Repository: pamela-project/slambench2 Branch: master Commit: 8a9deeaa5124 Files: 417 Total size: 27.2 MB Directory structure: gitextract_mua7h2yd/ ├── .clang-format ├── .dockerignore ├── .gitignore ├── .travis.yml ├── CMakeLists.txt ├── CONTRIBUTORS ├── LICENSE ├── Makefile ├── README.md ├── _config.yml ├── benchmarks/ │ └── CMakeLists.txt ├── cmake_modules/ │ ├── CUDACheckCompute.cmake │ ├── FindBrisk.cmake │ ├── FindCVD.cmake │ ├── FindCeres.cmake │ ├── FindEigen.cmake │ ├── FindEigen3.cmake │ ├── FindFreeImage.cmake │ ├── FindG2O.cmake │ ├── FindGVARS.cmake │ ├── FindGlog.cmake │ ├── FindLIBYAML.cmake │ ├── FindOpenCL.cmake │ ├── FindOpenNI.cmake │ ├── FindOpenNI2.cmake │ ├── FindPAPI.cmake │ ├── FindSLAMBENCH.cmake │ ├── FindSuiteSparse.cmake │ ├── FindTooN.cmake │ └── cuda_compute_capability.c ├── docker/ │ ├── Makefile │ ├── cuda-ubuntu-16.04.docker │ ├── fastCI.docker │ ├── fedora-24.docker │ ├── fedora-25.docker │ ├── fedora-26.docker │ ├── github.docker │ ├── run_cuda.sh │ ├── travis-deps.docker │ ├── ubuntu-14.04-bitbucket.docker │ ├── ubuntu-14.04-deps.docker │ ├── ubuntu-14.04.docker │ ├── ubuntu-16.04.docker │ └── ubuntu-16.10.docker ├── framework/ │ ├── CMakeLists.txt │ ├── makefiles/ │ │ ├── README.md │ │ ├── brisk.make │ │ ├── ceres.make │ │ ├── cvd.make │ │ ├── dataset-utils.makefile │ │ ├── deps.makefile │ │ ├── download_benchmarks.py │ │ ├── download_datasets.py │ │ ├── eigen3.make │ │ ├── flann.make │ │ ├── freeimage.make │ │ ├── g2o.make │ │ ├── gcc.make │ │ ├── gvars.make │ │ ├── libopencl-stub.make │ │ ├── opencv.make │ │ ├── opengv.make │ │ ├── openni.make │ │ ├── opentuner.make │ │ ├── pangolin.make │ │ ├── pcl.make │ │ ├── sophus.make │ │ ├── suitesparse.make │ │ └── toon.make │ ├── patchs/ │ │ ├── OpenNI2_SLAMBench.patch │ │ ├── OpenNI_SLAMBench.patch │ │ ├── SensorKinect_SLAMBench.patch │ │ ├── freeimage.patch │ │ └── libopencl-stub_SLAMBench.patch │ ├── shared/ │ │ ├── CMakeLists.txt │ │ ├── include/ │ │ │ ├── ColumnWriter.h │ │ │ ├── ParameterComponent.h │ │ │ ├── ParameterManager.h │ │ │ ├── Parameters.h │ │ │ ├── ResultWriter.h │ │ │ ├── SLAMBenchAPI.h │ │ │ ├── SLAMBenchConfiguration.h │ │ │ ├── SLAMBenchException.h │ │ │ ├── SLAMBenchLibraryHelper.h │ │ │ ├── SLAMBenchUI.h │ │ │ ├── SLAMBenchUI_Pangolin.h │ │ │ ├── TimeStamp.h │ │ │ ├── io/ │ │ │ │ ├── Event.h │ │ │ │ ├── FrameBuffer.h │ │ │ │ ├── FrameBufferSource.h │ │ │ │ ├── FrameFormat.h │ │ │ │ ├── FrameSource.h │ │ │ │ ├── InputInterface.h │ │ │ │ ├── InputInterfaceManager.h │ │ │ │ ├── PixelFormat.h │ │ │ │ ├── SLAMFile.h │ │ │ │ ├── SLAMFrame.h │ │ │ │ ├── SensorType.h │ │ │ │ ├── core/ │ │ │ │ │ └── Core.h │ │ │ │ ├── deserialisation/ │ │ │ │ │ ├── Deserialiser.h │ │ │ │ │ ├── SLAMFileDeserialiser.h │ │ │ │ │ ├── SLAMFileHeaderDeserialiser.h │ │ │ │ │ ├── SLAMFrameDeserialiser.h │ │ │ │ │ └── SensorCollectionDeserialiser.h │ │ │ │ ├── format/ │ │ │ │ │ ├── DataFormatter.h │ │ │ │ │ ├── EventDataFormatter.h │ │ │ │ │ ├── ImageDataFormatter.h │ │ │ │ │ └── PointCloud.h │ │ │ │ ├── openni15/ │ │ │ │ │ ├── ONI15Frame.h │ │ │ │ │ ├── ONI15FrameStream.h │ │ │ │ │ └── ONI15InputInterface.h │ │ │ │ ├── openni2/ │ │ │ │ │ ├── ONI2Frame.h │ │ │ │ │ ├── ONI2FrameStream.h │ │ │ │ │ └── ONI2InputInterface.h │ │ │ │ ├── realsense/ │ │ │ │ │ ├── RealSense2Frame.h │ │ │ │ │ ├── RealSense2FrameStream.h │ │ │ │ │ └── RealSense2InputInterface.h │ │ │ │ ├── sensor/ │ │ │ │ │ ├── AccelerometerSensor.h │ │ │ │ │ ├── CameraSensor.h │ │ │ │ │ ├── CameraSensorFinder.h │ │ │ │ │ ├── DepthSensor.h │ │ │ │ │ ├── EventCameraSensor.h │ │ │ │ │ ├── GroundTruthSensor.h │ │ │ │ │ ├── GyroSensor.h │ │ │ │ │ ├── IMUSensor.h │ │ │ │ │ ├── OdomSensor.h │ │ │ │ │ ├── PointCloudSensor.h │ │ │ │ │ ├── Sensor.h │ │ │ │ │ ├── SensorCollection.h │ │ │ │ │ ├── SensorDatabase.h │ │ │ │ │ └── sensor_builder.h │ │ │ │ └── serialisation/ │ │ │ │ ├── SLAMFileHeaderSerialiser.h │ │ │ │ ├── SLAMFileSerialiser.h │ │ │ │ ├── SLAMFrameSerialiser.h │ │ │ │ └── Serialiser.h │ │ │ ├── lodepng.h │ │ │ ├── math_types.h │ │ │ ├── metrics/ │ │ │ │ ├── ATEMetric.h │ │ │ │ ├── DepthEstimationMetric.h │ │ │ │ ├── DurationMetric.h │ │ │ │ ├── FrameData.h │ │ │ │ ├── MemoryMetric.h │ │ │ │ ├── Metric.h │ │ │ │ ├── MetricManager.h │ │ │ │ ├── MetricValue.h │ │ │ │ ├── Phase.h │ │ │ │ ├── PointCloudMetric.h │ │ │ │ ├── PowerMetric.h │ │ │ │ ├── RPEMetric.h │ │ │ │ ├── memory_utils/ │ │ │ │ │ └── CUDAMonitor.h │ │ │ │ └── power_utils/ │ │ │ │ ├── PAPIMonitor.h │ │ │ │ ├── PowerMonitor.h │ │ │ │ └── XU3Monitor.h │ │ │ ├── outputs/ │ │ │ │ ├── Output.h │ │ │ │ ├── OutputManager.h │ │ │ │ ├── OutputManagerWriter.h │ │ │ │ ├── PoseOutput.h │ │ │ │ ├── TrajectoryAlignmentMethod.h │ │ │ │ └── TrajectoryInterface.h │ │ │ ├── sb_malloc.h │ │ │ ├── sysutils.h │ │ │ ├── timings.h │ │ │ ├── utils.h │ │ │ └── values/ │ │ │ ├── Value.h │ │ │ ├── ValueDispatch.h │ │ │ ├── ValueInterface.h │ │ │ └── ValuePrinter.h │ │ └── src/ │ │ ├── ColumnWriter.cpp │ │ ├── ParameterComponent.cpp │ │ ├── ParameterManager.cpp │ │ ├── ResultWriter.cpp │ │ ├── SLAMBenchConfiguration.cpp │ │ ├── SLAMBenchUI_Pangolin.cpp │ │ ├── dummy_library.cpp │ │ ├── io/ │ │ │ ├── FrameBuffer.cpp │ │ │ ├── FrameBufferSource.cpp │ │ │ ├── FrameFormat.cpp │ │ │ ├── FrameSource.cpp │ │ │ ├── InputInterface.cpp │ │ │ ├── InputInterfaceManager.cpp │ │ │ ├── PixelFormat.cpp │ │ │ ├── SLAMFile.cpp │ │ │ ├── SLAMFrame.cpp │ │ │ ├── core/ │ │ │ │ └── Core.cpp │ │ │ ├── deserialisation/ │ │ │ │ ├── Deserialiser.cpp │ │ │ │ ├── SLAMFileDeserialiser.cpp │ │ │ │ ├── SLAMFileHeaderDeserialiser.cpp │ │ │ │ ├── SLAMFrameDeserialiser.cpp │ │ │ │ └── SensorCollectionDeserialiser.cpp │ │ │ ├── format/ │ │ │ │ ├── DataFormatter.cpp │ │ │ │ └── PointCloud.cpp │ │ │ ├── openni/ │ │ │ │ ├── ONI2Frame.cpp │ │ │ │ ├── ONI2FrameStream.cpp │ │ │ │ └── ONI2InputInterface.cpp │ │ │ ├── openni15/ │ │ │ │ ├── ONI15Frame.cpp │ │ │ │ ├── ONI15FrameStream.cpp │ │ │ │ └── ONI15InputInterface.cpp │ │ │ ├── realsense/ │ │ │ │ ├── RealSense2Frame.cpp │ │ │ │ ├── RealSense2FrameStream.cpp │ │ │ │ └── RealSense2InputInterface.cpp │ │ │ ├── sensor/ │ │ │ │ ├── AccelerometerSensor.cpp │ │ │ │ ├── CameraSensor.cpp │ │ │ │ ├── CameraSensorFinder.cpp │ │ │ │ ├── DepthSensor.cpp │ │ │ │ ├── EventCameraSensor.cpp │ │ │ │ ├── GroundTruthSensor.cpp │ │ │ │ ├── GyroSensor.cpp │ │ │ │ ├── IMUSensor.cpp │ │ │ │ ├── OdomSensor.cpp │ │ │ │ ├── PointCloudSensor.cpp │ │ │ │ ├── Sensor.cpp │ │ │ │ ├── SensorCollection.cpp │ │ │ │ └── SensorDatabase.cpp │ │ │ └── serialisation/ │ │ │ ├── SLAMFileHeaderSerialiser.cpp │ │ │ ├── SLAMFileSerialiser.cpp │ │ │ ├── SLAMFrameSerialiser.cpp │ │ │ └── Serialiser.cpp │ │ ├── library_wrapper.cpp │ │ ├── lodepng.cpp │ │ ├── metrics/ │ │ │ ├── ATEMetric.cpp │ │ │ ├── DepthEstimationMetric.cpp │ │ │ ├── DurationMetric.cpp │ │ │ ├── MemoryMetric.cpp │ │ │ ├── Metric.cpp │ │ │ ├── MetricManager.cpp │ │ │ ├── Phase.cpp │ │ │ ├── PointCloudMetric.cpp │ │ │ ├── PowerMetric.cpp │ │ │ ├── RPEMetric.cpp │ │ │ ├── memory_utils/ │ │ │ │ └── CUDAMonitor.cpp │ │ │ └── power_utils/ │ │ │ ├── PAPIMonitor.cpp │ │ │ └── XU3Monitor.cpp │ │ ├── outputs/ │ │ │ ├── Output.cpp │ │ │ ├── OutputManager.cpp │ │ │ ├── OutputManagerWriter.cpp │ │ │ ├── TrajectoryAlignmentMethod.cpp │ │ │ └── TrajectoryInterface.cpp │ │ ├── sb_malloc.cpp │ │ └── values/ │ │ ├── Value.cpp │ │ ├── ValueDispatch.cpp │ │ ├── ValueInterface.cpp │ │ └── ValuePrinter.cpp │ └── tools/ │ ├── CMakeLists.txt │ ├── README.md │ ├── accuracy-tools/ │ │ ├── CMakeLists.txt │ │ └── pointcloud_aligner.cpp │ ├── dataset-tools/ │ │ ├── BONN.cpp │ │ ├── CMakeLists.txt │ │ ├── ETHI.cpp │ │ ├── EUROCMAV.cpp │ │ ├── ICL.cpp │ │ ├── ICLNUIM.cpp │ │ ├── OpenLORIS.cpp │ │ ├── SVO.cpp │ │ ├── TUM-ROSBAG.cpp │ │ ├── TUM.cpp │ │ ├── UZHFPV.cpp │ │ ├── VolumeDeform.cpp │ │ ├── dataset-generator.cpp │ │ ├── include/ │ │ │ ├── BONN.h │ │ │ ├── DatasetReader.h │ │ │ ├── ETHI.h │ │ │ ├── EUROCMAV.h │ │ │ ├── ICL.h │ │ │ ├── ICLNUIM.h │ │ │ ├── OpenLORIS.h │ │ │ ├── SVO.h │ │ │ ├── TUM.h │ │ │ ├── UZHFPV.h │ │ │ ├── VolumeDeform.h │ │ │ └── utils/ │ │ │ ├── PlyASCIIReader.h │ │ │ ├── RegexPattern.h │ │ │ ├── dataset_utils.h │ │ │ └── tinyply.h │ │ ├── io-inspect.cpp │ │ ├── io-monoslam.cpp │ │ ├── io-readply.cpp │ │ ├── lodepng.cpp │ │ └── lodepng.h │ ├── loaders/ │ │ ├── CMakeLists.txt │ │ ├── benchmark_loader.cpp │ │ ├── pangolin_loader.cpp │ │ └── slambench_app.cpp │ └── profiling-tools/ │ ├── CMakeLists.txt │ └── OCLWrapper.cpp ├── icra2018_results/ │ ├── 1080/ │ │ ├── memory_efusion_living_room_traj2_loop.log │ │ ├── memory_infinitam_living_room_traj2_loop.log │ │ ├── memory_kfusion_living_room_traj2_loop.log │ │ ├── memory_lsdslam_living_room_traj2_loop.log │ │ ├── memory_orbslam2_living_room_traj2_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj0_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj1_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj2_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj3_loop.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libinfinitam-cpp_living_room_traj0_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj1_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj2_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj3_loop.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libinfinitam-cuda_living_room_traj0_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj1_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj2_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj3_loop.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libkfusion-cpp_living_room_traj0_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj1_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj2_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj3_loop.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libkfusion-cuda_living_room_traj0_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj1_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj2_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj3_loop.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_liblsdslam-cpp_living_room_traj0_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj1_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj2_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj3_loop.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_liborbslam2-original_living_room_traj0_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj1_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj2_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj3_loop.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log │ │ └── violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log │ ├── Makefile │ ├── paper_run.sh │ ├── plotutils.py │ ├── slamlog.py │ ├── tegra/ │ │ ├── memory_efusion_living_room_traj2_loop.log │ │ ├── memory_infinitam_living_room_traj2_loop.log │ │ ├── memory_kfusion_living_room_traj2_loop.log │ │ ├── memory_lsdslam_living_room_traj2_loop.log │ │ ├── memory_orbslam2_living_room_traj2_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj0_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj1_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj2_loop.log │ │ ├── violons_libefusion-cuda_living_room_traj3_loop.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libinfinitam-cpp_living_room_traj0_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj1_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj2_loop.log │ │ ├── violons_libinfinitam-cpp_living_room_traj3_loop.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libinfinitam-cuda_living_room_traj0_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj1_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj2_loop.log │ │ ├── violons_libinfinitam-cuda_living_room_traj3_loop.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libkfusion-cpp_living_room_traj0_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj1_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj2_loop.log │ │ ├── violons_libkfusion-cpp_living_room_traj3_loop.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_libkfusion-cuda_living_room_traj0_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj1_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj2_loop.log │ │ ├── violons_libkfusion-cuda_living_room_traj3_loop.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_liblsdslam-cpp_living_room_traj0_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj1_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj2_loop.log │ │ ├── violons_liblsdslam-cpp_living_room_traj3_loop.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log │ │ ├── violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log │ │ ├── violons_liborbslam2-original_living_room_traj0_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj1_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj2_loop.log │ │ ├── violons_liborbslam2-original_living_room_traj3_loop.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log │ │ ├── violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log │ │ └── violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log │ ├── utils.py │ └── violins.py └── scripts/ ├── evaluate.py └── tum_evaluate_tools/ ├── __init__.py ├── associate.py └── evaluate_ate.py ================================================ FILE CONTENTS ================================================ ================================================ FILE: .clang-format ================================================ --- BasedOnStyle: Google NamespaceIndentation: All ColumnLimit: 120 IndentWidth: 4 ... ================================================ FILE: .dockerignore ================================================ docker/ bitbucket-pipelines.yml ================================================ FILE: .gitignore ================================================ # Docker files /docker/tmp /docker/nvidia-driver.run docker/workspace/ framework/makefiles/benchmarks.makefile framework/makefiles/datasets.makefile # Build files /build/ /install/ /android-build/ # Eclipse and other IDE files .cproject .project .settings/ .idea .pydevproject *~ # Python *.pyc # Dependencies /deps /android-deps/ # Ignore benchmarks folders benchmarks/* !benchmarks/CMakeLists.txt # DSE Files /opentuner.db/ # Paper results paper/*.aux paper/*.pdf paper/*.tex # Datasets /datasets /iros2020_results_backup /iros2020_results !/datasets/README.md !/datasets/datasets.repos # macOS .DS_Store ================================================ FILE: .travis.yml ================================================ language: cpp dist: trusty sudo: required services: - docker script: - make -C docker github-docker-image ================================================ FILE: CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) project(slambench) # CMake variables ####################################################### MESSAGE(STATUS CMAKE_MODULE_PATH=${CMAKE_MODULE_PATH}) SET(EXECUTABLE_OUTPUT_PATH ${PROJECT_BINARY_DIR}/bin CACHE PATH "Build directory" FORCE) SET(LIBRARY_OUTPUT_PATH ${PROJECT_BINARY_DIR}/lib CACHE PATH "Build directory" FORCE) SET(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_BINARY_DIR}/bin) SET(CMAKE_BUILD_FILES_DIRECTORY ${PROJECT_BINARY_DIR}/bfd) SET(CMAKE_BINARY_DIR ${PROJECT_BINARY_DIR}/bindir) SET(CMAKE_CACHEFILE_DIR ${PROJECT_BINARY_DIR}/cache) SET(CMAKE_BUILD_DIRECTORY ${PROJECT_BINARY_DIR}/builddir) # Most common compiler flags ####################################################### set(GENERAL_COMPILATION_FLAGS "-g -O3 -Wall -Wextra") if(CMAKE_COMPILER_IS_GNUCC) add_definitions(-D_FILE_OFFSET_BITS=64) ## Workaround for 32 bit boards with fwrite 2G limit set(GENERAL_COMPILATION_FLAGS "${GENERAL_COMPILATION_FLAGS} -Wno-error=deprecated-declarations ") # Eigen raises deprecated declarations warnings and int-in-bool-context warnings. set(GENERAL_COMPILATION_FLAGS "${GENERAL_COMPILATION_FLAGS} -Wno-unknown-pragmas -Wno-error=deprecated-declarations -Wno-error=unused-result -Wno-error=reorder") if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 6.0) set(GENERAL_COMPILATION_FLAGS "${GENERAL_COMPILATION_FLAGS} -Wno-error=ignored-attributes -Wno-misleading-indentation") endif() if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 7.0) set(GENERAL_COMPILATION_FLAGS "${GENERAL_COMPILATION_FLAGS} -Wno-error=implicit-fallthrough= -Wno-int-in-bool-context ") endif() endif() if(APPLE) set(GENERAL_COMPILATION_FLAGS "${GENERAL_COMPILATION_FLAGS} -D__APPLE__") endif(APPLE) include(CheckCXXCompilerFlag) CHECK_CXX_COMPILER_FLAG("-std=c++2a" COMPILER_SUPPORTS_CXX20) CHECK_CXX_COMPILER_FLAG("-std=c++17" COMPILER_SUPPORTS_CXX17) CHECK_CXX_COMPILER_FLAG("-std=c++14" COMPILER_SUPPORTS_CXX14) CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) if(COMPILER_SUPPORTS_CXX20) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++2a") message(STATUS "Using flag -std=c++2a") elseif(COMPILER_SUPPORTS_CXX17) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17") message(STATUS "Using flag -std=c++17") elseif(COMPILER_SUPPORTS_CXX14) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14") message(STATUS "Using flag -std=c++14") elseif(COMPILER_SUPPORTS_CXX11) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") message(STATUS "Using flag -std=c++11") else() message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") endif() set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${GENERAL_COMPILATION_FLAGS}") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GENERAL_COMPILATION_FLAGS}") # DEFINE SLAMBENCH LIBS/INCLUDES ###################################################### find_package(Eigen3 REQUIRED) SET(SLAMBENCH_INCLUDE_DIR ${EIGEN3_INCLUDE_DIR} ${CMAKE_SOURCE_DIR}/framework/shared/include CACHE STRING "The include paths needed to use SLAMBENCH") SET(SLAMBENCH_LIBRARIES slambench-utils -Wl,--whole-archive slambench-io slambench-metrics -Wl,--no-whole-archive) SET(SLAMBENCH_C_WRAPPER -Wl,--whole-archive slambench-c-wrapper -Wl,--no-whole-archive) # SLAMBENCH FUNCTIONS ####################################################### if(NOT WIN32) string(ASCII 27 Esc) set(ColorReset "${Esc}[m") set(Red "${Esc}[31m") set(Green "${Esc}[32m") endif() SET(NULL_FILE_PATH ${PROJECT_BINARY_DIR}/null.cpp) if (NOT EXISTS ${NULL_FILE_PATH}) file(WRITE ${NULL_FILE_PATH} "") ENDIF() function(explore_implementations algorithm_name implementations_path) set(appname ${algorithm_name}) FILE(GLOB VERSIONS ${implementations_path}) FOREACH(version_dir ${VERSIONS}) IF(IS_DIRECTORY ${version_dir}) get_filename_component(appversion ${version_dir} NAME) MESSAGE(STATUS "Load version ${appversion} of ${appname}.") ADD_SUBDIRECTORY(${version_dir}) ENDIF() ENDFOREACH(version_dir) endfunction() function(generate_slam_binaries_only library_name ) message(STATUS "Potential interfaces are ${SLAMBENCH_INTERFACES}...") FOREACH(INTERFACE ${SLAMBENCH_INTERFACES}) message(STATUS "${Green}Generation of ${library_name}-${INTERFACE} : Activated${ColorReset}") add_executable(${library_name}-${INTERFACE} ${NULL_FILE_PATH}) target_link_libraries(${library_name}-${INTERFACE} PRIVATE ${library_name} ${INTERFACE} ${library_name}) SET_TARGET_PROPERTIES(${library_name}-${INTERFACE} PROPERTIES LINK_FLAGS "${ARGN}") install(TARGETS ${library_name}-${INTERFACE} DESTINATION bin/) ENDFOREACH() endfunction() function(generate_slam_library library_name ) message(STATUS "Potential interfaces are ${SLAMBENCH_INTERFACES}...") FOREACH(INTERFACE ${SLAMBENCH_INTERFACES}) message(STATUS "${Green}Generation of ${library_name}-${INTERFACE} : Activated${ColorReset}") add_executable(${library_name}-${INTERFACE} ${NULL_FILE_PATH}) target_link_libraries(${library_name}-${INTERFACE} PRIVATE ${library_name} ${INTERFACE} ${library_name}) SET_TARGET_PROPERTIES(${library_name}-${INTERFACE} PROPERTIES LINK_FLAGS "${ARGN}") install(TARGETS ${library_name}-${INTERFACE} DESTINATION bin/) ENDFOREACH() message(STATUS "${Green}Generation of ${library_name}-library : Activated${ColorReset}") add_library(${library_name}-library SHARED ${NULL_FILE_PATH}) target_link_libraries(${library_name}-library PRIVATE ${SLAMBENCH_C_WRAPPER} ${library_name}) SET_TARGET_PROPERTIES(${library_name}-library PROPERTIES LINK_FLAGS "${ARGN}") install(TARGETS ${library_name}-library DESTINATION lib/) endfunction() #### SUB FOLDERS #### add_subdirectory(framework) # SLAMBench framework add_subdirectory(benchmarks) # Benchmarks ================================================ FILE: CONTRIBUTORS ================================================ - Bodin Bruno - Mawer John - Melot Nicolas - Moldovan Adrian - Nardi Luigi - Nisbet Andy - Saeedi Sajad - Vespa Emanuele - Wagstaff Harry - Zia M Zeeshan ================================================ FILE: LICENSE ================================================ The MIT License (MIT) Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 Authors are (in alphabetical order): - Bodin Bruno - Mawer John - Melot Nicolas - Moldovan Adrian - Nardi Luigi - Nisbet Andy - Saeedi Sajad - Vespa Emanuele - Wagstaff Harry - Zia M Zeeshan Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions: The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software. THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. The MIT license is limited to the ***PAMELA*** software. The libraries used that are not under the same license are: - Eigen3 (LGPLv3) - Pangolin (MIT) - OpenNI (Apache License 2.0) - PCL (3-clauses BSD) - PAPI (BSD) - Boost (Boost Software Licence) - libyaml (MIT) - LodePNG (zlib License) The SLAM algorithms that are using SLAMbench and that can be downloaded in the "benchmark" folder have the following licences: - OKVIS (BSD 3-Clause) - KFusion: (MIT License) - LSDSLAM (GPLv3) - orbslam2 (GPLv3) - PTAM (GPLv3) - SVO (GPLv3) - monoslam (Custom permissive licence) - ElasticFusion (Elastic Fusion license) - InfiniTAM (Oxford/Isis licence) Several of those SLAM systems include third-party libraries: - Sophus (MIT) - vikit_common (no licence file found) The additionnal dependencies used by those algorithms are that can be downloaded in the "deps" folder have the following licences: - OpenCV (BSD) - G2O (BSD) - BRISK (BSD) - CVD (two-clause BSD) - Flann (BSD) - gvars (BSD) - opengv (BSD) - TooN (2-clause BSD) - suitesparse (3-clause BSD) ================================================ FILE: Makefile ================================================ ECHO=/bin/echo #SHELL := /bin/bash WGET:=wget GET_REPLY:=read REPLY ifeq ("${SBQUIET}","1") GET_REPLY:=REPLY="y" WGET:=wget -q endif BoldGreen=\033[1;32m BoldRed=\033[1;31m ColorOff=\033[0m #### SLAMBENCH INFOS #### infos: @${ECHO} -e "\n*** SLAMBench is an evaluation framework for SLAM algorithms. *** " @${ECHO} -e "\n\ (1) First, several dependencies are needed to compile SLAMBench and its use-cases.\n\ We suggest that you to download and install them automatically using the following command:\n\ ${BoldGreen} - make deps ${ColorOff}\n\ (2) Then, to compile the SLAMBench framework you just need to type:\n\ ${BoldGreen} - make slambench ${ColorOff}\n\ (3) SLAMBench integrates a number of algorithms, however they are not directly distribute with the framework\n\ To download and build all the available algorithms, use:\n\ ${BoldGreen} - make algorithms${ColorOff}\n\ Alternatively, to see the list of available algorithms, use:\n\ ${BoldGreen} - make usecases ${ColorOff}\n\ (4) For information about downloading and building one of the available datasets, use:\n\ ${BoldGreen} - make datasetslist ${ColorOff}\n\ (5) Once the desired datasets and algorithms were built, you can run the benchmark using:\n\ ${BoldGreen} - ./build/bin/slambench -i path/to/dataset.slam -load path/to/algorithm-library.so ${ColorOff}\n\ " #### Dependencies #### include ./framework/makefiles/deps.makefile #### Compilation targets #### build/Makefile : framework/CMakeLists.txt mkdir -p build/ ${DEPS_ENV} cmake -U * -Bbuild -H. -DAPPS="${APPS}" ${DEPS_ARGS} -D"CMAKE_MODULE_PATH:PATH=${ROOT_DIR}/cmake_modules" .. slambench: build/Makefile $(MAKE) -C build $(MFLAGS) @echo "" @echo "=================================================================================================================" @echo "The SLAMBench library should have been compiled, you will find binaries in build/bin, and libraries in build/lib." @echo "" @echo "Tools/Debugger available: " @echo -n " - build/bin/slambench: " ; if [ -f build/bin/slambench ] ; then echo -e "${BoldGreen}Found${ColorOff}" ; else echo -e "${BoldRed}Not found (Missing dependencies?)${ColorOff}" ; fi @echo -n " - build/bin/pointcloud_aligner: " ; if [ -f build/bin/pointcloud_aligner ] ; then echo -e "${BoldGreen}Found${ColorOff}" ; else echo -e "${BoldRed}Not found (Missing dependencies (i.e. pcl)?)${ColorOff}" ; fi @echo -n " - build/bin/dataset-generator: " ; if [ -f build/bin/dataset-generator ] ; then echo -e "${BoldGreen}Found${ColorOff}" ; else echo -e "${BoldRed}Not found (Missing dependencies?)${ColorOff}" ; fi @echo -n " - build/bin/io-inspect-file: " ; if [ -f build/bin/io-inspect-file ] ; then echo -e "${BoldGreen}Found${ColorOff}" ; else echo -e "${BoldRed}Not found (Missing dependencies?)${ColorOff}" ; fi @echo -n " - build/bin/io-readply: " ; if [ -f build/bin/io-readply ] ; then echo -e "${BoldGreen}Found${ColorOff}" ; else echo -e "${BoldRed}Not found (Missing dependencies?)${ColorOff}" ; fi @echo "" @echo "The list of current algorithms available is:" @echo "" @for f in `ls build/lib/lib*-library.so 2> /dev/null || echo Nothing` ; do echo $$f ; done @echo "" @echo "The list of current filters available is:" @echo "" @for f in `ls build/lib/lib*-filter.so 2> /dev/null || echo Nothing` ; do echo $$f ; done @echo "" @echo "As a next step we suggest you to run \"make usecases\" or \"make slambench APPS=all\"." .PHONY: build/Makefile #### Benchmarks #### framework/makefiles/benchmarks.makefile : framework/makefiles/download_benchmarks.py benchmarks/benchmarks.json python $^ > $@ include framework/makefiles/benchmarks.makefile #### Datasets #### framework/makefiles/datasets.makefile : framework/makefiles/download_datasets.py datasets/datasets.repos python $^ > $@ include framework/makefiles/dataset-utils.makefile include framework/makefiles/datasets.makefile .PHONY: slambench benchmarks datasets #### ORBSLAM Voc #### ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt : ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt.tar.gz cd ./benchmarks/orbslam2/src/original/Vocabulary/ && tar -xf ORBvoc.txt.tar.gz #### CLEAN TOOLS #### clean : rm -rf build install android-build android-install docker/tmp/ cleandatasets : find datasets/ | grep [.]slam | xargs rm 2> /dev/null || true @echo "Datasets cleaned" cleandeps : rm -rf deps cleanall : clean cleandatasets cleandeps .PHONY: clean cleandeps cleandatasets cleanall #### DEMO PART #### demo-prepare : make slambench APPS=all make datasets/ICL_NUIM/living_room_traj2_loop.slam make datasets/EuRoCMAV/machine_hall/MH_01_easy/MH_01_easy.slam make datasets/TUM/freiburg2/rgbd_dataset_freiburg2_desk.slam demo-droneflight : $(MAKE) open_vins $(MFLAGS) $(MAKE) slambench APPS=open_vins $(MFLAGS) $(MAKE) datasets/UZHFPV/indoor_forward_3_snapdragon_with_gt.slam $(MFLAGS) @echo "You can now run ${BoldGreen}./build/bin/slambench -i datasets/UZHFPV/indoor_forward_3_snapdragon_with_gt.slam -load build/lib/libopen_vins-original-library.so${ColorOff}" demo-lib : clear @${ECHO} -e " " @${ECHO} -e " =======================" @${ECHO} -e " Pick gui and whether to use lifelong SLAM mode: " @${ECHO} -e " ./build/bin/slambench -gui -lifelong " @${ECHO} -e " =======================" @${ECHO} -e " Pick dataset " @${ECHO} -e " " @for d in `find datasets/ | grep [.]slam` ; do ${ECHO} " -i $$d" ; done @${ECHO} -e " " @${ECHO} -e " =======================" @${ECHO} -e " Pick libraries " @${ECHO} -e " * may requires parameters" @${ECHO} -e " * do not need to be open source" @${ECHO} -e " =======================" @${ECHO} -e " " @for d in `find build/lib/| grep [-]library[.]so` ; do ${ECHO} " -load $$d" ; done @${ECHO} -e " " @${ECHO} -e " " @${ECHO} -e " =======================" .PHONY: demo-droneflight demo-lib demo-prepare #### TESTS #### regression_test : make -C docker fastCI-docker-image # First test compilation of slambench and run kfusion make -C docker ubuntu-14.04-docker-image # Second compilation for embedded systems such as Odroid or TK1 # third run slambench for multiple datasets and check ATE and Memory usage test : make -C docker fastCI-docker-image ================================================ FILE: README.md ================================================ # SLAMBench [![Build Status](https://travis-ci.org/pamela-project/slambench2.svg?branch=master)](https://travis-ci.org/pamela-project/slambench2) Code has been added for the most recent paper based on SLAMBench: [Robust SLAM Systems: Are We There Yet?](https://arxiv.org/abs/2109.13160) \ https://robustslam.github.io/evaluation ## Contents * [What is SLAMBench?](#what-is-slambench) * [How to set up SLAMBench?](#how-to-set-up-slambench) * [What algorithms does SLAMBench support?](#what-algorithms-does-slambench-support) * [How to run an existing algorithm with SLAMBench?](#how-to-run-an-existing-algorithm-with-slambench) * [How to add a new benchmark in SLAMBench?](#how-to-add-a-new-benchmark-in-slambench) * [Known Issues](#known-issues) * [Release History](#release-history) ## Most frequent questions ## ### Where are the algorithms ? ### Use the following command to list all available algorithms: ``` make usecases ``` ## What is SLAMBench? ## SLAMBench is a SLAM performance benchmark that combines a framework for quantifying quality-of-result with instrumentation of accuracy, execution time, memory usage and energy consumption. It also include a graphical interface to visualize these information. SLAMBench offers a platform for a broad spectrum of future research in jointly exploring the design space of algorithmic and implementation-level optimisations. It targets desktop, laptop, mobile and embedded platforms. Some of the benchmarks (in particular KFusion) were tested on Ubuntu, OS X and Android (more information about android here [https://github.com/bbodin/slambench-android](https://github.com/bbodin/slambench-android)). SLAMBench currently supports the following algorithms: * ORB-SLAM3 [Campos et al, ARXIV'20]: C++ as distributed by https://github.com/UZ-SLAMLab * ReFusion [Palazollo et al. IROS'19]: CUDA as distributed by https://github.com/PRBonn * OpenVINS [Geneva et al. IROS'19]: C++ as distributed by https://github.com/rpng/ * Supereight [Vespa et al. RA-L'18]: C++, OpenMP as distributed by https://github.com/emanuelev * BundleFusion [Dai et al. ACM TOG'17]: CUDA as distributed by https://github.com/niessner * SemanticFusion [McCormac et al. ICRA'17]: CUDA as distributed by https://github.com/seaun163 * ORB-SLAM2 [Mur-Artal et al, TOR'15 and TOR'17]: C++ as distributed by https://github.com/raulmur * DSO [Engel et al. Arxiv'16]: C++ as distributed by https://github.com/JakobEngel * ElasticFusion [Whelan et al, IJRR'16]: CUDA as distributed by https://github.com/mp3guy * InfiniTAMv2 [Kahler et al, ISMAR'15]: C++, OpenMP and CUDA versions as distributed by https://github.com/victorprad/ * KinectFusion [Newcombe et al. ISMAR'11]: C++, OpenMP, OpenCL and CUDA inspired by https://github.com/GerhardR * LSDSLAM [Engel et al, ECCV'14]: C++, and threaded as distributed by https://github.com/tum-vision/ and modified by https://github.com/mp3guy * MonoSLAM [Davison et al, TPAMI'07]: Original version as distributed by https://github.com/hanmekim/ * OKVIS [Leutenegger et al, IJRR'15]: Original version as distributed by https://github.com/ethz-asl * PTAM [Klein et al, ISMAR'07 and ECCV'08]: Original version as distributed by https://github.com/Oxford-PTAM/ * SVO [Forster et al, ICRA'14]: Original version as distributed by https://github.com/uzh-rpg/rpg_svo/ (a more recent version available at http://rpg.ifi.uzh.ch/svo2.html) **IMPORTANT: If you use any of those algorithms in scientific publications, you should refer to the respective publications.** In addition, if you use SLAMBench in scientific publications, we would appreciate citations to the following papers: ``` @inproceedings{bujanca2021robust, author={Bujanca, Mihai and Shi, Xuesong and Spear, Matthew and Zhao, Pengpeng and Lennox, Barry and Luj{\'a}n, Mikel}, booktitle={2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)}, title={Robust SLAM Systems: Are We There Yet?}, year={2021}, doi={10.1109/IROS51168.2021.9636814} } @inproceedings{bujanca2019slambench, title={SLAMBench 3.0: Systematic automated reproducible evaluation of SLAM systems for robot vision challenges and scene understanding}, author={Bujanca, Mihai and Gafton, Paul and Saeedi, Sajad and Nisbet, Andy and Bodin, Bruno and O'Boyle, Michael FP and Davison, {Andrew J} and Kelly, {Paul H.J.} and Riley, Graham and Lennox, Barry and Luj{\'a}n, Mikel and Furber, Steven}, booktitle={2019 International Conference on Robotics and Automation (ICRA)}, pages={6351--6358}, year={2019}, organization={IEEE} } @inproceedings{Bodin2018, author = "Bruno Bodin and Harry Wagstaff and Sajad Saeedi and Luigi Nardi and Emanuele Vespa and Mayer, {John H} and Andy Nisbet and Mikel Luj{\'a}n and Steve Furber and Davison, {Andrew J} and Kelly, {Paul H.J.} and Michael O'Boyle", title = "SLAMBench2: Multi-Objective Head-to-Head Benchmarking for Visual SLAM", booktitle = "{IEEE Intl. Conf. on Robotics and Automation (ICRA)}", year = {2018}, month = {May} } @inproceedings{Nardi2015, title={Introducing SLAMBench, a performance and accuracy benchmarking methodology for SLAM}, author={Nardi, Luigi and Bodin, Bruno and Zia, M Zeeshan and Mawer, John and Nisbet, Andy and Kelly, Paul HJ and Davison, Andrew J and Luj{\'a}n, Mikel and O'Boyle, Michael FP and Riley, Graham and others}, booktitle={2015 IEEE international conference on robotics and automation (ICRA)}, pages={5783--5790}, year={2015}, organization={IEEE} } ``` ## How to set up SLAMBench? As SLAMBench deals with multiple SLAM algorithms, dependencies might be difficult to install on any systems. To ease the usage of SLAMBench we provide auto-installation of dependencies and recommend the use fresh installation of Ubuntu 18/20 or Fedora 24-29. ### Dependency installation #### Required by SLAMBench framework * CMake 2.8.11 or higher is required. * Make * GCC C/C++ * Boost (Optional) * GLUT (Optional) #### Required by benchmarks and datasets * Git * Mercurial * wget * unzip * lapack * blas * findutils * cvs * glog * gflags * p7zip #### To install them With Fedora 29: `dnf install -y yaml-cpp-devel gtk2-devel mesa-libEGL-devel vtk-devel cmake make git mercurial wget unzip gcc gcc-c++ lapack blas lapack-devel blas-devel findutils cvs glut-devel glew-devel boost-devel glog-devel gflags-devel libXmu-devel p7zip` With Fedora 24: ```dnf install -y gtk2-devel vtk-devel cmake make git mercurial wget unzip gcc gcc-c++ lapack blas lapack-devel blas-devel findutils cvs glut-devel glew-devel boost-devel glog-devel gflags-devel libXmu-devel``` With Ubuntu 20.04: ``` apt-get -y install libvtk6.3 libvtk6-dev unzip libflann-dev wget mercurial git gcc g++ cmake python-numpy freeglut3 freeglut3-dev libglew-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev libyaml-dev build-essential libyaml-cpp-dev ``` With Ubuntu 18.04: ``` apt-get -y install libvtk6.3 libvtk6-dev unzip libflann-dev wget mercurial git gcc g++ cmake python-numpy freeglut3 freeglut3-dev libglew-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev libyaml-dev build-essential libyaml-cpp-dev ``` #### Special requirements for CUDA To run the CUDA implementation of some of the algorithms, you will need extra dependencies. With Ubuntu: `apt-get -y install nvidia-cuda-toolkit clinfo` With Fedora: `yum install cuda` ### Compilation of SLAMBench and its benchmarks #### 1. Dependencies Install dependencies first [NOTE can be installed by the user on its system as well]: ```bash make deps ``` The idea is to maximise the chance of a good build, by selection the best cocktail of libraries. This will download and compile the following applications: Brisk, Ceres, CVD, Eigen3, Flann, FreeImage, G2O, Gvars, OpenCV, OpenGV, OpenTuner, Pangolin, PCL, Suitesparse, TooN. You can also install each ofthese individually, using the commands such as: `eigen3`, `flann`, `g2o`, `opencv`, `opengv`, `pcl`, `toon`, `suitesparse`, ... more information is available in the `framework/makefiles/README.md` file. #### 2. SLAMBench Framework SLAMBench is a framework that can be compiled by simply running: ```bash make slambench ``` Although, by doing this, you only compile the libraries of SLAMBench. #### 3. Usecases To download use-cases, there are specific target named after the type of algorithm you need to test: ```bash make kfusion lsdslam ``` Then to compile these specific use-case, you will need to specify identifiers together with the slambench target: ```bash make slambench APPS=kfusion,lsdslam ``` The current benchmarks identifiers are efusion, infinitam, kfusion, lsdslam, monoslam, okvis, ptam, orbslam2, svo. You will find more information to download and compile use-cases with the `make usecases` command. #### 4. Datasets To test a SLAM algorithm you can use a Live camera, or a dataset. SLAMBench provides tools to automatically download some of the most popular datasets, that is ICL-NUIM and TUM RGB-D. The file format (*.slam) will then include all the most important information about the dataset, those are **Camera calibration setting**, **initial position of the sensors**, and the **ground truth**. As an example to download and generate the Living Room Trajectory 2 from the ICLNUIM dataset, you can run the following : ```bash > make datasets/ICL_NUIM/living_room_traj2_loop.slam ``` SLAMBench currently supports the following datasets: * OpenLORIS [Shi et al, ICRA'20]: Lifelong SLAM dataset * Bonn Dynamic [Palazollo et al. IROS'19]: Dynamic scene dataset * UZH-FPV [Delmerico et al. ICRA'19]: Drone racing dataset * ETH Illumination [Park et al, ICRA'17]: Illumination changes dataset * VolumeDeform [Innmann et al, ECCV'16]: Non-rigid reconstruction * EuRoC MAV [Burri et al, IJRR'16]: Micro Aerial Vehicle dataset * ICL-NUIM [Handa et al, ICRA'14]: Synthetic dataset * TUM RGB-D [Sturm et al, IROS'12]: A standard SLAM benchmark A complete list of the datasets available is provided by the command `make datasets`. ## What algorithms does SLAMBench support? SLAMBench is already compatible with a wide range of algorithms which are not included in this repository (see [above](#what-is-slambench) for list of algorithms). However you can easily integrate those algorithms using the command: ```bash make usecases ``` This command will explain in details how to integrate algorithms that are already compatible with SLAMBench. ## How to run an existing algorithm with SLAMBench? Once you have compiled a benchmark, there are several ways to run it. For each implementation of this benchmark, you will find a specific library. As an example, with KinectFusion, after running `make slambench APPS=kfusion`, you may find the following libraries in the `build/lib` directory : ```bash > ls build/lib/libkfusion-*-library.so build/lib/libkfusion-cpp-library.so build/lib/libkfusion-notoon-library.so build/lib/libkfusion-openmp-library.so build/lib/libkfusion-cuda-library.so build/lib/libkfusion-opencl-library.so ``` We can see five different implementations (cpp, notoon, and openmp, cuda and opencl). The list of available binaries depends of the dependencies you installed beforehand. For example, you need CUDA to compile the kfusion-cuda. A complete list of the dependencies is available at the end of this README. ### Running a benchmark (e.g. KinectFusion) To run one algorithm you will need to use a **loader**. There are three different loaders supported, **benchmark**, **pangolin**, and **lifelong**. The first two loaders are used the same way, except that **benchmark** is a command line application dedicated to measurements, while **pangolin** is a graphical user interface less precise in term of measurement but which provide a good interface for demonstrations. The **lifelong** loader can take multiple input (multiple .slam files following the -i option, separated by ',') which will be sent to the benchmark one by one. Other than that it is similar to the **benchmark** loader. There is currently no loader both supporting loading multiple input and having a graphical user interface. Each loader has a series of parameters to specify such as the dataset location, or the libraries to run. The list of those parameters is available by using the "--help" parameters. ```bash > ./build/bin/benchmark_loader --help == SLAMBench Configuration == Available parameters : -fl --frame-limit : last frame to compute (Default=0) -o --log-file : Output log file (Default=) -i --input : Specify the input file or mode. (Default=) -load --load-library : Load a specific SLAM library. (Default=) -dse --dse : Output solution space of parameters. (Default=false) -h --help : Print the help. (Default=false) -nf --negative-focal-length : negative focal length (Default=false) -realtime --realtime-mode : realtime frame loading mode (Default=false) -realtime-mult --realtime-multiplier : realtime frame loading mode (Default=1) -fo --file-output : File to write slamfile containing outputs (Default=) ``` Then if you run the loader again, while providing a dataset file `-i dataset.slam`, you will see new parameters dedicated to the dataset: ```bash > ./build/bin/benchmark_loader -i datasets/ICL_NUIM/living_room_traj2_loop.slam --help == SLAMBench Configuration == Available parameters : .... -Camera-intrisics --Camera-intrisics : (Default=nullptr Current=0.751875,1,0.4992185,0.4989583) -Depth-intrisics --Depth-intrisics : (Default=nullptr Current=0.751875,1,0.4992185,0.4989583) -Depth-dip --Depth-disparity-params : (Default=nullptr Current=0.001,0) -Camera-intrisics --Camera-intrisics : (Default=nullptr Current=0.751875,1,0.4992185,0.4989583) ``` Finally is you add a library name `-load libname`, more parameter can be seen: ```bash > ./build/bin/benchmark_loader -i datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so --help == SLAMBench Configuration == Available parameters : .... -c --compute-size-ratio : Compute ratio (Default=1) -r --integration-rate : integration-rate (Default=2) -t --tracking-rate : tracking-rate (Default=1) -z --rendering-rate : rendering-rate (Default=4) -l --icp-threshold : icp-threshold (Default=1e-05) -m --mu : mu (Default=0.1) -s --volume-size : volume-size (Default=8,8,8) -d --volume-direction : volume-direction (Default=4,4,4) -v --volume-resolution : volume-resolution (Default=256,256,256) -y1 --pyramid-level1 : pyramid-level1 (Default=10) -y2 --pyramid-level2 : pyramid-level2 (Default=5) -y3 --pyramid-level3 : pyramid-level3 (Default=4) ``` You can run a loader with **only one dataset** at a time and **it must be specified first**. In the next section we will explain how to use SLAMBench to evaluate the performance of a SLAM algorithm. ### Evaluating a benchmark (eg. KinectFusion) SLAMBench works with Metrics and Outputs elements. When you run the ```benchmark_loader``` or the ```pangolin_loader``` or the ```lifelong_loader``` these are those elements that you can visualize. Metrics are components generated by SLAMBench framework really, while Outputs are generated by the algorithm or may be elements post-processed by SLAMBench (such as the aligned trajectory with the ground truth). Let us run the benchmark loader. Its output is composed of two main parts, the `Properties` section, and the `Statistics` section. the properties section details all the parameters used for the experiment (could been changed or not via the command line). the statistics section report all the outputs and metrics selection for output in the benchmark loader. ```bash > ./build/bin/benchmark_loader -i datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so SLAMBench Report run started: 2018-02-02 04:41:31 Properties: ================= frame-limit: 0 log-file: input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: ./build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Camera-intrisics: 0.751875,1,0.4992185,0.4989583 Depth-intrisics: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Camera-intrisics: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp Duration_Frame GPU_Memory CPU_Memory Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render X Y ZATE_Frame 1 0.0000000000 0.7679200000 0 623801799 0.1254800000 0.0195420000 0.0561620000 0.0000030000 0.5667170000 4.0000000000 4.0000000000 4.0000000000 0.0000002980 2 1.0000000000 0.2003970000 0 623801799 0.1242030000 0.0156470000 0.0581670000 0.0000000000 0.0023710000 4.0000000000 4.0000000000 4.0000000000 0.0010031639 3 2.0000000000 0.1989980000 0 623801799 0.1233680000 0.0152360000 0.0580180000 0.0000000000 0.0023690000 4.0000000000 4.0000000000 4.0000000000 0.0055015362 4 3.0000000000 0.7518580000 0 623801799 0.1220660000 0.0152080000 0.0563070000 0.5559520000 0.0023170000 4.0000000000 4.0000000000 4.0000000000 0.0036504765 5 4.0000000000 1.3683420000 0 623801799 0.1240890000 0.0767240000 0.0581630000 0.5504240000 0.5589330000 3.9957129955 4.0020360947 4.0009112358 0.0021276891 ... ``` ## How to add a new benchmark in SLAMBench? The main reason to provide a new version of SLAMBench is not only because of the introduction of new benchmarks but also because we provide now a clear and specific API for SLAM algorithms to be implemented in order to add a new algorithm. ``` bool sb_new_slam_configuration(SLAMBenchLibraryHelper * slam_settings); bool sb_init_slam_system(SLAMBenchLibraryHelper * slam_settings); bool sb_update_frame(SLAMBenchLibraryHelper * slam_settings, slambench::io::SLAMFrame * type); bool sb_process_once(SLAMBenchLibraryHelper * slam_settings); bool sb_relocalize(SLAMBenchLibraryHelper * slam_settings); bool sb_update_outputs(SLAMBenchLibraryHelper *lib, const slambench::TimeStamp *latest_output); bool sb_clean_slam_system(); bool sb_update_outputs(SLAMBenchUI *); ``` **If each of those functions are correctly implemented for a specific implementation of a specific algorithm, then this algorithm is compatible with SLAMBench and can be evaluated as well.** In this section we will present those functions one by one. ### bool sb\_new\_slam\_configuration(SLAMBenchLibraryHelper * slam\_settings) This function is called first, and only once, SLAM systems is expected to provide its parameters. Example : ```cpp bool sb_new_slam_configuration(SLAMBenchLibraryHelper * slam_settings) { slam_settings->addParameter(TypedParameter("c", "confidence", "Confidence", &confidence, &default_confidence)); slam_settings->addParameter(TypedParameter("d", "depth", "Depth", &depth, &default_depth)); slam_settings->addParameter(TypedParameter ("td", "textureDim", "textureDim", &textureDim, &default_textureDim)); return true; } ``` should always return `true` or an exception will be raised. ### bool sb\_init\_slam\_system(SLAMBenchLibraryHelper * slam\_settings) This function is called second, and only once, SLAM systems is expected to allocate memory, retrieve sensor informations. To retrieve sensor there is `SensorFinder`: ```cpp slambench::io::CameraSensorFinder sensor_finder; auto rgb_sensor = sensor_finder.FindOne(slam_settings->get_sensors(), {{"camera_type", "rgb"}}); ``` SLAM systems are also expected to define there output, there is one mandatory output, the pose: ```cpp pose_output = new slambench::outputs::Output("Pose", slambench::values::VT_POSE, true); slam_settings->GetOutputManager().RegisterOutput(pose_output); ``` should always return `true` or an exception will be raised. ### bool sb_update_frame (SLAMBenchLibraryHelper *slam_settings, slambench::io::SLAMFrame *frame) Algorithms receive frames ordered by timestamp. When `sb_update_frame` returns `false`, `sb_update_frame` will be directly called again with the next frame, if it returns `true`, `sb_process_once` will be called once. ### bool sb_process_once (SLAMBenchLibraryHelper *slam_settings) Should always return `true` or an exception will be raised. ### bool sb_relocalize (SLAMBenchLibraryHelper *slam_settings) This is newly introduced to support lifelong SLAM evaluation. It will be called when the input sequence has been switched to the next one. The implementation is expected to explicitly trigger tracking lost and invoke the algorithm's re-localization procedure (if there be). It should return whether the relocalization is sucessful from the algorithm's perspective. For backward compatibility, this function is allowed to be unimplemented in a benchmark. In such cases, the ```sb_process_once``` function will be called in a re-localization situation. ### bool sb_clean_slam_system() This function is called last, and only once, SLAM systems is expected to clean everything (free memory). ```cpp bool sb_clean_slam_system() { delete eFusion; delete inputRGB; delete inputDepth; return true; } ``` should always return `true` or an exception will be raised. ### bool sb_update_outputs(SLAMBenchLibraryHelper *slam_settings, const slambench::TimeStamp *timestamp) The algorithm will return visible outputs (Pose, Point cloud, Frames) as defined by the `sb_init_slam_system` function. Example : ```cpp bool sb_update_outputs(SLAMBenchLibraryHelper *lib, const slambench::TimeStamp *ts_p) { slambench::TimeStamp ts = *ts_p; if(pose_output->IsActive()) { // Get the current pose as an eigen matrix Eigen::Matrix4f mat = eFusion->getCurrPose(); std::lock_guard lock (lib->GetOutputManager().GetLock()); pose_output->AddPoint(ts, new slambench::values::PoseValue(mat)); } ``` should always return `true` or an exception will be raised. ## Known Issues ### KFusion CUDA version KFusion CUDA requires GCC 4.9 to work. To specify a new gcc compiler for CUDA only, you can use the `CUDA_HOST_COMPILER` flag as follows : ```bash make slambench APPS=kfusion CUDA_HOST_COMPILER=$(which gcc-4.9) ``` Modern O.S. are now using more recent version of this compiler, this may introduce several compatibility issues. To fix one of them, in the compilation process, when compiling CUDA application we use the ` -D_GLIBCXX_USE_CXX11_ABI=0 ` flag. ## Release History Version 4.0 (Oct 2021) - Robustness evaluation Version 3.0 (May 2019) - Depth estimation - Dynamic reconstruction - Semantic reconstruction Version 2.0 (Feb 2018) * This release is a complete new version Release candidate 1.1 (17 Mar 2015) * Bugfix : Move bilateralFilterKernel from preprocessing to tracking * Bugfix : Wrong interpretation of ICP Threshold parameter. * Esthetic : Uniformisation of HalfSampleRobustImage kernel * Performance : Change float3 to float4 for the rendering kernels (No effect on OpenCL, but high performance improvement with CUDA) * Performance : Add a dedicated buffer for the OpenCL rendering * Feature : Add OSX support Release candidate 1.0 (12 Nov 2014) * First public release Copyright (c) 2014-2021 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 and The RAIN Hub, funded by the Industrial Strategy Challenge Fund, part of the UK government’s modern Industrial Strategy. The fund is delivered by UK Research and Innovation and managed by EPSRC [EP/R026084/1]. ================================================ FILE: _config.yml ================================================ theme: jekyll-theme-cayman ================================================ FILE: benchmarks/CMakeLists.txt ================================================ ####################################################### # This file is the CMAKE script for Benchmarks Libraries ####################################################### cmake_minimum_required(VERSION 3.10) project(benchmarks) if (NOT SLAMBENCH_INCLUDE_DIR) message( FATAL_ERROR "SLAMBENCH_INCLUDE_DIR not found") else () include_directories(${SLAMBENCH_INCLUDE_DIR}) endif() ## EXTERNAL SOURCE CODE, SKIP WARNINGS .... ############################################################ set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-error") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error") #### ADD USE-CASES DIRECTORIES ### ############################################################ if ("${APPS}" STREQUAL "all") message(STATUS "Select all applications...") set(APPS_MOD "efusion;kfusion;lsdslam;monoslam;infinitam;ptam;okvis;orbslam2;orbslam3;svo;flame,refusion,kinectfusion,dso,fullfusion") else() message(STATUS "Select only ${APPS} applications...") string(REPLACE "," ";" APPS_MOD "${APPS}") endif() set(app_list ${APPS_MOD}) MESSAGE(STATUS "Application loop over ${APPS_MOD}") FOREACH(app ${app_list}) IF(IS_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}/${app}") MESSAGE(STATUS "Load application ${app}") ADD_SUBDIRECTORY(${app}) ELSE() MESSAGE(STATUS "Use-case ${app} not found. Please try \" make ${app} \" to download the usecase.") ENDIF() ENDFOREACH(app) ================================================ FILE: cmake_modules/CUDACheckCompute.cmake ================================================ ############################# #Sourced from: #https://raw.githubusercontent.com/jwetzl/CudaLBFGS/master/CheckComputeCapability.cmake ############################# # Check for GPUs present and their compute capability # based on http://stackoverflow.com/questions/2285185/easiest-way-to-test-for-existence-of-cuda-capable-gpu-from-cmake/2297877#2297877 (Christopher Bruns) if(CUDA_FOUND) message(STATUS "Try to compile and run : ${PROJECT_SOURCE_DIR}/cmake/cuda_compute_capability.c") try_run(RUN_RESULT_VAR COMPILE_RESULT_VAR ${CMAKE_BINARY_DIR} ${CMAKE_SOURCE_DIR}/cmake_modules/cuda_compute_capability.c CMAKE_FLAGS -DINCLUDE_DIRECTORIES:STRING=${CUDA_TOOLKIT_INCLUDE} -DLINK_LIBRARIES:STRING=${CUDA_CUDART_LIBRARY} COMPILE_OUTPUT_VARIABLE COMPILE_OUTPUT_VAR RUN_OUTPUT_VARIABLE RUN_OUTPUT_VAR) message(STATUS "Compile: ${RUN_OUTPUT_VAR}") if (COMPILE_RESULT_VAR) message(STATUS "compiled -> " ${RUN_RESULT_VAR}) else() message(STATUS "didn't compile") endif() # COMPILE_RESULT_VAR is TRUE when compile succeeds # RUN_RESULT_VAR is zero when a GPU is found if(COMPILE_RESULT_VAR AND NOT RUN_RESULT_VAR) message(STATUS "worked") set(CUDA_HAVE_GPU TRUE CACHE BOOL "Whether CUDA-capable GPU is present") set(CUDA_COMPUTE_CAPABILITY ${RUN_OUTPUT_VAR} CACHE STRING "Compute capability of CUDA-capable GPU present") mark_as_advanced(CUDA_COMPUTE_CAPABILITY) else() message(STATUS "didn't work") set(CUDA_HAVE_GPU FALSE CACHE BOOL "Whether CUDA-capable GPU is present") endif() endif() ================================================ FILE: cmake_modules/FindBrisk.cmake ================================================ find_path(BRISK_INCLUDE_PATH Brisk/Brisk.h ~/usr/include ~/usr/.local/include ~/.local/include ~/usr/local/include /usr/include /usr/local/include thirdparty ) if(BRISK_INCLUDE_PATH) set(BRISK_FOUND TRUE) set(BRISK_INCLUDE_PATHS ${BRISK_INCLUDE_PATH} CACHE STRING "The include paths needed to use BRISK") endif() mark_as_advanced( BRISK_INCLUDE_PATHS ) # Generate appropriate messages if(BRISK_FOUND) if(NOT BRISK_FIND_QUIETLY) message("-- Found Brisk: ${BRISK_INCLUDE_PATH}") endif(NOT BRISK_FIND_QUIETLY) else(BRISK_FOUND) if(BRISK_FIND_REQUIRED) message(FATAL_ERROR "-- Could NOT find BRISK (missing: BRISK_INCLUDE_PATH)") endif(BRISK_FIND_REQUIRED) endif(BRISK_FOUND) ================================================ FILE: cmake_modules/FindCVD.cmake ================================================ # - Try to find libCVD # # CVD_FOUND - system has libCVD # CVD_INCLUDE_DIR - the libCVD include directories # CVD_LIBRARY - link these to use libCVD FIND_PATH( CVD_INCLUDE_DIR NAMES cvd/cvd_image.h PATHS /usr/include /usr/local/include ) FIND_LIBRARY( CVD_LIBRARY NAMES cvd PATHS /usr/lib /usr/local/lib ) IF(CVD_INCLUDE_DIR AND CVD_LIBRARY) SET(CVD_FOUND TRUE) ENDIF() IF(CVD_FOUND) IF(NOT CVD_FIND_QUIETLY) MESSAGE(STATUS "Found CVD: ${CVD_LIBRARY}") ENDIF() ELSE() IF(CVD_FIND_REQUIRED) MESSAGE(FATAL_ERROR "Could not find CVD") ENDIF() ENDIF() ================================================ FILE: cmake_modules/FindCeres.cmake ================================================ # -*- mode: cmake; -*- ############################################################################### # Find Ceres # # This sets the following variables: # CERES_FOUND - True if CERES was found. # CERES_INCLUDE_DIRS - Directories containing the CERES include files. # CERES_LIBRARIES - Libraries needed to use CERES. # find_path(CERES_INCLUDE_PATH ceres/ceres.h ${CERES_DIR}/include NO_DEFAULT_PATH ) find_library(CERES_DYNAMIC_LIBRARY NAMES libceres.so PATHS ${CERES_DIR}/lib64 ${CERES_DIR}/lib NO_DEFAULT_PATH ) find_library(CERES_STATIC_LIBRARY NAMES libceres.a PATHS ${CERES_DIR}/lib64 ${CERES_DIR}/lib NO_DEFAULT_PATH ) message(STATUS "CERES_DIR=${CERES_DIR}") message(STATUS "CERES_INCLUDE_PATH=${CERES_INCLUDE_PATH}") message(STATUS "CERES_DYNAMIC_LIBRARY=${CERES_DYNAMIC_LIBRARY}") message(STATUS "CERES_STATIC_LIBRARY=${CERES_STATIC_LIBRARY}") if(CERES_STATIC_LIBRARY OR CERES_DYNAMIC_LIBRARY) if(CERES_INCLUDE_PATH) set(CERES_FOUND TRUE) set(CERES_INCLUDE_PATHS ${CERES_INCLUDE_PATH} CACHE STRING "The include paths needed to use CERES") if(CERES_STATIC_LIBRARY) set(CERES_LIBRARIES "${CERES_STATIC_LIBRARY}" CACHE STRING "The libraries needed to use CERES") ELSE() set(CERES_LIBRARIES "${CERES_DYNAMIC_LIBRARY}" CACHE STRING "The libraries needed to use CERES") ENDIF() else() if(Ceres_FIND_REQUIRED) message(FATAL_ERROR "-- Could NOT find CERES (missing: CERES_INCLUDE_PATH)") endif(Ceres_FIND_REQUIRED) endif() else() if(Ceres_FIND_REQUIRED) message(FATAL_ERROR "-- Could NOT find CERES (missing: CERES_STATIC_LIBRARY or CERES_DYNAMIC_LIBRARY)") endif(Ceres_FIND_REQUIRED) endif() mark_as_advanced( CERES_INCLUDE_PATHS CERES_LIBRARIES ) # Generate appropriate messages if(Ceres_FOUND) if(NOT Ceres_FIND_QUIETLY) message("-- Found CERES: ${CERES_INCLUDE_PATH}") endif(NOT Ceres_FIND_QUIETLY) endif(Ceres_FOUND) ================================================ FILE: cmake_modules/FindEigen.cmake ================================================ # - Try to find Eigen3 lib # # This module supports requiring a minimum version, e.g. you can do # find_package(Eigen3 3.1.2) # to require version 3.1.2 or newer of Eigen3. # # Once done this will define # # EIGEN3_FOUND - system has eigen lib with correct version # EIGEN3_INCLUDE_DIR - the eigen include directory # EIGEN3_VERSION - eigen version # Copyright (c) 2006, 2007 Montel Laurent, # Copyright (c) 2008, 2009 Gael Guennebaud, # Copyright (c) 2009 Benoit Jacob # Redistribution and use is allowed according to the terms of the 2-clause BSD license. if(NOT Eigen3_FIND_VERSION) if(NOT Eigen3_FIND_VERSION_MAJOR) set(Eigen3_FIND_VERSION_MAJOR 2) endif(NOT Eigen3_FIND_VERSION_MAJOR) if(NOT Eigen3_FIND_VERSION_MINOR) set(Eigen3_FIND_VERSION_MINOR 91) endif(NOT Eigen3_FIND_VERSION_MINOR) if(NOT Eigen3_FIND_VERSION_PATCH) set(Eigen3_FIND_VERSION_PATCH 0) endif(NOT Eigen3_FIND_VERSION_PATCH) set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") endif(NOT Eigen3_FIND_VERSION) macro(_eigen3_check_version) file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) set(EIGEN3_VERSION_OK FALSE) else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) set(EIGEN3_VERSION_OK TRUE) endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) if(NOT EIGEN3_VERSION_OK) message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " "but at least version ${Eigen3_FIND_VERSION} is required") endif(NOT EIGEN3_VERSION_OK) endmacro(_eigen3_check_version) if (EIGEN3_INCLUDE_DIR) # in cache already _eigen3_check_version() set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) else (EIGEN3_INCLUDE_DIR) find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library PATHS ${CMAKE_INSTALL_PREFIX}/include ${KDE4_INCLUDE_DIR} PATH_SUFFIXES eigen3 eigen ) if(EIGEN3_INCLUDE_DIR) _eigen3_check_version() endif(EIGEN3_INCLUDE_DIR) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) mark_as_advanced(EIGEN3_INCLUDE_DIR) endif(EIGEN3_INCLUDE_DIR) ================================================ FILE: cmake_modules/FindEigen3.cmake ================================================ # - Try to find Eigen3 lib # # This module supports requiring a minimum version, e.g. you can do # find_package(Eigen3 3.1.2) # to require version 3.1.2 or newer of Eigen3. # # Once done this will define # # EIGEN3_FOUND - system has eigen lib with correct version # EIGEN3_INCLUDE_DIR - the eigen include directory # EIGEN3_VERSION - eigen version # Copyright (c) 2006, 2007 Montel Laurent, # Copyright (c) 2008, 2009 Gael Guennebaud, # Copyright (c) 2009 Benoit Jacob # Redistribution and use is allowed according to the terms of the 2-clause BSD license. if(NOT Eigen3_FIND_VERSION) if(NOT Eigen3_FIND_VERSION_MAJOR) set(Eigen3_FIND_VERSION_MAJOR 2) endif(NOT Eigen3_FIND_VERSION_MAJOR) if(NOT Eigen3_FIND_VERSION_MINOR) set(Eigen3_FIND_VERSION_MINOR 91) endif(NOT Eigen3_FIND_VERSION_MINOR) if(NOT Eigen3_FIND_VERSION_PATCH) set(Eigen3_FIND_VERSION_PATCH 0) endif(NOT Eigen3_FIND_VERSION_PATCH) set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") endif(NOT Eigen3_FIND_VERSION) macro(_eigen3_check_version) file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) set(EIGEN3_VERSION_OK FALSE) else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) set(EIGEN3_VERSION_OK TRUE) endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) if(NOT EIGEN3_VERSION_OK) message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " "but at least version ${Eigen3_FIND_VERSION} is required") endif(NOT EIGEN3_VERSION_OK) endmacro(_eigen3_check_version) if (EIGEN3_INCLUDE_DIR) # in cache already _eigen3_check_version() set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) else (EIGEN3_INCLUDE_DIR) find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library PATHS ${CMAKE_INSTALL_PREFIX}/include ${KDE4_INCLUDE_DIR} PATH_SUFFIXES eigen3 eigen ) if(EIGEN3_INCLUDE_DIR) _eigen3_check_version() endif(EIGEN3_INCLUDE_DIR) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) mark_as_advanced(EIGEN3_INCLUDE_DIR) endif(EIGEN3_INCLUDE_DIR) ================================================ FILE: cmake_modules/FindFreeImage.cmake ================================================ # # Try to find the FreeImage library and include path. # Once done this will define # # FREEIMAGE_FOUND # FREEIMAGE_INCLUDE_PATH # FREEIMAGE_LIBRARY # FREEIMAGE_STATIC_LIBRARY # FREEIMAGE_DYNAMIC_LIBRARY # OPTION(USE_FreeImage_STATIC "Use Static FreeImage Lib" OFF) FIND_PATH(FreeImage_INCLUDE_PATH NAMES FreeImage.h PATHS /usr/include /usr/local/include /sw/include /opt/local/include DOC "The directory where FreeImage.h resides") FIND_LIBRARY(FreeImage_DYNAMIC_LIBRARY NAMES FreeImage freeimage PATHS /usr/lib64 /usr/lib /usr/local/lib64 /usr/local/lib /sw/lib /opt/local/lib DOC "The FreeImage library") SET(PX ${CMAKE_STATIC_LIBRARY_PREFIX}) SET(SX ${CMAKE_STATIC_LIBRARY_SUFFIX}) FIND_LIBRARY(FreeImage_STATIC_LIBRARY NAMES ${PX}FreeImageLIB${SX} ${PX}FreeImage${SX} ${PX}freeimage${SX} HINTS ${PROJECT_SOURCE_DIR}/FreeImage PATHS /usr/lib64 /usr/lib /usr/local/lib64 /usr/local/lib /sw/lib /opt/local/lib DOC "The FreeImage library") UNSET(PX) UNSET(SX) IF(USE_FreeImage_STATIC) IF(FreeImage_STATIC_LIBRARY) ADD_DEFINITIONS(-D$FREEIMAGE_LIB) SET(FreeImage_LIBRARY ${FreeImage_STATIC_LIBRARY}) MESSAGE(STATUS "Using Static FreeImage Lib FreeImage_LIBRARY = " ${FreeImage_LIBRARY}) else(FreeImage_STATIC_LIBRARY) if(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) message(FATAL_ERROR "Could not find FREEIMAGE static libs ") endif(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) endif(FreeImage_STATIC_LIBRARY) ELSE(USE_FreeImage_STATIC) IF(FreeImage_DYNAMIC_LIBRARY) REMOVE_DEFINITIONS(-DFREEIMAGE_LIB) SET(FreeImage_LIBRARY ${FreeImage_DYNAMIC_LIBRARY}) MESSAGE(STATUS "Using Dynamic FreeImage Lib FreeImage_LIBRARY = " ${FreeImage_LIBRARY}) else(FreeImage_DYNAMIC_LIBRARY) if(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) message(FATAL_ERROR "Could not find FREEIMAGE dynamic libs ") endif(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) endif(FreeImage_DYNAMIC_LIBRARY) ENDIF(USE_FreeImage_STATIC) IF(FreeImage_INCLUDE_PATH) MESSAGE(STATUS "Using FreeImage include dir") SET(FreeImage_INCLUDE_DIRS ${FreeImage_INCLUDE_PATH}) else(FreeImage_INCLUDE_PATH) if(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) message(FATAL_ERROR "Could not find FREEIMAGE include directory") endif(FreeImage_FIND_REQUIRED AND NOT FreeImage_FIND_QUIETLY) endif(FreeImage_INCLUDE_PATH) INCLUDE(FindPackageHandleStandardArgs) FIND_PACKAGE_HANDLE_STANDARD_ARGS(FREEIMAGE DEFAULT_MSG FreeImage_INCLUDE_DIRS FreeImage_LIBRARY) MARK_AS_ADVANCED( FreeImage_INCLUDE_DIRS FreeImage_DYNAMIC_LIBRARY FreeImage_STATIC_LIBRARY FreeImage_LIBRARY ) ================================================ FILE: cmake_modules/FindG2O.cmake ================================================ # Find the header files FIND_PATH(G2O_INCLUDE_DIR g2o/core/base_vertex.h ${G2O_ROOT}/include $ENV{G2O_ROOT}/include $ENV{G2O_ROOT} /usr/local/include /usr/include /opt/local/include /sw/local/include /sw/include NO_DEFAULT_PATH ) # Macro to unify finding both the debug and release versions of the # libraries; this is adapted from the OpenSceneGraph FIND_LIBRARY # macro. MACRO(FIND_G2O_LIBRARY MYLIBRARY MYLIBRARYNAME) FIND_LIBRARY("${MYLIBRARY}_DEBUG" NAMES "g2o_${MYLIBRARYNAME}_d" PATHS ${G2O_ROOT}/lib/Debug ${G2O_ROOT}/lib $ENV{G2O_ROOT}/lib/Debug $ENV{G2O_ROOT}/lib NO_DEFAULT_PATH ) FIND_LIBRARY("${MYLIBRARY}_DEBUG" NAMES "g2o_${MYLIBRARYNAME}_d" PATHS ~/Library/Frameworks /Library/Frameworks /usr/local/lib /usr/local/lib64 /usr/lib /usr/lib64 /opt/local/lib /sw/local/lib /sw/lib ) FIND_LIBRARY(${MYLIBRARY} NAMES "g2o_${MYLIBRARYNAME}" PATHS ${G2O_ROOT}/lib/Release ${G2O_ROOT}/lib $ENV{G2O_ROOT}/lib/Release $ENV{G2O_ROOT}/lib NO_DEFAULT_PATH ) FIND_LIBRARY(${MYLIBRARY} NAMES "g2o_${MYLIBRARYNAME}" PATHS ~/Library/Frameworks /Library/Frameworks /usr/local/lib /usr/local/lib64 /usr/lib /usr/lib64 /opt/local/lib /sw/local/lib /sw/lib ) IF(NOT ${MYLIBRARY}_DEBUG) IF(MYLIBRARY) SET(${MYLIBRARY}_DEBUG ${MYLIBRARY}) ENDIF(MYLIBRARY) ENDIF( NOT ${MYLIBRARY}_DEBUG) ENDMACRO(FIND_G2O_LIBRARY LIBRARY LIBRARYNAME) # Find the core elements FIND_G2O_LIBRARY(G2O_STUFF_LIBRARY stuff) FIND_G2O_LIBRARY(G2O_CORE_LIBRARY core) # Find the CLI library FIND_G2O_LIBRARY(G2O_CLI_LIBRARY cli) # Find the pluggable solvers FIND_G2O_LIBRARY(G2O_SOLVER_CHOLMOD solver_cholmod) FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE solver_csparse) FIND_G2O_LIBRARY(G2O_SOLVER_CSPARSE_EXTENSION csparse_extension) FIND_G2O_LIBRARY(G2O_SOLVER_DENSE solver_dense) FIND_G2O_LIBRARY(G2O_SOLVER_PCG solver_pcg) FIND_G2O_LIBRARY(G2O_SOLVER_SLAM2D_LINEAR solver_slam2d_linear) FIND_G2O_LIBRARY(G2O_SOLVER_STRUCTURE_ONLY solver_structure_only) FIND_G2O_LIBRARY(G2O_SOLVER_EIGEN solver_eigen) # Find the predefined types FIND_G2O_LIBRARY(G2O_TYPES_DATA types_data) FIND_G2O_LIBRARY(G2O_TYPES_ICP types_icp) FIND_G2O_LIBRARY(G2O_TYPES_SBA types_sba) FIND_G2O_LIBRARY(G2O_TYPES_SCLAM2D types_sclam2d) FIND_G2O_LIBRARY(G2O_TYPES_SIM3 types_sim3) FIND_G2O_LIBRARY(G2O_TYPES_SLAM2D types_slam2d) FIND_G2O_LIBRARY(G2O_TYPES_SLAM3D types_slam3d) # G2O solvers declared found if we found at least one solver SET(G2O_SOLVERS_FOUND "NO") IF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) SET(G2O_SOLVERS_FOUND "YES") ENDIF(G2O_SOLVER_CHOLMOD OR G2O_SOLVER_CSPARSE OR G2O_SOLVER_DENSE OR G2O_SOLVER_PCG OR G2O_SOLVER_SLAM2D_LINEAR OR G2O_SOLVER_STRUCTURE_ONLY OR G2O_SOLVER_EIGEN) # G2O itself declared found if we found the core libraries and at least one solver IF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) SET(G2O_FOUND "YES") ENDIF(G2O_STUFF_LIBRARY AND G2O_CORE_LIBRARY AND G2O_INCLUDE_DIR AND G2O_SOLVERS_FOUND) ================================================ FILE: cmake_modules/FindGVARS.cmake ================================================ # - Try to find GVARS # # GVARS_FOUND - system has GVARS # GVARS_INCLUDE_DIR - the GVARS include directories # GVARS_LIBRARY - link these to use GVARS FIND_PATH( GVARS_INCLUDE_DIR NAMES gvars3/config.h PATHS /usr/include /usr/local/include ) FIND_LIBRARY( GVARS_LIBRARY NAMES GVars3 PATHS /usr/lib /usr/local/lib ) IF(GVARS_INCLUDE_DIR AND GVARS_LIBRARY) SET(GVARS_FOUND TRUE) ENDIF() IF(GVARS_FOUND) IF(NOT GVARS_FIND_QUIETLY) MESSAGE(STATUS "Found GVARS: ${GVARS_LIBRARY}") ENDIF() ELSE() IF(GVARS_FIND_REQUIRED) MESSAGE(FATAL_ERROR "Could not find GVARS") ENDIF() ENDIF() ================================================ FILE: cmake_modules/FindGlog.cmake ================================================ # Ceres Solver - A fast non-linear least squares minimizer # Copyright 2015 Google Inc. All rights reserved. # http://ceres-solver.org/ # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright notice, # this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above copyright notice, # this list of conditions and the following disclaimer in the documentation # and/or other materials provided with the distribution. # * Neither the name of Google Inc. nor the names of its contributors may be # used to endorse or promote products derived from this software without # specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Author: alexs.mac@gmail.com (Alex Stewart) # # FindGlog.cmake - Find Google glog logging library. # # This module defines the following variables: # # GLOG_FOUND: TRUE iff glog is found. # GLOG_INCLUDE_DIRS: Include directories for glog. # GLOG_LIBRARIES: Libraries required to link glog. # # The following variables control the behaviour of this module: # # GLOG_INCLUDE_DIR_HINTS: List of additional directories in which to # search for glog includes, e.g: /timbuktu/include. # GLOG_LIBRARY_DIR_HINTS: List of additional directories in which to # search for glog libraries, e.g: /timbuktu/lib. # # The following variables are also defined by this module, but in line with # CMake recommended FindPackage() module style should NOT be referenced directly # by callers (use the plural variables detailed above instead). These variables # do however affect the behaviour of the module via FIND_[PATH/LIBRARY]() which # are NOT re-called (i.e. search for library is not repeated) if these variables # are set with valid values _in the CMake cache_. This means that if these # variables are set directly in the cache, either by the user in the CMake GUI, # or by the user passing -DVAR=VALUE directives to CMake when called (which # explicitly defines a cache variable), then they will be used verbatim, # bypassing the HINTS variables and other hard-coded search locations. # # GLOG_INCLUDE_DIR: Include directory for glog, not including the # include directory of any dependencies. # GLOG_LIBRARY: glog library, not including the libraries of any # dependencies. # Reset CALLERS_CMAKE_FIND_LIBRARY_PREFIXES to its value when # FindGlog was invoked. macro(GLOG_RESET_FIND_LIBRARY_PREFIX) if (MSVC) set(CMAKE_FIND_LIBRARY_PREFIXES "${CALLERS_CMAKE_FIND_LIBRARY_PREFIXES}") endif (MSVC) endmacro(GLOG_RESET_FIND_LIBRARY_PREFIX) # Called if we failed to find glog or any of it's required dependencies, # unsets all public (designed to be used externally) variables and reports # error message at priority depending upon [REQUIRED/QUIET/] argument. macro(GLOG_REPORT_NOT_FOUND REASON_MSG) unset(GLOG_FOUND) unset(GLOG_INCLUDE_DIRS) unset(GLOG_LIBRARIES) # Make results of search visible in the CMake GUI if glog has not # been found so that user does not have to toggle to advanced view. mark_as_advanced(CLEAR GLOG_INCLUDE_DIR GLOG_LIBRARY) glog_reset_find_library_prefix() # Note _FIND_[REQUIRED/QUIETLY] variables defined by FindPackage() # use the camelcase library name, not uppercase. if (Glog_FIND_QUIETLY) message(STATUS "Failed to find glog - " ${REASON_MSG} ${ARGN}) elseif (Glog_FIND_REQUIRED) message(FATAL_ERROR "Failed to find glog - " ${REASON_MSG} ${ARGN}) else() # Neither QUIETLY nor REQUIRED, use no priority which emits a message # but continues configuration and allows generation. message("-- Failed to find glog - " ${REASON_MSG} ${ARGN}) endif () endmacro(GLOG_REPORT_NOT_FOUND) # Handle possible presence of lib prefix for libraries on MSVC, see # also GLOG_RESET_FIND_LIBRARY_PREFIX(). if (MSVC) # Preserve the caller's original values for CMAKE_FIND_LIBRARY_PREFIXES # s/t we can set it back before returning. set(CALLERS_CMAKE_FIND_LIBRARY_PREFIXES "${CMAKE_FIND_LIBRARY_PREFIXES}") # The empty string in this list is important, it represents the case when # the libraries have no prefix (shared libraries / DLLs). set(CMAKE_FIND_LIBRARY_PREFIXES "lib" "" "${CMAKE_FIND_LIBRARY_PREFIXES}") endif (MSVC) # Search user-installed locations first, so that we prefer user installs # to system installs where both exist. list(APPEND GLOG_CHECK_INCLUDE_DIRS /usr/local/include /usr/local/homebrew/include # Mac OS X /opt/local/var/macports/software # Mac OS X. /opt/local/include /usr/include) # Windows (for C:/Program Files prefix). list(APPEND GLOG_CHECK_PATH_SUFFIXES glog/include glog/Include Glog/include Glog/Include) list(APPEND GLOG_CHECK_LIBRARY_DIRS /usr/local/lib /usr/local/homebrew/lib # Mac OS X. /opt/local/lib /usr/lib) # Windows (for C:/Program Files prefix). list(APPEND GLOG_CHECK_LIBRARY_SUFFIXES glog/lib glog/Lib Glog/lib Glog/Lib) # Search supplied hint directories first if supplied. find_path(GLOG_INCLUDE_DIR NAMES glog/logging.h PATHS ${GLOG_INCLUDE_DIR_HINTS} ${GLOG_CHECK_INCLUDE_DIRS} PATH_SUFFIXES ${GLOG_CHECK_PATH_SUFFIXES}) if (NOT GLOG_INCLUDE_DIR OR NOT EXISTS ${GLOG_INCLUDE_DIR}) glog_report_not_found( "Could not find glog include directory, set GLOG_INCLUDE_DIR " "to directory containing glog/logging.h") endif (NOT GLOG_INCLUDE_DIR OR NOT EXISTS ${GLOG_INCLUDE_DIR}) find_library(GLOG_LIBRARY NAMES glog PATHS ${GLOG_LIBRARY_DIR_HINTS} ${GLOG_CHECK_LIBRARY_DIRS} PATH_SUFFIXES ${GLOG_CHECK_LIBRARY_SUFFIXES}) if (NOT GLOG_LIBRARY OR NOT EXISTS ${GLOG_LIBRARY}) glog_report_not_found( "Could not find glog library, set GLOG_LIBRARY " "to full path to libglog.") endif (NOT GLOG_LIBRARY OR NOT EXISTS ${GLOG_LIBRARY}) # Mark internally as found, then verify. GLOG_REPORT_NOT_FOUND() unsets # if called. set(GLOG_FOUND TRUE) # Glog does not seem to provide any record of the version in its # source tree, thus cannot extract version. # Catch case when caller has set GLOG_INCLUDE_DIR in the cache / GUI and # thus FIND_[PATH/LIBRARY] are not called, but specified locations are # invalid, otherwise we would report the library as found. if (GLOG_INCLUDE_DIR AND NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) glog_report_not_found( "Caller defined GLOG_INCLUDE_DIR:" " ${GLOG_INCLUDE_DIR} does not contain glog/logging.h header.") endif (GLOG_INCLUDE_DIR AND NOT EXISTS ${GLOG_INCLUDE_DIR}/glog/logging.h) # TODO: This regex for glog library is pretty primitive, we use lowercase # for comparison to handle Windows using CamelCase library names, could # this check be better? string(TOLOWER "${GLOG_LIBRARY}" LOWERCASE_GLOG_LIBRARY) if (GLOG_LIBRARY AND NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") glog_report_not_found( "Caller defined GLOG_LIBRARY: " "${GLOG_LIBRARY} does not match glog.") endif (GLOG_LIBRARY AND NOT "${LOWERCASE_GLOG_LIBRARY}" MATCHES ".*glog[^/]*") # Set standard CMake FindPackage variables if found. if (GLOG_FOUND) set(GLOG_INCLUDE_DIRS ${GLOG_INCLUDE_DIR}) set(GLOG_LIBRARIES ${GLOG_LIBRARY}) endif (GLOG_FOUND) glog_reset_find_library_prefix() # Handle REQUIRED / QUIET optional arguments. include(FindPackageHandleStandardArgs) find_package_handle_standard_args(Glog DEFAULT_MSG GLOG_INCLUDE_DIRS GLOG_LIBRARIES) # Only mark internal variables as advanced if we found glog, otherwise # leave them visible in the standard GUI for the user to set manually. if (GLOG_FOUND) mark_as_advanced(FORCE GLOG_INCLUDE_DIR GLOG_LIBRARY) endif (GLOG_FOUND) ================================================ FILE: cmake_modules/FindLIBYAML.cmake ================================================ # CMake module to search for the libyaml library # (library for parsing YAML files) # # If it's found it sets LIBYAML_FOUND to TRUE # and following variables are set: # LIBYAML_INCLUDE_DIR # LIBYAML_LIBRARY FIND_PATH(LIBYAML_INCLUDE_DIR NAMES yaml.h HINTS /usr/include/yaml-cpp/) FIND_LIBRARY(LIBYAML_LIBRARY NAMES yaml-cpp HINTS /usr/lib64) if(LIBYAML_LIBRARY) message(STATUS "Found LIBYAML Library: ${LIBYAML_LIBRARY}") else() message(STATUS "NOT Found LIBYAML Library: ${LIBYAML_LIBRARY}") endif() if(LIBYAML_INCLUDE_DIR) message(STATUS "Found LIBYAML includes: ${LIBYAML_INCLUDE_DIR}") else() message(STATUS "NOT Found LIBYAML includes: ${LIBYAML_INCLUDE_DIR}") endif() if(LIBYAML_LIBRARY AND LIBYAML_INCLUDE_DIR) message(STATUS "Found LIBYAML: ${LIBYAML_LIBRARY}") set(LIBYAML_FOUND TRUE) ELSE() IF(LIBYAML_FIND_REQUIRED) message(FATAL_ERROR "NOT FOUND: LIBYAML") ELSE() message(STATUS "NOT FOUND: LIBYAML") ENDIF() endif() mark_as_advanced( LIBYAML_INCLUDE_DIR LIBYAML_LIBRARY ) ================================================ FILE: cmake_modules/FindOpenCL.cmake ================================================ # Module for locating OpenCL. # # Customizable variables: # OPENCL_ROOT_DIR # Specifies OpenCL's root directory. The find module uses this variable to # locate OpenCL. The variable will be filled automatically unless explicitly # set using CMake's -D command-line option. Instead of setting a CMake # variable, an environment variable called OCLROOT can be used. # While locating the root directory, the module will try to detect OpenCL # implementations provided by AMD's Accelerated Parallel Processing SDK, # NVIDIA's GPU Computing Toolkit and Intel's OpenCL SDK by examining the # AMDAPPSDKROOT, CUDA_PATH and INTELOCLSDKROOT environment variables, # respectively. # # Read-only variables: # OPENCL_FOUND # Indicates whether OpenCL has been found. # # OPENCL_INCLUDE_DIRS # Specifies the OpenCL include directories. # # OPENCL_LIBRARIES # Specifies the OpenCL libraries that should be passed to # target_link_libararies. # # # Copyright (c) 2012 Sergiu Dotenco # # Permission is hereby granted, free of charge, to any person obtaining a copy # of this software and associated documentation files (the "Software"), to deal # in the Software without restriction, including without limitation the rights # to use, copy, modify, merge, publish, distribute, sublicense, and/or sell # copies of the Software, and to permit persons to whom the Software is # furnished to do so, subject to the following conditions: # # The above copyright notice and this permission notice shall be included in all # copies or substantial portions of the Software. # # THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR # IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, # FITNESS FOR A PARTOPENCLLAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE # AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER # LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, # OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE # SOFTWARE. INCLUDE (FindPackageHandleStandardArgs) IF (CMAKE_SIZEOF_VOID_P EQUAL 8) SET (_OPENCL_POSSIBLE_LIB_SUFFIXES lib/Win64 lib/x86_64 lib/x64 lib lib64) ELSE (CMAKE_SIZEOF_VOID_P EQUAL 8) SET (_OPENCL_POSSIBLE_LIB_SUFFIXES lib/Win32 lib/x86 lib) ENDIF (CMAKE_SIZEOF_VOID_P EQUAL 8) LIST (APPEND _OPENCL_POSSIBLE_LIB_SUFFIXES lib/nvidia-current) FIND_PATH (OPENCL_ROOT_DIR NAMES OpenCL/cl.h CL/cl.h include/CL/cl.h include/nvidia-current/CL/cl.h HINTS ${CUDA_TOOLKIT_ROOT_DIR} PATHS ENV OCLROOT ENV AMDAPPSDKROOT ENV CUDA_PATH ENV INTELOCLSDKROOT PATH_SUFFIXES cuda DOC "OpenCL root directory") FIND_PATH (OPENCL_INCLUDE_DIR NAMES OpenCL/cl.h CL/cl.h HINTS ${OPENCL_ROOT_DIR} PATH_SUFFIXES include include/nvidia-current DOC "OpenCL include directory") FIND_LIBRARY (OPENCL_LIBRARY NAMES OpenCL HINTS ${OPENCL_ROOT_DIR} /usr/local/lib/mali/fbdev/ PATH_SUFFIXES ${_OPENCL_POSSIBLE_LIB_SUFFIXES} DOC "OpenCL library") SET (OPENCL_INCLUDE_DIRS ${OPENCL_INCLUDE_DIR}) SET (OPENCL_LIBRARIES ${OPENCL_LIBRARY}) IF (OPENCL_INCLUDE_DIR AND OPENCL_LIBRARY) SET (_OPENCL_VERSION_TEST_SOURCE " #if __APPLE__ #include #else /* !__APPLE__ */ #include #endif /* __APPLE__ */ #include #include int main() { char *version; cl_int result; cl_platform_id id; size_t n; result = clGetPlatformIDs(1, &id, NULL); if (result == CL_SUCCESS) { result = clGetPlatformInfo(id, CL_PLATFORM_VERSION, 0, NULL, &n); if (result == CL_SUCCESS) { version = (char*)malloc(n * sizeof(char)); result = clGetPlatformInfo(id, CL_PLATFORM_VERSION, n, version, NULL); if (result == CL_SUCCESS) { printf(\"%s\", version); fflush(stdout); } free(version); } } return result == CL_SUCCESS ? EXIT_SUCCESS : EXIT_FAILURE; } ") SET (_OPENCL_VERSION_SOURCE "${CMAKE_BINARY_DIR}${CMAKE_FILES_DIRECTORY}/CMakeTmp/openclversion.c") FILE (WRITE ${_OPENCL_VERSION_SOURCE} "${_OPENCL_VERSION_TEST_SOURCE}\n") TRY_RUN (_OPENCL_VERSION_RUN_RESULT _OPENCL_VERSION_COMPILE_RESULT ${CMAKE_BINARY_DIR} ${_OPENCL_VERSION_SOURCE} RUN_OUTPUT_VARIABLE _OPENCL_VERSION_STRING CMAKE_FLAGS "-DINCLUDE_DIRECTORIES:STRING=${OPENCL_INCLUDE_DIRS}" "-DLINK_LIBRARIES:STRING=${OPENCL_LIBRARIES}") IF (_OPENCL_VERSION_RUN_RESULT EQUAL 0) STRING (REGEX REPLACE "OpenCL[ \t]+([0-9]+)\\.[0-9]+.*" "\\1" OPENCL_VERSION_MAJOR "${_OPENCL_VERSION_STRING}") STRING (REGEX REPLACE "OpenCL[ \t]+[0-9]+\\.([0-9]+).*" "\\1" OPENCL_VERSION_MINOR "${_OPENCL_VERSION_STRING}") SET (OPENCL_VERSION_COMPONENTS 2) SET (OPENCL_VERSION "${OPENCL_VERSION_MAJOR}.${OPENCL_VERSION_MINOR}") ENDIF (_OPENCL_VERSION_RUN_RESULT EQUAL 0) ENDIF (OPENCL_INCLUDE_DIR AND OPENCL_LIBRARY) IF(OPENCL_LIBRARY) MESSAGE(STATUS "Using OPENCL_LIBRARY = ${OPENCL_LIBRARY}" ) else(OPENCL_LIBRARY) if(OpenCL_FIND_REQUIRED AND NOT OpenCL_FIND_QUIETLY) message(FATAL_ERROR "Could not find OpenCL libary") endif(OpenCL_FIND_REQUIRED AND NOT OpenCL_FIND_QUIETLY) endif(OPENCL_LIBRARY) MARK_AS_ADVANCED (OPENCL_INCLUDE_DIR OPENCL_LIBRARY) FIND_PACKAGE_HANDLE_STANDARD_ARGS (OpenCL REQUIRED_VARS OPENCL_ROOT_DIR OPENCL_INCLUDE_DIR OPENCL_LIBRARY VERSION_VAR OPENCL_VERSION) ================================================ FILE: cmake_modules/FindOpenNI.cmake ================================================ # -*- mode: cmake; -*- ############################################################################### # Find OpenNI # # This sets the following variables: # OPENNI_FOUND - True if OPENNI was found. # OPENNI_INCLUDE_DIRS - Directories containing the OPENNI include files. # OPENNI_LIBRARIES - Libraries needed to use OPENNI. # OPENNI_DEFINITIONS - Compiler flags for OPENNI. # # File forked from augmented_dev, project of alantrrs # (https://github.com/alantrrs/augmented_dev). find_package(PkgConfig) if(${CMAKE_VERSION} VERSION_LESS 2.8.2) pkg_check_modules(PC_OPENNI openni-dev) else() pkg_check_modules(PC_OPENNI QUIET openni-dev) endif() set(OPENNI_DEFINITIONS ${PC_OPENNI_CFLAGS_OTHER}) #using the 64bit version of OpenNi if generating for 64bit if(CMAKE_SIZEOF_VOID_P EQUAL 8) set(PROGRAMFILES_ "$ENV{PROGRAMW6432}") set(OPENNI_SUFFIX "64") else(CMAKE_SIZEOF_VOID_P EQUAL 8) set(PROGRAMFILES_ "$ENV{PROGRAMFILES}") set(OPENNI_SUFFIX "") endif(CMAKE_SIZEOF_VOID_P EQUAL 8) #add a hint so that it can find it without the pkg-config find_path(OPENNI_INCLUDE_DIR XnStatus.h HINTS ${PC_OPENNI_INCLUDEDIR} ${PC_OPENNI_INCLUDE_DIRS} /usr/include/ni /usr/include/openni "${PROGRAMFILES_}/OpenNI/Include" PATH_SUFFIXES openni) #add a hint so that it can find it without the pkg-config find_library(OPENNI_LIBRARY NAMES OpenNI64 OpenNI HINTS ${PC_OPENNI_LIBDIR} ${PC_OPENNI_LIBRARY_DIRS} /usr/lib "${PROGRAMFILES_}/OpenNI/Lib${OPENNI_SUFFIX}") set(OPENNI_INCLUDE_DIRS ${OPENNI_INCLUDE_DIR}) set(OPENNI_LIBRARIES ${OPENNI_LIBRARY}) include(FindPackageHandleStandardArgs) find_package_handle_standard_args(OpenNI DEFAULT_MSG OPENNI_LIBRARY OPENNI_INCLUDE_DIR) mark_as_advanced(OPENNI_LIBRARY OPENNI_INCLUDE_DIR) ================================================ FILE: cmake_modules/FindOpenNI2.cmake ================================================ find_library(OPENNI2_LIBRARY NAMES OpenNI2 PATHS ~/usr/lib ~/usr/local/lib ~/.local/lib64 ~/.local/lib /usr/lib /usr/local/lib /data/Repositories/OpenNI2-2.2-beta2/Bin/x64-Release /scratch/cad/OpenNI/Redist /data/sw/OpenNI/OpenNI2-2.2-beta2/Bin/x64-Release PATH_SUFFIXES openni2 ni2 ) if(OPENNI2_LIBRARY) else() find_library(OPENNI2_LIBRARY NAMES OpenNI2 PATHS /usr/lib /usr/local/lib ) endif() find_path(OPENNI2_INCLUDE_PATH NAMES OpenNI.h PATHS ~/usr/include ~/.local/include ~/usr/local/include /usr/include /usr/local/include /scratch/cad/OpenNI/Include /data/sw/OpenNI/OpenNI2-2.2-beta2/Include PATH_SUFFIXES openni2 ni2 ) if(OPENNI2_LIBRARY) else() message(STATUS "NOT Found OpenNI2 Library: ${OPENNI2_LIBRARY}") endif() if(OPENNI2_INCLUDE_PATH) set(OPENNI2_INCLUDE_DIR ${OPENNI2_INCLUDE_PATH}) else() message(STATUS "NOT Found OpenNI2 includes: ${OPENNI2_INCLUDE_PATH}") endif() if(OPENNI2_LIBRARY AND OPENNI2_INCLUDE_PATH) message(STATUS "Found OpenNI2: ${OPENNI2_LIBRARY}") set(OpenNI2_FOUND TRUE) set(OPENNI2_INCLUDE_PATHS ${OPENNI2_INCLUDE_PATH} CACHE STRING "The include paths needed to use OpenNI2") set(OPENNI2_LIBRARIES ${OPENNI2_LIBRARY} CACHE STRING "The libraries needed to use OpenNI2") else() message(STATUS "NOT FOUND: OpenNI2") endif() mark_as_advanced( OPENNI2_INCLUDE_PATHS OPENNI2_LIBRARIES ) ================================================ FILE: cmake_modules/FindPAPI.cmake ================================================ # Try to find PAPI headers and libraries. # # Usage of this module as follows: # # find_package(PAPI) # # Variables used by this module, they can change the default behaviour and need # to be set before calling find_package: # # PAPI_PREFIX Set this variable to the root installation of # libpapi if the module has problems finding the # proper installation path. # # Variables defined by this module: # # PAPI_FOUND System has PAPI libraries and headers # PAPI_LIBRARIES The PAPI library # PAPI_INCLUDE_DIRS The location of PAPI headers find_path(PAPI_PREFIX NAMES include/papi.h ) find_library(PAPI_LIBRARY # Pick the static library first for easier run-time linking. NAMES libpapi.a papi HINTS ${PAPI_PREFIX}/lib ${HILTIDEPS}/lib ) find_library(SENSORS_LIBRARY NAMES sensors DOCS "LM_SENSORS Library" ) find_path(PAPI_INCLUDE_DIRS NAMES papi.h HINTS ${PAPI_PREFIX}/include ${HILTIDEPS}/include ) if (PAPI_LIBRARY AND SENSORS_LIBRARY) SET(PAPI_LIBRARIES ${PAPI_LIBRARY} ${SENSORS_LIBRARY}) ENDIF() include(FindPackageHandleStandardArgs) find_package_handle_standard_args(PAPI DEFAULT_MSG PAPI_LIBRARY SENSORS_LIBRARY PAPI_INCLUDE_DIRS ) mark_as_advanced( PAPI_PREFIX_DIRS PAPI_LIBRARIES PAPI_INCLUDE_DIRS ) ================================================ FILE: cmake_modules/FindSLAMBENCH.cmake ================================================ find_path(SLAMBENCH_INCLUDE_PATH SLAMBenchAPI.h) find_library(SLAMBENCH_UTILS_LIBRARY libslambench-utils.a PATH ${SLAMBENCH_LIBRARY_PATH}) find_library(SLAMBENCH_IO_LIBRARY libslambench-io.a PATH ${SLAMBENCH_LIBRARY_PATH}) find_library(SLAMBENCH_C_WRAPPER_LIBRARY libslambench-c-wrapper.a PATH ${SLAMBENCH_LIBRARY_PATH}) find_library(SLAMBENCH_METRICS_LIBRARY libslambench-metrics.a PATH ${SLAMBENCH_LIBRARY_PATH}) if(SLAMBENCH_INCLUDE_PATH) if(SLAMBENCH_UTILS_LIBRARY) set(SLAMBENCH_FOUND TRUE) SET(SLAMBENCH_INCLUDE_DIR ${EIGEN3_INCLUDE_DIR} ${SLAMBENCH_INCLUDE_PATH} CACHE STRING "The include paths needed to use SLAMBENCH") SET(SLAMBENCH_LIBRARIES ${SLAMBENCH_UTILS_LIBRARY} -Wl,--whole-archive ${SLAMBENCH_IO_LIBRARY} ${SLAMBENCH_METRICS_LIBRARY} -Wl,--no-whole-archive) SET(SLAMBENCH_C_WRAPPER -Wl,--whole-archive ${SLAMBENCH_C_WRAPPER_LIBRARY} -Wl,--no-whole-archive) else() MESSAGE(STATUS "SLAMBENCH libraries are missing.") endif() else() MESSAGE(STATUS "SLAMBENCH headers are missing.") endif() mark_as_advanced( SLAMBENCH_INCLUDE_DIR SLAMBENCH_LIBRARIES SLAMBENCH_C_WRAPPER ) # Generate appropriate messages if(SLAMBENCH_FOUND) if(NOT SLAMBENCH_FIND_QUIETLY) message("-- Found SLAMbench2: ${SLAMBENCH_INCLUDE_DIR}") endif(NOT SLAMBENCH_FIND_QUIETLY) else(SLAMBENCH_FOUND) if(SLAMBENCH_FIND_REQUIRED) if(NOT SLAMBENCH_INCLUDE_PATH) message(FATAL_ERROR "-- Could NOT find SLAMBENCH (missing: SLAMBENCH_INCLUDE_PATH)") else () message(FATAL_ERROR "-- Could NOT find SLAMBENCH (missing: SLAMBENCH_LIBRARY_PATH)") endif() endif(SLAMBENCH_FIND_REQUIRED) endif(SLAMBENCH_FOUND) ================================================ FILE: cmake_modules/FindSuiteSparse.cmake ================================================ IF(SuiteSparse_FOUND) SET(SuiteSparse_FIND_QUIETLY TRUE) ENDIF(SuiteSparse_FOUND) ################ AMD ################## FIND_PATH(AMD_INCLUDE_DIR NAMES amd.h PATHS ${SUITE_SPARSE_ROOT}/include NO_DEFAULT_PATH ) FIND_LIBRARY(AMD_LIBRARY NAMES libamd.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) IF(AMD_INCLUDE_DIR AND AMD_LIBRARY) message(STATUS "Found AMD_INCLUDE_DIR: ${AMD_INCLUDE_DIR}") message(STATUS "Found AMD_LIBRARY: ${AMD_LIBRARY}") ENDIF(AMD_INCLUDE_DIR AND AMD_LIBRARY) ################ CAMD ################## FIND_PATH(CAMD_INCLUDE_DIR NAMES camd.h PATHS ${SUITE_SPARSE_ROOT}/include NO_DEFAULT_PATH ) FIND_LIBRARY(CAMD_LIBRARY NAMES libcamd.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) IF(CAMD_INCLUDE_DIR AND CAMD_LIBRARY) message(STATUS "Found CAMD_INCLUDE_DIR: ${CAMD_INCLUDE_DIR}") message(STATUS "Found CAMD_LIBRARY: ${CAMD_LIBRARY}") ENDIF(CAMD_INCLUDE_DIR AND CAMD_LIBRARY) ################ COLAMD ################## FIND_PATH(COALMD_INCLUDE_DIR NAMES colamd.h PATHS ${SUITE_SPARSE_ROOT}/include NO_DEFAULT_PATH ) FIND_LIBRARY(COLAMD_LIBRARY NAMES libcolamd.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) IF(COLAMD_INCLUDE_DIR AND COLAMD_LIBRARY) message(STATUS "Found COLAMD_INCLUDE_DIR: ${COLAMD_INCLUDE_DIR}") message(STATUS "Found COLAMD_LIBRARY: ${COALMD_LIBRARY}") ENDIF(COLAMD_INCLUDE_DIR AND COLAMD_LIBRARY) ################ SUITESPARSECONFIG ################## FIND_LIBRARY(SUITESPARSECONFIG_LIBRARY NAMES libsuitesparseconfig.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) # Look for csparse; note the difference in the directory specifications! FIND_PATH(CSPARSE_INCLUDE_DIR NAMES cs.h PATHS ${SUITE_SPARSE_ROOT}/include NO_DEFAULT_PATH ) FIND_LIBRARY(CSPARSE_LIBRARY NAMES libcxsparse.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) IF(CSPARSE_INCLUDE_DIR AND CSPARSE_LIBRARY AND SUITESPARSECONFIG_LIBRARY) message(STATUS "Found CSPARSE_INCLUDE_DIR: ${CSPARSE_INCLUDE_DIR}") message(STATUS "Found CSPARSE_LIBRARY: ${CSPARSE_LIBRARY}") message(STATUS "Found SUITESPARSECONFIG_LIBRARY: ${SUITESPARSECONFIG_LIBRARY}") SET(SuiteSparse_FOUND TRUE) ELSE(CSPARSE_INCLUDE_DIR AND CSPARSE_LIBRARY AND SUITESPARSECONFIG_LIBRARY) SET(SuiteSparse_FOUND FALSE) if(SuiteSparse_FIND_REQUIRED AND NOT SuiteSparse_FIND_QUIETLY) message(FATAL_ERROR "Could not find SuiteSparse libary") endif(SuiteSparse_FIND_REQUIRED AND NOT SuiteSparse_FIND_QUIETLY) ENDIF(CSPARSE_INCLUDE_DIR AND CSPARSE_LIBRARY AND SUITESPARSECONFIG_LIBRARY) ################ CHOLMOD ################## FIND_PATH(CHOLMOD_INCLUDE_DIR NAMES cholmod.h PATHS ${SUITE_SPARSE_ROOT}/include NO_DEFAULT_PATH ) FIND_LIBRARY(CHOLMOD_LIBRARY NAMES libcholmod.a PATHS ${SUITE_SPARSE_ROOT}/lib NO_DEFAULT_PATH ) IF(CHOLMOD_INCLUDE_DIR AND CHOLMOD_LIBRARY) message(STATUS "Found CHOLMOD_INCLUDE_DIR: ${CHOLMOD_INCLUDE_DIR}") message(STATUS "Found CHOLMOD_LIBRARY: ${CHOLMOD_LIBRARY}") ENDIF(CHOLMOD_INCLUDE_DIR AND CHOLMOD_LIBRARY) find_package(BLAS REQUIRED) find_package(LAPACK REQUIRED) SET(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARY} ${AMD_LIBRARY} ${COLAMD_LIBRARY} ${CSPARSE_LIBRARY} ${SUITESPARSECONFIG_LIBRARY} ${BLA_STATIC} ${LAPACK_LIBRARIES}) ================================================ FILE: cmake_modules/FindTooN.cmake ================================================ find_path(TOON_INCLUDE_PATH TooN/TooN.h ~/usr/include ~/usr/.local/include ~/.local/include ~/usr/local/include /usr/include /usr/local/include thirdparty ) if(TOON_INCLUDE_PATH) set(TooN_FOUND TRUE) set(TOON_INCLUDE_PATHS ${TOON_INCLUDE_PATH} CACHE STRING "The include paths needed to use TooN") endif() mark_as_advanced( TOON_INCLUDE_PATHS ) # Generate appropriate messages if(TooN_FOUND) if(NOT TooN_FIND_QUIETLY) message(STATUS "Found Toon: ${TOON_INCLUDE_PATH}") endif(NOT TooN_FIND_QUIETLY) else(TooN_FOUND) if(TooN_FIND_REQUIRED) message(FATAL_ERROR "Could NOT find TooN (missing: TOON_INCLUDE_PATH)") endif(TooN_FIND_REQUIRED) endif(TooN_FOUND) ================================================ FILE: cmake_modules/cuda_compute_capability.c ================================================ /* * Copyright (C) 2011 Florian Rathgeber, florian.rathgeber@gmail.com * * This code is licensed under the MIT License. See the FindCUDA.cmake script * for the text of the license. * * Based on code by Christopher Bruns published on Stack Overflow (CC-BY): * http://stackoverflow.com/questions/2285185 */ #include #include int main() { int deviceCount, device, major = 9999, minor = 9999; int gpuDeviceCount = 0; struct cudaDeviceProp properties; if (cudaGetDeviceCount(&deviceCount) != cudaSuccess) { printf("Couldn't get device count: %s\n", cudaGetErrorString(cudaGetLastError())); return 1; } /* machines with no GPUs can still report one emulation device */ for (device = 0; device < deviceCount; ++device) { cudaGetDeviceProperties(&properties, device); if (properties.major != 9999) {/* 9999 means emulation only */ ++gpuDeviceCount; /* get minimum compute capability of all devices */ if (major > properties.major) { major = properties.major; minor = properties.minor; } else if ((major == properties.major) && (minor > properties.minor)) { minor = properties.minor; } } } /* don't just return the number of gpus, because other runtime cuda errors can also yield non-zero return values */ if (gpuDeviceCount > 0) { if ((major == 2 && minor == 1)) { // There is no --arch compute_21 flag for nvcc, so force minor to 0 minor = 0; } /* this output will be parsed by FindCUDA.cmake */ printf("%d%d", major, minor); return 0; /* success */ } return 1; /* failure */ } ================================================ FILE: docker/Makefile ================================================ #################################### #### DOCKER PART #### #################################### ## sudo service docker start SLAMBENCH2_DIRECTORY=../ .PHONY: ./%-docker-image %-docker-image ./tmp/%-docker-image/DockerFile : ./%.docker mkdir -p ./tmp/$*-docker-image/slambench2 rm -rf ./tmp/$*-docker-image/slambench2/* cp -r ${SLAMBENCH2_DIRECTORY}/CMakeLists.txt ${SLAMBENCH2_DIRECTORY}/benchmarks ${SLAMBENCH2_DIRECTORY}/cmake_modules ${SLAMBENCH2_DIRECTORY}/framework ${SLAMBENCH2_DIRECTORY}/Makefile ./tmp/$*-docker-image/slambench2 cp -rf $< ./tmp/$*-docker-image/DockerFile # cp -f nvidia-driver.run ./tmp/$*-docker-image/ fedora24 : make fedora-24-docker-image ubuntu14 : make ubuntu-14.04-docker-image ubuntu16 : make ubuntu-16.04-docker-image nvidia_version=$(shell cat /proc/driver/nvidia/version | head -n 1 | awk '{ print $$8 }') nvidia-driver.run : wget -O nvidia-driver.run "http://us.download.nvidia.com/XFree86/Linux-x86_64/${nvidia_version}/NVIDIA-Linux-x86_64-${nvidia_version}.run" cuda-ubuntu16 : nvidia-driver.run make cuda-ubuntu-16.04-docker-image %-docker-image: ./%.docker ./tmp/%-docker-image/DockerFile docker build -f ./tmp/$*-docker-image/DockerFile -t bbodin/slambench:$* ./tmp/$*-docker-image ================================================ FILE: docker/cuda-ubuntu-16.04.docker ================================================ FROM ubuntu:16.04 # Dependencies ################################################################## RUN apt-get -y update && apt-get -y install libvtk6.2 libvtk6-dev unzip libflann-dev wget mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev libyaml-cpp-dev libyaml-dev libproj-dev RUN apt-get -y update && apt-get -y install libhdf5-dev libhdf5-dev # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy deps building system only ################################################################## RUN mkdir -p /slambench2/framework COPY ./slambench2/Makefile /slambench2/Makefile COPY ./slambench2/framework/makefiles /slambench2/framework/makefiles RUN ls -alp /slambench2/ /slambench2/framework/makefiles # Prepare CUDA ################################################################## RUN DEBIAN_FRONTEND=noninteractive apt-get -y install g++-4.8 ADD nvidia-driver.run /tmp/nvidia-driver.run RUN DEBIAN_FRONTEND=noninteractive apt-get install -y module-init-tools RUN sh /tmp/nvidia-driver.run -a -N --ui=none --no-kernel-module RUN rm /tmp/nvidia-driver.run RUN DEBIAN_FRONTEND=noninteractive apt-get install -y mesa-utils RUN DEBIAN_FRONTEND=noninteractive apt-get -y install nvidia-cuda-toolkit clinfo # Build deps ################################################################## RUN apt-get -y update && apt-get -y install flex RUN make -C /slambench2 gcc_cuda RUN make -C /slambench2 toon eigen3 cvd flann freeimage g2o gvars opencv opengv opentuner pangolin pcl suitesparse brisk ceres # Copy entire slambench folder ################################################################## COPY ./slambench2 /slambench2 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench APPS=all # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/fastCI.docker ================================================ FROM fedora:26 # Dependencies ################################################################## RUN dnf install -y git wget gcc gcc-c++ make mercurial cmake unzip RUN dnf install -y yaml-cpp-devel # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench APPS=kfusion # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/TUM/freiburg1/rgbd_dataset_freiburg1_desk.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/TUM/freiburg1/rgbd_dataset_freiburg1_desk.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/TUM/freiburg1/rgbd_dataset_freiburg1_desk.slam -load ./build/lib/libkfusion-cpp-library.so=kf1 -load ./build/lib/libkfusion-openmp-library.so=kf2 -fl 30 -kf1-s 5 -kf2-s 5 -kf1-d 1.71,2.4,1.152 -kf1-z 8 -kf2-d 1.71,2.4,1.152 -kf2-z 8 ================================================ FILE: docker/fedora-24.docker ================================================ FROM fedora:24 # Dependencies ################################################################## RUN dnf install -y emacs gtk2-devel vtk-devel cmake make git mercurial wget unzip gcc gcc-c++ lapack blas lapack-devel blas-devel findutils cvs glut-devel glew-devel boost-devel glog-devel gflags-devel libXmu-devel libyaml libyaml-devel yaml-cpp-devel tar # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 RUN make -C /slambench2 cvd RUN make -C /slambench2 flann RUN make -C /slambench2 freeimage RUN make -C /slambench2 g2o RUN make -C /slambench2 gvars RUN make -C /slambench2 opencv RUN make -C /slambench2 opengv RUN make -C /slambench2 opentuner RUN make -C /slambench2 pangolin RUN make -C /slambench2 pcl RUN make -C /slambench2 suitesparse RUN make -C /slambench2 brisk RUN make -C /slambench2 ceres # Build slambench2 ################################################################## RUN make -C /slambench2 slambench RUN make -C /slambench2 slambench APPS=okvis RUN make -C /slambench2 slambench APPS=ptam RUN make -C /slambench2 slambench APPS=orbslam2 RUN make -C /slambench2 slambench APPS=kfusion RUN make -C /slambench2 slambench APPS=monoslam RUN make -C /slambench2 slambench APPS=lsdslam RUN make -C /slambench2 slambench APPS=efusion # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/fedora-25.docker ================================================ FROM fedora:25 # Dependencies ################################################################## RUN dnf install -y emacs gtk2-devel vtk-devel cmake make git mercurial wget unzip gcc gcc-c++ lapack blas lapack-devel blas-devel findutils cvs glut-devel glew-devel boost-devel glog-devel gflags-devel libXmu-devel libyaml libyaml-devel yaml-cpp-devel tar # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 RUN make -C /slambench2 cvd RUN make -C /slambench2 flann RUN make -C /slambench2 freeimage RUN make -C /slambench2 g2o RUN make -C /slambench2 gvars RUN make -C /slambench2 opencv RUN make -C /slambench2 opengv RUN make -C /slambench2 opentuner RUN make -C /slambench2 pangolin RUN make -C /slambench2 pcl RUN make -C /slambench2 suitesparse RUN make -C /slambench2 brisk RUN make -C /slambench2 ceres # Build slambench2 ################################################################## RUN make -C /slambench2 slambench RUN make -C /slambench2 slambench APPS=okvis RUN make -C /slambench2 slambench APPS=ptam RUN make -C /slambench2 slambench APPS=orbslam2 RUN make -C /slambench2 slambench APPS=kfusion RUN make -C /slambench2 slambench APPS=monoslam RUN make -C /slambench2 slambench APPS=lsdslam RUN make -C /slambench2 slambench APPS=efusion # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/fedora-26.docker ================================================ FROM fedora:26 # Dependencies ################################################################## RUN dnf install -y emacs gtk2-devel vtk-devel cmake make git mercurial wget unzip gcc gcc-c++ lapack blas lapack-devel blas-devel findutils cvs glut-devel glew-devel boost-devel glog-devel gflags-devel libXmu-devel libyaml libyaml-devel yaml-cpp-devel tar # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 RUN make -C /slambench2 cvd RUN make -C /slambench2 flann RUN make -C /slambench2 freeimage RUN make -C /slambench2 g2o RUN make -C /slambench2 gvars RUN make -C /slambench2 opencv RUN make -C /slambench2 opengv RUN make -C /slambench2 opentuner RUN make -C /slambench2 pangolin RUN make -C /slambench2 pcl RUN make -C /slambench2 suitesparse RUN make -C /slambench2 brisk RUN make -C /slambench2 ceres # Build slambench2 ################################################################## RUN make -C /slambench2 slambench RUN make -C /slambench2 slambench APPS=okvis RUN make -C /slambench2 slambench APPS=ptam RUN make -C /slambench2 slambench APPS=orbslam2 RUN make -C /slambench2 slambench APPS=kfusion RUN make -C /slambench2 slambench APPS=monoslam RUN make -C /slambench2 slambench APPS=lsdslam RUN make -C /slambench2 slambench APPS=efusion # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/github.docker ================================================ FROM bbodin/slambench:travis-deps # Copy ################################################################## COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench SBQUIET=1 RUN make -C /slambench2 algorithms SBQUIET=1 RUN make -C /slambench2 slambench SBQUIET=1 APPS=all RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam SBQUIET=1 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-cpp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/run_cuda.sh ================================================ #!/bin/sh #version_gt() { test "$(echo "$@" | tr " " "\n" | sort -V | tail -n 1)" = "$1"; } #docker_version=$(docker version | grep 'Client version' | awk '{split($0,a,":"); print a[2]}' | tr -d ' ') # Docker 1.3.0 or later is required for --device #if test $# -lt 1; then # Get the latest opengl-nvidia build # and start with an interactive terminal enabled # args="-i -t $(docker images | grep ^opengl-nvidia | head -n 1 | awk '{ print $1":"$2 }')" #else # Use this script with derived images, and pass your 'docker run' args # args="$@" #fi echo "preparation" XSOCK=/tmp/.X11-unix XAUTH=/tmp/.docker.xauth touch $XAUTH echo "XSOCK=${XSOCK}" echo "XAUTH=${XAUTH}" echo "xauth nlist $DISPLAY | sed -e 's/^..../ffff/' | xauth -f $XAUTH nmerge -" xauth nlist $DISPLAY | sed -e 's/^..../ffff/' | xauth -f $XAUTH nmerge - echo "Run" echo docker run \ --runtime=nvidia \ -v $XSOCK:$XSOCK:rw \ -v $XAUTH:$XAUTH:rw \ --device=/dev/nvidia0:/dev/nvidia0 \ --device=/dev/nvidiactl:/dev/nvidiactl \ --device=/dev/nvidia-uvm:/dev/nvidia-uvm \ -e DISPLAY=$DISPLAY \ -e XAUTHORITY=$XAUTH \ -it \ bbodin/slambench:cuda-ubuntu-16.04 $@ docker run \ --runtime=nvidia \ -v $XSOCK:$XSOCK:rw \ -v $XAUTH:$XAUTH:rw \ --device=/dev/nvidia0:/dev/nvidia0 \ --device=/dev/nvidiactl:/dev/nvidiactl \ --device=/dev/nvidia-uvm:/dev/nvidia-uvm \ -e DISPLAY=$DISPLAY \ -e XAUTHORITY=$XAUTH \ -it \ bbodin/slambench:cuda-ubuntu-16.04 $@ ================================================ FILE: docker/travis-deps.docker ================================================ FROM ubuntu:16.04 # Dependencies ################################################################## RUN apt-get -y update && apt-get -y install libvtk6.2 libvtk6-dev unzip libflann-dev wget mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev libyaml-cpp-dev libyaml-dev libproj-dev # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy deps building system only ################################################################## RUN mkdir -p /slambench2/framework COPY ./slambench2/Makefile /slambench2/Makefile COPY ./slambench2/framework/makefiles /slambench2/framework/makefiles RUN ls -alp /slambench2/ /slambench2/framework/makefiles # Build deps ################################################################## RUN make -C /slambench2 toon eigen3 cvd flann freeimage g2o gvars opencv opengv opentuner pangolin pcl suitesparse brisk ceres # Copy entire slambench folder ################################################################## #COPY ./slambench2 /slambench2 # Build slambench2 ################################################################## #RUN make -C /slambench2 slambench APPS=all # Test slambench2 ################################################################## #RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/ubuntu-14.04-bitbucket.docker ================================================ FROM bbodin/slambench:ubuntu-14.04-deps # Copy ################################################################## COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench RUN make -C /slambench2 slambench APPS=okvis RUN make -C /slambench2 slambench APPS=ptam RUN make -C /slambench2 slambench APPS=kfusion RUN make -C /slambench2 slambench APPS=monoslam RUN make -C /slambench2 slambench APPS=lsdslam RUN make -C /slambench2 slambench APPS=efusion RUN make -C /slambench2 slambench APPS=infinitam RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/ubuntu-14.04-deps.docker ================================================ FROM ubuntu:14.04 # Dependencies ################################################################## RUN apt-get -y update && apt-get -y install unzip libflann-dev wget libyaml-cpp-dev mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs gfortran libatlas-base-dev libgoogle-glog-dev libgtk2.0-dev libvtk5.8 libvtk5-dev RUN apt-get -y update && apt-get -y install dictionaries-common RUN /usr/share/debconf/fix_db.pl RUN dpkg-reconfigure dictionaries-common RUN apt-get -y update && apt-get -y install gtk2.0 # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 RUN make -C /slambench2 cvd RUN make -C /slambench2 flann RUN make -C /slambench2 freeimage RUN make -C /slambench2 g2o RUN make -C /slambench2 gvars RUN make -C /slambench2 opencv RUN make -C /slambench2 opengv RUN make -C /slambench2 opentuner RUN make -C /slambench2 pangolin RUN make -C /slambench2 pcl RUN make -C /slambench2 suitesparse RUN make -C /slambench2 brisk RUN make -C /slambench2 ceres # Keep only deps ################################################################## RUN rm -rf /slambench2/CMakeLists.txt /slambench2/benchmarks /slambench2/cmake /slambench2/interfaces /slambench2/frontends /slambench2/framework /slambench2/Makefile /slambench2/build RUN rm -rf /slambench2/deps/repos RUN rm -rf /slambench2/datasets RUN rm -rf /slambench2/install RUN rm -rf /slambench2/temp RUN ls /slambench2 ================================================ FILE: docker/ubuntu-14.04.docker ================================================ FROM ubuntu:14.04 # Dependencies ################################################################## RUN apt-get -y update && apt-get -y install unzip libflann-dev wget libyaml-cpp-dev mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs gfortran libatlas-base-dev libgoogle-glog-dev libgtk2.0-dev libvtk5.8 libvtk5-dev dictionaries-common RUN /usr/share/debconf/fix_db.pl RUN dpkg-reconfigure dictionaries-common RUN apt-get -y update && apt-get -y install gtk2.0 # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy deps building system only ################################################################## RUN mkdir -p /slambench2/framework COPY ./slambench2/Makefile /slambench2/Makefile COPY ./slambench2/framework/makefiles /slambench2/framework/makefiles RUN ls -alp /slambench2/ /slambench2/framework/makefiles # Build deps ################################################################## RUN make -C /slambench2 toon eigen3 cvd flann freeimage g2o gvars opencv opengv opentuner pangolin pcl suitesparse brisk ceres # Copy entire slambench folder ################################################################## COPY ./slambench2 /slambench2 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench APPS=all # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-openmp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/ubuntu-16.04.docker ================================================ FROM ubuntu:16.04 # Dependencies ################################################################## RUN apt-get -y update && apt-get -y install libvtk6.2 libvtk6-dev unzip libflann-dev wget mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev libyaml-cpp-dev libyaml-dev libproj-dev # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy deps building system only ################################################################## RUN mkdir -p /slambench2/framework COPY ./slambench2/Makefile /slambench2/Makefile COPY ./slambench2/framework/makefiles /slambench2/framework/makefiles RUN ls -alp /slambench2/ /slambench2/framework/makefiles # Build deps ################################################################## RUN make -C /slambench2 toon eigen3 cvd flann freeimage g2o gvars opencv opengv opentuner pangolin pcl suitesparse brisk ceres # Copy entire slambench folder ################################################################## COPY ./slambench2 /slambench2 # Build slambench2 ################################################################## RUN make -C /slambench2 slambench APPS=all # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: docker/ubuntu-16.10.docker ================================================ FROM ubuntu:16.10 # Dependencies ################################################################## RUN df -h RUN apt-get -y update # Dependencies RUN apt-get -y install libvtk6.3 libvtk6-dev unzip libflann-dev wget mercurial git gcc cmake python-numpy freeglut3 freeglut3-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev libxmu-dev libxi-dev libboost-all-dev cvs libgoogle-glog-dev libatlas-base-dev gfortran gtk2.0 libgtk2.0-dev l libyaml-dev # Prepare ################################################################## RUN git config --global user.email "you@example.com" RUN git config --global user.name "Your Name" # Copy ################################################################## RUN mkdir /slambench2 COPY ./slambench2/ /slambench2/ RUN ls /slambench2 # Build deps ################################################################## RUN make -C /slambench2 toon RUN make -C /slambench2 eigen3 RUN make -C /slambench2 cvd RUN make -C /slambench2 flann RUN make -C /slambench2 freeimage RUN make -C /slambench2 g2o RUN make -C /slambench2 gvars RUN make -C /slambench2 opencv RUN make -C /slambench2 opengv RUN make -C /slambench2 opentuner RUN make -C /slambench2 pangolin RUN make -C /slambench2 pcl RUN make -C /slambench2 suitesparse RUN make -C /slambench2 brisk RUN make -C /slambench2 ceres # Build slambench2 ################################################################## RUN make -C /slambench2 slambench RUN make -C /slambench2 slambench APPS=okvis RUN make -C /slambench2 slambench APPS=ptam RUN make -C /slambench2 slambench APPS=orbslam2 RUN make -C /slambench2 slambench APPS=kfusion RUN make -C /slambench2 slambench APPS=monoslam RUN make -C /slambench2 slambench APPS=lsdslam RUN make -C /slambench2 slambench APPS=efusion # Test slambench2 ################################################################## RUN make -C /slambench2 datasets/ICL_NUIM/living_room_traj2_loop.slam RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-cpp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-openmp-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libkfusion-notoon-library.so -fl 30 -s 5 -d 1.71,2.4,1.152 -z 8 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/liblsdslam-cpp-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libinfinitam-cuda-library.so -fl 30 RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libmonoslam-sequential-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libptam-original_mp-library.so -fl 30 #RUN cd /slambench2 && ./build/bin/benchmark_loader -i ./datasets/ICL_NUIM/living_room_traj2_loop.slam -load ./build/lib/libokvis-original-library.so -fl 30 ================================================ FILE: framework/CMakeLists.txt ================================================ ####################################################### # This file is the CMAKE script for SLAMBench Libraries ####################################################### cmake_minimum_required(VERSION 3.0) project(slambench) # Find most common packages ####################################################### find_package(GLUT) find_package(OpenGL) find_package(Eigen3 REQUIRED) find_package(PAPI) #### BUILD SLAMBENCH AND TOOLS #### add_subdirectory(shared) # SLAMBench Shared library IF(NOT ANDROID) add_subdirectory(tools) # SLAMBench Tools ENDIF() ================================================ FILE: framework/makefiles/README.md ================================================ # SLAMBench Dependency System # ## Description ## The idea is to maximise the chance of a good build, by selection the best cocktail of libraries. Name | repository | Commit / Tag / Version | Date | Why | Notes ------------- | -------------------------------------------------------------- | ---------------------------------------- | ------------ | -------------------- | --------- BRISK | https://www.doc.ic.ac.uk/~sleutene/software/brisk-2.0.3.zip | 2.0.3 | N/A | OKVIS | - CERES | https://ceres-solver.googlesource.com/ceres-solver | 7c57de5080c9f5a4f067e2d20b5f33bad5b1ade6 | ? | OKVIS | - CVD | https://github.com/edrosten/libcvd | d190474150d4695e4c957863c5121c7eb79615d9 | | PTAM | - EIGEN | http://bitbucket.org/eigen/eigen | 3.2 | | SLAMBench | - FLANN | https://github.com/mariusmuja/flann | 06a49513138009d19a1f4e0ace67fbff13270c69 | 5 Aug 2016 | PCL | - FREEIMAGE | https://github.com/mikesart/freeimage.git | d49fb3982c1cb7826bc10edaf5c0ac4d9104660f | | | + Patches FREENECT | https://github.com/OpenKinect/libfreenect.git | 83e57e1318cc64c9aabac481b9e330acc1914a23 | | SLAMBench | - G2O | https://github.com/RainerKuemmerle/g2o | 1b118ac2ed2055c4016c3b7cbd710225ed1651af | 12 Jan 2017 | LSDSLAM | - GCC | git://gcc.gnu.org/git/gcc.git | gcc-5_3_0-release | | | + ec1cc0263f156f70693a62cf17b254a0029f4852 GVARS | https://github.com/edrosten/gvars | fc58c500c9d8f8713fb87a98cf7fb6be1db3295f | | PTAM | - LIBOPENCL-STUB | https://github.com/krrishnarraj/libopencl-stub.git | b4f84459e3a3a14d6a18b5dabe0a6ae9cbef709e | | | - LIBUSB | https://github.com/libusb/libusb.git | 8ddd8d994df6e367603266630bc2fe83b9cad868 | | OpenNI | - OPENCV | https://github.com/Itseez/opencv.git | 2c9547e | | LSDSLAM | + Patches OPENGV | https://github.com/laurentkneip/opengv | cc32b16281aa6eab67cb28a61cf87a2a5c2b0961 | | | - OPENNI 1.5 | https://github.com/OpenNI/OpenNI.git | 54e899c492f69aa8fa3e133fdd7d6b468f017b99 | | SLAMBench | + Patches OPENNI2 | https://github.com/occipital/OpenNI2/ | 1fce8edffab43c4a4cf201cff86f415b07a2d37f | | SLAMBench | - OPENTUNER | https://github.com/jansel/opentuner.git | master... | | DSE | - PANGOLIN | https://github.com/stevenlovegrove/Pangolin.git | 8b8b7b96adcf58ac2755dedd3f681fc512385af0 | | GUI, EFUSION | - PCL | https://github.com/PointCloudLibrary/pcl.git | 6fb1b65d3099a915255b070269b1ac78ed384921 | | OR | - SensorKinect | https://github.com/avin2/SensorKinect.git | 15f1975d5e50d84ca06ff784f83f8b7836749a7b | | OpenNI | - SUITESPARSE | https://github.com/jluttine/suitesparse.git | v4.3.1 | | EFUSION | - TOON | https://github.com/edrosten/TooN.git | 92241416d2a4874fd2334e08a5d417dfea6a1a3f | 21 Sep 2015 | KFUSION, PTAM, CVD | - ================================================ FILE: framework/makefiles/brisk.make ================================================ BRISK_INCLUDE_DIR=${DEPS_DIR}/brisk/include BRISK_DIR=${DEPS_DIR}/brisk/lib/CMake/brisk/ ${REPOS_DIR}/brisk : mkdir ${REPOS_DIR} -p rm $@ -rf mkdir $@ -p cd $@ ; wget --no-check-certificate https://www.doc.ic.ac.uk/~sleutene/software/brisk-2.0.5.zip cd $@ ; unzip *.zip ; rm brisk-2.0.5.zip; sed -i.bak "s/[#]include [<]algo/#include\\n#include benchmarks/$@/CMakeLists.txt") print("\t@echo \"explore_implementations ( $@ src/* )\" >> benchmarks/$@/CMakeLists.txt") previous = name list_str = " ".join(set([algoname for algoname in data.keys()])) print("") print(".PHONY: %s" % list_str) print("algorithms : %s" % list_str) print("") print("benchmarks_status:") for algorithm_token, details in data.items(): echo("************ Check-in %s in %s" % (algorithm_token, details["path"])) print("\t@if [ -d %s ] ; then git -C %s diff; fi" % (details["path"], details["path"])) ================================================ FILE: framework/makefiles/download_datasets.py ================================================ import sys DATASET_DIR = "datasets/" fd = open(sys.argv[1]) data =fd.read() fd.close() def echo(str="", echoargs = ""): print("\t@echo " + echoargs + " \"" + str + "\"") print("datasets:") echo("The following datasets are built on your system and available for use:") print("\t@for f in `find datasets/ | grep [.]slam` ; do echo \" - $$f\" ; done") echo() echo("Here is a list of the datasets available.") echo("If you are using any of the following datasets, ${BoldRed}please refer to their respective publications${ColorOff}:", "-e") echo("\t- TUM RGB-D SLAM dataset [Sturm et al, IROS'12]: https://vision.in.tum.de/data/datasets/rgbd-dataset") echo("\t- ICL-NUIM dataset [Handa et al, ICRA'14]: https://www.doc.ic.ac.uk/~ahanda/VaFRIC/iclnuim.html") echo("\t- EuRoC MAV Dataset [Burri et al, IJJR'16]: https://projects.asl.ethz.ch/datasets/doku.php") echo("\t- SVO sample dataset [Forster et al, ICRA 2014]: https://github.com/uzh-rpg/rpg_svo") echo("\t- Bonn RGB-D Dynamic Dataset [Palazzolo et al, IROS'19]: http://www.ipb.uni-bonn.de/data/rgbd-dynamic-dataset/") echo("\t- UZH-FPV Drone Racing Dataset [Delmerico et al, ICRA'19]: http://rpg.ifi.uzh.ch/uzh-fpv.html") echo("\t- OpenLORIS-Scene datasets [Shi et al, ICRA'20]: https://lifelong-robotic-vision.github.io/dataset/scene") echo("=================================================================================================================") echo() echo("=================================================================================================================") echo("SLAMBench integrates tools to automatically generate files compatible with SLAMBench from existing datasets.") echo("SLAMBench cannot download the OpenLORIS data for you. Please download the data manually (*-package.tar) to ./datasets/OpenLORIS/") echo("For details, please visit: https://lifelong-robotic-vision.github.io/dataset/scene") echo() targets = [] dataset_name = "" for line in data.split("\n"): if '#' in line or len(line) < 2: continue items = line.split(":") if "Dataset" in items: dataset_name = items.pop(1) continue items = line.split(";") dataset_tag = items.pop(0) dataset_description = items.pop(0) # here need another target echo("\t### " + dataset_name + " " + dataset_description + " ###") for dataset_file in items: echo("\t make ./" + DATASET_DIR + dataset_name + "/" + dataset_file) echo() echo("\tDatasets with a ROS option: TUM") echo("\t Use the ${BoldGreen}use_rosbag${ColorOff} option to build a dataset from a ROS bag:") echo("\t make ./datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam use_rosbag") echo() # at the end need to include dataset-utils.makefile # make datasettag list # make datasettag.all ================================================ FILE: framework/makefiles/eigen3.make ================================================ EIGEN3_INCLUDE_DIR=${DEPS_DIR}/eigen3/include/eigen3 ANDROID_EIGEN3_INCLUDE_DIR=${ANDROID_DEPS_DIR}/eigen3/include/eigen3 ${REPOS_DIR}/eigen3 : mkdir ${REPOS_DIR}/ -p rm ${REPOS_DIR}/eigen3 -rf cd ${REPOS_DIR}/ && git clone --depth 1 --branch 3.2.10 https://gitlab.com/libeigen/eigen.git eigen3 ${DEPS_DIR}/eigen3 : ${REPOS_DIR}/eigen3 cd ${REPOS_DIR}/eigen3 && mkdir build_dir -p cd ${REPOS_DIR}/eigen3 && rm build_dir/* -rf cd ${REPOS_DIR}/eigen3/build_dir && cmake .. -DBUILD_SHARED_LIBS=OFF -DCMAKE_BUILD_TYPE=Release "-DCMAKE_INSTALL_PREFIX:PATH=$@" +cd ${REPOS_DIR}/eigen3/build_dir && make mkdir ${DEPS_DIR}/eigen3 -p cd ${REPOS_DIR}/eigen3/build_dir && make install ${ANDROID_DEPS_DIR}/eigen3 : ${REPOS_DIR}/eigen3 mkdir $@/include/eigen3 -p cp -rf ${REPOS_DIR}/eigen3/Eigen $@/include/eigen3 eigen : eigen3 eigen3 : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi android-eigen3 : ${ANDROID_DEPS_DIR}/eigen3 .PHONY: eigen eigen3 android-eigen3 ================================================ FILE: framework/makefiles/flann.make ================================================ FLANN_INCLUDE_DIR=${DEPS_DIR}/flann/include FLANN_LIBRARY=${DEPS_DIR}/flann/lib/libflann.so #include eigen3 # not required ${REPOS_DIR}/flann : mkdir -p ${REPOS_DIR} rm -rf ${REPOS_DIR}/flann cd ${REPOS_DIR} ; git clone https://github.com/mariusmuja/flann.git flann cd ${REPOS_DIR}/flann && git checkout 06a49513138009d19a1f4e0ace67fbff13270c69 touch ${REPOS_DIR}/flann/src/cpp/empty.cpp sed -e "/add_library(flann_cpp SHARED/ s/\"\"/empty.cpp/" -e "/add_library(flann SHARED/ s/\"\"/empty.cpp/" -i ${REPOS_DIR}/flann/src/cpp/CMakeLists.txt ${DEPS_DIR}/flann : ${REPOS_DIR}/flann mkdir ${REPOS_DIR}/flann/build -p rm ${REPOS_DIR}/flann/buid/* -rf cd ${REPOS_DIR}/flann/build && cmake .. "-DCMAKE_INSTALL_PREFIX:PATH=$@" -DBUILD_MATLAB_BINDINGS=FALSE -DBUILD_PYTHON_BINDINGS=FALSE -DBUILD_EXAMPLES=FALSE -DBUILD_TESTS=FALSE -DBUILD_DOC=FALSE +cd ${REPOS_DIR}/flann/build && make mkdir -p $@ cd ${REPOS_DIR}/flann/build && make install flann : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: flann ================================================ FILE: framework/makefiles/freeimage.make ================================================ FREEIMAGE_INCLUDE_PATH=${DEPS_DIR}/freeimage/include FREEIMAGE_DYNAMIC_LIBRARY=${DEPS_DIR}/freeimage/lib/libfreeimage.so FREEIMAGE_URL=http://downloads.sourceforge.net/freeimage/FreeImage3180.zip ${REPOS_DIR}/FreeImage : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/FreeImage -rf cd ${REPOS_DIR} && wget ${FREEIMAGE_URL} && unzip FreeImage3180.zip && rm FreeImage3180.zip sed -i.bak "s/-o root -g root//" ${REPOS_DIR}/FreeImage/Makefile.gnu sed -i.bak "s/-Wno-ctor-dtor-privacy/-w/" ${REPOS_DIR}/FreeImage/Makefile.gnu sed -i.bak "s/defined._ARM_./defined\(_ARM_\) or defined\(__arm__\)/" ${REPOS_DIR}/FreeImage/Source/LibRawLite/libraw/libraw_types.h cd ${REPOS_DIR}/FreeImage && git apply ${ROOT_DIR}/framework/patchs/freeimage.patch ${DEPS_DIR}/freeimage : ${REPOS_DIR}/FreeImage +cd ${REPOS_DIR}/FreeImage && make DESTDIR=$@ mkdir -p $@ cd ${REPOS_DIR}/FreeImage && make install DESTDIR=$@ INCDIR=$@/include INSTALLDIR=$@/lib freeimage : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: freeimage ================================================ FILE: framework/makefiles/g2o.make ================================================ G2O_DIR=${DEPS_DIR}/g2o ANDROID_G2O_DIR=${ANDROID_DEPS_DIR} ${SUITE_SPARSE_ROOT}/lib/libcxsparse.a : suitesparse echo "please use make suitesparse" ${REPOS_DIR}/g2o : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/g2o -rf git clone "https://github.com/RainerKuemmerle/g2o" ${REPOS_DIR}/g2o cd ${REPOS_DIR}/g2o && git checkout 1b118ac2ed2055c4016c3b7cbd710225ed1651af ${DEPS_DIR}/g2o : ${REPOS_DIR}/g2o suitesparse eigen3 cd ${REPOS_DIR}/g2o && mkdir build -p rm ${REPOS_DIR}/g2o/build/* -rf cd ${REPOS_DIR}/g2o/build && cmake .. "-DCMAKE_INSTALL_PREFIX:PATH=$@" \ -DCHOLMOD_LIBRARY=${SUITE_SPARSE_ROOT}/lib/libcholmod.a -DCHOLMOD_FOUND=TRUE -DCHOLMOD_INCLUDE_DIR=${SUITE_SPARSE_ROOT}/include/ -DCHOLMOD_LIBRARIES=${SUITE_SPARSE_ROOT}/lib \ -DCSPARSE_INCLUDE_DIR=${SUITE_SPARSE_ROOT}/include/ -DCSPARSE_LIBRARY=${SUITE_SPARSE_ROOT}/lib/libcxsparse.a\ -DEIGEN3_INCLUDE_DIR=${EIGEN3_INCLUDE_DIR} +cd ${REPOS_DIR}/g2o/build && make mkdir -p $@ cd ${REPOS_DIR}/g2o/build && make install ${ANDROID_DEPS_DIR}/g2o : ${REPOS_DIR}/g2o ${REPOS_DIR}/android-cmake # What about CHOLMOD and BLAS ? cd ${REPOS_DIR}/g2o && mkdir android-build -p rm ${REPOS_DIR}/g2o/android-build/* -rf cd ${REPOS_DIR}/g2o/android-build && cmake -DBUILD_SHARED_LIBS=OFF -D CMAKE_INSTALL_PREFIX=$(ANDROID_DEPS_DIR) -DCMAKE_TOOLCHAIN_FILE=${REPOS_DIR}/android-cmake/android.toolchain.cmake -DANDROID_NDK=${ANDROID_NDK} -DCMAKE_BUILD_TYPE=Release -DANDROID_ABI="armeabi-v7a with NEON" -DEIGEN3_INCLUDE_DIR="$(ANDROID_DEPS_DIR)/include/eigen3" -DEIGEN3_VERSION_OK=ON -DG2O_BUILD_EXAMPLES=off -DG2O_BUILD_APPS=off -DCSPARSE_INCLUDE_DIR=${REPOS_DIR}/suitesparse/CXSparse/Include .. +cd ${REPOS_DIR}/g2o/android-build && make cd ${REPOS_DIR}/g2o/android-build && make install g2o : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi android-g2o : ${ANDROID_DEPS_DIR}/g2o .PHONY: g2o android-g2o ================================================ FILE: framework/makefiles/gcc.make ================================================ GCC7_COMPILER=${DEPS_DIR}/gcc7/bin/c++ GCC5_COMPILER=${DEPS_DIR}/gcc5/bin/c++ GCC_REPOS=gcc GCC_BUILD_DIR=${DEPS_DIR}/build/gcc ${REPOS_DIR}/${GCC_REPOS} : mkdir -p ${REPOS_DIR} rm -rf ${REPOS_DIR}/${GCC_REPOS} cd ${REPOS_DIR} && git clone git://gcc.gnu.org/git/gcc.git ${GCC_REPOS} ${DEPS_DIR}/gcc5 : ${REPOS_DIR}/${GCC_REPOS} cd $^ && git checkout gcc-5_3_0-release cd $^ && git cherry-pick ec1cc0263f156f70693a62cf17b254a0029f4852 || true cd $^ && ./contrib/download_prerequisites mkdir -p ${GCC_BUILD_DIR}/objdir rm -rf ${GCC_BUILD_DIR}/objdir/* cd ${GCC_BUILD_DIR}/objdir && ${REPOS_DIR}/${GCC_REPOS}/configure --prefix=$@ --enable-languages=c,c++ --disable-multilib +cd ${GCC_BUILD_DIR}/objdir && make mkdir -p $@ cd ${GCC_BUILD_DIR}/objdir && make install ${DEPS_DIR}/gcc7 : ${REPOS_DIR}/${GCC_REPOS} cd $^ && git checkout gcc-7_2_0-release cd $^ && ./contrib/download_prerequisites mkdir -p ${GCC_BUILD_DIR}/objdir rm -rf ${GCC_BUILD_DIR}/objdir/* cd ${GCC_BUILD_DIR}/objdir && ${REPOS_DIR}/${GCC_REPOS}/configure --prefix=$@ --enable-languages=c,c++ --disable-multilib --disable-libsanitizer +cd ${GCC_BUILD_DIR}/objdir && make mkdir -p $@ cd ${GCC_BUILD_DIR}/objdir && make install gcc5: +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi gcc7: +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: gcc5 gcc7 ================================================ FILE: framework/makefiles/gvars.make ================================================ GVARS_INCLUDE_DIR=${DEPS_DIR}/gvars/include GVARS_LIBRARY=${DEPS_DIR}/gvars/lib/libGVars3.so ${REPOS_DIR}/gvars : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/gvars -rf git clone "https://github.com/edrosten/gvars" ${REPOS_DIR}/gvars cd ${REPOS_DIR}/gvars && git checkout fc58c500c9d8f8713fb87a98cf7fb6be1db3295f ${DEPS_DIR}/gvars: ${REPOS_DIR}/gvars toon cd ${REPOS_DIR}/gvars && ./configure --prefix=$@ CPPFLAGS="-I${DEPS_DIR}/toon/include -fPIC" +cd ${REPOS_DIR}/gvars && make mkdir -p $@ cd ${REPOS_DIR}/gvars && make install gvars : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: gvars ================================================ FILE: framework/makefiles/libopencl-stub.make ================================================ dependencies/libopencl-stub : ANDROID_OPENCL_ROOT_DIR=${ANDROID_DEPS_DIR}/libopencl-stub/ ANDROID_OPENCL_INCLUDE_DIR=${ANDROID_DEPS_DIR}/libopencl-stub/include ANDROID_OPENCL_LIBRARY=${ANDROID_DEPS_DIR}/libopencl-stub/obj/local/armeabi-v7a/libOpenCL.a PATCH_DIR=${ROOT_DIR}/framework/patchs/ ${REPOS_DIR}/libopencl-stub : mkdir -p ${REPOS_DIR}/ git clone https://github.com/krrishnarraj/libopencl-stub.git $@ cd $@ && git checkout b4f84459e3a3a14d6a18b5dabe0a6ae9cbef709e cd $@ && git apply ${PATCH_DIR}/libopencl-stub_SLAMBench.patch ${ANDROID_DEPS_DIR}/libopencl-stub: ${REPOS_DIR}/libopencl-stub mkdir -p ${ANDROID_DEPS_DIR}/libopencl-stub rm -rf ${ANDROID_DEPS_DIR}/libopencl-stub/* cd ${REPOS_DIR}/libopencl-stub && ${ANDROID_NDK}/ndk-build NDK_PROJECT_PATH=. APP_BUILD_SCRIPT=Android.mk NDK_APPLICATION_MK=Application.mk cp ${REPOS_DIR}/libopencl-stub/include ${ANDROID_DEPS_DIR}/libopencl-stub -rf cp ${REPOS_DIR}/libopencl-stub/obj ${ANDROID_DEPS_DIR}/libopencl-stub -rf android-libopencl-stub: ${ANDROID_DEPS_DIR}/libopencl-stub .PHONY: android-libopencl-stub ================================================ FILE: framework/makefiles/opencv.make ================================================ OPENCV_DIR=${DEPS_DIR}/opencv/share/OpenCV/ ANDROID_OPENCV_DIR=${ANDROID_DEPS_DIR}/opencv/share/OpenCV/ OPENCV_CONTRIB_MODULES_DIR=${REPOS_DIR}/opencv_contrib/modules ${REPOS_DIR}/opencv : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/opencv -rf git clone "https://github.com/opencv/opencv.git" ${REPOS_DIR}/opencv git clone "https://github.com/opencv/opencv_contrib.git" ${REPOS_DIR}/opencv_contrib cd ${REPOS_DIR}/opencv && git checkout 3.4.3 cd ${REPOS_DIR}/opencv_contrib && git checkout 3.4.3 # TODO: update opencv flags for opencv 3 ${DEPS_DIR}/opencv : ${REPOS_DIR}/opencv cd ${REPOS_DIR}/opencv && mkdir build_dir -p cd ${REPOS_DIR}/opencv && rm build_dir/* -rf cd ${REPOS_DIR}/opencv/build_dir && cmake -D CMAKE_BUILD_TYPE=RELEASE -D CMAKE_INSTALL_PREFIX=$@ -DCMAKE_CXX_FLAGS="-Wno-error=address" \ -DWITH_GSTREAMER=OFF -DWITH_FFMPEG=OFF -DBUILD_PERF_TESTS=OFF -D WITH_OPENCL=OFF -D BUILD_WITH_DEBUG_INFO=OFF -D WITH_1394=OFF \ -D BUILD_TESTS=OFF -D WITH_TBB=OFF -D WITH_V4L=OFF -D WITH_OPENGL=OFF -D BUILD_opencv_gpu=OFF \ -D BUILD_opencv_java=OFF -D WITH_CUDA=OFF -DWITH_GTK=ON -D BUILD_opencv_ml=ON -D BUILD_opencv_videostab=OFF \ -D BUILD_opencv_ts=OFF -D BUILD_opencv_photo=ON -D BUILD_opencv_video=ON -D BUILD_opencv_stitching=OFF -DOPENCV_EXTRA_MODULES_PATH=${OPENCV_CONTRIB_MODULES_DIR} -DENABLE_PRECOMPILED_HEADERS=OFF .. > ${REPOS_DIR}/opencv/build_dir/opencv_cmake.log cat ${REPOS_DIR}/opencv/build_dir/opencv_cmake.log +cd ${REPOS_DIR}/opencv/build_dir && make mkdir -p $@ cd ${REPOS_DIR}/opencv/build_dir && make install $(ANDROID_DEPS_DIR)/opencv : ${REPOS_DIR}/opencv ${REPOS_DIR}/android-cmake cd ${REPOS_DIR}/opencv && mkdir build_dir -p cd ${REPOS_DIR}/opencv && rm build_dir/* -rf cd ${REPOS_DIR}/opencv/build_dir && cmake -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=${REPOS_DIR}/android-cmake/android.toolchain.cmake -DANDROID_NDK=${ANDROID_NDK} -DCMAKE_BUILD_TYPE=Release -DANDROID_ABI="armeabi-v7a with NEON" -DWITH_GSTREAMER=OFF -DBUILD_PERF_TESTS=OFF -D WITH_OPENCL=OFF -D CMAKE_INSTALL_PREFIX=$(ANDROID_DEPS_DIR) -D BUILD_WITH_DEBUG_INFO=OFF -D WITH_1394=OFF -D BUILD_TESTS=OFF -D WITH_TBB=OFF -D WITH_V4L=OFF -D WITH_OPENGL=OFF -D BUILD_opencv_gpu=OFF -D BUILD_opencv_java=OFF -D WITH_CUDA=OFF -DWITH_GTK=OFF -D BUILD_opencv_videostab=OFF -D BUILD_opencv_ts=OFF -D BUILD_opencv_stitching=OFF .. +cd ${REPOS_DIR}/opencv/build_dir && make cd ${REPOS_DIR}/opencv/build_dir && make install opencv : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi android-opencv : ${ANDROID_DEPS_DIR}/opencv .PHONY: opencv android-opencv ================================================ FILE: framework/makefiles/opengv.make ================================================ OPENGV_INCLUDE_DIR=${DEPS_DIR}/opengv/include OPENGV_LIBRARY=${DEPS_DIR}/opengv/lib/libopengv.a ${REPOS_DIR}/opengv : mkdir -p ${REPOS_DIR} rm -rf ${REPOS_DIR}/opengv cd ${REPOS_DIR} ; git clone "https://github.com/laurentkneip/opengv" opengv cd $@ ; git checkout cc32b16281aa6eab67cb28a61cf87a2a5c2b0961 ${DEPS_DIR}/opengv : ${REPOS_DIR}/opengv eigen3 mkdir ${REPOS_DIR}/opengv/build -p rm ${REPOS_DIR}/opengv/build/* -rf cd ${REPOS_DIR}/opengv/build && cmake .. "-DCMAKE_INSTALL_PREFIX:PATH=$@" -DCMAKE_CXX_FLAGS="-w -O3 -std=c++11" -DEIGEN_VERSION_OK=3 -DEIGEN_INCLUDE_DIR=${EIGEN3_INCLUDE_DIR} +cd ${REPOS_DIR}/opengv/build && make mkdir -p $@ cd ${REPOS_DIR}/opengv/build && make install ifdef EIGEN3_INCLUDE_DIR opengv : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi else opengv : @echo "*** Error eigen not defined or not found" @echo "*** EIGEN_INCLUDE_DIR=${EIGEN3_INCLUDE_DIR}" @exit 1 endif .PHONY: opengv ================================================ FILE: framework/makefiles/openni.make ================================================ ########################################## COMMIT USED ################################################################# OPENNI2_REPOS=https://github.com/occipital/OpenNI2/ OPENNI2_COMMIT=1fce8edffab43c4a4cf201cff86f415b07a2d37f OPENNI15_REPOS=https://github.com/OpenNI/OpenNI.git OPENNI15_COMMIT=54e899c492f69aa8fa3e133fdd7d6b468f017b99 LIBUSB_REPOS=https://github.com/libusb/libusb.git LIBUSB_COMMIT=8ddd8d994df6e367603266630bc2fe83b9cad868 SENSORK_REPOS=https://github.com/avin2/SensorKinect.git SENSORK_COMMIT=15f1975d5e50d84ca06ff784f83f8b7836749a7b FREENECT_REPOS=https://github.com/OpenKinect/libfreenect.git FREENECT_COMMIT=83e57e1318cc64c9aabac481b9e330acc1914a23 ########################################## OPENNI 1.5 PART ################################################################# OPENNI_INCLUDE_DIR=${DEPS_DIR}/openni15/Include OPENNI_LIBRARY=${DEPS_DIR}/openni15/Lib/libOpenNI.so ${REPOS_DIR}/libusb : rm -rf $@ git clone ${LIBUSB_REPOS} $@ && cd $@ && git checkout ${LIBUSB_COMMIT} ${DEPS_DIR}/libusb : ${REPOS_DIR}/libusb cd ${REPOS_DIR}/libusb && ./autogen.sh --prefix=$@ cd ${REPOS_DIR}/libusb && make mkdir -p ${DEPS_DIR}/libusb rm -rf ${DEPS_DIR}/libusb/* cd ${REPOS_DIR}/libusb && make install libusb : @+if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi ${REPOS_DIR}/openni15 : mkdir -p ${REPOS_DIR} rm -rf ${REPOS_DIR}/openni15 cd ${REPOS_DIR} ; git clone ${OPENNI15_REPOS} $@ && cd $@ && git checkout ${OPENNI15_COMMIT} sed -i".bak" "s/equivalent/glh_equivalent/g" ${REPOS_DIR}/openni15/Samples/NiViewer/glh/glh_linear.h ${REPOS_DIR}/SensorKinect : mkdir -p ${REPOS_DIR} rm -rf ${REPOS_DIR}/SensorKinect cd ${REPOS_DIR} ; git clone ${SENSORK_REPOS} $@ && cd $@ && git checkout ${SENSORK_COMMIT} ${DEPS_DIR}/openni15 : ${REPOS_DIR}/openni15 ${DEPS_DIR}/libusb chmod +x ${REPOS_DIR}/openni15/Platform/Linux/CreateRedist/RedistMaker cd ${REPOS_DIR}/openni15/Platform/Linux/CreateRedist/ && ./RedistMaker rm -rf ${DEPS_DIR}/openni15 cd ${REPOS_DIR}/openni15 && tar xf ${REPOS_DIR}/openni15/Platform/Linux/CreateRedist/Final/*.tar.bz2 mv ${REPOS_DIR}/openni15/OpenNI-Bin-*/ ${DEPS_DIR}/openni15 cp ${REPOS_DIR}/openni15/Data/SamplesConfig.xml ${DEPS_DIR}/openni15/ ${DEPS_DIR}/SensorKinect : ${REPOS_DIR}/SensorKinect ${REPOS_DIR}/openni15 cd $ ${DEPS_BUILD_DIR}/pcl/build.log.tmp 2>&1 if cat ${DEPS_BUILD_DIR}/pcl/build.log.tmp | grep "Requires external library" ; then echo "Error with deps of PCL." ; exit 1 ; fi +cd ${DEPS_BUILD_DIR}/pcl/ && make mkdir -p $@ cd ${DEPS_BUILD_DIR}/pcl/ && make install pcl : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: pcl ================================================ FILE: framework/makefiles/sophus.make ================================================ Sophus_INCLUDE_DIR=${DEPS_DIR}/Sophus/include Sophus_INCLUDE_DIRS=${DEPS_DIR}/Sophus/include Sophus_DIR=${DEPS_DIR}/Sophus/share/sophus/cmake ${REPOS_DIR}/Sophus : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/Sophus -rf git clone "https://github.com/strasdat/Sophus.git" ${REPOS_DIR}/Sophus cd ${REPOS_DIR}/Sophus && git checkout b474f05f839c0f63c281aa4e7ece03145729a2cd ${DEPS_DIR}/Sophus : ${REPOS_DIR}/Sophus cd ${REPOS_DIR}/Sophus && mkdir build -p && rm build/* -rf cd ${REPOS_DIR}/Sophus/build && cmake .. "-DCMAKE_INSTALL_PREFIX=$@" -DCMAKE_BUILD_TYPE=Release cd ${REPOS_DIR}/Sophus/build && make -j2 mkdir -p $@ cd ${REPOS_DIR}/Sophus/build && make install Sophus : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: sophus ================================================ FILE: framework/makefiles/suitesparse.make ================================================ SUITE_SPARSE_ROOT=${DEPS_DIR}/suitesparse ${REPOS_DIR}/suitesparse : mkdir ${REPOS_DIR}/ -p rm ${REPOS_DIR}/suitesparse -rf cd ${REPOS_DIR}/ && git clone "https://github.com/jluttine/suitesparse.git" cd ${REPOS_DIR}/suitesparse && git checkout v4.3.1 ${REPOS_DIR}/suitesparse/CMakeLists.txt : ${REPOS_DIR}/suitesparse echo -e "cmake_minimum_required(VERSION 2.8)\nproject(suitesparse)\ninclude_directories(SuiteSparse_config/)\ninclude_directories(CXSparse/Include)\ninclude_directories(\"${ANDROID_NDK}/platforms/android-21/arch-arm/usr/include\")\nFILE(GLOB cxsparse_source CXSparse/Source/*.c)\nadd_library(cxsparse_di \$${cxsparse_source} )\nadd_library(cxsparse_dl \$${cxsparse_source} )\nadd_library(cxsparse_ci \$${cxsparse_source} )\nadd_library(cxsparse_cl \$${cxsparse_source} )\nSET_TARGET_PROPERTIES(cxsparse_di PROPERTIES COMPILE_FLAG \"\" )\nSET_TARGET_PROPERTIES(cxsparse_dl PROPERTIES COMPILE_FLAG \" -DCS_LONG\" )\nSET_TARGET_PROPERTIES(cxsparse_ci PROPERTIES COMPILE_FLAG \"-DCS_COMPLEX\" )\nSET_TARGET_PROPERTIES(cxsparse_cl PROPERTIES COMPILE_FLAG \" -DCS_LONG -DCS_COMPLEX\" )\nINSTALL(TARGETS cxsparse_di cxsparse_dl cxsparse_ci cxsparse_cl \n RUNTIME DESTINATION \$${CMAKE_INSTALL_PREFIX}/bin\n LIBRARY DESTINATION \$${CMAKE_INSTALL_PREFIX}/lib\n ARCHIVE DESTINATION \$${CMAKE_INSTALL_PREFIX}/lib\n)\n" > ${REPOS_DIR}/suitesparse/CMakeLists.txt ## Bruno : TODO : I'm not happy with this build method ... I'd rather like having a full cmake version of it... ## Harry: Suitesparse is not safe to parallel build :-( ${DEPS_DIR}/suitesparse : ${REPOS_DIR}/suitesparse ${REPOS_DIR}/suitesparse/CMakeLists.txt cd ${REPOS_DIR}/suitesparse/ && make rm $@ -rf mkdir $@/include -p mkdir $@/lib -p +cd ${REPOS_DIR}/suitesparse/ && make install INSTALL_LIB=$@/lib INSTALL_INCLUDE=$@/include ${ANDROID_DEPS_DIR}/suitesparse : ${REPOS_DIR}/suitesparse ${REPOS_DIR}/suitesparse/CMakeLists.txt ${REPOS_DIR}/android-cmake cd ${REPOS_DIR}/suitesparse && mkdir build_dir -p cd ${REPOS_DIR}/suitesparse && rm build_dir/* -rf cd ${REPOS_DIR}/suitesparse/build_dir && cmake -DBUILD_SHARED_LIBS=OFF -DCMAKE_TOOLCHAIN_FILE=${REPOS_DIR}/android-cmake/android.toolchain.cmake -DANDROID_NDK=${ANDROID_NDK} -DCMAKE_BUILD_TYPE=Release -DANDROID_ABI="armeabi-v7a with NEON" -D CMAKE_INSTALL_PREFIX=$(ANDROID_DEPS_DIR) .. +cd ${REPOS_DIR}/suitesparse/build_dir && make cd ${REPOS_DIR}/suitesparse/build_dir && make install suitesparse : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi android-suitesparse : ${ANDROID_DEPS_DIR}/suitesparse .PHONY: suitesparse android-suitesparse ================================================ FILE: framework/makefiles/toon.make ================================================ TOON_INCLUDE_DIR=${DEPS_DIR}/toon/include ANDROID_TOON_INCLUDE_DIR=${ANDROID_DEPS_DIR}/toon/include ${REPOS_DIR}/TooN : mkdir ${REPOS_DIR} -p rm ${REPOS_DIR}/TooN -rf git clone "https://github.com/edrosten/TooN.git" ${REPOS_DIR}/TooN cd ${REPOS_DIR}/TooN && git checkout 92241416d2a4874fd2334e08a5d417dfea6a1a3f ${DEPS_DIR}/toon: ${REPOS_DIR}/TooN cd ${REPOS_DIR}/TooN && ./configure --prefix=$@ mkdir -p $@ +cd ${REPOS_DIR}/TooN && make install ${ANDROID_DEPS_DIR}/toon: ${REPOS_DIR}/TooN mkdir -p $@ cd ${REPOS_DIR}/TooN && ./configure --prefix=$@ --disable-lapack --enable-typeof=decltype +cd ${REPOS_DIR}/TooN && make install android-toon: ${ANDROID_DEPS_DIR}/toon toon : +if [ ! -d ${DEPS_DIR}/$@ ] ; then make ${DEPS_DIR}/$@ ; else echo "$@ skipped."; fi .PHONY: toon android-toon ================================================ FILE: framework/patchs/OpenNI2_SLAMBench.patch ================================================ From 24cca203f2e4e1de89fb858b7b018d86abb99c8a Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Tue, 26 Apr 2016 14:58:30 +0100 Subject: [PATCH] test --- Android.mk | 12 +++++++----- Application.mk | 3 +-- Include/OniPlatform.h | 2 ++ Packaging/ReleaseVersion.py | 4 ++-- Source/Core/OniContext.cpp | 15 ++++++--------- Source/Drivers/OniFile/DataRecords.cpp | 14 ++++++++++++++ ThirdParty/PSCommon/XnLib/Include/XnPlatform.h | 2 ++ ThirdParty/PSCommon/XnLib/Source/XnLogAndroidWriter.cpp | 2 +- 8 files changed, 35 insertions(+), 19 deletions(-) diff --git a/Android.mk b/Android.mk index 4e3e26b..c7ee11b 100644 --- a/Android.mk +++ b/Android.mk @@ -24,13 +24,15 @@ endif # Setup OpenNI2 local variables OPENNI2_CFLAGS := -O3 -ftree-vectorize -ffast-math -funroll-loops -fPIC -fvisibility=hidden -ifeq ($(ARCH_ARM_HAVE_ARMV7A),true) - OPENNI2_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -endif -ifeq ($(ARCH_ARM_HAVE_NEON),true) - OPENNI2_CFLAGS += -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions +ifeq ($(TARGET_ARCH),arm64) + OPENNI2_CFLAGS += -march=armv8-a -DHAVE_NEON=1 -flax-vector-conversions +else +ifeq ($(TARGET_ARCH),arm) + OPENNI2_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions endif +endif + # Recurse through all subdirs include $(call all-subdir-makefiles) diff --git a/Application.mk b/Application.mk index 9c7ff56..67982a6 100644 --- a/Application.mk +++ b/Application.mk @@ -21,5 +21,4 @@ APP_PLATFORM := android-9 # Use ARM v7a instruction set -APP_ABI := armeabi-v7a -ARCH_ARM_HAVE_ARMV7A := true \ No newline at end of file +APP_ABI := armeabi-v7a arm64-v8a diff --git a/Include/OniPlatform.h b/Include/OniPlatform.h index 602b4ba..6b1d7ef 100644 --- a/Include/OniPlatform.h +++ b/Include/OniPlatform.h @@ -37,6 +37,8 @@ # include "Win32/OniPlatformWin32.h" #elif defined (ANDROID) && defined (__arm__) # include "Android-Arm/OniPlatformAndroid-Arm.h" +#elif defined (ANDROID) && defined (__aarch64__) +# include "Android-Arm/OniPlatformAndroid-Arm.h" #elif (__linux__ && (i386 || __x86_64__)) # include "Linux-x86/OniPlatformLinux-x86.h" #elif (__linux__ && __arm__) diff --git a/Packaging/ReleaseVersion.py b/Packaging/ReleaseVersion.py index e2fdf5f..4413e6a 100755 --- a/Packaging/ReleaseVersion.py +++ b/Packaging/ReleaseVersion.py @@ -113,14 +113,14 @@ if plat == 'android': os.symlink('../../../', buildDir + '/jni/OpenNI2') shutil.copy('../Android.mk', buildDir + '/jni') shutil.copy('../Application.mk', buildDir + '/jni') - rc = subprocess.call([ ndkDir + '/ndk-build', '-C', buildDir, '-j8' ]) + rc = subprocess.call([ ndkDir + '/ndk-build', '-C', buildDir, '-j1' ]) if rc != 0: print 'Build failed!' sys.exit(3) finalFile = finalDir + '/' + outputDir + '.tar' - shutil.move(buildDir + '/libs/armeabi-v7a', outputDir) + shutil.move(buildDir + '/libs/', outputDir) # add config files shutil.copy('../Config/OpenNI.ini', outputDir) diff --git a/Source/Core/OniContext.cpp b/Source/Core/OniContext.cpp index 153c7c6..cf13851 100644 --- a/Source/Core/OniContext.cpp +++ b/Source/Core/OniContext.cpp @@ -23,8 +23,8 @@ #include #include -static const char* ONI_CONFIGURATION_FILE = "OpenNI.ini"; -static const char* ONI_DEFAULT_DRIVERS_REPOSITORY = "OpenNI2" XN_FILE_DIR_SEP "Drivers"; +static const char* ONI_CONFIGURATION_FILE = "/data/ni/OpenNI.ini"; +static const char* ONI_DEFAULT_DRIVERS_REPOSITORY = "/data/ni/"; #define XN_MASK_ONI_CONTEXT "OniContext" @@ -84,15 +84,12 @@ OniStatus Context::initialize() XnBool configurationFileExists = FALSE; // Search the module directory for OpenNI.ini. - xnOSStrCopy(strOniConfigurationFile, strBaseDir, XN_FILE_MAX_PATH); - rc = xnOSAppendFilePath(strOniConfigurationFile, ONI_CONFIGURATION_FILE, XN_FILE_MAX_PATH); - if (rc == XN_STATUS_OK) - { - xnOSDoesFileExist(strOniConfigurationFile, &configurationFileExists); - } + xnOSStrCopy(strOniConfigurationFile, ONI_CONFIGURATION_FILE, XN_FILE_MAX_PATH); + xnOSDoesFileExist(strOniConfigurationFile, &configurationFileExists); + #ifdef ONI_PLATFORM_ANDROID_OS - xnLogSetMaskMinSeverity(XN_LOG_MASK_ALL, (XnLogSeverity)0); + xnLogSetMaskMinSeverity(XN_LOG_MASK_ALL, (XnLogSeverity)3); xnLogSetAndroidOutput(TRUE); #endif diff --git a/Source/Drivers/OniFile/DataRecords.cpp b/Source/Drivers/OniFile/DataRecords.cpp index bffc7e6..17bad91 100644 --- a/Source/Drivers/OniFile/DataRecords.cpp +++ b/Source/Drivers/OniFile/DataRecords.cpp @@ -667,6 +667,8 @@ XnStatus GeneralPropRecord::Decode() XnUInt8* pData = const_cast(GetReadPos()); #if (XN_PLATFORM == XN_PLATFORM_LINUX_ARM || XN_PLATFORM == XN_PLATFORM_ARC || XN_PLATFORM == XN_PLATFORM_ANDROID_ARM) + +#if __arm__ // under ARM we have some alignment issues. Move this buffer so it will be aligned. XnUInt32 nAlignFix = XN_DEFAULT_MEM_ALIGN - ((XnUInt32)pData % XN_DEFAULT_MEM_ALIGN); if (nAlignFix != 0) @@ -674,6 +676,18 @@ XnStatus GeneralPropRecord::Decode() xnOSMemMove(pData + nAlignFix, pData, m_nPropDataSize); pData += nAlignFix; } +#elif __aarch64__ + // under ARM we have some alignment issues. Move this buffer so it will be aligned. + XnUInt64 nAlignFix = XN_DEFAULT_MEM_ALIGN - ((XnUInt64)pData % XN_DEFAULT_MEM_ALIGN); + if (nAlignFix != 0) + { + xnOSMemMove(pData + nAlignFix, pData, m_nPropDataSize); + pData += nAlignFix; + } +#else +#error "Unsupported ARM platform" +#endif + #endif m_pPropData = pData; diff --git a/ThirdParty/PSCommon/XnLib/Include/XnPlatform.h b/ThirdParty/PSCommon/XnLib/Include/XnPlatform.h index 07e8192..1abfc71 100644 --- a/ThirdParty/PSCommon/XnLib/Include/XnPlatform.h +++ b/ThirdParty/PSCommon/XnLib/Include/XnPlatform.h @@ -49,6 +49,8 @@ #include "Win32/XnPlatformWin32.h" #elif defined (ANDROID) && defined (__arm__) #include "Android-Arm/XnPlatformAndroid-Arm.h" +#elif defined (ANDROID) && defined (__aarch64__) +#include "Android-Arm/XnPlatformAndroid-Arm.h" #elif (__linux__ && (i386 || __x86_64__)) #include "Linux-x86/XnPlatformLinux-x86.h" #elif (__linux__ && __arm__) diff --git a/ThirdParty/PSCommon/XnLib/Source/XnLogAndroidWriter.cpp b/ThirdParty/PSCommon/XnLib/Source/XnLogAndroidWriter.cpp index 6c9b6c1..32b27b7 100644 --- a/ThirdParty/PSCommon/XnLib/Source/XnLogAndroidWriter.cpp +++ b/ThirdParty/PSCommon/XnLib/Source/XnLogAndroidWriter.cpp @@ -58,7 +58,7 @@ void XnLogAndroidWriter::WriteEntry(const XnLogEntry* pEntry) #ifdef XN_PLATFORM_ANDROID_OS ALOGE("OpenNI2: %s\n", pEntry->strMessage); #else - __android_log_print(OpenNISeverityToAndroid(pEntry->nSeverity), "OpenNI", pEntry->strMessage); + __android_log_print(OpenNISeverityToAndroid(pEntry->nSeverity), "OpenNI", "%s", pEntry->strMessage); #endif } -- 2.4.11 ================================================ FILE: framework/patchs/OpenNI_SLAMBench.patch ================================================ From 1e72c95f8eccb42e1b81330c5428d64bac4dedba Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Sun, 7 Jun 2015 14:08:10 +0100 Subject: [PATCH 1/2] temp fix --- Platform/Android/Samples/SamplesAssistant/jni/Android.mk | 2 +- Platform/Android/jni/Application.mk | 2 +- Platform/Android/jni/OpenNI.jni/Android.mk | 2 +- Platform/Android/jni/OpenNI/Android.mk | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Platform/Android/Samples/SamplesAssistant/jni/Android.mk b/Platform/Android/Samples/SamplesAssistant/jni/Android.mk index e4b980d..9515e8d 100644 --- a/Platform/Android/Samples/SamplesAssistant/jni/Android.mk +++ b/Platform/Android/Samples/SamplesAssistant/jni/Android.mk @@ -25,7 +25,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS:= -fvisibility=hidden -DXN_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_LDLIBS := -llog LOCAL_LDLIBS += $(OPENNI_DIR)/Platform/Android/libs/armeabi-v7a/libOpenNI.so diff --git a/Platform/Android/jni/Application.mk b/Platform/Android/jni/Application.mk index 6d2da24..4f04cd6 100644 --- a/Platform/Android/jni/Application.mk +++ b/Platform/Android/jni/Application.mk @@ -10,7 +10,7 @@ APP_CFLAGS := -O3 -ftree-vectorize -ffast-math -funroll-loops APP_CFLAGS += -fPIC ifeq ($(APP_ABI),armeabi-v7a) - APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfp=vfpv3-d16 -mfpu=vfp + APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp # optionally add NEON to compilation flags. # to activate, run: "ndk-build USE_NEON=1" diff --git a/Platform/Android/jni/OpenNI.jni/Android.mk b/Platform/Android/jni/OpenNI.jni/Android.mk index 30b332c..f79566f 100644 --- a/Platform/Android/jni/OpenNI.jni/Android.mk +++ b/Platform/Android/jni/OpenNI.jni/Android.mk @@ -22,7 +22,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS:= -fvisibility=hidden -DXN_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_LDLIBS := -llog diff --git a/Platform/Android/jni/OpenNI/Android.mk b/Platform/Android/jni/OpenNI/Android.mk index 06acac6..b1b36e7 100644 --- a/Platform/Android/jni/OpenNI/Android.mk +++ b/Platform/Android/jni/OpenNI/Android.mk @@ -28,7 +28,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS:= -fvisibility=hidden -DXN_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_EXPORT_C_INCLUDES := $(LOCAL_PATH)/../../../../Include LOCAL_SHARED_LIBRARIES := libusb -- 2.4.11 From 3340ca042133bcf5e747f13278d2c25bfdaacf0a Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Tue, 26 Apr 2016 14:31:00 +0100 Subject: [PATCH 2/2] add aarch64 --- Include/XnPlatform.h | 6 ++++-- Platform/Android/jni/Application.mk | 16 +++++++--------- Source/Modules/Common/DataRecords.cpp | 15 +++++++++++++++ 3 files changed, 26 insertions(+), 11 deletions(-) diff --git a/Include/XnPlatform.h b/Include/XnPlatform.h index c5e2b9b..cfda4d8 100644 --- a/Include/XnPlatform.h +++ b/Include/XnPlatform.h @@ -61,11 +61,13 @@ #include "Win32/XnPlatformWin32.h" #elif defined(ANDROID) && defined(__arm__) - #include "Android-Arm/XnPlatformAndroid-Arm.h" +#include "Android-Arm/XnPlatformAndroid-Arm.h" +#elif defined(ANDROID) && defined(__aarch64__) +#include "Android-Arm/XnPlatformAndroid-Arm.h" #elif (linux && (i386 || __x86_64__)) #include "Linux-x86/XnPlatformLinux-x86.h" #elif (linux && __arm__) - #include "Linux-Arm/XnPlatformLinux-Arm.h" +#include "Linux-Arm/XnPlatformLinux-Arm.h" #elif _ARC #include "ARC/XnPlatformARC.h" #elif (__APPLE__) diff --git a/Platform/Android/jni/Application.mk b/Platform/Android/jni/Application.mk index 4f04cd6..2854ed5 100644 --- a/Platform/Android/jni/Application.mk +++ b/Platform/Android/jni/Application.mk @@ -3,20 +3,18 @@ APP_STL := gnustl_static # Android >= v2.3 APP_PLATFORM := android-9 -# Build ARMv7-A machine code. -APP_ABI := armeabi-v7a +# Build ARMv7-A and arm64-v8a machine code. +APP_ABI := arm64-v8a armeabi-v7a APP_CFLAGS := -O3 -ftree-vectorize -ffast-math -funroll-loops APP_CFLAGS += -fPIC -ifeq ($(APP_ABI),armeabi-v7a) - APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -# optionally add NEON to compilation flags. -# to activate, run: "ndk-build USE_NEON=1" -ifdef USE_NEON -$(call __ndk_info,Building everything with NEON support!) - APP_CFLAGS += -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions +ifeq ($(TARGET_ARCH),arm64) + APP_CFLAGS += -march=armv8-a -DHAVE_NEON=1 -flax-vector-conversions +else +ifeq ($(TARGET_ARCH),arm) + APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions endif endif diff --git a/Source/Modules/Common/DataRecords.cpp b/Source/Modules/Common/DataRecords.cpp index 37e8dcd..9306c28 100644 --- a/Source/Modules/Common/DataRecords.cpp +++ b/Source/Modules/Common/DataRecords.cpp @@ -656,6 +656,8 @@ XnStatus GeneralPropRecord::Decode() XnUInt8* pData = const_cast(GetReadPos()); #if (XN_PLATFORM == XN_PLATFORM_LINUX_ARM || XN_PLATFORM == XN_PLATFORM_ARC || XN_PLATFORM == XN_PLATFORM_ANDROID_ARM) + #if __arm__ + // under ARM we have some alignment issues. Move this buffer so it will be aligned. XnUInt32 nAlignFix = XN_DEFAULT_MEM_ALIGN - ((XnUInt32)pData % XN_DEFAULT_MEM_ALIGN); if (nAlignFix != 0) @@ -663,6 +665,19 @@ XnStatus GeneralPropRecord::Decode() xnOSMemMove(pData + nAlignFix, pData, m_nPropDataSize); pData += nAlignFix; } +#elif __aarch64__ + // under ARM we have some alignment issues. Move this buffer so it will be aligned. + XnUInt64 nAlignFix = XN_DEFAULT_MEM_ALIGN - ((XnUInt64)pData % XN_DEFAULT_MEM_ALIGN); + if (nAlignFix != 0) + { + xnOSMemMove(pData + nAlignFix, pData, m_nPropDataSize); + pData += nAlignFix; + } +#else +#error "Unsupported ARM platform" +#endif + + #endif m_pPropData = pData; -- 2.4.11 ================================================ FILE: framework/patchs/SensorKinect_SLAMBench.patch ================================================ From 334f203bfc5f609dd0726fd54e075cb7e1ad5b8b Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Sun, 7 Jun 2015 14:09:43 +0100 Subject: [PATCH 1/2] tmp patch --- Data/GlobalDefaultsKinect.ini | 189 +---------------------- Platform/Android/jni/Application.mk | 2 +- Platform/Android/jni/XnCore/Android.mk | 2 +- Platform/Android/jni/XnDDK/Android.mk | 2 +- Platform/Android/jni/XnDeviceFile/Android.mk | 2 +- Platform/Android/jni/XnDeviceSensorV2/Android.mk | 2 +- Platform/Android/jni/XnFormats/Android.mk | 2 +- 7 files changed, 7 insertions(+), 194 deletions(-) diff --git a/Data/GlobalDefaultsKinect.ini b/Data/GlobalDefaultsKinect.ini index fcfec6c..652c1a6 100644 --- a/Data/GlobalDefaultsKinect.ini +++ b/Data/GlobalDefaultsKinect.ini @@ -1,189 +1,2 @@ -[Core] -; 0 - Verbose, 1 - Info, 2 - Warning, 3 - Error (default) -LogLevel=3 -; leave empty for nothing (default). ALL - all masks -LogMasks=ALL -; 0 - No (default), 1 - Yes -;LogWriteToConsole=1 -; 0 - No (default), 1 - Yes -LogWriteToFile=1 -; 0 - No (default), 1 - Yes -;LogWriteLineInfo=0 -; leave empty for nothing (default). ALL - all masks -;DumpMasks= - -; Number of milliseconds between profiling logs. 0 - Off (default) -;ProfilingInterval=1000 - -;---------------- Server Default Configuration ------------------- -[Server] -; Use a server to access sensor. 0 - No (single application), 1 - Yes (multiple applications). Default: Arm - 0, other platforms - 1. Not supported on Mac. -;EnableMultiProcess=0 - -; When multi process is enabled, allows server and client running in different sessions. 0 - No (default), 1 - Yes -;EnableMultiUsers=0 - -; The timeout in which a server goes down if no client is connected, in milliseconds -;ServerNoClientsTimeout=10000 - -; The number of shared memory buffers per stream (default is 6). -; This value affects the number of concurrent clients to the server: (NumberOfBuffers = clients + 3) -;NumberOfBuffers=6 - -;---------------- Sensor Default Configuration ------------------- [Device] -; Mirroring. 0 - Off (default), 1 - On -;Mirror=1 - -; FrameSync. 0 - Off (default), 1 - On -;FrameSync=1 - -; Stream Data Timestamps. 0 - milliseconds, 1 - microseconds (default) -;HighResTimestamps=1 - -; A filter for the firmware log. Default is determined by firmware. -;FirmwareLogFilter=0 - -; Automatic firmare log retrieval. 0 - Off (default), or the number of milliseconds between log retrievals operations. -;FirmwareLogInterval=1000 - -; Print firmware log to console when automatic firmware log retrieval is on. 0 - Off (default), 1 - On -;FirmwareLogPrint=1 - -; Automatic firmware CPU statistics retrieval. 0 - Off (default), or the number of milliseconds between CPU retrievals operations. -;FirmwareCPUInterval=1000 - -; Is APC enabled. 0 - Off, 1 - On (default) -;APCEnabled=1 - -; USB interface to be used. 0 - FW Default, 1 - ISO endpoints, 2 - BULK endpoints. Default: Arm - 2, other platforms - 1 -;UsbInterface=2 - -[Depth] -; Output format. 0 - Shift values, 1 - 12-bit depth values (default) -;OutputFormat=1 - -; Is stream mirrored. 0 - Off, 1 - On -;Mirror=1 - -; 0 - QVGA (default), 1 - VGA -;Resolution=1 - -; Frames per second (default is 30) -;FPS=30 - -; Min depth cutoff. 0-10000 mm (default is 0) -;MinDepthValue=0 - -; Max depth cutoff. 0-10000 mm (default is 10000) -;MaxDepthValue=10000 - -; Input format. 0 - Uncompressed 16-bit, 1 - PS Compression, 3 - Packed 11-bit (default) -;InputFormat=1 - -; Registration. 0 - Off (default), 1 - On -;Registration=1 - -; Registration Type. 0 - Don't care (default), 1 - use hardware accelaration, 2 - perform in software -;RegistrationType=0 - -; Hole Filler. 0 - Off, 1 - On (default) -;HoleFilter=1 - -; White Balance. 0 - Off, 1 - On (default) -;WhiteBalancedEnabled=1 - -; Gain. 0-50 (0 - Auto, 1 - Min., 50 - Max.). Default value is set by firmware. -;Gain=0 - -; GMC Mode. 0 - Off, 1 - On (default) -;GMCMode=0 - -; GMC Debug. 0 - Off (default), 1 - On -;GMCDebug=1 - -; Depth Auto Gain Region-of-Interest. Default values are set by firmware. -;DepthAGCBin0MinDepth=500 -;DepthAGCBin0MaxDepth=800 -;DepthAGCBin1MinDepth=1500 -;DepthAGCBin1MaxDepth=1800 -;DepthAGCBin2MinDepth=2500 -;DepthAGCBin2MaxDepth=2800 -;DepthAGCBin3MinDepth=3500 -;DepthAGCBin3MaxDepth=3800 - -; Wavelength Correction Mechanism. 0 - Off (default), 1 - On -;WavelengthCorrection=1 - -; Wavelength Correction debug info. 0 - Off (default), 1 - On -;WavelengthCorrectionDebug=1 - -; Cropping section -[Depth.Cropping] -;OffsetX=0 -;OffsetY=0 -;SizeX=320 -;SizeY=240 -;Enabled=1 - -[Image] -; Output format. 2 - Gray8 (2.0 MP only), 4 - YUV422, 5 - RGB24 (default) -;OutputFormat=5 - -; Is stream mirrored. 0 - Off, 1 - On -;Mirror=1 - -; 0 - QVGA (default), 1 - VGA, 2- SXGA (1.3MP) 3 - UXGA (2.0MP) -;Resolution=1 - -; Frames per second (default is 30) -;FPS=30 - -; Input format. 0 - BAYER (1.3MP or 2.0MP only), 1 - Compressed YUV422 (default in BULK), 2 - Jpeg, 5 - Uncompressed YUV422 (default in ISO), 6 - Uncompressed 8-bit BAYER -;InputFormat=5 - -; Anti Flicker. 0 - Off (default), 50 - 50Hz, 60 - 60 Hz. -;Flicker=50 - -; Image quality when using Jpeg. 1-10 (1 - Lowest, 10 - Highest (default)) -;Quality=10 - -; Cropping section -[Image.Cropping] -;OffsetX=0 -;OffsetY=0 -;SizeX=320 -;SizeY=240 -;Enabled=1 - -[IR] -; Output format. 3 - Grayscale 16-bit, 5 - RGB24 (default) -;OutputFormat=3 - -; Is stream mirrored. 0 - Off, 1 - On -;Mirror=1 - -; 0 - QVGA (default), 1 - VGA, 2 - SXGA(1.3MP) -;Resolution=1 - -; Frames per second (default is 30) -;FPS=30 - -; Cropping section -[SensorIR.Cropping] -;OffsetX=0 -;OffsetY=0 -;SizeX=320 -;SizeY=240 -;Enabled=1 - -[Audio] -; Sample Rate. 8000, 11025, 12000, 16000, 22050, 24000, 32000, 44100, 48000 (default) -;SampleRate=48000 - -; Volume. 0-49 (0 - Mute, 1 - Min., 49 - Max.). Default is 12. -;LeftChannelVolume=12 -;RightChannelVolume=12 - -; Number of channels. 1, 2 (default) -;NumOfChannels=2 +UsbInterface=1 diff --git a/Platform/Android/jni/Application.mk b/Platform/Android/jni/Application.mk index 6d2da24..4f04cd6 100644 --- a/Platform/Android/jni/Application.mk +++ b/Platform/Android/jni/Application.mk @@ -10,7 +10,7 @@ APP_CFLAGS := -O3 -ftree-vectorize -ffast-math -funroll-loops APP_CFLAGS += -fPIC ifeq ($(APP_ABI),armeabi-v7a) - APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfp=vfpv3-d16 -mfpu=vfp + APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp # optionally add NEON to compilation flags. # to activate, run: "ndk-build USE_NEON=1" diff --git a/Platform/Android/jni/XnCore/Android.mk b/Platform/Android/jni/XnCore/Android.mk index 979c53b..24e9932 100644 --- a/Platform/Android/jni/XnCore/Android.mk +++ b/Platform/Android/jni/XnCore/Android.mk @@ -24,7 +24,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS:= -fvisibility=hidden -DXN_CORE_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_SHARED_LIBRARIES := OpenNI libusb diff --git a/Platform/Android/jni/XnDDK/Android.mk b/Platform/Android/jni/XnDDK/Android.mk index 3c5d70b..233fc1d 100644 --- a/Platform/Android/jni/XnDDK/Android.mk +++ b/Platform/Android/jni/XnDDK/Android.mk @@ -25,7 +25,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS := -fvisibility=hidden -DXN_DDK_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_SHARED_LIBRARIES := OpenNI libusb XnCore XnFormats diff --git a/Platform/Android/jni/XnDeviceFile/Android.mk b/Platform/Android/jni/XnDeviceFile/Android.mk index 9fcabe5..68b9662 100644 --- a/Platform/Android/jni/XnDeviceFile/Android.mk +++ b/Platform/Android/jni/XnDeviceFile/Android.mk @@ -25,7 +25,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS := -fvisibility=hidden -DXN_DEVICE_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_SHARED_LIBRARIES := OpenNI libusb XnCore XnFormats XnDDK diff --git a/Platform/Android/jni/XnDeviceSensorV2/Android.mk b/Platform/Android/jni/XnDeviceSensorV2/Android.mk index 8df6499..9af0b73 100644 --- a/Platform/Android/jni/XnDeviceSensorV2/Android.mk +++ b/Platform/Android/jni/XnDeviceSensorV2/Android.mk @@ -25,7 +25,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS := -fvisibility=hidden -DXN_DEVICE_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_SHARED_LIBRARIES := OpenNI libusb XnCore XnFormats XnDDK diff --git a/Platform/Android/jni/XnFormats/Android.mk b/Platform/Android/jni/XnFormats/Android.mk index de31310..a60cf97 100644 --- a/Platform/Android/jni/XnFormats/Android.mk +++ b/Platform/Android/jni/XnFormats/Android.mk @@ -27,7 +27,7 @@ LOCAL_C_INCLUDES := \ LOCAL_CFLAGS := -fvisibility=hidden -DXN_FORMATS_EXPORTS -LOCAL_LDFLAGS += -Wl,--export-dynamic --dynamic-linker +LOCAL_LDFLAGS += -Wl,--export-dynamic LOCAL_SHARED_LIBRARIES := OpenNI libusb XnCore -- 2.4.11 From 7e2b9c705a0b8e26216c4e6a13167e59807dffbb Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Tue, 26 Apr 2016 14:58:47 +0100 Subject: [PATCH 2/2] fix build aarch64 --- Platform/Android/jni/Application.mk | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Platform/Android/jni/Application.mk b/Platform/Android/jni/Application.mk index 4f04cd6..909a024 100644 --- a/Platform/Android/jni/Application.mk +++ b/Platform/Android/jni/Application.mk @@ -4,22 +4,22 @@ APP_STL := gnustl_static APP_PLATFORM := android-9 # Build ARMv7-A machine code. -APP_ABI := armeabi-v7a +APP_ABI := arm64-v8a armeabi-v7a APP_CFLAGS := -O3 -ftree-vectorize -ffast-math -funroll-loops APP_CFLAGS += -fPIC -ifeq ($(APP_ABI),armeabi-v7a) - APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -# optionally add NEON to compilation flags. -# to activate, run: "ndk-build USE_NEON=1" -ifdef USE_NEON -$(call __ndk_info,Building everything with NEON support!) - APP_CFLAGS += -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions -endif +ifeq ($(TARGET_ARCH),arm64) + APP_CFLAGS += -march=armv8-a -DHAVE_NEON=1 -flax-vector-conversions +else +ifeq ($(TARGET_ARCH),arm) + APP_CFLAGS += -march=armv7-a -mfloat-abi=softfp -mtune=cortex-a9 -mfpu=vfp -mfpu=neon -DHAVE_NEON=1 -flax-vector-conversions + endif endif + + APP_CPPFLAGS += -frtti #$(call __ndk_info,APP_CFLAGS=$(APP_CFLAGS)) -- 2.4.11 ================================================ FILE: framework/patchs/freeimage.patch ================================================ From 8f0d44f1b1b8de0eda131210ce6e09e84f4deea0 Mon Sep 17 00:00:00 2001 From: Ryan Coe Date: Fri, 23 Feb 2018 17:06:37 -0800 Subject: [PATCH 1/1] fix float usage in powf64 Signed-off-by: Ryan Coe --- Source/LibRawLite/internal/dcraw_common.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/Source/LibRawLite/internal/dcraw_common.cpp b/Source/LibRawLite/internal/dcraw_common.cpp index 217133a9f9a1caccb77eae946b3af073f660b1cf..cde8e420ad66508feb1222b5fde7166104f6ff1a 100644 --- a/Source/LibRawLite/internal/dcraw_common.cpp +++ b/Source/LibRawLite/internal/dcraw_common.cpp @@ -5543,11 +5543,18 @@ static float powf_lim(float a, float b, float limup) { return (b>limup || b < -limup)?0.f:powf(a,b); } -static float powf64(float a, float b) +static float powf64(const float a, const float b) { return powf_lim(a,b,64.f); } - +static float powf64(const int a, const int b) +{ + return powf_lim((float)a,(float)b,64.f); +} +static float powf64(const double a, const double b) +{ + return powf_lim((float)a,(float)b,64.f); +} #ifdef LIBRAW_LIBRARY_BUILD -- 2.16.1 ================================================ FILE: framework/patchs/libopencl-stub_SLAMBench.patch ================================================ From 2c3bc3642a5177c9305da3b8dc93293ff576b4b9 Mon Sep 17 00:00:00 2001 From: "Bruno Bodin (zebulon)" Date: Tue, 26 Apr 2016 17:20:51 +0100 Subject: [PATCH] Slambench --- Application.mk | 1 + include/clinfos.h | 2602 ++++++++++++++++++++++++++++++++++++++++++++++++++ include/error.h | 53 + include/ext.h | 165 ++++ include/fmtmacros.h | 28 + include/memory.h | 21 + include/ms_support.h | 47 + include/strbuf.h | 96 ++ libopencl.c | 98 +- 9 files changed, 3107 insertions(+), 4 deletions(-) create mode 100644 Application.mk create mode 100644 include/clinfos.h create mode 100644 include/error.h create mode 100644 include/ext.h create mode 100644 include/fmtmacros.h create mode 100644 include/memory.h create mode 100644 include/ms_support.h create mode 100644 include/strbuf.h diff --git a/Application.mk b/Application.mk new file mode 100644 index 0000000..a252a72 --- /dev/null +++ b/Application.mk @@ -0,0 +1 @@ +APP_ABI := all diff --git a/include/clinfos.h b/include/clinfos.h new file mode 100644 index 0000000..0820fec --- /dev/null +++ b/include/clinfos.h @@ -0,0 +1,2602 @@ +/* Collect all available information on all available devices + * on all available OpenCL platforms present in the system + */ + +#include +#include +#include + +#ifndef RTLD_DEFAULT +#define RTLD_DEFAULT ((void*)0) +#endif + +/* Load STDC format macros (PRI*), or define them + * for those crappy, non-standard compilers + */ +#include "fmtmacros.h" + +// Support for the horrible MS C compiler +#ifdef _MSC_VER +#include "ms_support.h" +#endif + +#include "ext.h" +#include "error.h" +#include "memory.h" +#include "strbuf.h" + +#define ARRAY_SIZE(ar) (sizeof(ar)/sizeof(*ar)) +#define UNUSED __attribute__((unused)) + +struct platform_data { + char *pname; /* CL_PLATFORM_NAME */ + char *sname; /* CL_PLATFORM_ICD_SUFFIX_KHR or surrogate */ + cl_uint ndevs; /* number of devices */ + cl_bool has_amd_offline; /* has cl_amd_offline_devices extension */ +}; + +struct platform_info_checks { + int has_khr_icd; + cl_uint plat_version; +}; + +cl_uint num_platforms; +cl_platform_id *platform; +/* highest version exposed by any platform: if the OpenCL library (the ICD loader) + * has a lower version, problems may arise (such as API calls causing segfaults + * or any other unexpected behavior + */ +cl_uint max_plat_version; +/* auto-detected OpenCL version support for the ICD loader */ +cl_uint icdl_ocl_version_found = 10; +/* OpenCL version support declared by the ICD loader */ +cl_uint icdl_ocl_version; + +struct platform_data *pdata; +/* maximum length of a platform's sname */ +size_t platform_sname_maxlen; +/* maximum number of devices */ +cl_uint maxdevs; +/* line prefix, used to identify the platform/device for each + * device property in RAW output mode */ +char *line_pfx; +int line_pfx_len; + +cl_uint num_devs_all; + +cl_device_id *all_devices; + +enum output_modes { + CLINFO_HUMAN = 1, /* more human readable */ + CLINFO_RAW = 2, /* property-by-property */ + CLINFO_BOTH = CLINFO_HUMAN | CLINFO_RAW +}; + +enum output_modes output_mode = CLINFO_HUMAN; + +/* Specify if we should only be listing the platform and devices; + * can be done in both human and raw mode, and only the platform + * and device names (and number) will be shown + * TODO check if terminal supports UTF-8 and use Unicode line-drawing + * for the tree in list mode + */ +cl_bool list_only = CL_FALSE; + +static const char unk[] = "Unknown"; +static const char none[] = "None"; +static const char none_raw[] = "CL_NONE"; +static const char na[] = "n/a"; // not available +static const char core[] = "core"; // not available + +static const char bytes_str[] = " bytes"; +static const char pixels_str[] = " pixels"; +static const char images_str[] = " images"; + +static const char* bool_str[] = { "No", "Yes" }; +static const char* bool_raw_str[] = { "CL_FALSE", "CL_TRUE" }; + +static const char* endian_str[] = { "Big-Endian", "Little-Endian" }; + +static const cl_device_type devtype[] = { 0, + CL_DEVICE_TYPE_DEFAULT, CL_DEVICE_TYPE_CPU, CL_DEVICE_TYPE_GPU, + CL_DEVICE_TYPE_ACCELERATOR, CL_DEVICE_TYPE_CUSTOM, CL_DEVICE_TYPE_ALL }; + +const size_t devtype_count = ARRAY_SIZE(devtype); + +static const char* device_type_str[] = { unk, "Default", "CPU", "GPU", "Accelerator", "Custom", "All" }; +static const char* device_type_raw_str[] = { unk, + "CL_DEVICE_TYPE_DEFAULT", "CL_DEVICE_TYPE_CPU", "CL_DEVICE_TYPE_GPU", + "CL_DEVICE_TYPE_ACCELERATOR", "CL_DEVICE_TYPE_CUSTOM", "CL_DEVICE_TYPE_ALL" +}; + +static const char* partition_type_str[] = { + "none specified", none, "equally", "by counts", "by affinity domain", "by names (Intel)" +}; +static const char* partition_type_raw_str[] = { + "NONE SPECIFIED", + none_raw, + "CL_DEVICE_PARTITION_EQUALLY_EXT", + "CL_DEVICE_PARTITION_BY_COUNTS_EXT", + "CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT", + "CL_DEVICE_PARTITION_BY_NAMES_INTEL_EXT" +}; + +static const char numa[] = "NUMA"; +static const char l1cache[] = "L1 cache"; +static const char l2cache[] = "L2 cache"; +static const char l3cache[] = "L3 cache"; +static const char l4cache[] = "L4 cache"; + +static const char* affinity_domain_str[] = { + numa, l4cache, l3cache, l2cache, l1cache, "next partitionable" +}; + +static const char* affinity_domain_ext_str[] = { + numa, l4cache, l3cache, l2cache, l1cache, "next fissionable" +}; + +static const char* affinity_domain_raw_str[] = { + "CL_DEVICE_AFFINITY_DOMAIN_NUMA", + "CL_DEVICE_AFFINITY_DOMAIN_L4_CACHE", + "CL_DEVICE_AFFINITY_DOMAIN_L3_CACHE", + "CL_DEVICE_AFFINITY_DOMAIN_L2_CACHE", + "CL_DEVICE_AFFINITY_DOMAIN_L1_CACHE", + "CL_DEVICE_AFFINITY_DOMAIN_NEXT_PARTITIONABLE" +}; + +static const char* affinity_domain_raw_ext_str[] = { + "CL_AFFINITY_DOMAIN_NUMA_EXT", + "CL_AFFINITY_DOMAIN_L4_CACHE_EXT", + "CL_AFFINITY_DOMAIN_L3_CACHE_EXT", + "CL_AFFINITY_DOMAIN_L2_CACHE_EXT", + "CL_AFFINITY_DOMAIN_L1_CACHE_EXT", + "CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT" +}; + +const size_t affinity_domain_count = ARRAY_SIZE(affinity_domain_str); + +static const char* fp_conf_str[] = { + "Denormals", "Infinity and NANs", "Round to nearest", "Round to zero", + "Round to infinity", "IEEE754-2008 fused multiply-add", + "Support is emulated in software", + "Correctly-rounded divide and sqrt operations" +}; + +static const char* fp_conf_raw_str[] = { + "CL_FP_DENORM", + "CL_FP_INF_NAN", + "CL_FP_ROUND_TO_NEAREST", + "CL_FP_ROUND_TO_ZERO", + "CL_FP_ROUND_TO_INF", + "CL_FP_FMA", + "CL_FP_SOFT_FLOAT", + "CL_FP_CORRECTLY_ROUNDED_DIVIDE_SQRT" +}; + +const size_t fp_conf_count = ARRAY_SIZE(fp_conf_str); + +static const char* svm_cap_str[] = { + "Coarse-grained buffer sharing", + "Fine-grained buffer sharing", + "Fine-grained system sharing", + "Atomics" +}; + +static const char* svm_cap_raw_str[] = { + "CL_DEVICE_SVM_COARSE_GRAIN_BUFFER", + "CL_DEVICE_SVM_FINE_GRAIN_BUFFER", + "CL_DEVICE_SVM_FINE_GRAIN_SYSTEM", + "CL_DEVICE_SVM_ATOMICS", +}; + +const size_t svm_cap_count = ARRAY_SIZE(svm_cap_str); + +static const char* memsfx[] = { + "B", "KiB", "MiB", "GiB", "TiB" +}; + +const size_t memsfx_count = ARRAY_SIZE(memsfx); + +static const char* lmem_type_str[] = { none, "Local", "Global" }; +static const char* lmem_type_raw_str[] = { none_raw, "CL_LOCAL", "CL_GLOBAL" }; +static const char* cache_type_str[] = { none, "Read-Only", "Read/Write" }; +static const char* cache_type_raw_str[] = { none_raw, "CL_READ_ONLY_CACHE", "CL_READ_WRITE_CACHE" }; + +static const char* queue_prop_str[] = { "Out-of-order execution", "Profiling" }; +static const char* queue_prop_raw_str[] = { + "CL_QUEUE_OUT_OF_ORDER_EXEC_MODE_ENABLE", + "CL_QUEUE_PROFILING_ENABLE" +}; + +const size_t queue_prop_count = ARRAY_SIZE(queue_prop_str); + +static const char* execap_str[] = { "Run OpenCL kernels", "Run native kernels" }; +static const char* execap_raw_str[] = { + "CL_EXEC_KERNEL", + "CL_EXEC_NATIVE_KERNEL" +}; + +const size_t execap_count = ARRAY_SIZE(execap_str); + +static const char* sources[] = { + "#define GWO(type) global type* restrict\n", + "#define GRO(type) global const type* restrict\n", + "#define BODY int i = get_global_id(0); out[i] = in1[i] + in2[i]\n", + "#define _KRN(T, N) void kernel sum##N(GWO(T##N) out, GRO(T##N) in1, GRO(T##N) in2) { BODY; }\n", + "#define KRN(N) _KRN(float, N)\n", + "KRN()\n/* KRN(2)\nKRN(4)\nKRN(8)\nKRN(16) */\n", +}; + +const char *no_plat(void) +{ + return output_mode == CLINFO_HUMAN ? + "No platform" : + "CL_INVALID_PLATFORM"; +} + +const char *no_dev(void) +{ + return output_mode == CLINFO_HUMAN ? + "No devices found in platform" : + "CL_DEVICE_NOT_FOUND"; +} + +const char *no_dev_avail(void) +{ + return output_mode == CLINFO_HUMAN ? + "No devices available in platform" : + "CL_DEVICE_NOT_AVAILABLE"; +} + + +/* preferred workgroup size multiple for each kernel + * have not found a platform where the WG multiple changes, + * but keep this flexible (this can grow up to 5) + */ +#define NUM_KERNELS 1 +size_t wgm[NUM_KERNELS]; + +#define INDENT " " +#define I0_STR "%-48s " +#define I1_STR " %-46s " +#define I2_STR " %-44s " + +static const char empty_str[] = ""; +static const char spc_str[] = " "; +static const char times_str[] = "x"; +static const char comma_str[] = ", "; +static const char vbar_str[] = " | "; + +int had_error = 0; +const char *cur_sfx = empty_str; + +/* parse a CL_DEVICE_VERSION or CL_PLATFORM_VERSION info to determine the OpenCL version. + * Returns an unsigned integer in the form major*10 + minor + */ +cl_uint +getOpenCLVersion(const char *version) +{ + cl_uint ret = 10; + long parse = 0; + const char *from = version; + char *next = NULL; + parse = strtol(from, &next, 10); + + if (next != from) { + ret = parse*10; + // skip the dot TODO should we actually check for the dot? + from = ++next; + parse = strtol(from, &next, 10); + if (next != from) + ret += parse; + } + return ret; +} + + +/* print strbuf, prefixed by pname, skipping leading whitespace if skip is nonzero, + * affixing cur_sfx */ +static inline +void show_strbuf(const char *pname, int skip) +{ +LOGI("%s" I1_STR "%s%s\n", + line_pfx, pname, + (skip ? skip_leading_ws(strbuf) : strbuf), + had_error ? empty_str : cur_sfx); +} + +int +platform_info_str(cl_platform_id pid, cl_platform_info param, const char* pname, const struct platform_info_checks * chk UNUSED) +{ + error = clGetPlatformInfo(pid, param, 0, NULL, &nusz); + if (nusz > bufsz) { + REALLOC(strbuf, nusz, current_param); + bufsz = nusz; + } + had_error = REPORT_ERROR2("get %s size"); + if (!had_error) { + error = clGetPlatformInfo(pid, param, bufsz, strbuf, NULL); + had_error = REPORT_ERROR2("get %s"); + } + /* when only listing, do not print anything we're just gathering + * information + */ + if (!list_only) + show_strbuf(pname, 1); + return had_error; +} + +int +platform_info_ulong(cl_platform_id pid, cl_platform_info param, const char* pname, const struct platform_info_checks * chk UNUSED) +{ + cl_ulong val = 0; + + error = clGetPlatformInfo(pid, param, sizeof(val), &val, NULL); + had_error = REPORT_ERROR2("get %s"); + /* when only listing, do not print anything we're just gathering + * information + */ + if (!list_only) { + if (had_error) + show_strbuf(pname, 0); + else + LOGI("%s" I1_STR "%" PRIu64 "%s\n", line_pfx, pname, val, cur_sfx); + } + return had_error; +} + +struct platform_info_traits { + cl_platform_info param; // CL_PLATFORM_* + const char *sname; // "CL_PLATFORM_*" + const char *pname; // "Platform *" + const char *sfx; // suffix for the output in non-raw mode + /* pointer to function that shows the parameter */ + int (*show_func)(cl_platform_id pid, cl_platform_info param, const char *pname, const struct platform_info_checks *); + /* pointer to function that checks if the parameter should be checked */ + int (*check_func)(const struct platform_info_checks *); +}; + +int khr_icd_p(const struct platform_info_checks *chk) +{ + return chk->has_khr_icd; +} + +int plat_is_21(const struct platform_info_checks *chk) +{ + return !(chk->plat_version < 21); +} + +#define PINFO_COND(symbol, name, sfx, typ, funcptr) { symbol, #symbol, "Platform " name, sfx, &platform_info_##typ, &funcptr } +#define PINFO(symbol, name, sfx, typ) { symbol, #symbol, "Platform " name, sfx, &platform_info_##typ, NULL } +struct platform_info_traits pinfo_traits[] = { + PINFO(CL_PLATFORM_NAME, "Name", NULL, str), + PINFO(CL_PLATFORM_VENDOR, "Vendor", NULL, str), + PINFO(CL_PLATFORM_VERSION, "Version", NULL, str), + PINFO(CL_PLATFORM_PROFILE, "Profile", NULL, str), + PINFO(CL_PLATFORM_EXTENSIONS, "Extensions", NULL, str), + PINFO_COND(CL_PLATFORM_HOST_TIMER_RESOLUTION, "Host timer resolution", "ns", ulong, plat_is_21), + PINFO_COND(CL_PLATFORM_ICD_SUFFIX_KHR, "Extensions function suffix", NULL, str, khr_icd_p) +}; + +/* Print platform info and prepare arrays for device info */ +void +printPlatformInfo(cl_uint p) +{ + cl_platform_id pid = platform[p]; + size_t len = 0; + + struct platform_info_checks pinfo_checks = { 0, 10 }; + + current_function = __func__; + + for (current_line = 0; current_line < ARRAY_SIZE(pinfo_traits); ++current_line) { + const struct platform_info_traits *traits = pinfo_traits + current_line; + const char *pname = (output_mode == CLINFO_HUMAN ? + traits->pname : traits->sname); + + current_param = traits->sname; + + if (traits->check_func && !traits->check_func(&pinfo_checks)) + continue; + + cur_sfx = (output_mode == CLINFO_HUMAN && traits->sfx) ? traits->sfx : empty_str; + + had_error = traits->show_func(pid, traits->param, + pname, &pinfo_checks); + + if (had_error) + continue; + + /* post-processing */ + + switch (traits->param) { + case CL_PLATFORM_NAME: + /* Store name for future reference */ + len = strlen(strbuf); + ALLOC(pdata[p].pname, len+1, "platform name copy"); + /* memcpy instead of strncpy since we already have the len + * and memcpy is possibly more optimized */ + memcpy(pdata[p].pname, strbuf, len); + pdata[p].pname[len] = '\0'; + break; + case CL_PLATFORM_VERSION: + /* compute numeric value for OpenCL version */ + pinfo_checks.plat_version = getOpenCLVersion(strbuf + 7); + break; + case CL_PLATFORM_EXTENSIONS: + pinfo_checks.has_khr_icd = !!strstr(strbuf, "cl_khr_icd"); + pdata[p].has_amd_offline = !!strstr(strbuf, "cl_amd_offline_devices"); + break; + case CL_PLATFORM_ICD_SUFFIX_KHR: + /* Store ICD suffix for future reference */ + len = strlen(strbuf); + ALLOC(pdata[p].sname, len+1, "platform ICD suffix copy"); + /* memcpy instead of strncpy since we already have the len + * and memcpy is possibly more optimized */ + memcpy(pdata[p].sname, strbuf, len); + pdata[p].sname[len] = '\0'; + default: + /* do nothing */ + break; + } + + } + + if (pinfo_checks.plat_version > max_plat_version) + max_plat_version = pinfo_checks.plat_version; + + /* if no CL_PLATFORM_ICD_SUFFIX_KHR, use P### as short/symbolic name */ + if (!pdata[p].sname) { +#define SNAME_MAX 32 + ALLOC(pdata[p].sname, SNAME_MAX, "platform symbolic name"); + snprintf(pdata[p].sname, SNAME_MAX, "P%u", p); + } + + len = strlen(pdata[p].sname); + if (len > platform_sname_maxlen) + platform_sname_maxlen = len; + + error = clGetDeviceIDs(pid, CL_DEVICE_TYPE_ALL, 0, NULL, &(pdata[p].ndevs)); + if (error == CL_DEVICE_NOT_FOUND) + pdata[p].ndevs = 0; + else + CHECK_ERROR("number of devices"); + + num_devs_all += pdata[p].ndevs; + + if (pdata[p].ndevs > maxdevs) + maxdevs = pdata[p].ndevs; +} + +int +getWGsizes(cl_platform_id pid, cl_device_id dev) +{ + int ret = 0; + +#define RR_ERROR(what) do { \ + had_error = REPORT_ERROR(what); \ + if (had_error) { \ + ret = error; \ + goto out; \ + } \ +} while(0) + + + cl_context_properties ctxpft[] = { + CL_CONTEXT_PLATFORM, (cl_context_properties)pid, + 0, 0 }; + cl_uint cursor = 0; + cl_context ctx = NULL; + cl_program prg = NULL; + cl_kernel krn = NULL; + + ctx = clCreateContext(ctxpft, 1, &dev, NULL, NULL, &error); + RR_ERROR("create context"); + prg = clCreateProgramWithSource(ctx, ARRAY_SIZE(sources), sources, NULL, &error); + RR_ERROR("create program"); + error = clBuildProgram(prg, 1, &dev, NULL, NULL, NULL); + had_error = REPORT_ERROR("build program"); + if (had_error) + ret = error; + + /* for a program build failure, dump the log to stderr before bailing */ + if (error == CL_BUILD_PROGRAM_FAILURE) { + GET_STRING(clGetProgramBuildInfo, CL_PROGRAM_BUILD_LOG, "CL_PROGRAM_BUILD_LOG", prg, dev); + if (error == CL_SUCCESS) { + fputs("=== CL_PROGRAM_BUILD_LOG ===\n", stderr); + fputs(strbuf, stderr); + } + } + if (had_error) + goto out; + + for (cursor = 0; cursor < NUM_KERNELS; ++cursor) { + snprintf(strbuf, bufsz, "sum%u", 1<has_##ext[0]); \ +} + +DEFINE_EXT_CHECK(half) +DEFINE_EXT_CHECK(double) +DEFINE_EXT_CHECK(nv) +DEFINE_EXT_CHECK(amd) +DEFINE_EXT_CHECK(svm_ext) +DEFINE_EXT_CHECK(fission) +DEFINE_EXT_CHECK(atomic_counters) +DEFINE_EXT_CHECK(image2d_buffer) +DEFINE_EXT_CHECK(intel_local_thread) +DEFINE_EXT_CHECK(intel_AME) +DEFINE_EXT_CHECK(altera_dev_temp) +DEFINE_EXT_CHECK(spir) +DEFINE_EXT_CHECK(qcom_ext_host_ptr) +DEFINE_EXT_CHECK(simultaneous_sharing) + +/* In the version checks we negate the opposite conditions + * instead of double-negating the actual condition + */ + +// device supports 1.2 +int dev_is_12(const struct device_info_checks *chk) +{ + return !(chk->dev_version < 12); +} + +// device supports 2.0 +int dev_is_20(const struct device_info_checks *chk) +{ + return !(chk->dev_version < 20); +} + +// device supports 2.1 +int dev_is_21(const struct device_info_checks *chk) +{ + return !(chk->dev_version < 21); +} + +// device does not support 2.0 +int dev_not_20(const struct device_info_checks *chk) +{ + return !(chk->dev_version >= 20); +} + + +int dev_is_gpu(const struct device_info_checks *chk) +{ + return !!(chk->devtype & CL_DEVICE_TYPE_GPU); +} + +int dev_is_gpu_amd(const struct device_info_checks *chk) +{ + return dev_is_gpu(chk) && dev_has_amd(chk); +} + +int dev_has_svm(const struct device_info_checks *chk) +{ + return dev_is_20(chk) || dev_has_svm_ext(chk); +} + +int dev_has_partition(const struct device_info_checks *chk) +{ + return dev_is_12(chk) || dev_has_fission(chk); +} + +int dev_has_cache(const struct device_info_checks *chk) +{ + return chk->cachetype != CL_NONE; +} + +int dev_has_lmem(const struct device_info_checks *chk) +{ + return chk->lmemtype != CL_NONE; +} + +int dev_has_images(const struct device_info_checks *chk) +{ + return chk->image_support; +} + +int dev_has_images_12(const struct device_info_checks *chk) +{ + return dev_has_images(chk) && dev_is_12(chk); +} + +int dev_has_images_20(const struct device_info_checks *chk) +{ + return dev_has_images(chk) && dev_is_20(chk); +} + + +void identify_device_extensions(const char *extensions, struct device_info_checks *chk) +{ +#define _HAS_EXT(ext) (strstr(extensions, ext)) +#define HAS_EXT(ext) _HAS_EXT(#ext) +#define CPY_EXT(what, ext) do { \ + strncpy(chk->has_##what, has, sizeof(ext)); \ + chk->has_##what[sizeof(ext)-1] = '\0'; \ +} while (0) +#define CHECK_EXT(what, ext) do { \ + has = _HAS_EXT(#ext); \ + if (has) CPY_EXT(what, #ext); \ +} while(0) + + char *has; + CHECK_EXT(half, cl_khr_fp16); + CHECK_EXT(spir, cl_khr_spir); + CHECK_EXT(double, cl_khr_fp64); + if (!dev_has_double(chk)) + CHECK_EXT(double, cl_amd_fp64); + if (!dev_has_double(chk)) + CHECK_EXT(double, cl_APPLE_fp64_basic_ops); + CHECK_EXT(nv, cl_nv_device_attribute_query); + CHECK_EXT(amd, cl_amd_device_attribute_query); + CHECK_EXT(svm_ext, cl_amd_svm); + CHECK_EXT(fission, cl_ext_device_fission); + CHECK_EXT(atomic_counters, cl_ext_atomic_counters_64); + if (dev_has_atomic_counters(chk)) + CHECK_EXT(atomic_counters, cl_ext_atomic_counters_32); + CHECK_EXT(image2d_buffer, cl_khr_image2d_from_buffer); + CHECK_EXT(intel_local_thread, cl_intel_exec_by_local_thread); + CHECK_EXT(intel_AME, cl_intel_advanced_motion_estimation); + CHECK_EXT(altera_dev_temp, cl_altera_device_temperature); + CHECK_EXT(qcom_ext_host_ptr, cl_qcom_ext_host_ptr); + CHECK_EXT(simultaneous_sharing, cl_intel_simultaneous_sharing); +} + + + +/* + * Device info print functions + */ + +#define _GET_VAL \ + error = clGetDeviceInfo(dev, param, sizeof(val), &val, NULL); \ + had_error = REPORT_ERROR2("get %s"); + +#define _GET_VAL_ARRAY \ + error = clGetDeviceInfo(dev, param, 0, NULL, &szval); \ + had_error = REPORT_ERROR2("get number of %s"); \ + numval = szval/sizeof(val); \ + if (!had_error) { \ + REALLOC(val, numval, current_param); \ + error = clGetDeviceInfo(dev, param, szval, val, NULL); \ + had_error = REPORT_ERROR("get %s"); \ + } + +#define GET_VAL do { \ + _GET_VAL \ +} while (0) + +#define GET_VAL_ARRAY do { \ + _GET_VAL_ARRAY \ +} while (0) + +#define _FMT_VAL(fmt) \ + if (had_error) \ + show_strbuf(pname, 0); \ + else \ + LOGI("%s" I1_STR fmt "%s\n", line_pfx, pname, val, cur_sfx); + +#define FMT_VAL(fmt) do { \ + _FMT_VAL(fmt) \ +} while (0) + +#define SHOW_VAL(fmt) do { \ + _GET_VAL \ + _FMT_VAL(fmt) \ +} while (0) + +#define DEFINE_DEVINFO_SHOW(how, type, fmt) \ +int device_info_##how(cl_device_id dev, cl_device_info param, const char *pname, \ + const struct device_info_checks *chk UNUSED) \ +{ \ + type val = 0; \ + SHOW_VAL(fmt); \ + return had_error; \ +} + +/* Get string-type info without showing it */ +int device_info_str_get(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + current_param = pname; + error = clGetDeviceInfo(dev, param, 0, NULL, &nusz); + if (nusz > bufsz) { + REALLOC(strbuf, nusz, current_param); + bufsz = nusz; + } + had_error = REPORT_ERROR2("get %s size"); + if (!had_error) { + error = clGetDeviceInfo(dev, param, bufsz, strbuf, NULL); + had_error = REPORT_ERROR2("get %s"); + } + return had_error; +} + +int device_info_str(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk) +{ + had_error = device_info_str_get(dev, param, pname, chk); + show_strbuf(pname, 1); + return had_error; +} + +DEFINE_DEVINFO_SHOW(int, cl_uint, "%u") +DEFINE_DEVINFO_SHOW(hex, cl_uint, "0x%x") +DEFINE_DEVINFO_SHOW(long, cl_ulong, "%" PRIu64) +DEFINE_DEVINFO_SHOW(sz, size_t, "%" PRIuS) + +int device_info_bool(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_bool val = 0; + const char * const * str = (output_mode == CLINFO_HUMAN ? + bool_str : bool_raw_str); + GET_VAL; + if (had_error) + show_strbuf(pname, 0); + else { + LOGI("%s" I1_STR "%s%s\n", line_pfx, pname, str[val], cur_sfx); + /* abuse strbuf to pass the bool value up to the caller, + * this is used e.g. by CL_DEVICE_IMAGE_SUPPORT + */ + memcpy(strbuf, &val, sizeof(val)); + } + return had_error; +} + +int device_info_bits(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_uint val; + GET_VAL; + if (!had_error) + sprintf(strbuf, "%u bits (%u bytes)", val, val/8); + show_strbuf(pname, 0); + return had_error; +} + + +size_t strbuf_mem(cl_ulong val, size_t szval) +{ + double dbl = val; + size_t sfx = 0; + while (dbl > 1024 && sfx < memsfx_count) { + dbl /= 1024; + ++sfx; + } + return sprintf(strbuf + szval, " (%.4lg%s)", + dbl, memsfx[sfx]); +} + +int device_info_mem(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_ulong val = 0; + size_t szval = 0; + GET_VAL; + if (!had_error) { + szval += sprintf(strbuf, "%" PRIu64, val); + if (output_mode == CLINFO_HUMAN && val > 1024) + strbuf_mem(val, szval); + } + show_strbuf(pname, 0); + return had_error; +} + +int device_info_mem_int(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_uint val = 0; + size_t szval = 0; + GET_VAL; + if (!had_error) { + szval += sprintf(strbuf, "%u", val); + if (output_mode == CLINFO_HUMAN && val > 1024) + strbuf_mem(val, szval); + } + show_strbuf(pname, 0); + return had_error; +} + +int device_info_free_mem_amd(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t *val = NULL; + size_t szval = 0, numval = 0; + GET_VAL_ARRAY; + if (!had_error) { + size_t cursor = 0; + szval = 0; + for (cursor = 0; cursor < numval; ++cursor) { + if (szval > 0) { + strbuf[szval] = ' '; + ++szval; + } + szval += sprintf(strbuf + szval, "%" PRIuS, val[cursor]); + if (output_mode == CLINFO_HUMAN) + szval += strbuf_mem(val[cursor]*UINT64_C(1024), szval); + } + } + show_strbuf(pname, 0); + free(val); + return had_error; +} + +int device_info_time_offset(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_ulong val = 0; + GET_VAL; + if (!had_error) { + size_t szval = 0; + time_t time = val/UINT64_C(1000000000); + szval += snprintf(strbuf, bufsz, "%" PRIu64 "ns (", val); + szval += bufcpy(szval, ctime(&time)); + /* overwrite ctime's newline with the closing parenthesis */ + if (szval < bufsz) + strbuf[szval - 1] = ')'; + } + show_strbuf(pname, 0); + return had_error; +} + +int device_info_szptr(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t *val = NULL; + size_t szval = 0, numval = 0; + GET_VAL_ARRAY; + if (!had_error) { + size_t counter = 0; + set_separator(output_mode == CLINFO_HUMAN ? times_str : spc_str); + szval = 0; + for (counter = 0; counter < numval; ++counter) { + add_separator(&szval); + szval += snprintf(strbuf + szval, bufsz - szval - 1, "%" PRIuS, val[counter]); + if (szval >= bufsz) { + trunc_strbuf(); + break; + } + } + } + show_strbuf(pname, 0); + free(val); + return had_error; +} + +int device_info_wg(cl_device_id dev, cl_device_info param UNUSED, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_platform_id val = NULL; + { + /* shadow */ + cl_device_info param = CL_DEVICE_PLATFORM; + current_param = "CL_DEVICE_PLATFORM"; + GET_VAL; + } + current_param = pname; + if (!had_error) + had_error = getWGsizes(val, dev); + if (!had_error) { + sprintf(strbuf, "%" PRIuS, wgm[0]); + } + show_strbuf(pname, 0); + return had_error; +} + +int device_info_img_sz_2d(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t width = 0, height = 0, val = 0; + GET_VAL; /* HEIGHT */ + if (!had_error) { + height = val; + param = CL_DEVICE_IMAGE2D_MAX_WIDTH; + current_param = "CL_DEVICE_IMAGE2D_MAX_WIDTH"; + GET_VAL; + if (!had_error) { + width = val; + sprintf(strbuf, "%" PRIuS "x%" PRIuS, width, height); + } + } + show_strbuf(pname, 0); + return had_error; +} + +int device_info_img_sz_3d(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t width = 0, height = 0, depth = 0, val = 0; + GET_VAL; /* HEIGHT */ + if (!had_error) { + height = val; + param = CL_DEVICE_IMAGE3D_MAX_WIDTH; + current_param = "CL_DEVICE_IMAGE3D_MAX_WIDTH"; + GET_VAL; + if (!had_error) { + width = val; + param = CL_DEVICE_IMAGE3D_MAX_DEPTH; + current_param = "CL_DEVICE_IMAGE3D_MAX_DEPTH"; + GET_VAL; + if (!had_error) { + depth = val; + sprintf(strbuf, "%" PRIuS "x%" PRIuS "x%" PRIuS, + width, height, depth); + } + } + } + show_strbuf(pname, 0); + return had_error; +} + + +int device_info_devtype(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_type val = 0; + GET_VAL; + if (!had_error) { + /* iterate over device type strings, appending their textual form + * to strbuf. + * TODO: check for extra bits/no bits + */ + cl_uint i = devtype_count - 1; /* skip CL_DEVICE_TYPE_ALL */ + const char * const *devstr = (output_mode == CLINFO_HUMAN ? + device_type_str : device_type_raw_str); + size_t szval = 0; + strbuf[szval] = '\0'; + set_separator(output_mode == CLINFO_HUMAN ? comma_str : vbar_str); + for (; i > 0; --i) { + /* assemble CL_DEVICE_TYPE_* from index i */ + cl_device_type cur = (cl_device_type)(1) << (i-1); + if (val & cur) { + /* match: add separator if not first match */ + add_separator(&szval); + szval += bufcpy(szval, devstr[i]); + } + } + } + show_strbuf(pname, 0); + /* we abuse global strbuf to pass the device type over to the caller */ + if (!had_error) + memcpy(strbuf, &val, sizeof(val)); + return had_error; +} + +int device_info_cachetype(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_mem_cache_type val = 0; + GET_VAL; + if (!had_error) { + const char * const *ar = (output_mode == CLINFO_HUMAN ? + cache_type_str : cache_type_raw_str); + bufcpy(0, ar[val]); + } + show_strbuf(pname, 0); + /* we abuse global strbuf to pass the cache type over to the caller */ + if (!had_error) + memcpy(strbuf, &val, sizeof(val)); + return had_error; +} + +int device_info_lmemtype(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_local_mem_type val = 0; + GET_VAL; + if (!had_error) { + const char * const *ar = (output_mode == CLINFO_HUMAN ? + lmem_type_str : lmem_type_raw_str); + bufcpy(0, ar[val]); + } + show_strbuf(pname, 0); + /* we abuse global strbuf to pass the lmem type over to the caller */ + if (!had_error) + memcpy(strbuf, &val, sizeof(val)); + return had_error; +} + +/* stringify a cl_device_topology_amd */ +void devtopo_str(const cl_device_topology_amd *devtopo) +{ + switch (devtopo->raw.type) { + case 0: + if (output_mode == CLINFO_HUMAN) + sprintf(strbuf, "(%s)", na); + else + sprintf(strbuf, none_raw); + break; + case CL_DEVICE_TOPOLOGY_TYPE_PCIE_AMD: + sprintf(strbuf, "PCI-E, %02x:%02x.%u", + (cl_uchar)(devtopo->pcie.bus), + devtopo->pcie.device, devtopo->pcie.function); + break; + default: + sprintf(strbuf, "", + devtopo->raw.type, + devtopo->raw.data[0], devtopo->raw.data[1], + devtopo->raw.data[2], + devtopo->raw.data[3], devtopo->raw.data[4]); + } +} + +int device_info_devtopo_amd(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_topology_amd val; + GET_VAL; + /* TODO how to do this in CLINFO_RAW mode */ + if (!had_error) { + devtopo_str(&val); + } + show_strbuf(pname, 0); + return had_error; +} + +/* we assemble a cl_device_topology_amd struct from the NVIDIA info */ +int device_info_devtopo_nv(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_topology_amd devtopo; + cl_uint val = 0; + + devtopo.raw.type = CL_DEVICE_TOPOLOGY_TYPE_PCIE_AMD; + + GET_VAL; /* CL_DEVICE_PCI_BUS_ID_NV */ + + if (!had_error) { + devtopo.pcie.bus = val & 0xff; + + param = CL_DEVICE_PCI_SLOT_ID_NV; + current_param = "CL_DEVICE_PCI_SLOT_ID_NV"; + + GET_VAL; + + if (!had_error) { + devtopo.pcie.device = val >> 3; + devtopo.pcie.function = val & 7; + devtopo_str(&devtopo); + } + } + + show_strbuf(pname, 0); + return had_error; +} + +/* NVIDIA Compute Capability */ +int device_info_cc_nv(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_uint major = 0, val = 0; + GET_VAL; /* MAJOR */ + if (!had_error) { + major = val; + param = CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV; + current_param = "CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV"; + GET_VAL; + if (!had_error) + snprintf(strbuf, bufsz, "%u.%u", major, val); + } + + show_strbuf(pname, 0); + return had_error; +} + +/* AMD GFXIP */ +int device_info_gfxip_amd(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_uint major = 0, val = 0; + GET_VAL; /* MAJOR */ + if (!had_error) { + major = val; + param = CL_DEVICE_GFXIP_MINOR_AMD; + current_param = "CL_DEVICE_GFXIP_MINOR_AMD"; + GET_VAL; + if (!had_error) + snprintf(strbuf, bufsz, "%u.%u", major, val); + } + + show_strbuf(pname, 0); + return had_error; +} + + +/* Device Partition, CLINFO_HUMAN header */ +int device_info_partition_header(cl_device_id dev UNUSED, cl_device_info param UNUSED, + const char *pname, const struct device_info_checks *chk) +{ + int is_12 = dev_is_12(chk); + int has_fission = dev_has_fission(chk); + size_t szval = snprintf(strbuf, bufsz, "(%s%s%s)", + (is_12 ? core : empty_str), + (is_12 && has_fission ? comma_str : empty_str), + chk->has_fission); + if (szval >= bufsz) + trunc_strbuf(); + + show_strbuf(pname, 0); + had_error = CL_SUCCESS; + return had_error; +} + +/* Device partition properties */ +int device_info_partition_types(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t numval = 0, szval = 0, cursor = 0, slen = 0; + cl_device_partition_property *val = NULL; + const char * const *ptstr = (output_mode == CLINFO_HUMAN ? + partition_type_str : partition_type_raw_str); + + set_separator(output_mode == CLINFO_HUMAN ? comma_str : vbar_str); + + GET_VAL_ARRAY; + + szval = 0; + if (!had_error) { + for (cursor = 0; cursor < numval; ++cursor) { + int str_idx = -1; + + /* add separator for values past the first */ + add_separator(&szval); + + switch (val[cursor]) { + case 0: str_idx = 1; break; + case CL_DEVICE_PARTITION_EQUALLY: str_idx = 2; break; + case CL_DEVICE_PARTITION_BY_COUNTS: str_idx = 3; break; + case CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN: str_idx = 4; break; + case CL_DEVICE_PARTITION_BY_NAMES_INTEL: str_idx = 5; break; + default: + szval += snprintf(strbuf + szval, bufsz - szval - 1, "by (0x%" PRIXPTR ")", val[cursor]); + break; + } + if (str_idx > 0) { + /* string length, minus _EXT */ + slen = strlen(ptstr[str_idx]); + if (output_mode == CLINFO_RAW && str_idx > 1) + slen -= 4; + szval += bufcpy_len(szval, ptstr[str_idx], slen); + } + if (szval >= bufsz) { + trunc_strbuf(); + break; + } + } + if (szval == 0) { + bufcpy(szval, ptstr[0]); + } else if (szval < bufsz) + strbuf[szval] = '\0'; + } + + show_strbuf(pname, 0); + + free(val); + return had_error; +} + +int device_info_partition_types_ext(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t numval = 0, szval = 0, cursor = 0, slen = 0; + cl_device_partition_property_ext *val = NULL; + const char * const *ptstr = (output_mode == CLINFO_HUMAN ? + partition_type_str : partition_type_raw_str); + + set_separator(output_mode == CLINFO_HUMAN ? comma_str : vbar_str); + + GET_VAL_ARRAY; + + szval = 0; + if (!had_error) { + for (cursor = 0; cursor < numval; ++cursor) { + int str_idx = -1; + + /* add separator for values past the first */ + add_separator(&szval); + + switch (val[cursor]) { + case 0: str_idx = 1; break; + case CL_DEVICE_PARTITION_EQUALLY_EXT: str_idx = 2; break; + case CL_DEVICE_PARTITION_BY_COUNTS_EXT: str_idx = 3; break; + case CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT: str_idx = 4; break; + case CL_DEVICE_PARTITION_BY_NAMES_EXT: str_idx = 5; break; + default: + szval += snprintf(strbuf + szval, bufsz - szval - 1, "by (0x%" PRIX64 ")", val[cursor]); + break; + } + if (str_idx > 0) { + /* string length */ + slen = strlen(ptstr[str_idx]); + strncpy(strbuf + szval, ptstr[str_idx], slen); + szval += slen; + } + if (szval >= bufsz) { + trunc_strbuf(); + break; + } + } + if (szval == 0) { + slen = strlen(ptstr[0]); + memcpy(strbuf, ptstr[0], slen); + szval += slen; + } + if (szval < bufsz) + strbuf[szval] = '\0'; + } + + show_strbuf(pname, 0); + + free(val); + return had_error; +} + + +/* Device partition affinity domains */ +int device_info_partition_affinities(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_affinity_domain val; + GET_VAL; + if (!had_error && val) { + /* iterate over affinity domain strings appending their textual form + * to strbuf + * TODO: check for extra bits/no bits + */ + size_t szval = 0; + cl_uint i = 0; + const char * const *affstr = (output_mode == CLINFO_HUMAN ? + affinity_domain_str : affinity_domain_raw_str); + set_separator(output_mode == CLINFO_HUMAN ? comma_str : vbar_str); + for (i = 0; i < affinity_domain_count; ++i) { + cl_device_affinity_domain cur = (cl_device_affinity_domain)(1) << i; + if (val & cur) { + /* match: add separator if not first match */ + add_separator(&szval); + szval += bufcpy(szval, affstr[i]); + } + if (szval >= bufsz) + break; + } + } + if (val || had_error) + show_strbuf(pname, 0); + return had_error; +} + +int device_info_partition_affinities_ext(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + size_t numval = 0, szval = 0, cursor = 0, slen = 0; + cl_device_partition_property_ext *val = NULL; + const char * const *ptstr = (output_mode == CLINFO_HUMAN ? + affinity_domain_ext_str : affinity_domain_raw_ext_str); + + set_separator(output_mode == CLINFO_HUMAN ? comma_str : vbar_str); + + GET_VAL_ARRAY; + + szval = 0; + if (!had_error) { + for (cursor = 0; cursor < numval; ++cursor) { + int str_idx = -1; + + /* add separator for values past the first */ + add_separator(&szval); + + switch (val[cursor]) { + case CL_AFFINITY_DOMAIN_NUMA_EXT: str_idx = 0; break; + case CL_AFFINITY_DOMAIN_L4_CACHE_EXT: str_idx = 1; break; + case CL_AFFINITY_DOMAIN_L3_CACHE_EXT: str_idx = 2; break; + case CL_AFFINITY_DOMAIN_L2_CACHE_EXT: str_idx = 3; break; + case CL_AFFINITY_DOMAIN_L1_CACHE_EXT: str_idx = 4; break; + case CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT: str_idx = 5; break; + default: + szval += snprintf(strbuf + szval, bufsz - szval - 1, " (0x%" PRIX64 ")", val[cursor]); + break; + } + if (str_idx >= 0) { + /* string length */ + const char *str = ptstr[str_idx]; + slen = strlen(str); + strncpy(strbuf + szval, str, slen); + szval += slen; + } + if (szval >= bufsz) { + trunc_strbuf(); + break; + } + } + strbuf[szval] = '\0'; + } + + show_strbuf(pname, 0); + + free(val); + return had_error; +} + +/* Preferred / native vector widths */ +int device_info_vecwidth(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk) +{ + cl_uint preferred = 0, val = 0; + GET_VAL; + if (!had_error) { + preferred = val; + + /* we get called with PREFERRED, NATIVE is at +0x30 offset, except for HALF, + * which is at +0x08 */ + param += (param == CL_DEVICE_PREFERRED_VECTOR_WIDTH_HALF ? 0x08 : 0x30); + /* TODO update current_param */ + GET_VAL; + + if (!had_error) { + size_t szval = 0; + const char *ext = (param == CL_DEVICE_NATIVE_VECTOR_WIDTH_HALF ? + chk->has_half : (param == CL_DEVICE_NATIVE_VECTOR_WIDTH_DOUBLE ? + chk->has_double : NULL)); + szval = sprintf(strbuf, "%8u / %-8u", preferred, val); + if (ext) + sprintf(strbuf + szval, " (%s)", *ext ? ext : na); + } + } + show_strbuf(pname, 0); + return had_error; +} + +/* Floating-point configurations */ +int device_info_fpconf(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk) +{ + cl_device_fp_config val = 0; + int get_it = ( + (param == CL_DEVICE_SINGLE_FP_CONFIG) || + (param == CL_DEVICE_HALF_FP_CONFIG && dev_has_half(chk)) || + (param == CL_DEVICE_DOUBLE_FP_CONFIG && dev_has_double(chk))); + if (get_it) + GET_VAL; + else + had_error = CL_SUCCESS; + + if (!had_error) { + size_t szval = 0; + cl_uint i = 0; + const char * const *fpstr = (output_mode == CLINFO_HUMAN ? + fp_conf_str : fp_conf_raw_str); + set_separator(vbar_str); + if (output_mode == CLINFO_HUMAN) { + const char *why = na; + switch (param) { + case CL_DEVICE_HALF_FP_CONFIG: + if (get_it) + why = chk->has_half; + break; + case CL_DEVICE_SINGLE_FP_CONFIG: + why = core; + break; + case CL_DEVICE_DOUBLE_FP_CONFIG: + if (get_it) + why = chk->has_double; + break; + default: + /* "this can't happen" (unless OpenCL starts supporting _other_ floating-point formats, maybe) */ + fprintf(stderr, "unsupported floating-point configuration parameter %s\n", pname); + + } + /* show 'why' it's being shown */ + szval += sprintf(strbuf, "(%s)", why); + } + if (get_it) { + for (i = 0; i < fp_conf_count; ++i) { + cl_device_fp_config cur = (cl_device_fp_config)(1) << i; + if (output_mode == CLINFO_HUMAN) { + szval += sprintf(strbuf + szval, "\n%s" I2_STR "%s", + line_pfx, fpstr[i], bool_str[!!(val & cur)]); + } else if (val & cur) { + add_separator(&szval); + szval += bufcpy(szval, fpstr[i]); + } + } + } + } + + /* only print this for HUMAN output or if we actually got the value */ + if (output_mode == CLINFO_HUMAN || get_it) + show_strbuf(pname, 0); + return had_error; +} + +/* Queue properties */ +int device_info_qprop(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk) +{ + cl_command_queue_properties val = 0; + GET_VAL; + if (!had_error) { + size_t szval = 0; + cl_uint i = 0; + const char * const *qpstr = (output_mode == CLINFO_HUMAN ? + queue_prop_str : queue_prop_raw_str); + set_separator(vbar_str); + for (i = 0; i < queue_prop_count; ++i) { + cl_command_queue_properties cur = (cl_command_queue_properties)(1) << i; + if (output_mode == CLINFO_HUMAN) { + szval += sprintf(strbuf + szval, "\n%s" I2_STR "%s", + line_pfx, qpstr[i], bool_str[!!(val & cur)]); + } else if (val & cur) { + add_separator(&szval); + szval += bufcpy(szval, qpstr[i]); + } + } + if (output_mode == CLINFO_HUMAN && param == CL_DEVICE_QUEUE_PROPERTIES && + dev_has_intel_local_thread(chk)) + sprintf(strbuf + szval, "\n%s" I2_STR "%s", + line_pfx, "Local thread execution (Intel)", bool_str[CL_TRUE]); + } + show_strbuf(pname, 0); + return had_error; +} + +/* Execution capbilities */ +int device_info_execap(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_device_exec_capabilities val = 0; + GET_VAL; + if (!had_error) { + size_t szval = 0; + cl_uint i = 0; + const char * const *qpstr = (output_mode == CLINFO_HUMAN ? + execap_str : execap_raw_str); + set_separator(vbar_str); + for (i = 0; i < execap_count; ++i) { + cl_device_exec_capabilities cur = (cl_device_exec_capabilities)(1) << i; + if (output_mode == CLINFO_HUMAN) { + szval += sprintf(strbuf + szval, "\n%s" I2_STR "%s", + line_pfx, qpstr[i], bool_str[!!(val & cur)]); + } else if (val & cur) { + add_separator(&szval); + szval += bufcpy(szval, qpstr[i]); + } + } + } + show_strbuf(pname, 0); + return had_error; +} + +/* Arch bits and endianness (HUMAN) */ +int device_info_arch(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk UNUSED) +{ + cl_uint bits = 0; + { + cl_uint val = 0; + GET_VAL; + if (!had_error) + bits = val; + } + if (!had_error) { + cl_bool val = 0; + param = CL_DEVICE_ENDIAN_LITTLE; + current_param = "CL_DEVICE_ENDIAN_LITTLE"; + GET_VAL; + if (!had_error) + sprintf(strbuf, "%u, %s", bits, endian_str[val]); + } + show_strbuf(pname, 0); + return had_error; +} + +/* SVM capabilities */ +int device_info_svm_cap(cl_device_id dev, cl_device_info param, const char *pname, + const struct device_info_checks *chk) +{ + cl_device_svm_capabilities val = 0; + int is_20 = dev_is_20(chk); + int has_svm_ext = dev_has_svm_ext(chk); + + GET_VAL; + + if (!had_error) { + size_t szval = 0; + cl_uint i = 0; + const char * const *scstr = (output_mode == CLINFO_HUMAN ? + svm_cap_str : svm_cap_raw_str); + set_separator(vbar_str); + if (output_mode == CLINFO_HUMAN) { + /* show 'why' it's being shown */ + szval += sprintf(strbuf, "(%s%s%s)", + (is_20 ? core : empty_str), + (is_20 && has_svm_ext ? comma_str : empty_str), + chk->has_svm_ext); + } + for (i = 0; i < svm_cap_count; ++i) { + cl_device_svm_capabilities cur = (cl_device_svm_capabilities)(1) << i; + if (output_mode == CLINFO_HUMAN) { + szval += sprintf(strbuf + szval, "\n%s" I2_STR "%s", + line_pfx, scstr[i], bool_str[!!(val & cur)]); + } else if (val & cur) { + add_separator(&szval); + szval += bufcpy(szval, scstr[i]); + } + } + } + + show_strbuf(pname, 0); + return had_error; +} + +/* + * Device info traits + */ + +/* A CL_FALSE param means "just print pname" */ + +struct device_info_traits { + enum output_modes output_mode; + cl_device_info param; // CL_DEVICE_* + const char *sname; // "CL_DEVICE_*" + const char *pname; // "Device *" + const char *sfx; // suffix for the output in non-raw mode + /* pointer to function that shows the parameter */ + int (*show_func)(cl_device_id dev, cl_device_info param, const char *pname, const struct device_info_checks *); + /* pointer to function that checks if the parameter should be checked */ + int (*check_func)(const struct device_info_checks *); +}; + +#define DINFO_SFX(symbol, name, sfx, typ) symbol, #symbol, name, sfx, device_info_##typ +#define DINFO(symbol, name, typ) symbol, #symbol, name, NULL, device_info_##typ + +struct device_info_traits dinfo_traits[] = { + { CLINFO_BOTH, DINFO(CL_DEVICE_NAME, "Device Name", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_VENDOR, "Device Vendor", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_VENDOR_ID, "Device Vendor ID", hex), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_VERSION, "Device Version", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DRIVER_VERSION, "Driver Version", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_OPENCL_C_VERSION, "Device OpenCL C Version", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_EXTENSIONS, "Device Extensions", str_get), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_TYPE, "Device Type", devtype), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PROFILE, "Device Profile", str), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_BOARD_NAME_AMD, "Device Board Name (AMD)", str), dev_has_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_TOPOLOGY_AMD, "Device Topology (AMD)", devtopo_amd), dev_has_amd }, + + /* Device Topology (NV) is multipart, so different for HUMAN and RAW */ + { CLINFO_HUMAN, DINFO(CL_DEVICE_PCI_BUS_ID_NV, "Device Topology (NV)", devtopo_nv), dev_has_nv }, + { CLINFO_RAW, DINFO(CL_DEVICE_PCI_BUS_ID_NV, "Device PCI bus (NV)", int), dev_has_nv }, + { CLINFO_RAW, DINFO(CL_DEVICE_PCI_SLOT_ID_NV, "Device PCI slot (NV)", int), dev_has_nv }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_COMPUTE_UNITS, "Max compute units", int), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_SIMD_PER_COMPUTE_UNIT_AMD, "SIMD per compute unit (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_SIMD_WIDTH_AMD, "SIMD width (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_SIMD_INSTRUCTION_WIDTH_AMD, "SIMD instruction width (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_MAX_CLOCK_FREQUENCY, "Max clock frequency", "MHz", int), NULL }, + + /* Device Compute Capability (NV) is multipart, so different for HUMAN and RAW */ + { CLINFO_HUMAN, DINFO(CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV, "Compute Capability (NV)", cc_nv), dev_has_nv }, + { CLINFO_RAW, DINFO(CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV, INDENT "Compute Capability Major (NV)", int), dev_has_nv }, + { CLINFO_RAW, DINFO(CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV, INDENT "Compute Capability Minor (NV)", int), dev_has_nv }, + + /* GFXIP (AMD) is multipart, so different for HUMAN and RAW */ + /* TODO: find a better human-friendly name than GFXIP; v3 of the cl_amd_device_attribute_query + * extension specification calls it “core engine GFXIP”, which honestly is not better than + * our name choice. */ + { CLINFO_HUMAN, DINFO(CL_DEVICE_GFXIP_MAJOR_AMD, "Graphics IP (AMD)", gfxip_amd), dev_is_gpu_amd }, + { CLINFO_RAW, DINFO(CL_DEVICE_GFXIP_MAJOR_AMD, INDENT "Graphics IP MAJOR (AMD)", int), dev_is_gpu_amd }, + { CLINFO_RAW, DINFO(CL_DEVICE_GFXIP_MINOR_AMD, INDENT "Graphics IP MINOR (AMD)", int), dev_is_gpu_amd }, + + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_CORE_TEMPERATURE_ALTERA, "Core Temperature (Altera)", " C", int), dev_has_altera_dev_temp }, + + /* Device partition support: summary is only presented in HUMAN case */ + { CLINFO_HUMAN, DINFO(CL_DEVICE_PARTITION_MAX_SUB_DEVICES, "Device Partition", partition_header), dev_has_partition }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PARTITION_MAX_SUB_DEVICES, INDENT "Max number of sub-devices", int), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PARTITION_PROPERTIES, INDENT "Supported partition types", partition_types), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PARTITION_AFFINITY_DOMAIN, INDENT "Supported affinity domains", partition_affinities), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PARTITION_TYPES_EXT, INDENT "Supported partition types (ext)", partition_types_ext), dev_has_fission }, + { CLINFO_BOTH, DINFO(CL_DEVICE_AFFINITY_DOMAINS_EXT, INDENT "Supported affinity domains (ext)", partition_affinities_ext), dev_has_fission }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS, "Max work item dimensions", int), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_WORK_ITEM_SIZES, "Max work item sizes", szptr), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_WORK_GROUP_SIZE, "Max work group size", sz), NULL }, + { CLINFO_BOTH, DINFO(CL_KERNEL_PREFERRED_WORK_GROUP_SIZE_MULTIPLE, "Preferred work group size multiple", wg), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_WARP_SIZE_NV, "Warp size (NV)", int), dev_has_nv }, + { CLINFO_BOTH, DINFO(CL_DEVICE_WAVEFRONT_WIDTH_AMD, "Wavefront width (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_NUM_SUB_GROUPS, "Max sub-groups per work group", int), dev_is_21 }, + + /* Preferred/native vector widths: header is only presented in HUMAN case, that also pairs + * PREFERRED and NATIVE in a single line */ +#define DINFO_VECWIDTH(Type, type) \ + { CLINFO_HUMAN, DINFO(CL_DEVICE_PREFERRED_VECTOR_WIDTH_##Type, INDENT #type, vecwidth), NULL }, \ + { CLINFO_RAW, DINFO(CL_DEVICE_PREFERRED_VECTOR_WIDTH_##Type, INDENT #type, int), NULL }, \ + { CLINFO_RAW, DINFO(CL_DEVICE_NATIVE_VECTOR_WIDTH_##Type, INDENT #type, int), NULL } + + { CLINFO_HUMAN, DINFO(CL_FALSE, "Preferred / native vector sizes", str), NULL }, + DINFO_VECWIDTH(CHAR, char), + DINFO_VECWIDTH(SHORT, short), + DINFO_VECWIDTH(INT, int), + DINFO_VECWIDTH(LONG, long), + DINFO_VECWIDTH(HALF, half), + DINFO_VECWIDTH(FLOAT, float), + DINFO_VECWIDTH(DOUBLE, double), + + /* Floating point configurations */ +#define DINFO_FPCONF(Type, type, cond) \ + { CLINFO_BOTH, DINFO(CL_DEVICE_##Type##_FP_CONFIG, #type "-precision Floating-point support", fpconf), NULL } + + DINFO_FPCONF(HALF, Half, dev_has_half), + DINFO_FPCONF(SINGLE, Single, NULL), + DINFO_FPCONF(DOUBLE, Double, dev_has_double), + + /* Address bits and endianness are written together for HUMAN, separate for RAW */ + { CLINFO_HUMAN, DINFO(CL_DEVICE_ADDRESS_BITS, "Address bits", arch), NULL }, + { CLINFO_RAW, DINFO(CL_DEVICE_ADDRESS_BITS, "Address bits", int), NULL }, + { CLINFO_RAW, DINFO(CL_DEVICE_ENDIAN_LITTLE, "Little Endian", bool), NULL }, + + /* Global memory */ + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_MEM_SIZE, "Global memory size", mem), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_FREE_MEMORY_AMD, "Global free memory (AMD)", free_mem_amd), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_MEM_CHANNELS_AMD, "Global memory channels (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_MEM_CHANNEL_BANKS_AMD, "Global memory banks per channel (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_GLOBAL_MEM_CHANNEL_BANK_WIDTH_AMD, "Global memory bank width (AMD)", bytes_str, int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_ERROR_CORRECTION_SUPPORT, "Error Correction support", bool), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_MEM_ALLOC_SIZE, "Max memory allocation", mem), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_HOST_UNIFIED_MEMORY, "Unified memory for Host and Device", bool), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_INTEGRATED_MEMORY_NV, "Integrated memory (NV)", bool), dev_has_nv }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_SVM_CAPABILITIES, "Shared Virtual Memory (SVM) capabilities", svm_cap), dev_has_svm }, + + /* Alignment */ + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE, "Minimum alignment for any data type", bytes_str, int), NULL }, + { CLINFO_HUMAN, DINFO(CL_DEVICE_MEM_BASE_ADDR_ALIGN, "Alignment of base address", bits), NULL }, + { CLINFO_RAW, DINFO(CL_DEVICE_MEM_BASE_ADDR_ALIGN, "Alignment of base address", int), NULL }, + + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_PAGE_SIZE_QCOM, "Page size (QCOM)", bytes_str, sz), dev_has_qcom_ext_host_ptr }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM, "Externa memory padding (QCOM)", bytes_str, sz), dev_has_qcom_ext_host_ptr }, + + /* Atomics alignment, with HUMAN-only header */ + { CLINFO_HUMAN, DINFO(CL_FALSE, "Preferred alignment for atomics", str), dev_is_20 }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_PREFERRED_PLATFORM_ATOMIC_ALIGNMENT, INDENT "SVM", bytes_str, int), dev_is_20 }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_PREFERRED_GLOBAL_ATOMIC_ALIGNMENT, INDENT "Global", bytes_str, int), dev_is_20 }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_PREFERRED_LOCAL_ATOMIC_ALIGNMENT, INDENT "Local", bytes_str, int), dev_is_20 }, + + /* Global variables. TODO some 1.2 devices respond to this too */ + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_GLOBAL_VARIABLE_SIZE, "Max size for global variable", mem), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_VARIABLE_PREFERRED_TOTAL_SIZE, "Preferred total size of global vars", mem), dev_is_20 }, + + /* Global memory cache */ + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_MEM_CACHE_TYPE, "Global Memory cache type", cachetype), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GLOBAL_MEM_CACHE_SIZE, "Global Memory cache size", sz), dev_has_cache }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE, "Global Memory cache line", " bytes", int), dev_has_cache }, + + /* Image support */ + { CLINFO_BOTH, DINFO(CL_DEVICE_IMAGE_SUPPORT, "Image support", bool), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_SAMPLERS, INDENT "Max number of samplers per kernel", int), dev_has_images }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_IMAGE_MAX_BUFFER_SIZE, INDENT "Max size for 1D images from buffer", pixels_str, sz), dev_has_images_12 }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_IMAGE_MAX_ARRAY_SIZE, INDENT "Max 1D or 2D image array size", images_str, sz), dev_has_images_12 }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT, INDENT "Base address alignment for 2D image buffers", bytes_str, sz), dev_has_image2d_buffer }, + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_IMAGE_PITCH_ALIGNMENT, INDENT "Pitch alignment for 2D image buffers", bytes_str, sz), dev_has_image2d_buffer }, + + /* Image dimensions are split for RAW, combined for HUMAN */ + { CLINFO_HUMAN, DINFO_SFX(CL_DEVICE_IMAGE2D_MAX_HEIGHT, INDENT "Max 2D image size", pixels_str, img_sz_2d), dev_has_images }, + { CLINFO_RAW, DINFO(CL_DEVICE_IMAGE2D_MAX_HEIGHT, INDENT "Max 2D image height", sz), dev_has_images }, + { CLINFO_RAW, DINFO(CL_DEVICE_IMAGE2D_MAX_WIDTH, INDENT "Max 2D image width", sz), dev_has_images }, + { CLINFO_HUMAN, DINFO_SFX(CL_DEVICE_IMAGE3D_MAX_HEIGHT, INDENT "Max 3D image size", pixels_str, img_sz_3d), dev_has_images }, + { CLINFO_RAW, DINFO(CL_DEVICE_IMAGE3D_MAX_HEIGHT, INDENT "Max 3D image height", sz), dev_has_images }, + { CLINFO_RAW, DINFO(CL_DEVICE_IMAGE3D_MAX_WIDTH, INDENT "Max 3D image width", sz), dev_has_images }, + { CLINFO_RAW, DINFO(CL_DEVICE_IMAGE3D_MAX_DEPTH, INDENT "Max 3D image depth", sz), dev_has_images }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_READ_IMAGE_ARGS, INDENT "Max number of read image args", int), dev_has_images }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_WRITE_IMAGE_ARGS, INDENT "Max number of write image args", int), dev_has_images }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_READ_WRITE_IMAGE_ARGS, INDENT "Max number of read/write image args", int), dev_has_images_20 }, + + /* Pipes */ + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_PIPE_ARGS, "Max number of pipe args", int), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PIPE_MAX_ACTIVE_RESERVATIONS, "Max active pipe reservations", int), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PIPE_MAX_PACKET_SIZE, "Max pipe packet size", mem_int), dev_is_20 }, + + /* Local memory */ + { CLINFO_BOTH, DINFO(CL_DEVICE_LOCAL_MEM_TYPE, "Local memory type", lmemtype), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_LOCAL_MEM_SIZE, "Local memory size", mem), dev_has_lmem }, + { CLINFO_BOTH, DINFO(CL_DEVICE_LOCAL_MEM_SIZE_PER_COMPUTE_UNIT_AMD, "Local memory syze per CU (AMD)", mem), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_LOCAL_MEM_BANKS_AMD, "Local memory banks (AMD)", int), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_REGISTERS_PER_BLOCK_NV, "Registers per block (NV)", int), dev_has_nv }, + + /* Constant memory */ + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE, "Max constant buffer size", mem), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_CONSTANT_ARGS, "Max number of constant args", int), NULL }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_PARAMETER_SIZE, "Max size of kernel argument", mem), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_ATOMIC_COUNTERS_EXT, "Max number of atomic counters", sz), dev_has_atomic_counters }, + + /* Queue properties */ + { CLINFO_BOTH, DINFO(CL_DEVICE_QUEUE_PROPERTIES, "Queue properties", qprop), dev_not_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_QUEUE_PROPERTIES, "Queue properties (on host)", qprop), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_QUEUE_ON_DEVICE_PROPERTIES, "Queue properties (on device)", qprop), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_QUEUE_ON_DEVICE_PREFERRED_SIZE, INDENT "Preferred size", mem), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_QUEUE_ON_DEVICE_MAX_SIZE, INDENT "Max size", mem), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_ON_DEVICE_QUEUES, "Max queues on device", int), dev_is_20 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_MAX_ON_DEVICE_EVENTS, "Max events on device", int), dev_is_20 }, + + /* Interop */ + { CLINFO_BOTH, DINFO(CL_DEVICE_PREFERRED_INTEROP_USER_SYNC, "Prefer user sync for interop", bool), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_NUM_SIMULTANEOUS_INTEROPS_INTEL, "Number of simulataneous interops (Intel)", int), dev_has_simultaneous_sharing }, + /* TODO: this needs defines for the possible values of the context interops, + { CLINFO_BOTH, DINFO(CL_DEVICE_SIMULTANEOUS_INTEROPS_INTEL, "Simulataneous interops", interop_list), dev_has_simultaneous_sharing }, + */ + + /* Profiling resolution */ + { CLINFO_BOTH, DINFO_SFX(CL_DEVICE_PROFILING_TIMER_RESOLUTION, "Profiling timer resolution", "ns", long), NULL }, + { CLINFO_HUMAN, DINFO(CL_DEVICE_PROFILING_TIMER_OFFSET_AMD, "Profiling timer offset since Epoch (AMD)", time_offset), dev_has_amd }, + { CLINFO_RAW, DINFO(CL_DEVICE_PROFILING_TIMER_OFFSET_AMD, "Profiling timer offset since Epoch (AMD)", long), dev_has_amd }, + + /* Kernel execution capabilities */ + { CLINFO_BOTH, DINFO(CL_DEVICE_EXECUTION_CAPABILITIES, "Execution capabilities", execap), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_SUB_GROUP_INDEPENDENT_FORWARD_PROGRESS, INDENT "Sub-group independent forward progress", bool), dev_is_21 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_THREAD_TRACE_SUPPORTED_AMD, INDENT "Thread trace supported (AMD)", bool), dev_is_gpu_amd }, + { CLINFO_BOTH, DINFO(CL_DEVICE_KERNEL_EXEC_TIMEOUT_NV, INDENT "Kernel execution timeout (NV)", bool), dev_has_nv }, + { CLINFO_BOTH, DINFO(CL_DEVICE_GPU_OVERLAP_NV, "Concurrent copy and kernel execution (NV)", bool), dev_has_nv }, + { CLINFO_BOTH, DINFO(CL_DEVICE_ATTRIBUTE_ASYNC_ENGINE_COUNT_NV, INDENT "Number of async copy engines", int), dev_has_nv }, + /* TODO FIXME Current drivers don't seem to respond to this, should probably be queried based on driver version, + * or maybe it depends on some other device property? + { CLINFO_BOTH, DINFO(CL_DEVICE_AVAILABLE_ASYNC_QUEUES_AMD, INDENT "Number of async queues (AMD)", int), dev_is_gpu_amd }, + */ + { CLINFO_BOTH, DINFO(CL_DEVICE_IL_VERSION, INDENT "IL version", str), dev_is_21, }, + { CLINFO_BOTH, DINFO(CL_DEVICE_SPIR_VERSIONS, INDENT "SPIR versions", str), dev_has_spir }, + { CLINFO_BOTH, DINFO(CL_DEVICE_PRINTF_BUFFER_SIZE, "printf() buffer size", mem), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_BUILT_IN_KERNELS, "Built-in kernels", str), dev_is_12 }, + { CLINFO_BOTH, DINFO(CL_DEVICE_ME_VERSION_INTEL, "Motion Estimation accelerator version (Intel)", int), dev_has_intel_AME }, + + { CLINFO_BOTH, DINFO(CL_DEVICE_AVAILABLE, "Device Available", bool), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_COMPILER_AVAILABLE, "Compiler Available", bool), NULL }, + { CLINFO_BOTH, DINFO(CL_DEVICE_LINKER_AVAILABLE, "Linker Available", bool), dev_is_12 }, +}; + +/* Process all the device info in the traits, except if param_whitelist is not NULL, + * in which case only those in the whitelist will be processed. + * If present, the whitelist should be sorted in the order of appearance of the parameters + * in the traits table, and terminated by the value CL_FALSE + */ + +void +printDeviceInfo(const cl_device_id *device, cl_uint d, + const cl_device_info *param_whitelist) /* list of device info to process, or NULL */ +{ + cl_device_id dev = device[d]; + + char *extensions = NULL; + + /* pointer to the traits for CL_DEVICE_EXTENSIONS */ + const struct device_info_traits *extensions_traits = NULL; + + struct device_info_checks chk; + memset(&chk, 0, sizeof(chk)); + chk.dev_version = 10; + + current_function = __func__; + + for (current_line = 0; current_line < ARRAY_SIZE(dinfo_traits); ++current_line) { + + const struct device_info_traits *traits = dinfo_traits + current_line; + const char *pname = (output_mode == CLINFO_HUMAN ? + traits->pname : traits->sname); + + current_param = traits->sname; + + /* Whitelist check: finish if done traversing the list, + * skip current param if it's not the right one + */ + if (param_whitelist) { + if (*param_whitelist == CL_FALSE) + break; + if (traits->param != *param_whitelist) + continue; + ++param_whitelist; + } + + /* skip if it's not for this output mode */ + if (!(output_mode & traits->output_mode)) + continue; + + if (traits->check_func && !traits->check_func(&chk)) + continue; + + cur_sfx = (output_mode == CLINFO_HUMAN && traits->sfx) ? traits->sfx : empty_str; + + /* Handle headers */ + if (traits->param == CL_FALSE) { + strbuf[0] = '\0'; + show_strbuf(pname, 0); + had_error = CL_FALSE; + continue; + } + + had_error = traits->show_func(dev, traits->param, + pname, &chk); + + if (traits->param == CL_DEVICE_EXTENSIONS) { + /* make a backup of the extensions string, regardless of + * errors */ + size_t len = strlen(strbuf); + extensions_traits = traits; + ALLOC(extensions, len+1, "extensions"); + memcpy(extensions, strbuf, len); + extensions[len] = '\0'; + } + + if (had_error) + continue; + + switch (traits->param) { + case CL_DEVICE_VERSION: + /* compute numeric value for OpenCL version */ + chk.dev_version = getOpenCLVersion(strbuf + 7); + break; + case CL_DEVICE_EXTENSIONS: + identify_device_extensions(extensions, &chk); + break; + case CL_DEVICE_TYPE: + /* strbuf was abused to give us the dev type */ + memcpy(&(chk.devtype), strbuf, sizeof(chk.devtype)); + break; + case CL_DEVICE_GLOBAL_MEM_CACHE_TYPE: + /* strbuf was abused to give us the cache type */ + memcpy(&(chk.cachetype), strbuf, sizeof(chk.cachetype)); + break; + case CL_DEVICE_LOCAL_MEM_TYPE: + /* strbuf was abused to give us the lmem type */ + memcpy(&(chk.lmemtype), strbuf, sizeof(chk.lmemtype)); + break; + case CL_DEVICE_IMAGE_SUPPORT: + /* strbuf was abused to give us boolean value */ + memcpy(&(chk.image_support), strbuf, sizeof(chk.image_support)); + break; + default: + /* do nothing */ + break; + } + } + + // and finally the extensions, if we retrieved them + if (extensions) + LOGI("%s" I1_STR "%s\n", line_pfx, (output_mode == CLINFO_HUMAN ? + extensions_traits->pname : + extensions_traits->sname), extensions); + free(extensions); + extensions = NULL; +} + +/* list of allowed properties for AMD offline devices */ +/* everything else seems to be set to 0, and all the other string properties + * actually segfault the driver */ + +static const cl_device_info amd_offline_info_whitelist[] = { + CL_DEVICE_NAME, + /* These are present, but all the same, so just skip them: + CL_DEVICE_VENDOR, + CL_DEVICE_VENDOR_ID, + CL_DEVICE_VERSION, + CL_DRIVER_VERSION, + CL_DEVICE_OPENCL_C_VERSION, + */ + CL_DEVICE_EXTENSIONS, + CL_DEVICE_TYPE, + CL_DEVICE_MAX_WORK_GROUP_SIZE, + CL_DEVICE_AVAILABLE +}; + +/* process offline devices from the cl_amd_offline_devices extension */ +int processOfflineDevicesAMD(cl_uint p) +{ + int ret = 0; + + cl_platform_id pid = platform[p]; + cl_device_id *device = NULL; + cl_int num_devs, d; + + cl_context_properties ctxpft[] = { + CL_CONTEXT_PLATFORM, (cl_context_properties)pid, + CL_CONTEXT_OFFLINE_DEVICES_AMD, (cl_context_properties)CL_TRUE, + 0 + }; + + cl_context ctx = NULL; + + if (!list_only) + LOGI("%s" I0_STR, line_pfx, + (output_mode == CLINFO_HUMAN ? + "Number of offline devices (AMD)" : "#OFFDEVICES")); + + ctx = clCreateContextFromType(ctxpft, CL_DEVICE_TYPE_ALL, NULL, NULL, &error); + RR_ERROR("create context"); + + error = clGetContextInfo(ctx, CL_CONTEXT_NUM_DEVICES, sizeof(num_devs), &num_devs, NULL); + RR_ERROR("get num devs"); + + ALLOC(device, num_devs, "offline devices"); + + error = clGetContextInfo(ctx, CL_CONTEXT_DEVICES, num_devs*sizeof(*device), device, NULL); + RR_ERROR("get devs"); + + if (!list_only) + LOGI("%d\n", num_devs); + + for (d = 0; d < num_devs; ++d) { + if (list_only) { + /* + if (output_mode == CLINFO_HUMAN) + puts(" |"); + */ + if (d == num_devs - 1 && output_mode != CLINFO_RAW) + line_pfx[1] = '`'; + had_error = device_info_str_get(device[d], CL_DEVICE_NAME, "CL_DEVICE_NAME", NULL); + LOGI("%s%u: %s\n", line_pfx, d, strbuf); + } else { + if (line_pfx_len > 0) { + sprintf(strbuf, "[%s/%u]", pdata[p].sname, -d); + sprintf(line_pfx, "%*s", -line_pfx_len, strbuf); + } + printDeviceInfo(device, d, amd_offline_info_whitelist); + if (d < num_devs - 1) + puts(""); + } + fflush(stdout); + fflush(stderr); + } + + had_error = CL_FALSE; + out: + free(device); + if (ctx) + clReleaseContext(ctx); + return ret; + +} + +void listPlatformsAndDevices(cl_bool show_offline) +{ + cl_uint p, d; + cl_device_id *device; + + if (output_mode == CLINFO_RAW) + sprintf(strbuf, "%u", num_platforms); + else + sprintf(strbuf, " +-- %sDevice #", (show_offline ? "Offline" : "")); + + line_pfx_len = strlen(strbuf) + 1; + REALLOC(line_pfx, line_pfx_len, "line prefix"); + + for (p = 0, device = all_devices; p < num_platforms; device += pdata[p++].ndevs) { + LOGI("%s%u: %s\n", + (output_mode == CLINFO_HUMAN ? "Platform #" : ""), + p, pdata[p].pname); + if (output_mode == CLINFO_RAW) + sprintf(line_pfx, "%u:", p); + else + sprintf(line_pfx, " +-- Device #"); + + if (pdata[p].ndevs > 0) { + error = clGetDeviceIDs(platform[p], CL_DEVICE_TYPE_ALL, pdata[p].ndevs, device, NULL); + CHECK_ERROR("device IDs"); + for (d = 0; d < pdata[p].ndevs; ++d) { + /* + if (output_mode == CLINFO_HUMAN) + puts(" |"); + */ + cl_bool last_device = (d == pdata[p].ndevs - 1 && output_mode != CLINFO_RAW && + (!show_offline || !pdata[p].has_amd_offline)); + if (last_device) + line_pfx[1] = '`'; + had_error = device_info_str_get(device[d], CL_DEVICE_NAME, "CL_DEVICE_NAME", NULL); + LOGI("%s%u: %s\n", line_pfx, d, strbuf); + fflush(stdout); + fflush(stderr); + } + } + + if (show_offline && pdata[p].has_amd_offline) { + if (output_mode == CLINFO_RAW) + sprintf(line_pfx, "%u*", p); + else + sprintf(line_pfx, " +-- Offline Device #"); + had_error = processOfflineDevicesAMD(p); + if (had_error) + puts(strbuf); + } + } +} + +void showDevices(cl_bool show_offline) +{ + cl_uint p, d; + cl_device_id *device; + + /* TODO consider enabling this for both output modes */ + if (output_mode == CLINFO_RAW) { + sprintf(strbuf, "%u", maxdevs); + line_pfx_len = platform_sname_maxlen + strlen(strbuf) + 4; + REALLOC(line_pfx, line_pfx_len, "line prefix"); + } + + for (p = 0, device = all_devices; p < num_platforms; device += pdata[p++].ndevs) { + if (line_pfx_len > 0) { + sprintf(strbuf, "[%s/*]", pdata[p].sname); + sprintf(line_pfx, "%*s", -line_pfx_len, strbuf); + } + LOGI("%s" I1_STR "%s\n", + line_pfx, + (output_mode == CLINFO_HUMAN ? + pinfo_traits[0].pname : pinfo_traits[0].sname), + pdata[p].pname); + LOGI("%s" I0_STR "%u\n", + line_pfx, + (output_mode == CLINFO_HUMAN ? + "Number of devices" : "#DEVICES"), + pdata[p].ndevs); + + if (pdata[p].ndevs > 0) { + error = clGetDeviceIDs(platform[p], CL_DEVICE_TYPE_ALL, pdata[p].ndevs, device, NULL); + CHECK_ERROR("device IDs"); + } + for (d = 0; d < pdata[p].ndevs; ++d) { + if (line_pfx_len > 0) { + sprintf(strbuf, "[%s/%u]", pdata[p].sname, d); + sprintf(line_pfx, "%*s", -line_pfx_len, strbuf); + } + printDeviceInfo(device, d, NULL); + if (d < pdata[p].ndevs - 1) + puts(""); + fflush(stdout); + fflush(stderr); + } + if (show_offline && pdata[p].has_amd_offline) { + puts(""); + had_error = processOfflineDevicesAMD(p); + if (had_error) + puts(strbuf); + } + puts(""); + } +} + +/* check the behavior of clGetPlatformInfo() when given a NULL platform ID */ +void checkNullGetPlatformName(void) +{ + current_param = "CL_PLATFORM_NAME"; + + error = clGetPlatformInfo(NULL, CL_PLATFORM_NAME, bufsz, strbuf, NULL); + if (error == CL_INVALID_PLATFORM) { + bufcpy(0, no_plat()); + } else { + current_line = __LINE__+1; + had_error = REPORT_ERROR2("get %s"); + } +LOGI(I1_STR "%s\n", + "clGetPlatformInfo(NULL, CL_PLATFORM_NAME, ...)", strbuf); +} + +/* check the behavior of clGetDeviceIDs() when given a NULL platform ID; + * return the index of the default platform in our array of platform IDs, + * or num_platforms (which is an invalid platform index) in case of errors + * or no platform or device found. + */ +cl_uint checkNullGetDevices(void) +{ + cl_uint i = 0; /* generic iterator */ + cl_device_id dev = NULL; /* sample device */ + cl_platform_id plat = NULL; /* detected platform */ + + cl_uint found = 0; /* number of platforms found */ + cl_uint pidx = num_platforms; /* index of the platform found */ + cl_uint numdevs = 0; + + current_function = __func__; + current_param = "device IDs"; + + error = clGetDeviceIDs(NULL, CL_DEVICE_TYPE_ALL, 0, NULL, &numdevs); + /* TODO we should check other CL_DEVICE_TYPE_* combinations, since a smart + * implementation might give you a different default platform for GPUs + * and for CPUs. + * Of course the “no devices” case would then need to be handled differently. + * The logic might be maintained similarly, provided we also gather + * the number of devices of each type for each platform, although it's + * obviously more likely to have multiple platforms with no devices + * of a given type. + */ + + switch (error) { + case CL_INVALID_PLATFORM: + bufcpy(0, no_plat()); + break; + case CL_DEVICE_NOT_FOUND: + /* No devices were found, see if there are platforms with + * no devices, and if there's only one, assume this is the + * one being used as default by the ICD loader */ + for (i = 0; i < num_platforms; ++i) { + if (pdata[i].ndevs == 0) { + ++found; + if (found > 1) + break; + else { + plat = platform[i]; + pidx = i; + } + } + } + + switch (found) { + case 0: + bufcpy(0, (output_mode == CLINFO_HUMAN ? + "" : + "CL_DEVICE_NOT_FOUND | CL_INVALID_PLATFORM")); + break; + case 1: + bufcpy(0, (output_mode == CLINFO_HUMAN ? + pdata[pidx].pname : + pdata[pidx].sname)); + break; + default: /* found > 1 */ + bufcpy(0, (output_mode == CLINFO_HUMAN ? + "" : + "CL_DEVICE_NOT_FOUND | ????")); + break; + } + break; + default: + current_line = __LINE__+1; + had_error = REPORT_ERROR2("get number of %s"); + if (had_error) + break; + + /* Determine platform by looking at the CL_DEVICE_PLATFORM of + * one of the devices */ + error = clGetDeviceIDs(NULL, CL_DEVICE_TYPE_ALL, 1, &dev, NULL); + current_line = __LINE__+1; + had_error = REPORT_ERROR2("get %s"); + if (had_error) + break; + + current_param = "CL_DEVICE_PLATFORM"; + error = clGetDeviceInfo(dev, CL_DEVICE_PLATFORM, + sizeof(plat), &plat, NULL); + current_line = __LINE__+1; + had_error = REPORT_ERROR2("get %s"); + if (had_error) + break; + + for (i = 0; i < num_platforms; ++i) { + if (platform[i] == plat) { + pidx = i; + sprintf(strbuf, "%s [%s]", + (output_mode == CLINFO_HUMAN ? "Success" : "CL_SUCCESS"), + pdata[i].sname); + break; + } + } + if (i == num_platforms) { + sprintf(strbuf, "", plat); + } + } +LOGI(I1_STR "%s\n", + "clGetDeviceIDs(NULL, CL_DEVICE_TYPE_ALL, ...)", strbuf); + return pidx; +} + +void checkNullCtx(cl_uint pidx, const cl_device_id *dev, const char *which) +{ + cl_context ctx = clCreateContext(NULL, 1, dev, NULL, NULL, &error); + + current_function = __func__; + current_param = which; + current_line = __LINE__+2; + + had_error = REPORT_ERROR2("create context with device from %s platform"); + if (!had_error) + sprintf(strbuf, "%s [%s]", + (output_mode == CLINFO_HUMAN ? "Success" : "CL_SUCCESS"), + pdata[pidx].sname); + if (ctx) { + clReleaseContext(ctx); + ctx = NULL; + } +} + +/* check behavior of clCreateContextFromType() with NULL cl_context_properties */ +void checkNullCtxFromType(void) +{ + size_t t; /* type iterator */ + size_t i; /* generic iterator */ + char def[1024]; + cl_context ctx = NULL; + + size_t ndevs = 8; + size_t szval = 0; + size_t cursz = ndevs*sizeof(cl_device_id); + cl_platform_id plat = NULL; + cl_device_id *devs = NULL; + + const char *platname_prop = (output_mode == CLINFO_HUMAN ? + pinfo_traits[0].pname : + pinfo_traits[0].sname); + + const char *devname_prop = (output_mode == CLINFO_HUMAN ? + dinfo_traits[0].pname : + dinfo_traits[0].sname); + + ALLOC(devs, ndevs, "context devices"); + + current_function = __func__; + for (t = 2; t < devtype_count; ++t) { /* we skip 0 and _DEFAULT */ + current_param = device_type_raw_str[t]; + + sprintf(strbuf, "clCreateContextFromType(NULL, %s)", current_param); + sprintf(def, I1_STR, strbuf); + + current_line = __LINE__+1; + ctx = clCreateContextFromType(NULL, devtype[t], NULL, NULL, &error); + + switch (error) { + case CL_INVALID_PLATFORM: + bufcpy(0, no_plat()); break; + case CL_DEVICE_NOT_FOUND: + case CL_INVALID_DEVICE_TYPE: /* e.g. _CUSTOM device on 1.1 platform */ + bufcpy(0, no_dev()); break; + case CL_DEVICE_NOT_AVAILABLE: + bufcpy(0, no_dev_avail()); break; + default: + had_error = REPORT_ERROR2("create context from type %s"); + if (had_error) + break; + + /* get the devices */ + current_param = "CL_CONTEXT_DEVICES"; + current_line = __LINE__+2; + + error = clGetContextInfo(ctx, CL_CONTEXT_DEVICES, 0, NULL, &szval); + had_error = REPORT_ERROR2("get %s size"); + if (had_error) + break; + if (szval > cursz) { + REALLOC(devs, szval, "context devices"); + cursz = szval; + } + + current_line = __LINE__+1; + error = clGetContextInfo(ctx, CL_CONTEXT_DEVICES, cursz, devs, NULL); + had_error = REPORT_ERROR2("get %s"); + if (had_error) + break; + ndevs = szval/sizeof(cl_device_id); + if (ndevs < 1) { + bufcpy(0, ""); + } + + /* get the platform from the first device */ + current_param = "CL_DEVICE_PLATFORM"; + current_line = __LINE__+1; + error = clGetDeviceInfo(*devs, CL_DEVICE_PLATFORM, sizeof(plat), &plat, NULL); + had_error = REPORT_ERROR2("get %s"); + if (had_error) + break; + + szval = 0; + for (i = 0; i < num_platforms; ++i) { + if (platform[i] == plat) + break; + } + if (i == num_platforms) { + sprintf(strbuf, "", plat); + break; + } else { + szval += sprintf(strbuf, "%s (%" PRIuS ")", + (output_mode == CLINFO_HUMAN ? "Success" : "CL_SUCCESS"), + ndevs); + szval += snprintf(strbuf + szval, bufsz - szval, "\n" I2_STR "%s", + platname_prop, pdata[i].pname); + } + for (i = 0; i < ndevs; ++i) { + size_t szname = 0; + /* for each device, show the device name */ + /* TODO some other unique ID too, e.g. PCI address, if available? */ + + szval += snprintf(strbuf + szval, bufsz - szval, "\n" I2_STR, devname_prop); + if (szval >= bufsz) { + trunc_strbuf(); + break; + } + + current_param = "CL_DEVICE_NAME"; + current_line = __LINE__+1; + error = clGetDeviceInfo(devs[i], CL_DEVICE_NAME, bufsz - szval, strbuf + szval, &szname); + had_error = REPORT_ERROR2("get %s"); + if (had_error) + break; + szval += szname - 1; + + + } + if (i != ndevs) + break; /* had an error earlier, bail */ + + } + + if (ctx) { + clReleaseContext(ctx); + ctx = NULL; + } + LOGI("%s%s\n", def, strbuf); + } + free(devs); +} + +/* check the behavior of NULL platform in clGetDeviceIDs (see checkNullGetDevices) + * and in clCreateContext() */ +void checkNullBehavior(void) +{ + cl_device_id *dev = NULL; + cl_uint p = 0; + cl_uint pidx; + +LOGI("NULL platform behavior\n"); + + checkNullGetPlatformName(); + + pidx = checkNullGetDevices(); + + /* If there's a default platform, and it has devices, try + * creating a context with its first device and see if it works */ + + if (pidx == num_platforms) { + bufcpy(0, no_plat()); + } else if (pdata[pidx].ndevs == 0) { + bufcpy(0, no_dev()); + } else { + p = 0; + dev = all_devices; + while (p < num_platforms && p != pidx) { + dev += pdata[p++].ndevs; + } + if (p < num_platforms) { + checkNullCtx(pidx, dev, "default"); + } else { + /* this shouldn't happen, but still ... */ + bufcpy(0, ""); + } + } +LOGI(I1_STR "%s\n", "clCreateContext(NULL, ...) [default]", strbuf); + + /* Look for a device from a non-default platform, if there are any */ + if (pidx == num_platforms || num_platforms > 1) { + p = 0; + dev = all_devices; + while (p < num_platforms && (p == pidx || pdata[p].ndevs == 0)) { + dev += pdata[p++].ndevs; + } + if (p < num_platforms) { + checkNullCtx(p, dev, "non-default"); + } else { + bufcpy(0, ""); + } + LOGI(I1_STR "%s\n", "clCreateContext(NULL, ...) [other]", strbuf); + } + + checkNullCtxFromType(); + +} + + +/* Get properties of the ocl-icd loader, if available */ +/* All properties are currently char[] */ +typedef enum { + CL_ICDL_OCL_VERSION=1, + CL_ICDL_VERSION=2, + CL_ICDL_NAME=3, + CL_ICDL_VENDOR=4, +} cl_icdl_info; + +/* Function pointer to the ICD loader info function */ +cl_int (*clGetICDLoaderInfoOCLICD)(cl_icdl_info, size_t, void*, size_t*); + +/* We want to auto-detect the OpenCL version supported by the ICD loader. + * To do this, we will progressively find symbols introduced in new APIs, + * until a NULL symbol is found. + */ + +struct icd_loader_test { + cl_uint version; + const char *symbol; +} icd_loader_tests[] = { + { 11, "clCreateSubBuffer" }, + { 12, "clCreateImage" }, + { 20, "clSVMAlloc" }, + { 21, "clGetHostTimer" }, + { 0, NULL } +}; + +int +icdl_info_str(cl_icdl_info param, const char* pname) +{ + error = clGetICDLoaderInfoOCLICD(param, 0, NULL, &nusz); + if (nusz > bufsz) { + REALLOC(strbuf, nusz, current_param); + bufsz = nusz; + } + had_error = REPORT_ERROR2("get %s size"); + if (!had_error) { + error = clGetICDLoaderInfoOCLICD(param, bufsz, strbuf, NULL); + had_error = REPORT_ERROR2("get %s"); + } + show_strbuf(pname, 1); + return had_error; +} + +struct icdl_info_traits { + cl_icdl_info param; // CL_ICDL_* + const char *sname; // "CL_ICDL_*" + const char *pname; // "ICD loader *" +}; + +static const char * const oclicdl_pfx = "OCLICD"; + +#define LINFO(symbol, name) { symbol, #symbol, "ICD loader " name } +struct icdl_info_traits linfo_traits[] = { + LINFO(CL_ICDL_NAME, "Name"), + LINFO(CL_ICDL_VENDOR, "Vendor"), + LINFO(CL_ICDL_VERSION, "Version"), + LINFO(CL_ICDL_OCL_VERSION, "Profile") +}; + +/* GCC < 4.6 does not support the diagnostic push _inside_ the function, + * so we have to put it outside + */ +#if defined __GNUC__ && ((__GNUC__*10 + __GNUC_MINOR__) < 46) +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + +void oclIcdProps(void) +{ + /* First of all, we try to auto-detect the supported ICD loader version */ + int i = 0; + + do { + struct icd_loader_test check = icd_loader_tests[i]; + if (check.symbol == NULL) + break; + if (dlsym(RTLD_DEFAULT, check.symbol) == NULL) + break; + icdl_ocl_version_found = check.version; + ++i; + } while (1); + + + /* We find the clGetICDLoaderInfoOCLICD extension address, and use it to query + * the ICD loader properties. It should be noted however that + * clGetExtensionFunctionAddress is marked deprecated as of OpenCL 1.2, so + * to use it and compile cleanly we need disable the relevant warning. + * It should be noted that in this specific case we cannot replace the + * call to clGetExtensionFunctionAddress with a call to the superseding function + * clGetExtensionFunctionAddressForPlatform because the extension is in the + * loader itself, not in a specific platform. + */ + +#ifdef _MSC_VER + #pragma warning(push) +#pragma warning(disable : 4996) +#elif defined __GNUC__ && ((__GNUC__*10 + __GNUC_MINOR__) >= 46) + #pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif + + clGetICDLoaderInfoOCLICD = clGetExtensionFunctionAddress("clGetICDLoaderInfoOCLICD"); + +#ifdef _MSC_VER +#pragma warning(pop) +#elif defined __GNUC__ && ((__GNUC__*10 + __GNUC_MINOR__) >= 46) +#pragma GCC diagnostic pop +#endif + + if (clGetICDLoaderInfoOCLICD != NULL) { + /* TODO think of a sensible header in CLINFO_RAW */ + if (output_mode != CLINFO_RAW) + puts("\nICD loader properties"); + current_function = __func__; + + if (output_mode == CLINFO_RAW) { + line_pfx_len = strlen(oclicdl_pfx) + 5; + REALLOC(line_pfx, line_pfx_len, "line prefix OCL ICD"); + sprintf(strbuf, "[%s/*]", oclicdl_pfx); + sprintf(line_pfx, "%*s", -line_pfx_len, strbuf); + } + + for (current_line = 0; current_line < ARRAY_SIZE(linfo_traits); ++current_line) { + const struct icdl_info_traits *traits = linfo_traits + current_line; + current_param = traits->sname; + + had_error = icdl_info_str(traits->param, + output_mode == CLINFO_HUMAN ? + traits->pname : traits->sname); + + if (!had_error && traits->param == CL_ICDL_OCL_VERSION) { + icdl_ocl_version = getOpenCLVersion(strbuf + 7); + } + } + } + + if (output_mode == CLINFO_HUMAN) { + if (icdl_ocl_version && + icdl_ocl_version != icdl_ocl_version_found) { + LOGI( "\tNOTE:\tyour OpenCL library declares to support OpenCL %u.%u,\n" + "\t\tbut it seems to support up to OpenCL %u.%u %s.\n", + icdl_ocl_version / 10, icdl_ocl_version % 10, + icdl_ocl_version_found / 10, icdl_ocl_version_found % 10, + icdl_ocl_version_found < icdl_ocl_version ? + "only" : "too"); + } + if (icdl_ocl_version_found < max_plat_version) { + LOGI( "\tNOTE:\tyour OpenCL library only supports OpenCL %u.%u,\n" + "\t\tbut some installed platforms support OpenCL %u.%u.\n" + "\t\tPrograms using %u.%u features may crash\n" + "\t\tor behave unexepectedly\n", + icdl_ocl_version_found / 10, icdl_ocl_version_found % 10, + max_plat_version / 10, max_plat_version % 10, + max_plat_version / 10, max_plat_version % 10); + } + } +} + +#if defined __GNUC__ && ((__GNUC__*10 + __GNUC_MINOR__) < 46) +#pragma GCC diagnostic warning "-Wdeprecated-declarations" +#endif + +void version(void) +{ + puts("clinfo version 2.1.16.01.12"); +} diff --git a/include/error.h b/include/error.h new file mode 100644 index 0000000..a4f42c8 --- /dev/null +++ b/include/error.h @@ -0,0 +1,53 @@ +/* OpenCL error handling */ + +#include + +#include "ext.h" +#include "fmtmacros.h" + +cl_int error; + +int +check_ocl_error(cl_int err, const char *what, const char *func, int line) +{ + if (err != CL_SUCCESS) { + fflush(stdout); + fflush(stderr); + LOGI( "%s:%u: %s : error %d\n", + func, line, what, err); + fflush(stderr); + } + return err != CL_SUCCESS; +} + +const char *current_function; +size_t current_line; +const char *current_param; + +int +report_ocl_error(char *dstbuf, size_t sz, cl_int err, const char *fmt) +{ + static char full_fmt[1024]; + if (err != CL_SUCCESS) { + snprintf(full_fmt, 1024, "<%s:%" PRIuS ": %s : error %d>", + current_function, current_line, fmt, err); + snprintf(dstbuf, sz, full_fmt, current_param); + } + return err != CL_SUCCESS; +} + +int +report_ocl_error_old(char *where, size_t sz, cl_int err, const char *what, const char *func, int line) +{ + if (err != CL_SUCCESS) { + snprintf(where, sz, "<%s:%d: %s : error %d>", + func, line, what, err); + } + return err != CL_SUCCESS; +} + +#define CHECK_ERROR(what) if (check_ocl_error(error, what, __func__, __LINE__)) exit(1) + +#define REPORT_ERROR(what) report_ocl_error_old(strbuf, bufsz, error, what, __func__, __LINE__) +#define REPORT_ERROR2(what) report_ocl_error(strbuf, bufsz, error, what) + diff --git a/include/ext.h b/include/ext.h new file mode 100644 index 0000000..6094c52 --- /dev/null +++ b/include/ext.h @@ -0,0 +1,165 @@ +/* Include OpenCL header, and define OpenCL extensions, since what is and is not + * available in the official headers is very system-dependent */ + +#ifndef _EXT_H +#define _EXT_H + +#ifdef __APPLE__ +#include +#else +#include +#endif + +/* These two defines were introduced in the 1.2 headers + * on 2012-11-30, so earlier versions don't have them + * (e.g. Debian wheezy) + */ + +#ifndef CL_DEVICE_IMAGE_PITCH_ALIGNMENT +#define CL_DEVICE_IMAGE_PITCH_ALIGNMENT 0x104A +#define CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT 0x104B +#endif + +/* 2.0 headers are not very common for the time being, so + * let's copy the defines for the new CL_DEVICE_* properties + * here. + */ +#ifndef CL_VERSION_2_0 +#define CL_DEVICE_MAX_READ_WRITE_IMAGE_ARGS 0x104C +#define CL_DEVICE_MAX_GLOBAL_VARIABLE_SIZE 0x104D +#define CL_DEVICE_QUEUE_ON_DEVICE_PROPERTIES 0x104E +#define CL_DEVICE_QUEUE_ON_DEVICE_PREFERRED_SIZE 0x104F +#define CL_DEVICE_QUEUE_ON_DEVICE_MAX_SIZE 0x1050 +#define CL_DEVICE_MAX_ON_DEVICE_QUEUES 0x1051 +#define CL_DEVICE_MAX_ON_DEVICE_EVENTS 0x1052 +#define CL_DEVICE_SVM_CAPABILITIES 0x1053 +#define CL_DEVICE_GLOBAL_VARIABLE_PREFERRED_TOTAL_SIZE 0x1054 +#define CL_DEVICE_MAX_PIPE_ARGS 0x1055 +#define CL_DEVICE_PIPE_MAX_ACTIVE_RESERVATIONS 0x1056 +#define CL_DEVICE_PIPE_MAX_PACKET_SIZE 0x1057 +#define CL_DEVICE_PREFERRED_PLATFORM_ATOMIC_ALIGNMENT 0x1058 +#define CL_DEVICE_PREFERRED_GLOBAL_ATOMIC_ALIGNMENT 0x1059 +#define CL_DEVICE_PREFERRED_LOCAL_ATOMIC_ALIGNMENT 0x105A + +#define CL_DEVICE_SVM_COARSE_GRAIN_BUFFER (1 << 0) +#define CL_DEVICE_SVM_FINE_GRAIN_BUFFER (1 << 1) +#define CL_DEVICE_SVM_FINE_GRAIN_SYSTEM (1 << 2) +#define CL_DEVICE_SVM_ATOMICS (1 << 3) + +typedef cl_bitfield cl_device_svm_capabilities; +#endif + +#ifndef CL_VERSION_2_1 +#define CL_PLATFORM_HOST_TIMER_RESOLUTION 0x0905 +#define CL_DEVICE_IL_VERSION 0x105B +#define CL_DEVICE_MAX_NUM_SUB_GROUPS 0x105C +#define CL_DEVICE_SUB_GROUP_INDEPENDENT_FORWARD_PROGRESS 0x105D +#endif + +/* + * Extensions + */ + +/* cl_khr_icd */ +#define CL_PLATFORM_ICD_SUFFIX_KHR 0x0920 +#define CL_PLATFORM_NOT_FOUND_KHR -1001 + + +/* cl_khr_fp64 */ +#define CL_DEVICE_DOUBLE_FP_CONFIG 0x1032 + +/* cl_khr_fp16 */ +#define CL_DEVICE_HALF_FP_CONFIG 0x1033 + +/* cl_khr_terminate_context */ +#define CL_DEVICE_TERMINATE_CAPABILITY_KHR 0x200F + +/* cl_nv_device_attribute_query */ +#define CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV 0x4000 +#define CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV 0x4001 +#define CL_DEVICE_REGISTERS_PER_BLOCK_NV 0x4002 +#define CL_DEVICE_WARP_SIZE_NV 0x4003 +#define CL_DEVICE_GPU_OVERLAP_NV 0x4004 +#define CL_DEVICE_KERNEL_EXEC_TIMEOUT_NV 0x4005 +#define CL_DEVICE_INTEGRATED_MEMORY_NV 0x4006 +#define CL_DEVICE_ATTRIBUTE_ASYNC_ENGINE_COUNT_NV 0x4007 +#define CL_DEVICE_PCI_BUS_ID_NV 0x4008 +#define CL_DEVICE_PCI_SLOT_ID_NV 0x4009 + +/* cl_ext_atomic_counters_{32,64} */ +#define CL_DEVICE_MAX_ATOMIC_COUNTERS_EXT 0x4032 + +/* cl_amd_device_attribute_query */ +#define CL_DEVICE_PROFILING_TIMER_OFFSET_AMD 0x4036 +#define CL_DEVICE_TOPOLOGY_AMD 0x4037 +#define CL_DEVICE_BOARD_NAME_AMD 0x4038 +#define CL_DEVICE_GLOBAL_FREE_MEMORY_AMD 0x4039 +#define CL_DEVICE_SIMD_PER_COMPUTE_UNIT_AMD 0x4040 +#define CL_DEVICE_SIMD_WIDTH_AMD 0x4041 +#define CL_DEVICE_SIMD_INSTRUCTION_WIDTH_AMD 0x4042 +#define CL_DEVICE_WAVEFRONT_WIDTH_AMD 0x4043 +#define CL_DEVICE_GLOBAL_MEM_CHANNELS_AMD 0x4044 +#define CL_DEVICE_GLOBAL_MEM_CHANNEL_BANKS_AMD 0x4045 +#define CL_DEVICE_GLOBAL_MEM_CHANNEL_BANK_WIDTH_AMD 0x4046 +#define CL_DEVICE_LOCAL_MEM_SIZE_PER_COMPUTE_UNIT_AMD 0x4047 +#define CL_DEVICE_LOCAL_MEM_BANKS_AMD 0x4048 +#define CL_DEVICE_THREAD_TRACE_SUPPORTED_AMD 0x4049 +#define CL_DEVICE_GFXIP_MAJOR_AMD 0x404A +#define CL_DEVICE_GFXIP_MINOR_AMD 0x404B +#define CL_DEVICE_AVAILABLE_ASYNC_QUEUES_AMD 0x404C + +#ifndef CL_DEVICE_TOPOLOGY_TYPE_PCIE_AMD +#define CL_DEVICE_TOPOLOGY_TYPE_PCIE_AMD 1 + +typedef union +{ + struct { cl_uint type; cl_uint data[5]; } raw; + struct { cl_uint type; cl_char unused[17]; cl_char bus; cl_char device; cl_char function; } pcie; +} cl_device_topology_amd; +#endif + +/* cl_amd_offline_devices */ +#define CL_CONTEXT_OFFLINE_DEVICES_AMD 0x403F + +/* cl_ext_device_fission */ +#define cl_ext_device_fission 1 + +typedef cl_ulong cl_device_partition_property_ext; + +#define CL_DEVICE_PARTITION_EQUALLY_EXT 0x4050 +#define CL_DEVICE_PARTITION_BY_COUNTS_EXT 0x4051 +#define CL_DEVICE_PARTITION_BY_NAMES_EXT 0x4052 +#define CL_DEVICE_PARTITION_BY_NAMES_INTEL 0x4052 /* cl_intel_device_partition_by_names */ +#define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT 0x4053 + +#define CL_DEVICE_PARENT_DEVICE_EXT 0x4054 +#define CL_DEVICE_PARTITION_TYPES_EXT 0x4055 +#define CL_DEVICE_AFFINITY_DOMAINS_EXT 0x4056 +#define CL_DEVICE_REFERENCE_COUNT_EXT 0x4057 +#define CL_DEVICE_PARTITION_STYLE_EXT 0x4058 + +#define CL_AFFINITY_DOMAIN_L1_CACHE_EXT 0x1 +#define CL_AFFINITY_DOMAIN_L2_CACHE_EXT 0x2 +#define CL_AFFINITY_DOMAIN_L3_CACHE_EXT 0x3 +#define CL_AFFINITY_DOMAIN_L4_CACHE_EXT 0x4 +#define CL_AFFINITY_DOMAIN_NUMA_EXT 0x10 +#define CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT 0x100 + +/* cl_intel_advanced_motion_estimation */ +#define CL_DEVICE_ME_VERSION_INTEL 0x407E + +/* cl_qcom_ext_host_ptr */ +#define CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM 0x40A0 +#define CL_DEVICE_PAGE_SIZE_QCOM 0x40A1 + +/* cl_khr_spir */ +#define CL_DEVICE_SPIR_VERSIONS 0x40E0 + +/* cl_altera_device_temperature */ +#define CL_DEVICE_CORE_TEMPERATURE_ALTERA 0x40F3 + +/* cl_intel_simultaneous_sharing */ +#define CL_DEVICE_SIMULTANEOUS_INTEROPS_INTEL 0x4104 +#define CL_DEVICE_NUM_SIMULTANEOUS_INTEROPS_INTEL 0x4105 + +#endif diff --git a/include/fmtmacros.h b/include/fmtmacros.h new file mode 100644 index 0000000..0660583 --- /dev/null +++ b/include/fmtmacros.h @@ -0,0 +1,28 @@ +/* cl_ulong is always a 64bit integer, so in a few places + we want to use its shadow type uint64_t, and print the + values using PRIu64. We'll similarly define one for + size_t, to make support for non-standard/older compiler + easier. + */ + +#ifndef _FMT_MACROS_H +#define _FMT_MACROS_H + +#ifdef _WIN32 +# include +# include // size_t +# define PRIu64 "I64u" +# define PRIX64 "I64x" +# define PRIXPTR "p" +# define PRIuS "Iu" +#else +# define __STDC_FORMAT_MACROS +# include +#endif + +// size_t print spec +#ifndef PRIuS +# define PRIuS "zu" +#endif + +#endif diff --git a/include/memory.h b/include/memory.h new file mode 100644 index 0000000..36e532e --- /dev/null +++ b/include/memory.h @@ -0,0 +1,21 @@ +/* Memory handling */ + +#include + +#define CHECK_MEM(var, what) do { \ + if (!var) { \ + LOGI( "%s:%d: %s : Out of memory\n", \ + __func__, __LINE__, what); \ + exit(1); \ + } \ +} while (0) + +#define ALLOC(var, num, what) do { \ + var = calloc(num, sizeof(*(var))); \ + CHECK_MEM(var, what); \ +} while (0) + +#define REALLOC(var, num, what) do { \ + var = realloc(var, (num)*sizeof(*var)); \ + CHECK_MEM(var, what); \ +} while (0) diff --git a/include/ms_support.h b/include/ms_support.h new file mode 100644 index 0000000..2a8a129 --- /dev/null +++ b/include/ms_support.h @@ -0,0 +1,47 @@ +/* Missing functions and other misc stuff to support + * the horrible MS C compiler + * + * TODO could be improved by version-checking for C99 support + */ + +// also disable strncpy vs strncpy_s warning +#pragma warning(disable : 4996) + +// No inline in MS C +#define inline __inline + +// No snprintf in MS C, copy over implementation taken from +// stackoverflow + +#include +#include + +inline int c99_vsnprintf(char* str, size_t size, const char* format, va_list ap) +{ + int count = -1; + + if (size != 0) + count = _vsnprintf_s(str, size, _TRUNCATE, format, ap); + if (count == -1) + count = _vscprintf(format, ap); + + return count; +} + +inline int c99_snprintf(char* str, size_t size, const char* format, ...) +{ + int count; + va_list ap; + + va_start(ap, format); + count = c99_vsnprintf(str, size, format, ap); + va_end(ap); + + return count; +} + +#define snprintf c99_snprintf + +// And no __func__ either + +#define __func__ __FUNCTION__ diff --git a/include/strbuf.h b/include/strbuf.h new file mode 100644 index 0000000..8fc112f --- /dev/null +++ b/include/strbuf.h @@ -0,0 +1,96 @@ +/* multi-purpose string strbuf, will be initialized to be + * at least 1024 bytes long. + */ + +#include +#include +#include +#include "fmtmacros.h" + +char *strbuf; +size_t bufsz, nusz; + +#define GET_STRING(cmd, param, param_str, ...) do { \ + error = cmd(__VA_ARGS__, param, 0, NULL, &nusz); \ + if (nusz > bufsz) { \ + REALLOC(strbuf, nusz, #param); \ + bufsz = nusz; \ + } \ + if (REPORT_ERROR("get " param_str " size")) break; \ + error = cmd(__VA_ARGS__, param, bufsz, strbuf, NULL); \ + REPORT_ERROR("get " param_str); \ +} while (0) + +/* Skip leading whitespace in a string */ +static inline const char* skip_leading_ws(const char *str) +{ + const char *ret = str; + while (isspace(*ret)) ++ret; + return ret; +} + +/* replace last 3 chars in strbuf with ... */ +static const char ellip[] = "..."; + +static void trunc_strbuf(void) +{ + memcpy(strbuf + bufsz - 4, ellip, 4); +} + +/* copy a string to strbuf, at the given offset, + * returning the amount of bytes written (excluding the + * closing NULL byte) + */ +static inline size_t bufcpy_len(size_t offset, const char *str, size_t len) +{ + size_t maxlen = bufsz - offset - 1; + char *dst = strbuf + offset; + int trunc = 0; + if (bufsz < offset) { + fprintf(stderr, "bufcpy overflow copying %s at offset %" PRIuS "/%" PRIuS " (%s)\n", + str, offset, bufsz, strbuf); + maxlen = 0; + trunc = 1; + } + if (len > maxlen) { + len = maxlen; + trunc = 1; + /* TODO enlarge strbuf instead, if maxlen > 0 */ + } + memcpy(dst, str, len); + offset += len; + if (trunc) + trunc_strbuf(); + else + strbuf[offset] = '\0'; + return len; +} + +/* As above, auto-compute string length */ +static inline size_t bufcpy(size_t offset, const char *str) +{ + return bufcpy_len(offset, str, strlen(str)); +} + + +/* Separators: we want to be able to prepend separators as needed to strbuf, + * which we do only if halfway through the buffer. The callers should first + * call a 'set_separator' and then use add_separator(&offset) to add it, where szval + * is an offset inside the buffer, which will be incremented as needed + */ + +const char *sep; +size_t sepsz; + +void set_separator(const char* _sep) +{ + sep = _sep; + sepsz = strlen(sep); +} + +/* Note that no overflow check is done: it is assumed that strbuf will have enough room */ +void add_separator(size_t *offset) +{ + if (*offset) + *offset += bufcpy_len(*offset, sep, sepsz); +} diff --git a/libopencl.c b/libopencl.c index 4fb3b80..3e43517 100644 --- a/libopencl.c +++ b/libopencl.c @@ -9,12 +9,30 @@ * If none of these are set, default system paths will be considered **/ +#ifdef __ANDROID__ +#include +#ifndef LOGI +#define LOGI(...) ((void)__android_log_print(ANDROID_LOG_INFO, "LIBOPENCLSTUB", __VA_ARGS__)) +#define LOGW(...) ((void)__android_log_print(ANDROID_LOG_WARN, "LIBOPENCLSTUB", __VA_ARGS__)) +#endif +#else +#define LOGI(...) printf(__VA_ARGS__); +#define LOGW(...) printf(__VA_ARGS__); +#endif + #include "libopencl.h" +#include "clinfos.h" + -static const char *default_so_paths[] = { // Android - "/system/lib/libOpenCL.so", "/system/vendor/lib/libOpenCL.so", +static const char *default_so_paths[] = { // Android - 64bit first + "/vendor/lib64/libOpenCL.so", + "/system/lib64/libOpenCL.so", + "/vendor/lib64/egl/libGLES_mali.so", + // Android "/system/vendor/lib/egl/libGLES_mali.so", + "/system/vendor/lib/libOpenCL.so", + "/system/lib/libOpenCL.so", "/system/vendor/lib/libPVROCL.so", "/data/data/org.pocl.libs/files/lib/libpocl.so", // Linux @@ -33,6 +50,61 @@ static int access_file(const char *filename) return (stat(filename, &buffer) == 0); } + +void clinfos() { + cl_uint p; + int a = 0; + + cl_bool show_offline = CL_FALSE; + + output_mode = CLINFO_HUMAN; + show_offline = CL_TRUE; + + ALLOC(strbuf, 1024, "general string buffer"); + bufsz = 1024; + + error = clGetPlatformIDs(0, NULL, &num_platforms); + if (error != CL_PLATFORM_NOT_FOUND_KHR) + CHECK_ERROR("number of platforms"); + + if (!list_only) + LOGI(I0_STR "%u\n", + (output_mode == CLINFO_HUMAN ? + "Number of platforms" : "#PLATFORMS"), + num_platforms); + if (!num_platforms) + return; + + ALLOC(platform, num_platforms, "platform IDs"); + error = clGetPlatformIDs(num_platforms, platform, NULL); + CHECK_ERROR("platform IDs"); + + ALLOC(pdata, num_platforms, "platform data"); + ALLOC(line_pfx, 1, "line prefix"); + + for (p = 0; p < num_platforms; ++p) { + printPlatformInfo(p); + if (!list_only) + puts(""); + } + + if (num_devs_all > 0) { + ALLOC(all_devices, num_devs_all, "device IDs"); + } + + if (list_only) { + listPlatformsAndDevices(show_offline); + } else { + showDevices(show_offline); + if (output_mode != CLINFO_RAW) + checkNullBehavior(); + oclIcdProps(); + } + + return; +} + + static void open_libopencl_so() { char *path = NULL, *str = NULL; @@ -53,11 +125,29 @@ static void open_libopencl_so() if(!path) { + LOGI("Look for a real OpenCL library."); for(i=0; i<(sizeof(default_so_paths)/sizeof(char*)); i++) { if(access_file(default_so_paths[i])) { - path = (char *)default_so_paths[i]; - break; + + if (!path) { + path = (char *) default_so_paths[i]; + LOGI("%s is OK and selected.", path); + } else { + LOGI("%s is OK.", default_so_paths[i]); + } + + // Locally print infos + so_handle = dlopen(path, RTLD_LAZY); + + if(!so_handle) { + LOGI("Failed to Open it."); + } else { + LOGI("Library Opened."); + clinfos(); + dlclose(so_handle); + } + } } } -- 2.4.11 ================================================ FILE: framework/shared/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) set(common_properties "") set(common_libraries "") include_directories(./include) ########## Boost (required) #################### find_package(Boost 1.54 REQUIRED COMPONENTS program_options regex) ########## GLUT GUI Library #################### find_package(GLUT) if(GLUT_FOUND) ########## Pangolin GUI Library #################### find_package(Pangolin) if(Pangolin_FOUND) include_directories(${Pangolin_INCLUDE_DIRS}) include_directories(${TOON_INCLUDE_PATHS}) add_library(slambench-ui-pangolin src/SLAMBenchUI_Pangolin.cpp include/SLAMBenchUI_Pangolin.h) target_link_libraries(slambench-ui-pangolin ${Pangolin_LIBRARIES}) if(CMAKE_COMPILER_IS_GNUCC AND CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 8.0) target_compile_options(slambench-ui-pangolin PRIVATE "-Wno-error=catch-value=") endif() endif(Pangolin_FOUND) endif(GLUT_FOUND) ########## PCL Library #################### find_package(PCL) if (PCL_FOUND) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) set(common_libraries "${common_libraries}" "${PCL_LIBRARIES}") endif(PCL_FOUND) ########## Main Library #################### file(GLOB sensors_files src/io/sensor/*) add_library(slambench-c-wrapper src/library_wrapper.cpp ) set_target_properties(slambench-c-wrapper PROPERTIES COMPILE_FLAGS "-fPIC") set(MetricFiles src/ColumnWriter.cpp src/metrics/Phase.cpp src/metrics/ATEMetric.cpp src/metrics/RPEMetric.cpp src/metrics/PowerMetric.cpp src/metrics/DurationMetric.cpp src/metrics/MemoryMetric.cpp src/metrics/memory_utils/CUDAMonitor.cpp src/metrics/Metric.cpp src/metrics/MetricManager.cpp src/metrics/DepthEstimationMetric.cpp src/outputs/Output.cpp src/outputs/OutputManager.cpp src/outputs/OutputManagerWriter.cpp src/outputs/TrajectoryAlignmentMethod.cpp src/outputs/TrajectoryInterface.cpp src/values/Value.cpp src/values/ValueDispatch.cpp src/values/ValueInterface.cpp src/values/ValuePrinter.cpp ) ########## XU3 MONITORING #################### # Only work on the Odroid XU3 so far ########################################################### set(common_properties "${common_properties} -DXU3_MONITORING") list(APPEND MetricFiles src/metrics/power_utils/XU3Monitor.cpp) ########## PAPI MONITORING (optional) #################### # You need to install papi-devel and lm_sensors-devel ########################################################### find_package(PAPI) if (PAPI_FOUND) include_directories(${PAPI_INCLUDE_DIRS}) set(common_properties "${common_properties} -DPAPI_MONITORING") set(common_libraries "${common_libraries}" ${PAPI_LIBRARIES}) list(APPEND MetricFiles src/metrics/power_utils/PAPIMonitor.cpp) endif(PAPI_FOUND) add_library(slambench-metrics ${MetricFiles}) set_target_properties(slambench-metrics PROPERTIES COMPILE_FLAGS "${common_properties}") add_library(slambench-io ${sensors_files} src/io/core/Core.cpp src/io/FrameBuffer.cpp src/io/FrameBufferSource.cpp src/io/FrameFormat.cpp src/io/SLAMFile.cpp src/io/SLAMFrame.cpp src/io/PixelFormat.cpp src/io/InputInterface.cpp src/io/InputInterfaceManager.cpp src/io/FrameSource.cpp src/io/deserialisation/Deserialiser.cpp src/io/deserialisation/SLAMFileDeserialiser.cpp src/io/deserialisation/SLAMFileHeaderDeserialiser.cpp src/io/deserialisation/SLAMFrameDeserialiser.cpp src/io/deserialisation/SensorCollectionDeserialiser.cpp src/io/format/DataFormatter.cpp src/io/format/PointCloud.cpp src/io/serialisation/Serialiser.cpp src/io/serialisation/SLAMFileHeaderSerialiser.cpp src/io/serialisation/SLAMFileSerialiser.cpp src/io/serialisation/SLAMFrameSerialiser.cpp src/lodepng.cpp ) add_library(slambench-utils src/SLAMBenchConfiguration.cpp src/sb_malloc.cpp src/ParameterComponent.cpp src/ParameterManager.cpp src/ResultWriter.cpp ) target_include_directories(slambench-io PRIVATE ${Boost_INCLUDE_DIRS}) target_include_directories(slambench-metrics PRIVATE ${Boost_INCLUDE_DIRS}) target_link_libraries(slambench-io PRIVATE slambench-utils pthread ${Boost_LIBRARIES}) SET(EXTRA_LIBS_FOR_MEMORY "") find_package(OpenCL) if(OPENCL_FOUND) SET(EXTRA_LIBS_FOR_MEMORY "${EXTRA_LIBS_FOR_MEMORY};${OPENCL_LIBRARIES}") endif(OPENCL_FOUND) find_package(CUDA) if(CUDA_FOUND) STRING(REPLACE "_static.a" ".so" CUDA_LIBRARIES "${CUDA_LIBRARIES}") SET(EXTRA_LIBS_FOR_MEMORY "${EXTRA_LIBS_FOR_MEMORY};${CUDA_LIBRARIES}") endif(CUDA_FOUND) ########## OpenNI 2.0 and OpenNI 1.5 (optional) #################### find_package(OpenNI) if(OpenNI_FOUND) message(STATUS "SLAMBENCH will use OpenNI 1.5, include path = ${OPENNI_INCLUDE_DIR}") include_directories(${OPENNI_INCLUDE_DIR}) set(common_properties "${common_properties} -DDO_OPENNI15 -Wno-error=strict-aliasing ") set(common_libraries "${common_libraries}" "${OPENNI_LIBRARY}") add_library(slambench-io-oni15 src/io/openni15/ONI15Frame.cpp src/io/openni15/ONI15FrameStream.cpp src/io/openni15/ONI15InputInterface.cpp ) add_definitions(-DDO_OPENNI15=1) target_link_libraries(slambench-io-oni15 ${OPENNI_LIBRARIES}) target_link_libraries(slambench-utils slambench-io-oni15) SET_TARGET_PROPERTIES(slambench-io-oni15 PROPERTIES COMPILE_FLAGS "-fPIC -Wno-error=unused-but-set-variable -Wno-error=return-type -Wno-error=strict-aliasing") else(OpenNI_FOUND) message(STATUS "SLAMBENCH WILL NOT USE OPENNI 1.2 !!") endif(OpenNI_FOUND) find_package(OpenNI2) if(OpenNI2_FOUND) message(STATUS "SLAMBENCH will use OpenNI 2.X, include path = ${OPENNI2_INCLUDE_PATHS#}") include_directories(${OPENNI2_INCLUDE_PATHS}) set(common_properties "${common_properties} -DDO_OPENNI20") set(common_libraries "${common_libraries}" "${OPENNI2_LIBRARIES}") add_library(slambench-io-oni2 src/io/openni/ONI2Frame.cpp src/io/openni/ONI2FrameStream.cpp src/io/openni/ONI2InputInterface.cpp ) add_definitions(-DDO_OPENNI20=1) target_link_libraries(slambench-io-oni2 ${OPENNI2_LIBRARIES}) set_target_properties(slambench-io-oni2 PROPERTIES COMPILE_FLAGS "-fPIC -Wno-error=return-type -Wno-unused-variable -Wno-error=strict-aliasing") target_link_libraries(slambench-utils slambench-io-oni2) else(OpenNI2_FOUND) message(STATUS "SLAMBENCH WILL NOT USE OPENNI 2.X !!") endif(OpenNI2_FOUND) find_package(realsense2) if(realsense2_FOUND) message(STATUS "Found realsense:" ${realsense2_INCLUDE_DIR}) include_directories(${realsense2_INCLUDE_DIR}) add_library(slambench-io-realsense src/io/realsense/RealSense2Frame.cpp src/io/realsense/RealSense2FrameStream.cpp src/io/realsense/RealSense2InputInterface.cpp) add_definitions(-DDO_REALSENSE=1) set_target_properties(slambench-io-realsense PROPERTIES COMPILE_FLAGS "-fPIC -Wno-unused-variable -Wno-error=return-type -Wno-error=strict-aliasing") target_link_libraries(slambench-io-realsense ${realsense2_LIBRARY}) target_link_libraries(slambench-utils slambench-io-realsense) else() message(STATUS "No realsense") endif() target_link_libraries(slambench-utils "-Wl,--no-as-needed;${EXTRA_LIBS_FOR_MEMORY};-Wl,--as-needed" ${common_libraries} dl) set_target_properties(slambench-utils PROPERTIES COMPILE_FLAGS "-fPIC ${common_properties}") ================================================ FILE: framework/shared/include/ColumnWriter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef COLUMNWRITER_H #define COLUMNWRITER_H #include #include #include class SLAMBenchLibraryHelper; namespace slambench { namespace values { class ValueInterface; } namespace outputs { class BaseOutput; } namespace metrics { class Metric; class Phase; } } namespace slambench { class ColumnInterface { public: virtual ~ColumnInterface() = default; virtual void WriteHeader(std::ostream &str) const = 0; virtual void Write(std::ostream &str) = 0; }; class LibColumnInterface : public ColumnInterface { public: LibColumnInterface(SLAMBenchLibraryHelper *lib) : lib_(lib) {} virtual ~LibColumnInterface() = default; void Write(std::ostream& str) override = 0; void WriteHeader(std::ostream& str) const override = 0; protected: SLAMBenchLibraryHelper *GetLib() { return lib_; } const SLAMBenchLibraryHelper *GetLib() const { return lib_; } std::string GetHeaderPrefix() const; private: SLAMBenchLibraryHelper *lib_; }; class ValueLibColumnInterface : public LibColumnInterface { public: ValueLibColumnInterface(SLAMBenchLibraryHelper *lib, metrics::Metric *metric, metrics::Phase *phase); ValueLibColumnInterface(SLAMBenchLibraryHelper *lib, outputs::BaseOutput *output); ~ValueLibColumnInterface() override = default; virtual void Write(std::ostream& str) override; virtual void WriteHeader(std::ostream& str) const override; protected: const std::string &GetName() { return name_; } values::ValueInterface *GetValueInterface() { return value_; } const values::ValueInterface *GetValueInterface() const { return value_; } private: ValueLibColumnInterface(SLAMBenchLibraryHelper *lib, values::ValueInterface *value, const std::string &name) : LibColumnInterface(lib), value_(value), name_(name) {} values::ValueInterface *value_; const std::string name_; }; class CollectionValueLibColumnInterface : public ValueLibColumnInterface { public: CollectionValueLibColumnInterface(SLAMBenchLibraryHelper *lib, metrics::Metric *metric, metrics::Phase *phasespec); CollectionValueLibColumnInterface(SLAMBenchLibraryHelper *lib, outputs::BaseOutput *output); void Write(std::ostream& str) override; void WriteHeader(std::ostream& str) const override; private: void WriteInvalid(std::ostream &str); }; class OutputTimestampColumnInterface : public ColumnInterface { public: explicit OutputTimestampColumnInterface(outputs::BaseOutput *output) : output_(output) {}; ~OutputTimestampColumnInterface() override = default; void Write(std::ostream& str) override; void WriteHeader(std::ostream& str) const override; private: outputs::BaseOutput *output_; }; class RowNumberColumn : public ColumnInterface { public: RowNumberColumn(); void Write(std::ostream& str) override; void WriteHeader(std::ostream& str) const override; private: uint64_t counter_; }; class ColumnWriter { public: ColumnWriter(std::ostream &str, const std::string &separator); ~ColumnWriter() = default; void AddColumn(ColumnInterface *interface); void PrintRow(); void PrintHeader(); private: std::vector columns_; std::ostream &str_; std::string separator_; }; } #endif /* COLUMNWRITER_H */ ================================================ FILE: framework/shared/include/ParameterComponent.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_PARAMETERCOMPONENT_H_ #define FRAMEWORK_SHARED_INCLUDE_PARAMETERCOMPONENT_H_ #include #include struct Parameter; class ParameterComponent; typedef std::vector arguments_vector ; typedef std::vector components_vector ; class ParameterComponent { public: ParameterComponent(std::string name) : name_(name) {} virtual ~ParameterComponent(); const arguments_vector &getParameters() const { return arguments_; } const components_vector &getComponents() const { return components_; } std::string getName() const { return name_; } template void addParameter(T p) { T * param_ptr = new T (p); this->arguments_.push_back(param_ptr); param_ptr->resetValue(); } void AddComponent(ParameterComponent *component) { components_.push_back(component); } private: std::string name_; arguments_vector arguments_; components_vector components_; }; #endif ================================================ FILE: framework/shared/include/ParameterManager.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef PARAMETERMANAGER_H #define PARAMETERMANAGER_H #include #include #include #include typedef std::pair param_info_t; namespace slambench { class ParameterManager : public ParameterComponent { public : ParameterManager() : ParameterComponent("") {} void ClearComponents() { components_.clear(); }; void PrintValues(std::ostream &str, const ParameterComponent* c = nullptr) const; void PrintArguments(std::ostream &str, const ParameterComponent* c = nullptr) const; bool BuildArgumentsList(ParameterComponent *callback_data); bool ReadArgumentsOrQuit(unsigned int argc, const char * const * const argv); bool ReadArguments(unsigned int argc, const char * const * const argv); private: std::map params_long_, params_short_; std::vector components_; }; } #endif /* PARAMETERMANAGER_H */ ================================================ FILE: framework/shared/include/Parameters.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_PARAMETERS_H_ #define FRAMEWORK_SHARED_INCLUDE_PARAMETERS_H_ #include #include #include #include #include #include #include #include #include #include "ParameterComponent.h" template std::string precise_to_string(T value) { std::ostringstream os ; os << std::setprecision(std::numeric_limits::digits10 + 1) << value ; return os.str() ; } inline std::ostream & operator<<(std::ostream & out, const std::vector & m) { for (auto it = m.begin() ; it != m.end() ; it++) { if (it != m.begin()) out << ","; out << *it; } return out; } inline std::ostream & operator<<(std::ostream & out, const sb_uint2 & m) { return out << "" << m.x << "," << m.y << ""; } inline std::ostream & operator<<(std::ostream & out, const sb_uint3 & m) { return out << "" << m.x << "," << m.y << ","<< m.z << ""; } inline std::ostream & operator<<(std::ostream & out, const sb_float3 & m) { return out << "" << m.x << "," << m.y << ","<< m.z << ""; } inline std::ostream & operator<<(std::ostream & out, const sb_float4 & m) { return out << "" << m.x << "," << m.y << ","<< m.z << ","<< m.w << "" ; } template inline type3 atof3(const char * optarg) { type3 res; std::istringstream dotargs(optarg); std::string s; if (getline(dotargs, s, ',')) { res.x = atof(s.c_str()); } else return res; if (getline(dotargs, s, ',')) { res.y = atof(s.c_str()); } else { res.y = res.x; res.z = res.y; return res; } if (getline(dotargs, s, ',')) { res.z = atof(s.c_str()); } else { res.z = res.y; } return res; } template inline type3 atoi3(const char * optarg) { type3 res; std::istringstream dotargs(optarg); std::string s; if (getline(dotargs, s, ',')) { res.x = atoi(s.c_str()); } else return res; if (getline(dotargs, s, ',')) { res.y = atoi(s.c_str()); } else { res.y = res.x; res.z = res.y; return res; } if (getline(dotargs, s, ',')) { res.z = atoi(s.c_str()); } else { res.z = res.y; } return res; } template inline type4 atof4(const char * optarg) { type4 res; std::istringstream dotargs(optarg); std::string s; if (getline(dotargs, s, ',')) { res.x = atof(s.c_str()); } else return res; if (getline(dotargs, s, ',')) { res.y = atof(s.c_str()); } else { res.y = res.x; res.z = res.y; res.w = res.z; return res; } if (getline(dotargs, s, ',')) { res.z = atof(s.c_str()); } else { res.z = res.y; res.w = res.z; return res; } if (getline(dotargs, s, ',')) { res.w = atof(s.c_str()); } else { res.w = res.z; } return res; } struct Parameter { Parameter(std::string short_option, std::string name , std::string description, void (*callback)(Parameter*,ParameterComponent*) = nullptr) : short_option_(short_option), name_(name), description_(description), callback_(callback) { } virtual ~Parameter() {} inline std::string getDescription() {return description_;} inline void (*getCallback())(Parameter*,ParameterComponent*) {return callback_;} inline std::string getName() {return name_;} inline const std::string getShortOption(const ParameterComponent* pc) const {return (pc->getName() != "") ? pc->getName() + "-" + short_option_ : short_option_;} inline std::string getLongOption(const ParameterComponent* pc) const {return (pc->getName() != "") ? pc->getName() + "-" + name_ : name_;} virtual bool requiresValue() = 0; virtual const std::string getStrValue() const = 0; virtual void setValue(const char*) = 0; virtual void resetValue() = 0; virtual const std::string getStrDefault() = 0; virtual const std::string getStrDetails(ParameterComponent* pc) { std::stringstream res; res << "name:" << this->getLongOption(pc) << "\n" ; res << "short-option:" << this->getShortOption(pc) << "\n" ; res << "description:" << this->getDescription()<< "\n" ; return res.str(); } protected : std::string short_option_; std::string name_; std::string description_; void (*callback_)(Parameter*, ParameterComponent*); }; struct TriggeredParameter : Parameter { TriggeredParameter(std::string shortOption,std::string name, std::string description, void (*callback)(Parameter*, ParameterComponent*) = nullptr) : Parameter(shortOption,name, description, callback) { } bool requiresValue() {return false;}; const std::string getStrValue() const {return triggered_ ? "true" : "false";}; void setValue(const char*) { triggered_ = true;}; void resetValue() { triggered_ = false;}; const std::string getStrDefault() {return "false";}; virtual inline const std::string getStrDetails(ParameterComponent*pc) { std::stringstream res; res << Parameter::getStrDetails(pc); res << "type:triggered\n" ; return res.str(); } private : bool triggered_ = false; }; template struct TypedParameter : Parameter { TypedParameter(std::string shortOption,std::string name, std::string description, T* ptr,const T* default_v, void (*callback)(Parameter*, ParameterComponent*) = nullptr) : Parameter(shortOption,name, description, callback) , default_value_(default_v) , ptr_(ptr) { if (!ptr) { throw std::logic_error("SLAMBench: Internal error, an instance of TypedParameter needs a valid storage pointer."); } } const std::string getValue(const void*) const; void copyValue(T*,const T*); void setValue(const char* otarg); bool requiresValue() {return true;}; inline const std::string getStrDefault() {if (default_value_ == nullptr) return "nullptr"; return getValue(default_value_);}; inline void resetValue() {if (ptr_ == nullptr) return; if (default_value_ == nullptr) return; copyValue((T*)ptr_, default_value_);}; inline const std::string getStrValue() const {if (ptr_ == nullptr) return "nullptr"; return getValue((T*)ptr_);}; inline const T& getTypedValue() {if (ptr_ == nullptr) throw std::logic_error("Undefined Typed Parameter."); return *((T*)ptr_);}; inline const std::string getStrType() {return typeid(T).name();} virtual inline const std::string getStrDetails(ParameterComponent*pc) { std::stringstream res; res << Parameter::getStrDetails(pc); res << "type:" << this->getStrType()<< "\n" ; res << "default:" << this->getStrDefault()<< "\n" ; return res.str(); } private : const T *default_value_; void *ptr_; }; template<> inline const std::string TypedParameter::getValue(const void * ptr) const { return "" + precise_to_string(((const float*)ptr)[0]) + "," + precise_to_string(((const float*)ptr)[1]) + ""; }; template<> inline void TypedParameter::copyValue(float (*to) [2] , float const (*from) [2]) { (*to)[0] = (*from)[0]; (*to)[1] = (*from)[1]; }; template<> inline void TypedParameter::setValue(const char* optarg) { std::istringstream dotargs(optarg); std::string s; if (getline(dotargs, s, ',')) { ((float*)ptr_)[0] = atof(s.c_str()); } if (getline(dotargs, s, ',')) { ((float*)ptr_)[1] = atof(s.c_str()); } }; template<> inline const std::string TypedParameter::getValue(const void * ptr) const { return "" + precise_to_string(((const float*)ptr)[0]) + "," + precise_to_string(((const float*)ptr)[1]) + "," + precise_to_string(((const float*)ptr)[2]) + "," + precise_to_string(((const float*)ptr)[3]) + ""; }; template<> inline void TypedParameter::copyValue(float (*to) [4] , float const (*from) [4]) { (*to)[0] = (*from)[0]; (*to)[1] = (*from)[1]; (*to)[2] = (*from)[2]; (*to)[3] = (*from)[3]; }; template<> inline void TypedParameter::setValue(const char* optarg) { std::istringstream dotargs(optarg); std::string s; if (getline(dotargs, s, ',')) { ((float*)ptr_)[0] = atof(s.c_str()); } if (getline(dotargs, s, ',')) { ((float*)ptr_)[1] = atof(s.c_str()); } if (getline(dotargs, s, ',')) { ((float*)ptr_)[2] = atof(s.c_str()); } if (getline(dotargs, s, ',')) { ((float*)ptr_)[3] = atof(s.c_str()); } }; template<> inline void TypedParameter::copyValue(std::string* to,const std::string* from) {*to = *(std::string*)from;;}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(std::string*)ptr_) = std::string(otarg);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const {return *((std::string*) ptr);}; template<> inline void TypedParameter::copyValue(bool* to,const bool* from) {*to = *(bool*)from;;}; template<> inline void TypedParameter::setValue(const char* otarg) {if (ptr_) (*(bool*)ptr_) = (std::string(otarg) == "true");}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const {return (*(bool*)ptr)?"true":"false";}; template<> inline void TypedParameter::copyValue(unsigned int* to,const unsigned int* from) {*to = *(unsigned int*)from;;}; template<> inline void TypedParameter::copyValue(int* to,const int* from) {*to = *(int*)from;;}; template<> inline void TypedParameter::copyValue(long unsigned int* to,const long unsigned int* from) {*to = *(long unsigned int*)from;;}; template<> inline void TypedParameter::copyValue(float* to,const float* from) {*to = *(float*)from;;}; template<> inline void TypedParameter::copyValue(double* to,const double* from) {*to = *(double*)from;;}; template<> inline void TypedParameter::copyValue(sb_float3* to,const sb_float3* from) {*to = *(sb_float3*)from;;}; template<> inline void TypedParameter::copyValue(sb_float4* to,const sb_float4* from) {*to = *(sb_float4*)from;;}; template<> inline void TypedParameter::copyValue(sb_uint3* to,const sb_uint3* from) {*to = *(sb_uint3*)from;;}; template<> inline void TypedParameter< std::vector >::copyValue(std::vector * to,const std::vector * from) { to->clear(); for (int v : *from) { to->push_back(v); } }; template<> inline void TypedParameter< std::vector >::copyValue(std::vector * to,const std::vector * from) { to->clear(); for (auto v : *from) { to->push_back(v); } }; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(unsigned int*)ptr_) = atoi(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(int*)ptr_) = atoi(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(long unsigned int*)ptr_) = atoi(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(float*)ptr_) = atof(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(double*)ptr_) = atof(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(sb_float3*)ptr_)= atof3(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(sb_float4*)ptr_)= atof4(otarg);}; template<> inline void TypedParameter::setValue(const char*otarg) {if (ptr_) (*(sb_uint3*)ptr_) = atoi3(otarg);}; template<> inline void TypedParameter< std::vector >::setValue(const char*from) { if (ptr_ == nullptr) return; std::istringstream ss(from); std::string value; ((std::vector*)ptr_)->clear(); while(std::getline(ss, value, ',')) { ((std::vector*)ptr_)->push_back(atoi(value.c_str())); } }; template<> inline void TypedParameter< std::vector >::setValue(const char*from) { if (ptr_ == nullptr) return; std::istringstream ss(from); std::string value; ((std::vector*)ptr_)->clear(); while(std::getline(ss, value, ',')) { ((std::vector*)ptr_)->push_back((value.c_str())); } }; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{return precise_to_string(*(unsigned int*)ptr);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{return precise_to_string(*(int*)ptr);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{return precise_to_string(*(long unsigned int*)ptr);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{return precise_to_string(*(float*)ptr);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{return precise_to_string(*(double*)ptr);}; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{ return "" + precise_to_string(((sb_float3*)ptr)->x) + "," + precise_to_string(((sb_float3*)ptr)->y) + "," + precise_to_string(((sb_float3*)ptr)->z) + ""; }; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{ return "" + precise_to_string(((sb_float4*)ptr)->x) + "," + precise_to_string(((sb_float4*)ptr)->y) + "," + precise_to_string(((sb_float4*)ptr)->z)+ "," + precise_to_string(((sb_float4*)ptr)->w) + ""; }; template<> inline const std::string TypedParameter::getValue(const void * ptr) const{ return "" + precise_to_string(((sb_uint3*)ptr)->x) + "," + precise_to_string(((sb_uint3*)ptr)->y) + "," + precise_to_string(((sb_uint3*)ptr)->z) + ""; }; template<> inline const std::string TypedParameter< std::vector >::getValue(const void * ptr) const{ std::string res ; res = "" ; for (auto it = (*(std::vector*)ptr).begin() ; it != (*(std::vector*)ptr).end() ; it++ ) { if (it != (*(std::vector*)ptr).begin() ) { res +=","; } res += precise_to_string(*it); } res +=""; return res; }; template<> inline const std::string TypedParameter< std::vector >::getValue(const void * ptr) const{ std::string res = "" ; for (auto it = (*(std::vector*)ptr).begin() ; it != (*(std::vector*)ptr).end() ; it++ ) { if (it != (*(std::vector*)ptr).begin() ) { res +=","; } res += *it; } res += ""; return res; }; template struct DiscretParameter : TypedParameter { std::vector values; DiscretParameter(std::vector values , std::string shortOption,std::string name, std::string description, T* ptr,const T* default_v, void (*callback)(Parameter*, ParameterComponent*) = nullptr) : TypedParameter (shortOption, name , description, ptr, default_v, callback) , values(values) {} virtual ~DiscretParameter() {} virtual inline const std::string getStrDetails(ParameterComponent* pc) { std::stringstream res; res << TypedParameter::getStrDetails(pc); for (auto value : this->values) { res << "values:" << this->getValue(&value) << "\n"; } return res.str(); } }; template struct BoundedParameter : TypedParameter { T min_, max_; BoundedParameter(T min, T max, std::string shortOption,std::string name, std::string description, T* ptr,const T* default_v, void (*callback)(Parameter*, ParameterComponent*) = nullptr) : TypedParameter (shortOption, name , description, ptr, default_v, callback), min_(min), max_(max) {} virtual ~BoundedParameter() {} virtual inline const std::string getStrDetails(ParameterComponent* pc) { std::stringstream res; res << TypedParameter::getStrDetails(pc); res << "min:" << this->min_ << "\n"; res << "max:" << this->max_ << "\n"; return res.str(); } }; #endif /* FRAMEWORK_SHARED_INCLUDE_PARAMETERS_H_ */ ================================================ FILE: framework/shared/include/ResultWriter.h ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #ifndef RESULT_WRITER_H_ #define RESULT_WRITER_H_ #include #include class ResultWriter { public: ResultWriter(std::ofstream &stream); void WriteKV(std::string key, std::string value); void WriteKV(std::string key, std::vector values, std::string separator=","); void WriteTrajectory(slambench::outputs::BaseOutput::value_map_t traj); static std::string GetCPUModel(); static std::string GetMemorySize(); private: std::ofstream &out_; }; #endif ================================================ FILE: framework/shared/include/SLAMBenchAPI.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_SLAMBENCHAPI_H_ #define FRAMEWORK_SHARED_INCLUDE_SLAMBENCHAPI_H_ #include #include namespace slambench { namespace io { class SLAMFrame; } } /* * Those functions define SLAMBenchConfiguration and reuse it after parameters parsing * sb_new_slam_configuration: allocate slam_settings * sb_init_slam_system: retrieve arguments from slam_settings * */ bool sb_new_slam_configuration(SLAMBenchLibraryHelper * slam_settings) ; bool sb_init_slam_system(SLAMBenchLibraryHelper * slam_settings) ; /* * Every frame we update the sensors and we process * sb_update_frame: update information for a specific sensor, must be call for each sensor * sb_process_once: once every sensor are updated slam process them * */ bool sb_update_frame (SLAMBenchLibraryHelper * slam_settings, slambench::io::SLAMFrame * type) ; bool sb_relocalize (SLAMBenchLibraryHelper * slam_settings) ; bool sb_process_once (SLAMBenchLibraryHelper * slam_settings) ; /* * At any time, the SLAM system needs to provide its outputs * */ bool sb_update_outputs(SLAMBenchLibraryHelper *lib, const slambench::TimeStamp *latest_output); /* * At the end of the process the SLAM system can be ask to save the volume in a file and to clean memory * */ bool sb_clean_slam_system(); /* * C equivalent of each function (not used) * */ extern "C" { bool c_sb_new_slam_configuration(void * slam_settings) ; bool c_sb_init_slam_system(void* slam_settings) ; bool c_sb_update_frame (void * slam_settings, void * type) ; bool c_sb_relocalize (void * slam_settings) ; bool c_sb_process_once (void * slam_settings) ; bool c_sb_update_outputs(void *lib, void *timestamp); bool c_sb_clean_slam_system(); } #endif /* FRAMEWORK_SHARED_INCLUDE_SLAMBENCHAPI_H_ */ ================================================ FILE: framework/shared/include/SLAMBenchConfiguration.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef SLAMBENCH_CONFIGURATION_H_ #define SLAMBENCH_CONFIGURATION_H_ #include #include #include #include "ColumnWriter.h" #include #include #include #include #include #include #include #include #include #include #include #include #define LOAD_FUNC2HELPER(handle,lib,f) *(void**)(& lib->f) = dlsym(handle,#f); const char *dlsym_error_##lib##f = dlerror(); if (dlsym_error_##lib##f) {std::cerr << "Cannot load symbol " << #f << dlsym_error_##lib##f << std::endl; dlclose(handle); exit(1);} static const unsigned int default_frame_limit = 0; static const unsigned int default_start_frame = 0; static const double default_realtime_mult = 1; static const std::string default_dump_volume_file = ""; static const std::string default_log_file = ""; static const std::string default_save_map = ""; static const std::vector default_slam_libraries = {}; static const std::vector default_input_files = {}; static const bool default_is_false = false; typedef std::chrono::time_point stl_time; class SLAMBenchConfiguration : public ParameterComponent { private: slam_lib_container_t slam_libs_; std::ofstream log_filestream_; std::ostream* log_stream_; std::string log_file_; std::vector input_files_; std::vector slam_library_names_; slambench::RowNumberColumn row_number_; std::unique_ptr writer_; std::shared_ptr duration_metric_; std::shared_ptr power_metric_; std::vector alignments_; std::string alignment_technique_ = "umeyama"; std::string output_filename_; std::vector input_filenames_; slambench::ParameterManager param_manager_; slambench::outputs::OutputManager ground_truth_; std::vector> frame_callbacks_; double realtime_mult_; int current_input_id_ = 0; unsigned int frame_limit_; bool initialised_; unsigned int start_frame_; bool realtime_mode_; bool gt_available_; bool aided_reloc_ = false; public: SLAMBenchConfiguration(void (*input_callback)(Parameter*, ParameterComponent*) = nullptr, void (*libs_callback)(Parameter*, ParameterComponent*) = nullptr); ~SLAMBenchConfiguration() override; void AddFrameCallback(std::function callback) { frame_callbacks_.push_back(callback); } const slam_lib_container_t &GetLoadedLibs() const { return slam_libs_; } const slambench::ParameterManager &GetParameterManager() const { return param_manager_; } slambench::ParameterManager &GetParameterManager() { return param_manager_; } slambench::outputs::OutputManager &GetGroundTruth() { return ground_truth_; } /** * Initialise the selected libraries and inputs. * Initialise the ground truth output manager. All ground truth sensors in * the sensor collection are registered as GT outputs, and all frames * within the collection are registered as GT output values. */ void InitGroundtruth(bool with_point_cloud = false); void InitAlgorithms(); void InitAlignment(); void InitWriter(); void SaveResults(); void ComputeLoopAlgorithm(bool *stay_on, SLAMBenchUI *ui); void AddSLAMLibrary(const std::string& so_file, const std::string &id); bool LoadNextInputInterface(); inline std::ostream& GetLogStream() { if (!log_stream_) UpdateLogStream(); return *log_stream_; } inline void UpdateLogStream() { if (log_file_ != "") { log_filestream_.open(log_file_.c_str()); log_stream_ = &log_filestream_; } else { log_stream_ = &std::cout; } } inline void ResetSensors() { param_manager_.ClearComponents(); for (slambench::io::Sensor *sensor : input_interface_manager_->GetCurrentInputInterface()->GetSensors()) { GetParameterManager().AddComponent(dynamic_cast(&(*sensor))); } } void FireEndOfFrame() { for(auto i : frame_callbacks_) { i(); } } void StartStatistics(); void PrintDse(); slambench::io::InputInterfaceManager* input_interface_manager_; }; inline void input_callback(Parameter* param, ParameterComponent* caller) { auto config = dynamic_cast (caller); assert(config != nullptr && "caller can not be turned into a SLAMBenchConfiguration*"); auto parameter = dynamic_cast>*>(param); assert(parameter && "parameter list corrupted"); config->input_interface_manager_ = new slambench::io::InputInterfaceManager(parameter->getTypedValue()); //if(!config->input_interface_manager_.initialized()) { // first_sensors_ = &input_ref->GetSensors(); //} else { // input_ref->GetSensors() = *first_sensors_; //} for (slambench::io::Sensor *sensor : config->input_interface_manager_->GetCurrentInputInterface()->GetSensors()) { config->GetParameterManager().AddComponent(dynamic_cast(&(*sensor))); } } inline void help_callback(Parameter*, ParameterComponent* caller) { auto config = dynamic_cast (caller); std::cerr << " == SLAMBench Configuration ==" << std::endl; std::cerr << " Available parameters :" << std::endl; config->GetParameterManager().PrintArguments(std::cerr); exit(0); } inline void dse_callback(Parameter*, ParameterComponent* caller) { auto config = dynamic_cast(caller); config->PrintDse(); exit(0); } inline void log_callback(Parameter*, ParameterComponent* caller) { auto config = dynamic_cast(caller); config->UpdateLogStream(); } inline void slam_library_callback(Parameter* param, ParameterComponent* caller) { auto config = dynamic_cast(caller); auto parameter = dynamic_cast>*>(param) ; for (auto &library_name : parameter->getTypedValue()) { std::string library_filename; std::string library_identifier; auto pos = library_name.find('='); if (pos != std::string::npos) { library_filename = library_name.substr(0, pos); library_identifier = library_name.substr(pos+1); } else { library_filename = library_name; } config->AddSLAMLibrary(library_filename, library_identifier); } } #endif /* SLAMBENCH_CONFIGURATION_H_ */ ================================================ FILE: framework/shared/include/SLAMBenchException.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_SLAMBENCHEXCEPTION_H_ #define FRAMEWORK_SHARED_INCLUDE_SLAMBENCHEXCEPTION_H_ #include #include class SLAMBenchException : public std::exception { private: std::string err_msg_; public: SLAMBenchException(const char *msg) : err_msg_(msg) {}; ~SLAMBenchException() throw() {}; const char *what() const throw() { return this->err_msg_.c_str(); }; }; #endif /* FRAMEWORK_SHARED_INCLUDE_SLAMBENCHEXCEPTION_H_ */ ================================================ FILE: framework/shared/include/SLAMBenchLibraryHelper.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_SLAMBENCHLIBRARYHELPER_H_ #define FRAMEWORK_SHARED_INCLUDE_SLAMBENCHLIBRARYHELPER_H_ #include #include #include #include #include #include #include #include #include class SLAMBenchLibraryHelper : public ParameterComponent { private : std::string identifier_; std::string library_name_; slambench::metrics::MetricManager metric_manager_; std::ostream& log_stream_; slambench::io::InputInterface* input_interface_; slambench::outputs::OutputManager output_manager_; public: bool (* c_sb_new_slam_configuration)(SLAMBenchLibraryHelper*); bool (* c_sb_init_slam_system)(SLAMBenchLibraryHelper*); bool (* c_sb_update_frame)(SLAMBenchLibraryHelper*, slambench::io::SLAMFrame*); bool (* c_sb_process_once)(SLAMBenchLibraryHelper*); bool (* c_sb_clean_slam_system)(); bool (* c_sb_update_outputs)(SLAMBenchLibraryHelper*, const slambench::TimeStamp *ts); bool (* c_sb_relocalize)(SLAMBenchLibraryHelper* ); SLAMBenchLibraryHelper(const std::string& id, std::string lib, std::ostream& l, slambench::io::InputInterface* i) : ParameterComponent(id), identifier_(id), library_name_(std::move(lib)), log_stream_(l), input_interface_(i), c_sb_new_slam_configuration(nullptr), c_sb_init_slam_system(nullptr), c_sb_update_frame(nullptr), c_sb_process_once(nullptr), c_sb_clean_slam_system(nullptr), c_sb_update_outputs(nullptr), c_sb_relocalize(nullptr) {} inline const std::string& GetIdentifier() const {return identifier_;} inline const std::string& GetLibraryName() const {return library_name_;} inline std::ostream& GetLogStream() {return log_stream_;} inline slambench::metrics::MetricManager &GetMetricManager() { return metric_manager_; } inline slambench::outputs::OutputManager &GetOutputManager() { return output_manager_; } inline slambench::io::InputInterface *GetInputInterface() { return input_interface_;} inline const slambench::io::SensorCollection &get_sensors() { return this->GetInputInterface()->GetSensors(); } inline void update_input_interface(slambench::io::InputInterface* interface) { input_interface_ = interface; } }; typedef std::vector slam_lib_container_t; #endif /* FRAMEWORK_SHARED_INCLUDE_SLAMBENCHLIBRARYHELPER_H_ */ ================================================ FILE: framework/shared/include/SLAMBenchUI.h ================================================ #ifndef SLAMBENCHUI_H_ #define SLAMBENCHUI_H_ // #define DEBUG_MUTEXES #include #include #include #include #include #include #include #include #ifdef DEBUG_MUTEXES #include #endif #include /* * ************************************************************************************************ * ********************** SLAMBenchUI * ************************************************************************************************ */ class SLAMBenchUI { protected : int frame = 0; int width = 0; int height = 0; float cx = 0,cy = 0,fx = 0,fy = 0; public : typedef std::vector> output_manager_container; virtual ~SLAMBenchUI() {}; virtual bool process() = 0; virtual void stepFrame() { this->frame += 1; } virtual bool IsFreeRunning() { return true; } virtual bool CanFreeRun() { return true; } virtual bool SetFreeRunning() { return true; } virtual bool ClearFreeRunning() { return false; } virtual bool WaitForFrame() { return false; } virtual bool CanStep() { return false; } inline void update_camera(int height , int width, float fx, float fy , float cx , float cy ) { this->width = width; this->height = height; this->fx = fx; this->fy = fy; this->cx = cx; this->cy = cy; }; void AddOutputManager(const std::string &name, slambench::outputs::OutputManager *mgr) { output_managers_.push_back(std::make_pair(name, mgr)); } const output_manager_container &GetOutputManagers() { return output_managers_; } private : output_manager_container output_managers_; }; #endif ================================================ FILE: framework/shared/include/SLAMBenchUI_Pangolin.h ================================================ #ifndef SLAMBENCHUI_PANGOLIN_H_ #define SLAMBENCHUI_PANGOLIN_H_ #define GLM_FORCE_RADIANS #include #include #include #include #include #include #include #include #define MAX_WINDOW 4 //#define GEN_FOLLOW_BUTTON_NAME(context_name,item) (item.name != "") ? "ui.Follow " + ((context_name!="") ?context_name + " ":"") + item.name : "ui.Follow " + ((context_name!="")? context_name + " ":"") + " " + item.type ; #define GEN_FOLLOW_BUTTON_NAME(context_name,item) (item.name != "") ? "ui.Follow." + ((context_name!="") ?context_name + " ":"") + item.name : "ui.Follow." + context_name + " " + item.type ; //#define GEN_SHOW_BOX_NAME(context_name,item) (item.first.name != "") ? "ui.Show " + context_name + " " + item.first.name : "ui.Show " + context_name + " " + item.first.type ; #define GEN_SHOW_BOX_NAME(context_name,item) (item.first.name != "") ? "ui." + context_name + ".Show " + item.first.name : "ui." + context_name + ".Show " + item.first.type ; class PoseOutputDrawContext; class SLAMBenchUI_Pangolin : public SLAMBenchUI { public: SLAMBenchUI_Pangolin(); void InitialiseOutputs(); void AddControlsForOutput(const std::string &prefix, slambench::outputs::BaseOutput *output); void AddBackgroundControls(); void AddFollowControls(); bool DrawPoseOutput(slambench::outputs::BaseOutput *output); bool DrawPointCloudOutput(slambench::outputs::BaseOutput *output); bool DrawColouredPointCloudOutput(slambench::outputs::BaseOutput *output); bool DrawFrameOutput(slambench::outputs::BaseOutput *output); bool DrawOutput(slambench::outputs::BaseOutput *output); bool DrawList(slambench::outputs::BaseOutput *output); bool DrawFeature(slambench::values::FeatureValue* value); bool DrawString(slambench::outputs::BaseOutput* value); void drawTrajectory(const slambench::outputs::TrajectoryInterface *traj, float R, float G, float B, int print_poses = 0 ); void drawFrustum(Eigen::Matrix4f currPose, float R, float G, float B); bool process(); void preCall(); void DrawAxis(); void drawBackground(slambench::values::FrameValue * frame); unsigned int get_next_texture_id(); void FollowPose(Eigen::Matrix4f currPose ) ; void postCall(); void StopTracking(); ~SLAMBenchUI_Pangolin(); bool CanFreeRun() override; bool CanStep() override; bool ClearFreeRunning() override; bool IsFreeRunning() override; bool SetFreeRunning() override; bool WaitForFrame() override; private: std::map*> outputs_enabled_, outputs_visible_, outputs_follow_, outputs_background_; std::map pose_output_draw_contexts_; std::map*> outputs_text_; pangolin::Var* last_background_ = nullptr; pangolin::Var* last_follow_ = nullptr; std::map*> outputs_colour_; typedef struct { slambench::TimeStamp timestamp; GLuint VBO; } PointCloudState; std::map pointcloud_state_; std::vector frames_; bool EnqueueFrame(slambench::values::FrameValue*); bool DrawQueuedFrames(); bool DrawBackgrounds(); bool FollowPoses(); void lockOutputs(); void unlockOutputs(); pangolin::Var * frameCount; pangolin::Var * VRSS; pangolin::Var * VSIZE; pangolin::Var * TVM; pangolin::Var * CVM; pangolin::Var * TPM; pangolin::Var * CPM; pangolin::Var * showBackground; pangolin::Var * followPose; pangolin::Var * showEveryPose; pangolin::Var * freeRunning; pangolin::Var * nextFrame; pangolin::Var * unFollow; // RGB View pangolin::OpenGlRenderState s_cam; GLuint vbo; std::vector feature_texture_ids; uint32_t next_feature_texture_id_idx; uint textureId[MAX_WINDOW]; std::condition_variable step_cv; std::mutex step_mutex; bool isFreeRunning; }; #endif /* SLAMBENCHUI_PANGOLIN_H_ */ ================================================ FILE: framework/shared/include/TimeStamp.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef TIMESTAMP_H #define TIMESTAMP_H #include #include #include #include #include namespace slambench { struct TimeStamp { public: uint32_t S; uint32_t Ns; uint64_t ToNs() const { return (S * 1000000000ULL) + Ns; } double ToS() const { return ToNs() / 1000000000.0; } static TimeStamp get(uint32_t S, uint32_t Ns) { assert(Ns < 1000000000); TimeStamp ts; ts.S = S; ts.Ns = Ns; return ts; } static TimeStamp FromNs(uint64_t ns) { TimeStamp ts; ts.S = ns / 1000000000ULL; ts.Ns = ns % 1000000000ULL; return ts; } static TimeStamp Now() { auto time = std::chrono::duration_cast>>(std::chrono::high_resolution_clock::now().time_since_epoch()); return get(time.count() / 1000000000, time.count() % 1000000000); } }; typedef std::chrono::duration> Duration; inline void Sleep(const Duration d) { std::this_thread::sleep_for(d); } inline bool operator==(const TimeStamp &left, const TimeStamp &right) { return left.S == right.S && left.Ns == right.Ns; } inline bool operator!=(const TimeStamp &left, const TimeStamp &right) { return left.S != right.S || left.Ns != right.Ns; } inline bool operator<(const TimeStamp& left, const TimeStamp& right) { return ( left.S < right.S ) or ( left.S == right.S and left.Ns < right.Ns ); } inline bool operator<=(const TimeStamp& left, const TimeStamp& right) { return ( left.S < right.S ) or ( left.S == right.S and left.Ns <= right.Ns ); } inline bool operator>(const TimeStamp& left, const TimeStamp& right) { return ( left.S > right.S ) or ( left.S == right.S and left.Ns > right.Ns ); } inline bool operator>=(const TimeStamp& left, const TimeStamp& right) { return !(left < right); } inline Duration operator-(const TimeStamp& left, const TimeStamp& right) { uint64_t total_ns_left = left.Ns + (left.S * 1000000000ULL); uint64_t total_ns_right = right.Ns + (right.S * 1000000000ULL); uint64_t ns_diff = total_ns_left - total_ns_right; return Duration(ns_diff); } inline TimeStamp operator*(const TimeStamp &left, double right) { uint64_t total_ns = left.ToNs(); total_ns *= right; return TimeStamp::FromNs(total_ns); } inline void operator*=(TimeStamp &left, double right) { uint64_t total_ns = left.ToNs(); total_ns *= right; left = TimeStamp::FromNs(total_ns); } inline TimeStamp operator+(const TimeStamp &left, const TimeStamp &right) { TimeStamp res; res.S = left.S + right.S; res.Ns = left.Ns + right.Ns; if(res.Ns >= 1000000000) { res.Ns -= 1000000000; res.S += 1; } return res; } inline std::ostream &operator<<(std::ostream &str, const TimeStamp &t) { double s = t.S + (t.Ns / 1000000000.0); str << std::to_string(s); return str; } } #endif /* TIMESTAMP_H */ ================================================ FILE: framework/shared/include/io/Event.h ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_EVENT_H #define IO_EVENT_H #include namespace slambench { namespace io { struct Event { TimeStamp ts; uint16_t x; uint16_t y; bool polarity; Event(TimeStamp ts, uint16_t x, uint16_t y, bool polarity) : ts(ts), x(x), y(y), polarity(polarity) {} }; std::ostream& operator << (std::ostream &out, const Event &e) { out << e.ts.S << "." << e.ts.Ns << " = " << e.x << " " << e.y << " " << e.polarity; return out; } } } #endif // IO_EVENT_H ================================================ FILE: framework/shared/include/io/FrameBuffer.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_FRAMEBUFFER_H #define IO_FRAMEBUFFER_H #include #include namespace slambench { namespace io { class FrameBuffer { public: FrameBuffer(); ~FrameBuffer(); void Acquire(); bool TryAcquire(); void Release(); void ResetBuffer(); bool Busy(); bool Reserve(size_t size); void *Data(); void resetLock() { lock_.exchange(false); } private: std::atomic lock_; size_t size_; void *data_; }; } } #endif ================================================ FILE: framework/shared/include/io/FrameBufferSource.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_FRAMEBUFFERSOURCE_H #define IO_FRAMEBUFFERSOURCE_H #include namespace slambench { namespace io { class FrameBufferSource { public: virtual FrameBuffer *Next() = 0; virtual ~FrameBufferSource() {}; }; class SingleFrameBufferSource : public FrameBufferSource { public: FrameBuffer *Next() override; private: FrameBuffer fb_; }; } } #endif ================================================ FILE: framework/shared/include/io/FrameFormat.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_FRAMEFORMAT_H #define IO_FRAMEFORMAT_H #include namespace slambench { namespace io { namespace frameformat { enum EFrameFormat { UNKNOWN, Raster, JPEG, PNG }; EFrameFormat Parse(const std::string &); } } } #endif ================================================ FILE: framework/shared/include/io/FrameSource.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_FRAMESOURCE_H #define IO_FRAMESOURCE_H #include #include #include #include namespace slambench { namespace io { class SLAMFrame; class Sensor; class FrameStream { public: virtual ~FrameStream() = default; virtual SLAMFrame *GetNextFrame() = 0; virtual bool HasNextFrame() = 0; }; class FrameCollection { public: virtual ~FrameCollection() = default; virtual SLAMFrame *GetFrame(unsigned int index) = 0; virtual unsigned int GetFrameCount() = 0; }; class FrameCollectionStream : public FrameStream { public: FrameCollectionStream(FrameCollection &base_collection); SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; private: FrameCollection &collection_; unsigned int index_; }; /** * This is a class to separate out GT frames from the actual dataset. * Treated as a regular FrameStream, it will return only dataset frames, * skipping all of the GT frames. */ class GTBufferingFrameStream : public FrameStream { public: class GTFrameCollection : public FrameCollection { public: GTFrameCollection(GTBufferingFrameStream >_stream); ~GTFrameCollection() override = default; unsigned int GetFrameCount() override; SLAMFrame* GetFrame(unsigned int index) override; SLAMFrame* GetClosestFrameToTime(const slambench::TimeStamp& ts); private: GTBufferingFrameStream >_stream_; }; explicit GTBufferingFrameStream(FrameStream &base_stream); ~GTBufferingFrameStream() override = default; SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; GTFrameCollection *GetGTFrames(); private: void fastForward(); FrameStream &base_stream_; SLAMFrame *buffered_frame_; std::vector gt_frames_; }; /** * This is a class which returns frames according to how much real * time has passed since the last frame was fetched. * * If should_pause is set, then the stream will also block until the * frame should actually become available. */ class RealTimeFrameStream : public FrameStream { public: RealTimeFrameStream(FrameStream *base_stream, double multiplier, bool should_pause); ~RealTimeFrameStream() override = default; SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; private: bool is_valid_frame(SLAMFrame *frame) const; bool past_first_frame_; std::map last_frame_timestamp_; std::map last_frame_realtimestamp_; FrameStream *base_stream_; double acceleration_; bool should_pause_; }; } } #endif /* FRAMESOURCE_H */ ================================================ FILE: framework/shared/include/io/InputInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_INPUTINTERFACE_H #define IO_INPUTINTERFACE_H #include #include #include #include "sensor/SensorCollection.h" #include "deserialisation/SLAMFrameDeserialiser.h" namespace slambench { namespace io { class InputInterface { public: virtual ~InputInterface(); virtual SensorCollection &GetSensors() = 0; virtual FrameStream &GetFrames() = 0; }; class BasicInputInterface : public InputInterface { public: BasicInputInterface(FrameStream &frames, SensorCollection &sensors); FrameStream& GetFrames() override; SensorCollection& GetSensors() override; private: FrameStream &frames_; SensorCollection &sensors_; }; class FileInputInterface : public InputInterface { public: FileInputInterface(SLAMFile &input_file); FrameStream& GetFrames() override; SensorCollection& GetSensors() override; private: SLAMFile &file_; FrameCollectionStream stream_; }; class FileStreamInputInterface : public InputInterface { public: FileStreamInputInterface(FILE* input_file, FrameBufferSource *fb_source); FrameStream &GetFrames() override; SensorCollection &GetSensors() override; private: SLAMFrameDeserialiser deserialiser_; SensorCollection sensors_; }; } } #endif ================================================ FILE: framework/shared/include/io/InputInterfaceManager.h ================================================ /* Copyright (c) 2020 University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_INPUTINTERFACEMANAGER_H #define IO_INPUTINTERFACEMANAGER_H #include #include #include #include "sensor/SensorCollection.h" #include "deserialisation/SLAMFrameDeserialiser.h" #include "InputInterface.h" #include namespace slambench { namespace io { class InputInterfaceManager { public: InputInterfaceManager(const std::vector& dataset_filenames); ~InputInterfaceManager(); slambench::io::InputInterface *GetCurrentInputInterface(); SLAMFrame* GetNextFrame() const; SLAMFrame* GetClosestGTFrameToTime(slambench::TimeStamp& ts) const; bool LoadNextInputInterface(); bool initialized() { return input_interfaces_.empty(); } slambench::io::FrameStream *input_stream_; bool updated_ = false; private: std::list input_interfaces_; slambench::io::SensorCollection* first_sensors_; }; } } #endif // IO_INPUTINTERFACEMANAGER_H ================================================ FILE: framework/shared/include/io/PixelFormat.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_PIXELFORMAT_H #define IO_PIXELFORMAT_H #include #include namespace slambench { namespace io { namespace pixelformat { enum EPixelFormat { UNKNOWN, G_I_8, RGB_III_888, D_I_8, D_F_32, D_I_16, D_F_64, RGBA_IIII_8888 }; EPixelFormat Parse(const std::string &fmt); std::string TypeOf(EPixelFormat); size_t GetPixelSize(EPixelFormat); bool IsRGB(EPixelFormat); bool IsGrey(EPixelFormat); bool ISDepth(EPixelFormat); } } } #endif ================================================ FILE: framework/shared/include/io/SLAMFile.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFILE_H #define IO_SLAMFILE_H #include "FrameSource.h" #include "sensor/SensorCollection.h" #include "serialisation/SLAMFileSerialiser.h" #include #include namespace slambench { namespace io { class FrameBufferSource; class SLAMFrame; class Sensor; class SLAMFile : public FrameCollection { public: typedef SensorCollection sensor_container_t; typedef std::vector frame_container_t; typedef char magic_num_t[5]; typedef uint32_t version_t; sensor_container_t Sensors; static const int Version = 1; static const magic_num_t MagicNum; Sensor *GetSensor(const Sensor::sensor_type_t &type); SLAMFrame* GetFrame(unsigned int index) override; unsigned int GetFrameCount() override; void AddFrame(SLAMFrame *frame); static SLAMFile *Read(const std::string &filename, FrameBufferSource &fb_source); static bool Write(const std::string &filename, SLAMFile &file, SLAMFileSerialiser::frame_callback_t callback = nullptr); private: void AddGroundTruthFrame(SLAMFrame *frame); void AddRegularFrame(SLAMFrame *frame); frame_container_t frames_; }; } } #endif ================================================ FILE: framework/shared/include/io/SLAMFrame.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFRAME_H #define IO_SLAMFRAME_H #include #include #include #include #include #include "TimeStamp.h" #include "PixelFormat.h" namespace slambench { namespace io { class Sensor; class FrameBuffer; class SLAMFrame { public: virtual ~SLAMFrame(); TimeStamp Timestamp; Sensor *FrameSensor; size_t GetSize() const; void SetVariableSize(uint32_t size); uint32_t GetVariableSize() const; virtual void *GetData() = 0; virtual void FreeData() = 0; inline void SetData(void* data, size_t size) { data_ = malloc(size); memcpy(data_, data, size); } inline void SetData(void* data) { assert(data); data_ = data; } protected: void *data_; private: uint32_t size_if_variable_sized_; }; class SLAMInMemoryFrame : public SLAMFrame { public: void *Data; void *GetData() override; void FreeData() override; }; class SLAMFileFrame : public SLAMFrame { public: SLAMFileFrame(); typedef void (*callback_t)(SLAMFileFrame *, void *); callback_t ProcessCallback; std::string filename; void *GetData() override; void FreeData() override; protected: virtual void *LoadFile() = 0; }; class TxtFileFrame : public SLAMFileFrame { public: pixelformat::EPixelFormat input_pixel_format; protected: void *LoadFile() override; private: void *LoadCameraFile(); }; class ImageFileFrame : public SLAMFileFrame { protected: void *LoadFile() override; private: void *LoadPng(); void *LoadPbm(); }; class DeserialisedFrame : public SLAMFrame { public: DeserialisedFrame(FrameBuffer &buffer, FILE *file); void SetOffset(size_t data_offset); void *GetData() override; void FreeData() override; FrameBuffer& getFrameBuffer() { return buffer_; } private: FrameBuffer &buffer_; FILE *file_; size_t offset_; }; } } #endif ================================================ FILE: framework/shared/include/io/SensorType.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSORTYPE_H #define IO_SENSORTYPE_H namespace slambench { namespace io { namespace sensortype { } } } #endif ================================================ FILE: framework/shared/include/io/core/Core.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_CORE_H #define IO_CORE_H #include #include #include #include #include namespace slambench { namespace io { namespace core { size_t FileSize(FILE *file); class MappedFile { public: MappedFile(void *mapped_ptr, size_t size); MappedFile(MappedFile && other); ~MappedFile(); const void *Get() { return ptr_; } size_t Size() { return size_; } private: void *ptr_; size_t size_; }; MappedFile ReadFile(const std::string &filename); } } } #endif /* IO_CORE_H */ ================================================ FILE: framework/shared/include/io/deserialisation/Deserialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_DESERIALISER_H #define IO_DESERIALISER_H #include namespace slambench { namespace io { class Deserialiser { public: Deserialiser(FILE *target_file); FILE *File() const; bool Read(void *target, size_t bytes) const; bool Skip(size_t skip) const; size_t Offset() const; bool Good() const; private: FILE *target_file_; }; } } #endif ================================================ FILE: framework/shared/include/io/deserialisation/SLAMFileDeserialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFILEDESERIALISER_H #define IO_SLAMFILEDESERIALISER_H #include "io/deserialisation/Deserialiser.h" namespace slambench { namespace io { class FrameBuffer; class FrameBufferSource; class SLAMFile; class SLAMFrame; class SLAMFileDeserialiser : public Deserialiser { public: SLAMFileDeserialiser(FILE *file, FrameBufferSource *framebuffer_source); bool Deserialise(SLAMFile &target) const; private: bool DeserialiseHeader(SLAMFile &target) const; bool DeserialiseFrames(SLAMFile &target) const; bool DeserialiseFrame(SLAMFile &file, SLAMFrame *&frame) const; FrameBuffer *GetNextFramebuffer() const; FrameBufferSource *fb_source_; }; } } #endif ================================================ FILE: framework/shared/include/io/deserialisation/SLAMFileHeaderDeserialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFILEHEADERDESERIALISER_H #define IO_SLAMFILEHEADERDESERIALISER_H #include "io/deserialisation/Deserialiser.h" namespace slambench { namespace io { class SLAMFileHeaderDeserialiser : public Deserialiser { public: SLAMFileHeaderDeserialiser(std::FILE *_file); bool Deserialise(); }; } } #endif ================================================ FILE: framework/shared/include/io/deserialisation/SLAMFrameDeserialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFRAMEDESERIALISER_H #define IO_SLAMFRAMEDESERIALISER_H #include "io/deserialisation/Deserialiser.h" #include "io/FrameSource.h" namespace slambench { namespace io { class FrameBufferSource; class SensorCollection; class SLAMFrameDeserialiser : public Deserialiser, public slambench::io::FrameStream { public: SLAMFrameDeserialiser(FILE *file, SensorCollection &_sensors, FrameBufferSource *fb_source); SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; private: SensorCollection &sensors_; FrameBufferSource *fb_source_; }; } } #endif /* SLAMFRAMEDESERIALISER_H */ ================================================ FILE: framework/shared/include/io/deserialisation/SensorCollectionDeserialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSORCOLLECTIONDESERIALISER_H #define IO_SENSORCOLLECTIONDESERIALISER_H #include "io/deserialisation/Deserialiser.h" namespace slambench { namespace io { class Sensor; class SensorCollection; class SensorCollectionDeserialiser : public Deserialiser { public: SensorCollectionDeserialiser(std::FILE *_file); bool Deserialise(SensorCollection &target) const; bool DeserialiseSensor(Sensor *&sensor) const; }; } } #endif /* SENSORCOLLECTIONDESERIALISER_H */ ================================================ FILE: framework/shared/include/io/format/DataFormatter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_DATAFORMATTER_H #define IO_DATAFORMATTER_H namespace slambench { namespace io { class Sensor; class DataFormatter { public: DataFormatter(Sensor *sensor, void *data); Sensor *GetSensor() { return sensor_; } const Sensor *GetSensor() const { return sensor_; } protected: const void *Data() const { return data_; } void *Data() { return data_; } private: void *data_; Sensor *sensor_; }; } } #endif /* IO_DATAFORMATTER_H */ ================================================ FILE: framework/shared/include/io/format/EventDataFormatter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_EVENTDATAFORMATTER_H #define IO_EVENTDATAFORMATTER_H #include "io/format/DataFormatter.h" #include "io/sensor/EventCameraSensor.h" #include namespace slambench { namespace io { class EventData { public: uint32_t X, Y; bool Raised; }; class EventDataFormatter : public DataFormatter { private: uint8_t coordsize_; public: EventDataFormatter(Sensor *sensor, void *data) : DataFormatter(sensor, data) { coordsize_ = ((EventCameraSensor*)sensor)->GetCoordinateSize(); } EventData Get() const { EventData data; const char *ptr = (const char*)Data(); switch(coordsize_) { case 1: data.X = *((uint8_t*)ptr++); data.Y = *((uint8_t*)ptr++); break; case 2: data.X = *((uint16_t*)ptr++); data.Y = *((uint16_t*)ptr++); break; case 4: data.X = *((uint32_t*)ptr++); data.Y = *((uint32_t*)ptr++); break; } data.Raised = *ptr; return data; } void Put(const EventData &data) { char *ptr = (char*)Data(); switch(coordsize_) { case 1: *((uint8_t*)ptr++) = data.X; *((uint8_t*)ptr++) = data.Y; break; case 2: *((uint16_t*)ptr++) = data.X; *((uint16_t*)ptr++) = data.Y; break; case 4: *((uint32_t*)ptr++) = data.X; *((uint32_t*)ptr++) = data.Y; break; } *ptr = data.Raised; } }; } } #endif /* IO_EVENTDATAFORMATTER_H */ ================================================ FILE: framework/shared/include/io/format/ImageDataFormatter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_IMAGEDATAFORMATTER_H #define IO_IMAGEDATAFORMATTER_H #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/format/DataFormatter.h" #include namespace slambench { namespace io { template class PixelData { PixelData(void *data); }; template<> class PixelData { public: PixelData(const void *data) { const char *cdata = (const char*)data; r_ = (uint8_t) cdata[0]; g_ = (uint8_t) cdata[1]; b_ = (uint8_t) cdata[2]; } static const size_t Size = 3; private: uint8_t r_, g_, b_; public: static_assert(sizeof(r_) + sizeof(g_) + sizeof(b_) == Size, "Size mismatch!"); uint8_t R() const { return r_; } uint8_t G() const { return g_; } uint8_t B() const { return b_; } }; template<> class PixelData { public: PixelData(const void* data) { const float *fdata = (const float*)data; _d = *fdata; } private: float _d; public: float D() const { return _d; } static const size_t Size = 4; static_assert(sizeof(_d) == Size, "Size mismatch"); }; template class RasterImageFormatter : public DataFormatter { public: typedef PixelData pixel_t; RasterImageFormatter(Sensor *sensor, void *data) : DataFormatter(sensor, data) { assert(sensor->GetType() == CameraSensor::kCameraType || sensor->GetType() == DepthSensor::kDepthType); } CameraSensor *GetCamera() { return (CameraSensor*)DataFormatter::GetSensor(); } size_t Line() const { return GetCamera()->Width * pixel_t::Size; } size_t Stride() const { return pixel_t::Size; } pixel_t Get(uint32_t x, uint32_t y) const { const char *data = (const char*)Data(); data += Line() * y; data += Stride() * x; return pixel_t(data); } }; } } #endif /* IO_IMAGEDATAFORMATTER_H */ ================================================ FILE: framework/shared/include/io/format/PointCloud.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_POINTCLOUD_H #define IO_POINTCLOUD_H #include #include namespace slambench { namespace io { class Point { public: Point() : x(0), y(0), z(0) {} Point(float x, float y, float z) : x(x), y(y), z(z) {} float x, y, z; }; class PointCloud { public: typedef std::vector storage_t; storage_t &Get() { return points_; } const storage_t &Get() const { return points_; } static PointCloud *FromRaw(char*); std::vector ToRaw(); private: storage_t points_; }; class PlyReader { public: PointCloud *Read(std::istream &file); }; class PlyWriter { public: void Write(const PointCloud *cloud, std::ostream &file); }; } } #endif /* IO_POINTCLOUD_H */ ================================================ FILE: framework/shared/include/io/openni15/ONI15Frame.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_ONIFRAME15_H #define IO_ONIFRAME15_H #include "../SLAMFrame.h" #define linux true #include #include #include namespace slambench { namespace io { class Sensor; namespace openni15 { class ONI15Frame : public SLAMFrame { public: ONI15Frame(Sensor *sensor, const xn::OutputMetaData *frameref); ~ONI15Frame(); void* GetData() override; void FreeData() override; }; } } } #endif /* IO_ONIFRAME15_H */ ================================================ FILE: framework/shared/include/io/openni15/ONI15FrameStream.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_ONI15FRAMESTREAM_H #define IO_ONI15FRAMESTREAM_H #include "../FrameSource.h" #include #include namespace xn { class DepthGenerator; class ImageGenerator; class MapGenerator; class Context; class DepthMetaData; class ImageMetaData; } namespace slambench { namespace io { class Sensor; class CameraSensor; namespace openni15 { /* This class represents a stream of frames from OpenNI15 generators. Once the stream has been created, each desired sensor should be activated. */ class ONI15FrameStream : public FrameStream { public: ONI15FrameStream(xn::Context *context) ; bool ActivateSensor(CameraSensor *sensor); bool StartStreams(); SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; private: xn::Context * context_; xn::DepthGenerator* depth_generator_; xn::ImageGenerator* image_generator_; xn::DepthMetaData* DMD_ ; xn::ImageMetaData* IMD_ ; std::map _sensor_map; }; } } } #endif /* IO_ONI2FRAMESTREAM_H */ ================================================ FILE: framework/shared/include/io/openni15/ONI15InputInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifdef DO_OPENNI15 #ifndef IO_ONI15INPUTINTERFACE_H #define IO_ONI15INPUTINTERFACE_H #include #include #include namespace xn { class Context; } namespace slambench { namespace io { class CameraSensor; class DepthSensor; namespace openni15 { class ONI15FrameStream; class ONI15InputInterface : public InputInterface { public: ONI15InputInterface(); FrameStream& GetFrames() override; SensorCollection& GetSensors() override; private: void BuildSensors(); CameraSensor *BuildCameraSensor() ; DepthSensor *BuildDepthSensor() ; void BuildStream(); xn::Context * context_; ONI15FrameStream *stream_; SensorCollection sensors_; bool sensors_ready_; }; } } } #endif /* IO_ONI15INPUTINTERFACE_H */ #endif /* DO_OPENNI15 */ ================================================ FILE: framework/shared/include/io/openni2/ONI2Frame.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_ONIFRAME_H #define IO_ONIFRAME_H #include "../SLAMFrame.h" #include namespace slambench { namespace io { class Sensor; namespace openni2 { class ONI2Frame : public SLAMFrame { public: ONI2Frame(Sensor *sensor, const openni::VideoFrameRef &frameref); void* GetData() override; void FreeData() override; }; } } } #endif /* IO_ONIFRAME_H */ ================================================ FILE: framework/shared/include/io/openni2/ONI2FrameStream.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_ONI2FRAMESTREAM_H #define IO_ONI2FRAMESTREAM_H #include "../FrameSource.h" #include #include namespace openni { class Device; class VideoStream; } namespace slambench { namespace io { class Sensor; class CameraSensor; namespace openni2 { /* This class represents a stream of frames from an OpenNI2 device. Once the stream has been created, each desired sensor should be activated. */ class ONI2FrameStream : public FrameStream { public: ONI2FrameStream(openni::Device *device); bool ActivateSensor(CameraSensor *sensor); bool StartStreams(); SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; private: openni::Device *device_; std::vector streams_; std::map sensor_map_; }; } } } #endif /* IO_ONI2FRAMESTREAM_H */ ================================================ FILE: framework/shared/include/io/openni2/ONI2InputInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifdef DO_OPENNI20 #ifndef IO_ONI2INPUTINTERFACE_H #define IO_ONI2INPUTINTERFACE_H #include #include #include namespace openni { class Device; class SensorInfo; } namespace slambench { namespace io { class CameraSensor; class DepthSensor; namespace openni2 { class ONI2FrameStream; class ONI2InputInterface : public InputInterface { public: ONI2InputInterface(); ONI2InputInterface(const std::string& oni2_filename); FrameStream& GetFrames() override; SensorCollection& GetSensors() override; private: void BuildSensors(); void BuildStream(); CameraSensor *BuildCameraSensor(const openni::SensorInfo *sensor_info) ; DepthSensor *BuildDepthSensor(const openni::SensorInfo *sensor_info) ; openni::Device *device_; ONI2FrameStream *stream_; SensorCollection sensors_; bool sensors_ready_; }; } } } #endif /* IO_ONI2INPUTINTERFACE_H */ #endif /* DO_OPENNI20 */ ================================================ FILE: framework/shared/include/io/realsense/RealSense2Frame.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_REALSENSE2FRAME_H #define IO_REALSENSE2FRAME_H #include "../SLAMFrame.h" #include namespace slambench { namespace io { class Sensor; namespace realsense { class RealSense2Frame : public SLAMFrame { public: RealSense2Frame(Sensor *sensor, const rs2::frame& frameref); void* GetData() override; void FreeData() override; }; } } } #endif /* IO_REALSENSE2FRAME_H */ ================================================ FILE: framework/shared/include/io/realsense/RealSense2FrameStream.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_REALSENSE2FRAMESTREAM_H #define IO_REALSENSE2FRAMESTREAM_H #include "../FrameSource.h" #include #include #include #include namespace slambench { namespace io { class Sensor; class CameraSensor; namespace realsense { /* This class represents a stream of frames from an OpenNI2 device. Once the stream has been created, each desired sensor should be activated. */ class RealSense2FrameStream : public FrameStream { public: RealSense2FrameStream(rs2::pipeline &pipe); ~RealSense2FrameStream(); bool ActivateSensor(rs2_stream stream, Sensor* sensor); SLAMFrame* GetNextFrame() override; bool HasNextFrame() override; // private: rs2::pipeline &pipe_; rs2::frameset frameset_; std::vector new_frames_; std::map sensor_map_; }; } } } #endif /* IO_REALSENSE2FRAMESTREAM_H */ ================================================ FILE: framework/shared/include/io/realsense/RealSense2InputInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifdef DO_REALSENSE #ifndef IO_REALSENSE2INPUTINTERFACE_H #define IO_REALSENSE2INPUTINTERFACE_H #include #include #include "RealSense2FrameStream.h" #include #include #include namespace slambench { namespace io { class CameraSensor; class DepthSensor; namespace realsense { class RealSense2FrameStream; class RealSense2InputInterface : public InputInterface { public: RealSense2InputInterface(); FrameStream& GetFrames() override; SensorCollection& GetSensors() override; inline RealSense2FrameStream& GetStream() {return *stream_;} private: void BuildRGBSensor(const rs2::stream_profile& color_profile); void BuildDepthSensor(const rs2::stream_profile& depth_profile); void BuildAccelerometerGyroSensor(const rs2::stream_profile& motion_profile); void BuildStream(); RealSense2FrameStream* stream_; SensorCollection sensors_; bool sensors_ready_; rs2::pipeline pipe_; //rs2::frameset frameset_; }; } } } #endif /* IO_REALSENSE2INPUTINTERFACE_H */ #endif /* DO_REALSENSE */ ================================================ FILE: framework/shared/include/io/sensor/AccelerometerSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_ACCELEROMETERSENSOR_H #define IO_ACCELEROMETERSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class AccelerometerSensor : public Sensor { public: typedef float accel_intrinsic_t[12]; typedef float accel_noise_variances_t[3]; typedef float accel_bias_variances_t[3]; const static sensor_type_t kAccType; accel_intrinsic_t Intrinsic; accel_noise_variances_t NoiseVariances; accel_bias_variances_t BiasVariances; AccelerometerSensor(const sensor_name_t &sensor_name); size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_ACCELEROMETERSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/CameraSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_CAMERA_SENSOR_H #define IO_CAMERA_SENSOR_H #include "io/sensor/Sensor.h" #include "io/FrameFormat.h" #include "io/PixelFormat.h" namespace slambench { namespace io { class CameraSensor : public Sensor { public: // Intrisics as "Focal Length" and "Principal Point Offset" : fx, fy, cx, cy typedef float intrinsics_t[4]; // Distortion parameters : radial and tangential factors = k1, k2, p1, p2, p3 // More infos: https://docs.opencv.org/2.4/doc/tutorials/calib3d/camera_calibration/camera_calibration.html typedef enum {NoDistortion, RadialTangential, Equidistant, KannalaBrandt} distortion_type_t; typedef float distortion_coefficients_t[5]; const static sensor_type_t kCameraType; CameraSensor(const sensor_name_t &name, const sensor_type_t &type = kCameraType); // Resolution uint32_t Width; uint32_t Height; // Color setting frameformat::EFrameFormat FrameFormat; pixelformat::EPixelFormat PixelFormat; intrinsics_t Intrinsics; distortion_type_t DistortionType; distortion_coefficients_t RadialTangentialDistortion; distortion_coefficients_t EquidistantDistortion; distortion_coefficients_t Distortion; size_t GetFrameSize(const SLAMFrame *frame) const override; void CopyIntrinsics(const CameraSensor *other); void CopyIntrinsics(const intrinsics_t &other); void CopyRadialTangentialDistortion(const distortion_coefficients_t &other); void CopyEquidistantDistortion(const distortion_coefficients_t &other); void CopyDistortion(const distortion_coefficients_t &other, const distortion_type_t& type); }; } } #endif ================================================ FILE: framework/shared/include/io/sensor/CameraSensorFinder.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_CAMERASENSORFINDER_H #define IO_CAMERASENSORFINDER_H #include #include #include #include namespace slambench { namespace io { class SensorCollection; class CameraSensor; typedef std::pair CameraSensorFilter; class CameraSensorFinder { public: typedef std::function filter_lambda_t; CameraSensorFinder(); bool TestFilter(const CameraSensor *sensor, const CameraSensorFilter &filter); std::vector Find(const SensorCollection& sensors, const std::initializer_list &filters); CameraSensor *FindOne(const SensorCollection &sensors, const std::initializer_list &filters); private: void PrepareEvaluators(); std::map filter_evaluators_; }; } } #endif /* IO_CAMERASENSORFINDER_H */ ================================================ FILE: framework/shared/include/io/sensor/DepthSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_DEPTH_SENSOR_H #define IO_DEPTH_SENSOR_H #include "io/sensor/CameraSensor.h" namespace slambench { namespace io { class DepthSensor : public CameraSensor { public: DepthSensor(const Sensor::sensor_name_t &sensor_name); static const sensor_type_t kDepthType; typedef float disparity_params_t[2]; typedef enum { affine_disparity = 0x00000000, kinect_disparity = 0X00000001, } disparity_type_t; disparity_type_t DisparityType; disparity_params_t DisparityParams; void CopyDisparityParams(const DepthSensor *other); void CopyDisparityParams(const disparity_params_t &other); }; } } #endif ================================================ FILE: framework/shared/include/io/sensor/EventCameraSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_EVENTCAMERASENSOR_H #define IO_EVENTCAMERASENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class EventCameraSensor : public Sensor { public: EventCameraSensor(const sensor_name_t &sensor_name); static const sensor_type_t kEventCameraType; int Width; int Height; size_t GetCoordinateSize() const; size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_EVENTCAMERASENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/GroundTruthSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_GROUNDTRUTHSENSOR_H #define IO_GROUNDTRUTHSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class GroundTruthSensor : public Sensor { public: const static sensor_type_t kGroundTruthTrajectoryType; GroundTruthSensor(const Sensor::sensor_name_t &sensor_name); typedef Eigen::Matrix4f pose_t; size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_GROUNDTRUTHSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/GyroSensor.h ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #ifndef IO_GYROSENSOR_H #define IO_GYROSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class GyroSensor : public Sensor { public: typedef float gyro_intrinsic_t[12]; typedef float gyro_noise_variances_t[3]; typedef float gyro_bias_variances_t[3]; const static sensor_type_t kGyroType; gyro_intrinsic_t Intrinsic; gyro_noise_variances_t NoiseVariances; gyro_bias_variances_t BiasVariances; GyroSensor(const sensor_name_t &sensor_name); size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_GYROSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/IMUSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_IMUSENSOR_H #define IO_IMUSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class IMUSensor : public Sensor { public: static const sensor_type_t kIMUType; float GyroscopeNoiseDensity; float GyroscopeDriftNoiseDensity; float GyroscopeBiasDiffusion; float AcceleratorNoiseDensity; float AcceleratorBiasDiffusion; float AcceleratorSaturation; float GyroscopeSaturation; float AcceleratorDriftNoiseDensity; IMUSensor(const Sensor::sensor_name_t &sensor_name); size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_IMUSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/OdomSensor.h ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #ifndef IO_ODOMSENSOR_H #define IO_ODOMSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class OdomSensor : public Sensor { public: const static sensor_type_t kOdomType; OdomSensor(const sensor_name_t &sensor_name); size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_ODOMSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/PointCloudSensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_POINTCLOUDSENSOR_H #define IO_POINTCLOUDSENSOR_H #include "io/sensor/Sensor.h" namespace slambench { namespace io { class PointCloudSensor : public Sensor { public: static const sensor_type_t kPointCloudType; PointCloudSensor(const sensor_name_t &sensor_name); size_t GetFrameSize(const SLAMFrame *frame) const override; }; } } #endif /* IO_POINTCLOUDSENSOR_H */ ================================================ FILE: framework/shared/include/io/sensor/Sensor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSOR_SENSOR_H #define IO_SENSOR_SENSOR_H #include #include #include namespace slambench { namespace io { class Serialiser; class Deserialiser; class SLAMFrame; class Sensor : public ParameterComponent { public: typedef std::string sensor_name_t; typedef std::string sensor_type_t; typedef Eigen::Matrix4f pose_t; typedef uint8_t sensor_base_t; Sensor(const sensor_name_t &sensor_name, const sensor_type_t &sensor_type); virtual ~Sensor() = default; std::string Description; uint8_t Index; pose_t Pose; float Rate; float Delay; // Delay between sensor and baseline virtual size_t GetFrameSize(const SLAMFrame *frame) const = 0; const sensor_type_t &GetType() const; const sensor_name_t &GetName() const; void CopyPose(const Sensor *other); void CopyPose(const pose_t &other); bool IsVariableSize() const; bool IsGroundTruth() const; private: const sensor_name_t sensor_name_; const sensor_type_t sensor_type_; }; class SensorSerialiser { public: virtual ~SensorSerialiser() = default; bool Serialise(Serialiser *serialiser, const Sensor *sensor); virtual bool SerialiseSensorSpecific(Serialiser *serialiser, const Sensor *sensor) = 0; }; class SensorDeserialiser { public: virtual ~SensorDeserialiser() = default; bool Deserialise(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, const Deserialiser *d, Sensor **s); virtual bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t & type, Sensor **s) = 0; virtual bool DeserialiseSensorSpecific(const Deserialiser *d, Sensor *s) = 0; }; } } #endif ================================================ FILE: framework/shared/include/io/sensor/SensorCollection.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSOR_SENSORCOLLECTION_H #define IO_SENSOR_SENSORCOLLECTION_H #include "io/sensor/Sensor.h" #include #include namespace slambench { namespace io { class Sensor; class SensorCollection { protected: typedef std::vector container_t; public: container_t::iterator begin() { return container_.begin(); } container_t::iterator end() { return container_.end(); } container_t::const_iterator begin() const { return container_.begin(); } container_t::const_iterator end() const { return container_.end(); } Sensor &at(unsigned int sensor_idx); size_t size() const; Sensor *GetSensor(const Sensor::sensor_type_t &type); const Sensor *GetSensor(const Sensor::sensor_type_t &type) const; std::vector GetSensors(const Sensor::sensor_type_t & type); void AddSensor(Sensor *sensor); private: container_t container_; }; } } #endif ================================================ FILE: framework/shared/include/io/sensor/SensorDatabase.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSORDATABASE_H #define IO_SENSORDATABASE_H #include "io/sensor/Sensor.h" #include namespace slambench { namespace io { class SensorDatabaseEntry { public: SensorDatabaseEntry(SensorSerialiser *s, SensorDeserialiser *ds, bool ground_truth = false, bool variable_size = false); SensorSerialiser *GetSerialiser() const { return serialiser_; } SensorDeserialiser *GetDeserialiser() const {return deserialiser_; } bool IsGroundTruth() const { return is_ground_truth_; } bool IsVariableSize() const { return is_variable_size_; } private: SensorSerialiser *serialiser_; SensorDeserialiser *deserialiser_; bool is_ground_truth_; bool is_variable_size_; }; class SensorDatabase { public: SensorDatabaseEntry &Get(const Sensor::sensor_type_t &sensor_name); void RegisterSensor(const Sensor::sensor_type_t &sensor_name, const SensorDatabaseEntry &entry); static SensorDatabase *Singleton(void); private: std::map registrations_; static SensorDatabase *singleton_; }; class SensorDatabaseRegistration { public: SensorDatabaseRegistration(const Sensor::sensor_type_t &name, const SensorDatabaseEntry &entry); }; } } #endif /* IO_SENSORDATABASE_H */ ================================================ FILE: framework/shared/include/io/sensor/sensor_builder.h ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SENSOR_SENSOR_BUILDER_H #define IO_SENSOR_SENSOR_BUILDER_H #include #include #include #include #include #include #include #include #include namespace slambench { namespace io { template class SensorBuilder { protected: std::string name_; std::string description_; uint8_t index_; float rate_; float delay_; int width_; int height_; frameformat::EFrameFormat frameFormat_; pixelformat::EPixelFormat pixelFormat_; Sensor::pose_t pose_ = Sensor::pose_t::Identity(); CameraSensor::intrinsics_t intrinsics_; CameraSensor::distortion_type_t distortion_type_ = CameraSensor::NoDistortion; CameraSensor::distortion_coefficients_t distortion_; DepthSensor::disparity_type_t disparity_type_; DepthSensor::disparity_params_t disparity_; SensorBuilder() = default; public: T& name(const std::string& name) { name_ = name; return static_cast(*this); } T& index(const uint8_t& index) { index_ = index; return static_cast(*this); } T& description(const std::string& description) { description_ = description; return static_cast(*this); } T& rate(float rate) { rate_ = rate; return static_cast(*this); } T& size(uint32_t width, uint32_t height) { width_ = width; height_ = height; return static_cast(*this); } T& frameFormat(const frameformat::EFrameFormat& format) { frameFormat_ = format; return static_cast(*this); } T& pixelFormat(const pixelformat::EPixelFormat& format) { pixelFormat_ = format; return static_cast(*this); } T& pose(const Sensor::pose_t& pose) { pose_ = pose; return static_cast(*this); } T& delay(const float& delay) { delay_ = delay; return static_cast(*this); } T& intrinsics(const CameraSensor::intrinsics_t& intrinsics) { for(unsigned int i = 0; i < 4 ; ++i) { intrinsics_[i] = intrinsics[i]; } return static_cast(*this); } T& distortion(const CameraSensor::distortion_type_t& type, const CameraSensor::distortion_coefficients_t& distortion) { distortion_type_ = type; for(unsigned int i = 0; i < 5 ; ++i) { distortion_[i] = distortion[i]; } return static_cast(*this); } T& disparity(const DepthSensor::disparity_type_t& type, const DepthSensor::disparity_params_t& disparity) { disparity_type_ = type; for(int i = 0; i < 2; ++i) { disparity_[i] = disparity[i]; } return static_cast(*this); } static bool check(Sensor* s, std::string& name) { if(!s) { std::cout << name << " sensor not found..." << std::endl; return false; } else { std::cout << s->GetName() << " sensor created..." << std::endl; return true; } } }; class CameraSensorBuilder : public SensorBuilder { public: CameraSensor* build() { std::string name = name_.empty() ? "Camera" : name_; auto sensor = new CameraSensor(name, CameraSensor::kCameraType); sensor->Rate = rate_; sensor->Width = width_; sensor->Height = height_; sensor->Index = index_; sensor->FrameFormat = frameFormat_; sensor->PixelFormat = pixelFormat_; sensor->Description = description_.empty() ? "Camera" : description_; sensor->CopyPose(pose_); sensor->CopyIntrinsics(intrinsics_); sensor->DistortionType = distortion_type_; sensor->CopyDistortion(distortion_,distortion_type_); check(sensor, name); return sensor; } }; class RGBSensorBuilder : public SensorBuilder { public: CameraSensor* build() { std::string name = name_.empty() ? "RGB" : name_; auto sensor = new CameraSensor(name, CameraSensor::kCameraType); sensor->Rate = rate_; sensor->Width = width_; sensor->Height = height_; sensor->FrameFormat = frameFormat_ ? frameFormat_ : frameformat::Raster; sensor->PixelFormat = pixelFormat_ ? pixelFormat_ : pixelformat::RGB_III_888; sensor->Description = description_.empty() ? "RGB" : description_; sensor->CopyPose(pose_); sensor->CopyIntrinsics(intrinsics_); sensor->DistortionType = distortion_type_; sensor->CopyDistortion(distortion_,distortion_type_); check(sensor, name); return sensor; } }; class GreySensorBuilder : public SensorBuilder { public: CameraSensor* build() { std::string name = name_.empty() ? "Grey" : name_; auto sensor = new CameraSensor(name, CameraSensor::kCameraType); sensor->Rate = rate_; sensor->Width = width_; sensor->Height = height_; sensor->FrameFormat = frameFormat_ ? frameFormat_ : frameformat::Raster; sensor->PixelFormat = pixelformat::G_I_8; sensor->Description = description_.empty() ? "Grey" : description_; sensor->CopyPose(pose_); sensor->CopyIntrinsics(intrinsics_); sensor->DistortionType = distortion_type_; sensor->CopyDistortion(distortion_,distortion_type_); check(sensor, name); return sensor; } }; class DepthSensorBuilder : public SensorBuilder { public: DepthSensor* build() { std::string name = name_.empty() ? "Depth" : name_; auto sensor = new DepthSensor(name); sensor->Rate = rate_; sensor->Width = width_; sensor->Height = height_; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelFormat_ ? pixelFormat_ : pixelformat::D_I_16; sensor->Description = description_.empty() ? "Depth" : description_; sensor->CopyPose(pose_); sensor->CopyIntrinsics(intrinsics_); sensor->DistortionType = distortion_type_; sensor->CopyDistortion(distortion_,distortion_type_); sensor->DisparityType = disparity_type_; sensor->CopyDisparityParams(disparity_); check(sensor, name); return sensor; } }; class AccSensorBuilder : public SensorBuilder { public: AccelerometerSensor* build() { std::string name = name_.empty() ? "Accelerometer" : name_; auto sensor = new AccelerometerSensor(name); sensor->Description = description_.empty() ? "Accelerometer" : description_; check(sensor, name); return sensor; } }; class GyroSensorBuilder : public SensorBuilder { public: GyroSensor* build() { std::string name = name_.empty() ? "Gyro" : name_; auto sensor = new GyroSensor(name); sensor->Description = description_.empty() ? "Gyroscope" : description_; check(sensor, name); return sensor; } }; class OdomSensorBuilder : public SensorBuilder { public: OdomSensor* build() { std::string name = name_.empty() ? "Odom" : name_; auto sensor = new OdomSensor(name); sensor->Description = description_.empty() ? "Odometry" : description_; check(sensor, name); return sensor; } }; class GTSensorBuilder : public SensorBuilder { public: GroundTruthSensor* build() { std::string name = name_.empty() ? "GroundTruth" : name_; auto sensor = new GroundTruthSensor(name); sensor->Description = description_.empty() ? "GroundTruth" : description_; sensor->Rate = rate_; sensor->CopyPose(pose_); check(sensor, name); return sensor; } }; } // namespace io } // namespace slambench #endif // IO_SENSOR_SENSOR_BUILDER_H ================================================ FILE: framework/shared/include/io/serialisation/SLAMFileHeaderSerialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFILEHEADERSERIALISER_H #define IO_SLAMFILEHEADERSERIALISER_H #include "io/serialisation/Serialiser.h" namespace slambench { namespace io { class SLAMFile; class Sensor; class SLAMFileHeaderSerialiser : public Serialiser { public: SLAMFileHeaderSerialiser(FILE *target); bool Serialise(const SLAMFile &file); private: bool SerialiseHeader(const SLAMFile &file); bool SerialiseSensor(const Sensor &sensor); }; } } #endif ================================================ FILE: framework/shared/include/io/serialisation/SLAMFileSerialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFILESERIALISER_H #define IO_SLAMFILESERIALISER_H #include "io/serialisation/Serialiser.h" #include namespace slambench { namespace io { class SLAMFile; class SLAMFileSerialiser : public Serialiser { public: SLAMFileSerialiser(FILE *target); bool Serialise(SLAMFile &file); typedef void (*frame_callback_t)(int frame_num, int frame_count); frame_callback_t FrameCallback; private: bool SerialiseHeader(const SLAMFile &file); bool SerialiseFrames(SLAMFile &file); }; } } #endif ================================================ FILE: framework/shared/include/io/serialisation/SLAMFrameSerialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SLAMFRAMESERIALISER_H #define IO_SLAMFRAMESERIALISER_H #include "io/serialisation/Serialiser.h" #include namespace slambench { namespace io { class SLAMFrame; class SLAMFrameSerialiser : public Serialiser { public: SLAMFrameSerialiser(FILE *target); bool Serialise(SLAMFrame &frame); }; } } #endif ================================================ FILE: framework/shared/include/io/serialisation/Serialiser.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef IO_SERIALISER_H #define IO_SERIALISER_H #include namespace slambench { namespace io { class Serialiser { public: Serialiser(FILE *target_file); bool Write(const void *data, size_t size); protected: FILE *File(); private: FILE *_file; }; } } #endif ================================================ FILE: framework/shared/include/lodepng.h ================================================ /* LodePNG version 20140624 Copyright (c) 2005-2014 Lode Vandevenne This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 3. This notice may not be removed or altered from any source distribution. */ #ifndef LODEPNG_H #define LODEPNG_H #include /*for size_t*/ #ifdef __cplusplus #include #include #endif /*__cplusplus*/ /* The following #defines are used to create code sections. They can be disabled to disable code sections, which can give faster compile time and smaller binary. The "NO_COMPILE" defines are designed to be used to pass as defines to the compiler command to disable them without modifying this header, e.g. -DLODEPNG_NO_COMPILE_ZLIB for gcc. */ /*deflate & zlib. If disabled, you must specify alternative zlib functions in the custom_zlib field of the compress and decompress settings*/ #ifndef LODEPNG_NO_COMPILE_ZLIB #define LODEPNG_COMPILE_ZLIB #endif /*png encoder and png decoder*/ #ifndef LODEPNG_NO_COMPILE_PNG #define LODEPNG_COMPILE_PNG #endif /*deflate&zlib decoder and png decoder*/ #ifndef LODEPNG_NO_COMPILE_DECODER #define LODEPNG_COMPILE_DECODER #endif /*deflate&zlib encoder and png encoder*/ #ifndef LODEPNG_NO_COMPILE_ENCODER #define LODEPNG_COMPILE_ENCODER #endif /*the optional built in harddisk file loading and saving functions*/ #ifndef LODEPNG_NO_COMPILE_DISK #define LODEPNG_COMPILE_DISK #endif /*support for chunks other than IHDR, IDAT, PLTE, tRNS, IEND: ancillary and unknown chunks*/ #ifndef LODEPNG_NO_COMPILE_ANCILLARY_CHUNKS #define LODEPNG_COMPILE_ANCILLARY_CHUNKS #endif /*ability to convert error numerical codes to English text string*/ #ifndef LODEPNG_NO_COMPILE_ERROR_TEXT #define LODEPNG_COMPILE_ERROR_TEXT #endif /*Compile the default allocators (C's free, malloc and realloc). If you disable this, you can define the functions lodepng_free, lodepng_malloc and lodepng_realloc in your source files with custom allocators.*/ #ifndef LODEPNG_NO_COMPILE_ALLOCATORS #define LODEPNG_COMPILE_ALLOCATORS #endif /*compile the C++ version (you can disable the C++ wrapper here even when compiling for C++)*/ #ifdef __cplusplus #ifndef LODEPNG_NO_COMPILE_CPP #define LODEPNG_COMPILE_CPP #endif #endif #ifdef LODEPNG_COMPILE_PNG /*The PNG color types (also used for raw).*/ typedef enum LodePNGColorType { LCT_GREY = 0, /*greyscale: 1,2,4,8,16 bit*/ LCT_RGB = 2, /*RGB: 8,16 bit*/ LCT_PALETTE = 3, /*palette: 1,2,4,8 bit*/ LCT_GREY_ALPHA = 4, /*greyscale with alpha: 8,16 bit*/ LCT_RGBA = 6 /*RGB with alpha: 8,16 bit*/ } LodePNGColorType; #ifdef LODEPNG_COMPILE_DECODER /* Converts PNG data in memory to raw pixel data. out: Output parameter. Pointer to buffer that will contain the raw pixel data. After decoding, its size is w * h * (bytes per pixel) bytes larger than initially. Bytes per pixel depends on colortype and bitdepth. Must be freed after usage with free(*out). Note: for 16-bit per channel colors, uses big endian format like PNG does. w: Output parameter. Pointer to width of pixel data. h: Output parameter. Pointer to height of pixel data. in: Memory buffer with the PNG file. insize: size of the in buffer. colortype: the desired color type for the raw output image. See explanation on PNG color types. bitdepth: the desired bit depth for the raw output image. See explanation on PNG color types. Return value: LodePNG error code (0 means no error). */ unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_decode_memory, but always decodes to 32-bit RGBA raw image*/ unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize); /*Same as lodepng_decode_memory, but always decodes to 24-bit RGB raw image*/ unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize); #ifdef LODEPNG_COMPILE_DISK /* Load PNG from disk, from file with given name. Same as the other decode functions, but instead takes a filename as input. */ unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_decode_file, but always decodes to 32-bit RGBA raw image.*/ unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename); /*Same as lodepng_decode_file, but always decodes to 24-bit RGB raw image.*/ unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename); #endif /*LODEPNG_COMPILE_DISK*/ #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Converts raw pixel data into a PNG image in memory. The colortype and bitdepth of the output PNG image cannot be chosen, they are automatically determined by the colortype, bitdepth and content of the input pixel data. Note: for 16-bit per channel colors, needs big endian format like PNG does. out: Output parameter. Pointer to buffer that will contain the PNG image data. Must be freed after usage with free(*out). outsize: Output parameter. Pointer to the size in bytes of the out buffer. image: The raw pixel data to encode. The size of this buffer should be w * h * (bytes per pixel), bytes per pixel depends on colortype and bitdepth. w: width of the raw pixel data in pixels. h: height of the raw pixel data in pixels. colortype: the color type of the raw input image. See explanation on PNG color types. bitdepth: the bit depth of the raw input image. See explanation on PNG color types. Return value: LodePNG error code (0 means no error). */ unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_encode_memory, but always encodes from 32-bit RGBA raw image.*/ unsigned lodepng_encode32(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h); /*Same as lodepng_encode_memory, but always encodes from 24-bit RGB raw image.*/ unsigned lodepng_encode24(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h); #ifdef LODEPNG_COMPILE_DISK /* Converts raw pixel data into a PNG file on disk. Same as the other encode functions, but instead takes a filename as output. NOTE: This overwrites existing files without warning! */ unsigned lodepng_encode_file(const char* filename, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_encode_file, but always encodes from 32-bit RGBA raw image.*/ unsigned lodepng_encode32_file(const char* filename, const unsigned char* image, unsigned w, unsigned h); /*Same as lodepng_encode_file, but always encodes from 24-bit RGB raw image.*/ unsigned lodepng_encode24_file(const char* filename, const unsigned char* image, unsigned w, unsigned h); #endif /*LODEPNG_COMPILE_DISK*/ #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_CPP namespace lodepng { #ifdef LODEPNG_COMPILE_DECODER /*Same as lodepng_decode_memory, but decodes to an std::vector.*/ unsigned decode(std::vector& out, unsigned& w, unsigned& h, const unsigned char* in, size_t insize, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::vector& in, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #ifdef LODEPNG_COMPILE_DISK /* Converts PNG file from disk to raw pixel data in memory. Same as the other decode functions, but instead takes a filename as input. */ unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::string& filename, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER /*Same as lodepng_encode_memory, but encodes to an std::vector.*/ unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #ifdef LODEPNG_COMPILE_DISK /* Converts 32-bit RGBA raw pixel data into a PNG file on disk. Same as the other encode functions, but instead takes a filename as output. NOTE: This overwrites existing files without warning! */ unsigned encode(const std::string& filename, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned encode(const std::string& filename, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_ENCODER } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ERROR_TEXT /*Returns an English description of the numerical error code.*/ const char* lodepng_error_text(unsigned code); #endif /*LODEPNG_COMPILE_ERROR_TEXT*/ #ifdef LODEPNG_COMPILE_DECODER /*Settings for zlib decompression*/ typedef struct LodePNGDecompressSettings LodePNGDecompressSettings; struct LodePNGDecompressSettings { unsigned ignore_adler32; /*if 1, continue and don't give an error message if the Adler32 checksum is corrupted*/ /*use custom zlib decoder instead of built in one (default: null)*/ unsigned (*custom_zlib)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGDecompressSettings*); /*use custom deflate decoder instead of built in one (default: null) if custom_zlib is used, custom_deflate is ignored since only the built in zlib function will call custom_deflate*/ unsigned (*custom_inflate)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGDecompressSettings*); const void* custom_context; /*optional custom settings for custom functions*/ }; extern const LodePNGDecompressSettings lodepng_default_decompress_settings; void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Settings for zlib compression. Tweaking these settings tweaks the balance between speed and compression ratio. */ typedef struct LodePNGCompressSettings LodePNGCompressSettings; struct LodePNGCompressSettings /*deflate = compress*/ { /*LZ77 related settings*/ unsigned btype; /*the block type for LZ (0, 1, 2 or 3, see zlib standard). Should be 2 for proper compression.*/ unsigned use_lz77; /*whether or not to use LZ77. Should be 1 for proper compression.*/ unsigned windowsize; /*must be a power of two <= 32768. higher compresses more but is slower. Default value: 2048.*/ unsigned minmatch; /*mininum lz77 length. 3 is normally best, 6 can be better for some PNGs. Default: 0*/ unsigned nicematch; /*stop searching if >= this length found. Set to 258 for best compression. Default: 128*/ unsigned lazymatching; /*use lazy matching: better compression but a bit slower. Default: true*/ /*use custom zlib encoder instead of built in one (default: null)*/ unsigned (*custom_zlib)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGCompressSettings*); /*use custom deflate encoder instead of built in one (default: null) if custom_zlib is used, custom_deflate is ignored since only the built in zlib function will call custom_deflate*/ unsigned (*custom_deflate)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGCompressSettings*); const void* custom_context; /*optional custom settings for custom functions*/ }; extern const LodePNGCompressSettings lodepng_default_compress_settings; void lodepng_compress_settings_init(LodePNGCompressSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_PNG /* Color mode of an image. Contains all information required to decode the pixel bits to RGBA colors. This information is the same as used in the PNG file format, and is used both for PNG and raw image data in LodePNG. */ typedef struct LodePNGColorMode { /*header (IHDR)*/ LodePNGColorType colortype; /*color type, see PNG standard or documentation further in this header file*/ unsigned bitdepth; /*bits per sample, see PNG standard or documentation further in this header file*/ /* palette (PLTE and tRNS) Dynamically allocated with the colors of the palette, including alpha. When encoding a PNG, to store your colors in the palette of the LodePNGColorMode, first use lodepng_palette_clear, then for each color use lodepng_palette_add. If you encode an image without alpha with palette, don't forget to put value 255 in each A byte of the palette. When decoding, by default you can ignore this palette, since LodePNG already fills the palette colors in the pixels of the raw RGBA output. The palette is only supported for color type 3. */ unsigned char* palette; /*palette in RGBARGBA... order. When allocated, must be either 0, or have size 1024*/ size_t palettesize; /*palette size in number of colors (amount of bytes is 4 * palettesize)*/ /* transparent color key (tRNS) This color uses the same bit depth as the bitdepth value in this struct, which can be 1-bit to 16-bit. For greyscale PNGs, r, g and b will all 3 be set to the same. When decoding, by default you can ignore this information, since LodePNG sets pixels with this key to transparent already in the raw RGBA output. The color key is only supported for color types 0 and 2. */ unsigned key_defined; /*is a transparent color key given? 0 = false, 1 = true*/ unsigned key_r; /*red/greyscale component of color key*/ unsigned key_g; /*green component of color key*/ unsigned key_b; /*blue component of color key*/ } LodePNGColorMode; /*init, cleanup and copy functions to use with this struct*/ void lodepng_color_mode_init(LodePNGColorMode* info); void lodepng_color_mode_cleanup(LodePNGColorMode* info); /*return value is error code (0 means no error)*/ unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source); void lodepng_palette_clear(LodePNGColorMode* info); /*add 1 color to the palette*/ unsigned lodepng_palette_add(LodePNGColorMode* info, unsigned char r, unsigned char g, unsigned char b, unsigned char a); /*get the total amount of bits per pixel, based on colortype and bitdepth in the struct*/ unsigned lodepng_get_bpp(const LodePNGColorMode* info); /*get the amount of color channels used, based on colortype in the struct. If a palette is used, it counts as 1 channel.*/ unsigned lodepng_get_channels(const LodePNGColorMode* info); /*is it a greyscale type? (only colortype 0 or 4)*/ unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info); /*has it got an alpha channel? (only colortype 2 or 6)*/ unsigned lodepng_is_alpha_type(const LodePNGColorMode* info); /*has it got a palette? (only colortype 3)*/ unsigned lodepng_is_palette_type(const LodePNGColorMode* info); /*only returns true if there is a palette and there is a value in the palette with alpha < 255. Loops through the palette to check this.*/ unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info); /* Check if the given color info indicates the possibility of having non-opaque pixels in the PNG image. Returns true if the image can have translucent or invisible pixels (it still be opaque if it doesn't use such pixels). Returns false if the image can only have opaque pixels. In detail, it returns true only if it's a color type with alpha, or has a palette with non-opaque values, or if "key_defined" is true. */ unsigned lodepng_can_have_alpha(const LodePNGColorMode* info); /*Returns the byte size of a raw image buffer with given width, height and color mode*/ size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*The information of a Time chunk in PNG.*/ typedef struct LodePNGTime { unsigned year; /*2 bytes used (0-65535)*/ unsigned month; /*1-12*/ unsigned day; /*1-31*/ unsigned hour; /*0-23*/ unsigned minute; /*0-59*/ unsigned second; /*0-60 (to allow for leap seconds)*/ } LodePNGTime; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*Information about the PNG image, except pixels, width and height.*/ typedef struct LodePNGInfo { /*header (IHDR), palette (PLTE) and transparency (tRNS) chunks*/ unsigned compression_method;/*compression method of the original file. Always 0.*/ unsigned filter_method; /*filter method of the original file*/ unsigned interlace_method; /*interlace method of the original file*/ LodePNGColorMode color; /*color type and bits, palette and transparency of the PNG file*/ #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /* suggested background color chunk (bKGD) This color uses the same color mode as the PNG (except alpha channel), which can be 1-bit to 16-bit. For greyscale PNGs, r, g and b will all 3 be set to the same. When encoding the encoder writes the red one. For palette PNGs: When decoding, the RGB value will be stored, not a palette index. But when encoding, specify the index of the palette in background_r, the other two are then ignored. The decoder does not use this background color to edit the color of pixels. */ unsigned background_defined; /*is a suggested background color given?*/ unsigned background_r; /*red component of suggested background color*/ unsigned background_g; /*green component of suggested background color*/ unsigned background_b; /*blue component of suggested background color*/ /* non-international text chunks (tEXt and zTXt) The char** arrays each contain num strings. The actual messages are in text_strings, while text_keys are keywords that give a short description what the actual text represents, e.g. Title, Author, Description, or anything else. A keyword is minimum 1 character and maximum 79 characters long. It's discouraged to use a single line length longer than 79 characters for texts. Don't allocate these text buffers yourself. Use the init/cleanup functions correctly and use lodepng_add_text and lodepng_clear_text. */ size_t text_num; /*the amount of texts in these char** buffers (there may be more texts in itext)*/ char** text_keys; /*the keyword of a text chunk (e.g. "Comment")*/ char** text_strings; /*the actual text*/ /* international text chunks (iTXt) Similar to the non-international text chunks, but with additional strings "langtags" and "transkeys". */ size_t itext_num; /*the amount of international texts in this PNG*/ char** itext_keys; /*the English keyword of the text chunk (e.g. "Comment")*/ char** itext_langtags; /*language tag for this text's language, ISO/IEC 646 string, e.g. ISO 639 language tag*/ char** itext_transkeys; /*keyword translated to the international language - UTF-8 string*/ char** itext_strings; /*the actual international text - UTF-8 string*/ /*time chunk (tIME)*/ unsigned time_defined; /*set to 1 to make the encoder generate a tIME chunk*/ LodePNGTime time; /*phys chunk (pHYs)*/ unsigned phys_defined; /*if 0, there is no pHYs chunk and the values below are undefined, if 1 else there is one*/ unsigned phys_x; /*pixels per unit in x direction*/ unsigned phys_y; /*pixels per unit in y direction*/ unsigned phys_unit; /*may be 0 (unknown unit) or 1 (metre)*/ /* unknown chunks There are 3 buffers, one for each position in the PNG where unknown chunks can appear each buffer contains all unknown chunks for that position consecutively The 3 buffers are the unknown chunks between certain critical chunks: 0: IHDR-PLTE, 1: PLTE-IDAT, 2: IDAT-IEND Do not allocate or traverse this data yourself. Use the chunk traversing functions declared later, such as lodepng_chunk_next and lodepng_chunk_append, to read/write this struct. */ unsigned char* unknown_chunks_data[3]; size_t unknown_chunks_size[3]; /*size in bytes of the unknown chunks, given for protection*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGInfo; /*init, cleanup and copy functions to use with this struct*/ void lodepng_info_init(LodePNGInfo* info); void lodepng_info_cleanup(LodePNGInfo* info); /*return value is error code (0 means no error)*/ unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS void lodepng_clear_text(LodePNGInfo* info); /*use this to clear the texts again after you filled them in*/ unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str); /*push back both texts at once*/ void lodepng_clear_itext(LodePNGInfo* info); /*use this to clear the itexts again after you filled them in*/ unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, const char* transkey, const char* str); /*push back the 4 texts of 1 chunk at once*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /* Converts raw buffer from one color type to another color type, based on LodePNGColorMode structs to describe the input and output color type. See the reference manual at the end of this header file to see which color conversions are supported. return value = LodePNG error code (0 if all went ok, an error if the conversion isn't supported) The out buffer must have size (w * h * bpp + 7) / 8, where bpp is the bits per pixel of the output color type (lodepng_get_bpp) The fix_png value works as described in struct LodePNGDecoderSettings. Note: for 16-bit per channel colors, uses big endian format like PNG does. */ unsigned lodepng_convert(unsigned char* out, const unsigned char* in, LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, unsigned w, unsigned h, unsigned fix_png); #ifdef LODEPNG_COMPILE_DECODER /* Settings for the decoder. This contains settings for the PNG and the Zlib decoder, but not the Info settings from the Info structs. */ typedef struct LodePNGDecoderSettings { LodePNGDecompressSettings zlibsettings; /*in here is the setting to ignore Adler32 checksums*/ unsigned ignore_crc; /*ignore CRC checksums*/ /* The fix_png setting, if 1, makes the decoder tolerant towards some PNG images that do not correctly follow the PNG specification. This only supports errors that are fixable, were found in images that are actually used on the web, and are silently tolerated by other decoders as well. Currently only one such fix is implemented: if a palette index is out of bounds given the palette size, interpret it as opaque black. By default this value is 0, which makes it stop with an error on such images. */ unsigned fix_png; unsigned color_convert; /*whether to convert the PNG to the color type you want. Default: yes*/ #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS unsigned read_text_chunks; /*if false but remember_unknown_chunks is true, they're stored in the unknown chunks*/ /*store all bytes from unknown chunks in the LodePNGInfo (off by default, useful for a png editor)*/ unsigned remember_unknown_chunks; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGDecoderSettings; void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /*automatically use color type with less bits per pixel if losslessly possible. Default: AUTO*/ typedef enum LodePNGFilterStrategy { /*every filter at zero*/ LFS_ZERO, /*Use filter that gives minumum sum, as described in the official PNG filter heuristic.*/ LFS_MINSUM, /*Use the filter type that gives smallest Shannon entropy for this scanline. Depending on the image, this is better or worse than minsum.*/ LFS_ENTROPY, /* Brute-force-search PNG filters by compressing each filter for each scanline. Experimental, very slow, and only rarely gives better compression than MINSUM. */ LFS_BRUTE_FORCE, /*use predefined_filters buffer: you specify the filter type for each scanline*/ LFS_PREDEFINED } LodePNGFilterStrategy; /*automatically use color type with less bits per pixel if losslessly possible. Default: LAC_AUTO*/ typedef enum LodePNGAutoConvert { LAC_NO, /*use color type user requested*/ LAC_ALPHA, /*use color type user requested, but if only opaque pixels and RGBA or grey+alpha, use RGB or grey*/ LAC_AUTO, /*use PNG color type that can losslessly represent the uncompressed image the smallest possible*/ /* like AUTO, but do not choose 1, 2 or 4 bit per pixel types. sometimes a PNG image compresses worse if less than 8 bits per pixels. */ LAC_AUTO_NO_NIBBLES, /* like AUTO, but never choose palette color type. For small images, encoding the palette may take more bytes than what is gained. Note that AUTO also already prevents encoding the palette for extremely small images, but that may not be sufficient because due to the compression it cannot predict when to switch. */ LAC_AUTO_NO_PALETTE, LAC_AUTO_NO_NIBBLES_NO_PALETTE } LodePNGAutoConvert; /* Automatically chooses color type that gives smallest amount of bits in the output image, e.g. grey if there are only greyscale pixels, palette if there are less than 256 colors, ... The auto_convert parameter allows limiting it to not use palette, ... */ unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, const unsigned char* image, unsigned w, unsigned h, const LodePNGColorMode* mode_in, LodePNGAutoConvert auto_convert); /*Settings for the encoder.*/ typedef struct LodePNGEncoderSettings { LodePNGCompressSettings zlibsettings; /*settings for the zlib encoder, such as window size, ...*/ LodePNGAutoConvert auto_convert; /*how to automatically choose output PNG color type, if at all*/ /*If true, follows the official PNG heuristic: if the PNG uses a palette or lower than 8 bit depth, set all filters to zero. Otherwise use the filter_strategy. Note that to completely follow the official PNG heuristic, filter_palette_zero must be true and filter_strategy must be LFS_MINSUM*/ unsigned filter_palette_zero; /*Which filter strategy to use when not using zeroes due to filter_palette_zero. Set filter_palette_zero to 0 to ensure always using your chosen strategy. Default: LFS_MINSUM*/ LodePNGFilterStrategy filter_strategy; /*used if filter_strategy is LFS_PREDEFINED. In that case, this must point to a buffer with the same length as the amount of scanlines in the image, and each value must <= 5. You have to cleanup this buffer, LodePNG will never free it. Don't forget that filter_palette_zero must be set to 0 to ensure this is also used on palette or low bitdepth images.*/ const unsigned char* predefined_filters; /*force creating a PLTE chunk if colortype is 2 or 6 (= a suggested palette). If colortype is 3, PLTE is _always_ created.*/ unsigned force_palette; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*add LodePNG identifier and version as a text chunk, for debugging*/ unsigned add_id; /*encode text chunks as zTXt chunks instead of tEXt chunks, and use compression in iTXt chunks*/ unsigned text_compression; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGEncoderSettings; void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) /*The settings, state and information for extended encoding and decoding.*/ typedef struct LodePNGState { #ifdef LODEPNG_COMPILE_DECODER LodePNGDecoderSettings decoder; /*the decoding settings*/ #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER LodePNGEncoderSettings encoder; /*the encoding settings*/ #endif /*LODEPNG_COMPILE_ENCODER*/ LodePNGColorMode info_raw; /*specifies the format in which you would like to get the raw pixel buffer*/ LodePNGInfo info_png; /*info of the PNG image obtained after decoding*/ unsigned error; #ifdef LODEPNG_COMPILE_CPP //For the lodepng::State subclass. virtual ~LodePNGState() { } #endif } LodePNGState; /*init, cleanup and copy functions to use with this struct*/ void lodepng_state_init(LodePNGState* state); void lodepng_state_cleanup(LodePNGState* state); void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source); #endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ #ifdef LODEPNG_COMPILE_DECODER /* Same as lodepng_decode_memory, but uses a LodePNGState to allow custom settings and getting much more information about the PNG image and color mode. */ unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize); /* Read the PNG header, but not the actual data. This returns only the information that is in the header chunk of the PNG, such as width, height and color type. The information is placed in the info_png field of the LodePNGState. */ unsigned lodepng_inspect(unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /*This function allocates the out buffer with standard malloc and stores the size in *outsize.*/ unsigned lodepng_encode(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGState* state); #endif /*LODEPNG_COMPILE_ENCODER*/ /* The lodepng_chunk functions are normally not needed, except to traverse the unknown chunks stored in the LodePNGInfo struct, or add new ones to it. It also allows traversing the chunks of an encoded PNG file yourself. PNG standard chunk naming conventions: First byte: uppercase = critical, lowercase = ancillary Second byte: uppercase = public, lowercase = private Third byte: must be uppercase Fourth byte: uppercase = unsafe to copy, lowercase = safe to copy */ /*get the length of the data of the chunk. Total chunk length has 12 bytes more.*/ unsigned lodepng_chunk_length(const unsigned char* chunk); /*puts the 4-byte type in null terminated string*/ void lodepng_chunk_type(char type[5], const unsigned char* chunk); /*check if the type is the given type*/ unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type); /*0: it's one of the critical chunk types, 1: it's an ancillary chunk (see PNG standard)*/ unsigned char lodepng_chunk_ancillary(const unsigned char* chunk); /*0: public, 1: private (see PNG standard)*/ unsigned char lodepng_chunk_private(const unsigned char* chunk); /*0: the chunk is unsafe to copy, 1: the chunk is safe to copy (see PNG standard)*/ unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk); /*get pointer to the data of the chunk, where the input points to the header of the chunk*/ unsigned char* lodepng_chunk_data(unsigned char* chunk); const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk); /*returns 0 if the crc is correct, 1 if it's incorrect (0 for OK as usual!)*/ unsigned lodepng_chunk_check_crc(const unsigned char* chunk); /*generates the correct CRC from the data and puts it in the last 4 bytes of the chunk*/ void lodepng_chunk_generate_crc(unsigned char* chunk); /*iterate to next chunks. don't use on IEND chunk, as there is no next chunk then*/ unsigned char* lodepng_chunk_next(unsigned char* chunk); const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk); /* Appends chunk to the data in out. The given chunk should already have its chunk header. The out variable and outlength are updated to reflect the new reallocated buffer. Returns error code (0 if it went ok) */ unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk); /* Appends new chunk to out. The chunk to append is given by giving its length, type and data separately. The type is a 4-letter string. The out variable and outlength are updated to reflect the new reallocated buffer. Returne error code (0 if it went ok) */ unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data); /*Calculate CRC32 of buffer*/ unsigned lodepng_crc32(const unsigned char* buf, size_t len); #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ZLIB /* This zlib part can be used independently to zlib compress and decompress a buffer. It cannot be used to create gzip files however, and it only supports the part of zlib that is required for PNG, it does not support dictionaries. */ #ifdef LODEPNG_COMPILE_DECODER /*Inflate a buffer. Inflate is the decompression step of deflate. Out buffer must be freed after use.*/ unsigned lodepng_inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings); /* Decompresses Zlib data. Reallocates the out buffer and appends the data. The data must be according to the zlib specification. Either, *out must be NULL and *outsize must be 0, or, *out must be a valid buffer and *outsize its size in bytes. out must be freed by user after usage. */ unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Compresses data with Zlib. Reallocates the out buffer and appends the data. Zlib adds a small header and trailer around the deflate data. The data is output in the format of the zlib specification. Either, *out must be NULL and *outsize must be 0, or, *out must be a valid buffer and *outsize its size in bytes. out must be freed by user after usage. */ unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings); /* Find length-limited Huffman code for given frequencies. This function is in the public interface only for tests, it's used internally by lodepng_deflate. */ unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, size_t numcodes, unsigned maxbitlen); /*Compress a buffer with deflate. See RFC 1951. Out buffer must be freed after use.*/ unsigned lodepng_deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ #ifdef LODEPNG_COMPILE_DISK /* Load a file from disk into buffer. The function allocates the out buffer, and after usage you should free it. out: output parameter, contains pointer to loaded buffer. outsize: output parameter, size of the allocated out buffer filename: the path to the file to load return value: error code (0 means ok) */ unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename); /* Save a file from buffer to disk. Warning, if it exists, this function overwrites the file without warning! buffer: the buffer to write buffersize: size of the buffer to write filename: the path to the file to save to return value: error code (0 means ok) */ unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename); #endif /*LODEPNG_COMPILE_DISK*/ #ifdef LODEPNG_COMPILE_CPP //The LodePNG C++ wrapper uses std::vectors instead of manually allocated memory buffers. namespace lodepng { #ifdef LODEPNG_COMPILE_PNG class State: public LodePNGState { public: State(); State(const State& other); virtual ~State(); State& operator=(const State& other); }; #ifdef LODEPNG_COMPILE_DECODER //Same as other lodepng::decode, but using a State for more settings and information. unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const unsigned char* in, size_t insize); unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const std::vector& in); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER //Same as other lodepng::encode, but using a State for more settings and information. unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, State& state); unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, State& state); #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DISK /* Load a file from disk into an std::vector. If the vector is empty, then either the file doesn't exist or is an empty file. */ void load_file(std::vector& buffer, const std::string& filename); /* Save the binary data in an std::vector to a file on disk. The file is overwritten without warning. */ void save_file(const std::vector& buffer, const std::string& filename); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_PNG #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_DECODER //Zlib-decompress an unsigned char buffer unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); //Zlib-decompress an std::vector unsigned decompress(std::vector& out, const std::vector& in, const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER //Zlib-compress an unsigned char buffer unsigned compress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGCompressSettings& settings = lodepng_default_compress_settings); //Zlib-compress an std::vector unsigned compress(std::vector& out, const std::vector& in, const LodePNGCompressSettings& settings = lodepng_default_compress_settings); #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_ZLIB } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ /* TODO: [.] test if there are no memory leaks or security exploits - done a lot but needs to be checked often [.] check compatibility with vareous compilers - done but needs to be redone for every newer version [X] converting color to 16-bit per channel types [ ] read all public PNG chunk types (but never let the color profile and gamma ones touch RGB values) [ ] make sure encoder generates no chunks with size > (2^31)-1 [ ] partial decoding (stream processing) [X] let the "isFullyOpaque" function check color keys and transparent palettes too [X] better name for the variables "codes", "codesD", "codelengthcodes", "clcl" and "lldl" [ ] don't stop decoding on errors like 69, 57, 58 (make warnings) [ ] make option to choose if the raw image with non multiple of 8 bits per scanline should have padding bits or not [ ] let the C++ wrapper catch exceptions coming from the standard library and return LodePNG error codes */ #endif /*LODEPNG_H inclusion guard*/ /* LodePNG Documentation --------------------- 0. table of contents -------------------- 1. about 1.1. supported features 1.2. features not supported 2. C and C++ version 3. security 4. decoding 5. encoding 6. color conversions 6.1. PNG color types 6.2. color conversions 6.3. padding bits 6.4. A note about 16-bits per channel and endianness 7. error values 8. chunks and PNG editing 9. compiler support 10. examples 10.1. decoder C++ example 10.2. decoder C example 11. changes 12. contact information 1. about -------- PNG is a file format to store raster images losslessly with good compression, supporting different color types and alpha channel. LodePNG is a PNG codec according to the Portable Network Graphics (PNG) Specification (Second Edition) - W3C Recommendation 10 November 2003. The specifications used are: *) Portable Network Graphics (PNG) Specification (Second Edition): http://www.w3.org/TR/2003/REC-PNG-20031110 *) RFC 1950 ZLIB Compressed Data Format version 3.3: http://www.gzip.org/zlib/rfc-zlib.html *) RFC 1951 DEFLATE Compressed Data Format Specification ver 1.3: http://www.gzip.org/zlib/rfc-deflate.html The most recent version of LodePNG can currently be found at http://lodev.org/lodepng/ LodePNG works both in C (ISO C90) and C++, with a C++ wrapper that adds extra functionality. LodePNG exists out of two files: -lodepng.h: the header file for both C and C++ -lodepng.c(pp): give it the name lodepng.c or lodepng.cpp (or .cc) depending on your usage If you want to start using LodePNG right away without reading this doc, get the examples from the LodePNG website to see how to use it in code, or check the smaller examples in chapter 13 here. LodePNG is simple but only supports the basic requirements. To achieve simplicity, the following design choices were made: There are no dependencies on any external library. There are functions to decode and encode a PNG with a single function call, and extended versions of these functions taking a LodePNGState struct allowing to specify or get more information. By default the colors of the raw image are always RGB or RGBA, no matter what color type the PNG file uses. To read and write files, there are simple functions to convert the files to/from buffers in memory. This all makes LodePNG suitable for loading textures in games, demos and small programs, ... It's less suitable for full fledged image editors, loading PNGs over network (it requires all the image data to be available before decoding can begin), life-critical systems, ... 1.1. supported features ----------------------- The following features are supported by the decoder: *) decoding of PNGs with any color type, bit depth and interlace mode, to a 24- or 32-bit color raw image, or the same color type as the PNG *) encoding of PNGs, from any raw image to 24- or 32-bit color, or the same color type as the raw image *) Adam7 interlace and deinterlace for any color type *) loading the image from harddisk or decoding it from a buffer from other sources than harddisk *) support for alpha channels, including RGBA color model, translucent palettes and color keying *) zlib decompression (inflate) *) zlib compression (deflate) *) CRC32 and ADLER32 checksums *) handling of unknown chunks, allowing making a PNG editor that stores custom and unknown chunks. *) the following chunks are supported (generated/interpreted) by both encoder and decoder: IHDR: header information PLTE: color palette IDAT: pixel data IEND: the final chunk tRNS: transparency for palettized images tEXt: textual information zTXt: compressed textual information iTXt: international textual information bKGD: suggested background color pHYs: physical dimensions tIME: modification time 1.2. features not supported --------------------------- The following features are _not_ supported: *) some features needed to make a conformant PNG-Editor might be still missing. *) partial loading/stream processing. All data must be available and is processed in one call. *) The following public chunks are not supported but treated as unknown chunks by LodePNG cHRM, gAMA, iCCP, sRGB, sBIT, hIST, sPLT Some of these are not supported on purpose: LodePNG wants to provide the RGB values stored in the pixels, not values modified by system dependent gamma or color models. 2. C and C++ version -------------------- The C version uses buffers allocated with alloc that you need to free() yourself. You need to use init and cleanup functions for each struct whenever using a struct from the C version to avoid exploits and memory leaks. The C++ version has extra functions with std::vectors in the interface and the lodepng::State class which is a LodePNGState with constructor and destructor. These files work without modification for both C and C++ compilers because all the additional C++ code is in "#ifdef __cplusplus" blocks that make C-compilers ignore it, and the C code is made to compile both with strict ISO C90 and C++. To use the C++ version, you need to rename the source file to lodepng.cpp (instead of lodepng.c), and compile it with a C++ compiler. To use the C version, you need to rename the source file to lodepng.c (instead of lodepng.cpp), and compile it with a C compiler. 3. Security ----------- Even if carefully designed, it's always possible that LodePNG contains possible exploits. If you discover one, please let me know, and it will be fixed. When using LodePNG, care has to be taken with the C version of LodePNG, as well as the C-style structs when working with C++. The following conventions are used for all C-style structs: -if a struct has a corresponding init function, always call the init function when making a new one -if a struct has a corresponding cleanup function, call it before the struct disappears to avoid memory leaks -if a struct has a corresponding copy function, use the copy function instead of "=". The destination must also be inited already. 4. Decoding ----------- Decoding converts a PNG compressed image to a raw pixel buffer. Most documentation on using the decoder is at its declarations in the header above. For C, simple decoding can be done with functions such as lodepng_decode32, and more advanced decoding can be done with the struct LodePNGState and lodepng_decode. For C++, all decoding can be done with the various lodepng::decode functions, and lodepng::State can be used for advanced features. When using the LodePNGState, it uses the following fields for decoding: *) LodePNGInfo info_png: it stores extra information about the PNG (the input) in here *) LodePNGColorMode info_raw: here you can say what color mode of the raw image (the output) you want to get *) LodePNGDecoderSettings decoder: you can specify a few extra settings for the decoder to use LodePNGInfo info_png -------------------- After decoding, this contains extra information of the PNG image, except the actual pixels, width and height because these are already gotten directly from the decoder functions. It contains for example the original color type of the PNG image, text comments, suggested background color, etc... More details about the LodePNGInfo struct are at its declaration documentation. LodePNGColorMode info_raw ------------------------- When decoding, here you can specify which color type you want the resulting raw image to be. If this is different from the colortype of the PNG, then the decoder will automatically convert the result. This conversion always works, except if you want it to convert a color PNG to greyscale or to a palette with missing colors. By default, 32-bit color is used for the result. LodePNGDecoderSettings decoder ------------------------------ The settings can be used to ignore the errors created by invalid CRC and Adler32 chunks, and to disable the decoding of tEXt chunks. There's also a setting color_convert, true by default. If false, no conversion is done, the resulting data will be as it was in the PNG (after decompression) and you'll have to puzzle the colors of the pixels together yourself using the color type information in the LodePNGInfo. 5. Encoding ----------- Encoding converts a raw pixel buffer to a PNG compressed image. Most documentation on using the encoder is at its declarations in the header above. For C, simple encoding can be done with functions such as lodepng_encode32, and more advanced decoding can be done with the struct LodePNGState and lodepng_encode. For C++, all encoding can be done with the various lodepng::encode functions, and lodepng::State can be used for advanced features. Like the decoder, the encoder can also give errors. However it gives less errors since the encoder input is trusted, the decoder input (a PNG image that could be forged by anyone) is not trusted. When using the LodePNGState, it uses the following fields for encoding: *) LodePNGInfo info_png: here you specify how you want the PNG (the output) to be. *) LodePNGColorMode info_raw: here you say what color type of the raw image (the input) has *) LodePNGEncoderSettings encoder: you can specify a few settings for the encoder to use LodePNGInfo info_png -------------------- When encoding, you use this the opposite way as when decoding: for encoding, you fill in the values you want the PNG to have before encoding. By default it's not needed to specify a color type for the PNG since it's automatically chosen, but it's possible to choose it yourself given the right settings. The encoder will not always exactly match the LodePNGInfo struct you give, it tries as close as possible. Some things are ignored by the encoder. The encoder uses, for example, the following settings from it when applicable: colortype and bitdepth, text chunks, time chunk, the color key, the palette, the background color, the interlace method, unknown chunks, ... When encoding to a PNG with colortype 3, the encoder will generate a PLTE chunk. If the palette contains any colors for which the alpha channel is not 255 (so there are translucent colors in the palette), it'll add a tRNS chunk. LodePNGColorMode info_raw ------------------------- You specify the color type of the raw image that you give to the input here, including a possible transparent color key and palette you happen to be using in your raw image data. By default, 32-bit color is assumed, meaning your input has to be in RGBA format with 4 bytes (unsigned chars) per pixel. LodePNGEncoderSettings encoder ------------------------------ The following settings are supported (some are in sub-structs): *) auto_convert: when this option is enabled, the encoder will automatically choose the smallest possible color mode (including color key) that can encode the colors of all pixels without information loss. *) btype: the block type for LZ77. 0 = uncompressed, 1 = fixed huffman tree, 2 = dynamic huffman tree (best compression). Should be 2 for proper compression. *) use_lz77: whether or not to use LZ77 for compressed block types. Should be true for proper compression. *) windowsize: the window size used by the LZ77 encoder (1 - 32768). Has value 2048 by default, but can be set to 32768 for better, but slow, compression. *) force_palette: if colortype is 2 or 6, you can make the encoder write a PLTE chunk if force_palette is true. This can used as suggested palette to convert to by viewers that don't support more than 256 colors (if those still exist) *) add_id: add text chunk "Encoder: LodePNG " to the image. *) text_compression: default 1. If 1, it'll store texts as zTXt instead of tEXt chunks. zTXt chunks use zlib compression on the text. This gives a smaller result on large texts but a larger result on small texts (such as a single program name). It's all tEXt or all zTXt though, there's no separate setting per text yet. 6. color conversions -------------------- An important thing to note about LodePNG, is that the color type of the PNG, and the color type of the raw image, are completely independent. By default, when you decode a PNG, you get the result as a raw image in the color type you want, no matter whether the PNG was encoded with a palette, greyscale or RGBA color. And if you encode an image, by default LodePNG will automatically choose the PNG color type that gives good compression based on the values of colors and amount of colors in the image. It can be configured to let you control it instead as well, though. To be able to do this, LodePNG does conversions from one color mode to another. It can convert from almost any color type to any other color type, except the following conversions: RGB to greyscale is not supported, and converting to a palette when the palette doesn't have a required color is not supported. This is not supported on purpose: this is information loss which requires a color reduction algorithm that is beyong the scope of a PNG encoder (yes, RGB to grey is easy, but there are multiple ways if you want to give some channels more weight). By default, when decoding, you get the raw image in 32-bit RGBA or 24-bit RGB color, no matter what color type the PNG has. And by default when encoding, LodePNG automatically picks the best color model for the output PNG, and expects the input image to be 32-bit RGBA or 24-bit RGB. So, unless you want to control the color format of the images yourself, you can skip this chapter. 6.1. PNG color types -------------------- A PNG image can have many color types, ranging from 1-bit color to 64-bit color, as well as palettized color modes. After the zlib decompression and unfiltering in the PNG image is done, the raw pixel data will have that color type and thus a certain amount of bits per pixel. If you want the output raw image after decoding to have another color type, a conversion is done by LodePNG. The PNG specification gives the following color types: 0: greyscale, bit depths 1, 2, 4, 8, 16 2: RGB, bit depths 8 and 16 3: palette, bit depths 1, 2, 4 and 8 4: greyscale with alpha, bit depths 8 and 16 6: RGBA, bit depths 8 and 16 Bit depth is the amount of bits per pixel per color channel. So the total amount of bits per pixel is: amount of channels * bitdepth. 6.2. color conversions ---------------------- As explained in the sections about the encoder and decoder, you can specify color types and bit depths in info_png and info_raw to change the default behaviour. If, when decoding, you want the raw image to be something else than the default, you need to set the color type and bit depth you want in the LodePNGColorMode, or the parameters of the simple function of LodePNG you're using. If, when encoding, you use another color type than the default in the input image, you need to specify its color type and bit depth in the LodePNGColorMode of the raw image, or use the parameters of the simplefunction of LodePNG you're using. If, when encoding, you don't want LodePNG to choose the output PNG color type but control it yourself, you need to set auto_convert in the encoder settings to LAC_NONE, and specify the color type you want in the LodePNGInfo of the encoder. If you do any of the above, LodePNG may need to do a color conversion, which follows the rules below, and may sometimes not be allowed. To avoid some confusion: -the decoder converts from PNG to raw image -the encoder converts from raw image to PNG -the colortype and bitdepth in LodePNGColorMode info_raw, are those of the raw image -the colortype and bitdepth in the color field of LodePNGInfo info_png, are those of the PNG -when encoding, the color type in LodePNGInfo is ignored if auto_convert is enabled, it is automatically generated instead -when decoding, the color type in LodePNGInfo is set by the decoder to that of the original PNG image, but it can be ignored since the raw image has the color type you requested instead -if the color type of the LodePNGColorMode and PNG image aren't the same, a conversion between the color types is done if the color types are supported. If it is not supported, an error is returned. If the types are the same, no conversion is done. -even though some conversions aren't supported, LodePNG supports loading PNGs from any colortype and saving PNGs to any colortype, sometimes it just requires preparing the raw image correctly before encoding. -both encoder and decoder use the same color converter. Non supported color conversions: -color to greyscale: no error is thrown, but the result will look ugly because only the red channel is taken -anything, to palette when that palette does not have that color in it: in this case an error is thrown Supported color conversions: -anything to 8-bit RGB, 8-bit RGBA, 16-bit RGB, 16-bit RGBA -any grey or grey+alpha, to grey or grey+alpha -anything to a palette, as long as the palette has the requested colors in it -removing alpha channel -higher to smaller bitdepth, and vice versa If you want no color conversion to be done: -In the encoder, you can make it save a PNG with any color type by giving the raw color mode and LodePNGInfo the same color mode, and setting auto_convert to LAC_NO. -In the decoder, you can make it store the pixel data in the same color type as the PNG has, by setting the color_convert setting to false. Settings in info_raw are then ignored. The function lodepng_convert does the color conversion. It is available in the interface but normally isn't needed since the encoder and decoder already call it. 6.3. padding bits ----------------- In the PNG file format, if a less than 8-bit per pixel color type is used and the scanlines have a bit amount that isn't a multiple of 8, then padding bits are used so that each scanline starts at a fresh byte. But that is NOT true for the LodePNG raw input and output. The raw input image you give to the encoder, and the raw output image you get from the decoder will NOT have these padding bits, e.g. in the case of a 1-bit image with a width of 7 pixels, the first pixel of the second scanline will the the 8th bit of the first byte, not the first bit of a new byte. 6.4. A note about 16-bits per channel and endianness ---------------------------------------------------- LodePNG uses unsigned char arrays for 16-bit per channel colors too, just like for any other color format. The 16-bit values are stored in big endian (most significant byte first) in these arrays. This is the opposite order of the little endian used by x86 CPU's. LodePNG always uses big endian because the PNG file format does so internally. Conversions to other formats than PNG uses internally are not supported by LodePNG on purpose, there are myriads of formats, including endianness of 16-bit colors, the order in which you store R, G, B and A, and so on. Supporting and converting to/from all that is outside the scope of LodePNG. This may mean that, depending on your use case, you may want to convert the big endian output of LodePNG to little endian with a for loop. This is certainly not always needed, many applications and libraries support big endian 16-bit colors anyway, but it means you cannot simply cast the unsigned char* buffer to an unsigned short* buffer on x86 CPUs. 7. error values --------------- All functions in LodePNG that return an error code, return 0 if everything went OK, or a non-zero code if there was an error. The meaning of the LodePNG error values can be retrieved with the function lodepng_error_text: given the numerical error code, it returns a description of the error in English as a string. Check the implementation of lodepng_error_text to see the meaning of each code. 8. chunks and PNG editing ------------------------- If you want to add extra chunks to a PNG you encode, or use LodePNG for a PNG editor that should follow the rules about handling of unknown chunks, or if your program is able to read other types of chunks than the ones handled by LodePNG, then that's possible with the chunk functions of LodePNG. A PNG chunk has the following layout: 4 bytes length 4 bytes type name length bytes data 4 bytes CRC 8.1. iterating through chunks ----------------------------- If you have a buffer containing the PNG image data, then the first chunk (the IHDR chunk) starts at byte number 8 of that buffer. The first 8 bytes are the signature of the PNG and are not part of a chunk. But if you start at byte 8 then you have a chunk, and can check the following things of it. NOTE: none of these functions check for memory buffer boundaries. To avoid exploits, always make sure the buffer contains all the data of the chunks. When using lodepng_chunk_next, make sure the returned value is within the allocated memory. unsigned lodepng_chunk_length(const unsigned char* chunk): Get the length of the chunk's data. The total chunk length is this length + 12. void lodepng_chunk_type(char type[5], const unsigned char* chunk): unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type): Get the type of the chunk or compare if it's a certain type unsigned char lodepng_chunk_critical(const unsigned char* chunk): unsigned char lodepng_chunk_private(const unsigned char* chunk): unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk): Check if the chunk is critical in the PNG standard (only IHDR, PLTE, IDAT and IEND are). Check if the chunk is private (public chunks are part of the standard, private ones not). Check if the chunk is safe to copy. If it's not, then, when modifying data in a critical chunk, unsafe to copy chunks of the old image may NOT be saved in the new one if your program doesn't handle that type of unknown chunk. unsigned char* lodepng_chunk_data(unsigned char* chunk): const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk): Get a pointer to the start of the data of the chunk. unsigned lodepng_chunk_check_crc(const unsigned char* chunk): void lodepng_chunk_generate_crc(unsigned char* chunk): Check if the crc is correct or generate a correct one. unsigned char* lodepng_chunk_next(unsigned char* chunk): const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk): Iterate to the next chunk. This works if you have a buffer with consecutive chunks. Note that these functions do no boundary checking of the allocated data whatsoever, so make sure there is enough data available in the buffer to be able to go to the next chunk. unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk): unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data): These functions are used to create new chunks that are appended to the data in *out that has length *outlength. The append function appends an existing chunk to the new data. The create function creates a new chunk with the given parameters and appends it. Type is the 4-letter name of the chunk. 8.2. chunks in info_png ----------------------- The LodePNGInfo struct contains fields with the unknown chunk in it. It has 3 buffers (each with size) to contain 3 types of unknown chunks: the ones that come before the PLTE chunk, the ones that come between the PLTE and the IDAT chunks, and the ones that come after the IDAT chunks. It's necessary to make the distionction between these 3 cases because the PNG standard forces to keep the ordering of unknown chunks compared to the critical chunks, but does not force any other ordering rules. info_png.unknown_chunks_data[0] is the chunks before PLTE info_png.unknown_chunks_data[1] is the chunks after PLTE, before IDAT info_png.unknown_chunks_data[2] is the chunks after IDAT The chunks in these 3 buffers can be iterated through and read by using the same way described in the previous subchapter. When using the decoder to decode a PNG, you can make it store all unknown chunks if you set the option settings.remember_unknown_chunks to 1. By default, this option is off (0). The encoder will always encode unknown chunks that are stored in the info_png. If you need it to add a particular chunk that isn't known by LodePNG, you can use lodepng_chunk_append or lodepng_chunk_create to the chunk data in info_png.unknown_chunks_data[x]. Chunks that are known by LodePNG should not be added in that way. E.g. to make LodePNG add a bKGD chunk, set background_defined to true and add the correct parameters there instead. 9. compiler support ------------------- No libraries other than the current standard C library are needed to compile LodePNG. For the C++ version, only the standard C++ library is needed on top. Add the files lodepng.c(pp) and lodepng.h to your project, include lodepng.h where needed, and your program can read/write PNG files. It is compatible with C90 and up, and C++03 and up. If performance is important, use optimization when compiling! For both the encoder and decoder, this makes a large difference. Make sure that LodePNG is compiled with the same compiler of the same version and with the same settings as the rest of the program, or the interfaces with std::vectors and std::strings in C++ can be incompatible. CHAR_BITS must be 8 or higher, because LodePNG uses unsigned chars for octets. *) gcc and g++ LodePNG is developed in gcc so this compiler is natively supported. It gives no warnings with compiler options "-Wall -Wextra -pedantic -ansi", with gcc and g++ version 4.7.1 on Linux, 32-bit and 64-bit. *) Clang Fully supported and warning-free. *) Mingw The Mingw compiler (a port of gcc for Windows) should be fully supported by LodePNG. *) Visual Studio and Visual C++ Express Edition LodePNG should be warning-free with warning level W4. Two warnings were disabled with pragmas though: warning 4244 about implicit conversions, and warning 4996 where it wants to use a non-standard function fopen_s instead of the standard C fopen. Visual Studio may want "stdafx.h" files to be included in each source file and give an error "unexpected end of file while looking for precompiled header". This is not standard C++ and will not be added to the stock LodePNG. You can disable it for lodepng.cpp only by right clicking it, Properties, C/C++, Precompiled Headers, and set it to Not Using Precompiled Headers there. NOTE: Modern versions of VS should be fully supported, but old versions, e.g. VS6, are not guaranteed to work. *) Compilers on Macintosh LodePNG has been reported to work both with gcc and LLVM for Macintosh, both for C and C++. *) Other Compilers If you encounter problems on any compilers, feel free to let me know and I may try to fix it if the compiler is modern and standards complient. 10. examples ------------ This decoder example shows the most basic usage of LodePNG. More complex examples can be found on the LodePNG website. 10.1. decoder C++ example ------------------------- #include "lodepng.h" #include int main(int argc, char *argv[]) { const char* filename = argc > 1 ? argv[1] : "test.png"; //load and decode std::vector image; unsigned width, height; unsigned error = lodepng::decode(image, width, height, filename); //if there's an error, display it if(error) std::cout << "decoder error " << error << ": " << lodepng_error_text(error) << std::endl; //the pixels are now in the vector "image", 4 bytes per pixel, ordered RGBARGBA..., use it as texture, draw it, ... } 10.2. decoder C example ----------------------- #include "lodepng.h" int main(int argc, char *argv[]) { unsigned error; unsigned char* image; size_t width, height; const char* filename = argc > 1 ? argv[1] : "test.png"; error = lodepng_decode32_file(&image, &width, &height, filename); if(error) printf("decoder error %u: %s\n", error, lodepng_error_text(error)); / * use image here * / free(image); return 0; } 11. changes ----------- The version number of LodePNG is the date of the change given in the format yyyymmdd. Some changes aren't backwards compatible. Those are indicated with a (!) symbol. *) 09 jun 2014: Faster encoder by fixing hash bug and more zeros optimization. *) 22 dec 2013: Power of two windowsize required for optimization. *) 15 apr 2013: Fixed bug with LAC_ALPHA and color key. *) 25 mar 2013: Added an optional feature to ignore some PNG errors (fix_png). *) 11 mar 2013 (!): Bugfix with custom free. Changed from "my" to "lodepng_" prefix for the custom allocators and made it possible with a new #define to use custom ones in your project without needing to change lodepng's code. *) 28 jan 2013: Bugfix with color key. *) 27 okt 2012: Tweaks in text chunk keyword length error handling. *) 8 okt 2012 (!): Added new filter strategy (entropy) and new auto color mode. (no palette). Better deflate tree encoding. New compression tweak settings. Faster color conversions while decoding. Some internal cleanups. *) 23 sep 2012: Reduced warnings in Visual Studio a little bit. *) 1 sep 2012 (!): Removed #define's for giving custom (de)compression functions and made it work with function pointers instead. *) 23 jun 2012: Added more filter strategies. Made it easier to use custom alloc and free functions and toggle #defines from compiler flags. Small fixes. *) 6 may 2012 (!): Made plugging in custom zlib/deflate functions more flexible. *) 22 apr 2012 (!): Made interface more consistent, renaming a lot. Removed redundant C++ codec classes. Reduced amount of structs. Everything changed, but it is cleaner now imho and functionality remains the same. Also fixed several bugs and shrinked the implementation code. Made new samples. *) 6 nov 2011 (!): By default, the encoder now automatically chooses the best PNG color model and bit depth, based on the amount and type of colors of the raw image. For this, autoLeaveOutAlphaChannel replaced by auto_choose_color. *) 9 okt 2011: simpler hash chain implementation for the encoder. *) 8 sep 2011: lz77 encoder lazy matching instead of greedy matching. *) 23 aug 2011: tweaked the zlib compression parameters after benchmarking. A bug with the PNG filtertype heuristic was fixed, so that it chooses much better ones (it's quite significant). A setting to do an experimental, slow, brute force search for PNG filter types is added. *) 17 aug 2011 (!): changed some C zlib related function names. *) 16 aug 2011: made the code less wide (max 120 characters per line). *) 17 apr 2011: code cleanup. Bugfixes. Convert low to 16-bit per sample colors. *) 21 feb 2011: fixed compiling for C90. Fixed compiling with sections disabled. *) 11 dec 2010: encoding is made faster, based on suggestion by Peter Eastman to optimize long sequences of zeros. *) 13 nov 2010: added LodePNG_InfoColor_hasPaletteAlpha and LodePNG_InfoColor_canHaveAlpha functions for convenience. *) 7 nov 2010: added LodePNG_error_text function to get error code description. *) 30 okt 2010: made decoding slightly faster *) 26 okt 2010: (!) changed some C function and struct names (more consistent). Reorganized the documentation and the declaration order in the header. *) 08 aug 2010: only changed some comments and external samples. *) 05 jul 2010: fixed bug thanks to warnings in the new gcc version. *) 14 mar 2010: fixed bug where too much memory was allocated for char buffers. *) 02 sep 2008: fixed bug where it could create empty tree that linux apps could read by ignoring the problem but windows apps couldn't. *) 06 jun 2008: added more error checks for out of memory cases. *) 26 apr 2008: added a few more checks here and there to ensure more safety. *) 06 mar 2008: crash with encoding of strings fixed *) 02 feb 2008: support for international text chunks added (iTXt) *) 23 jan 2008: small cleanups, and #defines to divide code in sections *) 20 jan 2008: support for unknown chunks allowing using LodePNG for an editor. *) 18 jan 2008: support for tIME and pHYs chunks added to encoder and decoder. *) 17 jan 2008: ability to encode and decode compressed zTXt chunks added Also vareous fixes, such as in the deflate and the padding bits code. *) 13 jan 2008: Added ability to encode Adam7-interlaced images. Improved filtering code of encoder. *) 07 jan 2008: (!) changed LodePNG to use ISO C90 instead of C++. A C++ wrapper around this provides an interface almost identical to before. Having LodePNG be pure ISO C90 makes it more portable. The C and C++ code are together in these files but it works both for C and C++ compilers. *) 29 dec 2007: (!) changed most integer types to unsigned int + other tweaks *) 30 aug 2007: bug fixed which makes this Borland C++ compatible *) 09 aug 2007: some VS2005 warnings removed again *) 21 jul 2007: deflate code placed in new namespace separate from zlib code *) 08 jun 2007: fixed bug with 2- and 4-bit color, and small interlaced images *) 04 jun 2007: improved support for Visual Studio 2005: crash with accessing invalid std::vector element [0] fixed, and level 3 and 4 warnings removed *) 02 jun 2007: made the encoder add a tag with version by default *) 27 may 2007: zlib and png code separated (but still in the same file), simple encoder/decoder functions added for more simple usage cases *) 19 may 2007: minor fixes, some code cleaning, new error added (error 69), moved some examples from here to lodepng_examples.cpp *) 12 may 2007: palette decoding bug fixed *) 24 apr 2007: changed the license from BSD to the zlib license *) 11 mar 2007: very simple addition: ability to encode bKGD chunks. *) 04 mar 2007: (!) tEXt chunk related fixes, and support for encoding palettized PNG images. Plus little interface change with palette and texts. *) 03 mar 2007: Made it encode dynamic Huffman shorter with repeat codes. Fixed a bug where the end code of a block had length 0 in the Huffman tree. *) 26 feb 2007: Huffman compression with dynamic trees (BTYPE 2) now implemented and supported by the encoder, resulting in smaller PNGs at the output. *) 27 jan 2007: Made the Adler-32 test faster so that a timewaste is gone. *) 24 jan 2007: gave encoder an error interface. Added color conversion from any greyscale type to 8-bit greyscale with or without alpha. *) 21 jan 2007: (!) Totally changed the interface. It allows more color types to convert to and is more uniform. See the manual for how it works now. *) 07 jan 2007: Some cleanup & fixes, and a few changes over the last days: encode/decode custom tEXt chunks, separate classes for zlib & deflate, and at last made the decoder give errors for incorrect Adler32 or Crc. *) 01 jan 2007: Fixed bug with encoding PNGs with less than 8 bits per channel. *) 29 dec 2006: Added support for encoding images without alpha channel, and cleaned out code as well as making certain parts faster. *) 28 dec 2006: Added "Settings" to the encoder. *) 26 dec 2006: The encoder now does LZ77 encoding and produces much smaller files now. Removed some code duplication in the decoder. Fixed little bug in an example. *) 09 dec 2006: (!) Placed output parameters of public functions as first parameter. Fixed a bug of the decoder with 16-bit per color. *) 15 okt 2006: Changed documentation structure *) 09 okt 2006: Encoder class added. It encodes a valid PNG image from the given image buffer, however for now it's not compressed. *) 08 sep 2006: (!) Changed to interface with a Decoder class *) 30 jul 2006: (!) LodePNG_InfoPng , width and height are now retrieved in different way. Renamed decodePNG to decodePNGGeneric. *) 29 jul 2006: (!) Changed the interface: image info is now returned as a struct of type LodePNG::LodePNG_Info, instead of a vector, which was a bit clumsy. *) 28 jul 2006: Cleaned the code and added new error checks. Corrected terminology "deflate" into "inflate". *) 23 jun 2006: Added SDL example in the documentation in the header, this example allows easy debugging by displaying the PNG and its transparency. *) 22 jun 2006: (!) Changed way to obtain error value. Added loadFile function for convenience. Made decodePNG32 faster. *) 21 jun 2006: (!) Changed type of info vector to unsigned. Changed position of palette in info vector. Fixed an important bug that happened on PNGs with an uncompressed block. *) 16 jun 2006: Internally changed unsigned into unsigned where needed, and performed some optimizations. *) 07 jun 2006: (!) Renamed functions to decodePNG and placed them in LodePNG namespace. Changed the order of the parameters. Rewrote the documentation in the header. Renamed files to lodepng.cpp and lodepng.h *) 22 apr 2006: Optimized and improved some code *) 07 sep 2005: (!) Changed to std::vector interface *) 12 aug 2005: Initial release (C++, decoder only) 12. contact information ----------------------- Feel free to contact me with suggestions, problems, comments, ... concerning LodePNG. If you encounter a PNG image that doesn't work properly with this decoder, feel free to send it and I'll use it to find and fix the problem. My email address is (puzzle the account and domain together with an @ symbol): Domain: gmail dot com. Account: lode dot vandevenne. Copyright (c) 2005-2014 Lode Vandevenne */ ================================================ FILE: framework/shared/include/math_types.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef MATH_TYPES_H_ #define MATH_TYPES_H_ typedef struct sb_int2 { int x,y; } sb_int2; typedef struct sb_uint2 { unsigned int x,y; } sb_uint2; typedef struct sb_uint3 { unsigned int x,y,z; } sb_int3; typedef struct sb_uchar3 { unsigned char x,y,z; } sb_uchar3; typedef struct sb_uchar4 { unsigned char x,y,z,w; } sb_uchar4; typedef struct sb_float3 { float x,y,z; } sb_float3; typedef struct sb_float4 { float x,y,z,w; } sb_float4; inline sb_int2 make_sb_int2( int a, int b) {return {a,b};} inline sb_uint2 make_sb_uint2(unsigned int a,unsigned int b) {return {a,b};} inline sb_uchar3 make_sb_uchar3(unsigned char a,unsigned char b, unsigned char c) {return {a,b,c};} inline sb_uchar4 make_sb_uchar4(unsigned char a,unsigned char b, unsigned char c, unsigned char d) {return {a,b,c,d};} inline sb_uint3 make_sb_uint3(unsigned int a,unsigned int b, unsigned int c) {return {a,b,c};} inline sb_float3 make_sb_float3(float a,float b, float c) {return {a,b,c};} inline sb_float4 make_sb_float4(float a,float b, float c, float d) {return {a,b,c,d};} #endif /* MATH_TYPES_H_ */ ================================================ FILE: framework/shared/include/metrics/ATEMetric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef ATEMETRIC_H #define ATEMETRIC_H #include "metrics/Metric.h" namespace slambench { namespace outputs { class TrajectoryInterface; } } namespace slambench { namespace metrics { class ATEMetric : public Metric { public: ATEMetric(const slambench::outputs::TrajectoryInterface *tested_trajectory, const slambench::outputs::TrajectoryInterface *ground_truth); const slambench::values::ValueDescription& GetValueDescription() const override; const std::string& GetDescription() const override; void MeasureStart(Phase* phase) override; void MeasureEnd(Phase* phase) override; Value *GetValue(Phase* phase) override; private: const outputs::TrajectoryInterface *trajectory_; const outputs::TrajectoryInterface *ground_truth_; values::TrajectoryValue::pose_container_t latest_trajectory_; slambench::TimeStamp next_gt_ts_; }; } } #endif /* ATEMETRIC_H */ ================================================ FILE: framework/shared/include/metrics/DepthEstimationMetric.h ================================================ #ifndef DEPTHESTIMATIONMETRIC_H #define DEPTHESTIMATIONMETRIC_H #include "Metric.h" #include namespace slambench { namespace metrics { using slambench::values::FrameValue; class DepthEstimationMetric : public Metric { public: DepthEstimationMetric(const slambench::outputs::BaseOutput * const tested, const slambench::outputs::BaseOutput * const gt); ~DepthEstimationMetric() = default; const slambench::values::ValueDescription& GetValueDescription() const override; const std::string& GetDescription() const override; void MeasureStart(Phase* phase) override; void MeasureEnd(Phase* phase) override; Value *GetValue(Phase* phase) override; private: const slambench::outputs::BaseOutput * const tested_; const slambench::outputs::BaseOutput * const gt_; }; } } #endif //DEPTHESTIMATIONMETRIC_H ================================================ FILE: framework/shared/include/metrics/DurationMetric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef DURATIONMETRIC_H #define DURATIONMETRIC_H #include "Metric.h" #include #include #include namespace slambench { namespace values { class Value; } namespace metrics { class Phase; class DurationMetric : public Metric { public: DurationMetric(); virtual void MeasureStart(Phase* phase) override; virtual void MeasureEnd(Phase* phase) override; values::Value *GetValue(Phase *phase) override; const slambench::values::ValueDescription& GetValueDescription() const override; const std::string &GetDescription() const override; private: std::unordered_map phase_start_; std::unordered_map phase_end_; uint64_t getTime() const; }; } } #endif /* DURATIONMETRIC_H */ ================================================ FILE: framework/shared/include/metrics/FrameData.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEDATA_H #define FRAMEDATA_H #include namespace slambench { namespace values { class Value; } namespace metrics { class Metric; class Phase; typedef std::map PhaseData; class FrameData { public: FrameData() = default; ~FrameData() {phase_data_.clear();frame_data_.clear();}; PhaseData &GetPhaseData(Phase *p) { return phase_data_[p]; } PhaseData &GetFrameData() { return frame_data_; } void Clear() { phase_data_.clear(); frame_data_.clear(); } private: std::map phase_data_; PhaseData frame_data_; }; } } #endif /* FRAMEDATA_H */ ================================================ FILE: framework/shared/include/metrics/MemoryMetric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef MEMORYMETRIC_H #define MEMORYMETRIC_H #include "Metric.h" #include "memory_utils/CUDAMonitor.h" #include #include #include namespace slambench { namespace metrics { class Phase; class MemoryMetric : public Metric { public: MemoryMetric(); ~MemoryMetric(); virtual void MeasureStart(Phase* phase) override; virtual void MeasureEnd(Phase* phase) override; values::Value *GetValue(Phase* phase) override; const values::ValueDescription &GetValueDescription() const override; const std::string &GetDescription() const override; private: // CUDAMonitor cuda_monitor; slambench::values::ValueDescription desc_; std::unordered_map CPU_Usage_; std::unordered_map GPU_Usage_; }; } } #endif /* CPUMEMORYMETRIC_H */ ================================================ FILE: framework/shared/include/metrics/Metric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef METRIC_H #define METRIC_H #include "MetricValue.h" #include "SLAMBenchLibraryHelper.h" #include "io/SLAMFrame.h" #include "values/Value.h" #include #include #include namespace slambench { namespace metrics { class Phase; using values::Value; // Class representing a metric such as power, time, memory usage, etc. class Metric { public: Metric(const std::string &name); virtual ~Metric(); virtual void MeasureStart(Phase *phase) = 0; virtual void MeasureEnd(Phase *phase) = 0; virtual Value *GetValue(Phase *phase) = 0; virtual const values::ValueDescription &GetValueDescription() const = 0; const std::string &GetName() const { return name_; } virtual const std::string &GetDescription() const = 0; private: const std::string name_; }; } } #endif /* METRIC_H */ ================================================ FILE: framework/shared/include/metrics/MetricManager.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef METRICSMANAGER_H #define METRICSMANAGER_H #include "Phase.h" #include "FrameData.h" #include #include #include #include #include namespace slambench { namespace metrics { class Metric; class Phase; class MetricManager { public: MetricManager(); ~MetricManager(); typedef std::shared_ptr MetricPtr; typedef std::vector metric_list_t; typedef std::vector phase_list_t; void AddPhaseMetric(const MetricPtr& m); void AddFrameMetric(const MetricPtr& m); void AddPhase(Phase *p); void AddPhase(const std::string &phase_name); void BeginPhase(Phase *phase); void EndPhase(Phase *phase); Phase *GetPhase(const std::string &phasename); Phase *GetFramePhase() { return &frame_phase_; } Phase *GetInitPhase() { return &init_phase_; } const PhaseData *GetInitPhaseData() { return &init_data_; } phase_list_t GetPhases() { return phases_; } metric_list_t GetPhaseMetrics() { return phase_metrics_; } metric_list_t GetFrameMetrics() { return frame_metrics_; } FrameData *GetFrame(uint64_t frame_number); FrameData *GetLastFrame(); std::string GetHeader() const; void BeginFrame(); void EndFrame(); void BeginInit(); void EndInit(); void reset() { all_metrics_.clear(); frame_data_.clear(); frame_metrics_.clear(); phase_metrics_.clear(); // phases_.clear(); } std::vector& getDuration() { return frame_phase_duration_; } private: metric_list_t frame_metrics_; metric_list_t phase_metrics_; std::set> all_metrics_; phase_list_t phases_; std::vector frame_data_; PhaseData init_data_; Phase init_phase_; Phase frame_phase_; uint64_t frame_counter_; char duration_metric_typeid_[100]; std::vector frame_phase_duration_; }; } } #endif /* METRICSMANAGER_H */ ================================================ FILE: framework/shared/include/metrics/MetricValue.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef METRICVALUE_H #define METRICVALUE_H #include #include #include #include namespace slambench { namespace metrics { class MetricValue { private: MetricValue(size_t size, void *data) { data_.resize(size); memcpy(data_.data(), data, size); } public: MetricValue(const MetricValue &other) : data_(other.data_) {} template MetricValue(T value) : MetricValue(sizeof(value), &value) {} const void *GetStorage() const { return (void*)data_.data(); } template T As() const { assert(sizeof(T) == data_.size()); return *(T*)GetStorage(); } private: std::vector data_; }; } } #endif /* METRICVALUE_H */ ================================================ FILE: framework/shared/include/metrics/Phase.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef PHASE_H #define PHASE_H #include "MetricValue.h" #include #include namespace slambench { namespace metrics { class Metric; class MetricManager; // Class representing a phase (i.e., a duration) of an algorithm class Phase { public: Phase(MetricManager *mgr, const std::string &phasename); void Begin(); void End(); const std::string &GetName() { return name_; } private: const std::string name_; MetricManager *manager_; }; } } #endif /* PHASE_H */ ================================================ FILE: framework/shared/include/metrics/PointCloudMetric.h ================================================ #ifndef POINTCLOUDMETRIC_H #define POINTCLOUDMETRIC_H #include "metrics/Metric.h" #include "outputs/Output.h" namespace slambench { namespace metrics { using slambench::values::PointCloudValue; class PointCloudMetric : public Metric { private: const slambench::outputs::BaseOutput * const heatmap_pointcloud; slambench::TimeStamp lastMeasurement; public: PointCloudMetric(const slambench::outputs::BaseOutput * const heatmap_pointcloud); ~PointCloudMetric() = default; const slambench::values::ValueDescription& GetValueDescription() const override; const std::string& GetDescription() const override; void MeasureStart(Phase* phase) override; void MeasureEnd(Phase* phase) override; Value *GetValue(Phase* phase) override; }; } } #endif ================================================ FILE: framework/shared/include/metrics/PowerMetric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef POWERMETRIC_H #define POWERMETRIC_H #include "metrics/Metric.h" #include "metrics/power_utils/PowerMonitor.h" namespace slambench { namespace metrics { class PowerMetric : public Metric { public: PowerMetric(); const slambench::values::ValueDescription& GetValueDescription() const override; const std::string& GetDescription() const override; void MeasureStart(Phase* phase) override; void MeasureEnd(Phase* phase) override; slambench::values::Value *GetValue(Phase* phase) override; private : PowerMonitor *pm_ = nullptr; slambench::values::Value *last_res_; }; } } #endif /* POWERMETRIC_H */ ================================================ FILE: framework/shared/include/metrics/RPEMetric.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef RPEMETRIC_H #define RPEMETRIC_H #include "metrics/Metric.h" #include "outputs/TrajectoryAlignmentMethod.h" #include "outputs/TrajectoryInterface.h" namespace slambench { namespace metrics { class RPEMetric : public Metric { public: RPEMetric(const slambench::outputs::TrajectoryInterface *tested_trajectory, const slambench::outputs::TrajectoryInterface *ground_truth); const slambench::values::ValueDescription& GetValueDescription() const override; const std::string& GetDescription() const override; void MeasureStart(Phase* phase) override; void MeasureEnd(Phase* phase) override; Value *GetValue(Phase* phase) override; private: const outputs::TrajectoryInterface *trajectory_; const outputs::TrajectoryInterface *ground_truth_; values::TrajectoryValue::pose_container_t latest_trajectory_; slambench::TimeStamp next_gt_ts_; }; } } #endif /* RPEMETRIC_H */ ================================================ FILE: framework/shared/include/metrics/memory_utils/CUDAMonitor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_METRICS_MEMORY_UTILS_CUDAMONITOR_H_ #define FRAMEWORK_SHARED_INCLUDE_METRICS_MEMORY_UTILS_CUDAMONITOR_H_ #include #include typedef int cudaError_t ; typedef cudaError_t (*cudaMemGetInfo_t)( size_t * , size_t * ); typedef struct CUuuid_st { char bytes[16]; } CUuuid; typedef struct CUuuid_st cudaUUID_t; typedef struct { char name[256]; cudaUUID_t uuid; size_t totalGlobalMem; size_t sharedMemPerBlock; int regsPerBlock; int warpSize; size_t memPitch; int maxThreadsPerBlock; int maxThreadsDim[3]; int maxGridSize[3]; int clockRate; size_t totalConstMem; int major; int minor; size_t textureAlignment; size_t texturePitchAlignment; int deviceOverlap; int multiProcessorCount; int kernelExecTimeoutEnabled; int integrated; int canMapHostMemory; int computeMode; int maxTexture1D; int maxTexture1DMipmap; int maxTexture1DLinear; int maxTexture2D[2]; int maxTexture2DMipmap[2]; int maxTexture2DLinear[3]; int maxTexture2DGather[2]; int maxTexture3D[3]; int maxTexture3DAlt[3]; int maxTextureCubemap; int maxTexture1DLayered[2]; int maxTexture2DLayered[3]; int maxTextureCubemapLayered[2]; int maxSurface1D; int maxSurface2D[2]; int maxSurface3D[3]; int maxSurface1DLayered[2]; int maxSurface2DLayered[3]; int maxSurfaceCubemap; int maxSurfaceCubemapLayered[2]; size_t surfaceAlignment; int concurrentKernels; int ECCEnabled; int pciBusID; int pciDeviceID; int pciDomainID; int tccDriver; int asyncEngineCount; int unifiedAddressing; int memoryClockRate; int memoryBusWidth; int l2CacheSize; int maxThreadsPerMultiProcessor; int streamPrioritiesSupported; int globalL1CacheSupported; int localL1CacheSupported; size_t sharedMemPerMultiprocessor; int regsPerMultiprocessor; int managedMemory; int isMultiGpuBoard; int multiGpuBoardGroupID; int singleToDoublePrecisionPerfRatio; int pageableMemoryAccess; int concurrentManagedAccess; int computePreemptionSupported; int canUseHostPointerForRegisteredMem; int cooperativeLaunch; int cooperativeMultiDeviceLaunch; int pageableMemoryAccessUsesHostPageTables; int directManagedMemAccessFromHost; } cudaDeviceProp; typedef cudaError_t (*cudaGetDeviceProperties_t)( cudaDeviceProp * , int ); class CUDAMonitor { public : CUDAMonitor () : libcuda_cudaMemGetInfo(nullptr), libcuda_cudaGetDeviceProperties(nullptr) { Init(); } private : cudaMemGetInfo_t libcuda_cudaMemGetInfo ; cudaGetDeviceProperties_t libcuda_cudaGetDeviceProperties; bool Init(); public : size_t getUsedBytes() ; bool IsActive() ; std::string device_name = ""; }; #endif /* FRAMEWORK_SHARED_INCLUDE_METRICS_MEMORY_UTILS_CUDAMONITOR_H_ */ ================================================ FILE: framework/shared/include/metrics/power_utils/PAPIMonitor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_PAPI_MONITOR_H_ #define FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_PAPI_MONITOR_H_ #include "values/Value.h" #include "outputs/Output.h" #include "PowerMonitor.h" #include "papi.h" #include class PAPIMonitor : public PowerMonitor { public : static PAPIMonitor * generate () { static PAPIMonitor * loader = nullptr; assert (loader == nullptr); loader = new PAPIMonitor (); if (loader->IsValid()) { return loader; } else { delete loader; return nullptr; } } private : int EventSet; long long before_time,after_time; long long*values; #define MAX_RAPL_EVENTS 64 char event_names[MAX_RAPL_EVENTS][PAPI_MAX_STR_LEN]; char units[MAX_RAPL_EVENTS][PAPI_MIN_STR_LEN]; int num_events=0; struct PapiPower { double packagePower; double pp1Power; double dramPower; double pp0Power; } papiReading; private : slambench::values::TypeForVT::type current; bool init_res = false; bool start_res = false; private : bool papi_init(); bool papi_start(); bool papi_stop(); bool papi_read(); public : PAPIMonitor() : PowerMonitor(), EventSet (PAPI_NULL) { init_res = papi_init(); } ~PAPIMonitor() { if(init_res) { papi_stop(); } } bool IsValid () { return init_res; } void startSample () { start_res = papi_start(); } const slambench::values::ValueDescription &GetType () const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ {"PP0", slambench::values::VT_DOUBLE}, {"PP1", slambench::values::VT_DOUBLE}, {"PAPI_PACKAGE", slambench::values::VT_DOUBLE}, {"PAPI_DRAM", slambench::values::VT_DOUBLE}}); return desc; } slambench::values::Value *endSample () { assert(start_res); bool res = papi_read(); if (!res) { std::cerr << "READ FAILED" << std::endl; return new slambench::values::TypeForVT::type({}); } auto pp1 = new slambench::values::TypeForVT::type(this->papiReading.pp1Power); auto pp0 = new slambench::values::TypeForVT::type(this->papiReading.pp0Power); auto package = new slambench::values::TypeForVT::type(this->papiReading.packagePower); auto dram = new slambench::values::TypeForVT::type(this->papiReading.dramPower); return new slambench::values::TypeForVT::type({{"PP0", pp0}, {"PP1", pp1}, {"PAPI_PACKAGE", package}, {"PAPI_DRAM", dram}});; } }; #endif /* FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_PAPI_MONITOR_H_ */ ================================================ FILE: framework/shared/include/metrics/power_utils/PowerMonitor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_METRICS_POWER_UTILS_POWERMONITOR_H_ #define FRAMEWORK_SHARED_INCLUDE_METRICS_POWER_UTILS_POWERMONITOR_H_ class PowerMonitor { public: virtual ~PowerMonitor() {}; virtual const slambench::values::ValueDescription& GetType () const = 0 ; virtual slambench::values::Value* endSample() = 0; virtual void startSample() = 0; }; #endif /* FRAMEWORK_SHARED_INCLUDE_METRICS_POWER_UTILS_POWERMONITOR_H_ */ ================================================ FILE: framework/shared/include/metrics/power_utils/XU3Monitor.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_XU3_MONITOR_H_ #define FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_XU3_MONITOR_H_ #include "values/Value.h" #include "outputs/Output.h" #include "PowerMonitor.h" #include enum XU3Sensor { SENSOR_A7 = 45, SENSOR_A15 = 40, SENSOR_GPU = 44, SENSOR_DRAM = 41 }; class XU3Monitor : public PowerMonitor { public : static XU3Monitor *generate () { static XU3Monitor *loader = nullptr; assert (loader == nullptr); loader = new XU3Monitor (); if (loader->IsValid()) { return loader; } else { delete loader; return nullptr; } } private : FILE *powerA7 = nullptr; FILE *powerA15 = nullptr; FILE *powerGPU = nullptr; FILE *powerDRAM = nullptr; double vpowerA7 = 0.0; double vpowerA15 = 0.0; double vpowerGPU = 0.0; double vpowerDRAM = 0.0; double startTime; private : bool odroid_init(); bool odroid_start(); bool odroid_sample(); bool odroid_finish(); float getPower(XU3Sensor sensor) ; bool enableSensor(XU3Sensor sensor) ; public : XU3Monitor() : PowerMonitor() { odroid_init(); } ~XU3Monitor() { if(IsValid ()) { odroid_finish(); } } bool IsValid () { return powerA7 or powerA15 or powerGPU or powerDRAM; } void startSample () { if(IsValid ()) { odroid_start(); } } const slambench::values::ValueDescription &GetType () const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ {"A7_Power", slambench::values::VT_DOUBLE}, {"A15_Power", slambench::values::VT_DOUBLE}, {"GPU_Power", slambench::values::VT_DOUBLE}, {"DRAM_Power", slambench::values::VT_DOUBLE}} ); return desc; } slambench::values::Value *endSample() { this->vpowerA7 = 0.0; this->vpowerA15 = 0.0; this->vpowerGPU = 0.0; this->vpowerDRAM = 0.0; odroid_sample(); auto v1 = new slambench::values::TypeForVT::type(this->vpowerA7); auto v2 = new slambench::values::TypeForVT::type(this->vpowerA15); auto v3 = new slambench::values::TypeForVT::type(this->vpowerGPU); auto v4 = new slambench::values::TypeForVT::type(this->vpowerDRAM); return new slambench::values::TypeForVT::type({ {"A7_Power", v1}, {"A15_Power", v2}, {"GPU_Power", v3}, {"DRAM_Power", v4}});; } }; #endif /* FRAMEWORK_INCLUDE_METRICS_POWER_UTILS_PAPI_MONITOR_H_ */ ================================================ FILE: framework/shared/include/outputs/Output.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef OUTPUT_H #define OUTPUT_H #include "TimeStamp.h" #include "values/Value.h" #include "TrajectoryAlignmentMethod.h" #include #include #include #include namespace slambench { namespace outputs { class TrajectoryInterface; /** * Base output interface */ class BaseOutput { public: typedef std::function callback_t; typedef slambench::TimeStamp timestamp_t; typedef std::map value_map_t; BaseOutput(const std::string &name, const values::ValueDescription &type, bool is_main_output = false); virtual ~BaseOutput() = default; const std::string &GetName() const { return name_; } values::ValueType GetType() const { return type_.GetType(); } const values::ValueDescription &GetValueDescription() const { return type_; } void SetKeepOnlyMostRecent(bool only_most_recent) { only_keep_most_recent_ = only_most_recent; } bool GetKeepOnlyMostRecent() const { return only_keep_most_recent_; } bool IsActive() const { return active_; } void SetActive(bool active) { active_ = active; } virtual const value_map_t &GetValues() const = 0; virtual const value_map_t::value_type &GetMostRecentValue() const; virtual bool Empty() const; bool IsMainOutput() const { return main_; } void AddUpdateCallback(callback_t callback) { update_callbacks_.push_back(callback); } void RemoveUpdateCallback(callback_t callback); virtual void reset() {} protected: void Updated() const; private: const std::string name_; values::ValueDescription type_; bool only_keep_most_recent_; bool active_; bool main_; std::vector update_callbacks_; }; /** * Output which has values added to it and stores them in a map */ class Output : public BaseOutput { public: Output(const std::string &name, values::ValueType type, bool main_output = false); ~Output() override = default; void AddPoint(timestamp_t time, const values::Value *value); const value_map_t &GetValues() const override; const value_map_t::value_type &GetMostRecentValue() const override; void reset() override { values_.clear(); } private: value_map_t values_; }; class DerivedOutput : public BaseOutput { public: DerivedOutput(const std::string &name, values::ValueType type, const std::initializer_list &derived_from, bool main = false); ~DerivedOutput() override = default; bool Empty() const override; const value_map_t::value_type& GetMostRecentValue() const override; const BaseOutput::value_map_t& GetValues() const override; void Invalidate(); protected: virtual void Recalculate() = 0; value_map_t &GetCachedValueMap(); private: void recalculate() const; value_map_t cached_values_; std::vector derived_from_; bool up_to_date_; }; class AlignmentOutput : public DerivedOutput { public: AlignmentOutput(const std::string &name, TrajectoryInterface *gt_trajectory, BaseOutput *trajectory, TrajectoryAlignmentMethod *method); ~AlignmentOutput() override = default; void Recalculate() override; Eigen::Matrix4f& getTransformation() { return transformation_; } /* When freezed, the alignment will stop updating in recalculate() */ void SetFreeze(bool freeze) { freeze_ = freeze; } private: bool freeze_; TrajectoryInterface *gt_trajectory_; BaseOutput *trajectory_; TrajectoryAlignmentMethod *method_; Eigen::Matrix4f transformation_; }; class AlignedPoseOutput : public DerivedOutput { public: AlignedPoseOutput(const std::string &name, AlignmentOutput *alignment, BaseOutput *pose_output); ~AlignedPoseOutput() override = default; void Recalculate() override; private: AlignmentOutput *alignment_; BaseOutput *pose_output_; }; /** * An output which returns a transformed point cloud */ class AlignedPointCloudOutput : public DerivedOutput { public: AlignedPointCloudOutput(const std::string &name, AlignmentOutput *, BaseOutput *pc_output); ~AlignedPointCloudOutput() override = default; void Recalculate() override; private: AlignmentOutput *alignment_; BaseOutput *pointcloud_; }; /** * An output which returns an aligned trajectory */ class AlignedTrajectoryOutput : public DerivedOutput { public: AlignedTrajectoryOutput(const std::string &name, AlignmentOutput *, BaseOutput *trajectory_output); ~AlignedTrajectoryOutput() override; void Recalculate() override; private: AlignmentOutput *alignment_; BaseOutput *trajectory_; }; /** * An output which shows the quality of the reconstruction */ class PointCloudHeatMap : public DerivedOutput { public: PointCloudHeatMap(const std::string &name, BaseOutput *gt_pointcloud, BaseOutput *pointcloud, const std::function &convert); ~PointCloudHeatMap() override = default; void Recalculate() override; std::function convert; private: BaseOutput *gt_pointcloud_; BaseOutput *pointcloud_; }; class PoseToXYZOutput : public BaseOutput { public: PoseToXYZOutput(BaseOutput *pose_output); ~PoseToXYZOutput() override = default; const BaseOutput::value_map_t& GetValues() const override; const value_map_t::value_type& GetMostRecentValue() const override; private: BaseOutput *pose_output_; mutable value_map_t cached_values_; }; } } #endif /* OUTPUT_H */ ================================================ FILE: framework/shared/include/outputs/OutputManager.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef OUTPUTMANAGER_H #define OUTPUTMANAGER_H #include "utils.h" #include "Output.h" #include "io/SLAMFile.h" #include "io/SLAMFrame.h" #include "io/sensor/SensorCollection.h" #include #include #include namespace slambench { namespace outputs { class Output; class OutputManager { public: typedef std::map output_map_t; typedef output_map_t::iterator output_map_iterator_t; ~OutputManager(); void LoadGTOutputsFromSLAMFile(io::SLAMFile *file); void LoadGTOutputsFromSLAMFile(io::SensorCollection &sensors, io::FrameCollection *gt_frames, bool with_point_cloud); void RegisterOutput(BaseOutput *output); BaseOutput *GetOutput(const std::string &outputname); BaseOutput *GetMainOutput(slambench::values::ValueType); output_map_iterator_t begin() { return output_map_.begin(); } output_map_iterator_t end() { return output_map_.end(); } bool WriteFile(const std::string &filename); size_t OutputCount() const { return output_map_.size(); } FastLock &GetLock() { return lock_; } private: std::map output_map_; FastLock lock_; }; } } #endif /* OUTPUTMANAGER_H */ ================================================ FILE: framework/shared/include/outputs/OutputManagerWriter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef OUTPUTMANAGERWRITER_H #define OUTPUTMANAGERWRITER_H #include "io/SLAMFile.h" #include "TimeStamp.h" #include #include namespace slambench { namespace values { class Value; class PoseValue; class PointCloudValue; } namespace outputs { class BaseOutput; class OutputManager; class OutputManagerWriter { public: slambench::io::SLAMFile *GetFile(OutputManager &outman); bool Write(OutputManager &outman, const std::string &filename); private: bool CreateSensors(OutputManager &outman, slambench::io::SLAMFile &file); bool CreateFrames(OutputManager &outman, slambench::io::SLAMFile &file); slambench::io::SLAMFrame *CreateFrame(BaseOutput *output, TimeStamp ts,const values::Value* value); slambench::io::SLAMFrame *CreatePoseFrame(BaseOutput *output, TimeStamp ts,const values::PoseValue* value); slambench::io::SLAMFrame *CreatePointCloudFrame(BaseOutput *output, TimeStamp ts,const values::PointCloudValue* value); slambench::io::Sensor *CreateSensor(const BaseOutput *output); slambench::io::Sensor *CreatePoseSensor(const BaseOutput *output); slambench::io::Sensor *CreatePointCloudSensor(const BaseOutput *output); bool SerialiseFile(slambench::io::SLAMFile &file, const std::string &filename); std::map output_map_; }; } } #endif /* OUTPUTMANAGERWRITER_H */ ================================================ FILE: framework/shared/include/outputs/PoseOutput.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef POSEOUTPUT_H #define POSEOUTPUT_H namespace slambench { namespace outputs { class PoseOutput { public: private: }; } } #endif /* POSEOUTPUT_H */ ================================================ FILE: framework/shared/include/outputs/TrajectoryAlignmentMethod.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef TRAJECTORYALIGNMENTMETHOD_H #define TRAJECTORYALIGNMENTMETHOD_H #include "values/Value.h" #include #include namespace slambench { namespace outputs { class Output; class TrajectoryAlignmentMethod { public: typedef slambench::values::TrajectoryValue::pose_container_t trajectory_t; virtual Eigen::Matrix4f operator()(const trajectory_t &ground_truth, const trajectory_t &trajectory) = 0; virtual ~TrajectoryAlignmentMethod() {}; }; class OriginalTrajectoryAlignmentMethod : public TrajectoryAlignmentMethod { public: virtual Eigen::Matrix4f operator()(const trajectory_t &ground_truth, const trajectory_t &trajectory) override; }; class UmeyamaTrajectoryAlignmentMethod : public TrajectoryAlignmentMethod { public: Eigen::Matrix4f operator()(const trajectory_t &ground_truth, const trajectory_t &trajectory) override; }; class NewTrajectoryAlignmentMethod : public TrajectoryAlignmentMethod { public: virtual Eigen::Matrix4f operator()(const trajectory_t &ground_truth, const trajectory_t &trajectory) override; }; } } #endif /* TRAJECTORYALIGNMENTMETHOD_H */ ================================================ FILE: framework/shared/include/outputs/TrajectoryInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef TRAJECTORYINTERFACE_H #define TRAJECTORYINTERFACE_H #include "outputs/Output.h" #include "values/Value.h" namespace slambench { namespace outputs { /** * We want to treat multiple things as trajectories so we need a way * of interfacing with these things in a consistent way. */ class TrajectoryInterface { public: virtual values::PoseValue Get(const TimeStamp &when) const = 0; virtual values::TrajectoryValue::pose_container_t GetAll() const = 0; }; class PoseOutputTrajectoryInterface : public TrajectoryInterface { public: PoseOutputTrajectoryInterface(BaseOutput *pose_output); ~PoseOutputTrajectoryInterface() = default; values::PoseValue Get(const TimeStamp& when) const override; values::TrajectoryValue::pose_container_t GetAll() const override; private: void recalculate() const; BaseOutput *pose_output_; mutable TimeStamp newest_point_; mutable values::TrajectoryValue::pose_container_t cached_traj_; }; /** * Wrapper for TrajectoryValue to implement the TrajectoryInterface **/ class TrajectoryValueWrapper : public TrajectoryInterface { private: const values::TrajectoryValue *trajectoryValue_; public: TrajectoryValueWrapper(const values::TrajectoryValue *t); values::PoseValue Get(const TimeStamp &when) const override; values::TrajectoryValue::pose_container_t GetAll() const override; }; class TrajectoryOutputInterface : public TrajectoryInterface { private: const BaseOutput *trajectory_output_; public: TrajectoryOutputInterface(const BaseOutput *t); values::PoseValue Get(const TimeStamp &when) const override; values::TrajectoryValue::pose_container_t GetAll() const override; }; } } #endif /* TRAJECTORYINTERFACE_H */ ================================================ FILE: framework/shared/include/sb_malloc.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef SB_MALLOC_H_ #define SB_MALLOC_H_ #include #include #include #include #define MEM_ERROR(...) printf( __VA_ARGS__ ); #define MEM_DEBUG(...) printf( __VA_ARGS__ ); #define NO_MEM_DEBUG #ifdef NO_MEM_DEBUG #undef MEM_DEBUG #define MEM_DEBUG(...) #endif #ifdef ANDROID extern "C" { void *malloc(size_t size) ; void free(void* ptr) ; } #else extern "C" { void *malloc(size_t size) throw(); void free(void* ptr) throw(); } #endif namespace slambench { namespace memory { class MemoryProfiler; class MemoryData { friend class MemoryProfiler; public: MemoryData() : TotalBytesAllocated(0), MaxBytesAllocated(0), BytesAllocatedAtEndOfFrame(0) {} ssize_t TotalBytesAllocated; ssize_t MaxBytesAllocated; ssize_t BytesAllocatedAtEndOfFrame; void ResetBytesAllocated () { MaxBytesAllocated = BytesAllocatedAtEndOfFrame; } private: void RecordAllocation(ssize_t bytes) { TotalBytesAllocated += bytes; BytesAllocatedAtEndOfFrame += bytes; if(BytesAllocatedAtEndOfFrame > MaxBytesAllocated) { MaxBytesAllocated = BytesAllocatedAtEndOfFrame; } MEM_DEBUG("%ld RecordAllocation:%ld\n" , BytesAllocatedAtEndOfFrame , bytes) ; } void RecordFree(ssize_t bytes) { BytesAllocatedAtEndOfFrame -= bytes; MEM_DEBUG("%ld RecordFree:%ld\n" , BytesAllocatedAtEndOfFrame , bytes) ; } }; class MemoryProfile { friend class MemoryProfiler; public: static MemoryProfile singleton; void StartFrame(int i); void EndFrame(); void StartAlgorithm(); void EndAlgorithm(); void ResetBytesAllocated () { overall_data_.ResetBytesAllocated(); } void ResetGPUBytesAllocated () { overall_gpu_data_.ResetBytesAllocated(); } const MemoryData &GetDataForFrame(uint32_t frame_idx) const { return data_.at(frame_idx); } const MemoryData &GetDataForCurrentFrame() const { return GetDataForFrame(GetCurrentFrame()); } const MemoryData &GetOverallData() const { return overall_data_; } const MemoryData &GetGPUDataForFrame(uint32_t frame_idx) const { return gpu_data_.at(frame_idx); } const MemoryData &GetGPUDataForCurrentFrame() const { return GetGPUDataForFrame(GetCurrentFrame()); } const MemoryData &GetOverallGPUData() const { return overall_gpu_data_; } bool HasDataForFrame(uint32_t frame_idx) const { return data_.count(frame_idx); } uint32_t GetCurrentFrame() const { return _frame; }; private: std::map data_; std::map gpu_data_; MemoryData overall_data_; MemoryData overall_gpu_data_; uint32_t _frame; MemoryData &DataForFrame(uint32_t frame_idx) { return data_[frame_idx]; } MemoryData &GPUDataForFrame(uint32_t frame_idx) { return gpu_data_[frame_idx]; } MemoryData &GPUDataForCurrentFrame() { return GPUDataForFrame(GetCurrentFrame()); } MemoryData &DataForCurrentFrame() { return DataForFrame(GetCurrentFrame()); } MemoryData &OverallData() { return overall_data_; } MemoryData &OverallGPUData() { return overall_gpu_data_; } }; } } #endif ================================================ FILE: framework/shared/include/sysutils.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef SYSUTILS_H_ #define SYSUTILS_H_ #include "sys/types.h" #include "sys/sysinfo.h" inline int parseLine(char* line){ int i = strlen(line); while (*line < '0' || *line > '9') line++; line[i-3] = '\0'; i = atoi(line); return i; } inline int getValueVmSize(){ //Note: this value is in KB! FILE* file = fopen("/proc/self/status", "r"); int result = -1; char line[128]; while (fgets(line, 128, file) != NULL){ if (strncmp(line, "VmSize:", 7) == 0){ result = parseLine(line); break; } } fclose(file); return result; } inline int getValueVmRSS(){ //Note: this value is in KB! FILE* file = fopen("/proc/self/status", "r"); int result = -1; char line[128]; while (fgets(line, 128, file) != NULL){ if (strncmp(line, "VmRSS:", 6) == 0){ result = parseLine(line); break; } } fclose(file); return result; } #endif /* SYSUTILS_H_ */ ================================================ FILE: framework/shared/include/timings.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef TIMINGS_H #define TIMINGS_H #ifdef __APPLE__ #include /* clock_t, clock, CLOCKS_PER_SEC */ #else #include #include #endif inline float tick() { std::chrono::time_point tickdata; tickdata = std::chrono::high_resolution_clock::now(); static struct timeval t; struct timeval diff = t; gettimeofday(&t, NULL); return ((t.tv_sec - diff.tv_sec) * 1000000u + t.tv_usec - diff.tv_usec) / 1.e6; } inline double tock() { #ifdef __APPLE__ clock_serv_t cclock; mach_timespec_t clockData; host_get_clock_service(mach_host_self(), SYSTEM_CLOCK, &cclock); clock_get_time(cclock, &clockData); mach_port_deallocate(mach_task_self(), cclock); return (double) clockData.tv_sec + clockData.tv_nsec / 1000000000.0; #else static auto base = std::chrono::high_resolution_clock::now(); auto end_of_computation = std::chrono::high_resolution_clock::now(); std::chrono::duration total_time = end_of_computation - base; return total_time.count(); #endif } //// this is duplicated to fix otherwise missing references in some of the algorithms //inline double TICK() //{ // return tock(); //} //inline double TOCK(std::string str="", int size=0) //{ // return tock(); //} #endif //TIMINGS_H ================================================ FILE: framework/shared/include/utils.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_SHARED_INCLUDE_UTILS_H_ #define FRAMEWORK_SHARED_INCLUDE_UTILS_H_ #include #include #include inline std::string getFileExt(const std::string& s) { std::string str = ""; size_t i = s.rfind('.', s.length()); if (i != std::string::npos) { str = (s.substr(i+1, s.length() - i)); std::transform(str.begin(), str.end(),str.begin(), ::toupper); } return str; } class FastLock { public: FastLock() { flag_.clear(); } void lock() { while(flag_.test_and_set()) ; } void unlock() { flag_.clear(); } private: std::atomic_flag flag_; }; #endif /* FRAMEWORK_SHARED_INCLUDE_UTILS_H_ */ ================================================ FILE: framework/shared/include/values/Value.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef OUTPUT_VALUE_H #define OUTPUT_VALUE_H #include "TimeStamp.h" #include "io/PixelFormat.h" #include #include #include #include namespace slambench { namespace values { class ConstValueDispatch; class ValueDispatch; enum ValueType { VT_UNKNOWN, // Represents an initialised or invalid VT VT_COLLECTION, // Can represent a structured collection of values of other types VT_LIST, // Can represent a flat list of values of other types VT_U64, // Can represent an arbitrary 64-bit value VT_DOUBLE, // Can represent an arbitrary double-precision float VT_STRING, // Can represent a text string VT_TRAJECTORY, // Represents a sequence of poses VT_POSE, // A matrix which specifically represents a pose (position + orientation) VT_POINTCLOUD, // A list of point positions VT_COLOUREDPOINTCLOUD, // A list of point positions with colours VT_HEATMAPPOINTCLOUD, // A pointcloud for visualising values VT_FEATURE, // A tracked feature VT_FEATURELIST, VT_FRAME, VT_MATRIX //Can represent an arbitrary matrix }; static inline const std::string TypeAsString (const ValueType& v) { switch (v) { case VT_COLLECTION : return "VT_COLLECTION "; case VT_LIST : return "VT_LIST "; case VT_U64 : return "VT_U64 "; case VT_DOUBLE : return "VT_DOUBLE "; case VT_STRING : return "VT_STRING "; case VT_TRAJECTORY : return "VT_TRAJECTORY "; case VT_POSE : return "VT_POSE "; case VT_POINTCLOUD : return "VT_POINTCLOUD "; case VT_COLOUREDPOINTCLOUD : return "VT_COLOUREDPOINTCLOUD "; case VT_HEATMAPPOINTCLOUD : return "VT_HEATMAPPOINTCLOUD "; case VT_FEATURE : return "VT_FEATURE "; case VT_FEATURELIST : return "VT_FEATURELIST "; case VT_FRAME : return "VT_FRAME "; case VT_MATRIX : return "VT_MATRIX "; case VT_UNKNOWN : default : return "VT_UNKNOWN "; } } class ValueDescription { public: typedef std::vector> structured_description; ValueDescription(ValueType type); ValueDescription(const structured_description &structured_desc); ValueType GetType() const; const structured_description &GetStructureDescription() const; private: ValueType type_; structured_description structured_type_; }; class Value { public: Value(ValueType type) : value_type_(type) {} ValueType GetType() const { return value_type_; } virtual ~Value(); void Dispatch(ValueDispatch *vd); void Dispatch(ConstValueDispatch *vd) const; private: ValueType value_type_; }; // Fail if no specializations are provided template struct TypeForVT; template struct VTForType; template class TypedValue : public Value { public: TypedValue() : Value(VTForType::value()) {} TypedValue(const T& val) : Value(VTForType::value()), value_(val) {} const T &GetValue() const { return value_; } private: T value_; }; class ValueCollectionValue : public Value { public: typedef std::vector> value_map_t; ValueCollectionValue() : Value(VT_COLLECTION) {} ValueCollectionValue(const std::initializer_list &values) : Value(VT_COLLECTION), values_(values) {} ~ValueCollectionValue(); const value_map_t &GetValue() const { return values_; } private: value_map_t values_; }; class ValueListValue : public Value { public: typedef std::vector value_list; ValueListValue() : Value(VT_LIST) {} ValueListValue(const std::initializer_list &values) : Value(VT_LIST), values_(values) {} ValueListValue(const std::vector &values) : Value(VT_LIST), values_(values) {} ~ValueListValue(); const value_list &GetValue() const { return values_; } private: value_list values_; }; class PoseValue : public Value { public: PoseValue(const Eigen::Matrix4f &pose) : Value(VT_POSE), pose_(pose) {} Eigen::Vector3f GetTranslation() const { return pose_.block<3,1>(0,3); } Eigen::Matrix3f GetRotation() const { return pose_.block<3,3>(0,0);} const Eigen::Matrix4f &GetValue() const { return pose_; } private: Eigen::Matrix4f pose_; }; class Trajectory { public: typedef std::pair value_t; private: typedef std::vector storage_t; public: typedef storage_t::const_iterator const_iterator_t; typedef storage_t::const_reverse_iterator const_reverse_iterator_t; const value_t &at(unsigned int i) const { return values_.at(i); } const PoseValue &at(const TimeStamp &ts) const { //todo: search more intelligently for(auto &i : values_) { if(i.first == ts) { return i.second; } } throw std::out_of_range("Could not find timestamp in trajectory"); } void push_back(const TimeStamp &ts, const PoseValue &pose) { if(!empty() && ts < values_.rbegin()->first) { throw std::invalid_argument("Trajectory is append-only (inserted timestamp is before most recent recorded point)"); } values_.push_back(value_t(ts, pose)); } void insert(const value_t &value) { push_back(value.first, value.second); } size_t size() const { return values_.size(); } bool empty() const { return values_.size() == 0; } void clear() { values_.clear(); } const_iterator_t begin() const { return values_.begin(); } const_reverse_iterator_t rbegin() const { return values_.rbegin(); } const_iterator_t end() const { return values_.end(); } const_reverse_iterator_t rend() const { return values_.rend(); } private: std::vector> values_; }; class TrajectoryValue : public Value { public: typedef Trajectory pose_container_t; TrajectoryValue() : Value(VT_TRAJECTORY) {} TrajectoryValue(const pose_container_t &trajectory) : Value(VT_TRAJECTORY), poses_(trajectory) {} const pose_container_t &GetPoints() const { return poses_; } private: pose_container_t poses_; }; class Point3DF { public: Point3DF() : X(0), Y(0), Z(0) {} Point3DF(float x, float y, float z) : X(x), Y(y), Z(z) {} float X, Y, Z; }; class ColoredPoint3DF { public: ColoredPoint3DF() : X(0), Y(0), Z(0) , R(0), G(0), B(0) {} ColoredPoint3DF(float x, float y, float z) : X(x), Y(y), Z(z), R(0), G(0), B(0) {} ColoredPoint3DF(float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) : X(x), Y(y), Z(z), R(r), G(g), B(b) {} float X, Y, Z; uint8_t R, G, B; }; class HeatMapPoint3DF { public: HeatMapPoint3DF() : X(0), Y(0), Z(0) , value(0) {} HeatMapPoint3DF(float x, float y, float z, double value) : X(x), Y(y), Z(z), value(value) {} float X, Y, Z; double value; }; class PointCloudValue : public Value { public: typedef std::vector point_container_t; PointCloudValue() : Value(VT_POINTCLOUD), points_(std::make_shared()), transform_(Eigen::Matrix4f::Identity()) { } PointCloudValue(const PointCloudValue &other) : Value(VT_POINTCLOUD), points_(other.points_), transform_(other.transform_) { } virtual ~PointCloudValue() { } void AddPoint(const Point3DF &point) { makeUnique(); points_->push_back(point); } void Clear() { makeUnique(); points_->clear(); } const point_container_t &GetPoints() const { assert(points_); return *points_; } const Eigen::Matrix4f &GetTransform() const { return transform_; } void SetTransform(const Eigen::Matrix4f &new_txfm) { transform_ = new_txfm; } private: void makeUnique() { if(!points_.unique()) { points_ = std::make_shared(*points_); } } std::shared_ptr points_; Eigen::Matrix4f transform_; }; class HeatMapPointCloudValue : public Value { public: typedef std::vector point_container_t; HeatMapPointCloudValue() : Value(VT_HEATMAPPOINTCLOUD), points_(std::make_shared()), transform_(Eigen::Matrix4f::Identity()) { } HeatMapPointCloudValue(const HeatMapPointCloudValue &other) : Value(VT_HEATMAPPOINTCLOUD), points_(other.points_), transform_(other.transform_) { } virtual ~HeatMapPointCloudValue() { } void AddPoint(const HeatMapPoint3DF &point) { makeUnique(); points_->push_back(point); } void Clear() { makeUnique(); points_->clear(); } const point_container_t &GetPoints() const { assert(points_); return *points_; } const Eigen::Matrix4f &GetTransform() const { return transform_; } void SetTransform(const Eigen::Matrix4f &new_txfm) { transform_ = new_txfm; } private: void makeUnique() { if(!points_.unique()) { points_ = std::make_shared(*points_); } } std::shared_ptr points_; Eigen::Matrix4f transform_; }; class ColoredPointCloudValue : public Value { public: typedef std::vector point_container_t; ColoredPointCloudValue() : Value(VT_COLOUREDPOINTCLOUD), points_(std::make_shared()), transform_(Eigen::Matrix4f::Identity()) { } ColoredPointCloudValue(const ColoredPointCloudValue &other) : Value(VT_COLOUREDPOINTCLOUD), points_(other.points_), transform_(other.transform_) { } ColoredPointCloudValue(const HeatMapPointCloudValue &other, std::function convert) : Value(VT_HEATMAPPOINTCLOUD), points_(std::make_shared()), transform_(Eigen::Matrix4f::Identity()) { const auto otherValues = other.GetPoints(); points_->reserve(otherValues.size()); double max = 0, min = std::numeric_limits::max(); for (const auto &otherValue : otherValues) { min = std::min(otherValue.value, min); max = std::max(otherValue.value, max); } for (const auto &otherValue : otherValues) points_->push_back(convert(otherValue, min, max)); } virtual ~ColoredPointCloudValue() { } void AddPoint(const ColoredPoint3DF &point) { makeUnique(); points_->push_back(point); } void Clear() { makeUnique(); points_->clear(); } const point_container_t &GetPoints() const { assert(points_); return *points_; } const Eigen::Matrix4f &GetTransform() const { return transform_; } void SetTransform(const Eigen::Matrix4f &new_txfm) { transform_ = new_txfm; } private: void makeUnique() { if(!points_.unique()) { points_ = std::make_shared(*points_); } } std::shared_ptr points_; Eigen::Matrix4f transform_; }; class FrameValue : public Value { public: FrameValue(const FrameValue&); FrameValue(uint32_t width, uint32_t height, slambench::io::pixelformat::EPixelFormat pxl_format, void *data); FrameValue(uint32_t width, uint32_t height, slambench::io::pixelformat::EPixelFormat pxl_format); void *GetData() { return data_.data(); } const void *GetData() const { return data_.data(); } unsigned char at(int row, int col) const { return data_.at(row*height_+col); } //NOTE: assumes row-major uint32_t GetWidth() const { return width_; } uint32_t GetHeight() const { return height_; } slambench::io::pixelformat::EPixelFormat GetFormat() const { return pxl_format_; } private: uint32_t width_, height_; slambench::io::pixelformat::EPixelFormat pxl_format_; std::vector data_; }; class FeatureValue : public Value { public: FeatureValue(const Eigen::Matrix4f &pose, const FrameValue &patch); virtual ~FeatureValue(); FrameValue &GetPatch() { return image_patch_; } Eigen::Matrix4f &GetPose() { return pose_; } private: FrameValue image_patch_; Eigen::Matrix4f pose_; }; /* Specialisations of VT traits live down here */ template<> struct TypeForVT { typedef ValueCollectionValue type; }; template<> struct TypeForVT { typedef TypedValue type; }; template<> struct TypeForVT { typedef TypedValue type; }; template<> struct TypeForVT { typedef TypedValue type; }; template<> struct TypeForVT { typedef TrajectoryValue type; }; template<> struct TypeForVT { typedef PoseValue type; }; template<> struct TypeForVT { typedef PointCloudValue type; }; template<> struct TypeForVT { typedef TypedValue type; }; template<> struct VTForType { static constexpr ValueType value() { return VT_U64; } }; template<> struct VTForType { static constexpr ValueType value() { return VT_DOUBLE; } }; template<> struct VTForType { static constexpr ValueType value() { return VT_STRING; } }; template<> struct VTForType { static constexpr ValueType value() { return VT_MATRIX; } }; } } #endif /* OUTPUT_VALUE_H */ ================================================ FILE: framework/shared/include/values/ValueDispatch.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef VALUEDISPATCH_H #define VALUEDISPATCH_H #include "Value.h" namespace slambench { namespace values { class Value; class ValueDispatch { public: virtual ~ValueDispatch(); #define DISPATCH(vt) virtual void Dispatch(TypeForVT::type *value) = 0; DISPATCH(VT_COLLECTION); DISPATCH(VT_U64); DISPATCH(VT_DOUBLE); DISPATCH(VT_STRING); DISPATCH(VT_TRAJECTORY); DISPATCH(VT_POSE); DISPATCH(VT_POINTCLOUD); DISPATCH(VT_MATRIX); #undef DISPATCH }; class ConstValueDispatch { public: virtual ~ConstValueDispatch(); #define DISPATCH(vt) virtual void Dispatch(const TypeForVT::type *value) = 0; DISPATCH(VT_COLLECTION); DISPATCH(VT_U64); DISPATCH(VT_DOUBLE); DISPATCH(VT_STRING); DISPATCH(VT_TRAJECTORY); DISPATCH(VT_POSE); DISPATCH(VT_POINTCLOUD); DISPATCH(VT_MATRIX); #undef DISPATCH }; } } #endif /* VALUEDISPATCH_H */ ================================================ FILE: framework/shared/include/values/ValueInterface.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef VALUEINTERFACE_H #define VALUEINTERFACE_H #include "metrics/MetricManager.h" #include "metrics/Metric.h" #include "metrics/Phase.h" namespace slambench { namespace values { class ValueInterface { public: virtual ~ValueInterface(); virtual const values::Value *Get() = 0; virtual const values::ValueDescription &GetDescription() const = 0; }; class MetricValueInterface : public ValueInterface { public: MetricValueInterface(metrics::MetricManager &manager, metrics::Metric &metric, metrics::Phase &phase) : manager_(manager), metric_(metric), phase_(phase) {} virtual ~MetricValueInterface() {} const values::Value *Get() override { return manager_.GetLastFrame()->GetPhaseData(&phase_).at(&metric_); } const values::ValueDescription &GetDescription() const override { return metric_.GetValueDescription(); } private: metrics::MetricManager &manager_; metrics::Metric &metric_; metrics::Phase &phase_; }; class OutputValueInterface : public ValueInterface { public: OutputValueInterface(outputs::BaseOutput &output) : output_(output) {} virtual ~OutputValueInterface() {} const values::Value* Get() override { return output_.GetMostRecentValue().second; } const values::ValueDescription &GetDescription() const override { return output_.GetValueDescription(); } private: outputs::BaseOutput &output_; }; } } #endif /* VALUEINTERFACE_H */ ================================================ FILE: framework/shared/include/values/ValuePrinter.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef VALUEPRINTER_H #define VALUEPRINTER_H #include "ValueDispatch.h" #include namespace slambench { namespace values { class ValuePrinter : public ConstValueDispatch { public: ValuePrinter(std::ostream &str); virtual ~ValuePrinter(); void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; void Dispatch(const TypeForVT::type* value) override; private: std::ostream &str_; }; } } #endif /* VALUEPRINTER_H */ ================================================ FILE: framework/shared/src/ColumnWriter.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "ColumnWriter.h" #include "metrics/Metric.h" #include "outputs/Output.h" #include "values/ValueInterface.h" #include "values/ValuePrinter.h" using namespace slambench; std::string LibColumnInterface::GetHeaderPrefix() const { std::string libname = GetLib()->getName(); if(libname != "") { if (libname.find("-") != libname.npos) { throw std::logic_error("This library name contains an illegal character '-' !" ); } libname = libname + "-"; } return libname; } ValueLibColumnInterface::ValueLibColumnInterface(SLAMBenchLibraryHelper* lib, outputs::BaseOutput* output) : ValueLibColumnInterface(lib, new values::OutputValueInterface(*output), output->GetName()) {} ValueLibColumnInterface::ValueLibColumnInterface(SLAMBenchLibraryHelper *lib, metrics::Metric *metric, metrics::Phase *phase) : ValueLibColumnInterface(lib, new values::MetricValueInterface(lib->GetMetricManager(), *metric, *phase), metric->GetName() + "_" + phase->GetName()) {} void ValueLibColumnInterface::Write(std::ostream& str) { values::ValuePrinter printer(str); auto value = value_->Get(); if(value != nullptr) { value_->Get()->Dispatch(&printer); } else { throw std::logic_error("Could not print missing value"); } } void ValueLibColumnInterface::WriteHeader(std::ostream& str) const { str << GetHeaderPrefix() << name_; } CollectionValueLibColumnInterface::CollectionValueLibColumnInterface(SLAMBenchLibraryHelper* lib, metrics::Metric* metric, metrics::Phase* phase) : ValueLibColumnInterface(lib,metric, phase) {} CollectionValueLibColumnInterface::CollectionValueLibColumnInterface(SLAMBenchLibraryHelper* lib, outputs::BaseOutput* output) : ValueLibColumnInterface(lib, output) {} void CollectionValueLibColumnInterface::WriteHeader(std::ostream& str) const { auto &spec = GetValueInterface()->GetDescription(); if(spec.GetType() != values::VT_COLLECTION) { throw std::logic_error(""); } if(spec.GetStructureDescription().empty()) { return; } auto i = spec.GetStructureDescription().begin(); str << GetHeaderPrefix() << i->first; i++; while(i != spec.GetStructureDescription().end()) { str << "\t" << GetHeaderPrefix() << i->first; i++; } } void CollectionValueLibColumnInterface::Write(std::ostream& str) { values::ValuePrinter printer(str); auto value = (values::TypeForVT::type*)GetValueInterface()->Get(); if(value->GetValue().empty()) { WriteInvalid(str); } else { auto i = value->GetValue().begin(); i->second->Dispatch(&printer); i++; while(i != value->GetValue().end()) { str << "\t"; i->second->Dispatch(&printer); i++; } } } void CollectionValueLibColumnInterface::WriteInvalid(std::ostream& str) { auto &spec = GetValueInterface()->GetDescription().GetStructureDescription(); if(spec.empty()) { return; } auto i = spec.begin(); str << "(n/a)"; i++; while(i != spec.end()) { str << "\t(n/a)"; i++; } } void OutputTimestampColumnInterface::Write(std::ostream& str) { TimeStamp ts = output_->GetMostRecentValue().first; double timestamp = ts.S + (ts.Ns/1000000000.0); str << timestamp; } void OutputTimestampColumnInterface::WriteHeader(std::ostream& str) const { str << "Timestamp"; } RowNumberColumn::RowNumberColumn() : counter_(1) {} void RowNumberColumn::Write(std::ostream& str) { str << counter_; counter_++; } void RowNumberColumn::WriteHeader(std::ostream& str) const { str << "Frame Number"; } ColumnWriter::ColumnWriter(std::ostream& str, const std::string &separator) : str_(str), separator_(separator) {} void ColumnWriter::AddColumn(ColumnInterface* interface) { columns_.push_back(interface); } void ColumnWriter::PrintRow() { if(!columns_.empty()) { auto i = columns_.begin(); columns_.front()->Write(str_); i++; while(i != columns_.end()) { str_ << separator_; (*i)->Write(str_); i++; } } str_ << std::endl; } void ColumnWriter::PrintHeader() { str_ << std::endl ; str_ << "Statistics:" << std::endl<<"=================" << std::endl<< std::endl; if(!columns_.empty()) { auto i = columns_.begin(); columns_.front()->WriteHeader(str_); i++; while(i != columns_.end()) { str_ << separator_; (*i)->WriteHeader(str_); i++; } } str_ << std::endl; } ================================================ FILE: framework/shared/src/ParameterComponent.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include ParameterComponent::~ParameterComponent() { for (Parameter* it : arguments_) { delete it; } arguments_.clear(); } ================================================ FILE: framework/shared/src/ParameterManager.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "Parameters.h" #include "ParameterManager.h" using namespace slambench; void ParameterManager::PrintValues(std::ostream &str, const ParameterComponent* c) const { c = c ? c : this; for (const auto param : c->getParameters()) { if (param == nullptr) { std::exit(1); } str << param->getLongOption(c) << ": " << param->getStrValue() << std::endl; } for (ParameterComponent* component_ptr : c->getComponents()) { PrintValues(str, component_ptr); } } void ParameterManager::PrintArguments(std::ostream& str, const ParameterComponent* c) const { static std::string::size_type short_len = 0; static std::string::size_type long_len = 0; static std::string::size_type depth = 0; c = c ? c : this; std::string comp = c->getName(); str << std::endl << std::setw(depth*3) << std::right << "" << " Component name: " << comp << "Depth:" << depth << std::endl ; for (Parameter* param : c->getParameters()) { std::string short_name = param->getShortOption(this); std::string long_name = param->getLongOption(this); short_len = std::max (short_name.length(), short_len) ; long_len = std::max (long_name.length(), long_len) ; } if (c->getComponents().size()) { str << std::setw(depth*3) << std::right << "" << " Sub components: " << comp << std::endl ; depth++; for (const ParameterComponent* component_ptr : c->getComponents()) { PrintArguments(str, component_ptr); } depth--; } if (c->getParameters().size()) { for (Parameter* param : c->getParameters()) { std::string short_name = param->getShortOption(c); std::string long_name = param->getLongOption(c); str << std::setw(depth*3) << std::right << "" ; if (short_name.length() > 0) { str << " -" << std::setw(short_len) << std::left << short_name ; } else { str << " " << std::setw(short_len) << std::left << " "; } str << " --" << std::setw(long_len) << std::left << long_name << " : " << param->getDescription() ; std::string defaultstr = param->getStrDefault(); std::string currentstr = param->getStrValue(); str << " (" ; if (defaultstr != "nullptr") { str << " Default=" << defaultstr ; } if (defaultstr != currentstr) { str << " Current=" << currentstr ; } str << " )" << std::endl; } } } bool ParameterManager::ReadArgumentsOrQuit(unsigned int argc, const char* const* const argv) { if(!ReadArguments(argc, argv)) { PrintArguments(std::cerr); exit(1); } return true; } bool ParameterManager::BuildArgumentsList(ParameterComponent *component_ptr) { if (!component_ptr) { params_long_.clear(); params_short_.clear(); component_ptr = this; } for (Parameter* param_ptr : component_ptr->getParameters()) { if (param_ptr->getLongOption(component_ptr) != "") { std::string long_opt = param_ptr->getLongOption(component_ptr); if (params_long_.count(long_opt)) { std::cerr << "*** Duplicated long option replaced: '" << long_opt << "'"<< std::endl; return false; params_long_[long_opt] = param_info_t(component_ptr, param_ptr); } else { params_long_[long_opt] = param_info_t(component_ptr, param_ptr); } } if (param_ptr->getShortOption(component_ptr) != "") { std::string short_opt = param_ptr->getShortOption(component_ptr); if (params_short_.count(short_opt)) { std::cerr << "*** Duplicated short option replaced: '" << short_opt << "'" << std::endl; return false; params_short_[short_opt] = param_info_t(component_ptr, param_ptr); } else { params_short_[short_opt] = param_info_t(component_ptr, param_ptr); } } } for (ParameterComponent* sub_component_ptr : component_ptr->getComponents()) { this->BuildArgumentsList(sub_component_ptr); } return true; } bool ParameterManager::ReadArguments(unsigned int argc, const char* const* const argv) { // Read and parse argvs unsigned i = 1; while(i < argc) { //****************************************** // Update_Map //****************************************** this->BuildArgumentsList(nullptr); //****************************************** // Parse next value //****************************************** const char *the_arg = argv[i]; param_info_t* param_info = nullptr; // figure out what kind of arg it is (long or short) if(the_arg[0] == '-') { if(the_arg[1] == '-') { // long arg if(params_long_.count(&the_arg[2])) { param_info = ¶ms_long_.at(&the_arg[2]); } else { // error - we've encountered a long param we don't support std::cerr << "Unrecognized argument: " << the_arg << std::endl; return false; } } else { // short arg if(params_short_.count(&the_arg[1])) { param_info = ¶ms_short_.at(&the_arg[1]); } else { std::cerr << "Unrecognized argument: " << the_arg << std::endl; return false; } } } else { std::cerr << "Error parsing arguments '" << the_arg << "'."; return false; } auto the_component = param_info->first; auto the_param = param_info->second; if(the_param) { if (the_param->requiresValue()) { std::string str_value = argv[i+1] ; i++; the_param->setValue(str_value.c_str()); std::cerr << "Parameter " << the_param->getName() << " assigned value " << the_param->getStrValue() << std::endl; } else { std::cerr << "Parameter " << the_param->getName() << " triggered." << std::endl; } if (the_param->getCallback()) { (the_param->getCallback())(the_param, the_component); } } i++; } return true; } ================================================ FILE: framework/shared/src/ResultWriter.cpp ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #include "ResultWriter.h" #include ResultWriter::ResultWriter(std::ofstream &out_stream):out_(out_stream) {} void ResultWriter::WriteKV(std::string key, std::string value) { out_ << key << ": " << value << std::endl; } void ResultWriter::WriteKV(std::string key, std::vector values, std::string separator) { out_ << key << ": "; for (auto it = values.begin(); it != values.end(); ++it) { if (it != values.begin()) out_ << separator; out_ << *it; } out_ << std::endl; } void ResultWriter::WriteTrajectory(slambench::outputs::BaseOutput::value_map_t traj) { float x, y, z; Eigen::Matrix3d R; out_ << "# data_stamp, p.x, p.y, p.z, q.x, q.y, q.z, q.w" << std::endl; for (auto point: traj) { Eigen::Matrix4f pose = dynamic_cast(point.second)->GetValue(); x = pose(0, 3); if (std::to_string(x) == "-nan") { continue; } y = pose(1, 3); z = pose(2, 3); Eigen::Matrix3f R = pose.block<3,3>(0,0); Eigen::Quaternionf q(R); q.normalize(); out_ << point.first << " " << x << " " << y << " " << z << " " << q.x() << " " << q.y() << " " << q.z() << " " << q.w() <= 48 && int(mem_info[i]) <= 57) { break; } position++; } mem_info = mem_info.substr(position, 100); position = 0; for(size_t i = 0; i < mem_info.size(); i++) { if (int(mem_info[i]) < 48 || int(mem_info[i]) > 57) { break; } position++; } mem_info = mem_info.substr(0, position); mem_size = std::stoi(mem_info); break; } } fclose(fp); return std::to_string(mem_size / 1024 / 1024) + " GB"; } ================================================ FILE: framework/shared/src/SLAMBenchConfiguration.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "SLAMBenchConfiguration.h" #include "TimeStamp.h" #include #include "sb_malloc.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "ResultWriter.h" SLAMBenchConfiguration::SLAMBenchConfiguration(void (*custom_input_callback)(Parameter*, ParameterComponent*),void (*libs_callback)(Parameter*, ParameterComponent*)) : ParameterComponent("") { if(!custom_input_callback) custom_input_callback = input_callback; if(!libs_callback) libs_callback = slam_library_callback; initialised_ = false; log_stream_ = nullptr; slam_library_names_ = {}; // Run Related addParameter(TypedParameter("fl", "frame-limit", "last frame to compute", &frame_limit_, &default_frame_limit)); addParameter(TypedParameter("s", "start-frame", "first frame to compute", &start_frame_, &default_start_frame)); addParameter(TypedParameter("o", "log-file", "Output log file", &log_file_, &default_log_file, log_callback)); addParameter(TypedParameter>("i", "input" , "Specify the input file or mode." , &input_files_, &default_input_files , custom_input_callback)); addParameter(TypedParameter >("load", "load-slam-library" , "Load a specific SLAM library." , &slam_library_names_, &default_slam_libraries, libs_callback)); addParameter(TriggeredParameter("dse", "dse", "Output solution space of parameters.", dse_callback)); addParameter(TriggeredParameter("h", "help", "Print the help.", help_callback)); addParameter(TypedParameter("realtime", "realtime-mode", "realtime frame loading mode", &realtime_mode_, &default_is_false)); addParameter(TypedParameter("realtime-mult", "realtime-multiplier", "realtime frame loading mode", &realtime_mult_, &default_realtime_mult)); param_manager_.AddComponent(this); } SLAMBenchConfiguration::~SLAMBenchConfiguration() { //Clean algorithms for (auto lib : slam_libs_) { std::cerr << "Cleaning " << lib->getName() << std::endl; if (!lib->c_sb_clean_slam_system()) { std::cerr << "Algorithm cleaning failed." << std::endl; exit(1); } else { std::cerr << "Algorithm cleaning succeed." << std::endl; } } } void SLAMBenchConfiguration::AddSLAMLibrary(const std::string& so_file, const std::string &id) { std::cerr << "new library name: " << so_file << std::endl; void* handle = dlopen(so_file.c_str(),RTLD_LAZY); if (!handle) { std::cerr << "Cannot open library: " << dlerror() << std::endl; exit(1); } auto libname_start = so_file.find_last_of('/')+3; auto libName = so_file.substr(libname_start, so_file.find('-', libname_start)); auto lib_ptr = new SLAMBenchLibraryHelper(id, libName, this->GetLogStream(), input_interface_manager_->GetCurrentInputInterface()); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_init_slam_system); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_new_slam_configuration); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_update_frame); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_process_once); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_clean_slam_system); LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_update_outputs); // workaround to be compatible with benchmarks that does not implement the relocalize API if (dlsym(handle, "_Z13sb_relocalizeP22SLAMBenchLibraryHelper")) { LOAD_FUNC2HELPER(handle,lib_ptr,c_sb_relocalize); } else { std::cout << "Benchmark does not implement sb_relocalize(). Will use the default." << std::endl; lib_ptr->c_sb_relocalize = lib_ptr->c_sb_process_once; } slam_libs_.push_back(lib_ptr); size_t pre = slambench::memory::MemoryProfile::singleton.GetOverallData().BytesAllocatedAtEndOfFrame; if (!lib_ptr->c_sb_new_slam_configuration(lib_ptr)) { std::cerr << "Configuration construction failed." << std::endl; exit(1); } size_t post = slambench::memory::MemoryProfile::singleton.GetOverallData().BytesAllocatedAtEndOfFrame; std::cerr << "Configuration consumed " << post-pre << " bytes" << std::endl; param_manager_.AddComponent(lib_ptr); std::cerr << "SLAM library loaded: " << so_file << std::endl; } void SLAMBenchConfiguration::InitGroundtruth(bool with_point_cloud) { if(initialised_) return; auto interface = input_interface_manager_->GetCurrentInputInterface(); if(interface != nullptr) { auto gt_buffering_stream = new slambench::io::GTBufferingFrameStream(interface->GetFrames()); input_interface_manager_->input_stream_ = gt_buffering_stream; if(realtime_mode_) { std::cerr << "Real time mode enabled" << std::endl; input_interface_manager_->input_stream_ = new slambench::io::RealTimeFrameStream(input_interface_manager_->input_stream_, realtime_mult_, true); } else { std::cerr << "Process every frame mode enabled" << std::endl; } ground_truth_.LoadGTOutputsFromSLAMFile(interface->GetSensors(), gt_buffering_stream->GetGTFrames(), with_point_cloud); } auto gt_trajectory = ground_truth_.GetMainOutput(slambench::values::VT_POSE); if(gt_trajectory == nullptr) { // Warn if there is no ground truth gt_available_ = false; std::cerr << "Dataset does not provide a GT trajectory" << std::endl; } else { gt_available_ = true; } initialised_ = true; } void SLAMBenchConfiguration::InitAlgorithms() { assert(initialised_); for (auto &lib : slam_libs_) { lib->GetMetricManager().BeginInit(); bool init_worked = lib->c_sb_init_slam_system(lib); lib->GetMetricManager().EndInit(); if (!init_worked) { std::cerr << "Algorithm initialization failed." << std::endl; exit(1); } auto trajectory = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); if(trajectory == nullptr) { std::cerr << "Algo does not provide a main pose output" << std::endl; exit(1); } } } void SLAMBenchConfiguration::InitAlignment() { if(!gt_available_) return; slambench::outputs::TrajectoryAlignmentMethod *alignment_method; if(alignment_technique_ == "original") { alignment_method = new slambench::outputs::OriginalTrajectoryAlignmentMethod(); } else if(alignment_technique_ == "new") { alignment_method = new slambench::outputs::NewTrajectoryAlignmentMethod(); } else if(alignment_technique_ == "umeyama") { alignment_method = new slambench::outputs::UmeyamaTrajectoryAlignmentMethod(); } else { std::cerr << "Unknown alignment method " << alignment_technique_ << std::endl; throw std::logic_error("Unknown alignment method"); } auto gt_traj = GetGroundTruth().GetMainOutput(slambench::values::VT_POSE); alignments_.clear(); for(size_t i = 0; i < slam_libs_.size(); i++) { SLAMBenchLibraryHelper *lib = slam_libs_[i]; auto lib_traj = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); auto alignment = new slambench::outputs::AlignmentOutput(lib->getName() + "Alignment", new slambench::outputs::PoseOutputTrajectoryInterface( gt_traj), lib_traj, alignment_method); alignment->SetActive(true); alignment->SetKeepOnlyMostRecent(true); alignments_.push_back(alignment); auto aligned = new slambench::outputs::AlignedPoseOutput(lib_traj->GetName() + " (Aligned)", alignments_[i], lib_traj); lib->GetOutputManager().RegisterOutput(aligned); //Align point cloud auto pointcloud = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POINTCLOUD); if(pointcloud != nullptr) { auto pc_aligned = new slambench::outputs::AlignedPointCloudOutput(lib->getName() + pointcloud->GetName() + "(Aligned)", alignment, pointcloud); lib->GetOutputManager().RegisterOutput(pc_aligned); } } } void SLAMBenchConfiguration::ComputeLoopAlgorithm(bool *stay_on, SLAMBenchUI *ui) { assert(initialised_); int input_seq = 0; bool ongoing = false; std::vector libs_trans; // ********* [[ MAIN LOOP ]] ********* unsigned int frame_count = 0; while(true) { if (frame_count != 0 && ui && !ongoing) { if (!(ui->WaitForFrame() || !ui->IsFreeRunning())) { std::cerr << "!ui->WaitForFrame() ==> break" << std::endl; break; } } auto current_frame = input_interface_manager_->GetNextFrame(); while (current_frame != nullptr) { frame_count++; if (current_frame->FrameSensor->GetType() != slambench::io::GroundTruthSensor::kGroundTruthTrajectoryType) { // ********* [[ NEW FRAME PROCESSED BY ALGO ]] ********* for (size_t i = 0; i < slam_libs_.size(); i++) { auto lib = slam_libs_[i]; // ********* [[ SEND THE FRAME ]] ********* ongoing = not lib->c_sb_update_frame(lib, current_frame); // This algorithm hasn't received enough frames yet. if (ongoing) { continue; } // ********* [[ PROCESS ALGO START ]] ********* lib->GetMetricManager().BeginFrame(); slambench::TimeStamp ts = current_frame->Timestamp; if (!input_interface_manager_->updated_) { if (not lib->c_sb_process_once(lib)) { std::cerr <<"Error after lib->c_sb_process_once." << std::endl; exit(1); } } else { // ********** [[or relocalization]] ********** //Mihai: need assertion / safety mechanism to avoid ugly errors bool res = lib->c_sb_relocalize(lib); input_interface_manager_->updated_ = false; frame_count = 0; /* If the library failed to re-localize at the beginning of a new input, the framework will send a ground-truth pose to it (so-called aided_reloc). The sent pose is transformed to be relative to the first estimated pose from the library. */ if(!res && gt_available_) { aided_reloc_ = true; //Find the nearest one auto gt_frame = input_interface_manager_->GetClosestGTFrameToTime(ts); Eigen::Matrix4f &t = alignments_[i]->getTransformation(); Eigen::Matrix4f gt; memcpy(gt.data(), gt_frame->GetData(), gt_frame->GetSize()); slambench::io::FrameBuffer* buffer = &(dynamic_cast(gt_frame)->getFrameBuffer()); buffer->resetLock(); Eigen::Matrix4f es = t.inverse() * gt; memcpy(gt_frame->GetData(), es.data(), gt_frame->GetSize()); buffer->resetLock(); lib->c_sb_update_frame(lib, gt_frame);// groundtruth feed buffer->resetLock(); memcpy(gt_frame->GetData(), gt.data(), gt_frame->GetSize()); buffer->resetLock(); } } if (!lib->c_sb_update_outputs(lib, &ts)) { std::cerr << "Failed to get outputs" << std::endl; exit(1); } lib->GetMetricManager().EndFrame(); } // ********* [[ FINALIZE ]] ********* if (!ongoing) { FireEndOfFrame(); if (ui) ui->stepFrame(); frame_count += 1; if (frame_limit_ > 0 && frame_count >= frame_limit_) { break; } } } current_frame->FreeData(); current_frame = input_interface_manager_->GetNextFrame(); } // we're done with the frame if (!output_filename_.empty()) SaveResults(); // Freeze the alignment after end of the first input if (input_seq++ == 0) for(auto& alignment : alignments_) alignment->SetFreeze(true); if (!LoadNextInputInterface()) break; } } bool SLAMBenchConfiguration::LoadNextInputInterface() { if(!input_interface_manager_->LoadNextInputInterface()) return false; initialised_ = false; ResetSensors(); InitGroundtruth(); InitAlignment(); InitWriter(); for (auto lib : this->slam_libs_) { lib->update_input_interface(input_interface_manager_->GetCurrentInputInterface()); } current_input_id_++; return true; } //saves results in TUM format TODO: move out of SLAMBenchConfiguration void SLAMBenchConfiguration::SaveResults() { if (output_filename_.empty() ) { return; } boost::filesystem::path input_name(input_filenames_[current_input_id_]); input_name = input_name.filename(); boost::filesystem::path output_name = boost::filesystem::path(output_filename_); boost::filesystem::path output_prefix; boost::filesystem::path gt_dir; if (boost::filesystem::is_directory(output_name)) { output_name.append("/"); output_prefix = output_name; gt_dir = output_name; } else { output_prefix = output_name.replace_extension().append("-"); gt_dir = output_name.parent_path(); } boost::filesystem::path gt_file = gt_dir; gt_file += input_name; gt_file.replace_extension(".gt"); bool first_input = current_input_id_ == 0; static std::string cpu_info = ResultWriter::GetCPUModel(); static std::string gpu_info = "";// memory_metric->cuda_monitor.IsActive() ? memory_metric->cuda_monitor.device_name : ""; static std::string mem_info = ResultWriter::GetMemorySize(); for(SLAMBenchLibraryHelper *lib : slam_libs_) { std::string filename = output_prefix.append(lib->GetLibraryName() + ".txt").string(); std::ofstream out(filename, first_input ? std::ios::out : std::ios::app); ResultWriter writer(out); if (first_input) { writer.WriteKV("benchmark", lib->GetLibraryName()); writer.WriteKV("inputs", input_filenames_); writer.WriteKV("CPU", cpu_info); if (!gpu_info.empty()) writer.WriteKV("GPU", gpu_info); writer.WriteKV("memory", mem_info); } out << std::endl; writer.WriteKV("input", input_name.string()); writer.WriteKV("aided_reloc", std::to_string(aided_reloc_)); slambench::outputs::BaseOutput::value_map_t traj = lib->GetOutputManager().GetOutput("Pose")->GetValues(); writer.WriteTrajectory(traj); std::cout << "Results saved into " << filename << std::endl; } if (!boost::filesystem::exists(gt_file)) { std::ofstream out(gt_file.string()); slambench::outputs::BaseOutput::value_map_t traj = GetGroundTruth().GetMainOutput(slambench::values::VT_POSE)->GetValues(); ResultWriter writer(out); writer.WriteKV("input", input_name.string()); writer.WriteTrajectory(traj); std::cout << "Ground-truth saved into " << gt_file.string() << std::endl; } } void SLAMBenchConfiguration::InitWriter() { if (writer_) { for(SLAMBenchLibraryHelper *lib : slam_libs_) { lib->GetMetricManager().reset(); lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE)->reset(); } //TODO: move this to callback when starting a new sequence aided_reloc_ = false; } else { // the following metrics last for all inputs; other metrics are allocated for only one input duration_metric_ = std::make_shared(); power_metric_ = std::make_shared(); } auto gt_traj = ground_truth_.GetMainOutput(slambench::values::VT_POSE); writer_ = std::make_unique(this->GetLogStream(), "\t"); writer_->AddColumn(&(row_number_)); int i = 0; for(SLAMBenchLibraryHelper *lib : slam_libs_) { // retrieve the trajectory of the lib auto lib_traj = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); if (lib_traj == nullptr) { std::cerr << "There is no output trajectory in the library outputs." << std::endl; exit(1); } writer_->AddColumn(new slambench::OutputTimestampColumnInterface(lib_traj)); if (gt_traj) { // Create an aligned trajectory auto aligned = new slambench::outputs::AlignedPoseOutput("", &*alignments_[i], lib_traj); // Add ATE metric auto ate_metric = std::make_shared(new slambench::outputs::PoseOutputTrajectoryInterface(aligned), new slambench::outputs::PoseOutputTrajectoryInterface(gt_traj)); if (!ate_metric->GetValueDescription().GetStructureDescription().empty()) { lib->GetMetricManager().AddFrameMetric(ate_metric); writer_->AddColumn(new slambench::CollectionValueLibColumnInterface(lib, &*ate_metric, lib->GetMetricManager().GetFramePhase())); } // Add RPE metric auto rpe_metric = std::make_shared(new slambench::outputs::PoseOutputTrajectoryInterface(aligned), new slambench::outputs::PoseOutputTrajectoryInterface(gt_traj)); lib->GetMetricManager().AddFrameMetric(rpe_metric); writer_->AddColumn(new slambench::CollectionValueLibColumnInterface(lib, &*rpe_metric, lib->GetMetricManager().GetFramePhase())); } else { std::cerr<<"NO GT TRAJECTORY!!"<GetMetricManager().AddFrameMetric(duration_metric_); lib->GetMetricManager().AddPhaseMetric(duration_metric_); writer_->AddColumn(new slambench::ValueLibColumnInterface(lib, &*duration_metric_, lib->GetMetricManager().GetFramePhase())); for(auto phase : lib->GetMetricManager().GetPhases()) { writer_->AddColumn(new slambench::ValueLibColumnInterface(lib, &*duration_metric_, phase)); } // Add a memory metric auto memory_metric = std::make_shared(); lib->GetMetricManager().AddFrameMetric(memory_metric); writer_->AddColumn(new slambench::CollectionValueLibColumnInterface(lib, &*memory_metric, lib->GetMetricManager().GetFramePhase())); // Add a power metric if it makes sense if (!power_metric_->GetValueDescription().GetStructureDescription().empty()) { lib->GetMetricManager().AddFrameMetric(power_metric_); writer_->AddColumn(new slambench::CollectionValueLibColumnInterface(lib, &*power_metric_, lib->GetMetricManager().GetFramePhase())); } // Add XYZ row from the trajectory auto traj = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); traj->SetActive(true); writer_->AddColumn(new slambench::CollectionValueLibColumnInterface(lib, new slambench::outputs::PoseToXYZOutput(traj))); i++; } frame_callbacks_.clear(); AddFrameCallback([this]{writer_->PrintRow();}); // @suppress("Invalid arguments") writer_->PrintHeader(); } void SLAMBenchConfiguration::PrintDse() { for (SLAMBenchLibraryHelper* lib : slam_libs_) { std::cout << "libs:" << lib->GetIdentifier() << "\n" ; for (auto parameter : lib->getParameters()) { std::cout << "argument:" << parameter->getLongOption(lib) << "\n" ; std::cout << parameter->getStrDetails(lib) << "\n" ; } } exit(0); } void SLAMBenchConfiguration::StartStatistics() { GetLogStream().setf(std::ios::fixed, std::ios::floatfield); GetLogStream().precision(10); time_t rawtime; struct tm *timeinfo; char buffer[80]; time(&rawtime); timeinfo=localtime(&rawtime); strftime(buffer,80,"%Y-%m-%d %I:%M:%S",timeinfo); this->GetLogStream() << "SLAMBench Report run started:\t" << buffer << std::endl << std::endl; // Print arguments known so far this->GetLogStream() << "Properties:" << std::endl << "=================" << std::endl << std::endl; param_manager_.PrintValues(GetLogStream()); } ================================================ FILE: framework/shared/src/SLAMBenchUI_Pangolin.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include SLAMBenchUI_Pangolin::SLAMBenchUI_Pangolin() : SLAMBenchUI() { isFreeRunning = false; int view_width = 1280; int view_height = 980; int panel_width = 360; view_width += panel_width; pangolin::Params windowParams; windowParams.Set("SAMPLE_BUFFERS", 0); windowParams.Set("SAMPLES", 0); pangolin::CreateWindowAndBind("Main", view_width, view_height, windowParams); glGenTextures(MAX_WINDOW, textureId); glGenBuffers(1, &vbo); // Define Camera Render Object (for view / scene browsing) pangolin::OpenGlMatrix proj = pangolin::ProjectionMatrix(640,480,420,420,320,240,0.1,1000); s_cam = pangolin::OpenGlRenderState(proj, pangolin::ModelViewLookAt(-1, -5, -1, 0, 0, 0, pangolin::AxisNegY)); //! Set bounds for the View using mixed fractional / pixel coordinates (OpenGl view coordinates) // View& SetBounds(Attach bottom, Attach top, Attach left, Attach right); // SetBounds (Attach bottom, Attach top, Attach left, Attach right, double aspect); // 'Negative' aspect ratio causes pangolin to overdraw and then trim the // view. This is a little bit hacky but is a much easier solution than // trapping window resize events and rescaling the window then. pangolin::Display("cam").SetBounds(0.0, 1.0f, 0.0f, 1.0f, 640 / 480.0).SetHandler(new pangolin::Handler3D(s_cam)) .SetLock(pangolin::LockRight, pangolin::LockTop); pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, pangolin::Attach::Pix(panel_width)); frameCount = new pangolin::Var("ui.Frame", 0); TVM = new pangolin::Var("ui.Total Virtual Memory (MB)", 0); CVM = new pangolin::Var("ui.Used Virtual Memory (MB)", 0); VSIZE = new pangolin::Var("ui.Process Virtual Memory (MB)", 0); TPM = new pangolin::Var("ui.Total Physical Memory (MB)", 0); CPM = new pangolin::Var("ui.Used Physical Memory (MB)", 0); VRSS = new pangolin::Var("ui.Process Physical Memory (MB)", 0); showEveryPose = new pangolin::Var("ui.Show every poses", 0, 0, 100); if(CanFreeRun()) { freeRunning = new pangolin::Var("ui.Free Running", true, true); } if(CanStep()) { nextFrame = new pangolin::Var("ui.Next Frame", false, false); } unFollow=NULL; } SLAMBenchUI_Pangolin::~SLAMBenchUI_Pangolin() { if(unFollow) delete unFollow; delete frameCount; delete VRSS ; delete VSIZE; delete TVM ; delete CVM ; delete TPM ; delete CPM ; } void SLAMBenchUI_Pangolin::AddFollowControls() { pangolin::Var categoryText("ui.description.Camera Pose", false,false); for(auto output_mgr : GetOutputManagers()) { const std::string &prefix = output_mgr.first; for(auto output : *output_mgr.second) { slambench::outputs::BaseOutput* bo = output.second; std::string panelname = "ui.output." + prefix + "." + bo->GetName(); switch(bo->GetType()) { case slambench::values::VT_POSE: outputs_follow_.insert({bo, new pangolin::Var(panelname + "." + bo->GetName() + " Follow", false, true)}); break; default: break; } } } } void SLAMBenchUI_Pangolin::AddBackgroundControls() { pangolin::Var categoryText("ui.description.Backgrounds", false,false); for(auto output_mgr : GetOutputManagers()) { const std::string &prefix = output_mgr.first; for(auto output : *output_mgr.second) { slambench::outputs::BaseOutput* bo = output.second; std::string panelname = "ui.output." + prefix + "." + bo->GetName(); switch(bo->GetType()) { case slambench::values::VT_FRAME: outputs_background_.insert({bo, new pangolin::Var(panelname + "." + bo->GetName() + " Background", false, true)}); break; default: break; } } } } void SLAMBenchUI_Pangolin::AddControlsForOutput(const std::string &prefix, slambench::outputs::BaseOutput* output) { std::string button_name = "ui.output." + prefix + "." + output->GetName() ; if(output->GetType() == slambench::values::VT_STRING) { outputs_text_[output] = new pangolin::Var(button_name); outputs_enabled_.insert({output, new pangolin::Var(button_name + " Enabled", true, true)}); } else { outputs_enabled_.insert({output, new pangolin::Var(button_name + " Enabled", true, true)}); outputs_visible_.insert({output, new pangolin::Var(button_name + " Visible", true, true)}); switch(output->GetType()) { case slambench::values::VT_POINTCLOUD: case slambench::values::VT_POSE: outputs_colour_.insert({output, new pangolin::Var(button_name + " Colour", 0.0, 0.0, 1.0)}); break; default: break; } } } void SLAMBenchUI_Pangolin::InitialiseOutputs() { AddBackgroundControls(); AddFollowControls(); for(auto output_mgr : GetOutputManagers()) { for(auto output : *output_mgr.second) { AddControlsForOutput(output_mgr.first, output.second); } } int i = 0; for(auto output : outputs_colour_) { pangolin::Var *var = output.second; float value = (1.0 / outputs_colour_.size()) * (i+1); *var = value; i++; std::cerr << "Set " << output.first->GetName() << " to " << *var << std::endl; } } bool SLAMBenchUI_Pangolin::CanFreeRun() { return true; } bool SLAMBenchUI_Pangolin::CanStep() { return true; } bool SLAMBenchUI_Pangolin::ClearFreeRunning() { if(isFreeRunning) { isFreeRunning = false; std::unique_lock lck(step_mutex); step_cv.wait(lck); } return true; } bool SLAMBenchUI_Pangolin::IsFreeRunning() { return isFreeRunning; } bool SLAMBenchUI_Pangolin::SetFreeRunning() { if(!isFreeRunning) { isFreeRunning = true; std::unique_lock lck(step_mutex); step_cv.wait(lck); } return true; } bool SLAMBenchUI_Pangolin::WaitForFrame() { if(!CanStep()) { throw std::exception(); } std::unique_lock lck(step_mutex); step_cv.wait(lck); return true; } void SLAMBenchUI_Pangolin::StopTracking () { if(unFollow) unFollow->Ref().Set(true); } float ConvertChannel(float f) { // f ranges from -1 to 1, we want 0 to 1 return (f + 1) / 2; } std::tuple ConvertColour(std::tuple incol) { return std::make_tuple(ConvertChannel(std::get<0>(incol)), ConvertChannel(std::get<1>(incol)), ConvertChannel(std::get<2>(incol))); } std::tuple GetUnconvertedColour(float f) { // convert to wavelength float wl = 380 + (f * (645-380)); if(wl >= 380 && wl <= 440) { return std::make_tuple(-1 * (wl - 440) / (440 - 380), 0, 1); } else if(wl >= 440 && wl <= 490) { return std::make_tuple(0, ((wl - 440) / (490 - 440)), 1); } else if(wl >= 490 && wl <= 510) { return std::make_tuple(0, 1, -1 * (wl - 510) / (510-490)); } else if(wl >=510 && wl <= 580) { return std::make_tuple((wl-510) / (580-510), 1, 0); } else if(wl >= 580 && wl <= 645) { return std::make_tuple(1, -1 * (wl - 645) / (645 - 580), 0); } else if(wl >= 645 && wl <= 780) { return std::make_tuple(1, 0, 0); } return std::make_tuple(0,0,0); } std::tuple GetColour(float f) { return ConvertColour(GetUnconvertedColour(f)); } class PoseOutputDrawContext { public: PoseOutputDrawContext(slambench::outputs::BaseOutput *output) : interface(output) {} slambench::outputs::PoseOutputTrajectoryInterface interface; }; bool SLAMBenchUI_Pangolin::DrawPoseOutput(slambench::outputs::BaseOutput* output) { assert(output->GetType() == slambench::values::VT_POSE); auto &context = pose_output_draw_contexts_[output]; if(context == nullptr) { context = new PoseOutputDrawContext(output); } auto colour = GetColour(outputs_colour_.at(output)->Get()); drawTrajectory(&context->interface, std::get<0>(colour), std::get<1>(colour), std::get<2>(colour), showEveryPose->Ref().Get()); return true; } bool SLAMBenchUI_Pangolin::DrawPointCloudOutput(slambench::outputs::BaseOutput* output) { assert(output->GetType() == slambench::values::VT_POINTCLOUD); output->SetKeepOnlyMostRecent(true); if(!output->IsActive() or output->GetValues().empty()) { return true; } #ifdef HARRY_SPEEDUP auto timestamp = output->GetMostRecentValue().first; const slambench::values::PointCloudValue *latest_pc = static_cast(output->GetMostRecentValue().second); size_t size = latest_pc->GetPoints().size(); auto colour = GetColour(outputs_colour_.at(output)->Get()); bool new_output = false; if(!pointcloud_state_.count(output)) { glCreateBuffers(1, &pointcloud_state_[output].VBO); new_output = true; } auto &state = pointcloud_state_[output]; glBindBuffer(GL_ARRAY_BUFFER, state.VBO); if(new_output || state.timestamp != timestamp) { glBufferData(GL_ARRAY_BUFFER, sizeof(slambench::values::Point3DF) * size, latest_pc->GetPoints().data(), GL_STATIC_DRAW); state.timestamp = timestamp; } glColor3f(std::get<0>(colour),std::get<1>(colour),std::get<2>(colour)); glMatrixMode(GL_MODELVIEW); glPushMatrix(); glMultMatrixf((GLfloat*)latest_pc->GetTransform().data()); glVertexPointer(3, GL_FLOAT, sizeof(slambench::values::Point3DF), 0); glEnableClientState(GL_VERTEX_ARRAY); glDrawArrays(GL_POINTS, 0, size); glDisableClientState(GL_VERTEX_ARRAY); glBindBuffer(GL_ARRAY_BUFFER, 0); glPopMatrix(); return true; #else const slambench::values::PointCloudValue *latest_pc = static_cast(output->GetValues().rbegin()->second); size_t size = latest_pc->GetPoints().size(); auto colour = GetColour(outputs_colour_.at(output)->Get()); glColor3f(std::get<0>(colour),std::get<1>(colour),std::get<2>(colour)); glBindBuffer(GL_ARRAY_BUFFER, vbo); glBufferData(GL_ARRAY_BUFFER, sizeof(slambench::values::Point3DF) * size, latest_pc->GetPoints().data(), GL_STATIC_DRAW); glMatrixMode(GL_MODELVIEW); glPushMatrix(); glMultMatrixf((GLfloat*)latest_pc->GetTransform().data()); glBindBuffer(GL_ARRAY_BUFFER, vbo); glVertexPointer(3, GL_FLOAT, sizeof(slambench::values::Point3DF), 0); glEnableClientState(GL_VERTEX_ARRAY); glDrawArrays(GL_POINTS, 0, size); glDisableClientState(GL_VERTEX_ARRAY); glBindBuffer(GL_ARRAY_BUFFER, 0); glPopMatrix(); return true; #endif } bool SLAMBenchUI_Pangolin::DrawColouredPointCloudOutput(slambench::outputs::BaseOutput* output) { assert(output->GetType() == slambench::values::VT_COLOUREDPOINTCLOUD); output->SetKeepOnlyMostRecent(true); if(!output->IsActive() or output->GetValues().empty()) { return true; } #ifdef HARRY_SPEEDUP auto timestamp = output->GetMostRecentValue().first; const slambench::values::ColoredPointCloudValue *latest_pc = static_cast(output->GetMostRecentValue().second); size_t size = latest_pc->GetPoints().size(); bool new_output = false; if(!pointcloud_state_.count(output)) { glCreateBuffers(1, &pointcloud_state_[output].VBO); new_output = true; } auto &state = pointcloud_state_[output]; glBindBuffer(GL_ARRAY_BUFFER, state.VBO); if(new_output || state.timestamp != timestamp) { glBufferData(GL_ARRAY_BUFFER, sizeof(slambench::values::Point3DF) * size, latest_pc->GetPoints().data(), GL_STATIC_DRAW); state.timestamp = timestamp; } glMatrixMode(GL_MODELVIEW); glPushMatrix(); glMultMatrixf((GLfloat*)latest_pc->GetTransform().data()); glVertexPointer(3, GL_FLOAT, sizeof(slambench::values::ColoredPoint3DF), 0); glColorPointer(3, GL_UNSIGNED_BYTE, sizeof(slambench::values::ColoredPoint3DF), (void*)offsetof(slambench::values::ColoredPoint3DF, R)); glEnableClientState(GL_VERTEX_ARRAY); glEnableClientState(GL_COLOR_ARRAY); glDrawArrays(GL_POINTS, 0, size); glDisableClientState(GL_VERTEX_ARRAY); glDisableClientState(GL_COLOR_ARRAY); glBindBuffer(GL_ARRAY_BUFFER, 0); glPopMatrix(); return true; #else const slambench::values::ColoredPointCloudValue *latest_pc = static_cast(output->GetValues().rbegin()->second); size_t size = latest_pc->GetPoints().size(); glBindBuffer(GL_ARRAY_BUFFER, vbo); glBufferData(GL_ARRAY_BUFFER, sizeof(slambench::values::Point3DF) * size, latest_pc->GetPoints().data(), GL_STATIC_DRAW); glMatrixMode(GL_MODELVIEW); glPushMatrix(); glMultMatrixf((GLfloat*)latest_pc->GetTransform().data()); glBindBuffer(GL_ARRAY_BUFFER, vbo); glVertexPointer(3, GL_FLOAT, sizeof(slambench::values::ColoredPoint3DF), 0); glColorPointer(3, GL_UNSIGNED_BYTE, sizeof(slambench::values::ColoredPoint3DF), (void*)offsetof(slambench::values::ColoredPoint3DF, R)); glEnableClientState(GL_VERTEX_ARRAY); glDrawArrays(GL_POINTS, 0, size); glDisableClientState(GL_VERTEX_ARRAY); glBindBuffer(GL_ARRAY_BUFFER, 0); glPopMatrix(); return true; #endif } bool SLAMBenchUI_Pangolin::EnqueueFrame(slambench::values::FrameValue *frame) { frames_.push_back(*frame); return true; } bool SLAMBenchUI_Pangolin::DrawBackgrounds() { for (auto button : outputs_background_) { if (button.second->Get() and last_background_ != button.second) { // std::cout << "New background" << std::endl; last_background_ = button.second; break; } if (!button.second->Get() and last_background_ == button.second) { // std::cout << "unchecked background" << std::endl; last_background_ = nullptr; break; } } for (auto button : outputs_background_) { button.second->Ref().Set(last_background_ == button.second); } for(auto output_mgr : GetOutputManagers()) { std::lock_guard lock(output_mgr.second->GetLock()); (void)lock; // I hate that werror so much for(auto output : *output_mgr.second) { if (output.second->IsActive() and (output.second->GetType() == slambench::values::VT_FRAME) and outputs_background_.at(output.second)->Get()) { this->drawBackground((slambench::values::FrameValue*)output.second->GetValues().rbegin()->second); } } } return true; } bool SLAMBenchUI_Pangolin::FollowPoses() { for (auto button : outputs_follow_) { if (button.second->Get() and last_follow_ != button.second) { // std::cout << "New follow" << std::endl; last_follow_ = button.second; break; } if (!button.second->Get() and last_follow_ == button.second) { // std::cout << "unchecked follow" << std::endl; last_follow_ = nullptr; break; } } bool should_follow = false; for (auto button : outputs_follow_) { if(last_follow_ == button.second) { should_follow = true; } button.second->Ref().Set(last_follow_ == button.second); } if(should_follow) { Eigen::Matrix4f followed_pose = Eigen::Matrix4f::Identity(); bool got_pose = false; for(auto output_mgrp : GetOutputManagers()) { auto output_mgr = output_mgrp.second; std::lock_guard lock(output_mgr->GetLock()); (void)lock; // I hate that werror so much for(auto output : *output_mgr) { if (output.second->GetType() != slambench::values::VT_POSE) { continue; } if(not output.second->IsActive()) { continue; } if(output.second->Empty()) { continue; } if (outputs_follow_.at(output.second)->Get()) { followed_pose = ((slambench::values::PoseValue*)(output.second->GetMostRecentValue().second))->GetValue(); got_pose = true; } } } if(got_pose) { FollowPose(followed_pose); } } return true; } bool SLAMBenchUI_Pangolin::DrawQueuedFrames() { if (frames_.size() == 0) { return true; } Eigen::Vector4f winReg[MAX_WINDOW]; // (x1, y1, x2, y2) winReg[0] = {0.0f, 0.5f, 0.5f, 1.0f}; winReg[1] = {0.5f, 0.5f, 1.0f, 1.0f}; winReg[2] = {0.0f, 0.0f, 0.5f, 0.5f}; winReg[3] = {0.5f, 0.0f, 1.0f, 0.5f}; //display the image glColor3f(1.0,1.0,1.0); glMatrixMode(GL_PROJECTION); glLoadIdentity(); glMatrixMode(GL_MODELVIEW); glLoadIdentity(); glEnable(GL_TEXTURE_2D); for (unsigned int w = 0 ; w < frames_.size(); w++) { slambench::values::FrameValue &frame = frames_.at(w); glBindTexture(GL_TEXTURE_2D, textureId[w]); GLint format, type, internalformat; switch(frame.GetFormat()) { case slambench::io::pixelformat::G_I_8: case slambench::io::pixelformat::D_I_8: internalformat = GL_RGBA; format = GL_LUMINANCE; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::RGB_III_888: internalformat = GL_RGB; format = GL_RGB; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::RGBA_IIII_8888: internalformat = GL_RGBA; format = GL_RGBA; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::D_I_16: internalformat = GL_LUMINANCE; format = GL_LUMINANCE; type = GL_UNSIGNED_SHORT; break; default: // unknown type! abort(); } glTexImage2D(GL_TEXTURE_2D, 0, internalformat, frame.GetWidth(), frame.GetHeight(), 0, format, type, frame.GetData()); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glBegin(GL_QUADS); { glTexCoord2f(0, 1); glVertex2f(winReg[w][0], winReg[w][1]); glTexCoord2f(1, 1); glVertex2f(winReg[w][2], winReg[w][1]); glTexCoord2f(1, 0); glVertex2f(winReg[w][2], winReg[w][3]); glTexCoord2f(0, 0); glVertex2f(winReg[w][0], winReg[w][3]); } glEnd(); } glDisable(GL_TEXTURE_2D); frames_.clear(); return true; } bool SLAMBenchUI_Pangolin::DrawFrameOutput(slambench::outputs::BaseOutput* output) { if(!output->IsActive() or output->GetValues().empty()) { return true; } // get most recent frame output slambench::values::FrameValue *value = (slambench::values::FrameValue*)output->GetValues().rbegin()->second; EnqueueFrame(value); return true; } bool SLAMBenchUI_Pangolin::DrawFeature(slambench::values::FeatureValue* value) { glEnable(GL_DEPTH_TEST); glEnable(GL_TEXTURE_2D); glColor4f(1,1,1,1); auto tex_id = get_next_texture_id(); glBindTexture(GL_TEXTURE_2D, tex_id); glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB8, value->GetPatch().GetWidth(), value->GetPatch().GetHeight(), 0, GL_LUMINANCE, GL_UNSIGNED_BYTE, value->GetPatch().GetData()); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glBegin(GL_QUADS); const float uvs[] = {0, 0, 0, 1, 1, 1, 1, 0}; const float vertices[] = {-0.05, -0.05, 0, 0.05, -0.05, 0, 0.05, 0.05, 0, -0.05, 0.05, 0}; for(int i = 0; i < 4; ++i) { float vertex[] = {vertices[3*i], vertices[1+3*i], vertices[2+3*i]}; vertex[0] += value->GetPose()(0,1); vertex[1] += value->GetPose()(0,2); vertex[2] += value->GetPose()(0,3); glTexCoord2fv(uvs + (2*i)); glVertex3fv(vertex); } glEnd(); glDisable(GL_TEXTURE_2D); glDisable(GL_DEPTH_TEST); return true; } bool SLAMBenchUI_Pangolin::DrawList(slambench::outputs::BaseOutput* output) { if (output->Empty()) { return true; } // take the most recent list auto list_value = (slambench::values::ValueListValue*)output->GetMostRecentValue().second; auto &list = list_value->GetValue(); for(auto i : list) { switch(i->GetType()) { case slambench::values::VT_FEATURE: DrawFeature(static_cast(i)); break; default: throw std::logic_error("Unknown list type"); } } return true; } bool SLAMBenchUI_Pangolin::DrawString(slambench::outputs::BaseOutput* value) { if (value->Empty()) { return true; } auto string_value = (slambench::values::TypeForVT::type*)value->GetMostRecentValue().second; outputs_text_.at(value)->Ref().Set(string_value->GetValue()); return true; } bool SLAMBenchUI_Pangolin::DrawOutput(slambench::outputs::BaseOutput* output) { // std::cout << "Drawing an output " << output->GetType() << std::endl; if(outputs_visible_.count(output) != 0 && !outputs_visible_.at(output)->Get()) { return true; } if(!output->IsActive()) { return true; } switch(output->GetType()) { case slambench::values::VT_POSE: return DrawPoseOutput(output); case slambench::values::VT_COLOUREDPOINTCLOUD: return DrawColouredPointCloudOutput(output); case slambench::values::VT_POINTCLOUD: return DrawPointCloudOutput(output); case slambench::values::VT_FRAME: return DrawFrameOutput(output); case slambench::values::VT_LIST: return DrawList(output); case slambench::values::VT_STRING: return DrawString(output); default: return false; } } void SLAMBenchUI_Pangolin::lockOutputs() { for(auto output_mgr : GetOutputManagers()) { output_mgr.second->GetLock().lock(); } } void SLAMBenchUI_Pangolin::unlockOutputs() { for(auto output_mgr : GetOutputManagers()) { output_mgr.second->GetLock().unlock(); } } bool SLAMBenchUI_Pangolin::process(){ // std::cout << "Processing!" << std::endl; /*** * Running system */ if(CanFreeRun()) { if(freeRunning->Get() != isFreeRunning) { isFreeRunning = freeRunning->Get(); std::unique_lock lck(step_mutex); step_cv.notify_all(); } } if(CanStep()) { if(nextFrame->Ref().Get()) { nextFrame->Ref().Set(false); std::unique_lock lck(step_mutex); step_cv.notify_all(); } } for(auto output : outputs_enabled_) { bool should_be_active = output.second->Get(); if(should_be_active != output.first->IsActive()) { lockOutputs(); output.first->SetActive(should_be_active); unlockOutputs(); } } { // Update aspect ratio of display to match that of the window auto &display = pangolin::Display("cam"); double aspect = (double)(pangolin::DisplayBase().v.w-360) / pangolin::DisplayBase().v.h; display.SetAspect(aspect); } // Move to BIG screen // ******************** pangolin::Display("cam").Activate(s_cam); // Draw blue background // ******************** glClearColor(0.05, 0.05, 0.3, 0.0f); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); FollowPoses(); DrawBackgrounds(); for(auto output_mgr : GetOutputManagers()) { std::lock_guard lock(output_mgr.second->GetLock()); (void)lock; // I hate that werror so much for(auto output : *output_mgr.second) { DrawOutput(output.second); } } DrawQueuedFrames(); DrawAxis(); this->postCall(); return true; }; void SLAMBenchUI_Pangolin::DrawAxis() { glMatrixMode(GL_PROJECTION); glPushMatrix(); glLoadIdentity(); glMatrixMode(GL_MODELVIEW); glPushMatrix(); glLoadIdentity(); auto mat = s_cam.GetModelViewMatrix(); mat.m[12] = -0.85; mat.m[13] = 0.85; mat.m[14] = -0.5; mat.m[15] = 1; mat.Multiply(); glBegin(GL_LINES); glColor3f(1,0.5,0.5); glVertex3f(0, 0, 0); glVertex3f(0.1, 0, 0); glColor3f(0.5,1,0.5); glVertex3f(0, 0, 0); glVertex3f(0, 0.1, 0); glColor3f(0.5,0.5,1); glVertex3f(0, 0, 0); glVertex3f(0, 0, 0.1); glEnd(); glPopMatrix(); glMatrixMode(GL_PROJECTION); glPopMatrix(); } unsigned int SLAMBenchUI_Pangolin::get_next_texture_id() { if(next_feature_texture_id_idx == feature_texture_ids.size()) { uint texture_id; glGenTextures(1, &texture_id); feature_texture_ids.push_back(texture_id); } return feature_texture_ids.at(next_feature_texture_id_idx++); } void SLAMBenchUI_Pangolin::drawBackground(slambench::values::FrameValue * frame) { glBindTexture(GL_TEXTURE_2D, textureId[0]); glColor3f(1.0,1.0,1.0); glEnable(GL_TEXTURE_2D); glDisable(GL_DEPTH_TEST); glMatrixMode(GL_PROJECTION); glPushMatrix(); glLoadIdentity(); glMatrixMode(GL_MODELVIEW); glPushMatrix(); glLoadIdentity(); glOrtho( 0, 1, 0, 1, -1, 1 ); GLint format, type, internalformat; switch(frame->GetFormat()) { case slambench::io::pixelformat::G_I_8: case slambench::io::pixelformat::D_I_8: internalformat = GL_RGBA; format = GL_LUMINANCE; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::RGB_III_888: internalformat = GL_RGB; format = GL_RGB; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::RGBA_IIII_8888: internalformat = GL_RGBA; format = GL_RGBA; type = GL_UNSIGNED_BYTE; break; case slambench::io::pixelformat::D_I_16: internalformat = GL_LUMINANCE; format = GL_LUMINANCE; type = GL_UNSIGNED_SHORT; break; default: // unknown type! abort(); } glTexImage2D(GL_TEXTURE_2D, 0, internalformat, frame->GetWidth(), frame->GetHeight(), 0, format, type, frame->GetData()); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); glBegin( GL_QUADS ); { glTexCoord2f(0,1); glVertex2f(0.0f, 0.0f); glTexCoord2f(1,1); glVertex2f(1, 0.0f); glTexCoord2f(1,0); glVertex2f(1, 1); glTexCoord2f(0,0); glVertex2f(0.0f, 1); } glEnd(); glPopMatrix(); glMatrixMode(GL_PROJECTION); glPopMatrix(); glMatrixMode(GL_MODELVIEW); glEnable(GL_DEPTH_TEST); glDisable(GL_TEXTURE_2D); } void SLAMBenchUI_Pangolin::drawTrajectory(const slambench::outputs::TrajectoryInterface *trajectory, float R , float G, float B , int print_poses) { glPushMatrix(); glColor3f(R, G, B); glBegin(GL_LINES); bool first = true; auto traj = trajectory->GetAll(); if(traj.empty()) { return; } for(auto &point : traj) { const auto &mat = point.second.GetValue(); if (first) { glVertex3f(mat(0,3),mat(1,3),mat(2,3)); first = false; } glVertex3f(mat(0,3),mat(1,3),mat(2,3)); glVertex3f(mat(0,3),mat(1,3),mat(2,3)); } glEnd(); glPopMatrix(); int print_me = 0; int frequency = print_poses ; //std::cout << "frequency =" << frequency < frequency) {print_me = 0;} else {continue;} Eigen::Matrix4f matfrtu = point.second.GetValue(); matfrtu.block<3,1>(0,0) = matfrtu.block<3,1>(0,0) / (matfrtu.block<3,1>(0,0)).norm(); matfrtu.block<3,1>(0,1) = matfrtu.block<3,1>(0,1) / (matfrtu.block<3,1>(0,1)).norm(); matfrtu.block<3,1>(0,2) = matfrtu.block<3,1>(0,2) / (matfrtu.block<3,1>(0,2)).norm(); this->drawFrustum( matfrtu, R,G,B); } Eigen::Matrix4f matfrtu = traj.rbegin()->second.GetValue(); matfrtu.block<3,1>(0,0) = matfrtu.block<3,1>(0,0) / (matfrtu.block<3,1>(0,0)).norm(); matfrtu.block<3,1>(0,1) = matfrtu.block<3,1>(0,1) / (matfrtu.block<3,1>(0,1)).norm(); matfrtu.block<3,1>(0,2) = matfrtu.block<3,1>(0,2) / (matfrtu.block<3,1>(0,2)).norm(); this->drawFrustum( matfrtu, R,G,B); } void SLAMBenchUI_Pangolin::FollowPose(Eigen::Matrix4f currPose ) { pangolin::OpenGlMatrix mv; Eigen::Matrix3f currRot = currPose.topLeftCorner(3, 3); Eigen::Quaternionf currQuat(currRot); Eigen::Vector3f forwardVector(0, 0, 1); Eigen::Vector3f upVector(0, -1, 0); // Flip cloud ? Eigen::Vector3f forward = (currQuat * forwardVector).normalized(); Eigen::Vector3f up = (currQuat * upVector).normalized(); Eigen::Vector3f eye(currPose(0, 3), currPose(1, 3), currPose(2, 3)); Eigen::Vector3f at = eye + forward; Eigen::Vector3f z = (eye - at).normalized(); // Forward Eigen::Vector3f x = up.cross(z).normalized(); // Right Eigen::Vector3f y = z.cross(x); Eigen::Matrix4d m; m << x(0), x(1), x(2), -(x.dot(eye)), y(0), y(1), y(2), -(y.dot(eye)), z(0), z(1), z(2), -(z.dot(eye)), 0, 0, 0, 1; memcpy(&mv.m[0], m.data(), sizeof(Eigen::Matrix4d)); s_cam.SetModelViewMatrix(mv); } void SLAMBenchUI_Pangolin::drawFrustum(Eigen::Matrix4f currPose, float R , float G, float B) { glPushMatrix(); glMultMatrixf((GLfloat*) currPose.data()); glColor3f(R, G, B); glBegin(GL_LINES); glVertex3f(0, 0, 0); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glVertex3f(0, 0, 0); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0, 0, 0); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0, 0, 0); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (height - 1 - cy) / fy, 0.05); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glVertex3f(0.05 * (0 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glVertex3f(0.05 * (width - 1 - cx) / fx, 0.05 * (0 - cy) / fy, 0.05); glEnd(); glBegin(GL_LINES); glVertex3f(0,0,0); glVertex3f(0,-0.05,0); glVertex3f(0.02,-0.03,0); glVertex3f(0, -0.05,0); glVertex3f(-0.02,-0.03,0); glVertex3f(0, -0.05,0); glEnd(); glPopMatrix(); } void SLAMBenchUI_Pangolin::postCall() { struct sysinfo memInfo; sysinfo (&memInfo); long long totalVirtualMem = memInfo.totalram; //Add other values in next statement to avoid int overflow on right hand side... totalVirtualMem += memInfo.totalswap; totalVirtualMem *= memInfo.mem_unit; long long virtualMemUsed = memInfo.totalram - memInfo.freeram; //Add other values in next statement to avoid int overflow on right hand side... virtualMemUsed += memInfo.totalswap - memInfo.freeswap; virtualMemUsed *= memInfo.mem_unit; long long totalPhysMem = memInfo.totalram; //Multiply in next statement to avoid int overflow on right hand side... totalPhysMem *= memInfo.mem_unit; long long physMemUsed = memInfo.totalram - memInfo.freeram; //Multiply in next statement to avoid int overflow on right hand side... physMemUsed *= memInfo.mem_unit; VRSS->operator=(getValueVmRSS()/ 1000); VSIZE->operator=(getValueVmSize()/ 1000); TVM->operator=(totalVirtualMem / 1000000); CVM->operator=(virtualMemUsed / 1000000 ); TPM->operator=(totalPhysMem / 1000000 ); CPM->operator=(physMemUsed / 1000000 ); frameCount->operator=(this->frame); pangolin::FinishFrame(); glFinish(); } ================================================ FILE: framework/shared/src/dummy_library.cpp ================================================ /* Copyright (c) 2014 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include bool sb_new_slam_configuration(SLAMBenchLibraryHelper * slam_settings) { return false; } bool sb_init_slam_system(SLAMBenchLibraryHelper * slam_settings) { return false; } bool sb_update_frame (SLAMBenchLibraryHelper * , slambench::io::SLAMFrame* s) { return false; } bool sb_process_once (SLAMBenchLibraryHelper * slam_settings) { return false; } bool sb_clean_slam_system() { return false; } bool sb_update_outputs(SLAMBenchLibraryHelper *lib, const slambench::TimeStamp *timestamp) { return false; } ================================================ FILE: framework/shared/src/io/FrameBuffer.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/FrameBuffer.h" #include #include using namespace slambench::io; FrameBuffer::FrameBuffer() : lock_(false), size_(0), data_(nullptr) { } FrameBuffer::~FrameBuffer() { // This is dangerous if the frame buffer hasn't been released if(data_) { free(data_); } } void FrameBuffer::Acquire() { if(lock_.exchange(true)) { throw std::logic_error("FrameBuffer is already locked"); } } bool FrameBuffer::TryAcquire() { if(lock_.exchange(true)) return false; return true; } void FrameBuffer::Release() { lock_ = false; } void FrameBuffer::ResetBuffer() { if(data_) { free(data_); data_ = malloc(0); } } bool FrameBuffer::Busy() { return lock_; } bool FrameBuffer::Reserve(size_t new_size) { if(new_size > size_) { size_ = new_size; } if(data_) { data_ = realloc(data_, size_); if(data_ == nullptr) return false; } return true; } void *FrameBuffer::Data() { if(data_ == nullptr) { data_ = malloc(size_); } return data_; } ================================================ FILE: framework/shared/src/io/FrameBufferSource.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/FrameBufferSource.h" using namespace slambench::io; FrameBuffer *SingleFrameBufferSource::Next() { return &fb_; } ================================================ FILE: framework/shared/src/io/FrameFormat.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/FrameFormat.h" #include using namespace slambench::io; static std::map formats = { {"raster", frameformat::Raster}, {"jpeg", frameformat::JPEG}, {"png", frameformat::PNG} }; frameformat::EFrameFormat frameformat::Parse(const std::string& str) { if(formats.count(str)) { return formats.at(str); } return frameformat::UNKNOWN; } ================================================ FILE: framework/shared/src/io/FrameSource.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/FrameSource.h" #include "io/SLAMFrame.h" #include "io/sensor/Sensor.h" #include #include using namespace slambench::io; FrameCollectionStream::FrameCollectionStream(FrameCollection& base_collection) : collection_(base_collection), index_(0) {} SLAMFrame* FrameCollectionStream::GetNextFrame() { if(!HasNextFrame()) { return nullptr; } return collection_.GetFrame(index_++); } bool FrameCollectionStream::HasNextFrame() { return index_ < collection_.GetFrameCount(); } GTBufferingFrameStream::GTFrameCollection::GTFrameCollection(GTBufferingFrameStream& gt_stream) : gt_stream_(gt_stream) {} SLAMFrame* GTBufferingFrameStream::GTFrameCollection::GetFrame(unsigned int index) { return gt_stream_.gt_frames_.at(index); } SLAMFrame* GTBufferingFrameStream::GTFrameCollection::GetClosestFrameToTime(const slambench::TimeStamp& ts) { auto frame = std::lower_bound(gt_stream_.gt_frames_.begin(), gt_stream_.gt_frames_.end(), ts, [](SLAMFrame *frame, slambench::TimeStamp t){ return frame->Timestamp < t; }); if (frame == gt_stream_.gt_frames_.end()) { frame--; } else if (frame != gt_stream_.gt_frames_.begin() && (*frame)->Timestamp - ts > ts - (*(frame - 1))->Timestamp) { frame--; } return *frame; } unsigned int GTBufferingFrameStream::GTFrameCollection::GetFrameCount() { return gt_stream_.gt_frames_.size(); } GTBufferingFrameStream::GTBufferingFrameStream(FrameStream& base_stream) : base_stream_(base_stream), buffered_frame_(nullptr) { fastForward(); } SLAMFrame* GTBufferingFrameStream::GetNextFrame() { if(buffered_frame_ != nullptr) { auto frame = buffered_frame_; buffered_frame_ = nullptr; return frame; } return base_stream_.GetNextFrame(); } bool GTBufferingFrameStream::HasNextFrame() { return base_stream_.HasNextFrame() || buffered_frame_ != nullptr; } GTBufferingFrameStream::GTFrameCollection* GTBufferingFrameStream::GetGTFrames() { // TODO : memory leak here return new GTFrameCollection(*this); } void GTBufferingFrameStream::fastForward() { assert(gt_frames_.empty()); SLAMFrame *next_frame = nullptr; while(true) { if(!base_stream_.HasNextFrame()) { break; } next_frame = base_stream_.GetNextFrame(); if(next_frame == nullptr) { break; } if(!next_frame->FrameSensor->IsGroundTruth()) { break; } gt_frames_.push_back(next_frame); } buffered_frame_ = next_frame; } RealTimeFrameStream::RealTimeFrameStream(FrameStream* base_stream, double multiplier, bool should_pause) : base_stream_(base_stream), acceleration_(multiplier), should_pause_(should_pause) {} bool RealTimeFrameStream::HasNextFrame() { return base_stream_->HasNextFrame(); } SLAMFrame* RealTimeFrameStream::GetNextFrame() { SLAMFrame *frame = nullptr; do { frame = base_stream_->GetNextFrame(); if(frame) { frame->Timestamp *= acceleration_; } } while(HasNextFrame() && !is_valid_frame(frame)); if(frame) { auto now = slambench::TimeStamp::Now(); auto last_timestamp = last_frame_timestamp_[frame->FrameSensor]; auto last_realtimestamp = last_frame_realtimestamp_[frame->FrameSensor]; last_frame_timestamp_[frame->FrameSensor] = frame->Timestamp; last_frame_realtimestamp_[frame->FrameSensor] = now; // if the slam time since the last frame is greater than the real time // since the last frame, then sleep until it isn't. auto slam_time_since_last_frame = frame->Timestamp - last_timestamp; auto real_time_since_last_frame = now - last_realtimestamp; if(slam_time_since_last_frame > real_time_since_last_frame) { if(should_pause_) { slambench::Sleep(slam_time_since_last_frame - real_time_since_last_frame); } } } return frame; } bool RealTimeFrameStream::is_valid_frame(SLAMFrame* frame) const { if(frame == nullptr) { throw std::logic_error(""); } // first frame encountered for a sensor is always valid if(last_frame_timestamp_.count(frame->FrameSensor) == 0) { return true; } // frame is valid if the time between the frame and the last returned frame // is greater than the real time since the last returned frame slambench::TimeStamp last_sensor_time {0,0}; if(last_frame_timestamp_.count(frame->FrameSensor)) { last_sensor_time = last_frame_timestamp_.at(frame->FrameSensor); } slambench::TimeStamp last_sensor_realtime {0,0}; if(last_frame_realtimestamp_.count(frame->FrameSensor)) { last_sensor_realtime = last_frame_realtimestamp_.at(frame->FrameSensor); } auto time_since_last_frame = frame->Timestamp - last_sensor_time; auto realtime_since_last_frame = slambench::TimeStamp::Now() - last_sensor_realtime; return time_since_last_frame >= realtime_since_last_frame; } ================================================ FILE: framework/shared/src/io/InputInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/InputInterface.h" #include "io/SLAMFile.h" #include "io/FrameBufferSource.h" #include "io/deserialisation/SLAMFileHeaderDeserialiser.h" #include "io/deserialisation/SensorCollectionDeserialiser.h" using namespace slambench::io; InputInterface::~InputInterface() { } BasicInputInterface::BasicInputInterface(FrameStream& frames, SensorCollection& sensors) : frames_(frames), sensors_(sensors) { } FrameStream& BasicInputInterface::GetFrames() { return frames_; } SensorCollection& BasicInputInterface::GetSensors() { return sensors_; } FileInputInterface::FileInputInterface(SLAMFile& input_file) : file_(input_file), stream_(input_file) { } FrameStream& FileInputInterface::GetFrames() { return stream_; } SensorCollection& FileInputInterface::GetSensors() { return file_.Sensors; } FileStreamInputInterface::FileStreamInputInterface(FILE* input_file, FrameBufferSource *fb_source) : deserialiser_(input_file, sensors_, fb_source) { // deserialise header and sensors if (input_file == nullptr) { throw std::exception(); } SLAMFileHeaderDeserialiser hdr(input_file); if(!hdr.Deserialise()) { throw std::exception(); } SensorCollectionDeserialiser scd(input_file); if(!scd.Deserialise(sensors_)) { throw std::exception(); } } FrameStream& FileStreamInputInterface::GetFrames() { return deserialiser_; } SensorCollection& FileStreamInputInterface::GetSensors() { return sensors_; } ================================================ FILE: framework/shared/src/io/InputInterfaceManager.cpp ================================================ /* Copyright (c) 2020 University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include using namespace slambench::io; InputInterfaceManager::InputInterfaceManager(const std::vector & dataset_filenames) { #ifdef DO_OPENNI20 if (dataset_filenames[0] == "oni2") { std::cerr << "Load OpenNI 2 interface ..." << std::endl; input_interfaces_.push_back(new slambench::io::openni2::ONI2InputInterface()); return; } #endif #ifdef DO_OPENNI15 if (dataset_filenames[0] == "oni15") { std::cerr << "Load OpenNI 1.5 interface ..." << std::endl; input_interfaces_.push_back(new slambench::io::openni15::ONI15InputInterface()); return; } #endif #ifdef DO_REALSENSE if (dataset_filenames[0] == "realsense") { std::cerr << "Load RealSense interface ..." << std::endl; auto interface = new slambench::io::realsense::RealSense2InputInterface(); input_interfaces_.push_back(interface); input_stream_ = &interface->GetStream(); return; } #endif // TODO: Handle other types of interface // TODO: Add a getFrameStream in Config to handle that // TODO: config will be aware of sensors and then sensors will be able to add there arguments for(const auto &filename : dataset_filenames) { FILE *input_desc = fopen(filename.c_str(), "r"); if (input_desc == nullptr) { throw std::logic_error("Could not open the input file"); } auto input_ref = new slambench::io::FileStreamInputInterface(input_desc, new slambench::io::SingleFrameBufferSource()); input_interfaces_.push_back(input_ref); ////workaround to be compatible with benchmarks that does not implement sensors resetting. ////assume different input_interface_manager_ has exactly the same types of sensors. ////If sensors are different, may introduce problems. // FIXME: this works for a single library but doesn't work for more than that. Should be moved inside each library } first_sensors_ = &GetCurrentInputInterface()->GetSensors(); } InputInterfaceManager::~InputInterfaceManager() { for(auto interface : input_interfaces_) delete interface; if(first_sensors_) delete first_sensors_; if(input_stream_) delete input_stream_; } InputInterface* InputInterfaceManager::GetCurrentInputInterface() { if(input_interfaces_.empty()) { throw std::logic_error("Input interface has not been added to SLAM configuration"); } return input_interfaces_.front(); } SLAMFrame* InputInterfaceManager::GetNextFrame() const { if (input_stream_ == nullptr || !input_stream_->HasNextFrame()) { std::cerr << "No input loaded." << std::endl; return nullptr; } return input_stream_->GetNextFrame(); } SLAMFrame* InputInterfaceManager::GetClosestGTFrameToTime(slambench::TimeStamp& ts) const { return dynamic_cast(input_stream_)->GetGTFrames()->GetClosestFrameToTime(ts); } bool InputInterfaceManager::LoadNextInputInterface() { input_interfaces_.pop_front(); delete input_stream_; if(input_interfaces_.empty()) return false; updated_ = true; GetCurrentInputInterface()->GetSensors() = *first_sensors_; return true; } ================================================ FILE: framework/shared/src/io/PixelFormat.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/PixelFormat.h" #include #include using namespace slambench::io; static std::map formats = { {"G_I_8", pixelformat::G_I_8}, {"RGB_III_888", pixelformat::RGB_III_888}, {"RGBA_IIII_8888", pixelformat::RGBA_IIII_8888}, {"D_I_8", pixelformat::D_I_8}, {"D_I_16", pixelformat::D_I_16}, {"D_F_32", pixelformat::D_F_32}, {"D_F_64", pixelformat::D_F_64} }; static std::map reverse_formats_; std::map &GetReverseFormats() { if(reverse_formats_.empty()) { for(auto i : formats) { reverse_formats_[i.second] = i.first; } } return reverse_formats_; } pixelformat::EPixelFormat pixelformat::Parse(const std::string& fmt) { if(formats.count(fmt)) { return formats.at(fmt); } else { return pixelformat::UNKNOWN; } } std::string pixelformat::TypeOf(pixelformat::EPixelFormat format) { using namespace pixelformat; switch(format) { case UNKNOWN: return "UNKNOWN"; case G_I_8: return "grey"; case RGB_III_888: case RGBA_IIII_8888: return "rgb"; case D_I_8: case D_I_16: case D_F_32: case D_F_64: return "depth"; default: return "???"; } } size_t pixelformat::GetPixelSize(pixelformat::EPixelFormat format) { using namespace pixelformat; switch(format) { case G_I_8 : return 1; case RGB_III_888 : return 3; case RGBA_IIII_8888 : return 4; case D_I_8 : return 1; case D_F_32 : return 4; case D_I_16 : return 2; case D_F_64 : return 8; default: assert(false); return 0; } } bool pixelformat::IsRGB(pixelformat::EPixelFormat format) { using namespace pixelformat; switch(format) { case RGB_III_888: case RGBA_IIII_8888: return true; default: return false; } } bool pixelformat::IsGrey(pixelformat::EPixelFormat format) { using namespace pixelformat; switch(format) { case G_I_8: return true; default: return false; } } ================================================ FILE: framework/shared/src/io/SLAMFile.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/SLAMFile.h" #include "io/deserialisation/SLAMFileDeserialiser.h" #include "io/serialisation/SLAMFileSerialiser.h" #include "io/FrameBufferSource.h" #include "io/sensor/Sensor.h" #include "io/SLAMFrame.h" #include using namespace slambench::io; const SLAMFile::magic_num_t SLAMFile::MagicNum = "SLAM"; SLAMFrame* SLAMFile::GetFrame(unsigned int index) { return frames_.at(index); } unsigned int SLAMFile::GetFrameCount() { return frames_.size(); } void SLAMFile::AddFrame(SLAMFrame* frame) { // Order ground truth frames before regular frames if(frame->FrameSensor->IsGroundTruth()) { AddGroundTruthFrame(frame); } else { AddRegularFrame(frame); } } void SLAMFile::AddRegularFrame(SLAMFrame *frame) { assert(!frame->FrameSensor->IsGroundTruth()); // Place frame in correct place given the timestamp for (auto it = frames_.begin() ; it != frames_.end() ; it++) { if((*it)->FrameSensor->IsGroundTruth()) { continue; } if ((*it)->Timestamp <= frame->Timestamp) { continue; } else {frames_.insert(it, frame);return;} } frames_.push_back(frame); } void SLAMFile::AddGroundTruthFrame(SLAMFrame* frame) { assert(frame->FrameSensor->IsGroundTruth()); for (auto it = frames_.begin() ; it != frames_.end() ; it++) { if(!(*it)->FrameSensor->IsGroundTruth()) { frames_.insert(it, frame);return; } if ((*it)->Timestamp <= frame->Timestamp) { continue; } else {frames_.insert(it, frame);return;} } frames_.push_back(frame); } Sensor* SLAMFile::GetSensor(const Sensor::sensor_type_t &type) { for(auto &i : Sensors) { if(i->GetType() == type) return i; } return nullptr; } SLAMFile* SLAMFile::Read(const std::string& filename, FrameBufferSource &fb_source) { FILE *base_file = fopen(filename.c_str(), "r"); if(!base_file) { return nullptr; } SLAMFileDeserialiser deserialiser(base_file, &fb_source); SLAMFile *file = new SLAMFile(); if(!deserialiser.Deserialise(*file)) { fclose(base_file); delete file; return nullptr; } return file; } bool SLAMFile::Write(const std::string& filename, SLAMFile& file, SLAMFileSerialiser::frame_callback_t callback) { FILE *base_file = fopen(filename.c_str(), "w"); if(!base_file) { return false; } SLAMFileSerialiser serialiser(base_file); serialiser.FrameCallback = callback; if(!serialiser.Serialise(file)) { fclose(base_file); return false; } fclose(base_file); return true; } ================================================ FILE: framework/shared/src/io/SLAMFrame.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/FrameBuffer.h" #include "io/SLAMFrame.h" #include "io/sensor/Sensor.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "lodepng.h" #include "io/sensor/AccelerometerSensor.h" #include "io/core/Core.h" #include #include #include #include #include #include using namespace slambench::io; SLAMFrame::~SLAMFrame() {} size_t SLAMFrame::GetSize() const { if(FrameSensor->IsVariableSize()) { return size_if_variable_sized_; } else { return FrameSensor->GetFrameSize(this); } } void SLAMFrame::SetVariableSize(uint32_t size) { assert(FrameSensor->IsVariableSize()); size_if_variable_sized_ = size; } uint32_t SLAMFrame::GetVariableSize() const { assert(FrameSensor->IsVariableSize()); return size_if_variable_sized_; } void *SLAMInMemoryFrame::GetData() { return Data; } void SLAMInMemoryFrame::FreeData() { // do nothing } SLAMFileFrame::SLAMFileFrame() : ProcessCallback(nullptr) {} void *SLAMFileFrame::GetData() { if(data_ != nullptr) return data_; data_ = LoadFile(); if(ProcessCallback != nullptr) { ProcessCallback(this, (void*)data_); } return data_; } void SLAMFileFrame::FreeData() { free(data_); data_ = nullptr; } void *TxtFileFrame::LoadFile() { // Figure out the underlying data type to load const Sensor::sensor_type_t &type = FrameSensor->GetType(); if(type == CameraSensor::kCameraType || type == DepthSensor::kDepthType) { return LoadCameraFile(); } else { return nullptr; } } template bool ParseElem(const std::string &str, DType &result); template<> bool ParseElem(const std::string &str, float &result) { if(str.size() == 0) return false; for(auto c : str) { if(!(isdigit(c) || c == '.' || c == 'e' || c == '+')) { return false; } } result = strtof(str.c_str(), nullptr); return true; } template<> bool ParseElem(const std::string &str, double &result) { if(str.size() == 0) return false; for(auto c : str) { if(!(isdigit(c) || c == '.' || c == 'e' || c == '+')) { return false; } } result = strtod(str.c_str(), nullptr); return true; } template<> bool ParseElem(const std::string &str, unsigned char &result) { if(str.size() == 0) return false; for(auto c : str) { if(!isdigit(c)) return false; } result = strtol(str.c_str(), nullptr, 10); return true; } template std::vector ParseFile(std::ifstream &str) { std::vector data; std::string curr_string; while(str.good() && !str.eof()) { char c = str.get(); if(isdigit(c) || c == '.' || c == 'e' || c == '+') { curr_string += c; } else { DType value; if(ParseElem(curr_string, value)) { data.push_back(value); } curr_string = ""; } } return data; } template void *LoadData(const std::string &filename, int count_per_pxl, int pixels) { std::ifstream str (filename.c_str()); if(!str.good()) { throw std::logic_error("Failed to load data file"); } DType *data = new DType[pixels * count_per_pxl]; std::vector values = ParseFile(str); size_t elem_count = count_per_pxl * pixels; if(values.size() < elem_count) { delete [] data; std::cerr << "File " << filename << " size mismatch " << values.size() << " < " << (elem_count) << std::endl; throw std::logic_error("File size mismatch "); } for(size_t i = 0; i < elem_count; ++i) { data[i] = values.at(i); } return data; } template void* ConvertPixels(void *input, size_t pxl_count); template<> void *ConvertPixels(void *input, size_t pxl_count) { float *pxls = (float*)input; uint16_t *outpxls = (uint16_t*)malloc(pxl_count * sizeof(uint16_t)); for(size_t i = 0; i < pxl_count; ++i) { outpxls[i] = pxls[i] * 1000; } return outpxls; } template<> void *ConvertPixels(void *input, size_t pxl_count) { double *pxls = (double*)input; uint16_t *outpxls = (uint16_t*)malloc(pxl_count * sizeof(uint16_t)); for(size_t i = 0; i < pxl_count; ++i) { outpxls[i] = pxls[i] * 1000; } return outpxls; } void *Convert(void *input, size_t count, pixelformat::EPixelFormat input_format, pixelformat::EPixelFormat output_format) { void *output = nullptr; switch(output_format) { case pixelformat::D_I_16: switch(input_format) { case pixelformat::D_F_32: output = ConvertPixels(input, count); break; case pixelformat::D_F_64: output = ConvertPixels(input, count); break; default: assert(false); } break; default: assert(false); } return output; } void *TxtFileFrame::LoadCameraFile() { CameraSensor *camera = (CameraSensor*)FrameSensor; void *data = nullptr; auto frame_size = camera->Width * camera->Height; switch(input_pixel_format) { case pixelformat::G_I_8: data = LoadData(filename, 1, frame_size); break; case pixelformat::RGB_III_888: data = LoadData(filename, 3, frame_size); break; case pixelformat::D_I_8: data = LoadData(filename, 1, frame_size); break; case pixelformat::D_F_32: data = LoadData(filename, 1, frame_size); break; case pixelformat::D_F_64: data = LoadData(filename, 1, frame_size); break; case pixelformat::D_I_16: data = LoadData(filename, 1, frame_size); break; default: assert(false); } if(camera->PixelFormat != input_pixel_format) { void *newdata = Convert(data, frame_size, input_pixel_format, camera->PixelFormat); free(data); data = newdata; } return data; } DeserialisedFrame::DeserialisedFrame(FrameBuffer &buffer, FILE *file) : buffer_(buffer), file_(file), offset_(0) { } void DeserialisedFrame::SetOffset(size_t new_offset) { offset_ = new_offset; } void *DeserialisedFrame::GetData() { unsigned long size = GetSize(); buffer_.Acquire(); buffer_.Reserve(size); fseeko(file_, offset_, SEEK_SET); fread(buffer_.Data(), size, 1, file_); // TODO : Check return value of fread return buffer_.Data(); } void DeserialisedFrame::FreeData() { buffer_.Release(); buffer_.ResetBuffer(); } void* ImageFileFrame::LoadFile() { // get file extension std::string ext = filename.substr(filename.size() - 3, 3); if(ext == "png") return LoadPng(); else if(ext == "pgm") return LoadPbm(); else throw std::logic_error("Unrecognized file type"); } void* ImageFileFrame::LoadPbm() { CameraSensor *camera = nullptr; auto &type = FrameSensor->GetType(); if(type == CameraSensor::kCameraType || type == DepthSensor::kDepthType) { camera = (CameraSensor*)FrameSensor; } else { std::cerr << "Sensor type is " << FrameSensor->GetType() << std::endl; throw std::logic_error("Unrecognized sensor type"); } std::ifstream file(filename.c_str()); std::string mnum, size, max; std::getline(file, mnum); std::getline(file, size); std::getline(file, max); // only support p5 for now if(mnum.compare("P5")) { return nullptr; } // don't support max scaling for now if(max.compare("255")) { return nullptr; } char *orig_ptr = strdup(size.c_str()); char *ptr = orig_ptr; unsigned int size_x = strtol(ptr, &ptr, 10); unsigned int size_y = strtol(ptr, &ptr, 10); if(size_x != camera->Width || size_y != camera->Height) { throw std::runtime_error(""); } char *data = (char*)malloc(size_x * size_y); file.read(data, size_x * size_y); free(orig_ptr); return data; } void* ImageFileFrame::LoadPng() { Sensor *sensor = nullptr; auto &type = FrameSensor->GetType(); if(type == CameraSensor::kCameraType || type == DepthSensor::kDepthType) { sensor = (CameraSensor*)FrameSensor; } else { std::cerr << "Sensor type is " << FrameSensor->GetType() << std::endl; throw std::logic_error("Unrecognized sensor type"); } // BUG! A DepthSensor is not a CameraSensor!!!!!!! //CameraSensor *camera = dynamic_cast(sensor); CameraSensor *camera = (CameraSensor*)(sensor); if(camera == nullptr) { throw std::logic_error("Cannot instantiate an image for something which isn't a camera"); } std::vector pixels; unsigned width, height; auto mappedfile = core::ReadFile(filename); char *outdata; switch(camera->PixelFormat) { // Generic case when reading RGB from a PNG file case pixelformat::RGB_III_888: { if (lodepng::decode(pixels, width, height, (const unsigned char*)mappedfile.Get(), mappedfile.Size(), LCT_RGB, 8)) { throw std::logic_error("Failed to decode png"); } if(width != camera->Width || height != camera->Height) { throw std::logic_error("PNG width does not match sensor width"); } if(pixels.size() != FrameSensor->GetFrameSize(this)) { throw std::logic_error("Decoded png does not match expected frame size"); } outdata = (char*)malloc(FrameSensor->GetFrameSize(this)); memcpy(outdata, pixels.data(), FrameSensor->GetFrameSize(this)); break; } // Generic case when reading a Grey scale image from a PNG case pixelformat::G_I_8: { if (lodepng::decode(pixels, width, height, (const unsigned char*)mappedfile.Get(), mappedfile.Size(), LCT_RGB, 8)) { throw std::logic_error("Failed to decode png"); } if(width != camera->Width || height != camera->Height) { throw std::logic_error("PNG width does not match sensor width"); } outdata = (char*)malloc(FrameSensor->GetFrameSize(this)); // convert rgb to greyscale for(size_t idx = 0; idx < camera->Width * camera->Height; ++idx) { uint32_t total = pixels[3*idx] + pixels[(3*idx) + 1] + pixels[(3*idx) + 2]; total /= 3; outdata[idx] = total; } break; } // Special case when reading depth from a TUM PNG case pixelformat::D_I_16: { lodepng::State state = lodepng::State(); state.decoder.color_convert = false; if (lodepng::decode(pixels, width, height, state, (const unsigned char*)mappedfile.Get(), mappedfile.Size())) { throw std::logic_error("Failed to decode png"); } if(width != camera->Width || height != camera->Height) { throw std::logic_error("PNG width does not match sensor width"); } if(width * height * 2 != pixels.size()) { throw std::logic_error("Got an unexpected number of pixels"); } outdata = (char*)malloc(FrameSensor->GetFrameSize(this)); //Extract the 16bit value, bigendian format (png method for multibyte) // Divide by 5: 5000 units = 1m (scene2raw does *1000). int k = 0; for(unsigned y = 0; y < height; y++) { for (unsigned x = 0; x < width; x++) { size_t index = y * width * 2 + x * 2; int r = pixels[index + 0] * 256 + pixels[index + 1]; ((uint16_t*)outdata)[k++] = r; } } break; } default: { std::cerr << "Pixel format is " << camera->PixelFormat << std::endl; throw std::logic_error("Unsupported pixel format"); break; } } if (outdata == nullptr) { throw std::logic_error("Should never happend"); } return outdata; } ================================================ FILE: framework/shared/src/io/core/Core.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/core/Core.h" using namespace slambench::io::core; size_t slambench::io::core::FileSize(FILE *file) { struct stat st; fstat(fileno(file), &st); return st.st_size; } MappedFile::MappedFile(void* mapped_ptr, size_t size) : ptr_(mapped_ptr), size_(size) { } MappedFile::MappedFile(MappedFile&& other) : ptr_(other.ptr_), size_(other.size_) { other.ptr_ = nullptr; } MappedFile::~MappedFile() { if (ptr_) { munmap(ptr_, size_); } } MappedFile slambench::io::core::ReadFile(const std::string &filename) { FILE *file = fopen(filename.c_str(), "r"); size_t size = FileSize(file); void *data = mmap(nullptr, size, PROT_READ, MAP_PRIVATE, fileno(file), 0); if(data == MAP_FAILED) { throw std::logic_error(""); } fclose(file); return MappedFile(data, size); } ================================================ FILE: framework/shared/src/io/deserialisation/Deserialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/deserialisation/Deserialiser.h" using namespace slambench::io; Deserialiser::Deserialiser(FILE *file) : target_file_(file) {} FILE *Deserialiser::File() const { return target_file_; } bool Deserialiser::Read(void *target, size_t bytes) const { return fread(target, bytes, 1, File()) == 1; } bool Deserialiser::Skip(size_t bytes) const { fseek(File(), bytes, SEEK_CUR); return true; } size_t Deserialiser::Offset() const { return ftello(File()); } bool Deserialiser::Good() const { return feof(File()) == 0; } ================================================ FILE: framework/shared/src/io/deserialisation/SLAMFileDeserialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/deserialisation/SLAMFileDeserialiser.h" #include "io/deserialisation/SLAMFileHeaderDeserialiser.h" #include "io/deserialisation/SensorCollectionDeserialiser.h" #include "io/FrameBuffer.h" #include "io/FrameBufferSource.h" #include "io/SLAMFile.h" #include "io/SLAMFrame.h" #include "io/sensor/Sensor.h" using namespace slambench::io; SLAMFileDeserialiser::SLAMFileDeserialiser(FILE *file, FrameBufferSource *fb_source) : Deserialiser(file), fb_source_(fb_source) { } bool SLAMFileDeserialiser::Deserialise(SLAMFile &target) const { if(!DeserialiseHeader(target)) return false; if(!DeserialiseFrames(target)) return false; return true; } bool SLAMFileDeserialiser::DeserialiseHeader(SLAMFile &target) const { SLAMFileHeaderDeserialiser d(File()); if(!d.Deserialise()) { return false; } SensorCollectionDeserialiser sensor_deserialiser(File()); if(!sensor_deserialiser.Deserialise(target.Sensors)) { return false; } return true; } bool SLAMFileDeserialiser::DeserialiseFrames(SLAMFile &target) const { SLAMFrame *frame; while(DeserialiseFrame(target, frame)) { target.AddFrame(frame); } return true; } bool SLAMFileDeserialiser::DeserialiseFrame(SLAMFile &file, SLAMFrame *&target) const { DeserialisedFrame *dsf = new DeserialisedFrame(*GetNextFramebuffer(), File()); if(!Read(&dsf->Timestamp, sizeof(dsf->Timestamp))) { delete dsf; return false; } uint8_t sensor_index = 0; Read(&sensor_index, sizeof(sensor_index)); dsf->FrameSensor = &file.Sensors.at(sensor_index); if(dsf->FrameSensor->IsVariableSize()) { uint32_t framesize; Read(&framesize, sizeof(framesize)); dsf->SetVariableSize(framesize); } dsf->SetOffset(Offset()); Skip(dsf->FrameSensor->GetFrameSize(dsf)); target = dsf; return true; } FrameBuffer *SLAMFileDeserialiser::GetNextFramebuffer() const { return fb_source_->Next(); } ================================================ FILE: framework/shared/src/io/deserialisation/SLAMFileHeaderDeserialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/deserialisation/SLAMFileHeaderDeserialiser.h" #include "io/SLAMFile.h" #include "io/sensor/Sensor.h" #include "io/SensorType.h" #include "io/sensor/SensorDatabase.h" #include #include "io/sensor/GroundTruthSensor.h" #include "io/deserialisation/SensorCollectionDeserialiser.h" using namespace slambench::io; SLAMFileHeaderDeserialiser::SLAMFileHeaderDeserialiser(FILE *file) : Deserialiser(file) { } bool SLAMFileHeaderDeserialiser::Deserialise() { // check magic number SLAMFile::magic_num_t mnum; if(!Read(mnum, sizeof(mnum))) { fprintf(stderr, "Read failed\n"); return false; } if(strcmp(mnum, SLAMFile::MagicNum) != 0) { fprintf(stderr, "SLAM file does not have correct magic number (expected %s, got %c%c%c%c)\n", SLAMFile::MagicNum, mnum[0],mnum[1],mnum[2],mnum[3]); return false; } SLAMFile::version_t version; Read(&version, sizeof(SLAMFile::version_t)); if(version != SLAMFile::Version) { fprintf(stderr, "SLAM file is not correct version (expected %u, got %u)\n", SLAMFile::Version, version); return false; } return true; } ================================================ FILE: framework/shared/src/io/deserialisation/SLAMFrameDeserialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/deserialisation/SLAMFrameDeserialiser.h" #include "io/FrameBufferSource.h" #include "io/SLAMFrame.h" #include "io/sensor/SensorCollection.h" #include "io/sensor/Sensor.h" #include "io/deserialisation/SLAMFileHeaderDeserialiser.h" using namespace slambench::io; SLAMFrameDeserialiser::SLAMFrameDeserialiser(FILE* file, SensorCollection& sensors, FrameBufferSource *fb_source) : Deserialiser(file), sensors_(sensors), fb_source_(fb_source) { } SLAMFrame* SLAMFrameDeserialiser::GetNextFrame() { DeserialisedFrame *dsf = new DeserialisedFrame(*fb_source_->Next(), File()); if(!Read(&dsf->Timestamp, sizeof(dsf->Timestamp))) { delete dsf; return nullptr; } uint8_t sensor_index = 0; if (!Read(&sensor_index, sizeof(sensor_index))) { printf("Could not read sensor data"); delete dsf; return nullptr; } if (sensor_index >= sensors_.size()) { printf("Invalid sensor index (%d), max value is (%d).", sensor_index, sensors_.size() - 1 ); delete dsf; return nullptr; } dsf->FrameSensor = &sensors_.at(sensor_index); if(dsf->FrameSensor->IsVariableSize()) { uint32_t framesize; if (!Read(&framesize, sizeof(framesize))) { printf("Could not read frame size"); delete dsf; return nullptr; } dsf->SetVariableSize(framesize); } dsf->SetOffset(Offset()); Skip(dsf->GetSize()); return dsf; } bool SLAMFrameDeserialiser::HasNextFrame() { return Good(); } ================================================ FILE: framework/shared/src/io/deserialisation/SensorCollectionDeserialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/deserialisation/SensorCollectionDeserialiser.h" #include "io/sensor/SensorCollection.h" #include "io/sensor/SensorDatabase.h" #include "io/sensor/Sensor.h" #include using namespace slambench::io; SensorCollectionDeserialiser::SensorCollectionDeserialiser(std::FILE* _file) : Deserialiser(_file) { } bool SensorCollectionDeserialiser::Deserialise(SensorCollection& target) const { uint32_t sensor_count; Read(&sensor_count, sizeof(sensor_count)); for(uint32_t i = 0; i < sensor_count; ++i) { Sensor *sensor; if(!DeserialiseSensor(sensor)) { return false; } target.AddSensor(sensor); } return true; } bool SensorCollectionDeserialiser::DeserialiseSensor(Sensor*& sensor) const { uint8_t sensor_name_size; Read(&sensor_name_size, sizeof(sensor_name_size)); std::vector namedata(sensor_name_size); Read(namedata.data(), sensor_name_size); uint8_t sensor_type_size; Read(&sensor_type_size, sizeof(sensor_type_size)); std::vector typedata(sensor_type_size); Read(typedata.data(), sensor_type_size); auto deserialiser = SensorDatabase::Singleton()->Get(typedata.data()).GetDeserialiser(); return deserialiser->Deserialise(namedata.data(), typedata.data(), this, &sensor); } ================================================ FILE: framework/shared/src/io/format/DataFormatter.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/format/DataFormatter.h" using namespace slambench::io; DataFormatter::DataFormatter(Sensor* sensor, void* data) : data_(data), sensor_(sensor) { } ================================================ FILE: framework/shared/src/io/format/PointCloud.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/format/PointCloud.h" #include #include using namespace slambench::io; PointCloud* PointCloud::FromRaw(char* data) { uint32_t count = *(uint32_t*)data; float *fdata = (float*)(data+4); PointCloud *pc = new PointCloud(); for(uint32_t i = 0; i < count; ++i) { float x = fdata[i*3]; float y = fdata[i*3+1]; float z = fdata[i*3+2]; pc->Get().push_back(Point(x,y,z)); } return pc; } std::vector PointCloud::ToRaw() { std::vector output(4 + (Get().size() * 12)); *(uint32_t*)(output.data()) = Get().size(); float *fdata = (float*)(output.data()+4); for(uint32_t i = 0; i < Get().size(); ++i) { fdata[i*3] = Get().at(i).x; fdata[i*3+1] = Get().at(i).y; fdata[i*3+2] = Get().at(i).z; } return output; } // very basic PLY file format reader PointCloud *PlyReader::Read(std::istream &input) { // read the PLY header int point_size = 0; int point_y_offset = -1; int point_z_offset = -1; int point_x_offset = -1; int point_count = -1; boost::regex rgx ("^([^ ]+)\\s*([^ ]+)?\\s*([^ ]+)?\\s*$"); do { std::string line; std::getline(input, line); // figure out the type of line boost::cmatch cm; boost::regex_search (line.c_str(), cm, rgx); if(cm.size() == 0) { printf("Line does not match expected format\n"); printf("%s\n", line.c_str()); return nullptr; } const std::string &type = cm[1]; if(type == "ply") { printf("Found ply header\n"); // so far so good } else if(type == "format") { if(cm[2] != "binary_little_endian") { printf("Invalid format type '%s'\n", cm[2].str().c_str()); return nullptr; } if(cm[3] != "1.0") { printf("Invalid version\n"); return nullptr; } } else if(type == "element") { if(cm[2] != "vertex") { printf("Invalid element type\n"); return nullptr; } point_count = strtol(cm[3].str().c_str(), nullptr, 10); printf("Located point count\n"); } else if(type == "property") { const std::string &ptype = cm[2]; const std::string &pname = cm[3]; if(ptype == "float") { if(pname == "x") { point_x_offset = point_size; printf("Located point x\n"); } else if(pname == "y") { point_y_offset = point_size; printf("Located point y\n"); } else if(pname == "z") { point_z_offset = point_size; printf("Located point z\n"); } point_size += 4; } else if(ptype == "uchar") { point_size += 1; } else { return nullptr; } } else if(type == "end_header") { break; } else { printf("Unexpected line type '%s'\n", cm[1].str().c_str()); return nullptr; } } while(input.good()); // make sure we have read all of the important values if(point_count == -1 || point_size == 0 || point_x_offset == -1 || point_y_offset == -1 || point_z_offset == -1) { printf("Did not locate expected element types\n"); return nullptr; } // start parsing points PointCloud *pc = new PointCloud(); std::vector pointdata (point_count); for(int i = 0; i < point_count; ++i) { char *pd = pointdata.data(); // read data input.read(pd, point_size); Point p; p.x = *(float*)(pd + point_x_offset); p.y = *(float*)(pd + point_y_offset); p.z = *(float*)(pd + point_z_offset); pc->Get().push_back(p); } return pc; } void PlyWriter::Write(const PointCloud* cloud, std::ostream& file) { file << "ply" << std::endl; file << "format binary_little_endian 1.0" << std::endl; file << "element vertex " << cloud->Get().size() << std::endl; file << "property float x" << std::endl; file << "property float y" << std::endl; file << "property float z" << std::endl; file << "end_header" << std::endl; for(auto point : cloud->Get()) { struct { float x, y, z; } data; data.x = point.x; data.y = point.y; data.z = point.z; file.write((char*)&data, sizeof(data)); } } ================================================ FILE: framework/shared/src/io/openni/ONI2Frame.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni2/ONI2Frame.h" using namespace slambench::io::openni2; ONI2Frame::ONI2Frame(Sensor *sensor, const openni::VideoFrameRef& frameref) { FrameSensor = sensor; Timestamp.Ns = frameref.getTimestamp() % 1000000000; Timestamp.S = frameref.getTimestamp() / 1000000000; data_ = malloc(frameref.getDataSize()); memcpy(data_, frameref.getData(), frameref.getDataSize()); } void* ONI2Frame::GetData() { return data_; } void ONI2Frame::FreeData() { free(data_); data_ = nullptr; } ================================================ FILE: framework/shared/src/io/openni/ONI2FrameStream.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni2/ONI2FrameStream.h" #include "io/openni2/ONI2Frame.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/Sensor.h" #include #include using namespace slambench::io::openni2; using namespace slambench::io; ONI2FrameStream::ONI2FrameStream(openni::Device *device) : device_(device) {} SLAMFrame* ONI2FrameStream::GetNextFrame() { int ready_stream_idx = 0; auto status = openni::OpenNI::waitForAnyStream(streams_.data(), streams_.size(), &ready_stream_idx, openni::TIMEOUT_FOREVER); if(status != openni::STATUS_OK) { return nullptr; } else { openni::VideoFrameRef *ref = new openni::VideoFrameRef(); openni::VideoStream *ready_stream = streams_.at(ready_stream_idx); ready_stream->readFrame(ref); auto frame = new ONI2Frame(sensor_map_.at(ready_stream), *ref); delete ref; return frame; } } bool ONI2FrameStream::HasNextFrame() { for(auto &i : streams_) { if(i->isValid()) return true; } return false; } class FrameAllocator : public openni::VideoStream::FrameAllocator { public: FrameAllocator() : _ptr(malloc(0)),_size(0) {} void* allocateFrameBuffer(int size) override { if(size != _size) { _ptr = realloc(_ptr, size); _size = size; } return _ptr; } void freeFrameBuffer(void* data) override { if(data != _ptr) { throw std::logic_error("Attempted to free a pointer with the wrong allocator"); } } private: void *_ptr; int _size; }; bool ONI2FrameStream::ActivateSensor(CameraSensor* sensor) { openni::VideoStream *stream = new openni::VideoStream(); openni::SensorType sensor_type; if(sensor->GetType() == CameraSensor::kCameraType) sensor_type = openni::SENSOR_COLOR; else if(sensor->GetType() == DepthSensor::kDepthType) sensor_type = openni::SENSOR_DEPTH; else throw std::logic_error("Unrecognized sensor type"); openni::Status nRetVal = stream->create(*device_, sensor_type); if (nRetVal != openni::STATUS_OK) { printf("Failed to create %s \n", openni::OpenNI::getExtendedError()); exit(1); } openni::VideoMode vidmode; vidmode.setFps(30); openni::PixelFormat oniformat; switch(sensor->PixelFormat) { case pixelformat::RGB_III_888: oniformat = openni::PIXEL_FORMAT_RGB888; break; case pixelformat::D_I_16: oniformat = openni::PIXEL_FORMAT_DEPTH_1_MM; break; default: throw std::logic_error("Unknown pixel format"); } vidmode.setPixelFormat(oniformat); vidmode.setResolution(sensor->Width, sensor->Height); stream->setVideoMode(vidmode); stream->setMirroringEnabled(false); stream->setFrameBuffersAllocator(new FrameAllocator()); streams_.push_back(stream); sensor_map_[stream] = sensor; return true; } bool ONI2FrameStream::StartStreams() { //device_->setDepthColorSyncEnabled(false); device_->setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR); //device_->setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF); for(auto i : streams_) { std::cerr << "Start stream ... "; auto nRetVal = i->start(); if (nRetVal != openni::STATUS_OK) { std::cerr << "FAILED" << openni::OpenNI::getExtendedError()<< std::endl; exit(1); } else { std::cerr << "WORK" << std::endl; } } return true; } ================================================ FILE: framework/shared/src/io/openni/ONI2InputInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni2/ONI2InputInterface.h" #include "OpenNI.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/SensorCollection.h" #include "io/openni2/ONI2FrameStream.h" #include #include using namespace slambench::io; using namespace slambench::io::openni2; ONI2InputInterface::ONI2InputInterface() : stream_(nullptr), sensors_ready_(false) { openni::OpenNI::initialize(); device_ = new openni::Device(); openni::Status status = device_->open(openni::ANY_DEVICE); if (status == openni::STATUS_OK) { std::cout << " ** OpenNI2 Device " << device_->getDeviceInfo().getUsbProductId() << ":" << device_->getDeviceInfo().getUsbVendorId() << " " << device_->getDeviceInfo().getName() << ", " << device_->getDeviceInfo().getVendor() << std::endl; } else { std::cout << " ** OpenNI2 Error with the device Status:" ; switch (status) { case openni::STATUS_OK : std::cout << "STATUS_OK" ; break; case openni::STATUS_ERROR : std::cout << "STATUS_ERROR" ; break; case openni::STATUS_NOT_IMPLEMENTED : std::cout << "STATUS_NOT_IMPLEMENTED" ; break; case openni::STATUS_NOT_SUPPORTED : std::cout << "STATUS_NOT_SUPPORTED" ; break; case openni::STATUS_BAD_PARAMETER : std::cout << "STATUS_BAD_PARAMETER" ; break; case openni::STATUS_OUT_OF_FLOW : std::cout << "STATUS_OUT_OF_FLOW" ; break; case openni::STATUS_NO_DEVICE : std::cout << "STATUS_NO_DEVICE" ; break; case openni::STATUS_TIME_OUT : std::cout << "STATUS_TIME_OUT" ; break; } std::cout << std::endl; exit(1); } } ONI2InputInterface::ONI2InputInterface(const std::string& oni2_filename) : stream_(nullptr), sensors_ready_(false) { openni::OpenNI::initialize(); device_ = new openni::Device(); openni::Status status = device_->open(oni2_filename.c_str()); if (status != openni::STATUS_OK) { std::cout << " ** OpenNI2 Error with the device Status:" ; switch (status) { case openni::STATUS_OK : std::cout << "STATUS_OK" ; break; case openni::STATUS_ERROR : std::cout << "STATUS_ERROR" ; break; case openni::STATUS_NOT_IMPLEMENTED : std::cout << "STATUS_NOT_IMPLEMENTED" ; break; case openni::STATUS_NOT_SUPPORTED : std::cout << "STATUS_NOT_SUPPORTED" ; break; case openni::STATUS_BAD_PARAMETER : std::cout << "STATUS_BAD_PARAMETER" ; break; case openni::STATUS_OUT_OF_FLOW : std::cout << "STATUS_OUT_OF_FLOW" ; break; case openni::STATUS_NO_DEVICE : std::cout << "STATUS_NO_DEVICE" ; break; case openni::STATUS_TIME_OUT : std::cout << "STATUS_TIME_OUT" ; break; } std::cout << std::endl; exit(1); } } FrameStream& ONI2InputInterface::GetFrames() { if(stream_ == nullptr) BuildStream(); return *stream_; } SensorCollection& ONI2InputInterface::GetSensors() { BuildSensors(); return sensors_; } void ONI2InputInterface::BuildSensors() { if(sensors_ready_) return; auto depth_sensor_info = device_->getSensorInfo(openni::SENSOR_DEPTH); if(depth_sensor_info != nullptr) { // find a suitable video mode...? auto vid_mode = depth_sensor_info->getSupportedVideoModes()[0]; slambench::io::CameraSensor::intrinsics_t intrinsics; // guess the intrinsics for now std::cerr << "I'm guessing which intrinsics to use" << std::endl; intrinsics[0] = 0.751875; intrinsics[1] = 1.0; intrinsics[2] = 0.5; intrinsics[3] = 0.5; auto depth_sensor = DepthSensorBuilder() .name("Depth") .description("ONI2 Depth Sensor") .size(vid_mode.getResolutionX(), vid_mode.getResolutionY()) .pose(Eigen::Matrix4f::Identity()) .intrinsics(intrinsics) .frameFormat(frameformat::Raster) .pixelFormat(pixelformat::D_I_16) .rate(vid_mode.getFps()) //.distortion(distortion_type, distortion) //.disparity(disparity_type, disparity_params) .index(sensors_.size()) .build(); sensors_.AddSensor(depth_sensor); } auto color_sensor_info = device_->getSensorInfo(openni::SENSOR_COLOR); if(color_sensor_info != nullptr) { // find a suitable video mode...? auto vid_mode = color_sensor_info->getSupportedVideoModes()[0]; // guess the intrinsics for now slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = 0.751875; intrinsics[1] = 1.0; intrinsics[2] = 0.5; intrinsics[3] = 0.5; auto sensor = CameraSensorBuilder() .name("RGB") .description("ONI2 RGB Sensor") .rate(vid_mode.getFps()) .size(vid_mode.getResolutionX(), vid_mode.getResolutionY()) .pose(Eigen::Matrix4f::Identity()) .intrinsics(intrinsics) //.distortion(distortion_type, distortion) .frameFormat(frameformat::Raster) .pixelFormat(pixelformat::RGB_III_888) .index(sensors_.size()) .build(); sensors_.AddSensor(sensor); } sensors_ready_ = true; } void ONI2InputInterface::BuildStream() { BuildSensors(); stream_ = new ONI2FrameStream(device_); bool depth_found = false; bool rgb_found= false; for(auto *sensor : sensors_) { if(sensor->GetType() == slambench::io::CameraSensor::kCameraType) { rgb_found = true; stream_->ActivateSensor((CameraSensor*)sensor); } else if (sensor->GetType() == slambench::io::DepthSensor::kDepthType) { depth_found = true; stream_->ActivateSensor((DepthSensor*)sensor); } } assert(rgb_found and depth_found); stream_->StartStreams(); } ================================================ FILE: framework/shared/src/io/openni15/ONI15Frame.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni15/ONI15Frame.h" #include using namespace slambench::io::openni15; ONI15Frame::ONI15Frame(Sensor * sensor, const xn::OutputMetaData * md) { FrameSensor = sensor; Timestamp.Ns = md->Timestamp() % 1000000000; Timestamp.S = md->Timestamp() / 1000000000; size_t size = md->DataSize(); data_ = malloc(size); const XnUInt8* ptr = md->Data(); if (ptr) { memcpy(data_, ptr, size); } } ONI15Frame::~ONI15Frame() { FreeData(); } void* ONI15Frame::GetData() { assert(data_); return data_; } void ONI15Frame::FreeData() { free(data_); data_ = nullptr; } ================================================ FILE: framework/shared/src/io/openni15/ONI15FrameStream.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni15/ONI15FrameStream.h" #include "io/openni15/ONI15Frame.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/Sensor.h" #include #include using namespace slambench::io::openni15; using namespace slambench::io; ONI15FrameStream::ONI15FrameStream(xn::Context *context) : context_(context) { } SLAMFrame* ONI15FrameStream::GetNextFrame() { ONI15Frame *frame = nullptr; context_->WaitAnyUpdateAll(); // all frame seen, we clean them all. if (DMD_ and IMD_) { delete DMD_; DMD_ = nullptr; delete IMD_; IMD_ = nullptr; } // no Depth we give it a try if (!DMD_) { DMD_ = new xn::DepthMetaData(); depth_generator_->GetMetaData(*DMD_); if (DMD_->DataSize() == 0) { delete DMD_; DMD_ = nullptr; } else { frame = new ONI15Frame(_sensor_map.at(depth_generator_), DMD_); return frame; } } // no image we give it a try if (!IMD_) { IMD_ = new xn::ImageMetaData(); image_generator_->GetMetaData(*IMD_); if (IMD_->DataSize() == 0) { delete IMD_; IMD_ = nullptr; } else { frame = new ONI15Frame(_sensor_map.at(image_generator_), IMD_); return frame; } } // No new frame found we have a problem ! assert(false); return nullptr; } bool ONI15FrameStream::HasNextFrame() { return true; } bool ONI15FrameStream::ActivateSensor(CameraSensor* sensor) { assert(context_); if(sensor->GetType() == CameraSensor::kCameraType) { xn::ImageGenerator *stream = new xn::ImageGenerator(); if (stream->Create(*context_) != XN_STATUS_OK) { std::cout << ( "OpenNI15: Create(context_) ERROR !!!") << std::endl; return false; } image_generator_ = stream; _sensor_map[stream] = sensor; }else if(sensor->GetType() == DepthSensor::kDepthType) { xn::DepthGenerator *stream = new xn::DepthGenerator(); if (stream->Create(*context_) != XN_STATUS_OK) { std::cout << ( "OpenNI15: Create(context_) ERROR !!!") << std::endl; return false; } depth_generator_ = stream; _sensor_map[stream] = sensor; }else{ throw std::logic_error("Unrecognized sensor type"); } return true; } bool ONI15FrameStream::StartStreams() { if (context_->StartGeneratingAll() != XN_STATUS_OK) { std::cout << ( "OpenNI15 context_.StartGeneratingAll() ERROR !!!") << std::endl; return false; } return true; } ================================================ FILE: framework/shared/src/io/openni15/ONI15InputInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/openni15/ONI15InputInterface.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/SensorCollection.h" #include "io/openni15/ONI15FrameStream.h" #include #define linux true #include #include #include using namespace slambench::io; using namespace slambench::io::openni15; ONI15InputInterface::ONI15InputInterface() : stream_(nullptr), sensors_ready_(false) { context_ = new xn::Context(); if (context_->Init() != XN_STATUS_OK) { std::cerr << ( "OpenNI15: Error Init Failed.") << std::endl; exit(1); return; } if (context_->StartGeneratingAll() != XN_STATUS_OK) { std::cerr << ( "OpenNI15: context_.StartGeneratingAll() ERROR !!!") << std::endl; exit(1); return; } std::cerr << ( "OpenNI15: Ready !!!") << std::endl; } FrameStream& ONI15InputInterface::GetFrames() { if(stream_ == nullptr) BuildStream(); return *stream_; } SensorCollection& ONI15InputInterface::GetSensors() { BuildSensors(); return sensors_; } CameraSensor *ONI15InputInterface::BuildCameraSensor() { std::string sensor_type = slambench::io::CameraSensor::kCameraType; CameraSensor *sensor = new CameraSensor(sensor_type); sensor->Description = "ONI15 RGB Sensor"; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelformat::RGB_III_888; sensor->Width = 640; sensor->Height = 480; sensor->Pose = Eigen::Matrix4f::Identity(); bzero(sensor->Intrinsics, sizeof(sensor->Intrinsics)); // guess the intrinsics for now std::cerr << "I'm guessing which intrinsics to use" << std::endl; sensor->Intrinsics[0] = 0.751875; sensor->Intrinsics[1] = 1.0; sensor->Intrinsics[2] = 0.5; sensor->Intrinsics[3] = 0.5; std::cerr << "Built an RGB sensor with " << sensor->Width << ", " << sensor->Height << ", " << sensor->GetFrameSize(NULL) << "b per frame" << std::endl; return sensor; } DepthSensor *ONI15InputInterface::BuildDepthSensor() { std::string sensor_type = slambench::io::DepthSensor::kDepthType; DepthSensor *sensor = new DepthSensor(sensor_type); sensor->Description = "ONI15 Depth Sensor"; sensor->FrameFormat = frameformat::Raster; // find a suitable video mode...? sensor->PixelFormat = pixelformat::D_I_16; sensor->Width = 640; sensor->Height = 480; sensor->Pose = Eigen::Matrix4f::Identity(); bzero(sensor->Intrinsics, sizeof(sensor->Intrinsics)); // guess the intrinsics for now std::cerr << "I'm guessing which intrinsics to use" << std::endl; sensor->Intrinsics[0] = 0.751875; sensor->Intrinsics[1] = 1.0; sensor->Intrinsics[2] = 0.5; sensor->Intrinsics[3] = 0.5; std::cerr << "Built a depth sensor with " << sensor->Width << ", " << sensor->Height << ", " << sensor->GetFrameSize(NULL) << "b per frame" << std::endl; return sensor; } void ONI15InputInterface::BuildSensors() { if(sensors_ready_) return; auto depth_sensor = BuildDepthSensor(); depth_sensor->Index = sensors_.size(); sensors_.AddSensor(depth_sensor); auto rgb_sensor = BuildCameraSensor(); rgb_sensor->Index = sensors_.size(); sensors_.AddSensor(rgb_sensor); sensors_ready_ = true; } void ONI15InputInterface::BuildStream() { BuildSensors(); stream_ = new ONI15FrameStream(context_); bool depth_found = false; bool rgb_found = false; for(auto *sensor : sensors_) { if(sensor->GetType() == slambench::io::CameraSensor::kCameraType) { rgb_found = true; assert(stream_->ActivateSensor((CameraSensor*)sensor)); } else if (sensor->GetType() == slambench::io::DepthSensor::kDepthType) { depth_found = true; assert(stream_->ActivateSensor((DepthSensor*)sensor)); } } assert(rgb_found and depth_found); stream_->StartStreams(); } ================================================ FILE: framework/shared/src/io/realsense/RealSense2Frame.cpp ================================================ /* Copyright (c) 2020 University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/realsense/RealSense2Frame.h" using namespace slambench::io::realsense; RealSense2Frame::RealSense2Frame(Sensor *sensor, const rs2::frame& frameref) { FrameSensor = sensor; Timestamp.Ns = (int)frameref.get_timestamp() % 1000000000; Timestamp.S = frameref.get_timestamp() / 1000000000; data_ = malloc(frameref.get_data_size()); memcpy(data_, frameref.get_data(), frameref.get_data_size()); } void* RealSense2Frame::GetData() { return data_; } void RealSense2Frame::FreeData() { free(data_); data_ = nullptr; } ================================================ FILE: framework/shared/src/io/realsense/RealSense2FrameStream.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/realsense/RealSense2FrameStream.h" #include "io/realsense/RealSense2Frame.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/Sensor.h" #include #include using namespace slambench::io::realsense; using namespace slambench::io; RealSense2FrameStream:: RealSense2FrameStream(rs2::pipeline &pipe) : pipe_(pipe) {} RealSense2FrameStream::~RealSense2FrameStream() {} SLAMFrame* RealSense2FrameStream::GetNextFrame() { for(auto frame = new_frames_.begin(); frame < new_frames_.end() ; frame++) { auto it = sensor_map_.find(frame->get_profile().stream_type()); if(it != sensor_map_.end()) { auto fr = new RealSense2Frame(it->second, *frame); new_frames_.erase(frame); return fr; } } return nullptr; } bool RealSense2FrameStream::ActivateSensor(rs2_stream stream, Sensor* sensor) { sensor_map_[stream] = sensor; return true; } bool RealSense2FrameStream::HasNextFrame() { if(!new_frames_.empty()) return true; rs2::frameset frameset; pipe_.poll_for_frames(&frameset); for (const rs2::frame& f : frameset) new_frames_.push_back(f); return true; } ================================================ FILE: framework/shared/src/io/realsense/RealSense2InputInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include using namespace slambench::io; using namespace slambench::io::realsense; RealSense2InputInterface::RealSense2InputInterface() : stream_(nullptr), sensors_ready_(false) { try { std::cout << "Querying Realsense device info..." << std::endl; // Create librealsense context and check device is connected rs2::context ctx; auto devs = ctx.query_devices(); int device_num = devs.size(); assert(device_num && "Device not found!"); std::cout << "Device number: " << device_num << std::endl; // Query the info of first device // Device serial number (different for each device, can be used for searching device when having mutiple devices) std::cout << "Serial number: " << devs.front().get_info(RS2_CAMERA_INFO_SERIAL_NUMBER) << std::endl; BuildStream(); } catch(const rs2::error &e){ // Capture device exception std::cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << "\nExiting!" << std::endl; exit(EXIT_FAILURE); } } FrameStream& RealSense2InputInterface::GetFrames() { if(stream_ == nullptr) BuildStream(); return *stream_; } SensorCollection& RealSense2InputInterface::GetSensors() { BuildStream(); return sensors_; } void RealSense2InputInterface::BuildRGBSensor(const rs2::stream_profile& color_profile) { rs2::video_stream_profile cvsprofile(color_profile); rs2_intrinsics color_intrinsics = cvsprofile.get_intrinsics(); slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = color_intrinsics.fx / color_intrinsics.width; intrinsics[1] = color_intrinsics.fy / color_intrinsics.height; intrinsics[2] = color_intrinsics.ppx / color_intrinsics.width; intrinsics[3] = color_intrinsics.ppy / color_intrinsics.height; slambench::io::CameraSensor::distortion_coefficients_t distortion; for(size_t i = 0; i < 5; i++) distortion[i] = color_intrinsics.coeffs[i]; slambench::io::CameraSensor::distortion_type_t distortion_type; if (color_intrinsics.model == rs2_distortion::RS2_DISTORTION_NONE) { distortion_type = slambench::io::CameraSensor::NoDistortion; } else if (color_intrinsics.model == rs2_distortion::RS2_DISTORTION_BROWN_CONRADY || color_intrinsics.model == rs2_distortion::RS2_DISTORTION_INVERSE_BROWN_CONRADY) { distortion_type = slambench::io::CameraSensor::RadialTangential; } else if (color_intrinsics.model == rs2_distortion::RS2_DISTORTION_KANNALA_BRANDT4) { distortion_type = slambench::io::CameraSensor::KannalaBrandt; } else { std::cerr<<"Unsupported distortion type!"<Intrinsic[i] = gyro_sensor->Intrinsic[i*4+j] = intrinsics.data[i][j]; } } for (int i = 0; i < 3; i++) { gyro_sensor->NoiseVariances[i] = intrinsics.noise_variances[i]; gyro_sensor->BiasVariances[i] = intrinsics.bias_variances[i]; } sensors_.AddSensor(gyro_sensor); } // If casting succeeded and the arrived frame is from accelerometer stream if (mprofile.stream_type() == RS2_STREAM_ACCEL && mprofile.format() == RS2_FORMAT_MOTION_XYZ32F) { auto accelerometer_sensor = AccSensorBuilder() .name(mprofile.stream_name()) .rate(mprofile.fps()) .description("Realsense Accelerometer") .index(sensors_.size()) .pose(pose) .build(); // Get accelerometer measures for (int i = 0; i < 3; i++) { for (int j = 0; j < 4; j++) { accelerometer_sensor->Intrinsic[i*4+j] = intrinsics.data[i][j]; } } for (int i = 0; i < 3; i++) { accelerometer_sensor->NoiseVariances[i] = intrinsics.noise_variances[i]; accelerometer_sensor->BiasVariances[i] = intrinsics.bias_variances[i]; } sensors_.AddSensor(accelerometer_sensor); } } void RealSense2InputInterface::BuildDepthSensor(const rs2::stream_profile& depth_profile) { rs2::video_stream_profile dvsprofile(depth_profile); rs2_intrinsics depth_intrinsics = dvsprofile.get_intrinsics(); slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = depth_intrinsics.fx / depth_intrinsics.width; intrinsics[1] = depth_intrinsics.fy / depth_intrinsics.height; intrinsics[2] = depth_intrinsics.ppx / depth_intrinsics.width; intrinsics[3] = depth_intrinsics.ppy / depth_intrinsics.height; slambench::io::CameraSensor::distortion_coefficients_t distortion; for(size_t i = 0; i < 5; i++) distortion[i] = depth_intrinsics.coeffs[i]; slambench::io::CameraSensor::distortion_type_t distortion_type; if (depth_intrinsics.model == rs2_distortion::RS2_DISTORTION_NONE) { distortion_type = slambench::io::CameraSensor::NoDistortion; } else if (depth_intrinsics.model == rs2_distortion::RS2_DISTORTION_BROWN_CONRADY || depth_intrinsics.model == rs2_distortion::RS2_DISTORTION_INVERSE_BROWN_CONRADY) { distortion_type = slambench::io::CameraSensor::RadialTangential; } else if (depth_intrinsics.model == rs2_distortion::RS2_DISTORTION_KANNALA_BRANDT4) { distortion_type = slambench::io::CameraSensor::KannalaBrandt; } else { std::cerr<<"Unsupported distortion type!"<GetType() == slambench::io::CameraSensor::kCameraType) { rgb_found = true; stream_->ActivateSensor(RS2_STREAM_COLOR, (CameraSensor*)sensor); } else if (sensor->GetType() == slambench::io::DepthSensor::kDepthType) { depth_found = true; stream_->ActivateSensor(RS2_STREAM_DEPTH, (DepthSensor*)sensor); } else if (sensor->GetType() == slambench::io::AccelerometerSensor::kAccType) { acc_found = true; stream_->ActivateSensor(RS2_STREAM_ACCEL, (AccelerometerSensor*)sensor); } else if (sensor->GetType() == slambench::io::GyroSensor::kGyroType) { gyro_found = true; stream_->ActivateSensor(RS2_STREAM_GYRO, (GyroSensor*)sensor); } } assert(rgb_found and depth_found); if(acc_found && gyro_found) std::cout<<"Motion data available"<Write(&sensor->Intrinsic , sizeof(sensor->Intrinsic)); serialiser->Write(&sensor->NoiseVariances, sizeof(sensor->NoiseVariances)); serialiser->Write(&sensor->BiasVariances, sizeof(sensor->BiasVariances)); return true; } }; class ACCDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name,const Sensor::sensor_type_t &type, Sensor** s) override { if(type != AccelerometerSensor::kAccType) { return false; } *s = new AccelerometerSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { AccelerometerSensor *sensor = (AccelerometerSensor*)s; d->Read(&sensor->Intrinsic , sizeof(sensor->Intrinsic)); d->Read(&sensor->NoiseVariances, sizeof(sensor->NoiseVariances)); d->Read(&sensor->BiasVariances, sizeof(sensor->BiasVariances)); return true; } }; static slambench::io::SensorDatabaseRegistration acc_reg(AccelerometerSensor::kAccType, slambench::io::SensorDatabaseEntry(new ACCSerialiser(), new ACCDeserialiser(), false, false)); ================================================ FILE: framework/shared/src/io/sensor/CameraSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/SensorDatabase.h" #include #include using namespace slambench::io; const Sensor::sensor_type_t CameraSensor::kCameraType = "Camera"; CameraSensor::CameraSensor(const Sensor::sensor_name_t &name, const Sensor::sensor_type_t &sensor_type) : Sensor(name, sensor_type) , Width (0), Height (0), FrameFormat (slambench::io::frameformat::UNKNOWN), PixelFormat(slambench::io::pixelformat::UNKNOWN), DistortionType(NoDistortion) { this->addParameter(TypedParameter("ip", "intrinsics-parameters","Focal length and Principal Point Offset : fx,fy,cx,cy", &(this->Intrinsics),nullptr)); } size_t CameraSensor::GetFrameSize(const SLAMFrame *frame) const { (void)frame; return Width * Height * pixelformat::GetPixelSize(PixelFormat); } void CameraSensor::CopyRadialTangentialDistortion(const distortion_coefficients_t &other) { for(unsigned int i = 0; i < 5 ; ++i) { RadialTangentialDistortion[i] = other[i]; } } void CameraSensor::CopyEquidistantDistortion(const distortion_coefficients_t &other) { for(unsigned int i = 0; i < 4 ; ++i) { EquidistantDistortion[i] = other[i]; } } void CameraSensor::CopyDistortion(const distortion_coefficients_t &other, const distortion_type_t& type) { for(unsigned int i = 0; i < 5 ; ++i) { Distortion[i] = other[i]; } } void CameraSensor::CopyIntrinsics(const intrinsics_t &other) { for(unsigned int i = 0; i < 4 ; ++i) { Intrinsics[i] = other[i]; } } void CameraSensor::CopyIntrinsics(const CameraSensor* other) { CopyIntrinsics(other->Intrinsics); } class CameraSensorSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* s) override { CameraSensor *sensor = (CameraSensor*)s; serialiser->Write(&sensor->FrameFormat, sizeof(sensor->FrameFormat)); serialiser->Write(&sensor->PixelFormat, sizeof(sensor->PixelFormat)); serialiser->Write(&sensor->Width, sizeof(sensor->Width)); serialiser->Write(&sensor->Height, sizeof(sensor->Height)); serialiser->Write(&sensor->Intrinsics, sizeof(sensor->Intrinsics)); serialiser->Write(&sensor->DistortionType, sizeof(sensor->DistortionType)); serialiser->Write(&sensor->RadialTangentialDistortion, sizeof(sensor->RadialTangentialDistortion)); serialiser->Write(&sensor->EquidistantDistortion, sizeof(sensor->EquidistantDistortion)); serialiser->Write(&sensor->Distortion, sizeof(sensor->Distortion)); return true; } }; class CameraSensorDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, Sensor** s) override { if(type == CameraSensor::kCameraType) { *s = new CameraSensor(sensor_name, type); return true; } else { return false; } } bool DeserialiseSensorSpecific(const Deserialiser* deserialiser, Sensor* s) override { CameraSensor *sensor = (CameraSensor*)s; assert(sensor->GetType() == CameraSensor::kCameraType); deserialiser->Read(&sensor->FrameFormat, sizeof(sensor->FrameFormat)); deserialiser->Read(&sensor->PixelFormat, sizeof(sensor->PixelFormat)); deserialiser->Read(&sensor->Width, sizeof(sensor->Width)); deserialiser->Read(&sensor->Height, sizeof(sensor->Height)); deserialiser->Read(&sensor->Intrinsics, sizeof(sensor->Intrinsics)); deserialiser->Read(&sensor->DistortionType, sizeof(sensor->DistortionType)); deserialiser->Read(&sensor->RadialTangentialDistortion, sizeof(sensor->RadialTangentialDistortion)); deserialiser->Read(&sensor->EquidistantDistortion, sizeof(sensor->EquidistantDistortion)); deserialiser->Read(&sensor->Distortion, sizeof(sensor->Distortion)); return true; } }; static slambench::io::SensorDatabaseRegistration camera_reg(CameraSensor::kCameraType, slambench::io::SensorDatabaseEntry(new CameraSensorSerialiser(), new CameraSensorDeserialiser(), false, false)); ================================================ FILE: framework/shared/src/io/sensor/CameraSensorFinder.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/CameraSensorFinder.h" #include "io/sensor/CameraSensor.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/SensorCollection.h" using namespace slambench::io; CameraSensorFinder::CameraSensorFinder() { PrepareEvaluators(); } std::vector CameraSensorFinder::Find(const SensorCollection& sensors, const std::initializer_list &filters) { std::vector output; for(auto sensor : sensors) { // this is still a nightmare but at least it only happens here if(sensor->GetType() == CameraSensor::kCameraType || sensor->GetType() == DepthSensor::kDepthType) { CameraSensor *cam = static_cast(sensor); bool success = true; for(auto filter : filters) { success &= TestFilter(cam, filter); } if(success) { output.push_back(cam); } } } return output; } CameraSensor* CameraSensorFinder::FindOne(const SensorCollection& sensors, const std::initializer_list& filters) { auto found_sensors = Find(sensors, filters); if(found_sensors.empty()) { return nullptr; } else { return found_sensors.front(); } } bool CameraSensorFinder::TestFilter(const CameraSensor* sensor, const CameraSensorFilter& filter) { return filter_evaluators_.at(filter.first)(sensor, filter.second); } void CameraSensorFinder::PrepareEvaluators() { filter_evaluators_["width"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return sensor->Width == std::stoul(value);}; filter_evaluators_["height"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return sensor->Height == std::stoul(value);}; filter_evaluators_["name"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return sensor->getName() == value;}; filter_evaluators_["pixel_format"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return sensor->PixelFormat == pixelformat::Parse(value);}; filter_evaluators_["camera_type"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return pixelformat::TypeOf(sensor->PixelFormat) == value;}; filter_evaluators_["frame_format"] = [](const CameraSensor *sensor, const std::string &value) -> bool {return sensor->FrameFormat == frameformat::Parse(value);}; } ================================================ FILE: framework/shared/src/io/sensor/DepthSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" #include "io/sensor/DepthSensor.h" #include "io/sensor/SensorDatabase.h" #include using namespace slambench::io; const Sensor::sensor_type_t DepthSensor::kDepthType = "Depth"; DepthSensor::DepthSensor(const Sensor::sensor_name_t &sensor_name) : CameraSensor(sensor_name, kDepthType) { this->addParameter(TypedParameter("dip", "disparity-params","Don't know what to say", &(this->DisparityParams),NULL)); } void DepthSensor::CopyDisparityParams(const disparity_params_t &other) { for(int i = 0; i < 2; ++i) { DisparityParams[i] = other[i]; } } void DepthSensor::CopyDisparityParams(const DepthSensor* other) { CopyDisparityParams(other->DisparityParams); } class DepthSensorSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* s) override { DepthSensor *sensor = (DepthSensor*)s; assert(sensor->GetType() == DepthSensor::kDepthType); serialiser->Write(&sensor->FrameFormat, sizeof(sensor->FrameFormat)); serialiser->Write(&sensor->PixelFormat, sizeof(sensor->PixelFormat)); serialiser->Write(&sensor->Width, sizeof(sensor->Width)); serialiser->Write(&sensor->Height, sizeof(sensor->Height)); serialiser->Write(&sensor->Intrinsics, sizeof(sensor->Intrinsics)); serialiser->Write(&sensor->DisparityParams, sizeof(sensor->DisparityParams)); serialiser->Write(&sensor->DisparityType, sizeof(sensor->DisparityType)); serialiser->Write(&sensor->DistortionType, sizeof(sensor->DistortionType)); serialiser->Write(&sensor->RadialTangentialDistortion, sizeof(sensor->RadialTangentialDistortion)); return true; } }; class DepthSensorDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t & type, Sensor** s) override { if(type == DepthSensor::kDepthType) { *s = new DepthSensor(sensor_name); return true; } else { return false; } } bool DeserialiseSensorSpecific(const Deserialiser* deserialiser, Sensor* s) override { DepthSensor *sensor = (DepthSensor*)s; assert(sensor->GetType() == DepthSensor::kDepthType); deserialiser->Read(&sensor->FrameFormat, sizeof(sensor->FrameFormat)); deserialiser->Read(&sensor->PixelFormat, sizeof(sensor->PixelFormat)); deserialiser->Read(&sensor->Width, sizeof(sensor->Width)); deserialiser->Read(&sensor->Height, sizeof(sensor->Height)); deserialiser->Read(&sensor->Intrinsics, sizeof(sensor->Intrinsics)); deserialiser->Read(&sensor->DisparityParams, sizeof(sensor->DisparityParams)); deserialiser->Read(&sensor->DisparityType, sizeof(sensor->DisparityType)); deserialiser->Read(&sensor->DistortionType, sizeof(sensor->DistortionType)); deserialiser->Read(&sensor->RadialTangentialDistortion, sizeof(sensor->RadialTangentialDistortion)); return true; } }; static slambench::io::SensorDatabaseRegistration depth_reg (DepthSensor::kDepthType, slambench::io::SensorDatabaseEntry(new DepthSensorSerialiser(), new DepthSensorDeserialiser())); ================================================ FILE: framework/shared/src/io/sensor/EventCameraSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" #include "io/sensor/EventCameraSensor.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; const Sensor::sensor_type_t EventCameraSensor::kEventCameraType = "EventCamera"; EventCameraSensor::EventCameraSensor(const sensor_name_t &sensor_name) : Sensor(sensor_name, kEventCameraType) { } size_t EventCameraSensor::GetCoordinateSize() const { if(Width <= UINT8_MAX && Height <= UINT8_MAX) return 1; if(Width <= UINT16_MAX && Height <= UINT16_MAX) return 2; return 4; } size_t EventCameraSensor::GetFrameSize(const SLAMFrame *frame) const { // X, Y, on/off (void)frame; return (GetCoordinateSize() * 2) + 1; } class EventCameraSensorSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* s) override { EventCameraSensor *sensor = (EventCameraSensor*)s; serialiser->Write(&sensor->Width, sizeof(sensor->Width)); serialiser->Write(&sensor->Height, sizeof(sensor->Height)); return true; } }; class EventCameraSensorDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, Sensor** s) override { if(type != EventCameraSensor::kEventCameraType) { return false; } *s = new EventCameraSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* deserialiser, Sensor* s) override { EventCameraSensor *sensor = (EventCameraSensor*)s; assert(sensor->GetType() == EventCameraSensor::kEventCameraType); deserialiser->Read(&sensor->Width, sizeof(sensor->Width)); deserialiser->Read(&sensor->Height, sizeof(sensor->Height)); return true; } }; static slambench::io::SensorDatabaseRegistration evcam_reg(EventCameraSensor::kEventCameraType, slambench::io::SensorDatabaseEntry(new EventCameraSensorSerialiser(), new EventCameraSensorDeserialiser(), false, true)); ================================================ FILE: framework/shared/src/io/sensor/GroundTruthSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/GroundTruthSensor.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; const Sensor::sensor_type_t GroundTruthSensor::kGroundTruthTrajectoryType = "GroundTruthTrajectory"; GroundTruthSensor::GroundTruthSensor(const Sensor::sensor_name_t &sensor_name) : Sensor(sensor_name, kGroundTruthTrajectoryType) { } size_t GroundTruthSensor::GetFrameSize(const SLAMFrame *frame) const { (void)frame; return sizeof(pose_t); } class GTSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* sensor) override { // nothing to do (void)serialiser; (void)sensor; return true; } }; class GTDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, Sensor** s) override { if(type != GroundTruthSensor::kGroundTruthTrajectoryType) { return false; } *s = new GroundTruthSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { // nothing to do (void)d; (void)s; return true; } }; static slambench::io::SensorDatabaseRegistration gt_reg(GroundTruthSensor::kGroundTruthTrajectoryType, slambench::io::SensorDatabaseEntry(new GTSerialiser(), new GTDeserialiser(), true, false)); ================================================ FILE: framework/shared/src/io/sensor/GyroSensor.cpp ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #include "io/sensor/GyroSensor.h" #include "io/sensor/SensorDatabase.h" #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" using namespace slambench::io; const Sensor::sensor_type_t GyroSensor::kGyroType = "Gyro"; GyroSensor::GyroSensor(const sensor_name_t &sensor_name) : Sensor(sensor_name, kGyroType) { } size_t GyroSensor::GetFrameSize(const SLAMFrame *frame) const { (void)frame; return 3 * sizeof(float); } class GyroSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* s) override { GyroSensor *sensor = (GyroSensor*)s; serialiser->Write(&sensor->Intrinsic , sizeof(sensor->Intrinsic)); serialiser->Write(&sensor->NoiseVariances, sizeof(sensor->NoiseVariances)); serialiser->Write(&sensor->BiasVariances, sizeof(sensor->BiasVariances)); return true; } }; class GyroDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name,const Sensor::sensor_type_t &type, Sensor** s) override { if(type != GyroSensor::kGyroType) { return false; } *s = new GyroSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { GyroSensor *sensor = (GyroSensor*)s; d->Read(&sensor->Intrinsic , sizeof(sensor->Intrinsic)); d->Read(&sensor->NoiseVariances, sizeof(sensor->NoiseVariances)); d->Read(&sensor->BiasVariances, sizeof(sensor->BiasVariances)); return true; } }; static slambench::io::SensorDatabaseRegistration gyro_reg(GyroSensor::kGyroType, slambench::io::SensorDatabaseEntry(new GyroSerialiser(), new GyroDeserialiser(), false, false)); ================================================ FILE: framework/shared/src/io/sensor/IMUSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/IMUSensor.h" #include "io/sensor/SensorDatabase.h" #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" using namespace slambench::io; const Sensor::sensor_type_t IMUSensor::kIMUType = "IMU"; IMUSensor::IMUSensor(const Sensor::sensor_name_t &sensor_name) : Sensor(sensor_name, kIMUType) { } size_t IMUSensor::GetFrameSize(const SLAMFrame *frame) const { (void)frame; return 6 * sizeof(float); } class IMUSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* s) override { IMUSensor *sensor = (IMUSensor*)s; serialiser->Write(&sensor->GyroscopeNoiseDensity, sizeof(sensor->GyroscopeNoiseDensity)); serialiser->Write(&sensor->GyroscopeDriftNoiseDensity, sizeof(sensor->GyroscopeDriftNoiseDensity)); serialiser->Write(&sensor->GyroscopeBiasDiffusion, sizeof(sensor->GyroscopeBiasDiffusion)); serialiser->Write(&sensor->GyroscopeSaturation , sizeof(sensor->GyroscopeSaturation)); serialiser->Write(&sensor->AcceleratorNoiseDensity, sizeof(sensor->AcceleratorNoiseDensity)); serialiser->Write(&sensor->AcceleratorDriftNoiseDensity , sizeof(sensor->AcceleratorDriftNoiseDensity)); serialiser->Write(&sensor->AcceleratorBiasDiffusion, sizeof(sensor->AcceleratorBiasDiffusion)); serialiser->Write(&sensor->AcceleratorSaturation , sizeof(sensor->AcceleratorSaturation)); return true; } }; class IMUDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, Sensor** s) override { if(type != IMUSensor::kIMUType) { return false; } *s = new IMUSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { // nothing to do (void)d; (void)s; IMUSensor *sensor = (IMUSensor*)s; d->Read(&sensor->GyroscopeNoiseDensity, sizeof(sensor->GyroscopeNoiseDensity)); d->Read(&sensor->GyroscopeDriftNoiseDensity, sizeof(sensor->GyroscopeDriftNoiseDensity)); d->Read(&sensor->GyroscopeBiasDiffusion, sizeof(sensor->GyroscopeBiasDiffusion)); d->Read(&sensor->GyroscopeSaturation , sizeof(sensor->GyroscopeSaturation)); d->Read(&sensor->AcceleratorNoiseDensity, sizeof(sensor->AcceleratorNoiseDensity)); d->Read(&sensor->AcceleratorDriftNoiseDensity , sizeof(sensor->AcceleratorDriftNoiseDensity)); d->Read(&sensor->AcceleratorBiasDiffusion, sizeof(sensor->AcceleratorBiasDiffusion)); d->Read(&sensor->AcceleratorSaturation , sizeof(sensor->AcceleratorSaturation)); return true; } }; static slambench::io::SensorDatabaseRegistration imu_reg(IMUSensor::kIMUType, slambench::io::SensorDatabaseEntry(new IMUSerialiser(), new IMUDeserialiser(), false, false)); ================================================ FILE: framework/shared/src/io/sensor/OdomSensor.cpp ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #include "io/sensor/OdomSensor.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; const Sensor::sensor_type_t OdomSensor::kOdomType = "Odom"; OdomSensor::OdomSensor(const sensor_name_t &sensor_name) : Sensor(sensor_name, kOdomType) { } size_t OdomSensor::GetFrameSize(const SLAMFrame *frame) const { (void)frame; return 13 * sizeof(float); } class OdomSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* sensor) override { // nothing to do (void)serialiser; (void)sensor; return true; } }; class OdomDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name,const Sensor::sensor_type_t &type, Sensor** s) override { if(type != OdomSensor::kOdomType) { return false; } *s = new OdomSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { // nothing to do (void)d; (void)s; return true; } }; static slambench::io::SensorDatabaseRegistration odom_reg(OdomSensor::kOdomType, slambench::io::SensorDatabaseEntry(new OdomSerialiser(), new OdomDeserialiser(), false, false)); ================================================ FILE: framework/shared/src/io/sensor/PointCloudSensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/SLAMFrame.h" #include "io/sensor/PointCloudSensor.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; const Sensor::sensor_type_t PointCloudSensor::kPointCloudType = "PointCloud"; PointCloudSensor::PointCloudSensor(const sensor_name_t &sensor_name) : Sensor(sensor_name, kPointCloudType) {} size_t PointCloudSensor::GetFrameSize(const SLAMFrame *frame) const { return frame->GetVariableSize(); } class PCSerialiser : public SensorSerialiser { bool SerialiseSensorSpecific(Serialiser* serialiser, const Sensor* sensor) override { // nothing to do (void)serialiser; (void)sensor; return true; } }; class PCDeserialiser : public SensorDeserialiser { bool InstantiateSensor(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, Sensor** s) override { if(type != PointCloudSensor::kPointCloudType) { return false; } *s = new PointCloudSensor(sensor_name); return true; } bool DeserialiseSensorSpecific(const Deserialiser* d, Sensor* s) override { // nothing to do (void)d; (void)s; return true; } }; static slambench::io::SensorDatabaseRegistration rgb_reg(PointCloudSensor::kPointCloudType, slambench::io::SensorDatabaseEntry(new PCSerialiser(), new PCDeserialiser(), true, true)); ================================================ FILE: framework/shared/src/io/sensor/Sensor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/Sensor.h" #include "io/serialisation/Serialiser.h" #include "io/deserialisation/Deserialiser.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; Sensor::Sensor(const sensor_name_t &name, const sensor_type_t &type) : ParameterComponent(name), Index(0), Rate(0), Delay(0), sensor_name_(name), sensor_type_(type) {} const Sensor::sensor_type_t &Sensor::GetType() const { return sensor_type_; } const Sensor::sensor_name_t &Sensor::GetName() const { return sensor_name_; } void Sensor::CopyPose(const pose_t &other) { Pose = other; } void Sensor::CopyPose(const Sensor* other) { CopyPose(other->Pose); } bool Sensor::IsGroundTruth() const { return SensorDatabase::Singleton()->Get(GetType()).IsGroundTruth(); } bool Sensor::IsVariableSize() const { return SensorDatabase::Singleton()->Get(GetType()).IsVariableSize(); } bool SensorDeserialiser::Deserialise(const Sensor::sensor_name_t &sensor_name, const Sensor::sensor_type_t &type, const Deserialiser* d, Sensor** s) { Sensor *sensor; if(!InstantiateSensor(sensor_name, type, &sensor)) { fprintf(stderr, "Could not instantiate sensor of type %s\n", type.c_str()); return false; } d->Read(&sensor->Index, sizeof(sensor->Index)); uint32_t desc_bytes; d->Read(&desc_bytes, sizeof(desc_bytes)); char desc[desc_bytes]; d->Read(desc, desc_bytes); sensor->Description = desc; d->Read(&sensor->Rate, sizeof(sensor->Rate)); d->Read(&sensor->Pose, sizeof(sensor->Pose)); d->Read(&sensor->Delay, sizeof(sensor->Delay)); *s = sensor; bool success = DeserialiseSensorSpecific(d, *s); if(!success) { fprintf(stderr, "Sensor specific initialisation failed for '%s' (type %s)\n", desc, type.c_str()); } return success; } bool SensorSerialiser::Serialise(Serialiser* serialiser, const Sensor* sensor) { Sensor::sensor_type_t raw_name = sensor->GetName(); uint8_t name_size = raw_name.size()+1; serialiser->Write(&name_size, sizeof(name_size)); serialiser->Write(raw_name.c_str(), name_size); Sensor::sensor_type_t raw_type = sensor->GetType(); uint8_t type_size = raw_type.size()+1; serialiser->Write(&type_size, sizeof(type_size)); serialiser->Write(raw_type.c_str(), type_size); serialiser->Write(&sensor->Index, sizeof(sensor->Index)); uint32_t desc_bytes = sensor->Description.size()+1; serialiser->Write(&desc_bytes, sizeof(desc_bytes)); serialiser->Write(sensor->Description.c_str(), desc_bytes); serialiser->Write(&sensor->Rate, sizeof(sensor->Rate)); serialiser->Write(&sensor->Pose, sizeof(sensor->Pose)); serialiser->Write(&sensor->Delay, sizeof(sensor->Delay)); return SerialiseSensorSpecific(serialiser, sensor); } ================================================ FILE: framework/shared/src/io/sensor/SensorCollection.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/SensorCollection.h" #include "io/sensor/Sensor.h" #include using namespace slambench::io; Sensor &SensorCollection::at(unsigned int sensor_idx) { return *container_.at(sensor_idx); } size_t SensorCollection::size() const { return container_.size(); } void SensorCollection::AddSensor(Sensor* sensor) { if(sensor == nullptr) { throw std::logic_error("Cannot add a null sensor to SensorCollection"); } sensor->Index = container_.size(); container_.push_back(sensor); } Sensor* SensorCollection::GetSensor(const Sensor::sensor_type_t & type) { for(auto &i : container_) { if(i->GetType() == type) { return i; } } return nullptr; } const Sensor* SensorCollection::GetSensor(const Sensor::sensor_type_t & type) const { for(auto &i : container_) { if(i->GetType() == type) { return i; } } return nullptr; } std::vector SensorCollection::GetSensors(const Sensor::sensor_type_t & type) { std::vector output; for(auto &i : container_) { if(i->GetType() == type) { output.push_back(i); } } return output; } ================================================ FILE: framework/shared/src/io/sensor/SensorDatabase.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/SensorDatabase.h" #include using namespace slambench::io; SensorDatabase *SensorDatabase::singleton_; SensorDatabase* SensorDatabase::Singleton() { if(singleton_ == nullptr) { singleton_ = new SensorDatabase(); } return singleton_; } SensorDatabaseEntry::SensorDatabaseEntry(SensorSerialiser* s, SensorDeserialiser* ds, bool ground_truth, bool variable_size) : serialiser_(s), deserialiser_(ds), is_ground_truth_(ground_truth), is_variable_size_(variable_size) { } SensorDatabaseEntry& SensorDatabase::Get(const Sensor::sensor_type_t& sensor_name) { return registrations_.at(sensor_name); } void SensorDatabase::RegisterSensor(const Sensor::sensor_type_t& sensor_name, const SensorDatabaseEntry& entry) { registrations_.insert({sensor_name, entry}); } SensorDatabaseRegistration::SensorDatabaseRegistration(const Sensor::sensor_type_t& name, const SensorDatabaseEntry& entry) { SensorDatabase::Singleton()->RegisterSensor(name, entry); } ================================================ FILE: framework/shared/src/io/serialisation/SLAMFileHeaderSerialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/SLAMFileHeaderSerialiser.h" #include "io/SLAMFile.h" #include "io/sensor/Sensor.h" #include "io/sensor/SensorDatabase.h" using namespace slambench::io; SLAMFileHeaderSerialiser::SLAMFileHeaderSerialiser(FILE *file) : Serialiser(file) { } bool SLAMFileHeaderSerialiser::Serialise(const SLAMFile &file) { if(!SerialiseHeader(file)) return false; for(const auto &sensor : file.Sensors) { if(!SerialiseSensor(*sensor)) { printf("Could not serialise sensor %s\n", sensor->Description.c_str()); return false; } } return true; } bool SLAMFileHeaderSerialiser::SerialiseHeader(const SLAMFile &file) { Write(SLAMFile::MagicNum, sizeof(SLAMFile::MagicNum)); uint32_t version = SLAMFile::Version; Write(&version, sizeof(version)); uint32_t sensorcount = file.Sensors.size(); Write(&sensorcount, sizeof(sensorcount)); return true; } bool SLAMFileHeaderSerialiser::SerialiseSensor(const Sensor &sensor) { if(!SensorDatabase::Singleton()->Get(sensor.GetType()).GetSerialiser()->Serialise(this, &sensor)) return false; return true; } ================================================ FILE: framework/shared/src/io/serialisation/SLAMFileSerialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/SLAMFileSerialiser.h" #include "io/serialisation/SLAMFileHeaderSerialiser.h" #include "io/serialisation/SLAMFrameSerialiser.h" #include "io/SLAMFile.h" #include #include using namespace slambench::io; SLAMFileSerialiser::SLAMFileSerialiser(FILE *target) : Serialiser(target), FrameCallback(nullptr) { } bool SLAMFileSerialiser::Serialise(SLAMFile &file) { if(!SerialiseHeader(file)) return false; if(!SerialiseFrames(file)) return false; return true; } bool SLAMFileSerialiser::SerialiseHeader(const SLAMFile &file) { SLAMFileHeaderSerialiser sfhs(File()); return sfhs.Serialise(file); } bool SLAMFileSerialiser::SerialiseFrames(SLAMFile &file) { SLAMFrameSerialiser sfs(File()); uint32_t frame_idx = 0; for(unsigned int i = 0; i < file.GetFrameCount(); ++i) { SLAMFrame *frame = file.GetFrame(i); if(!sfs.Serialise(*frame)) { std::cerr<<"Failed to serialise frame"; return false; } if(FrameCallback != nullptr) { FrameCallback(frame_idx, file.GetFrameCount()); } frame_idx++; } return true; } ================================================ FILE: framework/shared/src/io/serialisation/SLAMFrameSerialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/SLAMFrameSerialiser.h" #include "io/SLAMFrame.h" #include "io/sensor/Sensor.h" using namespace slambench::io; SLAMFrameSerialiser::SLAMFrameSerialiser(FILE *target) : Serialiser(target) { } bool SLAMFrameSerialiser::Serialise(SLAMFrame &frame) { void *frame_data = frame.GetData(); if(frame_data == nullptr) { printf("Could not get frame data\n"); return false; } struct { decltype(frame.Timestamp) timestamp; decltype(frame.FrameSensor->Index) index; } __attribute__((packed)) data; data.timestamp = frame.Timestamp; data.index = frame.FrameSensor->Index; if (!Write(&data, sizeof(data))) { printf("Could not write frame header\n"); return false; } if(frame.FrameSensor->IsVariableSize()) { uint32_t data_size = frame.GetSize(); if (!Write(&data_size, sizeof(data_size))) { printf("Could not write frame size data\n"); return false; } } if (!Write(frame_data, frame.GetSize())) { printf("Could not write frame data\n"); return false; } frame.FreeData(); return true; } ================================================ FILE: framework/shared/src/io/serialisation/Serialiser.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/serialisation/Serialiser.h" using namespace slambench::io; Serialiser::Serialiser(FILE *target_file) : _file(target_file) { } FILE *Serialiser::File() { return _file; } bool Serialiser::Write(const void *data, size_t size) { return fwrite(data, size, 1, File()) == 1; } ================================================ FILE: framework/shared/src/library_wrapper.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include extern "C" { bool c_sb_new_slam_configuration(void * slam_settings) { return sb_new_slam_configuration((SLAMBenchLibraryHelper *) slam_settings); } bool c_sb_init_slam_system(void * slam_settings) { return sb_init_slam_system((SLAMBenchLibraryHelper *) slam_settings); } bool c_sb_update_frame(void * slam_settings, void * type) { return sb_update_frame((SLAMBenchLibraryHelper *) slam_settings, (slambench::io::SLAMFrame *) type); } bool c_sb_relocalize(void * slam_settings) { return sb_relocalize((SLAMBenchLibraryHelper *) slam_settings); } bool c_sb_process_once (void * slam_settings){ return sb_process_once((SLAMBenchLibraryHelper *) slam_settings); } bool c_sb_clean_slam_system(){ return sb_clean_slam_system(); } bool c_sb_update_outputs(void *lib, void *timestamp) { return sb_update_outputs((SLAMBenchLibraryHelper*)lib, (const slambench::TimeStamp *)timestamp); } } ================================================ FILE: framework/shared/src/lodepng.cpp ================================================ /* LodePNG version 20140624 Copyright (c) 2005-2014 Lode Vandevenne This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 3. This notice may not be removed or altered from any source distribution. */ /* The manual and changelog are in the header file "lodepng.h" Rename this file to lodepng.cpp to use it for C++, or to lodepng.c to use it for C. */ #include "lodepng.h" #include #include #ifdef LODEPNG_COMPILE_CPP #include #endif /*LODEPNG_COMPILE_CPP*/ #define VERSION_STRING "20140624" #if (_MSC_VER >= 1310) /*Visual Studio: Kept warning-free but a few warning types are not desired here.*/ #pragma warning( disable : 4244 ) /*implicit conversions: not warned by gcc -Wall -Wextra and requires too much casts*/ #pragma warning( disable : 4996 ) /*VS does not like fopen, but fopen_s is not standard C so unusable here*/ #endif /*_MSC_VER >= 1310*/ /* This source file is built up in the following large parts. The code sections with the "LODEPNG_COMPILE_" #defines divide this up further in an intermixed way. -Tools for C and common code for PNG and Zlib -C Code for Zlib (huffman, deflate, ...) -C Code for PNG (file format chunks, adam7, PNG filters, color conversions, ...) -The C++ wrapper around all of the above */ /*The malloc, realloc and free functions defined here with "lodepng_" in front of the name, so that you can easily change them to others related to your platform if needed. Everything else in the code calls these. Pass -DLODEPNG_NO_COMPILE_ALLOCATORS to the compiler, or comment out #define LODEPNG_COMPILE_ALLOCATORS in the header, to disable the ones here and define them in your own project's source files without needing to change lodepng source code. Don't forget to remove "static" if you copypaste them from here.*/ #ifdef LODEPNG_COMPILE_ALLOCATORS static void* lodepng_malloc(size_t size) { return malloc(size); } static void* lodepng_realloc(void* ptr, size_t new_size) { return realloc(ptr, new_size); } static void lodepng_free(void* ptr) { free(ptr); } #else /*LODEPNG_COMPILE_ALLOCATORS*/ void* lodepng_malloc(size_t size); void* lodepng_realloc(void* ptr, size_t new_size); void lodepng_free(void* ptr); #endif /*LODEPNG_COMPILE_ALLOCATORS*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // Tools for C, and common code for PNG and Zlib. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* Often in case of an error a value is assigned to a variable and then it breaks out of a loop (to go to the cleanup phase of a function). This macro does that. It makes the error handling code shorter and more readable. Example: if(!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83); */ #define CERROR_BREAK(errorvar, code)\ {\ errorvar = code;\ break;\ } /*version of CERROR_BREAK that assumes the common case where the error variable is named "error"*/ #define ERROR_BREAK(code) CERROR_BREAK(error, code) /*Set error var to the error code, and return it.*/ #define CERROR_RETURN_ERROR(errorvar, code)\ {\ errorvar = code;\ return code;\ } /*Try the code, if it returns error, also return the error.*/ #define CERROR_TRY_RETURN(call)\ {\ unsigned error = call;\ if(error) return error;\ } /* About uivector, ucvector and string: -All of them wrap dynamic arrays or text strings in a similar way. -LodePNG was originally written in C++. The vectors replace the std::vectors that were used in the C++ version. -The string tools are made to avoid problems with compilers that declare things like strncat as deprecated. -They're not used in the interface, only internally in this file as static functions. -As with many other structs in this file, the init and cleanup functions serve as ctor and dtor. */ #ifdef LODEPNG_COMPILE_ZLIB /*dynamic vector of unsigned ints*/ typedef struct uivector { unsigned* data; size_t size; /*size in number of unsigned longs*/ size_t allocsize; /*allocated size in bytes*/ } uivector; static void uivector_cleanup(void* p) { ((uivector*) p)->size = ((uivector*) p)->allocsize = 0; lodepng_free(((uivector*) p)->data); ((uivector*) p)->data = NULL; } /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_resize(uivector* p, size_t size) { if (size * sizeof(unsigned) > p->allocsize) { size_t newsize = size * sizeof(unsigned) * 2; void* data = lodepng_realloc(p->data, newsize); if (data) { p->allocsize = newsize; p->data = (unsigned*) data; p->size = size; } else return 0; } else p->size = size; return 1; } /*resize and give all new elements the value*/ static unsigned uivector_resizev(uivector* p, size_t size, unsigned value) { size_t oldsize = p->size, i; if (!uivector_resize(p, size)) return 0; for (i = oldsize; i < size; i++) p->data[i] = value; return 1; } static void uivector_init(uivector* p) { p->data = NULL; p->size = p->allocsize = 0; } #ifdef LODEPNG_COMPILE_ENCODER /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_push_back(uivector* p, unsigned c) { if (!uivector_resize(p, p->size + 1)) return 0; p->data[p->size - 1] = c; return 1; } /*copy q to p, returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_copy(uivector* p, const uivector* q) { size_t i; if (!uivector_resize(p, q->size)) return 0; for (i = 0; i < q->size; i++) p->data[i] = q->data[i]; return 1; } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ /* /////////////////////////////////////////////////////////////////////////// */ /*dynamic vector of unsigned chars*/ typedef struct ucvector { unsigned char* data; size_t size; /*used size*/ size_t allocsize; /*allocated size*/ } ucvector; /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned ucvector_resize(ucvector* p, size_t size) { if (size * sizeof(unsigned char) > p->allocsize) { size_t newsize = size * sizeof(unsigned char) * 2; void* data = lodepng_realloc(p->data, newsize); if (data) { p->allocsize = newsize; p->data = (unsigned char*) data; p->size = size; } else return 0; /*error: not enough memory*/ } else p->size = size; return 1; } #ifdef LODEPNG_COMPILE_PNG static void ucvector_cleanup(void* p) { ((ucvector*) p)->size = ((ucvector*) p)->allocsize = 0; lodepng_free(((ucvector*) p)->data); ((ucvector*) p)->data = NULL; } static void ucvector_init(ucvector* p) { p->data = NULL; p->size = p->allocsize = 0; } #ifdef LODEPNG_COMPILE_DECODER /*resize and give all new elements the value*/ static unsigned ucvector_resizev(ucvector* p, size_t size, unsigned char value) { size_t oldsize = p->size, i; if (!ucvector_resize(p, size)) return 0; for (i = oldsize; i < size; i++) p->data[i] = value; return 1; } #endif /*LODEPNG_COMPILE_DECODER*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ZLIB /*you can both convert from vector to buffer&size and vica versa. If you use init_buffer to take over a buffer and size, it is not needed to use cleanup*/ static void ucvector_init_buffer(ucvector* p, unsigned char* buffer, size_t size) { p->data = buffer; p->allocsize = p->size = size; } #endif /*LODEPNG_COMPILE_ZLIB*/ #if (defined(LODEPNG_COMPILE_PNG) && defined(LODEPNG_COMPILE_ANCILLARY_CHUNKS)) || defined(LODEPNG_COMPILE_ENCODER) /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned ucvector_push_back(ucvector* p, unsigned char c) { if (!ucvector_resize(p, p->size + 1)) return 0; p->data[p->size - 1] = c; return 1; } #endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_PNG #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned string_resize(char** out, size_t size) { char* data = (char*) lodepng_realloc(*out, size + 1); if (data) { data[size] = 0; /*null termination char*/ *out = data; } return data != 0; } /*init a {char*, size_t} pair for use as string*/ static void string_init(char** out) { *out = NULL; string_resize(out, 0); } /*free the above pair again*/ static void string_cleanup(char** out) { lodepng_free(*out); *out = NULL; } static void string_set(char** out, const char* in) { size_t insize = strlen(in), i = 0; if (string_resize(out, insize)) { for (i = 0; i < insize; i++) { (*out)[i] = in[i]; } } } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ #endif /*LODEPNG_COMPILE_PNG*/ /* ////////////////////////////////////////////////////////////////////////// */ unsigned lodepng_read32bitInt(const unsigned char* buffer) { return (unsigned) ((buffer[0] << 24) | (buffer[1] << 16) | (buffer[2] << 8) | buffer[3]); } #if defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER) /*buffer must have at least 4 allocated bytes available*/ static void lodepng_set32bitInt(unsigned char* buffer, unsigned value) { buffer[0] = (unsigned char) ((value >> 24) & 0xff); buffer[1] = (unsigned char) ((value >> 16) & 0xff); buffer[2] = (unsigned char) ((value >> 8) & 0xff); buffer[3] = (unsigned char) ((value) & 0xff); } #endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ #ifdef LODEPNG_COMPILE_ENCODER static void lodepng_add32bitInt(ucvector* buffer, unsigned value) { ucvector_resize(buffer, buffer->size + 4); /*todo: give error if resize failed*/ lodepng_set32bitInt(&buffer->data[buffer->size - 4], value); } #endif /*LODEPNG_COMPILE_ENCODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / File IO / */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename) { FILE* file; long size; /*provide some proper output values if error will happen*/ *out = 0; *outsize = 0; file = fopen(filename, "rb"); if (!file) return 78; /*get filesize:*/ fseek(file, 0, SEEK_END); size = ftell(file); rewind(file); /*read contents of the file into the vector*/ *outsize = 0; *out = (unsigned char*) lodepng_malloc((size_t) size); if (size && (*out)) (*outsize) = fread(*out, 1, (size_t) size, file); fclose(file); if (!(*out) && size) return 83; /*the above malloc failed*/ return 0; } /*write given buffer to the file, overwriting the file, it doesn't append to it.*/ unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename) { FILE* file; file = fopen(filename, "wb"); if (!file) return 79; fwrite((char*) buffer, 1, buffersize, file); fclose(file); return 0; } #endif /*LODEPNG_COMPILE_DISK*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // End of common code and tools. Begin of Zlib related code. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_ENCODER /*TODO: this ignores potential out of memory errors*/ #define addBitToStream(/*size_t**/ bitpointer, /*ucvector**/ bitstream, /*unsigned char*/ bit)\ {\ /*add a new byte at the end*/\ if(((*bitpointer) & 7) == 0) ucvector_push_back(bitstream, (unsigned char)0);\ /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/\ (bitstream->data[bitstream->size - 1]) |= (bit << ((*bitpointer) & 0x7));\ (*bitpointer)++;\ } static void addBitsToStream(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) { size_t i; for (i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char )((value >> i) & 1)); } static void addBitsToStreamReversed(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) { size_t i; for (i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char )((value >> (nbits - 1 - i)) & 1)); } #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DECODER #define READBIT(bitpointer, bitstream) ((bitstream[bitpointer >> 3] >> (bitpointer & 0x7)) & (unsigned char)1) static unsigned char readBitFromStream(size_t* bitpointer, const unsigned char* bitstream) { unsigned char result = (unsigned char) (READBIT(*bitpointer, bitstream)); (*bitpointer)++; return result; } static unsigned readBitsFromStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) { unsigned result = 0, i; for (i = 0; i < nbits; i++) { result += ((unsigned) READBIT(*bitpointer, bitstream)) << i; (*bitpointer)++; } return result; } #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / Deflate - Huffman / */ /* ////////////////////////////////////////////////////////////////////////// */ #define FIRST_LENGTH_CODE_INDEX 257 #define LAST_LENGTH_CODE_INDEX 285 /*256 literals, the end code, some length codes, and 2 unused codes*/ #define NUM_DEFLATE_CODE_SYMBOLS 288 /*the distance codes have their own symbols, 30 used, 2 unused*/ #define NUM_DISTANCE_SYMBOLS 32 /*the code length codes. 0-15: code lengths, 16: copy previous 3-6 times, 17: 3-10 zeros, 18: 11-138 zeros*/ #define NUM_CODE_LENGTH_CODES 19 /*the base lengths represented by codes 257-285*/ static const unsigned LENGTHBASE[29] = { 3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31, 35, 43, 51, 59, 67, 83, 99, 115, 131, 163, 195, 227, 258 }; /*the extra bits used by codes 257-285 (added to base length)*/ static const unsigned LENGTHEXTRA[29] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3, 4, 4, 4, 4, 5, 5, 5, 5, 0 }; /*the base backwards distances (the bits of distance codes appear after length codes and use their own huffman tree)*/ static const unsigned DISTANCEBASE[30] = { 1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193, 257, 385, 513, 769, 1025, 1537, 2049, 3073, 4097, 6145, 8193, 12289, 16385, 24577 }; /*the extra bits of backwards distances (added to base)*/ static const unsigned DISTANCEEXTRA[30] = { 0, 0, 0, 0, 1, 1, 2, 2, 3, 3, 4, 4, 5, 5, 6, 6, 7, 7, 8, 8, 9, 9, 10, 10, 11, 11, 12, 12, 13, 13 }; /*the order in which "code length alphabet code lengths" are stored, out of this the huffman tree of the dynamic huffman tree lengths is generated*/ static const unsigned CLCL_ORDER[NUM_CODE_LENGTH_CODES] = { 16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15 }; /* ////////////////////////////////////////////////////////////////////////// */ /* Huffman tree struct, containing multiple representations of the tree */ typedef struct HuffmanTree { unsigned* tree2d; unsigned* tree1d; unsigned* lengths; /*the lengths of the codes of the 1d-tree*/ unsigned maxbitlen; /*maximum number of bits a single code can get*/ unsigned numcodes; /*number of symbols in the alphabet = number of codes*/ } HuffmanTree; /*function used for debug purposes to draw the tree in ascii art with C++*/ /* static void HuffmanTree_draw(HuffmanTree* tree) { std::cout << "tree. length: " << tree->numcodes << " maxbitlen: " << tree->maxbitlen << std::endl; for(size_t i = 0; i < tree->tree1d.size; i++) { if(tree->lengths.data[i]) std::cout << i << " " << tree->tree1d.data[i] << " " << tree->lengths.data[i] << std::endl; } std::cout << std::endl; }*/ static void HuffmanTree_init(HuffmanTree* tree) { tree->tree2d = 0; tree->tree1d = 0; tree->lengths = 0; } static void HuffmanTree_cleanup(HuffmanTree* tree) { lodepng_free(tree->tree2d); lodepng_free(tree->tree1d); lodepng_free(tree->lengths); } /*the tree representation used by the decoder. return value is error*/ static unsigned HuffmanTree_make2DTree(HuffmanTree* tree) { unsigned nodefilled = 0; /*up to which node it is filled*/ unsigned treepos = 0; /*position in the tree (1 of the numcodes columns)*/ unsigned n, i; tree->tree2d = (unsigned*) lodepng_malloc( tree->numcodes * 2 * sizeof(unsigned)); if (!tree->tree2d) return 83; /*alloc fail*/ /* convert tree1d[] to tree2d[][]. In the 2D array, a value of 32767 means uninited, a value >= numcodes is an address to another bit, a value < numcodes is a code. The 2 rows are the 2 possible bit values (0 or 1), there are as many columns as codes - 1. A good huffmann tree has N * 2 - 1 nodes, of which N - 1 are internal nodes. Here, the internal nodes are stored (what their 0 and 1 option point to). There is only memory for such good tree currently, if there are more nodes (due to too long length codes), error 55 will happen */ for (n = 0; n < tree->numcodes * 2; n++) { tree->tree2d[n] = 32767; /*32767 here means the tree2d isn't filled there yet*/ } for (n = 0; n < tree->numcodes; n++) /*the codes*/ { for (i = 0; i < tree->lengths[n]; i++) /*the bits for this code*/ { unsigned char bit = (unsigned char) ((tree->tree1d[n] >> (tree->lengths[n] - i - 1)) & 1); if (treepos > tree->numcodes - 2) return 55; /*oversubscribed, see comment in lodepng_error_text*/ if (tree->tree2d[2 * treepos + bit] == 32767) /*not yet filled in*/ { if (i + 1 == tree->lengths[n]) /*last bit*/ { tree->tree2d[2 * treepos + bit] = n; /*put the current code in it*/ treepos = 0; } else { /*put address of the next step in here, first that address has to be found of course (it's just nodefilled + 1)...*/ nodefilled++; /*addresses encoded with numcodes added to it*/ tree->tree2d[2 * treepos + bit] = nodefilled + tree->numcodes; treepos = nodefilled; } } else treepos = tree->tree2d[2 * treepos + bit] - tree->numcodes; } } for (n = 0; n < tree->numcodes * 2; n++) { if (tree->tree2d[n] == 32767) tree->tree2d[n] = 0; /*remove possible remaining 32767's*/ } return 0; } /* Second step for the ...makeFromLengths and ...makeFromFrequencies functions. numcodes, lengths and maxbitlen must already be filled in correctly. return value is error. */ static unsigned HuffmanTree_makeFromLengths2(HuffmanTree* tree) { uivector blcount; uivector nextcode; unsigned bits, n, error = 0; uivector_init(&blcount); uivector_init(&nextcode); tree->tree1d = (unsigned*) lodepng_malloc( tree->numcodes * sizeof(unsigned)); if (!tree->tree1d) error = 83; /*alloc fail*/ if (!uivector_resizev(&blcount, tree->maxbitlen + 1, 0) || !uivector_resizev(&nextcode, tree->maxbitlen + 1, 0)) error = 83; /*alloc fail*/ if (!error) { /*step 1: count number of instances of each code length*/ for (bits = 0; bits < tree->numcodes; bits++) blcount.data[tree->lengths[bits]]++; /*step 2: generate the nextcode values*/ for (bits = 1; bits <= tree->maxbitlen; bits++) { nextcode.data[bits] = (nextcode.data[bits - 1] + blcount.data[bits - 1]) << 1; } /*step 3: generate all the codes*/ for (n = 0; n < tree->numcodes; n++) { if (tree->lengths[n] != 0) tree->tree1d[n] = nextcode.data[tree->lengths[n]]++; } } uivector_cleanup(&blcount); uivector_cleanup(&nextcode); if (!error) return HuffmanTree_make2DTree(tree); else return error; } /* given the code lengths (as stored in the PNG file), generate the tree as defined by Deflate. maxbitlen is the maximum bits that a code in the tree can have. return value is error. */ static unsigned HuffmanTree_makeFromLengths(HuffmanTree* tree, const unsigned* bitlen, size_t numcodes, unsigned maxbitlen) { unsigned i; tree->lengths = (unsigned*) lodepng_malloc(numcodes * sizeof(unsigned)); if (!tree->lengths) return 83; /*alloc fail*/ for (i = 0; i < numcodes; i++) tree->lengths[i] = bitlen[i]; tree->numcodes = (unsigned) numcodes; /*number of symbols*/ tree->maxbitlen = maxbitlen; return HuffmanTree_makeFromLengths2(tree); } #ifdef LODEPNG_COMPILE_ENCODER /* A coin, this is the terminology used for the package-merge algorithm and the coin collector's problem. This is used to generate the huffman tree. A coin can be multiple coins (when they're merged) */ typedef struct Coin { uivector symbols; float weight; /*the sum of all weights in this coin*/ } Coin; static void coin_init(Coin* c) { uivector_init(&c->symbols); } /*argument c is void* so that this dtor can be given as function pointer to the vector resize function*/ static void coin_cleanup(void* c) { uivector_cleanup(&((Coin*) c)->symbols); } static void coin_copy(Coin* c1, const Coin* c2) { c1->weight = c2->weight; uivector_copy(&c1->symbols, &c2->symbols); } static void add_coins(Coin* c1, const Coin* c2) { size_t i; for (i = 0; i < c2->symbols.size; i++) uivector_push_back(&c1->symbols, c2->symbols.data[i]); c1->weight += c2->weight; } static void init_coins(Coin* coins, size_t num) { size_t i; for (i = 0; i < num; i++) coin_init(&coins[i]); } static void cleanup_coins(Coin* coins, size_t num) { size_t i; for (i = 0; i < num; i++) coin_cleanup(&coins[i]); } static int coin_compare(const void* a, const void* b) { float wa = ((const Coin*) a)->weight; float wb = ((const Coin*) b)->weight; return wa > wb ? 1 : wa < wb ? -1 : 0; } static unsigned append_symbol_coins(Coin* coins, const unsigned* frequencies, unsigned numcodes, size_t sum) { unsigned i; unsigned j = 0; /*index of present symbols*/ for (i = 0; i < numcodes; i++) { if (frequencies[i] != 0) /*only include symbols that are present*/ { coins[j].weight = frequencies[i] / (float) sum; uivector_push_back(&coins[j].symbols, i); j++; } } return 0; } unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, size_t numcodes, unsigned maxbitlen) { unsigned i, j; size_t sum = 0, numpresent = 0; unsigned error = 0; Coin* coins; /*the coins of the currently calculated row*/ Coin* prev_row; /*the previous row of coins*/ size_t numcoins; size_t coinmem; if (numcodes == 0) return 80; /*error: a tree of 0 symbols is not supposed to be made*/ for (i = 0; i < numcodes; i++) { if (frequencies[i] > 0) { numpresent++; sum += frequencies[i]; } } for (i = 0; i < numcodes; i++) lengths[i] = 0; /*ensure at least two present symbols. There should be at least one symbol according to RFC 1951 section 3.2.7. To decoders incorrectly require two. To make these work as well ensure there are at least two symbols. The Package-Merge code below also doesn't work correctly if there's only one symbol, it'd give it the theoritical 0 bits but in practice zlib wants 1 bit*/ if (numpresent == 0) { lengths[0] = lengths[1] = 1; /*note that for RFC 1951 section 3.2.7, only lengths[0] = 1 is needed*/ } else if (numpresent == 1) { for (i = 0; i < numcodes; i++) { if (frequencies[i]) { lengths[i] = 1; lengths[i == 0 ? 1 : 0] = 1; break; } } } else { /*Package-Merge algorithm represented by coin collector's problem For every symbol, maxbitlen coins will be created*/ coinmem = numpresent * 2; /*max amount of coins needed with the current algo*/ coins = (Coin*) lodepng_malloc(sizeof(Coin) * coinmem); prev_row = (Coin*) lodepng_malloc(sizeof(Coin) * coinmem); if (!coins || !prev_row) { lodepng_free(coins); lodepng_free(prev_row); return 83; /*alloc fail*/ } init_coins(coins, coinmem); init_coins(prev_row, coinmem); /*first row, lowest denominator*/ error = append_symbol_coins(coins, frequencies, numcodes, sum); numcoins = numpresent; qsort(coins, numcoins, sizeof(Coin), coin_compare); if (!error) { unsigned numprev = 0; for (j = 1; j <= maxbitlen && !error; j++) /*each of the remaining rows*/ { unsigned tempnum; Coin* tempcoins; /*swap prev_row and coins, and their amounts*/ tempcoins = prev_row; prev_row = coins; coins = tempcoins; tempnum = numprev; numprev = numcoins; numcoins = tempnum; cleanup_coins(coins, numcoins); init_coins(coins, numcoins); numcoins = 0; /*fill in the merged coins of the previous row*/ for (i = 0; i + 1 < numprev; i += 2) { /*merge prev_row[i] and prev_row[i + 1] into new coin*/ Coin* coin = &coins[numcoins++]; coin_copy(coin, &prev_row[i]); add_coins(coin, &prev_row[i + 1]); } /*fill in all the original symbols again*/ if (j < maxbitlen) { error = append_symbol_coins(coins + numcoins, frequencies, numcodes, sum); numcoins += numpresent; } qsort(coins, numcoins, sizeof(Coin), coin_compare); } } if (!error) { /*calculate the lenghts of each symbol, as the amount of times a coin of each symbol is used*/ for (i = 0; i < numpresent - 1; i++) { Coin* coin = &coins[i]; for (j = 0; j < coin->symbols.size; j++) lengths[coin->symbols.data[j]]++; } } cleanup_coins(coins, coinmem); lodepng_free(coins); cleanup_coins(prev_row, coinmem); lodepng_free(prev_row); } return error; } /*Create the Huffman tree given the symbol frequencies*/ static unsigned HuffmanTree_makeFromFrequencies(HuffmanTree* tree, const unsigned* frequencies, size_t mincodes, size_t numcodes, unsigned maxbitlen) { unsigned error = 0; while (!frequencies[numcodes - 1] && numcodes > mincodes) numcodes--; /*trim zeroes*/ tree->maxbitlen = maxbitlen; tree->numcodes = (unsigned) numcodes; /*number of symbols*/ tree->lengths = (unsigned*) lodepng_realloc(tree->lengths, numcodes * sizeof(unsigned)); if (!tree->lengths) return 83; /*alloc fail*/ /*initialize all lengths to 0*/ memset(tree->lengths, 0, numcodes * sizeof(unsigned)); error = lodepng_huffman_code_lengths(tree->lengths, frequencies, numcodes, maxbitlen); if (!error) error = HuffmanTree_makeFromLengths2(tree); return error; } static unsigned HuffmanTree_getCode(const HuffmanTree* tree, unsigned index) { return tree->tree1d[index]; } static unsigned HuffmanTree_getLength(const HuffmanTree* tree, unsigned index) { return tree->lengths[index]; } #endif /*LODEPNG_COMPILE_ENCODER*/ /*get the literal and length code tree of a deflated block with fixed tree, as per the deflate specification*/ static unsigned generateFixedLitLenTree(HuffmanTree* tree) { unsigned i, error = 0; unsigned* bitlen = (unsigned*) lodepng_malloc( NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); if (!bitlen) return 83; /*alloc fail*/ /*288 possible codes: 0-255=literals, 256=endcode, 257-285=lengthcodes, 286-287=unused*/ for (i = 0; i <= 143; i++) bitlen[i] = 8; for (i = 144; i <= 255; i++) bitlen[i] = 9; for (i = 256; i <= 279; i++) bitlen[i] = 7; for (i = 280; i <= 287; i++) bitlen[i] = 8; error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DEFLATE_CODE_SYMBOLS, 15); lodepng_free(bitlen); return error; } /*get the distance code tree of a deflated block with fixed tree, as specified in the deflate specification*/ static unsigned generateFixedDistanceTree(HuffmanTree* tree) { unsigned i, error = 0; unsigned* bitlen = (unsigned*) lodepng_malloc( NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); if (!bitlen) return 83; /*alloc fail*/ /*there are 32 distance codes, but 30-31 are unused*/ for (i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen[i] = 5; error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DISTANCE_SYMBOLS, 15); lodepng_free(bitlen); return error; } #ifdef LODEPNG_COMPILE_DECODER /* returns the code, or (unsigned)(-1) if error happened inbitlength is the length of the complete buffer, in bits (so its byte length times 8) */ static unsigned huffmanDecodeSymbol(const unsigned char* in, size_t* bp, const HuffmanTree* codetree, size_t inbitlength) { unsigned treepos = 0, ct; for (;;) { if (*bp >= inbitlength) return (unsigned) (-1); /*error: end of input memory reached without endcode*/ /* decode the symbol from the tree. The "readBitFromStream" code is inlined in the expression below because this is the biggest bottleneck while decoding */ ct = codetree->tree2d[(treepos << 1) + READBIT(*bp, in)]; (*bp)++; if (ct < codetree->numcodes) return ct; /*the symbol is decoded, return it*/ else treepos = ct - codetree->numcodes; /*symbol not yet decoded, instead move tree position*/ if (treepos >= codetree->numcodes) return (unsigned) (-1); /*error: it appeared outside the codetree*/ } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_DECODER /* ////////////////////////////////////////////////////////////////////////// */ /* / Inflator (Decompressor) / */ /* ////////////////////////////////////////////////////////////////////////// */ /*get the tree of a deflated block with fixed tree, as specified in the deflate specification*/ static void getTreeInflateFixed(HuffmanTree* tree_ll, HuffmanTree* tree_d) { /*TODO: check for out of memory errors*/ generateFixedLitLenTree(tree_ll); generateFixedDistanceTree(tree_d); } /*get the tree of a deflated block with dynamic tree, the tree itself is also Huffman compressed with a known tree*/ static unsigned getTreeInflateDynamic(HuffmanTree* tree_ll, HuffmanTree* tree_d, const unsigned char* in, size_t* bp, size_t inlength) { /*make sure that length values that aren't filled in will be 0, or a wrong tree will be generated*/ unsigned error = 0; unsigned n, HLIT, HDIST, HCLEN, i; size_t inbitlength = inlength * 8; /*see comments in deflateDynamic for explanation of the context and these variables, it is analogous*/ unsigned* bitlen_ll = 0; /*lit,len code lengths*/ unsigned* bitlen_d = 0; /*dist code lengths*/ /*code length code lengths ("clcl"), the bit lengths of the huffman tree used to compress bitlen_ll and bitlen_d*/ unsigned* bitlen_cl = 0; HuffmanTree tree_cl; /*the code tree for code length codes (the huffman tree for compressed huffman trees)*/ if ((*bp) >> 3 >= inlength - 2) return 49; /*error: the bit pointer is or will go past the memory*/ /*number of literal/length codes + 257. Unlike the spec, the value 257 is added to it here already*/ HLIT = readBitsFromStream(bp, in, 5) + 257; /*number of distance codes. Unlike the spec, the value 1 is added to it here already*/ HDIST = readBitsFromStream(bp, in, 5) + 1; /*number of code length codes. Unlike the spec, the value 4 is added to it here already*/ HCLEN = readBitsFromStream(bp, in, 4) + 4; HuffmanTree_init(&tree_cl); while (!error) { /*read the code length codes out of 3 * (amount of code length codes) bits*/ bitlen_cl = (unsigned*) lodepng_malloc( NUM_CODE_LENGTH_CODES * sizeof(unsigned)); if (!bitlen_cl) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < NUM_CODE_LENGTH_CODES; i++) { if (i < HCLEN) bitlen_cl[CLCL_ORDER[i]] = readBitsFromStream(bp, in, 3); else bitlen_cl[CLCL_ORDER[i]] = 0; /*if not, it must stay 0*/ } error = HuffmanTree_makeFromLengths(&tree_cl, bitlen_cl, NUM_CODE_LENGTH_CODES, 7); if (error) break; /*now we can use this tree to read the lengths for the tree that this function will return*/ bitlen_ll = (unsigned*) lodepng_malloc( NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); bitlen_d = (unsigned*) lodepng_malloc( NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); if (!bitlen_ll || !bitlen_d) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < NUM_DEFLATE_CODE_SYMBOLS; i++) bitlen_ll[i] = 0; for (i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen_d[i] = 0; /*i is the current symbol we're reading in the part that contains the code lengths of lit/len and dist codes*/ i = 0; while (i < HLIT + HDIST) { unsigned code = huffmanDecodeSymbol(in, bp, &tree_cl, inbitlength); if (code <= 15) /*a length code*/ { if (i < HLIT) bitlen_ll[i] = code; else bitlen_d[i - HLIT] = code; i++; } else if (code == 16) /*repeat previous*/ { unsigned replength = 3; /*read in the 2 bits that indicate repeat length (3-6)*/ unsigned value; /*set value to the previous code*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ if (i == 0) ERROR_BREAK(54); /*can't repeat previous if i is 0*/ replength += readBitsFromStream(bp, in, 2); if (i < HLIT + 1) value = bitlen_ll[i - 1]; else value = bitlen_d[i - HLIT - 1]; /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(13); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = value; else bitlen_d[i - HLIT] = value; i++; } } else if (code == 17) /*repeat "0" 3-10 times*/ { unsigned replength = 3; /*read in the bits that indicate repeat length*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ replength += readBitsFromStream(bp, in, 3); /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(14); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = 0; else bitlen_d[i - HLIT] = 0; i++; } } else if (code == 18) /*repeat "0" 11-138 times*/ { unsigned replength = 11; /*read in the bits that indicate repeat length*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ replength += readBitsFromStream(bp, in, 7); /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(15); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = 0; else bitlen_d[i - HLIT] = 0; i++; } } else /*if(code == (unsigned)(-1))*//*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { if (code == (unsigned) (-1)) { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inbitlength ? 10 : 11; } else error = 16; /*unexisting code, this can never happen*/ break; } } if (error) break; if (bitlen_ll[256] == 0) ERROR_BREAK(64); /*the length of the end code 256 must be larger than 0*/ /*now we've finally got HLIT and HDIST, so generate the code trees, and the function is done*/ error = HuffmanTree_makeFromLengths(tree_ll, bitlen_ll, NUM_DEFLATE_CODE_SYMBOLS, 15); if (error) break; error = HuffmanTree_makeFromLengths(tree_d, bitlen_d, NUM_DISTANCE_SYMBOLS, 15); break; /*end of error-while*/ } lodepng_free(bitlen_cl); lodepng_free(bitlen_ll); lodepng_free(bitlen_d); HuffmanTree_cleanup(&tree_cl); return error; } /*inflate a block with dynamic of fixed Huffman tree*/ static unsigned inflateHuffmanBlock(ucvector* out, const unsigned char* in, size_t* bp, size_t* pos, size_t inlength, unsigned btype) { unsigned error = 0; HuffmanTree tree_ll; /*the huffman tree for literal and length codes*/ HuffmanTree tree_d; /*the huffman tree for distance codes*/ size_t inbitlength = inlength * 8; HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); if (btype == 1) getTreeInflateFixed(&tree_ll, &tree_d); else if (btype == 2) error = getTreeInflateDynamic(&tree_ll, &tree_d, in, bp, inlength); while (!error) /*decode all symbols until end reached, breaks at end code*/ { /*code_ll is literal, length or end code*/ unsigned code_ll = huffmanDecodeSymbol(in, bp, &tree_ll, inbitlength); if (code_ll <= 255) /*literal symbol*/ { if ((*pos) >= out->size) { /*reserve more room at once*/ if (!ucvector_resize(out, ((*pos) + 1) * 2)) ERROR_BREAK(83 /*alloc fail*/); } out->data[(*pos)] = (unsigned char) (code_ll); (*pos)++; } else if (code_ll >= FIRST_LENGTH_CODE_INDEX && code_ll <= LAST_LENGTH_CODE_INDEX) /*length code*/ { unsigned code_d, distance; unsigned numextrabits_l, numextrabits_d; /*extra bits for length and distance*/ size_t start, forward, backward, length; /*part 1: get length base*/ length = LENGTHBASE[code_ll - FIRST_LENGTH_CODE_INDEX]; /*part 2: get extra bits and add the value of that to length*/ numextrabits_l = LENGTHEXTRA[code_ll - FIRST_LENGTH_CODE_INDEX]; if (*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ length += readBitsFromStream(bp, in, numextrabits_l); /*part 3: get distance code*/ code_d = huffmanDecodeSymbol(in, bp, &tree_d, inbitlength); if (code_d > 29) { if (code_ll == (unsigned) (-1)) /*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inlength * 8 ? 10 : 11; } else error = 18; /*error: invalid distance code (30-31 are never used)*/ break; } distance = DISTANCEBASE[code_d]; /*part 4: get extra bits from distance*/ numextrabits_d = DISTANCEEXTRA[code_d]; if (*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ distance += readBitsFromStream(bp, in, numextrabits_d); /*part 5: fill in all the out[n] values based on the length and dist*/ start = (*pos); if (distance > start) ERROR_BREAK(52); /*too long backward distance*/ backward = start - distance; if ((*pos) + length >= out->size) { /*reserve more room at once*/ if (!ucvector_resize(out, ((*pos) + length) * 2)) ERROR_BREAK(83 /*alloc fail*/); } for (forward = 0; forward < length; forward++) { out->data[(*pos)] = out->data[backward]; (*pos)++; backward++; if (backward >= start) backward = start - distance; } } else if (code_ll == 256) { break; /*end code, break the loop*/ } else /*if(code == (unsigned)(-1))*//*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inlength * 8 ? 10 : 11; break; } } HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); return error; } static unsigned inflateNoCompression(ucvector* out, const unsigned char* in, size_t* bp, size_t* pos, size_t inlength) { /*go to first boundary of byte*/ size_t p; unsigned LEN, NLEN, n, error = 0; while (((*bp) & 0x7) != 0) (*bp)++; p = (*bp) / 8; /*byte position*/ /*read LEN (2 bytes) and NLEN (2 bytes)*/ if (p >= inlength - 4) return 52; /*error, bit pointer will jump past memory*/ LEN = in[p] + 256u * in[p + 1]; p += 2; NLEN = in[p] + 256u * in[p + 1]; p += 2; /*check if 16-bit NLEN is really the one's complement of LEN*/ if (LEN + NLEN != 65535) return 21; /*error: NLEN is not one's complement of LEN*/ if ((*pos) + LEN >= out->size) { if (!ucvector_resize(out, (*pos) + LEN)) return 83; /*alloc fail*/ } /*read the literal data: LEN bytes are now stored in the out buffer*/ if (p + LEN > inlength) return 23; /*error: reading outside of in buffer*/ for (n = 0; n < LEN; n++) out->data[(*pos)++] = in[p++]; (*bp) = p * 8; return error; } static unsigned lodepng_inflatev(ucvector* out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { /*bit pointer in the "in" data, current byte is bp >> 3, current bit is bp & 0x7 (from lsb to msb of the byte)*/ size_t bp = 0; unsigned BFINAL = 0; size_t pos = 0; /*byte position in the out buffer*/ unsigned error = 0; (void) settings; while (!BFINAL) { unsigned BTYPE; if (bp + 2 >= insize * 8) return 52; /*error, bit pointer will jump past memory*/ BFINAL = readBitFromStream(&bp, in); BTYPE = 1u * readBitFromStream(&bp, in); BTYPE += 2u * readBitFromStream(&bp, in); if (BTYPE == 3) return 20; /*error: invalid BTYPE*/ else if (BTYPE == 0) error = inflateNoCompression(out, in, &bp, &pos, insize); /*no compression*/ else error = inflateHuffmanBlock(out, in, &bp, &pos, insize, BTYPE); /*compression, BTYPE 01 or 10*/ if (error) return error; } /*Only now we know the true size of out, resize it to that*/ if (!ucvector_resize(out, pos)) error = 83; /*alloc fail*/ return error; } unsigned lodepng_inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { unsigned error; ucvector v; ucvector_init_buffer(&v, *out, *outsize); error = lodepng_inflatev(&v, in, insize, settings); *out = v.data; *outsize = v.size; return error; } static unsigned inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (settings->custom_inflate) { return settings->custom_inflate(out, outsize, in, insize, settings); } else { return lodepng_inflate(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* ////////////////////////////////////////////////////////////////////////// */ /* / Deflator (Compressor) / */ /* ////////////////////////////////////////////////////////////////////////// */ static const size_t MAX_SUPPORTED_DEFLATE_LENGTH = 258; /*bitlen is the size in bits of the code*/ static void addHuffmanSymbol(size_t* bp, ucvector* compressed, unsigned code, unsigned bitlen) { addBitsToStreamReversed(bp, compressed, code, bitlen); } /*search the index in the array, that has the largest value smaller than or equal to the given value, given array must be sorted (if no value is smaller, it returns the size of the given array)*/ static size_t searchCodeIndex(const unsigned* array, size_t array_size, size_t value) { /*linear search implementation*/ /*for(size_t i = 1; i < array_size; i++) if(array[i] > value) return i - 1; return array_size - 1;*/ /*binary search implementation (not that much faster) (precondition: array_size > 0)*/ size_t left = 1; size_t right = array_size - 1; while (left <= right) { size_t mid = (left + right) / 2; if (array[mid] <= value) left = mid + 1; /*the value to find is more to the right*/ else if (array[mid - 1] > value) right = mid - 1; /*the value to find is more to the left*/ else return mid - 1; } return array_size - 1; } static void addLengthDistance(uivector* values, size_t length, size_t distance) { /*values in encoded vector are those used by deflate: 0-255: literal bytes 256: end 257-285: length/distance pair (length code, followed by extra length bits, distance code, extra distance bits) 286-287: invalid*/ unsigned length_code = (unsigned) searchCodeIndex(LENGTHBASE, 29, length); unsigned extra_length = (unsigned) (length - LENGTHBASE[length_code]); unsigned dist_code = (unsigned) searchCodeIndex(DISTANCEBASE, 30, distance); unsigned extra_distance = (unsigned) (distance - DISTANCEBASE[dist_code]); uivector_push_back(values, length_code + FIRST_LENGTH_CODE_INDEX); uivector_push_back(values, extra_length); uivector_push_back(values, dist_code); uivector_push_back(values, extra_distance); } /*3 bytes of data get encoded into two bytes. The hash cannot use more than 3 bytes as input because 3 is the minimum match length for deflate*/ static const unsigned HASH_NUM_VALUES = 65536; static const unsigned HASH_BIT_MASK = 65535; /*HASH_NUM_VALUES - 1, but C90 does not like that as initializer*/ typedef struct Hash { int* head; /*hash value to head circular pos - can be outdated if went around window*/ /*circular pos to prev circular pos*/ unsigned short* chain; int* val; /*circular pos to hash value*/ /*TODO: do this not only for zeros but for any repeated byte. However for PNG it's always going to be the zeros that dominate, so not important for PNG*/ int* headz; /*similar to head, but for chainz*/ unsigned short* chainz; /*those with same amount of zeros*/ unsigned short* zeros; /*length of zeros streak, used as a second hash chain*/ } Hash; static unsigned hash_init(Hash* hash, unsigned windowsize) { unsigned i; hash->head = (int*) lodepng_malloc(sizeof(int) * HASH_NUM_VALUES); hash->val = (int*) lodepng_malloc(sizeof(int) * windowsize); hash->chain = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); hash->zeros = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); hash->headz = (int*) lodepng_malloc( sizeof(int) * (MAX_SUPPORTED_DEFLATE_LENGTH + 1)); hash->chainz = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); if (!hash->head || !hash->chain || !hash->val || !hash->headz || !hash->chainz || !hash->zeros) { return 83; /*alloc fail*/ } /*initialize hash table*/ for (i = 0; i < HASH_NUM_VALUES; i++) hash->head[i] = -1; for (i = 0; i < windowsize; i++) hash->val[i] = -1; for (i = 0; i < windowsize; i++) hash->chain[i] = i; /*same value as index indicates uninitialized*/ for (i = 0; i <= MAX_SUPPORTED_DEFLATE_LENGTH; i++) hash->headz[i] = -1; for (i = 0; i < windowsize; i++) hash->chainz[i] = i; /*same value as index indicates uninitialized*/ return 0; } static void hash_cleanup(Hash* hash) { lodepng_free(hash->head); lodepng_free(hash->val); lodepng_free(hash->chain); lodepng_free(hash->zeros); lodepng_free(hash->headz); lodepng_free(hash->chainz); } static unsigned getHash(const unsigned char* data, size_t size, size_t pos) { unsigned result = 0; if (pos + 2 < size) { /*A simple shift and xor hash is used. Since the data of PNGs is dominated by zeroes due to the filters, a better hash does not have a significant effect on speed in traversing the chain, and causes more time spend on calculating the hash.*/ result ^= (unsigned) (data[pos + 0] << 0u); result ^= (unsigned) (data[pos + 1] << 4u); result ^= (unsigned) (data[pos + 2] << 8u); } else { size_t amount, i; if (pos >= size) return 0; amount = size - pos; for (i = 0; i < amount; i++) result ^= (unsigned) (data[pos + i] << (i * 8u)); } return result & HASH_BIT_MASK; } static unsigned countZeros(const unsigned char* data, size_t size, size_t pos) { const unsigned char* start = data + pos; const unsigned char* end = start + MAX_SUPPORTED_DEFLATE_LENGTH; if (end > data + size) end = data + size; data = start; while (data != end && *data == 0) data++; /*subtracting two addresses returned as 32-bit number (max value is MAX_SUPPORTED_DEFLATE_LENGTH)*/ return (unsigned) (data - start); } /*wpos = pos & (windowsize - 1)*/ static void updateHashChain(Hash* hash, size_t wpos, unsigned hashval, unsigned short numzeros) { hash->val[wpos] = (int) hashval; if (hash->head[hashval] != -1) hash->chain[wpos] = hash->head[hashval]; hash->head[hashval] = wpos; hash->zeros[wpos] = numzeros; if (hash->headz[numzeros] != -1) hash->chainz[wpos] = hash->headz[numzeros]; hash->headz[numzeros] = wpos; } /* LZ77-encode the data. Return value is error code. The input are raw bytes, the output is in the form of unsigned integers with codes representing for example literal bytes, or length/distance pairs. It uses a hash table technique to let it encode faster. When doing LZ77 encoding, a sliding window (of windowsize) is used, and all past bytes in that window can be used as the "dictionary". A brute force search through all possible distances would be slow, and this hash technique is one out of several ways to speed this up. */ static unsigned encodeLZ77(uivector* out, Hash* hash, const unsigned char* in, size_t inpos, size_t insize, unsigned windowsize, unsigned minmatch, unsigned nicematch, unsigned lazymatching) { size_t pos; unsigned i, error = 0; /*for large window lengths, assume the user wants no compression loss. Otherwise, max hash chain length speedup.*/ unsigned maxchainlength = windowsize >= 8192 ? windowsize : windowsize / 8; unsigned maxlazymatch = windowsize >= 8192 ? MAX_SUPPORTED_DEFLATE_LENGTH : 64; unsigned usezeros = 1; /*not sure if setting it to false for windowsize < 8192 is better or worse*/ unsigned numzeros = 0; unsigned offset; /*the offset represents the distance in LZ77 terminology*/ unsigned length; unsigned lazy = 0; unsigned lazylength = 0, lazyoffset = 0; unsigned hashval; unsigned current_offset, current_length; unsigned prev_offset; const unsigned char *lastptr, *foreptr, *backptr; unsigned hashpos; if (windowsize <= 0 || windowsize > 32768) return 60; /*error: windowsize smaller/larger than allowed*/ if ((windowsize & (windowsize - 1)) != 0) return 90; /*error: must be power of two*/ if (nicematch > MAX_SUPPORTED_DEFLATE_LENGTH) nicematch = MAX_SUPPORTED_DEFLATE_LENGTH; for (pos = inpos; pos < insize; pos++) { size_t wpos = pos & (windowsize - 1); /*position for in 'circular' hash buffers*/ unsigned chainlength = 0; hashval = getHash(in, insize, pos); if (usezeros && hashval == 0) { if (numzeros == 0) numzeros = countZeros(in, insize, pos); else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; } else { numzeros = 0; } updateHashChain(hash, wpos, hashval, numzeros); /*the length and offset found for the current position*/ length = 0; offset = 0; hashpos = hash->chain[wpos]; lastptr = &in[ insize < pos + MAX_SUPPORTED_DEFLATE_LENGTH ? insize : pos + MAX_SUPPORTED_DEFLATE_LENGTH]; /*search for the longest string*/ prev_offset = 0; for (;;) { if (chainlength++ >= maxchainlength) break; current_offset = hashpos <= wpos ? wpos - hashpos : wpos - hashpos + windowsize; if (current_offset < prev_offset) break; /*stop when went completely around the circular buffer*/ prev_offset = current_offset; if (current_offset > 0) { /*test the next characters*/ foreptr = &in[pos]; backptr = &in[pos - current_offset]; /*common case in PNGs is lots of zeros. Quickly skip over them as a speedup*/ if (numzeros >= 3) { unsigned skip = hash->zeros[hashpos]; if (skip > numzeros) skip = numzeros; backptr += skip; foreptr += skip; } while (foreptr != lastptr && *backptr == *foreptr) /*maximum supported length by deflate is max length*/ { ++backptr; ++foreptr; } current_length = (unsigned) (foreptr - &in[pos]); if (current_length > length) { length = current_length; /*the longest length*/ offset = current_offset; /*the offset that is related to this longest length*/ /*jump out once a length of max length is found (speed gain). This also jumps out if length is MAX_SUPPORTED_DEFLATE_LENGTH*/ if (current_length >= nicematch) break; } } if (hashpos == hash->chain[hashpos]) break; if (numzeros >= 3 && length > numzeros) { hashpos = hash->chainz[hashpos]; if (hash->zeros[hashpos] != numzeros) break; } else { hashpos = hash->chain[hashpos]; /*outdated hash value, happens if particular value was not encountered in whole last window*/ if (hash->val[hashpos] != (int) hashval) break; } } if (lazymatching) { if (!lazy && length >= 3 && length <= maxlazymatch && length < MAX_SUPPORTED_DEFLATE_LENGTH) { lazy = 1; lazylength = length; lazyoffset = offset; continue; /*try the next byte*/ } if (lazy) { lazy = 0; if (pos == 0) ERROR_BREAK(81); if (length > lazylength + 1) { /*push the previous character as literal*/ if (!uivector_push_back(out, in[pos - 1])) ERROR_BREAK(83 /*alloc fail*/); } else { length = lazylength; offset = lazyoffset; hash->head[hashval] = -1; /*the same hashchain update will be done, this ensures no wrong alteration*/ hash->headz[numzeros] = -1; /*idem*/ pos--; } } } if (length >= 3 && offset > windowsize) ERROR_BREAK(86 /*too big (or overflown negative) offset*/); /*encode it as length/distance pair or literal value*/ if (length < 3) /*only lengths of 3 or higher are supported as length/distance pair*/ { if (!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); } else if (length < minmatch || (length == 3 && offset > 4096)) { /*compensate for the fact that longer offsets have more extra bits, a length of only 3 may be not worth it then*/ if (!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); } else { addLengthDistance(out, length, offset); for (i = 1; i < length; i++) { pos++; wpos = pos & (windowsize - 1); hashval = getHash(in, insize, pos); if (usezeros && hashval == 0) { if (numzeros == 0) numzeros = countZeros(in, insize, pos); else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; } else { numzeros = 0; } updateHashChain(hash, wpos, hashval, numzeros); } } } /*end of the loop through each character of input*/ return error; } /* /////////////////////////////////////////////////////////////////////////// */ static unsigned deflateNoCompression(ucvector* out, const unsigned char* data, size_t datasize) { /*non compressed deflate block data: 1 bit BFINAL,2 bits BTYPE,(5 bits): it jumps to start of next byte, 2 bytes LEN, 2 bytes NLEN, LEN bytes literal DATA*/ size_t i, j, numdeflateblocks = (datasize + 65534) / 65535; unsigned datapos = 0; for (i = 0; i < numdeflateblocks; i++) { unsigned BFINAL, BTYPE, LEN, NLEN; unsigned char firstbyte; BFINAL = (i == numdeflateblocks - 1); BTYPE = 0; firstbyte = (unsigned char) (BFINAL + ((BTYPE & 1) << 1) + ((BTYPE & 2) << 1)); ucvector_push_back(out, firstbyte); LEN = 65535; if (datasize - datapos < 65535) LEN = (unsigned) datasize - datapos; NLEN = 65535 - LEN; ucvector_push_back(out, (unsigned char) (LEN % 256)); ucvector_push_back(out, (unsigned char) (LEN / 256)); ucvector_push_back(out, (unsigned char) (NLEN % 256)); ucvector_push_back(out, (unsigned char) (NLEN / 256)); /*Decompressed data*/ for (j = 0; j < 65535 && datapos < datasize; j++) { ucvector_push_back(out, data[datapos++]); } } return 0; } /* write the lz77-encoded data, which has lit, len and dist codes, to compressed stream using huffman trees. tree_ll: the tree for lit and len codes. tree_d: the tree for distance codes. */ static void writeLZ77data(size_t* bp, ucvector* out, const uivector* lz77_encoded, const HuffmanTree* tree_ll, const HuffmanTree* tree_d) { size_t i = 0; for (i = 0; i < lz77_encoded->size; i++) { unsigned val = lz77_encoded->data[i]; addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_ll, val), HuffmanTree_getLength(tree_ll, val)); if (val > 256) /*for a length code, 3 more things have to be added*/ { unsigned length_index = val - FIRST_LENGTH_CODE_INDEX; unsigned n_length_extra_bits = LENGTHEXTRA[length_index]; unsigned length_extra_bits = lz77_encoded->data[++i]; unsigned distance_code = lz77_encoded->data[++i]; unsigned distance_index = distance_code; unsigned n_distance_extra_bits = DISTANCEEXTRA[distance_index]; unsigned distance_extra_bits = lz77_encoded->data[++i]; addBitsToStream(bp, out, length_extra_bits, n_length_extra_bits); addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_d, distance_code), HuffmanTree_getLength(tree_d, distance_code)); addBitsToStream(bp, out, distance_extra_bits, n_distance_extra_bits); } } } /*Deflate for a block of type "dynamic", that is, with freely, optimally, created huffman trees*/ static unsigned deflateDynamic(ucvector* out, size_t* bp, Hash* hash, const unsigned char* data, size_t datapos, size_t dataend, const LodePNGCompressSettings* settings, unsigned final) { unsigned error = 0; /* A block is compressed as follows: The PNG data is lz77 encoded, resulting in literal bytes and length/distance pairs. This is then huffman compressed with two huffman trees. One huffman tree is used for the lit and len values ("ll"), another huffman tree is used for the dist values ("d"). These two trees are stored using their code lengths, and to compress even more these code lengths are also run-length encoded and huffman compressed. This gives a huffman tree of code lengths "cl". The code lenghts used to describe this third tree are the code length code lengths ("clcl"). */ /*The lz77 encoded data, represented with integers since there will also be length and distance codes in it*/ uivector lz77_encoded; HuffmanTree tree_ll; /*tree for lit,len values*/ HuffmanTree tree_d; /*tree for distance codes*/ HuffmanTree tree_cl; /*tree for encoding the code lengths representing tree_ll and tree_d*/ uivector frequencies_ll; /*frequency of lit,len codes*/ uivector frequencies_d; /*frequency of dist codes*/ uivector frequencies_cl; /*frequency of code length codes*/ uivector bitlen_lld; /*lit,len,dist code lenghts (int bits), literally (without repeat codes).*/ uivector bitlen_lld_e; /*bitlen_lld encoded with repeat codes (this is a rudemtary run length compression)*/ /*bitlen_cl is the code length code lengths ("clcl"). The bit lengths of codes to represent tree_cl (these are written as is in the file, it would be crazy to compress these using yet another huffman tree that needs to be represented by yet another set of code lengths)*/ uivector bitlen_cl; size_t datasize = dataend - datapos; /* Due to the huffman compression of huffman tree representations ("two levels"), there are some anologies: bitlen_lld is to tree_cl what data is to tree_ll and tree_d. bitlen_lld_e is to bitlen_lld what lz77_encoded is to data. bitlen_cl is to bitlen_lld_e what bitlen_lld is to lz77_encoded. */ unsigned BFINAL = final; size_t numcodes_ll, numcodes_d, i; unsigned HLIT, HDIST, HCLEN; uivector_init(&lz77_encoded); HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); HuffmanTree_init(&tree_cl); uivector_init(&frequencies_ll); uivector_init(&frequencies_d); uivector_init(&frequencies_cl); uivector_init(&bitlen_lld); uivector_init(&bitlen_lld_e); uivector_init(&bitlen_cl); /*This while loop never loops due to a break at the end, it is here to allow breaking out of it to the cleanup phase on error conditions.*/ while (!error) { if (settings->use_lz77) { error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, settings->minmatch, settings->nicematch, settings->lazymatching); if (error) break; } else { if (!uivector_resize(&lz77_encoded, datasize)) ERROR_BREAK(83 /*alloc fail*/); for (i = datapos; i < dataend; i++) lz77_encoded.data[i] = data[i]; /*no LZ77, but still will be Huffman compressed*/ } if (!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83 /*alloc fail*/); if (!uivector_resizev(&frequencies_d, 30, 0)) ERROR_BREAK(83 /*alloc fail*/); /*Count the frequencies of lit, len and dist codes*/ for (i = 0; i < lz77_encoded.size; i++) { unsigned symbol = lz77_encoded.data[i]; frequencies_ll.data[symbol]++; if (symbol > 256) { unsigned dist = lz77_encoded.data[i + 2]; frequencies_d.data[dist]++; i += 3; } } frequencies_ll.data[256] = 1; /*there will be exactly 1 end code, at the end of the block*/ /*Make both huffman trees, one for the lit and len codes, one for the dist codes*/ error = HuffmanTree_makeFromFrequencies(&tree_ll, frequencies_ll.data, 257, frequencies_ll.size, 15); if (error) break; /*2, not 1, is chosen for mincodes: some buggy PNG decoders require at least 2 symbols in the dist tree*/ error = HuffmanTree_makeFromFrequencies(&tree_d, frequencies_d.data, 2, frequencies_d.size, 15); if (error) break; numcodes_ll = tree_ll.numcodes; if (numcodes_ll > 286) numcodes_ll = 286; numcodes_d = tree_d.numcodes; if (numcodes_d > 30) numcodes_d = 30; /*store the code lengths of both generated trees in bitlen_lld*/ for (i = 0; i < numcodes_ll; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_ll, (unsigned) i)); for (i = 0; i < numcodes_d; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_d, (unsigned) i)); /*run-length compress bitlen_ldd into bitlen_lld_e by using repeat codes 16 (copy length 3-6 times), 17 (3-10 zeroes), 18 (11-138 zeroes)*/ for (i = 0; i < (unsigned) bitlen_lld.size; i++) { unsigned j = 0; /*amount of repititions*/ while (i + j + 1 < (unsigned) bitlen_lld.size && bitlen_lld.data[i + j + 1] == bitlen_lld.data[i]) j++; if (bitlen_lld.data[i] == 0 && j >= 2) /*repeat code for zeroes*/ { j++; /*include the first zero*/ if (j <= 10) /*repeat code 17 supports max 10 zeroes*/ { uivector_push_back(&bitlen_lld_e, 17); uivector_push_back(&bitlen_lld_e, j - 3); } else /*repeat code 18 supports max 138 zeroes*/ { if (j > 138) j = 138; uivector_push_back(&bitlen_lld_e, 18); uivector_push_back(&bitlen_lld_e, j - 11); } i += (j - 1); } else if (j >= 3) /*repeat code for value other than zero*/ { size_t k; unsigned num = j / 6, rest = j % 6; uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); for (k = 0; k < num; k++) { uivector_push_back(&bitlen_lld_e, 16); uivector_push_back(&bitlen_lld_e, 6 - 3); } if (rest >= 3) { uivector_push_back(&bitlen_lld_e, 16); uivector_push_back(&bitlen_lld_e, rest - 3); } else j -= rest; i += j; } else /*too short to benefit from repeat code*/ { uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); } } /*generate tree_cl, the huffmantree of huffmantrees*/ if (!uivector_resizev(&frequencies_cl, NUM_CODE_LENGTH_CODES, 0)) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < bitlen_lld_e.size; i++) { frequencies_cl.data[bitlen_lld_e.data[i]]++; /*after a repeat code come the bits that specify the number of repetitions, those don't need to be in the frequencies_cl calculation*/ if (bitlen_lld_e.data[i] >= 16) i++; } error = HuffmanTree_makeFromFrequencies(&tree_cl, frequencies_cl.data, frequencies_cl.size, frequencies_cl.size, 7); if (error) break; if (!uivector_resize(&bitlen_cl, tree_cl.numcodes)) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < tree_cl.numcodes; i++) { /*lenghts of code length tree is in the order as specified by deflate*/ bitlen_cl.data[i] = HuffmanTree_getLength(&tree_cl, CLCL_ORDER[i]); } while (bitlen_cl.data[bitlen_cl.size - 1] == 0 && bitlen_cl.size > 4) { /*remove zeros at the end, but minimum size must be 4*/ if (!uivector_resize(&bitlen_cl, bitlen_cl.size - 1)) ERROR_BREAK(83 /*alloc fail*/); } if (error) break; /* Write everything into the output After the BFINAL and BTYPE, the dynamic block consists out of the following: - 5 bits HLIT, 5 bits HDIST, 4 bits HCLEN - (HCLEN+4)*3 bits code lengths of code length alphabet - HLIT + 257 code lenghts of lit/length alphabet (encoded using the code length alphabet, + possible repetition codes 16, 17, 18) - HDIST + 1 code lengths of distance alphabet (encoded using the code length alphabet, + possible repetition codes 16, 17, 18) - compressed data - 256 (end code) */ /*Write block type*/ addBitToStream(bp, out, BFINAL); addBitToStream(bp, out, 0); /*first bit of BTYPE "dynamic"*/ addBitToStream(bp, out, 1); /*second bit of BTYPE "dynamic"*/ /*write the HLIT, HDIST and HCLEN values*/ HLIT = (unsigned) (numcodes_ll - 257); HDIST = (unsigned) (numcodes_d - 1); HCLEN = (unsigned) bitlen_cl.size - 4; /*trim zeroes for HCLEN. HLIT and HDIST were already trimmed at tree creation*/ while (!bitlen_cl.data[HCLEN + 4 - 1] && HCLEN > 0) HCLEN--; addBitsToStream(bp, out, HLIT, 5); addBitsToStream(bp, out, HDIST, 5); addBitsToStream(bp, out, HCLEN, 4); /*write the code lenghts of the code length alphabet*/ for (i = 0; i < HCLEN + 4; i++) addBitsToStream(bp, out, bitlen_cl.data[i], 3); /*write the lenghts of the lit/len AND the dist alphabet*/ for (i = 0; i < bitlen_lld_e.size; i++) { addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_cl, bitlen_lld_e.data[i]), HuffmanTree_getLength(&tree_cl, bitlen_lld_e.data[i])); /*extra bits of repeat codes*/ if (bitlen_lld_e.data[i] == 16) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 2); else if (bitlen_lld_e.data[i] == 17) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 3); else if (bitlen_lld_e.data[i] == 18) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 7); } /*write the compressed data symbols*/ writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); /*error: the length of the end code 256 must be larger than 0*/ if (HuffmanTree_getLength(&tree_ll, 256) == 0) ERROR_BREAK(64); /*write the end code*/ addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); break; /*end of error-while*/ } /*cleanup*/ uivector_cleanup(&lz77_encoded); HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); HuffmanTree_cleanup(&tree_cl); uivector_cleanup(&frequencies_ll); uivector_cleanup(&frequencies_d); uivector_cleanup(&frequencies_cl); uivector_cleanup(&bitlen_lld_e); uivector_cleanup(&bitlen_lld); uivector_cleanup(&bitlen_cl); return error; } static unsigned deflateFixed(ucvector* out, size_t* bp, Hash* hash, const unsigned char* data, size_t datapos, size_t dataend, const LodePNGCompressSettings* settings, unsigned final) { HuffmanTree tree_ll; /*tree for literal values and length codes*/ HuffmanTree tree_d; /*tree for distance codes*/ unsigned BFINAL = final; unsigned error = 0; size_t i; HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); generateFixedLitLenTree(&tree_ll); generateFixedDistanceTree(&tree_d); addBitToStream(bp, out, BFINAL); addBitToStream(bp, out, 1); /*first bit of BTYPE*/ addBitToStream(bp, out, 0); /*second bit of BTYPE*/ if (settings->use_lz77) /*LZ77 encoded*/ { uivector lz77_encoded; uivector_init(&lz77_encoded); error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, settings->minmatch, settings->nicematch, settings->lazymatching); if (!error) writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); uivector_cleanup(&lz77_encoded); } else /*no LZ77, but still will be Huffman compressed*/ { for (i = datapos; i < dataend; i++) { addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, data[i]), HuffmanTree_getLength(&tree_ll, data[i])); } } /*add END code*/ if (!error) addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); /*cleanup*/ HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); return error; } static unsigned lodepng_deflatev(ucvector* out, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { unsigned error = 0; size_t i, blocksize, numdeflateblocks; size_t bp = 0; /*the bit pointer*/ Hash hash; if (settings->btype > 2) return 61; else if (settings->btype == 0) return deflateNoCompression(out, in, insize); else if (settings->btype == 1) blocksize = insize; else /*if(settings->btype == 2)*/ { blocksize = insize / 8 + 8; if (blocksize < 65535) blocksize = 65535; } numdeflateblocks = (insize + blocksize - 1) / blocksize; if (numdeflateblocks == 0) numdeflateblocks = 1; error = hash_init(&hash, settings->windowsize); if (error) return error; for (i = 0; i < numdeflateblocks && !error; i++) { unsigned final = (i == numdeflateblocks - 1); size_t start = i * blocksize; size_t end = start + blocksize; if (end > insize) end = insize; if (settings->btype == 1) error = deflateFixed(out, &bp, &hash, in, start, end, settings, final); else if (settings->btype == 2) error = deflateDynamic(out, &bp, &hash, in, start, end, settings, final); } hash_cleanup(&hash); return error; } unsigned lodepng_deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { unsigned error; ucvector v; ucvector_init_buffer(&v, *out, *outsize); error = lodepng_deflatev(&v, in, insize, settings); *out = v.data; *outsize = v.size; return error; } static unsigned deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (settings->custom_deflate) { return settings->custom_deflate(out, outsize, in, insize, settings); } else { return lodepng_deflate(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / Adler32 */ /* ////////////////////////////////////////////////////////////////////////// */ static unsigned update_adler32(unsigned adler, const unsigned char* data, unsigned len) { unsigned s1 = adler & 0xffff; unsigned s2 = (adler >> 16) & 0xffff; while (len > 0) { /*at least 5550 sums can be done before the sums overflow, saving a lot of module divisions*/ unsigned amount = len > 5550 ? 5550 : len; len -= amount; while (amount > 0) { s1 += (*data++); s2 += s1; amount--; } s1 %= 65521; s2 %= 65521; } return (s2 << 16) | s1; } /*Return the adler32 of the bytes data[0..len-1]*/ static unsigned adler32(const unsigned char* data, unsigned len) { return update_adler32(1L, data, len); } /* ////////////////////////////////////////////////////////////////////////// */ /* / Zlib / */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_DECODER unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { unsigned error = 0; unsigned CM, CINFO, FDICT; if (insize < 2) return 53; /*error, size of zlib data too small*/ /*read information from zlib header*/ if ((in[0] * 256 + in[1]) % 31 != 0) { /*error: 256 * in[0] + in[1] must be a multiple of 31, the FCHECK value is supposed to be made that way*/ return 24; } CM = in[0] & 15; CINFO = (in[0] >> 4) & 15; /*FCHECK = in[1] & 31;*//*FCHECK is already tested above*/ FDICT = (in[1] >> 5) & 1; /*FLEVEL = (in[1] >> 6) & 3;*//*FLEVEL is not used here*/ if (CM != 8 || CINFO > 7) { /*error: only compression method 8: inflate with sliding window of 32k is supported by the PNG spec*/ return 25; } if (FDICT != 0) { /*error: the specification of PNG says about the zlib stream: "The additional flags shall not specify a preset dictionary."*/ return 26; } error = inflate(out, outsize, in + 2, insize - 2, settings); if (error) return error; if (!settings->ignore_adler32) { unsigned ADLER32 = lodepng_read32bitInt(&in[insize - 4]); unsigned checksum = adler32(*out, (unsigned) (*outsize)); if (checksum != ADLER32) return 58; /*error, adler checksum not correct, data must be corrupted*/ } return 0; /*no error*/ } static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (settings->custom_zlib) { return settings->custom_zlib(out, outsize, in, insize, settings); } else { return lodepng_zlib_decompress(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { /*initially, *out must be NULL and outsize 0, if you just give some random *out that's pointing to a non allocated buffer, this'll crash*/ ucvector outv; size_t i; unsigned error; unsigned char* deflatedata = 0; size_t deflatesize = 0; unsigned ADLER32; /*zlib data: 1 byte CMF (CM+CINFO), 1 byte FLG, deflate data, 4 byte ADLER32 checksum of the Decompressed data*/ unsigned CMF = 120; /*0b01111000: CM 8, CINFO 7. With CINFO 7, any window size up to 32768 can be used.*/ unsigned FLEVEL = 0; unsigned FDICT = 0; unsigned CMFFLG = 256 * CMF + FDICT * 32 + FLEVEL * 64; unsigned FCHECK = 31 - CMFFLG % 31; CMFFLG += FCHECK; /*ucvector-controlled version of the output buffer, for dynamic array*/ ucvector_init_buffer(&outv, *out, *outsize); ucvector_push_back(&outv, (unsigned char) (CMFFLG / 256)); ucvector_push_back(&outv, (unsigned char) (CMFFLG % 256)); error = deflate(&deflatedata, &deflatesize, in, insize, settings); if (!error) { ADLER32 = adler32(in, (unsigned) insize); for (i = 0; i < deflatesize; i++) ucvector_push_back(&outv, deflatedata[i]); lodepng_free(deflatedata); lodepng_add32bitInt(&outv, ADLER32); } *out = outv.data; *outsize = outv.size; return error; } /* compress using the default or custom zlib function */ static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (settings->custom_zlib) { return settings->custom_zlib(out, outsize, in, insize, settings); } else { return lodepng_zlib_compress(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_ENCODER*/ #else /*no LODEPNG_COMPILE_ZLIB*/ #ifdef LODEPNG_COMPILE_DECODER static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ return settings->custom_zlib(out, outsize, in, insize, settings); } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ return settings->custom_zlib(out, outsize, in, insize, settings); } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_ENCODER /*this is a good tradeoff between speed and compression ratio*/ #define DEFAULT_WINDOWSIZE 2048 void lodepng_compress_settings_init(LodePNGCompressSettings* settings) { /*compress with dynamic huffman tree (not in the mathematical sense, just not the predefined one)*/ settings->btype = 2; settings->use_lz77 = 1; settings->windowsize = DEFAULT_WINDOWSIZE; settings->minmatch = 3; settings->nicematch = 128; settings->lazymatching = 1; settings->custom_zlib = 0; settings->custom_deflate = 0; settings->custom_context = 0; } const LodePNGCompressSettings lodepng_default_compress_settings = { 2, 1, DEFAULT_WINDOWSIZE, 3, 128, 1, 0, 0, 0 }; #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DECODER void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings) { settings->ignore_adler32 = 0; settings->custom_zlib = 0; settings->custom_inflate = 0; settings->custom_context = 0; } const LodePNGDecompressSettings lodepng_default_decompress_settings = { 0, 0, 0, 0 }; #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // End of Zlib related code. Begin of PNG related code. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_PNG /* ////////////////////////////////////////////////////////////////////////// */ /* / CRC32 / */ /* ////////////////////////////////////////////////////////////////////////// */ /* CRC polynomial: 0xedb88320 */ static unsigned lodepng_crc32_table[256] = { 0u, 1996959894u, 3993919788u, 2567524794u, 124634137u, 1886057615u, 3915621685u, 2657392035u, 249268274u, 2044508324u, 3772115230u, 2547177864u, 162941995u, 2125561021u, 3887607047u, 2428444049u, 498536548u, 1789927666u, 4089016648u, 2227061214u, 450548861u, 1843258603u, 4107580753u, 2211677639u, 325883990u, 1684777152u, 4251122042u, 2321926636u, 335633487u, 1661365465u, 4195302755u, 2366115317u, 997073096u, 1281953886u, 3579855332u, 2724688242u, 1006888145u, 1258607687u, 3524101629u, 2768942443u, 901097722u, 1119000684u, 3686517206u, 2898065728u, 853044451u, 1172266101u, 3705015759u, 2882616665u, 651767980u, 1373503546u, 3369554304u, 3218104598u, 565507253u, 1454621731u, 3485111705u, 3099436303u, 671266974u, 1594198024u, 3322730930u, 2970347812u, 795835527u, 1483230225u, 3244367275u, 3060149565u, 1994146192u, 31158534u, 2563907772u, 4023717930u, 1907459465u, 112637215u, 2680153253u, 3904427059u, 2013776290u, 251722036u, 2517215374u, 3775830040u, 2137656763u, 141376813u, 2439277719u, 3865271297u, 1802195444u, 476864866u, 2238001368u, 4066508878u, 1812370925u, 453092731u, 2181625025u, 4111451223u, 1706088902u, 314042704u, 2344532202u, 4240017532u, 1658658271u, 366619977u, 2362670323u, 4224994405u, 1303535960u, 984961486u, 2747007092u, 3569037538u, 1256170817u, 1037604311u, 2765210733u, 3554079995u, 1131014506u, 879679996u, 2909243462u, 3663771856u, 1141124467u, 855842277u, 2852801631u, 3708648649u, 1342533948u, 654459306u, 3188396048u, 3373015174u, 1466479909u, 544179635u, 3110523913u, 3462522015u, 1591671054u, 702138776u, 2966460450u, 3352799412u, 1504918807u, 783551873u, 3082640443u, 3233442989u, 3988292384u, 2596254646u, 62317068u, 1957810842u, 3939845945u, 2647816111u, 81470997u, 1943803523u, 3814918930u, 2489596804u, 225274430u, 2053790376u, 3826175755u, 2466906013u, 167816743u, 2097651377u, 4027552580u, 2265490386u, 503444072u, 1762050814u, 4150417245u, 2154129355u, 426522225u, 1852507879u, 4275313526u, 2312317920u, 282753626u, 1742555852u, 4189708143u, 2394877945u, 397917763u, 1622183637u, 3604390888u, 2714866558u, 953729732u, 1340076626u, 3518719985u, 2797360999u, 1068828381u, 1219638859u, 3624741850u, 2936675148u, 906185462u, 1090812512u, 3747672003u, 2825379669u, 829329135u, 1181335161u, 3412177804u, 3160834842u, 628085408u, 1382605366u, 3423369109u, 3138078467u, 570562233u, 1426400815u, 3317316542u, 2998733608u, 733239954u, 1555261956u, 3268935591u, 3050360625u, 752459403u, 1541320221u, 2607071920u, 3965973030u, 1969922972u, 40735498u, 2617837225u, 3943577151u, 1913087877u, 83908371u, 2512341634u, 3803740692u, 2075208622u, 213261112u, 2463272603u, 3855990285u, 2094854071u, 198958881u, 2262029012u, 4057260610u, 1759359992u, 534414190u, 2176718541u, 4139329115u, 1873836001u, 414664567u, 2282248934u, 4279200368u, 1711684554u, 285281116u, 2405801727u, 4167216745u, 1634467795u, 376229701u, 2685067896u, 3608007406u, 1308918612u, 956543938u, 2808555105u, 3495958263u, 1231636301u, 1047427035u, 2932959818u, 3654703836u, 1088359270u, 936918000u, 2847714899u, 3736837829u, 1202900863u, 817233897u, 3183342108u, 3401237130u, 1404277552u, 615818150u, 3134207493u, 3453421203u, 1423857449u, 601450431u, 3009837614u, 3294710456u, 1567103746u, 711928724u, 3020668471u, 3272380065u, 1510334235u, 755167117u }; /*Return the CRC of the bytes buf[0..len-1].*/ unsigned lodepng_crc32(const unsigned char* buf, size_t len) { unsigned c = 0xffffffffL; size_t n; for (n = 0; n < len; n++) { c = lodepng_crc32_table[(c ^ buf[n]) & 0xff] ^ (c >> 8); } return c ^ 0xffffffffL; } /* ////////////////////////////////////////////////////////////////////////// */ /* / Reading and writing single bits and bytes from/to stream for LodePNG / */ /* ////////////////////////////////////////////////////////////////////////// */ static unsigned char readBitFromReversedStream(size_t* bitpointer, const unsigned char* bitstream) { unsigned char result = (unsigned char) ((bitstream[(*bitpointer) >> 3] >> (7 - ((*bitpointer) & 0x7))) & 1); (*bitpointer)++; return result; } static unsigned readBitsFromReversedStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) { unsigned result = 0; size_t i; for (i = nbits - 1; i < nbits; i--) { result += (unsigned) readBitFromReversedStream(bitpointer, bitstream) << i; } return result; } #ifdef LODEPNG_COMPILE_DECODER static void setBitOfReversedStream0(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) { /*the current bit in bitstream must be 0 for this to work*/ if (bit) { /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/ bitstream[(*bitpointer) >> 3] |= (bit << (7 - ((*bitpointer) & 0x7))); } (*bitpointer)++; } #endif /*LODEPNG_COMPILE_DECODER*/ static void setBitOfReversedStream(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) { /*the current bit in bitstream may be 0 or 1 for this to work*/ if (bit == 0) bitstream[(*bitpointer) >> 3] &= (unsigned char) (~(1 << (7 - ((*bitpointer) & 0x7)))); else bitstream[(*bitpointer) >> 3] |= (1 << (7 - ((*bitpointer) & 0x7))); (*bitpointer)++; } /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG chunks / */ /* ////////////////////////////////////////////////////////////////////////// */ unsigned lodepng_chunk_length(const unsigned char* chunk) { return lodepng_read32bitInt(&chunk[0]); } void lodepng_chunk_type(char type[5], const unsigned char* chunk) { unsigned i; for (i = 0; i < 4; i++) type[i] = (char) chunk[4 + i]; type[4] = 0; /*null termination char*/ } unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type) { if (strlen(type) != 4) return 0; return (chunk[4] == type[0] && chunk[5] == type[1] && chunk[6] == type[2] && chunk[7] == type[3]); } unsigned char lodepng_chunk_ancillary(const unsigned char* chunk) { return ((chunk[4] & 32) != 0); } unsigned char lodepng_chunk_private(const unsigned char* chunk) { return ((chunk[6] & 32) != 0); } unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk) { return ((chunk[7] & 32) != 0); } unsigned char* lodepng_chunk_data(unsigned char* chunk) { return &chunk[8]; } const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk) { return &chunk[8]; } unsigned lodepng_chunk_check_crc(const unsigned char* chunk) { unsigned length = lodepng_chunk_length(chunk); unsigned CRC = lodepng_read32bitInt(&chunk[length + 8]); /*the CRC is taken of the data and the 4 chunk type letters, not the length*/ unsigned checksum = lodepng_crc32(&chunk[4], length + 4); if (CRC != checksum) return 1; else return 0; } void lodepng_chunk_generate_crc(unsigned char* chunk) { unsigned length = lodepng_chunk_length(chunk); unsigned CRC = lodepng_crc32(&chunk[4], length + 4); lodepng_set32bitInt(chunk + 8 + length, CRC); } unsigned char* lodepng_chunk_next(unsigned char* chunk) { unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; return &chunk[total_chunk_length]; } const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk) { unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; return &chunk[total_chunk_length]; } unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk) { unsigned i; unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; unsigned char *chunk_start, *new_buffer; size_t new_length = (*outlength) + total_chunk_length; if (new_length < total_chunk_length || new_length < (*outlength)) return 77; /*integer overflow happened*/ new_buffer = (unsigned char*) lodepng_realloc(*out, new_length); if (!new_buffer) return 83; /*alloc fail*/ (*out) = new_buffer; (*outlength) = new_length; chunk_start = &(*out)[new_length - total_chunk_length]; for (i = 0; i < total_chunk_length; i++) chunk_start[i] = chunk[i]; return 0; } unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data) { unsigned i; unsigned char *chunk, *new_buffer; size_t new_length = (*outlength) + length + 12; if (new_length < length + 12 || new_length < (*outlength)) return 77; /*integer overflow happened*/ new_buffer = (unsigned char*) lodepng_realloc(*out, new_length); if (!new_buffer) return 83; /*alloc fail*/ (*out) = new_buffer; (*outlength) = new_length; chunk = &(*out)[(*outlength) - length - 12]; /*1: length*/ lodepng_set32bitInt(chunk, (unsigned) length); /*2: chunk name (4 letters)*/ chunk[4] = (unsigned char) type[0]; chunk[5] = (unsigned char) type[1]; chunk[6] = (unsigned char) type[2]; chunk[7] = (unsigned char) type[3]; /*3: the data*/ for (i = 0; i < length; i++) chunk[8 + i] = data[i]; /*4: CRC (of the chunkname characters and the data)*/ lodepng_chunk_generate_crc(chunk); return 0; } /* ////////////////////////////////////////////////////////////////////////// */ /* / Color types and such / */ /* ////////////////////////////////////////////////////////////////////////// */ /*return type is a LodePNG error code*/ static unsigned checkColorValidity(LodePNGColorType colortype, unsigned bd) /*bd = bitdepth*/ { switch (colortype) { case 0: if (!(bd == 1 || bd == 2 || bd == 4 || bd == 8 || bd == 16)) return 37; break; /*grey*/ case 2: if (!(bd == 8 || bd == 16)) return 37; break; /*RGB*/ case 3: if (!(bd == 1 || bd == 2 || bd == 4 || bd == 8)) return 37; break; /*palette*/ case 4: if (!(bd == 8 || bd == 16)) return 37; break; /*grey + alpha*/ case 6: if (!(bd == 8 || bd == 16)) return 37; break; /*RGBA*/ default: return 31; } return 0; /*allowed color type / bits combination*/ } static unsigned getNumColorChannels(LodePNGColorType colortype) { switch (colortype) { case 0: return 1; /*grey*/ case 2: return 3; /*RGB*/ case 3: return 1; /*palette*/ case 4: return 2; /*grey + alpha*/ case 6: return 4; /*RGBA*/ } return 0; /*unexisting color type*/ } static unsigned lodepng_get_bpp_lct(LodePNGColorType colortype, unsigned bitdepth) { /*bits per pixel is amount of channels * bits per channel*/ return getNumColorChannels(colortype) * bitdepth; } /* ////////////////////////////////////////////////////////////////////////// */ void lodepng_color_mode_init(LodePNGColorMode* info) { info->key_defined = 0; info->key_r = info->key_g = info->key_b = 0; info->colortype = LCT_RGBA; info->bitdepth = 8; info->palette = 0; info->palettesize = 0; } void lodepng_color_mode_cleanup(LodePNGColorMode* info) { lodepng_palette_clear(info); } unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source) { size_t i; lodepng_color_mode_cleanup(dest); *dest = *source; if (source->palette) { dest->palette = (unsigned char*) lodepng_malloc(1024); if (!dest->palette && source->palettesize) return 83; /*alloc fail*/ for (i = 0; i < source->palettesize * 4; i++) dest->palette[i] = source->palette[i]; } return 0; } static int lodepng_color_mode_equal(const LodePNGColorMode* a, const LodePNGColorMode* b) { size_t i; if (a->colortype != b->colortype) return 0; if (a->bitdepth != b->bitdepth) return 0; if (a->key_defined != b->key_defined) return 0; if (a->key_defined) { if (a->key_r != b->key_r) return 0; if (a->key_g != b->key_g) return 0; if (a->key_b != b->key_b) return 0; } if (a->palettesize != b->palettesize) return 0; for (i = 0; i < a->palettesize * 4; i++) { if (a->palette[i] != b->palette[i]) return 0; } return 1; } void lodepng_palette_clear(LodePNGColorMode* info) { if (info->palette) lodepng_free(info->palette); info->palette = 0; info->palettesize = 0; } unsigned lodepng_palette_add(LodePNGColorMode* info, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { unsigned char* data; /*the same resize technique as C++ std::vectors is used, and here it's made so that for a palette with the max of 256 colors, it'll have the exact alloc size*/ if (!info->palette) /*allocate palette if empty*/ { /*room for 256 colors with 4 bytes each*/ data = (unsigned char*) lodepng_realloc(info->palette, 1024); if (!data) return 83; /*alloc fail*/ else info->palette = data; } info->palette[4 * info->palettesize + 0] = r; info->palette[4 * info->palettesize + 1] = g; info->palette[4 * info->palettesize + 2] = b; info->palette[4 * info->palettesize + 3] = a; info->palettesize++; return 0; } unsigned lodepng_get_bpp(const LodePNGColorMode* info) { /*calculate bits per pixel out of colortype and bitdepth*/ return lodepng_get_bpp_lct(info->colortype, info->bitdepth); } unsigned lodepng_get_channels(const LodePNGColorMode* info) { return getNumColorChannels(info->colortype); } unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info) { return info->colortype == LCT_GREY || info->colortype == LCT_GREY_ALPHA; } unsigned lodepng_is_alpha_type(const LodePNGColorMode* info) { return (info->colortype & 4) != 0; /*4 or 6*/ } unsigned lodepng_is_palette_type(const LodePNGColorMode* info) { return info->colortype == LCT_PALETTE; } unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info) { size_t i; for (i = 0; i < info->palettesize; i++) { if (info->palette[i * 4 + 3] < 255) return 1; } return 0; } unsigned lodepng_can_have_alpha(const LodePNGColorMode* info) { return info->key_defined || lodepng_is_alpha_type(info) || lodepng_has_palette_alpha(info); } size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color) { return (w * h * lodepng_get_bpp(color) + 7) / 8; } size_t lodepng_get_raw_size_lct(unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { return (w * h * lodepng_get_bpp_lct(colortype, bitdepth) + 7) / 8; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static void LodePNGUnknownChunks_init(LodePNGInfo* info) { unsigned i; for (i = 0; i < 3; i++) info->unknown_chunks_data[i] = 0; for (i = 0; i < 3; i++) info->unknown_chunks_size[i] = 0; } static void LodePNGUnknownChunks_cleanup(LodePNGInfo* info) { unsigned i; for (i = 0; i < 3; i++) lodepng_free(info->unknown_chunks_data[i]); } static unsigned LodePNGUnknownChunks_copy(LodePNGInfo* dest, const LodePNGInfo* src) { unsigned i; LodePNGUnknownChunks_cleanup(dest); for (i = 0; i < 3; i++) { size_t j; dest->unknown_chunks_size[i] = src->unknown_chunks_size[i]; dest->unknown_chunks_data[i] = (unsigned char*) lodepng_malloc( src->unknown_chunks_size[i]); if (!dest->unknown_chunks_data[i] && dest->unknown_chunks_size[i]) return 83; /*alloc fail*/ for (j = 0; j < src->unknown_chunks_size[i]; j++) { dest->unknown_chunks_data[i][j] = src->unknown_chunks_data[i][j]; } } return 0; } /******************************************************************************/ static void LodePNGText_init(LodePNGInfo* info) { info->text_num = 0; info->text_keys = NULL; info->text_strings = NULL; } static void LodePNGText_cleanup(LodePNGInfo* info) { size_t i; for (i = 0; i < info->text_num; i++) { string_cleanup(&info->text_keys[i]); string_cleanup(&info->text_strings[i]); } lodepng_free(info->text_keys); lodepng_free(info->text_strings); } static unsigned LodePNGText_copy(LodePNGInfo* dest, const LodePNGInfo* source) { size_t i = 0; dest->text_keys = 0; dest->text_strings = 0; dest->text_num = 0; for (i = 0; i < source->text_num; i++) { CERROR_TRY_RETURN( lodepng_add_text(dest, source->text_keys[i], source->text_strings[i])); } return 0; } void lodepng_clear_text(LodePNGInfo* info) { LodePNGText_cleanup(info); } unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str) { char** new_keys = (char**) (lodepng_realloc(info->text_keys, sizeof(char*) * (info->text_num + 1))); char** new_strings = (char**) (lodepng_realloc(info->text_strings, sizeof(char*) * (info->text_num + 1))); if (!new_keys || !new_strings) { lodepng_free(new_keys); lodepng_free(new_strings); return 83; /*alloc fail*/ } info->text_num++; info->text_keys = new_keys; info->text_strings = new_strings; string_init(&info->text_keys[info->text_num - 1]); string_set(&info->text_keys[info->text_num - 1], key); string_init(&info->text_strings[info->text_num - 1]); string_set(&info->text_strings[info->text_num - 1], str); return 0; } /******************************************************************************/ static void LodePNGIText_init(LodePNGInfo* info) { info->itext_num = 0; info->itext_keys = NULL; info->itext_langtags = NULL; info->itext_transkeys = NULL; info->itext_strings = NULL; } static void LodePNGIText_cleanup(LodePNGInfo* info) { size_t i; for (i = 0; i < info->itext_num; i++) { string_cleanup(&info->itext_keys[i]); string_cleanup(&info->itext_langtags[i]); string_cleanup(&info->itext_transkeys[i]); string_cleanup(&info->itext_strings[i]); } lodepng_free(info->itext_keys); lodepng_free(info->itext_langtags); lodepng_free(info->itext_transkeys); lodepng_free(info->itext_strings); } static unsigned LodePNGIText_copy(LodePNGInfo* dest, const LodePNGInfo* source) { size_t i = 0; dest->itext_keys = 0; dest->itext_langtags = 0; dest->itext_transkeys = 0; dest->itext_strings = 0; dest->itext_num = 0; for (i = 0; i < source->itext_num; i++) { CERROR_TRY_RETURN( lodepng_add_itext(dest, source->itext_keys[i], source->itext_langtags[i], source->itext_transkeys[i], source->itext_strings[i])); } return 0; } void lodepng_clear_itext(LodePNGInfo* info) { LodePNGIText_cleanup(info); } unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, const char* transkey, const char* str) { char** new_keys = (char**) (lodepng_realloc(info->itext_keys, sizeof(char*) * (info->itext_num + 1))); char** new_langtags = (char**) (lodepng_realloc(info->itext_langtags, sizeof(char*) * (info->itext_num + 1))); char** new_transkeys = (char**) (lodepng_realloc(info->itext_transkeys, sizeof(char*) * (info->itext_num + 1))); char** new_strings = (char**) (lodepng_realloc(info->itext_strings, sizeof(char*) * (info->itext_num + 1))); if (!new_keys || !new_langtags || !new_transkeys || !new_strings) { lodepng_free(new_keys); lodepng_free(new_langtags); lodepng_free(new_transkeys); lodepng_free(new_strings); return 83; /*alloc fail*/ } info->itext_num++; info->itext_keys = new_keys; info->itext_langtags = new_langtags; info->itext_transkeys = new_transkeys; info->itext_strings = new_strings; string_init(&info->itext_keys[info->itext_num - 1]); string_set(&info->itext_keys[info->itext_num - 1], key); string_init(&info->itext_langtags[info->itext_num - 1]); string_set(&info->itext_langtags[info->itext_num - 1], langtag); string_init(&info->itext_transkeys[info->itext_num - 1]); string_set(&info->itext_transkeys[info->itext_num - 1], transkey); string_init(&info->itext_strings[info->itext_num - 1]); string_set(&info->itext_strings[info->itext_num - 1], str); return 0; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ void lodepng_info_init(LodePNGInfo* info) { lodepng_color_mode_init(&info->color); info->interlace_method = 0; info->compression_method = 0; info->filter_method = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS info->background_defined = 0; info->background_r = info->background_g = info->background_b = 0; LodePNGText_init(info); LodePNGIText_init(info); info->time_defined = 0; info->phys_defined = 0; LodePNGUnknownChunks_init(info); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } void lodepng_info_cleanup(LodePNGInfo* info) { lodepng_color_mode_cleanup(&info->color); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS LodePNGText_cleanup(info); LodePNGIText_cleanup(info); LodePNGUnknownChunks_cleanup(info); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source) { lodepng_info_cleanup(dest); *dest = *source; lodepng_color_mode_init(&dest->color); CERROR_TRY_RETURN(lodepng_color_mode_copy(&dest->color, &source->color)); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS CERROR_TRY_RETURN(LodePNGText_copy(dest, source)); CERROR_TRY_RETURN(LodePNGIText_copy(dest, source)); LodePNGUnknownChunks_init(dest); CERROR_TRY_RETURN(LodePNGUnknownChunks_copy(dest, source)); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ return 0; } void lodepng_info_swap(LodePNGInfo* a, LodePNGInfo* b) { LodePNGInfo temp = *a; *a = *b; *b = temp; } /* ////////////////////////////////////////////////////////////////////////// */ /*index: bitgroup index, bits: bitgroup size(1, 2 or 4), in: bitgroup value, out: octet array to add bits to*/ static void addColorBits(unsigned char* out, size_t index, unsigned bits, unsigned in) { unsigned m = bits == 1 ? 7 : bits == 2 ? 3 : 1; /*8 / bits - 1*/ /*p = the partial index in the byte, e.g. with 4 palettebits it is 0 for first half or 1 for second half*/ unsigned p = index & m; in &= (1u << bits) - 1u; /*filter out any other bits of the input value*/ in = in << (bits * (m - p)); if (p == 0) out[index * bits / 8] = in; else out[index * bits / 8] |= in; } typedef struct ColorTree ColorTree; /* One node of a color tree This is the data structure used to count the number of unique colors and to get a palette index for a color. It's like an octree, but because the alpha channel is used too, each node has 16 instead of 8 children. */ struct ColorTree { ColorTree* children[16]; /*up to 16 pointers to ColorTree of next level*/ int index; /*the payload. Only has a meaningful value if this is in the last level*/ }; static void color_tree_init(ColorTree* tree) { int i; for (i = 0; i < 16; i++) tree->children[i] = 0; tree->index = -1; } static void color_tree_cleanup(ColorTree* tree) { int i; for (i = 0; i < 16; i++) { if (tree->children[i]) { color_tree_cleanup(tree->children[i]); lodepng_free(tree->children[i]); } } } /*returns -1 if color not present, its index otherwise*/ static int color_tree_get(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { int bit = 0; for (bit = 0; bit < 8; bit++) { int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); if (!tree->children[i]) return -1; else tree = tree->children[i]; } return tree ? tree->index : -1; } #ifdef LODEPNG_COMPILE_ENCODER static int color_tree_has(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { return color_tree_get(tree, r, g, b, a) >= 0; } #endif /*LODEPNG_COMPILE_ENCODER*/ /*color is not allowed to already exist. Index should be >= 0 (it's signed to be compatible with using -1 for "doesn't exist")*/ static void color_tree_add(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a, unsigned index) { int bit; for (bit = 0; bit < 8; bit++) { int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); if (!tree->children[i]) { tree->children[i] = (ColorTree*) lodepng_malloc(sizeof(ColorTree)); color_tree_init(tree->children[i]); } tree = tree->children[i]; } tree->index = (int) index; } /*put a pixel, given its RGBA color, into image of any color type*/ static unsigned rgba8ToPixel(unsigned char* out, size_t i, const LodePNGColorMode* mode, ColorTree* tree /*for palette*/, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { if (mode->colortype == LCT_GREY) { unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/ ; if (mode->bitdepth == 8) out[i] = grey; else if (mode->bitdepth == 16) out[i * 2 + 0] = out[i * 2 + 1] = grey; else { /*take the most significant bits of grey*/ grey = (grey >> (8 - mode->bitdepth)) & ((1 << mode->bitdepth) - 1); addColorBits(out, i, mode->bitdepth, grey); } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { out[i * 3 + 0] = r; out[i * 3 + 1] = g; out[i * 3 + 2] = b; } else { out[i * 6 + 0] = out[i * 6 + 1] = r; out[i * 6 + 2] = out[i * 6 + 3] = g; out[i * 6 + 4] = out[i * 6 + 5] = b; } } else if (mode->colortype == LCT_PALETTE) { int index = color_tree_get(tree, r, g, b, a); if (index < 0) return 82; /*color not in palette*/ if (mode->bitdepth == 8) out[i] = index; else addColorBits(out, i, mode->bitdepth, (unsigned) index); } else if (mode->colortype == LCT_GREY_ALPHA) { unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/ ; if (mode->bitdepth == 8) { out[i * 2 + 0] = grey; out[i * 2 + 1] = a; } else if (mode->bitdepth == 16) { out[i * 4 + 0] = out[i * 4 + 1] = grey; out[i * 4 + 2] = out[i * 4 + 3] = a; } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { out[i * 4 + 0] = r; out[i * 4 + 1] = g; out[i * 4 + 2] = b; out[i * 4 + 3] = a; } else { out[i * 8 + 0] = out[i * 8 + 1] = r; out[i * 8 + 2] = out[i * 8 + 3] = g; out[i * 8 + 4] = out[i * 8 + 5] = b; out[i * 8 + 6] = out[i * 8 + 7] = a; } } return 0; /*no error*/ } /*put a pixel, given its RGBA16 color, into image of any color 16-bitdepth type*/ static unsigned rgba16ToPixel(unsigned char* out, size_t i, const LodePNGColorMode* mode, unsigned short r, unsigned short g, unsigned short b, unsigned short a) { if (mode->bitdepth != 16) return 85; /*must be 16 for this function*/ if (mode->colortype == LCT_GREY) { unsigned short grey = r; /*((unsigned)r + g + b) / 3*/ ; out[i * 2 + 0] = (grey >> 8) & 255; out[i * 2 + 1] = grey & 255; } else if (mode->colortype == LCT_RGB) { out[i * 6 + 0] = (r >> 8) & 255; out[i * 6 + 1] = r & 255; out[i * 6 + 2] = (g >> 8) & 255; out[i * 6 + 3] = g & 255; out[i * 6 + 4] = (b >> 8) & 255; out[i * 6 + 5] = b & 255; } else if (mode->colortype == LCT_GREY_ALPHA) { unsigned short grey = r; /*((unsigned)r + g + b) / 3*/ ; out[i * 4 + 0] = (grey >> 8) & 255; out[i * 4 + 1] = grey & 255; out[i * 4 + 2] = (a >> 8) & 255; out[i * 4 + 3] = a & 255; } else if (mode->colortype == LCT_RGBA) { out[i * 8 + 0] = (r >> 8) & 255; out[i * 8 + 1] = r & 255; out[i * 8 + 2] = (g >> 8) & 255; out[i * 8 + 3] = g & 255; out[i * 8 + 4] = (b >> 8) & 255; out[i * 8 + 5] = b & 255; out[i * 8 + 6] = (a >> 8) & 255; out[i * 8 + 7] = a & 255; } return 0; /*no error*/ } /*Get RGBA8 color of pixel with index i (y * width + x) from the raw image with given color type.*/ static unsigned getPixelColorRGBA8(unsigned char* r, unsigned char* g, unsigned char* b, unsigned char* a, const unsigned char* in, size_t i, const LodePNGColorMode* mode, unsigned fix_png) { if (mode->colortype == LCT_GREY) { if (mode->bitdepth == 8) { *r = *g = *b = in[i]; if (mode->key_defined && *r == mode->key_r) *a = 0; else *a = 255; } else if (mode->bitdepth == 16) { *r = *g = *b = in[i * 2 + 0]; if (mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; else *a = 255; } else { unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ size_t j = i * mode->bitdepth; unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); *r = *g = *b = (value * 255) / highest; if (mode->key_defined && value == mode->key_r) *a = 0; else *a = 255; } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { *r = in[i * 3 + 0]; *g = in[i * 3 + 1]; *b = in[i * 3 + 2]; if (mode->key_defined && *r == mode->key_r && *g == mode->key_g && *b == mode->key_b) *a = 0; else *a = 255; } else { *r = in[i * 6 + 0]; *g = in[i * 6 + 2]; *b = in[i * 6 + 4]; if (mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; else *a = 255; } } else if (mode->colortype == LCT_PALETTE) { unsigned index; if (mode->bitdepth == 8) index = in[i]; else { size_t j = i * mode->bitdepth; index = readBitsFromReversedStream(&j, in, mode->bitdepth); } if (index >= mode->palettesize) { /*This is an error according to the PNG spec, but fix_png can ignore it*/ if (!fix_png) return (mode->bitdepth == 8 ? 46 : 47); /*index out of palette*/ *r = *g = *b = 0; *a = 255; } else { *r = mode->palette[index * 4 + 0]; *g = mode->palette[index * 4 + 1]; *b = mode->palette[index * 4 + 2]; *a = mode->palette[index * 4 + 3]; } } else if (mode->colortype == LCT_GREY_ALPHA) { if (mode->bitdepth == 8) { *r = *g = *b = in[i * 2 + 0]; *a = in[i * 2 + 1]; } else { *r = *g = *b = in[i * 4 + 0]; *a = in[i * 4 + 2]; } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { *r = in[i * 4 + 0]; *g = in[i * 4 + 1]; *b = in[i * 4 + 2]; *a = in[i * 4 + 3]; } else { *r = in[i * 8 + 0]; *g = in[i * 8 + 2]; *b = in[i * 8 + 4]; *a = in[i * 8 + 6]; } } return 0; /*no error*/ } /*Similar to getPixelColorRGBA8, but with all the for loops inside of the color mode test cases, optimized to convert the colors much faster, when converting to RGBA or RGB with 8 bit per cannel. buffer must be RGBA or RGB output with enough memory, if has_alpha is true the output is RGBA. mode has the color mode of the input buffer.*/ static unsigned getPixelColorsRGBA8(unsigned char* buffer, size_t numpixels, unsigned has_alpha, const unsigned char* in, const LodePNGColorMode* mode, unsigned fix_png) { unsigned num_channels = has_alpha ? 4 : 3; size_t i; if (mode->colortype == LCT_GREY) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i]; if (has_alpha) buffer[3] = mode->key_defined && in[i] == mode->key_r ? 0 : 255; } } else if (mode->bitdepth == 16) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 2]; if (has_alpha) buffer[3] = mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r ? 0 : 255; } } else { unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ size_t j = 0; for (i = 0; i < numpixels; i++, buffer += num_channels) { unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); buffer[0] = buffer[1] = buffer[2] = (value * 255) / highest; if (has_alpha) buffer[3] = mode->key_defined && value == mode->key_r ? 0 : 255; } } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 3 + 0]; buffer[1] = in[i * 3 + 1]; buffer[2] = in[i * 3 + 2]; if (has_alpha) buffer[3] = mode->key_defined && buffer[0] == mode->key_r && buffer[1] == mode->key_g && buffer[2] == mode->key_b ? 0 : 255; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 6 + 0]; buffer[1] = in[i * 6 + 2]; buffer[2] = in[i * 6 + 4]; if (has_alpha) buffer[3] = mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b ? 0 : 255; } } } else if (mode->colortype == LCT_PALETTE) { unsigned index; size_t j = 0; for (i = 0; i < numpixels; i++, buffer += num_channels) { if (mode->bitdepth == 8) index = in[i]; else index = readBitsFromReversedStream(&j, in, mode->bitdepth); if (index >= mode->palettesize) { /*This is an error according to the PNG spec, but fix_png can ignore it*/ if (!fix_png) return (mode->bitdepth == 8 ? 46 : 47); /*index out of palette*/ buffer[0] = buffer[1] = buffer[2] = 0; if (has_alpha) buffer[3] = 255; } else { buffer[0] = mode->palette[index * 4 + 0]; buffer[1] = mode->palette[index * 4 + 1]; buffer[2] = mode->palette[index * 4 + 2]; if (has_alpha) buffer[3] = mode->palette[index * 4 + 3]; } } } else if (mode->colortype == LCT_GREY_ALPHA) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 2 + 0]; if (has_alpha) buffer[3] = in[i * 2 + 1]; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 4 + 0]; if (has_alpha) buffer[3] = in[i * 4 + 2]; } } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 4 + 0]; buffer[1] = in[i * 4 + 1]; buffer[2] = in[i * 4 + 2]; if (has_alpha) buffer[3] = in[i * 4 + 3]; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 8 + 0]; buffer[1] = in[i * 8 + 2]; buffer[2] = in[i * 8 + 4]; if (has_alpha) buffer[3] = in[i * 8 + 6]; } } } return 0; /*no error*/ } /*Get RGBA16 color of pixel with index i (y * width + x) from the raw image with given color type, but the given color type must be 16-bit itself.*/ static unsigned getPixelColorRGBA16(unsigned short* r, unsigned short* g, unsigned short* b, unsigned short* a, const unsigned char* in, size_t i, const LodePNGColorMode* mode) { if (mode->bitdepth != 16) return 85; /*error: this function only supports 16-bit input*/ if (mode->colortype == LCT_GREY) { *r = *g = *b = 256 * in[i * 2 + 0] + in[i * 2 + 1]; if (mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; else *a = 65535; } else if (mode->colortype == LCT_RGB) { *r = 256 * in[i * 6 + 0] + in[i * 6 + 1]; *g = 256 * in[i * 6 + 2] + in[i * 6 + 3]; *b = 256 * in[i * 6 + 4] + in[i * 6 + 5]; if (mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; else *a = 65535; } else if (mode->colortype == LCT_GREY_ALPHA) { *r = *g = *b = 256 * in[i * 4 + 0] + in[i * 4 + 1]; *a = 256 * in[i * 4 + 2] + in[i * 4 + 3]; } else if (mode->colortype == LCT_RGBA) { *r = 256 * in[i * 8 + 0] + in[i * 8 + 1]; *g = 256 * in[i * 8 + 2] + in[i * 8 + 3]; *b = 256 * in[i * 8 + 4] + in[i * 8 + 5]; *a = 256 * in[i * 8 + 6] + in[i * 8 + 7]; } else return 85; /*error: this function only supports 16-bit input, not palettes*/ return 0; /*no error*/ } /* converts from any color type to 24-bit or 32-bit (later maybe more supported). return value = LodePNG error code the out buffer must have (w * h * bpp + 7) / 8 bytes, where bpp is the bits per pixel of the output color type (lodepng_get_bpp) for < 8 bpp images, there may _not_ be padding bits at the end of scanlines. */ unsigned lodepng_convert(unsigned char* out, const unsigned char* in, LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, unsigned w, unsigned h, unsigned fix_png) { unsigned error = 0; size_t i; ColorTree tree; size_t numpixels = w * h; if (lodepng_color_mode_equal(mode_out, mode_in)) { size_t numbytes = lodepng_get_raw_size(w, h, mode_in); for (i = 0; i < numbytes; i++) out[i] = in[i]; return error; } if (mode_out->colortype == LCT_PALETTE) { size_t palsize = 1u << mode_out->bitdepth; if (mode_out->palettesize < palsize) palsize = mode_out->palettesize; color_tree_init(&tree); for (i = 0; i < palsize; i++) { unsigned char* p = &mode_out->palette[i * 4]; color_tree_add(&tree, p[0], p[1], p[2], p[3], i); } } if (mode_in->bitdepth == 16 && mode_out->bitdepth == 16) { for (i = 0; i < numpixels; i++) { unsigned short r = 0, g = 0, b = 0, a = 0; error = getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode_in); if (error) break; error = rgba16ToPixel(out, i, mode_out, r, g, b, a); if (error) break; } } else if (mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGBA) { error = getPixelColorsRGBA8(out, numpixels, 1, in, mode_in, fix_png); } else if (mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGB) { error = getPixelColorsRGBA8(out, numpixels, 0, in, mode_in, fix_png); } else { unsigned char r = 0, g = 0, b = 0, a = 0; for (i = 0; i < numpixels; i++) { error = getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode_in, fix_png); if (error) break; error = rgba8ToPixel(out, i, mode_out, &tree, r, g, b, a); if (error) break; } } if (mode_out->colortype == LCT_PALETTE) { color_tree_cleanup(&tree); } return error; } #ifdef LODEPNG_COMPILE_ENCODER typedef struct ColorProfile { unsigned char sixteenbit; /*needs more than 8 bits per channel*/ unsigned char sixteenbit_done; unsigned char colored; /*not greyscale*/ unsigned char colored_done; unsigned char key; /*a color key is required, or more*/ unsigned short key_r; /*these values are always in 16-bit bitdepth in the profile*/ unsigned short key_g; unsigned short key_b; unsigned char alpha; /*alpha channel, or alpha palette, required*/ unsigned char alpha_done; unsigned numcolors; ColorTree tree; /*for listing the counted colors, up to 256*/ unsigned char* palette; /*size 1024. Remember up to the first 256 RGBA colors*/ unsigned maxnumcolors; /*if more than that amount counted*/ unsigned char numcolors_done; unsigned greybits; /*amount of bits required for greyscale (1, 2, 4, 8). Does not take 16 bit into account.*/ unsigned char greybits_done; } ColorProfile; static void color_profile_init(ColorProfile* profile, const LodePNGColorMode* mode) { profile->sixteenbit = 0; profile->sixteenbit_done = mode->bitdepth == 16 ? 0 : 1; profile->colored = 0; profile->colored_done = lodepng_is_greyscale_type(mode) ? 1 : 0; profile->key = 0; profile->alpha = 0; profile->alpha_done = lodepng_can_have_alpha(mode) ? 0 : 1; profile->numcolors = 0; color_tree_init(&profile->tree); profile->palette = (unsigned char*) lodepng_malloc(1024); profile->maxnumcolors = 257; if (lodepng_get_bpp(mode) <= 8) { unsigned bpp = lodepng_get_bpp(mode); profile->maxnumcolors = bpp == 1 ? 2 : (bpp == 2 ? 4 : (bpp == 4 ? 16 : 256)); } profile->numcolors_done = 0; profile->greybits = 1; profile->greybits_done = lodepng_get_bpp(mode) == 1 ? 1 : 0; } static void color_profile_cleanup(ColorProfile* profile) { color_tree_cleanup(&profile->tree); lodepng_free(profile->palette); } /*function used for debug purposes with C++*/ /*void printColorProfile(ColorProfile* p) { std::cout << "sixteenbit: " << (int)p->sixteenbit << std::endl; std::cout << "sixteenbit_done: " << (int)p->sixteenbit_done << std::endl; std::cout << "colored: " << (int)p->colored << std::endl; std::cout << "colored_done: " << (int)p->colored_done << std::endl; std::cout << "key: " << (int)p->key << std::endl; std::cout << "key_r: " << (int)p->key_r << std::endl; std::cout << "key_g: " << (int)p->key_g << std::endl; std::cout << "key_b: " << (int)p->key_b << std::endl; std::cout << "alpha: " << (int)p->alpha << std::endl; std::cout << "alpha_done: " << (int)p->alpha_done << std::endl; std::cout << "numcolors: " << (int)p->numcolors << std::endl; std::cout << "maxnumcolors: " << (int)p->maxnumcolors << std::endl; std::cout << "numcolors_done: " << (int)p->numcolors_done << std::endl; std::cout << "greybits: " << (int)p->greybits << std::endl; std::cout << "greybits_done: " << (int)p->greybits_done << std::endl; }*/ /*Returns how many bits needed to represent given value (max 8 bit)*/ unsigned getValueRequiredBits(unsigned short value) { if (value == 0 || value == 255) return 1; /*The scaling of 2-bit and 4-bit values uses multiples of 85 and 17*/ if (value % 17 == 0) return value % 85 == 0 ? 2 : 4; return 8; } /*profile must already have been inited with mode. It's ok to set some parameters of profile to done already.*/ static unsigned get_color_profile(ColorProfile* profile, const unsigned char* in, size_t numpixels /*must be full image size, for certain filesize based choices*/, const LodePNGColorMode* mode, unsigned fix_png) { unsigned error = 0; size_t i; if (mode->bitdepth == 16) { for (i = 0; i < numpixels; i++) { unsigned short r, g, b, a; error = getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode); if (error) break; /*a color is considered good for 8-bit if the first byte and the second byte are equal, (so if it's divisible through 257), NOT necessarily if the second byte is 0*/ if (!profile->sixteenbit_done && (((r & 255) != ((r >> 8) & 255)) || ((g & 255) != ((g >> 8) & 255)) || ((b & 255) != ((b >> 8) & 255)))) { profile->sixteenbit = 1; profile->sixteenbit_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore at 16-bit*/ profile->numcolors_done = 1; /*counting colors no longer useful, palette doesn't support 16-bit*/ } if (!profile->colored_done && (r != g || r != b)) { profile->colored = 1; profile->colored_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->alpha_done && a != 65535) { /*only use color key if numpixels large enough to justify tRNS chunk size*/ if (a == 0 && numpixels > 16 && !(profile->key && (r != profile->key_r || g != profile->key_g || b != profile->key_b))) { if (!profile->alpha && !profile->key) { profile->key = 1; profile->key_r = r; profile->key_g = g; profile->key_b = b; } } else { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } } /* Color key cannot be used if an opaque pixel also has that RGB color. */ if (!profile->alpha_done && a == 65535 && profile->key && r == profile->key_r && g == profile->key_g && b == profile->key_b) { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->greybits_done) { /*assuming 8-bit r, this test does not care about 16-bit*/ unsigned bits = getValueRequiredBits(r); if (bits > profile->greybits) profile->greybits = bits; if (profile->greybits >= 8) profile->greybits_done = 1; } if (!profile->numcolors_done) { /*assuming 8-bit rgba, this test does not care about 16-bit*/ if (!color_tree_has(&profile->tree, (unsigned char) r, (unsigned char) g, (unsigned char) b, (unsigned char) a)) { color_tree_add(&profile->tree, (unsigned char) r, (unsigned char) g, (unsigned char) b, (unsigned char) a, profile->numcolors); if (profile->numcolors < 256) { unsigned char* p = profile->palette; unsigned i = profile->numcolors; p[i * 4 + 0] = (unsigned char) r; p[i * 4 + 1] = (unsigned char) g; p[i * 4 + 2] = (unsigned char) b; p[i * 4 + 3] = (unsigned char) a; } profile->numcolors++; if (profile->numcolors >= profile->maxnumcolors) profile->numcolors_done = 1; } } if (profile->alpha_done && profile->numcolors_done && profile->colored_done && profile->sixteenbit_done && profile->greybits_done) { break; } }; } else /* < 16-bit */ { for (i = 0; i < numpixels; i++) { unsigned char r = 0, g = 0, b = 0, a = 0; error = getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode, fix_png); if (error) break; if (!profile->colored_done && (r != g || r != b)) { profile->colored = 1; profile->colored_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->alpha_done && a != 255) { if (a == 0 && !(profile->key && (r != profile->key_r || g != profile->key_g || b != profile->key_b))) { if (!profile->key) { profile->key = 1; profile->key_r = r; profile->key_g = g; profile->key_b = b; } } else { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } } /* Color key cannot be used if an opaque pixel also has that RGB color. */ if (!profile->alpha_done && a == 255 && profile->key && r == profile->key_r && g == profile->key_g && b == profile->key_b) { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->greybits_done) { unsigned bits = getValueRequiredBits(r); if (bits > profile->greybits) profile->greybits = bits; if (profile->greybits >= 8) profile->greybits_done = 1; } if (!profile->numcolors_done) { if (!color_tree_has(&profile->tree, r, g, b, a)) { color_tree_add(&profile->tree, r, g, b, a, profile->numcolors); if (profile->numcolors < 256) { unsigned char* p = profile->palette; unsigned i = profile->numcolors; p[i * 4 + 0] = r; p[i * 4 + 1] = g; p[i * 4 + 2] = b; p[i * 4 + 3] = a; } profile->numcolors++; if (profile->numcolors >= profile->maxnumcolors) profile->numcolors_done = 1; } } if (profile->alpha_done && profile->numcolors_done && profile->colored_done && profile->greybits_done) { break; } }; } /*make the profile's key always 16-bit for consistency*/ if (mode->bitdepth < 16) { /*repeat each byte twice*/ profile->key_r *= 257; profile->key_g *= 257; profile->key_b *= 257; } return error; } static void setColorKeyFrom16bit(LodePNGColorMode* mode_out, unsigned r, unsigned g, unsigned b, unsigned bitdepth) { unsigned mask = (1u << bitdepth) - 1u; mode_out->key_defined = 1; mode_out->key_r = r & mask; mode_out->key_g = g & mask; mode_out->key_b = b & mask; } /*updates values of mode with a potentially smaller color model. mode_out should contain the user chosen color model, but will be overwritten with the new chosen one.*/ unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, const unsigned char* image, unsigned w, unsigned h, const LodePNGColorMode* mode_in, LodePNGAutoConvert auto_convert) { ColorProfile profile; unsigned error = 0; int no_nibbles = auto_convert == LAC_AUTO_NO_NIBBLES || auto_convert == LAC_AUTO_NO_NIBBLES_NO_PALETTE; int no_palette = auto_convert == LAC_AUTO_NO_PALETTE || auto_convert == LAC_AUTO_NO_NIBBLES_NO_PALETTE; if (auto_convert == LAC_ALPHA) { if (mode_out->colortype != LCT_RGBA && mode_out->colortype != LCT_GREY_ALPHA) return 0; } color_profile_init(&profile, mode_in); if (auto_convert == LAC_ALPHA) { profile.colored_done = 1; profile.greybits_done = 1; profile.numcolors_done = 1; profile.sixteenbit_done = 1; } error = get_color_profile(&profile, image, w * h, mode_in, 0 /*fix_png*/); if (!error && auto_convert == LAC_ALPHA) { if (!profile.alpha) { mode_out->colortype = ( mode_out->colortype == LCT_RGBA ? LCT_RGB : LCT_GREY); if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } else if (!error && auto_convert != LAC_ALPHA) { mode_out->key_defined = 0; if (profile.sixteenbit) { mode_out->bitdepth = 16; if (profile.alpha) { mode_out->colortype = profile.colored ? LCT_RGBA : LCT_GREY_ALPHA; } else { mode_out->colortype = profile.colored ? LCT_RGB : LCT_GREY; if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } else /*less than 16 bits per channel*/ { /*don't add palette overhead if image hasn't got a lot of pixels*/ unsigned n = profile.numcolors; int palette_ok = !no_palette && n <= 256 && (n * 2 < w * h); unsigned palettebits = n <= 2 ? 1 : (n <= 4 ? 2 : (n <= 16 ? 4 : 8)); int grey_ok = !profile.colored && !profile.alpha; /*grey without alpha, with potentially low bits*/ if (palette_ok || grey_ok) { if (!palette_ok || (grey_ok && profile.greybits <= palettebits)) { unsigned grey = profile.key_r; mode_out->colortype = LCT_GREY; mode_out->bitdepth = profile.greybits; if (profile.key) setColorKeyFrom16bit(mode_out, grey, grey, grey, mode_out->bitdepth); } else { /*fill in the palette*/ unsigned i; unsigned char* p = profile.palette; /*remove potential earlier palette*/ lodepng_palette_clear(mode_out); for (i = 0; i < profile.numcolors; i++) { error = lodepng_palette_add(mode_out, p[i * 4 + 0], p[i * 4 + 1], p[i * 4 + 2], p[i * 4 + 3]); if (error) break; } mode_out->colortype = LCT_PALETTE; mode_out->bitdepth = palettebits; } } else /*8-bit per channel*/ { mode_out->bitdepth = 8; if (profile.alpha) { mode_out->colortype = profile.colored ? LCT_RGBA : LCT_GREY_ALPHA; } else { mode_out->colortype = profile.colored ? LCT_RGB : LCT_GREY /*LCT_GREY normally won't occur, already done earlier*/; if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } } } color_profile_cleanup(&profile); if (mode_out->colortype == LCT_PALETTE && mode_in->palettesize == mode_out->palettesize) { /*In this case keep the palette order of the input, so that the user can choose an optimal one*/ size_t i; for (i = 0; i < mode_in->palettesize * 4; i++) { mode_out->palette[i] = mode_in->palette[i]; } } if (no_nibbles && mode_out->bitdepth < 8) { /*palette can keep its small amount of colors, as long as no indices use it*/ mode_out->bitdepth = 8; } return error; } #endif /* #ifdef LODEPNG_COMPILE_ENCODER */ /* Paeth predicter, used by PNG filter type 4 The parameters are of type short, but should come from unsigned chars, the shorts are only needed to make the paeth calculation correct. */ static unsigned char paethPredictor(short a, short b, short c) { short pa = abs(b - c); short pb = abs(a - c); short pc = abs(a + b - c - c); if (pc < pa && pc < pb) return (unsigned char) c; else if (pb < pa) return (unsigned char) b; else return (unsigned char) a; } /*shared values used by multiple Adam7 related functions*/ static const unsigned ADAM7_IX[7] = { 0, 4, 0, 2, 0, 1, 0 }; /*x start values*/ static const unsigned ADAM7_IY[7] = { 0, 0, 4, 0, 2, 0, 1 }; /*y start values*/ static const unsigned ADAM7_DX[7] = { 8, 8, 4, 4, 2, 2, 1 }; /*x delta values*/ static const unsigned ADAM7_DY[7] = { 8, 8, 8, 4, 4, 2, 2 }; /*y delta values*/ /* Outputs various dimensions and positions in the image related to the Adam7 reduced images. passw: output containing the width of the 7 passes passh: output containing the height of the 7 passes filter_passstart: output containing the index of the start and end of each reduced image with filter bytes padded_passstart output containing the index of the start and end of each reduced image when without filter bytes but with padded scanlines passstart: output containing the index of the start and end of each reduced image without padding between scanlines, but still padding between the images w, h: width and height of non-interlaced image bpp: bits per pixel "padded" is only relevant if bpp is less than 8 and a scanline or image does not end at a full byte */ static void Adam7_getpassvalues(unsigned passw[7], unsigned passh[7], size_t filter_passstart[8], size_t padded_passstart[8], size_t passstart[8], unsigned w, unsigned h, unsigned bpp) { /*the passstart values have 8 values: the 8th one indicates the byte after the end of the 7th (= last) pass*/ unsigned i; /*calculate width and height in pixels of each pass*/ for (i = 0; i < 7; i++) { passw[i] = (w + ADAM7_DX[i] - ADAM7_IX[i] - 1) / ADAM7_DX[i]; passh[i] = (h + ADAM7_DY[i] - ADAM7_IY[i] - 1) / ADAM7_DY[i]; if (passw[i] == 0) passh[i] = 0; if (passh[i] == 0) passw[i] = 0; } filter_passstart[0] = padded_passstart[0] = passstart[0] = 0; for (i = 0; i < 7; i++) { /*if passw[i] is 0, it's 0 bytes, not 1 (no filtertype-byte)*/ filter_passstart[i + 1] = filter_passstart[i] + ((passw[i] && passh[i]) ? passh[i] * (1 + (passw[i] * bpp + 7) / 8) : 0); /*bits padded if needed to fill full byte at end of each scanline*/ padded_passstart[i + 1] = padded_passstart[i] + passh[i] * ((passw[i] * bpp + 7) / 8); /*only padded at end of reduced image*/ passstart[i + 1] = passstart[i] + (passh[i] * passw[i] * bpp + 7) / 8; } } #ifdef LODEPNG_COMPILE_DECODER /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG Decoder / */ /* ////////////////////////////////////////////////////////////////////////// */ /*read the information from the header and store it in the LodePNGInfo. return value is error*/ unsigned lodepng_inspect(unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { LodePNGInfo* info = &state->info_png; if (insize == 0 || in == 0) { CERROR_RETURN_ERROR(state->error, 48); /*error: the given data is empty*/ } if (insize < 29) { CERROR_RETURN_ERROR(state->error, 27); /*error: the data length is smaller than the length of a PNG header*/ } /*when decoding a new PNG image, make sure all parameters created after previous decoding are reset*/ lodepng_info_cleanup(info); lodepng_info_init(info); if (in[0] != 137 || in[1] != 80 || in[2] != 78 || in[3] != 71 || in[4] != 13 || in[5] != 10 || in[6] != 26 || in[7] != 10) { CERROR_RETURN_ERROR(state->error, 28); /*error: the first 8 bytes are not the correct PNG signature*/ } if (in[12] != 'I' || in[13] != 'H' || in[14] != 'D' || in[15] != 'R') { CERROR_RETURN_ERROR(state->error, 29); /*error: it doesn't start with a IHDR chunk!*/ } /*read the values given in the header*/ *w = lodepng_read32bitInt(&in[16]); *h = lodepng_read32bitInt(&in[20]); info->color.bitdepth = in[24]; info->color.colortype = (LodePNGColorType) in[25]; info->compression_method = in[26]; info->filter_method = in[27]; info->interlace_method = in[28]; if (!state->decoder.ignore_crc) { unsigned CRC = lodepng_read32bitInt(&in[29]); unsigned checksum = lodepng_crc32(&in[12], 17); if (CRC != checksum) { CERROR_RETURN_ERROR(state->error, 57); /*invalid CRC*/ } } /*error: only compression method 0 is allowed in the specification*/ if (info->compression_method != 0) CERROR_RETURN_ERROR(state->error, 32); /*error: only filter method 0 is allowed in the specification*/ if (info->filter_method != 0) CERROR_RETURN_ERROR(state->error, 33); /*error: only interlace methods 0 and 1 exist in the specification*/ if (info->interlace_method > 1) CERROR_RETURN_ERROR(state->error, 34); state->error = checkColorValidity(info->color.colortype, info->color.bitdepth); return state->error; } static unsigned unfilterScanline(unsigned char* recon, const unsigned char* scanline, const unsigned char* precon, size_t bytewidth, unsigned char filterType, size_t length) { /* For PNG filter method 0 unfilter a PNG image scanline by scanline. when the pixels are smaller than 1 byte, the filter works byte per byte (bytewidth = 1) precon is the previous unfiltered scanline, recon the result, scanline the current one the incoming scanlines do NOT include the filtertype byte, that one is given in the parameter filterType instead recon and scanline MAY be the same memory address! precon must be disjoint. */ size_t i; switch (filterType) { case 0: for (i = 0; i < length; i++) recon[i] = scanline[i]; break; case 1: for (i = 0; i < bytewidth; i++) recon[i] = scanline[i]; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth]; break; case 2: if (precon) { for (i = 0; i < length; i++) recon[i] = scanline[i] + precon[i]; } else { for (i = 0; i < length; i++) recon[i] = scanline[i]; } break; case 3: if (precon) { for (i = 0; i < bytewidth; i++) recon[i] = scanline[i] + precon[i] / 2; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + ((recon[i - bytewidth] + precon[i]) / 2); } else { for (i = 0; i < bytewidth; i++) recon[i] = scanline[i]; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth] / 2; } break; case 4: if (precon) { for (i = 0; i < bytewidth; i++) { recon[i] = (scanline[i] + precon[i]); /*paethPredictor(0, precon[i], 0) is always precon[i]*/ } for (i = bytewidth; i < length; i++) { recon[i] = (scanline[i] + paethPredictor(recon[i - bytewidth], precon[i], precon[i - bytewidth])); } } else { for (i = 0; i < bytewidth; i++) { recon[i] = scanline[i]; } for (i = bytewidth; i < length; i++) { /*paethPredictor(recon[i - bytewidth], 0, 0) is always recon[i - bytewidth]*/ recon[i] = (scanline[i] + recon[i - bytewidth]); } } break; default: return 36; /*error: unexisting filter type given*/ } return 0; } static unsigned unfilter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { /* For PNG filter method 0 this function unfilters a single image (e.g. without interlacing this is called once, with Adam7 seven times) out must have enough bytes allocated already, in must have the scanlines + 1 filtertype byte per scanline w and h are image dimensions or dimensions of reduced image, bpp is bits per pixel in and out are allowed to be the same memory address (but aren't the same size since in has the extra filter bytes) */ unsigned y; unsigned char* prevline = 0; /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ size_t bytewidth = (bpp + 7) / 8; size_t linebytes = (w * bpp + 7) / 8; for (y = 0; y < h; y++) { size_t outindex = linebytes * y; size_t inindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ unsigned char filterType = in[inindex]; CERROR_TRY_RETURN( unfilterScanline(&out[outindex], &in[inindex + 1], prevline, bytewidth, filterType, linebytes)); prevline = &out[outindex]; } return 0; } /* in: Adam7 interlaced image, with no padding bits between scanlines, but between reduced images so that each reduced image starts at a byte. out: the same pixels, but re-ordered so that they're now a non-interlaced image with size w*h bpp: bits per pixel out has the following size in bits: w * h * bpp. in is possibly bigger due to padding bits between reduced images. out must be big enough AND must be 0 everywhere if bpp < 8 in the current implementation (because that's likely a little bit faster) NOTE: comments about padding bits are only relevant if bpp < 8 */ static void Adam7_deinterlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); if (bpp >= 8) { for (i = 0; i < 7; i++) { unsigned x, y, b; size_t bytewidth = bpp / 8; for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { size_t pixelinstart = passstart[i] + (y * passw[i] + x) * bytewidth; size_t pixeloutstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; for (b = 0; b < bytewidth; b++) { out[pixeloutstart + b] = in[pixelinstart + b]; } } } } else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ { for (i = 0; i < 7; i++) { unsigned x, y, b; unsigned ilinebits = bpp * passw[i]; unsigned olinebits = bpp * w; size_t obp, ibp; /*bit pointers (for out and in buffer)*/ for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { ibp = (8 * passstart[i]) + (y * ilinebits + x * bpp); obp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; for (b = 0; b < bpp; b++) { unsigned char bit = readBitFromReversedStream(&ibp, in); /*note that this function assumes the out buffer is completely 0, use setBitOfReversedStream otherwise*/ setBitOfReversedStream0(&obp, out, bit); } } } } } static void removePaddingBits(unsigned char* out, const unsigned char* in, size_t olinebits, size_t ilinebits, unsigned h) { /* After filtering there are still padding bits if scanlines have non multiple of 8 bit amounts. They need to be removed (except at last scanline of (Adam7-reduced) image) before working with pure image buffers for the Adam7 code, the color convert code and the output to the user. in and out are allowed to be the same buffer, in may also be higher but still overlapping; in must have >= ilinebits*h bits, out must have >= olinebits*h bits, olinebits must be <= ilinebits also used to move bits after earlier such operations happened, e.g. in a sequence of reduced images from Adam7 only useful if (ilinebits - olinebits) is a value in the range 1..7 */ unsigned y; size_t diff = ilinebits - olinebits; size_t ibp = 0, obp = 0; /*input and output bit pointers*/ for (y = 0; y < h; y++) { size_t x; for (x = 0; x < olinebits; x++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } ibp += diff; } } /*out must be buffer big enough to contain full image, and in must contain the full decompressed data from the IDAT chunks (with filter index bytes and possible padding bits) return value is error*/ static unsigned postProcessScanlines(unsigned char* out, unsigned char* in, unsigned w, unsigned h, const LodePNGInfo* info_png) { /* This function converts the filtered-padded-interlaced data into pure 2D image buffer with the PNG's colortype. Steps: *) if no Adam7: 1) unfilter 2) remove padding bits (= posible extra bits per scanline if bpp < 8) *) if adam7: 1) 7x unfilter 2) 7x remove padding bits 3) Adam7_deinterlace NOTE: the in buffer will be overwritten with intermediate data! */ unsigned bpp = lodepng_get_bpp(&info_png->color); if (bpp == 0) return 31; /*error: invalid colortype*/ if (info_png->interlace_method == 0) { if (bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) { CERROR_TRY_RETURN(unfilter(in, in, w, h, bpp)); removePaddingBits(out, in, w * bpp, ((w * bpp + 7) / 8) * 8, h); } /*we can immediatly filter into the out buffer, no other steps needed*/ else CERROR_TRY_RETURN(unfilter(out, in, w, h, bpp)); } else /*interlace_method is 1 (Adam7)*/ { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); for (i = 0; i < 7; i++) { CERROR_TRY_RETURN( unfilter(&in[padded_passstart[i]], &in[filter_passstart[i]], passw[i], passh[i], bpp)); /*TODO: possible efficiency improvement: if in this reduced image the bits fit nicely in 1 scanline, move bytes instead of bits or move not at all*/ if (bpp < 8) { /*remove padding bits in scanlines; after this there still may be padding bits between the different reduced images: each reduced image still starts nicely at a byte*/ removePaddingBits(&in[passstart[i]], &in[padded_passstart[i]], passw[i] * bpp, ((passw[i] * bpp + 7) / 8) * 8, passh[i]); } } Adam7_deinterlace(out, in, w, h, bpp); } return 0; } static unsigned readChunk_PLTE(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) { unsigned pos = 0, i; if (color->palette) lodepng_free(color->palette); color->palettesize = chunkLength / 3; color->palette = (unsigned char*) lodepng_malloc(4 * color->palettesize); if (!color->palette && color->palettesize) { color->palettesize = 0; return 83; /*alloc fail*/ } if (color->palettesize > 256) return 38; /*error: palette too big*/ for (i = 0; i < color->palettesize; i++) { color->palette[4 * i + 0] = data[pos++]; /*R*/ color->palette[4 * i + 1] = data[pos++]; /*G*/ color->palette[4 * i + 2] = data[pos++]; /*B*/ color->palette[4 * i + 3] = 255; /*alpha*/ } return 0; /* OK */ } static unsigned readChunk_tRNS(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) { unsigned i; if (color->colortype == LCT_PALETTE) { /*error: more alpha values given than there are palette entries*/ if (chunkLength > color->palettesize) return 38; for (i = 0; i < chunkLength; i++) color->palette[4 * i + 3] = data[i]; } else if (color->colortype == LCT_GREY) { /*error: this chunk must be 2 bytes for greyscale image*/ if (chunkLength != 2) return 30; color->key_defined = 1; color->key_r = color->key_g = color->key_b = 256u * data[0] + data[1]; } else if (color->colortype == LCT_RGB) { /*error: this chunk must be 6 bytes for RGB image*/ if (chunkLength != 6) return 41; color->key_defined = 1; color->key_r = 256u * data[0] + data[1]; color->key_g = 256u * data[2] + data[3]; color->key_b = 256u * data[4] + data[5]; } else return 42; /*error: tRNS chunk not allowed for other color models*/ return 0; /* OK */ } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*background color chunk (bKGD)*/ static unsigned readChunk_bKGD(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (info->color.colortype == LCT_PALETTE) { /*error: this chunk must be 1 byte for indexed color image*/ if (chunkLength != 1) return 43; info->background_defined = 1; info->background_r = info->background_g = info->background_b = data[0]; } else if (info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) { /*error: this chunk must be 2 bytes for greyscale image*/ if (chunkLength != 2) return 44; info->background_defined = 1; info->background_r = info->background_g = info->background_b = 256u * data[0] + data[1]; } else if (info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) { /*error: this chunk must be 6 bytes for greyscale image*/ if (chunkLength != 6) return 45; info->background_defined = 1; info->background_r = 256u * data[0] + data[1]; info->background_g = 256u * data[2] + data[3]; info->background_b = 256u * data[4] + data[5]; } return 0; /* OK */ } /*text chunk (tEXt)*/ static unsigned readChunk_tEXt(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { unsigned error = 0; char *key = 0, *str = 0; unsigned i; while (!error) /*not really a while loop, only used to break on error*/ { unsigned length, string2_begin; length = 0; while (length < chunkLength && data[length] != 0) length++; /*even though it's not allowed by the standard, no error is thrown if there's no null termination char, if the text is empty*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; string2_begin = length + 1; /*skip keyword null terminator*/ length = chunkLength < string2_begin ? 0 : chunkLength - string2_begin; str = (char*) lodepng_malloc(length + 1); if (!str) CERROR_BREAK(error, 83); /*alloc fail*/ str[length] = 0; for (i = 0; i < length; i++) str[i] = (char) data[string2_begin + i]; error = lodepng_add_text(info, key, str); break; } lodepng_free(key); lodepng_free(str); return error; } /*compressed text chunk (zTXt)*/ static unsigned readChunk_zTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, const unsigned char* data, size_t chunkLength) { unsigned error = 0; unsigned i; unsigned length, string2_begin; char *key = 0; ucvector decoded; ucvector_init(&decoded); while (!error) /*not really a while loop, only used to break on error*/ { for (length = 0; length < chunkLength && data[length] != 0; length++) ; if (length + 2 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; if (data[length + 1] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ string2_begin = length + 2; if (string2_begin > chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ length = chunkLength - string2_begin; /*will fail if zlib error, e.g. if length is too small*/ error = zlib_decompress(&decoded.data, &decoded.size, (unsigned char*) (&data[string2_begin]), length, zlibsettings); if (error) break; ucvector_push_back(&decoded, 0); error = lodepng_add_text(info, key, (char*) decoded.data); break; } lodepng_free(key); ucvector_cleanup(&decoded); return error; } /*international text chunk (iTXt)*/ static unsigned readChunk_iTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, const unsigned char* data, size_t chunkLength) { unsigned error = 0; unsigned i; unsigned length, begin, compressed; char *key = 0, *langtag = 0, *transkey = 0; ucvector decoded; ucvector_init(&decoded); while (!error) /*not really a while loop, only used to break on error*/ { /*Quick check if the chunk length isn't too small. Even without check it'd still fail with other error checks below if it's too short. This just gives a different error code.*/ if (chunkLength < 5) CERROR_BREAK(error, 30); /*iTXt chunk too short*/ /*read the key*/ for (length = 0; length < chunkLength && data[length] != 0; length++) ; if (length + 3 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination char, corrupt?*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; /*read the compression method*/ compressed = data[length + 1]; if (data[length + 2] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ /*even though it's not allowed by the standard, no error is thrown if there's no null termination char, if the text is empty for the next 3 texts*/ /*read the langtag*/ begin = length + 3; length = 0; for (i = begin; i < chunkLength && data[i] != 0; i++) length++; langtag = (char*) lodepng_malloc(length + 1); if (!langtag) CERROR_BREAK(error, 83); /*alloc fail*/ langtag[length] = 0; for (i = 0; i < length; i++) langtag[i] = (char) data[begin + i]; /*read the transkey*/ begin += length + 1; length = 0; for (i = begin; i < chunkLength && data[i] != 0; i++) length++; transkey = (char*) lodepng_malloc(length + 1); if (!transkey) CERROR_BREAK(error, 83); /*alloc fail*/ transkey[length] = 0; for (i = 0; i < length; i++) transkey[i] = (char) data[begin + i]; /*read the actual text*/ begin += length + 1; length = chunkLength < begin ? 0 : chunkLength - begin; if (compressed) { /*will fail if zlib error, e.g. if length is too small*/ error = zlib_decompress(&decoded.data, &decoded.size, (unsigned char*) (&data[begin]), length, zlibsettings); if (error) break; if (decoded.allocsize < decoded.size) decoded.allocsize = decoded.size; ucvector_push_back(&decoded, 0); } else { if (!ucvector_resize(&decoded, length + 1)) CERROR_BREAK(error, 83 /*alloc fail*/); decoded.data[length] = 0; for (i = 0; i < length; i++) decoded.data[i] = data[begin + i]; } error = lodepng_add_itext(info, key, langtag, transkey, (char*) decoded.data); break; } lodepng_free(key); lodepng_free(langtag); lodepng_free(transkey); ucvector_cleanup(&decoded); return error; } static unsigned readChunk_tIME(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (chunkLength != 7) return 73; /*invalid tIME chunk size*/ info->time_defined = 1; info->time.year = 256u * data[0] + data[1]; info->time.month = data[2]; info->time.day = data[3]; info->time.hour = data[4]; info->time.minute = data[5]; info->time.second = data[6]; return 0; /* OK */ } static unsigned readChunk_pHYs(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (chunkLength != 9) return 74; /*invalid pHYs chunk size*/ info->phys_defined = 1; info->phys_x = 16777216u * data[0] + 65536u * data[1] + 256u * data[2] + data[3]; info->phys_y = 16777216u * data[4] + 65536u * data[5] + 256u * data[6] + data[7]; info->phys_unit = data[8]; return 0; /* OK */ } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*read a PNG, the result will be in the same color type as the PNG (hence "generic")*/ static void decodeGeneric(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { unsigned char IEND = 0; const unsigned char* chunk; size_t i; ucvector idat; /*the data from idat chunks*/ ucvector scanlines; /*for unknown chunk order*/ unsigned unknown = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS unsigned critical_pos = 1; /*1 = after IHDR, 2 = after PLTE, 3 = after IDAT*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*provide some proper output values if error will happen*/ *out = 0; state->error = lodepng_inspect(w, h, state, in, insize); /*reads header and resets other parameters in state->info_png*/ if (state->error) return; ucvector_init(&idat); chunk = &in[33]; /*first byte of the first chunk after the header*/ /*loop through the chunks, ignoring unknown chunks and stopping at IEND chunk. IDAT data is put at the start of the in buffer*/ while (!IEND && !state->error) { unsigned chunkLength; const unsigned char* data; /*the data in the chunk*/ /*error: size of the in buffer too small to contain next chunk*/ if ((size_t) ((chunk - in) + 12) > insize || chunk < in) CERROR_BREAK(state->error, 30); /*length of the data of the chunk, excluding the length bytes, chunk type and CRC bytes*/ chunkLength = lodepng_chunk_length(chunk); /*error: chunk length larger than the max PNG chunk size*/ if (chunkLength > 2147483647) CERROR_BREAK(state->error, 63); if ((size_t) ((chunk - in) + chunkLength + 12) > insize || (chunk + chunkLength + 12) < in) { CERROR_BREAK(state->error, 64); /*error: size of the in buffer too small to contain next chunk*/ } data = lodepng_chunk_data_const(chunk); /*IDAT chunk, containing compressed image data*/ if (lodepng_chunk_type_equals(chunk, "IDAT")) { size_t oldsize = idat.size; if (!ucvector_resize(&idat, oldsize + chunkLength)) CERROR_BREAK(state->error, 83 /*alloc fail*/); for (i = 0; i < chunkLength; i++) idat.data[oldsize + i] = data[i]; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS critical_pos = 3; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } /*IEND chunk*/ else if (lodepng_chunk_type_equals(chunk, "IEND")) { IEND = 1; } /*palette chunk (PLTE)*/ else if (lodepng_chunk_type_equals(chunk, "PLTE")) { state->error = readChunk_PLTE(&state->info_png.color, data, chunkLength); if (state->error) break; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS critical_pos = 2; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } /*palette transparency chunk (tRNS)*/ else if (lodepng_chunk_type_equals(chunk, "tRNS")) { state->error = readChunk_tRNS(&state->info_png.color, data, chunkLength); if (state->error) break; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*background color chunk (bKGD)*/ else if (lodepng_chunk_type_equals(chunk, "bKGD")) { state->error = readChunk_bKGD(&state->info_png, data, chunkLength); if (state->error) break; } /*text chunk (tEXt)*/ else if (lodepng_chunk_type_equals(chunk, "tEXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_tEXt(&state->info_png, data, chunkLength); if (state->error) break; } } /*compressed text chunk (zTXt)*/ else if (lodepng_chunk_type_equals(chunk, "zTXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_zTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); if (state->error) break; } } /*international text chunk (iTXt)*/ else if (lodepng_chunk_type_equals(chunk, "iTXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_iTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); if (state->error) break; } } else if (lodepng_chunk_type_equals(chunk, "tIME")) { state->error = readChunk_tIME(&state->info_png, data, chunkLength); if (state->error) break; } else if (lodepng_chunk_type_equals(chunk, "pHYs")) { state->error = readChunk_pHYs(&state->info_png, data, chunkLength); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ else /*it's not an implemented chunk type, so ignore it: skip over the data*/ { /*error: unknown critical chunk (5th bit of first byte of chunk type is 0)*/ if (!lodepng_chunk_ancillary(chunk)) CERROR_BREAK(state->error, 69); unknown = 1; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS if (state->decoder.remember_unknown_chunks) { state->error = lodepng_chunk_append( &state->info_png.unknown_chunks_data[critical_pos - 1], &state->info_png.unknown_chunks_size[critical_pos - 1], chunk); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } if (!state->decoder.ignore_crc && !unknown) /*check CRC if wanted, only on known chunk types*/ { if (lodepng_chunk_check_crc(chunk)) CERROR_BREAK(state->error, 57); /*invalid CRC*/ } if (!IEND) chunk = lodepng_chunk_next_const(chunk); } ucvector_init(&scanlines); if (!state->error) { /*maximum final image length is already reserved in the vector's length - this is not really necessary*/ if (!ucvector_resize(&scanlines, lodepng_get_raw_size(*w, *h, &state->info_png.color) + *h)) { state->error = 83; /*alloc fail*/ } } if (!state->error) { /*decompress with the Zlib decompressor*/ state->error = zlib_decompress(&scanlines.data, &scanlines.size, idat.data, idat.size, &state->decoder.zlibsettings); } ucvector_cleanup(&idat); if (!state->error) { ucvector outv; ucvector_init(&outv); if (!ucvector_resizev(&outv, lodepng_get_raw_size(*w, *h, &state->info_png.color), 0)) state->error = 83; /*alloc fail*/ if (!state->error) state->error = postProcessScanlines(outv.data, scanlines.data, *w, *h, &state->info_png); *out = outv.data; } ucvector_cleanup(&scanlines); } unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { *out = 0; decodeGeneric(out, w, h, state, in, insize); if (state->error) return state->error; if (!state->decoder.color_convert || lodepng_color_mode_equal(&state->info_raw, &state->info_png.color)) { /*same color type, no copying or converting of data needed*/ /*store the info_png color settings on the info_raw so that the info_raw still reflects what colortype the raw image has to the end user*/ if (!state->decoder.color_convert) { state->error = lodepng_color_mode_copy(&state->info_raw, &state->info_png.color); if (state->error) return state->error; } } else { /*color conversion needed; sort of copy of the data*/ unsigned char* data = *out; size_t outsize; /*TODO: check if this works according to the statement in the documentation: "The converter can convert from greyscale input color type, to 8-bit greyscale or greyscale with alpha"*/ if (!(state->info_raw.colortype == LCT_RGB || state->info_raw.colortype == LCT_RGBA) && !(state->info_raw.bitdepth == 8)) { return 56; /*unsupported color mode conversion*/ } outsize = lodepng_get_raw_size(*w, *h, &state->info_raw); *out = (unsigned char*) lodepng_malloc(outsize); if (!(*out)) { state->error = 83; /*alloc fail*/ } else state->error = lodepng_convert(*out, data, &state->info_raw, &state->info_png.color, *w, *h, state->decoder.fix_png); lodepng_free(data); } return state->error; } unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth) { unsigned error; LodePNGState state; lodepng_state_init(&state); state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; error = lodepng_decode(out, w, h, &state, in, insize); lodepng_state_cleanup(&state); return error; } unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) { return lodepng_decode_memory(out, w, h, in, insize, LCT_RGBA, 8); } unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) { return lodepng_decode_memory(out, w, h, in, insize, LCT_RGB, 8); } #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error; error = lodepng_load_file(&buffer, &buffersize, filename); if (!error) error = lodepng_decode_memory(out, w, h, buffer, buffersize, colortype, bitdepth); lodepng_free(buffer); return error; } unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) { return lodepng_decode_file(out, w, h, filename, LCT_RGBA, 8); } unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) { return lodepng_decode_file(out, w, h, filename, LCT_RGB, 8); } #endif /*LODEPNG_COMPILE_DISK*/ void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings) { settings->color_convert = 1; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS settings->read_text_chunks = 1; settings->remember_unknown_chunks = 0; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ settings->ignore_crc = 0; settings->fix_png = 0; lodepng_decompress_settings_init(&settings->zlibsettings); } #endif /*LODEPNG_COMPILE_DECODER*/ #if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) void lodepng_state_init(LodePNGState* state) { #ifdef LODEPNG_COMPILE_DECODER lodepng_decoder_settings_init(&state->decoder); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER lodepng_encoder_settings_init(&state->encoder); #endif /*LODEPNG_COMPILE_ENCODER*/ lodepng_color_mode_init(&state->info_raw); lodepng_info_init(&state->info_png); state->error = 1; } void lodepng_state_cleanup(LodePNGState* state) { lodepng_color_mode_cleanup(&state->info_raw); lodepng_info_cleanup(&state->info_png); } void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source) { lodepng_state_cleanup(dest); *dest = *source; lodepng_color_mode_init(&dest->info_raw); lodepng_info_init(&dest->info_png); dest->error = lodepng_color_mode_copy(&dest->info_raw, &source->info_raw); if (dest->error) return; dest->error = lodepng_info_copy(&dest->info_png, &source->info_png); if (dest->error) return; } #endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ #ifdef LODEPNG_COMPILE_ENCODER /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG Encoder / */ /* ////////////////////////////////////////////////////////////////////////// */ /*chunkName must be string of 4 characters*/ static unsigned addChunk(ucvector* out, const char* chunkName, const unsigned char* data, size_t length) { CERROR_TRY_RETURN( lodepng_chunk_create(&out->data, &out->size, (unsigned )length, chunkName, data)); out->allocsize = out->size; /*fix the allocsize again*/ return 0; } static void writeSignature(ucvector* out) { /*8 bytes PNG signature, aka the magic bytes*/ ucvector_push_back(out, 137); ucvector_push_back(out, 80); ucvector_push_back(out, 78); ucvector_push_back(out, 71); ucvector_push_back(out, 13); ucvector_push_back(out, 10); ucvector_push_back(out, 26); ucvector_push_back(out, 10); } static unsigned addChunk_IHDR(ucvector* out, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth, unsigned interlace_method) { unsigned error = 0; ucvector header; ucvector_init(&header); lodepng_add32bitInt(&header, w); /*width*/ lodepng_add32bitInt(&header, h); /*height*/ ucvector_push_back(&header, (unsigned char) bitdepth); /*bit depth*/ ucvector_push_back(&header, (unsigned char) colortype); /*color type*/ ucvector_push_back(&header, 0); /*compression method*/ ucvector_push_back(&header, 0); /*filter method*/ ucvector_push_back(&header, interlace_method); /*interlace method*/ error = addChunk(out, "IHDR", header.data, header.size); ucvector_cleanup(&header); return error; } static unsigned addChunk_PLTE(ucvector* out, const LodePNGColorMode* info) { unsigned error = 0; size_t i; ucvector PLTE; ucvector_init(&PLTE); for (i = 0; i < info->palettesize * 4; i++) { /*add all channels except alpha channel*/ if (i % 4 != 3) ucvector_push_back(&PLTE, info->palette[i]); } error = addChunk(out, "PLTE", PLTE.data, PLTE.size); ucvector_cleanup(&PLTE); return error; } static unsigned addChunk_tRNS(ucvector* out, const LodePNGColorMode* info) { unsigned error = 0; size_t i; ucvector tRNS; ucvector_init(&tRNS); if (info->colortype == LCT_PALETTE) { size_t amount = info->palettesize; /*the tail of palette values that all have 255 as alpha, does not have to be encoded*/ for (i = info->palettesize; i > 0; i--) { if (info->palette[4 * (i - 1) + 3] == 255) amount--; else break; } /*add only alpha channel*/ for (i = 0; i < amount; i++) ucvector_push_back(&tRNS, info->palette[4 * i + 3]); } else if (info->colortype == LCT_GREY) { if (info->key_defined) { ucvector_push_back(&tRNS, (unsigned char) (info->key_r / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_r % 256)); } } else if (info->colortype == LCT_RGB) { if (info->key_defined) { ucvector_push_back(&tRNS, (unsigned char) (info->key_r / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_r % 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_g / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_g % 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_b / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_b % 256)); } } error = addChunk(out, "tRNS", tRNS.data, tRNS.size); ucvector_cleanup(&tRNS); return error; } static unsigned addChunk_IDAT(ucvector* out, const unsigned char* data, size_t datasize, LodePNGCompressSettings* zlibsettings) { ucvector zlibdata; unsigned error = 0; /*compress with the Zlib compressor*/ ucvector_init(&zlibdata); error = zlib_compress(&zlibdata.data, &zlibdata.size, data, datasize, zlibsettings); if (!error) error = addChunk(out, "IDAT", zlibdata.data, zlibdata.size); ucvector_cleanup(&zlibdata); return error; } static unsigned addChunk_IEND(ucvector* out) { unsigned error = 0; error = addChunk(out, "IEND", 0, 0); return error; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static unsigned addChunk_tEXt(ucvector* out, const char* keyword, const char* textstring) { unsigned error = 0; size_t i; ucvector text; ucvector_init(&text); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&text, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&text, 0); /*0 termination char*/ for (i = 0; textstring[i] != 0; i++) ucvector_push_back(&text, (unsigned char) textstring[i]); error = addChunk(out, "tEXt", text.data, text.size); ucvector_cleanup(&text); return error; } static unsigned addChunk_zTXt(ucvector* out, const char* keyword, const char* textstring, LodePNGCompressSettings* zlibsettings) { unsigned error = 0; ucvector data, compressed; size_t i, textsize = strlen(textstring); ucvector_init(&data); ucvector_init(&compressed); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&data, 0); /*0 termination char*/ ucvector_push_back(&data, 0); /*compression method: 0*/ error = zlib_compress(&compressed.data, &compressed.size, (unsigned char*) textstring, textsize, zlibsettings); if (!error) { for (i = 0; i < compressed.size; i++) ucvector_push_back(&data, compressed.data[i]); error = addChunk(out, "zTXt", data.data, data.size); } ucvector_cleanup(&compressed); ucvector_cleanup(&data); return error; } static unsigned addChunk_iTXt(ucvector* out, unsigned compressed, const char* keyword, const char* langtag, const char* transkey, const char* textstring, LodePNGCompressSettings* zlibsettings) { unsigned error = 0; ucvector data; size_t i, textsize = strlen(textstring); ucvector_init(&data); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&data, 0); /*null termination char*/ ucvector_push_back(&data, compressed ? 1 : 0); /*compression flag*/ ucvector_push_back(&data, 0); /*compression method*/ for (i = 0; langtag[i] != 0; i++) ucvector_push_back(&data, (unsigned char) langtag[i]); ucvector_push_back(&data, 0); /*null termination char*/ for (i = 0; transkey[i] != 0; i++) ucvector_push_back(&data, (unsigned char) transkey[i]); ucvector_push_back(&data, 0); /*null termination char*/ if (compressed) { ucvector compressed_data; ucvector_init(&compressed_data); error = zlib_compress(&compressed_data.data, &compressed_data.size, (unsigned char*) textstring, textsize, zlibsettings); if (!error) { for (i = 0; i < compressed_data.size; i++) ucvector_push_back(&data, compressed_data.data[i]); } ucvector_cleanup(&compressed_data); } else /*not compressed*/ { for (i = 0; textstring[i] != 0; i++) ucvector_push_back(&data, (unsigned char) textstring[i]); } if (!error) error = addChunk(out, "iTXt", data.data, data.size); ucvector_cleanup(&data); return error; } static unsigned addChunk_bKGD(ucvector* out, const LodePNGInfo* info) { unsigned error = 0; ucvector bKGD; ucvector_init(&bKGD); if (info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); } else if (info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_g / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_g % 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_b / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_b % 256)); } else if (info->color.colortype == LCT_PALETTE) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); /*palette index*/ } error = addChunk(out, "bKGD", bKGD.data, bKGD.size); ucvector_cleanup(&bKGD); return error; } static unsigned addChunk_tIME(ucvector* out, const LodePNGTime* time) { unsigned error = 0; unsigned char* data = (unsigned char*) lodepng_malloc(7); if (!data) return 83; /*alloc fail*/ data[0] = (unsigned char) (time->year / 256); data[1] = (unsigned char) (time->year % 256); data[2] = (unsigned char) time->month; data[3] = (unsigned char) time->day; data[4] = (unsigned char) time->hour; data[5] = (unsigned char) time->minute; data[6] = (unsigned char) time->second; error = addChunk(out, "tIME", data, 7); lodepng_free(data); return error; } static unsigned addChunk_pHYs(ucvector* out, const LodePNGInfo* info) { unsigned error = 0; ucvector data; ucvector_init(&data); lodepng_add32bitInt(&data, info->phys_x); lodepng_add32bitInt(&data, info->phys_y); ucvector_push_back(&data, info->phys_unit); error = addChunk(out, "pHYs", data.data, data.size); ucvector_cleanup(&data); return error; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ static void filterScanline(unsigned char* out, const unsigned char* scanline, const unsigned char* prevline, size_t length, size_t bytewidth, unsigned char filterType) { size_t i; switch (filterType) { case 0: /*None*/ for (i = 0; i < length; i++) out[i] = scanline[i]; break; case 1: /*Sub*/ if (prevline) { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; } break; case 2: /*Up*/ if (prevline) { for (i = 0; i < length; i++) out[i] = scanline[i] - prevline[i]; } else { for (i = 0; i < length; i++) out[i] = scanline[i]; } break; case 3: /*Average*/ if (prevline) { for (i = 0; i < bytewidth; i++) out[i] = scanline[i] - prevline[i] / 2; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - ((scanline[i - bytewidth] + prevline[i]) / 2); } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth] / 2; } break; case 4: /*Paeth*/ if (prevline) { /*paethPredictor(0, prevline[i], 0) is always prevline[i]*/ for (i = 0; i < bytewidth; i++) out[i] = (scanline[i] - prevline[i]); for (i = bytewidth; i < length; i++) { out[i] = (scanline[i] - paethPredictor(scanline[i - bytewidth], prevline[i], prevline[i - bytewidth])); } } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; /*paethPredictor(scanline[i - bytewidth], 0, 0) is always scanline[i - bytewidth]*/ for (i = bytewidth; i < length; i++) out[i] = (scanline[i] - scanline[i - bytewidth]); } break; default: return; /*unexisting filter type given*/ } } /* log2 approximation. A slight bit faster than std::log. */ static float flog2(float f) { float result = 0; while (f > 32) { result += 4; f /= 16; } while (f > 2) { result++; f /= 2; } return result + 1.442695f * (f * f * f / 3 - 3 * f * f / 2 + 3 * f - 1.83333f); } static unsigned filter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, const LodePNGColorMode* info, const LodePNGEncoderSettings* settings) { /* For PNG filter method 0 out must be a buffer with as size: h + (w * h * bpp + 7) / 8, because there are the scanlines with 1 extra byte per scanline */ unsigned bpp = lodepng_get_bpp(info); /*the width of a scanline in bytes, not including the filter type*/ size_t linebytes = (w * bpp + 7) / 8; /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ size_t bytewidth = (bpp + 7) / 8; const unsigned char* prevline = 0; unsigned x, y; unsigned error = 0; LodePNGFilterStrategy strategy = settings->filter_strategy; /* There is a heuristic called the minimum sum of absolute differences heuristic, suggested by the PNG standard: * If the image type is Palette, or the bit depth is smaller than 8, then do not filter the image (i.e. use fixed filtering, with the filter None). * (The other case) If the image type is Grayscale or RGB (with or without Alpha), and the bit depth is not smaller than 8, then use adaptive filtering heuristic as follows: independently for each row, apply all five filters and select the filter that produces the smallest sum of absolute values per row. This heuristic is used if filter strategy is LFS_MINSUM and filter_palette_zero is true. If filter_palette_zero is true and filter_strategy is not LFS_MINSUM, the above heuristic is followed, but for "the other case", whatever strategy filter_strategy is set to instead of the minimum sum heuristic is used. */ if (settings->filter_palette_zero && (info->colortype == LCT_PALETTE || info->bitdepth < 8)) strategy = LFS_ZERO; if (bpp == 0) return 31; /*error: invalid color type*/ if (strategy == LFS_ZERO) { for (y = 0; y < h; y++) { size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ size_t inindex = linebytes * y; out[outindex] = 0; /*filter type byte*/ filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, 0); prevline = &in[inindex]; } } else if (strategy == LFS_MINSUM) { /*adaptive filtering*/ size_t sum[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ size_t smallest = 0; unsigned char type, bestType = 0; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); if (!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ } if (!error) { for (y = 0; y < h; y++) { /*try the 5 filter types*/ for (type = 0; type < 5; type++) { filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); /*calculate the sum of the result*/ sum[type] = 0; if (type == 0) { for (x = 0; x < linebytes; x++) sum[type] += (unsigned char) (attempt[type].data[x]); } else { for (x = 0; x < linebytes; x++) { /*For differences, each byte should be treated as signed, values above 127 are negative (converted to signed char). Filtertype 0 isn't a difference though, so use unsigned there. This means filtertype 0 is almost never chosen, but that is justified.*/ unsigned char s = attempt[type].data[x]; sum[type] += s < 128 ? s : (255U - s); } } /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || sum[type] < smallest) { bestType = type; smallest = sum[type]; } } prevline = &in[y * linebytes]; /*now fill the out values*/ out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else if (strategy == LFS_ENTROPY) { float sum[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ float smallest = 0; unsigned type, bestType = 0; unsigned count[256]; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); if (!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ } for (y = 0; y < h; y++) { /*try the 5 filter types*/ for (type = 0; type < 5; type++) { filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); for (x = 0; x < 256; x++) count[x] = 0; for (x = 0; x < linebytes; x++) count[attempt[type].data[x]]++; count[type]++; /*the filter type itself is part of the scanline*/ sum[type] = 0; for (x = 0; x < 256; x++) { float p = count[x] / (float) (linebytes + 1); sum[type] += count[x] == 0 ? 0 : flog2(1 / p) * p; } /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || sum[type] < smallest) { bestType = type; smallest = sum[type]; } } prevline = &in[y * linebytes]; /*now fill the out values*/ out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else if (strategy == LFS_PREDEFINED) { for (y = 0; y < h; y++) { size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ size_t inindex = linebytes * y; unsigned char type = settings->predefined_filters[y]; out[outindex] = type; /*filter type byte*/ filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, type); prevline = &in[inindex]; } } else if (strategy == LFS_BRUTE_FORCE) { /*brute force filter chooser. deflate the scanline after every filter attempt to see which one deflates best. This is very slow and gives only slightly smaller, sometimes even larger, result*/ size_t size[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ size_t smallest = 0; unsigned type = 0, bestType = 0; unsigned char* dummy; LodePNGCompressSettings zlibsettings = settings->zlibsettings; /*use fixed tree on the attempts so that the tree is not adapted to the filtertype on purpose, to simulate the true case where the tree is the same for the whole image. Sometimes it gives better result with dynamic tree anyway. Using the fixed tree sometimes gives worse, but in rare cases better compression. It does make this a bit less slow, so it's worth doing this.*/ zlibsettings.btype = 1; /*a custom encoder likely doesn't read the btype setting and is optimized for complete PNG images only, so disable it*/ zlibsettings.custom_zlib = 0; zlibsettings.custom_deflate = 0; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); ucvector_resize(&attempt[type], linebytes); /*todo: give error if resize failed*/ } for (y = 0; y < h; y++) /*try the 5 filter types*/ { for (type = 0; type < 5; type++) { unsigned testsize = attempt[type].size; /*if(testsize > 8) testsize /= 8;*//*it already works good enough by testing a part of the row*/ filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); size[type] = 0; dummy = 0; zlib_compress(&dummy, &size[type], attempt[type].data, testsize, &zlibsettings); lodepng_free(dummy); /*check if this is smallest size (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || size[type] < smallest) { bestType = type; smallest = size[type]; } } prevline = &in[y * linebytes]; out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else return 88; /* unknown filter strategy */ return error; } static void addPaddingBits(unsigned char* out, const unsigned char* in, size_t olinebits, size_t ilinebits, unsigned h) { /*The opposite of the removePaddingBits function olinebits must be >= ilinebits*/ unsigned y; size_t diff = olinebits - ilinebits; size_t obp = 0, ibp = 0; /*bit pointers*/ for (y = 0; y < h; y++) { size_t x; for (x = 0; x < ilinebits; x++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } /*obp += diff; --> no, fill in some value in the padding bits too, to avoid "Use of uninitialised value of size ###" warning from valgrind*/ for (x = 0; x < diff; x++) setBitOfReversedStream(&obp, out, 0); } } /* in: non-interlaced image with size w*h out: the same pixels, but re-ordered according to PNG's Adam7 interlacing, with no padding bits between scanlines, but between reduced images so that each reduced image starts at a byte. bpp: bits per pixel there are no padding bits, not between scanlines, not between reduced images in has the following size in bits: w * h * bpp. out is possibly bigger due to padding bits between reduced images NOTE: comments about padding bits are only relevant if bpp < 8 */ static void Adam7_interlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); if (bpp >= 8) { for (i = 0; i < 7; i++) { unsigned x, y, b; size_t bytewidth = bpp / 8; for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { size_t pixelinstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; size_t pixeloutstart = passstart[i] + (y * passw[i] + x) * bytewidth; for (b = 0; b < bytewidth; b++) { out[pixeloutstart + b] = in[pixelinstart + b]; } } } } else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ { for (i = 0; i < 7; i++) { unsigned x, y, b; unsigned ilinebits = bpp * passw[i]; unsigned olinebits = bpp * w; size_t obp, ibp; /*bit pointers (for out and in buffer)*/ for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { ibp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; obp = (8 * passstart[i]) + (y * ilinebits + x * bpp); for (b = 0; b < bpp; b++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } } } } } /*out must be buffer big enough to contain uncompressed IDAT chunk data, and in must contain the full image. return value is error**/ static unsigned preProcessScanlines(unsigned char** out, size_t* outsize, const unsigned char* in, unsigned w, unsigned h, const LodePNGInfo* info_png, const LodePNGEncoderSettings* settings) { /* This function converts the pure 2D image with the PNG's colortype, into filtered-padded-interlaced data. Steps: *) if no Adam7: 1) add padding bits (= posible extra bits per scanline if bpp < 8) 2) filter *) if adam7: 1) Adam7_interlace 2) 7x add padding bits 3) 7x filter */ unsigned bpp = lodepng_get_bpp(&info_png->color); unsigned error = 0; if (info_png->interlace_method == 0) { *outsize = h + (h * ((w * bpp + 7) / 8)); /*image size plus an extra byte per scanline + possible padding bits*/ *out = (unsigned char*) lodepng_malloc(*outsize); if (!(*out) && (*outsize)) error = 83; /*alloc fail*/ if (!error) { /*non multiple of 8 bits per scanline, padding bits needed per scanline*/ if (bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) { unsigned char* padded = (unsigned char*) lodepng_malloc( h * ((w * bpp + 7) / 8)); if (!padded) error = 83; /*alloc fail*/ if (!error) { addPaddingBits(padded, in, ((w * bpp + 7) / 8) * 8, w * bpp, h); error = filter(*out, padded, w, h, &info_png->color, settings); } lodepng_free(padded); } else { /*we can immediatly filter into the out buffer, no other steps needed*/ error = filter(*out, in, w, h, &info_png->color, settings); } } } else /*interlace_method is 1 (Adam7)*/ { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned char* adam7; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); *outsize = filter_passstart[7]; /*image size plus an extra byte per scanline + possible padding bits*/ *out = (unsigned char*) lodepng_malloc(*outsize); if (!(*out)) error = 83; /*alloc fail*/ adam7 = (unsigned char*) lodepng_malloc(passstart[7]); if (!adam7 && passstart[7]) error = 83; /*alloc fail*/ if (!error) { unsigned i; Adam7_interlace(adam7, in, w, h, bpp); for (i = 0; i < 7; i++) { if (bpp < 8) { unsigned char* padded = (unsigned char*) lodepng_malloc( padded_passstart[i + 1] - padded_passstart[i]); if (!padded) ERROR_BREAK(83); /*alloc fail*/ addPaddingBits(padded, &adam7[passstart[i]], ((passw[i] * bpp + 7) / 8) * 8, passw[i] * bpp, passh[i]); error = filter(&(*out)[filter_passstart[i]], padded, passw[i], passh[i], &info_png->color, settings); lodepng_free(padded); } else { error = filter(&(*out)[filter_passstart[i]], &adam7[padded_passstart[i]], passw[i], passh[i], &info_png->color, settings); } if (error) break; } } lodepng_free(adam7); } return error; } /* palette must have 4 * palettesize bytes allocated, and given in format RGBARGBARGBARGBA... returns 0 if the palette is opaque, returns 1 if the palette has a single color with alpha 0 ==> color key returns 2 if the palette is semi-translucent. */ static unsigned getPaletteTranslucency(const unsigned char* palette, size_t palettesize) { size_t i; unsigned key = 0; unsigned r = 0, g = 0, b = 0; /*the value of the color with alpha 0, so long as color keying is possible*/ for (i = 0; i < palettesize; i++) { if (!key && palette[4 * i + 3] == 0) { r = palette[4 * i + 0]; g = palette[4 * i + 1]; b = palette[4 * i + 2]; key = 1; i = (size_t) (-1); /*restart from beginning, to detect earlier opaque colors with key's value*/ } else if (palette[4 * i + 3] != 255) return 2; /*when key, no opaque RGB may have key's RGB*/ else if (key && r == palette[i * 4 + 0] && g == palette[i * 4 + 1] && b == palette[i * 4 + 2]) return 2; } return key; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static unsigned addUnknownChunks(ucvector* out, unsigned char* data, size_t datasize) { unsigned char* inchunk = data; while ((size_t) (inchunk - data) < datasize) { CERROR_TRY_RETURN(lodepng_chunk_append(&out->data, &out->size, inchunk)); out->allocsize = out->size; /*fix the allocsize again*/ inchunk = lodepng_chunk_next(inchunk); } return 0; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ unsigned lodepng_encode(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGState* state) { LodePNGInfo info; ucvector outv; unsigned char* data = 0; /*uncompressed version of the IDAT chunk data*/ size_t datasize = 0; /*provide some proper output values if error will happen*/ *out = 0; *outsize = 0; state->error = 0; lodepng_info_init(&info); lodepng_info_copy(&info, &state->info_png); if ((info.color.colortype == LCT_PALETTE || state->encoder.force_palette) && (info.color.palettesize == 0 || info.color.palettesize > 256)) { state->error = 68; /*invalid palette size, it is only allowed to be 1-256*/ return state->error; } if (state->encoder.auto_convert != LAC_NO) { state->error = lodepng_auto_choose_color(&info.color, image, w, h, &state->info_raw, state->encoder.auto_convert); } if (state->error) return state->error; if (state->encoder.zlibsettings.btype > 2) { CERROR_RETURN_ERROR(state->error, 61); /*error: unexisting btype*/ } if (state->info_png.interlace_method > 1) { CERROR_RETURN_ERROR(state->error, 71); /*error: unexisting interlace mode*/ } state->error = checkColorValidity(info.color.colortype, info.color.bitdepth); if (state->error) return state->error; /*error: unexisting color type given*/ state->error = checkColorValidity(state->info_raw.colortype, state->info_raw.bitdepth); if (state->error) return state->error; /*error: unexisting color type given*/ if (!lodepng_color_mode_equal(&state->info_raw, &info.color)) { unsigned char* converted; size_t size = (w * h * lodepng_get_bpp(&info.color) + 7) / 8; converted = (unsigned char*) lodepng_malloc(size); if (!converted && size) state->error = 83; /*alloc fail*/ if (!state->error) { state->error = lodepng_convert(converted, image, &info.color, &state->info_raw, w, h, 0 /*fix_png*/); } if (!state->error) preProcessScanlines(&data, &datasize, converted, w, h, &info, &state->encoder); lodepng_free(converted); } else preProcessScanlines(&data, &datasize, image, w, h, &info, &state->encoder); ucvector_init(&outv); while (!state->error) /*while only executed once, to break on error*/ { #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS size_t i; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*write signature and chunks*/ writeSignature(&outv); /*IHDR*/ addChunk_IHDR(&outv, w, h, info.color.colortype, info.color.bitdepth, info.interlace_method); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*unknown chunks between IHDR and PLTE*/ if (info.unknown_chunks_data[0]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[0], info.unknown_chunks_size[0]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*PLTE*/ if (info.color.colortype == LCT_PALETTE) { addChunk_PLTE(&outv, &info.color); } if (state->encoder.force_palette && (info.color.colortype == LCT_RGB || info.color.colortype == LCT_RGBA)) { addChunk_PLTE(&outv, &info.color); } /*tRNS*/ if (info.color.colortype == LCT_PALETTE && getPaletteTranslucency(info.color.palette, info.color.palettesize) != 0) { addChunk_tRNS(&outv, &info.color); } if ((info.color.colortype == LCT_GREY || info.color.colortype == LCT_RGB) && info.color.key_defined) { addChunk_tRNS(&outv, &info.color); } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*bKGD (must come between PLTE and the IDAt chunks*/ if (info.background_defined) addChunk_bKGD(&outv, &info); /*pHYs (must come before the IDAT chunks)*/ if (info.phys_defined) addChunk_pHYs(&outv, &info); /*unknown chunks between PLTE and IDAT*/ if (info.unknown_chunks_data[1]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[1], info.unknown_chunks_size[1]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*IDAT (multiple IDAT chunks must be consecutive)*/ state->error = addChunk_IDAT(&outv, data, datasize, &state->encoder.zlibsettings); if (state->error) break; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*tIME*/ if (info.time_defined) addChunk_tIME(&outv, &info.time); /*tEXt and/or zTXt*/ for (i = 0; i < info.text_num; i++) { if (strlen(info.text_keys[i]) > 79) { state->error = 66; /*text chunk too large*/ break; } if (strlen(info.text_keys[i]) < 1) { state->error = 67; /*text chunk too small*/ break; } if (state->encoder.text_compression) { addChunk_zTXt(&outv, info.text_keys[i], info.text_strings[i], &state->encoder.zlibsettings); } else { addChunk_tEXt(&outv, info.text_keys[i], info.text_strings[i]); } } /*LodePNG version id in text chunk*/ if (state->encoder.add_id) { unsigned alread_added_id_text = 0; for (i = 0; i < info.text_num; i++) { if (!strcmp(info.text_keys[i], "LodePNG")) { alread_added_id_text = 1; break; } } if (alread_added_id_text == 0) { addChunk_tEXt(&outv, "LodePNG", VERSION_STRING); /*it's shorter as tEXt than as zTXt chunk*/ } } /*iTXt*/ for (i = 0; i < info.itext_num; i++) { if (strlen(info.itext_keys[i]) > 79) { state->error = 66; /*text chunk too large*/ break; } if (strlen(info.itext_keys[i]) < 1) { state->error = 67; /*text chunk too small*/ break; } addChunk_iTXt(&outv, state->encoder.text_compression, info.itext_keys[i], info.itext_langtags[i], info.itext_transkeys[i], info.itext_strings[i], &state->encoder.zlibsettings); } /*unknown chunks between IDAT and IEND*/ if (info.unknown_chunks_data[2]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[2], info.unknown_chunks_size[2]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ addChunk_IEND(&outv); break; /*this isn't really a while loop; no error happened so break out now!*/ } lodepng_info_cleanup(&info); lodepng_free(data); /*instead of cleaning the vector up, give it to the output*/ *out = outv.data; *outsize = outv.size; return state->error; } unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned error; LodePNGState state; lodepng_state_init(&state); state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; state.info_png.color.colortype = colortype; state.info_png.color.bitdepth = bitdepth; lodepng_encode(out, outsize, image, w, h, &state); error = state.error; lodepng_state_cleanup(&state); return error; } unsigned lodepng_encode32(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGBA, 8); } unsigned lodepng_encode24(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGB, 8); } #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_encode_file(const char* filename, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode_memory(&buffer, &buffersize, image, w, h, colortype, bitdepth); if (!error) error = lodepng_save_file(buffer, buffersize, filename); lodepng_free(buffer); return error; } unsigned lodepng_encode32_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_file(filename, image, w, h, LCT_RGBA, 8); } unsigned lodepng_encode24_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_file(filename, image, w, h, LCT_RGB, 8); } #endif /*LODEPNG_COMPILE_DISK*/ void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings) { lodepng_compress_settings_init(&settings->zlibsettings); settings->filter_palette_zero = 1; settings->filter_strategy = LFS_MINSUM; settings->auto_convert = LAC_AUTO; settings->force_palette = 0; settings->predefined_filters = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS settings->add_id = 0; settings->text_compression = 1; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ERROR_TEXT /* This returns the description of a numerical error code in English. This is also the documentation of all the error codes. */ const char* lodepng_error_text(unsigned code) { switch (code) { case 0: return "no error, everything went ok"; case 1: return "nothing done yet"; /*the Encoder/Decoder has done nothing yet, error checking makes no sense yet*/ case 10: return "end of input memory reached without huffman end code"; /*while huffman decoding*/ case 11: return "error in code tree made it jump outside of huffman tree"; /*while huffman decoding*/ case 13: return "problem while processing dynamic deflate block"; case 14: return "problem while processing dynamic deflate block"; case 15: return "problem while processing dynamic deflate block"; case 16: return "unexisting code while processing dynamic deflate block"; case 17: return "end of out buffer memory reached while inflating"; case 18: return "invalid distance code while inflating"; case 19: return "end of out buffer memory reached while inflating"; case 20: return "invalid deflate block BTYPE encountered while decoding"; case 21: return "NLEN is not ones complement of LEN in a deflate block"; /*end of out buffer memory reached while inflating: This can happen if the inflated deflate data is longer than the amount of bytes required to fill up all the pixels of the image, given the color depth and image dimensions. Something that doesn't happen in a normal, well encoded, PNG image.*/ case 22: return "end of out buffer memory reached while inflating"; case 23: return "end of in buffer memory reached while inflating"; case 24: return "invalid FCHECK in zlib header"; case 25: return "invalid compression method in zlib header"; case 26: return "FDICT encountered in zlib header while it's not used for PNG"; case 27: return "PNG file is smaller than a PNG header"; /*Checks the magic file header, the first 8 bytes of the PNG file*/ case 28: return "incorrect PNG signature, it's no PNG or corrupted"; case 29: return "first chunk is not the header chunk"; case 30: return "chunk length too large, chunk broken off at end of file"; case 31: return "illegal PNG color type or bpp"; case 32: return "illegal PNG compression method"; case 33: return "illegal PNG filter method"; case 34: return "illegal PNG interlace method"; case 35: return "chunk length of a chunk is too large or the chunk too small"; case 36: return "illegal PNG filter type encountered"; case 37: return "illegal bit depth for this color type given"; case 38: return "the palette is too big"; /*more than 256 colors*/ case 39: return "more palette alpha values given in tRNS chunk than there are colors in the palette"; case 40: return "tRNS chunk has wrong size for greyscale image"; case 41: return "tRNS chunk has wrong size for RGB image"; case 42: return "tRNS chunk appeared while it was not allowed for this color type"; case 43: return "bKGD chunk has wrong size for palette image"; case 44: return "bKGD chunk has wrong size for greyscale image"; case 45: return "bKGD chunk has wrong size for RGB image"; /*Is the palette too small?*/ case 46: return "a value in indexed image is larger than the palette size (bitdepth = 8)"; /*Is the palette too small?*/ case 47: return "a value in indexed image is larger than the palette size (bitdepth < 8)"; /*the input data is empty, maybe a PNG file doesn't exist or is in the wrong path*/ case 48: return "empty input or file doesn't exist"; case 49: return "jumped past memory while generating dynamic huffman tree"; case 50: return "jumped past memory while generating dynamic huffman tree"; case 51: return "jumped past memory while inflating huffman block"; case 52: return "jumped past memory while inflating"; case 53: return "size of zlib data too small"; case 54: return "repeat symbol in tree while there was no value symbol yet"; /*jumped past tree while generating huffman tree, this could be when the tree will have more leaves than symbols after generating it out of the given lenghts. They call this an oversubscribed dynamic bit lengths tree in zlib.*/ case 55: return "jumped past tree while generating huffman tree"; case 56: return "given output image colortype or bitdepth not supported for color conversion"; case 57: return "invalid CRC encountered (checking CRC can be disabled)"; case 58: return "invalid ADLER32 encountered (checking ADLER32 can be disabled)"; case 59: return "requested color conversion not supported"; case 60: return "invalid window size given in the settings of the encoder (must be 0-32768)"; case 61: return "invalid BTYPE given in the settings of the encoder (only 0, 1 and 2 are allowed)"; /*LodePNG leaves the choice of RGB to greyscale conversion formula to the user.*/ case 62: return "conversion from color to greyscale not supported"; case 63: return "length of a chunk too long, max allowed for PNG is 2147483647 bytes per chunk"; /*(2^31-1)*/ /*this would result in the inability of a deflated block to ever contain an end code. It must be at least 1.*/ case 64: return "the length of the END symbol 256 in the Huffman tree is 0"; case 66: return "the length of a text chunk keyword given to the encoder is longer than the maximum of 79 bytes"; case 67: return "the length of a text chunk keyword given to the encoder is smaller than the minimum of 1 byte"; case 68: return "tried to encode a PLTE chunk with a palette that has less than 1 or more than 256 colors"; case 69: return "unknown chunk type with 'critical' flag encountered by the decoder"; case 71: return "unexisting interlace mode given to encoder (must be 0 or 1)"; case 72: return "while decoding, unexisting compression method encountering in zTXt or iTXt chunk (it must be 0)"; case 73: return "invalid tIME chunk size"; case 74: return "invalid pHYs chunk size"; /*length could be wrong, or data chopped off*/ case 75: return "no null termination char found while decoding text chunk"; case 76: return "iTXt chunk too short to contain required bytes"; case 77: return "integer overflow in buffer size"; case 78: return "failed to open file for reading"; /*file doesn't exist or couldn't be opened for reading*/ case 79: return "failed to open file for writing"; case 80: return "tried creating a tree of 0 symbols"; case 81: return "lazy matching at pos 0 is impossible"; case 82: return "color conversion to palette requested while a color isn't in palette"; case 83: return "memory allocation failed"; case 84: return "given image too small to contain all pixels to be encoded"; case 85: return "internal color conversion bug"; case 86: return "impossible offset in lz77 encoding (internal bug)"; case 87: return "must provide custom zlib function pointer if LODEPNG_COMPILE_ZLIB is not defined"; case 88: return "invalid filter strategy given for LodePNGEncoderSettings.filter_strategy"; case 89: return "text chunk keyword too short or long: must have size 1-79"; /*the windowsize in the LodePNGCompressSettings. Requiring POT(==> & instead of %) makes encoding 12% faster.*/ case 90: return "windowsize must be a power of two"; } return "unknown error code"; } #endif /*LODEPNG_COMPILE_ERROR_TEXT*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // C++ Wrapper // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_CPP namespace lodepng { #ifdef LODEPNG_COMPILE_DISK void load_file(std::vector& buffer, const std::string& filename) { std::ifstream file(filename.c_str(), std::ios::in | std::ios::binary | std::ios::ate); /*get filesize*/ std::streamsize size = 0; if (file.seekg(0, std::ios::end).good()) size = file.tellg(); if (file.seekg(0, std::ios::beg).good()) size -= file.tellg(); /*read contents of the file into the vector*/ buffer.resize(size_t(size)); if (size > 0) file.read((char*) (&buffer[0]), size); } /*write given buffer to the file, overwriting the file, it doesn't append to it.*/ void save_file(const std::vector& buffer, const std::string& filename) { std::ofstream file(filename.c_str(), std::ios::out | std::ios::binary); file.write(buffer.empty() ? 0 : (char*) &buffer[0], std::streamsize(buffer.size())); } #endif //LODEPNG_COMPILE_DISK #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_DECODER unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings& settings) { unsigned char* buffer = 0; size_t buffersize = 0; unsigned error = zlib_decompress(&buffer, &buffersize, in, insize, &settings); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned decompress(std::vector& out, const std::vector& in, const LodePNGDecompressSettings& settings) { return decompress(out, in.empty() ? 0 : &in[0], in.size(), settings); } #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER unsigned compress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGCompressSettings& settings) { unsigned char* buffer = 0; size_t buffersize = 0; unsigned error = zlib_compress(&buffer, &buffersize, in, insize, &settings); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned compress(std::vector& out, const std::vector& in, const LodePNGCompressSettings& settings) { return compress(out, in.empty() ? 0 : &in[0], in.size(), settings); } #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_PNG State::State() { lodepng_state_init(this); } State::State(const State& other) { lodepng_state_init(this); lodepng_state_copy(this, &other); } State::~State() { lodepng_state_cleanup(this); } State& State::operator=(const State& other) { lodepng_state_copy(this, &other); return *this; } #ifdef LODEPNG_COMPILE_DECODER unsigned decode(std::vector& out, unsigned& w, unsigned& h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; unsigned error = lodepng_decode_memory(&buffer, &w, &h, in, insize, colortype, bitdepth); if (buffer && !error) { State state; state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::vector& in, LodePNGColorType colortype, unsigned bitdepth) { return decode(out, w, h, in.empty() ? 0 : &in[0], (unsigned) in.size(), colortype, bitdepth); } unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const unsigned char* in, size_t insize) { unsigned char* buffer = NULL; unsigned error = lodepng_decode(&buffer, &w, &h, &state, in, insize); if (buffer && !error) { size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); out.insert(out.end(), &buffer[0], &buffer[buffersize]); } lodepng_free(buffer); return error; } unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const std::vector& in) { return decode(out, w, h, state, in.empty() ? 0 : &in[0], in.size()); } #ifdef LODEPNG_COMPILE_DISK unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::string& filename, LodePNGColorType colortype, unsigned bitdepth) { std::vector buffer; load_file(buffer, filename); return decode(out, w, h, buffer, colortype, bitdepth); } #endif //LODEPNG_COMPILE_DECODER #endif //LODEPNG_COMPILE_DISK #ifdef LODEPNG_COMPILE_ENCODER unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode_memory(&buffer, &buffersize, in, w, h, colortype, bitdepth); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { if (lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; return encode(out, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); } unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, State& state) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode(&buffer, &buffersize, in, w, h, &state); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, State& state) { if (lodepng_get_raw_size(w, h, &state.info_raw) > in.size()) return 84; return encode(out, in.empty() ? 0 : &in[0], w, h, state); } #ifdef LODEPNG_COMPILE_DISK unsigned encode(const std::string& filename, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { std::vector buffer; unsigned error = encode(buffer, in, w, h, colortype, bitdepth); if (!error) save_file(buffer, filename); return error; } unsigned encode(const std::string& filename, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { if (lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; return encode(filename, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); } #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_PNG } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ ================================================ FILE: framework/shared/src/metrics/ATEMetric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/ATEMetric.h" #include #include "outputs/TrajectoryAlignmentMethod.h" #include using namespace slambench::metrics; ATEMetric::ATEMetric(const slambench::outputs::TrajectoryInterface* tested_trajectory, const slambench::outputs::TrajectoryInterface * ground_truth) : Metric("ATE"), trajectory_(tested_trajectory), ground_truth_(ground_truth) { next_gt_ts_ = {0,0}; } const slambench::values::ValueDescription &ATEMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ std::make_pair("AbsoluteError", slambench::values::VT_DOUBLE), std::make_pair("OrientationError", slambench::values::VT_DOUBLE), std::make_pair("MeanATE", slambench::values::VT_DOUBLE), std::make_pair("MaxATE", slambench::values::VT_DOUBLE)}); return desc; } const std::string& ATEMetric::GetDescription() const { static std::string desc = "Absolute Trajectory Error"; return desc; } void ATEMetric::MeasureStart(Phase* phase) { (void)phase; } void ATEMetric::MeasureEnd(Phase* phase) { (void)phase; latest_trajectory_ = trajectory_->GetAll(); } Value *ATEMetric::GetValue(Phase* phase) { (void)phase; auto gt_traj = ground_truth_->GetAll(); auto es_traj = latest_trajectory_; if(gt_traj.size() == 0) { std::cerr << "**** Error: Empty GT." << std::endl; return new values::TypedValue((double(std::nan("")))); } auto gt_iterator = gt_traj.begin() ; auto es_iterator = es_traj.begin() ; double LastATE = 0.0; double MaxATE = 0.0; double SumATE = 0.0; double CountATE = 0.0; double LastAOE = 0.0; for (es_iterator = es_traj.begin() ; es_iterator != es_traj.end() ; es_iterator ++) { // Find closest gt point //**************************************************************************************** // Step 1 : ensure GT in the futre exists //*************************************** while((gt_iterator->first < es_iterator->first) && gt_iterator != gt_traj.end() ) { gt_iterator++; } if(gt_iterator == gt_traj.end()) { std::cerr << "**** ATE Error: No more groundtruth to compare with." << std::endl; LastATE = double(std::nan("")); break; } // Step 2 : Closest Future //************************ auto closest = gt_iterator; for (; gt_iterator != gt_traj.end(); ++gt_iterator) { auto GT_TS = gt_iterator; if ( GT_TS->first > es_iterator->first ) { break; } auto CL_TS = gt_iterator; if (es_iterator->first - CL_TS->first > es_iterator->first - GT_TS->first) { closest = GT_TS; } } gt_iterator = closest; // compute Absolute Error for this point //**************************************************************************************** const Eigen::Matrix4f& gt_pose = gt_iterator->second.GetValue(); const Eigen::Matrix4f& aligned_pose = es_iterator->second.GetValue(); Eigen::Vector3f diff = { std::abs(gt_pose(0,3) - aligned_pose(0,3)) , std::abs(gt_pose(1,3) - aligned_pose(1,3)) , std::abs(gt_pose(2,3) - aligned_pose(2,3)) } ; LastATE = std::sqrt( diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2]); // compute Orientation Error for this point //**************************************************************************************** Eigen::Matrix3f gt_rot = gt_pose.block<3,3>(0,0); Eigen::Matrix3f aligned_rot = aligned_pose.block<3,3>(0,0); // the rotation matrix in aligned pose has a scale factor, need be de-scaled to be a valid rotation matrix aligned_rot /= aligned_rot.block<3,1>(0,0).norm(); Eigen::AngleAxisf diff_angle(gt_rot.transpose() * aligned_rot); LastAOE = diff_angle.angle() / M_PI * 180.; // cumul values //**************************************************************************************** MaxATE = std::max(MaxATE,LastATE); SumATE += LastATE ; CountATE++; } double MeanATE = SumATE / CountATE; auto absolute_error = new slambench::values::TypeForVT::type(LastATE); auto orientation_error = new slambench::values::TypeForVT::type(LastAOE); auto mean_ate = new slambench::values::TypeForVT::type(MeanATE); auto max_ate = new slambench::values::TypeForVT::type(MaxATE); return new slambench::values::TypeForVT::type({ {"AbsoluteError",absolute_error}, {"OrientationError",orientation_error}, {"MeanATE",mean_ate}, {"MaxATE",max_ate}, }); } ================================================ FILE: framework/shared/src/metrics/DepthEstimationMetric.cpp ================================================ /* Copyright (c) 2018 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include "outputs/TrajectoryAlignmentMethod.h" #include #include #include #include using namespace slambench::metrics; DepthEstimationMetric::DepthEstimationMetric(const slambench::outputs::BaseOutput * const tested, const slambench::outputs::BaseOutput * const gt) : Metric("DepthEstimation"), tested_(tested), gt_(gt) {} const slambench::values::ValueDescription &DepthEstimationMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ {"Absolute Relative Difference", slambench::values::VT_DOUBLE}, {"DepthEstimation (1.25)", slambench::values::VT_DOUBLE}, {"DepthEstimation (1.25^2)", slambench::values::VT_DOUBLE}, {"DepthEstimation (1.25^3)", slambench::values::VT_DOUBLE}, }); return desc; } const std::string& DepthEstimationMetric::GetDescription() const { static std::string desc = "Percentage of accurately estimated pixels"; return desc; } void DepthEstimationMetric::MeasureStart(Phase* /**/){} void DepthEstimationMetric::MeasureEnd(Phase* /**/) {} Value *DepthEstimationMetric::GetValue(Phase* /**/) { const float THR = 1.25; if (tested_->Empty()) return new slambench::values::TypeForVT::type(std::nan("")); const outputs::Output::value_map_t::value_type tested_frame = tested_->GetMostRecentValue(); const outputs::Output::value_map_t::value_type gt_frame = gt_->GetMostRecentValue(); auto tested_frame_sb = reinterpret_cast(tested_frame.second); auto gt_frame_sb = reinterpret_cast(gt_frame.second); assert(tested_frame_sb->GetWidth() == gt_frame_sb->GetWidth()); assert(tested_frame_sb->GetHeight() == gt_frame_sb->GetHeight()); assert(tested_frame_sb->GetFormat() == gt_frame_sb->GetFormat()); // FIXME: extend support beyond 8-bit depth assert(tested_frame_sb->GetFormat() == slambench::io::pixelformat::EPixelFormat::D_I_8); auto width = tested_frame_sb->GetWidth(); auto height = tested_frame_sb->GetHeight(); auto pixcount = width * height; double rel = 0; double depth_est; double depth_est_thr_squared; double depth_est_thr_cubed; int count_depth_est = 0; int count_depth_est_thr_squared = 0; int count_depth_est_thr_cubed = 0; for (unsigned int ii = 0; ii < width; ++ii) { for (unsigned int jj = 0; jj < height; ++jj) { float test_depth = tested_frame_sb->at(ii,jj); float gt_depth = gt_frame_sb->at(ii, jj); rel += std::abs((gt_depth - test_depth) / test_depth); auto max_val = std::max(test_depth / gt_depth, gt_depth / test_depth); if(max_val > THR) count_depth_est++; if(max_val > THR*THR) count_depth_est_thr_squared++; if(max_val > THR*THR*THR) count_depth_est_thr_cubed++; } } rel /= pixcount; depth_est = count_depth_est * 100.0 / pixcount; depth_est_thr_squared = count_depth_est_thr_squared * 100.0 / pixcount; depth_est_thr_cubed = count_depth_est_thr_cubed * 100.0 / pixcount; auto rel_val = new slambench::values::TypeForVT::type(rel); auto depth_est_val = new slambench::values::TypeForVT::type(depth_est); auto depth_est_thr_squared_val = new slambench::values::TypeForVT::type(depth_est_thr_squared); auto depth_est_thr_cubed_val = new slambench::values::TypeForVT::type(depth_est_thr_cubed); return new slambench::values::TypeForVT::type({ {"Absolute Relative Difference",rel_val}, {"DepthEstimation (1.25)", depth_est_val}, {"DepthEstimation (1.25^2)",depth_est_thr_squared_val}, {"DepthEstimation (1.25^3)",depth_est_thr_cubed_val} }); } ================================================ FILE: framework/shared/src/metrics/DurationMetric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "sb_malloc.h" #include "metrics/DurationMetric.h" #include #include #include #include #include #include using namespace slambench::metrics; /* Duration Metric */ DurationMetric::DurationMetric() : Metric("Duration") { } void DurationMetric::MeasureStart(Phase* phase) { assert(!phase_start_.count(phase)); phase_start_[phase] = getTime(); } void DurationMetric::MeasureEnd(Phase* phase) { assert(phase_start_.count(phase)); assert(!phase_end_.count(phase)); phase_end_[phase] = getTime(); } Value *DurationMetric::GetValue(Phase *phase) { auto value = phase_end_.at(phase) - phase_start_.at(phase); phase_end_.erase(phase); phase_start_.erase(phase); // time is recorded in microseconds but report it in full seconds return new values::TypedValue(value / 1000000.0); } const slambench::values::ValueDescription &DurationMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::VT_DOUBLE; return desc; } const std::string &DurationMetric::GetDescription() const { static std::string desc = "Duration of the phase in whole microseconds"; return desc; } uint64_t DurationMetric::getTime() const { auto now = std::chrono::high_resolution_clock::now().time_since_epoch(); // convert time into time in microseconds (1/1000000) return std::chrono::duration_cast>>(now).count(); } ================================================ FILE: framework/shared/src/metrics/MemoryMetric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/MemoryMetric.h" #include "sb_malloc.h" #include #include #include #include #include #include using namespace slambench::metrics; /* CPU Memory Metric */ const slambench::values::ValueDescription &MemoryMetric::GetValueDescription() const { return desc_; } MemoryMetric::MemoryMetric() : Metric("Memory") , desc_({}) { slambench::memory::MemoryProfile::singleton.StartAlgorithm(); // if (cuda_monitor.IsActive()) { // desc_ = slambench::values::ValueDescription({ // {"CPU_Memory", slambench::values::VT_U64}, // {"GPU_Memory", slambench::values::VT_U64}, // {"CUDA_Memory", slambench::values::VT_U64}}); // } else { desc_ = slambench::values::ValueDescription({ {"CPU_Memory", slambench::values::VT_U64}, {"GPU_Memory", slambench::values::VT_U64}}); // } } MemoryMetric::~MemoryMetric() { slambench::memory::MemoryProfile::singleton.EndAlgorithm(); } void MemoryMetric::MeasureStart(Phase* phase) { (void)phase; slambench::memory::MemoryProfile::singleton.ResetBytesAllocated(); slambench::memory::MemoryProfile::singleton.ResetGPUBytesAllocated(); } void MemoryMetric::MeasureEnd(Phase* phase) { (void)phase; assert(!CPU_Usage_.count(phase)); CPU_Usage_[phase] = slambench::memory::MemoryProfile::singleton.GetOverallData().MaxBytesAllocated ; GPU_Usage_[phase] = slambench::memory::MemoryProfile::singleton.GetOverallGPUData().MaxBytesAllocated ; } Value *MemoryMetric::GetValue(Phase* phase) { auto cpu_mem = new slambench::values::TypeForVT::type(CPU_Usage_[phase]); auto gpu_mem = new slambench::values::TypeForVT::type(GPU_Usage_[phase]); CPU_Usage_.erase(phase); GPU_Usage_.erase(phase); // if (cuda_monitor.IsActive()) { // auto cuda_mem = new slambench::values::TypeForVT::type(cuda_monitor.getUsedBytes()); // return new slambench::values::TypeForVT::type({ // {"CPU_Memory",cpu_mem}, // {"GPU_Memory",gpu_mem}, // {"CUDA_Memory",cuda_mem} // }); // } else { return new slambench::values::TypeForVT::type({ {"CPU_Memory",cpu_mem}, {"GPU_Memory",gpu_mem} }); // } } const std::string& MemoryMetric::GetDescription() const { static const std::string desc = "Memory in Bytes"; return desc; } ================================================ FILE: framework/shared/src/metrics/Metric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "sb_malloc.h" #include "metrics/Metric.h" #include #include #include #include #include #include using namespace slambench::metrics; /* Metric Base Class */ Metric::Metric(const std::string& name) : name_(name) { } Metric::~Metric() { } const std::string &Metric::GetDescription() const { static std::string desc = "No description for metric"; return desc; } ================================================ FILE: framework/shared/src/metrics/MetricManager.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/Metric.h" #include "metrics/MetricManager.h" #include "metrics/Phase.h" #include "metrics/DurationMetric.h" #include #include using namespace slambench::metrics; MetricManager::MetricManager() : init_phase_(this,"Initialisation"), frame_phase_(this, "Frame"), frame_counter_(0) { strcpy(duration_metric_typeid_, typeid(DurationMetric).name()); frame_phase_duration_.clear(); } MetricManager::~MetricManager() { for(auto i : frame_data_) { delete i; } } void MetricManager::AddPhaseMetric(const MetricPtr& m) { phase_metrics_.push_back(m); all_metrics_.insert(m); } void MetricManager::AddFrameMetric(const MetricPtr& m) { frame_metrics_.push_back(m); all_metrics_.insert(m); } void MetricManager::AddPhase(Phase* p) { phases_.push_back(p); } void MetricManager::AddPhase(const std::string &phase_name) { AddPhase(new Phase(this, phase_name)); } void MetricManager::BeginInit() { for(auto &i : frame_metrics_) { i->MeasureStart(&init_phase_); } } void MetricManager::EndInit() { for(auto &i : frame_metrics_ ) { i->MeasureEnd(&init_phase_); } for(auto &i : frame_metrics_) { init_data_.insert({&*i, i->GetValue(&init_phase_)}); } } void MetricManager::BeginFrame() { for(auto &i : frame_metrics_) { i->MeasureStart(&frame_phase_); } } void MetricManager::BeginPhase(Phase* phase) { for(auto &i : phase_metrics_ ) { i->MeasureStart(phase); } } void MetricManager::EndFrame() { for(auto &i : frame_metrics_ ) { i->MeasureEnd(&frame_phase_); } auto &frame = *GetFrame(frame_counter_); auto &frame_data = frame.GetFrameData(); for(auto &i : frame_metrics_) { frame_data.insert({&*i, i->GetValue(&frame_phase_)}); if (!strcmp(duration_metric_typeid_, typeid(*i).name())) { frame_phase_duration_.push_back(dynamic_cast*>(frame_data[&*i])->GetValue()); } } // yeaaaahhhhh frame.GetPhaseData(&frame_phase_) = frame_data; for(auto &i : phase_metrics_) { for(auto j : phases_) { frame.GetPhaseData(j).insert({&*i, i->GetValue(j)}); } } frame_counter_++; } FrameData* MetricManager::GetFrame(uint64_t frame_number) { while(frame_data_.size() <= frame_number) { frame_data_.push_back(new FrameData()); } assert(frame_data_.at(frame_number) != nullptr); return frame_data_.at(frame_number); } FrameData* MetricManager::GetLastFrame() { return *frame_data_.rbegin(); } std::string MetricManager::GetHeader() const { std::ostringstream str; for(auto &m : frame_metrics_) { str << "Frame_" << m->GetName() << "\t"; } for(auto p : phases_) { for(auto &m : phase_metrics_) { str << p->GetName() << "_" << m->GetName() << "\t"; } } return str.str(); } void MetricManager::EndPhase(Phase* phase) { for(auto &i : phase_metrics_ ) { i->MeasureEnd(phase); } } Phase* MetricManager::GetPhase(const std::string& phasename) { for (auto &i : phases_) { if (i->GetName() == phasename) { return i; } } assert(false); } ================================================ FILE: framework/shared/src/metrics/Phase.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/MetricManager.h" #include "metrics/Phase.h" using namespace slambench::metrics; Phase::Phase(MetricManager* mgr, const std::string &phasename) : name_(phasename), manager_(mgr) { } void Phase::Begin() { manager_->BeginPhase(this); } void Phase::End() { manager_->EndPhase(this); } ================================================ FILE: framework/shared/src/metrics/PointCloudMetric.cpp ================================================ #include "metrics/PointCloudMetric.h" #include "io/format/PointCloud.h" using slambench::values::PointCloudValue; using namespace slambench::metrics; PointCloudMetric::PointCloudMetric(const slambench::outputs::BaseOutput * const heatmap_pointcloud) : Metric("PointCloud_Metric"), heatmap_pointcloud(heatmap_pointcloud) { } const slambench::values::ValueDescription &PointCloudMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ {"PointCloud_Metric", slambench::values::VT_DOUBLE}}); return desc; } const std::string& PointCloudMetric::GetDescription() const { static std::string desc = "Point Cloud Reconstruction Accuracy"; return desc; } void PointCloudMetric::MeasureStart(Phase* /* unused */) { } void PointCloudMetric::MeasureEnd(Phase* /* unused */) { } constexpr int COMPUTE_EVERY_FRAMES = 20; Value *PointCloudMetric::GetValue(Phase* /* unused */) { if (heatmap_pointcloud->Empty()) return new slambench::values::TypeForVT::type(std::nan("")); const outputs::Output::value_map_t::value_type tested_frame = heatmap_pointcloud->GetMostRecentValue(); const auto pcv = reinterpret_cast(tested_frame.second); double total = 0; for (const auto &value : pcv->GetPoints()) { total += value.value; } const double average = total / pcv->GetPoints().size(); return new slambench::values::TypeForVT::type(average); } ================================================ FILE: framework/shared/src/metrics/PowerMetric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifdef PAPI_MONITORING #include "metrics/power_utils/PAPIMonitor.h" #endif #ifdef XU3_MONITORING #include "metrics/power_utils/XU3Monitor.h" #endif #include "metrics/PowerMetric.h" #include "outputs/TrajectoryAlignmentMethod.h" #include namespace slambench { namespace metrics { PowerMetric::PowerMetric() : Metric("Power"), last_res_(nullptr) { pm_ = nullptr; #ifdef PAPI_MONITORING if (!pm_) { std::cerr << "*** Test PAPI Monitoring." << std::endl; pm_ = PAPIMonitor::generate(); if (pm_) {std::cerr << "*** PAPI Monitoring works." << std::endl;} else {std::cerr << "*** PAPI Monitoring failed." << std::endl;} } #endif #ifdef XU3_MONITORING if (!pm_) { std::cerr << "*** Test XU3 Monitoring." << std::endl; pm_ = XU3Monitor::generate(); if (pm_) {std::cerr << "*** XU3 Monitoring works." << std::endl;} else {std::cerr << "*** XU3 Monitoring failed." << std::endl;} } #endif if (!pm_) {std::cerr << "*** There is no available power monitoring techniques on this system." << std::endl;} } const values::ValueDescription &PowerMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription(slambench::values::VT_COLLECTION); if (!pm_) return desc; return pm_->GetType(); } const std::string& PowerMetric::GetDescription() const { static std::string with = "PAPI Power consumption in Watts."; static std::string without = "Power Monitor not found."; return pm_ ? with : without; } void PowerMetric::MeasureStart(Phase* phase) { (void)phase; if (pm_) { pm_->startSample(); } } void PowerMetric::MeasureEnd(Phase* phase) { (void)phase; if (pm_) { last_res_ = pm_->endSample(); } } slambench::values::Value * PowerMetric::GetValue(Phase* phase) { (void)phase; if (pm_ != nullptr) { return last_res_; } else { return new slambench::values::TypeForVT::type({}); } } } } ================================================ FILE: framework/shared/src/metrics/RPEMetric.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/RPEMetric.h" #include "outputs/TrajectoryAlignmentMethod.h" #include using namespace slambench::metrics; RPEMetric::RPEMetric(const slambench::outputs::TrajectoryInterface* tested_trajectory, const slambench::outputs::TrajectoryInterface * ground_truth) : Metric("RPE"), trajectory_(tested_trajectory), ground_truth_(ground_truth) { next_gt_ts_ = {0,0}; } const slambench::values::ValueDescription &RPEMetric::GetValueDescription() const { static const slambench::values::ValueDescription desc = slambench::values::ValueDescription({ {"RPE_RMSE", slambench::values::VT_DOUBLE}}); return desc; } const std::string& RPEMetric::GetDescription() const { static std::string desc = "Average Trajectory Error"; return desc; } void RPEMetric::MeasureStart(Phase* phase) { (void)phase; } void RPEMetric::MeasureEnd(Phase* phase) { (void)phase; latest_trajectory_ = trajectory_->GetAll(); } Value *RPEMetric::GetValue(Phase* phase) { (void)phase; auto gt_traj = ground_truth_->GetAll(); auto es_traj = latest_trajectory_; if(gt_traj.size() == 0) { std::cerr << "**** Error: Empty GT." << std::endl; return new values::TypedValue((double(std::nan("")))); } double norms = 0.0; int count = 0; // TODO TODO TODO TODO TODO TODO TODO TODO TODO TODO TODO TODO // Previously there was i_delta in original implementation // I drop the feature for now, will put it back later // TODO: The solution here is to have ParameterComponent for Metrics, so this parameter is visible externally // in RPE we compare shift from previous point, we need to store them auto gt_previous_iterator = gt_traj.end(); auto es_previous_iterator = es_traj.end(); auto gt_iterator = gt_traj.begin(); auto es_iterator = es_traj.begin(); bool first_point = true; for (es_iterator = es_traj.begin(); es_iterator != es_traj.end(); es_iterator++) { // Find closest gt point //**************************************************************************************** // Step 1 : ensure GT in the future exists //*************************************** while(gt_iterator->first < es_iterator->first ) { gt_iterator++; } if(gt_iterator == gt_traj.end()) { std::cerr << "**** RPE Error: No more groundtruth to compare with." << std::endl; break; } // Step 2 : Closest Future //************************ auto closest = gt_iterator; for (; gt_iterator != gt_traj.end(); ++gt_iterator) { auto GT_TS = gt_iterator; if ( GT_TS->first > es_iterator->first ) { break; } auto CL_TS = gt_iterator; if (es_iterator->first - CL_TS->first > es_iterator->first - GT_TS->first) { closest = GT_TS; } } gt_iterator = closest; // If at least two points are processed, we can compute Relative Pose Error //**************************************************************************************** if (!first_point) { auto pose_gt_i = gt_previous_iterator->second.GetValue(); auto pose_gt_j = gt_iterator->second.GetValue(); auto pose_gt_diff = pose_gt_i * pose_gt_j.inverse(); auto pose_es_i = es_previous_iterator->second.GetValue(); auto pose_es_j = es_iterator->second.GetValue(); auto pose_es_diff = pose_es_i * pose_es_j.inverse(); Eigen::Matrix4f E = pose_es_diff * pose_gt_diff.inverse(); Eigen::Vector3f v = E.block<3,1>(0,3); double length = v.norm(); norms = norms + length*length; count++; } // store previous values //**************************************************************************************** gt_previous_iterator = gt_iterator ; es_previous_iterator = es_iterator ; first_point = false; } double RPE = (count == 0) ? 0 : std::sqrt(norms/ (double)count); auto rpe_rmse = new slambench::values::TypeForVT::type(RPE); return new slambench::values::TypeForVT::type({ {"RPE_RMSE",rpe_rmse}, }); } ================================================ FILE: framework/shared/src/metrics/memory_utils/CUDAMonitor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "metrics/memory_utils/CUDAMonitor.h" #include #include bool CUDAMonitor::IsActive() { return libcuda_cudaMemGetInfo != nullptr; } bool CUDAMonitor::Init() { libcuda_cudaMemGetInfo = (cudaMemGetInfo_t)dlsym(RTLD_NEXT, "cudaMemGetInfo"); if (libcuda_cudaMemGetInfo == nullptr) { std::cerr << "*** CUDA Monitor: cudaMemGetInfo is not available" << std::endl; } libcuda_cudaGetDeviceProperties = (cudaGetDeviceProperties_t)dlsym(RTLD_NEXT, "cudaGetDeviceProperties"); if (libcuda_cudaGetDeviceProperties == nullptr) { std::cerr << "*** CUDA Monitor: cudaGetDeviceProperties is not available" << std::endl; } else { cudaDeviceProp prop; libcuda_cudaGetDeviceProperties(&prop, 0); device_name = prop.name; } return libcuda_cudaMemGetInfo != nullptr; } size_t CUDAMonitor::getUsedBytes() { if (libcuda_cudaMemGetInfo == nullptr) { return 0; } // show memory usage of GPU size_t free_byte ; size_t total_byte ; cudaError_t error = libcuda_cudaMemGetInfo(&free_byte, &total_byte); if (error != 0) { return 0.0; } double free_db = (double)free_byte ; double total_db = (double)total_byte ; double used_db = total_db - free_db ; return used_db ; } ================================================ FILE: framework/shared/src/metrics/power_utils/PAPIMonitor.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include "metrics/power_utils/PAPIMonitor.h" #include #define DEBUG_INFO(msg) std::cerr << msg << std::endl; #undef DEBUG_INFO #define DEBUG_INFO(msg) ; bool PAPIMonitor::papi_init () { int cid,rapl_cid=-1,numcmp; int code; int r = 0; const PAPI_component_info_t *cmpinfo = nullptr; PAPI_event_info_t evinfo; int retval = PAPI_library_init( PAPI_VER_CURRENT ); if ( retval != PAPI_VER_CURRENT ) { std::cerr << "*** PAPI_library_init failed " << retval << std::endl; return false; } numcmp = PAPI_num_components(); DEBUG_INFO("Found " << numcmp<< "components"); for(cid=0; cidname,"rapl")) { rapl_cid=cid; DEBUG_INFO(" - RAPL FOUND !"); if (cmpinfo->disabled) { std::cerr <<"*** RAPL component disabled: " << cmpinfo->disabled_reason << std::endl; return false; } break; } } /* Component not found */ if (cid==numcmp) { std::cerr << "*** PAPI Rapl components not found\n"; return false; } ; /* Create EventSet */ EventSet = PAPI_NULL; retval = PAPI_create_eventset( &EventSet ); if (retval != PAPI_OK) { std::cerr << "*** PAPI_create_eventset FAIL "<< std::endl; return false; } /* Add all events */ code = PAPI_NATIVE_MASK; r = PAPI_enum_cmp_event( &code, PAPI_ENUM_FIRST, rapl_cid ); while ( r == PAPI_OK ) { DEBUG_INFO(" - Read event !"); retval = PAPI_event_code_to_name( code, event_names[num_events] ); DEBUG_INFO(" - Name = " << event_names[num_events] ); if ( retval != PAPI_OK ) { std::cerr << "Error translating " << code << " PAPI_event_code_to_name" << std::endl << retval; return false; } retval = PAPI_get_event_info(code,&evinfo); if (retval != PAPI_OK) { std::cerr << "Error getting event info " << std::endl << retval; return false; } strncpy(units[num_events],evinfo.units,sizeof(units[0])); // buffer must be null terminated to safely use strstr operation on it below units[num_events][sizeof(units[0])-1] = '\0'; retval = PAPI_add_event( EventSet, code ); if (retval != PAPI_OK) { break; /* We've hit an event limit */ } num_events++; r = PAPI_enum_cmp_event( &code, PAPI_ENUM_EVENTS, rapl_cid ); } values= (long long int *) calloc(num_events,sizeof(long long)); if (values==NULL) { std::cerr << "Failed to allocate memory in PAPI initialisation"<< std::endl; return false; } return true; // That means OK } bool PAPIMonitor::papi_start() { /* Start Counting */ before_time=PAPI_get_real_nsec(); int retval = PAPI_start( EventSet); if (retval != PAPI_OK) { std::cerr << "ERROR: PAPI_start() " << std::endl<< retval; } return retval == PAPI_OK; } bool PAPIMonitor::papi_read() { /* Stop Counting */ after_time=PAPI_get_real_nsec(); int retval = PAPI_stop( EventSet, values); if (retval != PAPI_OK) { std:: cerr << "ERROR: PAPI_stop() "<< std::endl<< retval; return false; } DEBUG_INFO("before_time = " << before_time); DEBUG_INFO("after_time = " << after_time); double elapsed_time=(double)(((double)(after_time-before_time)) / (double)1.0e9); DEBUG_INFO("elapsed_time = " << elapsed_time); for(int i=0;i bool XU3Monitor::odroid_init () { powerA7 = NULL; powerA15 = NULL; powerGPU = NULL; powerDRAM = NULL; if (enableSensor(SENSOR_A7)) { enableSensor(SENSOR_A15); enableSensor(SENSOR_GPU); enableSensor(SENSOR_DRAM); return true; } else { return false; } } bool XU3Monitor::odroid_start () { return true; } bool XU3Monitor::odroid_sample () { if (powerA7) this->vpowerA7 = getPower(SENSOR_A7); if (powerA15) this->vpowerA15 = getPower(SENSOR_A15); if (powerGPU) this->vpowerGPU = getPower(SENSOR_GPU); if (powerDRAM) this->vpowerDRAM = getPower(SENSOR_DRAM); return true; } bool XU3Monitor::odroid_finish() { if (powerA7) fclose(powerA7); if (powerA15) fclose(powerA15); if (powerGPU) fclose(powerGPU); if (powerDRAM) fclose(powerDRAM); return true; } float XU3Monitor::getPower(XU3Sensor sensor) { FILE *tmp = NULL; float power; switch (sensor) { case SENSOR_A7: tmp = powerA7; break; case SENSOR_A15: tmp = powerA15; break; case SENSOR_GPU: tmp = powerGPU; break; case SENSOR_DRAM: tmp = powerDRAM; break; } if (tmp) { rewind(tmp); fscanf(tmp, "%f\n", &power); return (power); } return 0; } bool XU3Monitor::enableSensor(XU3Sensor sensor) { char enableFile[256]; FILE *tmp; for (int dn = 0; dn < 5; dn++) { sprintf(enableFile, "/sys/bus/i2c/drivers/INA231/%d-00%d/enable", dn, sensor); if ((tmp = fopen(enableFile, "a"))!= 0) { fprintf(tmp, "1\n"); fclose(tmp); sprintf(enableFile, "/sys/bus/i2c/drivers/INA231/%d-00%d/sensor_W", dn, sensor); if ((tmp = fopen(enableFile, "r")) != 0) { switch (sensor) { case SENSOR_A7: powerA7 = tmp; break; case SENSOR_A15: powerA15 = tmp; break; case SENSOR_GPU: powerGPU = tmp; break; case SENSOR_DRAM: powerDRAM = tmp; break; } return true; } } } return false; } ================================================ FILE: framework/shared/src/outputs/Output.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "outputs/Output.h" #include "values/Value.h" #include "outputs/TrajectoryAlignmentMethod.h" #include "outputs/TrajectoryInterface.h" #include #include #include using namespace slambench::outputs; using slambench::values::PointCloudValue; typedef pcl::PointXYZ point_t; BaseOutput::BaseOutput(const std::string& name, const values::ValueDescription &type, bool main_output) : name_(name), type_(type), only_keep_most_recent_(false), active_(false), main_(main_output) { } const BaseOutput::value_map_t::value_type& BaseOutput::GetMostRecentValue() const { if(GetValues().empty()) { throw std::logic_error("No values in output"); } return *GetValues().rbegin(); } bool BaseOutput::Empty() const { return GetValues().empty(); } Output::Output(const std::string& name, values::ValueType type, bool main_output) : BaseOutput(name, type, main_output) { } void Output::AddPoint(timestamp_t time, const values::Value *value) { assert(value->GetType() == GetType()); assert(IsActive()); if(GetKeepOnlyMostRecent()) { for(auto i : values_) { delete i.second; } values_.clear(); } values_[time] = value; Updated(); } const Output::value_map_t& Output::GetValues() const { assert(IsActive()); return values_; } const BaseOutput::value_map_t::value_type& Output::GetMostRecentValue() const { if(values_.empty()) { throw std::logic_error("No values available in output"); } return *values_.rbegin(); } void BaseOutput::Updated() const { for(auto i : update_callbacks_) { i(this); } } DerivedOutput::DerivedOutput(const std::string &name, values::ValueType type, const std::initializer_list &derived_from, bool main) : BaseOutput(name, type, main), derived_from_(derived_from), up_to_date_(false) { for(BaseOutput *i : derived_from_) { i->AddUpdateCallback([this](const BaseOutput*){this->Invalidate();}); } } bool DerivedOutput::Empty() const { if(!up_to_date_) { recalculate(); } return cached_values_.empty(); } void DerivedOutput::recalculate() const { const_cast(this)->Recalculate(); const_cast(this)->up_to_date_ = true; Updated(); } const BaseOutput::value_map_t::value_type& DerivedOutput::GetMostRecentValue() const { if(!up_to_date_) { recalculate(); } return *cached_values_.rbegin(); } const BaseOutput::value_map_t& DerivedOutput::GetValues() const { if(!up_to_date_) { recalculate(); } return cached_values_; } void DerivedOutput::Invalidate() { up_to_date_ = false; } BaseOutput::value_map_t& DerivedOutput::GetCachedValueMap() { return cached_values_; } AlignmentOutput::AlignmentOutput(const std::string& name, TrajectoryInterface* gt_trajectory, BaseOutput* trajectory, TrajectoryAlignmentMethod *method) : DerivedOutput(name, values::VT_MATRIX, {trajectory}), freeze_(false), gt_trajectory_(gt_trajectory), trajectory_(trajectory), method_(method) { } void AlignmentOutput::Recalculate() { if (freeze_) return; assert(GetKeepOnlyMostRecent()); auto &target = GetCachedValueMap(); for(auto i : target) { delete i.second; } target.clear(); if(trajectory_->Empty()) { return; } slambench::outputs::PoseOutputTrajectoryInterface traj_int(trajectory_); //transformation_ = (*method_)(gt_trajectory_->GetAll(), traj_int.GetAll()); auto transformation = (*method_)(gt_trajectory_->GetAll(), traj_int.GetAll()); auto &last_point = trajectory_->GetMostRecentValue(); target.insert({last_point.first, new values::TypedValue(transformation)}); } AlignedPoseOutput::AlignedPoseOutput(const std::string& name, AlignmentOutput* alignment, BaseOutput* pose_output) : DerivedOutput(name, values::VT_POSE, {alignment, pose_output}), alignment_(alignment), pose_output_(pose_output) { } void AlignedPoseOutput::Recalculate() { auto &target = GetCachedValueMap(); for(auto i : target) { delete i.second; } target.clear(); if(!alignment_->IsActive()) return; if(alignment_->Empty()) return; if(!pose_output_->IsActive()) return; if(pose_output_->Empty()) return; auto newest_alignment = alignment_->GetMostRecentValue().second; values::TypedValue *mv = (values::TypedValue*)newest_alignment; for(auto traj_point : pose_output_->GetValues()) { auto pose = (values::PoseValue*)traj_point.second; Eigen::Matrix4f tmp = mv->GetValue() * pose->GetValue(); target.insert({traj_point.first, const_cast(new values::PoseValue(tmp))}); } } AlignedPointCloudOutput::AlignedPointCloudOutput(const std::string& name, AlignmentOutput* alignment, BaseOutput* pc_output) : DerivedOutput(name, values::VT_POINTCLOUD, {alignment, pc_output}), alignment_(alignment), pointcloud_(pc_output) { SetKeepOnlyMostRecent(true); } void AlignedPointCloudOutput::Recalculate() { assert(GetKeepOnlyMostRecent()); auto &target = GetCachedValueMap(); for(auto i : target) { delete i.second; } target.clear(); if(!pointcloud_->IsActive() || pointcloud_->GetValues().empty() || !alignment_->IsActive() || alignment_->GetValues().empty()) { return; } auto latest_point = pointcloud_->GetMostRecentValue(); auto latest_pc = (values::PointCloudValue*)latest_point.second; auto latest_ts = latest_point.first; auto latest_alignment = ((values::TypedValue*)alignment_->GetMostRecentValue().second)->GetValue(); auto new_pc = new values::PointCloudValue(*latest_pc); new_pc->SetTransform(latest_alignment); target.insert({latest_ts, new_pc}); } AlignedTrajectoryOutput::AlignedTrajectoryOutput(const std::string &name, AlignmentOutput *alignment, BaseOutput *trajectory_output) : DerivedOutput(name, values::VT_TRAJECTORY, {alignment, trajectory_output}), alignment_(alignment), trajectory_(trajectory_output) { SetKeepOnlyMostRecent(true); } AlignedTrajectoryOutput::~AlignedTrajectoryOutput() { SetKeepOnlyMostRecent(true); } void AlignedTrajectoryOutput::Recalculate() { assert(GetKeepOnlyMostRecent()); auto &target = GetCachedValueMap(); for(auto i : target) { delete i.second; } target.clear(); if(!trajectory_->IsActive() || trajectory_->GetValues().empty() || !alignment_->IsActive() || alignment_->GetValues().empty()) { return; } auto latest_data_point = trajectory_->GetMostRecentValue(); auto latest_trajectory = (values::TrajectoryValue*)latest_data_point.second; auto latest_ts = latest_data_point.first; auto latest_alignment = ((values::TypedValue*)alignment_->GetMostRecentValue().second)->GetValue(); values::Trajectory *t = new values::Trajectory(); for (auto &point : latest_trajectory->GetPoints()) { auto &pose = point.second.GetValue(); if ((pose.array().abs() == std::numeric_limits::infinity()).any()) continue; Eigen::Matrix4f transformed_pose = latest_alignment * pose; t->push_back(point.first, values::PoseValue(transformed_pose)); } auto new_trajectory = new values::TrajectoryValue(*t); target.insert({latest_ts, new_trajectory}); } PointCloudHeatMap::PointCloudHeatMap(const std::string &name, BaseOutput *gt_pointcloud, BaseOutput *pointcloud, const std::function &convert) : DerivedOutput(name, values::VT_HEATMAPPOINTCLOUD, {gt_pointcloud, pointcloud}, false), gt_pointcloud_(gt_pointcloud), pointcloud_(pointcloud), convert(convert) { } slambench::values::HeatMapPointCloudValue *getValue(const pcl::PointCloud::Ptr >, const pcl::PointCloud::Ptr &test) { auto value = new slambench::values::HeatMapPointCloudValue(); pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); tree->setInputCloud(gt); std::vector pointIdxNKNSearch(1); std::vector pointNKNSquaredDistance(1); for(size_t i = 0; i < test->size(); i++) { const auto &point = test->at(i); tree->nearestKSearch(point, 1, pointIdxNKNSearch, pointNKNSquaredDistance); const double distance = sqrt(pointNKNSquaredDistance.at(0)); value->AddPoint(slambench::values::HeatMapPoint3DF(point.x, point.y, point.z, distance)); } return value; } void PointCloudHeatMap::Recalculate() { assert(GetKeepOnlyMostRecent()); BaseOutput::value_map_t &target = GetCachedValueMap(); for(auto i : target) { delete i.second; } target.clear(); if (pointcloud_->Empty()) { return; } const BaseOutput::value_map_t::value_type &tested_frame = pointcloud_->GetMostRecentValue(); const BaseOutput::value_map_t::value_type >_frame = gt_pointcloud_->GetMostRecentValue(); const PointCloudValue *tested_pointcloud = reinterpret_cast(tested_frame.second); const PointCloudValue *gt_pointcloud = reinterpret_cast(gt_frame.second); pcl::PointCloud::Ptr tested_cloud = pcl::PointCloud::Ptr(new pcl::PointCloud); for (const auto &point : tested_pointcloud->GetPoints()) { const Eigen::Matrix4f &transform = tested_pointcloud->GetTransform(); const Eigen::Vector4f eigenPoint(point.X, point.Y, point.Z, 1); const Eigen::Vector4f transformedPoint = transform * eigenPoint; tested_cloud->push_back({transformedPoint(0), transformedPoint(1), transformedPoint(2)}); } pcl::PointCloud::Ptr gt_cloud = pcl::PointCloud::Ptr(new pcl::PointCloud); for (const auto &point : gt_pointcloud->GetPoints()) { gt_cloud->push_back({point.X, point.Y, point.Z}); } target.insert({tested_frame.first, getValue(gt_cloud, tested_cloud)}); } PoseToXYZOutput::PoseToXYZOutput(BaseOutput* pose_output) : BaseOutput(pose_output->GetName() + " (XYZ)", values::ValueDescription({{"X", values::VT_DOUBLE}, {"Y", values::VT_DOUBLE}, {"Z", values::VT_DOUBLE}})), pose_output_(pose_output) { } const BaseOutput::value_map_t& PoseToXYZOutput::GetValues() const { GetMostRecentValue(); return cached_values_; } const BaseOutput::value_map_t::value_type& PoseToXYZOutput::GetMostRecentValue() const { cached_values_.clear(); auto pose_value = pose_output_->GetMostRecentValue(); auto val = (values::TypeForVT::type*)pose_value.second; float x = val->GetValue()(0, 3); float y = val->GetValue()(1, 3); float z = val->GetValue()(2, 3); auto xv = new values::TypeForVT::type(x); auto yv = new values::TypeForVT::type(y); auto zv = new values::TypeForVT::type(z); cached_values_.insert({pose_value.first, new values::TypeForVT::type({{"X", xv}, {"Y", yv}, {"Z", zv}})}); return *cached_values_.begin(); } ================================================ FILE: framework/shared/src/outputs/OutputManager.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "outputs/OutputManager.h" #include "outputs/OutputManagerWriter.h" #include "io/sensor/Sensor.h" #include "io/sensor/GroundTruthSensor.h" #include "io/sensor/PointCloudSensor.h" #include "io/format/PointCloud.h" #include using namespace slambench::outputs; OutputManager::~OutputManager() { for(auto &i : output_map_) { delete i.second; } } BaseOutput* OutputManager::GetOutput(const std::string& outputname) { return output_map_.at(outputname); } BaseOutput* OutputManager::GetMainOutput(slambench::values::ValueType type) { for(auto &i : output_map_) { if(i.second->IsMainOutput() && i.second->GetType() == type) { return i.second; } } return nullptr; } void OutputManager::RegisterOutput(BaseOutput* output) { assert(output != nullptr); if(output->IsMainOutput() && GetMainOutput(output->GetType())) { delete output_map_[output->GetName()]; output_map_.erase(output->GetName()); // throw std::logic_error("A main output for this type is already registered"); } output_map_[output->GetName()] = output; } bool OutputManager::WriteFile(const std::string& filename) { OutputManagerWriter writer; return writer.Write(*this, filename); } void OutputManager::LoadGTOutputsFromSLAMFile(io::SLAMFile* file) { LoadGTOutputsFromSLAMFile(file->Sensors, file, true); } slambench::outputs::Output *createGTOutput(const slambench::io::Sensor* sensor) { assert(sensor->IsGroundTruth()); if(sensor->GetType() == slambench::io::GroundTruthSensor::kGroundTruthTrajectoryType) { return new slambench::outputs::Output("Trajectory", slambench::values::VT_POSE, true); } else if(sensor->GetType() == slambench::io::PointCloudSensor::kPointCloudType) { return new slambench::outputs::Output("PointCloud", slambench::values::VT_POINTCLOUD, true); } else { // unknown GT type assert(false); } throw std::logic_error("Unrecognised ground truth sensor type"); } void OutputManager::LoadGTOutputsFromSLAMFile(io::SensorCollection& sensors, io::FrameCollection* gt_frames, bool with_point_cloud) { std::map gt_outputs; // Initialise ground truth outputs for(slambench::io::Sensor *sensor : sensors) { if(sensor->IsGroundTruth()) { // we've found a GT sensor so try and create a GT output to represent it auto output = createGTOutput(sensor); output->SetActive(true); gt_outputs[sensor] = output; RegisterOutput(output); } } for(unsigned frame_idx = 0; frame_idx < gt_frames->GetFrameCount(); ++frame_idx) { auto i = gt_frames->GetFrame(frame_idx); if(!i->FrameSensor->IsGroundTruth()) { continue; } auto output = gt_outputs.at(i->FrameSensor); if(i->FrameSensor->GetType() == slambench::io::GroundTruthSensor::kGroundTruthTrajectoryType) { Eigen::Matrix4f K; memcpy(K.data(), i->GetData(), i->GetSize()); i->FreeData(); output->AddPoint(i->Timestamp, new slambench::values::PoseValue(K)); } if(with_point_cloud and i->FrameSensor->GetType() == slambench::io::PointCloudSensor::kPointCloudType) { slambench::io::PointCloud *pc = slambench::io::PointCloud::FromRaw((char*)i->GetData()); i->FreeData(); auto pcv = new slambench::values::PointCloudValue(); for(auto p : pc->Get()) { pcv->AddPoint({p.x,p.y,p.z}); } delete pc; output->AddPoint(i->Timestamp, pcv); } } } ================================================ FILE: framework/shared/src/outputs/OutputManagerWriter.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/sensor/Sensor.h" #include "io/sensor/GroundTruthSensor.h" #include "io/sensor/PointCloudSensor.h" #include "io/SLAMFrame.h" #include "io/format/PointCloud.h" #include "outputs/OutputManagerWriter.h" #include "outputs/OutputManager.h" using namespace slambench::outputs; slambench::io::SLAMFile* OutputManagerWriter::GetFile(OutputManager& outman) { auto file = new slambench::io::SLAMFile(); std::lock_guard lock (outman.GetLock()); (void)lock; // I hate this werror if(!CreateSensors(outman, *file)) { delete file; return nullptr; } if(!CreateFrames(outman, *file)) { delete file; return nullptr; } return file; } bool OutputManagerWriter::Write(OutputManager& outman, const std::string& filename) { auto file = GetFile(outman); if(!SerialiseFile(*file, filename)) { return false; } delete file; return true; } bool OutputManagerWriter::CreateSensors(OutputManager& outman, slambench::io::SLAMFile& file) { for(auto output : outman) { if(output.second->IsActive()) { auto sensor = CreateSensor(output.second); if(sensor == nullptr) { continue; } output_map_.insert({output.second, sensor}); file.Sensors.AddSensor(sensor); } } return true; } slambench::io::Sensor* OutputManagerWriter::CreateSensor(const BaseOutput* output) { switch(output->GetType()) { case slambench::values::VT_POSE: return CreatePoseSensor(output); case slambench::values::VT_POINTCLOUD: return CreatePointCloudSensor(output); default: return nullptr; } __builtin_unreachable(); } slambench::io::Sensor* OutputManagerWriter::CreatePoseSensor(const BaseOutput* output) { // This is not really a ground truth. We need a 'trajectory' sensor auto sensor = new slambench::io::GroundTruthSensor("Output Trajectory"); sensor->Description = output->GetName(); return sensor; } slambench::io::Sensor* OutputManagerWriter::CreatePointCloudSensor(const BaseOutput* output) { auto sensor = new slambench::io::PointCloudSensor("Output Point Cloud"); sensor->Description = output->GetName(); return sensor; } bool OutputManagerWriter::CreateFrames(OutputManager& outman, slambench::io::SLAMFile& file) { for(auto output : outman) { slambench::outputs::BaseOutput *op = output.second; if(op->IsActive()) { for(auto frame : op->GetValues()) { auto output_frame = CreateFrame(op, frame.first, frame.second); if(output_frame != nullptr) { file.AddFrame(output_frame); } } } } return true; } slambench::io::SLAMFrame* OutputManagerWriter::CreateFrame(BaseOutput *output, TimeStamp ts, const slambench::values::Value* value) { switch(value->GetType()) { case slambench::values::VT_POSE: return CreatePoseFrame(output, ts, (const slambench::values::PoseValue*)value); case slambench::values::VT_POINTCLOUD: return CreatePointCloudFrame(output, ts, (const slambench::values::PointCloudValue*)value); default: return nullptr; } __builtin_unreachable(); } slambench::io::SLAMFrame* OutputManagerWriter::CreatePointCloudFrame(BaseOutput *output, TimeStamp ts, const slambench::values::PointCloudValue* value) { auto pointcloud = new slambench::io::PointCloud(); for(auto i : value->GetPoints()) { pointcloud->Get().push_back(slambench::io::Point(i.X, i.Y, i.Z)); } auto frame = new slambench::io::SLAMInMemoryFrame(); auto pointclouddata = pointcloud->ToRaw(); frame->FrameSensor = output_map_.at(output); frame->Timestamp = ts; frame->SetData(pointclouddata.data(), pointclouddata.size()); frame->SetVariableSize(pointclouddata.size()); return frame; } slambench::io::SLAMFrame* OutputManagerWriter::CreatePoseFrame(BaseOutput *output, TimeStamp ts, const slambench::values::PoseValue* value) { auto frame = new slambench::io::SLAMInMemoryFrame(); frame->FrameSensor = output_map_.at(output); frame->Timestamp = ts; frame->SetData((void*)&value->GetValue()); return frame; } bool OutputManagerWriter::SerialiseFile(slambench::io::SLAMFile& file, const std::string& filename) { FILE *f = fopen(filename.c_str(), "w"); slambench::io::SLAMFileSerialiser sfs(f); sfs.Serialise(file); fclose(f); return true; } ================================================ FILE: framework/shared/src/outputs/TrajectoryAlignmentMethod.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "outputs/TrajectoryAlignmentMethod.h" #include "outputs/Output.h" #include #include #include using namespace slambench::outputs; // TODO: this is duplicated in ATEMetric.cpp static boost::optional select_closest_before(const TrajectoryAlignmentMethod::trajectory_t & GT , slambench::TimeStamp start_from , const slambench::TimeStamp& LO_TS) { if(GT.size() == 0) { std::cerr << "**** Error: Empty GT." << std::endl; return boost::none; } auto gt_iterator = GT.begin(); while(gt_iterator->first < start_from) { gt_iterator++; } if(gt_iterator == GT.end()) { std::cerr << "**** Error: No more GT to compare with." << std::endl; return boost::none; } /* * We iterate over GT. * If GT_TS happens after LO_TS we stop the loop. * It can be that the first GT_TS we found happens after, this means we should not compare with this one (skip long gap of empty GT). * Then closest is the first found, or the closest. * */ slambench::TimeStamp closest = gt_iterator->first; for (; gt_iterator != GT.end(); ++gt_iterator) { const slambench::TimeStamp & GT_TS = gt_iterator->first; if ( GT_TS > LO_TS ) { break; } slambench::TimeStamp CL_TS = gt_iterator->first; if (LO_TS - CL_TS > LO_TS - GT_TS) { closest = GT_TS; } } return closest; } Eigen::Matrix4f align_trajectories_original (const TrajectoryAlignmentMethod::trajectory_t & gt , const TrajectoryAlignmentMethod::trajectory_t & t) { Eigen::Matrix4f res = Eigen::Matrix4f::Identity(); if (gt.size() != 0 and t.size() != 0){ for (auto past_point : t) { auto closest = select_closest_before(gt,{0,0},past_point.first); if (closest) { res = ((gt.at(closest.get()))).GetValue() * past_point.second.GetValue().inverse(); //std::cout << res << std::endl; return res ; } } } return res ; } bool associate(const TrajectoryAlignmentMethod::trajectory_t & gt, const TrajectoryAlignmentMethod::trajectory_t & t, std::vector& vGroundTruth, std::vector& vEstimate) { uint gid = 0; auto gt_time = [gt](uint id) { return gt.at(id).first.ToS(); }; for (uint tid = 0; tid < t.size(); tid++) { vEstimate.push_back(t.at(tid).second.GetValue()); double time = t.at(tid).first.ToS(); // assume that gt is sorted wrt time while (gid < gt.size() && gt_time(gid) < time) gid++; // find the two closest points' indices in gt uint gid_a, gid_b; if (gid == 0) { gid_a = gid_b = 0; } else if (gid == gt.size()) { gid_a = gid_b = gid - 1; } else { gid_a = gt_time(gid) == time ? gid : gid - 1; gid_b = gid; } Eigen::Matrix4f gt_pose; if (gid_a == gid_b) { gt_pose = gt.at(gid_a).second.GetValue(); } else { // interpolate between two gt poses double t = (time - gt_time(gid_a)) / (gt_time(gid_b) - gt_time(gid_a)); Eigen::Matrix4f pose_a = gt.at(gid_a).second.GetValue(); Eigen::Matrix4f pose_b = gt.at(gid_b).second.GetValue(); Eigen::Quaternion q_a(pose_a.block<3, 3>(0, 0)); Eigen::Quaternion q_b(pose_b.block<3, 3>(0, 0)); auto q = q_a.slerp(t, q_b); gt_pose = pose_a * (1 - t) + pose_b * t; gt_pose.block<3, 3>(0, 0) = q.toRotationMatrix(); } vGroundTruth.push_back(gt_pose); } return (bool)(vGroundTruth.size() * vEstimate.size()); } Eigen::Matrix4f align_trajectories_umeyama_eigen(const TrajectoryAlignmentMethod::trajectory_t & gt, const TrajectoryAlignmentMethod::trajectory_t & est) { std::vector vGroundTruth; std::vector vEstimate; //if(associate(gt, t, vGroundTruth, vEstimate)) //{ associate(gt, est, vGroundTruth, vEstimate); // convert pose vectors to Eigen matrices int N = vEstimate.size(); Eigen::MatrixXf esMat(3,N); for (int i = 0; i < N; i++) { esMat(0,i) = vEstimate.at(i).block<3,1>(0,3)(0); esMat(1,i) = vEstimate.at(i).block<3,1>(0,3)(1); esMat(2,i) = vEstimate.at(i).block<3,1>(0,3)(2); } Eigen::MatrixXf gtMat(3,N); for (int i = 0; i < N; i++) { gtMat(0,i) = vGroundTruth.at(i).block<3,1>(0,3)(0); gtMat(1,i) = vGroundTruth.at(i).block<3,1>(0,3)(1); gtMat(2,i) = vGroundTruth.at(i).block<3,1>(0,3)(2); } return Eigen::umeyama(esMat, gtMat, true); } Eigen::MatrixXd ATERotation(Eigen::MatrixXd model, Eigen::MatrixXd data) { Eigen::MatrixXd w; w = Eigen::MatrixXd::Identity(3,3); int cols = model.cols(); //Model = [M0, M1, ...], Data = [D0, D1, ...] // W = M0*D0' + M1*D1' + ... = \sum{Mi*Di} for (int i = 0; i < cols; i++) w = w + model.col(i) * data.col(i).transpose(); Eigen::JacobiSVD svd(w.transpose(), Eigen::ComputeThinU | Eigen::ComputeThinV); Eigen::Matrix3d U = svd.matrixU(); Eigen::Matrix3d V = svd.matrixV(); float detV = V.determinant(); float detU = U.determinant(); Eigen::MatrixXd S; S = Eigen::MatrixXd::Identity(3,3); if(detU * detV < 0) S(2,2) = -1; Eigen::MatrixXd rot; rot = U * S * V.transpose(); return rot; } double ATEScale(Eigen::MatrixXd model, Eigen::MatrixXd data, Eigen::MatrixXd rotation) { int cols = model.cols(); Eigen::MatrixXd rotatedModel; rotatedModel = rotation * model; double dots = 0.0; double norms = 0.0; double normi = 0.0; //Model = [M0, M1, ...], Rotated Data = [R0, R1, ...] // W = M0.D0' + M1.D1' + ... = \sum{Mi.Di} for (int i = 0; i < cols; i++) { Eigen::Vector3d v1 = data.col(i); Eigen::Vector3d v2 = rotatedModel.col(i); Eigen::Vector3d v3 = model.col(i); dots = dots + v1.transpose()*v2; normi = v3.norm(); norms = norms + normi*normi; } // scale return (dots/norms); //return 1; } Eigen::Vector3d ATETranslation(Eigen::MatrixXd model, Eigen::MatrixXd data, double scale, Eigen::MatrixXd rotation, float& ate) { int N = model.cols(); Eigen::Vector3d translation = data.rowwise().mean() - (scale*rotation)*(model.rowwise().mean()); Eigen::MatrixXd rotatedModel(3,N); rotatedModel = (scale*rotation)*model; // error matrix E = [E1, E2, ...] Eigen::MatrixXd errorMat(3, N); errorMat = (rotatedModel.colwise() + translation) - data; // Absoute Trajectory Error (ATE) = |||E1|| + ||E2||+ ... = \sum(||Ei||) for (int i = 0; i < N; i++) ate = ate + errorMat.col(i).norm(); ate = ate/N; return translation; } Eigen::Matrix4d calculateATE(std::vector gt, std::vector es, float & ate) { // convert pose vectors to Eigen matrices int N = gt.size(); Eigen::MatrixXd gtMat(3,N); for (int i = 0; i < N; i++) { gtMat(0,i) = gt.at(i).block<3,1>(0,3)(0); gtMat(1,i) = gt.at(i).block<3,1>(0,3)(1); gtMat(2,i) = gt.at(i).block<3,1>(0,3)(2); } int M = gt.size(); Eigen::MatrixXd esMat(3,N); for (int i = 0; i < M; i++) { esMat(0,i) = es.at(i).block<3,1>(0,3)(0); esMat(1,i) = es.at(i).block<3,1>(0,3)(1); esMat(2,i) = es.at(i).block<3,1>(0,3)(2); } // calculate the mean pose to zero-shift the poses Eigen::Vector3d gtMean = gtMat.rowwise().mean(); Eigen::Vector3d esMean = esMat.rowwise().mean(); Eigen::MatrixXd gtZeroMat(3,N); Eigen::MatrixXd esZeroMat(3,N); gtZeroMat = gtMat.colwise() - gtMean; esZeroMat = esMat.colwise() - esMean; // absoulte trajector error (ate) float error = 0; //bool bOk = prepareData(gt, es, gtZeroMat, esZeroMat); Eigen::Matrix3d rotation = ATERotation(gtZeroMat, esZeroMat); double scale = ATEScale(gtZeroMat, esZeroMat, rotation); Eigen::Vector3d translation = ATETranslation(gtMat, esMat, scale, rotation, error); ate = error; Eigen::Matrix4d Mat; Mat = Eigen::Matrix4d::Identity(); Mat.block<3,3>(0,0) = scale*rotation; Mat.block<3,1>(0,3) = translation; Mat.block<1,4>(3,0) << 0,0,0,1; return Mat; } Eigen::Matrix4f align_trajectories_new (const TrajectoryAlignmentMethod::trajectory_t & gt , const TrajectoryAlignmentMethod::trajectory_t & t) { if (t.size() <= 100){ // do not align for the first 100 frames, because it will not be accurate return align_trajectories_original(gt , t) ; } if (t.size() > 100) // do not align for the first 100 frames, because it will not be accurate { std::vector vGroundTruth; std::vector vEstimate; //if(associate(gt, t, vGroundTruth, vEstimate)) //{ associate(gt, t, vGroundTruth, vEstimate); float error; Eigen::Matrix4d Mat = calculateATE(vGroundTruth, vEstimate, error); //std::cout << " ------ " << error << std::endl; //if (error < 0.1) //{ return Mat.cast().inverse(); //return Mat.cast(); //} } else { return align_trajectories_original(gt , t) ; } } Eigen::Matrix4f NewTrajectoryAlignmentMethod::operator()(const TrajectoryAlignmentMethod::trajectory_t & ground_truth, const TrajectoryAlignmentMethod::trajectory_t & trajectory) { return align_trajectories_new(ground_truth, trajectory); } Eigen::Matrix4f OriginalTrajectoryAlignmentMethod::operator()(const TrajectoryAlignmentMethod::trajectory_t & ground_truth, const TrajectoryAlignmentMethod::trajectory_t & trajectory) { return align_trajectories_original(ground_truth, trajectory); } Eigen::Matrix4f UmeyamaTrajectoryAlignmentMethod::operator()(const TrajectoryAlignmentMethod::trajectory_t & ground_truth, const TrajectoryAlignmentMethod::trajectory_t & trajectory) { return align_trajectories_umeyama_eigen(ground_truth, trajectory); } ================================================ FILE: framework/shared/src/outputs/TrajectoryInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "outputs/TrajectoryInterface.h" #include using namespace slambench; using namespace slambench::outputs; using namespace slambench::values; PoseOutputTrajectoryInterface::PoseOutputTrajectoryInterface(BaseOutput* pose_output) : pose_output_(pose_output), newest_point_(TimeStamp::get(0,0)) { assert(pose_output_->GetType() == VT_POSE); } PoseValue PoseOutputTrajectoryInterface::Get(const TimeStamp& when) const { return *dynamic_cast(pose_output_->GetValues().at(when)); } TrajectoryValue::pose_container_t PoseOutputTrajectoryInterface::GetAll() const { if(( ((!pose_output_->IsActive()) || !pose_output_->Empty()) && ((!pose_output_->IsActive()) || pose_output_->GetMostRecentValue().first > newest_point_)) || cached_traj_.empty()) { recalculate(); } return cached_traj_; } void PoseOutputTrajectoryInterface::recalculate() const { cached_traj_.clear(); for(auto i : pose_output_->GetValues()) { auto point = dynamic_cast(i.second); auto newval = new PoseValue(point->GetValue()); cached_traj_.insert({i.first, *newval}); } if(!cached_traj_.empty()) { newest_point_ = cached_traj_.rbegin()->first; } } TrajectoryValueWrapper::TrajectoryValueWrapper(const TrajectoryValue *t) : trajectoryValue_(t) { } values::PoseValue TrajectoryValueWrapper::Get(const TimeStamp &when) const { return trajectoryValue_->GetPoints().at(when); } values::TrajectoryValue::pose_container_t TrajectoryValueWrapper::GetAll() const { return trajectoryValue_->GetPoints(); } TrajectoryOutputInterface::TrajectoryOutputInterface(const BaseOutput *t): trajectory_output_(t) { } values::PoseValue TrajectoryOutputInterface::Get(const TimeStamp &when) const { const values::Value *raw_value = trajectory_output_->GetMostRecentValue().second; const auto tv = reinterpret_cast(raw_value); return tv->GetPoints().at(when); } values::TrajectoryValue::pose_container_t TrajectoryOutputInterface::GetAll() const { const values::Value *raw_value = trajectory_output_->GetMostRecentValue().second; const auto tv = reinterpret_cast(raw_value); return tv->GetPoints(); } ================================================ FILE: framework/shared/src/sb_malloc.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "sb_malloc.h" #include #include #include #include #include #include #include #ifdef ANDROID #define __throw() #else #define __throw() throw() #endif static bool track_allocs_frame = false; static bool track_allocs = false; namespace slambench { namespace memory { MemoryProfile MemoryProfile::singleton; void MemoryProfile::StartFrame(int i) { _frame = i; data_[_frame]; gpu_data_[_frame]; track_allocs_frame = true;} void MemoryProfile::EndFrame() { track_allocs_frame = false; } void MemoryProfile::StartAlgorithm() { std::cerr << "*** Start memory tracking" << std::endl; track_allocs = true; } void MemoryProfile::EndAlgorithm() { track_allocs = false; } class MemoryProfiler { public: static MemoryProfiler &GetSingleton() { return *singleton_ptr_; } static bool SingletonAvailable() { return singleton_ptr_ != nullptr && singleton_ptr_->IsEnabled(); } MemoryProfiler() : _enabled(true) {} ~MemoryProfiler() { singleton_ptr_ = nullptr; } MemoryData &GetData() { return MemoryProfile::singleton.DataForCurrentFrame(); } MemoryData &GetGPUData() { return MemoryProfile::singleton.GPUDataForCurrentFrame(); } MemoryData &GetOverallData() { return MemoryProfile::singleton.OverallData(); } MemoryData &GetOverallGPUData() { return MemoryProfile::singleton.OverallGPUData(); } bool IsEnabled() const { return _enabled; } void Enable() { _enabled = true; } void AddAllocation(void *ptr, size_t size) { if(!track_allocs) return; track_allocs = false; _allocation_sizes[ptr] = size; if(track_allocs_frame) { GetData().RecordAllocation(size); } GetOverallData().RecordAllocation(size); track_allocs = true; } void FreeAllocation(void *ptr) { if(!track_allocs) return; track_allocs = false; auto size = _allocation_sizes[ptr]; if(track_allocs_frame) { GetData().RecordFree(size); } GetOverallData().RecordFree(size); _allocation_sizes.erase(ptr); track_allocs = true; } void AddAllocationGPU(void *ptr, size_t size) { if(!track_allocs) return; track_allocs = false; _gpu_allocation_sizes[ptr] = size; if(track_allocs_frame) { GetGPUData().RecordAllocation(size); } GetOverallGPUData().RecordAllocation(size); track_allocs = true; } void FreeAllocationGPU(void *ptr) { if(!track_allocs) return; track_allocs = false; auto size = _gpu_allocation_sizes[ptr]; if(track_allocs_frame) { GetGPUData().RecordFree(size); } GetOverallGPUData().RecordFree(size); _gpu_allocation_sizes.erase(ptr); track_allocs = true; } private: std::map _allocation_sizes; std::map _gpu_allocation_sizes; static MemoryProfiler singleton_; static MemoryProfiler *singleton_ptr_; bool _enabled; }; MemoryProfiler MemoryProfiler::singleton_; MemoryProfiler *MemoryProfiler::singleton_ptr_ = &singleton_; } } #define ENABLE_MEM_PROFILING #ifdef ENABLE_MEM_PROFILING extern "C" { //################################################################################################################### //###################################### SYNC ############################################################ //################################################################################################################### static std::recursive_mutex gpu_alloc_lock; typedef std::lock_guard gpu_lock_guard_t; static std::recursive_mutex alloc_lock; typedef std::lock_guard lock_guard_t; static std::recursive_mutex opencl_alloc_lock; typedef std::lock_guard opencl_lock_guard_t; //################################################################################################################### //###################################### GPU SIDE : CUDA ############################################################ //################################################################################################################### typedef int cudaError_t ; typedef void * cudaArray_t ; #define ADD_CUDA_ALLOCATION2(FunName , Arg1 , Arg2 , ArgName1, ArgName2 , Ptr, Size ) \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 ) ; \ typedef cudaError_t (*FunName##_t)(Arg1 , Arg2); \ static FunName##_t libcuda_##FunName = load_and_call_libcuda_##FunName; \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2) { \ libcuda_##FunName = (FunName##_t)dlsym(RTLD_NEXT, #FunName); \ if (!libcuda_##FunName) { \ MEM_ERROR("Bad day for %s.\n", #FunName); \ exit(1); \ } \ return libcuda_##FunName(ArgName1,ArgName2); \ } \ cudaError_t FunName (Arg1 , Arg2) __throw() \ { \ gpu_lock_guard_t lock(gpu_alloc_lock); \ cudaError_t error = libcuda_##FunName(ArgName1,ArgName2); \ MEM_DEBUG("Call %s.\n", #FunName); \ if(slambench::memory::MemoryProfiler::SingletonAvailable()) { \ slambench::memory::MemoryProfiler::GetSingleton().AddAllocationGPU(Ptr, Size); \ } \ return error; \ }; \ \ #define ADD_CUDA_ALLOCATION4(FunName , Arg1 , Arg2 , Arg3 , Arg4 , ArgName1, ArgName2 , ArgName3, ArgName4 , Ptr, Size ) \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4 ) ; \ typedef cudaError_t (*FunName##_t)(Arg1 , Arg2 , Arg3 , Arg4); \ static FunName##_t libcuda_##FunName = load_and_call_libcuda_##FunName; \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4) { \ libcuda_##FunName = (FunName##_t)dlsym(RTLD_NEXT, #FunName); \ if (!libcuda_##FunName) { \ MEM_ERROR("Bad day for %s.\n", #FunName); \ exit(1); \ } \ return libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4); \ } \ cudaError_t FunName (Arg1 , Arg2 , Arg3 , Arg4) __throw() \ { \ gpu_lock_guard_t lock(gpu_alloc_lock); \ cudaError_t error = libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4); \ MEM_DEBUG("Call %s.\n", #FunName); \ if(slambench::memory::MemoryProfiler::SingletonAvailable()) { \ slambench::memory::MemoryProfiler::GetSingleton().AddAllocationGPU(Ptr, Size); \ } \ return error; \ }; #define CATCH_CUDA_FUNC4(FunName , Arg1 , Arg2 , Arg3 , Arg4 , ArgName1, ArgName2 , ArgName3, ArgName4 ) \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4 ) ; \ typedef cudaError_t (*FunName##_t)(Arg1 , Arg2 , Arg3 , Arg4); \ static FunName##_t libcuda_##FunName = load_and_call_libcuda_##FunName; \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4) { \ libcuda_##FunName = (FunName##_t)dlsym(RTLD_NEXT, #FunName); \ if (!libcuda_##FunName) { \ MEM_ERROR("Bad day for %s.\n", #FunName); \ exit(1); \ } \ return libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4); \ } \ cudaError_t FunName (Arg1 , Arg2 , Arg3 , Arg4) __throw() \ { \ gpu_lock_guard_t lock(gpu_alloc_lock); \ cudaError_t error = libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4); \ MEM_DEBUG("Call %s.\n", #FunName); \ return error; \ }; #define CATCH_CUDA_FUNC5(FunName , Arg1 , Arg2 , Arg3 , Arg4 , Arg5 , ArgName1, ArgName2 , ArgName3, ArgName4 , ArgName5 ) \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4 , Arg5) ; \ typedef cudaError_t (*FunName##_t)(Arg1 , Arg2 , Arg3 , Arg4, Arg5); \ static FunName##_t libcuda_##FunName = load_and_call_libcuda_##FunName; \ static cudaError_t load_and_call_libcuda_##FunName( Arg1 , Arg2 , Arg3 , Arg4, Arg5) { \ libcuda_##FunName = (FunName##_t)dlsym(RTLD_NEXT, #FunName); \ if (!libcuda_##FunName) { \ MEM_ERROR("Bad day for %s.\n", #FunName); \ exit(1); \ } \ return libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4 , ArgName5); \ } \ cudaError_t FunName (Arg1 , Arg2 , Arg3 , Arg4, Arg5) __throw() \ { \ gpu_lock_guard_t lock(gpu_alloc_lock); \ cudaError_t error = libcuda_##FunName(ArgName1,ArgName2 , ArgName3, ArgName4 , ArgName5); \ MEM_DEBUG("Call %s.\n", #FunName); \ return error; \ }; // cudaError_t cudaMalloc ( void** devPtr, size_t size ) //******************************************************** ADD_CUDA_ALLOCATION2(cudaMalloc , void** devPtr, size_t size, devPtr, size , (void*) *devPtr, size ); // cudaError_t cudaMallocHost ( void** ptr, size_t size ) //******************************************************** ADD_CUDA_ALLOCATION2(cudaMallocHost , void** devPtr, size_t size, devPtr, size , (void*) *devPtr, size ); // cudaError_t cudaMallocPitch ( void** devPtr, size_t* pitch, size_t width, size_t height ) //******************************************************** ADD_CUDA_ALLOCATION4(cudaMallocPitch , void** devPtr, size_t size, size_t width, size_t height , devPtr, size , width, height , (void*) *devPtr,width * height ); // __host__ ​cudaError_t cudaMallocArray ( cudaArray_t* array, const cudaChannelFormatDesc* desc_, size_t width, size_t height = 0, unsigned int flags = 0 ) // Allocate an array on the device. //******************************************************** /* CATCH_CUDA_FUNC5(cudaMallocArray , cudaArray_t* array, const void* desc_, size_t width, size_t height , unsigned int flags , array, desc_ , width, height , flags ) ; */ // cudaError_t cudaFree ( void* devPtr ) //******************************************************** static cudaError_t load_and_call_libcuda_cudaFree( void* devPtr) ; typedef cudaError_t (*cudaFree_t)( void* devPtr); static cudaFree_t libcuda_cudaFree = load_and_call_libcuda_cudaFree; static cudaError_t load_and_call_libcuda_cudaFree( void* devPtr) { libcuda_cudaFree = (cudaFree_t) dlsym(RTLD_NEXT, "cudaFree"); if (!libcuda_cudaFree) { MEM_ERROR("The memory profiler did not find cudaFree. You may need to recompile without memory profiling.\n"); exit(1); } cudaError_t res = libcuda_cudaFree(devPtr); return res; } cudaError_t cudaFree ( void* devPtr) __throw() { gpu_lock_guard_t lock(gpu_alloc_lock); if(slambench::memory::MemoryProfiler::SingletonAvailable()) { slambench::memory::MemoryProfiler::GetSingleton().FreeAllocationGPU(devPtr); return libcuda_cudaFree(devPtr); } else { return libcuda_cudaFree(devPtr); } } // cudaError_t cudaFreeHost ( void* devPtr) //******************************************************** static cudaError_t load_and_call_libcuda_cudaFreeHost( void* devPtr) ; typedef cudaError_t (*cudaFreeHost_t)( void* devPtr); static cudaFreeHost_t libcuda_cudaFreeHost = load_and_call_libcuda_cudaFreeHost; static cudaError_t load_and_call_libcuda_cudaFreeHost( void* devPtr) { libcuda_cudaFreeHost = (cudaFreeHost_t)dlsym(RTLD_NEXT, "cudaFreeHost"); if (!libcuda_cudaMalloc) { MEM_ERROR("Bad day for cudaFreeHost.\n"); exit(1); } return libcuda_cudaFreeHost(devPtr); } cudaError_t cudaFreeHost ( void* devPtr) __throw() { gpu_lock_guard_t lock(gpu_alloc_lock); if(slambench::memory::MemoryProfiler::SingletonAvailable()) { slambench::memory::MemoryProfiler::GetSingleton().FreeAllocationGPU(devPtr); return libcuda_cudaFreeHost(devPtr); } else { return libcuda_cudaFreeHost(devPtr); } } //################################################################################################################### //###################################### GPU SIDE : OPENCL ########################################################## //################################################################################################################### // We provide our own clCreateBuffer/clReleaseMemObject #include typedef int32_t cl_int __attribute__((aligned(4))); typedef uint64_t cl_ulong __attribute__((aligned(8))); typedef cl_ulong cl_bitfield; typedef struct _cl_context * cl_context; typedef cl_bitfield cl_mem_flags; typedef struct _cl_mem * cl_mem; static cl_mem load_and_call_libopencl_clCreateBuffer( cl_context a, cl_mem_flags b, size_t c, void *d, cl_int *e) ; static cl_int load_and_call_libopencl_clReleaseMemObject(cl_mem a) ; typedef cl_mem (*clCreateBuffer_t)( cl_context , cl_mem_flags , size_t , void *, cl_int *); typedef cl_int (*clReleaseMemObject_t)(cl_mem); static clCreateBuffer_t libopencl_clCreateBuffer = load_and_call_libopencl_clCreateBuffer; static clReleaseMemObject_t libopencl_clReleaseMemObject = load_and_call_libopencl_clReleaseMemObject; static cl_mem load_and_call_libopencl_clCreateBuffer( cl_context a, cl_mem_flags b, size_t c, void *d, cl_int *e) { libopencl_clCreateBuffer = (clCreateBuffer_t)dlsym(RTLD_NEXT, "clCreateBuffer"); return libopencl_clCreateBuffer(a,b,c,d,e); } static cl_int load_and_call_libopencl_clReleaseMemObject(cl_mem a) { libopencl_clReleaseMemObject = (clReleaseMemObject_t)dlsym(RTLD_NEXT, "clReleaseMemObject"); return libopencl_clReleaseMemObject(a); } cl_mem clCreateBuffer ( cl_context a , cl_mem_flags b , size_t c , void * d, cl_int * e) __throw() { if(slambench::memory::MemoryProfiler::SingletonAvailable()) { lock_guard_t lock(opencl_alloc_lock); cl_mem ptr = libopencl_clCreateBuffer(a,b,c,d,e); slambench::memory::MemoryProfiler::GetSingleton().AddAllocationGPU((void*) ptr, c); return ptr; } else { return libopencl_clCreateBuffer(a,b,c,d,e); } } cl_int clReleaseMemObject ( cl_mem ptr )__throw() { if(slambench::memory::MemoryProfiler::SingletonAvailable()) { lock_guard_t lock(opencl_alloc_lock); slambench::memory::MemoryProfiler::GetSingleton().FreeAllocationGPU((void*) ptr); return libopencl_clReleaseMemObject(ptr); } else { return libopencl_clReleaseMemObject(ptr); } } //################################################################################################################### //###################################### CPU SIDE ############################################################# //################################################################################################################### // We provide our own malloc/calloc/realloc/free, which are then used // by whatever we link against (i.e., SLAM implementations). static void *load_and_call_libc_malloc(size_t); static void load_and_call_libc_free(void*); static void *load_and_call_libc_calloc(size_t, size_t); static void *load_and_call_libc_realloc(void*, size_t); typedef void *(*malloc_t)(size_t); typedef void (*free_t)(void*); typedef void *(*realloc_t)(void*, size_t); typedef void *(*calloc_t)(size_t, size_t); // TODO: make this thread-safe static malloc_t libc_malloc = load_and_call_libc_malloc; static free_t libc_free = load_and_call_libc_free; static calloc_t libc_calloc = load_and_call_libc_calloc; static realloc_t libc_realloc = load_and_call_libc_realloc; static void* load_and_call_libc_malloc(size_t t) { libc_malloc = (malloc_t)dlsym(RTLD_NEXT, "malloc"); return libc_malloc(t); } static void load_and_call_libc_free(void *t) { libc_free = (free_t)dlsym(RTLD_NEXT, "free"); libc_free(t); } static void* load_and_call_libc_calloc(size_t nmemb, size_t size) { libc_calloc = (calloc_t)dlsym(RTLD_NEXT, "calloc"); return libc_calloc(nmemb, size); } static void *load_and_call_libc_realloc(void *t, size_t size) { libc_realloc = (realloc_t)dlsym(RTLD_NEXT, "realloc"); return libc_realloc(t, size); } //define a scratch space for calloc static char calloc_scratch[4096]; static char* calloc_ptr = calloc_scratch; void *malloc(size_t size) __throw() { lock_guard_t lock(alloc_lock); void *ptr = libc_malloc(size); if(slambench::memory::MemoryProfiler::SingletonAvailable()) { slambench::memory::MemoryProfiler::GetSingleton().AddAllocation(ptr, size); } return ptr; } void free(void* ptr) __throw() { lock_guard_t lock(alloc_lock); if(slambench::memory::MemoryProfiler::SingletonAvailable()) { if(ptr > calloc_scratch && ptr < calloc_scratch+sizeof(calloc_scratch)) { // do nothing } else { libc_free(ptr); slambench::memory::MemoryProfiler::GetSingleton().FreeAllocation(ptr); } } else { libc_free(ptr); } } void *realloc(void *ptr, size_t newsize) __throw() { lock_guard_t lock(alloc_lock); if(slambench::memory::MemoryProfiler::SingletonAvailable()) { if(ptr > calloc_scratch && ptr < calloc_scratch+sizeof(calloc_scratch)) { abort(); } auto newptr = libc_realloc(ptr, newsize); slambench::memory::MemoryProfiler::GetSingleton().FreeAllocation(ptr); slambench::memory::MemoryProfiler::GetSingleton().AddAllocation(newptr, newsize); return newptr; } else { return libc_realloc(ptr, newsize); } } void *calloc(size_t nmemb, size_t size) __throw() { lock_guard_t lock(alloc_lock); // need to be careful with calloc since dlsym will use it! need to do this // even if the profiler is disabled. static bool reentered = false; if(reentered) { void *ptr = calloc_ptr; calloc_ptr += nmemb*size; calloc_ptr += 16-(((uintptr_t)calloc_ptr) % 16); if(calloc_ptr >= (calloc_scratch + sizeof(calloc_scratch))) abort(); return ptr; } reentered = true; if(slambench::memory::MemoryProfiler::SingletonAvailable()) { void *result = libc_calloc(nmemb, size); slambench::memory::MemoryProfiler::GetSingleton().AddAllocation(result, nmemb * size); reentered = false; return result; } else { void *ptr = libc_calloc(nmemb, size); reentered = false; return ptr; } } } void *operator new(std::size_t size) { lock_guard_t lock(alloc_lock); void *mem = malloc(size); if(mem == nullptr) { throw std::bad_alloc(); } else { return mem; } } void *operator new(std::size_t size, const std::nothrow_t ¬hrow_value) __throw() { (void)nothrow_value; try { return operator new(size); } catch (std::exception &e) { return nullptr; } } void *operator new[](std::size_t size) { lock_guard_t lock(alloc_lock); void *mem = malloc(size); if(mem == nullptr) { throw std::bad_alloc(); } else { return mem; } } void *operator new[](std::size_t size, const std::nothrow_t ¬hrow_value) __throw() { (void)nothrow_value; try { return operator new[](size); } catch (std::exception &e) { return nullptr; } } #endif ================================================ FILE: framework/shared/src/values/Value.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "values/Value.h" #include "values/ValueDispatch.h" using namespace slambench::values; ValueDescription::ValueDescription(ValueType type) : type_(type) { } ValueDescription::ValueDescription(const structured_description& structured_desc) : type_(VT_COLLECTION), structured_type_(structured_desc) { } ValueType ValueDescription::GetType() const { return type_; } const ValueDescription::structured_description& ValueDescription::GetStructureDescription() const { if(GetType() != VT_COLLECTION) { throw std::logic_error(""); } return structured_type_; } Value::~Value() { } void Value::Dispatch(ValueDispatch* vd) { switch(GetType()) { #define HANDLE(vt) case vt: vd->Dispatch((TypeForVT::type*)this); return; HANDLE(VT_COLLECTION); HANDLE(VT_U64); HANDLE(VT_DOUBLE); HANDLE(VT_STRING); HANDLE(VT_TRAJECTORY); HANDLE(VT_POSE); HANDLE(VT_POINTCLOUD); // HANDLE(VT_FEATURE); // HANDLE(VT_FEATURELIST); // HANDLE(VT_FRAME); HANDLE(VT_MATRIX); #undef HANDLE case VT_UNKNOWN: default: assert(false); } } void Value::Dispatch(ConstValueDispatch* vd) const { switch(GetType()) { #define HANDLE(vt) case vt: vd->Dispatch((const TypeForVT::type*)this); return; HANDLE(VT_COLLECTION); HANDLE(VT_U64); HANDLE(VT_DOUBLE); HANDLE(VT_STRING); HANDLE(VT_TRAJECTORY); HANDLE(VT_POSE); HANDLE(VT_POINTCLOUD); // HANDLE(VT_FEATURE); // HANDLE(VT_FEATURELIST); // HANDLE(VT_FRAME); HANDLE(VT_MATRIX); #undef HANDLE case VT_UNKNOWN: default: assert(false); } } FrameValue::FrameValue(const FrameValue& other) : Value(VT_FRAME), width_(other.width_), height_(other.height_), pxl_format_(other.pxl_format_), data_(other.data_) { } FrameValue::FrameValue(uint32_t width, uint32_t height, slambench::io::pixelformat::EPixelFormat pxl_format, void* data) : Value(VT_FRAME), width_(width), height_(height), pxl_format_(pxl_format) { auto depth = slambench::io::pixelformat::GetPixelSize(pxl_format_); size_t datasize = width * height * depth; data_.resize(datasize); memcpy(data_.data(), data, datasize); } FrameValue::FrameValue(uint32_t width, uint32_t height, slambench::io::pixelformat::EPixelFormat pxl_format) : Value(VT_FRAME), width_(width), height_(height), pxl_format_(pxl_format) { auto depth = slambench::io::pixelformat::GetPixelSize(pxl_format_); size_t datasize = width * height * depth; data_.resize(datasize); } ValueCollectionValue::~ValueCollectionValue() { for(auto i : values_) { delete i.second; } } ValueListValue::~ValueListValue() { for(auto i : values_) { delete i; } } FeatureValue::FeatureValue(const Eigen::Matrix4f& pose, const FrameValue& patch) : Value(VT_FEATURE), image_patch_(patch), pose_(pose) { } FeatureValue::~FeatureValue() { } ================================================ FILE: framework/shared/src/values/ValueDispatch.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "values/ValueDispatch.h" using namespace slambench::values; ValueDispatch::~ValueDispatch() { } ConstValueDispatch::~ConstValueDispatch() { } ================================================ FILE: framework/shared/src/values/ValueInterface.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "values/ValueInterface.h" using namespace slambench::values; ValueInterface::~ValueInterface() { } ================================================ FILE: framework/shared/src/values/ValuePrinter.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "values/ValuePrinter.h" using namespace slambench::values; ValuePrinter::ValuePrinter(std::ostream& str) : str_(str) { } ValuePrinter::~ValuePrinter() { } void ValuePrinter::Dispatch(const TypeForVT::type* value) { str_ << value->GetValue(); } void ValuePrinter::Dispatch(const TypeForVT::type* value) { str_ << value->GetValue(); } void ValuePrinter::Dispatch(const TypeForVT::type* value) { str_ << value->GetValue(); } void ValuePrinter::Dispatch(const TypeForVT::type* value) { (void)value; str_ << "(point cloud)"; } void ValuePrinter::Dispatch(const TypeForVT::type* value) { (void)value; str_ << "(collection)"; } void ValuePrinter::Dispatch(const TypeForVT::type* value) { (void)value; str_ << "(trajectory)"; } void ValuePrinter::Dispatch(const TypeForVT::type* value) { // extract x, y, z auto &matrix = value->GetValue(); auto x = matrix(0, 3); auto y = matrix(1, 3); auto z = matrix(2, 3); str_ << x << ", " << y << ", " << z; } void ValuePrinter::Dispatch(const TypeForVT::type* value) { str_ << value->GetValue(); } ================================================ FILE: framework/tools/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) include_directories(${SLAMBENCH_INCLUDE_DIR}) add_subdirectory(accuracy-tools) # SLAMBench reconstruction Error etc... add_subdirectory(dataset-tools) # SLAMBench Dataset Generator add_subdirectory(profiling-tools) # SLAMBench Profiling add_subdirectory(loaders) # SLAMBench Loaders ================================================ FILE: framework/tools/README.md ================================================ # SLAMBench Tools # ================================================ FILE: framework/tools/accuracy-tools/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) project(accuracy_tools) find_package(PCL REQUIRED) get_directory_property(DirDefs COMPILE_DEFINITIONS) message(STATUS "VTK FIX:Previous properties=${DirDefs}") set_directory_properties(PROPERTIES COMPILE_DEFINITIONS "") ###################################################################################### ################# COMMONS ###################################################################################### include_directories(. ../../shared/include) set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} --std=c++14 -Wno-error=unused-parameter -Wno-error=unused-variable -Wno-error=unused-but-set-variable -Wno-error=attributes") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} --std=c++14 -Wno-error=unused-parameter -Wno-error=unused-variable -Wno-error=unused-but-set-variable -Wno-error=attributes") find_package(Pangolin QUIET) IF(Pangolin_FOUND) set(main_common_libraries ${SLAMBENCH_LIBRARIES}) set(gui_pangolin_libraries ${main_common_libraries} slambench-ui-pangolin ${Pangolin_LIBRARIES} ${OPENGL_LIBRARIES} pthread) if (PCL_FOUND) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) add_executable(pointcloud_aligner pointcloud_aligner.cpp) TARGET_INCLUDE_DIRECTORIES(pointcloud_aligner PUBLIC ${SLAMBENCH_INCLUDE_DIR}) TARGET_INCLUDE_DIRECTORIES(pointcloud_aligner PUBLIC ${Pangolin_INCLUDE_DIR}) TARGET_INCLUDE_DIRECTORIES(pointcloud_aligner PUBLIC ${TOON_INCLUDE_PATHS}) target_link_libraries(pointcloud_aligner PRIVATE ${gui_pangolin_libraries} ${PCL_LIBRARIES}) target_compile_options(pointcloud_aligner PRIVATE "-Wno-error=comment") if (CMAKE_COMPILER_IS_GNUCC AND CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 8.0) target_compile_options(pointcloud_aligner PRIVATE "-Wno-error=catch-value=") endif() install(TARGETS pointcloud_aligner DESTINATION bin/) else (PCL_FOUND) message(STATUS "Trajectory tool will not be compile, PCL not found.") endif(PCL_FOUND) ENDIF(Pangolin_FOUND) ================================================ FILE: framework/tools/accuracy-tools/pointcloud_aligner.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #undef HAVE_OPENNI #include typedef pcl::PointXYZ point_t; float getScore( pcl::PointCloud::Ptr gt,pcl::PointCloud::Ptr test) { std::cout << "Building tree, may take a few minutes..." << std::endl; pcl::search::KdTree::Ptr tree (new pcl::search::KdTree); tree->setInputCloud(gt); std::vector pointIdxNKNSearch(1); std::vector pointNKNSquaredDistance(1); double totalSum = 0; int count = 0; std::cout << "Start KNN search..." << std::endl; for(size_t i = 0; i < test->size(); i++) { if ((i % 500) == 0) std::cout << "\r" << i << std::flush; tree->nearestKSearch(test->at(i), 1, pointIdxNKNSearch, pointNKNSquaredDistance); totalSum += sqrt(pointNKNSquaredDistance.at(0)); count++; } std::cout << std::endl; return totalSum / (double)test->size(); } void computeAlignment(std::vector outputs, slambench::outputs::AlignmentOutput *alignment) { std::vector::Ptr> clouds ; for(auto output_mgr : outputs) { for(auto output : *output_mgr) { slambench::outputs::BaseOutput* bo = output.second; if (bo->GetType() == slambench::values::VT_POINTCLOUD) { std::cout << "Find one !" << std::endl; if(bo->GetValues().empty()) { std::cout << "An empty one !" << std::endl; continue; } const slambench::values::PointCloudValue *latest_pc = static_cast(bo->GetValues().rbegin()->second); size_t size = latest_pc->GetPoints().size(); std::cout << "With " << size << " points." << std::endl; pcl::PointCloud::Ptr cloud = pcl::PointCloud::Ptr(new pcl::PointCloud); for (auto point : latest_pc->GetPoints()) { cloud->push_back({point.X,point.Y,point.Z}); } clouds.push_back(cloud); } } } if (clouds.size() != 2) { std::cout << "Too many point clouds founds." << std::endl; throw std::invalid_argument(""); } auto alignment_value = (slambench::values::TypeForVT::type*)alignment->GetMostRecentValue().second; pcl::transformPointCloud(*clouds[0], *clouds[0], alignment_value->GetValue()); std::cout << "Transformation done." << std::endl; std::cout << "WE NEED TO Do THE TRAJECTORy ALIGNEMENT HERE !!!!" << std::endl; std::cout << "Initialize first scoring." << std::endl; int iteration = 0; float value = getScore(clouds[0],clouds[1]); std::cout << "First score is " << value << std::endl; if(value < 0.05) { std::cout << "Interesting score, we start icp." << std::endl; pcl::IterativeClosestPoint icp; pcl::PointCloud::Ptr aligned (new pcl::PointCloud ); icp.setInputSource(clouds[1]); icp.setInputTarget(clouds[0]); icp.setMaximumIterations(1); for(int i = 0; i < 10; i++) { std::cout << "Align pass " << i << std::endl; icp.align(*aligned, icp.getFinalTransformation()); iteration++; } std::cout << "Final scoring " << std::endl; value = std::min(getScore(clouds[0],aligned), value); } else { std::cout << "Score is too far, no ICP." << std::endl; } std::cout << value << std::endl; return; } slambench::outputs::OutputManager *LoadSLAMFile(const std::string &filename, slambench::io::FrameBufferSource &fb_src) { auto mgr = new slambench::outputs::OutputManager (); auto file = slambench::io::SLAMFile::Read(filename, fb_src); mgr->LoadGTOutputsFromSLAMFile(file); return mgr; } int main(int argc, char * argv[]) { //*************************************************************************************** // Init the GUI //*************************************************************************************** std::cerr << "Creation of GUI interface." << std::endl; SLAMBenchUI_Pangolin * ui_pangolin = new SLAMBenchUI_Pangolin(); // Initialise input data slambench::io::SingleFrameBufferSource fb_src; // for each arg, try and load an input file std::vector outputs; if(argc != 3) { printf("Usage: %s [slam file 1] [slam file 2]\n", argv[0]); return 1; } auto slamfile_alignee_filename = argv[1]; auto slamfile_target_filename = argv[2]; auto output_mgr_alignee = LoadSLAMFile(slamfile_alignee_filename, fb_src); auto output_mgr_target = LoadSLAMFile(slamfile_target_filename, fb_src); outputs.push_back(output_mgr_alignee); outputs.push_back(output_mgr_target); // Align traj1 onto traj2 auto alignee_traj = output_mgr_alignee->GetMainOutput(slambench::values::VT_POSE); auto alignee_pointcloud = (slambench::values::PointCloudValue*)output_mgr_alignee->GetMainOutput(slambench::values::VT_POINTCLOUD)->GetMostRecentValue().second; auto target_traj = output_mgr_target->GetMainOutput(slambench::values::VT_POSE); if(alignee_traj == nullptr || target_traj == nullptr) { std::cerr << "Both slamfiles must provide a pose output!"; return 1; } std::cerr << "File loaded" << std::endl; auto alignment = new slambench::outputs::AlignmentOutput("Alignment", new slambench::outputs::PoseOutputTrajectoryInterface(target_traj), alignee_traj, new slambench::outputs::OriginalTrajectoryAlignmentMethod()); alignment->SetKeepOnlyMostRecent(true); auto aligned_traj1 = new slambench::outputs::AlignedPoseOutput("Aligned", alignment, alignee_traj); output_mgr_alignee->RegisterOutput(aligned_traj1); auto partially_aligned_pc_op = new slambench::outputs::Output("Partially aligned PC", slambench::values::VT_POINTCLOUD); auto partially_aligned_pc = new slambench::values::PointCloudValue(*alignee_pointcloud); partially_aligned_pc->SetTransform(((slambench::values::TypeForVT::type*)alignment->GetMostRecentValue().second)->GetValue()); partially_aligned_pc_op->SetActive(true); partially_aligned_pc_op->AddPoint({0,0}, partially_aligned_pc); auto ui_output_manager = new slambench::outputs::OutputManager(); ui_output_manager->RegisterOutput(partially_aligned_pc_op); ui_pangolin->AddOutputManager("Traj1", output_mgr_alignee); ui_pangolin->AddOutputManager("Traj2", output_mgr_target); ui_pangolin->AddOutputManager("UI", ui_output_manager); // Initialise the UI ui_pangolin->InitialiseOutputs(); SLAMBenchUI * ui = dynamic_cast (ui_pangolin); // Provide the current camera position to the GUI // FIXME : temporary values (Toky) float fx = 520.9000244141; float fy = 521.0000000000; float cx = 324.5999755859; float cy = 249.2000122070; ui->update_camera(480,640, fx, fy , cx , cy ); //*************************************************************************************** // GUI LOOP + GUI CLOSED //*************************************************************************************** std::cerr << "Start to compute" << std::endl; std::thread compute_thread (computeAlignment, outputs, alignment); std::cerr << "Start rendering loop." << std::endl; while( !pangolin::ShouldQuit() ) { usleep(40000); if (!ui->process ()) { std::cerr << "Rendering problem." << std::endl; exit(1); } } std::cout << "Stop Pangolin..." << std::endl; pangolin::Quit(); std::cout << "GUI closed ... " << std::endl; compute_thread.join(); //*************************************************************************************** // CLOSE LIBRARIES //*************************************************************************************** std::cout << "End of program." << std::endl; return 0; } ================================================ FILE: framework/tools/dataset-tools/BONN.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/BONN.h" #include "include/utils/RegexPattern.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include "include/utils/PlyASCIIReader.h" #include #include #include #include #include #include #include #include #include using namespace slambench::io; constexpr CameraSensor::intrinsics_t BONNReader::intrinsics_rgb; constexpr DepthSensor::intrinsics_t BONNReader::intrinsics_depth; constexpr CameraSensor::distortion_coefficients_t BONNReader::distortion_rgb; constexpr DepthSensor::distortion_coefficients_t BONNReader::distortion_depth; constexpr DepthSensor::disparity_params_t BONNReader::disparity_params; constexpr DepthSensor::disparity_type_t BONNReader::disparity_type; constexpr CameraSensor::distortion_type_t BONNReader::distortion_type; bool loadBONNDepthData(const std::string &dirname, SLAMFile &file) { std::string line; printf("Directory name: %s\n", dirname.c_str()); std::ifstream infile(dirname + "/" + "depth.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex depth_line = boost::regex(expr); int lineCount = 0; while (std::getline(infile, line)) { printf("line %d: %s\n", lineCount, line.c_str()); lineCount++; if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, depth_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string depth_filename = match[3]; auto depth_frame = new ImageFileFrame(); depth_frame->FrameSensor = *file.Sensors.end(); depth_frame->Timestamp.S = timestampS; depth_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << depth_filename; depth_frame->filename = frame_name.str(); if (access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame (%s)\n", frame_name.str().c_str()); perror(""); continue; } file.AddFrame(depth_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadBONNRGBData(const std::string &dirname, SLAMFile &file) { std::string line; std::ifstream infile(dirname + "/" + "rgb.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex rgb_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, rgb_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string rgb_filename = match[3]; auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = *file.Sensors.end(); rgb_frame->Timestamp.S = timestampS; rgb_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << rgb_filename; rgb_frame->filename = frame_name.str(); if (access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(rgb_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadBONNGreyData(const std::string &dirname, SLAMFile &file) { std::string line; std::ifstream infile(dirname + "/" + "rgb.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex rgb_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, rgb_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string rgb_filename = match[3]; auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = *file.Sensors.end(); grey_frame->Timestamp.S = timestampS; grey_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << rgb_filename; grey_frame->filename = frame_name.str(); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(grey_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadBONNGroundTruthData(const std::string &dirname, SLAMFile &file) { std::ifstream infile(dirname + "/" + "groundtruth.txt"); std::string line; boost::smatch match; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& num = RegexPattern::number; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp tx ty tz qx qy qz qw std::string expr = start + ts + ws // timestamp + num + ws // tx + num + ws // ty + num + ws // tz + num + ws // qx + num + ws // qy + num + ws // qz + num + end; // qw boost::regex groundtruth_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, groundtruth_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); float tx = std::stof(match[3]); float ty = std::stof(match[4]); float tz = std::stof(match[5]); float QX = std::stof(match[6]); float QY = std::stof(match[7]); float QZ = std::stof(match[8]); float QW = std::stof(match[9]); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = *file.Sensors.end(); gt_frame->Timestamp.S = timestampS; gt_frame->Timestamp.Ns = timestampNS; gt_frame->Data = malloc(gt_frame->GetSize()); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } else { std::cerr << "Unknown line: " << line << std::endl; return false; } } return true; } bool loadBONNPointCloudData(slambench::io::SLAMFile &slamfile, const std::string& plyname) { auto pcd = new slambench::io::PointCloudSensor("PointCloud"); pcd->Description = "Ground truth point cloud"; pcd->Index = slamfile.Sensors.size(); slamfile.Sensors.AddSensor(pcd); auto pointcloud = PlyASCIIReader::read(plyname); if(pointcloud == nullptr) { fprintf(stderr, "Could not read point cloud\n"); return false; } auto rawpointcloud = pointcloud->ToRaw(); auto pcloudframe = new SLAMInMemoryFrame(); pcloudframe->FrameSensor = slamfile.GetSensor(PointCloudSensor::kPointCloudType); int numBytes = rawpointcloud.size(); pcloudframe->Data = malloc(numBytes); pcloudframe->SetVariableSize(rawpointcloud.size()); std::copy(rawpointcloud.data(), rawpointcloud.data() + numBytes, reinterpret_cast(pcloudframe->Data)); slamfile.AddFrame(pcloudframe); return true; } SLAMFile *BONNReader::GenerateSLAMFile() { if (!(grey || rgb || depth)) { std::cerr << "No sensors defined\n"; return nullptr; } std::string dirname = input; const std::vector requirements = {"rgb.txt", "rgb", "depth.txt", "depth", "groundtruth.txt"}; if (!checkRequirements(dirname, requirements)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } auto slamfile_ptr = new SLAMFile(); auto &slamfile = *slamfile_ptr; Sensor::pose_t pose = Eigen::Matrix4f::Identity(); // load Depth if (depth) { auto depth_sensor = DepthSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .pose(pose) .intrinsics(intrinsics_depth) .distortion(distortion_type, distortion_depth) .disparity(disparity_type, disparity_params) .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(depth_sensor); if (!loadBONNDepthData(dirname, slamfile)) { std::cout << "Error while loading depth information." << std::endl; delete slamfile_ptr; return nullptr; } } // load Grey if (grey) { auto grey_sensor = GreySensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .pose(pose) .intrinsics(intrinsics_rgb) .distortion(distortion_type, distortion_rgb) .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(grey_sensor); if (!loadBONNGreyData(dirname, slamfile)) { std::cerr << "Error while loading Grey information." << std::endl; delete slamfile_ptr; return nullptr; } } // load RGB if (rgb) { auto rgb_sensor = RGBSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .pose(pose) .intrinsics(intrinsics_rgb) .distortion(distortion_type, distortion_rgb) .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(rgb_sensor); if (!loadBONNRGBData(dirname, slamfile)) { std::cerr << "Error while loading RGB information." << std::endl; delete slamfile_ptr; return nullptr; } } // load GT if (gt) { auto gt_sensor = GTSensorBuilder() .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(gt_sensor); if(!loadBONNGroundTruthData(dirname, slamfile)) { std::cerr << "Error while loading gt information." << std::endl; delete slamfile_ptr; return nullptr; } } // load PointCloud if (!plyfile.empty() && !loadBONNPointCloudData(slamfile, plyfile)) { std::cerr << "Error while loading point cloud information." << std::endl; delete slamfile_ptr; return nullptr; } return slamfile_ptr; } ================================================ FILE: framework/tools/dataset-tools/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) include_directories(./include) set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-error=unused-parameter -Wno-error=unused-variable -Wno-error=unused-but-set-variable") set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-error=unused-parameter -Wno-error=unused-variable -Wno-error=unused-but-set-variable") # use colour to highlight error messages string(ASCII 27 ESC) string(ASCII 10 LF) set(BoldRed "${ESC}[1;31m") set(BoldGreen "${ESC}[1;32m") set(ColourReset "${ESC}[m") #------------------------------------------------ ### find required external dependencies ### NOTE: dependencies vary according to dataset #------------------------------------------------ # Boost is required - abort if not found find_package(Boost 1.54 REQUIRED COMPONENTS system filesystem program_options regex) # EUROCMAV datasets support requirements - skip if not found find_package(LIBYAML QUIET) IF (NOT LIBYAML_FOUND) message(STATUS "${BoldRed}LibYAML dependency for UZH-FPV, EuRoC-MAV and OpenLORIS datasets not found - datasets skipped${ColourReset}") ENDIF () #------------------------------------------------ # TUM rosbag datasets support requirements - skip if not found # OpenCV should be looked for before ROS packages in order to find # the OpenCV version used in SLAMBench, not any in the ROS environment find_package(OpenCV QUIET) IF (NOT OpenCV_FOUND) message(STATUS "${BoldRed}OpenCV dependency for TUM rosbag datasets not found${ColourReset}") ENDIF () # Find ROS distribution - if one is installed # check if ROS environment has been setup if (NOT "x$ENV{ROS_DISTRO}" STREQUAL "x") set(ROS_DIST $ENV{ROS_DISTRO}) message (STATUS "Found ROS distribution: ${ROS_DIST}") else () # if ROS not setup, try standard location if (EXISTS "/opt/ros/") # get ROS distribution name execute_process(COMMAND "ls" WORKING_DIRECTORY "/opt/ros/" OUTPUT_VARIABLE SDS) string (STRIP ${SDS} SUBDIRS) string(REPLACE ${LF} ";" ROS_DISTS ${SUBDIRS}) list (LENGTH ROS_DISTS LENSD) if (${LENSD} EQUAL 1) list (GET ROS_DISTS 0 ROS_DIST) list (APPEND CMAKE_PREFIX_PATH "/opt/ros/${ROS_DIST}") message (STATUS "Found ROS distribution: ${ROS_DIST}") elseif (${LENSD} GREATER 1) message (STATUS "${BoldRed}Found more than one ROS distribution - please setup ROS environment before building SLAMBench${ColourReset}") else () message (STATUS "${BoldRed}Could NOT find a ROS distribution${ColourReset}") endif () endif () endif () # Find required ROS packages set(ROSPKGS rosbag_storage roscpp_serialization) set(ROSPKGS_FOUND TRUE) foreach (ROSPKG ${ROSPKGS}) find_package(${ROSPKG} QUIET) if (NOT ${ROSPKG}_FOUND) set(ROSPKGS_FOUND FALSE) message(STATUS "${BoldRed}${ROSPKG} dependency for TUM rosbag datasets not found${ColourReset}") endif () endforeach (ROSPKG) # report success or failure in finding tum-rosbag dependencies IF (OpenCV_FOUND AND ROSPKGS_FOUND) message (STATUS "${BoldGreen}Generation of tum-rosbag dataset support : Activated${ColourReset}") else () message(STATUS "${BoldRed}Dependencies for TUM rosbag datasets not found - dataset skipped${ColourReset}") endif () #------------------------------------------------ #------------------------------------------------ ### add executables and target libraries #------------------------------------------------ add_executable(io-readply io-readply.cpp) target_link_libraries(io-readply slambench-io slambench-metrics) add_executable(io-inspect-file io-inspect.cpp) target_link_libraries(io-inspect-file PRIVATE -Wl,--whole-archive slambench-io slambench-metrics -Wl,--no-whole-archive) IF (LIBYAML_FOUND) add_library(EUROCMAV EUROCMAV.cpp) target_link_libraries(EUROCMAV slambench-io ${Boost_LIBRARIES} ${LIBYAML_LIBRARY}) target_include_directories(EUROCMAV PRIVATE ${Boost_INCLUDE_DIRS} ${LIBYAML_INCLUDE_DIR}) set(EUROCMAV_LIB "EUROCMAV") add_library(OpenLORIS OpenLORIS.cpp) target_link_libraries(OpenLORIS slambench-io ${Boost_LIBRARIES} ${LIBYAML_LIBRARY}) target_include_directories(OpenLORIS PRIVATE ${Boost_INCLUDE_DIRS} ${LIBYAML_INCLUDE_DIR}) set(OpenLORIS_LIB "OpenLORIS") add_library(UZHFPV UZHFPV.cpp) target_link_libraries(UZHFPV slambench-io ${Boost_LIBRARIES} ${LIBYAML_LIBRARY}) target_include_directories(UZHFPV PRIVATE ${Boost_INCLUDE_DIRS} ${LIBYAML_INCLUDE_DIR}) set(UZHFPV_LIB "UZHFPV") ENDIF (LIBYAML_FOUND) add_library(SVO SVO.cpp) target_link_libraries(SVO slambench-io ${Boost_LIBRARIES}) target_include_directories(SVO PRIVATE ${Boost_INCLUDE_DIRS}) add_library(ICL ICL.cpp) target_link_libraries(ICL slambench-io ${Boost_LIBRARIES}) target_include_directories(ICL PRIVATE ${Boost_INCLUDE_DIRS}) add_library(TUM TUM.cpp) target_link_libraries(TUM slambench-io ${Boost_LIBRARIES}) target_include_directories(TUM PRIVATE ${Boost_INCLUDE_DIRS}) add_library(BONN BONN.cpp) target_link_libraries(BONN slambench-io ${Boost_LIBRARIES}) target_include_directories(BONN PRIVATE ${Boost_INCLUDE_DIRS}) add_library(ICLNUIM ICLNUIM.cpp) target_link_libraries(ICLNUIM slambench-io) target_include_directories(ICLNUIM PRIVATE ${Boost_INCLUDE_DIRS}) add_library(ETHI ETHI.cpp) target_link_libraries(ETHI slambench-io TUM ICLNUIM) target_include_directories(ETHI PRIVATE ${Boost_INCLUDE_DIRS}) add_library(VolumeDeform VolumeDeform.cpp) target_link_libraries(VolumeDeform slambench-io) target_include_directories(VolumeDeform PRIVATE ${Boost_INCLUDE_DIRS}) # if all dependencies found add TUM-ROSBAG target IF (OpenCV_FOUND AND ROSPKGS_FOUND) add_library(TUM-ROSBAG TUM-ROSBAG.cpp) # in some platforms, newer versions of the gnu linker # changed the search PATHs for dependency libraries. # This option uses old-style PATHs. target_link_libraries(TUM-ROSBAG "-Wl,--disable-new-dtags") target_link_libraries(TUM-ROSBAG slambench-io ${Boost_LIBRARIES}) target_link_libraries(TUM-ROSBAG ${OpenCV_LIBRARIES}) foreach (ROSPKG ${ROSPKGS}) target_link_libraries(TUM-ROSBAG ${${ROSPKG}_LIBRARIES}) endforeach (ROSPKG) target_include_directories(TUM-ROSBAG PRIVATE ${Boost_INCLUDE_DIRS}) target_include_directories(TUM-ROSBAG PRIVATE ${OpenCV_INCLUDE_DIRS}) target_include_directories(TUM-ROSBAG PRIVATE ${rosbag_storage_INCLUDE_DIRS}) add_definitions(-DROSBAG_SUPPORT=1) set(TUM-ROSBAG_LIB "TUM-ROSBAG") endif () add_executable(dataset-generator dataset-generator.cpp) target_link_libraries(dataset-generator TUM UZHFPV ICLNUIM ICL ETHI BONN VolumeDeform ${OpenLORIS_LIB} ${UZHFPV_LIB} ${EUROCMAV_LIB} SVO ${TUM-ROSBAG_LIB}) ================================================ FILE: framework/tools/dataset-tools/ETHI.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/ETHI.h" #include #include using namespace slambench::io; SLAMFile *ETHIReader::GenerateSLAMFile() {return nullptr;} ================================================ FILE: framework/tools/dataset-tools/EUROCMAV.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/EUROCMAV.h" #include "include/utils/RegexPattern.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; bool loadIMUData(const std::string &dirname, IMUSensor *IMU_sensor, SLAMFile *file) { std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "data.csv"); const std::string& ns = RegexPattern::nanoseconds; const std::string& num = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp,w_RS_S_x,w_RS_S_y,w_RS_S_z,a_RS_S_x,a_RS_S_y,a_RS_S_z std::string expr = start + ns + "," // nanosecond timestamp + num + "," // w_RS_S_x + num + "," // w_RS_S_y + num + "," // w_RS_S_z + num + "," // a_RS_S_x + num + "," // a_RS_S_y + num + "\\s*" // a_RS_S_z + end; boost::regex imu_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, imu_line)) { uint64_t timestamp = strtol(std::string(match[1]).c_str(), nullptr, 10); int timestampS = timestamp / 1000000000; int timestampNS = timestamp % 1000000000; float gx = std::stof(match[2]); float gy = std::stof(match[3]); float gz = std::stof(match[4]); float ax = std::stof(match[5]); float ay = std::stof(match[6]); float az = std::stof(match[7]); auto IMU_frame = new SLAMInMemoryFrame(); IMU_frame->FrameSensor = IMU_sensor; IMU_frame->Timestamp.S = timestampS; IMU_frame->Timestamp.Ns = timestampNS; IMU_frame->Data = malloc(IMU_sensor->GetFrameSize(IMU_frame)); ((float *)IMU_frame->Data)[0] = gx; ((float *)IMU_frame->Data)[1] = gy; ((float *)IMU_frame->Data)[2] = gz; ((float *)IMU_frame->Data)[3] = ax; ((float *)IMU_frame->Data)[4] = ay; ((float *)IMU_frame->Data)[5] = az; file->AddFrame(IMU_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadGTData(const std::string &dirname, Sensor *gt_sensor, SLAMFile *file) { std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "data.csv"); const std::string& ns = RegexPattern::nanoseconds; const std::string& num = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp, p_RS_R_x, p_RS_R_y, p_RS_R_z, q_RS_w, q_RS_x, q_RS_y, q_RS_z, v_RS_R_x, v_RS_R_y, v_RS_R_z, // b_w_RS_S_x, b_w_RS_S_y, b_w_RS_S_z, b_a_RS_S_x, b_a_RS_S_y, b_a_RS_S_z std::string expr = start + ns + "," // nanosecond timestamp + num + "," // p_RS_R_x + num + "," // p_RS_R_y + num + "," // p_RS_R_z + num + "," // q_RS_w + num + "," // q_RS_x + num + "," // q_RS_y + num + "," // q_RS_z + num + "," // v_RS_R_x + num + "," // v_RS_R_y + num + "," // v_RS_R_z + num + "," // b_w_RS_S_x + num + "," // b_w_RS_S_y + num + "," // b_w_RS_S_z + num + "," // b_a_RS_S_x + num + "," // b_a_RS_S_y + num + "\\s*" // b_a_RS_S_z + end; boost::regex groundtruth_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, groundtruth_line)) { uint64_t timestamp = strtol(std::string(match[1]).c_str(), nullptr, 10); int timestampS = timestamp / 1000000000; int timestampNS = timestamp % 1000000000; float p_RS_R_x = std::stof(match[2]); // [m], float p_RS_R_y = std::stof(match[3]); // [m], float p_RS_R_z = std::stof(match[4]); // [m], float q_RS_w = std::stof(match[5]); // [], float q_RS_x = std::stof(match[6]); // [], float q_RS_y = std::stof(match[7]); // [], float q_RS_z = std::stof(match[8]); // [], // float v_RS_R_x = std::stof(match[9]) ; // [m s^-1] // float v_RS_R_y = std::stof(match[10]) ; // [m s^-1] // float v_RS_R_z = std::stof(match[11]) ; // [m s^-1] // float b_w_RS_S_x = std::stof(match[11]) ; // [rad s^-1], // float b_w_RS_S_y = std::stof(match[12]) ; // [rad s^-1], // float b_w_RS_S_z = std::stof(match[13]) ; // [rad s^-1], // float b_a_RS_S_x = std::stof(match[14]) ; // [m s^-2] // float b_a_RS_S_y = std::stof(match[15]) ; // [m s^-2] // float b_a_RS_S_z = std::stof(match[16]) ; // [m s^-2] Eigen::Matrix3f rotationMat = Eigen::Quaternionf(q_RS_w, q_RS_x, q_RS_y, q_RS_z).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << p_RS_R_x, p_RS_R_y, p_RS_R_z; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp.S = timestampS; gt_frame->Timestamp.Ns = timestampNS; gt_frame->Data = malloc(gt_sensor->GetFrameSize(gt_frame)); memcpy(gt_frame->Data, pose.data(), gt_sensor->GetFrameSize(gt_frame)); file->AddFrame(gt_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } SLAMFile *EUROCMAVReader::GenerateSLAMFile() { // first, see what sensors we have std::vector sensor_directories; std::string input_dir = input; DIR *dir = opendir(input_dir.c_str()); dirent *pdir; while ((pdir = readdir(dir)) != nullptr) { if (pdir->d_type == DT_DIR) { if (strcmp(pdir->d_name, ".") == 0) { continue; } if (strcmp(pdir->d_name, "..") == 0) { continue; } sensor_directories.emplace_back(pdir->d_name); } } auto slamfile = new SLAMFile(); std::sort(sensor_directories.begin(), sensor_directories.end()); for (auto &dirname : sensor_directories) { // try and get sensor.yaml file std::string cam_dirname = input_dir + "/" + dirname; std::string filename = cam_dirname + "/sensor.yaml"; YAML::Node sensor = YAML::LoadFile(filename.c_str()); // check sensor type auto sensor_type = sensor["sensor_type"].as(); if (sensor_type == "camera" and this->stereo) { std::cerr << "Found sensor type " << sensor_type << " from directory " << dirname << std::endl; // get pose Eigen::Matrix4f pose; for (int i = 0; i < 16; ++i) { int y = i % 4; int x = i / 4; std::cout << " " << sensor["T_BS"]["data"][i].as(); pose(x, y) = sensor["T_BS"]["data"][i].as(); if ((i + 1) % 4 == 0) std::cout << std::endl; } // get resolution int width = sensor["resolution"][0].as(); int height = sensor["resolution"][1].as(); float rate = sensor["rate_hz"].as(); // get intrinsics CameraSensor::intrinsics_t intrinsics = { sensor["intrinsics"][0].as() / width, sensor["intrinsics"][1].as() / height, sensor["intrinsics"][2].as() / width, sensor["intrinsics"][3].as() / height }; // check expected distortion type if (sensor["distortion_model"].as() != "radial-tangential") { std::cerr << "Unsupported distortion type for Eurocmav." << std::endl; exit(1); } // get distortion coefficients CameraSensor::distortion_coefficients_t distortion = { sensor["distortion_coefficients"][0].as(), sensor["distortion_coefficients"][1].as(), sensor["distortion_coefficients"][2].as(), sensor["distortion_coefficients"][3].as(), 0 }; // Create a Grey sensor auto grey_sensor = GreySensorBuilder() .name(dirname) .rate(rate) .size(width, height) .description(sensor["comment"].as()) .intrinsics(intrinsics) .distortion(CameraSensor::distortion_type_t::RadialTangential, distortion) .pose(pose) .build(); grey_sensor->Index = slamfile->Sensors.size(); slamfile->Sensors.AddSensor(grey_sensor); // Create a RGB equivalent sensor auto rgb_sensor = RGBSensorBuilder() .name(dirname + "clone") .description("RGB clone from " + sensor["comment"].as()) .rate(rate) .size(width, height) .intrinsics(intrinsics) .pose(pose) .distortion(CameraSensor::distortion_type_t::RadialTangential, distortion) .build(); rgb_sensor->Index = slamfile->Sensors.size(); if (this->rgb) { slamfile->Sensors.AddSensor(rgb_sensor); } // now, load frames dir = opendir((cam_dirname + "/data/").c_str()); while ((pdir = readdir(dir)) != nullptr) { if (pdir->d_type == DT_REG) { // Add the original Grey Image auto frame = new ImageFileFrame(); frame->FrameSensor = grey_sensor; frame->filename = cam_dirname + "/data/" + pdir->d_name; uint64_t timestamp = strtol(pdir->d_name, nullptr, 10); frame->Timestamp.S = timestamp / 1000000000; frame->Timestamp.Ns = timestamp % 1000000000; slamfile->AddFrame(frame); if (this->rgb) { // Add the clone RGB auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = rgb_sensor; rgb_frame->filename = cam_dirname + "/data/" + pdir->d_name; rgb_frame->Timestamp.S = timestamp / 1000000000; rgb_frame->Timestamp.Ns = timestamp % 1000000000; slamfile->AddFrame(rgb_frame); } } } } else if (sensor_type == "imu" and this->imu) { std::cerr << "Found sensor type " << sensor_type << " from directory " << dirname << std::endl; auto imu_sensor = new IMUSensor(dirname); imu_sensor->Index = slamfile->Sensors.size(); imu_sensor->Description = sensor["comment"].as(); imu_sensor->Rate = sensor["rate_hz"].as(); imu_sensor->GyroscopeNoiseDensity = sensor["gyroscope_noise_density"].as(); imu_sensor->GyroscopeDriftNoiseDensity = 4.0e-6; imu_sensor->GyroscopeBiasDiffusion = sensor["gyroscope_random_walk"].as(); imu_sensor->GyroscopeSaturation = 7.8; imu_sensor->AcceleratorNoiseDensity = sensor["accelerometer_noise_density"].as(); imu_sensor->AcceleratorDriftNoiseDensity = 4.0e-5; imu_sensor->AcceleratorBiasDiffusion = sensor["accelerometer_random_walk"].as(); imu_sensor->AcceleratorSaturation = 176.0; // double tau = 3600.0; // # reversion time constant, currently not in use [s] // double g = 9.81007; // # Earth's acceleration due to gravity [m/s^2] // Eigen::Vector3d a0 = {0.0, 0.0, 0.0}; // # Accelerometer bias [m/s^2] Eigen::Matrix4f pose; for (int i = 0; i < 16; ++i) { int y = i % 4; int x = i / 4; std::cout << " " << sensor["T_BS"]["data"][i].as(); pose(x, y) = sensor["T_BS"]["data"][i].as(); if ((i + 1) % 4 == 0) std::cout << std::endl; } imu_sensor->CopyPose(pose); slamfile->Sensors.AddSensor(imu_sensor); if (not loadIMUData(cam_dirname, imu_sensor, slamfile)) { delete slamfile; return nullptr; } } else if (sensor_type == "visual-inertial" and this->gt) { std::cerr << "Found sensor type " << sensor_type << " from directory " << dirname << std::endl; auto gt_sensor = GTSensorBuilder() .name(dirname) .description("Ground Truth") .build(); gt_sensor->Index = slamfile->Sensors.size(); slamfile->Sensors.AddSensor(gt_sensor); if (not loadGTData(cam_dirname, gt_sensor, slamfile)) { delete slamfile; return nullptr; } } else { std::cerr << "Unknown sensor type " << sensor_type << " from directory " << dirname << std::endl; } } return slamfile; } ================================================ FILE: framework/tools/dataset-tools/ICL.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/ICL.h" #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io ; static DepthSensor *GetDepthSensor(const Sensor::pose_t &pose, const DepthSensor::intrinsics_t &intrinsics, const DepthSensor::disparity_params_t &dparams, const DepthSensor::disparity_type_t &dtype) { DepthSensor *sensor = new DepthSensor("Depth"); sensor->Index = 0; sensor->Width = 640; sensor->Height = 480; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelformat::D_I_16; sensor->DisparityType = dtype; sensor->Description = "Depth"; sensor->Rate = 1; sensor->CopyPose(pose); sensor->CopyIntrinsics(intrinsics); sensor->CopyDisparityParams(dparams); return sensor; } static CameraSensor *GetRGBSensor(const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics) { CameraSensor *sensor = new CameraSensor("RGB", CameraSensor::kCameraType); sensor->Index = 0; sensor->Width = 640; sensor->Height = 480; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelformat::RGB_III_888; sensor->Description = "RGB"; sensor->Rate = 1; sensor->CopyPose(pose); sensor->CopyIntrinsics(intrinsics); return sensor; } static CameraSensor *GetGreySensor(const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics) { CameraSensor *sensor = new CameraSensor("Grey", CameraSensor::kCameraType); sensor->Index = 0; sensor->Width = 640; sensor->Height = 480; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelformat::G_I_8; sensor->Description = "Grey"; sensor->Rate = 1; sensor->CopyPose(pose); sensor->CopyIntrinsics(intrinsics); return sensor; } void undistort_frame(slambench::io::SLAMFileFrame *frame, void *data) { uint16_t *depthMap = (uint16_t*)data; uint32_t w = ((slambench::io::CameraSensor*)frame->FrameSensor)->Width; uint32_t h = ((slambench::io::CameraSensor*)frame->FrameSensor)->Height; float u0 = 320.00; float v0 = 240.00; float fx = -600.00; float fy = 600.00; for (uint32_t v = 0; v < h; v++) { for (uint32_t u = 0; u < w; u++) { double u_u0_by_fx = (u - u0) / fx; double v_v0_by_fy = (v - v0) / fy; depthMap[u + v * w] = depthMap[u + v * w] / std::sqrt(u_u0_by_fx * u_u0_by_fx + v_v0_by_fy * v_v0_by_fy + 1); } } } /* * * The dataset folder contains : * > accelerometer.txt depth depth.txt groundtruth.txt rgb rgb.txt * */ bool analyseIclFolder(const std::string &dirname) { static const std::vector requirements = { //"accelerometer.txt", //"rgb.txt", //"rgb", //"depth.txt", //"depth", //"groundtruth.txt" //"cam0.ccam", //"cam0_gt.visim" }; try { if ( !boost::filesystem::exists( dirname ) ) return false; boost::filesystem::directory_iterator end_itr; // default construction yields past-the-end for ( auto requirement : requirements ) { bool seen = false; for ( boost::filesystem::directory_iterator itr( dirname ); itr != end_itr; ++itr ) { if (requirement == itr->path().filename()) { seen = true; } } if (!seen) { std::cout << "File not found: /" << requirement << std::endl; return false; } } } catch (boost::filesystem::filesystem_error& e) { std::cerr << "I/O Error with directory " << dirname << std::endl; std::cerr << e.what() << std::endl; return false; } return true; } bool loadICLDepthData(const std::string &dirname , SLAMFile &file, const Sensor::pose_t &pose_depth, const DepthSensor::intrinsics_t &intrinsics_depth, const DepthSensor::disparity_params_t &disparity_params, const DepthSensor::disparity_type_t &disparity_type) { DepthSensor *depth_sensor = GetDepthSensor(pose_depth, intrinsics_depth,disparity_params,disparity_type); depth_sensor->Index = file.Sensors.size(); file.Sensors.AddSensor(depth_sensor); if(!depth_sensor) { std::cout << "depth sensor not found..." << std::endl; return false; } std::string cam_name = ""; std::string trajectory_name = ""; std::string light_name = ""; std::string time_name = ""; std::string root_name = ""; std::string directory_head = ""; std::size_t found = dirname.find_last_of("/"); if (found == dirname.length()-1) // the dirname ends with / { } else { cam_name = dirname.substr(found+1, 10); std::size_t found2 = dirname.rfind("/", found-1); std::size_t found3 = dirname.rfind("/", found2-1); std::size_t found4 = dirname.rfind("/", found3-1); std::size_t found5 = dirname.rfind("/", found4-1); trajectory_name = dirname.substr(found2+1,found-found2-1); light_name = dirname.substr(found3+1,found2-found3-1); time_name = dirname.substr(found4+1,found3-found4-1); root_name = dirname.substr(found5+1,found4-found5-1); directory_head = dirname.substr(0,found5); std::cout << "cam_name: " << cam_name << std::endl; std::cout << "trajectory_name: " << trajectory_name << std::endl; std::cout << "light_name: " << light_name << std::endl; std::cout << "time_name: " << time_name << std::endl; std::cout << "root_name: " << root_name << std::endl; //std::cout << "directory_head: " << directory_head << std::endl; } int frame_no = 0; std::string line; boost::smatch match; std::ifstream infile(directory_head + "/" + root_name + "/trajectories/" + trajectory_name + "/" + cam_name + "/cam0_gt.visim"); while (std::getline(infile, line)){ if (line.size() == 0) { continue; } else if (boost::regex_match(line,match,boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line,match,boost::regex("^([-0-9.e]+).*"))) { uint64_t time = std::stoull(match[1]); double time_float = time * std::pow(10, -9); uint32_t time_second = std::floor(time_float); uint32_t time_nsecond = std::round((time_float - time_second)*std::pow(10, 9)); ImageFileFrame *depth_frame = new ImageFileFrame(); depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp.S = time_second; depth_frame->Timestamp.Ns = time_nsecond; depth_frame->ProcessCallback = undistort_frame; std::stringstream frame_name; frame_name << dirname << "/depth/" << frame_no << ".png"; depth_frame->filename = frame_name.str(); if(access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(depth_frame); frame_no++; } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } std::cerr << "Checked Depth frames:" << frame_no << std::endl; return true; } bool loadICLRGBData(const std::string &dirname , SLAMFile &file, const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics) { CameraSensor *rgb_sensor = GetRGBSensor(pose, intrinsics); rgb_sensor->Index =file.Sensors.size(); file.Sensors.AddSensor(rgb_sensor); if(!rgb_sensor) { std::cout << "rgb sensor not found..." << std::endl; return false; } std::string cam_name = ""; std::string trajectory_name = ""; std::string light_name = ""; std::string time_name = ""; std::string root_name = ""; std::string directory_head = ""; std::size_t found = dirname.find_last_of("/"); if (found == dirname.length()-1) // the dirname ends with / { } else { cam_name = dirname.substr(found+1, 10); std::size_t found2 = dirname.rfind("/", found-1); std::size_t found3 = dirname.rfind("/", found2-1); std::size_t found4 = dirname.rfind("/", found3-1); std::size_t found5 = dirname.rfind("/", found4-1); trajectory_name = dirname.substr(found2+1,found-found2-1); light_name = dirname.substr(found3+1,found2-found3-1); time_name = dirname.substr(found4+1,found3-found4-1); root_name = dirname.substr(found5+1,found4-found5-1); directory_head = dirname.substr(0,found5); } int frame_no = 0; std::string line; boost::smatch match; std::ifstream infile(directory_head + "/" + root_name + "/trajectories/" + trajectory_name + "/" + cam_name + "/cam0_gt.visim"); while (std::getline(infile, line)){ if (line.size() == 0) { continue; } else if (boost::regex_match(line,match,boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line,match,boost::regex("^([-0-9.e]+).*"))) {//else if (boost::regex_match(line,match,boost::regex("^([0-9]+).*"))) { uint64_t time = std::stoull(match[1]); double time_float = time * std::pow(10, -9); uint32_t time_second = std::floor(time_float); uint32_t time_nsecond = std::round((time_float - time_second)*std::pow(10, 9)); ImageFileFrame *rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = rgb_sensor; rgb_frame->Timestamp.S = time_second; rgb_frame->Timestamp.Ns = time_nsecond; std::stringstream frame_name; frame_name << dirname << "/rgb/" << frame_no << ".png"; rgb_frame->filename = frame_name.str(); if(access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(rgb_frame); frame_no++; } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } std::cerr << "Checked RGB frames:" << frame_no << std::endl; return true; } bool loadICLGreyData(const std::string &dirname , SLAMFile &file, const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics) { CameraSensor *grey_sensor = GetGreySensor(pose, intrinsics); grey_sensor->Index =file.Sensors.size(); file.Sensors.AddSensor(grey_sensor); if(!grey_sensor) { std::cout << "grey sensor not found..." << std::endl; return false; } std::string cam_name = ""; std::string trajectory_name = ""; std::string light_name = ""; std::string time_name = ""; std::string root_name = ""; std::string directory_head = ""; std::size_t found = dirname.find_last_of("/"); if (found == dirname.length()-1) // the dirname ends with / { } else { cam_name = dirname.substr(found+1, 10); std::size_t found2 = dirname.rfind("/", found-1); std::size_t found3 = dirname.rfind("/", found2-1); std::size_t found4 = dirname.rfind("/", found3-1); std::size_t found5 = dirname.rfind("/", found4-1); trajectory_name = dirname.substr(found2+1,found-found2-1); light_name = dirname.substr(found3+1,found2-found3-1); time_name = dirname.substr(found4+1,found3-found4-1); root_name = dirname.substr(found5+1,found4-found5-1); directory_head = dirname.substr(0,found5); } int frame_no = 0; std::string line; boost::smatch match; std::ifstream infile(directory_head + "/" + root_name + "/trajectories/" + trajectory_name + "/" + cam_name + "/cam0_gt.visim"); while (std::getline(infile, line)){ if (line.size() == 0) { continue; } else if (boost::regex_match(line,match,boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line,match,boost::regex("^([-0-9.e]+).*"))) {//else if (boost::regex_match(line,match,boost::regex("^([0-9]+).*"))) { uint64_t time = std::stoull(match[1]); double time_float = time * std::pow(10, -9); uint32_t time_second = std::floor(time_float); uint32_t time_nsecond = std::round((time_float - time_second)*std::pow(10, 9)); ImageFileFrame *grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp.S = time_second; grey_frame->Timestamp.Ns = time_nsecond; std::stringstream frame_name; frame_name << dirname << "/rgb/" << frame_no << ".png"; grey_frame->filename = frame_name.str(); if(access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No GREY image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(grey_frame); frame_no++; } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } std::cerr << "Checked GREY frames:" << frame_no << std::endl; return true; } bool loadICLGroundTruthData(const std::string &dirname , SLAMFile &file) { GroundTruthSensor *gt_sensor = new GroundTruthSensor("GroundTruth"); gt_sensor->Index = file.Sensors.size(); gt_sensor->Description = "GroundTruthSensor"; gt_sensor->Rate = 1; file.Sensors.AddSensor(gt_sensor); if(!gt_sensor) { std::cout << "gt sensor not found..." << std::endl; return false; } else { std::cout << "gt sensor created..." << std::endl; } std::string cam_name = ""; std::string trajectory_name = ""; std::string light_name = ""; std::string time_name = ""; std::string root_name = ""; std::string directory_head = ""; std::size_t found = dirname.find_last_of("/"); if (found == dirname.length()-1) // the dirname ends with / { } else { cam_name = dirname.substr(found+1, 10); std::size_t found2 = dirname.rfind("/", found-1); std::size_t found3 = dirname.rfind("/", found2-1); std::size_t found4 = dirname.rfind("/", found3-1); std::size_t found5 = dirname.rfind("/", found4-1); trajectory_name = dirname.substr(found2+1,found-found2-1); light_name = dirname.substr(found3+1,found2-found3-1); time_name = dirname.substr(found4+1,found3-found4-1); root_name = dirname.substr(found5+1,found4-found5-1); directory_head = dirname.substr(0,found5); } std::string line; boost::smatch match; std::ifstream infile(directory_head + "/" + root_name + "/trajectories/" + trajectory_name + "/" + cam_name + "/cam0_gt.visim"); int frame_no = 0; while (std::getline(infile, line)){ if (line.size() == 0) { continue; } else if (boost::regex_match(line,match,boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line,match,boost::regex("^([0-9]+),+([-0-9.e]+),+([-0-9.e]+),+([-0-9.e]+),+([-0-9.e]+),+([-0-9.e]+),+([-0-9.e]+),+([-0-9.e]+).*"))) { float tx = std::stof(match[2]); float ty = std::stof(match[3]); float tz = std::stof(match[4]); float QW = std::stof(match[5]); float QX = std::stof(match[6]); float QY = std::stof(match[7]); float QZ = std::stof(match[8]); //std::cout << timestampNS << " " << tx << " " << ty << " " << tz << " " << QW << " " << QX << " " << QY << " " << QZ << std::endl; Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW,QZ,QX,QY).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); //pose.block(0,0,3,3) = rotationMat; //pose.block(0,3,3,1) << tx , ty , tz; // convert to Povray here // modify translation/orientation pose(0,0) = rotationMat(0,0); pose(0,1) = rotationMat(0,1); pose(0,2) = rotationMat(0,2); pose(0,3) = tx; pose(1,0) = rotationMat(1,0); pose(1,1) = rotationMat(1,1); pose(1,2) = rotationMat(1,2); pose(1,3) = ty; pose(2,0) = rotationMat(2,0); pose(2,1) = rotationMat(2,1); pose(2,2) = rotationMat(2,2); pose(2,3) = tz; pose(3,0) = 0.0; pose(3,1) = 0.0; pose(3,2) = 0.0; pose(3,3) = 1.0; Sensor::pose_t pose_temp = Eigen::Matrix4f::Identity(); pose_temp << 1, 0 , 0 , 0, 0, 1, 0, 0, 0, 0, 1, 0, 0, 0, 0, 1; /*pose.block<2,3>(0,0) = -pose.block<2,3>(0,0); Sensor::pose_t pose_temp = Eigen::Matrix4f::Identity(); pose_temp << 1, 0 , 0 , 0, 0, 0, -1, 0, 0, 1, 0, 0, 0, 0, 0, 1;*/ pose = pose * pose_temp; uint64_t time = std::stoull(match[1]); double time_float = time * std::pow(10, -9); uint32_t time_second = std::floor(time_float); uint32_t time_nsecond = std::round((time_float - time_second)*std::pow(10, 9)); //std::cout<< std::fixed << time << " " << time_second << " " << time_nsecond << " " << (time_float - time_second)*std::pow(10, 9) << std::endl; SLAMInMemoryFrame *gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Data = malloc(gt_frame->GetSize()); gt_frame->Timestamp.S = time_second; gt_frame->Timestamp.Ns = time_nsecond; memcpy(gt_frame->Data,pose.data(),gt_frame->GetSize()); //FillPose(frame_name.str(), *((GroundTruthSensor::pose_t*)gt_frame->Data)); file.AddFrame(gt_frame); frame_no++; } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } std::cerr << "Checked GT frames:" << frame_no << std::endl; return true; } bool loadICLAccelerometerData(const std::string &dirname , SLAMFile &file) { AccelerometerSensor *accelerometer_sensor = new AccelerometerSensor("Accelerometer"); accelerometer_sensor->Index = file.Sensors.size(); accelerometer_sensor->Rate = 1; accelerometer_sensor->Description = "AccelerometerSensor"; file.Sensors.AddSensor(accelerometer_sensor); if(!accelerometer_sensor) { std::cout << "accelerometer_sensor not found..." << std::endl; return false; }else { std::cout << "accelerometer_sensor created..." << std::endl; } std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "accelerometer.txt"); while (std::getline(infile, line)){ if (line.size() == 0) { continue; } else if (boost::regex_match(line,match,boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line,match,boost::regex("^([0-9]+)[.]([0-9]+)\\s+([-0-9.]+)\\s+([-0-9.]+)\\s+([-0-9.]+)$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow ( 10, 9 - match[2].length()); float ax = std::stof(match[3]); float ay = std::stof(match[4]); float az = std::stof(match[5]); SLAMInMemoryFrame *accelerometer_frame = new SLAMInMemoryFrame(); accelerometer_frame->FrameSensor = accelerometer_sensor; accelerometer_frame->Timestamp.S = timestampS; accelerometer_frame->Timestamp.Ns = timestampNS; accelerometer_frame->Data = malloc(accelerometer_frame->GetSize()); ((float*)accelerometer_frame->Data)[0] = ax; ((float*)accelerometer_frame->Data)[1] = ay; ((float*)accelerometer_frame->Data)[2] = az; file.AddFrame(accelerometer_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } void frame_callback(int idx, int total) { printf("\r"); // print progress bar printf("["); const int width = 50; float blocks = width * ((float)idx / total); for(int i = 0; i < blocks; ++i) { printf("#"); } for(int i = blocks; i < width; ++i) { printf(" "); } printf("] "); printf("%u / %u", idx, total); fflush(stdout); } bool Serialise(const std::string &filename, SLAMFile &file) { return SLAMFile::Write(filename, file, frame_callback); } SLAMFile* ICLReader::GenerateSLAMFile () { if(!(grey || rgb || depth)) { std::cerr << "No sensors defined\n"; return nullptr; } std::string dirname = input; if (!analyseIclFolder(dirname)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } SLAMFile * slamfilep = new SLAMFile(); SLAMFile & slamfile = *slamfilep; /** * init SLAMFile */ Sensor::pose_t pose = Eigen::Matrix4f::Identity(); ////// Default are freiburg1 CameraSensor::intrinsics_t intrinsics; DepthSensor::intrinsics_t intrinsics_depth; for (int i = 0; i < 4; i++) { intrinsics[i] = fr1_intrinsics_rgb[i]; intrinsics_depth[i] = fr1_intrinsics_depth[i]; } DepthSensor::disparity_params_t disparity_params = {0.005,0.0}; DepthSensor::disparity_type_t disparity_type = DepthSensor::affine_disparity; /** * load Depth */ if(gt && depth && !loadICLDepthData(dirname, slamfile,pose,intrinsics_depth,disparity_params,disparity_type)) { std::cout << "Error while loading depth information." << std::endl; delete slamfilep; return nullptr; } /** * load Grey */ if(grey && !loadICLGreyData(dirname, slamfile,pose,intrinsics)) { std::cout << "Error while loading Grey information." << std::endl; delete slamfilep; return nullptr; } /** * load RGB */ if(gt && rgb && !loadICLRGBData(dirname, slamfile,pose,intrinsics)) { std::cout << "Error while loading RGB information." << std::endl; delete slamfilep; return nullptr; } /** * load GT */ if(gt && !loadICLGroundTruthData(dirname, slamfile)) { std::cout << "Error while loading gt information." << std::endl; delete slamfilep; return nullptr; } /** * load Accelerometer: This one failed */ if(accelerometer && !loadICLAccelerometerData(dirname, slamfile)) { std::cout << "Error while loading Accelerometer information." << std::endl; delete slamfilep; return nullptr; } return slamfilep; } ================================================ FILE: framework/tools/dataset-tools/ICLNUIM.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/ICLNUIM.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; constexpr DepthSensor::disparity_params_t ICLNUIMReader::disparity_params; constexpr DepthSensor::disparity_type_t ICLNUIMReader::disparity_type; struct float3 { float x, y, z; }; void ICLNUIMReader::AddSensors(SLAMFile &file) { // TODO This information should come from the dataset !! Sensor::pose_t pose_depth = Eigen::Matrix4f::Identity(); Sensor::pose_t pose = Eigen::Matrix4f::Identity(); CameraSensor::intrinsics_t intrinsics{0.751875, -1.0, 0.4992185, 0.4989583}; if (this->positive_focal) intrinsics[1] = 1.0; // TODO : This is actually -1, bug .. no. CameraSensor::intrinsics_t intrinsics_depth{0.751875, -1.0, 0.4992185, 0.4989583}; if (this->positive_focal) intrinsics_depth[1] = 1.0; // TODO : This is actually -1, bug .. no. if (this->rgb) { this->rgb_sensor = RGBSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .pose(pose) .intrinsics(intrinsics) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(this->rgb_sensor); } if (this->depth) { this->depth_sensor = DepthSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .disparity(disparity_type, disparity_params) .pose(pose_depth) .intrinsics(intrinsics_depth) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(this->depth_sensor); } if (this->grey) { this->grey_sensor = GreySensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .pose(pose) .intrinsics(intrinsics) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(this->grey_sensor); } if (this->gt) { this->gt_sensor = GTSensorBuilder() .rate(image_params.rate) .pose(pose) .build(); this->gt_sensor->Index = file.Sensors.size(); file.Sensors.AddSensor(this->gt_sensor); } } static void undistort_frame(slambench::io::SLAMFileFrame *frame, void *data) { auto depthMap = (uint16_t *)data; uint32_t w = dynamic_cast(frame->FrameSensor)->Width; uint32_t h = dynamic_cast(frame->FrameSensor)->Height; float u0 = 319.50; float v0 = 239.50; float fx = 481.20; float fy = -480.00; for (uint32_t v = 0; v < h; v++) { for (uint32_t u = 0; u < w; u++) { double u_u0_by_fx = (u - u0) / fx; double v_v0_by_fy = (v - v0) / fy; depthMap[u + v * w] = depthMap[u + v * w] / std::sqrt(u_u0_by_fx * u_u0_by_fx + v_v0_by_fy * v_v0_by_fy + 1); } } } static float3 normalise(const float3 &input) { float3 output = input; float magnitude = std::abs(std::sqrt((output.x * output.x) + (output.y * output.y) + (output.z * output.z))); if (output.x != 0) output.x /= magnitude; if (output.y != 0) output.y /= magnitude; if (output.z != 0) output.z /= magnitude; return output; } // Function to print matrix values existed in commit d2c324d and earlier //void printMat(const Eigen::Matrix4f &mat, const std::string& color = "\033[0m"); bool FillPose(std::ifstream &istream, GroundTruthSensor::pose_t &pose, bool positive_focal) { const std::string& start = RegexPattern::start; const std::string& lkey = RegexPattern::lowercase_key; std::string key_expr = start + lkey; boost::regex key_regex(key_expr); const std::string& value = "([-+]?[0-9]*\\.?[0-9]+([eE][-+]?[0-9]+)?)"; std::string value_expr = value + ", " + value + ", " + value; boost::regex value_regex(value_expr); // find the important features for calculating the pose std::map kvs; std::string line; while(std::getline(istream, line)) { boost::cmatch match; if(!boost::regex_search(line.c_str(), match, key_regex)) { continue; } std::string key = match.str(0); if(!boost::regex_search(line.c_str(), match, value_regex)) { if (key != "cam_angle") { std::cout << "Error reading this line :" << line << std::endl; exit(1); } continue; } kvs[key].x = strtof(match.str(1).c_str(), nullptr); kvs[key].y = strtof(match.str(3).c_str(), nullptr); kvs[key].z = strtof(match.str(5).c_str(), nullptr); } // row 3 float3 los = normalise(kvs["cam_dir"]); float3 up = normalise(kvs["cam_up"]); float3 right = normalise(kvs["cam_right"]); pose(0, 0) = right.x; pose(0, 1) = right.y; pose(0, 2) = right.z; pose(0, 3) = kvs["cam_pos"].x; pose(1, 0) = up.x; pose(1, 1) = up.y; pose(1, 2) = up.z; pose(1, 3) = kvs["cam_pos"].y; pose(2, 0) = los.x; pose(2, 1) = los.y; pose(2, 2) = los.z; pose(2, 3) = kvs["cam_pos"].z; pose(3, 0) = 0.0; pose(3, 1) = 0.0; pose(3, 2) = 0.0; pose(3, 3) = 1.0; if (positive_focal) { // First The ground truth is not align with the point cloud we need to flip pose(0, 3) *= -1.0; // Pos // Second the ground truth is looking to the wrong Z direction static const GroundTruthSensor::pose_t origin = pose; pose = origin.inverse() * pose; pose(0, 2) *= -1.0; // Rot pose(1, 2) *= -1.0; // Rot pose(2, 0) *= -1.0; // Rot pose(2, 1) *= -1.0; // Rot pose = origin * pose; // Finally the camera is upside down ! pose = origin.inverse() * pose; pose.block<2, 3>(0, 0) = -pose.block<2, 3>(0, 0); pose = origin * pose; } istream.close(); return true; } bool GetPoseETHI(std::ifstream &istream, GroundTruthSensor::pose_t &pose) { std::string line; boost::smatch match; const std::string& f_no = RegexPattern::number; const std::string& ws = RegexPattern::whitespace; const std::string& dec = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: frame_no tx ty tz qx qy qz qw std::string expr = start + f_no + ws // frame_no + dec + ws // tx + dec + ws // ty + dec + ws // tz + dec + ws // qx + dec + ws // qy + dec + ws // qz + dec + end; // qw boost::regex groundtruth_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); std::getline(istream, line); if (line.empty()) { return false; } else if (boost::regex_match(line, match, comment)) { return false; } else if (boost::regex_match(line, match, groundtruth_line)) { float tx = std::stof(match[2]); float ty = std::stof(match[3]); float tz = std::stof(match[4]); float QX = std::stof(match[5]); float QY = std::stof(match[6]); float QZ = std::stof(match[7]); float QW = std::stof(match[8]); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; } else { std::cout << "Unknown line:" << line << std::endl; return false; } return true; } bool ICLNUIMReader::GetFrame(const std::string &dirname, SLAMFile &file, int frame_no) { // two frames to add: one for rgb and one for depth const int frame_rate = 25; double frame_time = 1.0 / frame_rate; uint64_t total_ns = frame_time * frame_no * 1000000000; TimeStamp ts; ts.S = total_ns / 1000000000; ts.Ns = total_ns % 1000000000; if (rgb_sensor) { auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = rgb_sensor; rgb_frame->Timestamp = ts; std::stringstream frame_name; frame_name << dirname << "/scene_00_" << std::setw(4) << std::setfill('0') << frame_no << ".png"; rgb_frame->filename = frame_name.str(); if (access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame %d (%s)\n", frame_no, frame_name.str().c_str()); return false; } file.AddFrame(rgb_frame); } if (grey_sensor) { auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = grey_sensor; rgb_frame->Timestamp = ts; std::stringstream frame_name; frame_name << dirname << "/scene_00_" << std::setw(4) << std::setfill('0') << frame_no << ".png"; rgb_frame->filename = frame_name.str(); if (access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No Grey image for frame %d (%s)\n", frame_no, frame_name.str().c_str()); perror(""); return false; } file.AddFrame(rgb_frame); } if (depth_sensor) { SLAMFileFrame* depth_frame; std::stringstream frame_name; frame_name << dirname << "/scene_00_" << std::setw(4) << std::setfill('0') << frame_no << ".depth"; // ETHI sequence if(istream.is_open()) { depth_frame = new ImageFileFrame(); frame_name << ".png"; } else { depth_frame = new TxtFileFrame(); dynamic_cast(depth_frame)->input_pixel_format = pixelformat::D_F_32; depth_frame->ProcessCallback = undistort_frame; } depth_frame->filename = frame_name.str(); depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp = ts; if (access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame %d (%s)\n", frame_no, frame_name.str().c_str()); perror(""); return false; } file.AddFrame(depth_frame); } if (gt_sensor) { auto frame = new SLAMInMemoryFrame(); frame->FrameSensor = gt_sensor; frame->Timestamp = ts; frame->Data = malloc(frame->GetSize()); bzero(frame->Data, frame->GetSize()); if(istream.is_open()) { GetPoseETHI(istream, *((GroundTruthSensor::pose_t *)frame->Data)); } else { std::stringstream frame_name; frame_name << dirname << "/scene_00_" << std::setw(4) << std::setfill('0') << frame_no << ".txt"; if (access(frame_name.str().c_str(), F_OK) < 0) { printf("No metadata for frame %d (%s)\n", frame_no, frame_name.str().c_str()); perror(""); return false; } istream = std::ifstream(frame_name.str()); FillPose(istream, *((GroundTruthSensor::pose_t *)frame->Data), this->positive_focal); } file.AddFrame(frame); } return true; } bool ICLNUIMReader::AddFrames(const std::string &dirname, SLAMFile &file) { int frame_no = 0; auto gt_file = dirname+"/groundtruth.txt"; if(access(gt_file.c_str(), F_OK) >= 0) { istream = std::ifstream(gt_file); } while (GetFrame(dirname, file, frame_no)) { frame_no++; } return true; } void AddPointCloudSensor(SLAMFile &slamfile) { auto pcd = new PointCloudSensor("PointCloud"); pcd->Description = "Ground truth point cloud"; pcd->Index = slamfile.Sensors.size(); slamfile.Sensors.AddSensor(pcd); } void AddPlyFile(SLAMFile &slamfile, const std::string& plyname) { PlyReader plyreader; std::ifstream file(plyname.c_str()); if (!file.good()) { fprintf(stderr, "Could not open PLY file\n"); return; } auto pointcloud = plyreader.Read(file); if (pointcloud == nullptr) { fprintf(stderr, "Could not build point cloud\n"); return; } auto rawpointcloud = pointcloud->ToRaw(); auto pcloudframe = new SLAMInMemoryFrame(); pcloudframe->FrameSensor = slamfile.GetSensor(PointCloudSensor::kPointCloudType); pcloudframe->Data = malloc(rawpointcloud.size()); pcloudframe->SetVariableSize(rawpointcloud.size()); memcpy(pcloudframe->Data, rawpointcloud.data(), rawpointcloud.size()); slamfile.AddFrame(pcloudframe); } SLAMFile *ICLNUIMReader::GenerateSLAMFile() { std::cout << "Selection input file is " << this->input << std::endl; auto slamfile = new SLAMFile(); if (!(grey || rgb || depth || gt)) { std::cout << "No sensor required." << std::endl; delete slamfile; return nullptr; } if (plyfile.length() != 0) { std::cout << "Add point cloud." << std::endl; AddPointCloudSensor(*slamfile); } AddSensors(*slamfile); if (plyfile.length() != 0) { AddPlyFile(*slamfile, plyfile); } if (!AddFrames(input, *slamfile)) { std::cout << "Failed to add frames." << std::endl; delete slamfile; return nullptr; } if(istream.is_open()) istream.close(); return slamfile; } ================================================ FILE: framework/tools/dataset-tools/OpenLORIS.cpp ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #include "include/OpenLORIS.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "io/sensor/sensor_builder.h" #include "utils/dataset_utils.h" using namespace slambench::io; void Dijkstra(int n, int s, std::vector > G, std::vector &vis, std::vector &d, std::vector &pre) { fill(d.begin(), d.end(), INF); for (int i = 0; i < n; ++i) pre[i] = i; d[s] = 0; for (int i = 0; i < n; ++i) { int u = -1; int MIN = INF; for (int j = 0; j < n; ++j) { if (vis[j] == false && d[j] < MIN) { u = j; MIN = d[j]; } } if (u == -1) return; vis[u] = true; for (int v = 0; v < n; ++v) { if (vis[v] == false && d[u] + G[u][v] < d[v]) { d[v] = d[u] + G[u][v]; pre[v] = u; } } } } void DFSPrint(int s, int v, std::vector pre, std::vector &result) { if (v == s) { result.push_back(s); return; } DFSPrint(s, pre[v], pre, result); result.push_back(v); } Eigen::Matrix4f slambench::io::compute_trans_matrix(const std::string& input_name_1, const std::string& input_name_2, const std::string& filename) { auto yaml = YAML::LoadFile(filename); std::map name_to_index; std::map transforms; int num = 0; for (size_t i = 0; i < yaml["trans_matrix"].size(); i++) { int index_1, index_2; std::string name_1 = yaml["trans_matrix"][i]["parent_frame"].as(); if (name_to_index.count(name_1) == 0) { name_to_index[name_1] = num; num++; } std::string name_2 = yaml["trans_matrix"][i]["child_frame"].as(); if (name_to_index.count(name_2) == 0) { name_to_index[name_2] = num; num++; } index_1 = name_to_index[name_1]; index_2 = name_to_index[name_2]; trans_direction dir(index_1, index_2); Eigen::Matrix4f trans_matrix; trans_matrix << yaml["trans_matrix"][i]["matrix"]["data"][0].as(), yaml["trans_matrix"][i]["matrix"]["data"][1].as(), yaml["trans_matrix"][i]["matrix"]["data"][2].as(), yaml["trans_matrix"][i]["matrix"]["data"][3].as(), yaml["trans_matrix"][i]["matrix"]["data"][4].as(), yaml["trans_matrix"][i]["matrix"]["data"][5].as(), yaml["trans_matrix"][i]["matrix"]["data"][6].as(), yaml["trans_matrix"][i]["matrix"]["data"][7].as(), yaml["trans_matrix"][i]["matrix"]["data"][8].as(), yaml["trans_matrix"][i]["matrix"]["data"][9].as(), yaml["trans_matrix"][i]["matrix"]["data"][10].as(), yaml["trans_matrix"][i]["matrix"]["data"][11].as(), yaml["trans_matrix"][i]["matrix"]["data"][12].as(), yaml["trans_matrix"][i]["matrix"]["data"][13].as(), yaml["trans_matrix"][i]["matrix"]["data"][14].as(), yaml["trans_matrix"][i]["matrix"]["data"][15].as(); // problem transforms[dir] = trans_matrix; trans_direction dir_inv(index_2, index_1); transforms[dir_inv] = trans_matrix.inverse(); } int s = name_to_index[input_name_1]; int v = name_to_index[input_name_2]; int n = name_to_index.size(); std::vector > G; std::vector g; for (int j = 0; j < n; j++) { g.push_back(INF); } for (int i = 0; i < n; i++) { G.push_back(g); } for (auto& transform : transforms) { trans_direction index_pair = transform.first; G[index_pair.first][index_pair.second] = 1; } std::vector vis(n); std::vector d(n); std::vector pre(n); Dijkstra(n, s, G, vis, d, pre); std::vector result; DFSPrint(s, v, pre, result); Eigen::Matrix4f result_matrix = Eigen::MatrixXf::Identity(4, 4); for (auto it = result.begin(); it != (result.end() - 1); it++) { trans_direction dir(*it, *(it + 1)); Eigen::Matrix4f trans = transforms[dir]; result_matrix = result_matrix * trans; } // std::cout<(); auto height = yaml[sensor_name]["height"].as(); slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = yaml[sensor_name]["intrinsics"]["data"][0].as() / width; intrinsics[1] = yaml[sensor_name]["intrinsics"]["data"][2].as() / height; intrinsics[2] = yaml[sensor_name]["intrinsics"]["data"][1].as() / width; intrinsics[3] = yaml[sensor_name]["intrinsics"]["data"][3].as() / height; slambench::io::CameraSensor::distortion_coefficients_t distortion; slambench::io::CameraSensor::distortion_type_t distortion_type; if (yaml[sensor_name]["distortion_model"].as() == "radial-tangential") { distortion_type = slambench::io::CameraSensor::RadialTangential; distortion[0] = yaml[sensor_name]["distortion_coefficients"]["data"][0].as(); distortion[1] = yaml[sensor_name]["distortion_coefficients"]["data"][1].as(); distortion[2] = yaml[sensor_name]["distortion_coefficients"]["data"][2].as(); distortion[3] = yaml[sensor_name]["distortion_coefficients"]["data"][3].as(); distortion[4] = 0; //?? } auto depth_sensor = DepthSensorBuilder() .name("Depth") .description("Depth") .rate(yaml[sensor_name]["fps"].as()) .size(width, height) .pose(pose) .intrinsics(intrinsics) .distortion(distortion_type, distortion) .disparity(disparity_type, disparity_params) .index(file.Sensors.size()) .frameFormat(frameformat::Raster) .pixelFormat(pixelformat::D_I_16) .build(); file.Sensors.AddSensor(depth_sensor); std::string line; std::string txt_name; if (aligned_depth) { txt_name = "aligned_depth.txt"; } else { txt_name = "depth.txt"; } std::ifstream infile(dirname + "/" + txt_name); boost::smatch match; while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+(.*)$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string depthfilename = match[3]; auto depth_frame = new ImageFileFrame(); depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp.S = timestampS; depth_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << depthfilename; depth_frame->filename = frame_name.str(); if (access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(depth_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadOpenLORISImageData(const std::string &dirname, // directory of data const std::string &name_in_yaml, // sensor name in sensors.yaml const std::string &index_filename, // filename of the data index (.txt) bool greyscale, SLAMFile &file, const std::string &out_sensor_name, // name in .slam, should be identical const YAML::Node yaml) { slambench::io::CameraSensor::distortion_type_t distortion_type; if (yaml[name_in_yaml]["distortion_model"].as() == "radial-tangential") { distortion_type = slambench::io::CameraSensor::RadialTangential; } else if (yaml[name_in_yaml]["distortion_model"].as() == "Kannala-Brandt") { distortion_type = slambench::io::CameraSensor::KannalaBrandt; } auto pose = compute_trans_matrix("d400_color_optical_frame", name_in_yaml, dirname + "/trans_matrix.yaml"); auto width = yaml[name_in_yaml]["width"].as(); auto height = yaml[name_in_yaml]["height"].as(); slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = yaml[name_in_yaml]["intrinsics"]["data"][0].as() / width; intrinsics[1] = yaml[name_in_yaml]["intrinsics"]["data"][2].as() / height; intrinsics[2] = yaml[name_in_yaml]["intrinsics"]["data"][1].as() / width; intrinsics[3] = yaml[name_in_yaml]["intrinsics"]["data"][3].as() / height; slambench::io::CameraSensor::distortion_coefficients_t distortion; distortion[0] = yaml[name_in_yaml]["distortion_coefficients"]["data"][0].as(); distortion[1] = yaml[name_in_yaml]["distortion_coefficients"]["data"][1].as(); distortion[2] = yaml[name_in_yaml]["distortion_coefficients"]["data"][2].as(); distortion[3] = yaml[name_in_yaml]["distortion_coefficients"]["data"][3].as(); distortion[4] = 0; auto sensor = CameraSensorBuilder() .name(out_sensor_name) .description(greyscale ? "Grey" : "RGB") .rate(yaml[name_in_yaml]["fps"].as()) .size(width, height) .pose(pose) .intrinsics(intrinsics) .distortion(distortion_type, distortion) .frameFormat(frameformat::Raster) .pixelFormat(greyscale ? pixelformat::G_I_8 : pixelformat::RGB_III_888) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(sensor); std::string line; std::ifstream infile(dirname + "/" + index_filename); boost::smatch match; while (std::getline(infile, line)) { if (line.size() == 0) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+(.*)$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string rgbfilename = match[3]; auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = sensor; grey_frame->Timestamp.S = timestampS; grey_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << rgbfilename; grey_frame->filename = frame_name.str(); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(grey_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadOpenLORISGroundTruthData(const std::string &dirname, SLAMFile &file) { auto gt_sensor = GTSensorBuilder() .name("GroundTruth") .description("GroundTruthSensor") .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(gt_sensor); // The target frame of gt in OpenLORIS is base_link. We change it here to d400_color, because most algorithms // would report estimated poses of d400_color (I guess). Though the transformation_ between the estimate target // frame and gt traget frame SHOULD be considered in traj alignment / evaluation / visualization, it is not. Eigen::Matrix4f trans_mat = compute_trans_matrix("d400_color_optical_frame", "base_link", dirname + "/trans_matrix.yaml"); std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "groundtruth.txt"); while (std::getline(infile, line)) { if (line.size() == 0) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match( line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]" "+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)" "\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?" ")[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]" "+([Ee]([+-]?)[0-9]+)?)?)\\s*$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); float tx = std::stof(match[3]); float ty = std::stof(match[7]); float tz = std::stof(match[11]); float QX = std::stof(match[15]); float QY = std::stof(match[19]); float QZ = std::stof(match[23]); float QW = std::stof(match[27]); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; pose = pose * trans_mat; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp.S = timestampS; gt_frame->Timestamp.Ns = timestampNS; gt_frame->Data = malloc(gt_frame->GetSize()); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadOpenLORISAccelerometerData(const std::string &dirname, const std::string &sensor_name, SLAMFile &file, const YAML::Node& yaml) { auto accelerometer_sensor = AccSensorBuilder() .name(sensor_name) .rate(yaml[sensor_name]["fps"].as()) .description("AccelerometerSensor") .index(file.Sensors.size()) .pose(compute_trans_matrix("d400_color_optical_frame", sensor_name, dirname + "/trans_matrix.yaml")) .build(); // accelerometer_sensor->AcceleratorNoiseDensity = 2.0000e-3; // accelerometer_sensor->AcceleratorDriftNoiseDensity = 4.0e-5; // accelerometer_sensor->AcceleratorBiasDiffusion = 3.0000e-3; // accelerometer_sensor->AcceleratorSaturation = 176.0; for (int i = 0; i < 12; i++) { accelerometer_sensor->Intrinsic[i] = yaml[sensor_name]["imu_intrinsic"]["data"][i].as(); } for (int i = 0; i < 3; i++) { accelerometer_sensor->NoiseVariances[i] = yaml[sensor_name]["noise_variances"]["data"][i].as(); accelerometer_sensor->BiasVariances[i] = yaml[sensor_name]["bias_variances"]["data"][i].as(); } file.Sensors.AddSensor(accelerometer_sensor); std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + sensor_name + ".txt"); while (std::getline(infile, line)) { if (line.size() == 0) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)" "\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[" "0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s*$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); auto accelerometer_frame = new SLAMInMemoryFrame(); accelerometer_frame->FrameSensor = accelerometer_sensor; accelerometer_frame->Timestamp.S = timestampS; accelerometer_frame->Timestamp.Ns = timestampNS; accelerometer_frame->Data = malloc(accelerometer_frame->GetSize()); ((float *)accelerometer_frame->Data)[0] = std::stof(match[3]); // ax ((float *)accelerometer_frame->Data)[1] = std::stof(match[7]); // ay ((float *)accelerometer_frame->Data)[2] = std::stof(match[11]); // az file.AddFrame(accelerometer_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadOpenLORISGyroData(const std::string &dirname, const std::string &sensor_name, SLAMFile &file, const YAML::Node& yaml) { auto gyro_sensor = GyroSensorBuilder() .name(sensor_name) .rate(yaml[sensor_name]["fps"].as()) .description("GyroSensor") .index(file.Sensors.size()) .pose(compute_trans_matrix("d400_color_optical_frame", sensor_name, dirname + "/trans_matrix.yaml")) .build(); // gyro_sensor->GyroscopeNoiseDensity = 1.6968e-04; // gyro_sensor->GyroscopeDriftNoiseDensity = 4.0e-6; // gyro_sensor->GyroscopeBiasDiffusion = 1.9393e-05; // gyro_sensor->GyroscopeSaturation = 7.8; for (int i = 0; i < 12; i++) { gyro_sensor->Intrinsic[i] = yaml[sensor_name]["imu_intrinsic"]["data"][i].as(); } for (int i = 0; i < 3; i++) { gyro_sensor->NoiseVariances[i] = yaml[sensor_name]["noise_variances"]["data"][i].as(); gyro_sensor->BiasVariances[i] = yaml[sensor_name]["bias_variances"]["data"][i].as(); } file.Sensors.AddSensor(gyro_sensor); std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + sensor_name + ".txt"); while (std::getline(infile, line)) { if (line.size() == 0) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match(line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)" "\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[" "0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s*$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); auto gyro_frame = new SLAMInMemoryFrame(); gyro_frame->FrameSensor = gyro_sensor; gyro_frame->Timestamp.S = timestampS; gyro_frame->Timestamp.Ns = timestampNS; gyro_frame->Data = malloc(gyro_frame->GetSize()); ((float *)gyro_frame->Data)[0] = std::stof(match[3]); // wx ((float *)gyro_frame->Data)[1] = std::stof(match[7]); // wy ((float *)gyro_frame->Data)[2] = std::stof( match[11]); // wz file.AddFrame(gyro_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadOpenLORISOdomData(const std::string &dirname, const std::string &sensor_name, SLAMFile &file) { auto odom_sensor = OdomSensorBuilder() .name(sensor_name) .description("OdomSensor") .index(file.Sensors.size()) .pose(Eigen::Matrix4f::Identity()) .build(); file.Sensors.AddSensor(odom_sensor); std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "odom.txt"); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, boost::regex("^\\s*#.*$"))) { continue; } else if (boost::regex_match( line, match, boost::regex("^([0-9]+)[.]([0-9]+)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]" "+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)" "\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?" ")[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]" "+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[" "0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?" ")\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]" "?)[0-9]+)?)?)\\s+([+-]?[0-9]+(.[0-9]+([Ee]([+-]?)[0-9]+)?)?)\\s*$"))) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); auto odom_frame = new SLAMInMemoryFrame(); odom_frame->FrameSensor = odom_sensor; odom_frame->Timestamp.S = timestampS; odom_frame->Timestamp.Ns = timestampNS; odom_frame->Data = malloc(odom_frame->GetSize()); ((float *)odom_frame->Data)[0] = std::stof(match[3]); // px ((float *)odom_frame->Data)[1] = std::stof(match[7]); // py ((float *)odom_frame->Data)[2] = std::stof(match[11]); // pz ((float *)odom_frame->Data)[3] = std::stof(match[15]); // ox ((float *)odom_frame->Data)[4] = std::stof(match[19]); // oy ((float *)odom_frame->Data)[5] = std::stof(match[23]); // oz ((float *)odom_frame->Data)[6] = std::stof(match[27]); // ow ((float *)odom_frame->Data)[7] = std::stof(match[31]); // lx ((float *)odom_frame->Data)[8] = std::stof(match[35]); // ly ((float *)odom_frame->Data)[9] = std::stof(match[39]); // lz ((float *)odom_frame->Data)[10] = std::stof(match[43]); // ax ((float *)odom_frame->Data)[11] = std::stof(match[47]); // ay ((float *)odom_frame->Data)[12] = std::stof(match[51]); // az file.AddFrame(odom_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } SLAMFile *OpenLORISReader::GenerateSLAMFile() { if (!(grey || color || depth || aligned_depth || fisheye1 || fisheye2)) { std::cerr << "No sensors defined\n"; return nullptr; } std::string dirname = input; static const std::vector requirements = {"d400_accelerometer.txt", "d400_gyroscope.txt", "t265_accelerometer.txt", "t265_gyroscope.txt", "odom.txt", "color.txt", "color", "depth.txt", "depth", "aligned_depth.txt", "aligned_depth", "fisheye1.txt", "fisheye1", "fisheye2.txt", "fisheye2", "groundtruth.txt", "sensors.yaml", "trans_matrix.yaml"}; if (!checkRequirements(dirname, requirements)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } auto slamfilep = new SLAMFile(); SLAMFile &slamfile = *slamfilep; DepthSensor::disparity_params_t disparity_params = {0.001, 0.0}; DepthSensor::disparity_type_t disparity_type = DepthSensor::affine_disparity; auto yaml = YAML::LoadFile(dirname + "/sensors.yaml"); /*** load RGB ***/ if (color && !loadOpenLORISImageData(dirname, "d400_color_optical_frame", "color.txt", false, slamfile,"RGB", yaml)) { std::cout << "Error while loading OpenLORIS RGB information." << std::endl; delete slamfilep; return nullptr; } /*** load Grey ***/ if (grey && !loadOpenLORISImageData(dirname, "d400_color_optical_frame", "color.txt", true, slamfile, "Grey", yaml)) { std::cout << "Error while loading OpenLORIS Grey information." << std::endl; delete slamfilep; return nullptr; } /*** load Aligned_Depth ***/ if (aligned_depth && !loadOpenLORISDepthData(dirname, "d400_color_optical_frame", slamfile, disparity_params, disparity_type, yaml, true)) { std::cout << "Error while loading OpenLORIS depth information." << std::endl; delete slamfilep; return nullptr; } /*** load Depth ***/ if (depth && !loadOpenLORISDepthData(dirname, "d400_depth_optical_frame", slamfile, disparity_params, disparity_type, yaml)) { std::cout << "Error while loading OpenLORIS depth information." << std::endl; delete slamfilep; return nullptr; } /*** load Intel Realsense D400 Accelerometer ***/ if (d400_accel && !loadOpenLORISAccelerometerData(dirname, "d400_accelerometer", slamfile, yaml)) { std::cout << "Error while loading Accelerometer information." << std::endl; delete slamfilep; return nullptr; } /*** load Intel Realsense D400 Gyro ***/ if (d400_gyro && !loadOpenLORISGyroData(dirname, "d400_gyroscope",slamfile, yaml)) { std::cout << "Error while loading Gyro information." << std::endl; delete slamfilep; return nullptr; } /*** load Intel Realsense T265 Fisheye cameras ***/ if (fisheye1 && !loadOpenLORISImageData(dirname, "t265_fisheye1_optical_frame", "fisheye1.txt", true, slamfile, "t265_fisheye1", yaml)) { std::cout << "Error while loading OpenLORIS fisheye1 information." << std::endl; delete slamfilep; return nullptr; } if (fisheye2 && !loadOpenLORISImageData(dirname, "t265_fisheye2_optical_frame", "fisheye2.txt", true, slamfile, "t265_fisheye2", yaml)) { std::cout << "Error while loading OpenLORIS fisheye2 information." << std::endl; delete slamfilep; return nullptr; } /*** load Intel Realsense T265 accelerometer ***/ if (t265_accel && !loadOpenLORISAccelerometerData(dirname, "t265_accelerometer", slamfile, yaml)) { std::cout << "Error while loading Accelerometer information." << std::endl; delete slamfilep; return nullptr; } /*** load Intel Realsense T265 accelerometer ***/ if (t265_gyro && !loadOpenLORISGyroData(dirname, "t265_gyroscope",slamfile, yaml)) { std::cout << "Error while loading Gyro information." << std::endl; delete slamfilep; return nullptr; } /*** load wheel odometry ***/ if (odom && !loadOpenLORISOdomData(dirname, "odometer", slamfile)) { std::cout << "Error while loading Odom information." << std::endl; delete slamfilep; return nullptr; } /*** load GT ***/ if (gt && !loadOpenLORISGroundTruthData(dirname, slamfile)) { std::cout << "Error while loading gt information." << std::endl; delete slamfilep; return nullptr; } return slamfilep; } ================================================ FILE: framework/tools/dataset-tools/SVO.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/SVO.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; constexpr CameraSensor::intrinsics_t SVOReader::svo_grey; constexpr float SVOReader::translation[]; constexpr float SVOReader::rotation[]; bool loadSVOGreyData(const std::string &dirname, SLAMFile &file, CameraSensor* grey_sensor) { for (int frame_no = 2; frame_no < 188; frame_no++) { auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp.S = frame_no - 2; std::stringstream frame_name; frame_name << dirname << "/img/frame_" << std::setw(6) << std::setfill('0') << frame_no << "_0.png"; grey_frame->filename = frame_name.str(); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No grey image for frame %d (%s)\n", frame_no, frame_name.str().c_str()); return false; } file.AddFrame(grey_frame); } return true; } bool loadSVOGroundTruthData(const std::string &dirname, SLAMFile &file, GroundTruthSensor* gt_sensor) { std::string line; std::vector results; std::ifstream infile(dirname + "/" + "trajectory_nominal.txt"); int timestampS = 0; while (std::getline(infile, line)) { if (line.empty()) continue; boost::split(results, line, boost::is_any_of(" ")); // int timestampS = std::stoi(results[0]); float tx = std::stof(results[1]); float ty = std::stof(results[2]); float tz = std::stof(results[3]); float QX = std::stof(results[4]); float QY = std::stof(results[5]); float QZ = std::stof(results[6]); float QW = std::stof(results[7]); // the raw ground truth data are not normalized, we need normalized quaternions float Q_length = std::sqrt(std::pow(QX, 2) + std::pow(QY, 2) + std::pow(QZ, 2) + std::pow(QW, 2)); QX /= Q_length; QY /= Q_length; QZ /= Q_length; QW /= Q_length; Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp.S = timestampS++; gt_frame->Data = malloc(gt_frame->GetSize()); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } return true; } SLAMFile *SVOReader::GenerateSLAMFile() { std::string dirname = input; auto slamfile_ptr = new SLAMFile(); auto &slamfile = *slamfile_ptr; Sensor::pose_t pose = Eigen::Matrix4f::Identity(); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(rotation[0], rotation[1], rotation[2], rotation[3]) .toRotationMatrix(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << translation[0], translation[1], translation[2]; // load Grey auto grey_sensor = GreySensorBuilder() .name("Grey") .size(752, 480) .description("Grey") .pose(pose) .intrinsics(svo_grey) .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(grey_sensor); if (!loadSVOGreyData(dirname, slamfile, grey_sensor)) { std::cout << "Error while loading Grey information." << std::endl; delete slamfile_ptr; return nullptr; } // load GT auto gt_sensor = GTSensorBuilder() .name("GT") .description("GroundTruthSensor") .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(gt_sensor); if (!loadSVOGroundTruthData(dirname, slamfile, gt_sensor)) { std::cout << "Error while loading gt information." << std::endl; delete slamfile_ptr; return nullptr; } return slamfile_ptr; } ================================================ FILE: framework/tools/dataset-tools/TUM-ROSBAG.cpp ================================================ /* Copyright (c) 2017-2020 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 The development of the interface with ROS datasets (rosbags) is supported by the RAIN Hub, which is funded by the Industrial Strategy Challenge Fund, part of the UK government’s modern Industrial Strategy. The fund is delivered by UK Research and Innovation and managed by EPSRC [EP/R026084/1]. This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include "TUM.h" using namespace slambench::io ; bool loadTUMROSBAG_DepthData(const std::string & dirname, const std::string & bagname, const std::string & topic, SLAMFile & file, const Sensor::pose_t & pose, const TUMROSBAGReader::image_params_t & image_params, const DepthSensor::intrinsics_t & intrinsics, const CameraSensor::distortion_coefficients_t & distortion, const CameraSensor::distortion_type_t & distortion_type, const DepthSensor::disparity_params_t & disparity_params, const DepthSensor::disparity_type_t & disparity_type) { // allocate new sensor auto *depth_sensor = new DepthSensor("Depth"); if (depth_sensor == nullptr) { std::cerr << "error allocating depth sensor" << std::endl; return false; } std::cout << "depth sensor created" << std::endl; // populate sensor data depth_sensor->Index = file.Sensors.size(); depth_sensor->Width = image_params.width; depth_sensor->Height = image_params.height; depth_sensor->FrameFormat = frameformat::Raster; depth_sensor->PixelFormat = pixelformat::D_I_16; depth_sensor->DisparityType = disparity_type; depth_sensor->Description = "Depth"; depth_sensor->CopyPose(pose); depth_sensor->CopyIntrinsics(intrinsics); depth_sensor->CopyDisparityParams(disparity_params); depth_sensor->DistortionType = distortion_type; depth_sensor->CopyRadialTangentialDistortion(distortion); depth_sensor->Rate = image_params.rate; file.Sensors.AddSensor(depth_sensor); // create directory for depth images std::string depthdir = dirname + "/depth/"; if (!boost::filesystem::exists(depthdir)) { if (!boost::filesystem::create_directory(depthdir)) { std::cerr << "error creating depth directory: " << depthdir << std::endl; delete depth_sensor; return false; } } // open rosbag file rosbag::Bag bag; try { bag.open(bagname,rosbag::bagmode::Read); } catch (...) { std::cerr << "error opening depth rosbag: " << bagname << std::endl; delete depth_sensor; return false; } // create query to fetch depth topic messages rosbag::View view(bag, rosbag::TopicQuery(topic)); // produce png image for every depth message for (const auto& msg : view) { sensor_msgs::Image::ConstPtr imgi = msg.instantiate(); if (imgi == nullptr) { continue; } cv::Mat imgo = cv::Mat(imgi->height, imgi->width, CV_32FC1, const_cast(&imgi->data[0]), imgi->step); cv::Mat image = cv::Mat(imgi->height, imgi->width, CV_16UC1); for (uint r = 0; r < imgi->height; r++) { for (uint c = 0; c < imgi->width; c++) { float dist = imgo.at(r * imgi->width + c); auto dist16 = (ushort) (image_params.depthMapFactor * dist); image.at(r, c) = dist16; } } std::stringstream frame_name; frame_name << depthdir; frame_name << imgi->header.stamp.sec << "." << imgi->header.stamp.nsec << ".png"; if (!cv::imwrite(frame_name.str(), image)) { std::cerr << "error writing depth image: " << frame_name.str() << std::endl; delete depth_sensor; return false; } // allocate new depth frame auto *depth_frame = new ImageFileFrame(); if (depth_frame == nullptr) { std::cerr << "error creating depth frame" << std::endl; delete depth_sensor; return false; } // populate frame and update slambench file depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp.S = imgi->header.stamp.sec; depth_frame->Timestamp.Ns = imgi->header.stamp.nsec; depth_frame->filename = frame_name.str(); file.AddFrame(depth_frame); } bag.close(); return true; } bool loadTUMROSBAG_RGBGreyData( bool doRGB, bool doGrey, const std::string & dirname, const std::string & bagname, const std::string & topic, SLAMFile & file, const Sensor::pose_t & pose, const TUMROSBAGReader::image_params_t & image_params, const CameraSensor::intrinsics_t & intrinsics, const CameraSensor::distortion_coefficients_t & distortion, const CameraSensor::distortion_type_t & distortion_type) { auto *rgb_sensor = new CameraSensor("RGB", CameraSensor::kCameraType); if (rgb_sensor == nullptr) { std::cerr << "error allocating rgb sensor" << std::endl; return false; } std::cout << "rgb sensor created" << std::endl; auto *grey_sensor = new CameraSensor("Grey", CameraSensor::kCameraType); if (grey_sensor == nullptr) { std::cerr << "error allocating grey sensor" << std::endl; delete rgb_sensor; return false; } std::cout << "grey sensor created" << std::endl; // populate rgb sensor data if (doRGB) { rgb_sensor->Index = file.Sensors.size(); rgb_sensor->Width = image_params.width; rgb_sensor->Height = image_params.height; rgb_sensor->FrameFormat = frameformat::Raster; rgb_sensor->PixelFormat = pixelformat::RGB_III_888; rgb_sensor->Description = "RGB"; rgb_sensor->CopyPose(pose); rgb_sensor->CopyIntrinsics(intrinsics); rgb_sensor->DistortionType = distortion_type; rgb_sensor->CopyRadialTangentialDistortion(distortion); rgb_sensor->Rate = image_params.rate; file.Sensors.AddSensor(rgb_sensor); } // populate grey sensor data if (doGrey) { grey_sensor->Index = file.Sensors.size(); grey_sensor->Width = image_params.width; grey_sensor->Height = image_params.height; grey_sensor->FrameFormat = frameformat::Raster; grey_sensor->PixelFormat = pixelformat::G_I_8; grey_sensor->Description = "Grey"; grey_sensor->CopyPose(pose); grey_sensor->CopyIntrinsics(intrinsics); grey_sensor->CopyRadialTangentialDistortion(distortion); grey_sensor->DistortionType = distortion_type; grey_sensor->Rate = image_params.rate; file.Sensors.AddSensor(grey_sensor); } // create directory for rgb images std::string rgbdir = dirname + "/rgb/"; if (!boost::filesystem::exists(rgbdir)) { if (!boost::filesystem::create_directory(rgbdir)) { std::cerr << "error creating rgb directory: " << rgbdir << std::endl; delete rgb_sensor; delete grey_sensor; return false; } } // open rosbag file rosbag::Bag bag; try { bag.open(bagname, rosbag::bagmode::Read); } catch (...) { std::cerr << "error opening rgb rosbag: " << bagname << std::endl; delete rgb_sensor; delete grey_sensor; return false; } // create query to fetch rgb images topic messages // NOTE: TUM rosbag files do not contain grey images - use rgb ones! rosbag::View view(bag, rosbag::TopicQuery(topic)); // produce png image for every rgb message for (const auto& msg : view) { sensor_msgs::Image::ConstPtr imgi = msg.instantiate(); if (imgi == nullptr) { continue; } cv::Mat imgo = cv::Mat(imgi->height, imgi->width, CV_8UC3, const_cast(&imgi->data[0]), imgi->step); cv::Mat image = cv::Mat(imgi->height, imgi->width, CV_8UC3); for (uint r = 0; r < imgi->height; r++) { for (uint c = 0; c < imgi->width; c++) { // NOTE: OpenCV defaults to BGR8 encoding! image.at(r, c)[0] = imgo.at(r, c)[2]; image.at(r, c)[1] = imgo.at(r, c)[1]; image.at(r, c)[2] = imgo.at(r, c)[0]; } } std::stringstream frame_name; frame_name << rgbdir; frame_name << imgi->header.stamp.sec << "." << imgi->header.stamp.nsec << ".png"; if (!cv::imwrite(frame_name.str(), image)) { std::cerr << "error writing rgb image: " << frame_name.str() << std::endl; delete rgb_sensor; delete grey_sensor; return false; } if (doRGB) { // allocate new rgb frame auto *rgb_frame = new ImageFileFrame(); if (rgb_frame == nullptr) { std::cerr << "error creating rgb frame" << std::endl; delete rgb_sensor; delete grey_sensor; return false; } // populate frame and update slambench file rgb_frame->FrameSensor = rgb_sensor; rgb_frame->Timestamp.S = imgi->header.stamp.sec; rgb_frame->Timestamp.Ns = imgi->header.stamp.nsec; rgb_frame->filename = frame_name.str(); file.AddFrame(rgb_frame); } if (doGrey) { // allocate new grey frame auto *grey_frame = new ImageFileFrame(); if (grey_frame == nullptr) { std::cerr << "error creating grey frame" << std::endl; delete rgb_sensor; delete grey_sensor; return false; } // populate frame and update slambench file grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp.S = imgi->header.stamp.sec; grey_frame->Timestamp.Ns = imgi->header.stamp.nsec; grey_frame->filename = frame_name.str(); file.AddFrame(grey_frame); } } bag.close(); return true; } bool loadTUMROSBAG_GroundTruthData(const std::string & bagname, const std::string & topic, const TUMROSBAGReader::gt_frame_ids_t & gt_ids, SLAMFile & file) { auto *gt_sensor = new GroundTruthSensor("GroundTruth"); if (gt_sensor == nullptr) { std::cerr << "error allocating ground truth sensor" << std::endl; return false; } std::cout << "gt sensor created" << std::endl; // populate sensor data gt_sensor->Index = file.Sensors.size(); gt_sensor->Description = "GroundTruthSensor"; file.Sensors.AddSensor(gt_sensor); // initialised to avoid warnings! tf::Transform w_k_trans = tf::Transform::getIdentity(); tf::Transform k_c_trans = tf::Transform::getIdentity(); tf::Transform c_r_trans = tf::Transform::getIdentity(); tf::Transform r_o_trans = tf::Transform::getIdentity(); bool w_k_new = false; bool k_c_rdy = false; bool c_r_rdy = false; bool r_o_rdy = false; bool all_rdy = false; // NOTE: initialised to avoid warning uint32_t ts_sec = 0; uint32_t ts_nsec = 0; // open rosbag // the ground truth topic contains several transformations // ground truth is built from the following composition: // optical frame -> rgb frame -> camera -> kinect -> world rosbag::Bag bag; try { bag.open(bagname,rosbag::bagmode::Read); } catch (...) { std::cerr << "error opening gt rosbag: " << bagname << std::endl; delete gt_sensor; return false; } // create query to fetch ground truth topic messages rosbag::View view(bag, rosbag::TopicQuery(topic)); for (const auto& msg : view) { tf::tfMessage::ConstPtr msgi = msg.instantiate(); if (msgi == nullptr) { continue; } for (const auto& msgii : msgi->transforms) { if (!r_o_rdy && msgii.child_frame_id == gt_ids.optical) { // record the /openni_rgb_frame to /openni_rgb_optical_frame // transformation_ only once if ((msgii.header.frame_id == gt_ids.rgb)) { r_o_rdy = true; all_rdy = r_o_rdy && c_r_rdy && k_c_rdy; tf::transformMsgToTF(msgii.transform, r_o_trans); } } else if (!c_r_rdy && msgii.child_frame_id == gt_ids.rgb) { // record the /openni_camera to /openni_rgb_frame // transformation_ only once if ((msgii.header.frame_id == gt_ids.camera)) { c_r_rdy = true; all_rdy = r_o_rdy && c_r_rdy && k_c_rdy; tf::transformMsgToTF(msgii.transform, c_r_trans); } } else if (!k_c_rdy && msgii.child_frame_id == gt_ids.camera) { // record the /kinect to /openni_camera // transformation_ only once if ((msgii.header.frame_id == gt_ids.kinect)) { k_c_rdy = true; all_rdy = r_o_rdy && c_r_rdy && k_c_rdy; tf::transformMsgToTF(msgii.transform, k_c_trans); } } else if (msgii.child_frame_id == gt_ids.kinect) { // track continuously the /world to /kinect transformation_ if (msgii.header.frame_id == gt_ids.world) { w_k_new = true; tf::transformMsgToTF(msgii.transform, w_k_trans); // record time stamp to use later in frame ts_sec = msgii.header.stamp.sec; ts_nsec = msgii.header.stamp.nsec; } } if (all_rdy && w_k_new) { w_k_new = false; Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); tf::Transform w_o_trans = w_k_trans * k_c_trans * c_r_trans * r_o_trans; tf::Vector3 tr = w_o_trans.getOrigin(); tf::Matrix3x3 rt = w_o_trans.getBasis(); // NOTE: float64 (double) to float casts pose.block(0, 0, 3, 3) << (float) rt[0][0], (float) rt[0][1], (float) rt[0][2], (float) rt[1][0], (float) rt[1][1], (float) rt[1][2], (float) rt[2][0], (float) rt[2][1], (float) rt[2][2]; pose.block(0, 3, 3, 1) << (float) tr.x(), (float) tr.y(), (float) tr.z(); // allocate new gt frame auto *gt_frame = new SLAMInMemoryFrame(); if (gt_frame == nullptr) { std::cerr << "error creating gt frame" << std::endl; delete gt_sensor; return false; } gt_frame->FrameSensor = gt_sensor; // allocate memory for gt data gt_frame->Data = malloc(gt_frame->GetSize()); if (gt_frame->Data == nullptr) { std::cerr << "error allocating memory for gt frame" << std::endl; delete gt_sensor; return false; } // populate frame data and update slambench file gt_frame->Timestamp.S = ts_sec; gt_frame->Timestamp.Ns = ts_nsec; memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); // move on to next gt message (skip rest of transformations) break; } } } bag.close(); return true; } bool loadTUMROSBAG_AccelerometerData(const std::string & bagname, const std::string & topic, SLAMFile & file) { auto *acc_sensor = new AccelerometerSensor("Accelerometer"); if (acc_sensor == nullptr) { std::cerr << "error allocating accelerometer sensor" << std::endl; return false; } std::cout << "accelerometer sensor created" << std::endl; // populate sensor data acc_sensor->Index = file.Sensors.size(); acc_sensor->Description = "AccelerometerSensor"; file.Sensors.AddSensor(acc_sensor); // open rosbag rosbag::Bag bag; try { bag.open(bagname,rosbag::bagmode::Read); } catch (...) { std::cerr << "error opening accelerometer rosbag: " << bagname << std::endl; return false; } // create query to fetch ground truth topic messages rosbag::View view(bag, rosbag::TopicQuery(topic)); for (const auto& msg : view) { sensor_msgs::Imu::ConstPtr msgi = msg.instantiate(); if (msgi == nullptr) { continue; } // allocate new accelerometer frame auto *acc_frame = new SLAMInMemoryFrame(); if (acc_frame == nullptr) { std::cerr << "error creating acc frame" << std::endl; delete acc_sensor; return false; } acc_frame->FrameSensor = acc_sensor; // allocate memory for accelerometer data acc_frame->Data = malloc(acc_frame->GetSize()); if (acc_frame->Data == nullptr) { std::cerr << "error allocating memory for acc frame" << std::endl; delete acc_sensor; return false; } // populate frame and update slambench file acc_frame->Timestamp.S = msgi->header.stamp.sec; acc_frame->Timestamp.Ns = msgi->header.stamp.nsec; // NOTE: float64 (double) to float casts ((float *) acc_frame->Data)[0] = (float) (msgi->linear_acceleration).x; ((float *) acc_frame->Data)[1] = (float) (msgi->linear_acceleration).y; ((float *) acc_frame->Data)[2] = (float) (msgi->linear_acceleration).z; file.AddFrame(acc_frame); } bag.close(); return true; } SLAMFile* TUMROSBAGReader::GenerateSLAMFile () { // NOTE: can accelerometer be used on its own? if (!(grey || rgb || depth || accelerometer)) { std::cerr << "error: no sensors defined" << std::endl; return nullptr; } std::string dirname = input; // rosbag file auto pos = dirname.rfind('/'); if (pos == std::string::npos) { pos = 0; } std::string bagname = dirname + "/../../" + dirname.substr(pos) + ".bag"; auto * slamfilep = new SLAMFile(); if (slamfilep == nullptr) { std::cerr << "error creating slamfile handle" << std::endl; return nullptr; } SLAMFile & slamfile = *slamfilep; Sensor::pose_t pose = Eigen::Matrix4f::Identity(); image_params_t image_params = get_image_params(); /** * get sensor parameters * * some of these parameters depend on the actual kinect device used * */ DepthSensor::disparity_params_t disparity_params; DepthSensor::disparity_type_t disparity_type; CameraSensor::intrinsics_t intrinsics_rgb; DepthSensor::intrinsics_t intrinsics_depth; CameraSensor::distortion_coefficients_t distortion_rgb; DepthSensor::distortion_coefficients_t distortion_depth; CameraSensor::distortion_type_t distortion_type; uint32_t kinect = get_sensor_params(disparity_params, disparity_type, intrinsics_rgb, intrinsics_depth, distortion_rgb, distortion_depth, distortion_type); if (kinect) { std::cout << "using freiburg" << kinect << " camera calibration parameters" << std::endl; } else { std::cout << "using default camera calibration parameters" << std::endl; std::cout << "warning: camera calibration might be wrong!" << std::endl; } /** * load Depth */ if (depth && !loadTUMROSBAG_DepthData(dirname, bagname, depth_topic, slamfile, pose, image_params, intrinsics_depth, distortion_depth, distortion_type, disparity_params, disparity_type)) { std::cerr << "error loading depth data." << std::endl; delete slamfilep; return nullptr; } /** * load RGB and/or Grey * NOTE: TUM rosbag files do not contain grey images - use rgb ones! */ if ((rgb || grey) && !loadTUMROSBAG_RGBGreyData(rgb, grey, dirname, bagname, rgb_topic, slamfile, pose, image_params, intrinsics_rgb, distortion_rgb, distortion_type)) { std::cerr << "error loading RGB/Grey data." << std::endl; delete slamfilep; return nullptr; } /** * load GT */ if (gt && !loadTUMROSBAG_GroundTruthData(bagname, gt_topic, gt_frame_ids, slamfile)) { std::cerr << "error loading gt data." << std::endl; delete slamfilep; return nullptr; } /** * load Accelerometer */ if (accelerometer && !loadTUMROSBAG_AccelerometerData(bagname, acc_topic, slamfile)) { std::cerr << "error loading Accelerometer data." << std::endl; delete slamfilep; return nullptr; } return slamfilep; } ================================================ FILE: framework/tools/dataset-tools/TUM.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/TUM.h" #include "include/utils/RegexPattern.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; bool loadTUMDepthData(const std::string &dirname, SLAMFile &file, const Sensor::pose_t &pose, const DepthSensor::intrinsics_t &intrinsics, const CameraSensor::distortion_coefficients_t &distortion, const DepthSensor::disparity_params_t &disparity_params, const DepthSensor::disparity_type_t &disparity_type, const CameraSensor::distortion_type_t &distortion_type) { auto img_params = TUMReader::get_image_params(); auto depth_sensor = DepthSensorBuilder() .name("Depth") .rate(img_params.rate) .size(img_params.width, img_params.height) .pose(pose) .intrinsics(intrinsics) .distortion(distortion_type, distortion) .disparity(disparity_type, disparity_params) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(depth_sensor); std::string line; std::ifstream infile(dirname + "/" + "depth.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex depth_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, depth_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string depth_filename = match[3]; auto depth_frame = new ImageFileFrame(); depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp.S = timestampS; depth_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << depth_filename; depth_frame->filename = frame_name.str(); if (access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(depth_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadTUMRGBData(const std::string &dirname, SLAMFile &file, const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics, const CameraSensor::distortion_coefficients_t &distortion, const CameraSensor::distortion_type_t &distortion_type) { auto img_params = TUMReader::get_image_params(); auto rgb_sensor = RGBSensorBuilder() .rate(img_params.rate) .size(img_params.width, img_params.height) .pose(pose) .intrinsics(intrinsics) .distortion(distortion_type, distortion) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(rgb_sensor); std::string line; std::ifstream infile(dirname + "/" + "rgb.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex rgb_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, rgb_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string rgb_filename = match[3]; auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = rgb_sensor; rgb_frame->Timestamp.S = timestampS; rgb_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << rgb_filename; rgb_frame->filename = frame_name.str(); if (access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(rgb_frame); } else { std::cerr << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadTUMGreyData(const std::string &dirname, SLAMFile &file, const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics, const CameraSensor::distortion_coefficients_t &distortion, const CameraSensor::distortion_type_t &distortion_type) { auto img_params = TUMReader::get_image_params(); auto grey_sensor = GreySensorBuilder() .rate(img_params.rate) .size(img_params.width, img_params.height) .pose(pose) .intrinsics(intrinsics) .distortion(distortion_type, distortion) .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(grey_sensor); std::string line; std::ifstream infile(dirname + "/" + "rgb.txt"); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: timestamp filename std::string expr = start + ts + ws // timestamp + fn + end; // filename boost::regex rgb_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, rgb_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); std::string rgb_filename = match[3]; auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp.S = timestampS; grey_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << rgb_filename; grey_frame->filename = frame_name.str(); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(grey_frame); } else { std::cout << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadTUMGroundTruthData(const std::string &dirname , SLAMFile &file) { auto gt_sensor = GTSensorBuilder() .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(gt_sensor); std::ifstream infile(dirname + "/" + "groundtruth.txt"); std::string line; boost::smatch match; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& dec = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp tx ty tz qx qy qz qw std::string expr = start + ts + ws // timestamp + dec + ws // tx + dec + ws // ty + dec + ws // tz + dec + ws // qx + dec + ws // qy + dec + ws // qz + dec + end; // qw boost::regex groundtruth_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty() || boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, groundtruth_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); float tx = std::stof(match[3]); float ty = std::stof(match[4]); float tz = std::stof(match[5]); float QX = std::stof(match[6]); float QY = std::stof(match[7]); float QZ = std::stof(match[8]); float QW = std::stof(match[9]); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp.S = timestampS; gt_frame->Timestamp.Ns = timestampNS; gt_frame->Data = malloc(gt_frame->GetSize()); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } else { std::cout << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadTUMAccelerometerData(const std::string &dirname, SLAMFile &file) { auto accelerometer_sensor = AccSensorBuilder() .index(file.Sensors.size()) .build(); file.Sensors.AddSensor(accelerometer_sensor); std::ifstream infile(dirname + "/" + "accelerometer.txt"); std::string line; boost::smatch match; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& dec = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp ax ay az std::string expr = start + ts + ws // timestamp + dec + ws // ax + dec + ws // ay + dec + end; // az boost::regex accelerometer_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, accelerometer_line)) { int timestampS = std::stoi(match[1]); int timestampNS = std::stoi(match[2]) * std::pow(10, 9 - match[2].length()); float ax = std::stof(match[3]); float ay = std::stof(match[4]); float az = std::stof(match[5]); auto accelerometer_frame = new SLAMInMemoryFrame(); accelerometer_frame->FrameSensor = accelerometer_sensor; accelerometer_frame->Timestamp.S = timestampS; accelerometer_frame->Timestamp.Ns = timestampNS; accelerometer_frame->Data = malloc(accelerometer_frame->GetSize()); ((float *)accelerometer_frame->Data)[0] = ax; ((float *)accelerometer_frame->Data)[1] = ay; ((float *)accelerometer_frame->Data)[2] = az; file.AddFrame(accelerometer_frame); } else { std::cout << "Unknown line:" << line << std::endl; return false; } } return true; } SLAMFile* TUMReader::GenerateSLAMFile () { if(!(grey || rgb || depth)) { std::cerr << "No sensors defined\n"; return nullptr; } bool is_ethi = false; std::string dirname = input; const std::vector requirements = {"accelerometer.txt", "rgb.txt", "rgb", "depth.txt", "depth", "groundtruth.txt"}; if (!checkRequirements(dirname, requirements)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } auto slamfilep = new SLAMFile(); SLAMFile & slamfile = *slamfilep; Sensor::pose_t pose = Eigen::Matrix4f::Identity(); /// Default parameters from freiburg1 CameraSensor::intrinsics_t intrinsics_rgb; DepthSensor::intrinsics_t intrinsics_depth; CameraSensor::distortion_type_t distortion_type; CameraSensor::distortion_coefficients_t distortion_rgb; DepthSensor::distortion_coefficients_t distortion_depth; DepthSensor::disparity_params_t disparity_params; DepthSensor::disparity_type_t disparity_type; TUMReader::DatasetOrigin d_origin = get_sensor_params(disparity_params, disparity_type, intrinsics_rgb, intrinsics_depth, distortion_rgb, distortion_depth, distortion_type); if (d_origin == TUMReader::DatasetOrigin::Default) { std::cout << "using default camera calibration parameters" << std::endl; std::cout << "warning: camera calibration might be wrong!" << std::endl; } else if (d_origin == TUMReader::DatasetOrigin::ETHI) { is_ethi = true; std::cout << "using ETH Illumination camera calibration parameters" << std::endl; } else { std::cout << "using freiburg" << d_origin << " camera calibration parameters" << std::endl; } if(gt && !loadTUMGroundTruthData(dirname, slamfile)) { std::cout << "Error while loading gt information." << std::endl; delete slamfilep; return nullptr; } if(accelerometer && !loadTUMAccelerometerData(dirname, slamfile)) { std::cout << "Error while loading Accelerometer information." << std::endl; delete slamfilep; return nullptr; } if (is_ethi) dirname = input + "/depth"; if(depth && !loadTUMDepthData(dirname, slamfile,pose,intrinsics_depth,distortion_depth,disparity_params,disparity_type,distortion_type)) { std::cout << "Error while loading depth information." << std::endl; delete slamfilep; return nullptr; } if (is_ethi) dirname = input + "/rgb"; if(grey && !loadTUMGreyData(dirname, slamfile,pose,intrinsics_rgb,distortion_rgb,distortion_type)) { std::cout << "Error while loading Grey information." << std::endl; delete slamfilep; return nullptr; } if(rgb && !loadTUMRGBData(dirname, slamfile,pose,intrinsics_rgb,distortion_rgb,distortion_type)) { std::cout << "Error while loading RGB information." << std::endl; delete slamfilep; return nullptr; } return slamfilep; } ================================================ FILE: framework/tools/dataset-tools/UZHFPV.cpp ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "include/UZHFPV.h" #include "include/utils/RegexPattern.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; bool loadUZHFPVGreyData(const std::string& dirname, const std::string& filename, const std::string& sensor_name_yaml, SLAMFile &file, const YAML::Node& yaml) { auto width = yaml[sensor_name_yaml]["resolution"][0].as(); auto height = yaml[sensor_name_yaml]["resolution"][1].as(); slambench::io::CameraSensor::intrinsics_t intrinsics; intrinsics[0] = yaml[sensor_name_yaml]["intrinsics"][0].as() / width; intrinsics[1] = yaml[sensor_name_yaml]["intrinsics"][1].as() / height; intrinsics[2] = yaml[sensor_name_yaml]["intrinsics"][2].as() / width; intrinsics[3] = yaml[sensor_name_yaml]["intrinsics"][3].as() / height; slambench::io::CameraSensor::distortion_coefficients_t distortion; for(size_t i = 0; i < 4; i++) distortion[i] = yaml[sensor_name_yaml]["distortion_coeffs"][i].as(); distortion[4] = 0; Eigen::Matrix4f pose; pose << yaml[sensor_name_yaml]["T_cam_imu"][0][0].as(), yaml[sensor_name_yaml]["T_cam_imu"][1][0].as(), yaml[sensor_name_yaml]["T_cam_imu"][2][0].as(), yaml[sensor_name_yaml]["T_cam_imu"][3][0].as(), yaml[sensor_name_yaml]["T_cam_imu"][0][1].as(), yaml[sensor_name_yaml]["T_cam_imu"][1][1].as(), yaml[sensor_name_yaml]["T_cam_imu"][2][1].as(), yaml[sensor_name_yaml]["T_cam_imu"][3][1].as(), yaml[sensor_name_yaml]["T_cam_imu"][0][2].as(), yaml[sensor_name_yaml]["T_cam_imu"][1][2].as(), yaml[sensor_name_yaml]["T_cam_imu"][2][2].as(), yaml[sensor_name_yaml]["T_cam_imu"][3][2].as(), yaml[sensor_name_yaml]["T_cam_imu"][0][3].as(), yaml[sensor_name_yaml]["T_cam_imu"][1][3].as(), yaml[sensor_name_yaml]["T_cam_imu"][2][3].as(), yaml[sensor_name_yaml]["T_cam_imu"][3][3].as(); auto rate = yaml["cam1"] ? 30 : 50; // if cam1 exists, it's Snapdragon (30fps), else it's Davis (50fps). auto grey_sensor = GreySensorBuilder() .name("Grey " + sensor_name_yaml) .size(width, height) .pose(pose.transpose()) .intrinsics(intrinsics) .distortion(CameraSensor::distortion_type_t::Equidistant, distortion) .rate(rate) .index(file.Sensors.size()) .build(); //if(sensor_name_yaml.find("cam1")) grey_sensor->Delay = yaml[sensor_name_yaml]["timeshift_cam_imu"].as(); file.Sensors.AddSensor(grey_sensor); std::string line; std::ifstream infile(dirname + "/" + filename); boost::smatch match; boost::regex comment = boost::regex(RegexPattern::comment); const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; const std::string& id = RegexPattern::decimal; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& fn = RegexPattern::filename; // format: id timestamp filename std::string expr = start + id + ws // id + ts + ws // timestamp + fn + ws // filename + end; boost::regex grey_line = boost::regex(expr); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, grey_line)) { // int identifer = std::stoi(match[1]); int timestampS = std::stoi(match[2]); int timestampNS = std::stod(match[3]) * std::pow(10, 9 - match[3].length()); std::string grey_filename = match[4]; auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp.S = timestampS; grey_frame->Timestamp.Ns = timestampNS; std::stringstream frame_name; frame_name << dirname << "/" << grey_filename; grey_frame->filename = frame_name.str(); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No Grey image for frame (%s)\n", frame_name.str().c_str()); perror(""); return false; } file.AddFrame(grey_frame); } else { std::cout << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadUZHFPVGroundTruthData(const std::string &dirname, SLAMFile &file, GroundTruthSensor* gt_sensor) { std::ifstream infile(dirname + "/" + "groundtruth.txt"); std::string line; boost::smatch match; const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& id = RegexPattern::integer; const std::string& dec = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: id timestamp tx ty tz qx qy qz qw std::string expr = start + id + ws // id + ts + ws // timestamp + dec + ws // tx + dec + ws // ty + dec + ws // tz + dec + ws // qx + dec + ws // qy + dec + ws // qz + dec + end; // qw boost::regex groundtruth_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, groundtruth_line)) { // int identifier = std::stoi(match[1]); int timestampS = std::stoi(match[2]); int timestampNS = std::stod(match[3]) * std::pow(10, 9 - match[3].length()); float tx = std::stof(match[4]); float ty = std::stof(match[5]); float tz = std::stof(match[6]); float QX = std::stof(match[7]); float QY = std::stof(match[8]); float QZ = std::stof(match[9]); float QW = std::stof(match[10]); Eigen::Matrix3f rotationMat = Eigen::Quaternionf(QW, QX, QY, QZ).toRotationMatrix(); Eigen::Matrix4f pose = Eigen::Matrix4f::Identity(); pose.block(0, 0, 3, 3) = rotationMat; pose.block(0, 3, 3, 1) << tx, ty, tz; auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp.S = timestampS; gt_frame->Timestamp.Ns = timestampNS; gt_frame->Data = malloc(gt_frame->GetSize()); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } else { std::cout << "Unknown line:" << line << std::endl; return false; } } return true; } bool loadUZHFPVIMUData(const std::string &dirname, SLAMFile &file, const YAML::Node& yaml) { auto imu_sensor = new IMUSensor(dirname); // parameters from calibration imu.yaml imu_sensor->AcceleratorNoiseDensity = yaml["accelerometer_noise_density"].as(); imu_sensor->AcceleratorBiasDiffusion = yaml["accelerometer_random_walk"].as(); imu_sensor->GyroscopeNoiseDensity = yaml["gyroscope_noise_density"].as(); imu_sensor->GyroscopeBiasDiffusion = yaml["gyroscope_random_walk"].as(); imu_sensor->Rate = yaml["update_rate"].as(); imu_sensor->Index = file.Sensors.size(); file.Sensors.AddSensor(imu_sensor); std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "imu.txt"); const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& id = RegexPattern::integer; const std::string& dec = RegexPattern::decimal; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp ang_vel_x ang_vel_y ang_vel_z lin_acc_x lin_acc_y lin_acc_z std::string expr = start + id + ws // id + ts + ws // timestamp + dec + ws // ang_vel_x + dec + ws // ang_vel_y + dec + ws // ang_vel_z + dec + ws // lin_acc_x + dec + ws // lin_acc_y + dec + end; // lin_acc_z boost::regex imu_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, imu_line)) { // int identifier = std::stoi(match[1]); int timestampS = std::stoi(match[2]); int timestampNS = std::stod(match[3]) * std::pow(10, 9 - match[3].length()); float gx = std::stof(match[4]); float gy = std::stof(match[5]); float gz = std::stof(match[6]); float ax = std::stof(match[7]); float ay = std::stof(match[8]); float az = std::stof(match[9]); auto IMU_frame = new SLAMInMemoryFrame(); IMU_frame->FrameSensor = imu_sensor; IMU_frame->Timestamp.S = timestampS; IMU_frame->Timestamp.Ns = timestampNS; IMU_frame->Data = malloc(imu_sensor->GetFrameSize(IMU_frame)); ((float *)IMU_frame->Data)[0] = gx; ((float *)IMU_frame->Data)[1] = gy; ((float *)IMU_frame->Data)[2] = gz; ((float *)IMU_frame->Data)[3] = ax; ((float *)IMU_frame->Data)[4] = ay; ((float *)IMU_frame->Data)[5] = az; file.AddFrame(IMU_frame); } else { std::cerr << "Unknown line: " << line << std::endl; return false; } } return true; } bool loadUZHFPVEventData(const std::string &dirname, SLAMFile &file, EventCameraSensor *event_sensor) { using namespace slambench; std::string line; boost::smatch match; std::ifstream infile(dirname + "/" + "events.txt"); const std::string& ts = RegexPattern::timestamp; const std::string& ws = RegexPattern::whitespace; const std::string& num = RegexPattern::integer; const std::string& start = RegexPattern::start; const std::string& end = RegexPattern::end; // format: timestamp x y polarity std::string expr = start + ts + ws // timestamp + num + ws // x + num + ws // y + num + end; // polarity boost::regex events_line = boost::regex(expr); boost::regex comment = boost::regex(RegexPattern::comment); std::vector events = {}; while (std::getline(infile, line)) { if (line.empty()) { continue; } else if (boost::regex_match(line, match, comment)) { continue; } else if (boost::regex_match(line, match, events_line)) { uint32_t timestampS = std::stoi(match[0]); uint32_t timestampNs = std::stod(match[2]) * std::pow(10, 9 - match[2].length()); auto timestamp = TimeStamp{timestampS, timestampNs}; int x = std::stoi(match[3]); int y = std::stoi(match[4]); bool p = std::stoi(match[5]); events.emplace_back(timestamp, x, y, p); } else { std::cerr << "Unknown line: " << line << std::endl; return false; } } size_t current_index = 0, i; auto current_ts = events[current_index].ts; // loop runs once per SLAM Frame while(current_index < events.size() - 1) { auto event_frame = new SLAMInMemoryFrame(); event_frame->FrameSensor = event_sensor; event_frame->Timestamp = current_ts; // loop from current position until frame found with time difference greater than framerate for(i = current_index; i < events.size(); ++i) { auto delta = events[i].ts - current_ts; if (delta > std::chrono::milliseconds{20}) break; } size_t count = (i - 1) - current_index; size_t variable_size = sizeof(Event) * count; // copy from and to points into malloc'd memory event_frame->SetVariableSize(variable_size); event_frame->Data = malloc(variable_size); memcpy(event_frame->Data, &events[current_index], variable_size); file.AddFrame(event_frame); // set index to beginning of next frame current_index = i; current_ts = events[current_index].ts; } return true; } SLAMFile *UZHFPVReader::GenerateSLAMFile() { std::string dirname = input; // check requirements for slamfile std::vector requirements = {"img"}; if (imu) { requirements.emplace_back("imu.txt"); requirements.emplace_back("imu.yaml"); } if (gt) { requirements.emplace_back("groundtruth.txt"); } if (stereo) { requirements.emplace_back("left_images.txt"); requirements.emplace_back("right_images.txt"); } else { requirements.emplace_back("images.txt"); } if (events) { requirements.emplace_back("events.txt"); } if (!checkRequirements(dirname, requirements)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } YAML::Node yaml = YAML::LoadFile(dirname + "/sensors.yaml"); // Setup slamfile auto slamfile_ptr = new SLAMFile(); auto &slamfile = *slamfile_ptr; Sensor::pose_t pose = Eigen::Matrix4f::Identity(); // load events data if (events) { auto event_sensor = new EventCameraSensor(dirname); event_sensor->Width = 346; event_sensor->Height = 260; event_sensor->Index = slamfile.Sensors.size(); slamfile.Sensors.AddSensor(event_sensor); if (!loadUZHFPVEventData(dirname, slamfile, event_sensor)) { std::cerr << "Error while loading grey left stereo information." << std::endl; delete slamfile_ptr; return nullptr; } } // load camera data if (stereo) { // snapdragon stereo left if (!loadUZHFPVGreyData(dirname, "left_images.txt", "cam0", slamfile, yaml)) { std::cerr << "Error while loading grey left stereo information." << std::endl; delete slamfile_ptr; return nullptr; } // snapdragon stereo right if (!loadUZHFPVGreyData(dirname, "right_images.txt", "cam1", slamfile, yaml)) { std::cerr << "Error while loading grey right stereo information." << std::endl; delete slamfile_ptr; return nullptr; } } else { // davis grey camera auto grey_sensor = GreySensorBuilder() .name("Grey") .size(346, 260) .pose(pose) .intrinsics(davis_intrinsics) .distortion(CameraSensor::distortion_type_t::Equidistant, davis_distortion) .rate(50) // from paper .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(grey_sensor); if (!loadUZHFPVGreyData(dirname, "images.txt", "cam0", slamfile, yaml)) { std::cerr << "Error while loading Grey information." << std::endl; delete slamfile_ptr; return nullptr; } } // load GT if (gt) { auto gt_sensor = GTSensorBuilder() .name("GroundTruth") .description("GroundTruthSensor") .index(slamfile.Sensors.size()) .build(); slamfile.Sensors.AddSensor(gt_sensor); if(!loadUZHFPVGroundTruthData(dirname, slamfile, gt_sensor)) { std::cerr << "Error while loading gt information." << std::endl; delete slamfile_ptr; return nullptr; } } yaml = YAML::LoadFile(dirname + "/imu.yaml"); // load IMU data if (imu) { if(!loadUZHFPVIMUData(dirname, slamfile, yaml)) { std::cerr << "Error while loading gt information." << std::endl; delete slamfile_ptr; return nullptr; } } return slamfile_ptr; } ================================================ FILE: framework/tools/dataset-tools/VolumeDeform.cpp ================================================ /* Copyright (c) 2020 University of Manchester. Supported by the RAIN Hub, which is funded by the Industrial Strategy Challenge Fund, part of the UK government’s modern Industrial Strategy. The fund is delivered by UK Research and Innovation and managed by EPSRC [EP/R026084/1]. This code is licensed under the MIT License. */ #include "include/VolumeDeform.h" #include "include/utils/dataset_utils.h" #include "io/sensor/sensor_builder.h" #include #include #include #include #include using namespace slambench::io; std::string GetFileName(const std::string& dirname, size_t frame_idx, bool is_depth_img) { //Construct the file_name char frame_idx_str[20]; sprintf(frame_idx_str, "%06d", static_cast(frame_idx)); std::string file_name = "frame-"; file_name += std::string(frame_idx_str); if (is_depth_img) { file_name += ".depth"; } else { file_name += ".color"; } file_name += ".png"; return dirname + "/" + file_name; } bool VolumeDeformReader::GetFrame(const std::string &dirname, int frame_no, SLAMFile &file, std::ifstream& infile, CameraSensor* rgb_sensor, CameraSensor* grey_sensor, DepthSensor* depth_sensor, GroundTruthSensor* gt_sensor) { double frame_time = 1.0 / image_params.rate; uint64_t total_ns = frame_time * frame_no * 1000000000; slambench::TimeStamp ts; ts.S = total_ns / 1000000000; ts.Ns = total_ns % 1000000000; if (rgb_sensor) { auto rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = rgb_sensor; rgb_frame->Timestamp = ts;; rgb_frame->filename = GetFileName(dirname, frame_no, false); if (access(rgb_frame->filename.c_str(), F_OK) < 0) { printf("No RGB image for frame %d (%s)\n", frame_no, rgb_frame->filename.c_str()); return false; } file.AddFrame(rgb_frame); } if (grey_sensor) { auto grey_frame = new ImageFileFrame(); grey_frame->FrameSensor = grey_sensor; grey_frame->Timestamp = ts; grey_frame->filename = GetFileName(dirname, frame_no, false); if (access(grey_frame->filename.c_str(), F_OK) < 0) { printf("No Grey image for frame %d (%s)\n", frame_no, grey_frame->filename.c_str()); perror(""); return false; } file.AddFrame(grey_frame); } if (depth_sensor) { auto depth_frame = new ImageFileFrame(); depth_frame->filename = GetFileName(dirname, frame_no, true); depth_frame->FrameSensor = depth_sensor; depth_frame->Timestamp = ts; if (access(depth_frame->filename.c_str(), F_OK) < 0) { printf("No depth image for frame %d (%s)\n", frame_no, depth_frame->filename.c_str()); perror(""); return false; } file.AddFrame(depth_frame); } if (gt_sensor) { std::vector myNumbers; float number; std::string line; std::getline(infile, line); if(line.empty()) return false; std::stringstream iss( line ); while ( iss >> number ) myNumbers.push_back( number ); auto pose = Eigen::Map(myNumbers.data()).transpose(); // FIXME: why doesn't using ColMajor instead fix this? auto gt_frame = new SLAMInMemoryFrame(); gt_frame->FrameSensor = gt_sensor; gt_frame->Timestamp = ts; gt_frame->Data = malloc(sizeof(slambench::io::Sensor::pose_t)); memcpy(gt_frame->Data, pose.data(), gt_frame->GetSize()); file.AddFrame(gt_frame); } return true; } SLAMFile *VolumeDeformReader::GenerateSLAMFile() { if (!(grey || rgb || depth)) { std::cerr << "No sensors defined\n"; return nullptr; } const std::vector requirements = {"data", "canonical", "reconstruction", "poses.txt"}; if (!checkRequirements(input, requirements)) { std::cerr << "Invalid folder." << std::endl; return nullptr; } auto slamfile_ptr = new SLAMFile(); auto &slamfile = *slamfile_ptr; CameraSensor *rgb_sensor, *grey_sensor; DepthSensor *depth_sensor; GroundTruthSensor *gt_sensor; // load Depth if (depth) { depth_sensor = DepthSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .intrinsics(intrinsics) .build(); slamfile.Sensors.AddSensor(depth_sensor); } // load Grey if (grey) { grey_sensor = GreySensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .intrinsics(intrinsics) .build(); slamfile.Sensors.AddSensor(grey_sensor); } // load RGB if (rgb) { rgb_sensor = RGBSensorBuilder() .rate(image_params.rate) .size(image_params.width, image_params.height) .intrinsics(intrinsics) .build(); slamfile.Sensors.AddSensor(rgb_sensor); } // load GT if (gt) { gt_sensor = GTSensorBuilder().build(); slamfile.Sensors.AddSensor(gt_sensor); } auto gt_file = input + "/poses.txt"; std::ifstream istream; if(access(gt_file.c_str(), F_OK) >= 0) istream = std::ifstream(gt_file); int frame_no = 0; while (GetFrame(input+"/data", frame_no, slamfile, istream, rgb_sensor, grey_sensor, depth_sensor, gt_sensor)) { frame_no++; } if(istream.is_open()) istream.close(); return slamfile_ptr; } ================================================ FILE: framework/tools/dataset-tools/dataset-generator.cpp ================================================ /* Copyright (c) 2017-2020 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 The development of the interface with ROS datasets (rosbags) is supported by the RAIN Hub, which is funded by the Industrial Strategy Challenge Fund, part of the UK government’s modern Industrial Strategy. The fund is delivered by UK Research and Innovation and managed by EPSRC [EP/R026084/1]. This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #include #include #include "include/BONN.h" #include "include/EUROCMAV.h" #include "include/ICL.h" #include "include/ICLNUIM.h" #include "include/SVO.h" #include "include/TUM.h" #include "include/UZHFPV.h" #include "include/OpenLORIS.h" #include "include/VolumeDeform.h" using namespace slambench::io; class MainComponent : public ParameterComponent { private: slambench::ParameterManager param_manager; DatasetReader *reader = nullptr; public: std::string binary_name; std::string dataset; std::string output; bool quiet; public: static void help_callback(Parameter *, ParameterComponent *caller) { auto config = dynamic_cast(caller); std::cerr << "\n" "== =========================== ==\n" "== SLAMBench Dataset Generator ==\n" "== =========================== ==\n" "\n" "Description:\n The dataset generator is used to produce *.slam files" "(dataset files compatible with the SLAMBench loader).\n" "\n" "Usage:\n " << config->binary_name << " -d dataset-type -o output-slam-file " "[with extra arguments required for the different dataset type]\n" "\n" "Parameters:\n"; config->param_manager.PrintArguments(std::cerr); exit(0); } static void dataset_callback(Parameter *p, ParameterComponent *caller) { auto config = dynamic_cast(caller); auto dataset = dynamic_cast *>(p); std::string dataset_name = dataset->getTypedValue(); if (dataset_name == "iclnuim") { config->reader = new ICLNUIMReader(""); } else if (dataset_name == "tum") { config->reader = new TUMReader(""); } else if (dataset_name == "tum-rosbag") { #ifdef ROSBAG_SUPPORT config->reader = new TUMROSBAGReader(""); #else std::cerr << "\033[1;31mError: ROS support not enabled for this dataset. Please rebuild SLAMBench with ROS dependencies.\033[0m" << std::endl; exit(1); #endif } else if (dataset_name == "eurocmav") { config->reader = new EUROCMAVReader(""); } else if (dataset_name == "icl") { config->reader = new ICLReader(""); } else if (dataset_name == "svo") { config->reader = new SVOReader(""); } else if (dataset_name == "bonn") { config->reader = new BONNReader(""); } else if (dataset_name == "uzhfpv") { config->reader = new UZHFPVReader(""); } else if (dataset_name == "OpenLORIS") { config->reader = new OpenLORISReader(""); } else if (dataset_name == "VolumeDeform") { config->reader = new VolumeDeformReader(""); } else if (dataset_name == "ethi") { auto eth_reader = new ETHIReader(""); if(eth_reader->dataset == "iclnuim") config->reader =new ICLNUIMReader(""); else if(eth_reader->dataset == "tum") config->reader = new TUMReader(""); } else std::cerr<<"The base dataset must be either iclnuim or tum"<reader) { config->param_manager.AddComponent(config->reader); } else { std::cout << "Data format not found" << std::endl; exit(1); } } static void frame_callback(int idx, int total) { printf("\r"); // print progress bar printf("["); const int width = 50; float blocks = width * ((float)idx / total); int i = 0; for (; i < blocks; ++i) { printf("#"); } for (; i < width; ++i) { printf(" "); } printf("] "); printf("%i / %i", idx, total); fflush(stdout); } MainComponent(int argc, char *argv[]) : ParameterComponent(""), binary_name(argv[0]), quiet(false) { this->addParameter(TypedParameter("d", "dataset", "Name of the input dataset type " "(iclnuim, tum, eurocmav, icl, svo, bonn, ethi, uzhfpv, OpenLORIS)", &this->dataset, nullptr, dataset_callback)); this->addParameter(TypedParameter("o","output","Output slam file", &this->output, nullptr)); this->addParameter(TypedParameter("q", "quiet","Hide the progress bar", &this->quiet, nullptr)); this->addParameter(TriggeredParameter("h", "help","Print the help.", help_callback)); this->param_manager.AddComponent(this); this->param_manager.ReadArguments(argc, argv); } bool Run() { SLAMFile *slam_file = reader->GenerateSLAMFile(); if (slam_file == nullptr) { std::cout << "No SLAM File generated." << std::endl; return false; } std::cout << "Writing output." << std::endl; return SLAMFile::Write(this->output, *slam_file, this->quiet ? nullptr : frame_callback); } }; int main(int argc, char *argv[]) { auto main = new MainComponent(argc, argv); if (main->dataset.empty()) { std::cout << " Please define the dataset type using the -d argument.\n" " Possible values are: iclnuim, tum, eurocmav, icl, svo, bonn, ethi, uzhfpv, OpenLORIS\n\n" " To have details of arguments for any type of dataset you are interested by,\n" " Please run the help mode for this dataset (e.g " << argv[0] << " -d tum)\n"; return EXIT_FAILURE; } if (main->output.empty()) { std::cout << "Please define the output file using the -o argument.\n"; return EXIT_FAILURE; } std::cout << "Selected Dataset is " << main->dataset << std::endl; std::cout << "Selected output is " << main->output << std::endl; std::cout << "Run generation...\n"; bool res = main->Run(); std::cout << std::endl << "Done.\n"; assert(res); } ================================================ FILE: framework/tools/dataset-tools/include/BONN.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_BONN_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_BONN_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class BONNReader : public DatasetReader { private: static constexpr image_params_t image_params = { 640, 480, 30.0, 5000.0 }; static constexpr CameraSensor::intrinsics_t intrinsics_rgb = {0.8481606891, 1.1303684792, 0.493114875, 0.4953252042}; static constexpr DepthSensor::intrinsics_t intrinsics_depth = {0.8481606891, 1.1303684792, 0.493114875, 0.4953252042}; static constexpr CameraSensor::distortion_coefficients_t distortion_rgb = {0.039903, -0.099343, -0.000730, -0.000144, 0.000000}; static constexpr DepthSensor::distortion_coefficients_t distortion_depth = {0.039903, -0.099343, -0.000730, -0.000144, 0.000000}; static constexpr DepthSensor::disparity_params_t disparity_params = {0.0002, 0.0}; static constexpr DepthSensor::disparity_type_t disparity_type = DepthSensor::affine_disparity; static constexpr CameraSensor::distortion_type_t distortion_type = CameraSensor::distortion_type_t::RadialTangential; public: std::string input; std::string plyfile; bool grey = true, rgb = true, depth = true, gt = true; explicit BONNReader(const std::string& name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the BONN dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY " "stream need to be include in the slam file.", &this->grey, nullptr)); this->addParameter(TypedParameter("rgb", "rgb", "set to true or false to specify if the RGB " "stream need to be include in the slam file.", &this->rgb, nullptr)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH " "stream need to be include in the slam file.", &this->depth, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH " "POSE stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("ply", "ply-file", "When a PLY file is specified, the GROUNDTRUTH POINT " "CLOUD will be included in the slam file.", &this->plyfile, nullptr)); } SLAMFile* GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_BONN_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/DatasetReader.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASETREADER_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASETREADER_H_ #include namespace slambench { namespace io { class SLAMFile; class DatasetReader : public ParameterComponent { public : typedef struct { const uint32_t width; const uint32_t height; const float rate; const float depthMapFactor; } image_params_t; DatasetReader(const std::string &name) : ParameterComponent(name) {} virtual slambench::io::SLAMFile *GenerateSLAMFile() = 0; }; } } #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASETREADER_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/ETHI.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ETHI_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ETHI_H_ #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class ETHIReader : public DatasetReader { public: std::string dataset = ""; explicit ETHIReader(const std::string &name) : DatasetReader(name) { this->addParameter(TypedParameter("dataset", "base-dataset", "If this is iclnuim or tum", &this->dataset, nullptr)); } SLAMFile *GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ETHI_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/EUROCMAV.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_EUROCMAV_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_EUROCMAV_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class EUROCMAVReader : public DatasetReader { private: static constexpr CameraSensor::intrinsics_t fr1_intrinsics_rgb = {0.9375, 1.25, 0.5, 0.5}; static constexpr DepthSensor::intrinsics_t fr1_intrinsics_depth = {0.9375, 1.25, 0.5, 0.5}; public: std::string input; bool imu = true, gt = true, stereo = true, rgb = false; explicit EUROCMAVReader(const std::string& name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the EUROCMAV dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("sgrey", "stereo-grey", "set to true or false to specify if the STEREO GREY " "stream need to be include in the slam file.", &this->stereo, nullptr)); this->addParameter(TypedParameter("srgb", "srgb", "set to true or false to specify if the STEREO RGB " "stream need to be include in the slam file.", &this->rgb, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH POSE " "stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("imu", "imu", "set to true or false to specify if the IMU " "stream need to be include in the slam file.", &this->imu, nullptr)); } SLAMFile* GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_EUROCMAV_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/ICL.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICL_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICL_H_ #include #include #include #include #include #include #include #include "../../dataset-tools/include/DatasetReader.h" namespace slambench { namespace io { class ICLReader : public DatasetReader { private : static constexpr CameraSensor::intrinsics_t fr1_intrinsics_rgb = { 0.9375, 1.25, 0.5, 0.5 }; static constexpr DepthSensor::intrinsics_t fr1_intrinsics_depth = { 0.9375, 1.25, 0.5, 0.5 }; public : std::string input; bool grey = true, rgb = true, depth = true, gt = true, accelerometer = false; ICLReader (std::string name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the ICL dataset directory", &this->input, NULL)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY stream need to be include in the slam file.", &this->grey, NULL)); this->addParameter(TypedParameter("rgb", "rgb", "set to true or false to specify if the RGB stream need to be include in the slam file.", &this->rgb, NULL)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH stream need to be include in the slam file.", &this->depth, NULL)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH POSE stream need to be include in the slam file.", &this->gt, NULL)); this->addParameter(TypedParameter("acc", "accelerometer", "set to true or false to specify if the ACCELEROMETER stream need to be include in the slam file.", &this->accelerometer, NULL)); } SLAMFile* GenerateSLAMFile () ; }; } } #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICL_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/ICLNUIM.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICLNUIM_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICLNUIM_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class ICLNUIMReader : public DatasetReader { private: CameraSensor *rgb_sensor = nullptr; DepthSensor *depth_sensor = nullptr; CameraSensor *grey_sensor = nullptr; GroundTruthSensor *gt_sensor = nullptr; std::ifstream istream; static constexpr DepthSensor::disparity_params_t disparity_params = {0.0002, 0.0}; static constexpr DepthSensor::disparity_type_t disparity_type = DepthSensor::affine_disparity; void AddSensors(SLAMFile &file); bool GetFrame(const std::string &dirname, SLAMFile &file, int frame_no); bool AddFrames(const std::string &dirname, SLAMFile &file); public: static constexpr image_params_t image_params = { 640, 480, 1, 5000.0 }; std::string input; bool grey = true, rgb = true, depth = true, gt = true; std::string plyfile = ""; bool positive_focal = false; explicit ICLNUIMReader(const std::string &name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the ICLNUIM dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY " "stream need to be include in the slam file.", &this->grey, nullptr)); this->addParameter(TypedParameter("rgb", "rgb", "set to true or false to specify if the RGB " "stream need to be include in the slam file.", &this->rgb, nullptr)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH " "stream need to be include in the slam file.", &this->depth, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the " "GROUNDTRUTH POSE stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("ply", "ply-file", "When a PLY file is specified, the GROUNDTRUTH POINT CLOUD " "will be included in the slam file.", &this->plyfile, nullptr)); this->addParameter(TypedParameter("pf", "positive-focal", "This is a workaround to correct the ICLNUIM " "to a positive focal length.", &this->positive_focal, nullptr)); } SLAMFile *GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_ICLNUIM_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/OpenLORIS.h ================================================ /* Copyright (c) 2019 Intel Corp. This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_OPENLORIS_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_OPENLORIS_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" #include #include #include #include namespace slambench { namespace io { const int INF = 99; typedef std::pair trans_direction; Eigen::Matrix4f compute_trans_matrix(const std::string &input_name_1, const std::string &input_name_2, const std::string &filename); class OpenLORISReader : public DatasetReader { public : std::string input; bool color = true, grey = true, depth = true, aligned_depth = true, fisheye1 = true, fisheye2 = true, d400_accel = true, d400_gyro = true, t265_accel = true, t265_gyro = true, odom = true, gt = true; OpenLORISReader(std::string name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the OpenLORIS dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY stream need to be include in the slam file.", &this->grey, nullptr)); this->addParameter(TypedParameter("color", "color", "set to true or false to specify if the RGB stream need to be include in the slam file.", &this->color, nullptr)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH stream need to be include in the slam file.", &this->depth, nullptr)); this->addParameter(TypedParameter("aligned_depth", "aligned_depth", "set to true or false to specify if the ALIGNED_DEPTH stream need to be include in the slam file.", &this->aligned_depth, nullptr)); this->addParameter(TypedParameter("fisheye1", "fisheye1", "set to true or false to specify if the FISHEYE1 stream need to be include in the slam file.", &this->fisheye1, nullptr)); this->addParameter(TypedParameter("fisheye2", "fisheye2", "set to true or false to specify if the FISHEYE2 GREY stream need to be include in the slam file.", &this->fisheye2, nullptr)); this->addParameter(TypedParameter("d400_accel", "d400_accelerometer", "set to true or false to specify if the D400_ACCELEROMETER stream need to be include in the slam file.", &this->d400_accel, nullptr)); this->addParameter(TypedParameter("d400_gyro", "d400_gyro", "set to true or false to specify if the D400_GYRO stream need to be include in the slam file.", &this->d400_gyro, nullptr)); this->addParameter(TypedParameter("t265_accel", "t265_accelerometer", "set to true or false to specify if the T265_ACCELEROMETER stream need to be include in the slam file.", &this->t265_accel, nullptr)); this->addParameter(TypedParameter("t265_gyro", "t265_gyro", "set to true or false to specify if the T265_GYRO stream need to be include in the slam file.", &this->t265_gyro, nullptr)); this->addParameter(TypedParameter("odom", "odom", "set to true or false to specify if the ODOMETRY stream need to be include in the slam file.", &this->odom, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH POSE stream need to be include in the slam file.", &this->gt, nullptr)); } SLAMFile* GenerateSLAMFile (); }; } } #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_OPENLORIS_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/SVO.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_SVO_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_SVO_H_ #include #include #include #include #include #include "DatasetReader.h" #include #include #include namespace slambench { namespace io { class SVOReader : public DatasetReader { private: static constexpr CameraSensor::intrinsics_t svo_grey = {0.419547872, 0.657291667, 0.5, 0.5}; // ATAN // static constexpr CameraSensor::intrinsics_t svo_grey = { 315.5, 315.5, 376.0, 240.0 }; // Pinhole static constexpr float translation[] = {0.1131, 0.1131, 2.0}; // x, y, z static constexpr float rotation[] = {0.0, 0.9675388, 0.2527226, 0.0}; // w, x, y, z public: std::string input; explicit SVOReader(const std::string& name) : DatasetReader(name) { this->addParameter(TypedParameter( "i", "input-directory", "path of the SVO dataset directory", &this->input, nullptr)); } SLAMFile* GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_SVO_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/TUM.h ================================================ /* Copyright (c) 2017-2020 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 The development of the interface with ROS datasets (rosbags) is supported by the RAIN Hub, which is funded by the Industrial Strategy Challenge Fund, part of the UK government’s modern Industrial Strategy. The fund is delivered by UK Research and Innovation and managed by EPSRC [EP/R026084/1]. This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_TUM_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_TUM_H_ #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class TUMReader : public DatasetReader { enum DatasetOrigin { Default = 0, Freiburg1, Freiburg2, Freiburg3, ETHI }; private: /**** * Taken from: * https://vision.in.tum.de/_media/spezial/bib/sturm12iros.pdf * data recorded on three Microsoft Xbox Kinect sensors * (freiburg1, freiburg2 and freiburg3) * at full resolution (640×480) and full frame rate (30 Hz) * depth images are expected to be scaled by a factor of 5000 [5000 : 1 m] * (no indication as to the reason). * */ static constexpr image_params_t fr_image_params = { 640, 480, 30.0, 5000.0 }; /**** * source of these parameters unknown */ static constexpr DepthSensor::disparity_params_t fr_disparity_params = { 0.0002, 0.0 }; static const DepthSensor::disparity_type_t fr_disparity_type = DepthSensor::affine_disparity; /**** * intrinsic parameters: focal length and optical center {fx, fy, cx, cy} * expressed as fractions of image width (fx and cx) and height (fy and cy) * Taken from: * https://vision.in.tum.de/data/datasets/rgbd-dataset/file_formats#intrinsic_camera_calibration_of_the_kinect * data recorded on three Microsoft Xbox Kinect sensors * (freiburg1, freiburg2 and freiburg3) Camera fx fy cx cy (ROS default) 525.0 525.0 319.5 239.5 Freiburg 1 RGB 517.3 516.5 318.6 255.3 Freiburg 2 RGB 520.9 521.0 325.1 249.7 Freiburg 3 RGB 535.4 539.2 320.1 247.6 ETHI RGB 538.7 540.7 319.2 233.6 Camera fx fy cx cy Freiburg 1 IR 591.1 590.1 331.0 234.0 Freiburg 2 IR 580.8 581.8 308.8 253.0 Freiburg 3 IR 567.6 570.2 324.7 250.1 ETHI IR 538.7 540.7 319.2 233.6 * */ static constexpr CameraSensor::intrinsics_t fr1_intrinsics_rgb = { 517.3 / fr_image_params.width, 516.5 / fr_image_params.height, 318.6 / fr_image_params.width, 255.3 / fr_image_params.height }; static constexpr CameraSensor::intrinsics_t fr2_intrinsics_rgb = { 520.9 / fr_image_params.width, 521.0 / fr_image_params.height, 325.1 / fr_image_params.width, 249.7 / fr_image_params.height }; static constexpr CameraSensor::intrinsics_t fr3_intrinsics_rgb = { 535.4 / fr_image_params.width, 539.2 / fr_image_params.height, 320.1 / fr_image_params.width, 247.6 / fr_image_params.height }; static constexpr CameraSensor::intrinsics_t ethi_intrinsics_rgb = {538.7 / fr_image_params.width, 540.7 / fr_image_params.height, 319.2 / fr_image_params.width, 233.6 / fr_image_params.height}; // default ROS values -- use with caution static constexpr CameraSensor::intrinsics_t default_intrinsics_rgb = { 525.0 / fr_image_params.width, 525.0 / fr_image_params.height, 319.5 / fr_image_params.width, 239.5 / fr_image_params.height }; // depth images are taken by the IR camera static constexpr DepthSensor::intrinsics_t fr1_intrinsics_depth = { 591.1 / fr_image_params.width, 590.1 / fr_image_params.height, 331.0 / fr_image_params.width, 234.0 / fr_image_params.height }; static constexpr DepthSensor::intrinsics_t fr2_intrinsics_depth = { 580.8 / fr_image_params.width, 581.8 / fr_image_params.height, 308.8 / fr_image_params.width, 253.0 / fr_image_params.height }; static constexpr DepthSensor::intrinsics_t fr3_intrinsics_depth = { 567.6 / fr_image_params.width, 570.2 / fr_image_params.height, 324.7 / fr_image_params.width, 250.1 / fr_image_params.height }; static constexpr DepthSensor::intrinsics_t ethi_intrinsics_depth = { 538.7 / fr_image_params.width, 540.7 / fr_image_params.height, 319.2 / fr_image_params.width, 233.6 / fr_image_params.height}; // default ROS values -- use with caution static constexpr DepthSensor::intrinsics_t default_intrinsics_depth = { 525.0 / fr_image_params.width, 525.0 / fr_image_params.height, 319.5 / fr_image_params.width, 239.5 / fr_image_params.height }; /**** * distortion parameters: radial and tangential factors {k1, k2, p1, p2, k3} * Taken from: * https://vision.in.tum.de/data/datasets/rgbd-dataset/file_formats#intrinsic_camera_calibration_of_the_kinect * data recorded on three Microsoft Xbox Kinect sensors (freiburg1, freiburg2 and freiburg3) Camera d0 d1 d2 d3 d4 (ROS default) 0.0 0.0 0.0 0.0 0.0 Freiburg 1 RGB 0.2624 -0.9531 -0.0054 0.0026 1.1633 Freiburg 2 RGB 0.2312 -0.7849 -0.0033 -0.0001 0.9172 Freiburg 3 RGB 0 0 0 0 0 ETHI RGB 0 0 0 0 0 Camera d0 d1 d2 d3 d4 Freiburg 1 IR -0.0410 0.3286 0.0087 0.0051 -0.5643 Freiburg 2 IR -0.2297 1.4766 0.0005 -0.0075 -3.4194 Freiburg 3 IR 0 0 0 0 0 ETHI IR 0 0 0 0 0 * */ static const CameraSensor::distortion_type_t camera_distortion_type = CameraSensor::RadialTangential; // these numbers taken from ORBSLAM2 examples // (appear to have higher precision than table above) static constexpr CameraSensor::distortion_coefficients_t fr1_distortion_rgb = { 0.262383, -0.953104, -0.005358, 0.002628 , 1.163314 }; static constexpr CameraSensor::distortion_coefficients_t fr2_distortion_rgb = { 0.231222, -0.784899, -0.003257, -0.000105, 0.917205 }; static constexpr CameraSensor::distortion_coefficients_t fr3_distortion_rgb = { 0.0, 0.0, 0.0, 0.0, 0.0 }; static constexpr CameraSensor::distortion_coefficients_t ethi_distortion_rgb = { 0.0, 0.0, 0.0, 0.0, 0.0 }; // default ROS values -- use with caution static constexpr CameraSensor::distortion_coefficients_t default_distortion_rgb = { 0.0, 0.0, 0.0, 0.0, 0.0 }; // depth images are pre-registered to the RGB images, thus rectifying // depth images based on intrinsic parameters is not straight forward // use RGB (not IR) distortion parameters as an approximation static constexpr DepthSensor::distortion_coefficients_t fr1_distortion_depth = { 0.262383 , -0.953104, -0.005358, 0.002628 , 1.163314 }; static constexpr DepthSensor::distortion_coefficients_t fr2_distortion_depth = { 0.231222, -0.784899, -0.003257, -0.000105, 0.917205 }; static constexpr DepthSensor::distortion_coefficients_t fr3_distortion_depth = { 0.0, 0.0, 0.0, 0.0, 0.0 }; static constexpr DepthSensor::distortion_coefficients_t ethi_distortion_depth = { 0.0, 0.0, 0.0, 0.0, 0.0 }; // default ROS values -- use with caution static constexpr DepthSensor::distortion_coefficients_t default_distortion_depth = { 0.0, 0.0, 0.0, 0.0, 0.0 }; public : std::string input; bool grey = true, rgb = true, depth = true, gt = true, accelerometer = true; explicit TUMReader(std::string name) : DatasetReader(std::move(name)) { this->addParameter(TypedParameter("i", "input-directory", "path of the TUM dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY stream need to be include in the slam file.", &this->grey, nullptr)); this->addParameter(TypedParameter("rgb", "rgb", "set to true or false to specify if the RGB stream need to be include in the slam file.", &this->rgb, nullptr)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH stream need to be include in the slam file.", &this->depth, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH POSE stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("acc", "accelerometer", "set to true or false to specify if the ACCELEROMETER stream need to be include in the slam file.", &this->accelerometer, nullptr)); } static image_params_t get_image_params () { return fr_image_params; } // these parameters depend on the particular kinect sensor used // return the kinect number (0 for default values) DatasetOrigin get_sensor_params(DepthSensor::disparity_params_t & depth_disparity_params, DepthSensor::disparity_type_t & depth_disparity_type, CameraSensor::intrinsics_t & rgb_intrinsics, DepthSensor::intrinsics_t & depth_intrinsics, CameraSensor::distortion_coefficients_t & rgb_distortion, DepthSensor::distortion_coefficients_t & depth_distortion, CameraSensor::distortion_type_t & distortion_type ) { for (uint32_t i = 0; i < 2; i++) { depth_disparity_params[i] = fr_disparity_params[i]; } depth_disparity_type = fr_disparity_type; distortion_type = camera_distortion_type; if (input.find("freiburg1") != std::string::npos) { for (uint32_t i = 0; i < 4; i++) { rgb_intrinsics[i] = fr1_intrinsics_rgb[i]; depth_intrinsics[i] = fr1_intrinsics_depth[i]; } for (uint32_t i = 0; i < 5; i++) { rgb_distortion[i] = fr1_distortion_rgb[i]; depth_distortion[i] = fr1_distortion_depth[i]; } return DatasetOrigin::Freiburg1; } if (input.find("freiburg2") != std::string::npos) { for (uint32_t i = 0; i < 4; i++) { rgb_intrinsics[i] = fr2_intrinsics_rgb[i]; depth_intrinsics[i] = fr2_intrinsics_depth[i]; } for (uint32_t i = 0; i < 5; i++) { rgb_distortion[i] = fr2_distortion_rgb[i]; depth_distortion[i] = fr2_distortion_depth[i]; } return DatasetOrigin::Freiburg2; } if (input.find("freiburg3") != std::string::npos) { for (uint32_t i = 0; i < 4; i++) { rgb_intrinsics[i] = fr3_intrinsics_rgb[i]; depth_intrinsics[i] = fr3_intrinsics_depth[i]; } for (uint32_t i = 0; i < 5; i++) { rgb_distortion[i] = fr3_distortion_rgb[i]; depth_distortion[i] = fr3_distortion_depth[i]; } return DatasetOrigin::Freiburg3; } if (input.find("ethi") != std::string::npos) { for (uint32_t i = 0; i < 4; i++) { rgb_intrinsics[i] = ethi_intrinsics_rgb[i]; depth_intrinsics[i] = ethi_intrinsics_depth[i]; } for (uint32_t i = 0; i < 5; i++) { rgb_distortion[i] = ethi_distortion_rgb[i]; depth_distortion[i] = ethi_distortion_depth[i]; } return DatasetOrigin::ETHI; } // use default parameters for (uint32_t i = 0; i < 4; i++) { rgb_intrinsics[i] = default_intrinsics_rgb[i]; depth_intrinsics[i] = default_intrinsics_depth[i]; } for (uint32_t i = 0; i < 5; i++) { rgb_distortion[i] = default_distortion_rgb[i]; depth_distortion[i] = default_distortion_depth[i]; } return DatasetOrigin::Default; } SLAMFile *GenerateSLAMFile() override; }; /**** * reader used to process TUM rosbags * image and sensor parameters derived from TUMReader */ class TUMROSBAGReader : public TUMReader { public: typedef struct { const std::string world; const std::string kinect; const std::string camera; const std::string rgb; const std::string optical; } gt_frame_ids_t; private: // ROS topic associated with each sensor const std::string depth_topic = "/camera/depth/image"; const std::string rgb_topic = "/camera/rgb/image_color"; const std::string gt_topic = "/tf"; const std::string acc_topic = "/imu"; // the ground truth topic (/tf) contains several transformations // ground truth is built from the following composition: // optical frame -> rgb frame -> camera -> kinect -> world const gt_frame_ids_t gt_frame_ids = { "/world", "/kinect", "/openni_camera", "/openni_rgb_frame", "/openni_rgb_optical_frame" }; public : explicit TUMROSBAGReader(std::string name) : TUMReader(std::move(name)) { } SLAMFile * GenerateSLAMFile() override; }; } } #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_TUM_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/UZHFPV.h ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UZHFPV_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UZHFPV_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class UZHFPVReader : public DatasetReader { private: // Parameters taken from indoor_forward calibration file: camchain-..indoor_forward_calib_snapdragon_cam.yaml static constexpr CameraSensor::intrinsics_t snapdragon_cam0_intrinsics = {278.66723066149086, 278.48991409740296, 319.75221200593535, 241.96858910358173}; static constexpr CameraSensor::distortion_coefficients_t snapdragon_cam0_distortion = {-0.013721808247486035, 0.020727425669427896, -0.012786476702685545, 0.0025242267320687625}; static constexpr CameraSensor::intrinsics_t snapdragon_cam1_intrinsics = {277.61640629770613, 277.63749695723294, 314.8944703346039, 236.04310050462587}; static constexpr CameraSensor::distortion_coefficients_t snapdragon_cam1_distortion = {-0.008456929295619607, 0.011407590938612062, -0.006951788325762078, 0.0015368127092821786}; // Parameters taken from indoor_forward calibration file: camchain-..indoor_forward_calib_davis_cam.yaml static constexpr CameraSensor::intrinsics_t davis_intrinsics = {172.98992850734132, 172.98303181090185, 163.33639726024606, 134.99537889030861}; static constexpr CameraSensor::distortion_coefficients_t davis_distortion = {-0.027576733308582076, -0.006593578674675004, 0.0008566938165177085, -0.00030899587045247486}; public: std::string input; bool imu = true, gt = false, stereo = false, events = false; explicit UZHFPVReader(const std::string& name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the UZHFPV dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("s", "stereo", "set to true or false to specify if the STEREO " "stream need to be include in the slam file.", &this->stereo, nullptr)); this->addParameter(TypedParameter("e", "event", "set to true or false to specify if the EVENT " "stream need to be include in the slam file.", &this->events, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH POSE " "stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("imu", "imu", "set to true or false to specify if the IMU " "stream need to be include in the slam file.", &this->imu, nullptr)); } SLAMFile* GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UZHFPV_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/VolumeDeform.h ================================================ /* Copyright (c) 2020 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_VOLUMEDEFORM_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_VOLUMEDEFORM_H_ #include #include #include #include #include #include #include #include "DatasetReader.h" namespace slambench { namespace io { class VolumeDeformReader : public DatasetReader { private: static constexpr image_params_t image_params = { 640, 480, 30.0, 1000.0 }; // fx,fy,cx,cy same for rgb and depth static constexpr CameraSensor::intrinsics_t intrinsics = {570.0 / image_params.width, 570.0 / image_params.height, 320.0 / image_params.width, 240.0 / image_params.height}; public: std::string input; std::string plyfile; bool grey = true, rgb = true, depth = true, gt = true; bool GetFrame(const std::string &dirname, int frame_no, SLAMFile &file, std::ifstream& infile, CameraSensor* rgb_sensor = nullptr, CameraSensor* grey_sensor = nullptr, DepthSensor* depth_sensor = nullptr, GroundTruthSensor* gt_sensor = nullptr); explicit VolumeDeformReader(const std::string& name) : DatasetReader(name) { this->addParameter(TypedParameter("i", "input-directory", "path of the VolumeDeform dataset directory", &this->input, nullptr)); this->addParameter(TypedParameter("grey", "grey", "set to true or false to specify if the GREY " "stream need to be include in the slam file.", &this->grey, nullptr)); this->addParameter(TypedParameter("rgb", "rgb", "set to true or false to specify if the RGB " "stream need to be include in the slam file.", &this->rgb, nullptr)); this->addParameter(TypedParameter("depth", "depth", "set to true or false to specify if the DEPTH " "stream need to be include in the slam file.", &this->depth, nullptr)); this->addParameter(TypedParameter("gt", "gt", "set to true or false to specify if the GROUNDTRUTH " "POSE stream need to be include in the slam file.", &this->gt, nullptr)); this->addParameter(TypedParameter("ply", "ply-file", "When a PLY file is specified, the GROUNDTRUTH POINT " "CLOUD will be included in the slam file.", &this->plyfile, nullptr)); } SLAMFile* GenerateSLAMFile() override; }; } // namespace io } // namespace slambench #endif /* FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_VOLUMEDEFORM_H_ */ ================================================ FILE: framework/tools/dataset-tools/include/utils/PlyASCIIReader.h ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UTILS_PLYASCIIREADER_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UTILS_PLYASCIIREADER_H_ #include #include #include #include #include #include #include "timings.h" // Due to -Werror flag the implementation of tinyply fails, these directive allow it to build #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wswitch" #pragma GCC diagnostic ignored "-Wsign-compare" #define TINYPLY_IMPLEMENTATION #include "./tinyply.h" #pragma GCC diagnostic pop class PlyASCIIReader { public: static slambench::io::PointCloud* read(const std::string &filepath) { using namespace tinyply; using namespace slambench::io; std::ifstream ss(filepath, std::ios::binary); if (ss.fail()) { throw std::runtime_error("failed to open " + filepath); } PlyFile file; file.parse_header(ss); std::cout << "Reading ASCII Plyfile: " << filepath << std::endl; std::cout << "........................................................................\n"; for (const auto& c : file.get_comments()) std::cout << "Comment: " << c << std::endl; for (const auto& e : file.get_elements()) { std::cout << "element - " << e.name << " (" << e.size << ")" << std::endl; for (const auto& p : e.properties) { std::cout << "\tproperty - " << p.name << " (" << tinyply::PropertyTable[p.propertyType].str << ")" << std::endl; } } std::cout << "........................................................................\n"; // tinyply treats parsed data as untyped byte buffers. std::shared_ptr points_data; const int list_size_hint = 54000000; try { points_data = file.request_properties_from_element("vertex", {"x", "y", "z" }, list_size_hint); } catch (const std::exception & e) { std::cerr << "tinyply exception: " << e.what() << std::endl; } double start = tock(); file.read(ss); double end = tock(); std::cout << "Reading took " << (end-start) << " seconds." << std::endl; std::cout << "Read " << points_data->count << " total points "<< std::endl; // move from untyped bytes buffers to point objects const size_t numBytes = points_data->buffer.size_bytes(); std::vector points(points_data->count); std::copy(points_data->buffer.get(), points_data->buffer.get() + numBytes, reinterpret_cast(points.data())); // create pointcloud and assign points auto pc = new PointCloud(); pc->Get() = points; return pc; } }; #endif // FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_UTILS_PLYASCIIREADER_H_ ================================================ FILE: framework/tools/dataset-tools/include/utils/RegexPattern.h ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_REGEXPATTERN_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_REGEXPATTERN_H_ class RegexPattern { public: // characters static constexpr auto start = "^"; static constexpr auto end = "$"; // components static constexpr auto whitespace = "\\s+"; static constexpr auto integer = "(\\d+)"; static constexpr auto decimal = "([-0-9.]+)"; static constexpr auto nanoseconds = "([0-9]+)"; static constexpr auto number = R"(([+\-]?(?:0|[1-9]\d*)(?:\.\d*)?(?:[eE][+\-]?\d+)?|[-0-9.]+))"; static constexpr auto timestamp = "([0-9]+)[.]([0-9]+)"; static constexpr auto filename = "(.*)"; static constexpr auto lowercase_key = "([a-z_]+)"; // full patterns static constexpr auto comment = "^\\s*#.*$"; }; #endif ================================================ FILE: framework/tools/dataset-tools/include/utils/dataset_utils.h ================================================ /* Copyright (c) 2019 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifndef FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASET_UTILS_H_ #define FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASET_UTILS_H_ #include namespace slambench { namespace io { /** * Check for files and folders in a given directory and return true iff all exist * * @param directory_name directory to check for requirements * @param required vector of names of required files / folders */ inline bool checkRequirements(const std::string& directory_name, const std::vector& requirements) { try { if (!boost::filesystem::exists(directory_name)) return false; for (auto const &requirement : requirements) { auto fullpath = directory_name+"/"+requirement; if (!boost::filesystem::exists(fullpath)) { std::cout << "File not found:" << fullpath << std::endl; return false; } } } catch (boost::filesystem::filesystem_error &e) { std::cerr << "I/O Error with directory " << directory_name << std::endl; std::cerr << e.what() << std::endl; return false; } return true; } } // namespace io } // namespace slambench #endif // FRAMEWORK_TOOLS_DATASET_TOOLS_INCLUDE_DATASET_UTILS_H_ ================================================ FILE: framework/tools/dataset-tools/include/utils/tinyply.h ================================================ /* * tinyply 2.2 (https://github.com/ddiakopoulos/tinyply) * * A single-header, zero-dependency (except the C++ STL) public domain implementation * of the PLY mesh file format. Requires C++11; errors are handled through exceptions. * * This software is in the public domain. Where that dedication is not * recognized, you are granted a perpetual, irrevocable license to copy, * distribute, and modify this file as you see fit. * * Authored by Dimitri Diakopoulos (http://www.dimitridiakopoulos.com) * * tinyply.h may be included in many files, however in a single compiled file, * the implementation must be created with the following defined * before including the header. * #define TINYPLY_IMPLEMENTATION */ //////////////////////// // tinyply header // //////////////////////// #ifndef tinyply_h #define tinyply_h #include #include #include #include #include #include #include namespace tinyply { enum class Type : uint8_t { INVALID, INT8, UINT8, INT16, UINT16, INT32, UINT32, FLOAT32, FLOAT64 }; struct PropertyInfo { int stride; std::string str; }; static std::map PropertyTable { { Type::INT8, { 1, "char" } }, { Type::UINT8, { 1, "uchar" } }, { Type::INT16, { 2, "short" } }, { Type::UINT16, { 2, "ushort" } }, { Type::INT32, { 4, "int" } }, { Type::UINT32, { 4, "uint" } }, { Type::FLOAT32, { 4, "float" } }, { Type::FLOAT64, { 8, "double" } }, { Type::INVALID, { 0, "INVALID" } } }; class Buffer { uint8_t * alias{ nullptr }; struct delete_array { void operator()(uint8_t * p) { delete[] p; } }; std::unique_ptr data; size_t size; public: Buffer() {}; Buffer(const size_t size) : data(new uint8_t[size], delete_array()), size(size) { alias = data.get(); } // allocating Buffer(uint8_t * ptr) { alias = ptr; } // non-allocating, todo: set size? uint8_t * get() { return alias; } size_t size_bytes() const { return size; } }; struct PlyData { Type t; size_t count; Buffer buffer; bool isList; }; struct PlyProperty { PlyProperty(std::istream & is); PlyProperty(Type type, std::string & _name) : name(_name), propertyType(type) {} PlyProperty(Type list_type, Type prop_type, std::string & _name, size_t list_count) : name(_name), propertyType(prop_type), isList(true), listType(list_type), listCount(list_count) {} std::string name; Type propertyType; bool isList{ false }; Type listType{ Type::INVALID }; size_t listCount{ 0 }; }; struct PlyElement { PlyElement(std::istream & istream); PlyElement(const std::string & _name, size_t count) : name(_name), size(count) {} std::string name; size_t size; std::vector properties; }; struct PlyFile { struct PlyFileImpl; std::unique_ptr impl; PlyFile(); ~PlyFile(); /* * The ply format requires an ascii header. This can be used to determine at * runtime which properties or elements exist in the file. Limited validation of the * header is performed; it is assumed the header correctly reflects the contents of the * payload. This function may throw. Returns true on success, false on failure. */ bool parse_header(std::istream & is); /* * Execute a read operation. Data must be requested via `request_properties_from_element(...)` * prior to calling this function. */ void read(std::istream & is); /* * `write` performs no validation and assumes that the data passed into * `add_properties_to_element` is well-formed. */ void write(std::ostream & os, bool isBinary); /* * These functions are valid after a call to `parse_header(...)`. In the case of * writing, get_comments() may also be used to add new comments to the ply header. */ std::vector get_elements() const; std::vector get_info() const; std::vector & get_comments(); /* * In the general case where |list_size_hint| is zero, `read` performs a two-pass * parse to support variable length lists. The most general use of the * ply format is storing triangle meshes. When this fact is known a-priori, we can pass * an expected list length that will apply to this element. Doing so results in an up-front * memory allocation and a single-pass import, a 2x performance optimization. */ std::shared_ptr request_properties_from_element(const std::string & elementKey, const std::initializer_list propertyKeys, const uint32_t list_size_hint = 0); void add_properties_to_element(const std::string & elementKey, const std::initializer_list propertyKeys, const Type type, const size_t count, uint8_t * data, const Type listType, const size_t listCount); }; } // end namespace tinyply #endif // end tinyply_h //////////////////////////////// // tinyply implementation // //////////////////////////////// #ifdef TINYPLY_IMPLEMENTATION #include #include #include #include #include using namespace tinyply; using namespace std; template inline T2 endian_swap(const T & v) { return v; } template<> inline uint16_t endian_swap(const uint16_t & v) { return (v << 8) | (v >> 8); } template<> inline uint32_t endian_swap(const uint32_t & v) { return (v << 24) | ((v << 8) & 0x00ff0000) | ((v >> 8) & 0x0000ff00) | (v >> 24); } template<> inline uint64_t endian_swap(const uint64_t & v) { return (((v & 0x00000000000000ffLL) << 56) | ((v & 0x000000000000ff00LL) << 40) | ((v & 0x0000000000ff0000LL) << 24) | ((v & 0x00000000ff000000LL) << 8) | ((v & 0x000000ff00000000LL) >> 8) | ((v & 0x0000ff0000000000LL) >> 24) | ((v & 0x00ff000000000000LL) >> 40) | ((v & 0xff00000000000000LL) >> 56)); } template<> inline int16_t endian_swap(const int16_t & v) { uint16_t r = endian_swap(*(uint16_t*)&v); return *(int16_t*)&r; } template<> inline int32_t endian_swap(const int32_t & v) { uint32_t r = endian_swap(*(uint32_t*)&v); return *(int32_t*)&r; } template<> inline int64_t endian_swap(const int64_t & v) { uint64_t r = endian_swap(*(uint64_t*)&v); return *(int64_t*)&r; } template<> inline float endian_swap(const uint32_t & v) { union { float f; uint32_t i; }; i = endian_swap(v); return f; } template<> inline double endian_swap(const uint64_t & v) { union { double d; uint64_t i; }; i = endian_swap(v); return d; } inline uint32_t hash_fnv1a(const std::string & str) { static const uint32_t fnv1aBase32 = 0x811C9DC5u; static const uint32_t fnv1aPrime32 = 0x01000193u; uint32_t result = fnv1aBase32; for (auto & c : str) { result ^= static_cast(c); result *= fnv1aPrime32; } return result; } inline Type property_type_from_string(const std::string & t) { if (t == "int8" || t == "char") return Type::INT8; else if (t == "uint8" || t == "uchar") return Type::UINT8; else if (t == "int16" || t == "short") return Type::INT16; else if (t == "uint16" || t == "ushort") return Type::UINT16; else if (t == "int32" || t == "int") return Type::INT32; else if (t == "uint32" || t == "uint") return Type::UINT32; else if (t == "float32" || t == "float") return Type::FLOAT32; else if (t == "float64" || t == "double") return Type::FLOAT64; return Type::INVALID; } typedef std::function cast_t; struct PlyFile::PlyFileImpl { struct PlyDataCursor { size_t byteOffset{ 0 }; size_t totalSizeBytes{ 0 }; }; struct ParsingHelper { std::shared_ptr data; std::shared_ptr cursor; uint32_t list_size_hint; }; struct PropertyLookup { ParsingHelper * helper{ nullptr }; bool skip{ false }; size_t prop_stride{ 0 }; // precomputed size_t list_stride{ 0 }; // precomputed }; std::unordered_map userData; bool isBinary = false; bool isBigEndian = false; std::vector elements; std::vector comments; std::vector objInfo; uint8_t scratch[64]; // large enough for max list size void read(std::istream & is); void write(std::ostream & os, bool isBinary); std::shared_ptr request_properties_from_element(const std::string & elementKey, const std::initializer_list propertyKeys, const uint32_t list_size_hint); void add_properties_to_element(const std::string & elementKey, const std::initializer_list propertyKeys, const Type type, const size_t count, uint8_t * data, const Type listType, const size_t listCount); size_t read_property_binary(const Type & t, const size_t & stride, void * dest, size_t & destOffset, std::istream & is); size_t read_property_ascii(const Type & t, const size_t & stride, void * dest, size_t & destOffset, std::istream & is); std::vector> make_property_lookup_table() { std::vector> element_property_lookup; for (auto & element : elements) { std::vector lookups; for (auto & property : element.properties) { PropertyLookup f; auto cursorIt = userData.find(hash_fnv1a(element.name + property.name)); if (cursorIt != userData.end()) f.helper = &cursorIt->second; else f.skip = true; f.prop_stride = PropertyTable[property.propertyType].stride; if (property.isList) f.list_stride = PropertyTable[property.listType].stride; lookups.push_back(f); } element_property_lookup.push_back(lookups); } return element_property_lookup; } bool parse_header(std::istream & is); void parse_data(std::istream & is, bool firstPass); void read_header_format(std::istream & is); void read_header_element(std::istream & is); void read_header_property(std::istream & is); void read_header_text(std::string line, std::istream & is, std::vector & place, int erase = 0); void write_header(std::ostream & os); void write_ascii_internal(std::ostream & os); void write_binary_internal(std::ostream & os); void write_property_ascii(Type t, std::ostream & os, uint8_t * src, size_t & srcOffset); void write_property_binary(Type t, std::ostream & os, uint8_t * src, size_t & srcOffset, const size_t & stride); }; PlyProperty::PlyProperty(std::istream & is) : isList(false) { std::string type; is >> type; if (type == "list") { std::string countType; is >> countType >> type; listType = property_type_from_string(countType); isList = true; } propertyType = property_type_from_string(type); is >> name; } PlyElement::PlyElement(std::istream & is) { is >> name >> size; } template inline T ply_read_ascii(std::istream & is) { T data; is >> data; return data; } template inline void endian_swap_buffer(uint8_t * data_ptr, const size_t num_bytes, const size_t stride) { for (size_t count = 0; count < num_bytes; count += stride) { *(reinterpret_cast(data_ptr)) = endian_swap(*(reinterpret_cast(data_ptr))); data_ptr += stride; } } template void ply_cast_ascii(void * dest, std::istream & is) { *(static_cast(dest)) = ply_read_ascii(is); } int64_t find_element(const std::string & key, const std::vector & list) { for (size_t i = 0; i < list.size(); i++) if (list[i].name == key) return i; return -1; } int64_t find_property(const std::string & key, const std::vector & list) { for (size_t i = 0; i < list.size(); ++i) if (list[i].name == key) return i; return -1; } bool PlyFile::PlyFileImpl::parse_header(std::istream & is) { std::string line; while (std::getline(is, line)) { std::istringstream ls(line); std::string token; ls >> token; if (token == "ply" || token == "PLY" || token == "") continue; else if (token == "comment") read_header_text(line, ls, comments, 8); else if (token == "format") read_header_format(ls); else if (token == "element") read_header_element(ls); else if (token == "property") read_header_property(ls); else if (token == "obj_info") read_header_text(line, ls, objInfo, 9); else if (token == "end_header") break; else return false; // unexpected header field } return true; } void PlyFile::PlyFileImpl::read_header_text(std::string line, std::istream & is, std::vector& place, int erase) { place.push_back((erase > 0) ? line.erase(0, erase) : line); } void PlyFile::PlyFileImpl::read_header_format(std::istream & is) { std::string s; (is >> s); if (s == "binary_little_endian") isBinary = true; else if (s == "binary_big_endian") isBinary = isBigEndian = true; } void PlyFile::PlyFileImpl::read_header_element(std::istream & is) { elements.emplace_back(is); } void PlyFile::PlyFileImpl::read_header_property(std::istream & is) { if (!elements.size()) throw std::runtime_error("no elements defined; file is malformed"); elements.back().properties.emplace_back(is); } size_t PlyFile::PlyFileImpl::read_property_binary(const Type & t, const size_t & stride, void * dest, size_t & destOffset, std::istream & is) { destOffset += stride; is.read((char*)dest, stride); return stride; } size_t PlyFile::PlyFileImpl::read_property_ascii(const Type & t, const size_t & stride, void * dest, size_t & destOffset, std::istream & is) { destOffset += stride; switch (t) { case Type::INT8: *((int8_t *)dest) = ply_read_ascii(is); break; case Type::UINT8: *((uint8_t *)dest) = ply_read_ascii(is); break; case Type::INT16: ply_cast_ascii(dest, is); break; case Type::UINT16: ply_cast_ascii(dest, is); break; case Type::INT32: ply_cast_ascii(dest, is); break; case Type::UINT32: ply_cast_ascii(dest, is); break; case Type::FLOAT32: ply_cast_ascii(dest, is); break; case Type::FLOAT64: ply_cast_ascii(dest, is); break; case Type::INVALID: throw std::invalid_argument("invalid ply property"); } return stride; } void PlyFile::PlyFileImpl::write_property_ascii(Type t, std::ostream & os, uint8_t * src, size_t & srcOffset) { switch (t) { case Type::INT8: os << static_cast(*reinterpret_cast(src)); break; case Type::UINT8: os << static_cast(*reinterpret_cast(src)); break; case Type::INT16: os << *reinterpret_cast(src); break; case Type::UINT16: os << *reinterpret_cast(src); break; case Type::INT32: os << *reinterpret_cast(src); break; case Type::UINT32: os << *reinterpret_cast(src); break; case Type::FLOAT32: os << *reinterpret_cast(src); break; case Type::FLOAT64: os << *reinterpret_cast(src); break; case Type::INVALID: throw std::invalid_argument("invalid ply property"); } os << " "; srcOffset += PropertyTable[t].stride; } void PlyFile::PlyFileImpl::write_property_binary(Type t, std::ostream & os, uint8_t * src, size_t & srcOffset, const size_t & stride) { os.write((char *)src, stride); srcOffset += stride; } void PlyFile::PlyFileImpl::read(std::istream & is) { std::vector> buffers; for (auto & entry : userData) buffers.push_back(entry.second.data); // Discover if we can allocate up front without parsing the file twice uint32_t list_hints = 0; for (auto & b : buffers) for (auto & entry : userData) list_hints += entry.second.list_size_hint; // No list hints? Then we need to calculate how much memory to allocate if (list_hints == 0) parse_data(is, true); // Count the number of properties (required for allocation) // e.g. if we have properties x y and z requested, we ensure // that their buffer points to the same PlyData std::unordered_map unique_data_count; for (auto & ptr : buffers) unique_data_count[ptr.get()] += 1; // Since group-requested properties share the same cursor, // we need to find unique cursors so we only allocate once std::sort(buffers.begin(), buffers.end()); buffers.erase(std::unique(buffers.begin(), buffers.end()), buffers.end()); // We sorted by ptrs on PlyData, need to remap back onto its cursor in the userData table for (auto & b : buffers) { for (auto & entry : userData) { if (entry.second.data == b && b->buffer.get() == nullptr) { // If we didn't receive any list hints, it means we did two passes over the // file to compute the total length of all (potentially) variable-length lists if (list_hints == 0) { b->buffer = Buffer(entry.second.cursor->totalSizeBytes); } else { // otherwise, we can allocate up front, skipping the first pass. const size_t list_size_multiplier = (entry.second.data->isList ? entry.second.list_size_hint : 1); auto bytes_per_property = entry.second.data->count * PropertyTable[entry.second.data->t].stride * list_size_multiplier; bytes_per_property *= unique_data_count[b.get()]; b->buffer = Buffer(bytes_per_property); } } } } // Populate the data parse_data(is, false); if (isBigEndian) { for (auto & b : buffers) { uint8_t * data_ptr = b->buffer.get(); const size_t stride = PropertyTable[b->t].stride; const size_t buffer_size_bytes = b->buffer.size_bytes(); switch (b->t) { case Type::INT16: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; case Type::UINT16: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; case Type::INT32: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; case Type::UINT32: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; case Type::FLOAT32: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; case Type::FLOAT64: endian_swap_buffer(data_ptr, buffer_size_bytes, stride); break; } } } } void PlyFile::PlyFileImpl::write(std::ostream & os, bool _isBinary) { // reset cursors for (auto & d : userData) { d.second.cursor->byteOffset = 0; } if (_isBinary) write_binary_internal(os); else write_ascii_internal(os); } void PlyFile::PlyFileImpl::write_binary_internal(std::ostream & os) { isBinary = true; write_header(os); uint8_t listSize[4] = { 0, 0, 0, 0 }; size_t dummyCount = 0; auto element_property_lookup = make_property_lookup_table(); size_t element_idx = 0; for (auto & e : elements) { for (size_t i = 0; i < e.size; ++i) { size_t property_index = 0; for (auto & p : e.properties) { auto & f = element_property_lookup[element_idx][property_index]; auto * helper = f.helper; if (p.isList) { std::memcpy(listSize, &p.listCount, sizeof(uint32_t)); write_property_binary(p.listType, os, listSize, dummyCount, f.list_stride); write_property_binary(p.propertyType, os, (helper->data->buffer.get() + helper->cursor->byteOffset), helper->cursor->byteOffset, f.prop_stride * p.listCount); } else { write_property_binary(p.propertyType, os, (helper->data->buffer.get() + helper->cursor->byteOffset), helper->cursor->byteOffset, f.prop_stride); } property_index++; } } element_idx++; } } void PlyFile::PlyFileImpl::write_ascii_internal(std::ostream & os) { write_header(os); for (auto & e : elements) { for (size_t i = 0; i < e.size; ++i) { for (auto & p : e.properties) { auto & helper = userData[hash_fnv1a(e.name + p.name)]; if (p.isList) { os << p.listCount << " "; for (int j = 0; j < p.listCount; ++j) { write_property_ascii(p.propertyType, os, (helper.data->buffer.get() + helper.cursor->byteOffset), helper.cursor->byteOffset); } } else { write_property_ascii(p.propertyType, os, (helper.data->buffer.get() + helper.cursor->byteOffset), helper.cursor->byteOffset); } } os << "\n"; } } } void PlyFile::PlyFileImpl::write_header(std::ostream & os) { const std::locale & fixLoc = std::locale("C"); os.imbue(fixLoc); os << "ply\n"; if (isBinary) os << ((isBigEndian) ? "format binary_big_endian 1.0" : "format binary_little_endian 1.0") << "\n"; else os << "format ascii 1.0\n"; for (const auto & comment : comments) os << "comment " << comment << "\n"; for (auto & e : elements) { os << "element " << e.name << " " << e.size << "\n"; for (const auto & p : e.properties) { if (p.isList) { os << "property list " << PropertyTable[p.listType].str << " " << PropertyTable[p.propertyType].str << " " << p.name << "\n"; } else { os << "property " << PropertyTable[p.propertyType].str << " " << p.name << "\n"; } } } os << "end_header\n"; } std::shared_ptr PlyFile::PlyFileImpl::request_properties_from_element(const std::string & elementKey, const std::initializer_list propertyKeys, const uint32_t list_size_hint) { // Each key in `propertyKey` gets an entry into the userData map (keyed by a hash of // element name and property name), but groups of properties (requested from the // public api through this function) all share the same `ParsingHelper`. When it comes // time to .read(), we check the number of unique PlyData shared pointers // and allocate a single buffer that will be used by each individual property. ParsingHelper helper; helper.data = std::make_shared(); helper.data->count = 0; helper.data->isList = false; helper.data->t = Type::INVALID; helper.cursor = std::make_shared(); helper.list_size_hint = list_size_hint; if (elements.empty()) throw std::runtime_error("header had no elements defined. malformed file?"); if (elementKey.empty()) throw std::invalid_argument("`elementKey` argument is empty"); if (!propertyKeys.size()) throw std::invalid_argument("`propertyKeys` argument is empty"); const int64_t elementIndex = find_element(elementKey, elements); std::vector keys_not_found; // Sanity check if the user requested element is in the pre-parsed header if (elementIndex >= 0) { // We found the element const PlyElement & element = elements[elementIndex]; helper.data->count = element.size; // Find each of the keys for (auto key : propertyKeys) { const int64_t propertyIndex = find_property(key, element.properties); if (propertyIndex >= 0) { // We found the property const PlyProperty & property = element.properties[propertyIndex]; helper.data->t = property.propertyType; helper.data->isList = property.isList; auto result = userData.insert(std::pair(hash_fnv1a(element.name + property.name), helper)); if (result.second == false) { throw std::invalid_argument("element-property key has already been requested: " + hash_fnv1a(element.name + property.name)); } } else keys_not_found.push_back(key); } } else throw std::invalid_argument("the element key was not found in the header: " + elementKey); if (keys_not_found.size()) { std::stringstream ss; for (auto & str : keys_not_found) ss << str << ", "; throw std::invalid_argument("the following property keys were not found in the header: " + ss.str()); } return helper.data; } void PlyFile::PlyFileImpl::add_properties_to_element(const std::string & elementKey, const std::initializer_list propertyKeys, const Type type, const size_t count, uint8_t * data, const Type listType, const size_t listCount) { ParsingHelper helper; helper.data = std::make_shared(); helper.data->count = count; helper.data->t = type; helper.data->buffer = Buffer(data); helper.cursor = std::make_shared(); auto create_property_on_element = [&](PlyElement & e) { for (auto key : propertyKeys) { PlyProperty newProp = (listType == Type::INVALID) ? PlyProperty(type, key) : PlyProperty(listType, type, key, listCount); userData.insert(std::pair(hash_fnv1a(elementKey + key), helper)); e.properties.push_back(newProp); } }; const int64_t idx = find_element(elementKey, elements); if (idx >= 0) { PlyElement & e = elements[idx]; create_property_on_element(e); } else { PlyElement newElement = (listType == Type::INVALID) ? PlyElement(elementKey, count) : PlyElement(elementKey, count); create_property_on_element(newElement); elements.push_back(newElement); } } void PlyFile::PlyFileImpl::parse_data(std::istream & is, bool firstPass) { std::function read; std::function skip; const auto start = is.tellg(); size_t listSize = 0; size_t dummyCount = 0; std::string skip_ascii_buffer; // Special case mirroring read_property_binary but for list types; this // has an additional big endian check to flip the data in place immediately // after reading. We do this as a performance optimization; endian flipping is // done on regular properties as a post-process after reading (also for optimization) // but we need the correct little-endian list count as we read the file. auto read_list_binary = [this](const Type & t, void * dst, size_t & destOffset, std::istream & _is) { const size_t stride = PropertyTable[t].stride; // @todo - this is already precomputed destOffset += stride; _is.read((char*)dst, stride); if (isBigEndian) { switch (t) { case Type::INT16: endian_swap(*(int16_t*)dst); break; case Type::UINT16: endian_swap(*(uint16_t*)dst); break; case Type::INT32: endian_swap(*(int32_t*)dst); break; case Type::UINT32: endian_swap(*(uint32_t*)dst); break; } } return stride; }; if (isBinary) { read = [this, &listSize, &dummyCount, &read_list_binary](PropertyLookup & f, const PlyProperty & p, uint8_t * dest, size_t & destOffset, std::istream & _is) { if (!p.isList) { read_property_binary(p.propertyType, f.prop_stride, dest + destOffset, destOffset, _is); } else { read_list_binary(p.listType, &listSize, dummyCount, _is); // the list size read_property_binary(p.propertyType, f.prop_stride * listSize, dest + destOffset, destOffset, _is); // properties in list } }; skip = [this, &listSize, &dummyCount, &read_list_binary](PropertyLookup & f, const PlyProperty & p, std::istream & _is) { if (!p.isList) { _is.read((char*)scratch, f.prop_stride); return f.prop_stride; } read_list_binary(p.listType, &listSize, dummyCount, _is); // the list size (does not count for memory alloc) return read_property_binary(p.propertyType, f.prop_stride * listSize, scratch, dummyCount, _is); }; } else { read = [this, &listSize, &dummyCount](PropertyLookup & f, const PlyProperty & p, uint8_t * dest, size_t & destOffset, std::istream & _is) { if (!p.isList) { read_property_ascii(p.propertyType, f.prop_stride, dest + destOffset, destOffset, _is); } else { read_property_ascii(p.listType, f.list_stride, &listSize, dummyCount, _is); // the list size for (size_t i = 0; i < listSize; ++i) { read_property_ascii(p.propertyType, f.prop_stride, dest + destOffset, destOffset, _is); } } }; skip = [this, &listSize, &dummyCount, &skip_ascii_buffer](PropertyLookup & f, const PlyProperty & p, std::istream & _is) { skip_ascii_buffer.clear(); if (p.isList) { read_property_ascii(p.listType, f.list_stride, &listSize, dummyCount, _is); // the list size for (size_t i = 0; i < listSize; ++i) _is >> skip_ascii_buffer; // properties in list return listSize * f.prop_stride; } _is >> skip_ascii_buffer; return f.prop_stride; }; } auto element_property_lookup = make_property_lookup_table(); size_t element_idx = 0; size_t property_index = 0; for (auto & element : elements) { for (size_t count = 0; count < element.size; ++count) { property_index = 0; for (auto & property : element.properties) { auto & f = element_property_lookup[element_idx][property_index]; if (!f.skip) { auto * helper = f.helper; if (firstPass) helper->cursor->totalSizeBytes += skip(f, property, is); else read(f, property, helper->data->buffer.get(), helper->cursor->byteOffset, is); } else skip(f, property, is); property_index++; } } element_idx++; } // Reset istream reader to the beginning if (firstPass) is.seekg(start, is.beg); } // Wrap the public interface: PlyFile::PlyFile() { impl.reset(new PlyFileImpl()); }; PlyFile::~PlyFile() { }; bool PlyFile::parse_header(std::istream & is) { return impl->parse_header(is); } void PlyFile::read(std::istream & is) { return impl->read(is); } void PlyFile::write(std::ostream & os, bool isBinary) { return impl->write(os, isBinary); } std::vector PlyFile::get_elements() const { return impl->elements; } std::vector & PlyFile::get_comments() { return impl->comments; } std::vector PlyFile::get_info() const { return impl->objInfo; } std::shared_ptr PlyFile::request_properties_from_element(const std::string & elementKey, const std::initializer_list propertyKeys, const uint32_t list_size_hint) { return impl->request_properties_from_element(elementKey, propertyKeys, list_size_hint); } void PlyFile::add_properties_to_element(const std::string & elementKey, const std::initializer_list propertyKeys, const Type type, const size_t count, uint8_t * data, const Type listType, const size_t listCount) { return impl->add_properties_to_element(elementKey, propertyKeys, type, count, data, listType, listCount); } #endif // end TINYPLY_IMPLEMENTATION ================================================ FILE: framework/tools/dataset-tools/io-inspect.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/SLAMFile.h" #include "io/SLAMFrame.h" #include "io/FrameBufferSource.h" #include "io/deserialisation/SLAMFileDeserialiser.h" #include "io/format/ImageDataFormatter.h" #include #include using namespace slambench::io; slambench::io::SingleFrameBufferSource single_fb_source; void printFrame (SLAMFrame *frame , unsigned int index ) { std::cout << "Frame " << index << std::endl; std::cout << " -> Timestamp " << std::fixed << std::setprecision(9) << (double)frame->Timestamp.S + (frame->Timestamp.Ns / 1000000000.0) << std::endl; if (frame->FrameSensor->GetType() == CameraSensor::kCameraType) { slambench::io::CameraSensor * rgb_sensor = dynamic_cast (frame->FrameSensor) ; } std::cout << " -> Sensor " << frame->FrameSensor->GetType() << " " << (uint32_t)frame->FrameSensor->Index << " (" << frame->FrameSensor->Description.c_str() << ")" << std::endl; } void Deserialise(const std::string &filename, SLAMFile &file) { FILE *input_file = fopen(filename.c_str(), "r"); SLAMFileDeserialiser deserialiser(input_file, &single_fb_source); if(deserialiser.Deserialise(file)) { printf("Deserialisation success\n"); } else { printf("Deserialisation failure\n"); } } void Check(SLAMFile &file) { std::cout << "File version: " << SLAMFile::Version << std::endl; std::cout << "Sensor count: " << file.Sensors.size() << std::endl; std::cout << "Frame count: " << file.GetFrameCount() << std::endl; for(const auto &sensor : file.Sensors) { unsigned int count = 0; for(unsigned int index = 0; index < file.GetFrameCount(); ++index) { SLAMFrame *frame = file.GetFrame(index); if (frame->FrameSensor->Index == sensor->Index) count++; } if (sensor->GetType() == CameraSensor::kCameraType) { slambench::io::CameraSensor * rgb_sensor = dynamic_cast (sensor) ; std::cout << "Sensor " << (uint32_t)sensor->Index << ": " << " (" << count << " frames)" << std::endl << " Type: " << sensor->GetType() << std::endl << " FrameFormat: " << rgb_sensor->FrameFormat << std::endl << " PixelFormat: " << slambench::io::pixelformat::TypeOf(rgb_sensor->PixelFormat) << std::endl << " Desc: " << sensor->Description.c_str() << std::endl; } else { std::cout << "Sensor " << (uint32_t)sensor->Index << ": " << " (" << count << " frames)" << std::endl << " Type: " << sensor->GetType() << std::endl << " Desc: " << sensor->Description.c_str() << std::endl; } } for(unsigned int index = 0; index < file.GetFrameCount(); ++index) { SLAMFrame *frame = file.GetFrame(index); printFrame(frame,index); } } int main(int , char **argv) { SLAMFile file; Deserialise(argv[1], file); Check(file); return 0; } ================================================ FILE: framework/tools/dataset-tools/io-monoslam.cpp ================================================ /* * To change this license header, choose License Headers in Project Properties. * To change this template file, choose Tools | Templates * and open the template in the editor. */ #include #include #include #include #include #include #include #include #include #include #include #include #include #include using namespace slambench::io; CameraSensor *GetGreySensor(const Sensor::pose_t &pose, const CameraSensor::intrinsics_t &intrinsics) { CameraSensor *sensor = new CameraSensor(sensortype::Grey); sensor->Index = 0; sensor->Width = 320; sensor->Height = 240; sensor->FrameFormat = frameformat::Raster; sensor->PixelFormat = pixelformat::G_I_8; sensor->CopyPose(pose); sensor->CopyIntrinsics(intrinsics); return sensor; } void AddSensors(SLAMFile &file, bool Depth, bool RGB, bool Grey, bool GT) { // TODO This information should come from the dataset !! Sensor::pose_t pose_depth = Eigen::Matrix4f::Identity(); Sensor::pose_t pose = Eigen::Matrix4f::Identity(); CameraSensor::intrinsics_t intrinsics; intrinsics[0] = 1.0; intrinsics[1] = 1.0; intrinsics[2] = 0.5; intrinsics[3] = 0.5; DepthSensor::intrinsics_t intrinsics_depth; intrinsics_depth[0] = 0.751875; intrinsics_depth[1] = 1.0; intrinsics_depth[2] = 0.5; intrinsics_depth[3] = 0.5; DepthSensor::disparity_params_t disparity_params = {0.0002,0.0}; DepthSensor::disparity_type_t disparity_type = DepthSensor::affine_disparity; int idx = 0; if(Grey) { CameraSensor *grey_sensor = GetGreySensor(pose, intrinsics); grey_sensor->Index = idx++; file.Sensors.AddSensor(grey_sensor); } } bool GetFrame(const std::string &dirname, SLAMFile &file, int frame_no) { // two frames to add: one for rgb and one for depth Sensor *grey_sensor = file.Sensors.GetSensor(sensortype::Grey); if(grey_sensor) { ImageFileFrame *rgb_frame = new ImageFileFrame(); rgb_frame->FrameSensor = grey_sensor; rgb_frame->Timestamp.S = frame_no; std::stringstream frame_name; frame_name << dirname << "/rawoutput" << std::setw(4) << std::setfill('0') << frame_no << ".pgm"; rgb_frame->Filename = frame_name.str(); if(access(rgb_frame->Filename.c_str(), F_OK) < 0) { printf("No greyscale image for frame %u (%s)\n", frame_no, frame_name.str().c_str()); perror(""); return false; } file.AddFrame(rgb_frame); } return true; } bool AddFrames(const std::string &dirname, SLAMFile &file) { int frame_no = 0; while(GetFrame(dirname, file, frame_no)) { printf("\rRead frame %u ", frame_no); frame_no++; } printf("\n"); return true; } void frame_callback(int idx, int total) { printf("\r"); // print progress bar printf("["); const int width = 50; float blocks = width * ((float)idx / total); for(int i = 0; i < blocks; ++i) { printf("#"); } for(int i = blocks; i < width; ++i) { printf(" "); } printf("] "); printf("%u / %u", idx, total); fflush(stdout); } bool Serialise(const std::string &filename, SLAMFile &file) { return SLAMFile::Write(filename, file, frame_callback); } int main(int argc, char **argv) { SLAMFile slamfile; AddSensors(slamfile, 0, 0,1, 0); if(!AddFrames(argv[1], slamfile)) { fprintf(stderr, "Failed to add frames\n"); return 1; } printf("Writing output\n"); if(!Serialise(argv[2], slamfile)) { fprintf(stderr, "\nFailed to write output\n"); return 1; } printf("\nSerialisation succeeded\n"); return 0; } ================================================ FILE: framework/tools/dataset-tools/io-readply.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include "io/format/PointCloud.h" #include int main(int argc, char **argv) { slambench::io::PlyReader reader; std::ifstream str (argv[1]); auto pc = reader.Read(str); if(pc == nullptr) { printf("Could not read pointcloud!\n"); return 1; } else { for(auto p : pc->Get()) { printf("%f %f %f\n", p.x, p.y, p.z); } } return 0; } ================================================ FILE: framework/tools/dataset-tools/lodepng.cpp ================================================ /* LodePNG version 20140624 Copyright (c) 2005-2014 Lode Vandevenne This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 3. This notice may not be removed or altered from any source distribution. */ /* The manual and changelog are in the header file "lodepng.h" Rename this file to lodepng.cpp to use it for C++, or to lodepng.c to use it for C. */ #include "lodepng.h" #include #include #ifdef LODEPNG_COMPILE_CPP #include #endif /*LODEPNG_COMPILE_CPP*/ #define VERSION_STRING "20140624" #if (_MSC_VER >= 1310) /*Visual Studio: Kept warning-free but a few warning types are not desired here.*/ #pragma warning( disable : 4244 ) /*implicit conversions: not warned by gcc -Wall -Wextra and requires too much casts*/ #pragma warning( disable : 4996 ) /*VS does not like fopen, but fopen_s is not standard C so unusable here*/ #endif /*_MSC_VER >= 1310*/ /* This source file is built up in the following large parts. The code sections with the "LODEPNG_COMPILE_" #defines divide this up further in an intermixed way. -Tools for C and common code for PNG and Zlib -C Code for Zlib (huffman, deflate, ...) -C Code for PNG (file format chunks, adam7, PNG filters, color conversions, ...) -The C++ wrapper around all of the above */ /*The malloc, realloc and free functions defined here with "lodepng_" in front of the name, so that you can easily change them to others related to your platform if needed. Everything else in the code calls these. Pass -DLODEPNG_NO_COMPILE_ALLOCATORS to the compiler, or comment out #define LODEPNG_COMPILE_ALLOCATORS in the header, to disable the ones here and define them in your own project's source files without needing to change lodepng source code. Don't forget to remove "static" if you copypaste them from here.*/ #ifdef LODEPNG_COMPILE_ALLOCATORS static void* lodepng_malloc(size_t size) { return malloc(size); } static void* lodepng_realloc(void* ptr, size_t new_size) { return realloc(ptr, new_size); } static void lodepng_free(void* ptr) { free(ptr); } #else /*LODEPNG_COMPILE_ALLOCATORS*/ void* lodepng_malloc(size_t size); void* lodepng_realloc(void* ptr, size_t new_size); void lodepng_free(void* ptr); #endif /*LODEPNG_COMPILE_ALLOCATORS*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // Tools for C, and common code for PNG and Zlib. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* Often in case of an error a value is assigned to a variable and then it breaks out of a loop (to go to the cleanup phase of a function). This macro does that. It makes the error handling code shorter and more readable. Example: if(!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83); */ #define CERROR_BREAK(errorvar, code)\ {\ errorvar = code;\ break;\ } /*version of CERROR_BREAK that assumes the common case where the error variable is named "error"*/ #define ERROR_BREAK(code) CERROR_BREAK(error, code) /*Set error var to the error code, and return it.*/ #define CERROR_RETURN_ERROR(errorvar, code)\ {\ errorvar = code;\ return code;\ } /*Try the code, if it returns error, also return the error.*/ #define CERROR_TRY_RETURN(call)\ {\ unsigned error = call;\ if(error) return error;\ } /* About uivector, ucvector and string: -All of them wrap dynamic arrays or text strings in a similar way. -LodePNG was originally written in C++. The vectors replace the std::vectors that were used in the C++ version. -The string tools are made to avoid problems with compilers that declare things like strncat as deprecated. -They're not used in the interface, only internally in this file as static functions. -As with many other structs in this file, the init and cleanup functions serve as ctor and dtor. */ #ifdef LODEPNG_COMPILE_ZLIB /*dynamic vector of unsigned ints*/ typedef struct uivector { unsigned* data; size_t size; /*size in number of unsigned longs*/ size_t allocsize; /*allocated size in bytes*/ } uivector; static void uivector_cleanup(void* p) { ((uivector*) p)->size = ((uivector*) p)->allocsize = 0; lodepng_free(((uivector*) p)->data); ((uivector*) p)->data = NULL; } /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_resize(uivector* p, size_t size) { if (size * sizeof(unsigned) > p->allocsize) { size_t newsize = size * sizeof(unsigned) * 2; void* data = lodepng_realloc(p->data, newsize); if (data) { p->allocsize = newsize; p->data = (unsigned*) data; p->size = size; } else return 0; } else p->size = size; return 1; } /*resize and give all new elements the value*/ static unsigned uivector_resizev(uivector* p, size_t size, unsigned value) { size_t oldsize = p->size, i; if (!uivector_resize(p, size)) return 0; for (i = oldsize; i < size; i++) p->data[i] = value; return 1; } static void uivector_init(uivector* p) { p->data = NULL; p->size = p->allocsize = 0; } #ifdef LODEPNG_COMPILE_ENCODER /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_push_back(uivector* p, unsigned c) { if (!uivector_resize(p, p->size + 1)) return 0; p->data[p->size - 1] = c; return 1; } /*copy q to p, returns 1 if success, 0 if failure ==> nothing done*/ static unsigned uivector_copy(uivector* p, const uivector* q) { size_t i; if (!uivector_resize(p, q->size)) return 0; for (i = 0; i < q->size; i++) p->data[i] = q->data[i]; return 1; } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ /* /////////////////////////////////////////////////////////////////////////// */ /*dynamic vector of unsigned chars*/ typedef struct ucvector { unsigned char* data; size_t size; /*used size*/ size_t allocsize; /*allocated size*/ } ucvector; /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned ucvector_resize(ucvector* p, size_t size) { if (size * sizeof(unsigned char) > p->allocsize) { size_t newsize = size * sizeof(unsigned char) * 2; void* data = lodepng_realloc(p->data, newsize); if (data) { p->allocsize = newsize; p->data = (unsigned char*) data; p->size = size; } else return 0; /*error: not enough memory*/ } else p->size = size; return 1; } #ifdef LODEPNG_COMPILE_PNG static void ucvector_cleanup(void* p) { ((ucvector*) p)->size = ((ucvector*) p)->allocsize = 0; lodepng_free(((ucvector*) p)->data); ((ucvector*) p)->data = NULL; } static void ucvector_init(ucvector* p) { p->data = NULL; p->size = p->allocsize = 0; } #ifdef LODEPNG_COMPILE_DECODER /*resize and give all new elements the value*/ static unsigned ucvector_resizev(ucvector* p, size_t size, unsigned char value) { size_t oldsize = p->size, i; if (!ucvector_resize(p, size)) return 0; for (i = oldsize; i < size; i++) p->data[i] = value; return 1; } #endif /*LODEPNG_COMPILE_DECODER*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ZLIB /*you can both convert from vector to buffer&size and vica versa. If you use init_buffer to take over a buffer and size, it is not needed to use cleanup*/ static void ucvector_init_buffer(ucvector* p, unsigned char* buffer, size_t size) { p->data = buffer; p->allocsize = p->size = size; } #endif /*LODEPNG_COMPILE_ZLIB*/ #if (defined(LODEPNG_COMPILE_PNG) && defined(LODEPNG_COMPILE_ANCILLARY_CHUNKS)) || defined(LODEPNG_COMPILE_ENCODER) /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned ucvector_push_back(ucvector* p, unsigned char c) { if (!ucvector_resize(p, p->size + 1)) return 0; p->data[p->size - 1] = c; return 1; } #endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_PNG #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*returns 1 if success, 0 if failure ==> nothing done*/ static unsigned string_resize(char** out, size_t size) { char* data = (char*) lodepng_realloc(*out, size + 1); if (data) { data[size] = 0; /*null termination char*/ *out = data; } return data != 0; } /*init a {char*, size_t} pair for use as string*/ static void string_init(char** out) { *out = NULL; string_resize(out, 0); } /*free the above pair again*/ static void string_cleanup(char** out) { lodepng_free(*out); *out = NULL; } static void string_set(char** out, const char* in) { size_t insize = strlen(in), i = 0; if (string_resize(out, insize)) { for (i = 0; i < insize; i++) { (*out)[i] = in[i]; } } } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ #endif /*LODEPNG_COMPILE_PNG*/ /* ////////////////////////////////////////////////////////////////////////// */ unsigned lodepng_read32bitInt(const unsigned char* buffer) { return (unsigned) ((buffer[0] << 24) | (buffer[1] << 16) | (buffer[2] << 8) | buffer[3]); } #if defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER) /*buffer must have at least 4 allocated bytes available*/ static void lodepng_set32bitInt(unsigned char* buffer, unsigned value) { buffer[0] = (unsigned char) ((value >> 24) & 0xff); buffer[1] = (unsigned char) ((value >> 16) & 0xff); buffer[2] = (unsigned char) ((value >> 8) & 0xff); buffer[3] = (unsigned char) ((value) & 0xff); } #endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ #ifdef LODEPNG_COMPILE_ENCODER static void lodepng_add32bitInt(ucvector* buffer, unsigned value) { ucvector_resize(buffer, buffer->size + 4); /*todo: give error if resize failed*/ lodepng_set32bitInt(&buffer->data[buffer->size - 4], value); } #endif /*LODEPNG_COMPILE_ENCODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / File IO / */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename) { FILE* file; long size; /*provide some proper output values if error will happen*/ *out = 0; *outsize = 0; file = fopen(filename, "rb"); if (!file) return 78; /*get filesize:*/ fseek(file, 0, SEEK_END); size = ftell(file); rewind(file); /*read contents of the file into the vector*/ *outsize = 0; *out = (unsigned char*) lodepng_malloc((size_t) size); if (size && (*out)) (*outsize) = fread(*out, 1, (size_t) size, file); fclose(file); if (!(*out) && size) return 83; /*the above malloc failed*/ return 0; } /*write given buffer to the file, overwriting the file, it doesn't append to it.*/ unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename) { FILE* file; file = fopen(filename, "wb"); if (!file) return 79; fwrite((char*) buffer, 1, buffersize, file); fclose(file); return 0; } #endif /*LODEPNG_COMPILE_DISK*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // End of common code and tools. Begin of Zlib related code. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_ENCODER /*TODO: this ignores potential out of memory errors*/ #define addBitToStream(/*size_t**/ bitpointer, /*ucvector**/ bitstream, /*unsigned char*/ bit)\ {\ /*add a new byte at the end*/\ if(((*bitpointer) & 7) == 0) ucvector_push_back(bitstream, (unsigned char)0);\ /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/\ (bitstream->data[bitstream->size - 1]) |= (bit << ((*bitpointer) & 0x7));\ (*bitpointer)++;\ } static void addBitsToStream(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) { size_t i; for (i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char )((value >> i) & 1)); } static void addBitsToStreamReversed(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) { size_t i; for (i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char )((value >> (nbits - 1 - i)) & 1)); } #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DECODER #define READBIT(bitpointer, bitstream) ((bitstream[bitpointer >> 3] >> (bitpointer & 0x7)) & (unsigned char)1) static unsigned char readBitFromStream(size_t* bitpointer, const unsigned char* bitstream) { unsigned char result = (unsigned char) (READBIT(*bitpointer, bitstream)); (*bitpointer)++; return result; } static unsigned readBitsFromStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) { unsigned result = 0, i; for (i = 0; i < nbits; i++) { result += ((unsigned) READBIT(*bitpointer, bitstream)) << i; (*bitpointer)++; } return result; } #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / Deflate - Huffman / */ /* ////////////////////////////////////////////////////////////////////////// */ #define FIRST_LENGTH_CODE_INDEX 257 #define LAST_LENGTH_CODE_INDEX 285 /*256 literals, the end code, some length codes, and 2 unused codes*/ #define NUM_DEFLATE_CODE_SYMBOLS 288 /*the distance codes have their own symbols, 30 used, 2 unused*/ #define NUM_DISTANCE_SYMBOLS 32 /*the code length codes. 0-15: code lengths, 16: copy previous 3-6 times, 17: 3-10 zeros, 18: 11-138 zeros*/ #define NUM_CODE_LENGTH_CODES 19 /*the base lengths represented by codes 257-285*/ static const unsigned LENGTHBASE[29] = { 3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31, 35, 43, 51, 59, 67, 83, 99, 115, 131, 163, 195, 227, 258 }; /*the extra bits used by codes 257-285 (added to base length)*/ static const unsigned LENGTHEXTRA[29] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3, 4, 4, 4, 4, 5, 5, 5, 5, 0 }; /*the base backwards distances (the bits of distance codes appear after length codes and use their own huffman tree)*/ static const unsigned DISTANCEBASE[30] = { 1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193, 257, 385, 513, 769, 1025, 1537, 2049, 3073, 4097, 6145, 8193, 12289, 16385, 24577 }; /*the extra bits of backwards distances (added to base)*/ static const unsigned DISTANCEEXTRA[30] = { 0, 0, 0, 0, 1, 1, 2, 2, 3, 3, 4, 4, 5, 5, 6, 6, 7, 7, 8, 8, 9, 9, 10, 10, 11, 11, 12, 12, 13, 13 }; /*the order in which "code length alphabet code lengths" are stored, out of this the huffman tree of the dynamic huffman tree lengths is generated*/ static const unsigned CLCL_ORDER[NUM_CODE_LENGTH_CODES] = { 16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15 }; /* ////////////////////////////////////////////////////////////////////////// */ /* Huffman tree struct, containing multiple representations of the tree */ typedef struct HuffmanTree { unsigned* tree2d; unsigned* tree1d; unsigned* lengths; /*the lengths of the codes of the 1d-tree*/ unsigned maxbitlen; /*maximum number of bits a single code can get*/ unsigned numcodes; /*number of symbols in the alphabet = number of codes*/ } HuffmanTree; /*function used for debug purposes to draw the tree in ascii art with C++*/ /* static void HuffmanTree_draw(HuffmanTree* tree) { std::cout << "tree. length: " << tree->numcodes << " maxbitlen: " << tree->maxbitlen << std::endl; for(size_t i = 0; i < tree->tree1d.size; i++) { if(tree->lengths.data[i]) std::cout << i << " " << tree->tree1d.data[i] << " " << tree->lengths.data[i] << std::endl; } std::cout << std::endl; }*/ static void HuffmanTree_init(HuffmanTree* tree) { tree->tree2d = 0; tree->tree1d = 0; tree->lengths = 0; } static void HuffmanTree_cleanup(HuffmanTree* tree) { lodepng_free(tree->tree2d); lodepng_free(tree->tree1d); lodepng_free(tree->lengths); } /*the tree representation used by the decoder. return value is error*/ static unsigned HuffmanTree_make2DTree(HuffmanTree* tree) { unsigned nodefilled = 0; /*up to which node it is filled*/ unsigned treepos = 0; /*position in the tree (1 of the numcodes columns)*/ unsigned n, i; tree->tree2d = (unsigned*) lodepng_malloc( tree->numcodes * 2 * sizeof(unsigned)); if (!tree->tree2d) return 83; /*alloc fail*/ /* convert tree1d[] to tree2d[][]. In the 2D array, a value of 32767 means uninited, a value >= numcodes is an address to another bit, a value < numcodes is a code. The 2 rows are the 2 possible bit values (0 or 1), there are as many columns as codes - 1. A good huffmann tree has N * 2 - 1 nodes, of which N - 1 are internal nodes. Here, the internal nodes are stored (what their 0 and 1 option point to). There is only memory for such good tree currently, if there are more nodes (due to too long length codes), error 55 will happen */ for (n = 0; n < tree->numcodes * 2; n++) { tree->tree2d[n] = 32767; /*32767 here means the tree2d isn't filled there yet*/ } for (n = 0; n < tree->numcodes; n++) /*the codes*/ { for (i = 0; i < tree->lengths[n]; i++) /*the bits for this code*/ { unsigned char bit = (unsigned char) ((tree->tree1d[n] >> (tree->lengths[n] - i - 1)) & 1); if (treepos > tree->numcodes - 2) return 55; /*oversubscribed, see comment in lodepng_error_text*/ if (tree->tree2d[2 * treepos + bit] == 32767) /*not yet filled in*/ { if (i + 1 == tree->lengths[n]) /*last bit*/ { tree->tree2d[2 * treepos + bit] = n; /*put the current code in it*/ treepos = 0; } else { /*put address of the next step in here, first that address has to be found of course (it's just nodefilled + 1)...*/ nodefilled++; /*addresses encoded with numcodes added to it*/ tree->tree2d[2 * treepos + bit] = nodefilled + tree->numcodes; treepos = nodefilled; } } else treepos = tree->tree2d[2 * treepos + bit] - tree->numcodes; } } for (n = 0; n < tree->numcodes * 2; n++) { if (tree->tree2d[n] == 32767) tree->tree2d[n] = 0; /*remove possible remaining 32767's*/ } return 0; } /* Second step for the ...makeFromLengths and ...makeFromFrequencies functions. numcodes, lengths and maxbitlen must already be filled in correctly. return value is error. */ static unsigned HuffmanTree_makeFromLengths2(HuffmanTree* tree) { uivector blcount; uivector nextcode; unsigned bits, n, error = 0; uivector_init(&blcount); uivector_init(&nextcode); tree->tree1d = (unsigned*) lodepng_malloc( tree->numcodes * sizeof(unsigned)); if (!tree->tree1d) error = 83; /*alloc fail*/ if (!uivector_resizev(&blcount, tree->maxbitlen + 1, 0) || !uivector_resizev(&nextcode, tree->maxbitlen + 1, 0)) error = 83; /*alloc fail*/ if (!error) { /*step 1: count number of instances of each code length*/ for (bits = 0; bits < tree->numcodes; bits++) blcount.data[tree->lengths[bits]]++; /*step 2: generate the nextcode values*/ for (bits = 1; bits <= tree->maxbitlen; bits++) { nextcode.data[bits] = (nextcode.data[bits - 1] + blcount.data[bits - 1]) << 1; } /*step 3: generate all the codes*/ for (n = 0; n < tree->numcodes; n++) { if (tree->lengths[n] != 0) tree->tree1d[n] = nextcode.data[tree->lengths[n]]++; } } uivector_cleanup(&blcount); uivector_cleanup(&nextcode); if (!error) return HuffmanTree_make2DTree(tree); else return error; } /* given the code lengths (as stored in the PNG file), generate the tree as defined by Deflate. maxbitlen is the maximum bits that a code in the tree can have. return value is error. */ static unsigned HuffmanTree_makeFromLengths(HuffmanTree* tree, const unsigned* bitlen, size_t numcodes, unsigned maxbitlen) { unsigned i; tree->lengths = (unsigned*) lodepng_malloc(numcodes * sizeof(unsigned)); if (!tree->lengths) return 83; /*alloc fail*/ for (i = 0; i < numcodes; i++) tree->lengths[i] = bitlen[i]; tree->numcodes = (unsigned) numcodes; /*number of symbols*/ tree->maxbitlen = maxbitlen; return HuffmanTree_makeFromLengths2(tree); } #ifdef LODEPNG_COMPILE_ENCODER /* A coin, this is the terminology used for the package-merge algorithm and the coin collector's problem. This is used to generate the huffman tree. A coin can be multiple coins (when they're merged) */ typedef struct Coin { uivector symbols; float weight; /*the sum of all weights in this coin*/ } Coin; static void coin_init(Coin* c) { uivector_init(&c->symbols); } /*argument c is void* so that this dtor can be given as function pointer to the vector resize function*/ static void coin_cleanup(void* c) { uivector_cleanup(&((Coin*) c)->symbols); } static void coin_copy(Coin* c1, const Coin* c2) { c1->weight = c2->weight; uivector_copy(&c1->symbols, &c2->symbols); } static void add_coins(Coin* c1, const Coin* c2) { size_t i; for (i = 0; i < c2->symbols.size; i++) uivector_push_back(&c1->symbols, c2->symbols.data[i]); c1->weight += c2->weight; } static void init_coins(Coin* coins, size_t num) { size_t i; for (i = 0; i < num; i++) coin_init(&coins[i]); } static void cleanup_coins(Coin* coins, size_t num) { size_t i; for (i = 0; i < num; i++) coin_cleanup(&coins[i]); } static int coin_compare(const void* a, const void* b) { float wa = ((const Coin*) a)->weight; float wb = ((const Coin*) b)->weight; return wa > wb ? 1 : wa < wb ? -1 : 0; } static unsigned append_symbol_coins(Coin* coins, const unsigned* frequencies, unsigned numcodes, size_t sum) { unsigned i; unsigned j = 0; /*index of present symbols*/ for (i = 0; i < numcodes; i++) { if (frequencies[i] != 0) /*only include symbols that are present*/ { coins[j].weight = frequencies[i] / (float) sum; uivector_push_back(&coins[j].symbols, i); j++; } } return 0; } unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, size_t numcodes, unsigned maxbitlen) { unsigned i, j; size_t sum = 0, numpresent = 0; unsigned error = 0; Coin* coins; /*the coins of the currently calculated row*/ Coin* prev_row; /*the previous row of coins*/ size_t numcoins; size_t coinmem; if (numcodes == 0) return 80; /*error: a tree of 0 symbols is not supposed to be made*/ for (i = 0; i < numcodes; i++) { if (frequencies[i] > 0) { numpresent++; sum += frequencies[i]; } } for (i = 0; i < numcodes; i++) lengths[i] = 0; /*ensure at least two present symbols. There should be at least one symbol according to RFC 1951 section 3.2.7. To decoders incorrectly require two. To make these work as well ensure there are at least two symbols. The Package-Merge code below also doesn't work correctly if there's only one symbol, it'd give it the theoritical 0 bits but in practice zlib wants 1 bit*/ if (numpresent == 0) { lengths[0] = lengths[1] = 1; /*note that for RFC 1951 section 3.2.7, only lengths[0] = 1 is needed*/ } else if (numpresent == 1) { for (i = 0; i < numcodes; i++) { if (frequencies[i]) { lengths[i] = 1; lengths[i == 0 ? 1 : 0] = 1; break; } } } else { /*Package-Merge algorithm represented by coin collector's problem For every symbol, maxbitlen coins will be created*/ coinmem = numpresent * 2; /*max amount of coins needed with the current algo*/ coins = (Coin*) lodepng_malloc(sizeof(Coin) * coinmem); prev_row = (Coin*) lodepng_malloc(sizeof(Coin) * coinmem); if (!coins || !prev_row) { lodepng_free(coins); lodepng_free(prev_row); return 83; /*alloc fail*/ } init_coins(coins, coinmem); init_coins(prev_row, coinmem); /*first row, lowest denominator*/ error = append_symbol_coins(coins, frequencies, numcodes, sum); numcoins = numpresent; qsort(coins, numcoins, sizeof(Coin), coin_compare); if (!error) { unsigned numprev = 0; for (j = 1; j <= maxbitlen && !error; j++) /*each of the remaining rows*/ { unsigned tempnum; Coin* tempcoins; /*swap prev_row and coins, and their amounts*/ tempcoins = prev_row; prev_row = coins; coins = tempcoins; tempnum = numprev; numprev = numcoins; numcoins = tempnum; cleanup_coins(coins, numcoins); init_coins(coins, numcoins); numcoins = 0; /*fill in the merged coins of the previous row*/ for (i = 0; i + 1 < numprev; i += 2) { /*merge prev_row[i] and prev_row[i + 1] into new coin*/ Coin* coin = &coins[numcoins++]; coin_copy(coin, &prev_row[i]); add_coins(coin, &prev_row[i + 1]); } /*fill in all the original symbols again*/ if (j < maxbitlen) { error = append_symbol_coins(coins + numcoins, frequencies, numcodes, sum); numcoins += numpresent; } qsort(coins, numcoins, sizeof(Coin), coin_compare); } } if (!error) { /*calculate the lenghts of each symbol, as the amount of times a coin of each symbol is used*/ for (i = 0; i < numpresent - 1; i++) { Coin* coin = &coins[i]; for (j = 0; j < coin->symbols.size; j++) lengths[coin->symbols.data[j]]++; } } cleanup_coins(coins, coinmem); lodepng_free(coins); cleanup_coins(prev_row, coinmem); lodepng_free(prev_row); } return error; } /*Create the Huffman tree given the symbol frequencies*/ static unsigned HuffmanTree_makeFromFrequencies(HuffmanTree* tree, const unsigned* frequencies, size_t mincodes, size_t numcodes, unsigned maxbitlen) { unsigned error = 0; while (!frequencies[numcodes - 1] && numcodes > mincodes) numcodes--; /*trim zeroes*/ tree->maxbitlen = maxbitlen; tree->numcodes = (unsigned) numcodes; /*number of symbols*/ tree->lengths = (unsigned*) lodepng_realloc(tree->lengths, numcodes * sizeof(unsigned)); if (!tree->lengths) return 83; /*alloc fail*/ /*initialize all lengths to 0*/ memset(tree->lengths, 0, numcodes * sizeof(unsigned)); error = lodepng_huffman_code_lengths(tree->lengths, frequencies, numcodes, maxbitlen); if (!error) error = HuffmanTree_makeFromLengths2(tree); return error; } static unsigned HuffmanTree_getCode(const HuffmanTree* tree, unsigned index) { return tree->tree1d[index]; } static unsigned HuffmanTree_getLength(const HuffmanTree* tree, unsigned index) { return tree->lengths[index]; } #endif /*LODEPNG_COMPILE_ENCODER*/ /*get the literal and length code tree of a deflated block with fixed tree, as per the deflate specification*/ static unsigned generateFixedLitLenTree(HuffmanTree* tree) { unsigned i, error = 0; unsigned* bitlen = (unsigned*) lodepng_malloc( NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); if (!bitlen) return 83; /*alloc fail*/ /*288 possible codes: 0-255=literals, 256=endcode, 257-285=lengthcodes, 286-287=unused*/ for (i = 0; i <= 143; i++) bitlen[i] = 8; for (i = 144; i <= 255; i++) bitlen[i] = 9; for (i = 256; i <= 279; i++) bitlen[i] = 7; for (i = 280; i <= 287; i++) bitlen[i] = 8; error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DEFLATE_CODE_SYMBOLS, 15); lodepng_free(bitlen); return error; } /*get the distance code tree of a deflated block with fixed tree, as specified in the deflate specification*/ static unsigned generateFixedDistanceTree(HuffmanTree* tree) { unsigned i, error = 0; unsigned* bitlen = (unsigned*) lodepng_malloc( NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); if (!bitlen) return 83; /*alloc fail*/ /*there are 32 distance codes, but 30-31 are unused*/ for (i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen[i] = 5; error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DISTANCE_SYMBOLS, 15); lodepng_free(bitlen); return error; } #ifdef LODEPNG_COMPILE_DECODER /* returns the code, or (unsigned)(-1) if error happened inbitlength is the length of the complete buffer, in bits (so its byte length times 8) */ static unsigned huffmanDecodeSymbol(const unsigned char* in, size_t* bp, const HuffmanTree* codetree, size_t inbitlength) { unsigned treepos = 0, ct; for (;;) { if (*bp >= inbitlength) return (unsigned) (-1); /*error: end of input memory reached without endcode*/ /* decode the symbol from the tree. The "readBitFromStream" code is inlined in the expression below because this is the biggest bottleneck while decoding */ ct = codetree->tree2d[(treepos << 1) + READBIT(*bp, in)]; (*bp)++; if (ct < codetree->numcodes) return ct; /*the symbol is decoded, return it*/ else treepos = ct - codetree->numcodes; /*symbol not yet decoded, instead move tree position*/ if (treepos >= codetree->numcodes) return (unsigned) (-1); /*error: it appeared outside the codetree*/ } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_DECODER /* ////////////////////////////////////////////////////////////////////////// */ /* / Inflator (Decompressor) / */ /* ////////////////////////////////////////////////////////////////////////// */ /*get the tree of a deflated block with fixed tree, as specified in the deflate specification*/ static void getTreeInflateFixed(HuffmanTree* tree_ll, HuffmanTree* tree_d) { /*TODO: check for out of memory errors*/ generateFixedLitLenTree(tree_ll); generateFixedDistanceTree(tree_d); } /*get the tree of a deflated block with dynamic tree, the tree itself is also Huffman compressed with a known tree*/ static unsigned getTreeInflateDynamic(HuffmanTree* tree_ll, HuffmanTree* tree_d, const unsigned char* in, size_t* bp, size_t inlength) { /*make sure that length values that aren't filled in will be 0, or a wrong tree will be generated*/ unsigned error = 0; unsigned n, HLIT, HDIST, HCLEN, i; size_t inbitlength = inlength * 8; /*see comments in deflateDynamic for explanation of the context and these variables, it is analogous*/ unsigned* bitlen_ll = 0; /*lit,len code lengths*/ unsigned* bitlen_d = 0; /*dist code lengths*/ /*code length code lengths ("clcl"), the bit lengths of the huffman tree used to compress bitlen_ll and bitlen_d*/ unsigned* bitlen_cl = 0; HuffmanTree tree_cl; /*the code tree for code length codes (the huffman tree for compressed huffman trees)*/ if ((*bp) >> 3 >= inlength - 2) return 49; /*error: the bit pointer is or will go past the memory*/ /*number of literal/length codes + 257. Unlike the spec, the value 257 is added to it here already*/ HLIT = readBitsFromStream(bp, in, 5) + 257; /*number of distance codes. Unlike the spec, the value 1 is added to it here already*/ HDIST = readBitsFromStream(bp, in, 5) + 1; /*number of code length codes. Unlike the spec, the value 4 is added to it here already*/ HCLEN = readBitsFromStream(bp, in, 4) + 4; HuffmanTree_init(&tree_cl); while (!error) { /*read the code length codes out of 3 * (amount of code length codes) bits*/ bitlen_cl = (unsigned*) lodepng_malloc( NUM_CODE_LENGTH_CODES * sizeof(unsigned)); if (!bitlen_cl) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < NUM_CODE_LENGTH_CODES; i++) { if (i < HCLEN) bitlen_cl[CLCL_ORDER[i]] = readBitsFromStream(bp, in, 3); else bitlen_cl[CLCL_ORDER[i]] = 0; /*if not, it must stay 0*/ } error = HuffmanTree_makeFromLengths(&tree_cl, bitlen_cl, NUM_CODE_LENGTH_CODES, 7); if (error) break; /*now we can use this tree to read the lengths for the tree that this function will return*/ bitlen_ll = (unsigned*) lodepng_malloc( NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); bitlen_d = (unsigned*) lodepng_malloc( NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); if (!bitlen_ll || !bitlen_d) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < NUM_DEFLATE_CODE_SYMBOLS; i++) bitlen_ll[i] = 0; for (i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen_d[i] = 0; /*i is the current symbol we're reading in the part that contains the code lengths of lit/len and dist codes*/ i = 0; while (i < HLIT + HDIST) { unsigned code = huffmanDecodeSymbol(in, bp, &tree_cl, inbitlength); if (code <= 15) /*a length code*/ { if (i < HLIT) bitlen_ll[i] = code; else bitlen_d[i - HLIT] = code; i++; } else if (code == 16) /*repeat previous*/ { unsigned replength = 3; /*read in the 2 bits that indicate repeat length (3-6)*/ unsigned value; /*set value to the previous code*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ if (i == 0) ERROR_BREAK(54); /*can't repeat previous if i is 0*/ replength += readBitsFromStream(bp, in, 2); if (i < HLIT + 1) value = bitlen_ll[i - 1]; else value = bitlen_d[i - HLIT - 1]; /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(13); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = value; else bitlen_d[i - HLIT] = value; i++; } } else if (code == 17) /*repeat "0" 3-10 times*/ { unsigned replength = 3; /*read in the bits that indicate repeat length*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ replength += readBitsFromStream(bp, in, 3); /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(14); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = 0; else bitlen_d[i - HLIT] = 0; i++; } } else if (code == 18) /*repeat "0" 11-138 times*/ { unsigned replength = 11; /*read in the bits that indicate repeat length*/ if (*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ replength += readBitsFromStream(bp, in, 7); /*repeat this value in the next lengths*/ for (n = 0; n < replength; n++) { if (i >= HLIT + HDIST) ERROR_BREAK(15); /*error: i is larger than the amount of codes*/ if (i < HLIT) bitlen_ll[i] = 0; else bitlen_d[i - HLIT] = 0; i++; } } else /*if(code == (unsigned)(-1))*//*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { if (code == (unsigned) (-1)) { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inbitlength ? 10 : 11; } else error = 16; /*unexisting code, this can never happen*/ break; } } if (error) break; if (bitlen_ll[256] == 0) ERROR_BREAK(64); /*the length of the end code 256 must be larger than 0*/ /*now we've finally got HLIT and HDIST, so generate the code trees, and the function is done*/ error = HuffmanTree_makeFromLengths(tree_ll, bitlen_ll, NUM_DEFLATE_CODE_SYMBOLS, 15); if (error) break; error = HuffmanTree_makeFromLengths(tree_d, bitlen_d, NUM_DISTANCE_SYMBOLS, 15); break; /*end of error-while*/ } lodepng_free(bitlen_cl); lodepng_free(bitlen_ll); lodepng_free(bitlen_d); HuffmanTree_cleanup(&tree_cl); return error; } /*inflate a block with dynamic of fixed Huffman tree*/ static unsigned inflateHuffmanBlock(ucvector* out, const unsigned char* in, size_t* bp, size_t* pos, size_t inlength, unsigned btype) { unsigned error = 0; HuffmanTree tree_ll; /*the huffman tree for literal and length codes*/ HuffmanTree tree_d; /*the huffman tree for distance codes*/ size_t inbitlength = inlength * 8; HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); if (btype == 1) getTreeInflateFixed(&tree_ll, &tree_d); else if (btype == 2) error = getTreeInflateDynamic(&tree_ll, &tree_d, in, bp, inlength); while (!error) /*decode all symbols until end reached, breaks at end code*/ { /*code_ll is literal, length or end code*/ unsigned code_ll = huffmanDecodeSymbol(in, bp, &tree_ll, inbitlength); if (code_ll <= 255) /*literal symbol*/ { if ((*pos) >= out->size) { /*reserve more room at once*/ if (!ucvector_resize(out, ((*pos) + 1) * 2)) ERROR_BREAK(83 /*alloc fail*/); } out->data[(*pos)] = (unsigned char) (code_ll); (*pos)++; } else if (code_ll >= FIRST_LENGTH_CODE_INDEX && code_ll <= LAST_LENGTH_CODE_INDEX) /*length code*/ { unsigned code_d, distance; unsigned numextrabits_l, numextrabits_d; /*extra bits for length and distance*/ size_t start, forward, backward, length; /*part 1: get length base*/ length = LENGTHBASE[code_ll - FIRST_LENGTH_CODE_INDEX]; /*part 2: get extra bits and add the value of that to length*/ numextrabits_l = LENGTHEXTRA[code_ll - FIRST_LENGTH_CODE_INDEX]; if (*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ length += readBitsFromStream(bp, in, numextrabits_l); /*part 3: get distance code*/ code_d = huffmanDecodeSymbol(in, bp, &tree_d, inbitlength); if (code_d > 29) { if (code_ll == (unsigned) (-1)) /*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inlength * 8 ? 10 : 11; } else error = 18; /*error: invalid distance code (30-31 are never used)*/ break; } distance = DISTANCEBASE[code_d]; /*part 4: get extra bits from distance*/ numextrabits_d = DISTANCEEXTRA[code_d]; if (*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ distance += readBitsFromStream(bp, in, numextrabits_d); /*part 5: fill in all the out[n] values based on the length and dist*/ start = (*pos); if (distance > start) ERROR_BREAK(52); /*too long backward distance*/ backward = start - distance; if ((*pos) + length >= out->size) { /*reserve more room at once*/ if (!ucvector_resize(out, ((*pos) + length) * 2)) ERROR_BREAK(83 /*alloc fail*/); } for (forward = 0; forward < length; forward++) { out->data[(*pos)] = out->data[backward]; (*pos)++; backward++; if (backward >= start) backward = start - distance; } } else if (code_ll == 256) { break; /*end code, break the loop*/ } else /*if(code == (unsigned)(-1))*//*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ { /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol (10=no endcode, 11=wrong jump outside of tree)*/ error = (*bp) > inlength * 8 ? 10 : 11; break; } } HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); return error; } static unsigned inflateNoCompression(ucvector* out, const unsigned char* in, size_t* bp, size_t* pos, size_t inlength) { /*go to first boundary of byte*/ size_t p; unsigned LEN, NLEN, n, error = 0; while (((*bp) & 0x7) != 0) (*bp)++; p = (*bp) / 8; /*byte position*/ /*read LEN (2 bytes) and NLEN (2 bytes)*/ if (p >= inlength - 4) return 52; /*error, bit pointer will jump past memory*/ LEN = in[p] + 256u * in[p + 1]; p += 2; NLEN = in[p] + 256u * in[p + 1]; p += 2; /*check if 16-bit NLEN is really the one's complement of LEN*/ if (LEN + NLEN != 65535) return 21; /*error: NLEN is not one's complement of LEN*/ if ((*pos) + LEN >= out->size) { if (!ucvector_resize(out, (*pos) + LEN)) return 83; /*alloc fail*/ } /*read the literal data: LEN bytes are now stored in the out buffer*/ if (p + LEN > inlength) return 23; /*error: reading outside of in buffer*/ for (n = 0; n < LEN; n++) out->data[(*pos)++] = in[p++]; (*bp) = p * 8; return error; } static unsigned lodepng_inflatev(ucvector* out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { /*bit pointer in the "in" data, current byte is bp >> 3, current bit is bp & 0x7 (from lsb to msb of the byte)*/ size_t bp = 0; unsigned BFINAL = 0; size_t pos = 0; /*byte position in the out buffer*/ unsigned error = 0; (void) settings; while (!BFINAL) { unsigned BTYPE; if (bp + 2 >= insize * 8) return 52; /*error, bit pointer will jump past memory*/ BFINAL = readBitFromStream(&bp, in); BTYPE = 1u * readBitFromStream(&bp, in); BTYPE += 2u * readBitFromStream(&bp, in); if (BTYPE == 3) return 20; /*error: invalid BTYPE*/ else if (BTYPE == 0) error = inflateNoCompression(out, in, &bp, &pos, insize); /*no compression*/ else error = inflateHuffmanBlock(out, in, &bp, &pos, insize, BTYPE); /*compression, BTYPE 01 or 10*/ if (error) return error; } /*Only now we know the true size of out, resize it to that*/ if (!ucvector_resize(out, pos)) error = 83; /*alloc fail*/ return error; } unsigned lodepng_inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { unsigned error; ucvector v; ucvector_init_buffer(&v, *out, *outsize); error = lodepng_inflatev(&v, in, insize, settings); *out = v.data; *outsize = v.size; return error; } static unsigned inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (settings->custom_inflate) { return settings->custom_inflate(out, outsize, in, insize, settings); } else { return lodepng_inflate(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* ////////////////////////////////////////////////////////////////////////// */ /* / Deflator (Compressor) / */ /* ////////////////////////////////////////////////////////////////////////// */ static const size_t MAX_SUPPORTED_DEFLATE_LENGTH = 258; /*bitlen is the size in bits of the code*/ static void addHuffmanSymbol(size_t* bp, ucvector* compressed, unsigned code, unsigned bitlen) { addBitsToStreamReversed(bp, compressed, code, bitlen); } /*search the index in the array, that has the largest value smaller than or equal to the given value, given array must be sorted (if no value is smaller, it returns the size of the given array)*/ static size_t searchCodeIndex(const unsigned* array, size_t array_size, size_t value) { /*linear search implementation*/ /*for(size_t i = 1; i < array_size; i++) if(array[i] > value) return i - 1; return array_size - 1;*/ /*binary search implementation (not that much faster) (precondition: array_size > 0)*/ size_t left = 1; size_t right = array_size - 1; while (left <= right) { size_t mid = (left + right) / 2; if (array[mid] <= value) left = mid + 1; /*the value to find is more to the right*/ else if (array[mid - 1] > value) right = mid - 1; /*the value to find is more to the left*/ else return mid - 1; } return array_size - 1; } static void addLengthDistance(uivector* values, size_t length, size_t distance) { /*values in encoded vector are those used by deflate: 0-255: literal bytes 256: end 257-285: length/distance pair (length code, followed by extra length bits, distance code, extra distance bits) 286-287: invalid*/ unsigned length_code = (unsigned) searchCodeIndex(LENGTHBASE, 29, length); unsigned extra_length = (unsigned) (length - LENGTHBASE[length_code]); unsigned dist_code = (unsigned) searchCodeIndex(DISTANCEBASE, 30, distance); unsigned extra_distance = (unsigned) (distance - DISTANCEBASE[dist_code]); uivector_push_back(values, length_code + FIRST_LENGTH_CODE_INDEX); uivector_push_back(values, extra_length); uivector_push_back(values, dist_code); uivector_push_back(values, extra_distance); } /*3 bytes of data get encoded into two bytes. The hash cannot use more than 3 bytes as input because 3 is the minimum match length for deflate*/ static const unsigned HASH_NUM_VALUES = 65536; static const unsigned HASH_BIT_MASK = 65535; /*HASH_NUM_VALUES - 1, but C90 does not like that as initializer*/ typedef struct Hash { int* head; /*hash value to head circular pos - can be outdated if went around window*/ /*circular pos to prev circular pos*/ unsigned short* chain; int* val; /*circular pos to hash value*/ /*TODO: do this not only for zeros but for any repeated byte. However for PNG it's always going to be the zeros that dominate, so not important for PNG*/ int* headz; /*similar to head, but for chainz*/ unsigned short* chainz; /*those with same amount of zeros*/ unsigned short* zeros; /*length of zeros streak, used as a second hash chain*/ } Hash; static unsigned hash_init(Hash* hash, unsigned windowsize) { unsigned i; hash->head = (int*) lodepng_malloc(sizeof(int) * HASH_NUM_VALUES); hash->val = (int*) lodepng_malloc(sizeof(int) * windowsize); hash->chain = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); hash->zeros = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); hash->headz = (int*) lodepng_malloc( sizeof(int) * (MAX_SUPPORTED_DEFLATE_LENGTH + 1)); hash->chainz = (unsigned short*) lodepng_malloc( sizeof(unsigned short) * windowsize); if (!hash->head || !hash->chain || !hash->val || !hash->headz || !hash->chainz || !hash->zeros) { return 83; /*alloc fail*/ } /*initialize hash table*/ for (i = 0; i < HASH_NUM_VALUES; i++) hash->head[i] = -1; for (i = 0; i < windowsize; i++) hash->val[i] = -1; for (i = 0; i < windowsize; i++) hash->chain[i] = i; /*same value as index indicates uninitialized*/ for (i = 0; i <= MAX_SUPPORTED_DEFLATE_LENGTH; i++) hash->headz[i] = -1; for (i = 0; i < windowsize; i++) hash->chainz[i] = i; /*same value as index indicates uninitialized*/ return 0; } static void hash_cleanup(Hash* hash) { lodepng_free(hash->head); lodepng_free(hash->val); lodepng_free(hash->chain); lodepng_free(hash->zeros); lodepng_free(hash->headz); lodepng_free(hash->chainz); } static unsigned getHash(const unsigned char* data, size_t size, size_t pos) { unsigned result = 0; if (pos + 2 < size) { /*A simple shift and xor hash is used. Since the data of PNGs is dominated by zeroes due to the filters, a better hash does not have a significant effect on speed in traversing the chain, and causes more time spend on calculating the hash.*/ result ^= (unsigned) (data[pos + 0] << 0u); result ^= (unsigned) (data[pos + 1] << 4u); result ^= (unsigned) (data[pos + 2] << 8u); } else { size_t amount, i; if (pos >= size) return 0; amount = size - pos; for (i = 0; i < amount; i++) result ^= (unsigned) (data[pos + i] << (i * 8u)); } return result & HASH_BIT_MASK; } static unsigned countZeros(const unsigned char* data, size_t size, size_t pos) { const unsigned char* start = data + pos; const unsigned char* end = start + MAX_SUPPORTED_DEFLATE_LENGTH; if (end > data + size) end = data + size; data = start; while (data != end && *data == 0) data++; /*subtracting two addresses returned as 32-bit number (max value is MAX_SUPPORTED_DEFLATE_LENGTH)*/ return (unsigned) (data - start); } /*wpos = pos & (windowsize - 1)*/ static void updateHashChain(Hash* hash, size_t wpos, unsigned hashval, unsigned short numzeros) { hash->val[wpos] = (int) hashval; if (hash->head[hashval] != -1) hash->chain[wpos] = hash->head[hashval]; hash->head[hashval] = wpos; hash->zeros[wpos] = numzeros; if (hash->headz[numzeros] != -1) hash->chainz[wpos] = hash->headz[numzeros]; hash->headz[numzeros] = wpos; } /* LZ77-encode the data. Return value is error code. The input are raw bytes, the output is in the form of unsigned integers with codes representing for example literal bytes, or length/distance pairs. It uses a hash table technique to let it encode faster. When doing LZ77 encoding, a sliding window (of windowsize) is used, and all past bytes in that window can be used as the "dictionary". A brute force search through all possible distances would be slow, and this hash technique is one out of several ways to speed this up. */ static unsigned encodeLZ77(uivector* out, Hash* hash, const unsigned char* in, size_t inpos, size_t insize, unsigned windowsize, unsigned minmatch, unsigned nicematch, unsigned lazymatching) { size_t pos; unsigned i, error = 0; /*for large window lengths, assume the user wants no compression loss. Otherwise, max hash chain length speedup.*/ unsigned maxchainlength = windowsize >= 8192 ? windowsize : windowsize / 8; unsigned maxlazymatch = windowsize >= 8192 ? MAX_SUPPORTED_DEFLATE_LENGTH : 64; unsigned usezeros = 1; /*not sure if setting it to false for windowsize < 8192 is better or worse*/ unsigned numzeros = 0; unsigned offset; /*the offset represents the distance in LZ77 terminology*/ unsigned length; unsigned lazy = 0; unsigned lazylength = 0, lazyoffset = 0; unsigned hashval; unsigned current_offset, current_length; unsigned prev_offset; const unsigned char *lastptr, *foreptr, *backptr; unsigned hashpos; if (windowsize <= 0 || windowsize > 32768) return 60; /*error: windowsize smaller/larger than allowed*/ if ((windowsize & (windowsize - 1)) != 0) return 90; /*error: must be power of two*/ if (nicematch > MAX_SUPPORTED_DEFLATE_LENGTH) nicematch = MAX_SUPPORTED_DEFLATE_LENGTH; for (pos = inpos; pos < insize; pos++) { size_t wpos = pos & (windowsize - 1); /*position for in 'circular' hash buffers*/ unsigned chainlength = 0; hashval = getHash(in, insize, pos); if (usezeros && hashval == 0) { if (numzeros == 0) numzeros = countZeros(in, insize, pos); else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; } else { numzeros = 0; } updateHashChain(hash, wpos, hashval, numzeros); /*the length and offset found for the current position*/ length = 0; offset = 0; hashpos = hash->chain[wpos]; lastptr = &in[ insize < pos + MAX_SUPPORTED_DEFLATE_LENGTH ? insize : pos + MAX_SUPPORTED_DEFLATE_LENGTH]; /*search for the longest string*/ prev_offset = 0; for (;;) { if (chainlength++ >= maxchainlength) break; current_offset = hashpos <= wpos ? wpos - hashpos : wpos - hashpos + windowsize; if (current_offset < prev_offset) break; /*stop when went completely around the circular buffer*/ prev_offset = current_offset; if (current_offset > 0) { /*test the next characters*/ foreptr = &in[pos]; backptr = &in[pos - current_offset]; /*common case in PNGs is lots of zeros. Quickly skip over them as a speedup*/ if (numzeros >= 3) { unsigned skip = hash->zeros[hashpos]; if (skip > numzeros) skip = numzeros; backptr += skip; foreptr += skip; } while (foreptr != lastptr && *backptr == *foreptr) /*maximum supported length by deflate is max length*/ { ++backptr; ++foreptr; } current_length = (unsigned) (foreptr - &in[pos]); if (current_length > length) { length = current_length; /*the longest length*/ offset = current_offset; /*the offset that is related to this longest length*/ /*jump out once a length of max length is found (speed gain). This also jumps out if length is MAX_SUPPORTED_DEFLATE_LENGTH*/ if (current_length >= nicematch) break; } } if (hashpos == hash->chain[hashpos]) break; if (numzeros >= 3 && length > numzeros) { hashpos = hash->chainz[hashpos]; if (hash->zeros[hashpos] != numzeros) break; } else { hashpos = hash->chain[hashpos]; /*outdated hash value, happens if particular value was not encountered in whole last window*/ if (hash->val[hashpos] != (int) hashval) break; } } if (lazymatching) { if (!lazy && length >= 3 && length <= maxlazymatch && length < MAX_SUPPORTED_DEFLATE_LENGTH) { lazy = 1; lazylength = length; lazyoffset = offset; continue; /*try the next byte*/ } if (lazy) { lazy = 0; if (pos == 0) ERROR_BREAK(81); if (length > lazylength + 1) { /*push the previous character as literal*/ if (!uivector_push_back(out, in[pos - 1])) ERROR_BREAK(83 /*alloc fail*/); } else { length = lazylength; offset = lazyoffset; hash->head[hashval] = -1; /*the same hashchain update will be done, this ensures no wrong alteration*/ hash->headz[numzeros] = -1; /*idem*/ pos--; } } } if (length >= 3 && offset > windowsize) ERROR_BREAK(86 /*too big (or overflown negative) offset*/); /*encode it as length/distance pair or literal value*/ if (length < 3) /*only lengths of 3 or higher are supported as length/distance pair*/ { if (!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); } else if (length < minmatch || (length == 3 && offset > 4096)) { /*compensate for the fact that longer offsets have more extra bits, a length of only 3 may be not worth it then*/ if (!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); } else { addLengthDistance(out, length, offset); for (i = 1; i < length; i++) { pos++; wpos = pos & (windowsize - 1); hashval = getHash(in, insize, pos); if (usezeros && hashval == 0) { if (numzeros == 0) numzeros = countZeros(in, insize, pos); else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; } else { numzeros = 0; } updateHashChain(hash, wpos, hashval, numzeros); } } } /*end of the loop through each character of input*/ return error; } /* /////////////////////////////////////////////////////////////////////////// */ static unsigned deflateNoCompression(ucvector* out, const unsigned char* data, size_t datasize) { /*non compressed deflate block data: 1 bit BFINAL,2 bits BTYPE,(5 bits): it jumps to start of next byte, 2 bytes LEN, 2 bytes NLEN, LEN bytes literal DATA*/ size_t i, j, numdeflateblocks = (datasize + 65534) / 65535; unsigned datapos = 0; for (i = 0; i < numdeflateblocks; i++) { unsigned BFINAL, BTYPE, LEN, NLEN; unsigned char firstbyte; BFINAL = (i == numdeflateblocks - 1); BTYPE = 0; firstbyte = (unsigned char) (BFINAL + ((BTYPE & 1) << 1) + ((BTYPE & 2) << 1)); ucvector_push_back(out, firstbyte); LEN = 65535; if (datasize - datapos < 65535) LEN = (unsigned) datasize - datapos; NLEN = 65535 - LEN; ucvector_push_back(out, (unsigned char) (LEN % 256)); ucvector_push_back(out, (unsigned char) (LEN / 256)); ucvector_push_back(out, (unsigned char) (NLEN % 256)); ucvector_push_back(out, (unsigned char) (NLEN / 256)); /*Decompressed data*/ for (j = 0; j < 65535 && datapos < datasize; j++) { ucvector_push_back(out, data[datapos++]); } } return 0; } /* write the lz77-encoded data, which has lit, len and dist codes, to compressed stream using huffman trees. tree_ll: the tree for lit and len codes. tree_d: the tree for distance codes. */ static void writeLZ77data(size_t* bp, ucvector* out, const uivector* lz77_encoded, const HuffmanTree* tree_ll, const HuffmanTree* tree_d) { size_t i = 0; for (i = 0; i < lz77_encoded->size; i++) { unsigned val = lz77_encoded->data[i]; addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_ll, val), HuffmanTree_getLength(tree_ll, val)); if (val > 256) /*for a length code, 3 more things have to be added*/ { unsigned length_index = val - FIRST_LENGTH_CODE_INDEX; unsigned n_length_extra_bits = LENGTHEXTRA[length_index]; unsigned length_extra_bits = lz77_encoded->data[++i]; unsigned distance_code = lz77_encoded->data[++i]; unsigned distance_index = distance_code; unsigned n_distance_extra_bits = DISTANCEEXTRA[distance_index]; unsigned distance_extra_bits = lz77_encoded->data[++i]; addBitsToStream(bp, out, length_extra_bits, n_length_extra_bits); addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_d, distance_code), HuffmanTree_getLength(tree_d, distance_code)); addBitsToStream(bp, out, distance_extra_bits, n_distance_extra_bits); } } } /*Deflate for a block of type "dynamic", that is, with freely, optimally, created huffman trees*/ static unsigned deflateDynamic(ucvector* out, size_t* bp, Hash* hash, const unsigned char* data, size_t datapos, size_t dataend, const LodePNGCompressSettings* settings, unsigned final) { unsigned error = 0; /* A block is compressed as follows: The PNG data is lz77 encoded, resulting in literal bytes and length/distance pairs. This is then huffman compressed with two huffman trees. One huffman tree is used for the lit and len values ("ll"), another huffman tree is used for the dist values ("d"). These two trees are stored using their code lengths, and to compress even more these code lengths are also run-length encoded and huffman compressed. This gives a huffman tree of code lengths "cl". The code lenghts used to describe this third tree are the code length code lengths ("clcl"). */ /*The lz77 encoded data, represented with integers since there will also be length and distance codes in it*/ uivector lz77_encoded; HuffmanTree tree_ll; /*tree for lit,len values*/ HuffmanTree tree_d; /*tree for distance codes*/ HuffmanTree tree_cl; /*tree for encoding the code lengths representing tree_ll and tree_d*/ uivector frequencies_ll; /*frequency of lit,len codes*/ uivector frequencies_d; /*frequency of dist codes*/ uivector frequencies_cl; /*frequency of code length codes*/ uivector bitlen_lld; /*lit,len,dist code lenghts (int bits), literally (without repeat codes).*/ uivector bitlen_lld_e; /*bitlen_lld encoded with repeat codes (this is a rudemtary run length compression)*/ /*bitlen_cl is the code length code lengths ("clcl"). The bit lengths of codes to represent tree_cl (these are written as is in the file, it would be crazy to compress these using yet another huffman tree that needs to be represented by yet another set of code lengths)*/ uivector bitlen_cl; size_t datasize = dataend - datapos; /* Due to the huffman compression of huffman tree representations ("two levels"), there are some anologies: bitlen_lld is to tree_cl what data is to tree_ll and tree_d. bitlen_lld_e is to bitlen_lld what lz77_encoded is to data. bitlen_cl is to bitlen_lld_e what bitlen_lld is to lz77_encoded. */ unsigned BFINAL = final; size_t numcodes_ll, numcodes_d, i; unsigned HLIT, HDIST, HCLEN; uivector_init(&lz77_encoded); HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); HuffmanTree_init(&tree_cl); uivector_init(&frequencies_ll); uivector_init(&frequencies_d); uivector_init(&frequencies_cl); uivector_init(&bitlen_lld); uivector_init(&bitlen_lld_e); uivector_init(&bitlen_cl); /*This while loop never loops due to a break at the end, it is here to allow breaking out of it to the cleanup phase on error conditions.*/ while (!error) { if (settings->use_lz77) { error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, settings->minmatch, settings->nicematch, settings->lazymatching); if (error) break; } else { if (!uivector_resize(&lz77_encoded, datasize)) ERROR_BREAK(83 /*alloc fail*/); for (i = datapos; i < dataend; i++) lz77_encoded.data[i] = data[i]; /*no LZ77, but still will be Huffman compressed*/ } if (!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83 /*alloc fail*/); if (!uivector_resizev(&frequencies_d, 30, 0)) ERROR_BREAK(83 /*alloc fail*/); /*Count the frequencies of lit, len and dist codes*/ for (i = 0; i < lz77_encoded.size; i++) { unsigned symbol = lz77_encoded.data[i]; frequencies_ll.data[symbol]++; if (symbol > 256) { unsigned dist = lz77_encoded.data[i + 2]; frequencies_d.data[dist]++; i += 3; } } frequencies_ll.data[256] = 1; /*there will be exactly 1 end code, at the end of the block*/ /*Make both huffman trees, one for the lit and len codes, one for the dist codes*/ error = HuffmanTree_makeFromFrequencies(&tree_ll, frequencies_ll.data, 257, frequencies_ll.size, 15); if (error) break; /*2, not 1, is chosen for mincodes: some buggy PNG decoders require at least 2 symbols in the dist tree*/ error = HuffmanTree_makeFromFrequencies(&tree_d, frequencies_d.data, 2, frequencies_d.size, 15); if (error) break; numcodes_ll = tree_ll.numcodes; if (numcodes_ll > 286) numcodes_ll = 286; numcodes_d = tree_d.numcodes; if (numcodes_d > 30) numcodes_d = 30; /*store the code lengths of both generated trees in bitlen_lld*/ for (i = 0; i < numcodes_ll; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_ll, (unsigned) i)); for (i = 0; i < numcodes_d; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_d, (unsigned) i)); /*run-length compress bitlen_ldd into bitlen_lld_e by using repeat codes 16 (copy length 3-6 times), 17 (3-10 zeroes), 18 (11-138 zeroes)*/ for (i = 0; i < (unsigned) bitlen_lld.size; i++) { unsigned j = 0; /*amount of repititions*/ while (i + j + 1 < (unsigned) bitlen_lld.size && bitlen_lld.data[i + j + 1] == bitlen_lld.data[i]) j++; if (bitlen_lld.data[i] == 0 && j >= 2) /*repeat code for zeroes*/ { j++; /*include the first zero*/ if (j <= 10) /*repeat code 17 supports max 10 zeroes*/ { uivector_push_back(&bitlen_lld_e, 17); uivector_push_back(&bitlen_lld_e, j - 3); } else /*repeat code 18 supports max 138 zeroes*/ { if (j > 138) j = 138; uivector_push_back(&bitlen_lld_e, 18); uivector_push_back(&bitlen_lld_e, j - 11); } i += (j - 1); } else if (j >= 3) /*repeat code for value other than zero*/ { size_t k; unsigned num = j / 6, rest = j % 6; uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); for (k = 0; k < num; k++) { uivector_push_back(&bitlen_lld_e, 16); uivector_push_back(&bitlen_lld_e, 6 - 3); } if (rest >= 3) { uivector_push_back(&bitlen_lld_e, 16); uivector_push_back(&bitlen_lld_e, rest - 3); } else j -= rest; i += j; } else /*too short to benefit from repeat code*/ { uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); } } /*generate tree_cl, the huffmantree of huffmantrees*/ if (!uivector_resizev(&frequencies_cl, NUM_CODE_LENGTH_CODES, 0)) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < bitlen_lld_e.size; i++) { frequencies_cl.data[bitlen_lld_e.data[i]]++; /*after a repeat code come the bits that specify the number of repetitions, those don't need to be in the frequencies_cl calculation*/ if (bitlen_lld_e.data[i] >= 16) i++; } error = HuffmanTree_makeFromFrequencies(&tree_cl, frequencies_cl.data, frequencies_cl.size, frequencies_cl.size, 7); if (error) break; if (!uivector_resize(&bitlen_cl, tree_cl.numcodes)) ERROR_BREAK(83 /*alloc fail*/); for (i = 0; i < tree_cl.numcodes; i++) { /*lenghts of code length tree is in the order as specified by deflate*/ bitlen_cl.data[i] = HuffmanTree_getLength(&tree_cl, CLCL_ORDER[i]); } while (bitlen_cl.data[bitlen_cl.size - 1] == 0 && bitlen_cl.size > 4) { /*remove zeros at the end, but minimum size must be 4*/ if (!uivector_resize(&bitlen_cl, bitlen_cl.size - 1)) ERROR_BREAK(83 /*alloc fail*/); } if (error) break; /* Write everything into the output After the BFINAL and BTYPE, the dynamic block consists out of the following: - 5 bits HLIT, 5 bits HDIST, 4 bits HCLEN - (HCLEN+4)*3 bits code lengths of code length alphabet - HLIT + 257 code lenghts of lit/length alphabet (encoded using the code length alphabet, + possible repetition codes 16, 17, 18) - HDIST + 1 code lengths of distance alphabet (encoded using the code length alphabet, + possible repetition codes 16, 17, 18) - compressed data - 256 (end code) */ /*Write block type*/ addBitToStream(bp, out, BFINAL); addBitToStream(bp, out, 0); /*first bit of BTYPE "dynamic"*/ addBitToStream(bp, out, 1); /*second bit of BTYPE "dynamic"*/ /*write the HLIT, HDIST and HCLEN values*/ HLIT = (unsigned) (numcodes_ll - 257); HDIST = (unsigned) (numcodes_d - 1); HCLEN = (unsigned) bitlen_cl.size - 4; /*trim zeroes for HCLEN. HLIT and HDIST were already trimmed at tree creation*/ while (!bitlen_cl.data[HCLEN + 4 - 1] && HCLEN > 0) HCLEN--; addBitsToStream(bp, out, HLIT, 5); addBitsToStream(bp, out, HDIST, 5); addBitsToStream(bp, out, HCLEN, 4); /*write the code lenghts of the code length alphabet*/ for (i = 0; i < HCLEN + 4; i++) addBitsToStream(bp, out, bitlen_cl.data[i], 3); /*write the lenghts of the lit/len AND the dist alphabet*/ for (i = 0; i < bitlen_lld_e.size; i++) { addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_cl, bitlen_lld_e.data[i]), HuffmanTree_getLength(&tree_cl, bitlen_lld_e.data[i])); /*extra bits of repeat codes*/ if (bitlen_lld_e.data[i] == 16) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 2); else if (bitlen_lld_e.data[i] == 17) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 3); else if (bitlen_lld_e.data[i] == 18) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 7); } /*write the compressed data symbols*/ writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); /*error: the length of the end code 256 must be larger than 0*/ if (HuffmanTree_getLength(&tree_ll, 256) == 0) ERROR_BREAK(64); /*write the end code*/ addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); break; /*end of error-while*/ } /*cleanup*/ uivector_cleanup(&lz77_encoded); HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); HuffmanTree_cleanup(&tree_cl); uivector_cleanup(&frequencies_ll); uivector_cleanup(&frequencies_d); uivector_cleanup(&frequencies_cl); uivector_cleanup(&bitlen_lld_e); uivector_cleanup(&bitlen_lld); uivector_cleanup(&bitlen_cl); return error; } static unsigned deflateFixed(ucvector* out, size_t* bp, Hash* hash, const unsigned char* data, size_t datapos, size_t dataend, const LodePNGCompressSettings* settings, unsigned final) { HuffmanTree tree_ll; /*tree for literal values and length codes*/ HuffmanTree tree_d; /*tree for distance codes*/ unsigned BFINAL = final; unsigned error = 0; size_t i; HuffmanTree_init(&tree_ll); HuffmanTree_init(&tree_d); generateFixedLitLenTree(&tree_ll); generateFixedDistanceTree(&tree_d); addBitToStream(bp, out, BFINAL); addBitToStream(bp, out, 1); /*first bit of BTYPE*/ addBitToStream(bp, out, 0); /*second bit of BTYPE*/ if (settings->use_lz77) /*LZ77 encoded*/ { uivector lz77_encoded; uivector_init(&lz77_encoded); error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, settings->minmatch, settings->nicematch, settings->lazymatching); if (!error) writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); uivector_cleanup(&lz77_encoded); } else /*no LZ77, but still will be Huffman compressed*/ { for (i = datapos; i < dataend; i++) { addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, data[i]), HuffmanTree_getLength(&tree_ll, data[i])); } } /*add END code*/ if (!error) addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); /*cleanup*/ HuffmanTree_cleanup(&tree_ll); HuffmanTree_cleanup(&tree_d); return error; } static unsigned lodepng_deflatev(ucvector* out, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { unsigned error = 0; size_t i, blocksize, numdeflateblocks; size_t bp = 0; /*the bit pointer*/ Hash hash; if (settings->btype > 2) return 61; else if (settings->btype == 0) return deflateNoCompression(out, in, insize); else if (settings->btype == 1) blocksize = insize; else /*if(settings->btype == 2)*/ { blocksize = insize / 8 + 8; if (blocksize < 65535) blocksize = 65535; } numdeflateblocks = (insize + blocksize - 1) / blocksize; if (numdeflateblocks == 0) numdeflateblocks = 1; error = hash_init(&hash, settings->windowsize); if (error) return error; for (i = 0; i < numdeflateblocks && !error; i++) { unsigned final = (i == numdeflateblocks - 1); size_t start = i * blocksize; size_t end = start + blocksize; if (end > insize) end = insize; if (settings->btype == 1) error = deflateFixed(out, &bp, &hash, in, start, end, settings, final); else if (settings->btype == 2) error = deflateDynamic(out, &bp, &hash, in, start, end, settings, final); } hash_cleanup(&hash); return error; } unsigned lodepng_deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { unsigned error; ucvector v; ucvector_init_buffer(&v, *out, *outsize); error = lodepng_deflatev(&v, in, insize, settings); *out = v.data; *outsize = v.size; return error; } static unsigned deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (settings->custom_deflate) { return settings->custom_deflate(out, outsize, in, insize, settings); } else { return lodepng_deflate(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* / Adler32 */ /* ////////////////////////////////////////////////////////////////////////// */ static unsigned update_adler32(unsigned adler, const unsigned char* data, unsigned len) { unsigned s1 = adler & 0xffff; unsigned s2 = (adler >> 16) & 0xffff; while (len > 0) { /*at least 5550 sums can be done before the sums overflow, saving a lot of module divisions*/ unsigned amount = len > 5550 ? 5550 : len; len -= amount; while (amount > 0) { s1 += (*data++); s2 += s1; amount--; } s1 %= 65521; s2 %= 65521; } return (s2 << 16) | s1; } /*Return the adler32 of the bytes data[0..len-1]*/ static unsigned adler32(const unsigned char* data, unsigned len) { return update_adler32(1L, data, len); } /* ////////////////////////////////////////////////////////////////////////// */ /* / Zlib / */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_DECODER unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { unsigned error = 0; unsigned CM, CINFO, FDICT; if (insize < 2) return 53; /*error, size of zlib data too small*/ /*read information from zlib header*/ if ((in[0] * 256 + in[1]) % 31 != 0) { /*error: 256 * in[0] + in[1] must be a multiple of 31, the FCHECK value is supposed to be made that way*/ return 24; } CM = in[0] & 15; CINFO = (in[0] >> 4) & 15; /*FCHECK = in[1] & 31;*//*FCHECK is already tested above*/ FDICT = (in[1] >> 5) & 1; /*FLEVEL = (in[1] >> 6) & 3;*//*FLEVEL is not used here*/ if (CM != 8 || CINFO > 7) { /*error: only compression method 8: inflate with sliding window of 32k is supported by the PNG spec*/ return 25; } if (FDICT != 0) { /*error: the specification of PNG says about the zlib stream: "The additional flags shall not specify a preset dictionary."*/ return 26; } error = inflate(out, outsize, in + 2, insize - 2, settings); if (error) return error; if (!settings->ignore_adler32) { unsigned ADLER32 = lodepng_read32bitInt(&in[insize - 4]); unsigned checksum = adler32(*out, (unsigned) (*outsize)); if (checksum != ADLER32) return 58; /*error, adler checksum not correct, data must be corrupted*/ } return 0; /*no error*/ } static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (settings->custom_zlib) { return settings->custom_zlib(out, outsize, in, insize, settings); } else { return lodepng_zlib_decompress(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { /*initially, *out must be NULL and outsize 0, if you just give some random *out that's pointing to a non allocated buffer, this'll crash*/ ucvector outv; size_t i; unsigned error; unsigned char* deflatedata = 0; size_t deflatesize = 0; unsigned ADLER32; /*zlib data: 1 byte CMF (CM+CINFO), 1 byte FLG, deflate data, 4 byte ADLER32 checksum of the Decompressed data*/ unsigned CMF = 120; /*0b01111000: CM 8, CINFO 7. With CINFO 7, any window size up to 32768 can be used.*/ unsigned FLEVEL = 0; unsigned FDICT = 0; unsigned CMFFLG = 256 * CMF + FDICT * 32 + FLEVEL * 64; unsigned FCHECK = 31 - CMFFLG % 31; CMFFLG += FCHECK; /*ucvector-controlled version of the output buffer, for dynamic array*/ ucvector_init_buffer(&outv, *out, *outsize); ucvector_push_back(&outv, (unsigned char) (CMFFLG / 256)); ucvector_push_back(&outv, (unsigned char) (CMFFLG % 256)); error = deflate(&deflatedata, &deflatesize, in, insize, settings); if (!error) { ADLER32 = adler32(in, (unsigned) insize); for (i = 0; i < deflatesize; i++) ucvector_push_back(&outv, deflatedata[i]); lodepng_free(deflatedata); lodepng_add32bitInt(&outv, ADLER32); } *out = outv.data; *outsize = outv.size; return error; } /* compress using the default or custom zlib function */ static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (settings->custom_zlib) { return settings->custom_zlib(out, outsize, in, insize, settings); } else { return lodepng_zlib_compress(out, outsize, in, insize, settings); } } #endif /*LODEPNG_COMPILE_ENCODER*/ #else /*no LODEPNG_COMPILE_ZLIB*/ #ifdef LODEPNG_COMPILE_DECODER static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings) { if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ return settings->custom_zlib(out, outsize, in, insize, settings); } #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings) { if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ return settings->custom_zlib(out, outsize, in, insize, settings); } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_ENCODER /*this is a good tradeoff between speed and compression ratio*/ #define DEFAULT_WINDOWSIZE 2048 void lodepng_compress_settings_init(LodePNGCompressSettings* settings) { /*compress with dynamic huffman tree (not in the mathematical sense, just not the predefined one)*/ settings->btype = 2; settings->use_lz77 = 1; settings->windowsize = DEFAULT_WINDOWSIZE; settings->minmatch = 3; settings->nicematch = 128; settings->lazymatching = 1; settings->custom_zlib = 0; settings->custom_deflate = 0; settings->custom_context = 0; } const LodePNGCompressSettings lodepng_default_compress_settings = { 2, 1, DEFAULT_WINDOWSIZE, 3, 128, 1, 0, 0, 0 }; #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DECODER void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings) { settings->ignore_adler32 = 0; settings->custom_zlib = 0; settings->custom_inflate = 0; settings->custom_context = 0; } const LodePNGDecompressSettings lodepng_default_decompress_settings = { 0, 0, 0, 0 }; #endif /*LODEPNG_COMPILE_DECODER*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // End of Zlib related code. Begin of PNG related code. // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_PNG /* ////////////////////////////////////////////////////////////////////////// */ /* / CRC32 / */ /* ////////////////////////////////////////////////////////////////////////// */ /* CRC polynomial: 0xedb88320 */ static unsigned lodepng_crc32_table[256] = { 0u, 1996959894u, 3993919788u, 2567524794u, 124634137u, 1886057615u, 3915621685u, 2657392035u, 249268274u, 2044508324u, 3772115230u, 2547177864u, 162941995u, 2125561021u, 3887607047u, 2428444049u, 498536548u, 1789927666u, 4089016648u, 2227061214u, 450548861u, 1843258603u, 4107580753u, 2211677639u, 325883990u, 1684777152u, 4251122042u, 2321926636u, 335633487u, 1661365465u, 4195302755u, 2366115317u, 997073096u, 1281953886u, 3579855332u, 2724688242u, 1006888145u, 1258607687u, 3524101629u, 2768942443u, 901097722u, 1119000684u, 3686517206u, 2898065728u, 853044451u, 1172266101u, 3705015759u, 2882616665u, 651767980u, 1373503546u, 3369554304u, 3218104598u, 565507253u, 1454621731u, 3485111705u, 3099436303u, 671266974u, 1594198024u, 3322730930u, 2970347812u, 795835527u, 1483230225u, 3244367275u, 3060149565u, 1994146192u, 31158534u, 2563907772u, 4023717930u, 1907459465u, 112637215u, 2680153253u, 3904427059u, 2013776290u, 251722036u, 2517215374u, 3775830040u, 2137656763u, 141376813u, 2439277719u, 3865271297u, 1802195444u, 476864866u, 2238001368u, 4066508878u, 1812370925u, 453092731u, 2181625025u, 4111451223u, 1706088902u, 314042704u, 2344532202u, 4240017532u, 1658658271u, 366619977u, 2362670323u, 4224994405u, 1303535960u, 984961486u, 2747007092u, 3569037538u, 1256170817u, 1037604311u, 2765210733u, 3554079995u, 1131014506u, 879679996u, 2909243462u, 3663771856u, 1141124467u, 855842277u, 2852801631u, 3708648649u, 1342533948u, 654459306u, 3188396048u, 3373015174u, 1466479909u, 544179635u, 3110523913u, 3462522015u, 1591671054u, 702138776u, 2966460450u, 3352799412u, 1504918807u, 783551873u, 3082640443u, 3233442989u, 3988292384u, 2596254646u, 62317068u, 1957810842u, 3939845945u, 2647816111u, 81470997u, 1943803523u, 3814918930u, 2489596804u, 225274430u, 2053790376u, 3826175755u, 2466906013u, 167816743u, 2097651377u, 4027552580u, 2265490386u, 503444072u, 1762050814u, 4150417245u, 2154129355u, 426522225u, 1852507879u, 4275313526u, 2312317920u, 282753626u, 1742555852u, 4189708143u, 2394877945u, 397917763u, 1622183637u, 3604390888u, 2714866558u, 953729732u, 1340076626u, 3518719985u, 2797360999u, 1068828381u, 1219638859u, 3624741850u, 2936675148u, 906185462u, 1090812512u, 3747672003u, 2825379669u, 829329135u, 1181335161u, 3412177804u, 3160834842u, 628085408u, 1382605366u, 3423369109u, 3138078467u, 570562233u, 1426400815u, 3317316542u, 2998733608u, 733239954u, 1555261956u, 3268935591u, 3050360625u, 752459403u, 1541320221u, 2607071920u, 3965973030u, 1969922972u, 40735498u, 2617837225u, 3943577151u, 1913087877u, 83908371u, 2512341634u, 3803740692u, 2075208622u, 213261112u, 2463272603u, 3855990285u, 2094854071u, 198958881u, 2262029012u, 4057260610u, 1759359992u, 534414190u, 2176718541u, 4139329115u, 1873836001u, 414664567u, 2282248934u, 4279200368u, 1711684554u, 285281116u, 2405801727u, 4167216745u, 1634467795u, 376229701u, 2685067896u, 3608007406u, 1308918612u, 956543938u, 2808555105u, 3495958263u, 1231636301u, 1047427035u, 2932959818u, 3654703836u, 1088359270u, 936918000u, 2847714899u, 3736837829u, 1202900863u, 817233897u, 3183342108u, 3401237130u, 1404277552u, 615818150u, 3134207493u, 3453421203u, 1423857449u, 601450431u, 3009837614u, 3294710456u, 1567103746u, 711928724u, 3020668471u, 3272380065u, 1510334235u, 755167117u }; /*Return the CRC of the bytes buf[0..len-1].*/ unsigned lodepng_crc32(const unsigned char* buf, size_t len) { unsigned c = 0xffffffffL; size_t n; for (n = 0; n < len; n++) { c = lodepng_crc32_table[(c ^ buf[n]) & 0xff] ^ (c >> 8); } return c ^ 0xffffffffL; } /* ////////////////////////////////////////////////////////////////////////// */ /* / Reading and writing single bits and bytes from/to stream for LodePNG / */ /* ////////////////////////////////////////////////////////////////////////// */ static unsigned char readBitFromReversedStream(size_t* bitpointer, const unsigned char* bitstream) { unsigned char result = (unsigned char) ((bitstream[(*bitpointer) >> 3] >> (7 - ((*bitpointer) & 0x7))) & 1); (*bitpointer)++; return result; } static unsigned readBitsFromReversedStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) { unsigned result = 0; size_t i; for (i = nbits - 1; i < nbits; i--) { result += (unsigned) readBitFromReversedStream(bitpointer, bitstream) << i; } return result; } #ifdef LODEPNG_COMPILE_DECODER static void setBitOfReversedStream0(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) { /*the current bit in bitstream must be 0 for this to work*/ if (bit) { /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/ bitstream[(*bitpointer) >> 3] |= (bit << (7 - ((*bitpointer) & 0x7))); } (*bitpointer)++; } #endif /*LODEPNG_COMPILE_DECODER*/ static void setBitOfReversedStream(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) { /*the current bit in bitstream may be 0 or 1 for this to work*/ if (bit == 0) bitstream[(*bitpointer) >> 3] &= (unsigned char) (~(1 << (7 - ((*bitpointer) & 0x7)))); else bitstream[(*bitpointer) >> 3] |= (1 << (7 - ((*bitpointer) & 0x7))); (*bitpointer)++; } /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG chunks / */ /* ////////////////////////////////////////////////////////////////////////// */ unsigned lodepng_chunk_length(const unsigned char* chunk) { return lodepng_read32bitInt(&chunk[0]); } void lodepng_chunk_type(char type[5], const unsigned char* chunk) { unsigned i; for (i = 0; i < 4; i++) type[i] = (char) chunk[4 + i]; type[4] = 0; /*null termination char*/ } unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type) { if (strlen(type) != 4) return 0; return (chunk[4] == type[0] && chunk[5] == type[1] && chunk[6] == type[2] && chunk[7] == type[3]); } unsigned char lodepng_chunk_ancillary(const unsigned char* chunk) { return ((chunk[4] & 32) != 0); } unsigned char lodepng_chunk_private(const unsigned char* chunk) { return ((chunk[6] & 32) != 0); } unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk) { return ((chunk[7] & 32) != 0); } unsigned char* lodepng_chunk_data(unsigned char* chunk) { return &chunk[8]; } const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk) { return &chunk[8]; } unsigned lodepng_chunk_check_crc(const unsigned char* chunk) { unsigned length = lodepng_chunk_length(chunk); unsigned CRC = lodepng_read32bitInt(&chunk[length + 8]); /*the CRC is taken of the data and the 4 chunk type letters, not the length*/ unsigned checksum = lodepng_crc32(&chunk[4], length + 4); if (CRC != checksum) return 1; else return 0; } void lodepng_chunk_generate_crc(unsigned char* chunk) { unsigned length = lodepng_chunk_length(chunk); unsigned CRC = lodepng_crc32(&chunk[4], length + 4); lodepng_set32bitInt(chunk + 8 + length, CRC); } unsigned char* lodepng_chunk_next(unsigned char* chunk) { unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; return &chunk[total_chunk_length]; } const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk) { unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; return &chunk[total_chunk_length]; } unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk) { unsigned i; unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; unsigned char *chunk_start, *new_buffer; size_t new_length = (*outlength) + total_chunk_length; if (new_length < total_chunk_length || new_length < (*outlength)) return 77; /*integer overflow happened*/ new_buffer = (unsigned char*) lodepng_realloc(*out, new_length); if (!new_buffer) return 83; /*alloc fail*/ (*out) = new_buffer; (*outlength) = new_length; chunk_start = &(*out)[new_length - total_chunk_length]; for (i = 0; i < total_chunk_length; i++) chunk_start[i] = chunk[i]; return 0; } unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data) { unsigned i; unsigned char *chunk, *new_buffer; size_t new_length = (*outlength) + length + 12; if (new_length < length + 12 || new_length < (*outlength)) return 77; /*integer overflow happened*/ new_buffer = (unsigned char*) lodepng_realloc(*out, new_length); if (!new_buffer) return 83; /*alloc fail*/ (*out) = new_buffer; (*outlength) = new_length; chunk = &(*out)[(*outlength) - length - 12]; /*1: length*/ lodepng_set32bitInt(chunk, (unsigned) length); /*2: chunk name (4 letters)*/ chunk[4] = (unsigned char) type[0]; chunk[5] = (unsigned char) type[1]; chunk[6] = (unsigned char) type[2]; chunk[7] = (unsigned char) type[3]; /*3: the data*/ for (i = 0; i < length; i++) chunk[8 + i] = data[i]; /*4: CRC (of the chunkname characters and the data)*/ lodepng_chunk_generate_crc(chunk); return 0; } /* ////////////////////////////////////////////////////////////////////////// */ /* / Color types and such / */ /* ////////////////////////////////////////////////////////////////////////// */ /*return type is a LodePNG error code*/ static unsigned checkColorValidity(LodePNGColorType colortype, unsigned bd) /*bd = bitdepth*/ { switch (colortype) { case 0: if (!(bd == 1 || bd == 2 || bd == 4 || bd == 8 || bd == 16)) return 37; break; /*grey*/ case 2: if (!(bd == 8 || bd == 16)) return 37; break; /*RGB*/ case 3: if (!(bd == 1 || bd == 2 || bd == 4 || bd == 8)) return 37; break; /*palette*/ case 4: if (!(bd == 8 || bd == 16)) return 37; break; /*grey + alpha*/ case 6: if (!(bd == 8 || bd == 16)) return 37; break; /*RGBA*/ default: return 31; } return 0; /*allowed color type / bits combination*/ } static unsigned getNumColorChannels(LodePNGColorType colortype) { switch (colortype) { case 0: return 1; /*grey*/ case 2: return 3; /*RGB*/ case 3: return 1; /*palette*/ case 4: return 2; /*grey + alpha*/ case 6: return 4; /*RGBA*/ } return 0; /*unexisting color type*/ } static unsigned lodepng_get_bpp_lct(LodePNGColorType colortype, unsigned bitdepth) { /*bits per pixel is amount of channels * bits per channel*/ return getNumColorChannels(colortype) * bitdepth; } /* ////////////////////////////////////////////////////////////////////////// */ void lodepng_color_mode_init(LodePNGColorMode* info) { info->key_defined = 0; info->key_r = info->key_g = info->key_b = 0; info->colortype = LCT_RGBA; info->bitdepth = 8; info->palette = 0; info->palettesize = 0; } void lodepng_color_mode_cleanup(LodePNGColorMode* info) { lodepng_palette_clear(info); } unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source) { size_t i; lodepng_color_mode_cleanup(dest); *dest = *source; if (source->palette) { dest->palette = (unsigned char*) lodepng_malloc(1024); if (!dest->palette && source->palettesize) return 83; /*alloc fail*/ for (i = 0; i < source->palettesize * 4; i++) dest->palette[i] = source->palette[i]; } return 0; } static int lodepng_color_mode_equal(const LodePNGColorMode* a, const LodePNGColorMode* b) { size_t i; if (a->colortype != b->colortype) return 0; if (a->bitdepth != b->bitdepth) return 0; if (a->key_defined != b->key_defined) return 0; if (a->key_defined) { if (a->key_r != b->key_r) return 0; if (a->key_g != b->key_g) return 0; if (a->key_b != b->key_b) return 0; } if (a->palettesize != b->palettesize) return 0; for (i = 0; i < a->palettesize * 4; i++) { if (a->palette[i] != b->palette[i]) return 0; } return 1; } void lodepng_palette_clear(LodePNGColorMode* info) { if (info->palette) lodepng_free(info->palette); info->palette = 0; info->palettesize = 0; } unsigned lodepng_palette_add(LodePNGColorMode* info, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { unsigned char* data; /*the same resize technique as C++ std::vectors is used, and here it's made so that for a palette with the max of 256 colors, it'll have the exact alloc size*/ if (!info->palette) /*allocate palette if empty*/ { /*room for 256 colors with 4 bytes each*/ data = (unsigned char*) lodepng_realloc(info->palette, 1024); if (!data) return 83; /*alloc fail*/ else info->palette = data; } info->palette[4 * info->palettesize + 0] = r; info->palette[4 * info->palettesize + 1] = g; info->palette[4 * info->palettesize + 2] = b; info->palette[4 * info->palettesize + 3] = a; info->palettesize++; return 0; } unsigned lodepng_get_bpp(const LodePNGColorMode* info) { /*calculate bits per pixel out of colortype and bitdepth*/ return lodepng_get_bpp_lct(info->colortype, info->bitdepth); } unsigned lodepng_get_channels(const LodePNGColorMode* info) { return getNumColorChannels(info->colortype); } unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info) { return info->colortype == LCT_GREY || info->colortype == LCT_GREY_ALPHA; } unsigned lodepng_is_alpha_type(const LodePNGColorMode* info) { return (info->colortype & 4) != 0; /*4 or 6*/ } unsigned lodepng_is_palette_type(const LodePNGColorMode* info) { return info->colortype == LCT_PALETTE; } unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info) { size_t i; for (i = 0; i < info->palettesize; i++) { if (info->palette[i * 4 + 3] < 255) return 1; } return 0; } unsigned lodepng_can_have_alpha(const LodePNGColorMode* info) { return info->key_defined || lodepng_is_alpha_type(info) || lodepng_has_palette_alpha(info); } size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color) { return (w * h * lodepng_get_bpp(color) + 7) / 8; } size_t lodepng_get_raw_size_lct(unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { return (w * h * lodepng_get_bpp_lct(colortype, bitdepth) + 7) / 8; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static void LodePNGUnknownChunks_init(LodePNGInfo* info) { unsigned i; for (i = 0; i < 3; i++) info->unknown_chunks_data[i] = 0; for (i = 0; i < 3; i++) info->unknown_chunks_size[i] = 0; } static void LodePNGUnknownChunks_cleanup(LodePNGInfo* info) { unsigned i; for (i = 0; i < 3; i++) lodepng_free(info->unknown_chunks_data[i]); } static unsigned LodePNGUnknownChunks_copy(LodePNGInfo* dest, const LodePNGInfo* src) { unsigned i; LodePNGUnknownChunks_cleanup(dest); for (i = 0; i < 3; i++) { size_t j; dest->unknown_chunks_size[i] = src->unknown_chunks_size[i]; dest->unknown_chunks_data[i] = (unsigned char*) lodepng_malloc( src->unknown_chunks_size[i]); if (!dest->unknown_chunks_data[i] && dest->unknown_chunks_size[i]) return 83; /*alloc fail*/ for (j = 0; j < src->unknown_chunks_size[i]; j++) { dest->unknown_chunks_data[i][j] = src->unknown_chunks_data[i][j]; } } return 0; } /******************************************************************************/ static void LodePNGText_init(LodePNGInfo* info) { info->text_num = 0; info->text_keys = NULL; info->text_strings = NULL; } static void LodePNGText_cleanup(LodePNGInfo* info) { size_t i; for (i = 0; i < info->text_num; i++) { string_cleanup(&info->text_keys[i]); string_cleanup(&info->text_strings[i]); } lodepng_free(info->text_keys); lodepng_free(info->text_strings); } static unsigned LodePNGText_copy(LodePNGInfo* dest, const LodePNGInfo* source) { size_t i = 0; dest->text_keys = 0; dest->text_strings = 0; dest->text_num = 0; for (i = 0; i < source->text_num; i++) { CERROR_TRY_RETURN( lodepng_add_text(dest, source->text_keys[i], source->text_strings[i])); } return 0; } void lodepng_clear_text(LodePNGInfo* info) { LodePNGText_cleanup(info); } unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str) { char** new_keys = (char**) (lodepng_realloc(info->text_keys, sizeof(char*) * (info->text_num + 1))); char** new_strings = (char**) (lodepng_realloc(info->text_strings, sizeof(char*) * (info->text_num + 1))); if (!new_keys || !new_strings) { lodepng_free(new_keys); lodepng_free(new_strings); return 83; /*alloc fail*/ } info->text_num++; info->text_keys = new_keys; info->text_strings = new_strings; string_init(&info->text_keys[info->text_num - 1]); string_set(&info->text_keys[info->text_num - 1], key); string_init(&info->text_strings[info->text_num - 1]); string_set(&info->text_strings[info->text_num - 1], str); return 0; } /******************************************************************************/ static void LodePNGIText_init(LodePNGInfo* info) { info->itext_num = 0; info->itext_keys = NULL; info->itext_langtags = NULL; info->itext_transkeys = NULL; info->itext_strings = NULL; } static void LodePNGIText_cleanup(LodePNGInfo* info) { size_t i; for (i = 0; i < info->itext_num; i++) { string_cleanup(&info->itext_keys[i]); string_cleanup(&info->itext_langtags[i]); string_cleanup(&info->itext_transkeys[i]); string_cleanup(&info->itext_strings[i]); } lodepng_free(info->itext_keys); lodepng_free(info->itext_langtags); lodepng_free(info->itext_transkeys); lodepng_free(info->itext_strings); } static unsigned LodePNGIText_copy(LodePNGInfo* dest, const LodePNGInfo* source) { size_t i = 0; dest->itext_keys = 0; dest->itext_langtags = 0; dest->itext_transkeys = 0; dest->itext_strings = 0; dest->itext_num = 0; for (i = 0; i < source->itext_num; i++) { CERROR_TRY_RETURN( lodepng_add_itext(dest, source->itext_keys[i], source->itext_langtags[i], source->itext_transkeys[i], source->itext_strings[i])); } return 0; } void lodepng_clear_itext(LodePNGInfo* info) { LodePNGIText_cleanup(info); } unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, const char* transkey, const char* str) { char** new_keys = (char**) (lodepng_realloc(info->itext_keys, sizeof(char*) * (info->itext_num + 1))); char** new_langtags = (char**) (lodepng_realloc(info->itext_langtags, sizeof(char*) * (info->itext_num + 1))); char** new_transkeys = (char**) (lodepng_realloc(info->itext_transkeys, sizeof(char*) * (info->itext_num + 1))); char** new_strings = (char**) (lodepng_realloc(info->itext_strings, sizeof(char*) * (info->itext_num + 1))); if (!new_keys || !new_langtags || !new_transkeys || !new_strings) { lodepng_free(new_keys); lodepng_free(new_langtags); lodepng_free(new_transkeys); lodepng_free(new_strings); return 83; /*alloc fail*/ } info->itext_num++; info->itext_keys = new_keys; info->itext_langtags = new_langtags; info->itext_transkeys = new_transkeys; info->itext_strings = new_strings; string_init(&info->itext_keys[info->itext_num - 1]); string_set(&info->itext_keys[info->itext_num - 1], key); string_init(&info->itext_langtags[info->itext_num - 1]); string_set(&info->itext_langtags[info->itext_num - 1], langtag); string_init(&info->itext_transkeys[info->itext_num - 1]); string_set(&info->itext_transkeys[info->itext_num - 1], transkey); string_init(&info->itext_strings[info->itext_num - 1]); string_set(&info->itext_strings[info->itext_num - 1], str); return 0; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ void lodepng_info_init(LodePNGInfo* info) { lodepng_color_mode_init(&info->color); info->interlace_method = 0; info->compression_method = 0; info->filter_method = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS info->background_defined = 0; info->background_r = info->background_g = info->background_b = 0; LodePNGText_init(info); LodePNGIText_init(info); info->time_defined = 0; info->phys_defined = 0; LodePNGUnknownChunks_init(info); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } void lodepng_info_cleanup(LodePNGInfo* info) { lodepng_color_mode_cleanup(&info->color); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS LodePNGText_cleanup(info); LodePNGIText_cleanup(info); LodePNGUnknownChunks_cleanup(info); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source) { lodepng_info_cleanup(dest); *dest = *source; lodepng_color_mode_init(&dest->color); CERROR_TRY_RETURN(lodepng_color_mode_copy(&dest->color, &source->color)); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS CERROR_TRY_RETURN(LodePNGText_copy(dest, source)); CERROR_TRY_RETURN(LodePNGIText_copy(dest, source)); LodePNGUnknownChunks_init(dest); CERROR_TRY_RETURN(LodePNGUnknownChunks_copy(dest, source)); #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ return 0; } void lodepng_info_swap(LodePNGInfo* a, LodePNGInfo* b) { LodePNGInfo temp = *a; *a = *b; *b = temp; } /* ////////////////////////////////////////////////////////////////////////// */ /*index: bitgroup index, bits: bitgroup size(1, 2 or 4), in: bitgroup value, out: octet array to add bits to*/ static void addColorBits(unsigned char* out, size_t index, unsigned bits, unsigned in) { unsigned m = bits == 1 ? 7 : bits == 2 ? 3 : 1; /*8 / bits - 1*/ /*p = the partial index in the byte, e.g. with 4 palettebits it is 0 for first half or 1 for second half*/ unsigned p = index & m; in &= (1u << bits) - 1u; /*filter out any other bits of the input value*/ in = in << (bits * (m - p)); if (p == 0) out[index * bits / 8] = in; else out[index * bits / 8] |= in; } typedef struct ColorTree ColorTree; /* One node of a color tree This is the data structure used to count the number of unique colors and to get a palette index for a color. It's like an octree, but because the alpha channel is used too, each node has 16 instead of 8 children. */ struct ColorTree { ColorTree* children[16]; /*up to 16 pointers to ColorTree of next level*/ int index; /*the payload. Only has a meaningful value if this is in the last level*/ }; static void color_tree_init(ColorTree* tree) { int i; for (i = 0; i < 16; i++) tree->children[i] = 0; tree->index = -1; } static void color_tree_cleanup(ColorTree* tree) { int i; for (i = 0; i < 16; i++) { if (tree->children[i]) { color_tree_cleanup(tree->children[i]); lodepng_free(tree->children[i]); } } } /*returns -1 if color not present, its index otherwise*/ static int color_tree_get(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { int bit = 0; for (bit = 0; bit < 8; bit++) { int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); if (!tree->children[i]) return -1; else tree = tree->children[i]; } return tree ? tree->index : -1; } #ifdef LODEPNG_COMPILE_ENCODER static int color_tree_has(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { return color_tree_get(tree, r, g, b, a) >= 0; } #endif /*LODEPNG_COMPILE_ENCODER*/ /*color is not allowed to already exist. Index should be >= 0 (it's signed to be compatible with using -1 for "doesn't exist")*/ static void color_tree_add(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a, unsigned index) { int bit; for (bit = 0; bit < 8; bit++) { int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); if (!tree->children[i]) { tree->children[i] = (ColorTree*) lodepng_malloc(sizeof(ColorTree)); color_tree_init(tree->children[i]); } tree = tree->children[i]; } tree->index = (int) index; } /*put a pixel, given its RGBA color, into image of any color type*/ static unsigned rgba8ToPixel(unsigned char* out, size_t i, const LodePNGColorMode* mode, ColorTree* tree /*for palette*/, unsigned char r, unsigned char g, unsigned char b, unsigned char a) { if (mode->colortype == LCT_GREY) { unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/ ; if (mode->bitdepth == 8) out[i] = grey; else if (mode->bitdepth == 16) out[i * 2 + 0] = out[i * 2 + 1] = grey; else { /*take the most significant bits of grey*/ grey = (grey >> (8 - mode->bitdepth)) & ((1 << mode->bitdepth) - 1); addColorBits(out, i, mode->bitdepth, grey); } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { out[i * 3 + 0] = r; out[i * 3 + 1] = g; out[i * 3 + 2] = b; } else { out[i * 6 + 0] = out[i * 6 + 1] = r; out[i * 6 + 2] = out[i * 6 + 3] = g; out[i * 6 + 4] = out[i * 6 + 5] = b; } } else if (mode->colortype == LCT_PALETTE) { int index = color_tree_get(tree, r, g, b, a); if (index < 0) return 82; /*color not in palette*/ if (mode->bitdepth == 8) out[i] = index; else addColorBits(out, i, mode->bitdepth, (unsigned) index); } else if (mode->colortype == LCT_GREY_ALPHA) { unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/ ; if (mode->bitdepth == 8) { out[i * 2 + 0] = grey; out[i * 2 + 1] = a; } else if (mode->bitdepth == 16) { out[i * 4 + 0] = out[i * 4 + 1] = grey; out[i * 4 + 2] = out[i * 4 + 3] = a; } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { out[i * 4 + 0] = r; out[i * 4 + 1] = g; out[i * 4 + 2] = b; out[i * 4 + 3] = a; } else { out[i * 8 + 0] = out[i * 8 + 1] = r; out[i * 8 + 2] = out[i * 8 + 3] = g; out[i * 8 + 4] = out[i * 8 + 5] = b; out[i * 8 + 6] = out[i * 8 + 7] = a; } } return 0; /*no error*/ } /*put a pixel, given its RGBA16 color, into image of any color 16-bitdepth type*/ static unsigned rgba16ToPixel(unsigned char* out, size_t i, const LodePNGColorMode* mode, unsigned short r, unsigned short g, unsigned short b, unsigned short a) { if (mode->bitdepth != 16) return 85; /*must be 16 for this function*/ if (mode->colortype == LCT_GREY) { unsigned short grey = r; /*((unsigned)r + g + b) / 3*/ ; out[i * 2 + 0] = (grey >> 8) & 255; out[i * 2 + 1] = grey & 255; } else if (mode->colortype == LCT_RGB) { out[i * 6 + 0] = (r >> 8) & 255; out[i * 6 + 1] = r & 255; out[i * 6 + 2] = (g >> 8) & 255; out[i * 6 + 3] = g & 255; out[i * 6 + 4] = (b >> 8) & 255; out[i * 6 + 5] = b & 255; } else if (mode->colortype == LCT_GREY_ALPHA) { unsigned short grey = r; /*((unsigned)r + g + b) / 3*/ ; out[i * 4 + 0] = (grey >> 8) & 255; out[i * 4 + 1] = grey & 255; out[i * 4 + 2] = (a >> 8) & 255; out[i * 4 + 3] = a & 255; } else if (mode->colortype == LCT_RGBA) { out[i * 8 + 0] = (r >> 8) & 255; out[i * 8 + 1] = r & 255; out[i * 8 + 2] = (g >> 8) & 255; out[i * 8 + 3] = g & 255; out[i * 8 + 4] = (b >> 8) & 255; out[i * 8 + 5] = b & 255; out[i * 8 + 6] = (a >> 8) & 255; out[i * 8 + 7] = a & 255; } return 0; /*no error*/ } /*Get RGBA8 color of pixel with index i (y * width + x) from the raw image with given color type.*/ static unsigned getPixelColorRGBA8(unsigned char* r, unsigned char* g, unsigned char* b, unsigned char* a, const unsigned char* in, size_t i, const LodePNGColorMode* mode, unsigned fix_png) { if (mode->colortype == LCT_GREY) { if (mode->bitdepth == 8) { *r = *g = *b = in[i]; if (mode->key_defined && *r == mode->key_r) *a = 0; else *a = 255; } else if (mode->bitdepth == 16) { *r = *g = *b = in[i * 2 + 0]; if (mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; else *a = 255; } else { unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ size_t j = i * mode->bitdepth; unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); *r = *g = *b = (value * 255) / highest; if (mode->key_defined && value == mode->key_r) *a = 0; else *a = 255; } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { *r = in[i * 3 + 0]; *g = in[i * 3 + 1]; *b = in[i * 3 + 2]; if (mode->key_defined && *r == mode->key_r && *g == mode->key_g && *b == mode->key_b) *a = 0; else *a = 255; } else { *r = in[i * 6 + 0]; *g = in[i * 6 + 2]; *b = in[i * 6 + 4]; if (mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; else *a = 255; } } else if (mode->colortype == LCT_PALETTE) { unsigned index; if (mode->bitdepth == 8) index = in[i]; else { size_t j = i * mode->bitdepth; index = readBitsFromReversedStream(&j, in, mode->bitdepth); } if (index >= mode->palettesize) { /*This is an error according to the PNG spec, but fix_png can ignore it*/ if (!fix_png) return (mode->bitdepth == 8 ? 46 : 47); /*index out of palette*/ *r = *g = *b = 0; *a = 255; } else { *r = mode->palette[index * 4 + 0]; *g = mode->palette[index * 4 + 1]; *b = mode->palette[index * 4 + 2]; *a = mode->palette[index * 4 + 3]; } } else if (mode->colortype == LCT_GREY_ALPHA) { if (mode->bitdepth == 8) { *r = *g = *b = in[i * 2 + 0]; *a = in[i * 2 + 1]; } else { *r = *g = *b = in[i * 4 + 0]; *a = in[i * 4 + 2]; } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { *r = in[i * 4 + 0]; *g = in[i * 4 + 1]; *b = in[i * 4 + 2]; *a = in[i * 4 + 3]; } else { *r = in[i * 8 + 0]; *g = in[i * 8 + 2]; *b = in[i * 8 + 4]; *a = in[i * 8 + 6]; } } return 0; /*no error*/ } /*Similar to getPixelColorRGBA8, but with all the for loops inside of the color mode test cases, optimized to convert the colors much faster, when converting to RGBA or RGB with 8 bit per cannel. buffer must be RGBA or RGB output with enough memory, if has_alpha is true the output is RGBA. mode has the color mode of the input buffer.*/ static unsigned getPixelColorsRGBA8(unsigned char* buffer, size_t numpixels, unsigned has_alpha, const unsigned char* in, const LodePNGColorMode* mode, unsigned fix_png) { unsigned num_channels = has_alpha ? 4 : 3; size_t i; if (mode->colortype == LCT_GREY) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i]; if (has_alpha) buffer[3] = mode->key_defined && in[i] == mode->key_r ? 0 : 255; } } else if (mode->bitdepth == 16) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 2]; if (has_alpha) buffer[3] = mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r ? 0 : 255; } } else { unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ size_t j = 0; for (i = 0; i < numpixels; i++, buffer += num_channels) { unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); buffer[0] = buffer[1] = buffer[2] = (value * 255) / highest; if (has_alpha) buffer[3] = mode->key_defined && value == mode->key_r ? 0 : 255; } } } else if (mode->colortype == LCT_RGB) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 3 + 0]; buffer[1] = in[i * 3 + 1]; buffer[2] = in[i * 3 + 2]; if (has_alpha) buffer[3] = mode->key_defined && buffer[0] == mode->key_r && buffer[1] == mode->key_g && buffer[2] == mode->key_b ? 0 : 255; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 6 + 0]; buffer[1] = in[i * 6 + 2]; buffer[2] = in[i * 6 + 4]; if (has_alpha) buffer[3] = mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b ? 0 : 255; } } } else if (mode->colortype == LCT_PALETTE) { unsigned index; size_t j = 0; for (i = 0; i < numpixels; i++, buffer += num_channels) { if (mode->bitdepth == 8) index = in[i]; else index = readBitsFromReversedStream(&j, in, mode->bitdepth); if (index >= mode->palettesize) { /*This is an error according to the PNG spec, but fix_png can ignore it*/ if (!fix_png) return (mode->bitdepth == 8 ? 46 : 47); /*index out of palette*/ buffer[0] = buffer[1] = buffer[2] = 0; if (has_alpha) buffer[3] = 255; } else { buffer[0] = mode->palette[index * 4 + 0]; buffer[1] = mode->palette[index * 4 + 1]; buffer[2] = mode->palette[index * 4 + 2]; if (has_alpha) buffer[3] = mode->palette[index * 4 + 3]; } } } else if (mode->colortype == LCT_GREY_ALPHA) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 2 + 0]; if (has_alpha) buffer[3] = in[i * 2 + 1]; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = buffer[1] = buffer[2] = in[i * 4 + 0]; if (has_alpha) buffer[3] = in[i * 4 + 2]; } } } else if (mode->colortype == LCT_RGBA) { if (mode->bitdepth == 8) { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 4 + 0]; buffer[1] = in[i * 4 + 1]; buffer[2] = in[i * 4 + 2]; if (has_alpha) buffer[3] = in[i * 4 + 3]; } } else { for (i = 0; i < numpixels; i++, buffer += num_channels) { buffer[0] = in[i * 8 + 0]; buffer[1] = in[i * 8 + 2]; buffer[2] = in[i * 8 + 4]; if (has_alpha) buffer[3] = in[i * 8 + 6]; } } } return 0; /*no error*/ } /*Get RGBA16 color of pixel with index i (y * width + x) from the raw image with given color type, but the given color type must be 16-bit itself.*/ static unsigned getPixelColorRGBA16(unsigned short* r, unsigned short* g, unsigned short* b, unsigned short* a, const unsigned char* in, size_t i, const LodePNGColorMode* mode) { if (mode->bitdepth != 16) return 85; /*error: this function only supports 16-bit input*/ if (mode->colortype == LCT_GREY) { *r = *g = *b = 256 * in[i * 2 + 0] + in[i * 2 + 1]; if (mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; else *a = 65535; } else if (mode->colortype == LCT_RGB) { *r = 256 * in[i * 6 + 0] + in[i * 6 + 1]; *g = 256 * in[i * 6 + 2] + in[i * 6 + 3]; *b = 256 * in[i * 6 + 4] + in[i * 6 + 5]; if (mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; else *a = 65535; } else if (mode->colortype == LCT_GREY_ALPHA) { *r = *g = *b = 256 * in[i * 4 + 0] + in[i * 4 + 1]; *a = 256 * in[i * 4 + 2] + in[i * 4 + 3]; } else if (mode->colortype == LCT_RGBA) { *r = 256 * in[i * 8 + 0] + in[i * 8 + 1]; *g = 256 * in[i * 8 + 2] + in[i * 8 + 3]; *b = 256 * in[i * 8 + 4] + in[i * 8 + 5]; *a = 256 * in[i * 8 + 6] + in[i * 8 + 7]; } else return 85; /*error: this function only supports 16-bit input, not palettes*/ return 0; /*no error*/ } /* converts from any color type to 24-bit or 32-bit (later maybe more supported). return value = LodePNG error code the out buffer must have (w * h * bpp + 7) / 8 bytes, where bpp is the bits per pixel of the output color type (lodepng_get_bpp) for < 8 bpp images, there may _not_ be padding bits at the end of scanlines. */ unsigned lodepng_convert(unsigned char* out, const unsigned char* in, LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, unsigned w, unsigned h, unsigned fix_png) { unsigned error = 0; size_t i; ColorTree tree; size_t numpixels = w * h; if (lodepng_color_mode_equal(mode_out, mode_in)) { size_t numbytes = lodepng_get_raw_size(w, h, mode_in); for (i = 0; i < numbytes; i++) out[i] = in[i]; return error; } if (mode_out->colortype == LCT_PALETTE) { size_t palsize = 1u << mode_out->bitdepth; if (mode_out->palettesize < palsize) palsize = mode_out->palettesize; color_tree_init(&tree); for (i = 0; i < palsize; i++) { unsigned char* p = &mode_out->palette[i * 4]; color_tree_add(&tree, p[0], p[1], p[2], p[3], i); } } if (mode_in->bitdepth == 16 && mode_out->bitdepth == 16) { for (i = 0; i < numpixels; i++) { unsigned short r = 0, g = 0, b = 0, a = 0; error = getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode_in); if (error) break; error = rgba16ToPixel(out, i, mode_out, r, g, b, a); if (error) break; } } else if (mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGBA) { error = getPixelColorsRGBA8(out, numpixels, 1, in, mode_in, fix_png); } else if (mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGB) { error = getPixelColorsRGBA8(out, numpixels, 0, in, mode_in, fix_png); } else { unsigned char r = 0, g = 0, b = 0, a = 0; for (i = 0; i < numpixels; i++) { error = getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode_in, fix_png); if (error) break; error = rgba8ToPixel(out, i, mode_out, &tree, r, g, b, a); if (error) break; } } if (mode_out->colortype == LCT_PALETTE) { color_tree_cleanup(&tree); } return error; } #ifdef LODEPNG_COMPILE_ENCODER typedef struct ColorProfile { unsigned char sixteenbit; /*needs more than 8 bits per channel*/ unsigned char sixteenbit_done; unsigned char colored; /*not greyscale*/ unsigned char colored_done; unsigned char key; /*a color key is required, or more*/ unsigned short key_r; /*these values are always in 16-bit bitdepth in the profile*/ unsigned short key_g; unsigned short key_b; unsigned char alpha; /*alpha channel, or alpha palette, required*/ unsigned char alpha_done; unsigned numcolors; ColorTree tree; /*for listing the counted colors, up to 256*/ unsigned char* palette; /*size 1024. Remember up to the first 256 RGBA colors*/ unsigned maxnumcolors; /*if more than that amount counted*/ unsigned char numcolors_done; unsigned greybits; /*amount of bits required for greyscale (1, 2, 4, 8). Does not take 16 bit into account.*/ unsigned char greybits_done; } ColorProfile; static void color_profile_init(ColorProfile* profile, const LodePNGColorMode* mode) { profile->sixteenbit = 0; profile->sixteenbit_done = mode->bitdepth == 16 ? 0 : 1; profile->colored = 0; profile->colored_done = lodepng_is_greyscale_type(mode) ? 1 : 0; profile->key = 0; profile->alpha = 0; profile->alpha_done = lodepng_can_have_alpha(mode) ? 0 : 1; profile->numcolors = 0; color_tree_init(&profile->tree); profile->palette = (unsigned char*) lodepng_malloc(1024); profile->maxnumcolors = 257; if (lodepng_get_bpp(mode) <= 8) { unsigned bpp = lodepng_get_bpp(mode); profile->maxnumcolors = bpp == 1 ? 2 : (bpp == 2 ? 4 : (bpp == 4 ? 16 : 256)); } profile->numcolors_done = 0; profile->greybits = 1; profile->greybits_done = lodepng_get_bpp(mode) == 1 ? 1 : 0; } static void color_profile_cleanup(ColorProfile* profile) { color_tree_cleanup(&profile->tree); lodepng_free(profile->palette); } /*function used for debug purposes with C++*/ /*void printColorProfile(ColorProfile* p) { std::cout << "sixteenbit: " << (int)p->sixteenbit << std::endl; std::cout << "sixteenbit_done: " << (int)p->sixteenbit_done << std::endl; std::cout << "colored: " << (int)p->colored << std::endl; std::cout << "colored_done: " << (int)p->colored_done << std::endl; std::cout << "key: " << (int)p->key << std::endl; std::cout << "key_r: " << (int)p->key_r << std::endl; std::cout << "key_g: " << (int)p->key_g << std::endl; std::cout << "key_b: " << (int)p->key_b << std::endl; std::cout << "alpha: " << (int)p->alpha << std::endl; std::cout << "alpha_done: " << (int)p->alpha_done << std::endl; std::cout << "numcolors: " << (int)p->numcolors << std::endl; std::cout << "maxnumcolors: " << (int)p->maxnumcolors << std::endl; std::cout << "numcolors_done: " << (int)p->numcolors_done << std::endl; std::cout << "greybits: " << (int)p->greybits << std::endl; std::cout << "greybits_done: " << (int)p->greybits_done << std::endl; }*/ /*Returns how many bits needed to represent given value (max 8 bit)*/ unsigned getValueRequiredBits(unsigned short value) { if (value == 0 || value == 255) return 1; /*The scaling of 2-bit and 4-bit values uses multiples of 85 and 17*/ if (value % 17 == 0) return value % 85 == 0 ? 2 : 4; return 8; } /*profile must already have been inited with mode. It's ok to set some parameters of profile to done already.*/ static unsigned get_color_profile(ColorProfile* profile, const unsigned char* in, size_t numpixels /*must be full image size, for certain filesize based choices*/, const LodePNGColorMode* mode, unsigned fix_png) { unsigned error = 0; size_t i; if (mode->bitdepth == 16) { for (i = 0; i < numpixels; i++) { unsigned short r, g, b, a; error = getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode); if (error) break; /*a color is considered good for 8-bit if the first byte and the second byte are equal, (so if it's divisible through 257), NOT necessarily if the second byte is 0*/ if (!profile->sixteenbit_done && (((r & 255) != ((r >> 8) & 255)) || ((g & 255) != ((g >> 8) & 255)) || ((b & 255) != ((b >> 8) & 255)))) { profile->sixteenbit = 1; profile->sixteenbit_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore at 16-bit*/ profile->numcolors_done = 1; /*counting colors no longer useful, palette doesn't support 16-bit*/ } if (!profile->colored_done && (r != g || r != b)) { profile->colored = 1; profile->colored_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->alpha_done && a != 65535) { /*only use color key if numpixels large enough to justify tRNS chunk size*/ if (a == 0 && numpixels > 16 && !(profile->key && (r != profile->key_r || g != profile->key_g || b != profile->key_b))) { if (!profile->alpha && !profile->key) { profile->key = 1; profile->key_r = r; profile->key_g = g; profile->key_b = b; } } else { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } } /* Color key cannot be used if an opaque pixel also has that RGB color. */ if (!profile->alpha_done && a == 65535 && profile->key && r == profile->key_r && g == profile->key_g && b == profile->key_b) { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->greybits_done) { /*assuming 8-bit r, this test does not care about 16-bit*/ unsigned bits = getValueRequiredBits(r); if (bits > profile->greybits) profile->greybits = bits; if (profile->greybits >= 8) profile->greybits_done = 1; } if (!profile->numcolors_done) { /*assuming 8-bit rgba, this test does not care about 16-bit*/ if (!color_tree_has(&profile->tree, (unsigned char) r, (unsigned char) g, (unsigned char) b, (unsigned char) a)) { color_tree_add(&profile->tree, (unsigned char) r, (unsigned char) g, (unsigned char) b, (unsigned char) a, profile->numcolors); if (profile->numcolors < 256) { unsigned char* p = profile->palette; unsigned i = profile->numcolors; p[i * 4 + 0] = (unsigned char) r; p[i * 4 + 1] = (unsigned char) g; p[i * 4 + 2] = (unsigned char) b; p[i * 4 + 3] = (unsigned char) a; } profile->numcolors++; if (profile->numcolors >= profile->maxnumcolors) profile->numcolors_done = 1; } } if (profile->alpha_done && profile->numcolors_done && profile->colored_done && profile->sixteenbit_done && profile->greybits_done) { break; } }; } else /* < 16-bit */ { for (i = 0; i < numpixels; i++) { unsigned char r = 0, g = 0, b = 0, a = 0; error = getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode, fix_png); if (error) break; if (!profile->colored_done && (r != g || r != b)) { profile->colored = 1; profile->colored_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->alpha_done && a != 255) { if (a == 0 && !(profile->key && (r != profile->key_r || g != profile->key_g || b != profile->key_b))) { if (!profile->key) { profile->key = 1; profile->key_r = r; profile->key_g = g; profile->key_b = b; } } else { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } } /* Color key cannot be used if an opaque pixel also has that RGB color. */ if (!profile->alpha_done && a == 255 && profile->key && r == profile->key_r && g == profile->key_g && b == profile->key_b) { profile->alpha = 1; profile->alpha_done = 1; profile->greybits_done = 1; /*greybits is not applicable anymore*/ } if (!profile->greybits_done) { unsigned bits = getValueRequiredBits(r); if (bits > profile->greybits) profile->greybits = bits; if (profile->greybits >= 8) profile->greybits_done = 1; } if (!profile->numcolors_done) { if (!color_tree_has(&profile->tree, r, g, b, a)) { color_tree_add(&profile->tree, r, g, b, a, profile->numcolors); if (profile->numcolors < 256) { unsigned char* p = profile->palette; unsigned i = profile->numcolors; p[i * 4 + 0] = r; p[i * 4 + 1] = g; p[i * 4 + 2] = b; p[i * 4 + 3] = a; } profile->numcolors++; if (profile->numcolors >= profile->maxnumcolors) profile->numcolors_done = 1; } } if (profile->alpha_done && profile->numcolors_done && profile->colored_done && profile->greybits_done) { break; } }; } /*make the profile's key always 16-bit for consistency*/ if (mode->bitdepth < 16) { /*repeat each byte twice*/ profile->key_r *= 257; profile->key_g *= 257; profile->key_b *= 257; } return error; } static void setColorKeyFrom16bit(LodePNGColorMode* mode_out, unsigned r, unsigned g, unsigned b, unsigned bitdepth) { unsigned mask = (1u << bitdepth) - 1u; mode_out->key_defined = 1; mode_out->key_r = r & mask; mode_out->key_g = g & mask; mode_out->key_b = b & mask; } /*updates values of mode with a potentially smaller color model. mode_out should contain the user chosen color model, but will be overwritten with the new chosen one.*/ unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, const unsigned char* image, unsigned w, unsigned h, const LodePNGColorMode* mode_in, LodePNGAutoConvert auto_convert) { ColorProfile profile; unsigned error = 0; int no_nibbles = auto_convert == LAC_AUTO_NO_NIBBLES || auto_convert == LAC_AUTO_NO_NIBBLES_NO_PALETTE; int no_palette = auto_convert == LAC_AUTO_NO_PALETTE || auto_convert == LAC_AUTO_NO_NIBBLES_NO_PALETTE; if (auto_convert == LAC_ALPHA) { if (mode_out->colortype != LCT_RGBA && mode_out->colortype != LCT_GREY_ALPHA) return 0; } color_profile_init(&profile, mode_in); if (auto_convert == LAC_ALPHA) { profile.colored_done = 1; profile.greybits_done = 1; profile.numcolors_done = 1; profile.sixteenbit_done = 1; } error = get_color_profile(&profile, image, w * h, mode_in, 0 /*fix_png*/); if (!error && auto_convert == LAC_ALPHA) { if (!profile.alpha) { mode_out->colortype = ( mode_out->colortype == LCT_RGBA ? LCT_RGB : LCT_GREY); if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } else if (!error && auto_convert != LAC_ALPHA) { mode_out->key_defined = 0; if (profile.sixteenbit) { mode_out->bitdepth = 16; if (profile.alpha) { mode_out->colortype = profile.colored ? LCT_RGBA : LCT_GREY_ALPHA; } else { mode_out->colortype = profile.colored ? LCT_RGB : LCT_GREY; if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } else /*less than 16 bits per channel*/ { /*don't add palette overhead if image hasn't got a lot of pixels*/ unsigned n = profile.numcolors; int palette_ok = !no_palette && n <= 256 && (n * 2 < w * h); unsigned palettebits = n <= 2 ? 1 : (n <= 4 ? 2 : (n <= 16 ? 4 : 8)); int grey_ok = !profile.colored && !profile.alpha; /*grey without alpha, with potentially low bits*/ if (palette_ok || grey_ok) { if (!palette_ok || (grey_ok && profile.greybits <= palettebits)) { unsigned grey = profile.key_r; mode_out->colortype = LCT_GREY; mode_out->bitdepth = profile.greybits; if (profile.key) setColorKeyFrom16bit(mode_out, grey, grey, grey, mode_out->bitdepth); } else { /*fill in the palette*/ unsigned i; unsigned char* p = profile.palette; /*remove potential earlier palette*/ lodepng_palette_clear(mode_out); for (i = 0; i < profile.numcolors; i++) { error = lodepng_palette_add(mode_out, p[i * 4 + 0], p[i * 4 + 1], p[i * 4 + 2], p[i * 4 + 3]); if (error) break; } mode_out->colortype = LCT_PALETTE; mode_out->bitdepth = palettebits; } } else /*8-bit per channel*/ { mode_out->bitdepth = 8; if (profile.alpha) { mode_out->colortype = profile.colored ? LCT_RGBA : LCT_GREY_ALPHA; } else { mode_out->colortype = profile.colored ? LCT_RGB : LCT_GREY /*LCT_GREY normally won't occur, already done earlier*/; if (profile.key) setColorKeyFrom16bit(mode_out, profile.key_r, profile.key_g, profile.key_b, mode_out->bitdepth); } } } } color_profile_cleanup(&profile); if (mode_out->colortype == LCT_PALETTE && mode_in->palettesize == mode_out->palettesize) { /*In this case keep the palette order of the input, so that the user can choose an optimal one*/ size_t i; for (i = 0; i < mode_in->palettesize * 4; i++) { mode_out->palette[i] = mode_in->palette[i]; } } if (no_nibbles && mode_out->bitdepth < 8) { /*palette can keep its small amount of colors, as long as no indices use it*/ mode_out->bitdepth = 8; } return error; } #endif /* #ifdef LODEPNG_COMPILE_ENCODER */ /* Paeth predicter, used by PNG filter type 4 The parameters are of type short, but should come from unsigned chars, the shorts are only needed to make the paeth calculation correct. */ static unsigned char paethPredictor(short a, short b, short c) { short pa = abs(b - c); short pb = abs(a - c); short pc = abs(a + b - c - c); if (pc < pa && pc < pb) return (unsigned char) c; else if (pb < pa) return (unsigned char) b; else return (unsigned char) a; } /*shared values used by multiple Adam7 related functions*/ static const unsigned ADAM7_IX[7] = { 0, 4, 0, 2, 0, 1, 0 }; /*x start values*/ static const unsigned ADAM7_IY[7] = { 0, 0, 4, 0, 2, 0, 1 }; /*y start values*/ static const unsigned ADAM7_DX[7] = { 8, 8, 4, 4, 2, 2, 1 }; /*x delta values*/ static const unsigned ADAM7_DY[7] = { 8, 8, 8, 4, 4, 2, 2 }; /*y delta values*/ /* Outputs various dimensions and positions in the image related to the Adam7 reduced images. passw: output containing the width of the 7 passes passh: output containing the height of the 7 passes filter_passstart: output containing the index of the start and end of each reduced image with filter bytes padded_passstart output containing the index of the start and end of each reduced image when without filter bytes but with padded scanlines passstart: output containing the index of the start and end of each reduced image without padding between scanlines, but still padding between the images w, h: width and height of non-interlaced image bpp: bits per pixel "padded" is only relevant if bpp is less than 8 and a scanline or image does not end at a full byte */ static void Adam7_getpassvalues(unsigned passw[7], unsigned passh[7], size_t filter_passstart[8], size_t padded_passstart[8], size_t passstart[8], unsigned w, unsigned h, unsigned bpp) { /*the passstart values have 8 values: the 8th one indicates the byte after the end of the 7th (= last) pass*/ unsigned i; /*calculate width and height in pixels of each pass*/ for (i = 0; i < 7; i++) { passw[i] = (w + ADAM7_DX[i] - ADAM7_IX[i] - 1) / ADAM7_DX[i]; passh[i] = (h + ADAM7_DY[i] - ADAM7_IY[i] - 1) / ADAM7_DY[i]; if (passw[i] == 0) passh[i] = 0; if (passh[i] == 0) passw[i] = 0; } filter_passstart[0] = padded_passstart[0] = passstart[0] = 0; for (i = 0; i < 7; i++) { /*if passw[i] is 0, it's 0 bytes, not 1 (no filtertype-byte)*/ filter_passstart[i + 1] = filter_passstart[i] + ((passw[i] && passh[i]) ? passh[i] * (1 + (passw[i] * bpp + 7) / 8) : 0); /*bits padded if needed to fill full byte at end of each scanline*/ padded_passstart[i + 1] = padded_passstart[i] + passh[i] * ((passw[i] * bpp + 7) / 8); /*only padded at end of reduced image*/ passstart[i + 1] = passstart[i] + (passh[i] * passw[i] * bpp + 7) / 8; } } #ifdef LODEPNG_COMPILE_DECODER /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG Decoder / */ /* ////////////////////////////////////////////////////////////////////////// */ /*read the information from the header and store it in the LodePNGInfo. return value is error*/ unsigned lodepng_inspect(unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { LodePNGInfo* info = &state->info_png; if (insize == 0 || in == 0) { CERROR_RETURN_ERROR(state->error, 48); /*error: the given data is empty*/ } if (insize < 29) { CERROR_RETURN_ERROR(state->error, 27); /*error: the data length is smaller than the length of a PNG header*/ } /*when decoding a new PNG image, make sure all parameters created after previous decoding are reset*/ lodepng_info_cleanup(info); lodepng_info_init(info); if (in[0] != 137 || in[1] != 80 || in[2] != 78 || in[3] != 71 || in[4] != 13 || in[5] != 10 || in[6] != 26 || in[7] != 10) { CERROR_RETURN_ERROR(state->error, 28); /*error: the first 8 bytes are not the correct PNG signature*/ } if (in[12] != 'I' || in[13] != 'H' || in[14] != 'D' || in[15] != 'R') { CERROR_RETURN_ERROR(state->error, 29); /*error: it doesn't start with a IHDR chunk!*/ } /*read the values given in the header*/ *w = lodepng_read32bitInt(&in[16]); *h = lodepng_read32bitInt(&in[20]); info->color.bitdepth = in[24]; info->color.colortype = (LodePNGColorType) in[25]; info->compression_method = in[26]; info->filter_method = in[27]; info->interlace_method = in[28]; if (!state->decoder.ignore_crc) { unsigned CRC = lodepng_read32bitInt(&in[29]); unsigned checksum = lodepng_crc32(&in[12], 17); if (CRC != checksum) { CERROR_RETURN_ERROR(state->error, 57); /*invalid CRC*/ } } /*error: only compression method 0 is allowed in the specification*/ if (info->compression_method != 0) CERROR_RETURN_ERROR(state->error, 32); /*error: only filter method 0 is allowed in the specification*/ if (info->filter_method != 0) CERROR_RETURN_ERROR(state->error, 33); /*error: only interlace methods 0 and 1 exist in the specification*/ if (info->interlace_method > 1) CERROR_RETURN_ERROR(state->error, 34); state->error = checkColorValidity(info->color.colortype, info->color.bitdepth); return state->error; } static unsigned unfilterScanline(unsigned char* recon, const unsigned char* scanline, const unsigned char* precon, size_t bytewidth, unsigned char filterType, size_t length) { /* For PNG filter method 0 unfilter a PNG image scanline by scanline. when the pixels are smaller than 1 byte, the filter works byte per byte (bytewidth = 1) precon is the previous unfiltered scanline, recon the result, scanline the current one the incoming scanlines do NOT include the filtertype byte, that one is given in the parameter filterType instead recon and scanline MAY be the same memory address! precon must be disjoint. */ size_t i; switch (filterType) { case 0: for (i = 0; i < length; i++) recon[i] = scanline[i]; break; case 1: for (i = 0; i < bytewidth; i++) recon[i] = scanline[i]; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth]; break; case 2: if (precon) { for (i = 0; i < length; i++) recon[i] = scanline[i] + precon[i]; } else { for (i = 0; i < length; i++) recon[i] = scanline[i]; } break; case 3: if (precon) { for (i = 0; i < bytewidth; i++) recon[i] = scanline[i] + precon[i] / 2; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + ((recon[i - bytewidth] + precon[i]) / 2); } else { for (i = 0; i < bytewidth; i++) recon[i] = scanline[i]; for (i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth] / 2; } break; case 4: if (precon) { for (i = 0; i < bytewidth; i++) { recon[i] = (scanline[i] + precon[i]); /*paethPredictor(0, precon[i], 0) is always precon[i]*/ } for (i = bytewidth; i < length; i++) { recon[i] = (scanline[i] + paethPredictor(recon[i - bytewidth], precon[i], precon[i - bytewidth])); } } else { for (i = 0; i < bytewidth; i++) { recon[i] = scanline[i]; } for (i = bytewidth; i < length; i++) { /*paethPredictor(recon[i - bytewidth], 0, 0) is always recon[i - bytewidth]*/ recon[i] = (scanline[i] + recon[i - bytewidth]); } } break; default: return 36; /*error: unexisting filter type given*/ } return 0; } static unsigned unfilter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { /* For PNG filter method 0 this function unfilters a single image (e.g. without interlacing this is called once, with Adam7 seven times) out must have enough bytes allocated already, in must have the scanlines + 1 filtertype byte per scanline w and h are image dimensions or dimensions of reduced image, bpp is bits per pixel in and out are allowed to be the same memory address (but aren't the same size since in has the extra filter bytes) */ unsigned y; unsigned char* prevline = 0; /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ size_t bytewidth = (bpp + 7) / 8; size_t linebytes = (w * bpp + 7) / 8; for (y = 0; y < h; y++) { size_t outindex = linebytes * y; size_t inindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ unsigned char filterType = in[inindex]; CERROR_TRY_RETURN( unfilterScanline(&out[outindex], &in[inindex + 1], prevline, bytewidth, filterType, linebytes)); prevline = &out[outindex]; } return 0; } /* in: Adam7 interlaced image, with no padding bits between scanlines, but between reduced images so that each reduced image starts at a byte. out: the same pixels, but re-ordered so that they're now a non-interlaced image with size w*h bpp: bits per pixel out has the following size in bits: w * h * bpp. in is possibly bigger due to padding bits between reduced images. out must be big enough AND must be 0 everywhere if bpp < 8 in the current implementation (because that's likely a little bit faster) NOTE: comments about padding bits are only relevant if bpp < 8 */ static void Adam7_deinterlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); if (bpp >= 8) { for (i = 0; i < 7; i++) { unsigned x, y, b; size_t bytewidth = bpp / 8; for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { size_t pixelinstart = passstart[i] + (y * passw[i] + x) * bytewidth; size_t pixeloutstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; for (b = 0; b < bytewidth; b++) { out[pixeloutstart + b] = in[pixelinstart + b]; } } } } else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ { for (i = 0; i < 7; i++) { unsigned x, y, b; unsigned ilinebits = bpp * passw[i]; unsigned olinebits = bpp * w; size_t obp, ibp; /*bit pointers (for out and in buffer)*/ for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { ibp = (8 * passstart[i]) + (y * ilinebits + x * bpp); obp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; for (b = 0; b < bpp; b++) { unsigned char bit = readBitFromReversedStream(&ibp, in); /*note that this function assumes the out buffer is completely 0, use setBitOfReversedStream otherwise*/ setBitOfReversedStream0(&obp, out, bit); } } } } } static void removePaddingBits(unsigned char* out, const unsigned char* in, size_t olinebits, size_t ilinebits, unsigned h) { /* After filtering there are still padding bits if scanlines have non multiple of 8 bit amounts. They need to be removed (except at last scanline of (Adam7-reduced) image) before working with pure image buffers for the Adam7 code, the color convert code and the output to the user. in and out are allowed to be the same buffer, in may also be higher but still overlapping; in must have >= ilinebits*h bits, out must have >= olinebits*h bits, olinebits must be <= ilinebits also used to move bits after earlier such operations happened, e.g. in a sequence of reduced images from Adam7 only useful if (ilinebits - olinebits) is a value in the range 1..7 */ unsigned y; size_t diff = ilinebits - olinebits; size_t ibp = 0, obp = 0; /*input and output bit pointers*/ for (y = 0; y < h; y++) { size_t x; for (x = 0; x < olinebits; x++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } ibp += diff; } } /*out must be buffer big enough to contain full image, and in must contain the full decompressed data from the IDAT chunks (with filter index bytes and possible padding bits) return value is error*/ static unsigned postProcessScanlines(unsigned char* out, unsigned char* in, unsigned w, unsigned h, const LodePNGInfo* info_png) { /* This function converts the filtered-padded-interlaced data into pure 2D image buffer with the PNG's colortype. Steps: *) if no Adam7: 1) unfilter 2) remove padding bits (= posible extra bits per scanline if bpp < 8) *) if adam7: 1) 7x unfilter 2) 7x remove padding bits 3) Adam7_deinterlace NOTE: the in buffer will be overwritten with intermediate data! */ unsigned bpp = lodepng_get_bpp(&info_png->color); if (bpp == 0) return 31; /*error: invalid colortype*/ if (info_png->interlace_method == 0) { if (bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) { CERROR_TRY_RETURN(unfilter(in, in, w, h, bpp)); removePaddingBits(out, in, w * bpp, ((w * bpp + 7) / 8) * 8, h); } /*we can immediatly filter into the out buffer, no other steps needed*/ else CERROR_TRY_RETURN(unfilter(out, in, w, h, bpp)); } else /*interlace_method is 1 (Adam7)*/ { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); for (i = 0; i < 7; i++) { CERROR_TRY_RETURN( unfilter(&in[padded_passstart[i]], &in[filter_passstart[i]], passw[i], passh[i], bpp)); /*TODO: possible efficiency improvement: if in this reduced image the bits fit nicely in 1 scanline, move bytes instead of bits or move not at all*/ if (bpp < 8) { /*remove padding bits in scanlines; after this there still may be padding bits between the different reduced images: each reduced image still starts nicely at a byte*/ removePaddingBits(&in[passstart[i]], &in[padded_passstart[i]], passw[i] * bpp, ((passw[i] * bpp + 7) / 8) * 8, passh[i]); } } Adam7_deinterlace(out, in, w, h, bpp); } return 0; } static unsigned readChunk_PLTE(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) { unsigned pos = 0, i; if (color->palette) lodepng_free(color->palette); color->palettesize = chunkLength / 3; color->palette = (unsigned char*) lodepng_malloc(4 * color->palettesize); if (!color->palette && color->palettesize) { color->palettesize = 0; return 83; /*alloc fail*/ } if (color->palettesize > 256) return 38; /*error: palette too big*/ for (i = 0; i < color->palettesize; i++) { color->palette[4 * i + 0] = data[pos++]; /*R*/ color->palette[4 * i + 1] = data[pos++]; /*G*/ color->palette[4 * i + 2] = data[pos++]; /*B*/ color->palette[4 * i + 3] = 255; /*alpha*/ } return 0; /* OK */ } static unsigned readChunk_tRNS(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) { unsigned i; if (color->colortype == LCT_PALETTE) { /*error: more alpha values given than there are palette entries*/ if (chunkLength > color->palettesize) return 38; for (i = 0; i < chunkLength; i++) color->palette[4 * i + 3] = data[i]; } else if (color->colortype == LCT_GREY) { /*error: this chunk must be 2 bytes for greyscale image*/ if (chunkLength != 2) return 30; color->key_defined = 1; color->key_r = color->key_g = color->key_b = 256u * data[0] + data[1]; } else if (color->colortype == LCT_RGB) { /*error: this chunk must be 6 bytes for RGB image*/ if (chunkLength != 6) return 41; color->key_defined = 1; color->key_r = 256u * data[0] + data[1]; color->key_g = 256u * data[2] + data[3]; color->key_b = 256u * data[4] + data[5]; } else return 42; /*error: tRNS chunk not allowed for other color models*/ return 0; /* OK */ } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*background color chunk (bKGD)*/ static unsigned readChunk_bKGD(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (info->color.colortype == LCT_PALETTE) { /*error: this chunk must be 1 byte for indexed color image*/ if (chunkLength != 1) return 43; info->background_defined = 1; info->background_r = info->background_g = info->background_b = data[0]; } else if (info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) { /*error: this chunk must be 2 bytes for greyscale image*/ if (chunkLength != 2) return 44; info->background_defined = 1; info->background_r = info->background_g = info->background_b = 256u * data[0] + data[1]; } else if (info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) { /*error: this chunk must be 6 bytes for greyscale image*/ if (chunkLength != 6) return 45; info->background_defined = 1; info->background_r = 256u * data[0] + data[1]; info->background_g = 256u * data[2] + data[3]; info->background_b = 256u * data[4] + data[5]; } return 0; /* OK */ } /*text chunk (tEXt)*/ static unsigned readChunk_tEXt(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { unsigned error = 0; char *key = 0, *str = 0; unsigned i; while (!error) /*not really a while loop, only used to break on error*/ { unsigned length, string2_begin; length = 0; while (length < chunkLength && data[length] != 0) length++; /*even though it's not allowed by the standard, no error is thrown if there's no null termination char, if the text is empty*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; string2_begin = length + 1; /*skip keyword null terminator*/ length = chunkLength < string2_begin ? 0 : chunkLength - string2_begin; str = (char*) lodepng_malloc(length + 1); if (!str) CERROR_BREAK(error, 83); /*alloc fail*/ str[length] = 0; for (i = 0; i < length; i++) str[i] = (char) data[string2_begin + i]; error = lodepng_add_text(info, key, str); break; } lodepng_free(key); lodepng_free(str); return error; } /*compressed text chunk (zTXt)*/ static unsigned readChunk_zTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, const unsigned char* data, size_t chunkLength) { unsigned error = 0; unsigned i; unsigned length, string2_begin; char *key = 0; ucvector decoded; ucvector_init(&decoded); while (!error) /*not really a while loop, only used to break on error*/ { for (length = 0; length < chunkLength && data[length] != 0; length++) ; if (length + 2 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; if (data[length + 1] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ string2_begin = length + 2; if (string2_begin > chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ length = chunkLength - string2_begin; /*will fail if zlib error, e.g. if length is too small*/ error = zlib_decompress(&decoded.data, &decoded.size, (unsigned char*) (&data[string2_begin]), length, zlibsettings); if (error) break; ucvector_push_back(&decoded, 0); error = lodepng_add_text(info, key, (char*) decoded.data); break; } lodepng_free(key); ucvector_cleanup(&decoded); return error; } /*international text chunk (iTXt)*/ static unsigned readChunk_iTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, const unsigned char* data, size_t chunkLength) { unsigned error = 0; unsigned i; unsigned length, begin, compressed; char *key = 0, *langtag = 0, *transkey = 0; ucvector decoded; ucvector_init(&decoded); while (!error) /*not really a while loop, only used to break on error*/ { /*Quick check if the chunk length isn't too small. Even without check it'd still fail with other error checks below if it's too short. This just gives a different error code.*/ if (chunkLength < 5) CERROR_BREAK(error, 30); /*iTXt chunk too short*/ /*read the key*/ for (length = 0; length < chunkLength && data[length] != 0; length++) ; if (length + 3 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination char, corrupt?*/ if (length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ key = (char*) lodepng_malloc(length + 1); if (!key) CERROR_BREAK(error, 83); /*alloc fail*/ key[length] = 0; for (i = 0; i < length; i++) key[i] = (char) data[i]; /*read the compression method*/ compressed = data[length + 1]; if (data[length + 2] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ /*even though it's not allowed by the standard, no error is thrown if there's no null termination char, if the text is empty for the next 3 texts*/ /*read the langtag*/ begin = length + 3; length = 0; for (i = begin; i < chunkLength && data[i] != 0; i++) length++; langtag = (char*) lodepng_malloc(length + 1); if (!langtag) CERROR_BREAK(error, 83); /*alloc fail*/ langtag[length] = 0; for (i = 0; i < length; i++) langtag[i] = (char) data[begin + i]; /*read the transkey*/ begin += length + 1; length = 0; for (i = begin; i < chunkLength && data[i] != 0; i++) length++; transkey = (char*) lodepng_malloc(length + 1); if (!transkey) CERROR_BREAK(error, 83); /*alloc fail*/ transkey[length] = 0; for (i = 0; i < length; i++) transkey[i] = (char) data[begin + i]; /*read the actual text*/ begin += length + 1; length = chunkLength < begin ? 0 : chunkLength - begin; if (compressed) { /*will fail if zlib error, e.g. if length is too small*/ error = zlib_decompress(&decoded.data, &decoded.size, (unsigned char*) (&data[begin]), length, zlibsettings); if (error) break; if (decoded.allocsize < decoded.size) decoded.allocsize = decoded.size; ucvector_push_back(&decoded, 0); } else { if (!ucvector_resize(&decoded, length + 1)) CERROR_BREAK(error, 83 /*alloc fail*/); decoded.data[length] = 0; for (i = 0; i < length; i++) decoded.data[i] = data[begin + i]; } error = lodepng_add_itext(info, key, langtag, transkey, (char*) decoded.data); break; } lodepng_free(key); lodepng_free(langtag); lodepng_free(transkey); ucvector_cleanup(&decoded); return error; } static unsigned readChunk_tIME(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (chunkLength != 7) return 73; /*invalid tIME chunk size*/ info->time_defined = 1; info->time.year = 256u * data[0] + data[1]; info->time.month = data[2]; info->time.day = data[3]; info->time.hour = data[4]; info->time.minute = data[5]; info->time.second = data[6]; return 0; /* OK */ } static unsigned readChunk_pHYs(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) { if (chunkLength != 9) return 74; /*invalid pHYs chunk size*/ info->phys_defined = 1; info->phys_x = 16777216u * data[0] + 65536u * data[1] + 256u * data[2] + data[3]; info->phys_y = 16777216u * data[4] + 65536u * data[5] + 256u * data[6] + data[7]; info->phys_unit = data[8]; return 0; /* OK */ } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*read a PNG, the result will be in the same color type as the PNG (hence "generic")*/ static void decodeGeneric(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { unsigned char IEND = 0; const unsigned char* chunk; size_t i; ucvector idat; /*the data from idat chunks*/ ucvector scanlines; /*for unknown chunk order*/ unsigned unknown = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS unsigned critical_pos = 1; /*1 = after IHDR, 2 = after PLTE, 3 = after IDAT*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*provide some proper output values if error will happen*/ *out = 0; state->error = lodepng_inspect(w, h, state, in, insize); /*reads header and resets other parameters in state->info_png*/ if (state->error) return; ucvector_init(&idat); chunk = &in[33]; /*first byte of the first chunk after the header*/ /*loop through the chunks, ignoring unknown chunks and stopping at IEND chunk. IDAT data is put at the start of the in buffer*/ while (!IEND && !state->error) { unsigned chunkLength; const unsigned char* data; /*the data in the chunk*/ /*error: size of the in buffer too small to contain next chunk*/ if ((size_t) ((chunk - in) + 12) > insize || chunk < in) CERROR_BREAK(state->error, 30); /*length of the data of the chunk, excluding the length bytes, chunk type and CRC bytes*/ chunkLength = lodepng_chunk_length(chunk); /*error: chunk length larger than the max PNG chunk size*/ if (chunkLength > 2147483647) CERROR_BREAK(state->error, 63); if ((size_t) ((chunk - in) + chunkLength + 12) > insize || (chunk + chunkLength + 12) < in) { CERROR_BREAK(state->error, 64); /*error: size of the in buffer too small to contain next chunk*/ } data = lodepng_chunk_data_const(chunk); /*IDAT chunk, containing compressed image data*/ if (lodepng_chunk_type_equals(chunk, "IDAT")) { size_t oldsize = idat.size; if (!ucvector_resize(&idat, oldsize + chunkLength)) CERROR_BREAK(state->error, 83 /*alloc fail*/); for (i = 0; i < chunkLength; i++) idat.data[oldsize + i] = data[i]; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS critical_pos = 3; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } /*IEND chunk*/ else if (lodepng_chunk_type_equals(chunk, "IEND")) { IEND = 1; } /*palette chunk (PLTE)*/ else if (lodepng_chunk_type_equals(chunk, "PLTE")) { state->error = readChunk_PLTE(&state->info_png.color, data, chunkLength); if (state->error) break; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS critical_pos = 2; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } /*palette transparency chunk (tRNS)*/ else if (lodepng_chunk_type_equals(chunk, "tRNS")) { state->error = readChunk_tRNS(&state->info_png.color, data, chunkLength); if (state->error) break; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*background color chunk (bKGD)*/ else if (lodepng_chunk_type_equals(chunk, "bKGD")) { state->error = readChunk_bKGD(&state->info_png, data, chunkLength); if (state->error) break; } /*text chunk (tEXt)*/ else if (lodepng_chunk_type_equals(chunk, "tEXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_tEXt(&state->info_png, data, chunkLength); if (state->error) break; } } /*compressed text chunk (zTXt)*/ else if (lodepng_chunk_type_equals(chunk, "zTXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_zTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); if (state->error) break; } } /*international text chunk (iTXt)*/ else if (lodepng_chunk_type_equals(chunk, "iTXt")) { if (state->decoder.read_text_chunks) { state->error = readChunk_iTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); if (state->error) break; } } else if (lodepng_chunk_type_equals(chunk, "tIME")) { state->error = readChunk_tIME(&state->info_png, data, chunkLength); if (state->error) break; } else if (lodepng_chunk_type_equals(chunk, "pHYs")) { state->error = readChunk_pHYs(&state->info_png, data, chunkLength); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ else /*it's not an implemented chunk type, so ignore it: skip over the data*/ { /*error: unknown critical chunk (5th bit of first byte of chunk type is 0)*/ if (!lodepng_chunk_ancillary(chunk)) CERROR_BREAK(state->error, 69); unknown = 1; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS if (state->decoder.remember_unknown_chunks) { state->error = lodepng_chunk_append( &state->info_png.unknown_chunks_data[critical_pos - 1], &state->info_png.unknown_chunks_size[critical_pos - 1], chunk); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } if (!state->decoder.ignore_crc && !unknown) /*check CRC if wanted, only on known chunk types*/ { if (lodepng_chunk_check_crc(chunk)) CERROR_BREAK(state->error, 57); /*invalid CRC*/ } if (!IEND) chunk = lodepng_chunk_next_const(chunk); } ucvector_init(&scanlines); if (!state->error) { /*maximum final image length is already reserved in the vector's length - this is not really necessary*/ if (!ucvector_resize(&scanlines, lodepng_get_raw_size(*w, *h, &state->info_png.color) + *h)) { state->error = 83; /*alloc fail*/ } } if (!state->error) { /*decompress with the Zlib decompressor*/ state->error = zlib_decompress(&scanlines.data, &scanlines.size, idat.data, idat.size, &state->decoder.zlibsettings); } ucvector_cleanup(&idat); if (!state->error) { ucvector outv; ucvector_init(&outv); if (!ucvector_resizev(&outv, lodepng_get_raw_size(*w, *h, &state->info_png.color), 0)) state->error = 83; /*alloc fail*/ if (!state->error) state->error = postProcessScanlines(outv.data, scanlines.data, *w, *h, &state->info_png); *out = outv.data; } ucvector_cleanup(&scanlines); } unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize) { *out = 0; decodeGeneric(out, w, h, state, in, insize); if (state->error) return state->error; if (!state->decoder.color_convert || lodepng_color_mode_equal(&state->info_raw, &state->info_png.color)) { /*same color type, no copying or converting of data needed*/ /*store the info_png color settings on the info_raw so that the info_raw still reflects what colortype the raw image has to the end user*/ if (!state->decoder.color_convert) { state->error = lodepng_color_mode_copy(&state->info_raw, &state->info_png.color); if (state->error) return state->error; } } else { /*color conversion needed; sort of copy of the data*/ unsigned char* data = *out; size_t outsize; /*TODO: check if this works according to the statement in the documentation: "The converter can convert from greyscale input color type, to 8-bit greyscale or greyscale with alpha"*/ if (!(state->info_raw.colortype == LCT_RGB || state->info_raw.colortype == LCT_RGBA) && !(state->info_raw.bitdepth == 8)) { return 56; /*unsupported color mode conversion*/ } outsize = lodepng_get_raw_size(*w, *h, &state->info_raw); *out = (unsigned char*) lodepng_malloc(outsize); if (!(*out)) { state->error = 83; /*alloc fail*/ } else state->error = lodepng_convert(*out, data, &state->info_raw, &state->info_png.color, *w, *h, state->decoder.fix_png); lodepng_free(data); } return state->error; } unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth) { unsigned error; LodePNGState state; lodepng_state_init(&state); state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; error = lodepng_decode(out, w, h, &state, in, insize); lodepng_state_cleanup(&state); return error; } unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) { return lodepng_decode_memory(out, w, h, in, insize, LCT_RGBA, 8); } unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) { return lodepng_decode_memory(out, w, h, in, insize, LCT_RGB, 8); } #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error; error = lodepng_load_file(&buffer, &buffersize, filename); if (!error) error = lodepng_decode_memory(out, w, h, buffer, buffersize, colortype, bitdepth); lodepng_free(buffer); return error; } unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) { return lodepng_decode_file(out, w, h, filename, LCT_RGBA, 8); } unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) { return lodepng_decode_file(out, w, h, filename, LCT_RGB, 8); } #endif /*LODEPNG_COMPILE_DISK*/ void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings) { settings->color_convert = 1; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS settings->read_text_chunks = 1; settings->remember_unknown_chunks = 0; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ settings->ignore_crc = 0; settings->fix_png = 0; lodepng_decompress_settings_init(&settings->zlibsettings); } #endif /*LODEPNG_COMPILE_DECODER*/ #if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) void lodepng_state_init(LodePNGState* state) { #ifdef LODEPNG_COMPILE_DECODER lodepng_decoder_settings_init(&state->decoder); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER lodepng_encoder_settings_init(&state->encoder); #endif /*LODEPNG_COMPILE_ENCODER*/ lodepng_color_mode_init(&state->info_raw); lodepng_info_init(&state->info_png); state->error = 1; } void lodepng_state_cleanup(LodePNGState* state) { lodepng_color_mode_cleanup(&state->info_raw); lodepng_info_cleanup(&state->info_png); } void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source) { lodepng_state_cleanup(dest); *dest = *source; lodepng_color_mode_init(&dest->info_raw); lodepng_info_init(&dest->info_png); dest->error = lodepng_color_mode_copy(&dest->info_raw, &source->info_raw); if (dest->error) return; dest->error = lodepng_info_copy(&dest->info_png, &source->info_png); if (dest->error) return; } #endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ #ifdef LODEPNG_COMPILE_ENCODER /* ////////////////////////////////////////////////////////////////////////// */ /* / PNG Encoder / */ /* ////////////////////////////////////////////////////////////////////////// */ /*chunkName must be string of 4 characters*/ static unsigned addChunk(ucvector* out, const char* chunkName, const unsigned char* data, size_t length) { CERROR_TRY_RETURN( lodepng_chunk_create(&out->data, &out->size, (unsigned )length, chunkName, data)); out->allocsize = out->size; /*fix the allocsize again*/ return 0; } static void writeSignature(ucvector* out) { /*8 bytes PNG signature, aka the magic bytes*/ ucvector_push_back(out, 137); ucvector_push_back(out, 80); ucvector_push_back(out, 78); ucvector_push_back(out, 71); ucvector_push_back(out, 13); ucvector_push_back(out, 10); ucvector_push_back(out, 26); ucvector_push_back(out, 10); } static unsigned addChunk_IHDR(ucvector* out, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth, unsigned interlace_method) { unsigned error = 0; ucvector header; ucvector_init(&header); lodepng_add32bitInt(&header, w); /*width*/ lodepng_add32bitInt(&header, h); /*height*/ ucvector_push_back(&header, (unsigned char) bitdepth); /*bit depth*/ ucvector_push_back(&header, (unsigned char) colortype); /*color type*/ ucvector_push_back(&header, 0); /*compression method*/ ucvector_push_back(&header, 0); /*filter method*/ ucvector_push_back(&header, interlace_method); /*interlace method*/ error = addChunk(out, "IHDR", header.data, header.size); ucvector_cleanup(&header); return error; } static unsigned addChunk_PLTE(ucvector* out, const LodePNGColorMode* info) { unsigned error = 0; size_t i; ucvector PLTE; ucvector_init(&PLTE); for (i = 0; i < info->palettesize * 4; i++) { /*add all channels except alpha channel*/ if (i % 4 != 3) ucvector_push_back(&PLTE, info->palette[i]); } error = addChunk(out, "PLTE", PLTE.data, PLTE.size); ucvector_cleanup(&PLTE); return error; } static unsigned addChunk_tRNS(ucvector* out, const LodePNGColorMode* info) { unsigned error = 0; size_t i; ucvector tRNS; ucvector_init(&tRNS); if (info->colortype == LCT_PALETTE) { size_t amount = info->palettesize; /*the tail of palette values that all have 255 as alpha, does not have to be encoded*/ for (i = info->palettesize; i > 0; i--) { if (info->palette[4 * (i - 1) + 3] == 255) amount--; else break; } /*add only alpha channel*/ for (i = 0; i < amount; i++) ucvector_push_back(&tRNS, info->palette[4 * i + 3]); } else if (info->colortype == LCT_GREY) { if (info->key_defined) { ucvector_push_back(&tRNS, (unsigned char) (info->key_r / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_r % 256)); } } else if (info->colortype == LCT_RGB) { if (info->key_defined) { ucvector_push_back(&tRNS, (unsigned char) (info->key_r / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_r % 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_g / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_g % 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_b / 256)); ucvector_push_back(&tRNS, (unsigned char) (info->key_b % 256)); } } error = addChunk(out, "tRNS", tRNS.data, tRNS.size); ucvector_cleanup(&tRNS); return error; } static unsigned addChunk_IDAT(ucvector* out, const unsigned char* data, size_t datasize, LodePNGCompressSettings* zlibsettings) { ucvector zlibdata; unsigned error = 0; /*compress with the Zlib compressor*/ ucvector_init(&zlibdata); error = zlib_compress(&zlibdata.data, &zlibdata.size, data, datasize, zlibsettings); if (!error) error = addChunk(out, "IDAT", zlibdata.data, zlibdata.size); ucvector_cleanup(&zlibdata); return error; } static unsigned addChunk_IEND(ucvector* out) { unsigned error = 0; error = addChunk(out, "IEND", 0, 0); return error; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static unsigned addChunk_tEXt(ucvector* out, const char* keyword, const char* textstring) { unsigned error = 0; size_t i; ucvector text; ucvector_init(&text); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&text, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&text, 0); /*0 termination char*/ for (i = 0; textstring[i] != 0; i++) ucvector_push_back(&text, (unsigned char) textstring[i]); error = addChunk(out, "tEXt", text.data, text.size); ucvector_cleanup(&text); return error; } static unsigned addChunk_zTXt(ucvector* out, const char* keyword, const char* textstring, LodePNGCompressSettings* zlibsettings) { unsigned error = 0; ucvector data, compressed; size_t i, textsize = strlen(textstring); ucvector_init(&data); ucvector_init(&compressed); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&data, 0); /*0 termination char*/ ucvector_push_back(&data, 0); /*compression method: 0*/ error = zlib_compress(&compressed.data, &compressed.size, (unsigned char*) textstring, textsize, zlibsettings); if (!error) { for (i = 0; i < compressed.size; i++) ucvector_push_back(&data, compressed.data[i]); error = addChunk(out, "zTXt", data.data, data.size); } ucvector_cleanup(&compressed); ucvector_cleanup(&data); return error; } static unsigned addChunk_iTXt(ucvector* out, unsigned compressed, const char* keyword, const char* langtag, const char* transkey, const char* textstring, LodePNGCompressSettings* zlibsettings) { unsigned error = 0; ucvector data; size_t i, textsize = strlen(textstring); ucvector_init(&data); for (i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char) keyword[i]); if (i < 1 || i > 79) return 89; /*error: invalid keyword size*/ ucvector_push_back(&data, 0); /*null termination char*/ ucvector_push_back(&data, compressed ? 1 : 0); /*compression flag*/ ucvector_push_back(&data, 0); /*compression method*/ for (i = 0; langtag[i] != 0; i++) ucvector_push_back(&data, (unsigned char) langtag[i]); ucvector_push_back(&data, 0); /*null termination char*/ for (i = 0; transkey[i] != 0; i++) ucvector_push_back(&data, (unsigned char) transkey[i]); ucvector_push_back(&data, 0); /*null termination char*/ if (compressed) { ucvector compressed_data; ucvector_init(&compressed_data); error = zlib_compress(&compressed_data.data, &compressed_data.size, (unsigned char*) textstring, textsize, zlibsettings); if (!error) { for (i = 0; i < compressed_data.size; i++) ucvector_push_back(&data, compressed_data.data[i]); } ucvector_cleanup(&compressed_data); } else /*not compressed*/ { for (i = 0; textstring[i] != 0; i++) ucvector_push_back(&data, (unsigned char) textstring[i]); } if (!error) error = addChunk(out, "iTXt", data.data, data.size); ucvector_cleanup(&data); return error; } static unsigned addChunk_bKGD(ucvector* out, const LodePNGInfo* info) { unsigned error = 0; ucvector bKGD; ucvector_init(&bKGD); if (info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); } else if (info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_g / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_g % 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_b / 256)); ucvector_push_back(&bKGD, (unsigned char) (info->background_b % 256)); } else if (info->color.colortype == LCT_PALETTE) { ucvector_push_back(&bKGD, (unsigned char) (info->background_r % 256)); /*palette index*/ } error = addChunk(out, "bKGD", bKGD.data, bKGD.size); ucvector_cleanup(&bKGD); return error; } static unsigned addChunk_tIME(ucvector* out, const LodePNGTime* time) { unsigned error = 0; unsigned char* data = (unsigned char*) lodepng_malloc(7); if (!data) return 83; /*alloc fail*/ data[0] = (unsigned char) (time->year / 256); data[1] = (unsigned char) (time->year % 256); data[2] = (unsigned char) time->month; data[3] = (unsigned char) time->day; data[4] = (unsigned char) time->hour; data[5] = (unsigned char) time->minute; data[6] = (unsigned char) time->second; error = addChunk(out, "tIME", data, 7); lodepng_free(data); return error; } static unsigned addChunk_pHYs(ucvector* out, const LodePNGInfo* info) { unsigned error = 0; ucvector data; ucvector_init(&data); lodepng_add32bitInt(&data, info->phys_x); lodepng_add32bitInt(&data, info->phys_y); ucvector_push_back(&data, info->phys_unit); error = addChunk(out, "pHYs", data.data, data.size); ucvector_cleanup(&data); return error; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ static void filterScanline(unsigned char* out, const unsigned char* scanline, const unsigned char* prevline, size_t length, size_t bytewidth, unsigned char filterType) { size_t i; switch (filterType) { case 0: /*None*/ for (i = 0; i < length; i++) out[i] = scanline[i]; break; case 1: /*Sub*/ if (prevline) { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; } break; case 2: /*Up*/ if (prevline) { for (i = 0; i < length; i++) out[i] = scanline[i] - prevline[i]; } else { for (i = 0; i < length; i++) out[i] = scanline[i]; } break; case 3: /*Average*/ if (prevline) { for (i = 0; i < bytewidth; i++) out[i] = scanline[i] - prevline[i] / 2; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - ((scanline[i - bytewidth] + prevline[i]) / 2); } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; for (i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth] / 2; } break; case 4: /*Paeth*/ if (prevline) { /*paethPredictor(0, prevline[i], 0) is always prevline[i]*/ for (i = 0; i < bytewidth; i++) out[i] = (scanline[i] - prevline[i]); for (i = bytewidth; i < length; i++) { out[i] = (scanline[i] - paethPredictor(scanline[i - bytewidth], prevline[i], prevline[i - bytewidth])); } } else { for (i = 0; i < bytewidth; i++) out[i] = scanline[i]; /*paethPredictor(scanline[i - bytewidth], 0, 0) is always scanline[i - bytewidth]*/ for (i = bytewidth; i < length; i++) out[i] = (scanline[i] - scanline[i - bytewidth]); } break; default: return; /*unexisting filter type given*/ } } /* log2 approximation. A slight bit faster than std::log. */ static float flog2(float f) { float result = 0; while (f > 32) { result += 4; f /= 16; } while (f > 2) { result++; f /= 2; } return result + 1.442695f * (f * f * f / 3 - 3 * f * f / 2 + 3 * f - 1.83333f); } static unsigned filter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, const LodePNGColorMode* info, const LodePNGEncoderSettings* settings) { /* For PNG filter method 0 out must be a buffer with as size: h + (w * h * bpp + 7) / 8, because there are the scanlines with 1 extra byte per scanline */ unsigned bpp = lodepng_get_bpp(info); /*the width of a scanline in bytes, not including the filter type*/ size_t linebytes = (w * bpp + 7) / 8; /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ size_t bytewidth = (bpp + 7) / 8; const unsigned char* prevline = 0; unsigned x, y; unsigned error = 0; LodePNGFilterStrategy strategy = settings->filter_strategy; /* There is a heuristic called the minimum sum of absolute differences heuristic, suggested by the PNG standard: * If the image type is Palette, or the bit depth is smaller than 8, then do not filter the image (i.e. use fixed filtering, with the filter None). * (The other case) If the image type is Grayscale or RGB (with or without Alpha), and the bit depth is not smaller than 8, then use adaptive filtering heuristic as follows: independently for each row, apply all five filters and select the filter that produces the smallest sum of absolute values per row. This heuristic is used if filter strategy is LFS_MINSUM and filter_palette_zero is true. If filter_palette_zero is true and filter_strategy is not LFS_MINSUM, the above heuristic is followed, but for "the other case", whatever strategy filter_strategy is set to instead of the minimum sum heuristic is used. */ if (settings->filter_palette_zero && (info->colortype == LCT_PALETTE || info->bitdepth < 8)) strategy = LFS_ZERO; if (bpp == 0) return 31; /*error: invalid color type*/ if (strategy == LFS_ZERO) { for (y = 0; y < h; y++) { size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ size_t inindex = linebytes * y; out[outindex] = 0; /*filter type byte*/ filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, 0); prevline = &in[inindex]; } } else if (strategy == LFS_MINSUM) { /*adaptive filtering*/ size_t sum[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ size_t smallest = 0; unsigned char type, bestType = 0; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); if (!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ } if (!error) { for (y = 0; y < h; y++) { /*try the 5 filter types*/ for (type = 0; type < 5; type++) { filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); /*calculate the sum of the result*/ sum[type] = 0; if (type == 0) { for (x = 0; x < linebytes; x++) sum[type] += (unsigned char) (attempt[type].data[x]); } else { for (x = 0; x < linebytes; x++) { /*For differences, each byte should be treated as signed, values above 127 are negative (converted to signed char). Filtertype 0 isn't a difference though, so use unsigned there. This means filtertype 0 is almost never chosen, but that is justified.*/ unsigned char s = attempt[type].data[x]; sum[type] += s < 128 ? s : (255U - s); } } /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || sum[type] < smallest) { bestType = type; smallest = sum[type]; } } prevline = &in[y * linebytes]; /*now fill the out values*/ out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else if (strategy == LFS_ENTROPY) { float sum[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ float smallest = 0; unsigned type, bestType = 0; unsigned count[256]; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); if (!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ } for (y = 0; y < h; y++) { /*try the 5 filter types*/ for (type = 0; type < 5; type++) { filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); for (x = 0; x < 256; x++) count[x] = 0; for (x = 0; x < linebytes; x++) count[attempt[type].data[x]]++; count[type]++; /*the filter type itself is part of the scanline*/ sum[type] = 0; for (x = 0; x < 256; x++) { float p = count[x] / (float) (linebytes + 1); sum[type] += count[x] == 0 ? 0 : flog2(1 / p) * p; } /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || sum[type] < smallest) { bestType = type; smallest = sum[type]; } } prevline = &in[y * linebytes]; /*now fill the out values*/ out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else if (strategy == LFS_PREDEFINED) { for (y = 0; y < h; y++) { size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ size_t inindex = linebytes * y; unsigned char type = settings->predefined_filters[y]; out[outindex] = type; /*filter type byte*/ filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, type); prevline = &in[inindex]; } } else if (strategy == LFS_BRUTE_FORCE) { /*brute force filter chooser. deflate the scanline after every filter attempt to see which one deflates best. This is very slow and gives only slightly smaller, sometimes even larger, result*/ size_t size[5]; ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ size_t smallest = 0; unsigned type = 0, bestType = 0; unsigned char* dummy; LodePNGCompressSettings zlibsettings = settings->zlibsettings; /*use fixed tree on the attempts so that the tree is not adapted to the filtertype on purpose, to simulate the true case where the tree is the same for the whole image. Sometimes it gives better result with dynamic tree anyway. Using the fixed tree sometimes gives worse, but in rare cases better compression. It does make this a bit less slow, so it's worth doing this.*/ zlibsettings.btype = 1; /*a custom encoder likely doesn't read the btype setting and is optimized for complete PNG images only, so disable it*/ zlibsettings.custom_zlib = 0; zlibsettings.custom_deflate = 0; for (type = 0; type < 5; type++) { ucvector_init(&attempt[type]); ucvector_resize(&attempt[type], linebytes); /*todo: give error if resize failed*/ } for (y = 0; y < h; y++) /*try the 5 filter types*/ { for (type = 0; type < 5; type++) { unsigned testsize = attempt[type].size; /*if(testsize > 8) testsize /= 8;*//*it already works good enough by testing a part of the row*/ filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); size[type] = 0; dummy = 0; zlib_compress(&dummy, &size[type], attempt[type].data, testsize, &zlibsettings); lodepng_free(dummy); /*check if this is smallest size (or if type == 0 it's the first case so always store the values)*/ if (type == 0 || size[type] < smallest) { bestType = type; smallest = size[type]; } } prevline = &in[y * linebytes]; out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ for (x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; } for (type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); } else return 88; /* unknown filter strategy */ return error; } static void addPaddingBits(unsigned char* out, const unsigned char* in, size_t olinebits, size_t ilinebits, unsigned h) { /*The opposite of the removePaddingBits function olinebits must be >= ilinebits*/ unsigned y; size_t diff = olinebits - ilinebits; size_t obp = 0, ibp = 0; /*bit pointers*/ for (y = 0; y < h; y++) { size_t x; for (x = 0; x < ilinebits; x++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } /*obp += diff; --> no, fill in some value in the padding bits too, to avoid "Use of uninitialised value of size ###" warning from valgrind*/ for (x = 0; x < diff; x++) setBitOfReversedStream(&obp, out, 0); } } /* in: non-interlaced image with size w*h out: the same pixels, but re-ordered according to PNG's Adam7 interlacing, with no padding bits between scanlines, but between reduced images so that each reduced image starts at a byte. bpp: bits per pixel there are no padding bits, not between scanlines, not between reduced images in has the following size in bits: w * h * bpp. out is possibly bigger due to padding bits between reduced images NOTE: comments about padding bits are only relevant if bpp < 8 */ static void Adam7_interlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned i; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); if (bpp >= 8) { for (i = 0; i < 7; i++) { unsigned x, y, b; size_t bytewidth = bpp / 8; for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { size_t pixelinstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; size_t pixeloutstart = passstart[i] + (y * passw[i] + x) * bytewidth; for (b = 0; b < bytewidth; b++) { out[pixeloutstart + b] = in[pixelinstart + b]; } } } } else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ { for (i = 0; i < 7; i++) { unsigned x, y, b; unsigned ilinebits = bpp * passw[i]; unsigned olinebits = bpp * w; size_t obp, ibp; /*bit pointers (for out and in buffer)*/ for (y = 0; y < passh[i]; y++) for (x = 0; x < passw[i]; x++) { ibp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; obp = (8 * passstart[i]) + (y * ilinebits + x * bpp); for (b = 0; b < bpp; b++) { unsigned char bit = readBitFromReversedStream(&ibp, in); setBitOfReversedStream(&obp, out, bit); } } } } } /*out must be buffer big enough to contain uncompressed IDAT chunk data, and in must contain the full image. return value is error**/ static unsigned preProcessScanlines(unsigned char** out, size_t* outsize, const unsigned char* in, unsigned w, unsigned h, const LodePNGInfo* info_png, const LodePNGEncoderSettings* settings) { /* This function converts the pure 2D image with the PNG's colortype, into filtered-padded-interlaced data. Steps: *) if no Adam7: 1) add padding bits (= posible extra bits per scanline if bpp < 8) 2) filter *) if adam7: 1) Adam7_interlace 2) 7x add padding bits 3) 7x filter */ unsigned bpp = lodepng_get_bpp(&info_png->color); unsigned error = 0; if (info_png->interlace_method == 0) { *outsize = h + (h * ((w * bpp + 7) / 8)); /*image size plus an extra byte per scanline + possible padding bits*/ *out = (unsigned char*) lodepng_malloc(*outsize); if (!(*out) && (*outsize)) error = 83; /*alloc fail*/ if (!error) { /*non multiple of 8 bits per scanline, padding bits needed per scanline*/ if (bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) { unsigned char* padded = (unsigned char*) lodepng_malloc( h * ((w * bpp + 7) / 8)); if (!padded) error = 83; /*alloc fail*/ if (!error) { addPaddingBits(padded, in, ((w * bpp + 7) / 8) * 8, w * bpp, h); error = filter(*out, padded, w, h, &info_png->color, settings); } lodepng_free(padded); } else { /*we can immediatly filter into the out buffer, no other steps needed*/ error = filter(*out, in, w, h, &info_png->color, settings); } } } else /*interlace_method is 1 (Adam7)*/ { unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; unsigned char* adam7; Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); *outsize = filter_passstart[7]; /*image size plus an extra byte per scanline + possible padding bits*/ *out = (unsigned char*) lodepng_malloc(*outsize); if (!(*out)) error = 83; /*alloc fail*/ adam7 = (unsigned char*) lodepng_malloc(passstart[7]); if (!adam7 && passstart[7]) error = 83; /*alloc fail*/ if (!error) { unsigned i; Adam7_interlace(adam7, in, w, h, bpp); for (i = 0; i < 7; i++) { if (bpp < 8) { unsigned char* padded = (unsigned char*) lodepng_malloc( padded_passstart[i + 1] - padded_passstart[i]); if (!padded) ERROR_BREAK(83); /*alloc fail*/ addPaddingBits(padded, &adam7[passstart[i]], ((passw[i] * bpp + 7) / 8) * 8, passw[i] * bpp, passh[i]); error = filter(&(*out)[filter_passstart[i]], padded, passw[i], passh[i], &info_png->color, settings); lodepng_free(padded); } else { error = filter(&(*out)[filter_passstart[i]], &adam7[padded_passstart[i]], passw[i], passh[i], &info_png->color, settings); } if (error) break; } } lodepng_free(adam7); } return error; } /* palette must have 4 * palettesize bytes allocated, and given in format RGBARGBARGBARGBA... returns 0 if the palette is opaque, returns 1 if the palette has a single color with alpha 0 ==> color key returns 2 if the palette is semi-translucent. */ static unsigned getPaletteTranslucency(const unsigned char* palette, size_t palettesize) { size_t i; unsigned key = 0; unsigned r = 0, g = 0, b = 0; /*the value of the color with alpha 0, so long as color keying is possible*/ for (i = 0; i < palettesize; i++) { if (!key && palette[4 * i + 3] == 0) { r = palette[4 * i + 0]; g = palette[4 * i + 1]; b = palette[4 * i + 2]; key = 1; i = (size_t) (-1); /*restart from beginning, to detect earlier opaque colors with key's value*/ } else if (palette[4 * i + 3] != 255) return 2; /*when key, no opaque RGB may have key's RGB*/ else if (key && r == palette[i * 4 + 0] && g == palette[i * 4 + 1] && b == palette[i * 4 + 2]) return 2; } return key; } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS static unsigned addUnknownChunks(ucvector* out, unsigned char* data, size_t datasize) { unsigned char* inchunk = data; while ((size_t) (inchunk - data) < datasize) { CERROR_TRY_RETURN(lodepng_chunk_append(&out->data, &out->size, inchunk)); out->allocsize = out->size; /*fix the allocsize again*/ inchunk = lodepng_chunk_next(inchunk); } return 0; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ unsigned lodepng_encode(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGState* state) { LodePNGInfo info; ucvector outv; unsigned char* data = 0; /*uncompressed version of the IDAT chunk data*/ size_t datasize = 0; /*provide some proper output values if error will happen*/ *out = 0; *outsize = 0; state->error = 0; lodepng_info_init(&info); lodepng_info_copy(&info, &state->info_png); if ((info.color.colortype == LCT_PALETTE || state->encoder.force_palette) && (info.color.palettesize == 0 || info.color.palettesize > 256)) { state->error = 68; /*invalid palette size, it is only allowed to be 1-256*/ return state->error; } if (state->encoder.auto_convert != LAC_NO) { state->error = lodepng_auto_choose_color(&info.color, image, w, h, &state->info_raw, state->encoder.auto_convert); } if (state->error) return state->error; if (state->encoder.zlibsettings.btype > 2) { CERROR_RETURN_ERROR(state->error, 61); /*error: unexisting btype*/ } if (state->info_png.interlace_method > 1) { CERROR_RETURN_ERROR(state->error, 71); /*error: unexisting interlace mode*/ } state->error = checkColorValidity(info.color.colortype, info.color.bitdepth); if (state->error) return state->error; /*error: unexisting color type given*/ state->error = checkColorValidity(state->info_raw.colortype, state->info_raw.bitdepth); if (state->error) return state->error; /*error: unexisting color type given*/ if (!lodepng_color_mode_equal(&state->info_raw, &info.color)) { unsigned char* converted; size_t size = (w * h * lodepng_get_bpp(&info.color) + 7) / 8; converted = (unsigned char*) lodepng_malloc(size); if (!converted && size) state->error = 83; /*alloc fail*/ if (!state->error) { state->error = lodepng_convert(converted, image, &info.color, &state->info_raw, w, h, 0 /*fix_png*/); } if (!state->error) preProcessScanlines(&data, &datasize, converted, w, h, &info, &state->encoder); lodepng_free(converted); } else preProcessScanlines(&data, &datasize, image, w, h, &info, &state->encoder); ucvector_init(&outv); while (!state->error) /*while only executed once, to break on error*/ { #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS size_t i; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*write signature and chunks*/ writeSignature(&outv); /*IHDR*/ addChunk_IHDR(&outv, w, h, info.color.colortype, info.color.bitdepth, info.interlace_method); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*unknown chunks between IHDR and PLTE*/ if (info.unknown_chunks_data[0]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[0], info.unknown_chunks_size[0]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*PLTE*/ if (info.color.colortype == LCT_PALETTE) { addChunk_PLTE(&outv, &info.color); } if (state->encoder.force_palette && (info.color.colortype == LCT_RGB || info.color.colortype == LCT_RGBA)) { addChunk_PLTE(&outv, &info.color); } /*tRNS*/ if (info.color.colortype == LCT_PALETTE && getPaletteTranslucency(info.color.palette, info.color.palettesize) != 0) { addChunk_tRNS(&outv, &info.color); } if ((info.color.colortype == LCT_GREY || info.color.colortype == LCT_RGB) && info.color.key_defined) { addChunk_tRNS(&outv, &info.color); } #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*bKGD (must come between PLTE and the IDAt chunks*/ if (info.background_defined) addChunk_bKGD(&outv, &info); /*pHYs (must come before the IDAT chunks)*/ if (info.phys_defined) addChunk_pHYs(&outv, &info); /*unknown chunks between PLTE and IDAT*/ if (info.unknown_chunks_data[1]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[1], info.unknown_chunks_size[1]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*IDAT (multiple IDAT chunks must be consecutive)*/ state->error = addChunk_IDAT(&outv, data, datasize, &state->encoder.zlibsettings); if (state->error) break; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*tIME*/ if (info.time_defined) addChunk_tIME(&outv, &info.time); /*tEXt and/or zTXt*/ for (i = 0; i < info.text_num; i++) { if (strlen(info.text_keys[i]) > 79) { state->error = 66; /*text chunk too large*/ break; } if (strlen(info.text_keys[i]) < 1) { state->error = 67; /*text chunk too small*/ break; } if (state->encoder.text_compression) { addChunk_zTXt(&outv, info.text_keys[i], info.text_strings[i], &state->encoder.zlibsettings); } else { addChunk_tEXt(&outv, info.text_keys[i], info.text_strings[i]); } } /*LodePNG version id in text chunk*/ if (state->encoder.add_id) { unsigned alread_added_id_text = 0; for (i = 0; i < info.text_num; i++) { if (!strcmp(info.text_keys[i], "LodePNG")) { alread_added_id_text = 1; break; } } if (alread_added_id_text == 0) { addChunk_tEXt(&outv, "LodePNG", VERSION_STRING); /*it's shorter as tEXt than as zTXt chunk*/ } } /*iTXt*/ for (i = 0; i < info.itext_num; i++) { if (strlen(info.itext_keys[i]) > 79) { state->error = 66; /*text chunk too large*/ break; } if (strlen(info.itext_keys[i]) < 1) { state->error = 67; /*text chunk too small*/ break; } addChunk_iTXt(&outv, state->encoder.text_compression, info.itext_keys[i], info.itext_langtags[i], info.itext_transkeys[i], info.itext_strings[i], &state->encoder.zlibsettings); } /*unknown chunks between IDAT and IEND*/ if (info.unknown_chunks_data[2]) { state->error = addUnknownChunks(&outv, info.unknown_chunks_data[2], info.unknown_chunks_size[2]); if (state->error) break; } #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ addChunk_IEND(&outv); break; /*this isn't really a while loop; no error happened so break out now!*/ } lodepng_info_cleanup(&info); lodepng_free(data); /*instead of cleaning the vector up, give it to the output*/ *out = outv.data; *outsize = outv.size; return state->error; } unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned error; LodePNGState state; lodepng_state_init(&state); state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; state.info_png.color.colortype = colortype; state.info_png.color.bitdepth = bitdepth; lodepng_encode(out, outsize, image, w, h, &state); error = state.error; lodepng_state_cleanup(&state); return error; } unsigned lodepng_encode32(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGBA, 8); } unsigned lodepng_encode24(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGB, 8); } #ifdef LODEPNG_COMPILE_DISK unsigned lodepng_encode_file(const char* filename, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode_memory(&buffer, &buffersize, image, w, h, colortype, bitdepth); if (!error) error = lodepng_save_file(buffer, buffersize, filename); lodepng_free(buffer); return error; } unsigned lodepng_encode32_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_file(filename, image, w, h, LCT_RGBA, 8); } unsigned lodepng_encode24_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) { return lodepng_encode_file(filename, image, w, h, LCT_RGB, 8); } #endif /*LODEPNG_COMPILE_DISK*/ void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings) { lodepng_compress_settings_init(&settings->zlibsettings); settings->filter_palette_zero = 1; settings->filter_strategy = LFS_MINSUM; settings->auto_convert = LAC_AUTO; settings->force_palette = 0; settings->predefined_filters = 0; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS settings->add_id = 0; settings->text_compression = 1; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ERROR_TEXT /* This returns the description of a numerical error code in English. This is also the documentation of all the error codes. */ const char* lodepng_error_text(unsigned code) { switch (code) { case 0: return "no error, everything went ok"; case 1: return "nothing done yet"; /*the Encoder/Decoder has done nothing yet, error checking makes no sense yet*/ case 10: return "end of input memory reached without huffman end code"; /*while huffman decoding*/ case 11: return "error in code tree made it jump outside of huffman tree"; /*while huffman decoding*/ case 13: return "problem while processing dynamic deflate block"; case 14: return "problem while processing dynamic deflate block"; case 15: return "problem while processing dynamic deflate block"; case 16: return "unexisting code while processing dynamic deflate block"; case 17: return "end of out buffer memory reached while inflating"; case 18: return "invalid distance code while inflating"; case 19: return "end of out buffer memory reached while inflating"; case 20: return "invalid deflate block BTYPE encountered while decoding"; case 21: return "NLEN is not ones complement of LEN in a deflate block"; /*end of out buffer memory reached while inflating: This can happen if the inflated deflate data is longer than the amount of bytes required to fill up all the pixels of the image, given the color depth and image dimensions. Something that doesn't happen in a normal, well encoded, PNG image.*/ case 22: return "end of out buffer memory reached while inflating"; case 23: return "end of in buffer memory reached while inflating"; case 24: return "invalid FCHECK in zlib header"; case 25: return "invalid compression method in zlib header"; case 26: return "FDICT encountered in zlib header while it's not used for PNG"; case 27: return "PNG file is smaller than a PNG header"; /*Checks the magic file header, the first 8 bytes of the PNG file*/ case 28: return "incorrect PNG signature, it's no PNG or corrupted"; case 29: return "first chunk is not the header chunk"; case 30: return "chunk length too large, chunk broken off at end of file"; case 31: return "illegal PNG color type or bpp"; case 32: return "illegal PNG compression method"; case 33: return "illegal PNG filter method"; case 34: return "illegal PNG interlace method"; case 35: return "chunk length of a chunk is too large or the chunk too small"; case 36: return "illegal PNG filter type encountered"; case 37: return "illegal bit depth for this color type given"; case 38: return "the palette is too big"; /*more than 256 colors*/ case 39: return "more palette alpha values given in tRNS chunk than there are colors in the palette"; case 40: return "tRNS chunk has wrong size for greyscale image"; case 41: return "tRNS chunk has wrong size for RGB image"; case 42: return "tRNS chunk appeared while it was not allowed for this color type"; case 43: return "bKGD chunk has wrong size for palette image"; case 44: return "bKGD chunk has wrong size for greyscale image"; case 45: return "bKGD chunk has wrong size for RGB image"; /*Is the palette too small?*/ case 46: return "a value in indexed image is larger than the palette size (bitdepth = 8)"; /*Is the palette too small?*/ case 47: return "a value in indexed image is larger than the palette size (bitdepth < 8)"; /*the input data is empty, maybe a PNG file doesn't exist or is in the wrong path*/ case 48: return "empty input or file doesn't exist"; case 49: return "jumped past memory while generating dynamic huffman tree"; case 50: return "jumped past memory while generating dynamic huffman tree"; case 51: return "jumped past memory while inflating huffman block"; case 52: return "jumped past memory while inflating"; case 53: return "size of zlib data too small"; case 54: return "repeat symbol in tree while there was no value symbol yet"; /*jumped past tree while generating huffman tree, this could be when the tree will have more leaves than symbols after generating it out of the given lenghts. They call this an oversubscribed dynamic bit lengths tree in zlib.*/ case 55: return "jumped past tree while generating huffman tree"; case 56: return "given output image colortype or bitdepth not supported for color conversion"; case 57: return "invalid CRC encountered (checking CRC can be disabled)"; case 58: return "invalid ADLER32 encountered (checking ADLER32 can be disabled)"; case 59: return "requested color conversion not supported"; case 60: return "invalid window size given in the settings of the encoder (must be 0-32768)"; case 61: return "invalid BTYPE given in the settings of the encoder (only 0, 1 and 2 are allowed)"; /*LodePNG leaves the choice of RGB to greyscale conversion formula to the user.*/ case 62: return "conversion from color to greyscale not supported"; case 63: return "length of a chunk too long, max allowed for PNG is 2147483647 bytes per chunk"; /*(2^31-1)*/ /*this would result in the inability of a deflated block to ever contain an end code. It must be at least 1.*/ case 64: return "the length of the END symbol 256 in the Huffman tree is 0"; case 66: return "the length of a text chunk keyword given to the encoder is longer than the maximum of 79 bytes"; case 67: return "the length of a text chunk keyword given to the encoder is smaller than the minimum of 1 byte"; case 68: return "tried to encode a PLTE chunk with a palette that has less than 1 or more than 256 colors"; case 69: return "unknown chunk type with 'critical' flag encountered by the decoder"; case 71: return "unexisting interlace mode given to encoder (must be 0 or 1)"; case 72: return "while decoding, unexisting compression method encountering in zTXt or iTXt chunk (it must be 0)"; case 73: return "invalid tIME chunk size"; case 74: return "invalid pHYs chunk size"; /*length could be wrong, or data chopped off*/ case 75: return "no null termination char found while decoding text chunk"; case 76: return "iTXt chunk too short to contain required bytes"; case 77: return "integer overflow in buffer size"; case 78: return "failed to open file for reading"; /*file doesn't exist or couldn't be opened for reading*/ case 79: return "failed to open file for writing"; case 80: return "tried creating a tree of 0 symbols"; case 81: return "lazy matching at pos 0 is impossible"; case 82: return "color conversion to palette requested while a color isn't in palette"; case 83: return "memory allocation failed"; case 84: return "given image too small to contain all pixels to be encoded"; case 85: return "internal color conversion bug"; case 86: return "impossible offset in lz77 encoding (internal bug)"; case 87: return "must provide custom zlib function pointer if LODEPNG_COMPILE_ZLIB is not defined"; case 88: return "invalid filter strategy given for LodePNGEncoderSettings.filter_strategy"; case 89: return "text chunk keyword too short or long: must have size 1-79"; /*the windowsize in the LodePNGCompressSettings. Requiring POT(==> & instead of %) makes encoding 12% faster.*/ case 90: return "windowsize must be a power of two"; } return "unknown error code"; } #endif /*LODEPNG_COMPILE_ERROR_TEXT*/ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ /* // C++ Wrapper // */ /* ////////////////////////////////////////////////////////////////////////// */ /* ////////////////////////////////////////////////////////////////////////// */ #ifdef LODEPNG_COMPILE_CPP namespace lodepng { #ifdef LODEPNG_COMPILE_DISK void load_file(std::vector& buffer, const std::string& filename) { std::ifstream file(filename.c_str(), std::ios::in | std::ios::binary | std::ios::ate); /*get filesize*/ std::streamsize size = 0; if (file.seekg(0, std::ios::end).good()) size = file.tellg(); if (file.seekg(0, std::ios::beg).good()) size -= file.tellg(); /*read contents of the file into the vector*/ buffer.resize(size_t(size)); if (size > 0) file.read((char*) (&buffer[0]), size); } /*write given buffer to the file, overwriting the file, it doesn't append to it.*/ void save_file(const std::vector& buffer, const std::string& filename) { std::ofstream file(filename.c_str(), std::ios::out | std::ios::binary); file.write(buffer.empty() ? 0 : (char*) &buffer[0], std::streamsize(buffer.size())); } #endif //LODEPNG_COMPILE_DISK #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_DECODER unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings& settings) { unsigned char* buffer = 0; size_t buffersize = 0; unsigned error = zlib_decompress(&buffer, &buffersize, in, insize, &settings); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned decompress(std::vector& out, const std::vector& in, const LodePNGDecompressSettings& settings) { return decompress(out, in.empty() ? 0 : &in[0], in.size(), settings); } #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER unsigned compress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGCompressSettings& settings) { unsigned char* buffer = 0; size_t buffersize = 0; unsigned error = zlib_compress(&buffer, &buffersize, in, insize, &settings); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned compress(std::vector& out, const std::vector& in, const LodePNGCompressSettings& settings) { return compress(out, in.empty() ? 0 : &in[0], in.size(), settings); } #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_PNG State::State() { lodepng_state_init(this); } State::State(const State& other) { lodepng_state_init(this); lodepng_state_copy(this, &other); } State::~State() { lodepng_state_cleanup(this); } State& State::operator=(const State& other) { lodepng_state_copy(this, &other); return *this; } #ifdef LODEPNG_COMPILE_DECODER unsigned decode(std::vector& out, unsigned& w, unsigned& h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; unsigned error = lodepng_decode_memory(&buffer, &w, &h, in, insize, colortype, bitdepth); if (buffer && !error) { State state; state.info_raw.colortype = colortype; state.info_raw.bitdepth = bitdepth; size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::vector& in, LodePNGColorType colortype, unsigned bitdepth) { return decode(out, w, h, in.empty() ? 0 : &in[0], (unsigned) in.size(), colortype, bitdepth); } unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const unsigned char* in, size_t insize) { unsigned char* buffer = NULL; unsigned error = lodepng_decode(&buffer, &w, &h, &state, in, insize); if (buffer && !error) { size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); out.insert(out.end(), &buffer[0], &buffer[buffersize]); } lodepng_free(buffer); return error; } unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const std::vector& in) { return decode(out, w, h, state, in.empty() ? 0 : &in[0], in.size()); } #ifdef LODEPNG_COMPILE_DISK unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::string& filename, LodePNGColorType colortype, unsigned bitdepth) { std::vector buffer; load_file(buffer, filename); return decode(out, w, h, buffer, colortype, bitdepth); } #endif //LODEPNG_COMPILE_DECODER #endif //LODEPNG_COMPILE_DISK #ifdef LODEPNG_COMPILE_ENCODER unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode_memory(&buffer, &buffersize, in, w, h, colortype, bitdepth); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { if (lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; return encode(out, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); } unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, State& state) { unsigned char* buffer; size_t buffersize; unsigned error = lodepng_encode(&buffer, &buffersize, in, w, h, &state); if (buffer) { out.insert(out.end(), &buffer[0], &buffer[buffersize]); lodepng_free(buffer); } return error; } unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, State& state) { if (lodepng_get_raw_size(w, h, &state.info_raw) > in.size()) return 84; return encode(out, in.empty() ? 0 : &in[0], w, h, state); } #ifdef LODEPNG_COMPILE_DISK unsigned encode(const std::string& filename, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { std::vector buffer; unsigned error = encode(buffer, in, w, h, colortype, bitdepth); if (!error) save_file(buffer, filename); return error; } unsigned encode(const std::string& filename, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) { if (lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; return encode(filename, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); } #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_PNG } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ ================================================ FILE: framework/tools/dataset-tools/lodepng.h ================================================ /* LodePNG version 20140624 Copyright (c) 2005-2014 Lode Vandevenne This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 3. This notice may not be removed or altered from any source distribution. */ #ifndef LODEPNG_H #define LODEPNG_H #include /*for size_t*/ #ifdef __cplusplus #include #include #endif /*__cplusplus*/ /* The following #defines are used to create code sections. They can be disabled to disable code sections, which can give faster compile time and smaller binary. The "NO_COMPILE" defines are designed to be used to pass as defines to the compiler command to disable them without modifying this header, e.g. -DLODEPNG_NO_COMPILE_ZLIB for gcc. */ /*deflate & zlib. If disabled, you must specify alternative zlib functions in the custom_zlib field of the compress and decompress settings*/ #ifndef LODEPNG_NO_COMPILE_ZLIB #define LODEPNG_COMPILE_ZLIB #endif /*png encoder and png decoder*/ #ifndef LODEPNG_NO_COMPILE_PNG #define LODEPNG_COMPILE_PNG #endif /*deflate&zlib decoder and png decoder*/ #ifndef LODEPNG_NO_COMPILE_DECODER #define LODEPNG_COMPILE_DECODER #endif /*deflate&zlib encoder and png encoder*/ #ifndef LODEPNG_NO_COMPILE_ENCODER #define LODEPNG_COMPILE_ENCODER #endif /*the optional built in harddisk file loading and saving functions*/ #ifndef LODEPNG_NO_COMPILE_DISK #define LODEPNG_COMPILE_DISK #endif /*support for chunks other than IHDR, IDAT, PLTE, tRNS, IEND: ancillary and unknown chunks*/ #ifndef LODEPNG_NO_COMPILE_ANCILLARY_CHUNKS #define LODEPNG_COMPILE_ANCILLARY_CHUNKS #endif /*ability to convert error numerical codes to English text string*/ #ifndef LODEPNG_NO_COMPILE_ERROR_TEXT #define LODEPNG_COMPILE_ERROR_TEXT #endif /*Compile the default allocators (C's free, malloc and realloc). If you disable this, you can define the functions lodepng_free, lodepng_malloc and lodepng_realloc in your source files with custom allocators.*/ #ifndef LODEPNG_NO_COMPILE_ALLOCATORS #define LODEPNG_COMPILE_ALLOCATORS #endif /*compile the C++ version (you can disable the C++ wrapper here even when compiling for C++)*/ #ifdef __cplusplus #ifndef LODEPNG_NO_COMPILE_CPP #define LODEPNG_COMPILE_CPP #endif #endif #ifdef LODEPNG_COMPILE_PNG /*The PNG color types (also used for raw).*/ typedef enum LodePNGColorType { LCT_GREY = 0, /*greyscale: 1,2,4,8,16 bit*/ LCT_RGB = 2, /*RGB: 8,16 bit*/ LCT_PALETTE = 3, /*palette: 1,2,4,8 bit*/ LCT_GREY_ALPHA = 4, /*greyscale with alpha: 8,16 bit*/ LCT_RGBA = 6 /*RGB with alpha: 8,16 bit*/ } LodePNGColorType; #ifdef LODEPNG_COMPILE_DECODER /* Converts PNG data in memory to raw pixel data. out: Output parameter. Pointer to buffer that will contain the raw pixel data. After decoding, its size is w * h * (bytes per pixel) bytes larger than initially. Bytes per pixel depends on colortype and bitdepth. Must be freed after usage with free(*out). Note: for 16-bit per channel colors, uses big endian format like PNG does. w: Output parameter. Pointer to width of pixel data. h: Output parameter. Pointer to height of pixel data. in: Memory buffer with the PNG file. insize: size of the in buffer. colortype: the desired color type for the raw output image. See explanation on PNG color types. bitdepth: the desired bit depth for the raw output image. See explanation on PNG color types. Return value: LodePNG error code (0 means no error). */ unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_decode_memory, but always decodes to 32-bit RGBA raw image*/ unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize); /*Same as lodepng_decode_memory, but always decodes to 24-bit RGB raw image*/ unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize); #ifdef LODEPNG_COMPILE_DISK /* Load PNG from disk, from file with given name. Same as the other decode functions, but instead takes a filename as input. */ unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_decode_file, but always decodes to 32-bit RGBA raw image.*/ unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename); /*Same as lodepng_decode_file, but always decodes to 24-bit RGB raw image.*/ unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename); #endif /*LODEPNG_COMPILE_DISK*/ #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Converts raw pixel data into a PNG image in memory. The colortype and bitdepth of the output PNG image cannot be chosen, they are automatically determined by the colortype, bitdepth and content of the input pixel data. Note: for 16-bit per channel colors, needs big endian format like PNG does. out: Output parameter. Pointer to buffer that will contain the PNG image data. Must be freed after usage with free(*out). outsize: Output parameter. Pointer to the size in bytes of the out buffer. image: The raw pixel data to encode. The size of this buffer should be w * h * (bytes per pixel), bytes per pixel depends on colortype and bitdepth. w: width of the raw pixel data in pixels. h: height of the raw pixel data in pixels. colortype: the color type of the raw input image. See explanation on PNG color types. bitdepth: the bit depth of the raw input image. See explanation on PNG color types. Return value: LodePNG error code (0 means no error). */ unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_encode_memory, but always encodes from 32-bit RGBA raw image.*/ unsigned lodepng_encode32(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h); /*Same as lodepng_encode_memory, but always encodes from 24-bit RGB raw image.*/ unsigned lodepng_encode24(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h); #ifdef LODEPNG_COMPILE_DISK /* Converts raw pixel data into a PNG file on disk. Same as the other encode functions, but instead takes a filename as output. NOTE: This overwrites existing files without warning! */ unsigned lodepng_encode_file(const char* filename, const unsigned char* image, unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth); /*Same as lodepng_encode_file, but always encodes from 32-bit RGBA raw image.*/ unsigned lodepng_encode32_file(const char* filename, const unsigned char* image, unsigned w, unsigned h); /*Same as lodepng_encode_file, but always encodes from 24-bit RGB raw image.*/ unsigned lodepng_encode24_file(const char* filename, const unsigned char* image, unsigned w, unsigned h); #endif /*LODEPNG_COMPILE_DISK*/ #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_CPP namespace lodepng { #ifdef LODEPNG_COMPILE_DECODER /*Same as lodepng_decode_memory, but decodes to an std::vector.*/ unsigned decode(std::vector& out, unsigned& w, unsigned& h, const unsigned char* in, size_t insize, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::vector& in, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #ifdef LODEPNG_COMPILE_DISK /* Converts PNG file from disk to raw pixel data in memory. Same as the other decode functions, but instead takes a filename as input. */ unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::string& filename, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER /*Same as lodepng_encode_memory, but encodes to an std::vector.*/ unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #ifdef LODEPNG_COMPILE_DISK /* Converts 32-bit RGBA raw pixel data into a PNG file on disk. Same as the other encode functions, but instead takes a filename as output. NOTE: This overwrites existing files without warning! */ unsigned encode(const std::string& filename, const unsigned char* in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); unsigned encode(const std::string& filename, const std::vector& in, unsigned w, unsigned h, LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_ENCODER } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ERROR_TEXT /*Returns an English description of the numerical error code.*/ const char* lodepng_error_text(unsigned code); #endif /*LODEPNG_COMPILE_ERROR_TEXT*/ #ifdef LODEPNG_COMPILE_DECODER /*Settings for zlib decompression*/ typedef struct LodePNGDecompressSettings LodePNGDecompressSettings; struct LodePNGDecompressSettings { unsigned ignore_adler32; /*if 1, continue and don't give an error message if the Adler32 checksum is corrupted*/ /*use custom zlib decoder instead of built in one (default: null)*/ unsigned (*custom_zlib)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGDecompressSettings*); /*use custom deflate decoder instead of built in one (default: null) if custom_zlib is used, custom_deflate is ignored since only the built in zlib function will call custom_deflate*/ unsigned (*custom_inflate)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGDecompressSettings*); const void* custom_context; /*optional custom settings for custom functions*/ }; extern const LodePNGDecompressSettings lodepng_default_decompress_settings; void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Settings for zlib compression. Tweaking these settings tweaks the balance between speed and compression ratio. */ typedef struct LodePNGCompressSettings LodePNGCompressSettings; struct LodePNGCompressSettings /*deflate = compress*/ { /*LZ77 related settings*/ unsigned btype; /*the block type for LZ (0, 1, 2 or 3, see zlib standard). Should be 2 for proper compression.*/ unsigned use_lz77; /*whether or not to use LZ77. Should be 1 for proper compression.*/ unsigned windowsize; /*must be a power of two <= 32768. higher compresses more but is slower. Default value: 2048.*/ unsigned minmatch; /*mininum lz77 length. 3 is normally best, 6 can be better for some PNGs. Default: 0*/ unsigned nicematch; /*stop searching if >= this length found. Set to 258 for best compression. Default: 128*/ unsigned lazymatching; /*use lazy matching: better compression but a bit slower. Default: true*/ /*use custom zlib encoder instead of built in one (default: null)*/ unsigned (*custom_zlib)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGCompressSettings*); /*use custom deflate encoder instead of built in one (default: null) if custom_zlib is used, custom_deflate is ignored since only the built in zlib function will call custom_deflate*/ unsigned (*custom_deflate)(unsigned char**, size_t*, const unsigned char*, size_t, const LodePNGCompressSettings*); const void* custom_context; /*optional custom settings for custom functions*/ }; extern const LodePNGCompressSettings lodepng_default_compress_settings; void lodepng_compress_settings_init(LodePNGCompressSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_PNG /* Color mode of an image. Contains all information required to decode the pixel bits to RGBA colors. This information is the same as used in the PNG file format, and is used both for PNG and raw image data in LodePNG. */ typedef struct LodePNGColorMode { /*header (IHDR)*/ LodePNGColorType colortype; /*color type, see PNG standard or documentation further in this header file*/ unsigned bitdepth; /*bits per sample, see PNG standard or documentation further in this header file*/ /* palette (PLTE and tRNS) Dynamically allocated with the colors of the palette, including alpha. When encoding a PNG, to store your colors in the palette of the LodePNGColorMode, first use lodepng_palette_clear, then for each color use lodepng_palette_add. If you encode an image without alpha with palette, don't forget to put value 255 in each A byte of the palette. When decoding, by default you can ignore this palette, since LodePNG already fills the palette colors in the pixels of the raw RGBA output. The palette is only supported for color type 3. */ unsigned char* palette; /*palette in RGBARGBA... order. When allocated, must be either 0, or have size 1024*/ size_t palettesize; /*palette size in number of colors (amount of bytes is 4 * palettesize)*/ /* transparent color key (tRNS) This color uses the same bit depth as the bitdepth value in this struct, which can be 1-bit to 16-bit. For greyscale PNGs, r, g and b will all 3 be set to the same. When decoding, by default you can ignore this information, since LodePNG sets pixels with this key to transparent already in the raw RGBA output. The color key is only supported for color types 0 and 2. */ unsigned key_defined; /*is a transparent color key given? 0 = false, 1 = true*/ unsigned key_r; /*red/greyscale component of color key*/ unsigned key_g; /*green component of color key*/ unsigned key_b; /*blue component of color key*/ } LodePNGColorMode; /*init, cleanup and copy functions to use with this struct*/ void lodepng_color_mode_init(LodePNGColorMode* info); void lodepng_color_mode_cleanup(LodePNGColorMode* info); /*return value is error code (0 means no error)*/ unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source); void lodepng_palette_clear(LodePNGColorMode* info); /*add 1 color to the palette*/ unsigned lodepng_palette_add(LodePNGColorMode* info, unsigned char r, unsigned char g, unsigned char b, unsigned char a); /*get the total amount of bits per pixel, based on colortype and bitdepth in the struct*/ unsigned lodepng_get_bpp(const LodePNGColorMode* info); /*get the amount of color channels used, based on colortype in the struct. If a palette is used, it counts as 1 channel.*/ unsigned lodepng_get_channels(const LodePNGColorMode* info); /*is it a greyscale type? (only colortype 0 or 4)*/ unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info); /*has it got an alpha channel? (only colortype 2 or 6)*/ unsigned lodepng_is_alpha_type(const LodePNGColorMode* info); /*has it got a palette? (only colortype 3)*/ unsigned lodepng_is_palette_type(const LodePNGColorMode* info); /*only returns true if there is a palette and there is a value in the palette with alpha < 255. Loops through the palette to check this.*/ unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info); /* Check if the given color info indicates the possibility of having non-opaque pixels in the PNG image. Returns true if the image can have translucent or invisible pixels (it still be opaque if it doesn't use such pixels). Returns false if the image can only have opaque pixels. In detail, it returns true only if it's a color type with alpha, or has a palette with non-opaque values, or if "key_defined" is true. */ unsigned lodepng_can_have_alpha(const LodePNGColorMode* info); /*Returns the byte size of a raw image buffer with given width, height and color mode*/ size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*The information of a Time chunk in PNG.*/ typedef struct LodePNGTime { unsigned year; /*2 bytes used (0-65535)*/ unsigned month; /*1-12*/ unsigned day; /*1-31*/ unsigned hour; /*0-23*/ unsigned minute; /*0-59*/ unsigned second; /*0-60 (to allow for leap seconds)*/ } LodePNGTime; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /*Information about the PNG image, except pixels, width and height.*/ typedef struct LodePNGInfo { /*header (IHDR), palette (PLTE) and transparency (tRNS) chunks*/ unsigned compression_method;/*compression method of the original file. Always 0.*/ unsigned filter_method; /*filter method of the original file*/ unsigned interlace_method; /*interlace method of the original file*/ LodePNGColorMode color; /*color type and bits, palette and transparency of the PNG file*/ #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /* suggested background color chunk (bKGD) This color uses the same color mode as the PNG (except alpha channel), which can be 1-bit to 16-bit. For greyscale PNGs, r, g and b will all 3 be set to the same. When encoding the encoder writes the red one. For palette PNGs: When decoding, the RGB value will be stored, not a palette index. But when encoding, specify the index of the palette in background_r, the other two are then ignored. The decoder does not use this background color to edit the color of pixels. */ unsigned background_defined; /*is a suggested background color given?*/ unsigned background_r; /*red component of suggested background color*/ unsigned background_g; /*green component of suggested background color*/ unsigned background_b; /*blue component of suggested background color*/ /* non-international text chunks (tEXt and zTXt) The char** arrays each contain num strings. The actual messages are in text_strings, while text_keys are keywords that give a short description what the actual text represents, e.g. Title, Author, Description, or anything else. A keyword is minimum 1 character and maximum 79 characters long. It's discouraged to use a single line length longer than 79 characters for texts. Don't allocate these text buffers yourself. Use the init/cleanup functions correctly and use lodepng_add_text and lodepng_clear_text. */ size_t text_num; /*the amount of texts in these char** buffers (there may be more texts in itext)*/ char** text_keys; /*the keyword of a text chunk (e.g. "Comment")*/ char** text_strings; /*the actual text*/ /* international text chunks (iTXt) Similar to the non-international text chunks, but with additional strings "langtags" and "transkeys". */ size_t itext_num; /*the amount of international texts in this PNG*/ char** itext_keys; /*the English keyword of the text chunk (e.g. "Comment")*/ char** itext_langtags; /*language tag for this text's language, ISO/IEC 646 string, e.g. ISO 639 language tag*/ char** itext_transkeys; /*keyword translated to the international language - UTF-8 string*/ char** itext_strings; /*the actual international text - UTF-8 string*/ /*time chunk (tIME)*/ unsigned time_defined; /*set to 1 to make the encoder generate a tIME chunk*/ LodePNGTime time; /*phys chunk (pHYs)*/ unsigned phys_defined; /*if 0, there is no pHYs chunk and the values below are undefined, if 1 else there is one*/ unsigned phys_x; /*pixels per unit in x direction*/ unsigned phys_y; /*pixels per unit in y direction*/ unsigned phys_unit; /*may be 0 (unknown unit) or 1 (metre)*/ /* unknown chunks There are 3 buffers, one for each position in the PNG where unknown chunks can appear each buffer contains all unknown chunks for that position consecutively The 3 buffers are the unknown chunks between certain critical chunks: 0: IHDR-PLTE, 1: PLTE-IDAT, 2: IDAT-IEND Do not allocate or traverse this data yourself. Use the chunk traversing functions declared later, such as lodepng_chunk_next and lodepng_chunk_append, to read/write this struct. */ unsigned char* unknown_chunks_data[3]; size_t unknown_chunks_size[3]; /*size in bytes of the unknown chunks, given for protection*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGInfo; /*init, cleanup and copy functions to use with this struct*/ void lodepng_info_init(LodePNGInfo* info); void lodepng_info_cleanup(LodePNGInfo* info); /*return value is error code (0 means no error)*/ unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source); #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS void lodepng_clear_text(LodePNGInfo* info); /*use this to clear the texts again after you filled them in*/ unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str); /*push back both texts at once*/ void lodepng_clear_itext(LodePNGInfo* info); /*use this to clear the itexts again after you filled them in*/ unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, const char* transkey, const char* str); /*push back the 4 texts of 1 chunk at once*/ #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ /* Converts raw buffer from one color type to another color type, based on LodePNGColorMode structs to describe the input and output color type. See the reference manual at the end of this header file to see which color conversions are supported. return value = LodePNG error code (0 if all went ok, an error if the conversion isn't supported) The out buffer must have size (w * h * bpp + 7) / 8, where bpp is the bits per pixel of the output color type (lodepng_get_bpp) The fix_png value works as described in struct LodePNGDecoderSettings. Note: for 16-bit per channel colors, uses big endian format like PNG does. */ unsigned lodepng_convert(unsigned char* out, const unsigned char* in, LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, unsigned w, unsigned h, unsigned fix_png); #ifdef LODEPNG_COMPILE_DECODER /* Settings for the decoder. This contains settings for the PNG and the Zlib decoder, but not the Info settings from the Info structs. */ typedef struct LodePNGDecoderSettings { LodePNGDecompressSettings zlibsettings; /*in here is the setting to ignore Adler32 checksums*/ unsigned ignore_crc; /*ignore CRC checksums*/ /* The fix_png setting, if 1, makes the decoder tolerant towards some PNG images that do not correctly follow the PNG specification. This only supports errors that are fixable, were found in images that are actually used on the web, and are silently tolerated by other decoders as well. Currently only one such fix is implemented: if a palette index is out of bounds given the palette size, interpret it as opaque black. By default this value is 0, which makes it stop with an error on such images. */ unsigned fix_png; unsigned color_convert; /*whether to convert the PNG to the color type you want. Default: yes*/ #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS unsigned read_text_chunks; /*if false but remember_unknown_chunks is true, they're stored in the unknown chunks*/ /*store all bytes from unknown chunks in the LodePNGInfo (off by default, useful for a png editor)*/ unsigned remember_unknown_chunks; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGDecoderSettings; void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /*automatically use color type with less bits per pixel if losslessly possible. Default: AUTO*/ typedef enum LodePNGFilterStrategy { /*every filter at zero*/ LFS_ZERO, /*Use filter that gives minumum sum, as described in the official PNG filter heuristic.*/ LFS_MINSUM, /*Use the filter type that gives smallest Shannon entropy for this scanline. Depending on the image, this is better or worse than minsum.*/ LFS_ENTROPY, /* Brute-force-search PNG filters by compressing each filter for each scanline. Experimental, very slow, and only rarely gives better compression than MINSUM. */ LFS_BRUTE_FORCE, /*use predefined_filters buffer: you specify the filter type for each scanline*/ LFS_PREDEFINED } LodePNGFilterStrategy; /*automatically use color type with less bits per pixel if losslessly possible. Default: LAC_AUTO*/ typedef enum LodePNGAutoConvert { LAC_NO, /*use color type user requested*/ LAC_ALPHA, /*use color type user requested, but if only opaque pixels and RGBA or grey+alpha, use RGB or grey*/ LAC_AUTO, /*use PNG color type that can losslessly represent the uncompressed image the smallest possible*/ /* like AUTO, but do not choose 1, 2 or 4 bit per pixel types. sometimes a PNG image compresses worse if less than 8 bits per pixels. */ LAC_AUTO_NO_NIBBLES, /* like AUTO, but never choose palette color type. For small images, encoding the palette may take more bytes than what is gained. Note that AUTO also already prevents encoding the palette for extremely small images, but that may not be sufficient because due to the compression it cannot predict when to switch. */ LAC_AUTO_NO_PALETTE, LAC_AUTO_NO_NIBBLES_NO_PALETTE } LodePNGAutoConvert; /* Automatically chooses color type that gives smallest amount of bits in the output image, e.g. grey if there are only greyscale pixels, palette if there are less than 256 colors, ... The auto_convert parameter allows limiting it to not use palette, ... */ unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, const unsigned char* image, unsigned w, unsigned h, const LodePNGColorMode* mode_in, LodePNGAutoConvert auto_convert); /*Settings for the encoder.*/ typedef struct LodePNGEncoderSettings { LodePNGCompressSettings zlibsettings; /*settings for the zlib encoder, such as window size, ...*/ LodePNGAutoConvert auto_convert; /*how to automatically choose output PNG color type, if at all*/ /*If true, follows the official PNG heuristic: if the PNG uses a palette or lower than 8 bit depth, set all filters to zero. Otherwise use the filter_strategy. Note that to completely follow the official PNG heuristic, filter_palette_zero must be true and filter_strategy must be LFS_MINSUM*/ unsigned filter_palette_zero; /*Which filter strategy to use when not using zeroes due to filter_palette_zero. Set filter_palette_zero to 0 to ensure always using your chosen strategy. Default: LFS_MINSUM*/ LodePNGFilterStrategy filter_strategy; /*used if filter_strategy is LFS_PREDEFINED. In that case, this must point to a buffer with the same length as the amount of scanlines in the image, and each value must <= 5. You have to cleanup this buffer, LodePNG will never free it. Don't forget that filter_palette_zero must be set to 0 to ensure this is also used on palette or low bitdepth images.*/ const unsigned char* predefined_filters; /*force creating a PLTE chunk if colortype is 2 or 6 (= a suggested palette). If colortype is 3, PLTE is _always_ created.*/ unsigned force_palette; #ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS /*add LodePNG identifier and version as a text chunk, for debugging*/ unsigned add_id; /*encode text chunks as zTXt chunks instead of tEXt chunks, and use compression in iTXt chunks*/ unsigned text_compression; #endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ } LodePNGEncoderSettings; void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) /*The settings, state and information for extended encoding and decoding.*/ typedef struct LodePNGState { #ifdef LODEPNG_COMPILE_DECODER LodePNGDecoderSettings decoder; /*the decoding settings*/ #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER LodePNGEncoderSettings encoder; /*the encoding settings*/ #endif /*LODEPNG_COMPILE_ENCODER*/ LodePNGColorMode info_raw; /*specifies the format in which you would like to get the raw pixel buffer*/ LodePNGInfo info_png; /*info of the PNG image obtained after decoding*/ unsigned error; #ifdef LODEPNG_COMPILE_CPP //For the lodepng::State subclass. virtual ~LodePNGState() { } #endif } LodePNGState; /*init, cleanup and copy functions to use with this struct*/ void lodepng_state_init(LodePNGState* state); void lodepng_state_cleanup(LodePNGState* state); void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source); #endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ #ifdef LODEPNG_COMPILE_DECODER /* Same as lodepng_decode_memory, but uses a LodePNGState to allow custom settings and getting much more information about the PNG image and color mode. */ unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize); /* Read the PNG header, but not the actual data. This returns only the information that is in the header chunk of the PNG, such as width, height and color type. The information is placed in the info_png field of the LodePNGState. */ unsigned lodepng_inspect(unsigned* w, unsigned* h, LodePNGState* state, const unsigned char* in, size_t insize); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /*This function allocates the out buffer with standard malloc and stores the size in *outsize.*/ unsigned lodepng_encode(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h, LodePNGState* state); #endif /*LODEPNG_COMPILE_ENCODER*/ /* The lodepng_chunk functions are normally not needed, except to traverse the unknown chunks stored in the LodePNGInfo struct, or add new ones to it. It also allows traversing the chunks of an encoded PNG file yourself. PNG standard chunk naming conventions: First byte: uppercase = critical, lowercase = ancillary Second byte: uppercase = public, lowercase = private Third byte: must be uppercase Fourth byte: uppercase = unsafe to copy, lowercase = safe to copy */ /*get the length of the data of the chunk. Total chunk length has 12 bytes more.*/ unsigned lodepng_chunk_length(const unsigned char* chunk); /*puts the 4-byte type in null terminated string*/ void lodepng_chunk_type(char type[5], const unsigned char* chunk); /*check if the type is the given type*/ unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type); /*0: it's one of the critical chunk types, 1: it's an ancillary chunk (see PNG standard)*/ unsigned char lodepng_chunk_ancillary(const unsigned char* chunk); /*0: public, 1: private (see PNG standard)*/ unsigned char lodepng_chunk_private(const unsigned char* chunk); /*0: the chunk is unsafe to copy, 1: the chunk is safe to copy (see PNG standard)*/ unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk); /*get pointer to the data of the chunk, where the input points to the header of the chunk*/ unsigned char* lodepng_chunk_data(unsigned char* chunk); const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk); /*returns 0 if the crc is correct, 1 if it's incorrect (0 for OK as usual!)*/ unsigned lodepng_chunk_check_crc(const unsigned char* chunk); /*generates the correct CRC from the data and puts it in the last 4 bytes of the chunk*/ void lodepng_chunk_generate_crc(unsigned char* chunk); /*iterate to next chunks. don't use on IEND chunk, as there is no next chunk then*/ unsigned char* lodepng_chunk_next(unsigned char* chunk); const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk); /* Appends chunk to the data in out. The given chunk should already have its chunk header. The out variable and outlength are updated to reflect the new reallocated buffer. Returns error code (0 if it went ok) */ unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk); /* Appends new chunk to out. The chunk to append is given by giving its length, type and data separately. The type is a 4-letter string. The out variable and outlength are updated to reflect the new reallocated buffer. Returne error code (0 if it went ok) */ unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data); /*Calculate CRC32 of buffer*/ unsigned lodepng_crc32(const unsigned char* buf, size_t len); #endif /*LODEPNG_COMPILE_PNG*/ #ifdef LODEPNG_COMPILE_ZLIB /* This zlib part can be used independently to zlib compress and decompress a buffer. It cannot be used to create gzip files however, and it only supports the part of zlib that is required for PNG, it does not support dictionaries. */ #ifdef LODEPNG_COMPILE_DECODER /*Inflate a buffer. Inflate is the decompression step of deflate. Out buffer must be freed after use.*/ unsigned lodepng_inflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings); /* Decompresses Zlib data. Reallocates the out buffer and appends the data. The data must be according to the zlib specification. Either, *out must be NULL and *outsize must be 0, or, *out must be a valid buffer and *outsize its size in bytes. out must be freed by user after usage. */ unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGDecompressSettings* settings); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER /* Compresses data with Zlib. Reallocates the out buffer and appends the data. Zlib adds a small header and trailer around the deflate data. The data is output in the format of the zlib specification. Either, *out must be NULL and *outsize must be 0, or, *out must be a valid buffer and *outsize its size in bytes. out must be freed by user after usage. */ unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings); /* Find length-limited Huffman code for given frequencies. This function is in the public interface only for tests, it's used internally by lodepng_deflate. */ unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, size_t numcodes, unsigned maxbitlen); /*Compress a buffer with deflate. See RFC 1951. Out buffer must be freed after use.*/ unsigned lodepng_deflate(unsigned char** out, size_t* outsize, const unsigned char* in, size_t insize, const LodePNGCompressSettings* settings); #endif /*LODEPNG_COMPILE_ENCODER*/ #endif /*LODEPNG_COMPILE_ZLIB*/ #ifdef LODEPNG_COMPILE_DISK /* Load a file from disk into buffer. The function allocates the out buffer, and after usage you should free it. out: output parameter, contains pointer to loaded buffer. outsize: output parameter, size of the allocated out buffer filename: the path to the file to load return value: error code (0 means ok) */ unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename); /* Save a file from buffer to disk. Warning, if it exists, this function overwrites the file without warning! buffer: the buffer to write buffersize: size of the buffer to write filename: the path to the file to save to return value: error code (0 means ok) */ unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename); #endif /*LODEPNG_COMPILE_DISK*/ #ifdef LODEPNG_COMPILE_CPP //The LodePNG C++ wrapper uses std::vectors instead of manually allocated memory buffers. namespace lodepng { #ifdef LODEPNG_COMPILE_PNG class State: public LodePNGState { public: State(); State(const State& other); virtual ~State(); State& operator=(const State& other); }; #ifdef LODEPNG_COMPILE_DECODER //Same as other lodepng::decode, but using a State for more settings and information. unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const unsigned char* in, size_t insize); unsigned decode(std::vector& out, unsigned& w, unsigned& h, State& state, const std::vector& in); #endif /*LODEPNG_COMPILE_DECODER*/ #ifdef LODEPNG_COMPILE_ENCODER //Same as other lodepng::encode, but using a State for more settings and information. unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, State& state); unsigned encode(std::vector& out, const std::vector& in, unsigned w, unsigned h, State& state); #endif /*LODEPNG_COMPILE_ENCODER*/ #ifdef LODEPNG_COMPILE_DISK /* Load a file from disk into an std::vector. If the vector is empty, then either the file doesn't exist or is an empty file. */ void load_file(std::vector& buffer, const std::string& filename); /* Save the binary data in an std::vector to a file on disk. The file is overwritten without warning. */ void save_file(const std::vector& buffer, const std::string& filename); #endif //LODEPNG_COMPILE_DISK #endif //LODEPNG_COMPILE_PNG #ifdef LODEPNG_COMPILE_ZLIB #ifdef LODEPNG_COMPILE_DECODER //Zlib-decompress an unsigned char buffer unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); //Zlib-decompress an std::vector unsigned decompress(std::vector& out, const std::vector& in, const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); #endif //LODEPNG_COMPILE_DECODER #ifdef LODEPNG_COMPILE_ENCODER //Zlib-compress an unsigned char buffer unsigned compress(std::vector& out, const unsigned char* in, size_t insize, const LodePNGCompressSettings& settings = lodepng_default_compress_settings); //Zlib-compress an std::vector unsigned compress(std::vector& out, const std::vector& in, const LodePNGCompressSettings& settings = lodepng_default_compress_settings); #endif //LODEPNG_COMPILE_ENCODER #endif //LODEPNG_COMPILE_ZLIB } //namespace lodepng #endif /*LODEPNG_COMPILE_CPP*/ /* TODO: [.] test if there are no memory leaks or security exploits - done a lot but needs to be checked often [.] check compatibility with vareous compilers - done but needs to be redone for every newer version [X] converting color to 16-bit per channel types [ ] read all public PNG chunk types (but never let the color profile and gamma ones touch RGB values) [ ] make sure encoder generates no chunks with size > (2^31)-1 [ ] partial decoding (stream processing) [X] let the "isFullyOpaque" function check color keys and transparent palettes too [X] better name for the variables "codes", "codesD", "codelengthcodes", "clcl" and "lldl" [ ] don't stop decoding on errors like 69, 57, 58 (make warnings) [ ] make option to choose if the raw image with non multiple of 8 bits per scanline should have padding bits or not [ ] let the C++ wrapper catch exceptions coming from the standard library and return LodePNG error codes */ #endif /*LODEPNG_H inclusion guard*/ /* LodePNG Documentation --------------------- 0. table of contents -------------------- 1. about 1.1. supported features 1.2. features not supported 2. C and C++ version 3. security 4. decoding 5. encoding 6. color conversions 6.1. PNG color types 6.2. color conversions 6.3. padding bits 6.4. A note about 16-bits per channel and endianness 7. error values 8. chunks and PNG editing 9. compiler support 10. examples 10.1. decoder C++ example 10.2. decoder C example 11. changes 12. contact information 1. about -------- PNG is a file format to store raster images losslessly with good compression, supporting different color types and alpha channel. LodePNG is a PNG codec according to the Portable Network Graphics (PNG) Specification (Second Edition) - W3C Recommendation 10 November 2003. The specifications used are: *) Portable Network Graphics (PNG) Specification (Second Edition): http://www.w3.org/TR/2003/REC-PNG-20031110 *) RFC 1950 ZLIB Compressed Data Format version 3.3: http://www.gzip.org/zlib/rfc-zlib.html *) RFC 1951 DEFLATE Compressed Data Format Specification ver 1.3: http://www.gzip.org/zlib/rfc-deflate.html The most recent version of LodePNG can currently be found at http://lodev.org/lodepng/ LodePNG works both in C (ISO C90) and C++, with a C++ wrapper that adds extra functionality. LodePNG exists out of two files: -lodepng.h: the header file for both C and C++ -lodepng.c(pp): give it the name lodepng.c or lodepng.cpp (or .cc) depending on your usage If you want to start using LodePNG right away without reading this doc, get the examples from the LodePNG website to see how to use it in code, or check the smaller examples in chapter 13 here. LodePNG is simple but only supports the basic requirements. To achieve simplicity, the following design choices were made: There are no dependencies on any external library. There are functions to decode and encode a PNG with a single function call, and extended versions of these functions taking a LodePNGState struct allowing to specify or get more information. By default the colors of the raw image are always RGB or RGBA, no matter what color type the PNG file uses. To read and write files, there are simple functions to convert the files to/from buffers in memory. This all makes LodePNG suitable for loading textures in games, demos and small programs, ... It's less suitable for full fledged image editors, loading PNGs over network (it requires all the image data to be available before decoding can begin), life-critical systems, ... 1.1. supported features ----------------------- The following features are supported by the decoder: *) decoding of PNGs with any color type, bit depth and interlace mode, to a 24- or 32-bit color raw image, or the same color type as the PNG *) encoding of PNGs, from any raw image to 24- or 32-bit color, or the same color type as the raw image *) Adam7 interlace and deinterlace for any color type *) loading the image from harddisk or decoding it from a buffer from other sources than harddisk *) support for alpha channels, including RGBA color model, translucent palettes and color keying *) zlib decompression (inflate) *) zlib compression (deflate) *) CRC32 and ADLER32 checksums *) handling of unknown chunks, allowing making a PNG editor that stores custom and unknown chunks. *) the following chunks are supported (generated/interpreted) by both encoder and decoder: IHDR: header information PLTE: color palette IDAT: pixel data IEND: the final chunk tRNS: transparency for palettized images tEXt: textual information zTXt: compressed textual information iTXt: international textual information bKGD: suggested background color pHYs: physical dimensions tIME: modification time 1.2. features not supported --------------------------- The following features are _not_ supported: *) some features needed to make a conformant PNG-Editor might be still missing. *) partial loading/stream processing. All data must be available and is processed in one call. *) The following public chunks are not supported but treated as unknown chunks by LodePNG cHRM, gAMA, iCCP, sRGB, sBIT, hIST, sPLT Some of these are not supported on purpose: LodePNG wants to provide the RGB values stored in the pixels, not values modified by system dependent gamma or color models. 2. C and C++ version -------------------- The C version uses buffers allocated with alloc that you need to free() yourself. You need to use init and cleanup functions for each struct whenever using a struct from the C version to avoid exploits and memory leaks. The C++ version has extra functions with std::vectors in the interface and the lodepng::State class which is a LodePNGState with constructor and destructor. These files work without modification for both C and C++ compilers because all the additional C++ code is in "#ifdef __cplusplus" blocks that make C-compilers ignore it, and the C code is made to compile both with strict ISO C90 and C++. To use the C++ version, you need to rename the source file to lodepng.cpp (instead of lodepng.c), and compile it with a C++ compiler. To use the C version, you need to rename the source file to lodepng.c (instead of lodepng.cpp), and compile it with a C compiler. 3. Security ----------- Even if carefully designed, it's always possible that LodePNG contains possible exploits. If you discover one, please let me know, and it will be fixed. When using LodePNG, care has to be taken with the C version of LodePNG, as well as the C-style structs when working with C++. The following conventions are used for all C-style structs: -if a struct has a corresponding init function, always call the init function when making a new one -if a struct has a corresponding cleanup function, call it before the struct disappears to avoid memory leaks -if a struct has a corresponding copy function, use the copy function instead of "=". The destination must also be inited already. 4. Decoding ----------- Decoding converts a PNG compressed image to a raw pixel buffer. Most documentation on using the decoder is at its declarations in the header above. For C, simple decoding can be done with functions such as lodepng_decode32, and more advanced decoding can be done with the struct LodePNGState and lodepng_decode. For C++, all decoding can be done with the various lodepng::decode functions, and lodepng::State can be used for advanced features. When using the LodePNGState, it uses the following fields for decoding: *) LodePNGInfo info_png: it stores extra information about the PNG (the input) in here *) LodePNGColorMode info_raw: here you can say what color mode of the raw image (the output) you want to get *) LodePNGDecoderSettings decoder: you can specify a few extra settings for the decoder to use LodePNGInfo info_png -------------------- After decoding, this contains extra information of the PNG image, except the actual pixels, width and height because these are already gotten directly from the decoder functions. It contains for example the original color type of the PNG image, text comments, suggested background color, etc... More details about the LodePNGInfo struct are at its declaration documentation. LodePNGColorMode info_raw ------------------------- When decoding, here you can specify which color type you want the resulting raw image to be. If this is different from the colortype of the PNG, then the decoder will automatically convert the result. This conversion always works, except if you want it to convert a color PNG to greyscale or to a palette with missing colors. By default, 32-bit color is used for the result. LodePNGDecoderSettings decoder ------------------------------ The settings can be used to ignore the errors created by invalid CRC and Adler32 chunks, and to disable the decoding of tEXt chunks. There's also a setting color_convert, true by default. If false, no conversion is done, the resulting data will be as it was in the PNG (after decompression) and you'll have to puzzle the colors of the pixels together yourself using the color type information in the LodePNGInfo. 5. Encoding ----------- Encoding converts a raw pixel buffer to a PNG compressed image. Most documentation on using the encoder is at its declarations in the header above. For C, simple encoding can be done with functions such as lodepng_encode32, and more advanced decoding can be done with the struct LodePNGState and lodepng_encode. For C++, all encoding can be done with the various lodepng::encode functions, and lodepng::State can be used for advanced features. Like the decoder, the encoder can also give errors. However it gives less errors since the encoder input is trusted, the decoder input (a PNG image that could be forged by anyone) is not trusted. When using the LodePNGState, it uses the following fields for encoding: *) LodePNGInfo info_png: here you specify how you want the PNG (the output) to be. *) LodePNGColorMode info_raw: here you say what color type of the raw image (the input) has *) LodePNGEncoderSettings encoder: you can specify a few settings for the encoder to use LodePNGInfo info_png -------------------- When encoding, you use this the opposite way as when decoding: for encoding, you fill in the values you want the PNG to have before encoding. By default it's not needed to specify a color type for the PNG since it's automatically chosen, but it's possible to choose it yourself given the right settings. The encoder will not always exactly match the LodePNGInfo struct you give, it tries as close as possible. Some things are ignored by the encoder. The encoder uses, for example, the following settings from it when applicable: colortype and bitdepth, text chunks, time chunk, the color key, the palette, the background color, the interlace method, unknown chunks, ... When encoding to a PNG with colortype 3, the encoder will generate a PLTE chunk. If the palette contains any colors for which the alpha channel is not 255 (so there are translucent colors in the palette), it'll add a tRNS chunk. LodePNGColorMode info_raw ------------------------- You specify the color type of the raw image that you give to the input here, including a possible transparent color key and palette you happen to be using in your raw image data. By default, 32-bit color is assumed, meaning your input has to be in RGBA format with 4 bytes (unsigned chars) per pixel. LodePNGEncoderSettings encoder ------------------------------ The following settings are supported (some are in sub-structs): *) auto_convert: when this option is enabled, the encoder will automatically choose the smallest possible color mode (including color key) that can encode the colors of all pixels without information loss. *) btype: the block type for LZ77. 0 = uncompressed, 1 = fixed huffman tree, 2 = dynamic huffman tree (best compression). Should be 2 for proper compression. *) use_lz77: whether or not to use LZ77 for compressed block types. Should be true for proper compression. *) windowsize: the window size used by the LZ77 encoder (1 - 32768). Has value 2048 by default, but can be set to 32768 for better, but slow, compression. *) force_palette: if colortype is 2 or 6, you can make the encoder write a PLTE chunk if force_palette is true. This can used as suggested palette to convert to by viewers that don't support more than 256 colors (if those still exist) *) add_id: add text chunk "Encoder: LodePNG " to the image. *) text_compression: default 1. If 1, it'll store texts as zTXt instead of tEXt chunks. zTXt chunks use zlib compression on the text. This gives a smaller result on large texts but a larger result on small texts (such as a single program name). It's all tEXt or all zTXt though, there's no separate setting per text yet. 6. color conversions -------------------- An important thing to note about LodePNG, is that the color type of the PNG, and the color type of the raw image, are completely independent. By default, when you decode a PNG, you get the result as a raw image in the color type you want, no matter whether the PNG was encoded with a palette, greyscale or RGBA color. And if you encode an image, by default LodePNG will automatically choose the PNG color type that gives good compression based on the values of colors and amount of colors in the image. It can be configured to let you control it instead as well, though. To be able to do this, LodePNG does conversions from one color mode to another. It can convert from almost any color type to any other color type, except the following conversions: RGB to greyscale is not supported, and converting to a palette when the palette doesn't have a required color is not supported. This is not supported on purpose: this is information loss which requires a color reduction algorithm that is beyong the scope of a PNG encoder (yes, RGB to grey is easy, but there are multiple ways if you want to give some channels more weight). By default, when decoding, you get the raw image in 32-bit RGBA or 24-bit RGB color, no matter what color type the PNG has. And by default when encoding, LodePNG automatically picks the best color model for the output PNG, and expects the input image to be 32-bit RGBA or 24-bit RGB. So, unless you want to control the color format of the images yourself, you can skip this chapter. 6.1. PNG color types -------------------- A PNG image can have many color types, ranging from 1-bit color to 64-bit color, as well as palettized color modes. After the zlib decompression and unfiltering in the PNG image is done, the raw pixel data will have that color type and thus a certain amount of bits per pixel. If you want the output raw image after decoding to have another color type, a conversion is done by LodePNG. The PNG specification gives the following color types: 0: greyscale, bit depths 1, 2, 4, 8, 16 2: RGB, bit depths 8 and 16 3: palette, bit depths 1, 2, 4 and 8 4: greyscale with alpha, bit depths 8 and 16 6: RGBA, bit depths 8 and 16 Bit depth is the amount of bits per pixel per color channel. So the total amount of bits per pixel is: amount of channels * bitdepth. 6.2. color conversions ---------------------- As explained in the sections about the encoder and decoder, you can specify color types and bit depths in info_png and info_raw to change the default behaviour. If, when decoding, you want the raw image to be something else than the default, you need to set the color type and bit depth you want in the LodePNGColorMode, or the parameters of the simple function of LodePNG you're using. If, when encoding, you use another color type than the default in the input image, you need to specify its color type and bit depth in the LodePNGColorMode of the raw image, or use the parameters of the simplefunction of LodePNG you're using. If, when encoding, you don't want LodePNG to choose the output PNG color type but control it yourself, you need to set auto_convert in the encoder settings to LAC_NONE, and specify the color type you want in the LodePNGInfo of the encoder. If you do any of the above, LodePNG may need to do a color conversion, which follows the rules below, and may sometimes not be allowed. To avoid some confusion: -the decoder converts from PNG to raw image -the encoder converts from raw image to PNG -the colortype and bitdepth in LodePNGColorMode info_raw, are those of the raw image -the colortype and bitdepth in the color field of LodePNGInfo info_png, are those of the PNG -when encoding, the color type in LodePNGInfo is ignored if auto_convert is enabled, it is automatically generated instead -when decoding, the color type in LodePNGInfo is set by the decoder to that of the original PNG image, but it can be ignored since the raw image has the color type you requested instead -if the color type of the LodePNGColorMode and PNG image aren't the same, a conversion between the color types is done if the color types are supported. If it is not supported, an error is returned. If the types are the same, no conversion is done. -even though some conversions aren't supported, LodePNG supports loading PNGs from any colortype and saving PNGs to any colortype, sometimes it just requires preparing the raw image correctly before encoding. -both encoder and decoder use the same color converter. Non supported color conversions: -color to greyscale: no error is thrown, but the result will look ugly because only the red channel is taken -anything, to palette when that palette does not have that color in it: in this case an error is thrown Supported color conversions: -anything to 8-bit RGB, 8-bit RGBA, 16-bit RGB, 16-bit RGBA -any grey or grey+alpha, to grey or grey+alpha -anything to a palette, as long as the palette has the requested colors in it -removing alpha channel -higher to smaller bitdepth, and vice versa If you want no color conversion to be done: -In the encoder, you can make it save a PNG with any color type by giving the raw color mode and LodePNGInfo the same color mode, and setting auto_convert to LAC_NO. -In the decoder, you can make it store the pixel data in the same color type as the PNG has, by setting the color_convert setting to false. Settings in info_raw are then ignored. The function lodepng_convert does the color conversion. It is available in the interface but normally isn't needed since the encoder and decoder already call it. 6.3. padding bits ----------------- In the PNG file format, if a less than 8-bit per pixel color type is used and the scanlines have a bit amount that isn't a multiple of 8, then padding bits are used so that each scanline starts at a fresh byte. But that is NOT true for the LodePNG raw input and output. The raw input image you give to the encoder, and the raw output image you get from the decoder will NOT have these padding bits, e.g. in the case of a 1-bit image with a width of 7 pixels, the first pixel of the second scanline will the the 8th bit of the first byte, not the first bit of a new byte. 6.4. A note about 16-bits per channel and endianness ---------------------------------------------------- LodePNG uses unsigned char arrays for 16-bit per channel colors too, just like for any other color format. The 16-bit values are stored in big endian (most significant byte first) in these arrays. This is the opposite order of the little endian used by x86 CPU's. LodePNG always uses big endian because the PNG file format does so internally. Conversions to other formats than PNG uses internally are not supported by LodePNG on purpose, there are myriads of formats, including endianness of 16-bit colors, the order in which you store R, G, B and A, and so on. Supporting and converting to/from all that is outside the scope of LodePNG. This may mean that, depending on your use case, you may want to convert the big endian output of LodePNG to little endian with a for loop. This is certainly not always needed, many applications and libraries support big endian 16-bit colors anyway, but it means you cannot simply cast the unsigned char* buffer to an unsigned short* buffer on x86 CPUs. 7. error values --------------- All functions in LodePNG that return an error code, return 0 if everything went OK, or a non-zero code if there was an error. The meaning of the LodePNG error values can be retrieved with the function lodepng_error_text: given the numerical error code, it returns a description of the error in English as a string. Check the implementation of lodepng_error_text to see the meaning of each code. 8. chunks and PNG editing ------------------------- If you want to add extra chunks to a PNG you encode, or use LodePNG for a PNG editor that should follow the rules about handling of unknown chunks, or if your program is able to read other types of chunks than the ones handled by LodePNG, then that's possible with the chunk functions of LodePNG. A PNG chunk has the following layout: 4 bytes length 4 bytes type name length bytes data 4 bytes CRC 8.1. iterating through chunks ----------------------------- If you have a buffer containing the PNG image data, then the first chunk (the IHDR chunk) starts at byte number 8 of that buffer. The first 8 bytes are the signature of the PNG and are not part of a chunk. But if you start at byte 8 then you have a chunk, and can check the following things of it. NOTE: none of these functions check for memory buffer boundaries. To avoid exploits, always make sure the buffer contains all the data of the chunks. When using lodepng_chunk_next, make sure the returned value is within the allocated memory. unsigned lodepng_chunk_length(const unsigned char* chunk): Get the length of the chunk's data. The total chunk length is this length + 12. void lodepng_chunk_type(char type[5], const unsigned char* chunk): unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type): Get the type of the chunk or compare if it's a certain type unsigned char lodepng_chunk_critical(const unsigned char* chunk): unsigned char lodepng_chunk_private(const unsigned char* chunk): unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk): Check if the chunk is critical in the PNG standard (only IHDR, PLTE, IDAT and IEND are). Check if the chunk is private (public chunks are part of the standard, private ones not). Check if the chunk is safe to copy. If it's not, then, when modifying data in a critical chunk, unsafe to copy chunks of the old image may NOT be saved in the new one if your program doesn't handle that type of unknown chunk. unsigned char* lodepng_chunk_data(unsigned char* chunk): const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk): Get a pointer to the start of the data of the chunk. unsigned lodepng_chunk_check_crc(const unsigned char* chunk): void lodepng_chunk_generate_crc(unsigned char* chunk): Check if the crc is correct or generate a correct one. unsigned char* lodepng_chunk_next(unsigned char* chunk): const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk): Iterate to the next chunk. This works if you have a buffer with consecutive chunks. Note that these functions do no boundary checking of the allocated data whatsoever, so make sure there is enough data available in the buffer to be able to go to the next chunk. unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk): unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, const char* type, const unsigned char* data): These functions are used to create new chunks that are appended to the data in *out that has length *outlength. The append function appends an existing chunk to the new data. The create function creates a new chunk with the given parameters and appends it. Type is the 4-letter name of the chunk. 8.2. chunks in info_png ----------------------- The LodePNGInfo struct contains fields with the unknown chunk in it. It has 3 buffers (each with size) to contain 3 types of unknown chunks: the ones that come before the PLTE chunk, the ones that come between the PLTE and the IDAT chunks, and the ones that come after the IDAT chunks. It's necessary to make the distionction between these 3 cases because the PNG standard forces to keep the ordering of unknown chunks compared to the critical chunks, but does not force any other ordering rules. info_png.unknown_chunks_data[0] is the chunks before PLTE info_png.unknown_chunks_data[1] is the chunks after PLTE, before IDAT info_png.unknown_chunks_data[2] is the chunks after IDAT The chunks in these 3 buffers can be iterated through and read by using the same way described in the previous subchapter. When using the decoder to decode a PNG, you can make it store all unknown chunks if you set the option settings.remember_unknown_chunks to 1. By default, this option is off (0). The encoder will always encode unknown chunks that are stored in the info_png. If you need it to add a particular chunk that isn't known by LodePNG, you can use lodepng_chunk_append or lodepng_chunk_create to the chunk data in info_png.unknown_chunks_data[x]. Chunks that are known by LodePNG should not be added in that way. E.g. to make LodePNG add a bKGD chunk, set background_defined to true and add the correct parameters there instead. 9. compiler support ------------------- No libraries other than the current standard C library are needed to compile LodePNG. For the C++ version, only the standard C++ library is needed on top. Add the files lodepng.c(pp) and lodepng.h to your project, include lodepng.h where needed, and your program can read/write PNG files. It is compatible with C90 and up, and C++03 and up. If performance is important, use optimization when compiling! For both the encoder and decoder, this makes a large difference. Make sure that LodePNG is compiled with the same compiler of the same version and with the same settings as the rest of the program, or the interfaces with std::vectors and std::strings in C++ can be incompatible. CHAR_BITS must be 8 or higher, because LodePNG uses unsigned chars for octets. *) gcc and g++ LodePNG is developed in gcc so this compiler is natively supported. It gives no warnings with compiler options "-Wall -Wextra -pedantic -ansi", with gcc and g++ version 4.7.1 on Linux, 32-bit and 64-bit. *) Clang Fully supported and warning-free. *) Mingw The Mingw compiler (a port of gcc for Windows) should be fully supported by LodePNG. *) Visual Studio and Visual C++ Express Edition LodePNG should be warning-free with warning level W4. Two warnings were disabled with pragmas though: warning 4244 about implicit conversions, and warning 4996 where it wants to use a non-standard function fopen_s instead of the standard C fopen. Visual Studio may want "stdafx.h" files to be included in each source file and give an error "unexpected end of file while looking for precompiled header". This is not standard C++ and will not be added to the stock LodePNG. You can disable it for lodepng.cpp only by right clicking it, Properties, C/C++, Precompiled Headers, and set it to Not Using Precompiled Headers there. NOTE: Modern versions of VS should be fully supported, but old versions, e.g. VS6, are not guaranteed to work. *) Compilers on Macintosh LodePNG has been reported to work both with gcc and LLVM for Macintosh, both for C and C++. *) Other Compilers If you encounter problems on any compilers, feel free to let me know and I may try to fix it if the compiler is modern and standards complient. 10. examples ------------ This decoder example shows the most basic usage of LodePNG. More complex examples can be found on the LodePNG website. 10.1. decoder C++ example ------------------------- #include "lodepng.h" #include int main(int argc, char *argv[]) { const char* filename = argc > 1 ? argv[1] : "test.png"; //load and decode std::vector image; unsigned width, height; unsigned error = lodepng::decode(image, width, height, filename); //if there's an error, display it if(error) std::cout << "decoder error " << error << ": " << lodepng_error_text(error) << std::endl; //the pixels are now in the vector "image", 4 bytes per pixel, ordered RGBARGBA..., use it as texture, draw it, ... } 10.2. decoder C example ----------------------- #include "lodepng.h" int main(int argc, char *argv[]) { unsigned error; unsigned char* image; size_t width, height; const char* filename = argc > 1 ? argv[1] : "test.png"; error = lodepng_decode32_file(&image, &width, &height, filename); if(error) printf("decoder error %u: %s\n", error, lodepng_error_text(error)); / * use image here * / free(image); return 0; } 11. changes ----------- The version number of LodePNG is the date of the change given in the format yyyymmdd. Some changes aren't backwards compatible. Those are indicated with a (!) symbol. *) 09 jun 2014: Faster encoder by fixing hash bug and more zeros optimization. *) 22 dec 2013: Power of two windowsize required for optimization. *) 15 apr 2013: Fixed bug with LAC_ALPHA and color key. *) 25 mar 2013: Added an optional feature to ignore some PNG errors (fix_png). *) 11 mar 2013 (!): Bugfix with custom free. Changed from "my" to "lodepng_" prefix for the custom allocators and made it possible with a new #define to use custom ones in your project without needing to change lodepng's code. *) 28 jan 2013: Bugfix with color key. *) 27 okt 2012: Tweaks in text chunk keyword length error handling. *) 8 okt 2012 (!): Added new filter strategy (entropy) and new auto color mode. (no palette). Better deflate tree encoding. New compression tweak settings. Faster color conversions while decoding. Some internal cleanups. *) 23 sep 2012: Reduced warnings in Visual Studio a little bit. *) 1 sep 2012 (!): Removed #define's for giving custom (de)compression functions and made it work with function pointers instead. *) 23 jun 2012: Added more filter strategies. Made it easier to use custom alloc and free functions and toggle #defines from compiler flags. Small fixes. *) 6 may 2012 (!): Made plugging in custom zlib/deflate functions more flexible. *) 22 apr 2012 (!): Made interface more consistent, renaming a lot. Removed redundant C++ codec classes. Reduced amount of structs. Everything changed, but it is cleaner now imho and functionality remains the same. Also fixed several bugs and shrinked the implementation code. Made new samples. *) 6 nov 2011 (!): By default, the encoder now automatically chooses the best PNG color model and bit depth, based on the amount and type of colors of the raw image. For this, autoLeaveOutAlphaChannel replaced by auto_choose_color. *) 9 okt 2011: simpler hash chain implementation for the encoder. *) 8 sep 2011: lz77 encoder lazy matching instead of greedy matching. *) 23 aug 2011: tweaked the zlib compression parameters after benchmarking. A bug with the PNG filtertype heuristic was fixed, so that it chooses much better ones (it's quite significant). A setting to do an experimental, slow, brute force search for PNG filter types is added. *) 17 aug 2011 (!): changed some C zlib related function names. *) 16 aug 2011: made the code less wide (max 120 characters per line). *) 17 apr 2011: code cleanup. Bugfixes. Convert low to 16-bit per sample colors. *) 21 feb 2011: fixed compiling for C90. Fixed compiling with sections disabled. *) 11 dec 2010: encoding is made faster, based on suggestion by Peter Eastman to optimize long sequences of zeros. *) 13 nov 2010: added LodePNG_InfoColor_hasPaletteAlpha and LodePNG_InfoColor_canHaveAlpha functions for convenience. *) 7 nov 2010: added LodePNG_error_text function to get error code description. *) 30 okt 2010: made decoding slightly faster *) 26 okt 2010: (!) changed some C function and struct names (more consistent). Reorganized the documentation and the declaration order in the header. *) 08 aug 2010: only changed some comments and external samples. *) 05 jul 2010: fixed bug thanks to warnings in the new gcc version. *) 14 mar 2010: fixed bug where too much memory was allocated for char buffers. *) 02 sep 2008: fixed bug where it could create empty tree that linux apps could read by ignoring the problem but windows apps couldn't. *) 06 jun 2008: added more error checks for out of memory cases. *) 26 apr 2008: added a few more checks here and there to ensure more safety. *) 06 mar 2008: crash with encoding of strings fixed *) 02 feb 2008: support for international text chunks added (iTXt) *) 23 jan 2008: small cleanups, and #defines to divide code in sections *) 20 jan 2008: support for unknown chunks allowing using LodePNG for an editor. *) 18 jan 2008: support for tIME and pHYs chunks added to encoder and decoder. *) 17 jan 2008: ability to encode and decode compressed zTXt chunks added Also vareous fixes, such as in the deflate and the padding bits code. *) 13 jan 2008: Added ability to encode Adam7-interlaced images. Improved filtering code of encoder. *) 07 jan 2008: (!) changed LodePNG to use ISO C90 instead of C++. A C++ wrapper around this provides an interface almost identical to before. Having LodePNG be pure ISO C90 makes it more portable. The C and C++ code are together in these files but it works both for C and C++ compilers. *) 29 dec 2007: (!) changed most integer types to unsigned int + other tweaks *) 30 aug 2007: bug fixed which makes this Borland C++ compatible *) 09 aug 2007: some VS2005 warnings removed again *) 21 jul 2007: deflate code placed in new namespace separate from zlib code *) 08 jun 2007: fixed bug with 2- and 4-bit color, and small interlaced images *) 04 jun 2007: improved support for Visual Studio 2005: crash with accessing invalid std::vector element [0] fixed, and level 3 and 4 warnings removed *) 02 jun 2007: made the encoder add a tag with version by default *) 27 may 2007: zlib and png code separated (but still in the same file), simple encoder/decoder functions added for more simple usage cases *) 19 may 2007: minor fixes, some code cleaning, new error added (error 69), moved some examples from here to lodepng_examples.cpp *) 12 may 2007: palette decoding bug fixed *) 24 apr 2007: changed the license from BSD to the zlib license *) 11 mar 2007: very simple addition: ability to encode bKGD chunks. *) 04 mar 2007: (!) tEXt chunk related fixes, and support for encoding palettized PNG images. Plus little interface change with palette and texts. *) 03 mar 2007: Made it encode dynamic Huffman shorter with repeat codes. Fixed a bug where the end code of a block had length 0 in the Huffman tree. *) 26 feb 2007: Huffman compression with dynamic trees (BTYPE 2) now implemented and supported by the encoder, resulting in smaller PNGs at the output. *) 27 jan 2007: Made the Adler-32 test faster so that a timewaste is gone. *) 24 jan 2007: gave encoder an error interface. Added color conversion from any greyscale type to 8-bit greyscale with or without alpha. *) 21 jan 2007: (!) Totally changed the interface. It allows more color types to convert to and is more uniform. See the manual for how it works now. *) 07 jan 2007: Some cleanup & fixes, and a few changes over the last days: encode/decode custom tEXt chunks, separate classes for zlib & deflate, and at last made the decoder give errors for incorrect Adler32 or Crc. *) 01 jan 2007: Fixed bug with encoding PNGs with less than 8 bits per channel. *) 29 dec 2006: Added support for encoding images without alpha channel, and cleaned out code as well as making certain parts faster. *) 28 dec 2006: Added "Settings" to the encoder. *) 26 dec 2006: The encoder now does LZ77 encoding and produces much smaller files now. Removed some code duplication in the decoder. Fixed little bug in an example. *) 09 dec 2006: (!) Placed output parameters of public functions as first parameter. Fixed a bug of the decoder with 16-bit per color. *) 15 okt 2006: Changed documentation structure *) 09 okt 2006: Encoder class added. It encodes a valid PNG image from the given image buffer, however for now it's not compressed. *) 08 sep 2006: (!) Changed to interface with a Decoder class *) 30 jul 2006: (!) LodePNG_InfoPng , width and height are now retrieved in different way. Renamed decodePNG to decodePNGGeneric. *) 29 jul 2006: (!) Changed the interface: image info is now returned as a struct of type LodePNG::LodePNG_Info, instead of a vector, which was a bit clumsy. *) 28 jul 2006: Cleaned the code and added new error checks. Corrected terminology "deflate" into "inflate". *) 23 jun 2006: Added SDL example in the documentation in the header, this example allows easy debugging by displaying the PNG and its transparency. *) 22 jun 2006: (!) Changed way to obtain error value. Added loadFile function for convenience. Made decodePNG32 faster. *) 21 jun 2006: (!) Changed type of info vector to unsigned. Changed position of palette in info vector. Fixed an important bug that happened on PNGs with an uncompressed block. *) 16 jun 2006: Internally changed unsigned into unsigned where needed, and performed some optimizations. *) 07 jun 2006: (!) Renamed functions to decodePNG and placed them in LodePNG namespace. Changed the order of the parameters. Rewrote the documentation in the header. Renamed files to lodepng.cpp and lodepng.h *) 22 apr 2006: Optimized and improved some code *) 07 sep 2005: (!) Changed to std::vector interface *) 12 aug 2005: Initial release (C++, decoder only) 12. contact information ----------------------- Feel free to contact me with suggestions, problems, comments, ... concerning LodePNG. If you encounter a PNG image that doesn't work properly with this decoder, feel free to send it and I'll use it to find and fix the problem. My email address is (puzzle the account and domain together with an @ symbol): Domain: gmail dot com. Account: lode dot vandevenne. Copyright (c) 2005-2014 Lode Vandevenne */ ================================================ FILE: framework/tools/loaders/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) add_executable(slambench slambench_app.cpp) target_include_directories(slambench PUBLIC ${SLAMBENCH_INCLUDE_DIR} ${PROJECT_SOURCE_DIR}/shared/include) target_link_libraries(slambench PRIVATE pthread ${SLAMBENCH_LIBRARIES}) find_package(Pangolin QUIET) find_package(TOON QUIET) IF(Pangolin_FOUND) set(gui_pangolin_libraries slambench-ui-pangolin ${Pangolin_LIBRARIES} ${OPENGL_LIBRARIES} pthread) TARGET_INCLUDE_DIRECTORIES(slambench PUBLIC ${Pangolin_INCLUDE_DIR}) TARGET_INCLUDE_DIRECTORIES(slambench PUBLIC ${TOON_INCLUDE_PATHS}) target_link_libraries(slambench PRIVATE ${gui_pangolin_libraries}) add_definitions(-DWITH_GUI=1) ENDIF(Pangolin_FOUND) ================================================ FILE: framework/tools/loaders/benchmark_loader.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #include "../../shared/include/metrics/MemoryMetric.h" #include "ColumnWriter.h" #include std::string default_output_filename; std::string output_filename; std::string alignment_technique = "original"; std::string default_alignment_technique = "original"; TypedParameter file_output_parameter ("fo", "file-output", "File to write slamfile containing outputs", &output_filename, &default_output_filename); TypedParameter alignment_type_parameter("a", "alignment-technique", "Select an alignment technique by name, if not found, default used (default,new).", &alignment_technique, &default_alignment_technique); int main(int argc, char * argv[]) { try { SLAMBenchConfiguration * config = new SLAMBenchConfiguration(); //*************************************************************************************** // Start the argument processing //*************************************************************************************** config->addParameter(file_output_parameter); config->GetParameterManager().ReadArgumentsOrQuit(argc, argv); //*************************************************************************************** // At this point the datasets/libraries/sensors are loaded with their arguments set. //*************************************************************************************** //*************************************************************************************** // We initialise the configuration, means to retrieve groundtruth and set the alignement //*************************************************************************************** config->InitGroundtruth(false); // get GT trajectory auto gt_traj = config->GetGroundTruth().GetMainOutput(slambench::values::VT_POSE); slambench::outputs::TrajectoryAlignmentMethod *alignment_method; if(alignment_technique == "original") { alignment_method = new slambench::outputs::OriginalTrajectoryAlignmentMethod(); } else if(alignment_technique == "new") { alignment_method = new slambench::outputs::NewTrajectoryAlignmentMethod(); } else { std::cerr << "Unknown alignment method " << alignment_technique << std::endl; return 1; } //*************************************************************************************** // We prepare the logging and create the global metrics //*************************************************************************************** config->start_statistics(); slambench::ColumnWriter cw (config->get_log_stream(), "\t"); slambench::RowNumberColumn row_number; cw.AddColumn(&row_number); auto memory_metric = new slambench::metrics::MemoryMetric(); auto duration_metric = new slambench::metrics::DurationMetric(); auto power_metric = new slambench::metrics::PowerMetric(); //*************************************************************************************** // We init the algos now because we need their output already // TODO: if pose and map were by default we could init the algo much later, // thus move memory metric later //*************************************************************************************** config->InitAlgorithms(); bool have_timestamp = false; for(SLAMBenchLibraryHelper *lib : config->GetLoadedLibs()) { // retrieve the trajectory of the lib auto lib_traj = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); if (lib_traj == nullptr) { std::cerr << "There is no output trajectory in the library outputs." << std::endl; exit(1); } // Create timestamp column if we don't have one if(!have_timestamp) { have_timestamp = true; cw.AddColumn(new slambench::OutputTimestampColumnInterface(lib_traj)); } if (gt_traj) { // Create an aligned trajectory auto alignment = new slambench::outputs::AlignmentOutput("Alignment", new slambench::outputs::PoseOutputTrajectoryInterface(gt_traj), lib_traj, alignment_method); alignment->SetActive(true); alignment->SetKeepOnlyMostRecent(true); auto aligned = new slambench::outputs::AlignedPoseOutput(lib_traj->GetName() + " (Aligned)", alignment, lib_traj); // Add ATE metric auto ate_metric = new slambench::metrics::ATEMetric(new slambench::outputs::PoseOutputTrajectoryInterface(aligned), new slambench::outputs::PoseOutputTrajectoryInterface(gt_traj)); if (ate_metric->GetValueDescription().GetStructureDescription().size() > 0) { lib->GetMetricManager().AddFrameMetric(ate_metric); cw.AddColumn(new slambench::CollectionValueLibColumnInterface(lib, ate_metric, lib->GetMetricManager().GetFramePhase())); } // Add RPE metric auto rpe_metric = new slambench::metrics::RPEMetric(new slambench::outputs::PoseOutputTrajectoryInterface(aligned), new slambench::outputs::PoseOutputTrajectoryInterface(gt_traj)); lib->GetMetricManager().AddFrameMetric(rpe_metric); cw.AddColumn(new slambench::CollectionValueLibColumnInterface(lib, rpe_metric, lib->GetMetricManager().GetFramePhase())); } // Add a duration metric lib->GetMetricManager().AddFrameMetric(duration_metric); lib->GetMetricManager().AddPhaseMetric(duration_metric); cw.AddColumn(new slambench::ValueLibColumnInterface(lib, duration_metric, lib->GetMetricManager().GetFramePhase())); for(auto phase : lib->GetMetricManager().GetPhases()) { cw.AddColumn(new slambench::ValueLibColumnInterface(lib, duration_metric, phase)); } // Add a memory metric lib->GetMetricManager().AddFrameMetric(memory_metric); cw.AddColumn(new slambench::CollectionValueLibColumnInterface(lib, memory_metric, lib->GetMetricManager().GetFramePhase())); // Add a power metric if it makes sense if (power_metric->GetValueDescription().GetStructureDescription().size() > 0) { lib->GetMetricManager().AddFrameMetric(power_metric); cw.AddColumn(new slambench::CollectionValueLibColumnInterface(lib, power_metric, lib->GetMetricManager().GetFramePhase())); } // Add XYZ row from the trajectory auto traj = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); traj->SetActive(true); cw.AddColumn(new slambench::CollectionValueLibColumnInterface(lib, new slambench::outputs::PoseToXYZOutput(traj))); } config->AddFrameCallback([&cw]{cw.PrintRow();}); // @suppress("Invalid arguments") cw.PrintHeader(); //*************************************************************************************** // We run the experiment //*************************************************************************************** SLAMBenchConfiguration::compute_loop_algorithm (config,NULL,NULL); //*************************************************************************************** // End of experiment, we output the map //*************************************************************************************** // TODO: Only one output file does not do the job for more than one SLAM systems, output directory maybe ? SLAMBenchLibraryHelper *main_lib = nullptr; if(output_filename != "" && config->GetLoadedLibs().size() > 1) { std::cerr << "Can only write outputs to file when there is only one lib loaded" << std::endl; return 1; } else if(output_filename != "") { // enable all writeable outputs SLAMBenchLibraryHelper *lib = config->GetLoadedLibs().front(); main_lib = lib; lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE)->SetActive(true); } if(output_filename != "") { slambench::TimeStamp timestamp = main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE)->GetMostRecentValue().first; main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_POINTCLOUD)->SetActive(true); main_lib->c_sb_update_outputs(main_lib, ×tamp); std::cout << "Writing outputs to " << output_filename << std::endl; slambench::outputs::OutputManagerWriter omw; SLAMBenchLibraryHelper *lib = *config->GetLoadedLibs().begin(); omw.Write(lib->GetOutputManager(), output_filename); std::cout << "Done writing outputs." << std::endl; } std::cout << "End of program." << std::endl; delete config; delete alignment_method; delete memory_metric; delete duration_metric; delete power_metric; } catch (const SLAMBenchException& e) { std::cout << "An error occurred during the execution." << std::endl; std::cout << e.what() << std::endl; } return 0; } ================================================ FILE: framework/tools/loaders/pangolin_loader.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #include #include #include #include #include #include std::string alignment_technique = "original"; std::string default_alignment_technique = "original"; void run_pangolin(bool *stay_on, SLAMBenchConfiguration *config); static SLAMBenchUI * volatile ui = nullptr; int main(int argc, char * argv[]) { try { SLAMBenchConfiguration * config = new SLAMBenchConfiguration(); //*************************************************************************************** // Start the argument processing //*************************************************************************************** config->addParameter(TypedParameter ("a", "alignment-technique", "Select an alignment technique by name, if not found, default used (default,new).", &alignment_technique, &default_alignment_technique)); config->GetParameterManager().ReadArgumentsOrQuit(argc, argv); //*************************************************************************************** // At this point the datasets/libraries/sensors are loaded with their arguments set. //*************************************************************************************** //*************************************************************************************** // We initialise the configuration, means to retrieve groundtruth and set the alignement //*************************************************************************************** config->InitGroundtruth(); // get GT trajectory auto gt_trajectory = config->GetGroundTruth().GetMainOutput(slambench::values::VT_POSE); slambench::outputs::TrajectoryAlignmentMethod *alignment_method; if(alignment_technique == "original") { alignment_method = new slambench::outputs::OriginalTrajectoryAlignmentMethod(); } else if(alignment_technique == "new") { alignment_method = new slambench::outputs::NewTrajectoryAlignmentMethod(); } else { std::cerr << "Unknown alignment method " << alignment_technique << std::endl; return 1; } //*************************************************************************************** // We prepare the logging and create the global metrics //*************************************************************************************** // N/A //*************************************************************************************** // We init the algos now because we need their output already // TODO: if pose and map were by default we could init the algo much later, // thus move memory metric later //*************************************************************************************** config->InitAlgorithms(); // If a ground truth is available, produce an aligned trajectory for each algorithm if(gt_trajectory) { for(auto lib : config->GetLoadedLibs()) { // trajectory slambench::outputs::BaseOutput *trajectory = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE); // produce an alignment auto alignment = new slambench::outputs::AlignmentOutput("Alignment", new slambench::outputs::PoseOutputTrajectoryInterface(gt_trajectory), trajectory, alignment_method); alignment->SetActive(true); alignment->SetKeepOnlyMostRecent(true); auto aligned = new slambench::outputs::AlignedPoseOutput(trajectory->GetName() + " (Aligned)", alignment, trajectory); lib->GetOutputManager().RegisterOutput(aligned); // try and align a pointcloud slambench::outputs::BaseOutput *pointcloud = lib->GetOutputManager().GetMainOutput(slambench::values::VT_POINTCLOUD); if(pointcloud != nullptr) { auto pc_aligned = new slambench::outputs::AlignedPointCloudOutput(pointcloud->GetName() + "(Aligned)", alignment, pointcloud); lib->GetOutputManager().RegisterOutput(pc_aligned); } } } //*************************************************************************************** // We Start the GUI //*************************************************************************************** bool stay_on = true; std::thread pangolin_thread(run_pangolin, &stay_on, config); while(ui == nullptr) ; // spin until UI is initialised //*************************************************************************************** // We Start the Experiment //*************************************************************************************** SLAMBenchConfiguration::compute_loop_algorithm( config, &stay_on, ui); //*************************************************************************************** // We End and wait until the GUI stop //*************************************************************************************** stay_on = false; pangolin_thread.join(); } catch (const SLAMBenchException& e) { std::cout << "An error occurred during the execution." << std::endl; std::cout << e.what() << std::endl; } return 0; } void run_pangolin(bool *stay_on, SLAMBenchConfiguration *config) { std::cerr << "Creation of GUI interface." << std::endl; SLAMBenchUI_Pangolin * ui_pangolin = new SLAMBenchUI_Pangolin(); ui_pangolin->AddOutputManager("Ground Truth", &config->GetGroundTruth()); for(auto lib : config->GetLoadedLibs()) { ui_pangolin->AddOutputManager(lib->getName(), &lib->GetOutputManager()); } ui_pangolin->InitialiseOutputs(); ui = dynamic_cast (ui_pangolin); // Provide the current camera position to the GUI // FIXME : temporary values (Toky) float fx = 520.9000244141; float fy = 521.0000000000; float cx = 324.5999755859; float cy = 249.2000122070; ui->update_camera(480,640, fx, fy , cx , cy ); std::cerr << "Start rendering loop." << std::endl; while( !pangolin::ShouldQuit()) { usleep(40000); if (!ui->process ()) { std::cerr << "Rendering problem." << std::endl; exit(1); } } std::cout << "Stop Pangolin..." << std::endl; pangolin::Quit(); std::cout << "GUI closed ... " << std::endl; //*************************************************************************************** // CLOSE COMPUTE THREADS //*************************************************************************************** *stay_on = false; std::cout << "Wait for compute thread..." << std::endl; // compute_thread.join(); //*************************************************************************************** // CLOSE LIBRARIES //*************************************************************************************** std::cout << "End of program." << std::endl; } ================================================ FILE: framework/tools/loaders/slambench_app.cpp ================================================ /* Copyright (c) 2017 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #include #include #include #include #include #include #include #include std::string default_output_filename; std::string output_filename; bool use_gui, default_use_gui = false; bool lifelong_slam, default_lifelong_slam = false; std::string alignment_technique = "new"; std::string default_alignment_technique = "new"; TypedParameter file_output_parameter ("fo", "file-output", "File to write slamfile containing outputs", &output_filename, &default_output_filename); TypedParameter alignment_type_parameter("a", "alignment-technique", "Select an alignment technique by name, if not found, \"new alignment\" used (original,new,umeyama).", &alignment_technique, &default_alignment_technique); TypedParameter gui_parameter("gui", "gui", "Whether or not to display the graphical user interface", &use_gui, &default_use_gui); TypedParameter lifelong_parameter("ll", "lifelong", "If given multiple sequences, relocalise in between sequences rather than starting a new ", &lifelong_slam, &default_lifelong_slam); #ifdef WITH_GUI #include #include static SLAMBenchUI* volatile ui = nullptr; void run_pangolin(bool *stay_on, SLAMBenchConfiguration *config) { std::cerr << "Creation of GUI interface." << std::endl; auto ui_pangolin = new SLAMBenchUI_Pangolin(); ui_pangolin->AddOutputManager("Ground Truth", &config->GetGroundTruth()); for (auto lib : config->GetLoadedLibs()) { ui_pangolin->AddOutputManager(lib->getName(), &lib->GetOutputManager()); } ui_pangolin->InitialiseOutputs(); ui = dynamic_cast (ui_pangolin); // Provide the current camera position to the GUI ui->update_camera(480, 640, 520, 521, 324, 249); std::cerr << "Start rendering loop." << std::endl; while (!pangolin::ShouldQuit()) { usleep(40000); if (!ui->process()) { std::cerr << "Rendering problem." << std::endl; exit(1); } } //*************************************************************************************** // FINISH RENDERING //*************************************************************************************** std::cout << "Stop Pangolin..." << std::endl; pangolin::Quit(); std::cout << "GUI closed ... " << std::endl; //*************************************************************************************** // CLOSE COMPUTE THREADS //*************************************************************************************** *stay_on = false; std::cout << "Wait for compute thread..." << std::endl; // compute_thread.join(); } #endif int main(int argc, char * argv[]) { try { auto config = new SLAMBenchConfiguration(); config->addParameter(file_output_parameter); config->addParameter(alignment_type_parameter); config->addParameter(gui_parameter); config->addParameter(lifelong_parameter); // At this point the datasets/libraries/sensors are loaded with their arguments set. config->GetParameterManager().ReadArgumentsOrQuit(argc, argv); // Initialise the configuration, retrieve the ground truth and set the alignement config->InitGroundtruth(); // Prepare the logging config->StartStatistics(); //*************************************************************************************** // We init the algos now because we need their output already // TODO: if pose and map were by default we could init the algo much later, // thus move memory metric later //*************************************************************************************** config->InitAlgorithms(); config->InitAlignment(); config->InitWriter(); // Run the experiment if(use_gui) { #ifdef WITH_GUI std::thread pangolin_thread(run_pangolin, &use_gui, config); while(ui == nullptr) ; // spin until UI is initialised config->ComputeLoopAlgorithm(&use_gui, ui); pangolin_thread.join(); #else std::cerr<< "Not compiled with Pangolin support! Continuing without GUI." <ComputeLoopAlgorithm(nullptr, nullptr); } // End of experiment, we output the map // TODO: Only one output file does not do the job for more than one SLAM systems, output directory maybe ? if(!output_filename.empty()) { if(config->GetLoadedLibs().size() > 1) { std::cerr << "Can only write outputs to file when there is only one lib loaded" << std::endl; return 1; } // enable all writeable outputs auto main_lib = config->GetLoadedLibs().front(); main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE)->SetActive(true); main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_POINTCLOUD)->SetActive(true); main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_FRAME)->SetActive(true); auto timestamp = main_lib->GetOutputManager().GetMainOutput(slambench::values::VT_POSE)->GetMostRecentValue().first; main_lib->c_sb_update_outputs(main_lib, ×tamp); std::cout << "Writing outputs to " << output_filename << std::endl; slambench::outputs::OutputManagerWriter omw; omw.Write(main_lib->GetOutputManager(), output_filename); std::cout << "Done writing outputs." << std::endl; } std::cout << "End of program." << std::endl; delete config; } catch (const SLAMBenchException& e) { std::cout << "An error occurred during the execution." << std::endl; std::cout << e.what() << std::endl; } return 0; } ================================================ FILE: framework/tools/profiling-tools/CMakeLists.txt ================================================ cmake_minimum_required(VERSION 3.10) ###################################################################################### ########## OPENCL Wrapper for profiling (optional) ###################################################################################### find_package(OpenCL) if (OpenCL_FOUND) include_directories(${OPENCL_INCLUDE_DIRS}) add_library(oclwrapper SHARED OCLWrapper.cpp) target_link_libraries(oclwrapper ${OPENCL_LIBRARIES}) else (OpenCL_FOUND) message(STATUS "OpenCL wrapper cannot be build, OpenCL not found.") endif(OpenCL_FOUND) ================================================ FILE: framework/tools/profiling-tools/OCLWrapper.cpp ================================================ /* Copyright (c) 2014 University of Edinburgh, Imperial College, University of Manchester. Developed in the PAMELA project, EPSRC Programme Grant EP/K008730/1 This code is licensed under the MIT License. */ #ifdef __APPLE__ #include #else #include #endif #include #include #include #include #include #include #include #include #define CL_ENQUEUE_NDRANGE_KERNEL_NAME "clEnqueueNDRangeKernel" typedef cl_int (*clEnqueueNDRangeKernelFunction)(cl_command_queue command_queue, cl_kernel kernel, cl_uint work_dim, const size_t* global_work_offset, const size_t* global_work_size, const size_t* local_work_size, cl_uint num_events_in_wait_list, const cl_event* event_wait_list, cl_event* event); #define CL_CREATE_COMMAND_QUEUE_NAME "clCreateCommandQueue" typedef cl_command_queue (*clCreateCommandQueueFunction)(cl_context, cl_device_id, cl_command_queue_properties, cl_int*); #define checkError(err,str) if (err != CL_SUCCESS) {std::cout << str << std::endl; exit(err);} unsigned long int computeEventDuration(cl_event* event) { if (event == NULL) throw std::runtime_error( "Error computing event duration. \ Event is not initialized"); cl_int errorCode; cl_ulong start, end; errorCode = clGetEventProfilingInfo(*event, CL_PROFILING_COMMAND_START, sizeof(cl_ulong), &start, NULL); checkError(errorCode, "Error querying the event start time"); errorCode = clGetEventProfilingInfo(*event, CL_PROFILING_COMMAND_END, sizeof(cl_ulong), &end, NULL); checkError(errorCode, "Error querying the event end time"); return static_cast(end - start); } std::string getKernelName(cl_kernel kernel) { size_t nameSize; cl_int errorCode = clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, 0, NULL, &nameSize); checkError(errorCode, "Error querying the kernel name size"); char* name = new char[nameSize]; errorCode = clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, nameSize, name, NULL); checkError(errorCode, "Error querying the kernel name"); std::string nameString(name); delete[] name; return nameString; } void enqueueKernel(cl_command_queue command_queue, cl_kernel kernel, cl_uint work_dim, const size_t* global_work_offset, const size_t* global_work_size, const size_t* local_work_size, cl_uint num_events_in_wait_list, const cl_event* event_wait_list, cl_event* event, const std::string& kernelName) { static const char* kernel_to_change = getenv("KERNEL"); size_t new_local_work_size[3]; size_t new_global_work_size[3]; const size_t * pnew_local_work_size = local_work_size; const size_t * pnew_global_work_size = global_work_size; if (kernel_to_change != NULL) { if (kernelName == kernel_to_change) { pnew_local_work_size = (const size_t *) &new_local_work_size; for (unsigned int index = 0; index < work_dim; ++index) { std::stringstream varname; varname << "ls" << index; char* stringws = getenv(varname.str().c_str()); if (stringws) { std::istringstream(stringws) >> new_local_work_size[index]; } else { pnew_local_work_size = local_work_size; break; }; } if (pnew_local_work_size == (const size_t *) &new_local_work_size) { std::cout << "New localsize used :" << pnew_local_work_size[0]; if (work_dim > 1) std::cout << "x" << pnew_local_work_size[1]; if (work_dim > 2) std::cout << "x" << pnew_local_work_size[2]; std::cout << std::endl; } pnew_global_work_size = (const size_t *) &new_global_work_size; for (unsigned int index = 0; index < work_dim; ++index) { std::stringstream varname; varname << "gs" << index; char* stringws = getenv(varname.str().c_str()); if (stringws) { std::istringstream(stringws) >> new_global_work_size[index]; } else { pnew_global_work_size = global_work_size; break; }; } if (pnew_global_work_size == (const size_t *) &new_global_work_size) { std::cout << "New globalsize used :" << pnew_global_work_size[0]; if (work_dim > 1) std::cout << "x" << pnew_global_work_size[1]; if (work_dim > 2) std::cout << "x" << pnew_global_work_size[2]; std::cout << std::endl; } } } // Get pointer to original function calls. clEnqueueNDRangeKernelFunction originalclEnqueueKernel; *(void **) (&originalclEnqueueKernel) = dlsym(RTLD_NEXT, CL_ENQUEUE_NDRANGE_KERNEL_NAME); cl_int errorCode = 0; errorCode = originalclEnqueueKernel(command_queue, kernel, work_dim, global_work_offset, global_work_size, pnew_local_work_size, num_events_in_wait_list, event_wait_list, event); checkError(errorCode, "Error enqueuing the original kernel"); clFinish(command_queue); cl_int eventStatus = clWaitForEvents(1, event); std::cerr << kernelName; int totalglobalsize = 1; int totallocalsize = 1; for (unsigned int index = 0; index < work_dim; ++index) { totalglobalsize *= global_work_size[index]; if (pnew_local_work_size) { totallocalsize *= pnew_local_work_size[index]; } else { totallocalsize = 0; } } std::cerr << " " << totalglobalsize << " " << totallocalsize; if (eventStatus == -5) { std::cerr << " 0" << std::endl; } else { std::cerr << " " << computeEventDuration(event) << std::endl; } checkError(errorCode, "Error releasing the event"); } // overload function cl_int clEnqueueNDRangeKernel(cl_command_queue command_queue, cl_kernel kernel, cl_uint work_dim, const size_t* global_work_offset, const size_t* global_work_size, const size_t* local_work_size, cl_uint num_events_in_wait_list, const cl_event* event_wait_list, cl_event* event) { // Setup the event to measure the kernel execution time. bool isEventNull = (event == NULL); if (isEventNull) { event = new cl_event(); clRetainEvent(*event); } std::string kernelName = getKernelName(kernel); enqueueKernel(command_queue, kernel, work_dim, global_work_offset, global_work_size, local_work_size, num_events_in_wait_list, event_wait_list, event, kernelName); if (isEventNull) { clReleaseEvent(*event); delete event; } return CL_SUCCESS; } // overload function cl_command_queue clCreateCommandQueue(cl_context context, cl_device_id device, cl_command_queue_properties properties, cl_int* errcode_ret) { // Get pointer to original function calls. clCreateCommandQueueFunction originalclCreateCommandQueue; *(void **) (&originalclCreateCommandQueue) = dlsym(RTLD_NEXT, CL_CREATE_COMMAND_QUEUE_NAME); properties = properties | CL_QUEUE_PROFILING_ENABLE; return originalclCreateCommandQueue(context, device, properties, errcode_ret); } ================================================ FILE: icra2018_results/1080/memory_efusion_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:15:40 Properties: ================= frame-limit: 0 log-file: out_paper//memory_efusion_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0090210000 198579092 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0026371528 0.0013185764 0.0026371528 0.0017031863 0.0204370000 199227998 95654128 760807424 -0.0024932427 -0.0007044431 0.0006994744 3 0.0800000000 0.0100871567 0.0042414365 0.0100871567 0.0039453144 0.0157320000 199077794 95654128 760807424 -0.0044113910 -0.0079503814 0.0020711878 4 0.1200000000 0.0064609488 0.0047963146 0.0100871567 0.0045198247 0.0167270000 199078458 95654128 760807424 -0.0073308754 -0.0036204318 0.0007240017 5 0.1600000000 0.0057110265 0.0049792570 0.0100871567 0.0042706688 0.0159490000 199081750 95654128 760807424 -0.0100553054 -0.0022949593 0.0015700991 6 0.2000000000 0.0112805627 0.0060294746 0.0112805627 0.0041732509 0.0158290000 199083358 95654128 760807424 -0.0072992113 -0.0091361767 0.0032450091 7 0.2400000000 0.0135540208 0.0071044098 0.0135540208 0.0039259674 0.0158660000 199085966 95654128 760807424 -0.0089091705 -0.0113498140 0.0037236330 8 0.2800000000 0.0107231289 0.0075567497 0.0135540208 0.0037343884 0.0159900000 199088574 95654128 760807424 -0.0096100438 -0.0084813563 0.0030573488 9 0.3200000000 0.0097235013 0.0077974998 0.0135540208 0.0035714156 0.0158910000 199090286 95654128 760807424 -0.0101317223 -0.0085724834 0.0021830453 10 0.3600000000 0.0067283097 0.0076905808 0.0135540208 0.0034787580 0.0158600000 199094494 95654128 760807424 -0.0100675877 -0.0046240999 0.0014621485 11 0.4000000000 0.0064338772 0.0075763350 0.0135540208 0.0038185849 0.0158490000 199097102 95654128 760807424 -0.0118880654 -0.0051044086 0.0014768707 12 0.4400000000 0.0055728490 0.0074093779 0.0135540208 0.0037261660 0.0157930000 199098042 95654128 760807424 -0.0098036425 -0.0047088633 0.0001410431 13 0.4800000000 0.0088175200 0.0075176965 0.0135540208 0.0035711982 0.0158060000 199100850 95654128 760807424 -0.0071352324 -0.0061654276 -0.0000742798 14 0.5200000000 0.0092213796 0.0076393881 0.0135540208 0.0034565984 0.0158490000 199103458 95654128 760807424 -0.0065823053 -0.0051982040 -0.0007044386 15 0.5600000000 0.0108876443 0.0078559385 0.0135540208 0.0033434001 0.0158200000 199104266 95654128 760807424 -0.0089444770 -0.0056892172 0.0006350941 16 0.6000000000 0.0184974466 0.0085210328 0.0184974466 0.0034223249 0.0158250000 199106874 95654128 760807424 -0.0084662288 -0.0161986072 0.0018946307 17 0.6400000000 0.0161478408 0.0089696686 0.0184974466 0.0034379325 0.0158350000 199109290 95654128 760807424 -0.0113789421 -0.0153486151 0.0001675033 18 0.6800000000 0.0221328847 0.0097009583 0.0221328847 0.0034413521 0.0158170000 199115098 95654128 760807424 -0.0084276451 -0.0197052192 0.0019852838 19 0.7200000000 0.0201055091 0.0102485663 0.0221328847 0.0034966226 0.0164440000 199117706 95654128 760807424 -0.0103541492 -0.0174598750 0.0006507002 20 0.7600000000 0.0215131119 0.0108117936 0.0221328847 0.0034549391 0.0160710000 199118514 95654128 760807424 -0.0144756893 -0.0206799004 0.0013912533 21 0.8000000000 0.0267535094 0.0115709229 0.0267535094 0.0034232776 0.0158840000 199121454 95654128 760807424 -0.0124407895 -0.0230992008 0.0020042015 22 0.8400000000 0.0300625525 0.0124114515 0.0300625525 0.0034358628 0.0158450000 199123982 95654128 760807424 -0.0136958817 -0.0249262918 0.0017657080 23 0.8800000000 0.0304828174 0.0131971631 0.0304828174 0.0033707266 0.0158130000 199124790 95654128 760807424 -0.0125416974 -0.0257448442 0.0012449664 24 0.9200000000 0.0266937762 0.0137595220 0.0304828174 0.0033523162 0.0157630000 199127398 95654128 760807424 -0.0233151205 -0.0214212872 -0.0001865282 25 0.9600000000 0.0255954564 0.0142329593 0.0304828174 0.0033549478 0.0157860000 199130206 95654128 760807424 -0.0254838523 -0.0196202770 -0.0012257308 26 1.0000000000 0.0262101721 0.0146936214 0.0304828174 0.0033388963 0.0157580000 199130998 95654128 760807424 -0.0275975335 -0.0184477344 -0.0018390665 27 1.0400000000 0.0282834247 0.0151969474 0.0304828174 0.0033520922 0.0157450000 199133606 95654128 760807424 -0.0316985361 -0.0205885638 -0.0045927404 28 1.0800000000 0.0305297207 0.0157445465 0.0305297207 0.0034793504 0.0157420000 199136214 95654128 760807424 -0.0358802713 -0.0213602856 -0.0044593825 29 1.1200000000 0.0339501053 0.0163723243 0.0339501053 0.0036339901 0.0157200000 199137206 95654128 760807424 -0.0404079594 -0.0243348610 -0.0062383506 30 1.1600000000 0.0291963574 0.0167997921 0.0339501053 0.0035759123 0.0157130000 199139814 95654128 760807424 -0.0525395013 -0.0210875701 -0.0058968780 31 1.2000000000 0.0292491298 0.0172013837 0.0339501053 0.0035550944 0.0157440000 199140622 95654128 760807424 -0.0606839880 -0.0219500642 -0.0075829071 32 1.2400000000 0.0368122123 0.0178142220 0.0368122123 0.0037163267 0.0156840000 199143214 95654128 760807424 -0.0651723817 -0.0291861705 -0.0077604186 33 1.2800000000 0.0385045856 0.0184412028 0.0385045856 0.0037402297 0.0157610000 199148838 95654128 760807424 -0.0739758089 -0.0334096737 -0.0069114752 34 1.3200000000 0.0443853512 0.0192042660 0.0443853512 0.0036837435 0.0157560000 199156046 95654128 760807424 -0.0963910222 -0.0375464298 -0.0077222171 35 1.3600000000 0.0455008969 0.0199555983 0.0455008969 0.0039882530 0.0157210000 199158654 95654128 760807424 -0.0996186063 -0.0378845297 -0.0094717909 36 1.4000000000 0.0498891622 0.0207870862 0.0498891622 0.0044568925 0.0157540000 199161262 95654128 760807424 -0.1033664122 -0.0407271981 -0.0092919013 37 1.4400000000 0.0451959893 0.0214467862 0.0498891622 0.0044029887 0.0158510000 199162270 95654128 760807424 -0.1190132201 -0.0400445610 -0.0079860128 38 1.4800000000 0.0401330516 0.0219385301 0.0498891622 0.0043645940 0.0157490000 199164878 95654128 760807424 -0.1316675544 -0.0354127996 -0.0086453594 39 1.5200000000 0.0445632786 0.0225186518 0.0498891622 0.0043248721 0.0157430000 199167486 95654128 760807424 -0.1333151758 -0.0401661620 -0.0109468000 40 1.5600000000 0.0437998213 0.0230506811 0.0498891622 0.0042861562 0.0156990000 199168294 95654128 760807424 -0.1433345079 -0.0410356186 -0.0106800487 41 1.6000000000 0.0411494300 0.0234921140 0.0498891622 0.0042782106 0.0157380000 199171102 95654128 760807424 -0.1528392136 -0.0386657938 -0.0102921370 42 1.6400000000 0.0409626886 0.0239080800 0.0498891622 0.0042340001 0.0157280000 199171894 95654128 760807424 -0.1638475806 -0.0354125202 -0.0089674443 43 1.6800000000 0.0468040891 0.0244405453 0.0498891622 0.0041861622 0.0157750000 199174502 95654128 760807424 -0.1660161018 -0.0388228074 -0.0061789160 44 1.7200000000 0.0467707962 0.0249480510 0.0498891622 0.0042398200 0.0157920000 199177110 95654128 760807424 -0.1744252145 -0.0411150344 -0.0081031583 45 1.7600000000 0.0487261266 0.0254764527 0.0498891622 0.0042190690 0.0158040000 199178118 95654128 760807424 -0.1805272251 -0.0397668295 -0.0044525415 46 1.8000000000 0.0520135835 0.0260533469 0.0520135835 0.0042118306 0.0157920000 199180726 95654128 760807424 -0.1862655431 -0.0430259742 -0.0030282736 47 1.8400000000 0.0565873794 0.0267030071 0.0565873794 0.0042820581 0.0158460000 199183334 95654128 760807424 -0.1885485202 -0.0498375222 -0.0023084194 48 1.8800000000 0.0554225184 0.0273013303 0.0565873794 0.0042854743 0.0158520000 199184142 95654128 760807424 -0.1914724410 -0.0477676280 -0.0027554715 49 1.9200000000 0.0483129695 0.0277301393 0.0565873794 0.0042682016 0.0159310000 199186934 95654128 760807424 -0.2044636309 -0.0420439988 -0.0029993788 50 1.9600000000 0.0523277111 0.0282220907 0.0565873794 0.0043016589 0.0158320000 199189542 95654128 760807424 -0.2198711485 -0.0476021133 0.0030661807 51 2.0000000000 0.0551811308 0.0287506993 0.0565873794 0.0042826216 0.0158140000 199190350 95654128 760807424 -0.2205468863 -0.0518686995 0.0026909725 52 2.0400000000 0.0543477423 0.0292429501 0.0565873794 0.0042581275 0.0158400000 199192958 95654128 760807424 -0.2259499431 -0.0512978509 0.0013571766 53 2.0800000000 0.0559523962 0.0297469020 0.0565873794 0.0042408414 0.0158130000 199193966 95654128 760807424 -0.2260720134 -0.0546129644 -0.0018534213 54 2.1200000000 0.0523760021 0.0301659594 0.0565873794 0.0043400761 0.0157260000 199196574 95654128 760807424 -0.2362338901 -0.0508757904 0.0012660869 55 2.1600000000 0.0485463627 0.0305001485 0.0565873794 0.0044554986 0.0157220000 199199182 95654128 760807424 -0.2405269146 -0.0468673594 0.0009123727 56 2.2000000000 0.0451576672 0.0307618899 0.0565873794 0.0044742369 0.0157590000 199199974 95654128 760807424 -0.2592192590 -0.0417556688 0.0075114649 57 2.2400000000 0.0508189760 0.0311137686 0.0565873794 0.0044358958 0.0158060000 199202782 95654128 760807424 -0.2602382302 -0.0485637523 0.0097371116 58 2.2800000000 0.0468818732 0.0313856325 0.0565873794 0.0044001407 0.0157630000 199205390 95654128 760807424 -0.2727861106 -0.0466389991 0.0125466678 59 2.3200000000 0.0442872234 0.0316043035 0.0565873794 0.0044663539 0.0157700000 199206198 95654128 760807424 -0.2857498229 -0.0402964838 0.0163461398 60 2.3600000000 0.0485905334 0.0318874074 0.0565873794 0.0045760313 0.0157870000 199208806 95654128 760807424 -0.2868021131 -0.0457538813 0.0162637495 61 2.4000000000 0.0447512046 0.0320982893 0.0565873794 0.0046434365 0.0157960000 199211614 95654128 760807424 -0.2957808375 -0.0441492721 0.0149550457 62 2.4400000000 0.0414042212 0.0322483850 0.0565873794 0.0047900349 0.0158160000 199212422 95654128 760807424 -0.3189317882 -0.0386375673 0.0220509917 63 2.4800000000 0.0382823087 0.0323441615 0.0565873794 0.0049157183 0.0157800000 199215030 95654128 760807424 -0.3292100728 -0.0370469950 0.0239451472 64 2.5200000000 0.0343676023 0.0323757778 0.0565873794 0.0051400845 0.0157500000 199217638 95654128 760807424 -0.3423811793 -0.0307294503 0.0270876922 65 2.5600000000 0.0314134359 0.0323609725 0.0565873794 0.0053341422 0.0157620000 199224278 95654128 760807424 -0.3591589332 -0.0297854170 0.0311558284 66 2.6000000000 0.0322691575 0.0323595814 0.0565873794 0.0054796355 0.0158150000 199240430 95654128 760807424 -0.3703802526 -0.0302785095 0.0338467099 67 2.6400000000 0.0315576419 0.0323476121 0.0565873794 0.0055430199 0.0158420000 199409866 95654128 760807424 -0.3803149760 -0.0264058188 0.0355307348 68 2.6800000000 0.0313157849 0.0323324382 0.0565873794 0.0055235149 0.0157970000 199412474 95654128 760807424 -0.3911168277 -0.0258213263 0.0339615494 69 2.7200000000 0.0263048597 0.0322450820 0.0565873794 0.0055049140 0.0165760000 199415282 95654128 760807424 -0.4018940628 -0.0185064655 0.0364764482 70 2.7600000000 0.0235799700 0.0321212947 0.0565873794 0.0054879489 0.0158660000 199416090 95654128 760807424 -0.4134708047 -0.0157558955 0.0363230556 71 2.8000000000 0.0262276791 0.0320382860 0.0565873794 0.0055144253 0.0158380000 199418698 95654128 760807424 -0.4189737439 -0.0175977964 0.0338540338 72 2.8400000000 0.0289597157 0.0319955281 0.0565873794 0.0061710784 0.0159160000 199421322 95654128 760807424 -0.4334383607 -0.0148553653 0.0370378457 73 2.8800000000 0.0284570716 0.0319470561 0.0565873794 0.0062427337 0.0158480000 199422330 95654128 760807424 -0.4443531036 -0.0137336301 0.0382776745 74 2.9200000000 0.0275675729 0.0318878739 0.0565873794 0.0063211064 0.0159060000 199424938 95654128 760807424 -0.4466990232 -0.0110744257 0.0360629447 75 2.9600000000 0.0274368692 0.0318285272 0.0565873794 0.0063789857 0.0158970000 199427546 95654128 760807424 -0.4506964982 -0.0102010854 0.0351960622 76 3.0000000000 0.0321612656 0.0318329053 0.0565873794 0.0064126781 0.0159400000 199428354 95654128 760807424 -0.4508700073 -0.0144840386 0.0302572101 77 3.0400000000 0.0329811797 0.0318478180 0.0565873794 0.0064107041 0.0158860000 199431146 95654128 760807424 -0.4512129426 -0.0149901342 0.0242106579 78 3.0800000000 0.0366987474 0.0319100094 0.0565873794 0.0063815430 0.0159780000 199431954 95654128 760807424 -0.4506838322 -0.0183871873 0.0185859352 79 3.1200000000 0.0387896895 0.0319970939 0.0565873794 0.0063489500 0.0159180000 199434562 95654128 760807424 -0.4562318921 -0.0169873573 0.0165847540 80 3.1600000000 0.0439270549 0.0321462184 0.0565873794 0.0063360993 0.0159870000 199438326 95654128 760807424 -0.4598583579 -0.0196885280 0.0143181216 81 3.2000000000 0.0395911373 0.0322381310 0.0565873794 0.0063086925 0.0159590000 199607958 95654128 760807424 -0.4700203538 -0.0153068304 0.0148813101 82 3.2400000000 0.0390609652 0.0323213363 0.0565873794 0.0063280719 0.0159900000 199610566 95654128 760807424 -0.4801810384 -0.0155358370 0.0140335066 83 3.2800000000 0.0355026051 0.0323596648 0.0565873794 0.0063326456 0.0159720000 199613174 95654128 760807424 -0.4919620156 -0.0113758296 0.0103022512 84 3.3200000000 0.0303926412 0.0323362479 0.0565873794 0.0063157057 0.0159620000 199613982 95654128 760807424 -0.5042786598 -0.0069527207 0.0090701617 85 3.3600000000 0.0338446312 0.0323539936 0.0565873794 0.0063157270 0.0159290000 199616790 95654128 760807424 -0.5145150423 -0.0081325872 0.0096226893 86 3.4000000000 0.0299361199 0.0323258788 0.0565873794 0.0063626563 0.0160750000 199619398 95654128 760807424 -0.5303586721 -0.0035575614 0.0116176223 87 3.4400000000 0.0298443679 0.0322973557 0.0565873794 0.0064897145 0.0159920000 199620206 95654128 760807424 -0.5393974185 -0.0041370192 0.0110724103 88 3.4800000000 0.0266220178 0.0322328632 0.0565873794 0.0065695902 0.0159350000 199622814 95654128 760807424 -0.5534371138 -0.0005895477 0.0110304765 89 3.5200000000 0.0261351820 0.0321643499 0.0565873794 0.0066733550 0.0159780000 199623822 95654128 760807424 -0.5623205304 0.0005255556 0.0113013256 90 3.5600000000 0.0250491034 0.0320852916 0.0565873794 0.0067743306 0.0159690000 199626446 95654128 760807424 -0.5709735155 -0.0007456413 0.0097119333 91 3.6000000000 0.0262133759 0.0320207651 0.0565873794 0.0068309454 0.0159910000 199629054 95654128 760807424 -0.5837507248 -0.0020658812 0.0114376955 92 3.6400000000 0.0248073302 0.0319423582 0.0565873794 0.0068435934 0.0160190000 199629862 95654128 760807424 -0.5996577144 0.0014718459 0.0154624488 93 3.6800000000 0.0282015596 0.0319021345 0.0565873794 0.0068359485 0.0167020000 199632670 95654128 760807424 -0.6015052199 -0.0017028709 0.0139123406 94 3.7200000000 0.0287994500 0.0318691272 0.0565873794 0.0068125342 0.0160440000 199635278 95654128 760807424 -0.6069484353 -0.0031834850 0.0127243828 95 3.7600000000 0.0283411518 0.0318319907 0.0565873794 0.0068150262 0.0160190000 199636086 95654128 760807424 -0.6213353276 -0.0022502071 0.0177968629 96 3.8000000000 0.0284032933 0.0317962751 0.0565873794 0.0067867818 0.0160050000 199638694 95654128 760807424 -0.6307749152 -0.0022207610 0.0173674375 97 3.8400000000 0.0278009027 0.0317550857 0.0565873794 0.0067537811 0.0160540000 199641502 95654128 760807424 -0.6360018849 -0.0036643983 0.0187562387 98 3.8800000000 0.0307208337 0.0317445321 0.0565873794 0.0067274283 0.0160140000 199642310 95654128 760807424 -0.6506360173 -0.0085041942 0.0235109441 99 3.9200000000 0.0334215276 0.0317614714 0.0565873794 0.0067038442 0.0160490000 199644918 95654128 760807424 -0.6566256881 -0.0109054297 0.0268212855 100 3.9600000000 0.0304026399 0.0317478831 0.0565873794 0.0066734254 0.0160910000 199648230 95654128 760807424 -0.6654935479 -0.0078691943 0.0298565552 101 4.0000000000 0.0280820951 0.0317115882 0.0565873794 0.0066432768 0.0160520000 199817878 95654128 760807424 -0.6736974120 -0.0059484625 0.0351908617 102 4.0400000000 0.0259241927 0.0316548490 0.0565873794 0.0066272081 0.0160540000 199820486 95654128 760807424 -0.6784198880 -0.0054489388 0.0368493833 103 4.0800000000 0.0290422644 0.0316294841 0.0565873794 0.0065956642 0.0160590000 199821294 95654128 760807424 -0.6875373721 -0.0086858682 0.0431620181 104 4.1200000000 0.0290709287 0.0316048826 0.0565873794 0.0065653190 0.0161080000 199823902 95654128 760807424 -0.6993187666 -0.0088663977 0.0537953526 105 4.1600000000 0.0295045525 0.0315848795 0.0565873794 0.0065754070 0.0160470000 199826710 95654128 760807424 -0.7007381320 -0.0086500365 0.0566891655 106 4.2000000000 0.0234080087 0.0315077392 0.0565873794 0.0065547651 0.0161010000 199827502 95654128 760807424 -0.7124599218 -0.0041248659 0.0608023331 107 4.2400000000 0.0230035931 0.0314282612 0.0565873794 0.0065421625 0.0161490000 199830110 95654128 760807424 -0.7120105028 -0.0066935853 0.0590329096 108 4.2800000000 0.0237780940 0.0313574263 0.0565873794 0.0065144630 0.0160860000 199832718 95654128 760807424 -0.7214694023 -0.0085320361 0.0670858026 109 4.3200000000 0.0249999575 0.0312991009 0.0565873794 0.0065010272 0.0161130000 199833726 95654128 760807424 -0.7220396996 -0.0091981189 0.0687412992 110 4.3600000000 0.0239698645 0.0312324715 0.0565873794 0.0065085124 0.0161090000 199836334 95654128 760807424 -0.7320408821 -0.0099378293 0.0755404010 111 4.4000000000 0.0223217160 0.0311521944 0.0565873794 0.0064980428 0.0161380000 199838942 95654128 760807424 -0.7395170927 -0.0095068049 0.0813724697 112 4.4400000000 0.0257163253 0.0311036598 0.0565873794 0.0065066071 0.0161680000 199839766 95654128 760807424 -0.7446871400 -0.0112846233 0.0892183781 113 4.4800000000 0.0250240285 0.0310498578 0.0565873794 0.0065139472 0.0161560000 199842574 95654128 760807424 -0.7483003139 -0.0092906402 0.0929298103 114 4.5200000000 0.0279746242 0.0310228821 0.0565873794 0.0065617109 0.0161720000 199843382 95654128 760807424 -0.7582687140 -0.0125495903 0.1036359519 115 4.5600000000 0.0274628866 0.0309919256 0.0565873794 0.0065812472 0.0161850000 199845990 95654128 760807424 -0.7586623430 -0.0118031856 0.1064784974 116 4.6000000000 0.0284700096 0.0309701849 0.0565873794 0.0066126845 0.0161330000 199848598 95654128 760807424 -0.7683888674 -0.0094802603 0.1172670871 117 4.6400000000 0.0238145217 0.0309090254 0.0565873794 0.0066062480 0.0161850000 199849606 95654128 760807424 -0.7791025639 -0.0020336183 0.1275464743 118 4.6800000000 0.0259956717 0.0308673868 0.0565873794 0.0065823816 0.0161890000 199852214 95654128 760807424 -0.7825962901 -0.0053514089 0.1324608922 119 4.7200000000 0.0244217627 0.0308132219 0.0565873794 0.0065608417 0.0162000000 199854822 95654128 760807424 -0.7907667756 -0.0051540658 0.1391335130 120 4.7600000000 0.0230371635 0.0307484214 0.0565873794 0.0065365893 0.0162130000 199855630 95654128 760807424 -0.7981805205 -0.0015906547 0.1467321664 121 4.8000000000 0.0202708505 0.0306618299 0.0565873794 0.0065245021 0.0162060000 199858438 95654128 760807424 -0.8099064827 0.0030194623 0.1626119912 122 4.8400000000 0.0197435040 0.0305723355 0.0565873794 0.0065075745 0.0162270000 199861046 95654128 760807424 -0.8105869889 0.0066809645 0.1644673049 123 4.8800000000 0.0202268977 0.0304882262 0.0565873794 0.0064845713 0.0161970000 199861854 95654128 760807424 -0.8161545992 0.0091134738 0.1708295643 124 4.9200000000 0.0210503396 0.0304121142 0.0565873794 0.0064626427 0.0162540000 199864462 95654128 760807424 -0.8264054656 0.0098223360 0.1842324138 125 4.9600000000 0.0221218374 0.0303457920 0.0565873794 0.0064673463 0.0162380000 199865470 95654128 760807424 -0.8290974498 0.0075975470 0.1905805767 126 5.0000000000 0.0203621760 0.0302665570 0.0565873794 0.0064472133 0.0162330000 199868094 95654128 760807424 -0.8356361985 0.0089944517 0.1986374259 127 5.0400000000 0.0224242900 0.0302048068 0.0565873794 0.0064233202 0.0163220000 199870702 95654128 760807424 -0.8444821239 0.0063631646 0.2155444175 128 5.0800000000 0.0181625560 0.0301107267 0.0565873794 0.0064069173 0.0162360000 199871510 95654128 760807424 -0.8519821763 0.0123763606 0.2219798267 129 5.1200000000 0.0159286819 0.0300007884 0.0565873794 0.0063837348 0.0162610000 199885582 95654128 760807424 -0.8588014245 0.0124319699 0.2291795313 130 5.1600000000 0.0142402081 0.0298795532 0.0565873794 0.0063747314 0.0162500000 199913790 95654128 760807424 -0.8703675866 0.0166023001 0.2459881902 131 5.2000000000 0.0138809010 0.0297574261 0.0565873794 0.0063985633 0.0162730000 199914598 95654128 760807424 -0.8737038970 0.0159749705 0.2508947253 132 5.2400000000 0.0125347050 0.0296269509 0.0565873794 0.0064187543 0.0163770000 199918930 95654128 760807424 -0.8736839890 0.0161852501 0.2506185472 133 5.2800000000 0.0143580977 0.0295121475 0.0565873794 0.0064112664 0.0164340000 200090354 95654128 760807424 -0.8840085268 0.0179630816 0.2671507299 134 5.3200000000 0.0128155705 0.0293875462 0.0565873794 0.0064158977 0.0164270000 200091162 95654128 760807424 -0.8963862062 0.0240811650 0.2838450372 135 5.3600000000 0.0136302458 0.0292708254 0.0565873794 0.0064378154 0.0164360000 200093770 95654128 760807424 -0.8979189992 0.0253746808 0.2880425453 136 5.4000000000 0.0142661799 0.0291604971 0.0565873794 0.0064766813 0.0163950000 200096378 95654128 760807424 -0.9035479426 0.0211286657 0.2993725538 137 5.4400000000 0.0135588627 0.0290466166 0.0565873794 0.0065395620 0.0164350000 200097386 95654128 760807424 -0.9087882042 0.0240651015 0.3097975552 138 5.4800000000 0.0137075316 0.0289354638 0.0565873794 0.0065782011 0.0164100000 200099994 95654128 760807424 -0.9142451286 0.0228410941 0.3143880367 139 5.5200000000 0.0144062052 0.0288309368 0.0565873794 0.0066244801 0.0164520000 200100802 95654128 760807424 -0.9191100597 0.0179335847 0.3194557726 140 5.5600000000 0.0164834857 0.0287427407 0.0565873794 0.0066983787 0.0164080000 200103410 95654128 760807424 -0.9267788529 0.0176282432 0.3325157762 141 5.6000000000 0.0159996878 0.0286523644 0.0565873794 0.0067308901 0.0170870000 200106218 95654128 760807424 -0.9324721694 0.0188185107 0.3384733796 142 5.6400000000 0.0174587779 0.0285735364 0.0565873794 0.0067756675 0.0164750000 200107026 95654128 760807424 -0.9405248165 0.0165808778 0.3527539074 143 5.6800000000 0.0170335062 0.0284928368 0.0565873794 0.0068551728 0.0163760000 200109634 95654128 760807424 -0.9468364120 0.0163971540 0.3634625077 144 5.7200000000 0.0168769881 0.0284121712 0.0565873794 0.0068920136 0.0163360000 200112242 95654128 760807424 -0.9523243904 0.0183631629 0.3722898364 145 5.7600000000 0.0133431479 0.0283082469 0.0565873794 0.0068896055 0.0163910000 200113250 95654128 760807424 -0.9608452320 0.0214430466 0.3796906769 146 5.8000000000 0.0134300925 0.0282063418 0.0565873794 0.0068767428 0.0163400000 200115858 95654128 760807424 -0.9673052430 0.0203367211 0.3888083696 147 5.8400000000 0.0143539039 0.0281121075 0.0565873794 0.0068600296 0.0164430000 200118466 95654128 760807424 -0.9767009020 0.0199700836 0.4090556204 148 5.8800000000 0.0135355704 0.0280136174 0.0565873794 0.0068379322 0.0163490000 200119274 95654128 760807424 -0.9784352779 0.0195393600 0.4133089483 149 5.9200000000 0.0124185085 0.0279089522 0.0565873794 0.0068190764 0.0164090000 200122082 95654128 760807424 -0.9838584065 0.0201101340 0.4250485897 150 5.9600000000 0.0115296766 0.0277997570 0.0565873794 0.0067999941 0.0164890000 200123778 95654128 760807424 -0.9875609279 0.0196199808 0.4350703359 151 6.0000000000 0.0115716569 0.0276922862 0.0565873794 0.0067812473 0.0163950000 200295030 95654128 760807424 -0.9911735654 0.0222937744 0.4438393414 152 6.0400000000 0.0108962534 0.0275817860 0.0565873794 0.0067659179 0.0164310000 200297638 95654128 760807424 -0.9951195717 0.0228361450 0.4550249279 153 6.0800000000 0.0104459934 0.0274697873 0.0565873794 0.0067512304 0.0165560000 200298646 95654128 760807424 -0.9993032217 0.0227521881 0.4635451436 154 6.1200000000 0.0102415653 0.0273579158 0.0565873794 0.0067724298 0.0163370000 200301254 95654128 760807424 -1.0041266680 0.0237469710 0.4758141041 155 6.1600000000 0.0096437922 0.0272436311 0.0565873794 0.0068273672 0.0163440000 200303862 95654128 760807424 -1.0069274902 0.0233395379 0.4834894836 156 6.2000000000 0.0164500754 0.0271744416 0.0565873794 0.0069797223 0.0163550000 200304670 95654128 760807424 -1.0053585768 0.0192709249 0.4951361120 157 6.2400000000 0.0150725376 0.0270973594 0.0565873794 0.0070777629 0.0163450000 200307478 95654128 760807424 -1.0081217289 0.0236951243 0.5065523982 158 6.2800000000 0.0157728232 0.0270256852 0.0565873794 0.0071443995 0.0163040000 200310086 95654128 760807424 -1.0111910105 0.0215646271 0.5223304629 159 6.3200000000 0.0167589821 0.0269611147 0.0565873794 0.0071794883 0.0163900000 200310894 95654128 760807424 -1.0110269785 0.0186838731 0.5300494432 160 6.3600000000 0.0166279208 0.0268965322 0.0565873794 0.0072151624 0.0163390000 200313502 95654128 760807424 -1.0120902061 0.0205977689 0.5455650687 161 6.4000000000 0.0148482248 0.0268216980 0.0565873794 0.0072007907 0.0163100000 200314510 95654128 760807424 -1.0122925043 0.0222181939 0.5580057502 162 6.4400000000 0.0167361107 0.0267594413 0.0565873794 0.0071813225 0.0162920000 200317118 95654228 760807424 -1.0109827518 0.0214221664 0.5675398707 163 6.4800000000 0.0130465021 0.0266753129 0.0565873794 0.0071646277 0.0163660000 200319726 95654228 760807424 -1.0149894953 0.0244314000 0.5825407505 164 6.5200000000 0.0163212046 0.0266121780 0.0565873794 0.0071454323 0.0162800000 200320534 95654228 760807424 -1.0138913393 0.0234160684 0.5915772915 165 6.5600000000 0.0149509236 0.0265415038 0.0565873794 0.0071379143 0.0169700000 200323342 95654228 760807424 -1.0160150528 0.0259537492 0.6101555228 166 6.6000000000 0.0160205122 0.0264781243 0.0565873794 0.0071537291 0.0163260000 200325950 95654228 760807424 -1.0149663687 0.0271851830 0.6202256083 167 6.6400000000 0.0149552831 0.0264091253 0.0565873794 0.0071609669 0.0162550000 200326758 95654228 760807424 -1.0151618719 0.0297443736 0.6310047507 168 6.6800000000 0.0139586376 0.0263350152 0.0565873794 0.0071648433 0.0162240000 200329366 95654228 760807424 -1.0163806677 0.0278186575 0.6439236999 169 6.7200000000 0.0120556671 0.0262505220 0.0565873794 0.0071503648 0.0162120000 200332174 95654228 760807424 -1.0166087151 0.0269229040 0.6601555943 170 6.7600000000 0.0125786299 0.0261700991 0.0565873794 0.0071455241 0.0162460000 200332982 95654228 760807424 -1.0176496506 0.0298713446 0.6772519946 171 6.8000000000 0.0124597698 0.0260899218 0.0565873794 0.0071400852 0.0162230000 200335590 95654228 760807424 -1.0170701742 0.0319686271 0.6863614917 172 6.8400000000 0.0112301568 0.0260035278 0.0565873794 0.0071207249 0.0161920000 200338198 95654228 760807424 -1.0183249712 0.0366709642 0.6997845173 173 6.8800000000 0.0121431518 0.0259234100 0.0565873794 0.0071014793 0.0162360000 200339206 95654228 760807424 -1.0190625191 0.0404440239 0.7132297754 174 6.9200000000 0.0141703160 0.0258558635 0.0565873794 0.0070823545 0.0162530000 200341814 95654228 760807424 -1.0200881958 0.0453059003 0.7250161767 175 6.9600000000 0.0148786632 0.0257931366 0.0565873794 0.0070623962 0.0162660000 200342622 95654228 760807424 -1.0198521614 0.0475922935 0.7368726730 176 7.0000000000 0.0138369342 0.0257252037 0.0565873794 0.0070481548 0.0163030000 200345230 95654228 760807424 -1.0228319168 0.0481997542 0.7526132464 177 7.0400000000 0.0146974120 0.0256628998 0.0565873794 0.0070670362 0.0162820000 200348038 95654228 760807424 -1.0237472057 0.0477490239 0.7599322796 178 7.0800000000 0.0149164945 0.0256025267 0.0565873794 0.0070534085 0.0162790000 200348830 95654228 760807424 -1.0229822397 0.0470573679 0.7666771412 179 7.1200000000 0.0129915616 0.0255320744 0.0565873794 0.0070403659 0.0162820000 200351438 95654228 760807424 -1.0213805437 0.0460786410 0.7799621224 180 7.1600000000 0.0123427873 0.0254588006 0.0565873794 0.0070215013 0.0162830000 200354046 95654228 760807424 -1.0214103460 0.0483879186 0.7935987711 181 7.2000000000 0.0100744218 0.0253738040 0.0565873794 0.0070065841 0.0162800000 200355054 95654228 760807424 -1.0204126835 0.0486699603 0.8068802953 182 7.2400000000 0.0102239009 0.0252905628 0.0565873794 0.0069904747 0.0163030000 200357662 95654228 760807424 -1.0209597349 0.0505298078 0.8222455978 183 7.2800000000 0.0106278118 0.0252104384 0.0565873794 0.0069754767 0.0162560000 200360270 95654228 760807424 -1.0231943130 0.0511041060 0.8380003572 184 7.3200000000 0.0105713662 0.0251308783 0.0565873794 0.0069566952 0.0163200000 200361078 95654228 760807424 -1.0208232403 0.0498204529 0.8476718068 185 7.3600000000 0.0104154246 0.0250513353 0.0565873794 0.0069412132 0.0163100000 200363886 95654228 760807424 -1.0201561451 0.0509872027 0.8642705083 186 7.4000000000 0.0101471543 0.0249712053 0.0565873794 0.0069292675 0.0163610000 200365518 95654228 760807424 -1.0192699432 0.0486023799 0.8806984425 187 7.4400000000 0.0113121048 0.0248981620 0.0565873794 0.0069241004 0.0162980000 200536782 95654228 760807424 -1.0148494244 0.0469910428 0.8868576884 188 7.4800000000 0.0098668411 0.0248182081 0.0565873794 0.0069271552 0.0163210000 200539390 95654228 760807424 -1.0144065619 0.0509113148 0.9040864706 189 7.5200000000 0.0111770574 0.0247460327 0.0565873794 0.0069107368 0.0163200000 200540398 95654228 760807424 -1.0136638880 0.0571361743 0.9230853319 190 7.5600000000 0.0118347583 0.0246780786 0.0565873794 0.0069009710 0.0163140000 200543006 95654228 760807424 -1.0128675699 0.0577470101 0.9397385120 191 7.6000000000 0.0088402415 0.0245951580 0.0565873794 0.0068919852 0.0162870000 200545614 95654228 760807424 -1.0110441446 0.0554164536 0.9552106261 192 7.6400000000 0.0087975524 0.0245128788 0.0565873794 0.0068824751 0.0163070000 200546438 95654228 760807424 -1.0091952085 0.0610064976 0.9712004662 193 7.6800000000 0.0093551036 0.0244343411 0.0565873794 0.0068857086 0.0162580000 200549246 95654228 760807424 -1.0079247952 0.0618456490 0.9879875779 194 7.7200000000 0.0101408111 0.0243606631 0.0565873794 0.0068830682 0.0163110000 200551854 95654228 760807424 -1.0083497763 0.0572154485 1.0028771162 195 7.7600000000 0.0079246145 0.0242763757 0.0565873794 0.0068909371 0.0165640000 200552662 95654228 760807424 -1.0062748194 0.0558811352 1.0175403357 196 7.8000000000 0.0069334055 0.0241878912 0.0565873794 0.0069310132 0.0167020000 200555270 95654228 760807424 -1.0050816536 0.0604556166 1.0370169878 197 7.8400000000 0.0080020893 0.0241057297 0.0565873794 0.0069531727 0.0167070000 200556278 95654228 760807424 -1.0024425983 0.0635510236 1.0464431047 198 7.8800000000 0.0080746124 0.0240247645 0.0565873794 0.0069758146 0.0166600000 200558902 95654228 760807424 -1.0005651712 0.0644728839 1.0618821383 199 7.9200000000 0.0089155370 0.0239488387 0.0565873794 0.0069660219 0.0166460000 200561510 95654228 760807424 -0.9995563030 0.0681180432 1.0778725147 200 7.9600000000 0.0099885100 0.0238790371 0.0565873794 0.0069537178 0.0166120000 200562318 95654228 760807424 -0.9995802045 0.0671301484 1.0908124447 201 8.0000000000 0.0089046909 0.0238045379 0.0565873794 0.0069707369 0.0166510000 200565126 95654228 760807424 -0.9985320568 0.0677087754 1.1107248068 202 8.0400000000 0.0083883032 0.0237282199 0.0565873794 0.0069837731 0.0165790000 200567734 95654228 760807424 -0.9957184792 0.0689138472 1.1220202446 203 8.0800000000 0.0103089958 0.0236621153 0.0565873794 0.0070011781 0.0166130000 200568542 95654228 760807424 -0.9927189350 0.0710213482 1.1368229389 204 8.1200000000 0.0095485914 0.0235929314 0.0565873794 0.0069925358 0.0165730000 200571150 95654228 760807424 -0.9908673167 0.0704847351 1.1502454281 205 8.1600000000 0.0103962244 0.0235285572 0.0565873794 0.0069824238 0.0166010000 200573958 95654228 760807424 -0.9890765548 0.0717406496 1.1630996466 206 8.1999999990 0.0113346819 0.0234693636 0.0565873794 0.0069739384 0.0165370000 200574766 95654228 760807424 -0.9862065911 0.0713571310 1.1749844551 207 8.2400000000 0.0127916262 0.0234177804 0.0565873794 0.0069649150 0.0165910000 200577374 95654228 760807424 -0.9819779992 0.0739604235 1.1865544319 208 8.2799999990 0.0153867127 0.0233791695 0.0565873794 0.0069510562 0.0166000000 200579982 95654228 760807424 -0.9784305096 0.0778952688 1.1974254847 209 8.3200000000 0.0146812061 0.0233375524 0.0565873794 0.0069473176 0.0166280000 200580990 95654228 760807424 -0.9735398293 0.0808220729 1.2119553089 210 8.3599999990 0.0106073739 0.0232769325 0.0565873794 0.0069738634 0.0165920000 200583598 95654228 760807424 -0.9674462676 0.0788866132 1.2262446880 211 8.4000000000 0.0109463539 0.0232184937 0.0565873794 0.0069976228 0.0166130000 200584406 95654228 760807424 -0.9644164443 0.0776812360 1.2415794134 212 8.4399999990 0.0115540521 0.0231634728 0.0565873794 0.0069825136 0.0173060000 200587014 95654228 760807424 -0.9563731551 0.0812902749 1.2521836758 213 8.4800000000 0.0135051953 0.0231181288 0.0565873794 0.0069818189 0.0166820000 200589822 95654228 760807424 -0.9504551291 0.0863137916 1.2651948929 214 8.5200000000 0.0159696974 0.0230847249 0.0565873794 0.0070580909 0.0165900000 200590630 95654228 760807424 -0.9435605407 0.0906225070 1.2790313959 215 8.5600000000 0.0149667449 0.0230469668 0.0565873794 0.0070650817 0.0166450000 200593958 95654228 760807424 -0.9360330701 0.0885562450 1.2891931534 216 8.6000000000 0.0197777431 0.0230318315 0.0565873794 0.0070521498 0.0166130000 200765218 95654228 760807424 -0.9306077957 0.0957913920 1.2989349365 217 8.6400000000 0.0209952574 0.0230224464 0.0565873794 0.0070857842 0.0166940000 200766226 95654228 760807424 -0.9217486382 0.1015952900 1.3183747530 218 8.6800000000 0.0191447679 0.0230046589 0.0565873794 0.0071358192 0.0165640000 200768834 95654228 760807424 -0.9125380516 0.0998102650 1.3285518885 219 8.7200000000 0.0194169320 0.0229882766 0.0565873794 0.0071379657 0.0165920000 200771442 95654228 760807424 -0.9035221934 0.1017378420 1.3377380371 220 8.7600000000 0.0218510125 0.0229831072 0.0565873794 0.0071417022 0.0165600000 200772250 95654228 760807424 -0.8942003250 0.1082556695 1.3481254578 221 8.8000000000 0.0252365675 0.0229933038 0.0565873794 0.0071907685 0.0166040000 200775074 95654228 760807424 -0.8851771355 0.1135306805 1.3610553741 222 8.8400000000 0.0266773999 0.0230098989 0.0565873794 0.0071948097 0.0165750000 200775882 95654228 760807424 -0.8762686253 0.1147469729 1.3709738255 223 8.8800000000 0.0276154019 0.0230305514 0.0565873794 0.0071973629 0.0165770000 200778490 95654228 760807424 -0.8663059473 0.1180772111 1.3796384335 224 8.9200000000 0.0280872788 0.0230531260 0.0565873794 0.0072042398 0.0165990000 200782594 95654228 760807424 -0.8562116027 0.1209880561 1.3901326656 225 8.9600000000 0.0278070997 0.0230742548 0.0565873794 0.0072003355 0.0162700000 200952202 95654228 760807424 -0.8458883166 0.1233262122 1.3984519243 226 9.0000000000 0.0266737863 0.0230901819 0.0565873794 0.0071868005 0.0162060000 200954810 95654228 760807424 -0.8357704282 0.1255071014 1.4098273516 227 9.0400000000 0.0268399809 0.0231067009 0.0565873794 0.0071734862 0.0161940000 200957418 95654228 760807424 -0.8234215379 0.1331376731 1.4206258059 228 9.0800000000 0.0265169386 0.0231216581 0.0565873794 0.0071843668 0.0162970000 200958242 95654228 760807424 -0.8124112487 0.1373369992 1.4328358173 229 9.1200000000 0.0266693253 0.0231371500 0.0565873794 0.0072333751 0.0162870000 200961050 95654228 760807424 -0.8013148904 0.1420869827 1.4406356812 230 9.1600000000 0.0263764989 0.0231512342 0.0565873794 0.0073446280 0.0163120000 200964598 95654228 760807424 -0.7916516066 0.1450527012 1.4477539062 231 9.2000000000 0.0273222793 0.0231692906 0.0565873794 0.0075452443 0.0163170000 201134058 95654228 760807424 -0.7821575999 0.1465450823 1.4534574747 232 9.2400000000 0.0267693847 0.0231848083 0.0565873794 0.0077005264 0.0162760000 201136666 95654228 760807424 -0.7720475793 0.1494556814 1.4621539116 233 9.2800000000 0.0263136849 0.0231982369 0.0565873794 0.0078409401 0.0163050000 201137674 95654228 760807424 -0.7624059916 0.1522986442 1.4703491926 234 9.3200000000 0.0263030734 0.0232115055 0.0565873794 0.0079453957 0.0162730000 201141254 95654228 760807424 -0.7527998686 0.1562370062 1.4780155420 235 9.3600000000 0.0238443539 0.0232141985 0.0565873794 0.0080204289 0.0162660000 201312502 95654228 760807424 -0.7425438166 0.1571419537 1.4867172241 236 9.4000000000 0.0241725873 0.0232182594 0.0565873794 0.0080782619 0.0170490000 201313310 95654228 760807424 -0.7327290773 0.1607173532 1.4953321218 237 9.4400000000 0.0226232614 0.0232157489 0.0565873794 0.0081064459 0.0163260000 201316118 95654228 760807424 -0.7221484780 0.1639552712 1.5029543638 238 9.4800000000 0.0216442924 0.0232091461 0.0565873794 0.0081270374 0.0163010000 201318726 95654228 760807424 -0.7106192112 0.1692799628 1.5109854937 239 9.5200000000 0.0229621027 0.0232081125 0.0565873794 0.0081686028 0.0165180000 201319534 95654228 760807424 -0.7003911138 0.1759685725 1.5184862614 240 9.5600000000 0.0218612421 0.0232025005 0.0565873794 0.0082293670 0.0163410000 201322142 95654228 760807424 -0.6897841096 0.1802068502 1.5284988880 241 9.6000000000 0.0227698702 0.0232007054 0.0565873794 0.0082808180 0.0163850000 201324950 95654228 760807424 -0.6805469990 0.1829254180 1.5396760702 242 9.6400000000 0.0233433861 0.0232012950 0.0565873794 0.0082992332 0.0163270000 201325758 95654228 760807424 -0.6711501479 0.1863381565 1.5508283377 243 9.6800000000 0.0226681400 0.0231991009 0.0565873794 0.0083094436 0.0163560000 201328350 95654228 760807424 -0.6592981219 0.1919754446 1.5569922924 244 9.7200000000 0.0207534917 0.0231890779 0.0565873794 0.0083526987 0.0164290000 201331898 95654228 760807424 -0.6471996307 0.1966625154 1.5652875900 245 9.7600000000 0.0225469898 0.0231864571 0.0565873794 0.0084086751 0.0164500000 201501578 95654228 760807424 -0.6379574537 0.1985706985 1.5668637753 246 9.8000000000 0.0210034586 0.0231775832 0.0565873794 0.0084313545 0.0164480000 201504186 95654228 760807424 -0.6272129416 0.2007794082 1.5781079531 247 9.8400000000 0.0217276104 0.0231717128 0.0565873794 0.0084367811 0.0164570000 201504994 95654228 760807424 -0.6174205542 0.2029023170 1.5901969671 248 9.8800000000 0.0218684785 0.0231664579 0.0565873794 0.0084216554 0.0165360000 201507602 95654228 760807424 -0.6082823873 0.2048221529 1.5991299152 249 9.9200000000 0.0205444880 0.0231559279 0.0565873794 0.0084058345 0.0165000000 201510410 95654228 760807424 -0.5978543162 0.2054613382 1.6056209803 250 9.9600000000 0.0178185645 0.0231345784 0.0565873794 0.0083894860 0.0165670000 201512382 95654228 760807424 -0.5866388083 0.2054536343 1.6152135134 251 10.0000000000 0.0169008486 0.0231097428 0.0565873794 0.0083736586 0.0166150000 201683654 95654228 760807424 -0.5749237537 0.2080725580 1.6230186224 252 10.0400000000 0.0151121160 0.0230780062 0.0565873794 0.0083589780 0.0165170000 201686262 95654228 760807424 -0.5649706125 0.2059015483 1.6337980032 253 10.0800000000 0.0171476062 0.0230545659 0.0565873794 0.0083437796 0.0165230000 201687270 95654228 760807424 -0.5587772727 0.2040656954 1.6427011490 254 10.1200000000 0.0190159865 0.0230386660 0.0565873794 0.0083589480 0.0165640000 201689878 95654228 760807424 -0.5501090884 0.2102445811 1.6534143686 255 10.1600000000 0.0214791819 0.0230325504 0.0565873794 0.0083733372 0.0165230000 201692486 95654228 760807424 -0.5403528810 0.2193801254 1.6621897221 256 10.2000000000 0.0218690168 0.0230280053 0.0565873794 0.0083601801 0.0165130000 201693294 95654228 760807424 -0.5297057033 0.2243788391 1.6705917120 257 10.2400000000 0.0210041013 0.0230201302 0.0565873794 0.0083464509 0.0165110000 201718630 95654228 760807424 -0.5202844739 0.2225656062 1.6778892279 258 10.2800000000 0.0212560203 0.0230132925 0.0565873794 0.0083302750 0.0165580000 201770638 95654228 760807424 -0.5100466609 0.2283672988 1.6879560947 259 10.3200000000 0.0220312513 0.0230095009 0.0565873794 0.0083255446 0.0165600000 201773246 95654228 760807424 -0.5000804067 0.2329246104 1.6946010590 260 10.3600000000 0.0220077671 0.0230056481 0.0565873794 0.0083323446 0.0165740000 201775854 95654228 760807424 -0.4900672734 0.2348663360 1.7042506933 261 10.4000000000 0.0204835031 0.0229959847 0.0565873794 0.0083307125 0.0165520000 201776862 95654228 760807424 -0.4799650311 0.2330179065 1.7116577625 262 10.4400000000 0.0205314141 0.0229865779 0.0565873794 0.0083169493 0.0165340000 201779470 95654228 760807424 -0.4702587724 0.2329406887 1.7168891430 263 10.4800000000 0.0200266801 0.0229753235 0.0565873794 0.0083029131 0.0165450000 201782078 95654228 760807424 -0.4595166445 0.2332550436 1.7213213444 264 10.5200000000 0.0196450707 0.0229627090 0.0565873794 0.0082918538 0.0165000000 201782870 95654228 760807424 -0.4489890039 0.2324612290 1.7270710468 265 10.5600000000 0.0216894690 0.0229579043 0.0565873794 0.0082765799 0.0165710000 201785678 95654228 760807424 -0.4389727414 0.2366356999 1.7347691059 266 10.6000000000 0.0206516702 0.0229492342 0.0565873794 0.0082647409 0.0166180000 201789398 95654228 760807424 -0.4263673723 0.2380422503 1.7389643192 267 10.6400000000 0.0214218069 0.0229435135 0.0565873794 0.0082603399 0.0165870000 201958874 95654228 760807424 -0.4156136811 0.2374270409 1.7421503067 268 10.6800000000 0.0205366481 0.0229345327 0.0565873794 0.0082551382 0.0165890000 201961482 95654228 760807424 -0.4041909873 0.2363156229 1.7497122288 269 10.7200000000 0.0210296754 0.0229274514 0.0565873794 0.0082428584 0.0166020000 201962490 95654228 760807424 -0.3923847079 0.2366111130 1.7516494989 270 10.7600000000 0.0208494943 0.0229197553 0.0565873794 0.0082349473 0.0165950000 201965098 95654228 760807424 -0.3677910864 0.2408265471 1.7629567385 271 10.8000000000 0.0203199610 0.0229101620 0.0565873794 0.0082523134 0.0165470000 201967706 95654228 760807424 -0.3531943262 0.2440717071 1.7662658691 272 10.8400000000 0.0193612073 0.0228971143 0.0565873794 0.0083119263 0.0168450000 201968514 95654228 760807424 -0.3408325613 0.2412162274 1.7697260380 273 10.8800000000 0.0193432607 0.0228840965 0.0565873794 0.0083196233 0.0166890000 201971322 95654228 760807424 -0.3283485174 0.2421998084 1.7754635811 274 10.9200000000 0.0196834020 0.0228724152 0.0565873794 0.0083291771 0.0167040000 201973930 95654228 760807424 -0.3155876696 0.2437502593 1.7804719210 275 10.9600000000 0.0187272206 0.0228573417 0.0565873794 0.0083318984 0.0166830000 201974738 95654228 760807424 -0.3019986451 0.2428949326 1.7824773788 276 11.0000000000 0.0174831711 0.0228378701 0.0565873794 0.0083286565 0.0167510000 201977346 95654228 760807424 -0.2882025540 0.2432290167 1.7857329845 277 11.0400000000 0.0185576621 0.0228224181 0.0565873794 0.0083333157 0.0167240000 201980154 95654228 760807424 -0.2749381363 0.2454714626 1.7879196405 278 11.0800000000 0.0185034629 0.0228068823 0.0565873794 0.0083390923 0.0167150000 201980962 95654228 760807424 -0.2614082992 0.2470571846 1.7912267447 279 11.1200000000 0.0197294764 0.0227958522 0.0565873794 0.0083498396 0.0168030000 201983570 95654228 760807424 -0.2482144386 0.2501976788 1.7961366177 280 11.1600000000 0.0204356182 0.0227874228 0.0565873794 0.0083573181 0.0168250000 201986178 95654228 760807424 -0.2345665395 0.2531746924 1.7988307476 281 11.2000000000 0.0206494592 0.0227798143 0.0565873794 0.0083629991 0.0167970000 201987186 95654228 760807424 -0.2212301791 0.2542213500 1.8008323908 282 11.2400000000 0.0202339403 0.0227707864 0.0565873794 0.0083591847 0.0168980000 201989794 95654228 760807424 -0.2094332874 0.2531380057 1.8069236279 283 11.2800000000 0.0209511593 0.0227643566 0.0565873794 0.0083445561 0.0178120000 201990602 95654228 760807424 -0.1976581216 0.2551265061 1.8099355698 284 11.3200000000 0.0202386137 0.0227554632 0.0565873794 0.0083333667 0.0171330000 201993210 95654228 760807424 -0.1849638075 0.2563909292 1.8152763844 285 11.3600000000 0.0207093712 0.0227482839 0.0565873794 0.0083302097 0.0170460000 201997230 95654228 760807424 -0.1733889729 0.2576700747 1.8180702925 286 11.4000000000 0.0222079325 0.0227463946 0.0565873794 0.0083226142 0.0169220000 202166730 95654228 760807424 -0.1638772488 0.2588826716 1.8221955299 287 11.4400000000 0.0219464749 0.0227436074 0.0565873794 0.0083080703 0.0169780000 202169338 95654228 760807424 -0.1542179734 0.2578119040 1.8250732422 288 11.4800000000 0.0219191331 0.0227407446 0.0565873794 0.0082945408 0.0169680000 202171946 95654228 760807424 -0.1463050544 0.2573199570 1.8303774595 289 11.5200000000 0.0228893068 0.0227412587 0.0565873794 0.0082815851 0.0169530000 202172954 95654228 760807424 -0.1383836269 0.2577302754 1.8360852003 290 11.5600000000 0.0220172405 0.0227387621 0.0565873794 0.0082739631 0.0169790000 202175562 95654228 760807424 -0.1300644726 0.2563151419 1.8406897783 291 11.6000000000 0.0225338861 0.0227380580 0.0565873794 0.0082635803 0.0169800000 202178170 95654228 760807424 -0.1229099408 0.2549737096 1.8463274240 292 11.6400000000 0.0227311179 0.0227380343 0.0565873794 0.0082508163 0.0170360000 202178978 95654228 760807424 -0.1154276431 0.2553741932 1.8516392708 293 11.6800000000 0.0236021448 0.0227409834 0.0565873794 0.0082372216 0.0170160000 202181786 95654228 760807424 -0.1085517481 0.2567702234 1.8581743240 294 11.7200000000 0.0230637901 0.0227420814 0.0565873794 0.0082247143 0.0170320000 202182610 95654228 760807424 -0.1029033735 0.2542050183 1.8650101423 295 11.7600000000 0.0236041117 0.0227450036 0.0565873794 0.0082166229 0.0170950000 202185218 95654228 760807424 -0.0973608196 0.2553754449 1.8724926710 296 11.8000000000 0.0220964532 0.0227428125 0.0565873794 0.0082081184 0.0170460000 202187826 95654228 760807424 -0.0905098692 0.2549461722 1.8801126480 297 11.8400000000 0.0215752479 0.0227388813 0.0565873794 0.0082007448 0.0170310000 202188834 95654228 760807424 -0.0846661031 0.2545692325 1.8874011040 298 11.8800000000 0.0209749509 0.0227329621 0.0565873794 0.0081942832 0.0169890000 202191442 95654228 760807424 -0.0800785124 0.2530172467 1.8960822821 299 11.9200000000 0.0213576183 0.0227283623 0.0565873794 0.0081851744 0.0170000000 202194050 95654228 760807424 -0.0752508342 0.2543687820 1.9059110880 300 11.9600000000 0.0211357083 0.0227230534 0.0565873794 0.0081724845 0.0170750000 202194858 95654228 760807424 -0.0700832382 0.2543623447 1.9129474163 301 12.0000000000 0.0224395525 0.0227221116 0.0565873794 0.0081589769 0.0170970000 202197682 95654228 760807424 -0.0668033734 0.2554899752 1.9226341248 302 12.0400000000 0.0233659092 0.0227242434 0.0565873794 0.0081474289 0.0183490000 202200434 95654228 760807424 -0.0634006411 0.2554724514 1.9312853813 303 12.0800000000 0.0236472562 0.0227272896 0.0565873794 0.0081412643 0.0183320000 202201442 95654228 760807424 -0.0595501587 0.2563642561 1.9420877695 304 12.1200000000 0.0243161786 0.0227325162 0.0565873794 0.0081377036 0.0183780000 202204050 95654228 760807424 -0.0559974164 0.2572835088 1.9522778988 305 12.1600000000 0.0257873777 0.0227425321 0.0565873794 0.0081354311 0.0187980000 202205058 95654228 760807424 -0.0529084690 0.2585605979 1.9629169703 306 12.2000000000 0.0267730299 0.0227557037 0.0565873794 0.0081249766 0.0187560000 202207666 95654228 760807424 -0.0504183322 0.2592127621 1.9751762152 307 12.2400000000 0.0271427240 0.0227699937 0.0565873794 0.0081263023 0.0183900000 202210474 95654228 760807424 -0.0474543795 0.2600343525 1.9863637686 308 12.2800000000 0.0269177407 0.0227834604 0.0565873794 0.0081315001 0.0184500000 202211282 95654228 760807424 -0.0448119752 0.2584626377 1.9956852198 309 12.3200000000 0.0275417045 0.0227988592 0.0565873794 0.0081433908 0.0183920000 202214090 95654228 760807424 -0.0431363843 0.2588330507 2.0064785480 310 12.3600000000 0.0280312337 0.0228157379 0.0565873794 0.0081631385 0.0184060000 202214898 95654228 760807424 -0.0418984443 0.2586444616 2.0183982849 311 12.4000000000 0.0278619919 0.0228319638 0.0565873794 0.0081721912 0.0183980000 202217706 95654228 760807424 -0.0403318293 0.2589431405 2.0300896168 312 12.4400000000 0.0283821952 0.0228497530 0.0565873794 0.0082094691 0.0184810000 202221642 95654228 760807424 -0.0390811190 0.2577539384 2.0533936024 313 12.4800000000 0.0285501275 0.0228679650 0.0565873794 0.0082032893 0.0184410000 202391334 95654228 760807424 -0.0385999009 0.2579027116 2.0643527508 314 12.5200000000 0.0289258026 0.0228872575 0.0565873794 0.0081961694 0.0183260000 202393942 95654228 760807424 -0.0385119282 0.2578634918 2.0774304867 315 12.5600000000 0.0289578084 0.0229065291 0.0565873794 0.0081932542 0.0184070000 202394950 95654228 760807424 -0.0385018624 0.2579255998 2.0893497467 316 12.6000000000 0.0287549496 0.0229250368 0.0565873794 0.0081832236 0.0181910000 202397558 95654228 760807424 -0.0384916328 0.2570085227 2.1006088257 317 12.6400000000 0.0280838348 0.0229413106 0.0565873794 0.0081710485 0.0185170000 202400366 95654228 760807424 -0.0386105329 0.2564157248 2.1138117313 318 12.6800000000 0.0274921674 0.0229556214 0.0565873794 0.0081589317 0.0183510000 202401174 95654228 760807424 -0.0387799777 0.2557792068 2.1256647110 319 12.7200000000 0.0270623062 0.0229684951 0.0565873794 0.0081464700 0.0183830000 202404014 95654228 760807424 -0.0393152498 0.2549001873 2.1347920895 320 12.7600000000 0.0269192513 0.0229808412 0.0565873794 0.0081339810 0.0184190000 202406622 95654228 760807424 -0.0406561121 0.2542268038 2.1445839405 321 12.8000000000 0.0266918950 0.0229924021 0.0565873794 0.0081252209 0.0184250000 202407630 95654228 760807424 -0.0429548807 0.2539358437 2.1575644016 322 12.8400000000 0.0257342923 0.0230009173 0.0565873794 0.0081148622 0.0182510000 202410254 95654228 760807424 -0.0447556227 0.2521415055 2.1671605110 323 12.8800000000 0.0256685372 0.0230091762 0.0565873794 0.0081082942 0.0182290000 202411262 95654228 760807424 -0.0465827137 0.2519668639 2.1772537231 324 12.9200000000 0.0252397470 0.0230160606 0.0565873794 0.0080989497 0.0185480000 202415114 95654228 760807424 -0.0486540683 0.2509743869 2.1881544590 325 12.9600000000 0.0252097044 0.0230228103 0.0565873794 0.0080868059 0.0185170000 202586490 95654228 760807424 -0.0499298945 0.2523369491 2.1984720230 326 13.0000000000 0.0248118769 0.0230282982 0.0565873794 0.0080759817 0.0185460000 202587298 95654228 760807424 -0.0511823893 0.2526832521 2.2080790997 327 13.0400000000 0.0262444466 0.0230381336 0.0565873794 0.0080729987 0.0185790000 202590122 95654228 760807424 -0.0530979112 0.2551290691 2.2220532894 328 13.0800000000 0.0276705883 0.0230522569 0.0565873794 0.0080651236 0.0183520000 202591062 95654228 760807424 -0.0534879528 0.2586265206 2.2327697277 329 13.1200000000 0.0282814279 0.0230681510 0.0565873794 0.0080550513 0.0184020000 202593870 95654228 760807424 -0.0545935929 0.2611975074 2.2417922020 330 13.1600000000 0.0293445066 0.0230871703 0.0565873794 0.0080446919 0.0186670000 202598766 95654228 760807424 -0.0565469600 0.2629839778 2.2500832081 331 13.2000000000 0.0311111696 0.0231114120 0.0565873794 0.0080348987 0.0186160000 202768590 95654228 760807424 -0.0593210123 0.2661905289 2.2577276230 332 13.2400000000 0.0305487104 0.0231338135 0.0565873794 0.0080263249 0.0189210000 202771198 95654228 760807424 -0.0603824705 0.2669572830 2.2654268742 333 13.2800000000 0.0317413509 0.0231596619 0.0565873794 0.0080165063 0.0190420000 202773234 95654228 760807424 -0.0636707768 0.2686642408 2.2711923122 334 13.3200000000 0.0325533114 0.0231877866 0.0565873794 0.0080049048 0.0192050000 202775842 95654228 760807424 -0.0670924932 0.2688298523 2.2751159668 335 13.3600000000 0.0323869959 0.0232152470 0.0565873794 0.0079939775 0.0190570000 202778650 95654228 760807424 -0.0686744303 0.2699536383 2.2818207741 336 13.4000000000 0.0335040465 0.0232458684 0.0565873794 0.0079826239 0.0190630000 202779590 95654228 760807424 -0.0706762820 0.2725278437 2.2871465683 337 13.4400000000 0.0319327936 0.0232716456 0.0565873794 0.0079768759 0.0190940000 202782398 95654228 760807424 -0.0719766691 0.2727188468 2.2933356762 338 13.4800000000 0.0339389034 0.0233032056 0.0565873794 0.0079808673 0.0194700000 202786606 95654228 760807424 -0.0743291751 0.2755677700 2.2962622643 339 13.5200000000 0.0362334028 0.0233413477 0.0565873794 0.0080146966 0.0194210000 202956286 95654228 760807424 -0.0788093656 0.2773222327 2.3029863834 340 13.5600000000 0.0352970511 0.0233765116 0.0565873794 0.0080247431 0.0193920000 202958894 95654228 760807424 -0.0822865665 0.2763213813 2.3128380775 341 13.6000000000 0.0353834778 0.0234117226 0.0565873794 0.0080218859 0.0195380000 202960166 95654228 760807424 -0.0841724202 0.2772068679 2.3174626827 342 13.6400000000 0.0356647335 0.0234475501 0.0565873794 0.0080132651 0.0182470000 202962774 95654228 760807424 -0.0860488191 0.2780115604 2.3218066692 343 13.6800000000 0.0373593755 0.0234881094 0.0565873794 0.0080036217 0.0180420000 202965514 95654228 760807424 -0.0883857906 0.2800486386 2.3251440525 344 13.7200000000 0.0377488025 0.0235295649 0.0565873794 0.0079931412 0.0193480000 202968458 95654228 760807424 -0.0893498957 0.2820871770 2.3295345306 345 13.7600000000 0.0371102877 0.0235689293 0.0565873794 0.0079850662 0.0182720000 203139890 95654228 760807424 -0.0912511572 0.2810961306 2.3352746964 346 13.8000000000 0.0361567177 0.0236053102 0.0565873794 0.0079790245 0.0181990000 203142498 95654228 760807424 -0.0925617665 0.2799133360 2.3403122425 347 13.8400000000 0.0350562036 0.0236383099 0.0565873794 0.0079694725 0.0203300000 203143638 95654228 760807424 -0.0939337462 0.2768000364 2.3419294357 348 13.8800000000 0.0343251266 0.0236690191 0.0565873794 0.0079599958 0.0188960000 203146246 95654228 760807424 -0.0923255906 0.2784414887 2.3443775177 349 13.9200000000 0.0331798606 0.0236962708 0.0565873794 0.0079546079 0.0185130000 203147186 95654228 760807424 -0.0922669545 0.2778708041 2.3498010635 350 13.9600000000 0.0311954264 0.0237176970 0.0565873794 0.0079538040 0.0183260000 203149794 95654228 760807424 -0.0913870782 0.2758262455 2.3581337929 351 14.0000000000 0.0308527146 0.0237380247 0.0565873794 0.0079434582 0.0188770000 203153090 95654228 760807424 -0.0900609717 0.2740429044 2.3585584164 352 14.0400000000 0.0289511476 0.0237528347 0.0565873794 0.0079354294 0.0191130000 203155650 95654228 760807424 -0.0906074420 0.2707588375 2.3636801243 353 14.0800000000 0.0278830510 0.0237645350 0.0565873794 0.0079243924 0.0186040000 203326970 95654228 760807424 -0.0903624967 0.2691067755 2.3685429096 354 14.1200000000 0.0277025476 0.0237756593 0.0565873794 0.0079134220 0.0189020000 203329578 95654228 760807424 -0.0904361010 0.2688831091 2.3733806610 355 14.1600000000 0.0270311031 0.0237848296 0.0565873794 0.0079032284 0.0188910000 203330718 95654228 760807424 -0.0900638327 0.2678246200 2.3786408901 356 14.2000000000 0.0272316691 0.0237945117 0.0565873794 0.0078942976 0.0185780000 203333326 95654228 760807424 -0.0894292220 0.2675578892 2.3825380802 357 14.2400000000 0.0272463020 0.0238041806 0.0565873794 0.0078878216 0.0188280000 203335934 95654228 760807424 -0.0897528976 0.2688418925 2.3894534111 358 14.2800000000 0.0276266672 0.0238148579 0.0565873794 0.0078774718 0.0191180000 203336874 95654228 760807424 -0.0894109830 0.2672213018 2.3933956623 359 14.3200000000 0.0274656229 0.0238250272 0.0565873794 0.0078667350 0.0190070000 203339682 95654228 760807424 -0.0907351077 0.2651402056 2.3995361328 360 14.3600000000 0.0280515421 0.0238367675 0.0565873794 0.0078577578 0.0192810000 203340490 95654228 760807424 -0.0918309391 0.2635174692 2.4053637981 361 14.4000000000 0.0284802318 0.0238496303 0.0565873794 0.0078498649 0.0188580000 203343098 95654228 760807424 -0.0926556289 0.2636440992 2.4120647907 362 14.4400000000 0.0287590809 0.0238631923 0.0565873794 0.0078411964 0.0189080000 203345706 95654228 760807424 -0.0939069837 0.2628587484 2.4187049866 363 14.4800000000 0.0293782130 0.0238783852 0.0565873794 0.0078306661 0.0191150000 203346714 95654228 760807424 -0.0940598324 0.2637346387 2.4251520634 364 14.5200000000 0.0291457400 0.0238928560 0.0565873794 0.0078226559 0.0190420000 203349322 95654228 760807424 -0.0956477076 0.2630417347 2.4342830181 365 14.5600000000 0.0288061928 0.0239063172 0.0565873794 0.0078131931 0.0189960000 203351930 95654228 760807424 -0.0965467468 0.2615707219 2.4419159889 366 14.6000000000 0.0284654647 0.0239187739 0.0565873794 0.0078049078 0.0189920000 203352738 95654228 760807424 -0.0980681106 0.2614835799 2.4518771172 367 14.6400000000 0.0290857852 0.0239328529 0.0565873794 0.0077945251 0.0192700000 203355546 95654228 760807424 -0.0989222303 0.2615601420 2.4585878849 368 14.6800000000 0.0293932762 0.0239476910 0.0565873794 0.0077865586 0.0201340000 203358154 95654228 760807424 -0.0994203612 0.2616217732 2.4657697678 369 14.7200000000 0.0294773169 0.0239626765 0.0565873794 0.0077858731 0.0192170000 203358946 95654228 760807424 -0.1014706120 0.2602957785 2.4745762348 370 14.7600000000 0.0303965658 0.0239800653 0.0565873794 0.0077783844 0.0192010000 203361554 95654228 760807424 -0.1034811065 0.2612169385 2.4845919609 371 14.8000000000 0.0309520978 0.0239988579 0.0565873794 0.0077767984 0.0192210000 203362562 95654228 760807424 -0.1048073694 0.2580126822 2.4912259579 372 14.8400000000 0.0317656137 0.0240197363 0.0565873794 0.0077729335 0.0191560000 203365170 95654228 760807424 -0.1065879986 0.2556830943 2.4991028309 373 14.8800000000 0.0336735621 0.0240456178 0.0565873794 0.0077818714 0.0191460000 203367778 95654228 760807424 -0.1091036946 0.2528674006 2.5065774918 374 14.9200000000 0.0345509984 0.0240737071 0.0565873794 0.0077784898 0.0193390000 203368586 95654228 760807424 -0.1102257371 0.2515736222 2.5138416290 375 14.9600000000 0.0352713913 0.0241035676 0.0565873794 0.0077854344 0.0195570000 203371394 95654228 760807424 -0.1109622642 0.2510654628 2.5215954781 376 15.0000000000 0.0368063487 0.0241373516 0.0565873794 0.0077856657 0.0194920000 203374002 95654228 760807424 -0.1115317270 0.2517136931 2.5288045406 377 15.0400000000 0.0373505428 0.0241723998 0.0565873794 0.0077911687 0.0191150000 203374826 95654228 760807424 -0.1093706265 0.2520047724 2.5404007435 378 15.0800000000 0.0375896730 0.0242078953 0.0565873794 0.0077827894 0.0194010000 203377434 95654228 760807424 -0.1081061289 0.2530948520 2.5482723713 379 15.1200000000 0.0372024029 0.0242421816 0.0565873794 0.0077727643 0.0192470000 203380242 95654228 760807424 -0.1058297455 0.2535758615 2.5539150238 380 15.1600000000 0.0373806730 0.0242767565 0.0565873794 0.0077649426 0.0193600000 203381050 95654228 760807424 -0.1029497534 0.2544275522 2.5581908226 381 15.2000000000 0.0374402367 0.0243113063 0.0565873794 0.0077556190 0.0194730000 203383658 95654228 760807424 -0.1005067155 0.2561683953 2.5628292561 382 15.2400000000 0.0365404747 0.0243433199 0.0565873794 0.0077481661 0.0197840000 203386266 95654228 760807424 -0.0974082872 0.2570837736 2.5678782463 383 15.2800000000 0.0368351750 0.0243759357 0.0565873794 0.0077396779 0.0195060000 203387406 95654228 760807424 -0.0950621217 0.2579314709 2.5724008083 384 15.3200000000 0.0367190130 0.0244080791 0.0565873794 0.0077298796 0.0191340000 203390014 95654228 760807424 -0.0921317860 0.2578332126 2.5761749744 385 15.3600000000 0.0366897136 0.0244399795 0.0565873794 0.0077212489 0.0194660000 203390822 95654228 760807424 -0.0896253064 0.2560272515 2.5788288116 386 15.4000000000 0.0380313098 0.0244751902 0.0565873794 0.0077264933 0.0192060000 203393430 95654228 760807424 -0.0885209665 0.2542375326 2.5834527016 387 15.4400000000 0.0405163579 0.0245166402 0.0565873794 0.0077467719 0.0194420000 203396238 95654228 760807424 -0.0876963586 0.2536109984 2.5892460346 388 15.4800000000 0.0397089384 0.0245557956 0.0565873794 0.0077387186 0.0195000000 203397046 95654228 760807424 -0.0841778517 0.2562521994 2.5914349556 389 15.5200000000 0.0404164754 0.0245965686 0.0565873794 0.0077328933 0.0192660000 203399654 95654228 760807424 -0.0825225562 0.2580981255 2.5934052467 390 15.5600000000 0.0394374877 0.0246346222 0.0565873794 0.0077240105 0.0194560000 203402262 95654228 760807424 -0.0775291994 0.2613340020 2.5931246281 391 15.6000000000 0.0378204025 0.0246683454 0.0565873794 0.0077234949 0.0206170000 203403270 95654228 760807424 -0.0722986311 0.2624287009 2.5915081501 392 15.6400000000 0.0381881855 0.0247028348 0.0565873794 0.0077210515 0.0188530000 203405878 95654228 760807424 -0.0697892532 0.2649733722 2.5914659500 393 15.6800000000 0.0360192470 0.0247316298 0.0565873794 0.0077131808 0.0187300000 203408470 95654228 760807424 -0.0655967072 0.2674570084 2.5946352482 394 15.7200000000 0.0376010053 0.0247642932 0.0565873794 0.0077045891 0.0203270000 203409478 95654228 760807424 -0.0646947101 0.2680466175 2.5950407982 395 15.7600000000 0.0421648584 0.0248083452 0.0565873794 0.0077122612 0.0200650000 203412070 95654228 760807424 -0.0655675679 0.2664288282 2.5914273262 396 15.8000000000 0.0455427393 0.0248607048 0.0565873794 0.0077075763 0.0194180000 203413078 95654228 760807424 -0.0642601028 0.2678707540 2.5883674622 397 15.8400000000 0.0442832224 0.0249096280 0.0565873794 0.0077053433 0.0195960000 203415670 95654228 760807424 -0.0602467917 0.2693590522 2.5905902386 398 15.8800000000 0.0453937165 0.0249610956 0.0565873794 0.0076991191 0.0195150000 203418446 95654228 760807424 -0.0585562512 0.2675265968 2.5903720856 399 15.9200000000 0.0399104692 0.0249985627 0.0565873794 0.0076896523 0.0194310000 203419254 95654228 760807424 -0.0493988357 0.2693127990 2.5948443413 400 15.9600000000 0.0370193608 0.0250286147 0.0565873794 0.0076847411 0.0192490000 203422062 95654228 760807424 -0.0423271880 0.2658783197 2.5922152996 401 16.0000000000 0.0377724729 0.0250603949 0.0565873794 0.0076800015 0.0192620000 203422870 95654228 760807424 -0.0378789604 0.2667598724 2.5899250507 402 16.0400000000 0.0387647711 0.0250944854 0.0565873794 0.0076731005 0.0193530000 203425678 95654228 760807424 -0.0326749794 0.2694863081 2.5891866684 403 16.0800000000 0.0383902080 0.0251274772 0.0565873794 0.0076732969 0.0192420000 203428286 95654228 760807424 -0.0278264582 0.2689540684 2.5913560390 404 16.1200000000 0.0395117179 0.0251630818 0.0565873794 0.0076680504 0.0191130000 203429278 95654228 760807424 -0.0222968422 0.2715559900 2.5870480537 405 16.1600000000 0.0394350402 0.0251983212 0.0565873794 0.0076593762 0.0193040000 203431886 95654228 760807424 -0.0167048667 0.2717693448 2.5882165432 406 16.2000000000 0.0392305776 0.0252328834 0.0565873794 0.0076502153 0.0194850000 203434510 95654228 760807424 -0.0107718157 0.2732481658 2.5911223888 407 16.2400000000 0.0393452607 0.0252675575 0.0565873794 0.0076431322 0.0191510000 203605802 95654228 760807424 -0.0053968113 0.2749546170 2.5929021835 408 16.2800000000 0.0386078879 0.0253002544 0.0565873794 0.0076464212 0.0200270000 203608610 95654228 760807424 0.0001431582 0.2752373517 2.5969543457 409 16.3200000000 0.0379173979 0.0253311032 0.0565873794 0.0076525308 0.0192770000 203609418 95654228 760807424 0.0070617669 0.2778669894 2.6002192497 410 16.3600000000 0.0382113382 0.0253625184 0.0565873794 0.0076436014 0.0191450000 203612210 95654228 760807424 0.0129508469 0.2803321481 2.6041276455 411 16.3999999990 0.0385398604 0.0253945801 0.0565873794 0.0076385925 0.0191840000 203614834 95654228 760807424 0.0168639272 0.2811079323 2.6052114964 412 16.4400000000 0.0381505452 0.0254255411 0.0565873794 0.0076539865 0.0193070000 203617730 95654228 760807424 0.0225079898 0.2817729115 2.6120278835 413 16.4800000000 0.0379336663 0.0254558272 0.0565873794 0.0076678421 0.0192130000 203788994 95654228 760807424 0.0286010727 0.2823696733 2.6191415787 414 16.5200000000 0.0391943753 0.0254890121 0.0565873794 0.0076634672 0.0192380000 203790002 95654228 760807424 0.0324458107 0.2818686366 2.6228594780 415 16.5599999990 0.0404720493 0.0255251158 0.0565873794 0.0076844821 0.0190220000 203792610 95654228 760807424 0.0351257361 0.2757992446 2.6259202957 416 16.6000000000 0.0401386097 0.0255602443 0.0565873794 0.0077609230 0.0192160000 203795418 95654228 760807424 0.0415635817 0.2755727768 2.6319742203 417 16.6400000000 0.0403384008 0.0255956836 0.0565873794 0.0077925918 0.0190310000 203796226 95654228 760807424 0.0476458445 0.2775998712 2.6339004040 418 16.6800000000 0.0410075672 0.0256325541 0.0565873794 0.0077980255 0.0190170000 203800254 95654228 760807424 0.0502512939 0.2773232460 2.6333024502 419 16.7199999990 0.0414260291 0.0256702474 0.0565873794 0.0078284752 0.0190270000 203969758 95654228 760807424 0.0569238290 0.2780424356 2.6382710934 420 16.7600000000 0.0421184041 0.0257094096 0.0565873794 0.0078192611 0.0189560000 203972582 95654228 760807424 0.0631238222 0.2804088891 2.6390287876 421 16.8000000000 0.0416260548 0.0257472164 0.0565873794 0.0078299756 0.0189230000 203975190 95654228 760807424 0.0673226938 0.2757376134 2.6405065060 422 16.8400000000 0.0451784506 0.0257932620 0.0565873794 0.0078312671 0.0190270000 203976198 95654228 760807424 0.0753019005 0.2773567736 2.6435863972 423 16.8799999990 0.0429416895 0.0258338020 0.0565873794 0.0078277228 0.0188180000 203978806 95654228 760807424 0.0827160627 0.2723286748 2.6445724964 424 16.9200000000 0.0408663489 0.0258692561 0.0565873794 0.0078194356 0.0188000000 203980922 95654228 760807424 0.0891224071 0.2657693028 2.6436436176 425 16.9600000000 0.0389282033 0.0258999831 0.0565873794 0.0078183736 0.0188240000 204152226 95654228 760807424 0.0980551168 0.2639743090 2.6420483589 426 17.0000000000 0.0378973372 0.0259281459 0.0565873794 0.0078107410 0.0187430000 204155034 95654228 760807424 0.1073417515 0.2620722353 2.6419076920 427 17.0400000000 0.0365911797 0.0259531178 0.0565873794 0.0078084991 0.0188870000 204155826 95654228 760807424 0.1144038513 0.2584250569 2.6381328106 428 17.0800000000 0.0353945680 0.0259751773 0.0565873794 0.0078001247 0.0189870000 204158634 95654228 760807424 0.1250880361 0.2565324306 2.6360342503 429 17.1200000000 0.0361800864 0.0259989650 0.0565873794 0.0077927170 0.0195860000 204161242 95654228 760807424 0.1349236667 0.2553269565 2.6340506077 430 17.1600000000 0.0340725780 0.0260177408 0.0565873794 0.0077900867 0.0189530000 204162250 95654228 760807424 0.1452522576 0.2524387240 2.6290481091 431 17.2000000000 0.0324187130 0.0260325922 0.0565873794 0.0077811697 0.0188810000 204164858 95654228 760807424 0.1561369300 0.2475407273 2.6263425350 432 17.2400000000 0.0312654376 0.0260447053 0.0565873794 0.0077806016 0.0189710000 204165850 95654228 760807424 0.1688694358 0.2445130050 2.6218626499 433 17.2800000000 0.0306252409 0.0260552839 0.0565873794 0.0077726610 0.0189800000 204169574 95654228 760807424 0.1807299852 0.2428543568 2.6170256138 434 17.3200000000 0.0295498427 0.0260633359 0.0565873794 0.0077641414 0.0188150000 204341050 95654228 760807424 0.1916822046 0.2370170057 2.6076741219 435 17.3600000000 0.0295070522 0.0260712525 0.0565873794 0.0077756613 0.0187100000 204341858 95654228 760807424 0.2048962414 0.2367973626 2.6029603481 436 17.4000000000 0.0289821867 0.0260779289 0.0565873794 0.0077779938 0.0189590000 204344666 95654228 760807424 0.2208654881 0.2396381497 2.5966937542 437 17.4400000000 0.0297450144 0.0260863204 0.0565873794 0.0077767739 0.0186920000 204345458 95654228 760807424 0.2371589392 0.2447529733 2.5885982513 438 17.4800000000 0.0333471000 0.0261028976 0.0565873794 0.0078780456 0.0187480000 204348266 95654228 760807424 0.2474498153 0.2462201267 2.5782229900 439 17.5200000000 0.0340552889 0.0261210124 0.0565873794 0.0080165950 0.0187720000 204350874 95654228 760807424 0.2543576360 0.2410067171 2.5673112869 440 17.5600000000 0.0299070403 0.0261296170 0.0565873794 0.0080419183 0.0188150000 204351882 95654228 760807424 0.2648051977 0.2328198999 2.5592432022 441 17.6000000000 0.0247795396 0.0261265556 0.0565873794 0.0080400807 0.0186830000 204354490 95654228 760807424 0.2774737477 0.2250295281 2.5532586575 442 17.6400000000 0.0239786636 0.0261216961 0.0565873794 0.0081033113 0.0187380000 204355482 95654228 760807424 0.2924733162 0.2274526060 2.5439164639 443 17.6800000000 0.0230398141 0.0261147392 0.0565873794 0.0081200603 0.0187880000 204358090 95654228 760807424 0.3180111647 0.2295584530 2.5295112133 444 17.7200000000 0.0264990330 0.0261156048 0.0565873794 0.0081158404 0.0187010000 204362030 95654228 760807424 0.3246725500 0.2274622172 2.5169224739 445 17.7600000000 0.0285637826 0.0261211063 0.0565873794 0.0081116461 0.0185870000 204531530 95654228 760807424 0.3326011300 0.2237906456 2.5073964596 446 17.8000000000 0.0272207446 0.0261235718 0.0565873794 0.0081027528 0.0186110000 204534338 95654228 760807424 0.3440568447 0.2255064994 2.5002548695 447 17.8400000000 0.0266527291 0.0261247556 0.0565873794 0.0080979021 0.0185470000 204536946 95654228 760807424 0.3527131975 0.2229212970 2.4923439026 448 17.8800000000 0.0256658010 0.0261237312 0.0565873794 0.0080888833 0.0185150000 204537954 95654228 760807424 0.3612390161 0.2210261822 2.4862267971 449 17.9200000000 0.0248128232 0.0261208116 0.0565873794 0.0080800369 0.0185210000 204540562 95654228 760807424 0.3701938093 0.2201655358 2.4793779850 450 17.9600000000 0.0246500075 0.0261175431 0.0565873794 0.0080724379 0.0185500000 204541570 95654228 760807424 0.3771265745 0.2149356008 2.4732098579 451 18.0000000000 0.0177681427 0.0260990300 0.0565873794 0.0080770807 0.0183950000 204544146 95654228 760807424 0.3939909935 0.2150042504 2.4696953297 452 18.0400000000 0.0188260656 0.0260829394 0.0565873794 0.0080709396 0.0183960000 204546954 95654228 760807424 0.4022508860 0.2131768763 2.4625947475 453 18.0800000000 0.0193401650 0.0260680547 0.0565873794 0.0080621259 0.0184040000 204547762 95654228 760807424 0.4096130133 0.2092429101 2.4565238953 454 18.1200000000 0.0196632743 0.0260539472 0.0565873794 0.0080638846 0.0184140000 204550570 95654228 760807424 0.4192821383 0.2091326416 2.4493889809 455 18.1600000000 0.0221947674 0.0260454655 0.0565873794 0.0080567588 0.0183960000 204551378 95654228 760807424 0.4271960855 0.2071471810 2.4428555965 456 18.2000000000 0.0214683712 0.0260354280 0.0565873794 0.0080504497 0.0183600000 204554662 95654228 760807424 0.4366226792 0.2037040889 2.4353029728 457 18.2400000000 0.0210182723 0.0260244496 0.0565873794 0.0080567497 0.0183830000 204725978 95654228 760807424 0.4471164644 0.2022980899 2.4287791252 458 18.2800000000 0.0223091971 0.0260163377 0.0565873794 0.0080692830 0.0183540000 204726986 95654228 760807424 0.4573982656 0.2024694979 2.4262492657 459 18.3200000000 0.0240985025 0.0260121594 0.0565873794 0.0080622823 0.0185010000 204729594 95654228 760807424 0.4681966603 0.2071667314 2.4229705334 460 18.3600000000 0.0275221709 0.0260154420 0.0565873794 0.0080615240 0.0183680000 204730602 95654228 760807424 0.4733235240 0.2031017244 2.4177236557 461 18.4000000000 0.0298823807 0.0260238302 0.0565873794 0.0080542589 0.0184490000 204733210 95654228 760807424 0.4821237624 0.2009989172 2.4143588543 462 18.4400000000 0.0356318243 0.0260446267 0.0565873794 0.0080466736 0.0185010000 204736018 95654228 760807424 0.4878293574 0.2042666376 2.4099459648 463 18.4800000000 0.0355621949 0.0260651830 0.0565873794 0.0080405513 0.0184890000 204736826 95654228 760807424 0.4969316125 0.2016468048 2.4037530422 464 18.5200000000 0.0340397879 0.0260823696 0.0565873794 0.0080335572 0.0183750000 204739634 95654228 760807424 0.5065847635 0.1987878978 2.4004175663 465 18.5600000000 0.0430056900 0.0261187639 0.0565873794 0.0080379957 0.0183780000 204742226 95654228 760807424 0.5059705377 0.1916529834 2.3902876377 466 18.6000000000 0.0480240472 0.0261657709 0.0565873794 0.0080641830 0.0185710000 204743234 95654228 760807424 0.5146329999 0.1903351694 2.3829848766 467 18.6400000000 0.0534166768 0.0262241241 0.0565873794 0.0080632351 0.0184240000 204745842 95654228 760807424 0.5209097266 0.1906195879 2.3781645298 468 18.6800000000 0.0576247126 0.0262912193 0.0576247126 0.0080707515 0.0183670000 204747442 95654228 760807424 0.5278912783 0.1868005246 2.3742876053 469 18.7200000000 0.0590988174 0.0263611716 0.0590988174 0.0080999178 0.0183840000 204918778 95654228 760807424 0.5365723372 0.1828091145 2.3705725670 470 18.7600000000 0.0738058835 0.0264621178 0.0738058835 0.0081729812 0.0186010000 204921586 95654228 760807424 0.5359190106 0.1814618558 2.3580186367 471 18.8000000000 0.0761026070 0.0265675116 0.0761026070 0.0082335802 0.0188060000 204922394 95654228 760807424 0.5450437069 0.1815942377 2.3541722298 472 18.8400000000 0.0729315877 0.0266657406 0.0761026070 0.0082740791 0.0185000000 204925678 95654228 760807424 0.5582470894 0.1833935082 2.3530032635 473 18.8800000000 0.0658931211 0.0267486737 0.0761026070 0.0082794360 0.0184390000 205095190 95654228 760807424 0.5741543174 0.1842655241 2.3531439304 474 18.9200000000 0.0672014505 0.0268340171 0.0761026070 0.0082782737 0.0184680000 205097998 95654228 760807424 0.5786173940 0.1818882376 2.3447690010 475 18.9600000000 0.0666275173 0.0269177929 0.0761026070 0.0082765267 0.0184590000 205100606 95654228 760807424 0.5872265100 0.1783522218 2.3435115814 476 19.0000000000 0.0657280907 0.0269993271 0.0761026070 0.0082819837 0.0183880000 205101614 95654228 760807424 0.5976977348 0.1775670797 2.3416702747 477 19.0400000000 0.0579381920 0.0270641885 0.0761026070 0.0082796010 0.0183470000 205104222 95654228 760807424 0.6125203371 0.1786008179 2.3379497528 478 19.0800000000 0.0578203090 0.0271285318 0.0761026070 0.0082723277 0.0183000000 205105230 95654228 760807424 0.6249932051 0.1800076067 2.3423454762 479 19.1200000000 0.0560274273 0.0271888636 0.0761026070 0.0082657540 0.0183350000 205107838 95654228 760807424 0.6336618662 0.1750198454 2.3418176174 480 19.1600000000 0.0573278144 0.0272516530 0.0761026070 0.0082790359 0.0182770000 205111042 95654228 760807424 0.6439313293 0.1716350764 2.3405981064 481 19.2000000000 0.0547873564 0.0273088998 0.0761026070 0.0082973450 0.0183000000 205280546 95654228 760807424 0.6548737884 0.1716966480 2.3340117931 482 19.2400000000 0.0519380458 0.0273599976 0.0761026070 0.0082897874 0.0184560000 205283354 95654228 760807424 0.6663627625 0.1748773456 2.3385286331 483 19.2800000000 0.0550471246 0.0274173209 0.0761026070 0.0082814793 0.0182880000 205285962 95654228 760807424 0.6716531515 0.1727561951 2.3371071815 484 19.3200000000 0.0524093658 0.0274689573 0.0761026070 0.0082784373 0.0181880000 205286970 95654228 760807424 0.6795206666 0.1723386198 2.3329708576 485 19.3600000000 0.0481340736 0.0275115658 0.0761026070 0.0082748200 0.0183480000 205289578 95654228 760807424 0.6927508712 0.1774468869 2.3309266567 486 19.4000000000 0.0434457883 0.0275443523 0.0761026070 0.0082896206 0.0184150000 205290586 95654228 760807424 0.7076960802 0.1885667294 2.3323223591 487 19.4400000000 0.0431013554 0.0275762969 0.0761026070 0.0083195294 0.0183470000 205293194 95654228 760807424 0.7143352032 0.1831786484 2.3273789883 488 19.4800000000 0.0436722115 0.0276092803 0.0761026070 0.0083197502 0.0182790000 205296002 95654228 760807424 0.7120897174 0.1801173836 2.3217215538 489 19.5200000000 0.0503660068 0.0276558176 0.0761026070 0.0083151571 0.0183290000 205296810 95654228 760807424 0.7083238959 0.1765195429 2.3183963299 490 19.5600000000 0.0513436198 0.0277041600 0.0761026070 0.0083070760 0.0183370000 205299618 95654228 760807424 0.7114663124 0.1774425507 2.3114140034 491 19.6000000000 0.0522460528 0.0277541435 0.0761026070 0.0082993540 0.0183490000 205300842 95654228 760807424 0.7155654430 0.1779121757 2.3101067543 492 19.6400000000 0.0511567444 0.0278017098 0.0761026070 0.0082931536 0.0192350000 205472394 95654228 760807424 0.7180711031 0.1834462881 2.3026497364 493 19.6800000000 0.0500776283 0.0278468942 0.0761026070 0.0082955988 0.0184510000 205475002 95654228 760807424 0.7226712108 0.1869627237 2.2961246967 494 19.7200000000 0.0514036939 0.0278945800 0.0761026070 0.0082945582 0.0183980000 205476010 95654228 760807424 0.7232043147 0.1833150983 2.2886068821 495 19.7600000000 0.0528742522 0.0279450440 0.0761026070 0.0082874992 0.0183500000 205478618 95654228 760807424 0.7219395041 0.1811359376 2.2789955139 496 19.8000000000 0.0515917428 0.0279927188 0.0761026070 0.0082842635 0.0183330000 205479626 95654228 760807424 0.7223705053 0.1813265234 2.2719154358 497 19.8400000000 0.0527562015 0.0280425447 0.0761026070 0.0082765568 0.0183640000 205482234 95654228 760807424 0.7254776359 0.1805912852 2.2668237686 498 19.8800000000 0.0540338829 0.0280947362 0.0761026070 0.0082692135 0.0183800000 205485042 95654228 760807424 0.7222864032 0.1792025864 2.2579185963 499 19.9200000000 0.0579905696 0.0281546477 0.0761026070 0.0082613243 0.0184220000 205485866 95654228 760807424 0.7204641700 0.1804393977 2.2546143532 500 19.9600000000 0.0641310439 0.0282266004 0.0761026070 0.0082546257 0.0184640000 205488674 95654228 760807424 0.7164581418 0.1835975796 2.2487406731 501 20.0000000000 0.0663907975 0.0283027765 0.0761026070 0.0082475727 0.0184400000 205491282 95654228 760807424 0.7168720961 0.1842797101 2.2413072586 502 20.0400000000 0.0683225468 0.0283824971 0.0761026070 0.0082400117 0.0184110000 205492290 95654228 760807424 0.7186279893 0.1819302738 2.2383303642 503 20.0800000000 0.0715601072 0.0284683373 0.0761026070 0.0082323132 0.0184440000 205494930 95654228 760807424 0.7199138999 0.1854435205 2.2291157246 504 20.1200000000 0.0759124681 0.0285624725 0.0761026070 0.0082275012 0.0184480000 205495938 95654228 760807424 0.7184571624 0.1883708537 2.2204337120 505 20.1600000000 0.0787077546 0.0286617701 0.0787077546 0.0082224987 0.0184110000 205499510 95654228 760807424 0.7108942866 0.1854936481 2.2095818520 506 20.2000000000 0.0821171105 0.0287674131 0.0821171105 0.0082172251 0.0184350000 205670822 95654228 760807424 0.7079578042 0.1891743690 2.2028756142 507 20.2400000000 0.0855931789 0.0288794954 0.0855931789 0.0082192701 0.0184500000 205671646 95654228 760807424 0.7079187632 0.1941610873 2.1949453354 508 20.2800000000 0.0868908092 0.0289936909 0.0868908092 0.0082221030 0.0184420000 205674454 95654228 760807424 0.7010574937 0.1944509745 2.1854417324 509 20.3200000000 0.0871760100 0.0291079980 0.0871760100 0.0082146799 0.0184560000 205675262 95654228 760807424 0.7047740817 0.1943482459 2.1747121811 510 20.3600000000 0.0935930386 0.0292344393 0.0935930386 0.0082074371 0.0184660000 205678070 95654228 760807424 0.7055594921 0.1998813748 2.1630504131 511 20.4000000000 0.0995984003 0.0293721379 0.0995984003 0.0082023956 0.0184910000 205680678 95654228 760807424 0.7044994831 0.2072630227 2.1539154053 512 20.4400000000 0.1029325277 0.0295158105 0.1029325277 0.0082221206 0.0186870000 205681686 95654228 760807424 0.7032976151 0.2123113275 2.1465556622 513 20.4800000000 0.1034476310 0.0296599271 0.1034476310 0.0082216007 0.0185920000 205729366 95654228 760807424 0.7061236501 0.2097916305 2.1343488693 514 20.5200000000 0.1059393436 0.0298083306 0.1059393436 0.0082146771 0.0185730000 205832774 95654228 760807424 0.7052205205 0.2125158608 2.1228568554 515 20.5600000000 0.1135280579 0.0299708932 0.1135280579 0.0082179943 0.0185650000 205835382 95654228 760807424 0.7068408132 0.2211613953 2.1129937172 516 20.6000000000 0.1183032617 0.0301420800 0.1183032617 0.0082262764 0.0185610000 205838786 95654228 760807424 0.7094267011 0.2249070108 2.1036446095 517 20.6400000000 0.1207880378 0.0303174106 0.1207880378 0.0082280112 0.0185690000 206008314 95654228 760807424 0.7049737573 0.2262011915 2.1044728756 518 20.6800000000 0.1230568364 0.0304964443 0.1230568364 0.0082209859 0.0185170000 206011122 95654228 760807424 0.7164846659 0.2251745909 2.0871949196 519 20.7200000000 0.1302772313 0.0306887001 0.1302772313 0.0082193853 0.0186290000 206013730 95654228 760807424 0.7029333711 0.2336901426 2.0923628807 520 20.7600000000 0.1283445656 0.0308764999 0.1302772313 0.0082225172 0.0185210000 206014738 95654228 760807424 0.6995421052 0.2368188351 2.0911898613 521 20.8000000000 0.1215157583 0.0310504716 0.1302772313 0.0082303599 0.0185630000 206017346 95654228 760807424 0.7014290690 0.2298478633 2.0813934803 522 20.8400000000 0.1169736907 0.0312150755 0.1302772313 0.0082261091 0.0186040000 206018354 95654228 760807424 0.7081633806 0.2253063470 2.0723550320 523 20.8800000000 0.1150314659 0.0313753362 0.1302772313 0.0082206006 0.0186250000 206020962 95654228 760807424 0.6996219158 0.2242973447 2.0755188465 524 20.9200000000 0.1204941496 0.0315454103 0.1302772313 0.0082162080 0.0186720000 206023770 95654228 760807424 0.7103967071 0.2241817862 2.0593049526 525 20.9600000000 0.1244008020 0.0317222777 0.1302772313 0.0082099171 0.0186670000 206024578 95654228 760807424 0.7052100897 0.2234048843 2.0564546585 526 21.0000000000 0.1285984963 0.0319064530 0.1302772313 0.0082036355 0.0186200000 206027402 95654228 760807424 0.7083779573 0.2198096961 2.0464239120 527 21.0400000000 0.1294014454 0.0320914530 0.1302772313 0.0082079750 0.0185350000 206028210 95654228 760807424 0.7092029452 0.2222017199 2.0357656479 528 21.0800000000 0.1315909475 0.0322798990 0.1315909475 0.0082008528 0.0186420000 206031018 95654228 760807424 0.7110648155 0.2235848606 2.0317716599 529 21.1200000000 0.1381994337 0.0324801250 0.1381994337 0.0081967680 0.0186470000 206033626 95654228 760807424 0.7178729773 0.2209499329 2.0182199478 530 21.1600000000 0.1386979520 0.0326805360 0.1386979520 0.0081920500 0.0187090000 206034634 95654228 760807424 0.7136183977 0.2210164666 2.0166158676 531 21.2000000000 0.1471720189 0.0328961508 0.1471720189 0.0081872027 0.0187710000 206038162 95654228 760807424 0.7186442018 0.2256204933 2.0081367493 532 21.2400000000 0.1491644830 0.0331147003 0.1491644830 0.0081800668 0.0187900000 206207906 95654228 760807424 0.7180752158 0.2241171449 2.0032861233 533 21.2800000000 0.1496374160 0.0333333171 0.1496374160 0.0081733653 0.0187820000 206210514 95654228 760807424 0.7164403200 0.2229437381 1.9991455078 534 21.3200000000 0.1537881941 0.0335588880 0.1537881941 0.0081690240 0.0196990000 206213322 95654228 760807424 0.7205073237 0.2229533643 1.9859820604 535 21.3600000000 0.1567091942 0.0337890755 0.1567091942 0.0081643717 0.0188770000 206214146 95654228 760807424 0.7249085903 0.2273712307 1.9729367495 536 21.4000000000 0.1570030004 0.0340189522 0.1570030004 0.0081576592 0.0189040000 206216954 95654228 760807424 0.7227040529 0.2270982713 1.9692552090 537 21.4400000000 0.1592987627 0.0342522479 0.1592987627 0.0081506381 0.0188520000 206219562 95654228 760807424 0.7278833985 0.2253084481 1.9536291361 538 21.4800000000 0.1586080194 0.0344833925 0.1592987627 0.0081437480 0.0188450000 206220570 95654228 760807424 0.7273176312 0.2231260985 1.9454332590 539 21.5200000000 0.1584765315 0.0347134354 0.1592987627 0.0081366937 0.0189640000 206223194 95654228 760807424 0.7248227596 0.2219754457 1.9372565746 540 21.5600000000 0.1596210897 0.0349447459 0.1596210897 0.0081304442 0.0190320000 206224202 95654228 760807424 0.7281928658 0.2247669250 1.9239057302 541 21.6000000000 0.1584955156 0.0351731207 0.1596210897 0.0081234633 0.0188680000 206226810 95654228 760807424 0.7294283509 0.2248266786 1.9148545265 542 21.6400000000 0.1595327705 0.0354025666 0.1596210897 0.0081210502 0.0189280000 206229618 95654228 760807424 0.7324721217 0.2238408923 1.9034401178 543 21.6800000000 0.1589503139 0.0356300946 0.1596210897 0.0081140020 0.0189500000 206230442 95654228 760807424 0.7330446839 0.2199055851 1.8979114294 544 21.7200000000 0.1588761359 0.0358566499 0.1596210897 0.0081121628 0.0189410000 206233250 95654228 760807424 0.7340833545 0.2205027044 1.8885989189 545 21.7600000000 0.1589213759 0.0360824567 0.1596210897 0.0081084581 0.0190290000 206235170 95654228 760807424 0.7373022437 0.2196343690 1.8770427704 546 21.8000000000 0.1572288424 0.0363043365 0.1596210897 0.0081120392 0.0189630000 206406722 95654228 760807424 0.7392565012 0.2180281430 1.8706793785 547 21.8400000000 0.1572830081 0.0365255041 0.1596210897 0.0081098518 0.0189990000 206409330 95654228 760807424 0.7415386438 0.2196540385 1.8591148853 548 21.8800000000 0.1573056132 0.0367459058 0.1596210897 0.0081032751 0.0190220000 206410338 95654228 760807424 0.7399807572 0.2213776410 1.8558802605 549 21.9200000000 0.1564205587 0.0369638924 0.1596210897 0.0080973165 0.0190160000 206412946 95654228 760807424 0.7406963110 0.2187697589 1.8493067026 550 21.9600000000 0.1563248038 0.0371809122 0.1596210897 0.0080909153 0.0190440000 206413954 95654228 760807424 0.7398943305 0.2200699300 1.8432580233 551 22.0000000000 0.1564558595 0.0373973822 0.1596210897 0.0080846093 0.0190710000 206416562 95654228 760807424 0.7408019900 0.2212189436 1.8349691629 552 22.0400000000 0.1568888277 0.0376138522 0.1596210897 0.0080777751 0.0191400000 206419370 95654228 760807424 0.7444393635 0.2232130617 1.8277812004 553 22.0800000000 0.1590888202 0.0378335176 0.1596210897 0.0080740663 0.0190590000 206420178 95654228 760807424 0.7422874570 0.2254196256 1.8258938789 554 22.1200000000 0.1611881703 0.0380561794 0.1611881703 0.0080676088 0.0199860000 206422986 95654228 760807424 0.7421019077 0.2259252518 1.8195189238 555 22.1600000000 0.1618216932 0.0382791804 0.1618216932 0.0080609220 0.0191360000 206425594 95654228 760807424 0.7428931594 0.2292214036 1.8128045797 556 22.2000000000 0.1606704593 0.0384993086 0.1618216932 0.0080557510 0.0190980000 206426602 95654228 760807424 0.7426196933 0.2298574001 1.8038170338 557 22.2400000000 0.1603439897 0.0387180602 0.1618216932 0.0080620580 0.0191080000 206430186 95654228 760807424 0.7420873642 0.2262834460 1.8003402948 558 22.2800000000 0.1592857689 0.0389341314 0.1618216932 0.0080551904 0.0191150000 206599942 95654228 760807424 0.7405177355 0.2220691144 1.7944179773 559 22.3200000000 0.1598893702 0.0391505093 0.1618216932 0.0080501670 0.0191050000 206602550 95654228 760807424 0.7393702269 0.2242702395 1.7900843620 560 22.3600000000 0.1618629098 0.0393696386 0.1618629098 0.0080444035 0.0192120000 206605358 95654228 760807424 0.7375102043 0.2264483124 1.7875655890 561 22.4000000000 0.1638973355 0.0395916131 0.1638973355 0.0080383628 0.0193770000 206606166 95654228 760807424 0.7395749688 0.2263883799 1.7811443806 562 22.4400000000 0.1636979729 0.0398124429 0.1638973355 0.0080319227 0.0191890000 206608974 95654228 760807424 0.7388716936 0.2268776149 1.7793771029 563 22.4800000000 0.1649489254 0.0400347102 0.1649489254 0.0080264662 0.0192100000 206609782 95654228 760807424 0.7401140332 0.2278252393 1.7708330154 564 22.5200000000 0.1657355875 0.0402575841 0.1657355875 0.0080223372 0.0192640000 206612590 95654228 760807424 0.7405197620 0.2264986932 1.7657902241 565 22.5600000000 0.1669526249 0.0404818231 0.1669526249 0.0080157356 0.0192930000 206615198 95654228 760807424 0.7426097393 0.2226973623 1.7565025091 566 22.6000000000 0.1649425775 0.0407017184 0.1669526249 0.0080115868 0.0191830000 206616338 95654228 760807424 0.7442130446 0.2196577489 1.7494133711 567 22.6400000000 0.1657240391 0.0409222163 0.1669526249 0.0080054933 0.0193200000 206620526 95654228 760807424 0.7451015711 0.2165634930 1.7464468479 568 22.6800000000 0.1662569046 0.0411428760 0.1669526249 0.0079986071 0.0192720000 206790290 95654228 760807424 0.7473241091 0.2139930129 1.7388831377 569 22.7200000000 0.1643520743 0.0413594124 0.1669526249 0.0079952659 0.0192170000 206792898 95654228 760807424 0.7498636842 0.2100373805 1.7278125286 570 22.7600000000 0.1628177911 0.0415724972 0.1669526249 0.0079929658 0.0192380000 206795706 95654228 760807424 0.7493607402 0.2113503814 1.7171274424 571 22.8000000000 0.1621330529 0.0417836366 0.1669526249 0.0079871133 0.0193030000 206796514 95654228 760807424 0.7494885325 0.2138821036 1.7078379393 572 22.8400000000 0.1618535370 0.0419935490 0.1669526249 0.0079837922 0.0192810000 206799322 95654228 760807424 0.7504333854 0.2104559988 1.6991366148 573 22.8800000000 0.1617806703 0.0422026015 0.1669526249 0.0079809022 0.0193560000 206801930 95654228 760807424 0.7506318688 0.2106982768 1.6896047592 574 22.9200000000 0.1607007533 0.0424090443 0.1669526249 0.0079745557 0.0193160000 206802938 95654228 760807424 0.7484021187 0.2099766284 1.6832475662 575 22.9600000000 0.1614994109 0.0426161580 0.1669526249 0.0079689673 0.0193390000 206805546 95654228 760807424 0.7472250462 0.2075000852 1.6744952202 576 23.0000000000 0.1601710767 0.0428202464 0.1669526249 0.0079646263 0.0193150000 206806554 95654228 760807424 0.7460151315 0.2005317956 1.6676391363 577 23.0400000000 0.1589643210 0.0430215360 0.1669526249 0.0079656811 0.0192970000 206809162 95654228 760807424 0.7449369431 0.2006158382 1.6579126120 578 23.0800000000 0.1600216925 0.0432239584 0.1669526249 0.0079589157 0.0193040000 206811970 95654228 760807424 0.7437090278 0.1998068541 1.6499271393 579 23.1200000000 0.1612557620 0.0434278130 0.1669526249 0.0079523965 0.0193230000 206812778 95654228 760807424 0.7426629066 0.1965335310 1.6427478790 580 23.1600000000 0.1623608619 0.0436328699 0.1669526249 0.0079462420 0.0193630000 206815570 95654228 760807424 0.7417320609 0.1946283877 1.6345423460 581 23.2000000000 0.1618701816 0.0438363765 0.1669526249 0.0079398690 0.0193280000 206816378 95654228 760807424 0.7405628562 0.1943617910 1.6250803471 582 23.2400000000 0.1632516384 0.0440415574 0.1669526249 0.0079347058 0.0193340000 206819186 95654228 760807424 0.7391055226 0.1919467449 1.6163543463 583 23.2800000000 0.1610522270 0.0442422618 0.1669526249 0.0079290928 0.0193300000 206821794 95654228 760807424 0.7397726178 0.1866316199 1.6059094667 584 23.3200000000 0.1588065922 0.0444384336 0.1669526249 0.0079322144 0.0193910000 206822802 95654228 760807424 0.7385290265 0.1855378598 1.5927903652 585 23.3600000000 0.1589624584 0.0446342011 0.1669526249 0.0079262883 0.0194670000 206826794 95654228 760807424 0.7373631001 0.1837952435 1.5825870037 586 23.4000000000 0.1586074084 0.0448286947 0.1669526249 0.0079214267 0.0194360000 206996558 95654228 760807424 0.7370350361 0.1789297909 1.5721999407 587 23.4400000000 0.1564390063 0.0450188315 0.1669526249 0.0079268750 0.0194750000 206999182 95654228 760807424 0.7366376519 0.1765137315 1.5613312721 588 23.4800000000 0.1565328538 0.0452084812 0.1669526249 0.0079366560 0.0195090000 207001990 95654228 760807424 0.7347819805 0.1790141463 1.5347046852 589 23.5200000000 0.1557598561 0.0453961745 0.1669526249 0.0079305619 0.0195510000 207002798 95654228 760807424 0.7332142591 0.1791242659 1.5248737335 590 23.5600000000 0.1530842334 0.0455786966 0.1669526249 0.0079273065 0.0195670000 207005606 95654228 760807424 0.7319855690 0.1786709279 1.5116940737 591 23.6000000000 0.1535992026 0.0457614725 0.1669526249 0.0079272206 0.0195900000 207008478 95654228 760807424 0.7311874032 0.1784928739 1.5000075102 592 23.6400000000 0.1517935693 0.0459405807 0.1669526249 0.0079213209 0.0195980000 207009486 95654228 760807424 0.7309424281 0.1764669716 1.4839119911 593 23.6800000000 0.1485436410 0.0461136044 0.1669526249 0.0079198257 0.0196850000 207012094 95654228 760807424 0.7302351594 0.1742168367 1.4689711332 594 23.7200000000 0.1448324323 0.0462797978 0.1669526249 0.0079186205 0.0204600000 207013102 95654228 760807424 0.7299630642 0.1714325696 1.4542815685 595 23.7600000000 0.1436577588 0.0464434582 0.1669526249 0.0079162053 0.0197850000 207015710 95654228 760807424 0.7280483246 0.1697369367 1.4444578886 596 23.8000000000 0.1444553286 0.0466079076 0.1669526249 0.0079121954 0.0196950000 207018518 95654228 760807424 0.7264143825 0.1699270010 1.4337947369 597 23.8400000000 0.1447916180 0.0467723695 0.1669526249 0.0079064261 0.0198430000 207021618 95654228 760807424 0.7240251303 0.1729799956 1.4232915640 598 23.8800000000 0.1451416761 0.0469368666 0.1669526249 0.0079006799 0.0199050000 207193166 95654228 760807424 0.7229449749 0.1735433489 1.4103256464 599 23.9200000000 0.1424293220 0.0470962864 0.1669526249 0.0078952849 0.0198830000 207193974 95654228 760807424 0.7209024429 0.1741003096 1.3979659081 600 23.9600000000 0.1415933818 0.0472537816 0.1669526249 0.0078916811 0.0198780000 207196782 95654228 760807424 0.7193292379 0.1734239608 1.3863722086 601 24.0000000000 0.1415702999 0.0474107142 0.1669526249 0.0078857395 0.0199000000 207199390 95654228 760807424 0.7169583440 0.1738734543 1.3764262199 602 24.0400000000 0.1417752653 0.0475674660 0.1669526249 0.0078793673 0.0199420000 207200530 95654228 760807424 0.7152491808 0.1735639870 1.3646562099 603 24.0800000000 0.1400108635 0.0477207718 0.1669526249 0.0078736121 0.0198950000 207203138 95654228 760807424 0.7124314308 0.1715759188 1.3551213741 604 24.1200000000 0.1396482140 0.0478729695 0.1669526249 0.0078674713 0.0199710000 207204146 95654228 760807424 0.7093684673 0.1732381731 1.3458743095 605 24.1600000000 0.1384894848 0.0480227489 0.1669526249 0.0078622644 0.0199970000 207206754 95654228 760807424 0.7065996528 0.1699422896 1.3370481730 606 24.2000000000 0.1391281486 0.0481730878 0.1669526249 0.0078560947 0.0199910000 207209562 95654228 760807424 0.7041949034 0.1693823338 1.3290942907 607 24.2400000000 0.1400512606 0.0483244522 0.1669526249 0.0078500720 0.0199690000 207210370 95654228 760807424 0.7022464275 0.1694878042 1.3175150156 608 24.2800000000 0.1395327598 0.0484744659 0.1669526249 0.0078439946 0.0201880000 207213178 95654228 760807424 0.6995867491 0.1700637490 1.3090671301 609 24.3200000000 0.1387471557 0.0486226969 0.1669526249 0.0078411434 0.0200900000 207215918 95654228 760807424 0.6981205940 0.1648060232 1.3005679846 610 24.3600000000 0.1403462738 0.0487730634 0.1669526249 0.0078352485 0.0200870000 207216926 95654228 760807424 0.6959758401 0.1624731570 1.2936363220 611 24.4000000000 0.1403696984 0.0489229761 0.1669526249 0.0078354813 0.0201260000 207219534 95654228 760807424 0.6948149800 0.1626328379 1.2796353102 612 24.4400000000 0.1388765424 0.0490699590 0.1669526249 0.0078314215 0.0201660000 207220542 95654228 760807424 0.6923875213 0.1619729549 1.2694135904 613 24.4800000000 0.1388028711 0.0492163422 0.1669526249 0.0078267847 0.0204770000 207223150 95654228 760807424 0.6903485060 0.1583269387 1.2629923820 614 24.5200000000 0.1398931295 0.0493640243 0.1669526249 0.0078207355 0.0216910000 207226090 95654228 760807424 0.6886221766 0.1559002995 1.2518222332 615 24.5600000000 0.1407646835 0.0495126433 0.1669526249 0.0078148169 0.0209450000 207226898 95654228 760807424 0.6872044802 0.1548859477 1.2444458008 616 24.6000000000 0.1411640942 0.0496614281 0.1669526249 0.0078090797 0.0210390000 207229706 95654228 760807424 0.6859681606 0.1519913673 1.2343091965 617 24.6400000000 0.1391495466 0.0498064655 0.1669526249 0.0078078412 0.0209290000 207230514 95654228 760807424 0.6843881607 0.1476799995 1.2224690914 618 24.6800000000 0.1392275691 0.0499511599 0.1669526249 0.0078061281 0.0210760000 207235890 95654228 760807424 0.6834481359 0.1447712332 1.2104915380 619 24.7200000000 0.1388562173 0.0500947868 0.1669526249 0.0078068383 0.0210230000 207407286 95654228 760807424 0.6827087402 0.1429401040 1.1956541538 620 24.7600000000 0.1391406208 0.0502384091 0.1669526249 0.0078032594 0.0210530000 207408294 95654228 760807424 0.6800780892 0.1433254778 1.1876175404 621 24.8000000000 0.1396401078 0.0503823732 0.1669526249 0.0077977657 0.0211170000 207410902 95654228 760807424 0.6788428426 0.1439480931 1.1777365208 622 24.8400000000 0.1386911422 0.0505243487 0.1669526249 0.0077920837 0.0211370000 207412042 95654228 760807424 0.6773002744 0.1408113539 1.1665894985 623 24.8800000000 0.1381305903 0.0506649687 0.1669526249 0.0077881771 0.0211520000 207414650 95654228 760807424 0.6753398776 0.1397773772 1.1562592983 624 24.9200000000 0.1361772865 0.0508020077 0.1669526249 0.0077841649 0.0212050000 207417458 95654228 760807424 0.6731827259 0.1403754205 1.1431717873 625 24.9600000000 0.1371413618 0.0509401506 0.1669526249 0.0077785760 0.0212080000 207418398 95654228 760807424 0.6705917120 0.1405263543 1.1338119507 626 25.0000000000 0.1371759474 0.0510779075 0.1669526249 0.0077736733 0.0212240000 207421206 95654228 760807424 0.6687598825 0.1384498775 1.1245230436 627 25.0400000000 0.1357374638 0.0512129307 0.1669526249 0.0077701810 0.0212100000 207423814 95654228 760807424 0.6663864255 0.1361999810 1.1138658524 628 25.0800000000 0.1345670521 0.0513456602 0.1669526249 0.0077651784 0.0214160000 207424822 95654228 760807424 0.6632114053 0.1377515495 1.1032098532 629 25.1200000000 0.1345777214 0.0514779846 0.1669526249 0.0077627889 0.0215620000 207429694 95654228 760807424 0.6607549787 0.1353092790 1.0979373455 630 25.1600000000 0.1355192512 0.0516113835 0.1669526249 0.0077572772 0.0214090000 207599494 95654228 760807424 0.6573140025 0.1358945370 1.0897486210 631 25.2000000000 0.1350896060 0.0517436786 0.1669526249 0.0077526776 0.0213570000 207602102 95654228 760807424 0.6536132693 0.1363555342 1.0811581612 632 25.2400000000 0.1335575730 0.0518731309 0.1669526249 0.0077499701 0.0214770000 207604910 95654228 760807424 0.6502697468 0.1351404339 1.0736036301 633 25.2800000000 0.1326476336 0.0520007368 0.1669526249 0.0077454140 0.0214110000 207605718 95654228 760807424 0.6466825008 0.1348253787 1.0628421307 634 25.3200000000 0.1320148110 0.0521269420 0.1669526249 0.0077432972 0.0213980000 207608526 95654228 760807424 0.6418631077 0.1350730509 1.0550769567 635 25.3600000000 0.1316701621 0.0522522069 0.1669526249 0.0077434408 0.0213960000 207609334 95654228 760807424 0.6380693316 0.1354626119 1.0490568876 636 25.4000000000 0.1303120255 0.0523749424 0.1669526249 0.0077445528 0.0214030000 207612142 95654228 760807424 0.6349335313 0.1315836906 1.0394018888 637 25.4400000000 0.1295581907 0.0524961092 0.1669526249 0.0077392022 0.0213470000 207614750 95654228 760807424 0.6309670806 0.1318331212 1.0317813158 638 25.4800000000 0.1291716695 0.0526162904 0.1669526249 0.0077343855 0.0214000000 207615758 95654228 760807424 0.6277952790 0.1298389137 1.0236252546 639 25.5200000000 0.1289173812 0.0527356974 0.1669526249 0.0077293207 0.0213870000 207618366 95654228 760807424 0.6229452491 0.1290840358 1.0171544552 640 25.5600000000 0.1271770447 0.0528520120 0.1669526249 0.0077245302 0.0213770000 207619374 95654228 760807424 0.6192253232 0.1262715906 1.0099636316 641 25.6000000000 0.1277012676 0.0529687815 0.1669526249 0.0077189523 0.0214210000 207621982 95654228 760807424 0.6145566702 0.1252366751 1.0044906139 642 25.6400000000 0.1274162978 0.0530847434 0.1669526249 0.0077142447 0.0214660000 207624790 95654228 760807424 0.6093953848 0.1245569065 0.9991277456 643 25.6800000000 0.1270388514 0.0531997575 0.1669526249 0.0077090479 0.0213840000 207625598 95654228 760807424 0.6047646999 0.1229064092 0.9920235276 644 25.7200000000 0.1275610775 0.0533152254 0.1669526249 0.0077030771 0.0214170000 207628406 95654228 760807424 0.5994697809 0.1219553724 0.9881565571 645 25.7600000000 0.1275512129 0.0534303200 0.1669526249 0.0076973238 0.0213910000 207631014 95654228 760807424 0.5947720408 0.1196622401 0.9822682142 646 25.8000000000 0.1263665259 0.0535432243 0.1669526249 0.0076919827 0.0215010000 207634682 95654228 760807424 0.5885953307 0.1179628149 0.9770958424 647 25.8400000000 0.1249457747 0.0536535837 0.1669526249 0.0076864748 0.0214400000 207805978 95654228 760807424 0.5817486048 0.1178283468 0.9700933695 648 25.8800000000 0.1243871450 0.0537627405 0.1669526249 0.0076846333 0.0214210000 207806986 95654228 760807424 0.5752349496 0.1169404462 0.9652335048 649 25.9200000000 0.1239967868 0.0538709593 0.1669526249 0.0076823839 0.0214310000 207809594 95654228 760807424 0.5681829453 0.1141264513 0.9600870609 650 25.9600000000 0.1249090359 0.0539802487 0.1669526249 0.0076783705 0.0215690000 207812402 95654228 760807424 0.5550206900 0.1087352559 0.9524784684 651 26.0000000000 0.1240401492 0.0540878676 0.1669526249 0.0076827963 0.0219510000 207813210 95654228 760807424 0.5384699106 0.1088154316 0.9418886900 652 26.0400000000 0.1220340878 0.0541920796 0.1669526249 0.0076783473 0.0214780000 207816018 95654228 760807424 0.5290324688 0.1088193282 0.9337860942 653 26.0800000000 0.1203787178 0.0542934374 0.1669526249 0.0076772392 0.0214850000 207816826 95654228 760807424 0.5191293955 0.1104979217 0.9281755686 654 26.1200000000 0.1189863235 0.0543923562 0.1669526249 0.0076798006 0.0214880000 207819634 95654228 760807424 0.5091300607 0.1105142385 0.9228394628 655 26.1600000000 0.1190110818 0.0544910107 0.1669526249 0.0076752785 0.0214450000 207822242 95654228 760807424 0.4997218847 0.1081678495 0.9172615409 656 26.2000000000 0.1183545515 0.0545883637 0.1669526249 0.0076754438 0.0215880000 207823250 95654228 760807424 0.4893477261 0.1092777401 0.9122288823 657 26.2400000000 0.1172010303 0.0546836645 0.1669526249 0.0076765104 0.0216670000 207825858 95654228 760807424 0.4790597558 0.1097215712 0.9071469903 658 26.2800000000 0.1163772270 0.0547774237 0.1669526249 0.0076788532 0.0216510000 207826866 95654228 760807424 0.4682295322 0.1112453490 0.9016386271 659 26.3200000000 0.1150404587 0.0548688699 0.1669526249 0.0076757990 0.0215000000 207829474 95654228 760807424 0.4567761123 0.1132272258 0.8972058892 660 26.3600000000 0.1143554971 0.0549590012 0.1669526249 0.0076706719 0.0214910000 207832282 95654228 760807424 0.4461558759 0.1141083091 0.8929316998 661 26.4000000000 0.1132905707 0.0550472486 0.1669526249 0.0076656053 0.0211550000 207833090 95654228 760807424 0.4344330728 0.1162282005 0.8879417777 662 26.4400000000 0.1125656143 0.0551341344 0.1669526249 0.0076641780 0.0208740000 207835898 95654228 760807424 0.4226674736 0.1195377484 0.8854208589 663 26.4800000000 0.1128027588 0.0552211157 0.1669526249 0.0076773633 0.0209260000 207838506 95654228 760807424 0.4121953547 0.1195623428 0.8822224736 664 26.5200000000 0.1118848324 0.0553064526 0.1669526249 0.0076829472 0.0209460000 207839514 95654228 760807424 0.4016840756 0.1162977815 0.8750993609 665 26.5600000000 0.1118379459 0.0553914624 0.1669526249 0.0076776695 0.0209050000 207842122 95654228 760807424 0.3913229704 0.1176973805 0.8718091846 666 26.6000000000 0.1110279262 0.0554750006 0.1669526249 0.0076737786 0.0209040000 207843130 95654228 760807424 0.3803879917 0.1190307438 0.8676734567 667 26.6400000000 0.1112928912 0.0555586856 0.1669526249 0.0076760671 0.0209720000 207845738 95654228 760807424 0.3698577881 0.1225401238 0.8663243651 668 26.6800000000 0.1101344377 0.0556403859 0.1669526249 0.0076959495 0.0209450000 207848546 95654228 760807424 0.3588936627 0.1258661747 0.8619446158 669 26.7200000000 0.1094801128 0.0557208638 0.1669526249 0.0077404929 0.0219460000 207852114 95654228 760807424 0.3479511440 0.1266481727 0.8584422469 670 26.7600000000 0.1089092642 0.0558002494 0.1669526249 0.0077685962 0.0210710000 208023642 95654228 760807424 0.3383924365 0.1263995916 0.8546136618 671 26.8000000000 0.1090331897 0.0558795832 0.1669526249 0.0077743067 0.0209690000 208024450 95654228 760807424 0.3289153874 0.1270109266 0.8508552909 672 26.8400000000 0.1083166376 0.0559576145 0.1669526249 0.0077702831 0.0209320000 208027258 95654228 760807424 0.3194213808 0.1294145286 0.8459084034 673 26.8800000000 0.1082494780 0.0560353142 0.1669526249 0.0077655346 0.0209500000 208029866 95654228 760807424 0.3106070757 0.1301209778 0.8421387672 674 26.9200000000 0.1075320989 0.0561117189 0.1669526249 0.0077601759 0.0209670000 208030874 95654228 760807424 0.3018733263 0.1304999590 0.8377491236 675 26.9600000000 0.1067856327 0.0561867914 0.1669526249 0.0077546096 0.0209370000 208033482 95654228 760807424 0.2933987677 0.1325394511 0.8339732885 676 27.0000000000 0.1059859917 0.0562604588 0.1669526249 0.0077503719 0.0209990000 208034490 95654228 760807424 0.2846660614 0.1367481798 0.8296694160 677 27.0400000000 0.1059095562 0.0563337957 0.1669526249 0.0077564411 0.0209830000 208037098 95654228 760807424 0.2758811414 0.1398332864 0.8276991844 678 27.0800000000 0.1062628850 0.0564074375 0.1669526249 0.0077673836 0.0210010000 208039906 95654228 760807424 0.2676373124 0.1424255818 0.8245491982 679 27.1200000000 0.1057793200 0.0564801501 0.1669526249 0.0077786355 0.0210050000 208040714 95654228 760807424 0.2590999007 0.1443046778 0.8203684092 680 27.1600000000 0.1056703329 0.0565524886 0.1669526249 0.0077791796 0.0210120000 208043522 95654228 760807424 0.2512879074 0.1441124529 0.8153968453 681 27.2000000000 0.1050837860 0.0566237534 0.1669526249 0.0077739194 0.0209860000 208046130 95654228 760807424 0.2433321476 0.1450249404 0.8113303781 682 27.2400000000 0.1046626866 0.0566941917 0.1669526249 0.0077686058 0.0209890000 208047138 95654228 760807424 0.2352983356 0.1489377767 0.8065288067 683 27.2800000000 0.1037084907 0.0567630267 0.1669526249 0.0077685184 0.0209460000 208049746 95654228 760807424 0.2276565880 0.1509807855 0.8014168143 684 27.3200000000 0.1034671739 0.0568313076 0.1669526249 0.0077713395 0.0209600000 208050754 95654228 760807424 0.2196107209 0.1525773704 0.7967430949 685 27.3600000000 0.1027563959 0.0568983515 0.1669526249 0.0077710011 0.0209780000 208053362 95654228 760807424 0.2117804736 0.1523768902 0.7906616330 686 27.4000000000 0.1022278965 0.0569644296 0.1669526249 0.0077667830 0.0210140000 208056170 95654228 760807424 0.2036891878 0.1563706845 0.7845649719 687 27.4400000000 0.1021088436 0.0570301420 0.1669526249 0.0077737435 0.0210030000 208056978 95654228 760807424 0.1957394034 0.1600125432 0.7788578868 688 27.4800000000 0.1010987908 0.0570941952 0.1669526249 0.0077903679 0.0209600000 208059786 95654228 760807424 0.1873731315 0.1607222706 0.7724226117 689 27.5200000000 0.1014533341 0.0571585771 0.1669526249 0.0077981710 0.0211340000 208063422 95654228 760807424 0.1795053482 0.1633471996 0.7672182322 690 27.5600000000 0.1014495566 0.0572227670 0.1669526249 0.0077991172 0.0210020000 208234986 95654228 760807424 0.1717486233 0.1645361930 0.7607435584 691 27.6000000000 0.1007736474 0.0572857928 0.1669526249 0.0078008322 0.0209440000 208237594 95654228 760807424 0.1630866528 0.1680832505 0.7541739941 692 27.6400000000 0.1001676470 0.0573477608 0.1669526249 0.0078174945 0.0209880000 208238602 95654228 760807424 0.1547086388 0.1708205342 0.7477185130 693 27.6800000000 0.1002575979 0.0574096798 0.1669526249 0.0078489293 0.0209230000 208241210 95654228 760807424 0.1469842643 0.1709869355 0.7409199476 694 27.7200000000 0.1001625136 0.0574712833 0.1669526249 0.0078623117 0.0209710000 208242218 95654228 760807424 0.1399399489 0.1708177775 0.7326674461 695 27.7600000000 0.0998540670 0.0575322657 0.1669526249 0.0078611618 0.0209640000 208244826 95654228 760807424 0.1329772770 0.1700470150 0.7249048948 696 27.8000000000 0.0996818915 0.0575928255 0.1669526249 0.0078567958 0.0209640000 208247634 95654228 760807424 0.1257477552 0.1723805964 0.7176432610 697 27.8400000000 0.0990218073 0.0576522645 0.1669526249 0.0078545906 0.0210070000 208248442 95654228 760807424 0.1181363240 0.1749990135 0.7103996277 698 27.8800000000 0.0985489935 0.0577108558 0.1669526249 0.0078561449 0.0209350000 208251250 95654228 760807424 0.1096657738 0.1791067421 0.7037836313 699 27.9200000000 0.0975378156 0.0577678329 0.1669526249 0.0078654074 0.0209450000 208253858 95654228 760807424 0.1015729457 0.1827250272 0.6964783072 700 27.9600000000 0.0966609344 0.0578233945 0.1669526249 0.0078818518 0.0210020000 208254866 95654228 760807424 0.0934090465 0.1854216456 0.6890391707 701 28.0000000000 0.0961719602 0.0578781000 0.1669526249 0.0079001920 0.0209220000 208257474 95654228 760807424 0.0855312347 0.1874842793 0.6825333238 702 28.0400000000 0.0955878571 0.0579318176 0.1669526249 0.0079133550 0.0209380000 208258482 95654228 760807424 0.0777342469 0.1886169761 0.6755633354 703 28.0800000000 0.0952671915 0.0579849262 0.1669526249 0.0079195749 0.0208830000 208261090 95654228 760807424 0.0707541779 0.1898361295 0.6703193188 704 28.1200000000 0.0945643634 0.0580368856 0.1669526249 0.0079243064 0.0209380000 208263898 95654228 760807424 0.0623318106 0.1960435957 0.6651715040 705 28.1600000000 0.0942301154 0.0580882236 0.1669526249 0.0079467003 0.0211660000 208267650 95654228 760807424 0.0542533845 0.2003152519 0.6605807543 706 28.2000000000 0.0939566419 0.0581390287 0.1669526249 0.0079649001 0.0217420000 208439226 95654228 760807424 0.0469204262 0.2002700120 0.6559223533 707 28.2400000000 0.0932011381 0.0581886215 0.1669526249 0.0079669003 0.0210690000 208440034 95654228 760807424 0.0396090224 0.2034365833 0.6514562368 708 28.2800000000 0.0929857343 0.0582377699 0.1669526249 0.0079642786 0.0208310000 208442842 95654228 760807424 0.0315857530 0.2079353780 0.6481616497 709 28.3200000000 0.0927232578 0.0582864096 0.1669526249 0.0079595712 0.0208620000 208445450 95654228 760807424 0.0252562128 0.2048843056 0.6447550058 710 28.3600000000 0.0925874040 0.0583347208 0.1669526249 0.0079559500 0.0209600000 208446458 95654228 760807424 0.0186131001 0.2066800892 0.6407660246 711 28.4000000000 0.0913803056 0.0583811984 0.1669526249 0.0079505324 0.0207150000 208449066 95654228 760807424 0.0106457556 0.2134229243 0.6382709742 712 28.4400000000 0.0910791755 0.0584271226 0.1669526249 0.0079472782 0.0207280000 208450074 95654228 760807424 0.0026696427 0.2157360017 0.6352871656 713 28.4800000000 0.0913800746 0.0584733399 0.1669526249 0.0079449013 0.0207410000 208452682 95654228 760807424 -0.0024089217 0.2136621475 0.6338878274 714 28.5200000000 0.0902380049 0.0585178282 0.1669526249 0.0079609153 0.0207220000 208455490 95654228 760807424 -0.0103677530 0.2206195444 0.6321172714 715 28.5600000000 0.0893231556 0.0585609126 0.1669526249 0.0079557983 0.0207380000 208456298 95654228 760807424 -0.0190269966 0.2268359065 0.6307094097 716 28.6000000000 0.0892921165 0.0586038333 0.1669526249 0.0079558410 0.0207210000 208459106 95654228 760807424 -0.0257643014 0.2291628420 0.6323087811 717 28.6400000000 0.0888642967 0.0586460375 0.1669526249 0.0079529230 0.0207190000 208461714 95654228 760807424 -0.0323443860 0.2309291214 0.6340064406 718 28.6800000000 0.0886468962 0.0586878215 0.1669526249 0.0079482736 0.0206980000 208462722 95654228 760807424 -0.0395040400 0.2361906767 0.6362540722 719 28.7200000000 0.0885284767 0.0587293245 0.1669526249 0.0079467850 0.0207600000 208465330 95654228 760807424 -0.0471194759 0.2396402210 0.6380156279 720 28.7600000000 0.0889980495 0.0587713644 0.1669526249 0.0079437599 0.0207360000 208466338 95654228 760807424 -0.0545194037 0.2432443649 0.6416254640 721 28.8000000000 0.0889492631 0.0588132200 0.1669526249 0.0079385973 0.0206720000 208468946 95654228 760807424 -0.0614690334 0.2451082766 0.6452778578 722 28.8400000000 0.0884994119 0.0588543366 0.1669526249 0.0079335095 0.0207200000 208471754 95654228 760807424 -0.0695357248 0.2479883432 0.6480299830 723 28.8800000000 0.0886353552 0.0588955275 0.1669526249 0.0079280481 0.0206830000 208472562 95654228 760807424 -0.0773317665 0.2503503859 0.6525223851 724 28.9200000000 0.0886544511 0.0589366310 0.1669526249 0.0079226663 0.0206740000 208475370 95654228 760807424 -0.0857659802 0.2535147369 0.6568221450 725 28.9600000000 0.0880765393 0.0589768239 0.1669526249 0.0079200532 0.0218430000 208476178 95654228 760807424 -0.0945241600 0.2563506961 0.6610101461 726 29.0000000000 0.0879691169 0.0590167582 0.1669526249 0.0079253635 0.0208790000 208478986 95654228 760807424 -0.1031578928 0.2572139204 0.6665331125 727 29.0400000000 0.0882516801 0.0590569713 0.1669526249 0.0079265336 0.0208070000 208484378 95654228 760807424 -0.1123658568 0.2611208856 0.6711298823 728 29.0800000000 0.0887790471 0.0590977984 0.1669526249 0.0079277897 0.0207200000 208654194 95654228 760807424 -0.1210264713 0.2650340199 0.6773275733 729 29.1200000000 0.0894475803 0.0591394304 0.1669526249 0.0079244124 0.0206460000 208656802 95654228 760807424 -0.1299682409 0.2700102031 0.6827789545 730 29.1600000000 0.0893985629 0.0591808813 0.1669526249 0.0079205685 0.0207120000 208657810 95654228 760807424 -0.1387459934 0.2717022002 0.6886526346 731 29.2000000000 0.0888572186 0.0592214782 0.1669526249 0.0079162934 0.0206910000 208660418 95654228 760807424 -0.1481871456 0.2739589512 0.6939797401 732 29.2400000000 0.0887090266 0.0592617617 0.1669526249 0.0079120282 0.0206180000 208663226 95654228 760807424 -0.1583911479 0.2783989906 0.6996572614 733 29.2800000000 0.0892097950 0.0593026185 0.1669526249 0.0079071402 0.0206490000 208664034 95654228 760807424 -0.1683044732 0.2828022242 0.7069308162 734 29.3200000000 0.0892165229 0.0593433732 0.1669526249 0.0079029056 0.0206050000 208666842 95654228 760807424 -0.1780658811 0.2869247496 0.7142649889 735 29.3600000000 0.0891859010 0.0593839752 0.1669526249 0.0078999241 0.0205650000 208669450 95654228 760807424 -0.1873524487 0.2908080220 0.7213809490 736 29.4000000000 0.0890514627 0.0594242843 0.1669526249 0.0078960225 0.0205160000 208670458 95654228 760807424 -0.1961212307 0.2952576280 0.7294403911 737 29.4400000000 0.0894708186 0.0594650530 0.1669526249 0.0078915227 0.0205740000 208673066 95654228 760807424 -0.2050531060 0.2992902100 0.7366448045 738 29.4800000000 0.0897940397 0.0595061492 0.1669526249 0.0078912571 0.0205180000 208674074 95654228 760807424 -0.2141090035 0.3031572402 0.7445319891 739 29.5200000000 0.0900346413 0.0595474598 0.1669526249 0.0079059970 0.0204740000 208676682 95654228 760807424 -0.2221867591 0.3068751693 0.7521254420 740 29.5600000000 0.0907359868 0.0595896064 0.1669526249 0.0079241752 0.0205240000 208679490 95654228 760807424 -0.2292846590 0.3106397688 0.7607045770 741 29.6000000000 0.0906816795 0.0596315660 0.1669526249 0.0079521805 0.0205020000 208680298 95654228 760807424 -0.2367854714 0.3147328496 0.7688384652 742 29.6400000000 0.0915254354 0.0596745497 0.1669526249 0.0079689075 0.0205190000 208683106 95654228 760807424 -0.2433707714 0.3195286691 0.7774195671 743 29.6800000000 0.0925122872 0.0597187458 0.1669526249 0.0079677241 0.0206240000 208686846 95654228 760807424 -0.2485411167 0.3220088184 0.7852888703 744 29.7200000000 0.0922088549 0.0597624153 0.1669526249 0.0079625986 0.0205400000 208858454 95654228 760807424 -0.2538453341 0.3232197165 0.7920249104 745 29.7600000000 0.0922262073 0.0598059909 0.1669526249 0.0079592011 0.0205420000 208861062 95654228 760807424 -0.2592375576 0.3257535994 0.7983564734 746 29.8000000000 0.0927615836 0.0598501673 0.1669526249 0.0079553559 0.0204850000 208862070 95654228 760807424 -0.2642513514 0.3286097944 0.8039284945 747 29.8400000000 0.0930580348 0.0598946223 0.1669526249 0.0079502776 0.0204510000 208864678 95654228 760807424 -0.2696482539 0.3325166106 0.8086132407 748 29.8800000000 0.0930729434 0.0599389783 0.1669526249 0.0079481890 0.0204320000 208865686 95654228 760807424 -0.2750758827 0.3360916972 0.8134489655 749 29.9200000000 0.0935385525 0.0599838376 0.1669526249 0.0079445637 0.0204580000 208868294 95654228 760807424 -0.2788342834 0.3400622606 0.8197330832 750 29.9600000000 0.0937848315 0.0600289056 0.1669526249 0.0079419049 0.0205000000 208871102 95654228 760807424 -0.2826976776 0.3433211148 0.8253578544 751 30.0000000000 0.0947705954 0.0600751661 0.1669526249 0.0079383517 0.0203770000 208871910 95654228 760807424 -0.2870370150 0.3466477394 0.8294678926 752 30.0400000000 0.0952580869 0.0601219519 0.1669526249 0.0079343873 0.0204340000 208874718 95654228 760807424 -0.2907133102 0.3502154052 0.8331993818 753 30.0800000000 0.0953028128 0.0601686729 0.1669526249 0.0079354499 0.0204490000 208877326 95654228 760807424 -0.2951572537 0.3517157733 0.8361561894 754 30.1200000000 0.0958160311 0.0602159505 0.1669526249 0.0079416587 0.0204700000 208878334 95654228 760807424 -0.2990876734 0.3542607427 0.8396437168 755 30.1600000000 0.0961889252 0.0602635968 0.1669526249 0.0079536753 0.0204320000 208880942 95654228 760807424 -0.3032099009 0.3562600613 0.8427768350 756 30.2000000000 0.0969023928 0.0603120609 0.1669526249 0.0079621240 0.0204790000 208881950 95654228 760807424 -0.3076485991 0.3601739705 0.8457154632 757 30.2400000000 0.0968243927 0.0603602938 0.1669526249 0.0079643954 0.0204210000 208884558 95654228 760807424 -0.3126460612 0.3631689250 0.8481374979 758 30.2800000000 0.0966477022 0.0604081664 0.1669526249 0.0079687938 0.0204150000 208887366 95654228 760807424 -0.3178380728 0.3642696142 0.8517647982 759 30.3200000000 0.0958644077 0.0604548808 0.1669526249 0.0079911955 0.0204030000 208888174 95654228 760807424 -0.3230801225 0.3663144708 0.8554820418 760 30.3600000000 0.0961012766 0.0605017839 0.1669526249 0.0080052244 0.0205010000 208890982 95654228 760807424 -0.3290144503 0.3720513880 0.8584091067 761 30.4000000000 0.0955590233 0.0605478513 0.1669526249 0.0080202951 0.0205240000 208894454 95654228 760807424 -0.3356772959 0.3740421534 0.8619121909 762 30.4400000000 0.0954569653 0.0605936638 0.1669526249 0.0080257567 0.0205280000 209066070 95654228 760807424 -0.3428330123 0.3770176470 0.8643355966 763 30.4800000000 0.0952125192 0.0606390358 0.1669526249 0.0080245912 0.0214260000 209068678 95654228 760807424 -0.3498413265 0.3813220263 0.8656581640 764 30.5200000000 0.0953573212 0.0606844786 0.1669526249 0.0080244728 0.0204780000 209069686 95654228 760807424 -0.3572474718 0.3857360482 0.8678566813 765 30.5600000000 0.0954686105 0.0607299480 0.1669526249 0.0080227263 0.0203930000 209072294 95654228 760807424 -0.3649230897 0.3901630938 0.8695369363 766 30.6000000000 0.0948211178 0.0607744535 0.1669526249 0.0080230758 0.0204350000 209073302 95654228 760807424 -0.3723320067 0.3929718137 0.8721688986 767 30.6400000000 0.0938999727 0.0608176419 0.1669526249 0.0080217022 0.0204320000 209075910 95654228 760807424 -0.3796658516 0.3968567252 0.8740052581 768 30.6800000000 0.0941675231 0.0608610662 0.1669526249 0.0080230705 0.0204080000 209078718 95654228 760807424 -0.3875920475 0.4015195370 0.8755139112 769 30.7200000000 0.0950745568 0.0609055571 0.1669526249 0.0080235549 0.0204050000 209079526 95654228 760807424 -0.3963680565 0.4069828689 0.8768202662 770 30.7600000000 0.0952021107 0.0609500981 0.1669526249 0.0080220247 0.0204370000 209082334 95654228 760807424 -0.4053347707 0.4111031592 0.8782214522 771 30.8000000000 0.0948732495 0.0609940970 0.1669526249 0.0080181418 0.0204700000 209084942 95654228 760807424 -0.4131927788 0.4152994156 0.8791414499 772 30.8400000000 0.0945199654 0.0610375243 0.1669526249 0.0080169091 0.0204580000 209085950 95654228 760807424 -0.4213012755 0.4177551568 0.8801367879 773 30.8800000000 0.0942068398 0.0610804341 0.1669526249 0.0080177508 0.0204390000 209088558 95654228 760807424 -0.4301431179 0.4202009141 0.8811672926 774 30.9200000000 0.0944592208 0.0611235592 0.1669526249 0.0080202811 0.0204630000 209089566 95654236 760807424 -0.4382767677 0.4233373106 0.8817109466 775 30.9600000000 0.0941349864 0.0611661545 0.1669526249 0.0080264047 0.0204680000 209092174 95654236 760807424 -0.4461622536 0.4248737097 0.8832440376 776 31.0000000000 0.0942102373 0.0612087371 0.1669526249 0.0080336454 0.0204930000 209094982 95654236 760807424 -0.4543521702 0.4274114370 0.8844615817 777 31.0400000000 0.0943314359 0.0612513661 0.1669526249 0.0080451454 0.0204930000 209095790 95654236 760807424 -0.4625583887 0.4312226772 0.8851093054 778 31.0800000000 0.0937689468 0.0612931625 0.1669526249 0.0080491124 0.0204870000 209098598 95654236 760807424 -0.4704972208 0.4340501428 0.8864588737 779 31.1200000000 0.0937299654 0.0613348015 0.1669526249 0.0080480728 0.0204860000 209099406 95654236 760807424 -0.4785645902 0.4360241592 0.8880769014 780 31.1600000000 0.0936404690 0.0613762190 0.1669526249 0.0080479494 0.0204870000 209102214 95654236 760807424 -0.4858172536 0.4390982687 0.8888458014 781 31.2000000000 0.0939968675 0.0614179868 0.1669526249 0.0080459224 0.0204750000 209104822 95654236 760807424 -0.4935508072 0.4420104325 0.8898336291 782 31.2400000000 0.0941615775 0.0614598584 0.1669526249 0.0080420797 0.0214120000 209105830 95654236 760807424 -0.5010105968 0.4434921741 0.8903555274 783 31.2800000000 0.0942724273 0.0615017646 0.1669526249 0.0080380532 0.0205180000 209108438 95654236 760807424 -0.5088308454 0.4448432624 0.8910579085 784 31.3200000000 0.0946075618 0.0615439914 0.1669526249 0.0080333707 0.0204790000 209109446 95654236 760807424 -0.5154914856 0.4464124739 0.8930242062 785 31.3600000000 0.0949215814 0.0615865106 0.1669526249 0.0080284369 0.0204890000 209112054 95654236 760807424 -0.5218927860 0.4476976395 0.8930752277 786 31.4000000000 0.0949408859 0.0616289462 0.1669526249 0.0080255197 0.0205930000 209114862 95654236 760807424 -0.5277362466 0.4491907060 0.8941603303 787 31.4400000000 0.0951475352 0.0616715365 0.1669526249 0.0080216353 0.0205100000 209115670 95654236 760807424 -0.5333632231 0.4516024292 0.8953112364 788 31.4800000000 0.0955596045 0.0617145417 0.1669526249 0.0080188071 0.0206890000 209120802 95654236 760807424 -0.5389105678 0.4527485371 0.8966585398 789 31.5200000000 0.0958511904 0.0617578074 0.1669526249 0.0080164599 0.0206810000 209292218 95654236 760807424 -0.5447940826 0.4527367651 0.8972210884 790 31.5600000000 0.0960436314 0.0618012072 0.1669526249 0.0080118651 0.0205540000 209293226 95654236 760807424 -0.5502049923 0.4529562891 0.8982527256 791 31.6000000000 0.0963588580 0.0618448958 0.1669526249 0.0080073277 0.0206840000 209295834 95654236 760807424 -0.5541129708 0.4545588791 0.8993675113 792 31.6400000000 0.0963757411 0.0618884953 0.1669526249 0.0080023304 0.0206120000 209296842 95654236 760807424 -0.5579982996 0.4543832541 0.9014315605 793 31.6800000000 0.0967398882 0.0619324441 0.1669526249 0.0079983084 0.0206100000 209299450 95654236 760807424 -0.5623030066 0.4536854625 0.9024716616 794 31.7200000000 0.0970769376 0.0619767067 0.1669526249 0.0079993899 0.0208000000 209302258 95654236 760807424 -0.5659024119 0.4527295530 0.9039998651 795 31.7600000000 0.0972021371 0.0620210154 0.1669526249 0.0080102172 0.0206060000 209303066 95654236 760807424 -0.5687301159 0.4522762597 0.9052488804 796 31.8000000000 0.0975877792 0.0620656973 0.1669526249 0.0080284631 0.0206380000 209305874 95654236 760807424 -0.5719324350 0.4516198933 0.9069232345 797 31.8400000000 0.0977457091 0.0621104652 0.1669526249 0.0080458754 0.0206150000 209306682 95654236 760807424 -0.5746150017 0.4504028559 0.9085524082 798 31.8800000000 0.0980145112 0.0621554577 0.1669526249 0.0080645365 0.0205820000 209309490 95654236 760807424 -0.5775288939 0.4492895603 0.9093319178 799 31.9200000000 0.0980154648 0.0622003388 0.1669526249 0.0080750842 0.0205690000 209312098 95654236 760807424 -0.5799747109 0.4476271272 0.9107372761 800 31.9600000000 0.0981065035 0.0622452215 0.1669526249 0.0080833401 0.0205770000 209313106 95654236 760807424 -0.5824758410 0.4456381798 0.9119490981 801 32.0000000000 0.0986966491 0.0622907289 0.1669526249 0.0080975272 0.0206430000 209315714 95654236 760807424 -0.5846038461 0.4446817040 0.9135670066 802 32.0400000000 0.0993143171 0.0623368930 0.1669526249 0.0081051179 0.0205940000 209316722 95654236 760807424 -0.5868620276 0.4433310628 0.9149621129 803 32.0800000000 0.0993555486 0.0623829934 0.1669526249 0.0081148661 0.0205610000 209319330 95654236 760807424 -0.5877204537 0.4429558814 0.9179840088 804 32.1199999990 0.0999740884 0.0624297485 0.1669526249 0.0081293334 0.0205520000 209322138 95654236 760807424 -0.5893302560 0.4425142407 0.9201363325 805 32.1600000000 0.1002662927 0.0624767505 0.1669526249 0.0081455612 0.0205640000 209322946 95654236 760807424 -0.5904948711 0.4411503971 0.9218423367 806 32.2000000000 0.1005564183 0.0625239957 0.1669526249 0.0081625075 0.0206040000 209325754 95654236 760807424 -0.5916975141 0.4400403798 0.9233955741 807 32.2400000000 0.1009956747 0.0625716682 0.1669526249 0.0081803287 0.0205830000 209328362 95654236 760807424 -0.5925540924 0.4373156130 0.9253797531 808 32.2800000000 0.1012097001 0.0626194875 0.1669526249 0.0081883766 0.0204720000 209329370 95654236 760807424 -0.5943001509 0.4345819652 0.9278156161 809 32.3200000000 0.1020312235 0.0626682041 0.1669526249 0.0081961215 0.0205690000 209331978 95654236 760807424 -0.5946611166 0.4319484532 0.9299197793 810 32.3600000000 0.1024250612 0.0627172867 0.1669526249 0.0082016516 0.0204910000 209332986 95654236 760807424 -0.5955888629 0.4299721122 0.9318866134 811 32.4000000000 0.1026252806 0.0627664950 0.1669526249 0.0082008607 0.0204590000 209335594 95654236 760807424 -0.5970055461 0.4260191619 0.9343470335 812 32.4399999990 0.1037026346 0.0628169090 0.1669526249 0.0082012377 0.0204820000 209338402 95654236 760807424 -0.5981086493 0.4236667454 0.9364410639 813 32.4800000000 0.1039546579 0.0628675089 0.1669526249 0.0082006689 0.0204670000 209339210 95654236 760807424 -0.5993157029 0.4203425348 0.9403514266 814 32.5200000000 0.1044372320 0.0629185774 0.1669526249 0.0081998736 0.0205010000 209342018 95654236 760807424 -0.6005120873 0.4174478650 0.9438447952 815 32.5600000000 0.1042503491 0.0629692912 0.1669526249 0.0081976926 0.0205360000 209342826 95654236 760807424 -0.6010220051 0.4144199193 0.9467219710 816 32.6000000000 0.1046832800 0.0630204113 0.1669526249 0.0081962438 0.0205340000 209345634 95654236 760807424 -0.6010633111 0.4108907282 0.9501008987 817 32.6400000000 0.1044787169 0.0630711559 0.1669526249 0.0081926032 0.0205170000 209348242 95654236 760807424 -0.6014904976 0.4074868560 0.9530133605 818 32.6800000000 0.1061682850 0.0631238418 0.1669526249 0.0081884320 0.0204710000 209349250 95654236 760807424 -0.6029859781 0.4054029286 0.9563667178 819 32.7200000000 0.1068390831 0.0631772182 0.1669526249 0.0081848433 0.0204580000 209351858 95654236 760807424 -0.6033361554 0.4042552412 0.9605202079 820 32.7599999990 0.1072597578 0.0632309774 0.1669526249 0.0081833068 0.0213680000 209352866 95654236 760807424 -0.6033060551 0.4029143155 0.9652345181 821 32.7999999990 0.1075095311 0.0632849099 0.1669526249 0.0081870858 0.0204790000 209355474 95654236 760807424 -0.6037948728 0.4002126753 0.9712480903 822 32.8400000000 0.1083965302 0.0633397902 0.1669526249 0.0082102146 0.0204740000 209358282 95654236 760807424 -0.6046876907 0.3983070254 0.9758304358 823 32.8800000000 0.1085272878 0.0633946960 0.1669526249 0.0082193164 0.0203960000 209359090 95654236 760807424 -0.6054660678 0.3962791562 0.9808430076 824 32.9200000000 0.1089376435 0.0634499666 0.1669526249 0.0082259964 0.0204520000 209361898 95654236 760807424 -0.6059067845 0.3960296512 0.9858901501 825 32.9600000000 0.1096641272 0.0635059837 0.1669526249 0.0082383527 0.0203850000 209364506 95654236 760807424 -0.6065981388 0.3944050372 0.9913713932 826 33.0000000000 0.1107234806 0.0635631478 0.1669526249 0.0082499278 0.0203730000 209365514 95654236 760807424 -0.6075736284 0.3942073286 0.9969843030 827 33.0400000000 0.1119129285 0.0636216118 0.1669526249 0.0082660118 0.0204110000 209368122 95654236 760807424 -0.6090555191 0.3919675946 1.0020707846 828 33.0800000000 0.1122438237 0.0636803343 0.1669526249 0.0082898708 0.0203920000 209369130 95654236 760807424 -0.6094486713 0.3885698915 1.0075033903 829 33.1199999990 0.1132506728 0.0637401297 0.1669526249 0.0083115178 0.0204210000 209371738 95654236 760807424 -0.6109226942 0.3861645460 1.0129864216 830 33.1600000000 0.1140466481 0.0638007399 0.1669526249 0.0083284181 0.0204530000 209374546 95654236 760807424 -0.6117542386 0.3836756945 1.0186553001 831 33.2000000000 0.1146219522 0.0638618966 0.1669526249 0.0083467612 0.0204140000 209377914 95654236 760807424 -0.6121018529 0.3790693283 1.0253961086 832 33.2400000000 0.1150407121 0.0639234096 0.1669526249 0.0083572408 0.0203460000 209549454 95654236 760807424 -0.6126725674 0.3756945431 1.0317631960 833 33.2800000000 0.1160989404 0.0639860453 0.1669526249 0.0083595674 0.0204130000 209550262 95654236 760807424 -0.6149589419 0.3725743890 1.0384715796 834 33.3200000000 0.1167627871 0.0640493268 0.1669526249 0.0083631747 0.0203620000 209553070 95654236 760807424 -0.6164765358 0.3677454591 1.0446794033 835 33.3600000000 0.1166923568 0.0641123723 0.1669526249 0.0083671218 0.0203020000 209555678 95654236 760807424 -0.6184619665 0.3644226491 1.0506517887 836 33.4000000000 0.1172537282 0.0641759385 0.1669526249 0.0083757690 0.0203190000 209556686 95654236 760807424 -0.6197629571 0.3611192703 1.0575044155 837 33.4399999990 0.1181703508 0.0642404480 0.1669526249 0.0083938101 0.0205000000 209559294 95654236 760807424 -0.6213728189 0.3594389260 1.0636860132 838 33.4800000000 0.1187582165 0.0643055050 0.1669526249 0.0084216460 0.0203180000 209560302 95654236 760807424 -0.6223121881 0.3549398184 1.0693445206 839 33.5200000000 0.1197000071 0.0643715294 0.1669526249 0.0084546001 0.0213190000 209562910 95654236 760807424 -0.6235548854 0.3531478345 1.0752241611 840 33.5600000000 0.1208252758 0.0644387363 0.1669526249 0.0084800552 0.0204480000 209565718 95654236 760807424 -0.6256281137 0.3524503410 1.0790938139 841 33.6000000000 0.1214482635 0.0645065241 0.1669526249 0.0084832800 0.0203590000 209566526 95654236 760807424 -0.6273576021 0.3510786295 1.0838760138 842 33.6400000000 0.1219530180 0.0645747503 0.1669526249 0.0084828832 0.0202880000 209569334 95654236 760807424 -0.6287998557 0.3497153819 1.0881350040 843 33.6800000000 0.1227105409 0.0646437133 0.1669526249 0.0084843797 0.0203960000 209571942 95654236 760807424 -0.6297821403 0.3474391103 1.0932600498 844 33.7200000000 0.1232762188 0.0647131831 0.1669526249 0.0084895821 0.0203880000 209572950 95654236 760807424 -0.6304796338 0.3433572352 1.0983029604 845 33.7599999990 0.1246478111 0.0647841116 0.1669526249 0.0085046575 0.0203440000 209575558 95654236 760807424 -0.6312870979 0.3414970636 1.1027305126 846 33.7999999990 0.1247559860 0.0648550004 0.1669526249 0.0085106989 0.0202400000 209576566 95654236 760807424 -0.6320962906 0.3397401273 1.1075580120 847 33.8400000000 0.1253154129 0.0649263822 0.1669526249 0.0085090829 0.0202480000 209579174 95654236 760807424 -0.6335765123 0.3352960050 1.1107525826 848 33.8800000000 0.1255844086 0.0649979129 0.1669526249 0.0085045319 0.0202040000 209581982 95654236 760807424 -0.6342884898 0.3324438334 1.1145954132 849 33.9200000000 0.1264691651 0.0650703172 0.1669526249 0.0084998346 0.0202750000 209585114 95654236 760807424 -0.6357913613 0.3277469277 1.1172143221 850 33.9600000000 0.1257889569 0.0651417509 0.1669526249 0.0084954645 0.0202220000 209756742 95654236 760807424 -0.6363525391 0.3234283924 1.1209965944 851 34.0000000000 0.1261829287 0.0652134796 0.1669526249 0.0084905006 0.0201700000 209757550 95654236 760807424 -0.6371941566 0.3212897778 1.1242324114 852 34.0400000000 0.1263576150 0.0652852451 0.1669526249 0.0084858557 0.0201300000 209760358 95654236 760807424 -0.6377372742 0.3156769276 1.1273661852 853 34.0800000000 0.1259899288 0.0653564112 0.1669526249 0.0084825313 0.0202830000 209762966 95654236 760807424 -0.6377007961 0.3122693300 1.1303766966 854 34.1199999990 0.1267919540 0.0654283497 0.1669526249 0.0084824253 0.0201450000 209763974 95654236 760807424 -0.6387023926 0.3103032112 1.1332818270 855 34.1600000000 0.1270128936 0.0655003784 0.1669526249 0.0084833049 0.0201420000 209766582 95654236 760807424 -0.6382074356 0.3075596988 1.1370137930 856 34.2000000000 0.1274507940 0.0655727504 0.1669526249 0.0084849242 0.0201300000 209767590 95654236 760807424 -0.6382794380 0.3057153523 1.1402432919 857 34.2400000000 0.1288828254 0.0656466245 0.1669526249 0.0084812523 0.0201150000 209770198 95654236 760807424 -0.6403523088 0.3057722449 1.1433492899 858 34.2800000000 0.1303100884 0.0657219898 0.1669526249 0.0084773593 0.0202140000 209773006 95654236 760807424 -0.6423093081 0.3047596514 1.1462303400 859 34.3200000000 0.1304159462 0.0657973029 0.1669526249 0.0084728227 0.0201610000 209773814 95654236 760807424 -0.6417105198 0.2991845608 1.1480357647 860 34.3600000000 0.1310240626 0.0658731480 0.1669526249 0.0084686932 0.0202070000 209776622 95654236 760807424 -0.6424315572 0.2951477468 1.1495325565 861 34.4000000000 0.1303769052 0.0659480653 0.1669526249 0.0084640386 0.0201530000 209779230 95654236 760807424 -0.6417773962 0.2918564975 1.1520969868 862 34.4400000000 0.1306771040 0.0660231570 0.1669526249 0.0084591684 0.0203380000 209780238 95654236 760807424 -0.6416239738 0.2885860503 1.1537795067 863 34.4800000000 0.1302542090 0.0660975846 0.1669526249 0.0084551180 0.0201960000 209782846 95654236 760807424 -0.6408112049 0.2826318443 1.1551452875 864 34.5200000000 0.1300416887 0.0661715940 0.1669526249 0.0084514921 0.0201440000 209783854 95654236 760807424 -0.6415265203 0.2784250379 1.1567144394 865 34.5600000000 0.1294747591 0.0662447768 0.1669526249 0.0084466793 0.0201530000 209786462 95654236 760807424 -0.6424399614 0.2767176032 1.1583949327 866 34.6000000000 0.1301323771 0.0663185500 0.1669526249 0.0084425830 0.0201240000 209789270 95654236 760807424 -0.6434949040 0.2763235271 1.1594681740 867 34.6400000000 0.1292751580 0.0663911643 0.1669526249 0.0084396123 0.0200770000 209790078 95654236 760807424 -0.6437707543 0.2721897364 1.1608501673 868 34.6800000000 0.1288893670 0.0664631669 0.1669526249 0.0084351286 0.0200840000 209792886 95654236 760807424 -0.6442853212 0.2680012286 1.1617244482 869 34.7200000000 0.1290993094 0.0665352453 0.1669526249 0.0084315838 0.0201120000 209793694 95654236 760807424 -0.6441879869 0.2646118402 1.1625689268 870 34.7600000000 0.1294644624 0.0666075777 0.1669526249 0.0084276161 0.0200860000 209796502 95654236 760807424 -0.6465743184 0.2612857521 1.1637934446 871 34.8000000000 0.1299761087 0.0666803315 0.1669526249 0.0084237056 0.0201380000 209799110 95654236 760807424 -0.6463098526 0.2612312436 1.1643835306 872 34.8400000000 0.1300234944 0.0667529727 0.1669526249 0.0084193624 0.0201040000 209800118 95654236 760807424 -0.6481717825 0.2575227022 1.1654001474 873 34.8800000000 0.1302703172 0.0668257303 0.1669526249 0.0084153162 0.0200960000 209802726 95654236 760807424 -0.6495661139 0.2550583184 1.1668268442 874 34.9200000000 0.1310680658 0.0668992341 0.1669526249 0.0084116979 0.0201310000 209803734 95654236 760807424 -0.6512812972 0.2539669871 1.1677930355 875 34.9600000000 0.1308103949 0.0669722754 0.1669526249 0.0084084726 0.0200440000 209806342 95654236 760807424 -0.6527104974 0.2538576722 1.1698342562 876 35.0000000000 0.1314161867 0.0670458415 0.1669526249 0.0084041310 0.0200770000 209809150 95654236 760807424 -0.6535452604 0.2537583709 1.1704925299 877 35.0400000000 0.1292702407 0.0671167930 0.1669526249 0.0083995376 0.0211280000 209809958 95654236 760807424 -0.6531823277 0.2517525852 1.1717493534 878 35.0800000000 0.1293156594 0.0671876345 0.1669526249 0.0083948757 0.0203280000 209812766 95654236 760807424 -0.6538938284 0.2522889376 1.1728340387 879 35.1200000000 0.1311855465 0.0672604421 0.1669526249 0.0083904118 0.0202580000 209815374 95654236 760807424 -0.6562542915 0.2523967326 1.1742793322 880 35.1600000000 0.1335393935 0.0673357591 0.1669526249 0.0083857644 0.0203150000 209816382 95654236 760807424 -0.6584379673 0.2551296949 1.1755602360 881 35.2000000000 0.1343237311 0.0674117954 0.1669526249 0.0083814473 0.0202020000 209818990 95654236 760807424 -0.6591290832 0.2562746704 1.1769349575 882 35.2400000000 0.1347500980 0.0674881427 0.1669526249 0.0083774141 0.0201190000 209819998 95654236 760807424 -0.6592038870 0.2523786724 1.1776955128 ================================================ FILE: icra2018_results/1080/memory_infinitam_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:15:57 Properties: ================= frame-limit: 0 log-file: out_paper//memory_infinitam_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0032290000 14154453 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025881492 0.0012940746 0.0025881492 0.0016479522 0.0025110000 14351349 955859216 1373700096 0.0001491974 -0.0015389282 0.0011201169 3 0.0800000000 0.0054591955 0.0026824482 0.0054591955 0.0017220981 0.0013390000 14353717 955859216 1373700096 -0.0038292797 -0.0031308038 0.0017659018 4 0.1200000000 0.0071080080 0.0037888382 0.0071080080 0.0015496811 0.0013280000 14356093 955859216 1373700096 -0.0022651835 -0.0055630994 0.0010873042 5 0.1600000000 0.0088851051 0.0048080916 0.0088851051 0.0013764281 0.0013240000 14358453 955859216 1373700096 -0.0045972592 -0.0063785226 0.0030389763 6 0.2000000000 0.0102891028 0.0057215934 0.0102891028 0.0012644645 0.0013360000 14361229 955859216 1373700096 -0.0038707939 -0.0083202105 0.0025938994 7 0.2400000000 0.0119142374 0.0066062569 0.0119142374 0.0012500048 0.0013240000 14363205 955859216 1373700096 -0.0037800057 -0.0100338357 0.0033170516 8 0.2800000000 0.0135552306 0.0074748786 0.0135552306 0.0012154173 0.0013220000 14365181 955859216 1373700096 -0.0048537147 -0.0114162117 0.0035832629 9 0.3200000000 0.0145001300 0.0082554621 0.0145001300 0.0012413039 0.0013370000 14367925 955859216 1373700096 -0.0065823239 -0.0129055651 0.0038818400 10 0.3600000000 0.0164705422 0.0090769701 0.0164705422 0.0012859763 0.0013270000 14371501 955859216 1373700096 -0.0065532792 -0.0136584528 0.0049750521 11 0.4000000000 0.0168847069 0.0097867643 0.0168847069 0.0015188572 0.0013360000 14373477 955859216 1373700096 -0.0073775002 -0.0149108972 0.0057885116 12 0.4400000000 0.0184355862 0.0105074995 0.0184355862 0.0018455035 0.0013400000 14375453 955859216 1373700096 -0.0073211030 -0.0166409519 0.0053952606 13 0.4800000000 0.0194877144 0.0111982853 0.0194877144 0.0019781877 0.0013360000 14377429 955859216 1373700096 -0.0093033938 -0.0177838691 0.0062079947 14 0.5200000000 0.0215931833 0.0119407780 0.0215931833 0.0019389495 0.0013460000 14379405 955859216 1373700096 -0.0092646340 -0.0187591910 0.0061596120 15 0.5600000000 0.0229519214 0.0126748542 0.0229519214 0.0018724351 0.0013410000 14381381 955859216 1373700096 -0.0117975315 -0.0188956149 0.0072132889 16 0.6000000000 0.0226152837 0.0132961310 0.0229519214 0.0018597716 0.0013360000 14383357 955859216 1373700096 -0.0114101861 -0.0204201397 0.0061401250 17 0.6400000000 0.0235187877 0.0138974638 0.0235187877 0.0018271797 0.0013500000 14386869 955859216 1373700096 -0.0131594259 -0.0225843228 0.0049224421 18 0.6800000000 0.0242247451 0.0144712016 0.0242247451 0.0017733804 0.0013550000 14392045 955859216 1373700096 -0.0144591192 -0.0231084172 0.0060552214 19 0.7200000000 0.0251365639 0.0150325365 0.0251365639 0.0017820581 0.0013500000 14394021 955859216 1373700096 -0.0158813652 -0.0237181839 0.0058658649 20 0.7600000000 0.0248267893 0.0155222491 0.0251365639 0.0018951142 0.0013630000 14395997 955859216 1373700096 -0.0188157484 -0.0246541630 0.0053912690 21 0.8000000000 0.0255757589 0.0160009877 0.0255757589 0.0018563175 0.0013510000 14397973 955859216 1373700096 -0.0216081440 -0.0244546160 0.0059043700 22 0.8400000000 0.0259834453 0.0164547358 0.0259834453 0.0018325142 0.0013500000 14399949 955859216 1373700096 -0.0269861184 -0.0256312098 0.0054987129 23 0.8800000000 0.0263936277 0.0168868615 0.0263936277 0.0017920898 0.0013550000 14401925 955859216 1373700096 -0.0269361660 -0.0269933641 0.0040242895 24 0.9200000000 0.0290096086 0.0173919760 0.0290096086 0.0017804430 0.0013600000 14403901 955859216 1373700096 -0.0341994502 -0.0279302467 0.0039055997 25 0.9600000000 0.0310023297 0.0179363901 0.0310023297 0.0017817479 0.0013700000 14405877 955859216 1373700096 -0.0355961397 -0.0286908429 0.0036661206 26 1.0000000000 0.0305129699 0.0184201047 0.0310023297 0.0017510060 0.0013800000 14407853 955859216 1373700096 -0.0414785407 -0.0296978280 0.0043538357 27 1.0400000000 0.0316679142 0.0189107643 0.0316679142 0.0018663164 0.0014130000 14409829 955859216 1373700096 -0.0470324941 -0.0315172486 0.0024761977 28 1.0800000000 0.0337086208 0.0194392592 0.0337086208 0.0020549393 0.0014010000 14411805 955859216 1373700096 -0.0515129343 -0.0316950865 0.0026543664 29 1.1200000000 0.0356133878 0.0199969878 0.0356133878 0.0022439035 0.0013830000 14413781 955859216 1373700096 -0.0572070330 -0.0333026834 0.0003335181 30 1.1600000000 0.0347626582 0.0204891768 0.0356133878 0.0022601454 0.0013850000 14415757 955859216 1373700096 -0.0664446056 -0.0332099199 0.0019988301 31 1.2000000000 0.0365049243 0.0210058138 0.0365049243 0.0022730069 0.0013920000 14417733 955859216 1373700096 -0.0729319826 -0.0341823138 0.0006545496 32 1.2400000000 0.0382170007 0.0215436634 0.0382170007 0.0023176666 0.0013980000 14419709 955859216 1373700096 -0.0794171691 -0.0354639962 -0.0012621412 33 1.2800000000 0.0381254628 0.0220461422 0.0382170007 0.0023842527 0.0013710000 14424757 955859216 1373700096 -0.0849476159 -0.0357555747 -0.0015644442 34 1.3200000000 0.0218973160 0.0220417649 0.0382170007 0.0027749393 0.0015460000 14433133 955859216 1373700096 -0.1155837104 -0.0208355766 -0.0059262030 35 1.3600000000 0.0269055553 0.0221807304 0.0382170007 0.0031649691 0.0013900000 14435109 955859216 1373700096 -0.1185312197 -0.0249380656 -0.0073561864 36 1.4000000000 0.0308846049 0.0224225047 0.0382170007 0.0037752240 0.0014060000 14437085 955859216 1373700096 -0.1235114485 -0.0278855376 -0.0082394835 37 1.4400000000 0.0266829748 0.0225376525 0.0382170007 0.0037802259 0.0014470000 14439061 955859216 1373700096 -0.1348785460 -0.0258857105 -0.0080295652 38 1.4800000000 0.0257613659 0.0226224871 0.0382170007 0.0037351145 0.0014460000 14441037 955859216 1373700096 -0.1467400491 -0.0255210809 -0.0075408090 39 1.5200000000 0.0296551362 0.0228028114 0.0382170007 0.0036947716 0.0014040000 14443013 955859216 1373700096 -0.1497309208 -0.0299648773 -0.0099029290 40 1.5600000000 0.0270952452 0.0229101222 0.0382170007 0.0036930166 0.0014360000 14444989 955859216 1373700096 -0.1597596854 -0.0291190129 -0.0099063823 41 1.6000000000 0.0262605809 0.0229918408 0.0382170007 0.0037110824 0.0014400000 14446965 955859216 1373700096 -0.1702438444 -0.0294301435 -0.0084069343 42 1.6400000000 0.0271349922 0.0230904872 0.0382170007 0.0036676876 0.0014460000 14448941 955859216 1373700096 -0.1833981723 -0.0287976358 -0.0060266475 43 1.6800000000 0.0303194262 0.0232586021 0.0382170007 0.0036343626 0.0013880000 14450917 955859216 1373700096 -0.1894268394 -0.0313646793 -0.0020316369 44 1.7200000000 0.0335382596 0.0234922307 0.0382170007 0.0036435140 0.0013990000 14452893 955859216 1373700096 -0.1955450326 -0.0352081619 -0.0032847128 45 1.7600000000 0.0372643732 0.0237982783 0.0382170007 0.0036350177 0.0013990000 14454869 955859216 1373700096 -0.2029326856 -0.0366833508 0.0011243984 46 1.8000000000 0.0399724022 0.0241498897 0.0399724022 0.0036277491 0.0014300000 14456845 955859216 1373700096 -0.2087752372 -0.0387931019 0.0019241077 47 1.8400000000 0.0405393429 0.0244986014 0.0405393429 0.0037262251 0.0014210000 14458821 955859216 1373700096 -0.2119503319 -0.0412296169 0.0018131750 48 1.8800000000 0.0420067310 0.0248633541 0.0420067310 0.0037501546 0.0014260000 14460797 955859216 1373700096 -0.2160209864 -0.0428662635 0.0032152513 49 1.9200000000 0.0443751439 0.0252615539 0.0443751439 0.0037142039 0.0014320000 14462773 955859216 1373700096 -0.2228552103 -0.0440444313 0.0045203562 50 1.9600000000 0.0251635127 0.0252595931 0.0443751439 0.0038263271 0.0016050000 14464749 955859216 1373700096 -0.2402641028 -0.0259081163 0.0049249073 51 2.0000000000 0.0293987244 0.0253407525 0.0443751439 0.0038208179 0.0014190000 14466725 955859216 1373700096 -0.2385581285 -0.0302260872 0.0030440737 52 2.0400000000 0.0334663391 0.0254970138 0.0443751439 0.0037914368 0.0014310000 14468701 955859216 1373700096 -0.2414335310 -0.0336947329 0.0031636760 53 2.0800000000 0.0354457237 0.0256847253 0.0443751439 0.0038141348 0.0014460000 14470677 955859216 1373700096 -0.2432968765 -0.0379859805 0.0004846470 54 2.1200000000 0.0258635953 0.0256880377 0.0443751439 0.0040135992 0.0015450000 14472653 955859216 1373700096 -0.2575136721 -0.0302962568 0.0039240415 55 2.1600000000 0.0309045892 0.0257828841 0.0443751439 0.0040589232 0.0014300000 14474629 955859216 1373700096 -0.2591563165 -0.0344214514 0.0048075295 56 2.2000000000 0.0258393213 0.0257838919 0.0443751439 0.0041008896 0.0015610000 14476605 955859216 1373700096 -0.2797060907 -0.0290874317 0.0127212144 57 2.2400000000 0.0277811196 0.0258189310 0.0443751439 0.0040722242 0.0014520000 14478581 955859216 1373700096 -0.2843064368 -0.0336447693 0.0137693761 58 2.2800000000 0.0279245954 0.0258552356 0.0443751439 0.0040759789 0.0014830000 14480557 955859216 1373700096 -0.2935922742 -0.0344253518 0.0165702961 59 2.3200000000 0.0288918708 0.0259067040 0.0443751439 0.0042119350 0.0015000000 14482533 955859216 1373700096 -0.3075580895 -0.0330242738 0.0224231575 60 2.3600000000 0.0308595840 0.0259892520 0.0443751439 0.0043340308 0.0014730000 14484509 955859216 1373700096 -0.3106804490 -0.0366670154 0.0210235268 61 2.4000000000 0.0325904079 0.0260974676 0.0443751439 0.0044635756 0.0014240000 14486485 955859216 1373700096 -0.3167962730 -0.0397505984 0.0211246032 62 2.4400000000 0.0260292664 0.0260963676 0.0443751439 0.0045538802 0.0015640000 14488461 955859216 1373700096 -0.3417752683 -0.0328700244 0.0298981108 63 2.4800000000 0.0271836650 0.0261136263 0.0443751439 0.0047035904 0.0014940000 14490437 955859216 1373700096 -0.3502487838 -0.0351224579 0.0313136131 64 2.5200000000 0.0281925686 0.0261461098 0.0443751439 0.0050605667 0.0015090000 14492413 955859216 1373700096 -0.3625967801 -0.0348884128 0.0360390209 65 2.5600000000 0.0282592941 0.0261786203 0.0443751439 0.0053565975 0.0015010000 14500533 955859216 1373700096 -0.3763554990 -0.0351083688 0.0397540331 66 2.6000000000 0.0293164346 0.0262261629 0.0443751439 0.0054465555 0.0014900000 14515309 955859216 1373700096 -0.3868575394 -0.0348267034 0.0419059545 67 2.6400000000 0.0304726530 0.0262895434 0.0443751439 0.0055017547 0.0014870000 14517285 955859216 1373700096 -0.3969136775 -0.0334553085 0.0443771407 68 2.6800000000 0.0303924773 0.0263498807 0.0443751439 0.0054819215 0.0015060000 14519261 955859216 1373700096 -0.4080641568 -0.0335875340 0.0436406471 69 2.7200000000 0.0301129688 0.0264044182 0.0443751439 0.0054433741 0.0014880000 14521237 955859216 1373700096 -0.4176523685 -0.0330459215 0.0480388030 70 2.7600000000 0.0359430201 0.0265406839 0.0443751439 0.0054103060 0.0014300000 14523213 955859216 1373700096 -0.4255240858 -0.0368494838 0.0489343144 71 2.8000000000 0.0408244208 0.0267418633 0.0443751439 0.0054324883 0.0014440000 14525189 955859216 1373700096 -0.4319766164 -0.0409709215 0.0469225571 72 2.8400000000 0.0275069047 0.0267524889 0.0443751439 0.0063410323 0.0016360000 14527165 955859216 1373700096 -0.4500087500 -0.0229842775 0.0466924421 73 2.8800000000 0.0308343638 0.0268084050 0.0443751439 0.0063842607 0.0015370000 14529141 955859216 1373700096 -0.4595469832 -0.0248313099 0.0490848832 74 2.9200000000 0.0377605148 0.0269564064 0.0443751439 0.0064301525 0.0014760000 14531117 955859216 1373700096 -0.4606555700 -0.0298463237 0.0474769138 75 2.9600000000 0.0447682627 0.0271938979 0.0447682627 0.0064501483 0.0014790000 14533093 955859216 1373700096 -0.4608738720 -0.0329294540 0.0461692251 76 3.0000000000 0.0292861443 0.0272214274 0.0447682627 0.0065967071 0.0016620000 14535069 955859216 1373700096 -0.4613810480 -0.0148910014 0.0345968492 77 3.0400000000 0.0325159281 0.0272901872 0.0447682627 0.0065945459 0.0015610000 14537045 955859216 1373700096 -0.4612701237 -0.0176935121 0.0284653325 78 3.0800000000 0.0292111449 0.0273148148 0.0447682627 0.0065638887 0.0016000000 14539021 955859216 1373700096 -0.4601790905 -0.0132605899 0.0205512438 79 3.1200000000 0.0370578580 0.0274381445 0.0447682627 0.0065425424 0.0014920000 14540997 955859216 1373700096 -0.4658188224 -0.0177605692 0.0200844258 80 3.1600000000 0.0434199236 0.0276379167 0.0447682627 0.0065228431 0.0014830000 14542973 955859216 1373700096 -0.4683830142 -0.0210698787 0.0177428313 81 3.2000000000 0.0289328080 0.0276539030 0.0447682627 0.0065040874 0.0016790000 14544949 955859216 1373700096 -0.4826561809 -0.0080729062 0.0175625179 82 3.2400000000 0.0303054526 0.0276862390 0.0447682627 0.0065122787 0.0015630000 14546925 955859216 1373700096 -0.4907026887 -0.0092885448 0.0173258409 83 3.2800000000 0.0311335847 0.0277277733 0.0447682627 0.0065519339 0.0015640000 14548901 955859216 1373700096 -0.4982014000 -0.0080065941 0.0142982407 84 3.3200000000 0.0306323655 0.0277623518 0.0447682627 0.0065405436 0.0015680000 14550877 955859216 1373700096 -0.5108972192 -0.0086618094 0.0144708371 85 3.3600000000 0.0290050842 0.0277769722 0.0447682627 0.0065210995 0.0016340000 14552853 955859216 1373700096 -0.5249108076 -0.0061440389 0.0145492824 86 3.4000000000 0.0297731962 0.0278001841 0.0447682627 0.0065630643 0.0015880000 14554829 955859216 1373700096 -0.5395101905 -0.0061650332 0.0186718255 87 3.4400000000 0.0293411575 0.0278178964 0.0447682627 0.0066819727 0.0015980000 14556805 955859216 1373700096 -0.5493971109 -0.0068820613 0.0182733517 88 3.4800000000 0.0292988606 0.0278347255 0.0447682627 0.0068281333 0.0016040000 14558781 955859216 1373700096 -0.5624446273 -0.0065046079 0.0185338296 89 3.5200000000 0.0291305482 0.0278492854 0.0447682627 0.0069588268 0.0016120000 14560757 955859216 1373700096 -0.5718231201 -0.0061402679 0.0186247956 90 3.5600000000 0.0287350323 0.0278591270 0.0447682627 0.0070494789 0.0016150000 14562733 955859216 1373700096 -0.5794009566 -0.0075519281 0.0173333604 91 3.6000000000 0.0286341719 0.0278676440 0.0447682627 0.0070884576 0.0016040000 14564709 955859216 1373700096 -0.5939254165 -0.0087083420 0.0203002319 92 3.6400000000 0.0288663283 0.0278784992 0.0447682627 0.0070967800 0.0016080000 14566685 955859216 1373700096 -0.6090333462 -0.0068033142 0.0254698079 93 3.6800000000 0.0287816152 0.0278882101 0.0447682627 0.0070752572 0.0016240000 14568661 955859216 1373700096 -0.6138219237 -0.0076515237 0.0220535416 94 3.7200000000 0.0306322575 0.0279174021 0.0447682627 0.0070491349 0.0015590000 14570637 955859216 1373700096 -0.6200987697 -0.0116957957 0.0218553301 95 3.7600000000 0.0289963894 0.0279287599 0.0447682627 0.0070269195 0.0016310000 14572613 955859216 1373700096 -0.6339726448 -0.0088844150 0.0281549226 96 3.8000000000 0.0289107021 0.0279389885 0.0447682627 0.0069977423 0.0016620000 14574589 955859216 1373700096 -0.6441264749 -0.0093495613 0.0276837461 97 3.8400000000 0.0300164111 0.0279604052 0.0447682627 0.0069623379 0.0015790000 14576565 955859216 1373700096 -0.6491663456 -0.0130946161 0.0297196172 98 3.8800000000 0.0288968273 0.0279699605 0.0447682627 0.0069336189 0.0016550000 14578541 955859216 1373700096 -0.6642091870 -0.0126729803 0.0336476937 99 3.9200000000 0.0317941941 0.0280085891 0.0447682627 0.0069082861 0.0015930000 14580517 955859216 1373700096 -0.6685992479 -0.0139834052 0.0370262004 100 3.9600000000 0.0329833664 0.0280583369 0.0447682627 0.0068738573 0.0016100000 14582493 955859216 1373700096 -0.6763670444 -0.0155582204 0.0411791913 101 4.0000000000 0.0329145901 0.0281064186 0.0447682627 0.0068408810 0.0016000000 14584469 955859216 1373700096 -0.6850045323 -0.0171899684 0.0471795462 102 4.0400000000 0.0336133502 0.0281604082 0.0447682627 0.0068165922 0.0016080000 14586445 955859216 1373700096 -0.6883287430 -0.0192953497 0.0489075072 103 4.0800000000 0.0302006658 0.0281802165 0.0447682627 0.0067861098 0.0016740000 14588421 955859216 1373700096 -0.7005777955 -0.0165811852 0.0552150048 104 4.1200000000 0.0291873608 0.0281899006 0.0447682627 0.0067573578 0.0016830000 14590397 955859216 1373700096 -0.7136470079 -0.0173753686 0.0679269433 105 4.1600000000 0.0312375445 0.0282189257 0.0447682627 0.0067600805 0.0016230000 14592373 955859216 1373700096 -0.7153831124 -0.0194869041 0.0698691532 106 4.2000000000 0.0324841067 0.0282591633 0.0447682627 0.0067687705 0.0016340000 14594349 955859216 1373700096 -0.7212472558 -0.0200166106 0.0749762207 107 4.2400000000 0.0297945663 0.0282735129 0.0447682627 0.0067453178 0.0016970000 14596325 955859216 1373700096 -0.7229484916 -0.0208337847 0.0711598322 108 4.2800000000 0.0293420292 0.0282834065 0.0447682627 0.0067142525 0.0017230000 14598301 955859216 1373700096 -0.7326747179 -0.0213702060 0.0795527026 109 4.3200000000 0.0318438821 0.0283160714 0.0447682627 0.0066974219 0.0016460000 14600277 955859216 1373700096 -0.7332721353 -0.0236425474 0.0807990432 110 4.3600000000 0.0318941660 0.0283485996 0.0447682627 0.0067017476 0.0016410000 14602253 955859216 1373700096 -0.7411254048 -0.0242557693 0.0891551971 111 4.4000000000 0.0317269862 0.0283790355 0.0447682627 0.0067004034 0.0016530000 14604229 955859216 1373700096 -0.7474584579 -0.0253924280 0.0958417058 112 4.4400000000 0.0326877013 0.0284175057 0.0447682627 0.0067022177 0.0016740000 14606205 955859216 1373700096 -0.7548299432 -0.0257102810 0.1037202775 113 4.4800000000 0.0331782885 0.0284596365 0.0447682627 0.0067079860 0.0016760000 14608181 955859216 1373700096 -0.7586845756 -0.0262655318 0.1079456285 114 4.5200000000 0.0300237481 0.0284733568 0.0447682627 0.0067394672 0.0017280000 14610157 955859216 1373700096 -0.7710569501 -0.0235425029 0.1200997829 115 4.5600000000 0.0315210670 0.0284998586 0.0447682627 0.0067634318 0.0016700000 14612133 955859216 1373700096 -0.7710315585 -0.0249214265 0.1219991073 116 4.6000000000 0.0301123504 0.0285137594 0.0447682627 0.0067959029 0.0017470000 14614109 955859216 1373700096 -0.7820385098 -0.0210505016 0.1339221597 117 4.6400000000 0.0327662937 0.0285501059 0.0447682627 0.0068080248 0.0017040000 14616085 955859216 1373700096 -0.7884741426 -0.0205748565 0.1443412155 118 4.6800000000 0.0333265215 0.0285905840 0.0447682627 0.0067799098 0.0016880000 14618061 955859216 1373700096 -0.7933750749 -0.0225950759 0.1485153437 119 4.7200000000 0.0343378298 0.0286388802 0.0447682627 0.0067545357 0.0016860000 14620037 955859216 1373700096 -0.7992940545 -0.0239787549 0.1555514783 120 4.7600000000 0.0356843770 0.0286975926 0.0447682627 0.0067274105 0.0016970000 14622013 955859216 1373700096 -0.8054313660 -0.0239635538 0.1637701541 121 4.8000000000 0.0308902767 0.0287157140 0.0447682627 0.0067147455 0.0017690000 14623989 955859216 1373700096 -0.8171616793 -0.0199142303 0.1815860271 122 4.8400000000 0.0342202559 0.0287608332 0.0447682627 0.0066891528 0.0016950000 14625965 955859216 1373700096 -0.8170665503 -0.0215827227 0.1822833568 123 4.8800000000 0.0368573368 0.0288266584 0.0447682627 0.0066682652 0.0017000000 14627941 955859216 1373700096 -0.8214374185 -0.0198905375 0.1885062903 124 4.9200000000 0.0301438216 0.0288372807 0.0447682627 0.0066433075 0.0018650000 14629917 955859216 1373700096 -0.8339193463 -0.0128626293 0.2046139985 125 4.9600000000 0.0321650468 0.0288639028 0.0447682627 0.0066357050 0.0017410000 14631893 955859216 1373700096 -0.8371105790 -0.0148985935 0.2095049322 126 5.0000000000 0.0338446014 0.0289034322 0.0447682627 0.0066175998 0.0017000000 14633869 955859216 1373700096 -0.8411914706 -0.0152955577 0.2167499214 127 5.0400000000 0.0298355836 0.0289107720 0.0447682627 0.0065934521 0.0018790000 14635845 955859216 1373700096 -0.8525597453 -0.0105884159 0.2338428348 128 5.0800000000 0.0325613208 0.0289392919 0.0447682627 0.0065683811 0.0017230000 14637821 955859216 1373700096 -0.8565734625 -0.0132957753 0.2394668311 129 5.1200000000 0.0336103737 0.0289755018 0.0447682627 0.0065446855 0.0017300000 14652085 955859216 1373700096 -0.8601064086 -0.0139192259 0.2461005449 130 5.1600000000 0.0303330887 0.0289859448 0.0447682627 0.0065341107 0.0018030000 14679661 955859216 1373700096 -0.8702778816 -0.0109098069 0.2643403411 131 5.2000000000 0.0316205844 0.0290060565 0.0447682627 0.0065648639 0.0017500000 14681637 955859216 1373700096 -0.8731679320 -0.0115231071 0.2682950199 132 5.2400000000 0.0300576538 0.0290140232 0.0447682627 0.0065730063 0.0018230000 14683613 955859216 1373700096 -0.8743204474 -0.0103781298 0.2661221027 133 5.2800000000 0.0297803525 0.0290197851 0.0447682627 0.0065715679 0.0017900000 14685589 955859216 1373700096 -0.8846461773 -0.0098865656 0.2851679921 134 5.3200000000 0.0297416840 0.0290251724 0.0447682627 0.0065985476 0.0017810000 14687565 955859216 1373700096 -0.8933600187 -0.0073897275 0.3014864922 135 5.3600000000 0.0293367039 0.0290274800 0.0447682627 0.0066166834 0.0017910000 14689541 955859216 1373700096 -0.8967798352 -0.0066279140 0.3054358661 136 5.4000000000 0.0290636718 0.0290277461 0.0447682627 0.0066503743 0.0017940000 14691517 955859216 1373700096 -0.9037802219 -0.0062910770 0.3175299764 137 5.4400000000 0.0297632646 0.0290331149 0.0447682627 0.0067033962 0.0016990000 14693493 955859216 1373700096 -0.9086292386 -0.0065895929 0.3265936673 138 5.4800000000 0.0287071280 0.0290307527 0.0447682627 0.0067418246 0.0017890000 14695469 955859216 1373700096 -0.9147313833 -0.0064067501 0.3314317763 139 5.5200000000 0.0283751134 0.0290260358 0.0447682627 0.0067827419 0.0017770000 14697445 955859216 1373700096 -0.9208672643 -0.0081221955 0.3366877437 140 5.5600000000 0.0283840969 0.0290214505 0.0447682627 0.0068517591 0.0017880000 14699421 955859216 1373700096 -0.9301099777 -0.0073878574 0.3509082794 141 5.6000000000 0.0283773970 0.0290168828 0.0447682627 0.0068839375 0.0017940000 14701397 955859216 1373700096 -0.9355052710 -0.0061412654 0.3563709557 142 5.6400000000 0.0281530228 0.0290107993 0.0447682627 0.0069169756 0.0017940000 14703373 955859216 1373700096 -0.9446847439 -0.0058697881 0.3709878623 143 5.6800000000 0.0296666157 0.0290153854 0.0447682627 0.0069939070 0.0017290000 14705349 955859216 1373700096 -0.9492177367 -0.0050587370 0.3807164431 144 5.7200000000 0.0282689147 0.0290102016 0.0447682627 0.0070336777 0.0017890000 14707325 955859216 1373700096 -0.9560834765 -0.0020073412 0.3887061477 145 5.7600000000 0.0278022867 0.0290018711 0.0447682627 0.0070322290 0.0018080000 14709301 955859216 1373700096 -0.9617640376 -0.0024494156 0.3954305649 146 5.8000000000 0.0278078858 0.0289936931 0.0447682627 0.0070228216 0.0018020000 14711277 955859216 1373700096 -0.9675365686 -0.0023494123 0.4048192799 147 5.8400000000 0.0276975632 0.0289848759 0.0447682627 0.0070056258 0.0018000000 14713253 955859216 1373700096 -0.9776775241 -0.0030022627 0.4256319106 148 5.8800000000 0.0274741482 0.0289746683 0.0447682627 0.0069842442 0.0018380000 14715229 955859216 1373700096 -0.9791086316 -0.0029304186 0.4289678335 149 5.9200000000 0.0298162457 0.0289803165 0.0447682627 0.0069680987 0.0017630000 14717205 955859216 1373700096 -0.9824404120 -0.0044162758 0.4396735728 150 5.9600000000 0.0303047933 0.0289891463 0.0447682627 0.0069491043 0.0017660000 14719181 955859216 1373700096 -0.9858976603 -0.0051418832 0.4483718574 151 6.0000000000 0.0309783388 0.0290023198 0.0447682627 0.0069298684 0.0017600000 14721157 955859216 1373700096 -0.9889312983 -0.0053581404 0.4579918087 152 6.0400000000 0.0317163803 0.0290201754 0.0447682627 0.0069161040 0.0017630000 14723133 955859216 1373700096 -0.9916958213 -0.0047098738 0.4686113000 153 6.0800000000 0.0306708608 0.0290309642 0.0447682627 0.0069040918 0.0017710000 14725109 955859216 1373700096 -0.9955861568 -0.0047171498 0.4771909416 154 6.1200000000 0.0277779959 0.0290228281 0.0447682627 0.0069179259 0.0018180000 14727085 955859216 1373700096 -1.0010775328 -0.0025217941 0.4897605479 155 6.1600000000 0.0269135796 0.0290092200 0.0447682627 0.0069760451 0.0017640000 14729061 955859216 1373700096 -1.0030722618 -0.0025508332 0.4975046217 156 6.2000000000 0.0270275827 0.0289965172 0.0447682627 0.0070842619 0.0018370000 14731037 955859216 1373700096 -1.0075770617 -0.0015077818 0.5121749640 157 6.2400000000 0.0270267501 0.0289839709 0.0447682627 0.0071715474 0.0017690000 14733013 955859216 1373700096 -1.0096901655 -0.0008342662 0.5228820443 158 6.2800000000 0.0267174188 0.0289696257 0.0447682627 0.0072448138 0.0018380000 14734989 955859216 1373700096 -1.0127695799 -0.0001869107 0.5392209291 159 6.3200000000 0.0265858229 0.0289546332 0.0447682627 0.0072728999 0.0017730000 14736965 955859216 1373700096 -1.0135512352 -0.0007013027 0.5471435189 160 6.3600000000 0.0278491396 0.0289477239 0.0447682627 0.0073120587 0.0017660000 14738941 955859216 1373700096 -1.0139200687 -0.0004540498 0.5619788170 161 6.4000000000 0.0293335728 0.0289501204 0.0447682627 0.0072972036 0.0017520000 14740917 955859216 1373700096 -1.0135977268 -0.0014593221 0.5728145242 162 6.4400000000 0.0294710044 0.0289533358 0.0447682627 0.0072769061 0.0017730000 14742893 955859216 1373700096 -1.0136095285 -0.0033544535 0.5839195251 163 6.4800000000 0.0313375257 0.0289679627 0.0447682627 0.0072599175 0.0017830000 14744869 955859216 1373700096 -1.0139038563 -0.0038629188 0.5966653228 164 6.5200000000 0.0332279876 0.0289939385 0.0447682627 0.0072415279 0.0017690000 14746845 955859216 1373700096 -1.0135594606 -0.0043836315 0.6085096002 165 6.5600000000 0.0263491347 0.0289779094 0.0447682627 0.0072378149 0.0018960000 14748821 955859216 1373700096 -1.0164617300 0.0035831986 0.6266111135 166 6.6000000000 0.0314561129 0.0289928383 0.0447682627 0.0072474864 0.0017610000 14750797 955859216 1373700096 -1.0144369602 -0.0007728875 0.6379879117 167 6.6400000000 0.0346690416 0.0290268275 0.0447682627 0.0072497206 0.0017520000 14752773 955859216 1373700096 -1.0124981403 -0.0019966257 0.6481599808 168 6.6800000000 0.0352400579 0.0290638110 0.0447682627 0.0072488921 0.0017830000 14754749 955859216 1373700096 -1.0115436316 -0.0023455033 0.6601815224 169 6.7200000000 0.0334330946 0.0290896648 0.0447682627 0.0072353764 0.0017730000 14756725 955859216 1373700096 -1.0117247105 -0.0027240436 0.6742966175 170 6.7600000000 0.0263997968 0.0290738420 0.0447682627 0.0072256560 0.0019170000 14758701 955859216 1373700096 -1.0159317255 0.0062106508 0.6922338605 171 6.8000000000 0.0297701154 0.0290779138 0.0447682627 0.0072205105 0.0017810000 14760677 955859216 1373700096 -1.0142139196 0.0056828400 0.7016834617 172 6.8400000000 0.0311636440 0.0290900402 0.0447682627 0.0072018972 0.0017620000 14762653 955859216 1373700096 -1.0129613876 0.0056175711 0.7138255835 173 6.8800000000 0.0324887969 0.0291096862 0.0447682627 0.0071821681 0.0017630000 14764629 955859216 1373700096 -1.0127391815 0.0059208353 0.7273163795 174 6.9200000000 0.0333534256 0.0291340755 0.0447682627 0.0071620717 0.0017790000 14766605 955859216 1373700096 -1.0135265589 0.0068563554 0.7397341728 175 6.9600000000 0.0261436943 0.0291169876 0.0447682627 0.0071443834 0.0019010000 14768581 955859216 1373700096 -1.0152851343 0.0147903319 0.7525559068 176 7.0000000000 0.0266945139 0.0291032235 0.0447682627 0.0071277996 0.0018350000 14770557 955859216 1373700096 -1.0165009499 0.0146241644 0.7670974731 177 7.0400000000 0.0264049601 0.0290879791 0.0447682627 0.0071375900 0.0018270000 14772533 955859216 1373700096 -1.0155630112 0.0125227310 0.7742269635 178 7.0800000000 0.0292499475 0.0290888890 0.0447682627 0.0071218853 0.0017670000 14774509 955859216 1373700096 -1.0137134790 0.0092087835 0.7816951275 179 7.1200000000 0.0270645935 0.0290775801 0.0447682627 0.0071065926 0.0018390000 14776485 955859216 1373700096 -1.0138490200 0.0139734987 0.7948855758 180 7.1600000000 0.0307317022 0.0290867697 0.0447682627 0.0070883853 0.0017610000 14778461 955859216 1373700096 -1.0119012594 0.0127906809 0.8072805405 181 7.2000000000 0.0324886031 0.0291055643 0.0447682627 0.0070723711 0.0017730000 14780437 955859216 1373700096 -1.0095132589 0.0117482869 0.8183897734 182 7.2400000000 0.0333176367 0.0291287076 0.0447682627 0.0070544538 0.0017800000 14782413 955859216 1373700096 -1.0092332363 0.0112481527 0.8315362930 183 7.2800000000 0.0254665446 0.0291086958 0.0447682627 0.0070456345 0.0019230000 14784389 955859216 1373700096 -1.0133792162 0.0194700826 0.8488296270 184 7.3200000000 0.0280845892 0.0291031300 0.0447682627 0.0070270458 0.0017710000 14786365 955859216 1373700096 -1.0105575323 0.0165038910 0.8593377471 185 7.3600000000 0.0299461465 0.0291076868 0.0447682627 0.0070111339 0.0017680000 14788341 955859216 1373700096 -1.0081831217 0.0150522459 0.8736726046 186 7.4000000000 0.0250503998 0.0290858734 0.0447682627 0.0069979396 0.0019100000 14790317 955859216 1373700096 -1.0099550486 0.0195820294 0.8928748369 187 7.4400000000 0.0255816132 0.0290671341 0.0447682627 0.0069911637 0.0018540000 14792293 955859216 1373700096 -1.0067076683 0.0191323254 0.9012979269 188 7.4800000000 0.0298663862 0.0290713854 0.0447682627 0.0070032790 0.0017650000 14794269 955859216 1373700096 -1.0030506849 0.0185130965 0.9159866571 189 7.5200000000 0.0247377139 0.0290484559 0.0447682627 0.0069877590 0.0019150000 14796245 955859216 1373700096 -1.0024044514 0.0262677483 0.9341064095 190 7.5600000000 0.0282298177 0.0290441473 0.0447682627 0.0069750725 0.0017680000 14798221 955859216 1373700096 -0.9990354776 0.0217462555 0.9481727481 191 7.6000000000 0.0243647955 0.0290196481 0.0447682627 0.0069624349 0.0018990000 14800197 955859216 1373700096 -0.9989262223 0.0278177913 0.9650224447 192 7.6400000000 0.0311474763 0.0290307305 0.0447682627 0.0069611414 0.0017860000 14802173 955859216 1373700096 -0.9934834838 0.0272605624 0.9794617891 193 7.6800000000 0.0241593588 0.0290054903 0.0447682627 0.0069681594 0.0019210000 14804149 955859216 1373700096 -0.9953174591 0.0345422551 0.9980950356 194 7.7200000000 0.0245255176 0.0289823976 0.0447682627 0.0069632592 0.0018500000 14806125 955859216 1373700096 -0.9954842329 0.0301160235 1.0141129494 195 7.7600000000 0.0245572906 0.0289597048 0.0447682627 0.0069655898 0.0018520000 14808101 955859216 1373700096 -0.9942732453 0.0298264064 1.0269939899 196 7.8000000000 0.0250496827 0.0289397557 0.0447682627 0.0070013470 0.0018390000 14810077 955859216 1373700096 -0.9922578931 0.0329510942 1.0435688496 197 7.8400000000 0.0249935035 0.0289197239 0.0447682627 0.0070256402 0.0018380000 14812053 955859216 1373700096 -0.9904992580 0.0365103893 1.0555096865 198 7.8800000000 0.0249422733 0.0288996358 0.0447682627 0.0070432316 0.0018050000 14814029 955859216 1373700096 -0.9893495440 0.0402539819 1.0719889402 199 7.9200000000 0.0242895223 0.0288764694 0.0447682627 0.0070356487 0.0018160000 14816005 955859216 1373700096 -0.9874873757 0.0418962538 1.0876851082 200 7.9600000000 0.0236434266 0.0288503042 0.0447682627 0.0070254129 0.0018420000 14817981 955859216 1373700096 -0.9875384569 0.0410162322 1.1016012430 201 8.0000000000 0.0236467756 0.0288244160 0.0447682627 0.0070400225 0.0018380000 14819957 955859216 1373700096 -0.9868668318 0.0414892510 1.1200838089 202 8.0400000000 0.0234075058 0.0287975996 0.0447682627 0.0070561863 0.0018190000 14821933 955859216 1373700096 -0.9841389060 0.0425843261 1.1306420565 203 8.0800000000 0.0237137359 0.0287725559 0.0447682627 0.0070651065 0.0018120000 14823909 955859216 1373700096 -0.9817834496 0.0440961085 1.1475769281 204 8.1200000000 0.0232130829 0.0287453036 0.0447682627 0.0070565699 0.0018220000 14825885 955859216 1373700096 -0.9800291061 0.0440619029 1.1601716280 205 8.1600000000 0.0242083091 0.0287231719 0.0447682627 0.0070483458 0.0017450000 14827861 955859216 1373700096 -0.9768056273 0.0420643203 1.1713614464 206 8.1999999990 0.0264140125 0.0287119624 0.0447682627 0.0070395393 0.0017670000 14829837 955859216 1373700096 -0.9728808999 0.0400398076 1.1841441393 207 8.2400000000 0.0300100259 0.0287182333 0.0447682627 0.0070337441 0.0017480000 14831813 955859216 1373700096 -0.9674938917 0.0394921675 1.1974446774 208 8.2799999990 0.0336118564 0.0287417603 0.0447682627 0.0070197022 0.0017460000 14833789 955859216 1373700096 -0.9623970389 0.0381118059 1.2099478245 209 8.3200000000 0.0374263600 0.0287833134 0.0447682627 0.0070141756 0.0017460000 14835765 955859216 1373700096 -0.9568964839 0.0362688191 1.2227028608 210 8.3599999990 0.0407109521 0.0288401117 0.0447682627 0.0070325966 0.0017630000 14837741 955859216 1373700096 -0.9504666328 0.0338186771 1.2343848944 211 8.4000000000 0.0416263975 0.0289007102 0.0447682627 0.0070489699 0.0017550000 14839717 955859216 1373700096 -0.9451483488 0.0311154295 1.2473406792 212 8.4399999990 0.0435108207 0.0289696258 0.0447682627 0.0070341790 0.0017380000 14841693 955859216 1373700096 -0.9375286698 0.0322084762 1.2594757080 213 8.4800000000 0.0477531627 0.0290578114 0.0477531627 0.0070318357 0.0017470000 14843669 955859216 1373700096 -0.9300083518 0.0318944827 1.2732145786 214 8.5200000000 0.0234134346 0.0290314358 0.0477531627 0.0071658857 0.0019680000 14845645 955859216 1373700096 -0.9292214513 0.0556521006 1.2874873877 215 8.5600000000 0.0280723497 0.0290269750 0.0477531627 0.0071701680 0.0017570000 14847621 955859216 1373700096 -0.9202402234 0.0505665056 1.2983636856 216 8.6000000000 0.0231457744 0.0289997472 0.0477531627 0.0071567808 0.0018860000 14849597 955859216 1373700096 -0.9122208953 0.0597425066 1.3096024990 217 8.6400000000 0.0260313563 0.0289860680 0.0477531627 0.0071751091 0.0018350000 14851573 955859216 1373700096 -0.9025861621 0.0599042214 1.3261153698 218 8.6800000000 0.0261054728 0.0289728542 0.0477531627 0.0072216402 0.0018340000 14853549 955859216 1373700096 -0.8940474987 0.0595863238 1.3357015848 219 8.7200000000 0.0324659795 0.0289888046 0.0477531627 0.0072177948 0.0017550000 14855525 955859216 1373700096 -0.8824345469 0.0561341569 1.3470026255 220 8.7600000000 0.0401655994 0.0290396082 0.0477531627 0.0072164426 0.0017770000 14857501 955859216 1373700096 -0.8699951768 0.0534483977 1.3588255644 221 8.8000000000 0.0448275805 0.0291110470 0.0477531627 0.0072452676 0.0017660000 14859477 955859216 1373700096 -0.8591436148 0.0500019230 1.3705561161 222 8.8400000000 0.0473100655 0.0291930245 0.0477531627 0.0072487765 0.0017680000 14861453 955859216 1373700096 -0.8493044972 0.0491803437 1.3842712641 223 8.8800000000 0.0499672703 0.0292861826 0.0499672703 0.0072471862 0.0017760000 14863429 955859216 1373700096 -0.8380841613 0.0496709943 1.3950052261 224 8.9200000000 0.0532432497 0.0293931338 0.0532432497 0.0072491076 0.0017710000 14865405 955859216 1373700096 -0.8265714049 0.0494002849 1.4058028460 225 8.9600000000 0.0543511845 0.0295040585 0.0543511845 0.0072446182 0.0017690000 14867381 955859216 1373700096 -0.8159236908 0.0509616770 1.4142695665 226 9.0000000000 0.0542027541 0.0296133447 0.0543511845 0.0072299642 0.0017630000 14869357 955859216 1373700096 -0.8056901097 0.0550000407 1.4249929190 227 9.0400000000 0.0307612978 0.0296184018 0.0543511845 0.0072568634 0.0019440000 14871333 955859216 1373700096 -0.7993144989 0.0837627500 1.4338676929 228 9.0800000000 0.0325020216 0.0296310492 0.0543511845 0.0072643972 0.0018170000 14873309 955859216 1373700096 -0.7874636054 0.0878376141 1.4475501776 229 9.1200000000 0.0307020396 0.0296357261 0.0543511845 0.0073235062 0.0018710000 14875285 955859216 1373700096 -0.7772931457 0.0936341435 1.4551151991 230 9.1600000000 0.0298140869 0.0296365015 0.0543511845 0.0074221851 0.0018780000 14877261 955859216 1373700096 -0.7666617632 0.0986223221 1.4619880915 231 9.2000000000 0.0292270090 0.0296347288 0.0543511845 0.0076281199 0.0018580000 14879237 955859216 1373700096 -0.7575344443 0.1002483591 1.4694612026 232 9.2400000000 0.0286675375 0.0296305599 0.0543511845 0.0077876561 0.0018500000 14881213 955859216 1373700096 -0.7482095957 0.1037601307 1.4778265953 233 9.2800000000 0.0277900025 0.0296226605 0.0543511845 0.0079283066 0.0018390000 14883189 955859216 1373700096 -0.7388194203 0.1074943095 1.4851757288 234 9.3200000000 0.0267400183 0.0296103415 0.0543511845 0.0080304171 0.0018080000 14885165 955859216 1373700096 -0.7291193604 0.1122767702 1.4921215773 235 9.3600000000 0.0252359807 0.0295917272 0.0543511845 0.0081074735 0.0018350000 14887141 955859216 1373700096 -0.7194256186 0.1171275228 1.4993838072 236 9.4000000000 0.0242697932 0.0295691767 0.0543511845 0.0081664388 0.0018210000 14889117 955859216 1373700096 -0.7102528214 0.1208009943 1.5079225302 237 9.4400000000 0.0240241643 0.0295457800 0.0543511845 0.0081936510 0.0017830000 14891093 955859216 1373700096 -0.7003825903 0.1252481192 1.5142383575 238 9.4800000000 0.0238581616 0.0295218824 0.0543511845 0.0082136943 0.0017790000 14893069 955859216 1373700096 -0.6896076202 0.1313915849 1.5219943523 239 9.5200000000 0.0236754157 0.0294974202 0.0543511845 0.0082555893 0.0017750000 14895045 955859216 1373700096 -0.6789520979 0.1368269175 1.5294325352 240 9.5600000000 0.0234320574 0.0294721479 0.0543511845 0.0083077153 0.0017800000 14897021 955859216 1373700096 -0.6688743830 0.1418543309 1.5380967855 241 9.6000000000 0.0234344620 0.0294470953 0.0543511845 0.0083593511 0.0017250000 14898997 955859216 1373700096 -0.6595886946 0.1427345723 1.5467903614 242 9.6400000000 0.0233139154 0.0294217515 0.0543511845 0.0083788362 0.0017300000 14900973 955859216 1373700096 -0.6498594880 0.1454823464 1.5553196669 243 9.6800000000 0.0227643307 0.0293943547 0.0543511845 0.0083923899 0.0018040000 14902949 955859216 1373700096 -0.6390765905 0.1520139277 1.5630402565 244 9.7200000000 0.0226078443 0.0293665412 0.0543511845 0.0084362811 0.0017970000 14904925 955859216 1373700096 -0.6278238893 0.1585983038 1.5711023808 245 9.7600000000 0.0257832557 0.0293519155 0.0543511845 0.0084912899 0.0016930000 14906901 955859216 1373700096 -0.6166199446 0.1580648571 1.5793119669 246 9.8000000000 0.0261367504 0.0293388457 0.0543511845 0.0085084596 0.0016810000 14908877 955859216 1373700096 -0.6061934829 0.1605641097 1.5880331993 247 9.8400000000 0.0251864791 0.0293220345 0.0543511845 0.0085129686 0.0016850000 14910853 955859216 1373700096 -0.5970054269 0.1616924703 1.5975450277 248 9.8800000000 0.0248275530 0.0293039116 0.0543511845 0.0084975914 0.0016870000 14912829 955859216 1373700096 -0.5877918601 0.1637859195 1.6058858633 249 9.9200000000 0.0242010318 0.0292834181 0.0543511845 0.0084814757 0.0016800000 14914805 955859216 1373700096 -0.5779747367 0.1666753888 1.6131724119 250 9.9600000000 0.0226557609 0.0292569075 0.0543511845 0.0084651181 0.0017320000 14916781 955859216 1373700096 -0.5687619448 0.1704062074 1.6228171587 251 10.0000000000 0.0224985704 0.0292299819 0.0543511845 0.0084486001 0.0017170000 14918757 955859216 1373700096 -0.5587411523 0.1736174226 1.6314550638 252 10.0400000000 0.0223166216 0.0292025479 0.0543511845 0.0084345502 0.0017110000 14920733 955859216 1373700096 -0.5502535701 0.1728850752 1.6417939663 253 10.0800000000 0.0220484678 0.0291742709 0.0543511845 0.0084187932 0.0017040000 14922709 955859216 1373700096 -0.5427398682 0.1700282544 1.6515837908 254 10.1200000000 0.0231019612 0.0291503642 0.0543511845 0.0084377770 0.0016460000 14924685 955859216 1373700096 -0.5327363014 0.1727415621 1.6595872641 255 10.1600000000 0.0233024899 0.0291274313 0.0543511845 0.0084531779 0.0016330000 14926661 955859216 1373700096 -0.5218240619 0.1794519573 1.6687395573 256 10.2000000000 0.0227891225 0.0291026723 0.0543511845 0.0084402303 0.0016540000 14928637 955859216 1373700096 -0.5107817650 0.1848551482 1.6775649786 257 10.2400000000 0.0224625114 0.0290768351 0.0543511845 0.0084256026 0.0016570000 14955189 955859216 1373700096 -0.5015045404 0.1848772764 1.6861320734 258 10.2800000000 0.0238456596 0.0290565592 0.0543511845 0.0084093756 0.0016460000 15008365 955859216 1373700096 -0.4908240438 0.1886450648 1.6949883699 259 10.3200000000 0.0245484076 0.0290391532 0.0543511845 0.0084018338 0.0016750000 15010341 955859216 1373700096 -0.4801949859 0.1918172091 1.7013260126 260 10.3600000000 0.0213852562 0.0290097152 0.0543511845 0.0084098362 0.0017890000 15012317 955859216 1373700096 -0.4710842967 0.1965124458 1.7099574804 261 10.4000000000 0.0232570339 0.0289876742 0.0543511845 0.0084076175 0.0016740000 15014293 955859216 1373700096 -0.4610050023 0.1941965222 1.7163038254 262 10.4400000000 0.0236739870 0.0289673930 0.0543511845 0.0083944600 0.0016480000 15016269 955859216 1373700096 -0.4513933957 0.1940551400 1.7234774828 263 10.4800000000 0.0234659072 0.0289464748 0.0543511845 0.0083803095 0.0016520000 15018245 955859216 1373700096 -0.4406108558 0.1957716048 1.7297089100 264 10.5200000000 0.0232095905 0.0289247442 0.0543511845 0.0083693984 0.0016450000 15020221 955859216 1373700096 -0.4303473532 0.1956958920 1.7357996702 265 10.5600000000 0.0227361992 0.0289013912 0.0543511845 0.0083538111 0.0016590000 15022197 955859216 1373700096 -0.4192064703 0.1980653256 1.7425302267 266 10.6000000000 0.0212382842 0.0288725825 0.0543511845 0.0083433856 0.0017260000 15024173 955859216 1373700096 -0.4076711237 0.2018275410 1.7465991974 267 10.6400000000 0.0210632198 0.0288433340 0.0543511845 0.0083394105 0.0017100000 15026149 955859216 1373700096 -0.3964717686 0.2010790557 1.7506929636 268 10.6800000000 0.0219995473 0.0288177974 0.0543511845 0.0083315505 0.0016530000 15028125 955859216 1373700096 -0.3848026395 0.1996990889 1.7573475838 269 10.7200000000 0.0218452793 0.0287918773 0.0543511845 0.0083198930 0.0016480000 15030101 955859216 1373700096 -0.3728961349 0.1998041272 1.7601476908 270 10.7600000000 0.0206871647 0.0287618598 0.0543511845 0.0083115904 0.0017880000 15032077 955859216 1373700096 -0.3479636610 0.2055473030 1.7698251009 271 10.8000000000 0.0206131302 0.0287317907 0.0543511845 0.0083274921 0.0017890000 15034053 955859216 1373700096 -0.3336540163 0.2093640417 1.7731496096 272 10.8400000000 0.0204886328 0.0287014850 0.0543511845 0.0083878167 0.0017380000 15036029 955859216 1373700096 -0.3217088580 0.2076520324 1.7769747972 273 10.8800000000 0.0204232521 0.0286711618 0.0543511845 0.0083955777 0.0017000000 15038005 955859216 1373700096 -0.3091179132 0.2084467411 1.7815217972 274 10.9200000000 0.0203350727 0.0286407381 0.0543511845 0.0084035113 0.0017160000 15039981 955859216 1373700096 -0.2958701849 0.2097495049 1.7852451801 275 10.9600000000 0.0202838760 0.0286103495 0.0543511845 0.0084084013 0.0017350000 15041957 955859216 1373700096 -0.2829736471 0.2098035663 1.7880736589 276 11.0000000000 0.0201699100 0.0285797682 0.0543511845 0.0084051774 0.0017110000 15043933 955859216 1373700096 -0.2695384622 0.2117922008 1.7919459343 277 11.0400000000 0.0199882220 0.0285487518 0.0543511845 0.0084106003 0.0017840000 15045909 955859216 1373700096 -0.2560421526 0.2134282738 1.7952466011 278 11.0800000000 0.0198972989 0.0285176315 0.0543511845 0.0084156368 0.0017240000 15047885 955859216 1373700096 -0.2424659729 0.2153017372 1.7988896370 279 11.1200000000 0.0197792333 0.0284863111 0.0543511845 0.0084248769 0.0018260000 15049861 955859216 1373700096 -0.2285599113 0.2171804458 1.8027018309 280 11.1600000000 0.0196872465 0.0284548858 0.0543511845 0.0084326883 0.0018150000 15051837 955859216 1373700096 -0.2145738900 0.2197817564 1.8059413433 281 11.2000000000 0.0196348149 0.0284234977 0.0543511845 0.0084383099 0.0017630000 15053813 955859216 1373700096 -0.2014212459 0.2207072973 1.8088129759 282 11.2400000000 0.0195841566 0.0283921525 0.0543511845 0.0084332596 0.0017650000 15055789 955859216 1373700096 -0.1895742863 0.2197891623 1.8133898973 283 11.2800000000 0.0204044580 0.0283639274 0.0543511845 0.0084184910 0.0017170000 15057765 955859216 1373700096 -0.1768746227 0.2204895020 1.8166286945 284 11.3200000000 0.0194833782 0.0283326579 0.0543511845 0.0084075072 0.0017810000 15059741 955859216 1373700096 -0.1646897644 0.2233833969 1.8214668036 285 11.3600000000 0.0192131232 0.0283006595 0.0543511845 0.0084046520 0.0017980000 15061717 955859216 1373700096 -0.1531862617 0.2247336656 1.8256874084 286 11.4000000000 0.0190011226 0.0282681437 0.0543511845 0.0083960531 0.0017940000 15063693 955859216 1373700096 -0.1427073479 0.2249540389 1.8297106028 287 11.4400000000 0.0188669786 0.0282353870 0.0543511845 0.0083815079 0.0017890000 15065669 955859216 1373700096 -0.1332273930 0.2247041911 1.8338506222 288 11.4800000000 0.0187577605 0.0282024786 0.0543511845 0.0083676744 0.0017950000 15067645 955859216 1373700096 -0.1243782938 0.2247366458 1.8378828764 289 11.5200000000 0.0186587498 0.0281694553 0.0543511845 0.0083542938 0.0017980000 15069621 955859216 1373700096 -0.1158834919 0.2247059047 1.8443549871 290 11.5600000000 0.0185648706 0.0281363360 0.0543511845 0.0083451768 0.0017980000 15071597 955859216 1373700096 -0.1075889692 0.2252391875 1.8501930237 291 11.6000000000 0.0184186492 0.0281029419 0.0543511845 0.0083338951 0.0017800000 15073573 955859216 1373700096 -0.1000926122 0.2244587094 1.8572280407 292 11.6400000000 0.0182777122 0.0280692939 0.0543511845 0.0083212232 0.0017920000 15075549 955859216 1373700096 -0.0920894220 0.2256286144 1.8630393744 293 11.6800000000 0.0182022396 0.0280356179 0.0543511845 0.0083070214 0.0018000000 15077525 955859216 1373700096 -0.0851411521 0.2259594798 1.8698258400 294 11.7200000000 0.0181425270 0.0280019679 0.0543511845 0.0082941512 0.0018130000 15079501 955859216 1373700096 -0.0790492296 0.2252689451 1.8770031929 295 11.7600000000 0.0184509885 0.0279695917 0.0543511845 0.0082854522 0.0017290000 15081477 955859216 1373700096 -0.0733684674 0.2249023318 1.8836969137 296 11.8000000000 0.0190237258 0.0279393692 0.0543511845 0.0082762874 0.0017370000 15083453 955859216 1373700096 -0.0674736425 0.2244607359 1.8897870779 297 11.8400000000 0.0194209907 0.0279106878 0.0543511845 0.0082674774 0.0017460000 15085429 955859216 1373700096 -0.0625906363 0.2235445529 1.8967965841 298 11.8800000000 0.0200022850 0.0278841495 0.0543511845 0.0082621125 0.0017620000 15087405 955859216 1373700096 -0.0576897524 0.2222732902 1.9040490389 299 11.9200000000 0.0177868064 0.0278503792 0.0543511845 0.0082522374 0.0019100000 15089381 955859216 1373700096 -0.0528650023 0.2247164696 1.9140126705 300 11.9600000000 0.0194641110 0.0278224249 0.0543511845 0.0082399281 0.0017720000 15091357 955859216 1373700096 -0.0477565937 0.2237150222 1.9210722446 301 12.0000000000 0.0178991407 0.0277894572 0.0543511845 0.0082264619 0.0018580000 15093333 955859216 1373700096 -0.0432940796 0.2256961316 1.9312576056 302 12.0400000000 0.0176636185 0.0277559279 0.0543511845 0.0082151903 0.0018720000 15095309 955859216 1373700096 -0.0393741392 0.2257688046 1.9411774874 303 12.0800000000 0.0175054502 0.0277220980 0.0543511845 0.0082086344 0.0018830000 15097285 955859216 1373700096 -0.0352298841 0.2262588888 1.9510909319 304 12.1200000000 0.0172997843 0.0276878141 0.0543511845 0.0082064212 0.0018980000 15099261 955859216 1373700096 -0.0313895792 0.2267034352 1.9613165855 305 12.1600000000 0.0170774013 0.0276530258 0.0543511845 0.0082027019 0.0019070000 15101237 955859216 1373700096 -0.0277781282 0.2268647999 1.9726704359 306 12.2000000000 0.0168613326 0.0276177589 0.0543511845 0.0081952743 0.0018940000 15103213 955859216 1373700096 -0.0242387354 0.2270596772 1.9842051268 307 12.2400000000 0.0167088900 0.0275822251 0.0543511845 0.0081962867 0.0018990000 15105189 955859216 1373700096 -0.0210366566 0.2279234380 1.9957036972 308 12.2800000000 0.0166050866 0.0275465850 0.0543511845 0.0081991637 0.0019040000 15107165 955859216 1373700096 -0.0184569806 0.2281551808 2.0073137283 309 12.3200000000 0.0162445270 0.0275100088 0.0543511845 0.0082095664 0.0019780000 15109141 955859216 1373700096 -0.0166113563 0.2281890512 2.0183999538 310 12.3600000000 0.0160627551 0.0274730822 0.0543511845 0.0082272549 0.0019770000 15111117 955859216 1373700096 -0.0150094973 0.2278483659 2.0303113461 311 12.4000000000 0.0158960726 0.0274358570 0.0543511845 0.0082399999 0.0020030000 15113093 955859216 1373700096 -0.0128577612 0.2288403064 2.0410690308 312 12.4400000000 0.0155401789 0.0273977299 0.0543511845 0.0082745533 0.0019880000 15115069 955859216 1373700096 -0.0106416289 0.2289584875 2.0650155544 313 12.4800000000 0.0153032010 0.0273590892 0.0543511845 0.0082677098 0.0019570000 15117045 955859216 1373700096 -0.0101085147 0.2290013880 2.0756490231 314 12.5200000000 0.0150869088 0.0273200058 0.0543511845 0.0082592418 0.0019430000 15119021 955859216 1373700096 -0.0101133687 0.2281064242 2.0882492065 315 12.5600000000 0.0147276064 0.0272800300 0.0543511845 0.0082580228 0.0019500000 15120997 955859216 1373700096 -0.0097571108 0.2287362218 2.0997283459 316 12.6000000000 0.0144134909 0.0272393131 0.0543511845 0.0082470503 0.0019510000 15122973 955859216 1373700096 -0.0096436432 0.2293653935 2.1120147705 317 12.6400000000 0.0139672663 0.0271974454 0.0543511845 0.0082340663 0.0019550000 15124949 955859216 1373700096 -0.0100242179 0.2292243689 2.1237239838 318 12.6800000000 0.0138741145 0.0271555481 0.0543511845 0.0082210814 0.0020650000 15126925 955859216 1373700096 -0.0106893387 0.2288476378 2.1349911690 319 12.7200000000 0.0135786701 0.0271129874 0.0543511845 0.0082081745 0.0020710000 15128901 955859216 1373700096 -0.0114719933 0.2293587774 2.1450600624 320 12.7600000000 0.0132942600 0.0270698039 0.0543511845 0.0081953374 0.0020690000 15130877 955859216 1373700096 -0.0127197634 0.2298702747 2.1553287506 321 12.8000000000 0.0130221201 0.0270260416 0.0543511845 0.0081854308 0.0020780000 15132853 955859216 1373700096 -0.0148997270 0.2290879637 2.1658945084 322 12.8400000000 0.0127291232 0.0269816412 0.0543511845 0.0081752688 0.0020910000 15134829 955859216 1373700096 -0.0165706314 0.2297931910 2.1751587391 323 12.8800000000 0.0124349082 0.0269366049 0.0543511845 0.0081668656 0.0021030000 15136805 955859216 1373700096 -0.0185680538 0.2290612161 2.1837677956 324 12.9200000000 0.0121449865 0.0268909518 0.0543511845 0.0081556033 0.0021110000 15138781 955859216 1373700096 -0.0205952637 0.2288108468 2.1928777695 325 12.9600000000 0.0118749486 0.0268447487 0.0543511845 0.0081433305 0.0021150000 15140757 955859216 1373700096 -0.0220143944 0.2300293297 2.2018015385 326 13.0000000000 0.0116461385 0.0267981272 0.0543511845 0.0081317936 0.0022110000 15142733 955859216 1373700096 -0.0240028258 0.2300167233 2.2089202404 327 13.0400000000 0.0113854269 0.0267509935 0.0543511845 0.0081212945 0.0022240000 15144709 955859216 1373700096 -0.0260352194 0.2307835966 2.2185208797 328 13.0800000000 0.0111715859 0.0267034954 0.0543511845 0.0081096608 0.0022420000 15146685 955859216 1373700096 -0.0266181305 0.2338072807 2.2247934341 329 13.1200000000 0.0109577794 0.0266556360 0.0543511845 0.0080983161 0.0022850000 15148661 955859216 1373700096 -0.0282719769 0.2349527776 2.2338347435 330 13.1600000000 0.0107768001 0.0266075183 0.0543511845 0.0080877264 0.0022750000 15150637 955859216 1373700096 -0.0302092712 0.2355632782 2.2420363426 331 13.2000000000 0.0106484471 0.0265593036 0.0543511845 0.0080760474 0.0022930000 15152613 955859216 1373700096 -0.0319878757 0.2365132421 2.2522706985 332 13.2400000000 0.0105958842 0.0265112210 0.0543511845 0.0080652681 0.0022470000 15154589 955859216 1373700096 -0.0338581540 0.2372922748 2.2611906528 333 13.2800000000 0.0104906028 0.0264631111 0.0543511845 0.0080536055 0.0022750000 15156565 955859216 1373700096 -0.0360162966 0.2378775477 2.2710642815 334 13.3200000000 0.0104132537 0.0264150576 0.0543511845 0.0080427037 0.0022950000 15158541 955859216 1373700096 -0.0383335017 0.2381175011 2.2795681953 335 13.3600000000 0.0102929501 0.0263669319 0.0543511845 0.0080307154 0.0023130000 15160517 955859216 1373700096 -0.0404408053 0.2393509150 2.2884616852 336 13.4000000000 0.0101608438 0.0263186995 0.0543511845 0.0080187939 0.0023100000 15162493 955859216 1373700096 -0.0419589579 0.2414917350 2.2964203358 337 13.4400000000 0.0100338086 0.0262703764 0.0543511845 0.0080182863 0.0023750000 15164469 955859216 1373700096 -0.0436890237 0.2441018373 2.3039760590 338 13.4800000000 0.0098868813 0.0262219045 0.0543511845 0.0080257347 0.0023800000 15166445 955859216 1373700096 -0.0455330908 0.2459546626 2.3102934361 339 13.5200000000 0.0097830510 0.0261734123 0.0543511845 0.0080433288 0.0024420000 15168421 955859216 1373700096 -0.0479704663 0.2461466640 2.3159101009 340 13.5600000000 0.0097080879 0.0261249849 0.0543511845 0.0080401532 0.0024490000 15170397 955859216 1373700096 -0.0503554791 0.2466998845 2.3210201263 341 13.6000000000 0.0096619418 0.0260767062 0.0543511845 0.0080337174 0.0024740000 15172373 955859216 1373700096 -0.0525216274 0.2472783178 2.3258552551 342 13.6400000000 0.0095769279 0.0260284612 0.0543511845 0.0080259078 0.0024080000 15174349 955859216 1373700096 -0.0546566881 0.2477803528 2.3315584660 343 13.6800000000 0.0095103635 0.0259803035 0.0543511845 0.0080143599 0.0024030000 15176325 955859216 1373700096 -0.0566360280 0.2481920272 2.3364248276 344 13.7200000000 0.0094770333 0.0259323289 0.0543511845 0.0080027461 0.0024090000 15178301 955859216 1373700096 -0.0577345416 0.2499312609 2.3419718742 345 13.7600000000 0.0094079515 0.0258844321 0.0543511845 0.0079951692 0.0024200000 15180277 955859216 1373700096 -0.0596604459 0.2499268204 2.3474886417 346 13.8000000000 0.0093585877 0.0258366696 0.0543511845 0.0079899502 0.0023920000 15182253 955859216 1373700096 -0.0613346770 0.2499019802 2.3525602818 347 13.8400000000 0.0092951674 0.0257889995 0.0543511845 0.0079790391 0.0023980000 15184229 955859216 1373700096 -0.0636700839 0.2486606985 2.3571131229 348 13.8800000000 0.0092381435 0.0257414396 0.0543511845 0.0079683634 0.0023950000 15186205 955859216 1373700096 -0.0642573833 0.2509503365 2.3628802299 349 13.9200000000 0.0091454443 0.0256938866 0.0543511845 0.0079661357 0.0023570000 15188181 955859216 1373700096 -0.0659284368 0.2507696450 2.3686566353 350 13.9600000000 0.0090708761 0.0256463923 0.0543511845 0.0079571722 0.0023490000 15190157 955859216 1373700096 -0.0679457262 0.2494797111 2.3774843216 351 14.0000000000 0.0090689911 0.0255991632 0.0543511845 0.0079466036 0.0023880000 15192133 955859216 1373700096 -0.0680256411 0.2502009571 2.3817758560 352 14.0400000000 0.0092713190 0.0255527773 0.0543511845 0.0079377746 0.0022820000 15194109 955859216 1373700096 -0.0686996430 0.2496340573 2.3867006302 353 14.0800000000 0.0092250602 0.0255065232 0.0543511845 0.0079265026 0.0022790000 15196085 955859216 1373700096 -0.0690713599 0.2487249821 2.3909785748 354 14.1200000000 0.0090072760 0.0254599151 0.0543511845 0.0079153726 0.0023640000 15198061 955859216 1373700096 -0.0687036440 0.2495034188 2.3956110477 355 14.1600000000 0.0091834217 0.0254140658 0.0543511845 0.0079044860 0.0022640000 15200037 955859216 1373700096 -0.0693487749 0.2479413301 2.4006135464 356 14.2000000000 0.0089713102 0.0253678783 0.0543511845 0.0078951753 0.0023690000 15202013 955859216 1373700096 -0.0689985901 0.2480271757 2.4050791264 357 14.2400000000 0.0089438325 0.0253218726 0.0543511845 0.0078845411 0.0023550000 15203989 955859216 1373700096 -0.0686735883 0.2485603243 2.4106969833 358 14.2800000000 0.0090563400 0.0252764381 0.0543511845 0.0078743865 0.0022780000 15205965 955859216 1373700096 -0.0690733418 0.2471037656 2.4162888527 359 14.3200000000 0.0089671612 0.0252310084 0.0543511845 0.0078646866 0.0022770000 15207941 955859216 1373700096 -0.0696959198 0.2454509586 2.4217448235 360 14.3600000000 0.0089984415 0.0251859179 0.0543511845 0.0078561435 0.0028990000 15209917 955859216 1373700096 -0.0698790029 0.2441357672 2.4279108047 361 14.4000000000 0.0089813927 0.0251410300 0.0543511845 0.0078517208 0.0023220000 15211893 955859216 1373700096 -0.0700180903 0.2440299988 2.4343852997 362 14.4400000000 0.0089315949 0.0250962526 0.0543511845 0.0078449099 0.0022990000 15213869 955859216 1373700096 -0.0700521618 0.2443204224 2.4409403801 363 14.4800000000 0.0089179706 0.0250516843 0.0543511845 0.0078344266 0.0022900000 15215845 955859216 1373700096 -0.0699540898 0.2452151477 2.4481298923 364 14.5200000000 0.0085249590 0.0250062812 0.0543511845 0.0078248212 0.0021860000 15217821 955859216 1373700096 -0.0702325627 0.2448999733 2.4549949169 365 14.5600000000 0.0086151790 0.0249613741 0.0543511845 0.0078141811 0.0022810000 15219797 955859216 1373700096 -0.0708620772 0.2440967709 2.4623069763 366 14.6000000000 0.0086956350 0.0249169322 0.0543511845 0.0078037810 0.0022920000 15221773 955859216 1373700096 -0.0710430369 0.2448224872 2.4702184200 367 14.6400000000 0.0081924824 0.0248713615 0.0543511845 0.0077935414 0.0021910000 15223749 955859216 1373700096 -0.0708705187 0.2460364550 2.4768044949 368 14.6800000000 0.0082102269 0.0248260867 0.0543511845 0.0077840376 0.0022700000 15225725 955859216 1373700096 -0.0711371899 0.2468645275 2.4848628044 369 14.7200000000 0.0082900338 0.0247812735 0.0543511845 0.0077829895 0.0023660000 15227701 955859216 1373700096 -0.0719953850 0.2465994060 2.4924840927 370 14.7600000000 0.0082388474 0.0247365643 0.0543511845 0.0077805274 0.0023680000 15229677 955859216 1373700096 -0.0722305700 0.2470561713 2.5003833771 371 14.8000000000 0.0081973728 0.0246919842 0.0543511845 0.0077740743 0.0023780000 15231653 955859216 1373700096 -0.0723175183 0.2468346506 2.5076329708 372 14.8400000000 0.0081589874 0.0246475407 0.0543511845 0.0077698538 0.0023750000 15233629 955859216 1373700096 -0.0725506619 0.2464008033 2.5146796703 373 14.8800000000 0.0081263902 0.0246032481 0.0543511845 0.0077695280 0.0023870000 15235605 955859216 1373700096 -0.0727073252 0.2462665439 2.5220284462 374 14.9200000000 0.0080896728 0.0245590941 0.0543511845 0.0077655089 0.0024000000 15237581 955859216 1373700096 -0.0729095414 0.2456352115 2.5293769836 375 14.9600000000 0.0080560353 0.0245150860 0.0543511845 0.0077684509 0.0023930000 15239557 955859216 1373700096 -0.0726781636 0.2452607155 2.5363574028 376 15.0000000000 0.0080192667 0.0244712141 0.0543511845 0.0077679929 0.0024090000 15241533 955859216 1373700096 -0.0717136785 0.2466014922 2.5437612534 377 15.0400000000 0.0079683233 0.0244274399 0.0543511845 0.0077604916 0.0025240000 15243509 955859216 1373700096 -0.0694659576 0.2477855533 2.5569648743 378 15.0800000000 0.0078898948 0.0243836897 0.0543511845 0.0077502548 0.0025310000 15245485 955859216 1373700096 -0.0675317124 0.2490348071 2.5634212494 379 15.1200000000 0.0078182453 0.0243399814 0.0543511845 0.0077400416 0.0024280000 15247461 955859216 1373700096 -0.0656457692 0.2496003509 2.5690784454 380 15.1600000000 0.0077669993 0.0242963683 0.0543511845 0.0077309710 0.0024590000 15249437 955859216 1373700096 -0.0628928691 0.2507528067 2.5744292736 381 15.2000000000 0.0077470248 0.0242529317 0.0543511845 0.0077210394 0.0025560000 15251413 955859216 1373700096 -0.0605391227 0.2517849505 2.5795218945 382 15.2400000000 0.0077147516 0.0242096381 0.0543511845 0.0077123923 0.0025570000 15253389 955859216 1373700096 -0.0583168603 0.2522688806 2.5843272209 383 15.2800000000 0.0076702693 0.0241664543 0.0543511845 0.0077030292 0.0025760000 15255365 955859216 1373700096 -0.0556431264 0.2533217669 2.5888409615 384 15.3200000000 0.0076215859 0.0241233687 0.0543511845 0.0076930021 0.0025810000 15257341 955859216 1373700096 -0.0528287739 0.2540416718 2.5926477909 385 15.3600000000 0.0075964103 0.0240804416 0.0543511845 0.0076837125 0.0025870000 15259317 955859216 1373700096 -0.0503184684 0.2536545694 2.5952177048 386 15.4000000000 0.0075548403 0.0240376291 0.0543511845 0.0076801277 0.0026030000 15261293 955859216 1373700096 -0.0472671725 0.2543436587 2.5973520279 387 15.4400000000 0.0075027649 0.0239949034 0.0543511845 0.0076800167 0.0026180000 15263269 955859216 1373700096 -0.0435720794 0.2565023005 2.5994815826 388 15.4800000000 0.0074458793 0.0239522513 0.0543511845 0.0076704492 0.0026020000 15265245 955859216 1373700096 -0.0405419469 0.2577933371 2.6003835201 389 15.5200000000 0.0074007516 0.0239097024 0.0543511845 0.0076610441 0.0026210000 15267221 955859216 1373700096 -0.0379192159 0.2579590082 2.6013610363 390 15.5600000000 0.0073176203 0.0238671586 0.0543511845 0.0076512705 0.0026290000 15269197 955859216 1373700096 -0.0340504088 0.2610703409 2.6025207043 391 15.6000000000 0.0072901500 0.0238247622 0.0543511845 0.0076563107 0.0026200000 15271173 955859216 1373700096 -0.0308649577 0.2614251077 2.6038579941 392 15.6400000000 0.0071859965 0.0237823164 0.0543511845 0.0076471369 0.0025920000 15273149 955859216 1373700096 -0.0280285757 0.2612253129 2.6041920185 393 15.6800000000 0.0069644880 0.0237395229 0.0543511845 0.0076380874 0.0025590000 15275125 955859216 1373700096 -0.0258692466 0.2596949935 2.6045229435 394 15.7200000000 0.0066055628 0.0236960357 0.0543511845 0.0076305478 0.0025500000 15277101 955859216 1373700096 -0.0238975156 0.2578002214 2.6049606800 395 15.7600000000 0.0072458615 0.0236543897 0.0543511845 0.0076341452 0.0026800000 15279077 955859216 1373700096 -0.0206208657 0.2580629885 2.6064665318 396 15.8000000000 0.0084387325 0.0236159663 0.0543511845 0.0076281835 0.0027050000 15281053 955859216 1373700096 -0.0171139967 0.2581635714 2.6084003448 397 15.8400000000 0.0380216800 0.0236522527 0.0543511845 0.0077493386 0.0027620000 15283029 955859216 1373700096 -0.0150491809 0.2577674687 2.6396548748 398 15.8800000000 0.0674296468 0.0237622462 0.0674296468 0.0078557379 0.0028150000 15285005 955859216 1373700096 -0.0126965428 0.2559387982 2.6686720848 399 15.9200000000 0.1084955037 0.0239746102 0.1084955037 0.0080986560 0.0027840000 15286981 955859216 1373700096 -0.0091094142 0.2581055164 2.7083716393 400 15.9600000000 0.1078899428 0.0241843986 0.1084955037 0.0080922011 0.0028870000 15288957 955859216 1373700096 -0.0048114830 0.2589089572 2.7082769871 401 16.0000000000 0.1056476310 0.0243875488 0.1084955037 0.0080878847 0.0027480000 15290933 955859216 1373700096 -0.0002215748 0.2594987452 2.7066900730 402 16.0400000000 0.1047272459 0.0245873988 0.1084955037 0.0080803648 0.0027400000 15292909 955859216 1373700096 0.0053424025 0.2600296140 2.7060599327 403 16.0800000000 0.1040861905 0.0247846662 0.1084955037 0.0080756496 0.0027190000 15294885 955859216 1373700096 0.0100006824 0.2595392764 2.7070596218 404 16.1200000000 0.1035540625 0.0249796400 0.1084955037 0.0080674903 0.0027080000 15296861 955859216 1373700096 0.0149549423 0.2599554658 2.7056646347 405 16.1600000000 0.1031652838 0.0251726910 0.1084955037 0.0080595235 0.0026690000 15298837 955859216 1373700096 0.0203609131 0.2603804171 2.7068331242 406 16.2000000000 0.1029011607 0.0253641404 0.1084955037 0.0080512716 0.0026230000 15300813 955859216 1373700096 0.0262294859 0.2620225251 2.7092068195 407 16.2400000000 0.1024813205 0.0255536175 0.1084955037 0.0080439375 0.0025830000 15302789 955859216 1373700096 0.0313327946 0.2627715468 2.7107989788 408 16.2800000000 0.1022073925 0.0257414944 0.1084955037 0.0080458106 0.0025710000 15304765 955859216 1373700096 0.0365834124 0.2632706165 2.7134006023 409 16.3200000000 0.1019956619 0.0259279349 0.1084955037 0.0080482897 0.0025570000 15306741 955859216 1373700096 0.0431975499 0.2667645216 2.7158143520 410 16.3600000000 0.1017887965 0.0261129614 0.1084955037 0.0080402148 0.0025620000 15308717 955859216 1373700096 0.0493009016 0.2697891891 2.7200126648 411 16.3999999990 0.1016610637 0.0262967767 0.1084955037 0.0080351017 0.0025310000 15310693 955859216 1373700096 0.0527151898 0.2683784962 2.7215590477 412 16.4400000000 0.1015223041 0.0264793630 0.1084955037 0.0080505081 0.0025210000 15312669 955859216 1373700096 0.0578062236 0.2681902051 2.7276754379 413 16.4800000000 0.1013330594 0.0266606068 0.1084955037 0.0080645237 0.0025250000 15314645 955859216 1373700096 0.0639532655 0.2695344388 2.7342746258 414 16.5200000000 0.1012488380 0.0268407716 0.1084955037 0.0080611101 0.0025010000 15316621 955859216 1373700096 0.0686925426 0.2673730850 2.7377455235 415 16.5599999990 0.1011857912 0.0270199162 0.1084955037 0.0080746476 0.0024860000 15318597 955859216 1373700096 0.0717710033 0.2615094483 2.7432618141 416 16.6000000000 0.1008925810 0.0271974947 0.1084955037 0.0081507456 0.0024600000 15320573 955859216 1373700096 0.0779975429 0.2613831758 2.7486555576 417 16.6400000000 0.1005411074 0.0273733787 0.1084955037 0.0081804239 0.0024450000 15322549 955859216 1373700096 0.0842070803 0.2627329528 2.7499070168 418 16.6800000000 0.1002831236 0.0275478039 0.1084955037 0.0081834477 0.0024530000 15324525 955859216 1373700096 0.0863668323 0.2591116726 2.7490577698 419 16.7199999990 0.0998886824 0.0277204552 0.1084955037 0.0082114053 0.0024800000 15326501 955859216 1373700096 0.0939685777 0.2616644800 2.7543089390 420 16.7600000000 0.0990647152 0.0278903225 0.1084955037 0.0082020886 0.0023980000 15328477 955859216 1373700096 0.1012714356 0.2622881234 2.7533736229 421 16.8000000000 0.0987443998 0.0280586219 0.1084955037 0.0082130263 0.0023870000 15330453 955859216 1373700096 0.1051928625 0.2562024593 2.7539165020 422 16.8400000000 0.2332638204 0.0285448902 0.2332638204 0.0089216011 0.0024970000 15332429 955859216 1373700096 0.1121350676 0.4366623163 2.8058509827 423 16.8799999990 0.3316042721 0.0292613426 0.3316042721 0.0091001423 0.0025190000 15334405 955859216 1373700096 0.1195739731 0.5400285125 2.8278443813 424 16.9200000000 0.4469181597 0.0302463823 0.4469181597 0.0093362876 0.0026200000 15336381 955859216 1373700096 0.1252360642 0.6570962071 2.8453443050 425 16.9600000000 0.4793654680 0.0313031331 0.4793654680 0.0093567501 0.0026230000 15338357 955859216 1373700096 0.1341073066 0.6905671954 2.8490321636 426 17.0000000000 0.6326761842 0.0327148069 0.6326761842 0.0099358858 0.0027210000 15340333 955859216 1373700096 0.1465737671 0.8519924879 2.8560550213 427 17.0400000000 0.7899895310 0.0344882840 0.7899895310 0.0104266300 0.0029300000 15342309 955859216 1373700096 0.1553245336 1.0112634897 2.8562085629 428 17.0800000000 0.8124664426 0.0363059900 0.8124664426 0.0104183144 0.0028870000 15344285 955859216 1373700096 0.1570221186 1.0332832336 2.8509287834 429 17.1200000000 0.8953781724 0.0383084893 0.8953781724 0.0105456625 0.0031120000 15346261 955859216 1373700096 0.1737542301 1.1189978123 2.8431463242 430 17.1600000000 0.8969205022 0.0403052614 0.8969205022 0.0105374912 0.0030520000 15348237 955859216 1373700096 0.1819655597 1.1159451008 2.8399190903 431 17.2000000000 0.8869915605 0.0422697307 0.8969205022 0.0105281854 0.0029440000 15350213 955859216 1373700096 0.1926699132 1.1012387276 2.8370864391 432 17.2400000000 0.8800431490 0.0442090211 0.8969205022 0.0105313342 0.0029050000 15352189 955859216 1373700096 0.2080558240 1.0922392607 2.8340120316 433 17.2800000000 0.8762174845 0.0461305187 0.8969205022 0.0105258647 0.0028640000 15354165 955859216 1373700096 0.2202072889 1.0866317749 2.8293852806 434 17.3200000000 0.8704106808 0.0480297817 0.8969205022 0.0105210116 0.0027760000 15356141 955859216 1373700096 0.2310689986 1.0751649141 2.8240556717 435 17.3600000000 0.8658506274 0.0499098296 0.8969205022 0.0105341269 0.0027270000 15358117 955859216 1373700096 0.2449140549 1.0691894293 2.8199601173 436 17.4000000000 0.8610605001 0.0517702670 0.8969205022 0.0105449665 0.0027590000 15360093 955859216 1373700096 0.2611869872 1.0683058500 2.8121974468 437 17.4400000000 0.8561899066 0.0536110442 0.8969205022 0.0105333589 0.0027490000 15362069 955859216 1373700096 0.2780195475 1.0692309141 2.8020074368 438 17.4800000000 0.8535610437 0.0554374140 0.8969205022 0.0105654498 0.0027340000 15364045 955859216 1373700096 0.2904102504 1.0677254200 2.7940087318 439 17.5200000000 0.8501362801 0.0572476620 0.8969205022 0.0106225701 0.0027550000 15366021 955859216 1373700096 0.2960273325 1.0581035614 2.7857258320 440 17.5600000000 0.8503639698 0.0590501991 0.8969205022 0.0106302564 0.0026500000 15367997 955859216 1373700096 0.3002883494 1.0487830639 2.7809932232 441 17.6000000000 0.8482954502 0.0608398708 0.8969205022 0.0106279670 0.0026240000 15369973 955859216 1373700096 0.3081266582 1.0387805700 2.7769992352 442 17.6400000000 0.8432877660 0.0626101150 0.8969205022 0.0106790213 0.0026030000 15371949 955859216 1373700096 0.3217227161 1.0343686342 2.7685096264 443 17.6800000000 0.8345811963 0.0643527133 0.8969205022 0.0107256282 0.0026240000 15373925 955859216 1373700096 0.3438730240 1.0297411680 2.7502131462 444 17.7200000000 0.8297879696 0.0660766666 0.8969205022 0.0107158092 0.0025860000 15375901 955859216 1373700096 0.3527826965 1.0237433910 2.7403454781 445 17.7600000000 0.8263009191 0.0677850357 0.8969205022 0.0107062335 0.0025720000 15377877 955859216 1373700096 0.3619179130 1.0170595646 2.7336251736 446 17.8000000000 0.8225289583 0.0694772867 0.8969205022 0.0106971790 0.0025690000 15379853 955859216 1373700096 0.3693104982 1.0132995844 2.7244963646 447 17.8400000000 0.8202214241 0.0711568038 0.8969205022 0.0106874494 0.0024970000 15381829 955859216 1373700096 0.3739808500 1.0076577663 2.7176291943 448 17.8800000000 0.8173103333 0.0728223250 0.8969205022 0.0106783553 0.0025770000 15383805 955859216 1373700096 0.3807376325 1.0023665428 2.7114636898 449 17.9200000000 0.8150314093 0.0744753519 0.8969205022 0.0106703729 0.0024690000 15385781 955859216 1373700096 0.3878890574 0.9977252483 2.7045800686 450 17.9600000000 0.8133480549 0.0761172913 0.8969205022 0.0106629759 0.0024610000 15387757 955859216 1373700096 0.3950293362 0.9909679294 2.7012956142 451 18.0000000000 0.8113319278 0.0777474789 0.8969205022 0.0106646615 0.0024340000 15389733 955859216 1373700096 0.4055527151 0.9882218838 2.6965634823 452 18.0400000000 0.8082075715 0.0793635411 0.8969205022 0.0106589336 0.0024200000 15391709 955859216 1373700096 0.4149634242 0.9849576354 2.6904630661 453 18.0800000000 0.8058406115 0.0809672432 0.8969205022 0.0106491474 0.0023570000 15393685 955859216 1373700096 0.4222064614 0.9785256982 2.6858346462 454 18.1200000000 0.8036731482 0.0825591065 0.8969205022 0.0106467511 0.0023240000 15395661 955859216 1373700096 0.4327130616 0.9753446579 2.6812300682 455 18.1600000000 0.8022761345 0.0841409021 0.8969205022 0.0106380123 0.0023000000 15397637 955859216 1373700096 0.4445971549 0.9724429250 2.6773633957 456 18.2000000000 0.8000380397 0.0857108520 0.8969205022 0.0106302760 0.0023050000 15399613 955859216 1373700096 0.4549256563 0.9662136436 2.6732871532 457 18.2400000000 0.7989931107 0.0872716447 0.8969205022 0.0106271058 0.0022650000 15401589 955859216 1373700096 0.4646089673 0.9618213177 2.6700921059 458 18.2800000000 0.7973777056 0.0888220946 0.8969205022 0.0106347141 0.0022850000 15403565 955859216 1373700096 0.4765825868 0.9614993930 2.6669747829 459 18.3200000000 0.7935383916 0.0903574242 0.8969205022 0.0106292306 0.0022250000 15405541 955859216 1373700096 0.4909065664 0.9600673318 2.6601648331 460 18.3600000000 0.7923836708 0.0918835682 0.8969205022 0.0106222572 0.0022900000 15407517 955859216 1373700096 0.4997446835 0.9542637467 2.6582810879 461 18.4000000000 0.7923520207 0.0934030226 0.8969205022 0.0106129510 0.0022710000 15409493 955859216 1373700096 0.5111572742 0.9519463181 2.6566476822 462 18.4400000000 0.7893947363 0.0949094981 0.8969205022 0.0106056563 0.0022290000 15411469 955859216 1373700096 0.5234096050 0.9497582316 2.6510591507 463 18.4800000000 0.7868271470 0.0964039207 0.8969205022 0.0105956989 0.0022120000 15413445 955859216 1373700096 0.5316563845 0.9446849227 2.6459460258 464 18.5200000000 0.7877923846 0.0978939821 0.8969205022 0.0105907240 0.0022650000 15415421 955859216 1373700096 0.5412335396 0.9405249357 2.6480419636 465 18.5600000000 0.7874602675 0.0993769203 0.8969205022 0.0105832946 0.0021930000 15417397 955859216 1373700096 0.5489010215 0.9359051585 2.6460831165 466 18.6000000000 0.7879791260 0.1008546074 0.8969205022 0.0105839087 0.0021850000 15419373 955859216 1373700096 0.5629014969 0.9359858036 2.6475553513 467 18.6400000000 0.8152709603 0.1023844069 0.8969205022 0.0106575510 0.0023030000 15421349 955859216 1373700096 0.5651090741 0.9538845420 2.6717960835 468 18.6800000000 0.8315445185 0.1039424413 0.8969205022 0.0106823234 0.0022200000 15423325 955859216 1373700096 0.5743155479 0.9592900276 2.6938812733 469 18.7200000000 0.8258735538 0.1054817401 0.8969205022 0.0107106820 0.0023500000 15425301 955859216 1373700096 0.5861650705 0.9537701607 2.6871569157 470 18.7600000000 0.9189887643 0.1072126061 0.9189887643 0.0109703357 0.0023740000 15427277 955859216 1373700096 0.5920805335 1.0371615887 2.7207300663 471 18.8000000000 1.0149564743 0.1091398755 1.0149564743 0.0114448440 0.0027200000 15429253 955859216 1373700096 0.5982521176 1.1109492779 2.7881443501 472 18.8400000000 0.9579806924 0.1109382670 1.0149564743 0.0121044449 0.0025970000 15431229 955859216 1373700096 0.5998081565 1.0180863142 2.8465490341 473 18.8800000000 1.1962279081 0.1132327483 1.1962279081 0.0138425469 0.0028250000 15433205 955859216 1373700096 0.5842416286 1.2655215263 2.8781938553 474 18.9200000000 1.2522021532 0.1156356373 1.2522021532 0.0142787485 0.0027890000 15435181 955859216 1373700096 0.5608919859 1.2896456718 2.9435045719 475 18.9600000000 1.3630841970 0.1182618448 1.3630841970 0.0153663446 0.0027480000 15437157 955859216 1373700096 0.5668620467 1.3510797024 3.0568325520 476 19.0000000000 1.4588927031 0.1210782962 1.4588927031 0.0167314402 0.0030830000 15439133 955859216 1373700096 0.3324352801 1.3865727186 3.1149072647 477 19.0400000000 1.5209562778 0.1240130509 1.5209562778 0.0171191391 0.0030320000 15441109 955859216 1373700096 0.1959567666 1.3989616632 3.1335024834 478 19.0800000000 1.6315032244 0.1271667960 1.6315032244 0.0180332199 0.0030910000 15443085 955859216 1373700096 -0.0258888025 1.4142100811 3.1588213444 479 19.1200000000 1.7090252638 0.1304692145 1.7090252638 0.0183808303 0.0031730000 15445061 955859216 1373700096 -0.1391391307 1.4253585339 3.1828062534 480 19.1600000000 1.8337495327 0.1340177152 1.8337495327 0.0192380911 0.0033130000 15447037 955859216 1373700096 -0.3214946091 1.4399217367 3.2122092247 481 19.2000000000 1.8549147844 0.1375954638 1.8549147844 0.0192363401 0.0032180000 15449013 955859216 1373700096 -0.3195201755 1.4513845444 3.2306981087 482 19.2400000000 1.8964886665 0.1412446198 1.8964886665 0.0192995438 0.0031720000 15450989 955859216 1373700096 -0.3805162609 1.4546427727 3.2302415371 483 19.2800000000 1.9126597643 0.1449121460 1.9126597643 0.0192835163 0.0031750000 15452965 955859216 1373700096 -0.3961279988 1.4541012049 3.2310559750 484 19.3200000000 1.9340153933 0.1486086403 1.9340153933 0.0192784768 0.0031190000 15454941 955859216 1373700096 -0.4196545780 1.4547219276 3.2348868847 485 19.3600000000 1.9121507406 0.1522448096 1.9340153933 0.0193405804 0.0032710000 15456917 955859216 1373700096 -0.3519049287 1.4651527405 3.2460167408 486 19.4000000000 1.9119195938 0.1558655396 1.9340153933 0.0193287271 0.0035000000 15458893 955859216 1373700096 -0.3437618911 1.4663656950 3.2445318699 487 19.4400000000 1.9027867317 0.1594526467 1.9340153933 0.0193217886 0.0034480000 15460869 955859216 1373700096 -0.3220062554 1.4617494345 3.2431817055 488 19.4800000000 1.9090390205 0.1630378647 1.9340153933 0.0193155402 0.0032870000 15462845 955859216 1373700096 -0.3240462542 1.4603755474 3.2450799942 489 19.5200000000 2.0248596668 0.1668452713 2.0248596668 0.0199210378 0.0033850000 15464821 955859216 1373700096 -0.5280802846 1.4600572586 3.2198042870 490 19.5600000000 2.0168821812 0.1706208568 2.0248596668 0.0199150386 0.0040530000 15466797 955859216 1373700096 -0.5526763201 1.4360673428 3.1840410233 491 19.6000000000 2.0134849548 0.1743741442 2.0248596668 0.0199113572 0.0034880000 15468773 955859216 1373700096 -0.5751386285 1.4195955992 3.1504623890 492 19.6400000000 2.0049886703 0.1780949054 2.0248596668 0.0198997574 0.0035830000 15470749 955859216 1373700096 -0.5773088932 1.4100058079 3.1290965080 493 19.6800000000 1.9985203743 0.1817874520 2.0248596668 0.0198823933 0.0035320000 15472725 955859216 1373700096 -0.5925936103 1.3926507235 3.0981111526 494 19.7200000000 2.0002408028 0.1854685317 2.0248596668 0.0198631968 0.0034920000 15474701 955859216 1373700096 -0.6068345904 1.3799661398 3.0804128647 495 19.7600000000 1.9941679239 0.1891224698 2.0248596668 0.0198519968 0.0033700000 15476677 955859216 1373700096 -0.6019517779 1.3719440699 3.0706143379 496 19.8000000000 1.9914481640 0.1927561910 2.0248596668 0.0198387663 0.0033590000 15478653 955859216 1373700096 -0.6030777097 1.3688971996 3.0613555908 497 19.8400000000 1.9915742874 0.1963755433 2.0248596668 0.0198198482 0.0033970000 15480629 955859216 1373700096 -0.6094070077 1.3588123322 3.0493962765 498 19.8800000000 2.1330335140 0.2002644147 2.1330335140 0.0206985778 0.0034240000 15482605 955859216 1373700096 -0.8276198506 1.3520432711 3.0069284439 499 19.9200000000 2.1707541943 0.2042132920 2.1707541943 0.0207532794 0.0034800000 15484581 955859216 1373700096 -0.8959381580 1.3315347433 2.9879066944 500 19.9600000000 2.2134447098 0.2082317549 2.2134447098 0.0208089059 0.0035440000 15486557 955859216 1373700096 -0.9670666456 1.3151649237 2.9639742374 501 20.0000000000 2.2458865643 0.2122989301 2.2458865643 0.0208336332 0.0036280000 15488533 955859216 1373700096 -1.0235611200 1.2968053818 2.9393293858 502 20.0400000000 2.2670719624 0.2163921035 2.2670719624 0.0208332089 0.0036720000 15490509 955859216 1373700096 -1.0647414923 1.2781678438 2.9122445583 503 20.0800000000 2.2644004822 0.2204636907 2.2670719624 0.0208238031 0.0037400000 15492485 955859216 1373700096 -1.0642675161 1.2710818052 2.8982951641 504 20.1200000000 2.2612931728 0.2245129556 2.2670719624 0.0208049201 0.0036870000 15494461 955859216 1373700096 -1.0629286766 1.2637951374 2.8905324936 505 20.1600000000 2.2570624352 0.2285378060 2.2670719624 0.0207956325 0.0036970000 15496437 955859216 1373700096 -1.0634458065 1.2574836016 2.8797984123 506 20.2000000000 2.2413868904 0.2325157687 2.2670719624 0.0208184316 0.0037230000 15498413 955859216 1373700096 -1.0441309214 1.2584965229 2.8737587929 507 20.2400000000 2.2563135624 0.2365074803 2.2670719624 0.0209462644 0.0039140000 15500389 955859216 1373700096 -1.0178207159 1.3556491137 2.8159675598 508 20.2800000000 2.2049612999 0.2403823894 2.2670719624 0.0209531783 0.0039680000 15502365 955859216 1373700096 -1.0113735199 1.2482361794 2.8535101414 509 20.3200000000 2.1807947159 0.2441945943 2.2670719624 0.0209671186 0.0038850000 15504341 955859216 1373700096 -0.9788693786 1.2417967319 2.8491373062 510 20.3600000000 2.1679215431 0.2479666080 2.2670719624 0.0209686830 0.0037960000 15506317 955859216 1373700096 -0.9584946632 1.2380883694 2.8411798477 511 20.4000000000 2.1661462784 0.2517203842 2.2670719624 0.0209518258 0.0039430000 15508293 955859216 1373700096 -0.9557216167 1.2364425659 2.8317651749 512 20.4400000000 2.1426019669 0.2554135123 2.2670719624 0.0209594929 0.0037640000 15510269 955859216 1373700096 -0.9318084717 1.2329642773 2.8192956448 513 20.4800000000 2.1391916275 0.2590855944 2.2670719624 0.0209422632 0.0037050000 15561397 955859216 1373700096 -0.9232899547 1.2269179821 2.8130013943 514 20.5200000000 2.1400060654 0.2627449728 2.2670719624 0.0209250587 0.0035700000 15665773 955859216 1373700096 -0.9189388156 1.2281557322 2.8109741211 515 20.5600000000 2.1360535622 0.2663824652 2.2670719624 0.0209094026 0.0036960000 15667749 955859216 1373700096 -0.9051411152 1.2317230701 2.8045020103 516 20.6000000000 2.1335918903 0.2700010881 2.2670719624 0.0208915137 0.0038660000 15669725 955859216 1373700096 -0.8935865164 1.2360906601 2.7956244946 517 20.6400000000 2.1308238506 0.2736003584 2.2670719624 0.0208757742 0.0035660000 15671701 955859216 1373700096 -0.8982043266 1.2270847559 2.7976269722 518 20.6800000000 2.1296110153 0.2771833906 2.2670719624 0.0208616600 0.0036540000 15673677 955859216 1373700096 -0.8767116070 1.2231850624 2.7955501080 519 20.7200000000 2.1254277229 0.2807445550 2.2670719624 0.0208569937 0.0034930000 15675653 955859216 1373700096 -0.8854688406 1.2244961262 2.7902727127 520 20.7600000000 2.1215033531 0.2842844758 2.2670719624 0.0208444904 0.0034990000 15677629 955859216 1373700096 -0.8890578151 1.2296175957 2.7821559906 521 20.8000000000 2.1176002026 0.2878033159 2.2670719624 0.0208254223 0.0033800000 15679605 955859216 1373700096 -0.8868175149 1.2248408794 2.7777493000 522 20.8400000000 2.1150228977 0.2913037366 2.2670719624 0.0208068794 0.0034610000 15681581 955859216 1373700096 -0.8821949959 1.2150056362 2.7787446976 523 20.8800000000 2.1094522476 0.2947801200 2.2670719624 0.0207993880 0.0034250000 15683557 955859216 1373700096 -0.8911765814 1.2115639448 2.7751317024 524 20.9200000000 2.1035895348 0.2982320463 2.2670719624 0.0207984699 0.0035020000 15685533 955859216 1373700096 -0.8609900475 1.2089452744 2.7706866264 525 20.9600000000 2.0922820568 0.3016492844 2.2670719624 0.0207939573 0.0034470000 15687509 955859216 1373700096 -0.8493041396 1.2045338154 2.7656464577 526 21.0000000000 2.0942697525 0.3050573081 2.2670719624 0.0207795529 0.0034120000 15689485 955859216 1373700096 -0.8376470208 1.2010585070 2.7662212849 527 21.0400000000 2.0990993977 0.3084615626 2.2670719624 0.0207732549 0.0034730000 15691461 955859216 1373700096 -0.8387789726 1.2017644644 2.7651698589 528 21.0800000000 2.0981047153 0.3118510383 2.2670719624 0.0207626177 0.0033240000 15693437 955859216 1373700096 -0.8331214190 1.2007137537 2.7643520832 529 21.1200000000 2.0951719284 0.3152221552 2.2670719624 0.0207559325 0.0033210000 15695413 955859216 1373700096 -0.8090511560 1.1965775490 2.7613425255 530 21.1600000000 2.0914893150 0.3185736027 2.2670719624 0.0207519401 0.0034190000 15697389 955859216 1373700096 -0.8097510338 1.1949924231 2.7579276562 531 21.2000000000 2.0882930756 0.3219064078 2.2670719624 0.0207430232 0.0032850000 15699365 955859216 1373700096 -0.7930138707 1.1914703846 2.7546589375 532 21.2400000000 2.0844354630 0.3252194323 2.2670719624 0.0207347963 0.0033680000 15701341 955859216 1373700096 -0.7868317962 1.1881288290 2.7505998611 533 21.2800000000 2.0807428360 0.3285130972 2.2670719624 0.0207224360 0.0033180000 15703317 955859216 1373700096 -0.7840271592 1.1851223707 2.7469954491 534 21.3200000000 2.0774197578 0.3317882033 2.2670719624 0.0207153771 0.0032350000 15705293 955859216 1373700096 -0.7677285075 1.1813575029 2.7432706356 535 21.3600000000 2.0720167160 0.3350409669 2.2670719624 0.0207099667 0.0032310000 15707269 955859216 1373700096 -0.7529028058 1.1801840067 2.7369096279 536 21.4000000000 2.0683407784 0.3382747352 2.2670719624 0.0206957666 0.0033700000 15709245 955859216 1373700096 -0.7516863942 1.1773221493 2.7333459854 537 21.4400000000 2.0644683838 0.3414892485 2.2670719624 0.0206838907 0.0034540000 15711221 955859216 1373700096 -0.7338121533 1.1730564833 2.7287924290 538 21.4800000000 2.0598571301 0.3446832409 2.2670719624 0.0206726316 0.0032270000 15713197 955859216 1373700096 -0.7276714444 1.1700680256 2.7239098549 539 21.5200000000 2.0543725491 0.3478552062 2.2670719624 0.0206609820 0.0032150000 15715173 955859216 1373700096 -0.7232314944 1.1664974689 2.7181479931 540 21.5600000000 2.0481343269 0.3510038712 2.2670719624 0.0206516284 0.0031750000 15717149 955859216 1373700096 -0.7107656598 1.1637297869 2.7107787132 541 21.6000000000 2.0430479050 0.3541314942 2.2670719624 0.0206368341 0.0032000000 15719125 955859216 1373700096 -0.7032602429 1.1625535488 2.7048037052 542 21.6400000000 2.0381162167 0.3572384771 2.2670719624 0.0206187537 0.0031280000 15721101 955859216 1373700096 -0.6921154261 1.1571774483 2.6993756294 543 21.6800000000 2.0367326736 0.3603314682 2.2670719624 0.0206040239 0.0030670000 15723077 955859216 1373700096 -0.6876356602 1.1537020206 2.6979475021 544 21.7200000000 2.0314629078 0.3634034010 2.2670719624 0.0205960683 0.0030210000 15725053 955859216 1373700096 -0.6799424291 1.1512541771 2.6918351650 545 21.7600000000 2.0272600651 0.3664563490 2.2670719624 0.0205848593 0.0030390000 15727029 955859216 1373700096 -0.6695942283 1.1468384266 2.6870787144 546 21.8000000000 2.0245032310 0.3694930649 2.2670719624 0.0205766725 0.0030510000 15729005 955859216 1373700096 -0.6639404893 1.1458827257 2.6836051941 547 21.8400000000 2.0190672874 0.3725087399 2.2670719624 0.0205670360 0.0029900000 15730981 955859216 1373700096 -0.6538323164 1.1437611580 2.6771278381 548 21.8800000000 2.0151178837 0.3755062019 2.2670719624 0.0205517103 0.0029930000 15732957 955859216 1373700096 -0.6534568667 1.1418122053 2.6729021072 549 21.9200000000 2.0125684738 0.3784881004 2.2670719624 0.0205371645 0.0029790000 15734933 955859216 1373700096 -0.6480357051 1.1391800642 2.6700799465 550 21.9600000000 2.0080220699 0.3814508894 2.2670719624 0.0205246183 0.0029510000 15736909 955859216 1373700096 -0.6435391307 1.1387343407 2.6646919250 551 22.0000000000 2.0041255951 0.3843958526 2.2670719624 0.0205077732 0.0030410000 15738885 955859216 1373700096 -0.6375012398 1.1362591982 2.6601388454 552 22.0400000000 2.0016615391 0.3873256817 2.2670719624 0.0204928141 0.0029330000 15740861 955859216 1373700096 -0.6295096874 1.1358126402 2.6566436291 553 22.0800000000 1.9995291233 0.3902410586 2.2670719624 0.0204774214 0.0029410000 15742837 955859216 1373700096 -0.6286422610 1.1345349550 2.6542587280 554 22.1200000000 1.9967575073 0.3931409078 2.2670719624 0.0204625918 0.0028810000 15744813 955859216 1373700096 -0.6231359243 1.1309908628 2.6511213779 555 22.1600000000 1.9922015667 0.3960220982 2.2670719624 0.0204538237 0.0029190000 15746789 955859216 1373700096 -0.6171185374 1.1309407949 2.6453781128 556 22.2000000000 1.9870107174 0.3988835885 2.2670719624 0.0204381056 0.0029220000 15748765 955859216 1373700096 -0.6108890176 1.1304156780 2.6388659477 557 22.2400000000 1.9852271080 0.4017316020 2.2670719624 0.0204206401 0.0028630000 15750741 955859216 1373700096 -0.6085277796 1.1264185905 2.6372349262 558 22.2800000000 1.9817258120 0.4045631329 2.2670719624 0.0204057381 0.0028280000 15752717 955859216 1373700096 -0.6055953503 1.1217101812 2.6335148811 559 22.3200000000 1.9778958559 0.4073776816 2.2670719624 0.0204007745 0.0027950000 15754693 955859216 1373700096 -0.6021951437 1.1220606565 2.6287384033 560 22.3600000000 1.9754469395 0.4101778052 2.2670719624 0.0203882927 0.0028580000 15756669 955859216 1373700096 -0.6008032560 1.1206680536 2.6259214878 561 22.4000000000 1.9737819433 0.4129649784 2.2670719624 0.0203748071 0.0027890000 15758645 955859216 1373700096 -0.5928580165 1.1182032824 2.6234259605 562 22.4400000000 1.9711811543 0.4157376050 2.2670719624 0.0203637553 0.0027620000 15760621 955859216 1373700096 -0.5918659568 1.1179808378 2.6201095581 563 22.4800000000 1.9679225683 0.4184945943 2.2670719624 0.0203486360 0.0028050000 15762597 955859216 1373700096 -0.5840747356 1.1155608892 2.6157455444 564 22.5200000000 1.9660032988 0.4212384041 2.2670719624 0.0203329745 0.0027730000 15764573 955859216 1373700096 -0.5798240900 1.1119825840 2.6134409904 565 22.5600000000 1.9632780552 0.4239676778 2.2670719624 0.0203223415 0.0027560000 15766549 955859216 1373700096 -0.5693258643 1.1068775654 2.6098566055 566 22.6000000000 1.9601113796 0.4266817126 2.2670719624 0.0203199515 0.0028530000 15768525 955859216 1373700096 -0.5634319186 1.1037659645 2.6067318916 567 22.6400000000 1.9581714869 0.4293827528 2.2670719624 0.0203139624 0.0027970000 15770501 955859216 1373700096 -0.5580505133 1.1015993357 2.6040296555 568 22.6800000000 1.9560220242 0.4320704980 2.2670719624 0.0203042129 0.0027860000 15772477 955859216 1373700096 -0.5500627160 1.0975631475 2.6011116505 569 22.7200000000 1.9526976347 0.4347429534 2.2670719624 0.0202969588 0.0027660000 15774453 955859216 1373700096 -0.5410470963 1.0932661295 2.5968241692 570 22.7600000000 1.9463075399 0.4373948211 2.2670719624 0.0202936078 0.0027340000 15776429 955859216 1373700096 -0.5346981883 1.0916728973 2.5890517235 571 22.8000000000 1.9409238100 0.4400279717 2.2670719624 0.0202790187 0.0027390000 15778405 955859216 1373700096 -0.5293707848 1.0896866322 2.5824177265 572 22.8400000000 1.9380702972 0.4426469268 2.2670719624 0.0202624696 0.0027260000 15780381 955859216 1373700096 -0.5232861042 1.0832054615 2.5790920258 573 22.8800000000 1.9334422350 0.4452486638 2.2670719624 0.0202546898 0.0027210000 15782357 955859216 1373700096 -0.5169439316 1.0793610811 2.5733587742 574 22.9200000000 1.9277919531 0.4478314918 2.2670719624 0.0202423993 0.0027080000 15784333 955859216 1373700096 -0.5137130022 1.0774555206 2.5667514801 575 22.9600000000 1.9232556820 0.4503974470 2.2670719624 0.0202264359 0.0026920000 15786309 955859216 1373700096 -0.5076172948 1.0710796118 2.5615584850 576 23.0000000000 1.9202512503 0.4529492765 2.2670719624 0.0202134078 0.0027020000 15788285 955859216 1373700096 -0.5029945374 1.0651415586 2.5582885742 577 23.0400000000 1.9143141508 0.4554819712 2.2670719624 0.0202084360 0.0026880000 15790261 955859216 1373700096 -0.4971676767 1.0631759167 2.5507423878 578 23.0800000000 1.9094389677 0.4579974678 2.2670719624 0.0201947294 0.0027220000 15792237 955859216 1373700096 -0.4909262657 1.0590204000 2.5447566509 579 23.1200000000 1.9057273865 0.4604978649 2.2670719624 0.0201808044 0.0027750000 15794213 955859216 1373700096 -0.4847398698 1.0535843372 2.5400438309 580 23.1600000000 1.9009679556 0.4629814340 2.2670719624 0.0201683368 0.0026870000 15796189 955859216 1373700096 -0.4777354896 1.0489852428 2.5339932442 581 23.2000000000 1.8955777884 0.4654471764 2.2670719624 0.0201543814 0.0027750000 15798165 955859216 1373700096 -0.4720045626 1.0456786156 2.5271940231 582 23.2400000000 1.8902754784 0.4678953350 2.2670719624 0.0201392347 0.0027290000 15800141 955859216 1373700096 -0.4649984241 1.0396540165 2.5206100941 583 23.2800000000 1.8869929314 0.4703294647 2.2670719624 0.0201246043 0.0026980000 15802117 955859216 1373700096 -0.4584663212 1.0337356329 2.5162625313 584 23.3200000000 1.8803584576 0.4727438979 2.2670719624 0.0201191488 0.0027000000 15804093 955859216 1373700096 -0.4516313076 1.0295222998 2.5080163479 585 23.3600000000 1.8747164011 0.4751404321 2.2670719624 0.0201087733 0.0027030000 15806069 955859216 1373700096 -0.4444247782 1.0247722864 2.5006375313 586 23.4000000000 1.8706513643 0.4775218501 2.2670719624 0.0200979870 0.0027010000 15808045 955859216 1373700096 -0.4368087053 1.0180999041 2.4952065945 587 23.4400000000 1.8656979799 0.4798867157 2.2670719624 0.0200973738 0.0026970000 15810021 955859216 1373700096 -0.4308201969 1.0139054060 2.4887793064 588 23.4800000000 1.8513470888 0.4822191313 2.2670719624 0.0201408303 0.0027920000 15811997 955859216 1373700096 -0.4129199982 1.0060882568 2.4693822861 589 23.5200000000 1.8454535007 0.4845336209 2.2670719624 0.0201302857 0.0027600000 15813973 955859216 1373700096 -0.4071768820 1.0036008358 2.4615483284 590 23.5600000000 1.8383444548 0.4868282155 2.2670719624 0.0201168048 0.0027440000 15815949 955859216 1373700096 -0.4004448056 1.0003992319 2.4523489475 591 23.6000000000 1.8336033821 0.4891070229 2.2670719624 0.0201009681 0.0027730000 15817925 955859216 1373700096 -0.3931778967 0.9942603707 2.4457998276 592 23.6400000000 1.8278577328 0.4913684261 2.2670719624 0.0200877693 0.0028130000 15819901 955859216 1373700096 -0.3840333521 0.9872137904 2.4377725124 593 23.6800000000 1.8214857578 0.4936114570 2.2670719624 0.0200801011 0.0027520000 15821877 955859216 1373700096 -0.3763295710 0.9824897647 2.4290735722 594 23.7200000000 1.8156422377 0.4958370981 2.2670719624 0.0200716274 0.0027700000 15823853 955859216 1373700096 -0.3688010871 0.9780022502 2.4209442139 595 23.7600000000 1.8104125261 0.4980464686 2.2670719624 0.0200621056 0.0027870000 15825829 955859216 1373700096 -0.3640278578 0.9732936025 2.4141712189 596 23.8000000000 1.8035011292 0.5002368287 2.2670719624 0.0200563946 0.0027840000 15827805 955859216 1373700096 -0.3559124470 0.9697954655 2.4044585228 597 23.8400000000 1.7967467308 0.5024085371 2.2670719624 0.0200457149 0.0028220000 15829781 955859216 1373700096 -0.3502445221 0.9669030309 2.3955557346 598 23.8800000000 1.7902514935 0.5045621206 2.2670719624 0.0200329568 0.0028650000 15831757 955859216 1373700096 -0.3416037560 0.9617674947 2.3862569332 599 23.9200000000 1.7833291292 0.5066969571 2.2670719624 0.0200203567 0.0028930000 15833733 955859216 1373700096 -0.3363457620 0.9592289925 2.3771653175 600 23.9600000000 1.7775020599 0.5088149656 2.2670719624 0.0200059296 0.0029030000 15835709 955859216 1373700096 -0.3296322227 0.9552025795 2.3688015938 601 24.0000000000 1.7712711096 0.5109155581 2.2670719624 0.0199925968 0.0029130000 15837685 955859216 1373700096 -0.3242695332 0.9506964684 2.3606660366 602 24.0400000000 1.7650867701 0.5129988990 2.2670719624 0.0199807987 0.0029180000 15839661 955859216 1373700096 -0.3165759742 0.9460822344 2.3516418934 603 24.0800000000 1.7590931654 0.5150653903 2.2670719624 0.0199680941 0.0028860000 15841637 955859216 1373700096 -0.3124807477 0.9423138499 2.3438467979 604 24.1200000000 1.7533718348 0.5171155666 2.2670719624 0.0199547771 0.0029300000 15843613 955859216 1373700096 -0.3088417351 0.9390811920 2.3364298344 605 24.1600000000 1.7484350204 0.5191508053 2.2670719624 0.0199408507 0.0029330000 15845589 955859216 1373700096 -0.3045992553 0.9345518947 2.3297221661 606 24.2000000000 1.7446902990 0.5211731477 2.2670719624 0.0199260871 0.0029300000 15847565 955859216 1373700096 -0.3008030653 0.9289709330 2.3246593475 607 24.2400000000 1.7386705875 0.5231789096 2.2670719624 0.0199140375 0.0029350000 15849541 955859216 1373700096 -0.2931112647 0.9235150218 2.3157880306 608 24.2800000000 1.7327377796 0.5251683156 2.2670719624 0.0199011608 0.0029230000 15851517 955859216 1373700096 -0.2889535129 0.9210246801 2.3078098297 609 24.3200000000 1.7293034792 0.5271455491 2.2670719624 0.0198866213 0.0029210000 15853493 955859216 1373700096 -0.2835978568 0.9150612950 2.3025107384 610 24.3600000000 1.7262586355 0.5291113082 2.2670719624 0.0198728058 0.0029940000 15855469 955859216 1373700096 -0.2791081965 0.9081198573 2.2980413437 611 24.4000000000 1.7208614349 0.5310617994 2.2670719624 0.0198637799 0.0030500000 15857445 955859216 1373700096 -0.2702962458 0.9025492072 2.2892580032 612 24.4400000000 1.7153989077 0.5329969908 2.2670719624 0.0198536229 0.0030480000 15859421 955859216 1373700096 -0.2657184899 0.8991238475 2.2815485001 613 24.4800000000 1.7119626999 0.5349202627 2.2670719624 0.0198388348 0.0029990000 15861397 955859216 1373700096 -0.2618534863 0.8940369487 2.2766294479 614 24.5200000000 1.7070618868 0.5368292882 2.2670719624 0.0198259313 0.0030040000 15863373 955859216 1373700096 -0.2538115680 0.8870775104 2.2686190605 615 24.5600000000 1.7037634850 0.5387267422 2.2670719624 0.0198128224 0.0029980000 15865349 955859216 1373700096 -0.2487244755 0.8826554418 2.2632632256 616 24.6000000000 1.7000818253 0.5406120589 2.2670719624 0.0197998080 0.0030100000 15867325 955859216 1373700096 -0.2418672740 0.8760318756 2.2569341660 617 24.6400000000 1.6957226992 0.5424841993 2.2670719624 0.0197903994 0.0030970000 15869301 955859216 1373700096 -0.2354204655 0.8704701066 2.2498373985 618 24.6800000000 1.6914944649 0.5443434392 2.2670719624 0.0197817538 0.0030580000 15871277 955859216 1373700096 -0.2269571871 0.8642288446 2.2421586514 619 24.7200000000 1.6861886978 0.5461881003 2.2670719624 0.0197757767 0.0030700000 15873253 955859216 1373700096 -0.2167921066 0.8581075668 2.2325320244 620 24.7600000000 1.6808973551 0.5480182766 2.2670719624 0.0197712992 0.0031930000 15875229 955859216 1373700096 -0.2123229206 0.8548713326 2.2248699665 621 24.8000000000 1.6767723560 0.5498359160 2.2670719624 0.0197600462 0.0031040000 15877205 955859216 1373700096 -0.2061033249 0.8504358530 2.2178106308 622 24.8400000000 1.6728291512 0.5516413713 2.2670719624 0.0197480954 0.0031230000 15879181 955859216 1373700096 -0.1997105628 0.8445532918 2.2109079361 623 24.8800000000 1.6677033901 0.5534328032 2.2670719624 0.0197406279 0.0032230000 15881157 955859216 1373700096 -0.1935846359 0.8408047557 2.2026340961 624 24.9200000000 1.6619105339 0.5552092098 2.2670719624 0.0197308669 0.0032280000 15883133 955859216 1373700096 -0.1876119822 0.8368690610 2.1936123371 625 24.9600000000 1.6575671434 0.5569729825 2.2670719624 0.0197193014 0.0031440000 15885109 955859216 1373700096 -0.1824160516 0.8311824203 2.1865644455 626 25.0000000000 1.6543136835 0.5587259229 2.2670719624 0.0197084080 0.0034250000 15887085 955859216 1373700096 -0.1770575941 0.8256196380 2.1806077957 627 25.0400000000 1.6494880915 0.5604655755 2.2670719624 0.0197035373 0.0031860000 15889061 955859216 1373700096 -0.1717693359 0.8212267160 2.1727757454 628 25.0800000000 1.6432181597 0.5621897038 2.2670719624 0.0196990617 0.0033360000 15891037 955859216 1373700096 -0.1673874557 0.8183690906 2.1636278629 629 25.1200000000 1.6397306919 0.5639028055 2.2670719624 0.0196876849 0.0031910000 15893013 955859216 1373700096 -0.1646015346 0.8147811294 2.1583995819 630 25.1600000000 1.6342445612 0.5656017607 2.2670719624 0.0196796523 0.0032000000 15894989 955859216 1373700096 -0.1604294032 0.8101777434 2.1502072811 631 25.2000000000 1.6284718513 0.5672861824 2.2670719624 0.0196718283 0.0031920000 15896965 955859216 1373700096 -0.1569775492 0.8069846630 2.1419334412 632 25.2400000000 1.6244741678 0.5689589482 2.2670719624 0.0196601116 0.0031780000 15898941 955859216 1373700096 -0.1553961486 0.8027948737 2.1365180016 633 25.2800000000 1.6181035042 0.5706163645 2.2670719624 0.0196521548 0.0031590000 15900917 955859216 1373700096 -0.1504395008 0.7987737656 2.1269998550 634 25.3200000000 1.6114920378 0.5722581243 2.2670719624 0.0196419634 0.0031370000 15902893 955859216 1373700096 -0.1483497173 0.7958974838 2.1181368828 635 25.3600000000 1.6070647240 0.5738877410 2.2670719624 0.0196286199 0.0031600000 15904869 955859216 1373700096 -0.1472048163 0.7927713394 2.1122088432 636 25.4000000000 1.6027173996 0.5755053977 2.2670719624 0.0196167987 0.0031140000 15906845 955859216 1373700096 -0.1429875940 0.7871201634 2.1051948071 637 25.4400000000 1.5974292755 0.5771096738 2.2670719624 0.0196069103 0.0031140000 15908821 955859216 1373700096 -0.1410286576 0.7836958170 2.0978577137 638 25.4800000000 1.5935680866 0.5787028688 2.2670719624 0.0195964696 0.0031010000 15910797 955859216 1373700096 -0.1376311183 0.7786080837 2.0916016102 639 25.5200000000 1.5890352726 0.5802839837 2.2670719624 0.0195873259 0.0030900000 15912773 955859216 1373700096 -0.1370878369 0.7732539177 2.0857434273 640 25.5600000000 1.5850130320 0.5818538728 2.2670719624 0.0195773814 0.0030840000 15914749 955859216 1373700096 -0.1357797384 0.7689510584 2.0800981522 641 25.6000000000 1.5799386501 0.5834109473 2.2670719624 0.0195671917 0.0030910000 15916725 955859216 1373700096 -0.1345463395 0.7641809583 2.0733346939 642 25.6400000000 1.5750843287 0.5849556099 2.2670719624 0.0195561985 0.0030710000 15918701 955859216 1373700096 -0.1347406507 0.7597620487 2.0674071312 643 25.6800000000 1.5705755949 0.5864884559 2.2670719624 0.0195447937 0.0030630000 15920677 955859216 1373700096 -0.1332063377 0.7545396686 2.0611429214 644 25.7200000000 1.5654888153 0.5880086428 2.2670719624 0.0195330069 0.0030580000 15922653 955859216 1373700096 -0.1336514652 0.7502268553 2.0549612045 645 25.7600000000 1.5611820221 0.5895174388 2.2670719624 0.0195203297 0.0030780000 15924629 955859216 1373700096 -0.1327306479 0.7449498177 2.0489022732 646 25.8000000000 1.5558310747 0.5910132803 2.2670719624 0.0195082343 0.0030910000 15926605 955859216 1373700096 -0.1343507767 0.7400308251 2.0431649685 647 25.8400000000 1.5487859249 0.5924936090 2.2670719624 0.0194978575 0.0030510000 15928581 955859216 1373700096 -0.1353459507 0.7363424897 2.0347211361 648 25.8800000000 1.5429725647 0.5939603975 2.2670719624 0.0194846857 0.0031690000 15930557 955859216 1373700096 -0.1369376928 0.7320662737 2.0281419754 649 25.9200000000 1.5374149084 0.5954141024 2.2670719624 0.0194713971 0.0031690000 15932533 955859216 1373700096 -0.1384640932 0.7257965803 2.0218341351 650 25.9600000000 1.5275194645 0.5968481107 2.2670719624 0.0194731649 0.0031310000 15934509 955859216 1373700096 -0.1419752687 0.7121831775 2.0106911659 651 26.0000000000 1.5117508173 0.5982534912 2.2670719624 0.0195006942 0.0031330000 15936485 955859216 1373700096 -0.1466964781 0.7032002807 1.9932355881 652 26.0400000000 1.5032826662 0.5996415727 2.2670719624 0.0194944328 0.0031400000 15938461 955859216 1373700096 -0.1493423581 0.6991232038 1.9835602045 653 26.0800000000 1.4928994179 0.6010095020 2.2670719624 0.0194864901 0.0031110000 15940437 955859216 1373700096 -0.1530938298 0.6970031261 1.9727324247 654 26.1200000000 1.4843665361 0.6023602009 2.2670719624 0.0194755721 0.0031100000 15942413 955859216 1373700096 -0.1577817351 0.6923127770 1.9641432762 655 26.1600000000 1.4764431715 0.6036946787 2.2670719624 0.0194661001 0.0030860000 15944389 955859216 1373700096 -0.1600092947 0.6852279902 1.9554070234 656 26.2000000000 1.4669364691 0.6050105961 2.2670719624 0.0194617553 0.0030740000 15946365 955859216 1373700096 -0.1644236147 0.6808347702 1.9456204176 657 26.2400000000 1.4582145214 0.6063092322 2.2670719624 0.0194572193 0.0030690000 15948341 955859216 1373700096 -0.1694175750 0.6765652895 1.9367001057 658 26.2800000000 1.4480417967 0.6075884610 2.2670719624 0.0194544218 0.0030510000 15950317 955859216 1373700096 -0.1738833487 0.6726672053 1.9260358810 659 26.3200000000 1.4370113611 0.6088470693 2.2670719624 0.0194505622 0.0030370000 15952293 955859216 1373700096 -0.1795869470 0.6701276302 1.9151929617 660 26.3600000000 1.4274281263 0.6100873437 2.2670719624 0.0194434211 0.0030400000 15954269 955859216 1373700096 -0.1844686419 0.6664396524 1.9055091143 661 26.4000000000 1.4162038565 0.6113068845 2.2670719624 0.0194367546 0.0030860000 15956245 955859216 1373700096 -0.1898945868 0.6633475423 1.8941864967 662 26.4400000000 1.4053428173 0.6125063346 2.2670719624 0.0194282947 0.0030420000 15958221 955859216 1373700096 -0.1969546527 0.6619355679 1.8840999603 663 26.4800000000 1.3966472149 0.6136890508 2.2670719624 0.0194236165 0.0030350000 15960197 955859216 1373700096 -0.2019395381 0.6569777727 1.8753689528 664 26.5200000000 1.3887497187 0.6148563109 2.2670719624 0.0194172709 0.0030250000 15962173 955859216 1373700096 -0.2048875391 0.6491304636 1.8666925430 665 26.5600000000 1.3797705173 0.6160065578 2.2670719624 0.0194088357 0.0030080000 15964149 955859216 1373700096 -0.2101106793 0.6452721953 1.8578567505 666 26.6000000000 1.3695937395 0.6171380701 2.2670719624 0.0194003441 0.0029900000 15966125 955859216 1373700096 -0.2152164131 0.6423969865 1.8475582600 667 26.6400000000 1.3598024845 0.6182515100 2.2670719624 0.0193898353 0.0029910000 15968101 955859216 1373700096 -0.2214494646 0.6409208179 1.8384786844 668 26.6800000000 1.3488161564 0.6193451696 2.2670719624 0.0193811497 0.0030060000 15970077 955859216 1373700096 -0.2266581804 0.6399918199 1.8274130821 669 26.7200000000 1.3392479420 0.6204212575 2.2670719624 0.0193774960 0.0030000000 15972053 955859216 1373700096 -0.2322118580 0.6366903782 1.8180223703 670 26.7600000000 1.3312124014 0.6214821398 2.2670719624 0.0193718428 0.0030160000 15974029 955859216 1373700096 -0.2366472781 0.6322275996 1.8100916147 671 26.8000000000 1.3230391741 0.6225276793 2.2670719624 0.0193627270 0.0030010000 15976005 955859216 1373700096 -0.2405540794 0.6281688809 1.8015426397 672 26.8400000000 1.3137339354 0.6235562601 2.2670719624 0.0193534420 0.0029730000 15977981 955859216 1373700096 -0.2442146540 0.6259540915 1.7916960716 673 26.8800000000 1.3057686090 0.6245699486 2.2670719624 0.0193446240 0.0029770000 15979957 955859216 1373700096 -0.2476549447 0.6222798228 1.7833740711 674 26.9200000000 1.2977774143 0.6255687727 2.2670719624 0.0193360823 0.0029830000 15981933 955859216 1373700096 -0.2510008216 0.6191267967 1.7748973370 675 26.9600000000 1.2897632122 0.6265527645 2.2670719624 0.0193278420 0.0029630000 15983909 955859216 1373700096 -0.2550305426 0.6170619130 1.7667815685 676 27.0000000000 1.2802350521 0.6275197501 2.2670719624 0.0193202933 0.0029650000 15985885 955859216 1373700096 -0.2587343156 0.6167411804 1.7567702532 677 27.0400000000 1.2717541456 0.6284713519 2.2670719624 0.0193117766 0.0029810000 15987861 955859216 1373700096 -0.2633637786 0.6160836220 1.7485574484 678 27.0800000000 1.2640408278 0.6294087700 2.2670719624 0.0193049403 0.0029790000 15989837 955859216 1373700096 -0.2667145729 0.6140513420 1.7404575348 679 27.1200000000 1.2556647062 0.6303310909 2.2670719624 0.0192988723 0.0029840000 15991813 955859216 1373700096 -0.2700930536 0.6116663814 1.7315083742 680 27.1600000000 1.2487472296 0.6312405264 2.2670719624 0.0192929419 0.0030280000 15993789 955859216 1373700096 -0.2719733715 0.6072394252 1.7236499786 681 27.2000000000 1.2413958311 0.6321364960 2.2670719624 0.0192837315 0.0030220000 15995765 955859216 1373700096 -0.2750474215 0.6046209335 1.7158057690 682 27.2400000000 1.2328073978 0.6330172452 2.2670719624 0.0192755123 0.0030590000 15997741 955859216 1373700096 -0.2777055204 0.6037563682 1.7063714266 683 27.2800000000 1.2246959209 0.6338835390 2.2670719624 0.0192677312 0.0030700000 15999717 955859216 1373700096 -0.2799677849 0.6021742821 1.6972936392 684 27.3200000000 1.2171112299 0.6347362110 2.2670719624 0.0192612374 0.0030800000 16001693 955859216 1373700096 -0.2826798260 0.5990917087 1.6888833046 685 27.3600000000 1.2098737955 0.6355758280 2.2670719624 0.0192539048 0.0029670000 16003669 955859216 1373700096 -0.2840508521 0.5954496264 1.6802378893 686 27.4000000000 1.2008241415 0.6363998051 2.2670719624 0.0192455624 0.0030740000 16005645 955859216 1373700096 -0.2859619260 0.5940346122 1.6697579622 687 27.4400000000 1.1920948029 0.6372086770 2.2670719624 0.0192403127 0.0030520000 16007621 955859216 1373700096 -0.2874608040 0.5926313996 1.6594617367 688 27.4800000000 1.1839450598 0.6380033520 2.2670719624 0.0192409243 0.0030740000 16009597 955859216 1373700096 -0.2891990542 0.5895830393 1.6499674320 689 27.5200000000 1.1759018898 0.6387840465 2.2670719624 0.0192403889 0.0029770000 16011573 955859216 1373700096 -0.2908747196 0.5864769816 1.6404457092 690 27.5600000000 1.1682499647 0.6395513884 2.2670719624 0.0192385030 0.0029940000 16013549 955859216 1373700096 -0.2914826274 0.5830141306 1.6306867599 691 27.6000000000 1.1586534977 0.6403026216 2.2670719624 0.0192355711 0.0029820000 16015525 955859216 1373700096 -0.2930795252 0.5819357038 1.6192570925 692 27.6400000000 1.1493068933 0.6410381769 2.2670719624 0.0192373559 0.0029670000 16017501 955859216 1373700096 -0.2943037152 0.5802210569 1.6080110073 693 27.6800000000 1.1420804262 0.6417611816 2.2670719624 0.0192430889 0.0029730000 16019477 955859216 1373700096 -0.2945436835 0.5757342577 1.5984083414 694 27.7200000000 1.1354166269 0.6424725006 2.2670719624 0.0192416079 0.0029700000 16021453 955859216 1373700096 -0.2937323749 0.5699849129 1.5889419317 695 27.7600000000 1.1293923855 0.6431731048 2.2670719624 0.0192335244 0.0029780000 16023429 955859216 1373700096 -0.2933605909 0.5645674467 1.5803910494 696 27.8000000000 1.1215592623 0.6438604412 2.2670719624 0.0192262748 0.0029690000 16025405 955859216 1373700096 -0.2933078408 0.5617173314 1.5698863268 697 27.8400000000 1.1131337881 0.6445337172 2.2670719624 0.0192199175 0.0029940000 16027381 955859216 1373700096 -0.2937728167 0.5597232580 1.5589751005 698 27.8800000000 1.1034548283 0.6451911973 2.2670719624 0.0192139516 0.0030050000 16029357 955859216 1373700096 -0.2950944304 0.5585667491 1.5471974611 699 27.9200000000 1.0945742130 0.6458340915 2.2670719624 0.0192085007 0.0029910000 16031333 955859216 1373700096 -0.2963150740 0.5573797226 1.5362759829 700 27.9600000000 1.0857692957 0.6464625703 2.2670719624 0.0192068704 0.0029860000 16033309 955859216 1373700096 -0.2973257005 0.5550898910 1.5251572132 701 28.0000000000 1.0778263807 0.6470779253 2.2670719624 0.0192061933 0.0030180000 16035285 955859216 1373700096 -0.2985063791 0.5524505377 1.5151548386 702 28.0400000000 1.0705484152 0.6476811596 2.2670719624 0.0192049092 0.0030270000 16037261 955859216 1373700096 -0.2995342314 0.5488998294 1.5057283640 703 28.0800000000 1.0641419888 0.6482735647 2.2670719624 0.0191981405 0.0030340000 16039237 955859216 1373700096 -0.3010601401 0.5459654331 1.4977935553 704 28.1200000000 1.0543229580 0.6488503394 2.2670719624 0.0191919077 0.0030200000 16041213 955859216 1373700096 -0.3039909601 0.5471878648 1.4866894484 705 28.1600000000 1.0456650257 0.6494131972 2.2670719624 0.0191946916 0.0030710000 16043189 955859216 1373700096 -0.3066792488 0.5468001962 1.4767938852 706 28.2000000000 1.0397324562 0.6499660573 2.2670719624 0.0191982352 0.0030620000 16045165 955859216 1373700096 -0.3087649941 0.5430855751 1.4697004557 707 28.2400000000 1.0318652391 0.6505062259 2.2670719624 0.0191927074 0.0030860000 16047141 955859216 1373700096 -0.3112721145 0.5423300862 1.4607415199 708 28.2800000000 1.0233798027 0.6510328835 2.2670719624 0.0191876275 0.0030700000 16049117 955859216 1373700096 -0.3147644699 0.5425644517 1.4516245127 709 28.3200000000 1.0194658041 0.6515525350 2.2670719624 0.0191823995 0.0030770000 16051093 955859216 1373700096 -0.3169138432 0.5371181369 1.4469648600 710 28.3600000000 1.0134788752 0.6520622904 2.2670719624 0.0191751435 0.0030810000 16053069 955859216 1373700096 -0.3191426396 0.5347854495 1.4400203228 711 28.4000000000 1.0032960176 0.6525562900 2.2670719624 0.0191691870 0.0031660000 16055045 955859216 1373700096 -0.3235855699 0.5384667516 1.4297636747 712 28.4400000000 0.9958941340 0.6530385061 2.2670719624 0.0191636062 0.0032630000 16057021 955859216 1373700096 -0.3272323608 0.5372321010 1.4220737219 713 28.4800000000 0.9935747981 0.6535161166 2.2670719624 0.0191515511 0.0030230000 16058997 955859216 1373700096 -0.3301362395 0.5323704481 1.4200567007 714 28.5200000000 0.9836254120 0.6539784545 2.2670719624 0.0191591338 0.0031400000 16060973 955859216 1373700096 -0.3353174925 0.5360696316 1.4107249975 715 28.5600000000 0.9737612009 0.6544257031 2.2670719624 0.0191512402 0.0031250000 16062949 955859216 1373700096 -0.3409762383 0.5391405225 1.4016811848 716 28.6000000000 0.9680841565 0.6548637736 2.2670719624 0.0191482929 0.0030720000 16064925 955859216 1373700096 -0.3471575975 0.5389273763 1.3981313705 717 28.6400000000 0.9625418186 0.6552928922 2.2670719624 0.0191390914 0.0030000000 16066901 955859216 1373700096 -0.3535595536 0.5391460657 1.3948951960 718 28.6800000000 0.9547396898 0.6557099490 2.2670719624 0.0191293953 0.0030950000 16068877 955859216 1373700096 -0.3605651259 0.5421270728 1.3893656731 719 28.7200000000 0.9474152923 0.6561156588 2.2670719624 0.0191247586 0.0031130000 16070853 955859216 1373700096 -0.3672959805 0.5431491733 1.3840898275 720 28.7600000000 0.9408529997 0.6565111273 2.2670719624 0.0191190246 0.0030700000 16072829 955859216 1373700096 -0.3751004934 0.5440354347 1.3804574013 721 28.8000000000 0.9356991053 0.6568983506 2.2670719624 0.0191098940 0.0029990000 16074805 955859216 1373700096 -0.3832410276 0.5439909101 1.3787314892 722 28.8400000000 0.9286393523 0.6572747232 2.2670719624 0.0191005082 0.0030890000 16076781 955859216 1373700096 -0.3916380405 0.5451620817 1.3748183250 723 28.8800000000 0.9226063490 0.6576417102 2.2670719624 0.0190905024 0.0031030000 16078757 955859216 1373700096 -0.4008332193 0.5455942750 1.3725929260 724 28.9200000000 0.9156460762 0.6579980698 2.2670719624 0.0190813121 0.0030970000 16080733 955859216 1373700096 -0.4103114605 0.5467723608 1.3693636656 725 28.9600000000 0.9083354473 0.6583433628 2.2670719624 0.0190719944 0.0030810000 16082709 955859216 1373700096 -0.4203364551 0.5482364297 1.3660193682 726 29.0000000000 0.9023097754 0.6586794047 2.2670719624 0.0190681966 0.0029890000 16084685 955859216 1373700096 -0.4303221107 0.5485337973 1.3641955853 727 29.0400000000 0.8946534395 0.6590039907 2.2670719624 0.0190633140 0.0030690000 16086661 955859216 1373700096 -0.4408503175 0.5496813059 1.3605003357 728 29.0800000000 0.8878128529 0.6593182886 2.2670719624 0.0190578456 0.0029710000 16088637 955859216 1373700096 -0.4517187178 0.5508409739 1.3581467867 729 29.1200000000 0.8804410696 0.6596216120 2.2670719624 0.0190487674 0.0030810000 16090613 955859216 1373700096 -0.4627218843 0.5529247522 1.3551115990 730 29.1600000000 0.8740606904 0.6599153642 2.2670719624 0.0190396266 0.0030480000 16092589 955859216 1373700096 -0.4735884666 0.5534272790 1.3530789614 731 29.2000000000 0.8665869832 0.6601980887 2.2670719624 0.0190324309 0.0030390000 16094565 955859216 1373700096 -0.4845770597 0.5548409820 1.3497349024 732 29.2400000000 0.8579168320 0.6604681963 2.2670719624 0.0190269920 0.0030580000 16096541 955859216 1373700096 -0.4962008893 0.5575277805 1.3452533484 733 29.2800000000 0.8502821326 0.6607271512 2.2670719624 0.0190223887 0.0030420000 16098517 955859216 1373700096 -0.5086673498 0.5600150824 1.3424118757 734 29.3200000000 0.8431060314 0.6609756237 2.2670719624 0.0190177993 0.0030500000 16100493 955859216 1373700096 -0.5214720368 0.5633161664 1.3402835131 735 29.3600000000 0.8362175226 0.6612140481 2.2670719624 0.0190132227 0.0030450000 16102469 955859216 1373700096 -0.5337133408 0.5663612485 1.3381111622 736 29.4000000000 0.8293733597 0.6614425254 2.2670719624 0.0190094365 0.0030580000 16104445 955859216 1373700096 -0.5460568070 0.5703371167 1.3359718323 737 29.4400000000 0.8232185841 0.6616620316 2.2670719624 0.0190053029 0.0030620000 16106421 955859216 1373700096 -0.5578889847 0.5733961463 1.3342676163 738 29.4800000000 0.8168817163 0.6618723564 2.2670719624 0.0190065507 0.0030680000 16108397 955859216 1373700096 -0.5699171424 0.5766614079 1.3323383331 739 29.5200000000 0.8114711642 0.6620747905 2.2670719624 0.0190175825 0.0030720000 16110373 955859216 1373700096 -0.5815950632 0.5796812177 1.3312371969 740 29.5600000000 0.8068176508 0.6622703889 2.2670719624 0.0190259230 0.0030400000 16112349 955859216 1373700096 -0.5926080942 0.5825726390 1.3306325674 741 29.6000000000 0.8017906547 0.6624586754 2.2670719624 0.0190431454 0.0029580000 16114325 955859216 1373700096 -0.6037337184 0.5868940353 1.3295520544 742 29.6400000000 0.7976568937 0.6626408832 2.2670719624 0.0190606496 0.0029430000 16116301 955859216 1373700096 -0.6144190431 0.5912597179 1.3291585445 743 29.6800000000 0.7955068946 0.6628197070 2.2670719624 0.0190597440 0.0029090000 16118277 955859216 1373700096 -0.6236366034 0.5936654806 1.3303266764 744 29.7200000000 0.7927746773 0.6629943776 2.2670719624 0.0190504103 0.0029030000 16120253 955859216 1373700096 -0.6320903301 0.5961872339 1.3304965496 745 29.7600000000 0.7894517779 0.6631641191 2.2670719624 0.0190406997 0.0029040000 16122229 955859216 1373700096 -0.6402674317 0.5990973711 1.3297680616 746 29.8000000000 0.7867304087 0.6633297575 2.2670719624 0.0190312966 0.0029030000 16124205 955859216 1373700096 -0.6480950713 0.6013510823 1.3295485973 747 29.8400000000 0.7831386328 0.6634901443 2.2670719624 0.0190267284 0.0028960000 16126181 955859216 1373700096 -0.6558221579 0.6043404937 1.3281999826 748 29.8800000000 0.7796301842 0.6636454117 2.2670719624 0.0190303699 0.0029030000 16128157 955859216 1373700096 -0.6635009646 0.6078130603 1.3268730640 749 29.9200000000 0.7769447565 0.6637966792 2.2670719624 0.0190317017 0.0028900000 16130133 955859216 1373700096 -0.6704749465 0.6110173464 1.3261687756 750 29.9600000000 0.7743695974 0.6639441097 2.2670719624 0.0190345073 0.0028720000 16132109 955859216 1373700096 -0.6770160198 0.6139679551 1.3253943920 751 30.0000000000 0.7720922828 0.6640881153 2.2670719624 0.0190370698 0.0028720000 16134085 955859216 1373700096 -0.6829632521 0.6162262559 1.3247421980 752 30.0400000000 0.7697407603 0.6642286108 2.2670719624 0.0190366094 0.0028680000 16136061 955859216 1373700096 -0.6885445714 0.6187300682 1.3238860369 753 30.0800000000 0.7676466107 0.6643659521 2.2670719624 0.0190341394 0.0027750000 16138037 955859216 1373700096 -0.6932179332 0.6222743988 1.3225443363 754 30.1200000000 0.7654255033 0.6644999834 2.2670719624 0.0190382816 0.0027650000 16140013 955859216 1373700096 -0.6981733441 0.6244586706 1.3214505911 755 30.1600000000 0.7628456354 0.6646302425 2.2670719624 0.0190473347 0.0027490000 16141989 955859216 1373700096 -0.7033575177 0.6254190207 1.3201006651 756 30.2000000000 0.7595913410 0.6647558524 2.2670719624 0.0190573668 0.0027810000 16143965 955859216 1373700096 -0.7091713548 0.6264421344 1.3184366226 757 30.2400000000 0.7560132742 0.6648764038 2.2670719624 0.0190549908 0.0027580000 16145941 955859216 1373700096 -0.7145170569 0.6290409565 1.3157875538 758 30.2800000000 0.7528413534 0.6649924526 2.2670719624 0.0190539195 0.0027470000 16147917 955859216 1373700096 -0.7202302814 0.6306986809 1.3136789799 759 30.3200000000 0.7487895489 0.6651028572 2.2670719624 0.0190717652 0.0027640000 16149893 955859216 1373700096 -0.7268077135 0.6319369674 1.3110730648 760 30.3600000000 0.7434309721 0.6652059205 2.2670719624 0.0190877840 0.0027460000 16151869 955859216 1373700096 -0.7332368493 0.6355630159 1.3064825535 761 30.4000000000 0.7383779883 0.6653020730 2.2670719624 0.0191011152 0.0027710000 16153845 955859216 1373700096 -0.7394683957 0.6377604008 1.3022423983 762 30.4400000000 0.7329942584 0.6653909079 2.2670719624 0.0191042576 0.0027390000 16155821 955859216 1373700096 -0.7456325293 0.6399482489 1.2975462675 763 30.4800000000 0.7272431850 0.6654719725 2.2670719624 0.0191047129 0.0027160000 16157797 955859216 1373700096 -0.7522447109 0.6419704556 1.2926312685 764 30.5200000000 0.7214112878 0.6655451915 2.2670719624 0.0191026343 0.0027100000 16159773 955859216 1373700096 -0.7589474320 0.6442462206 1.2875452042 765 30.5600000000 0.7141498327 0.6656087270 2.2670719624 0.0191073369 0.0028890000 16161749 955859216 1373700096 -0.7663809657 0.6436198354 1.2815302610 766 30.6000000000 0.7090571523 0.6656654482 2.2670719624 0.0191027921 0.0026930000 16163725 955859216 1373700096 -0.7731839418 0.6461251378 1.2772358656 767 30.6400000000 0.7012052536 0.6657117843 2.2670719624 0.0191037869 0.0028880000 16165701 955859216 1373700096 -0.7804914117 0.6463752389 1.2701100111 768 30.6800000000 0.6950098872 0.6657499328 2.2670719624 0.0191015260 0.0027660000 16167677 955859216 1373700096 -0.7876212597 0.6479454041 1.2646125555 769 30.7200000000 0.6883682013 0.6657793454 2.2670719624 0.0190999158 0.0027580000 16169653 955859216 1373700096 -0.7948590517 0.6497561932 1.2585899830 770 30.7600000000 0.6813155413 0.6657995223 2.2670719624 0.0190984989 0.0028360000 16171629 955859216 1373700096 -0.8021864891 0.6510673165 1.2521500587 771 30.8000000000 0.6745991707 0.6658109356 2.2670719624 0.0190941176 0.0028330000 16173605 955859216 1373700096 -0.8091886640 0.6522228718 1.2459611893 772 30.8400000000 0.6684454679 0.6658143482 2.2670719624 0.0190891839 0.0028300000 16175581 955859216 1373700096 -0.8161350489 0.6523272991 1.2404551506 773 30.8800000000 0.6620609164 0.6658094925 2.2670719624 0.0190850282 0.0028320000 16177557 955859216 1373700096 -0.8232349157 0.6528795958 1.2346332073 774 30.9200000000 0.6563647985 0.6657972901 2.2670719624 0.0190822727 0.0028390000 16179533 955859216 1373700096 -0.8302372098 0.6530861855 1.2295664549 775 30.9600000000 0.6508655548 0.6657780233 2.2670719624 0.0190783814 0.0027340000 16181509 955859216 1373700096 -0.8370792270 0.6525097489 1.2247434855 776 31.0000000000 0.6458879709 0.6657523918 2.2670719624 0.0190758532 0.0026160000 16183485 955859216 1373700096 -0.8438968062 0.6531600356 1.2204940319 777 31.0400000000 0.6379716396 0.6657166380 2.2670719624 0.0190864259 0.0028100000 16185461 955859216 1373700096 -0.8507688642 0.6522172689 1.2127149105 778 31.0800000000 0.6328528523 0.6656743966 2.2670719624 0.0190830734 0.0026070000 16187437 955859216 1373700096 -0.8570880294 0.6544265151 1.2078895569 779 31.1200000000 0.6259590387 0.6656234141 2.2670719624 0.0190836779 0.0028130000 16189413 955859216 1373700096 -0.8637893200 0.6528115273 1.2013121843 780 31.1600000000 0.6203937531 0.6655654274 2.2670719624 0.0190793338 0.0028020000 16191389 955859216 1373700096 -0.8700775504 0.6530973315 1.1960201263 781 31.2000000000 0.6146274209 0.6655002058 2.2670719624 0.0190740204 0.0028030000 16193365 955859216 1373700096 -0.8760572672 0.6529904008 1.1904592514 782 31.2400000000 0.6097208858 0.6654288768 2.2670719624 0.0190654529 0.0027870000 16195341 955859216 1373700096 -0.8818798661 0.6522206068 1.1858930588 783 31.2800000000 0.6048213840 0.6653514726 2.2670719624 0.0190564625 0.0027940000 16197317 955859216 1373700096 -0.8878010511 0.6518259645 1.1812840700 784 31.3200000000 0.6004281044 0.6652686622 2.2670719624 0.0190489457 0.0028030000 16199293 955859216 1373700096 -0.8933193088 0.6511923671 1.1771935225 785 31.3600000000 0.5963824987 0.6651809091 2.2670719624 0.0190396954 0.0027980000 16201269 955859216 1373700096 -0.8985358477 0.6500519514 1.1734923124 786 31.4000000000 0.5923281908 0.6650882211 2.2670719624 0.0190300125 0.0027910000 16203245 955859216 1373700096 -0.9038158655 0.6492129564 1.1697243452 787 31.4400000000 0.5882950425 0.6649906440 2.2670719624 0.0190204311 0.0027920000 16205221 955859216 1373700096 -0.9085872769 0.6494286060 1.1657404900 788 31.4800000000 0.5853244066 0.6648895448 2.2670719624 0.0190105747 0.0027900000 16207197 955859216 1373700096 -0.9133180380 0.6491008997 1.1629979610 789 31.5200000000 0.5822166204 0.6647847628 2.2670719624 0.0190008088 0.0027900000 16209173 955859216 1373700096 -0.9177675247 0.6477771997 1.1602059603 790 31.5600000000 0.5794003606 0.6646766813 2.2670719624 0.0189908282 0.0028030000 16211149 955859216 1373700096 -0.9223286510 0.6467486024 1.1576919556 791 31.6000000000 0.5766499043 0.6645653959 2.2670719624 0.0189814948 0.0028090000 16213125 955859216 1373700096 -0.9264866710 0.6457974911 1.1551840305 792 31.6400000000 0.5746063590 0.6644518113 2.2670719624 0.0189720468 0.0028030000 16215101 955859216 1373700096 -0.9304016232 0.6445646882 1.1534742117 793 31.6800000000 0.5728673339 0.6643363201 2.2670719624 0.0189614024 0.0028050000 16217077 955859216 1373700096 -0.9339533448 0.6430314779 1.1521098614 794 31.7200000000 0.5716336370 0.6642195661 2.2670719624 0.0189523856 0.0028090000 16219053 955859216 1373700096 -0.9372244477 0.6414316297 1.1512997150 795 31.7600000000 0.5704024434 0.6641015571 2.2670719624 0.0189469549 0.0028150000 16221029 955859216 1373700096 -0.9403997064 0.6398848295 1.1504682302 796 31.8000000000 0.5694716573 0.6639826754 2.2670719624 0.0189447765 0.0028090000 16223005 955859216 1373700096 -0.9437463284 0.6384548545 1.1499577761 797 31.8400000000 0.5690401196 0.6638635504 2.2670719624 0.0189488387 0.0028430000 16224981 955859216 1373700096 -0.9465702176 0.6372074485 1.1499266624 798 31.8800000000 0.5681883693 0.6637436567 2.2670719624 0.0189548179 0.0029970000 16226957 955859216 1373700096 -0.9494324923 0.6353567243 1.1495330334 799 31.9200000000 0.5676496029 0.6636233888 2.2670719624 0.0189584029 0.0028840000 16228933 955859216 1373700096 -0.9522410631 0.6333496571 1.1495052576 800 31.9600000000 0.5674285889 0.6635031453 2.2670719624 0.0189608070 0.0028890000 16230909 955859216 1373700096 -0.9549477100 0.6313187480 1.1498287916 801 32.0000000000 0.5679066777 0.6633837989 2.2670719624 0.0189645885 0.0027940000 16232885 955859216 1373700096 -0.9578980803 0.6297724247 1.1510123014 802 32.0400000000 0.5680482388 0.6632649267 2.2670719624 0.0189611177 0.0027880000 16234861 955859216 1373700096 -0.9605748653 0.6280022264 1.1516972780 803 32.0800000000 0.5693398118 0.6631479589 2.2670719624 0.0189566647 0.0026950000 16236837 955859216 1373700096 -0.9628158808 0.6287874579 1.1535540819 804 32.1199999990 0.5693519115 0.6630312971 2.2670719624 0.0189544577 0.0029100000 16238813 955859216 1373700096 -0.9652112722 0.6278564334 1.1534000635 805 32.1600000000 0.5705416203 0.6629164031 2.2670719624 0.0189520412 0.0028130000 16240789 955859216 1373700096 -0.9673680067 0.6271453500 1.1551973820 806 32.2000000000 0.5708603263 0.6628021896 2.2670719624 0.0189523183 0.0029000000 16242765 955859216 1373700096 -0.9696204066 0.6255304217 1.1558392048 807 32.2400000000 0.5725947618 0.6626904084 2.2670719624 0.0189538641 0.0028220000 16244741 955859216 1373700096 -0.9714673758 0.6234623194 1.1584925652 808 32.2800000000 0.5734968781 0.6625800204 2.2670719624 0.0189534522 0.0029220000 16246717 955859216 1373700096 -0.9739689827 0.6215031147 1.1598557234 809 32.3200000000 0.5758060217 0.6624727596 2.2670719624 0.0189511470 0.0028350000 16248693 955859216 1373700096 -0.9759274125 0.6190034151 1.1632113457 810 32.3600000000 0.5771793127 0.6623674590 2.2670719624 0.0189519496 0.0028290000 16250669 955859216 1373700096 -0.9781159759 0.6171770096 1.1653064489 811 32.4000000000 0.5791414976 0.6622648376 2.2670719624 0.0189446509 0.0027310000 16252645 955859216 1373700096 -0.9806267023 0.6136189699 1.1689846516 812 32.4399999990 0.5808142424 0.6621645290 2.2670719624 0.0189385055 0.0027510000 16254621 955859216 1373700096 -0.9830483198 0.6105259061 1.1715657711 813 32.4800000000 0.5828310847 0.6620669479 2.2670719624 0.0189343255 0.0027550000 16256597 955859216 1373700096 -0.9856123328 0.6087075472 1.1741566658 814 32.5200000000 0.5847968459 0.6619720215 2.2670719624 0.0189300988 0.0027570000 16258573 955859216 1373700096 -0.9882037640 0.6067112684 1.1769741774 815 32.5600000000 0.5868175030 0.6618798074 2.2670719624 0.0189245097 0.0027740000 16260549 955859216 1373700096 -0.9909925461 0.6041800380 1.1802219152 816 32.6000000000 0.5896720290 0.6617913174 2.2670719624 0.0189215361 0.0027720000 16262525 955859216 1373700096 -0.9938730001 0.6008268595 1.1843115091 817 32.6400000000 0.5909430981 0.6617045999 2.2670719624 0.0189316522 0.0029850000 16264501 955859216 1373700096 -0.9953148961 0.6012831926 1.1847174168 818 32.6800000000 0.5936519504 0.6616214060 2.2670719624 0.0189228698 0.0027900000 16266477 955859216 1373700096 -0.9991805553 0.5971993208 1.1891645193 819 32.7200000000 0.5963896513 0.6615417579 2.2670719624 0.0189172205 0.0027880000 16268453 955859216 1373700096 -1.0029493570 0.5955945253 1.1928158998 820 32.7599999990 0.5990539193 0.6614655532 2.2670719624 0.0189119289 0.0027950000 16270429 955859216 1373700096 -1.0066806078 0.5941862464 1.1963802576 821 32.7999999990 0.6028581858 0.6613941679 2.2670719624 0.0189149719 0.0028020000 16272405 955859216 1373700096 -1.0102587938 0.5945716500 1.2005665302 822 32.8400000000 0.6062289476 0.6613270569 2.2670719624 0.0189354976 0.0036160000 16274381 955859216 1373700096 -1.0129150152 0.5965307355 1.2039479017 823 32.8800000000 0.6093515754 0.6612639032 2.2670719624 0.0189448296 0.0031240000 16276357 955859216 1373700096 -1.0168709755 0.5963933468 1.2078697681 824 32.9200000000 0.6124894023 0.6612047109 2.2670719624 0.0189532627 0.0030350000 16278333 955859216 1373700096 -1.0211439133 0.5979176760 1.2109317780 825 32.9600000000 0.6164051294 0.6611504083 2.2670719624 0.0189566373 0.0029350000 16280309 955859216 1373700096 -1.0256236792 0.5978634953 1.2156916857 826 33.0000000000 0.6199730635 0.6611005568 2.2670719624 0.0189569104 0.0029550000 16282285 955859216 1373700096 -1.0304080248 0.5985130072 1.2197867632 827 33.0400000000 0.6237384677 0.6610553790 2.2670719624 0.0189611149 0.0031450000 16284261 955859216 1373700096 -1.0349843502 0.5976936221 1.2242475748 828 33.0800000000 0.6277835369 0.6610151956 2.2670719624 0.0189786747 0.0030100000 16286237 955859216 1373700096 -1.0393962860 0.5957587361 1.2294687033 829 33.1199999990 0.6315682530 0.6609796746 2.2670719624 0.0190066665 0.0030630000 16288213 955859216 1373700096 -1.0444451571 0.5947556496 1.2336958647 830 33.1600000000 0.6354436278 0.6609489082 2.2670719624 0.0190331236 0.0030570000 16290189 955859216 1373700096 -1.0491297245 0.5934874415 1.2384052277 831 33.2000000000 0.6406970024 0.6609245377 2.2670719624 0.0190630741 0.0035210000 16292165 955859216 1373700096 -1.0539717674 0.5914139152 1.2448359728 832 33.2400000000 0.6450361013 0.6609054410 2.2670719624 0.0190878869 0.0032320000 16294141 955859216 1373700096 -1.0591205359 0.5897324085 1.2501424551 833 33.2800000000 0.6492743492 0.6608914781 2.2670719624 0.0191003445 0.0031050000 16296117 955859216 1373700096 -1.0647094250 0.5887370110 1.2551468611 834 33.3200000000 0.6539124846 0.6608831100 2.2670719624 0.0191058555 0.0030230000 16298093 955859216 1373700096 -1.0700746775 0.5858416557 1.2612861395 835 33.3600000000 0.6573737264 0.6608789072 2.2670719624 0.0191244002 0.0031190000 16300069 955859216 1373700096 -1.0754084587 0.5854198933 1.2650038004 836 33.4000000000 0.6617252827 0.6608799196 2.2670719624 0.0191436312 0.0031140000 16302045 955859216 1373700096 -1.0807831287 0.5842189789 1.2701405287 837 33.4399999990 0.6654528975 0.6608853831 2.2670719624 0.0191657151 0.0031150000 16304021 955859216 1373700096 -1.0861896276 0.5837108493 1.2743844986 838 33.4800000000 0.6699695587 0.6608962234 2.2670719624 0.0191961227 0.0031020000 16305997 955859216 1373700096 -1.0908391476 0.5813267231 1.2799773216 839 33.5200000000 0.6741649508 0.6609120384 2.2670719624 0.0192329292 0.0031230000 16307973 955859216 1373700096 -1.0958300829 0.5811432600 1.2846633196 840 33.5600000000 0.6761564612 0.6609301865 2.2670719624 0.0192528899 0.0031130000 16309949 955859216 1373700096 -1.1006634235 0.5797727108 1.2871179581 841 33.6000000000 0.6790561080 0.6609517393 2.2670719624 0.0192576042 0.0031140000 16311925 955859216 1373700096 -1.1055383682 0.5793436170 1.2903366089 842 33.6400000000 0.6817761660 0.6609764714 2.2670719624 0.0192552872 0.0031290000 16313901 955859216 1373700096 -1.1101821661 0.5786833763 1.2934107780 843 33.6800000000 0.6851400137 0.6610051352 2.2670719624 0.0192542624 0.0030350000 16315877 955859216 1373700096 -1.1146473885 0.5767050982 1.2982146740 844 33.7200000000 0.6887711883 0.6610380333 2.2670719624 0.0192600374 0.0030330000 16317853 955859216 1373700096 -1.1186711788 0.5737707019 1.3030726910 845 33.7599999990 0.6926220059 0.6610754108 2.2670719624 0.0192791427 0.0031550000 16319829 955859216 1373700096 -1.1226511002 0.5730147362 1.3066817522 846 33.7999999990 0.6951928735 0.6611157388 2.2670719624 0.0192904986 0.0031600000 16321805 955859216 1373700096 -1.1267344952 0.5721369386 1.3096657991 847 33.8400000000 0.6978743076 0.6611591373 2.2670719624 0.0192883908 0.0031520000 16323781 955859216 1373700096 -1.1299985647 0.5688700080 1.3133715391 848 33.8800000000 0.7005904317 0.6612056365 2.2670719624 0.0192840369 0.0031590000 16325757 955859216 1373700096 -1.1335791349 0.5669195056 1.3167446852 849 33.9200000000 0.7033895254 0.6612553231 2.2670719624 0.0192751269 0.0030700000 16327733 955859216 1373700096 -1.1365536451 0.5628817677 1.3216038942 850 33.9600000000 0.7059634924 0.6613079209 2.2670719624 0.0192678553 0.0031580000 16329709 955859216 1373700096 -1.1399962902 0.5607633591 1.3241590261 851 34.0000000000 0.7081656456 0.6613629829 2.2670719624 0.0192573244 0.0029800000 16331685 955859216 1373700096 -1.1432726383 0.5579087138 1.3290717602 852 34.0400000000 0.7118242979 0.6614222097 2.2670719624 0.0192484054 0.0029790000 16333661 955859216 1373700096 -1.1459795237 0.5543180108 1.3344063759 853 34.0800000000 0.7142241001 0.6614841111 2.2670719624 0.0192533373 0.0031780000 16335637 955859216 1373700096 -1.1490660906 0.5532248616 1.3351655006 854 34.1199999990 0.7167151570 0.6615487845 2.2670719624 0.0192524894 0.0031990000 16337613 955859216 1373700096 -1.1518572569 0.5520464778 1.3381145000 855 34.1600000000 0.7196565270 0.6616167468 2.2670719624 0.0192471086 0.0031100000 16339589 955859216 1373700096 -1.1539049149 0.5503080487 1.3426893950 856 34.2000000000 0.7217633724 0.6616870115 2.2670719624 0.0192429229 0.0032010000 16341565 955859216 1373700096 -1.1566203833 0.5486934185 1.3445265293 857 34.2400000000 0.7228942513 0.6617584319 2.2670719624 0.0192319790 0.0030020000 16343541 955859216 1373700096 -1.1584302187 0.5483128428 1.3482090235 858 34.2800000000 0.7242528796 0.6618312692 2.2670719624 0.0192209991 0.0030210000 16345517 955859216 1373700096 -1.1607484818 0.5473918319 1.3498679399 859 34.3200000000 0.7270438671 0.6619071861 2.2670719624 0.0192107310 0.0030110000 16347493 955859216 1373700096 -1.1622895002 0.5433374047 1.3530362844 860 34.3600000000 0.7283276916 0.6619844192 2.2670719624 0.0192004185 0.0030200000 16349469 955859216 1373700096 -1.1637641191 0.5383476019 1.3569027185 861 34.4000000000 0.7301456928 0.6620635845 2.2670719624 0.0191918196 0.0030250000 16351445 955859216 1373700096 -1.1660708189 0.5347781181 1.3604094982 862 34.4400000000 0.7319834232 0.6621446980 2.2670719624 0.0191820709 0.0030340000 16353421 955859216 1373700096 -1.1679197550 0.5310434699 1.3634479046 863 34.4800000000 0.7339226007 0.6622278705 2.2670719624 0.0191734032 0.0030270000 16355397 955859216 1373700096 -1.1688823700 0.5259205103 1.3670923710 864 34.5200000000 0.7355033159 0.6623126801 2.2670719624 0.0191654968 0.0030250000 16357373 955859216 1373700096 -1.1700783968 0.5222867727 1.3710384369 865 34.5600000000 0.7359303832 0.6623977872 2.2670719624 0.0191558326 0.0030330000 16359349 955859216 1373700096 -1.1715246439 0.5207417607 1.3736221790 866 34.6000000000 0.7360876799 0.6624828795 2.2670719624 0.0191450467 0.0030300000 16361325 955859216 1373700096 -1.1731207371 0.5190623403 1.3746666908 867 34.6400000000 0.7379692793 0.6625699457 2.2670719624 0.0191346194 0.0030250000 16363301 955859216 1373700096 -1.1749678850 0.5173810124 1.3754390478 868 34.6800000000 0.7390289307 0.6626580321 2.2670719624 0.0191260182 0.0030220000 16365277 955859216 1373700096 -1.1762167215 0.5146120191 1.3764117956 869 34.7200000000 0.7407128215 0.6627478535 2.2670719624 0.0191176254 0.0030430000 16367253 955859216 1373700096 -1.1767896414 0.5120158792 1.3788273335 870 34.7600000000 0.7407479882 0.6628375088 2.2670719624 0.0191079209 0.0030390000 16369229 955859216 1373700096 -1.1773518324 0.5091698170 1.3810346127 871 34.8000000000 0.7408638597 0.6629270913 2.2670719624 0.0190979645 0.0030550000 16371205 955859216 1373700096 -1.1784007549 0.5070753694 1.3823632002 872 34.8400000000 0.7413096428 0.6630169796 2.2670719624 0.0190893415 0.0030340000 16373181 955859216 1373700096 -1.1797112226 0.5044244528 1.3832345009 873 34.8800000000 0.7422714829 0.6631077636 2.2670719624 0.0190811516 0.0030440000 16375157 955859216 1373700096 -1.1813014746 0.5024809837 1.3845876455 874 34.9200000000 0.7427576184 0.6631988962 2.2670719624 0.0190730645 0.0030600000 16377133 955859216 1373700096 -1.1828533411 0.5008359551 1.3855863810 875 34.9600000000 0.7426718473 0.6632897224 2.2670719624 0.0190652116 0.0030540000 16379109 955859216 1373700096 -1.1849755049 0.5006526709 1.3856573105 876 35.0000000000 0.7434781194 0.6633812617 2.2670719624 0.0190569318 0.0030520000 16381085 955859216 1373700096 -1.1868059635 0.5006636977 1.3852992058 877 35.0400000000 0.7440083027 0.6634731967 2.2670719624 0.0190469915 0.0030540000 16383061 955859216 1373700096 -1.1886322498 0.5008429885 1.3851349354 878 35.0800000000 0.7442051172 0.6635651465 2.2670719624 0.0190362239 0.0030580000 16385037 955859216 1373700096 -1.1902335882 0.5015175343 1.3845909834 879 35.1200000000 0.7448223829 0.6636575894 2.2670719624 0.0190254401 0.0030580000 16387013 955859216 1373700096 -1.1915909052 0.5015301108 1.3846656084 880 35.1600000000 0.7450400591 0.6637500694 2.2670719624 0.0190147444 0.0030610000 16388989 955859216 1373700096 -1.1931148767 0.5022293329 1.3846205473 881 35.2000000000 0.7455451488 0.6638429129 2.2670719624 0.0190041688 0.0030580000 16390965 955859216 1373700096 -1.1948237419 0.5030507445 1.3840483427 882 35.2400000000 0.7473001480 0.6639375356 2.2670719624 0.0189934721 0.0030800000 16392941 955859216 1373700096 -1.1952813864 0.5005800724 1.3855795860 ================================================ FILE: icra2018_results/1080/memory_kfusion_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:15:34 Properties: ================= frame-limit: 0 log-file: out_paper//memory_kfusion_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 -nan 0.0034840000 0.0004940000 0.0005470000 0.0000050000 0.0000010000 0.0023450000 12532477 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378911 0.0017470000 0.0004560000 0.0005340000 0.0000030000 0.0000010000 0.0007320000 12732221 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728699 0.0017320000 0.0004490000 0.0005340000 0.0000030000 0.0000010000 0.0007240000 12735389 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723129 0.0024410000 0.0004490000 0.0005360000 0.0000030000 0.0000060000 0.0014240000 12738565 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276867 0.0024566393 0.0055015511 0.0048987302 0.0058670000 0.0004470000 0.0031560000 0.0000030000 0.0000030000 0.0022310000 12741725 96830484 509673472 3.9957129955 4.0020370483 4.0009112358 6 0.2000000000 0.0021193668 0.0024004272 0.0055015511 0.0043897879 0.0044890000 0.0004510000 0.0028490000 0.0000000000 0.0000030000 0.0011610000 12745301 96830484 509673472 3.9965579510 4.0017552376 4.0000634193 7 0.2400000000 0.0020520808 0.0023506635 0.0055015511 0.0040162830 0.0042100000 0.0004510000 0.0022700000 0.0000030000 0.0000040000 0.0014570000 12748077 96830484 509673472 3.9963893890 4.0014748573 4.0003581047 8 0.2800000000 0.0021309818 0.0023232032 0.0055015511 0.0037226256 0.0040510000 0.0004480000 0.0024210000 0.0000000000 0.0000030000 0.0011510000 12750853 96830484 509673472 3.9949610233 4.0019330978 4.0002708435 9 0.3200000000 0.0021698186 0.0023061605 0.0055015511 0.0035285755 0.0050110000 0.0004480000 0.0022770000 0.0000030000 0.0000020000 0.0022480000 12754397 96830484 509673472 3.9930253029 4.0012869835 4.0003128052 10 0.3600000000 0.0022089549 0.0022964399 0.0055015511 0.0033889312 0.0039180000 0.0004500000 0.0022820000 0.0000000000 0.0000040000 0.0011520000 12758773 96830484 509673472 3.9929094315 4.0026316643 4.0009026527 11 0.4000000000 0.0022601751 0.0022931431 0.0055015511 0.0033576804 0.0046610000 0.0004510000 0.0027180000 0.0000030000 0.0000040000 0.0014550000 12761549 96830484 509673472 3.9919466972 4.0017867088 4.0016007423 12 0.4400000000 0.0022672073 0.0022909818 0.0055015511 0.0034304144 0.0039010000 0.0004480000 0.0022740000 0.0000010000 0.0000030000 0.0011430000 12764325 96830484 509673472 3.9918613434 4.0017361641 4.0008234978 13 0.4800000000 0.0022819978 0.0022902907 0.0055015511 0.0034359352 0.0049960000 0.0004480000 0.0022760000 0.0000030000 0.0000030000 0.0022320000 12767101 96830484 509673472 3.9894280434 4.0015416145 4.0013961792 14 0.5200000000 0.0023268927 0.0022929052 0.0055015511 0.0033242452 0.0069930000 0.0004500000 0.0053560000 0.0000000000 0.0000040000 0.0011490000 12769877 96830484 509673472 3.9894309044 4.0028085709 4.0008172989 15 0.5600000000 0.0023079070 0.0022939053 0.0055015511 0.0032120938 0.0045190000 0.0004500000 0.0025720000 0.0000040000 0.0000030000 0.0014560000 12772653 96830484 509673472 3.9863359928 4.0038881302 4.0015878677 16 0.6000000000 0.0023973526 0.0023003707 0.0055015511 0.0031278743 0.0049330000 0.0004510000 0.0032970000 0.0000000000 0.0000030000 0.0011460000 12775429 96830484 509673472 3.9871206284 4.0023245811 4.0005326271 17 0.6400000000 0.0024036658 0.0023064469 0.0055015511 0.0030498162 0.0053040000 0.0004510000 0.0025730000 0.0000030000 0.0000030000 0.0022330000 12779741 96830484 509673472 3.9851038456 4.0008935928 3.9991035461 18 0.6800000000 0.0024461173 0.0023142064 0.0055015511 0.0029599922 0.0044990000 0.0004490000 0.0028680000 0.0000000000 0.0000040000 0.0011400000 12785717 96830484 509673472 3.9835441113 4.0011601448 4.0000782013 19 0.7200000000 0.0024378977 0.0023207165 0.0055015511 0.0029192022 0.0045280000 0.0004490000 0.0025830000 0.0000030000 0.0000030000 0.0014490000 12788493 96830484 509673472 3.9820592403 4.0014061928 3.9996428490 20 0.7600000000 0.0025582798 0.0023325946 0.0055015511 0.0029371945 0.0043490000 0.0004490000 0.0027240000 0.0000000000 0.0000030000 0.0011330000 12791269 96830484 509673472 3.9790954590 4.0002269745 3.9993181229 21 0.8000000000 0.0026400634 0.0023472360 0.0055015511 0.0028722664 0.0054760000 0.0004490000 0.0027350000 0.0000030000 0.0000030000 0.0022430000 12794045 96830484 509673472 3.9762642384 4.0010976791 3.9996490479 22 0.8400000000 0.0029139980 0.0023729979 0.0055015511 0.0028126401 0.0039460000 0.0004500000 0.0022920000 0.0000000000 0.0000030000 0.0011570000 12796821 96830484 509673472 3.9707870483 4.0004653931 3.9992003441 23 0.8800000000 0.0029073921 0.0023962324 0.0055015511 0.0027480098 0.0045780000 0.0004560000 0.0027080000 0.0000030000 0.0000030000 0.0013610000 12799597 96830484 509673472 3.9713716507 3.9995737076 3.9975576401 24 0.9200000000 0.0028074081 0.0024133648 0.0055015511 0.0026877869 0.0040880000 0.0004200000 0.0025400000 0.0000000000 0.0000030000 0.0010790000 12802373 96830484 509673472 3.9628982544 4.0010151863 3.9969213009 25 0.9600000000 0.0027890853 0.0024283936 0.0055015511 0.0026594899 0.0046880000 0.0004200000 0.0021230000 0.0000040000 0.0000030000 0.0020910000 12805149 96830484 509673472 3.9617063999 4.0022802353 3.9961562157 26 1.0000000000 0.0028312423 0.0024438878 0.0055015511 0.0026071527 0.0040740000 0.0004200000 0.0025250000 0.0000010000 0.0000030000 0.0010750000 12807925 96830484 509673472 3.9554359913 4.0008039474 3.9970479012 27 1.0400000000 0.0026908601 0.0024530349 0.0055015511 0.0026328908 0.0043700000 0.0004190000 0.0025240000 0.0000030000 0.0000030000 0.0013720000 12810701 96830484 509673472 3.9496476650 4.0000371933 3.9948542118 28 1.0800000000 0.0027713049 0.0024644017 0.0055015511 0.0027076861 0.0040860000 0.0004170000 0.0025380000 0.0000010000 0.0000030000 0.0010780000 12813477 96830484 509673472 3.9448781013 4.0019001961 3.9945559502 29 1.1200000000 0.0027278329 0.0024734855 0.0055015511 0.0027861364 0.0053460000 0.0004160000 0.0027950000 0.0000030000 0.0000030000 0.0020780000 12816253 96830484 509673472 3.9388289452 4.0020222664 3.9917790890 30 1.1600000000 0.0030030743 0.0024911385 0.0055015511 0.0027896121 0.0040760000 0.0004200000 0.0025300000 0.0000010000 0.0000030000 0.0010690000 12819029 96830484 509673472 3.9293975830 4.0014457703 3.9938297272 31 1.2000000000 0.0029134697 0.0025047620 0.0055015511 0.0027658133 0.0047690000 0.0004190000 0.0029410000 0.0000030000 0.0000040000 0.0013510000 12821805 96830484 509673472 3.9228034019 4.0022144318 3.9920370579 32 1.2400000000 0.0029502921 0.0025186849 0.0055015511 0.0027655082 0.0040720000 0.0004190000 0.0025190000 0.0000000000 0.0000030000 0.0010760000 12824581 96830484 509673472 3.9160883427 4.0025353432 3.9897420406 33 1.2800000000 0.0029388322 0.0025314166 0.0055015511 0.0028074236 0.0050840000 0.0004190000 0.0025320000 0.0000030000 0.0000030000 0.0020720000 12830429 96830484 509673472 3.9104778767 4.0022206306 3.9895055294 34 1.3200000000 0.0028928840 0.0025420480 0.0055015511 0.0027808541 0.0040910000 0.0004180000 0.0025360000 0.0000000000 0.0000030000 0.0010760000 12839605 96830484 509673472 3.8820109367 4.0016808510 3.9892072678 35 1.3600000000 0.0030740034 0.0025572467 0.0055015511 0.0030478220 0.0043800000 0.0004190000 0.0025380000 0.0000030000 0.0000030000 0.0013570000 12842381 96830484 509673472 3.8787236214 4.0025434494 3.9865612984 36 1.4000000000 0.0030465741 0.0025708391 0.0055015511 0.0035590300 0.0036960000 0.0004190000 0.0021310000 0.0000000000 0.0000040000 0.0010820000 12845157 96830484 509673472 3.8730773926 4.0032992363 3.9847621918 37 1.4400000000 0.0030497839 0.0025837836 0.0055015511 0.0035973852 0.0055090000 0.0004180000 0.0029430000 0.0000030000 0.0000040000 0.0020810000 12847933 96830484 509673472 3.8621592522 4.0013198853 3.9860253334 38 1.4800000000 0.0032347857 0.0026009152 0.0055015511 0.0035571079 0.0042380000 0.0004180000 0.0026770000 0.0000000000 0.0000030000 0.0010750000 12850709 96830484 509673472 3.8505938053 4.0007586479 3.9867534637 39 1.5200000000 0.0032996268 0.0026188309 0.0055015511 0.0035142520 0.0039610000 0.0004190000 0.0021230000 0.0000030000 0.0000030000 0.0013490000 12853485 96830484 509673472 3.8474643230 4.0001368523 3.9834077358 40 1.5600000000 0.0033595394 0.0026373486 0.0055015511 0.0034974516 0.0036810000 0.0004180000 0.0021190000 0.0000010000 0.0000030000 0.0010740000 12856261 96830484 509673472 3.8375627995 3.9985218048 3.9840941429 41 1.6000000000 0.0033771237 0.0026553919 0.0055015511 0.0035179954 0.0052290000 0.0004180000 0.0026640000 0.0000040000 0.0000030000 0.0020740000 12859037 96830484 509673472 3.8271627426 3.9974079132 3.9858467579 42 1.6400000000 0.0033799068 0.0026726423 0.0055015511 0.0034791447 0.0036990000 0.0004220000 0.0021270000 0.0000000000 0.0000030000 0.0010800000 12861813 96830484 509673472 3.8137965202 3.9989016056 3.9880623817 43 1.6800000000 0.0033599804 0.0026886269 0.0055015511 0.0034583165 0.0042620000 0.0004220000 0.0024090000 0.0000040000 0.0000030000 0.0013560000 12864589 96830484 509673472 3.8069851398 3.9993276596 3.9914343357 44 1.7200000000 0.0033661884 0.0027040260 0.0055015511 0.0034889453 0.0038370000 0.0004180000 0.0022730000 0.0000010000 0.0000030000 0.0010740000 12867365 96830484 509673472 3.8006703854 3.9986772537 3.9893207550 45 1.7600000000 0.0033918242 0.0027193104 0.0055015511 0.0035075278 0.0052470000 0.0004200000 0.0026790000 0.0000030000 0.0000020000 0.0020710000 12870141 96830484 509673472 3.7923028469 4.0006680489 3.9930343628 46 1.8000000000 0.0034432332 0.0027350479 0.0055015511 0.0035142342 0.0042380000 0.0004200000 0.0026730000 0.0000010000 0.0000030000 0.0010690000 12872917 96830484 509673472 3.7863345146 4.0012741089 3.9931325912 47 1.8400000000 0.0034609591 0.0027504928 0.0055015511 0.0036200770 0.0039670000 0.0004190000 0.0021220000 0.0000030000 0.0000030000 0.0013470000 12875693 96830484 509673472 3.7833206654 3.9994668961 3.9928333759 48 1.8800000000 0.0034226219 0.0027644955 0.0055015511 0.0036631838 0.0041220000 0.0004190000 0.0025490000 0.0000010000 0.0000030000 0.0010770000 12878469 96830484 509673472 3.7787642479 3.9991862774 3.9939386845 49 1.9200000000 0.0036193100 0.0027819407 0.0055015511 0.0036249447 0.0051130000 0.0004200000 0.0025420000 0.0000030000 0.0000030000 0.0020690000 12881245 96830484 509673472 3.7716324329 4.0004019737 3.9947488308 50 1.9600000000 0.0036020253 0.0027983424 0.0055015511 0.0036102777 0.0041160000 0.0004180000 0.0025490000 0.0000010000 0.0000030000 0.0010710000 12884021 96830484 509673472 3.7573082447 4.0000443459 3.9996886253 51 2.0000000000 0.0035140107 0.0028123751 0.0055015511 0.0035844030 0.0042670000 0.0004170000 0.0024160000 0.0000040000 0.0000030000 0.0013480000 12886797 96830484 509673472 3.7588646412 3.9998886585 3.9966924191 52 2.0400000000 0.0035647256 0.0028268434 0.0055015511 0.0035492286 0.0042540000 0.0004180000 0.0026790000 0.0000000000 0.0000040000 0.0010740000 12889573 96830484 509673472 3.7549414635 4.0002875328 3.9959812164 53 2.0800000000 0.0034589334 0.0028387696 0.0055015511 0.0035930305 0.0055360000 0.0004190000 0.0029580000 0.0000030000 0.0000030000 0.0020730000 12892349 96830484 509673472 3.7529308796 3.9978303909 3.9927303791 54 2.1200000000 0.0036061904 0.0028529811 0.0055015511 0.0036678873 0.0041230000 0.0004170000 0.0025440000 0.0000010000 0.0000030000 0.0010770000 12895125 96830484 509673472 3.7399079800 3.9963834286 3.9985299110 55 2.1600000000 0.0035217302 0.0028651402 0.0055015511 0.0037628748 0.0043990000 0.0004180000 0.0025440000 0.0000030000 0.0000030000 0.0013510000 12897901 96830484 509673472 3.7375404835 3.9971230030 3.9982161522 56 2.2000000000 0.0036147384 0.0028785258 0.0055015511 0.0037702022 0.0041280000 0.0004200000 0.0025450000 0.0000000000 0.0000030000 0.0010750000 12900677 96830484 509673472 3.7177095413 3.9974887371 4.0073981285 57 2.2400000000 0.0037543508 0.0028938912 0.0055015511 0.0037490664 0.0049590000 0.0004180000 0.0024100000 0.0000030000 0.0000030000 0.0020400000 12903453 96830484 509673472 3.7129154205 3.9949150085 4.0079960823 58 2.2800000000 0.0036991327 0.0029077747 0.0055015511 0.0037578658 0.0036820000 0.0003940000 0.0021630000 0.0000010000 0.0000030000 0.0010340000 12906229 96830484 509673472 3.7035665512 3.9941790104 4.0107655525 59 2.3200000000 0.0038119289 0.0029230993 0.0055015511 0.0038959011 0.0038120000 0.0003940000 0.0020350000 0.0000040000 0.0000030000 0.0012900000 12909005 96830484 509673472 3.6894257069 3.9966034889 4.0165252686 60 2.3600000000 0.0037969921 0.0029376642 0.0055015511 0.0040111584 0.0036880000 0.0003940000 0.0021730000 0.0000000000 0.0000040000 0.0010300000 12911781 96830484 509673472 3.6862921715 3.9948878288 4.0145845413 61 2.4000000000 0.0038415659 0.0029524822 0.0055015511 0.0041276680 0.0048680000 0.0003920000 0.0024270000 0.0000030000 0.0000030000 0.0019540000 12914557 96830484 509673472 3.6795256138 3.9934599400 4.0143737793 62 2.4400000000 0.0038519476 0.0029669898 0.0055015511 0.0042929610 0.0039370000 0.0003970000 0.0024230000 0.0000000000 0.0000030000 0.0010210000 12917333 96830484 509673472 3.6558568478 3.9938809872 4.0246863365 63 2.4800000000 0.0038875362 0.0029816016 0.0055015511 0.0044370717 0.0043080000 0.0003930000 0.0025450000 0.0000030000 0.0000020000 0.0012710000 12920109 96830484 509673472 3.6471881866 3.9928195477 4.0258588791 64 2.5200000000 0.0038809592 0.0029956541 0.0055015511 0.0047966559 0.0039310000 0.0003940000 0.0024180000 0.0000010000 0.0000030000 0.0010230000 12922885 96830484 509673472 3.6346523762 3.9939305782 4.0304188728 65 2.5600000000 0.0038915584 0.0030094372 0.0055015511 0.0051044626 0.0048730000 0.0003930000 0.0024140000 0.0000040000 0.0000030000 0.0019570000 12931805 96830484 509673472 3.6208136082 3.9938168526 4.0341477394 66 2.6000000000 0.0040776967 0.0030256230 0.0055015511 0.0051955859 0.0035540000 0.0003940000 0.0020290000 0.0000000000 0.0000030000 0.0010260000 12947381 96830484 509673472 3.6103196144 3.9951491356 4.0361337662 67 2.6400000000 0.0040973444 0.0030416188 0.0055015511 0.0052467188 0.0043240000 0.0003930000 0.0025410000 0.0000030000 0.0000030000 0.0012870000 12950157 96830484 509673472 3.6001150608 3.9975602627 4.0384063721 68 2.6800000000 0.0043203449 0.0030604236 0.0055015511 0.0052299886 0.0040700000 0.0003930000 0.0025520000 0.0000000000 0.0000040000 0.0010230000 12952933 96830484 509673472 3.5891768932 3.9974370003 4.0377373695 69 2.7200000000 0.0043210322 0.0030786933 0.0055015511 0.0051934229 0.0048690000 0.0003940000 0.0024180000 0.0000030000 0.0000030000 0.0019510000 12955709 96830484 509673472 3.5796027184 3.9976992607 4.0422320366 70 2.7600000000 0.0044691442 0.0030985569 0.0055015511 0.0051655168 0.0039330000 0.0003930000 0.0024140000 0.0000010000 0.0000040000 0.0010220000 12958485 96830484 509673472 3.5707461834 3.9996323586 4.0418829918 71 2.8000000000 0.0045009977 0.0031183096 0.0055015511 0.0052159664 0.0041830000 0.0003930000 0.0024020000 0.0000020000 0.0000030000 0.0012790000 12961261 96830484 509673472 3.5635983944 4.0002312660 4.0388054848 72 2.8400000000 0.0048466693 0.0031423146 0.0055015511 0.0058973494 0.0040620000 0.0003930000 0.0025380000 0.0000000000 0.0000030000 0.0010230000 12964037 96830484 509673472 3.5478830338 4.0054097176 4.0417704582 73 2.8800000000 0.0048706639 0.0031659906 0.0055015511 0.0059701013 0.0049670000 0.0003930000 0.0025010000 0.0000030000 0.0000030000 0.0019630000 12966813 96830484 509673472 3.5378990173 4.0068225861 4.0434460640 74 2.9200000000 0.0049523395 0.0031901304 0.0055015511 0.0060608448 0.0036320000 0.0003920000 0.0021060000 0.0000000000 0.0000030000 0.0010260000 12969589 96830484 509673472 3.5358510017 4.0085158348 4.0402979851 75 2.9600000000 0.0050944239 0.0032155210 0.0055015511 0.0061155866 0.0042790000 0.0003910000 0.0024860000 0.0000040000 0.0000030000 0.0012890000 12972365 96830484 509673472 3.5346469879 4.0121555328 4.0375261307 76 3.0000000000 0.0050744712 0.0032399809 0.0055015511 0.0061499892 0.0038920000 0.0003930000 0.0023620000 0.0000000000 0.0000040000 0.0010260000 12975141 96830484 509673472 3.5366408825 4.0152044296 4.0294275284 77 3.0400000000 0.0047418405 0.0032594855 0.0055015511 0.0061733062 0.0044700000 0.0003920000 0.0019610000 0.0000030000 0.0000030000 0.0020020000 12977917 96830484 509673472 3.5357542038 4.0155291557 4.0226597786 78 3.0800000000 0.0043574874 0.0032735625 0.0055015511 0.0061424400 0.0040060000 0.0003930000 0.0024570000 0.0000000000 0.0000040000 0.0010300000 12980693 96830484 509673472 3.5369186401 4.0168824196 4.0154695511 79 3.1200000000 0.0042994614 0.0032865486 0.0055015511 0.0061043442 0.0038720000 0.0003930000 0.0020660000 0.0000030000 0.0000030000 0.0012940000 12983469 96830484 509673472 3.5298628807 4.0200643539 4.0133037567 80 3.1600000000 0.0040653758 0.0032962839 0.0055015511 0.0060686978 0.0043340000 0.0003910000 0.0027940000 0.0000000000 0.0000030000 0.0010310000 12986245 96830484 509673472 3.5259101391 4.0230660439 4.0096011162 81 3.2000000000 0.0041703563 0.0033070749 0.0055015511 0.0060408276 0.0070090000 0.0003920000 0.0045140000 0.0000030000 0.0000030000 0.0019830000 12989021 96830484 509673472 3.5140922070 4.0221219063 4.0126113892 82 3.2400000000 0.0043994314 0.0033203963 0.0055015511 0.0060490054 0.0043520000 0.0003930000 0.0027970000 0.0000000000 0.0000030000 0.0010420000 12991797 96830484 509673472 3.5058872700 4.0222706795 4.0121884346 83 3.2800000000 0.0043160873 0.0033323926 0.0055015511 0.0060868350 0.0038730000 0.0003930000 0.0020560000 0.0000030000 0.0000030000 0.0012990000 12994573 96830484 509673472 3.4979910851 4.0243487358 4.0090532303 84 3.3200000000 0.0043093422 0.0033440230 0.0055015511 0.0060778719 0.0039590000 0.0003920000 0.0024170000 0.0000000000 0.0000040000 0.0010260000 12997349 96830484 509673472 3.4852666855 4.0233683586 4.0093283653 85 3.3600000000 0.0045079975 0.0033577168 0.0055015511 0.0060685334 0.0056210000 0.0003910000 0.0031260000 0.0000030000 0.0000030000 0.0019770000 13000125 96830484 509673472 3.4720723629 4.0242362022 4.0097374916 86 3.4000000000 0.0044961269 0.0033709541 0.0055015511 0.0061071517 0.0043110000 0.0003940000 0.0027520000 0.0000000000 0.0000040000 0.0010420000 13002901 96830484 509673472 3.4570422173 4.0251412392 4.0137987137 87 3.4400000000 0.0041861450 0.0033803241 0.0055015511 0.0062325877 0.0041990000 0.0003910000 0.0023790000 0.0000030000 0.0000030000 0.0012990000 13005677 96830484 509673472 3.4469790459 4.0238537788 4.0134687424 88 3.4800000000 0.0038641291 0.0033858219 0.0055015511 0.0063830288 0.0035760000 0.0003910000 0.0020260000 0.0000000000 0.0000040000 0.0010310000 13008453 96830484 509673472 3.4335215092 4.0241298676 4.0137062073 89 3.5200000000 0.0040299422 0.0033930592 0.0055015511 0.0065297679 0.0052470000 0.0003890000 0.0027320000 0.0000030000 0.0000030000 0.0019950000 13011229 96830484 509673472 3.4245271683 4.0243425369 4.0138106346 90 3.5600000000 0.0044025057 0.0034042753 0.0055015511 0.0066381371 0.0036710000 0.0003950000 0.0021100000 0.0000000000 0.0000030000 0.0010340000 13014005 96830484 509673472 3.4175684452 4.0225906372 4.0125837326 91 3.6000000000 0.0041462174 0.0034124285 0.0055015511 0.0066785265 0.0040270000 0.0003940000 0.0022160000 0.0000030000 0.0000030000 0.0012830000 13016781 96830484 509673472 3.4026930332 4.0212779045 4.0156178474 92 3.6400000000 0.0042098621 0.0034210962 0.0055015511 0.0066904798 0.0037690000 0.0003920000 0.0022190000 0.0000010000 0.0000040000 0.0010260000 13019557 96830484 509673472 3.3876020908 4.0233888626 4.0208144188 93 3.6800000000 0.0041152774 0.0034285606 0.0055015511 0.0066699094 0.0047320000 0.0003940000 0.0022130000 0.0000030000 0.0000030000 0.0019870000 13022333 96830484 509673472 3.3826243877 4.0225024223 4.0174145699 94 3.7200000000 0.0040466669 0.0034351362 0.0055015511 0.0066420579 0.0041240000 0.0003930000 0.0025680000 0.0000010000 0.0000050000 0.0010250000 13025109 96830484 509673472 3.3753571510 4.0200653076 4.0169701576 95 3.7600000000 0.0041561369 0.0034427256 0.0055015511 0.0066274875 0.0041440000 0.0003930000 0.0023270000 0.0000030000 0.0000030000 0.0012860000 13027885 96830484 509673472 3.3624589443 4.0213980675 4.0235280991 96 3.8000000000 0.0040898337 0.0034494663 0.0055015511 0.0065997872 0.0041220000 0.0003940000 0.0025700000 0.0000010000 0.0000030000 0.0010200000 13030661 96830484 509673472 3.3521382809 4.0208730698 4.0231080055 97 3.8400000000 0.0042554373 0.0034577753 0.0055015511 0.0065660211 0.0048470000 0.0003940000 0.0023240000 0.0000030000 0.0000030000 0.0019870000 13033437 96830484 509673472 3.3468508720 4.0181565285 4.0250062943 98 3.8800000000 0.0042275456 0.0034656301 0.0055015511 0.0065406138 0.0037760000 0.0003940000 0.0022140000 0.0000000000 0.0000040000 0.0010270000 13036213 96830484 509673472 3.3322305679 4.0175251961 4.0290789604 99 3.9200000000 0.0043088249 0.0034741472 0.0055015511 0.0065134503 0.0041410000 0.0003940000 0.0023130000 0.0000030000 0.0000030000 0.0012900000 13038989 96830484 509673472 3.3268020153 4.0189337730 4.0322198868 100 3.9600000000 0.0044690496 0.0034840963 0.0055015511 0.0064807935 0.0037780000 0.0003920000 0.0022180000 0.0000010000 0.0000070000 0.0010260000 13041765 96830484 509673472 3.3189003468 4.0183334351 4.0362596512 101 4.0000000000 0.0041833599 0.0034910197 0.0055015511 0.0064511219 0.0054370000 0.0003940000 0.0029130000 0.0000040000 0.0000030000 0.0019870000 13044541 96830484 509673472 3.3098387718 4.0166215897 4.0422787666 102 4.0400000000 0.0041824323 0.0034977982 0.0055015511 0.0064307220 0.0037790000 0.0003910000 0.0022190000 0.0000010000 0.0000040000 0.0010260000 13047317 96830484 509673472 3.3061685562 4.0152349472 4.0438976288 103 4.0800000000 0.0041300105 0.0035039362 0.0055015511 0.0064001433 0.0040330000 0.0003930000 0.0022130000 0.0000030000 0.0000030000 0.0012840000 13050093 96830484 509673472 3.2954182625 4.0147414207 4.0505309105 104 4.1200000000 0.0043187356 0.0035117708 0.0055015511 0.0063752011 0.0037680000 0.0003930000 0.0022130000 0.0000000000 0.0000030000 0.0010210000 13052869 96830484 509673472 3.2830889225 4.0128827095 4.0633401871 105 4.1600000000 0.0042486768 0.0035187890 0.0055015511 0.0063732640 0.0047450000 0.0003910000 0.0021960000 0.0000030000 0.0000030000 0.0020100000 13055645 96830484 509673472 3.2800836563 4.0127511024 4.0651054382 106 4.2000000000 0.0043454953 0.0035265881 0.0055015511 0.0063829235 0.0042620000 0.0003920000 0.0026880000 0.0000010000 0.0000030000 0.0010370000 13058421 96830484 509673472 3.2739670277 4.0132446289 4.0701570511 107 4.2400000000 0.0044658165 0.0035353659 0.0055015511 0.0063664244 0.0040510000 0.0003940000 0.0022120000 0.0000030000 0.0000030000 0.0012980000 13061197 96830484 509673472 3.2737631798 4.0100226402 4.0664796829 108 4.2800000000 0.0041308873 0.0035408800 0.0055015511 0.0063377503 0.0039050000 0.0003910000 0.0023460000 0.0000000000 0.0000040000 0.0010180000 13063973 96830484 509673472 3.2635629177 4.0090346336 4.0749340057 109 4.3200000000 0.0042456407 0.0035473457 0.0055015511 0.0063187262 0.0051170000 0.0003940000 0.0025860000 0.0000030000 0.0000030000 0.0019840000 13066749 96830484 509673472 3.2618083954 4.0092091560 4.0760202408 110 4.3600000000 0.0047162338 0.0035579720 0.0055015511 0.0063306059 0.0038230000 0.0003920000 0.0022470000 0.0000000000 0.0000030000 0.0010330000 13069525 96830484 509673472 3.2547655106 4.0085163116 4.0843892097 111 4.4000000000 0.0043509034 0.0035651155 0.0055015511 0.0063284376 0.0040710000 0.0003910000 0.0022320000 0.0000030000 0.0000030000 0.0012930000 13072301 96830484 509673472 3.2477705479 4.0073041916 4.0910844803 112 4.4400000000 0.0043603014 0.0035722154 0.0055015511 0.0063294915 0.0039490000 0.0003920000 0.0023650000 0.0000010000 0.0000040000 0.0010340000 13075077 96830484 509673472 3.2398099899 4.0079455376 4.0989503860 113 4.4800000000 0.0044167275 0.0035796889 0.0055015511 0.0063361432 0.0047560000 0.0003910000 0.0022290000 0.0000040000 0.0000030000 0.0019790000 13077853 96830484 509673472 3.2356553078 4.0078215599 4.1031556129 114 4.5200000000 0.0044326698 0.0035871712 0.0055015511 0.0063829178 0.0041900000 0.0003930000 0.0026170000 0.0000010000 0.0000030000 0.0010250000 13080629 96830484 509673472 3.2248802185 4.0076951981 4.1154427528 115 4.5600000000 0.0044092713 0.0035943199 0.0055015511 0.0064050644 0.0040770000 0.0003910000 0.0022360000 0.0000030000 0.0000020000 0.0012930000 13083405 96830484 509673472 3.2241582870 4.0075912476 4.1172785759 116 4.6000000000 0.0044552204 0.0036017415 0.0055015511 0.0064461014 0.0039550000 0.0003930000 0.0023680000 0.0000000000 0.0000030000 0.0010330000 13086181 96830484 509673472 3.2137994766 4.0102262497 4.1293282509 117 4.6400000000 0.0045301323 0.0036096764 0.0055015511 0.0064536201 0.0044120000 0.0003920000 0.0018620000 0.0000030000 0.0000030000 0.0019960000 13088957 96830484 509673472 3.2062170506 4.0131716728 4.1397786140 118 4.6800000000 0.0044905161 0.0036171412 0.0055015511 0.0064264189 0.0039240000 0.0003930000 0.0023400000 0.0000000000 0.0000030000 0.0010310000 13091733 96830484 509673472 3.2005338669 4.0115981102 4.1439752579 119 4.7200000000 0.0043853414 0.0036235966 0.0055015511 0.0064043524 0.0040820000 0.0003930000 0.0022210000 0.0000030000 0.0000030000 0.0013040000 13094509 96830484 509673472 3.1941065788 4.0111169815 4.1509766579 120 4.7600000000 0.0043745786 0.0036298548 0.0055015511 0.0063796496 0.0059780000 0.0003910000 0.0043870000 0.0000010000 0.0000030000 0.0010380000 13097285 96830484 509673472 3.1872184277 4.0124707222 4.1592063904 121 4.8000000000 0.0042411303 0.0036349067 0.0055015511 0.0063623810 0.0054910000 0.0003920000 0.0029370000 0.0000040000 0.0000030000 0.0019970000 13100061 96830484 509673472 3.1777899265 4.0119318962 4.1769351959 122 4.8400000000 0.0043888805 0.0036410868 0.0055015511 0.0063399567 0.0038120000 0.0003920000 0.0022190000 0.0000000000 0.0000030000 0.0010360000 13102837 96830484 509673472 3.1763195992 4.0134382248 4.1777811050 123 4.8800000000 0.0044055404 0.0036473019 0.0055015511 0.0063178094 0.0045470000 0.0003910000 0.0026930000 0.0000030000 0.0000030000 0.0012920000 13105613 96830484 509673472 3.1706607342 4.0176057816 4.1841592789 124 4.9200000000 0.0046009091 0.0036549922 0.0055015511 0.0062978287 0.0042880000 0.0003910000 0.0026940000 0.0000010000 0.0000030000 0.0010320000 13108389 96830484 509673472 3.1615464687 4.0185523033 4.2000665665 125 4.9600000000 0.0045762532 0.0036623623 0.0055015511 0.0062877022 0.0048750000 0.0003930000 0.0023230000 0.0000030000 0.0000030000 0.0019860000 13111165 96830484 509673472 3.1571626663 4.0183296204 4.2050652504 126 5.0000000000 0.0043872287 0.0036681152 0.0055015511 0.0062683559 0.0041830000 0.0003920000 0.0025920000 0.0000010000 0.0000030000 0.0010270000 13113941 96830484 509673472 3.1521556377 4.0194320679 4.2123508453 127 5.0400000000 0.0045894142 0.0036753696 0.0055015511 0.0062440999 0.0040900000 0.0003910000 0.0022160000 0.0000030000 0.0000030000 0.0013070000 13116717 96830484 509673472 3.1428625584 4.0204434395 4.2293457985 128 5.0800000000 0.0045449371 0.0036821631 0.0055015511 0.0062215730 0.0039330000 0.0003920000 0.0023310000 0.0000000000 0.0000030000 0.0010350000 13119493 96830484 509673472 3.1373460293 4.0202531815 4.2351269722 129 5.1200000000 0.0045419862 0.0036888284 0.0055015511 0.0061986321 0.0048970000 0.0003920000 0.0023250000 0.0000030000 0.0000020000 0.0019970000 13134557 96830484 509673472 3.1333973408 4.0206022263 4.2417912483 130 5.1600000000 0.0044211829 0.0036944619 0.0055015511 0.0061938690 0.0041780000 0.0003950000 0.0025710000 0.0000000000 0.0000040000 0.0010330000 13162933 96830484 509673472 3.1246552467 4.0203957558 4.2597913742 131 5.2000000000 0.0045658811 0.0037011139 0.0055015511 0.0062249239 0.0042070000 0.0003930000 0.0023260000 0.0000030000 0.0000030000 0.0013060000 13165709 96830484 509673472 3.1212174892 4.0209646225 4.2639012337 132 5.2400000000 0.0045076851 0.0037072243 0.0055015511 0.0062369436 0.0039370000 0.0003910000 0.0023280000 0.0000000000 0.0000040000 0.0010350000 13168485 96830484 509673472 3.1207387447 4.0206923485 4.2615709305 133 5.2800000000 0.0044369483 0.0037127109 0.0055015511 0.0062368092 0.0049100000 0.0003930000 0.0023320000 0.0000030000 0.0000030000 0.0020010000 13171261 96830484 509673472 3.1103410721 4.0208978653 4.2806963921 134 5.3200000000 0.0049509592 0.0037219516 0.0055015511 0.0062691717 0.0038180000 0.0003930000 0.0022060000 0.0000010000 0.0000030000 0.0010360000 13174037 96830484 509673472 3.1018047333 4.0237231255 4.2973408699 135 5.3600000000 0.0050950567 0.0037321227 0.0055015511 0.0062898416 0.0040950000 0.0003920000 0.0022020000 0.0000030000 0.0000030000 0.0013120000 13176813 96830484 509673472 3.0986595154 4.0242085457 4.3013195992 136 5.4000000000 0.0052635367 0.0037433831 0.0055015511 0.0063267739 0.0039380000 0.0003910000 0.0023290000 0.0000000000 0.0000030000 0.0010310000 13179589 96830484 509673472 3.0919308662 4.0243411064 4.3133587837 137 5.4400000000 0.0052027917 0.0037540358 0.0055015511 0.0063797597 0.0049160000 0.0003930000 0.0023270000 0.0000030000 0.0000030000 0.0020070000 13182365 96830484 509673472 3.0865361691 4.0247192383 4.3225984573 138 5.4800000000 0.0052038999 0.0037645420 0.0055015511 0.0064223031 0.0038300000 0.0003920000 0.0022130000 0.0000000000 0.0000030000 0.0010360000 13185141 96830484 509673472 3.0809524059 4.0238685608 4.3272933960 139 5.5200000000 0.0050571710 0.0037738415 0.0055015511 0.0064647493 0.0041180000 0.0003910000 0.0022120000 0.0000020000 0.0000030000 0.0013230000 13187917 96830484 509673472 3.0748412609 4.0217156410 4.3324899673 140 5.5600000000 0.0050816773 0.0037831832 0.0055015511 0.0065367526 0.0039420000 0.0003900000 0.0023260000 0.0000000000 0.0000030000 0.0010350000 13190693 96830484 509673472 3.0655717850 4.0224575996 4.3467669487 141 5.6000000000 0.0050855028 0.0037924195 0.0055015511 0.0065705596 0.0047960000 0.0003920000 0.0022070000 0.0000030000 0.0000030000 0.0020000000 13193469 96830484 509673472 3.0601952076 4.0236697197 4.3522353172 142 5.6400000000 0.0051267003 0.0038018159 0.0055015511 0.0066051338 0.0036060000 0.0003950000 0.0019730000 0.0000010000 0.0000030000 0.0010440000 13196245 96830484 509673472 3.0509710312 4.0237722397 4.3669514656 143 5.6800000000 0.0051577762 0.0038112981 0.0055015511 0.0066816661 0.0047600000 0.0003920000 0.0022190000 0.0000030000 0.0000030000 0.0019180000 13199021 96830484 509673472 3.0457365513 4.0260252953 4.3769559860 144 5.7200000000 0.0052310433 0.0038211574 0.0055015511 0.0067255132 0.0039730000 0.0004040000 0.0023080000 0.0000010000 0.0000040000 0.0010540000 13201797 96830484 509673472 3.0395276546 4.0277652740 4.3848271370 145 5.7600000000 0.0052077551 0.0038307202 0.0055015511 0.0067255252 0.0048450000 0.0003950000 0.0022290000 0.0000030000 0.0000030000 0.0020160000 13204573 96830484 509673472 3.0339641571 4.0268282890 4.3915762901 146 5.8000000000 0.0052451137 0.0038404078 0.0055015511 0.0067167888 0.0039860000 0.0003920000 0.0023450000 0.0000010000 0.0000030000 0.0010460000 13207349 96830484 509673472 3.0281231403 4.0269808769 4.4010467529 147 5.8400000000 0.0052808914 0.0038502070 0.0055015511 0.0067002993 0.0041700000 0.0003920000 0.0022210000 0.0000030000 0.0000030000 0.0013530000 13210125 96830484 509673472 3.0179359913 4.0262284279 4.4219789505 148 5.8800000000 0.0053074518 0.0038600533 0.0055015511 0.0066797245 0.0039890000 0.0003910000 0.0023440000 0.0000000000 0.0000040000 0.0010510000 13212901 96830484 509673472 3.0165126324 4.0261392593 4.4253592491 149 5.9200000000 0.0052760998 0.0038695569 0.0055015511 0.0066631086 0.0048360000 0.0003920000 0.0022190000 0.0000030000 0.0000030000 0.0020200000 13215677 96830484 509673472 3.0121576786 4.0268230438 4.4364209175 150 5.9600000000 0.0053268955 0.0038792725 0.0055015511 0.0066447321 0.0040010000 0.0003940000 0.0023430000 0.0000000000 0.0000040000 0.0010600000 13218453 96830484 509673472 3.0085952282 4.0266041756 4.4451346397 151 6.0000000000 0.0053692479 0.0038891399 0.0055015511 0.0066261101 0.0041790000 0.0003920000 0.0022410000 0.0000040000 0.0000030000 0.0013400000 13221229 96830484 509673472 3.0052974224 4.0271205902 4.4548664093 152 6.0400000000 0.0053455778 0.0038987217 0.0055015511 0.0066126065 0.0038830000 0.0003930000 0.0022280000 0.0000000000 0.0000040000 0.0010550000 13224005 96830484 509673472 3.0021955967 4.0284247398 4.4656457901 153 6.0800000000 0.0054274574 0.0039087135 0.0055015511 0.0066018790 0.0047600000 0.0003920000 0.0021060000 0.0000030000 0.0000030000 0.0020530000 13226781 96830484 509673472 2.9985527992 4.0274677277 4.4742336273 154 6.1200000000 0.0053975401 0.0039183812 0.0055015511 0.0066206748 0.0036320000 0.0003910000 0.0019750000 0.0000000000 0.0000030000 0.0010600000 13229557 96830484 509673472 2.9940743446 4.0267791748 4.4865503311 155 6.1600000000 0.0053812792 0.0039278192 0.0055015511 0.0066840132 0.0042750000 0.0003930000 0.0023310000 0.0000030000 0.0000030000 0.0013380000 13232333 96830484 509673472 2.9924228191 4.0258522034 4.4941554070 156 6.2000000000 0.0053935330 0.0039372148 0.0055015511 0.0067957865 0.0042590000 0.0003910000 0.0025910000 0.0000010000 0.0000030000 0.0010680000 13235109 96830484 509673472 2.9877269268 4.0269794464 4.5091171265 157 6.2400000000 0.0054101413 0.0039465965 0.0055015511 0.0068866472 0.0049840000 0.0003910000 0.0023360000 0.0000030000 0.0000030000 0.0020450000 13237885 96830484 509673472 2.9854710102 4.0275936127 4.5200409889 158 6.2800000000 0.0054019168 0.0039558074 0.0055015511 0.0069635139 0.0040260000 0.0003920000 0.0023480000 0.0000000000 0.0000030000 0.0010730000 13240661 96830484 509673472 2.9824733734 4.0278787613 4.5365486145 159 6.3200000000 0.0054337368 0.0039651026 0.0055015511 0.0069939671 0.0040770000 0.0003930000 0.0021080000 0.0000030000 0.0000030000 0.0013600000 13243437 96830484 509673472 2.9819092751 4.0272893906 4.5442638397 160 6.3600000000 0.0054282551 0.0039742473 0.0055015511 0.0070316601 0.0039110000 0.0003920000 0.0022310000 0.0000000000 0.0000030000 0.0010730000 13246213 96830484 509673472 2.9807803631 4.0286645889 4.5597090721 161 6.4000000000 0.0055286461 0.0039839019 0.0055286461 0.0070169335 0.0048710000 0.0003910000 0.0022160000 0.0000030000 0.0000040000 0.0020430000 13248989 96830484 509673472 2.9809012413 4.0291776657 4.5705718994 162 6.4400000000 0.0056188568 0.0039939942 0.0056188568 0.0069973589 0.0040180000 0.0003920000 0.0023380000 0.0000000000 0.0000030000 0.0010720000 13251765 96830484 509673472 2.9807972908 4.0274944305 4.5817489624 163 6.4800000000 0.0055624577 0.0040036167 0.0056188568 0.0069805798 0.0042060000 0.0003920000 0.0022120000 0.0000030000 0.0000020000 0.0013790000 13254541 96830484 509673472 2.9798259735 4.0287628174 4.5947461128 164 6.5200000000 0.0055745235 0.0040131954 0.0056188568 0.0069641183 0.0041570000 0.0003920000 0.0024660000 0.0000000000 0.0000030000 0.0010790000 13257317 96830484 509673472 2.9797205925 4.0301423073 4.6065702438 165 6.5600000000 0.0056312690 0.0040230019 0.0056312690 0.0069546300 0.0048990000 0.0003940000 0.0022230000 0.0000030000 0.0000030000 0.0020570000 13260093 96830484 509673472 2.9786863327 4.0314221382 4.6245646477 166 6.6000000000 0.0056379130 0.0040327303 0.0056379130 0.0069716502 0.0039220000 0.0003930000 0.0022210000 0.0000010000 0.0000040000 0.0010840000 13262869 96830484 509673472 2.9794631004 4.0321283340 4.6358709335 167 6.6400000000 0.0056015439 0.0040421244 0.0056379130 0.0069789813 0.0042060000 0.0003910000 0.0022150000 0.0000030000 0.0000030000 0.0013720000 13265645 96830484 509673472 2.9805140495 4.0339975357 4.6462459564 168 6.6800000000 0.0056427028 0.0040516516 0.0056427028 0.0069812043 0.0039610000 0.0003930000 0.0022190000 0.0000000000 0.0000040000 0.0010930000 13268421 96830484 509673472 2.9810287952 4.0342435837 4.6586809158 169 6.7200000000 0.0056608310 0.0040611734 0.0056608310 0.0069677157 0.0054490000 0.0003950000 0.0027170000 0.0000040000 0.0000040000 0.0020750000 13271197 96830484 509673472 2.9810914993 4.0320711136 4.6730828285 170 6.7600000000 0.0056843879 0.0040707217 0.0056843879 0.0069597897 0.0039960000 0.0003950000 0.0022410000 0.0000010000 0.0000040000 0.0010990000 13273973 96830484 509673472 2.9791998863 4.0341596603 4.6901674271 171 6.8000000000 0.0056571336 0.0040799990 0.0056843879 0.0069530611 0.0042900000 0.0003980000 0.0022400000 0.0000040000 0.0000040000 0.0013850000 13276749 96830484 509673472 2.9802639484 4.0368928909 4.6993741989 172 6.8400000000 0.0057266806 0.0040895727 0.0057266806 0.0069348196 0.0040000000 0.0003980000 0.0022400000 0.0000010000 0.0000040000 0.0010970000 13279525 96830484 509673472 2.9807951450 4.0381984711 4.7123975754 173 6.8800000000 0.0057206945 0.0040990012 0.0057266806 0.0069156234 0.0054490000 0.0003990000 0.0027070000 0.0000040000 0.0000040000 0.0020710000 13282301 96830484 509673472 2.9804234505 4.0398039818 4.7263231277 174 6.9200000000 0.0057963300 0.0041087559 0.0057963300 0.0068962113 0.0039940000 0.0003970000 0.0022310000 0.0000000000 0.0000030000 0.0010970000 13285077 96830484 509673472 2.9793746471 4.0416250229 4.7389674187 175 6.9600000000 0.0057795374 0.0041183033 0.0057963300 0.0068764325 0.0043000000 0.0003980000 0.0022280000 0.0000040000 0.0000030000 0.0013980000 13287853 96830484 509673472 2.9798502922 4.0425524712 4.7507953644 176 7.0000000000 0.0058102859 0.0041279168 0.0058102859 0.0068606964 0.0037480000 0.0003970000 0.0019930000 0.0000010000 0.0000040000 0.0010880000 13290629 96830484 509673472 2.9785783291 4.0429191589 4.7653398514 177 7.0400000000 0.0058318935 0.0041375438 0.0058318935 0.0068712717 0.0049770000 0.0003970000 0.0022400000 0.0000040000 0.0000040000 0.0020640000 13293405 96830484 509673472 2.9796292782 4.0405187607 4.7724251747 178 7.0800000000 0.0058777933 0.0041473205 0.0058777933 0.0068570921 0.0036280000 0.0003970000 0.0018740000 0.0000010000 0.0000040000 0.0010820000 13296181 96830484 509673472 2.9808826447 4.0401020050 4.7797036171 179 7.1200000000 0.0057799108 0.0041564411 0.0058777933 0.0068430768 0.0043130000 0.0003980000 0.0022470000 0.0000040000 0.0000040000 0.0013910000 13298957 96830484 509673472 2.9810791016 4.0424814224 4.7933559418 180 7.1600000000 0.0058091911 0.0041656230 0.0058777933 0.0068247817 0.0040110000 0.0003990000 0.0022470000 0.0000010000 0.0000040000 0.0010890000 13301733 96830484 509673472 2.9818780422 4.0449323654 4.8063964844 181 7.2000000000 0.0058111027 0.0041747141 0.0058777933 0.0068100599 0.0046170000 0.0003960000 0.0018790000 0.0000040000 0.0000040000 0.0020620000 13304509 96830484 509673472 2.9840197563 4.0455880165 4.8172211647 182 7.2400000000 0.0058332621 0.0041838270 0.0058777933 0.0067932005 0.0037650000 0.0003960000 0.0019990000 0.0000010000 0.0000050000 0.0010870000 13307285 96830484 509673472 2.9836959839 4.0458641052 4.8311939240 183 7.2800000000 0.0058430680 0.0041928939 0.0058777933 0.0067780830 0.0044150000 0.0003960000 0.0023530000 0.0000030000 0.0000040000 0.0013840000 13310061 96830484 509673472 2.9820084572 4.0464444160 4.8473682404 184 7.3200000000 0.0058487826 0.0042018933 0.0058777933 0.0067601524 0.0041270000 0.0003980000 0.0023580000 0.0000000000 0.0000040000 0.0010890000 13312837 96830484 509673472 2.9841961861 4.0460104942 4.8579773903 185 7.3600000000 0.0058368095 0.0042107307 0.0058777933 0.0067444853 0.0050180000 0.0003970000 0.0022420000 0.0000040000 0.0000030000 0.0020900000 13315613 96830484 509673472 2.9857387543 4.0463008881 4.8733549118 186 7.4000000000 0.0057915095 0.0042192295 0.0058777933 0.0067320655 0.0040350000 0.0003970000 0.0022570000 0.0000000000 0.0000050000 0.0010920000 13318389 96830484 509673472 2.9855985641 4.0459337234 4.8914747238 187 7.4400000000 0.0057636858 0.0042274886 0.0058777933 0.0067256439 0.0048010000 0.0003970000 0.0027110000 0.0000040000 0.0000030000 0.0014030000 13321165 96830484 509673472 2.9887242317 4.0459308624 4.8998761177 188 7.4800000000 0.0057792170 0.0042357425 0.0058777933 0.0067341239 0.0040320000 0.0003970000 0.0022430000 0.0000010000 0.0000040000 0.0011010000 13323941 96830484 509673472 2.9911038876 4.0494847298 4.9153175354 189 7.5200000000 0.0057374379 0.0042436879 0.0058777933 0.0067179987 0.0046400000 0.0003960000 0.0018690000 0.0000040000 0.0000040000 0.0020810000 13326717 96830484 509673472 2.9932599068 4.0521392822 4.9329338074 190 7.5600000000 0.0058082659 0.0042519226 0.0058777933 0.0067079569 0.0040260000 0.0003970000 0.0022340000 0.0000010000 0.0000050000 0.0011030000 13329493 96830484 509673472 2.9955294132 4.0511288643 4.9477066994 191 7.6000000000 0.0058088265 0.0042600739 0.0058777933 0.0066962684 0.0043290000 0.0003970000 0.0022330000 0.0000040000 0.0000030000 0.0014040000 13332269 96830484 509673472 2.9968359470 4.0533871651 4.9640116692 192 7.6400000000 0.0059125400 0.0042686805 0.0059125400 0.0066890655 0.0040310000 0.0003960000 0.0022250000 0.0000010000 0.0000040000 0.0011120000 13335045 96830484 509673472 3.0005047321 4.0595703125 4.9790940285 193 7.6800000000 0.0059914929 0.0042776070 0.0059914929 0.0066904874 0.0053790000 0.0003990000 0.0025980000 0.0000040000 0.0000040000 0.0020830000 13337821 96830484 509673472 3.0005235672 4.0601081848 4.9973883629 194 7.7200000000 0.0061021987 0.0042870121 0.0061021987 0.0066878278 0.0040360000 0.0004000000 0.0022320000 0.0000010000 0.0000040000 0.0011070000 13340597 96830484 509673472 3.0002632141 4.0561037064 5.0136933327 195 7.7600000000 0.0060857469 0.0042962364 0.0061021987 0.0066909870 0.0039690000 0.0003980000 0.0018740000 0.0000050000 0.0000040000 0.0013960000 13343373 96830484 509673472 3.0014877319 4.0556716919 5.0267190933 196 7.8000000000 0.0060643093 0.0043052571 0.0061021987 0.0067278308 0.0040450000 0.0003980000 0.0022320000 0.0000000000 0.0000040000 0.0011150000 13346149 96830484 509673472 3.0033607483 4.0593199730 5.0434827805 197 7.8400000000 0.0061500561 0.0043146216 0.0061500561 0.0067534488 0.0051780000 0.0003970000 0.0023470000 0.0000040000 0.0000040000 0.0021300000 13348925 96830484 509673472 3.0052099228 4.0627899170 5.0555558205 198 7.8800000000 0.0060171690 0.0043232203 0.0061500561 0.0067713834 0.0039320000 0.0003990000 0.0021170000 0.0000000000 0.0000040000 0.0011140000 13351701 96830484 509673472 3.0063338280 4.0664367676 5.0721011162 199 7.9200000000 0.0060552228 0.0043319239 0.0061500561 0.0067645900 0.0043620000 0.0003970000 0.0022230000 0.0000040000 0.0000040000 0.0014300000 13354477 96830484 509673472 3.0084040165 4.0674023628 5.0879073143 200 7.9600000000 0.0062433127 0.0043414808 0.0062433127 0.0067552328 0.0040640000 0.0003980000 0.0022310000 0.0000010000 0.0000040000 0.0011280000 13357253 96830484 509673472 3.0085837841 4.0659961700 5.1019749641 201 8.0000000000 0.0061993464 0.0043507239 0.0062433127 0.0067705383 0.0050590000 0.0003980000 0.0022210000 0.0000040000 0.0000040000 0.0021280000 13360029 96830484 509673472 3.0092198849 4.0664038658 5.1206936836 202 8.0400000000 0.0061744615 0.0043597523 0.0062433127 0.0067876655 0.0041860000 0.0003970000 0.0023440000 0.0000000000 0.0000040000 0.0011350000 13362805 96830484 509673472 3.0120339394 4.0673012733 5.1309661865 203 8.0800000000 0.0062667690 0.0043691465 0.0062667690 0.0067971930 0.0043760000 0.0003970000 0.0022220000 0.0000040000 0.0000030000 0.0014440000 13365581 96830484 509673472 3.0143363476 4.0690822601 5.1484045982 204 8.1200000000 0.0061378600 0.0043778167 0.0062667690 0.0067893842 0.0040850000 0.0003980000 0.0022340000 0.0000000000 0.0000040000 0.0011370000 13368357 96830484 509673472 3.0162239075 4.0684924126 5.1606812477 205 8.1600000000 0.0062076291 0.0043867426 0.0062667690 0.0067815234 0.0050950000 0.0003980000 0.0022300000 0.0000040000 0.0000030000 0.0021500000 13371133 96830484 509673472 3.0191428661 4.0674738884 5.1724519730 206 8.1999999990 0.0062210215 0.0043956468 0.0062667690 0.0067722635 0.0044410000 0.0003970000 0.0025870000 0.0000000000 0.0000040000 0.0011420000 13373909 96830484 509673472 3.0225040913 4.0675692558 5.1859960556 207 8.2400000000 0.0062034870 0.0044043804 0.0062667690 0.0067650326 0.0043890000 0.0003970000 0.0022290000 0.0000040000 0.0000030000 0.0014410000 13376685 96830484 509673472 3.0270359516 4.0703945160 5.1995906830 208 8.2799999990 0.0061653703 0.0044128467 0.0062667690 0.0067523339 0.0040770000 0.0003970000 0.0022290000 0.0000010000 0.0000040000 0.0011300000 13379461 96830484 509673472 3.0312514305 4.0725197792 5.2121906281 209 8.3200000000 0.0062722573 0.0044217434 0.0062722573 0.0067497083 0.0047390000 0.0003980000 0.0018660000 0.0000040000 0.0000030000 0.0021530000 13382237 96830484 509673472 3.0358080864 4.0743994713 5.2252998352 210 8.3599999990 0.0062816082 0.0044305999 0.0062816082 0.0067736492 0.0042060000 0.0003980000 0.0023460000 0.0000010000 0.0000040000 0.0011390000 13385013 96830484 509673472 3.0414373875 4.0752453804 5.2363162041 211 8.4000000000 0.0063410904 0.0044396543 0.0063410904 0.0067933879 0.0043960000 0.0003960000 0.0022200000 0.0000040000 0.0000040000 0.0014520000 13387789 96830484 509673472 3.0464916229 4.0734281540 5.2500743866 212 8.4399999990 0.0063801347 0.0044488075 0.0063801347 0.0067795258 0.0038490000 0.0003970000 0.0019880000 0.0000000000 0.0000040000 0.0011380000 13390565 96830484 509673472 3.0537750721 4.0763788223 5.2616963387 213 8.4800000000 0.0064225332 0.0044580739 0.0064225332 0.0067811308 0.0052210000 0.0003980000 0.0023330000 0.0000030000 0.0000030000 0.0021580000 13393341 96830484 509673472 3.0602052212 4.0803074837 5.2761926651 214 8.5200000000 0.0064715529 0.0044674826 0.0064715529 0.0068439794 0.0040930000 0.0003980000 0.0022150000 0.0000000000 0.0000040000 0.0011510000 13396117 96830484 509673472 3.0672638416 4.0806159973 5.2883310318 215 8.5600000000 0.0064998376 0.0044769354 0.0064998376 0.0068534144 0.0045250000 0.0003960000 0.0023240000 0.0000040000 0.0000030000 0.0014750000 13398893 96830484 509673472 3.0751450062 4.0799407959 5.2988371849 216 8.6000000000 0.0065783253 0.0044866641 0.0065783253 0.0068386360 0.0040870000 0.0003970000 0.0022080000 0.0000010000 0.0000040000 0.0011510000 13401669 96830484 509673472 3.0844509602 4.0844588280 5.3104386330 217 8.6400000000 0.0067020943 0.0044968735 0.0067020943 0.0068625340 0.0051270000 0.0003970000 0.0022180000 0.0000040000 0.0000040000 0.0021750000 13404445 96830484 509673472 3.0934443474 4.0874881744 5.3273048401 218 8.6800000000 0.0065605817 0.0045063400 0.0067020943 0.0069131246 0.0040910000 0.0003970000 0.0022050000 0.0000000000 0.0000040000 0.0011540000 13407221 96830484 509673472 3.1018726826 4.0872259140 5.3363728523 219 8.7200000000 0.0067113610 0.0045164086 0.0067113610 0.0069131941 0.0044200000 0.0003980000 0.0022000000 0.0000040000 0.0000040000 0.0014830000 13409997 96830484 509673472 3.1120402813 4.0900874138 5.3467040062 220 8.7600000000 0.0068521942 0.0045270258 0.0068521942 0.0069164090 0.0040990000 0.0003980000 0.0022000000 0.0000000000 0.0000040000 0.0011640000 13412773 96830484 509673472 3.1226286888 4.0950989723 5.3584675789 221 8.8000000000 0.0067516076 0.0045370918 0.0068521942 0.0069538586 0.0051480000 0.0003950000 0.0021880000 0.0000040000 0.0000040000 0.0022200000 13415549 96830484 509673472 3.1322836876 4.0962281227 5.3702397346 222 8.8400000000 0.0069169519 0.0045478119 0.0069169519 0.0069623779 0.0037640000 0.0003970000 0.0018420000 0.0000010000 0.0000040000 0.0011810000 13418325 96830484 509673472 3.1415848732 4.0980639458 5.3847823143 223 8.8800000000 0.0069196904 0.0045584481 0.0069196904 0.0069631454 0.0044250000 0.0003970000 0.0021840000 0.0000040000 0.0000040000 0.0014990000 13421101 96830484 509673472 3.1522419453 4.1012020111 5.3941621780 224 8.9200000000 0.0068647834 0.0045687442 0.0069196904 0.0069690171 0.0041180000 0.0003980000 0.0021970000 0.0000000000 0.0000040000 0.0011790000 13423877 96830484 509673472 3.1629633904 4.1042346954 5.4047870636 225 8.9600000000 0.0068980544 0.0045790967 0.0069196904 0.0069663535 0.0051600000 0.0003960000 0.0021950000 0.0000040000 0.0000040000 0.0022220000 13426653 96830484 509673472 3.1734352112 4.1069211960 5.4128260612 226 9.0000000000 0.0072254403 0.0045908062 0.0072254403 0.0069527532 0.0041320000 0.0004000000 0.0021880000 0.0000000000 0.0000040000 0.0011930000 13429429 96830484 509673472 3.1838812828 4.1111669540 5.4244599342 227 9.0400000000 0.0070937173 0.0046018323 0.0072254403 0.0069389750 0.0047840000 0.0004420000 0.0024170000 0.0000040000 0.0000040000 0.0015310000 13432205 96830484 509673472 3.1958563328 4.1170096397 5.4328417778 228 9.0800000000 0.0072643943 0.0046135102 0.0072643943 0.0069502678 0.0040950000 0.0004040000 0.0021750000 0.0000000000 0.0000040000 0.0011990000 13434981 96830484 509673472 3.2074055672 4.1230902672 5.4463391304 229 9.1200000000 0.0072253821 0.0046249157 0.0072643943 0.0070096127 0.0052160000 0.0003970000 0.0022830000 0.0000030000 0.0000030000 0.0022200000 13437757 96830484 509673472 3.2179820538 4.1271700859 5.4537768364 230 9.1600000000 0.0072599859 0.0046363725 0.0072643943 0.0071109560 0.0042050000 0.0003960000 0.0022940000 0.0000010000 0.0000030000 0.0012010000 13440533 96830484 509673472 3.2288749218 4.1312575340 5.4606409073 231 9.2000000000 0.0071143950 0.0046470999 0.0072643943 0.0073238445 0.0040430000 0.0003960000 0.0018280000 0.0000030000 0.0000030000 0.0015040000 13443309 96830484 509673472 3.2381241322 4.1320676804 5.4680809975 232 9.2400000000 0.0072366716 0.0046582619 0.0072643943 0.0074886121 0.0041060000 0.0003940000 0.0022030000 0.0000000000 0.0000040000 0.0011960000 13446085 96830484 509673472 3.2476441860 4.1351461411 5.4764394760 233 9.2800000000 0.0071883346 0.0046691205 0.0072643943 0.0076323315 0.0051690000 0.0003950000 0.0022080000 0.0000030000 0.0000030000 0.0022460000 13448861 96830484 509673472 3.2572534084 4.1378970146 5.4837450981 234 9.3200000000 0.0072323345 0.0046800744 0.0072643943 0.0077362816 0.0041220000 0.0003970000 0.0022200000 0.0000000000 0.0000030000 0.0011910000 13451637 96830484 509673472 3.2672071457 4.1416530609 5.4906444550 235 9.3600000000 0.0071960459 0.0046907807 0.0072643943 0.0078134357 0.0044100000 0.0003950000 0.0022040000 0.0000030000 0.0000020000 0.0014910000 13454413 96830484 509673472 3.2773098946 4.1448554993 5.4979395866 236 9.4000000000 0.0073503372 0.0047020500 0.0073503372 0.0078744968 0.0041280000 0.0003940000 0.0022320000 0.0000000000 0.0000030000 0.0011870000 13457189 96830484 509673472 3.2867805958 4.1478281021 5.5063047409 237 9.4400000000 0.0072635226 0.0047128579 0.0073503372 0.0079028136 0.0048150000 0.0003950000 0.0018660000 0.0000030000 0.0000040000 0.0022320000 13459965 96830484 509673472 3.2967557907 4.1517910957 5.5127701759 238 9.4800000000 0.0074485955 0.0047243526 0.0074485955 0.0079248186 0.0041260000 0.0003950000 0.0022260000 0.0000000000 0.0000030000 0.0011810000 13462741 96830484 509673472 3.3076429367 4.1580104828 5.5205726624 239 9.5200000000 0.0073743653 0.0047354405 0.0074485955 0.0079685660 0.0044450000 0.0003940000 0.0022370000 0.0000030000 0.0000030000 0.0014890000 13465517 96830484 509673472 3.3183660507 4.1630940437 5.5281019211 240 9.5600000000 0.0074186162 0.0047466204 0.0074485955 0.0080226047 0.0038010000 0.0003950000 0.0018980000 0.0000000000 0.0000040000 0.0011830000 13468293 96830484 509673472 3.3285760880 4.1679182053 5.5366687775 241 9.6000000000 0.0073739910 0.0047575224 0.0074485955 0.0080773449 0.0054220000 0.0003960000 0.0024290000 0.0000030000 0.0000030000 0.0022680000 13471069 96830484 509673472 3.3378717899 4.1686444283 5.5453929901 242 9.6400000000 0.0072604534 0.0047678651 0.0074485955 0.0080981347 0.0043960000 0.0003960000 0.0024690000 0.0000000000 0.0000030000 0.0012030000 13473845 96830484 509673472 3.3476212025 4.1710424423 5.5539355278 243 9.6800000000 0.0072607538 0.0047781239 0.0074485955 0.0081124943 0.0049980000 0.0003950000 0.0027540000 0.0000030000 0.0000030000 0.0015170000 13476621 96830484 509673472 3.3586022854 4.1770153046 5.5616979599 244 9.7200000000 0.0072714370 0.0047883424 0.0074485955 0.0081594785 0.0044410000 0.0003960000 0.0025310000 0.0000010000 0.0000030000 0.0011860000 13479397 96830484 509673472 3.3698980808 4.1834440231 5.5698738098 245 9.7600000000 0.0071215229 0.0047978656 0.0074485955 0.0082226926 0.0054660000 0.0003980000 0.0025240000 0.0000040000 0.0000030000 0.0022110000 13482173 96830484 509673472 3.3801255226 4.1858167648 5.5777177811 246 9.8000000000 0.0071205953 0.0048073075 0.0074485955 0.0082425213 0.0040510000 0.0003950000 0.0021540000 0.0000000000 0.0000040000 0.0011720000 13484949 96830484 509673472 3.3904662132 4.1886811256 5.5866932869 247 9.8400000000 0.0072004125 0.0048169962 0.0074485955 0.0082476598 0.0047320000 0.0003940000 0.0025290000 0.0000040000 0.0000030000 0.0014750000 13487725 96830484 509673472 3.3999838829 4.1890230179 5.5966734886 248 9.8800000000 0.0072000292 0.0048266052 0.0074485955 0.0082328635 0.0044420000 0.0003960000 0.0025410000 0.0000000000 0.0000040000 0.0011700000 13490501 96830484 509673472 3.4093174934 4.1907835007 5.6051855087 249 9.9200000000 0.0071771718 0.0048360453 0.0074485955 0.0082174428 0.0053750000 0.0003980000 0.0024010000 0.0000040000 0.0000030000 0.0022370000 13493277 96830484 509673472 3.4193496704 4.1930518150 5.6128292084 250 9.9600000000 0.0071918867 0.0048454686 0.0074485955 0.0082012656 0.0039210000 0.0004010000 0.0020140000 0.0000010000 0.0000030000 0.0011710000 13496053 96830484 509673472 3.4290330410 4.1952629089 5.6217751503 251 10.0000000000 0.0072807050 0.0048551708 0.0074485955 0.0081851099 0.0047420000 0.0003950000 0.0025210000 0.0000030000 0.0000020000 0.0014880000 13498829 96830484 509673472 3.4391508102 4.1984252930 5.6305847168 252 10.0400000000 0.0072272238 0.0048645837 0.0074485955 0.0081719316 0.0044490000 0.0003940000 0.0025370000 0.0000000000 0.0000040000 0.0011790000 13501605 96830484 509673472 3.4476833344 4.1974649429 5.6410279274 253 10.0800000000 0.0071757156 0.0048737186 0.0074485955 0.0081566534 0.0073250000 0.0003960000 0.0043360000 0.0000050000 0.0000030000 0.0022500000 13504381 96830484 509673472 3.4552299976 4.1943354607 5.6508445740 254 10.1200000000 0.0072520515 0.0048830821 0.0074485955 0.0081769322 0.0044630000 0.0003970000 0.0025470000 0.0000010000 0.0000030000 0.0011760000 13507157 96830484 509673472 3.4650208950 4.1982078552 5.6597423553 255 10.1600000000 0.0072530629 0.0048923761 0.0074485955 0.0081921115 0.0048140000 0.0003950000 0.0025430000 0.0000030000 0.0000030000 0.0015330000 13509933 96830484 509673472 3.4759025574 4.2050762177 5.6686515808 256 10.2000000000 0.0072717825 0.0049016707 0.0074485955 0.0081795804 0.0039380000 0.0003960000 0.0020230000 0.0000010000 0.0000030000 0.0011810000 13512709 96830484 509673472 3.4870977402 4.2099943161 5.6771063805 257 10.2400000000 0.0072231293 0.0049107036 0.0074485955 0.0081652963 0.0055080000 0.0003960000 0.0025370000 0.0000040000 0.0000030000 0.0022210000 13540061 96830484 509673472 3.4964659214 4.2096490860 5.6859159470 258 10.2800000000 0.0072380486 0.0049197243 0.0074485955 0.0081494397 0.0048700000 0.0003950000 0.0029540000 0.0000010000 0.0000030000 0.0011720000 13594037 96830484 509673472 3.5068166256 4.2147345543 5.6947417259 259 10.3200000000 0.0072607100 0.0049287629 0.0074485955 0.0081436190 0.0047790000 0.0003970000 0.0025410000 0.0000040000 0.0000030000 0.0014880000 13596813 96830484 509673472 3.5172986984 4.2186360359 5.7011475563 260 10.3600000000 0.0072670924 0.0049377565 0.0074485955 0.0081496626 0.0043290000 0.0003970000 0.0024070000 0.0000010000 0.0000030000 0.0011730000 13599589 96830484 509673472 3.5272772312 4.2202401161 5.7093830109 261 10.4000000000 0.0072087119 0.0049464574 0.0074485955 0.0081493713 0.0053830000 0.0003940000 0.0024020000 0.0000030000 0.0000030000 0.0022320000 13602365 96830484 509673472 3.5368404388 4.2197041512 5.7162175179 262 10.4400000000 0.0072257542 0.0049551570 0.0074485955 0.0081369972 0.0044560000 0.0003930000 0.0025290000 0.0000000000 0.0000030000 0.0011770000 13605141 96830484 509673472 3.5463674068 4.2199916840 5.7234263420 263 10.4800000000 0.0071984548 0.0049636867 0.0074485955 0.0081235241 0.0047580000 0.0003990000 0.0025210000 0.0000030000 0.0000030000 0.0014800000 13607917 96830484 509673472 3.5571599007 4.2214097977 5.7290377617 264 10.5200000000 0.0071901456 0.0049721202 0.0074485955 0.0081132666 0.0059870000 0.0003970000 0.0040690000 0.0000010000 0.0000030000 0.0011620000 13610693 96830484 509673472 3.5674726963 4.2210483551 5.7350444794 265 10.5600000000 0.0072379960 0.0049806707 0.0074485955 0.0080981381 0.0054460000 0.0003970000 0.0025150000 0.0000030000 0.0000030000 0.0021770000 13613469 96830484 509673472 3.5787215233 4.2229795456 5.7412075996 266 10.6000000000 0.0071544908 0.0049888430 0.0074485955 0.0080873292 0.0047010000 0.0003980000 0.0027860000 0.0000010000 0.0000030000 0.0011570000 13616245 96830484 509673472 3.5907096863 4.2252111435 5.7455229759 267 10.6400000000 0.0071788444 0.0049970452 0.0074485955 0.0080836528 0.0047550000 0.0003970000 0.0025260000 0.0000030000 0.0000030000 0.0014690000 13619021 96830484 509673472 3.6019752026 4.2243146896 5.7495560646 268 10.6800000000 0.0072043259 0.0050052814 0.0074485955 0.0080768860 0.0048120000 0.0003960000 0.0029050000 0.0000000000 0.0000030000 0.0011460000 13621797 96830484 509673472 3.6133160591 4.2237768173 5.7556066513 269 10.7200000000 0.0071599754 0.0050132914 0.0074485955 0.0080659244 0.0053370000 0.0003930000 0.0024020000 0.0000030000 0.0000030000 0.0021730000 13624573 96830484 509673472 3.6252140999 4.2235774994 5.7579569817 270 10.7600000000 0.0071546678 0.0050212224 0.0074485955 0.0080566415 0.0043160000 0.0003950000 0.0024020000 0.0000000000 0.0000040000 0.0011480000 13627349 96830484 509673472 3.6506152153 4.2283115387 5.7682752609 271 10.8000000000 0.0071445885 0.0050290577 0.0074485955 0.0080736532 0.0046200000 0.0003960000 0.0023910000 0.0000030000 0.0000030000 0.0014620000 13630125 96830484 509673472 3.6649413109 4.2320513725 5.7716107368 272 10.8400000000 0.0071649109 0.0050369101 0.0074485955 0.0081357878 0.0044240000 0.0003940000 0.0025250000 0.0000000000 0.0000040000 0.0011360000 13632901 96830484 509673472 3.6768913269 4.2302012444 5.7751269341 273 10.8800000000 0.0071709296 0.0050447270 0.0074485955 0.0081441858 0.0054560000 0.0004100000 0.0025280000 0.0000040000 0.0000030000 0.0021370000 13635677 96830484 509673472 3.6895010471 4.2309336662 5.7796788216 274 10.9200000000 0.0072003426 0.0050525942 0.0074485955 0.0081530218 0.0044510000 0.0003970000 0.0025520000 0.0000010000 0.0000030000 0.0011280000 13638453 96830484 509673472 3.7027790546 4.2321758270 5.7833552361 275 10.9600000000 0.0071804002 0.0050603317 0.0074485955 0.0081586503 0.0047440000 0.0003970000 0.0025340000 0.0000030000 0.0000030000 0.0014370000 13641229 96830484 509673472 3.7156677246 4.2321162224 5.7861166000 276 11.0000000000 0.0072026625 0.0050680938 0.0074485955 0.0081558471 0.0043120000 0.0003960000 0.0024240000 0.0000000000 0.0000040000 0.0011180000 13644005 96830484 509673472 3.7291328907 4.2340221405 5.7898879051 277 11.0400000000 0.0072200582 0.0050758626 0.0074485955 0.0081614233 0.0052920000 0.0003950000 0.0024100000 0.0000030000 0.0000030000 0.0021070000 13646781 96830484 509673472 3.7427012920 4.2355189323 5.7932348251 278 11.0800000000 0.0072439029 0.0050836613 0.0074485955 0.0081672659 0.0043020000 0.0003940000 0.0024190000 0.0000000000 0.0000040000 0.0011130000 13649557 96830484 509673472 3.7562873363 4.2372832298 5.7966055870 279 11.1200000000 0.0072256303 0.0050913386 0.0074485955 0.0081766005 0.0047450000 0.0003960000 0.0025390000 0.0000030000 0.0000030000 0.0014320000 13652333 96830484 509673472 3.7702391148 4.2390341759 5.8006019592 280 11.1600000000 0.0072257449 0.0050989615 0.0074485955 0.0081848622 0.0044220000 0.0003930000 0.0025510000 0.0000000000 0.0000030000 0.0011000000 13655109 96830484 509673472 3.7842402458 4.2415351868 5.8037648201 281 11.2000000000 0.0072633964 0.0051066641 0.0074485955 0.0081912237 0.0054000000 0.0003960000 0.0025520000 0.0000030000 0.0000020000 0.0020710000 13657885 96830484 509673472 3.7973935604 4.2424201965 5.8063678741 282 11.2400000000 0.0072317682 0.0051141999 0.0074485955 0.0081865919 0.0044270000 0.0003950000 0.0025610000 0.0000010000 0.0000030000 0.0010870000 13660661 96830484 509673472 3.8092379570 4.2414031029 5.8109903336 283 11.2800000000 0.0072237048 0.0051216540 0.0074485955 0.0081722833 0.0047670000 0.0003950000 0.0025610000 0.0000030000 0.0000030000 0.0014200000 13663437 96830484 509673472 3.8215346336 4.2427086830 5.8134732246 284 11.3200000000 0.0072532925 0.0051291598 0.0074485955 0.0081614013 0.0042910000 0.0003960000 0.0024240000 0.0000000000 0.0000040000 0.0010800000 13666213 96830484 509673472 3.8341231346 4.2448267937 5.8188343048 285 11.3600000000 0.0073550236 0.0051369698 0.0074485955 0.0081586280 0.0057800000 0.0003950000 0.0029460000 0.0000030000 0.0000020000 0.0020490000 13668989 96830484 509673472 3.8457341194 4.2460331917 5.8229637146 286 11.4000000000 0.0072565689 0.0051443810 0.0074485955 0.0081505211 0.0048110000 0.0003950000 0.0029490000 0.0000000000 0.0000030000 0.0010760000 13671765 96830484 509673472 3.8562357426 4.2458915710 5.8269667625 287 11.4400000000 0.0073007662 0.0051518946 0.0074485955 0.0081363427 0.0050910000 0.0003970000 0.0029150000 0.0000030000 0.0000030000 0.0013830000 13674541 96830484 509673472 3.8657681942 4.2455487251 5.8311662674 288 11.4800000000 0.0072297128 0.0051591092 0.0074485955 0.0081230492 0.0044220000 0.0003960000 0.0025700000 0.0000000000 0.0000030000 0.0010670000 13677317 96830484 509673472 3.8746147156 4.2453570366 5.8351063728 289 11.5200000000 0.0072868117 0.0051664715 0.0074485955 0.0081103440 0.0054120000 0.0003950000 0.0025630000 0.0000030000 0.0000020000 0.0020540000 13680093 96830484 509673472 3.8831646442 4.2452907562 5.8416728973 290 11.5600000000 0.0072940481 0.0051738080 0.0074485955 0.0081020862 0.0067880000 0.0003950000 0.0049360000 0.0000000000 0.0000040000 0.0010640000 13682869 96830484 509673472 3.8914830685 4.2456989288 5.8474278450 291 11.6000000000 0.0073340884 0.0051812316 0.0074485955 0.0080918929 0.0069910000 0.0003990000 0.0048200000 0.0000030000 0.0000030000 0.0013760000 13685645 96830484 509673472 3.8990385532 4.2448382378 5.8545546532 292 11.6400000000 0.0073332400 0.0051886015 0.0074485955 0.0080797795 0.0051590000 0.0003970000 0.0033130000 0.0000000000 0.0000030000 0.0010550000 13688421 96830484 509673472 3.9070794582 4.2458267212 5.8603177071 293 11.6800000000 0.0073266509 0.0051958986 0.0074485955 0.0080660535 0.0052610000 0.0003950000 0.0024330000 0.0000030000 0.0000030000 0.0020370000 13691197 96830484 509673472 3.9140496254 4.2460818291 5.8671760559 294 11.7200000000 0.0073637995 0.0052032724 0.0074485955 0.0080537503 0.0044120000 0.0003940000 0.0025660000 0.0000000000 0.0000030000 0.0010560000 13693973 96830484 509673472 3.9201757908 4.2453894615 5.8745245934 295 11.7600000000 0.0073572029 0.0052105739 0.0074485955 0.0080458683 0.0045790000 0.0003970000 0.0024170000 0.0000040000 0.0000030000 0.0013620000 13696749 96830484 509673472 3.9258635044 4.2453398705 5.8814735413 296 11.8000000000 0.0073395078 0.0052177662 0.0074485955 0.0080368135 0.0042810000 0.0003950000 0.0024300000 0.0000000000 0.0000030000 0.0010560000 13699525 96830484 509673472 3.9317138195 4.2455096245 5.8880057335 297 11.8400000000 0.0073793987 0.0052250444 0.0074485955 0.0080283096 0.0052690000 0.0003970000 0.0024350000 0.0000030000 0.0000030000 0.0020320000 13702301 96830484 509673472 3.9366185665 4.2450776100 5.8955593109 298 11.8800000000 0.0073999725 0.0052323429 0.0074485955 0.0080238081 0.0038860000 0.0003940000 0.0020340000 0.0000000000 0.0000030000 0.0010570000 13705077 96830484 509673472 3.9415140152 4.2444567680 5.9035243988 299 11.9200000000 0.0073813270 0.0052395301 0.0074485955 0.0080148115 0.0047650000 0.0003960000 0.0025610000 0.0000030000 0.0000030000 0.0013970000 13707853 96830484 509673472 3.9465563297 4.2444572449 5.9116525650 300 11.9600000000 0.0073854090 0.0052466830 0.0074485955 0.0080022774 0.0039090000 0.0003950000 0.0020470000 0.0000000000 0.0000030000 0.0010620000 13710629 96830484 509673472 3.9515702724 4.2452769279 5.9199399948 301 12.0000000000 0.0073838877 0.0052537834 0.0074485955 0.0079891987 0.0051450000 0.0003950000 0.0023000000 0.0000030000 0.0000030000 0.0020430000 13713405 96830484 509673472 3.9562072754 4.2455592155 5.9291758537 302 12.0400000000 0.0074367658 0.0052610118 0.0074485955 0.0079785828 0.0044320000 0.0003960000 0.0025560000 0.0000000000 0.0000040000 0.0010690000 13716181 96830484 509673472 3.9601831436 4.2454562187 5.9390702248 303 12.0800000000 0.0073895343 0.0052680366 0.0074485955 0.0079726561 0.0046190000 0.0003980000 0.0024240000 0.0000030000 0.0000030000 0.0013810000 13718957 96830484 509673472 3.9643700123 4.2457022667 5.9490251541 304 12.1200000000 0.0074990336 0.0052753754 0.0074990336 0.0079716506 0.0054810000 0.0003940000 0.0036070000 0.0000000000 0.0000040000 0.0010660000 13721733 96830484 509673472 3.9683089256 4.2460722923 5.9592866898 305 12.1600000000 0.0074478355 0.0052824982 0.0074990336 0.0079687090 0.0053090000 0.0003960000 0.0024370000 0.0000040000 0.0000030000 0.0020610000 13724509 96830484 509673472 3.9719648361 4.2458791733 5.9705724716 306 12.2000000000 0.0074819364 0.0052896859 0.0074990336 0.0079621110 0.0044420000 0.0003950000 0.0025570000 0.0000000000 0.0000040000 0.0010740000 13727285 96830484 509673472 3.9755818844 4.2458806038 5.9820895195 307 12.2400000000 0.0075255302 0.0052969688 0.0075255302 0.0079639680 0.0045860000 0.0003960000 0.0023720000 0.0000040000 0.0000020000 0.0014010000 13730061 96830484 509673472 3.9788665771 4.2466516495 5.9937334061 308 12.2800000000 0.0075551816 0.0053043007 0.0075551816 0.0079680097 0.0039250000 0.0003950000 0.0020430000 0.0000000000 0.0000040000 0.0010710000 13732837 96830484 509673472 3.9815020561 4.2467846870 6.0053009987 309 12.3200000000 0.0075220112 0.0053114777 0.0075551816 0.0079793921 0.0052680000 0.0003950000 0.0023820000 0.0000030000 0.0000030000 0.0020700000 13735613 96830484 509673472 3.9834141731 4.2463593483 6.0162405968 310 12.3600000000 0.0075694961 0.0053187617 0.0075694961 0.0079983576 0.0046500000 0.0003950000 0.0027600000 0.0000000000 0.0000040000 0.0010780000 13738389 96830484 509673472 3.9850912094 4.2458829880 6.0281934738 311 12.4000000000 0.0075954697 0.0053260823 0.0075954697 0.0080122303 0.0050130000 0.0003950000 0.0028080000 0.0000030000 0.0000030000 0.0013900000 13741165 96830484 509673472 3.9873123169 4.2467226982 6.0389842987 312 12.4400000000 0.0076361587 0.0053334864 0.0076361587 0.0080494223 0.0043200000 0.0003940000 0.0024270000 0.0000000000 0.0000030000 0.0010810000 13743941 96830484 509673472 3.9896705151 4.2464714050 6.0628237724 313 12.4800000000 0.0076379045 0.0053408487 0.0076379045 0.0080432508 0.0053010000 0.0003950000 0.0024250000 0.0000040000 0.0000030000 0.0020580000 13746717 96830484 509673472 3.9902601242 4.2462687492 6.0735831261 314 12.5200000000 0.0076865163 0.0053483190 0.0076865163 0.0080355880 0.0043360000 0.0003960000 0.0024410000 0.0000000000 0.0000030000 0.0010760000 13749493 96830484 509673472 3.9903218746 4.2451815605 6.0861415863 315 12.5600000000 0.0077175442 0.0053558404 0.0077175442 0.0080359125 0.0046380000 0.0003950000 0.0024180000 0.0000030000 0.0000030000 0.0013970000 13752269 96830484 509673472 3.9907758236 4.2454409599 6.0974960327 316 12.6000000000 0.0077124364 0.0053632979 0.0077175442 0.0080256965 0.0043160000 0.0003960000 0.0024250000 0.0000000000 0.0000030000 0.0010730000 13755045 96830484 509673472 3.9909594059 4.2456798553 6.1096587181 317 12.6400000000 0.0076553384 0.0053705283 0.0077175442 0.0080131394 0.0053250000 0.0003950000 0.0024310000 0.0000030000 0.0000030000 0.0020690000 13757821 96830484 509673472 3.9906392097 4.2449569702 6.1213068962 318 12.6800000000 0.0076575852 0.0053777204 0.0077175442 0.0080004922 0.0043230000 0.0003970000 0.0024270000 0.0000000000 0.0000030000 0.0010710000 13760597 96830484 509673472 3.9899997711 4.2444348335 6.1326689720 319 12.7200000000 0.0076138591 0.0053847302 0.0077175442 0.0079879161 0.0050190000 0.0003960000 0.0028130000 0.0000030000 0.0000030000 0.0013790000 13763373 96830484 509673472 3.9892706871 4.2445020676 6.1427092552 320 12.7600000000 0.0075689089 0.0053915557 0.0077175442 0.0079753922 0.0066740000 0.0003930000 0.0047890000 0.0000000000 0.0000030000 0.0010660000 13766149 96830484 509673472 3.9880726337 4.2445864677 6.1529402733 321 12.8000000000 0.0075131026 0.0053981649 0.0077175442 0.0079653306 0.0057930000 0.0003950000 0.0029590000 0.0000040000 0.0000030000 0.0020040000 13768925 96830484 509673472 3.9859287739 4.2434425354 6.1637492180 322 12.8400000000 0.0074351886 0.0054044911 0.0077175442 0.0079550935 0.0048520000 0.0003970000 0.0029520000 0.0000010000 0.0000030000 0.0010660000 13771701 96830484 509673472 3.9842870235 4.2437133789 6.1732449532 323 12.8800000000 0.0073882723 0.0054106328 0.0077175442 0.0079462473 0.0047160000 0.0003960000 0.0025440000 0.0000030000 0.0000030000 0.0013400000 13774477 96830484 509673472 3.9823307991 4.2425599098 6.1819763184 324 12.9200000000 0.0073316176 0.0054165618 0.0077175442 0.0079349283 0.0046650000 0.0003950000 0.0028000000 0.0000000000 0.0000040000 0.0010350000 13777253 96830484 509673472 3.9803481102 4.2418599129 6.1911954880 325 12.9600000000 0.0072255661 0.0054221280 0.0077175442 0.0079228846 0.0056260000 0.0003950000 0.0028050000 0.0000040000 0.0000030000 0.0019870000 13780029 96830484 509673472 3.9789474010 4.2425870895 6.2003059387 326 13.0000000000 0.0071915463 0.0054275556 0.0077175442 0.0079112751 0.0042660000 0.0003940000 0.0024130000 0.0000000000 0.0000040000 0.0010210000 13782805 96830484 509673472 3.9769923687 4.2422051430 6.2075762749 327 13.0400000000 0.0072087157 0.0054330026 0.0077175442 0.0079005208 0.0049380000 0.0003950000 0.0027950000 0.0000040000 0.0000030000 0.0013050000 13785581 96830484 509673472 3.9750576019 4.2425994873 6.2173290253 328 13.0800000000 0.0072088344 0.0054384167 0.0077175442 0.0078896279 0.0041220000 0.0003930000 0.0022780000 0.0000010000 0.0000040000 0.0010100000 13788357 96830484 509673472 3.9745416641 4.2453007698 6.2239003181 329 13.1200000000 0.0071731433 0.0054436894 0.0077175442 0.0078781945 0.0052980000 0.0003950000 0.0025440000 0.0000030000 0.0000030000 0.0019130000 13791133 96830484 509673472 3.9729366302 4.2460446358 6.2329826355 330 13.1600000000 0.0071350350 0.0054488147 0.0077175442 0.0078673726 0.0042510000 0.0003960000 0.0024130000 0.0000000000 0.0000030000 0.0009920000 13793909 96830484 509673472 3.9710316658 4.2462692261 6.2410383224 331 13.2000000000 0.0071886992 0.0054540712 0.0077175442 0.0078558752 0.0045280000 0.0003950000 0.0024140000 0.0000030000 0.0000030000 0.0012720000 13796685 96830484 509673472 3.9693367481 4.2468905449 6.2510919571 332 13.2400000000 0.0073234844 0.0054597019 0.0077175442 0.0078461543 0.0041090000 0.0003940000 0.0022880000 0.0000010000 0.0000030000 0.0009780000 13799461 96830484 509673472 3.9675891399 4.2474899292 6.2596859932 333 13.2800000000 0.0072819269 0.0054651741 0.0077175442 0.0078353863 0.0050560000 0.0003970000 0.0024230000 0.0000030000 0.0000030000 0.0017800000 13802237 96830484 509673472 3.9654877186 4.2476987839 6.2690157890 334 13.3200000000 0.0073059071 0.0054706853 0.0077175442 0.0078241629 0.0047030000 0.0003960000 0.0029340000 0.0000010000 0.0000030000 0.0009230000 13805013 96830484 509673472 3.9632742405 4.2476205826 6.2769842148 335 13.3600000000 0.0072845127 0.0054760997 0.0077175442 0.0078126222 0.0041010000 0.0003970000 0.0020310000 0.0000030000 0.0000030000 0.0012160000 13807789 96830484 509673472 3.9612259865 4.2485785484 6.2855792046 336 13.4000000000 0.0072893389 0.0054814962 0.0077175442 0.0078010280 0.0043170000 0.0003960000 0.0025510000 0.0000000000 0.0000040000 0.0009130000 13810565 96830484 509673472 3.9597787857 4.2504639626 6.2933950424 337 13.4400000000 0.0072844592 0.0054868463 0.0077175442 0.0077996942 0.0047280000 0.0003940000 0.0021700000 0.0000030000 0.0000030000 0.0017050000 13813341 96830484 509673472 3.9581034184 4.2528572083 6.3008241653 338 13.4800000000 0.0073104640 0.0054922416 0.0077175442 0.0078057727 0.0037910000 0.0003970000 0.0020290000 0.0000000000 0.0000030000 0.0009090000 13816117 96830484 509673472 3.9563405514 4.2544832230 6.3070259094 339 13.5200000000 0.0073159602 0.0054976213 0.0077175442 0.0078217249 0.0044470000 0.0003950000 0.0024230000 0.0000030000 0.0000020000 0.0011660000 13818893 96830484 509673472 3.9539377689 4.2544822693 6.3124794960 340 13.5600000000 0.0073213466 0.0055029852 0.0077175442 0.0078181760 0.0041770000 0.0003960000 0.0024120000 0.0000000000 0.0000040000 0.0009110000 13821669 96830484 509673472 3.9515523911 4.2548332214 6.3176312447 341 13.6000000000 0.0073563186 0.0055084202 0.0077175442 0.0078115339 0.0049180000 0.0003940000 0.0024200000 0.0000030000 0.0000030000 0.0016420000 13824445 96830484 509673472 3.9494173527 4.2552204132 6.3224840164 342 13.6400000000 0.0073263133 0.0055137357 0.0077175442 0.0078031797 0.0041920000 0.0003940000 0.0024250000 0.0000000000 0.0000040000 0.0009110000 13827221 96830484 509673472 3.9473016262 4.2555336952 6.3279967308 343 13.6800000000 0.0073950682 0.0055192206 0.0077175442 0.0077921818 0.0042730000 0.0003950000 0.0022930000 0.0000030000 0.0000030000 0.0011200000 13829997 96830484 509673472 3.9454154968 4.2558588982 6.3327326775 344 13.7200000000 0.0074189375 0.0055247430 0.0077175442 0.0077809613 0.0042600000 0.0003960000 0.0025430000 0.0000010000 0.0000030000 0.0008550000 13832773 96830484 509673472 3.9443650246 4.2575039864 6.3382663727 345 13.7600000000 0.0074402853 0.0055302953 0.0077175442 0.0077730332 0.0050120000 0.0003940000 0.0025450000 0.0000040000 0.0000030000 0.0016060000 13835549 96830484 509673472 3.9424917698 4.2573852539 6.3436841965 346 13.8000000000 0.0074306629 0.0055357877 0.0077175442 0.0077672303 0.0041050000 0.0003960000 0.0024080000 0.0000000000 0.0000030000 0.0008370000 13838325 96830484 509673472 3.9408526421 4.2572388649 6.3486800194 347 13.8400000000 0.0073828329 0.0055411106 0.0077175442 0.0077564550 0.0043470000 0.0003960000 0.0024130000 0.0000030000 0.0000030000 0.0010700000 13841101 96830484 509673472 3.9384818077 4.2558178902 6.3532772064 348 13.8800000000 0.0073452918 0.0055462950 0.0077175442 0.0077459141 0.0041170000 0.0003950000 0.0024240000 0.0000010000 0.0000030000 0.0008260000 13843877 96830484 509673472 3.9379153252 4.2579889297 6.3590674400 349 13.9200000000 0.0073330654 0.0055514147 0.0077175442 0.0077430024 0.0042870000 0.0003960000 0.0018880000 0.0000030000 0.0000030000 0.0015320000 13846653 96830484 509673472 3.9362776279 4.2576274872 6.3647785187 350 13.9600000000 0.0073157237 0.0055564556 0.0077175442 0.0077348942 0.0044660000 0.0003940000 0.0027920000 0.0000010000 0.0000030000 0.0008100000 13849429 96830484 509673472 3.9342591763 4.2562332153 6.3736109734 351 14.0000000000 0.0071669128 0.0055610438 0.0077175442 0.0077247219 0.0048730000 0.0003980000 0.0029500000 0.0000030000 0.0000030000 0.0010530000 13852205 96830484 509673472 3.9340078831 4.2567772865 6.3782548904 352 14.0400000000 0.0071672988 0.0055656070 0.0077175442 0.0077164797 0.0041070000 0.0003960000 0.0024270000 0.0000010000 0.0000030000 0.0008110000 13854981 96830484 509673472 3.9334282875 4.2563681602 6.3830265999 353 14.0800000000 0.0071675782 0.0055701452 0.0077175442 0.0077055541 0.0055890000 0.0003950000 0.0032170000 0.0000030000 0.0000020000 0.0014950000 13857757 96830484 509673472 3.9330935478 4.2553591728 6.3873205185 354 14.1200000000 0.0071858093 0.0055747092 0.0077175442 0.0076946802 0.0042330000 0.0003940000 0.0025610000 0.0000010000 0.0000030000 0.0008030000 13860533 96830484 509673472 3.9334216118 4.2559065819 6.3921518326 355 14.1600000000 0.0072022416 0.0055792938 0.0077175442 0.0076841876 0.0044890000 0.0003960000 0.0025590000 0.0000030000 0.0000030000 0.0010490000 13863309 96830484 509673472 3.9329156876 4.2544879913 6.3968858719 356 14.2000000000 0.0071529676 0.0055837142 0.0077175442 0.0076756036 0.0044980000 0.0003960000 0.0028240000 0.0000000000 0.0000040000 0.0007940000 13866085 96830484 509673472 3.9331886768 4.2542719841 6.4015374184 357 14.2400000000 0.0070721786 0.0055878836 0.0077175442 0.0076652868 0.0048250000 0.0003970000 0.0024360000 0.0000030000 0.0000030000 0.0015040000 13868861 96830484 509673472 3.9334709644 4.2547068596 6.4071516991 358 14.2800000000 0.0070929276 0.0055920876 0.0077175442 0.0076553076 0.0041160000 0.0003960000 0.0024410000 0.0000010000 0.0000040000 0.0007980000 13871637 96830484 509673472 3.9331927299 4.2533307076 6.4125308990 359 14.3200000000 0.0070806812 0.0055962341 0.0077175442 0.0076461278 0.0043550000 0.0003950000 0.0024360000 0.0000030000 0.0000030000 0.0010390000 13874413 96830484 509673472 3.9325654507 4.2515134811 6.4179716110 360 14.3600000000 0.0070396364 0.0056002436 0.0077175442 0.0076377582 0.0046360000 0.0003970000 0.0029600000 0.0000000000 0.0000030000 0.0007920000 13877189 96830484 509673472 3.9323945045 4.2501807213 6.4240846634 361 14.4000000000 0.0070467503 0.0056042505 0.0077175442 0.0076342943 0.0049260000 0.0003970000 0.0025630000 0.0000040000 0.0000030000 0.0014730000 13879965 96830484 509673472 3.9322919846 4.2499990463 6.4305696487 362 14.4400000000 0.0070522795 0.0056082506 0.0077175442 0.0076281508 0.0042490000 0.0003970000 0.0025590000 0.0000010000 0.0000030000 0.0007930000 13882741 96830484 509673472 3.9322953224 4.2502036095 6.4370794296 363 14.4800000000 0.0070546451 0.0056122352 0.0077175442 0.0076179797 0.0048600000 0.0003970000 0.0029520000 0.0000030000 0.0000030000 0.0010160000 13885517 96830484 509673472 3.9324471951 4.2510905266 6.4442420006 364 14.5200000000 0.0070528449 0.0056161929 0.0077175442 0.0076083497 0.0048900000 0.0003950000 0.0032190000 0.0000000000 0.0000030000 0.0007870000 13888293 96830484 509673472 3.9320948124 4.2504220009 6.4514389038 365 14.5600000000 0.0070742336 0.0056201875 0.0077175442 0.0075982313 0.0055430000 0.0003950000 0.0031990000 0.0000040000 0.0000030000 0.0014520000 13891069 96830484 509673472 3.9315402508 4.2495083809 6.4584417343 366 14.6000000000 0.0070843156 0.0056241879 0.0077175442 0.0075878513 0.0045990000 0.0003960000 0.0029250000 0.0000000000 0.0000030000 0.0007830000 13893845 96830484 509673472 3.9314532280 4.2504177094 6.4662661552 367 14.6400000000 0.0071531790 0.0056283541 0.0077175442 0.0075776546 0.0047070000 0.0003960000 0.0027930000 0.0000030000 0.0000030000 0.0010170000 13896621 96830484 509673472 3.9315357208 4.2513799667 6.4734916687 368 14.6800000000 0.0072001526 0.0056326253 0.0077175442 0.0075699479 0.0041840000 0.0003950000 0.0025150000 0.0000010000 0.0000030000 0.0007770000 13899397 96830484 509673472 3.9313642979 4.2518968582 6.4812393188 369 14.7200000000 0.0072063543 0.0056368901 0.0077175442 0.0075697260 0.0062800000 0.0003950000 0.0039050000 0.0000030000 0.0000030000 0.0014720000 13902173 96830484 509673472 3.9305913448 4.2516274452 6.4886651039 370 14.7600000000 0.0072334534 0.0056412051 0.0077175442 0.0075678426 0.0049330000 0.0003970000 0.0032490000 0.0000000000 0.0000030000 0.0007880000 13904949 96830484 509673472 3.9304080009 4.2519974709 6.4965972900 371 14.8000000000 0.0072602257 0.0056455691 0.0077175442 0.0075621546 0.0044010000 0.0003950000 0.0024770000 0.0000040000 0.0000030000 0.0010230000 13907725 96830484 509673472 3.9303929806 4.2516899109 6.5037355423 372 14.8400000000 0.0072689569 0.0056499330 0.0077175442 0.0075584505 0.0045380000 0.0003960000 0.0028430000 0.0000000000 0.0000040000 0.0007900000 13910501 96830484 509673472 3.9301886559 4.2511601448 6.5107669830 373 14.8800000000 0.0072786645 0.0056542996 0.0077175442 0.0075591627 0.0047210000 0.0003970000 0.0023460000 0.0000030000 0.0000030000 0.0014710000 13913277 96830484 509673472 3.9300799370 4.2509202957 6.5180263519 374 14.9200000000 0.0073253801 0.0056587677 0.0077175442 0.0075559103 0.0045300000 0.0003970000 0.0028370000 0.0000000000 0.0000040000 0.0007930000 13916053 96830484 509673472 3.9299650192 4.2502450943 6.5252223015 375 14.9600000000 0.0073676561 0.0056633248 0.0077175442 0.0075586737 0.0047760000 0.0003960000 0.0028280000 0.0000030000 0.0000030000 0.0010410000 13918829 96830484 509673472 3.9302554131 4.2498779297 6.5321621895 376 15.0000000000 0.0073912381 0.0056679203 0.0077175442 0.0075582144 0.0062820000 0.0003980000 0.0045760000 0.0000000000 0.0000040000 0.0008010000 13921605 96830484 509673472 3.9312670231 4.2512407303 6.5395827293 377 15.0400000000 0.0074287974 0.0056725910 0.0077175442 0.0075511159 0.0047440000 0.0003940000 0.0023240000 0.0000040000 0.0000030000 0.0015120000 13924381 96830484 509673472 3.9336028099 4.2523298264 6.5526747704 378 15.0800000000 0.0075418511 0.0056775362 0.0077175442 0.0075411757 0.0040600000 0.0003940000 0.0023310000 0.0000000000 0.0000030000 0.0008180000 13927157 96830484 509673472 3.9356451035 4.2535877228 6.5589742661 379 15.1200000000 0.0075285495 0.0056824201 0.0077175442 0.0075312585 0.0043040000 0.0003950000 0.0023290000 0.0000030000 0.0000030000 0.0010660000 13929933 96830484 509673472 3.9374945164 4.2540154457 6.5646619797 380 15.1600000000 0.0075819204 0.0056874188 0.0077175442 0.0075224801 0.0040830000 0.0003960000 0.0023250000 0.0000010000 0.0000040000 0.0008320000 13932709 96830484 509673472 3.9402890205 4.2551121712 6.5700855255 381 15.2000000000 0.0076034279 0.0056924477 0.0077175442 0.0075127202 0.0077150000 0.0007620000 0.0047230000 0.0000030000 0.0000030000 0.0015800000 13935485 96830484 509673472 3.9426708221 4.2560839653 6.5751633644 382 15.2400000000 0.0076282993 0.0056975154 0.0077175442 0.0075040560 0.0041310000 0.0004000000 0.0023520000 0.0000000000 0.0000030000 0.0008460000 13938261 96830484 509673472 3.9449152946 4.2564477921 6.5799775124 383 15.2800000000 0.0076737213 0.0057026752 0.0077175442 0.0074948517 0.0043640000 0.0003950000 0.0023510000 0.0000030000 0.0000030000 0.0010950000 13941037 96830484 509673472 3.9476091862 4.2574386597 6.5845546722 384 15.3200000000 0.0076853232 0.0057078383 0.0077175442 0.0074851538 0.0041610000 0.0004330000 0.0023530000 0.0000000000 0.0000040000 0.0008490000 13943813 96830484 509673472 3.9504272938 4.2580885887 6.5883827209 385 15.3600000000 0.0077628260 0.0057131759 0.0077628260 0.0074763914 0.0048940000 0.0003980000 0.0023640000 0.0000030000 0.0000020000 0.0016080000 13946589 96830484 509673472 3.9529907703 4.2577357292 6.5909218788 386 15.4000000000 0.0077601224 0.0057184789 0.0077628260 0.0074740164 0.0041380000 0.0003950000 0.0023580000 0.0000000000 0.0000030000 0.0008580000 13949365 96830484 509673472 3.9560241699 4.2582926750 6.5931081772 387 15.4400000000 0.0077929907 0.0057238394 0.0077929907 0.0074759281 0.0049170000 0.0003950000 0.0028770000 0.0000040000 0.0000030000 0.0011180000 13952141 96830484 509673472 3.9597334862 4.2604236603 6.5953216553 388 15.4800000000 0.0077772569 0.0057291317 0.0077929907 0.0074669456 0.0041920000 0.0003980000 0.0023960000 0.0000000000 0.0000040000 0.0008720000 13954917 96830484 509673472 3.9627382755 4.2615790367 6.5963692665 389 15.5200000000 0.0077770837 0.0057343964 0.0077929907 0.0074581379 0.0049880000 0.0003980000 0.0024090000 0.0000030000 0.0000030000 0.0016530000 13957693 96830484 509673472 3.9653537273 4.2616858482 6.5973720551 390 15.5600000000 0.0077607809 0.0057395922 0.0077929907 0.0074486703 0.0042460000 0.0003950000 0.0024330000 0.0000000000 0.0000040000 0.0008880000 13960469 96830484 509673472 3.9692211151 4.2647280693 6.5986142159 391 15.6000000000 0.0077087246 0.0057446284 0.0077929907 0.0074560459 0.0043800000 0.0003940000 0.0022910000 0.0000040000 0.0000030000 0.0011630000 13963245 96830484 509673472 3.9723589420 4.2649397850 6.5999598503 392 15.6400000000 0.0077269007 0.0057496852 0.0077929907 0.0074474710 0.0042530000 0.0003990000 0.0024250000 0.0000000000 0.0000040000 0.0008980000 13966021 96830484 509673472 3.9752094746 4.2647452354 6.6003494263 393 15.6800000000 0.0076640551 0.0057545564 0.0077929907 0.0074382384 0.0051010000 0.0003930000 0.0024210000 0.0000030000 0.0000030000 0.0017490000 13968797 96830484 509673472 3.9772744179 4.2631621361 6.6010055542 394 15.7200000000 0.0077087372 0.0057595162 0.0077929907 0.0074301429 0.0042670000 0.0003950000 0.0024130000 0.0000000000 0.0000040000 0.0009280000 13971573 96830484 509673472 3.9793279171 4.2614059448 6.6020131111 395 15.7600000000 0.0077465060 0.0057645466 0.0077929907 0.0074322632 0.0047040000 0.0003970000 0.0025420000 0.0000030000 0.0000030000 0.0012290000 13974349 96830484 509673472 3.9826650620 4.2618608475 6.6026096344 396 15.8000000000 0.0077646100 0.0057695972 0.0077929907 0.0074268163 0.0044540000 0.0003960000 0.0025580000 0.0000000000 0.0000030000 0.0009600000 13977125 96830484 509673472 3.9864375591 4.2621340752 6.6028308868 397 15.8400000000 0.0077309567 0.0057745377 0.0077929907 0.0074297900 0.0052680000 0.0003960000 0.0024220000 0.0000030000 0.0000040000 0.0019090000 13979901 96830484 509673472 3.9892997742 4.2613101006 6.6027908325 398 15.8800000000 0.0077135116 0.0057794095 0.0077929907 0.0074246859 0.0042170000 0.0003970000 0.0022740000 0.0000000000 0.0000030000 0.0010070000 13982677 96830484 509673472 3.9922194481 4.2594923973 6.6021018028 399 15.9200000000 0.0076740026 0.0057841578 0.0077929907 0.0074168292 0.0044140000 0.0003930000 0.0021460000 0.0000030000 0.0000030000 0.0013310000 13985453 96830484 509673472 3.9967370033 4.2611165047 6.6006484032 400 15.9600000000 0.0076503023 0.0057888232 0.0077929907 0.0074097925 0.0042580000 0.0003960000 0.0022830000 0.0000000000 0.0000030000 0.0010320000 13988229 96830484 509673472 4.0010619164 4.2621221542 6.6008315086 401 16.0000000000 0.0076102433 0.0057933654 0.0077929907 0.0074043839 0.0053290000 0.0003970000 0.0024130000 0.0000030000 0.0000030000 0.0019720000 13991005 96830484 509673472 4.0053973198 4.2624897957 6.6012177467 402 16.0400000000 0.0076247579 0.0057979211 0.0077929907 0.0073959809 0.0039770000 0.0003940000 0.0020260000 0.0000000000 0.0000040000 0.0010150000 13993781 96830484 509673472 4.0109300613 4.2631044388 6.6009101868 403 16.0800000000 0.0076576588 0.0058025358 0.0077929907 0.0073904864 0.0047210000 0.0003960000 0.0023980000 0.0000030000 0.0000030000 0.0013780000 13996557 96830484 509673472 4.0155510902 4.2625999451 6.6021823883 404 16.1200000000 0.0077604498 0.0058073822 0.0077929907 0.0073819973 0.0043740000 0.0003960000 0.0023870000 0.0000000000 0.0000030000 0.0010490000 13999333 96830484 509673472 4.0205311775 4.2631030083 6.6009111404 405 16.1600000000 0.0079377787 0.0058126424 0.0079377787 0.0073733774 0.0053220000 0.0003950000 0.0023540000 0.0000030000 0.0000030000 0.0020240000 14002109 96830484 509673472 4.0259776115 4.2636036873 6.6018218994 406 16.2000000000 0.0081362789 0.0058183656 0.0081362789 0.0073647444 0.0044440000 0.0003960000 0.0024500000 0.0000010000 0.0000040000 0.0010460000 14004885 96830484 509673472 4.0319223404 4.2653036118 6.6039910316 407 16.2400000000 0.0081807654 0.0058241701 0.0081807654 0.0073570018 0.0042770000 0.0003990000 0.0019340000 0.0000040000 0.0000030000 0.0013890000 14007661 96830484 509673472 4.0371022224 4.2662134171 6.6058945656 408 16.2800000000 0.0082343314 0.0058300773 0.0082343314 0.0073598106 0.0042920000 0.0003930000 0.0022780000 0.0000000000 0.0000040000 0.0010700000 14010437 96830484 509673472 4.0424003601 4.2668251991 6.6086230278 409 16.3200000000 0.0081886621 0.0058358440 0.0082343314 0.0073628881 0.0053810000 0.0003940000 0.0023830000 0.0000030000 0.0000030000 0.0020500000 14013213 96830484 509673472 4.0490622520 4.2703733444 6.6114535332 410 16.3600000000 0.0082857823 0.0058418195 0.0082857823 0.0073541395 0.0042450000 0.0003970000 0.0022370000 0.0000000000 0.0000040000 0.0010580000 14015989 96830484 509673472 4.0552625656 4.2735033035 6.6156740189 411 16.3999999990 0.0083229775 0.0058478564 0.0083229775 0.0073481888 0.0045780000 0.0003970000 0.0022140000 0.0000030000 0.0000030000 0.0014110000 14018765 96830484 509673472 4.0587940216 4.2723112106 6.6174273491 412 16.4400000000 0.0082874354 0.0058537777 0.0083229775 0.0073641000 0.0042340000 0.0003960000 0.0022100000 0.0000000000 0.0000030000 0.0010740000 14021541 96830484 509673472 4.0640063286 4.2721576691 6.6238965988 413 16.4800000000 0.0083450871 0.0058598099 0.0083450871 0.0073784371 0.0052840000 0.0003960000 0.0021990000 0.0000030000 0.0000030000 0.0021240000 14024317 96830484 509673472 4.0703563690 4.2736282349 6.6309795380 414 16.5200000000 0.0083817057 0.0058659014 0.0083817057 0.0073747035 0.0042760000 0.0003950000 0.0022230000 0.0000000000 0.0000030000 0.0010960000 14027093 96830484 509673472 4.0751905441 4.2715601921 6.6345133781 415 16.5599999990 0.0084778704 0.0058721953 0.0084778704 0.0073894770 0.0046180000 0.0003950000 0.0022000000 0.0000040000 0.0000030000 0.0014590000 14029869 96830484 509673472 4.0783972740 4.2658677101 6.6400699615 416 16.6000000000 0.0085358229 0.0058785983 0.0085358229 0.0074722957 0.0042520000 0.0003940000 0.0022070000 0.0000000000 0.0000040000 0.0010840000 14032645 96830484 509673472 4.0847339630 4.2659163475 6.6457824707 417 16.6400000000 0.0085819019 0.0058850810 0.0085819019 0.0075057139 0.0054210000 0.0003930000 0.0023250000 0.0000040000 0.0000030000 0.0021320000 14035421 96830484 509673472 4.0910511017 4.2675933838 6.6474013329 418 16.6800000000 0.0086514475 0.0058916991 0.0086514475 0.0075103910 0.0043870000 0.0003940000 0.0023350000 0.0000010000 0.0000030000 0.0010910000 14038197 96830484 509673472 4.0932707787 4.2644901276 6.6467247009 419 16.7199999990 0.0087731397 0.0058985761 0.0087731397 0.0075425205 0.0051250000 0.0003960000 0.0026820000 0.0000030000 0.0000030000 0.0014760000 14040973 96830484 509673472 4.1011242867 4.2675762177 6.6524443626 420 16.7600000000 0.0087657440 0.0059054027 0.0087731397 0.0075338974 0.0044060000 0.0003950000 0.0023430000 0.0000010000 0.0000040000 0.0010970000 14043749 96830484 509673472 4.1084718704 4.2703027725 6.6523809433 421 16.8000000000 0.0088522006 0.0059124022 0.0088522006 0.0075450980 0.0054630000 0.0003950000 0.0023340000 0.0000030000 0.0000030000 0.0021590000 14046525 96830484 509673472 4.1124119759 4.2658700943 6.6533012390 422 16.8400000000 0.0089683440 0.0059196438 0.0089683440 0.0075425747 0.0042630000 0.0003960000 0.0022040000 0.0000000000 0.0000040000 0.0010880000 14049301 96830484 509673472 4.1213064194 4.2593297958 6.6553187370 423 16.8799999990 0.0089398352 0.0059267837 0.0089683440 0.0075389108 0.0047550000 0.0003970000 0.0023250000 0.0000030000 0.0000030000 0.0014560000 14052077 96830484 509673472 4.1283588409 4.2582559586 6.6552710533 424 16.9200000000 0.0087863971 0.0059335281 0.0089683440 0.0075305336 0.0043920000 0.0003950000 0.0023290000 0.0000000000 0.0000040000 0.0010890000 14054853 96830484 509673472 4.1336355209 4.2552499771 6.6530051231 425 16.9600000000 0.0086668991 0.0059399595 0.0089683440 0.0075301205 0.0058080000 0.0003960000 0.0026850000 0.0000030000 0.0000020000 0.0021440000 14057629 96830484 509673472 4.1413555145 4.2557187080 6.6503477097 426 17.0000000000 0.0086779827 0.0059463868 0.0089683440 0.0075224694 0.0044060000 0.0003960000 0.0023460000 0.0000000000 0.0000040000 0.0010820000 14060405 96830484 509673472 4.1502323151 4.2558245659 6.6496558189 427 17.0400000000 0.0086731836 0.0059527727 0.0089683440 0.0075205407 0.0057170000 0.0003970000 0.0032630000 0.0000030000 0.0000030000 0.0014750000 14063181 96830484 509673472 4.1561083794 4.2520556450 6.6451964378 428 17.0800000000 0.0087062456 0.0059592061 0.0089683440 0.0075123517 0.0050840000 0.0003960000 0.0030210000 0.0000000000 0.0000040000 0.0010820000 14065957 96830484 509673472 4.1658697128 4.2503232956 6.6418919563 429 17.1200000000 0.0085174125 0.0059651693 0.0089683440 0.0075055435 0.0064030000 0.0003940000 0.0032200000 0.0000040000 0.0000030000 0.0021960000 14068733 96830484 509673472 4.1762199402 4.2491555214 6.6403279305 430 17.1600000000 0.0088024130 0.0059717675 0.0089683440 0.0075030671 0.0061250000 0.0003970000 0.0040620000 0.0000000000 0.0000040000 0.0010810000 14071509 96830484 509673472 4.1846570969 4.2454786301 6.6335592270 431 17.2000000000 0.0089793056 0.0059787456 0.0089793056 0.0074944372 0.0054410000 0.0003950000 0.0029840000 0.0000040000 0.0000030000 0.0014760000 14074285 96830484 509673472 4.1942462921 4.2411890030 6.6301403046 432 17.2400000000 0.0091351802 0.0059860521 0.0091351802 0.0074932025 0.0064520000 0.0003960000 0.0043880000 0.0000000000 0.0000030000 0.0010810000 14077061 96830484 509673472 4.2063670158 4.2399039268 6.6254305840 433 17.2800000000 0.0088987369 0.0059927789 0.0091351802 0.0074860071 0.0075220000 0.0003950000 0.0043610000 0.0000040000 0.0000030000 0.0021810000 14079837 96830484 509673472 4.2175412178 4.2383670807 6.6197524071 434 17.3200000000 0.0088293897 0.0059993149 0.0091351802 0.0074774338 0.0057860000 0.0003990000 0.0037250000 0.0000010000 0.0000030000 0.0010740000 14082613 96830484 509673472 4.2272930145 4.2337594032 6.6112394333 435 17.3600000000 0.0087972004 0.0060057468 0.0091351802 0.0074888749 0.0065180000 0.0003950000 0.0040790000 0.0000040000 0.0000030000 0.0014490000 14085389 96830484 509673472 4.2402200699 4.2329463959 6.6058607101 436 17.4000000000 0.0087523190 0.0060120463 0.0091351802 0.0074941100 0.0050900000 0.0003970000 0.0030210000 0.0000010000 0.0000030000 0.0010730000 14088165 96830484 509673472 4.2561111450 4.2366771698 6.5988545418 437 17.4400000000 0.0088253776 0.0060184841 0.0091351802 0.0074916458 0.0064990000 0.0003950000 0.0033620000 0.0000030000 0.0000030000 0.0021470000 14090941 96830484 509673472 4.2734794617 4.2422299385 6.5902395248 438 17.4800000000 0.0087700067 0.0060247661 0.0091351802 0.0075961711 0.0057500000 0.0003960000 0.0036980000 0.0000000000 0.0000030000 0.0010620000 14093717 96830484 509673472 4.2868208885 4.2434558868 6.5821967125 439 17.5200000000 0.0086374208 0.0060307175 0.0091351802 0.0077374701 0.0068370000 0.0003950000 0.0044100000 0.0000030000 0.0000030000 0.0014320000 14096493 96830484 509673472 4.2942752838 4.2379856110 6.5713262558 440 17.5600000000 0.0085926550 0.0060365401 0.0091351802 0.0077669115 0.0057750000 0.0003960000 0.0037130000 0.0000000000 0.0000030000 0.0010690000 14099269 96830484 509673472 4.3002514839 4.2293653488 6.5628676414 441 17.6000000000 0.0086851101 0.0060425459 0.0091351802 0.0077633666 0.0075510000 0.0004000000 0.0043900000 0.0000030000 0.0000020000 0.0021580000 14102045 96830484 509673472 4.3081564903 4.2225627899 6.5553159714 442 17.6400000000 0.0085355854 0.0060481862 0.0091351802 0.0078229197 0.0054100000 0.0003960000 0.0033570000 0.0000000000 0.0000030000 0.0010570000 14104821 96830484 509673472 4.3215737343 4.2234468460 6.5462479591 443 17.6800000000 0.0083706332 0.0060534288 0.0091351802 0.0078455149 0.0054940000 0.0003960000 0.0030110000 0.0000040000 0.0000030000 0.0014820000 14107597 96830484 509673472 4.3470187187 4.2275171280 6.5287795067 444 17.7200000000 0.0079312539 0.0060576581 0.0091351802 0.0078406241 0.0061670000 0.0003960000 0.0040970000 0.0000010000 0.0000040000 0.0010710000 14110373 96830484 509673472 4.3558998108 4.2267451286 6.5169005394 445 17.7600000000 0.0079429168 0.0060618947 0.0091351802 0.0078367850 0.0058740000 0.0003960000 0.0026700000 0.0000030000 0.0000040000 0.0021940000 14113149 96830484 509673472 4.3660683632 4.2239298820 6.5087947845 446 17.8000000000 0.0080221100 0.0060662898 0.0091351802 0.0078279912 0.0065250000 0.0003950000 0.0044510000 0.0000010000 0.0000030000 0.0010740000 14115925 96830484 509673472 4.3761963844 4.2241234779 6.4996829033 447 17.8400000000 0.0077645662 0.0060700890 0.0091351802 0.0078236018 0.0068140000 0.0003970000 0.0043360000 0.0000040000 0.0000030000 0.0014720000 14118701 96830484 509673472 4.3836765289 4.2211017609 6.4918394089 448 17.8800000000 0.0079199476 0.0060742182 0.0091351802 0.0078149197 0.0043980000 0.0003960000 0.0023170000 0.0000010000 0.0000030000 0.0010740000 14121477 96830484 509673472 4.3914966583 4.2191653252 6.4843926430 449 17.9200000000 0.0080029164 0.0060785137 0.0091351802 0.0078064169 0.0076510000 0.0003970000 0.0044220000 0.0000040000 0.0000030000 0.0022180000 14124253 96830484 509673472 4.3996429443 4.2173199654 6.4763746262 450 17.9600000000 0.0079508293 0.0060826744 0.0091351802 0.0077989529 0.0065080000 0.0003940000 0.0044210000 0.0000000000 0.0000040000 0.0010760000 14127029 96830484 509673472 4.4062380791 4.2131223679 6.4705810547 451 18.0000000000 0.0077521862 0.0060863762 0.0091351802 0.0078022423 0.0076360000 0.0003960000 0.0049920000 0.0000040000 0.0000040000 0.0014830000 14129805 96830484 509673472 4.4154338837 4.2126736641 6.4646272659 452 18.0400000000 0.0078977384 0.0060903837 0.0091351802 0.0077961823 0.0058970000 0.0004090000 0.0037540000 0.0000010000 0.0000040000 0.0010920000 14132581 96830484 509673472 4.4255423546 4.2127766609 6.4580779076 453 18.0800000000 0.0078627691 0.0060942962 0.0091351802 0.0077875609 0.0067600000 0.0003970000 0.0033820000 0.0000030000 0.0000020000 0.0023500000 14135357 96830484 509673472 4.4330635071 4.2094402313 6.4514865875 454 18.1200000000 0.0077575836 0.0060979598 0.0091351802 0.0077867958 0.0061850000 0.0003950000 0.0040850000 0.0000010000 0.0000040000 0.0010810000 14138133 96830484 509673472 4.4429168701 4.2086572647 6.4458513260 455 18.1600000000 0.0077107255 0.0061015044 0.0091351802 0.0077794257 0.0069150000 0.0003970000 0.0044320000 0.0000040000 0.0000030000 0.0014610000 14140909 96830484 509673472 4.4531550407 4.2076830864 6.4406008720 456 18.2000000000 0.0078229466 0.0061052795 0.0091351802 0.0077724978 0.0043690000 0.0003950000 0.0022760000 0.0000000000 0.0000040000 0.0010750000 14143685 96830484 509673472 4.4619107246 4.2045464516 6.4340710640 457 18.2400000000 0.0077467612 0.0061088713 0.0091351802 0.0077736151 0.0069020000 0.0003970000 0.0036530000 0.0000030000 0.0000030000 0.0022240000 14146461 96830484 509673472 4.4709420204 4.2017283440 6.4290819168 458 18.2800000000 0.0077503971 0.0061124555 0.0091351802 0.0077881595 0.0064390000 0.0003970000 0.0043350000 0.0000010000 0.0000040000 0.0010840000 14149237 96830484 509673472 4.4827232361 4.2029695511 6.4261312485 459 18.3200000000 0.0079559600 0.0061164718 0.0091351802 0.0077816548 0.0068470000 0.0003970000 0.0043350000 0.0000030000 0.0000030000 0.0014850000 14152013 96830484 509673472 4.4961409569 4.2053523064 6.4198803902 460 18.3600000000 0.0077024545 0.0061199196 0.0091351802 0.0077814317 0.0054100000 0.0003950000 0.0033110000 0.0000000000 0.0000030000 0.0010790000 14154789 96830484 509673472 4.5040397644 4.2013778687 6.4160194397 461 18.4000000000 0.0076168058 0.0061231666 0.0091351802 0.0077739524 0.0065670000 0.0003960000 0.0033080000 0.0000040000 0.0000030000 0.0022310000 14157565 96830484 509673472 4.5150842667 4.1995186806 6.4130368233 462 18.4400000000 0.0075979745 0.0061263589 0.0091351802 0.0077665776 0.0050730000 0.0003960000 0.0029700000 0.0000010000 0.0000030000 0.0010770000 14160341 96830484 509673472 4.5262737274 4.2004065514 6.4073219299 463 18.4800000000 0.0075927302 0.0061295260 0.0091351802 0.0077608877 0.0058370000 0.0003970000 0.0033060000 0.0000030000 0.0000030000 0.0014960000 14163117 96830484 509673472 4.5355434418 4.1983575821 6.4011416435 464 18.5200000000 0.0076373452 0.0061327756 0.0091351802 0.0077546218 0.0054820000 0.0003950000 0.0033550000 0.0000000000 0.0000030000 0.0010960000 14165893 96830484 509673472 4.5433955193 4.1948413849 6.3981666565 465 18.5600000000 0.0076478859 0.0061360339 0.0091351802 0.0077504926 0.0058890000 0.0003970000 0.0026320000 0.0000030000 0.0000030000 0.0022240000 14168669 96830484 509673472 4.5513367653 4.1907601357 6.3950834274 466 18.6000000000 0.0074602794 0.0061388756 0.0091351802 0.0077670942 0.0047870000 0.0003940000 0.0026580000 0.0000000000 0.0000030000 0.0010980000 14171445 96830484 509673472 4.5628476143 4.1917138100 6.3919367790 467 18.6400000000 0.0073102303 0.0061413839 0.0091351802 0.0077622145 0.0055530000 0.0003950000 0.0030120000 0.0000030000 0.0000030000 0.0015060000 14174221 96830484 509673472 4.5738010406 4.1900820732 6.3892912865 468 18.6800000000 0.0074310768 0.0061441396 0.0091351802 0.0077638383 0.0062150000 0.0003960000 0.0040680000 0.0000010000 0.0000030000 0.0010990000 14176997 96830484 509673472 4.5838475227 4.1866078377 6.3884840012 469 18.7200000000 0.0074154534 0.0061468503 0.0091351802 0.0077859713 0.0065970000 0.0003970000 0.0033460000 0.0000030000 0.0000030000 0.0022140000 14179773 96830484 509673472 4.5931591988 4.1850676537 6.3871607780 470 18.7600000000 0.0074397265 0.0061496011 0.0091351802 0.0078044867 0.0044560000 0.0003970000 0.0023070000 0.0000000000 0.0000040000 0.0011080000 14182549 96830484 509673472 4.6016001701 4.1816930771 6.3867478371 471 18.8000000000 0.0073985984 0.0061522529 0.0091351802 0.0078560872 0.0052040000 0.0003980000 0.0026400000 0.0000030000 0.0000030000 0.0015220000 14185325 96830484 509673472 4.6128129959 4.1799640656 6.3846597672 472 18.8400000000 0.0073946007 0.0061548850 0.0091351802 0.0078999017 0.0051730000 0.0003970000 0.0030130000 0.0000000000 0.0000040000 0.0011190000 14188101 96830484 509673472 4.6234240532 4.1802377701 6.3815937042 473 18.8800000000 0.0074693197 0.0061576639 0.0091351802 0.0079087399 0.0059250000 0.0003940000 0.0025930000 0.0000030000 0.0000030000 0.0022870000 14190877 96830484 509673472 4.6330971718 4.1803116798 6.3775429726 474 18.9200000000 0.0074319080 0.0061603522 0.0091351802 0.0079063582 0.0048060000 0.0003950000 0.0026340000 0.0000010000 0.0000030000 0.0011320000 14193653 96830484 509673472 4.6384119987 4.1788721085 6.3699936867 475 18.9600000000 0.0074722944 0.0061631142 0.0091351802 0.0079050956 0.0048380000 0.0003960000 0.0022650000 0.0000030000 0.0000020000 0.0015260000 14196429 96830484 509673472 4.6472187042 4.1769437790 6.3678359985 476 19.0000000000 0.0075043095 0.0061659318 0.0091351802 0.0079108938 0.0048060000 0.0003950000 0.0026210000 0.0000000000 0.0000030000 0.0011400000 14199205 96830484 509673472 4.6564579010 4.1767673492 6.3651156425 477 19.0400000000 0.0074581881 0.0061686410 0.0091351802 0.0079090810 0.0059710000 0.0003950000 0.0026040000 0.0000030000 0.0000040000 0.0023170000 14201981 96830484 509673472 4.6648988724 4.1767644882 6.3571753502 478 19.0800000000 0.0075200340 0.0061714682 0.0091351802 0.0079029919 0.0051780000 0.0003950000 0.0029770000 0.0000010000 0.0000030000 0.0011530000 14204757 96830484 509673472 4.6776580811 4.1761507988 6.3602948189 479 19.1200000000 0.0075669531 0.0061743815 0.0091351802 0.0078959213 0.0048760000 0.0003970000 0.0022910000 0.0000030000 0.0000030000 0.0015360000 14207533 96830484 509673472 4.6849417686 4.1733856201 6.3590211868 480 19.1600000000 0.0077109174 0.0061775826 0.0091351802 0.0079012486 0.0052460000 0.0003970000 0.0030140000 0.0000000000 0.0000030000 0.0011790000 14210309 96830484 509673472 4.6955070496 4.1714773178 6.3608751297 481 19.2000000000 0.0080176434 0.0061814081 0.0091351802 0.0079168017 0.0067440000 0.0003980000 0.0033600000 0.0000030000 0.0000030000 0.0023240000 14213085 96830484 509673472 4.7033867836 4.1736750603 6.3549947739 482 19.2400000000 0.0079697566 0.0061851184 0.0091351802 0.0079091110 0.0066790000 0.0003960000 0.0044500000 0.0000000000 0.0000040000 0.0011720000 14215861 96830484 509673472 4.7131662369 4.1732430458 6.3561902046 483 19.2800000000 0.0078590689 0.0061885841 0.0091351802 0.0079011295 0.0051740000 0.0003970000 0.0025640000 0.0000030000 0.0000030000 0.0015490000 14218637 96830484 509673472 4.7217345238 4.1709036827 6.3549637794 484 19.3200000000 0.0080566360 0.0061924437 0.0091351802 0.0078977676 0.0067170000 0.0003940000 0.0045010000 0.0000010000 0.0000030000 0.0011630000 14221413 96830484 509673472 4.7269506454 4.1707863808 6.3504276276 485 19.3600000000 0.0082232198 0.0061966309 0.0091351802 0.0078948609 0.0064340000 0.0003970000 0.0030610000 0.0000030000 0.0000030000 0.0023090000 14224189 96830484 509673472 4.7365651131 4.1739192009 6.3460178375 486 19.4000000000 0.0079949908 0.0062003312 0.0091351802 0.0078976986 0.0049330000 0.0003940000 0.0027180000 0.0000000000 0.0000040000 0.0011580000 14226965 96830484 509673472 4.7453379631 4.1768369675 6.3436427116 487 19.4400000000 0.0081571871 0.0062043494 0.0091351802 0.0079399672 0.0053120000 0.0003950000 0.0027000000 0.0000030000 0.0000030000 0.0015470000 14229741 96830484 509673472 4.7514152527 4.1737446785 6.3407478333 488 19.4800000000 0.0080855321 0.0062082043 0.0091351802 0.0079393455 0.0048240000 0.0003970000 0.0026000000 0.0000000000 0.0000040000 0.0011600000 14232517 96830484 509673472 4.7512836456 4.1710939407 6.3332109451 489 19.5200000000 0.0081153046 0.0062121043 0.0091351802 0.0079313627 0.0059780000 0.0003980000 0.0026020000 0.0000040000 0.0000030000 0.0023100000 14235293 96830484 509673472 4.7562661171 4.1705727577 6.3288855553 490 19.5600000000 0.0081001110 0.0062159573 0.0091351802 0.0079235359 0.0045660000 0.0003950000 0.0023550000 0.0000010000 0.0000030000 0.0011460000 14238069 96830484 509673472 4.7603125572 4.1698632240 6.3205952644 491 19.6000000000 0.0080622975 0.0062197177 0.0091351802 0.0079156667 0.0060220000 0.0003950000 0.0034040000 0.0000030000 0.0000020000 0.0015520000 14240845 96830484 509673472 4.7660760880 4.1690659523 6.3162446022 492 19.6400000000 0.0082244007 0.0062237923 0.0091351802 0.0079076931 0.0049170000 0.0003960000 0.0027030000 0.0000010000 0.0000030000 0.0011430000 14243621 96830484 509673472 4.7663931847 4.1695818901 6.3045768738 493 19.6800000000 0.0081568705 0.0062277133 0.0091351802 0.0079049844 0.0060710000 0.0003980000 0.0027020000 0.0000030000 0.0000030000 0.0022950000 14246397 96830484 509673472 4.7684059143 4.1687517166 6.2935690880 494 19.7200000000 0.0080229510 0.0062313474 0.0091351802 0.0079064319 0.0045690000 0.0003970000 0.0023650000 0.0000000000 0.0000030000 0.0011370000 14249173 96830484 509673472 4.7697520256 4.1637191772 6.2863411903 495 19.7600000000 0.0080633191 0.0062350484 0.0091351802 0.0078998208 0.0056650000 0.0003950000 0.0030700000 0.0000030000 0.0000040000 0.0015240000 14251949 96830484 509673472 4.7695498466 4.1607875824 6.2757277489 496 19.8000000000 0.0081157507 0.0062388401 0.0091351802 0.0078959368 0.0045760000 0.0003950000 0.0023670000 0.0000010000 0.0000030000 0.0011400000 14254725 96830484 509673472 4.7682056427 4.1609678268 6.2684803009 497 19.8400000000 0.0080524385 0.0062424892 0.0091351802 0.0078884346 0.0057110000 0.0003940000 0.0023610000 0.0000030000 0.0000030000 0.0022720000 14257501 96830484 509673472 4.7715363503 4.1578588486 6.2621955872 498 19.8800000000 0.0080937240 0.0062462065 0.0091351802 0.0078817247 0.0048090000 0.0003980000 0.0026050000 0.0000000000 0.0000030000 0.0011310000 14260277 96830484 509673472 4.7698354721 4.1567740440 6.2512321472 499 19.9200000000 0.0081861103 0.0062500941 0.0091351802 0.0078738821 0.0051830000 0.0003970000 0.0025780000 0.0000030000 0.0000030000 0.0015230000 14263053 96830484 509673472 4.7707886696 4.1555590630 6.2446579933 500 19.9600000000 0.0081768297 0.0062539476 0.0091351802 0.0078662410 0.0049240000 0.0003960000 0.0027210000 0.0000000000 0.0000030000 0.0011290000 14265829 96830484 509673472 4.7706351280 4.1541814804 6.2343664169 501 20.0000000000 0.0082747182 0.0062579811 0.0091351802 0.0078590819 0.0063800000 0.0003950000 0.0030550000 0.0000040000 0.0000030000 0.0022370000 14268605 96830484 509673472 4.7714900970 4.1525149345 6.2237076759 502 20.0400000000 0.0081732366 0.0062617963 0.0091351802 0.0078513418 0.0044460000 0.0003970000 0.0022340000 0.0000010000 0.0000030000 0.0011280000 14271381 96830484 509673472 4.7748017311 4.1500830650 6.2177195549 503 20.0800000000 0.0081220027 0.0062654945 0.0091351802 0.0078446553 0.0055140000 0.0003950000 0.0029460000 0.0000030000 0.0000030000 0.0014870000 14274157 96830484 509673472 4.7768664360 4.1501765251 6.2048945427 504 20.1200000000 0.0082678292 0.0062694674 0.0091351802 0.0078377818 0.0059920000 0.0003990000 0.0038010000 0.0000000000 0.0000030000 0.0011050000 14276933 96830484 509673472 4.7755236626 4.1470670700 6.1943273544 505 20.1600000000 0.0082223369 0.0062733345 0.0091351802 0.0078334719 0.0064130000 0.0003960000 0.0031050000 0.0000030000 0.0000030000 0.0022210000 14279709 96830484 509673472 4.7714524269 4.1451625824 6.1814012527 506 20.2000000000 0.0084591173 0.0062776542 0.0091351802 0.0078301477 0.0052760000 0.0003940000 0.0030990000 0.0000010000 0.0000030000 0.0010940000 14282485 96830484 509673472 4.7707886696 4.1479835510 6.1724123955 507 20.2400000000 0.0084900158 0.0062820178 0.0091351802 0.0078287712 0.0055430000 0.0003960000 0.0029610000 0.0000030000 0.0000030000 0.0014900000 14285261 96830484 509673472 4.7709856033 4.1490192413 6.1610789299 508 20.2800000000 0.0083995694 0.0062861863 0.0091351802 0.0078340411 0.0049340000 0.0003940000 0.0027310000 0.0000010000 0.0000040000 0.0011150000 14288037 96830484 509673472 4.7636222839 4.1464247704 6.1515045166 509 20.3200000000 0.0083845006 0.0062903087 0.0091351802 0.0078279726 0.0060250000 0.0003980000 0.0027360000 0.0000030000 0.0000030000 0.0021920000 14290813 96830484 509673472 4.7673354149 4.1452345848 6.1419286728 510 20.3600000000 0.0084520821 0.0062945474 0.0091351802 0.0078205729 0.0049660000 0.0003950000 0.0027590000 0.0000010000 0.0000040000 0.0011030000 14293589 96830484 509673472 4.7717137337 4.1464204788 6.1270575523 511 20.4000000000 0.0084441761 0.0062987542 0.0091351802 0.0078140358 0.0049440000 0.0003960000 0.0023820000 0.0000040000 0.0000030000 0.0014630000 14296365 96830484 509673472 4.7746062279 4.1502981186 6.1147265434 512 20.4400000000 0.0085134516 0.0063030797 0.0091351802 0.0078253559 0.0053230000 0.0003950000 0.0031230000 0.0000000000 0.0000040000 0.0011000000 14299141 96830484 509673472 4.7712345123 4.1509475708 6.1017856598 513 20.4800000000 0.0086237658 0.0063076035 0.0091351802 0.0078320443 0.0060440000 0.0003980000 0.0027270000 0.0000040000 0.0000030000 0.0022000000 14351069 96830484 509673472 4.7759599686 4.1494607925 6.0905556679 514 20.5200000000 0.0086605484 0.0063121812 0.0091351802 0.0078261438 0.0049820000 0.0003970000 0.0027590000 0.0000000000 0.0000040000 0.0011040000 14456245 96830484 509673472 4.7774095535 4.1509890556 6.0789632797 515 20.5600000000 0.0087015498 0.0063168208 0.0091351802 0.0078259680 0.0053490000 0.0003970000 0.0027520000 0.0000030000 0.0000030000 0.0014860000 14459021 96830484 509673472 4.7826809883 4.1531939507 6.0665922165 516 20.6000000000 0.0087606786 0.0063215569 0.0091351802 0.0078358264 0.0049800000 0.0003950000 0.0027560000 0.0000000000 0.0000040000 0.0011130000 14461797 96830484 509673472 4.7855682373 4.1523876190 6.0530118942 517 20.6400000000 0.0088112196 0.0063263725 0.0091351802 0.0078390466 0.0061020000 0.0003970000 0.0027800000 0.0000030000 0.0000030000 0.0021950000 14464573 96830484 509673472 4.7812833786 4.1500720978 6.0541625023 518 20.6800000000 0.0086953649 0.0063309459 0.0091351802 0.0078317391 0.0057640000 0.0004070000 0.0035290000 0.0000000000 0.0000030000 0.0011110000 14467349 96830484 509673472 4.7955279350 4.1502113342 6.0333614349 519 20.7200000000 0.0087861931 0.0063356766 0.0091351802 0.0078253981 0.0053580000 0.0003970000 0.0027680000 0.0000030000 0.0000030000 0.0014770000 14470125 96830484 509673472 4.7864437103 4.1529822350 6.0374698639 520 20.7600000000 0.0088223740 0.0063404587 0.0091351802 0.0078297346 0.0068100000 0.0003940000 0.0046060000 0.0000000000 0.0000040000 0.0010930000 14472901 96830484 509673472 4.7793974876 4.1547803879 6.0376439095 521 20.8000000000 0.0087168086 0.0063450198 0.0091351802 0.0078436947 0.0060180000 0.0003970000 0.0027310000 0.0000030000 0.0000030000 0.0021660000 14475677 96830484 509673472 4.7771024704 4.1525921822 6.0300731659 522 20.8400000000 0.0088139474 0.0063497496 0.0091351802 0.0078406754 0.0046240000 0.0003960000 0.0024160000 0.0000010000 0.0000040000 0.0010950000 14478453 96830484 509673472 4.7787184715 4.1489777565 6.0234999657 523 20.8800000000 0.0087479251 0.0063543350 0.0091351802 0.0078337849 0.0049850000 0.0003970000 0.0023970000 0.0000030000 0.0000030000 0.0014630000 14481229 96830484 509673472 4.7683458328 4.1477532387 6.0292539597 524 20.9200000000 0.0087871654 0.0063589778 0.0091351802 0.0078296915 0.0049850000 0.0003970000 0.0027710000 0.0000010000 0.0000030000 0.0010980000 14484005 96830484 509673472 4.7851586342 4.1480789185 6.0077056885 525 20.9600000000 0.0087143574 0.0063634642 0.0091351802 0.0078222397 0.0056850000 0.0003960000 0.0023910000 0.0000030000 0.0000030000 0.0021750000 14486781 96830484 509673472 4.7849178314 4.1473507881 6.0027265549 526 21.0000000000 0.0086346474 0.0063677821 0.0091351802 0.0078152247 0.0049620000 0.0003980000 0.0027480000 0.0000000000 0.0000030000 0.0010950000 14489557 96830484 509673472 4.7928900719 4.1437883377 5.9897370338 527 21.0400000000 0.0086461613 0.0063721054 0.0091351802 0.0078157156 0.0056720000 0.0003960000 0.0030940000 0.0000030000 0.0000030000 0.0014600000 14492333 96830484 509673472 4.7939610481 4.1442942619 5.9806342125 528 21.0800000000 0.0087738801 0.0063766542 0.0091351802 0.0078085082 0.0049690000 0.0003950000 0.0027530000 0.0000000000 0.0000030000 0.0010930000 14495109 96830484 509673472 4.7966365814 4.1438608170 5.9758238792 529 21.1200000000 0.0086536994 0.0063809586 0.0091351802 0.0078020471 0.0060490000 0.0003950000 0.0027390000 0.0000040000 0.0000030000 0.0021790000 14497885 96830484 509673472 4.8098773956 4.1417360306 5.9552726746 530 21.1600000000 0.0086644525 0.0063852671 0.0091351802 0.0077974001 0.0056830000 0.0003980000 0.0034660000 0.0000000000 0.0000040000 0.0010900000 14500661 96830484 509673472 4.8064451218 4.1419634819 5.9534840584 531 21.2000000000 0.0087460103 0.0063897129 0.0091351802 0.0077907523 0.0053360000 0.0003960000 0.0027380000 0.0000030000 0.0000030000 0.0014650000 14503437 96830484 509673472 4.8145236969 4.1408677101 5.9383187294 532 21.2400000000 0.0087307543 0.0063941134 0.0091351802 0.0077846682 0.0053420000 0.0003970000 0.0031080000 0.0000000000 0.0000040000 0.0011040000 14506213 96830484 509673472 4.8149604797 4.1395015717 5.9302625656 533 21.2800000000 0.0086800000 0.0063984021 0.0091351802 0.0077786222 0.0060720000 0.0003960000 0.0027490000 0.0000040000 0.0000030000 0.0021910000 14508989 96830484 509673472 4.8135461807 4.1384544373 5.9251823425 534 21.3200000000 0.0088042160 0.0064029074 0.0091351802 0.0077738455 0.0049910000 0.0003950000 0.0027540000 0.0000010000 0.0000030000 0.0011020000 14511765 96830484 509673472 4.8208456039 4.1369023323 5.9098229408 535 21.3600000000 0.0087679354 0.0064073280 0.0091351802 0.0077697227 0.0050200000 0.0003950000 0.0023950000 0.0000040000 0.0000030000 0.0014850000 14514541 96830484 509673472 4.8265252113 4.1390552521 5.8949570656 536 21.4000000000 0.0087472247 0.0064116935 0.0091351802 0.0077633765 0.0050250000 0.0003980000 0.0027770000 0.0000000000 0.0000030000 0.0011080000 14517317 96830484 509673472 4.8240976334 4.1382117271 5.8910775185 537 21.4400000000 0.0089932000 0.0064165008 0.0091351802 0.0077562390 0.0064700000 0.0003970000 0.0031380000 0.0000040000 0.0000030000 0.0021870000 14520093 96830484 509673472 4.8318705559 4.1367402077 5.8738317490 538 21.4800000000 0.0089997808 0.0064213024 0.0091351802 0.0077492383 0.0046820000 0.0004000000 0.0024050000 0.0000000000 0.0000040000 0.0011240000 14522869 96830484 509673472 4.8319997787 4.1366953850 5.8655910492 539 21.5200000000 0.0092123142 0.0064264805 0.0092123142 0.0077421782 0.0072670000 0.0003970000 0.0046460000 0.0000030000 0.0000030000 0.0014750000 14525645 96830484 509673472 4.8303093910 4.1364326477 5.8575897217 540 21.5600000000 0.0094159255 0.0064320165 0.0094159255 0.0077361022 0.0054050000 0.0003980000 0.0031410000 0.0000010000 0.0000040000 0.0011220000 14528421 96830484 509673472 4.8334541321 4.1376519203 5.8429317474 541 21.6000000000 0.0092303716 0.0064371891 0.0094159255 0.0077293595 0.0061010000 0.0003950000 0.0027540000 0.0000030000 0.0000030000 0.0022010000 14531197 96830484 509673472 4.8339939117 4.1392941475 5.8336634636 542 21.6400000000 0.0091242511 0.0064421468 0.0094159255 0.0077270981 0.0054180000 0.0003950000 0.0031580000 0.0000000000 0.0000030000 0.0011170000 14533973 96830484 509673472 4.8363695145 4.1373543739 5.8208608627 543 21.6800000000 0.0091312993 0.0064470992 0.0094159255 0.0077200777 0.0054370000 0.0003960000 0.0027850000 0.0000040000 0.0000030000 0.0015000000 14536749 96830484 509673472 4.8373289108 4.1347770691 5.8155841827 544 21.7200000000 0.0092237750 0.0064522034 0.0094159255 0.0077198805 0.0050400000 0.0003960000 0.0027680000 0.0000010000 0.0000030000 0.0011230000 14539525 96830484 509673472 4.8379201889 4.1355881691 5.8053398132 545 21.7600000000 0.0094288066 0.0064576650 0.0094288066 0.0077164967 0.0061380000 0.0003960000 0.0027800000 0.0000030000 0.0000030000 0.0022010000 14542301 96830484 509673472 4.8407568932 4.1342000961 5.7931709290 546 21.8000000000 0.0094837183 0.0064632072 0.0094837183 0.0077209119 0.0050580000 0.0003950000 0.0027800000 0.0000010000 0.0000030000 0.0011270000 14545077 96830484 509673472 4.8422369957 4.1348857880 5.7865090370 547 21.8400000000 0.0095994147 0.0064689407 0.0095994147 0.0077189207 0.0054400000 0.0003960000 0.0027940000 0.0000030000 0.0000030000 0.0014890000 14547853 96830484 509673472 4.8442368507 4.1367926598 5.7747502327 548 21.8800000000 0.0095542790 0.0064745709 0.0095994147 0.0077120103 0.0050750000 0.0003970000 0.0027830000 0.0000000000 0.0000040000 0.0011350000 14550629 96830484 509673472 4.8409194946 4.1370506287 5.7714562416 549 21.9200000000 0.0091554038 0.0064794540 0.0095994147 0.0077054213 0.0061520000 0.0003940000 0.0027890000 0.0000030000 0.0000030000 0.0022020000 14553405 96830484 509673472 4.8420424461 4.1360449791 5.7651491165 550 21.9600000000 0.0092881676 0.0064845608 0.0095994147 0.0076990704 0.0047550000 0.0003980000 0.0024310000 0.0000010000 0.0000040000 0.0011400000 14556181 96830484 509673472 4.8415980339 4.1383247375 5.7582468987 551 22.0000000000 0.0094120018 0.0064898737 0.0095994147 0.0076933933 0.0058180000 0.0003960000 0.0031460000 0.0000030000 0.0000030000 0.0015010000 14558957 96830484 509673472 4.8420891762 4.1383814812 5.7502007484 552 22.0400000000 0.0097538820 0.0064957868 0.0097538820 0.0076866198 0.0047210000 0.0003970000 0.0024010000 0.0000000000 0.0000040000 0.0011460000 14561733 96830484 509673472 4.8453960419 4.1400194168 5.7418670654 553 22.0800000000 0.0097908294 0.0065017453 0.0097908294 0.0076831417 0.0061680000 0.0003960000 0.0027660000 0.0000030000 0.0000030000 0.0022250000 14564509 96830484 509673472 4.8439669609 4.1400570869 5.7394895554 554 22.1200000000 0.0095561575 0.0065072586 0.0097908294 0.0076772028 0.0050700000 0.0003950000 0.0027620000 0.0000000000 0.0000040000 0.0011420000 14567285 96830484 509673472 4.8443470001 4.1382074356 5.7326140404 555 22.1600000000 0.0095349252 0.0065127139 0.0097908294 0.0076708930 0.0053330000 0.0003970000 0.0026320000 0.0000030000 0.0000030000 0.0015300000 14570061 96830484 509673472 4.8450918198 4.1407017708 5.7244520187 556 22.2000000000 0.0100431945 0.0065190637 0.0100431945 0.0076671176 0.0050730000 0.0003950000 0.0027580000 0.0000000000 0.0000030000 0.0011530000 14572837 96830484 509673472 4.8449101448 4.1436681747 5.7155885696 557 22.2400000000 0.0101697007 0.0065256178 0.0101697007 0.0076747355 0.0056560000 0.0003950000 0.0022590000 0.0000030000 0.0000030000 0.0022220000 14575613 96830484 509673472 4.8444256783 4.1410546303 5.7114071846 558 22.2800000000 0.0102632223 0.0065323160 0.0102632223 0.0076679940 0.0047200000 0.0003960000 0.0023890000 0.0000000000 0.0000030000 0.0011610000 14578389 96830484 509673472 4.8423857689 4.1385750771 5.7053842545 559 22.3200000000 0.0100698434 0.0065386443 0.0102632223 0.0076632657 0.0051110000 0.0003960000 0.0023800000 0.0000030000 0.0000030000 0.0015540000 14581165 96830484 509673472 4.8418793678 4.1407890320 5.7001104355 560 22.3600000000 0.0102633834 0.0065452956 0.0102633834 0.0076576424 0.0049630000 0.0003980000 0.0026270000 0.0000000000 0.0000030000 0.0011610000 14583941 96830484 509673472 4.8406429291 4.1408562660 5.6966810226 561 22.4000000000 0.0104557294 0.0065522661 0.0104557294 0.0076517710 0.0057890000 0.0003960000 0.0023540000 0.0000030000 0.0000030000 0.0022580000 14586717 96830484 509673472 4.8440642357 4.1399374008 5.6882143021 562 22.4400000000 0.0109123262 0.0065600242 0.0109123262 0.0076451726 0.0050870000 0.0003980000 0.0027490000 0.0000000000 0.0000040000 0.0011650000 14589493 96830484 509673472 4.8425641060 4.1417021751 5.6849908829 563 22.4800000000 0.0110126510 0.0065679330 0.0110126510 0.0076408308 0.0054930000 0.0003980000 0.0027690000 0.0000030000 0.0000030000 0.0015410000 14592269 96830484 509673472 4.8447556496 4.1417579651 5.6756491661 564 22.5200000000 0.0108684907 0.0065755581 0.0110126510 0.0076375898 0.0047350000 0.0003950000 0.0023990000 0.0000000000 0.0000040000 0.0011630000 14595045 96830484 509673472 4.8449726105 4.1396164894 5.6699624062 565 22.5600000000 0.0108590955 0.0065831396 0.0110126510 0.0076309152 0.0058080000 0.0003960000 0.0024010000 0.0000030000 0.0000030000 0.0022260000 14597821 96830484 509673472 4.8483200073 4.1370558739 5.6584997177 566 22.6000000000 0.0111116702 0.0065911405 0.0111116702 0.0076257688 0.0069750000 0.0003950000 0.0046380000 0.0000000000 0.0000040000 0.0011570000 14600597 96830484 509673472 4.8491406441 4.1363415718 5.6516509056 567 22.6400000000 0.0110893371 0.0065990738 0.0111116702 0.0076198479 0.0047450000 0.0003960000 0.0020340000 0.0000030000 0.0000030000 0.0015250000 14603373 96830484 509673472 4.8505125046 4.1357746124 5.6452493668 568 22.6800000000 0.0113046737 0.0066073583 0.0113046737 0.0076134181 0.0055170000 0.0003960000 0.0031670000 0.0000010000 0.0000030000 0.0011630000 14606149 96830484 509673472 4.8527808189 4.1337919235 5.6363058090 569 22.7200000000 0.0115973949 0.0066161282 0.0115973949 0.0076090205 0.0060570000 0.0003950000 0.0026600000 0.0000040000 0.0000030000 0.0022100000 14608925 96830484 509673472 4.8549261093 4.1324467659 5.6257057190 570 22.7600000000 0.0117686950 0.0066251677 0.0117686950 0.0076053461 0.0047730000 0.0003950000 0.0024320000 0.0000000000 0.0000040000 0.0011560000 14611701 96830484 509673472 4.8538236618 4.1351041794 5.6157836914 571 22.8000000000 0.0118130222 0.0066342533 0.0118130222 0.0076001483 0.0055190000 0.0003950000 0.0028010000 0.0000040000 0.0000030000 0.0015300000 14614477 96830484 509673472 4.8525524139 4.1364321709 5.6072950363 572 22.8400000000 0.0120342951 0.0066436939 0.0120342951 0.0075982320 0.0046350000 0.0003960000 0.0023060000 0.0000000000 0.0000030000 0.0011430000 14617253 96830484 509673472 4.8525023460 4.1326227188 5.5987510681 573 22.8800000000 0.0115045346 0.0066521771 0.0120342951 0.0075937309 0.0056840000 0.0003990000 0.0023010000 0.0000030000 0.0000020000 0.0021860000 14620029 96830484 509673472 4.8515973091 4.1319556236 5.5901150703 574 22.9200000000 0.0111208642 0.0066599623 0.0120342951 0.0075871903 0.0050110000 0.0003950000 0.0026670000 0.0000010000 0.0000040000 0.0011540000 14622805 96830484 509673472 4.8487176895 4.1332230568 5.5836987495 575 22.9600000000 0.0106530795 0.0066669068 0.0120342951 0.0075823879 0.0054790000 0.0003950000 0.0027780000 0.0000050000 0.0000030000 0.0015070000 14625581 96830484 509673472 4.8473682404 4.1297512054 5.5744118690 576 23.0000000000 0.0107001122 0.0066739089 0.0120342951 0.0075776165 0.0051030000 0.0003970000 0.0027830000 0.0000000000 0.0000040000 0.0011290000 14628357 96830484 509673472 4.8464407921 4.1262869835 5.5671391487 577 23.0400000000 0.0107696690 0.0066810073 0.0120342951 0.0075788370 0.0056760000 0.0004000000 0.0022990000 0.0000030000 0.0000030000 0.0021680000 14631133 96830484 509673472 4.8450922966 4.1279721260 5.5575985909 578 23.0800000000 0.0109205823 0.0066883422 0.0120342951 0.0075722905 0.0045020000 0.0003960000 0.0021740000 0.0000000000 0.0000040000 0.0011280000 14633909 96830484 509673472 4.8441567421 4.1274585724 5.5480265617 579 23.1200000000 0.0108794160 0.0066955806 0.0120342951 0.0075658412 0.0050010000 0.0003970000 0.0023030000 0.0000030000 0.0000020000 0.0014990000 14636685 96830484 509673472 4.8435950279 4.1246747971 5.5389022827 580 23.1600000000 0.0111180758 0.0067032056 0.0120342951 0.0075609640 0.0053810000 0.0003990000 0.0030500000 0.0000000000 0.0000040000 0.0011300000 14639461 96830484 509673472 4.8429803848 4.1238832474 5.5285511017 581 23.2000000000 0.0109911775 0.0067105860 0.0120342951 0.0075547725 0.0060530000 0.0003950000 0.0026760000 0.0000030000 0.0000030000 0.0021760000 14642237 96830484 509673472 4.8414020538 4.1239733696 5.5192728043 582 23.2400000000 0.0109506771 0.0067178713 0.0120342951 0.0075487456 0.0050100000 0.0003950000 0.0026920000 0.0000000000 0.0000030000 0.0011200000 14645013 96830484 509673472 4.8400030136 4.1217627525 5.5082063675 583 23.2800000000 0.0111306114 0.0067254404 0.0120342951 0.0075427168 0.0050090000 0.0003960000 0.0023140000 0.0000030000 0.0000030000 0.0014890000 14647789 96830484 509673472 4.8399524689 4.1185994148 5.4986672401 584 23.3200000000 0.0113337059 0.0067333312 0.0120342951 0.0075431799 0.0058830000 0.0003970000 0.0028340000 0.0000010000 0.0000030000 0.0016540000 14650565 96830484 509673472 4.8379011154 4.1192336082 5.4873290062 585 23.3600000000 0.0114487484 0.0067413918 0.0120342951 0.0075381104 0.0061080000 0.0004090000 0.0027000000 0.0000030000 0.0000030000 0.0021520000 14653341 96830484 509673472 4.8366246223 4.1185526848 5.4758863449 586 23.4000000000 0.0115260100 0.0067495567 0.0120342951 0.0075339081 0.0046810000 0.0003990000 0.0023300000 0.0000000000 0.0000040000 0.0011360000 14656117 96830484 509673472 4.8362579346 4.1153268814 5.4647402763 587 23.4400000000 0.0116041200 0.0067578268 0.0120342951 0.0075380802 0.0052800000 0.0003970000 0.0025780000 0.0000030000 0.0000030000 0.0014860000 14658893 96830484 509673472 4.8348450661 4.1148467064 5.4551668167 588 23.4800000000 0.0118472483 0.0067664823 0.0120342951 0.0075459083 0.0046900000 0.0003970000 0.0023440000 0.0000000000 0.0000040000 0.0011330000 14661669 96830484 509673472 4.8321719170 4.1171193123 5.4275417328 589 23.5200000000 0.0119001968 0.0067751982 0.0120342951 0.0075401524 0.0058340000 0.0003950000 0.0024710000 0.0000030000 0.0000020000 0.0021430000 14664445 96830484 509673472 4.8303041458 4.1186089516 5.4176573753 590 23.5600000000 0.0120675182 0.0067841683 0.0120675182 0.0075376807 0.0047120000 0.0003960000 0.0023680000 0.0000000000 0.0000040000 0.0011280000 14667221 96830484 509673472 4.8279943466 4.1204395294 5.4060559273 591 23.6000000000 0.0120852003 0.0067931379 0.0120852003 0.0075418690 0.0047900000 0.0003960000 0.0021000000 0.0000030000 0.0000030000 0.0014740000 14669997 96830484 509673472 4.8267893791 4.1181726456 5.3948230743 592 23.6400000000 0.0121728946 0.0068022253 0.0121728946 0.0075357705 0.0048320000 0.0003960000 0.0024850000 0.0000000000 0.0000030000 0.0011330000 14672773 96830484 509673472 4.8256993294 4.1156506538 5.3806986809 593 23.6800000000 0.0122769726 0.0068114576 0.0122769726 0.0075314623 0.0058510000 0.0003950000 0.0025000000 0.0000030000 0.0000020000 0.0021310000 14675549 96830484 509673472 4.8238930702 4.1156377792 5.3681144714 594 23.7200000000 0.0124368705 0.0068209280 0.0124368705 0.0075272643 0.0071560000 0.0003990000 0.0048030000 0.0000000000 0.0000030000 0.0011290000 14678325 96830484 509673472 4.8224229813 4.1156444550 5.3561639786 595 23.7600000000 0.0122824078 0.0068301069 0.0124368705 0.0075240728 0.0050690000 0.0003960000 0.0023900000 0.0000040000 0.0000030000 0.0014500000 14681101 96830484 509673472 4.8198084831 4.1146140099 5.3472223282 596 23.8000000000 0.0122773331 0.0068392466 0.0124368705 0.0075233343 0.0047400000 0.0003950000 0.0023930000 0.0000000000 0.0000030000 0.0011270000 14683877 96830484 509673472 4.8180212975 4.1159453392 5.3342428207 597 23.8400000000 0.0123880198 0.0068485410 0.0124368705 0.0075172961 0.0058510000 0.0003960000 0.0025110000 0.0000030000 0.0000030000 0.0021070000 14686653 96830484 509673472 4.8152675629 4.1177196503 5.3236265182 598 23.8800000000 0.0125186639 0.0068580228 0.0125186639 0.0075118824 0.0048750000 0.0003990000 0.0025210000 0.0000010000 0.0000030000 0.0011200000 14689429 96830484 509673472 4.8135895729 4.1176290512 5.3098649979 599 23.9200000000 0.0124669783 0.0068673867 0.0125186639 0.0075060302 0.0054790000 0.0003970000 0.0027790000 0.0000040000 0.0000030000 0.0014630000 14692205 96830484 509673472 4.8105592728 4.1196289062 5.2996826172 600 23.9600000000 0.0127330087 0.0068771627 0.0127330087 0.0075031041 0.0051240000 0.0003950000 0.0027800000 0.0000010000 0.0000030000 0.0011220000 14694981 96830484 509673472 4.8085412979 4.1199779510 5.2882843018 601 24.0000000000 0.0127027510 0.0068868559 0.0127330087 0.0074975038 0.0057210000 0.0003960000 0.0023870000 0.0000040000 0.0000030000 0.0021000000 14697757 96830484 509673472 4.8055014610 4.1200909615 5.2779889107 602 24.0400000000 0.0127688302 0.0068966266 0.0127688302 0.0074913590 0.0048660000 0.0003970000 0.0025290000 0.0000000000 0.0000030000 0.0011030000 14700533 96830484 509673472 4.8034987450 4.1201338768 5.2653679848 603 24.0800000000 0.0127280932 0.0069062974 0.0127688302 0.0074851852 0.0050600000 0.0003950000 0.0024010000 0.0000030000 0.0000030000 0.0014230000 14703309 96830484 509673472 4.8000731468 4.1204562187 5.2564530373 604 24.1200000000 0.0126338508 0.0069157801 0.0127688302 0.0074789862 0.0043470000 0.0003960000 0.0019930000 0.0000010000 0.0000030000 0.0011200000 14706085 96830484 509673472 4.7967000008 4.1212320328 5.2485322952 605 24.1600000000 0.0124688102 0.0069249586 0.0127688302 0.0074731705 0.0057000000 0.0003960000 0.0023870000 0.0000030000 0.0000040000 0.0020740000 14708861 96830484 509673472 4.7938299179 4.1201434135 5.2399082184 606 24.2000000000 0.0124222841 0.0069340301 0.0127688302 0.0074672063 0.0044790000 0.0003970000 0.0021410000 0.0000000000 0.0000030000 0.0010950000 14711637 96830484 509673472 4.7913403511 4.1176991463 5.2323770523 607 24.2400000000 0.0124074165 0.0069430472 0.0127688302 0.0074614807 0.0048020000 0.0003960000 0.0021330000 0.0000030000 0.0000030000 0.0014260000 14714413 96830484 509673472 4.7891664505 4.1170983315 5.2196526527 608 24.2800000000 0.0124505330 0.0069521056 0.0127688302 0.0074557126 0.0055030000 0.0003970000 0.0031770000 0.0000010000 0.0000030000 0.0010880000 14717189 96830484 509673472 4.7860822678 4.1186332703 5.2108988762 609 24.3200000000 0.0124281896 0.0069610975 0.0127688302 0.0074514513 0.0056910000 0.0003960000 0.0023950000 0.0000040000 0.0000030000 0.0020500000 14719965 96830484 509673472 4.7844333649 4.1158390045 5.2018589973 610 24.3600000000 0.0127072660 0.0069705175 0.0127688302 0.0074456369 0.0068420000 0.0003960000 0.0044910000 0.0000000000 0.0000040000 0.0010890000 14722741 96830484 509673472 4.7824144363 4.1120681763 5.1933956146 611 24.4000000000 0.0127462596 0.0069799704 0.0127688302 0.0074441566 0.0050890000 0.0003980000 0.0024070000 0.0000040000 0.0000030000 0.0013980000 14725517 96830484 509673472 4.7810440063 4.1113514900 5.1798267365 612 24.4400000000 0.0127553549 0.0069894073 0.0127688302 0.0074392505 0.0051660000 0.0003970000 0.0028090000 0.0000000000 0.0000040000 0.0010670000 14728293 96830484 509673472 4.7781581879 4.1117401123 5.1705746651 613 24.4800000000 0.0127998758 0.0069988860 0.0127998758 0.0074338918 0.0056810000 0.0003980000 0.0023920000 0.0000030000 0.0000030000 0.0020270000 14731069 96830484 509673472 4.7759962082 4.1098179817 5.1632061005 614 24.5200000000 0.0129273906 0.0070085416 0.0129273906 0.0074279345 0.0048850000 0.0003970000 0.0025510000 0.0000010000 0.0000040000 0.0010780000 14733845 96830484 509673472 4.7741498947 4.1074929237 5.1499552727 615 24.5600000000 0.0129558891 0.0070182121 0.0129558891 0.0074222711 0.0050480000 0.0003950000 0.0024070000 0.0000030000 0.0000030000 0.0013870000 14736621 96830484 509673472 4.7727651596 4.1061968803 5.1416163445 616 24.6000000000 0.0130465915 0.0070279984 0.0130465915 0.0074171042 0.0049000000 0.0003970000 0.0025550000 0.0000000000 0.0000030000 0.0010860000 14739397 96830484 509673472 4.7712521553 4.1034126282 5.1304769516 617 24.6400000000 0.0130602419 0.0070377751 0.0130602419 0.0074161180 0.0058310000 0.0003980000 0.0025410000 0.0000040000 0.0000030000 0.0020260000 14742173 96830484 509673472 4.7693395615 4.1018471718 5.1195974350 618 24.6800000000 0.0132361418 0.0070478049 0.0132361418 0.0074163777 0.0047670000 0.0003980000 0.0024290000 0.0000010000 0.0000030000 0.0010800000 14744949 96830484 509673472 4.7682433128 4.1001553535 5.1066617966 619 24.7200000000 0.0130848624 0.0070575578 0.0132361418 0.0074178035 0.0050740000 0.0003950000 0.0024310000 0.0000040000 0.0000030000 0.0013690000 14747725 96830484 509673472 4.7670559883 4.0992617607 5.0915164948 620 24.7600000000 0.0132214520 0.0070674995 0.0132361418 0.0074150570 0.0047630000 0.0003990000 0.0024360000 0.0000000000 0.0000030000 0.0010640000 14750501 96830484 509673472 4.7641448975 4.1002244949 5.0825090408 621 24.8000000000 0.0132581200 0.0070774683 0.0132581200 0.0074092108 0.0057770000 0.0003970000 0.0025580000 0.0000030000 0.0000030000 0.0019460000 14753277 96830484 509673472 4.7624368668 4.0997071266 5.0721735954 622 24.8400000000 0.0131494971 0.0070872304 0.0132581200 0.0074034850 0.0052800000 0.0003980000 0.0029660000 0.0000000000 0.0000040000 0.0010450000 14756053 96830484 509673472 4.7605323792 4.0975799561 5.0613417625 623 24.8800000000 0.0134962201 0.0070975177 0.0134962201 0.0074008772 0.0050390000 0.0003980000 0.0024250000 0.0000030000 0.0000030000 0.0013430000 14758829 96830484 509673472 4.7582101822 4.0983471870 5.0503473282 624 24.9200000000 0.0136615811 0.0071080371 0.0136615811 0.0073955549 0.0048860000 0.0004010000 0.0025700000 0.0000000000 0.0000040000 0.0010290000 14761605 96830484 509673472 4.7552547455 4.0992379189 5.0390462875 625 24.9600000000 0.0138031645 0.0071187493 0.0138031645 0.0073897695 0.0061760000 0.0003980000 0.0029470000 0.0000040000 0.0000030000 0.0019550000 14764381 96830484 509673472 4.7524714470 4.0976605415 5.0289955139 626 25.0000000000 0.0138438828 0.0071294923 0.0138438828 0.0073847030 0.0048500000 0.0003990000 0.0025590000 0.0000000000 0.0000040000 0.0010180000 14767157 96830484 509673472 4.7505235672 4.0956740379 5.0196852684 627 25.0400000000 0.0139378747 0.0071403510 0.0139378747 0.0073815432 0.0051180000 0.0003990000 0.0025380000 0.0000030000 0.0000030000 0.0013090000 14769933 96830484 509673472 4.7477278709 4.0953378677 5.0092663765 628 25.0800000000 0.0138593419 0.0071510500 0.0139378747 0.0073759369 0.0048110000 0.0003970000 0.0025470000 0.0000000000 0.0000030000 0.0009970000 14772709 96830484 509673472 4.7439041138 4.0972361565 4.9998474121 629 25.1200000000 0.0138628390 0.0071617206 0.0139378747 0.0073726184 0.0057220000 0.0003960000 0.0025430000 0.0000040000 0.0000030000 0.0019040000 14775485 96830484 509673472 4.7413039207 4.0965409279 4.9936046600 630 25.1600000000 0.0139985895 0.0071725727 0.0139985895 0.0073675128 0.0052130000 0.0004010000 0.0029470000 0.0000010000 0.0000040000 0.0009880000 14778261 96830484 509673472 4.7374000549 4.0965948105 4.9841237068 631 25.2000000000 0.0139078964 0.0071832468 0.0139985895 0.0073639774 0.0053600000 0.0004020000 0.0028020000 0.0000030000 0.0000040000 0.0012780000 14781037 96830484 509673472 4.7334299088 4.0974078178 4.9755311012 632 25.2400000000 0.0140409768 0.0071940976 0.0140409768 0.0073629465 0.0048110000 0.0003990000 0.0025670000 0.0000010000 0.0000030000 0.0009680000 14783813 96830484 509673472 4.7296419144 4.0965313911 4.9698543549 633 25.2800000000 0.0136087937 0.0072042314 0.0140409768 0.0073589448 0.0056620000 0.0003990000 0.0025560000 0.0000030000 0.0000030000 0.0018250000 14786589 96830484 509673472 4.7255892754 4.0975079536 4.9600434303 634 25.3200000000 0.0145192165 0.0072157693 0.0145192165 0.0073556712 0.0070510000 0.0004010000 0.0048190000 0.0000000000 0.0000030000 0.0009530000 14789365 96830484 509673472 4.7204122543 4.0991845131 4.9509291649 635 25.3600000000 0.0144749107 0.0072272010 0.0145192165 0.0073582980 0.0070620000 0.0003990000 0.0045240000 0.0000040000 0.0000030000 0.0012490000 14792141 96830484 509673472 4.7163820267 4.0990452766 4.9454393387 636 25.4000000000 0.0144271674 0.0072385217 0.0145192165 0.0073583720 0.0052010000 0.0003990000 0.0029570000 0.0000000000 0.0000040000 0.0009550000 14794917 96830484 509673472 4.7129201889 4.0973811150 4.9363303185 637 25.4400000000 0.0145302964 0.0072499687 0.0145302964 0.0073532512 0.0062880000 0.0004000000 0.0031980000 0.0000030000 0.0000020000 0.0017990000 14797693 96830484 509673472 4.7084317207 4.0978603363 4.9292750359 638 25.4800000000 0.0145493150 0.0072614097 0.0145493150 0.0073489172 0.0043940000 0.0003990000 0.0021700000 0.0000010000 0.0000040000 0.0009390000 14800469 96830484 509673472 4.7051048279 4.0961890221 4.9212951660 639 25.5200000000 0.0147157423 0.0072730753 0.0147157423 0.0073433254 0.0058630000 0.0003990000 0.0033420000 0.0000030000 0.0000040000 0.0012300000 14803245 96830484 509673472 4.6999773979 4.0941472054 4.9153556824 640 25.5600000000 0.0148627125 0.0072849341 0.0148627125 0.0073383254 0.0048040000 0.0003990000 0.0025780000 0.0000000000 0.0000040000 0.0009350000 14806021 96830484 509673472 4.6958665848 4.0927677155 4.9091076851 641 25.6000000000 0.0148075856 0.0072966700 0.0148627125 0.0073332641 0.0056440000 0.0004000000 0.0025760000 0.0000030000 0.0000030000 0.0017670000 14808797 96830484 509673472 4.6907815933 4.0916914940 4.9027371407 642 25.6400000000 0.0151452245 0.0073088951 0.0151452245 0.0073286596 0.0055970000 0.0004020000 0.0033720000 0.0000010000 0.0000040000 0.0009280000 14811573 96830484 509673472 4.6854000092 4.0906162262 4.8975005150 643 25.6800000000 0.0150738815 0.0073209713 0.0151452245 0.0073232541 0.0053620000 0.0004010000 0.0028380000 0.0000030000 0.0000030000 0.0012240000 14814349 96830484 509673472 4.6807308197 4.0889797211 4.8910636902 644 25.7200000000 0.0154477619 0.0073335905 0.0154477619 0.0073176725 0.0048040000 0.0004010000 0.0025790000 0.0000000000 0.0000030000 0.0009270000 14817125 96830484 509673472 4.6750264168 4.0880861282 4.8857259750 645 25.7600000000 0.0155672422 0.0073463559 0.0155672422 0.0073122310 0.0064660000 0.0004000000 0.0033590000 0.0000030000 0.0000030000 0.0017870000 14819901 96830484 509673472 4.6700472832 4.0861186981 4.8793778419 646 25.8000000000 0.0158549733 0.0073595271 0.0158549733 0.0073066168 0.0052100000 0.0004010000 0.0029810000 0.0000010000 0.0000040000 0.0009230000 14822677 96830484 509673472 4.6636219025 4.0845289230 4.8751134872 647 25.8400000000 0.0159167517 0.0073727531 0.0159167517 0.0073010288 0.0054840000 0.0004010000 0.0029680000 0.0000040000 0.0000030000 0.0012040000 14825453 96830484 509673472 4.6562800407 4.0850205421 4.8694477081 648 25.8800000000 0.0160860512 0.0073861996 0.0160860512 0.0072987939 0.0052000000 0.0004020000 0.0029750000 0.0000010000 0.0000030000 0.0009120000 14828229 96830484 509673472 4.6495552063 4.0844216347 4.8649697304 649 25.9200000000 0.0161070619 0.0073996370 0.0161070619 0.0072976110 0.0060220000 0.0004020000 0.0029710000 0.0000030000 0.0000030000 0.0017330000 14831005 96830484 509673472 4.6424446106 4.0814356804 4.8599233627 650 25.9600000000 0.0166042857 0.0074137980 0.0166042857 0.0072935505 0.0055680000 0.0004030000 0.0033530000 0.0000010000 0.0000030000 0.0009080000 14833781 96830484 509673472 4.6283740997 4.0748095512 4.8508181572 651 26.0000000000 0.0171406697 0.0074287394 0.0171406697 0.0072946456 0.0050430000 0.0004010000 0.0025470000 0.0000040000 0.0000030000 0.0011870000 14836557 96830484 509673472 4.6109142303 4.0750250816 4.8401579857 652 26.0400000000 0.0175599512 0.0074442781 0.0175599512 0.0072891902 0.0058900000 0.0004030000 0.0031630000 0.0000010000 0.0000050000 0.0011900000 14839333 96830484 509673472 4.6015214920 4.0758838654 4.8340215683 653 26.0800000000 0.0176423900 0.0074598954 0.0176423900 0.0072861654 0.0060690000 0.0004170000 0.0029730000 0.0000040000 0.0000030000 0.0017200000 14842109 96830484 509673472 4.5913109779 4.0786933899 4.8293256760 654 26.1200000000 0.0182823073 0.0074764434 0.0182823073 0.0072926475 0.0052210000 0.0004040000 0.0029910000 0.0000000000 0.0000040000 0.0008990000 14844885 96830484 509673472 4.5809755325 4.0786938667 4.8252468109 655 26.1600000000 0.0188157707 0.0074937554 0.0188157707 0.0072882195 0.0074940000 0.0004380000 0.0049650000 0.0000030000 0.0000030000 0.0011710000 14847661 96830484 509673472 4.5715146065 4.0763697624 4.8187680244 656 26.2000000000 0.0182756018 0.0075101911 0.0188157707 0.0072869157 0.0055870000 0.0004000000 0.0033820000 0.0000000000 0.0000030000 0.0008870000 14850437 96830484 509673472 4.5606956482 4.0769371986 4.8153853416 657 26.2400000000 0.0184660237 0.0075268666 0.0188157707 0.0072869312 0.0078480000 0.0004010000 0.0048310000 0.0000040000 0.0000030000 0.0016870000 14853213 96830484 509673472 4.5500826836 4.0773477554 4.8116416931 658 26.2800000000 0.0182001442 0.0075430874 0.0188157707 0.0072884199 0.0051760000 0.0004020000 0.0029690000 0.0000010000 0.0000030000 0.0008810000 14855989 96830484 509673472 4.5388903618 4.0786266327 4.8073658943 659 26.3200000000 0.0186549984 0.0075599492 0.0188157707 0.0072859150 0.0070330000 0.0004000000 0.0045520000 0.0000040000 0.0000030000 0.0011560000 14858765 96830484 509673472 4.5270843506 4.0814666748 4.8036928177 660 26.3600000000 0.0182414781 0.0075761333 0.0188157707 0.0072809090 0.0047730000 0.0003970000 0.0025790000 0.0000000000 0.0000030000 0.0008770000 14861541 96830484 509673472 4.5162539482 4.0826005936 4.8006510735 661 26.4000000000 0.0184318852 0.0075925566 0.0188157707 0.0072757960 0.0059560000 0.0004000000 0.0029590000 0.0000030000 0.0000030000 0.0016720000 14864317 96830484 509673472 4.5041785240 4.0851893425 4.7965970039 662 26.4400000000 0.0184355658 0.0076089357 0.0188157707 0.0072746865 0.0071510000 0.0003990000 0.0049530000 0.0000000000 0.0000040000 0.0008730000 14867093 96830484 509673472 4.4923281670 4.0885586739 4.7951173782 663 26.4800000000 0.0185722671 0.0076254717 0.0188157707 0.0072920685 0.0054780000 0.0004020000 0.0029590000 0.0000040000 0.0000030000 0.0011650000 14869869 96830484 509673472 4.4816451073 4.0880179405 4.7914156914 664 26.5200000000 0.0188396089 0.0076423604 0.0188396089 0.0072997765 0.0047970000 0.0004020000 0.0025810000 0.0000000000 0.0000040000 0.0008760000 14872645 96830484 509673472 4.4714684486 4.0850706100 4.7854332924 665 26.5600000000 0.0188915748 0.0076592766 0.0188915748 0.0072948737 0.0079680000 0.0004030000 0.0049560000 0.0000040000 0.0000030000 0.0016680000 14875421 96830484 509673472 4.4608998299 4.0856022835 4.7824554443 666 26.6000000000 0.0184334330 0.0076754540 0.0188915748 0.0072910354 0.0055880000 0.0004030000 0.0033730000 0.0000010000 0.0000040000 0.0008740000 14878197 96830484 509673472 4.4497799873 4.0878257751 4.7795467377 667 26.6400000000 0.0189777184 0.0076923989 0.0189777184 0.0072948387 0.0050770000 0.0004010000 0.0025760000 0.0000040000 0.0000030000 0.0011590000 14880973 96830484 509673472 4.4391245842 4.0908422470 4.7774491310 668 26.6800000000 0.0186366066 0.0077087824 0.0189777184 0.0073168935 0.0051910000 0.0004000000 0.0029860000 0.0000000000 0.0000030000 0.0008700000 14883749 96830484 509673472 4.4280734062 4.0949816704 4.7747464180 669 26.7200000000 0.0190239940 0.0077256961 0.0190239940 0.0073597274 0.0059880000 0.0004020000 0.0029680000 0.0000030000 0.0000030000 0.0016730000 14886525 96830484 509673472 4.4171400070 4.0963673592 4.7713794708 670 26.7600000000 0.0183927137 0.0077416170 0.0190239940 0.0073966367 0.0063790000 0.0004030000 0.0041760000 0.0000000000 0.0000030000 0.0008690000 14889301 96830484 509673472 4.4074878693 4.0959382057 4.7691979408 671 26.8000000000 0.0185530428 0.0077577294 0.0190239940 0.0074035228 0.0054520000 0.0004010000 0.0029680000 0.0000030000 0.0000030000 0.0011400000 14892077 96830484 509673472 4.3979711533 4.0963654518 4.7653350830 672 26.8400000000 0.0186602976 0.0077739534 0.0190239940 0.0073994481 0.0059600000 0.0004010000 0.0037540000 0.0000000000 0.0000040000 0.0008610000 14894853 96830484 509673472 4.3883881569 4.0989480019 4.7610898018 673 26.8800000000 0.0179473571 0.0077890699 0.0190239940 0.0073954887 0.0079620000 0.0004000000 0.0049550000 0.0000030000 0.0000020000 0.0016610000 14897629 96830484 509673472 4.3793811798 4.0994863510 4.7584347725 674 26.9200000000 0.0183673408 0.0078047647 0.0190239940 0.0073900765 0.0047970000 0.0004030000 0.0025890000 0.0000000000 0.0000030000 0.0008630000 14900405 96830484 509673472 4.3706278801 4.1005201340 4.7540445328 675 26.9600000000 0.0180137549 0.0078198891 0.0190239940 0.0073846428 0.0074570000 0.0004020000 0.0049590000 0.0000040000 0.0000030000 0.0011510000 14903181 96830484 509673472 4.3618893623 4.1024894714 4.7518110275 676 27.0000000000 0.0184165780 0.0078355647 0.0190239940 0.0073802693 0.0055830000 0.0004030000 0.0033690000 0.0000000000 0.0000030000 0.0008620000 14905957 96830484 509673472 4.3528356552 4.1068115234 4.7478041649 677 27.0400000000 0.0183915142 0.0078511570 0.0190239940 0.0073890366 0.0071450000 0.0004030000 0.0041360000 0.0000040000 0.0000030000 0.0016460000 14908733 96830484 509673472 4.3441052437 4.1099376678 4.7460837364 678 27.0800000000 0.0179057885 0.0078659868 0.0190239940 0.0074023168 0.0067790000 0.0004020000 0.0045570000 0.0000000000 0.0000040000 0.0008550000 14911509 96830484 509673472 4.3358798027 4.1118788719 4.7435584068 679 27.1200000000 0.0183472689 0.0078814232 0.0190239940 0.0074119989 0.0054110000 0.0004000000 0.0029520000 0.0000030000 0.0000030000 0.0011020000 14914285 96830484 509673472 4.3270125389 4.1140146255 4.7391824722 680 27.1600000000 0.0175291393 0.0078956110 0.0190239940 0.0074143706 0.0055510000 0.0003980000 0.0033560000 0.0000000000 0.0000030000 0.0008440000 14917061 96830484 509673472 4.3191728592 4.1139292717 4.7355742455 681 27.2000000000 0.0185623113 0.0079112743 0.0190239940 0.0074091702 0.0063390000 0.0004030000 0.0033590000 0.0000040000 0.0000030000 0.0016210000 14919837 96830484 509673472 4.3112168312 4.1151609421 4.7305817604 682 27.2400000000 0.0185895059 0.0079269315 0.0190239940 0.0074039949 0.0051680000 0.0004010000 0.0029690000 0.0000000000 0.0000040000 0.0008430000 14922613 96830484 509673472 4.3029704094 4.1188039780 4.7265062332 683 27.2800000000 0.0193738099 0.0079436912 0.0193738099 0.0074031493 0.0054240000 0.0004000000 0.0029560000 0.0000040000 0.0000030000 0.0011000000 14925389 96830484 509673472 4.2950787544 4.1216716766 4.7211666107 684 27.3200000000 0.0189231858 0.0079597431 0.0193738099 0.0074083773 0.0051540000 0.0004010000 0.0029530000 0.0000000000 0.0000030000 0.0008410000 14928165 96830484 509673472 4.2867345810 4.1227545738 4.7175092697 685 27.3600000000 0.0196967367 0.0079768774 0.0196967367 0.0074076583 0.0079080000 0.0004010000 0.0049430000 0.0000040000 0.0000030000 0.0016040000 14930941 96830484 509673472 4.2790703773 4.1235804558 4.7110409737 686 27.4000000000 0.0195958037 0.0079938146 0.0196967367 0.0074044294 0.0071550000 0.0004020000 0.0049520000 0.0000000000 0.0000040000 0.0008420000 14933717 96830484 509673472 4.2705340385 4.1270923615 4.7057127953 687 27.4400000000 0.0192687362 0.0080102264 0.0196967367 0.0074113525 0.0058220000 0.0004010000 0.0033550000 0.0000030000 0.0000030000 0.0011000000 14936493 96830484 509673472 4.2623229027 4.1306700706 4.7006297112 688 27.4800000000 0.0197024774 0.0080272210 0.0197024774 0.0074270020 0.0051570000 0.0003990000 0.0029600000 0.0000000000 0.0000040000 0.0008350000 14939269 96830484 509673472 4.2540416718 4.1323618889 4.6946358681 689 27.5200000000 0.0196065027 0.0080440269 0.0197024774 0.0074367452 0.0063120000 0.0004000000 0.0033380000 0.0000030000 0.0000030000 0.0016000000 14942045 96830484 509673472 4.2456631660 4.1340050697 4.6891360283 690 27.5600000000 0.0193907581 0.0080604714 0.0197024774 0.0074378822 0.0063570000 0.0004000000 0.0041480000 0.0000010000 0.0000040000 0.0008410000 14944821 96830484 509673472 4.2377271652 4.1353974342 4.6826896667 691 27.6000000000 0.0197560452 0.0080773970 0.0197560452 0.0074380189 0.0073760000 0.0003970000 0.0049080000 0.0000040000 0.0000030000 0.0010930000 14947597 96830484 509673472 4.2288699150 4.1397180557 4.6760253906 692 27.6400000000 0.0202161297 0.0080949385 0.0202161297 0.0074525724 0.0047790000 0.0004000000 0.0025650000 0.0000000000 0.0000040000 0.0008440000 14950373 96830484 509673472 4.2202010155 4.1435413361 4.6691570282 693 27.6800000000 0.0205720142 0.0081129430 0.0205720142 0.0074829766 0.0059380000 0.0003990000 0.0029550000 0.0000040000 0.0000030000 0.0015990000 14953149 96830484 509673472 4.2123632431 4.1439952850 4.6614403725 694 27.7200000000 0.0213790704 0.0081320584 0.0213790704 0.0074975096 0.0051700000 0.0003980000 0.0029560000 0.0000000000 0.0000040000 0.0008420000 14955925 96830484 509673472 4.2048873901 4.1433763504 4.6523489952 695 27.7600000000 0.0216896664 0.0081515658 0.0216896664 0.0074973733 0.0062390000 0.0004000000 0.0037530000 0.0000030000 0.0000030000 0.0011030000 14958701 96830484 509673472 4.1977801323 4.1426100731 4.6446723938 696 27.8000000000 0.0223372970 0.0081719476 0.0223372970 0.0074933386 0.0051860000 0.0003980000 0.0029580000 0.0000010000 0.0000040000 0.0008440000 14961477 96830484 509673472 4.1900315285 4.1451239586 4.6365594864 697 27.8400000000 0.0230155960 0.0081932441 0.0230155960 0.0074904728 0.0071230000 0.0004010000 0.0041250000 0.0000040000 0.0000030000 0.0016040000 14964253 96830484 509673472 4.1819105148 4.1485934258 4.6288003922 698 27.8800000000 0.0233675893 0.0082149838 0.0233675893 0.0074926509 0.0047950000 0.0003980000 0.0025560000 0.0000000000 0.0000040000 0.0008430000 14967029 96830484 509673472 4.1729054451 4.1531491280 4.6219830513 699 27.9200000000 0.0234038215 0.0082367132 0.0234038215 0.0075035145 0.0053060000 0.0003990000 0.0028290000 0.0000030000 0.0000030000 0.0010880000 14969805 96830484 509673472 4.1645145416 4.1572523117 4.6158800125 700 27.9600000000 0.0232906528 0.0082582188 0.0234038215 0.0075204560 0.0048160000 0.0003990000 0.0025710000 0.0000010000 0.0000030000 0.0008520000 14972581 96830484 509673472 4.1558179855 4.1604542732 4.6093115807 701 28.0000000000 0.0229872782 0.0082792303 0.0234038215 0.0075395534 0.0055410000 0.0003990000 0.0025610000 0.0000040000 0.0000030000 0.0015870000 14975357 96830484 509673472 4.1475811005 4.1627621651 4.6035728455 702 28.0400000000 0.0222847369 0.0082991812 0.0234038215 0.0075547573 0.0048000000 0.0003980000 0.0025580000 0.0000010000 0.0000030000 0.0008490000 14978133 96830484 509673472 4.1395258904 4.1639180183 4.5982050896 703 28.0800000000 0.0213247780 0.0083177098 0.0234038215 0.0075632448 0.0050410000 0.0004000000 0.0025480000 0.0000030000 0.0000030000 0.0011050000 14980909 96830484 509673472 4.1322994232 4.1649799347 4.5947065353 704 28.1200000000 0.0201817174 0.0083345620 0.0234038215 0.0075704942 0.0046690000 0.0003970000 0.0024290000 0.0000010000 0.0000040000 0.0008530000 14983685 96830484 509673472 4.1233811378 4.1712923050 4.5919981003 705 28.1600000000 0.0193199888 0.0083501442 0.0234038215 0.0075948571 0.0059310000 0.0003970000 0.0029390000 0.0000030000 0.0000030000 0.0016040000 14986461 96830484 509673472 4.1149239540 4.1755385399 4.5889549255 706 28.2000000000 0.0186680425 0.0083647588 0.0234038215 0.0076160293 0.0048080000 0.0003960000 0.0025480000 0.0000010000 0.0000030000 0.0008670000 14989237 96830484 509673472 4.1076536179 4.1756038666 4.5860023499 707 28.2400000000 0.0181885883 0.0083786539 0.0234038215 0.0076185210 0.0057240000 0.0003970000 0.0032080000 0.0000030000 0.0000030000 0.0011200000 14992013 96830484 509673472 4.0998244286 4.1790533066 4.5827636719 708 28.2800000000 0.0175692290 0.0083916349 0.0234038215 0.0076159654 0.0051950000 0.0004000000 0.0029340000 0.0000010000 0.0000040000 0.0008610000 14994789 96830484 509673472 4.0915465355 4.1834869385 4.5809168816 709 28.3200000000 0.0164757017 0.0084030370 0.0234038215 0.0076116495 0.0055610000 0.0003960000 0.0025470000 0.0000030000 0.0000030000 0.0016110000 14997565 96830484 509673472 4.0851912498 4.1805114746 4.5793886185 710 28.3600000000 0.0156619996 0.0084132609 0.0234038215 0.0076080622 0.0051930000 0.0003970000 0.0029300000 0.0000010000 0.0000040000 0.0008660000 15000341 96830484 509673472 4.0783090591 4.1814818382 4.5772953033 711 28.4000000000 0.0152898319 0.0084229326 0.0234038215 0.0076030827 0.0054720000 0.0003970000 0.0029550000 0.0000040000 0.0000030000 0.0011170000 15003117 96830484 509673472 4.0697560310 4.1893715858 4.5762839317 712 28.4400000000 0.0149738537 0.0084321333 0.0234038215 0.0076001690 0.0048210000 0.0003960000 0.0025560000 0.0000000000 0.0000040000 0.0008640000 15005893 96830484 509673472 4.0618724823 4.1916384697 4.5741963387 713 28.4800000000 0.0147928558 0.0084410544 0.0234038215 0.0075971167 0.0056290000 0.0003950000 0.0025850000 0.0000040000 0.0000020000 0.0016180000 15008669 96830484 509673472 4.0568604469 4.1881833076 4.5736846924 714 28.5200000000 0.0148073835 0.0084499708 0.0234038215 0.0076159000 0.0048510000 0.0004000000 0.0025690000 0.0000000000 0.0000030000 0.0008620000 15011445 96830484 509673472 4.0485134125 4.1957001686 4.5732026100 715 28.5600000000 0.0146850990 0.0084586913 0.0234038215 0.0076111319 0.0055340000 0.0003990000 0.0029630000 0.0000030000 0.0000030000 0.0011360000 15014221 96830484 509673472 4.0397443771 4.2025403976 4.5731811523 716 28.6000000000 0.0146524683 0.0084673418 0.0234038215 0.0076117249 0.0048340000 0.0003980000 0.0025530000 0.0000000000 0.0000040000 0.0008640000 15016997 96830484 509673472 4.0329961777 4.2042908669 4.5752968788 717 28.6400000000 0.0146053219 0.0084759024 0.0234038215 0.0076090890 0.0059940000 0.0003980000 0.0029530000 0.0000030000 0.0000030000 0.0016190000 15019773 96830484 509673472 4.0265450478 4.2058696747 4.5780787468 718 28.6800000000 0.0146620348 0.0084845182 0.0234038215 0.0076043619 0.0049740000 0.0003980000 0.0026840000 0.0000010000 0.0000030000 0.0008600000 15022549 96830484 509673472 4.0192084312 4.2105760574 4.5807962418 719 28.7200000000 0.0146476142 0.0084930900 0.0234038215 0.0076032193 0.0049620000 0.0003960000 0.0024130000 0.0000040000 0.0000030000 0.0011310000 15025325 96830484 509673472 4.0114727020 4.2138457298 4.5830001831 720 28.7600000000 0.0146649797 0.0085016620 0.0234038215 0.0076010893 0.0048230000 0.0003980000 0.0025510000 0.0000000000 0.0000030000 0.0008590000 15028101 96830484 509673472 4.0040192604 4.2162003517 4.5866451263 721 28.8000000000 0.0147095276 0.0085102721 0.0234038215 0.0075962872 0.0054360000 0.0003990000 0.0024100000 0.0000040000 0.0000030000 0.0016000000 15030877 96830484 509673472 3.9971327782 4.2171154022 4.5912480354 722 28.8400000000 0.0147220893 0.0085188757 0.0234038215 0.0075910414 0.0047000000 0.0003970000 0.0024130000 0.0000010000 0.0000030000 0.0008620000 15033653 96830484 509673472 3.9892899990 4.2195806503 4.5956292152 723 28.8800000000 0.0147159547 0.0085274471 0.0234038215 0.0075858384 0.0050800000 0.0003980000 0.0025490000 0.0000030000 0.0000040000 0.0011020000 15036429 96830484 509673472 3.9816026688 4.2208595276 4.6011595726 724 28.9200000000 0.0146630285 0.0085359216 0.0234038215 0.0075806293 0.0048320000 0.0003960000 0.0025560000 0.0000010000 0.0000040000 0.0008540000 15039205 96830484 509673472 3.9733309746 4.2232136726 4.6065478325 725 28.9600000000 0.0146289999 0.0085443259 0.0234038215 0.0075779641 0.0063640000 0.0003960000 0.0033340000 0.0000040000 0.0000030000 0.0016110000 15041981 96830484 509673472 3.9646775723 4.2258548737 4.6122894287 726 29.0000000000 0.0146746207 0.0085527698 0.0234038215 0.0075830036 0.0050800000 0.0003950000 0.0028090000 0.0000000000 0.0000040000 0.0008570000 15044757 96830484 509673472 3.9565711021 4.2272825241 4.6183643341 727 29.0400000000 0.0146144405 0.0085611077 0.0234038215 0.0075873728 0.0049560000 0.0003990000 0.0024170000 0.0000040000 0.0000030000 0.0010980000 15047533 96830484 509673472 3.9473941326 4.2293381691 4.6242823601 728 29.0800000000 0.0146900993 0.0085695267 0.0234038215 0.0075910993 0.0047020000 0.0003970000 0.0024190000 0.0000010000 0.0000040000 0.0008550000 15050309 96830484 509673472 3.9386262894 4.2318096161 4.6308646202 729 29.1200000000 0.0146648576 0.0085778879 0.0234038215 0.0075907189 0.0055610000 0.0003960000 0.0025480000 0.0000040000 0.0000030000 0.0015830000 15053085 96830484 509673472 3.9298596382 4.2344160080 4.6378707886 730 29.1600000000 0.0148015339 0.0085864135 0.0234038215 0.0075872152 0.0060170000 0.0003970000 0.0037400000 0.0000000000 0.0000030000 0.0008490000 15055861 96830484 509673472 3.9211103916 4.2357645035 4.6446847916 731 29.2000000000 0.0148281408 0.0085949521 0.0234038215 0.0075826629 0.0049650000 0.0003970000 0.0024340000 0.0000030000 0.0000030000 0.0010980000 15058637 96830484 509673472 3.9117431641 4.2384061813 4.6511168480 732 29.2400000000 0.0149860708 0.0086036831 0.0234038215 0.0075785290 0.0044470000 0.0003980000 0.0021660000 0.0000000000 0.0000040000 0.0008460000 15061413 96830484 509673472 3.9016389847 4.2427988052 4.6576485634 733 29.2800000000 0.0149071356 0.0086122826 0.0234038215 0.0075738345 0.0055550000 0.0003990000 0.0025420000 0.0000040000 0.0000030000 0.0015740000 15064189 96830484 509673472 3.8918917179 4.2460560799 4.6660380363 734 29.3200000000 0.0148262670 0.0086207486 0.0234038215 0.0075694223 0.0044480000 0.0003950000 0.0021690000 0.0000010000 0.0000040000 0.0008450000 15066965 96830484 509673472 3.8827767372 4.2497072220 4.6752905846 735 29.3600000000 0.0146844657 0.0086289985 0.0234038215 0.0075663919 0.0050750000 0.0003960000 0.0025550000 0.0000040000 0.0000030000 0.0010820000 15069741 96830484 509673472 3.8739030361 4.2531218529 4.6840653419 736 29.4000000000 0.0145357111 0.0086370239 0.0234038215 0.0075631914 0.0048270000 0.0003970000 0.0025420000 0.0000000000 0.0000040000 0.0008480000 15072517 96830484 509673472 3.8653006554 4.2573456764 4.6932592392 737 29.4400000000 0.0143338200 0.0086447536 0.0234038215 0.0075584906 0.0058120000 0.0003970000 0.0027880000 0.0000030000 0.0000030000 0.0015780000 15075293 96830484 509673472 3.8570153713 4.2604908943 4.7020478249 738 29.4800000000 0.0142052537 0.0086522882 0.0234038215 0.0075571335 0.0047070000 0.0003970000 0.0024020000 0.0000000000 0.0000040000 0.0008500000 15078069 96830484 509673472 3.8485097885 4.2639656067 4.7108135223 739 29.5200000000 0.0140976608 0.0086596568 0.0234038215 0.0075722214 0.0049220000 0.0003990000 0.0023980000 0.0000030000 0.0000040000 0.0010780000 15080845 96830484 509673472 3.8406710625 4.2668504715 4.7196755409 740 29.5600000000 0.0141408248 0.0086670637 0.0234038215 0.0075917171 0.0048370000 0.0003970000 0.0025360000 0.0000000000 0.0000030000 0.0008540000 15083621 96830484 509673472 3.8335928917 4.2695608139 4.7282662392 741 29.6000000000 0.0141964583 0.0086745258 0.0234038215 0.0076159308 0.0055180000 0.0003960000 0.0025150000 0.0000030000 0.0000020000 0.0015570000 15086397 96830484 509673472 3.8263485432 4.2739381790 4.7367458344 742 29.6400000000 0.0142480517 0.0086820373 0.0234038215 0.0076343793 0.0050860000 0.0003980000 0.0027810000 0.0000000000 0.0000040000 0.0008500000 15089173 96830484 509673472 3.8201489449 4.2776322365 4.7457246780 743 29.6800000000 0.0141865173 0.0086894458 0.0234038215 0.0076340018 0.0050390000 0.0004000000 0.0025110000 0.0000040000 0.0000030000 0.0010720000 15091949 96830484 509673472 3.8153162003 4.2786369324 4.7539196014 744 29.7200000000 0.0141959880 0.0086968470 0.0234038215 0.0076293715 0.0052310000 0.0003970000 0.0029360000 0.0000000000 0.0000030000 0.0008440000 15094725 96830484 509673472 3.8103458881 4.2806229591 4.7609181404 745 29.7600000000 0.0142010776 0.0087042353 0.0234038215 0.0076271610 0.0054260000 0.0003980000 0.0024080000 0.0000040000 0.0000030000 0.0015550000 15097501 96830484 509673472 3.8051693439 4.2833333015 4.7673606873 746 29.8000000000 0.0141980182 0.0087115996 0.0234038215 0.0076231897 0.0047260000 0.0003970000 0.0024250000 0.0000010000 0.0000040000 0.0008440000 15100277 96830484 509673472 3.8003442287 4.2852001190 4.7736997604 747 29.8400000000 0.0141940117 0.0087189388 0.0234038215 0.0076182764 0.0050680000 0.0003970000 0.0025360000 0.0000030000 0.0000030000 0.0010670000 15103053 96830484 509673472 3.7950968742 4.2882914543 4.7794380188 748 29.8800000000 0.0141583513 0.0087262108 0.0234038215 0.0076154705 0.0050850000 0.0003970000 0.0027920000 0.0000010000 0.0000040000 0.0008370000 15105829 96830484 509673472 3.7901055813 4.2918062210 4.7853803635 749 29.9200000000 0.0141648687 0.0087334720 0.0234038215 0.0076120125 0.0055180000 0.0003970000 0.0025160000 0.0000040000 0.0000030000 0.0015390000 15108605 96830484 509673472 3.7858099937 4.2947058678 4.7910299301 750 29.9600000000 0.0141791273 0.0087407329 0.0234038215 0.0076089527 0.0048510000 0.0003960000 0.0025370000 0.0000000000 0.0000030000 0.0008480000 15111381 96830484 509673472 3.7817609310 4.2975273132 4.7962603569 751 30.0000000000 0.0142160412 0.0087480235 0.0234038215 0.0076059401 0.0049160000 0.0003980000 0.0023940000 0.0000030000 0.0000030000 0.0010510000 15114157 96830484 509673472 3.7779874802 4.2997059822 4.8008751869 752 30.0400000000 0.0142573137 0.0087553497 0.0234038215 0.0076030747 0.0052370000 0.0003960000 0.0029190000 0.0000000000 0.0000040000 0.0008500000 15116933 96830484 509673472 3.7744195461 4.3024230003 4.8051824570 753 30.0800000000 0.0142574776 0.0087626567 0.0234038215 0.0076022862 0.0053870000 0.0003990000 0.0023920000 0.0000030000 0.0000030000 0.0015170000 15119709 96830484 509673472 3.7707173824 4.3043723106 4.8089079857 754 30.1200000000 0.0142907547 0.0087699884 0.0234038215 0.0076078324 0.0050940000 0.0003990000 0.0027850000 0.0000000000 0.0000040000 0.0008270000 15122485 96830484 509673472 3.7671651840 4.3065071106 4.8124728203 755 30.1600000000 0.0143503798 0.0087773796 0.0234038215 0.0076191280 0.0049500000 0.0003970000 0.0023800000 0.0000040000 0.0000030000 0.0010750000 15125261 96830484 509673472 3.7631106377 4.3079886436 4.8157191277 756 30.2000000000 0.0143578649 0.0087847612 0.0234038215 0.0076305173 0.0052240000 0.0003990000 0.0029110000 0.0000000000 0.0000030000 0.0008190000 15128037 96830484 509673472 3.7588417530 4.3107352257 4.8192877769 757 30.2400000000 0.0143215647 0.0087920754 0.0234038215 0.0076321991 0.0053830000 0.0003970000 0.0023790000 0.0000030000 0.0000040000 0.0015170000 15130813 96830484 509673472 3.7540323734 4.3137836456 4.8223166466 758 30.2800000000 0.0143272150 0.0087993776 0.0234038215 0.0076353019 0.0052060000 0.0003960000 0.0029010000 0.0000000000 0.0000030000 0.0008190000 15133589 96830484 509673472 3.7491452694 4.3155264854 4.8257660866 759 30.3200000000 0.0143730063 0.0088067210 0.0234038215 0.0076522847 0.0049140000 0.0004000000 0.0023690000 0.0000030000 0.0000040000 0.0010590000 15136365 96830484 509673472 3.7436273098 4.3185868263 4.8292517662 760 30.3600000000 0.0143878590 0.0088140646 0.0234038215 0.0076651681 0.0051800000 0.0003970000 0.0028890000 0.0000010000 0.0000030000 0.0008120000 15139141 96830484 509673472 3.7373211384 4.3234467506 4.8322610855 761 30.4000000000 0.0143975662 0.0088214017 0.0234038215 0.0076742134 0.0054550000 0.0003970000 0.0024890000 0.0000040000 0.0000030000 0.0014810000 15141917 96830484 509673472 3.7309877872 4.3269224167 4.8349933624 762 30.4400000000 0.0144075323 0.0088287326 0.0234038215 0.0076754993 0.0050450000 0.0003990000 0.0027600000 0.0000000000 0.0000040000 0.0008070000 15144693 96830484 509673472 3.7242169380 4.3305659294 4.8371901512 763 30.4800000000 0.0144663164 0.0088361213 0.0234038215 0.0076743347 0.0050310000 0.0003960000 0.0025070000 0.0000040000 0.0000030000 0.0010430000 15147469 96830484 509673472 3.7170135975 4.3346457481 4.8393964767 764 30.5200000000 0.0145217404 0.0088435632 0.0234038215 0.0076740856 0.0050530000 0.0003980000 0.0027710000 0.0000000000 0.0000040000 0.0008020000 15150245 96830484 509673472 3.7092709541 4.3385281563 4.8415856361 765 30.5600000000 0.0145005118 0.0088509579 0.0234038215 0.0076718403 0.0054550000 0.0003980000 0.0025080000 0.0000040000 0.0000030000 0.0014550000 15153021 96830484 509673472 3.7015848160 4.3425374031 4.8438706398 766 30.6000000000 0.0145804090 0.0088584376 0.0234038215 0.0076708753 0.0047950000 0.0003970000 0.0025270000 0.0000010000 0.0000040000 0.0007890000 15155797 96830484 509673472 3.6938910484 4.3461709023 4.8461494446 767 30.6400000000 0.0145623703 0.0088658743 0.0234038215 0.0076695273 0.0050360000 0.0003960000 0.0025280000 0.0000030000 0.0000040000 0.0010230000 15158573 96830484 509673472 3.6853933334 4.3501658440 4.8479857445 768 30.6800000000 0.0146076605 0.0088733506 0.0234038215 0.0076706589 0.0048140000 0.0003970000 0.0025400000 0.0000000000 0.0000030000 0.0007820000 15161349 96830484 509673472 3.6770789623 4.3538455963 4.8500652313 769 30.7200000000 0.0146278478 0.0088808336 0.0234038215 0.0076713102 0.0054400000 0.0003960000 0.0025240000 0.0000030000 0.0000030000 0.0014240000 15164125 96830484 509673472 3.6687047482 4.3581080437 4.8521847725 770 30.7600000000 0.0146342190 0.0088883056 0.0234038215 0.0076684984 0.0047910000 0.0003950000 0.0025200000 0.0000010000 0.0000040000 0.0007820000 15166901 96830484 509673472 3.6603212357 4.3623938560 4.8542804718 771 30.8000000000 0.0146410884 0.0088957670 0.0234038215 0.0076648205 0.0054140000 0.0003980000 0.0029190000 0.0000040000 0.0000030000 0.0009980000 15169677 96830484 509673472 3.6518585682 4.3661909103 4.8559808731 772 30.8400000000 0.0147050209 0.0089032920 0.0234038215 0.0076624479 0.0048090000 0.0003950000 0.0025310000 0.0000000000 0.0000040000 0.0007740000 15172453 96830484 509673472 3.6435592175 4.3688035011 4.8577666283 773 30.8800000000 0.0147016849 0.0089107931 0.0234038215 0.0076610624 0.0054430000 0.0003960000 0.0025220000 0.0000040000 0.0000040000 0.0014090000 15175229 96830484 509673472 3.6350376606 4.3718733788 4.8596067429 774 30.9200000000 0.0147453239 0.0089183313 0.0234038215 0.0076644198 0.0051780000 0.0003980000 0.0029030000 0.0000010000 0.0000040000 0.0007690000 15178005 96830484 509673472 3.6269762516 4.3743290901 4.8616347313 775 30.9600000000 0.0147887189 0.0089259060 0.0234038215 0.0076697027 0.0048870000 0.0003980000 0.0023910000 0.0000030000 0.0000040000 0.0009990000 15180781 96830484 509673472 3.6186838150 4.3759083748 4.8631105423 776 31.0000000000 0.0147937443 0.0089334676 0.0234038215 0.0076773653 0.0046490000 0.0003960000 0.0023880000 0.0000000000 0.0000030000 0.0007630000 15183557 96830484 509673472 3.6101126671 4.3778591156 4.8646345139 777 31.0400000000 0.0148291588 0.0089410554 0.0234038215 0.0076881364 0.0050120000 0.0003980000 0.0021190000 0.0000030000 0.0000030000 0.0013950000 15186333 96830484 509673472 3.6016428471 4.3810915947 4.8659210205 778 31.0800000000 0.0148525201 0.0089486537 0.0234038215 0.0076891708 0.0046400000 0.0003980000 0.0023830000 0.0000000000 0.0000040000 0.0007570000 15189109 96830484 509673472 3.5933084488 4.3844466209 4.8670721054 779 31.1200000000 0.0148736443 0.0089562596 0.0234038215 0.0076876577 0.0049840000 0.0003970000 0.0025100000 0.0000040000 0.0000030000 0.0009690000 15191885 96830484 509673472 3.5854470730 4.3867053986 4.8686099052 780 31.1600000000 0.0148852095 0.0089638608 0.0234038215 0.0076866663 0.0047840000 0.0003970000 0.0025260000 0.0000000000 0.0000030000 0.0007530000 15194661 96830484 509673472 3.5777349472 4.3893294334 4.8701419830 781 31.2000000000 0.0149344746 0.0089715056 0.0234038215 0.0076844537 0.0056610000 0.0003970000 0.0027800000 0.0000030000 0.0000030000 0.0013720000 15197437 96830484 509673472 3.5700395107 4.3917531967 4.8709049225 782 31.2400000000 0.0149240717 0.0089791176 0.0234038215 0.0076804010 0.0050530000 0.0003960000 0.0027950000 0.0000010000 0.0000040000 0.0007500000 15200213 96830484 509673472 3.5627417564 4.3930764198 4.8721742630 783 31.2800000000 0.0149170831 0.0089867012 0.0234038215 0.0076758677 0.0052990000 0.0003960000 0.0027950000 0.0000030000 0.0000040000 0.0009910000 15202989 96830484 509673472 3.5555405617 4.3947482109 4.8735418320 784 31.3200000000 0.0149604809 0.0089943208 0.0234038215 0.0076711231 0.0050570000 0.0003970000 0.0027980000 0.0000000000 0.0000040000 0.0007440000 15205765 96830484 509673472 3.5489115715 4.3960537910 4.8749604225 785 31.3600000000 0.0149550876 0.0090019141 0.0234038215 0.0076663915 0.0054170000 0.0003970000 0.0025310000 0.0000030000 0.0000030000 0.0013570000 15208541 96830484 509673472 3.5425050259 4.3966536522 4.8760895729 786 31.4000000000 0.0149752861 0.0090095139 0.0234038215 0.0076632068 0.0054900000 0.0004550000 0.0027890000 0.0000000000 0.0000040000 0.0007640000 15211317 96830484 509673472 3.5360922813 4.3975763321 4.8773274422 787 31.4400000000 0.0149635542 0.0090170793 0.0234038215 0.0076598771 0.0050890000 0.0004100000 0.0025490000 0.0000030000 0.0000030000 0.0009680000 15214093 96830484 509673472 3.5303144455 4.3995294571 4.8785009384 788 31.4800000000 0.0149913626 0.0090246609 0.0234038215 0.0076580218 0.0049570000 0.0003990000 0.0026750000 0.0000000000 0.0000030000 0.0007410000 15216869 96830484 509673472 3.5250968933 4.4004378319 4.8801174164 789 31.5200000000 0.0150151923 0.0090322535 0.0234038215 0.0076565380 0.0052010000 0.0004000000 0.0024140000 0.0000040000 0.0000030000 0.0012470000 15219645 96830484 509673472 3.5197999477 4.4005088806 4.8811955452 790 31.5600000000 0.0150071792 0.0090398167 0.0234038215 0.0076528342 0.0050230000 0.0003970000 0.0028190000 0.0000000000 0.0000030000 0.0006780000 15222421 96830484 509673472 3.5146903992 4.4006853104 4.8826565742 791 31.6000000000 0.0149963107 0.0090473470 0.0234038215 0.0076481470 0.0049170000 0.0003990000 0.0024210000 0.0000030000 0.0000040000 0.0009630000 15225197 96830484 509673472 3.5098438263 4.4009284973 4.8838677406 792 31.6400000000 0.0149962008 0.0090548582 0.0234038215 0.0076433546 0.0048270000 0.0004000000 0.0025580000 0.0000000000 0.0000030000 0.0007380000 15227973 96830484 509673472 3.5055809021 4.4005460739 4.8852591515 793 31.6800000000 0.0149992974 0.0090623543 0.0234038215 0.0076401909 0.0054630000 0.0003980000 0.0025540000 0.0000040000 0.0000030000 0.0013780000 15230749 96830484 509673472 3.5017232895 4.3997616768 4.8864722252 794 31.7200000000 0.0149983019 0.0090698303 0.0234038215 0.0076428345 0.0048220000 0.0003970000 0.0025530000 0.0000010000 0.0000040000 0.0007440000 15233525 96830484 509673472 3.4984242916 4.3986692429 4.8878889084 795 31.7600000000 0.0149943735 0.0090772826 0.0234038215 0.0076520739 0.0049300000 0.0003970000 0.0024310000 0.0000030000 0.0000040000 0.0009570000 15236301 96830484 509673472 3.4951646328 4.3976435661 4.8891816139 796 31.8000000000 0.0149849607 0.0090847043 0.0234038215 0.0076694970 0.0046860000 0.0003970000 0.0024200000 0.0000000000 0.0000030000 0.0007360000 15239077 96830484 509673472 3.4919991493 4.3965382576 4.8908505440 797 31.8400000000 0.0150258634 0.0090921587 0.0234038215 0.0076891858 0.0054580000 0.0003980000 0.0025650000 0.0000040000 0.0000030000 0.0013560000 15241853 96830484 509673472 3.4896328449 4.3954634666 4.8924660683 798 31.8800000000 0.0150147416 0.0090995805 0.0234038215 0.0077073493 0.0047020000 0.0003990000 0.0024220000 0.0000010000 0.0000040000 0.0007450000 15244629 96830484 509673472 3.4867827892 4.3939709663 4.8937740326 799 31.9200000000 0.0150366705 0.0091070111 0.0234038215 0.0077177064 0.0045300000 0.0003960000 0.0020380000 0.0000040000 0.0000030000 0.0009520000 15247405 96830484 509673472 3.4841732979 4.3922038078 4.8951792717 800 31.9600000000 0.0149989724 0.0091143761 0.0234038215 0.0077254184 0.0043260000 0.0003960000 0.0020360000 0.0000000000 0.0000040000 0.0007520000 15250181 96830484 509673472 3.4817991257 4.3901815414 4.8967022896 801 32.0000000000 0.0149894739 0.0091217108 0.0234038215 0.0077384051 0.0049780000 0.0003970000 0.0020450000 0.0000030000 0.0000040000 0.0013850000 15252957 96830484 509673472 3.4798204899 4.3884849548 4.8987469673 802 32.0400000000 0.0150138540 0.0091290576 0.0234038215 0.0077442980 0.0047170000 0.0003980000 0.0024190000 0.0000000000 0.0000030000 0.0007520000 15255733 96830484 509673472 3.4777314663 4.3864250183 4.9005551338 803 32.0800000000 0.0149964243 0.0091363644 0.0234038215 0.0077554980 0.0045780000 0.0003980000 0.0020390000 0.0000040000 0.0000030000 0.0009920000 15258509 96830484 509673472 3.4768621922 4.3860807419 4.9031410217 804 32.1199999990 0.0150234560 0.0091436867 0.0234038215 0.0077719745 0.0048650000 0.0003970000 0.0025580000 0.0000000000 0.0000040000 0.0007620000 15261285 96830484 509673472 3.4757497311 4.3853344917 4.9051532745 805 32.1600000000 0.0149897840 0.0091509489 0.0234038215 0.0077880582 0.0055170000 0.0003980000 0.0025610000 0.0000040000 0.0000030000 0.0013960000 15264061 96830484 509673472 3.4747533798 4.3836150169 4.9073553085 806 32.2000000000 0.0150057552 0.0091582129 0.0234038215 0.0078047376 0.0047460000 0.0003980000 0.0024220000 0.0000010000 0.0000030000 0.0007640000 15266837 96830484 509673472 3.4735121727 4.3820662498 4.9090790749 807 32.2400000000 0.0150147658 0.0091654701 0.0234038215 0.0078221430 0.0045850000 0.0003990000 0.0020260000 0.0000030000 0.0000030000 0.0009950000 15269613 96830484 509673472 3.4729151726 4.3790049553 4.9110703468 808 32.2800000000 0.0150223300 0.0091727187 0.0234038215 0.0078312309 0.0047440000 0.0003970000 0.0024250000 0.0000000000 0.0000040000 0.0007670000 15272389 96830484 509673472 3.4717168808 4.3765935898 4.9133419991 809 32.3200000000 0.0150084719 0.0091799322 0.0234038215 0.0078372734 0.0054100000 0.0003970000 0.0024280000 0.0000030000 0.0000030000 0.0014140000 15275165 96830484 509673472 3.4715015888 4.3728895187 4.9157671928 810 32.3600000000 0.0150340265 0.0091871595 0.0234038215 0.0078440666 0.0047560000 0.0003990000 0.0024300000 0.0000000000 0.0000040000 0.0007730000 15277941 96830484 509673472 3.4707136154 4.3705410957 4.9178771973 811 32.4000000000 0.0150299212 0.0091943639 0.0234038215 0.0078426344 0.0071770000 0.0003970000 0.0046280000 0.0000040000 0.0000030000 0.0009930000 15280717 96830484 509673472 3.4696333408 4.3667325974 4.9199676514 812 32.4399999990 0.0150403017 0.0092015633 0.0234038215 0.0078416743 0.0071140000 0.0003970000 0.0047760000 0.0000000000 0.0000040000 0.0007760000 15283493 96830484 509673472 3.4688682556 4.3632202148 4.9221758842 813 32.4800000000 0.0150019135 0.0092086979 0.0234038215 0.0078418240 0.0055420000 0.0003970000 0.0025650000 0.0000030000 0.0000040000 0.0014120000 15286269 96830484 509673472 3.4686572552 4.3606390953 4.9252305031 814 32.5200000000 0.0150171882 0.0092158336 0.0234038215 0.0078423261 0.0049880000 0.0005970000 0.0024400000 0.0000000000 0.0000030000 0.0007830000 15289045 96830484 509673472 3.4680800438 4.3578152657 4.9280681610 815 32.5600000000 0.0149815753 0.0092229081 0.0234038215 0.0078399244 0.0049840000 0.0004000000 0.0024190000 0.0000030000 0.0000030000 0.0009990000 15291821 96830484 509673472 3.4672636986 4.3547873497 4.9308013916 816 32.6000000000 0.0150015475 0.0092299898 0.0234038215 0.0078379638 0.0048950000 0.0003970000 0.0025600000 0.0000010000 0.0000030000 0.0007720000 15294597 96830484 509673472 3.4670178890 4.3505215645 4.9341163635 817 32.6400000000 0.0149596957 0.0092370029 0.0234038215 0.0078342217 0.0054320000 0.0003980000 0.0024260000 0.0000030000 0.0000030000 0.0014340000 15297373 96830484 509673472 3.4662525654 4.3470702171 4.9370064735 818 32.6800000000 0.0149487955 0.0092439855 0.0234038215 0.0078296761 0.0049200000 0.0003980000 0.0025670000 0.0000000000 0.0000040000 0.0007810000 15300149 96830484 509673472 3.4656007290 4.3434238434 4.9407124519 819 32.7200000000 0.0149640050 0.0092509697 0.0234038215 0.0078263331 0.0051630000 0.0003990000 0.0025660000 0.0000030000 0.0000030000 0.0010000000 15302925 96830484 509673472 3.4653968811 4.3415002823 4.9449739456 820 32.7599999990 0.0149468733 0.0092579159 0.0234038215 0.0078235158 0.0049280000 0.0003990000 0.0025670000 0.0000000000 0.0000040000 0.0007870000 15305701 96830484 509673472 3.4648013115 4.3390760422 4.9492430687 821 32.7999999990 0.0148618445 0.0092647416 0.0234038215 0.0078275125 0.0054370000 0.0003990000 0.0024400000 0.0000030000 0.0000030000 0.0014180000 15308477 96830484 509673472 3.4653165340 4.3370056152 4.9547982216 822 32.8400000000 0.0149076404 0.0092716065 0.0234038215 0.0078511378 0.0048130000 0.0003980000 0.0024500000 0.0000010000 0.0000030000 0.0007880000 15311253 96830484 509673472 3.4650454521 4.3344697952 4.9596862793 823 32.8800000000 0.0148421377 0.0092783750 0.0234038215 0.0078610684 0.0055500000 0.0004010000 0.0029530000 0.0000030000 0.0000040000 0.0010160000 15314029 96830484 509673472 3.4644279480 4.3323874474 4.9646911621 824 32.9200000000 0.0149065256 0.0092852053 0.0234038215 0.0078654649 0.0055910000 0.0003970000 0.0032120000 0.0000010000 0.0000040000 0.0007960000 15316805 96830484 509673472 3.4640736580 4.3315801620 4.9705429077 825 32.9600000000 0.0148100210 0.0092919021 0.0234038215 0.0078781183 0.0056170000 0.0003970000 0.0025630000 0.0000030000 0.0000030000 0.0014640000 15319581 96830484 509673472 3.4637763500 4.3291244507 4.9765634537 826 33.0000000000 0.0147065921 0.0092984574 0.0234038215 0.0078860333 0.0048210000 0.0003970000 0.0024310000 0.0000000000 0.0000030000 0.0008000000 15322357 96830484 509673472 3.4633414745 4.3277649879 4.9827437401 827 33.0400000000 0.0146322101 0.0093049069 0.0234038215 0.0079026439 0.0050270000 0.0004000000 0.0024320000 0.0000040000 0.0000030000 0.0010080000 15325133 96830484 509673472 3.4627931118 4.3245472908 4.9885945320 828 33.0800000000 0.0145911099 0.0093112912 0.0234038215 0.0079296179 0.0049360000 0.0003960000 0.0025480000 0.0000010000 0.0000040000 0.0007940000 15327909 96830484 509673472 3.4624831676 4.3207349777 4.9941558838 829 33.1199999990 0.0145420199 0.0093176009 0.0234038215 0.0079507607 0.0054570000 0.0003970000 0.0024130000 0.0000040000 0.0000030000 0.0014530000 15330685 96830484 509673472 3.4617583752 4.3175115585 5.0003685951 830 33.1600000000 0.0144277010 0.0093237576 0.0234038215 0.0079664885 0.0048230000 0.0003960000 0.0024090000 0.0000010000 0.0000030000 0.0008080000 15333461 96830484 509673472 3.4611141682 4.3140044212 5.0062336922 831 33.2000000000 0.0142812971 0.0093297234 0.0234038215 0.0079841133 0.0050210000 0.0004010000 0.0024120000 0.0000030000 0.0000030000 0.0009940000 15336237 96830484 509673472 3.4612455368 4.3089199066 5.0130391121 832 33.2400000000 0.0141255362 0.0093354876 0.0234038215 0.0079938944 0.0049600000 0.0003980000 0.0025500000 0.0000000000 0.0000030000 0.0008030000 15339013 96830484 509673472 3.4605348110 4.3047127724 5.0195188522 833 33.2800000000 0.0139739746 0.0093410560 0.0234038215 0.0079968648 0.0058590000 0.0004000000 0.0028080000 0.0000040000 0.0000030000 0.0014470000 15341789 96830484 509673472 3.4595835209 4.3012294769 5.0264039040 834 33.3200000000 0.0139111169 0.0093465357 0.0234038215 0.0080009258 0.0053440000 0.0003980000 0.0029480000 0.0000000000 0.0000030000 0.0008050000 15344565 96830484 509673472 3.4587943554 4.2960877419 5.0329232216 835 33.3600000000 0.0137430755 0.0093518010 0.0234038215 0.0080074548 0.0051710000 0.0004020000 0.0025500000 0.0000040000 0.0000030000 0.0010140000 15347341 96830484 509673472 3.4574675560 4.2932944298 5.0391044617 836 33.4000000000 0.0136487354 0.0093569409 0.0234038215 0.0080166667 0.0053570000 0.0003980000 0.0029480000 0.0000000000 0.0000040000 0.0008110000 15350117 96830484 509673472 3.4565820694 4.2896146774 5.0458016396 837 33.4399999990 0.0135026518 0.0093618939 0.0234038215 0.0080320662 0.0055310000 0.0004000000 0.0024320000 0.0000030000 0.0000040000 0.0014650000 15352893 96830484 509673472 3.4554309845 4.2869272232 5.0521941185 838 33.4800000000 0.0134273805 0.0093667453 0.0234038215 0.0080612833 0.0044390000 0.0003980000 0.0020320000 0.0000000000 0.0000040000 0.0008070000 15355669 96830484 509673472 3.4550287724 4.2820277214 5.0581789017 839 33.5200000000 0.0132829575 0.0093714131 0.0234038215 0.0080922814 0.0050230000 0.0004000000 0.0023980000 0.0000030000 0.0000030000 0.0010090000 15358445 96830484 509673472 3.4544811249 4.2794241905 5.0646243095 840 33.5600000000 0.0130839972 0.0093758328 0.0234038215 0.0081134058 0.0048370000 0.0003970000 0.0024070000 0.0000000000 0.0000030000 0.0008150000 15361221 96830484 509673472 3.4522542953 4.2767581940 5.0692820549 841 33.6000000000 0.0128807984 0.0093800004 0.0234038215 0.0081159737 0.0056360000 0.0003990000 0.0025550000 0.0000030000 0.0000030000 0.0014570000 15363997 96830484 509673472 3.4508469105 4.2745561600 5.0747604370 842 33.6400000000 0.0127107929 0.0093839562 0.0234038215 0.0081144377 0.0049660000 0.0003990000 0.0025430000 0.0000000000 0.0000030000 0.0008080000 15366773 96830484 509673472 3.4494299889 4.2722659111 5.0798292160 843 33.6800000000 0.0125204064 0.0093876768 0.0234038215 0.0081143317 0.0052130000 0.0003990000 0.0025610000 0.0000040000 0.0000030000 0.0010170000 15369549 96830484 509673472 3.4483847618 4.2687005997 5.0850777626 844 33.7200000000 0.0123535581 0.0093911909 0.0234038215 0.0081194450 0.0049630000 0.0003990000 0.0025420000 0.0000000000 0.0000030000 0.0008080000 15372325 96830484 509673472 3.4476621151 4.2636570930 5.0899558067 845 33.7599999990 0.0121643851 0.0093944728 0.0234038215 0.0081303330 0.0055030000 0.0003990000 0.0024110000 0.0000030000 0.0000040000 0.0014650000 15375101 96830484 509673472 3.4475893974 4.2603254318 5.0951514244 846 33.7999999990 0.0117588863 0.0093972676 0.0234038215 0.0081374079 0.0048390000 0.0004000000 0.0024050000 0.0000000000 0.0000030000 0.0008190000 15377877 96830484 509673472 3.4463891983 4.2576665878 5.0997309685 847 33.8400000000 0.0114403600 0.0093996797 0.0234038215 0.0081362422 0.0051750000 0.0004010000 0.0025510000 0.0000030000 0.0000030000 0.0010040000 15380653 96830484 509673472 3.4455940723 4.2526540756 5.1033678055 848 33.8800000000 0.0111546181 0.0094017492 0.0234038215 0.0081317902 0.0048330000 0.0003970000 0.0024190000 0.0000000000 0.0000030000 0.0007910000 15383429 96830484 509673472 3.4447321892 4.2489714622 5.1074504852 849 33.9200000000 0.0107861375 0.0094033799 0.0234038215 0.0081270285 0.0055910000 0.0003970000 0.0025470000 0.0000040000 0.0000030000 0.0014220000 15386205 96830484 509673472 3.4439406395 4.2432360649 5.1110167503 850 33.9600000000 0.0105255116 0.0094047000 0.0234038215 0.0081225779 0.0048490000 0.0003990000 0.0024050000 0.0000000000 0.0000030000 0.0008210000 15388981 96830484 509673472 3.4431729317 4.2393426895 5.1146869659 851 34.0000000000 0.0103141144 0.0094057687 0.0234038215 0.0081178278 0.0052030000 0.0003980000 0.0025420000 0.0000040000 0.0000040000 0.0010380000 15391757 96830484 509673472 3.4422764778 4.2363071442 5.1186285019 852 34.0400000000 0.0101502649 0.0094066425 0.0234038215 0.0081130808 0.0048520000 0.0003970000 0.0024060000 0.0000000000 0.0000040000 0.0008300000 15394533 96830484 509673472 3.4425928593 4.2309861183 5.1224913597 853 34.0800000000 0.0098332893 0.0094071427 0.0234038215 0.0081106310 0.0052920000 0.0003980000 0.0021390000 0.0000040000 0.0000030000 0.0015080000 15397309 96830484 509673472 3.4416449070 4.2268524170 5.1254868507 854 34.1199999990 0.0095127430 0.0094072663 0.0234038215 0.0081089793 0.0050350000 0.0004000000 0.0025500000 0.0000000000 0.0000030000 0.0008500000 15400085 96830484 509673472 3.4414086342 4.2240428925 5.1290354729 855 34.1600000000 0.0090810983 0.0094068848 0.0234038215 0.0081098355 0.0051040000 0.0004010000 0.0024130000 0.0000040000 0.0000030000 0.0010420000 15402861 96830484 509673472 3.4416799545 4.2203278542 5.1325449944 856 34.2000000000 0.0087116081 0.0094060726 0.0234038215 0.0081097666 0.0081200000 0.0004040000 0.0053030000 0.0000010000 0.0000040000 0.0008740000 15405637 96830484 509673472 3.4411818981 4.2171387672 5.1353721619 857 34.2400000000 0.0083655538 0.0094048584 0.0234038215 0.0081056666 0.0057860000 0.0004150000 0.0025610000 0.0000030000 0.0000030000 0.0015340000 15408413 96830484 509673472 3.4401326180 4.2157945633 5.1382365227 858 34.2800000000 0.0080824783 0.0094033172 0.0234038215 0.0081010940 0.0054900000 0.0004390000 0.0029450000 0.0000000000 0.0000040000 0.0008470000 15411189 96830484 509673472 3.4389710426 4.2132945061 5.1406230927 859 34.3200000000 0.0079321610 0.0094016046 0.0234038215 0.0080966681 0.0052670000 0.0004050000 0.0025530000 0.0000040000 0.0000030000 0.0010610000 15413965 96830484 509673472 3.4392890930 4.2071509361 5.1425662041 860 34.3600000000 0.0075821541 0.0093994889 0.0234038215 0.0080922342 0.0048980000 0.0003990000 0.0024090000 0.0000000000 0.0000030000 0.0008480000 15416741 96830484 509673472 3.4386522770 4.2019801140 5.1440320015 861 34.4000000000 0.0072099068 0.0093969459 0.0234038215 0.0080879184 0.0055870000 0.0003990000 0.0024070000 0.0000030000 0.0000040000 0.0015340000 15419517 96830484 509673472 3.4383196831 4.1982827187 5.1465249062 862 34.4400000000 0.0068567432 0.0093939990 0.0234038215 0.0080832468 0.0050400000 0.0003990000 0.0025430000 0.0000010000 0.0000040000 0.0008490000 15422293 96830484 509673472 3.4381964207 4.1939525604 5.1484742165 863 34.4800000000 0.0065161064 0.0093906642 0.0234038215 0.0080788861 0.0056340000 0.0003980000 0.0029410000 0.0000030000 0.0000030000 0.0010460000 15425069 96830484 509673472 3.4380509853 4.1873650551 5.1496829987 864 34.5200000000 0.0060912753 0.0093868455 0.0234038215 0.0080745463 0.0045140000 0.0003990000 0.0020170000 0.0000010000 0.0000030000 0.0008520000 15427845 96830484 509673472 3.4382395744 4.1836380959 5.1514482498 865 34.5600000000 0.0058906805 0.0093828037 0.0234038215 0.0080698768 0.0064820000 0.0003980000 0.0033250000 0.0000030000 0.0000030000 0.0015090000 15430621 96830484 509673472 3.4372994900 4.1823873520 5.1531543732 866 34.6000000000 0.0058179144 0.0093786872 0.0234038215 0.0080673931 0.0045200000 0.0004000000 0.0020400000 0.0000010000 0.0000040000 0.0008360000 15433397 96830484 509673472 3.4360690117 4.1808862686 5.1542773247 867 34.6400000000 0.0056784176 0.0093744193 0.0234038215 0.0080641238 0.0052640000 0.0004020000 0.0025600000 0.0000030000 0.0000030000 0.0010480000 15436173 96830484 509673472 3.4362993240 4.1780986786 5.1559038162 868 34.6800000000 0.0056740870 0.0093701562 0.0234038215 0.0080600066 0.0046160000 0.0003990000 0.0021230000 0.0000010000 0.0000040000 0.0008380000 15438949 96830484 509673472 3.4356739521 4.1743216515 5.1566581726 869 34.7200000000 0.0054815426 0.0093656814 0.0234038215 0.0080557657 0.0054720000 0.0004000000 0.0022980000 0.0000030000 0.0000030000 0.0015150000 15441725 96830484 509673472 3.4362785816 4.1708250046 5.1577100754 870 34.7600000000 0.0053936755 0.0093611159 0.0234038215 0.0080514077 0.0048810000 0.0004010000 0.0024200000 0.0000010000 0.0000040000 0.0008080000 15444501 96830484 509673472 3.4353151321 4.1681756973 5.1581826210 871 34.8000000000 0.0053738221 0.0093565381 0.0234038215 0.0080467804 0.0046810000 0.0003970000 0.0020250000 0.0000040000 0.0000030000 0.0010040000 15447277 96830484 509673472 3.4343438148 4.1663365364 5.1589169502 872 34.8400000000 0.0052798879 0.0093518630 0.0234038215 0.0080425245 0.0048850000 0.0003990000 0.0024240000 0.0000000000 0.0000030000 0.0008070000 15450053 96830484 509673472 3.4332633018 4.1631307602 5.1595444679 873 34.8800000000 0.0051564449 0.0093470573 0.0234038215 0.0080380716 0.0055430000 0.0003990000 0.0024320000 0.0000040000 0.0000030000 0.0014500000 15452829 96830484 509673472 3.4328534603 4.1610312462 5.1609210968 874 34.9200000000 0.0052125254 0.0093423267 0.0234038215 0.0080341799 0.0048910000 0.0003990000 0.0024170000 0.0000000000 0.0000030000 0.0008090000 15455605 96830484 509673472 3.4321591854 4.1598286629 5.1621079445 875 34.9600000000 0.0050856448 0.0093374619 0.0234038215 0.0080306660 0.0052390000 0.0004000000 0.0025510000 0.0000030000 0.0000040000 0.0010150000 15458381 96830484 509673472 3.4306297302 4.1598424911 5.1635861397 876 35.0000000000 0.0051528737 0.0093326850 0.0234038215 0.0080269296 0.0043840000 0.0004000000 0.0019040000 0.0000010000 0.0000040000 0.0008040000 15461157 96830484 509673472 3.4298586845 4.1590299606 5.1649312973 877 35.0400000000 0.0050936262 0.0093278514 0.0234038215 0.0080223647 0.0052970000 0.0003990000 0.0021560000 0.0000040000 0.0000030000 0.0014570000 15463933 96830484 509673472 3.4289684296 4.1586933136 5.1663298607 878 35.0800000000 0.0052036420 0.0093231541 0.0234038215 0.0080179370 0.0046390000 0.0004020000 0.0021640000 0.0000000000 0.0000030000 0.0008070000 15466709 96830484 509673472 3.4279501438 4.1590414047 5.1674847603 879 35.1200000000 0.0051756208 0.0093184356 0.0234038215 0.0080133963 0.0048610000 0.0003980000 0.0021620000 0.0000030000 0.0000030000 0.0010210000 15469485 96830484 509673472 3.4270985126 4.1579713821 5.1685752869 880 35.1600000000 0.0051332046 0.0093136797 0.0234038215 0.0080092046 0.0049020000 0.0004000000 0.0024260000 0.0000000000 0.0000040000 0.0008070000 15472261 96830484 509673472 3.4264726639 4.1588721275 5.1699171066 881 35.2000000000 0.0051965336 0.0093090064 0.0234038215 0.0080053442 0.0050220000 0.0004010000 0.0018930000 0.0000040000 0.0000030000 0.0014490000 15475037 96830484 509673472 3.4254279137 4.1587538719 5.1712212563 882 35.2400000000 0.0050967298 0.0093042306 0.0234038215 0.0080019516 0.0050450000 0.0004000000 0.0025570000 0.0000010000 0.0000040000 0.0008090000 15477813 96830484 509673472 3.4259686470 4.1547031403 5.1718530655 ================================================ FILE: icra2018_results/1080/memory_lsdslam_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:01:39 Properties: ================= frame-limit: 0 log-file: out_paper//memory_lsdslam_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0153440000 86827604 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0010221110 0.0005110555 0.0010221110 0.0016486765 0.0387140000 103183657 0 402718720 -0.0006010678 -0.0001195244 0.0001060443 3 0.0800000000 0.0050368467 0.0020196526 0.0050368467 0.0023331402 0.0215020000 106455569 0 402718720 -0.0005712564 -0.0001159089 -0.0002626415 4 0.1200000000 0.0030105244 0.0022673706 0.0050368467 0.0021972292 0.0213530000 106458217 0 402718720 -0.0008395423 -0.0004368496 -0.0003819885 5 0.1600000000 0.0058184462 0.0029775857 0.0058184462 0.0019636265 0.0206820000 106460881 0 402718720 -0.0009795793 -0.0000027206 -0.0002612148 6 0.2000000000 0.0051384396 0.0033377280 0.0058184462 0.0018817739 0.0207890000 106463929 0 402718720 -0.0005845805 -0.0000757059 -0.0006002540 7 0.2400000000 0.0052057360 0.0036045863 0.0058184462 0.0017252949 0.0203400000 106466177 0 402718720 -0.0005683319 0.0000713028 -0.0004218094 8 0.2800000000 0.0065800720 0.0039765220 0.0065800720 0.0016593006 0.0203840000 106468425 0 402718720 -0.0006063433 0.0001757963 -0.0005147401 9 0.3200000000 0.0080526182 0.0044294216 0.0080526182 0.0016340920 0.0221440000 106471505 0 402718720 -0.0010380259 0.0000522868 -0.0005210924 10 0.3600000000 0.0081044836 0.0047969278 0.0081044836 0.0016454699 0.0221780000 106475353 0 402718720 -0.0013087916 0.0000750954 -0.0004509437 11 0.4000000000 0.0093984492 0.0052152479 0.0093984492 0.0018088903 0.0199610000 106477601 0 402718720 -0.0008957226 0.0000751102 -0.0001808895 12 0.4400000000 0.0094706044 0.0055698610 0.0094706044 0.0021761640 0.0206070000 106479849 0 402718720 -0.0007593075 -0.0000005458 -0.0004498283 13 0.4800000000 0.0110082580 0.0059881992 0.0110082580 0.0022167070 0.0195020000 106482097 0 402718720 -0.0016798322 -0.0000336746 -0.0001003841 14 0.5200000000 0.0109660253 0.0063437582 0.0110082580 0.0021937212 0.0296290000 106484345 0 402718720 -0.0019606531 -0.0010226226 -0.0000116620 15 0.5600000000 0.0139691764 0.0068521194 0.0139691764 0.0021532649 0.0213330000 106486593 0 402718720 -0.0020313677 0.0001300166 -0.0003221555 16 0.6000000000 0.0133041330 0.0072553703 0.0139691764 0.0022222298 0.0206140000 106488841 0 402718720 -0.0015773640 -0.0000094086 -0.0005183284 17 0.6400000000 0.0138059510 0.0076406985 0.0139691764 0.0022505849 0.0205280000 106492753 0 402718720 -0.0031562904 -0.0012515889 -0.0008958912 18 0.6800000000 0.0174049083 0.0081831546 0.0174049083 0.0023576317 0.0228820000 106498201 0 402718720 -0.0016320179 -0.0045921686 -0.0006295637 19 0.7200000000 0.0175940488 0.0086784649 0.0175940488 0.0025288205 0.0194630000 106500449 0 402718720 -0.0023679030 -0.0004589465 -0.0013908958 20 0.7600000000 0.0203366689 0.0092613751 0.0203366689 0.0025888000 0.0197780000 106502697 0 402718720 -0.0026747861 -0.0005096134 -0.0014838291 21 0.8000000000 0.0241022408 0.0099680829 0.0241022408 0.0025306025 0.0199860000 106504945 0 402718720 -0.0018647636 -0.0001894720 -0.0016551752 22 0.8400000000 0.0295359325 0.0108575307 0.0295359325 0.0026146935 0.0202690000 106507193 0 402718720 -0.0021181731 -0.0002913807 -0.0015463522 23 0.8800000000 0.0290699080 0.0116493731 0.0295359325 0.0025785272 0.0207710000 106509441 0 402718720 -0.0020462936 0.0000022076 -0.0023591069 24 0.9200000000 0.0352930799 0.0126345276 0.0352930799 0.0028196324 0.0222310000 106511689 0 402718720 -0.0041387957 0.0000000737 -0.0031308315 25 0.9600000000 0.0355664901 0.0135518061 0.0355664901 0.0027740306 0.0537790000 106513937 0 402718720 -0.0050042840 0.0009137367 -0.0037828644 26 1.0000000000 0.0407356694 0.0145973393 0.0407356694 0.0028441873 0.0273460000 106516185 0 402718720 -0.0061319182 0.0006566583 -0.0029565943 27 1.0400000000 0.0460910574 0.0157637733 0.0460910574 0.0030297597 0.0224980000 106518433 0 402718720 -0.0064592562 0.0004693865 -0.0043467609 28 1.0800000000 0.0489963107 0.0169506496 0.0489963107 0.0033440414 0.0199230000 106520681 0 402718720 -0.0083498303 -0.0004474318 -0.0041515878 29 1.1200000000 0.0525621250 0.0181786315 0.0525621250 0.0036770268 0.0222550000 106522929 0 402718720 -0.0109420186 -0.0000399562 -0.0050495001 30 1.1600000000 0.0571475215 0.0194775945 0.0571475215 0.0041794470 0.0339010000 106525177 0 402718720 -0.0159000810 -0.0000889053 -0.0038441299 31 1.2000000000 0.0600341931 0.0207858719 0.0600341931 0.0043455298 0.0279580000 106527425 0 402718720 -0.0195541866 -0.0003700769 -0.0041839192 32 1.2400000000 0.0642836168 0.0221451764 0.0642836168 0.0044772236 0.0281330000 106529673 0 402718720 -0.0222196467 -0.0007074057 -0.0050073327 33 1.2800000000 0.0680458769 0.0235361068 0.0680458769 0.0045985394 0.0267920000 106535249 0 402718720 -0.0239848010 -0.0007214104 -0.0050769718 34 1.3200000000 0.0854386613 0.0253567701 0.0854386613 0.0055973019 0.0268640000 106543897 0 402718720 -0.0348482728 -0.0008019696 -0.0049022478 35 1.3600000000 0.0871313363 0.0271217577 0.0871313363 0.0057724779 0.0273800000 106546145 0 402718720 -0.0367471129 -0.0007946193 -0.0057829092 36 1.4000000000 0.0902810544 0.0288761826 0.0902810544 0.0062030982 0.0264380000 106548393 0 402718720 -0.0394289307 -0.0011519954 -0.0064139809 37 1.4400000000 0.0969246328 0.0307153299 0.0969246328 0.0064337492 0.0270120000 106550641 0 402718720 -0.0435134619 -0.0008812989 -0.0056946720 38 1.4800000000 0.1037840843 0.0326381919 0.1037840843 0.0065433934 0.0517490000 118892141 0 402718720 -0.0484429635 -0.0007620376 -0.0051629506 39 1.5200000000 0.1067030206 0.0345372901 0.1067030206 0.0064768831 0.0203660000 122553997 0 402718720 -0.0489069261 -0.0011520091 -0.0063196477 40 1.5600000000 0.1133394241 0.0365073434 0.1133394241 0.0064370452 0.0284720000 125748437 0 402718720 -0.0521548055 -0.0016218214 -0.0061395774 41 1.6000000000 0.1198616028 0.0385403741 0.1198616028 0.0064013111 0.0289900000 125750685 0 402718720 -0.0559138320 -0.0019886955 -0.0056572510 42 1.6400000000 0.1288172752 0.0406898242 0.1288172752 0.0064332890 0.0162060000 125752933 0 402718720 -0.0601656809 -0.0008910592 -0.0049997773 43 1.6800000000 0.1335005611 0.0428482134 0.1335005611 0.0063742072 0.0157060000 125755181 0 402718720 -0.0621613003 -0.0007944948 -0.0036822946 44 1.7200000000 0.1372464299 0.0449936274 0.1372464299 0.0063196490 0.0156600000 125757429 0 402718720 -0.0647445843 -0.0016313283 -0.0045193150 45 1.7600000000 0.1420539021 0.0471505224 0.1420539021 0.0062788642 0.0157130000 125759677 0 402718720 -0.0682628602 -0.0014697916 -0.0031571491 46 1.8000000000 0.1461073607 0.0493017580 0.1461073607 0.0062140242 0.0170090000 125761925 0 402718720 -0.0701636970 -0.0004700999 -0.0036043331 47 1.8400000000 0.1495470703 0.0514346370 0.1495470703 0.0062266301 0.0164590000 125764173 0 402718720 -0.0697437748 -0.0003123159 -0.0032924262 48 1.8800000000 0.1527054012 0.0535444446 0.1527054012 0.0061764370 0.0166420000 125766421 0 402718720 -0.0710848942 -0.0000658497 -0.0029243326 49 1.9200000000 0.1573966146 0.0556638766 0.1573966146 0.0061560534 0.0209470000 125768669 0 402718720 -0.0736479759 -0.0000878447 -0.0027709759 50 1.9600000000 0.1666463017 0.0578835251 0.1666463017 0.0063479760 0.0164390000 125770917 0 402718720 -0.0786924884 -0.0000066427 -0.0007028050 51 2.0000000000 0.1648788005 0.0599814717 0.1666463017 0.0062871257 0.0171920000 125773165 0 402718720 -0.0787848234 -0.0021353804 -0.0015991166 52 2.0400000000 0.1678642184 0.0620561399 0.1678642184 0.0062368057 0.0217560000 125775413 0 402718720 -0.0797809660 -0.0011418709 -0.0020321822 53 2.0800000000 0.1690072417 0.0640740852 0.1690072417 0.0062299296 0.0203900000 125777661 0 402718720 -0.0806599557 -0.0014444985 -0.0032268446 54 2.1200000000 0.1773535907 0.0661718539 0.1773535907 0.0062330208 0.0212270000 125779909 0 402718720 -0.0853610411 -0.0017707776 -0.0011762143 55 2.1600000000 0.1792208999 0.0682272911 0.1792208999 0.0062119541 0.0235860000 125782157 0 402718720 -0.0857493803 -0.0017121264 -0.0008412982 56 2.2000000000 0.1921453774 0.0704401140 0.1921453774 0.0063255825 0.0225810000 125784405 0 402718720 -0.0928636864 -0.0006414056 0.0018607760 57 2.2400000000 0.1954839081 0.0726338648 0.1954839081 0.0062839662 0.0230940000 125786653 0 402718720 -0.0944608077 -0.0013362539 0.0023466900 58 2.2800000000 0.2009222656 0.0748457338 0.2009222656 0.0063859825 0.0229820000 125788901 0 402718720 -0.0983995497 -0.0018866452 0.0037058054 59 2.3200000000 0.2107910663 0.0771498920 0.2107910663 0.0067649150 0.0236790000 125791149 0 402718720 -0.1027900577 -0.0012729637 0.0057026003 60 2.3600000000 0.2128191739 0.0794110467 0.2128191739 0.0068195288 0.0242040000 125793397 0 402718720 -0.1038557813 -0.0013865192 0.0052556051 61 2.4000000000 0.2173991203 0.0816731462 0.2173991203 0.0069361494 0.0243490000 125795645 0 402718720 -0.1060889363 -0.0012071860 0.0053246208 62 2.4400000000 0.2337903976 0.0841266503 0.2337903976 0.0076108332 0.0250210000 125797893 0 402718720 -0.1137990132 -0.0009842241 0.0088096196 63 2.4800000000 0.2390441597 0.0865856584 0.2390441597 0.0077847861 0.0256230000 125800141 0 402718720 -0.1172221527 -0.0012369355 0.0097387042 64 2.5200000000 0.2465581745 0.0890852289 0.2465581745 0.0082257953 0.0243110000 125802389 0 402718720 -0.1224385053 -0.0008748922 0.0113452338 65 2.5600000000 0.2576562464 0.0916786292 0.2576562464 0.0086210974 0.0248780000 125811293 0 402718720 -0.1253427565 0.0002159419 0.0125944251 66 2.6000000000 0.2649591267 0.0943040913 0.2649591267 0.0087772542 0.0248980000 125826341 0 402718720 -0.1287907958 0.0006271695 0.0131456200 67 2.6400000000 0.2720668018 0.0969572661 0.2720668018 0.0088879516 0.0632510000 144663089 0 402718720 -0.1320098788 0.0017284239 0.0141074117 68 2.6800000000 0.2744824886 0.0995679311 0.2744824886 0.0088824142 0.0229780000 148324545 0 402718720 -0.1406597644 0.0025082221 0.0145887658 69 2.7200000000 0.2811039686 0.1021988882 0.2811039686 0.0088429507 0.0177550000 151518985 0 402718720 -0.1438241750 0.0029017453 0.0162004028 70 2.7600000000 0.2871097922 0.1048404725 0.2871097922 0.0087928865 0.0160160000 151521233 0 402718720 -0.1466896087 0.0032136887 0.0160009712 71 2.8000000000 0.2915111482 0.1074696370 0.2915111482 0.0087542959 0.0152500000 151523481 0 402718720 -0.1492812485 0.0035502850 0.0148926862 72 2.8400000000 0.3018983901 0.1101700363 0.3018983901 0.0088141926 0.0478640000 151525729 0 402718720 -0.1551019698 0.0057803071 0.0157016926 73 2.8800000000 0.3084669411 0.1128864323 0.3084669411 0.0087703724 0.0174830000 151527977 0 402718720 -0.1585803181 0.0060032313 0.0162813291 74 2.9200000000 0.3091797233 0.1155390443 0.3091797233 0.0087713983 0.0166050000 151530225 0 402718720 -0.1598259062 0.0068172263 0.0152416499 75 2.9600000000 0.3102965355 0.1181358109 0.3102965355 0.0087605037 0.0175510000 151532473 0 402718720 -0.1599810719 0.0082372781 0.0140581075 76 3.0000000000 0.3078273237 0.1206317518 0.3102965355 0.0087653502 0.0170270000 151534721 0 402718720 -0.1601888835 0.0088258097 0.0111521548 77 3.0400000000 0.3083820045 0.1230700668 0.3102965355 0.0087747773 0.0182860000 151536969 0 402718720 -0.1598771363 0.0090502528 0.0088516306 78 3.0800000000 0.3078468740 0.1254390002 0.3102965355 0.0087654802 0.0176550000 151539217 0 402718720 -0.1585443467 0.0099994652 0.0062454906 79 3.1200000000 0.3124079704 0.1278056960 0.3124079704 0.0087474453 0.0176950000 151541465 0 402718720 -0.1608774811 0.0113122286 0.0054211803 80 3.1600000000 0.3146394193 0.1301411176 0.3146394193 0.0087257510 0.0201320000 151543713 0 402718720 -0.1620870382 0.0127399731 0.0042311531 81 3.2000000000 0.3223671615 0.1325142786 0.3223671615 0.0087497045 0.0183290000 151545961 0 402718720 -0.1663203686 0.0123278257 0.0052228710 82 3.2400000000 0.3282389641 0.1349011650 0.3282389641 0.0087868472 0.0180490000 151548209 0 402718720 -0.1688868403 0.0127321687 0.0049807443 83 3.2800000000 0.3332856596 0.1372913397 0.3332856596 0.0088707086 0.0196610000 151550457 0 402718720 -0.1715983152 0.0137378564 0.0039253146 84 3.3200000000 0.3414836526 0.1397222005 0.3414836526 0.0089323604 0.0189420000 151552705 0 402718720 -0.1759088933 0.0135109499 0.0039092163 85 3.3600000000 0.3503438830 0.1422001027 0.3503438830 0.0090042505 0.0196520000 151554953 0 402718720 -0.1806448698 0.0142289940 0.0041058715 86 3.4000000000 0.3605352044 0.1447388829 0.3605352044 0.0091436663 0.0192580000 151557201 0 402718720 -0.1852977574 0.0147510581 0.0052353563 87 3.4400000000 0.3668980300 0.1472924363 0.3668980300 0.0092889149 0.0522540000 163866489 0 402718720 -0.1886557788 0.0140747735 0.0051088589 88 3.4800000000 0.3752645254 0.1498830283 0.3752645254 0.0094753954 0.0221350000 167528761 0 402718720 -0.1933291405 0.0139919491 0.0046040085 89 3.5200000000 0.3814198077 0.1524845651 0.3814198077 0.0096300770 0.0427380000 170723201 0 402718720 -0.1964999139 0.0141907157 0.0045886636 90 3.5600000000 0.3859815001 0.1550789755 0.3859815001 0.0097254154 0.0190200000 170725449 0 402718720 -0.1993962973 0.0137450006 0.0045555052 91 3.6000000000 0.3953829706 0.1577196787 0.3953829706 0.0098457129 0.0140470000 170727697 0 402718720 -0.2045249790 0.0132343518 0.0056582247 92 3.6400000000 0.4052372575 0.1604100872 0.4052372575 0.0099464152 0.0152210000 170729945 0 402718720 -0.2099640369 0.0140501261 0.0074910829 93 3.6800000000 0.4082173407 0.1630746813 0.4082173407 0.0099240125 0.0147980000 170732193 0 402718720 -0.2116825879 0.0136093767 0.0064481697 94 3.7200000000 0.4130294621 0.1657337747 0.4130294621 0.0098996403 0.0155230000 170734441 0 402718720 -0.2140740007 0.0127975354 0.0063101258 95 3.7600000000 0.4216758311 0.1684279016 0.4216758311 0.0099380774 0.0229870000 170736689 0 402718720 -0.2185904980 0.0136595787 0.0087615699 96 3.8000000000 0.4282309115 0.1711341830 0.4282309115 0.0099352782 0.0194920000 170738937 0 402718720 -0.2221803367 0.0135824857 0.0086163804 97 3.8400000000 0.4321443141 0.1738250091 0.4321443141 0.0098931711 0.0172690000 170741185 0 402718720 -0.2238389254 0.0125287948 0.0093493834 98 3.8800000000 0.4412858784 0.1765542016 0.4412858784 0.0099272498 0.0153420000 170743433 0 402718720 -0.2293332517 0.0124536343 0.0112518016 99 3.9200000000 0.4452390075 0.1792681896 0.4452390075 0.0098954436 0.0163590000 170745681 0 402718720 -0.2310054153 0.0132249510 0.0121419476 100 3.9600000000 0.4506099820 0.1819816075 0.4506099820 0.0098632022 0.0195500000 170747929 0 402718720 -0.2340003699 0.0129553536 0.0137993721 101 4.0000000000 0.4564238489 0.1846988574 0.4564238489 0.0098257915 0.0181750000 170750177 0 402718720 -0.2369859815 0.0122189401 0.0159838982 102 4.0400000000 0.4589808583 0.1873878966 0.4589808583 0.0097822234 0.0179670000 170752425 0 402718720 -0.2380815744 0.0116968919 0.0164446160 103 4.0800000000 0.4659328759 0.1900922168 0.4659328759 0.0097572031 0.0191380000 170754673 0 402718720 -0.2420490086 0.0115062967 0.0192626882 104 4.1200000000 0.4746868014 0.1928287032 0.4746868014 0.0097748828 0.0194300000 170756921 0 402718720 -0.2465592325 0.0110575436 0.0239610206 105 4.1600000000 0.4773190022 0.1955381346 0.4773190022 0.0097486657 0.0185630000 170759169 0 402718720 -0.2468432039 0.0110867396 0.0241745692 106 4.2000000000 0.4812963605 0.1982339670 0.4812963605 0.0097633663 0.0185190000 170761417 0 402718720 -0.2495068014 0.0106935408 0.0260909740 107 4.2400000000 0.4816958606 0.2008831435 0.4816958606 0.0097283004 0.0185770000 170763665 0 402718720 -0.2492392361 0.0101050595 0.0248189624 108 4.2800000000 0.4881804287 0.2035433036 0.4881804287 0.0097040345 0.0189690000 170765913 0 402718720 -0.2528761327 0.0099894824 0.0278310236 109 4.3200000000 0.4893859029 0.2061657127 0.4893859029 0.0096692947 0.0191480000 170768161 0 402718720 -0.2535161972 0.0101422239 0.0282976534 110 4.3600000000 0.4946853518 0.2087886186 0.4946853518 0.0096851829 0.0190690000 170770409 0 402718720 -0.2565478384 0.0098418463 0.0317895412 111 4.4000000000 0.4991100729 0.2114041272 0.4991100729 0.0096862800 0.0197190000 170772657 0 402718720 -0.2589139640 0.0090666311 0.0342084058 112 4.4400000000 0.5043582916 0.2140197893 0.5043582916 0.0097071410 0.0475310000 183079565 0 402718720 -0.2620716095 0.0105703380 0.0372801423 113 4.4800000000 0.5073931813 0.2166160140 0.5073931813 0.0096943305 0.0145770000 186741021 0 402718720 -0.2635770738 0.0110402107 0.0388241000 114 4.5200000000 0.5155249834 0.2192380225 0.5155249834 0.0097758143 0.0207470000 189935461 0 402718720 -0.2671762407 0.0098763071 0.0429840386 115 4.5600000000 0.5154689550 0.2218139437 0.5155249834 0.0097717272 0.0156690000 189937709 0 402718720 -0.2680678666 0.0110291652 0.0446045920 116 4.6000000000 0.5235694647 0.2244152844 0.5235694647 0.0098516379 0.0145800000 189939957 0 402718720 -0.2713770866 0.0119551113 0.0485775843 117 4.6400000000 0.5294877887 0.2270227417 0.5294877887 0.0098822749 0.0145970000 189942205 0 402718720 -0.2741332054 0.0133876381 0.0523652136 118 4.6800000000 0.5333180428 0.2296184646 0.5333180428 0.0098513429 0.0219600000 189944453 0 402718720 -0.2762209773 0.0128565161 0.0541787259 119 4.7200000000 0.5386661291 0.2322155038 0.5386661291 0.0098132933 0.0141470000 189946701 0 402718720 -0.2779812515 0.0128724435 0.0562440567 120 4.7600000000 0.5437530875 0.2348116503 0.5437530875 0.0097798252 0.0145650000 189948949 0 402718720 -0.2804790735 0.0136902547 0.0595824607 121 4.8000000000 0.5515725017 0.2374295086 0.5515725017 0.0097583301 0.0138670000 189951197 0 402718720 -0.2840192616 0.0137148686 0.0663305596 122 4.8400000000 0.5526536703 0.2400133132 0.5526536703 0.0097212193 0.0138380000 189953445 0 402718720 -0.2845902145 0.0141890720 0.0665420368 123 4.8800000000 0.5571398735 0.2425915779 0.5571398735 0.0097045564 0.0167490000 189955693 0 402718720 -0.2865120769 0.0156567600 0.0686997026 124 4.9200000000 0.5650275946 0.2451918684 0.5650275946 0.0097153188 0.0151720000 189957941 0 402718720 -0.2898373306 0.0161452927 0.0748185068 125 4.9600000000 0.5687020421 0.2477799498 0.5687020421 0.0096983589 0.0154690000 189960189 0 402718720 -0.2912147343 0.0159034804 0.0764933899 126 5.0000000000 0.5725595951 0.2503575660 0.5725595951 0.0096810646 0.0186640000 189962437 0 402718720 -0.2931111753 0.0166854262 0.0793475732 127 5.0400000000 0.5809868574 0.2529609462 0.5809868574 0.0096711683 0.0165420000 189964685 0 402718720 -0.2965086997 0.0175804645 0.0857666582 128 5.0800000000 0.5854790211 0.2555587437 0.5854790211 0.0096390568 0.0167080000 189966933 0 402718720 -0.2983017862 0.0175498221 0.0878348947 129 5.1200000000 0.5887804627 0.2581418578 0.5887804627 0.0096102276 0.0167640000 189982493 0 402718720 -0.2999273837 0.0176104177 0.0904811397 130 5.1600000000 0.5976077914 0.2607531342 0.5976077914 0.0096396193 0.0174780000 190010341 0 402718720 -0.3026690185 0.0176745821 0.0968957767 131 5.2000000000 0.6004859805 0.2633465147 0.6004859805 0.0096558063 0.0168980000 190012589 0 402718720 -0.3040387928 0.0183656998 0.0984177589 132 5.2400000000 0.6003753543 0.2658997635 0.6004859805 0.0096493236 0.0173420000 190014837 0 402718720 -0.3041263223 0.0182983875 0.0975877866 133 5.2800000000 0.6102161407 0.2684886084 0.6102161407 0.0096959443 0.0180090000 190017085 0 402718720 -0.3076654971 0.0182976741 0.1045560315 134 5.3200000000 0.6189224720 0.2711037865 0.6189224720 0.0097624697 0.0500430000 190019333 0 402718720 -0.3105833232 0.0195158757 0.1104523465 135 5.3600000000 0.6216925979 0.2737007407 0.6216925979 0.0097741791 0.0515920000 202329057 0 402718720 -0.3117433190 0.0194945876 0.1118059978 136 5.4000000000 0.6278383136 0.2763046934 0.6278383136 0.0098143022 0.0229570000 205990513 0 402718720 -0.3143869638 0.0193609763 0.1172653809 137 5.4400000000 0.6325834394 0.2789052682 0.6325834394 0.0098663081 0.0166040000 209184953 0 402718720 -0.3164680600 0.0201274976 0.1209488362 138 5.4800000000 0.6370843053 0.2815007685 0.6370843053 0.0099042126 0.0167680000 209187201 0 402718720 -0.3183452487 0.0199269801 0.1227249056 139 5.5200000000 0.6419104934 0.2840936442 0.6419104934 0.0099426086 0.0164850000 209189449 0 402718720 -0.3204228580 0.0190570001 0.1246168315 140 5.5600000000 0.6500366330 0.2867075227 0.6500366330 0.0100531391 0.0144990000 209191697 0 402718720 -0.3241244555 0.0198736060 0.1302408129 141 5.6000000000 0.6554880142 0.2893229872 0.6554880142 0.0100835374 0.0144840000 209193945 0 402718720 -0.3252510726 0.0198457986 0.1316012293 142 5.6400000000 0.6641548276 0.2919626480 0.6641548276 0.0101566055 0.0138950000 209196193 0 402718720 -0.3285426199 0.0204624515 0.1371442527 143 5.6800000000 0.6696986556 0.2946041586 0.6696986556 0.0102273056 0.0133040000 209198441 0 402718720 -0.3303154111 0.0211573076 0.1406756043 144 5.7200000000 0.6753698587 0.2972483648 0.6753698587 0.0102782234 0.0132910000 209200689 0 402718720 -0.3324537277 0.0218615271 0.1435438693 145 5.7600000000 0.6803185940 0.2998902285 0.6803185940 0.0102821734 0.0166100000 209202937 0 402718720 -0.3343620896 0.0216264818 0.1459590644 146 5.8000000000 0.6859486699 0.3025344644 0.6859486699 0.0102818417 0.0149070000 209205185 0 402718720 -0.3364254236 0.0216086507 0.1495205611 147 5.8400000000 0.6972199678 0.3052193998 0.6972199678 0.0102990883 0.0142560000 209207433 0 402718720 -0.3398281634 0.0214723535 0.1570994407 148 5.8800000000 0.6988965869 0.3078793808 0.6988965869 0.0102744231 0.0189200000 209209681 0 402718720 -0.3403292000 0.0213995054 0.1582107842 149 5.9200000000 0.7047211528 0.3105427484 0.7047211528 0.0102581996 0.0176630000 209211929 0 402718720 -0.3415447474 0.0216303989 0.1616670340 150 5.9600000000 0.7088704705 0.3131982665 0.7088704705 0.0102393616 0.0170070000 209214177 0 402718720 -0.3428902626 0.0216409229 0.1651712954 151 6.0000000000 0.7134874463 0.3158491882 0.7134874463 0.0102173823 0.0173440000 209216425 0 402718720 -0.3439982831 0.0219048057 0.1683527082 152 6.0400000000 0.7185481787 0.3184985237 0.7185481787 0.0102043055 0.0482940000 221522265 0 402718720 -0.3447693288 0.0227750223 0.1719049066 153 6.0800000000 0.7221766114 0.3211369426 0.7221766114 0.0102003738 0.0217050000 225183721 0 402718720 -0.3464052379 0.0232961383 0.1760382652 154 6.1200000000 0.7280732989 0.3237793864 0.7280732989 0.0102208167 0.0163880000 228378161 0 402718720 -0.3480424881 0.0230599567 0.1804041415 155 6.1600000000 0.7299470901 0.3263998232 0.7299470901 0.0102567957 0.0147830000 228380409 0 402718720 -0.3495118916 0.0233747326 0.1839635670 156 6.2000000000 0.7376989722 0.3290363562 0.7376989722 0.0103520126 0.0150160000 228382657 0 402718720 -0.3505620360 0.0234494768 0.1883842051 157 6.2400000000 0.7422654629 0.3316683888 0.7422654629 0.0104148603 0.0344150000 228384905 0 402718720 -0.3510501385 0.0236589555 0.1923416257 158 6.2800000000 0.7482877374 0.3343052201 0.7482877374 0.0104795453 0.0183500000 228387153 0 402718720 -0.3523753285 0.0237022061 0.1984969527 159 6.3200000000 0.7513378263 0.3369280667 0.7513378263 0.0104924567 0.0321340000 228389401 0 402718720 -0.3521249592 0.0235469732 0.2009515762 160 6.3600000000 0.7566862702 0.3395515554 0.7566862702 0.0105249944 0.0158110000 228391649 0 402718720 -0.3524422348 0.0239901543 0.2063861191 161 6.4000000000 0.7596268058 0.3421607185 0.7596268058 0.0105066838 0.0153420000 228393897 0 402718720 -0.3525141180 0.0243066009 0.2103177160 162 6.4400000000 0.7632328868 0.3447599294 0.7632328868 0.0104814048 0.0173680000 228396145 0 402718720 -0.3522535563 0.0236962251 0.2145528048 163 6.4800000000 0.7680872679 0.3473570296 0.7680872679 0.0104620942 0.0453850000 240701429 0 402718720 -0.3523919880 0.0237446111 0.2190685272 164 6.5200000000 0.7712938190 0.3499420101 0.7712938190 0.0104333972 0.0214090000 244364565 0 402718720 -0.3526204824 0.0238789637 0.2242215127 165 6.5600000000 0.7779642344 0.3525360841 0.7779642344 0.0104031196 0.0160170000 247559005 0 402718720 -0.3526974022 0.0247213561 0.2304646969 166 6.6000000000 0.7810848355 0.3551177031 0.7810848355 0.0103794708 0.0143480000 247561253 0 402718720 -0.3524577916 0.0249313507 0.2346698940 167 6.6400000000 0.7841995358 0.3576870554 0.7841995358 0.0103534925 0.0140040000 247563501 0 402718720 -0.3519793153 0.0253541786 0.2380654067 168 6.6800000000 0.7874469757 0.3602451502 0.7874469757 0.0103244048 0.0144190000 247565749 0 402718720 -0.3519443870 0.0257717669 0.2434362173 169 6.7200000000 0.7928531170 0.3628049606 0.7928531170 0.0102964424 0.0144070000 247567997 0 402718720 -0.3515776992 0.0248068850 0.2481770068 170 6.7600000000 0.7999325395 0.3653762993 0.7999325395 0.0102998173 0.0145900000 247570245 0 402718720 -0.3525275588 0.0253861248 0.2539035976 171 6.8000000000 0.8026705980 0.3679335759 0.8026705980 0.0102883798 0.0144990000 247572493 0 402718720 -0.3520610034 0.0263133012 0.2571960390 172 6.8400000000 0.8069714308 0.3704861216 0.8069714308 0.0102683787 0.0143860000 247574741 0 402718720 -0.3518681824 0.0269141942 0.2618531585 173 6.8800000000 0.8122707009 0.3730397897 0.8122707009 0.0102494445 0.0163860000 247576989 0 402718720 -0.3520891368 0.0275392104 0.2666411996 174 6.9200000000 0.8174779415 0.3755940319 0.8174779415 0.0102307346 0.0145750000 247579237 0 402718720 -0.3524176478 0.0278209038 0.2712008953 175 6.9600000000 0.8219661713 0.3781447299 0.8219661713 0.0102090332 0.0145830000 247581485 0 402718720 -0.3519482911 0.0282956176 0.2752332091 176 7.0000000000 0.8280820847 0.3807011921 0.8280820847 0.0101942869 0.0179440000 247583733 0 402718720 -0.3525529504 0.0283221379 0.2804933488 177 7.0400000000 0.8299837112 0.3832395114 0.8299837112 0.0101840894 0.0160710000 247585981 0 402718720 -0.3522150218 0.0274505895 0.2831838727 178 7.0800000000 0.8322598934 0.3857620979 0.8322598934 0.0101574140 0.0153490000 247588229 0 402718720 -0.3516640365 0.0272462331 0.2856094539 179 7.1200000000 0.8372799754 0.3882845441 0.8372799754 0.0101477859 0.0169420000 247590477 0 402718720 -0.3516795039 0.0282423086 0.2904897332 180 7.1600000000 0.8421733379 0.3908061485 0.8421733379 0.0101282327 0.0173860000 247592725 0 402718720 -0.3512351215 0.0288783237 0.2949400246 181 7.2000000000 0.8452867270 0.3933170909 0.8452867270 0.0101008894 0.0528240000 259903005 0 402718720 -0.3505506217 0.0291190427 0.2987278104 182 7.2400000000 0.8510167003 0.3958319240 0.8510167003 0.0100773713 0.0200760000 263564461 0 402718720 -0.3507442772 0.0287639704 0.3034910560 183 7.2800000000 0.8586645722 0.3983610641 0.8586645722 0.0100563164 0.0146800000 266758901 0 402718720 -0.3512417376 0.0289066769 0.3090647459 184 7.3200000000 0.8615168333 0.4008782150 0.8615168333 0.0100311432 0.0135740000 266761149 0 402718720 -0.3507487774 0.0283339210 0.3129876852 185 7.3600000000 0.8676520586 0.4034013169 0.8676520586 0.0100167143 0.0131980000 266763397 0 402718720 -0.3497818112 0.0288904216 0.3179847300 186 7.4000000000 0.8749185205 0.4059363556 0.8749185205 0.0100161295 0.0376520000 266765645 0 402718720 -0.3497821689 0.0291053150 0.3250473738 187 7.4400000000 0.8772376776 0.4084566835 0.8772376776 0.0100016376 0.0184850000 266767893 0 402718720 -0.3487755954 0.0289534498 0.3273704648 188 7.4800000000 0.8825381994 0.4109783937 0.8825381994 0.0100214538 0.0148380000 266770141 0 402718720 -0.3478926122 0.0300165024 0.3330676854 189 7.5200000000 0.8888508677 0.4135068195 0.8888508677 0.0100081516 0.0134990000 266772389 0 402718720 -0.3471903801 0.0304779541 0.3396416605 190 7.5600000000 0.8944304585 0.4160379966 0.8944304585 0.0099832837 0.0133390000 266774637 0 402718720 -0.3463217020 0.0302876364 0.3444376588 191 7.6000000000 0.9011255503 0.4185777220 0.9011255503 0.0099816195 0.0159610000 266776885 0 402718720 -0.3457262218 0.0310245268 0.3501581550 192 7.6400000000 0.9061426520 0.4211171227 0.9061426520 0.0099859559 0.0699360000 279102157 0 402718720 -0.3444477022 0.0330410302 0.3554238975 193 7.6800000000 0.9146364331 0.4236742175 0.9146364331 0.0099645842 0.0200520000 282763613 0 402718720 -0.3441362679 0.0332992412 0.3617093563 194 7.7200000000 0.9218332767 0.4262420477 0.9218332767 0.0099487420 0.0152660000 285958053 0 402718720 -0.3442996144 0.0319975875 0.3676230311 195 7.7600000000 0.9271444082 0.4288107778 0.9271444082 0.0099609777 0.0140360000 285960301 0 402718720 -0.3439233303 0.0319002643 0.3721566498 196 7.8000000000 0.9341305494 0.4313889399 0.9341305494 0.0100165768 0.0140100000 285962549 0 402718720 -0.3432424068 0.0328902043 0.3780444860 197 7.8400000000 0.9389053583 0.4339651654 0.9389053583 0.0100492065 0.0451670000 285964797 0 402718720 -0.3426213861 0.0337745585 0.3822146952 198 7.8800000000 0.9462633133 0.4365525297 0.9462633133 0.0100892382 0.0168490000 285967045 0 402718720 -0.3422258496 0.0344071090 0.3881729543 199 7.9200000000 0.9529997706 0.4391477420 0.9529997706 0.0100928840 0.0139220000 285969293 0 402718720 -0.3413788974 0.0349746943 0.3934619427 200 7.9600000000 0.9592309594 0.4417481581 0.9592309594 0.0100952746 0.0130460000 285971541 0 402718720 -0.3415375054 0.0342200808 0.3985419273 201 8.0000000000 0.9681730270 0.4443671873 0.9681730270 0.0101335107 0.0779520000 298286773 0 402718720 -0.3410054445 0.0342790373 0.4049820900 202 8.0400000000 0.9721210003 0.4469798299 0.9721210003 0.0101488560 0.0174650000 301948229 0 402718720 -0.3398658335 0.0345104337 0.4085408151 203 8.0800000000 0.9794805646 0.4496029863 0.9794805646 0.0101724847 0.0150110000 305142669 0 402718720 -0.3391140103 0.0347674116 0.4146667123 204 8.1200000000 0.9845325947 0.4522251902 0.9845325947 0.0101696128 0.0139680000 305144917 0 402718720 -0.3384808898 0.0347656496 0.4192883968 205 8.1600000000 0.9890484810 0.4548438404 0.9890484810 0.0101589495 0.0133110000 305147165 0 402718720 -0.3374020457 0.0344475880 0.4233745635 206 8.1999999990 0.9941090941 0.4574616329 0.9941090941 0.0101507072 0.0129210000 305149413 0 402718720 -0.3362645209 0.0343486778 0.4283294976 207 8.2400000000 0.9991822243 0.4600786406 0.9991822243 0.0101452458 0.0130450000 305151661 0 402718720 -0.3346384168 0.0350381210 0.4329459667 208 8.2799999990 1.0030200481 0.4626889358 1.0030200481 0.0101230621 0.0126340000 305153909 0 402718720 -0.3334478438 0.0352818370 0.4382093847 209 8.3200000000 1.0083713531 0.4652998565 1.0083713531 0.0100989838 0.0126950000 305156157 0 402718720 -0.3314937055 0.0360897593 0.4421331584 210 8.3599999990 1.0117087364 0.4679018035 1.0117087364 0.0100838135 0.0131710000 305158405 0 402718720 -0.3294953704 0.0362538472 0.4460187554 211 8.4000000000 1.0164397955 0.4705015097 1.0164397955 0.0100669125 0.0139380000 305160653 0 402718720 -0.3277050853 0.0356719345 0.4511058927 212 8.4399999990 1.0193883181 0.4730905984 1.0193883181 0.0100445726 0.0807570000 317478809 0 402718720 -0.3252347708 0.0360395201 0.4553400278 213 8.4800000000 1.0243117809 0.4756784913 1.0243117809 0.0100214660 0.0171570000 321140265 0 402718720 -0.3231192827 0.0365029871 0.4604446590 214 8.5200000000 1.0273880959 0.4782565735 1.0273880959 0.0100220883 0.0138500000 324334705 0 402718720 -0.3204509616 0.0369575098 0.4655798078 215 8.5600000000 1.0299692154 0.4808226788 1.0299692154 0.0100121634 0.0125590000 324336953 0 402718720 -0.3178730607 0.0363798812 0.4687892795 216 8.6000000000 1.0327202082 0.4833777600 1.0327202082 0.0099959503 0.0125730000 324339201 0 402718720 -0.3147983253 0.0371462032 0.4727402329 217 8.6400000000 1.0380108356 0.4859336728 1.0380108356 0.0099847788 0.0317690000 324341449 0 402718720 -0.3115737736 0.0382140242 0.4789801240 218 8.6800000000 1.0397810936 0.4884742573 1.0397810936 0.0099986872 0.0189510000 324343697 0 402718720 -0.3084067404 0.0378233753 0.4823375344 219 8.7200000000 1.0416063070 0.4909999744 1.0416063070 0.0099812435 0.0126010000 324345945 0 402718720 -0.3047378659 0.0392596647 0.4860548675 220 8.7600000000 1.0442626476 0.4935148047 1.0442626476 0.0099646015 0.0121770000 324348193 0 402718720 -0.3010775149 0.0404858403 0.4901413321 221 8.8000000000 1.0473954678 0.4960210521 1.0473954678 0.0099592330 0.0124390000 324350441 0 402718720 -0.2975641489 0.0410492979 0.4942808151 222 8.8400000000 1.0519853830 0.4985253959 1.0519853830 0.0099414540 0.0133560000 324352689 0 402718720 -0.2942618728 0.0414640121 0.4994584620 223 8.8800000000 1.0537692308 0.5010152786 1.0537692308 0.0099293848 0.0129560000 324354937 0 402718720 -0.2910462618 0.0420455001 0.5022886395 224 8.9200000000 1.0558432341 0.5034921891 1.0558432341 0.0099109673 0.0140470000 324357185 0 402718720 -0.2866427600 0.0432965346 0.5068061352 225 8.9600000000 1.0568205118 0.5059514261 1.0568205118 0.0098942850 0.0148430000 324359433 0 402718720 -0.2829603255 0.0439508334 0.5096468925 226 9.0000000000 1.0596554279 0.5084014438 1.0596554279 0.0098731683 0.0161800000 324361681 0 402718720 -0.2791900933 0.0452713892 0.5140193701 227 9.0400000000 1.0604673624 0.5108334522 1.0604673624 0.0098578412 0.0150030000 324363929 0 402718720 -0.2748233974 0.0475657918 0.5172956586 228 9.0800000000 1.0648046732 0.5132631506 1.0648046732 0.0098585508 0.0149510000 324366177 0 402718720 -0.2707956433 0.0493953973 0.5219143629 229 9.1200000000 1.0653085709 0.5156738293 1.0653085709 0.0098937253 0.0147190000 324368425 0 402718720 -0.2670617104 0.0502202436 0.5252236724 230 9.1600000000 1.0663840771 0.5180682217 1.0663840771 0.0099538713 0.0151390000 324370673 0 402718720 -0.2633331716 0.0518945120 0.5270731449 231 9.2000000000 1.0677944422 0.5204479888 1.0677944422 0.0100700780 0.0150110000 324372921 0 402718720 -0.2601428926 0.0518694818 0.5296427011 232 9.2400000000 1.0697886944 0.5228158367 1.0697886944 0.0101398781 0.0149820000 324375169 0 402718720 -0.2566582859 0.0530637279 0.5326526761 233 9.2800000000 1.0712833405 0.5251697745 1.0712833405 0.0102077458 0.0154650000 324377417 0 402718720 -0.2532252371 0.0541531257 0.5351321101 234 9.3200000000 1.0725697279 0.5275090905 1.0725697279 0.0102527201 0.0155160000 324379665 0 402718720 -0.2497391850 0.0553517453 0.5374407172 235 9.3600000000 1.0737156868 0.5298333739 1.0737156868 0.0102882935 0.0151460000 324381913 0 402718720 -0.2466205806 0.0560950898 0.5400568247 236 9.4000000000 1.0761059523 0.5321480882 1.0761059523 0.0103042245 0.0156260000 324384161 0 402718720 -0.2427918166 0.0575185381 0.5431861877 237 9.4400000000 1.0770404339 0.5344472121 1.0770404339 0.0103122876 0.0158510000 324386409 0 402718720 -0.2391695231 0.0590146184 0.5456309319 238 9.4800000000 1.0789725780 0.5367351338 1.0789725780 0.0103174507 0.0158090000 324388657 0 402718720 -0.2353519052 0.0613052025 0.5482578874 239 9.5200000000 1.0807883739 0.5390115072 1.0807883739 0.0103439152 0.0158390000 324390905 0 402718720 -0.2315854728 0.0622321703 0.5508334041 240 9.5600000000 1.0832982063 0.5412793684 1.0832982063 0.0103601878 0.0162940000 324393153 0 402718720 -0.2279406488 0.0646625161 0.5539540052 241 9.6000000000 1.0856798887 0.5435382917 1.0856798887 0.0103882869 0.0506930000 324395401 0 402718720 -0.2245188504 0.0646914542 0.5573967695 242 9.6400000000 1.0883061886 0.5457893987 1.0883061886 0.0103909461 0.0186430000 324397649 0 402718720 -0.2212020606 0.0655847341 0.5602961183 243 9.6800000000 1.0906634331 0.5480316787 1.0906634331 0.0103858494 0.0163280000 324399897 0 402718720 -0.2173429132 0.0679290742 0.5628029704 244 9.7200000000 1.0928949118 0.5502647247 1.0928949118 0.0103892307 0.0838900000 336721097 0 402718720 -0.2133662850 0.0700582564 0.5658233166 245 9.7600000000 1.0939289331 0.5524837623 1.0939289331 0.0104016480 0.0173540000 340382553 0 402718720 -0.2103543878 0.0707375109 0.5698718429 246 9.8000000000 1.0970891714 0.5546976055 1.0970891714 0.0103948572 0.0198320000 343576993 0 402718720 -0.2066447139 0.0716053247 0.5729529262 247 9.8400000000 1.1006529331 0.5569079509 1.1006529331 0.0103849430 0.0186690000 343579241 0 402718720 -0.2033293545 0.0715960413 0.5766546130 248 9.8800000000 1.1037877798 0.5591131115 1.1037877798 0.0103652199 0.0188170000 343581489 0 402718720 -0.2001116127 0.0722964704 0.5795533061 249 9.9200000000 1.1062053442 0.5613102691 1.1062053442 0.0103499204 0.0174100000 343583737 0 402718720 -0.1963402182 0.0728895366 0.5824087858 250 9.9600000000 1.1096193790 0.5635035055 1.1096193790 0.0103364629 0.0168130000 343585985 0 402718720 -0.1929075420 0.0736384690 0.5855966806 251 10.0000000000 1.1129138470 0.5656923913 1.1129138470 0.0103229783 0.0165130000 343588233 0 402718720 -0.1892560273 0.0744017288 0.5888003111 252 10.0400000000 1.1173499823 0.5678815088 1.1173499823 0.0103091634 0.0161860000 343590481 0 402718720 -0.1863273680 0.0739592165 0.5925435424 253 10.0800000000 1.1214652061 0.5700695866 1.1214652061 0.0103000436 0.0153710000 343592729 0 402718720 -0.1836611331 0.0727620199 0.5961072445 254 10.1200000000 1.1251574755 0.5722549720 1.1251574755 0.0103233371 0.0165850000 343594977 0 402718720 -0.1802565753 0.0739839673 0.5992047191 255 10.1600000000 1.1288121939 0.5744375493 1.1288121939 0.0103425135 0.0160610000 343597225 0 402718720 -0.1763115972 0.0763203055 0.6024689674 256 10.2000000000 1.1322031021 0.5766163210 1.1322031021 0.0103298034 0.0155590000 343599473 0 402718720 -0.1723644733 0.0780251473 0.6054214835 257 10.2400000000 1.1356946230 0.5787917230 1.1356946230 0.0103133858 0.0166730000 343628345 0 402718720 -0.1689929813 0.0777233914 0.6086630225 258 10.2800000000 1.1396112442 0.5809654421 1.1396112442 0.0102967942 0.0171040000 343681793 0 402718720 -0.1652827114 0.0795790181 0.6117190123 259 10.3200000000 1.1418882608 0.5831311672 1.1418882608 0.0102780357 0.0164140000 343684041 0 402718720 -0.1616239846 0.0808270276 0.6140349507 260 10.3600000000 1.1451563835 0.5852928027 1.1451563835 0.0102627855 0.0169810000 343686289 0 402718720 -0.1579993516 0.0813129470 0.6171442270 261 10.4000000000 1.1480120420 0.5874488151 1.1480120420 0.0102483827 0.1286570000 356038349 0 402718720 -0.1548199803 0.0810430646 0.6191711426 262 10.4400000000 1.1503139734 0.5895971554 1.1503139734 0.0102329087 0.0217790000 359699805 0 402718720 -0.1511825621 0.0836084634 0.6221004128 263 10.4800000000 1.1520640850 0.5917358129 1.1520640850 0.0102136125 0.0179600000 362894245 0 402718720 -0.1473961174 0.0840778500 0.6241913438 264 10.5200000000 1.1540338993 0.5938657299 1.1540338993 0.0101961429 0.0167550000 362896493 0 402718720 -0.1437197626 0.0838720426 0.6263259053 265 10.5600000000 1.1561374664 0.5959875101 1.1561374664 0.0101792873 0.0160460000 362898741 0 402718720 -0.1397460550 0.0844422206 0.6286537647 266 10.6000000000 1.1572129726 0.5980973802 1.1572129726 0.0101697548 0.0146510000 362900989 0 402718720 -0.1355833262 0.0852065012 0.6301243305 267 10.6400000000 1.1579390764 0.6001941656 1.1579390764 0.0101655604 0.0149230000 362903237 0 402718720 -0.1316031218 0.0848472342 0.6315984130 268 10.6800000000 1.1601835489 0.6022836782 1.1601835489 0.0101535588 0.0156220000 362905485 0 402718720 -0.1275763661 0.0845343396 0.6336929202 269 10.7200000000 1.1598248482 0.6043563220 1.1601835489 0.0101407855 0.0150620000 362907733 0 402718720 -0.1233092025 0.0844852626 0.6346352696 270 10.7600000000 1.1633309126 0.6064265982 1.1633309126 0.0101415735 0.0156350000 362909981 0 402718720 -0.1143533513 0.0859282166 0.6383813620 271 10.8000000000 1.1639099121 0.6084837322 1.1639099121 0.0101649062 0.0179330000 362912229 0 402718720 -0.1092835069 0.0872258171 0.6395299435 272 10.8400000000 1.1645317078 0.6105280263 1.1645317078 0.0102216829 0.0165690000 362914477 0 402718720 -0.1050002798 0.0865565464 0.6408413649 273 10.8800000000 1.1658997536 0.6125623549 1.1658997536 0.0102242879 0.0164640000 362916725 0 402718720 -0.1004560962 0.0868138969 0.6424898505 274 10.9200000000 1.1667189598 0.6145848243 1.1667189598 0.0102287661 0.0190570000 362918973 0 402718720 -0.0957959890 0.0872296393 0.6438397169 275 10.9600000000 1.1671009064 0.6165939737 1.1671009064 0.0102342328 0.0177690000 362921221 0 402718720 -0.0911556184 0.0871205330 0.6447941065 276 11.0000000000 1.1682173014 0.6185926089 1.1682173014 0.0102301308 0.0178730000 362923469 0 402718720 -0.0863206685 0.0877939165 0.6461570859 277 11.0400000000 1.1691628695 0.6205802272 1.1691628695 0.0102333420 0.1044080000 375246641 0 402718720 -0.0815407559 0.0882948935 0.6473316550 278 11.0800000000 1.1696069241 0.6225551434 1.1696069241 0.0102345542 0.0216890000 378908097 0 402718720 -0.0756380334 0.0892736316 0.6492352486 279 11.1200000000 1.1710901260 0.6245212186 1.1710901260 0.0102480337 0.0172740000 382102537 0 402718720 -0.0708094016 0.0896965787 0.6505530477 280 11.1600000000 1.1721918583 0.6264771851 1.1721918583 0.0102613038 0.0154630000 382104785 0 402718720 -0.0658517703 0.0906021520 0.6516433358 281 11.2000000000 1.1725025177 0.6284203358 1.1725025177 0.0102721072 0.0155750000 382107033 0 402718720 -0.0613615923 0.0906149298 0.6529632807 282 11.2400000000 1.1747617722 0.6303577168 1.1747617722 0.0102650875 0.0452630000 382109281 0 402718720 -0.0569953099 0.0903627351 0.6543250084 283 11.2800000000 1.1755628586 0.6322842367 1.1755628586 0.0102509933 0.0176540000 382111529 0 402718720 -0.0526774116 0.0908078700 0.6551924944 284 11.3200000000 1.1783620119 0.6342070458 1.1783620119 0.0102394512 0.0154720000 382113777 0 402718720 -0.0481290147 0.0915179104 0.6571373940 285 11.3600000000 1.1803545952 0.6361233530 1.1803545952 0.0102415061 0.0154350000 382116025 0 402718720 -0.0440471247 0.0918309614 0.6586307883 286 11.4000000000 1.1824150085 0.6380334637 1.1824150085 0.0102442679 0.0153640000 382118273 0 402718720 -0.0403246395 0.0917967558 0.6599106193 287 11.4400000000 1.1844230890 0.6399372603 1.1844230890 0.0102397310 0.0182830000 382120521 0 402718720 -0.0369526260 0.0915918276 0.6614134312 288 11.4800000000 1.1864837408 0.6418349911 1.1864837408 0.0102346976 0.0166220000 382122769 0 402718720 -0.0337572135 0.0914890915 0.6628546715 289 11.5200000000 1.1901938915 0.6437324267 1.1901938915 0.0102303367 0.0166620000 382125017 0 402718720 -0.0307537857 0.0913594067 0.6651406288 290 11.5600000000 1.1936014891 0.6456285270 1.1936014891 0.0102280373 0.0188870000 382127265 0 402718720 -0.0277809799 0.0914086401 0.6672220826 291 11.6000000000 1.1976667643 0.6475255656 1.1976667643 0.0102227157 0.0237870000 382129513 0 402718720 -0.0250555370 0.0909419209 0.6697724462 292 11.6400000000 1.2011207342 0.6494214394 1.2011207342 0.0102180741 0.0199330000 382131761 0 402718720 -0.0221663248 0.0912120342 0.6718076468 293 11.6800000000 1.2052565813 0.6513184877 1.2052565813 0.0102107230 0.0193570000 382134009 0 402718720 -0.0196579508 0.0912258402 0.6742620468 294 11.7200000000 1.2096464634 0.6532175624 1.2096464634 0.0102012640 0.0195520000 382136257 0 402718720 -0.0174593553 0.0908263251 0.6768254638 295 11.7600000000 1.2138975859 0.6551181727 1.2138975859 0.0101947576 0.0192430000 382138505 0 402718720 -0.0154703856 0.0907769725 0.6793323159 296 11.8000000000 1.2179039717 0.6570194761 1.2179039717 0.0101880225 0.0198320000 382140753 0 402718720 -0.0133625707 0.0908128098 0.6816382408 297 11.8400000000 1.2225669622 0.6589236764 1.2225669622 0.0101847537 0.0198200000 382143001 0 402718720 -0.0115890848 0.0905250609 0.6843225956 298 11.8800000000 1.2274463177 0.6608314705 1.2274463177 0.0101889222 0.0199420000 382145249 0 402718720 -0.0098578446 0.0901793987 0.6872101426 299 11.9200000000 1.2324999571 0.6627434052 1.2324999571 0.0101882410 0.0199940000 382147497 0 402718720 -0.0079335636 0.0900870413 0.6901897788 300 11.9600000000 1.2377671003 0.6646601508 1.2377671003 0.0101799381 0.0204940000 382149745 0 402718720 -0.0061656870 0.0902757496 0.6931439638 301 12.0000000000 1.2435417175 0.6665833454 1.2435417175 0.0101712690 0.0208010000 382151993 0 402718720 -0.0045154481 0.0902849063 0.6964399815 302 12.0400000000 1.2497663498 0.6685144150 1.2497663498 0.0101684399 0.0211160000 382154241 0 402718720 -0.0031890310 0.0901388451 0.6999848485 303 12.0800000000 1.2559936047 0.6704532902 1.2559936047 0.0101746862 0.1041550000 394476981 0 402718720 -0.0015099198 0.0901125818 0.7036165595 304 12.1200000000 1.2622817755 0.6724000944 1.2622817755 0.0101870656 0.0330240000 398138437 0 402718720 -0.0003342890 0.0899768546 0.7074885368 305 12.1600000000 1.2693988085 0.6743574672 1.2693988085 0.0101983432 0.0174550000 401332877 0 402718720 0.0011516125 0.0898500681 0.7116490602 306 12.2000000000 1.2766413689 0.6763257153 1.2766413689 0.0102030711 0.0152580000 401335125 0 402718720 0.0025666840 0.0896626562 0.7158393860 307 12.2400000000 1.2839113474 0.6783048216 1.2839113474 0.0102195116 0.0157050000 401337373 0 402718720 0.0038898608 0.0900208876 0.7200373411 308 12.2800000000 1.2913733721 0.6802953039 1.2913733721 0.0102386063 0.0162360000 401339621 0 402718720 0.0047345287 0.0896705836 0.7242365479 309 12.3200000000 1.2980740070 0.6822945877 1.2980740070 0.0102718943 0.0154480000 401341869 0 402718720 0.0055629346 0.0895339400 0.7283462882 310 12.3600000000 1.3055896759 0.6843052170 1.3055896759 0.0103168932 0.0164310000 401344117 0 402718720 0.0062435633 0.0892111287 0.7326647043 311 12.4000000000 1.3124010563 0.6863248178 1.3124010563 0.0103474908 0.0164290000 401346365 0 402718720 0.0071660699 0.0893748552 0.7366332412 312 12.4400000000 1.3274778128 0.6883797954 1.3274778128 0.0104543505 0.0161540000 401348613 0 402718720 0.0081258016 0.0891562179 0.7453703284 313 12.4800000000 1.3342715502 0.6904433473 1.3342715502 0.0104552228 0.0190700000 401350861 0 402718720 0.0084168874 0.0890455619 0.7492390275 314 12.5200000000 1.3421097994 0.6925187182 1.3421097994 0.0104582452 0.0190930000 401353109 0 402718720 0.0085856933 0.0885084346 0.7538766861 315 12.5600000000 1.3493013382 0.6946037423 1.3493013382 0.0104657427 0.0180300000 401355357 0 402718720 0.0088017508 0.0884917900 0.7580159307 316 12.6000000000 1.3569842577 0.6966998832 1.3569842577 0.0104672713 0.0221870000 401357605 0 402718720 0.0090883831 0.0885317102 0.7625515461 317 12.6400000000 1.3642265797 0.6988056457 1.3642265797 0.0104683597 0.0206780000 401359853 0 402718720 0.0090817418 0.0882313699 0.7667674422 318 12.6800000000 1.3714936972 0.7009210169 1.3714936972 0.0104733674 0.0212150000 401362101 0 402718720 0.0089623146 0.0879890993 0.7709401250 319 12.7200000000 1.3777439594 0.7030427189 1.3777439594 0.0104825630 0.0214860000 401364349 0 402718720 0.0088464385 0.0879971832 0.7747459412 320 12.7600000000 1.3841965199 0.7051713245 1.3841965199 0.0104927100 0.0208960000 401366597 0 402718720 0.0085990224 0.0880027115 0.7786002159 321 12.8000000000 1.3908978701 0.7073075443 1.3908978701 0.0105153031 0.0219720000 401368845 0 402718720 0.0079354327 0.0875796899 0.7824009657 322 12.8400000000 1.3967202902 0.7094485777 1.3967202902 0.0105498678 0.0225540000 401371093 0 402718720 0.0077733370 0.0877757445 0.7859126329 323 12.8800000000 1.4020211697 0.7115927653 1.4020211697 0.0106009175 0.0409580000 401373341 0 402718720 0.0071816645 0.0872219652 0.7891439795 324 12.9200000000 1.4077882767 0.7137415168 1.4077882767 0.0106639412 0.0229390000 401375589 0 402718720 0.0061189868 0.0867893547 0.7924501896 325 12.9600000000 1.4139235020 0.7158959230 1.4139235020 0.0107308051 0.1251110000 413698657 0 402718720 0.0055895210 0.0872112885 0.7953243852 326 13.0000000000 1.4188694954 0.7180522836 1.4188694954 0.0108134131 0.0312030000 417363425 0 402718720 0.0045124707 0.0874378309 0.7974629402 327 13.0400000000 1.4249148369 0.7202139428 1.4249148369 0.0109148415 0.0270910000 420557865 0 402718720 0.0035897193 0.0872247890 0.8010748625 328 13.0800000000 1.4290174246 0.7223749290 1.4290174246 0.0110060530 0.0249090000 420560113 0 402718720 0.0036170003 0.0882253721 0.8034268618 329 13.1200000000 1.4347391129 0.7245401697 1.4347391129 0.0110944843 0.0222350000 420562361 0 402718720 0.0030032196 0.0884138942 0.8067224622 330 13.1600000000 1.4395821095 0.7267069635 1.4395821095 0.0111727201 0.0220390000 420564609 0 402718720 0.0024671571 0.0884743929 0.8097720146 331 13.2000000000 1.4455382824 0.7288786593 1.4455382824 0.0112410269 0.0203280000 420566857 0 402718720 0.0019547199 0.0886068642 0.8135709167 332 13.2400000000 1.4507424831 0.7310529479 1.4507424831 0.0112959837 0.0194040000 420569105 0 402718720 0.0013915427 0.0886362642 0.8167839050 333 13.2800000000 1.4566786289 0.7332320040 1.4566786289 0.0113505404 0.1160170000 432889773 0 402718720 0.0007410531 0.0886926353 0.8202607632 334 13.3200000000 1.4616991282 0.7354130433 1.4616991282 0.0114193344 0.0372380000 436551229 0 402718720 0.0000725956 0.0886140540 0.8232076168 335 13.3600000000 1.4670330286 0.7375969836 1.4670330286 0.0114691298 0.0314580000 439745669 0 402718720 -0.0003848662 0.0889990479 0.8266726732 336 13.4000000000 1.4722473621 0.7397834430 1.4722473621 0.0115407657 0.0306870000 439747917 0 402718720 -0.0009471264 0.0893545747 0.8294695616 337 13.4400000000 1.4770948887 0.7419713108 1.4770948887 0.0116516495 0.0296090000 439750165 0 402718720 -0.0014783128 0.0902813822 0.8322746158 338 13.4800000000 1.4809844494 0.7441577402 1.4809844494 0.0117687275 0.0268960000 439752413 0 402718720 -0.0019961593 0.0908285230 0.8347595334 339 13.5200000000 1.4844548702 0.7463415076 1.4844548702 0.0118881397 0.0250980000 439754661 0 402718720 -0.0028204599 0.0908620581 0.8368282318 340 13.5600000000 1.4877156019 0.7485220196 1.4877156019 0.0119643478 0.1501650000 452084009 0 402718720 -0.0036582488 0.0909329727 0.8386456370 341 13.6000000000 1.4916925430 0.7507014053 1.4916925430 0.0120491306 0.0388260000 455745465 0 402718720 -0.0054880800 0.0918612182 0.8393404484 342 13.6400000000 1.4950498343 0.7528778627 1.4950498343 0.0121133386 0.0617180000 458939905 0 402718720 -0.0062430841 0.0920461863 0.8416810036 343 13.6800000000 1.4981032610 0.7550505315 1.4981032610 0.0121540618 0.0288690000 458942153 0 402718720 -0.0069550090 0.0921443999 0.8434481621 344 13.7200000000 1.5015360117 0.7572205474 1.5015360117 0.0122090054 0.0268150000 458944401 0 402718720 -0.0072612129 0.0926845670 0.8456183076 345 13.7600000000 1.5048559904 0.7593876067 1.5048559904 0.0122870453 0.0243140000 458946649 0 402718720 -0.0079053799 0.0926114023 0.8477769494 346 13.8000000000 1.5080037117 0.7615512370 1.5080037117 0.0123654479 0.0231840000 458948897 0 402718720 -0.0085159512 0.0926782563 0.8496498466 347 13.8400000000 1.5105593204 0.7637097618 1.5105593204 0.0123998331 0.0220970000 458951145 0 402718720 -0.0093007069 0.0921836868 0.8515525460 348 13.8800000000 1.5143061876 0.7658666481 1.5143061876 0.0124284891 0.0227120000 458953393 0 402718720 -0.0096048191 0.0929675326 0.8537070751 349 13.9200000000 1.5180033445 0.7680217675 1.5180033445 0.0124649428 0.2519000000 471346877 0 402718720 -0.0101501783 0.0929065272 0.8557656407 350 13.9600000000 1.5283795595 0.7701942184 1.5283795595 0.0125512845 0.0342680000 475008333 0 402718720 -0.0129863648 0.0931396857 0.8538938761 351 14.0000000000 1.5310250521 0.7723618276 1.5310250521 0.0125553224 0.0246750000 478202773 0 402718720 -0.0130222179 0.0933057517 0.8555055261 352 14.0400000000 1.5338323116 0.7745250960 1.5338323116 0.0125490046 0.0226570000 478205021 0 402718720 -0.0131753124 0.0931192562 0.8573291302 353 14.0800000000 1.5362763405 0.7766830315 1.5362763405 0.0125354933 0.0217040000 478207269 0 402718720 -0.0132914744 0.0927055627 0.8591059446 354 14.1200000000 1.5392686129 0.7788372281 1.5392686129 0.0125270752 0.0492200000 478209517 0 402718720 -0.0131792575 0.0926690251 0.8609263897 355 14.1600000000 1.5420424938 0.7809871021 1.5420424938 0.0125160260 0.0242130000 478211765 0 402718720 -0.0132944146 0.0923038796 0.8627855182 356 14.2000000000 1.5448775291 0.7831328617 1.5448775291 0.0125099569 0.0224760000 478214013 0 402718720 -0.0133227715 0.0918375552 0.8646097779 357 14.2400000000 1.5483425856 0.7852763063 1.5483425856 0.0125025497 0.0240080000 478216261 0 402718720 -0.0131752724 0.0921666920 0.8667274117 358 14.2800000000 1.5515034199 0.7874166055 1.5515034199 0.0124925584 0.0230960000 478218509 0 402718720 -0.0132494103 0.0915859789 0.8688879609 359 14.3200000000 1.5546122789 0.7895536408 1.5546122789 0.0124784745 0.0288920000 478220757 0 402718720 -0.0134478202 0.0908596888 0.8711459637 360 14.3600000000 1.5582659245 0.7916889527 1.5582659245 0.0124661408 0.0274850000 478223005 0 402718720 -0.0136226648 0.0900971070 0.8735511303 361 14.4000000000 1.5621812344 0.7938232804 1.5621812344 0.0124566573 0.0276530000 478225253 0 402718720 -0.0137303984 0.0897809342 0.8760818839 362 14.4400000000 1.5661444664 0.7959567643 1.5661444664 0.0124454690 0.0325620000 478227501 0 402718720 -0.0137254307 0.0897777155 0.8786672354 363 14.4800000000 1.5706048012 0.7980907809 1.5706048012 0.0124324408 0.0322320000 478229749 0 402718720 -0.0138121583 0.0897500739 0.8814454079 364 14.5200000000 1.5749228001 0.8002249348 1.5749228001 0.0124190521 0.0320570000 478231997 0 402718720 -0.0139269382 0.0893604308 0.8843069077 365 14.5600000000 1.5790797472 0.8023587836 1.5790797472 0.0124053644 0.0321330000 478234245 0 402718720 -0.0141869104 0.0888421535 0.8871616721 366 14.6000000000 1.5839134455 0.8044941789 1.5839134455 0.0123923706 0.0335890000 478236493 0 402718720 -0.0142435888 0.0893368199 0.8901916742 367 14.6400000000 1.5884262323 0.8066302335 1.5884262323 0.0123788799 0.0695560000 478238741 0 402718720 -0.0143446969 0.0893487409 0.8930335641 368 14.6800000000 1.5930933952 0.8087673617 1.5930933952 0.0123720715 0.0329170000 478240989 0 402718720 -0.0144975167 0.0892931297 0.8960545063 369 14.7200000000 1.5975744724 0.8109050503 1.5975744724 0.0123743600 0.1764410000 490566353 0 402718720 -0.0148859415 0.0888219029 0.8990072012 370 14.7600000000 1.6105450392 0.8130662395 1.6105450392 0.0123693472 0.0351700000 494227809 0 402718720 -0.0164210517 0.0887987688 0.8938490152 371 14.8000000000 1.6149467230 0.8152276424 1.6149467230 0.0123707212 0.0246830000 497422249 0 402718720 -0.0164681952 0.0884479210 0.8966792822 372 14.8400000000 1.6190943718 0.8173885745 1.6190943718 0.0123888280 0.0230850000 497424497 0 402718720 -0.0166029893 0.0881923139 0.8995234370 373 14.8800000000 1.6234774590 0.8195496707 1.6234774590 0.0124265837 0.0470340000 497426745 0 402718720 -0.0167412460 0.0880019292 0.9024422169 374 14.9200000000 1.6278059483 0.8217107837 1.6278059483 0.0124689826 0.0256730000 497428993 0 402718720 -0.0167991612 0.0875807703 0.9054035544 375 14.9600000000 1.6319646835 0.8238714608 1.6319646835 0.0125387399 0.0238980000 497431241 0 402718720 -0.0168149192 0.0872902870 0.9081746340 376 15.0000000000 1.6365536451 0.8260328496 1.6365536451 0.0126161689 0.0243920000 497433489 0 402718720 -0.0165724885 0.0877012014 0.9110243917 377 15.0400000000 1.6445508003 0.8282039847 1.6445508003 0.0128803963 0.0587640000 497435737 0 402718720 -0.0159342960 0.0879195854 0.9161602855 378 15.0800000000 1.6484993696 0.8303740783 1.6484993696 0.0129364103 0.0235710000 497437985 0 402718720 -0.0152929015 0.0883114934 0.9187440276 379 15.1200000000 1.6519964933 0.8325419475 1.6519964933 0.0129795900 0.0296620000 497440233 0 402718720 -0.0147022111 0.0884045735 0.9209113121 380 15.1600000000 1.6552631855 0.8347070034 1.6552631855 0.0130280075 0.1449950000 509759485 0 402718720 -0.0136666317 0.0887646899 0.9230120182 381 15.2000000000 1.6593823433 0.8368715056 1.6593823433 0.0130765929 0.0345540000 513420941 0 402718720 -0.0108478265 0.0904509351 0.9238966107 382 15.2400000000 1.6621420383 0.8390318997 1.6621420383 0.0131337268 0.0240930000 516615381 0 402718720 -0.0099667944 0.0905127898 0.9259119034 383 15.2800000000 1.6649250984 0.8411882788 1.6649250984 0.0131892500 0.0221120000 516617629 0 402718720 -0.0090213176 0.0908045471 0.9276673794 384 15.3200000000 1.6672983170 0.8433396070 1.6672983170 0.0132381703 0.0202820000 516619877 0 402718720 -0.0080386596 0.0908696949 0.9291152954 385 15.3600000000 1.6687300205 0.8454834782 1.6687300205 0.0132912955 0.0204320000 516622125 0 402718720 -0.0069583757 0.0907146037 0.9301897883 386 15.4000000000 1.6700235605 0.8476195924 1.6700235605 0.0133391943 0.0207870000 516624373 0 402718720 -0.0057579945 0.0910065919 0.9310374260 387 15.4400000000 1.6714777946 0.8497484250 1.6714777946 0.0134097006 0.0197150000 516626621 0 402718720 -0.0043843384 0.0917879716 0.9318153858 388 15.4800000000 1.6721546650 0.8518680287 1.6721546650 0.0135224436 0.0182380000 516628869 0 402718720 -0.0032542639 0.0922730267 0.9321191907 389 15.5200000000 1.6728037596 0.8539784033 1.6728037596 0.0136340842 0.0191960000 516631117 0 402718720 -0.0022892191 0.0923183635 0.9324497581 390 15.5600000000 1.6737068892 0.8560802712 1.6737068892 0.0137386226 0.1572960000 528952669 0 402718720 -0.0008027906 0.0935282782 0.9329208732 391 15.6000000000 1.6750484705 0.8581748190 1.6750484705 0.0138201521 0.0227740000 532614125 0 402718720 0.0009576721 0.0948346406 0.9328099489 392 15.6400000000 1.6751701832 0.8602589909 1.6751701832 0.0139021015 0.0621940000 535808565 0 402718720 0.0021122671 0.0946185440 0.9331322312 393 15.6800000000 1.6754999161 0.8623333953 1.6754999161 0.0140249974 0.0257830000 535810813 0 402718720 0.0029620845 0.0940116793 0.9333874583 394 15.7200000000 1.6759777069 0.8643984824 1.6759777069 0.0141739140 0.0239380000 535813061 0 402718720 0.0037605355 0.0932587907 0.9337547421 395 15.7600000000 1.6763772964 0.8664541249 1.6763772964 0.0143179911 0.0248960000 535815309 0 402718720 0.0048880526 0.0935399011 0.9338870645 396 15.8000000000 1.6765266657 0.8684997627 1.6765266657 0.0144286215 0.0240530000 535817557 0 402718720 0.0062537841 0.0935376287 0.9339004755 397 15.8400000000 1.6763581038 0.8705346703 1.6765266657 0.0145678696 0.0223350000 535819805 0 402718720 0.0074315653 0.0933728516 0.9340779185 398 15.8800000000 1.6761184931 0.8725587503 1.6765266657 0.0146824093 0.0211300000 535822053 0 402718720 0.0083309645 0.0927044600 0.9336386323 399 15.9200000000 1.6751363277 0.8745702229 1.6765266657 0.0147786128 0.2544970000 548157577 0 402718720 0.0101506449 0.0931726098 0.9332638979 400 15.9600000000 1.6767115593 0.8765755762 1.6767115593 0.0148729024 0.0253170000 551819033 0 402718720 0.0116711333 0.0937876031 0.9321976304 401 16.0000000000 1.6772080660 0.8785721660 1.6772080660 0.0149670144 0.0310810000 555013473 0 402718720 0.0132013150 0.0940159932 0.9323382378 402 16.0400000000 1.6772861481 0.8805590167 1.6772861481 0.0150659880 0.0270930000 555015721 0 402718720 0.0152758397 0.0940925404 0.9325670600 403 16.0800000000 1.6782320738 0.8825383543 1.6782320738 0.0151344567 0.0257470000 555017969 0 402718720 0.0168808307 0.0937618241 0.9332184196 404 16.1200000000 1.6777745485 0.8845067607 1.6782320738 0.0151943518 0.0594250000 555020217 0 402718720 0.0185823664 0.0939346999 0.9328265786 405 16.1600000000 1.6787660122 0.8864678947 1.6787660122 0.0152752746 0.0240740000 555022465 0 402718720 0.0206322316 0.0940272957 0.9334172010 406 16.2000000000 1.6804586649 0.8884235370 1.6804586649 0.0153886765 0.2847080000 567365793 0 402718720 0.0228197444 0.0944965854 0.9344750643 407 16.2400000000 1.6819759607 0.8903732972 1.6819759607 0.0155238702 0.0250830000 571027249 0 402718720 0.0246362612 0.0948995352 0.9350168109 408 16.2800000000 1.6836037636 0.8923174895 1.6836037636 0.0156842369 0.0243480000 574221689 0 402718720 0.0268991534 0.0947588906 0.9363406301 409 16.3200000000 1.6855758429 0.8942569965 1.6855758429 0.0158273057 0.0214190000 574223937 0 402718720 0.0289155357 0.0957288146 0.9372735620 410 16.3600000000 1.6885772943 0.8961943631 1.6885772943 0.0159559737 0.0214190000 574226185 0 402718720 0.0312735289 0.0968597457 0.9388963580 411 16.3999999990 1.6896367073 0.8981248798 1.6896367073 0.0161229779 0.0205310000 574228433 0 402718720 0.0325785689 0.0963897184 0.9394453764 412 16.4400000000 1.6934735775 0.9000553378 1.6934735775 0.0163441054 0.0187560000 574230681 0 402718720 0.0345719010 0.0962007120 0.9418831468 413 16.4800000000 1.6978055239 0.9019869363 1.6978055239 0.0165436910 0.2516990000 586571837 0 402718720 0.0369571373 0.0966508165 0.9444645047 414 16.5200000000 1.7004941702 0.9039156977 1.7004941702 0.0167039927 0.0272430000 590233293 0 402718720 0.0384595357 0.0960147232 0.9452169538 415 16.5599999990 1.7036702633 0.9058428171 1.7036702633 0.0168793866 0.0205940000 593427733 0 402718720 0.0397355594 0.0938811824 0.9472603798 416 16.6000000000 1.7072602510 0.9077693014 1.7072602510 0.0170587717 0.0185170000 593429981 0 402718720 0.0423084237 0.0939133316 0.9494050145 417 16.6400000000 1.7084734440 0.9096894552 1.7084734440 0.0171722965 0.0177370000 593432229 0 402718720 0.0444863327 0.0943724886 0.9499913454 418 16.6800000000 1.7080249786 0.9115993488 1.7084734440 0.0172688564 0.0485640000 593434477 0 402718720 0.0455702990 0.0934983343 0.9496433735 419 16.7199999990 1.7118974924 0.9135093682 1.7118974924 0.0174046164 0.0190030000 593436725 0 402718720 0.0483964868 0.0941047296 0.9517698288 420 16.7600000000 1.7121195793 0.9154108211 1.7121195793 0.0174745175 0.2061650000 605774249 0 402718720 0.0510203429 0.0953055024 0.9517999887 421 16.8000000000 1.7129169703 0.9173051350 1.7129169703 0.0175148206 0.0241330000 609435705 0 402718720 0.0515580066 0.0931944624 0.9518178701 422 16.8400000000 1.7139582634 0.9191929386 1.7139582634 0.0177622720 0.0176650000 612630145 0 402718720 0.0548252761 0.0908512846 0.9525315762 423 16.8799999990 1.7141482830 0.9210722657 1.7141482830 0.0178016380 0.0173800000 612632393 0 402718720 0.0575183257 0.0905811563 0.9523788691 424 16.9200000000 1.7122087479 0.9229381536 1.7141482830 0.0178232979 0.0175340000 612634641 0 402718720 0.0602085330 0.0886174738 0.9526475668 425 16.9600000000 1.7117009163 0.9247940660 1.7141482830 0.0178535042 0.0155920000 612636889 0 402718720 0.0622930974 0.0896527469 0.9508900642 426 17.0000000000 1.7114278078 0.9266406241 1.7141482830 0.0178698109 0.0159840000 612639137 0 402718720 0.0655510798 0.0896872655 0.9506478906 427 17.0400000000 1.7084767818 0.9284716221 1.7141482830 0.0178825584 0.1635620000 624974629 0 402718720 0.0676132888 0.0883715600 0.9490574598 428 17.0800000000 1.7064262629 0.9302892731 1.7141482830 0.0178886300 0.0167250000 628636085 0 402718720 0.0701467246 0.0871649608 0.9481235147 429 17.1200000000 1.7057135105 0.9320967888 1.7141482830 0.0178914804 0.0209920000 631830525 0 402718720 0.0738000497 0.0867358670 0.9475938082 430 17.1600000000 1.7011735439 0.9338853394 1.7141482830 0.0178956760 0.0190650000 631832773 0 402718720 0.0778403133 0.0857787877 0.9454586506 431 17.2000000000 1.6987904310 0.9356600612 1.7141482830 0.0178969126 0.0191700000 631835021 0 402718720 0.0809027925 0.0842166096 0.9445986748 432 17.2400000000 1.6967443228 0.9374218303 1.7141482830 0.0178946890 0.0457390000 631837269 0 402718720 0.0842021704 0.0833730325 0.9424812198 433 17.2800000000 1.6935212612 0.9391680184 1.7141482830 0.0178860425 0.0191080000 631839517 0 402718720 0.0880678520 0.0828215852 0.9405425191 434 17.3200000000 1.6885236502 0.9408946443 1.7141482830 0.0178811308 0.0189750000 631841765 0 402718720 0.0915490091 0.0811563432 0.9373325706 435 17.3600000000 1.6857708693 0.9426070034 1.7141482830 0.0178812587 0.0169710000 631844013 0 402718720 0.0961089507 0.0809964612 0.9354710579 436 17.4000000000 1.6824780703 0.9443039554 1.7141482830 0.0178709505 0.0165560000 631846261 0 402718720 0.1014807075 0.0822807625 0.9328349829 437 17.4400000000 1.6781953573 0.9459833408 1.7141482830 0.0178560623 0.0184220000 631848509 0 402718720 0.1074617282 0.0840196833 0.9299039245 438 17.4800000000 1.6740791798 0.9476456600 1.7141482830 0.0178746270 0.1373530000 644176325 0 402718720 0.1120691523 0.0843083933 0.9270933867 439 17.5200000000 1.6677590609 0.9492860095 1.7141482830 0.0179215503 0.0256490000 647837781 0 402718720 0.1136807799 0.0839418545 0.9227323532 440 17.5600000000 1.6624302864 0.9509067919 1.7141482830 0.0179286857 0.0222780000 651032221 0 402718720 0.1155554503 0.0808136016 0.9196853042 441 17.6000000000 1.6576293707 0.9525093374 1.7141482830 0.0179172007 0.0210110000 651034469 0 402718720 0.1182505414 0.0784065425 0.9171333909 442 17.6400000000 1.6528627872 0.9540938475 1.7141482830 0.0179205846 0.0215250000 651036717 0 402718720 0.1228868961 0.0786663145 0.9140245318 443 17.6800000000 1.6438391209 0.9556508346 1.7141482830 0.0179323720 0.0533230000 651038965 0 402718720 0.1315959394 0.0799538642 0.9081382155 444 17.7200000000 1.6377297640 0.9571870484 1.7141482830 0.0179231168 0.0202410000 651041213 0 402718720 0.1349704415 0.0796257183 0.9044074416 445 17.7600000000 1.6331878901 0.9587061514 1.7141482830 0.0179140853 0.1013200000 663358809 0 402718720 0.1383495927 0.0786681175 0.9015024304 446 17.8000000000 1.6288933754 0.9602088133 1.7141482830 0.0179025296 0.0199620000 667020265 0 402718720 0.1429550350 0.0786965415 0.8976703882 447 17.8400000000 1.6246711016 0.9616953061 1.7141482830 0.0178919795 0.0206540000 670214705 0 402718720 0.1457046717 0.0779151544 0.8947970867 448 17.8800000000 1.6205135584 0.9631658826 1.7141482830 0.0178819822 0.0184330000 670216953 0 402718720 0.1483348906 0.0772401169 0.8923040628 449 17.9200000000 1.6160285473 0.9646199197 1.7141482830 0.0178774946 0.0187300000 670219201 0 402718720 0.1508659124 0.0765033513 0.8894349337 450 17.9600000000 1.6128778458 0.9660604929 1.7141482830 0.0178769127 0.0177090000 670221449 0 402718720 0.1532344520 0.0749651045 0.8874891400 451 18.0000000000 1.6101977825 0.9674887352 1.7141482830 0.0178751254 0.0165650000 670223697 0 402718720 0.1566153616 0.0747946054 0.8854910135 452 18.0400000000 1.6069889069 0.9689035586 1.7141482830 0.0178668450 0.0153350000 670225945 0 402718720 0.1598980725 0.0747170523 0.8833112121 453 18.0800000000 1.6035902500 0.9703046330 1.7141482830 0.0178571119 0.0942770000 682655185 0 402718720 0.1627702266 0.0734611973 0.8811146021 454 18.1200000000 1.6021128893 0.9716962811 1.7141482830 0.0178489547 0.0196290000 686316641 0 402718720 0.1661808044 0.0745308399 0.8778770566 455 18.1600000000 1.5997039080 0.9730765177 1.7141482830 0.0178334418 0.0192160000 689511081 0 402718720 0.1698221415 0.0741260499 0.8763015270 456 18.2000000000 1.5965886116 0.9744438687 1.7141482830 0.0178166618 0.0172200000 689513329 0 402718720 0.1726434082 0.0729407519 0.8738002181 457 18.2400000000 1.5943788290 0.9758004004 1.7141482830 0.0178023643 0.0161200000 689515577 0 402718720 0.1757241488 0.0716785565 0.8722626567 458 18.2800000000 1.5940599442 0.9771503121 1.7141482830 0.0177964996 0.0492490000 689517825 0 402718720 0.1800970435 0.0722328871 0.8712401986 459 18.3200000000 1.5917520523 0.9784893137 1.7141482830 0.0177807375 0.0191150000 689520073 0 402718720 0.1842984557 0.0730409920 0.8690299988 460 18.3600000000 1.5902507305 0.9798192298 1.7141482830 0.0177684685 0.0162280000 689522321 0 402718720 0.1871011555 0.0715400502 0.8676976562 461 18.4000000000 1.5897766352 0.9811423478 1.7141482830 0.0177560868 0.0166640000 689524569 0 402718720 0.1910352260 0.0709035471 0.8665816784 462 18.4400000000 1.5876629353 0.9824551629 1.7141482830 0.0177403884 0.0160790000 689526817 0 402718720 0.1949704885 0.0709289908 0.8647194505 463 18.4800000000 1.5849343538 0.9837564139 1.7141482830 0.0177276672 0.0171650000 689529065 0 402718720 0.1983092576 0.0704195201 0.8623928428 464 18.5200000000 1.5841196775 0.9850503002 1.7141482830 0.0177173796 0.0184020000 689531313 0 402718720 0.2009955496 0.0690495595 0.8612855673 465 18.5600000000 1.5832272768 0.9863367023 1.7141482830 0.0177182291 0.1112600000 701850857 0 402718720 0.2038682997 0.0677348524 0.8600274324 466 18.6000000000 1.5828584433 0.9876167919 1.7141482830 0.0177330162 0.0229740000 705512313 0 402718720 0.2082912773 0.0670157149 0.8596708179 467 18.6400000000 1.5826766491 0.9888910100 1.7141482830 0.0177354491 0.0171140000 708706753 0 402718720 0.2122889161 0.0663933381 0.8587096930 468 18.6800000000 1.5838217735 0.9901622296 1.7141482830 0.0177484826 0.0169370000 708709001 0 402718720 0.2159645259 0.0652806312 0.8583216667 469 18.7200000000 1.5844346285 0.9914293349 1.7141482830 0.0177714094 0.0152820000 708711249 0 402718720 0.2195910811 0.0647783801 0.8576860428 470 18.7600000000 1.5858697891 0.9926941018 1.7141482830 0.0178074547 0.0407040000 708713497 0 402718720 0.2230141014 0.0636013001 0.8574259877 471 18.8000000000 1.5861178637 0.9939540249 1.7141482830 0.0178534151 0.0197220000 708715745 0 402718720 0.2269787043 0.0628731102 0.8566266298 472 18.8400000000 1.5858737230 0.9952080921 1.7141482830 0.0178858478 0.0164290000 708717993 0 402718720 0.2307268679 0.0629008114 0.8555151820 473 18.8800000000 1.5851078033 0.9964552373 1.7141482830 0.0178994505 0.0163050000 708720241 0 402718720 0.2347476035 0.0628480166 0.8538707495 474 18.9200000000 1.5812022686 0.9976888809 1.7141482830 0.0178970674 0.0163990000 708722489 0 402718720 0.2363350540 0.0625007004 0.8513715267 475 18.9600000000 1.5812766552 0.9989174867 1.7141482830 0.0179097306 0.0200720000 708724737 0 402718720 0.2393097430 0.0617653839 0.8505172729 476 19.0000000000 1.5812822580 1.0001409421 1.7141482830 0.0179259654 0.0176470000 708726985 0 402718720 0.2431918830 0.0613487735 0.8495095968 477 19.0400000000 1.5777182579 1.0013517960 1.7141482830 0.0179229222 0.0173330000 708729233 0 402718720 0.2458610088 0.0616573282 0.8466788530 478 19.0800000000 1.5817843676 1.0025660901 1.7141482830 0.0179385573 0.0205150000 708731481 0 402718720 0.2509196401 0.0611332543 0.8477157354 479 19.1200000000 1.5822776556 1.0037763439 1.7141482830 0.0179374443 0.0213300000 708733729 0 402718720 0.2536465526 0.0602401532 0.8471549153 480 19.1600000000 1.5851958990 1.0049876346 1.7141482830 0.0179568340 0.0202450000 708735977 0 402718720 0.2573444545 0.0596059673 0.8477904797 481 19.2000000000 1.5830183029 1.0061893616 1.7141482830 0.0179601815 0.0204610000 708738225 0 402718720 0.2599792480 0.0602691546 0.8457916379 482 19.2400000000 1.5856834650 1.0073916315 1.7141482830 0.0179609859 0.0195250000 708740473 0 402718720 0.2636124790 0.0603108965 0.8459996581 483 19.2800000000 1.5863648653 1.0085903339 1.7141482830 0.0179592108 0.0965560000 721070677 0 402718720 0.2667210996 0.0595462210 0.8456015587 484 19.3200000000 1.5838418007 1.0097788699 1.7141482830 0.0179474695 0.0181090000 724732133 0 402718720 0.2679021060 0.0589956641 0.8448890448 485 19.3600000000 1.5829277039 1.0109606201 1.7141482830 0.0179381862 0.0278390000 727926573 0 402718720 0.2711839974 0.0601027831 0.8434687853 486 19.4000000000 1.5834492445 1.0121385802 1.7141482830 0.0179250711 0.0404000000 727928821 0 402718720 0.2745033801 0.0612942912 0.8423309326 487 19.4400000000 1.5826413631 1.0133100439 1.7141482830 0.0179251721 0.0217540000 727931069 0 402718720 0.2766965926 0.0600342788 0.8413545489 488 19.4800000000 1.5777220726 1.0144666259 1.7141482830 0.0179156787 0.0219410000 727933317 0 402718720 0.2764400542 0.0591984317 0.8387502432 489 19.5200000000 1.5760546923 1.0156150677 1.7141482830 0.0179149105 0.0228780000 727935565 0 402718720 0.2782924473 0.0589386635 0.8371821642 490 19.5600000000 1.5715765953 1.0167496831 1.7141482830 0.0179156468 0.0205620000 727937813 0 402718720 0.2796117067 0.0585111603 0.8344814181 491 19.6000000000 1.5698037148 1.0178760661 1.7141482830 0.0179193973 0.0208400000 727940061 0 402718720 0.2817060053 0.0581776984 0.8329601288 492 19.6400000000 1.5628690720 1.0189837754 1.7141482830 0.0179107094 0.0196650000 727942309 0 402718720 0.2817619145 0.0583360419 0.8290205598 493 19.6800000000 1.5563110113 1.0200736887 1.7141482830 0.0179078989 0.0196560000 727944557 0 402718720 0.2822959423 0.0580991618 0.8252962828 494 19.7200000000 1.5519859791 1.0211504342 1.7141482830 0.0179085501 0.0226310000 727946805 0 402718720 0.2826855183 0.0562855639 0.8227636814 495 19.7600000000 1.5452040434 1.0222091284 1.7141482830 0.0179048525 0.0224310000 727949053 0 402718720 0.2826902568 0.0551912747 0.8192294240 496 19.8000000000 1.5405398607 1.0232541500 1.7141482830 0.0178923854 0.0191250000 727951301 0 402718720 0.2820223868 0.0551146269 0.8168863058 497 19.8400000000 1.5371267796 1.0242880990 1.7141482830 0.0178825556 0.0239020000 727953549 0 402718720 0.2831609845 0.0540588088 0.8146737814 498 19.8800000000 1.5298604965 1.0253033046 1.7141482830 0.0178701694 0.0216450000 727955797 0 402718720 0.2822310328 0.0535511039 0.8111184835 499 19.9200000000 1.5261147022 1.0263069346 1.7141482830 0.0178633954 0.0214640000 727958045 0 402718720 0.2825433314 0.0529879034 0.8089361787 500 19.9600000000 1.5195679665 1.0272934567 1.7141482830 0.0178592197 0.0206350000 727960293 0 402718720 0.2824477851 0.0523502752 0.8054834008 501 20.0000000000 1.5132558346 1.0282634415 1.7141482830 0.0178523862 0.0583760000 727962541 0 402718720 0.2825633585 0.0516815409 0.8018228412 502 20.0400000000 1.5100932121 1.0292232617 1.7141482830 0.0178450551 0.0208710000 727964789 0 402718720 0.2838319540 0.0507289357 0.7997925282 503 20.0800000000 1.5025293827 1.0301642282 1.7141482830 0.0178351866 0.0245870000 727967037 0 402718720 0.2844393551 0.0507413000 0.7953684330 504 20.1200000000 1.4955942631 1.0310877005 1.7141482830 0.0178257507 0.0228230000 727969285 0 402718720 0.2835209668 0.0491429120 0.7921023369 505 20.1600000000 1.4867303371 1.0319899631 1.7141482830 0.0178148337 0.0230000000 727971533 0 402718720 0.2821436226 0.0485821776 0.7877052426 506 20.2000000000 1.4812471867 1.0328778233 1.7141482830 0.0178074760 0.0258540000 727973781 0 402718720 0.2823861837 0.0496065989 0.7846786976 507 20.2400000000 1.4741145372 1.0337481126 1.7141482830 0.0178043830 0.0251540000 727976029 0 402718720 0.2824601233 0.0498826467 0.7809170485 508 20.2800000000 1.4665513039 1.0346000874 1.7141482830 0.0178057487 0.0214200000 727978277 0 402718720 0.2796202004 0.0489912033 0.7777037024 509 20.3200000000 1.4612126350 1.0354382260 1.7141482830 0.0177940258 0.0230990000 727980525 0 402718720 0.2804347575 0.0482109711 0.7746636271 510 20.3600000000 1.4530849457 1.0362571412 1.7141482830 0.0177830408 0.0228760000 727982773 0 402718720 0.2822180986 0.0487541743 0.7694939375 511 20.4000000000 1.4463115931 1.0370595960 1.7141482830 0.0177736260 0.0247450000 727985021 0 402718720 0.2828435004 0.0501308255 0.7652769089 512 20.4400000000 1.4375877380 1.0378418776 1.7141482830 0.0177814428 0.0249090000 727987269 0 402718720 0.2809484601 0.0500325151 0.7612329125 513 20.4800000000 1.4318660498 1.0386099559 1.7141482830 0.0177845357 0.0254880000 728042765 0 402718720 0.2832663655 0.0498074926 0.7570937276 514 20.5200000000 1.4249759912 1.0393616408 1.7141482830 0.0177791455 0.0255960000 728147413 0 402718720 0.2834032178 0.0501168892 0.7533544302 515 20.5600000000 1.4187020063 1.0400982240 1.7141482830 0.0177764197 0.0564380000 728149661 0 402718720 0.2852269709 0.0509222224 0.7490845919 516 20.6000000000 1.4110881090 1.0408171967 1.7141482830 0.0177821076 0.0267840000 728151909 0 402718720 0.2861232162 0.0506394170 0.7445106506 517 20.6400000000 1.4107561111 1.0415327458 1.7141482830 0.0177770770 0.0261780000 728154157 0 402718720 0.2847373188 0.0497857220 0.7447846532 518 20.6800000000 1.4015098810 1.0422276824 1.7141482830 0.0177683464 0.0267360000 728156405 0 402718720 0.2897067666 0.0499545857 0.7374779582 519 20.7200000000 1.4018740654 1.0429206426 1.7141482830 0.0177645413 0.0259100000 728158653 0 402718720 0.2865530252 0.0508247986 0.7390666008 520 20.7600000000 1.4002792835 1.0436078708 1.7141482830 0.0177606187 0.0315580000 728160901 0 402718720 0.2833103240 0.0511145927 0.7395523190 521 20.8000000000 1.3949056864 1.0442821468 1.7141482830 0.0177652578 0.0250020000 728163149 0 402718720 0.2833219767 0.0505892672 0.7366318703 522 20.8400000000 1.3912249804 1.0449467883 1.7141482830 0.0177570050 0.0245920000 728165397 0 402718720 0.2839602828 0.0491645709 0.7344064116 523 20.8800000000 1.3921637535 1.0456106831 1.7141482830 0.0177497404 0.0249570000 728167645 0 402718720 0.2799697220 0.0483415350 0.7366353869 524 20.9200000000 1.3830109835 1.0462545768 1.7141482830 0.0177360581 0.1213720000 740489005 0 402718720 0.2859414220 0.0488500893 0.7290685177 525 20.9600000000 1.3802855015 1.0468908261 1.7141482830 0.0177304925 0.0169910000 744157805 0 402718720 0.2865563035 0.0499724969 0.7264579535 526 21.0000000000 1.3741128445 1.0475129212 1.7141482830 0.0177174108 0.0319330000 747352245 0 402718720 0.2885588408 0.0486415364 0.7222176194 527 21.0400000000 1.3687717915 1.0481225206 1.7141482830 0.0177086715 0.0232140000 747354493 0 402718720 0.2888159752 0.0485602878 0.7192758322 528 21.0800000000 1.3663901091 1.0487253001 1.7141482830 0.0176981793 0.0561490000 747356741 0 402718720 0.2897168994 0.0484500602 0.7177446485 529 21.1200000000 1.3571606874 1.0493083538 1.7141482830 0.0176875210 0.0246510000 747358989 0 402718720 0.2938039303 0.0477332175 0.7107763886 530 21.1600000000 1.3552421331 1.0498855873 1.7141482830 0.0176816740 0.0219050000 747361237 0 402718720 0.2928709984 0.0479570962 0.7100942731 531 21.2000000000 1.3480640650 1.0504471287 1.7141482830 0.0176697295 0.0214060000 747363485 0 402718720 0.2948361337 0.0476936586 0.7051954269 532 21.2400000000 1.3431893587 1.0509973961 1.7141482830 0.0176605819 0.0207190000 747365733 0 402718720 0.2951256335 0.0473049805 0.7024301887 533 21.2800000000 1.3395296335 1.0515387324 1.7141482830 0.0176477502 0.0245320000 747367981 0 402718720 0.2944768071 0.0470233448 0.7008495927 534 21.3200000000 1.3323451281 1.0520645870 1.7141482830 0.0176353778 0.0217210000 747370229 0 402718720 0.2965844572 0.0463978052 0.6956481338 535 21.3600000000 1.3248294592 1.0525744279 1.7141482830 0.0176235107 0.0269570000 747372477 0 402718720 0.2991079092 0.0471559390 0.6903014779 536 21.4000000000 1.3217617273 1.0530766430 1.7141482830 0.0176140088 0.0219900000 747374725 0 402718720 0.2980811596 0.0468826666 0.6890476942 537 21.4400000000 1.3135592937 1.0535617131 1.7141482830 0.0176038937 0.0211770000 747376973 0 402718720 0.3009071350 0.0465045646 0.6832037568 538 21.4800000000 1.3085643053 1.0540356956 1.7141482830 0.0175927885 0.0273220000 747379221 0 402718720 0.3008981645 0.0465286486 0.6803727746 539 21.5200000000 1.3033070564 1.0544981657 1.7141482830 0.0175824303 0.0238220000 747381469 0 402718720 0.3001847565 0.0463886112 0.6777834892 540 21.5600000000 1.2954280376 1.0549443321 1.7141482830 0.0175709319 0.0216690000 747383717 0 402718720 0.3013352752 0.0468032919 0.6728939414 541 21.6000000000 1.2901972532 1.0553791804 1.7141482830 0.0175603913 0.0229600000 747385965 0 402718720 0.3013660014 0.0473238900 0.6697447300 542 21.6400000000 1.2829661369 1.0557990825 1.7141482830 0.0175538859 0.0519310000 747388213 0 402718720 0.3020592630 0.0469005257 0.6652880311 543 21.6800000000 1.2799934149 1.0562119635 1.7141482830 0.0175416322 0.0238990000 747390461 0 402718720 0.3021989465 0.0459899530 0.6635388136 544 21.7200000000 1.2740590572 1.0566124177 1.7141482830 0.0175277413 0.0250120000 747392709 0 402718720 0.3023606241 0.0464360602 0.6602041125 545 21.7600000000 1.2677243948 1.0569997791 1.7141482830 0.0175126251 0.0233340000 747394957 0 402718720 0.3028775454 0.0459922999 0.6562926173 546 21.8000000000 1.2642440796 1.0573793474 1.7141482830 0.0175005787 0.0238600000 747397205 0 402718720 0.3033219874 0.0463228375 0.6540915370 547 21.8400000000 1.2578741312 1.0577458827 1.7141482830 0.0174853793 0.0263450000 747399453 0 402718720 0.3038148880 0.0470079258 0.6501014829 548 21.8800000000 1.2548484802 1.0581055589 1.7141482830 0.0174721967 0.0251480000 747401701 0 402718720 0.3027289212 0.0470387936 0.6489751935 549 21.9200000000 1.2512525320 1.0584573749 1.7141482830 0.0174586257 0.0232140000 747403949 0 402718720 0.3030061722 0.0468019210 0.6468028426 550 21.9600000000 1.2472581863 1.0588006491 1.7141482830 0.0174453050 0.0258640000 747406197 0 402718720 0.3026400506 0.0475482717 0.6446235776 551 22.0000000000 1.2426753044 1.0591343599 1.7141482830 0.0174345988 0.0253070000 747408445 0 402718720 0.3026429415 0.0476102754 0.6419975162 552 22.0400000000 1.2389214039 1.0594600611 1.7141482830 0.0174226199 0.0243110000 747410693 0 402718720 0.3036201596 0.0481971316 0.6392055154 553 22.0800000000 1.2369990349 1.0597811081 1.7141482830 0.0174135453 0.0251330000 747412941 0 402718720 0.3030900359 0.0481611528 0.6383833885 554 22.1200000000 1.2329306602 1.0600936524 1.7141482830 0.0174039494 0.1118550000 759729617 0 402718720 0.3031916618 0.0477167442 0.6360217929 555 22.1600000000 1.2282623053 1.0603966590 1.7141482830 0.0173892932 0.0257610000 763391073 0 402718720 0.3014591336 0.0492965914 0.6345473528 556 22.2000000000 1.2233370543 1.0606897172 1.7141482830 0.0173832126 0.0662920000 766585513 0 402718720 0.3015665412 0.0497405045 0.6315087080 557 22.2400000000 1.2204469442 1.0609765345 1.7141482830 0.0173782258 0.0245330000 766587761 0 402718720 0.3011092842 0.0491840579 0.6303941607 558 22.2800000000 1.2162669897 1.0612548328 1.7141482830 0.0173669096 0.0256070000 766590009 0 402718720 0.3003706634 0.0486607403 0.6283082366 559 22.3200000000 1.2131848335 1.0615266217 1.7141482830 0.0173561995 0.0246140000 766592257 0 402718720 0.3000344634 0.0492436960 0.6265282035 560 22.3600000000 1.2108751535 1.0617933155 1.7141482830 0.0173470331 0.0236480000 766594505 0 402718720 0.2995755672 0.0493067056 0.6254780293 561 22.4000000000 1.2069358826 1.0620520367 1.7141482830 0.0173378503 0.0253310000 766596753 0 402718720 0.3006240427 0.0490198322 0.6227348447 562 22.4400000000 1.2047410011 1.0623059316 1.7141482830 0.0173280829 0.0234840000 766599001 0 402718720 0.2999874651 0.0495381579 0.6217690706 563 22.4800000000 1.1998734474 1.0625502789 1.7141482830 0.0173214392 0.0235930000 766601249 0 402718720 0.3007195294 0.0495155044 0.6186208129 564 22.5200000000 1.1964161396 1.0627876297 1.7141482830 0.0173137063 0.0223520000 766603497 0 402718720 0.3006285727 0.0489899591 0.6168010831 565 22.5600000000 1.1906740665 1.0630139774 1.7141482830 0.0173057832 0.0246530000 766605745 0 402718720 0.3016637266 0.0483587123 0.6128456593 566 22.6000000000 1.1870541573 1.0632331297 1.7141482830 0.0172990736 0.0210170000 766607993 0 402718720 0.3019675314 0.0481334627 0.6104694009 567 22.6400000000 1.1837649345 1.0634457078 1.7141482830 0.0172904871 0.0221750000 766610241 0 402718720 0.3022440374 0.0480845422 0.6083778143 568 22.6800000000 1.1793037653 1.0636496833 1.7141482830 0.0172812858 0.0835810000 778922865 0 402718720 0.3030912876 0.0476077348 0.6052580476 569 22.7200000000 1.1734333038 1.0638426246 1.7141482830 0.0172731821 0.0304140000 782584321 0 402718720 0.3050827384 0.0468714908 0.6014050245 570 22.7600000000 1.1673911810 1.0640242887 1.7141482830 0.0172627069 0.0603600000 785778761 0 402718720 0.3045008183 0.0475632288 0.5982978344 571 22.8000000000 1.1620186567 1.0641959076 1.7141482830 0.0172550206 0.0221660000 785781009 0 402718720 0.3039233983 0.0479442887 0.5956256390 572 22.8400000000 1.1568778753 1.0643579390 1.7141482830 0.0172485610 0.0213370000 785783257 0 402718720 0.3036725223 0.0472339429 0.5927312970 573 22.8800000000 1.1511346102 1.0645093817 1.7141482830 0.0172369991 0.0217520000 785785505 0 402718720 0.3031461537 0.0473834090 0.5897911787 574 22.9200000000 1.1463518143 1.0646519644 1.7141482830 0.0172262544 0.0230170000 785787753 0 402718720 0.3024506867 0.0475184768 0.5873492956 575 22.9600000000 1.1402634382 1.0647834626 1.7141482830 0.0172163959 0.0226460000 785790001 0 402718720 0.3017968535 0.0470284633 0.5841688514 576 23.0000000000 1.1356896162 1.0649065635 1.7141482830 0.0172039437 0.0229010000 785792249 0 402718720 0.3014706671 0.0460084416 0.5816945434 577 23.0400000000 1.1298204660 1.0650190660 1.7141482830 0.0171916604 0.0221550000 785794497 0 402718720 0.3005425036 0.0465645753 0.5786998868 578 23.0800000000 1.1240490675 1.0651211940 1.7141482830 0.0171802500 0.0275360000 785796745 0 402718720 0.3001998663 0.0465167277 0.5754336119 579 23.1200000000 1.1185448170 1.0652134628 1.7141482830 0.0171684497 0.0234530000 785798993 0 402718720 0.2999122143 0.0458005294 0.5722911954 580 23.1600000000 1.1123772860 1.0652947797 1.7141482830 0.0171550345 0.0237110000 785801241 0 402718720 0.2996757925 0.0456095487 0.5688253641 581 23.2000000000 1.1064977646 1.0653656971 1.7141482830 0.0171415181 0.0284450000 785803489 0 402718720 0.2989878953 0.0457259342 0.5657613277 582 23.2400000000 1.0995337963 1.0654244051 1.7141482830 0.0171311485 0.0248350000 785805737 0 402718720 0.2985100448 0.0449876413 0.5620856285 583 23.2800000000 1.0940320492 1.0654734749 1.7141482830 0.0171181442 0.0977230000 798121309 0 402718720 0.2983272672 0.0442221612 0.5588885546 584 23.3200000000 1.0869188309 1.0655101964 1.7141482830 0.0171067195 0.0623440000 801782765 0 402718720 0.2980957627 0.0450458527 0.5547471046 585 23.3600000000 1.0799547434 1.0655348879 1.7141482830 0.0170939790 0.0259940000 804977205 0 402718720 0.2971471548 0.0449408926 0.5511943102 586 23.4000000000 1.0734007359 1.0655483108 1.7141482830 0.0170826439 0.0215440000 804979453 0 402718720 0.2972692251 0.0442323647 0.5472471714 587 23.4400000000 1.0674400330 1.0655515335 1.7141482830 0.0170731631 0.0200660000 804981701 0 402718720 0.2963692546 0.0442788601 0.5441880226 588 23.4800000000 1.0510008335 1.0655267874 1.7141482830 0.0170717752 0.0190940000 804983949 0 402718720 0.2950724065 0.0449254960 0.5352189541 589 23.5200000000 1.0448608398 1.0654917009 1.7141482830 0.0170635700 0.0193520000 804986197 0 402718720 0.2943532765 0.0453067869 0.5318965316 590 23.5600000000 1.0375535488 1.0654443481 1.7141482830 0.0170602793 0.0192500000 804988445 0 402718720 0.2933712304 0.0455954559 0.5281990170 591 23.6000000000 1.0306174755 1.0653854194 1.7141482830 0.0170595961 0.0190670000 804990693 0 402718720 0.2927855551 0.0453037806 0.5244628787 592 23.6400000000 1.0223139524 1.0653126636 1.7141482830 0.0170505206 0.0181310000 804992941 0 402718720 0.2922560275 0.0449480489 0.5198190808 593 23.6800000000 1.0146694183 1.0652272618 1.7141482830 0.0170393036 0.0219650000 804995189 0 402718720 0.2914208174 0.0448139757 0.5157495141 594 23.7200000000 1.0074952841 1.0651300699 1.7141482830 0.0170278709 0.0228630000 804997437 0 402718720 0.2907800078 0.0448414721 0.5117757916 595 23.7600000000 1.0014069080 1.0650229722 1.7141482830 0.0170164429 0.1121810000 817312341 0 402718720 0.2899716794 0.0448096395 0.5086441040 596 23.8000000000 0.9940507412 1.0649038912 1.7141482830 0.0170044421 0.0287640000 820973797 0 402718720 0.2889421284 0.0441360101 0.5040745735 597 23.8400000000 0.9869630337 1.0647733370 1.7141482830 0.0169925825 0.0203240000 824168237 0 402718720 0.2877432406 0.0455584265 0.5010125637 598 23.8800000000 0.9788557291 1.0646296621 1.7141482830 0.0169858232 0.0178310000 824170485 0 402718720 0.2868490517 0.0453805439 0.4965146184 599 23.9200000000 0.9721382260 1.0644752524 1.7141482830 0.0169762640 0.0190920000 824172733 0 402718720 0.2854482830 0.0463396572 0.4933662117 600 23.9600000000 0.9651308060 1.0643096783 1.7141482830 0.0169714334 0.0512520000 824174981 0 402718720 0.2847342491 0.0462863036 0.4895652831 601 24.0000000000 0.9582399726 1.0641331896 1.7141482830 0.0169627226 0.0199030000 824177229 0 402718720 0.2836036086 0.0461278968 0.4862836301 602 24.0400000000 0.9506295323 1.0639446453 1.7141482830 0.0169520046 0.0192970000 824179477 0 402718720 0.2826375663 0.0465745479 0.4820938408 603 24.0800000000 0.9443901777 1.0637463792 1.7141482830 0.0169408142 0.0183350000 824181725 0 402718720 0.2815759480 0.0464831479 0.4790915251 604 24.1200000000 0.9386920333 1.0635393356 1.7141482830 0.0169289137 0.0186250000 824183973 0 402718720 0.2802608609 0.0469145775 0.4764048159 605 24.1600000000 0.9328062534 1.0633232478 1.7141482830 0.0169188452 0.0230180000 824186221 0 402718720 0.2793191671 0.0465303771 0.4734567702 606 24.2000000000 0.9275625348 1.0630992203 1.7141482830 0.0169075383 0.0198750000 824188469 0 402718720 0.2785367072 0.0460998416 0.4708078504 607 24.2400000000 0.9197803140 1.0628631100 1.7141482830 0.0168956723 0.0182440000 824190717 0 402718720 0.2775581777 0.0458867773 0.4666061103 608 24.2800000000 0.9138984680 1.0626181024 1.7141482830 0.0168832094 0.0236070000 824192965 0 402718720 0.2764702439 0.0463423580 0.4637512863 609 24.3200000000 0.9082465768 1.0623646188 1.7141482830 0.0168737879 0.1213030000 836511113 0 402718720 0.2758792937 0.0457750484 0.4606179893 610 24.3600000000 0.9028778076 1.0621031650 1.7141482830 0.0168624707 0.0266200000 840172057 0 402718720 0.2752592862 0.0442454927 0.4577441812 611 24.4000000000 0.8949917555 1.0618296602 1.7141482830 0.0168504139 0.0217010000 843366497 0 402718720 0.2745711803 0.0442388803 0.4531731904 612 24.4400000000 0.8889304996 1.0615471453 1.7141482830 0.0168384432 0.0180710000 843368745 0 402718720 0.2736023068 0.0448742434 0.4500395060 613 24.4800000000 0.8840427399 1.0612575785 1.7141482830 0.0168280254 0.0176010000 843370993 0 402718720 0.2728461027 0.0441310331 0.4474837780 614 24.5200000000 0.8761476874 1.0609560966 1.7141482830 0.0168179497 0.0430940000 843373241 0 402718720 0.2720310688 0.0437216163 0.4432341456 615 24.5600000000 0.8710370064 1.0606472851 1.7141482830 0.0168054013 0.0199180000 843375489 0 402718720 0.2715660930 0.0436925143 0.4403544962 616 24.6000000000 0.8644666076 1.0603288100 1.7141482830 0.0167934848 0.0174410000 843377737 0 402718720 0.2709516287 0.0429137163 0.4366356730 617 24.6400000000 0.8578282595 1.0600006081 1.7141482830 0.0167821803 0.0175010000 843379985 0 402718720 0.2700587511 0.0426247269 0.4331446886 618 24.6800000000 0.8505569100 1.0596617025 1.7141482830 0.0167719383 0.0172980000 843382233 0 402718720 0.2695343792 0.0427000858 0.4286931455 619 24.7200000000 0.8418809772 1.0593098758 1.7141482830 0.0167611313 0.0222590000 843384481 0 402718720 0.2689131796 0.0425852798 0.4237431288 620 24.7600000000 0.8360484838 1.0589497767 1.7141482830 0.0167514582 0.1279040000 855705281 0 402718720 0.2679277062 0.0431465320 0.4206700623 621 24.8000000000 0.8301728964 1.0585813760 1.7141482830 0.0167413824 0.0262370000 859366737 0 402718720 0.2674403191 0.0435239263 0.4166997373 622 24.8400000000 0.8236269951 1.0582036358 1.7141482830 0.0167304514 0.0171800000 862561177 0 402718720 0.2666037083 0.0431780443 0.4131653905 623 24.8800000000 0.8170185685 1.0578165009 1.7141482830 0.0167197429 0.0166430000 862563425 0 402718720 0.2657077610 0.0434984937 0.4096966386 624 24.9200000000 0.8101072311 1.0574195309 1.7141482830 0.0167092719 0.0171250000 862565673 0 402718720 0.2644140720 0.0436403863 0.4060364366 625 24.9600000000 0.8037055135 1.0570135884 1.7141482830 0.0166993896 0.0469260000 862567921 0 402718720 0.2633732855 0.0433979258 0.4027451277 626 25.0000000000 0.7979255319 1.0565997098 1.7141482830 0.0166889963 0.0188440000 862570169 0 402718720 0.2626068294 0.0427457839 0.3996396065 627 25.0400000000 0.7914816141 1.0561768739 1.7141482830 0.0166794952 0.0164780000 862572417 0 402718720 0.2612376809 0.0424069241 0.3965853751 628 25.0800000000 0.7848928571 1.0557448930 1.7141482830 0.0166716897 0.1255100000 874891701 0 402718720 0.2598935366 0.0433645621 0.3934448659 629 25.1200000000 0.7807918191 1.0553077657 1.7141482830 0.0166651649 0.0165520000 878553157 0 402718720 0.2585525811 0.0432893224 0.3913176954 630 25.1600000000 0.7742901444 1.0548617059 1.7141482830 0.0166603400 0.0196090000 881747597 0 402718720 0.2571942210 0.0433080457 0.3880810738 631 25.2000000000 0.7683669329 1.0544076730 1.7141482830 0.0166581158 0.0143190000 881749845 0 402718720 0.2557638288 0.0434533954 0.3851674199 632 25.2400000000 0.7637601495 1.0539477877 1.7141482830 0.0166552454 0.0142070000 881752093 0 402718720 0.2543776333 0.0431425720 0.3833208382 633 25.2800000000 0.7567434907 1.0534782706 1.7141482830 0.0166514966 0.0139400000 881754341 0 402718720 0.2527850270 0.0433379114 0.3799079657 634 25.3200000000 0.7505005598 1.0530003878 1.7141482830 0.0166487212 0.0138690000 881756589 0 402718720 0.2507660985 0.0438627042 0.3775949776 635 25.3600000000 0.7459432483 1.0525168333 1.7141482830 0.0166488923 0.1128870000 894077889 0 402718720 0.2494570464 0.0435494147 0.3757547438 636 25.4000000000 0.7402077913 1.0520257813 1.7141482830 0.0166481564 0.0200780000 897739345 0 402718720 0.2482923716 0.0430169106 0.3720812798 637 25.4400000000 0.7347539067 1.0515277093 1.7141482830 0.0166416426 0.0148360000 900933785 0 402718720 0.2467291802 0.0430710092 0.3697063029 638 25.4800000000 0.7292386293 1.0510225540 1.7141482830 0.0166340030 0.0143390000 900936033 0 402718720 0.2454210371 0.0429503359 0.3671343923 639 25.5200000000 0.7240474224 1.0505108558 1.7141482830 0.0166261939 0.0140610000 900938281 0 402718720 0.2436634898 0.0423021279 0.3652579486 640 25.5600000000 0.7192202210 1.0499932142 1.7141482830 0.0166160821 0.0430570000 900940529 0 402718720 0.2422100455 0.0421480685 0.3633514047 641 25.6000000000 0.7138699293 1.0494688409 1.7141482830 0.0166063578 0.0188570000 900942777 0 402718720 0.2405162007 0.0420540646 0.3609462976 642 25.6400000000 0.7090978622 1.0489386681 1.7141482830 0.0165957787 0.0148960000 900945025 0 402718720 0.2386042029 0.0418740250 0.3593044877 643 25.6800000000 0.7034639716 1.0484013824 1.7141482830 0.0165850761 0.0147340000 900947273 0 402718720 0.2369054705 0.0414655060 0.3574716449 644 25.7200000000 0.6984283924 1.0478579460 1.7141482830 0.0165747569 0.0137430000 900949521 0 402718720 0.2349808663 0.0413934067 0.3559344709 645 25.7600000000 0.6930296421 1.0473078246 1.7141482830 0.0165650761 0.0160190000 900951769 0 402718720 0.2333293110 0.0411533825 0.3538365364 646 25.8000000000 0.6882805824 1.0467520549 1.7141482830 0.0165550351 0.0148330000 900954017 0 402718720 0.2311032116 0.0406815074 0.3526824415 647 25.8400000000 0.6820443273 1.0461883645 1.7141482830 0.0165455050 0.0144970000 900956265 0 402718720 0.2284844071 0.0408717282 0.3512124717 648 25.8800000000 0.6769251227 1.0456185138 1.7141482830 0.0165396538 0.1209000000 913280381 0 402718720 0.2263803631 0.0411338545 0.3496561944 649 25.9200000000 0.6717447042 1.0450424370 1.7141482830 0.0165337296 0.0151410000 916941837 0 402718720 0.2239361703 0.0410778485 0.3476180732 650 25.9600000000 0.6610072851 1.0444516137 1.7141482830 0.0165341458 0.0176810000 920136277 0 402718720 0.2193764597 0.0391281322 0.3447588682 651 26.0000000000 0.6485097408 1.0438434081 1.7141482830 0.0165340644 0.0138320000 920138525 0 402718720 0.2135181874 0.0394369401 0.3414459229 652 26.0400000000 0.6416130066 1.0432264903 1.7141482830 0.0165273195 0.0131510000 920140773 0 402718720 0.2101674676 0.0393970311 0.3398846984 653 26.0800000000 0.6351492405 1.0426015634 1.7141482830 0.0165258816 0.0353080000 920143021 0 402718720 0.2066907883 0.0402549841 0.3385983407 654 26.1200000000 0.6291089654 1.0419693117 1.7141482830 0.0165320289 0.0197340000 920145269 0 402718720 0.2032912076 0.0403224342 0.3374458551 655 26.1600000000 0.6219685674 1.0413280892 1.7141482830 0.0165262371 0.0139180000 920147517 0 402718720 0.1999920160 0.0399124064 0.3359123468 656 26.2000000000 0.6155394912 1.0406790212 1.7141482830 0.0165189581 0.0169800000 920149765 0 402718720 0.1963525265 0.0400572009 0.3344821036 657 26.2400000000 0.6092571020 1.0400223669 1.7141482830 0.0165110379 0.0160790000 920152013 0 402718720 0.1927005947 0.0401030257 0.3335979283 658 26.2800000000 0.6021892428 1.0393569670 1.7141482830 0.0165028161 0.0145240000 920154261 0 402718720 0.1888232529 0.0408895686 0.3324533999 659 26.3200000000 0.5959768295 1.0386841595 1.7141482830 0.0164952077 0.0158970000 920156509 0 402718720 0.1849292666 0.0417692252 0.3313875198 660 26.3600000000 0.5899654031 1.0380042826 1.7141482830 0.0164909728 0.0147650000 920158757 0 402718720 0.1812345684 0.0419719927 0.3301998377 661 26.4000000000 0.5831957459 1.0373162213 1.7141482830 0.0164876035 0.0149950000 920161005 0 402718720 0.1771941781 0.0424343385 0.3290947378 662 26.4400000000 0.5775553584 1.0366217184 1.7141482830 0.0164857376 0.0169280000 920163253 0 402718720 0.1732081920 0.0439476743 0.3291854858 663 26.4800000000 0.5713365078 1.0359199308 1.7141482830 0.0164945774 0.0161350000 920165501 0 402718720 0.1694654673 0.0445871875 0.3285123110 664 26.5200000000 0.5652554631 1.0352110988 1.7141482830 0.0165011530 0.0171910000 920167749 0 402718720 0.1658748835 0.0439972170 0.3256912529 665 26.5600000000 0.5595330596 1.0344957934 1.7141482830 0.0164953446 0.0165480000 920169997 0 402718720 0.1623477489 0.0442779213 0.3250890672 666 26.6000000000 0.5530725718 1.0337729358 1.7141482830 0.0164899320 0.0154910000 920172245 0 402718720 0.1585897505 0.0456219241 0.3245796859 667 26.6400000000 0.5489410162 1.0330460513 1.7141482830 0.0164942283 0.1053790000 932496841 0 402718720 0.1550159156 0.0465957187 0.3237097859 668 26.6800000000 0.5422518849 1.0323113295 1.7141482830 0.0165087701 0.0169980000 936158297 0 402718720 0.1505431682 0.0486490950 0.3245159090 669 26.7200000000 0.5369779468 1.0315709209 1.7141482830 0.0165418750 0.0162060000 939352737 0 402718720 0.1468323022 0.0490362868 0.3235446811 670 26.7600000000 0.5317507982 1.0308249207 1.7141482830 0.0165655265 0.0141400000 939354985 0 402718720 0.1435927749 0.0486148857 0.3229157925 671 26.8000000000 0.5263046026 1.0300730275 1.7141482830 0.0165719074 0.0141120000 939357233 0 402718720 0.1402802020 0.0482118875 0.3219023049 672 26.8400000000 0.5209966302 1.0293154734 1.7141482830 0.0165666264 0.0354610000 939359481 0 402718720 0.1370740980 0.0492572077 0.3204583824 673 26.8800000000 0.5158762932 1.0285525622 1.7141482830 0.0165592256 0.0175570000 939361729 0 402718720 0.1339913607 0.0498049445 0.3194174170 674 26.9200000000 0.5111693740 1.0277849314 1.7141482830 0.0165518973 0.0152600000 939363977 0 402718720 0.1310545802 0.0503305346 0.3178732097 675 26.9600000000 0.5064156651 1.0270125325 1.7141482830 0.0165434947 0.0138910000 939366225 0 402718720 0.1281089485 0.0508639328 0.3175735772 676 27.0000000000 0.5016972423 1.0262354389 1.7141482830 0.0165410528 0.0150060000 939368473 0 402718720 0.1251357049 0.0517894439 0.3165093958 677 27.0400000000 0.4983119071 1.0254556404 1.7141482830 0.0165489530 0.0152290000 939370721 0 402718720 0.1220998615 0.0523696765 0.3158916533 678 27.0800000000 0.4940843582 1.0246719070 1.7141482830 0.0165552413 0.0161510000 939372969 0 402718720 0.1192932948 0.0533928275 0.3148019016 679 27.1200000000 0.4893545508 1.0238835162 1.7141482830 0.0165626370 0.0163490000 939375217 0 402718720 0.1163187549 0.0540519133 0.3134838343 680 27.1600000000 0.4839729369 1.0230895300 1.7141482830 0.0165619219 0.0171020000 939377465 0 402718720 0.1136692464 0.0536371842 0.3122013211 681 27.2000000000 0.4794982076 1.0222913049 1.7141482830 0.0165538092 0.0150940000 939379713 0 402718720 0.1110632494 0.0541512817 0.3112381995 682 27.2400000000 0.4750674069 1.0214889238 1.7141482830 0.0165484705 0.0162840000 939381961 0 402718720 0.1082015336 0.0546839088 0.3099226356 683 27.2800000000 0.4702490866 1.0206818377 1.7141482830 0.0165479016 0.0167090000 939384209 0 402718720 0.1055374220 0.0552041344 0.3087631762 684 27.3200000000 0.4655376375 1.0198702233 1.7141482830 0.0165502526 0.0172910000 939386457 0 402718720 0.1027091891 0.0555625446 0.3073807061 685 27.3600000000 0.4602288008 1.0190532286 1.7141482830 0.0165479039 0.0171100000 939388705 0 402718720 0.1000936851 0.0558700785 0.3055906296 686 27.4000000000 0.4546523690 1.0182304868 1.7141482830 0.0165437042 0.0175100000 939390953 0 402718720 0.0972327143 0.0569854118 0.3041747510 687 27.4400000000 0.4494338632 1.0174025441 1.7141482830 0.0165512452 0.0197340000 939393201 0 402718720 0.0944508240 0.0577947348 0.3024137020 688 27.4800000000 0.4439633489 1.0165690569 1.7141482830 0.0165622085 0.0246150000 939395449 0 402718720 0.0916473418 0.0584837496 0.3008674979 689 27.5200000000 0.4385208189 1.0157300899 1.7141482830 0.0165715889 0.0202030000 939397697 0 402718720 0.0888159871 0.0585918054 0.2992294729 690 27.5600000000 0.4326393306 1.0148850309 1.7141482830 0.0165706825 0.0549780000 939399945 0 402718720 0.0861588195 0.0594007000 0.2969785035 691 27.6000000000 0.4270661473 1.0140343523 1.7141482830 0.0165737342 0.0225000000 939402193 0 402718720 0.0831651315 0.0604185537 0.2951563001 692 27.6400000000 0.4212782085 1.0131777683 1.7141482830 0.0165894504 0.0525900000 939404441 0 402718720 0.0802615210 0.0610631481 0.2934119403 693 27.6800000000 0.4148387611 1.0123143642 1.7141482830 0.0166147934 0.0209170000 939406689 0 402718720 0.0776422694 0.0607226528 0.2914036214 694 27.7200000000 0.4082133770 1.0114439017 1.7141482830 0.0166252582 0.0194940000 939408937 0 402718720 0.0750632510 0.0606427677 0.2885766625 695 27.7600000000 0.4019424319 1.0105669212 1.7141482830 0.0166245361 0.0193200000 939411185 0 402718720 0.0726991296 0.0601328909 0.2863543630 696 27.8000000000 0.3959295452 1.0096838215 1.7141482830 0.0166222480 0.0191800000 939413433 0 402718720 0.0701230466 0.0605401359 0.2840112746 697 27.8400000000 0.3901038766 1.0087948976 1.7141482830 0.0166247255 0.1121380000 951738029 0 402718720 0.0675194561 0.0607689321 0.2820536792 698 27.8800000000 0.3827133775 1.0078979327 1.7141482830 0.0166277458 0.0240580000 955399485 0 402718720 0.0646602735 0.0632328838 0.2819676995 699 27.9200000000 0.3777989447 1.0069965035 1.7141482830 0.0166423034 0.0175000000 958593925 0 402718720 0.0617723987 0.0640056729 0.2801451385 700 27.9600000000 0.3722847998 1.0060897725 1.7141482830 0.0166564405 0.0168720000 958596173 0 402718720 0.0588401891 0.0651149452 0.2780436277 701 28.0000000000 0.3671971858 1.0051783708 1.7141482830 0.0166744790 0.0169400000 958598421 0 402718720 0.0561620854 0.0653584972 0.2762950659 702 28.0400000000 0.3619426489 1.0042620806 1.7141482830 0.0166868615 0.0481700000 958600669 0 402718720 0.0535184182 0.0654844344 0.2745024264 703 28.0800000000 0.3577740192 1.0033424674 1.7141482830 0.0166918589 0.0193630000 958602917 0 402718720 0.0511196479 0.0656530857 0.2731753886 704 28.1200000000 0.3545088172 1.0024208287 1.7141482830 0.0166992727 0.0180790000 958605165 0 402718720 0.0482236668 0.0676624104 0.2719085515 705 28.1600000000 0.3511831760 1.0014970874 1.7141482830 0.0167174772 0.0182500000 958607413 0 402718720 0.0454471558 0.0689087957 0.2706643641 706 28.2000000000 0.3475887179 1.0005708716 1.7141482830 0.0167289538 0.0166300000 958609661 0 402718720 0.0429842174 0.0686318353 0.2694447041 707 28.2400000000 0.3447643816 0.9996432811 1.7141482830 0.0167289504 0.0293340000 958611909 0 402718720 0.0403429605 0.0699584484 0.2680943310 708 28.2800000000 0.3425602913 0.9987151977 1.7141482830 0.0167247149 0.0203760000 958614157 0 402718720 0.0375845693 0.0713042989 0.2672657073 709 28.3200000000 0.3392461240 0.9977850580 1.7141482830 0.0167168557 0.1023000000 970929617 0 402718720 0.0356302150 0.0699703842 0.2665026784 710 28.3600000000 0.3382114172 0.9968560810 1.7141482830 0.0167084603 0.0238580000 974591073 0 402718720 0.0333053768 0.0705110133 0.2636109293 711 28.4000000000 0.3373216391 0.9959284658 1.7141482830 0.0167007531 0.0211480000 977785513 0 402718720 0.0306859035 0.0723623559 0.2637232244 712 28.4400000000 0.3357172310 0.9950012028 1.7141482830 0.0166950615 0.0196220000 977787761 0 402718720 0.0280571077 0.0730770752 0.2628697753 713 28.4800000000 0.3341005743 0.9940742735 1.7141482830 0.0166854061 0.0175360000 977790009 0 402718720 0.0263991151 0.0719093680 0.2626284659 714 28.5200000000 0.3346898854 0.9931507659 1.7141482830 0.0166761345 0.0499890000 977792257 0 402718720 0.0236440152 0.0739889592 0.2626364827 715 28.5600000000 0.3352850080 0.9922306740 1.7141482830 0.0166658247 0.0215820000 977794505 0 402718720 0.0206825584 0.0764771029 0.2626478076 716 28.6000000000 0.3367783725 0.9913152378 1.7141482830 0.0166616414 0.0169600000 977796753 0 402718720 0.0184903722 0.0767374560 0.2633869350 717 28.6400000000 0.3385270536 0.9904047940 1.7141482830 0.0166534275 0.0184570000 977799001 0 402718720 0.0163193960 0.0774830356 0.2643557489 718 28.6800000000 0.3411384821 0.9895005234 1.7141482830 0.0166454395 0.0184800000 977801249 0 402718720 0.0139860269 0.0788833275 0.2654430568 719 28.7200000000 0.3429070115 0.9886012278 1.7141482830 0.0166405164 0.0183950000 977803497 0 402718720 0.0115349088 0.0798678249 0.2663111687 720 28.7600000000 0.3457327783 0.9877083550 1.7141482830 0.0166344390 0.0203080000 977805745 0 402718720 0.0090926411 0.0805535689 0.2676399946 721 28.8000000000 0.3489334285 0.9868223981 1.7141482830 0.0166261174 0.0179010000 977807993 0 402718720 0.0068425327 0.0806081444 0.2692392170 722 28.8400000000 0.3522365391 0.9859434703 1.7141482830 0.0166168813 0.1035350000 990124817 0 402718720 0.0043009738 0.0813509896 0.2707738876 723 28.8800000000 0.3562446237 0.9850725175 1.7141482830 0.0166107598 0.0219530000 993786273 0 402718720 0.0020086789 0.0799909830 0.2731516659 724 28.9200000000 0.3603817821 0.9842096850 1.7141482830 0.0166019092 0.0181820000 996980713 0 402718720 -0.0006858309 0.0806155577 0.2749750614 725 28.9600000000 0.3648780584 0.9833554345 1.7141482830 0.0165966236 0.0154270000 996982961 0 402718720 -0.0034600771 0.0813010037 0.2770521343 726 29.0000000000 0.3693481386 0.9825096944 1.7141482830 0.0165950848 0.0154030000 996985209 0 402718720 -0.0060297744 0.0817431659 0.2791172266 727 29.0400000000 0.3740918636 0.9816728061 1.7141482830 0.0165941190 0.0454380000 996987457 0 402718720 -0.0090888105 0.0823137686 0.2811918855 728 29.0800000000 0.3793994784 0.9808455075 1.7141482830 0.0165934534 0.0192960000 996989705 0 402718720 -0.0119062271 0.0829132050 0.2834905386 729 29.1200000000 0.3850841224 0.9800282766 1.7141482830 0.0165893358 0.0896900000 1009302637 0 402718720 -0.0148536302 0.0838733837 0.2858300507 730 29.1600000000 0.3901140690 0.9792201749 1.7141482830 0.0165809540 0.0213210000 1012964093 0 402718720 -0.0179209597 0.0852687582 0.2879576683 731 29.2000000000 0.3956067860 0.9784217982 1.7141482830 0.0165751141 0.0164940000 1016158533 0 402718720 -0.0209341720 0.0858497992 0.2902021706 732 29.2400000000 0.4016292393 0.9776338302 1.7141482830 0.0165710627 0.0153550000 1016160781 0 402718720 -0.0241539497 0.0870553702 0.2926233113 733 29.2800000000 0.4084669054 0.9768573405 1.7141482830 0.0165660596 0.0148210000 1016163029 0 402718720 -0.0273349211 0.0879630670 0.2954506278 734 29.3200000000 0.4159675837 0.9760931855 1.7141482830 0.0165588179 0.0147000000 1016165277 0 402718720 -0.0302774701 0.0890615508 0.2985938489 735 29.3600000000 0.4230987430 0.9753408122 1.7141482830 0.0165515260 0.0146970000 1016167525 0 402718720 -0.0331520140 0.0902732238 0.3015377820 736 29.4000000000 0.4307829440 0.9746009237 1.7141482830 0.0165446235 0.0918980000 1028486401 0 402718720 -0.0359779485 0.0915938318 0.3045376539 737 29.4400000000 0.4378302991 0.9738726054 1.7141482830 0.0165371630 0.0176400000 1032147857 0 402718720 -0.0386210233 0.0926261693 0.3075758219 738 29.4800000000 0.4451226592 0.9731561421 1.7141482830 0.0165350403 0.0156780000 1035342297 0 402718720 -0.0414196625 0.0936972871 0.3105879724 739 29.5200000000 0.4524052143 0.9724514723 1.7141482830 0.0165418653 0.0142210000 1035344545 0 402718720 -0.0439927280 0.0945958123 0.3135215938 740 29.5600000000 0.4592276514 0.9717579266 1.7141482830 0.0165485815 0.0143400000 1035346793 0 402718720 -0.0464074314 0.0955256820 0.3164665699 741 29.6000000000 0.4665705562 0.9710761623 1.7141482830 0.0165573823 0.0433030000 1035349041 0 402718720 -0.0486673117 0.0969609246 0.3194140792 742 29.6400000000 0.4738994241 0.9704061128 1.7141482830 0.0165623681 0.0177890000 1035351289 0 402718720 -0.0506737046 0.0980215967 0.3224814534 743 29.6800000000 0.4798997939 0.9697459428 1.7141482830 0.0165564507 0.0784690000 1047666045 0 402718720 -0.0523136333 0.0984994620 0.3252077699 744 29.7200000000 0.4854582548 0.9690950185 1.7141482830 0.0165481575 0.0149370000 1051327501 0 402718720 -0.0538627245 0.0995744169 0.3274015188 745 29.7600000000 0.4908883572 0.9684531303 1.7141482830 0.0165407780 0.0153310000 1054521941 0 402718720 -0.0556203462 0.1004573703 0.3295300901 746 29.8000000000 0.4959638417 0.9678197667 1.7141482830 0.0165329959 0.0136020000 1054524189 0 402718720 -0.0571825430 0.1011392102 0.3316400945 747 29.8400000000 0.5011092424 0.9671949868 1.7141482830 0.0165250539 0.0134350000 1054526437 0 402718720 -0.0589095727 0.1019704714 0.3336337805 748 29.8800000000 0.5063830018 0.9665789280 1.7141482830 0.0165182088 0.0137320000 1054528685 0 402718720 -0.0605847687 0.1031884551 0.3356156051 749 29.9200000000 0.5112180710 0.9659709696 1.7141482830 0.0165106082 0.0137720000 1054530933 0 402718720 -0.0618973300 0.1040583923 0.3376442492 750 29.9600000000 0.5157126188 0.9653706252 1.7141482830 0.0165032407 0.0141440000 1054533181 0 402718720 -0.0633136109 0.1050006747 0.3394292593 751 30.0000000000 0.5197399259 0.9647772421 1.7141482830 0.0164954181 0.0139770000 1054535429 0 402718720 -0.0645224079 0.1056951880 0.3410130739 752 30.0400000000 0.5235871077 0.9641905531 1.7141482830 0.0164871323 0.0863760000 1066857097 0 402718720 -0.0656910390 0.1066172346 0.3425108790 753 30.0800000000 0.5260421634 0.9636086827 1.7141482830 0.0164770542 0.0123510000 1070518553 0 402718720 -0.0670759231 0.1084080860 0.3442887962 754 30.1200000000 0.5292512774 0.9630326119 1.7141482830 0.0164719783 0.0163390000 1073712993 0 402718720 -0.0684385896 0.1091634631 0.3455204666 755 30.1600000000 0.5324122906 0.9624622538 1.7141482830 0.0164694641 0.0152970000 1073715241 0 402718720 -0.0697729960 0.1095454842 0.3466078639 756 30.2000000000 0.5360331535 0.9618981942 1.7141482830 0.0164671078 0.0148700000 1073717489 0 402718720 -0.0711933002 0.1104183123 0.3478667140 757 30.2400000000 0.5395635366 0.9613402884 1.7141482830 0.0164608611 0.0391630000 1073719737 0 402718720 -0.0726892725 0.1113908440 0.3489011824 758 30.2800000000 0.5430229306 0.9607884185 1.7141482830 0.0164552475 0.0186950000 1073721985 0 402718720 -0.0743528679 0.1118354872 0.3501902521 759 30.3200000000 0.5468807220 0.9602430856 1.7141482830 0.0164557442 0.0151110000 1073724233 0 402718720 -0.0760724396 0.1127680242 0.3515554667 760 30.3600000000 0.5512359738 0.9597049184 1.7141482830 0.0164553886 0.0153870000 1073726481 0 402718720 -0.0782861486 0.1144668832 0.3524475992 761 30.4000000000 0.5549483299 0.9591730437 1.7141482830 0.0164527648 0.0165040000 1073728729 0 402718720 -0.0802585781 0.1155129746 0.3535976410 762 30.4400000000 0.5586348176 0.9586474030 1.7141482830 0.0164471917 0.0153820000 1073730977 0 402718720 -0.0824471861 0.1166723594 0.3544055820 763 30.4800000000 0.5624740124 0.9581281718 1.7141482830 0.0164407008 0.0159740000 1073733225 0 402718720 -0.0848011449 0.1181130707 0.3552160561 764 30.5200000000 0.5664592981 0.9576155162 1.7141482830 0.0164352799 0.0159830000 1073735473 0 402718720 -0.0872373208 0.1192490533 0.3560462296 765 30.5600000000 0.5705294013 0.9571095213 1.7141482830 0.0164289346 0.0150320000 1073737721 0 402718720 -0.0898726135 0.1205463409 0.3567723036 766 30.6000000000 0.5746015310 0.9566101636 1.7141482830 0.0164233504 0.0166370000 1073739969 0 402718720 -0.0922136679 0.1215653345 0.3577004969 767 30.6400000000 0.5787590146 0.9561175285 1.7141482830 0.0164184296 0.0162910000 1073742217 0 402718720 -0.0951252952 0.1229363456 0.3582554460 768 30.6800000000 0.5828692317 0.9556315281 1.7141482830 0.0164152010 0.0165510000 1073744465 0 402718720 -0.0976879075 0.1240133271 0.3591346443 769 30.7200000000 0.5872349143 0.9551524688 1.7141482830 0.0164114940 0.0158580000 1073746713 0 402718720 -0.1004976481 0.1254694462 0.3598497808 770 30.7600000000 0.5916885138 0.9546804377 1.7141482830 0.0164059340 0.0162080000 1073748961 0 402718720 -0.1032223105 0.1268267930 0.3606290221 771 30.8000000000 0.5958137512 0.9542149815 1.7141482830 0.0163997483 0.0162580000 1073751209 0 402718720 -0.1058779433 0.1279824525 0.3613365293 772 30.8400000000 0.5996443033 0.9537556931 1.7141482830 0.0163945420 0.0828770000 1086074169 0 402718720 -0.1086352691 0.1287897676 0.3619422913 773 30.8800000000 0.6041035652 0.9533033617 1.7141482830 0.0163899361 0.0238980000 1089735625 0 402718720 -0.1111051887 0.1296951026 0.3623261452 774 30.9200000000 0.6080955863 0.9528573569 1.7141482830 0.0163882405 0.0201950000 1092930065 0 402718720 -0.1136569008 0.1304139197 0.3631030917 775 30.9600000000 0.6117646098 0.9524172372 1.7141482830 0.0163870071 0.0199010000 1092932313 0 402718720 -0.1162744686 0.1308208704 0.3636074066 776 31.0000000000 0.6155096292 0.9519830779 1.7141482830 0.0163862718 0.0185630000 1092934561 0 402718720 -0.1190008521 0.1314146966 0.3642465472 777 31.0400000000 0.6194858551 0.9515551536 1.7141482830 0.0163872718 0.0509020000 1092936809 0 402718720 -0.1217891499 0.1324576586 0.3647306561 778 31.0800000000 0.6233116984 0.9511332468 1.7141482830 0.0163833709 0.0200040000 1092939057 0 402718720 -0.1245097816 0.1335488558 0.3652592003 779 31.1200000000 0.6271684766 0.9507173742 1.7141482830 0.0163780565 0.0188730000 1092941305 0 402718720 -0.1270555556 0.1342227012 0.3657452166 780 31.1600000000 0.6309490204 0.9503074148 1.7141482830 0.0163730678 0.0186340000 1092943553 0 402718720 -0.1295302659 0.1350940615 0.3662527800 781 31.2000000000 0.6343982220 0.9499029215 1.7141482830 0.0163679532 0.0182130000 1092945801 0 402718720 -0.1320505738 0.1358316392 0.3666593730 782 31.2400000000 0.6376200914 0.9495035829 1.7141482830 0.0163611191 0.0213790000 1092948049 0 402718720 -0.1344266087 0.1362240762 0.3670807183 783 31.2800000000 0.6410260201 0.9491096141 1.7141482830 0.0163537090 0.0208800000 1092950297 0 402718720 -0.1367141008 0.1367454380 0.3676387966 784 31.3200000000 0.6441801786 0.9487206735 1.7141482830 0.0163464047 0.0202500000 1092952545 0 402718720 -0.1388655752 0.1371567547 0.3680819869 785 31.3600000000 0.6469930410 0.9483363071 1.7141482830 0.0163383930 0.0234260000 1092954793 0 402718720 -0.1408823580 0.1373265684 0.3685290813 786 31.4000000000 0.6499498487 0.9479566805 1.7141482830 0.0163304045 0.0230170000 1092957041 0 402718720 -0.1429331452 0.1375922412 0.3689958453 787 31.4400000000 0.6529298425 0.9475818053 1.7141482830 0.0163220147 0.0231760000 1092959289 0 402718720 -0.1447874606 0.1382336617 0.3694196045 788 31.4800000000 0.6557194591 0.9472114216 1.7141482830 0.0163140572 0.0229480000 1092961537 0 402718720 -0.1464652121 0.1384963691 0.3699879050 789 31.5200000000 0.6580875516 0.9468449782 1.7141482830 0.0163059256 0.0228890000 1092963785 0 402718720 -0.1481644511 0.1384663284 0.3703713119 790 31.5600000000 0.6605641246 0.9464825973 1.7141482830 0.0162977085 0.0231420000 1092966033 0 402718720 -0.1497809589 0.1385348737 0.3709252179 791 31.6000000000 0.6628898382 0.9461240730 1.7141482830 0.0162904376 0.0230260000 1092968281 0 402718720 -0.1513519585 0.1386677027 0.3712565303 792 31.6400000000 0.6649351120 0.9457690364 1.7141482830 0.0162824440 0.0564960000 1092970529 0 402718720 -0.1526564509 0.1384974122 0.3718140721 793 31.6800000000 0.6667265296 0.9454171543 1.7141482830 0.0162739930 0.0235470000 1092972777 0 402718720 -0.1538539380 0.1382258087 0.3722079694 794 31.7200000000 0.6683102250 0.9450681531 1.7141482830 0.0162664014 0.0219040000 1092975025 0 402718720 -0.1549022347 0.1378823072 0.3726394176 795 31.7600000000 0.6698191762 0.9447219280 1.7141482830 0.0162601074 0.0222740000 1092977273 0 402718720 -0.1559429318 0.1375724375 0.3730788529 796 31.8000000000 0.6714991927 0.9443786834 1.7141482830 0.0162571119 0.0219840000 1092979521 0 402718720 -0.1568642110 0.1372252107 0.3736433983 797 31.8400000000 0.6729168296 0.9440380788 1.7141482830 0.0162529983 0.0218450000 1092981769 0 402718720 -0.1576371193 0.1368158162 0.3741408288 798 31.8800000000 0.6741766334 0.9436999065 1.7141482830 0.0162477946 0.1020080000 1105315197 0 402718720 -0.1585366279 0.1362933666 0.3745649159 799 31.9200000000 0.6757779121 0.9433645849 1.7141482830 0.0162409392 0.0262670000 1108976653 0 402718720 -0.1591731161 0.1356899291 0.3745985627 800 31.9600000000 0.6769241691 0.9430315344 1.7141482830 0.0162331925 0.0178200000 1112171093 0 402718720 -0.1598782837 0.1350249499 0.3750653863 801 32.0000000000 0.6782596707 0.9427009827 1.7141482830 0.0162269946 0.0180430000 1112173341 0 402718720 -0.1605581492 0.1344456077 0.3756838739 802 32.0400000000 0.6794386506 0.9423727255 1.7141482830 0.0162200374 0.0181880000 1112175589 0 402718720 -0.1611673832 0.1337393075 0.3763121068 803 32.0800000000 0.6810109019 0.9420472437 1.7141482830 0.0162159746 0.0374840000 1112177837 0 402718720 -0.1614011526 0.1336338520 0.3771483600 804 32.1199999990 0.6822770238 0.9417241465 1.7141482830 0.0162139479 0.0203040000 1112180085 0 402718720 -0.1617308706 0.1334021389 0.3778046072 805 32.1600000000 0.6833894849 0.9414032338 1.7141482830 0.0162116166 0.0168870000 1112182333 0 402718720 -0.1620066911 0.1328437328 0.3785261810 806 32.2000000000 0.6843877435 0.9410843561 1.7141482830 0.0162077126 0.0170910000 1112184581 0 402718720 -0.1623855233 0.1322932392 0.3790765405 807 32.2400000000 0.6849471927 0.9407669618 1.7141482830 0.0162052225 0.0170990000 1112186829 0 402718720 -0.1625502259 0.1312973201 0.3797077239 808 32.2800000000 0.6860048175 0.9404516621 1.7141482830 0.0161991495 0.0204850000 1112189077 0 402718720 -0.1628917605 0.1305012107 0.3804297149 809 32.3200000000 0.6865616441 0.9401378302 1.7141482830 0.0161927946 0.0173880000 1112191325 0 402718720 -0.1629105061 0.1292810589 0.3811868727 810 32.3600000000 0.6874231696 0.9398258368 1.7141482830 0.0161855662 0.1126980000 1124521277 0 402718720 -0.1631292552 0.1284867972 0.3818874657 811 32.4000000000 0.6877469420 0.9395150120 1.7141482830 0.0161761140 0.0239330000 1128182733 0 402718720 -0.1637678593 0.1268340349 0.3828817904 812 32.4399999990 0.6885329485 0.9392059208 1.7141482830 0.0161672457 0.0190900000 1131377173 0 402718720 -0.1639725715 0.1257749498 0.3834287524 813 32.4800000000 0.6895609498 0.9388988544 1.7141482830 0.0161592513 0.0187250000 1131379421 0 402718720 -0.1640096605 0.1249111369 0.3845454454 814 32.5200000000 0.6907528639 0.9385940068 1.7141482830 0.0161510412 0.0185480000 1131381669 0 402718720 -0.1641526073 0.1240084842 0.3853648603 815 32.5600000000 0.6918725967 0.9382912811 1.7141482830 0.0161414805 0.0433250000 1131383917 0 402718720 -0.1643818915 0.1229518279 0.3862505853 816 32.6000000000 0.6928027868 0.9379904374 1.7141482830 0.0161322758 0.0201670000 1131386165 0 402718720 -0.1644466221 0.1215788946 0.3873352110 817 32.6400000000 0.6939442158 0.9376917272 1.7141482830 0.0161224431 0.0169630000 1131388413 0 402718720 -0.1645959318 0.1203898638 0.3882896602 818 32.6800000000 0.6954177022 0.9373955487 1.7141482830 0.0161126043 0.0168190000 1131390661 0 402718720 -0.1647435129 0.1192101166 0.3894551694 819 32.7200000000 0.6973822117 0.9371024921 1.7141482830 0.0161032486 0.1389200000 1143723313 0 402718720 -0.1647434682 0.1185883060 0.3908687532 820 32.7599999990 0.6994203925 0.9368126359 1.7141482830 0.0160943605 0.0225320000 1147384769 0 402718720 -0.1649506092 0.1179489046 0.3921588957 821 32.7999999990 0.7018380761 0.9365264306 1.7141482830 0.0160891293 0.0183230000 1150579209 0 402718720 -0.1645990908 0.1172760278 0.3940676451 822 32.8400000000 0.7040891647 0.9362436602 1.7141482830 0.0160913329 0.0171440000 1150581457 0 402718720 -0.1647163630 0.1164045781 0.3956241310 823 32.8800000000 0.7066227198 0.9359646554 1.7141482830 0.0160852675 0.0172020000 1150583705 0 402718720 -0.1648162305 0.1156803071 0.3973248899 824 32.9200000000 0.7097575665 0.9356901322 1.7141482830 0.0160773816 0.0170380000 1150585953 0 402718720 -0.1648963392 0.1153949052 0.3992286325 825 32.9600000000 0.7127147317 0.9354198590 1.7141482830 0.0160747885 0.0165520000 1150588201 0 402718720 -0.1649610996 0.1145697832 0.4011606574 826 33.0000000000 0.7160069942 0.9351542260 1.7141482830 0.0160698547 0.0160980000 1150590449 0 402718720 -0.1650325805 0.1141159981 0.4031697512 827 33.0400000000 0.7188635468 0.9348926895 1.7141482830 0.0160702247 0.0157560000 1150592697 0 402718720 -0.1651551872 0.1130686626 0.4050542116 828 33.0800000000 0.7213355899 0.9346347703 1.7141482830 0.0160717149 0.0156710000 1150594945 0 402718720 -0.1652278006 0.1117808819 0.4068835974 829 33.1199999990 0.7244531512 0.9343812340 1.7141482830 0.0160685377 0.0188290000 1150597193 0 402718720 -0.1653880924 0.1106956750 0.4088850319 830 33.1600000000 0.7272679806 0.9341316999 1.7141482830 0.0160629016 0.0172700000 1150599441 0 402718720 -0.1655622274 0.1095567569 0.4108173549 831 33.2000000000 0.7301281691 0.9338862083 1.7141482830 0.0160593777 0.1318530000 1162935177 0 402718720 -0.1654420495 0.1078763753 0.4130337834 832 33.2400000000 0.7332603931 0.9336450715 1.7141482830 0.0160523818 0.0242480000 1166596633 0 402718720 -0.1657915264 0.1065448821 0.4149830937 833 33.2800000000 0.7368464470 0.9334088187 1.7141482830 0.0160445097 0.0474220000 1169791073 0 402718720 -0.1660229415 0.1053308472 0.4172114134 834 33.3200000000 0.7399725318 0.9331768807 1.7141482830 0.0160385865 0.0205160000 1169793321 0 402718720 -0.1661854684 0.1036873907 0.4192752838 835 33.3600000000 0.7434014678 0.9329496047 1.7141482830 0.0160316979 0.0191650000 1169795569 0 402718720 -0.1665752232 0.1028169468 0.4213361442 836 33.4000000000 0.7468646169 0.9327270150 1.7141482830 0.0160258446 0.0174870000 1169797817 0 402718720 -0.1667401642 0.1015545353 0.4235106409 837 33.4399999990 0.7504011393 0.9325091824 1.7141482830 0.0160217104 0.0175290000 1169800065 0 402718720 -0.1670739800 0.1006891951 0.4256313443 838 33.4800000000 0.7532021403 0.9322952122 1.7141482830 0.0160230624 0.0172110000 1169802313 0 402718720 -0.1671942919 0.0991064236 0.4275235534 839 33.5200000000 0.7566491961 0.9320858606 1.7141482830 0.0160217646 0.0173870000 1169804561 0 402718720 -0.1672938615 0.0982741788 0.4296100140 840 33.5600000000 0.7595794201 0.9318804958 1.7141482830 0.0160169355 0.0179980000 1169806809 0 402718720 -0.1679823399 0.0973969623 0.4311341345 841 33.6000000000 0.7628127933 0.9316794640 1.7141482830 0.0160083308 0.0202800000 1169809057 0 402718720 -0.1684360206 0.0967009738 0.4328700006 842 33.6400000000 0.7658146024 0.9314824749 1.7141482830 0.0159993145 0.0192110000 1169811305 0 402718720 -0.1688876003 0.0959608331 0.4345452487 843 33.6800000000 0.7686192989 0.9312892801 1.7141482830 0.0159909115 0.0189360000 1169813553 0 402718720 -0.1692036390 0.0948240533 0.4362750053 844 33.7200000000 0.7709405422 0.9310992935 1.7141482830 0.0159845204 0.0217430000 1169815801 0 402718720 -0.1694194973 0.0932041034 0.4378479123 845 33.7599999990 0.7735309601 0.9309128221 1.7141482830 0.0159786905 0.1564700000 1182154693 0 402718720 -0.1694295257 0.0921632573 0.4394768775 846 33.7999999990 0.7762377262 0.9307299910 1.7141482830 0.0159707547 0.0230270000 1185816149 0 402718720 -0.1700248122 0.0916938931 0.4406878352 847 33.8400000000 0.7779444456 0.9305496066 1.7141482830 0.0159620348 0.0195630000 1189010589 0 402718720 -0.1702766120 0.0900978521 0.4418709874 848 33.8800000000 0.7800670266 0.9303721508 1.7141482830 0.0159528841 0.0189130000 1189012837 0 402718720 -0.1705095768 0.0889027938 0.4432599843 849 33.9200000000 0.7817479372 0.9301970928 1.7141482830 0.0159439134 0.0466670000 1189015085 0 402718720 -0.1708557904 0.0871113986 0.4442680478 850 33.9600000000 0.7836055160 0.9300246321 1.7141482830 0.0159355931 0.0201170000 1189017333 0 402718720 -0.1710844487 0.0858862698 0.4454919100 851 34.0000000000 0.7858422399 0.9298552051 1.7141482830 0.0159266146 0.0176280000 1189019581 0 402718720 -0.1713140905 0.0848800465 0.4467794299 852 34.0400000000 0.7874087095 0.9296880144 1.7141482830 0.0159173559 0.0166850000 1189021829 0 402718720 -0.1711951196 0.0832010061 0.4479840994 853 34.0800000000 0.7889733315 0.9295230499 1.7141482830 0.0159081843 0.0165960000 1189024077 0 402718720 -0.1714821905 0.0818762258 0.4489528537 854 34.1199999990 0.7907632589 0.9293605677 1.7141482830 0.0158991174 0.0178010000 1189026325 0 402718720 -0.1716070920 0.0810401142 0.4501132369 855 34.1600000000 0.7923604250 0.9292003336 1.7141482830 0.0158914280 0.0198400000 1189028573 0 402718720 -0.1714949906 0.0799638331 0.4511964619 856 34.2000000000 0.7937856317 0.9290421389 1.7141482830 0.0158831906 0.0183160000 1189030821 0 402718720 -0.1716017872 0.0790134445 0.4521947205 857 34.2400000000 0.7956819534 0.9288865261 1.7141482830 0.0158742200 0.0182560000 1189033069 0 402718720 -0.1720571220 0.0786682367 0.4530256391 858 34.2800000000 0.7972057462 0.9287330520 1.7141482830 0.0158653163 0.0208610000 1189035317 0 402718720 -0.1723645627 0.0779585913 0.4537980556 859 34.3200000000 0.7975674272 0.9285803563 1.7141482830 0.0158569600 0.0213310000 1189037565 0 402718720 -0.1722363383 0.0758884102 0.4545116723 860 34.3600000000 0.7981966138 0.9284287473 1.7141482830 0.0158478864 0.0197830000 1189039813 0 402718720 -0.1724608541 0.0743056610 0.4548950791 861 34.4000000000 0.7994145751 0.9282789050 1.7141482830 0.0158387459 0.0220270000 1189042061 0 402718720 -0.1725934297 0.0732252002 0.4556527436 862 34.4400000000 0.8002349734 0.9281303622 1.7141482830 0.0158295885 0.0224380000 1189044309 0 402718720 -0.1725697070 0.0719839856 0.4562515020 863 34.4800000000 0.8003849387 0.9279823373 1.7141482830 0.0158206025 0.1389180000 1201385909 0 402718720 -0.1725418717 0.0699012876 0.4566205144 864 34.5200000000 0.8009460568 0.9278353046 1.7141482830 0.0158114562 0.0248500000 1205047365 0 402718720 -0.1726376414 0.0689069778 0.4572207630 865 34.5600000000 0.8021228909 0.9276899723 1.7141482830 0.0158032809 0.0410490000 1208241805 0 402718720 -0.1733065099 0.0686289147 0.4575709403 866 34.6000000000 0.8030017614 0.9275459906 1.7141482830 0.0157966660 0.0191070000 1208244053 0 402718720 -0.1735874563 0.0681039691 0.4580328465 867 34.6400000000 0.8036241531 0.9274030588 1.7141482830 0.0157881645 0.0171320000 1208246301 0 402718720 -0.1735026985 0.0671875924 0.4586132467 868 34.6800000000 0.8039399385 0.9272608202 1.7141482830 0.0157793960 0.0170530000 1208248549 0 402718720 -0.1736889184 0.0659636408 0.4588394463 869 34.7200000000 0.8041523099 0.9271191533 1.7141482830 0.0157704251 0.0173760000 1208250797 0 402718720 -0.1734620482 0.0649006292 0.4591204822 870 34.7600000000 0.8045208454 0.9269782357 1.7141482830 0.0157614453 0.0248550000 1208253045 0 402718720 -0.1737765372 0.0639966279 0.4592828751 871 34.8000000000 0.8051324487 0.9268383439 1.7141482830 0.0157526031 0.0160960000 1208255293 0 402718720 -0.1740736067 0.0634043813 0.4594901204 872 34.8400000000 0.8056071401 0.9266993173 1.7141482830 0.0157436231 0.0153920000 1208257541 0 402718720 -0.1744303107 0.0624374747 0.4596800506 873 34.8800000000 0.8063539267 0.9265614646 1.7141482830 0.0157346250 0.0179360000 1208259789 0 402718720 -0.1745536029 0.0617213994 0.4601933956 874 34.9200000000 0.8071714640 0.9264248628 1.7141482830 0.0157256773 0.0166810000 1208262037 0 402718720 -0.1747266203 0.0613006689 0.4605905414 875 34.9600000000 0.8085603118 0.9262901604 1.7141482830 0.0157168012 0.0160190000 1208264285 0 402718720 -0.1751951426 0.0613910928 0.4610515833 876 35.0000000000 0.8094825745 0.9261568184 1.7141482830 0.0157081654 0.0184270000 1208266533 0 402718720 -0.1755138785 0.0610706508 0.4614878595 877 35.0400000000 0.8105842471 0.9260250367 1.7141482830 0.0156992486 0.0168940000 1208268781 0 402718720 -0.1758076549 0.0610405691 0.4619118571 878 35.0800000000 0.8116039634 0.9258947166 1.7141482830 0.0156904733 0.0154540000 1208271029 0 402718720 -0.1761233807 0.0610895492 0.4622989297 879 35.1200000000 0.8124384880 0.9257656424 1.7141482830 0.0156815923 0.0155690000 1208273277 0 402718720 -0.1763417274 0.0607355535 0.4626940787 880 35.1600000000 0.8135167956 0.9256380869 1.7141482830 0.0156730704 0.0160120000 1208275525 0 402718720 -0.1765476912 0.0610314496 0.4631189704 881 35.2000000000 0.8145951033 0.9255120449 1.7141482830 0.0156644563 0.0164090000 1208277773 0 402718720 -0.1768905073 0.0609771684 0.4635343850 882 35.2400000000 0.8145213127 0.9253862051 1.7141482830 0.0156557230 0.0169220000 1208280021 0 402718720 -0.1766929179 0.0596600398 0.4637442827 ================================================ FILE: icra2018_results/1080/memory_orbslam2_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:14:38 Properties: ================= frame-limit: 0 log-file: out_paper//memory_orbslam2_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.1147620000 348371200 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0015366985 0.0007683493 0.0015366985 0.0014142410 0.0354160000 356516126 0 402718720 0.0006963463 0.0000178619 -0.0003427534 3 0.0800000000 0.0016735863 0.0010700950 0.0016735863 0.0011899923 0.0326400000 356446883 0 402718720 -0.0042211143 0.0007406494 -0.0004876328 4 0.1200000000 0.0024419085 0.0014130483 0.0024419085 0.0014277847 0.0314370000 356416730 0 402718720 -0.0008867451 0.0010379477 -0.0008999060 5 0.1600000000 0.0039741946 0.0019252776 0.0039741946 0.0016265168 0.0306160000 356419874 0 402718720 -0.0042848135 -0.0013940356 0.0008131070 6 0.2000000000 0.0014003824 0.0018377951 0.0039741946 0.0019230322 0.0316000000 356427202 0 402718720 -0.0041308869 0.0017212915 -0.0003472701 7 0.2400000000 0.0010873142 0.0017305835 0.0039741946 0.0017641345 0.0313640000 356430022 0 402718720 -0.0050418065 0.0021759116 -0.0001017336 8 0.2800000000 0.0027016464 0.0018519664 0.0039741946 0.0017276818 0.0311400000 356432746 0 402718720 -0.0046347482 0.0026124960 -0.0001455753 9 0.3200000000 0.0015491414 0.0018183191 0.0039741946 0.0018703967 0.0316000000 356435798 0 402718720 -0.0078405319 0.0016512125 -0.0006178146 10 0.3600000000 0.0028334318 0.0019198304 0.0039741946 0.0018593079 0.0312950000 356439614 0 402718720 -0.0068665133 0.0035439760 -0.0001547314 11 0.4000000000 0.0011676110 0.0018514468 0.0039741946 0.0020431603 0.0315180000 356443014 0 402718720 -0.0089891246 0.0010386308 0.0009926157 12 0.4400000000 0.0008785391 0.0017703712 0.0039741946 0.0022557723 0.0310080000 356445430 0 402718720 -0.0096634757 0.0001935088 0.0000033209 13 0.4800000000 0.0022112497 0.0018042849 0.0039741946 0.0023560131 0.0311450000 356447906 0 402718720 -0.0106707150 -0.0000895370 0.0001798930 14 0.5200000000 0.0030858414 0.0018958247 0.0039741946 0.0022856067 0.0310860000 356451854 0 402718720 -0.0098020658 0.0009585606 -0.0008529733 15 0.5600000000 0.0014060595 0.0018631737 0.0039741946 0.0022711367 0.0315540000 356454530 0 402718720 -0.0156703815 0.0014727294 0.0008822269 16 0.6000000000 0.0016274810 0.0018484429 0.0039741946 0.0022656387 0.0310680000 356457014 0 402718720 -0.0132763758 0.0015437255 -0.0000447271 17 0.6400000000 0.0036871072 0.0019565996 0.0039741946 0.0022674515 0.0309600000 356459902 0 402718720 -0.0145988856 -0.0030452055 -0.0022173140 18 0.6800000000 0.0015628892 0.0019347268 0.0039741946 0.0022558057 0.0315100000 356465094 0 402718720 -0.0173929222 -0.0003607706 -0.0016158025 19 0.7200000000 0.0052115913 0.0021071933 0.0052115913 0.0022556278 0.0317960000 356468642 0 402718720 -0.0179517865 -0.0046272194 -0.0016029361 20 0.7600000000 0.0028862215 0.0021461447 0.0052115913 0.0023998337 0.0313230000 356472718 0 402718720 -0.0215866417 -0.0035259330 -0.0019827508 21 0.8000000000 0.0063275355 0.0023452586 0.0063275355 0.0023765011 0.0312580000 356477586 0 402718720 -0.0200570486 -0.0022941725 -0.0018668360 22 0.8400000000 0.0042913128 0.0024337156 0.0063275355 0.0023413879 0.0318140000 356482610 0 402718720 -0.0283920206 -0.0035139772 -0.0026809138 23 0.8800000000 0.0066685574 0.0026178392 0.0066685574 0.0023221498 0.0318370000 356485550 0 402718720 -0.0246901587 -0.0034089976 -0.0044475487 24 0.9200000000 0.0057054879 0.0027464912 0.0066685574 0.0023081019 0.0318870000 356491030 0 402718720 -0.0348994806 -0.0033104646 -0.0056543429 25 0.9600000000 0.0055181221 0.0028573564 0.0066685574 0.0022774061 0.0315750000 356494566 0 402718720 -0.0358598940 -0.0017885674 -0.0057806456 26 1.0000000000 0.0069222231 0.0030136975 0.0069222231 0.0022437816 0.0312170000 356496754 0 402718720 -0.0404531658 -0.0023146968 -0.0057929303 27 1.0400000000 0.0060039097 0.0031244461 0.0069222231 0.0022860279 0.0311380000 356501174 0 402718720 -0.0465699174 -0.0008327917 -0.0066495575 28 1.0800000000 0.0051015019 0.0031950552 0.0069222231 0.0025453202 0.0312540000 356506158 0 402718720 -0.0554234795 -0.0041456232 -0.0077031013 29 1.1200000000 0.0036743453 0.0032115824 0.0069222231 0.0026425882 0.0309950000 356510766 0 402718720 -0.0611919314 -0.0012619670 -0.0112496382 30 1.1600000000 0.0049112891 0.0032682393 0.0069222231 0.0027329887 0.0311790000 356515358 0 402718720 -0.0683106035 -0.0017751934 -0.0072918683 31 1.2000000000 0.0051721591 0.0033296561 0.0069222231 0.0027166468 0.0308590000 356519742 0 402718720 -0.0744710416 -0.0005747064 -0.0098682940 32 1.2400000000 0.0060897288 0.0034159084 0.0069222231 0.0027397648 0.0307950000 356523746 0 402718720 -0.0804964304 -0.0008306702 -0.0123685375 33 1.2800000000 0.0051692920 0.0034690412 0.0069222231 0.0027950972 0.0306580000 356528586 0 402718720 -0.0883311629 -0.0033667530 -0.0119779259 34 1.3200000000 0.0024701313 0.0034396615 0.0069222231 0.0028106863 0.0309870000 356537838 0 402718720 -0.1188199371 -0.0023373729 -0.0118304668 35 1.3600000000 0.0053815413 0.0034951438 0.0069222231 0.0031660482 0.0307660000 356541150 0 402718720 -0.1183462515 -0.0009737088 -0.0151321115 36 1.4000000000 0.0084955515 0.0036340440 0.0084955515 0.0037727239 0.0302070000 356543422 0 402718720 -0.1215044707 -0.0017551981 -0.0180687532 37 1.4400000000 0.0043734806 0.0036540288 0.0084955515 0.0037730877 0.0306230000 356547362 0 402718720 -0.1356615871 -0.0009988463 -0.0153372576 38 1.4800000000 0.0034748858 0.0036493145 0.0084955515 0.0037293748 0.0305540000 356551834 0 402718720 -0.1485827565 -0.0012805774 -0.0154172396 39 1.5200000000 0.0048651542 0.0036804899 0.0084955515 0.0037001453 0.0299820000 356555158 0 402718720 -0.1502835006 -0.0006866154 -0.0177778378 40 1.5600000000 0.0051729139 0.0037178005 0.0084955515 0.0037185529 0.0300350000 356558698 0 402718720 -0.1610693038 -0.0062329560 -0.0188449603 41 1.6000000000 0.0021421215 0.0036793693 0.0084955515 0.0038132693 0.0298580000 356562722 0 402718720 -0.1732441038 -0.0043079196 -0.0152004035 42 1.6400000000 0.0006390783 0.0036069814 0.0084955515 0.0037789036 0.0301470000 356568206 0 402718720 -0.1881743670 -0.0029992564 -0.0126480740 43 1.6800000000 0.0037401016 0.0036100772 0.0084955515 0.0037519153 0.0306480000 356570566 0 402718720 -0.1921056360 -0.0012040427 -0.0101364125 44 1.7200000000 0.0040937671 0.0036210702 0.0084955515 0.0037698529 0.0300430000 356574646 0 402718720 -0.1980177462 -0.0019157571 -0.0110754687 45 1.7600000000 0.0021833212 0.0035891202 0.0084955515 0.0038670744 0.0297060000 356577538 0 402718720 -0.2117488980 0.0000622829 -0.0072801579 46 1.8000000000 0.0027624040 0.0035711481 0.0084955515 0.0038641893 0.0304990000 356581406 0 402718720 -0.2168426514 0.0019075929 -0.0079961158 47 1.8400000000 0.0006985636 0.0035100293 0.0084955515 0.0039453864 0.0304490000 356583906 0 402718720 -0.2193665504 -0.0025282106 -0.0089463759 48 1.8800000000 0.0038367731 0.0035168364 0.0084955515 0.0039735882 0.0307470000 356586154 0 402718720 -0.2216939330 0.0003374711 -0.0076323636 49 1.9200000000 0.0014716848 0.0034750986 0.0084955515 0.0039411095 0.0309190000 356589034 0 402718720 -0.2295423597 -0.0015997561 -0.0065240506 50 1.9600000000 0.0012295777 0.0034301882 0.0084955515 0.0039093497 0.0306190000 356591986 0 402718720 -0.2458912283 -0.0012703732 -0.0008017588 51 2.0000000000 0.0042459159 0.0034461829 0.0084955515 0.0039111294 0.0300480000 356594038 0 402718720 -0.2402105927 0.0001845707 -0.0039967410 52 2.0400000000 0.0020325643 0.0034189979 0.0084955515 0.0039042217 0.0300800000 356597366 0 402718720 -0.2493748814 -0.0009195153 -0.0049255993 53 2.0800000000 0.0019934399 0.0033921006 0.0084955515 0.0039336280 0.0304720000 356599666 0 402718720 -0.2513683140 -0.0046455353 -0.0076894462 54 2.1200000000 0.0017977402 0.0033625754 0.0084955515 0.0039768574 0.0308710000 356602474 0 402718720 -0.2636341751 -0.0065296772 -0.0013560448 55 2.1600000000 0.0031251148 0.0033582579 0.0084955515 0.0040931827 0.0308830000 356604958 0 402718720 -0.2658417821 -0.0038843530 -0.0002574511 56 2.2000000000 0.0037599646 0.0033654313 0.0084955515 0.0041210097 0.0317460000 356608666 0 402718720 -0.2879450917 -0.0032014220 0.0078390613 57 2.2400000000 0.0034323053 0.0033666045 0.0084955515 0.0040981661 0.0305060000 356610074 0 402718720 -0.2906554639 -0.0046402756 0.0086647142 58 2.2800000000 0.0028763323 0.0033581515 0.0084955515 0.0041095225 0.0302280000 356611946 0 402718720 -0.3015157878 -0.0070214076 0.0108019002 59 2.3200000000 0.0040021837 0.0033690673 0.0084955515 0.0042301994 0.0304960000 356614702 0 402718720 -0.3163929284 -0.0062331343 0.0176663976 60 2.3600000000 0.0015174515 0.0033382071 0.0084955515 0.0043935692 0.0306290000 356616922 0 402718720 -0.3151232600 -0.0067201960 0.0128477588 61 2.4000000000 0.0024173113 0.0033231104 0.0084955515 0.0044820654 0.0308110000 356620814 0 402718720 -0.3227944672 -0.0067204200 0.0140594598 62 2.4400000000 0.0070320549 0.0033829321 0.0084955515 0.0046790310 0.0309760000 356625118 0 402718720 -0.3429005146 -0.0030578985 0.0256167036 63 2.4800000000 0.0032967173 0.0033815636 0.0084955515 0.0048443348 0.0298730000 356629382 0 402718720 -0.3562960625 -0.0098323328 0.0276399348 64 2.5200000000 0.0035684297 0.0033844834 0.0084955515 0.0051742759 0.0298800000 356634402 0 402718720 -0.3673578501 -0.0060384562 0.0316704437 65 2.5600000000 0.0084913699 0.0034630509 0.0084955515 0.0053284232 0.0297340000 356637418 0 402718720 -0.3869245052 -0.0020464021 0.0356581956 66 2.6000000000 0.0042739622 0.0034753374 0.0084955515 0.0055223569 0.0297270000 356654814 0 402718720 -0.3964269757 -0.0081052221 0.0365630388 67 2.6400000000 0.0017520259 0.0034496163 0.0084955515 0.0055664105 0.0294950000 356658966 0 402718720 -0.4037500322 -0.0040249578 0.0384061672 68 2.6800000000 0.0025226397 0.0034359843 0.0084955515 0.0055540705 0.0290480000 356662030 0 402718720 -0.4143118560 -0.0035463143 0.0383826233 69 2.7200000000 0.0021366219 0.0034171530 0.0084955515 0.0055190280 0.0288830000 356666686 0 402718720 -0.4237728715 -0.0024020730 0.0410566628 70 2.7600000000 0.0085287718 0.0034901761 0.0085287718 0.0055296827 0.0290230000 356671506 0 402718720 -0.4370636046 0.0018864945 0.0460007973 71 2.8000000000 0.0036221743 0.0034920352 0.0085287718 0.0055735422 0.0294530000 356674286 0 402718720 -0.4415324926 0.0009055622 0.0383058265 72 2.8400000000 0.0100167058 0.0035826557 0.0100167058 0.0062933864 0.0290790000 356677934 0 402718720 -0.4636234939 0.0027441371 0.0465906039 73 2.8800000000 0.0069056051 0.0036281755 0.0100167058 0.0063656488 0.0314020000 357092051 0 402718720 -0.4719093442 0.0047006076 0.0453056395 74 2.9200000000 0.0071509476 0.0036757806 0.0100167058 0.0064474331 0.0684340000 357612595 0 402718720 -0.4742102027 0.0047271410 0.0420972072 75 2.9600000000 0.0063638547 0.0037116215 0.0100167058 0.0064977904 0.0895880000 358803354 0 402718720 -0.4751891792 0.0089836232 0.0385790467 76 3.0000000000 0.0049289931 0.0037276396 0.0100167058 0.0065209683 0.0391140000 359648235 0 402718720 -0.4716442227 0.0127907731 0.0304471031 77 3.0400000000 0.0173600838 0.0039046843 0.0173600838 0.0067608065 0.0440590000 359337917 0 402718720 -0.4785395861 0.0002948453 0.0160773098 78 3.0800000000 0.0192015786 0.0041007984 0.0192015786 0.0067280701 0.0296460000 357609278 0 402718720 -0.4792383313 0.0009836090 0.0094396472 79 3.1200000000 0.0158395190 0.0042493898 0.0192015786 0.0066929979 0.0294060000 357614606 0 402718720 -0.4852602780 0.0082434099 0.0073344111 80 3.1600000000 0.0183073338 0.0044251141 0.0192015786 0.0066737479 0.0291790000 357619418 0 402718720 -0.4884136915 0.0073056240 0.0029100478 81 3.2000000000 0.0173776541 0.0045850220 0.0192015786 0.0066362819 0.0289830000 357625458 0 402718720 -0.5001766086 0.0075569879 0.0057492331 82 3.2400000000 0.0182328392 0.0047514587 0.0192015786 0.0066672432 0.0301550000 357630730 0 402718720 -0.5067938566 0.0060306089 0.0029463321 83 3.2800000000 0.0196782202 0.0049312992 0.0196782202 0.0067131682 0.0302960000 357635062 0 402718720 -0.5155819654 0.0063212058 0.0011098236 84 3.3200000000 0.0185472351 0.0050933937 0.0196782202 0.0066934135 0.0286190000 357640202 0 402718720 -0.5234807730 0.0067289919 -0.0033753514 85 3.3600000000 0.0187038835 0.0052535171 0.0196782202 0.0066784351 0.0280030000 357645226 0 402718720 -0.5415597558 0.0076936586 0.0009433031 86 3.4000000000 0.0193571970 0.0054175134 0.0196782202 0.0067035007 0.0279140000 357648842 0 402718720 -0.5591921806 0.0090582911 0.0072563291 87 3.4400000000 0.0169081334 0.0055495895 0.0196782202 0.0068086575 0.0282980000 357654350 0 402718720 -0.5676660538 0.0108397398 0.0058461130 88 3.4800000000 0.0216266848 0.0057322838 0.0216266848 0.0070000201 0.0299700000 358003662 0 402718720 -0.5815824866 0.0050812885 0.0063972473 89 3.5200000000 0.0195961688 0.0058880578 0.0216266848 0.0071089480 0.0832610000 358189730 0 402718720 -0.5919928551 0.0090196496 0.0070903748 90 3.5600000000 0.0213787742 0.0060601768 0.0216266848 0.0072011529 0.0632130000 360513438 0 402718720 -0.5988019705 0.0043055238 0.0048628896 91 3.6000000000 0.0186961219 0.0061990334 0.0216266848 0.0072310021 0.0528100000 360477563 0 402718720 -0.6153855324 0.0084988251 0.0113943666 92 3.6400000000 0.0171797555 0.0063183890 0.0216266848 0.0072345116 0.0293600000 358164758 0 402718720 -0.6298825145 0.0124706235 0.0164558887 93 3.6800000000 0.0174261872 0.0064378277 0.0216266848 0.0072176343 0.0285360000 358167214 0 402718720 -0.6342298985 0.0111270417 0.0110404938 94 3.7200000000 0.0192280430 0.0065738938 0.0216266848 0.0071818036 0.0289510000 358171722 0 402718720 -0.6435572505 0.0081754830 0.0118177533 95 3.7600000000 0.0200430993 0.0067156750 0.0216266848 0.0071985265 0.0287460000 358175202 0 402718720 -0.6547697783 0.0063439528 0.0159255564 96 3.8000000000 0.0212951954 0.0068675450 0.0216266848 0.0071671838 0.0286100000 358177982 0 402718720 -0.6686374545 0.0075987903 0.0196220577 97 3.8400000000 0.0208081361 0.0070112624 0.0216266848 0.0071322002 0.0290320000 358181226 0 402718720 -0.6734565496 0.0045596845 0.0217345953 98 3.8800000000 0.0241274983 0.0071859179 0.0241274983 0.0071025263 0.0287780000 358185882 0 402718720 -0.6918897033 0.0039835111 0.0266130418 99 3.9200000000 0.0195736308 0.0073110463 0.0241274983 0.0070827747 0.0279380000 358189090 0 402718720 -0.6939336658 0.0087541277 0.0291404724 100 3.9600000000 0.0208830778 0.0074467666 0.0241274983 0.0070485800 0.0277890000 358191550 0 402718720 -0.7031595111 0.0071794847 0.0332666785 101 4.0000000000 0.0213032272 0.0075839593 0.0241274983 0.0070233089 0.0279140000 358194066 0 402718720 -0.7103458047 0.0030406471 0.0354012698 102 4.0400000000 0.0189887602 0.0076957710 0.0241274983 0.0069994716 0.0277180000 358196782 0 402718720 -0.7118716836 0.0022819452 0.0381659120 103 4.0800000000 0.0214799941 0.0078295985 0.0241274983 0.0069687827 0.0272300000 358202058 0 402718720 -0.7261264324 0.0024835132 0.0463205129 104 4.1200000000 0.0169278365 0.0079170815 0.0241274983 0.0069466986 0.0277440000 358204962 0 402718720 -0.7341951728 0.0029580481 0.0564431697 105 4.1600000000 0.0192524306 0.0080250372 0.0241274983 0.0069596724 0.0294120000 358672514 0 402718720 -0.7375979424 -0.0009159325 0.0582969934 106 4.2000000000 0.0212262310 0.0081495768 0.0241274983 0.0069412201 0.0897840000 358825470 0 402718720 -0.7496593595 0.0060544154 0.0681087673 107 4.2400000000 0.0212396812 0.0082719142 0.0241274983 0.0069896848 0.0792670000 361661178 0 402718720 -0.7440149188 -0.0063283667 0.0578391552 108 4.2800000000 0.0204954334 0.0083850949 0.0241274983 0.0069627933 0.0393660000 361662858 0 402718720 -0.7549618483 -0.0057213726 0.0690331608 109 4.3200000000 0.0145115666 0.0084413011 0.0241274983 0.0069790348 0.0564180000 361513697 0 402718720 -0.7549554706 0.0035852324 0.0734680295 110 4.3600000000 0.0138674350 0.0084906296 0.0241274983 0.0069861275 0.0303400000 358763330 0 402718720 -0.7612116933 0.0003704848 0.0807223618 111 4.4000000000 0.0127342725 0.0085288606 0.0241274983 0.0069879346 0.0297950000 358766794 0 402718720 -0.7664185166 -0.0002027722 0.0862014294 112 4.4400000000 0.0157521013 0.0085933538 0.0241274983 0.0069769714 0.0296760000 358771606 0 402718720 -0.7782428265 0.0018694280 0.0960788429 113 4.4800000000 0.0148263620 0.0086485132 0.0241274983 0.0069900184 0.0295670000 358776246 0 402718720 -0.7809047699 -0.0003369693 0.1010759622 114 4.5200000000 0.0160748065 0.0087136561 0.0241274983 0.0070124145 0.0293200000 358779106 0 402718720 -0.7936820388 0.0024973406 0.1147672832 115 4.5600000000 0.0157134589 0.0087745240 0.0241274983 0.0070665434 0.0288830000 358783634 0 402718720 -0.7914743423 -0.0031843428 0.1110779643 116 4.6000000000 0.0164368618 0.0088405786 0.0241274983 0.0070982975 0.0283820000 358786310 0 402718720 -0.8042875528 0.0023642164 0.1240427345 117 4.6400000000 0.0137499832 0.0088825393 0.0241274983 0.0070982513 0.0284960000 358789294 0 402718720 -0.8101730347 0.0091738068 0.1352246106 118 4.6800000000 0.0160563122 0.0089433340 0.0241274983 0.0070705527 0.0279560000 358794822 0 402718720 -0.8180562854 0.0059518218 0.1424606740 119 4.7200000000 0.0128084384 0.0089758139 0.0241274983 0.0070429923 0.0280900000 358798078 0 402718720 -0.8204873800 0.0038489066 0.1473697126 120 4.7600000000 0.0119469743 0.0090005736 0.0241274983 0.0070134042 0.0280280000 358801382 0 402718720 -0.8264291883 0.0059251245 0.1544492245 121 4.8000000000 0.0174662117 0.0090705375 0.0241274983 0.0070071188 0.0286230000 358805694 0 402718720 -0.8407865167 0.0024536252 0.1732298285 122 4.8400000000 0.0168834347 0.0091345776 0.0241274983 0.0070093017 0.0310070000 359319823 0 402718720 -0.8429939151 0.0088411383 0.1778413206 123 4.8800000000 0.0162653308 0.0091925512 0.0241274983 0.0069882627 0.0959880000 359370258 0 402718720 -0.8477052450 0.0111176204 0.1841040999 124 4.9200000000 0.0148839448 0.0092384496 0.0241274983 0.0069659147 0.0878040000 361143550 0 402718720 -0.8559078574 0.0129464250 0.1987381727 125 4.9600000000 0.0164496601 0.0092961393 0.0241274983 0.0069476599 0.0627950000 362837703 0 402718720 -0.8618323803 0.0130062029 0.2048981190 126 5.0000000000 0.0153838797 0.0093444547 0.0241274983 0.0069277412 0.0664780000 362765255 0 402718720 -0.8656275868 0.0145819392 0.2121901214 127 5.0400000000 0.0163966175 0.0093999835 0.0241274983 0.0069024792 0.0336830000 359382554 0 402718720 -0.8760432005 0.0143550206 0.2284766436 128 5.0800000000 0.0163957644 0.0094546380 0.0241274983 0.0068815708 0.0368230000 359387074 0 402718720 -0.8815398216 0.0155316815 0.2358320057 129 5.1200000000 0.0140225990 0.0094900486 0.0241274983 0.0068599462 0.0352630000 359388222 0 402718720 -0.8834602237 0.0185309835 0.2402974814 130 5.1600000000 0.0166488066 0.0095451160 0.0241274983 0.0068417331 0.0359390000 359418354 0 402718720 -0.8943598270 0.0189537127 0.2616100609 131 5.2000000000 0.0180995408 0.0096104169 0.0241274983 0.0068724887 0.0355390000 359423442 0 402718720 -0.8995059133 0.0200494900 0.2653860748 132 5.2400000000 0.0178233366 0.0096726360 0.0241274983 0.0068755414 0.0348250000 359425082 0 402718720 -0.8994718194 0.0198151357 0.2636719346 133 5.2800000000 0.0156569630 0.0097176309 0.0241274983 0.0068756500 0.0349190000 359429918 0 402718720 -0.9074507952 0.0215175580 0.2818749249 134 5.3200000000 0.0182025414 0.0097809512 0.0241274983 0.0069098829 0.0292590000 359434750 0 402718720 -0.9191412330 0.0197787341 0.2986967862 135 5.3600000000 0.0185652450 0.0098460200 0.0241274983 0.0069118805 0.0306670000 359834643 0 402718720 -0.9226897359 0.0225339197 0.3027239740 136 5.4000000000 0.0174545441 0.0099019650 0.0241274983 0.0069462296 0.0930650000 359996147 0 402718720 -0.9284739494 0.0236318260 0.3144051731 137 5.4400000000 0.0166368801 0.0099511250 0.0241274983 0.0069993501 0.0914400000 360006467 0 402718720 -0.9331378937 0.0229929090 0.3229712248 138 5.4800000000 0.0179406498 0.0100090201 0.0241274983 0.0070308177 0.0721510000 363809893 0 402718720 -0.9399964213 0.0214009825 0.3286149204 139 5.5200000000 0.0192928724 0.0100758104 0.0241274983 0.0070695694 0.0366070000 364027935 0 402718720 -0.9468067288 0.0196036138 0.3362443447 140 5.5600000000 0.0159419216 0.0101177112 0.0241274983 0.0071221325 0.0727070000 363957663 0 402718720 -0.9532359242 0.0215055179 0.3478005826 141 5.6000000000 0.0182703398 0.0101755313 0.0241274983 0.0071334318 0.0311200000 360012847 0 402718720 -0.9600194693 0.0265129954 0.3540448546 142 5.6400000000 0.0173918307 0.0102263503 0.0241274983 0.0071719660 0.0320350000 360019463 0 402718720 -0.9690515995 0.0236569420 0.3689076602 143 5.6800000000 0.0178944357 0.0102799733 0.0241274983 0.0072278625 0.0312630000 360021835 0 402718720 -0.9736656547 0.0300015695 0.3785677552 144 5.7200000000 0.0165798794 0.0103237226 0.0241274983 0.0072875158 0.0305080000 360026439 0 402718720 -0.9800353646 0.0271065533 0.3861712217 145 5.7600000000 0.0174380261 0.0103727868 0.0241274983 0.0072797456 0.0303650000 360029567 0 402718720 -0.9862539768 0.0270974152 0.3932135403 146 5.8000000000 0.0168131087 0.0104168986 0.0241274983 0.0072688111 0.0301890000 360033631 0 402718720 -0.9913714528 0.0246629044 0.4041444957 147 5.8400000000 0.0204753149 0.0104853232 0.0241274983 0.0072462558 0.0299280000 360034327 0 402718720 -1.0045363903 0.0273309723 0.4263726175 148 5.8800000000 0.0203441083 0.0105519366 0.0241274983 0.0072270268 0.0300120000 360040355 0 402718720 -1.0059289932 0.0255939104 0.4301963449 149 5.9200000000 0.0190076008 0.0106086860 0.0241274983 0.0072058501 0.0293470000 360041747 0 402718720 -1.0094861984 0.0261771306 0.4394643307 150 5.9600000000 0.0193561465 0.0106670024 0.0241274983 0.0071880524 0.0287580000 360045411 0 402718720 -1.0125697851 0.0286745839 0.4491755664 151 6.0000000000 0.0202638712 0.0107305578 0.0241274983 0.0071658349 0.0285960000 360046959 0 402718720 -1.0165013075 0.0302756652 0.4589013457 152 6.0400000000 0.0207739919 0.0107966331 0.0241274983 0.0071508044 0.0292440000 360050275 0 402718720 -1.0200809240 0.0310424380 0.4705521464 153 6.0800000000 0.0193285495 0.0108523972 0.0241274983 0.0071439141 0.0317500000 360557475 0 402718720 -1.0227042437 0.0274098031 0.4793266654 154 6.1200000000 0.0185373370 0.0109022994 0.0241274983 0.0071635460 0.0931210000 360585623 0 402718720 -1.0272705555 0.0259647705 0.4893764853 155 6.1600000000 0.0171775334 0.0109427848 0.0241274983 0.0072337336 0.0863880000 360745955 0 402718720 -1.0279490948 0.0217747390 0.4960103035 156 6.2000000000 0.0194552932 0.0109973522 0.0241274983 0.0073279176 0.0787050000 365105311 0 402718720 -1.0330954790 0.0284791999 0.5147382021 157 6.2400000000 0.0176679250 0.0110398399 0.0241274983 0.0074185207 0.0534420000 365071551 0 402718720 -1.0351984501 0.0276361629 0.5211336017 158 6.2800000000 0.0176803283 0.0110818683 0.0241274983 0.0075065984 0.0806440000 364983727 0 402718720 -1.0351837873 0.0344372280 0.5386716127 159 6.3200000000 0.0147632556 0.0111050217 0.0241274983 0.0075427628 0.0292590000 360598687 0 402718720 -1.0351761580 0.0292839110 0.5447546244 160 6.3600000000 0.0200838894 0.0111611396 0.0241274983 0.0075600521 0.0287110000 360602079 0 402718720 -1.0384871960 0.0363183878 0.5637362003 161 6.4000000000 0.0181258097 0.0112043984 0.0241274983 0.0075472212 0.0302840000 361004391 0 402718720 -1.0381700993 0.0327168331 0.5745523572 162 6.4400000000 0.0164517593 0.0112367895 0.0241274983 0.0075258918 0.0898390000 361167079 0 402718720 -1.0375146866 0.0289427936 0.5847531557 163 6.4800000000 0.0168728456 0.0112713666 0.0241274983 0.0075051040 0.0871200000 361171839 0 402718720 -1.0382485390 0.0332546458 0.5961444974 164 6.5200000000 0.0154234562 0.0112966842 0.0241274983 0.0074855196 0.0830810000 363486999 0 402718720 -1.0379825830 0.0319974497 0.6077601314 165 6.5600000000 0.0157510284 0.0113236802 0.0241274983 0.0074745947 0.0565700000 366243230 0 402718720 -1.0393595695 0.0332274325 0.6257951260 166 6.6000000000 0.0159736518 0.0113516921 0.0241274983 0.0074818986 0.0420930000 366219083 0 402718720 -1.0389455557 0.0331733003 0.6374722719 167 6.6400000000 0.0192137193 0.0113987701 0.0241274983 0.0075077752 0.0854070000 366148339 0 402718720 -1.0393098593 0.0392641649 0.6494765282 168 6.6800000000 0.0211521108 0.0114568257 0.0241274983 0.0075150768 0.0286820000 361184551 0 402718720 -1.0398350954 0.0397994667 0.6644635201 169 6.7200000000 0.0232841391 0.0115268098 0.0241274983 0.0075035388 0.0307770000 361591067 0 402718720 -1.0400540829 0.0401027016 0.6807916164 170 6.7600000000 0.0195911992 0.0115742474 0.0241274983 0.0074986522 0.0904420000 361734320 0 402718720 -1.0388290882 0.0419114269 0.6952085495 171 6.8000000000 0.0207978468 0.0116281866 0.0241274983 0.0074905799 0.0869070000 361736324 0 402718720 -1.0398764610 0.0426832065 0.7059675455 172 6.8400000000 0.0189190656 0.0116705754 0.0241274983 0.0074710163 0.0822680000 361747140 0 402718720 -1.0381822586 0.0441369899 0.7162995338 173 6.8800000000 0.0186666306 0.0117110150 0.0241274983 0.0074505826 0.0783670000 367315716 0 402718720 -1.0391206741 0.0442765243 0.7301539183 174 6.9200000000 0.0208013300 0.0117632582 0.0241274983 0.0074319455 0.0601340000 367355567 0 402718720 -1.0406854153 0.0475589857 0.7455576658 175 6.9600000000 0.0151329469 0.0117825136 0.0241274983 0.0074161817 0.0873150000 367096843 0 402718720 -1.0372594595 0.0449551307 0.7527205944 176 7.0000000000 0.0185934808 0.0118212123 0.0241274983 0.0074074183 0.0305920000 361745488 0 402718720 -1.0395325422 0.0487466194 0.7707870603 177 7.0400000000 0.0175136272 0.0118533728 0.0241274983 0.0074094774 0.0300440000 361749196 0 402718720 -1.0362308025 0.0474637598 0.7775892019 178 7.0800000000 0.0169030428 0.0118817417 0.0241274983 0.0073934359 0.0303210000 361751484 0 402718720 -1.0351738930 0.0479170568 0.7805926204 179 7.1200000000 0.0171817895 0.0119113509 0.0241274983 0.0073786150 0.0295890000 361753240 0 402718720 -1.0360392332 0.0488767847 0.7961830497 180 7.1600000000 0.0167266577 0.0119381026 0.0241274983 0.0073595780 0.0288260000 361755088 0 402718720 -1.0339833498 0.0529772602 0.8068667650 181 7.2000000000 0.0182119794 0.0119727649 0.0241274983 0.0073571334 0.0285010000 361756420 0 402718720 -1.0358707905 0.0481949784 0.8213318586 182 7.2400000000 0.0169602372 0.0120001686 0.0241274983 0.0073455878 0.0284590000 361761296 0 402718720 -1.0328371525 0.0528292321 0.8335514069 183 7.2800000000 0.0218833797 0.0120541752 0.0241274983 0.0073399203 0.0280940000 361762480 0 402718720 -1.0351793766 0.0578961037 0.8542300463 184 7.3200000000 0.0221360940 0.0121089683 0.0241274983 0.0073205118 0.0293370000 362142568 0 402718720 -1.0329041481 0.0580997393 0.8645789027 185 7.3600000000 0.0175052099 0.0121381372 0.0241274983 0.0073083503 0.0864390000 362292832 0 402718720 -1.0305255651 0.0533101894 0.8781313300 186 7.4000000000 0.0155574214 0.0121565204 0.0241274983 0.0072950035 0.0851120000 362296924 0 402718720 -1.0300611258 0.0522843227 0.8934108019 187 7.4400000000 0.0203831512 0.0122005131 0.0241274983 0.0072842006 0.0795340000 362316864 0 402718720 -1.0286393166 0.0552807003 0.9066957235 188 7.4800000000 0.0192514267 0.0122380179 0.0241274983 0.0072903434 0.0771230000 368158876 0 402718720 -1.0255277157 0.0593392551 0.9198950529 189 7.5200000000 0.0197189152 0.0122775994 0.0241274983 0.0072732092 0.0664310000 368132107 0 402718720 -1.0239038467 0.0618070289 0.9383828044 190 7.5600000000 0.0181472097 0.0123084921 0.0241274983 0.0072596016 0.0313830000 368145188 0 402718720 -1.0210382938 0.0611282960 0.9479959011 191 7.6000000000 0.0180496648 0.0123385506 0.0241274983 0.0072542191 0.0861810000 368074535 0 402718720 -1.0175192356 0.0650743470 0.9644086361 192 7.6400000000 0.0206554867 0.0123818680 0.0241274983 0.0072421263 0.0286470000 362311348 0 402718720 -1.0167499781 0.0716054142 0.9821136594 193 7.6800000000 0.0173279680 0.0124074954 0.0241274983 0.0072319863 0.0278830000 362313564 0 402718720 -1.0150008202 0.0698877126 0.9974641204 194 7.7200000000 0.0179919582 0.0124362813 0.0241274983 0.0072312088 0.0291750000 362671056 0 402718720 -1.0155985355 0.0654476956 1.0168263912 195 7.7600000000 0.0198398493 0.0124742483 0.0241274983 0.0072286257 0.0807290000 362840500 0 402718720 -1.0149654150 0.0667721257 1.0309128761 196 7.8000000000 0.0214990880 0.0125202934 0.0241274983 0.0072582939 0.0790610000 362841464 0 402718720 -1.0140492916 0.0692194700 1.0520323515 197 7.8400000000 0.0221270360 0.0125690586 0.0241274983 0.0072843383 0.0745720000 363119228 0 402718720 -1.0103657246 0.0751935840 1.0640836954 198 7.8800000000 0.0219665803 0.0126165209 0.0241274983 0.0073050186 0.0754420000 368006896 0 402718720 -1.0123748779 0.0745701417 1.0821064711 199 7.9200000000 0.0205387659 0.0126563311 0.0241274983 0.0072965679 0.0513070000 369114041 0 402718720 -1.0097174644 0.0771356076 1.0940611362 200 7.9600000000 0.0193678886 0.0126898889 0.0241274983 0.0072877044 0.0369400000 369163301 0 402718720 -1.0085465908 0.0744477734 1.1084935665 201 8.0000000000 0.0183935873 0.0127182655 0.0241274983 0.0073451676 0.0816630000 369033843 0 402718720 -1.0113054514 0.0645456091 1.1271144152 202 8.0400000000 0.0153521085 0.0127313044 0.0241274983 0.0073667022 0.0330550000 363256300 0 402718720 -1.0057724714 0.0711768121 1.1321913004 203 8.0800000000 0.0161180235 0.0127479877 0.0241274983 0.0073744438 0.0754770000 363356568 0 402718720 -1.0040619373 0.0710938275 1.1525138617 204 8.1200000000 0.0197068527 0.0127820998 0.0241274983 0.0073785293 0.0737770000 363353404 0 402718720 -0.9997305274 0.0774289668 1.1691203117 205 8.1600000000 0.0150168492 0.0127930010 0.0241274983 0.0073840259 0.0711210000 363434981 0 402718720 -0.9958158731 0.0750094801 1.1732927561 206 8.1999999990 0.0158947371 0.0128080580 0.0241274983 0.0073702812 0.0710220000 368751676 0 402718720 -0.9938535094 0.0755177736 1.1847970486 207 8.2400000000 0.0156330448 0.0128217052 0.0241274983 0.0073632646 0.0437040000 370230852 0 402718720 -0.9904745817 0.0752357021 1.2020958662 208 8.2799999990 0.0152860153 0.0128335529 0.0241274983 0.0073509707 0.0421400000 369913144 0 402718720 -0.9846362472 0.0794207081 1.2140305042 209 8.3200000000 0.0240216535 0.0128870845 0.0241274983 0.0074109941 0.0819170000 369941563 0 402718720 -0.9823496342 0.0810660571 1.2402087450 210 8.3599999990 0.0235354155 0.0129377908 0.0241274983 0.0074321133 0.0358660000 363665604 0 402718720 -0.9762272835 0.0838687569 1.2497318983 211 8.4000000000 0.0240278337 0.0129903503 0.0241274983 0.0074535814 0.0768180000 363869332 0 402718720 -0.9708577394 0.0842154846 1.2627897263 212 8.4399999990 0.0234586261 0.0130397289 0.0241274983 0.0074376479 0.0772100000 363868672 0 402718720 -0.9623678327 0.0844236165 1.2765243053 213 8.4800000000 0.0211549439 0.0130778285 0.0241274983 0.0074329946 0.0739160000 364892560 0 402718720 -0.9560581446 0.0867751464 1.2887015343 214 8.5200000000 0.0204406194 0.0131122341 0.0241274983 0.0074882107 0.0717580000 370273140 0 402718720 -0.9491349459 0.0857859403 1.3005990982 215 8.5600000000 0.0227880292 0.0131572378 0.0241274983 0.0075011569 0.0446600000 371191348 0 402718720 -0.9427852631 0.0881501585 1.3112148046 216 8.6000000000 0.0210343190 0.0131937058 0.0241274983 0.0074851950 0.0455010000 370857172 0 402718720 -0.9334267378 0.0901453570 1.3220427036 217 8.6400000000 0.0201555975 0.0132257882 0.0241274983 0.0075088658 0.0291250000 370963196 0 402718720 -0.9249143004 0.0946020782 1.3358312845 218 8.6800000000 0.0212364215 0.0132625342 0.0241274983 0.0075487619 0.0889410000 370892203 0 402718720 -0.9198352098 0.0888576955 1.3462342024 219 8.7200000000 0.0216275193 0.0133007305 0.0241274983 0.0075505317 0.0397890000 364236432 0 402718720 -0.9099351168 0.0947358534 1.3552268744 220 8.7600000000 0.0223622173 0.0133419191 0.0241274983 0.0075555388 0.0774390000 364416156 0 402718720 -0.9017882943 0.0972602591 1.3659545183 221 8.8000000000 0.0210068393 0.0133766020 0.0241274983 0.0075760592 0.0839530000 364419840 0 402718720 -0.8909028769 0.0959136188 1.3783190250 222 8.8400000000 0.0213465262 0.0134125025 0.0241274983 0.0075850531 0.0759300000 364714564 0 402718720 -0.8814617395 0.0991097614 1.3931781054 223 8.8800000000 0.0219171811 0.0134506401 0.0241274983 0.0075855812 0.0805120000 369395808 0 402718720 -0.8708975315 0.1040987372 1.4026597738 224 8.9200000000 0.0207644086 0.0134832909 0.0241274983 0.0075855777 0.0477920000 372085296 0 402718720 -0.8599604964 0.1019328237 1.4135237932 225 8.9600000000 0.0214694794 0.0135187850 0.0241274983 0.0075903975 0.0719670000 372102075 0 402718720 -0.8483216763 0.1099400073 1.4225614071 226 9.0000000000 0.0207457989 0.0135507630 0.0241274983 0.0075750838 0.0329680000 372008708 0 402718720 -0.8381699920 0.1125098914 1.4332126379 227 9.0400000000 0.0187356584 0.0135736039 0.0241274983 0.0075619327 0.0922990000 371936675 0 402718720 -0.8219587207 0.1180996597 1.4436453581 228 9.0800000000 0.0193580221 0.0135989742 0.0241274983 0.0075807032 0.0417920000 364932756 0 402718720 -0.8136968017 0.1198964342 1.4556137323 229 9.1200000000 0.0180852059 0.0136185647 0.0241274983 0.0076310826 0.0892040000 365006112 0 402718720 -0.8035697341 0.1243601739 1.4596799612 230 9.1600000000 0.0187520199 0.0136408841 0.0241274983 0.0077275251 0.0873090000 365011696 0 402718720 -0.7924156189 0.1294220984 1.4683119059 231 9.2000000000 0.0185395777 0.0136620905 0.0241274983 0.0079099964 0.0804880000 365297312 0 402718720 -0.7806075811 0.1294887364 1.4789638519 232 9.2400000000 0.0189979915 0.0136850901 0.0241274983 0.0080725834 0.0854010000 370822116 0 402718720 -0.7736073732 0.1325326413 1.4848903418 233 9.2800000000 0.0195461661 0.0137102449 0.0241274983 0.0082048555 0.0526360000 373275372 0 402718720 -0.7623453140 0.1361071765 1.4950798750 234 9.3200000000 0.0193280689 0.0137342527 0.0241274983 0.0083072794 0.0692730000 373218265 0 402718720 -0.7549159527 0.1374073178 1.4985131025 235 9.3600000000 0.0183741190 0.0137539969 0.0241274983 0.0083834874 0.0388580000 373200544 0 402718720 -0.7425436974 0.1443543732 1.5067861080 236 9.4000000000 0.0159939360 0.0137634881 0.0241274983 0.0084375242 0.1047100000 373129751 0 402718720 -0.7322018743 0.1459776908 1.5126776695 237 9.4400000000 0.0172392521 0.0137781538 0.0241274983 0.0084707129 0.0450740000 365031572 0 402718720 -0.7215486765 0.1516586095 1.5216636658 238 9.4800000000 0.0168685075 0.0137911385 0.0241274983 0.0084871214 0.0349810000 365035880 0 402718720 -0.7130421996 0.1552378386 1.5260074139 239 9.5200000000 0.0150593128 0.0137964446 0.0241274983 0.0085193983 0.0373990000 365542096 0 402718720 -0.7001302838 0.1600110829 1.5338058472 240 9.5600000000 0.0165211987 0.0138077978 0.0241274983 0.0085757968 0.0989080000 365609392 0 402718720 -0.6912057400 0.1668065935 1.5427410603 241 9.6000000000 0.0159029849 0.0138164915 0.0241274983 0.0086230292 0.0955060000 365613456 0 402718720 -0.6815812588 0.1658829749 1.5512686968 242 9.6400000000 0.0152913863 0.0138225861 0.0241274983 0.0086432679 0.0946750000 365732808 0 402718720 -0.6713225842 0.1706228256 1.5586296320 243 9.6800000000 0.0158200525 0.0138308061 0.0241274983 0.0086522990 0.0880290000 372797112 0 402718720 -0.6589845419 0.1760080308 1.5697367191 244 9.7200000000 0.0151318647 0.0138361383 0.0241274983 0.0086914298 0.0425270000 374707532 0 402718720 -0.6473914981 0.1821721643 1.5771952868 245 9.7600000000 0.0148735223 0.0138403726 0.0241274983 0.0087497552 0.0661780000 374339077 0 402718720 -0.6371860504 0.1846466213 1.5847032070 246 9.8000000000 0.0142775169 0.0138421496 0.0241274983 0.0087640357 0.0345780000 374334408 0 402718720 -0.6249219179 0.1880959719 1.5947816372 247 9.8400000000 0.0170088373 0.0138549702 0.0241274983 0.0087790281 0.1026990000 374264519 0 402718720 -0.6198718548 0.1903970391 1.6027176380 248 9.8800000000 0.0174242835 0.0138693626 0.0241274983 0.0087634103 0.0412200000 365587716 0 402718720 -0.6106489897 0.1922938824 1.6118927002 249 9.9200000000 0.0162343811 0.0138788606 0.0241274983 0.0087500553 0.0317510000 366019644 0 402718720 -0.5978161693 0.1957333237 1.6205828190 250 9.9600000000 0.0171996858 0.0138921439 0.0241274983 0.0087326262 0.0944170000 366157260 0 402718720 -0.5882131457 0.1984876990 1.6307424307 251 10.0000000000 0.0151358051 0.0138970988 0.0241274983 0.0087165756 0.0887300000 366156920 0 402718720 -0.5770315528 0.2019077688 1.6370680332 252 10.0400000000 0.0143387942 0.0138988515 0.0241274983 0.0087017706 0.0827410000 366443616 0 402718720 -0.5685960054 0.2005429417 1.6464009285 253 10.0800000000 0.0146380235 0.0139017731 0.0241274983 0.0086862799 0.0880800000 372775828 0 402718720 -0.5614367723 0.1946587563 1.6582163572 254 10.1200000000 0.0158063509 0.0139092715 0.0241274983 0.0087026619 0.0474590000 375168388 0 402718720 -0.5519534945 0.2021169811 1.6663451195 255 10.1600000000 0.0144626098 0.0139114414 0.0241274983 0.0087180317 0.0801700000 375121747 0 402718720 -0.5411621928 0.2076043487 1.6737891436 256 10.2000000000 0.0155505631 0.0139178443 0.0241274983 0.0087069037 0.0351430000 374953120 0 402718720 -0.5310388207 0.2090764195 1.6848605871 257 10.2400000000 0.0183140561 0.0139349501 0.0241274983 0.0087148781 0.1114130000 375007835 0 402718720 -0.5178414583 0.2148643732 1.6980679035 258 10.2800000000 0.0151740992 0.0139397530 0.0241274983 0.0086988024 0.0422270000 366226100 0 402718720 -0.5070929527 0.2203111947 1.7022868395 259 10.3200000000 0.0173403844 0.0139528829 0.0241274983 0.0086932339 0.0297480000 366230408 0 402718720 -0.4957435727 0.2251276374 1.7118595839 260 10.3600000000 0.0146657638 0.0139556247 0.0241274983 0.0086941001 0.0295450000 366233728 0 402718720 -0.4862732589 0.2262744904 1.7159342766 261 10.4000000000 0.0148131428 0.0139589103 0.0241274983 0.0086916904 0.0314430000 366679272 0 402718720 -0.4741547704 0.2268535942 1.7237161398 262 10.4400000000 0.0175302606 0.0139725414 0.0241274983 0.0086800106 0.0958610000 366803020 0 402718720 -0.4636406600 0.2295855731 1.7329190969 263 10.4800000000 0.0150833093 0.0139767648 0.0241274983 0.0086659976 0.0925320000 366807148 0 402718720 -0.4539696574 0.2294116169 1.7360327244 264 10.5200000000 0.0158183575 0.0139837405 0.0241274983 0.0086540576 0.0901560000 369628672 0 402718720 -0.4426078796 0.2287658751 1.7441959381 265 10.5600000000 0.0162270255 0.0139922058 0.0241274983 0.0086393717 0.0894410000 376113820 0 402718720 -0.4334660172 0.2301732004 1.7505577803 266 10.6000000000 0.0152496044 0.0139969328 0.0241274983 0.0086265341 0.0649710000 376436197 0 402718720 -0.4215043783 0.2317060232 1.7542577982 267 10.6400000000 0.0149845304 0.0140006317 0.0241274983 0.0086192371 0.0538260000 376162213 0 402718720 -0.4080111384 0.2301443517 1.7596800327 268 10.6800000000 0.0168292895 0.0140111864 0.0241274983 0.0086131923 0.0351730000 376252220 0 402718720 -0.3962289095 0.2303113788 1.7678859234 269 10.7200000000 0.0192185678 0.0140305447 0.0241274983 0.0086044813 0.1089250000 376181715 0 402718720 -0.3852850497 0.2310272157 1.7724198103 270 10.7600000000 0.0190950371 0.0140493021 0.0241274983 0.0085948566 0.0435770000 366823420 0 402718720 -0.3603602350 0.2340918779 1.7838560343 271 10.8000000000 0.0184157342 0.0140654144 0.0241274983 0.0086162279 0.0306270000 366824832 0 402718720 -0.3495083451 0.2388006449 1.7840995789 272 10.8400000000 0.0205352940 0.0140892007 0.0241274983 0.0086693278 0.0305000000 366828468 0 402718720 -0.3328522444 0.2382769585 1.7914566994 273 10.8800000000 0.0191782247 0.0141078418 0.0241274983 0.0086778926 0.0299490000 366828652 0 402718720 -0.3219012320 0.2373611927 1.7949938774 274 10.9200000000 0.0208626613 0.0141324944 0.0241274983 0.0086866830 0.0299600000 366831656 0 402718720 -0.3069788218 0.2408608794 1.7996494770 275 10.9600000000 0.0200030506 0.0141538419 0.0241274983 0.0086912566 0.0301210000 366834884 0 402718720 -0.2959153354 0.2411454618 1.8005579710 276 11.0000000000 0.0222686958 0.0141832435 0.0241274983 0.0086917771 0.0290410000 366836032 0 402718720 -0.2825918794 0.2407970130 1.8087351322 277 11.0400000000 0.0216662418 0.0142102580 0.0241274983 0.0086914308 0.0290580000 366839880 0 402718720 -0.2681118250 0.2426409870 1.8115115166 278 11.0800000000 0.0172827393 0.0142213101 0.0241274983 0.0086936188 0.0289640000 366840060 0 402718720 -0.2561247349 0.2423862219 1.8102874756 279 11.1200000000 0.0189393777 0.0142382207 0.0241274983 0.0087028250 0.0286230000 366843720 0 402718720 -0.2411308140 0.2451350093 1.8161574602 280 11.1600000000 0.0165747050 0.0142465653 0.0241274983 0.0087083379 0.0309690000 367299792 0 402718720 -0.2290432155 0.2471012473 1.8158726692 281 11.2000000000 0.0161802974 0.0142534469 0.0241274983 0.0087134792 0.0924530000 367398272 0 402718720 -0.2166348100 0.2480015159 1.8174434900 282 11.2400000000 0.0166565012 0.0142619684 0.0241274983 0.0087078201 0.0901980000 367401316 0 402718720 -0.2042995691 0.2475317717 1.8227369785 283 11.2800000000 0.0174983423 0.0142734043 0.0241274983 0.0086928318 0.0897580000 369706496 0 402718720 -0.1914111972 0.2490785420 1.8266013861 284 11.3200000000 0.0177111868 0.0142855092 0.0241274983 0.0086805352 0.0844920000 375669480 0 402718720 -0.1789959073 0.2512775660 1.8322505951 285 11.3600000000 0.0184854586 0.0143002459 0.0241274983 0.0086781973 0.0414060000 377662027 0 402718720 -0.1675544977 0.2537271976 1.8363177776 286 11.4000000000 0.0178625509 0.0143127015 0.0241274983 0.0086701160 0.0771910000 377540395 0 402718720 -0.1581893861 0.2537816465 1.8386095762 287 11.4400000000 0.0172367264 0.0143228897 0.0241274983 0.0086555535 0.0356010000 377304760 0 402718720 -0.1464579999 0.2511454821 1.8450106382 288 11.4800000000 0.0207693018 0.0143452731 0.0241274983 0.0086420203 0.1092570000 377233311 0 402718720 -0.1378908455 0.2547783852 1.8507314920 289 11.5200000000 0.0215126500 0.0143700737 0.0241274983 0.0086284356 0.0472350000 367369804 0 402718720 -0.1304509640 0.2573591173 1.8550553322 290 11.5600000000 0.0209310763 0.0143926978 0.0241274983 0.0086194304 0.0296840000 367372524 0 402718720 -0.1225357950 0.2570622563 1.8606231213 291 11.6000000000 0.0202234872 0.0144127349 0.0241274983 0.0086102729 0.0291440000 367373844 0 402718720 -0.1135507226 0.2547649741 1.8688280582 292 11.6400000000 0.0194259938 0.0144299036 0.0241274983 0.0085973801 0.0286020000 367376956 0 402718720 -0.1058921218 0.2556028664 1.8734042645 293 11.6800000000 0.0202537477 0.0144497802 0.0241274983 0.0085841791 0.0309620000 367832320 0 402718720 -0.0983109176 0.2581444383 1.8792330027 294 11.7200000000 0.0201223698 0.0144690747 0.0241274983 0.0085710062 0.0912040000 367935044 0 402718720 -0.0933026373 0.2568472326 1.8863930702 295 11.7600000000 0.0194067340 0.0144858126 0.0241274983 0.0085644371 0.0845040000 367938280 0 402718720 -0.0862021744 0.2556146681 1.8944590092 296 11.8000000000 0.0191145167 0.0145014501 0.0241274983 0.0085540931 0.0834350000 367969176 0 402718720 -0.0807877183 0.2559486330 1.9001463652 297 11.8400000000 0.0190837681 0.0145168788 0.0241274983 0.0085448639 0.0872460000 375211900 0 402718720 -0.0752672255 0.2560293078 1.9073096514 298 11.8800000000 0.0177504774 0.0145277298 0.0241274983 0.0085390125 0.0482680000 378033282 0 402718720 -0.0717524588 0.2541514039 1.9137904644 299 11.9200000000 0.0193606410 0.0145438933 0.0241274983 0.0085298231 0.0734880000 377942117 0 402718720 -0.0653582513 0.2564432025 1.9225832224 300 11.9600000000 0.0194539484 0.0145602602 0.0241274983 0.0085167212 0.0384570000 377789009 0 402718720 -0.0593746305 0.2559202015 1.9332604408 301 12.0000000000 0.0184890106 0.0145733125 0.0241274983 0.0085071873 0.1073650000 377673867 0 402718720 -0.0514196157 0.2555096745 1.9425185919 302 12.0400000000 0.0184498318 0.0145861487 0.0241274983 0.0084953730 0.0435060000 367951708 0 402718720 -0.0480547547 0.2549503744 1.9527150393 303 12.0800000000 0.0200815015 0.0146042852 0.0241274983 0.0084902644 0.0294560000 367957584 0 402718720 -0.0414733589 0.2565574050 1.9638016224 304 12.1200000000 0.0190023407 0.0146187524 0.0241274983 0.0084861202 0.0297800000 367957680 0 402718720 -0.0387569666 0.2570682168 1.9721595049 305 12.1600000000 0.0185761452 0.0146317275 0.0241274983 0.0084847934 0.0328460000 368508160 0 402718720 -0.0342600942 0.2542555928 1.9856797457 306 12.2000000000 0.0187246036 0.0146451029 0.0241274983 0.0084752298 0.0948220000 368528784 0 402718720 -0.0319882929 0.2553030252 1.9964337349 307 12.2400000000 0.0186323375 0.0146580906 0.0241274983 0.0084777302 0.0885570000 368531640 0 402718720 -0.0274421871 0.2556598485 2.0082035065 308 12.2800000000 0.0180375986 0.0146690631 0.0241274983 0.0084803430 0.0859230000 368802600 0 402718720 -0.0258858204 0.2553957999 2.0194513798 309 12.3200000000 0.0180836171 0.0146801134 0.0241274983 0.0084895426 0.0877470000 375294160 0 402718720 -0.0234504938 0.2555952668 2.0299260616 310 12.3600000000 0.0167461652 0.0146867781 0.0241274983 0.0085059099 0.0639360000 379016532 0 402718720 -0.0227233469 0.2540879548 2.0409030914 311 12.4000000000 0.0178588592 0.0146969777 0.0241274983 0.0085214589 0.0646780000 378945255 0 402718720 -0.0185208917 0.2551039457 2.0530469418 312 12.4400000000 0.0170877632 0.0147046405 0.0241274983 0.0085556146 0.0471000000 378863265 0 402718720 -0.0170339644 0.2557660341 2.0750508308 313 12.4800000000 0.0183248632 0.0147162067 0.0241274983 0.0085473041 0.0339600000 378921832 0 402718720 -0.0164956748 0.2554042637 2.0877223015 314 12.5200000000 0.0204430819 0.0147344452 0.0241274983 0.0085380477 0.1109540000 378850299 0 402718720 -0.0156823397 0.2527236640 2.1041867733 315 12.5600000000 0.0219029579 0.0147572023 0.0241274983 0.0085339336 0.0519700000 368546240 0 402718720 -0.0155098438 0.2555450797 2.1155092716 316 12.6000000000 0.0214608926 0.0147784165 0.0241274983 0.0085254791 0.0321750000 368984420 0 402718720 -0.0137495995 0.2558127046 2.1270763874 317 12.6400000000 0.0212471336 0.0147988226 0.0241274983 0.0085120276 0.0945590000 369093496 0 402718720 -0.0152690709 0.2559935451 2.1377422810 318 12.6800000000 0.0217082724 0.0148205504 0.0241274983 0.0084988168 0.0885770000 369091800 0 402718720 -0.0149633884 0.2557069063 2.1496324539 319 12.7200000000 0.0206296761 0.0148387608 0.0241274983 0.0084856351 0.0828500000 369362760 0 402718720 -0.0161836445 0.2552221417 2.1589071751 320 12.7600000000 0.0197811723 0.0148542059 0.0241274983 0.0084723273 0.0838390000 376058772 0 402718720 -0.0180514455 0.2552435398 2.1682868004 321 12.8000000000 0.0214538276 0.0148747655 0.0241274983 0.0084622154 0.0546230000 379079220 0 402718720 -0.0201235116 0.2552845478 2.1801226139 322 12.8400000000 0.0202077553 0.0148913275 0.0241274983 0.0084506820 0.0742230000 379005319 0 402718720 -0.0217535496 0.2549961805 2.1883721352 323 12.8800000000 0.0202405509 0.0149078886 0.0241274983 0.0084403500 0.0373710000 379189984 0 402718720 -0.0236852467 0.2534776032 2.1974444389 324 12.9200000000 0.0201675612 0.0149241222 0.0241274983 0.0084357592 0.1079430000 378775007 0 402718720 -0.0305824578 0.2518858314 2.2068204880 325 12.9600000000 0.0199788976 0.0149396753 0.0241274983 0.0084230220 0.0461150000 369659468 0 402718720 -0.0330497473 0.2525215149 2.2154552937 326 13.0000000000 0.0204851404 0.0149566859 0.0241274983 0.0084115445 0.0916140000 369657436 0 402718720 -0.0336351991 0.2531778812 2.2229170799 327 13.0400000000 0.0206706468 0.0149741598 0.0241274983 0.0084002047 0.0864630000 369666864 0 402718720 -0.0358458310 0.2536847591 2.2326860428 328 13.0800000000 0.0208086912 0.0149919480 0.0241274983 0.0083900185 0.0832890000 369935028 0 402718720 -0.0348680988 0.2562461197 2.2396483421 329 13.1200000000 0.0203725789 0.0150083025 0.0241274983 0.0083776247 0.0877180000 375872196 0 402718720 -0.0368656404 0.2561620772 2.2487421036 330 13.1600000000 0.0202384591 0.0150241515 0.0241274983 0.0083656930 0.0696200000 380178965 0 402718720 -0.0386131853 0.2563997805 2.2565486431 331 13.2000000000 0.0210037585 0.0150422168 0.0241274983 0.0083545010 0.0721250000 380093295 0 402718720 -0.0402516536 0.2584787309 2.2661774158 332 13.2400000000 0.0192678627 0.0150549446 0.0241274983 0.0083451945 0.0462790000 379914328 0 402718720 -0.0435804576 0.2572761178 2.2733614445 333 13.2800000000 0.0215051677 0.0150743147 0.0241274983 0.0083415600 0.1056760000 379838771 0 402718720 -0.0418424830 0.2615322173 2.2828400135 334 13.3200000000 0.0214029513 0.0150932627 0.0241274983 0.0083292166 0.0568950000 370379956 0 402718720 -0.0432050973 0.2609912455 2.2911255360 335 13.3600000000 0.0218067076 0.0151133028 0.0241274983 0.0083167595 0.1057100000 370355212 0 402718720 -0.0458389223 0.2622729242 2.3001589775 336 13.4000000000 0.0220732577 0.0151340170 0.0241274983 0.0083051927 0.0906270000 370355112 0 402718720 -0.0463699102 0.2645605803 2.3080091476 337 13.4400000000 0.0223520733 0.0151554355 0.0241274983 0.0083014969 0.0865200000 370357408 0 402718720 -0.0481122285 0.2671706080 2.3157088757 338 13.4800000000 0.0221045837 0.0151759951 0.0241274983 0.0083070131 0.0814500000 373317704 0 402718720 -0.0500816703 0.2687149644 2.3217020035 339 13.5200000000 0.0216901023 0.0151952108 0.0241274983 0.0083160360 0.0831780000 379185636 0 402718720 -0.0525504947 0.2677914202 2.3275232315 340 13.5600000000 0.0214603171 0.0152136376 0.0241274983 0.0083124927 0.0513480000 382291536 0 402718720 -0.0550444424 0.2685996294 2.3318250179 341 13.6000000000 0.0213611349 0.0152316654 0.0241274983 0.0083037160 0.0517060000 382449864 0 402718720 -0.0570936501 0.2685243785 2.3369243145 342 13.6400000000 0.0225997008 0.0152532094 0.0241274983 0.0082956018 0.0673630000 382424945 0 402718720 -0.0590661466 0.2702349722 2.3429925442 343 13.6800000000 0.0207009390 0.0152690920 0.0241274983 0.0082841681 0.0303400000 382030848 0 402718720 -0.0616178811 0.2684392035 2.3471238613 344 13.7200000000 0.0230909046 0.0152918298 0.0241274983 0.0082737704 0.0978580000 382114275 0 402718720 -0.0609493852 0.2711655796 2.3547339439 345 13.7600000000 0.0213937145 0.0153095164 0.0241274983 0.0082652046 0.0698550000 370728213 0 402718720 -0.0633832812 0.2695776224 2.3592431545 346 13.8000000000 0.0211347584 0.0153263524 0.0241274983 0.0082595020 0.0288470000 371010856 0 402718720 -0.0642789602 0.2695683837 2.3637650013 347 13.8400000000 0.0223195553 0.0153465057 0.0241274983 0.0082485002 0.0850900000 371062908 0 402718720 -0.0659472346 0.2688587010 2.3691883087 348 13.8800000000 0.0216386598 0.0153645866 0.0241274983 0.0082374394 0.0754150000 371067968 0 402718720 -0.0663374662 0.2704299390 2.3745839596 349 13.9200000000 0.0212988574 0.0153815903 0.0241274983 0.0082304868 0.0783400000 371137797 0 402718720 -0.0688698292 0.2703073025 2.3798828125 350 13.9600000000 0.0209404938 0.0153974728 0.0241274983 0.0082216012 0.0811320000 379872768 0 402718720 -0.0708842874 0.2679437399 2.3889703751 351 14.0000000000 0.0212730747 0.0154142124 0.0241274983 0.0082103534 0.0650060000 384235773 0 402718720 -0.0707347989 0.2685973644 2.3936131001 352 14.0400000000 0.0216326453 0.0154318784 0.0241274983 0.0082017846 0.0353260000 383830323 0 402718720 -0.0710927844 0.2689519525 2.3981206417 353 14.0800000000 0.0220784862 0.0154507074 0.0241274983 0.0081901831 0.0849300000 384093063 0 402718720 -0.0713975430 0.2678390145 2.4030969143 354 14.1200000000 0.0202199966 0.0154641799 0.0241274983 0.0081788948 0.0312440000 384618891 0 402718720 -0.0716891885 0.2669396698 2.4066898823 355 14.1600000000 0.0220673755 0.0154827805 0.0241274983 0.0081683663 0.0300670000 383816232 0 402718720 -0.0715861320 0.2673288882 2.4123110771 356 14.2000000000 0.0206724685 0.0154973583 0.0241274983 0.0081596014 0.1029580000 383739347 0 402718720 -0.0731917024 0.2645150721 2.4173297882 357 14.2400000000 0.0205347836 0.0155114687 0.0241274983 0.0081485098 0.0771700000 371282229 0 402718720 -0.0726901889 0.2648939192 2.4228334427 358 14.2800000000 0.0198072419 0.0155234681 0.0241274983 0.0081376594 0.0273010000 371085144 0 402718720 -0.0737630725 0.2627110481 2.4279017448 359 14.3200000000 0.0202887133 0.0155367417 0.0241274983 0.0081282730 0.0264780000 371087772 0 402718720 -0.0733362436 0.2623461783 2.4330258369 360 14.3600000000 0.0211036243 0.0155522053 0.0241274983 0.0081208209 0.0261640000 371090316 0 402718720 -0.0735775232 0.2614415288 2.4399099350 361 14.4000000000 0.0196587965 0.0155635809 0.0241274983 0.0081187816 0.0256600000 371092328 0 402718720 -0.0734984279 0.2595812082 2.4457371235 362 14.4400000000 0.0198012516 0.0155752872 0.0241274983 0.0081103721 0.0255130000 371095308 0 402718720 -0.0740749836 0.2601936162 2.4522387981 363 14.4800000000 0.0201465506 0.0155878802 0.0241274983 0.0081001829 0.0258870000 371097508 0 402718720 -0.0731517673 0.2619140744 2.4592566490 364 14.5200000000 0.0207464602 0.0156020521 0.0241274983 0.0080902025 0.0255470000 371097896 0 402718720 -0.0742235780 0.2612489164 2.4672365189 365 14.5600000000 0.0199679807 0.0156140135 0.0241274983 0.0080792827 0.0254360000 371103316 0 402718720 -0.0744692683 0.2598562837 2.4736866951 366 14.6000000000 0.0217827521 0.0156308680 0.0241274983 0.0080689930 0.0253500000 371105236 0 402718720 -0.0742775202 0.2629718482 2.4821739197 367 14.6400000000 0.0201088320 0.0156430696 0.0241274983 0.0080610617 0.0253620000 371106236 0 402718720 -0.0755719543 0.2612422705 2.4892759323 368 14.6800000000 0.0214637648 0.0156588867 0.0241274983 0.0080564397 0.0263360000 371109400 0 402718720 -0.0736792088 0.2642423511 2.4967699051 369 14.7200000000 0.0211065095 0.0156736499 0.0241274983 0.0080550436 0.0295380000 371739468 0 402718720 -0.0756306648 0.2636457086 2.5040872097 370 14.7600000000 0.0213247687 0.0156889232 0.0241274983 0.0080495298 0.0826790000 371697944 0 402718720 -0.0756117105 0.2639921606 2.5122754574 371 14.8000000000 0.0215464700 0.0157047117 0.0241274983 0.0080426740 0.0709930000 371697160 0 402718720 -0.0756122470 0.2639724910 2.5196056366 372 14.8400000000 0.0206963923 0.0157181302 0.0241274983 0.0080409238 0.0699470000 371748528 0 402718720 -0.0756165981 0.2629461288 2.5259582996 373 14.8800000000 0.0212292708 0.0157329054 0.0241274983 0.0080380077 0.0766970000 379841684 0 402718720 -0.0756818056 0.2632468641 2.5335741043 374 14.9200000000 0.0208524801 0.0157465941 0.0241274983 0.0080336334 0.0653990000 384973208 0 402718720 -0.0760475993 0.2621236742 2.5407698154 375 14.9600000000 0.0211914014 0.0157611136 0.0241274983 0.0080355987 0.0331390000 384324200 0 402718720 -0.0757114887 0.2617542744 2.5481159687 376 15.0000000000 0.0209678598 0.0157749613 0.0241274983 0.0080337031 0.0830860000 384577743 0 402718720 -0.0746860504 0.2626788318 2.5555086136 377 15.0400000000 0.0203505252 0.0157870981 0.0241274983 0.0080245437 0.0291890000 384602993 0 402718720 -0.0730705857 0.2641419470 2.5676398277 378 15.0800000000 0.0207909476 0.0158003358 0.0241274983 0.0080139009 0.0290450000 384292672 0 402718720 -0.0703697205 0.2653766274 2.5746016502 379 15.1200000000 0.0206521470 0.0158131374 0.0241274983 0.0080086867 0.1013110000 384214463 0 402718720 -0.0709310770 0.2650952339 2.5806765556 380 15.1600000000 0.0203931574 0.0158251901 0.0241274983 0.0079986968 0.0699870000 371937421 0 402718720 -0.0687454939 0.2665374279 2.5854177475 381 15.2000000000 0.0203367434 0.0158370314 0.0241274983 0.0079883682 0.0262350000 371726504 0 402718720 -0.0662026405 0.2673147917 2.5905952454 382 15.2400000000 0.0203638449 0.0158488817 0.0241274983 0.0079800513 0.0253310000 371727356 0 402718720 -0.0637234449 0.2676037550 2.5955278873 383 15.2800000000 0.0200917646 0.0158599597 0.0241274983 0.0079696834 0.0256670000 371728336 0 402718720 -0.0611574948 0.2684250772 2.5998322964 384 15.3200000000 0.0197435301 0.0158700732 0.0241274983 0.0079596380 0.0258710000 371732712 0 402718720 -0.0585660636 0.2691629827 2.6031429768 385 15.3600000000 0.0195312724 0.0158795828 0.0241274983 0.0079501150 0.0260030000 371735340 0 402718720 -0.0562337637 0.2682292759 2.6058015823 386 15.4000000000 0.0198686477 0.0158899172 0.0241274983 0.0079449042 0.0275320000 371743192 0 402718720 -0.0526977479 0.2690541744 2.6082792282 387 15.4400000000 0.0184511356 0.0158965353 0.0241274983 0.0079471565 0.0311770000 372273072 0 402718720 -0.0490476191 0.2709985971 2.6087856293 388 15.4800000000 0.0186753888 0.0159036973 0.0241274983 0.0079376584 0.0937360000 372315352 0 402718720 -0.0456751138 0.2720760703 2.6101710796 389 15.5200000000 0.0189784840 0.0159116016 0.0241274983 0.0079283506 0.0853960000 372312984 0 402718720 -0.0430134833 0.2727631032 2.6111295223 390 15.5600000000 0.0193061810 0.0159203057 0.0241274983 0.0079182934 0.0857860000 372566648 0 402718720 -0.0384629220 0.2764968276 2.6122734547 391 15.6000000000 0.0192568917 0.0159288391 0.0241274983 0.0079244110 0.0908640000 380046296 0 402718720 -0.0353521407 0.2770797610 2.6133608818 392 15.6400000000 0.0191322863 0.0159370112 0.0241274983 0.0079153369 0.0819430000 385141268 0 402718720 -0.0322179869 0.2766141295 2.6138799191 393 15.6800000000 0.0193556882 0.0159457101 0.0241274983 0.0079054060 0.0390200000 385821581 0 402718720 -0.0290441401 0.2752164006 2.6147139072 394 15.7200000000 0.0195438322 0.0159548424 0.0241274983 0.0078966313 0.0972010000 385694039 0 402718720 -0.0270498395 0.2737267613 2.6156189442 395 15.7600000000 0.0192168653 0.0159631007 0.0241274983 0.0078949760 0.0354940000 386030797 0 402718720 -0.0246272683 0.2742027938 2.6157202721 396 15.8000000000 0.0145420991 0.0159595123 0.0241274983 0.0079009036 0.1189750000 385324959 0 402718720 -0.0224402845 0.2712242603 2.6124281883 397 15.8400000000 0.0146654733 0.0159562528 0.0241274983 0.0079003897 0.0810620000 372346048 0 402718720 -0.0203738511 0.2701911032 2.6127500534 398 15.8800000000 0.0146910753 0.0159530739 0.0241274983 0.0078945384 0.0311690000 372349204 0 402718720 -0.0165307522 0.2684723139 2.6122286320 399 15.9200000000 0.0153767932 0.0159516296 0.0241274983 0.0078860659 0.0309630000 372350184 0 402718720 -0.0109252632 0.2712449729 2.6106917858 400 15.9600000000 0.0150477784 0.0159493700 0.0241274983 0.0078797879 0.0310900000 372355840 0 402718720 -0.0073387325 0.2712368369 2.6116528511 401 16.0000000000 0.0146285724 0.0159460762 0.0241274983 0.0078738686 0.0314040000 372357792 0 402718720 -0.0038869977 0.2713473439 2.6118609905 402 16.0400000000 0.0138183413 0.0159407834 0.0241274983 0.0078654034 0.0337230000 372817588 0 402718720 0.0004490018 0.2708757818 2.6116607189 403 16.0800000000 0.0144452257 0.0159370723 0.0241274983 0.0078600605 0.1003450000 372895092 0 402718720 0.0061234832 0.2708362937 2.6139590740 404 16.1200000000 0.0142734200 0.0159329543 0.0241274983 0.0078510310 0.0932600000 372897608 0 402718720 0.0109756589 0.2712128758 2.6128902435 405 16.1600000000 0.0140827484 0.0159283859 0.0241274983 0.0078423336 0.0929740000 373169060 0 402718720 0.0155839324 0.2718953490 2.6138093472 406 16.2000000000 0.0144220321 0.0159246757 0.0241274983 0.0078335476 0.0943640000 381145948 0 402718720 0.0220752358 0.2733386457 2.6172542572 407 16.2400000000 0.0148072382 0.0159219302 0.0241274983 0.0078254370 0.0732120000 385705837 0 402718720 0.0292747617 0.2754229903 2.6188969612 408 16.2800000000 0.0147425635 0.0159190396 0.0241274983 0.0078277602 0.0661630000 385212439 0 402718720 0.0339193344 0.2754536271 2.6221666336 409 16.3200000000 0.0141000096 0.0159145920 0.0241274983 0.0078303785 0.0532190000 385333525 0 402718720 0.0373020172 0.2782965302 2.6237683296 410 16.3600000000 0.0139100775 0.0159097030 0.0241274983 0.0078218841 0.0360280000 385175656 0 402718720 0.0462619662 0.2819348276 2.6281163692 411 16.3999999990 0.0151919900 0.0159079567 0.0241274983 0.0078189102 0.1212110000 385107095 0 402718720 0.0489935875 0.2802495658 2.6317594051 412 16.4400000000 0.0153962690 0.0159067148 0.0241274983 0.0078338072 0.0669270000 373369380 0 402718720 0.0554226637 0.2795385420 2.6388177872 413 16.4800000000 0.0158154815 0.0159064939 0.0241274983 0.0078464273 0.1048640000 373465164 0 402718720 0.0631530285 0.2810483277 2.6460189819 414 16.5200000000 0.0155089274 0.0159055336 0.0241274983 0.0078416758 0.1017880000 373468552 0 402718720 0.0668992996 0.2792344689 2.6490054131 415 16.5599999990 0.0164118819 0.0159067537 0.0241274983 0.0078546582 0.0937150000 373773788 0 402718720 0.0715981722 0.2749954462 2.6544017792 416 16.6000000000 0.0154459625 0.0159056460 0.0241274983 0.0079279564 0.0946970000 380508400 0 402718720 0.0741509199 0.2731565535 2.6601102352 417 16.6400000000 0.0175029226 0.0159094764 0.0241274983 0.0079612346 0.0816900000 385449992 0 402718720 0.0847167969 0.2773970664 2.6623148918 418 16.6800000000 0.0162145998 0.0159102064 0.0241274983 0.0079649050 0.0499910000 385647512 0 402718720 0.0857870579 0.2732480466 2.6608700752 419 16.7199999990 0.0182366464 0.0159157587 0.0241274983 0.0079978795 0.0699770000 385925305 0 402718720 0.0958373547 0.2780770957 2.6672575474 420 16.7600000000 0.0175614692 0.0159196771 0.0241274983 0.0079885033 0.0341430000 385392764 0 402718720 0.1033542156 0.2803129554 2.6665964127 421 16.8000000000 0.0155607052 0.0159188244 0.0241274983 0.0079985608 0.1148840000 385485603 0 402718720 0.1046670675 0.2726703882 2.6679525375 422 16.8400000000 0.0188597143 0.0159257933 0.0241274983 0.0079930575 0.0794250000 373989956 0 402718720 0.1130576134 0.2682337463 2.6723694801 423 16.8799999990 0.0175671782 0.0159296737 0.0241274983 0.0079891503 0.0951830000 373972076 0 402718720 0.1189581156 0.2676985860 2.6700763702 424 16.9200000000 0.0174523406 0.0159332649 0.0241274983 0.0079802257 0.0958980000 373974020 0 402718720 0.1255263090 0.2632316947 2.6694173813 425 16.9600000000 0.0169549547 0.0159356689 0.0241274983 0.0079807075 0.0876720000 374203255 0 402718720 0.1335625648 0.2653118968 2.6649303436 426 17.0000000000 0.0194493197 0.0159439169 0.0241274983 0.0079755784 0.0889150000 382750672 0 402718720 0.1430197954 0.2641867399 2.6684036255 427 17.0400000000 0.0191433504 0.0159514097 0.0241274983 0.0079710019 0.0605430000 386457001 0 402718720 0.1505784988 0.2601747811 2.6635804176 428 17.0800000000 0.0172814131 0.0159545172 0.0241274983 0.0079624957 0.0607030000 386218586 0 402718720 0.1576303244 0.2582437396 2.6581878662 429 17.1200000000 0.0161087550 0.0159548767 0.0241274983 0.0079545952 0.0535800000 386281825 0 402718720 0.1670287848 0.2575624883 2.6545166969 430 17.1600000000 0.0161169060 0.0159552535 0.0241274983 0.0079546141 0.0339060000 386127108 0 402718720 0.1763039827 0.2512025833 2.6499958038 431 17.2000000000 0.0267578475 0.0159803175 0.0267578475 0.0079609553 0.1069070000 386057555 0 402718720 0.1952760220 0.2571315169 2.6496236324 432 17.2400000000 0.0284993183 0.0160092967 0.0284993183 0.0079597939 0.0802120000 374360404 0 402718720 0.2081438303 0.2581049204 2.6443896294 433 17.2800000000 0.0298197437 0.0160411915 0.0298197437 0.0079521123 0.1025850000 374607800 0 402718720 0.2212334871 0.2570984960 2.6394798756 434 17.3200000000 0.0279261451 0.0160685762 0.0298197437 0.0079438364 0.1082170000 374609612 0 402718720 0.2304244041 0.2497428507 2.6314888000 435 17.3600000000 0.0257527083 0.0160908386 0.0298197437 0.0079559660 0.0966850000 374643516 0 402718720 0.2425839901 0.2475105226 2.6247036457 436 17.4000000000 0.0272922833 0.0161165299 0.0298197437 0.0079545988 0.0955780000 383684824 0 402718720 0.2569942474 0.2532424927 2.6187958717 437 17.4400000000 0.0252450090 0.0161374189 0.0298197437 0.0079492575 0.0560940000 386545272 0 402718720 0.2743397951 0.2592359185 2.6058232784 438 17.4800000000 0.0271013472 0.0161624507 0.0298197437 0.0080641810 0.0762430000 386475823 0 402718720 0.2868691683 0.2615052462 2.6003432274 439 17.5200000000 0.0230635554 0.0161781708 0.0298197437 0.0081771090 0.0449320000 386306737 0 402718720 0.2936583757 0.2522624731 2.5879235268 440 17.5600000000 0.0274152271 0.0162037095 0.0298197437 0.0082120004 0.0367270000 386445932 0 402718720 0.3002181053 0.2480431050 2.5809042454 441 17.6000000000 0.0309232082 0.0162370871 0.0309232082 0.0082071623 0.1092640000 386375611 0 402718720 0.3114339113 0.2434543222 2.5745420456 442 17.6400000000 0.0310192686 0.0162705309 0.0310192686 0.0082516786 0.0728700000 374983996 0 402718720 0.3214920759 0.2420812845 2.5702991486 443 17.6800000000 0.0283395071 0.0162977747 0.0310192686 0.0082777643 0.0902920000 375163548 0 402718720 0.3454107642 0.2432848066 2.5525209904 444 17.7200000000 0.0283080097 0.0163248248 0.0310192686 0.0082757887 0.0870560000 375166552 0 402718720 0.3526171446 0.2420617640 2.5426406860 445 17.7600000000 0.0309661310 0.0163577266 0.0310192686 0.0082736996 0.0831720000 375464260 0 402718720 0.3637219071 0.2411668301 2.5362620354 446 17.8000000000 0.0293664224 0.0163868940 0.0310192686 0.0082656922 0.0833310000 380238332 0 402718720 0.3742120862 0.2420958281 2.5241897106 447 17.8400000000 0.0292486548 0.0164156676 0.0310192686 0.0082631628 0.0708250000 385009796 0 402718720 0.3822008967 0.2373643368 2.5180242062 448 17.8800000000 0.0279392432 0.0164413898 0.0310192686 0.0082542995 0.0351910000 386422652 0 402718720 0.3883302808 0.2350074351 2.5094947815 449 17.9200000000 0.0332424827 0.0164788087 0.0332424827 0.0082480827 0.0982520000 386354263 0 402718720 0.4007277489 0.2369682193 2.5041871071 450 17.9600000000 0.0313897394 0.0165119441 0.0332424827 0.0082408341 0.0691310000 375539693 0 402718720 0.4053362608 0.2305372506 2.4985179901 451 18.0000000000 0.0307456851 0.0165435045 0.0332424827 0.0082480228 0.0798530000 375648340 0 402718720 0.4169681668 0.2310878783 2.4905390739 452 18.0400000000 0.0328996107 0.0165796906 0.0332424827 0.0082440613 0.0788160000 375652612 0 402718720 0.4278090596 0.2353232354 2.4821779728 453 18.0800000000 0.0333659984 0.0166167465 0.0333659984 0.0082356929 0.0793050000 379507836 0 402718720 0.4357581139 0.2310840935 2.4776561260 454 18.1200000000 0.0316466577 0.0166498520 0.0333659984 0.0082346637 0.0895830000 383197417 0 402718720 0.4411479831 0.2298442125 2.4710533619 455 18.1600000000 0.0311140846 0.0166816415 0.0333659984 0.0082276299 0.0738700000 376034385 0 402718720 0.4536063075 0.2271442115 2.4666202068 456 18.2000000000 0.0331286602 0.0167177096 0.0333659984 0.0082207424 0.0775660000 376060840 0 402718720 0.4610518813 0.2274198532 2.4593257904 457 18.2400000000 0.0326649658 0.0167526051 0.0333659984 0.0082250304 0.0732260000 376385844 0 402718720 0.4714810252 0.2257735580 2.4517533779 458 18.2800000000 0.0304537471 0.0167825202 0.0333659984 0.0082391357 0.0791460000 382517868 0 402718720 0.4801679850 0.2230954915 2.4511687756 459 18.3200000000 0.0304074977 0.0168122043 0.0333659984 0.0082320966 0.0862480000 383369601 0 402718720 0.4910817146 0.2240312099 2.4464740753 460 18.3600000000 0.0299489126 0.0168407624 0.0333659984 0.0082325273 0.0636520000 376492116 0 402718720 0.4972932935 0.2190610766 2.4428367615 461 18.4000000000 0.0306122135 0.0168706354 0.0333659984 0.0082317412 0.0758730000 376492196 0 402718720 0.5140904784 0.2203240544 2.4373054504 462 18.4400000000 0.0333569832 0.0169063201 0.0333659984 0.0082229654 0.0763280000 380071560 0 402718720 0.5237979293 0.2229517847 2.4341137409 463 18.4800000000 0.0324908458 0.0169399800 0.0333659984 0.0082194962 0.0762390000 385655744 0 402718720 0.5312683582 0.2182396501 2.4296071529 464 18.5200000000 0.0329444520 0.0169744724 0.0333659984 0.0082173462 0.0958200000 387244317 0 402718720 0.5358056426 0.2128136307 2.4287631512 465 18.5600000000 0.0319677442 0.0170067160 0.0333659984 0.0082146305 0.0707390000 376831964 0 402718720 0.5425722003 0.2094131410 2.4237203598 466 18.6000000000 0.0324697532 0.0170398984 0.0333659984 0.0082302206 0.0788760000 377161156 0 402718720 0.5509120822 0.2081608474 2.4222788811 467 18.6400000000 0.0294483025 0.0170664689 0.0333659984 0.0082310016 0.0726930000 377143568 0 402718720 0.5647784472 0.2071201354 2.4158036709 468 18.6800000000 0.0296859853 0.0170934337 0.0333659984 0.0082318796 0.0751940000 377531608 0 402718720 0.5727121234 0.2030928135 2.4151844978 469 18.7200000000 0.0307879075 0.0171226330 0.0333659984 0.0082474926 0.0735530000 378059788 0 402718720 0.5828772783 0.2029274553 2.4144477844 470 18.7600000000 0.0312384311 0.0171526666 0.0333659984 0.0082717004 0.0696880000 378046948 0 402718720 0.5895381570 0.2013669610 2.4115443230 471 18.8000000000 0.0294431690 0.0171787611 0.0333659984 0.0083266057 0.0660100000 378478904 0 402718720 0.5993900299 0.1981517673 2.4077520370 472 18.8400000000 0.0311909076 0.0172084478 0.0333659984 0.0083617172 0.0677900000 378608408 0 402718720 0.6066094041 0.1965514570 2.4072675705 473 18.8800000000 0.0295529030 0.0172345460 0.0333659984 0.0083723295 0.0816580000 378876268 0 402718720 0.6181257367 0.1956506968 2.4026529789 474 18.9200000000 0.0297410749 0.0172609311 0.0333659984 0.0083690963 0.0652490000 379085195 0 402718720 0.6232558489 0.1948667616 2.3944439888 475 18.9600000000 0.0306146741 0.0172890443 0.0333659984 0.0083660512 0.0818160000 379305888 0 402718720 0.6306935549 0.1909283102 2.3946413994 476 19.0000000000 0.0274928790 0.0173104809 0.0333659984 0.0083764902 0.0819720000 379825832 0 402718720 0.6411116719 0.1863787323 2.3910737038 477 19.0400000000 0.0293697380 0.0173357624 0.0333659984 0.0083737664 0.0692630000 379764704 0 402718720 0.6476730704 0.1883373410 2.3831331730 478 19.0800000000 0.0291529335 0.0173604845 0.0333659984 0.0083675220 0.0765120000 380028916 0 402718720 0.6582888961 0.1860668659 2.3852043152 479 19.1200000000 0.0271816496 0.0173809880 0.0333659984 0.0083621541 0.0812970000 380319000 0 402718720 0.6698201895 0.1851038635 2.3834524155 480 19.1600000000 0.0300859325 0.0174074566 0.0333659984 0.0083668516 0.0671820000 380349476 0 402718720 0.6747912169 0.1817433238 2.3860645294 481 19.2000000000 0.0304101594 0.0174344892 0.0333659984 0.0083811347 0.0738450000 380713020 0 402718720 0.6826167703 0.1845026761 2.3801622391 482 19.2400000000 0.0312393047 0.0174631299 0.0333659984 0.0083727186 0.0776410000 381193336 0 402718720 0.6923264861 0.1849893928 2.3819892406 483 19.2800000000 0.0350267887 0.0174994936 0.0350267887 0.0083662685 0.0943130000 381425916 0 402718720 0.6963549852 0.1858158708 2.3791749477 484 19.3200000000 0.0375704169 0.0175409625 0.0375704169 0.0083615061 0.0883020000 381752964 0 402718720 0.7008299828 0.1885080934 2.3754217625 485 19.3600000000 0.0393733867 0.0175859778 0.0393733867 0.0083579971 0.0720130000 381815572 0 402718720 0.7069691420 0.1897221357 2.3724293709 486 19.4000000000 0.0422805063 0.0176367896 0.0422805063 0.0083607274 0.0803100000 382152120 0 402718720 0.7121167779 0.1935914010 2.3691203594 487 19.4400000000 0.0296941027 0.0176615479 0.0422805063 0.0084144695 0.0834670000 382483812 0 402718720 0.7343858480 0.1865859628 2.3664193153 488 19.4800000000 0.0381809995 0.0177035960 0.0422805063 0.0084255375 0.0804980000 382595732 0 402718720 0.7292395234 0.1930606067 2.3592221737 489 19.5200000000 0.0377807580 0.0177446535 0.0422805063 0.0084210072 0.0969500000 382961848 0 402718720 0.7313053608 0.1869402081 2.3573672771 490 19.5600000000 0.0371390171 0.0177842339 0.0422805063 0.0084146217 0.0955810000 383471236 0 402718720 0.7373657823 0.1888634413 2.3468947411 491 19.6000000000 0.0379007682 0.0178252044 0.0422805063 0.0084090831 0.0862020000 383524136 0 402718720 0.7407490015 0.1839420348 2.3453431129 492 19.6400000000 0.0369929932 0.0178641633 0.0422805063 0.0084061248 0.0904280000 383637144 0 402718720 0.7445952296 0.1896426231 2.3302490711 493 19.6800000000 0.0355579481 0.0179000534 0.0422805063 0.0084019423 0.0858480000 383738728 0 402718720 0.7471468449 0.1869812012 2.3190941811 494 19.7200000000 0.0315659754 0.0179277172 0.0422805063 0.0084078667 0.1052350000 384067816 0 402718720 0.7552907467 0.1809422672 2.3121647835 495 19.7600000000 0.0335041992 0.0179591848 0.0422805063 0.0084007114 0.0987230000 384231011 0 402718720 0.7539479733 0.1800108999 2.3014323711 496 19.8000000000 0.0336069427 0.0179907327 0.0422805063 0.0084002079 0.0971530000 384295080 0 402718720 0.7495269179 0.1745401919 2.2974085808 497 19.8400000000 0.0294545610 0.0180137988 0.0422805063 0.0083922549 0.1138840000 384569528 0 402718720 0.7540954351 0.1693314463 2.2875239849 498 19.8800000000 0.0303604230 0.0180385912 0.0422805063 0.0083864569 0.1056600000 384717651 0 402718720 0.7538864613 0.1716338843 2.2758483887 499 19.9200000000 0.0308845565 0.0180643346 0.0422805063 0.0083783872 0.1051960000 384806312 0 402718720 0.7553123236 0.1704643518 2.2704284191 500 19.9600000000 0.0358540453 0.0180999140 0.0422805063 0.0083743468 0.1135280000 384809464 0 402718720 0.7468430996 0.1704382747 2.2586510181 501 20.0000000000 0.0401467755 0.0181439197 0.0422805063 0.0083690573 0.1018080000 385016608 0 402718720 0.7445032597 0.1720844507 2.2481765747 502 20.0400000000 0.0460172258 0.0181994443 0.0460172258 0.0083638690 0.1011230000 393584688 0 402718720 0.7416629791 0.1721676588 2.2422966957 503 20.0800000000 0.0408988521 0.0182445723 0.0460172258 0.0083610315 0.1168230000 396130797 0 402718720 0.7497479916 0.1688371748 2.2318465710 504 20.1200000000 0.0422172137 0.0182921371 0.0460172258 0.0083556410 0.1054600000 384843835 0 402718720 0.7498426437 0.1696091443 2.2205643654 505 20.1600000000 0.0402152315 0.0183355491 0.0460172258 0.0083538163 0.1007700000 384798560 0 402718720 0.7458570004 0.1652982831 2.2064676285 506 20.2000000000 0.0426440313 0.0183835896 0.0460172258 0.0083503398 0.1028670000 385009572 0 402718720 0.7438435555 0.1699893326 2.1973867416 507 20.2400000000 0.0427281596 0.0184316065 0.0460172258 0.0083490283 0.1033100000 389753020 0 402718720 0.7442538142 0.1708324254 2.1867299080 508 20.2800000000 0.0412823781 0.0184765884 0.0460172258 0.0083503036 0.1184940000 393090613 0 402718720 0.7375056744 0.1675466001 2.1758923531 509 20.3200000000 0.0381654426 0.0185152698 0.0460172258 0.0083464687 0.0946930000 385316980 0 402718720 0.7444108725 0.1638081968 2.1674449444 510 20.3600000000 0.0413046554 0.0185599549 0.0460172258 0.0083408299 0.1099020000 385472620 0 402718720 0.7438799143 0.1651547104 2.1517615318 511 20.4000000000 0.0428386703 0.0186074670 0.0460172258 0.0083344395 0.0999300000 389969864 0 402718720 0.7431572676 0.1663552225 2.1401476860 512 20.4400000000 0.0406194068 0.0186504591 0.0460172258 0.0083464424 0.0919640000 396527628 0 402718720 0.7441114187 0.1688018292 2.1269311905 513 20.4800000000 0.0584128872 0.0187279687 0.0584128872 0.0083967051 0.1341330000 396696811 0 402718720 0.7410320640 0.1819040775 2.1238207817 514 20.5200000000 0.0658873543 0.0188197185 0.0658873543 0.0083966559 0.0982910000 385863992 0 402718720 0.7329449654 0.1835570782 2.1144587994 515 20.5600000000 0.0600743107 0.0188998245 0.0658873543 0.0083996527 0.1129470000 385862448 0 402718720 0.7459536791 0.1852853000 2.1010813713 516 20.6000000000 0.0646241605 0.0189884375 0.0658873543 0.0084112421 0.1029390000 385904828 0 402718720 0.7444573641 0.1864128560 2.0884232521 517 20.6400000000 0.0633231178 0.0190741913 0.0658873543 0.0084104640 0.1016080000 395650600 0 402718720 0.7391811609 0.1809383035 2.0890853405 518 20.6800000000 0.0663567185 0.0191654703 0.0663567185 0.0084036353 0.1282900000 396946385 0 402718720 0.7505329847 0.1830140054 2.0681269169 519 20.7200000000 0.0598997027 0.0192439563 0.0663567185 0.0084012201 0.0950460000 386377700 0 402718720 0.7470320463 0.1814806759 2.0716812611 520 20.7600000000 0.0552347563 0.0193131694 0.0663567185 0.0084049937 0.1076470000 386377784 0 402718720 0.7463541627 0.1837633103 2.0702354908 521 20.8000000000 0.0557671487 0.0193831386 0.0663567185 0.0084120005 0.0999300000 389508232 0 402718720 0.7430041432 0.1827986836 2.0608558655 522 20.8400000000 0.0578377023 0.0194568064 0.0663567185 0.0084130200 0.0964680000 396551364 0 402718720 0.7423088551 0.1777312756 2.0570063591 523 20.8800000000 0.0486952774 0.0195127117 0.0663567185 0.0084162281 0.0343990000 398303759 0 402718720 0.7430889010 0.1744591743 2.0608446598 524 20.9200000000 0.0654507726 0.0196003797 0.0663567185 0.0084394942 0.0795770000 397965235 0 402718720 0.7400243282 0.1780640781 2.0430469513 525 20.9600000000 0.0637214929 0.0196844199 0.0663567185 0.0084325369 0.0325400000 397565196 0 402718720 0.7430171967 0.1792104095 2.0371038914 526 21.0000000000 0.0521168523 0.0197460785 0.0663567185 0.0084412181 0.0327160000 397719968 0 402718720 0.7581706643 0.1659851372 2.0215995312 527 21.0400000000 0.0481673852 0.0198000089 0.0663567185 0.0085589344 0.1250280000 397651635 0 402718720 0.7717143893 0.1803894490 1.9938583374 528 21.0800000000 0.0489313453 0.0198551819 0.0663567185 0.0085518702 0.0332370000 386755700 0 402718720 0.7765769958 0.1818135381 1.9890310764 529 21.1200000000 0.0480507724 0.0199084817 0.0663567185 0.0085451649 0.1013320000 386919636 0 402718720 0.7894116044 0.1787097603 1.9681291580 530 21.1600000000 0.0462828614 0.0199582447 0.0663567185 0.0085399375 0.1066690000 386919876 0 402718720 0.7881900668 0.1781108081 1.9663954973 531 21.2000000000 0.0498881377 0.0200146098 0.0663567185 0.0085339036 0.1008670000 390338192 0 402718720 0.7950916290 0.1802904606 1.9512513876 532 21.2400000000 0.0499156900 0.0200708149 0.0663567185 0.0085303756 0.0945220000 396865292 0 402718720 0.7897283435 0.1752557009 1.9454640150 533 21.2800000000 0.0528912917 0.0201323917 0.0663567185 0.0085242535 0.0378490000 399244141 0 402718720 0.7854256034 0.1756877899 1.9414079189 534 21.3200000000 0.0534870811 0.0201948537 0.0663567185 0.0085188824 0.0842580000 398962613 0 402718720 0.7933891416 0.1751788110 1.9262441397 535 21.3600000000 0.0550017059 0.0202599132 0.0663567185 0.0085150073 0.0335650000 398750628 0 402718720 0.7975420952 0.1782861948 1.9111059904 536 21.4000000000 0.0508035719 0.0203168977 0.0663567185 0.0085100444 0.0340090000 398912052 0 402718720 0.7993152142 0.1754877865 1.9052479267 537 21.4400000000 0.0453262106 0.0203634700 0.0663567185 0.0085066966 0.1339200000 398843539 0 402718720 0.8116719127 0.1701140553 1.8884559870 538 21.4800000000 0.0486632362 0.0204160718 0.0663567185 0.0085006835 0.0324840000 386936340 0 402718720 0.8087211847 0.1720710844 1.8801298141 539 21.5200000000 0.0463265069 0.0204641431 0.0663567185 0.0084959955 0.0355620000 387451580 0 402718720 0.8119582534 0.1720291674 1.8705117702 540 21.5600000000 0.0412044488 0.0205025510 0.0663567185 0.0084932091 0.1200860000 387501076 0 402718720 0.8186267614 0.1693821847 1.8548580408 541 21.6000000000 0.0479033552 0.0205531995 0.0663567185 0.0084947343 0.1198890000 387502696 0 402718720 0.8103801012 0.1734651625 1.8488993645 542 21.6400000000 0.0512299836 0.0206097987 0.0663567185 0.0084949848 0.1144140000 391341876 0 402718720 0.8158514500 0.1770374179 1.8352729082 543 21.6800000000 0.0481656902 0.0206605462 0.0663567185 0.0084891756 0.1128530000 398536092 0 402718720 0.8153287172 0.1700494140 1.8301476240 544 21.7200000000 0.0457214937 0.0207066141 0.0663567185 0.0084876208 0.0390120000 400618617 0 402718720 0.8179578185 0.1692340672 1.8198816776 545 21.7600000000 0.0485356338 0.0207576765 0.0663567185 0.0084874149 0.1055730000 400269319 0 402718720 0.8215330243 0.1718584448 1.8060451746 546 21.8000000000 0.0501751453 0.0208115547 0.0663567185 0.0084878149 0.0344040000 400714673 0 402718720 0.8184745312 0.1715303659 1.8030093908 547 21.8400000000 0.0501971729 0.0208652761 0.0663567185 0.0084851648 0.0340710000 400068885 0 402718720 0.8212503195 0.1736757457 1.7904677391 548 21.8800000000 0.0424020514 0.0209045768 0.0663567185 0.0084875745 0.1535770000 400158467 0 402718720 0.8247594833 0.1691160649 1.7820246220 549 21.9200000000 0.0433733128 0.0209455035 0.0663567185 0.0084804613 0.0327180000 387466896 0 402718720 0.8258561492 0.1695240438 1.7756704092 550 21.9600000000 0.0463752821 0.0209917394 0.0663567185 0.0084741113 0.0333130000 387469824 0 402718720 0.8228989244 0.1739045680 1.7702449560 551 22.0000000000 0.0414332263 0.0210288383 0.0663567185 0.0084743559 0.0312760000 387471556 0 402718720 0.8295458555 0.1712956429 1.7613301277 552 22.0400000000 0.0449665263 0.0210722037 0.0663567185 0.0084699353 0.0322630000 387473964 0 402718720 0.8280717134 0.1742968261 1.7556865215 553 22.0800000000 0.0445233211 0.0211146108 0.0663567185 0.0084648977 0.0302190000 387476464 0 402718720 0.8276854753 0.1742002964 1.7521750927 554 22.1200000000 0.0441090129 0.0211561169 0.0663567185 0.0084586370 0.0303870000 387478720 0 402718720 0.8277065158 0.1716250479 1.7464917898 555 22.1600000000 0.0465328805 0.0212018408 0.0663567185 0.0084541561 0.0318800000 387879556 0 402718720 0.8320254087 0.1787709296 1.7374762297 556 22.2000000000 0.0443631932 0.0212434979 0.0663567185 0.0084509867 0.1148100000 388041540 0 402718720 0.8348213434 0.1800031960 1.7275038958 557 22.2400000000 0.0452634357 0.0212866217 0.0663567185 0.0084567680 0.1118280000 388043088 0 402718720 0.8327177167 0.1777571738 1.7241941690 558 22.2800000000 0.0463603511 0.0213315567 0.0663567185 0.0084496461 0.1087960000 391757120 0 402718720 0.8304110169 0.1759866923 1.7195967436 559 22.3200000000 0.0453969575 0.0213746075 0.0663567185 0.0084444880 0.1088960000 399116652 0 402718720 0.8308619261 0.1779237539 1.7137188911 560 22.3600000000 0.0481100045 0.0214223493 0.0663567185 0.0084384884 0.0407690000 399300251 0 402718720 0.8282583952 0.1803698391 1.7105920315 561 22.4000000000 0.0489139222 0.0214713538 0.0663567185 0.0084318041 0.0758680000 399385589 0 402718720 0.8299491405 0.1797956675 1.7030991316 562 22.4400000000 0.0459242202 0.0215148643 0.0663567185 0.0084255468 0.0359160000 399134183 0 402718720 0.8271080256 0.1773671061 1.6995697021 563 22.4800000000 0.0430037081 0.0215530327 0.0663567185 0.0084260349 0.1302770000 399193667 0 402718720 0.8341528177 0.1761888117 1.6890437603 564 22.5200000000 0.0469491892 0.0215980614 0.0663567185 0.0084244076 0.0330610000 388053320 0 402718720 0.8355404735 0.1783815026 1.6840573549 565 22.5600000000 0.0472447798 0.0216434538 0.0663567185 0.0084171958 0.0337420000 388055452 0 402718720 0.8354557157 0.1752807200 1.6723794937 566 22.6000000000 0.0476622619 0.0216894234 0.0663567185 0.0084112227 0.0317880000 388057768 0 402718720 0.8377913237 0.1753118932 1.6657789946 567 22.6400000000 0.0488282815 0.0217372874 0.0663567185 0.0084042376 0.0305070000 388059960 0 402718720 0.8405625224 0.1762790084 1.6602060795 568 22.6800000000 0.0469679236 0.0217817075 0.0663567185 0.0083979545 0.0321750000 388062460 0 402718720 0.8442866206 0.1726582050 1.6501352787 569 22.7200000000 0.0473862737 0.0218267068 0.0663567185 0.0083919929 0.0296360000 388064576 0 402718720 0.8449484110 0.1709550768 1.6413294077 570 22.7600000000 0.0441399291 0.0218658528 0.0663567185 0.0083927445 0.0298710000 388066952 0 402718720 0.8490270376 0.1714265794 1.6284542084 571 22.8000000000 0.0482884273 0.0219121270 0.0663567185 0.0083905072 0.0292810000 388068960 0 402718720 0.8428510427 0.1758766025 1.6219669580 572 22.8400000000 0.0489454940 0.0219593881 0.0663567185 0.0083858388 0.0306610000 388071812 0 402718720 0.8397548199 0.1716339886 1.6129066944 573 22.8800000000 0.0467405543 0.0220026362 0.0663567185 0.0083821690 0.0292940000 388073928 0 402718720 0.8417521715 0.1693920642 1.6028647423 574 22.9200000000 0.0478906371 0.0220477373 0.0663567185 0.0083753068 0.0291570000 388076136 0 402718720 0.8379907012 0.1714720726 1.5976238251 575 22.9600000000 0.0451244041 0.0220878706 0.0663567185 0.0083723200 0.0289890000 388078284 0 402718720 0.8392965198 0.1660155952 1.5884609222 576 23.0000000000 0.0484708026 0.0221336743 0.0663567185 0.0083707898 0.0306770000 388080892 0 402718720 0.8358238935 0.1654779911 1.5804183483 577 23.0400000000 0.0447355025 0.0221728456 0.0663567185 0.0083727408 0.0314740000 388541160 0 402718720 0.8327376842 0.1627662182 1.5707631111 578 23.0800000000 0.0490731709 0.0222193859 0.0663567185 0.0083683453 0.1072490000 388675500 0 402718720 0.8343615532 0.1673124731 1.5611321926 579 23.1200000000 0.0466290489 0.0222615442 0.0663567185 0.0083619398 0.1066690000 388677916 0 402718720 0.8327922821 0.1617081165 1.5524089336 580 23.1600000000 0.0488632135 0.0223074092 0.0663567185 0.0083576130 0.1188060000 392316016 0 402718720 0.8326473832 0.1631392390 1.5413846970 581 23.2000000000 0.0452271700 0.0223468580 0.0663567185 0.0083523125 0.1038430000 399069428 0 402718720 0.8301844597 0.1590428352 1.5337610245 582 23.2400000000 0.0451414064 0.0223860239 0.0663567185 0.0083457997 0.0507480000 399376312 0 402718720 0.8292448521 0.1568851173 1.5228021145 583 23.2800000000 0.0459839776 0.0224265007 0.0663567185 0.0083391512 0.0646070000 399288453 0 402718720 0.8286643028 0.1543744504 1.5136439800 584 23.3200000000 0.0472178794 0.0224689517 0.0663567185 0.0083390216 0.0339220000 399050888 0 402718720 0.8282990456 0.1565332413 1.5018079281 585 23.3600000000 0.0413083471 0.0225011557 0.0663567185 0.0083405179 0.1361120000 399118587 0 402718720 0.8318786621 0.1510871053 1.4866745472 586 23.4000000000 0.0424730852 0.0225352375 0.0663567185 0.0083358390 0.0308260000 388691280 0 402718720 0.8335498571 0.1492817104 1.4751150608 587 23.4400000000 0.0407241918 0.0225662238 0.0663567185 0.0083381086 0.0305930000 388693764 0 402718720 0.8358537555 0.1470929086 1.4645969868 588 23.4800000000 0.0418622680 0.0225990402 0.0663567185 0.0083452244 0.0305410000 388695820 0 402718720 0.8293582201 0.1501320899 1.4384503365 589 23.5200000000 0.0401868224 0.0226289006 0.0663567185 0.0083404779 0.0319760000 388698612 0 402718720 0.8285136223 0.1499145627 1.4292488098 590 23.5600000000 0.0399017073 0.0226581766 0.0663567185 0.0083369082 0.0294820000 388700636 0 402718720 0.8262233138 0.1512856185 1.4177684784 591 23.6000000000 0.0426938459 0.0226920779 0.0663567185 0.0083403706 0.0307530000 388702736 0 402718720 0.8217858076 0.1511681527 1.4081966877 592 23.6400000000 0.0369219594 0.0227161149 0.0663567185 0.0083446747 0.0314190000 388705052 0 402718720 0.8262491226 0.1435991526 1.3925542831 593 23.6800000000 0.0350958519 0.0227369913 0.0663567185 0.0083405407 0.0289850000 388707600 0 402718720 0.8201564550 0.1408124715 1.3837311268 594 23.7200000000 0.0344251841 0.0227566684 0.0663567185 0.0083354257 0.0290620000 388709872 0 402718720 0.8191821575 0.1400699019 1.3716675043 595 23.7600000000 0.0350988731 0.0227774116 0.0663567185 0.0083336810 0.0310050000 388712340 0 402718720 0.8171185255 0.1400599033 1.3612693548 596 23.8000000000 0.0375302285 0.0228021646 0.0663567185 0.0083309884 0.0284150000 388714396 0 402718720 0.8153085709 0.1436663270 1.3496955633 597 23.8400000000 0.0387433358 0.0228288668 0.0663567185 0.0083274747 0.0297050000 388716896 0 402718720 0.8147393465 0.1473028362 1.3354715109 598 23.8800000000 0.0381856710 0.0228545471 0.0663567185 0.0083233368 0.0283510000 388719596 0 402718720 0.8114019632 0.1460594535 1.3250719309 599 23.9200000000 0.0370267145 0.0228782068 0.0663567185 0.0083199511 0.0284460000 388721560 0 402718720 0.8119224906 0.1476237178 1.3105890751 600 23.9600000000 0.0357446410 0.0228996508 0.0663567185 0.0083187898 0.0293450000 388724076 0 402718720 0.8049680591 0.1458348632 1.3020412922 601 24.0000000000 0.0321134180 0.0229149815 0.0663567185 0.0083196218 0.0323420000 389269396 0 402718720 0.8036445975 0.1417975724 1.2948334217 602 24.0400000000 0.0309694894 0.0229283611 0.0663567185 0.0083136846 0.1182410000 389372584 0 402718720 0.8035889864 0.1408720762 1.2816275358 603 24.0800000000 0.0317595936 0.0229430066 0.0663567185 0.0083082425 0.1103450000 389375228 0 402718720 0.7966425419 0.1413307786 1.2740656137 604 24.1200000000 0.0326738246 0.0229591172 0.0663567185 0.0083017104 0.1014280000 393602348 0 402718720 0.7944440842 0.1432230622 1.2652485371 605 24.1600000000 0.0316965133 0.0229735592 0.0663567185 0.0082966764 0.0965910000 400030504 0 402718720 0.7930885553 0.1409669667 1.2579590082 606 24.2000000000 0.0341157094 0.0229919456 0.0663567185 0.0082907135 0.0657360000 400171007 0 402718720 0.7899111509 0.1405915320 1.2513928413 607 24.2400000000 0.0335869119 0.0230094003 0.0663567185 0.0082844908 0.0484330000 399997368 0 402718720 0.7880824804 0.1396242231 1.2381054163 608 24.2800000000 0.0329138152 0.0230256904 0.0663567185 0.0082802330 0.0373240000 400140784 0 402718720 0.7887682915 0.1410526931 1.2274355888 609 24.3200000000 0.0309143681 0.0230386439 0.0663567185 0.0082764420 0.1240050000 400072615 0 402718720 0.7834769487 0.1373164952 1.2102020979 610 24.3600000000 0.0289760362 0.0230483773 0.0663567185 0.0082702937 0.0332690000 389389224 0 402718720 0.7800765038 0.1311512142 1.2047057152 611 24.4000000000 0.0328106880 0.0230643549 0.0663567185 0.0082728244 0.0320730000 389391696 0 402718720 0.7769447565 0.1339224130 1.1917290688 612 24.4400000000 0.0313770883 0.0230779378 0.0663567185 0.0082675153 0.0316280000 389394136 0 402718720 0.7751703262 0.1332298219 1.1810824871 613 24.4800000000 0.0350577757 0.0230974808 0.0663567185 0.0082623612 0.0317850000 389396376 0 402718720 0.7743130922 0.1350799650 1.1720271111 614 24.5200000000 0.0316002294 0.0231113289 0.0663567185 0.0082574453 0.0314540000 389398616 0 402718720 0.7717866898 0.1292475015 1.1580018997 615 24.5600000000 0.0317739546 0.0231254145 0.0663567185 0.0082512499 0.0310120000 389401244 0 402718720 0.7713990211 0.1281135827 1.1492273808 616 24.6000000000 0.0242054854 0.0231271678 0.0663567185 0.0082498395 0.0335240000 389403436 0 402718720 0.7684462070 0.1174473166 1.1411590576 617 24.6400000000 0.0306191240 0.0231393104 0.0663567185 0.0082571214 0.0301930000 389405660 0 402718720 0.7676115036 0.1225668639 1.1293121576 618 24.6800000000 0.0314945243 0.0231528302 0.0663567185 0.0082566846 0.0299310000 389407916 0 402718720 0.7672150731 0.1216493174 1.1150732040 619 24.7200000000 0.0284580290 0.0231614008 0.0663567185 0.0082518769 0.0300320000 389410264 0 402718720 0.7655799389 0.1174637228 1.1042439938 620 24.7600000000 0.0304169077 0.0231731032 0.0663567185 0.0082519887 0.0315560000 389412752 0 402718720 0.7615547180 0.1203615516 1.0936279297 621 24.8000000000 0.0324575044 0.0231880539 0.0663567185 0.0082511696 0.0308020000 389414884 0 402718720 0.7637526989 0.1220877469 1.0788540840 622 24.8400000000 0.0277402531 0.0231953726 0.0663567185 0.0082477995 0.0294720000 389417200 0 402718720 0.7580100894 0.1151775569 1.0721222162 623 24.8800000000 0.0294616334 0.0232054308 0.0663567185 0.0082429203 0.0314150000 389419640 0 402718720 0.7557100058 0.1172014624 1.0638458729 624 24.9200000000 0.0348687768 0.0232241220 0.0663567185 0.0082429713 0.0312360000 389422080 0 402718720 0.7547155619 0.1238950640 1.0502494574 625 24.9600000000 0.0315878503 0.0232375040 0.0663567185 0.0082456305 0.0297590000 389424564 0 402718720 0.7572800517 0.1187699437 1.0366617441 626 25.0000000000 0.0309269372 0.0232497874 0.0663567185 0.0082434307 0.0289510000 389426896 0 402718720 0.7511616349 0.1157372594 1.0344760418 627 25.0400000000 0.0268763099 0.0232555714 0.0663567185 0.0082396618 0.0285600000 389429228 0 402718720 0.7498930097 0.1115119681 1.0237524509 628 25.0800000000 0.0223509837 0.0232541309 0.0663567185 0.0082354426 0.0287920000 389431824 0 402718720 0.7453972101 0.1084610224 1.0150383711 629 25.1200000000 0.0240596626 0.0232554116 0.0663567185 0.0082340414 0.0301820000 389433776 0 402718720 0.7417020798 0.1075398847 1.0137991905 630 25.1600000000 0.0320880562 0.0232694317 0.0663567185 0.0082360067 0.0281930000 389436432 0 402718720 0.7354111671 0.1159188449 1.0044903755 631 25.2000000000 0.0319476388 0.0232831848 0.0663567185 0.0082326242 0.0288470000 389439028 0 402718720 0.7331597805 0.1184249371 0.9904150963 632 25.2400000000 0.0275200550 0.0232898887 0.0663567185 0.0082408746 0.0280810000 389441548 0 402718720 0.7326666117 0.1130687445 0.9824830294 633 25.2800000000 0.0329508483 0.0233051509 0.0663567185 0.0082408820 0.0292990000 389443452 0 402718720 0.7245565653 0.1188234389 0.9760101438 634 25.3200000000 0.0350496396 0.0233236753 0.0663567185 0.0082355171 0.0335190000 390162584 0 402718720 0.7170257568 0.1224786043 0.9673441052 635 25.3600000000 0.0331552215 0.0233391580 0.0663567185 0.0082417044 0.1577200000 390242676 0 402718720 0.7164685726 0.1212757230 0.9579843879 636 25.4000000000 0.0361078046 0.0233592345 0.0663567185 0.0082403507 0.1194070000 390252436 0 402718720 0.7112888098 0.1222426444 0.9513825774 637 25.4400000000 0.0332868472 0.0233748195 0.0663567185 0.0082377064 0.1135840000 395080692 0 402718720 0.7083883882 0.1199645028 0.9432413578 638 25.4800000000 0.0335273892 0.0233907326 0.0663567185 0.0082326644 0.0844390000 400401760 0 402718720 0.7050200701 0.1184706390 0.9359237552 639 25.5200000000 0.0388069004 0.0234148580 0.0663567185 0.0082308205 0.0852610000 400313731 0 402718720 0.6985649467 0.1214427948 0.9317660332 640 25.5600000000 0.0375331789 0.0234369179 0.0663567185 0.0082247089 0.0417770000 400318936 0 402718720 0.6936730742 0.1185821295 0.9272611737 641 25.6000000000 0.0334527418 0.0234525432 0.0663567185 0.0082209312 0.1279570000 400250607 0 402718720 0.6855934262 0.1131403297 0.9194025397 642 25.6400000000 0.0338834710 0.0234687908 0.0663567185 0.0082149419 0.0357560000 390268576 0 402718720 0.6795578599 0.1118177548 0.9163392186 643 25.6800000000 0.0322759710 0.0234824878 0.0663567185 0.0082095825 0.0358380000 390271148 0 402718720 0.6757746339 0.1090485603 0.9079427719 644 25.7200000000 0.0359826162 0.0235018979 0.0663567185 0.0082053157 0.0359670000 390273484 0 402718720 0.6706250310 0.1116313487 0.9046340585 645 25.7600000000 0.0306913741 0.0235130444 0.0663567185 0.0082039168 0.0355020000 390275924 0 402718720 0.6657294035 0.1045134664 0.8966721892 646 25.8000000000 0.0331593044 0.0235279767 0.0663567185 0.0081983920 0.0350070000 390278412 0 402718720 0.6598360538 0.1053418815 0.8940760493 647 25.8400000000 0.0342455059 0.0235445417 0.0663567185 0.0081926555 0.0351560000 390280764 0 402718720 0.6500469446 0.1060524434 0.8897789121 648 25.8800000000 0.0342945047 0.0235611311 0.0663567185 0.0081947276 0.0354750000 390283420 0 402718720 0.6459240913 0.1050499529 0.8879584074 649 25.9200000000 0.0351034850 0.0235789159 0.0663567185 0.0081904437 0.0348150000 390285448 0 402718720 0.6377241611 0.1030833721 0.8831140995 650 25.9600000000 0.0302244667 0.0235891399 0.0663567185 0.0081869494 0.0348870000 390287968 0 402718720 0.6232126951 0.0913380533 0.8725513220 651 26.0000000000 0.0332837589 0.0236040318 0.0663567185 0.0081919638 0.0334370000 390290564 0 402718720 0.6058272123 0.0944120064 0.8632186055 652 26.0400000000 0.0334290639 0.0236191008 0.0663567185 0.0081866185 0.0343160000 390292856 0 402718720 0.5970645547 0.0944496095 0.8601801395 653 26.0800000000 0.0349066369 0.0236363865 0.0663567185 0.0081808669 0.0328470000 390294928 0 402718720 0.5859923959 0.1000445411 0.8530619144 654 26.1200000000 0.0341514461 0.0236524646 0.0663567185 0.0081861688 0.0331420000 390297508 0 402718720 0.5770776272 0.0999601781 0.8467823267 655 26.1600000000 0.0288858935 0.0236604545 0.0663567185 0.0081996468 0.0327050000 390300440 0 402718720 0.5679459572 0.0898360610 0.8471401930 656 26.2000000000 0.0384605713 0.0236830157 0.0663567185 0.0082218403 0.0344510000 390302544 0 402718720 0.5556982756 0.0994734317 0.8458928466 657 26.2400000000 0.0343682095 0.0236992793 0.0663567185 0.0082196782 0.0342650000 390304772 0 402718720 0.5449051261 0.0960636884 0.8403132558 658 26.2800000000 0.0285139550 0.0237065964 0.0663567185 0.0082223938 0.0340260000 390307180 0 402718720 0.5354609489 0.0930218175 0.8316665888 659 26.3200000000 0.0406014770 0.0237322336 0.0663567185 0.0082475467 0.0334870000 390309404 0 402718720 0.5218849778 0.1061040461 0.8346200585 660 26.3600000000 0.0357135385 0.0237503871 0.0663567185 0.0082512992 0.0320410000 390311812 0 402718720 0.5094138384 0.0993712172 0.8342405558 661 26.4000000000 0.0326555893 0.0237638594 0.0663567185 0.0082485513 0.0315030000 390314220 0 402718720 0.4989435077 0.0993687660 0.8289270997 662 26.4400000000 0.0397190116 0.0237879608 0.0663567185 0.0082525120 0.0323570000 390316876 0 402718720 0.4866543114 0.1143774167 0.8186264634 663 26.4800000000 0.0335720293 0.0238027181 0.0663567185 0.0083053697 0.0332940000 390318548 0 402718720 0.4766471088 0.1052926630 0.8206852078 664 26.5200000000 0.0365169980 0.0238218661 0.0663567185 0.0083035165 0.0319660000 390321140 0 402718720 0.4669151306 0.1069693118 0.8120346069 665 26.5600000000 0.0327771604 0.0238353327 0.0663567185 0.0083106658 0.0317790000 390323564 0 402718720 0.4578604698 0.1013018712 0.8138571382 666 26.6000000000 0.0380626842 0.0238566951 0.0663567185 0.0083095852 0.0325500000 390325864 0 402718720 0.4448899031 0.1107171997 0.8070105910 667 26.6400000000 0.0386137478 0.0238788196 0.0663567185 0.0083076247 0.0336660000 390327780 0 402718720 0.4338909984 0.1159298345 0.7993188500 668 26.6800000000 0.0373894125 0.0238990451 0.0663567185 0.0083604036 0.0312780000 390330264 0 402718720 0.4243299961 0.1162976027 0.8042792678 669 26.7200000000 0.0367206074 0.0239182103 0.0663567185 0.0083933051 0.0322710000 390332612 0 402718720 0.4129746556 0.1174955666 0.7999562025 670 26.7600000000 0.0389540792 0.0239406519 0.0663567185 0.0084117222 0.0333260000 390334960 0 402718720 0.4036419392 0.1200591028 0.7957515717 671 26.8000000000 0.0351270624 0.0239573232 0.0663567185 0.0084418159 0.0309250000 390337232 0 402718720 0.3938003778 0.1138773933 0.7966037393 672 26.8400000000 0.0261535291 0.0239605913 0.0663567185 0.0084660473 0.0308170000 390340148 0 402718720 0.3856033087 0.1060378179 0.7919300795 673 26.8800000000 0.0394175202 0.0239835585 0.0663567185 0.0084937518 0.0313970000 390342420 0 402718720 0.3761542439 0.1225250661 0.7877932191 674 26.9200000000 0.0352317579 0.0240002473 0.0663567185 0.0085029898 0.0327120000 390344756 0 402718720 0.3671233356 0.1154742539 0.7891645432 675 26.9600000000 0.0232190806 0.0239990900 0.0663567185 0.0085226182 0.0326370000 390346920 0 402718720 0.3582834303 0.1095305160 0.7763983607 676 27.0000000000 0.0374240018 0.0240189493 0.0663567185 0.0085471679 0.0324240000 390349052 0 402718720 0.3468022346 0.1263506860 0.7791606784 677 27.0400000000 0.0350969732 0.0240353127 0.0663567185 0.0085549072 0.0325370000 390351476 0 402718720 0.3397260606 0.1306549907 0.7690733075 678 27.0800000000 0.0330956094 0.0240486760 0.0663567185 0.0085742856 0.0325870000 390353780 0 402718720 0.3325682282 0.1302997321 0.7667786479 679 27.1200000000 0.0385960862 0.0240701007 0.0663567185 0.0085791374 0.0329260000 390356388 0 402718720 0.3222493231 0.1363613755 0.7673279643 680 27.1600000000 0.0437679403 0.0240990682 0.0663567185 0.0085790161 0.0311570000 390358368 0 402718720 0.3124642968 0.1405923516 0.7647924423 681 27.2000000000 0.0377607532 0.0241191294 0.0663567185 0.0085813534 0.0323880000 390360732 0 402718720 0.3049817681 0.1371951699 0.7568811178 682 27.2400000000 0.0357718207 0.0241362154 0.0663567185 0.0085769659 0.0304510000 390363292 0 402718720 0.2965690494 0.1373069435 0.7555744052 683 27.2800000000 0.0415764116 0.0241617501 0.0663567185 0.0086068038 0.0312930000 390365408 0 402718720 0.2876712382 0.1388010532 0.7630494237 684 27.3200000000 0.0390370935 0.0241834977 0.0663567185 0.0086236554 0.0320250000 390367724 0 402718720 0.2807359695 0.1462536901 0.7435470819 685 27.3600000000 0.0352345705 0.0241996306 0.0663567185 0.0086509762 0.0320140000 390370116 0 402718720 0.2738903761 0.1398203224 0.7445789576 686 27.4000000000 0.0381994955 0.0242200386 0.0663567185 0.0086532918 0.0321060000 390372664 0 402718720 0.2641238570 0.1428341419 0.7445588708 687 27.4400000000 0.0339206569 0.0242341589 0.0663567185 0.0086623411 0.0313960000 390374704 0 402718720 0.2582812607 0.1465508044 0.7317721248 688 27.4800000000 0.0334326550 0.0242475288 0.0663567185 0.0086652384 0.0316810000 390377052 0 402718720 0.2482605726 0.1507635713 0.7185483575 689 27.5200000000 0.0287671611 0.0242540885 0.0663567185 0.0086999358 0.0303000000 390379476 0 402718720 0.2415023148 0.1464098543 0.7161663771 690 27.5600000000 0.0467682667 0.0242867177 0.0663567185 0.0087426638 0.0375490000 391184800 0 402718720 0.2305696607 0.1639411151 0.7168690562 691 27.6000000000 0.0484474227 0.0243216826 0.0663567185 0.0087439136 0.1329340000 391171016 0 402718720 0.2229216695 0.1681253463 0.7149527669 692 27.6400000000 0.0517189428 0.0243612740 0.0663567185 0.0087448868 0.1122810000 391199996 0 402718720 0.2147169709 0.1759566665 0.7079299092 693 27.6800000000 0.0478567332 0.0243951780 0.0663567185 0.0087964699 0.1114200000 400331860 0 402718720 0.2071379721 0.1710327864 0.7023730874 694 27.7200000000 0.0513549969 0.0244340250 0.0663567185 0.0088028794 0.0888100000 400263275 0 402718720 0.2007416636 0.1735312939 0.6959213614 695 27.7600000000 0.0521144122 0.0244738529 0.0663567185 0.0087978432 0.0432850000 400247748 0 402718720 0.1927901655 0.1738991439 0.6879602075 696 27.8000000000 0.0385903083 0.0244941351 0.0663567185 0.0096373281 0.1233110000 400179863 0 402718720 0.1904954314 0.1455730498 0.6183316708 697 27.8400000000 0.0286982078 0.0245001668 0.0663567185 0.0096566777 0.0358850000 391183616 0 402718720 0.1837615967 0.1412314475 0.6192675829 698 27.8800000000 0.0366847143 0.0245176232 0.0663567185 0.0096540520 0.0353910000 391186428 0 402718720 0.1738599837 0.1485438943 0.6052484512 699 27.9200000000 0.0327107906 0.0245293444 0.0663567185 0.0096617411 0.0353310000 391188720 0 402718720 0.1669161171 0.1542143077 0.6037909389 700 27.9600000000 0.0369481035 0.0245470855 0.0663567185 0.0096788676 0.0352260000 391190868 0 402718720 0.1558145583 0.1549197584 0.5918818712 701 28.0000000000 0.0319166556 0.0245575985 0.0663567185 0.0097128922 0.0344930000 391193632 0 402718720 0.1502777040 0.1542127430 0.5902497768 702 28.0400000000 0.0355276875 0.0245732254 0.0663567185 0.0097175041 0.0334550000 391195736 0 402718720 0.1404535621 0.1561344266 0.5804483891 703 28.0800000000 0.0311470348 0.0245825764 0.0663567185 0.0097282975 0.0325050000 391198300 0 402718720 0.1354168504 0.1565348804 0.5800297260 704 28.1200000000 0.0367910899 0.0245999181 0.0663567185 0.0097238801 0.0331300000 391200528 0 402718720 0.1252366453 0.1668693870 0.5707500577 705 28.1600000000 0.0321641415 0.0246106475 0.0663567185 0.0097616246 0.0327830000 391203140 0 402718720 0.1180669367 0.1662529856 0.5701242089 706 28.2000000000 0.0350371897 0.0246254159 0.0663567185 0.0097729827 0.0325650000 391205492 0 402718720 0.1101085246 0.1666456461 0.5631678104 707 28.2400000000 0.0329079926 0.0246371310 0.0663567185 0.0097749542 0.0321660000 391207704 0 402718720 0.1020733863 0.1690016091 0.5611923933 708 28.2800000000 0.0333321206 0.0246494121 0.0663567185 0.0097690504 0.0316250000 391210204 0 402718720 0.0945822299 0.1756586730 0.5581057668 709 28.3200000000 0.0331105515 0.0246613460 0.0663567185 0.0097651820 0.0322490000 391212508 0 402718720 0.0893764049 0.1715004146 0.5549704432 710 28.3600000000 0.0350945145 0.0246760406 0.0663567185 0.0097606315 0.0319460000 391214980 0 402718720 0.0806564689 0.1728463173 0.5494383574 711 28.4000000000 0.0320111811 0.0246863573 0.0663567185 0.0097557381 0.0323200000 391217296 0 402718720 0.0729602426 0.1816022396 0.5508223176 712 28.4400000000 0.0346783400 0.0247003910 0.0663567185 0.0097489019 0.0314380000 391219520 0 402718720 0.0631698221 0.1869508922 0.5462793112 713 28.4800000000 0.0321077816 0.0247107800 0.0663567185 0.0097424344 0.0342200000 391222112 0 402718720 0.0591543913 0.1798004508 0.5472116470 714 28.5200000000 0.0315733738 0.0247203915 0.0663567185 0.0097486892 0.0330050000 391224168 0 402718720 0.0507920086 0.1855633557 0.5468850136 715 28.5600000000 0.0283319168 0.0247254426 0.0663567185 0.0097487081 0.0372530000 391948340 0 402718720 0.0449672937 0.1960971802 0.5506003499 716 28.6000000000 0.0278044064 0.0247297428 0.0663567185 0.0097497443 0.1339410000 392016008 0 402718720 0.0387851745 0.1967012584 0.5529852509 717 28.6400000000 0.0283229277 0.0247347542 0.0663567185 0.0097443219 0.1134510000 396568384 0 402718720 0.0328461081 0.1996489912 0.5555665493 718 28.6800000000 0.0267150346 0.0247375123 0.0663567185 0.0097391930 0.0778310000 400198548 0 402718720 0.0259232968 0.2027619481 0.5597476959 719 28.7200000000 0.0279275980 0.0247419491 0.0663567185 0.0097336000 0.0551700000 399971720 0 402718720 0.0179887712 0.2079559714 0.5609712005 720 28.7600000000 0.0353881344 0.0247567355 0.0663567185 0.0097445166 0.1076030000 399903675 0 402718720 0.0055071414 0.2234317213 0.5626763701 721 28.8000000000 0.0382403843 0.0247754368 0.0663567185 0.0097380968 0.0361070000 392033500 0 402718720 -0.0025788546 0.2266995907 0.5656006336 722 28.8400000000 0.0362434164 0.0247913204 0.0663567185 0.0097319926 0.0352060000 392035264 0 402718720 -0.0090679526 0.2281638533 0.5715989470 723 28.8800000000 0.0362950787 0.0248072316 0.0663567185 0.0097254993 0.0336200000 392037812 0 402718720 -0.0156082809 0.2304433733 0.5777828693 724 28.9200000000 0.0370529704 0.0248241456 0.0663567185 0.0097188130 0.0346440000 392040008 0 402718720 -0.0242731571 0.2333183885 0.5824625492 725 28.9600000000 0.0382874608 0.0248427156 0.0663567185 0.0097129676 0.0333700000 392043632 0 402718720 -0.0343761146 0.2362929881 0.5868387222 726 29.0000000000 0.0368021354 0.0248591887 0.0663567185 0.0097195756 0.0330820000 392044400 0 402718720 -0.0398572385 0.2374330163 0.5945723653 727 29.0400000000 0.0386246890 0.0248781233 0.0663567185 0.0097163356 0.0324400000 392047652 0 402718720 -0.0499053597 0.2415021062 0.5997606516 728 29.0800000000 0.0363169126 0.0248938360 0.0663567185 0.0097228982 0.0310780000 392049544 0 402718720 -0.0583263636 0.2417854369 0.6075648069 729 29.1200000000 0.0369951166 0.0249104358 0.0663567185 0.0097191683 0.0301970000 392052048 0 402718720 -0.0670121908 0.2447707951 0.6139866114 730 29.1600000000 0.0371562541 0.0249272109 0.0663567185 0.0097134625 0.0292450000 392054352 0 402718720 -0.0764921308 0.2464247048 0.6209280491 731 29.2000000000 0.0384841375 0.0249457566 0.0663567185 0.0097070483 0.0288750000 392056548 0 402718720 -0.0859161615 0.2500621676 0.6264278889 732 29.2400000000 0.0373962522 0.0249627655 0.0663567185 0.0097036185 0.0286740000 392057100 0 402718720 -0.0972845852 0.2519017458 0.6324114799 733 29.2800000000 0.0380218774 0.0249805815 0.0663567185 0.0096979630 0.0282670000 392060312 0 402718720 -0.1055873632 0.2569726706 0.6411198974 734 29.3200000000 0.0363043398 0.0249960089 0.0663567185 0.0096918209 0.0277580000 392063240 0 402718720 -0.1131805778 0.2601632774 0.6520392299 735 29.3600000000 0.0373709910 0.0250128456 0.0663567185 0.0096883830 0.0334920000 392819936 0 402718720 -0.1241130829 0.2636940479 0.6591303945 736 29.4000000000 0.0380320437 0.0250305348 0.0663567185 0.0096838085 0.1328590000 392878172 0 402718720 -0.1310504675 0.2692416608 0.6682513952 737 29.4400000000 0.0382348523 0.0250484511 0.0663567185 0.0096779476 0.1047850000 396840132 0 402718720 -0.1386834383 0.2734379768 0.6773614883 738 29.4800000000 0.0386796780 0.0250669216 0.0663567185 0.0096736349 0.0732000000 400608716 0 402718720 -0.1487446427 0.2769475579 0.6852372289 739 29.5200000000 0.0376133397 0.0250838991 0.0663567185 0.0096864251 0.0511930000 400494760 0 402718720 -0.1562803984 0.2791012824 0.6946802735 740 29.5600000000 0.0387038626 0.0251023045 0.0663567185 0.0097129778 0.0984630000 400423115 0 402718720 -0.1656538248 0.2907403111 0.7138005495 741 29.6000000000 0.0372268781 0.0251186669 0.0663567185 0.0097326947 0.0313320000 392895368 0 402718720 -0.1744803190 0.2931029797 0.7219946384 742 29.6400000000 0.0376563482 0.0251355641 0.0663567185 0.0097460678 0.0296450000 392895000 0 402718720 -0.1787213087 0.2980765104 0.7323833704 743 29.6800000000 0.0375740938 0.0251523050 0.0663567185 0.0097434604 0.0289460000 392894200 0 402718720 -0.1837705672 0.2991468310 0.7408283949 744 29.7200000000 0.0384965427 0.0251702408 0.0663567185 0.0097378612 0.0276350000 392895716 0 402718720 -0.1876043677 0.3020547330 0.7475364208 745 29.7600000000 0.0396108180 0.0251896242 0.0663567185 0.0097347911 0.0272230000 392896284 0 402718720 -0.1926741004 0.3055195808 0.7529525757 746 29.8000000000 0.0396235324 0.0252089726 0.0663567185 0.0097290608 0.0254970000 392895000 0 402718720 -0.1985414326 0.3075698018 0.7597070932 747 29.8400000000 0.0383321531 0.0252265404 0.0663567185 0.0097233367 0.0250580000 392899364 0 402718720 -0.2021043301 0.3094569147 0.7658110261 748 29.8800000000 0.0408464111 0.0252474226 0.0663567185 0.0097172896 0.0245020000 392901528 0 402718720 -0.2079623938 0.3150444925 0.7701953650 749 29.9200000000 0.0402313173 0.0252674278 0.0663567185 0.0097127560 0.0240600000 392902840 0 402718720 -0.2122034729 0.3174769282 0.7763224244 750 29.9600000000 0.0384827107 0.0252850482 0.0663567185 0.0097084200 0.0281040000 393482196 0 402718720 -0.2158007026 0.3186142445 0.7821055651 751 30.0000000000 0.0387788005 0.0253030159 0.0663567185 0.0097036233 0.0860710000 393590452 0 402718720 -0.2193636000 0.3212428093 0.7871083021 752 30.0400000000 0.0376740955 0.0253194668 0.0663567185 0.0096999513 0.0702780000 397787324 0 402718720 -0.2240328491 0.3226296604 0.7913489938 753 30.0800000000 0.0374669954 0.0253355990 0.0663567185 0.0096969143 0.0419130000 397755208 0 402718720 -0.2277101874 0.3247753084 0.7959709167 754 30.1200000000 0.0324851424 0.0253450811 0.0663567185 0.0097127263 0.0676210000 397677823 0 402718720 -0.2298170626 0.3234884143 0.8044661283 755 30.1600000000 0.0337521844 0.0253562164 0.0663567185 0.0097167326 0.0285220000 393531100 0 402718720 -0.2345031202 0.3257083595 0.8062334061 756 30.2000000000 0.0312639251 0.0253640308 0.0663567185 0.0097294977 0.0285520000 393537372 0 402718720 -0.2374339998 0.3264973164 0.8117687702 757 30.2400000000 0.0341496505 0.0253756366 0.0663567185 0.0097258936 0.0281590000 393538236 0 402718720 -0.2436223328 0.3316902220 0.8121654987 758 30.2800000000 0.0332470164 0.0253860210 0.0663567185 0.0097271835 0.0268950000 393538124 0 402718720 -0.2474795282 0.3328710198 0.8167135715 759 30.3200000000 0.0357073024 0.0253996196 0.0663567185 0.0097322687 0.0269940000 393541780 0 402718720 -0.2527253032 0.3380764127 0.8190770745 760 30.3600000000 0.0358157754 0.0254133250 0.0663567185 0.0097403817 0.0267060000 393542156 0 402718720 -0.2601894736 0.3429806232 0.8219769001 761 30.4000000000 0.0370770134 0.0254286518 0.0663567185 0.0097423742 0.0270290000 393547364 0 402718720 -0.2657439411 0.3476979733 0.8244746923 762 30.4400000000 0.0330085792 0.0254385992 0.0663567185 0.0097506242 0.0255520000 393547944 0 402718720 -0.2714414895 0.3473004997 0.8276542425 763 30.4800000000 0.0359450243 0.0254523691 0.0663567185 0.0097449050 0.0253450000 393553012 0 402718720 -0.2778501809 0.3545199931 0.8302108049 764 30.5200000000 0.0369849391 0.0254674641 0.0663567185 0.0097416166 0.0254980000 393559452 0 402718720 -0.2861315608 0.3590432107 0.8311746120 765 30.5600000000 0.0365921147 0.0254820061 0.0663567185 0.0097381160 0.0246450000 393556724 0 402718720 -0.2924438417 0.3629460633 0.8345220089 766 30.6000000000 0.0368393026 0.0254968329 0.0663567185 0.0097351586 0.0245380000 393559780 0 402718720 -0.2997182310 0.3665345907 0.8363528848 767 30.6400000000 0.0381220169 0.0255132934 0.0663567185 0.0097303182 0.0238520000 393562516 0 402718720 -0.3094649911 0.3716239929 0.8370850086 768 30.6800000000 0.0377371833 0.0255292099 0.0663567185 0.0097298129 0.0240140000 393563120 0 402718720 -0.3175918162 0.3750547767 0.8397407532 769 30.7200000000 0.0388456024 0.0255465264 0.0663567185 0.0097292015 0.0237930000 393567800 0 402718720 -0.3278516829 0.3802537620 0.8410036564 770 30.7600000000 0.0384082608 0.0255632299 0.0663567185 0.0097240204 0.0236370000 393569032 0 402718720 -0.3332195878 0.3843454719 0.8444207907 771 30.8000000000 0.0366042107 0.0255775503 0.0663567185 0.0097218414 0.0229440000 393569112 0 402718720 -0.3410460949 0.3857787848 0.8451963663 772 30.8400000000 0.0408427529 0.0255973239 0.0663567185 0.0097164753 0.0269800000 394134440 0 402718720 -0.3496384025 0.3929983377 0.8472037315 773 30.8800000000 0.0406072028 0.0256167416 0.0663567185 0.0097136126 0.0817580000 394155372 0 402718720 -0.3585951030 0.3957707584 0.8487135172 774 30.9200000000 0.0398562364 0.0256351388 0.0663567185 0.0097166759 0.0763960000 397358570 0 402718720 -0.3672372997 0.3973973393 0.8506398797 775 30.9600000000 0.0417337194 0.0256559112 0.0663567185 0.0097152501 0.0454660000 398495703 0 402718720 -0.3745417297 0.4010927379 0.8529349566 776 31.0000000000 0.0414101221 0.0256762130 0.0663567185 0.0097218057 0.0690550000 398447139 0 402718720 -0.3833709657 0.4025784731 0.8540185690 777 31.0400000000 0.0417170115 0.0256968575 0.0663567185 0.0097257825 0.0268610000 394166684 0 402718720 -0.3898444176 0.4062855542 0.8566607237 778 31.0800000000 0.0416487865 0.0257173613 0.0663567185 0.0097272800 0.0260980000 394166780 0 402718720 -0.4002819955 0.4094511271 0.8566592932 779 31.1200000000 0.0411394686 0.0257371586 0.0663567185 0.0097229622 0.0271320000 394170476 0 402718720 -0.4059728980 0.4111137092 0.8589552641 780 31.1600000000 0.0417472869 0.0257576844 0.0663567185 0.0097212884 0.0267310000 394171828 0 402718720 -0.4151913524 0.4141348898 0.8590811491 781 31.2000000000 0.0419929400 0.0257784722 0.0663567185 0.0097173816 0.0261150000 394176552 0 402718720 -0.4234373271 0.4166969657 0.8595938683 782 31.2400000000 0.0419157669 0.0257991081 0.0663567185 0.0097117723 0.0266760000 394177212 0 402718720 -0.4301084280 0.4182023108 0.8616840839 783 31.2800000000 0.0418404378 0.0258195951 0.0663567185 0.0097060485 0.0257280000 394178776 0 402718720 -0.4369326234 0.4197430909 0.8630006909 784 31.3200000000 0.0421723984 0.0258404533 0.0663567185 0.0096999265 0.0261270000 394182260 0 402718720 -0.4426910281 0.4212018549 0.8642805815 785 31.3600000000 0.0424627028 0.0258616282 0.0663567185 0.0096940437 0.0256910000 394185696 0 402718720 -0.4483796954 0.4220961928 0.8656463027 786 31.4000000000 0.0427297615 0.0258830889 0.0663567185 0.0096891968 0.0259430000 394189668 0 402718720 -0.4566156268 0.4229182005 0.8650560975 787 31.4400000000 0.0427878872 0.0259045689 0.0663567185 0.0096847789 0.0254910000 394189808 0 402718720 -0.4618141055 0.4251460731 0.8669709563 788 31.4800000000 0.0429985933 0.0259262619 0.0663567185 0.0096810347 0.0261040000 394193448 0 402718720 -0.4662679136 0.4262546301 0.8688424826 789 31.5200000000 0.0427901559 0.0259476356 0.0663567185 0.0096771739 0.0255560000 394196564 0 402718720 -0.4716448784 0.4263255000 0.8706374764 790 31.5600000000 0.0434669442 0.0259698119 0.0663567185 0.0096720002 0.0251720000 394197644 0 402718720 -0.4773040712 0.4271218181 0.8715190291 791 31.6000000000 0.0432272926 0.0259916292 0.0663567185 0.0096662858 0.0246770000 394197600 0 402718720 -0.4826729298 0.4269388318 0.8719431162 792 31.6400000000 0.0432342514 0.0260134002 0.0663567185 0.0096603108 0.0249340000 394202892 0 402718720 -0.4858513772 0.4264681339 0.8733875155 793 31.6800000000 0.0441264883 0.0260362415 0.0663567185 0.0096558373 0.0249820000 394205884 0 402718720 -0.4907502234 0.4268158078 0.8747341633 794 31.7200000000 0.0438104942 0.0260586272 0.0663567185 0.0096554456 0.0253260000 394207496 0 402718720 -0.4931488633 0.4255040884 0.8767884374 795 31.7600000000 0.0437451079 0.0260808743 0.0663567185 0.0096595522 0.0242930000 394207224 0 402718720 -0.4958816469 0.4242410660 0.8777266741 796 31.8000000000 0.0435706414 0.0261028464 0.0663567185 0.0096713048 0.0237300000 394205064 0 402718720 -0.4991003275 0.4231552482 0.8798726797 797 31.8400000000 0.0438716374 0.0261251410 0.0663567185 0.0096865152 0.0242110000 394210616 0 402718720 -0.5004454851 0.4223465025 0.8819302320 798 31.8800000000 0.0445783213 0.0261482653 0.0663567185 0.0096996700 0.0238540000 394211568 0 402718720 -0.5041913390 0.4214721918 0.8822781444 799 31.9200000000 0.0443454757 0.0261710402 0.0663567185 0.0097041006 0.0237660000 394215112 0 402718720 -0.5073537230 0.4197291136 0.8843275309 800 31.9600000000 0.0445297100 0.0261939886 0.0663567185 0.0097059427 0.0240410000 394219024 0 402718720 -0.5110523105 0.4174203277 0.8837440014 801 32.0000000000 0.0438975096 0.0262160903 0.0663567185 0.0097152817 0.0238690000 394218548 0 402718720 -0.5118219852 0.4153853655 0.8870624304 802 32.0400000000 0.0444583818 0.0262388363 0.0663567185 0.0097170681 0.0243340000 394223028 0 402718720 -0.5136888623 0.4136962295 0.8883014917 803 32.0800000000 0.0445871502 0.0262616861 0.0663567185 0.0097239227 0.0235020000 394224212 0 402718720 -0.5154324174 0.4135979712 0.8907985091 804 32.1199999990 0.0439057574 0.0262836314 0.0663567185 0.0097342845 0.0240960000 394229520 0 402718720 -0.5150187016 0.4120569825 0.8932007551 805 32.1600000000 0.0456053466 0.0263076335 0.0663567185 0.0097445309 0.0244980000 394230872 0 402718720 -0.5181492567 0.4117933214 0.8935728073 806 32.2000000000 0.0438819639 0.0263294379 0.0663567185 0.0097551773 0.0284530000 394765872 0 402718720 -0.5179189444 0.4087956250 0.8968570828 807 32.2400000000 0.0448014326 0.0263523276 0.0663567185 0.0097663981 0.0835330000 394810852 0 402718720 -0.5190373063 0.4065544009 0.8982101679 808 32.2800000000 0.0445284694 0.0263748229 0.0663567185 0.0097716301 0.0749900000 397538748 0 402718720 -0.5207237005 0.4040142298 0.9007337093 809 32.3200000000 0.0444972776 0.0263972239 0.0663567185 0.0097744857 0.0602700000 399378476 0 402718720 -0.5201712847 0.4002879858 0.9033774734 810 32.3600000000 0.0454386845 0.0264207319 0.0663567185 0.0097757455 0.0743920000 399355491 0 402718720 -0.5228611231 0.3983037472 0.9032738805 811 32.4000000000 0.0451080203 0.0264437742 0.0663567185 0.0097721811 0.0264900000 394818544 0 402718720 -0.5232416391 0.3942817450 0.9057905674 812 32.4399999990 0.0452343971 0.0264669153 0.0663567185 0.0097698794 0.0269110000 394820080 0 402718720 -0.5239362121 0.3909822702 0.9082210660 813 32.4800000000 0.0448667705 0.0264895474 0.0663567185 0.0097676602 0.0262630000 394821588 0 402718720 -0.5238286257 0.3883226514 0.9120485783 814 32.5200000000 0.0451885127 0.0265125191 0.0663567185 0.0097657662 0.0262820000 394825424 0 402718720 -0.5245834589 0.3858436346 0.9148774743 815 32.5600000000 0.0445995666 0.0265347118 0.0663567185 0.0097612371 0.0253960000 394828404 0 402718720 -0.5264620781 0.3822890520 0.9175071120 816 32.6000000000 0.0442200936 0.0265563850 0.0663567185 0.0097569512 0.0256450000 394832172 0 402718720 -0.5248391628 0.3774505854 0.9207962155 817 32.6400000000 0.0440623611 0.0265778122 0.0663567185 0.0097538649 0.0252290000 394832956 0 402718720 -0.5241057277 0.3740761876 0.9247322679 818 32.6800000000 0.0437816791 0.0265988438 0.0663567185 0.0097482399 0.0249890000 394837300 0 402718720 -0.5265788436 0.3699958920 0.9273076653 819 32.7200000000 0.0447020940 0.0266209479 0.0663567185 0.0097437252 0.0243850000 394838576 0 402718720 -0.5280672908 0.3690303564 0.9312381148 820 32.7599999990 0.0435911343 0.0266416432 0.0663567185 0.0097383039 0.0241250000 394841820 0 402718720 -0.5299304724 0.3655321598 0.9355754852 821 32.7999999990 0.0438905731 0.0266626529 0.0663567185 0.0097405172 0.0239770000 394843680 0 402718720 -0.5290319324 0.3640178442 0.9415117502 822 32.8400000000 0.0438774787 0.0266835955 0.0663567185 0.0097586503 0.0241690000 394847256 0 402718720 -0.5293270946 0.3612023890 0.9457866549 823 32.8800000000 0.0453603826 0.0267062891 0.0663567185 0.0097655787 0.0240540000 394850680 0 402718720 -0.5309190154 0.3605614305 0.9501154423 824 32.9200000000 0.0452941582 0.0267288472 0.0663567185 0.0097677248 0.0238200000 394852112 0 402718720 -0.5311490297 0.3601157665 0.9573163986 825 32.9600000000 0.0466735698 0.0267530226 0.0663567185 0.0097847305 0.0238320000 394856796 0 402718720 -0.5297037959 0.3587062359 0.9620469809 826 33.0000000000 0.0434652381 0.0267732553 0.0663567185 0.0097826200 0.0231640000 394857152 0 402718720 -0.5329071879 0.3544009924 0.9690185785 827 33.0400000000 0.0455520190 0.0267959624 0.0663567185 0.0098005518 0.0230290000 394861312 0 402718720 -0.5329825878 0.3530642986 0.9737486839 828 33.0800000000 0.0460127145 0.0268191710 0.0663567185 0.0098205830 0.0294360000 395599864 0 402718720 -0.5307669640 0.3499064445 0.9798228145 829 33.1199999990 0.0466009453 0.0268430332 0.0663567185 0.0098367170 0.1008710000 395582196 0 402718720 -0.5320695639 0.3474318981 0.9860917926 830 33.1600000000 0.0471308976 0.0268674764 0.0663567185 0.0098469984 0.0868170000 397413916 0 402718720 -0.5337654948 0.3443176150 0.9909884930 831 33.2000000000 0.0482213870 0.0268931731 0.0663567185 0.0098622683 0.0632670000 401020156 0 402718720 -0.5340036154 0.3406456411 0.9979692101 832 33.2400000000 0.0475773960 0.0269180339 0.0663567185 0.0098674424 0.0411660000 400838780 0 402718720 -0.5335721970 0.3360998929 1.0049322844 833 33.2800000000 0.0458167084 0.0269407214 0.0663567185 0.0098658573 0.0839410000 400766615 0 402718720 -0.5335388184 0.3311767578 1.0126279593 834 33.3200000000 0.0460936874 0.0269636866 0.0663567185 0.0098676740 0.0290860000 395590024 0 402718720 -0.5357103944 0.3261828423 1.0183125734 835 33.3600000000 0.0470457673 0.0269877370 0.0663567185 0.0098735865 0.0302690000 395593000 0 402718720 -0.5359047651 0.3245099783 1.0243895054 836 33.4000000000 0.0454006903 0.0270097621 0.0663567185 0.0098746185 0.0296450000 395594720 0 402718720 -0.5372758508 0.3196799755 1.0322536230 837 33.4399999990 0.0472491048 0.0270339429 0.0663567185 0.0098886477 0.0296260000 395599092 0 402718720 -0.5368392467 0.3186937571 1.0376830101 838 33.4800000000 0.0456376858 0.0270561430 0.0663567185 0.0099069259 0.0298710000 395603248 0 402718720 -0.5384299159 0.3122319877 1.0436044931 839 33.5200000000 0.0457959697 0.0270784789 0.0663567185 0.0099279375 0.0283360000 395604204 0 402718720 -0.5385124683 0.3102225959 1.0507839918 840 33.5600000000 0.0449133851 0.0270997110 0.0663567185 0.0099409024 0.0282410000 395607508 0 402718720 -0.5405436158 0.3071105182 1.0561876297 841 33.6000000000 0.0466732718 0.0271229851 0.0663567185 0.0099421663 0.0284580000 395611988 0 402718720 -0.5404826999 0.3065401018 1.0605968237 842 33.6400000000 0.0451942757 0.0271444475 0.0663567185 0.0099386082 0.0271520000 395607356 0 402718720 -0.5433797836 0.3034204841 1.0669753551 843 33.6800000000 0.0462331101 0.0271670912 0.0663567185 0.0099370897 0.0277230000 395612124 0 402718720 -0.5448311567 0.3009282053 1.0713858604 844 33.7200000000 0.0460138768 0.0271894215 0.0663567185 0.0099392716 0.0272310000 395614516 0 402718720 -0.5451397300 0.2959083915 1.0765616894 845 33.7599999990 0.0453297235 0.0272108893 0.0663567185 0.0099460574 0.0272840000 395616912 0 402718720 -0.5460537672 0.2920159101 1.0814824104 846 33.7999999990 0.0470010191 0.0272342819 0.0663567185 0.0099496177 0.0273890000 395620012 0 402718720 -0.5470340252 0.2908142209 1.0838345289 847 33.8400000000 0.0454248227 0.0272557583 0.0663567185 0.0099472087 0.0273850000 395618524 0 402718720 -0.5491830111 0.2848979831 1.0885790586 848 33.8800000000 0.0464744084 0.0272784219 0.0663567185 0.0099426188 0.0273990000 395623264 0 402718720 -0.5476891994 0.2827726603 1.0934166908 849 33.9200000000 0.0468337387 0.0273014552 0.0663567185 0.0099379274 0.0274440000 395625752 0 402718720 -0.5509753823 0.2776692808 1.0961595774 850 33.9600000000 0.0470125973 0.0273246448 0.0663567185 0.0099324082 0.0264970000 395625276 0 402718720 -0.5509728789 0.2741052806 1.0994796753 851 34.0000000000 0.0467307642 0.0273474487 0.0663567185 0.0099270765 0.0261830000 395627376 0 402718720 -0.5526781678 0.2704789340 1.1019405127 852 34.0400000000 0.0463775918 0.0273697845 0.0663567185 0.0099213398 0.0269330000 395633008 0 402718720 -0.5525432229 0.2655039132 1.1073422432 853 34.0800000000 0.0476331450 0.0273935399 0.0663567185 0.0099177021 0.0265770000 395634696 0 402718720 -0.5534471273 0.2627460957 1.1094062328 854 34.1199999990 0.0465202667 0.0274159366 0.0663567185 0.0099140676 0.0310110000 396280404 0 402718720 -0.5541321039 0.2591745853 1.1131905317 855 34.1600000000 0.0473708510 0.0274392757 0.0663567185 0.0099124226 0.1072140000 396335444 0 402718720 -0.5547297597 0.2568750381 1.1167818308 856 34.2000000000 0.0477505513 0.0274630038 0.0663567185 0.0099113746 0.0921700000 396363340 0 402718720 -0.5543266535 0.2544346452 1.1194300652 857 34.2400000000 0.0474096090 0.0274862787 0.0663567185 0.0099063705 0.0686550000 402028744 0 402718720 -0.5563828945 0.2530104518 1.1219609976 858 34.2800000000 0.0489613488 0.0275113079 0.0663567185 0.0099015922 0.0454350000 402012960 0 402718720 -0.5562095046 0.2524413466 1.1242582798 859 34.3200000000 0.0453289077 0.0275320502 0.0663567185 0.0098978965 0.0880380000 401939315 0 402718720 -0.5566250086 0.2425157130 1.1259467602 860 34.3600000000 0.0461927839 0.0275537487 0.0663567185 0.0098924309 0.0303530000 396340476 0 402718720 -0.5578153133 0.2385224253 1.1270376444 861 34.4000000000 0.0458752103 0.0275750280 0.0663567185 0.0098870039 0.0287160000 396340584 0 402718720 -0.5576155186 0.2350631654 1.1298612356 862 34.4400000000 0.0445336811 0.0275947016 0.0663567185 0.0098814484 0.0298070000 396342224 0 402718720 -0.5583082438 0.2299715877 1.1324896812 863 34.4800000000 0.0440429449 0.0276137610 0.0663567185 0.0098758499 0.0286810000 396346196 0 402718720 -0.5572824478 0.2234057039 1.1339381933 864 34.5200000000 0.0456157103 0.0276345966 0.0663567185 0.0098713209 0.0280550000 396346332 0 402718720 -0.5566154718 0.2218573391 1.1357896328 865 34.5600000000 0.0455228277 0.0276552766 0.0663567185 0.0098661517 0.0283200000 396348112 0 402718720 -0.5594354272 0.2204852253 1.1366198063 866 34.6000000000 0.0463200510 0.0276768295 0.0663567185 0.0098617466 0.0273770000 396348848 0 402718720 -0.5596823692 0.2202887684 1.1387790442 867 34.6400000000 0.0458975695 0.0276978453 0.0663567185 0.0098578710 0.0272350000 396355044 0 402718720 -0.5599087477 0.2169662416 1.1397175789 868 34.6800000000 0.0469282269 0.0277200001 0.0663567185 0.0098532758 0.0273450000 396355964 0 402718720 -0.5599569082 0.2143104523 1.1405147314 869 34.7200000000 0.0463422164 0.0277414296 0.0663567185 0.0098482093 0.0269650000 396361148 0 402718720 -0.5604843497 0.2101030052 1.1406241655 870 34.7600000000 0.0448318087 0.0277610737 0.0663567185 0.0098428175 0.0271570000 396362868 0 402718720 -0.5612367988 0.2059786916 1.1411784887 871 34.8000000000 0.0449536890 0.0277808127 0.0663567185 0.0098372661 0.0263140000 396364048 0 402718720 -0.5627054572 0.2046181411 1.1427572966 872 34.8400000000 0.0445242822 0.0278000139 0.0663567185 0.0098324245 0.0274450000 396368268 0 402718720 -0.5627381802 0.2012816817 1.1440540552 873 34.8800000000 0.0453924425 0.0278201656 0.0663567185 0.0098274563 0.0270560000 396370476 0 402718720 -0.5647517443 0.1997714043 1.1440886259 874 34.9200000000 0.0457335375 0.0278406614 0.0663567185 0.0098226798 0.0263100000 396371072 0 402718720 -0.5639409423 0.1992250085 1.1462771893 875 34.9600000000 0.0453084484 0.0278606246 0.0663567185 0.0098175903 0.0269290000 396374584 0 402718720 -0.5661780834 0.1988460869 1.1473127604 876 35.0000000000 0.0456501618 0.0278809323 0.0663567185 0.0098130286 0.0270560000 396376856 0 402718720 -0.5663191080 0.1983065903 1.1486159563 877 35.0400000000 0.0460219681 0.0279016176 0.0663567185 0.0098074919 0.0264160000 396379004 0 402718720 -0.5668739080 0.1985757798 1.1503366232 878 35.0800000000 0.0445059650 0.0279205292 0.0663567185 0.0098023544 0.0263780000 396379968 0 402718720 -0.5685064197 0.1972881407 1.1518750191 879 35.1200000000 0.0458013117 0.0279408714 0.0663567185 0.0097971649 0.0267490000 396383572 0 402718720 -0.5686137676 0.1977771074 1.1534365416 880 35.1600000000 0.0458450578 0.0279612170 0.0663567185 0.0097916100 0.0263790000 396385396 0 402718720 -0.5693668127 0.1988641769 1.1550835371 881 35.2000000000 0.0458269715 0.0279814960 0.0663567185 0.0097874467 0.0266260000 396389336 0 402718720 -0.5705240965 0.1985060126 1.1558768749 882 35.2400000000 0.0439751223 0.0279996294 0.0663567185 0.0097834847 0.0263780000 396391068 0 402718720 -0.5704808831 0.1925628334 1.1563619375 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:25:26 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0253950000 198738908 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0060497462 0.0030248731 0.0060497462 0.0064463918 0.0239650000 199524134 95654128 760807424 -0.0008780303 -0.0012178377 -0.0001706580 3 0.0800000000 0.0096953409 0.0052483624 0.0096953409 0.0049059559 0.0209660000 199373666 95654128 760807424 -0.0010523738 -0.0070183724 -0.0013676159 4 0.1200000000 0.0045009982 0.0050615213 0.0096953409 0.0066517178 0.0301800000 199374462 95654128 760807424 -0.0009397154 -0.0027233711 -0.0007470614 5 0.1600000000 0.0026911977 0.0045874566 0.0096953409 0.0067403485 0.0198060000 199377622 95654128 760807424 0.0032244746 -0.0043270830 -0.0006665161 6 0.2000000000 0.0039746398 0.0044853205 0.0096953409 0.0062225673 0.0182480000 199379230 95654128 760807424 -0.0014669911 -0.0070265811 0.0018310461 7 0.2400000000 0.0044925380 0.0044863515 0.0096953409 0.0059239299 0.0179350000 199381838 95654128 760807424 -0.0019187463 -0.0080926828 0.0039794650 8 0.2800000000 0.0061262650 0.0046913407 0.0096953409 0.0054872193 0.0170970000 199384446 95654128 760807424 -0.0029230067 -0.0045495136 0.0042556911 9 0.3200000000 0.0107976170 0.0053698159 0.0107976170 0.0051717517 0.0204390000 199386158 95654128 760807424 -0.0071431012 -0.0024934155 0.0047728200 10 0.3600000000 0.0108827120 0.0059211055 0.0108827120 0.0049018398 0.0175250000 199390366 95654128 760807424 -0.0062207761 -0.0069856350 0.0064257323 11 0.4000000000 0.0110362647 0.0063861200 0.0110362647 0.0047355060 0.0171270000 199392974 95654128 760807424 -0.0060840631 -0.0089186076 0.0076925480 12 0.4400000000 0.0118381567 0.0068404564 0.0118381567 0.0047106230 0.0287230000 199393782 95654128 760807424 -0.0057332567 -0.0106529100 0.0082174987 13 0.4800000000 0.0144480206 0.0074256536 0.0144480206 0.0045781426 0.0226970000 199397618 95654128 760807424 -0.0086134346 -0.0058507370 0.0081017157 14 0.5200000000 0.0185418390 0.0082196668 0.0185418390 0.0044692107 0.0181310000 199400226 95654128 760807424 -0.0123227816 -0.0048453701 0.0095936302 15 0.5600000000 0.0191221144 0.0089464967 0.0191221144 0.0043999624 0.0171230000 199401034 95654128 760807424 -0.0110107316 -0.0078883320 0.0115060620 16 0.6000000000 0.0205922760 0.0096743579 0.0205922760 0.0042762669 0.0171350000 199403642 95654128 760807424 -0.0117928097 -0.0083367620 0.0124819549 17 0.6400000000 0.0209578164 0.0103380907 0.0209578164 0.0042927793 0.0171360000 199406058 95654128 760807424 -0.0129461791 -0.0069401292 0.0121296095 18 0.6800000000 0.0228265971 0.0110318967 0.0228265971 0.0042004220 0.0171540000 199411866 95654128 760807424 -0.0139405942 -0.0067751678 0.0128853805 19 0.7200000000 0.0231229253 0.0116682666 0.0231229253 0.0041137106 0.0170230000 199414474 95654128 760807424 -0.0117614055 -0.0077140937 0.0139208268 20 0.7600000000 0.0232820027 0.0122489534 0.0232820027 0.0040753901 0.0161550000 199415282 95654128 760807424 -0.0121504553 -0.0056657456 0.0132102938 21 0.8000000000 0.0237098038 0.0127947082 0.0237098038 0.0040545019 0.0165780000 199418090 95654128 760807424 -0.0142515246 -0.0018977216 0.0128063960 22 0.8400000000 0.0250555966 0.0133520213 0.0250555966 0.0040186082 0.0161180000 199420618 95654128 760807424 -0.0162137374 0.0007335951 0.0123082837 23 0.8800000000 0.0261386037 0.0139079596 0.0261386037 0.0039474974 0.0160760000 199421426 95654128 760807424 -0.0164604746 0.0019352607 0.0125871263 24 0.9200000000 0.0274126902 0.0144706568 0.0274126902 0.0038716328 0.0161090000 199424018 95654128 760807424 -0.0168668926 0.0039058439 0.0123924874 25 0.9600000000 0.0263647176 0.0149464192 0.0274126902 0.0038001610 0.0161140000 199426826 95654128 760807424 -0.0144935781 0.0028019883 0.0128986156 26 1.0000000000 0.0292226318 0.0154955043 0.0292226318 0.0037735918 0.0160990000 199427634 95654128 760807424 -0.0180307068 0.0046233712 0.0120598152 27 1.0400000000 0.0304702707 0.0160501253 0.0304702707 0.0037235258 0.0202000000 199430242 95654128 760807424 -0.0192045178 0.0051568141 0.0123110656 28 1.0800000000 0.0312955044 0.0165946031 0.0312955044 0.0036849832 0.0164970000 199432850 95654128 760807424 -0.0177739095 0.0047987108 0.0127211325 29 1.1200000000 0.0309526026 0.0170897065 0.0312955044 0.0039427466 0.0160480000 199433842 95654128 760807424 -0.0159983225 0.0046532452 0.0134354103 30 1.1600000000 0.0315030143 0.0175701501 0.0315030143 0.0041767506 0.0160610000 199436450 95654128 760807424 -0.0169938207 0.0026329334 0.0147194639 31 1.2000000000 0.0321831517 0.0180415373 0.0321831517 0.0045596391 0.0160480000 199437242 95654128 760807424 -0.0153562445 0.0001790735 0.0165475085 32 1.2400000000 0.0341271758 0.0185442135 0.0341271758 0.0048915057 0.0161240000 199439850 95654128 760807424 -0.0149182156 0.0046163015 0.0169594362 33 1.2800000000 0.0334835909 0.0189969219 0.0341271758 0.0050881562 0.0160480000 199445474 95654128 760807424 -0.0141125415 0.0071344068 0.0160825755 34 1.3200000000 0.0334265754 0.0194213234 0.0341271758 0.0051730451 0.0160980000 199452682 95654128 760807424 -0.0142337512 0.0087750489 0.0154025936 35 1.3600000000 0.0352904685 0.0198747276 0.0352904685 0.0055581900 0.0160850000 199455290 95654128 760807424 -0.0153970132 0.0114752725 0.0155299995 36 1.4000000000 0.0377416201 0.0203710302 0.0377416201 0.0059428813 0.0160940000 199457866 95654128 760807424 -0.0159108732 0.0120869763 0.0161861293 37 1.4400000000 0.0342870578 0.0207471390 0.0377416201 0.0066342828 0.0160680000 199458874 95654128 760807424 -0.0118461624 0.0091588739 0.0175112300 38 1.4800000000 0.0350003131 0.0211222225 0.0377416201 0.0083594842 0.0160940000 199461482 95654128 760807424 -0.0100512011 0.0109830471 0.0180841815 39 1.5200000000 0.0384349078 0.0215661376 0.0384349078 0.0085359638 0.0167160000 199464090 95654128 760807424 -0.0108595006 0.0150015987 0.0176346805 40 1.5600000000 0.0394145101 0.0220123469 0.0394145101 0.0086381470 0.0204050000 199464898 95654128 760807424 -0.0099458564 0.0165409390 0.0169333331 41 1.6000000000 0.0395726822 0.0224406477 0.0395726822 0.0088348716 0.0165210000 199467706 95654128 760807424 -0.0088553801 0.0126941614 0.0183934476 42 1.6400000000 0.0399727337 0.0228580783 0.0399727337 0.0089321173 0.0189890000 199468514 95654128 760807424 -0.0070242630 0.0139586236 0.0175045133 43 1.6800000000 0.0399471112 0.0232554977 0.0399727337 0.0091382783 0.0163860000 199472074 95654128 760807424 -0.0058290870 0.0158003159 0.0171590764 44 1.7200000000 0.0396876484 0.0236289557 0.0399727337 0.0094750278 0.0160760000 199643310 95654128 760807424 -0.0020551342 0.0197893512 0.0176398139 45 1.7600000000 0.0366451740 0.0239182050 0.0399727337 0.0098516559 0.0199300000 199644318 95654128 760807424 0.0023435145 0.0153470719 0.0195974223 46 1.8000000000 0.0416656248 0.0243040185 0.0416656248 0.0110628904 0.0168640000 199646926 95654128 760807424 0.0249491483 0.0158280078 0.0177066587 47 1.8400000000 0.0546722338 0.0249501507 0.0546722338 0.0109625124 0.0160800000 199649534 95654128 760807424 0.0729633868 0.0173451658 0.0092986356 48 1.8800000000 0.0515151173 0.0255035875 0.0546722338 0.0111039303 0.0161650000 199650342 95654128 760807424 0.0774338692 0.0140218269 0.0096437428 49 1.9200000000 0.0494206250 0.0259916903 0.0546722338 0.0112714938 0.0207760000 199653134 95654128 760807424 0.0822951943 0.0132945217 0.0087953107 50 1.9600000000 0.0513997823 0.0264998521 0.0546722338 0.0113789752 0.0167570000 199655742 95654128 760807424 0.0813292041 0.0108403005 0.0101484703 51 2.0000000000 0.0473328605 0.0269083425 0.0546722338 0.0114695546 0.0161580000 199656550 95654128 760807424 0.0868713856 0.0066501992 0.0088846628 52 2.0400000000 0.0498329289 0.0273491999 0.0546722338 0.0115142036 0.0161880000 199659142 95654128 760807424 0.0877109319 0.0069963015 0.0085640792 53 2.0800000000 0.0465298966 0.0277110999 0.0546722338 0.0115832037 0.0161080000 199660150 95654128 760807424 0.0910590068 0.0024784976 0.0086564841 54 2.1200000000 0.0437422357 0.0280079728 0.0546722338 0.0116468373 0.0160710000 199662758 95654128 760807424 0.0965952873 0.0017706247 0.0067218514 55 2.1600000000 0.0411121659 0.0282462308 0.0546722338 0.0117179507 0.0161100000 199665350 95654128 760807424 0.1023643911 0.0008829430 0.0080611920 56 2.2000000000 0.0443087071 0.0285330608 0.0546722338 0.0117351391 0.0160760000 199667322 95654128 760807424 0.0998930633 -0.0014860746 0.0082028313 57 2.2400000000 0.0409524366 0.0287509445 0.0546722338 0.0119118817 0.0167990000 199838738 95654128 760807424 0.1021631286 -0.0076740077 0.0092868339 58 2.2800000000 0.0448981337 0.0290293444 0.0546722338 0.0120245737 0.0161730000 199841346 95654128 760807424 0.1003038213 -0.0076279072 0.0094202776 59 2.3200000000 0.0433013514 0.0292712428 0.0546722338 0.0123071862 0.0160910000 199842138 95654128 760807424 0.1032436043 -0.0124129672 0.0100158881 60 2.3600000000 0.0431981198 0.0295033574 0.0546722338 0.0124974675 0.0161060000 199844746 95654128 760807424 0.1064315438 -0.0129808523 0.0088150874 61 2.4000000000 0.0454804450 0.0297652769 0.0546722338 0.0126919161 0.0160610000 199847554 95654128 760807424 0.1060679853 -0.0086942166 0.0059794551 62 2.4400000000 0.0458678044 0.0300249951 0.0546722338 0.0128436283 0.0161830000 199848362 95654128 760807424 0.1091129035 -0.0081108939 0.0035342646 63 2.4800000000 0.0469171815 0.0302931250 0.0546722338 0.0130383124 0.0206240000 199850954 95654128 760807424 0.1115673706 -0.0084412312 0.0036286744 64 2.5200000000 0.0477234125 0.0305654732 0.0546722338 0.0131589314 0.0166710000 199853562 95654128 760807424 0.1143387407 -0.0121807447 0.0034259651 65 2.5600000000 0.0504924692 0.0308720424 0.0546722338 0.0132424653 0.0243500000 199860202 95654128 760807424 0.1152406558 -0.0149172358 0.0030420255 66 2.6000000000 0.0529864393 0.0312071090 0.0546722338 0.0133250757 0.0172060000 199875594 95654128 760807424 0.1173096672 -0.0191921610 0.0024876315 67 2.6400000000 0.0558532178 0.0315749614 0.0558532178 0.0134577268 0.0160450000 199876402 95654128 760807424 0.1181334555 -0.0220673252 0.0025799267 68 2.6800000000 0.0608536713 0.0320055307 0.0608536713 0.0135192938 0.0160710000 199879010 95654128 760807424 0.1176569015 -0.0211134963 0.0004523778 69 2.7200000000 0.0612226613 0.0324289673 0.0612226613 0.0136491807 0.0161040000 199881818 95654128 760807424 0.1209185645 -0.0220802166 -0.0006278614 70 2.7600000000 0.0607549734 0.0328336246 0.0612226613 0.0138245830 0.0161420000 199882626 95654128 760807424 0.1233019978 -0.0219500083 -0.0028915526 71 2.8000000000 0.0619764887 0.0332440874 0.0619764887 0.0139050142 0.0161170000 199885234 95654128 760807424 0.1254642308 -0.0220521390 -0.0066754324 72 2.8400000000 0.0628635138 0.0336554684 0.0628635138 0.0141059609 0.0161030000 199887842 95654128 760807424 0.1276826411 -0.0223523900 -0.0068563959 73 2.8800000000 0.0646763071 0.0340804114 0.0646763071 0.0142103809 0.0160790000 199888850 95654128 760807424 0.1281690001 -0.0257382467 -0.0073500094 74 2.9200000000 0.0649579242 0.0344976750 0.0649579242 0.0143143768 0.0161370000 199891458 95654128 760807424 0.1328012496 -0.0284859315 -0.0084177051 75 2.9600000000 0.0621699691 0.0348666390 0.0649579242 0.0144900895 0.0160900000 199894770 95654128 760807424 0.1380715519 -0.0323105492 -0.0078548035 76 3.0000000000 0.0616716258 0.0352193362 0.0649579242 0.0145812704 0.0160510000 200064214 95654128 760807424 0.1442045867 -0.0369111449 -0.0099664731 77 3.0400000000 0.0617400408 0.0355637609 0.0649579242 0.0146937080 0.0163390000 200067022 95654128 760807424 0.1484910846 -0.0424822271 -0.0104965763 78 3.0800000000 0.0641131699 0.0359297790 0.0649579242 0.0147003817 0.0162800000 200067830 95654128 760807424 0.1510502994 -0.0451768488 -0.0132851806 79 3.1200000000 0.0636241585 0.0362803407 0.0649579242 0.0147713381 0.0163230000 200070438 95654128 760807424 0.1565160751 -0.0474494547 -0.0148990098 80 3.1600000000 0.0642525926 0.0366299939 0.0649579242 0.0152386594 0.0162280000 200073046 95654128 760807424 0.1645803303 -0.0486354493 -0.0205699056 81 3.2000000000 0.0624878481 0.0369492266 0.0649579242 0.0152448970 0.0162480000 200074054 95654128 760807424 0.1711040735 -0.0516784713 -0.0235099923 82 3.2400000000 0.0610690936 0.0372433714 0.0649579242 0.0152457702 0.0161820000 200076662 95654128 760807424 0.1759665608 -0.0554257073 -0.0264396202 83 3.2800000000 0.0621720143 0.0375437165 0.0649579242 0.0152951804 0.0195150000 200079270 95654128 760807424 0.1775095761 -0.0535666309 -0.0277686715 84 3.3200000000 0.0604221895 0.0378160792 0.0649579242 0.0152820009 0.0164980000 200080078 95654128 760807424 0.1824109107 -0.0590399504 -0.0295771342 85 3.3600000000 0.0606506765 0.0380847216 0.0649579242 0.0152789154 0.0162240000 200082886 95654128 760807424 0.1850892752 -0.0602474995 -0.0323989093 86 3.4000000000 0.0608067140 0.0383489308 0.0649579242 0.0153199499 0.0162070000 200085494 95654128 760807424 0.1862547398 -0.0588476658 -0.0333543569 87 3.4400000000 0.0577665381 0.0385721217 0.0649579242 0.0153715519 0.0162270000 200086302 95654128 760807424 0.1929424852 -0.0577411689 -0.0356805474 88 3.4800000000 0.0608110428 0.0388248367 0.0649579242 0.0153666786 0.0161800000 200088910 95654128 760807424 0.1949660629 -0.0614278316 -0.0373459607 89 3.5200000000 0.0507586710 0.0389589247 0.0649579242 0.0154195880 0.0196100000 200089902 95654128 760807424 0.2084230632 -0.0596246719 -0.0406087711 90 3.5600000000 0.0436725989 0.0390112989 0.0649579242 0.0154540960 0.0165320000 200092510 95654128 760807424 0.2195774764 -0.0619193017 -0.0429692641 91 3.6000000000 0.0448190905 0.0390751207 0.0649579242 0.0154616912 0.0161980000 200095118 95654128 760807424 0.2210822999 -0.0646245927 -0.0450834818 92 3.6400000000 0.0465651304 0.0391565339 0.0649579242 0.0154407475 0.0162010000 200095926 95654128 760807424 0.2225965559 -0.0656899810 -0.0473472327 93 3.6800000000 0.0449808650 0.0392191611 0.0649579242 0.0154181539 0.0162120000 200098734 95654128 760807424 0.2261926383 -0.0650904179 -0.0486927591 94 3.7200000000 0.0457781442 0.0392889375 0.0649579242 0.0153715204 0.0169330000 200101342 95654128 760807424 0.2286171317 -0.0675768182 -0.0501928516 95 3.7600000000 0.0453252718 0.0393524779 0.0649579242 0.0153332174 0.0162610000 200102150 95654128 760807424 0.2326375544 -0.0681692958 -0.0527563207 96 3.8000000000 0.0456996448 0.0394185942 0.0649579242 0.0152890480 0.0162390000 200104758 95654128 760807424 0.2361774594 -0.0701297447 -0.0546987392 97 3.8400000000 0.0475561135 0.0395024862 0.0649579242 0.0152413374 0.0162180000 200107566 95654128 760807424 0.2361299545 -0.0708450750 -0.0566327870 98 3.8800000000 0.0480600782 0.0395898085 0.0649579242 0.0151899176 0.0162710000 200109958 95654128 760807424 0.2351078689 -0.0705785602 -0.0576584749 99 3.9200000000 0.0468528494 0.0396631726 0.0649579242 0.0151366962 0.0162780000 200281182 95654128 760807424 0.2382274419 -0.0707079619 -0.0611712299 100 3.9600000000 0.0425713807 0.0396922547 0.0649579242 0.0151029920 0.0162420000 200283790 95654128 760807424 0.2424548417 -0.0682906955 -0.0635677055 101 4.0000000000 0.0447536521 0.0397423675 0.0649579242 0.0150429996 0.0162630000 200284798 95654128 760807424 0.2420616746 -0.0671727061 -0.0655555725 102 4.0400000000 0.0417533554 0.0397620831 0.0649579242 0.0150192135 0.0209960000 200287406 95654128 760807424 0.2461344898 -0.0631215945 -0.0674248561 103 4.0800000000 0.0422264747 0.0397860092 0.0649579242 0.0149638425 0.0168930000 200288214 95654128 760807424 0.2473556399 -0.0639057979 -0.0703676715 104 4.1200000000 0.0427873656 0.0398148684 0.0649579242 0.0149135569 0.0163120000 200290822 95654128 760807424 0.2488052398 -0.0618018210 -0.0700662360 105 4.1600000000 0.0432986803 0.0398480476 0.0649579242 0.0148558033 0.0162750000 200293630 95654128 760807424 0.2501283288 -0.0611279383 -0.0736183003 106 4.2000000000 0.0402046181 0.0398514114 0.0649579242 0.0148091368 0.0192930000 200294422 95654128 760807424 0.2541663349 -0.0584429502 -0.0755131543 107 4.2400000000 0.0458017923 0.0399070225 0.0649579242 0.0147426320 0.0165340000 200297030 95654128 760807424 0.2474661469 -0.0554846451 -0.0760314986 108 4.2800000000 0.0485559255 0.0399871049 0.0649579242 0.0146767136 0.0196990000 200299654 95654128 760807424 0.2477957606 -0.0511485897 -0.0784581751 109 4.3200000000 0.0541835018 0.0401173471 0.0649579242 0.0146100547 0.0165830000 200300662 95654128 760807424 0.2432772964 -0.0495439097 -0.0790602118 110 4.3600000000 0.0592057258 0.0402908778 0.0649579242 0.0145436638 0.0163100000 200303254 95654128 760807424 0.2391390502 -0.0476791076 -0.0788321570 111 4.4000000000 0.0652246997 0.0405155068 0.0652246997 0.0144790787 0.0170660000 200305862 95654128 760807424 0.2346577942 -0.0457415283 -0.0781735778 112 4.4400000000 0.0627771690 0.0407142717 0.0652246997 0.0144254137 0.0163210000 200306670 95654128 760807424 0.2407675833 -0.0452952795 -0.0786074921 113 4.4800000000 0.0637213066 0.0409178737 0.0652246997 0.0143615322 0.0163580000 200309478 95654128 760807424 0.2414308935 -0.0442953743 -0.0792694464 114 4.5200000000 0.0620069206 0.0411028654 0.0652246997 0.0142994566 0.0162940000 200310286 95654128 760807424 0.2445696890 -0.0424084999 -0.0796201155 115 4.5600000000 0.0590392388 0.0412588338 0.0652246997 0.0142385358 0.0163360000 200313846 95654128 760807424 0.2474465668 -0.0369793922 -0.0836686715 116 4.6000000000 0.0577803329 0.0414012606 0.0652246997 0.0141807133 0.0163080000 200485090 95654128 760807424 0.2498856336 -0.0357859097 -0.0836384371 117 4.6400000000 0.0541441403 0.0415101741 0.0652246997 0.0141352251 0.0163780000 200486098 95654128 760807424 0.2533415556 -0.0328315012 -0.0881076753 118 4.6800000000 0.0527124032 0.0416051082 0.0652246997 0.0141011472 0.0162530000 200488706 95654128 760807424 0.2554021776 -0.0303839333 -0.0879888237 119 4.7200000000 0.0514283143 0.0416876562 0.0652246997 0.0140585429 0.0162800000 200491314 95654128 760807424 0.2561800778 -0.0246943962 -0.0896444321 120 4.7600000000 0.0489566661 0.0417482312 0.0652246997 0.0140085562 0.0162900000 200492122 95654128 760807424 0.2588368058 -0.0245377272 -0.0909742415 121 4.8000000000 0.0480175726 0.0418000440 0.0652246997 0.0139619391 0.0163010000 200494930 95654128 760807424 0.2583852708 -0.0203629080 -0.0915848315 122 4.8400000000 0.0485684723 0.0418555229 0.0652246997 0.0139487297 0.0163450000 200497538 95654128 760807424 0.2564338148 -0.0171216913 -0.0935745463 123 4.8800000000 0.0458938107 0.0418883545 0.0652246997 0.0138995727 0.0163160000 200498346 95654128 760807424 0.2585468888 -0.0173675939 -0.0936011449 124 4.9200000000 0.0469553471 0.0419292173 0.0652246997 0.0138631782 0.0163580000 200500954 95654128 760807424 0.2567310333 -0.0164920203 -0.0934256315 125 4.9600000000 0.0470960252 0.0419705518 0.0652246997 0.0138215031 0.0164190000 200502794 95654128 760807424 0.2558286786 -0.0123924520 -0.0929317102 126 5.0000000000 0.0473053269 0.0420128913 0.0652246997 0.0137833551 0.0163430000 200674042 95654128 760807424 0.2553512156 -0.0105803804 -0.0930935740 127 5.0400000000 0.0485824011 0.0420646197 0.0652246997 0.0137560718 0.0163490000 200676650 95654128 760807424 0.2530296147 -0.0107424771 -0.0918345898 128 5.0800000000 0.0464863777 0.0420991647 0.0652246997 0.0137180089 0.0163620000 200677458 95654128 760807424 0.2548554838 -0.0102128526 -0.0908214077 129 5.1200000000 0.0462727211 0.0421315179 0.0652246997 0.0136952374 0.0163770000 200691530 95654128 760807424 0.2548184395 -0.0073007741 -0.0916291773 130 5.1600000000 0.0451597013 0.0421548116 0.0652246997 0.0136711799 0.0164070000 200719738 95654128 760807424 0.2553529143 -0.0118784700 -0.0902071521 131 5.2000000000 0.0455839597 0.0421809883 0.0652246997 0.0136551811 0.0163880000 200720546 95654128 760807424 0.2529923022 -0.0097077573 -0.0876760185 132 5.2400000000 0.0459973626 0.0422099002 0.0652246997 0.0136358601 0.0163500000 200723154 95654128 760807424 0.2499170750 -0.0061678942 -0.0866922885 133 5.2800000000 0.0467707142 0.0422441920 0.0652246997 0.0136129647 0.0163950000 200725962 95654128 760807424 0.2473616749 -0.0058164173 -0.0860221609 134 5.3200000000 0.0441090949 0.0422581092 0.0652246997 0.0135701115 0.0163910000 200726770 95654128 760807424 0.2498433739 -0.0088885408 -0.0839306116 135 5.3600000000 0.0446839072 0.0422760781 0.0652246997 0.0135336502 0.0164390000 200730238 95654128 760807424 0.2462668866 -0.0069035334 -0.0814075470 136 5.4000000000 0.0454227515 0.0422992154 0.0652246997 0.0135009393 0.0164050000 200901494 95654128 760807424 0.2458814681 -0.0099226907 -0.0792890638 137 5.4400000000 0.0450087674 0.0423189932 0.0652246997 0.0134687943 0.0164120000 200902502 95654128 760807424 0.2460516393 -0.0081642941 -0.0774015635 138 5.4800000000 0.0430271402 0.0423241247 0.0652246997 0.0135294481 0.0229740000 200905110 95654128 760807424 0.2443440557 -0.0074771936 -0.0747997388 139 5.5200000000 0.0437971428 0.0423347219 0.0652246997 0.0134966950 0.0178980000 200905918 95654128 760807424 0.2414767742 -0.0068286359 -0.0724313706 140 5.5600000000 0.0448695682 0.0423528280 0.0652246997 0.0134787372 0.0164780000 200908526 95654128 760807424 0.2392762005 -0.0047456278 -0.0707505643 141 5.6000000000 0.0449611656 0.0423713268 0.0652246997 0.0134540623 0.0164430000 200911334 95654128 760807424 0.2371111959 -0.0028428757 -0.0694467872 142 5.6400000000 0.0457358174 0.0423950204 0.0652246997 0.0134271958 0.0164920000 200912142 95654128 760807424 0.2349677235 -0.0010263872 -0.0682009757 143 5.6800000000 0.0444676504 0.0424095143 0.0652246997 0.0134042428 0.0165030000 200914750 95654128 760807424 0.2338873893 0.0004535499 -0.0664389357 144 5.7200000000 0.0451018773 0.0424282113 0.0652246997 0.0133758851 0.0164560000 200917358 95654128 760807424 0.2295179367 0.0031402325 -0.0653873384 145 5.7600000000 0.0457458086 0.0424510913 0.0652246997 0.0133505934 0.0165290000 200918366 95654128 760807424 0.2257680744 0.0081403209 -0.0649648383 146 5.8000000000 0.0460121185 0.0424754819 0.0652246997 0.0133188501 0.0164970000 200920974 95654128 760807424 0.2243479490 0.0068676132 -0.0625864789 147 5.8400000000 0.0458648577 0.0424985388 0.0652246997 0.0132995656 0.0165230000 200923582 95654128 760807424 0.2204127461 0.0108142775 -0.0610546693 148 5.8800000000 0.0466863438 0.0425268348 0.0652246997 0.0132787916 0.0168470000 200924406 95654128 760807424 0.2173441201 0.0155878728 -0.0602735952 149 5.9200000000 0.0456599295 0.0425478623 0.0652246997 0.0132598318 0.0200820000 200927214 95654128 760807424 0.2149970978 0.0155384643 -0.0587466657 150 5.9600000000 0.0478685275 0.0425833334 0.0652246997 0.0132428196 0.0213900000 200929550 95654128 760807424 0.2083466500 0.0177699700 -0.0569422767 151 6.0000000000 0.0486750528 0.0426236759 0.0652246997 0.0132263056 0.0170540000 201100758 95654128 760807424 0.2035980672 0.0193229057 -0.0551594421 152 6.0400000000 0.0491015166 0.0426662933 0.0652246997 0.0132083716 0.0165130000 201103366 95654128 760807424 0.1995714009 0.0198753811 -0.0534443781 153 6.0800000000 0.0474621207 0.0426976386 0.0652246997 0.0131870755 0.0165030000 201104374 95654128 760807424 0.1971024722 0.0223792046 -0.0511442833 154 6.1200000000 0.0494048297 0.0427411917 0.0652246997 0.0131867426 0.0164870000 201106982 95654128 760807424 0.1921686083 0.0243674330 -0.0494012088 155 6.1600000000 0.0479357876 0.0427747053 0.0652246997 0.0131761980 0.0167580000 201109590 95654128 760807424 0.1891845167 0.0244276002 -0.0478209220 156 6.2000000000 0.0468154661 0.0428006076 0.0652246997 0.0131690312 0.0165240000 201110398 95654128 760807424 0.1857687086 0.0254685022 -0.0453287847 157 6.2400000000 0.0492301956 0.0428415604 0.0652246997 0.0131736309 0.0165180000 201113206 95654128 760807424 0.1791069657 0.0280537996 -0.0432707593 158 6.2800000000 0.0484230258 0.0428768861 0.0652246997 0.0131839411 0.0166150000 201115798 95654128 760807424 0.1772223562 0.0287096947 -0.0414332002 159 6.3200000000 0.0480141751 0.0429091961 0.0652246997 0.0131882460 0.0165030000 201116606 95654128 760807424 0.1738594174 0.0302723050 -0.0398667455 160 6.3600000000 0.0478958897 0.0429403629 0.0652246997 0.0131914671 0.0164750000 201119230 95654128 760807424 0.1708239019 0.0325335041 -0.0388224274 161 6.4000000000 0.0477318764 0.0429701239 0.0652246997 0.0131907939 0.0164690000 201120222 95654128 760807424 0.1679902375 0.0335784927 -0.0375830419 162 6.4400000000 0.0489609279 0.0430071042 0.0652246997 0.0131967565 0.0164980000 201122830 95654128 760807424 0.1624231637 0.0336031727 -0.0358458497 163 6.4800000000 0.0466475636 0.0430294383 0.0652246997 0.0131994605 0.0198210000 201125438 95654128 760807424 0.1607651860 0.0300276391 -0.0333227664 164 6.5200000000 0.0480492450 0.0430600468 0.0652246997 0.0131916317 0.0168460000 201126262 95654128 760807424 0.1564074606 0.0304215718 -0.0314200446 165 6.5600000000 0.0503118597 0.0431039972 0.0652246997 0.0131903503 0.0165890000 201129070 95654128 760807424 0.1496570855 0.0346669555 -0.0301494021 166 6.6000000000 0.0497730859 0.0431441725 0.0652246997 0.0131990197 0.0165930000 201132518 95654128 760807424 0.1451217681 0.0371971875 -0.0282167885 167 6.6400000000 0.0487272739 0.0431776042 0.0652246997 0.0132280506 0.0167220000 201301986 95654128 760807424 0.1425807029 0.0405390598 -0.0276051890 168 6.6800000000 0.0492541678 0.0432137742 0.0652246997 0.0132228833 0.0166020000 201304594 95654128 760807424 0.1380652785 0.0427116118 -0.0259631891 169 6.7200000000 0.0429060459 0.0432119533 0.0652246997 0.0132491311 0.0165230000 201307402 95654128 760807424 0.1397746056 0.0350639485 -0.0238258969 170 6.7600000000 0.0440975465 0.0432171627 0.0652246997 0.0132615022 0.0165020000 201308210 95654128 760807424 0.1342689693 0.0336506031 -0.0233266782 171 6.8000000000 0.0447339527 0.0432260328 0.0652246997 0.0132702834 0.0195480000 201310818 95654128 760807424 0.1309889108 0.0350962244 -0.0223271158 172 6.8400000000 0.0426821895 0.0432228710 0.0652246997 0.0132800538 0.0168580000 201313426 95654128 760807424 0.1312687248 0.0360568203 -0.0205823127 173 6.8800000000 0.0468011051 0.0432435544 0.0652246997 0.0133444543 0.0165560000 201314434 95654128 760807424 0.1268311888 0.0415363684 -0.0213727467 174 6.9200000000 0.0469058715 0.0432646022 0.0652246997 0.0133677971 0.0166020000 201317042 95654128 760807424 0.1254526228 0.0410815626 -0.0210254118 175 6.9600000000 0.0450744666 0.0432749443 0.0652246997 0.0133951199 0.0165760000 201317850 95654128 760807424 0.1264423430 0.0398707390 -0.0214914642 176 7.0000000000 0.0457752310 0.0432891504 0.0652246997 0.0134014020 0.0166060000 201321434 95654128 760807424 0.1253839135 0.0399710797 -0.0211597085 177 7.0400000000 0.0429770499 0.0432873872 0.0652246997 0.0134253506 0.0166540000 201492902 95654128 760807424 0.1256917715 0.0413610972 -0.0208302364 178 7.0800000000 0.0435137935 0.0432886591 0.0652246997 0.0134587838 0.0166320000 201493710 95654128 760807424 0.1229025796 0.0399792865 -0.0191436037 179 7.1200000000 0.0427333154 0.0432855566 0.0652246997 0.0135128579 0.0166380000 201496318 95654128 760807424 0.1222568974 0.0401547886 -0.0191735085 180 7.1600000000 0.0446272939 0.0432930107 0.0652246997 0.0135526454 0.0166170000 201498926 95654128 760807424 0.1190393344 0.0409982055 -0.0186305232 181 7.2000000000 0.0463312566 0.0433097966 0.0652246997 0.0135483734 0.0166090000 201499934 95654128 760807424 0.1144734472 0.0406358019 -0.0175753757 182 7.2400000000 0.0443458520 0.0433154892 0.0652246997 0.0135350784 0.0196230000 201502542 95654128 760807424 0.1161254570 0.0407787152 -0.0173873901 183 7.2800000000 0.0434060358 0.0433159840 0.0652246997 0.0135175247 0.0169230000 201505150 95654128 760807424 0.1128598824 0.0413438678 -0.0154302623 184 7.3200000000 0.0427127033 0.0433127053 0.0652246997 0.0135175888 0.0197270000 201505958 95654128 760807424 0.1118726730 0.0416318998 -0.0157651342 185 7.3600000000 0.0391981825 0.0432904647 0.0652246997 0.0135023511 0.0169470000 201508766 95654128 760807424 0.1105089560 0.0379464813 -0.0140716601 186 7.4000000000 0.0415728390 0.0432812301 0.0652246997 0.0135164564 0.0167650000 201509574 95654128 760807424 0.1081991270 0.0379165821 -0.0127178486 187 7.4400000000 0.0403779186 0.0432657044 0.0652246997 0.0135468298 0.0166980000 201512182 95654128 760807424 0.1069712713 0.0378598385 -0.0131013608 188 7.4800000000 0.0419159904 0.0432585250 0.0652246997 0.0135660375 0.0167190000 201515810 95654128 760807424 0.1023083776 0.0360877961 -0.0119399577 189 7.5200000000 0.0427198112 0.0432556747 0.0652246997 0.0136083788 0.0167180000 201685490 95654128 760807424 0.0991309881 0.0381028578 -0.0111555830 190 7.5600000000 0.0418451168 0.0432482507 0.0652246997 0.0136390005 0.0167350000 201688114 95654128 760807424 0.0973783508 0.0348214321 -0.0098882886 191 7.6000000000 0.0429987833 0.0432469446 0.0652246997 0.0136817193 0.0166830000 201690722 95654128 760807424 0.0943874493 0.0383852161 -0.0107597494 192 7.6400000000 0.0423247516 0.0432421415 0.0652246997 0.0137058069 0.0166970000 201691530 95654128 760807424 0.0923633277 0.0366493203 -0.0101549672 193 7.6800000000 0.0412117392 0.0432316213 0.0652246997 0.0137264419 0.0167240000 201694338 95654128 760807424 0.0922936723 0.0369212590 -0.0091943601 194 7.7200000000 0.0418610685 0.0432245566 0.0652246997 0.0137391969 0.0167320000 201696946 95654128 760807424 0.0891248211 0.0377664194 -0.0102845840 195 7.7600000000 0.0412870646 0.0432146207 0.0652246997 0.0137398350 0.0217150000 201697754 95654128 760807424 0.0903808102 0.0418025739 -0.0108959330 196 7.8000000000 0.0409601107 0.0432031181 0.0652246997 0.0137243953 0.0173330000 201700362 95654128 760807424 0.0873284787 0.0409640633 -0.0100763934 197 7.8400000000 0.0425393842 0.0431997489 0.0652246997 0.0137416163 0.0166920000 201701370 95654128 760807424 0.0894986987 0.0434645265 -0.0106732100 198 7.8800000000 0.0415663198 0.0431914993 0.0652246997 0.0137396441 0.0202210000 201703978 95654128 760807424 0.0880729929 0.0419511795 -0.0101634543 199 7.9200000000 0.0429554023 0.0431903129 0.0652246997 0.0137611348 0.0207120000 201707914 95654128 760807424 0.0914130732 0.0435909592 -0.0100151179 200 7.9600000000 0.0425312594 0.0431870176 0.0652246997 0.0137748840 0.0171530000 201877394 95654128 760807424 0.0906152874 0.0443143286 -0.0096940668 201 8.0000000000 0.0418350957 0.0431802916 0.0652246997 0.0137888071 0.0258080000 201880202 95654128 760807424 0.0936571583 0.0451667942 -0.0092730289 202 8.0400000000 0.0416641831 0.0431727861 0.0652246997 0.0137854717 0.0185670000 201882810 95654128 760807424 0.0922002196 0.0459024310 -0.0106760021 203 8.0800000000 0.0409603827 0.0431618876 0.0652246997 0.0137735296 0.0167960000 201883618 95654128 760807424 0.0902194381 0.0481677987 -0.0102581494 204 8.1200000000 0.0406414680 0.0431495326 0.0652246997 0.0137434558 0.0168360000 201886226 95654128 760807424 0.0896600038 0.0510885902 -0.0099026859 205 8.1600000000 0.0399992280 0.0431341653 0.0652246997 0.0137200832 0.0167920000 201889050 95654128 760807424 0.0883949474 0.0490721203 -0.0083835591 206 8.1999999990 0.0399960577 0.0431189317 0.0652246997 0.0137041047 0.0167760000 201889858 95654128 760807424 0.0856642276 0.0461690165 -0.0069411765 207 8.2400000000 0.0393997729 0.0431009648 0.0652246997 0.0136959882 0.0167930000 201892466 95654128 760807424 0.0840190500 0.0471904762 -0.0072383350 208 8.2799999990 0.0388968624 0.0430807527 0.0652246997 0.0137055557 0.0168710000 201895074 95654128 760807424 0.0851066485 0.0447577648 -0.0051305396 209 8.3200000000 0.0401426293 0.0430666947 0.0652246997 0.0137208563 0.0168850000 201896082 95654128 760807424 0.0817025974 0.0473381691 -0.0056182300 210 8.3599999990 0.0387995765 0.0430463751 0.0652246997 0.0137219898 0.0168440000 201898706 95654128 760807424 0.0800749958 0.0469382815 -0.0030904524 211 8.4000000000 0.0373140909 0.0430192079 0.0652246997 0.0137471069 0.0209660000 201899514 95654128 760807424 0.0792492852 0.0463997573 -0.0024170503 212 8.4399999990 0.0386695042 0.0429986904 0.0652246997 0.0137735601 0.0174030000 201902122 95654128 760807424 0.0786402747 0.0452255346 -0.0003929220 213 8.4800000000 0.0373988561 0.0429724001 0.0652246997 0.0137778144 0.0169160000 201904930 95654128 760807424 0.0758670717 0.0445476770 0.0008640946 214 8.5200000000 0.0376636945 0.0429475931 0.0652246997 0.0138060414 0.0206300000 201905738 95654128 760807424 0.0744189769 0.0468257479 0.0012547559 215 8.5600000000 0.0380341969 0.0429247401 0.0652246997 0.0138362588 0.0173280000 201909678 95654128 760807424 0.0728392079 0.0450091846 0.0032370212 216 8.6000000000 0.0386528149 0.0429049627 0.0652246997 0.0138599169 0.0169340000 202080974 95654128 760807424 0.0750974342 0.0505996421 0.0052451314 217 8.6400000000 0.0370153785 0.0428778217 0.0652246997 0.0138538628 0.0169290000 202081982 95654128 760807424 0.0764799938 0.0492849611 0.0075711235 218 8.6800000000 0.0390945375 0.0428604672 0.0652246997 0.0138620217 0.0169620000 202084590 95654128 760807424 0.0765086785 0.0466972291 0.0099968016 219 8.7200000000 0.0407102145 0.0428506487 0.0652246997 0.0138855744 0.0169530000 202087198 95654128 760807424 0.0769498870 0.0459434278 0.0136472229 220 8.7600000000 0.0422635861 0.0428479802 0.0652246997 0.0138991865 0.0169780000 202088006 95654128 760807424 0.0758638456 0.0445270650 0.0172426198 221 8.8000000000 0.0433716550 0.0428503498 0.0652246997 0.0139288968 0.0178010000 202090830 95654128 760807424 0.0762125403 0.0452130139 0.0192989595 222 8.8400000000 0.0421540849 0.0428472135 0.0652246997 0.0139478997 0.0170390000 202091638 95654128 760807424 0.0763385966 0.0445531718 0.0214940757 223 8.8800000000 0.0421924628 0.0428442774 0.0652246997 0.0140059537 0.0226580000 202094262 95654128 760807424 0.0749081820 0.0462653376 0.0224477332 224 8.9200000000 0.0422417857 0.0428415877 0.0652246997 0.0140231574 0.0175430000 202096870 95654128 760807424 0.0711407363 0.0462713614 0.0234581288 225 8.9600000000 0.0390532017 0.0428247504 0.0652246997 0.0141632322 0.0170040000 202097878 95654128 760807424 0.0324464291 0.0413085967 0.0079748686 226 9.0000000000 0.0372005329 0.0427998645 0.0652246997 0.0141673537 0.0171220000 202100486 95654128 760807424 0.0291473456 0.0440449230 0.0069403439 227 9.0400000000 0.0369114727 0.0427739244 0.0652246997 0.0141674651 0.0172510000 202104870 95654128 760807424 0.0264046006 0.0431369990 0.0078983409 228 9.0800000000 0.0370826758 0.0427489628 0.0652246997 0.0141796095 0.0172190000 202274338 95654128 760807424 0.0225904286 0.0434049144 0.0081627676 229 9.1200000000 0.0368336812 0.0427231319 0.0652246997 0.0141813185 0.0171480000 202277146 95654128 760807424 0.0186563525 0.0436400585 0.0081312545 230 9.1600000000 0.0372892059 0.0426995061 0.0652246997 0.0141970411 0.0172140000 202279770 95654128 760807424 0.0134038646 0.0443335995 0.0079403138 231 9.2000000000 0.0376571342 0.0426776777 0.0652246997 0.0142024555 0.0171320000 202280578 95654128 760807424 0.0094876224 0.0448571481 0.0076424279 232 9.2400000000 0.0374178179 0.0426550059 0.0652246997 0.0142075426 0.0171920000 202283202 95654128 760807424 0.0060255039 0.0436478071 0.0080675278 233 9.2800000000 0.0368717872 0.0426301852 0.0652246997 0.0142188619 0.0171740000 202284210 95654128 760807424 0.0041190349 0.0462096743 0.0067072590 234 9.3200000000 0.0374457166 0.0426080293 0.0652246997 0.0142290736 0.0171840000 202286818 95654128 760807424 -0.0006776159 0.0466907918 0.0057541681 235 9.3600000000 0.0374839194 0.0425862246 0.0652246997 0.0142476908 0.0172250000 202289426 95654128 760807424 -0.0029829128 0.0472289026 0.0055972142 236 9.4000000000 0.0384029895 0.0425684990 0.0652246997 0.0142897913 0.0173380000 202290250 95654128 760807424 -0.0065404642 0.0466181748 0.0050871819 237 9.4400000000 0.0387550741 0.0425524086 0.0652246997 0.0143270583 0.0173500000 202294750 95654128 760807424 -0.0096855862 0.0441512428 0.0046506743 238 9.4800000000 0.0386581756 0.0425360463 0.0652246997 0.0143485783 0.0203860000 202466046 95654128 760807424 -0.0129870828 0.0407250598 0.0043093688 239 9.5200000000 0.0387491807 0.0425202017 0.0652246997 0.0143606835 0.0206840000 202466870 95654128 760807424 -0.0150914406 0.0416194275 0.0040668305 240 9.5600000000 0.0384264179 0.0425031443 0.0652246997 0.0145002431 0.0176190000 202469478 95654128 760807424 -0.0178167652 0.0343213826 0.0053657941 241 9.6000000000 0.0393326655 0.0424899887 0.0652246997 0.0144982612 0.0300960000 202472318 95654128 760807424 -0.0208863094 0.0355858952 0.0047248756 242 9.6400000000 0.0395941548 0.0424780225 0.0652246997 0.0145070036 0.0204030000 202473126 95654128 760807424 -0.0217185356 0.0348410942 0.0049538799 243 9.6800000000 0.0397345722 0.0424667326 0.0652246997 0.0145221330 0.0178550000 202475734 95654128 760807424 -0.0231966414 0.0337888896 0.0043518678 244 9.7200000000 0.0401980206 0.0424574346 0.0652246997 0.0145274648 0.0266200000 202480766 95654128 760807424 -0.0246567670 0.0344859622 0.0046533728 245 9.7600000000 0.0394505337 0.0424451615 0.0652246997 0.0145226650 0.0187740000 202650358 95654128 760807424 -0.0263382066 0.0336518958 0.0046614343 246 9.8000000000 0.0400274843 0.0424353336 0.0652246997 0.0145291488 0.0178750000 202652966 95654128 760807424 -0.0277906023 0.0346311703 0.0045433724 247 9.8400000000 0.0418978371 0.0424331575 0.0652246997 0.0145409167 0.0214210000 202653774 95654128 760807424 -0.0319002308 0.0363580175 0.0040501361 248 9.8800000000 0.0426489115 0.0424340274 0.0652246997 0.0145407326 0.0214070000 202656398 95654128 760807424 -0.0348886885 0.0348902196 0.0037230793 249 9.9200000000 0.0440736078 0.0424406121 0.0652246997 0.0145537285 0.0185280000 202659206 95654128 760807424 -0.0396334268 0.0331412964 0.0023286045 250 9.9600000000 0.0447406955 0.0424498124 0.0652246997 0.0145477688 0.0177750000 202660014 95654128 760807424 -0.0423174091 0.0343983881 0.0019642124 251 10.0000000000 0.0456046909 0.0424623817 0.0652246997 0.0145474181 0.0177800000 202662622 95654128 760807424 -0.0457914732 0.0334751271 0.0006100434 252 10.0400000000 0.0456667580 0.0424750974 0.0652246997 0.0145508839 0.0185940000 202665362 95654128 760807424 -0.0489842109 0.0319067575 -0.0005603153 253 10.0800000000 0.0471237525 0.0424934716 0.0652246997 0.0145477859 0.0182090000 202668198 95654128 760807424 -0.0521328747 0.0331201330 -0.0010778608 254 10.1200000000 0.0487912148 0.0425182658 0.0652246997 0.0145458168 0.0213380000 202839506 95654128 760807424 -0.0552408546 0.0332670100 -0.0012979723 255 10.1600000000 0.0493483543 0.0425450505 0.0652246997 0.0145371388 0.0180820000 202842114 95654128 760807424 -0.0574221201 0.0336385630 -0.0022570502 256 10.2000000000 0.0497987568 0.0425733853 0.0652246997 0.0145335428 0.0181060000 202843054 95654128 760807424 -0.0589441694 0.0339491479 -0.0023580501 257 10.2400000000 0.0496367589 0.0426008692 0.0652246997 0.0146462557 0.0180170000 202868390 95654128 760807424 -0.0642236695 0.0293326117 -0.0035185572 258 10.2800000000 0.0511360690 0.0426339514 0.0652246997 0.0146497903 0.0178960000 202920398 95654128 760807424 -0.0666341633 0.0306376051 -0.0044204113 259 10.3200000000 0.0509705432 0.0426661390 0.0652246997 0.0146373251 0.0297620000 202923006 95654128 760807424 -0.0687161386 0.0288211368 -0.0047184657 260 10.3600000000 0.0520879515 0.0427023768 0.0652246997 0.0146272856 0.0199190000 202925878 95654128 760807424 -0.0710097626 0.0281585418 -0.0051422371 261 10.4000000000 0.0540580451 0.0427458851 0.0652246997 0.0146119130 0.0182200000 202926886 95654128 760807424 -0.0733143389 0.0294479541 -0.0063324356 262 10.4400000000 0.0527368151 0.0427840184 0.0652246997 0.0145901832 0.0180130000 202929494 95654128 760807424 -0.0741432980 0.0268673543 -0.0068325521 263 10.4800000000 0.0532398745 0.0428237745 0.0652246997 0.0145717043 0.0181830000 202952046 95654128 760807424 -0.0766313821 0.0256995875 -0.0071839374 264 10.5200000000 0.0549125820 0.0428695654 0.0652246997 0.0145625362 0.0182270000 203103866 95654128 760807424 -0.0791054070 0.0259440094 -0.0073781046 265 10.5600000000 0.0546839871 0.0429141481 0.0652246997 0.0145451285 0.0282110000 203106674 95654128 760807424 -0.0813905522 0.0241292268 -0.0094169118 266 10.6000000000 0.0557723865 0.0429624874 0.0652246997 0.0145382936 0.0201680000 203109282 95654128 760807424 -0.0838067606 0.0237567313 -0.0107153561 267 10.6400000000 0.0551129058 0.0430079946 0.0652246997 0.0145347276 0.0181790000 203110090 95654128 760807424 -0.0857381150 0.0222861767 -0.0119086206 268 10.6800000000 0.0556301810 0.0430550923 0.0652246997 0.0145398401 0.0181030000 203112698 95654128 760807424 -0.0880312324 0.0214861631 -0.0136944121 269 10.7200000000 0.0572074540 0.0431077033 0.0652246997 0.0145558634 0.0182540000 203113838 95654128 760807424 -0.0905458555 0.0216015112 -0.0152404075 270 10.7600000000 0.0582199097 0.0431636744 0.0652246997 0.0145621065 0.0182960000 203116446 95654128 760807424 -0.0931813493 0.0213330574 -0.0179488938 271 10.8000000000 0.0574575886 0.0432164195 0.0652246997 0.0145680441 0.0182650000 203119054 95654128 760807424 -0.0961092040 0.0180718787 -0.0198571291 272 10.8400000000 0.0573798865 0.0432684911 0.0652246997 0.0145871928 0.0184550000 203119862 95654128 760807424 -0.0984011292 0.0163297616 -0.0218535550 273 10.8800000000 0.0581922121 0.0433231567 0.0652246997 0.0146089858 0.0184990000 203142650 95654128 760807424 -0.1014620811 0.0150254313 -0.0236860979 274 10.9200000000 0.0592397638 0.0433812465 0.0652246997 0.0146225363 0.0184200000 203296462 95654128 760807424 -0.1034882888 0.0149556249 -0.0254337955 275 10.9600000000 0.0588636957 0.0434375463 0.0652246997 0.0146306860 0.0183860000 203297270 95654128 760807424 -0.1056569889 0.0123220235 -0.0270775873 276 11.0000000000 0.0592655353 0.0434948941 0.0652246997 0.0146289784 0.0182570000 203299878 95654128 760807424 -0.1082553789 0.0119138146 -0.0291370060 277 11.0400000000 0.0603019558 0.0435555694 0.0652246997 0.0149532425 0.0186770000 203302818 95654128 760807424 -0.1163919941 0.0058601671 -0.0363838077 278 11.0800000000 0.0621247627 0.0436223651 0.0652246997 0.0149496931 0.0183940000 203303626 95654128 760807424 -0.1193013415 0.0056287614 -0.0387623012 279 11.1200000000 0.0631470978 0.0436923462 0.0652246997 0.0149358022 0.0218380000 203306722 95654128 760807424 -0.1212068796 0.0041100583 -0.0393331349 280 11.1600000000 0.0650889724 0.0437687627 0.0652246997 0.0149266404 0.0187430000 203309330 95654128 760807424 -0.1228461340 0.0051718769 -0.0396453366 281 11.2000000000 0.0633280650 0.0438383688 0.0652246997 0.0149229041 0.0184930000 203310338 95654128 760807424 -0.1238733009 0.0011759545 -0.0417264700 282 11.2400000000 0.0639166832 0.0439095685 0.0652246997 0.0149175105 0.0184910000 203312946 95654128 760807424 -0.1251245141 0.0008556410 -0.0421986766 283 11.2800000000 0.0645640790 0.0439825526 0.0652246997 0.0149099805 0.0186680000 203333270 95654128 760807424 -0.1262729317 -0.0006433923 -0.0432816371 284 11.3200000000 0.0644117445 0.0440544864 0.0652246997 0.0149142848 0.0225670000 203487406 95654128 760807424 -0.1275999993 -0.0024385019 -0.0439579599 285 11.3600000000 0.0640382096 0.0441246047 0.0652246997 0.0149136896 0.0188820000 203490214 95654128 760807424 -0.1291367412 -0.0050064609 -0.0456731580 286 11.4000000000 0.0637937859 0.0441933781 0.0652246997 0.0148978726 0.0185450000 203491022 95654128 760807424 -0.1294656396 -0.0075702015 -0.0458209813 287 11.4400000000 0.0641639158 0.0442629618 0.0652246997 0.0148820382 0.0221520000 203493630 95654128 760807424 -0.1303527504 -0.0086999675 -0.0465180278 288 11.4800000000 0.0652662963 0.0443358901 0.0652662963 0.0148636709 0.0187550000 203496238 95654128 760807424 -0.1323218346 -0.0100769922 -0.0480880365 289 11.5200000000 0.0637781247 0.0444031643 0.0652662963 0.0148450867 0.0226600000 203497378 95654128 760807424 -0.1324321330 -0.0140416697 -0.0491304547 290 11.5600000000 0.0609723590 0.0444602994 0.0652662963 0.0148259170 0.0224840000 203499986 95654128 760807424 -0.1319032162 -0.0180266965 -0.0491996408 291 11.6000000000 0.0602200255 0.0445144565 0.0652662963 0.0148040017 0.0187630000 203502594 95654128 760807424 -0.1325738430 -0.0214617532 -0.0487109125 292 11.6400000000 0.0622002743 0.0445750244 0.0652662963 0.0147804674 0.0186170000 203503402 95654128 760807424 -0.1342156678 -0.0217727497 -0.0495977513 293 11.6800000000 0.0635986179 0.0446399514 0.0652662963 0.0147554126 0.0187800000 203506210 95654128 760807424 -0.1349567920 -0.0217417646 -0.0508480221 294 11.7200000000 0.0634879991 0.0447040604 0.0652662963 0.0147307614 0.0186800000 203507018 95654128 760807424 -0.1350552589 -0.0229723994 -0.0511103272 295 11.7600000000 0.0620614663 0.0447628990 0.0652662963 0.0147114760 0.0226980000 203509626 95654128 760807424 -0.1344402134 -0.0292016380 -0.0516279936 296 11.8000000000 0.0621945299 0.0448217897 0.0652662963 0.0146909654 0.0189820000 203512234 95654128 760807424 -0.1343197078 -0.0308067948 -0.0523931608 297 11.8400000000 0.0638566464 0.0448858801 0.0652662963 0.0146798901 0.0187170000 203513226 95654128 760807424 -0.1353776902 -0.0302094538 -0.0527365729 298 11.8800000000 0.0644139573 0.0449514106 0.0652662963 0.0147162239 0.0226000000 203534858 95654128 760807424 -0.1366233975 -0.0331638716 -0.0552180521 299 11.9200000000 0.0638106093 0.0450144848 0.0652662963 0.0147151491 0.0191900000 203689478 95654128 760807424 -0.1372147948 -0.0354242139 -0.0564127266 300 11.9600000000 0.0639965832 0.0450777585 0.0652662963 0.0147310183 0.0219600000 203690286 95654128 760807424 -0.1378643215 -0.0375646465 -0.0562453307 301 12.0000000000 0.0626475960 0.0451361300 0.0652662963 0.0147347102 0.0186680000 203693094 95654128 760807424 -0.1383648068 -0.0413157940 -0.0570388362 302 12.0400000000 0.0633009523 0.0451962784 0.0652662963 0.0147810652 0.0270960000 203695846 95654128 760807424 -0.1405118257 -0.0435026363 -0.0608166531 303 12.0800000000 0.0619777516 0.0452516628 0.0652662963 0.0147625383 0.0208610000 203696854 95654128 760807424 -0.1417748779 -0.0469731204 -0.0625735670 304 12.1200000000 0.0616525561 0.0453056131 0.0652662963 0.0147501659 0.0241620000 203699462 95654128 760807424 -0.1436703205 -0.0496940464 -0.0649333224 305 12.1600000000 0.0615585856 0.0453589016 0.0652662963 0.0147417416 0.0207590000 203700470 95654128 760807424 -0.1451552510 -0.0506654978 -0.0678047687 306 12.2000000000 0.0616589114 0.0454121696 0.0652662963 0.0147355509 0.0203890000 203703078 95654128 760807424 -0.1452511549 -0.0522380918 -0.0690867528 307 12.2400000000 0.0617106482 0.0454652591 0.0652662963 0.0147464489 0.0199710000 203706018 95654128 760807424 -0.1464817226 -0.0535610691 -0.0714908540 308 12.2800000000 0.0612789318 0.0455166022 0.0652662963 0.0147580803 0.0203910000 203706826 95654128 760807424 -0.1477465630 -0.0550905094 -0.0749846846 309 12.3200000000 0.0606128387 0.0455654573 0.0652662963 0.0147496972 0.0203710000 203709634 95654128 760807424 -0.1487190127 -0.0572955981 -0.0776639208 310 12.3600000000 0.0611351468 0.0456156821 0.0652662963 0.0147521205 0.0206960000 203729418 95654128 760807424 -0.1507297605 -0.0584453940 -0.0808567926 311 12.4000000000 0.0607409626 0.0456643165 0.0652662963 0.0147502149 0.0239340000 203884626 95654128 760807424 -0.1522721946 -0.0600531362 -0.0842799544 312 12.4400000000 0.0610733405 0.0457137044 0.0652662963 0.0147425224 0.0207250000 203887234 95654128 760807424 -0.1536034644 -0.0609099269 -0.0865376592 313 12.4800000000 0.0618327819 0.0457652030 0.0652662963 0.0147362783 0.0205610000 203888242 95654128 760807424 -0.1551717520 -0.0618255027 -0.0882416368 314 12.5200000000 0.0614820421 0.0458152566 0.0652662963 0.0147336609 0.0210200000 203890982 95654128 760807424 -0.1561081111 -0.0633569583 -0.0907659754 315 12.5600000000 0.0621050522 0.0458669703 0.0652662963 0.0147335666 0.0210550000 203891990 95654128 760807424 -0.1576867551 -0.0636775494 -0.0929986238 316 12.6000000000 0.0623278618 0.0459190617 0.0652662963 0.0147318894 0.0239800000 203894598 95654128 760807424 -0.1591347158 -0.0648633987 -0.0950551480 317 12.6400000000 0.0618652403 0.0459693651 0.0652662963 0.0147175771 0.0208660000 203897406 95654128 760807424 -0.1608726531 -0.0670522898 -0.0969292596 318 12.6800000000 0.0620973036 0.0460200819 0.0652662963 0.0147049669 0.0208070000 203898214 95654128 760807424 -0.1622931212 -0.0676040500 -0.0995005593 319 12.7200000000 0.0623961911 0.0460714177 0.0652662963 0.0147235849 0.0207840000 203901022 95654128 760807424 -0.1645261347 -0.0684796199 -0.1044067070 320 12.7600000000 0.0622610003 0.0461220101 0.0652662963 0.0147097821 0.0208400000 203903630 95654128 760807424 -0.1652970761 -0.0692328960 -0.1068950593 321 12.8000000000 0.0619723648 0.0461713882 0.0652662963 0.0146949230 0.0244440000 203904638 95654128 760807424 -0.1666672528 -0.0699086636 -0.1092948467 322 12.8400000000 0.0627879873 0.0462229925 0.0652662963 0.0146828555 0.0210100000 203907246 95654128 760807424 -0.1680268049 -0.0694552585 -0.1114804745 323 12.8800000000 0.0628712177 0.0462745350 0.0652662963 0.0146659583 0.0208610000 203908254 95654128 760807424 -0.1692166924 -0.0693710223 -0.1143122390 324 12.9200000000 0.0615045205 0.0463215411 0.0652662963 0.0146466736 0.0238850000 203910862 95654128 760807424 -0.1702522486 -0.0708829015 -0.1167748719 325 12.9600000000 0.0625549033 0.0463714899 0.0652662963 0.0146308793 0.0209670000 203913670 95654128 760807424 -0.1717613488 -0.0697343647 -0.1180718839 326 13.0000000000 0.0623830743 0.0464206052 0.0652662963 0.0146116388 0.0209830000 203914610 95654128 760807424 -0.1730247587 -0.0697751939 -0.1201136038 327 13.0400000000 0.0623199642 0.0464692271 0.0652662963 0.0145930391 0.0208750000 203917418 95654128 760807424 -0.1743366867 -0.0688177198 -0.1218654215 328 13.0800000000 0.0635797903 0.0465213935 0.0652662963 0.0145750261 0.0207700000 203918226 95654128 760807424 -0.1762537211 -0.0667435303 -0.1231895760 329 13.1200000000 0.0632406175 0.0465722118 0.0652662963 0.0145616979 0.0209390000 203921034 95654128 760807424 -0.1773248911 -0.0652466193 -0.1252635270 330 13.1600000000 0.0622955970 0.0466198584 0.0652662963 0.0145445704 0.0209350000 203923642 95654128 760807424 -0.1786647737 -0.0644293278 -0.1277858168 331 13.2000000000 0.0630624965 0.0466695340 0.0652662963 0.0145291867 0.0263950000 203942998 95654128 760807424 -0.1801550686 -0.0619110726 -0.1286244988 332 13.2400000000 0.0632514283 0.0467194795 0.0652662963 0.0145094015 0.0213150000 204098682 95654128 760807424 -0.1817732006 -0.0594833046 -0.1299973428 333 13.2800000000 0.0620618202 0.0467655526 0.0652662963 0.0145017546 0.0210420000 204099690 95654128 760807424 -0.1827155501 -0.0580273457 -0.1319145560 334 13.3200000000 0.0623593405 0.0468122406 0.0652662963 0.0145449101 0.0212440000 204102298 95654128 760807424 -0.1851759702 -0.0522732474 -0.1337856650 335 13.3600000000 0.0636580065 0.0468625265 0.0652662963 0.0145307892 0.0210470000 204105106 95654128 760807424 -0.1867179126 -0.0483426526 -0.1340043396 336 13.4000000000 0.0641906485 0.0469140982 0.0652662963 0.0145165266 0.0210660000 204105914 95654128 760807424 -0.1881478429 -0.0450279340 -0.1345959604 337 13.4400000000 0.0628485680 0.0469613815 0.0652662963 0.0145078944 0.0210230000 204108722 95654128 760807424 -0.1886434555 -0.0437460840 -0.1358377635 338 13.4800000000 0.0630651340 0.0470090258 0.0652662963 0.0145105131 0.0210360000 204111330 95654128 760807424 -0.1893542856 -0.0409654602 -0.1367759705 339 13.5200000000 0.0642533526 0.0470598940 0.0652662963 0.0145203081 0.0246880000 204112338 95654128 760807424 -0.1906230301 -0.0372063406 -0.1362633556 340 13.5600000000 0.0643451661 0.0471107330 0.0652662963 0.0145221381 0.0211970000 204114946 95654128 760807424 -0.1905988604 -0.0343770459 -0.1353859901 341 13.6000000000 0.0644586980 0.0471616068 0.0652662963 0.0145139239 0.0257630000 204115954 95654128 760807424 -0.1917836070 -0.0319051817 -0.1353971511 342 13.6400000000 0.0642323419 0.0472115213 0.0652662963 0.0145128290 0.0213330000 204118562 95654128 760807424 -0.1927068681 -0.0287045036 -0.1364764720 343 13.6800000000 0.0647548288 0.0472626679 0.0652662963 0.0145176464 0.0211260000 204121370 95654128 760807424 -0.1936688721 -0.0260165762 -0.1358744353 344 13.7200000000 0.0654849708 0.0473156397 0.0654849708 0.0145306544 0.0211980000 204122178 95654128 760807424 -0.1942686737 -0.0222491119 -0.1356730163 345 13.7600000000 0.0650933459 0.0473671693 0.0654849708 0.0147226554 0.0254260000 204125250 95654128 760807424 -0.1959131509 -0.0172525924 -0.1355364174 346 13.8000000000 0.0648681670 0.0474177502 0.0654849708 0.0147301492 0.0212800000 204126058 95654128 760807424 -0.1967015713 -0.0153383762 -0.1354909539 347 13.8400000000 0.0661605522 0.0474717641 0.0661605522 0.0147283412 0.0211030000 204128866 95654128 760807424 -0.1981273592 -0.0115163345 -0.1352154762 348 13.8800000000 0.0656266212 0.0475239332 0.0661605522 0.0147119314 0.0211790000 204131474 95654128 760807424 -0.1990865171 -0.0088029159 -0.1366967708 349 13.9200000000 0.0654284135 0.0475752354 0.0661605522 0.0146912258 0.0211120000 204132482 95654128 760807424 -0.2004380524 -0.0053149476 -0.1385063827 350 13.9600000000 0.0650964379 0.0476252960 0.0661605522 0.0146764764 0.0247540000 204135090 95654128 760807424 -0.2007180750 -0.0033268123 -0.1370088160 351 14.0000000000 0.0639121607 0.0476716974 0.0661605522 0.0146922474 0.0213570000 204136098 95654128 760807424 -0.2012558132 -0.0012653780 -0.1376028061 352 14.0400000000 0.0631995648 0.0477158106 0.0661605522 0.0146988975 0.0198600000 204138706 95654128 760807424 -0.2015217692 0.0012088418 -0.1375346184 353 14.0800000000 0.0641455799 0.0477623539 0.0661605522 0.0146998564 0.0211400000 204141314 95654128 760807424 -0.2024843693 0.0055018687 -0.1366413087 354 14.1200000000 0.0644891337 0.0478096047 0.0661605522 0.0147322365 0.0211730000 204142322 95654128 760807424 -0.2027753592 0.0090495460 -0.1356586814 355 14.1600000000 0.0641914681 0.0478557508 0.0661605522 0.0147480260 0.0243270000 204144930 95654128 760807424 -0.2033803910 0.0117963068 -0.1360610127 356 14.2000000000 0.0650094226 0.0479039352 0.0661605522 0.0147507279 0.0211860000 204147738 95654128 760807424 -0.2038444430 0.0160959251 -0.1351611167 357 14.2400000000 0.0650436580 0.0479519457 0.0661605522 0.0147555542 0.0211770000 204148546 95654128 760807424 -0.2041461021 0.0188747291 -0.1336297840 358 14.2800000000 0.0659327433 0.0480021713 0.0661605522 0.0147538265 0.0211790000 204151354 95654128 760807424 -0.2049334049 0.0223865379 -0.1330012679 359 14.3200000000 0.0655273721 0.0480509881 0.0661605522 0.0147712113 0.0250350000 204152162 95654128 760807424 -0.2049245834 0.0250207186 -0.1321636140 360 14.3600000000 0.0644814670 0.0480966283 0.0661605522 0.0147718079 0.0223980000 204154970 95654128 760807424 -0.2051239908 0.0267065316 -0.1319982260 361 14.4000000000 0.0646006167 0.0481423457 0.0661605522 0.0147603077 0.0212210000 204157578 95654128 760807424 -0.2058428526 0.0295854993 -0.1319696158 362 14.4400000000 0.0644412041 0.0481873702 0.0661605522 0.0147606765 0.0213870000 204176086 95654128 760807424 -0.2056653798 0.0323127881 -0.1316056848 363 14.4800000000 0.0637790859 0.0482303226 0.0661605522 0.0147606824 0.0212410000 204332766 95654128 760807424 -0.2055207342 0.0335382596 -0.1309744567 364 14.5200000000 0.0647718757 0.0482757664 0.0661605522 0.0147492809 0.0212470000 204333774 95654128 760807424 -0.2060613036 0.0373510420 -0.1302227080 365 14.5600000000 0.0644705445 0.0483201356 0.0661605522 0.0147701765 0.0210670000 204336382 95654128 760807424 -0.2063676715 0.0378758796 -0.1279981881 366 14.6000000000 0.0649592057 0.0483655976 0.0661605522 0.0148621597 0.0208140000 204339190 95654128 760807424 -0.2057753056 0.0444651619 -0.1256251186 367 14.6400000000 0.0650201961 0.0484109780 0.0661605522 0.0148759472 0.0208010000 204339998 95654128 760807424 -0.2054303139 0.0475647785 -0.1252844483 368 14.6800000000 0.0642980263 0.0484541493 0.0661605522 0.0148849505 0.0262520000 204342806 95654128 760807424 -0.2042741925 0.0497397184 -0.1237241924 369 14.7200000000 0.0644681379 0.0484975476 0.0661605522 0.0149036576 0.0212000000 204345546 95654128 760807424 -0.2032100111 0.0565420538 -0.1204528287 370 14.7600000000 0.0652568489 0.0485428430 0.0661605522 0.0148988483 0.0212330000 204363438 95654128 760807424 -0.2022572607 0.0605946742 -0.1185028553 371 14.8000000000 0.0656371936 0.0485889194 0.0661605522 0.0148965160 0.0208250000 204520378 95654128 760807424 -0.2017219961 0.0630233213 -0.1164298877 372 14.8400000000 0.0650040433 0.0486330461 0.0661605522 0.0148908923 0.0208770000 204521386 95654128 760807424 -0.2002728432 0.0644880459 -0.1137845516 373 14.8800000000 0.0655099228 0.0486782924 0.0661605522 0.0148836722 0.0214880000 204523994 95654128 760807424 -0.1991524547 0.0677975118 -0.1109323949 374 14.9200000000 0.0650230125 0.0487219949 0.0661605522 0.0148768842 0.0212010000 204526802 95654128 760807424 -0.1972881556 0.0704847723 -0.1082101315 375 14.9600000000 0.0640619993 0.0487629016 0.0661605522 0.0148741948 0.0211820000 204527610 95654128 760807424 -0.1953734159 0.0722609907 -0.1054424718 376 15.0000000000 0.0637556389 0.0488027759 0.0661605522 0.0148819042 0.0243710000 204547094 95654128 760807424 -0.1935724169 0.0744922906 -0.1032031327 377 15.0400000000 0.0639600605 0.0488429809 0.0661605522 0.0149018022 0.0209910000 204702430 95654128 760807424 -0.1916231364 0.0768651143 -0.1000214964 378 15.0800000000 0.0638113990 0.0488825799 0.0661605522 0.0149148685 0.0249940000 204705238 95654128 760807424 -0.1894089729 0.0798344687 -0.0979306698 379 15.1200000000 0.0644488111 0.0489236517 0.0661605522 0.0149091736 0.0210690000 204707846 95654128 760807424 -0.1878109425 0.0826173723 -0.0953812823 380 15.1600000000 0.0639851466 0.0489632872 0.0661605522 0.0149148229 0.0208070000 204708854 95654128 760807424 -0.1855459809 0.0840382874 -0.0931862071 381 15.2000000000 0.0634591728 0.0490013342 0.0661605522 0.0149188875 0.0238340000 204711462 95654128 760807424 -0.1829830855 0.0855104327 -0.0914667100 382 15.2400000000 0.0628597885 0.0490376129 0.0661605522 0.0149156170 0.0249560000 204729182 95654136 760807424 -0.1803602725 0.0865351409 -0.0891225711 383 15.2800000000 0.0636216104 0.0490756912 0.0661605522 0.0149082591 0.0210650000 204886514 95654136 760807424 -0.1783610135 0.0892720222 -0.0872675329 384 15.3200000000 0.0634492412 0.0491131223 0.0661605522 0.0149242073 0.0211370000 204889322 95654136 760807424 -0.1765824854 0.0898825303 -0.0851389840 385 15.3600000000 0.0638623983 0.0491514321 0.0661605522 0.0149250827 0.0209670000 204890130 95654136 760807424 -0.1748545319 0.0901983306 -0.0828750059 386 15.4000000000 0.0641225949 0.0491902175 0.0661605522 0.0149241057 0.0209660000 204892938 95654136 760807424 -0.1725237072 0.0928271115 -0.0810853317 387 15.4400000000 0.0642601699 0.0492291579 0.0661605522 0.0149230219 0.0244200000 204895546 95654136 760807424 -0.1694612950 0.0941574499 -0.0785544366 388 15.4800000000 0.0639395937 0.0492670714 0.0661605522 0.0149318107 0.0208540000 204896554 95654136 760807424 -0.1662847102 0.0947119445 -0.0762622133 389 15.5200000000 0.0633831397 0.0493033595 0.0661605522 0.0149358081 0.0210190000 204915398 95654136 760807424 -0.1638413668 0.0955759212 -0.0741758570 390 15.5600000000 0.0635225102 0.0493398189 0.0661605522 0.0149271726 0.0210080000 205071358 95654136 760807424 -0.1611409038 0.0957016125 -0.0712654591 391 15.6000000000 0.0635268837 0.0493761029 0.0661605522 0.0149240510 0.0210400000 205073966 95654136 760807424 -0.1586305946 0.0964780822 -0.0688960403 392 15.6400000000 0.0634470209 0.0494119981 0.0661605522 0.0149217374 0.0206370000 205076774 95654136 760807424 -0.1551995277 0.0964856222 -0.0663507730 393 15.6800000000 0.0637541115 0.0494484921 0.0661605522 0.0149196171 0.0206420000 205077582 95654136 760807424 -0.1530243605 0.0970565602 -0.0643662736 394 15.7200000000 0.0639127493 0.0494852034 0.0661605522 0.0149230274 0.0211020000 205080390 95654136 760807424 -0.1504482925 0.0984166339 -0.0624385513 395 15.7600000000 0.0640878677 0.0495221722 0.0661605522 0.0149257582 0.0207060000 205081198 95654136 760807424 -0.1479634643 0.0982729942 -0.0603285022 396 15.8000000000 0.0639035851 0.0495584889 0.0661605522 0.0149189318 0.0278530000 205084006 95654136 760807424 -0.1446980983 0.0990027934 -0.0585449822 397 15.8400000000 0.0634247065 0.0495934164 0.0661605522 0.0149107361 0.0211730000 205102434 95654136 760807424 -0.1413558871 0.0997544229 -0.0562868789 398 15.8800000000 0.0634145513 0.0496281428 0.0661605522 0.0149034086 0.0208350000 205258654 95654136 760807424 -0.1399690956 0.1005058587 -0.0564841628 399 15.9200000000 0.0630913526 0.0496618852 0.0661605522 0.0148990524 0.0209030000 205261262 95654136 760807424 -0.1366879493 0.1007393003 -0.0545366034 400 15.9600000000 0.0629462004 0.0496950960 0.0661605522 0.0148935019 0.0206380000 205262270 95654136 760807424 -0.1348829418 0.0998650417 -0.0538158976 401 16.0000000000 0.0626301020 0.0497273529 0.0661605522 0.0148811586 0.0209200000 205264878 95654136 760807424 -0.1327950954 0.0988691822 -0.0525351390 402 16.0400000000 0.0627785400 0.0497598185 0.0661605522 0.0148730097 0.0210060000 205267686 95654136 760807424 -0.1311289370 0.0988378525 -0.0513699688 403 16.0800000000 0.0625406206 0.0497915327 0.0661605522 0.0148715846 0.0241090000 205268494 95654136 760807424 -0.1295260936 0.0968331844 -0.0506980382 404 16.1200000000 0.0622163340 0.0498222871 0.0661605522 0.0148789219 0.0209470000 205271302 95654136 760807424 -0.1279346198 0.0961951762 -0.0503291413 405 16.1600000000 0.0622391514 0.0498529460 0.0661605522 0.0148797884 0.0209940000 205289094 95654136 760807424 -0.1257135868 0.0974142402 -0.0496740900 406 16.2000000000 0.0619604290 0.0498827674 0.0661605522 0.0148744754 0.0214460000 205445574 95654136 760807424 -0.1230762973 0.0975973010 -0.0484755710 407 16.2400000000 0.0611958466 0.0499105637 0.0661605522 0.0148838166 0.0237400000 205448182 95654136 760807424 -0.1196836457 0.0969556272 -0.0471742898 408 16.2800000000 0.0601881109 0.0499357538 0.0661605522 0.0148896166 0.0205630000 205449190 95654136 760807424 -0.1165867969 0.0962843224 -0.0463303030 409 16.3200000000 0.0595225878 0.0499591934 0.0661605522 0.0148817326 0.0205610000 205451798 95654136 760807424 -0.1127381623 0.0959843323 -0.0443434492 410 16.3600000000 0.0592642762 0.0499818888 0.0661605522 0.0148843397 0.0207650000 205454606 95654136 760807424 -0.1096191406 0.0950020701 -0.0426349305 411 16.3999999990 0.0594628304 0.0500049568 0.0661605522 0.0148962097 0.0207530000 205455414 95654136 760807424 -0.1071110517 0.0931767896 -0.0414175019 412 16.4400000000 0.0589616671 0.0500266963 0.0661605522 0.0148975797 0.0205090000 205458222 95654136 760807424 -0.1050963625 0.0925036594 -0.0405036546 413 16.4800000000 0.0586700514 0.0500476246 0.0661605522 0.0149031840 0.0243010000 205459030 95654136 760807424 -0.1019558161 0.0906969905 -0.0386241749 414 16.5200000000 0.0584781356 0.0500679881 0.0661605522 0.0148960542 0.0209870000 205476786 95654136 760807424 -0.0999412984 0.0906549320 -0.0380853564 415 16.5599999990 0.0587439574 0.0500888941 0.0661605522 0.0148844105 0.0272480000 205635158 95654136 760807424 -0.0980090797 0.0913975239 -0.0372579135 416 16.6000000000 0.0578948446 0.0501076584 0.0661605522 0.0148731490 0.0212510000 205636166 95654136 760807424 -0.0963302851 0.0905521512 -0.0364974141 417 16.6400000000 0.0576786399 0.0501258142 0.0661605522 0.0148644430 0.0208080000 205638774 95654136 760807424 -0.0939314887 0.0908936039 -0.0357737131 418 16.6800000000 0.0579761453 0.0501445949 0.0661605522 0.0148544545 0.0210530000 205639766 95654136 760807424 -0.0938834324 0.0897405148 -0.0357189439 419 16.7199999990 0.0576414205 0.0501624871 0.0661605522 0.0148484797 0.0208270000 205642374 95654136 760807424 -0.0917233378 0.0880975574 -0.0348209403 420 16.7600000000 0.0581696518 0.0501815518 0.0661605522 0.0148447664 0.0202370000 205645182 95654136 760807424 -0.0900367647 0.0874937549 -0.0335668959 421 16.8000000000 0.0577839911 0.0501996098 0.0661605522 0.0148476364 0.0206860000 205645990 95654136 760807424 -0.0883194953 0.0843059644 -0.0314872339 422 16.8400000000 0.0575751401 0.0502170874 0.0661605522 0.0148414378 0.0202710000 205648798 95654136 760807424 -0.0864062980 0.0850222036 -0.0308360998 423 16.8799999990 0.0572600625 0.0502337374 0.0661605522 0.0148377563 0.0200200000 205651406 95654136 760807424 -0.0840713531 0.0839230046 -0.0301416516 424 16.9200000000 0.0575179197 0.0502509171 0.0661605522 0.0148280699 0.0308540000 205652414 95654136 760807424 -0.0818676651 0.0825838298 -0.0292917807 425 16.9600000000 0.0570713617 0.0502669652 0.0661605522 0.0148304821 0.0214320000 205655022 95654136 760807424 -0.0785643309 0.0831267610 -0.0276819468 426 17.0000000000 0.0575205013 0.0502839923 0.0661605522 0.0148288804 0.0202740000 205656030 95654136 760807424 -0.0773800537 0.0782731771 -0.0258824900 427 17.0400000000 0.0565970019 0.0502987769 0.0661605522 0.0148248265 0.0204350000 205658638 95654136 760807424 -0.0734328777 0.0769262090 -0.0250367131 428 17.0800000000 0.0558185950 0.0503116736 0.0661605522 0.0148176787 0.0199950000 205661430 95654136 760807424 -0.0695910156 0.0769530535 -0.0240959320 429 17.1200000000 0.0547765307 0.0503220812 0.0661605522 0.0148135669 0.0202060000 205662238 95654136 760807424 -0.0673044845 0.0745587498 -0.0233101491 430 17.1600000000 0.0545946918 0.0503320175 0.0661605522 0.0148068120 0.0234310000 205665046 95654136 760807424 -0.0653514266 0.0759486035 -0.0226646680 431 17.2000000000 0.0555217229 0.0503440586 0.0661605522 0.0147994225 0.0203840000 205665854 95654136 760807424 -0.0635837168 0.0764833391 -0.0224024802 432 17.2400000000 0.0556091666 0.0503562464 0.0661605522 0.0147956712 0.0266590000 205668662 95654136 760807424 -0.0608032122 0.0721469298 -0.0209841449 433 17.2800000000 0.0554963276 0.0503681172 0.0661605522 0.0148067262 0.0337680000 205671270 95654136 760807424 -0.0596188828 0.0679966956 -0.0194070544 434 17.3200000000 0.0531397238 0.0503745034 0.0661605522 0.0148172856 0.0222240000 205672278 95654136 760807424 -0.0548700467 0.0645218864 -0.0178622548 435 17.3600000000 0.0541569777 0.0503831987 0.0661605522 0.0148180792 0.0202180000 205674886 95654136 760807424 -0.0537640080 0.0616555549 -0.0176500455 436 17.4000000000 0.0531738363 0.0503895993 0.0661605522 0.0148160696 0.0201710000 205675894 95654136 760807424 -0.0526974574 0.0579238459 -0.0164195988 437 17.4400000000 0.0539261699 0.0503976921 0.0661605522 0.0148092448 0.0200820000 205678502 95654136 760807424 -0.0522464253 0.0580854341 -0.0152794020 438 17.4800000000 0.0531307794 0.0504039321 0.0661605522 0.0148247452 0.0200470000 205681310 95654136 760807424 -0.0518545173 0.0564517118 -0.0136604263 439 17.5200000000 0.0523102283 0.0504082744 0.0661605522 0.0148380279 0.0200680000 205682118 95654136 760807424 -0.0528525785 0.0531733409 -0.0133638578 440 17.5600000000 0.0488699377 0.0504047782 0.0661605522 0.0148527639 0.0200050000 205684926 95654136 760807424 -0.0541034155 0.0448596068 -0.0121490601 441 17.6000000000 0.0478937477 0.0503990843 0.0661605522 0.0148698885 0.0200170000 205687534 95654136 760807424 -0.0553090870 0.0415198542 -0.0107794460 442 17.6400000000 0.0457805544 0.0503886351 0.0661605522 0.0149602426 0.0199360000 205688542 95654136 760807424 -0.0613501072 0.0412812941 -0.0113826059 443 17.6800000000 0.0437722355 0.0503736996 0.0661605522 0.0149681965 0.0200380000 205691150 95654136 760807424 -0.0647069514 0.0368958861 -0.0106514217 444 17.7200000000 0.0427677706 0.0503565692 0.0661605522 0.0149822646 0.0199340000 205692158 95654136 760807424 -0.0667806566 0.0316349715 -0.0082484456 445 17.7600000000 0.0430173613 0.0503400766 0.0661605522 0.0149858521 0.0199320000 205694734 95654136 760807424 -0.0684308857 0.0308196247 -0.0084266020 446 17.8000000000 0.0433214083 0.0503243397 0.0661605522 0.0149981343 0.0199090000 205697542 95654136 760807424 -0.0706015825 0.0266220458 -0.0062237773 447 17.8400000000 0.0447814204 0.0503119394 0.0661605522 0.0149934408 0.0224610000 205698350 95654136 760807424 -0.0708975568 0.0227596499 -0.0042693857 448 17.8800000000 0.0464890748 0.0503034062 0.0661605522 0.0149830762 0.0206840000 205701158 95654136 760807424 -0.0709156841 0.0239677988 -0.0032616367 449 17.9200000000 0.0461953320 0.0502942568 0.0661605522 0.0149705357 0.0199000000 205701966 95654136 760807424 -0.0716895387 0.0244801715 -0.0022561615 450 17.9600000000 0.0480476730 0.0502892644 0.0661605522 0.0149555090 0.0237050000 205704774 95654136 760807424 -0.0719729364 0.0236721709 -0.0008517200 451 18.0000000000 0.0482967831 0.0502848465 0.0661605522 0.0149483145 0.0199300000 205707382 95654136 760807424 -0.0726224631 0.0220029708 0.0017064990 452 18.0400000000 0.0488396436 0.0502816491 0.0661605522 0.0149450473 0.0197590000 205708390 95654136 760807424 -0.0724645033 0.0208659526 0.0047667059 453 18.0800000000 0.0483105704 0.0502772980 0.0661605522 0.0149380035 0.0197590000 205710998 95654136 760807424 -0.0718191192 0.0169604793 0.0083780736 454 18.1200000000 0.0486546382 0.0502737238 0.0661605522 0.0149239116 0.0265820000 205712006 95654136 760807424 -0.0711855441 0.0184505023 0.0115717575 455 18.1600000000 0.0495749414 0.0502721880 0.0661605522 0.0149085748 0.0201260000 205714614 95654136 760807424 -0.0699814558 0.0188380852 0.0145122260 456 18.2000000000 0.0516122021 0.0502751267 0.0661605522 0.0149014171 0.0231890000 205717422 95654136 760807424 -0.0708001480 0.0187405925 0.0194131937 457 18.2400000000 0.0520862192 0.0502790897 0.0661605522 0.0148905418 0.0198800000 205718230 95654136 760807424 -0.0712601691 0.0220560171 0.0234591141 458 18.2800000000 0.0516758673 0.0502821394 0.0661605522 0.0148852252 0.0197250000 205721038 95654136 760807424 -0.0710286275 0.0188547820 0.0312518291 459 18.3200000000 0.0532058850 0.0502885092 0.0661605522 0.0148721495 0.0234070000 205723646 95654136 760807424 -0.0701989457 0.0176209006 0.0395738855 460 18.3600000000 0.0480471030 0.0502836366 0.0661605522 0.0148604786 0.0199480000 205724654 95654136 760807424 -0.0646184534 0.0180880073 0.0447570160 461 18.4000000000 0.0460644662 0.0502744844 0.0661605522 0.0148458201 0.0198940000 205727262 95654136 760807424 -0.0619183779 0.0175090041 0.0516376719 462 18.4400000000 0.0442513488 0.0502614473 0.0661605522 0.0148311884 0.0198150000 205728270 95654136 760807424 -0.0565571561 0.0188407730 0.0582287572 463 18.4800000000 0.0487724915 0.0502582314 0.0661605522 0.0148157958 0.0197950000 205730878 95654136 760807424 -0.0594992414 0.0257012341 0.0655599013 464 18.5200000000 0.0485210866 0.0502544876 0.0661605522 0.0148017137 0.0198430000 205733686 95654136 760807424 -0.0583455749 0.0291403644 0.0730744079 465 18.5600000000 0.0478914380 0.0502494057 0.0661605522 0.0147903106 0.0230610000 205734494 95654136 760807424 -0.0537574030 0.0367939882 0.0900546014 466 18.6000000000 0.0513676666 0.0502518054 0.0661605522 0.0147759230 0.0200390000 205737302 95654136 760807424 -0.0532654002 0.0438763797 0.1007728428 467 18.6400000000 0.0528598204 0.0502573901 0.0661605522 0.0147605579 0.0198850000 205738110 95654136 760807424 -0.0511313006 0.0467855223 0.1113618538 468 18.6800000000 0.0537960082 0.0502649512 0.0661605522 0.0147462023 0.0198660000 205740918 95654136 760807424 -0.0489120968 0.0542667881 0.1208078265 469 18.7200000000 0.0536160581 0.0502720964 0.0661605522 0.0147374338 0.0198570000 205743526 95654136 760807424 -0.0478711016 0.0564476959 0.1327586472 470 18.7600000000 0.0549331829 0.0502820136 0.0661605522 0.0147305523 0.0198850000 205744566 95654136 760807424 -0.0463779457 0.0633221939 0.1439983100 471 18.8000000000 0.0575726591 0.0502974927 0.0661605522 0.0147217163 0.0230190000 205747174 95654136 760807424 -0.0459492728 0.0724411011 0.1558563262 472 18.8400000000 0.0591473989 0.0503162425 0.0661605522 0.0147066293 0.0200530000 205748182 95654136 760807424 -0.0452313013 0.0777847692 0.1678749025 473 18.8800000000 0.0576205887 0.0503316851 0.0661605522 0.0146912359 0.0199210000 205750790 95654136 760807424 -0.0408243202 0.0848856717 0.1808593273 474 18.9200000000 0.0542696416 0.0503399930 0.0661605522 0.0146773068 0.0199360000 205753598 95654136 760807424 -0.0351380929 0.0883822665 0.1927927136 475 18.9600000000 0.0546344705 0.0503490340 0.0661605522 0.0146729673 0.0198680000 205754406 95654136 760807424 -0.0300584808 0.0962052196 0.2040736377 476 19.0000000000 0.0549299456 0.0503586578 0.0661605522 0.0146632080 0.0243110000 205757214 95654136 760807424 -0.0264832526 0.0995067805 0.2170936465 477 19.0400000000 0.0544216856 0.0503671757 0.0661605522 0.0146514245 0.0202180000 205759822 95654136 760807424 -0.0231806133 0.1078528389 0.2275143415 478 19.0800000000 0.0552423671 0.0503773748 0.0661605522 0.0146376371 0.0200420000 205760830 95654136 760807424 -0.0210085232 0.1141336337 0.2408789247 479 19.1200000000 0.0528799482 0.0503825994 0.0661605522 0.0146253315 0.0199710000 205763438 95654136 760807424 -0.0176667087 0.1128751710 0.2534642816 480 19.1600000000 0.0512162186 0.0503843361 0.0661605522 0.0146153844 0.0207570000 205764462 95654136 760807424 -0.0120573919 0.1178796887 0.2630251646 481 19.2000000000 0.0480485819 0.0503794801 0.0661605522 0.0146003327 0.0200090000 205767070 95654136 760807424 -0.0080784373 0.1263886094 0.2732909620 482 19.2400000000 0.0479056574 0.0503743477 0.0661605522 0.0145961819 0.0199940000 205769878 95654136 760807424 -0.0037213354 0.1313234717 0.2842808068 483 19.2800000000 0.0482723899 0.0503699958 0.0661605522 0.0145986605 0.0199620000 205770686 95654136 760807424 -0.0012462470 0.1324488521 0.2958261669 484 19.3200000000 0.0499638729 0.0503691567 0.0661605522 0.0146001216 0.0200270000 205773494 95654136 760807424 0.0006729242 0.1343689263 0.3073807061 485 19.3600000000 0.0488997065 0.0503661269 0.0661605522 0.0145867714 0.0200230000 205774302 95654136 760807424 0.0023926599 0.1353671402 0.3193405569 486 19.4000000000 0.0491303280 0.0503635841 0.0661605522 0.0145717947 0.0232620000 205777110 95654136 760807424 0.0052509569 0.1417016685 0.3311999738 487 19.4400000000 0.0495926812 0.0503620011 0.0661605522 0.0145570332 0.0202410000 205779734 95654136 760807424 0.0063510677 0.1477716267 0.3425080478 488 19.4800000000 0.0496326201 0.0503605065 0.0661605522 0.0145426697 0.0200860000 205780742 95654136 760807424 0.0074859713 0.1490518600 0.3539564013 489 19.5200000000 0.0477606803 0.0503551899 0.0661605522 0.0145294531 0.0201440000 205783482 95654136 760807424 0.0101069286 0.1565191150 0.3637557626 490 19.5600000000 0.0496946685 0.0503538419 0.0661605522 0.0145152993 0.0203110000 205784886 95654136 760807424 0.0097541576 0.1644333303 0.3740400672 491 19.6000000000 0.0496158451 0.0503523388 0.0661605522 0.0145012651 0.0308560000 205787626 95654136 760807424 0.0142479017 0.1727746427 0.3836976588 492 19.6400000000 0.0501654819 0.0503519590 0.0661605522 0.0144869747 0.0217230000 205790566 95654136 760807424 0.0149794389 0.1787965447 0.3929061592 493 19.6800000000 0.0483651496 0.0503479290 0.0661605522 0.0144730051 0.0208550000 205791374 95654136 760807424 0.0165114645 0.1798397005 0.4037500918 494 19.7200000000 0.0473479629 0.0503418562 0.0661605522 0.0144585021 0.0208990000 205794182 95654136 760807424 0.0168637000 0.1796740741 0.4142900109 495 19.7600000000 0.0453685336 0.0503318091 0.0661605522 0.0144454130 0.0291460000 205796790 95654136 760807424 0.0187160000 0.1829571575 0.4247580171 496 19.8000000000 0.0450949930 0.0503212510 0.0661605522 0.0144324525 0.0215710000 205797798 95654136 760807424 0.0199090764 0.1906739771 0.4348903596 497 19.8400000000 0.0466440096 0.0503138521 0.0661605522 0.0144193873 0.0210880000 205800406 95654136 760807424 0.0200065374 0.1994456649 0.4456708729 498 19.8800000000 0.0464979410 0.0503061896 0.0661605522 0.0144093794 0.0210000000 205801414 95654136 760807424 0.0197936110 0.2073051333 0.4558245838 499 19.9200000000 0.0460838601 0.0502977280 0.0661605522 0.0144013519 0.0210330000 205804022 95654136 760807424 0.0200927090 0.2141697854 0.4672146142 500 19.9600000000 0.0460800827 0.0502892928 0.0661605522 0.0143905136 0.0210140000 205806830 95654136 760807424 0.0197294168 0.2167436033 0.4779398441 501 20.0000000000 0.0444551781 0.0502776478 0.0661605522 0.0143820433 0.0210910000 205807638 95654136 760807424 0.0200856123 0.2191530317 0.4884646535 502 20.0400000000 0.0449926704 0.0502671200 0.0661605522 0.0143720935 0.0246200000 205810446 95654136 760807424 0.0174140781 0.2235702723 0.4993479252 503 20.0800000000 0.0426943824 0.0502520648 0.0661605522 0.0143625638 0.0211800000 205811254 95654136 760807424 0.0174012184 0.2288921624 0.5102324486 504 20.1200000000 0.0433508754 0.0502383720 0.0661605522 0.0143483040 0.0237800000 205814062 95654136 760807424 0.0140853878 0.2342658490 0.5207726359 505 20.1600000000 0.0439521931 0.0502259241 0.0661605522 0.0143344929 0.0211450000 205816670 95654136 760807424 0.0124430386 0.2413633913 0.5315678120 506 20.2000000000 0.0451552309 0.0502159030 0.0661605522 0.0143242057 0.0210690000 205817678 95654136 760807424 0.0100157652 0.2516469955 0.5417221189 507 20.2400000000 0.0461137481 0.0502078119 0.0661605522 0.0143194590 0.0210590000 205820286 95654136 760807424 0.0073699146 0.2581750154 0.5519871712 508 20.2800000000 0.0463419929 0.0502002021 0.0661605522 0.0143178136 0.0210050000 205821294 95654136 760807424 0.0053621577 0.2632630169 0.5619644523 509 20.3200000000 0.0467405058 0.0501934050 0.0661605522 0.0143280294 0.0264680000 205823902 95654136 760807424 0.0024088256 0.2700850666 0.5717442036 510 20.3600000000 0.0467729941 0.0501866983 0.0661605522 0.0143265050 0.0214310000 205826710 95654136 760807424 -0.0003584933 0.2755411267 0.5815621018 511 20.4000000000 0.0469212644 0.0501803080 0.0661605522 0.0143268048 0.0315680000 205827518 95654136 760807424 -0.0021629659 0.2807087898 0.5904655457 512 20.4400000000 0.0477509946 0.0501755633 0.0661605522 0.0143307071 0.0246190000 205830326 95654136 760807424 -0.0023941516 0.2882964611 0.5988528728 513 20.4800000000 0.0480508022 0.0501714215 0.0661605522 0.0143303103 0.0267150000 205877990 95654136 760807424 -0.0035199076 0.2932049632 0.6073290706 514 20.5200000000 0.0483948141 0.0501679650 0.0661605522 0.0143315801 0.0215130000 205981398 95654136 760807424 -0.0050594085 0.2956475914 0.6160125136 515 20.5600000000 0.0467829108 0.0501613921 0.0661605522 0.0143418050 0.0212730000 205984006 95654136 760807424 -0.0057795169 0.2952508628 0.6231160760 516 20.6000000000 0.0461450219 0.0501536084 0.0661605522 0.0143574819 0.0212650000 205985014 95654136 760807424 -0.0062992573 0.2996085286 0.6305219531 517 20.6400000000 0.0470004492 0.0501475095 0.0661605522 0.0143700230 0.0213170000 205987622 95654136 760807424 -0.0066443416 0.3037760258 0.6375036836 518 20.6800000000 0.0477566496 0.0501428939 0.0661605522 0.0143873718 0.0212860000 205990430 95654136 760807424 -0.0074015441 0.3071040809 0.6441726089 519 20.7200000000 0.0476546064 0.0501380995 0.0661605522 0.0144050841 0.0245470000 205991238 95654136 760807424 -0.0056860293 0.3105023801 0.6499963403 520 20.7600000000 0.0477947108 0.0501335930 0.0661605522 0.0144338200 0.0248820000 205994046 95654136 760807424 -0.0044135153 0.3136743605 0.6556358933 521 20.8000000000 0.0477223396 0.0501289649 0.0661605522 0.0144597596 0.0210100000 205994854 95654136 760807424 -0.0022387013 0.3144314587 0.6610025764 522 20.8400000000 0.0462935641 0.0501216174 0.0661605522 0.0144869276 0.0212400000 205997662 95654136 760807424 0.0001898855 0.3135789037 0.6661230922 523 20.8800000000 0.0453780442 0.0501125475 0.0661605522 0.0145166813 0.0261230000 206000270 95654136 760807424 0.0022482160 0.3121356070 0.6706423163 524 20.9200000000 0.0446224175 0.0501020701 0.0661605522 0.0145537596 0.0211240000 206001278 95654136 760807424 0.0046089496 0.3145210445 0.6748514175 525 20.9600000000 0.0444301479 0.0500912664 0.0661605522 0.0145708433 0.0208910000 206003886 95654136 760807424 0.0075360970 0.3159221709 0.6790758967 526 21.0000000000 0.0434953570 0.0500787267 0.0661605522 0.0145812255 0.0207990000 206004894 95654136 760807424 0.0113524022 0.3147872090 0.6828657389 527 21.0400000000 0.0439323001 0.0500670636 0.0661605522 0.0145954670 0.0247490000 206007502 95654136 760807424 0.0141757615 0.3167747557 0.6864920855 528 21.0800000000 0.0432915315 0.0500542312 0.0661605522 0.0146097279 0.0209090000 206010310 95654136 760807424 0.0187167376 0.3182886839 0.6894828081 529 21.1200000000 0.0436690189 0.0500421609 0.0661605522 0.0146122184 0.0207030000 206011118 95654136 760807424 0.0212538615 0.3187085390 0.6924211979 530 21.1600000000 0.0441813171 0.0500311027 0.0661605522 0.0146151512 0.0207670000 206013926 95654136 760807424 0.0238738377 0.3198996186 0.6953544021 531 21.2000000000 0.0426683351 0.0500172368 0.0661605522 0.0146252246 0.0206970000 206016534 95654136 760807424 0.0284847058 0.3188392818 0.6980343461 532 21.2400000000 0.0422372296 0.0500026127 0.0661605522 0.0146416122 0.0239840000 206017542 95654136 760807424 0.0329134054 0.3182857633 0.7003099918 533 21.2800000000 0.0423569568 0.0499882682 0.0661605522 0.0146555399 0.0207070000 206020150 95654136 760807424 0.0361033008 0.3181128502 0.7024643421 534 21.3200000000 0.0420655459 0.0499734316 0.0661605522 0.0146717580 0.0248020000 206021158 95654136 760807424 0.0406156033 0.3181410134 0.7045972347 535 21.3600000000 0.0419319943 0.0499584009 0.0661605522 0.0146878912 0.0208110000 206023766 95654136 760807424 0.0444955938 0.3186128438 0.7068116665 536 21.4000000000 0.0414829366 0.0499425884 0.0661605522 0.0147050138 0.0205540000 206026574 95654136 760807424 0.0488023013 0.3190553188 0.7088909149 537 21.4400000000 0.0421762094 0.0499281259 0.0661605522 0.0147211829 0.0205270000 206027382 95654136 760807424 0.0514518358 0.3190623224 0.7111929059 538 21.4800000000 0.0398652926 0.0499094218 0.0661605522 0.0147300651 0.0245070000 206030190 95654136 760807424 0.0579410009 0.3185049593 0.7129122615 539 21.5200000000 0.0414935872 0.0498938080 0.0661605522 0.0147427338 0.0206960000 206030998 95654136 760807424 0.0629867315 0.3217966557 0.7148181796 540 21.5600000000 0.0417232066 0.0498786772 0.0661605522 0.0147418284 0.0205320000 206033806 95654136 760807424 0.0653474778 0.3212931454 0.7171162367 541 21.6000000000 0.0428339839 0.0498656556 0.0661605522 0.0147483133 0.0205980000 206036414 95654136 760807424 0.0697126240 0.3226528764 0.7192478180 542 21.6400000000 0.0429013558 0.0498528064 0.0661605522 0.0147577195 0.0238320000 206037422 95654136 760807424 0.0729713514 0.3237567246 0.7211564779 543 21.6800000000 0.0437611341 0.0498415878 0.0661605522 0.0147719325 0.0206650000 206040030 95654136 760807424 0.0762695298 0.3251886666 0.7233085036 544 21.7200000000 0.0442503616 0.0498313098 0.0661605522 0.0147838909 0.0231920000 206041038 95654136 760807424 0.0792924613 0.3264060616 0.7254894376 545 21.7600000000 0.0422930047 0.0498174781 0.0661605522 0.0147952350 0.0205390000 206043646 95654136 760807424 0.0846225694 0.3265973628 0.7274054885 546 21.8000000000 0.0416704863 0.0498025568 0.0661605522 0.0148716058 0.0204920000 206046454 95654136 760807424 0.0913877189 0.3279112577 0.7313532233 547 21.8400000000 0.0427312292 0.0497896294 0.0661605522 0.0148768408 0.0241110000 206047262 95654136 760807424 0.0940085799 0.3291836679 0.7341112494 548 21.8800000000 0.0430250503 0.0497772852 0.0661605522 0.0148887988 0.0205830000 206050070 95654136 760807424 0.0981821865 0.3313937783 0.7361511588 549 21.9200000000 0.0413315333 0.0497619014 0.0661605522 0.0149075905 0.0205270000 206052678 95654136 760807424 0.1027890295 0.3318997025 0.7380499244 550 21.9600000000 0.0405810252 0.0497452088 0.0661605522 0.0149228952 0.0204110000 206053686 95654136 760807424 0.1087291315 0.3324293196 0.7394691110 551 22.0000000000 0.0407250412 0.0497288383 0.0661605522 0.0149489722 0.0204090000 206056294 95654136 760807424 0.1125373021 0.3356075883 0.7410445213 552 22.0400000000 0.0431176126 0.0497168615 0.0661605522 0.0149583966 0.0204170000 206057302 95654136 760807424 0.1157676354 0.3400063813 0.7427412868 553 22.0800000000 0.0448432639 0.0497080484 0.0661605522 0.0149557945 0.0204390000 206059910 95654136 760807424 0.1194627285 0.3414062858 0.7443773746 554 22.1200000000 0.0437840037 0.0496973552 0.0661605522 0.0149488074 0.0235550000 206062718 95654136 760807424 0.1234119087 0.3398630619 0.7460445762 555 22.1600000000 0.0429934040 0.0496852760 0.0661605522 0.0149412413 0.0203640000 206063526 95654136 760807424 0.1296953410 0.3408727050 0.7471931577 556 22.2000000000 0.0415453389 0.0496706358 0.0661605522 0.0149386943 0.0203230000 206066334 95654136 760807424 0.1359628290 0.3429739475 0.7479736209 557 22.2400000000 0.0419986770 0.0496568621 0.0661605522 0.0149352315 0.0202410000 206067142 95654136 760807424 0.1398919821 0.3447634578 0.7496008277 558 22.2800000000 0.0419646800 0.0496430769 0.0661605522 0.0149339635 0.0202380000 206069950 95654136 760807424 0.1446436346 0.3472322822 0.7510976195 559 22.3200000000 0.0393688381 0.0496246972 0.0661605522 0.0149315748 0.0203050000 206072558 95654136 760807424 0.1533661932 0.3491489589 0.7518714666 560 22.3600000000 0.0396433882 0.0496068734 0.0661605522 0.0149263964 0.0241170000 206073566 95654136 760807424 0.1560351849 0.3494315445 0.7544958591 561 22.4000000000 0.0403090492 0.0495902998 0.0661605522 0.0149246299 0.0203340000 206076174 95654136 760807424 0.1607179791 0.3528631628 0.7563791871 562 22.4400000000 0.0393876098 0.0495721455 0.0661605522 0.0149227348 0.0202240000 206077182 95654136 760807424 0.1684235483 0.3567663133 0.7571133971 563 22.4800000000 0.0388726592 0.0495531411 0.0661605522 0.0149157930 0.0201360000 206079790 95654136 760807424 0.1738504171 0.3591858745 0.7578738332 564 22.5200000000 0.0404775254 0.0495370496 0.0661605522 0.0149051920 0.0237020000 206082598 95654136 760807424 0.1766274273 0.3617677689 0.7600287199 565 22.5600000000 0.0402676947 0.0495206436 0.0661605522 0.0148945277 0.0202340000 206083406 95654136 760807424 0.1799869835 0.3623799682 0.7614395618 566 22.6000000000 0.0400737748 0.0495039531 0.0661605522 0.0148861304 0.0201770000 206086214 95654136 760807424 0.1854409575 0.3655586839 0.7628128529 567 22.6400000000 0.0423389822 0.0494913164 0.0661605522 0.0148738857 0.0201750000 206088822 95654136 760807424 0.1873945743 0.3683643341 0.7644917965 568 22.6800000000 0.0420354120 0.0494781898 0.0661605522 0.0148644485 0.0236380000 206089830 95654136 760807424 0.1921380907 0.3702415526 0.7656837702 569 22.7200000000 0.0412472263 0.0494637242 0.0661605522 0.0148536435 0.0210820000 206092438 95654136 760807424 0.1983849555 0.3713877797 0.7656376362 570 22.7600000000 0.0409826078 0.0494488450 0.0661605522 0.0148433842 0.0201610000 206093446 95654136 760807424 0.2031668723 0.3743494451 0.7664904594 571 22.8000000000 0.0429291576 0.0494374270 0.0661605522 0.0148308337 0.0201390000 206096054 95654136 760807424 0.2057501525 0.3775097132 0.7677851319 572 22.8400000000 0.0438049510 0.0494275800 0.0661605522 0.0148183406 0.0201140000 206098862 95654136 760807424 0.2091141045 0.3792508245 0.7686282992 573 22.8800000000 0.0394694209 0.0494102010 0.0661605522 0.0148079664 0.0201360000 206099670 95654136 760807424 0.2158613950 0.3781906068 0.7681217194 574 22.9200000000 0.0406014286 0.0493948547 0.0661605522 0.0147971884 0.0228890000 206161250 95654136 760807424 0.2207416892 0.3832727671 0.7684543133 575 22.9600000000 0.0385585092 0.0493760089 0.0661605522 0.0147846509 0.0201640000 206273794 95654136 760807424 0.2251481712 0.3837454021 0.7689626217 576 23.0000000000 0.0418222286 0.0493628947 0.0661605522 0.0147719876 0.0200990000 206276602 95654136 760807424 0.2277566791 0.3904219866 0.7699853778 577 23.0400000000 0.0373503864 0.0493420758 0.0661605522 0.0147594322 0.0200470000 206279210 95654136 760807424 0.2343286723 0.3905199766 0.7696747184 578 23.0800000000 0.0411984399 0.0493279865 0.0661605522 0.0147474904 0.0200670000 206280218 95654136 760807424 0.2349800766 0.3954130113 0.7704750299 579 23.1200000000 0.0445864461 0.0493197973 0.0661605522 0.0147348984 0.0200870000 206282826 95654136 760807424 0.2348427474 0.3998596072 0.7710871696 580 23.1600000000 0.0420015343 0.0493071796 0.0661605522 0.0147233858 0.0239110000 206283834 95654136 760807424 0.2420210689 0.4047106504 0.7705659866 581 23.2000000000 0.0398303121 0.0492908683 0.0661605522 0.0147109208 0.0202340000 206286442 95654136 760807424 0.2476662844 0.4082776606 0.7697625160 582 23.2400000000 0.0359189212 0.0492678924 0.0661605522 0.0146987508 0.0200720000 206289250 95654136 760807424 0.2529226243 0.4088744521 0.7695956230 583 23.2800000000 0.0356740244 0.0492445753 0.0661605522 0.0146862589 0.0240120000 206348310 95654136 760807424 0.2576915920 0.4150591493 0.7689260840 584 23.3200000000 0.0361386314 0.0492221336 0.0661605522 0.0146747601 0.0203200000 206463146 95654136 760807424 0.2597703636 0.4181140065 0.7687959075 585 23.3600000000 0.0373972654 0.0492019202 0.0661605522 0.0146632741 0.0209020000 206465754 95654136 760807424 0.2617517710 0.4212995768 0.7686133385 586 23.4000000000 0.0372469909 0.0491815193 0.0661605522 0.0146517220 0.0201280000 206466762 95654136 760807424 0.2621543109 0.4224709272 0.7692145705 587 23.4400000000 0.0384117328 0.0491631721 0.0661605522 0.0146395747 0.0201170000 206469370 95654136 760807424 0.2649966180 0.4276600778 0.7690684199 588 23.4800000000 0.0400447026 0.0491476645 0.0661605522 0.0146281245 0.0200940000 206470378 95654136 760807424 0.2647893727 0.4307883084 0.7686554790 589 23.5200000000 0.0408237614 0.0491335323 0.0661605522 0.0146163214 0.0201210000 206531534 95654136 760807424 0.2664603889 0.4335704446 0.7687696218 590 23.5600000000 0.0380940847 0.0491148213 0.0661605522 0.0146041208 0.0200960000 206646566 95654136 760807424 0.2696068585 0.4329627454 0.7689300179 591 23.6000000000 0.0379075482 0.0490958581 0.0661605522 0.0145919041 0.0200810000 206647374 95654136 760807424 0.2712588012 0.4350767732 0.7697591782 592 23.6400000000 0.0389999710 0.0490788042 0.0661605522 0.0145801542 0.0201250000 206650182 95654136 760807424 0.2732148468 0.4383019805 0.7698386312 593 23.6800000000 0.0389078893 0.0490616526 0.0661605522 0.0145717561 0.0201810000 206650990 95654136 760807424 0.2765422165 0.4411320090 0.7699099779 594 23.7200000000 0.0396550559 0.0490458166 0.0661605522 0.0145595526 0.0201850000 206711650 95654136 760807424 0.2779881656 0.4430332184 0.7707641721 595 23.7600000000 0.0383314453 0.0490278092 0.0661605522 0.0145476978 0.0201480000 206826646 95654136 760807424 0.2795738876 0.4431576431 0.7712654471 596 23.8000000000 0.0388559885 0.0490107424 0.0661605522 0.0145357954 0.0301690000 206827654 95654136 760807424 0.2824598253 0.4479679465 0.7714235783 597 23.8400000000 0.0381948985 0.0489926254 0.0661605522 0.0145240082 0.0209400000 206830262 95654136 760807424 0.2839167714 0.4494306147 0.7718550563 598 23.8800000000 0.0377752073 0.0489738672 0.0661605522 0.0145123143 0.0202880000 206831270 95654136 760807424 0.2849673331 0.4500944018 0.7733369470 599 23.9200000000 0.0374263600 0.0489545892 0.0661605522 0.0145015396 0.0200580000 206833878 95654136 760807424 0.2861662805 0.4517217577 0.7741730809 600 23.9600000000 0.0364273936 0.0489337106 0.0661605522 0.0144908981 0.0202780000 206836686 95654136 760807424 0.2865302265 0.4524030983 0.7748561502 601 24.0000000000 0.0394225456 0.0489178850 0.0661605522 0.0144840360 0.0201350000 206896054 95654136 760807424 0.2860300839 0.4585800469 0.7772212029 602 24.0400000000 0.0378760807 0.0488995431 0.0661605522 0.0144727625 0.0200220000 207011478 95654136 760807424 0.2885609269 0.4588556290 0.7763357162 603 24.0800000000 0.0394325368 0.0488838433 0.0661605522 0.0144635151 0.0199300000 207014086 95654136 760807424 0.2878874540 0.4609060884 0.7777078152 604 24.1200000000 0.0407849327 0.0488704345 0.0661605522 0.0144521075 0.0199650000 207015094 95654136 760807424 0.2896343470 0.4646487236 0.7783740163 605 24.1600000000 0.0394630209 0.0488548851 0.0661605522 0.0144406649 0.0199840000 207017702 95654136 760807424 0.2898543775 0.4665306509 0.7798015475 606 24.2000000000 0.0393194146 0.0488391500 0.0661605522 0.0144287417 0.0237040000 207018710 95654136 760807424 0.2907441556 0.4682287276 0.7805354595 607 24.2400000000 0.0398235284 0.0488242972 0.0661605522 0.0144172704 0.0200510000 207021318 95654136 760807424 0.2929823399 0.4714300931 0.7806193233 608 24.2800000000 0.0373833738 0.0488054799 0.0661605522 0.0144054665 0.0199300000 207024126 95654136 760807424 0.2949990332 0.4706395268 0.7808576226 609 24.3200000000 0.0370963514 0.0487862531 0.0661605522 0.0143940766 0.0198490000 207024934 95654136 760807424 0.2944000363 0.4703691304 0.7826474309 610 24.3600000000 0.0397831947 0.0487714940 0.0661605522 0.0143823107 0.0199080000 207027742 95654136 760807424 0.2933900952 0.4753812551 0.7832171321 611 24.4000000000 0.0376820751 0.0487533444 0.0661605522 0.0143706428 0.0198910000 207028550 95654136 760807424 0.2955935299 0.4760659933 0.7832637429 612 24.4400000000 0.0382555202 0.0487361910 0.0661605522 0.0143590172 0.0198900000 207031358 95654136 760807424 0.2937012613 0.4773121178 0.7847602367 613 24.4800000000 0.0373543911 0.0487176237 0.0661605522 0.0143476084 0.0199200000 207033966 95654136 760807424 0.2948180139 0.4788216650 0.7852142453 614 24.5200000000 0.0378261991 0.0486998852 0.0661605522 0.0143366040 0.0199830000 207034974 95654136 760807424 0.2934539020 0.4804587662 0.7857539058 615 24.5600000000 0.0377551652 0.0486820889 0.0661605522 0.0143258855 0.0200400000 207094886 95654136 760807424 0.2927993238 0.4831771851 0.7872118354 616 24.6000000000 0.0367133282 0.0486626591 0.0661605522 0.0143148919 0.0199850000 207208962 95654136 760807424 0.2924430072 0.4841480553 0.7881278396 617 24.6400000000 0.0386933647 0.0486465014 0.0661605522 0.0143036677 0.0208020000 207211570 95654136 760807424 0.2913299203 0.4888535738 0.7887169719 618 24.6800000000 0.0387667865 0.0486305148 0.0661605522 0.0142945517 0.0201100000 207214378 95654136 760807424 0.2895254493 0.4895758331 0.7913811803 619 24.7200000000 0.0388375930 0.0486146943 0.0661605522 0.0142850128 0.0200080000 207215186 95654136 760807424 0.2862984836 0.4905136824 0.7939452529 620 24.7600000000 0.0400375165 0.0486008601 0.0661605522 0.0142769518 0.0201290000 207217994 95654136 760807424 0.2843088508 0.4934775531 0.7946689129 621 24.8000000000 0.0405065976 0.0485878259 0.0661605522 0.0142692012 0.0239090000 207220602 95654136 760807424 0.2835105956 0.4972819388 0.7962496877 622 24.8400000000 0.0397644304 0.0485736403 0.0661605522 0.0142622086 0.0202780000 207221610 95654136 760807424 0.2812585831 0.4978032410 0.7987226248 623 24.8800000000 0.0398161002 0.0485595833 0.0661605522 0.0142578603 0.0201580000 207224218 95654136 760807424 0.2820452452 0.5036550760 0.7997397184 624 24.9200000000 0.0403639004 0.0485464492 0.0661605522 0.0142510936 0.0239180000 207225226 95654136 760807424 0.2801476121 0.5044063926 0.8025643229 625 24.9600000000 0.0399396606 0.0485326783 0.0661605522 0.0142427687 0.0204120000 207227834 95654136 760807424 0.2790654302 0.5071158409 0.8054107428 626 25.0000000000 0.0383371711 0.0485163916 0.0661605522 0.0142348257 0.0202660000 207230642 95654136 760807424 0.2772907615 0.5090459585 0.8070163131 627 25.0400000000 0.0385337360 0.0485004703 0.0661605522 0.0142320228 0.0274090000 207231450 95654144 760807424 0.2773056924 0.5138652921 0.8076751828 628 25.0800000000 0.0378186479 0.0484834610 0.0661605522 0.0142326081 0.0211740000 207234258 95654144 760807424 0.2754737735 0.5155458450 0.8090500832 629 25.1200000000 0.0380987376 0.0484669511 0.0661605522 0.0142315192 0.0203810000 207291802 95654144 760807424 0.2748242021 0.5186384916 0.8100143075 630 25.1600000000 0.0375959836 0.0484496956 0.0661605522 0.0142267175 0.0203610000 207408130 95654144 760807424 0.2706318796 0.5191477537 0.8127697110 631 25.2000000000 0.0380798578 0.0484332616 0.0661605522 0.0142208366 0.0242830000 207410738 95654144 760807424 0.2686753273 0.5225382447 0.8139514327 632 25.2400000000 0.0381108969 0.0484169288 0.0661605522 0.0142137097 0.0209990000 207411746 95654144 760807424 0.2651177347 0.5222718120 0.8175150156 633 25.2800000000 0.0381039567 0.0484006366 0.0661605522 0.0142048278 0.0203390000 207414354 95654144 760807424 0.2614638507 0.5237287879 0.8202923536 634 25.3200000000 0.0390898325 0.0483859507 0.0661605522 0.0141973067 0.0204200000 207415362 95654144 760807424 0.2582930326 0.5283101797 0.8219665885 635 25.3600000000 0.0375382639 0.0483688678 0.0661605522 0.0141892241 0.0204370000 207417970 95654144 760807424 0.2559266388 0.5298273563 0.8241239190 636 25.4000000000 0.0362671390 0.0483498399 0.0661605522 0.0141838536 0.0205060000 207420778 95654144 760807424 0.2505191565 0.5280268192 0.8266901374 637 25.4400000000 0.0371707194 0.0483322903 0.0661605522 0.0141768911 0.0205510000 207421586 95654144 760807424 0.2459187359 0.5298515558 0.8302638531 638 25.4800000000 0.0371154137 0.0483147089 0.0661605522 0.0141680828 0.0205100000 207424394 95654144 760807424 0.2412103266 0.5309095979 0.8344280124 639 25.5200000000 0.0366771147 0.0482964967 0.0661605522 0.0141609998 0.0208800000 207427002 95654144 760807424 0.2358050495 0.5300303102 0.8374921679 640 25.5600000000 0.0375180878 0.0482796555 0.0661605522 0.0141527209 0.0205300000 207428010 95654144 760807424 0.2308674455 0.5303171277 0.8412067890 641 25.6000000000 0.0381743796 0.0482638906 0.0661605522 0.0141443061 0.0205420000 207430618 95654144 760807424 0.2266075313 0.5316582322 0.8446400166 642 25.6400000000 0.0368178226 0.0482460619 0.0661605522 0.0141391501 0.0208150000 207431626 95654144 760807424 0.2247186005 0.5344359279 0.8462157845 643 25.6800000000 0.0373242460 0.0482290761 0.0661605522 0.0141386134 0.0206120000 207434234 95654144 760807424 0.2178992033 0.5344166756 0.8502705097 644 25.7200000000 0.0385962576 0.0482141183 0.0661605522 0.0141374343 0.0206030000 207437042 95654144 760807424 0.2115678191 0.5341864228 0.8537689447 645 25.7600000000 0.0374409519 0.0481974158 0.0661605522 0.0141307646 0.0207040000 207437850 95654144 760807424 0.2071992755 0.5343042612 0.8560842872 646 25.8000000000 0.0364749655 0.0481792696 0.0661605522 0.0141234579 0.0235870000 207497442 95654144 760807424 0.2044239491 0.5357140303 0.8593045473 647 25.8400000000 0.0383754224 0.0481641168 0.0661605522 0.0141183987 0.0208210000 207612318 95654144 760807424 0.1982946098 0.5374527574 0.8624007702 648 25.8800000000 0.0384519212 0.0481491288 0.0661605522 0.0141102879 0.0207880000 207615126 95654144 760807424 0.1940688491 0.5393469930 0.8657381535 649 25.9200000000 0.0397951007 0.0481362567 0.0661605522 0.0141018732 0.0207860000 207617734 95654144 760807424 0.1874269545 0.5409104228 0.8686857820 650 25.9600000000 0.0388175100 0.0481219201 0.0661605522 0.0140941301 0.0209080000 207618742 95654144 760807424 0.1833433658 0.5430967212 0.8711860180 651 26.0000000000 0.0391670763 0.0481081646 0.0661605522 0.0140930283 0.0249070000 207621350 95654144 760807424 0.1804134846 0.5461826324 0.8726472259 652 26.0400000000 0.0395973101 0.0480951112 0.0661605522 0.0140901932 0.0210620000 207622358 95654144 760807424 0.1766000390 0.5489894748 0.8743649721 653 26.0800000000 0.0383134000 0.0480801315 0.0661605522 0.0140891375 0.0209180000 207624966 95654144 760807424 0.1722640991 0.5490127802 0.8768576384 654 26.1200000000 0.0385586396 0.0480655727 0.0661605522 0.0140899658 0.0209590000 207627774 95654144 760807424 0.1678693891 0.5502145886 0.8799521327 655 26.1600000000 0.0386429951 0.0480511870 0.0661605522 0.0140858895 0.0209530000 207628582 95654144 760807424 0.1663462371 0.5549578071 0.8813513517 656 26.2000000000 0.0371609889 0.0480345861 0.0661605522 0.0140810162 0.0248790000 207631390 95654144 760807424 0.1575217396 0.5570845008 0.8850411177 657 26.2400000000 0.0370376632 0.0480178480 0.0661605522 0.0140764297 0.0251210000 207633998 95654144 760807424 0.1546165496 0.5568748713 0.8872433901 658 26.2800000000 0.0380286910 0.0480026669 0.0661605522 0.0140695568 0.0211880000 207635006 95654144 760807424 0.1498417705 0.5589337945 0.8894480467 659 26.3200000000 0.0378812626 0.0479873082 0.0661605522 0.0140654482 0.0211830000 207637614 95654144 760807424 0.1464195997 0.5623400211 0.8908402324 660 26.3600000000 0.0388577841 0.0479734756 0.0661605522 0.0140632491 0.0211650000 207638622 95654144 760807424 0.1418997645 0.5641629100 0.8922129869 661 26.4000000000 0.0391154438 0.0479600746 0.0661605522 0.0140607852 0.0212860000 207697746 95654144 760807424 0.1402326226 0.5694520473 0.8925246000 662 26.4400000000 0.0387360081 0.0479461410 0.0661605522 0.0140547468 0.0212770000 207815106 95654144 760807424 0.1377486885 0.5717236400 0.8937016726 663 26.4800000000 0.0385777801 0.0479320108 0.0661605522 0.0140520346 0.0224200000 207815914 95654144 760807424 0.1342608482 0.5716363192 0.8952683806 664 26.5200000000 0.0376339592 0.0479165016 0.0661605522 0.0140504738 0.0214030000 207818722 95654144 760807424 0.1325104535 0.5723853707 0.8960088491 665 26.5600000000 0.0381169766 0.0479017655 0.0661605522 0.0140492782 0.0212780000 207819530 95654144 760807424 0.1284732521 0.5745346546 0.8972000480 666 26.6000000000 0.0371845104 0.0478856735 0.0661605522 0.0140438700 0.0212960000 207822338 95654144 760807424 0.1262489110 0.5750393271 0.8980436325 667 26.6400000000 0.0383331478 0.0478713519 0.0661605522 0.0140385306 0.0213420000 207824946 95654144 760807424 0.1219010130 0.5781852603 0.8991007805 668 26.6800000000 0.0373740494 0.0478556374 0.0661605522 0.0140315104 0.0212950000 207825954 95654144 760807424 0.1190243065 0.5797466040 0.9001989961 669 26.7200000000 0.0380838625 0.0478410308 0.0661605522 0.0140295496 0.0214220000 207828562 95654144 760807424 0.1145777404 0.5819776058 0.9014778733 670 26.7600000000 0.0390409641 0.0478278964 0.0661605522 0.0140219941 0.0214380000 207829570 95654144 760807424 0.1102540866 0.5824820399 0.9026224613 671 26.8000000000 0.0397461094 0.0478158520 0.0661605522 0.0140166813 0.0218710000 207832178 95654144 760807424 0.1058833748 0.5818704963 0.9042304158 672 26.8400000000 0.0388186760 0.0478024634 0.0661605522 0.0140080090 0.0221440000 207834986 95654144 760807424 0.1011871397 0.5796806216 0.9062237740 673 26.8800000000 0.0379868969 0.0477878786 0.0661605522 0.0139988685 0.0221330000 207835794 95654144 760807424 0.0990529954 0.5801215768 0.9071564674 674 26.9200000000 0.0377308205 0.0477729571 0.0661605522 0.0139937727 0.0221610000 207838602 95654144 760807424 0.0953860804 0.5794819593 0.9086906910 675 26.9600000000 0.0399365686 0.0477613477 0.0661605522 0.0139910458 0.0215120000 207841210 95654144 760807424 0.0899192393 0.5813754797 0.9097193480 676 27.0000000000 0.0406403057 0.0477508136 0.0661605522 0.0139841128 0.0216210000 207842218 95654144 760807424 0.0853803754 0.5824799538 0.9105273485 677 27.0400000000 0.0399423726 0.0477392797 0.0661605522 0.0139774099 0.0214760000 207844826 95654144 760807424 0.0813471302 0.5821237564 0.9115250111 678 27.0800000000 0.0409342498 0.0477292428 0.0661605522 0.0139695812 0.0224550000 207845834 95654144 760807424 0.0751854032 0.5819348097 0.9124746323 679 27.1200000000 0.0398584120 0.0477176510 0.0661605522 0.0139609897 0.0220360000 207848442 95654144 760807424 0.0709905922 0.5800959468 0.9136384130 680 27.1600000000 0.0264916997 0.0476864363 0.0661605522 0.0139624263 0.0711750000 209812406 95654144 760807424 0.0676995814 0.5549900532 0.9146076441 681 27.2000000000 0.0239915643 0.0476516421 0.0661605522 0.0139555987 0.0221850000 207986418 95654144 760807424 0.0687629133 0.5547996163 0.9162926674 682 27.2400000000 0.0247829463 0.0476181103 0.0661605522 0.0139513490 0.0222480000 207989226 95654144 760807424 0.0649356544 0.5579780936 0.9164921641 683 27.2800000000 0.0237719659 0.0475831965 0.0661605522 0.0139464561 0.0221570000 207990034 95654144 760807424 0.0637486279 0.5573065877 0.9173381925 684 27.3200000000 0.0248181056 0.0475499142 0.0661605522 0.0139371093 0.0221200000 207992842 95654144 760807424 0.0560026169 0.5548648238 0.9190672040 685 27.3600000000 0.0236956030 0.0475150904 0.0661605522 0.0139313598 0.0221330000 207995450 95654144 760807424 0.0548507683 0.5570960641 0.9197308421 686 27.4000000000 0.0245542433 0.0474816197 0.0661605522 0.0139272776 0.0219720000 207996458 95654144 760807424 0.0504963249 0.5586533546 0.9205356240 687 27.4400000000 0.0246520713 0.0474483890 0.0661605522 0.0139216875 0.0220830000 207999066 95654144 760807424 0.0461417660 0.5572721958 0.9223674536 688 27.4800000000 0.0243748110 0.0474148518 0.0661605522 0.0139217984 0.0221890000 208055614 95654144 760807424 0.0445447341 0.5580742955 0.9234365821 689 27.5200000000 0.0236259270 0.0473803250 0.0661605522 0.0139162350 0.0220140000 208173642 95654144 760807424 0.0416909456 0.5588920712 0.9242783189 690 27.5600000000 0.0248160381 0.0473476232 0.0661605522 0.0139103926 0.0220860000 208176450 95654144 760807424 0.0370310806 0.5610625148 0.9250208139 691 27.6000000000 0.0251994245 0.0473155708 0.0661605522 0.0139037683 0.0221010000 208177258 95654144 760807424 0.0327207707 0.5582118630 0.9267103672 692 27.6400000000 0.0244741216 0.0472825629 0.0661605522 0.0138981348 0.0220650000 208180066 95654144 760807424 0.0297977310 0.5588876605 0.9278076291 693 27.6800000000 0.0246794149 0.0472499465 0.0661605522 0.0138920041 0.0220830000 208182674 95654144 760807424 0.0252073277 0.5580048561 0.9289193153 694 27.7200000000 0.0235921983 0.0472158576 0.0661605522 0.0138858320 0.0255820000 208183682 95654144 760807424 0.0246671643 0.5602523685 0.9298310280 695 27.7600000000 0.0239320770 0.0471823557 0.0661605522 0.0138802843 0.0260680000 208186290 95654144 760807424 0.0219126418 0.5617185831 0.9307350516 696 27.8000000000 0.0239305049 0.0471489479 0.0661605522 0.0138744838 0.0222540000 208187298 95654144 760807424 0.0179251079 0.5596400499 0.9322963357 697 27.8400000000 0.0239179228 0.0471156179 0.0661605522 0.0138706294 0.0220540000 208189906 95654144 760807424 0.0139277894 0.5586878061 0.9335330129 698 27.8800000000 0.0230847523 0.0470811897 0.0661605522 0.0138658759 0.0220470000 208192714 95654144 760807424 0.0123787979 0.5595512986 0.9341682792 699 27.9200000000 0.0225897413 0.0470461519 0.0661605522 0.0138599818 0.0252710000 208193522 95654144 760807424 0.0089753978 0.5595359206 0.9352453351 700 27.9600000000 0.0225942023 0.0470112205 0.0661605522 0.0138574862 0.0220670000 208196330 95654144 760807424 0.0052601090 0.5601272583 0.9363067150 701 28.0000000000 0.0229221135 0.0469768566 0.0661605522 0.0138553162 0.0219820000 208197138 95654144 760807424 0.0023415787 0.5626053810 0.9370879531 702 28.0400000000 0.0223442875 0.0469417674 0.0661605522 0.0138495245 0.0220390000 208199946 95654144 760807424 -0.0019748989 0.5624856353 0.9381528497 703 28.0800000000 0.0233708695 0.0469082384 0.0661605522 0.0138476602 0.0220310000 208202554 95654144 760807424 -0.0053330185 0.5652857423 0.9391880035 704 28.1200000000 0.0232007019 0.0468745630 0.0661605522 0.0138415219 0.0252060000 208203562 95654144 760807424 -0.0085803382 0.5633071065 0.9407106042 705 28.1600000000 0.0229630992 0.0468406460 0.0661605522 0.0138360265 0.0221430000 208206170 95654144 760807424 -0.0115083680 0.5621427298 0.9421952367 706 28.2000000000 0.0233727116 0.0468074053 0.0661605522 0.0138311695 0.0230010000 208207178 95654144 760807424 -0.0137766227 0.5610557199 0.9434462190 707 28.2400000000 0.0238078292 0.0467748741 0.0661605522 0.0138279055 0.0220930000 208209786 95654144 760807424 -0.0175905135 0.5639714599 0.9441755414 708 28.2800000000 0.0228101201 0.0467410255 0.0661605522 0.0138213762 0.0255870000 208212594 95654144 760807424 -0.0191565156 0.5613096952 0.9457942247 709 28.3200000000 0.0235371497 0.0467082979 0.0661605522 0.0138145338 0.0220620000 208213402 95654144 760807424 -0.0239412412 0.5612453818 0.9469333887 710 28.3600000000 0.0241204165 0.0466764840 0.0661605522 0.0138094034 0.0221390000 208216210 95654144 760807424 -0.0279921852 0.5635319948 0.9479664564 711 28.4000000000 0.0230487157 0.0466432523 0.0661605522 0.0138047021 0.0220400000 208218818 95654144 760807424 -0.0301738121 0.5641219020 0.9487926960 712 28.4400000000 0.0227672234 0.0466097185 0.0661605522 0.0137968293 0.0220330000 208219826 95654144 760807424 -0.0351907648 0.5630691051 0.9499174953 713 28.4800000000 0.0224871282 0.0465758860 0.0661605522 0.0137901878 0.0220590000 208222434 95654144 760807424 -0.0391178541 0.5633481741 0.9509692788 714 28.5200000000 0.0233877730 0.0465434096 0.0661605522 0.0137869836 0.0220160000 208279262 95654144 760807424 -0.0429110005 0.5654900074 0.9522302151 715 28.5600000000 0.0228124633 0.0465102195 0.0661605522 0.0137787358 0.0219900000 208398126 95654144 760807424 -0.0475181900 0.5638990998 0.9537021518 716 28.6000000000 0.0224877074 0.0464766685 0.0661605522 0.0137734915 0.0220020000 208400934 95654144 760807424 -0.0513510033 0.5626939535 0.9549660683 717 28.6400000000 0.0238171313 0.0464450653 0.0661605522 0.0137666285 0.0220020000 208401742 95654144 760807424 -0.0562862009 0.5653951168 0.9557469487 718 28.6800000000 0.0230036117 0.0464124170 0.0661605522 0.0137594643 0.0216010000 208404550 95654144 760807424 -0.0606549941 0.5649352074 0.9565634131 719 28.7200000000 0.0227828212 0.0463795525 0.0661605522 0.0137573172 0.0219560000 208405358 95654144 760807424 -0.0646364093 0.5626526475 0.9577844143 720 28.7600000000 0.0233453084 0.0463475605 0.0661605522 0.0137594003 0.0215370000 208408166 95654144 760807424 -0.0683864355 0.5642481446 0.9584777951 721 28.8000000000 0.0223819334 0.0463143210 0.0661605522 0.0137558935 0.0222940000 208410774 95654144 760807424 -0.0711156651 0.5618874431 0.9598796964 722 28.8400000000 0.0231159870 0.0462821904 0.0661605522 0.0137518785 0.0216700000 208411782 95654144 760807424 -0.0774191320 0.5618141294 0.9606055617 723 28.8800000000 0.0231698100 0.0462502230 0.0661605522 0.0137445055 0.0215600000 208414390 95654144 760807424 -0.0816636980 0.5610578656 0.9615820646 724 28.9200000000 0.0225911196 0.0462175447 0.0661605522 0.0137374371 0.0215600000 208415398 95654144 760807424 -0.0857386217 0.5618459582 0.9620651007 725 28.9600000000 0.0228650123 0.0461853343 0.0661605522 0.0137313776 0.0214440000 208418006 95654144 760807424 -0.0898243412 0.5605526567 0.9635877609 726 29.0000000000 0.0233168509 0.0461538350 0.0661605522 0.0137237747 0.0214550000 208420814 95654144 760807424 -0.0941665024 0.5601775646 0.9645330906 727 29.0400000000 0.0229506716 0.0461219187 0.0661605522 0.0137193103 0.0251090000 208421622 95654144 760807424 -0.0973529071 0.5603779554 0.9649288654 728 29.0800000000 0.0229349900 0.0460900686 0.0661605522 0.0137166225 0.0216240000 208424430 95654144 760807424 -0.0996833742 0.5593619347 0.9659063220 729 29.1200000000 0.0225116685 0.0460577251 0.0661605522 0.0137175632 0.0215000000 208427038 95654144 760807424 -0.1016639844 0.5595264435 0.9667655230 730 29.1600000000 0.0221700929 0.0460250023 0.0661605522 0.0137146102 0.0215050000 208428046 95654144 760807424 -0.1036803573 0.5581593513 0.9676164985 731 29.2000000000 0.0213882215 0.0459912994 0.0661605522 0.0137120681 0.0251750000 208430654 95654144 760807424 -0.1079930663 0.5564678311 0.9676735997 732 29.2400000000 0.0220563933 0.0459586015 0.0661605522 0.0137085848 0.0215160000 208431662 95654144 760807424 -0.1119982898 0.5574459434 0.9679369330 733 29.2800000000 0.0218176097 0.0459256670 0.0661605522 0.0137042112 0.0269160000 208434270 95654144 760807424 -0.1141361743 0.5556641817 0.9687709212 734 29.3200000000 0.0211484414 0.0458919105 0.0661605522 0.0136965351 0.0216360000 208437078 95654144 760807424 -0.1163343787 0.5542122126 0.9691430926 735 29.3600000000 0.0213131029 0.0458584700 0.0661605522 0.0136899718 0.0214320000 208437886 95654144 760807424 -0.1200239435 0.5545031428 0.9690967798 736 29.4000000000 0.0210472140 0.0458247590 0.0661605522 0.0136844796 0.0214650000 208440694 95654144 760807424 -0.1230058223 0.5525616407 0.9690561891 737 29.4400000000 0.0210543871 0.0457911493 0.0661605522 0.0136789148 0.0214410000 208441502 95654144 760807424 -0.1256186664 0.5509630442 0.9693455696 738 29.4800000000 0.0212855022 0.0457579438 0.0661605522 0.0136725712 0.0213790000 208444310 95654144 760807424 -0.1274302900 0.5489618182 0.9699840546 739 29.5200000000 0.0211737081 0.0457246769 0.0661605522 0.0136666442 0.0213570000 208446918 95654144 760807424 -0.1289315224 0.5463349819 0.9703769088 740 29.5600000000 0.0210590735 0.0456913450 0.0661605522 0.0136630273 0.0214210000 208502390 95654144 760807424 -0.1300544590 0.5439416766 0.9709656239 741 29.6000000000 0.0213117711 0.0456584441 0.0661605522 0.0136603754 0.0213790000 208622090 95654144 760807424 -0.1328457296 0.5427278876 0.9711526036 742 29.6400000000 0.0211303569 0.0456253874 0.0661605522 0.0136556304 0.0213600000 208623098 95654144 760807424 -0.1344428062 0.5409671068 0.9715574980 743 29.6800000000 0.0216318388 0.0455930946 0.0661605522 0.0136541049 0.0317900000 208625706 95654144 760807424 -0.1358732730 0.5402965546 0.9719771147 744 29.7200000000 0.0208788794 0.0455598766 0.0661605522 0.0136568133 0.0220850000 208628514 95654144 760807424 -0.1379245818 0.5367824435 0.9725355506 745 29.7600000000 0.0205878932 0.0455263571 0.0661605522 0.0136487944 0.0213120000 208629322 95654144 760807424 -0.1383554041 0.5335296392 0.9731847644 746 29.8000000000 0.0204254016 0.0454927097 0.0661605522 0.0136408667 0.0213160000 208632130 95654144 760807424 -0.1389937997 0.5328158736 0.9741244912 747 29.8400000000 0.0203840919 0.0454590971 0.0661605522 0.0136329335 0.0212990000 208634738 95654144 760807424 -0.1399497837 0.5308331847 0.9749444127 748 29.8800000000 0.0206489991 0.0454259285 0.0661605522 0.0136239663 0.0213090000 208635746 95654144 760807424 -0.1416623741 0.5292843580 0.9748942256 749 29.9200000000 0.0212007202 0.0453935851 0.0661605522 0.0136149641 0.0212850000 208638354 95654144 760807424 -0.1443898827 0.5285574794 0.9748370051 750 29.9600000000 0.0206775907 0.0453606305 0.0661605522 0.0136060948 0.0213270000 208639362 95654144 760807424 -0.1454828829 0.5271264911 0.9749523401 751 30.0000000000 0.0212078616 0.0453284697 0.0661605522 0.0135970522 0.0217800000 208641970 95654144 760807424 -0.1457923353 0.5247035623 0.9756036401 752 30.0400000000 0.0205372088 0.0452955026 0.0661605522 0.0135880782 0.0250210000 208644778 95654144 760807424 -0.1452239156 0.5225946307 0.9765106440 753 30.0800000000 0.0206491128 0.0452627716 0.0661605522 0.0135806536 0.0214470000 208645586 95654144 760807424 -0.1468873173 0.5207045674 0.9772235155 754 30.1200000000 0.0209537186 0.0452305315 0.0661605522 0.0135740129 0.0213050000 208648394 95654144 760807424 -0.1466532946 0.5187192559 0.9781320095 755 30.1600000000 0.0216543153 0.0451993047 0.0661605522 0.0135682384 0.0212660000 208649202 95654144 760807424 -0.1470758319 0.5179715753 0.9796178937 756 30.2000000000 0.0211837087 0.0451675381 0.0661605522 0.0135608072 0.0212550000 208652010 95654144 760807424 -0.1465817839 0.5176275373 0.9804543853 757 30.2400000000 0.0210828092 0.0451357221 0.0661605522 0.0135530758 0.0212800000 208654618 95654144 760807424 -0.1470029503 0.5149378181 0.9811103344 758 30.2800000000 0.0208975207 0.0451037455 0.0661605522 0.0135479637 0.0212650000 208655626 95654144 760807424 -0.1475574374 0.5158425570 0.9817470908 759 30.3200000000 0.0214133710 0.0450725329 0.0661605522 0.0135438319 0.0212590000 208658234 95654144 760807424 -0.1477735043 0.5144279003 0.9829145074 760 30.3600000000 0.0218979288 0.0450420400 0.0661605522 0.0135421911 0.0237380000 208659242 95654144 760807424 -0.1469855756 0.5120204687 0.9841198325 761 30.4000000000 0.0216677953 0.0450113249 0.0661605522 0.0135362388 0.0213450000 208661850 95654144 760807424 -0.1462571621 0.5113943815 0.9858269691 762 30.4400000000 0.0212409962 0.0449801302 0.0661605522 0.0135278176 0.0212960000 208664658 95654144 760807424 -0.1449833065 0.5109399557 0.9871660471 763 30.4800000000 0.0216648094 0.0449495728 0.0661605522 0.0135192400 0.0212720000 208665466 95654144 760807424 -0.1433621198 0.5090113282 0.9890534878 764 30.5200000000 0.0213721413 0.0449187123 0.0661605522 0.0135114158 0.0213130000 208668274 95654144 760807424 -0.1405001879 0.5071731806 0.9905385375 765 30.5600000000 0.0210818443 0.0448875529 0.0661605522 0.0135040475 0.0212110000 208670882 95654144 760807424 -0.1378964484 0.5052660704 0.9924684763 766 30.6000000000 0.0207854211 0.0448560880 0.0661605522 0.0134993476 0.0220590000 208671890 95654144 760807424 -0.1358429939 0.5022897124 0.9938741326 767 30.6400000000 0.0212263968 0.0448252801 0.0661605522 0.0135037223 0.0212990000 208674498 95654144 760807424 -0.1334237903 0.4990174770 0.9957530499 768 30.6800000000 0.0217992775 0.0447952983 0.0661605522 0.0135123956 0.0211800000 208675506 95654144 760807424 -0.1306085885 0.4983349442 0.9979898930 769 30.7200000000 0.0223462116 0.0447661057 0.0661605522 0.0135667882 0.0246800000 208678114 95654144 760807424 -0.1248720065 0.4963467717 1.0013324022 770 30.7600000000 0.0224037059 0.0447370637 0.0661605522 0.0135939016 0.0211830000 208680922 95654144 760807424 -0.1208531633 0.4911224842 1.0028001070 771 30.8000000000 0.0222022627 0.0447078356 0.0661605522 0.0136144094 0.0210970000 208681730 95654144 760807424 -0.1170571521 0.4881385267 1.0042032003 772 30.8400000000 0.0221408978 0.0446786039 0.0661605522 0.0136356325 0.0248050000 208684538 95654144 760807424 -0.1146257520 0.4877499938 1.0052032471 773 30.8800000000 0.0222736858 0.0446496195 0.0661605522 0.0136602775 0.0212750000 208685346 95654144 760807424 -0.1109480858 0.4846904874 1.0068008900 774 30.9200000000 0.0220854059 0.0446204668 0.0661605522 0.0136793815 0.0210930000 208688154 95654144 760807424 -0.1072604805 0.4804126322 1.0077605247 775 30.9600000000 0.0217605345 0.0445909701 0.0661605522 0.0136978302 0.0210990000 208690762 95654144 760807424 -0.1036760584 0.4784008861 1.0088051558 776 31.0000000000 0.0217880774 0.0445615849 0.0661605522 0.0137183870 0.0211330000 208691770 95654144 760807424 -0.0998778641 0.4751333594 1.0101677179 777 31.0400000000 0.0219310559 0.0445324594 0.0661605522 0.0137290233 0.0211120000 208694378 95654144 760807424 -0.0967439786 0.4729391336 1.0116094351 778 31.0800000000 0.0218715183 0.0445033322 0.0661605522 0.0137358767 0.0281190000 208695386 95654144 760807424 -0.0935569555 0.4703458548 1.0132408142 779 31.1200000000 0.0216875505 0.0444740437 0.0661605522 0.0137362358 0.0214230000 208697994 95654144 760807424 -0.0901099220 0.4676228464 1.0150343180 780 31.1600000000 0.0213424694 0.0444443878 0.0661605522 0.0137315794 0.0211540000 208753982 95654144 760807424 -0.0871784911 0.4638227522 1.0166950226 781 31.2000000000 0.0211176109 0.0444145200 0.0661605522 0.0137267042 0.0211790000 208873166 95654144 760807424 -0.0851816759 0.4596924484 1.0180232525 782 31.2400000000 0.0214512963 0.0443851552 0.0661605522 0.0137243455 0.0211900000 208875974 95654144 760807424 -0.0822881460 0.4560804665 1.0205161572 783 31.2800000000 0.0212559924 0.0443556161 0.0661605522 0.0137185548 0.0211080000 208878582 95654144 760807424 -0.0798008814 0.4511940181 1.0223208666 784 31.3200000000 0.0208945181 0.0443256912 0.0661605522 0.0137127095 0.0210610000 208879590 95654144 760807424 -0.0771071464 0.4454739392 1.0242216587 785 31.3600000000 0.0210926607 0.0442960950 0.0661605522 0.0137081373 0.0211010000 208882198 95654144 760807424 -0.0752276853 0.4409218132 1.0262668133 786 31.4000000000 0.0214672666 0.0442670507 0.0661605522 0.0137016795 0.0210950000 208883206 95654144 760807424 -0.0742423162 0.4372652471 1.0275315046 787 31.4400000000 0.0213217270 0.0442378952 0.0661605522 0.0136939314 0.0211390000 208885814 95654144 760807424 -0.0726136863 0.4306937754 1.0289442539 788 31.4800000000 0.0210548583 0.0442084751 0.0661605522 0.0136913574 0.0211070000 208888622 95654144 760807424 -0.0698903203 0.4260604382 1.0313370228 789 31.5200000000 0.0207157861 0.0441786999 0.0661605522 0.0136889502 0.0210770000 208889430 95654144 760807424 -0.0682873428 0.4206032753 1.0326899290 790 31.5600000000 0.0207175314 0.0441490022 0.0661605522 0.0136886849 0.0211030000 208892238 95654144 760807424 -0.0669096708 0.4138930738 1.0343586206 791 31.6000000000 0.0208268948 0.0441195178 0.0661605522 0.0137089182 0.0211320000 208893046 95654144 760807424 -0.0658509508 0.4032230079 1.0369957685 792 31.6400000000 0.0213434845 0.0440907602 0.0661605522 0.0137104231 0.0209980000 208895854 95654144 760807424 -0.0660220459 0.4009653032 1.0390053988 793 31.6800000000 0.0210832506 0.0440617470 0.0661605522 0.0137066949 0.0209800000 208898462 95654144 760807424 -0.0650178120 0.3946424723 1.0407088995 794 31.7200000000 0.0210885312 0.0440328135 0.0661605522 0.0137023185 0.0247630000 208899470 95654144 760807424 -0.0647226498 0.3935004771 1.0423680544 795 31.7600000000 0.0211026426 0.0440039705 0.0661605522 0.0136997026 0.0211380000 208902078 95654144 760807424 -0.0641458929 0.3959206343 1.0443015099 796 31.8000000000 0.0217840765 0.0439760560 0.0661605522 0.0136972205 0.0210660000 208903086 95654144 760807424 -0.0638851747 0.3919403255 1.0469496250 797 31.8400000000 0.0210884009 0.0439473388 0.0661605522 0.0137011628 0.0247400000 208905694 95654144 760807424 -0.0626115054 0.3875954747 1.0491379499 798 31.8800000000 0.0206729416 0.0439181729 0.0661605522 0.0137766011 0.0211870000 208908502 95654144 760807424 -0.0621262118 0.3682255745 1.0542017221 799 31.9200000000 0.0229948554 0.0438919860 0.0661605522 0.0137960241 0.0210820000 208909310 95654144 760807424 -0.0630754903 0.3637797236 1.0569108725 800 31.9600000000 0.0231484678 0.0438660566 0.0661605522 0.0138009080 0.0210580000 208912118 95654144 760807424 -0.0638385564 0.3595160544 1.0590506792 801 32.0000000000 0.0215574224 0.0438382056 0.0661605522 0.0137942572 0.0210910000 208914726 95654144 760807424 -0.0632588938 0.3535111248 1.0619914532 802 32.0400000000 0.0199846569 0.0438084630 0.0661605522 0.0137862139 0.0210190000 208915734 95654144 760807424 -0.0636081994 0.3418432176 1.0647145510 803 32.0800000000 0.0206802953 0.0437796608 0.0661605522 0.0137784101 0.0211070000 208918342 95654144 760807424 -0.0644097328 0.3346680999 1.0679056644 804 32.1199999990 0.0199513827 0.0437500237 0.0661605522 0.0137748764 0.0247920000 208919350 95654144 760807424 -0.0656412393 0.3194155395 1.0739791393 805 32.1600000000 0.0202683359 0.0437208539 0.0661605522 0.0137670896 0.0212690000 208921958 95654144 760807424 -0.0670882463 0.3149414062 1.0771503448 806 32.2000000000 0.0206643082 0.0436922477 0.0661605522 0.0137592918 0.0210310000 208924766 95654144 760807424 -0.0675994754 0.3123826087 1.0810106993 807 32.2400000000 0.0209328569 0.0436640453 0.0661605522 0.0137510206 0.0246460000 208925574 95654144 760807424 -0.0698449314 0.3036457896 1.0839910507 808 32.2800000000 0.0214687120 0.0436365758 0.0661605522 0.0137425342 0.0211980000 208928382 95654144 760807424 -0.0728049725 0.2980832756 1.0863659382 809 32.3200000000 0.0230037384 0.0436110717 0.0661605522 0.0137361528 0.0210400000 208929190 95654144 760807424 -0.0738153607 0.2878322303 1.0909752846 810 32.3600000000 0.0250813030 0.0435881954 0.0661605522 0.0137288569 0.0209830000 208931998 95654144 760807424 -0.0743399039 0.2798941135 1.0956758261 811 32.4000000000 0.0218833815 0.0435614324 0.0661605522 0.0137248568 0.0211140000 208934606 95654144 760807424 -0.0760673583 0.2712512612 1.0994211435 812 32.4399999990 0.0216812752 0.0435344864 0.0661605522 0.0137180069 0.0220400000 208935614 95654144 760807424 -0.0776562095 0.2655695677 1.1027648449 813 32.4800000000 0.0229486600 0.0435091656 0.0661605522 0.0137119309 0.0210630000 208938222 95654144 760807424 -0.0780977681 0.2594970763 1.1073431969 814 32.5200000000 0.0236098655 0.0434847192 0.0661605522 0.0137054655 0.0210500000 208939230 95654144 760807424 -0.0792555809 0.2494421899 1.1119579077 815 32.5600000000 0.0249261111 0.0434619479 0.0661605522 0.0136986672 0.0210570000 208941838 95654144 760807424 -0.0800397247 0.2421125174 1.1160972118 816 32.6000000000 0.0263307951 0.0434409539 0.0661605522 0.0136907599 0.0273620000 208944646 95654144 760807424 -0.0806955621 0.2375376970 1.1204627752 817 32.6400000000 0.0294580460 0.0434238389 0.0661605522 0.0136827801 0.0214970000 208945454 95654144 760807424 -0.0824899971 0.2282848358 1.1253402233 818 32.6800000000 0.0340187438 0.0434123413 0.0661605522 0.0136765594 0.0211110000 208948262 95654144 760807424 -0.0832369551 0.2171951234 1.1322966814 819 32.7200000000 0.0390651487 0.0434070333 0.0661605522 0.0136705342 0.0211000000 208950870 95654144 760807424 -0.0846420825 0.2124419808 1.1379805803 820 32.7599999990 0.0405379459 0.0434035345 0.0661605522 0.0136626173 0.0210470000 208951878 95654144 760807424 -0.0864686146 0.2078376561 1.1422079802 821 32.7999999990 0.0329871550 0.0433908470 0.0661605522 0.0136567855 0.0210310000 208954486 95654144 760807424 -0.0884143487 0.1902910173 1.1468880177 822 32.8400000000 0.0372337066 0.0433833566 0.0661605522 0.0136526012 0.0210060000 208955494 95654144 760807424 -0.0891401619 0.1831731200 1.1515758038 823 32.8800000000 0.0409501530 0.0433804001 0.0661605522 0.0136479741 0.0210020000 208958102 95654144 760807424 -0.0889171883 0.1754766703 1.1567260027 824 32.9200000000 0.0440683737 0.0433812350 0.0661605522 0.0136411510 0.0210560000 208960910 95654144 760807424 -0.0886618420 0.1680735797 1.1618102789 825 32.9600000000 0.0480054058 0.0433868401 0.0661605522 0.0136332012 0.0210530000 208961718 95654144 760807424 -0.0895536020 0.1624954641 1.1660850048 826 33.0000000000 0.0517482981 0.0433969629 0.0661605522 0.0136257208 0.0248660000 208964526 95654144 760807424 -0.0898704678 0.1577273458 1.1701657772 827 33.0400000000 0.0485379286 0.0434031793 0.0661605522 0.0136187740 0.0212210000 208965334 95654144 760807424 -0.0900115594 0.1441984326 1.1740283966 828 33.0800000000 0.0512802638 0.0434126927 0.0661605522 0.0136125066 0.0210500000 208968142 95654144 760807424 -0.0903731138 0.1393467188 1.1771917343 829 33.1199999990 0.0568176880 0.0434288628 0.0661605522 0.0136096425 0.0210380000 208970750 95654144 760807424 -0.0907542557 0.1341173351 1.1803070307 830 33.1600000000 0.0627757609 0.0434521723 0.0661605522 0.0136055957 0.0209780000 208971758 95654144 760807424 -0.0906165019 0.1270743012 1.1841737032 831 33.2000000000 0.0657592714 0.0434790160 0.0661605522 0.0135984282 0.0210540000 208974366 95654144 760807424 -0.0904737934 0.1184741408 1.1871860027 832 33.2400000000 0.0655445531 0.0435055370 0.0661605522 0.0135953737 0.0211080000 208975374 95654144 760807424 -0.0908442363 0.1096040979 1.1884758472 833 33.2800000000 0.0699733123 0.0435373111 0.0699733123 0.0135877903 0.0211010000 208977982 95654144 760807424 -0.0916890502 0.1038837358 1.1909208298 834 33.3200000000 0.0667795837 0.0435651795 0.0699733123 0.0135819199 0.0209570000 208980790 95654144 760807424 -0.0925811529 0.0910320282 1.1934591532 835 33.3600000000 0.0695480928 0.0435962968 0.0699733123 0.0135738946 0.0257360000 208981598 95654144 760807424 -0.0924898237 0.0864565521 1.1958019733 836 33.4000000000 0.0724688843 0.0436308334 0.0724688843 0.0135690020 0.0212160000 208984406 95654144 760807424 -0.0909877717 0.0811460018 1.1984167099 837 33.4399999990 0.0764269978 0.0436700163 0.0764269978 0.0135656913 0.0210970000 208987014 95654144 760807424 -0.0900199190 0.0744713917 1.2011257410 838 33.4800000000 0.0850300938 0.0437193720 0.0850300938 0.0135593343 0.0211310000 208988022 95654144 760807424 -0.0894932598 0.0732246190 1.2033171654 839 33.5200000000 0.0898666382 0.0437743747 0.0898666382 0.0135522063 0.0212880000 208990630 95654144 760807424 -0.0880900025 0.0699387938 1.2056642771 840 33.5600000000 0.0914749950 0.0438311612 0.0914749950 0.0135447197 0.0210890000 208991638 95654144 760807424 -0.0863333195 0.0654405132 1.2074157000 841 33.6000000000 0.0779443309 0.0438717238 0.0914749950 0.0135570217 0.0210310000 208994246 95654144 760807424 -0.0845632032 0.0389914997 1.2107856274 842 33.6400000000 0.0830542520 0.0439182589 0.0914749950 0.0135504930 0.0222700000 208997054 95654144 760807424 -0.0830469802 0.0311512984 1.2149398327 843 33.6800000000 0.0851870850 0.0439672136 0.0914749950 0.0135427762 0.0210880000 208997862 95654144 760807424 -0.0829648748 0.0273447149 1.2156080008 844 33.7200000000 0.0865895897 0.0440177141 0.0914749950 0.0135413163 0.0244040000 209000670 95654144 760807424 -0.0822770819 0.0217089206 1.2160788774 845 33.7599999990 0.0889602527 0.0440709005 0.0914749950 0.0135467602 0.0211160000 209001478 95654144 760807424 -0.0811339170 0.0135059729 1.2171726227 846 33.7999999990 0.0909395814 0.0441263008 0.0914749950 0.0135457294 0.0210070000 209004286 95654144 760807424 -0.0798150003 0.0103380522 1.2173476219 847 33.8400000000 0.0913092643 0.0441820068 0.0914749950 0.0135462919 0.0209420000 209006894 95654144 760807424 -0.0789052397 0.0056070732 1.2170544863 848 33.8800000000 0.0952492654 0.0442422276 0.0952492654 0.0135425411 0.0209930000 209007902 95654144 760807424 -0.0773609132 -0.0019181562 1.2190493345 849 33.9200000000 0.0945062265 0.0443014314 0.0952492654 0.0135364253 0.0209840000 209010510 95654144 760807424 -0.0771027580 -0.0098228138 1.2196300030 850 33.9600000000 0.0924351886 0.0443580593 0.0952492654 0.0135321798 0.0209890000 209011518 95654144 760807424 -0.0773412138 -0.0154956775 1.2191647291 851 34.0000000000 0.0929415300 0.0444151492 0.0952492654 0.0135264047 0.0210160000 209014126 95654144 760807424 -0.0776629224 -0.0218978338 1.2196714878 852 34.0400000000 0.0906164348 0.0444693761 0.0952492654 0.0135218052 0.0211010000 209016934 95654144 760807424 -0.0780850947 -0.0287863649 1.2193150520 853 34.0800000000 0.0892648995 0.0445218913 0.0952492654 0.0135225935 0.0210060000 209017742 95654144 760807424 -0.0781959817 -0.0344920233 1.2189295292 854 34.1199999990 0.0902292281 0.0445754128 0.0952492654 0.0135244163 0.0249550000 209020550 95654144 760807424 -0.0786311924 -0.0410490260 1.2192115784 855 34.1600000000 0.0891619846 0.0446275608 0.0952492654 0.0135195493 0.0211080000 209023158 95654144 760807424 -0.0784427747 -0.0473700054 1.2195709944 856 34.2000000000 0.0861846507 0.0446761088 0.0952492654 0.0135164261 0.0209640000 209024166 95654144 760807424 -0.0781954899 -0.0522212870 1.2185792923 857 34.2400000000 0.0847732872 0.0447228967 0.0952492654 0.0135168506 0.0218200000 209026774 95654144 760807424 -0.0777121410 -0.0560648292 1.2174495459 858 34.2800000000 0.0836009234 0.0447682091 0.0952492654 0.0135219197 0.0211350000 209027782 95654144 760807424 -0.0779513568 -0.0608652942 1.2164201736 859 34.3200000000 0.0819596425 0.0448115053 0.0952492654 0.0135285687 0.0212190000 209030390 95654144 760807424 -0.0785390586 -0.0647961199 1.2145482302 860 34.3600000000 0.0810726285 0.0448536694 0.0952492654 0.0135281382 0.0208940000 209033198 95654144 760807424 -0.0785547122 -0.0683963522 1.2130874395 861 34.4000000000 0.0768590048 0.0448908416 0.0952492654 0.0135283264 0.0212170000 209034006 95654144 760807424 -0.0770237744 -0.0742247328 1.2120382786 862 34.4400000000 0.0784447119 0.0449297673 0.0952492654 0.0135315734 0.0211070000 209036814 95654144 760807424 -0.0761258230 -0.0759175941 1.2114996910 863 34.4800000000 0.0796454176 0.0449699940 0.0952492654 0.0135386364 0.0250970000 209037622 95654144 760807424 -0.0751252919 -0.0785669461 1.2112853527 864 34.5200000000 0.0787206218 0.0450090572 0.0952492654 0.0135425278 0.0212590000 209040430 95654144 760807424 -0.0755963922 -0.0793522149 1.2093091011 865 34.5600000000 0.0787977874 0.0450481193 0.0952492654 0.0135468257 0.0211300000 209043038 95654144 760807424 -0.0749343261 -0.0807105899 1.2079529762 866 34.6000000000 0.0797075555 0.0450881417 0.0952492654 0.0135462733 0.0209230000 209044046 95654144 760807424 -0.0740387514 -0.0840008035 1.2073642015 867 34.6400000000 0.0811280981 0.0451297103 0.0952492654 0.0135398242 0.0210720000 209046654 95654144 760807424 -0.0739067122 -0.0844454914 1.2064656019 868 34.6800000000 0.0802548975 0.0451701771 0.0952492654 0.0135340789 0.0210920000 209047662 95654144 760807424 -0.0731437951 -0.0863866732 1.2049973011 869 34.7200000000 0.0785527602 0.0452085921 0.0952492654 0.0135311901 0.0210260000 209050270 95654144 760807424 -0.0717128739 -0.0905315727 1.2042387724 870 34.7600000000 0.0780928433 0.0452463901 0.0952492654 0.0135246474 0.0208010000 209053078 95654144 760807424 -0.0708147138 -0.0937104449 1.2036430836 871 34.8000000000 0.0775376260 0.0452834638 0.0952492654 0.0135208698 0.0208070000 209053886 95654144 760807424 -0.0703079998 -0.0977862775 1.2028923035 872 34.8400000000 0.0778860897 0.0453208521 0.0952492654 0.0135152580 0.0208490000 209056694 95654144 760807424 -0.0700162649 -0.1013652086 1.2027690411 873 34.8800000000 0.0791662037 0.0453596212 0.0952492654 0.0135078741 0.0243110000 209059302 95654144 760807424 -0.0693104044 -0.1024934873 1.2024626732 874 34.9200000000 0.0778195038 0.0453967606 0.0952492654 0.0135015076 0.0247820000 209060310 95654144 760807424 -0.0693227500 -0.1058492437 1.2013266087 875 34.9600000000 0.0761095881 0.0454318610 0.0952492654 0.0134965898 0.0211200000 209062918 95654144 760807424 -0.0696693510 -0.1109421477 1.2007534504 876 35.0000000000 0.0756225437 0.0454663252 0.0952492654 0.0134893307 0.0209100000 209063926 95654144 760807424 -0.0690508857 -0.1142966524 1.2005652189 877 35.0400000000 0.0759273395 0.0455010584 0.0952492654 0.0134816895 0.0208300000 209066534 95654144 760807424 -0.0697491243 -0.1163480952 1.1995253563 878 35.0800000000 0.0761563852 0.0455359734 0.0952492654 0.0134744210 0.0208540000 209069342 95654144 760807424 -0.0701870695 -0.1199077815 1.1986292601 879 35.1200000000 0.0753469393 0.0455698880 0.0952492654 0.0134669330 0.0208680000 209070150 95654144 760807424 -0.0694259033 -0.1237786487 1.1980221272 880 35.1600000000 0.0756836832 0.0456041082 0.0952492654 0.0134596953 0.0208320000 209072958 95654144 760807424 -0.0689875856 -0.1277654171 1.1958588362 881 35.2000000000 0.0735170543 0.0456357915 0.0952492654 0.0134528729 0.0207450000 209073766 95654144 760807424 -0.0691760480 -0.1314664334 1.1941608191 882 35.2400000000 0.0711094812 0.0456646732 0.0952492654 0.0134464396 0.0252580000 209076574 95654144 760807424 -0.0693314597 -0.1368774027 1.1930288076 883 35.2800000000 0.0685484707 0.0456905892 0.0952492654 0.0134406753 0.0210250000 209079182 95654144 760807424 -0.0697634816 -0.1423346698 1.1917983294 884 35.3200000000 0.0662777200 0.0457138778 0.0952492654 0.0134399381 0.0208180000 209080190 95654144 760807424 -0.0703207478 -0.1469226927 1.1901586056 885 35.3600000000 0.0631572306 0.0457335878 0.0952492654 0.0134394022 0.0243060000 209082798 95654144 760807424 -0.0706226006 -0.1524178982 1.1889055967 886 35.4000000000 0.0606500469 0.0457504235 0.0952492654 0.0134410076 0.0210460000 209083806 95654144 760807424 -0.0719562843 -0.1570686400 1.1876653433 887 35.4400000000 0.0580393225 0.0457642780 0.0952492654 0.0134388559 0.0249370000 209086414 95654144 760807424 -0.0719018951 -0.1606357545 1.1863154173 888 35.4800000000 0.0553544052 0.0457750777 0.0952492654 0.0134391816 0.0221260000 209089222 95654144 760807424 -0.0732376799 -0.1658309996 1.1848216057 889 35.5200000000 0.0535410196 0.0457838133 0.0952492654 0.0134416454 0.0211420000 209090030 95654144 760807424 -0.0738151744 -0.1693915278 1.1834323406 890 35.5600000000 0.0517943054 0.0457905666 0.0952492654 0.0134497636 0.0210120000 209092838 95654144 760807424 -0.0752060115 -0.1720365435 1.1819152832 891 35.6000000000 0.0510128103 0.0457964277 0.0952492654 0.0134568491 0.0232740000 209095446 95654144 760807424 -0.0772824362 -0.1763613522 1.1807798147 892 35.6400000000 0.0495605431 0.0458006476 0.0952492654 0.0134624519 0.0209810000 209096454 95654144 760807424 -0.0787670240 -0.1792758554 1.1791857481 893 35.6800000000 0.0475389808 0.0458025942 0.0952492654 0.0134691103 0.0210580000 209099062 95654144 760807424 -0.0803681239 -0.1822313517 1.1775783300 894 35.7200000000 0.0462654233 0.0458031119 0.0952492654 0.0134785147 0.0209630000 209100070 95654144 760807424 -0.0818687454 -0.1861485392 1.1764743328 895 35.7600000000 0.0445497744 0.0458017116 0.0952492654 0.0134853264 0.0210050000 209102678 95654144 760807424 -0.0830093995 -0.1902450770 1.1751972437 896 35.8000000000 0.0424839109 0.0457980087 0.0952492654 0.0135016032 0.0209710000 209105486 95654144 760807424 -0.0838737339 -0.1929100603 1.1737575531 897 35.8400000000 0.0412699357 0.0457929606 0.0952492654 0.0135158973 0.0211420000 209106294 95654144 760807424 -0.0843592510 -0.1943022609 1.1732958555 898 35.8800000000 0.0403976291 0.0457869525 0.0952492654 0.0135246686 0.0214370000 209109102 95654144 760807424 -0.0857863352 -0.1961982995 1.1728522778 899 35.9200000000 0.0396020003 0.0457800727 0.0952492654 0.0135311297 0.0214530000 209109910 95654144 760807424 -0.0862394795 -0.1980259269 1.1734106541 900 35.9600000000 0.0386118330 0.0457721079 0.0952492654 0.0135328596 0.0213930000 209112718 95654144 760807424 -0.0869349092 -0.1997068524 1.1730448008 901 36.0000000000 0.0372936539 0.0457626979 0.0952492654 0.0135383193 0.0214990000 209115326 95654144 760807424 -0.0879919678 -0.2024301887 1.1730167866 902 36.0400000000 0.0360652730 0.0457519469 0.0952492654 0.0135465853 0.0217470000 209116334 95654144 760807424 -0.0887397453 -0.2042206228 1.1730982065 903 36.0800000000 0.0348889343 0.0457399170 0.0952492654 0.0135557675 0.0224800000 209118942 95654144 760807424 -0.0903302878 -0.2061133087 1.1725325584 904 36.1200000000 0.0340938866 0.0457270342 0.0952492654 0.0135702519 0.0211410000 209119950 95654144 760807424 -0.0911807418 -0.2084098160 1.1726051569 905 36.1600000000 0.0338108502 0.0457138671 0.0952492654 0.0135920745 0.0213670000 209122558 95654144 760807424 -0.0924236774 -0.2090456188 1.1719659567 906 36.2000000000 0.0333815515 0.0457002553 0.0952492654 0.0136139910 0.0210960000 209125366 95654144 760807424 -0.0938097835 -0.2101266384 1.1714680195 907 36.2400000000 0.0326740406 0.0456858934 0.0952492654 0.0136318039 0.0210930000 209126174 95654144 760807424 -0.0947529376 -0.2125404328 1.1715508699 908 36.2800000000 0.0320403315 0.0456708653 0.0952492654 0.0136450293 0.0210360000 209128982 95654144 760807424 -0.0958552882 -0.2128448337 1.1712496281 909 36.3200000000 0.0316428654 0.0456554329 0.0952492654 0.0136531435 0.0210380000 209131590 95654144 760807424 -0.0972144008 -0.2136811167 1.1711596251 910 36.3600000000 0.0314133093 0.0456397823 0.0952492654 0.0136596406 0.0211150000 209132598 95654144 760807424 -0.0991452336 -0.2150767893 1.1708856821 911 36.4000000000 0.0311442800 0.0456238706 0.0952492654 0.0136642540 0.0278560000 209135206 95654144 760807424 -0.1002865732 -0.2168811709 1.1709655523 912 36.4400000000 0.0312196631 0.0456080765 0.0952492654 0.0136697061 0.0214640000 209136214 95654144 760807424 -0.1019404083 -0.2179879844 1.1707103252 913 36.4800000000 0.0306394957 0.0455916816 0.0952492654 0.0137351060 0.0211820000 209138822 95654144 760807424 -0.1044360250 -0.2178255171 1.1694684029 914 36.5200000000 0.0299340021 0.0455745506 0.0952492654 0.0137504379 0.0211610000 209141630 95654144 760807424 -0.1051855609 -0.2192613184 1.1695773602 915 36.5600000000 0.0298914574 0.0455574107 0.0952492654 0.0137678458 0.0211360000 209142438 95654144 760807424 -0.1072070152 -0.2200744003 1.1696776152 916 36.6000000000 0.0295100380 0.0455398917 0.0952492654 0.0137820538 0.0251440000 209145246 95654144 760807424 -0.1088270992 -0.2208366543 1.1696355343 917 36.6400000000 0.0290469974 0.0455219060 0.0952492654 0.0137916359 0.0212870000 209146054 95654144 760807424 -0.1103460267 -0.2217355371 1.1698648930 918 36.6800000000 0.0288038068 0.0455036945 0.0952492654 0.0138023591 0.0211280000 209148862 95654144 760807424 -0.1118093356 -0.2227848619 1.1699895859 919 36.7200000000 0.0283375550 0.0454850154 0.0952492654 0.0138160658 0.0211570000 209151470 95654144 760807424 -0.1129032597 -0.2236237824 1.1705247164 920 36.7600000000 0.0276216585 0.0454655987 0.0952492654 0.0138288663 0.0213150000 209152478 95654144 760807424 -0.1141437367 -0.2244565487 1.1705939770 921 36.8000000000 0.0275913104 0.0454461912 0.0952492654 0.0138373700 0.0258850000 209155086 95654144 760807424 -0.1154754981 -0.2246199995 1.1707235575 922 36.8400000000 0.0272228010 0.0454264262 0.0952492654 0.0138433221 0.0214140000 209156094 95654144 760807424 -0.1167977899 -0.2255112976 1.1713086367 923 36.8800000000 0.0267853867 0.0454062300 0.0952492654 0.0138468053 0.0214180000 209158702 95654144 760807424 -0.1180607378 -0.2259284109 1.1724005938 924 36.9200000000 0.0268375762 0.0453861341 0.0952492654 0.0138490439 0.0212190000 209209990 95654144 760807424 -0.1193497479 -0.2253817469 1.1727204323 925 36.9600000000 0.0270021688 0.0453662595 0.0952492654 0.0138515281 0.0246940000 209333786 95654144 760807424 -0.1207191944 -0.2244499475 1.1729042530 926 37.0000000000 0.0262825824 0.0453456508 0.0952492654 0.0138517796 0.0215930000 209336594 95654144 760807424 -0.1218157485 -0.2255454957 1.1735378504 927 37.0400000000 0.0258395076 0.0453246086 0.0952492654 0.0138543572 0.0214450000 209339202 95654144 760807424 -0.1227677241 -0.2268900722 1.1744824648 928 37.0800000000 0.0253917295 0.0453031292 0.0952492654 0.0138633339 0.0211630000 209340210 95654144 760807424 -0.1240214109 -0.2268605083 1.1751219034 929 37.1200000000 0.0249468889 0.0452812172 0.0952492654 0.0138711283 0.0211250000 209342818 95654144 760807424 -0.1254074126 -0.2268701941 1.1748638153 930 37.1600000000 0.0252588317 0.0452596877 0.0952492654 0.0138792220 0.0249100000 209343826 95654144 760807424 -0.1274381727 -0.2257475853 1.1735175848 931 37.2000000000 0.0256896503 0.0452386673 0.0952492654 0.0138859227 0.0250090000 209346434 95654144 760807424 -0.1292505264 -0.2258628160 1.1740884781 932 37.2400000000 0.0256500337 0.0452176494 0.0952492654 0.0138990946 0.0213100000 209349242 95654144 760807424 -0.1311208755 -0.2262602299 1.1733906269 933 37.2800000000 0.0258355848 0.0451968755 0.0952492654 0.0139209562 0.0220760000 209350050 95654144 760807424 -0.1328969151 -0.2257781327 1.1730149984 934 37.3200000000 0.0257437732 0.0451760478 0.0952492654 0.0139401464 0.0250380000 209352858 95654144 760807424 -0.1346284747 -0.2250771821 1.1735354662 935 37.3600000000 0.0260046180 0.0451555436 0.0952492654 0.0139523937 0.0212110000 209353666 95654144 760807424 -0.1365745664 -0.2248096764 1.1726783514 936 37.4000000000 0.0262670852 0.0451353636 0.0952492654 0.0139616491 0.0211710000 209356474 95654144 760807424 -0.1382413656 -0.2245367467 1.1724812984 937 37.4400000000 0.0265220385 0.0451154988 0.0952492654 0.0139681209 0.0211730000 209359082 95654144 760807424 -0.1401447654 -0.2230227143 1.1717993021 938 37.4800000000 0.0275990143 0.0450968245 0.0952492654 0.0139720065 0.0214010000 209360090 95654144 760807424 -0.1422221810 -0.2219085842 1.1716166735 939 37.5200000000 0.0287820678 0.0450794499 0.0952492654 0.0139776736 0.0248650000 209362698 95654144 760807424 -0.1442736834 -0.2205365896 1.1712899208 940 37.5600000000 0.0297867917 0.0450631811 0.0952492654 0.0139813908 0.0211670000 209363706 95654144 760807424 -0.1462295800 -0.2193576694 1.1712373495 941 37.6000000000 0.0311384406 0.0450483833 0.0952492654 0.0139843406 0.0213270000 209366314 95654144 760807424 -0.1483154595 -0.2177152783 1.1706590652 942 37.6400000000 0.0320410393 0.0450345751 0.0952492654 0.0139873440 0.0213890000 209369122 95654144 760807424 -0.1499688923 -0.2164660096 1.1698600054 943 37.6800000000 0.0328677930 0.0450216729 0.0952492654 0.0139892703 0.0213040000 209369930 95654144 760807424 -0.1515525430 -0.2159657329 1.1692284346 944 37.7200000000 0.0339322127 0.0450099256 0.0952492654 0.0139933245 0.0212760000 209372738 95654144 760807424 -0.1531936079 -0.2146705687 1.1686946154 945 37.7600000000 0.0349961929 0.0449993290 0.0952492654 0.0139975530 0.0212710000 209375346 95654144 760807424 -0.1548479497 -0.2129614949 1.1705107689 946 37.8000000000 0.0355574563 0.0449893482 0.0952492654 0.0140009658 0.0212260000 209376354 95654144 760807424 -0.1561250985 -0.2125811726 1.1703804731 947 37.8400000000 0.0361120738 0.0449799741 0.0952492654 0.0140027956 0.0211870000 209378962 95654144 760807424 -0.1576479524 -0.2111598849 1.1698610783 948 37.8800000000 0.0369851738 0.0449715407 0.0952492654 0.0140032747 0.0210310000 209379970 95654144 760807424 -0.1590616554 -0.2100801021 1.1720950603 949 37.9200000000 0.0355029814 0.0449615633 0.0952492654 0.0140015771 0.0248930000 209382578 95654144 760807424 -0.1599740684 -0.2049014270 1.1785445213 950 37.9600000000 0.0353360400 0.0449514312 0.0952492654 0.0140007121 0.0211090000 209385386 95654144 760807424 -0.1615722626 -0.2002515197 1.1875405312 951 38.0000000000 0.0363805667 0.0449424187 0.0952492654 0.0140047095 0.0212720000 209386194 95654144 760807424 -0.1629883945 -0.1972427070 1.1914838552 952 38.0400000000 0.0375763401 0.0449346813 0.0952492654 0.0140068792 0.0212940000 209389002 95654144 760807424 -0.1642389894 -0.1951274574 1.1927154064 953 38.0800000000 0.0386902392 0.0449281289 0.0952492654 0.0140063546 0.0212090000 209389810 95654144 760807424 -0.1654919088 -0.1939383596 1.1939283609 954 38.1200000000 0.0387729481 0.0449216769 0.0952492654 0.0140044067 0.0211980000 209392618 95654144 760807424 -0.1666115373 -0.1934443116 1.1951262951 955 38.1600000000 0.0400630832 0.0449165893 0.0952492654 0.0140072886 0.0212010000 209395226 95654144 760807424 -0.1675082594 -0.1934228390 1.1958336830 956 38.2000000000 0.0400246345 0.0449114722 0.0952492654 0.0140070709 0.0210810000 209396234 95654144 760807424 -0.1686085314 -0.1928106844 1.1968612671 957 38.2400000000 0.0403816886 0.0449067389 0.0952492654 0.0140048731 0.0250160000 209398842 95654144 760807424 -0.1700274199 -0.1923002899 1.1966445446 958 38.2800000000 0.0421862267 0.0449038991 0.0952492654 0.0140049127 0.0213300000 209399850 95654144 760807424 -0.1708210409 -0.1935427040 1.1969532967 959 38.3200000000 0.0430331193 0.0449019484 0.0952492654 0.0140033891 0.0241580000 209402458 95654144 760807424 -0.1717952937 -0.1938895732 1.1982481480 960 38.3600000000 0.0419209190 0.0448988431 0.0952492654 0.0140008230 0.0245970000 209405266 95654144 760807424 -0.1730403304 -0.1931121945 1.1986465454 961 38.4000000000 0.0416196361 0.0448954309 0.0952492654 0.0139971006 0.0210300000 209406074 95654144 760807424 -0.1737801880 -0.1935582608 1.1967911720 962 38.4400000000 0.0403078198 0.0448906620 0.0952492654 0.0139918815 0.0212490000 209408882 95654144 760807424 -0.1749547571 -0.1939729601 1.1940047741 963 38.4800000000 0.0407741107 0.0448863873 0.0952492654 0.0139894283 0.0211830000 209411490 95654144 760807424 -0.1756565571 -0.1945334822 1.1919282675 964 38.5200000000 0.0402233750 0.0448815502 0.0952492654 0.0139856762 0.0210750000 209412498 95654144 760807424 -0.1769630313 -0.1940394491 1.1925591230 965 38.5600000000 0.0405668132 0.0448770789 0.0952492654 0.0139844318 0.0212710000 209415106 95654144 760807424 -0.1779061258 -0.1934508830 1.1911598444 966 38.6000000000 0.0399883240 0.0448720181 0.0952492654 0.0139825738 0.0212390000 209416114 95654144 760807424 -0.1789933294 -0.1937201470 1.1900230646 967 38.6400000000 0.0391534194 0.0448661044 0.0952492654 0.0139811312 0.0213570000 209465686 95654144 760807424 -0.1801790893 -0.1925716698 1.1908870935 968 38.6800000000 0.0390852988 0.0448601324 0.0952492654 0.0139833040 0.0212420000 209592862 95654144 760807424 -0.1812869608 -0.1934691221 1.1876585484 969 38.7200000000 0.0390230939 0.0448541087 0.0952492654 0.0139863947 0.0248070000 209593670 95654144 760807424 -0.1822183132 -0.1930044740 1.1888098717 970 38.7600000000 0.0386299901 0.0448476921 0.0952492654 0.0139844041 0.0213250000 209596478 95654144 760807424 -0.1830968261 -0.1940216124 1.1879346371 971 38.8000000000 0.0385407172 0.0448411967 0.0952492654 0.0139848487 0.0212040000 209597286 95654144 760807424 -0.1843289733 -0.1947153360 1.1855301857 972 38.8400000000 0.0390552841 0.0448352441 0.0952492654 0.0139857761 0.0209190000 209600094 95654144 760807424 -0.1853175014 -0.1939808130 1.1865653992 973 38.8800000000 0.0391744040 0.0448294262 0.0952492654 0.0139843406 0.0210220000 209602702 95654144 760807424 -0.1860003620 -0.1943290085 1.1860164404 974 38.9200000000 0.0397893712 0.0448242516 0.0952492654 0.0139826506 0.0209120000 209603710 95654144 760807424 -0.1867645830 -0.1934377551 1.1876678467 975 38.9600000000 0.0388714448 0.0448181462 0.0952492654 0.0139819809 0.0211100000 209606318 95654144 760807424 -0.1880127192 -0.1926989704 1.1852747202 976 39.0000000000 0.0407145992 0.0448139417 0.0952492654 0.0139829986 0.0209810000 209607326 95654144 760807424 -0.1891328990 -0.1913010180 1.1846159697 977 39.0400000000 0.0383123085 0.0448072870 0.0952492654 0.0139780184 0.0209320000 209609934 95654144 760807424 -0.1901916862 -0.1928153932 1.1822009087 978 39.0800000000 0.0394740328 0.0448018338 0.0952492654 0.0139783156 0.0210790000 209612742 95654144 760807424 -0.1911652833 -0.1911109388 1.1804100275 979 39.1200000000 0.0401307419 0.0447970625 0.0952492654 0.0139773390 0.0268440000 209613550 95654144 760807424 -0.1923912317 -0.1910694689 1.1770441532 980 39.1600000000 0.0404270217 0.0447926033 0.0952492654 0.0139767340 0.0213750000 209616358 95654144 760807424 -0.1934952140 -0.1895282418 1.1743474007 981 39.2000000000 0.0408675745 0.0447886022 0.0952492654 0.0139759013 0.0209420000 209618966 95654144 760807424 -0.1944489032 -0.1889223456 1.1735205650 982 39.2400000000 0.0404083803 0.0447841417 0.0952492654 0.0139718730 0.0208750000 209619974 95654144 760807424 -0.1949705482 -0.1896475703 1.1725846529 983 39.2800000000 0.0407971963 0.0447800858 0.0952492654 0.0139706501 0.0209010000 209622582 95654144 760807424 -0.1956009418 -0.1885551661 1.1714031696 984 39.3200000000 0.0402455889 0.0447754776 0.0952492654 0.0139717734 0.0210210000 209623590 95654144 760807424 -0.1965465695 -0.1876941770 1.1677458286 985 39.3600000000 0.0401796699 0.0447708118 0.0952492654 0.0139674645 0.0208100000 209626198 95654144 760807424 -0.1966366619 -0.1884952337 1.1671341658 986 39.4000000000 0.0408838727 0.0447668697 0.0952492654 0.0139672606 0.0208690000 209629006 95654144 760807424 -0.1964605153 -0.1879671812 1.1671565771 987 39.4400000000 0.0409311391 0.0447629834 0.0952492654 0.0139651876 0.0208450000 209629814 95654144 760807424 -0.1963482350 -0.1891914904 1.1669141054 988 39.4800000000 0.0407733321 0.0447589453 0.0952492654 0.0139629384 0.0208650000 209632622 95654144 760807424 -0.1961654425 -0.1905787140 1.1668795347 989 39.5200000000 0.0411518961 0.0447552981 0.0952492654 0.0139603227 0.0254290000 209633430 95654144 760807424 -0.1963616908 -0.1902253032 1.1645758152 990 39.5600000000 0.0420649834 0.0447525807 0.0952492654 0.0139620381 0.0213240000 209636238 95654144 760807424 -0.1966952384 -0.1879699677 1.1630548239 991 39.6000000000 0.0418953262 0.0447496975 0.0952492654 0.0139588448 0.0208960000 209638846 95654144 760807424 -0.1967330128 -0.1883679777 1.1607095003 992 39.6400000000 0.0420204177 0.0447469462 0.0952492654 0.0139565731 0.0208620000 209639854 95654144 760807424 -0.1968534440 -0.1879135221 1.1591911316 993 39.6800000000 0.0415727496 0.0447437496 0.0952492654 0.0139553602 0.0209160000 209642462 95654144 760807424 -0.1976321936 -0.1868263185 1.1545879841 994 39.7200000000 0.0430006795 0.0447419960 0.0952492654 0.0139526241 0.0211260000 209643470 95654144 760807424 -0.1977585703 -0.1864800304 1.1531246901 995 39.7600000000 0.0423556566 0.0447395977 0.0952492654 0.0139510858 0.0210410000 209646078 95654144 760807424 -0.1986644417 -0.1841584891 1.1472873688 996 39.8000000000 0.0429957286 0.0447378468 0.0952492654 0.0139521651 0.0208910000 209648886 95654144 760807424 -0.1988447756 -0.1840262860 1.1474287510 997 39.8400000000 0.0445380546 0.0447376464 0.0952492654 0.0139480387 0.0208940000 209649694 95654144 760807424 -0.1991661638 -0.1817580163 1.1472260952 998 39.8800000000 0.0448710695 0.0447377801 0.0952492654 0.0139421963 0.0208660000 209652502 95654144 760807424 -0.1994574070 -0.1798471063 1.1445924044 999 39.9200000000 0.0459459089 0.0447389894 0.0952492654 0.0139596863 0.0259860000 209655110 95654144 760807424 -0.1999559253 -0.1785618216 1.1421092749 1000 39.9600000000 0.0468487926 0.0447410992 0.0952492654 0.0139563992 0.0247410000 209656118 95654144 760807424 -0.2003098428 -0.1767016500 1.1410086155 1001 40.0000000000 0.0473251753 0.0447436807 0.0952492654 0.0139511630 0.0211630000 209658726 95654144 760807424 -0.2009550482 -0.1746463925 1.1379914284 1002 40.0400000000 0.0490148962 0.0447479434 0.0952492654 0.0139468907 0.0210490000 209659734 95654144 760807424 -0.2015544921 -0.1712842584 1.1354779005 1003 40.0800000000 0.0493538156 0.0447525355 0.0952492654 0.0139453359 0.0209700000 209662342 95654144 760807424 -0.2017731667 -0.1699153036 1.1336618662 1004 40.1200000000 0.0501015447 0.0447578632 0.0952492654 0.0139443920 0.0209480000 209710970 95654144 760807424 -0.2021310925 -0.1700845212 1.1318194866 1005 40.1600000000 0.0504244603 0.0447635016 0.0952492654 0.0139467431 0.0207960000 209837334 95654144 760807424 -0.2027377486 -0.1706348062 1.1320430040 1006 40.2000000000 0.0508555584 0.0447695573 0.0952492654 0.0139581871 0.0208350000 209840142 95654144 760807424 -0.2026496232 -0.1719609499 1.1316968203 1007 40.2400000000 0.0520289503 0.0447767663 0.0952492654 0.0139679524 0.0209110000 209840950 95654144 760807424 -0.2025793642 -0.1743843108 1.1323519945 1008 40.2800000000 0.0528375246 0.0447847631 0.0952492654 0.0139668852 0.0299230000 209843758 95654144 760807424 -0.2022874504 -0.1751097441 1.1319823265 1009 40.3200000000 0.0534691215 0.0447933700 0.0952492654 0.0139651219 0.0219240000 209846366 95654144 760807424 -0.2023824006 -0.1752800047 1.1306853294 1010 40.3600000000 0.0550707951 0.0448035456 0.0952492654 0.0139630603 0.0249290000 209847374 95654144 760807424 -0.2025533617 -0.1732217222 1.1282476187 1011 40.4000000000 0.0564004406 0.0448150163 0.0952492654 0.0139811513 0.0209800000 209849982 95654144 760807424 -0.2024636418 -0.1747259647 1.1276942492 1012 40.4400000000 0.0582121536 0.0448282546 0.0952492654 0.0140100913 0.0211590000 209850990 95654144 760807424 -0.2020491660 -0.1776199043 1.1293580532 1013 40.4800000000 0.0586433560 0.0448418924 0.0952492654 0.0140073989 0.0209590000 209853598 95654144 760807424 -0.2021916956 -0.1759841144 1.1267157793 1014 40.5200000000 0.0597217754 0.0448565669 0.0952492654 0.0140092593 0.0209530000 209856406 95654144 760807424 -0.2023992985 -0.1742553562 1.1254640818 1015 40.5600000000 0.0598128624 0.0448713021 0.0952492654 0.0140232749 0.0209210000 209857214 95654144 760807424 -0.2023442090 -0.1741851717 1.1243715286 1016 40.6000000000 0.0621713325 0.0448883297 0.0952492654 0.0140443815 0.0209560000 209860022 95654144 760807424 -0.2028361559 -0.1743763983 1.1261224747 1017 40.6400000000 0.0628573224 0.0449059984 0.0952492654 0.0140524922 0.0247930000 209862630 95654144 760807424 -0.2029270977 -0.1748410910 1.1249591112 1018 40.6800000000 0.0637839288 0.0449245425 0.0952492654 0.0140640871 0.0210950000 209863638 95654144 760807424 -0.2033500820 -0.1752965599 1.1245193481 1019 40.7200000000 0.0639375895 0.0449432010 0.0952492654 0.0140758264 0.0209300000 209866246 95654144 760807424 -0.2039428055 -0.1759326905 1.1232311726 1020 40.7600000000 0.0642390624 0.0449621185 0.0952492654 0.0140797399 0.0209340000 209867254 95654144 760807424 -0.2045039833 -0.1752663404 1.1222451925 1021 40.8000000000 0.0664396584 0.0449831543 0.0952492654 0.0140955280 0.0208880000 209869862 95654144 760807424 -0.2047367394 -0.1756492555 1.1230589151 1022 40.8400000000 0.0684591457 0.0450061250 0.0952492654 0.0140976272 0.0209780000 209872670 95654144 760807424 -0.2060919553 -0.1738924384 1.1237758398 1023 40.8800000000 0.0687016994 0.0450292878 0.0952492654 0.0141044606 0.0209830000 209873478 95654144 760807424 -0.2066132575 -0.1732205003 1.1231659651 1024 40.9200000000 0.0697039366 0.0450533841 0.0952492654 0.0141202994 0.0219590000 209876286 95654144 760807424 -0.2072139978 -0.1729440987 1.1227740049 1025 40.9600000000 0.0718994364 0.0450795754 0.0952492654 0.0141524321 0.0210400000 209967206 95654144 760807424 -0.2074826062 -0.1731605977 1.1240553856 1026 41.0000000000 0.0744327009 0.0451081847 0.0952492654 0.0141847502 0.0209730000 210174814 95654144 760807424 -0.2078942358 -0.1733246297 1.1244298220 1027 41.0400000000 0.0740358382 0.0451363518 0.0952492654 0.0141931677 0.0246920000 210177422 95654144 760807424 -0.2086618841 -0.1721375436 1.1217334270 1028 41.0800000000 0.0751089379 0.0451655080 0.0952492654 0.0142027659 0.0211010000 210178430 95654144 760807424 -0.2086284906 -0.1689557135 1.1216533184 1029 41.1200000000 0.0773923174 0.0451968266 0.0952492654 0.0142123456 0.0209770000 210181038 95654144 760807424 -0.2089045644 -0.1684794575 1.1221150160 1030 41.1600000000 0.0802949816 0.0452309025 0.0952492654 0.0142211554 0.0209810000 210182046 95654144 760807424 -0.2095218599 -0.1687144935 1.1231750250 1031 41.2000000000 0.0816283152 0.0452662055 0.0952492654 0.0142259825 0.0210230000 210184654 95654144 760807424 -0.2103619128 -0.1658325195 1.1221686602 1032 41.2400000000 0.0845837444 0.0453043039 0.0952492654 0.0142309051 0.0210140000 210187462 95654144 760807424 -0.2107278109 -0.1647675186 1.1233969927 1033 41.2800000000 0.0867908970 0.0453444652 0.0952492654 0.0142314850 0.0209570000 210188270 95654144 760807424 -0.2109814733 -0.1657399833 1.1242974997 1034 41.3200000000 0.0870532915 0.0453848025 0.0952492654 0.0142460430 0.0210720000 210191078 95654144 760807424 -0.2111083269 -0.1623235643 1.1213020086 1035 41.3600000000 0.0870946273 0.0454251019 0.0952492654 0.0142427357 0.0209900000 210193686 95654144 760807424 -0.2109759450 -0.1624563932 1.1202548742 1036 41.4000000000 0.0877486542 0.0454659547 0.0952492654 0.0142479611 0.0210200000 210194694 95654144 760807424 -0.2113292813 -0.1610945165 1.1190892458 1037 41.4400000000 0.0870701745 0.0455060745 0.0952492654 0.0142482651 0.0240340000 210197302 95654144 760807424 -0.2120996565 -0.1574494988 1.1171021461 1038 41.4800000000 0.0883865133 0.0455473851 0.0952492654 0.0142481437 0.0212670000 210198310 95654144 760807424 -0.2128281444 -0.1551740468 1.1164722443 1039 41.5200000000 0.0888993964 0.0455891099 0.0952492654 0.0142564890 0.0220600000 210343602 95654144 760807424 -0.2130763978 -0.1526436657 1.1155411005 1040 41.5600000000 0.0892125443 0.0456310555 0.0952492654 0.0142661380 0.0214400000 210374786 95654144 760807424 -0.2130673975 -0.1508857459 1.1145460606 1041 41.6000000000 0.0901453495 0.0456738166 0.0952492654 0.0142730646 0.0211470000 210375594 95654144 760807424 -0.2131893933 -0.1491303593 1.1144354343 1042 41.6400000000 0.0891900361 0.0457155788 0.0952492654 0.0142825255 0.0210630000 210378402 95654144 760807424 -0.2135829628 -0.1487487555 1.1116536856 1043 41.6800000000 0.0874845013 0.0457556257 0.0952492654 0.0142904760 0.0210440000 210379210 95654144 760807424 -0.2134887874 -0.1475861818 1.1082592010 1044 41.7200000000 0.0885725394 0.0457966381 0.0952492654 0.0142955400 0.0210630000 210382018 95654144 760807424 -0.2139267325 -0.1466973126 1.1082665920 1045 41.7600000000 0.0888348520 0.0458378230 0.0952492654 0.0142953176 0.0211500000 210384626 95654144 760807424 -0.2138415426 -0.1441452652 1.1086199284 1046 41.8000000000 0.0874883980 0.0458776419 0.0952492654 0.0142926534 0.0212650000 210385634 95654144 760807424 -0.2132629007 -0.1426978409 1.1063669920 1047 41.8400000000 0.0870745257 0.0459169894 0.0952492654 0.0142922583 0.0249240000 210388242 95654144 760807424 -0.2133982480 -0.1439106762 1.1051887274 1048 41.8800000000 0.0870836079 0.0459562705 0.0952492654 0.0142909841 0.0212230000 210389250 95654144 760807424 -0.2135012746 -0.1445813626 1.1035195589 1049 41.9200000000 0.0862363130 0.0459946691 0.0952492654 0.0142945472 0.0250280000 210391858 95654144 760807424 -0.2135479152 -0.1455108523 1.1006491184 1050 41.9600000000 0.0867948756 0.0460335264 0.0952492654 0.0142973912 0.0211920000 210394666 95654144 760807424 -0.2137400955 -0.1453667134 1.0996849537 1051 42.0000000000 0.0877244622 0.0460731943 0.0952492654 0.0142973505 0.0210790000 210395474 95654144 760807424 -0.2141196281 -0.1459267735 1.0990834236 1052 42.0400000000 0.0875767767 0.0461126463 0.0952492654 0.0142939010 0.0212170000 210398282 95654144 760807424 -0.2139885575 -0.1443501562 1.0986696482 1053 42.0800000000 0.0896535367 0.0461539957 0.0952492654 0.0142928184 0.0211700000 210400890 95654144 760807424 -0.2143536061 -0.1430226266 1.0996701717 1054 42.1200000000 0.0910631865 0.0461966041 0.0952492654 0.0142938835 0.0211760000 210401898 95654144 760807424 -0.2149667293 -0.1436677277 1.0998535156 1055 42.1600000000 0.0927278623 0.0462407095 0.0952492654 0.0142962463 0.0212000000 210404506 95654144 760807424 -0.2153718770 -0.1444679052 1.1003260612 1056 42.2000000000 0.0929535925 0.0462849452 0.0952492654 0.0142962586 0.0245300000 210405514 95654144 760807424 -0.2151689678 -0.1420547068 1.1007211208 1057 42.2400000000 0.0947948694 0.0463308392 0.0952492654 0.0143069249 0.0212280000 210408122 95654144 760807424 -0.2157827020 -0.1445504725 1.1008332968 1058 42.2800000000 0.0941757411 0.0463760612 0.0952492654 0.0143025756 0.0212910000 210410930 95654144 760807424 -0.2161397934 -0.1442105025 1.0998030901 1059 42.3200000000 0.0937428251 0.0464207890 0.0952492654 0.0142993802 0.0211860000 210411738 95654144 760807424 -0.2165903002 -0.1450056434 1.0988894701 1060 42.3600000000 0.0953125358 0.0464669133 0.0953125358 0.0142964962 0.0211630000 210414546 95654144 760807424 -0.2173916996 -0.1446247399 1.1005284786 1061 42.4000000000 0.0942635983 0.0465119620 0.0953125358 0.0142926382 0.0212180000 210415354 95654144 760807424 -0.2175304443 -0.1443395019 1.0992821455 1062 42.4400000000 0.0945083499 0.0465571564 0.0953125358 0.0142959954 0.0214870000 210418162 95654144 760807424 -0.2180873007 -0.1399065107 1.1029868126 1063 42.4800000000 0.0951736718 0.0466028916 0.0953125358 0.0142923916 0.0211680000 210420770 95654144 760807424 -0.2187945992 -0.1400220543 1.1039637327 1064 42.5200000000 0.0958820134 0.0466492065 0.0958820134 0.0142879817 0.0211020000 210421778 95654144 760807424 -0.2192789167 -0.1398517340 1.1051397324 1065 42.5600000000 0.0984282047 0.0466978253 0.0984282047 0.0142865145 0.0244660000 210424386 95654144 760807424 -0.2200386077 -0.1405164450 1.1082274914 1066 42.6000000000 0.0974640474 0.0467454484 0.0984282047 0.0142813449 0.0211340000 210425394 95654144 760807424 -0.2198300213 -0.1392938793 1.1073794365 1067 42.6400000000 0.0969123170 0.0467924651 0.0984282047 0.0142767326 0.0211530000 210428002 95654144 760807424 -0.2197322845 -0.1373651922 1.1080086231 1068 42.6800000000 0.0965105817 0.0468390177 0.0984282047 0.0142745830 0.0211810000 210430810 95654144 760807424 -0.2194633931 -0.1362012923 1.1088335514 1069 42.7200000000 0.0967419893 0.0468856996 0.0984282047 0.0142812058 0.0212090000 210431618 95654144 760807424 -0.2195490897 -0.1389139295 1.1076679230 1070 42.7600000000 0.0973059088 0.0469328213 0.0984282047 0.0142846266 0.0222440000 210576866 95654144 760807424 -0.2196430564 -0.1407204568 1.1066497564 1071 42.8000000000 0.0977075547 0.0469802300 0.0984282047 0.0142853366 0.0245050000 210608846 95654144 760807424 -0.2200355530 -0.1414704621 1.1076042652 1072 42.8400000000 0.0985016152 0.0470282910 0.0985016152 0.0142839815 0.0211820000 210609854 95654144 760807424 -0.2205819935 -0.1418994814 1.1094624996 1073 42.8800000000 0.0981503576 0.0470759351 0.0985016152 0.0142780781 0.0211460000 210612462 95654144 760807424 -0.2206657678 -0.1414351165 1.1085193157 1074 42.9200000000 0.0979156867 0.0471232719 0.0985016152 0.0142720839 0.0250190000 210613470 95654144 760807424 -0.2207306176 -0.1391825676 1.1097629070 1075 42.9600000000 0.0981652364 0.0471707528 0.0985016152 0.0142656215 0.0242990000 210616078 95654144 760807424 -0.2207359523 -0.1369237304 1.1109173298 1076 43.0000000000 0.0998216048 0.0472196848 0.0998216048 0.0142618985 0.0212390000 210618886 95654144 760807424 -0.2216874212 -0.1369340420 1.1140518188 1077 43.0400000000 0.1002731398 0.0472689452 0.1002731398 0.0142584519 0.0246040000 210619694 95654144 760807424 -0.2224135995 -0.1377239525 1.1162585020 1078 43.0800000000 0.1017708853 0.0473195036 0.1017708853 0.0142571995 0.0213130000 210622502 95654144 760807424 -0.2226706892 -0.1363928616 1.1201695204 1079 43.1200000000 0.1041390151 0.0473721630 0.1041390151 0.0142567260 0.0211900000 210623310 95654144 760807424 -0.2233186960 -0.1362110525 1.1250894070 1080 43.1600000000 0.1044163182 0.0474249817 0.1044163182 0.0142510725 0.0211600000 210626118 95654144 760807424 -0.2233958244 -0.1335671097 1.1286369562 1081 43.2000000000 0.1060328856 0.0474791980 0.1060328856 0.0142586299 0.0212000000 210628726 95654144 760807424 -0.2245185822 -0.1369353235 1.1307798624 1082 43.2400000000 0.1078321189 0.0475349771 0.1078321189 0.0142610365 0.0250770000 210629734 95654144 760807424 -0.2251757085 -0.1380611956 1.1334459782 1083 43.2800000000 0.1094934791 0.0475921871 0.1094934791 0.0142677291 0.0212960000 210632342 95654144 760807424 -0.2255944759 -0.1390652508 1.1367285252 1084 43.3200000000 0.1090922505 0.0476489215 0.1094934791 0.0142635356 0.0214810000 210633350 95654144 760807424 -0.2256841660 -0.1388631463 1.1368571520 1085 43.3600000000 0.1078707427 0.0477044255 0.1094934791 0.0142574525 0.0221330000 210635958 95654144 760807424 -0.2253748477 -0.1378006041 1.1366099119 1086 43.4000000000 0.1092412993 0.0477610893 0.1094934791 0.0142536467 0.0215930000 210638766 95654144 760807424 -0.2254818231 -0.1369959414 1.1393361092 1087 43.4400000000 0.1105103269 0.0478188163 0.1105103269 0.0142504723 0.0252990000 210639574 95654144 760807424 -0.2255537808 -0.1363541037 1.1426252127 1088 43.4800000000 0.1097690836 0.0478757559 0.1105103269 0.0142444201 0.0213190000 210642382 95654144 760807424 -0.2251865268 -0.1347209662 1.1430785656 1089 43.5200000000 0.1095743030 0.0479324120 0.1105103269 0.0142397016 0.0212630000 210644990 95654144 760807424 -0.2248487324 -0.1324997395 1.1456942558 1090 43.5600000000 0.1099464223 0.0479893056 0.1105103269 0.0142345210 0.0213150000 210788026 95654144 760807424 -0.2241587490 -0.1309194267 1.1483376026 1091 43.6000000000 0.1115646660 0.0480475782 0.1115646660 0.0142311811 0.0212090000 210820650 95654144 760807424 -0.2240004390 -0.1303135604 1.1518046856 1092 43.6400000000 0.1113670245 0.0481055630 0.1115646660 0.0142305584 0.0212650000 210821658 95654144 760807424 -0.2238746881 -0.1314341575 1.1529284716 1093 43.6800000000 0.1125211045 0.0481644976 0.1125211045 0.0142306368 0.0213870000 210824266 95654144 760807424 -0.2239113152 -0.1325526088 1.1554443836 1094 43.7200000000 0.1131474897 0.0482238971 0.1131474897 0.0142308905 0.0212340000 210827074 95654144 760807424 -0.2240824699 -0.1339382827 1.1563857794 1095 43.7600000000 0.1138796508 0.0482838567 0.1138796508 0.0142308345 0.0211510000 210827882 95654144 760807424 -0.2244958878 -0.1354068518 1.1582356691 1096 43.8000000000 0.1141437516 0.0483439478 0.1141437516 0.0142282629 0.0211930000 210830690 95654144 760807424 -0.2246867865 -0.1366211772 1.1590732336 1097 43.8400000000 0.1160188317 0.0484056387 0.1160188317 0.0142267700 0.0212270000 210831498 95654144 760807424 -0.2249085307 -0.1376276314 1.1625226736 1098 43.8800000000 0.1187181398 0.0484696756 0.1187181398 0.0142235830 0.0212530000 210834306 95654144 760807424 -0.2253412455 -0.1379459947 1.1667906046 1099 43.9200000000 0.1186853498 0.0485335661 0.1187181398 0.0142184967 0.0212640000 210836914 95654144 760807424 -0.2250360101 -0.1378400177 1.1669576168 1100 43.9600000000 0.1188207045 0.0485974635 0.1188207045 0.0142142420 0.0213510000 210837922 95654144 760807424 -0.2242215574 -0.1355340034 1.1706607342 1101 44.0000000000 0.1189791039 0.0486613887 0.1189791039 0.0142116516 0.0213440000 210840530 95654144 760807424 -0.2235326469 -0.1337848753 1.1738021374 1102 44.0400000000 0.1192993522 0.0487254885 0.1192993522 0.0142139694 0.0213150000 210841538 95654144 760807424 -0.2231729627 -0.1337212026 1.1761351824 1103 44.0800000000 0.1218314916 0.0487917677 0.1218314916 0.0142185177 0.0268010000 210844146 95654144 760807424 -0.2232349813 -0.1351727396 1.1796327829 1104 44.1200000000 0.1232872382 0.0488592455 0.1232872382 0.0142168387 0.0215520000 210846954 95654144 760807424 -0.2233766168 -0.1374783963 1.1807310581 1105 44.1600000000 0.1229252070 0.0489262735 0.1232872382 0.0142128753 0.0212880000 210847762 95654144 760807424 -0.2231530100 -0.1380744129 1.1810251474 1106 44.2000000000 0.1239949465 0.0489941475 0.1239949465 0.0142087014 0.0213440000 210850570 95654144 760807424 -0.2222135514 -0.1377178580 1.1843984127 1107 44.2400000000 0.1247179434 0.0490625520 0.1247179434 0.0142034120 0.0212570000 210853258 95654144 760807424 -0.2221404612 -0.1383907497 1.1859929562 1108 44.2800000000 0.1239614263 0.0491301503 0.1247179434 0.0141980383 0.0212810000 210854266 95654144 760807424 -0.2215482891 -0.1368471235 1.1877737045 1109 44.3200000000 0.1240610853 0.0491977165 0.1247179434 0.0141926922 0.0212740000 210856874 95654144 760807424 -0.2212169170 -0.1368059069 1.1889830828 1110 44.3600000000 0.1221078187 0.0492634013 0.1247179434 0.0141882968 0.0212440000 210857882 95654144 760807424 -0.2204909325 -0.1349897683 1.1886422634 1111 44.4000000000 0.1220826954 0.0493289452 0.1247179434 0.0141835484 0.0212040000 210860490 95654144 760807424 -0.2197192460 -0.1357956380 1.1897435188 1112 44.4400000000 0.1218336150 0.0493941473 0.1247179434 0.0141783156 0.0255190000 210863298 95654144 760807424 -0.2183911800 -0.1359011978 1.1905291080 1113 44.4800000000 0.1196262911 0.0494572489 0.1247179434 0.0141742839 0.0214460000 210864106 95654144 760807424 -0.2171166092 -0.1367167830 1.1877987385 1114 44.5200000000 0.1141768619 0.0495153455 0.1247179434 0.0141824663 0.0213600000 211007454 95654144 760807424 -0.2150409222 -0.1335210949 1.1845278740 1115 44.5600000000 0.1103042960 0.0495698647 0.1247179434 0.0141804076 0.0214160000 211039050 95654144 760807424 -0.2133078575 -0.1324231923 1.1810441017 1116 44.6000000000 0.1062595025 0.0496206619 0.1247179434 0.0141795871 0.0219360000 211041858 95654144 760807424 -0.2110561132 -0.1297793239 1.1792846918 1117 44.6400000000 0.1036076024 0.0496689940 0.1247179434 0.0141771697 0.0252050000 211044466 95654144 760807424 -0.2096175551 -0.1283929944 1.1766669750 1118 44.6800000000 0.1006197482 0.0497145671 0.1247179434 0.0141769371 0.0215080000 211045474 95654144 760807424 -0.2082945108 -0.1269519031 1.1757315397 1119 44.7200000000 0.0976085886 0.0497573679 0.1247179434 0.0141762769 0.0213320000 211048082 95654144 760807424 -0.2064709663 -0.1245550141 1.1754833460 1120 44.7600000000 0.0954977944 0.0497982075 0.1247179434 0.0141720601 0.0213820000 211049090 95654144 760807424 -0.2049309164 -0.1243380234 1.1752331257 1121 44.8000000000 0.0933117867 0.0498370243 0.1247179434 0.0141670184 0.0245830000 211051698 95654144 760807424 -0.2032902837 -0.1237638965 1.1738835573 1122 44.8400000000 0.0917908922 0.0498744163 0.1247179434 0.0141656627 0.0214100000 211054506 95654144 760807424 -0.2025300562 -0.1228968874 1.1730778217 1123 44.8800000000 0.0911631659 0.0499111828 0.1247179434 0.0141623345 0.0215640000 211055314 95654144 760807424 -0.2020292729 -0.1226302683 1.1741428375 1124 44.9200000000 0.0917911306 0.0499484425 0.1247179434 0.0141583506 0.0213810000 211058122 95654144 760807424 -0.2012440413 -0.1239188313 1.1748915911 1125 44.9600000000 0.0903011039 0.0499843116 0.1247179434 0.0141540931 0.0213470000 211060730 95654144 760807424 -0.2002822161 -0.1220665053 1.1747183800 1126 45.0000000000 0.0895573273 0.0500194563 0.1247179434 0.0141489149 0.0246040000 211061738 95654144 760807424 -0.1994810551 -0.1205428019 1.1759272814 1127 45.0400000000 0.0882853791 0.0500534101 0.1247179434 0.0141435450 0.0213110000 211064346 95654144 760807424 -0.1981561035 -0.1185064241 1.1772896051 1128 45.0800000000 0.0868683979 0.0500860475 0.1247179434 0.0141400994 0.0213140000 211065354 95654144 760807424 -0.1969895959 -0.1167594194 1.1778348684 1129 45.1200000000 0.0867879838 0.0501185559 0.1247179434 0.0141341454 0.0213960000 211067962 95654144 760807424 -0.1954844296 -0.1153187454 1.1798862219 1130 45.1600000000 0.0858608857 0.0501501863 0.1247179434 0.0141280423 0.0213800000 211070770 95654144 760807424 -0.1941006333 -0.1131533459 1.1809866428 1131 45.2000000000 0.0850335583 0.0501810292 0.1247179434 0.0141235562 0.0249720000 211071578 95654144 760807424 -0.1933359951 -0.1116495728 1.1811164618 1132 45.2400000000 0.0846622884 0.0502114897 0.1247179434 0.0141190271 0.0216910000 211074386 95654144 760807424 -0.1923379302 -0.1099747121 1.1816533804 1133 45.2800000000 0.0844829455 0.0502417381 0.1247179434 0.0141160940 0.0214850000 211075194 95654144 760807424 -0.1905516982 -0.1083233804 1.1845349073 1134 45.3200000000 0.0848456919 0.0502722531 0.1247179434 0.0141109639 0.0214580000 211078002 95654144 760807424 -0.1886190623 -0.1067940593 1.1872627735 1135 45.3600000000 0.0843967870 0.0503023187 0.1247179434 0.0141062112 0.0214560000 211080610 95654144 760807424 -0.1868833452 -0.1051831320 1.1905425787 1136 45.4000000000 0.0844592601 0.0503323865 0.1247179434 0.0141022585 0.0214490000 211081618 95654144 760807424 -0.1851217896 -0.1035843492 1.1927305460 1137 45.4400000000 0.0829941705 0.0503611127 0.1247179434 0.0141001618 0.0215630000 211084226 95654144 760807424 -0.1830100119 -0.1008136943 1.1965160370 1138 45.4800000000 0.0826582238 0.0503894933 0.1247179434 0.0140967872 0.0215210000 211085234 95654144 760807424 -0.1804973930 -0.1016680822 1.1984010935 1139 45.5200000000 0.0834018365 0.0504184769 0.1247179434 0.0141046894 0.0215280000 211087842 95654144 760807424 -0.1784851551 -0.0990159363 1.1997295618 1140 45.5600000000 0.0847552270 0.0504485969 0.1247179434 0.0141028816 0.0263320000 211090650 95654144 760807424 -0.1771426648 -0.0988579020 1.2014183998 1141 45.6000000000 0.0854911134 0.0504793090 0.1247179434 0.0141037718 0.0218200000 211091458 95654144 760807424 -0.1749816984 -0.0954884589 1.2032666206 1142 45.6400000000 0.0870891809 0.0505113667 0.1247179434 0.0141038095 0.0215510000 211094266 95654144 760807424 -0.1733554304 -0.0942547098 1.2052460909 1143 45.6800000000 0.0893947482 0.0505453854 0.1247179434 0.0141056336 0.0216220000 211096874 95654144 760807424 -0.1710231751 -0.0889074355 1.2064368725 1144 45.7200000000 0.0903487355 0.0505801785 0.1247179434 0.0141021876 0.0216720000 211097882 95654144 760807424 -0.1688654125 -0.0835629702 1.2071126699 1145 45.7600000000 0.0889325365 0.0506136740 0.1247179434 0.0140960744 0.0215850000 211100490 95654144 760807424 -0.1666090786 -0.0836354569 1.2093901634 1146 45.8000000000 0.0929420292 0.0506506098 0.1247179434 0.0141042674 0.0216440000 211101498 95654144 760807424 -0.1653107703 -0.0783943087 1.2090367079 1147 45.8400000000 0.0941974521 0.0506885756 0.1247179434 0.0141040121 0.0217060000 211104106 95654144 760807424 -0.1634149402 -0.0744310841 1.2098979950 1148 45.8800000000 0.0968570784 0.0507287921 0.1247179434 0.0141039289 0.0216040000 211106914 95654144 760807424 -0.1623332500 -0.0732074678 1.2106302977 1149 45.9200000000 0.1010642424 0.0507726002 0.1247179434 0.0141099884 0.0250540000 211107722 95654144 760807424 -0.1607813537 -0.0707151070 1.2110921144 1150 45.9600000000 0.1020276770 0.0508171698 0.1247179434 0.0141097877 0.0218500000 211110530 95654144 760807424 -0.1588193178 -0.0710488111 1.2133826017 1151 46.0000000000 0.1038964093 0.0508632856 0.1247179434 0.0141136122 0.0216170000 211111338 95654144 760807424 -0.1576918662 -0.0703742504 1.2139695883 1152 46.0400000000 0.1034558862 0.0509089389 0.1247179434 0.0141095025 0.0215500000 211114146 95654144 760807424 -0.1556928605 -0.0709355921 1.2157466412 1153 46.0800000000 0.1065490022 0.0509571956 0.1247179434 0.0141112836 0.0216150000 211116754 95654144 760807424 -0.1539742053 -0.0698364228 1.2167192698 1154 46.1200000000 0.1079578176 0.0510065896 0.1247179434 0.0141082448 0.0216960000 211117762 95654144 760807424 -0.1518850476 -0.0702874810 1.2191187143 1155 46.1600000000 0.1082778350 0.0510561751 0.1247179434 0.0141039749 0.0215820000 211120370 95654144 760807424 -0.1499346793 -0.0703752860 1.2211158276 1156 46.2000000000 0.1083280593 0.0511057182 0.1247179434 0.0140982305 0.0215790000 211121378 95654144 760807424 -0.1483504325 -0.0697398484 1.2229962349 1157 46.2400000000 0.1086642072 0.0511554663 0.1247179434 0.0140923390 0.0218560000 211123986 95654144 760807424 -0.1454556286 -0.0699228048 1.2256627083 1158 46.2800000000 0.1090719700 0.0512054805 0.1247179434 0.0140882766 0.0216960000 211126794 95654144 760807424 -0.1439839453 -0.0692378655 1.2276285887 1159 46.3200000000 0.1096953452 0.0512559463 0.1247179434 0.0140862089 0.0285980000 211127602 95654144 760807424 -0.1414944679 -0.0677069947 1.2298719883 1160 46.3600000000 0.1121783927 0.0513084657 0.1247179434 0.0140823196 0.0232160000 211130410 95654144 760807424 -0.1387305409 -0.0688136742 1.2324699163 1161 46.4000000000 0.1086320430 0.0513578400 0.1247179434 0.0140767739 0.0220080000 211133018 95654144 760807424 -0.1373829842 -0.0671908855 1.2332694530 1162 46.4400000000 0.1085106283 0.0514070248 0.1247179434 0.0140729286 0.0218300000 211134026 95654144 760807424 -0.1360384673 -0.0674820319 1.2338979244 1163 46.4800000000 0.1093162447 0.0514568178 0.1247179434 0.0140702573 0.0217900000 211136634 95654144 760807424 -0.1333076954 -0.0687173679 1.2365052700 1164 46.5200000000 0.1122683585 0.0515090614 0.1247179434 0.0140666619 0.0218230000 211137642 95654144 760807424 -0.1308777630 -0.0719752312 1.2398163080 1165 46.5600000000 0.1146128625 0.0515632277 0.1247179434 0.0140632129 0.0218930000 211140250 95654144 760807424 -0.1281607151 -0.0735263377 1.2420061827 1166 46.6000000000 0.1175649837 0.0516198330 0.1247179434 0.0140606014 0.0217310000 211143058 95654144 760807424 -0.1258343905 -0.0755017996 1.2438172102 1167 46.6400000000 0.1174324974 0.0516762278 0.1247179434 0.0140548823 0.0217600000 211143866 95654144 760807424 -0.1246292219 -0.0790646970 1.2444921732 1168 46.6800000000 0.1183715388 0.0517333299 0.1247179434 0.0140499730 0.0218080000 211146674 95654144 760807424 -0.1236093193 -0.0813519806 1.2457009554 1169 46.7200000000 0.1199481711 0.0517916831 0.1247179434 0.0140479045 0.0217770000 211147482 95654144 760807424 -0.1218411401 -0.0834815949 1.2475521564 1170 46.7600000000 0.1187312976 0.0518488964 0.1247179434 0.0140459486 0.0217270000 211150290 95654144 760807424 -0.1200282648 -0.0828552023 1.2499233484 1171 46.8000000000 0.1179334745 0.0519053307 0.1247179434 0.0140425637 0.0217660000 211152898 95654144 760807424 -0.1181389093 -0.0847108215 1.2522230148 1172 46.8400000000 0.1170276552 0.0519608959 0.1247179434 0.0140379286 0.0217490000 211153906 95654144 760807424 -0.1166457385 -0.0861170441 1.2532258034 1173 46.8800000000 0.1166255623 0.0520160235 0.1247179434 0.0140365808 0.0218260000 211156514 95654144 760807424 -0.1149361655 -0.0854721069 1.2543684244 1174 46.9200000000 0.1145840362 0.0520693182 0.1247179434 0.0140324562 0.0218330000 211157522 95654144 760807424 -0.1137269884 -0.0846767873 1.2560735941 1175 46.9600000000 0.1140757203 0.0521220896 0.1247179434 0.0140311613 0.0216530000 211160130 95654144 760807424 -0.1122218594 -0.0849898830 1.2578392029 1176 47.0000000000 0.1133615375 0.0521741639 0.1247179434 0.0140280870 0.0228880000 211162938 95654144 760807424 -0.1109993011 -0.0860353559 1.2586473227 1177 47.0400000000 0.1150418818 0.0522275775 0.1247179434 0.0140276415 0.0253580000 211163746 95654144 760807424 -0.1091987714 -0.0882470682 1.2611693144 1178 47.0800000000 0.1151293740 0.0522809746 0.1247179434 0.0140261880 0.0217390000 211166554 95654144 760807424 -0.1064940989 -0.0873750374 1.2639282942 1179 47.1200000000 0.1147093624 0.0523339249 0.1247179434 0.0140217669 0.0216030000 211169162 95654144 760807424 -0.1049313992 -0.0865508392 1.2656766176 1180 47.1600000000 0.1153638586 0.0523873401 0.1247179434 0.0140171486 0.0252160000 211170170 95654144 760807424 -0.1032432839 -0.0875304490 1.2673759460 1181 47.2000000000 0.1148834974 0.0524402581 0.1247179434 0.0140131166 0.0216130000 211172778 95654144 760807424 -0.1010200754 -0.0865008980 1.2694777250 1182 47.2400000000 0.1143761948 0.0524926573 0.1247179434 0.0140096871 0.0217820000 211173786 95654144 760807424 -0.0993190333 -0.0858574286 1.2711023092 1183 47.2800000000 0.1130696610 0.0525438636 0.1247179434 0.0140040044 0.0216470000 211176394 95654144 760807424 -0.0982455313 -0.0849160925 1.2730189562 1184 47.3200000000 0.1126584485 0.0525946360 0.1247179434 0.0139981334 0.0215620000 211179202 95654144 760807424 -0.0971246213 -0.0849088058 1.2738702297 1185 47.3600000000 0.1114117354 0.0526442707 0.1247179434 0.0139931908 0.0216040000 211180010 95654144 760807424 -0.0955587626 -0.0846056864 1.2750473022 1186 47.4000000000 0.1128561646 0.0526950396 0.1247179434 0.0139907864 0.0257870000 211182818 95654144 760807424 -0.0937980637 -0.0847845152 1.2761476040 1187 47.4400000000 0.1119174883 0.0527449322 0.1247179434 0.0139865430 0.0219350000 211183626 95654144 760807424 -0.0922112763 -0.0831590965 1.2778941393 1188 47.4800000000 0.1130326688 0.0527956794 0.1247179434 0.0139808515 0.0217480000 211186434 95654144 760807424 -0.0908183083 -0.0859583989 1.2794853449 1189 47.5200000000 0.1125217229 0.0528459116 0.1247179434 0.0139749752 0.0216460000 211189042 95654144 760807424 -0.0904948860 -0.0885026082 1.2802499533 1190 47.5600000000 0.1122737676 0.0528958509 0.1247179434 0.0139708533 0.0215870000 211190050 95654144 760807424 -0.0894454494 -0.0875636041 1.2812587023 1191 47.6000000000 0.1120874286 0.0529455500 0.1247179434 0.0139660703 0.0215860000 211192658 95654144 760807424 -0.0890725628 -0.0871925130 1.2823596001 1192 47.6400000000 0.1120168492 0.0529951065 0.1247179434 0.0139607072 0.0216800000 211193666 95654144 760807424 -0.0886117145 -0.0878371447 1.2836302519 1193 47.6800000000 0.1120247841 0.0530445865 0.1247179434 0.0139573258 0.0242230000 211347826 95654144 760807424 -0.0877192393 -0.0867911875 1.2843198776 1194 47.7200000000 0.1121948063 0.0530941260 0.1247179434 0.0139536689 0.0281720000 211821274 95654144 760807424 -0.0865782946 -0.0869993046 1.2857402563 1195 47.7600000000 0.1119081900 0.0531433428 0.1247179434 0.0139511341 0.0218470000 211358830 95654144 760807424 -0.0863845497 -0.0860729516 1.2876875401 1196 47.8000000000 0.1114562005 0.0531920994 0.1247179434 0.0139490254 0.0216790000 211361638 95654144 760807424 -0.0856442153 -0.0848579779 1.2890225649 1197 47.8400000000 0.1105876639 0.0532400489 0.1247179434 0.0139451115 0.0215790000 211364246 95654144 760807424 -0.0851331130 -0.0856817663 1.2899079323 1198 47.8800000000 0.1107394025 0.0532880450 0.1247179434 0.0139395198 0.0216030000 211365254 95654144 760807424 -0.0844477490 -0.0880536065 1.2913912535 1199 47.9200000000 0.1109859571 0.0533361667 0.1247179434 0.0139409543 0.0870990000 211895294 95654144 760807424 -0.0851527900 -0.0865179449 1.2926073074 1200 47.9600000000 0.1118148863 0.0533848990 0.1247179434 0.0139425372 0.0324960000 211898166 95654144 760807424 -0.0854712650 -0.0877050012 1.2934551239 1201 48.0000000000 0.1107918918 0.0534326983 0.1247179434 0.0139431617 0.0294010000 211899038 95654144 760807424 -0.0854941010 -0.0855913013 1.2948731184 1202 48.0400000000 0.1109574512 0.0534805559 0.1247179434 0.0139384453 0.0347720000 211901910 95654144 760807424 -0.0853837430 -0.0864210501 1.2957137823 1203 48.0800000000 0.1119341701 0.0535291457 0.1247179434 0.0139354449 0.0281510000 211902782 95654144 760807424 -0.0850773826 -0.0866824985 1.2965304852 1204 48.1200000000 0.1122777313 0.0535779402 0.1247179434 0.0139324448 0.0285690000 211905654 95654144 760807424 -0.0839435011 -0.0868589059 1.2980035543 1205 48.1600000000 0.1142486632 0.0536282894 0.1247179434 0.0139285673 0.0284990000 211908326 95654144 760807424 -0.0828980878 -0.0893538818 1.2990961075 1206 48.2000000000 0.1147545725 0.0536789745 0.1247179434 0.0139274105 0.0285830000 211909398 95654144 760807424 -0.0824615434 -0.0907292664 1.2997330427 1207 48.2400000000 0.1163595989 0.0537309054 0.1247179434 0.0139262948 0.0283170000 211912070 95654144 760807424 -0.0819586217 -0.0928910896 1.3007684946 1208 48.2800000000 0.1178567410 0.0537839897 0.1247179434 0.0139242770 0.0283280000 211913142 95654144 760807424 -0.0815796554 -0.0947160572 1.3019082546 1209 48.3200000000 0.1165445074 0.0538359008 0.1247179434 0.0139254078 0.0284250000 211915814 95654144 760807424 -0.0807810947 -0.0927887484 1.3020840883 1210 48.3600000000 0.1162324175 0.0538874682 0.1247179434 0.0139253657 0.0282730000 211918686 95654144 760807424 -0.0799865797 -0.0917211100 1.3041021824 1211 48.4000000000 0.1181139201 0.0539405041 0.1247179434 0.0139251698 0.0285050000 211919558 95654144 760807424 -0.0789809749 -0.0944819152 1.3057467937 1212 48.4400000000 0.1197073311 0.0539947672 0.1247179434 0.0139309783 0.0379170000 211922430 95654144 760807424 -0.0771465823 -0.0966904387 1.3063763380 1213 48.4800000000 0.1198653951 0.0540490711 0.1247179434 0.0139258927 0.0343710000 211925102 95654144 760807424 -0.0761759654 -0.0966161564 1.3062680960 1214 48.5200000000 0.1200841963 0.0541034657 0.1247179434 0.0139219222 0.0279000000 211926174 95654144 760807424 -0.0749174505 -0.0962448344 1.3069508076 1215 48.5600000000 0.1194722131 0.0541572672 0.1247179434 0.0139231898 0.0345150000 211928846 95654144 760807424 -0.0733736604 -0.0961460173 1.3081475496 1216 48.6000000000 0.1201793328 0.0542115616 0.1247179434 0.0139272749 0.0278590000 211929918 95654144 760807424 -0.0716640726 -0.0978655219 1.3094425201 1217 48.6400000000 0.1202204302 0.0542658006 0.1247179434 0.0139267275 0.0321430000 211932590 95654144 760807424 -0.0697823912 -0.0967552885 1.3090541363 1218 48.6800000000 0.1202612594 0.0543199841 0.1247179434 0.0139311022 0.0303940000 211935462 95654144 760807424 -0.0675088465 -0.0961922929 1.3109146357 1219 48.7200000000 0.1192359477 0.0543732375 0.1247179434 0.0139302891 0.0338740000 211936334 95654144 760807424 -0.0661636069 -0.0948260948 1.3123954535 1220 48.7600000000 0.1214445606 0.0544282140 0.1247179434 0.0139292388 0.0277870000 211939206 95654144 760807424 -0.0640718639 -0.0975238681 1.3135166168 1221 48.8000000000 0.1213351190 0.0544830108 0.1247179434 0.0139325237 0.0279400000 211940078 95654144 760807424 -0.0626065135 -0.0991321504 1.3143577576 1222 48.8400000000 0.1229257435 0.0545390196 0.1247179434 0.0139349619 0.0281040000 211942950 95654144 760807424 -0.0604900420 -0.0991364866 1.3150835037 1223 48.8800000000 0.1227750704 0.0545948136 0.1247179434 0.0139395764 0.0346440000 211945622 95654144 760807424 -0.0591434427 -0.0985920951 1.3155184984 1224 48.9200000000 0.1234199554 0.0546510433 0.1247179434 0.0139432615 0.0282220000 211946694 95654144 760807424 -0.0569698550 -0.0977210328 1.3170726299 1225 48.9600000000 0.1235420853 0.0547072809 0.1247179434 0.0139479767 0.0348370000 211949366 95654144 760807424 -0.0539207906 -0.0980765894 1.3185731173 1226 49.0000000000 0.1244187430 0.0547641418 0.1247179434 0.0139508423 0.0281820000 211950438 95654144 760807424 -0.0517063066 -0.0978785530 1.3199722767 1227 49.0400000000 0.1236803308 0.0548203082 0.1247179434 0.0139511568 0.0339340000 211953110 95654144 760807424 -0.0495185703 -0.0960891917 1.3212387562 1228 49.0800000000 0.1238894016 0.0548765534 0.1247179434 0.0139499486 0.0282620000 211955982 95654144 760807424 -0.0475110747 -0.0956491008 1.3226288557 1229 49.1200000000 0.1245302558 0.0549332285 0.1247179434 0.0139485248 0.0283140000 211956854 95654144 760807424 -0.0452183671 -0.0953485072 1.3241227865 1230 49.1600000000 0.1235379353 0.0549890047 0.1247179434 0.0139486034 0.0281920000 211959726 95654144 760807424 -0.0431602709 -0.0938883573 1.3249675035 1231 49.2000000000 0.1245458499 0.0550455090 0.1247179434 0.0139452536 0.0280050000 211962398 95654144 760807424 -0.0423464552 -0.0924748704 1.3253725767 1232 49.2400000000 0.1240858212 0.0551015482 0.1247179434 0.0139419089 0.0283010000 211963470 95654144 760807424 -0.0402827971 -0.0910134912 1.3255500793 1233 49.2800000000 0.1247720122 0.0551580531 0.1247720122 0.0139376753 0.0347310000 211966142 95654144 760807424 -0.0396382362 -0.0903899744 1.3260444403 1234 49.3200000000 0.1251256317 0.0552147529 0.1251256317 0.0139332149 0.0282320000 211967214 95654144 760807424 -0.0387191288 -0.0902135968 1.3269066811 1235 49.3600000000 0.1252000481 0.0552714212 0.1252000481 0.0139336406 0.0286790000 211969886 95654144 760807424 -0.0357777327 -0.0897654369 1.3282446861 1236 49.4000000000 0.1250012219 0.0553278369 0.1252000481 0.0139424112 0.0284110000 211972758 95654144 760807424 -0.0344067626 -0.0894372016 1.3286798000 1237 49.4400000000 0.1242464408 0.0553835512 0.1252000481 0.0139473076 0.0285230000 211973630 95654144 760807424 -0.0314766839 -0.0870832279 1.3286994696 1238 49.4800000000 0.1249226257 0.0554397217 0.1252000481 0.0139582591 0.0552900000 211982630 95654144 760807424 -0.0298410337 -0.0857249498 1.3289649487 1239 49.5200000000 0.1251142919 0.0554959562 0.1252000481 0.0139717411 0.0296370000 211977374 95654144 760807424 -0.0272969175 -0.0855285600 1.3289670944 1240 49.5600000000 0.1249936000 0.0555520027 0.1252000481 0.0139812930 0.0286280000 211986374 95654144 760807424 -0.0246595312 -0.0868151784 1.3297842741 1241 49.6000000000 0.1258594245 0.0556086565 0.1258594245 0.0139816641 0.0284340000 211989046 95654144 760807424 -0.0227817427 -0.0860978588 1.3301413059 1242 49.6400000000 0.1272832304 0.0556663655 0.1272832304 0.0139808804 0.0283990000 211916966 95654144 760807424 -0.0211730003 -0.0860756114 1.3306716681 1243 49.6800000000 0.1272076666 0.0557239209 0.1272832304 0.0139755069 0.0380190000 211919638 95654144 760807424 -0.0185625553 -0.0856040642 1.3315622807 1244 49.7200000000 0.1279608905 0.0557819892 0.1279608905 0.0139699224 0.0281930000 211920710 95654144 760807424 -0.0157966465 -0.0848060921 1.3319820166 1245 49.7600000000 0.1289608628 0.0558407674 0.1289608628 0.0139644508 0.0292550000 211923382 95654144 760807424 -0.0144271776 -0.0836993828 1.3316264153 1246 49.8000000000 0.1281457990 0.0558987971 0.1289608628 0.0139600664 0.0287050000 211926254 95654144 760807424 -0.0109504573 -0.0831147730 1.3317091465 1247 49.8400000000 0.1291981637 0.0559575777 0.1291981637 0.0139556611 0.0283310000 211927126 95654144 760807424 -0.0107427267 -0.0821221173 1.3317407370 1248 49.8800000000 0.1292501986 0.0560163057 0.1292501986 0.0139510701 0.0281410000 211929998 95654144 760807424 -0.0090158926 -0.0813494697 1.3311192989 1249 49.9200000000 0.1288328916 0.0560746056 0.1292501986 0.0139455301 0.0282300000 211932670 95654144 760807424 -0.0073306942 -0.0811055079 1.3311587572 1250 49.9600000000 0.1282134503 0.0561323167 0.1292501986 0.0139399937 0.0348010000 212105390 95654144 760807424 -0.0044526984 -0.0788290948 1.3307085037 1251 50.0000000000 0.1287664920 0.0561903776 0.1292501986 0.0139349632 0.0216650000 211648002 95654144 760807424 -0.0033579944 -0.0770771056 1.3301190138 1252 50.0400000000 0.1282121241 0.0562479030 0.1292501986 0.0139300857 0.0282630000 212109134 95654144 760807424 -0.0010614409 -0.0756854415 1.3299726248 1253 50.0800000000 0.1289161444 0.0563058984 0.1292501986 0.0139247911 0.0281950000 212111806 95654144 760807424 -0.0012171076 -0.0746115968 1.3296070099 1254 50.1200000000 0.1281966567 0.0563632275 0.1292501986 0.0139195999 0.0280540000 212114678 95654144 760807424 -0.0000165188 -0.0729593039 1.3284863234 1255 50.1600000000 0.1279820502 0.0564202943 0.1292501986 0.0139148632 0.0280000000 212115550 95654144 760807424 0.0015071982 -0.0723878145 1.3284029961 1256 50.2000000000 0.1277206242 0.0564770621 0.1292501986 0.0139102839 0.0280480000 212118422 95654144 760807424 0.0019713924 -0.0707116872 1.3277120590 1257 50.2400000000 0.1273615658 0.0565334539 0.1292501986 0.0139050013 0.0340040000 212119294 95654144 760807424 0.0022408792 -0.0691689402 1.3278803825 1258 50.2800000000 0.1277296096 0.0565900486 0.1292501986 0.0138994994 0.0281520000 212122166 95654144 760807424 0.0027642827 -0.0675595179 1.3268272877 1259 50.3200000000 0.1266790330 0.0566457190 0.1292501986 0.0138940396 0.0280980000 212125006 95654144 760807424 0.0062583331 -0.0655003414 1.3260180950 1260 50.3600000000 0.1265510768 0.0567011994 0.1292501986 0.0138905007 0.0281480000 212126078 95654144 760807424 0.0088447537 -0.0634097606 1.3248931170 1261 50.4000000000 0.1276791245 0.0567574864 0.1292501986 0.0138859704 0.0283560000 212128750 95654144 760807424 0.0116765294 -0.0633896589 1.3252570629 1262 50.4400000000 0.1287790388 0.0568145558 0.1292501986 0.0138806368 0.0281340000 212129822 95654144 760807424 0.0123237204 -0.0619210973 1.3245050907 1263 50.4800000000 0.1288707554 0.0568716074 0.1292501986 0.0138751668 0.0287150000 212132494 95654144 760807424 0.0144218290 -0.0594491847 1.3232980967 1264 50.5200000000 0.1276952922 0.0569276388 0.1292501986 0.0138698061 0.0344800000 212135366 95654144 760807424 0.0145290699 -0.0565500222 1.3220472336 1265 50.5600000000 0.1270771474 0.0569830930 0.1292501986 0.0138649760 0.0322560000 212136238 95654144 760807424 0.0185831934 -0.0569626391 1.3218948841 1266 50.6000000000 0.1285836846 0.0570396495 0.1292501986 0.0138600863 0.0303650000 212139110 95654144 760807424 0.0192447696 -0.0562527180 1.3216423988 1267 50.6400000000 0.1289590895 0.0570964131 0.1292501986 0.0138547915 0.0342350000 212141782 95654144 760807424 0.0208850279 -0.0538209192 1.3207825422 1268 50.6800000000 0.1285924613 0.0571527980 0.1292501986 0.0138505091 0.0276940000 212142854 95654144 760807424 0.0268525891 -0.0530502535 1.3195567131 1269 50.7200000000 0.1288827807 0.0572093228 0.1292501986 0.0138461686 0.0283620000 212145526 95654144 760807424 0.0276162531 -0.0526202843 1.3187457323 1270 50.7600000000 0.1293744147 0.0572661457 0.1293744147 0.0138412391 0.0277210000 212146598 95654144 760807424 0.0290955082 -0.0521892905 1.3184216022 1271 50.8000000000 0.1284669489 0.0573221652 0.1293744147 0.0138364685 0.0340280000 212149270 95654144 760807424 0.0302906036 -0.0501427166 1.3168216944 1272 50.8400000000 0.1279524267 0.0573776922 0.1293744147 0.0138325097 0.0277370000 212152142 95654144 760807424 0.0331170000 -0.0499147847 1.3160459995 1273 50.8800000000 0.1270961314 0.0574324592 0.1293744147 0.0138275014 0.0277770000 212148598 95654144 760807424 0.0339217186 -0.0473352335 1.3150384426 1274 50.9200000000 0.1281470954 0.0574879652 0.1293744147 0.0138227125 0.0277940000 212151470 95654144 760807424 0.0345189273 -0.0456892028 1.3140794039 1275 50.9600000000 0.1294330806 0.0575443927 0.1294330806 0.0138175700 0.0279610000 212323422 95654144 760807424 0.0373936221 -0.0465575494 1.3148007393 1276 51.0000000000 0.1299172789 0.0576011113 0.1299172789 0.0138122239 0.0280090000 212326294 95654144 760807424 0.0403343923 -0.0471098535 1.3145468235 1277 51.0400000000 0.1317359060 0.0576591652 0.1317359060 0.0138074909 0.0278160000 212328966 95654144 760807424 0.0425383002 -0.0491214655 1.3154129982 1278 51.0800000000 0.1319729388 0.0577173137 0.1319729388 0.0138021493 0.0280670000 212330038 95654144 760807424 0.0440154225 -0.0492817350 1.3152269125 1279 51.1200000000 0.1313474029 0.0577748821 0.1319729388 0.0137971153 0.0332310000 212332710 95654144 760807424 0.0461301990 -0.0495815948 1.3144334555 1280 51.1600000000 0.1322266161 0.0578330476 0.1322266161 0.0137925394 0.0343180000 212333782 95654144 760807424 0.0435472317 -0.0497752056 1.3140763044 1281 51.2000000000 0.1328372657 0.0578915989 0.1328372657 0.0137879294 0.0332430000 212336454 95654144 760807424 0.0440828279 -0.0471351035 1.3127732277 1282 51.2400000000 0.1329151690 0.0579501196 0.1329151690 0.0137828210 0.0308070000 212339878 95654144 760807424 0.0437263250 -0.0456834063 1.3121217489 1283 51.2800000000 0.1348675042 0.0580100708 0.1348675042 0.0137776568 0.0281240000 212340750 95654144 760807424 0.0424127504 -0.0468270294 1.3125629425 1284 51.3200000000 0.1353527009 0.0580703065 0.1353527009 0.0137724260 0.0282180000 212343622 95654144 760807424 0.0428932123 -0.0464398377 1.3126978874 1285 51.3600000000 0.1360609233 0.0581309996 0.1360609233 0.0137671347 0.0281650000 212346294 95654144 760807424 0.0441154465 -0.0462777950 1.3125641346 1286 51.4000000000 0.1368510574 0.0581922127 0.1368510574 0.0137619376 0.0395640000 212346814 95654144 760807424 0.0443555191 -0.0465451740 1.3127080202 1287 51.4400000000 0.1357576251 0.0582524811 0.1368510574 0.0137575430 0.0283600000 212349486 95654144 760807424 0.0460711941 -0.0464555174 1.3123083115 1288 51.4800000000 0.1358491927 0.0583127270 0.1368510574 0.0137543874 0.0282530000 212350558 95654144 760807424 0.0469523333 -0.0481330082 1.3128335476 1289 51.5200000000 0.1349717677 0.0583721987 0.1368510574 0.0137498620 0.0216010000 211897422 95654144 760807424 0.0477903485 -0.0454160944 1.3117324114 1290 51.5600000000 0.1358294934 0.0584322431 0.1368510574 0.0137483877 0.0348250000 212356102 95654144 760807424 0.0496721119 -0.0451567434 1.3119916916 1291 51.6000000000 0.1342675984 0.0584909846 0.1368510574 0.0137506874 0.0280710000 212356974 95654144 760807424 0.0514659956 -0.0442644618 1.3112510443 1292 51.6400000000 0.1353131533 0.0585504445 0.1368510574 0.0137521984 0.0283460000 212359846 95654144 760807424 0.0527369939 -0.0449526757 1.3114948273 1293 51.6800000000 0.1379909217 0.0586118834 0.1379909217 0.0137522023 0.0281460000 212532058 95654144 760807424 0.0512633100 -0.0454130284 1.3122311831 1294 51.7200000000 0.1376859099 0.0586729916 0.1379909217 0.0137483850 0.0282790000 212534930 95654144 760807424 0.0528215505 -0.0457897000 1.3121458292 1295 51.7600000000 0.1388970166 0.0587349407 0.1388970166 0.0137477787 0.0281830000 212537602 95654144 760807424 0.0510728098 -0.0463972948 1.3121951818 1296 51.8000000000 0.1399516016 0.0587976079 0.1399516016 0.0137597731 0.0217000000 212082870 95654144 760807424 0.0504793786 -0.0446928777 1.3114545345 1297 51.8400000000 0.1397622675 0.0588600324 0.1399516016 0.0137601588 0.0281090000 212541346 95654144 760807424 0.0504608266 -0.0446279570 1.3114837408 1298 51.8800000000 0.1397625804 0.0589223610 0.1399516016 0.0137606203 0.0281820000 212542418 95654144 760807424 0.0526714660 -0.0424699895 1.3109151125 1299 51.9200000000 0.1387176365 0.0589837893 0.1399516016 0.0137646556 0.0346130000 212545090 95654144 760807424 0.0545425825 -0.0400544181 1.3102419376 1300 51.9600000000 0.1388350427 0.0590452133 0.1399516016 0.0137687134 0.0281140000 212547962 95654144 760807424 0.0544487983 -0.0381694585 1.3097362518 1301 52.0000000000 0.1391136795 0.0591067571 0.1399516016 0.0137734832 0.0216830000 212093030 95654144 760807424 0.0551590435 -0.0363074578 1.3090633154 1302 52.0400000000 0.1401570290 0.0591690077 0.1401570290 0.0137804832 0.0282900000 212551706 95654144 760807424 0.0551308393 -0.0328110978 1.3080502748 1303 52.0800000000 0.1401926726 0.0592311901 0.1401926726 0.0137859096 0.0280720000 212554378 95654144 760807424 0.0568675883 -0.0282519795 1.3067291975 1304 52.1200000000 0.1388988197 0.0592922849 0.1401926726 0.0137878231 0.0216830000 212099646 95654144 760807424 0.0575534888 -0.0249275025 1.3051705360 1305 52.1600000000 0.1406827718 0.0593546531 0.1406827718 0.0137897995 0.0285780000 212558122 95654144 760807424 0.0585646890 -0.0242474992 1.3042045832 1306 52.2000000000 0.1392077208 0.0594157963 0.1406827718 0.0137889386 0.0282570000 212559194 95654144 760807424 0.0616223812 -0.0197003987 1.3024356365 1307 52.2400000000 0.1409271359 0.0594781615 0.1409271359 0.0137843156 0.0280660000 212734122 95654144 760807424 0.0614292435 -0.0169632062 1.3020802736 1308 52.2800000000 0.1392906904 0.0595391803 0.1409271359 0.0137797907 0.0216750000 212279394 95654144 760807424 0.0626947358 -0.0127371913 1.3001362085 1309 52.3200000000 0.1395496875 0.0596003037 0.1409271359 0.0137761244 0.0216460000 212282002 95654144 760807424 0.0620029047 -0.0093488675 1.2987509966 1310 52.3600000000 0.1380765438 0.0596602092 0.1409271359 0.0137766382 0.0250580000 212284810 95654144 760807424 0.0638612509 -0.0061630765 1.2973072529 1311 52.4000000000 0.1373940408 0.0597195027 0.1409271359 0.0137782535 0.0216690000 212285618 95654144 760807424 0.0641125813 -0.0002870769 1.2959023714 1312 52.4400000000 0.1379761547 0.0597791496 0.1409271359 0.0137785368 0.0216480000 212288426 95654144 760807424 0.0655679256 0.0048040096 1.2941358089 1313 52.4800000000 0.1366056502 0.0598376618 0.1409271359 0.0137762174 0.0216350000 212289234 95654144 760807424 0.0684927776 0.0103689274 1.2920539379 1314 52.5200000000 0.1346955001 0.0598946312 0.1409271359 0.0137751082 0.0216310000 212292042 95654144 760807424 0.0712648109 0.0182774104 1.2887198925 1315 52.5600000000 0.1352606714 0.0599519438 0.1409271359 0.0137709400 0.0217020000 212294650 95654144 760807424 0.0725129917 0.0246767309 1.2867056131 1316 52.6000000000 0.1351443678 0.0600090809 0.1409271359 0.0137666494 0.0217260000 212295658 95654144 760807424 0.0733838007 0.0310725514 1.2847676277 1317 52.6400000000 0.1354374737 0.0600663538 0.1409271359 0.0137650168 0.0216360000 212298266 95654144 760807424 0.0753339902 0.0382394604 1.2829301357 1318 52.6800000000 0.1326144189 0.0601213978 0.1409271359 0.0137632779 0.0217070000 212299274 95654144 760807424 0.0789479166 0.0481154807 1.2797297239 1319 52.7200000000 0.1318447888 0.0601757749 0.1409271359 0.0137610247 0.0255550000 212301882 95654144 760807424 0.0808859318 0.0569449365 1.2776297331 1320 52.7600000000 0.1328602135 0.0602308389 0.1409271359 0.0137591907 0.0254900000 212304690 95654144 760807424 0.0827266425 0.0644516572 1.2763084173 1321 52.8000000000 0.1329868287 0.0602859153 0.1409271359 0.0137597188 0.0219690000 212305498 95654144 760807424 0.0854548216 0.0750501305 1.2740831375 1322 52.8400000000 0.1317839026 0.0603399985 0.1409271359 0.0137560615 0.0217180000 212308306 95654144 760807424 0.0888278112 0.0842010453 1.2715038061 1323 52.8800000000 0.1321776658 0.0603942976 0.1409271359 0.0137533232 0.0216050000 212310914 95654144 760807424 0.0901556164 0.0927624628 1.2694420815 1324 52.9200000000 0.1314491481 0.0604479644 0.1409271359 0.0137556109 0.0217690000 212311922 95654144 760807424 0.0935060233 0.1041401327 1.2662880421 1325 52.9600000000 0.1311043352 0.0605012900 0.1409271359 0.0137540563 0.0215730000 212314530 95654144 760807424 0.0956807211 0.1148902550 1.2633424997 1326 53.0000000000 0.1308620572 0.0605543524 0.1409271359 0.0137529061 0.0215560000 212315538 95654144 760807424 0.0969817787 0.1258107424 1.2604696751 1327 53.0400000000 0.1305143982 0.0606070729 0.1409271359 0.0137502369 0.0215550000 212318146 95654144 760807424 0.0998627171 0.1354190409 1.2574125528 1328 53.0800000000 0.1291615218 0.0606586952 0.1409271359 0.0137523880 0.0216200000 212320954 95654144 760807424 0.1032481268 0.1482119560 1.2544844151 1329 53.1200000000 0.1294689327 0.0607104711 0.1409271359 0.0137491282 0.0215370000 212321762 95654144 760807424 0.1043503210 0.1567647904 1.2527366877 1330 53.1600000000 0.1288664192 0.0607617162 0.1409271359 0.0137451566 0.0216800000 212324570 95654144 760807424 0.1049694046 0.1658991128 1.2505199909 1331 53.2000000000 0.1285818517 0.0608126705 0.1409271359 0.0137499566 0.0216780000 212325378 95654144 760807424 0.1070120335 0.1783443540 1.2474088669 1332 53.2400000000 0.1281309724 0.0608632097 0.1409271359 0.0137516866 0.0216610000 212328186 95654144 760807424 0.1112181768 0.1905505210 1.2438931465 1333 53.2800000000 0.1278205365 0.0609134403 0.1409271359 0.0137469156 0.0216890000 212330794 95654144 760807424 0.1116787642 0.2019812465 1.2413358688 1334 53.3200000000 0.1274037510 0.0609632831 0.1409271359 0.0137439298 0.0215890000 212331802 95654144 760807424 0.1138816699 0.2119684219 1.2387182713 1335 53.3600000000 0.1275874227 0.0610131888 0.1409271359 0.0137405396 0.0217450000 212334410 95654144 760807424 0.1156729460 0.2219696343 1.2365447283 1336 53.4000000000 0.1276879609 0.0610630951 0.1409271359 0.0137356515 0.0216630000 212335418 95654144 760807424 0.1148556545 0.2324848622 1.2349898815 1337 53.4400000000 0.1285364330 0.0611135613 0.1409271359 0.0137308485 0.0215720000 212338026 95654144 760807424 0.1148166880 0.2391417921 1.2329185009 1338 53.4800000000 0.1283893883 0.0611638422 0.1409271359 0.0137278756 0.0216600000 212340834 95654144 760807424 0.1153811663 0.2496262193 1.2306394577 1339 53.5200000000 0.1279272735 0.0612137029 0.1409271359 0.0137356349 0.0215710000 212341642 95654144 760807424 0.1182314903 0.2620468140 1.2278205156 1340 53.5600000000 0.1274268031 0.0612631156 0.1409271359 0.0137503629 0.0255550000 212344450 95654144 760807424 0.1203002334 0.2811810374 1.2241661549 1341 53.6000000000 0.1270919144 0.0613122050 0.1409271359 0.0137513679 0.0216640000 212347058 95654144 760807424 0.1214316785 0.2932646275 1.2226223946 1342 53.6400000000 0.1260046065 0.0613604109 0.1409271359 0.0137470616 0.0216460000 212348066 95654144 760807424 0.1223948821 0.3048355877 1.2217996120 1343 53.6800000000 0.1273630559 0.0614095566 0.1409271359 0.0137431967 0.0216330000 212350674 95654144 760807424 0.1190349311 0.3103615344 1.2224252224 1344 53.7200000000 0.1277962625 0.0614589515 0.1409271359 0.0137390032 0.0216400000 212351682 95654144 760807424 0.1199120060 0.3155690730 1.2221616507 1345 53.7600000000 0.1277835369 0.0615082634 0.1409271359 0.0137388030 0.0216010000 212354290 95654144 760807424 0.1222796366 0.3219254613 1.2218542099 1346 53.8000000000 0.1273897439 0.0615572096 0.1409271359 0.0137384373 0.0216130000 212357098 95654144 760807424 0.1227309555 0.3265592456 1.2222051620 1347 53.8400000000 0.1278990060 0.0616064611 0.1409271359 0.0137879670 0.0215890000 212357906 95654144 760807424 0.1249993220 0.3419493437 1.2225404978 1348 53.8800000000 0.1279199123 0.0616556550 0.1409271359 0.0137883358 0.0216120000 212360714 95654144 760807424 0.1277794391 0.3503121734 1.2224001884 1349 53.9200000000 0.1293320805 0.0617058229 0.1409271359 0.0137836568 0.0215330000 212361522 95654144 760807424 0.1265341938 0.3542189002 1.2234784365 1350 53.9600000000 0.1304933280 0.0617567766 0.1409271359 0.0137788757 0.0262040000 212364330 95654144 760807424 0.1254222989 0.3580122590 1.2236276865 1351 54.0000000000 0.1305746734 0.0618077151 0.1409271359 0.0137747252 0.0216770000 212366938 95654144 760807424 0.1248093173 0.3610677123 1.2248263359 1352 54.0400000000 0.1307144910 0.0618586816 0.1409271359 0.0137705404 0.0216750000 212500038 95654144 760807424 0.1227130890 0.3638540804 1.2254110575 1353 54.0800000000 0.1309786439 0.0619097681 0.1409271359 0.0137744662 0.0216320000 212541070 95654144 760807424 0.1236356720 0.3686899543 1.2257230282 1354 54.1200000000 0.1313922107 0.0619610845 0.1409271359 0.0137756106 0.0216540000 212542078 95654144 760807424 0.1228002533 0.3722726107 1.2265096903 1355 54.1600000000 0.1316445619 0.0620125114 0.1409271359 0.0137778870 0.0216320000 212544686 95654144 760807424 0.1219448447 0.3756128848 1.2271935940 1356 54.2000000000 0.1323847324 0.0620644083 0.1409271359 0.0137810895 0.0337960000 212547494 95654144 760807424 0.1211557910 0.3789079785 1.2276357412 1357 54.2400000000 0.1323783249 0.0621162240 0.1409271359 0.0137815487 0.0224440000 212548302 95654144 760807424 0.1194532663 0.3827587366 1.2284849882 1358 54.2800000000 0.1329924464 0.0621684157 0.1409271359 0.0137786708 0.0216440000 212551110 95654144 760807424 0.1181108654 0.3826336563 1.2288641930 1359 54.3200000000 0.1321517676 0.0622199119 0.1409271359 0.0137753613 0.0215740000 212553718 95654144 760807424 0.1164470762 0.3854658306 1.2297127247 1360 54.3600000000 0.1327628940 0.0622717817 0.1409271359 0.0137762442 0.0300680000 212554726 95654144 760807424 0.1168138161 0.3907251060 1.2302198410 1361 54.4000000000 0.1324851364 0.0623233713 0.1409271359 0.0137713529 0.0219110000 212557334 95654144 760807424 0.1139348000 0.3927345574 1.2313202620 1362 54.4400000000 0.1317179054 0.0623743217 0.1409271359 0.0137678759 0.0215270000 212558342 95654144 760807424 0.1121416390 0.3965736032 1.2326241732 1363 54.4800000000 0.1309110969 0.0624246055 0.1409271359 0.0137636262 0.0224700000 212560950 95654144 760807424 0.1100927293 0.4015516341 1.2337231636 1364 54.5200000000 0.1306048632 0.0624745910 0.1409271359 0.0137591859 0.0216310000 212563758 95654144 760807424 0.1079278588 0.4029842913 1.2350859642 1365 54.5600000000 0.1302436739 0.0625242387 0.1409271359 0.0137553871 0.0215870000 212564566 95654144 760807424 0.1040431783 0.4035867453 1.2375601530 1366 54.6000000000 0.1304302067 0.0625739502 0.1409271359 0.0137560733 0.0215620000 212567374 95654144 760807424 0.1012051478 0.4053460956 1.2398242950 1367 54.6400000000 0.1306488067 0.0626237490 0.1409271359 0.0137657910 0.0215780000 212568182 95654144 760807424 0.1001010165 0.4105023444 1.2419418097 1368 54.6800000000 0.1301255375 0.0626730924 0.1409271359 0.0137653310 0.0215210000 212570990 95654144 760807424 0.0954186320 0.4136489332 1.2452533245 1369 54.7200000000 0.1299947798 0.0627222682 0.1409271359 0.0137683964 0.0215800000 212573598 95654144 760807424 0.0921166465 0.4176935256 1.2480826378 1370 54.7600000000 0.1298911870 0.0627712966 0.1409271359 0.0137703808 0.0215900000 212574606 95654144 760807424 0.0885533392 0.4243056774 1.2505993843 1371 54.8000000000 0.1304527670 0.0628206631 0.1409271359 0.0137673865 0.0216830000 212577214 95654144 760807424 0.0831727758 0.4283399880 1.2535771132 1372 54.8400000000 0.1303862482 0.0628699091 0.1409271359 0.0137676440 0.0254410000 212578222 95654144 760807424 0.0801868737 0.4355151057 1.2562510967 1373 54.8800000000 0.1300952435 0.0629188715 0.1409271359 0.0137658741 0.0216310000 212580830 95654144 760807424 0.0738995150 0.4415155649 1.2595682144 1374 54.9200000000 0.1291267723 0.0629670578 0.1409271359 0.0137645783 0.0255240000 212583638 95654144 760807424 0.0688333139 0.4454848766 1.2625731230 1375 54.9600000000 0.1286556721 0.0630148313 0.1409271359 0.0137666482 0.0215510000 212584446 95654144 760807424 0.0628003106 0.4509035647 1.2661021948 1376 55.0000000000 0.1282508969 0.0630622412 0.1409271359 0.0137701754 0.0214460000 212587254 95654144 760807424 0.0560208783 0.4568107724 1.2695440054 1377 55.0400000000 0.1276486665 0.0631091449 0.1409271359 0.0137764248 0.0215230000 212589862 95654144 760807424 0.0498468652 0.4622846842 1.2730346918 1378 55.0800000000 0.1276547015 0.0631559850 0.1409271359 0.0137810376 0.0260060000 212590870 95654144 760807424 0.0408442579 0.4667595029 1.2775520086 1379 55.1200000000 0.1275596768 0.0632026882 0.1409271359 0.0137849219 0.0216930000 212593478 95654144 760807424 0.0328044519 0.4717032313 1.2813688517 1380 55.1600000000 0.1270637661 0.0632489643 0.1409271359 0.0137957412 0.0215350000 212594486 95654144 760807424 0.0258916132 0.4785842896 1.2847310305 1381 55.2000000000 0.1262412667 0.0632945778 0.1409271359 0.0138050830 0.0214970000 212597094 95654144 760807424 0.0186748877 0.4841576517 1.2883105278 1382 55.2400000000 0.1261171401 0.0633400356 0.1409271359 0.0138144804 0.0254360000 212599902 95654144 760807424 0.0095233647 0.4884316921 1.2926560640 1383 55.2800000000 0.1258899271 0.0633852632 0.1409271359 0.0138306565 0.0216000000 212600710 95654144 760807424 0.0033821389 0.4949755073 1.2957036495 1384 55.3200000000 0.1256236136 0.0634302332 0.1409271359 0.0138420868 0.0216340000 212603518 95654144 760807424 -0.0039819954 0.4996221662 1.2987695932 1385 55.3600000000 0.1250297874 0.0634747094 0.1409271359 0.0138557799 0.0254890000 212604326 95654144 760807424 -0.0098036751 0.5051116943 1.3019219637 1386 55.4000000000 0.1244753376 0.0635187214 0.1409271359 0.0138659093 0.0216000000 212607134 95654144 760807424 -0.0154055599 0.5107775331 1.3048712015 1387 55.4400000000 0.1238321289 0.0635622062 0.1409271359 0.0138778371 0.0216610000 212609742 95654144 760807424 -0.0216825791 0.5141255856 1.3080992699 1388 55.4800000000 0.1240274161 0.0636057690 0.1409271359 0.0138875091 0.0214690000 212610750 95654144 760807424 -0.0284304637 0.5153502226 1.3114441633 1389 55.5200000000 0.1230306178 0.0636485515 0.1409271359 0.0138953183 0.0216330000 212744910 95654144 760807424 -0.0341891311 0.5193397403 1.3143640757 1390 55.5600000000 0.1229554489 0.0636912183 0.1409271359 0.0139089613 0.0255410000 212785530 95654144 760807424 -0.0390226655 0.5223001838 1.3171603680 1391 55.6000000000 0.1228478476 0.0637337464 0.1409271359 0.0139158205 0.0216180000 212788138 95654144 760807424 -0.0428694561 0.5275287032 1.3208069801 1392 55.6400000000 0.1229473129 0.0637762849 0.1409271359 0.0139170882 0.0255460000 212790946 95654144 760807424 -0.0465126857 0.5299145579 1.3241891861 1393 55.6800000000 0.1231444180 0.0638189038 0.1409271359 0.0139167482 0.0226180000 212791754 95654144 760807424 -0.0502953120 0.5326760411 1.3277370930 1394 55.7200000000 0.1223251745 0.0638608739 0.1409271359 0.0139161747 0.0216580000 212794562 95654144 760807424 -0.0539323464 0.5354220271 1.3306320906 1395 55.7600000000 0.1217767000 0.0639023906 0.1409271359 0.0139173202 0.0216230000 212797170 95654144 760807424 -0.0569674000 0.5378058553 1.3339226246 1396 55.8000000000 0.1225136891 0.0639443758 0.1409271359 0.0139278944 0.0251780000 212798178 95654152 760807424 -0.0579656810 0.5407491326 1.3366500139 1397 55.8400000000 0.1229416057 0.0639866071 0.1409271359 0.0139376469 0.0216270000 212800786 95654152 760807424 -0.0619512685 0.5419257283 1.3414447308 1398 55.8800000000 0.1227546707 0.0640286444 0.1409271359 0.0139460584 0.0215520000 212801794 95654152 760807424 -0.0640682280 0.5436993837 1.3465510607 1399 55.9200000000 0.1229325905 0.0640707487 0.1409271359 0.0139541883 0.0215630000 212804402 95654152 760807424 -0.0661492869 0.5468540788 1.3516064882 1400 55.9600000000 0.1232572794 0.0641130248 0.1409271359 0.0139579646 0.0215550000 212807210 95654152 760807424 -0.0673083141 0.5512066483 1.3555785418 1401 56.0000000000 0.1242315769 0.0641559360 0.1409271359 0.0139563949 0.0215550000 212808018 95654152 760807424 -0.0704502091 0.5529579520 1.3608185053 1402 56.0400000000 0.1236998811 0.0641984067 0.1409271359 0.0139563239 0.0215240000 212810826 95654152 760807424 -0.0723915920 0.5551885366 1.3659695387 1403 56.0800000000 0.1231368110 0.0642404155 0.1409271359 0.0139604958 0.0215140000 212811634 95654152 760807424 -0.0730220005 0.5572954416 1.3701010942 1404 56.1200000000 0.1237137616 0.0642827755 0.1409271359 0.0139694116 0.0217400000 212944378 95654152 760807424 -0.0727958381 0.5602037907 1.3741720915 1405 56.1600000000 0.1239319965 0.0643252304 0.1409271359 0.0139746287 0.0329340000 213265074 95654152 760807424 -0.0738301575 0.5639027357 1.3800784349 1406 56.2000000000 0.1246834844 0.0643681595 0.1409271359 0.0140290516 0.0217200000 212991994 95654152 760807424 -0.0744142011 0.5733509064 1.3937669992 1407 56.2400000000 0.1255621761 0.0644116520 0.1409271359 0.0140327691 0.0215790000 212994602 95654152 760807424 -0.0747326538 0.5790488720 1.4012058973 1408 56.2800000000 0.1262056231 0.0644555398 0.1409271359 0.0140338519 0.0225410000 212995610 95654152 760807424 -0.0757960975 0.5820043087 1.4099636078 1409 56.3200000000 0.1271537989 0.0645000382 0.1409271359 0.0140397750 0.0216200000 212998218 95654152 760807424 -0.0772339851 0.5842889547 1.4185804129 1410 56.3600000000 0.1278667152 0.0645449791 0.1409271359 0.0140630311 0.0215370000 213001026 95654152 760807424 -0.0763922334 0.5904217958 1.4256939888 1411 56.4000000000 0.1278328598 0.0645898323 0.1409271359 0.0140755965 0.0215080000 213001834 95654152 760807424 -0.0759255663 0.5951165557 1.4331867695 1412 56.4400000000 0.1277389973 0.0646345555 0.1409271359 0.0140842893 0.0214780000 213004642 95654152 760807424 -0.0779181942 0.5980209708 1.4422498941 1413 56.4800000000 0.1282712966 0.0646795921 0.1409271359 0.0140962726 0.0214250000 213007250 95654152 760807424 -0.0781635419 0.6047351956 1.4515112638 1414 56.5200000000 0.1289849430 0.0647250698 0.1409271359 0.0141039354 0.0249980000 213008258 95654152 760807424 -0.0772512183 0.6117010117 1.4592787027 1415 56.5600000000 0.1294326931 0.0647707995 0.1409271359 0.0141047001 0.0215810000 213010866 95654152 760807424 -0.0774655938 0.6163947582 1.4666138887 1416 56.6000000000 0.1302546710 0.0648170452 0.1409271359 0.0141096113 0.0215130000 213011874 95654152 760807424 -0.0770833567 0.6223542690 1.4729079008 1417 56.6400000000 0.1306600720 0.0648635117 0.1409271359 0.0141147018 0.0217410000 213014482 95654152 760807424 -0.0760626942 0.6268561482 1.4775935411 1418 56.6800000000 0.1309252232 0.0649100996 0.1409271359 0.0141187698 0.0215220000 213017290 95654152 760807424 -0.0757519379 0.6317076087 1.4837162495 1419 56.7200000000 0.1318117827 0.0649572467 0.1409271359 0.0141271105 0.0215780000 213148042 95654152 760807424 -0.0755531117 0.6351230145 1.4898130894 1420 56.7600000000 0.1322786361 0.0650046561 0.1409271359 0.0141340643 0.0215000000 213191430 95654152 760807424 -0.0762633532 0.6409978867 1.4967405796 1421 56.8000000000 0.1327167004 0.0650523071 0.1409271359 0.0141388656 0.0215130000 213192238 95654152 760807424 -0.0769537389 0.6444854736 1.5025783777 1422 56.8400000000 0.1331115663 0.0651001688 0.1409271359 0.0141460369 0.0216400000 213195046 95654152 760807424 -0.0770819336 0.6485561728 1.5077637434 1423 56.8800000000 0.1334151626 0.0651481765 0.1409271359 0.0141519222 0.0247190000 213197654 95654152 760807424 -0.0760647878 0.6544096470 1.5128489733 1424 56.9200000000 0.1342000067 0.0651966679 0.1409271359 0.0141517004 0.0215830000 213198662 95654152 760807424 -0.0762312487 0.6594037414 1.5188412666 1425 56.9600000000 0.1337610483 0.0652447833 0.1409271359 0.0141493159 0.0215680000 213201270 95654152 760807424 -0.0772688687 0.6609482169 1.5246080160 1426 57.0000000000 0.1339293718 0.0652929492 0.1409271359 0.0141513682 0.0215220000 213202278 95654152 760807424 -0.0763245597 0.6637715697 1.5285624266 1427 57.0400000000 0.1343417764 0.0653413366 0.1409271359 0.0141542552 0.0215170000 213204886 95654152 760807424 -0.0759051591 0.6683540940 1.5339033604 1428 57.0800000000 0.1343717575 0.0653896772 0.1409271359 0.0141550659 0.0215190000 213207694 95654152 760807424 -0.0771628618 0.6729511619 1.5416169167 1429 57.1200000000 0.1354148686 0.0654386802 0.1409271359 0.0141549615 0.0214950000 213208502 95654152 760807424 -0.0788917392 0.6769988537 1.5486462116 1430 57.1600000000 0.1359571069 0.0654879938 0.1409271359 0.0141553509 0.0215410000 213211310 95654152 760807424 -0.0784297287 0.6817988157 1.5557726622 1431 57.2000000000 0.1359588951 0.0655372397 0.1409271359 0.0141572016 0.0215520000 213213918 95654152 760807424 -0.0802881569 0.6857943535 1.5641428232 1432 57.2400000000 0.1359615624 0.0655864187 0.1409271359 0.0141603946 0.0246490000 213214926 95654152 760807424 -0.0814879686 0.6900573969 1.5710608959 1433 57.2800000000 0.1364485919 0.0656358689 0.1409271359 0.0141624825 0.0214350000 213217534 95654152 760807424 -0.0827185512 0.6950011253 1.5786602497 1434 57.3200000000 0.1360438019 0.0656849679 0.1409271359 0.0141694774 0.0215060000 213218542 95654152 760807424 -0.0832013115 0.6994656324 1.5857526064 1435 57.3600000000 0.1367462873 0.0657344880 0.1409271359 0.0141784300 0.0214650000 213221150 95654152 760807424 -0.0854426548 0.7015679479 1.5918489695 1436 57.4000000000 0.1368949860 0.0657840426 0.1409271359 0.0141905546 0.0215640000 213223958 95654152 760807424 -0.0856411979 0.7064884305 1.5990352631 1437 57.4400000000 0.1371985674 0.0658337396 0.1409271359 0.0142056605 0.0215400000 213354098 95654152 760807424 -0.0866375044 0.7109328508 1.6079164743 1438 57.4800000000 0.1376439929 0.0658836772 0.1409271359 0.0142220252 0.0214510000 213398066 95654152 760807424 -0.0856346339 0.7170128822 1.6141326427 1439 57.5200000000 0.1381186843 0.0659338752 0.1409271359 0.0142329892 0.0217720000 213398874 95654152 760807424 -0.0856340006 0.7246571183 1.6208755970 1440 57.5600000000 0.1385685652 0.0659843160 0.1409271359 0.0142379735 0.0216070000 213401682 95654152 760807424 -0.0859941915 0.7295367718 1.6281810999 1441 57.6000000000 0.1386904567 0.0660347713 0.1409271359 0.0142450482 0.0214170000 213404290 95654152 760807424 -0.0868575796 0.7319723368 1.6333336830 1442 57.6400000000 0.1383141130 0.0660848957 0.1409271359 0.0142464499 0.0259540000 213405298 95654152 760807424 -0.0869305506 0.7380769253 1.6379640102 1443 57.6800000000 0.1391912699 0.0661355585 0.1409271359 0.0142445721 0.0216200000 213407906 95654152 760807424 -0.0880998001 0.7407591343 1.6437133551 1444 57.7200000000 0.1387230307 0.0661858268 0.1409271359 0.0142417778 0.0214760000 213408914 95654152 760807424 -0.0894994736 0.7437883615 1.6500053406 1445 57.7600000000 0.1402043253 0.0662370507 0.1409271359 0.0142431488 0.0214320000 213411522 95654152 760807424 -0.0896641687 0.7469505668 1.6575659513 1446 57.8000000000 0.1401797235 0.0662881867 0.1409271359 0.0142410411 0.0214410000 213414330 95654152 760807424 -0.0891081691 0.7531726360 1.6626646519 1447 57.8400000000 0.1411465555 0.0663399202 0.1411465555 0.0142370356 0.0213230000 213415138 95654152 760807424 -0.0889780447 0.7537598014 1.6678378582 1448 57.8800000000 0.1413573772 0.0663917278 0.1413573772 0.0142347788 0.0213300000 213417946 95654152 760807424 -0.0905508399 0.7562239766 1.6747363806 1449 57.9200000000 0.1424703449 0.0664442320 0.1424703449 0.0142346713 0.0214690000 213420554 95654152 760807424 -0.0901994333 0.7587327957 1.6799218655 1450 57.9600000000 0.1424587816 0.0664966559 0.1424703449 0.0142325964 0.0214080000 213421562 95654152 760807424 -0.0906058326 0.7616948485 1.6842206717 1451 58.0000000000 0.1435752213 0.0665497769 0.1435752213 0.0142292055 0.0253510000 213424170 95654152 760807424 -0.0911933035 0.7640355229 1.6903455257 1452 58.0400000000 0.1443396807 0.0666033512 0.1443396807 0.0142264864 0.0215990000 213553402 95654152 760807424 -0.0904813036 0.7657178044 1.6951497793 1453 58.0800000000 0.1448138207 0.0666571781 0.1448138207 0.0142235065 0.0215000000 213597654 95654152 760807424 -0.0914220065 0.7660863996 1.6987010241 1454 58.1200000000 0.1452799737 0.0667112515 0.1452799737 0.0142190641 0.0217560000 213600462 95654152 760807424 -0.0906339139 0.7672369480 1.7042539120 1455 58.1600000000 0.1449979395 0.0667650568 0.1452799737 0.0142159291 0.0214350000 213601270 95654152 760807424 -0.0874109939 0.7691453099 1.7080585957 1456 58.2000000000 0.1441465765 0.0668182034 0.1452799737 0.0142127983 0.0305130000 213604078 95654152 760807424 -0.0864500180 0.7711844444 1.7113757133 1457 58.2400000000 0.1447347999 0.0668716809 0.1452799737 0.0142113701 0.0218130000 213604886 95654152 760807424 -0.0847487152 0.7724953294 1.7143675089 1458 58.2800000000 0.1449480355 0.0669252312 0.1452799737 0.0142077282 0.0213300000 213607694 95654152 760807424 -0.0835200697 0.7744766474 1.7178601027 1459 58.3200000000 0.1450505853 0.0669787784 0.1452799737 0.0142032031 0.0213560000 213610302 95654152 760807424 -0.0824393183 0.7745892406 1.7203359604 1460 58.3600000000 0.1460430473 0.0670329320 0.1460430473 0.0141985429 0.0213980000 213611310 95654152 760807424 -0.0781808719 0.7750547528 1.7240729332 1461 58.4000000000 0.1472591460 0.0670878438 0.1472591460 0.0141939689 0.0212010000 213613918 95654152 760807424 -0.0753400922 0.7749800086 1.7277563810 1462 58.4400000000 0.1486800462 0.0671436524 0.1486800462 0.0141896778 0.0213730000 213614926 95654152 760807424 -0.0709527656 0.7762063742 1.7342330217 1463 58.4800000000 0.1498541683 0.0672001873 0.1498541683 0.0141856352 0.0212900000 213617534 95654152 760807424 -0.0664809048 0.7760816813 1.7368419170 1464 58.5200000000 0.1490802318 0.0672561163 0.1498541683 0.0141811464 0.0212660000 213620342 95654152 760807424 -0.0622609667 0.7783278227 1.7403138876 1465 58.5600000000 0.1484089494 0.0673115107 0.1498541683 0.0141763880 0.0212260000 213621150 95654152 760807424 -0.0568600781 0.7793441415 1.7424138784 1466 58.6000000000 0.1490587592 0.0673672728 0.1498541683 0.0141717417 0.0246790000 213623958 95654152 760807424 -0.0532801822 0.7793827057 1.7463110685 1467 58.6400000000 0.1514105052 0.0674245620 0.1514105052 0.0141671450 0.0212980000 213626566 95654152 760807424 -0.0477240644 0.7787599564 1.7505539656 1468 58.6800000000 0.1517774314 0.0674820231 0.1517774314 0.0141628115 0.0213360000 213627574 95654152 760807424 -0.0425980128 0.7795392275 1.7534921169 1469 58.7200000000 0.1509324163 0.0675388307 0.1517774314 0.0141586179 0.0212420000 213630182 95654152 760807424 -0.0358701125 0.7827826738 1.7569967508 1470 58.7600000000 0.1509781480 0.0675955922 0.1517774314 0.0141554111 0.0212670000 213631190 95654152 760807424 -0.0297504216 0.7860088348 1.7586494684 1471 58.8000000000 0.1527647376 0.0676534910 0.1527647376 0.0141510414 0.0212520000 213633798 95654152 760807424 -0.0258382820 0.7864100933 1.7615369558 1472 58.8400000000 0.1547727436 0.0677126752 0.1547727436 0.0141471715 0.0212450000 213636606 95654152 760807424 -0.0207101349 0.7862780094 1.7645066977 1473 58.8800000000 0.1559930295 0.0677726076 0.1559930295 0.0141441920 0.0212480000 213637414 95654152 760807424 -0.0169155039 0.7866967916 1.7658276558 1474 58.9200000000 0.1566848606 0.0678329280 0.1566848606 0.0141416169 0.0212670000 213640222 95654152 760807424 -0.0109697934 0.7882916331 1.7666772604 1475 58.9600000000 0.1569925100 0.0678933752 0.1569925100 0.0141375541 0.0247320000 213768190 95654152 760807424 -0.0055040875 0.7893434167 1.7658185959 1476 59.0000000000 0.1580675095 0.0679544687 0.1580675095 0.0141331573 0.0249760000 213813382 95654152 760807424 -0.0009809225 0.7912198305 1.7663146257 1477 59.0400000000 0.1587519646 0.0680159430 0.1587519646 0.0141286651 0.0213260000 213815990 95654152 760807424 0.0031372993 0.7918131948 1.7664483786 1478 59.0800000000 0.1588115394 0.0680773744 0.1588115394 0.0141240901 0.0212390000 213816998 95654152 760807424 0.0075141047 0.7938661575 1.7671412230 1479 59.1200000000 0.1604275405 0.0681398154 0.1604275405 0.0141212957 0.0211510000 213819606 95654152 760807424 0.0150770042 0.7952841520 1.7654433250 1480 59.1600000000 0.1609059572 0.0682024952 0.1609059572 0.0141170652 0.0211900000 213820614 95654152 760807424 0.0190379135 0.7958717942 1.7628053427 1481 59.2000000000 0.1611071080 0.0682652262 0.1611071080 0.0141128684 0.0211560000 213823222 95654152 760807424 0.0211384576 0.7977499366 1.7646641731 1482 59.2400000000 0.1645524800 0.0683301973 0.1645524800 0.0141091143 0.0211720000 213826030 95654152 760807424 0.0232319310 0.7986877561 1.7695169449 1483 59.2800000000 0.1656577736 0.0683958262 0.1656577736 0.0141047816 0.0211160000 213826838 95654152 760807424 0.0248174928 0.7988718152 1.7671409845 1484 59.3200000000 0.1658381075 0.0684614881 0.1658381075 0.0141008057 0.0217390000 213829646 95654152 760807424 0.0299417786 0.8019949794 1.7685272694 1485 59.3600000000 0.1657717973 0.0685270169 0.1658381075 0.0140971279 0.0212080000 213832254 95654152 760807424 0.0343934670 0.8029848337 1.7668623924 1486 59.4000000000 0.1671609879 0.0685933924 0.1671609879 0.0140924676 0.0211880000 213833262 95654152 760807424 0.0387604646 0.8018776178 1.7658944130 1487 59.4400000000 0.1652226150 0.0686583751 0.1671609879 0.0140880436 0.0211750000 213835870 95654152 760807424 0.0434421003 0.8045307994 1.7633975744 1488 59.4800000000 0.1654918939 0.0687234514 0.1671609879 0.0140835868 0.0211750000 213836878 95654152 760807424 0.0444956347 0.8052058220 1.7606703043 1489 59.5200000000 0.1667979658 0.0687893174 0.1671609879 0.0140790133 0.0211360000 213839486 95654152 760807424 0.0459088385 0.8051923513 1.7607874870 1490 59.5600000000 0.1679430008 0.0688558635 0.1679430008 0.0140748379 0.0211470000 213968598 95654152 760807424 0.0462196767 0.8050524592 1.7590523958 1491 59.6000000000 0.1702190638 0.0689238469 0.1702190638 0.0140710180 0.0212810000 214012274 95654152 760807424 0.0468158387 0.8050937653 1.7602669001 1492 59.6400000000 0.1722697318 0.0689931135 0.1722697318 0.0140667606 0.0211740000 214015082 95654152 760807424 0.0487479903 0.8065128922 1.7649729252 1493 59.6800000000 0.1751749218 0.0690642333 0.1751749218 0.0140626333 0.0211500000 214015890 95654152 760807424 0.0483703129 0.8090795279 1.7698656321 1494 59.7200000000 0.1740594059 0.0691345112 0.1751749218 0.0140579371 0.0247290000 214018698 95654152 760807424 0.0504868031 0.8129700422 1.7715973854 1495 59.7600000000 0.1766321361 0.0692064160 0.1766321361 0.0140544641 0.0212590000 214021306 95654152 760807424 0.0510046147 0.8121237755 1.7730617523 1496 59.8000000000 0.1768256128 0.0692783539 0.1768256128 0.0140527248 0.0211650000 214022314 95654152 760807424 0.0533842891 0.8120675683 1.7717616558 1497 59.8400000000 0.1776146889 0.0693507229 0.1776146889 0.0140506417 0.0213110000 214024922 95654152 760807424 0.0539068729 0.8126909733 1.7710100412 1498 59.8800000000 0.1774338484 0.0694228745 0.1776146889 0.0140466027 0.0212340000 214025930 95654152 760807424 0.0554628968 0.8145630956 1.7676637173 1499 59.9200000000 0.1780045480 0.0694953106 0.1780045480 0.0140424022 0.0256770000 214028538 95654152 760807424 0.0555950254 0.8149322867 1.7670661211 1500 59.9600000000 0.1796040088 0.0695687164 0.1796040088 0.0140379304 0.0213240000 214031346 95654152 760807424 0.0557283536 0.8150815368 1.7697182894 1501 60.0000000000 0.1806360930 0.0696427120 0.1806360930 0.0140335170 0.0212360000 214032154 95654152 760807424 0.0557436310 0.8152564168 1.7705338001 1502 60.0400000000 0.1811130494 0.0697169266 0.1811130494 0.0140290771 0.0211980000 214034962 95654152 760807424 0.0540444702 0.8161864281 1.7723463774 1503 60.0800000000 0.1803979278 0.0697905666 0.1811130494 0.0140247956 0.0212700000 214037570 95654152 760807424 0.0547329895 0.8165451884 1.7712457180 1504 60.1200000000 0.1809378266 0.0698644677 0.1811130494 0.0140206140 0.0211900000 214038578 95654152 760807424 0.0556898341 0.8169472218 1.7708841562 1505 60.1600000000 0.1798201948 0.0699375280 0.1811130494 0.0140163098 0.0212180000 214041186 95654152 760807424 0.0569079667 0.8169490695 1.7669435740 1506 60.2000000000 0.1780408323 0.0700093098 0.1811130494 0.0140120124 0.0212630000 214042194 95654152 760807424 0.0574244931 0.8174775243 1.7627491951 1507 60.2400000000 0.1788268387 0.0700815178 0.1811130494 0.0140083005 0.0212790000 214044802 95654152 760807424 0.0598292574 0.8157812953 1.7629305124 1508 60.2800000000 0.1803655475 0.0701546504 0.1811130494 0.0140049169 0.0212680000 214047610 95654152 760807424 0.0596471913 0.8134611249 1.7628017664 1509 60.3200000000 0.1790644974 0.0702268240 0.1811130494 0.0140006604 0.0212910000 214048418 95654152 760807424 0.0619674698 0.8132771254 1.7595417500 1510 60.3600000000 0.1777904332 0.0702980581 0.1811130494 0.0139963968 0.0212560000 214051226 95654152 760807424 0.0644489378 0.8135758042 1.7618381977 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:26:07 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0092230000 198594044 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0013866430 0.0006933215 0.0013866430 0.0024966977 0.0222860000 199234790 95654128 760807424 0.0013854812 0.0003506358 0.0001633874 3 0.0800000000 0.0010409669 0.0008092033 0.0013866430 0.0022475723 0.0179600000 199084322 95654128 760807424 0.0008512606 -0.0017801201 -0.0005868654 4 0.1200000000 0.0005302234 0.0007394584 0.0013866430 0.0018711030 0.0410980000 199084986 95654128 760807424 0.0002154942 -0.0012006206 -0.0002920120 5 0.1600000000 0.0014926950 0.0008901057 0.0014926950 0.0020471879 0.0209890000 199088146 95654128 760807424 -0.0013063517 -0.0017737364 0.0000970314 6 0.2000000000 0.0012218629 0.0009453985 0.0014926950 0.0018805032 0.0179690000 199089754 95654128 760807424 0.0000093075 -0.0031981333 -0.0000434672 7 0.2400000000 0.0025293804 0.0011716817 0.0025293804 0.0018097818 0.0177460000 199092362 95654128 760807424 0.0009786387 -0.0046210070 -0.0000902005 8 0.2800000000 0.0032095632 0.0014264168 0.0032095632 0.0017711120 0.0176380000 199094970 95654128 760807424 0.0017243383 -0.0035889260 0.0002395323 9 0.3200000000 0.0024100726 0.0015357119 0.0032095632 0.0017151391 0.0176700000 199096682 95654128 760807424 0.0002531074 -0.0034168377 0.0003101851 10 0.3600000000 0.0021472885 0.0015968696 0.0032095632 0.0017339656 0.0177550000 199100890 95654128 760807424 0.0002748376 -0.0039355652 -0.0000382507 11 0.4000000000 0.0044976217 0.0018605743 0.0044976217 0.0018507417 0.0176950000 199103498 95654128 760807424 0.0029839170 -0.0045115817 0.0001149090 12 0.4400000000 0.0062985090 0.0022304022 0.0062985090 0.0018486042 0.0177050000 199104306 95654128 760807424 0.0053039491 -0.0036159081 0.0004612072 13 0.4800000000 0.0066619036 0.0025712869 0.0066619036 0.0018680132 0.0275220000 199107114 95654128 760807424 0.0062176399 -0.0019808537 0.0006646634 14 0.5200000000 0.0064865714 0.0028509501 0.0066619036 0.0018924242 0.0191080000 199109722 95654128 760807424 0.0064493450 -0.0009678295 0.0007124718 15 0.5600000000 0.0062357015 0.0030766002 0.0066619036 0.0018975593 0.0176850000 199110530 95654128 760807424 0.0061874548 -0.0007939647 0.0008529661 16 0.6000000000 0.0059492248 0.0032561392 0.0066619036 0.0018492817 0.0209700000 199113138 95654128 760807424 0.0062241140 -0.0007477928 0.0008634262 17 0.6400000000 0.0048669903 0.0033508952 0.0066619036 0.0017986805 0.0180500000 199115554 95654128 760807424 0.0050068554 -0.0008167662 0.0009526299 18 0.6800000000 0.0028819644 0.0033248435 0.0066619036 0.0018135516 0.0186170000 199121362 95654128 760807424 0.0029812632 -0.0001651331 0.0007798393 19 0.7200000000 0.0022489410 0.0032682170 0.0066619036 0.0020838048 0.0293670000 199123970 95654128 760807424 0.0022328070 0.0000320860 0.0006273653 20 0.7600000000 0.0028598025 0.0032477963 0.0066619036 0.0022165831 0.0209760000 199124778 95654128 760807424 0.0026738523 -0.0016481584 0.0005653308 21 0.8000000000 0.0020175374 0.0031892125 0.0066619036 0.0023819812 0.0178920000 199127586 95654128 760807424 0.0014684289 -0.0020387904 0.0004635834 22 0.8400000000 0.0019349781 0.0031322019 0.0066619036 0.0023895519 0.0227660000 199130194 95654128 760807424 0.0004068622 -0.0025670349 0.0005971208 23 0.8800000000 0.0028123825 0.0031182967 0.0066619036 0.0024190815 0.0184470000 199131002 95654128 760807424 0.0000040051 -0.0036764815 0.0005239913 24 0.9200000000 0.0031593523 0.0031200073 0.0066619036 0.0023856910 0.0177730000 199133610 95654128 760807424 -0.0005972027 -0.0039046707 0.0005036563 25 0.9600000000 0.0050383681 0.0031967418 0.0066619036 0.0023917200 0.0179300000 199136418 95654128 760807424 -0.0032891831 -0.0049859020 0.0005321620 26 1.0000000000 0.0050448948 0.0032678246 0.0066619036 0.0023862380 0.0178020000 199137226 95654128 760807424 -0.0031984826 -0.0046878513 0.0006435137 27 1.0400000000 0.0061486633 0.0033745223 0.0066619036 0.0023526805 0.0178440000 199139834 95654128 760807424 -0.0037906873 -0.0057707224 0.0010165540 28 1.0800000000 0.0063333502 0.0034801947 0.0066619036 0.0023250653 0.0178950000 199142442 95654128 760807424 -0.0037780011 -0.0061915256 0.0009365190 29 1.1200000000 0.0081279883 0.0036404635 0.0081279883 0.0023060617 0.0179050000 199143450 95654128 760807424 -0.0052368990 -0.0073810481 0.0009729961 30 1.1600000000 0.0086491844 0.0038074208 0.0086491844 0.0023528777 0.0179800000 199146058 95654128 760807424 -0.0048417235 -0.0076891920 0.0008797660 31 1.2000000000 0.0080709523 0.0039449541 0.0086491844 0.0023140761 0.0178790000 199146866 95654128 760807424 -0.0036491682 -0.0079182172 0.0006887416 32 1.2400000000 0.0089856936 0.0041024772 0.0089856936 0.0022881257 0.0181460000 199149474 95654128 760807424 -0.0020707175 -0.0096179331 0.0006445546 33 1.2800000000 0.0091170939 0.0042544353 0.0091170939 0.0023091398 0.0208630000 199155098 95654128 760807424 -0.0021444492 -0.0096167447 0.0005942184 34 1.3200000000 0.0096588489 0.0044133886 0.0096588489 0.0023170976 0.0181230000 199162306 95654128 760807424 -0.0031654160 -0.0104495706 0.0004763695 35 1.3600000000 0.0107937576 0.0045956849 0.0107937576 0.0023181795 0.0179950000 199164914 95654128 760807424 -0.0045493292 -0.0122763012 0.0003219509 36 1.4000000000 0.0113940388 0.0047845281 0.0113940388 0.0023141785 0.0212040000 199167522 95654128 760807424 -0.0018101656 -0.0132188955 0.0002502824 37 1.4400000000 0.0131223844 0.0050098755 0.0131223844 0.0022980233 0.0182250000 199168530 95654128 760807424 -0.0014641555 -0.0144224688 0.0006995954 38 1.4800000000 0.0127244527 0.0052128907 0.0131223844 0.0022704493 0.0179910000 199171138 95654128 760807424 -0.0019941819 -0.0146161057 0.0009356203 39 1.5200000000 0.0139555521 0.0054370615 0.0139555521 0.0023350657 0.0180240000 199173746 95654128 760807424 -0.0002593187 -0.0169715583 0.0010603487 40 1.5600000000 0.0137080038 0.0056438351 0.0139555521 0.0023975995 0.0180490000 199174554 95654128 760807424 -0.0014981555 -0.0164497923 0.0018083719 41 1.6000000000 0.0138815446 0.0058447548 0.0139555521 0.0024759588 0.0180320000 199177362 95654128 760807424 -0.0019600743 -0.0154517330 0.0022670799 42 1.6400000000 0.0142691135 0.0060453348 0.0142691135 0.0025371395 0.0180870000 199178170 95654128 760807424 -0.0027641747 -0.0161631275 0.0027113550 43 1.6800000000 0.0123713324 0.0061924510 0.0142691135 0.0025181350 0.0182250000 199180778 95654128 760807424 -0.0048164185 -0.0145663535 0.0029772210 44 1.7200000000 0.0112237409 0.0063067985 0.0142691135 0.0025094278 0.0248000000 199183386 95654128 760807424 -0.0046815728 -0.0130297691 0.0033367940 45 1.7600000000 0.0109371440 0.0064096951 0.0142691135 0.0024905462 0.0187220000 199184394 95654128 760807424 -0.0040546474 -0.0131236501 0.0039724046 46 1.8000000000 0.0103454255 0.0064952544 0.0142691135 0.0026782887 0.0182560000 199187002 95654128 760807424 -0.0053293770 -0.0137091801 0.0050030896 47 1.8400000000 0.0103365006 0.0065769831 0.0142691135 0.0028076062 0.0182780000 199189610 95654128 760807424 -0.0060335835 -0.0141272079 0.0058327327 48 1.8800000000 0.0099931611 0.0066481535 0.0142691135 0.0030150989 0.0183300000 199190418 95654128 760807424 -0.0056316932 -0.0138048790 0.0071948059 49 1.9200000000 0.0106484825 0.0067297928 0.0142691135 0.0032675255 0.0190420000 199193226 95654128 760807424 -0.0066881981 -0.0159652177 0.0079960674 50 1.9600000000 0.0094208959 0.0067836149 0.0142691135 0.0035513672 0.0185630000 199195834 95654128 760807424 -0.0067037162 -0.0152793238 0.0095146075 51 2.0000000000 0.0089612454 0.0068263135 0.0142691135 0.0036972404 0.0184390000 199196642 95654128 760807424 -0.0065887165 -0.0146249998 0.0113581493 52 2.0400000000 0.0088702086 0.0068656192 0.0142691135 0.0038745101 0.0185360000 199199250 95654128 760807424 -0.0065552951 -0.0146427983 0.0131844068 53 2.0800000000 0.0096324477 0.0069178235 0.0142691135 0.0039290301 0.0185210000 199200258 95654128 760807424 -0.0074738380 -0.0164711885 0.0146121075 54 2.1200000000 0.0099858930 0.0069746396 0.0142691135 0.0040161012 0.0184980000 199202866 95654128 760807424 -0.0061285463 -0.0176089425 0.0166206416 55 2.1600000000 0.0111445319 0.0070504558 0.0142691135 0.0040263928 0.0217870000 199205474 95654128 760807424 -0.0071465923 -0.0182286520 0.0190717801 56 2.2000000000 0.0110567054 0.0071219960 0.0142691135 0.0040184702 0.0188530000 199206282 95654128 760807424 -0.0077139116 -0.0175448619 0.0212044157 57 2.2400000000 0.0110192643 0.0071903691 0.0142691135 0.0040424439 0.0185960000 199209090 95654128 760807424 -0.0058767246 -0.0178501550 0.0237810686 58 2.2800000000 0.0100991782 0.0072405210 0.0142691135 0.0041507712 0.0186840000 199211698 95654128 760807424 -0.0061018025 -0.0154606514 0.0267927162 59 2.3200000000 0.0094059361 0.0072772230 0.0142691135 0.0042148529 0.0187360000 199212506 95654128 760807424 -0.0038299721 -0.0153836859 0.0296568405 60 2.3600000000 0.0085978238 0.0072992330 0.0142691135 0.0045198395 0.0187730000 199215114 95654128 760807424 -0.0027302727 -0.0159155093 0.0318261907 61 2.4000000000 0.0078677265 0.0073085525 0.0142691135 0.0047558827 0.0188160000 199217922 95654128 760807424 -0.0008350994 -0.0153728509 0.0347678773 62 2.4400000000 0.0081121009 0.0073215130 0.0142691135 0.0050268670 0.0188710000 199218730 95654128 760807424 0.0004010398 -0.0156979207 0.0376456007 63 2.4800000000 0.0085718147 0.0073413591 0.0142691135 0.0051943740 0.0189350000 199221338 95654128 760807424 0.0021894835 -0.0169392824 0.0403005481 64 2.5200000000 0.0084190564 0.0073581981 0.0142691135 0.0053352503 0.0221740000 199223946 95654128 760807424 0.0041265818 -0.0165454354 0.0433605686 65 2.5600000000 0.0087885922 0.0073802041 0.0142691135 0.0056053806 0.0190960000 199230586 95654128 760807424 0.0047619208 -0.0171558540 0.0461265668 66 2.6000000000 0.0091948286 0.0074076985 0.0142691135 0.0059562710 0.0235800000 199245994 95654128 760807424 0.0060156113 -0.0183941703 0.0486910455 67 2.6400000000 0.0092595313 0.0074353378 0.0142691135 0.0062466098 0.0193270000 199246802 95654128 760807424 0.0080902288 -0.0169944372 0.0519234762 68 2.6800000000 0.0085532544 0.0074517777 0.0142691135 0.0066508674 0.0190290000 199249410 95654128 760807424 0.0089451149 -0.0162011366 0.0547847897 69 2.7200000000 0.0081712585 0.0074622050 0.0142691135 0.0068495031 0.0191020000 199252218 95654128 760807424 0.0111308778 -0.0167615842 0.0575390197 70 2.7600000000 0.0088484911 0.0074820090 0.0142691135 0.0069774846 0.0190700000 199253026 95654128 760807424 0.0123298615 -0.0181133263 0.0599996261 71 2.8000000000 0.0086474428 0.0074984236 0.0142691135 0.0069991361 0.0191370000 199255634 95654128 760807424 0.0142225809 -0.0173384901 0.0631357357 72 2.8400000000 0.0096777463 0.0075286920 0.0142691135 0.0069932348 0.0191760000 199258242 95654128 760807424 0.0141243609 -0.0182342269 0.0657546222 73 2.8800000000 0.0098766144 0.0075608553 0.0142691135 0.0069736094 0.0191740000 199259250 95654128 760807424 0.0155293690 -0.0189970490 0.0681782439 74 2.9200000000 0.0100121330 0.0075939807 0.0142691135 0.0069938000 0.0192250000 199261858 95654128 760807424 0.0178356990 -0.0185226090 0.0712002143 75 2.9600000000 0.0103376769 0.0076305633 0.0142691135 0.0070715355 0.0193310000 199264466 95654128 760807424 0.0189280249 -0.0184551179 0.0738308653 76 3.0000000000 0.0106513221 0.0076703101 0.0142691135 0.0072363961 0.0192840000 199265274 95654128 760807424 0.0201232508 -0.0199305248 0.0759733766 77 3.0400000000 0.0106227370 0.0077086533 0.0142691135 0.0074090420 0.0227680000 199268082 95654128 760807424 0.0212032422 -0.0210376829 0.0780359358 78 3.0800000000 0.0106502436 0.0077463660 0.0142691135 0.0076388764 0.0194750000 199268890 95654128 760807424 0.0224588998 -0.0203045625 0.0806472376 79 3.1200000000 0.0100831576 0.0077759457 0.0142691135 0.0078278480 0.0192460000 199271498 95654128 760807424 0.0237471126 -0.0196439829 0.0833840296 80 3.1600000000 0.0096261576 0.0077990733 0.0142691135 0.0079851624 0.0193400000 199274106 95654128 760807424 0.0245411471 -0.0201462302 0.0855472684 81 3.2000000000 0.0106451213 0.0078342097 0.0142691135 0.0081364165 0.0192800000 199275114 95654128 760807424 0.0256378315 -0.0213799067 0.0882437527 82 3.2400000000 0.0102534974 0.0078637132 0.0142691135 0.0083223636 0.0192910000 199277722 95654128 760807424 0.0259969700 -0.0211462434 0.0907556564 83 3.2800000000 0.0100480802 0.0078900309 0.0142691135 0.0084997755 0.0193100000 199280330 95654128 760807424 0.0273671653 -0.0219456460 0.0931341723 84 3.3200000000 0.0109797707 0.0079268135 0.0142691135 0.0086302662 0.0194650000 199283150 95654128 760807424 0.0273535475 -0.0228597205 0.0955713913 85 3.3600000000 0.0105549330 0.0079577326 0.0142691135 0.0086787454 0.0193690000 199454586 95654128 760807424 0.0287554339 -0.0223095082 0.0981479660 86 3.4000000000 0.0096806521 0.0079777665 0.0142691135 0.0087297101 0.0193460000 199457194 95654128 760807424 0.0300025176 -0.0216800328 0.1006949469 87 3.4400000000 0.0098524448 0.0079993145 0.0142691135 0.0087992156 0.0193730000 199458002 95654128 760807424 0.0312506519 -0.0219117478 0.1035949588 88 3.4800000000 0.0100126304 0.0080221931 0.0142691135 0.0088754828 0.0215160000 199460610 95654128 760807424 0.0321992338 -0.0224554613 0.1063853726 89 3.5200000000 0.0099948114 0.0080443574 0.0142691135 0.0089626169 0.0194200000 199461618 95654128 760807424 0.0328105241 -0.0223587081 0.1092328951 90 3.5600000000 0.0099686831 0.0080657388 0.0142691135 0.0090807676 0.0194110000 199464226 95654128 760807424 0.0330478474 -0.0222497210 0.1119678095 91 3.6000000000 0.0100189783 0.0080872029 0.0142691135 0.0092263159 0.0194440000 199466834 95654128 760807424 0.0337893143 -0.0227241572 0.1149483100 92 3.6400000000 0.0102316886 0.0081105126 0.0142691135 0.0092939565 0.0195160000 199467642 95654128 760807424 0.0351051502 -0.0234064683 0.1183556318 93 3.6800000000 0.0102036987 0.0081330199 0.0142691135 0.0093069673 0.0194480000 199470450 95654128 760807424 0.0355131701 -0.0238757282 0.1212051287 94 3.7200000000 0.0099142194 0.0081519689 0.0142691135 0.0092689922 0.0194150000 199473058 95654128 760807424 0.0371602699 -0.0235454403 0.1241691932 95 3.7600000000 0.0097958697 0.0081692731 0.0142691135 0.0092669209 0.0194150000 199473866 95654128 760807424 0.0380813181 -0.0236515701 0.1274214834 96 3.8000000000 0.0095521016 0.0081836776 0.0142691135 0.0092842118 0.0194520000 199476474 95654128 760807424 0.0390742645 -0.0232622456 0.1305325776 97 3.8400000000 0.0098832464 0.0082011989 0.0142691135 0.0093899778 0.0195010000 199479266 95654128 760807424 0.0398609564 -0.0221774001 0.1341573745 98 3.8800000000 0.0094699776 0.0082141456 0.0142691135 0.0095291915 0.0194670000 199480074 95654128 760807424 0.0402956642 -0.0218663812 0.1373938620 99 3.9200000000 0.0097358953 0.0082295168 0.0142691135 0.0096599643 0.0195190000 199482682 95654128 760807424 0.0410035439 -0.0220694747 0.1406263560 100 3.9600000000 0.0101188729 0.0082484104 0.0142691135 0.0097809611 0.0201760000 199485290 95654128 760807424 0.0409548804 -0.0207888521 0.1441100836 101 4.0000000000 0.0104841087 0.0082705460 0.0142691135 0.0098159036 0.0195550000 199486298 95654128 760807424 0.0421441160 -0.0207055453 0.1476019025 102 4.0400000000 0.0103967935 0.0082913916 0.0142691135 0.0098211593 0.0194520000 199488906 95654128 760807424 0.0428532511 -0.0209284890 0.1505017728 103 4.0800000000 0.0101477280 0.0083094142 0.0142691135 0.0098463955 0.0194220000 199489714 95654128 760807424 0.0432598330 -0.0194744878 0.1538078636 104 4.1200000000 0.0100404760 0.0083260591 0.0142691135 0.0098471971 0.0194740000 199492306 95654128 760807424 0.0441536680 -0.0193332601 0.1570213139 105 4.1600000000 0.0100726075 0.0083426929 0.0142691135 0.0098429293 0.0194200000 199495114 95654128 760807424 0.0448371992 -0.0192637928 0.1598728746 106 4.2000000000 0.0102042984 0.0083602552 0.0142691135 0.0098381901 0.0196320000 199498918 95654128 760807424 0.0449234061 -0.0186605137 0.1626223177 107 4.2400000000 0.0100132544 0.0083757038 0.0142691135 0.0098173593 0.0194230000 199670150 95654128 760807424 0.0454098135 -0.0191022847 0.1649957895 108 4.2800000000 0.0096026650 0.0083870645 0.0142691135 0.0097999226 0.0194300000 199672758 95654128 760807424 0.0457496084 -0.0177920517 0.1677652597 109 4.3200000000 0.0092521878 0.0083950014 0.0142691135 0.0097789117 0.0193540000 199673766 95654128 760807424 0.0462328754 -0.0165834632 0.1704579741 110 4.3600000000 0.0084794108 0.0083957688 0.0142691135 0.0097438574 0.0224000000 199676390 95654128 760807424 0.0464888103 -0.0154424170 0.1727527082 111 4.4000000000 0.0082687419 0.0083946244 0.0142691135 0.0097129098 0.0195550000 199678998 95654128 760807424 0.0472600348 -0.0150497165 0.1756476462 112 4.4400000000 0.0078926310 0.0083901423 0.0142691135 0.0096830890 0.0193770000 199679806 95654128 760807424 0.0472194403 -0.0144061083 0.1781556457 113 4.4800000000 0.0082252668 0.0083886832 0.0142691135 0.0096504824 0.0193590000 199682614 95654128 760807424 0.0468821861 -0.0140226139 0.1806935668 114 4.5200000000 0.0080691287 0.0083858801 0.0142691135 0.0096177903 0.0193630000 199683422 95654128 760807424 0.0466273241 -0.0139282178 0.1829244345 115 4.5600000000 0.0083284331 0.0083853806 0.0142691135 0.0095858392 0.0193180000 199686030 95654128 760807424 0.0477375239 -0.0143672805 0.1853860468 116 4.6000000000 0.0086648464 0.0083877898 0.0142691135 0.0095636129 0.0193130000 199688654 95654128 760807424 0.0482266024 -0.0140685216 0.1879278123 117 4.6400000000 0.0094268797 0.0083966709 0.0142691135 0.0095291173 0.0199480000 199689662 95654128 760807424 0.0489966795 -0.0151123228 0.1904463321 118 4.6800000000 0.0102294367 0.0084122028 0.0142691135 0.0094994624 0.0227280000 199692270 95654128 760807424 0.0498869605 -0.0156779662 0.1933863908 119 4.7200000000 0.0092281010 0.0084190591 0.0142691135 0.0094785700 0.0195850000 199696510 95654128 760807424 0.0503503196 -0.0145458952 0.1962316334 120 4.7600000000 0.0088817757 0.0084229151 0.0142691135 0.0094555731 0.0192680000 199865954 95654128 760807424 0.0499216020 -0.0145152928 0.1988294423 121 4.8000000000 0.0090542482 0.0084281327 0.0142691135 0.0094455471 0.0192960000 199868762 95654128 760807424 0.0501892045 -0.0145266755 0.2020910531 122 4.8400000000 0.0098521048 0.0084398046 0.0142691135 0.0094428495 0.0192120000 199871370 95654128 760807424 0.0507559218 -0.0152277034 0.2053882033 123 4.8800000000 0.0092338854 0.0084462605 0.0142691135 0.0094319897 0.0191340000 199872178 95654128 760807424 0.0504348055 -0.0144972159 0.2080710232 124 4.9200000000 0.0087711560 0.0084488807 0.0142691135 0.0094085446 0.0192160000 199874786 95654128 760807424 0.0506039634 -0.0137123195 0.2111212909 125 4.9600000000 0.0094548780 0.0084569286 0.0142691135 0.0093837329 0.0191200000 199875794 95654128 760807424 0.0510339066 -0.0140661402 0.2144202441 126 5.0000000000 0.0095892316 0.0084659152 0.0142691135 0.0093697432 0.0190860000 199878402 95654128 760807424 0.0514573120 -0.0142425178 0.2174854130 127 5.0400000000 0.0089851329 0.0084700035 0.0142691135 0.0093764205 0.0191040000 199881010 95654128 760807424 0.0516996123 -0.0135763139 0.2210400403 128 5.0800000000 0.0087597622 0.0084722672 0.0142691135 0.0094026069 0.0190680000 199881818 95654128 760807424 0.0515400022 -0.0128749274 0.2240553051 129 5.1200000000 0.0086084716 0.0084733231 0.0142691135 0.0093879880 0.0190590000 199895890 95654128 760807424 0.0519316271 -0.0127053512 0.2271422744 130 5.1600000000 0.0088846292 0.0084764870 0.0142691135 0.0093760048 0.0190740000 199924098 95654128 760807424 0.0518609956 -0.0136906486 0.2298393548 131 5.2000000000 0.0079044485 0.0084721203 0.0142691135 0.0093732665 0.0191050000 199924906 95654128 760807424 0.0520661846 -0.0124271521 0.2324153483 132 5.2400000000 0.0082098944 0.0084701337 0.0142691135 0.0093524887 0.0231060000 199927514 95654128 760807424 0.0524345785 -0.0122097330 0.2353471518 133 5.2800000000 0.0087187486 0.0084720030 0.0142691135 0.0093424910 0.0192860000 199930322 95654128 760807424 0.0533515327 -0.0133231012 0.2380832732 134 5.3200000000 0.0081683993 0.0084697373 0.0142691135 0.0093736477 0.0190220000 199931130 95654128 760807424 0.0537064709 -0.0120582981 0.2408279628 135 5.3600000000 0.0078719202 0.0084653090 0.0142691135 0.0093766097 0.0191580000 199937586 95654128 760807424 0.0541440286 -0.0120867221 0.2432404011 136 5.4000000000 0.0077059763 0.0084597257 0.0142691135 0.0093858952 0.0190150000 200108810 95654128 760807424 0.0546999909 -0.0126298172 0.2454524040 137 5.4400000000 0.0080321888 0.0084566050 0.0142691135 0.0093843925 0.0190210000 200109818 95654128 760807424 0.0555374064 -0.0132125346 0.2479851991 138 5.4800000000 0.0085196914 0.0084570621 0.0142691135 0.0093627345 0.0189920000 200112426 95654128 760807424 0.0562233366 -0.0136119574 0.2502774298 139 5.5200000000 0.0085369842 0.0084576371 0.0142691135 0.0093504546 0.0189320000 200113234 95654128 760807424 0.0563974641 -0.0137477582 0.2522240281 140 5.5600000000 0.0080863358 0.0084549850 0.0142691135 0.0093477112 0.0189200000 200115842 95654128 760807424 0.0564427376 -0.0136943208 0.2544209659 141 5.6000000000 0.0075802291 0.0084487810 0.0142691135 0.0094004182 0.0222610000 200118650 95654128 760807424 0.0562383942 -0.0135460878 0.2582621872 142 5.6400000000 0.0066520879 0.0084361283 0.0142691135 0.0094115864 0.0191180000 200119458 95654128 760807424 0.0559866056 -0.0130884182 0.2606849670 143 5.6800000000 0.0062474506 0.0084208228 0.0142691135 0.0094173407 0.0221590000 200122066 95654128 760807424 0.0558906607 -0.0131382812 0.2627021074 144 5.7200000000 0.0054046880 0.0083998774 0.0142691135 0.0094176611 0.0190090000 200124674 95654128 760807424 0.0553353317 -0.0121339113 0.2646501958 145 5.7600000000 0.0052987295 0.0083784902 0.0142691135 0.0094122694 0.0188240000 200125682 95654128 760807424 0.0546953157 -0.0120010749 0.2664321065 146 5.8000000000 0.0062917243 0.0083641973 0.0142691135 0.0094059285 0.0188270000 200128290 95654128 760807424 0.0542559475 -0.0128851840 0.2681746483 147 5.8400000000 0.0066933888 0.0083528313 0.0142691135 0.0093983259 0.0187720000 200130898 95654128 760807424 0.0536874197 -0.0142801581 0.2697219849 148 5.8800000000 0.0067437813 0.0083419593 0.0142691135 0.0093799745 0.0187910000 200131706 95654128 760807424 0.0526439771 -0.0149987722 0.2711368203 149 5.9200000000 0.0079181474 0.0083391149 0.0142691135 0.0093597822 0.0188850000 200134514 95654128 760807424 0.0513439626 -0.0161676519 0.2725585401 150 5.9600000000 0.0076748650 0.0083346866 0.0142691135 0.0093431080 0.0187730000 200135322 95654128 760807424 0.0500830002 -0.0159733091 0.2740505040 151 6.0000000000 0.0078632655 0.0083315646 0.0142691135 0.0093231785 0.0195960000 200140434 95654128 760807424 0.0497208163 -0.0166796558 0.2764169574 152 6.0400000000 0.0083046034 0.0083313872 0.0142691135 0.0093057973 0.0189150000 200311682 95654128 760807424 0.0485964194 -0.0173179377 0.2781107724 153 6.0800000000 0.0071872687 0.0083239093 0.0142691135 0.0093023040 0.0187860000 200312690 95654128 760807424 0.0474845096 -0.0164653845 0.2805635929 154 6.1200000000 0.0077331644 0.0083200733 0.0142691135 0.0092796613 0.0224090000 200315298 95654128 760807424 0.0461384654 -0.0173073597 0.2818415761 155 6.1600000000 0.0085299462 0.0083214273 0.0142691135 0.0092588367 0.0191820000 200317906 95654128 760807424 0.0447695367 -0.0183346681 0.2837490141 156 6.2000000000 0.0084921401 0.0083225216 0.0142691135 0.0092665072 0.0188810000 200318714 95654128 760807424 0.0413456485 -0.0185354780 0.2863671780 157 6.2400000000 0.0086734407 0.0083247568 0.0142691135 0.0092468046 0.0187700000 200321522 95654128 760807424 0.0400361940 -0.0187700819 0.2884452939 158 6.2800000000 0.0080677858 0.0083231304 0.0142691135 0.0092303889 0.0188620000 200324130 95654128 760807424 0.0381792672 -0.0186863262 0.2910638154 159 6.3200000000 0.0079352735 0.0083206910 0.0142691135 0.0092231067 0.0187750000 200324938 95654128 760807424 0.0362410694 -0.0176242609 0.2914486527 160 6.3600000000 0.0075133545 0.0083156452 0.0142691135 0.0092146590 0.0188310000 200327546 95654128 760807424 0.0341827236 -0.0162718147 0.2932592630 161 6.4000000000 0.0080118570 0.0083137583 0.0142691135 0.0092044682 0.0183700000 200328554 95654128 760807424 0.0325850025 -0.0168020669 0.2948077321 162 6.4400000000 0.0079440176 0.0083114760 0.0142691135 0.0092215939 0.0184300000 200331162 95654128 760807424 0.0302395467 -0.0163851548 0.2965458632 163 6.4800000000 0.0081667770 0.0083105882 0.0142691135 0.0092165392 0.0184200000 200333770 95654128 760807424 0.0283984095 -0.0164420586 0.2981878221 164 6.5200000000 0.0081414878 0.0083095571 0.0142691135 0.0092012461 0.0183690000 200334578 95654128 760807424 0.0271593053 -0.0174438544 0.3007928431 165 6.5600000000 0.0090463487 0.0083140225 0.0142691135 0.0091906452 0.0186490000 200337386 95654128 760807424 0.0256181136 -0.0181150828 0.3017408252 166 6.6000000000 0.0095276516 0.0083213336 0.0142691135 0.0091750551 0.0184640000 200339994 95654128 760807424 0.0245197155 -0.0192683134 0.3036439717 167 6.6400000000 0.0101432707 0.0083322434 0.0142691135 0.0091590667 0.0183680000 200340802 95654128 760807424 0.0228957441 -0.0199256688 0.3060754240 168 6.6800000000 0.0099167041 0.0083416747 0.0142691135 0.0091429387 0.0190080000 200343410 95654128 760807424 0.0212375559 -0.0202148259 0.3076653183 169 6.7200000000 0.0097228372 0.0083498472 0.0142691135 0.0091276085 0.0187280000 200346218 95654128 760807424 0.0203785170 -0.0206379890 0.3093973398 170 6.7600000000 0.0098206820 0.0083584992 0.0142691135 0.0091112225 0.0220580000 200347026 95654128 760807424 0.0194881782 -0.0216398723 0.3121440411 171 6.8000000000 0.0099503798 0.0083678084 0.0142691135 0.0090930376 0.0185740000 200349634 95654128 760807424 0.0180054139 -0.0217474718 0.3125233948 172 6.8400000000 0.0104572736 0.0083799565 0.0142691135 0.0090747908 0.0183790000 200352242 95654128 760807424 0.0169137381 -0.0224799328 0.3128622472 173 6.8800000000 0.0114083327 0.0083974616 0.0142691135 0.0090567038 0.0184530000 200353250 95654128 760807424 0.0160985850 -0.0238165427 0.3131984174 174 6.9200000000 0.0108471634 0.0084115403 0.0142691135 0.0090755957 0.0184870000 200355858 95654128 760807424 0.0154910851 -0.0242316537 0.3149914443 175 6.9600000000 0.0103174485 0.0084224312 0.0142691135 0.0090917690 0.0184470000 200356666 95654128 760807424 0.0144264549 -0.0241802186 0.3162508309 176 7.0000000000 0.0106538497 0.0084351097 0.0142691135 0.0091032559 0.0249860000 200359274 95654128 760807424 0.0135685094 -0.0249553435 0.3166743815 177 7.0400000000 0.0104181645 0.0084463134 0.0142691135 0.0091247556 0.0190920000 200364242 95654128 760807424 0.0129006589 -0.0252962541 0.3175981641 178 7.0800000000 0.0109451478 0.0084603518 0.0142691135 0.0091294945 0.0184400000 200533706 95654128 760807424 0.0123294946 -0.0261044446 0.3176765442 179 7.1200000000 0.0110573564 0.0084748602 0.0142691135 0.0091343078 0.0184320000 200536314 95654128 760807424 0.0117688468 -0.0263416879 0.3181162477 180 7.1600000000 0.0111495387 0.0084897196 0.0142691135 0.0091622617 0.0184410000 200538922 95654128 760807424 0.0114358049 -0.0272607859 0.3192656636 181 7.2000000000 0.0106465239 0.0085016356 0.0142691135 0.0091833478 0.0185100000 200539930 95654128 760807424 0.0109628160 -0.0271962546 0.3199926019 182 7.2400000000 0.0105937906 0.0085131310 0.0142691135 0.0092007261 0.0183820000 200542538 95654128 760807424 0.0105242655 -0.0272638202 0.3203142881 183 7.2800000000 0.0104503138 0.0085237167 0.0142691135 0.0092251765 0.0186240000 200545146 95654128 760807424 0.0101708816 -0.0276417006 0.3207739890 184 7.3200000000 0.0100503108 0.0085320134 0.0142691135 0.0093682788 0.0184740000 200545954 95654128 760807424 0.0096080285 -0.0281286705 0.3218400776 185 7.3600000000 0.0103071053 0.0085416085 0.0142691135 0.0093810958 0.0183590000 200548762 95654128 760807424 0.0093232971 -0.0278927516 0.3209868371 186 7.4000000000 0.0103325341 0.0085512371 0.0142691135 0.0093808888 0.0183380000 200549570 95654128 760807424 0.0087821558 -0.0284082927 0.3221346140 187 7.4400000000 0.0105891367 0.0085621349 0.0142691135 0.0093687550 0.0217750000 200552178 95654128 760807424 0.0084656943 -0.0287777819 0.3232462108 188 7.4800000000 0.0105074625 0.0085724824 0.0142691135 0.0093562118 0.0184120000 200554786 95654128 760807424 0.0083256215 -0.0290449280 0.3246980906 189 7.5200000000 0.0106284050 0.0085833603 0.0142691135 0.0093535792 0.0184850000 200555794 95654128 760807424 0.0080371415 -0.0288910400 0.3254358172 190 7.5600000000 0.0104698762 0.0085932894 0.0142691135 0.0093647210 0.0182260000 200558402 95654128 760807424 0.0081305401 -0.0288068634 0.3272216618 191 7.6000000000 0.0104798442 0.0086031666 0.0142691135 0.0093560331 0.0181300000 200561010 95654128 760807424 0.0083982032 -0.0291434340 0.3288393915 192 7.6400000000 0.0099397181 0.0086101278 0.0142691135 0.0093459924 0.0182630000 200561818 95654128 760807424 0.0084881363 -0.0294315573 0.3315434456 193 7.6800000000 0.0092718443 0.0086135564 0.0142691135 0.0093389995 0.0181240000 200564626 95654128 760807424 0.0084018381 -0.0292331688 0.3339574337 194 7.7200000000 0.0087006846 0.0086140055 0.0142691135 0.0093267747 0.0181330000 200567234 95654128 760807424 0.0086471923 -0.0287236143 0.3355250657 195 7.7600000000 0.0077620088 0.0086096363 0.0142691135 0.0093173974 0.0182210000 200569694 95654128 760807424 0.0088207331 -0.0286082122 0.3383428752 196 7.8000000000 0.0075564189 0.0086042627 0.0142691135 0.0093074875 0.0181310000 200740962 95654128 760807424 0.0088535687 -0.0287860874 0.3399810493 197 7.8400000000 0.0071702315 0.0085969834 0.0142691135 0.0092969955 0.0181840000 200741970 95654128 760807424 0.0089548556 -0.0288909860 0.3419222236 198 7.8800000000 0.0067705102 0.0085877588 0.0142691135 0.0092869096 0.0181570000 200744578 95654128 760807424 0.0090036942 -0.0285806973 0.3446367085 199 7.9200000000 0.0068663671 0.0085791086 0.0142691135 0.0092751361 0.0181530000 200747186 95654128 760807424 0.0092915269 -0.0289019067 0.3450281322 200 7.9600000000 0.0067480258 0.0085699532 0.0142691135 0.0092621423 0.0181420000 200747994 95654128 760807424 0.0097314212 -0.0290218964 0.3439240754 201 8.0000000000 0.0062633930 0.0085584777 0.0142691135 0.0092608100 0.0180120000 200750802 95654128 760807424 0.0097763725 -0.0287096482 0.3471523523 202 8.0400000000 0.0065467642 0.0085485188 0.0142691135 0.0092446886 0.0180180000 200753410 95654128 760807424 0.0101386206 -0.0289964918 0.3449006081 203 8.0800000000 0.0063858787 0.0085378654 0.0142691135 0.0092333215 0.0188810000 200754218 95654128 760807424 0.0103479968 -0.0285350587 0.3445518315 204 8.1200000000 0.0066384375 0.0085285544 0.0142691135 0.0092328407 0.0181130000 200756826 95654128 760807424 0.0105556985 -0.0287963115 0.3449708521 205 8.1600000000 0.0071514812 0.0085218370 0.0142691135 0.0092327516 0.0214300000 200759634 95654128 760807424 0.0108021637 -0.0291533098 0.3450272977 206 8.1999999990 0.0066527370 0.0085127637 0.0142691135 0.0092367430 0.0182710000 200760442 95654128 760807424 0.0107088685 -0.0286385864 0.3460105360 207 8.2400000000 0.0064359005 0.0085027306 0.0142691135 0.0092666763 0.0179860000 200763050 95654128 760807424 0.0106923543 -0.0284011271 0.3468351364 208 8.2799999990 0.0071856976 0.0084963987 0.0142691135 0.0092968234 0.0180350000 200765658 95654128 760807424 0.0107424725 -0.0289454944 0.3461459577 209 8.3200000000 0.0062901080 0.0084858422 0.0142691135 0.0093222685 0.0181150000 200770470 95654128 760807424 0.0107313646 -0.0280068778 0.3461916745 210 8.3599999990 0.0056546358 0.0084723603 0.0142691135 0.0093282590 0.0180770000 200941678 95654128 760807424 0.0106024360 -0.0276839100 0.3477564752 211 8.4000000000 0.0062991241 0.0084620606 0.0142691135 0.0093328875 0.0179940000 200942486 95654128 760807424 0.0105054118 -0.0282618608 0.3500456512 212 8.4399999990 0.0059517934 0.0084502197 0.0142691135 0.0093276906 0.0179790000 200945094 95654128 760807424 0.0105670867 -0.0277218465 0.3491393626 213 8.4800000000 0.0068164980 0.0084425497 0.0142691135 0.0093266278 0.0180070000 200947902 95654128 760807424 0.0107468273 -0.0286858417 0.3469008207 214 8.5200000000 0.0061859326 0.0084320047 0.0142691135 0.0093289076 0.0179390000 200948710 95654128 760807424 0.0106981313 -0.0280076507 0.3474188447 215 8.5600000000 0.0068452233 0.0084246244 0.0142691135 0.0093326313 0.0179570000 200951318 95654128 760807424 0.0105681447 -0.0279507097 0.3493013382 216 8.6000000000 0.0067303013 0.0084167803 0.0142691135 0.0093291130 0.0179500000 200953926 95654128 760807424 0.0107674869 -0.0278812330 0.3479773104 217 8.6400000000 0.0069584385 0.0084100598 0.0142691135 0.0093435031 0.0178920000 200954934 95654128 760807424 0.0106552551 -0.0273915604 0.3488082290 218 8.6800000000 0.0080208154 0.0084082743 0.0142691135 0.0093705253 0.0178690000 200957542 95654128 760807424 0.0105451215 -0.0276296642 0.3495459557 219 8.7200000000 0.0090082306 0.0084110138 0.0142691135 0.0093942611 0.0178400000 200960150 95654128 760807424 0.0104582142 -0.0278087221 0.3501547575 220 8.7600000000 0.0087739713 0.0084126636 0.0142691135 0.0094065179 0.0178600000 200960958 95654128 760807424 0.0101599563 -0.0264110994 0.3503719866 221 8.8000000000 0.0073408242 0.0084078137 0.0142691135 0.0094077209 0.0185190000 200963766 95654128 760807424 0.0100762509 -0.0260795411 0.3476135731 222 8.8400000000 0.0068686670 0.0084008806 0.0142691135 0.0094038252 0.0212420000 200964574 95654128 760807424 0.0098695615 -0.0258316007 0.3452777565 223 8.8800000000 0.0068196771 0.0083937900 0.0142691135 0.0094056810 0.0180590000 200967182 95654128 760807424 0.0094739329 -0.0253863595 0.3431009948 224 8.9200000000 0.0056289216 0.0083814468 0.0142691135 0.0094333492 0.0178340000 200969790 95654128 760807424 0.0090610497 -0.0236232858 0.3435698450 225 8.9600000000 0.0053003752 0.0083677532 0.0142691135 0.0094571670 0.0213850000 200970798 95654128 760807424 0.0086807804 -0.0220107175 0.3440982699 226 9.0000000000 0.0055555757 0.0083553099 0.0142691135 0.0094893252 0.0180530000 200973406 95654128 760807424 0.0083857616 -0.0203417633 0.3448771536 227 9.0400000000 0.0041068378 0.0083365942 0.0142691135 0.0094979073 0.0178490000 200976014 95654128 760807424 0.0080395909 -0.0180236232 0.3429494798 228 9.0800000000 0.0032142357 0.0083141277 0.0142691135 0.0095170663 0.0178130000 200976822 95654128 760807424 0.0078870738 -0.0177314281 0.3409936130 229 9.1200000000 0.0028305328 0.0082901818 0.0142691135 0.0095383427 0.0213870000 200982230 95654128 760807424 0.0073914384 -0.0177029334 0.3388935328 230 9.1600000000 0.0036128194 0.0082698455 0.0142691135 0.0095524850 0.0212300000 201153474 95654128 760807424 0.0070371656 -0.0187966470 0.3384703100 231 9.2000000000 0.0050958795 0.0082561054 0.0142691135 0.0095689380 0.0212500000 201154282 95654128 760807424 0.0066328999 -0.0204900112 0.3362657428 232 9.2400000000 0.0034691745 0.0082354720 0.0142691135 0.0095845355 0.0180580000 201156890 95654128 760807424 0.0060290364 -0.0178712215 0.3352814615 233 9.2800000000 0.0051567312 0.0082222586 0.0142691135 0.0096253645 0.0206460000 201157898 95654128 760807424 0.0056013237 -0.0194018465 0.3357562125 234 9.3200000000 0.0035167395 0.0082021495 0.0142691135 0.0096474847 0.0305540000 201160506 95654128 760807424 0.0049743718 -0.0171339102 0.3335898221 235 9.3600000000 0.0052730166 0.0081896851 0.0142691135 0.0096618552 0.0212390000 201163114 95654128 760807424 0.0042653750 -0.0189262629 0.3323281109 236 9.4000000000 0.0052833073 0.0081773700 0.0142691135 0.0096711863 0.0180120000 201163922 95654128 760807424 0.0036484483 -0.0179407634 0.3331002891 237 9.4400000000 0.0053847781 0.0081655869 0.0142691135 0.0096871200 0.0177010000 201166730 95654128 760807424 0.0028448305 -0.0165424347 0.3335171342 238 9.4800000000 0.0056772130 0.0081551315 0.0142691135 0.0097641955 0.0177610000 201169338 95654128 760807424 0.0011817518 -0.0156177804 0.3307418525 239 9.5200000000 0.0073262881 0.0081516635 0.0142691135 0.0098026907 0.0245800000 201170146 95654128 760807424 0.0003843926 -0.0163196009 0.3305638731 240 9.5600000000 0.0075839707 0.0081492982 0.0142691135 0.0098258887 0.0190700000 201172754 95654128 760807424 -0.0004914924 -0.0160990320 0.3279818296 241 9.6000000000 0.0104089519 0.0081586743 0.0142691135 0.0098951238 0.0178850000 201177490 95654128 760807424 -0.0013714636 -0.0185678937 0.3261808753 242 9.6400000000 0.0111000696 0.0081708288 0.0142691135 0.0099720930 0.0177410000 201346970 95654128 760807424 -0.0021223829 -0.0183923133 0.3259861469 243 9.6800000000 0.0105922297 0.0081807935 0.0142691135 0.0100289058 0.0176390000 201349578 95654128 760807424 -0.0031083229 -0.0171665028 0.3239653409 244 9.7200000000 0.0100585250 0.0081884891 0.0142691135 0.0100730528 0.0176390000 201352186 95654128 760807424 -0.0038545241 -0.0160283055 0.3202859759 245 9.7600000000 0.0088404203 0.0081911500 0.0142691135 0.0101184790 0.0176520000 201353194 95654128 760807424 -0.0045445580 -0.0142800026 0.3191749752 246 9.8000000000 0.0098943524 0.0081980736 0.0142691135 0.0101384499 0.0176790000 201355802 95654128 760807424 -0.0055561103 -0.0143740885 0.3163787425 247 9.8400000000 0.0099781677 0.0082052805 0.0142691135 0.0101864537 0.0176520000 201356610 95654128 760807424 -0.0064561535 -0.0134279095 0.3157659769 248 9.8800000000 0.0087650903 0.0082075378 0.0142691135 0.0102407900 0.0175750000 201359218 95654128 760807424 -0.0070769629 -0.0112131983 0.3147526979 249 9.9200000000 0.0096126450 0.0082131808 0.0142691135 0.0102973785 0.0176030000 201362026 95654128 760807424 -0.0074142041 -0.0112914005 0.3133776784 250 9.9600000000 0.0089015374 0.0082159342 0.0142691135 0.0103466443 0.0176110000 201362834 95654128 760807424 -0.0079825856 -0.0095238797 0.3127358258 251 10.0000000000 0.0101383207 0.0082235931 0.0142691135 0.0103829010 0.0179900000 201365442 95654128 760807424 -0.0085793883 -0.0095017441 0.3094711602 252 10.0400000000 0.0107682543 0.0082336910 0.0142691135 0.0104510500 0.0209220000 201369922 95654128 760807424 -0.0093860095 -0.0090775220 0.3085086346 253 10.0800000000 0.0109348120 0.0082443673 0.0142691135 0.0104825803 0.0178010000 201539594 95654128 760807424 -0.0104937432 -0.0082593616 0.3058281541 254 10.1200000000 0.0117363706 0.0082581154 0.0142691135 0.0105155693 0.0175640000 201542202 95654128 760807424 -0.0111148339 -0.0078216717 0.3033661842 255 10.1600000000 0.0124154184 0.0082744185 0.0142691135 0.0105701004 0.0211540000 201544810 95654128 760807424 -0.0118779968 -0.0075709736 0.3020930290 256 10.2000000000 0.0129297208 0.0082926033 0.0142691135 0.0106143006 0.0178630000 201545618 95654128 760807424 -0.0124110561 -0.0071419016 0.3002976775 257 10.2400000000 0.0138642592 0.0083142829 0.0142691135 0.0106590841 0.0175860000 201570954 95654128 760807424 -0.0129816253 -0.0069780592 0.2986364067 258 10.2800000000 0.0139131276 0.0083359838 0.0142691135 0.0106725800 0.0176090000 201622962 95654128 760807424 -0.0132013829 -0.0059936368 0.2969235182 259 10.3200000000 0.0130252857 0.0083540893 0.0142691135 0.0106746952 0.0175550000 201625570 95654128 760807424 -0.0135721657 -0.0040709702 0.2955766320 260 10.3600000000 0.0131868627 0.0083726768 0.0142691135 0.0106883427 0.0208210000 201628178 95654128 760807424 -0.0145604452 -0.0029343320 0.2929777205 261 10.4000000000 0.0137379207 0.0083932333 0.0142691135 0.0107278843 0.0179330000 201630586 95654128 760807424 -0.0159169231 -0.0031621130 0.2926525772 262 10.4400000000 0.0138754454 0.0084141578 0.0142691135 0.0107371917 0.0175270000 201801858 95654128 760807424 -0.0162909329 -0.0023802337 0.2901748121 263 10.4800000000 0.0136114331 0.0084339193 0.0142691135 0.0107390943 0.0175190000 201804466 95654128 760807424 -0.0170279909 -0.0012492912 0.2892270982 264 10.5200000000 0.0127352988 0.0084502124 0.0142691135 0.0107417189 0.0175330000 201805274 95654128 760807424 -0.0171585158 0.0008641900 0.2874660194 265 10.5600000000 0.0132111311 0.0084681781 0.0142691135 0.0107606649 0.0175480000 201808082 95654128 760807424 -0.0173568614 0.0011126436 0.2848076224 266 10.6000000000 0.0132531207 0.0084861667 0.0142691135 0.0107610680 0.0175340000 201810690 95654128 760807424 -0.0181302670 0.0012693078 0.2841226161 267 10.6400000000 0.0142611116 0.0085077957 0.0142691135 0.0107444491 0.0174950000 201811498 95654128 760807424 -0.0184503030 0.0013270088 0.2815352976 268 10.6800000000 0.0143747376 0.0085296872 0.0143747376 0.0107376486 0.0174880000 201814106 95654128 760807424 -0.0197688919 0.0012498894 0.2806972563 269 10.7200000000 0.0141162276 0.0085504550 0.0143747376 0.0107361049 0.0182550000 201815114 95654128 760807424 -0.0201383997 0.0019829292 0.2795765102 270 10.7600000000 0.0150129842 0.0085743903 0.0150129842 0.0107422383 0.0175430000 201817722 95654128 760807424 -0.0206511691 0.0015094081 0.2775491476 271 10.8000000000 0.0162704941 0.0086027892 0.0162704941 0.0107421632 0.0175520000 201821590 95654128 760807424 -0.0211679153 0.0007034402 0.2762375772 272 10.8400000000 0.0177678950 0.0086364845 0.0177678950 0.0107285323 0.0212710000 201991070 95654128 760807424 -0.0218025539 -0.0000688827 0.2732933164 273 10.8800000000 0.0182535443 0.0086717118 0.0182535443 0.0107332668 0.0177000000 201993878 95654128 760807424 -0.0229919944 -0.0002612326 0.2713634372 274 10.9200000000 0.0188146029 0.0087087297 0.0188146029 0.0107327721 0.0174720000 201996486 95654128 760807424 -0.0237057470 -0.0005205501 0.2691391408 275 10.9600000000 0.0192703810 0.0087471357 0.0192703810 0.0107207150 0.0174390000 201997294 95654128 760807424 -0.0233102757 -0.0006584348 0.2674156725 276 11.0000000000 0.0203435682 0.0087891517 0.0203435682 0.0107071487 0.0174480000 201999902 95654128 760807424 -0.0236691199 -0.0015442544 0.2656866610 277 11.0400000000 0.0206939951 0.0088321295 0.0206939951 0.0106962469 0.0174490000 202002710 95654128 760807424 -0.0251749363 -0.0020269011 0.2638541758 278 11.0800000000 0.0210893527 0.0088762202 0.0210893527 0.0106893542 0.0174310000 202003518 95654128 760807424 -0.0258213188 -0.0022832858 0.2620058060 279 11.1200000000 0.0222844854 0.0089242785 0.0222844854 0.0106739454 0.0206320000 202006126 95654128 760807424 -0.0248097982 -0.0024852287 0.2583768964 280 11.1600000000 0.0226473138 0.0089732894 0.0226473138 0.0106557909 0.0177100000 202009966 95654128 760807424 -0.0246260036 -0.0018507998 0.2562302053 281 11.2000000000 0.0232350472 0.0090240430 0.0232350472 0.0106388814 0.0174250000 202179638 95654128 760807424 -0.0258733034 -0.0023417352 0.2540360987 282 11.2400000000 0.0237035882 0.0090760981 0.0237035882 0.0106214790 0.0174100000 202182246 95654128 760807424 -0.0266064461 -0.0022505161 0.2516464591 283 11.2800000000 0.0232519172 0.0091261893 0.0237035882 0.0106040263 0.0173850000 202183054 95654128 760807424 -0.0282349754 -0.0021474597 0.2512934506 284 11.3200000000 0.0258169807 0.0091849597 0.0258169807 0.0105876947 0.0214880000 202185662 95654128 760807424 -0.0287930798 -0.0045593050 0.2489919811 285 11.3600000000 0.0280728936 0.0092512332 0.0280728936 0.0105703769 0.0177450000 202188470 95654128 760807424 -0.0300739706 -0.0067136693 0.2463182956 286 11.4000000000 0.0293541607 0.0093215231 0.0293541607 0.0105524378 0.0208950000 202189278 95654128 760807424 -0.0317543522 -0.0082070706 0.2439467311 287 11.4400000000 0.0281801131 0.0093872325 0.0293541607 0.0105347297 0.0176310000 202191886 95654128 760807424 -0.0325238705 -0.0069808033 0.2424512655 288 11.4800000000 0.0283010993 0.0094529056 0.0293541607 0.0105173099 0.0173910000 202194494 95654128 760807424 -0.0328317657 -0.0072315196 0.2413912565 289 11.5200000000 0.0293808822 0.0095218606 0.0293808822 0.0105004286 0.0173880000 202195502 95654128 760807424 -0.0336057320 -0.0082585895 0.2397610694 290 11.5600000000 0.0283266958 0.0095867048 0.0293808822 0.0104832046 0.0174720000 202199506 95654128 760807424 -0.0341756977 -0.0070935823 0.2383941561 291 11.6000000000 0.0276799463 0.0096488809 0.0293808822 0.0104692115 0.0173880000 202370798 95654128 760807424 -0.0354391597 -0.0066186627 0.2369840443 292 11.6400000000 0.0282412786 0.0097125535 0.0293808822 0.0104521870 0.0173920000 202371606 95654128 760807424 -0.0359196700 -0.0074779652 0.2358333617 293 11.6800000000 0.0295049474 0.0097801043 0.0295049474 0.0104401722 0.0174740000 202374414 95654128 760807424 -0.0376634896 -0.0096153785 0.2346712649 294 11.7200000000 0.0296206661 0.0098475893 0.0296206661 0.0104232513 0.0174240000 202375222 95654128 760807424 -0.0390922502 -0.0095461262 0.2327104211 295 11.7600000000 0.0290164724 0.0099125685 0.0296206661 0.0104072461 0.0174080000 202377830 95654128 760807424 -0.0412501991 -0.0090410095 0.2314710319 296 11.8000000000 0.0282544307 0.0099745343 0.0296206661 0.0103901634 0.0174170000 202380438 95654128 760807424 -0.0437246710 -0.0086833686 0.2305765599 297 11.8400000000 0.0278588012 0.0100347507 0.0296206661 0.0103727058 0.0174060000 202381446 95654128 760807424 -0.0468319990 -0.0091223707 0.2305939794 298 11.8800000000 0.0281115454 0.0100954110 0.0296206661 0.0103609600 0.0173430000 202384054 95654128 760807424 -0.0486132503 -0.0093496498 0.2285464257 299 11.9200000000 0.0290188584 0.0101587002 0.0296206661 0.0103506859 0.0174760000 202389006 95654128 760807424 -0.0500902720 -0.0097902445 0.2273578048 300 11.9600000000 0.0297557805 0.0102240238 0.0297557805 0.0103367625 0.0174300000 202558382 95654128 760807424 -0.0518709384 -0.0104877744 0.2253665924 301 12.0000000000 0.0307812393 0.0102923202 0.0307812393 0.0103244440 0.0173330000 202561190 95654128 760807424 -0.0539696217 -0.0114497282 0.2245914638 302 12.0400000000 0.0317583606 0.0103633998 0.0317583606 0.0103100808 0.0186420000 202563942 95654128 760807424 -0.0575440899 -0.0128017981 0.2241799086 303 12.0800000000 0.0317122489 0.0104338580 0.0317583606 0.0102980601 0.0187170000 202564950 95654128 760807424 -0.0593913794 -0.0124611855 0.2219736576 304 12.1200000000 0.0319783837 0.0105047282 0.0319783837 0.0102880797 0.0221800000 202567558 95654128 760807424 -0.0614989847 -0.0127465399 0.2203987539 305 12.1600000000 0.0324998386 0.0105768433 0.0324998386 0.0102788036 0.0191750000 202570010 95654128 760807424 -0.0636227280 -0.0127688441 0.2190790474 306 12.2000000000 0.0340381227 0.0106535141 0.0340381227 0.0102640630 0.0186790000 202741258 95654128 760807424 -0.0666406602 -0.0143496618 0.2180445790 307 12.2400000000 0.0339318402 0.0107293393 0.0340381227 0.0102484746 0.0186190000 202744066 95654128 760807424 -0.0683494955 -0.0137804588 0.2164752185 308 12.2800000000 0.0342735164 0.0108057814 0.0342735164 0.0102329393 0.0185840000 202744874 95654128 760807424 -0.0711790100 -0.0148243792 0.2142824233 309 12.3200000000 0.0345765129 0.0108827094 0.0345765129 0.0102237112 0.0220880000 202747682 95654128 760807424 -0.0734888613 -0.0153159667 0.2124874592 310 12.3600000000 0.0341928750 0.0109579034 0.0345765129 0.0102142822 0.0189110000 202748490 95654128 760807424 -0.0751912370 -0.0143427607 0.2116203606 311 12.4000000000 0.0337576605 0.0110312146 0.0345765129 0.0101978567 0.0221920000 202751298 95654128 760807424 -0.0783993453 -0.0141206738 0.2116707712 312 12.4400000000 0.0333977714 0.0111029022 0.0345765129 0.0101814910 0.0188650000 202755894 95654128 760807424 -0.0812771842 -0.0144382613 0.2113647461 313 12.4800000000 0.0342826247 0.0111769589 0.0345765129 0.0101666898 0.0186440000 202925574 95654128 760807424 -0.0835630149 -0.0156292990 0.2101811171 314 12.5200000000 0.0344895050 0.0112512026 0.0345765129 0.0101517434 0.0186610000 202928182 95654128 760807424 -0.0853314251 -0.0156777538 0.2086731941 315 12.5600000000 0.0350912176 0.0113268852 0.0350912176 0.0101369954 0.0186170000 202929190 95654128 760807424 -0.0879247338 -0.0174782313 0.2077879608 316 12.6000000000 0.0361312404 0.0114053800 0.0361312404 0.0101273789 0.0185240000 202931798 95654128 760807424 -0.0888208300 -0.0185229816 0.2067167312 317 12.6400000000 0.0368435681 0.0114856267 0.0368435681 0.0101179115 0.0187250000 202936302 95654128 760807424 -0.0894556791 -0.0194368176 0.2055028528 318 12.6800000000 0.0373380519 0.0115669236 0.0373380519 0.0101214462 0.0222110000 203105786 95654128 760807424 -0.0917097554 -0.0208233241 0.2044683695 319 12.7200000000 0.0365687087 0.0116452991 0.0373380519 0.0101228351 0.0187730000 203108594 95654128 760807424 -0.0941137150 -0.0203087851 0.2022694349 320 12.7600000000 0.0367456563 0.0117237377 0.0373380519 0.0101102099 0.0225410000 203111202 95654128 760807424 -0.0948294923 -0.0198957212 0.2009919137 321 12.8000000000 0.0365668200 0.0118011305 0.0373380519 0.0100949305 0.0228840000 203112210 95654128 760807424 -0.0961651504 -0.0201805774 0.1994019449 322 12.8400000000 0.0376063734 0.0118812710 0.0376063734 0.0100813510 0.0187780000 203114818 95654128 760807424 -0.0963269174 -0.0218344312 0.1989679933 323 12.8800000000 0.0384573936 0.0119635500 0.0384573936 0.0100752476 0.0223000000 203115826 95654128 760807424 -0.0966352522 -0.0221605264 0.1979110837 324 12.9200000000 0.0386939943 0.0120460514 0.0386939943 0.0100647657 0.0187730000 203118434 95654128 760807424 -0.0985536426 -0.0229443405 0.1955452561 325 12.9600000000 0.0389454030 0.0121288186 0.0389454030 0.0100520098 0.0186620000 203122646 95654128 760807424 -0.0993577987 -0.0235460270 0.1943183392 326 13.0000000000 0.0394932255 0.0122127585 0.0394932255 0.0100439102 0.0185670000 203292150 95654128 760807424 -0.1007847637 -0.0249972921 0.1916918159 327 13.0400000000 0.0406745933 0.0122997978 0.0406745933 0.0100367913 0.0185410000 203294958 95654128 760807424 -0.1020984426 -0.0264558718 0.1888682097 328 13.0800000000 0.0411580056 0.0123877801 0.0411580056 0.0100267345 0.0185470000 203295766 95654128 760807424 -0.1025979817 -0.0268062521 0.1869575828 329 13.1200000000 0.0426281244 0.0124796961 0.0426281244 0.0100158193 0.0185220000 203298574 95654128 760807424 -0.1038919315 -0.0292906072 0.1855966747 330 13.1600000000 0.0418943986 0.0125688315 0.0426281244 0.0100075156 0.0226910000 203301182 95654128 760807424 -0.1042034030 -0.0282920729 0.1840857267 331 13.2000000000 0.0420160517 0.0126577959 0.0426281244 0.0099982345 0.0222340000 203302190 95654128 760807424 -0.1047487035 -0.0282751769 0.1823769510 332 13.2400000000 0.0423785448 0.0127473163 0.0426281244 0.0099893107 0.0187650000 203304798 95654128 760807424 -0.1054421738 -0.0289808903 0.1806904376 333 13.2800000000 0.0422038063 0.0128357742 0.0426281244 0.0099848417 0.0185220000 203305806 95654128 760807424 -0.1060197279 -0.0282240473 0.1779842377 334 13.3200000000 0.0423606783 0.0129241721 0.0426281244 0.0099764722 0.0184680000 203308414 95654128 760807424 -0.1062021032 -0.0275337026 0.1756694466 335 13.3600000000 0.0415974967 0.0130097641 0.0426281244 0.0099679502 0.0185630000 203311222 95654128 760807424 -0.1082511097 -0.0288762581 0.1737133563 336 13.4000000000 0.0415951423 0.0130948397 0.0426281244 0.0099933800 0.0185860000 203312030 95654128 760807424 -0.1103101373 -0.0296087693 0.1709389985 337 13.4400000000 0.0432686210 0.0131843761 0.0432686210 0.0099993545 0.0186690000 203316482 95654128 760807424 -0.1112298667 -0.0310255885 0.1676701158 338 13.4800000000 0.0419686735 0.0132695367 0.0432686210 0.0099977152 0.0186500000 203487778 95654128 760807424 -0.1123715714 -0.0295458045 0.1659945101 339 13.5200000000 0.0422834940 0.0133551236 0.0432686210 0.0099960660 0.0185790000 203488786 95654128 760807424 -0.1158531904 -0.0313500315 0.1634026319 340 13.5600000000 0.0422778316 0.0134401904 0.0432686210 0.0099846313 0.0185960000 203491394 95654128 760807424 -0.1188661829 -0.0319295824 0.1599898785 341 13.6000000000 0.0433253422 0.0135278302 0.0433253422 0.0099703882 0.0186190000 203492402 95654128 760807424 -0.1202679351 -0.0330701806 0.1574105471 342 13.6400000000 0.0429653004 0.0136139046 0.0433253422 0.0099565120 0.0185590000 203495010 95654128 760807424 -0.1231140718 -0.0339673422 0.1550199240 343 13.6800000000 0.0418773480 0.0136963053 0.0433253422 0.0099430572 0.0185820000 203497818 95654128 760807424 -0.1245322302 -0.0335204788 0.1524654925 344 13.7200000000 0.0425469019 0.0137801734 0.0433253422 0.0099332345 0.0185280000 203498626 95654128 760807424 -0.1256282777 -0.0344723500 0.1504462212 345 13.7600000000 0.0422126614 0.0138625864 0.0433253422 0.0099269026 0.0185810000 203501434 95654128 760807424 -0.1266279370 -0.0336410403 0.1469654590 346 13.8000000000 0.0416224338 0.0139428171 0.0433253422 0.0099136629 0.0185590000 203502242 95654128 760807424 -0.1274647564 -0.0327150561 0.1439622194 347 13.8400000000 0.0435216725 0.0140280588 0.0435216725 0.0099003157 0.0185850000 203505050 95654128 760807424 -0.1289852709 -0.0353719778 0.1401519328 348 13.8800000000 0.0437707789 0.0141135264 0.0437707789 0.0098863788 0.0186090000 203507658 95654128 760807424 -0.1288856417 -0.0355578549 0.1384554952 349 13.9200000000 0.0422935113 0.0141942713 0.0437707789 0.0098768950 0.0221620000 203508666 95654128 760807424 -0.1309811175 -0.0347131863 0.1344832629 350 13.9600000000 0.0419692919 0.0142736285 0.0437707789 0.0098694007 0.0188080000 203511274 95654128 760807424 -0.1316529065 -0.0343378894 0.1298433840 351 14.0000000000 0.0404062830 0.0143480805 0.0437707789 0.0098619691 0.0185830000 203512282 95654128 760807424 -0.1325032562 -0.0327648148 0.1259380728 352 14.0400000000 0.0392966345 0.0144189571 0.0437707789 0.0098555411 0.0185460000 203514890 95654128 760807424 -0.1340904683 -0.0324022546 0.1233572438 353 14.0800000000 0.0382753909 0.0144865391 0.0437707789 0.0098475526 0.0251590000 203517698 95654128 760807424 -0.1352435946 -0.0318614990 0.1211360022 354 14.1200000000 0.0388013572 0.0145552250 0.0437707789 0.0098354937 0.0190490000 203518506 95654128 760807424 -0.1360390484 -0.0321527831 0.1184149757 355 14.1600000000 0.0395736508 0.0146256994 0.0437707789 0.0098223548 0.0193740000 203521314 95654128 760807424 -0.1371302307 -0.0335089043 0.1162482351 356 14.2000000000 0.0382667035 0.0146921068 0.0437707789 0.0098089281 0.0186670000 203523922 95654128 760807424 -0.1382286698 -0.0320918523 0.1126943007 357 14.2400000000 0.0388880447 0.0147598825 0.0437707789 0.0097962083 0.0185510000 203524930 95654128 760807424 -0.1402317137 -0.0333733708 0.1103034019 358 14.2800000000 0.0402433313 0.0148310653 0.0437707789 0.0097861884 0.0185940000 203527538 95654128 760807424 -0.1411016732 -0.0344269052 0.1068552285 359 14.3200000000 0.0391507521 0.0148988082 0.0437707789 0.0097775180 0.0185980000 203528546 95654128 760807424 -0.1421214044 -0.0341976583 0.1035992429 360 14.3600000000 0.0391272046 0.0149661093 0.0437707789 0.0097656747 0.0186740000 203532650 95654128 760807424 -0.1426116377 -0.0351027846 0.1004786491 361 14.4000000000 0.0402198955 0.0150360644 0.0437707789 0.0097619486 0.0186020000 203704166 95654128 760807424 -0.1424082667 -0.0360988081 0.0981732532 362 14.4400000000 0.0401468463 0.0151054312 0.0437707789 0.0097513874 0.0186020000 203704974 95654128 760807424 -0.1413981915 -0.0352870449 0.0957537442 363 14.4800000000 0.0415957235 0.0151784072 0.0437707789 0.0097385318 0.0186670000 203707782 95654128 760807424 -0.1409751624 -0.0372614078 0.0938107371 364 14.5200000000 0.0422803089 0.0152528629 0.0437707789 0.0097311382 0.0222640000 203708590 95654128 760807424 -0.1402606964 -0.0377861857 0.0909336805 365 14.5600000000 0.0422926582 0.0153269446 0.0437707789 0.0097211639 0.0188330000 203711398 95654128 760807424 -0.1408335716 -0.0371291041 0.0882734507 366 14.6000000000 0.0418165438 0.0153993205 0.0437707789 0.0097112297 0.0186490000 203714006 95654128 760807424 -0.1422781795 -0.0370763429 0.0860081166 367 14.6400000000 0.0413375460 0.0154699969 0.0437707789 0.0097022457 0.0186780000 203715014 95654128 760807424 -0.1436870247 -0.0385804288 0.0836455673 368 14.6800000000 0.0425264351 0.0155435198 0.0437707789 0.0096925923 0.0186830000 203717622 95654128 760807424 -0.1424541324 -0.0398284122 0.0816143826 369 14.7200000000 0.0425743163 0.0156167740 0.0437707789 0.0096832766 0.0187110000 203718630 95654128 760807424 -0.1426493973 -0.0397605188 0.0794173703 370 14.7600000000 0.0433702059 0.0156917833 0.0437707789 0.0096710709 0.0187880000 203722962 95654128 760807424 -0.1427608132 -0.0401673988 0.0772008970 371 14.8000000000 0.0436521918 0.0157671483 0.0437707789 0.0096583528 0.0187290000 203894446 95654128 760807424 -0.1433437616 -0.0399305820 0.0747203529 372 14.8400000000 0.0432027504 0.0158408999 0.0437707789 0.0096508344 0.0194410000 203895254 95654128 760807424 -0.1445828974 -0.0398657806 0.0714378059 373 14.8800000000 0.0433432795 0.0159146328 0.0437707789 0.0096437886 0.0187870000 203898062 95654128 760807424 -0.1463411599 -0.0402168110 0.0681551397 374 14.9200000000 0.0430634655 0.0159872233 0.0437707789 0.0096471347 0.0187150000 203900670 95654128 760807424 -0.1487027705 -0.0401046649 0.0652020350 375 14.9600000000 0.0415357947 0.0160553528 0.0437707789 0.0096603203 0.0228150000 203901678 95654128 760807424 -0.1513443887 -0.0405572169 0.0634313896 376 15.0000000000 0.0401743278 0.0161194990 0.0437707789 0.0096495491 0.0189760000 203904286 95654128 760807424 -0.1528346390 -0.0399255455 0.0609361343 377 15.0400000000 0.0399152040 0.0161826176 0.0437707789 0.0096372811 0.0187310000 203905294 95654128 760807424 -0.1531966180 -0.0384052731 0.0588700697 378 15.0800000000 0.0399667099 0.0162455385 0.0437707789 0.0096489395 0.0187630000 203909306 95654128 760807424 -0.1535423100 -0.0391907506 0.0567730330 379 15.1200000000 0.0392409116 0.0163062123 0.0437707789 0.0096441993 0.0186960000 204080838 95654128 760807424 -0.1532199532 -0.0390395410 0.0545064099 380 15.1600000000 0.0381079465 0.0163635853 0.0437707789 0.0096319672 0.0187340000 204081646 95654128 760807424 -0.1543969363 -0.0377042107 0.0514886044 381 15.2000000000 0.0378963649 0.0164201017 0.0437707789 0.0096204657 0.0187430000 204084454 95654128 760807424 -0.1552753150 -0.0374836363 0.0494592525 382 15.2400000000 0.0367627405 0.0164733547 0.0437707789 0.0096088010 0.0187620000 204085262 95654128 760807424 -0.1555015147 -0.0364663452 0.0466181487 383 15.2800000000 0.0363936871 0.0165253660 0.0437707789 0.0095969310 0.0186740000 204088070 95654128 760807424 -0.1583289951 -0.0366358496 0.0437933095 384 15.3200000000 0.0361967683 0.0165765936 0.0437707789 0.0095851915 0.0226340000 204090678 95654128 760807424 -0.1596553475 -0.0362903811 0.0414508916 385 15.3600000000 0.0357147194 0.0166263031 0.0437707789 0.0095750833 0.0189240000 204091686 95654128 760807424 -0.1622683406 -0.0359569006 0.0391402394 386 15.4000000000 0.0347849540 0.0166733462 0.0437707789 0.0095638443 0.0228970000 204094294 95654128 760807424 -0.1643424928 -0.0352460109 0.0360050313 387 15.4400000000 0.0350966789 0.0167209517 0.0437707789 0.0095524636 0.0225070000 204095302 95654128 760807424 -0.1644076705 -0.0349015146 0.0339061841 388 15.4800000000 0.0356068388 0.0167696267 0.0437707789 0.0095455386 0.0188750000 204097910 95654128 760807424 -0.1668128222 -0.0351229794 0.0319966190 389 15.5200000000 0.0339657702 0.0168138327 0.0437707789 0.0095399890 0.0187620000 204100718 95654128 760807424 -0.1689678878 -0.0333338641 0.0292190406 390 15.5600000000 0.0337442458 0.0168572440 0.0437707789 0.0095332720 0.0188270000 204102818 95654128 760807424 -0.1716531217 -0.0331044756 0.0268230923 391 15.6000000000 0.0342080481 0.0169016195 0.0437707789 0.0095244945 0.0187390000 204274354 95654128 760807424 -0.1724466234 -0.0323106647 0.0244593266 392 15.6400000000 0.0340897962 0.0169454669 0.0437707789 0.0095252741 0.0186760000 204276962 95654128 760807424 -0.1761199832 -0.0320881046 0.0215067752 393 15.6800000000 0.0332417935 0.0169869333 0.0437707789 0.0095233939 0.0187150000 204277970 95654128 760807424 -0.1762896776 -0.0306578968 0.0191362035 394 15.7200000000 0.0330926813 0.0170278109 0.0437707789 0.0095183126 0.0187040000 204280578 95654128 760807424 -0.1770677269 -0.0299543031 0.0171866231 395 15.7600000000 0.0338401981 0.0170703739 0.0437707789 0.0095140090 0.0186820000 204281586 95654128 760807424 -0.1772408485 -0.0296019278 0.0153121278 396 15.8000000000 0.0337519199 0.0171124990 0.0437707789 0.0095107410 0.0227150000 204284194 95654128 760807424 -0.1760257632 -0.0279549304 0.0130275749 397 15.8400000000 0.0343210138 0.0171558454 0.0437707789 0.0095159215 0.0190550000 204287002 95654128 760807424 -0.1759237051 -0.0273651592 0.0112194428 398 15.8800000000 0.0339566246 0.0171980584 0.0437707789 0.0095263743 0.0187860000 204287810 95654128 760807424 -0.1763478220 -0.0271798242 0.0092630638 399 15.9200000000 0.0324745066 0.0172363452 0.0437707789 0.0095180203 0.0187700000 204290618 95654128 760807424 -0.1790606827 -0.0261744130 0.0064300713 400 15.9600000000 0.0318938345 0.0172729890 0.0437707789 0.0095070454 0.0188180000 204291426 95654128 760807424 -0.1800008565 -0.0240767840 0.0038977524 401 16.0000000000 0.0317545347 0.0173091025 0.0437707789 0.0095115709 0.0188040000 204294234 95654128 760807424 -0.1803112626 -0.0235664789 0.0020373284 402 16.0400000000 0.0317071304 0.0173449185 0.0437707789 0.0095084701 0.0189080000 204296842 95654128 760807424 -0.1803873479 -0.0226670559 0.0003576354 403 16.0800000000 0.0320008099 0.0173812855 0.0437707789 0.0095111472 0.0188860000 204297850 95654128 760807424 -0.1798334271 -0.0214118846 -0.0013333566 404 16.1200000000 0.0313431546 0.0174158446 0.0437707789 0.0095264668 0.0188520000 204300458 95654128 760807424 -0.1785784513 -0.0191162489 -0.0033144357 405 16.1600000000 0.0307832006 0.0174488504 0.0437707789 0.0095477312 0.0188830000 204301466 95654128 760807424 -0.1806888580 -0.0194967706 -0.0050619394 406 16.2000000000 0.0298936032 0.0174795025 0.0437707789 0.0095429208 0.0198510000 204304074 95654128 760807424 -0.1830009073 -0.0180411171 -0.0074574663 407 16.2400000000 0.0290510301 0.0175079338 0.0437707789 0.0095544067 0.0260420000 204306882 95654128 760807424 -0.1839368194 -0.0168583728 -0.0092725968 408 16.2800000000 0.0277532209 0.0175330448 0.0437707789 0.0095574484 0.0194050000 204307690 95654128 760807424 -0.1840707064 -0.0150919482 -0.0105335936 409 16.3200000000 0.0260011312 0.0175537491 0.0437707789 0.0095500479 0.0189630000 204310498 95654128 760807424 -0.1867131740 -0.0141999554 -0.0128096119 410 16.3600000000 0.0255373064 0.0175732212 0.0437707789 0.0095401594 0.0189020000 204313106 95654128 760807424 -0.1876972467 -0.0127439220 -0.0152113335 411 16.3999999990 0.0243611448 0.0175897369 0.0437707789 0.0095447516 0.0189420000 204314114 95654128 760807424 -0.1891149580 -0.0114147700 -0.0174249634 412 16.4400000000 0.0246945005 0.0176069814 0.0437707789 0.0095532774 0.0189200000 204316722 95654128 760807424 -0.1881882995 -0.0104542850 -0.0188420974 413 16.4800000000 0.0259325057 0.0176271401 0.0437707789 0.0095548210 0.0188530000 204317730 95654128 760807424 -0.1851281822 -0.0092139151 -0.0193831585 414 16.5200000000 0.0263517462 0.0176482140 0.0437707789 0.0095481515 0.0189270000 204321662 95654128 760807424 -0.1831505001 -0.0074940464 -0.0202711485 415 16.5599999990 0.0273680128 0.0176716352 0.0437707789 0.0095379127 0.0189190000 204493190 95654128 760807424 -0.1822669655 -0.0068578627 -0.0221176129 416 16.6000000000 0.0278295055 0.0176960532 0.0437707789 0.0095310933 0.0189320000 204493998 95654128 760807424 -0.1816992462 -0.0063326447 -0.0236819405 417 16.6400000000 0.0274845138 0.0177195267 0.0437707789 0.0095255378 0.0223780000 204496806 95654128 760807424 -0.1827912331 -0.0056160600 -0.0256733634 418 16.6800000000 0.0269919615 0.0177417096 0.0437707789 0.0095245674 0.0190970000 204497614 95654128 760807424 -0.1845279634 -0.0047741099 -0.0280285701 419 16.7199999990 0.0258859899 0.0177611470 0.0437707789 0.0095340774 0.0189460000 204500422 95654128 760807424 -0.1853955090 -0.0022725638 -0.0307869874 420 16.7600000000 0.0261816885 0.0177811959 0.0437707789 0.0095567960 0.0189310000 204503030 95654128 760807424 -0.1848875880 -0.0021758419 -0.0330189057 421 16.8000000000 0.0273227729 0.0178038600 0.0437707789 0.0095549305 0.0188970000 204504038 95654128 760807424 -0.1840698868 -0.0017327874 -0.0351239815 422 16.8400000000 0.0284876227 0.0178291769 0.0437707789 0.0095523157 0.0194720000 204506646 95654128 760807424 -0.1823259294 -0.0011544775 -0.0370422937 423 16.8799999990 0.0293291416 0.0178563636 0.0437707789 0.0095480170 0.0192320000 204507654 95654128 760807424 -0.1819436103 -0.0001932157 -0.0391771272 424 16.9200000000 0.0297315419 0.0178843711 0.0437707789 0.0095441418 0.0224730000 204510262 95654128 760807424 -0.1821164042 0.0002827626 -0.0417495072 425 16.9600000000 0.0281339642 0.0179084878 0.0437707789 0.0095601592 0.0191080000 204513070 95654128 760807424 -0.1830503941 0.0015892056 -0.0449430346 426 17.0000000000 0.0275797173 0.0179311902 0.0437707789 0.0095584552 0.0189310000 204513878 95654128 760807424 -0.1832308024 0.0020788971 -0.0480192788 427 17.0400000000 0.0268584453 0.0179520971 0.0437707789 0.0095490213 0.0222690000 204516686 95654128 760807424 -0.1841697395 0.0016656829 -0.0504823551 428 17.0800000000 0.0261598304 0.0179712741 0.0437707789 0.0095380744 0.0235120000 204519294 95654128 760807424 -0.1832706928 0.0025269287 -0.0539687388 429 17.1200000000 0.0260298755 0.0179900587 0.0437707789 0.0095289849 0.0191410000 204520302 95654128 760807424 -0.1831682324 0.0023839783 -0.0564129129 430 17.1600000000 0.0266750362 0.0180102563 0.0437707789 0.0095181980 0.0189410000 204522910 95654128 760807424 -0.1831705868 0.0021228527 -0.0594514906 431 17.2000000000 0.0264811013 0.0180299103 0.0437707789 0.0095072396 0.0189830000 204523918 95654128 760807424 -0.1829952896 0.0029463959 -0.0630707890 432 17.2400000000 0.0263953656 0.0180492747 0.0437707789 0.0095028134 0.0189740000 204526526 95654128 760807424 -0.1827694774 0.0037776439 -0.0652864650 433 17.2800000000 0.0262491070 0.0180682120 0.0437707789 0.0095024799 0.0189000000 204529334 95654128 760807424 -0.1831858158 0.0041570333 -0.0675113201 434 17.3200000000 0.0240661670 0.0180820322 0.0437707789 0.0094948133 0.0189440000 204530142 95654128 760807424 -0.1847471148 0.0057090726 -0.0703744292 435 17.3600000000 0.0235017929 0.0180944914 0.0437707789 0.0094850047 0.0189280000 204532950 95654128 760807424 -0.1845969856 0.0087296925 -0.0734465718 436 17.4000000000 0.0229788274 0.0181056940 0.0437707789 0.0094943388 0.0189060000 204533758 95654128 760807424 -0.1842185259 0.0095940800 -0.0762489960 437 17.4400000000 0.0224481151 0.0181156309 0.0437707789 0.0095087495 0.0189590000 204536566 95654128 760807424 -0.1836235672 0.0107424939 -0.0791684613 438 17.4800000000 0.0219872221 0.0181244701 0.0437707789 0.0095064561 0.0189640000 204539174 95654128 760807424 -0.1827468723 0.0117775314 -0.0818525106 439 17.5200000000 0.0211538617 0.0181313708 0.0437707789 0.0095041593 0.0230230000 204540182 95654128 760807424 -0.1810196489 0.0131169520 -0.0848584622 440 17.5600000000 0.0203674622 0.0181364528 0.0437707789 0.0095067503 0.0191870000 204542790 95654128 760807424 -0.1808000654 0.0144781470 -0.0874183327 441 17.6000000000 0.0200320166 0.0181407512 0.0437707789 0.0095093017 0.0189640000 204543798 95654128 760807424 -0.1799807549 0.0166697018 -0.0895743221 442 17.6400000000 0.0183216576 0.0181411605 0.0437707789 0.0095208206 0.0189780000 204546406 95654128 760807424 -0.1814437509 0.0164815411 -0.0928202793 443 17.6800000000 0.0176890697 0.0181401399 0.0437707789 0.0095223033 0.0189350000 204549214 95654128 760807424 -0.1816874295 0.0175446644 -0.0942803994 444 17.7200000000 0.0174562857 0.0181385997 0.0437707789 0.0095155845 0.0222660000 204550022 95654128 760807424 -0.1820245981 0.0174488351 -0.0962680876 445 17.7600000000 0.0170907937 0.0181362451 0.0437707789 0.0095053006 0.0191980000 204555178 95654128 760807424 -0.1820966899 0.0188837219 -0.0995896012 446 17.8000000000 0.0171675459 0.0181340731 0.0437707789 0.0094949577 0.0189740000 204726518 95654128 760807424 -0.1823991686 0.0184356328 -0.1017476618 447 17.8400000000 0.0175745785 0.0181328215 0.0437707789 0.0094884536 0.0189140000 204727526 95654128 760807424 -0.1820072681 0.0188915525 -0.1043461561 448 17.8800000000 0.0175357945 0.0181314888 0.0437707789 0.0094794502 0.0285720000 204730134 95654128 760807424 -0.1816352010 0.0194100924 -0.1066005975 449 17.9200000000 0.0165829491 0.0181280399 0.0437707789 0.0094718768 0.0291940000 204731142 95654128 760807424 -0.1819754243 0.0192661975 -0.1087055057 450 17.9600000000 0.0164731890 0.0181243625 0.0437707789 0.0094615838 0.0199980000 204733750 95654128 760807424 -0.1827335656 0.0200792477 -0.1133204550 451 18.0000000000 0.0159922913 0.0181196351 0.0437707789 0.0094673778 0.0189330000 204736558 95654128 760807424 -0.1833924949 0.0206727311 -0.1150775179 452 18.0400000000 0.0156525746 0.0181141770 0.0437707789 0.0094713807 0.0224450000 204737366 95654128 760807424 -0.1843007058 0.0206474606 -0.1166415066 453 18.0800000000 0.0149316425 0.0181071515 0.0437707789 0.0094747907 0.0197880000 204740174 95654128 760807424 -0.1853856742 0.0205714963 -0.1187283322 454 18.1200000000 0.0146660283 0.0180995719 0.0437707789 0.0094705142 0.0226780000 204740982 95654128 760807424 -0.1861256361 0.0208816621 -0.1216673031 455 18.1600000000 0.0146697313 0.0180920338 0.0437707789 0.0094606488 0.0191670000 204743790 95654128 760807424 -0.1866391897 0.0226117857 -0.1246353686 456 18.2000000000 0.0149456467 0.0180851339 0.0437707789 0.0094511532 0.0226810000 204746398 95654128 760807424 -0.1870514452 0.0238894690 -0.1269934773 457 18.2400000000 0.0150958290 0.0180785927 0.0437707789 0.0094513323 0.0190810000 204747406 95654128 760807424 -0.1875753254 0.0248836521 -0.1291808486 458 18.2800000000 0.0158420559 0.0180737094 0.0437707789 0.0094498907 0.0189500000 204750014 95654128 760807424 -0.1881854534 0.0255884565 -0.1310050935 459 18.3200000000 0.0165388919 0.0180703656 0.0437707789 0.0094651295 0.0218180000 204751022 95654128 760807424 -0.1887076199 0.0264544450 -0.1331905872 460 18.3600000000 0.0171293672 0.0180683200 0.0437707789 0.0094711453 0.0190230000 204753630 95654128 760807424 -0.1885048151 0.0266744904 -0.1357140690 461 18.4000000000 0.0183489565 0.0180689287 0.0437707789 0.0094702076 0.0189260000 204756438 95654128 760807424 -0.1881993711 0.0261007734 -0.1378938705 462 18.4400000000 0.0184849873 0.0180698293 0.0437707789 0.0094882220 0.0191020000 204757246 95654128 760807424 -0.1887348443 0.0265617538 -0.1400547624 463 18.4800000000 0.0177230015 0.0180690802 0.0437707789 0.0094945787 0.0189510000 204760054 95654128 760807424 -0.1905210018 0.0269359257 -0.1427744329 464 18.5200000000 0.0181262232 0.0180692033 0.0437707789 0.0094958190 0.0189970000 204762662 95654128 760807424 -0.1907891184 0.0260308031 -0.1453464776 465 18.5600000000 0.0187567025 0.0180706818 0.0437707789 0.0094947733 0.0189900000 204763670 95654128 760807424 -0.1911150217 0.0260823332 -0.1478100866 466 18.6000000000 0.0183038618 0.0180711822 0.0437707789 0.0094855688 0.0190130000 204766278 95654128 760807424 -0.1929196417 0.0275308490 -0.1514010578 467 18.6400000000 0.0169268027 0.0180687317 0.0437707789 0.0094756977 0.0189640000 204767286 95654128 760807424 -0.1956762224 0.0278230235 -0.1548853666 468 18.6800000000 0.0162596237 0.0180648661 0.0437707789 0.0094669800 0.0190600000 204769894 95654128 760807424 -0.1981148124 0.0291729141 -0.1577820629 469 18.7200000000 0.0162336919 0.0180609617 0.0437707789 0.0094684589 0.0189710000 204772702 95654128 760807424 -0.2003569007 0.0298066624 -0.1596593261 470 18.7600000000 0.0160818063 0.0180567507 0.0437707789 0.0094585917 0.0265150000 204773510 95654128 760807424 -0.2025464922 0.0335002951 -0.1630635113 471 18.8000000000 0.0164881721 0.0180534204 0.0437707789 0.0094909334 0.0194520000 204776318 95654128 760807424 -0.2029407769 0.0336830728 -0.1653726697 472 18.8400000000 0.0166767221 0.0180505037 0.0437707789 0.0095780395 0.0190570000 204777126 95654128 760807424 -0.2042634934 0.0352634080 -0.1680265367 473 18.8800000000 0.0159786996 0.0180461235 0.0437707789 0.0096412383 0.0192170000 204782042 95654128 760807424 -0.2064284533 0.0352901965 -0.1713227630 474 18.9200000000 0.0165356062 0.0180429368 0.0437707789 0.0096431443 0.0190210000 204953386 95654128 760807424 -0.2082806379 0.0353049859 -0.1733329147 475 18.9600000000 0.0165093150 0.0180397081 0.0437707789 0.0096383668 0.0190160000 204954394 95654128 760807424 -0.2097132802 0.0367703922 -0.1761445403 476 19.0000000000 0.0172008462 0.0180379458 0.0437707789 0.0096520764 0.0190680000 204957002 95654128 760807424 -0.2103130966 0.0393548459 -0.1787307262 477 19.0400000000 0.0186084695 0.0180391419 0.0437707789 0.0096504807 0.0190720000 204958010 95654128 760807424 -0.2097226232 0.0419417247 -0.1810031980 478 19.0800000000 0.0181920901 0.0180394618 0.0437707789 0.0096411708 0.0191150000 204960618 95654128 760807424 -0.2112129480 0.0448915884 -0.1841376275 479 19.1200000000 0.0199192911 0.0180433863 0.0437707789 0.0096418257 0.0190320000 204963426 95654128 760807424 -0.2102890313 0.0455809385 -0.1858945638 480 19.1600000000 0.0198431108 0.0180471358 0.0437707789 0.0096419233 0.0189790000 204964234 95654128 760807424 -0.2120108306 0.0469453558 -0.1882269382 481 19.2000000000 0.0203537717 0.0180519313 0.0437707789 0.0096399265 0.0230370000 204967042 95654128 760807424 -0.2122387439 0.0471294858 -0.1902767420 482 19.2400000000 0.0207452588 0.0180575191 0.0437707789 0.0096389618 0.0192380000 204969650 95654128 760807424 -0.2126275450 0.0474566855 -0.1926331520 483 19.2800000000 0.0202234332 0.0180620034 0.0437707789 0.0096554376 0.0190430000 204970658 95654128 760807424 -0.2146327496 0.0478554368 -0.1949088275 484 19.3200000000 0.0211053453 0.0180682913 0.0437707789 0.0096551053 0.0189910000 204973266 95654128 760807424 -0.2140904814 0.0476794504 -0.1963282079 485 19.3600000000 0.0212671626 0.0180748869 0.0437707789 0.0096466405 0.0190260000 204974274 95654128 760807424 -0.2143524438 0.0480514169 -0.1979823261 486 19.4000000000 0.0216867793 0.0180823188 0.0437707789 0.0096385258 0.0190920000 204976882 95654128 760807424 -0.2141329497 0.0482791327 -0.1996503323 487 19.4400000000 0.0214142501 0.0180891605 0.0437707789 0.0096318744 0.0190700000 204979690 95654128 760807424 -0.2149377018 0.0490422100 -0.2017758340 488 19.4800000000 0.0217743795 0.0180967122 0.0437707789 0.0096265421 0.0190280000 204980498 95654128 760807424 -0.2149639875 0.0508002713 -0.2039574683 489 19.5200000000 0.0224471260 0.0181056087 0.0437707789 0.0096299642 0.0227600000 204983306 95654128 760807424 -0.2145857811 0.0511601828 -0.2056417912 490 19.5600000000 0.0232639462 0.0181161360 0.0437707789 0.0096238781 0.0192380000 204984114 95654128 760807424 -0.2140134126 0.0529174134 -0.2074973136 491 19.6000000000 0.0229975283 0.0181260777 0.0437707789 0.0096156264 0.0190980000 204986922 95654128 760807424 -0.2153010666 0.0530845933 -0.2095103711 492 19.6400000000 0.0228009224 0.0181355794 0.0437707789 0.0096071380 0.0262390000 204989530 95654128 760807424 -0.2151697278 0.0539169051 -0.2114865929 493 19.6800000000 0.0222702045 0.0181439661 0.0437707789 0.0096009910 0.0196220000 204990538 95654128 760807424 -0.2167421132 0.0545281433 -0.2134357989 494 19.7200000000 0.0220944248 0.0181519629 0.0437707789 0.0095923699 0.0192380000 204995582 95654128 760807424 -0.2171210498 0.0562028661 -0.2153611928 495 19.7600000000 0.0222287402 0.0181601989 0.0437707789 0.0095955360 0.0191210000 205165278 95654128 760807424 -0.2183258981 0.0553363264 -0.2171253711 496 19.8000000000 0.0216124058 0.0181671590 0.0437707789 0.0095939968 0.0227530000 205167886 95654128 760807424 -0.2210644782 0.0556975603 -0.2197100818 497 19.8400000000 0.0221419036 0.0181751564 0.0437707789 0.0095903073 0.0192740000 205170694 95654128 760807424 -0.2212389857 0.0558780022 -0.2213478982 498 19.8800000000 0.0216729119 0.0181821800 0.0437707789 0.0095836243 0.0190450000 205171502 95654128 760807424 -0.2216884494 0.0551071241 -0.2230123281 499 19.9200000000 0.0210399535 0.0181879070 0.0437707789 0.0095742038 0.0190470000 205174310 95654128 760807424 -0.2230302542 0.0557814911 -0.2255819738 500 19.9600000000 0.0231258739 0.0181977830 0.0437707789 0.0095666253 0.0190530000 205176918 95654128 760807424 -0.2194153666 0.0573155135 -0.2268331051 501 20.0000000000 0.0227973145 0.0182069637 0.0437707789 0.0095782704 0.0190550000 205177926 95654128 760807424 -0.2217209190 0.0559101142 -0.2295477092 502 20.0400000000 0.0225692522 0.0182156535 0.0437707789 0.0095925636 0.0227640000 205180534 95654128 760807424 -0.2247387767 0.0558020547 -0.2325398922 503 20.0800000000 0.0224590022 0.0182240896 0.0437707789 0.0095842549 0.0197290000 205181542 95654128 760807424 -0.2250714749 0.0570410006 -0.2353391498 504 20.1200000000 0.0220819917 0.0182317441 0.0437707789 0.0095747457 0.0191600000 205184150 95654128 760807424 -0.2262566835 0.0578929782 -0.2380533516 505 20.1600000000 0.0224184170 0.0182400346 0.0437707789 0.0095669096 0.0191280000 205186958 95654128 760807424 -0.2247031033 0.0588484481 -0.2403152883 506 20.2000000000 0.0226555485 0.0182487609 0.0437707789 0.0095580254 0.0191420000 205187766 95654128 760807424 -0.2257915586 0.0600481331 -0.2424820215 507 20.2400000000 0.0229360517 0.0182580060 0.0437707789 0.0095527864 0.0191260000 205190574 95654128 760807424 -0.2267751992 0.0592819974 -0.2449529469 508 20.2800000000 0.0228639394 0.0182670728 0.0437707789 0.0095454663 0.0191350000 205191382 95654128 760807424 -0.2271083295 0.0594556630 -0.2479183078 509 20.3200000000 0.0235033520 0.0182773602 0.0437707789 0.0095426932 0.0191730000 205196594 95654128 760807424 -0.2265635580 0.0593561791 -0.2495258451 510 20.3600000000 0.0234321915 0.0182874677 0.0437707789 0.0095432508 0.0191290000 205367910 95654128 760807424 -0.2271955758 0.0603823103 -0.2519595325 511 20.4000000000 0.0235372018 0.0182977412 0.0437707789 0.0095355392 0.0190790000 205368918 95654128 760807424 -0.2280019969 0.0611210465 -0.2546543479 512 20.4400000000 0.0236109495 0.0183081186 0.0437707789 0.0095264856 0.0190720000 205371526 95654128 760807424 -0.2292312831 0.0618676357 -0.2576656938 513 20.4800000000 0.0236796122 0.0183185893 0.0437707789 0.0095190527 0.0191340000 205417590 95654128 760807424 -0.2259525508 0.0630976781 -0.2601938546 514 20.5200000000 0.0241904203 0.0183300131 0.0437707789 0.0095132544 0.0190820000 205522598 95654128 760807424 -0.2262014747 0.0633648336 -0.2630190253 515 20.5600000000 0.0246570669 0.0183422986 0.0437707789 0.0095070507 0.0228710000 205525406 95654128 760807424 -0.2245489061 0.0628986657 -0.2652573287 516 20.6000000000 0.0241764802 0.0183536052 0.0437707789 0.0095038431 0.0192320000 205526214 95654128 760807424 -0.2240295708 0.0619143024 -0.2686041594 517 20.6400000000 0.0242354963 0.0183649822 0.0437707789 0.0094966257 0.0190220000 205529022 95654128 760807424 -0.2217028141 0.0619389266 -0.2706931233 518 20.6800000000 0.0239671580 0.0183757972 0.0437707789 0.0094915307 0.0223120000 205531630 95654128 760807424 -0.2203362286 0.0622029714 -0.2733151913 519 20.7200000000 0.0236271024 0.0183859153 0.0437707789 0.0094868758 0.0191920000 205532638 95654128 760807424 -0.2198834419 0.0622999296 -0.2762931287 520 20.7600000000 0.0242007785 0.0183970977 0.0437707789 0.0094818959 0.0195510000 205535246 95654128 760807424 -0.2190354168 0.0622980408 -0.2782231271 521 20.8000000000 0.0245665442 0.0184089393 0.0437707789 0.0094735454 0.0191140000 205536254 95654128 760807424 -0.2182559073 0.0633551553 -0.2799697220 522 20.8400000000 0.0251045693 0.0184217661 0.0437707789 0.0094650864 0.0190970000 205538862 95654128 760807424 -0.2187548429 0.0653806627 -0.2820257545 523 20.8800000000 0.0261159874 0.0184364778 0.0437707789 0.0094563718 0.0190530000 205541670 95654128 760807424 -0.2186139226 0.0663459077 -0.2836039364 524 20.9200000000 0.0262826476 0.0184514515 0.0437707789 0.0094481770 0.0261730000 205542478 95654128 760807424 -0.2191637456 0.0660522059 -0.2859767973 525 20.9600000000 0.0262576714 0.0184663204 0.0437707789 0.0094418661 0.0196310000 205545286 95654128 760807424 -0.2195521593 0.0659381822 -0.2885572910 526 21.0000000000 0.0266913213 0.0184819573 0.0437707789 0.0094371432 0.0191090000 205546094 95654128 760807424 -0.2200943530 0.0666836351 -0.2908563912 527 21.0400000000 0.0272166543 0.0184985317 0.0437707789 0.0094322269 0.0190940000 205548902 95654128 760807424 -0.2201029509 0.0672999099 -0.2926127911 528 21.0800000000 0.0273435600 0.0185152837 0.0437707789 0.0094332824 0.0191330000 205551510 95654128 760807424 -0.2191306353 0.0674431995 -0.2941938639 529 21.1200000000 0.0275493022 0.0185323612 0.0437707789 0.0094319869 0.0191210000 205552518 95654128 760807424 -0.2183670849 0.0666165128 -0.2957890928 530 21.1600000000 0.0276790969 0.0185496192 0.0437707789 0.0094325921 0.0191040000 205555126 95654128 760807424 -0.2184256762 0.0664754733 -0.2973414958 531 21.2000000000 0.0282572657 0.0185679010 0.0437707789 0.0094381416 0.0191910000 205564946 95654128 760807424 -0.2187757492 0.0668315142 -0.2990074754 532 21.2400000000 0.0286137592 0.0185867842 0.0437707789 0.0094461321 0.0190910000 205730038 95654128 760807424 -0.2194727510 0.0650577173 -0.3008584976 533 21.2800000000 0.0282345880 0.0186048851 0.0437707789 0.0094539122 0.0192190000 205732846 95654128 760807424 -0.2191505432 0.0644397587 -0.3028641939 534 21.3200000000 0.0290950257 0.0186245296 0.0437707789 0.0094477429 0.0191290000 205733654 95654128 760807424 -0.2200762182 0.0641930774 -0.3045434654 535 21.3600000000 0.0293735210 0.0186446212 0.0437707789 0.0094436748 0.0232680000 205736462 95654128 760807424 -0.2209005654 0.0628352165 -0.3060279787 536 21.4000000000 0.0299543552 0.0186657214 0.0437707789 0.0094416259 0.0193280000 205739070 95654128 760807424 -0.2224650830 0.0626806021 -0.3080490828 537 21.4400000000 0.0307477675 0.0186882206 0.0437707789 0.0094402353 0.0191560000 205740078 95654128 760807424 -0.2227958292 0.0625561252 -0.3088876903 538 21.4800000000 0.0308163762 0.0187107636 0.0437707789 0.0094493287 0.0190760000 205742686 95654128 760807424 -0.2229399383 0.0617891848 -0.3102328479 539 21.5200000000 0.0300808754 0.0187318584 0.0437707789 0.0094654071 0.0191050000 205743694 95654128 760807424 -0.2216843665 0.0605041087 -0.3115117252 540 21.5600000000 0.0304787681 0.0187536120 0.0437707789 0.0094714517 0.0190610000 205746302 95654128 760807424 -0.2233726382 0.0595326945 -0.3134813011 541 21.6000000000 0.0311600361 0.0187765444 0.0437707789 0.0094734300 0.0190780000 205749110 95654128 760807424 -0.2259938717 0.0585684367 -0.3158018887 542 21.6400000000 0.0319597125 0.0188008676 0.0437707789 0.0094726978 0.0191490000 205749918 95654128 760807424 -0.2271175236 0.0572811253 -0.3169431388 543 21.6800000000 0.0312217306 0.0188237421 0.0437707789 0.0094739272 0.0229170000 205752726 95654128 760807424 -0.2270986289 0.0552305542 -0.3178389072 544 21.7200000000 0.0319427215 0.0188478578 0.0437707789 0.0094698922 0.0193590000 205762070 95654128 760807424 -0.2289920598 0.0545043983 -0.3197289109 545 21.7600000000 0.0326011181 0.0188730932 0.0437707789 0.0094642885 0.0191580000 205927782 95654128 760807424 -0.2303620577 0.0534923673 -0.3213349581 546 21.8000000000 0.0337106176 0.0189002681 0.0437707789 0.0094686199 0.0232730000 205930390 95654128 760807424 -0.2321723104 0.0526993684 -0.3223922849 547 21.8400000000 0.0348838978 0.0189294887 0.0437707789 0.0094894480 0.0193910000 205931398 95654128 760807424 -0.2335844934 0.0512262322 -0.3234966099 548 21.8800000000 0.0358225517 0.0189603154 0.0437707789 0.0095005023 0.0190950000 205934006 95654128 760807424 -0.2348933816 0.0501729809 -0.3241262436 549 21.9200000000 0.0360689387 0.0189914787 0.0437707789 0.0095109760 0.0191460000 205935014 95654128 760807424 -0.2356530577 0.0470666550 -0.3251783252 550 21.9600000000 0.0356889889 0.0190218378 0.0437707789 0.0095190028 0.0192060000 205937622 95654128 760807424 -0.2364148200 0.0459518395 -0.3267150819 551 22.0000000000 0.0367924906 0.0190540894 0.0437707789 0.0095155146 0.0191450000 205940430 95654128 760807424 -0.2385060638 0.0467056669 -0.3284105957 552 22.0400000000 0.0368158109 0.0190862665 0.0437707789 0.0095118227 0.0191440000 205941238 95654128 760807424 -0.2394308448 0.0458162315 -0.3295964897 553 22.0800000000 0.0374771953 0.0191195231 0.0437707789 0.0095118761 0.0201700000 205951518 95654128 760807424 -0.2411788106 0.0441802405 -0.3308332860 554 22.1200000000 0.0381221399 0.0191538239 0.0437707789 0.0095197249 0.0192690000 206117322 95654128 760807424 -0.2421440929 0.0443914905 -0.3313269615 555 22.1600000000 0.0388108790 0.0191892420 0.0437707789 0.0095238700 0.0191720000 206118330 95654128 760807424 -0.2435199618 0.0464560837 -0.3332970440 556 22.2000000000 0.0386897214 0.0192243148 0.0437707789 0.0095172202 0.0192010000 206120938 95654128 760807424 -0.2438686490 0.0459210239 -0.3347096443 557 22.2400000000 0.0395688973 0.0192608401 0.0437707789 0.0095097033 0.0192360000 206121946 95654128 760807424 -0.2449336350 0.0449362807 -0.3356187046 558 22.2800000000 0.0396783240 0.0192974305 0.0437707789 0.0095061454 0.0192810000 206124554 95654128 760807424 -0.2450555414 0.0435005724 -0.3358418941 559 22.3200000000 0.0388808437 0.0193324635 0.0437707789 0.0095084276 0.0192390000 206127362 95654128 760807424 -0.2448849529 0.0425009504 -0.3370058537 560 22.3600000000 0.0385103934 0.0193667098 0.0437707789 0.0095051384 0.0191610000 206128170 95654128 760807424 -0.2455441952 0.0418885462 -0.3387745917 561 22.4000000000 0.0387097932 0.0194011894 0.0437707789 0.0095032784 0.0192260000 206130978 95654128 760807424 -0.2456740141 0.0415138230 -0.3398975730 562 22.4400000000 0.0383050554 0.0194348262 0.0437707789 0.0094998685 0.0192720000 206139530 95654128 760807424 -0.2462504804 0.0404023379 -0.3412031829 563 22.4800000000 0.0383324511 0.0194683921 0.0437707789 0.0094960634 0.0192450000 206305826 95654128 760807424 -0.2466152310 0.0391445458 -0.3418895304 564 22.5200000000 0.0381878726 0.0195015827 0.0437707789 0.0094980267 0.0192630000 206308434 95654128 760807424 -0.2467131019 0.0395627506 -0.3431022465 565 22.5600000000 0.0373581126 0.0195331872 0.0437707789 0.0094989524 0.0191890000 206309442 95654128 760807424 -0.2469769567 0.0375441834 -0.3441047072 566 22.6000000000 0.0369623788 0.0195639808 0.0437707789 0.0094986483 0.0192230000 206312050 95654128 760807424 -0.2467232943 0.0369190313 -0.3452004194 567 22.6400000000 0.0378113128 0.0195961631 0.0437707789 0.0094970137 0.0192010000 206313058 95654128 760807424 -0.2480797023 0.0367783569 -0.3466409445 568 22.6800000000 0.0372159258 0.0196271838 0.0437707789 0.0094952066 0.0228110000 206315666 95654128 760807424 -0.2482946664 0.0349688493 -0.3473306894 569 22.7200000000 0.0370440707 0.0196577934 0.0437707789 0.0095004841 0.0193700000 206318474 95654128 760807424 -0.2483654618 0.0342478752 -0.3476708531 570 22.7600000000 0.0363553241 0.0196870873 0.0437707789 0.0095018860 0.0196680000 206319282 95654128 760807424 -0.2481102943 0.0329200402 -0.3477212489 571 22.8000000000 0.0360491090 0.0197157424 0.0437707789 0.0095059448 0.0192280000 206322090 95654128 760807424 -0.2481011897 0.0312230140 -0.3484078944 572 22.8400000000 0.0355508290 0.0197434261 0.0437707789 0.0095128252 0.0191940000 206324698 95654128 760807424 -0.2477493137 0.0301770587 -0.3488658071 573 22.8800000000 0.0360913202 0.0197719564 0.0437707789 0.0095108962 0.0192870000 206332550 95654128 760807424 -0.2488454580 0.0290668849 -0.3499546349 574 22.9200000000 0.0366933420 0.0198014362 0.0437707789 0.0095106866 0.0192050000 206499002 95654128 760807424 -0.2495001405 0.0273066014 -0.3515240550 575 22.9600000000 0.0377026834 0.0198325688 0.0437707789 0.0095131600 0.0192000000 206500010 95654128 760807424 -0.2507434785 0.0263449196 -0.3528729081 576 23.0000000000 0.0382695831 0.0198645775 0.0437707789 0.0095193357 0.0191860000 206502618 95654128 760807424 -0.2517412603 0.0252501499 -0.3540813625 577 23.0400000000 0.0381866470 0.0198963315 0.0437707789 0.0095249250 0.0191730000 206505426 95654128 760807424 -0.2512871921 0.0232936870 -0.3547573686 578 23.0800000000 0.0385324620 0.0199285740 0.0437707789 0.0095354987 0.0238870000 206506234 95654128 760807424 -0.2515841126 0.0234680716 -0.3556208909 579 23.1200000000 0.0388207287 0.0199612029 0.0437707789 0.0095388368 0.0229360000 206509042 95654128 760807424 -0.2516649961 0.0222960245 -0.3556753993 580 23.1600000000 0.0386637673 0.0199934487 0.0437707789 0.0095411268 0.0193400000 206509850 95654128 760807424 -0.2515690625 0.0198738389 -0.3557120860 581 23.2000000000 0.0380322784 0.0200244966 0.0437707789 0.0095419866 0.0193050000 206512658 95654128 760807424 -0.2508739829 0.0172006767 -0.3558105826 582 23.2400000000 0.0378489122 0.0200551227 0.0437707789 0.0095429343 0.0192650000 206522018 95654128 760807424 -0.2500221133 0.0159651823 -0.3564921319 583 23.2800000000 0.0377854966 0.0200855350 0.0437707789 0.0095496422 0.0226770000 206687162 95654128 760807424 -0.2492683828 0.0163260140 -0.3572801054 584 23.3200000000 0.0381567515 0.0201164789 0.0437707789 0.0095500170 0.0193580000 206689770 95654128 760807424 -0.2501664162 0.0154109988 -0.3576934338 585 23.3600000000 0.0385004282 0.0201479045 0.0437707789 0.0095616324 0.0191750000 206690778 95654128 760807424 -0.2499977946 0.0158644710 -0.3582120240 586 23.4000000000 0.0381910615 0.0201786948 0.0437707789 0.0095768304 0.0192310000 206693386 95654128 760807424 -0.2493529022 0.0161506571 -0.3582813144 587 23.4400000000 0.0379877090 0.0202090339 0.0437707789 0.0095801452 0.0192070000 206696194 95654128 760807424 -0.2490813434 0.0150792310 -0.3586624563 588 23.4800000000 0.0376943052 0.0202387707 0.0437707789 0.0095871459 0.0272200000 206697002 95654128 760807424 -0.2481065243 0.0155391982 -0.3583042324 589 23.5200000000 0.0375366025 0.0202681389 0.0437707789 0.0095955585 0.0196900000 206699810 95654128 760807424 -0.2478611022 0.0164363496 -0.3585760593 590 23.5600000000 0.0370927490 0.0202966552 0.0437707789 0.0096005747 0.0192310000 206702418 95654128 760807424 -0.2472565323 0.0165014118 -0.3586998880 591 23.6000000000 0.0366805196 0.0203243774 0.0437707789 0.0096000714 0.0191610000 206703426 95654128 760807424 -0.2467572689 0.0149404965 -0.3582661152 592 23.6400000000 0.0366439112 0.0203519442 0.0437707789 0.0096088324 0.0192570000 206712102 95654128 760807424 -0.2468646169 0.0133786472 -0.3584780097 593 23.6800000000 0.0367150120 0.0203795379 0.0437707789 0.0096155012 0.0191700000 206877570 95654128 760807424 -0.2470788360 0.0141196512 -0.3589100838 594 23.7200000000 0.0365794897 0.0204068106 0.0437707789 0.0096131986 0.0194100000 206880178 95654128 760807424 -0.2466931194 0.0134572675 -0.3586857319 595 23.7600000000 0.0366594419 0.0204341259 0.0437707789 0.0096152316 0.0195310000 206882986 95654128 760807424 -0.2468730807 0.0129805952 -0.3590499461 596 23.8000000000 0.0368995555 0.0204617525 0.0437707789 0.0096203116 0.0195510000 206883794 95654128 760807424 -0.2479292750 0.0129443211 -0.3596930802 597 23.8400000000 0.0372653306 0.0204898992 0.0437707789 0.0096199803 0.0195850000 206886602 95654128 760807424 -0.2481980771 0.0135136070 -0.3597090542 598 23.8800000000 0.0372623429 0.0205179467 0.0437707789 0.0096163767 0.0195300000 206887410 95654128 760807424 -0.2485860735 0.0119349808 -0.3601953685 599 23.9200000000 0.0360998698 0.0205439600 0.0437707789 0.0096109799 0.0195540000 206890218 95654128 760807424 -0.2470081449 0.0102519840 -0.3593837023 600 23.9600000000 0.0354574546 0.0205688158 0.0437707789 0.0096063650 0.0195160000 206892826 95654128 760807424 -0.2458919883 0.0096745621 -0.3589365482 601 24.0000000000 0.0347707905 0.0205924464 0.0437707789 0.0096034977 0.0195480000 206893834 95654128 760807424 -0.2452803254 0.0087320814 -0.3590283096 602 24.0400000000 0.0342368744 0.0206151115 0.0437707789 0.0096060279 0.0202040000 206896442 95654128 760807424 -0.2443942726 0.0090179499 -0.3588452935 603 24.0800000000 0.0336210281 0.0206366802 0.0437707789 0.0096155409 0.0196860000 206897450 95654128 760807424 -0.2437607944 0.0084910644 -0.3590283096 604 24.1200000000 0.0336865857 0.0206582860 0.0437707789 0.0096177230 0.0194870000 206900058 95654128 760807424 -0.2436899394 0.0075307367 -0.3585596383 605 24.1600000000 0.0335999541 0.0206796772 0.0437707789 0.0096155536 0.0194890000 206902866 95654128 760807424 -0.2441295981 0.0072932239 -0.3590605855 606 24.2000000000 0.0327165015 0.0206995399 0.0437707789 0.0096088757 0.0193040000 206903674 95654128 760807424 -0.2430148125 0.0046398621 -0.3588367403 607 24.2400000000 0.0315780491 0.0207174617 0.0437707789 0.0096028047 0.0229340000 206906482 95654128 760807424 -0.2408399284 0.0038062332 -0.3577061892 608 24.2800000000 0.0320000201 0.0207360185 0.0437707789 0.0095953158 0.0229190000 206909090 95654128 760807424 -0.2408646047 0.0022071109 -0.3575342894 609 24.3200000000 0.0307466164 0.0207524563 0.0437707789 0.0095893707 0.0192520000 206910098 95654128 760807424 -0.2394273281 0.0008317098 -0.3564644456 610 24.3600000000 0.0305246674 0.0207684763 0.0437707789 0.0095887945 0.0190830000 206912706 95654128 760807424 -0.2390660495 0.0007781782 -0.3568464816 611 24.4000000000 0.0301765762 0.0207838742 0.0437707789 0.0095831072 0.0191880000 206918742 95654128 760807424 -0.2384893745 -0.0007817511 -0.3567925394 612 24.4400000000 0.0304808877 0.0207997190 0.0437707789 0.0095824235 0.0191510000 207086422 95654128 760807424 -0.2391950935 0.0004990350 -0.3577988148 613 24.4800000000 0.0303035863 0.0208152228 0.0437707789 0.0095770687 0.0190800000 207089230 95654128 760807424 -0.2375923693 0.0007361302 -0.3568527699 614 24.5200000000 0.0311974995 0.0208321321 0.0437707789 0.0095695046 0.0191590000 207090038 95654128 760807424 -0.2393374890 0.0011820588 -0.3581052423 615 24.5600000000 0.0306318402 0.0208480666 0.0437707789 0.0095621245 0.0191860000 207092846 95654128 760807424 -0.2389638126 -0.0016665652 -0.3578867018 616 24.6000000000 0.0301600751 0.0208631835 0.0437707789 0.0095592133 0.0191950000 207093654 95654128 760807424 -0.2381887883 -0.0047600390 -0.3576243222 617 24.6400000000 0.0302423872 0.0208783848 0.0437707789 0.0095606976 0.0191800000 207096462 95654128 760807424 -0.2380487174 -0.0057345973 -0.3579446673 618 24.6800000000 0.0303055048 0.0208936390 0.0437707789 0.0095607013 0.0192190000 207099070 95654128 760807424 -0.2375213057 -0.0058571058 -0.3579085767 619 24.7200000000 0.0296960939 0.0209078595 0.0437707789 0.0095773822 0.0235490000 207100078 95654128 760807424 -0.2368559837 -0.0049158139 -0.3589714170 620 24.7600000000 0.0296305269 0.0209219283 0.0437707789 0.0095813242 0.0193190000 207102686 95654128 760807424 -0.2363163233 -0.0045058299 -0.3595240414 621 24.8000000000 0.0294915531 0.0209357280 0.0437707789 0.0095746671 0.0191840000 207103694 95654128 760807424 -0.2361614704 -0.0052798730 -0.3610081375 622 24.8400000000 0.0294494573 0.0209494157 0.0437707789 0.0095672425 0.0191510000 207106302 95654128 760807424 -0.2352862209 -0.0040366026 -0.3613377512 623 24.8800000000 0.0292759556 0.0209627809 0.0437707789 0.0095605134 0.0190870000 207109110 95654128 760807424 -0.2328411788 -0.0044134459 -0.3590828776 624 24.9200000000 0.0297724828 0.0209768990 0.0437707789 0.0095532418 0.0191980000 207109918 95654128 760807424 -0.2330697626 -0.0047708568 -0.3596299887 625 24.9600000000 0.0296937879 0.0209908460 0.0437707789 0.0095480397 0.0192480000 207112726 95654128 760807424 -0.2317803949 -0.0033116890 -0.3597448170 626 25.0000000000 0.0300500598 0.0210053176 0.0437707789 0.0095406935 0.0191170000 207115334 95654128 760807424 -0.2308867574 -0.0025724720 -0.3596137762 627 25.0400000000 0.0304827318 0.0210204331 0.0437707789 0.0095339050 0.0229960000 207116342 95654128 760807424 -0.2292056084 -0.0014706586 -0.3583713770 628 25.0800000000 0.0305984579 0.0210356847 0.0437707789 0.0095295457 0.0193680000 207118950 95654128 760807424 -0.2278919965 -0.0009191213 -0.3583927751 629 25.1200000000 0.0311642475 0.0210517874 0.0437707789 0.0095229145 0.0230220000 207119958 95654128 760807424 -0.2268314660 0.0004203704 -0.3587507606 630 25.1600000000 0.0314389728 0.0210682750 0.0437707789 0.0095197150 0.0222780000 207127510 95654128 760807424 -0.2251746356 0.0006862613 -0.3574781418 631 25.2000000000 0.0318658240 0.0210853868 0.0437707789 0.0095139900 0.0193040000 207296002 95654128 760807424 -0.2232391983 -0.0001553576 -0.3561397791 632 25.2400000000 0.0324843228 0.0211034231 0.0437707789 0.0095067766 0.0191710000 207296810 95654128 760807424 -0.2210217863 -0.0002047203 -0.3543981910 633 25.2800000000 0.0323320329 0.0211211618 0.0437707789 0.0094992871 0.0191880000 207299618 95654128 760807424 -0.2198458463 0.0011464345 -0.3551059365 634 25.3200000000 0.0319808610 0.0211382907 0.0437707789 0.0094933245 0.0192170000 207300426 95654128 760807424 -0.2178619504 0.0010642178 -0.3549657166 635 25.3600000000 0.0318729058 0.0211551956 0.0437707789 0.0094873286 0.0191500000 207303234 95654128 760807424 -0.2158816010 0.0013712357 -0.3546124995 636 25.4000000000 0.0317683183 0.0211718829 0.0437707789 0.0094813772 0.0193020000 207305842 95654128 760807424 -0.2147384882 0.0007365445 -0.3556112647 637 25.4400000000 0.0309293456 0.0211872007 0.0437707789 0.0094748694 0.0192120000 207306850 95654128 760807424 -0.2122799009 0.0008030061 -0.3562439382 638 25.4800000000 0.0317499936 0.0212037568 0.0437707789 0.0094714006 0.0228630000 207309458 95654128 760807424 -0.2103342265 0.0008155957 -0.3542562425 639 25.5200000000 0.0312756971 0.0212195188 0.0437707789 0.0094640145 0.0193580000 207310466 95654128 760807424 -0.2076651752 0.0004597759 -0.3543465137 640 25.5600000000 0.0310970210 0.0212349524 0.0437707789 0.0094570964 0.0193400000 207313074 95654128 760807424 -0.2059936821 0.0005403990 -0.3549268842 641 25.6000000000 0.0300437752 0.0212486948 0.0437707789 0.0094512434 0.0230450000 207315882 95654128 760807424 -0.2039053738 -0.0008930918 -0.3569035828 642 25.6400000000 0.0296535231 0.0212617864 0.0437707789 0.0094451598 0.0193460000 207316690 95654128 760807424 -0.2017765045 -0.0013615771 -0.3574347794 643 25.6800000000 0.0296152886 0.0212747778 0.0437707789 0.0094394633 0.0229950000 207319498 95654128 760807424 -0.1976464093 -0.0006901020 -0.3548004925 644 25.7200000000 0.0293566063 0.0212873273 0.0437707789 0.0094327406 0.0193670000 207322106 95654128 760807424 -0.1948576272 -0.0006301664 -0.3540884554 645 25.7600000000 0.0287940633 0.0212989656 0.0437707789 0.0094255455 0.0191830000 207323114 95654128 760807424 -0.1919446886 -0.0018219736 -0.3537808955 646 25.8000000000 0.0292602014 0.0213112895 0.0437707789 0.0094207975 0.0191300000 207325722 95654128 760807424 -0.1895793825 0.0002562827 -0.3530348241 647 25.8400000000 0.0297518503 0.0213243352 0.0437707789 0.0094137864 0.0192280000 207326730 95654128 760807424 -0.1871209294 0.0020131986 -0.3520128727 648 25.8800000000 0.0293970108 0.0213367930 0.0437707789 0.0094079935 0.0192070000 207329338 95654128 760807424 -0.1853151619 0.0003297039 -0.3520436287 649 25.9200000000 0.0291028358 0.0213487592 0.0437707789 0.0094011326 0.0191950000 207332146 95654128 760807424 -0.1823920012 -0.0012391976 -0.3514017761 650 25.9600000000 0.0286254063 0.0213599540 0.0437707789 0.0093945805 0.0191670000 207332954 95654128 760807424 -0.1793997586 -0.0015151678 -0.3509536386 651 26.0000000000 0.0281245336 0.0213703451 0.0437707789 0.0093874854 0.0227890000 207335762 95654128 760807424 -0.1767527908 -0.0018320081 -0.3509887159 652 26.0400000000 0.0283708461 0.0213810821 0.0437707789 0.0093817736 0.0201430000 207336570 95654128 760807424 -0.1736202836 -0.0027013645 -0.3495897949 653 26.0800000000 0.0284910742 0.0213919703 0.0437707789 0.0093747003 0.0193900000 207343706 95654128 760807424 -0.1713119745 -0.0021366330 -0.3491548598 654 26.1200000000 0.0290075149 0.0214036148 0.0437707789 0.0093677512 0.0192360000 207512738 95654128 760807424 -0.1656863242 -0.0018084641 -0.3463475108 655 26.1600000000 0.0286512151 0.0214146799 0.0437707789 0.0093606598 0.0327280000 207513746 95654128 760807424 -0.1631429493 -0.0029561638 -0.3461270630 656 26.2000000000 0.0287132990 0.0214258058 0.0437707789 0.0093537659 0.0209100000 207516354 95654128 760807424 -0.1601648629 -0.0030541213 -0.3448816538 657 26.2400000000 0.0278236419 0.0214355438 0.0437707789 0.0093469002 0.0194400000 207517362 95654128 760807424 -0.1565050930 -0.0048945621 -0.3440950513 658 26.2800000000 0.0280025527 0.0214455240 0.0437707789 0.0093398682 0.0193120000 207519970 95654128 760807424 -0.1540406197 -0.0056081656 -0.3433664441 659 26.3200000000 0.0282488856 0.0214558478 0.0437707789 0.0093333700 0.0229430000 207522778 95654128 760807424 -0.1511249542 -0.0064419527 -0.3426727653 660 26.3600000000 0.0277032647 0.0214653136 0.0437707789 0.0093264316 0.0316070000 207523586 95654128 760807424 -0.1481782943 -0.0067105107 -0.3421760798 661 26.4000000000 0.0284047592 0.0214758120 0.0437707789 0.0093196114 0.0206720000 207526394 95654128 760807424 -0.1463741362 -0.0065729232 -0.3409585953 662 26.4400000000 0.0282831099 0.0214860949 0.0437707789 0.0093138160 0.0192550000 207529002 95654128 760807424 -0.1432888955 -0.0088974163 -0.3406700790 663 26.4800000000 0.0286217965 0.0214968576 0.0437707789 0.0093070863 0.0192870000 207530010 95654128 760807424 -0.1403770596 -0.0100176297 -0.3392925858 664 26.5200000000 0.0293663684 0.0215087093 0.0437707789 0.0093002467 0.0225360000 207532618 95654128 760807424 -0.1382383704 -0.0126745366 -0.3381126523 665 26.5600000000 0.0301574413 0.0215217149 0.0437707789 0.0092951191 0.0202340000 207533626 95654128 760807424 -0.1360663027 -0.0147151239 -0.3367757201 666 26.6000000000 0.0300579760 0.0215345321 0.0437707789 0.0092959818 0.0193090000 207536234 95654128 760807424 -0.1332423240 -0.0146168629 -0.3358635008 667 26.6400000000 0.0310145672 0.0215487451 0.0437707789 0.0092934819 0.0192270000 207539042 95654128 760807424 -0.1309337914 -0.0157874841 -0.3345841467 668 26.6800000000 0.0308444630 0.0215626608 0.0437707789 0.0092905336 0.0192300000 207539850 95654128 760807424 -0.1285158396 -0.0157610290 -0.3340786695 669 26.7200000000 0.0306834579 0.0215762943 0.0437707789 0.0092863976 0.0228870000 207542658 95654128 760807424 -0.1261285245 -0.0166829210 -0.3341285288 670 26.7600000000 0.0304089934 0.0215894774 0.0437707789 0.0092857637 0.0194470000 207543466 95654128 760807424 -0.1241995171 -0.0169799924 -0.3350647092 671 26.8000000000 0.0305338092 0.0216028073 0.0437707789 0.0092816523 0.0192720000 207546274 95654128 760807424 -0.1220790967 -0.0185725819 -0.3364718556 672 26.8400000000 0.0309135988 0.0216166626 0.0437707789 0.0092753317 0.0192080000 207548882 95654128 760807424 -0.1190209538 -0.0192334112 -0.3350103199 673 26.8800000000 0.0302558597 0.0216294995 0.0437707789 0.0092797797 0.0192470000 207549890 95654128 760807424 -0.1179871336 -0.0205643997 -0.3379490077 674 26.9200000000 0.0300489329 0.0216419912 0.0437707789 0.0092879882 0.0192460000 207552498 95654128 760807424 -0.1152366698 -0.0201375391 -0.3387487829 675 26.9600000000 0.0303272828 0.0216548583 0.0437707789 0.0092833834 0.0193730000 207553506 95654128 760807424 -0.1128197536 -0.0226951297 -0.3409587443 676 27.0000000000 0.0314953700 0.0216694153 0.0437707789 0.0092769602 0.0192800000 207556114 95654128 760807424 -0.1106128320 -0.0262559205 -0.3408588171 677 27.0400000000 0.0313493572 0.0216837136 0.0437707789 0.0092740066 0.0192450000 207558922 95654128 760807424 -0.1073531806 -0.0260290019 -0.3413069844 678 27.0800000000 0.0309931040 0.0216974442 0.0437707789 0.0092709892 0.0192790000 207559730 95654128 760807424 -0.1052811891 -0.0271776859 -0.3440834284 679 27.1200000000 0.0309522618 0.0217110743 0.0437707789 0.0092690755 0.0192690000 207562538 95654128 760807424 -0.1035186872 -0.0274539795 -0.3459427655 680 27.1600000000 0.0317167751 0.0217257886 0.0437707789 0.0092668279 0.0236690000 207565146 95654128 760807424 -0.1006996110 -0.0287742894 -0.3473365903 681 27.2000000000 0.0313225463 0.0217398807 0.0437707789 0.0092614223 0.0196030000 207566154 95654128 760807424 -0.0979233459 -0.0269514807 -0.3472373486 682 27.2400000000 0.0315219462 0.0217542239 0.0437707789 0.0092553177 0.0193690000 207568762 95654128 760807424 -0.0955720469 -0.0282134693 -0.3495828807 683 27.2800000000 0.0322411619 0.0217695782 0.0437707789 0.0092493539 0.0192980000 207569770 95654128 760807424 -0.0925121605 -0.0290590320 -0.3499096632 684 27.3200000000 0.0323625766 0.0217850650 0.0437707789 0.0092428322 0.0193460000 207572378 95654128 760807424 -0.0890249163 -0.0295510795 -0.3507888019 685 27.3600000000 0.0322074220 0.0218002801 0.0437707789 0.0092361080 0.0193340000 207575186 95654128 760807424 -0.0866781622 -0.0309677143 -0.3520858288 686 27.4000000000 0.0321313106 0.0218153399 0.0437707789 0.0092347913 0.0287600000 207575994 95654128 760807424 -0.0834231898 -0.0320016742 -0.3532558084 687 27.4400000000 0.0328373648 0.0218313836 0.0437707789 0.0092351697 0.0200950000 207578802 95654128 760807424 -0.0807963908 -0.0322101861 -0.3547329307 688 27.4800000000 0.0330739431 0.0218477246 0.0437707789 0.0092344679 0.0246670000 207579610 95654128 760807424 -0.0778260380 -0.0331253894 -0.3571769297 689 27.5200000000 0.0337693021 0.0218650273 0.0437707789 0.0092332168 0.0201020000 207582418 95654128 760807424 -0.0750008747 -0.0349885076 -0.3594075739 690 27.5600000000 0.0345246904 0.0218833746 0.0437707789 0.0092358745 0.0194140000 207588230 95654128 760807424 -0.0720965117 -0.0348150618 -0.3614158928 691 27.6000000000 0.0350760072 0.0219024667 0.0437707789 0.0092292371 0.0193890000 207756850 95654128 760807424 -0.0686204955 -0.0343740880 -0.3630306125 692 27.6400000000 0.0351940878 0.0219216743 0.0437707789 0.0092252989 0.0194190000 207759458 95654128 760807424 -0.0661999583 -0.0332131162 -0.3650358021 693 27.6800000000 0.0356531814 0.0219414889 0.0437707789 0.0092225255 0.0194020000 207760466 95654128 760807424 -0.0629765913 -0.0341382921 -0.3659201264 694 27.7200000000 0.0363376737 0.0219622326 0.0437707789 0.0092160886 0.0193590000 207763074 95654128 760807424 -0.0593691878 -0.0360609479 -0.3678281307 695 27.7600000000 0.0378627107 0.0219851110 0.0437707789 0.0092098982 0.0193340000 207765882 95654128 760807424 -0.0571616925 -0.0387196392 -0.3701087832 696 27.8000000000 0.0390086770 0.0220095702 0.0437707789 0.0092043693 0.0203490000 207766690 95654128 760807424 -0.0544230938 -0.0401788950 -0.3709018826 697 27.8400000000 0.0395185947 0.0220346907 0.0437707789 0.0092016955 0.0194000000 207769498 95654128 760807424 -0.0501281582 -0.0393253453 -0.3765909374 698 27.8800000000 0.0389721468 0.0220589564 0.0437707789 0.0091952063 0.0233660000 207772106 95654128 760807424 -0.0480551533 -0.0390838645 -0.3782761097 699 27.9200000000 0.0392253734 0.0220835150 0.0437707789 0.0092127209 0.0195400000 207773114 95654128 760807424 -0.0441997088 -0.0396238118 -0.3831012547 700 27.9600000000 0.0389225148 0.0221075707 0.0437707789 0.0092077882 0.0193810000 207775722 95654128 760807424 -0.0423571579 -0.0407297164 -0.3867353201 701 28.0000000000 0.0385257192 0.0221309917 0.0437707789 0.0092052821 0.0193830000 207776730 95654128 760807424 -0.0405408442 -0.0412987582 -0.3888512850 702 28.0400000000 0.0395025574 0.0221557375 0.0437707789 0.0092092119 0.0230070000 207779338 95654128 760807424 -0.0391584001 -0.0435996242 -0.3909462392 703 28.0800000000 0.0409060717 0.0221824094 0.0437707789 0.0092225647 0.0195210000 207782146 95654128 760807424 -0.0373792052 -0.0448182896 -0.3923759460 704 28.1200000000 0.0420612395 0.0222106464 0.0437707789 0.0092266484 0.0193590000 207782954 95654128 760807424 -0.0357518457 -0.0462686829 -0.3947598636 705 28.1600000000 0.0416492373 0.0222382189 0.0437707789 0.0092275514 0.0193510000 207785762 95654128 760807424 -0.0331165716 -0.0465221182 -0.3949343264 706 28.2000000000 0.0419887267 0.0222661941 0.0437707789 0.0092330830 0.0193920000 207786570 95654128 760807424 -0.0313976035 -0.0470115319 -0.3961541653 707 28.2400000000 0.0433926955 0.0222960760 0.0437707789 0.0092371750 0.0195040000 207791946 95654128 760807424 -0.0299134329 -0.0479908548 -0.3987351656 708 28.2800000000 0.0444104187 0.0223273109 0.0444104187 0.0092311198 0.0238630000 207962714 95654128 760807424 -0.0282496512 -0.0489424355 -0.4012008607 709 28.3200000000 0.0439549237 0.0223578153 0.0444104187 0.0092246969 0.0231920000 207963722 95654128 760807424 -0.0267524216 -0.0490489304 -0.4029341042 710 28.3600000000 0.0446521789 0.0223892158 0.0446521789 0.0092221963 0.0227490000 207966330 95654128 760807424 -0.0242038965 -0.0508419834 -0.4039828479 711 28.4000000000 0.0459867939 0.0224224051 0.0459867939 0.0092191443 0.0195380000 207967338 95654128 760807424 -0.0219168570 -0.0520738475 -0.4057488143 712 28.4400000000 0.0465529636 0.0224562963 0.0465529636 0.0092128417 0.0203310000 207969946 95654128 760807424 -0.0205810852 -0.0531846508 -0.4072467983 713 28.4800000000 0.0461319238 0.0224895020 0.0465529636 0.0092102395 0.0195060000 207972754 95654128 760807424 -0.0198430754 -0.0525570065 -0.4100081325 714 28.5200000000 0.0448653698 0.0225208407 0.0465529636 0.0092123063 0.0194780000 207973562 95654128 760807424 -0.0181691274 -0.0493215881 -0.4117751122 715 28.5600000000 0.0455711223 0.0225530789 0.0465529636 0.0092085718 0.0194200000 207976370 95654128 760807424 -0.0159941912 -0.0489190109 -0.4142653048 716 28.6000000000 0.0451328345 0.0225846149 0.0465529636 0.0092042689 0.0194140000 207978978 95654128 760807424 -0.0127601912 -0.0479018539 -0.4132386446 717 28.6400000000 0.0466984473 0.0226182464 0.0466984473 0.0092015988 0.0194260000 207979986 95654128 760807424 -0.0110237012 -0.0499560535 -0.4159619808 718 28.6800000000 0.0467914827 0.0226519139 0.0467914827 0.0091956739 0.0265790000 207982594 95654128 760807424 -0.0092406888 -0.0493726097 -0.4183273911 719 28.7200000000 0.0495827645 0.0226893699 0.0495827645 0.0091910892 0.0200070000 207983602 95654128 760807424 -0.0071113808 -0.0533504933 -0.4207502306 720 28.7600000000 0.0516210943 0.0227295528 0.0516210943 0.0091879328 0.0194430000 207986210 95654128 760807424 -0.0045699636 -0.0559249222 -0.4214431047 721 28.8000000000 0.0531881154 0.0227717977 0.0531881154 0.0091899556 0.0194080000 207989018 95654128 760807424 -0.0021464617 -0.0559223033 -0.4227057993 722 28.8400000000 0.0533771813 0.0228141874 0.0533771813 0.0091838477 0.0193950000 207989826 95654128 760807424 0.0015997763 -0.0560487136 -0.4217528403 723 28.8800000000 0.0548820943 0.0228585414 0.0548820943 0.0091780817 0.0194490000 207992634 95654128 760807424 0.0037737519 -0.0566591620 -0.4225435853 724 28.9200000000 0.0556754842 0.0229038687 0.0556754842 0.0091722315 0.0194590000 207993442 95654128 760807424 0.0059048487 -0.0560342222 -0.4231863618 725 28.9600000000 0.0581999384 0.0229525529 0.0581999384 0.0091668161 0.0195720000 207996250 95654128 760807424 0.0089762369 -0.0589114763 -0.4234831929 726 29.0000000000 0.0602356680 0.0230039070 0.0602356680 0.0091616013 0.0194240000 207998858 95654128 760807424 0.0115310093 -0.0610432662 -0.4238817096 727 29.0400000000 0.0599065796 0.0230546673 0.0602356680 0.0091619522 0.0194200000 207999866 95654128 760807424 0.0157302693 -0.0599712953 -0.4218972325 728 29.0800000000 0.0611823276 0.0231070404 0.0611823276 0.0091564184 0.0232350000 208002474 95654128 760807424 0.0185143575 -0.0597389601 -0.4220905602 729 29.1200000000 0.0623221137 0.0231608334 0.0623221137 0.0091503605 0.0196620000 208003482 95654128 760807424 0.0215423927 -0.0615572780 -0.4205238521 730 29.1600000000 0.0633431375 0.0232158776 0.0633431375 0.0091523986 0.0195250000 208008082 95654128 760807424 0.0248911213 -0.0631572455 -0.4192327559 731 29.2000000000 0.0637778863 0.0232713660 0.0637778863 0.0091578558 0.0195080000 208179630 95654128 760807424 0.0283984058 -0.0627402961 -0.4179127514 732 29.2400000000 0.0638238192 0.0233267655 0.0638238192 0.0091560058 0.0194790000 208180438 95654128 760807424 0.0328962579 -0.0636931136 -0.4157031178 733 29.2800000000 0.0636180416 0.0233817332 0.0638238192 0.0091532956 0.0231580000 208183246 95654128 760807424 0.0375859886 -0.0644181743 -0.4133545756 734 29.3200000000 0.0636274591 0.0234365639 0.0638238192 0.0091487475 0.0196180000 208185854 95654128 760807424 0.0412789620 -0.0643941164 -0.4115306437 735 29.3600000000 0.0629898310 0.0234903778 0.0638238192 0.0091430783 0.0194890000 208186862 95654128 760807424 0.0449498147 -0.0642985329 -0.4092116952 736 29.4000000000 0.0630046353 0.0235440657 0.0638238192 0.0091375419 0.0195820000 208189470 95654128 760807424 0.0488152578 -0.0655019730 -0.4071397483 737 29.4400000000 0.0630593374 0.0235976821 0.0638238192 0.0091335931 0.0195000000 208190478 95654128 760807424 0.0517941229 -0.0656985268 -0.4058806896 738 29.4800000000 0.0629489571 0.0236510036 0.0638238192 0.0091291859 0.0233730000 208193086 95654128 760807424 0.0548669510 -0.0652951375 -0.4044645429 739 29.5200000000 0.0625672638 0.0237036643 0.0638238192 0.0091235230 0.0196460000 208195894 95654128 760807424 0.0581917204 -0.0659934431 -0.4022974074 740 29.5600000000 0.0653005764 0.0237598763 0.0653005764 0.0091208453 0.0194610000 208196702 95654128 760807424 0.0591741018 -0.0690816566 -0.4026404321 741 29.6000000000 0.0679510087 0.0238195135 0.0679510087 0.0091251385 0.0194830000 208199510 95654128 760807424 0.0602250248 -0.0716320649 -0.4022849202 742 29.6400000000 0.0690983757 0.0238805362 0.0690983757 0.0091278363 0.0194950000 208200318 95654128 760807424 0.0617581755 -0.0717448816 -0.4020351768 743 29.6800000000 0.0696554780 0.0239421445 0.0696554780 0.0091248581 0.0194010000 208203126 95654128 760807424 0.0645046905 -0.0726741329 -0.4010959268 744 29.7200000000 0.0687653348 0.0240023907 0.0696554780 0.0091206654 0.0195480000 208205734 95654128 760807424 0.0670551211 -0.0720275044 -0.3998883963 745 29.7600000000 0.0693562776 0.0240632684 0.0696554780 0.0091166145 0.0201720000 208206742 95654128 760807424 0.0700876266 -0.0726201907 -0.3987829983 746 29.8000000000 0.0695276260 0.0241242126 0.0696554780 0.0091124291 0.0194710000 208209350 95654128 760807424 0.0708168298 -0.0711780265 -0.3987404406 747 29.8400000000 0.0684627816 0.0241835681 0.0696554780 0.0091113596 0.0194800000 208210358 95654128 760807424 0.0718905330 -0.0704258978 -0.3977330327 748 29.8800000000 0.0688348785 0.0242432624 0.0696554780 0.0091190776 0.0196330000 208214938 95654128 760807424 0.0760866031 -0.0709220916 -0.3959840238 749 29.9200000000 0.0695018545 0.0243036877 0.0696554780 0.0091138124 0.0228910000 208386490 95654128 760807424 0.0760814697 -0.0693188533 -0.3971197903 750 29.9600000000 0.0707169920 0.0243655721 0.0707169920 0.0091089678 0.0195460000 208387298 95654128 760807424 0.0777388588 -0.0709435642 -0.3963480890 751 30.0000000000 0.0723840669 0.0244295115 0.0723840669 0.0091034582 0.0195350000 208390106 95654128 760807424 0.0793101937 -0.0722738281 -0.3956964016 752 30.0400000000 0.0729733333 0.0244940645 0.0729733333 0.0090996215 0.0195520000 208392714 95654128 760807424 0.0799974501 -0.0713165626 -0.3961862624 753 30.0800000000 0.0734295249 0.0245590518 0.0734295249 0.0090958201 0.0194750000 208393722 95654128 760807424 0.0807119086 -0.0712115169 -0.3965793252 754 30.1200000000 0.0730165318 0.0246233190 0.0734295249 0.0090901347 0.0194570000 208396330 95654128 760807424 0.0829230174 -0.0704865083 -0.3961474597 755 30.1600000000 0.0743500143 0.0246891822 0.0743500143 0.0090847985 0.0194930000 208397338 95654128 760807424 0.0833054855 -0.0708906427 -0.3968536854 756 30.2000000000 0.0743685141 0.0247548956 0.0743685141 0.0090791794 0.0196260000 208399946 95654128 760807424 0.0850930586 -0.0720863640 -0.3957737982 757 30.2400000000 0.0751705095 0.0248214948 0.0751705095 0.0090794056 0.0229860000 208402754 95654128 760807424 0.0862909928 -0.0733938143 -0.3952620625 758 30.2800000000 0.0765601099 0.0248897516 0.0765601099 0.0090967450 0.0197230000 208403562 95654128 760807424 0.0871788114 -0.0740628242 -0.3953816295 759 30.3200000000 0.0785452425 0.0249604439 0.0785452425 0.0091062930 0.0195310000 208406370 95654128 760807424 0.0892574340 -0.0760736018 -0.3950363100 760 30.3600000000 0.0792576000 0.0250318875 0.0792576000 0.0091105100 0.0222560000 208407178 95654128 760807424 0.0906833336 -0.0766595080 -0.3946660161 761 30.4000000000 0.0808260441 0.0251052044 0.0808260441 0.0091199980 0.0205330000 208409986 95654128 760807424 0.0914443508 -0.0778525025 -0.3951317668 762 30.4400000000 0.0830270573 0.0251812174 0.0830270573 0.0091345661 0.0233470000 208412594 95654128 760807424 0.0924667120 -0.0793427378 -0.3948773444 763 30.4800000000 0.0836068243 0.0252577909 0.0836068243 0.0091473006 0.0197810000 208413602 95654128 760807424 0.0948898047 -0.0796835199 -0.3948788941 764 30.5200000000 0.0842957720 0.0253350657 0.0842957720 0.0091570716 0.0196270000 208416210 95654128 760807424 0.0969332904 -0.0804936811 -0.3947662115 765 30.5600000000 0.0853952616 0.0254135758 0.0853952616 0.0091748387 0.0196200000 208417218 95654128 760807424 0.0986969620 -0.0816786513 -0.3945061862 766 30.6000000000 0.0862452090 0.0254929905 0.0862452090 0.0091916431 0.0197960000 208422434 95654128 760807424 0.1006554589 -0.0814856812 -0.3946146667 767 30.6400000000 0.0878404751 0.0255742779 0.0878404751 0.0091926659 0.0195580000 208593994 95654128 760807424 0.1020427719 -0.0818289295 -0.3952265680 768 30.6800000000 0.0888294205 0.0256566414 0.0888294205 0.0091910586 0.0195640000 208594802 95654128 760807424 0.1039067507 -0.0832210779 -0.3949553072 769 30.7200000000 0.0915212482 0.0257422911 0.0915212482 0.0091925406 0.0194940000 208597610 95654128 760807424 0.1046987846 -0.0849781930 -0.3957262337 770 30.7600000000 0.0917072892 0.0258279599 0.0917072892 0.0091890386 0.0198820000 208600218 95654128 760807424 0.1064140946 -0.0842964947 -0.3962446451 771 30.8000000000 0.0927114859 0.0259147090 0.0927114859 0.0091831098 0.0196290000 208601226 95654128 760807424 0.1073438525 -0.0854619369 -0.3966169357 772 30.8400000000 0.0936751962 0.0260024816 0.0936751962 0.0091869373 0.0194960000 208603834 95654128 760807424 0.1084677503 -0.0863418132 -0.3969561160 773 30.8800000000 0.0946549922 0.0260912947 0.0946549922 0.0091870551 0.0195330000 208604842 95654128 760807424 0.1102516875 -0.0866175517 -0.3973928988 774 30.9200000000 0.0943475664 0.0261794811 0.0946549922 0.0091820523 0.0195470000 208607450 95654128 760807424 0.1115449220 -0.0855871290 -0.3978645205 775 30.9600000000 0.0937813446 0.0262667093 0.0946549922 0.0091766876 0.0195020000 208610258 95654128 760807424 0.1129427776 -0.0843165368 -0.3981719017 776 31.0000000000 0.0948108956 0.0263550395 0.0948108956 0.0091751911 0.0195080000 208611066 95654128 760807424 0.1137197837 -0.0849150047 -0.3980133235 777 31.0400000000 0.0956051648 0.0264441645 0.0956051648 0.0091722506 0.0195420000 208613874 95654128 760807424 0.1149276569 -0.0858917758 -0.3979955018 778 31.0800000000 0.0954656154 0.0265328810 0.0956051648 0.0091672492 0.0196190000 208614682 95654128 760807424 0.1169176921 -0.0851726681 -0.3983090520 779 31.1200000000 0.0948110223 0.0266205294 0.0956051648 0.0091801229 0.0195030000 208617490 95654128 760807424 0.1184999719 -0.0839179009 -0.3986335993 780 31.1600000000 0.0947569981 0.0267078839 0.0956051648 0.0092168877 0.0197350000 208620098 95654128 760807424 0.1184253916 -0.0825183988 -0.3989720047 781 31.2000000000 0.0941975340 0.0267942983 0.0956051648 0.0092569475 0.0196700000 208621106 95654128 760807424 0.1206829622 -0.0829530954 -0.3989436328 782 31.2400000000 0.0941638872 0.0268804486 0.0956051648 0.0092916613 0.0198800000 208623714 95654128 760807424 0.1216693521 -0.0825778991 -0.3994248211 783 31.2800000000 0.0938858315 0.0269660238 0.0956051648 0.0093241276 0.0198020000 208624722 95654128 760807424 0.1224169135 -0.0821501240 -0.3998166025 784 31.3200000000 0.0934510082 0.0270508261 0.0956051648 0.0093390100 0.0196560000 208627330 95654128 760807424 0.1234573200 -0.0820586607 -0.4003176391 785 31.3600000000 0.0929799005 0.0271348122 0.0956051648 0.0093369776 0.0195720000 208630138 95654128 760807424 0.1238874346 -0.0814350992 -0.4006077945 786 31.4000000000 0.0933546275 0.0272190613 0.0956051648 0.0093312889 0.0195730000 208630946 95654128 760807424 0.1243002191 -0.0805961415 -0.4013028741 787 31.4400000000 0.0953707099 0.0273056581 0.0956051648 0.0093334866 0.0198590000 208633754 95654128 760807424 0.1230675578 -0.0806063190 -0.4023022354 788 31.4800000000 0.0941630006 0.0273905024 0.0956051648 0.0093344079 0.0195630000 208636362 95654128 760807424 0.1246387213 -0.0790955201 -0.4027241766 789 31.5200000000 0.0935224593 0.0274743199 0.0956051648 0.0093389335 0.0194970000 208637370 95654128 760807424 0.1263138056 -0.0777747855 -0.4029783309 790 31.5600000000 0.0928614736 0.0275570884 0.0956051648 0.0093706151 0.0196080000 208639978 95654128 760807424 0.1285004318 -0.0773745999 -0.4030136764 791 31.6000000000 0.0940680429 0.0276411731 0.0956051648 0.0094121149 0.0195790000 208640986 95654128 760807424 0.1298725009 -0.0792116821 -0.4030281007 792 31.6400000000 0.0926282257 0.0277232274 0.0956051648 0.0094201653 0.0232150000 208643594 95654128 760807424 0.1316484660 -0.0773318708 -0.4030970633 793 31.6800000000 0.0930161551 0.0278055640 0.0956051648 0.0094314038 0.0197330000 208646402 95654128 760807424 0.1326528937 -0.0773741901 -0.4030782580 794 31.7200000000 0.0930513665 0.0278877376 0.0956051648 0.0094524833 0.0195730000 208647210 95654128 760807424 0.1336846948 -0.0763226077 -0.4039095342 795 31.7600000000 0.0935961306 0.0279703896 0.0956051648 0.0094868625 0.0199640000 208650018 95654128 760807424 0.1349943876 -0.0770601407 -0.4035143852 796 31.8000000000 0.0940307006 0.0280533800 0.0956051648 0.0095244323 0.0196090000 208650826 95654128 760807424 0.1359891444 -0.0770392120 -0.4035251141 797 31.8400000000 0.0943459794 0.0281365577 0.0956051648 0.0096146154 0.0196280000 208653634 95654128 760807424 0.1374154091 -0.0771358758 -0.4029740393 798 31.8800000000 0.0955276266 0.0282210076 0.0956051648 0.0097263634 0.0196690000 208656242 95654128 760807424 0.1371741146 -0.0779059380 -0.4038194418 799 31.9200000000 0.0973327160 0.0283075054 0.0973327160 0.0097888612 0.0196310000 208657250 95654128 760807424 0.1367374063 -0.0790094286 -0.4042209387 800 31.9600000000 0.0973729119 0.0283938371 0.0973729119 0.0098079520 0.0195440000 208659858 95654128 760807424 0.1374033988 -0.0786690190 -0.4049220979 801 32.0000000000 0.0981973112 0.0284809825 0.0981973112 0.0098137128 0.0196090000 208660866 95654128 760807424 0.1377761364 -0.0791473091 -0.4048117995 802 32.0400000000 0.0958733037 0.0285650129 0.0981973112 0.0098171961 0.0196730000 208663474 95654128 760807424 0.1401671916 -0.0775415897 -0.4030666351 803 32.0800000000 0.0952206552 0.0286480211 0.0981973112 0.0098162561 0.0232170000 208666282 95654128 760807424 0.1416258961 -0.0769458860 -0.4024281204 804 32.1199999990 0.0964906365 0.0287324025 0.0981973112 0.0098170582 0.0196740000 208667090 95654128 760807424 0.1413225383 -0.0773796961 -0.4026264250 805 32.1600000000 0.0971186087 0.0288173543 0.0981973112 0.0098201359 0.0195940000 208669898 95654128 760807424 0.1421470642 -0.0781289488 -0.4022564888 806 32.2000000000 0.0980325267 0.0289032292 0.0981973112 0.0098207789 0.0196550000 208672506 95654128 760807424 0.1417612433 -0.0784426704 -0.4020814598 807 32.2400000000 0.0970589966 0.0289876849 0.0981973112 0.0098165289 0.0235740000 208673514 95654128 760807424 0.1434979588 -0.0779220685 -0.4007211626 808 32.2800000000 0.0967916995 0.0290716008 0.0981973112 0.0098122707 0.0229630000 208676122 95654128 760807424 0.1445991248 -0.0779365599 -0.3996909261 809 32.3200000000 0.0974657238 0.0291561424 0.0981973112 0.0098089569 0.0197850000 208677130 95654128 760807424 0.1446083337 -0.0779588744 -0.3996494114 810 32.3600000000 0.0982402638 0.0292414314 0.0982402638 0.0098058529 0.0196670000 208679738 95654128 760807424 0.1442207247 -0.0780924931 -0.3999693692 811 32.4000000000 0.0988124460 0.0293272156 0.0988124460 0.0098002583 0.0205680000 208682546 95654128 760807424 0.1446815729 -0.0786227062 -0.3995562792 812 32.4399999990 0.0996927619 0.0294138727 0.0996927619 0.0097942516 0.0196700000 208683354 95654128 760807424 0.1450705528 -0.0796668157 -0.3986162841 813 32.4800000000 0.0985310078 0.0294988876 0.0996927619 0.0097893214 0.0235290000 208686162 95654128 760807424 0.1472070962 -0.0790993646 -0.3972365260 814 32.5200000000 0.0993982777 0.0295847591 0.0996927619 0.0097855299 0.0198430000 208686970 95654128 760807424 0.1478071213 -0.0802036822 -0.3967153132 815 32.5600000000 0.0990301445 0.0296699682 0.0996927619 0.0097869052 0.0197600000 208689778 95654128 760807424 0.1497823298 -0.0809044987 -0.3952018917 816 32.6000000000 0.0988302678 0.0297547235 0.0996927619 0.0097892809 0.0197540000 208692386 95654128 760807424 0.1509773880 -0.0807247013 -0.3946023285 817 32.6400000000 0.0979264826 0.0298381650 0.0996927619 0.0097916305 0.0198710000 208693394 95654128 760807424 0.1526264697 -0.0804540962 -0.3935090303 818 32.6800000000 0.0973088220 0.0299206475 0.0996927619 0.0097942433 0.0196980000 208696002 95654128 760807424 0.1545454711 -0.0809467435 -0.3914361298 819 32.7200000000 0.0976352617 0.0300033271 0.0996927619 0.0097963099 0.0196910000 208697010 95654128 760807424 0.1542272270 -0.0805457607 -0.3913522959 820 32.7599999990 0.0981263891 0.0300864040 0.0996927619 0.0097972508 0.0199750000 208699618 95654128 760807424 0.1553203762 -0.0822013766 -0.3899099231 821 32.7999999990 0.0984991044 0.0301697325 0.0996927619 0.0098004754 0.0196950000 208702426 95654128 760807424 0.1554777771 -0.0826455280 -0.3896597922 822 32.8400000000 0.0996729359 0.0302542863 0.0996927619 0.0098021480 0.0197540000 208703234 95654128 760807424 0.1550142914 -0.0843242705 -0.3889884055 823 32.8800000000 0.0999647826 0.0303389892 0.0999647826 0.0098117080 0.0197050000 208706042 95654128 760807424 0.1559254974 -0.0855389833 -0.3875009120 824 32.9200000000 0.1000164896 0.0304235493 0.1000164896 0.0098185480 0.0196790000 208708650 95654128 760807424 0.1569948494 -0.0870831087 -0.3859226108 825 32.9600000000 0.0986075625 0.0305061966 0.1000164896 0.0098331978 0.0198690000 208709658 95654128 760807424 0.1579393744 -0.0864057839 -0.3847618401 826 33.0000000000 0.0988606736 0.0305889502 0.1000164896 0.0098430385 0.0197090000 208712266 95654128 760807424 0.1583557725 -0.0872735381 -0.3836069405 827 33.0400000000 0.0985896140 0.0306711759 0.1000164896 0.0098466720 0.0196800000 208713274 95654128 760807424 0.1582337469 -0.0874560699 -0.3825474679 828 33.0800000000 0.0994759724 0.0307542735 0.1000164896 0.0098525919 0.0197150000 208715882 95654128 760807424 0.1580816507 -0.0892480612 -0.3820456266 829 33.1199999990 0.0986264944 0.0308361459 0.1000164896 0.0098622547 0.0197530000 208718690 95654128 760807424 0.1577133983 -0.0882080793 -0.3813911378 830 33.1600000000 0.1005110443 0.0309200915 0.1005110443 0.0098598406 0.0197010000 208719498 95654128 760807424 0.1586310565 -0.0914150774 -0.3796387017 831 33.2000000000 0.1007384211 0.0310041088 0.1007384211 0.0098640741 0.0237930000 208722306 95654128 760807424 0.1567435712 -0.0911123976 -0.3794903755 832 33.2400000000 0.1000474766 0.0310870936 0.1007384211 0.0098595533 0.0198640000 208723114 95654128 760807424 0.1555145532 -0.0896106660 -0.3794444501 833 33.2800000000 0.0998457447 0.0311696370 0.1007384211 0.0098545892 0.0199190000 208725922 95654128 760807424 0.1556475461 -0.0904568732 -0.3777189851 834 33.3200000000 0.1001314521 0.0312523250 0.1007384211 0.0098502373 0.0231770000 208728530 95654128 760807424 0.1550086290 -0.0905692503 -0.3771894574 835 33.3600000000 0.0996045992 0.0313341840 0.1007384211 0.0098445219 0.0197630000 208729538 95654128 760807424 0.1547929943 -0.0900595784 -0.3760574758 836 33.4000000000 0.0992253125 0.0314153935 0.1007384211 0.0098390032 0.0197080000 208732146 95654128 760807424 0.1551472545 -0.0911643878 -0.3736079335 837 33.4399999990 0.0992452577 0.0314964328 0.1007384211 0.0098342704 0.0198110000 208733154 95654128 760807424 0.1541315466 -0.0914052650 -0.3731771111 838 33.4800000000 0.0998624414 0.0315780151 0.1007384211 0.0098288353 0.0236160000 208735762 95654128 760807424 0.1543848813 -0.0931738466 -0.3711196780 839 33.5200000000 0.1003788337 0.0316600185 0.1007384211 0.0098230364 0.0198770000 208738570 95654128 760807424 0.1537702084 -0.0943538845 -0.3701052070 840 33.5600000000 0.0984607115 0.0317395431 0.1007384211 0.0098181112 0.0197060000 208739378 95654128 760807424 0.1529564559 -0.0931298435 -0.3689524829 841 33.6000000000 0.0994878486 0.0318201000 0.1007384211 0.0098140253 0.0197390000 208742186 95654128 760807424 0.1525724530 -0.0959848985 -0.3668455184 842 33.6400000000 0.1004861817 0.0319016511 0.1007384211 0.0098178686 0.0197570000 208744794 95654128 760807424 0.1517371684 -0.0977654681 -0.3662448823 843 33.6800000000 0.1000210643 0.0319824571 0.1007384211 0.0098193881 0.0198250000 208745802 95654128 760807424 0.1510364860 -0.0975272059 -0.3655010164 844 33.7200000000 0.1017481685 0.0320651179 0.1017481685 0.0098151356 0.0237890000 208748410 95654128 760807424 0.1503966451 -0.1004111618 -0.3641865551 845 33.7599999990 0.1012335345 0.0321469740 0.1017481685 0.0098154400 0.0199780000 208749418 95654128 760807424 0.1500955820 -0.1007135808 -0.3629679084 846 33.7999999990 0.1016088203 0.0322290802 0.1017481685 0.0098139714 0.0197600000 208752026 95654128 760807424 0.1500873864 -0.1016369313 -0.3610196710 847 33.8400000000 0.1028795466 0.0323124928 0.1028795466 0.0098092553 0.0198080000 208754834 95654128 760807424 0.1491315216 -0.1030029953 -0.3601965308 848 33.8800000000 0.1015289575 0.0323941160 0.1028795466 0.0098039074 0.0199070000 208758234 95654128 760807424 0.1478967071 -0.1014680937 -0.3597211540 849 33.9200000000 0.1019130722 0.0324759993 0.1028795466 0.0097983801 0.0197960000 208929794 95654128 760807424 0.1467972696 -0.1016535610 -0.3598429561 850 33.9600000000 0.1009438708 0.0325565497 0.1028795466 0.0097934374 0.0231760000 208930602 95654128 760807424 0.1461870819 -0.1009968147 -0.3581770957 851 34.0000000000 0.0989057943 0.0326345160 0.1028795466 0.0097894545 0.0198690000 208933410 95654128 760807424 0.1448950469 -0.0988698304 -0.3585538566 852 34.0400000000 0.0972224772 0.0327103234 0.1028795466 0.0097859194 0.0199940000 208936018 95654128 760807424 0.1430640072 -0.0970470831 -0.3592766225 853 34.0800000000 0.0974606127 0.0327862323 0.1028795466 0.0097834003 0.0198360000 208937026 95654128 760807424 0.1426615715 -0.0983589888 -0.3575780690 854 34.1199999990 0.0989744589 0.0328637361 0.1028795466 0.0097803445 0.0237390000 208939634 95654128 760807424 0.1419761181 -0.1009987146 -0.3559218645 855 34.1600000000 0.0999442041 0.0329421928 0.1028795466 0.0097759019 0.0200110000 208940642 95654128 760807424 0.1413327157 -0.1037561968 -0.3544726372 856 34.2000000000 0.1001837254 0.0330207460 0.1028795466 0.0097735668 0.0198400000 208943250 95654128 760807424 0.1405369192 -0.1049529910 -0.3537032604 857 34.2400000000 0.1001455560 0.0330990713 0.1028795466 0.0097737529 0.0198850000 208946058 95654128 760807424 0.1395751983 -0.1048254445 -0.3528756201 858 34.2800000000 0.0988499895 0.0331757041 0.1028795466 0.0097706056 0.0343800000 208946866 95654128 760807424 0.1388973743 -0.1041836292 -0.3523641527 859 34.3200000000 0.0978074893 0.0332509448 0.1028795466 0.0097704298 0.0214300000 208949674 95654128 760807424 0.1383730918 -0.1037780344 -0.3516679108 860 34.3600000000 0.0967007279 0.0333247236 0.1028795466 0.0097680268 0.0198570000 208952282 95654128 760807424 0.1375842690 -0.1025157943 -0.3512352407 861 34.4000000000 0.0964290649 0.0333980155 0.1028795466 0.0097628003 0.0198620000 208953290 95654128 760807424 0.1355908662 -0.1020379439 -0.3507376611 862 34.4400000000 0.0962165743 0.0334708909 0.1028795466 0.0097574059 0.0199070000 208958882 95654128 760807424 0.1337249428 -0.1015629247 -0.3501978815 863 34.4800000000 0.0944864452 0.0335415926 0.1028795466 0.0097526607 0.0280110000 209128646 95654128 760807424 0.1317717135 -0.0988750905 -0.3499953747 864 34.5200000000 0.0929566473 0.0336103600 0.1028795466 0.0097472916 0.0207440000 209131254 95654128 760807424 0.1302676946 -0.0967610478 -0.3494928479 865 34.5600000000 0.0937845334 0.0336799255 0.1028795466 0.0097442646 0.0199570000 209134062 95654128 760807424 0.1292013824 -0.0986039713 -0.3466633856 866 34.6000000000 0.0939862803 0.0337495633 0.1028795466 0.0097387995 0.0199860000 209134870 95654128 760807424 0.1272504628 -0.0991504937 -0.3445471227 867 34.6400000000 0.0954058096 0.0338206778 0.1028795466 0.0097336031 0.0198530000 209137678 95654128 760807424 0.1256313324 -0.1002049595 -0.3437699974 868 34.6800000000 0.0954708308 0.0338917033 0.1028795466 0.0097300877 0.0198940000 209138486 95654128 760807424 0.1232869104 -0.0996028632 -0.3423441052 869 34.7200000000 0.0975672305 0.0339649778 0.1028795466 0.0097297350 0.0199510000 209141294 95654128 760807424 0.1220688745 -0.1016998142 -0.3402116895 870 34.7600000000 0.0981347412 0.0340387362 0.1028795466 0.0097327853 0.0199630000 209143902 95654128 760807424 0.1203396842 -0.1021561995 -0.3382941782 871 34.8000000000 0.0983181447 0.0341125357 0.1028795466 0.0097359823 0.0200130000 209144910 95654128 760807424 0.1182873026 -0.1031691357 -0.3361083567 872 34.8400000000 0.0967278630 0.0341843423 0.1028795466 0.0097306013 0.0239680000 209147518 95654128 760807424 0.1151916757 -0.1018146649 -0.3334573209 873 34.8800000000 0.0988338664 0.0342583967 0.1028795466 0.0097280471 0.0201670000 209148526 95654128 760807424 0.1129500344 -0.1031355560 -0.3306738734 874 34.9200000000 0.0990756899 0.0343325584 0.1028795466 0.0097230917 0.0200550000 209151134 95654128 760807424 0.1107939556 -0.1023425981 -0.3287564814 875 34.9600000000 0.1001777723 0.0344078101 0.1028795466 0.0097302207 0.0201900000 209153942 95654128 760807424 0.1079819724 -0.1035589874 -0.3252496123 876 35.0000000000 0.0997720733 0.0344824268 0.1028795466 0.0097310400 0.0200170000 209154750 95654128 760807424 0.1058788076 -0.1030382514 -0.3236620724 877 35.0400000000 0.1003062725 0.0345574825 0.1028795466 0.0097324723 0.0200950000 209159554 95654128 760807424 0.1036137938 -0.1031785831 -0.3217372596 878 35.0800000000 0.0996328518 0.0346316002 0.1028795466 0.0097373100 0.0200540000 209330858 95654128 760807424 0.1004227623 -0.1026358753 -0.3194743395 879 35.1200000000 0.0994790494 0.0347053744 0.1028795466 0.0097351623 0.0200780000 209331866 95654128 760807424 0.0983108133 -0.1021607369 -0.3178298473 880 35.1600000000 0.1002362594 0.0347798413 0.1028795466 0.0097436054 0.0201090000 209334474 95654128 760807424 0.0954876393 -0.1018644571 -0.3163262606 881 35.2000000000 0.0984340236 0.0348520935 0.1028795466 0.0097585241 0.0200460000 209335482 95654128 760807424 0.0928447247 -0.1003002301 -0.3138538599 882 35.2400000000 0.0976492241 0.0349232920 0.1028795466 0.0097594762 0.0228940000 209338090 95654128 760807424 0.0901978761 -0.0997203514 -0.3110751510 883 35.2800000000 0.0980864018 0.0349948244 0.1028795466 0.0097550609 0.0201420000 209340898 95654128 760807424 0.0876991004 -0.0998564437 -0.3105799258 884 35.3200000000 0.0984126255 0.0350665640 0.1028795466 0.0097509152 0.0201920000 209341706 95654128 760807424 0.0845518187 -0.0990134627 -0.3093392253 885 35.3600000000 0.0993391499 0.0351391884 0.1028795466 0.0097484920 0.0201200000 209344514 95654128 760807424 0.0821298659 -0.0998962224 -0.3067200184 886 35.4000000000 0.1002046987 0.0352126258 0.1028795466 0.0097443112 0.0201590000 209345322 95654128 760807424 0.0796370804 -0.1009907350 -0.3049212396 887 35.4400000000 0.1002865732 0.0352859899 0.1028795466 0.0097392114 0.0236080000 209348130 95654128 760807424 0.0764171928 -0.1007546782 -0.3037751019 888 35.4800000000 0.0998067707 0.0353586484 0.1028795466 0.0097339682 0.0202110000 209350738 95654128 760807424 0.0734934062 -0.1001722515 -0.3019286990 889 35.5200000000 0.1006997377 0.0354321479 0.1028795466 0.0097290120 0.0208810000 209351746 95654128 760807424 0.0708386675 -0.1008312777 -0.2993225455 890 35.5600000000 0.0992400497 0.0355038422 0.1028795466 0.0097246717 0.0202720000 209354354 95654128 760807424 0.0685446113 -0.0986837074 -0.2977795005 891 35.6000000000 0.1003725678 0.0355766466 0.1028795466 0.0097196110 0.0202320000 209355362 95654128 760807424 0.0666217804 -0.0989091545 -0.2977393568 892 35.6400000000 0.1004712358 0.0356493984 0.1028795466 0.0097142786 0.0202840000 209357970 95654128 760807424 0.0642096177 -0.0982092395 -0.2976204157 893 35.6800000000 0.1004132405 0.0357219223 0.1028795466 0.0097090476 0.0204220000 209360778 95654128 760807424 0.0619052500 -0.0979337394 -0.2954635620 894 35.7200000000 0.0998788103 0.0357936862 0.1028795466 0.0097038367 0.0203700000 209361586 95654128 760807424 0.0596525408 -0.0969405398 -0.2940492928 895 35.7600000000 0.0994408280 0.0358648003 0.1028795466 0.0096991287 0.0202470000 209364394 95654128 760807424 0.0572868697 -0.0961206481 -0.2928566039 896 35.8000000000 0.0992268920 0.0359355169 0.1028795466 0.0096940822 0.0202150000 209367002 95654128 760807424 0.0549739040 -0.0952627510 -0.2933795452 897 35.8400000000 0.0995285287 0.0360064121 0.1028795466 0.0096887469 0.0242120000 209368010 95654128 760807424 0.0529184006 -0.0947926641 -0.2936425805 898 35.8800000000 0.1003587544 0.0360780740 0.1028795466 0.0096837106 0.0203830000 209370618 95654128 760807424 0.0508523844 -0.0947312862 -0.2938261628 899 35.9200000000 0.1003938615 0.0361496154 0.1028795466 0.0096789803 0.0203260000 209371626 95654128 760807424 0.0485688113 -0.0943798870 -0.2939916253 900 35.9600000000 0.1008865610 0.0362215454 0.1028795466 0.0096739367 0.0204440000 209376914 95654128 760807424 0.0464065783 -0.0950936377 -0.2941882908 901 36.0000000000 0.1004782245 0.0362928625 0.1028795466 0.0096701372 0.0202980000 209548430 95654128 760807424 0.0444994643 -0.0943912640 -0.2947103679 902 36.0400000000 0.1012036279 0.0363648256 0.1028795466 0.0096649178 0.0250460000 209549238 95654128 760807424 0.0421691984 -0.0946718901 -0.2950667739 903 36.0800000000 0.1006207466 0.0364359839 0.1028795466 0.0096597826 0.0206080000 209552046 95654128 760807424 0.0397949480 -0.0941481218 -0.2947452068 904 36.1200000000 0.1003164425 0.0365066481 0.1028795466 0.0096546626 0.0210350000 209552854 95654128 760807424 0.0377952084 -0.0940662622 -0.2941447794 905 36.1600000000 0.0993683860 0.0365761086 0.1028795466 0.0096498295 0.0242830000 209555662 95654128 760807424 0.0354444422 -0.0926671475 -0.2933918834 906 36.2000000000 0.0996203348 0.0366456938 0.1028795466 0.0096476678 0.0203810000 209558270 95654128 760807424 0.0331769139 -0.0934072807 -0.2922978699 907 36.2400000000 0.1008135602 0.0367164412 0.1028795466 0.0096438062 0.0202380000 209559278 95654128 760807424 0.0312035475 -0.0940781757 -0.2956767380 908 36.2800000000 0.1013722420 0.0367876480 0.1028795466 0.0096385793 0.0202720000 209561886 95654128 760807424 0.0291170031 -0.0943967998 -0.2977361381 909 36.3200000000 0.1015676335 0.0368589131 0.1028795466 0.0096333176 0.0203420000 209562894 95654128 760807424 0.0267504305 -0.0948522910 -0.2972241938 910 36.3600000000 0.1007113233 0.0369290806 0.1028795466 0.0096282367 0.0203930000 209565502 95654128 760807424 0.0239225421 -0.0937471762 -0.2968998849 911 36.4000000000 0.1005255058 0.0369988901 0.1028795466 0.0096234025 0.0203510000 209568310 95654128 760807424 0.0213400144 -0.0940958038 -0.2966487706 912 36.4400000000 0.1015389636 0.0370696577 0.1028795466 0.0096182103 0.0239110000 209569118 95654128 760807424 0.0192087721 -0.0947479010 -0.2974687815 913 36.4800000000 0.1010373309 0.0371397209 0.1028795466 0.0096133822 0.0203950000 209571926 95654128 760807424 0.0166534502 -0.0938102305 -0.2974531949 914 36.5200000000 0.1008328646 0.0372094070 0.1028795466 0.0096098611 0.0202680000 209574534 95654128 760807424 0.0141086346 -0.0933931395 -0.2984772623 915 36.5600000000 0.1008433700 0.0372789524 0.1028795466 0.0096066468 0.0202730000 209575542 95654128 760807424 0.0118129477 -0.0936473534 -0.2989028990 916 36.6000000000 0.1002469808 0.0373476947 0.1028795466 0.0096016930 0.0203380000 209578150 95654128 760807424 0.0097320741 -0.0937962607 -0.2973564863 917 36.6400000000 0.1007297188 0.0374168136 0.1028795466 0.0095967663 0.0203250000 209579158 95654128 760807424 0.0075240359 -0.0942531824 -0.2996143103 918 36.6800000000 0.1004410312 0.0374854675 0.1028795466 0.0095915635 0.0203110000 209581766 95654128 760807424 0.0048904493 -0.0943127945 -0.2983256280 919 36.7200000000 0.0998615250 0.0375533413 0.1028795466 0.0095864112 0.0203690000 209584574 95654128 760807424 0.0025144124 -0.0938109905 -0.2968861461 920 36.7600000000 0.1002201810 0.0376214574 0.1028795466 0.0095814150 0.0202980000 209585382 95654128 760807424 0.0003795712 -0.0942922458 -0.2971327007 921 36.8000000000 0.0998494849 0.0376890232 0.1028795466 0.0095762333 0.0203120000 209588190 95654128 760807424 -0.0010448813 -0.0934622586 -0.2978104055 922 36.8400000000 0.0982691944 0.0377547283 0.1028795466 0.0095719509 0.0246060000 209588998 95654128 760807424 -0.0032538557 -0.0917844996 -0.2954615355 923 36.8800000000 0.0979456231 0.0378199406 0.1028795466 0.0095682687 0.0204710000 209591806 95654128 760807424 -0.0048632855 -0.0913414359 -0.2951673269 924 36.9200000000 0.0966987684 0.0378836622 0.1028795466 0.0095660522 0.0203220000 209594414 95654128 760807424 -0.0068807760 -0.0905757099 -0.2939988375 925 36.9600000000 0.0962908044 0.0379468051 0.1028795466 0.0095615521 0.0202630000 209595422 95654128 760807424 -0.0086712856 -0.0901344866 -0.2942196727 926 37.0000000000 0.0959608480 0.0380094553 0.1028795466 0.0095564742 0.0242570000 209600530 95654128 760807424 -0.0096177068 -0.0893309563 -0.2948383391 927 37.0400000000 0.0956718549 0.0380716585 0.1028795466 0.0095523475 0.0204870000 209770350 95654128 760807424 -0.0107115377 -0.0892832950 -0.2937823236 928 37.0800000000 0.0957763419 0.0381338403 0.1028795466 0.0095486770 0.0203020000 209772958 95654128 760807424 -0.0117329573 -0.0884545892 -0.2935877144 929 37.1200000000 0.0947362632 0.0381947686 0.1028795466 0.0095489810 0.0203110000 209775766 95654128 760807424 -0.0135141071 -0.0873586535 -0.2920452058 930 37.1600000000 0.0943607241 0.0382551621 0.1028795466 0.0095486273 0.0241740000 209776574 95654128 760807424 -0.0143458983 -0.0867460445 -0.2917316258 931 37.2000000000 0.0945145711 0.0383155911 0.1028795466 0.0095464127 0.0204270000 209779382 95654128 760807424 -0.0149480402 -0.0866305679 -0.2914813161 932 37.2400000000 0.0943375081 0.0383757005 0.1028795466 0.0095430808 0.0262180000 209781990 95654128 760807424 -0.0155724725 -0.0861744061 -0.2916279435 933 37.2800000000 0.0926910266 0.0384339162 0.1028795466 0.0095399263 0.0241940000 209782998 95654128 760807424 -0.0162365437 -0.0841762722 -0.2905447483 934 37.3200000000 0.0920869559 0.0384913606 0.1028795466 0.0095374665 0.0204100000 209785606 95654128 760807424 -0.0166989211 -0.0828844309 -0.2898783088 935 37.3600000000 0.0926519856 0.0385492864 0.1028795466 0.0095373597 0.0203060000 209786614 95654128 760807424 -0.0170142464 -0.0835100114 -0.2887613773 936 37.4000000000 0.0922777727 0.0386066886 0.1028795466 0.0095361388 0.0208450000 209789222 95654128 760807424 -0.0176728889 -0.0830869377 -0.2881354988 937 37.4400000000 0.0917063951 0.0386633586 0.1028795466 0.0095323795 0.0238350000 209792030 95654128 760807424 -0.0177529100 -0.0827196762 -0.2875729799 938 37.4800000000 0.0920036510 0.0387202245 0.1028795466 0.0095286816 0.0204950000 209792838 95654128 760807424 -0.0175787192 -0.0833341479 -0.2871628106 939 37.5200000000 0.0923851356 0.0387773757 0.1028795466 0.0095242118 0.0203800000 209795646 95654128 760807424 -0.0174357351 -0.0831866711 -0.2885346115 940 37.5600000000 0.0918642953 0.0388338511 0.1028795466 0.0095200088 0.0203490000 209796454 95654128 760807424 -0.0172469001 -0.0826014280 -0.2879565954 941 37.6000000000 0.0923897624 0.0388907649 0.1028795466 0.0095167174 0.0203990000 209799262 95654128 760807424 -0.0175188351 -0.0830707103 -0.2863772213 942 37.6400000000 0.0919304490 0.0389470703 0.1028795466 0.0095144426 0.0237850000 209801870 95654128 760807424 -0.0175949037 -0.0820300654 -0.2864619195 943 37.6800000000 0.0915563181 0.0390028596 0.1028795466 0.0095131001 0.0243370000 209802878 95654128 760807424 -0.0171192158 -0.0816756114 -0.2861619592 944 37.7200000000 0.0916478038 0.0390586275 0.1028795466 0.0095105049 0.0205220000 209805486 95654128 760807424 -0.0171488952 -0.0815373957 -0.2853445113 945 37.7600000000 0.0919207111 0.0391145662 0.1028795466 0.0095068787 0.0203640000 209806494 95654128 760807424 -0.0167542249 -0.0810221881 -0.2873888612 946 37.8000000000 0.0911536217 0.0391695758 0.1028795466 0.0095040145 0.0203300000 209809102 95654128 760807424 -0.0167430080 -0.0803682730 -0.2864335179 947 37.8400000000 0.0909543708 0.0392242588 0.1028795466 0.0094999607 0.0204110000 209811910 95654128 760807424 -0.0163474493 -0.0801420510 -0.2857315838 948 37.8800000000 0.0914584994 0.0392793582 0.1028795466 0.0094975060 0.0242190000 209812718 95654128 760807424 -0.0166353863 -0.0802397355 -0.2862372100 949 37.9200000000 0.0905335620 0.0393333669 0.1028795466 0.0094948127 0.0204710000 209815526 95654128 760807424 -0.0167270042 -0.0788361058 -0.2865190506 950 37.9600000000 0.0905110613 0.0393872381 0.1028795466 0.0094906126 0.0203760000 209818134 95654128 760807424 -0.0163652264 -0.0780459866 -0.2878987491 951 38.0000000000 0.0906358436 0.0394411273 0.1028795466 0.0094863674 0.0211870000 209819142 95654128 760807424 -0.0160429776 -0.0775143057 -0.2892692089 952 38.0400000000 0.0899728835 0.0394942069 0.1028795466 0.0094835122 0.0235280000 209821750 95654128 760807424 -0.0160310175 -0.0763866678 -0.2894765437 953 38.0800000000 0.0899069980 0.0395471059 0.1028795466 0.0094792513 0.0204590000 209822758 95654128 760807424 -0.0155489231 -0.0761369690 -0.2896896899 954 38.1200000000 0.0892867148 0.0395992439 0.1028795466 0.0094744392 0.0243500000 209825366 95654128 760807424 -0.0153088085 -0.0748335645 -0.2904481292 955 38.1600000000 0.0891529471 0.0396511326 0.1028795466 0.0094702544 0.0205830000 209828174 95654128 760807424 -0.0148675358 -0.0751496330 -0.2893730402 956 38.2000000000 0.0887793377 0.0397025219 0.1028795466 0.0094653973 0.0204100000 209828982 95654128 760807424 -0.0145548834 -0.0742681399 -0.2898733616 957 38.2400000000 0.0895931721 0.0397546542 0.1028795466 0.0094606016 0.0204780000 209831790 95654128 760807424 -0.0140433591 -0.0747856498 -0.2917768657 958 38.2800000000 0.0898613781 0.0398069577 0.1028795466 0.0094559060 0.0204570000 209832598 95654128 760807424 -0.0135070151 -0.0744433850 -0.2931122184 959 38.3200000000 0.0897009969 0.0398589849 0.1028795466 0.0094510628 0.0204550000 209835406 95654128 760807424 -0.0130624501 -0.0744385570 -0.2930135727 960 38.3600000000 0.0888521895 0.0399100194 0.1028795466 0.0094470323 0.0203770000 209838014 95654128 760807424 -0.0128314914 -0.0732947960 -0.2931837142 961 38.4000000000 0.0876959786 0.0399597447 0.1028795466 0.0094424204 0.0204180000 209839022 95654128 760807424 -0.0128377005 -0.0721017197 -0.2925717831 962 38.4400000000 0.0880055130 0.0400096883 0.1028795466 0.0094377637 0.0240670000 209841630 95654128 760807424 -0.0123299100 -0.0718902946 -0.2940444052 963 38.4800000000 0.0881775096 0.0400597068 0.1028795466 0.0094331186 0.0205610000 209842638 95654128 760807424 -0.0116417529 -0.0717522800 -0.2955762744 964 38.5200000000 0.0878454521 0.0401092771 0.1028795466 0.0094283262 0.0204380000 209845246 95654128 760807424 -0.0109431278 -0.0712273419 -0.2957725525 965 38.5600000000 0.0877266526 0.0401586215 0.1028795466 0.0094234965 0.0204280000 209848054 95654128 760807424 -0.0105433362 -0.0707860216 -0.2964157462 966 38.6000000000 0.0879696757 0.0402081154 0.1028795466 0.0094186706 0.0204260000 209848862 95654128 760807424 -0.0101700388 -0.0707798153 -0.2973088920 967 38.6400000000 0.0858840942 0.0402553501 0.1028795466 0.0094140415 0.0204460000 209851670 95654128 760807424 -0.0103467284 -0.0692726970 -0.2951896489 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:26:31 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0407240000 198579072 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0026371528 0.0013185764 0.0026371528 0.0017031863 0.0206450000 199227978 95654128 760807424 -0.0024932427 -0.0007044431 0.0006994744 3 0.0800000000 0.0100871567 0.0042414365 0.0100871567 0.0039453144 0.0159790000 199077774 95654128 760807424 -0.0044113910 -0.0079503814 0.0020711878 4 0.1200000000 0.0064609488 0.0047963146 0.0100871567 0.0045198247 0.0169530000 199078438 95654128 760807424 -0.0073308754 -0.0036204318 0.0007240017 5 0.1600000000 0.0057110265 0.0049792570 0.0100871567 0.0042706688 0.0160670000 199081730 95654128 760807424 -0.0100553054 -0.0022949593 0.0015700991 6 0.2000000000 0.0112805627 0.0060294746 0.0112805627 0.0041732509 0.0160100000 199083338 95654128 760807424 -0.0072992113 -0.0091361767 0.0032450091 7 0.2400000000 0.0135540208 0.0071044098 0.0135540208 0.0039259674 0.0160130000 199085946 95654128 760807424 -0.0089091705 -0.0113498140 0.0037236330 8 0.2800000000 0.0107231289 0.0075567497 0.0135540208 0.0037343884 0.0161520000 199088554 95654128 760807424 -0.0096100438 -0.0084813563 0.0030573488 9 0.3200000000 0.0097235013 0.0077974998 0.0135540208 0.0035714156 0.0160710000 199090266 95654128 760807424 -0.0101317223 -0.0085724834 0.0021830453 10 0.3600000000 0.0067283097 0.0076905808 0.0135540208 0.0034787580 0.0160490000 199094474 95654128 760807424 -0.0100675877 -0.0046240999 0.0014621485 11 0.4000000000 0.0064338772 0.0075763350 0.0135540208 0.0038185849 0.0160070000 199097082 95654128 760807424 -0.0118880654 -0.0051044086 0.0014768707 12 0.4400000000 0.0055728490 0.0074093779 0.0135540208 0.0037261660 0.0159810000 199098022 95654128 760807424 -0.0098036425 -0.0047088633 0.0001410431 13 0.4800000000 0.0088175200 0.0075176965 0.0135540208 0.0035711982 0.0159570000 199100830 95654128 760807424 -0.0071352324 -0.0061654276 -0.0000742798 14 0.5200000000 0.0092213796 0.0076393881 0.0135540208 0.0034565984 0.0160280000 199103438 95654128 760807424 -0.0065823053 -0.0051982040 -0.0007044386 15 0.5600000000 0.0108876443 0.0078559385 0.0135540208 0.0033434001 0.0160550000 199104246 95654128 760807424 -0.0089444770 -0.0056892172 0.0006350941 16 0.6000000000 0.0184974466 0.0085210328 0.0184974466 0.0034223249 0.0160380000 199106854 95654128 760807424 -0.0084662288 -0.0161986072 0.0018946307 17 0.6400000000 0.0161478408 0.0089696686 0.0184974466 0.0034379325 0.0160360000 199109270 95654128 760807424 -0.0113789421 -0.0153486151 0.0001675033 18 0.6800000000 0.0221328847 0.0097009583 0.0221328847 0.0034413521 0.0159690000 199115078 95654128 760807424 -0.0084276451 -0.0197052192 0.0019852838 19 0.7200000000 0.0201055091 0.0102485663 0.0221328847 0.0034966226 0.0160110000 199117686 95654128 760807424 -0.0103541492 -0.0174598750 0.0006507002 20 0.7600000000 0.0215131119 0.0108117936 0.0221328847 0.0034549391 0.0159970000 199118494 95654128 760807424 -0.0144756893 -0.0206799004 0.0013912533 21 0.8000000000 0.0267535094 0.0115709229 0.0267535094 0.0034232776 0.0160320000 199121434 95654128 760807424 -0.0124407895 -0.0230992008 0.0020042015 22 0.8400000000 0.0300625525 0.0124114515 0.0300625525 0.0034358628 0.0167270000 199123962 95654128 760807424 -0.0136958817 -0.0249262918 0.0017657080 23 0.8800000000 0.0304828174 0.0131971631 0.0304828174 0.0033707266 0.0162290000 199124770 95654128 760807424 -0.0125416974 -0.0257448442 0.0012449664 24 0.9200000000 0.0266937762 0.0137595220 0.0304828174 0.0033523162 0.0159670000 199127378 95654128 760807424 -0.0233151205 -0.0214212872 -0.0001865282 25 0.9600000000 0.0255954564 0.0142329593 0.0304828174 0.0033549478 0.0159780000 199130186 95654128 760807424 -0.0254838523 -0.0196202770 -0.0012257308 26 1.0000000000 0.0262101721 0.0146936214 0.0304828174 0.0033388963 0.0159550000 199130978 95654128 760807424 -0.0275975335 -0.0184477344 -0.0018390665 27 1.0400000000 0.0282834247 0.0151969474 0.0304828174 0.0033520922 0.0159070000 199133586 95654128 760807424 -0.0316985361 -0.0205885638 -0.0045927404 28 1.0800000000 0.0305297207 0.0157445465 0.0305297207 0.0034793504 0.0159390000 199136194 95654128 760807424 -0.0358802713 -0.0213602856 -0.0044593825 29 1.1200000000 0.0339501053 0.0163723243 0.0339501053 0.0036339901 0.0158590000 199137186 95654128 760807424 -0.0404079594 -0.0243348610 -0.0062383506 30 1.1600000000 0.0291963574 0.0167997921 0.0339501053 0.0035759123 0.0158980000 199139794 95654128 760807424 -0.0525395013 -0.0210875701 -0.0058968780 31 1.2000000000 0.0292491298 0.0172013837 0.0339501053 0.0035550944 0.0159010000 199140602 95654128 760807424 -0.0606839880 -0.0219500642 -0.0075829071 32 1.2400000000 0.0368122123 0.0178142220 0.0368122123 0.0037163267 0.0158900000 199143194 95654128 760807424 -0.0651723817 -0.0291861705 -0.0077604186 33 1.2800000000 0.0385045856 0.0184412028 0.0385045856 0.0037402297 0.0159320000 199148818 95654128 760807424 -0.0739758089 -0.0334096737 -0.0069114752 34 1.3200000000 0.0443853512 0.0192042660 0.0443853512 0.0036837435 0.0159330000 199156026 95654128 760807424 -0.0963910222 -0.0375464298 -0.0077222171 35 1.3600000000 0.0455008969 0.0199555983 0.0455008969 0.0039882530 0.0159710000 199158634 95654128 760807424 -0.0996186063 -0.0378845297 -0.0094717909 36 1.4000000000 0.0498891622 0.0207870862 0.0498891622 0.0044568925 0.0159420000 199161242 95654128 760807424 -0.1033664122 -0.0407271981 -0.0092919013 37 1.4400000000 0.0451959893 0.0214467862 0.0498891622 0.0044029887 0.0160010000 199162250 95654128 760807424 -0.1190132201 -0.0400445610 -0.0079860128 38 1.4800000000 0.0401330516 0.0219385301 0.0498891622 0.0043645940 0.0159700000 199164858 95654128 760807424 -0.1316675544 -0.0354127996 -0.0086453594 39 1.5200000000 0.0445632786 0.0225186518 0.0498891622 0.0043248721 0.0159620000 199167466 95654128 760807424 -0.1333151758 -0.0401661620 -0.0109468000 40 1.5600000000 0.0437998213 0.0230506811 0.0498891622 0.0042861562 0.0159400000 199168274 95654128 760807424 -0.1433345079 -0.0410356186 -0.0106800487 41 1.6000000000 0.0411494300 0.0234921140 0.0498891622 0.0042782106 0.0159190000 199171082 95654128 760807424 -0.1528392136 -0.0386657938 -0.0102921370 42 1.6400000000 0.0409626886 0.0239080800 0.0498891622 0.0042340001 0.0159390000 199171874 95654128 760807424 -0.1638475806 -0.0354125202 -0.0089674443 43 1.6800000000 0.0468040891 0.0244405453 0.0498891622 0.0041861622 0.0160120000 199174482 95654128 760807424 -0.1660161018 -0.0388228074 -0.0061789160 44 1.7200000000 0.0467707962 0.0249480510 0.0498891622 0.0042398200 0.0159600000 199177090 95654128 760807424 -0.1744252145 -0.0411150344 -0.0081031583 45 1.7600000000 0.0487261266 0.0254764527 0.0498891622 0.0042190690 0.0159840000 199178098 95654128 760807424 -0.1805272251 -0.0397668295 -0.0044525415 46 1.8000000000 0.0520135835 0.0260533469 0.0520135835 0.0042118306 0.0159830000 199180706 95654128 760807424 -0.1862655431 -0.0430259742 -0.0030282736 47 1.8400000000 0.0565873794 0.0267030071 0.0565873794 0.0042820581 0.0160050000 199183314 95654128 760807424 -0.1885485202 -0.0498375222 -0.0023084194 48 1.8800000000 0.0554225184 0.0273013303 0.0565873794 0.0042854743 0.0159690000 199184122 95654128 760807424 -0.1914724410 -0.0477676280 -0.0027554715 49 1.9200000000 0.0483129695 0.0277301393 0.0565873794 0.0042682016 0.0160990000 199186914 95654128 760807424 -0.2044636309 -0.0420439988 -0.0029993788 50 1.9600000000 0.0523277111 0.0282220907 0.0565873794 0.0043016589 0.0160330000 199189522 95654128 760807424 -0.2198711485 -0.0476021133 0.0030661807 51 2.0000000000 0.0551811308 0.0287506993 0.0565873794 0.0042826216 0.0160210000 199190330 95654128 760807424 -0.2205468863 -0.0518686995 0.0026909725 52 2.0400000000 0.0543477423 0.0292429501 0.0565873794 0.0042581275 0.0160370000 199192938 95654128 760807424 -0.2259499431 -0.0512978509 0.0013571766 53 2.0800000000 0.0559523962 0.0297469020 0.0565873794 0.0042408414 0.0160280000 199193946 95654128 760807424 -0.2260720134 -0.0546129644 -0.0018534213 54 2.1200000000 0.0523760021 0.0301659594 0.0565873794 0.0043400761 0.0160410000 199196554 95654128 760807424 -0.2362338901 -0.0508757904 0.0012660869 55 2.1600000000 0.0485463627 0.0305001485 0.0565873794 0.0044554986 0.0160160000 199199162 95654128 760807424 -0.2405269146 -0.0468673594 0.0009123727 56 2.2000000000 0.0451576672 0.0307618899 0.0565873794 0.0044742369 0.0160570000 199199954 95654128 760807424 -0.2592192590 -0.0417556688 0.0075114649 57 2.2400000000 0.0508189760 0.0311137686 0.0565873794 0.0044358958 0.0161000000 199202762 95654128 760807424 -0.2602382302 -0.0485637523 0.0097371116 58 2.2800000000 0.0468818732 0.0313856325 0.0565873794 0.0044001407 0.0160540000 199205370 95654128 760807424 -0.2727861106 -0.0466389991 0.0125466678 59 2.3200000000 0.0442872234 0.0316043035 0.0565873794 0.0044663539 0.0160730000 199206178 95654128 760807424 -0.2857498229 -0.0402964838 0.0163461398 60 2.3600000000 0.0485905334 0.0318874074 0.0565873794 0.0045760313 0.0161010000 199208786 95654128 760807424 -0.2868021131 -0.0457538813 0.0162637495 61 2.4000000000 0.0447512046 0.0320982893 0.0565873794 0.0046434365 0.0161000000 199211594 95654128 760807424 -0.2957808375 -0.0441492721 0.0149550457 62 2.4400000000 0.0414042212 0.0322483850 0.0565873794 0.0047900349 0.0161340000 199212402 95654128 760807424 -0.3189317882 -0.0386375673 0.0220509917 63 2.4800000000 0.0382823087 0.0323441615 0.0565873794 0.0049157183 0.0160790000 199215010 95654128 760807424 -0.3292100728 -0.0370469950 0.0239451472 64 2.5200000000 0.0343676023 0.0323757778 0.0565873794 0.0051400845 0.0161050000 199217618 95654128 760807424 -0.3423811793 -0.0307294503 0.0270876922 65 2.5600000000 0.0314134359 0.0323609725 0.0565873794 0.0053341422 0.0161680000 199225094 95654128 760807424 -0.3591589332 -0.0297854170 0.0311558284 66 2.6000000000 0.0322691575 0.0323595814 0.0565873794 0.0054796355 0.0161130000 199409130 95654128 760807424 -0.3703802526 -0.0302785095 0.0338467099 67 2.6400000000 0.0315576419 0.0323476121 0.0565873794 0.0055430199 0.0161370000 199409938 95654128 760807424 -0.3803149760 -0.0264058188 0.0355307348 68 2.6800000000 0.0313157849 0.0323324382 0.0565873794 0.0055235149 0.0161910000 199412546 95654128 760807424 -0.3911168277 -0.0258213263 0.0339615494 69 2.7200000000 0.0263048597 0.0322450820 0.0565873794 0.0055049140 0.0161470000 199415354 95654128 760807424 -0.4018940628 -0.0185064655 0.0364764482 70 2.7600000000 0.0235799700 0.0321212947 0.0565873794 0.0054879489 0.0161370000 199416162 95654128 760807424 -0.4134708047 -0.0157558955 0.0363230556 71 2.8000000000 0.0262276791 0.0320382860 0.0565873794 0.0055144253 0.0170570000 199418770 95654128 760807424 -0.4189737439 -0.0175977964 0.0338540338 72 2.8400000000 0.0289597157 0.0319955281 0.0565873794 0.0061710784 0.0162770000 199421394 95654128 760807424 -0.4334383607 -0.0148553653 0.0370378457 73 2.8800000000 0.0284570716 0.0319470561 0.0565873794 0.0062427337 0.0162000000 199422402 95654128 760807424 -0.4443531036 -0.0137336301 0.0382776745 74 2.9200000000 0.0275675729 0.0318878739 0.0565873794 0.0063211064 0.0162290000 199425010 95654128 760807424 -0.4466990232 -0.0110744257 0.0360629447 75 2.9600000000 0.0274368692 0.0318285272 0.0565873794 0.0063789857 0.0162330000 199427618 95654128 760807424 -0.4506964982 -0.0102010854 0.0351960622 76 3.0000000000 0.0321612656 0.0318329053 0.0565873794 0.0064126781 0.0162310000 199428426 95654128 760807424 -0.4508700073 -0.0144840386 0.0302572101 77 3.0400000000 0.0329811797 0.0318478180 0.0565873794 0.0064107041 0.0162130000 199431218 95654128 760807424 -0.4512129426 -0.0149901342 0.0242106579 78 3.0800000000 0.0366987474 0.0319100094 0.0565873794 0.0063815430 0.0163700000 199432026 95654128 760807424 -0.4506838322 -0.0183871873 0.0185859352 79 3.1200000000 0.0387896895 0.0319970939 0.0565873794 0.0063489500 0.0162470000 199434634 95654128 760807424 -0.4562318921 -0.0169873573 0.0165847540 80 3.1600000000 0.0439270549 0.0321462184 0.0565873794 0.0063360993 0.0162380000 199437242 95654128 760807424 -0.4598583579 -0.0196885280 0.0143181216 81 3.2000000000 0.0395911373 0.0322381310 0.0565873794 0.0063086925 0.0162580000 199438250 95654128 760807424 -0.4700203538 -0.0153068304 0.0148813101 82 3.2400000000 0.0390609652 0.0323213363 0.0565873794 0.0063280719 0.0163090000 199440858 95654128 760807424 -0.4801810384 -0.0155358370 0.0140335066 83 3.2800000000 0.0355026051 0.0323596648 0.0565873794 0.0063326456 0.0163560000 199444750 95654128 760807424 -0.4919620156 -0.0113758296 0.0103022512 84 3.3200000000 0.0303926412 0.0323362479 0.0565873794 0.0063157057 0.0163270000 199614182 95654128 760807424 -0.5042786598 -0.0069527207 0.0090701617 85 3.3600000000 0.0338446312 0.0323539936 0.0565873794 0.0063157270 0.0162820000 199616990 95654128 760807424 -0.5145150423 -0.0081325872 0.0096226893 86 3.4000000000 0.0299361199 0.0323258788 0.0565873794 0.0063626563 0.0163420000 199619598 95654128 760807424 -0.5303586721 -0.0035575614 0.0116176223 87 3.4400000000 0.0298443679 0.0322973557 0.0565873794 0.0064897145 0.0162980000 199620406 95654128 760807424 -0.5393974185 -0.0041370192 0.0110724103 88 3.4800000000 0.0266220178 0.0322328632 0.0565873794 0.0065695902 0.0162720000 199623014 95654128 760807424 -0.5534371138 -0.0005895477 0.0110304765 89 3.5200000000 0.0261351820 0.0321643499 0.0565873794 0.0066733550 0.0162970000 199624022 95654128 760807424 -0.5623205304 0.0005255556 0.0113013256 90 3.5600000000 0.0250491034 0.0320852916 0.0565873794 0.0067743306 0.0162990000 199626646 95654128 760807424 -0.5709735155 -0.0007456413 0.0097119333 91 3.6000000000 0.0262133759 0.0320207651 0.0565873794 0.0068309454 0.0163160000 199629254 95654128 760807424 -0.5837507248 -0.0020658812 0.0114376955 92 3.6400000000 0.0248073302 0.0319423582 0.0565873794 0.0068435934 0.0163570000 199630062 95654128 760807424 -0.5996577144 0.0014718459 0.0154624488 93 3.6800000000 0.0282015596 0.0319021345 0.0565873794 0.0068359485 0.0163580000 199632870 95654128 760807424 -0.6015052199 -0.0017028709 0.0139123406 94 3.7200000000 0.0287994500 0.0318691272 0.0565873794 0.0068125342 0.0163440000 199635478 95654128 760807424 -0.6069484353 -0.0031834850 0.0127243828 95 3.7600000000 0.0283411518 0.0318319907 0.0565873794 0.0068150262 0.0171450000 199636286 95654128 760807424 -0.6213353276 -0.0022502071 0.0177968629 96 3.8000000000 0.0284032933 0.0317962751 0.0565873794 0.0067867818 0.0164040000 199638894 95654128 760807424 -0.6307749152 -0.0022207610 0.0173674375 97 3.8400000000 0.0278009027 0.0317550857 0.0565873794 0.0067537811 0.0163860000 199641702 95654128 760807424 -0.6360018849 -0.0036643983 0.0187562387 98 3.8800000000 0.0307208337 0.0317445321 0.0565873794 0.0067274283 0.0163240000 199642510 95654128 760807424 -0.6506360173 -0.0085041942 0.0235109441 99 3.9200000000 0.0334215276 0.0317614714 0.0565873794 0.0067038442 0.0164010000 199645118 95654128 760807424 -0.6566256881 -0.0109054297 0.0268212855 100 3.9600000000 0.0304026399 0.0317478831 0.0565873794 0.0066734254 0.0164300000 199647726 95654128 760807424 -0.6654935479 -0.0078691943 0.0298565552 101 4.0000000000 0.0280820951 0.0317115882 0.0565873794 0.0066432768 0.0163670000 199648734 95654128 760807424 -0.6736974120 -0.0059484625 0.0351908617 102 4.0400000000 0.0259241927 0.0316548490 0.0565873794 0.0066272081 0.0164400000 199651342 95654128 760807424 -0.6784198880 -0.0054489388 0.0368493833 103 4.0800000000 0.0290422644 0.0316294841 0.0565873794 0.0065956642 0.0164070000 199652150 95654128 760807424 -0.6875373721 -0.0086858682 0.0431620181 104 4.1200000000 0.0290709287 0.0316048826 0.0565873794 0.0065653190 0.0164580000 199654758 95654128 760807424 -0.6993187666 -0.0088663977 0.0537953526 105 4.1600000000 0.0295045525 0.0315848795 0.0565873794 0.0065754070 0.0164570000 199658302 95654128 760807424 -0.7007381320 -0.0086500365 0.0566891655 106 4.2000000000 0.0234080087 0.0315077392 0.0565873794 0.0065547651 0.0163940000 199827734 95654128 760807424 -0.7124599218 -0.0041248659 0.0608023331 107 4.2400000000 0.0230035931 0.0314282612 0.0565873794 0.0065421625 0.0164420000 199830342 95654128 760807424 -0.7120105028 -0.0066935853 0.0590329096 108 4.2800000000 0.0237780940 0.0313574263 0.0565873794 0.0065144630 0.0164580000 199832950 95654128 760807424 -0.7214694023 -0.0085320361 0.0670858026 109 4.3200000000 0.0249999575 0.0312991009 0.0565873794 0.0065010272 0.0164460000 199833958 95654128 760807424 -0.7220396996 -0.0091981189 0.0687412992 110 4.3600000000 0.0239698645 0.0312324715 0.0565873794 0.0065085124 0.0164560000 199836566 95654128 760807424 -0.7320408821 -0.0099378293 0.0755404010 111 4.4000000000 0.0223217160 0.0311521944 0.0565873794 0.0064980428 0.0164990000 199839174 95654128 760807424 -0.7395170927 -0.0095068049 0.0813724697 112 4.4400000000 0.0257163253 0.0311036598 0.0565873794 0.0065066071 0.0165090000 199839998 95654128 760807424 -0.7446871400 -0.0112846233 0.0892183781 113 4.4800000000 0.0250240285 0.0310498578 0.0565873794 0.0065139472 0.0164820000 199842806 95654128 760807424 -0.7483003139 -0.0092906402 0.0929298103 114 4.5200000000 0.0279746242 0.0310228821 0.0565873794 0.0065617109 0.0164800000 199843614 95654128 760807424 -0.7582687140 -0.0125495903 0.1036359519 115 4.5600000000 0.0274628866 0.0309919256 0.0565873794 0.0065812472 0.0165190000 199846222 95654128 760807424 -0.7586623430 -0.0118031856 0.1064784974 116 4.6000000000 0.0284700096 0.0309701849 0.0565873794 0.0066126845 0.0164700000 199848830 95654128 760807424 -0.7683888674 -0.0094802603 0.1172670871 117 4.6400000000 0.0238145217 0.0309090254 0.0565873794 0.0066062480 0.0164910000 199849838 95654128 760807424 -0.7791025639 -0.0020336183 0.1275464743 118 4.6800000000 0.0259956717 0.0308673868 0.0565873794 0.0065823816 0.0165200000 199852446 95654128 760807424 -0.7825962901 -0.0053514089 0.1324608922 119 4.7200000000 0.0244217627 0.0308132219 0.0565873794 0.0065608417 0.0165290000 199855054 95654128 760807424 -0.7907667756 -0.0051540658 0.1391335130 120 4.7600000000 0.0230371635 0.0307484214 0.0565873794 0.0065365893 0.0165370000 199855862 95654128 760807424 -0.7981805205 -0.0015906547 0.1467321664 121 4.8000000000 0.0202708505 0.0306618299 0.0565873794 0.0065245021 0.0165080000 199858670 95654128 760807424 -0.8099064827 0.0030194623 0.1626119912 122 4.8400000000 0.0197435040 0.0305723355 0.0565873794 0.0065075745 0.0166140000 199862986 95654128 760807424 -0.8105869889 0.0066809645 0.1644673049 123 4.8800000000 0.0202268977 0.0304882262 0.0565873794 0.0064845713 0.0165800000 200032410 95654128 760807424 -0.8161545992 0.0091134738 0.1708295643 124 4.9200000000 0.0210503396 0.0304121142 0.0565873794 0.0064626427 0.0166090000 200035018 95654128 760807424 -0.8264054656 0.0098223360 0.1842324138 125 4.9600000000 0.0221218374 0.0303457920 0.0565873794 0.0064673463 0.0165860000 200036026 95654128 760807424 -0.8290974498 0.0075975470 0.1905805767 126 5.0000000000 0.0203621760 0.0302665570 0.0565873794 0.0064472133 0.0165650000 200038650 95654128 760807424 -0.8356361985 0.0089944517 0.1986374259 127 5.0400000000 0.0224242900 0.0302048068 0.0565873794 0.0064233202 0.0166410000 200041258 95654128 760807424 -0.8444821239 0.0063631646 0.2155444175 128 5.0800000000 0.0181625560 0.0301107267 0.0565873794 0.0064069173 0.0165600000 200042066 95654128 760807424 -0.8519821763 0.0123763606 0.2219798267 129 5.1200000000 0.0159286819 0.0300007884 0.0565873794 0.0063837348 0.0166090000 200056138 95654128 760807424 -0.8588014245 0.0124319699 0.2291795313 130 5.1600000000 0.0142402081 0.0298795532 0.0565873794 0.0063747314 0.0165940000 200084346 95654128 760807424 -0.8703675866 0.0166023001 0.2459881902 131 5.2000000000 0.0138809010 0.0297574261 0.0565873794 0.0063985633 0.0166240000 200085154 95654128 760807424 -0.8737038970 0.0159749705 0.2508947253 132 5.2400000000 0.0125347050 0.0296269509 0.0565873794 0.0064187543 0.0166470000 200087762 95654128 760807424 -0.8736839890 0.0161852501 0.2506185472 133 5.2800000000 0.0143580977 0.0295121475 0.0565873794 0.0064112664 0.0170160000 200090570 95654128 760807424 -0.8840085268 0.0179630816 0.2671507299 134 5.3200000000 0.0128155705 0.0293875462 0.0565873794 0.0064158977 0.0170310000 200091378 95654128 760807424 -0.8963862062 0.0240811650 0.2838450372 135 5.3600000000 0.0136302458 0.0292708254 0.0565873794 0.0064378154 0.0169950000 200093986 95654128 760807424 -0.8979189992 0.0253746808 0.2880425453 136 5.4000000000 0.0142661799 0.0291604971 0.0565873794 0.0064766813 0.0169520000 200096594 95654128 760807424 -0.9035479426 0.0211286657 0.2993725538 137 5.4400000000 0.0135588627 0.0290466166 0.0565873794 0.0065395620 0.0169860000 200097602 95654128 760807424 -0.9087882042 0.0240651015 0.3097975552 138 5.4800000000 0.0137075316 0.0289354638 0.0565873794 0.0065782011 0.0170150000 200100210 95654128 760807424 -0.9142451286 0.0228410941 0.3143880367 139 5.5200000000 0.0144062052 0.0288309368 0.0565873794 0.0066244801 0.0170260000 200101018 95654128 760807424 -0.9191100597 0.0179335847 0.3194557726 140 5.5600000000 0.0164834857 0.0287427407 0.0565873794 0.0066983787 0.0169950000 200103626 95654128 760807424 -0.9267788529 0.0176282432 0.3325157762 141 5.6000000000 0.0159996878 0.0286523644 0.0565873794 0.0067308901 0.0171010000 200106434 95654128 760807424 -0.9324721694 0.0188185107 0.3384733796 142 5.6400000000 0.0174587779 0.0285735364 0.0565873794 0.0067756675 0.0174540000 200107242 95654128 760807424 -0.9405248165 0.0165808778 0.3527539074 143 5.6800000000 0.0170335062 0.0284928368 0.0565873794 0.0068551728 0.0169610000 200109850 95654128 760807424 -0.9468364120 0.0163971540 0.3634625077 144 5.7200000000 0.0168769881 0.0284121712 0.0565873794 0.0068920136 0.0169360000 200112458 95654128 760807424 -0.9523243904 0.0183631629 0.3722898364 145 5.7600000000 0.0133431479 0.0283082469 0.0565873794 0.0068896055 0.0169910000 200114542 95654128 760807424 -0.9608452320 0.0214430466 0.3796906769 146 5.8000000000 0.0134300925 0.0282063418 0.0565873794 0.0068767428 0.0169430000 200285794 95654128 760807424 -0.9673052430 0.0203367211 0.3888083696 147 5.8400000000 0.0143539039 0.0281121075 0.0565873794 0.0068600296 0.0170480000 200288402 95654128 760807424 -0.9767009020 0.0199700836 0.4090556204 148 5.8800000000 0.0135355704 0.0280136174 0.0565873794 0.0068379322 0.0169470000 200289210 95654128 760807424 -0.9784352779 0.0195393600 0.4133089483 149 5.9200000000 0.0124185085 0.0279089522 0.0565873794 0.0068190764 0.0169590000 200292018 95654128 760807424 -0.9838584065 0.0201101340 0.4250485897 150 5.9600000000 0.0115296766 0.0277997570 0.0565873794 0.0067999941 0.0170040000 200292826 95654128 760807424 -0.9875609279 0.0196199808 0.4350703359 151 6.0000000000 0.0115716569 0.0276922862 0.0565873794 0.0067812473 0.0169280000 200295434 95654128 760807424 -0.9911735654 0.0222937744 0.4438393414 152 6.0400000000 0.0108962534 0.0275817860 0.0565873794 0.0067659179 0.0169690000 200298042 95654128 760807424 -0.9951195717 0.0228361450 0.4550249279 153 6.0800000000 0.0104459934 0.0274697873 0.0565873794 0.0067512304 0.0171220000 200299050 95654128 760807424 -0.9993032217 0.0227521881 0.4635451436 154 6.1200000000 0.0102415653 0.0273579158 0.0565873794 0.0067724298 0.0168750000 200301658 95654128 760807424 -1.0041266680 0.0237469710 0.4758141041 155 6.1600000000 0.0096437922 0.0272436311 0.0565873794 0.0068273672 0.0169160000 200304266 95654128 760807424 -1.0069274902 0.0233395379 0.4834894836 156 6.2000000000 0.0164500754 0.0271744416 0.0565873794 0.0069797223 0.0169390000 200305074 95654128 760807424 -1.0053585768 0.0192709249 0.4951361120 157 6.2400000000 0.0150725376 0.0270973594 0.0565873794 0.0070777629 0.0169410000 200307882 95654128 760807424 -1.0081217289 0.0236951243 0.5065523982 158 6.2800000000 0.0157728232 0.0270256852 0.0565873794 0.0071443995 0.0168860000 200310490 95654128 760807424 -1.0111910105 0.0215646271 0.5223304629 159 6.3200000000 0.0167589821 0.0269611147 0.0565873794 0.0071794883 0.0169610000 200311298 95654128 760807424 -1.0110269785 0.0186838731 0.5300494432 160 6.3600000000 0.0166279208 0.0268965322 0.0565873794 0.0072151624 0.0169270000 200313906 95654128 760807424 -1.0120902061 0.0205977689 0.5455650687 161 6.4000000000 0.0148482248 0.0268216980 0.0565873794 0.0072007907 0.0169350000 200314914 95654128 760807424 -1.0122925043 0.0222181939 0.5580057502 162 6.4400000000 0.0167361107 0.0267594413 0.0565873794 0.0071813225 0.0169110000 200317522 95654128 760807424 -1.0109827518 0.0214221664 0.5675398707 163 6.4800000000 0.0130465021 0.0266753129 0.0565873794 0.0071646277 0.0169610000 200320130 95654128 760807424 -1.0149894953 0.0244314000 0.5825407505 164 6.5200000000 0.0163212046 0.0266121780 0.0565873794 0.0071454323 0.0173490000 200320938 95654128 760807424 -1.0138913393 0.0234160684 0.5915772915 165 6.5600000000 0.0149509236 0.0265415038 0.0565873794 0.0071379143 0.0170570000 200323746 95654128 760807424 -1.0160150528 0.0259537492 0.6101555228 166 6.6000000000 0.0160205122 0.0264781243 0.0565873794 0.0071537291 0.0168540000 200326354 95654128 760807424 -1.0149663687 0.0271851830 0.6202256083 167 6.6400000000 0.0149552831 0.0264091253 0.0565873794 0.0071609669 0.0168080000 200327162 95654128 760807424 -1.0151618719 0.0297443736 0.6310047507 168 6.6800000000 0.0139586376 0.0263350152 0.0565873794 0.0071648433 0.0167950000 200329770 95654128 760807424 -1.0163806677 0.0278186575 0.6439236999 169 6.7200000000 0.0120556671 0.0262505220 0.0565873794 0.0071503648 0.0168170000 200332578 95654128 760807424 -1.0166087151 0.0269229040 0.6601555943 170 6.7600000000 0.0125786299 0.0261700991 0.0565873794 0.0071455241 0.0168120000 200333386 95654128 760807424 -1.0176496506 0.0298713446 0.6772519946 171 6.8000000000 0.0124597698 0.0260899218 0.0565873794 0.0071400852 0.0168200000 200335994 95654128 760807424 -1.0170701742 0.0319686271 0.6863614917 172 6.8400000000 0.0112301568 0.0260035278 0.0565873794 0.0071207249 0.0167790000 200338602 95654128 760807424 -1.0183249712 0.0366709642 0.6997845173 173 6.8800000000 0.0121431518 0.0259234100 0.0565873794 0.0071014793 0.0167840000 200339610 95654128 760807424 -1.0190625191 0.0404440239 0.7132297754 174 6.9200000000 0.0141703160 0.0258558635 0.0565873794 0.0070823545 0.0168230000 200342218 95654128 760807424 -1.0200881958 0.0453059003 0.7250161767 175 6.9600000000 0.0148786632 0.0257931366 0.0565873794 0.0070623962 0.0168210000 200343026 95654128 760807424 -1.0198521614 0.0475922935 0.7368726730 176 7.0000000000 0.0138369342 0.0257252037 0.0565873794 0.0070481548 0.0168260000 200345634 95654128 760807424 -1.0228319168 0.0481997542 0.7526132464 177 7.0400000000 0.0146974120 0.0256628998 0.0565873794 0.0070670362 0.0168240000 200348442 95654128 760807424 -1.0237472057 0.0477490239 0.7599322796 178 7.0800000000 0.0149164945 0.0256025267 0.0565873794 0.0070534085 0.0168190000 200349234 95654128 760807424 -1.0229822397 0.0470573679 0.7666771412 179 7.1200000000 0.0129915616 0.0255320744 0.0565873794 0.0070403659 0.0168610000 200351842 95654128 760807424 -1.0213805437 0.0460786410 0.7799621224 180 7.1600000000 0.0123427873 0.0254588006 0.0565873794 0.0070215013 0.0168250000 200354450 95654128 760807424 -1.0214103460 0.0483879186 0.7935987711 181 7.2000000000 0.0100744218 0.0253738040 0.0565873794 0.0070065841 0.0168160000 200355458 95654128 760807424 -1.0204126835 0.0486699603 0.8068802953 182 7.2400000000 0.0102239009 0.0252905628 0.0565873794 0.0069904747 0.0168600000 200358066 95654128 760807424 -1.0209597349 0.0505298078 0.8222455978 183 7.2800000000 0.0106278118 0.0252104384 0.0565873794 0.0069754767 0.0168280000 200360674 95654128 760807424 -1.0231943130 0.0511041060 0.8380003572 184 7.3200000000 0.0105713662 0.0251308783 0.0565873794 0.0069566952 0.0168670000 200361482 95654128 760807424 -1.0208232403 0.0498204529 0.8476718068 185 7.3600000000 0.0104154246 0.0250513353 0.0565873794 0.0069412132 0.0168690000 200364290 95654128 760807424 -1.0201561451 0.0509872027 0.8642705083 186 7.4000000000 0.0101471543 0.0249712053 0.0565873794 0.0069292675 0.0168730000 200365098 95654128 760807424 -1.0192699432 0.0486023799 0.8806984425 187 7.4400000000 0.0113121048 0.0248981620 0.0565873794 0.0069241004 0.0168860000 200367706 95654128 760807424 -1.0148494244 0.0469910428 0.8868576884 188 7.4800000000 0.0098668411 0.0248182081 0.0565873794 0.0069271552 0.0169130000 200370314 95654128 760807424 -1.0144065619 0.0509113148 0.9040864706 189 7.5200000000 0.0111770574 0.0247460327 0.0565873794 0.0069107368 0.0168750000 200371322 95654128 760807424 -1.0136638880 0.0571361743 0.9230853319 190 7.5600000000 0.0118347583 0.0246780786 0.0565873794 0.0069009710 0.0169090000 200373930 95654128 760807424 -1.0128675699 0.0577470101 0.9397385120 191 7.6000000000 0.0088402415 0.0245951580 0.0565873794 0.0068919852 0.0168560000 200376538 95654128 760807424 -1.0110441446 0.0554164536 0.9552106261 192 7.6400000000 0.0087975524 0.0245128788 0.0565873794 0.0068824751 0.0169080000 200377362 95654128 760807424 -1.0091952085 0.0610064976 0.9712004662 193 7.6800000000 0.0093551036 0.0244343411 0.0565873794 0.0068857086 0.0168350000 200380170 95654128 760807424 -1.0079247952 0.0618456490 0.9879875779 194 7.7200000000 0.0101408111 0.0243606631 0.0565873794 0.0068830682 0.0168850000 200382778 95654128 760807424 -1.0083497763 0.0572154485 1.0028771162 195 7.7600000000 0.0079246145 0.0242763757 0.0565873794 0.0068909371 0.0169110000 200383586 95654128 760807424 -1.0062748194 0.0558811352 1.0175403357 196 7.8000000000 0.0069334055 0.0241878912 0.0565873794 0.0069310132 0.0168860000 200386194 95654128 760807424 -1.0050816536 0.0604556166 1.0370169878 197 7.8400000000 0.0080020893 0.0241057297 0.0565873794 0.0069531727 0.0168940000 200387202 95654128 760807424 -1.0024425983 0.0635510236 1.0464431047 198 7.8800000000 0.0080746124 0.0240247645 0.0565873794 0.0069758146 0.0168700000 200389826 95654128 760807424 -1.0005651712 0.0644728839 1.0618821383 199 7.9200000000 0.0089155370 0.0239488387 0.0565873794 0.0069660219 0.0168490000 200392434 95654128 760807424 -0.9995563030 0.0681180432 1.0778725147 200 7.9600000000 0.0099885100 0.0238790371 0.0565873794 0.0069537178 0.0168130000 200393242 95654128 760807424 -0.9995802045 0.0671301484 1.0908124447 201 8.0000000000 0.0089046909 0.0238045379 0.0565873794 0.0069707369 0.0168540000 200396050 95654128 760807424 -0.9985320568 0.0677087754 1.1107248068 202 8.0400000000 0.0083883032 0.0237282199 0.0565873794 0.0069837731 0.0168110000 200398658 95654128 760807424 -0.9957184792 0.0689138472 1.1220202446 203 8.0800000000 0.0103089958 0.0236621153 0.0565873794 0.0070011781 0.0168520000 200399466 95654128 760807424 -0.9927189350 0.0710213482 1.1368229389 204 8.1200000000 0.0095485914 0.0235929314 0.0565873794 0.0069925358 0.0167860000 200402074 95654128 760807424 -0.9908673167 0.0704847351 1.1502454281 205 8.1600000000 0.0103962244 0.0235285572 0.0565873794 0.0069824238 0.0168040000 200404882 95654128 760807424 -0.9890765548 0.0717406496 1.1630996466 206 8.1999999990 0.0113346819 0.0234693636 0.0565873794 0.0069739384 0.0167780000 200405690 95654128 760807424 -0.9862065911 0.0713571310 1.1749844551 207 8.2400000000 0.0127916262 0.0234177804 0.0565873794 0.0069649150 0.0168010000 200408298 95654128 760807424 -0.9819779992 0.0739604235 1.1865544319 208 8.2799999990 0.0153867127 0.0233791695 0.0565873794 0.0069510562 0.0167720000 200410906 95654128 760807424 -0.9784305096 0.0778952688 1.1974254847 209 8.3200000000 0.0146812061 0.0233375524 0.0565873794 0.0069473176 0.0168080000 200411914 95654128 760807424 -0.9735398293 0.0808220729 1.2119553089 210 8.3599999990 0.0106073739 0.0232769325 0.0565873794 0.0069738634 0.0168000000 200414522 95654128 760807424 -0.9674462676 0.0788866132 1.2262446880 211 8.4000000000 0.0109463539 0.0232184937 0.0565873794 0.0069976228 0.0176140000 200415330 95654128 760807424 -0.9644164443 0.0776812360 1.2415794134 212 8.4399999990 0.0115540521 0.0231634728 0.0565873794 0.0069825136 0.0168560000 200417938 95654128 760807424 -0.9563731551 0.0812902749 1.2521836758 213 8.4800000000 0.0135051953 0.0231181288 0.0565873794 0.0069818189 0.0167770000 200420746 95654128 760807424 -0.9504551291 0.0863137916 1.2651948929 214 8.5200000000 0.0159696974 0.0230847249 0.0565873794 0.0070580909 0.0167670000 200421554 95654128 760807424 -0.9435605407 0.0906225070 1.2790313959 215 8.5600000000 0.0149667449 0.0230469668 0.0565873794 0.0070650817 0.0167800000 200424162 95654128 760807424 -0.9360330701 0.0885562450 1.2891931534 216 8.6000000000 0.0197777431 0.0230318315 0.0565873794 0.0070521498 0.0167800000 200426770 95654128 760807424 -0.9306077957 0.0957913920 1.2989349365 217 8.6400000000 0.0209952574 0.0230224464 0.0565873794 0.0070857842 0.0168670000 200427778 95654128 760807424 -0.9217486382 0.1015952900 1.3183747530 218 8.6800000000 0.0191447679 0.0230046589 0.0565873794 0.0071358192 0.0167730000 200430386 95654128 760807424 -0.9125380516 0.0998102650 1.3285518885 219 8.7200000000 0.0194169320 0.0229882766 0.0565873794 0.0071379657 0.0167410000 200432994 95654128 760807424 -0.9035221934 0.1017378420 1.3377380371 220 8.7600000000 0.0218510125 0.0229831072 0.0565873794 0.0071417022 0.0167590000 200433802 95654128 760807424 -0.8942003250 0.1082556695 1.3481254578 221 8.8000000000 0.0252365675 0.0229933038 0.0565873794 0.0071907685 0.0168360000 200437470 95654128 760807424 -0.8851771355 0.1135306805 1.3610553741 222 8.8400000000 0.0266773999 0.0230098989 0.0565873794 0.0071948097 0.0167890000 200606930 95654128 760807424 -0.8762686253 0.1147469729 1.3709738255 223 8.8800000000 0.0276154019 0.0230305514 0.0565873794 0.0071973629 0.0167670000 200609538 95654128 760807424 -0.8663059473 0.1180772111 1.3796384335 224 8.9200000000 0.0280872788 0.0230531260 0.0565873794 0.0072042398 0.0167750000 200612146 95654128 760807424 -0.8562116027 0.1209880561 1.3901326656 225 8.9600000000 0.0278070997 0.0230742548 0.0565873794 0.0072003355 0.0167670000 200613154 95654128 760807424 -0.8458883166 0.1233262122 1.3984519243 226 9.0000000000 0.0266737863 0.0230901819 0.0565873794 0.0071868005 0.0167710000 200615762 95654128 760807424 -0.8357704282 0.1255071014 1.4098273516 227 9.0400000000 0.0268399809 0.0231067009 0.0565873794 0.0071734862 0.0167860000 200618370 95654128 760807424 -0.8234215379 0.1331376731 1.4206258059 228 9.0800000000 0.0265169386 0.0231216581 0.0565873794 0.0071843668 0.0169400000 200620006 95654128 760807424 -0.8124112487 0.1373369992 1.4328358173 229 9.1200000000 0.0266693253 0.0231371500 0.0565873794 0.0072333751 0.0168700000 200791462 95654128 760807424 -0.8013148904 0.1420869827 1.4406356812 230 9.1600000000 0.0263764989 0.0231512342 0.0565873794 0.0073446280 0.0168560000 200794070 95654128 760807424 -0.7916516066 0.1450527012 1.4477539062 231 9.2000000000 0.0273222793 0.0231692906 0.0565873794 0.0075452443 0.0168710000 200794878 95654128 760807424 -0.7821575999 0.1465450823 1.4534574747 232 9.2400000000 0.0267693847 0.0231848083 0.0565873794 0.0077005264 0.0168690000 200797486 95654128 760807424 -0.7720475793 0.1494556814 1.4621539116 233 9.2800000000 0.0263136849 0.0231982369 0.0565873794 0.0078409401 0.0169240000 200800066 95654128 760807424 -0.7624059916 0.1522986442 1.4703491926 234 9.3200000000 0.0263030734 0.0232115055 0.0565873794 0.0079453957 0.0175710000 200971274 95654128 760807424 -0.7527998686 0.1562370062 1.4780155420 235 9.3600000000 0.0238443539 0.0232141985 0.0565873794 0.0080204289 0.0168950000 200973882 95654128 760807424 -0.7425438166 0.1571419537 1.4867172241 236 9.4000000000 0.0241725873 0.0232182594 0.0565873794 0.0080782619 0.0168460000 200974690 95654128 760807424 -0.7327290773 0.1607173532 1.4953321218 237 9.4400000000 0.0226232614 0.0232157489 0.0565873794 0.0081064459 0.0168370000 200977498 95654128 760807424 -0.7221484780 0.1639552712 1.5029543638 238 9.4800000000 0.0216442924 0.0232091461 0.0565873794 0.0081270374 0.0169010000 200980106 95654128 760807424 -0.7106192112 0.1692799628 1.5109854937 239 9.5200000000 0.0229621027 0.0232081125 0.0565873794 0.0081686028 0.0172090000 200981918 95654128 760807424 -0.7003911138 0.1759685725 1.5184862614 240 9.5600000000 0.0218612421 0.0232025005 0.0565873794 0.0082293670 0.0165400000 201153190 95654128 760807424 -0.6897841096 0.1802068502 1.5284988880 241 9.6000000000 0.0227698702 0.0232007054 0.0565873794 0.0082808180 0.0166210000 201155998 95654128 760807424 -0.6805469990 0.1829254180 1.5396760702 242 9.6400000000 0.0233433861 0.0232012950 0.0565873794 0.0082992332 0.0165420000 201156806 95654128 760807424 -0.6711501479 0.1863381565 1.5508283377 243 9.6800000000 0.0226681400 0.0231991009 0.0565873794 0.0083094436 0.0165720000 201159398 95654128 760807424 -0.6592981219 0.1919754446 1.5569922924 244 9.7200000000 0.0207534917 0.0231890779 0.0565873794 0.0083526987 0.0165860000 201162006 95654128 760807424 -0.6471996307 0.1966625154 1.5652875900 245 9.7600000000 0.0225469898 0.0231864571 0.0565873794 0.0084086751 0.0167210000 201164114 95654128 760807424 -0.6379574537 0.1985706985 1.5668637753 246 9.8000000000 0.0210034586 0.0231775832 0.0565873794 0.0084313545 0.0166830000 201335362 95654128 760807424 -0.6272129416 0.2007794082 1.5781079531 247 9.8400000000 0.0217276104 0.0231717128 0.0565873794 0.0084367811 0.0166580000 201336170 95654128 760807424 -0.6174205542 0.2029023170 1.5901969671 248 9.8800000000 0.0218684785 0.0231664579 0.0565873794 0.0084216554 0.0167270000 201338778 95654128 760807424 -0.6082823873 0.2048221529 1.5991299152 249 9.9200000000 0.0205444880 0.0231559279 0.0565873794 0.0084058345 0.0167090000 201341586 95654128 760807424 -0.5978543162 0.2054613382 1.6056209803 250 9.9600000000 0.0178185645 0.0231345784 0.0565873794 0.0083894860 0.0167020000 201342394 95654128 760807424 -0.5866388083 0.2054536343 1.6152135134 251 10.0000000000 0.0169008486 0.0231097428 0.0565873794 0.0083736586 0.0167840000 201345002 95654128 760807424 -0.5749237537 0.2080725580 1.6230186224 252 10.0400000000 0.0151121160 0.0230780062 0.0565873794 0.0083589780 0.0167360000 201347610 95654128 760807424 -0.5649706125 0.2059015483 1.6337980032 253 10.0800000000 0.0171476062 0.0230545659 0.0565873794 0.0083437796 0.0167020000 201348618 95654128 760807424 -0.5587772727 0.2040656954 1.6427011490 254 10.1200000000 0.0190159865 0.0230386660 0.0565873794 0.0083589480 0.0167700000 201351226 95654128 760807424 -0.5501090884 0.2102445811 1.6534143686 255 10.1600000000 0.0214791819 0.0230325504 0.0565873794 0.0083733372 0.0167470000 201353834 95654128 760807424 -0.5403528810 0.2193801254 1.6621897221 256 10.2000000000 0.0218690168 0.0230280053 0.0565873794 0.0083601801 0.0167640000 201354642 95654128 760807424 -0.5297057033 0.2243788391 1.6705917120 257 10.2400000000 0.0210041013 0.0230201302 0.0565873794 0.0083464509 0.0167220000 201379978 95654128 760807424 -0.5202844739 0.2225656062 1.6778892279 258 10.2800000000 0.0212560203 0.0230132925 0.0565873794 0.0083302750 0.0168520000 201433146 95654128 760807424 -0.5100466609 0.2283672988 1.6879560947 259 10.3200000000 0.0220312513 0.0230095009 0.0565873794 0.0083255446 0.0167650000 201604414 95654128 760807424 -0.5000804067 0.2329246104 1.6946010590 260 10.3600000000 0.0220077671 0.0230056481 0.0565873794 0.0083323446 0.0167550000 201607022 95654128 760807424 -0.4900672734 0.2348663360 1.7042506933 261 10.4000000000 0.0204835031 0.0229959847 0.0565873794 0.0083307125 0.0167780000 201608030 95654128 760807424 -0.4799650311 0.2330179065 1.7116577625 262 10.4400000000 0.0205314141 0.0229865779 0.0565873794 0.0083169493 0.0167920000 201610638 95654128 760807424 -0.4702587724 0.2329406887 1.7168891430 263 10.4800000000 0.0200266801 0.0229753235 0.0565873794 0.0083029131 0.0167540000 201613246 95654128 760807424 -0.4595166445 0.2332550436 1.7213213444 264 10.5200000000 0.0196450707 0.0229627090 0.0565873794 0.0082918538 0.0167560000 201614038 95654128 760807424 -0.4489890039 0.2324612290 1.7270710468 265 10.5600000000 0.0216894690 0.0229579043 0.0565873794 0.0082765799 0.0167960000 201616846 95654128 760807424 -0.4389727414 0.2366356999 1.7347691059 266 10.6000000000 0.0206516702 0.0229492342 0.0565873794 0.0082647409 0.0168170000 201619454 95654128 760807424 -0.4263673723 0.2380422503 1.7389643192 267 10.6400000000 0.0214218069 0.0229435135 0.0565873794 0.0082603399 0.0168180000 201620262 95654128 760807424 -0.4156136811 0.2374270409 1.7421503067 268 10.6800000000 0.0205366481 0.0229345327 0.0565873794 0.0082551382 0.0167910000 201622870 95654128 760807424 -0.4041909873 0.2363156229 1.7497122288 269 10.7200000000 0.0210296754 0.0229274514 0.0565873794 0.0082428584 0.0167850000 201623878 95654128 760807424 -0.3923847079 0.2366111130 1.7516494989 270 10.7600000000 0.0208494943 0.0229197553 0.0565873794 0.0082349473 0.0168080000 201626486 95654128 760807424 -0.3677910864 0.2408265471 1.7629567385 271 10.8000000000 0.0203199610 0.0229101620 0.0565873794 0.0082523134 0.0167740000 201629094 95654128 760807424 -0.3531943262 0.2440717071 1.7662658691 272 10.8400000000 0.0193612073 0.0228971143 0.0565873794 0.0083119263 0.0170090000 201629902 95654128 760807424 -0.3408325613 0.2412162274 1.7697260380 273 10.8800000000 0.0193432607 0.0228840965 0.0565873794 0.0083196233 0.0168830000 201632710 95654128 760807424 -0.3283485174 0.2421998084 1.7754635811 274 10.9200000000 0.0196834020 0.0228724152 0.0565873794 0.0083291771 0.0169160000 201635318 95654128 760807424 -0.3155876696 0.2437502593 1.7804719210 275 10.9600000000 0.0187272206 0.0228573417 0.0565873794 0.0083318984 0.0168810000 201636126 95654128 760807424 -0.3019986451 0.2428949326 1.7824773788 276 11.0000000000 0.0174831711 0.0228378701 0.0565873794 0.0083286565 0.0169610000 201638734 95654128 760807424 -0.2882025540 0.2432290167 1.7857329845 277 11.0400000000 0.0185576621 0.0228224181 0.0565873794 0.0083333157 0.0169150000 201641542 95654128 760807424 -0.2749381363 0.2454714626 1.7879196405 278 11.0800000000 0.0185034629 0.0228068823 0.0565873794 0.0083390923 0.0169470000 201642350 95654128 760807424 -0.2614082992 0.2470571846 1.7912267447 279 11.1200000000 0.0197294764 0.0227958522 0.0565873794 0.0083498396 0.0169970000 201644958 95654128 760807424 -0.2482144386 0.2501976788 1.7961366177 280 11.1600000000 0.0204356182 0.0227874228 0.0565873794 0.0083573181 0.0178510000 201647566 95654128 760807424 -0.2345665395 0.2531746924 1.7988307476 281 11.2000000000 0.0206494592 0.0227798143 0.0565873794 0.0083629991 0.0171210000 201648574 95654128 760807424 -0.2212301791 0.2542213500 1.8008323908 282 11.2400000000 0.0202339403 0.0227707864 0.0565873794 0.0083591847 0.0171900000 201652330 95654128 760807424 -0.2094332874 0.2531380057 1.8069236279 283 11.2800000000 0.0209511593 0.0227643566 0.0565873794 0.0083445561 0.0171400000 201821810 95654128 760807424 -0.1976581216 0.2551265061 1.8099355698 284 11.3200000000 0.0202386137 0.0227554632 0.0565873794 0.0083333667 0.0171570000 201824418 95654128 760807424 -0.1849638075 0.2563909292 1.8152763844 285 11.3600000000 0.0207093712 0.0227482839 0.0565873794 0.0083302097 0.0171740000 201827226 95654128 760807424 -0.1733889729 0.2576700747 1.8180702925 286 11.4000000000 0.0222079325 0.0227463946 0.0565873794 0.0083226142 0.0171380000 201828050 95654128 760807424 -0.1638772488 0.2588826716 1.8221955299 287 11.4400000000 0.0219464749 0.0227436074 0.0565873794 0.0083080703 0.0172620000 201830658 95654128 760807424 -0.1542179734 0.2578119040 1.8250732422 288 11.4800000000 0.0219191331 0.0227407446 0.0565873794 0.0082945408 0.0172000000 201833266 95654128 760807424 -0.1463050544 0.2573199570 1.8303774595 289 11.5200000000 0.0228893068 0.0227412587 0.0565873794 0.0082815851 0.0171610000 201834274 95654128 760807424 -0.1383836269 0.2577302754 1.8360852003 290 11.5600000000 0.0220172405 0.0227387621 0.0565873794 0.0082739631 0.0172100000 201836882 95654128 760807424 -0.1300644726 0.2563151419 1.8406897783 291 11.6000000000 0.0225338861 0.0227380580 0.0565873794 0.0082635803 0.0171810000 201839490 95654128 760807424 -0.1229099408 0.2549737096 1.8463274240 292 11.6400000000 0.0227311179 0.0227380343 0.0565873794 0.0082508163 0.0172270000 201840298 95654128 760807424 -0.1154276431 0.2553741932 1.8516392708 293 11.6800000000 0.0236021448 0.0227409834 0.0565873794 0.0082372216 0.0171840000 201843106 95654128 760807424 -0.1085517481 0.2567702234 1.8581743240 294 11.7200000000 0.0230637901 0.0227420814 0.0565873794 0.0082247143 0.0172130000 201843930 95654128 760807424 -0.1029033735 0.2542050183 1.8650101423 295 11.7600000000 0.0236041117 0.0227450036 0.0565873794 0.0082166229 0.0172520000 201846538 95654128 760807424 -0.0973608196 0.2553754449 1.8724926710 296 11.8000000000 0.0220964532 0.0227428125 0.0565873794 0.0082081184 0.0172570000 201849146 95654128 760807424 -0.0905098692 0.2549461722 1.8801126480 297 11.8400000000 0.0215752479 0.0227388813 0.0565873794 0.0082007448 0.0172370000 201850154 95654128 760807424 -0.0846661031 0.2545692325 1.8874011040 298 11.8800000000 0.0209749509 0.0227329621 0.0565873794 0.0081942832 0.0172100000 201852762 95654128 760807424 -0.0800785124 0.2530172467 1.8960822821 299 11.9200000000 0.0213576183 0.0227283623 0.0565873794 0.0081851744 0.0172130000 201855370 95654128 760807424 -0.0752508342 0.2543687820 1.9059110880 300 11.9600000000 0.0211357083 0.0227230534 0.0565873794 0.0081724845 0.0172730000 201856178 95654128 760807424 -0.0700832382 0.2543623447 1.9129474163 301 12.0000000000 0.0224395525 0.0227221116 0.0565873794 0.0081589769 0.0173090000 201859002 95654128 760807424 -0.0668033734 0.2554899752 1.9226341248 302 12.0400000000 0.0233659092 0.0227242434 0.0565873794 0.0081474289 0.0173550000 201861610 95654128 760807424 -0.0634006411 0.2554724514 1.9312853813 303 12.0800000000 0.0236472562 0.0227272896 0.0565873794 0.0081412643 0.0181400000 201862418 95654128 760807424 -0.0595501587 0.2563642561 1.9420877695 304 12.1200000000 0.0243161786 0.0227325162 0.0565873794 0.0081377036 0.0173240000 201865026 95654128 760807424 -0.0559974164 0.2572835088 1.9522778988 305 12.1600000000 0.0257873777 0.0227425321 0.0565873794 0.0081354311 0.0173020000 201866034 95654128 760807424 -0.0529084690 0.2585605979 1.9629169703 306 12.2000000000 0.0267730299 0.0227557037 0.0565873794 0.0081249766 0.0173220000 201868642 95654128 760807424 -0.0504183322 0.2592127621 1.9751762152 307 12.2400000000 0.0271427240 0.0227699937 0.0565873794 0.0081263023 0.0172650000 201871250 95654128 760807424 -0.0474543795 0.2600343525 1.9863637686 308 12.2800000000 0.0269177407 0.0227834604 0.0565873794 0.0081315001 0.0173830000 201872058 95654128 760807424 -0.0448119752 0.2584626377 1.9956852198 309 12.3200000000 0.0275417045 0.0227988592 0.0565873794 0.0081433908 0.0172980000 201874866 95654128 760807424 -0.0431363843 0.2588330507 2.0064785480 310 12.3600000000 0.0280312337 0.0228157379 0.0565873794 0.0081631385 0.0173160000 201877474 95654128 760807424 -0.0418984443 0.2586444616 2.0183982849 311 12.4000000000 0.0278619919 0.0228319638 0.0565873794 0.0081721912 0.0173110000 201878282 95654128 760807424 -0.0403318293 0.2589431405 2.0300896168 312 12.4400000000 0.0283821952 0.0228497530 0.0565873794 0.0082094691 0.0173350000 201880890 95654128 760807424 -0.0390811190 0.2577539384 2.0533936024 313 12.4800000000 0.0285501275 0.0228679650 0.0565873794 0.0082032893 0.0173110000 201883698 95654128 760807424 -0.0385999009 0.2579027116 2.0643527508 314 12.5200000000 0.0289258026 0.0228872575 0.0565873794 0.0081961694 0.0172270000 201884506 95654128 760807424 -0.0385119282 0.2578634918 2.0774304867 315 12.5600000000 0.0289578084 0.0229065291 0.0565873794 0.0081932542 0.0173410000 201887114 95654128 760807424 -0.0385018624 0.2579255998 2.0893497467 316 12.6000000000 0.0287549496 0.0229250368 0.0565873794 0.0081832236 0.0171410000 201889722 95654128 760807424 -0.0384916328 0.2570085227 2.1006088257 317 12.6400000000 0.0280838348 0.0229413106 0.0565873794 0.0081710485 0.0174580000 201890730 95654128 760807424 -0.0386105329 0.2564157248 2.1138117313 318 12.6800000000 0.0274921674 0.0229556214 0.0565873794 0.0081589317 0.0173100000 201894478 95654128 760807424 -0.0387799777 0.2557792068 2.1256647110 319 12.7200000000 0.0270623062 0.0229684951 0.0565873794 0.0081464700 0.0173280000 202063994 95654128 760807424 -0.0393152498 0.2549001873 2.1347920895 320 12.7600000000 0.0269192513 0.0229808412 0.0565873794 0.0081339810 0.0173050000 202066602 95654128 760807424 -0.0406561121 0.2542268038 2.1445839405 321 12.8000000000 0.0266918950 0.0229924021 0.0565873794 0.0081252209 0.0173860000 202069410 95654128 760807424 -0.0429548807 0.2539358437 2.1575644016 322 12.8400000000 0.0257342923 0.0230009173 0.0565873794 0.0081148622 0.0171980000 202070234 95654128 760807424 -0.0447556227 0.2521415055 2.1671605110 323 12.8800000000 0.0256685372 0.0230091762 0.0565873794 0.0081082942 0.0171510000 202072842 95654128 760807424 -0.0465827137 0.2519668639 2.1772537231 324 12.9200000000 0.0252397470 0.0230160606 0.0565873794 0.0080989497 0.0174420000 202075466 95654128 760807424 -0.0486540683 0.2509743869 2.1881544590 325 12.9600000000 0.0252097044 0.0230228103 0.0565873794 0.0080868059 0.0174780000 202077650 95654128 760807424 -0.0499298945 0.2523369491 2.1984720230 326 13.0000000000 0.0248118769 0.0230282982 0.0565873794 0.0080759817 0.0174920000 202248914 95654128 760807424 -0.0511823893 0.2526832521 2.2080790997 327 13.0400000000 0.0262444466 0.0230381336 0.0565873794 0.0080729987 0.0175450000 202251538 95654128 760807424 -0.0530979112 0.2551290691 2.2220532894 328 13.0800000000 0.0276705883 0.0230522569 0.0565873794 0.0080651236 0.0173160000 202252478 95654128 760807424 -0.0534879528 0.2586265206 2.2327697277 329 13.1200000000 0.0282814279 0.0230681510 0.0565873794 0.0080550513 0.0173470000 202255286 95654128 760807424 -0.0545935929 0.2611975074 2.2417922020 330 13.1600000000 0.0293445066 0.0230871703 0.0565873794 0.0080446919 0.0175680000 202256358 95654128 760807424 -0.0565469600 0.2629839778 2.2500832081 331 13.2000000000 0.0311111696 0.0231114120 0.0565873794 0.0080348987 0.0179690000 202259098 95654128 760807424 -0.0593210123 0.2661905289 2.2577276230 332 13.2400000000 0.0305487104 0.0231338135 0.0565873794 0.0080263249 0.0179220000 202263270 95654128 760807424 -0.0603824705 0.2669572830 2.2654268742 333 13.2800000000 0.0317413509 0.0231596619 0.0565873794 0.0080165063 0.0179810000 202433966 95654128 760807424 -0.0636707768 0.2686642408 2.2711923122 334 13.3200000000 0.0325533114 0.0231877866 0.0565873794 0.0080049048 0.0180840000 202436574 95654128 760807424 -0.0670924932 0.2688298523 2.2751159668 335 13.3600000000 0.0323869959 0.0232152470 0.0565873794 0.0079939775 0.0180050000 202439182 95654128 760807424 -0.0686744303 0.2699536383 2.2818207741 336 13.4000000000 0.0335040465 0.0232458684 0.0565873794 0.0079826239 0.0180190000 202440122 95654128 760807424 -0.0706762820 0.2725278437 2.2871465683 337 13.4400000000 0.0319327936 0.0232716456 0.0565873794 0.0079768759 0.0179780000 202442930 95654128 760807424 -0.0719766691 0.2727188468 2.2933356762 338 13.4800000000 0.0339389034 0.0233032056 0.0565873794 0.0079808673 0.0183070000 202445670 95654128 760807424 -0.0743291751 0.2755677700 2.2962622643 339 13.5200000000 0.0362334028 0.0233413477 0.0565873794 0.0080146966 0.0182660000 202446478 95654128 760807424 -0.0788093656 0.2773222327 2.3029863834 340 13.5600000000 0.0352970511 0.0233765116 0.0565873794 0.0080247431 0.0183470000 202451110 95654128 760807424 -0.0822865665 0.2763213813 2.3128380775 341 13.6000000000 0.0353834778 0.0234117226 0.0565873794 0.0080218859 0.0184070000 202620950 95654128 760807424 -0.0841724202 0.2772068679 2.3174626827 342 13.6400000000 0.0356647335 0.0234475501 0.0565873794 0.0080132651 0.0184870000 202623558 95654128 760807424 -0.0860488191 0.2780115604 2.3218066692 343 13.6800000000 0.0373593755 0.0234881094 0.0565873794 0.0080036217 0.0182600000 202626298 95654128 760807424 -0.0883857906 0.2800486386 2.3251440525 344 13.7200000000 0.0377488025 0.0235295649 0.0565873794 0.0079931412 0.0181630000 202627106 95654128 760807424 -0.0893498957 0.2820871770 2.3295345306 345 13.7600000000 0.0371102877 0.0235689293 0.0565873794 0.0079850662 0.0184410000 202630046 95654128 760807424 -0.0912511572 0.2810961306 2.3352746964 346 13.8000000000 0.0361567177 0.0236053102 0.0565873794 0.0079790245 0.0185030000 202634470 95654128 760807424 -0.0925617665 0.2799133360 2.3403122425 347 13.8400000000 0.0350562036 0.0236383099 0.0565873794 0.0079694725 0.0193220000 202804110 95654128 760807424 -0.0939337462 0.2768000364 2.3419294357 348 13.8800000000 0.0343251266 0.0236690191 0.0565873794 0.0079599958 0.0187890000 202806718 95654128 760807424 -0.0923255906 0.2784414887 2.3443775177 349 13.9200000000 0.0331798606 0.0236962708 0.0565873794 0.0079546079 0.0187240000 202809658 95654128 760807424 -0.0922669545 0.2778708041 2.3498010635 350 13.9600000000 0.0311954264 0.0237176970 0.0565873794 0.0079538040 0.0185130000 202810466 95654128 760807424 -0.0913870782 0.2758262455 2.3581337929 351 14.0000000000 0.0308527146 0.0237380247 0.0565873794 0.0079434582 0.0190620000 202813562 95654128 760807424 -0.0900609717 0.2740429044 2.3585584164 352 14.0400000000 0.0289511476 0.0237528347 0.0565873794 0.0079354294 0.0191890000 202816170 95654128 760807424 -0.0906074420 0.2707588375 2.3636801243 353 14.0800000000 0.0278830510 0.0237645350 0.0565873794 0.0079243924 0.0186680000 202817178 95654128 760807424 -0.0903624967 0.2691067755 2.3685429096 354 14.1200000000 0.0277025476 0.0237756593 0.0565873794 0.0079134220 0.0190300000 202819786 95654128 760807424 -0.0904361010 0.2688831091 2.3733806610 355 14.1600000000 0.0270311031 0.0237848296 0.0565873794 0.0079032284 0.0190590000 202820726 95654128 760807424 -0.0900638327 0.2678246200 2.3786408901 356 14.2000000000 0.0272316691 0.0237945117 0.0565873794 0.0078942976 0.0187940000 202823334 95654128 760807424 -0.0894292220 0.2675578892 2.3825380802 357 14.2400000000 0.0272463020 0.0238041806 0.0565873794 0.0078878216 0.0191810000 202828438 95654128 760807424 -0.0897528976 0.2688418925 2.3894534111 358 14.2800000000 0.0276266672 0.0238148579 0.0565873794 0.0078774718 0.0193910000 202998078 95654128 760807424 -0.0894109830 0.2672213018 2.3933956623 359 14.3200000000 0.0274656229 0.0238250272 0.0565873794 0.0078667350 0.0192560000 203000686 95654128 760807424 -0.0907351077 0.2651402056 2.3995361328 360 14.3600000000 0.0280515421 0.0238367675 0.0565873794 0.0078577578 0.0195050000 203003294 95654128 760807424 -0.0918309391 0.2635174692 2.4053637981 361 14.4000000000 0.0284802318 0.0238496303 0.0565873794 0.0078498649 0.0191190000 203004302 95654128 760807424 -0.0926556289 0.2636440992 2.4120647907 362 14.4400000000 0.0287590809 0.0238631923 0.0565873794 0.0078411964 0.0191720000 203006910 95654128 760807424 -0.0939069837 0.2628587484 2.4187049866 363 14.4800000000 0.0293782130 0.0238783852 0.0565873794 0.0078306661 0.0193870000 203009518 95654128 760807424 -0.0940598324 0.2637346387 2.4251520634 364 14.5200000000 0.0291457400 0.0238928560 0.0565873794 0.0078226559 0.0192630000 203010326 95654128 760807424 -0.0956477076 0.2630417347 2.4342830181 365 14.5600000000 0.0288061928 0.0239063172 0.0565873794 0.0078131931 0.0192070000 203013134 95654128 760807424 -0.0965467468 0.2615707219 2.4419159889 366 14.6000000000 0.0284654647 0.0239187739 0.0565873794 0.0078049078 0.0192490000 203013942 95654128 760807424 -0.0980681106 0.2614835799 2.4518771172 367 14.6400000000 0.0290857852 0.0239328529 0.0565873794 0.0077945251 0.0204040000 203016550 95654128 760807424 -0.0989222303 0.2615601420 2.4585878849 368 14.6800000000 0.0293932762 0.0239476910 0.0565873794 0.0077865586 0.0194500000 203019158 95654128 760807424 -0.0994203612 0.2616217732 2.4657697678 369 14.7200000000 0.0294773169 0.0239626765 0.0565873794 0.0077858731 0.0195650000 203020150 95654128 760807424 -0.1014706120 0.2602957785 2.4745762348 370 14.7600000000 0.0303965658 0.0239800653 0.0565873794 0.0077783844 0.0196590000 203022758 95654128 760807424 -0.1034811065 0.2612169385 2.4845919609 371 14.8000000000 0.0309520978 0.0239988579 0.0565873794 0.0077767984 0.0196540000 203025366 95654128 760807424 -0.1048073694 0.2580126822 2.4912259579 372 14.8400000000 0.0317656137 0.0240197363 0.0565873794 0.0077729335 0.0196720000 203026174 95654128 760807424 -0.1065879986 0.2556830943 2.4991028309 373 14.8800000000 0.0336735621 0.0240456178 0.0565873794 0.0077818714 0.0196500000 203028982 95654128 760807424 -0.1091036946 0.2528674006 2.5065774918 374 14.9200000000 0.0345509984 0.0240737071 0.0565873794 0.0077784898 0.0197950000 203031590 95654128 760807424 -0.1102257371 0.2515736222 2.5138416290 375 14.9600000000 0.0352713913 0.0241035676 0.0565873794 0.0077854344 0.0199960000 203032398 95654128 760807424 -0.1109622642 0.2510654628 2.5215954781 376 15.0000000000 0.0368063487 0.0241373516 0.0565873794 0.0077856657 0.0199490000 203035006 95654128 760807424 -0.1115317270 0.2517136931 2.5288045406 377 15.0400000000 0.0373505428 0.0241723998 0.0565873794 0.0077911687 0.0195800000 203036030 95654128 760807424 -0.1093706265 0.2520047724 2.5404007435 378 15.0800000000 0.0375896730 0.0242078953 0.0565873794 0.0077827894 0.0198720000 203038638 95654128 760807424 -0.1081061289 0.2530948520 2.5482723713 379 15.1200000000 0.0372024029 0.0242421816 0.0565873794 0.0077727643 0.0197250000 203041246 95654128 760807424 -0.1058297455 0.2535758615 2.5539150238 380 15.1600000000 0.0373806730 0.0242767565 0.0565873794 0.0077649426 0.0198200000 203042054 95654128 760807424 -0.1029497534 0.2544275522 2.5581908226 381 15.2000000000 0.0374402367 0.0243113063 0.0565873794 0.0077556190 0.0198950000 203044862 95654128 760807424 -0.1005067155 0.2561683953 2.5628292561 382 15.2400000000 0.0365404747 0.0243433199 0.0565873794 0.0077481661 0.0202340000 203047470 95654128 760807424 -0.0974082872 0.2570837736 2.5678782463 383 15.2800000000 0.0368351750 0.0243759357 0.0565873794 0.0077396779 0.0199640000 203048410 95654128 760807424 -0.0950621217 0.2579314709 2.5724008083 384 15.3200000000 0.0367190130 0.0244080791 0.0565873794 0.0077298796 0.0196170000 203051018 95654128 760807424 -0.0921317860 0.2578332126 2.5761749744 385 15.3600000000 0.0366897136 0.0244399795 0.0565873794 0.0077212489 0.0199090000 203053826 95654128 760807424 -0.0896253064 0.2560272515 2.5788288116 386 15.4000000000 0.0380313098 0.0244751902 0.0565873794 0.0077264933 0.0196330000 203054634 95654128 760807424 -0.0885209665 0.2542375326 2.5834527016 387 15.4400000000 0.0405163579 0.0245166402 0.0565873794 0.0077467719 0.0200380000 203059046 95654128 760807424 -0.0876963586 0.2536109984 2.5892460346 388 15.4800000000 0.0397089384 0.0245557956 0.0565873794 0.0077387186 0.0200010000 203230342 95654128 760807424 -0.0841778517 0.2562521994 2.5914349556 389 15.5200000000 0.0404164754 0.0245965686 0.0565873794 0.0077328933 0.0194880000 203231350 95654128 760807424 -0.0825225562 0.2580981255 2.5934052467 390 15.5600000000 0.0394374877 0.0246346222 0.0565873794 0.0077240105 0.0197130000 203233958 95654128 760807424 -0.0775291994 0.2613340020 2.5931246281 391 15.6000000000 0.0378204025 0.0246683454 0.0565873794 0.0077234949 0.0195190000 203234766 95654128 760807424 -0.0722986311 0.2624287009 2.5915081501 392 15.6400000000 0.0381881855 0.0247028348 0.0565873794 0.0077210515 0.0190630000 203237374 95654128 760807424 -0.0697892532 0.2649733722 2.5914659500 393 15.6800000000 0.0360192470 0.0247316298 0.0565873794 0.0077131808 0.0202940000 203240310 95654128 760807424 -0.0655967072 0.2674570084 2.5946352482 394 15.7200000000 0.0376010053 0.0247642932 0.0565873794 0.0077045891 0.0205980000 203241118 95654128 760807424 -0.0646947101 0.2680466175 2.5950407982 395 15.7600000000 0.0421648584 0.0248083452 0.0565873794 0.0077122612 0.0203250000 203243910 95654128 760807424 -0.0655675679 0.2664288282 2.5914273262 396 15.8000000000 0.0455427393 0.0248607048 0.0565873794 0.0077075763 0.0201560000 203246518 95654128 760807424 -0.0642601028 0.2678707540 2.5883674622 397 15.8400000000 0.0442832224 0.0249096280 0.0565873794 0.0077053433 0.0202290000 203247510 95654128 760807424 -0.0602467917 0.2693590522 2.5905902386 398 15.8800000000 0.0453937165 0.0249610956 0.0565873794 0.0076991191 0.0197630000 203250086 95654128 760807424 -0.0585562512 0.2675265968 2.5903720856 399 15.9200000000 0.0399104692 0.0249985627 0.0565873794 0.0076896523 0.0196670000 203251094 95654128 760807424 -0.0493988357 0.2693127990 2.5948443413 400 15.9600000000 0.0370193608 0.0250286147 0.0565873794 0.0076847411 0.0195250000 203253702 95654128 760807424 -0.0423271880 0.2658783197 2.5922152996 401 16.0000000000 0.0377724729 0.0250603949 0.0565873794 0.0076800015 0.0195280000 203256510 95654128 760807424 -0.0378789604 0.2667598724 2.5899250507 402 16.0400000000 0.0387647711 0.0250944854 0.0565873794 0.0076731005 0.0195560000 203257318 95654128 760807424 -0.0326749794 0.2694863081 2.5891866684 403 16.0800000000 0.0383902080 0.0251274772 0.0565873794 0.0076732969 0.0195160000 203260126 95654128 760807424 -0.0278264582 0.2689540684 2.5913560390 404 16.1200000000 0.0395117179 0.0251630818 0.0565873794 0.0076680504 0.0193820000 203260918 95654128 760807424 -0.0222968422 0.2715559900 2.5870480537 405 16.1600000000 0.0394350402 0.0251983212 0.0565873794 0.0076593762 0.0195150000 203263726 95654128 760807424 -0.0167048667 0.2717693448 2.5882165432 406 16.2000000000 0.0392305776 0.0252328834 0.0565873794 0.0076502153 0.0199240000 203266334 95654128 760807424 -0.0107718157 0.2732481658 2.5911223888 407 16.2400000000 0.0393452607 0.0252675575 0.0565873794 0.0076431322 0.0196860000 203269030 95654128 760807424 -0.0053968113 0.2749546170 2.5929021835 408 16.2800000000 0.0386078879 0.0253002544 0.0565873794 0.0076464212 0.0195580000 203440334 95654128 760807424 0.0001431582 0.2752373517 2.5969543457 409 16.3200000000 0.0379173979 0.0253311032 0.0565873794 0.0076525308 0.0193470000 203441342 95654128 760807424 0.0070617669 0.2778669894 2.6002192497 410 16.3600000000 0.0382113382 0.0253625184 0.0565873794 0.0076436014 0.0193820000 203443934 95654128 760807424 0.0129508469 0.2803321481 2.6041276455 411 16.3999999990 0.0385398604 0.0253945801 0.0565873794 0.0076385925 0.0194750000 203446758 95654128 760807424 0.0168639272 0.2811079323 2.6052114964 412 16.4400000000 0.0381505452 0.0254255411 0.0565873794 0.0076539865 0.0194850000 203447566 95654128 760807424 0.0225079898 0.2817729115 2.6120278835 413 16.4800000000 0.0379336663 0.0254558272 0.0565873794 0.0076678421 0.0194790000 203451570 95654128 760807424 0.0286010727 0.2823696733 2.6191415787 414 16.5200000000 0.0391943753 0.0254890121 0.0565873794 0.0076634672 0.0195200000 203622830 95654128 760807424 0.0324458107 0.2818686366 2.6228594780 415 16.5599999990 0.0404720493 0.0255251158 0.0565873794 0.0076844821 0.0192550000 203623838 95654128 760807424 0.0351257361 0.2757992446 2.6259202957 416 16.6000000000 0.0401386097 0.0255602443 0.0565873794 0.0077609230 0.0194870000 203626446 95654128 760807424 0.0415635817 0.2755727768 2.6319742203 417 16.6400000000 0.0403384008 0.0255956836 0.0565873794 0.0077925918 0.0193110000 203627454 95654128 760807424 0.0476458445 0.2775998712 2.6339004040 418 16.6800000000 0.0410075672 0.0256325541 0.0565873794 0.0077980255 0.0191840000 203630062 95654128 760807424 0.0502512939 0.2773232460 2.6333024502 419 16.7199999990 0.0414260291 0.0256702474 0.0565873794 0.0078284752 0.0192630000 203633974 95654128 760807424 0.0569238290 0.2780424356 2.6382710934 420 16.7600000000 0.0421184041 0.0257094096 0.0565873794 0.0078192611 0.0192040000 203803502 95654128 760807424 0.0631238222 0.2804088891 2.6390287876 421 16.8000000000 0.0416260548 0.0257472164 0.0565873794 0.0078299756 0.0191710000 203806310 95654128 760807424 0.0673226938 0.2757376134 2.6405065060 422 16.8400000000 0.0451784506 0.0257932620 0.0565873794 0.0078312671 0.0193140000 203807118 95654128 760807424 0.0753019005 0.2773567736 2.6435863972 423 16.8799999990 0.0429416895 0.0258338020 0.0565873794 0.0078277228 0.0191310000 203811090 95654128 760807424 0.0827160627 0.2723286748 2.6445724964 424 16.9200000000 0.0408663489 0.0258692561 0.0565873794 0.0078194356 0.0190590000 203982358 95654128 760807424 0.0891224071 0.2657693028 2.6436436176 425 16.9600000000 0.0389282033 0.0258999831 0.0565873794 0.0078183736 0.0190680000 203983366 95654128 760807424 0.0980551168 0.2639743090 2.6420483589 426 17.0000000000 0.0378973372 0.0259281459 0.0565873794 0.0078107410 0.0189970000 203985974 95654128 760807424 0.1073417515 0.2620722353 2.6419076920 427 17.0400000000 0.0365911797 0.0259531178 0.0565873794 0.0078084991 0.0199090000 203986966 95654128 760807424 0.1144038513 0.2584250569 2.6381328106 428 17.0800000000 0.0353945680 0.0259751773 0.0565873794 0.0078001247 0.0193020000 203989574 95654128 760807424 0.1250880361 0.2565324306 2.6360342503 429 17.1200000000 0.0361800864 0.0259989650 0.0565873794 0.0077927170 0.0190480000 203992382 95654128 760807424 0.1349236667 0.2553269565 2.6340506077 430 17.1600000000 0.0340725780 0.0260177408 0.0565873794 0.0077900867 0.0191000000 203993190 95654128 760807424 0.1452522576 0.2524387240 2.6290481091 431 17.2000000000 0.0324187130 0.0260325922 0.0565873794 0.0077811697 0.0190990000 203995998 95654128 760807424 0.1561369300 0.2475407273 2.6263425350 432 17.2400000000 0.0312654376 0.0260447053 0.0565873794 0.0077806016 0.0191820000 203998590 95654128 760807424 0.1688694358 0.2445130050 2.6218626499 433 17.2800000000 0.0306252409 0.0260552839 0.0565873794 0.0077726610 0.0191860000 203999598 95654128 760807424 0.1807299852 0.2428543568 2.6170256138 434 17.3200000000 0.0295498427 0.0260633359 0.0565873794 0.0077641414 0.0190490000 204002206 95654128 760807424 0.1916822046 0.2370170057 2.6076741219 435 17.3600000000 0.0295070522 0.0260712525 0.0565873794 0.0077756613 0.0190270000 204004458 95654128 760807424 0.2048962414 0.2367973626 2.6029603481 436 17.4000000000 0.0289821867 0.0260779289 0.0565873794 0.0077779938 0.0191910000 204175730 95654128 760807424 0.2208654881 0.2396381497 2.5966937542 437 17.4400000000 0.0297450144 0.0260863204 0.0565873794 0.0077767739 0.0190070000 204178522 95654128 760807424 0.2371589392 0.2447529733 2.5885982513 438 17.4800000000 0.0333471000 0.0261028976 0.0565873794 0.0078780456 0.0189760000 204179330 95654128 760807424 0.2474498153 0.2462201267 2.5782229900 439 17.5200000000 0.0340552889 0.0261210124 0.0565873794 0.0080165950 0.0190260000 204182138 95654128 760807424 0.2543576360 0.2410067171 2.5673112869 440 17.5600000000 0.0299070403 0.0261296170 0.0565873794 0.0080419183 0.0189890000 204182946 95654128 760807424 0.2648051977 0.2328198999 2.5592432022 441 17.6000000000 0.0247795396 0.0261265556 0.0565873794 0.0080400807 0.0189610000 204185754 95654128 760807424 0.2774737477 0.2250295281 2.5532586575 442 17.6400000000 0.0239786636 0.0261216961 0.0565873794 0.0081033113 0.0189900000 204188346 95654128 760807424 0.2924733162 0.2274526060 2.5439164639 443 17.6800000000 0.0230398141 0.0261147392 0.0565873794 0.0081200603 0.0190450000 204189354 95654128 760807424 0.3180111647 0.2295584530 2.5295112133 444 17.7200000000 0.0264990330 0.0261156048 0.0565873794 0.0081158404 0.0189640000 204191962 95654128 760807424 0.3246725500 0.2274622172 2.5169224739 445 17.7600000000 0.0285637826 0.0261211063 0.0565873794 0.0081116461 0.0188670000 204192970 95654128 760807424 0.3326011300 0.2237906456 2.5073964596 446 17.8000000000 0.0272207446 0.0261235718 0.0565873794 0.0081027528 0.0189010000 204196322 95654128 760807424 0.3440568447 0.2255064994 2.5002548695 447 17.8400000000 0.0266527291 0.0261247556 0.0565873794 0.0080979021 0.0188540000 204367830 95654128 760807424 0.3527131975 0.2229212970 2.4923439026 448 17.8800000000 0.0256658010 0.0261237312 0.0565873794 0.0080888833 0.0187990000 204368638 95654128 760807424 0.3612390161 0.2210261822 2.4862267971 449 17.9200000000 0.0248128232 0.0261208116 0.0565873794 0.0080800369 0.0188020000 204371446 95654128 760807424 0.3701938093 0.2201655358 2.4793779850 450 17.9600000000 0.0246500075 0.0261175431 0.0565873794 0.0080724379 0.0187990000 204374054 95654128 760807424 0.3771265745 0.2149356008 2.4732098579 451 18.0000000000 0.0177681427 0.0260990300 0.0565873794 0.0080770807 0.0187280000 204375030 95654128 760807424 0.3939909935 0.2150042504 2.4696953297 452 18.0400000000 0.0188260656 0.0260829394 0.0565873794 0.0080709396 0.0186770000 204377638 95654128 760807424 0.4022508860 0.2131768763 2.4625947475 453 18.0800000000 0.0193401650 0.0260680547 0.0565873794 0.0080621259 0.0186820000 204378646 95654128 760807424 0.4096130133 0.2092429101 2.4565238953 454 18.1200000000 0.0196632743 0.0260539472 0.0565873794 0.0080638846 0.0186790000 204381254 95654128 760807424 0.4192821383 0.2091326416 2.4493889809 455 18.1600000000 0.0221947674 0.0260454655 0.0565873794 0.0080567588 0.0185970000 204384062 95654128 760807424 0.4271960855 0.2071471810 2.4428555965 456 18.2000000000 0.0214683712 0.0260354280 0.0565873794 0.0080504497 0.0186250000 204384870 95654128 760807424 0.4366226792 0.2037040889 2.4353029728 457 18.2400000000 0.0210182723 0.0260244496 0.0565873794 0.0080567497 0.0186470000 204387678 95654128 760807424 0.4471164644 0.2022980899 2.4287791252 458 18.2800000000 0.0223091971 0.0260163377 0.0565873794 0.0080692830 0.0186440000 204388486 95654128 760807424 0.4573982656 0.2024694979 2.4262492657 459 18.3200000000 0.0240985025 0.0260121594 0.0565873794 0.0080622823 0.0187580000 204391294 95654128 760807424 0.4681966603 0.2071667314 2.4229705334 460 18.3600000000 0.0275221709 0.0260154420 0.0565873794 0.0080615240 0.0186690000 204393902 95654128 760807424 0.4733235240 0.2031017244 2.4177236557 461 18.4000000000 0.0298823807 0.0260238302 0.0565873794 0.0080542589 0.0186880000 204394910 95654128 760807424 0.4821237624 0.2009989172 2.4143588543 462 18.4400000000 0.0356318243 0.0260446267 0.0565873794 0.0080466736 0.0187650000 204397518 95654128 760807424 0.4878293574 0.2042666376 2.4099459648 463 18.4800000000 0.0355621949 0.0260651830 0.0565873794 0.0080405513 0.0187290000 204398574 95654128 760807424 0.4969316125 0.2016468048 2.4037530422 464 18.5200000000 0.0340397879 0.0260823696 0.0565873794 0.0080335572 0.0186150000 204401182 95654128 760807424 0.5065847635 0.1987878978 2.4004175663 465 18.5600000000 0.0430056900 0.0261187639 0.0565873794 0.0080379957 0.0186270000 204403974 95654128 760807424 0.5059705377 0.1916529834 2.3902876377 466 18.6000000000 0.0480240472 0.0261657709 0.0565873794 0.0080641830 0.0188060000 204404782 95654128 760807424 0.5146329999 0.1903351694 2.3829848766 467 18.6400000000 0.0534166768 0.0262241241 0.0565873794 0.0080632351 0.0186440000 204408410 95654128 760807424 0.5209097266 0.1906195879 2.3781645298 468 18.6800000000 0.0576247126 0.0262912193 0.0576247126 0.0080707515 0.0194730000 204579698 95654128 760807424 0.5278912783 0.1868005246 2.3742876053 469 18.7200000000 0.0590988174 0.0263611716 0.0590988174 0.0080999178 0.0187360000 204580706 95654128 760807424 0.5365723372 0.1828091145 2.3705725670 470 18.7600000000 0.0738058835 0.0264621178 0.0738058835 0.0081729812 0.0186690000 204583314 95654128 760807424 0.5359190106 0.1814618558 2.3580186367 471 18.8000000000 0.0761026070 0.0265675116 0.0761026070 0.0082335802 0.0188810000 204584826 95654128 760807424 0.5450437069 0.1815942377 2.3541722298 472 18.8400000000 0.0729315877 0.0266657406 0.0761026070 0.0082740791 0.0188280000 204756170 95654128 760807424 0.5582470894 0.1833935082 2.3530032635 473 18.8800000000 0.0658931211 0.0267486737 0.0761026070 0.0082794360 0.0187010000 204758978 95654128 760807424 0.5741543174 0.1842655241 2.3531439304 474 18.9200000000 0.0672014505 0.0268340171 0.0761026070 0.0082782737 0.0188230000 204759786 95654128 760807424 0.5786173940 0.1818882376 2.3447690010 475 18.9600000000 0.0666275173 0.0269177929 0.0761026070 0.0082765267 0.0187110000 204762594 95654128 760807424 0.5872265100 0.1783522218 2.3435115814 476 19.0000000000 0.0657280907 0.0269993271 0.0761026070 0.0082819837 0.0186510000 204764030 95654128 760807424 0.5976977348 0.1775670797 2.3416702747 477 19.0400000000 0.0579381920 0.0270641885 0.0761026070 0.0082796010 0.0186480000 204935566 95654128 760807424 0.6125203371 0.1786008179 2.3379497528 478 19.0800000000 0.0578203090 0.0271285318 0.0761026070 0.0082723277 0.0185660000 204938174 95654128 760807424 0.6249932051 0.1800076067 2.3423454762 479 19.1200000000 0.0560274273 0.0271888636 0.0761026070 0.0082657540 0.0186010000 204939182 95654128 760807424 0.6336618662 0.1750198454 2.3418176174 480 19.1600000000 0.0573278144 0.0272516530 0.0761026070 0.0082790359 0.0185650000 204941790 95654128 760807424 0.6439313293 0.1716350764 2.3405981064 481 19.2000000000 0.0547873564 0.0273088998 0.0761026070 0.0082973450 0.0185270000 204942798 95654128 760807424 0.6548737884 0.1716966480 2.3340117931 482 19.2400000000 0.0519380458 0.0273599976 0.0761026070 0.0082897874 0.0187280000 204945406 95654128 760807424 0.6663627625 0.1748773456 2.3385286331 483 19.2800000000 0.0550471246 0.0274173209 0.0761026070 0.0082814793 0.0185160000 204948214 95654128 760807424 0.6716531515 0.1727561951 2.3371071815 484 19.3200000000 0.0524093658 0.0274689573 0.0761026070 0.0082784373 0.0184060000 204949022 95654128 760807424 0.6795206666 0.1723386198 2.3329708576 485 19.3600000000 0.0481340736 0.0275115658 0.0761026070 0.0082748200 0.0186240000 204951830 95654128 760807424 0.6927508712 0.1774468869 2.3309266567 486 19.4000000000 0.0434457883 0.0275443523 0.0761026070 0.0082896206 0.0186450000 204954438 95654128 760807424 0.7076960802 0.1885667294 2.3323223591 487 19.4400000000 0.0431013554 0.0275762969 0.0761026070 0.0083195294 0.0185780000 204955446 95654128 760807424 0.7143352032 0.1831786484 2.3273789883 488 19.4800000000 0.0436722115 0.0276092803 0.0761026070 0.0083197502 0.0185430000 204958054 95654128 760807424 0.7120897174 0.1801173836 2.3217215538 489 19.5200000000 0.0503660068 0.0276558176 0.0761026070 0.0083151571 0.0195910000 204959538 95654128 760807424 0.7083238959 0.1765195429 2.3183963299 490 19.5600000000 0.0513436198 0.0277041600 0.0761026070 0.0083070760 0.0187140000 205130842 95654128 760807424 0.7114663124 0.1774425507 2.3114140034 491 19.6000000000 0.0522460528 0.0277541435 0.0761026070 0.0082993540 0.0186140000 205133634 95654128 760807424 0.7155654430 0.1779121757 2.3101067543 492 19.6400000000 0.0511567444 0.0278017098 0.0761026070 0.0082931536 0.0185790000 205134442 95654128 760807424 0.7180711031 0.1834462881 2.3026497364 493 19.6800000000 0.0500776283 0.0278468942 0.0761026070 0.0082955988 0.0186280000 205137250 95654128 760807424 0.7226712108 0.1869627237 2.2961246967 494 19.7200000000 0.0514036939 0.0278945800 0.0761026070 0.0082945582 0.0186270000 205138058 95654128 760807424 0.7232043147 0.1833150983 2.2886068821 495 19.7600000000 0.0528742522 0.0279450440 0.0761026070 0.0082874992 0.0185450000 205140866 95654128 760807424 0.7219395041 0.1811359376 2.2789955139 496 19.8000000000 0.0515917428 0.0279927188 0.0761026070 0.0082842635 0.0185610000 205143474 95654128 760807424 0.7223705053 0.1813265234 2.2719154358 497 19.8400000000 0.0527562015 0.0280425447 0.0761026070 0.0082765568 0.0186060000 205144482 95654128 760807424 0.7254776359 0.1805912852 2.2668237686 498 19.8800000000 0.0540338829 0.0280947362 0.0761026070 0.0082692135 0.0185580000 205147090 95654128 760807424 0.7222864032 0.1792025864 2.2579185963 499 19.9200000000 0.0579905696 0.0281546477 0.0761026070 0.0082613243 0.0186310000 205148114 95654128 760807424 0.7204641700 0.1804393977 2.2546143532 500 19.9600000000 0.0641310439 0.0282266004 0.0761026070 0.0082546257 0.0186710000 205151466 95654128 760807424 0.7164581418 0.1835975796 2.2487406731 501 20.0000000000 0.0663907975 0.0283027765 0.0761026070 0.0082475727 0.0186780000 205323010 95654128 760807424 0.7168720961 0.1842797101 2.2413072586 502 20.0400000000 0.0683225468 0.0283824971 0.0761026070 0.0082400117 0.0186370000 205323818 95654128 760807424 0.7186279893 0.1819302738 2.2383303642 503 20.0800000000 0.0715601072 0.0284683373 0.0761026070 0.0082323132 0.0186410000 205326658 95654128 760807424 0.7199138999 0.1854435205 2.2291157246 504 20.1200000000 0.0759124681 0.0285624725 0.0761026070 0.0082275012 0.0186760000 205329266 95654128 760807424 0.7184571624 0.1883708537 2.2204337120 505 20.1600000000 0.0787077546 0.0286617701 0.0787077546 0.0082224987 0.0186180000 205330274 95654128 760807424 0.7108942866 0.1854936481 2.2095818520 506 20.2000000000 0.0821171105 0.0287674131 0.0821171105 0.0082172251 0.0186750000 205332882 95654128 760807424 0.7079578042 0.1891743690 2.2028756142 507 20.2400000000 0.0855931789 0.0288794954 0.0855931789 0.0082192701 0.0186870000 205333906 95654128 760807424 0.7079187632 0.1941610873 2.1949453354 508 20.2800000000 0.0868908092 0.0289936909 0.0868908092 0.0082221030 0.0187000000 205336514 95654128 760807424 0.7010574937 0.1944509745 2.1854417324 509 20.3200000000 0.0871760100 0.0291079980 0.0871760100 0.0082146799 0.0187200000 205339322 95654128 760807424 0.7047740817 0.1943482459 2.1747121811 510 20.3600000000 0.0935930386 0.0292344393 0.0935930386 0.0082074371 0.0187070000 205340130 95654128 760807424 0.7055594921 0.1998813748 2.1630504131 511 20.4000000000 0.0995984003 0.0293721379 0.0995984003 0.0082023956 0.0187040000 205342938 95654128 760807424 0.7044994831 0.2072630227 2.1539154053 512 20.4400000000 0.1029325277 0.0295158105 0.1029325277 0.0082221206 0.0189270000 205344638 95654128 760807424 0.7032976151 0.2123113275 2.1465556622 513 20.4800000000 0.1034476310 0.0296599271 0.1034476310 0.0082216007 0.0188520000 205561242 95654128 760807424 0.7061236501 0.2097916305 2.1343488693 514 20.5200000000 0.1059393436 0.0298083306 0.1059393436 0.0082146771 0.0188060000 205666250 95654128 760807424 0.7052205205 0.2125158608 2.1228568554 515 20.5600000000 0.1135280579 0.0299708932 0.1135280579 0.0082179943 0.0187620000 205667258 95654128 760807424 0.7068408132 0.2211613953 2.1129937172 516 20.6000000000 0.1183032617 0.0301420800 0.1183032617 0.0082262764 0.0187870000 205669866 95654128 760807424 0.7094267011 0.2249070108 2.1036446095 517 20.6400000000 0.1207880378 0.0303174106 0.1207880378 0.0082280112 0.0188210000 205670890 95654128 760807424 0.7049737573 0.2262011915 2.1044728756 518 20.6800000000 0.1230568364 0.0304964443 0.1230568364 0.0082209859 0.0187670000 205673498 95654128 760807424 0.7164846659 0.2251745909 2.0871949196 519 20.7200000000 0.1302772313 0.0306887001 0.1302772313 0.0082193853 0.0188780000 205677206 95654128 760807424 0.7029333711 0.2336901426 2.0923628807 520 20.7600000000 0.1283445656 0.0308764999 0.1302772313 0.0082225172 0.0188380000 205846518 95654128 760807424 0.6995421052 0.2368188351 2.0911898613 521 20.8000000000 0.1215157583 0.0310504716 0.1302772313 0.0082303599 0.0188660000 205849326 95654128 760807424 0.7014290690 0.2298478633 2.0813934803 522 20.8400000000 0.1169736907 0.0312150755 0.1302772313 0.0082261091 0.0188840000 205851934 95654128 760807424 0.7081633806 0.2253063470 2.0723550320 523 20.8800000000 0.1150314659 0.0313753362 0.1302772313 0.0082206006 0.0188480000 205852942 95654128 760807424 0.6996219158 0.2242973447 2.0755188465 524 20.9200000000 0.1204941496 0.0315454103 0.1302772313 0.0082162080 0.0189080000 205855550 95654128 760807424 0.7103967071 0.2241817862 2.0593049526 525 20.9600000000 0.1244008020 0.0317222777 0.1302772313 0.0082099171 0.0189600000 205856558 95654128 760807424 0.7052100897 0.2234048843 2.0564546585 526 21.0000000000 0.1285984963 0.0319064530 0.1302772313 0.0082036355 0.0188640000 205859182 95654128 760807424 0.7083779573 0.2198096961 2.0464239120 527 21.0400000000 0.1294014454 0.0320914530 0.1302772313 0.0082079750 0.0188240000 205861990 95654128 760807424 0.7092029452 0.2222017199 2.0357656479 528 21.0800000000 0.1315909475 0.0322798990 0.1315909475 0.0082008528 0.0188650000 205862798 95654128 760807424 0.7110648155 0.2235848606 2.0317716599 529 21.1200000000 0.1381994337 0.0324801250 0.1381994337 0.0081967680 0.0189370000 205866358 95654128 760807424 0.7178729773 0.2209499329 2.0182199478 530 21.1600000000 0.1386979520 0.0326805360 0.1386979520 0.0081920500 0.0196650000 206035874 95654128 760807424 0.7136183977 0.2210164666 2.0166158676 531 21.2000000000 0.1471720189 0.0328961508 0.1471720189 0.0081872027 0.0192580000 206038714 95654128 760807424 0.7186442018 0.2256204933 2.0081367493 532 21.2400000000 0.1491644830 0.0331147003 0.1491644830 0.0081800668 0.0190280000 206041322 95654128 760807424 0.7180752158 0.2241171449 2.0032861233 533 21.2800000000 0.1496374160 0.0333333171 0.1496374160 0.0081733653 0.0190250000 206042330 95654128 760807424 0.7164403200 0.2229437381 1.9991455078 534 21.3200000000 0.1537881941 0.0335588880 0.1537881941 0.0081690240 0.0190260000 206044938 95654128 760807424 0.7205073237 0.2229533643 1.9859820604 535 21.3600000000 0.1567091942 0.0337890755 0.1567091942 0.0081643717 0.0191090000 206045962 95654128 760807424 0.7249085903 0.2273712307 1.9729367495 536 21.4000000000 0.1570030004 0.0340189522 0.1570030004 0.0081576592 0.0191550000 206048570 95654128 760807424 0.7227040529 0.2270982713 1.9692552090 537 21.4400000000 0.1592987627 0.0342522479 0.1592987627 0.0081506381 0.0191830000 206051378 95654128 760807424 0.7278833985 0.2253084481 1.9536291361 538 21.4800000000 0.1586080194 0.0344833925 0.1592987627 0.0081437480 0.0191350000 206052186 95654128 760807424 0.7273176312 0.2231260985 1.9454332590 539 21.5200000000 0.1584765315 0.0347134354 0.1592987627 0.0081366937 0.0192040000 206055010 95654128 760807424 0.7248227596 0.2219754457 1.9372565746 540 21.5600000000 0.1596210897 0.0349447459 0.1596210897 0.0081304442 0.0193950000 206059286 95654128 760807424 0.7281928658 0.2247669250 1.9239057302 541 21.6000000000 0.1584955156 0.0351731207 0.1596210897 0.0081234633 0.0191660000 206229030 95654128 760807424 0.7294283509 0.2248266786 1.9148545265 542 21.6400000000 0.1595327705 0.0354025666 0.1596210897 0.0081210502 0.0191920000 206231638 95654128 760807424 0.7324721217 0.2238408923 1.9034401178 543 21.6800000000 0.1589503139 0.0356300946 0.1596210897 0.0081140020 0.0191900000 206232662 95654128 760807424 0.7330446839 0.2199055851 1.8979114294 544 21.7200000000 0.1588761359 0.0358566499 0.1596210897 0.0081121628 0.0191780000 206235270 95654128 760807424 0.7340833545 0.2205027044 1.8885989189 545 21.7600000000 0.1589213759 0.0360824567 0.1596210897 0.0081084581 0.0191930000 206238078 95654128 760807424 0.7373022437 0.2196343690 1.8770427704 546 21.8000000000 0.1572288424 0.0363043365 0.1596210897 0.0081120392 0.0191910000 206238886 95654128 760807424 0.7392565012 0.2180281430 1.8706793785 547 21.8400000000 0.1572830081 0.0365255041 0.1596210897 0.0081098518 0.0192010000 206241694 95654128 760807424 0.7415386438 0.2196540385 1.8591148853 548 21.8800000000 0.1573056132 0.0367459058 0.1596210897 0.0081032751 0.0192240000 206242502 95654128 760807424 0.7399807572 0.2213776410 1.8558802605 549 21.9200000000 0.1564205587 0.0369638924 0.1596210897 0.0080973165 0.0192420000 206245310 95654128 760807424 0.7406963110 0.2187697589 1.8493067026 550 21.9600000000 0.1563248038 0.0371809122 0.1596210897 0.0080909153 0.0193820000 206247918 95654128 760807424 0.7398943305 0.2200699300 1.8432580233 551 22.0000000000 0.1564558595 0.0373973822 0.1596210897 0.0080846093 0.0198100000 206248926 95654128 760807424 0.7408019900 0.2212189436 1.8349691629 552 22.0400000000 0.1568888277 0.0376138522 0.1596210897 0.0080777751 0.0194140000 206252626 95654128 760807424 0.7444393635 0.2232130617 1.8277812004 553 22.0800000000 0.1590888202 0.0378335176 0.1596210897 0.0080740663 0.0194330000 206422378 95654128 760807424 0.7422874570 0.2254196256 1.8258938789 554 22.1200000000 0.1611881703 0.0380561794 0.1611881703 0.0080676088 0.0193920000 206424986 95654128 760807424 0.7421019077 0.2259252518 1.8195189238 555 22.1600000000 0.1618216932 0.0382791804 0.1618216932 0.0080609220 0.0193760000 206427794 95654128 760807424 0.7428931594 0.2292214036 1.8128045797 556 22.2000000000 0.1606704593 0.0384993086 0.1618216932 0.0080557510 0.0193590000 206428602 95654128 760807424 0.7426196933 0.2298574001 1.8038170338 557 22.2400000000 0.1603439897 0.0387180602 0.1618216932 0.0080620580 0.0193320000 206431410 95654128 760807424 0.7420873642 0.2262834460 1.8003402948 558 22.2800000000 0.1592857689 0.0389341314 0.1618216932 0.0080551904 0.0193450000 206434018 95654128 760807424 0.7405177355 0.2220691144 1.7944179773 559 22.3200000000 0.1598893702 0.0391505093 0.1618216932 0.0080501670 0.0193410000 206435026 95654128 760807424 0.7393702269 0.2242702395 1.7900843620 560 22.3600000000 0.1618629098 0.0393696386 0.1618629098 0.0080444035 0.0194130000 206437634 95654128 760807424 0.7375102043 0.2264483124 1.7875655890 561 22.4000000000 0.1638973355 0.0395916131 0.1638973355 0.0080383628 0.0196090000 206438642 95654128 760807424 0.7395749688 0.2263883799 1.7811443806 562 22.4400000000 0.1636979729 0.0398124429 0.1638973355 0.0080319227 0.0195610000 206442542 95654128 760807424 0.7388716936 0.2268776149 1.7793771029 563 22.4800000000 0.1649489254 0.0400347102 0.1649489254 0.0080264662 0.0195200000 206614070 95654128 760807424 0.7401140332 0.2278252393 1.7708330154 564 22.5200000000 0.1657355875 0.0402575841 0.1657355875 0.0080223372 0.0194970000 206614878 95654128 760807424 0.7405197620 0.2264986932 1.7657902241 565 22.5600000000 0.1669526249 0.0404818231 0.1669526249 0.0080157356 0.0195410000 206617686 95654128 760807424 0.7426097393 0.2226973623 1.7565025091 566 22.6000000000 0.1649425775 0.0407017184 0.1669526249 0.0080115868 0.0194480000 206618626 95654128 760807424 0.7442130446 0.2196577489 1.7494133711 567 22.6400000000 0.1657240391 0.0409222163 0.1669526249 0.0080054933 0.0194750000 206621434 95654128 760807424 0.7451015711 0.2165634930 1.7464468479 568 22.6800000000 0.1662569046 0.0411428760 0.1669526249 0.0079986071 0.0194620000 206624042 95654128 760807424 0.7473241091 0.2139930129 1.7388831377 569 22.7200000000 0.1643520743 0.0413594124 0.1669526249 0.0079952659 0.0195450000 206626430 95654128 760807424 0.7498636842 0.2100373805 1.7278125286 570 22.7600000000 0.1628177911 0.0415724972 0.1669526249 0.0079929658 0.0194650000 206797814 95654128 760807424 0.7493607402 0.2113503814 1.7171274424 571 22.8000000000 0.1621330529 0.0417836366 0.1669526249 0.0079871133 0.0195600000 206798822 95654128 760807424 0.7494885325 0.2138821036 1.7078379393 572 22.8400000000 0.1618535370 0.0419935490 0.1669526249 0.0079837922 0.0195560000 206801430 95654128 760807424 0.7504333854 0.2104559988 1.6991366148 573 22.8800000000 0.1617806703 0.0422026015 0.1669526249 0.0079809022 0.0196630000 206804238 95654128 760807424 0.7506318688 0.2106982768 1.6896047592 574 22.9200000000 0.1607007533 0.0424090443 0.1669526249 0.0079745557 0.0195700000 206805046 95654128 760807424 0.7484021187 0.2099766284 1.6832475662 575 22.9600000000 0.1614994109 0.0426161580 0.1669526249 0.0079689673 0.0195270000 206807854 95654128 760807424 0.7472250462 0.2075000852 1.6744952202 576 23.0000000000 0.1601710767 0.0428202464 0.1669526249 0.0079646263 0.0195370000 206810462 95654128 760807424 0.7460151315 0.2005317956 1.6676391363 577 23.0400000000 0.1589643210 0.0430215360 0.1669526249 0.0079656811 0.0196340000 206811470 95654128 760807424 0.7449369431 0.2006158382 1.6579126120 578 23.0800000000 0.1600216925 0.0432239584 0.1669526249 0.0079589157 0.0195360000 206814078 95654128 760807424 0.7437090278 0.1998068541 1.6499271393 579 23.1200000000 0.1612557620 0.0434278130 0.1669526249 0.0079523965 0.0195550000 206815086 95654128 760807424 0.7426629066 0.1965335310 1.6427478790 580 23.1600000000 0.1623608619 0.0436328699 0.1669526249 0.0079462420 0.0195450000 206817678 95654128 760807424 0.7417320609 0.1946283877 1.6345423460 581 23.2000000000 0.1618701816 0.0438363765 0.1669526249 0.0079398690 0.0195830000 206820486 95654128 760807424 0.7405628562 0.1943617910 1.6250803471 582 23.2400000000 0.1632516384 0.0440415574 0.1669526249 0.0079347058 0.0195920000 206821294 95654128 760807424 0.7391055226 0.1919467449 1.6163543463 583 23.2800000000 0.1610522270 0.0442422618 0.1669526249 0.0079290928 0.0195670000 206824102 95654128 760807424 0.7397726178 0.1866316199 1.6059094667 584 23.3200000000 0.1588065922 0.0444384336 0.1669526249 0.0079322144 0.0195930000 206824910 95654128 760807424 0.7385290265 0.1855378598 1.5927903652 585 23.3600000000 0.1589624584 0.0446342011 0.1669526249 0.0079262883 0.0196340000 206827718 95654128 760807424 0.7373631001 0.1837952435 1.5825870037 586 23.4000000000 0.1586074084 0.0448286947 0.1669526249 0.0079214267 0.0197370000 206832254 95654128 760807424 0.7370350361 0.1789297909 1.5721999407 587 23.4400000000 0.1564390063 0.0450188315 0.1669526249 0.0079268750 0.0197240000 207002038 95654128 760807424 0.7366376519 0.1765137315 1.5613312721 588 23.4800000000 0.1565328538 0.0452084812 0.1669526249 0.0079366560 0.0197390000 207004646 95654128 760807424 0.7347819805 0.1790141463 1.5347046852 589 23.5200000000 0.1557598561 0.0453961745 0.1669526249 0.0079305619 0.0197820000 207005654 95654128 760807424 0.7332142591 0.1791242659 1.5248737335 590 23.5600000000 0.1530842334 0.0455786966 0.1669526249 0.0079273065 0.0204810000 207008262 95654128 760807424 0.7319855690 0.1786709279 1.5116940737 591 23.6000000000 0.1535992026 0.0457614725 0.1669526249 0.0079272206 0.0200820000 207011334 95654128 760807424 0.7311874032 0.1784928739 1.5000075102 592 23.6400000000 0.1517935693 0.0459405807 0.1669526249 0.0079213209 0.0198400000 207012142 95654128 760807424 0.7309424281 0.1764669716 1.4839119911 593 23.6800000000 0.1485436410 0.0461136044 0.1669526249 0.0079198257 0.0198540000 207014950 95654128 760807424 0.7302351594 0.1742168367 1.4689711332 594 23.7200000000 0.1448324323 0.0462797978 0.1669526249 0.0079186205 0.0199030000 207017558 95654128 760807424 0.7299630642 0.1714325696 1.4542815685 595 23.7600000000 0.1436577588 0.0464434582 0.1669526249 0.0079162053 0.0199310000 207018566 95654128 760807424 0.7280483246 0.1697369367 1.4444578886 596 23.8000000000 0.1444553286 0.0466079076 0.1669526249 0.0079121954 0.0199950000 207021174 95654128 760807424 0.7264143825 0.1699270010 1.4337947369 597 23.8400000000 0.1447916180 0.0467723695 0.1669526249 0.0079064261 0.0200680000 207022314 95654128 760807424 0.7240251303 0.1729799956 1.4232915640 598 23.8800000000 0.1451416761 0.0469368666 0.1669526249 0.0079006799 0.0200620000 207024922 95654128 760807424 0.7229449749 0.1735433489 1.4103256464 599 23.9200000000 0.1424293220 0.0470962864 0.1669526249 0.0078952849 0.0200490000 207027730 95654128 760807424 0.7209024429 0.1741003096 1.3979659081 600 23.9600000000 0.1415933818 0.0472537816 0.1669526249 0.0078916811 0.0200660000 207028618 95654128 760807424 0.7193292379 0.1734239608 1.3863722086 601 24.0000000000 0.1415702999 0.0474107142 0.1669526249 0.0078857395 0.0201010000 207031426 95654128 760807424 0.7169583440 0.1738734543 1.3764262199 602 24.0400000000 0.1417752653 0.0475674660 0.1669526249 0.0078793673 0.0201290000 207032366 95654128 760807424 0.7152491808 0.1735639870 1.3646562099 603 24.0800000000 0.1400108635 0.0477207718 0.1669526249 0.0078736121 0.0201850000 207035174 95654128 760807424 0.7124314308 0.1715759188 1.3551213741 604 24.1200000000 0.1396482140 0.0478729695 0.1669526249 0.0078674713 0.0201920000 207037782 95654128 760807424 0.7093684673 0.1732381731 1.3458743095 605 24.1600000000 0.1384894848 0.0480227489 0.1669526249 0.0078622644 0.0202170000 207038790 95654128 760807424 0.7065996528 0.1699422896 1.3370481730 606 24.2000000000 0.1391281486 0.0481730878 0.1669526249 0.0078560947 0.0202410000 207041398 95654128 760807424 0.7041949034 0.1693823338 1.3290942907 607 24.2400000000 0.1400512606 0.0483244522 0.1669526249 0.0078500720 0.0202820000 207042406 95654128 760807424 0.7022464275 0.1694878042 1.3175150156 608 24.2800000000 0.1395327598 0.0484744659 0.1669526249 0.0078439946 0.0204420000 207045014 95654128 760807424 0.6995867491 0.1700637490 1.3090671301 609 24.3200000000 0.1387471557 0.0486226969 0.1669526249 0.0078411434 0.0203410000 207047954 95654128 760807424 0.6981205940 0.1648060232 1.3005679846 610 24.3600000000 0.1403462738 0.0487730634 0.1669526249 0.0078352485 0.0213110000 207048762 95654128 760807424 0.6959758401 0.1624731570 1.2936363220 611 24.4000000000 0.1403696984 0.0489229761 0.1669526249 0.0078354813 0.0204480000 207051570 95654128 760807424 0.6948149800 0.1626328379 1.2796353102 612 24.4400000000 0.1388765424 0.0490699590 0.1669526249 0.0078314215 0.0205220000 207055886 95654128 760807424 0.6923875213 0.1619729549 1.2694135904 613 24.4800000000 0.1388028711 0.0492163422 0.1669526249 0.0078267847 0.0204510000 207225662 95654128 760807424 0.6903485060 0.1583269387 1.2629923820 614 24.5200000000 0.1398931295 0.0493640243 0.1669526249 0.0078207355 0.0204920000 207228402 95654128 760807424 0.6886221766 0.1559002995 1.2518222332 615 24.5600000000 0.1407646835 0.0495126433 0.1669526249 0.0078148169 0.0205090000 207229410 95654128 760807424 0.6872044802 0.1548859477 1.2444458008 616 24.6000000000 0.1411640942 0.0496614281 0.1669526249 0.0078090797 0.0205990000 207232018 95654128 760807424 0.6859681606 0.1519913673 1.2343091965 617 24.6400000000 0.1391495466 0.0498064655 0.1669526249 0.0078078412 0.0205310000 207234826 95654128 760807424 0.6843881607 0.1476799995 1.2224690914 618 24.6800000000 0.1392275691 0.0499511599 0.1669526249 0.0078061281 0.0206210000 207235898 95654128 760807424 0.6834481359 0.1447712332 1.2104915380 619 24.7200000000 0.1388562173 0.0500947868 0.1669526249 0.0078068383 0.0206470000 207238706 95654128 760807424 0.6827087402 0.1429401040 1.1956541538 620 24.7600000000 0.1391406208 0.0502384091 0.1669526249 0.0078032594 0.0206410000 207239514 95654128 760807424 0.6800780892 0.1433254778 1.1876175404 621 24.8000000000 0.1396401078 0.0503823732 0.1669526249 0.0077977657 0.0206920000 207242322 95654128 760807424 0.6788428426 0.1439480931 1.1777365208 622 24.8400000000 0.1386911422 0.0505243487 0.1669526249 0.0077920837 0.0207440000 207245062 95654128 760807424 0.6773002744 0.1408113539 1.1665894985 623 24.8800000000 0.1381305903 0.0506649687 0.1669526249 0.0077881771 0.0207160000 207246070 95654128 760807424 0.6753398776 0.1397773772 1.1562592983 624 24.9200000000 0.1361772865 0.0508020077 0.1669526249 0.0077841649 0.0207950000 207248678 95654128 760807424 0.6731827259 0.1403754205 1.1431717873 625 24.9600000000 0.1371413618 0.0509401506 0.1669526249 0.0077785760 0.0209750000 207252334 95654128 760807424 0.6705917120 0.1405263543 1.1338119507 626 25.0000000000 0.1371759474 0.0510779075 0.1669526249 0.0077736733 0.0208730000 207423726 95654128 760807424 0.6687598825 0.1384498775 1.1245230436 627 25.0400000000 0.1357374638 0.0512129307 0.1669526249 0.0077701810 0.0212460000 207426534 95654128 760807424 0.6663864255 0.1361999810 1.1138658524 628 25.0800000000 0.1345670521 0.0513456602 0.1669526249 0.0077651784 0.0209110000 207427342 95654128 760807424 0.6632114053 0.1377515495 1.1032098532 629 25.1200000000 0.1345777214 0.0514779846 0.1669526249 0.0077627889 0.0213750000 207430150 95654128 760807424 0.6607549787 0.1353092790 1.0979373455 630 25.1600000000 0.1355192512 0.0516113835 0.1669526249 0.0077572772 0.0212650000 207432758 95654128 760807424 0.6573140025 0.1358945370 1.0897486210 631 25.2000000000 0.1350896060 0.0517436786 0.1669526249 0.0077526776 0.0208670000 207433766 95654128 760807424 0.6536132693 0.1363555342 1.0811581612 632 25.2400000000 0.1335575730 0.0518731309 0.1669526249 0.0077499701 0.0209670000 207436374 95654128 760807424 0.6502697468 0.1351404339 1.0736036301 633 25.2800000000 0.1326476336 0.0520007368 0.1669526249 0.0077454140 0.0208920000 207437382 95654128 760807424 0.6466825008 0.1348253787 1.0628421307 634 25.3200000000 0.1320148110 0.0521269420 0.1669526249 0.0077432972 0.0208880000 207439990 95654128 760807424 0.6418631077 0.1350730509 1.0550769567 635 25.3600000000 0.1316701621 0.0522522069 0.1669526249 0.0077434408 0.0209110000 207442798 95654128 760807424 0.6380693316 0.1354626119 1.0490568876 636 25.4000000000 0.1303120255 0.0523749424 0.1669526249 0.0077445528 0.0208560000 207443606 95654128 760807424 0.6349335313 0.1315836906 1.0394018888 637 25.4400000000 0.1295581907 0.0524961092 0.1669526249 0.0077392022 0.0209050000 207446414 95654128 760807424 0.6309670806 0.1318331212 1.0317813158 638 25.4800000000 0.1291716695 0.0526162904 0.1669526249 0.0077343855 0.0209360000 207447222 95654128 760807424 0.6277952790 0.1298389137 1.0236252546 639 25.5200000000 0.1289173812 0.0527356974 0.1669526249 0.0077293207 0.0209330000 207450030 95654128 760807424 0.6229452491 0.1290840358 1.0171544552 640 25.5600000000 0.1271770447 0.0528520120 0.1669526249 0.0077245302 0.0208670000 207452638 95654128 760807424 0.6192253232 0.1262715906 1.0099636316 641 25.6000000000 0.1277012676 0.0529687815 0.1669526249 0.0077189523 0.0212640000 207453646 95654128 760807424 0.6145566702 0.1252366751 1.0044906139 642 25.6400000000 0.1274162978 0.0530847434 0.1669526249 0.0077142447 0.0210580000 207458506 95654128 760807424 0.6093953848 0.1245569065 0.9991277456 643 25.6800000000 0.1270388514 0.0531997575 0.1669526249 0.0077090479 0.0209210000 207628302 95654128 760807424 0.6047646999 0.1229064092 0.9920235276 644 25.7200000000 0.1275610775 0.0533152254 0.1669526249 0.0077030771 0.0209520000 207630910 95654128 760807424 0.5994697809 0.1219553724 0.9881565571 645 25.7600000000 0.1275512129 0.0534303200 0.1669526249 0.0076973238 0.0209680000 207633718 95654128 760807424 0.5947720408 0.1196622401 0.9822682142 646 25.8000000000 0.1263665259 0.0535432243 0.1669526249 0.0076919827 0.0209760000 207634526 95654128 760807424 0.5885953307 0.1179628149 0.9770958424 647 25.8400000000 0.1249457747 0.0536535837 0.1669526249 0.0076864748 0.0217990000 207637334 95654128 760807424 0.5817486048 0.1178283468 0.9700933695 648 25.8800000000 0.1243871450 0.0537627405 0.1669526249 0.0076846333 0.0211860000 207639942 95654128 760807424 0.5752349496 0.1169404462 0.9652335048 649 25.9200000000 0.1239967868 0.0538709593 0.1669526249 0.0076823839 0.0210100000 207640950 95654128 760807424 0.5681829453 0.1141264513 0.9600870609 650 25.9600000000 0.1249090359 0.0539802487 0.1669526249 0.0076783705 0.0210280000 207643558 95654128 760807424 0.5550206900 0.1087352559 0.9524784684 651 26.0000000000 0.1240401492 0.0540878676 0.1669526249 0.0076827963 0.0209770000 207644566 95654128 760807424 0.5384699106 0.1088154316 0.9418886900 652 26.0400000000 0.1220340878 0.0541920796 0.1669526249 0.0076783473 0.0209580000 207647174 95654128 760807424 0.5290324688 0.1088193282 0.9337860942 653 26.0800000000 0.1203787178 0.0542934374 0.1669526249 0.0076772392 0.0210250000 207649982 95654128 760807424 0.5191293955 0.1104979217 0.9281755686 654 26.1200000000 0.1189863235 0.0543923562 0.1669526249 0.0076798006 0.0210100000 207650790 95654128 760807424 0.5091300607 0.1105142385 0.9228394628 655 26.1600000000 0.1190110818 0.0544910107 0.1669526249 0.0076752785 0.0210410000 207653598 95654128 760807424 0.4997218847 0.1081678495 0.9172615409 656 26.2000000000 0.1183545515 0.0545883637 0.1669526249 0.0076754438 0.0211050000 207654406 95654128 760807424 0.4893477261 0.1092777401 0.9122288823 657 26.2400000000 0.1172010303 0.0546836645 0.1669526249 0.0076765104 0.0211990000 207657214 95654128 760807424 0.4790597558 0.1097215712 0.9071469903 658 26.2800000000 0.1163772270 0.0547774237 0.1669526249 0.0076788532 0.0211560000 207659822 95654128 760807424 0.4682295322 0.1112453490 0.9016386271 659 26.3200000000 0.1150404587 0.0548688699 0.1669526249 0.0076757990 0.0210460000 207660830 95654128 760807424 0.4567761123 0.1132272258 0.8972058892 660 26.3600000000 0.1143554971 0.0549590012 0.1669526249 0.0076706719 0.0210640000 207663438 95654128 760807424 0.4461558759 0.1141083091 0.8929316998 661 26.4000000000 0.1132905707 0.0550472486 0.1669526249 0.0076656053 0.0213800000 207664446 95654128 760807424 0.4344330728 0.1162282005 0.8879417777 662 26.4400000000 0.1125656143 0.0551341344 0.1669526249 0.0076641780 0.0212490000 207670330 95654128 760807424 0.4226674736 0.1195377484 0.8854208589 663 26.4800000000 0.1128027588 0.0552211157 0.1669526249 0.0076773633 0.0211600000 207841862 95654128 760807424 0.4121953547 0.1195623428 0.8822224736 664 26.5200000000 0.1118848324 0.0553064526 0.1669526249 0.0076829472 0.0211140000 207842670 95654128 760807424 0.4016840756 0.1162977815 0.8750993609 665 26.5600000000 0.1118379459 0.0553914624 0.1669526249 0.0076776695 0.0211460000 207845478 95654128 760807424 0.3913229704 0.1176973805 0.8718091846 666 26.6000000000 0.1110279262 0.0554750006 0.1669526249 0.0076737786 0.0221310000 207848086 95654128 760807424 0.3803879917 0.1190307438 0.8676734567 667 26.6400000000 0.1112928912 0.0555586856 0.1669526249 0.0076760671 0.0212350000 207849094 95654128 760807424 0.3698577881 0.1225401238 0.8663243651 668 26.6800000000 0.1101344377 0.0556403859 0.1669526249 0.0076959495 0.0211350000 207851702 95654128 760807424 0.3588936627 0.1258661747 0.8619446158 669 26.7200000000 0.1094801128 0.0557208638 0.1669526249 0.0077404929 0.0211470000 207852710 95654128 760807424 0.3479511440 0.1266481727 0.8584422469 670 26.7600000000 0.1089092642 0.0558002494 0.1669526249 0.0077685962 0.0211240000 207855318 95654128 760807424 0.3383924365 0.1263995916 0.8546136618 671 26.8000000000 0.1090331897 0.0558795832 0.1669526249 0.0077743067 0.0211260000 207858126 95654128 760807424 0.3289153874 0.1270109266 0.8508552909 672 26.8400000000 0.1083166376 0.0559576145 0.1669526249 0.0077702831 0.0211020000 207858934 95654128 760807424 0.3194213808 0.1294145286 0.8459084034 673 26.8800000000 0.1082494780 0.0560353142 0.1669526249 0.0077655346 0.0211770000 207861742 95654128 760807424 0.3106070757 0.1301209778 0.8421387672 674 26.9200000000 0.1075320989 0.0561117189 0.1669526249 0.0077601759 0.0211350000 207862550 95654128 760807424 0.3018733263 0.1304999590 0.8377491236 675 26.9600000000 0.1067856327 0.0561867914 0.1669526249 0.0077546096 0.0211600000 207865358 95654128 760807424 0.2933987677 0.1325394511 0.8339732885 676 27.0000000000 0.1059859917 0.0562604588 0.1669526249 0.0077503719 0.0211410000 207867966 95654128 760807424 0.2846660614 0.1367481798 0.8296694160 677 27.0400000000 0.1059095562 0.0563337957 0.1669526249 0.0077564411 0.0211620000 207868974 95654128 760807424 0.2758811414 0.1398332864 0.8276991844 678 27.0800000000 0.1062628850 0.0564074375 0.1669526249 0.0077673836 0.0211510000 207871582 95654128 760807424 0.2676373124 0.1424255818 0.8245491982 679 27.1200000000 0.1057793200 0.0564801501 0.1669526249 0.0077786355 0.0211340000 207872590 95654128 760807424 0.2590999007 0.1443046778 0.8203684092 680 27.1600000000 0.1056703329 0.0565524886 0.1669526249 0.0077791796 0.0211570000 207875198 95654128 760807424 0.2512879074 0.1441124529 0.8153968453 681 27.2000000000 0.1050837860 0.0566237534 0.1669526249 0.0077739194 0.0211540000 207878006 95654128 760807424 0.2433321476 0.1450249404 0.8113303781 682 27.2400000000 0.1046626866 0.0566941917 0.1669526249 0.0077686058 0.0211540000 207878814 95654128 760807424 0.2352983356 0.1489377767 0.8065288067 683 27.2800000000 0.1037084907 0.0567630267 0.1669526249 0.0077685184 0.0212140000 207884706 95654128 760807424 0.2276565880 0.1509807855 0.8014168143 684 27.3200000000 0.1034671739 0.0568313076 0.1669526249 0.0077713395 0.0212180000 208056090 95654128 760807424 0.2196107209 0.1525773704 0.7967430949 685 27.3600000000 0.1027563959 0.0568983515 0.1669526249 0.0077710011 0.0211480000 208057098 95654128 760807424 0.2117804736 0.1523768902 0.7906616330 686 27.4000000000 0.1022278965 0.0569644296 0.1669526249 0.0077667830 0.0211520000 208059706 95654128 760807424 0.2036891878 0.1563706845 0.7845649719 687 27.4400000000 0.1021088436 0.0570301420 0.1669526249 0.0077737435 0.0211830000 208060714 95654128 760807424 0.1957394034 0.1600125432 0.7788578868 688 27.4800000000 0.1010987908 0.0570941952 0.1669526249 0.0077903679 0.0211600000 208063322 95654128 760807424 0.1873731315 0.1607222706 0.7724226117 689 27.5200000000 0.1014533341 0.0571585771 0.1669526249 0.0077981710 0.0212180000 208066130 95654128 760807424 0.1795053482 0.1633471996 0.7672182322 690 27.5600000000 0.1014495566 0.0572227670 0.1669526249 0.0077991172 0.0211500000 208066938 95654128 760807424 0.1717486233 0.1645361930 0.7607435584 691 27.6000000000 0.1007736474 0.0572857928 0.1669526249 0.0078008322 0.0211050000 208069746 95654128 760807424 0.1630866528 0.1680832505 0.7541739941 692 27.6400000000 0.1001676470 0.0573477608 0.1669526249 0.0078174945 0.0211560000 208070554 95654128 760807424 0.1547086388 0.1708205342 0.7477185130 693 27.6800000000 0.1002575979 0.0574096798 0.1669526249 0.0078489293 0.0210830000 208073362 95654128 760807424 0.1469842643 0.1709869355 0.7409199476 694 27.7200000000 0.1001625136 0.0574712833 0.1669526249 0.0078623117 0.0210720000 208075970 95654128 760807424 0.1399399489 0.1708177775 0.7326674461 695 27.7600000000 0.0998540670 0.0575322657 0.1669526249 0.0078611618 0.0209450000 208076978 95654128 760807424 0.1329772770 0.1700470150 0.7249048948 696 27.8000000000 0.0996818915 0.0575928255 0.1669526249 0.0078567958 0.0210960000 208079586 95654128 760807424 0.1257477552 0.1723805964 0.7176432610 697 27.8400000000 0.0990218073 0.0576522645 0.1669526249 0.0078545906 0.0211310000 208080594 95654128 760807424 0.1181363240 0.1749990135 0.7103996277 698 27.8800000000 0.0985489935 0.0577108558 0.1669526249 0.0078561449 0.0210810000 208083202 95654128 760807424 0.1096657738 0.1791067421 0.7037836313 699 27.9200000000 0.0975378156 0.0577678329 0.1669526249 0.0078654074 0.0211780000 208086010 95654128 760807424 0.1015729457 0.1827250272 0.6964783072 700 27.9600000000 0.0966609344 0.0578233945 0.1669526249 0.0078818518 0.0211750000 208086818 95654128 760807424 0.0934090465 0.1854216456 0.6890391707 701 28.0000000000 0.0961719602 0.0578781000 0.1669526249 0.0079001920 0.0212220000 208091606 95654128 760807424 0.0855312347 0.1874842793 0.6825333238 702 28.0400000000 0.0955878571 0.0579318176 0.1669526249 0.0079133550 0.0217880000 208262994 95654128 760807424 0.0777342469 0.1886169761 0.6755633354 703 28.0800000000 0.0952671915 0.0579849262 0.1669526249 0.0079195749 0.0213590000 208264002 95654128 760807424 0.0707541779 0.1898361295 0.6703193188 704 28.1200000000 0.0945643634 0.0580368856 0.1669526249 0.0079243064 0.0211190000 208266610 95654128 760807424 0.0623318106 0.1960435957 0.6651715040 705 28.1600000000 0.0942301154 0.0580882236 0.1669526249 0.0079467003 0.0212890000 208267618 95654128 760807424 0.0542533845 0.2003152519 0.6605807543 706 28.2000000000 0.0939566419 0.0581390287 0.1669526249 0.0079649001 0.0210420000 208270226 95654128 760807424 0.0469204262 0.2002700120 0.6559223533 707 28.2400000000 0.0932011381 0.0581886215 0.1669526249 0.0079669003 0.0210370000 208273034 95654128 760807424 0.0396090224 0.2034365833 0.6514562368 708 28.2800000000 0.0929857343 0.0582377699 0.1669526249 0.0079642786 0.0210170000 208273842 95654128 760807424 0.0315857530 0.2079353780 0.6481616497 709 28.3200000000 0.0927232578 0.0582864096 0.1669526249 0.0079595712 0.0209230000 208276650 95654128 760807424 0.0252562128 0.2048843056 0.6447550058 710 28.3600000000 0.0925874040 0.0583347208 0.1669526249 0.0079559500 0.0209330000 208277458 95654128 760807424 0.0186131001 0.2066800892 0.6407660246 711 28.4000000000 0.0913803056 0.0583811984 0.1669526249 0.0079505324 0.0209540000 208280266 95654128 760807424 0.0106457556 0.2134229243 0.6382709742 712 28.4400000000 0.0910791755 0.0584271226 0.1669526249 0.0079472782 0.0209140000 208282874 95654128 760807424 0.0026696427 0.2157360017 0.6352871656 713 28.4800000000 0.0913800746 0.0584733399 0.1669526249 0.0079449013 0.0209160000 208283882 95654128 760807424 -0.0024089217 0.2136621475 0.6338878274 714 28.5200000000 0.0902380049 0.0585178282 0.1669526249 0.0079609153 0.0208640000 208286490 95654128 760807424 -0.0103677530 0.2206195444 0.6321172714 715 28.5600000000 0.0893231556 0.0585609126 0.1669526249 0.0079557983 0.0208690000 208287498 95654128 760807424 -0.0190269966 0.2268359065 0.6307094097 716 28.6000000000 0.0892921165 0.0586038333 0.1669526249 0.0079558410 0.0209170000 208290106 95654128 760807424 -0.0257643014 0.2291628420 0.6323087811 717 28.6400000000 0.0888642967 0.0586460375 0.1669526249 0.0079529230 0.0209110000 208292914 95654128 760807424 -0.0323443860 0.2309291214 0.6340064406 718 28.6800000000 0.0886468962 0.0586878215 0.1669526249 0.0079482736 0.0208870000 208293722 95654128 760807424 -0.0395040400 0.2361906767 0.6362540722 719 28.7200000000 0.0885284767 0.0587293245 0.1669526249 0.0079467850 0.0208930000 208296530 95654128 760807424 -0.0471194759 0.2396402210 0.6380156279 720 28.7600000000 0.0889980495 0.0587713644 0.1669526249 0.0079437599 0.0208970000 208299138 95654128 760807424 -0.0545194037 0.2432443649 0.6416254640 721 28.8000000000 0.0889492631 0.0588132200 0.1669526249 0.0079385973 0.0218870000 208300146 95654128 760807424 -0.0614690334 0.2451082766 0.6452778578 722 28.8400000000 0.0884994119 0.0588543366 0.1669526249 0.0079335095 0.0210010000 208302754 95654128 760807424 -0.0695357248 0.2479883432 0.6480299830 723 28.8800000000 0.0886353552 0.0588955275 0.1669526249 0.0079280481 0.0208940000 208303762 95654128 760807424 -0.0773317665 0.2503503859 0.6525223851 724 28.9200000000 0.0886544511 0.0589366310 0.1669526249 0.0079226663 0.0208760000 208306370 95654128 760807424 -0.0857659802 0.2535147369 0.6568221450 725 28.9600000000 0.0880765393 0.0589768239 0.1669526249 0.0079200532 0.0208630000 208309178 95654128 760807424 -0.0945241600 0.2563506961 0.6610101461 726 29.0000000000 0.0879691169 0.0590167582 0.1669526249 0.0079253635 0.0209620000 208312242 95654128 760807424 -0.1031578928 0.2572139204 0.6665331125 727 29.0400000000 0.0882516801 0.0590569713 0.1669526249 0.0079265336 0.0209210000 208483854 95654128 760807424 -0.1123658568 0.2611208856 0.6711298823 728 29.0800000000 0.0887790471 0.0590977984 0.1669526249 0.0079277897 0.0208050000 208484662 95654128 760807424 -0.1210264713 0.2650340199 0.6773275733 729 29.1200000000 0.0894475803 0.0591394304 0.1669526249 0.0079244124 0.0208340000 208487470 95654128 760807424 -0.1299682409 0.2700102031 0.6827789545 730 29.1600000000 0.0893985629 0.0591808813 0.1669526249 0.0079205685 0.0208480000 208490078 95654128 760807424 -0.1387459934 0.2717022002 0.6886526346 731 29.2000000000 0.0888572186 0.0592214782 0.1669526249 0.0079162934 0.0208600000 208491086 95654128 760807424 -0.1481871456 0.2739589512 0.6939797401 732 29.2400000000 0.0887090266 0.0592617617 0.1669526249 0.0079120282 0.0208040000 208493694 95654128 760807424 -0.1583911479 0.2783989906 0.6996572614 733 29.2800000000 0.0892097950 0.0593026185 0.1669526249 0.0079071402 0.0208630000 208494702 95654128 760807424 -0.1683044732 0.2828022242 0.7069308162 734 29.3200000000 0.0892165229 0.0593433732 0.1669526249 0.0079029056 0.0207930000 208497310 95654128 760807424 -0.1780658811 0.2869247496 0.7142649889 735 29.3600000000 0.0891859010 0.0593839752 0.1669526249 0.0078999241 0.0207670000 208500118 95654128 760807424 -0.1873524487 0.2908080220 0.7213809490 736 29.4000000000 0.0890514627 0.0594242843 0.1669526249 0.0078960225 0.0207340000 208500926 95654128 760807424 -0.1961212307 0.2952576280 0.7294403911 737 29.4400000000 0.0894708186 0.0594650530 0.1669526249 0.0078915227 0.0206980000 208503734 95654128 760807424 -0.2050531060 0.2992902100 0.7366448045 738 29.4800000000 0.0897940397 0.0595061492 0.1669526249 0.0078912571 0.0207320000 208506342 95654128 760807424 -0.2141090035 0.3031572402 0.7445319891 739 29.5200000000 0.0900346413 0.0595474598 0.1669526249 0.0079059970 0.0206670000 208507350 95654128 760807424 -0.2221867591 0.3068751693 0.7521254420 740 29.5600000000 0.0907359868 0.0595896064 0.1669526249 0.0079241752 0.0207340000 208509958 95654128 760807424 -0.2292846590 0.3106397688 0.7607045770 741 29.6000000000 0.0906816795 0.0596315660 0.1669526249 0.0079521805 0.0206830000 208510966 95654128 760807424 -0.2367854714 0.3147328496 0.7688384652 742 29.6400000000 0.0915254354 0.0596745497 0.1669526249 0.0079689075 0.0206570000 208513574 95654128 760807424 -0.2433707714 0.3195286691 0.7774195671 743 29.6800000000 0.0925122872 0.0597187458 0.1669526249 0.0079677241 0.0206380000 208516382 95654128 760807424 -0.2485411167 0.3220088184 0.7852888703 744 29.7200000000 0.0922088549 0.0597624153 0.1669526249 0.0079625986 0.0206150000 208517190 95654128 760807424 -0.2538453341 0.3232197165 0.7920249104 745 29.7600000000 0.0922262073 0.0598059909 0.1669526249 0.0079592011 0.0206720000 208519998 95654128 760807424 -0.2592375576 0.3257535994 0.7983564734 746 29.8000000000 0.0927615836 0.0598501673 0.1669526249 0.0079553559 0.0205990000 208520806 95654128 760807424 -0.2642513514 0.3286097944 0.8039284945 747 29.8400000000 0.0930580348 0.0598946223 0.1669526249 0.0079502776 0.0206030000 208523614 95654128 760807424 -0.2696482539 0.3325166106 0.8086132407 748 29.8800000000 0.0930729434 0.0599389783 0.1669526249 0.0079481890 0.0207230000 208529206 95654128 760807424 -0.2750758827 0.3360916972 0.8134489655 749 29.9200000000 0.0935385525 0.0599838376 0.1669526249 0.0079445637 0.0207280000 208699006 95654128 760807424 -0.2788342834 0.3400622606 0.8197330832 750 29.9600000000 0.0937848315 0.0600289056 0.1669526249 0.0079419049 0.0206650000 208701614 95654128 760807424 -0.2826976776 0.3433211148 0.8253578544 751 30.0000000000 0.0947705954 0.0600751661 0.1669526249 0.0079383517 0.0206770000 208702622 95654128 760807424 -0.2870370150 0.3466477394 0.8294678926 752 30.0400000000 0.0952580869 0.0601219519 0.1669526249 0.0079343873 0.0206100000 208705230 95654128 760807424 -0.2907133102 0.3502154052 0.8331993818 753 30.0800000000 0.0953028128 0.0601686729 0.1669526249 0.0079354499 0.0206560000 208708038 95654128 760807424 -0.2951572537 0.3517157733 0.8361561894 754 30.1200000000 0.0958160311 0.0602159505 0.1669526249 0.0079416587 0.0206360000 208708846 95654128 760807424 -0.2990876734 0.3542607427 0.8396437168 755 30.1600000000 0.0961889252 0.0602635968 0.1669526249 0.0079536753 0.0205910000 208711654 95654128 760807424 -0.3032099009 0.3562600613 0.8427768350 756 30.2000000000 0.0969023928 0.0603120609 0.1669526249 0.0079621240 0.0206220000 208714262 95654128 760807424 -0.3076485991 0.3601739705 0.8457154632 757 30.2400000000 0.0968243927 0.0603602938 0.1669526249 0.0079643954 0.0205610000 208715270 95654128 760807424 -0.3126460612 0.3631689250 0.8481374979 758 30.2800000000 0.0966477022 0.0604081664 0.1669526249 0.0079687938 0.0205670000 208717878 95654128 760807424 -0.3178380728 0.3642696142 0.8517647982 759 30.3200000000 0.0958644077 0.0604548808 0.1669526249 0.0079911955 0.0215710000 208718886 95654128 760807424 -0.3230801225 0.3663144708 0.8554820418 760 30.3600000000 0.0961012766 0.0605017839 0.1669526249 0.0080052244 0.0206370000 208721494 95654128 760807424 -0.3290144503 0.3720513880 0.8584091067 761 30.4000000000 0.0955590233 0.0605478513 0.1669526249 0.0080202951 0.0205800000 208724302 95654128 760807424 -0.3356772959 0.3740421534 0.8619121909 762 30.4400000000 0.0954569653 0.0605936638 0.1669526249 0.0080257567 0.0206770000 208725110 95654128 760807424 -0.3428330123 0.3770176470 0.8643355966 763 30.4800000000 0.0952125192 0.0606390358 0.1669526249 0.0080245912 0.0205940000 208727918 95654128 760807424 -0.3498413265 0.3813220263 0.8656581640 764 30.5200000000 0.0953573212 0.0606844786 0.1669526249 0.0080244728 0.0206230000 208728726 95654128 760807424 -0.3572474718 0.3857360482 0.8678566813 765 30.5600000000 0.0954686105 0.0607299480 0.1669526249 0.0080227263 0.0205410000 208731534 95654128 760807424 -0.3649230897 0.3901630938 0.8695369363 766 30.6000000000 0.0948211178 0.0607744535 0.1669526249 0.0080230758 0.0205730000 208734142 95654128 760807424 -0.3723320067 0.3929718137 0.8721688986 767 30.6400000000 0.0938999727 0.0608176419 0.1669526249 0.0080217022 0.0205820000 208735150 95654128 760807424 -0.3796658516 0.3968567252 0.8740052581 768 30.6800000000 0.0941675231 0.0608610662 0.1669526249 0.0080230705 0.0206390000 208737758 95654128 760807424 -0.3875920475 0.4015195370 0.8755139112 769 30.7200000000 0.0950745568 0.0609055571 0.1669526249 0.0080235549 0.0207310000 208741290 95654128 760807424 -0.3963680565 0.4069828689 0.8768202662 770 30.7600000000 0.0952021107 0.0609500981 0.1669526249 0.0080220247 0.0206030000 208912706 95654128 760807424 -0.4053347707 0.4111031592 0.8782214522 771 30.8000000000 0.0948732495 0.0609940970 0.1669526249 0.0080181418 0.0206560000 208915514 95654128 760807424 -0.4131927788 0.4152994156 0.8791414499 772 30.8400000000 0.0945199654 0.0610375243 0.1669526249 0.0080169091 0.0206060000 208916322 95654128 760807424 -0.4213012755 0.4177551568 0.8801367879 773 30.8800000000 0.0942068398 0.0610804341 0.1669526249 0.0080177508 0.0206710000 208919130 95654128 760807424 -0.4301431179 0.4202009141 0.8811672926 774 30.9200000000 0.0944592208 0.0611235592 0.1669526249 0.0080202811 0.0206450000 208921738 95654128 760807424 -0.4382767677 0.4233373106 0.8817109466 775 30.9600000000 0.0941349864 0.0611661545 0.1669526249 0.0080264047 0.0206190000 208922746 95654128 760807424 -0.4461622536 0.4248737097 0.8832440376 776 31.0000000000 0.0942102373 0.0612087371 0.1669526249 0.0080336454 0.0206800000 208925354 95654128 760807424 -0.4543521702 0.4274114370 0.8844615817 777 31.0400000000 0.0943314359 0.0612513661 0.1669526249 0.0080451454 0.0213580000 208926362 95654128 760807424 -0.4625583887 0.4312226772 0.8851093054 778 31.0800000000 0.0937689468 0.0612931625 0.1669526249 0.0080491124 0.0210290000 208928970 95654128 760807424 -0.4704972208 0.4340501428 0.8864588737 779 31.1200000000 0.0937299654 0.0613348015 0.1669526249 0.0080480728 0.0206740000 208931778 95654128 760807424 -0.4785645902 0.4360241592 0.8880769014 780 31.1600000000 0.0936404690 0.0613762190 0.1669526249 0.0080479494 0.0206590000 208932586 95654128 760807424 -0.4858172536 0.4390982687 0.8888458014 781 31.2000000000 0.0939968675 0.0614179868 0.1669526249 0.0080459224 0.0206190000 208935394 95654128 760807424 -0.4935508072 0.4420104325 0.8898336291 782 31.2400000000 0.0941615775 0.0614598584 0.1669526249 0.0080420797 0.0206220000 208936202 95654128 760807424 -0.5010105968 0.4434921741 0.8903555274 783 31.2800000000 0.0942724273 0.0615017646 0.1669526249 0.0080380532 0.0206770000 208939010 95654128 760807424 -0.5088308454 0.4448432624 0.8910579085 784 31.3200000000 0.0946075618 0.0615439914 0.1669526249 0.0080333707 0.0206390000 208941618 95654128 760807424 -0.5154914856 0.4464124739 0.8930242062 785 31.3600000000 0.0949215814 0.0615865106 0.1669526249 0.0080284369 0.0206480000 208942626 95654128 760807424 -0.5218927860 0.4476976395 0.8930752277 786 31.4000000000 0.0949408859 0.0616289462 0.1669526249 0.0080255197 0.0206910000 208945234 95654128 760807424 -0.5277362466 0.4491907060 0.8941603303 787 31.4400000000 0.0951475352 0.0616715365 0.1669526249 0.0080216353 0.0206690000 208946242 95654128 760807424 -0.5333632231 0.4516024292 0.8953112364 788 31.4800000000 0.0955596045 0.0617145417 0.1669526249 0.0080188071 0.0207030000 208948850 95654128 760807424 -0.5389105678 0.4527485371 0.8966585398 789 31.5200000000 0.0958511904 0.0617578074 0.1669526249 0.0080164599 0.0207740000 208951658 95654128 760807424 -0.5447940826 0.4527367651 0.8972210884 790 31.5600000000 0.0960436314 0.0618012072 0.1669526249 0.0080118651 0.0206960000 208952466 95654128 760807424 -0.5502049923 0.4529562891 0.8982527256 791 31.6000000000 0.0963588580 0.0618448958 0.1669526249 0.0080073277 0.0207920000 208955274 95654128 760807424 -0.5541129708 0.4545588791 0.8993675113 792 31.6400000000 0.0963757411 0.0618884953 0.1669526249 0.0080023304 0.0207320000 208957882 95654128 760807424 -0.5579982996 0.4543832541 0.9014315605 793 31.6800000000 0.0967398882 0.0619324441 0.1669526249 0.0079983084 0.0207770000 208958890 95654128 760807424 -0.5623030066 0.4536854625 0.9024716616 794 31.7200000000 0.0970769376 0.0619767067 0.1669526249 0.0079993899 0.0207860000 208961498 95654128 760807424 -0.5659024119 0.4527295530 0.9039998651 795 31.7600000000 0.0972021371 0.0620210154 0.1669526249 0.0080102172 0.0207810000 208962506 95654128 760807424 -0.5687301159 0.4522762597 0.9052488804 796 31.8000000000 0.0975877792 0.0620656973 0.1669526249 0.0080284631 0.0207830000 208965114 95654128 760807424 -0.5719324350 0.4516198933 0.9069232345 797 31.8400000000 0.0977457091 0.0621104652 0.1669526249 0.0080458754 0.0207730000 208967922 95654128 760807424 -0.5746150017 0.4504028559 0.9085524082 798 31.8800000000 0.0980145112 0.0621554577 0.1669526249 0.0080645365 0.0207930000 208968730 95654128 760807424 -0.5775288939 0.4492895603 0.9093319178 799 31.9200000000 0.0980154648 0.0622003388 0.1669526249 0.0080750842 0.0207290000 208971538 95654128 760807424 -0.5799747109 0.4476271272 0.9107372761 800 31.9600000000 0.0981065035 0.0622452215 0.1669526249 0.0080833401 0.0207210000 208972346 95654128 760807424 -0.5824758410 0.4456381798 0.9119490981 801 32.0000000000 0.0986966491 0.0622907289 0.1669526249 0.0080975272 0.0206660000 208975154 95654128 760807424 -0.5846038461 0.4446817040 0.9135670066 802 32.0400000000 0.0993143171 0.0623368930 0.1669526249 0.0081051179 0.0206910000 208977762 95654128 760807424 -0.5868620276 0.4433310628 0.9149621129 803 32.0800000000 0.0993555486 0.0623829934 0.1669526249 0.0081148661 0.0207190000 208978770 95654128 760807424 -0.5877204537 0.4429558814 0.9179840088 804 32.1199999990 0.0999740884 0.0624297485 0.1669526249 0.0081293334 0.0206540000 208981378 95654128 760807424 -0.5893302560 0.4425142407 0.9201363325 805 32.1600000000 0.1002662927 0.0624767505 0.1669526249 0.0081455612 0.0207520000 208982386 95654128 760807424 -0.5904948711 0.4411503971 0.9218423367 806 32.2000000000 0.1005564183 0.0625239957 0.1669526249 0.0081625075 0.0207350000 208984994 95654128 760807424 -0.5916975141 0.4400403798 0.9233955741 807 32.2400000000 0.1009956747 0.0625716682 0.1669526249 0.0081803287 0.0207260000 208987802 95654128 760807424 -0.5925540924 0.4373156130 0.9253797531 808 32.2800000000 0.1012097001 0.0626194875 0.1669526249 0.0081883766 0.0206320000 208988610 95654128 760807424 -0.5943001509 0.4345819652 0.9278156161 809 32.3200000000 0.1020312235 0.0626682041 0.1669526249 0.0081961215 0.0207000000 208991418 95654128 760807424 -0.5946611166 0.4319484532 0.9299197793 810 32.3600000000 0.1024250612 0.0627172867 0.1669526249 0.0082016516 0.0206400000 208994026 95654128 760807424 -0.5955888629 0.4299721122 0.9318866134 811 32.4000000000 0.1026252806 0.0627664950 0.1669526249 0.0082008607 0.0206590000 208995034 95654128 760807424 -0.5970055461 0.4260191619 0.9343470335 812 32.4399999990 0.1037026346 0.0628169090 0.1669526249 0.0082012377 0.0206070000 208997642 95654128 760807424 -0.5981086493 0.4236667454 0.9364410639 813 32.4800000000 0.1039546579 0.0628675089 0.1669526249 0.0082006689 0.0206090000 208998650 95654128 760807424 -0.5993157029 0.4203425348 0.9403514266 814 32.5200000000 0.1044372320 0.0629185774 0.1669526249 0.0081998736 0.0206370000 209001258 95654128 760807424 -0.6005120873 0.4174478650 0.9438447952 815 32.5600000000 0.1042503491 0.0629692912 0.1669526249 0.0081976926 0.0216690000 209004066 95654128 760807424 -0.6010220051 0.4144199193 0.9467219710 816 32.6000000000 0.1046832800 0.0630204113 0.1669526249 0.0081962438 0.0207340000 209004874 95654128 760807424 -0.6010633111 0.4108907282 0.9501008987 817 32.6400000000 0.1044787169 0.0630711559 0.1669526249 0.0081926032 0.0208010000 209007682 95654128 760807424 -0.6014904976 0.4074868560 0.9530133605 818 32.6800000000 0.1061682850 0.0631238418 0.1669526249 0.0081884320 0.0206410000 209008490 95654128 760807424 -0.6029859781 0.4054029286 0.9563667178 819 32.7200000000 0.1068390831 0.0631772182 0.1669526249 0.0081848433 0.0206020000 209011298 95654128 760807424 -0.6033361554 0.4042552412 0.9605202079 820 32.7599999990 0.1072597578 0.0632309774 0.1669526249 0.0081833068 0.0206050000 209013906 95654128 760807424 -0.6033060551 0.4029143155 0.9652345181 821 32.7999999990 0.1075095311 0.0632849099 0.1669526249 0.0081870858 0.0206470000 209014914 95654128 760807424 -0.6037948728 0.4002126753 0.9712480903 822 32.8400000000 0.1083965302 0.0633397902 0.1669526249 0.0082102146 0.0206770000 209017522 95654128 760807424 -0.6046876907 0.3983070254 0.9758304358 823 32.8800000000 0.1085272878 0.0633946960 0.1669526249 0.0082193164 0.0206520000 209018530 95654128 760807424 -0.6054660678 0.3962791562 0.9808430076 824 32.9200000000 0.1089376435 0.0634499666 0.1669526249 0.0082259964 0.0206550000 209021138 95654128 760807424 -0.6059067845 0.3960296512 0.9858901501 825 32.9600000000 0.1096641272 0.0635059837 0.1669526249 0.0082383527 0.0205830000 209023946 95654128 760807424 -0.6065981388 0.3944050372 0.9913713932 826 33.0000000000 0.1107234806 0.0635631478 0.1669526249 0.0082499278 0.0205760000 209024754 95654128 760807424 -0.6075736284 0.3942073286 0.9969843030 827 33.0400000000 0.1119129285 0.0636216118 0.1669526249 0.0082660118 0.0205590000 209027562 95654128 760807424 -0.6090555191 0.3919675946 1.0020707846 828 33.0800000000 0.1122438237 0.0636803343 0.1669526249 0.0082898708 0.0205510000 209030170 95654128 760807424 -0.6094486713 0.3885698915 1.0075033903 829 33.1199999990 0.1132506728 0.0637401297 0.1669526249 0.0083115178 0.0206390000 209031178 95654128 760807424 -0.6109226942 0.3861645460 1.0129864216 830 33.1600000000 0.1140466481 0.0638007399 0.1669526249 0.0083284181 0.0206170000 209033786 95654128 760807424 -0.6117542386 0.3836756945 1.0186553001 831 33.2000000000 0.1146219522 0.0638618966 0.1669526249 0.0083467612 0.0204980000 209034794 95654128 760807424 -0.6121018529 0.3790693283 1.0253961086 832 33.2400000000 0.1150407121 0.0639234096 0.1669526249 0.0083572408 0.0204690000 209037402 95654128 760807424 -0.6126725674 0.3756945431 1.0317631960 833 33.2800000000 0.1160989404 0.0639860453 0.1669526249 0.0083595674 0.0204490000 209040210 95654128 760807424 -0.6149589419 0.3725743890 1.0384715796 834 33.3200000000 0.1167627871 0.0640493268 0.1669526249 0.0083631747 0.0215050000 209041018 95654128 760807424 -0.6164765358 0.3677454591 1.0446794033 835 33.3600000000 0.1166923568 0.0641123723 0.1669526249 0.0083671218 0.0206020000 209046570 95654128 760807424 -0.6184619665 0.3644226491 1.0506517887 836 33.4000000000 0.1172537282 0.0641759385 0.1669526249 0.0083757690 0.0205250000 209216186 95654128 760807424 -0.6197629571 0.3611192703 1.0575044155 837 33.4399999990 0.1181703508 0.0642404480 0.1669526249 0.0083938101 0.0206690000 209218994 95654128 760807424 -0.6213728189 0.3594389260 1.0636860132 838 33.4800000000 0.1187582165 0.0643055050 0.1669526249 0.0084216460 0.0204800000 209221602 95654128 760807424 -0.6223121881 0.3549398184 1.0693445206 839 33.5200000000 0.1197000071 0.0643715294 0.1669526249 0.0084546001 0.0205600000 209222610 95654128 760807424 -0.6235548854 0.3531478345 1.0752241611 840 33.5600000000 0.1208252758 0.0644387363 0.1669526249 0.0084800552 0.0205570000 209225218 95654128 760807424 -0.6256281137 0.3524503410 1.0790938139 841 33.6000000000 0.1214482635 0.0645065241 0.1669526249 0.0084832800 0.0205190000 209226226 95654128 760807424 -0.6273576021 0.3510786295 1.0838760138 842 33.6400000000 0.1219530180 0.0645747503 0.1669526249 0.0084828832 0.0204360000 209228834 95654128 760807424 -0.6287998557 0.3497153819 1.0881350040 843 33.6800000000 0.1227105409 0.0646437133 0.1669526249 0.0084843797 0.0204650000 209231642 95654128 760807424 -0.6297821403 0.3474391103 1.0932600498 844 33.7200000000 0.1232762188 0.0647131831 0.1669526249 0.0084895821 0.0205720000 209232450 95654128 760807424 -0.6304796338 0.3433572352 1.0983029604 845 33.7599999990 0.1246478111 0.0647841116 0.1669526249 0.0085046575 0.0204950000 209235258 95654128 760807424 -0.6312870979 0.3414970636 1.1027305126 846 33.7999999990 0.1247559860 0.0648550004 0.1669526249 0.0085106989 0.0203470000 209237866 95654128 760807424 -0.6320962906 0.3397401273 1.1075580120 847 33.8400000000 0.1253154129 0.0649263822 0.1669526249 0.0085090829 0.0203650000 209238874 95654128 760807424 -0.6335765123 0.3352960050 1.1107525826 848 33.8800000000 0.1255844086 0.0649979129 0.1669526249 0.0085045319 0.0204410000 209244230 95654128 760807424 -0.6342884898 0.3324438334 1.1145954132 849 33.9200000000 0.1264691651 0.0650703172 0.1669526249 0.0084998346 0.0203600000 209414038 95654128 760807424 -0.6357913613 0.3277469277 1.1172143221 850 33.9600000000 0.1257889569 0.0651417509 0.1669526249 0.0084954645 0.0203580000 209416646 95654128 760807424 -0.6363525391 0.3234283924 1.1209965944 851 34.0000000000 0.1261829287 0.0652134796 0.1669526249 0.0084905006 0.0203250000 209419454 95654128 760807424 -0.6371941566 0.3212897778 1.1242324114 852 34.0400000000 0.1263576150 0.0652852451 0.1669526249 0.0084858557 0.0203440000 209420262 95654128 760807424 -0.6377372742 0.3156769276 1.1273661852 853 34.0800000000 0.1259899288 0.0653564112 0.1669526249 0.0084825313 0.0204510000 209423070 95654128 760807424 -0.6377007961 0.3122693300 1.1303766966 854 34.1199999990 0.1267919540 0.0654283497 0.1669526249 0.0084824253 0.0202610000 209423878 95654128 760807424 -0.6387023926 0.3103032112 1.1332818270 855 34.1600000000 0.1270128936 0.0655003784 0.1669526249 0.0084833049 0.0202820000 209426686 95654128 760807424 -0.6382074356 0.3075596988 1.1370137930 856 34.2000000000 0.1274507940 0.0655727504 0.1669526249 0.0084849242 0.0203020000 209429294 95654128 760807424 -0.6382794380 0.3057153523 1.1402432919 857 34.2400000000 0.1288828254 0.0656466245 0.1669526249 0.0084812523 0.0203060000 209430302 95654128 760807424 -0.6403523088 0.3057722449 1.1433492899 858 34.2800000000 0.1303100884 0.0657219898 0.1669526249 0.0084773593 0.0202570000 209432910 95654128 760807424 -0.6423093081 0.3047596514 1.1462303400 859 34.3200000000 0.1304159462 0.0657973029 0.1669526249 0.0084728227 0.0203280000 209433918 95654128 760807424 -0.6417105198 0.2991845608 1.1480357647 860 34.3600000000 0.1310240626 0.0658731480 0.1669526249 0.0084686932 0.0202540000 209436526 95654128 760807424 -0.6424315572 0.2951477468 1.1495325565 861 34.4000000000 0.1303769052 0.0659480653 0.1669526249 0.0084640386 0.0202820000 209439334 95654128 760807424 -0.6417773962 0.2918564975 1.1520969868 862 34.4400000000 0.1306771040 0.0660231570 0.1669526249 0.0084591684 0.0203100000 209440142 95654128 760807424 -0.6416239738 0.2885860503 1.1537795067 863 34.4800000000 0.1302542090 0.0660975846 0.1669526249 0.0084551180 0.0203060000 209442950 95654128 760807424 -0.6408112049 0.2826318443 1.1551452875 864 34.5200000000 0.1300416887 0.0661715940 0.1669526249 0.0084514921 0.0203200000 209445558 95654128 760807424 -0.6415265203 0.2784250379 1.1567144394 865 34.5600000000 0.1294747591 0.0662447768 0.1669526249 0.0084466793 0.0203240000 209446566 95654128 760807424 -0.6424399614 0.2767176032 1.1583949327 866 34.6000000000 0.1301323771 0.0663185500 0.1669526249 0.0084425830 0.0202860000 209449174 95654128 760807424 -0.6434949040 0.2763235271 1.1594681740 867 34.6400000000 0.1292751580 0.0663911643 0.1669526249 0.0084396123 0.0202170000 209450182 95654128 760807424 -0.6437707543 0.2721897364 1.1608501673 868 34.6800000000 0.1288893670 0.0664631669 0.1669526249 0.0084351286 0.0202740000 209452790 95654128 760807424 -0.6442853212 0.2680012286 1.1617244482 869 34.7200000000 0.1290993094 0.0665352453 0.1669526249 0.0084315838 0.0202510000 209455598 95654128 760807424 -0.6441879869 0.2646118402 1.1625689268 870 34.7600000000 0.1294644624 0.0666075777 0.1669526249 0.0084276161 0.0202720000 209456406 95654128 760807424 -0.6465743184 0.2612857521 1.1637934446 871 34.8000000000 0.1299761087 0.0666803315 0.1669526249 0.0084237056 0.0202720000 209459214 95654128 760807424 -0.6463098526 0.2612312436 1.1643835306 872 34.8400000000 0.1300234944 0.0667529727 0.1669526249 0.0084193624 0.0211350000 209460022 95654128 760807424 -0.6481717825 0.2575227022 1.1654001474 873 34.8800000000 0.1302703172 0.0668257303 0.1669526249 0.0084153162 0.0203990000 209462830 95654128 760807424 -0.6495661139 0.2550583184 1.1668268442 874 34.9200000000 0.1310680658 0.0668992341 0.1669526249 0.0084116979 0.0203320000 209465438 95654128 760807424 -0.6512812972 0.2539669871 1.1677930355 875 34.9600000000 0.1308103949 0.0669722754 0.1669526249 0.0084084726 0.0202610000 209466446 95654128 760807424 -0.6527104974 0.2538576722 1.1698342562 876 35.0000000000 0.1314161867 0.0670458415 0.1669526249 0.0084041310 0.0203190000 209469054 95654128 760807424 -0.6535452604 0.2537583709 1.1704925299 877 35.0400000000 0.1292702407 0.0671167930 0.1669526249 0.0083995376 0.0203400000 209470062 95654128 760807424 -0.6531823277 0.2517525852 1.1717493534 878 35.0800000000 0.1293156594 0.0671876345 0.1669526249 0.0083948757 0.0204520000 209472670 95654128 760807424 -0.6538938284 0.2522889376 1.1728340387 879 35.1200000000 0.1311855465 0.0672604421 0.1669526249 0.0083904118 0.0203930000 209475478 95654128 760807424 -0.6562542915 0.2523967326 1.1742793322 880 35.1600000000 0.1335393935 0.0673357591 0.1669526249 0.0083857644 0.0204480000 209476286 95654128 760807424 -0.6584379673 0.2551296949 1.1755602360 881 35.2000000000 0.1343237311 0.0674117954 0.1669526249 0.0083814473 0.0203310000 209479094 95654128 760807424 -0.6591290832 0.2562746704 1.1769349575 882 35.2400000000 0.1347500980 0.0674881427 0.1669526249 0.0083774141 0.0203190000 209481702 95654128 760807424 -0.6592038870 0.2523786724 1.1776955128 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:26:48 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0095760000 198718716 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0014906204 0.0007453102 0.0014906204 0.0018488365 0.0229690000 199529670 95654128 760807424 -0.0002006323 0.0021261084 0.0016063029 3 0.0800000000 0.0051448587 0.0022118264 0.0051448587 0.0020652516 0.0177930000 199379202 95654128 760807424 -0.0021077488 -0.0076258783 0.0021185584 4 0.1200000000 0.0061540338 0.0031973782 0.0061540338 0.0026527719 0.0281830000 199379866 95654128 760807424 -0.0043492271 -0.0071370490 0.0010577580 5 0.1600000000 0.0051830057 0.0035945037 0.0061540338 0.0045026517 0.0182410000 199383026 95654128 760807424 -0.0025760494 0.0001287921 0.0040184655 6 0.2000000000 0.0058377683 0.0039683812 0.0061540338 0.0045763480 0.0177010000 199384634 95654128 760807424 -0.0007591686 -0.0102310870 0.0032144608 7 0.2400000000 0.0077825077 0.0045132564 0.0077825077 0.0042793614 0.0176880000 199387242 95654128 760807424 0.0006488978 -0.0227377452 0.0007024903 8 0.2800000000 0.0059227580 0.0046894441 0.0077825077 0.0039940962 0.0176380000 199389850 95654128 760807424 -0.0012176125 -0.0190639365 -0.0005991290 9 0.3200000000 0.0059278077 0.0048270400 0.0077825077 0.0049677966 0.0176790000 199391562 95654128 760807424 -0.0020724039 -0.0151531156 0.0027327049 10 0.3600000000 0.0040743011 0.0047517661 0.0077825077 0.0047513880 0.0177280000 199395770 95654128 760807424 -0.0038858289 -0.0208636522 0.0007907895 11 0.4000000000 0.0041454197 0.0046966437 0.0077825077 0.0046826915 0.0176730000 199398378 95654128 760807424 -0.0033602002 -0.0171444993 -0.0004601245 12 0.4400000000 0.0035383229 0.0046001170 0.0077825077 0.0047747560 0.0177520000 199399186 95654128 760807424 -0.0038383317 -0.0062900642 0.0024069408 13 0.4800000000 0.0038656055 0.0045436161 0.0077825077 0.0046155366 0.0228760000 199401994 95654128 760807424 -0.0036014919 -0.0070257103 0.0025526534 14 0.5200000000 0.0047846814 0.0045608351 0.0077825077 0.0044972249 0.0185610000 199404602 95654128 760807424 -0.0015134434 -0.0151681434 0.0001301537 15 0.5600000000 0.0044728112 0.0045549668 0.0077825077 0.0044768586 0.0176950000 199405410 95654128 760807424 0.0018446757 -0.0137117328 0.0001335422 16 0.6000000000 0.0038660716 0.0045119109 0.0077825077 0.0043454902 0.0177580000 199408018 95654128 760807424 0.0030971551 -0.0112607330 0.0004593164 17 0.6400000000 0.0031835586 0.0044337725 0.0077825077 0.0042355410 0.0208210000 199410434 95654128 760807424 0.0033998592 -0.0136367194 -0.0013891369 18 0.6800000000 0.0035338495 0.0043837768 0.0077825077 0.0041180757 0.0179370000 199416242 95654128 760807424 0.0024579354 -0.0138663538 -0.0026893807 19 0.7200000000 0.0035917899 0.0043420932 0.0077825077 0.0041232833 0.0176880000 199418850 95654128 760807424 0.0029473517 -0.0084557803 -0.0020835344 20 0.7600000000 0.0049795895 0.0043739681 0.0077825077 0.0043480763 0.0176810000 199419658 95654128 760807424 0.0012476378 -0.0083449921 -0.0047331331 21 0.8000000000 0.0049719503 0.0044024434 0.0077825077 0.0044814892 0.0177210000 199422466 95654128 760807424 0.0037087663 -0.0070186956 -0.0038620993 22 0.8400000000 0.0046808943 0.0044151003 0.0077825077 0.0044514372 0.0177200000 199425074 95654128 760807424 0.0042833793 -0.0045673084 -0.0034084511 23 0.8800000000 0.0059162076 0.0044803658 0.0077825077 0.0043710707 0.0176790000 199425882 95654128 760807424 0.0056660995 -0.0096293287 -0.0070698224 24 0.9200000000 0.0054480606 0.0045206864 0.0077825077 0.0043156610 0.0186150000 199428490 95654128 760807424 0.0087006055 -0.0079188105 -0.0065272870 25 0.9600000000 0.0065215551 0.0046007212 0.0077825077 0.0042451025 0.0177250000 199431298 95654128 760807424 0.0078920731 -0.0134894196 -0.0089958347 26 1.0000000000 0.0059188306 0.0046514177 0.0077825077 0.0041675768 0.0177150000 199432106 95654128 760807424 0.0076828906 -0.0148645034 -0.0098177055 27 1.0400000000 0.0062376913 0.0047101686 0.0077825077 0.0040891385 0.0177010000 199434714 95654128 760807424 0.0086640045 -0.0187282078 -0.0117983837 28 1.0800000000 0.0062820013 0.0047663054 0.0077825077 0.0040216002 0.0177220000 199437322 95654128 760807424 0.0068897167 -0.0198798478 -0.0133027034 29 1.1200000000 0.0063471971 0.0048208189 0.0077825077 0.0040572693 0.0176960000 199438330 95654128 760807424 0.0092632119 -0.0226851497 -0.0138057778 30 1.1600000000 0.0071129757 0.0048972242 0.0077825077 0.0040287023 0.0177690000 199440938 95654128 760807424 0.0123603847 -0.0225229543 -0.0136652132 31 1.2000000000 0.0067260643 0.0049562190 0.0077825077 0.0040147493 0.0177510000 199441746 95654128 760807424 0.0172034204 -0.0194637720 -0.0149518466 32 1.2400000000 0.0087901382 0.0050760290 0.0087901382 0.0041475397 0.0177310000 199444354 95654128 760807424 0.0162973963 -0.0196284018 -0.0155605506 33 1.2800000000 0.0094991140 0.0052100619 0.0094991140 0.0043788002 0.0177690000 199449978 95654128 760807424 0.0173539463 -0.0162826926 -0.0152042443 34 1.3200000000 0.0092938785 0.0053301741 0.0094991140 0.0045925335 0.0177910000 199457186 95654128 760807424 0.0251505412 -0.0124877300 -0.0172802191 35 1.3600000000 0.0099375416 0.0054618132 0.0099375416 0.0045262579 0.0177370000 199459794 95654128 760807424 0.0250807963 -0.0149980560 -0.0182826612 36 1.4000000000 0.0106050652 0.0056046813 0.0106050652 0.0044710458 0.0177060000 199462402 95654128 760807424 0.0247260481 -0.0175700355 -0.0213945862 37 1.4400000000 0.0121859573 0.0057825536 0.0121859573 0.0044185792 0.0176090000 199463410 95654128 760807424 0.0252763275 -0.0193240698 -0.0233763810 38 1.4800000000 0.0123836659 0.0059562671 0.0123836659 0.0043600515 0.0178970000 199466018 95654128 760807424 0.0245191827 -0.0190142598 -0.0236602593 39 1.5200000000 0.0127159776 0.0061295930 0.0127159776 0.0043384286 0.0178590000 199468626 95654128 760807424 0.0246744975 -0.0179302245 -0.0244892295 40 1.5600000000 0.0117321759 0.0062696576 0.0127159776 0.0045354942 0.0210090000 199469434 95654128 760807424 0.0287460163 -0.0159972478 -0.0249928553 41 1.6000000000 0.0119910361 0.0064092034 0.0127159776 0.0048022399 0.0179810000 199472242 95654128 760807424 0.0336469635 -0.0128435837 -0.0253791120 42 1.6400000000 0.0127524221 0.0065602324 0.0127524221 0.0047538277 0.0211800000 199473050 95654128 760807424 0.0327541083 -0.0122989379 -0.0266755018 43 1.6800000000 0.0135111073 0.0067218807 0.0135111073 0.0047206763 0.0178810000 199475658 95654128 760807424 0.0337485634 -0.0132988924 -0.0280780029 44 1.7200000000 0.0145272203 0.0068992748 0.0145272203 0.0046740404 0.0176690000 199478266 95654128 760807424 0.0342878290 -0.0124355005 -0.0283556506 45 1.7600000000 0.0154821081 0.0070900044 0.0154821081 0.0047650981 0.0176210000 199479274 95654128 760807424 0.0346785374 -0.0083038434 -0.0295988787 46 1.8000000000 0.0149007021 0.0072598022 0.0154821081 0.0048775843 0.0176610000 199481882 95654128 760807424 0.0370799266 -0.0088207638 -0.0299765319 47 1.8400000000 0.0153810689 0.0074325951 0.0154821081 0.0049064498 0.0176300000 199484490 95654128 760807424 0.0385199599 -0.0076662777 -0.0302197617 48 1.8800000000 0.0138860187 0.0075670414 0.0154821081 0.0049277202 0.0176910000 199485298 95654128 760807424 0.0425544716 -0.0073099523 -0.0301335994 49 1.9200000000 0.0135773607 0.0076897010 0.0154821081 0.0049537326 0.0227310000 199488106 95654128 760807424 0.0442351401 -0.0096170167 -0.0318989567 50 1.9600000000 0.0132579058 0.0078010651 0.0154821081 0.0049338090 0.0183740000 199490698 95654128 760807424 0.0409885719 -0.0086224852 -0.0334619693 51 2.0000000000 0.0123550454 0.0078903588 0.0154821081 0.0049409451 0.0220930000 199491506 95654128 760807424 0.0422737747 -0.0051622814 -0.0327948146 52 2.0400000000 0.0119494488 0.0079684182 0.0154821081 0.0049351760 0.0201590000 199494114 95654128 760807424 0.0437867567 -0.0078608692 -0.0330818109 53 2.0800000000 0.0114708031 0.0080345010 0.0154821081 0.0049158698 0.0179540000 199495106 95654128 760807424 0.0451380014 -0.0120810326 -0.0354462489 54 2.1200000000 0.0118450038 0.0081050658 0.0154821081 0.0049731095 0.0178140000 199499294 95654128 760807424 0.0458026715 -0.0124823516 -0.0355915651 55 2.1600000000 0.0102275973 0.0081436573 0.0154821081 0.0049599077 0.0179420000 199670498 95654128 760807424 0.0465971082 -0.0086320750 -0.0364856645 56 2.2000000000 0.0101537900 0.0081795525 0.0154821081 0.0049744718 0.0178430000 199671306 95654128 760807424 0.0492733605 -0.0100944731 -0.0375871845 57 2.2400000000 0.0105772512 0.0082216174 0.0154821081 0.0050023308 0.0178110000 199674098 95654128 760807424 0.0504242107 -0.0141295036 -0.0403257981 58 2.2800000000 0.0097886082 0.0082486345 0.0154821081 0.0051135824 0.0177020000 199676706 95654128 760807424 0.0527610779 -0.0118998466 -0.0405044593 59 2.3200000000 0.0095573682 0.0082708164 0.0154821081 0.0052874981 0.0177160000 199677498 95654128 760807424 0.0569505654 -0.0089078313 -0.0411956012 60 2.3600000000 0.0091825230 0.0082860115 0.0154821081 0.0053249920 0.0177310000 199680090 95654128 760807424 0.0593513697 -0.0124553293 -0.0438481793 61 2.4000000000 0.0082651684 0.0082856699 0.0154821081 0.0052972886 0.0209550000 199682882 95654128 760807424 0.0583301783 -0.0134947328 -0.0456903055 62 2.4400000000 0.0077952575 0.0082777600 0.0154821081 0.0053850886 0.0179760000 199683658 95654128 760807424 0.0608453415 -0.0123017598 -0.0454982668 63 2.4800000000 0.0079615274 0.0082727404 0.0154821081 0.0053848331 0.0179700000 199686250 95654128 760807424 0.0653152540 -0.0093506062 -0.0457207412 64 2.5200000000 0.0091426224 0.0082863323 0.0154821081 0.0053737219 0.0177930000 199688858 95654128 760807424 0.0664931238 -0.0135885617 -0.0490962006 65 2.5600000000 0.0091497479 0.0082996156 0.0154821081 0.0053552050 0.0177650000 199695482 95654128 760807424 0.0667778254 -0.0114469361 -0.0492909215 66 2.6000000000 0.0105002644 0.0083329588 0.0154821081 0.0053206606 0.0178640000 199710874 95654128 760807424 0.0619996786 -0.0129478853 -0.0513440706 67 2.6400000000 0.0116474554 0.0083824289 0.0154821081 0.0053178245 0.0177730000 199711682 95654128 760807424 0.0613619685 -0.0119672567 -0.0533616282 68 2.6800000000 0.0132304272 0.0084537230 0.0154821081 0.0053470855 0.0177750000 199714274 95654128 760807424 0.0646293908 -0.0145618860 -0.0537380315 69 2.7200000000 0.0122211901 0.0085083240 0.0154821081 0.0053673673 0.0177910000 199717082 95654128 760807424 0.0668511540 -0.0155942310 -0.0548074655 70 2.7600000000 0.0107184285 0.0085398969 0.0154821081 0.0054270358 0.0177780000 199717858 95654128 760807424 0.0711982101 -0.0129447337 -0.0560822040 71 2.8000000000 0.0115590086 0.0085824196 0.0154821081 0.0054372043 0.0174510000 199720466 95654128 760807424 0.0734846592 -0.0103052557 -0.0581662208 72 2.8400000000 0.0123948576 0.0086353701 0.0154821081 0.0054463615 0.0212640000 199723058 95654128 760807424 0.0745070279 -0.0098695913 -0.0591079704 73 2.8800000000 0.0108721172 0.0086660105 0.0154821081 0.0055130381 0.0178050000 199724066 95654128 760807424 0.0779736489 -0.0103035150 -0.0606248006 74 2.9200000000 0.0118208854 0.0087086439 0.0154821081 0.0056100151 0.0179360000 199726658 95654128 760807424 0.0788135305 -0.0116332760 -0.0630432889 75 2.9600000000 0.0112519553 0.0087425547 0.0154821081 0.0056454604 0.0212260000 199729266 95654128 760807424 0.0851909146 -0.0101111103 -0.0649960861 76 3.0000000000 0.0090789171 0.0087469806 0.0154821081 0.0056962708 0.0185360000 199732062 95654128 760807424 0.0905888006 -0.0104364613 -0.0669407547 77 3.0400000000 0.0077246320 0.0087337033 0.0154821081 0.0057611652 0.0176300000 199903494 95654128 760807424 0.0959809721 -0.0142238708 -0.0676670969 78 3.0800000000 0.0078641465 0.0087225551 0.0154821081 0.0057378571 0.0176110000 199904302 95654128 760807424 0.0987408683 -0.0152234901 -0.0707574263 79 3.1200000000 0.0073230066 0.0087048393 0.0154821081 0.0057949056 0.0208850000 199906894 95654128 760807424 0.1031038836 -0.0127121545 -0.0712681487 80 3.1600000000 0.0088238530 0.0087063270 0.0154821081 0.0057828270 0.0177600000 199909502 95654128 760807424 0.1066651568 -0.0172502082 -0.0739575401 81 3.2000000000 0.0078958701 0.0086963214 0.0154821081 0.0057616139 0.0175860000 199910478 95654128 760807424 0.1117547601 -0.0149967065 -0.0756653771 82 3.2400000000 0.0081218174 0.0086893152 0.0154821081 0.0057345196 0.0176120000 199913086 95654128 760807424 0.1170216128 -0.0193446614 -0.0778041855 83 3.2800000000 0.0087743271 0.0086903395 0.0154821081 0.0057265666 0.0175450000 199915678 95654128 760807424 0.1197968125 -0.0218475573 -0.0803297609 84 3.3200000000 0.0082219122 0.0086847630 0.0154821081 0.0057088185 0.0175260000 199916486 95654128 760807424 0.1233567968 -0.0158406682 -0.0829758644 85 3.3600000000 0.0080074258 0.0086767943 0.0154821081 0.0056796698 0.0175540000 199919294 95654128 760807424 0.1344172060 -0.0151072498 -0.0832346007 86 3.4000000000 0.0097712679 0.0086895207 0.0154821081 0.0057047551 0.0175940000 199921886 95654128 760807424 0.1348866373 -0.0124667678 -0.0850194246 87 3.4400000000 0.0111280931 0.0087175503 0.0154821081 0.0057037347 0.0208020000 199922694 95654128 760807424 0.1353613585 -0.0122555569 -0.0877171010 88 3.4800000000 0.0095246043 0.0087267214 0.0154821081 0.0056715534 0.0178010000 199925302 95654128 760807424 0.1426119953 -0.0110314796 -0.0891004205 89 3.5200000000 0.0081595797 0.0087203490 0.0154821081 0.0056605451 0.0175490000 199926294 95654128 760807424 0.1470459551 -0.0093576200 -0.0903143510 90 3.5600000000 0.0087964516 0.0087211946 0.0154821081 0.0056336396 0.0175990000 199928902 95654128 760807424 0.1502032131 -0.0117632821 -0.0918277353 91 3.6000000000 0.0098231519 0.0087333040 0.0154821081 0.0056913399 0.0175380000 199931510 95654128 760807424 0.1581891626 -0.0143329436 -0.0922986120 92 3.6400000000 0.0111777410 0.0087598739 0.0154821081 0.0057116334 0.0171310000 199932302 95654128 760807424 0.1624031514 -0.0080724005 -0.0926363096 93 3.6800000000 0.0092366887 0.0087650010 0.0154821081 0.0057744793 0.0171170000 199935110 95654128 760807424 0.1735709161 -0.0053449217 -0.0944406539 94 3.7200000000 0.0106344912 0.0087848892 0.0154821081 0.0057571042 0.0178810000 199937718 95654128 760807424 0.1810897887 -0.0077207778 -0.0970041752 95 3.7600000000 0.0105210952 0.0088031650 0.0154821081 0.0057307449 0.0171680000 199938494 95654128 760807424 0.1870564967 -0.0073439977 -0.0994588211 96 3.8000000000 0.0092654144 0.0088079801 0.0154821081 0.0057180551 0.0171400000 199941102 95654128 760807424 0.1955981255 -0.0071925456 -0.1011341065 97 3.8400000000 0.0082744434 0.0088024798 0.0154821081 0.0056997519 0.0206020000 199943910 95654128 760807424 0.2054691464 -0.0049486626 -0.1035955772 98 3.8800000000 0.0074737649 0.0087889214 0.0154821081 0.0056705147 0.0173810000 199944718 95654128 760807424 0.2155323029 -0.0053632883 -0.1049619913 99 3.9200000000 0.0075062974 0.0087759656 0.0154821081 0.0056828071 0.0205390000 199947310 95654128 760807424 0.2225424200 -0.0057376372 -0.1072752997 100 3.9600000000 0.0063066771 0.0087512728 0.0154821081 0.0056561032 0.0174430000 199949918 95654128 760807424 0.2325790375 -0.0052127573 -0.1081354842 101 4.0000000000 0.0071413880 0.0087353333 0.0154821081 0.0056544271 0.0172180000 199950926 95654128 760807424 0.2404269129 -0.0030582591 -0.1086139977 102 4.0400000000 0.0061709057 0.0087101919 0.0154821081 0.0056555329 0.0171000000 199953518 95654128 760807424 0.2456083596 -0.0027708113 -0.1111006811 103 4.0800000000 0.0057383529 0.0086813391 0.0154821081 0.0056298124 0.0171050000 199954326 95654128 760807424 0.2525312603 0.0033222353 -0.1105087623 104 4.1200000000 0.0060078925 0.0086556328 0.0154821081 0.0056091557 0.0171740000 199956934 95654128 760807424 0.2620877624 0.0051964065 -0.1114805192 105 4.1600000000 0.0055080019 0.0086256554 0.0154821081 0.0055976479 0.0170780000 199959742 95654128 760807424 0.2692736387 0.0084915422 -0.1120155826 106 4.2000000000 0.0072827484 0.0086129865 0.0154821081 0.0056130242 0.0170410000 199960550 95654128 760807424 0.2751599550 0.0038947668 -0.1132205203 107 4.2400000000 0.0065515502 0.0085937207 0.0154821081 0.0055868301 0.0201850000 199963158 95654128 760807424 0.2845352590 0.0021811563 -0.1147650555 108 4.2800000000 0.0071240729 0.0085801129 0.0154821081 0.0055690050 0.0174080000 199966666 95654128 760807424 0.2939600646 0.0013340528 -0.1161147058 109 4.3200000000 0.0059698238 0.0085561652 0.0154821081 0.0055476805 0.0171030000 200136318 95654128 760807424 0.3116673529 0.0012538749 -0.1197205037 110 4.3600000000 0.0062361588 0.0085350743 0.0154821081 0.0055467540 0.0171000000 200138926 95654128 760807424 0.3249491155 0.0014192630 -0.1207649037 111 4.4000000000 0.0055754902 0.0085084114 0.0154821081 0.0055244038 0.0171590000 200141534 95654128 760807424 0.3332183957 0.0032899510 -0.1218995377 112 4.4400000000 0.0061773476 0.0084875983 0.0154821081 0.0055062527 0.0170530000 200142342 95654128 760807424 0.3373326659 -0.0011225645 -0.1247176155 113 4.4800000000 0.0046357140 0.0084535108 0.0154821081 0.0054845762 0.0171270000 200145150 95654128 760807424 0.3486672044 -0.0012132028 -0.1260294020 114 4.5200000000 0.0053096227 0.0084259329 0.0154821081 0.0054760528 0.0205660000 200145958 95654128 760807424 0.3616900146 -0.0027729897 -0.1270146370 115 4.5600000000 0.0060475320 0.0084052511 0.0154821081 0.0054581317 0.0173710000 200148550 95654128 760807424 0.3705126047 -0.0057270918 -0.1278430969 116 4.6000000000 0.0079897791 0.0084016695 0.0154821081 0.0054398784 0.0170980000 200151158 95654128 760807424 0.3783396482 -0.0116157532 -0.1296252459 117 4.6400000000 0.0069761537 0.0083894856 0.0154821081 0.0054495314 0.0171130000 200152166 95654128 760807424 0.3860318959 -0.0132993488 -0.1314039975 118 4.6800000000 0.0072047934 0.0083794458 0.0154821081 0.0054440083 0.0170770000 200154774 95654128 760807424 0.3925927877 -0.0122502455 -0.1306981444 119 4.7200000000 0.0066303867 0.0083647478 0.0154821081 0.0054674566 0.0170910000 200157382 95654128 760807424 0.4052043855 -0.0097701894 -0.1291147619 120 4.7600000000 0.0101505248 0.0083796293 0.0154821081 0.0054514421 0.0171020000 200158206 95654128 760807424 0.4140800536 -0.0110020656 -0.1268669665 121 4.8000000000 0.0093714613 0.0083878263 0.0154821081 0.0054337955 0.0171250000 200161014 95654128 760807424 0.4261076450 -0.0137055144 -0.1287526041 122 4.8400000000 0.0090200817 0.0083930087 0.0154821081 0.0054360542 0.0171070000 200163622 95654128 760807424 0.4353137910 -0.0130488276 -0.1296001226 123 4.8800000000 0.0100100925 0.0084061557 0.0154821081 0.0054155147 0.0170860000 200164430 95654128 760807424 0.4458014071 -0.0114306128 -0.1274774969 124 4.9200000000 0.0099068517 0.0084182581 0.0154821081 0.0053960978 0.0170330000 200167038 95654128 760807424 0.4522878826 -0.0100712227 -0.1245507747 125 4.9600000000 0.0075352895 0.0084111943 0.0154821081 0.0053898843 0.0204370000 200168046 95654128 760807424 0.4556345940 -0.0068983138 -0.1227283180 126 5.0000000000 0.0067647900 0.0083981276 0.0154821081 0.0053749519 0.0205600000 200170654 95654128 760807424 0.4653325975 -0.0065716645 -0.1217382401 127 5.0400000000 0.0083847754 0.0083980225 0.0154821081 0.0053564829 0.0173140000 200173278 95654128 760807424 0.4745378494 -0.0077702324 -0.1187327802 128 5.0800000000 0.0089954743 0.0084026901 0.0154821081 0.0053524794 0.0170850000 200174086 95654128 760807424 0.4873450100 -0.0079538897 -0.1156695113 129 5.1200000000 0.0090285474 0.0084075417 0.0154821081 0.0053433887 0.0170380000 200188158 95654128 760807424 0.4980532825 -0.0066693607 -0.1123934016 130 5.1600000000 0.0090870420 0.0084127686 0.0154821081 0.0053244967 0.0203000000 200218426 95654128 760807424 0.5043175817 -0.0057902276 -0.1100154892 131 5.2000000000 0.0091284141 0.0084182316 0.0154821081 0.0053477491 0.0179180000 200387850 95654128 760807424 0.5119132400 -0.0074114380 -0.1074214578 132 5.2400000000 0.0089796167 0.0084224845 0.0154821081 0.0053334075 0.0173900000 200390458 95654128 760807424 0.5233790874 -0.0071107699 -0.1041402593 133 5.2800000000 0.0099997194 0.0084343434 0.0154821081 0.0053142051 0.0170430000 200393266 95654128 760807424 0.5343916416 -0.0073119448 -0.0997023359 134 5.3200000000 0.0066444413 0.0084209859 0.0154821081 0.0053457467 0.0170810000 200394090 95654128 760807424 0.5444245934 -0.0045222891 -0.0977019668 135 5.3600000000 0.0084639257 0.0084213040 0.0154821081 0.0053659728 0.0205240000 200396698 95654128 760807424 0.5527764559 -0.0047214418 -0.0930288061 136 5.4000000000 0.0091681294 0.0084267953 0.0154821081 0.0053846002 0.0199900000 200399306 95654128 760807424 0.5660929084 0.0021115108 -0.0871024430 137 5.4400000000 0.0109813288 0.0084454416 0.0154821081 0.0053744342 0.0172540000 200400314 95654128 760807424 0.5725368857 0.0039061273 -0.0833640471 138 5.4800000000 0.0069598565 0.0084346765 0.0154821081 0.0054239952 0.0170190000 200402922 95654128 760807424 0.5752973557 0.0072403159 -0.0806264281 139 5.5200000000 0.0076143644 0.0084287749 0.0154821081 0.0054061567 0.0171080000 200403730 95654128 760807424 0.5825250745 0.0082125198 -0.0750873014 140 5.5600000000 0.0097644627 0.0084383156 0.0154821081 0.0053902869 0.0170650000 200406338 95654128 760807424 0.5910186172 0.0068828538 -0.0697342753 141 5.6000000000 0.0096342452 0.0084467973 0.0154821081 0.0053718408 0.0170270000 200409066 95654128 760807424 0.5994207263 0.0078862486 -0.0652018040 142 5.6400000000 0.0094621247 0.0084539475 0.0154821081 0.0053570710 0.0170710000 200409874 95654128 760807424 0.6094781160 0.0091461139 -0.0596584864 143 5.6800000000 0.0099788858 0.0084646114 0.0154821081 0.0053462763 0.0171140000 200412482 95654128 760807424 0.6192623377 0.0098859426 -0.0549769886 144 5.7200000000 0.0097966455 0.0084738617 0.0154821081 0.0053646815 0.0170710000 200415106 95654128 760807424 0.6258637905 0.0099919820 -0.0502022058 145 5.7600000000 0.0077196122 0.0084686600 0.0154821081 0.0053473309 0.0204240000 200416114 95654128 760807424 0.6351125836 0.0118665928 -0.0462933406 146 5.8000000000 0.0099139716 0.0084785593 0.0154821081 0.0053317775 0.0173670000 200418802 95654128 760807424 0.6442896724 0.0113315210 -0.0397704542 147 5.8400000000 0.0088452017 0.0084810535 0.0154821081 0.0053140649 0.0171330000 200421410 95654128 760807424 0.6544285417 0.0161899179 -0.0339949429 148 5.8800000000 0.0100147305 0.0084914162 0.0154821081 0.0053269601 0.0171110000 200422218 95654128 760807424 0.6598796844 0.0145070115 -0.0290963054 149 5.9200000000 0.0082042255 0.0084894887 0.0154821081 0.0053119080 0.0181350000 200425026 95654128 760807424 0.6659659147 0.0156410467 -0.0251934435 150 5.9600000000 0.0070342049 0.0084797868 0.0154821081 0.0053162718 0.0198450000 200425834 95654128 760807424 0.6742345095 0.0199688748 -0.0199671984 151 6.0000000000 0.0067407559 0.0084682701 0.0154821081 0.0053119628 0.0173450000 200428442 95654128 760807424 0.6820634007 0.0225360226 -0.0147369085 152 6.0400000000 0.0085278405 0.0084686620 0.0154821081 0.0053097427 0.0172190000 200431082 95654128 760807424 0.6928305626 0.0209560208 -0.0043287352 153 6.0800000000 0.0103779538 0.0084811410 0.0154821081 0.0053250736 0.0171810000 200432090 95654128 760807424 0.7002624273 0.0203207768 0.0016932157 154 6.1200000000 0.0105365403 0.0084944878 0.0154821081 0.0053081416 0.0173020000 200434698 95654128 760807424 0.7071885467 0.0214158818 0.0061589698 155 6.1600000000 0.0071667256 0.0084859216 0.0154821081 0.0053100900 0.0172840000 200437306 95654128 760807424 0.7114719748 0.0247556474 0.0097622853 156 6.2000000000 0.0090849921 0.0084897618 0.0154821081 0.0053297820 0.0172950000 200438114 95654128 760807424 0.7187315226 0.0249628350 0.0163661279 157 6.2400000000 0.0088211168 0.0084918723 0.0154821081 0.0053393181 0.0172480000 200440922 95654128 760807424 0.7259945869 0.0259371381 0.0216786712 158 6.2800000000 0.0087788217 0.0084936884 0.0154821081 0.0053479560 0.0172200000 200443530 95654128 760807424 0.7304484844 0.0273340680 0.0282506049 159 6.3200000000 0.0107850861 0.0085080997 0.0154821081 0.0053811851 0.0176360000 200444338 95654128 760807424 0.7374561429 0.0271362383 0.0348564461 160 6.3600000000 0.0096274652 0.0085150958 0.0154821081 0.0054244078 0.0176760000 200446962 95654128 760807424 0.7511019707 0.0319113433 0.0484698787 161 6.4000000000 0.0061154268 0.0085001910 0.0154821081 0.0054441888 0.0176140000 200447970 95654128 760807424 0.7551063299 0.0381829776 0.0549721681 162 6.4400000000 0.0074848444 0.0084939234 0.0154821081 0.0054330826 0.0176810000 200450578 95654128 760807424 0.7605887055 0.0388477407 0.0627916604 163 6.4800000000 0.0075977780 0.0084884256 0.0154821081 0.0054443670 0.0218580000 200453186 95654128 760807424 0.7663228512 0.0400522277 0.0712990686 164 6.5200000000 0.0089502186 0.0084912414 0.0154821081 0.0054545056 0.0176710000 200453994 95654128 760807424 0.7736449838 0.0385403484 0.0794800147 165 6.5600000000 0.0084887594 0.0084912264 0.0154821081 0.0054565055 0.0214200000 200458354 95654128 760807424 0.7831398249 0.0412299074 0.0874076113 166 6.6000000000 0.0093578426 0.0084964470 0.0154821081 0.0054753418 0.0180240000 200629614 95654128 760807424 0.7906057239 0.0445504598 0.0968781561 167 6.6400000000 0.0087710377 0.0084980912 0.0154821081 0.0055188777 0.0177710000 200630422 95654128 760807424 0.7952197194 0.0469472781 0.1049859151 168 6.6800000000 0.0082747452 0.0084967618 0.0154821081 0.0055282941 0.0178020000 200633030 95654128 760807424 0.8019886017 0.0499648526 0.1134037524 169 6.7200000000 0.0082342532 0.0084952085 0.0154821081 0.0055166540 0.0212140000 200635838 95654128 760807424 0.8112920523 0.0543989986 0.1240227520 170 6.7600000000 0.0092489887 0.0084996425 0.0154821081 0.0055371691 0.0180240000 200636646 95654128 760807424 0.8163245916 0.0552774668 0.1333588958 171 6.8000000000 0.0080176760 0.0084968240 0.0154821081 0.0055213823 0.0177640000 200639254 95654128 760807424 0.8262985945 0.0590487383 0.1429199129 172 6.8400000000 0.0107069314 0.0085096734 0.0154821081 0.0055080411 0.0178260000 200641878 95654128 760807424 0.8344280124 0.0588511154 0.1535874605 173 6.8800000000 0.0099543417 0.0085180241 0.0154821081 0.0054925308 0.0178460000 200642886 95654128 760807424 0.8383536339 0.0595967881 0.1607284099 174 6.9200000000 0.0084710820 0.0085177543 0.0154821081 0.0054826462 0.0220670000 200645494 95654128 760807424 0.8460952640 0.0636774451 0.1701655090 175 6.9600000000 0.0094024716 0.0085228098 0.0154821081 0.0054708937 0.0182280000 200646302 95654128 760807424 0.8557673097 0.0663109794 0.1804055423 176 7.0000000000 0.0106892092 0.0085351189 0.0154821081 0.0054561285 0.0178850000 200648910 95654128 760807424 0.8633232713 0.0672878549 0.1907110214 177 7.0400000000 0.0096010175 0.0085411410 0.0154821081 0.0054905044 0.0209110000 200651734 95654128 760807424 0.8675379753 0.0684754029 0.1989114732 178 7.0800000000 0.0095813544 0.0085469848 0.0154821081 0.0055149993 0.0209540000 200652542 95654128 760807424 0.8722464442 0.0684036836 0.2067848593 179 7.1200000000 0.0091763213 0.0085505007 0.0154821081 0.0054997904 0.0180830000 200655150 95654128 760807424 0.8788707256 0.0710109249 0.2152935117 180 7.1600000000 0.0088459561 0.0085521421 0.0154821081 0.0054865281 0.0179630000 200657758 95654128 760807424 0.8860055804 0.0724429786 0.2241951525 181 7.2000000000 0.0106739542 0.0085638648 0.0154821081 0.0054737022 0.0179790000 200658766 95654128 760807424 0.8882598877 0.0718042776 0.2337062508 182 7.2400000000 0.0102389036 0.0085730683 0.0154821081 0.0054600643 0.0180360000 200661374 95654128 760807424 0.8937228918 0.0743494779 0.2426047474 183 7.2800000000 0.0092035308 0.0085765135 0.0154821081 0.0054456157 0.0180530000 200663982 95654128 760807424 0.8995746374 0.0773744062 0.2515998483 184 7.3200000000 0.0088380864 0.0085779351 0.0154821081 0.0054422231 0.0215220000 200664790 95654128 760807424 0.9046201110 0.0787059367 0.2594234943 185 7.3600000000 0.0092527512 0.0085815827 0.0154821081 0.0054312524 0.0214430000 200667598 95654128 760807424 0.9078191519 0.0782196373 0.2660320699 186 7.4000000000 0.0085721668 0.0085815321 0.0154821081 0.0054173197 0.0182960000 200668406 95654128 760807424 0.9136627913 0.0801149681 0.2746235430 187 7.4400000000 0.0093771154 0.0085857866 0.0154821081 0.0054124681 0.0181400000 200671046 95654128 760807424 0.9200146794 0.0798512548 0.2820589840 188 7.4800000000 0.0098176729 0.0085923392 0.0154821081 0.0054020734 0.0180760000 200673654 95654128 760807424 0.9222481847 0.0810073987 0.2890391052 189 7.5200000000 0.0095214015 0.0085972548 0.0154821081 0.0053877313 0.0182420000 200676306 95654128 760807424 0.9266170859 0.0806761086 0.2952969968 190 7.5600000000 0.0085945698 0.0085972407 0.0154821081 0.0053805991 0.0181710000 200847558 95654128 760807424 0.9330164790 0.0819818079 0.3028107882 191 7.6000000000 0.0100066345 0.0086046197 0.0154821081 0.0053723170 0.0216210000 200850166 95654128 760807424 0.9358075857 0.0825915784 0.3111229241 192 7.6400000000 0.0127144028 0.0086260248 0.0154821081 0.0053621364 0.0184140000 200850974 95654128 760807424 0.9383131266 0.0814805701 0.3200267255 193 7.6800000000 0.0107002007 0.0086367719 0.0154821081 0.0053497926 0.0182360000 200853782 95654128 760807424 0.9444748163 0.0850712061 0.3342565894 194 7.7200000000 0.0105866157 0.0086468226 0.0154821081 0.0053363908 0.0182920000 200856390 95654128 760807424 0.9469166994 0.0881032869 0.3436351717 195 7.7600000000 0.0118402168 0.0086631990 0.0154821081 0.0053247110 0.0182430000 200857198 95654128 760807424 0.9517455697 0.0881503969 0.3614127040 196 7.8000000000 0.0118278358 0.0086793451 0.0154821081 0.0053199776 0.0183230000 200859806 95654128 760807424 0.9513515234 0.0875986293 0.3712148070 197 7.8400000000 0.0105566727 0.0086888747 0.0154821081 0.0053074438 0.0186870000 200860814 95654128 760807424 0.9546715021 0.0894905925 0.3811725676 198 7.8800000000 0.0119399009 0.0087052940 0.0154821081 0.0052949391 0.0322070000 200863438 95654128 760807424 0.9568992257 0.0886177942 0.3920531869 199 7.9200000000 0.0119283032 0.0087214900 0.0154821081 0.0052894279 0.0213230000 200866046 95654128 760807424 0.9567203522 0.0878313035 0.4020691812 200 7.9600000000 0.0112797609 0.0087342814 0.0154821081 0.0052796970 0.0186540000 200866854 95654128 760807424 0.9590651989 0.0893332809 0.4130457938 201 8.0000000000 0.0113473078 0.0087472815 0.0154821081 0.0052675645 0.0218450000 200869662 95654128 760807424 0.9608291984 0.0892474875 0.4244051576 202 8.0400000000 0.0114300000 0.0087605623 0.0154821081 0.0052545907 0.0186260000 200872270 95654128 760807424 0.9619538784 0.0891749710 0.4347718954 203 8.0800000000 0.0107550994 0.0087703876 0.0154821081 0.0052424041 0.0281790000 200873078 95654128 760807424 0.9622262120 0.0900325999 0.4451763332 204 8.1200000000 0.0105169071 0.0087789490 0.0154821081 0.0052337883 0.0196320000 200875686 95654128 760807424 0.9620887637 0.0917275399 0.4557329118 205 8.1600000000 0.0115002124 0.0087922234 0.0154821081 0.0052448655 0.0184130000 200878494 95654128 760807424 0.9630164504 0.0925954282 0.4676321149 206 8.1999999990 0.0109643228 0.0088027676 0.0154821081 0.0052472690 0.0184570000 200879302 95654128 760807424 0.9633491635 0.0953195244 0.4796243608 207 8.2400000000 0.0120435469 0.0088184235 0.0154821081 0.0052401155 0.0184420000 200881910 95654128 760807424 0.9634066224 0.0968321562 0.4927651584 208 8.2799999990 0.0114631802 0.0088311387 0.0154821081 0.0052417906 0.0184960000 200884518 95654128 760807424 0.9636873007 0.1003265679 0.5043726563 209 8.3200000000 0.0119404066 0.0088460156 0.0154821081 0.0052337075 0.0184780000 200885526 95654128 760807424 0.9638285637 0.1013664678 0.5160714984 210 8.3599999990 0.0111941304 0.0088571971 0.0154821081 0.0052221242 0.0185190000 200888134 95654128 760807424 0.9650351405 0.1034734696 0.5276495218 211 8.4000000000 0.0112154726 0.0088683738 0.0154821081 0.0052189269 0.0185230000 200888942 95654136 760807424 0.9658378363 0.1055162847 0.5399525166 212 8.4399999990 0.0115007320 0.0088807905 0.0154821081 0.0052109061 0.0185510000 200891566 95654136 760807424 0.9647579789 0.1069791764 0.5522754192 213 8.4800000000 0.0119487634 0.0088951942 0.0154821081 0.0052040407 0.0216090000 200894374 95654136 760807424 0.9643579125 0.1083748341 0.5637132525 214 8.5200000000 0.0105952518 0.0089031384 0.0154821081 0.0052020595 0.0187430000 200895182 95654136 760807424 0.9637336731 0.1119269729 0.5748857856 215 8.5600000000 0.0104195802 0.0089101916 0.0154821081 0.0051919844 0.0220070000 200897790 95654136 760807424 0.9639560580 0.1152926683 0.5869117975 216 8.6000000000 0.0096605625 0.0089136655 0.0154821081 0.0051836296 0.0188350000 200900398 95654136 760807424 0.9642643332 0.1183316559 0.5991465449 217 8.6400000000 0.0105959959 0.0089214182 0.0154821081 0.0051781983 0.0185570000 200901406 95654136 760807424 0.9631841183 0.1190481335 0.6105261445 218 8.6800000000 0.0097537516 0.0089252362 0.0154821081 0.0051696402 0.0190310000 200904014 95654136 760807424 0.9619892240 0.1212994009 0.6208527088 219 8.7200000000 0.0100231161 0.0089302494 0.0154821081 0.0051629843 0.0189770000 200906622 95654136 760807424 0.9595396519 0.1220499203 0.6312298179 220 8.7600000000 0.0094091501 0.0089324262 0.0154821081 0.0051528724 0.0190620000 200907430 95654136 760807424 0.9556995630 0.1230018213 0.6407381296 221 8.8000000000 0.0104636503 0.0089393548 0.0154821081 0.0051417124 0.0190960000 200910254 95654136 760807424 0.9550219774 0.1244234368 0.6529489756 222 8.8400000000 0.0095644202 0.0089421704 0.0154821081 0.0051323623 0.0191020000 200911062 95654136 760807424 0.9544796348 0.1258940250 0.6636428833 223 8.8800000000 0.0091292066 0.0089430092 0.0154821081 0.0051212769 0.0192030000 200913670 95654136 760807424 0.9520627856 0.1262549013 0.6730222702 224 8.9200000000 0.0087654172 0.0089422163 0.0154821081 0.0051114689 0.0223240000 200916278 95654136 760807424 0.9507729411 0.1271820366 0.6832959652 225 8.9600000000 0.0092475377 0.0089435733 0.0154821081 0.0051014274 0.0192680000 200917286 95654136 760807424 0.9492567182 0.1284748465 0.6946505904 226 9.0000000000 0.0089999102 0.0089438226 0.0154821081 0.0050921484 0.0191970000 200919910 95654136 760807424 0.9494040012 0.1311118156 0.7155278921 227 9.0400000000 0.0095243808 0.0089463801 0.0154821081 0.0050820732 0.0193040000 200922518 95654136 760807424 0.9500988126 0.1326834410 0.7270911336 228 9.0800000000 0.0093894517 0.0089483234 0.0154821081 0.0050720807 0.0192820000 200923326 95654136 760807424 0.9472950101 0.1345265955 0.7366307974 229 9.1200000000 0.0086909113 0.0089471994 0.0154821081 0.0050828744 0.0227680000 200926134 95654136 760807424 0.9473546147 0.1370405257 0.7474634647 230 9.1600000000 0.0083098011 0.0089444281 0.0154821081 0.0050799461 0.0203000000 200928774 95654136 760807424 0.9481734633 0.1387974173 0.7578985095 231 9.2000000000 0.0084484192 0.0089422808 0.0154821081 0.0050749265 0.0228200000 200929582 95654136 760807424 0.9471964836 0.1399713308 0.7755249739 232 9.2400000000 0.0089992126 0.0089425262 0.0154821081 0.0050684382 0.0195150000 200932190 95654136 760807424 0.9473928809 0.1420519948 0.7879862785 233 9.2800000000 0.0088941893 0.0089423188 0.0154821081 0.0050675208 0.0194330000 200933198 95654136 760807424 0.9479107261 0.1448557675 0.8003085256 234 9.3200000000 0.0094454139 0.0089444688 0.0154821081 0.0050697903 0.0194350000 200935822 95654136 760807424 0.9469249845 0.1470295638 0.8115286827 235 9.3600000000 0.0072203912 0.0089371323 0.0154821081 0.0050671723 0.0196690000 200940450 95654136 760807424 0.9474390149 0.1504330337 0.8221804500 236 9.4000000000 0.0080471095 0.0089333610 0.0154821081 0.0050595611 0.0249600000 201109934 95654136 760807424 0.9501259923 0.1499194801 0.8316026330 237 9.4400000000 0.0080116885 0.0089294721 0.0154821081 0.0050662900 0.0201520000 201112742 95654136 760807424 0.9506443143 0.1525701284 0.8425050378 238 9.4800000000 0.0082023079 0.0089264167 0.0154821081 0.0050685296 0.0194840000 201115350 95654136 760807424 0.9502675533 0.1542910635 0.8529420495 239 9.5200000000 0.0082699722 0.0089236701 0.0154821081 0.0050707676 0.0195060000 201116158 95654136 760807424 0.9532465339 0.1561032087 0.8635545969 240 9.5600000000 0.0081721162 0.0089205386 0.0154821081 0.0050693356 0.0196580000 201118766 95654136 760807424 0.9529278874 0.1571054608 0.8733301163 241 9.6000000000 0.0079385629 0.0089164641 0.0154821081 0.0050588306 0.0196250000 201121590 95654136 760807424 0.9519866705 0.1587243825 0.8829052448 242 9.6400000000 0.0084615080 0.0089145841 0.0154821081 0.0050566302 0.0195370000 201122398 95654136 760807424 0.9523465633 0.1607851237 0.8948613405 243 9.6800000000 0.0083730891 0.0089123557 0.0154821081 0.0050475015 0.0196030000 201125006 95654136 760807424 0.9551543593 0.1633458138 0.9081772566 244 9.7200000000 0.0083978903 0.0089102472 0.0154821081 0.0050373083 0.0195990000 201127614 95654136 760807424 0.9568654299 0.1669861078 0.9204360843 245 9.7600000000 0.0081921341 0.0089073162 0.0154821081 0.0050293219 0.0196450000 201128622 95654136 760807424 0.9570596218 0.1679831296 0.9307857156 246 9.8000000000 0.0080471979 0.0089038197 0.0154821081 0.0050197147 0.0203660000 201131230 95654136 760807424 0.9576936364 0.1710946262 0.9420166612 247 9.8400000000 0.0076184985 0.0088986160 0.0154821081 0.0050102672 0.0198170000 201132038 95654136 760807424 0.9588493705 0.1739448905 0.9534249902 248 9.8800000000 0.0073116557 0.0088922170 0.0154821081 0.0050067194 0.0223360000 201134646 95654136 760807424 0.9580903053 0.1775968969 0.9636667967 249 9.9200000000 0.0077058505 0.0088874525 0.0154821081 0.0049974347 0.0198030000 201137454 95654136 760807424 0.9591545463 0.1783992648 0.9742828608 250 9.9600000000 0.0071913428 0.0088806680 0.0154821081 0.0049878718 0.0197520000 201138278 95654136 760807424 0.9599466920 0.1807106137 0.9847511649 251 10.0000000000 0.0072256653 0.0088740744 0.0154821081 0.0049791306 0.0197640000 201140886 95654136 760807424 0.9604346156 0.1812784225 0.9948003888 252 10.0400000000 0.0068072849 0.0088658728 0.0154821081 0.0049696807 0.0232140000 201143494 95654136 760807424 0.9613285065 0.1833075732 1.0043311119 253 10.0800000000 0.0067993598 0.0088577048 0.0154821081 0.0049621278 0.0199830000 201144502 95654136 760807424 0.9604979753 0.1852783561 1.0136570930 254 10.1200000000 0.0064303759 0.0088481484 0.0154821081 0.0049580798 0.0198370000 201147110 95654136 760807424 0.9618999958 0.1874461472 1.0229119062 255 10.1600000000 0.0068658455 0.0088403746 0.0154821081 0.0049492752 0.0193520000 201149718 95654136 760807424 0.9611857533 0.1887782663 1.0323110819 256 10.2000000000 0.0061031999 0.0088296826 0.0154821081 0.0049459048 0.0198320000 201150526 95654136 760807424 0.9601871967 0.1903523952 1.0400564671 257 10.2400000000 0.0073876944 0.0088240717 0.0154821081 0.0049693797 0.0198860000 201175862 95654136 760807424 0.9583347440 0.1909341663 1.0488111973 258 10.2800000000 0.0077000535 0.0088197151 0.0154821081 0.0049684809 0.0199130000 201227870 95654136 760807424 0.9583761096 0.1924632639 1.0583661795 259 10.3200000000 0.0076260096 0.0088151062 0.0154821081 0.0049724052 0.0229570000 201230478 95654136 760807424 0.9576391578 0.1936506778 1.0665199757 260 10.3600000000 0.0090092309 0.0088158528 0.0154821081 0.0049863594 0.0200370000 201233118 95654136 760807424 0.9544583559 0.1939066648 1.0743420124 261 10.4000000000 0.0092744175 0.0088176097 0.0154821081 0.0049772652 0.0199210000 201234126 95654136 760807424 0.9533374906 0.1953647882 1.0836945772 262 10.4400000000 0.0085850339 0.0088167220 0.0154821081 0.0049679310 0.0199680000 201236734 95654136 760807424 0.9546160698 0.1973840147 1.0926809311 263 10.4800000000 0.0088563012 0.0088168725 0.0154821081 0.0049585800 0.0199740000 201239342 95654136 760807424 0.9539539814 0.1987518668 1.1023238897 264 10.5200000000 0.0083138635 0.0088149672 0.0154821081 0.0049526086 0.0202090000 201243546 95654136 760807424 0.9513809681 0.2001203150 1.1102367640 265 10.5600000000 0.0083227698 0.0088131098 0.0154821081 0.0049437999 0.0200530000 201414954 95654136 760807424 0.9507282972 0.2002171725 1.1180270910 266 10.6000000000 0.0082630701 0.0088110420 0.0154821081 0.0049352322 0.0200520000 201417562 95654136 760807424 0.9510719180 0.2015017569 1.1264156103 267 10.6400000000 0.0082654404 0.0088089986 0.0154821081 0.0049279535 0.0201120000 201418370 95654136 760807424 0.9498652816 0.2029706389 1.1347708702 268 10.6800000000 0.0078057940 0.0088052553 0.0154821081 0.0049217831 0.0200850000 201420994 95654136 760807424 0.9490043521 0.2054580152 1.1442340612 269 10.7200000000 0.0087536508 0.0088050634 0.0154821081 0.0049207700 0.0236620000 201422002 95654136 760807424 0.9476361275 0.2050579041 1.1533702612 270 10.7600000000 0.0086120330 0.0088043485 0.0154821081 0.0049127577 0.0202390000 201424610 95654136 760807424 0.9451925755 0.2077624947 1.1625604630 271 10.8000000000 0.0080940472 0.0088017275 0.0154821081 0.0049065190 0.0202390000 201427218 95654136 760807424 0.9426953793 0.2103990018 1.1723403931 272 10.8400000000 0.0081065046 0.0087991715 0.0154821081 0.0048975649 0.0202120000 201428026 95654136 760807424 0.9404858947 0.2120152116 1.1817617416 273 10.8800000000 0.0075893770 0.0087947400 0.0154821081 0.0048888898 0.0201560000 201430834 95654136 760807424 0.9363898635 0.2131059170 1.1905852556 274 10.9200000000 0.0077986964 0.0087911048 0.0154821081 0.0048835631 0.0201770000 201433442 95654136 760807424 0.9352087379 0.2148390263 1.2007778883 275 10.9600000000 0.0080092810 0.0087882618 0.0154821081 0.0048758314 0.0202210000 201434250 95654136 760807424 0.9335222840 0.2179460078 1.2103834152 276 11.0000000000 0.0071980953 0.0087825004 0.0154821081 0.0048678869 0.0202160000 201436858 95654136 760807424 0.9291960001 0.2182476223 1.2182902098 277 11.0400000000 0.0072577656 0.0087769959 0.0154821081 0.0048660824 0.0254980000 201439666 95654136 760807424 0.9290199280 0.2203438133 1.2288556099 278 11.0800000000 0.0071060583 0.0087709853 0.0154821081 0.0048573911 0.0213050000 201440474 95654136 760807424 0.9240071774 0.2215912491 1.2378826141 279 11.1200000000 0.0073898239 0.0087660349 0.0154821081 0.0048494823 0.0203290000 201443082 95654136 760807424 0.9196911454 0.2212395072 1.2473628521 280 11.1600000000 0.0075242254 0.0087615999 0.0154821081 0.0048417811 0.0201980000 201445690 95654136 760807424 0.9167576432 0.2237187624 1.2579330206 281 11.2000000000 0.0071295733 0.0087557920 0.0154821081 0.0048343368 0.0202160000 201446698 95654136 760807424 0.9152533412 0.2277364433 1.2673956156 282 11.2400000000 0.0069616348 0.0087494297 0.0154821081 0.0048261871 0.0202290000 201449306 95654136 760807424 0.9111888409 0.2291684449 1.2760426998 283 11.2800000000 0.0069025485 0.0087429036 0.0154821081 0.0048182759 0.0202070000 201450114 95654136 760807424 0.9087691307 0.2321575880 1.2854921818 284 11.3200000000 0.0073683681 0.0087380637 0.0154821081 0.0048123239 0.0206490000 201452722 95654136 760807424 0.9025185704 0.2347915471 1.2963385582 285 11.3600000000 0.0069687734 0.0087318557 0.0154821081 0.0048042403 0.0206480000 201455530 95654136 760807424 0.8979220986 0.2357722372 1.3057364225 286 11.4000000000 0.0076328460 0.0087280130 0.0154821081 0.0048073265 0.0203570000 201456354 95654136 760807424 0.8994906545 0.2383491248 1.3159058094 287 11.4400000000 0.0070771826 0.0087222610 0.0154821081 0.0048010033 0.0207880000 201458962 95654136 760807424 0.8969342709 0.2423870414 1.3250006437 288 11.4800000000 0.0062439144 0.0087136556 0.0154821081 0.0047935359 0.0203810000 201461570 95654136 760807424 0.8901250958 0.2441313267 1.3319836855 289 11.5200000000 0.0068512536 0.0087072113 0.0154821081 0.0047893186 0.0203850000 201462578 95654136 760807424 0.8846048117 0.2420703471 1.3394421339 290 11.5600000000 0.0077754147 0.0087039982 0.0154821081 0.0047843111 0.0207360000 201467870 95654136 760807424 0.8810781837 0.2421958745 1.3480497599 291 11.6000000000 0.0071025696 0.0086984950 0.0154821081 0.0047764376 0.0204080000 201639138 95654136 760807424 0.8796181679 0.2450988442 1.3560161591 292 11.6400000000 0.0072937477 0.0086936842 0.0154821081 0.0047685751 0.0206620000 201639946 95654136 760807424 0.8751679063 0.2460028976 1.3640240431 293 11.6800000000 0.0074295681 0.0086893699 0.0154821081 0.0047610569 0.0207160000 201642754 95654136 760807424 0.8731226921 0.2481931597 1.3705061674 294 11.7200000000 0.0075310348 0.0086854299 0.0154821081 0.0047578618 0.0214060000 201643562 95654136 760807424 0.8693257570 0.2471472770 1.3773615360 295 11.7600000000 0.0084484378 0.0086846266 0.0154821081 0.0047571419 0.0207540000 201646170 95654136 760807424 0.8683242202 0.2466785908 1.3849473000 296 11.8000000000 0.0085697342 0.0086842384 0.0154821081 0.0047779357 0.0208380000 201648778 95654136 760807424 0.8655059338 0.2471152097 1.3929107189 297 11.8400000000 0.0083593596 0.0086831446 0.0154821081 0.0048056344 0.0208330000 201649802 95654136 760807424 0.8612238169 0.2472322136 1.4003481865 298 11.8800000000 0.0088626677 0.0086837470 0.0154821081 0.0048158335 0.0241980000 201652410 95654136 760807424 0.8581861854 0.2463987768 1.4089791775 299 11.9200000000 0.0091248415 0.0086852222 0.0154821081 0.0048104445 0.0203800000 201655018 95654136 760807424 0.8565572500 0.2456905395 1.4172015190 300 11.9600000000 0.0093933567 0.0086875827 0.0154821081 0.0048137691 0.0207440000 201655826 95654136 760807424 0.8542026877 0.2450811714 1.4248344898 301 12.0000000000 0.0105733853 0.0086938478 0.0154821081 0.0048114120 0.0305440000 201658634 95654136 760807424 0.8530109525 0.2446001619 1.4341957569 302 12.0400000000 0.0088366065 0.0086943205 0.0154821081 0.0048065137 0.0229440000 201661386 95654136 760807424 0.8526553512 0.2467279285 1.4429228306 303 12.0800000000 0.0086469725 0.0086941642 0.0154821081 0.0047994328 0.0220980000 201662410 95654136 760807424 0.8511604667 0.2459893376 1.4508409500 304 12.1200000000 0.0094290879 0.0086965818 0.0154821081 0.0047949410 0.0216480000 201665018 95654136 760807424 0.8486471772 0.2467567623 1.4600962400 305 12.1600000000 0.0086886585 0.0086965558 0.0154821081 0.0047874915 0.0203580000 201665826 95654136 760807424 0.8486074209 0.2480162680 1.4695470333 306 12.2000000000 0.0077908910 0.0086935961 0.0154821081 0.0047801755 0.0203820000 201668634 95654136 760807424 0.8456152678 0.2503018975 1.4784992933 307 12.2400000000 0.0084030973 0.0086926498 0.0154821081 0.0047731445 0.0207850000 201671242 95654136 760807424 0.8435402513 0.2514356673 1.4880895615 308 12.2800000000 0.0079032667 0.0086900869 0.0154821081 0.0047748639 0.0203870000 201672082 95654136 760807424 0.8422814608 0.2529537976 1.4978175163 309 12.3200000000 0.0077783396 0.0086871363 0.0154821081 0.0047736582 0.0278320000 201674690 95654136 760807424 0.8406668305 0.2539367974 1.5070631504 310 12.3600000000 0.0071326932 0.0086821219 0.0154821081 0.0047743968 0.0208050000 201677498 95654136 760807424 0.8406106234 0.2566213310 1.5166724920 311 12.4000000000 0.0075788726 0.0086785745 0.0154821081 0.0047963114 0.0213060000 201678306 95654136 760807424 0.8390473723 0.2585119307 1.5268164873 312 12.4400000000 0.0076218662 0.0086751876 0.0154821081 0.0048079980 0.0203630000 201680930 95654136 760807424 0.8378833532 0.2574518025 1.5347281694 313 12.4800000000 0.0077234488 0.0086721469 0.0154821081 0.0048084951 0.0243740000 201683538 95654136 760807424 0.8369107842 0.2583743334 1.5440444946 314 12.5200000000 0.0066073858 0.0086655712 0.0154821081 0.0048075628 0.0209160000 201684546 95654136 760807424 0.8352791667 0.2610629499 1.5534378290 315 12.5600000000 0.0073564765 0.0086614154 0.0154821081 0.0048018802 0.0217180000 201689742 95654136 760807424 0.8341907859 0.2608915865 1.5616681576 316 12.6000000000 0.0078878589 0.0086589674 0.0154821081 0.0047957833 0.0209400000 201859230 95654136 760807424 0.8340452909 0.2606495321 1.5697288513 317 12.6400000000 0.0085002286 0.0086584667 0.0154821081 0.0047889519 0.0211070000 201861838 95654136 760807424 0.8330324292 0.2614020109 1.5784622431 318 12.6800000000 0.0079561966 0.0086562583 0.0154821081 0.0047885036 0.0206780000 201864646 95654136 760807424 0.8341711164 0.2625155151 1.5872677565 319 12.7200000000 0.0066181156 0.0086498691 0.0154821081 0.0047842387 0.0210450000 201865454 95654136 760807424 0.8317953348 0.2668897510 1.5975376368 320 12.7600000000 0.0064673312 0.0086430487 0.0154821081 0.0047838772 0.0307170000 201868062 95654136 760807424 0.8296750784 0.2679986656 1.6066385508 321 12.8000000000 0.0070081917 0.0086379557 0.0154821081 0.0047984716 0.0244580000 201870670 95654136 760807424 0.8276703954 0.2694725990 1.6158425808 322 12.8400000000 0.0065721502 0.0086315401 0.0154821081 0.0048046715 0.0208610000 201871678 95654136 760807424 0.8263727427 0.2725625932 1.6246265173 323 12.8800000000 0.0067378879 0.0086256774 0.0154821081 0.0048198825 0.0215930000 201874286 95654136 760807424 0.8249804378 0.2739564180 1.6329630613 324 12.9200000000 0.0073192175 0.0086216451 0.0154821081 0.0048348885 0.0206790000 201876894 95654136 760807424 0.8232242465 0.2739198506 1.6400684118 325 12.9600000000 0.0075908992 0.0086184736 0.0154821081 0.0048468339 0.0206160000 201877702 95654136 760807424 0.8230344653 0.2738785446 1.6472938061 326 13.0000000000 0.0082181999 0.0086172458 0.0154821081 0.0048548865 0.0207120000 201880510 95654136 760807424 0.8218106031 0.2738672793 1.6553839445 327 13.0400000000 0.0067058192 0.0086114004 0.0154821081 0.0049475433 0.0207270000 201881318 95654136 760807424 0.8187103868 0.2807333767 1.6731810570 328 13.0800000000 0.0076218806 0.0086083836 0.0154821081 0.0049770632 0.0297510000 201883926 95654136 760807424 0.8161810040 0.2802022696 1.6824781895 329 13.1200000000 0.0068952288 0.0086031765 0.0154821081 0.0049820019 0.0215140000 201886534 95654136 760807424 0.8140808940 0.2822268307 1.6905552149 330 13.1600000000 0.0069651566 0.0085982128 0.0154821081 0.0049814906 0.0205600000 201887542 95654136 760807424 0.8128003478 0.2824039161 1.6978886127 331 13.2000000000 0.0073932237 0.0085945723 0.0154821081 0.0049834119 0.0206960000 201892774 95654136 760807424 0.8116146326 0.2821566164 1.7046675682 332 13.2400000000 0.0072204848 0.0085904335 0.0154821081 0.0049779157 0.0205540000 202064042 95654136 760807424 0.8105974197 0.2838136852 1.7122045755 333 13.2800000000 0.0071090129 0.0085859848 0.0154821081 0.0049743935 0.0205470000 202064850 95654136 760807424 0.8095555305 0.2855994403 1.7196288109 334 13.3200000000 0.0075782202 0.0085829675 0.0154821081 0.0049763129 0.0204530000 202067658 95654136 760807424 0.8086926341 0.2852708101 1.7259453535 335 13.3600000000 0.0065615745 0.0085769335 0.0154821081 0.0049840881 0.0205100000 202070266 95654136 760807424 0.8069195151 0.2895840108 1.7342823744 336 13.4000000000 0.0072391452 0.0085729520 0.0154821081 0.0049957764 0.0205040000 202071074 95654136 760807424 0.8042357564 0.2896039784 1.7407481670 337 13.4400000000 0.0077711460 0.0085705728 0.0154821081 0.0050146035 0.0205630000 202073682 95654136 760807424 0.8021963835 0.2885959744 1.7461004257 338 13.4800000000 0.0079410411 0.0085687102 0.0154821081 0.0050391795 0.0243490000 202074690 95654136 760807424 0.7985950708 0.2885656357 1.7515245676 339 13.5200000000 0.0080029657 0.0085670414 0.0154821081 0.0050547313 0.0206440000 202077298 95654136 760807424 0.7965918183 0.2903091013 1.7587273121 340 13.5600000000 0.0086084651 0.0085671632 0.0154821081 0.0050819563 0.0205770000 202079906 95654136 760807424 0.7914960980 0.2902767956 1.7648197412 341 13.6000000000 0.0089718634 0.0085683500 0.0154821081 0.0050917940 0.0207440000 202080714 95654136 760807424 0.7875660062 0.2910147905 1.7718527317 342 13.6400000000 0.0089768181 0.0085695444 0.0154821081 0.0051137718 0.0205990000 202083522 95654136 760807424 0.7830536366 0.2953690588 1.7798553705 343 13.6800000000 0.0095405392 0.0085723753 0.0154821081 0.0051291949 0.0205870000 202086130 95654136 760807424 0.7781695127 0.2986775637 1.7883613110 344 13.7200000000 0.0098198773 0.0085760017 0.0154821081 0.0051340275 0.0205220000 202089454 95654136 760807424 0.7738692164 0.3006626666 1.7946788073 345 13.7600000000 0.0103432517 0.0085811242 0.0154821081 0.0051337940 0.0204580000 202260726 95654136 760807424 0.7721922994 0.2981428504 1.7994425297 346 13.8000000000 0.0105325319 0.0085867641 0.0154821081 0.0051375325 0.0316910000 202263534 95654136 760807424 0.7691100836 0.2993263602 1.8035048246 347 13.8400000000 0.0111626424 0.0085941874 0.0154821081 0.0051455001 0.0238800000 202264342 95654136 760807424 0.7650622725 0.2973258793 1.8092525005 348 13.8800000000 0.0111428713 0.0086015112 0.0154821081 0.0051566731 0.0208010000 202266950 95654136 760807424 0.7604354024 0.2979182899 1.8157014847 349 13.9200000000 0.0106688961 0.0086074349 0.0154821081 0.0051547696 0.0203350000 202269558 95654136 760807424 0.7547607422 0.2983766794 1.8229758739 350 13.9600000000 0.0097108064 0.0086105874 0.0154821081 0.0051741852 0.0203450000 202270566 95654136 760807424 0.7490613461 0.3024162650 1.8303049803 351 14.0000000000 0.0098489458 0.0086141155 0.0154821081 0.0051745540 0.0202480000 202273174 95654136 760807424 0.7439792156 0.3020451367 1.8369252682 352 14.0400000000 0.0094725983 0.0086165544 0.0154821081 0.0051705672 0.0202760000 202273982 95654136 760807424 0.7390427589 0.3010979593 1.8408311605 353 14.0800000000 0.0095346523 0.0086191552 0.0154821081 0.0051639365 0.0202580000 202276590 95654136 760807424 0.7355694771 0.2985150516 1.8459944725 354 14.1200000000 0.0081368163 0.0086177927 0.0154821081 0.0051737525 0.0202090000 202279398 95654136 760807424 0.7296924591 0.3040148616 1.8538917303 355 14.1600000000 0.0102432258 0.0086223713 0.0154821081 0.0051833341 0.0202070000 202280206 95654136 760807424 0.7227294445 0.3018020689 1.8595407009 356 14.2000000000 0.0111010177 0.0086293338 0.0154821081 0.0051845379 0.0201550000 202282814 95654136 760807424 0.7156554461 0.3016304076 1.8637818098 357 14.2400000000 0.0099799344 0.0086331170 0.0154821081 0.0051853952 0.0203660000 202288202 95654136 760807424 0.7086160779 0.3044617772 1.8699576855 358 14.2800000000 0.0094966339 0.0086355291 0.0154821081 0.0051817291 0.0202600000 202457890 95654136 760807424 0.7037771344 0.3044739068 1.8755748272 359 14.3200000000 0.0098044826 0.0086387852 0.0154821081 0.0051822652 0.0237770000 202460498 95654136 760807424 0.6941179037 0.3091802001 1.8825520277 360 14.3600000000 0.0102790743 0.0086433416 0.0154821081 0.0051950984 0.0204320000 202463106 95654136 760807424 0.6773726344 0.3139580190 1.8941131830 361 14.4000000000 0.0106319869 0.0086488503 0.0154821081 0.0051895963 0.0201530000 202463914 95654136 760807424 0.6669920683 0.3192740679 1.9028975964 362 14.4400000000 0.0088917641 0.0086495213 0.0154821081 0.0051940788 0.0201900000 202466722 95654136 760807424 0.6516351700 0.3190153241 1.9100865126 363 14.4800000000 0.0089181624 0.0086502614 0.0154821081 0.0051903116 0.0201420000 202467530 95654136 760807424 0.6463146210 0.3155310750 1.9142540693 364 14.5200000000 0.0083726505 0.0086494987 0.0154821081 0.0051852272 0.0295540000 202470138 95654136 760807424 0.6392991543 0.3158267438 1.9209165573 365 14.5600000000 0.0075453366 0.0086464736 0.0154821081 0.0051803163 0.0211310000 202472746 95654136 760807424 0.6319551468 0.3157972693 1.9263945818 366 14.6000000000 0.0095207710 0.0086488624 0.0154821081 0.0051898052 0.0200260000 202473754 95654136 760807424 0.6128634214 0.3242849112 1.9390915632 367 14.6400000000 0.0096829757 0.0086516802 0.0154821081 0.0051832948 0.0200270000 202476362 95654136 760807424 0.6029448509 0.3282697499 1.9441736937 368 14.6800000000 0.0090658609 0.0086528056 0.0154821081 0.0051776148 0.0208560000 202478970 95654136 760807424 0.5945528746 0.3283042014 1.9485408068 369 14.7200000000 0.0080917384 0.0086512851 0.0154821081 0.0051760627 0.0236310000 202479778 95654136 760807424 0.5867757201 0.3267614245 1.9505081177 370 14.7600000000 0.0075187599 0.0086482243 0.0154821081 0.0051743525 0.0202050000 202482586 95654136 760807424 0.5793347359 0.3250541389 1.9527585506 371 14.8000000000 0.0073855566 0.0086448208 0.0154821081 0.0051706438 0.0199880000 202485194 95654136 760807424 0.5699739456 0.3277579248 1.9597835541 372 14.8400000000 0.0070070592 0.0086404183 0.0154821081 0.0051647023 0.0196780000 202488198 95654136 760807424 0.5616016388 0.3293032646 1.9654337168 373 14.8800000000 0.0064978888 0.0086346742 0.0154821081 0.0051628308 0.0196390000 202659474 95654136 760807424 0.5521795750 0.3310305178 1.9703509808 374 14.9200000000 0.0053994274 0.0086260238 0.0154821081 0.0051582654 0.0196250000 202660482 95654136 760807424 0.5420247912 0.3321669698 1.9732624292 375 14.9600000000 0.0039897696 0.0086136605 0.0154821081 0.0051516278 0.0196930000 202663090 95654136 760807424 0.5331187844 0.3312929869 1.9738159180 376 15.0000000000 0.0040778532 0.0086015972 0.0154821081 0.0051453231 0.0194520000 202665698 95654136 760807424 0.5242266059 0.3302197754 1.9786043167 377 15.0400000000 0.0022687069 0.0085847990 0.0154821081 0.0051698927 0.0195780000 202666506 95654136 760807424 0.5065634847 0.3312320709 1.9857476950 378 15.0800000000 0.0027360073 0.0085693260 0.0154821081 0.0051653727 0.0193520000 202669314 95654136 760807424 0.4976294041 0.3312781155 1.9894946814 379 15.1200000000 0.0024742533 0.0085532441 0.0154821081 0.0051626373 0.0194220000 202671922 95654136 760807424 0.4909565747 0.3312487602 1.9926084280 380 15.1600000000 0.0028434247 0.0085382182 0.0154821081 0.0051589954 0.0193880000 202672730 95654136 760807424 0.4835926592 0.3296614885 1.9959393740 381 15.2000000000 0.0026834132 0.0085228513 0.0154821081 0.0051688472 0.0193260000 202675338 95654136 760807424 0.4759226441 0.3314600289 2.0017745495 382 15.2400000000 0.0036648524 0.0085101340 0.0154821081 0.0051659865 0.0196220000 202678146 95654136 760807424 0.4672416747 0.3310298920 2.0030448437 383 15.2800000000 0.0040431949 0.0084984710 0.0154821081 0.0051681172 0.0193900000 202678954 95654136 760807424 0.4588889480 0.3303577304 2.0057067871 384 15.3200000000 0.0042093946 0.0084873015 0.0154821081 0.0051770355 0.0301700000 202681562 95654136 760807424 0.4505582452 0.3314946592 2.0110385418 385 15.3600000000 0.0043495386 0.0084765541 0.0154821081 0.0051771748 0.0204630000 202684170 95654136 760807424 0.4428297877 0.3316725492 2.0136516094 386 15.4000000000 0.0044977367 0.0084662463 0.0154821081 0.0051747462 0.0195120000 202685178 95654136 760807424 0.4358645380 0.3322274685 2.0166299343 387 15.4400000000 0.0047446834 0.0084566298 0.0154821081 0.0051749177 0.0195880000 202687786 95654136 760807424 0.4295215011 0.3326916993 2.0202105045 388 15.4800000000 0.0047147041 0.0084469857 0.0154821081 0.0051782377 0.0196600000 202688594 95654136 760807424 0.4230868816 0.3335282803 2.0237286091 389 15.5200000000 0.0048167557 0.0084376535 0.0154821081 0.0051840455 0.0196300000 202691202 95654136 760807424 0.4151482880 0.3349669576 2.0273571014 390 15.5600000000 0.0055790674 0.0084303238 0.0154821081 0.0051852496 0.0196120000 202694010 95654136 760807424 0.4076613188 0.3348273933 2.0299432278 391 15.6000000000 0.0061637149 0.0084245268 0.0154821081 0.0051809833 0.0196540000 202694818 95654136 760807424 0.4015374780 0.3350400627 2.0333538055 392 15.6400000000 0.0059191845 0.0084181356 0.0154821081 0.0051942070 0.0236820000 202699690 95654136 760807424 0.3950142562 0.3365623653 2.0387270451 393 15.6800000000 0.0067790537 0.0084139649 0.0154821081 0.0051886426 0.0282120000 202870966 95654136 760807424 0.3888065219 0.3355903625 2.0412399769 394 15.7200000000 0.0065319836 0.0084091883 0.0154821081 0.0051865120 0.0291780000 202871974 95654136 760807424 0.3820872009 0.3359869421 2.0446739197 395 15.7600000000 0.0064477324 0.0084042226 0.0154821081 0.0052006457 0.0207140000 202874582 95654136 760807424 0.3759269118 0.3380416930 2.0514972210 396 15.8000000000 0.0066927928 0.0083999008 0.0154821081 0.0052207113 0.0197350000 202877190 95654136 760807424 0.3689717054 0.3415325880 2.0571136475 397 15.8400000000 0.0073360568 0.0083972211 0.0154821081 0.0052160944 0.0197020000 202877998 95654136 760807424 0.3631738424 0.3391975462 2.0581483841 398 15.8800000000 0.0074776961 0.0083949108 0.0154821081 0.0052338303 0.0197880000 202880806 95654136 760807424 0.3584628403 0.3413442969 2.0669772625 399 15.9200000000 0.0084936386 0.0083951582 0.0154821081 0.0052367983 0.0232880000 202881614 95654136 760807424 0.3513181210 0.3434419930 2.0703122616 400 15.9600000000 0.0088716401 0.0083963494 0.0154821081 0.0052307713 0.0199060000 202884222 95654136 760807424 0.3465642929 0.3407322168 2.0730910301 401 16.0000000000 0.0093797352 0.0083988017 0.0154821081 0.0052242976 0.0197770000 202886830 95654136 760807424 0.3412078023 0.3390696347 2.0772473812 402 16.0400000000 0.0218423177 0.0084322433 0.0218423177 0.0060668080 0.0490720000 206571094 95654136 760807424 0.3327300549 0.3217108250 2.0763235092 403 16.0800000000 0.0134349521 0.0084446570 0.0218423177 0.0064048203 0.0205970000 203121422 95654136 760807424 0.3156001866 0.3301774263 2.0853242874 404 16.1200000000 0.0156363528 0.0084624582 0.0218423177 0.0065396141 0.0298580000 203124230 95654136 760807424 0.3162580132 0.3258631527 2.0917758942 405 16.1600000000 0.0166891888 0.0084827711 0.0218423177 0.0065813498 0.0213050000 203125038 95654136 760807424 0.3058366179 0.3246194124 2.0938351154 406 16.2000000000 0.0149353053 0.0084986641 0.0218423177 0.0066583819 0.0206260000 203127646 95654136 760807424 0.2974146903 0.3286165595 2.1016016006 407 16.2400000000 0.0144993858 0.0085134079 0.0218423177 0.0066589369 0.0204010000 203130254 95654136 760807424 0.2935444415 0.3304319084 2.1072728634 408 16.2800000000 0.0144764790 0.0085280232 0.0218423177 0.0066626492 0.0240370000 203131262 95654136 760807424 0.2910326123 0.3303700387 2.1135509014 409 16.3200000000 0.0129773747 0.0085389018 0.0218423177 0.0068384890 0.0202240000 203133870 95654136 760807424 0.2767118514 0.3349205554 2.1186537743 410 16.3600000000 0.0146858264 0.0085538943 0.0218423177 0.0068612601 0.0203450000 203134678 95654136 760807424 0.2771946788 0.3332985640 2.1210653782 411 16.3999999990 0.0130833015 0.0085649148 0.0218423177 0.0069585664 0.0238040000 203140506 95654136 760807424 0.2646237910 0.3361121714 2.1256852150 412 16.4400000000 0.0165187363 0.0085842202 0.0218423177 0.0069753775 0.0211200000 203311882 95654136 760807424 0.2631465495 0.3331045210 2.1275444031 413 16.4800000000 0.0120595684 0.0085926351 0.0218423177 0.0070920762 0.0298260000 203312690 95654136 760807424 0.2530576289 0.3387946784 2.1382458210 414 16.5200000000 0.0108582703 0.0085981076 0.0218423177 0.0071179700 0.0209650000 203315298 95654136 760807424 0.2460255176 0.3417963386 2.1444561481 415 16.5599999990 0.0106517356 0.0086030561 0.0218423177 0.0071499481 0.0235210000 203317906 95654136 760807424 0.2392373979 0.3450629115 2.1508874893 416 16.6000000000 0.0111469263 0.0086091712 0.0218423177 0.0071693693 0.0196880000 203318914 95654136 760807424 0.2323911190 0.3474406898 2.1543571949 417 16.6400000000 0.0116231246 0.0086163989 0.0218423177 0.0071740178 0.0198290000 203321522 95654136 760807424 0.2272007316 0.3483583927 2.1574594975 418 16.6800000000 0.0101339612 0.0086200294 0.0218423177 0.0071703962 0.0192760000 203324130 95654136 760807424 0.2245967090 0.3495552838 2.1658759117 419 16.7199999990 0.0132697476 0.0086311266 0.0218423177 0.0071739761 0.0196260000 203324938 95654136 760807424 0.2242696732 0.3518180847 2.1709055901 420 16.7600000000 0.0153992604 0.0086472412 0.0218423177 0.0072463406 0.0192330000 203327746 95654136 760807424 0.2161990702 0.3549253643 2.1728827953 421 16.8000000000 0.0182689279 0.0086700956 0.0218423177 0.0073155326 0.0194710000 203328554 95654136 760807424 0.2087915242 0.3573529720 2.1743071079 422 16.8400000000 0.0207279064 0.0086986686 0.0218423177 0.0073388385 0.0231070000 203331162 95654136 760807424 0.2021205127 0.3565091193 2.1764922142 423 16.8799999990 0.0239295140 0.0087346753 0.0239295140 0.0073381237 0.0197860000 203333770 95654136 760807424 0.1978208423 0.3523706198 2.1792113781 424 16.9200000000 0.0346963294 0.0087959056 0.0346963294 0.0073695687 0.0193140000 203334778 95654136 760807424 0.2057794482 0.3462196887 2.1882059574 425 16.9600000000 0.0440790989 0.0088789249 0.0440790989 0.0074630924 0.0192450000 203337386 95654136 760807424 0.2131100446 0.3403336704 2.1946780682 426 17.0000000000 0.0571315810 0.0089921940 0.0571315810 0.0075100949 0.0207320000 203339994 95654136 760807424 0.2204322815 0.3353579044 2.1998069286 427 17.0400000000 0.0678594187 0.0091300564 0.0678594187 0.0075283932 0.0215560000 203341002 95654136 760807424 0.2240993381 0.3300863206 2.2044274807 428 17.0800000000 0.0739108771 0.0092814135 0.0739108771 0.0075211371 0.0204680000 203343610 95654136 760807424 0.2246831954 0.3283804357 2.2094669342 429 17.1200000000 0.0804972947 0.0094474178 0.0804972947 0.0075189994 0.0205540000 203344618 95654136 760807424 0.2263560742 0.3262722790 2.2123661041 430 17.1600000000 0.0822853372 0.0096168084 0.0822853372 0.0075317717 0.0204750000 203347226 95654136 760807424 0.2241539955 0.3275481462 2.2155010700 431 17.2000000000 0.0841761902 0.0097898000 0.0841761902 0.0075491804 0.0201770000 203350034 95654136 760807424 0.2213299572 0.3267427981 2.2183985710 432 17.2400000000 0.0887093320 0.0099724841 0.0887093320 0.0075444175 0.0206320000 203350842 95654136 760807424 0.2203510851 0.3250211179 2.2237794399 433 17.2800000000 0.0926309451 0.0101633812 0.0926309451 0.0075378564 0.0202510000 203353650 95654136 760807424 0.2202994674 0.3246076107 2.2283742428 434 17.3200000000 0.0972122699 0.0103639547 0.0972122699 0.0075404487 0.0201280000 203356258 95654136 760807424 0.2191525549 0.3228411973 2.2340886593 435 17.3600000000 0.0986450091 0.0105668996 0.0986450091 0.0075484306 0.0204190000 203357266 95654136 760807424 0.2151521444 0.3202114403 2.2370483875 436 17.4000000000 0.0972657576 0.0107657502 0.0986450091 0.0075747549 0.0205000000 203359874 95654136 760807424 0.2094169408 0.3214237690 2.2398335934 437 17.4400000000 0.0948897377 0.0109582536 0.0986450091 0.0076072487 0.0203800000 203360882 95654136 760807424 0.2017147839 0.3246929348 2.2441403866 438 17.4800000000 0.0947640985 0.0111495912 0.0986450091 0.0076190408 0.0205610000 203363490 95654136 760807424 0.1965321004 0.3231106102 2.2471005917 439 17.5200000000 0.0946822688 0.0113398706 0.0986450091 0.0076189441 0.0205910000 203366298 95654136 760807424 0.1912231743 0.3222298920 2.2500321865 440 17.5600000000 0.0929787233 0.0115254135 0.0986450091 0.0076344849 0.0203150000 203367106 95654136 760807424 0.1844268739 0.3225362897 2.2518920898 441 17.6000000000 0.0894272327 0.0117020616 0.0986450091 0.0076709661 0.0204540000 203369914 95654136 760807424 0.1757370085 0.3241923451 2.2533667088 442 17.6400000000 0.0867009908 0.0118717424 0.0986450091 0.0076956817 0.0207580000 203370722 95654136 760807424 0.1684601307 0.3244003356 2.2547571659 443 17.6800000000 0.0835180506 0.0120334722 0.0986450091 0.0077222416 0.0206230000 203373530 95654136 760807424 0.1602618843 0.3272306621 2.2576861382 444 17.7200000000 0.0828621164 0.0121929962 0.0986450091 0.0077262412 0.0206480000 203376138 95654136 760807424 0.1542709619 0.3268248439 2.2603840828 445 17.7600000000 0.0808771551 0.0123473426 0.0986450091 0.0077376952 0.0204860000 203377146 95654136 760807424 0.1480383724 0.3280703723 2.2629003525 446 17.8000000000 0.0795147344 0.0124979422 0.0986450091 0.0077478998 0.0203180000 203379754 95654136 760807424 0.1416562200 0.3283272684 2.2649166584 447 17.8400000000 0.0790355429 0.0126467959 0.0986450091 0.0077515756 0.0219660000 203380762 95654136 760807424 0.1356548071 0.3281648457 2.2687380314 448 17.8800000000 0.0812824443 0.0128000004 0.0986450091 0.0077488576 0.0206590000 203383370 95654136 760807424 0.1311639547 0.3268867135 2.2720291615 449 17.9200000000 0.0824616849 0.0129551489 0.0986450091 0.0077458103 0.0201370000 203386178 95654136 760807424 0.1269868910 0.3256267607 2.2732746601 450 17.9600000000 0.0825626701 0.0131098323 0.0986450091 0.0077506162 0.0202860000 203386986 95654136 760807424 0.1221519560 0.3246537149 2.2754335403 451 18.0000000000 0.0890598372 0.0132782359 0.0986450091 0.0077546375 0.0202340000 203389794 95654136 760807424 0.1141442209 0.3193373382 2.2799539566 452 18.0400000000 0.0889868885 0.0134457329 0.0986450091 0.0077517805 0.0201170000 203392402 95654136 760807424 0.1085077971 0.3194616437 2.2827005386 453 18.0800000000 0.0901750624 0.0136151133 0.0986450091 0.0077465417 0.0203970000 203393410 95654136 760807424 0.1034686193 0.3177202046 2.2854480743 454 18.1200000000 0.0919675231 0.0137876957 0.0986450091 0.0077404289 0.0200040000 203396018 95654136 760807424 0.0979714617 0.3173775375 2.2893595695 455 18.1600000000 0.0933431536 0.0139625429 0.0986450091 0.0077349847 0.0201760000 203397026 95654136 760807424 0.0927271396 0.3175135255 2.2931149006 456 18.2000000000 0.0950031728 0.0141402636 0.0986450091 0.0077283157 0.0200670000 203399634 95654136 760807424 0.0885370672 0.3151144683 2.2942996025 457 18.2400000000 0.0967057496 0.0143209320 0.0986450091 0.0077258993 0.0203690000 203402442 95654136 760807424 0.0830888599 0.3138783574 2.2977938652 458 18.2800000000 0.0987393707 0.0145052518 0.0987393707 0.0077248706 0.0211980000 203403250 95654136 760807424 0.0773309469 0.3123294115 2.2991459370 459 18.3200000000 0.1001006737 0.0146917342 0.1001006737 0.0077215547 0.0205600000 203406058 95654136 760807424 0.0720415041 0.3103676438 2.3003520966 460 18.3600000000 0.1009859368 0.0148793303 0.1009859368 0.0077138620 0.0203510000 203406866 95654136 760807424 0.0668557361 0.3087038398 2.3013939857 461 18.4000000000 0.1014104933 0.0150670334 0.1014104933 0.0077065990 0.0201730000 203409674 95654136 760807424 0.0602429584 0.3074498773 2.3036282063 462 18.4400000000 0.1032909527 0.0152579943 0.1032909527 0.0077005980 0.0204470000 203412282 95654136 760807424 0.0543829240 0.3050655127 2.3065888882 463 18.4800000000 0.1048871726 0.0154515778 0.1048871726 0.0077041188 0.0242880000 203413290 95654136 760807424 0.0498854145 0.3037800193 2.3089470863 464 18.5200000000 0.1069021225 0.0156486695 0.1069021225 0.0076970647 0.0203920000 203415898 95654136 760807424 0.0444842838 0.3006188869 2.3100252151 465 18.5600000000 0.1091736630 0.0158497985 0.1091736630 0.0076901390 0.0201570000 203416906 95654136 760807424 0.0390035398 0.2969145775 2.3126895428 466 18.6000000000 0.1117265448 0.0160555426 0.1117265448 0.0076836602 0.0238590000 203419514 95654136 760807424 0.0342586264 0.2930720448 2.3142855167 467 18.6400000000 0.1137215719 0.0162646776 0.1137215719 0.0076757101 0.0204880000 203422322 95654136 760807424 0.0292795002 0.2913473845 2.3157567978 468 18.6800000000 0.1156717539 0.0164770859 0.1156717539 0.0076702800 0.0201280000 203423130 95654136 760807424 0.0246939249 0.2875125706 2.3158216476 469 18.7200000000 0.1174252331 0.0166923271 0.1174252331 0.0076634158 0.0201680000 203425938 95654136 760807424 0.0189324766 0.2853419781 2.3183281422 470 18.7600000000 0.1189169213 0.0169098263 0.1189169213 0.0076598626 0.0202600000 203428546 95654136 760807424 0.0140172876 0.2830507755 2.3202664852 471 18.8000000000 0.1155130193 0.0171191749 0.1189169213 0.0077178003 0.0200980000 203429554 95654136 760807424 0.0008631879 0.2862721384 2.3238642216 472 18.8400000000 0.1159257516 0.0173285108 0.1189169213 0.0077104243 0.0201070000 203432162 95654136 760807424 -0.0040199514 0.2841590643 2.3246996403 473 18.8800000000 0.1150584668 0.0175351281 0.1189169213 0.0077066785 0.0311890000 203433170 95654136 760807424 -0.0068091024 0.2823339701 2.3240168095 474 18.9200000000 0.1121128872 0.0177346592 0.1189169213 0.0077279904 0.0208860000 203435778 95654136 760807424 -0.0104873441 0.2838796973 2.3253481388 475 18.9600000000 0.1135521829 0.0179363803 0.1189169213 0.0077228239 0.0203160000 203438586 95654136 760807424 -0.0140419733 0.2802450955 2.3265209198 476 19.0000000000 0.1122479439 0.0181345139 0.1189169213 0.0077420943 0.0202670000 203439394 95654136 760807424 -0.0193825793 0.2797236741 2.3274409771 477 19.0400000000 0.1143994182 0.0183363271 0.1189169213 0.0077352146 0.0200850000 203442202 95654136 760807424 -0.0209546760 0.2743383646 2.3276875019 478 19.0800000000 0.1127586216 0.0185338633 0.1189169213 0.0077682512 0.0199360000 203443010 95654136 760807424 -0.0272966754 0.2749833465 2.3322567940 479 19.1200000000 0.1120496169 0.0187290945 0.1189169213 0.0077677016 0.0201800000 203448590 95654136 760807424 -0.0285437312 0.2749743462 2.3320102692 480 19.1600000000 0.1103339046 0.0189199378 0.1189169213 0.0077709759 0.0236720000 203619882 95654136 760807424 -0.0296808351 0.2759561539 2.3324289322 481 19.2000000000 0.1090660393 0.0191073518 0.1189169213 0.0077836343 0.0199050000 203620890 95654136 760807424 -0.0318903401 0.2766108513 2.3343012333 482 19.2400000000 0.1069615930 0.0192896220 0.1189169213 0.0078111455 0.0279150000 203623498 95654136 760807424 -0.0337278172 0.2790921926 2.3353247643 483 19.2800000000 0.1049222574 0.0194669152 0.1189169213 0.0078340284 0.0206730000 203624506 95654136 760807424 -0.0355754718 0.2804020345 2.3363745213 484 19.3200000000 0.1045986861 0.0196428073 0.1189169213 0.0078356400 0.0202280000 203627114 95654136 760807424 -0.0353797600 0.2800500989 2.3369801044 485 19.3600000000 0.1026545838 0.0198139656 0.1189169213 0.0078667985 0.0203750000 203629922 95654136 760807424 -0.0358605087 0.2826991677 2.3380963802 486 19.4000000000 0.1014226377 0.0199818847 0.1189169213 0.0078879132 0.0204490000 203630730 95654136 760807424 -0.0375058018 0.2843718529 2.3411273956 487 19.4400000000 0.0990271941 0.0201441954 0.1189169213 0.0079320952 0.0205950000 203633538 95654136 760807424 -0.0381757393 0.2874385417 2.3428573608 488 19.4800000000 0.0991780758 0.0203061501 0.1189169213 0.0079399405 0.0203590000 203636146 95654136 760807424 -0.0382708050 0.2859054804 2.3448152542 489 19.5200000000 0.1015641764 0.0204723219 0.1189169213 0.0079447825 0.0198050000 203637154 95654136 760807424 -0.0390295275 0.2839638293 2.3477840424 490 19.5600000000 0.1011657119 0.0206370023 0.1189169213 0.0079424199 0.0199890000 203639762 95654136 760807424 -0.0384593047 0.2844848037 2.3496782780 491 19.6000000000 0.1029316559 0.0208046085 0.1189169213 0.0079391873 0.0198080000 203640770 95654136 760807424 -0.0376984589 0.2820265591 2.3520658016 492 19.6400000000 0.1045635194 0.0209748502 0.1189169213 0.0079333167 0.0234910000 203643378 95654136 760807424 -0.0364005044 0.2796787918 2.3542108536 493 19.6800000000 0.1036696881 0.0211425882 0.1189169213 0.0079340701 0.0201030000 203646186 95654136 760807424 -0.0350495465 0.2816599905 2.3557534218 494 19.7200000000 0.1040759906 0.0213104696 0.1189169213 0.0079480146 0.0200740000 203646994 95654136 760807424 -0.0355713032 0.2816612720 2.3612291813 495 19.7600000000 0.1073690057 0.0214843252 0.1189169213 0.0079453363 0.0237860000 203649802 95654136 760807424 -0.0347757414 0.2773108780 2.3653962612 496 19.8000000000 0.1090221629 0.0216608128 0.1189169213 0.0079440599 0.0201930000 203650610 95654136 760807424 -0.0343635157 0.2757856548 2.3692009449 497 19.8400000000 0.1090974584 0.0218367416 0.1189169213 0.0079407211 0.0198060000 203653418 95654136 760807424 -0.0336699411 0.2761523128 2.3718144894 498 19.8800000000 0.1102029905 0.0220141839 0.1189169213 0.0079398505 0.0197640000 203656026 95654136 760807424 -0.0324645564 0.2751745284 2.3739833832 499 19.9200000000 0.1130153313 0.0221965509 0.1189169213 0.0079352831 0.0198000000 203657034 95654136 760807424 -0.0312980898 0.2713928819 2.3761615753 500 19.9600000000 0.1149674207 0.0223820927 0.1189169213 0.0079313009 0.0198800000 203659642 95654136 760807424 -0.0302831810 0.2697091699 2.3800458908 501 20.0000000000 0.1166662350 0.0225702846 0.1189169213 0.0079251652 0.0199040000 203660650 95654136 760807424 -0.0290302895 0.2681540549 2.3828802109 502 20.0400000000 0.1186042279 0.0227615873 0.1189169213 0.0079216902 0.0198520000 203663258 95654136 760807424 -0.0278897174 0.2665600479 2.3859295845 503 20.0800000000 0.1209848747 0.0229568622 0.1209848747 0.0079147321 0.0197770000 203666066 95654136 760807424 -0.0278934166 0.2648877501 2.3893353939 504 20.1200000000 0.1233585849 0.0231560719 0.1233585849 0.0079097772 0.0197550000 203666874 95654136 760807424 -0.0272733383 0.2622429132 2.3923063278 505 20.1600000000 0.1247402132 0.0233572287 0.1247402132 0.0079066187 0.0210030000 203669682 95654136 760807424 -0.0274112038 0.2612770796 2.3951733112 506 20.2000000000 0.1250080615 0.0235581196 0.1250080615 0.0079089825 0.0200110000 203672290 95654136 760807424 -0.0277631283 0.2600236535 2.3995578289 507 20.2400000000 0.1248797923 0.0237579651 0.1250080615 0.0079090360 0.0201740000 203673298 95654136 760807424 -0.0284469817 0.2597166598 2.4019074440 508 20.2800000000 0.1258565784 0.0239589467 0.1258565784 0.0079104171 0.0201650000 203675906 95654136 760807424 -0.0297690593 0.2583658695 2.4049501419 509 20.3200000000 0.1268704981 0.0241611305 0.1268704981 0.0079054331 0.0198500000 203676914 95654136 760807424 -0.0292586815 0.2567871213 2.4061264992 510 20.3600000000 0.1270063818 0.0243627878 0.1270063818 0.0079017376 0.0198010000 203679522 95654136 760807424 -0.0293351170 0.2564377785 2.4071478844 511 20.4000000000 0.1278331578 0.0245652739 0.1278331578 0.0079080297 0.0238630000 203682330 95654136 760807424 -0.0297249984 0.2558316588 2.4079527855 512 20.4400000000 0.1284852624 0.0247682426 0.1284852624 0.0079031432 0.0200760000 203683138 95654136 760807424 -0.0316267684 0.2554446459 2.4105174541 513 20.4800000000 0.1282965839 0.0249700522 0.1284852624 0.0079010912 0.0264980000 203731002 95654136 760807424 -0.0315686315 0.2560799718 2.4107856750 514 20.5200000000 0.1284244657 0.0251713254 0.1284852624 0.0078965305 0.0205550000 203834210 95654136 760807424 -0.0329396278 0.2564824820 2.4131410122 515 20.5600000000 0.1279797703 0.0253709534 0.1284852624 0.0078948191 0.0198620000 203837018 95654136 760807424 -0.0342401490 0.2567026317 2.4140851498 516 20.6000000000 0.1269624084 0.0255678361 0.1284852624 0.0079013051 0.0201110000 203839626 95654136 760807424 -0.0362732373 0.2575616539 2.4154798985 517 20.6400000000 0.1267491132 0.0257635446 0.1284852624 0.0078980136 0.0199930000 203840634 95654136 760807424 -0.0372217633 0.2576469481 2.4140808582 518 20.6800000000 0.1264744848 0.0259579672 0.1284852624 0.0078989700 0.0199070000 203843242 95654136 760807424 -0.0384706892 0.2577230632 2.4154458046 519 20.7200000000 0.1261137277 0.0261509456 0.1284852624 0.0078964519 0.0198100000 203844250 95654136 760807424 -0.0417790450 0.2579482198 2.4172432423 520 20.7600000000 0.1247635931 0.0263405853 0.1284852624 0.0078973253 0.0236980000 203846858 95654136 760807424 -0.0442930274 0.2576227784 2.4175720215 521 20.8000000000 0.1233877167 0.0265268562 0.1284852624 0.0079020597 0.0210400000 203849666 95654136 760807424 -0.0470533520 0.2585558295 2.4180204868 522 20.8400000000 0.1225108653 0.0267107336 0.1284852624 0.0079121969 0.0231580000 203850474 95654136 760807424 -0.0501174815 0.2585484087 2.4187071323 523 20.8800000000 0.1205998957 0.0268902540 0.1284852624 0.0079165262 0.0238890000 203853282 95654136 760807424 -0.0523867346 0.2601899803 2.4172353745 524 20.9200000000 0.1187348738 0.0270655300 0.1284852624 0.0079247016 0.0201020000 203855890 95654136 760807424 -0.0544818640 0.2610814273 2.4168977737 525 20.9600000000 0.1161772385 0.0272352666 0.1284852624 0.0079319450 0.0198280000 203856898 95654136 760807424 -0.0592783056 0.2610883713 2.4188592434 526 21.0000000000 0.1165160164 0.0274050018 0.1284852624 0.0079307359 0.0200320000 203859506 95654136 760807424 -0.0612446219 0.2621980011 2.4165265560 527 21.0400000000 0.1157836691 0.0275727033 0.1284852624 0.0079314882 0.0198290000 203860514 95654136 760807424 -0.0646383464 0.2628165781 2.4154770374 528 21.0800000000 0.1148712188 0.0277380414 0.1284852624 0.0079303084 0.0197980000 203863122 95654136 760807424 -0.0695885643 0.2615906596 2.4166369438 529 21.1200000000 0.1138667613 0.0279008556 0.1284852624 0.0079359785 0.0197590000 203865930 95654136 760807424 -0.0742279515 0.2620718777 2.4163641930 530 21.1600000000 0.1130347401 0.0280614856 0.1284852624 0.0079360167 0.0197740000 203866738 95654136 760807424 -0.0775656104 0.2636998594 2.4141297340 531 21.2000000000 0.1119202524 0.0282194117 0.1284852624 0.0079354326 0.0196500000 203869546 95654136 760807424 -0.0813548118 0.2644524872 2.4127767086 532 21.2400000000 0.1114230156 0.0283758094 0.1284852624 0.0079312252 0.0198240000 203870354 95654136 760807424 -0.0862039849 0.2645840645 2.4118928909 533 21.2800000000 0.1106166318 0.0285301074 0.1284852624 0.0079299207 0.0196340000 203873162 95654136 760807424 -0.0900510773 0.2654953301 2.4103717804 534 21.3200000000 0.1098531410 0.0286823977 0.1284852624 0.0079293131 0.0247820000 203875770 95654136 760807424 -0.0944610685 0.2642021775 2.4099588394 535 21.3600000000 0.1097380891 0.0288339037 0.1284852624 0.0079259223 0.0200480000 203876778 95654136 760807424 -0.0996043682 0.2632535100 2.4096651077 536 21.4000000000 0.1098746285 0.0289850991 0.1284852624 0.0079305255 0.0197520000 203879386 95654136 760807424 -0.1036640257 0.2630159259 2.4081866741 537 21.4400000000 0.1108242571 0.0291374997 0.1284852624 0.0079290370 0.0197020000 203880394 95654136 760807424 -0.1076243669 0.2628270686 2.4053320885 538 21.4800000000 0.1119219884 0.0292913743 0.1284852624 0.0079277142 0.0196610000 203883002 95654136 760807424 -0.1119455397 0.2625395060 2.4030120373 539 21.5200000000 0.1124457195 0.0294456495 0.1284852624 0.0079227626 0.0196160000 203885810 95654136 760807424 -0.1157417372 0.2613297999 2.4011995792 540 21.5600000000 0.1126706302 0.0295997698 0.1284852624 0.0079201747 0.0195540000 203886618 95654136 760807424 -0.1205536872 0.2613008618 2.3997967243 541 21.6000000000 0.1135623604 0.0297549687 0.1284852624 0.0079203128 0.0197740000 203889426 95654136 760807424 -0.1248651668 0.2597059906 2.3986556530 542 21.6400000000 0.1135218292 0.0299095201 0.1284852624 0.0079483846 0.0196280000 203892034 95654136 760807424 -0.1286186129 0.2580163777 2.3985195160 543 21.6800000000 0.1138639376 0.0300641323 0.1284852624 0.0079730679 0.0196980000 203893042 95654136 760807424 -0.1327829212 0.2559054494 2.3965091705 544 21.7200000000 0.1144816726 0.0302193116 0.1284852624 0.0081047769 0.0196270000 203895650 95654136 760807424 -0.1395404190 0.2534354031 2.3882336617 545 21.7600000000 0.1162842214 0.0303772288 0.1284852624 0.0081108005 0.0196730000 203896658 95654136 760807424 -0.1435280740 0.2541520000 2.3833909035 546 21.8000000000 0.1168890595 0.0305356754 0.1284852624 0.0081111817 0.0196850000 203899266 95654136 760807424 -0.1476216763 0.2531317472 2.3792610168 547 21.8400000000 0.1175435707 0.0306947392 0.1284852624 0.0081275595 0.0194870000 203902074 95654136 760807424 -0.1516459286 0.2508602738 2.3758323193 548 21.8800000000 0.1181040257 0.0308542452 0.1284852624 0.0081224822 0.0195210000 203902882 95654136 760807424 -0.1567663103 0.2556750178 2.3701698780 549 21.9200000000 0.1194197237 0.0310155667 0.1284852624 0.0081151008 0.0194900000 203905690 95654136 760807424 -0.1611157656 0.2577345371 2.3658673763 550 21.9600000000 0.1180246696 0.0311737650 0.1284852624 0.0081382049 0.0194720000 203906498 95654136 760807424 -0.1649638563 0.2530027628 2.3637371063 551 22.0000000000 0.1182872504 0.0313318657 0.1284852624 0.0081522880 0.0194880000 203909306 95654136 760807424 -0.1689901799 0.2518757880 2.3583049774 552 22.0400000000 0.1197430417 0.0314920309 0.1284852624 0.0081470644 0.0195120000 203911914 95654136 760807424 -0.1735326648 0.2576223910 2.3516635895 553 22.0800000000 0.1202421635 0.0316525194 0.1284852624 0.0081419490 0.0202320000 203912922 95654136 760807424 -0.1773503125 0.2589665055 2.3474955559 554 22.1200000000 0.1201990694 0.0318123507 0.1284852624 0.0081437650 0.0196070000 203915530 95654136 760807424 -0.1815105528 0.2578769326 2.3442890644 555 22.1600000000 0.1214794144 0.0319739130 0.1284852624 0.0081455121 0.0195690000 203916538 95654136 760807424 -0.1852061599 0.2575769722 2.3397960663 556 22.2000000000 0.1216959655 0.0321352836 0.1284852624 0.0081473829 0.0236040000 203919146 95654136 760807424 -0.1889106333 0.2562006116 2.3363358974 557 22.2400000000 0.1225990653 0.0322976961 0.1284852624 0.0081435237 0.0196190000 203921954 95654136 760807424 -0.1930453926 0.2581746280 2.3314387798 558 22.2800000000 0.1227941960 0.0324598762 0.1284852624 0.0081472895 0.0193880000 203922762 95654136 760807424 -0.1965329200 0.2578856647 2.3273439407 559 22.3200000000 0.1225476190 0.0326210350 0.1284852624 0.0081541087 0.0194220000 203925570 95654136 760807424 -0.2001077831 0.2578838468 2.3229568005 560 22.3600000000 0.1233301833 0.0327830156 0.1284852624 0.0081689940 0.0194750000 203928178 95654136 760807424 -0.2035005987 0.2568559647 2.3176939487 561 22.4000000000 0.1239665598 0.0329455531 0.1284852624 0.0081720943 0.0195650000 203929186 95654136 760807424 -0.2064515352 0.2572626173 2.3126201630 562 22.4400000000 0.1233239323 0.0331063687 0.1284852624 0.0081855237 0.0194470000 203931794 95654136 760807424 -0.2103136927 0.2543101013 2.3098804951 563 22.4800000000 0.1241373718 0.0332680579 0.1284852624 0.0082048232 0.0233860000 203932802 95654136 760807424 -0.2136708796 0.2521812618 2.3063600063 564 22.5200000000 0.1252348572 0.0334311196 0.1284852624 0.0082100120 0.0196120000 203935410 95654136 760807424 -0.2176375687 0.2522528470 2.3023314476 565 22.5600000000 0.1274374574 0.0335975025 0.1284852624 0.0082121106 0.0232040000 203938218 95654136 760807424 -0.2245097458 0.2545292974 2.2914509773 566 22.6000000000 0.1286066025 0.0337653631 0.1286066025 0.0082169549 0.0196220000 203939026 95654136 760807424 -0.2274614573 0.2515999377 2.2868924141 567 22.6400000000 0.1295387894 0.0339342757 0.1295387894 0.0082175687 0.0234500000 203941834 95654136 760807424 -0.2303262055 0.2513208687 2.2817673683 568 22.6800000000 0.1309495121 0.0341050772 0.1309495121 0.0082209883 0.0196070000 203942642 95654136 760807424 -0.2319888920 0.2540586889 2.2750146389 569 22.7200000000 0.1325554550 0.0342781007 0.1325554550 0.0082210849 0.0202820000 203945450 95654136 760807424 -0.2346142530 0.2539380789 2.2692587376 570 22.7600000000 0.1331503093 0.0344515607 0.1331503093 0.0082287661 0.0194880000 203948058 95654136 760807424 -0.2371792942 0.2511164546 2.2650058270 571 22.8000000000 0.1345972866 0.0346269472 0.1345972866 0.0082341359 0.0193980000 203949066 95654136 760807424 -0.2389083803 0.2469066828 2.2597253323 572 22.8400000000 0.1379382610 0.0348075614 0.1379382610 0.0082288869 0.0194300000 203951674 95654136 760807424 -0.2403156310 0.2496102303 2.2535409927 573 22.8800000000 0.1399290860 0.0349910196 0.1399290860 0.0082302072 0.0193600000 203952682 95654136 760807424 -0.2412679642 0.2485746443 2.2467014790 574 22.9200000000 0.1433518976 0.0351798016 0.1433518976 0.0082256426 0.0194090000 203955290 95654136 760807424 -0.2412367165 0.2452795208 2.2376623154 575 22.9600000000 0.1436757743 0.0353684902 0.1436757743 0.0082214407 0.0193810000 203958098 95654136 760807424 -0.2424889207 0.2459573150 2.2297508717 576 23.0000000000 0.1425475925 0.0355545651 0.1436757743 0.0082425411 0.0193080000 203958906 95654136 760807424 -0.2436615229 0.2448151559 2.2206087112 577 23.0400000000 0.1442375779 0.0357429239 0.1442375779 0.0082377021 0.0193930000 203961714 95654136 760807424 -0.2448976934 0.2439111471 2.2132732868 578 23.0800000000 0.1441363990 0.0359304558 0.1442375779 0.0082472107 0.0238620000 203964322 95654136 760807424 -0.2482057214 0.2467451841 2.2087192535 579 23.1200000000 0.1443705857 0.0361177445 0.1443705857 0.0082564700 0.0231620000 203965330 95654136 760807424 -0.2510800064 0.2476643622 2.2038214207 580 23.1600000000 0.1461918950 0.0363075275 0.1461918950 0.0082507976 0.0194600000 203967938 95654136 760807424 -0.2512064576 0.2474014461 2.1983263493 581 23.2000000000 0.1483354419 0.0365003466 0.1483354419 0.0082605822 0.0230050000 203968946 95654136 760807424 -0.2530760467 0.2472632527 2.1911263466 582 23.2400000000 0.1474621743 0.0366910027 0.1483354419 0.0082866791 0.0195420000 203971554 95654136 760807424 -0.2582730651 0.2478769869 2.1831550598 583 23.2800000000 0.1493383199 0.0368842228 0.1493383199 0.0082825330 0.0229500000 203974362 95654136 760807424 -0.2592062354 0.2479666024 2.1781804562 584 23.3200000000 0.1527799964 0.0370826744 0.1527799964 0.0082804314 0.0194960000 203975170 95654136 760807424 -0.2590084672 0.2475741655 2.1724219322 585 23.3600000000 0.1556497067 0.0372853531 0.1556497067 0.0082956747 0.0230710000 203977978 95654136 760807424 -0.2605571151 0.2460127026 2.1633200645 586 23.4000000000 0.1573287994 0.0374902054 0.1573287994 0.0082948463 0.0194560000 203978786 95654136 760807424 -0.2609745264 0.2445274740 2.1561162472 587 23.4400000000 0.1581947356 0.0376958350 0.1581947356 0.0082976447 0.0193690000 203981594 95654136 760807424 -0.2642642558 0.2445595264 2.1495831013 588 23.4800000000 0.1610005498 0.0379055368 0.1610005498 0.0083074270 0.0199270000 203984202 95654136 760807424 -0.2675020695 0.2435677648 2.1426684856 589 23.5200000000 0.1630687118 0.0381180380 0.1630687118 0.0083175210 0.0194560000 203985210 95654136 760807424 -0.2704258561 0.2417702079 2.1339993477 590 23.5600000000 0.1670984477 0.0383366489 0.1670984477 0.0083208937 0.0230850000 203987818 95654136 760807424 -0.2711355388 0.2382879853 2.1245145798 591 23.6000000000 0.1698066890 0.0385591024 0.1698066890 0.0083215044 0.0195050000 203988826 95654136 760807424 -0.2738996148 0.2368202657 2.1165342331 592 23.6400000000 0.1714718193 0.0387836171 0.1714718193 0.0083200984 0.0193930000 203991434 95654136 760807424 -0.2776355743 0.2363455743 2.1070885658 593 23.6800000000 0.1751545519 0.0390135850 0.1751545519 0.0083182913 0.0193350000 203994242 95654136 760807424 -0.2793176472 0.2352926135 2.0983738899 594 23.7200000000 0.1801825464 0.0392512432 0.1801825464 0.0083212375 0.0192640000 203995050 95654136 760807424 -0.2810974419 0.2306018174 2.0903568268 595 23.7600000000 0.1868919730 0.0394993788 0.1868919730 0.0083294383 0.0192970000 203997858 95654136 760807424 -0.2829593122 0.2235199511 2.0825324059 596 23.8000000000 0.1901319623 0.0397521181 0.1901319623 0.0083364108 0.0193530000 204000466 95654136 760807424 -0.2861859500 0.2200197279 2.0725862980 597 23.8400000000 0.1926326454 0.0400081994 0.1926326454 0.0083317170 0.0192740000 204001474 95654136 760807424 -0.2867341340 0.2200443298 2.0626780987 598 23.8800000000 0.1964971721 0.0402698866 0.1964971721 0.0083313365 0.0192810000 204004082 95654136 760807424 -0.2906921506 0.2183568627 2.0527989864 599 23.9200000000 0.2001944780 0.0405368726 0.2001944780 0.0083330615 0.0239600000 204005090 95654136 760807424 -0.2946542501 0.2170103639 2.0418572426 600 23.9600000000 0.2044736594 0.0408101005 0.2044736594 0.0083340773 0.0239010000 204007698 95654136 760807424 -0.2956959307 0.2144341916 2.0317437649 601 24.0000000000 0.2099780738 0.0410915780 0.2099780738 0.0083294613 0.0196370000 204010506 95654136 760807424 -0.2991859615 0.2077760696 2.0254499912 602 24.0400000000 0.2243071198 0.0413959228 0.2243071198 0.0083722430 0.0192840000 204011314 95654136 760807424 -0.3092816472 0.1853051186 2.0184738636 603 24.0800000000 0.2325051725 0.0417128535 0.2325051725 0.0083750294 0.0193520000 204014122 95654136 760807424 -0.3157421947 0.1716088355 2.0153911114 604 24.1200000000 0.2448394001 0.0420491558 0.2448394001 0.0084387397 0.0193190000 204014930 95654136 760807424 -0.3250076771 0.1515600979 2.0168738365 605 24.1600000000 0.2521213293 0.0423963825 0.2521213293 0.0084589895 0.0192870000 204017738 95654136 760807424 -0.3288768530 0.1422900558 2.0128288269 606 24.2000000000 0.2602258325 0.0427558370 0.2602258325 0.0084688120 0.0194160000 204053870 95654136 760807424 -0.3318991661 0.1315046996 2.0085659027 607 24.2400000000 0.2695587277 0.0431294827 0.2695587277 0.0084787004 0.0193380000 204193310 95654136 760807424 -0.3363807797 0.1181444675 2.0047075748 608 24.2800000000 0.2801640630 0.0435193422 0.2801640630 0.0084902402 0.0193460000 204195918 95654136 760807424 -0.3411163688 0.1039012522 1.9996532202 609 24.3200000000 0.2901425064 0.0439243063 0.2901425064 0.0085022131 0.0233220000 204196926 95654136 760807424 -0.3465639949 0.0913819447 1.9954196215 610 24.3600000000 0.2986227870 0.0443418448 0.2986227870 0.0085058786 0.0195630000 204199534 95654136 760807424 -0.3482831120 0.0811267570 1.9891834259 611 24.4000000000 0.3029332757 0.0447650714 0.3029332757 0.0085007842 0.0231230000 204202342 95654136 760807424 -0.3513126969 0.0760201216 1.9822839499 612 24.4400000000 0.3074152768 0.0451942384 0.3074152768 0.0084945383 0.0195380000 204203150 95654136 760807424 -0.3556251824 0.0715734810 1.9768800735 613 24.4800000000 0.3147124350 0.0456339092 0.3147124350 0.0084888376 0.0193400000 204205958 95654136 760807424 -0.3595166504 0.0641517863 1.9708256721 614 24.5200000000 0.3165156841 0.0460750847 0.3165156841 0.0084851635 0.0193400000 204208566 95654136 760807424 -0.3639049828 0.0630400255 1.9631206989 615 24.5600000000 0.3209795654 0.0465220839 0.3209795654 0.0084787134 0.0194000000 204209574 95654136 760807424 -0.3673122227 0.0584012829 1.9558737278 616 24.6000000000 0.3283821046 0.0469796488 0.3283821046 0.0084761385 0.0232660000 204212182 95654136 760807424 -0.3714312911 0.0516842529 1.9508469105 617 24.6400000000 0.3350629508 0.0474465586 0.3350629508 0.0084722318 0.0204700000 204213190 95654136 760807424 -0.3736600578 0.0469039530 1.9433288574 618 24.6800000000 0.3392012119 0.0479186535 0.3392012119 0.0084723396 0.0194710000 204215798 95654136 760807424 -0.3752470315 0.0448541306 1.9373773336 619 24.7200000000 0.3407239616 0.0483916830 0.3407239616 0.0084682130 0.0233460000 204218606 95654136 760807424 -0.3770475090 0.0452353545 1.9313377142 620 24.7600000000 0.3539554179 0.0488845278 0.3539554179 0.0084715017 0.0194780000 204219414 95654136 760807424 -0.3830969334 0.0348003320 1.9212480783 621 24.8000000000 0.3580735624 0.0493824167 0.3580735624 0.0084659651 0.0194420000 204222222 95654136 760807424 -0.3854961693 0.0317257270 1.9171011448 622 24.8400000000 0.3617754579 0.0498846563 0.3617754579 0.0084614790 0.0194220000 204223030 95654136 760807424 -0.3884674907 0.0285249427 1.9080924988 623 24.8800000000 0.3655016124 0.0503912646 0.3655016124 0.0084582623 0.0193020000 204225838 95654136 760807424 -0.3917105794 0.0257692579 1.9024783373 624 24.9200000000 0.3691131473 0.0509020369 0.3691131473 0.0084533220 0.0193860000 204228446 95654136 760807424 -0.3948030472 0.0227720141 1.8954484463 625 24.9600000000 0.3730248213 0.0514174333 0.3730248213 0.0084473222 0.0193920000 204229454 95654136 760807424 -0.3979201317 0.0189096723 1.8863294125 626 25.0000000000 0.3777063191 0.0519386616 0.3777063191 0.0084417188 0.0193590000 204232062 95654136 760807424 -0.4014721513 0.0152355609 1.8771796227 627 25.0400000000 0.3809618652 0.0524634195 0.3809618652 0.0084430987 0.0193000000 204233070 95654136 760807424 -0.4042957723 0.0129529657 1.8699052334 628 25.0800000000 0.3844098747 0.0529919966 0.3844098747 0.0084411493 0.0193670000 204235678 95654136 760807424 -0.4061094224 0.0108298799 1.8619095087 629 25.1200000000 0.3882063329 0.0535249288 0.3882063329 0.0084410349 0.0193110000 204238486 95654136 760807424 -0.4101516902 0.0101333167 1.8534930944 630 25.1600000000 0.3907521367 0.0540602101 0.3907521367 0.0084392085 0.0223560000 204239294 95654136 760807424 -0.4110768437 0.0088291224 1.8432768583 631 25.2000000000 0.3930757642 0.0545974772 0.3930757642 0.0084355906 0.0194260000 204242102 95654136 760807424 -0.4120468497 0.0083693163 1.8359823227 632 25.2400000000 0.3969898820 0.0551392373 0.3969898820 0.0084310008 0.0194400000 204244710 95654136 760807424 -0.4157385230 0.0066755237 1.8267295361 633 25.2800000000 0.4007076323 0.0556851590 0.4007076323 0.0084326541 0.0194300000 204245718 95654136 760807424 -0.4188596904 0.0044031395 1.8174308538 634 25.3200000000 0.4021378458 0.0562316143 0.4021378458 0.0084321990 0.0193860000 204248326 95654136 760807424 -0.4199883044 0.0051721116 1.8105350733 635 25.3600000000 0.4035492837 0.0567785713 0.4035492837 0.0084272710 0.0226790000 204249334 95654136 760807424 -0.4189975560 0.0059509897 1.8045876026 636 25.4000000000 0.4075824916 0.0573301498 0.4075824916 0.0084321467 0.0194870000 204251942 95654136 760807424 -0.4247362614 0.0044830698 1.7939523458 637 25.4400000000 0.4127355516 0.0578880860 0.4127355516 0.0084291129 0.0193310000 204254750 95654136 760807424 -0.4292319715 0.0040912852 1.7835092545 638 25.4800000000 0.4137563407 0.0584458733 0.4137563407 0.0084372851 0.0193290000 204255558 95654136 760807424 -0.4285009503 0.0057784915 1.7770118713 639 25.5200000000 0.4165152609 0.0590062322 0.4165152609 0.0084327283 0.0193640000 204258366 95654136 760807424 -0.4302272797 0.0062238784 1.7686389685 640 25.5600000000 0.4190136790 0.0595687439 0.4190136790 0.0084313856 0.0230510000 204259174 95654136 760807424 -0.4314952791 0.0070306491 1.7594218254 641 25.6000000000 0.4204101264 0.0601316790 0.4204101264 0.0084270872 0.0194770000 204261982 95654136 760807424 -0.4322331846 0.0065612737 1.7493203878 642 25.6400000000 0.4223219752 0.0606958383 0.4223219752 0.0084215641 0.0193570000 204264590 95654136 760807424 -0.4333273768 0.0057333778 1.7392212152 643 25.6800000000 0.4243581593 0.0612614096 0.4243581593 0.0084177551 0.0193890000 204265598 95654136 760807424 -0.4333729148 0.0060533928 1.7302097082 644 25.7200000000 0.4268399179 0.0618290780 0.4268399179 0.0084124971 0.0193640000 204268206 95654136 760807424 -0.4344226122 0.0060526473 1.7228163481 645 25.7600000000 0.4294873178 0.0623990908 0.4294873178 0.0084076264 0.0231820000 204269214 95654136 760807424 -0.4373355508 0.0064592464 1.7141153812 646 25.8000000000 0.4318605065 0.0629710125 0.4318605065 0.0084041299 0.0195740000 204271822 95654136 760807424 -0.4379311800 0.0055306139 1.7039451599 647 25.8400000000 0.4329687953 0.0635428793 0.4329687953 0.0084006976 0.0193860000 204274630 95654136 760807424 -0.4386946857 0.0072000870 1.6940914392 648 25.8800000000 0.4335250556 0.0641138394 0.4335250556 0.0083981818 0.0193430000 204275438 95654136 760807424 -0.4384301901 0.0079681110 1.6876529455 649 25.9200000000 0.4359007776 0.0646867006 0.4359007776 0.0083967275 0.0232270000 204278246 95654136 760807424 -0.4396986067 0.0084305471 1.6783522367 650 25.9600000000 0.4385819137 0.0652619240 0.4385819137 0.0083939407 0.0233880000 204280854 95654136 760807424 -0.4414848089 0.0072691208 1.6694126129 651 26.0000000000 0.4407524765 0.0658387144 0.4407524765 0.0083919123 0.0196210000 204281862 95654136 760807424 -0.4418465495 0.0057220757 1.6617051363 652 26.0400000000 0.4413716793 0.0664146852 0.4413716793 0.0083927022 0.0194070000 204284470 95654136 760807424 -0.4423641264 0.0070050959 1.6524291039 653 26.0800000000 0.4442380965 0.0669932816 0.4442380965 0.0083894662 0.0232160000 204285478 95654136 760807424 -0.4439920187 0.0060768095 1.6438323259 654 26.1200000000 0.4459862113 0.0675727815 0.4459862113 0.0083926536 0.0196030000 204288086 95654136 760807424 -0.4444553256 0.0077008316 1.6366578341 655 26.1600000000 0.4476559460 0.0681530611 0.4476559460 0.0083964671 0.0194350000 204290894 95654136 760807424 -0.4454528093 0.0089896712 1.6297959089 656 26.2000000000 0.4494483173 0.0687343039 0.4494483173 0.0083954855 0.0194700000 204291702 95654136 760807424 -0.4475667179 0.0097393617 1.6216998100 657 26.2400000000 0.4518698752 0.0693174631 0.4518698752 0.0083921822 0.0194090000 204294510 95654136 760807424 -0.4502714276 0.0095791202 1.6134940386 658 26.2800000000 0.4517050982 0.0698985993 0.4518698752 0.0083971569 0.0195450000 204325778 95654136 760807424 -0.4519731402 0.0115730120 1.6064842939 659 26.3200000000 0.4538381398 0.0704812086 0.4538381398 0.0083924148 0.0194950000 204468686 95654136 760807424 -0.4546049237 0.0113046551 1.5981937647 660 26.3600000000 0.4537829161 0.0710619688 0.4538381398 0.0083919639 0.0194450000 204471294 95654136 760807424 -0.4573116601 0.0120739322 1.5889461040 661 26.4000000000 0.4557010829 0.0716438736 0.4557010829 0.0083929532 0.0195100000 204472302 95654136 760807424 -0.4588378370 0.0131825730 1.5798399448 662 26.4400000000 0.4580199718 0.0722275233 0.4580199718 0.0083915290 0.0233150000 204474910 95654136 760807424 -0.4614778161 0.0137575995 1.5698671341 663 26.4800000000 0.4599600434 0.0728123386 0.4599600434 0.0083887814 0.0197150000 204475918 95654136 760807424 -0.4643273652 0.0152753750 1.5588616133 664 26.5200000000 0.4619087279 0.0733983271 0.4619087279 0.0083887438 0.0194650000 204478526 95654136 760807424 -0.4669584930 0.0153825097 1.5500420332 665 26.5600000000 0.4667021930 0.0739897615 0.4667021930 0.0083923010 0.0194690000 204481334 95654136 760807424 -0.4718209505 0.0159489680 1.5312027931 666 26.6000000000 0.4689427614 0.0745827840 0.4689427614 0.0083887679 0.0203900000 204482142 95654136 760807424 -0.4754065871 0.0166862514 1.5201319456 667 26.6400000000 0.4700774848 0.0751757296 0.4700774848 0.0083871607 0.0194960000 204484950 95654136 760807424 -0.4774553180 0.0190425385 1.5103162527 668 26.6800000000 0.4717552662 0.0757694115 0.4717552662 0.0083832433 0.0194290000 204487558 95654136 760807424 -0.4813174903 0.0198606551 1.4985064268 669 26.7200000000 0.4730244577 0.0763632158 0.4730244577 0.0083834235 0.0228720000 204488566 95654136 760807424 -0.4837339520 0.0205466952 1.4879591465 670 26.7600000000 0.4745576084 0.0769575358 0.4745576084 0.0083784987 0.0196100000 204491174 95654136 760807424 -0.4853956699 0.0232886840 1.4774687290 671 26.8000000000 0.4766359925 0.0775531818 0.4766359925 0.0083745108 0.0195900000 204492182 95654136 760807424 -0.4892777205 0.0228790808 1.4665441513 672 26.8400000000 0.4781050384 0.0781492411 0.4781050384 0.0083754880 0.0198940000 204494790 95654136 760807424 -0.4926672876 0.0238786526 1.4562826157 673 26.8800000000 0.4792882204 0.0787452871 0.4792882204 0.0083805732 0.0198490000 204497598 95654136 760807424 -0.4953112304 0.0251796748 1.4461075068 674 26.9200000000 0.4800066054 0.0793406303 0.4800066054 0.0083836320 0.0199900000 204528926 95654136 760807424 -0.4953899384 0.0272907801 1.4368530512 675 26.9600000000 0.4814967513 0.0799364172 0.4814967513 0.0083925050 0.0199530000 204672350 95654136 760807424 -0.4962626994 0.0287839416 1.4285210371 676 27.0000000000 0.4830943942 0.0805328047 0.4830943942 0.0083978802 0.0198710000 204673158 95654136 760807424 -0.4997003376 0.0306290109 1.4195035696 677 27.0400000000 0.4839925170 0.0811287570 0.4839925170 0.0084106481 0.0198570000 204675966 95654136 760807424 -0.5032489896 0.0330510736 1.4103357792 678 27.0800000000 0.4855282307 0.0817252164 0.4855282307 0.0084123524 0.0198460000 204678574 95654136 760807424 -0.5062256455 0.0339749902 1.4030513763 679 27.1200000000 0.4862549305 0.0823209892 0.4862549305 0.0084205170 0.0198820000 204679582 95654136 760807424 -0.5088655949 0.0360128023 1.3947662115 680 27.1600000000 0.4870568812 0.0829161890 0.4870568812 0.0084264240 0.0199240000 204682190 95654136 760807424 -0.5113875866 0.0379667692 1.3875989914 681 27.2000000000 0.4886237681 0.0835119417 0.4886237681 0.0084277885 0.0199440000 204713942 95654136 760807424 -0.5135690570 0.0395667218 1.3799350262 682 27.2400000000 0.4901282489 0.0841081533 0.4901282489 0.0084276999 0.0199090000 204857394 95654136 760807424 -0.5163416266 0.0410903320 1.3703742027 683 27.2800000000 0.4914744496 0.0847045901 0.4914744496 0.0084231083 0.0196020000 204860202 95654136 760807424 -0.5206547976 0.0419909507 1.3601297140 684 27.3200000000 0.4920136333 0.0853000711 0.4920136333 0.0084324177 0.0195130000 204861010 95654136 760807424 -0.5215721726 0.0431070216 1.3533388376 685 27.3600000000 0.4933414161 0.0858957519 0.4933414161 0.0084318255 0.0196210000 204863818 95654136 760807424 -0.5211930871 0.0437394083 1.3454740047 686 27.4000000000 0.4948480427 0.0864918923 0.4948480427 0.0084374757 0.0232810000 204866426 95654136 760807424 -0.5256311297 0.0447047092 1.3340427876 687 27.4400000000 0.4966270328 0.0870888867 0.4966270328 0.0084344834 0.0197370000 204867434 95654136 760807424 -0.5283955932 0.0437442288 1.3249447346 688 27.4800000000 0.4981994331 0.0876864311 0.4981994331 0.0084311352 0.0195080000 204870042 95654136 760807424 -0.5299470425 0.0444883741 1.3174892664 689 27.5200000000 0.5004130602 0.0882854537 0.5004130602 0.0084263868 0.0196650000 204900694 95654136 760807424 -0.5339620113 0.0447093733 1.3068526983 690 27.5600000000 0.5026704669 0.0888860117 0.5026704669 0.0084322654 0.0194860000 205044406 95654136 760807424 -0.5348985791 0.0455489196 1.3007935286 691 27.6000000000 0.5048345923 0.0894879634 0.5048345923 0.0084273365 0.0195310000 205047214 95654136 760807424 -0.5359507203 0.0452608392 1.2929077148 692 27.6400000000 0.5082928538 0.0900931727 0.5082928538 0.0084233732 0.0182180000 205048022 95654136 760807424 -0.5375863314 0.0436975583 1.2852954865 693 27.6800000000 0.5120828152 0.0907021044 0.5120828152 0.0084243378 0.0236710000 205050630 95654136 760807424 -0.5389484763 0.0429147221 1.2782974243 694 27.7200000000 0.5158849955 0.0913147599 0.5158849955 0.0084274316 0.0197330000 205051638 95654136 760807424 -0.5400475860 0.0418524481 1.2716534138 695 27.7600000000 0.5186992884 0.0919297016 0.5186992884 0.0084299162 0.0234230000 205054246 95654136 760807424 -0.5412958860 0.0395527408 1.2627192736 696 27.8000000000 0.5225703716 0.0925484382 0.5225703716 0.0084314216 0.0197800000 205057054 95654136 760807424 -0.5428606868 0.0392651968 1.2556453943 697 27.8400000000 0.5306161642 0.0931769429 0.5306161642 0.0084647531 0.0195510000 205057862 95654136 760807424 -0.5454260707 0.0356373116 1.2410299778 698 27.8800000000 0.5327445269 0.0938066958 0.5327445269 0.0084591727 0.0196040000 205060670 95654136 760807424 -0.5443135500 0.0331681371 1.2325830460 699 27.9200000000 0.5364789367 0.0944399895 0.5364789367 0.0084591216 0.0205920000 205063278 95654136 760807424 -0.5462476015 0.0342480093 1.2223901749 700 27.9600000000 0.5404402614 0.0950771327 0.5404402614 0.0084592428 0.0183130000 205064086 95654136 760807424 -0.5455132723 0.0350355059 1.2116065025 701 28.0000000000 0.5423104763 0.0957151261 0.5423104763 0.0084607912 0.0184090000 205096454 95654136 760807424 -0.5422633886 0.0353891551 1.2012207508 702 28.0400000000 0.5432773829 0.0963526791 0.5432773829 0.0084548119 0.0220830000 205238754 95654136 760807424 -0.5415089726 0.0376758948 1.1892703772 703 28.0800000000 0.5439661145 0.0969893981 0.5439661145 0.0084498297 0.0293890000 205241362 95654136 760807424 -0.5436195135 0.0371515118 1.1746405363 704 28.1200000000 0.5445640683 0.0976251576 0.5445640683 0.0084523104 0.0194540000 205243970 95654136 760807424 -0.5419200063 0.0349544771 1.1621365547 705 28.1600000000 0.5447899103 0.0982594338 0.5447899103 0.0084474881 0.0183920000 205244978 95654136 760807424 -0.5413427353 0.0322850943 1.1482695341 706 28.2000000000 0.5448654890 0.0988920203 0.5448654890 0.0084438024 0.0182820000 205247586 95654136 760807424 -0.5411325097 0.0299604740 1.1348180771 707 28.2400000000 0.5472782254 0.0995262299 0.5472782254 0.0084420389 0.0182790000 205250194 95654136 760807424 -0.5396993756 0.0310598370 1.1224607229 708 28.2800000000 0.5494544506 0.1001617218 0.5494544506 0.0084394023 0.0182980000 205251002 95654136 760807424 -0.5411334038 0.0334773287 1.1086677313 709 28.3200000000 0.5510300994 0.1007976433 0.5510300994 0.0084410202 0.0185010000 205283226 95654136 760807424 -0.5398844481 0.0315608010 1.0959031582 710 28.3600000000 0.5517082810 0.1014327287 0.5517082810 0.0084368657 0.0183500000 205427586 95654136 760807424 -0.5363011956 0.0319282189 1.0866367817 711 28.4000000000 0.5567006469 0.1020730493 0.5567006469 0.0084329870 0.0183400000 205428394 95654136 760807424 -0.5363526940 0.0316573456 1.0800919533 712 28.4400000000 0.5623372197 0.1027194877 0.5623372197 0.0084391777 0.0197470000 205431202 95654136 760807424 -0.5359476805 0.0313836411 1.0764956474 713 28.4800000000 0.5684721470 0.1033727173 0.5684721470 0.0084486204 0.0196550000 205432010 95654136 760807424 -0.5338396430 0.0319784917 1.0754953623 714 28.5200000000 0.5738921762 0.1040317081 0.5738921762 0.0084437634 0.0204430000 205434818 95654136 760807424 -0.5343651175 0.0317874625 1.0716542006 715 28.5600000000 0.5814704895 0.1046994547 0.5814704895 0.0084425617 0.0198050000 205437426 95654136 760807424 -0.5362638235 0.0313933007 1.0669577122 716 28.6000000000 0.5886114836 0.1053753094 0.5886114836 0.0084562615 0.0197310000 205438434 95654136 760807424 -0.5361331105 0.0303694904 1.0637443066 717 28.6400000000 0.5949929357 0.1060581792 0.5949929357 0.0084755056 0.0197160000 205441042 95654136 760807424 -0.5337942243 0.0297859721 1.0639426708 718 28.6800000000 0.5998461843 0.1067459062 0.5998461843 0.0084710642 0.0196110000 205442050 95654136 760807424 -0.5335870981 0.0290468875 1.0610218048 719 28.7200000000 0.6054816842 0.1074395582 0.6054816842 0.0084678375 0.0196140000 205444658 95654136 760807424 -0.5355703235 0.0292167459 1.0553990602 720 28.7600000000 0.6112809181 0.1081393379 0.6112809181 0.0084661361 0.0197220000 205477278 95654136 760807424 -0.5362304449 0.0285202265 1.0508960485 721 28.8000000000 0.6182191968 0.1088467996 0.6182191968 0.0084712475 0.0196730000 205620194 95654136 760807424 -0.5358286500 0.0274317432 1.0494776964 722 28.8400000000 0.6210917830 0.1095562801 0.6210917830 0.0084673234 0.0196420000 205623002 95654136 760807424 -0.5406342149 0.0289761815 1.0397486687 723 28.8800000000 0.6231639981 0.1102666643 0.6231639981 0.0084664527 0.0197490000 205625610 95654136 760807424 -0.5452057123 0.0298528094 1.0301339626 724 28.9200000000 0.6250581145 0.1109777022 0.6250581145 0.0084663517 0.0292190000 205626618 95654136 760807424 -0.5474967360 0.0308465865 1.0228824615 725 28.9600000000 0.6290075183 0.1116922261 0.6290075183 0.0084637987 0.0203780000 205629226 95654136 760807424 -0.5502985120 0.0315756612 1.0148954391 726 29.0000000000 0.6368365884 0.1124155654 0.6368365884 0.0084892099 0.0229200000 205630234 95654136 760807424 -0.5511952043 0.0311456770 1.0106142759 727 29.0400000000 0.6463729143 0.1131500322 0.6463729143 0.0085038362 0.0199560000 205632842 95654136 760807424 -0.5572930574 0.0305074211 0.9993618131 728 29.0800000000 0.6486275792 0.1138855783 0.6486275792 0.0085034849 0.0196320000 205635650 95654136 760807424 -0.5659326911 0.0320617743 0.9863403440 729 29.1200000000 0.6547961235 0.1146275680 0.6547961235 0.0085330075 0.0196900000 205636458 95654136 760807424 -0.5652868748 0.0326191075 0.9845294952 730 29.1600000000 0.6587232351 0.1153729046 0.6587232351 0.0085314936 0.0195770000 205639266 95654136 760807424 -0.5668493509 0.0331481397 0.9796844721 731 29.2000000000 0.6643889546 0.1161239525 0.6643889546 0.0085409970 0.0197810000 205668946 95654136 760807424 -0.5727269650 0.0331166424 0.9701424241 732 29.2400000000 0.6683765650 0.1168783960 0.6683765650 0.0085535682 0.0196400000 205814218 95654136 760807424 -0.5766481161 0.0336318798 0.9628107548 733 29.2800000000 0.6748107672 0.1176395588 0.6748107672 0.0085826832 0.0196320000 205816826 95654136 760807424 -0.5783265829 0.0327047370 0.9589328766 734 29.3200000000 0.6788249612 0.1184041166 0.6788249612 0.0085997254 0.0229760000 205817834 95654136 760807424 -0.5845732689 0.0334148630 0.9494406581 735 29.3600000000 0.6841536760 0.1191738439 0.6841536760 0.0086303923 0.0196790000 205820442 95654136 760807424 -0.5866538882 0.0333491750 0.9446708560 736 29.4000000000 0.6900641918 0.1199495101 0.6900641918 0.0086494620 0.0198370000 205821450 95654136 760807424 -0.5870599747 0.0331524871 0.9421670437 737 29.4400000000 0.6984465122 0.1207344450 0.6984465122 0.0086841495 0.0196650000 205824058 95654136 760807424 -0.5892289877 0.0316670164 0.9370318651 738 29.4800000000 0.7043924928 0.1215253096 0.7043924928 0.0087224160 0.0233470000 205826866 95654136 760807424 -0.5913162231 0.0315670148 0.9317475557 739 29.5200000000 0.7077614665 0.1223185926 0.7077614665 0.0087452674 0.0197490000 205827674 95654136 760807424 -0.5909991264 0.0316518210 0.9301220179 740 29.5600000000 0.7136533856 0.1231176937 0.7136533856 0.0087546091 0.0195140000 205830482 95654136 760807424 -0.5912755132 0.0305660181 0.9270163178 741 29.6000000000 0.7216048837 0.1239253687 0.7216048837 0.0087690179 0.0195380000 205833090 95654136 760807424 -0.5913729668 0.0294272341 0.9245693088 742 29.6400000000 0.7292149663 0.1247411229 0.7292149663 0.0087816249 0.0195700000 205834098 95654136 760807424 -0.5912979245 0.0286801476 0.9218630791 743 29.6800000000 0.7355711460 0.1255632359 0.7355711460 0.0087926061 0.0234060000 205836706 95654136 760807424 -0.5919408202 0.0282986425 0.9188590050 744 29.7200000000 0.7394421697 0.1263883420 0.7394421697 0.0087944152 0.0289800000 205865290 95654136 760807424 -0.5957359076 0.0293671601 0.9126690626 745 29.7600000000 0.7425851226 0.1272154518 0.7425851226 0.0088109760 0.0210270000 206010782 95654136 760807424 -0.5975162387 0.0291879922 0.9099212289 746 29.8000000000 0.7461575270 0.1280451329 0.7461575270 0.0088248414 0.0183760000 206013390 95654136 760807424 -0.6004865766 0.0297352038 0.9046331644 747 29.8400000000 0.7488518357 0.1288761994 0.7488518357 0.0088523992 0.0195330000 206014398 95654136 760807424 -0.5947083831 0.0296098571 0.9023703933 748 29.8800000000 0.7509536147 0.1297078537 0.7509536147 0.0088510800 0.0182610000 206017006 95654136 760807424 -0.5918154716 0.0294352323 0.9019739032 749 29.9200000000 0.7551518679 0.1305428924 0.7551518679 0.0088492419 0.0183710000 206019614 95654136 760807424 -0.5937793255 0.0298657138 0.8975771666 750 29.9600000000 0.7620760202 0.1313849366 0.7620760202 0.0088529055 0.0182370000 206020622 95654136 760807424 -0.5943511128 0.0301569737 0.8937740922 751 30.0000000000 0.7648013830 0.1322283673 0.7648013830 0.0088565851 0.0181090000 206023230 95654136 760807424 -0.5943216085 0.0301349293 0.8914374709 752 30.0400000000 0.7665863037 0.1330719284 0.7665863037 0.0088541920 0.0182680000 206024038 95654136 760807424 -0.5954666138 0.0297178067 0.8889316320 753 30.0800000000 0.7726686597 0.1339213264 0.7726686597 0.0088588898 0.0183500000 206026646 95654136 760807424 -0.5970177054 0.0300798677 0.8845960498 754 30.1200000000 0.7748866677 0.1347714131 0.7748866677 0.0088690837 0.0186660000 206057330 95654136 760807424 -0.5948910117 0.0296920482 0.8820899129 755 30.1600000000 0.7750896215 0.1356195167 0.7750896215 0.0088676990 0.0186080000 206201346 95654136 760807424 -0.5908649564 0.0292418543 0.8808012009 756 30.2000000000 0.7793588042 0.1364710237 0.7793588042 0.0088652686 0.0201050000 206203954 95654136 760807424 -0.5911462903 0.0291942023 0.8773109317 757 30.2400000000 0.7829617262 0.1373250405 0.7829617262 0.0088640098 0.0185710000 206206762 95654136 760807424 -0.5915214419 0.0288476907 0.8738926649 758 30.2800000000 0.7864957452 0.1381814662 0.7864957452 0.0088617827 0.0198490000 206207570 95654136 760807424 -0.5925878882 0.0290194135 0.8706437945 759 30.3200000000 0.7936235666 0.1390450263 0.7936235666 0.0088696241 0.0185410000 206210178 95654136 760807424 -0.5909657478 0.0289032143 0.8670672178 760 30.3600000000 0.7935085893 0.1399061625 0.7936235666 0.0088760789 0.0185500000 206211186 95654136 760807424 -0.5875120759 0.0275738128 0.8618407845 761 30.4000000000 0.7952572107 0.1407673334 0.7952572107 0.0088738784 0.0199700000 206213794 95654136 760807424 -0.5864946246 0.0270520225 0.8590032458 762 30.4400000000 0.7997598052 0.1416321529 0.7997598052 0.0088740841 0.0207090000 206216602 95654136 760807424 -0.5873791575 0.0268601961 0.8552679420 763 30.4800000000 0.8009248972 0.1424962326 0.8009248972 0.0088753643 0.0198020000 206244726 95654136 760807424 -0.5871509910 0.0254366156 0.8487874269 764 30.5200000000 0.8048311472 0.1433631631 0.8048311472 0.0088769080 0.0195910000 206391034 95654136 760807424 -0.5846449137 0.0253626518 0.8455678821 765 30.5600000000 0.8080884218 0.1442320850 0.8080884218 0.0088775266 0.0195920000 206393642 95654136 760807424 -0.5826361179 0.0246040002 0.8400382996 766 30.6000000000 0.8102740049 0.1451015914 0.8102740049 0.0088785923 0.0300750000 206394650 95654136 760807424 -0.5770189166 0.0251637809 0.8393461704 767 30.6400000000 0.8144592047 0.1459742871 0.8144592047 0.0088747985 0.0204610000 206397258 95654136 760807424 -0.5750735402 0.0257173926 0.8331397176 768 30.6800000000 0.8180958629 0.1468494454 0.8180958629 0.0088718149 0.0195720000 206398266 95654136 760807424 -0.5730788708 0.0260736458 0.8274238706 769 30.7200000000 0.8191807270 0.1477237384 0.8191807270 0.0088728246 0.0197220000 206427970 95654136 760807424 -0.5663706064 0.0264009964 0.8270419240 770 30.7600000000 0.8222393394 0.1485997327 0.8222393394 0.0088705864 0.0196650000 206574474 95654136 760807424 -0.5642281771 0.0269546844 0.8223598599 771 30.8000000000 0.8268973231 0.1494794961 0.8268973231 0.0088698866 0.0233030000 206575282 95654136 760807424 -0.5617949367 0.0277054682 0.8168222308 772 30.8400000000 0.8260451555 0.1503558765 0.8268973231 0.0088666648 0.0197570000 206578090 95654136 760807424 -0.5559028387 0.0255307611 0.8108034134 773 30.8800000000 0.8286577463 0.1512333692 0.8286577463 0.0088710922 0.0196960000 206605182 95654136 760807424 -0.5490682721 0.0254268795 0.8068138957 774 30.9200000000 0.8328179717 0.1521139694 0.8328179717 0.0088813567 0.0196810000 206751818 95654136 760807424 -0.5484685302 0.0264811721 0.8010203242 775 30.9600000000 0.8362632394 0.1529967427 0.8362632394 0.0088822828 0.0196130000 206754426 95654136 760807424 -0.5488054156 0.0272222441 0.7960430980 776 31.0000000000 0.8389249444 0.1538806708 0.8389249444 0.0088823377 0.0272530000 206755434 95654136 760807424 -0.5484483838 0.0281747133 0.7916284800 777 31.0400000000 0.8410244584 0.1547650257 0.8410244584 0.0088794545 0.0200970000 206758042 95654136 760807424 -0.5433499217 0.0284261368 0.7871240377 778 31.0800000000 0.8440195918 0.1556509570 0.8440195918 0.0088806434 0.0198420000 206786550 95654136 760807424 -0.5423377156 0.0293503776 0.7820924520 779 31.1200000000 0.8488903046 0.1565408663 0.8488903046 0.0088826888 0.0183200000 206933150 95654136 760807424 -0.5395672321 0.0306095015 0.7780642509 780 31.1600000000 0.8545526862 0.1574357533 0.8545526862 0.0088834050 0.0196320000 206935758 95654136 760807424 -0.5366657376 0.0314796492 0.7737960815 781 31.2000000000 0.8565109372 0.1583308560 0.8565109372 0.0088803042 0.0234860000 206936766 95654136 760807424 -0.5310966969 0.0325827114 0.7681629062 782 31.2400000000 0.8577193618 0.1592252147 0.8577193618 0.0088760476 0.0198880000 206939374 95654136 760807424 -0.5263913870 0.0319277905 0.7628956437 783 31.2800000000 0.8583649397 0.1601181134 0.8583649397 0.0088720639 0.0197370000 206942182 95654136 760807424 -0.5217682719 0.0329282582 0.7595112920 784 31.3200000000 0.8605996370 0.1610115848 0.8605996370 0.0088696772 0.0197170000 206969694 95654136 760807424 -0.5198501348 0.0346006341 0.7525703311 785 31.3600000000 0.8632133007 0.1619061092 0.8632133007 0.0088669555 0.0197430000 207116690 95654136 760807424 -0.5194804072 0.0346635878 0.7490608096 786 31.4000000000 0.8663146496 0.1628023033 0.8663146496 0.0088654474 0.0312030000 207117498 95654136 760807424 -0.5135815740 0.0346436910 0.7481072545 787 31.4400000000 0.8687006235 0.1636992516 0.8687006235 0.0088623910 0.0237410000 207120306 95654136 760807424 -0.5090539455 0.0334122293 0.7464223504 788 31.4800000000 0.8695664406 0.1645950222 0.8695664406 0.0088591852 0.0199560000 207122914 95654136 760807424 -0.5063677430 0.0342234783 0.7422494292 789 31.5200000000 0.8701498508 0.1654892615 0.8701498508 0.0088558555 0.0224100000 207150470 95654136 760807424 -0.5048635602 0.0355469435 0.7367179394 790 31.5600000000 0.8704957366 0.1663816747 0.8704957366 0.0088523887 0.0198110000 207297430 95654136 760807424 -0.5028980374 0.0359846540 0.7338493466 791 31.6000000000 0.8712870479 0.1672728320 0.8712870479 0.0088501185 0.0202080000 207298438 95654136 760807424 -0.5034990311 0.0344424024 0.7271628976 792 31.6400000000 0.8710926771 0.1681614934 0.8712870479 0.0088459443 0.0198770000 207301046 95654136 760807424 -0.5041201711 0.0331222825 0.7220333815 793 31.6800000000 0.8696440458 0.1690460868 0.8712870479 0.0088408737 0.0197280000 207303854 95654136 760807424 -0.5023602843 0.0324916430 0.7201927304 794 31.7200000000 0.8709173203 0.1699300556 0.8712870479 0.0088376777 0.0197050000 207304662 95654136 760807424 -0.5034704804 0.0308382250 0.7129684091 795 31.7600000000 0.8724971414 0.1708137878 0.8724971414 0.0088341327 0.0197560000 207307470 95654136 760807424 -0.5040477514 0.0301130991 0.7090530992 796 31.8000000000 0.8721221685 0.1716948285 0.8724971414 0.0088290164 0.0196460000 207310078 95654136 760807424 -0.5014351010 0.0298994128 0.7064055204 797 31.8400000000 0.8734191656 0.1725752856 0.8734191656 0.0088240733 0.0196810000 207311086 95654136 760807424 -0.4992320836 0.0291748159 0.7032894492 798 31.8800000000 0.8745192885 0.1734549147 0.8745192885 0.0088196393 0.0197550000 207339910 95654136 760807424 -0.4996939003 0.0286953133 0.7012451291 799 31.9200000000 0.8782561421 0.1743370188 0.8782561421 0.0088202674 0.0197460000 207485562 95654136 760807424 -0.5002340674 0.0277080406 0.6948593259 800 31.9600000000 0.8791209459 0.1752179987 0.8791209459 0.0088193348 0.0196550000 207488170 95654136 760807424 -0.5014448166 0.0262150783 0.6905115247 801 32.0000000000 0.8753799796 0.1760921086 0.8791209459 0.0088205338 0.0199110000 207490978 95654136 760807424 -0.4977037013 0.0259248819 0.6916633248 802 32.0400000000 0.8751778603 0.1769637866 0.8791209459 0.0088283651 0.0197100000 207491786 95654136 760807424 -0.4987269342 0.0246680155 0.6870033741 803 32.0800000000 0.8760284781 0.1778343528 0.8791209459 0.0088309723 0.0235390000 207494594 95654136 760807424 -0.4996982515 0.0220388025 0.6796916723 804 32.1199999990 0.8753790855 0.1787019458 0.8791209459 0.0088282782 0.0222110000 207495402 95654136 760807424 -0.4999865294 0.0206843391 0.6763407588 805 32.1600000000 0.8744937181 0.1795662834 0.8791209459 0.0088292329 0.0198040000 207498210 95654136 760807424 -0.5011652708 0.0188857205 0.6712520719 806 32.2000000000 0.8779740930 0.1804327943 0.8791209459 0.0088536022 0.0197490000 207500818 95654136 760807424 -0.4948126674 0.0148374038 0.6561114788 807 32.2400000000 0.8799665570 0.1812996267 0.8799665570 0.0088547991 0.0200450000 207501826 95654136 760807424 -0.4936347604 0.0132622290 0.6517692804 808 32.2800000000 0.8824610114 0.1821674007 0.8824610114 0.0088603046 0.0198950000 207529950 95654136 760807424 -0.4941861331 0.0115216263 0.6439402103 809 32.3200000000 0.8838524818 0.1830347494 0.8838524818 0.0088590242 0.0197190000 207675926 95654136 760807424 -0.4977526069 0.0097071212 0.6371190548 810 32.3600000000 0.8833703399 0.1838993612 0.8838524818 0.0088564312 0.0235600000 207678534 95654136 760807424 -0.4982435107 0.0081602642 0.6335260272 811 32.4000000000 0.8840817213 0.1847627180 0.8840817213 0.0088562310 0.0198340000 207681342 95654136 760807424 -0.5009245872 0.0037380708 0.6276304722 812 32.4399999990 0.8820397854 0.1856214336 0.8840817213 0.0088542689 0.0197450000 207682150 95654136 760807424 -0.4987546206 -0.0008651563 0.6258279681 813 32.4800000000 0.8863490820 0.1864833372 0.8863490820 0.0088810381 0.0197640000 207684958 95654136 760807424 -0.4978625476 0.0020466174 0.6166114807 814 32.5200000000 0.8925544024 0.1873507464 0.8925544024 0.0088925215 0.0232690000 207687566 95654136 760807424 -0.5011082888 0.0059692869 0.6038457751 815 32.5600000000 0.8915274739 0.1882147669 0.8925544024 0.0089022463 0.0198630000 207688574 95654136 760807424 -0.5027139187 0.0001138877 0.6009953618 816 32.6000000000 0.8927786946 0.1890782031 0.8927786946 0.0089031801 0.0198670000 207716498 95654136 760807424 -0.5013572574 -0.0013580609 0.5963785052 817 32.6400000000 0.8931992054 0.1899400403 0.8931992054 0.0089002826 0.0197500000 207862734 95654136 760807424 -0.5057222843 -0.0024283391 0.5892339945 818 32.6800000000 0.8943524957 0.1908011803 0.8943524957 0.0088987002 0.0196740000 207865342 95654136 760807424 -0.5092917681 -0.0034479219 0.5815328956 819 32.7200000000 0.8932312131 0.1916588482 0.8943524957 0.0088949020 0.0198290000 207868150 95654136 760807424 -0.5118885636 -0.0071296310 0.5762039423 820 32.7599999990 0.8943614364 0.1925158026 0.8943614364 0.0088928193 0.0197200000 207868958 95654136 760807424 -0.5112995505 -0.0081913741 0.5708187222 821 32.7999999990 0.8964959979 0.1933732693 0.8964959979 0.0088935654 0.0235850000 207871766 95654136 760807424 -0.5133308768 -0.0079516992 0.5634235740 822 32.8400000000 0.8987477422 0.1942313891 0.8987477422 0.0088904839 0.0198620000 207872574 95654136 760807424 -0.5141723156 -0.0097924499 0.5579019189 823 32.8800000000 0.9005647302 0.1950896313 0.9005647302 0.0088917444 0.0197660000 207875382 95654136 760807424 -0.5143582821 -0.0076571186 0.5526964664 824 32.9200000000 0.9037640095 0.1959496730 0.9037640095 0.0088916564 0.0196900000 207877990 95654136 760807424 -0.5166494250 -0.0061659990 0.5454013944 825 32.9600000000 0.9028556347 0.1968065288 0.9037640095 0.0088883462 0.0198780000 207878998 95654136 760807424 -0.5166472793 -0.0084602106 0.5408557653 826 33.0000000000 0.9047670960 0.1976636239 0.9047670960 0.0088868550 0.0198550000 207906370 95654136 760807424 -0.5136318207 -0.0078541357 0.5368096232 827 33.0400000000 0.9054264426 0.1985194435 0.9054264426 0.0088848895 0.0236430000 208052930 95654136 760807424 -0.5180155039 -0.0084645255 0.5274891257 828 33.0800000000 0.9044290185 0.1993719913 0.9054264426 0.0088818688 0.0198840000 208055538 95654136 760807424 -0.5169767737 -0.0143728210 0.5252277851 829 33.1199999990 0.9062627554 0.2002246942 0.9062627554 0.0088894989 0.0197310000 208058346 95654136 760807424 -0.5152080655 -0.0144068254 0.5208483934 830 33.1600000000 0.9091076851 0.2010787701 0.9091076851 0.0089082819 0.0236990000 208059154 95654136 760807424 -0.5221583247 -0.0112993326 0.5102992058 831 33.2000000000 0.9094668031 0.2019312226 0.9094668031 0.0089047811 0.0199640000 208061962 95654136 760807424 -0.5231326818 -0.0131569579 0.5053302646 832 33.2400000000 0.9086217880 0.2027806103 0.9094668031 0.0089020869 0.0197580000 208064570 95654136 760807424 -0.5193979144 -0.0145775145 0.5031327009 833 33.2800000000 0.9106855989 0.2036304363 0.9106855989 0.0089074321 0.0197820000 208065578 95654136 760807424 -0.5173986554 -0.0154548213 0.4972970784 834 33.3200000000 0.9118749499 0.2044796503 0.9118749499 0.0089140110 0.0197390000 208068186 95654136 760807424 -0.5199643373 -0.0160075836 0.4905073643 835 33.3600000000 0.9131690264 0.2053283801 0.9131690264 0.0089181179 0.0274720000 208094114 95654136 760807424 -0.5213305354 -0.0159017444 0.4831781387 836 33.4000000000 0.9141226411 0.2061762201 0.9141226411 0.0089206279 0.0204020000 208242566 95654136 760807424 -0.5217204690 -0.0148010356 0.4764160216 837 33.4399999990 0.9140800238 0.2070219833 0.9141226411 0.0089218586 0.0200250000 208245374 95654136 760807424 -0.5214576721 -0.0135866487 0.4699172080 838 33.4800000000 0.9129551649 0.2078643857 0.9141226411 0.0089212110 0.0205350000 208246182 95654136 760807424 -0.5209929943 -0.0134947337 0.4628848433 839 33.5200000000 0.9144348502 0.2087065436 0.9144348502 0.0089274844 0.0198960000 208248990 95654136 760807424 -0.5174946189 -0.0105238669 0.4532389045 840 33.5600000000 0.9134184718 0.2095454864 0.9144348502 0.0089244628 0.0198420000 208249798 95654136 760807424 -0.5104587674 -0.0124339946 0.4476275742 841 33.6000000000 0.9131127000 0.2103820704 0.9144348502 0.0089256353 0.0197100000 208252606 95654136 760807424 -0.5073531866 -0.0135246823 0.4410170615 842 33.6400000000 0.9131620526 0.2112167260 0.9144348502 0.0089385270 0.0198000000 208255214 95654136 760807424 -0.5065563321 -0.0127158659 0.4324256778 843 33.6800000000 0.9140270948 0.2120504275 0.9144348502 0.0089771408 0.0198820000 208281094 95654136 760807424 -0.4985139668 -0.0127660669 0.4172484875 844 33.7200000000 0.9156172872 0.2128840375 0.9156172872 0.0089820696 0.0198110000 208429806 95654136 760807424 -0.4955064654 -0.0120651694 0.4088357389 845 33.7599999990 0.9177070856 0.2137181476 0.9177070856 0.0089917079 0.0241100000 208430814 95654136 760807424 -0.4949920774 -0.0078255078 0.3999056518 846 33.7999999990 0.9186336994 0.2145513812 0.9186336994 0.0089968050 0.0186180000 208433422 95654136 760807424 -0.4953621924 0.0006173104 0.3903329372 847 33.8400000000 0.9205091000 0.2153848613 0.9205091000 0.0089933789 0.0198250000 208436030 95654136 760807424 -0.4896814525 0.0045061298 0.3812410533 848 33.8800000000 0.9206334352 0.2162165224 0.9206334352 0.0089901914 0.0198280000 208437038 95654136 760807424 -0.4808329344 0.0051839566 0.3736388981 849 33.9200000000 0.9208243489 0.2170464492 0.9208243489 0.0089854665 0.0231920000 208439646 95654136 760807424 -0.4791516960 0.0030916217 0.3657243848 850 33.9600000000 0.9212651849 0.2178749418 0.9212651849 0.0089813515 0.0184820000 208442254 95654136 760807424 -0.4711496234 0.0038485560 0.3569644392 851 34.0000000000 0.9220671654 0.2187024297 0.9220671654 0.0089768624 0.0233230000 208443262 95654136 760807424 -0.4629214108 0.0032006688 0.3498769104 852 34.0400000000 0.9227582216 0.2195287863 0.9227582216 0.0089723905 0.0186280000 208445870 95654136 760807424 -0.4597570002 0.0028217230 0.3412055075 853 34.0800000000 0.9244903326 0.2203552359 0.9244903326 0.0089689740 0.0197950000 208446878 95654136 760807424 -0.4534703493 0.0065104645 0.3327936530 854 34.1199999990 0.9248651266 0.2211801890 0.9248651266 0.0089643803 0.0185180000 208474290 95654136 760807424 -0.4504714906 0.0076346034 0.3248769045 855 34.1600000000 0.9238888621 0.2220020704 0.9248651266 0.0089598956 0.0206080000 208623358 95654136 760807424 -0.4469120800 0.0084407991 0.3164685071 856 34.2000000000 0.9245679975 0.2228228250 0.9248651266 0.0089611286 0.0238570000 208624366 95654136 760807424 -0.4394503534 0.0109269163 0.3093499839 857 34.2400000000 0.9253528118 0.2236425800 0.9253528118 0.0089598837 0.0199350000 208626974 95654136 760807424 -0.4348699152 0.0121016335 0.3020558655 858 34.2800000000 0.9249755740 0.2244599844 0.9253528118 0.0089568615 0.0198900000 208629782 95654136 760807424 -0.4303701222 0.0118816970 0.2959329784 859 34.3200000000 0.9253391027 0.2252759089 0.9253528118 0.0089631228 0.0237330000 208630590 95654136 760807424 -0.4268815219 0.0151572116 0.2869084775 860 34.3600000000 0.9271550775 0.2260920474 0.9271550775 0.0089639622 0.0199670000 208633398 95654136 760807424 -0.4211872220 0.0183645338 0.2788753808 861 34.4000000000 0.9254764915 0.2269043406 0.9271550775 0.0089588619 0.0232070000 208634206 95654136 760807424 -0.4172114730 0.0158899166 0.2708767354 862 34.4400000000 0.9255766869 0.2277148654 0.9271550775 0.0089579222 0.0199240000 208637014 95654136 760807424 -0.4121920764 0.0174103621 0.2632557750 863 34.4800000000 0.9250816107 0.2285229381 0.9271550775 0.0089562069 0.0197650000 208639622 95654136 760807424 -0.4069308639 0.0208260641 0.2555232048 864 34.5200000000 0.9269861579 0.2293313446 0.9271550775 0.0089528749 0.0198410000 208664190 95654136 760807424 -0.4031071365 0.0232509486 0.2482228875 865 34.5600000000 0.9250727296 0.2301356699 0.9271550775 0.0089494965 0.0197500000 208813582 95654136 760807424 -0.3991688192 0.0187440030 0.2414249927 866 34.6000000000 0.9216311574 0.2309341635 0.9271550775 0.0089446218 0.0225630000 208814590 95654136 760807424 -0.3982970119 0.0090578459 0.2367509604 867 34.6400000000 0.9216365814 0.2317308215 0.9271550775 0.0090005723 0.0198400000 208817198 95654136 760807424 -0.3952622116 0.0096898265 0.2206675112 868 34.6800000000 0.9225343466 0.2325266781 0.9271550775 0.0090067256 0.0197870000 208820006 95654136 760807424 -0.3880736232 0.0097413734 0.2152879387 869 34.7200000000 0.9242186546 0.2333226412 0.9271550775 0.0090207542 0.0198470000 208820814 95654136 760807424 -0.3858819306 0.0129484022 0.2082501352 870 34.7600000000 0.9244718552 0.2341170656 0.9271550775 0.0090266417 0.0198210000 208846874 95654136 760807424 -0.3813608289 0.0144644622 0.1998804659 871 34.8000000000 0.9245180488 0.2349097188 0.9271550775 0.0090250864 0.0197940000 208996462 95654136 760807424 -0.3746449053 0.0124472016 0.1949458718 872 34.8400000000 0.9233544469 0.2356992197 0.9271550775 0.0090317538 0.0196920000 208997470 95654136 760807424 -0.3740660548 0.0108001884 0.1872072220 873 34.8800000000 0.9239821434 0.2364876308 0.9271550775 0.0090379901 0.0196900000 209000078 95654136 760807424 -0.3669619262 0.0150958598 0.1800319999 874 34.9200000000 0.9251358509 0.2372755578 0.9271550775 0.0090415722 0.0195980000 209001086 95654136 760807424 -0.3661484122 0.0186054409 0.1720572561 875 34.9600000000 0.9268770218 0.2380636738 0.9271550775 0.0090402634 0.0196950000 209003694 95654136 760807424 -0.3610984385 0.0214056410 0.1661781967 876 35.0000000000 0.9262346029 0.2388492571 0.9271550775 0.0090362860 0.0196330000 209006502 95654136 760807424 -0.3568524122 0.0223724209 0.1587494165 877 35.0400000000 0.9263272285 0.2396331544 0.9271550775 0.0090317841 0.0235650000 209007310 95654136 760807424 -0.3474115431 0.0204856060 0.1549382657 878 35.0800000000 0.9260210395 0.2404149174 0.9271550775 0.0090315941 0.0197480000 209010118 95654136 760807424 -0.3445393443 0.0203291960 0.1493864357 879 35.1200000000 0.9261874557 0.2411950909 0.9271550775 0.0090398128 0.0196670000 209010926 95654136 760807424 -0.3432705402 0.0252192002 0.1399417967 880 35.1600000000 0.9259722233 0.2419732467 0.9271550775 0.0090365283 0.0197130000 209013734 95654136 760807424 -0.3351221979 0.0261868890 0.1334690154 881 35.2000000000 0.9275120497 0.2427513839 0.9275120497 0.0090351900 0.0197060000 209039278 95654136 760807424 -0.3283037841 0.0251596998 0.1295692921 882 35.2400000000 0.9285196662 0.2435288989 0.9285196662 0.0090352770 0.0199250000 209187622 95654136 760807424 -0.3214398921 0.0277161561 0.1222436130 883 35.2800000000 0.9282826781 0.2443043845 0.9285196662 0.0090359975 0.0197850000 209190230 95654136 760807424 -0.3198088408 0.0304879081 0.1122900918 884 35.3200000000 0.9290141463 0.2450789431 0.9290141463 0.0090312577 0.0196470000 209191238 95654136 760807424 -0.3114592135 0.0301320087 0.1073447615 885 35.3600000000 0.9277768135 0.2458503531 0.9290141463 0.0090279050 0.0196440000 209193846 95654136 760807424 -0.3049601018 0.0243138298 0.1026005596 886 35.4000000000 0.9281014800 0.2466203882 0.9290141463 0.0090234246 0.0196410000 209196654 95654136 760807424 -0.3029891551 0.0179356057 0.0962285548 887 35.4400000000 0.9291294217 0.2473898460 0.9291294217 0.0090283659 0.0237060000 209197462 95654136 760807424 -0.2999410927 0.0198890250 0.0863566250 888 35.4800000000 0.9284437299 0.2481567986 0.9291294217 0.0090249353 0.0200210000 209200270 95654136 760807424 -0.2955514789 0.0180960018 0.0789823160 889 35.5200000000 0.9276782870 0.2489211647 0.9291294217 0.0090265339 0.0197140000 209225586 95654136 760807424 -0.2918329835 0.0159645714 0.0711319000 890 35.5600000000 0.9279506803 0.2496841192 0.9291294217 0.0090430286 0.0196320000 209374190 95654136 760807424 -0.2874215841 0.0188571122 0.0619827844 891 35.6000000000 0.9281943440 0.2504456346 0.9291294217 0.0090536376 0.0233450000 209376798 95654136 760807424 -0.2821028829 0.0214411467 0.0504866838 892 35.6400000000 0.9265800714 0.2512036328 0.9291294217 0.0090543588 0.0198900000 209377806 95654136 760807424 -0.2798973620 0.0227365252 0.0405031517 893 35.6800000000 0.9260559678 0.2519593465 0.9291294217 0.0090524040 0.0197450000 209380414 95654136 760807424 -0.2729854882 0.0211082157 0.0340919420 894 35.7200000000 0.9258202910 0.2527131060 0.9291294217 0.0090610523 0.0197740000 209405422 95654136 760807424 -0.2650374770 0.0247413926 0.0271658245 895 35.7600000000 0.9268341660 0.2534663139 0.9291294217 0.0090710240 0.0198370000 209553990 95654136 760807424 -0.2596873045 0.0289726444 0.0172382612 896 35.8000000000 0.9275699854 0.2542186617 0.9291294217 0.0090738443 0.0197630000 209556798 95654136 760807424 -0.2543255687 0.0335385092 0.0094913067 897 35.8400000000 0.9290292263 0.2549709589 0.9291294217 0.0090757579 0.0241480000 209557606 95654136 760807424 -0.2469660491 0.0406894051 -0.0000914643 898 35.8800000000 0.9284675717 0.2557209551 0.9291294217 0.0090723333 0.0200640000 209560414 95654136 760807424 -0.2400163412 0.0405065455 -0.0065345457 899 35.9200000000 0.9273882508 0.2564680823 0.9291294217 0.0090676922 0.0199700000 209585342 95654136 760807424 -0.2338438779 0.0396444723 -0.0148291560 900 35.9600000000 0.9259099364 0.2572119065 0.9291294217 0.0090630295 0.0198890000 209734274 95654136 760807424 -0.2254052311 0.0331325009 -0.0200321358 901 36.0000000000 0.9250559211 0.2579531319 0.9291294217 0.0090648438 0.0199590000 209736882 95654136 760807424 -0.2222924381 0.0292309374 -0.0260111168 902 36.0400000000 0.9247205853 0.2586923419 0.9291294217 0.0090820707 0.0197400000 209737890 95654136 760807424 -0.2176304162 0.0318722390 -0.0394296944 903 36.0800000000 0.9236996174 0.2594287841 0.9291294217 0.0090831206 0.0245010000 209740498 95654136 760807424 -0.2121308744 0.0298904311 -0.0472731292 904 36.1200000000 0.9252278805 0.2601652875 0.9291294217 0.0090879024 0.0199310000 209743306 95654136 760807424 -0.1980393082 0.0298775174 -0.0432487242 905 36.1600000000 0.9254591465 0.2609004188 0.9291294217 0.0091626008 0.0200540000 209765938 95654136 760807424 -0.1820540875 0.0390843078 -0.0656903535 906 36.2000000000 0.9262071252 0.2616347529 0.9291294217 0.0091652580 0.0197620000 209916866 95654136 760807424 -0.1753927171 0.0377878100 -0.0727212355 907 36.2400000000 0.9252238870 0.2623663837 0.9291294217 0.0091664351 0.0309730000 209919474 95654136 760807424 -0.1705559194 0.0352560654 -0.0781814158 908 36.2800000000 0.9249842763 0.2630961391 0.9291294217 0.0091803723 0.0206530000 209920482 95654136 760807424 -0.1676684916 0.0360758863 -0.0842306763 909 36.3200000000 0.9259173274 0.2638253154 0.9291294217 0.0091830924 0.0203170000 209923090 95654136 760807424 -0.1588519812 0.0400417671 -0.0863871425 910 36.3600000000 0.9251841903 0.2645520834 0.9291294217 0.0091790557 0.0202000000 209924098 95654136 760807424 -0.1515354961 0.0399266407 -0.0878122672 911 36.4000000000 0.9256293178 0.2652777444 0.9291294217 0.0091776338 0.0203440000 209948846 95654136 760807424 -0.1464146823 0.0392650366 -0.0897449926 912 36.4400000000 0.9272892475 0.2660036342 0.9291294217 0.0091845423 0.0204100000 210099970 95654136 760807424 -0.1389746815 0.0429692566 -0.0947594866 913 36.4800000000 0.9271706939 0.2667278041 0.9291294217 0.0091816811 0.0202710000 210100778 95654136 760807424 -0.1328945309 0.0426421501 -0.0989798903 914 36.5200000000 0.9249730706 0.2674479849 0.9291294217 0.0091782086 0.0202370000 210103586 95654136 760807424 -0.1292825639 0.0404448695 -0.1043790281 915 36.5600000000 0.9242714047 0.2681658247 0.9291294217 0.0091786992 0.0202130000 210104394 95654136 760807424 -0.1214954779 0.0429545119 -0.1068438366 916 36.6000000000 0.9248276949 0.2688827045 0.9291294217 0.0091803524 0.0202460000 210107202 95654136 760807424 -0.1139311120 0.0455343872 -0.1105680391 917 36.6400000000 0.9267170429 0.2696000810 0.9291294217 0.0091779416 0.0202540000 210109810 95654136 760807424 -0.1066755801 0.0424695686 -0.1123893708 918 36.6800000000 0.9259001017 0.2703150048 0.9291294217 0.0091792158 0.0203280000 210110818 95654136 760807424 -0.1013680995 0.0391365774 -0.1171710417 919 36.7200000000 0.9236330390 0.2710259058 0.9291294217 0.0091821099 0.0202880000 210113426 95654136 760807424 -0.0957683697 0.0423897170 -0.1225178614 920 36.7600000000 0.9228197932 0.2717343775 0.9291294217 0.0091787715 0.0203560000 210136346 95654136 760807424 -0.0914388075 0.0441039428 -0.1290626973 921 36.8000000000 0.9237074256 0.2724422744 0.9291294217 0.0091742617 0.0203270000 210287562 95654136 760807424 -0.0806307942 0.0494272411 -0.1293185949 922 36.8400000000 0.9237470627 0.2731486787 0.9291294217 0.0091703739 0.0202490000 210290370 95654136 760807424 -0.0710271224 0.0479145460 -0.1310680807 923 36.8800000000 0.9222629070 0.2738519444 0.9291294217 0.0091658246 0.0202440000 210291178 95654136 760807424 -0.0654697642 0.0457969047 -0.1335348636 924 36.9200000000 0.9230003357 0.2745544859 0.9291294217 0.0091673221 0.0203010000 210293986 95654136 760807424 -0.0556125268 0.0500288233 -0.1391272992 925 36.9600000000 0.9235524535 0.2752561053 0.9291294217 0.0091629951 0.0203810000 210296594 95654136 760807424 -0.0456945449 0.0532374196 -0.1436767876 926 37.0000000000 0.9233657122 0.2759560077 0.9291294217 0.0091618779 0.0203860000 210297602 95654136 760807424 -0.0318074487 0.0573339164 -0.1504665762 927 37.0400000000 0.9231931567 0.2766542139 0.9291294217 0.0091571024 0.0202850000 210300210 95654136 760807424 -0.0203686394 0.0596521609 -0.1527091414 928 37.0800000000 0.9213132858 0.2773488897 0.9291294217 0.0091524331 0.0203990000 210301218 95654136 760807424 -0.0142684029 0.0568658076 -0.1573407799 929 37.1200000000 0.9213984013 0.2780421615 0.9291294217 0.0091519879 0.0204060000 210325334 95654136 760807424 -0.0054401821 0.0554117858 -0.1601690650 930 37.1600000000 0.9211063385 0.2787336283 0.9291294217 0.0091522753 0.0205800000 210477042 95654136 760807424 0.0041994704 0.0565950572 -0.1636599302 931 37.2000000000 0.9215036631 0.2794240365 0.9291294217 0.0091515045 0.0202830000 210477850 95654136 760807424 0.0109486729 0.0563774072 -0.1680435091 932 37.2400000000 0.9209753871 0.2801123963 0.9291294217 0.0091470995 0.0205190000 210480658 95654136 760807424 0.0207570679 0.0571736619 -0.1680636704 933 37.2800000000 0.9216302633 0.2807999825 0.9291294217 0.0091425057 0.0214900000 210481466 95654136 760807424 0.0304739494 0.0583637692 -0.1711754352 934 37.3200000000 0.9218084812 0.2814862871 0.9291294217 0.0091379507 0.0203670000 210484274 95654136 760807424 0.0401388481 0.0603806935 -0.1751708239 935 37.3600000000 0.9210413098 0.2821703031 0.9291294217 0.0091336661 0.0199980000 210486882 95654136 760807424 0.0500484109 0.0602871589 -0.1762777567 936 37.4000000000 0.9193664789 0.2828510683 0.9291294217 0.0091288753 0.0236700000 210487890 95654136 760807424 0.0597366020 0.0592546761 -0.1768250912 937 37.4400000000 0.9180447459 0.2835289698 0.9291294217 0.0091240705 0.0202210000 210490498 95654136 760807424 0.0697013810 0.0580334440 -0.1784137636 938 37.4800000000 0.9185445309 0.2842059586 0.9291294217 0.0091244554 0.0199520000 210491506 95654136 760807424 0.0774328038 0.0575165600 -0.1818326265 939 37.5200000000 0.9174571633 0.2848803476 0.9291294217 0.0091274055 0.0200500000 210494114 95654136 760807424 0.0866835043 0.0622284748 -0.1858170927 940 37.5600000000 0.9159731269 0.2855517229 0.9291294217 0.0091236573 0.0200690000 210518482 95654136 760807424 0.0960896611 0.0656182170 -0.1860606819 941 37.6000000000 0.9137296677 0.2862192871 0.9291294217 0.0091198982 0.0200030000 210668546 95654136 760807424 0.1022985727 0.0630588457 -0.1895841360 942 37.6400000000 0.9140120149 0.2868857337 0.9291294217 0.0091208780 0.0199640000 210671354 95654136 760807424 0.1105528027 0.0609648041 -0.1926791668 943 37.6800000000 0.9111894369 0.2875477737 0.9291294217 0.0091163578 0.0200090000 210673962 95654136 760807424 0.1187906563 0.0595138557 -0.1940133572 944 37.7200000000 0.9115160704 0.2882087571 0.9291294217 0.0091127148 0.0199580000 210674970 95654136 760807424 0.1266078949 0.0567295775 -0.1922000647 945 37.7600000000 0.9090945721 0.2888657791 0.9291294217 0.0091098520 0.0200200000 210677578 95654136 760807424 0.1351561546 0.0552877747 -0.1916774660 946 37.8000000000 0.9068475366 0.2895190368 0.9291294217 0.0091106824 0.0296530000 210678586 95654136 760807424 0.1426783651 0.0537865907 -0.1943445504 947 37.8400000000 0.9060151577 0.2901700358 0.9291294217 0.0091223179 0.0207510000 210681194 95654136 760807424 0.1507038325 0.0520864055 -0.1980139017 948 37.8800000000 0.9048206806 0.2908184015 0.9291294217 0.0091304285 0.0206980000 210684002 95654136 760807424 0.1589247137 0.0500396565 -0.1996547431 949 37.9200000000 0.9023453593 0.2914627924 0.9291294217 0.0091378893 0.0203340000 210684810 95654136 760807424 0.1653382778 0.0494573489 -0.2045335025 950 37.9600000000 0.8994097710 0.2921027366 0.9291294217 0.0091385240 0.0201910000 210687618 95654136 760807424 0.1723780930 0.0488091931 -0.2079038173 951 38.0000000000 0.8969401121 0.2927387380 0.9291294217 0.0091378098 0.0201530000 210708518 95654136 760807424 0.1790343076 0.0461837724 -0.2104588002 952 38.0400000000 0.8950437307 0.2933714113 0.9291294217 0.0091419966 0.0201750000 210860938 95654136 760807424 0.1863019317 0.0441287607 -0.2141238004 953 38.0800000000 0.8957631588 0.2940035118 0.9291294217 0.0091445815 0.0201630000 210863546 95654136 760807424 0.1946775913 0.0431152508 -0.2130494565 954 38.1200000000 0.8935328126 0.2946319492 0.9291294217 0.0091433241 0.0200220000 210864554 95654136 760807424 0.2021733671 0.0413423926 -0.2153628320 955 38.1600000000 0.8938663006 0.2952594198 0.9291294217 0.0091462921 0.0312690000 210867162 95654136 760807424 0.2095218003 0.0415750258 -0.2154850811 956 38.2000000000 0.8922613859 0.2958838988 0.9291294217 0.0091449768 0.0210160000 210868170 95654136 760807424 0.2175116539 0.0404471681 -0.2185247093 957 38.2400000000 0.8877184987 0.2965023258 0.9291294217 0.0091414963 0.0201490000 210870778 95654136 760807424 0.2235826403 0.0390791409 -0.2245617211 958 38.2800000000 0.8842801452 0.2971158725 0.9291294217 0.0091375200 0.0200290000 210873586 95654136 760807424 0.2287075669 0.0374088697 -0.2301854640 959 38.3200000000 0.8830461502 0.2977268530 0.9291294217 0.0091353283 0.0200760000 210874394 95654136 760807424 0.2366490960 0.0393797904 -0.2319922149 960 38.3600000000 0.8765319586 0.2983297750 0.9291294217 0.0091344038 0.0200470000 210877202 95654136 760807424 0.2444453537 0.0410799384 -0.2370869815 961 38.4000000000 0.8721802235 0.2989269139 0.9291294217 0.0091458921 0.0201270000 210879810 95654136 760807424 0.2486664653 0.0332584567 -0.2392437756 962 38.4400000000 0.8719795346 0.2995226027 0.9291294217 0.0091417889 0.0200440000 210880818 95654136 760807424 0.2556392848 0.0298524443 -0.2385888100 963 38.4800000000 0.8734673858 0.3001185993 0.9291294217 0.0091404809 0.0200360000 210883426 95654136 760807424 0.2624485195 0.0242106840 -0.2351614386 964 38.5200000000 0.8748273849 0.3007147703 0.9291294217 0.0091423572 0.0200430000 210884434 95654136 760807424 0.2671646774 0.0169788077 -0.2298878133 965 38.5600000000 0.8745511770 0.3013094194 0.9291294217 0.0091389562 0.0278220000 210887042 95654136 760807424 0.2727730274 0.0106382323 -0.2302013636 966 38.6000000000 0.8723675609 0.3019005769 0.9291294217 0.0091384744 0.0205720000 210909698 95654136 760807424 0.2797071338 0.0068897801 -0.2325184941 967 38.6400000000 0.8704425693 0.3024885210 0.9291294217 0.0091369888 0.0201070000 211060602 95654136 760807424 0.2833310366 0.0005734791 -0.2306294441 968 38.6800000000 0.8689657450 0.3030737248 0.9291294217 0.0091386831 0.0200680000 211063410 95654136 760807424 0.2888858318 -0.0015230586 -0.2333233654 969 38.7200000000 0.8668439984 0.3036555310 0.9291294217 0.0091359458 0.0239360000 211064218 95654136 760807424 0.2930779755 -0.0024053070 -0.2329977900 970 38.7600000000 0.8690376878 0.3042383993 0.9291294217 0.0091363060 0.0201200000 211067026 95654136 760807424 0.2980465293 -0.0036622107 -0.2331511676 971 38.8000000000 0.8641875386 0.3048150719 0.9291294217 0.0091362086 0.0199600000 211069634 95654136 760807424 0.3020254076 -0.0005726053 -0.2386809438 972 38.8400000000 0.8589005470 0.3053851187 0.9291294217 0.0091342436 0.0199950000 211070642 95654136 760807424 0.3077563345 -0.0003755928 -0.2443806827 973 38.8800000000 0.8527188301 0.3059476405 0.9291294217 0.0091396158 0.0199580000 211073250 95654136 760807424 0.3128176033 0.0011546862 -0.2500796914 974 38.9200000000 0.8504921794 0.3065067211 0.9291294217 0.0091406234 0.0199410000 211074258 95654136 760807424 0.3183693290 -0.0002810534 -0.2502427101 975 38.9600000000 0.8454861045 0.3070595205 0.9291294217 0.0091400376 0.0312940000 211076866 95654136 760807424 0.3190231025 -0.0029577867 -0.2514986992 976 39.0000000000 0.8405466080 0.3076061261 0.9291294217 0.0091384325 0.0208230000 211079674 95654136 760807424 0.3195831180 -0.0058527328 -0.2530672848 977 39.0400000000 0.8391630054 0.3081501966 0.9291294217 0.0091349766 0.0199620000 211080482 95654136 760807424 0.3193437159 -0.0063572153 -0.2502247691 978 39.0800000000 0.8330104351 0.3086868635 0.9291294217 0.0091349576 0.0207200000 211083290 95654136 760807424 0.3215940893 -0.0074683223 -0.2519552112 979 39.1200000000 0.8308479786 0.3092202252 0.9291294217 0.0091529810 0.0201650000 211085898 95654136 760807424 0.3257616758 -0.0071858992 -0.2554021776 980 39.1600000000 0.8379465938 0.3097597419 0.9291294217 0.0091691235 0.0200060000 211086906 95654136 760807424 0.3356085420 -0.0060948338 -0.2488038093 981 39.2000000000 0.8336724639 0.3102938018 0.9291294217 0.0091677578 0.0199000000 211089514 95654136 760807424 0.3391683996 -0.0027952450 -0.2502482235 982 39.2400000000 0.8263340592 0.3108193010 0.9291294217 0.0091665501 0.0238810000 211090522 95654136 760807424 0.3420100212 -0.0037123649 -0.2558932900 983 39.2800000000 0.8217031956 0.3113390202 0.9291294217 0.0091674933 0.0200450000 211093130 95654136 760807424 0.3446922600 -0.0057243556 -0.2573228180 984 39.3200000000 0.8199194074 0.3118558701 0.9291294217 0.0091648796 0.0198780000 211095938 95654136 760807424 0.3451156020 -0.0060639987 -0.2555328012 985 39.3600000000 0.8226258755 0.3123744184 0.9291294217 0.0091621534 0.0244390000 211096746 95654136 760807424 0.3495469689 -0.0071233325 -0.2515917718 986 39.4000000000 0.8220430017 0.3128913236 0.9291294217 0.0091591421 0.0352450000 211099554 95654136 760807424 0.3507136703 -0.0086358991 -0.2466726899 987 39.4400000000 0.8256679177 0.3134108541 0.9291294217 0.0091579236 0.0217410000 211100362 95654136 760807424 0.3540002704 -0.0106525356 -0.2387885749 988 39.4800000000 0.8318339586 0.3139355739 0.9291294217 0.0091537001 0.0200240000 211103170 95654136 760807424 0.3545747101 -0.0146418875 -0.2276436538 989 39.5200000000 0.8344115019 0.3144618387 0.9291294217 0.0091513274 0.0201540000 211105778 95654136 760807424 0.3555841148 -0.0145845693 -0.2222190946 990 39.5600000000 0.8306175470 0.3149832081 0.9291294217 0.0091524803 0.0201600000 211106786 95654136 760807424 0.3617624640 -0.0097944196 -0.2251623571 991 39.6000000000 0.8280910254 0.3155009758 0.9291294217 0.0091481637 0.0205760000 211109394 95654136 760807424 0.3671088517 -0.0059036282 -0.2231752425 992 39.6400000000 0.8232517242 0.3160128213 0.9291294217 0.0091449633 0.0199250000 211110402 95654136 760807424 0.3725642562 -0.0005006106 -0.2260907143 993 39.6800000000 0.8191538453 0.3165195092 0.9291294217 0.0091416230 0.0236890000 211113010 95654136 760807424 0.3790183365 0.0055257566 -0.2255589962 994 39.7200000000 0.8142772913 0.3170202715 0.9291294217 0.0091382251 0.0200210000 211115818 95654136 760807424 0.3863637745 0.0102964826 -0.2284948677 995 39.7600000000 0.8124005795 0.3175181412 0.9291294217 0.0091345081 0.0199130000 211116626 95654136 760807424 0.3928905129 0.0133726131 -0.2287898511 996 39.8000000000 0.8076846600 0.3180102763 0.9291294217 0.0091319195 0.0198710000 211119434 95654136 760807424 0.3979575336 0.0140651884 -0.2301818877 997 39.8400000000 0.8054727912 0.3184992056 0.9291294217 0.0091283914 0.0240370000 211122042 95654136 760807424 0.4035227597 0.0163918622 -0.2292091101 998 39.8800000000 0.8055947423 0.3189872772 0.9291294217 0.0091247787 0.0199710000 211123050 95654136 760807424 0.4087963998 0.0164081845 -0.2266735584 999 39.9200000000 0.8089313507 0.3194777117 0.9291294217 0.0091219093 0.0198860000 211125658 95654136 760807424 0.4153352082 0.0220579281 -0.2177858949 1000 39.9600000000 0.8063013554 0.3199645354 0.9291294217 0.0091175702 0.0198660000 211126666 95654136 760807424 0.4226541817 0.0259224977 -0.2205502540 1001 40.0000000000 0.8048579097 0.3204489444 0.9291294217 0.0091144285 0.0247550000 211129274 95654136 760807424 0.4307887852 0.0261092950 -0.2210837752 1002 40.0400000000 0.8041425347 0.3209316725 0.9291294217 0.0091134695 0.0200670000 211132082 95654136 760807424 0.4368285239 0.0310569424 -0.2183045894 1003 40.0800000000 0.8015621901 0.3214108654 0.9291294217 0.0091112378 0.0238750000 211132890 95654136 760807424 0.4430792034 0.0382903665 -0.2183236331 1004 40.1200000000 0.7967894077 0.3218843500 0.9291294217 0.0091075774 0.0199840000 211135698 95654136 760807424 0.4498884380 0.0412045196 -0.2213987857 1005 40.1600000000 0.7942876220 0.3223544030 0.9291294217 0.0091041830 0.0200000000 211136506 95654136 760807424 0.4583024681 0.0448307022 -0.2228684574 1006 40.2000000000 0.7902756333 0.3228195335 0.9291294217 0.0091007213 0.0199430000 211139314 95654136 760807424 0.4651843309 0.0509190485 -0.2230170071 1007 40.2400000000 0.7860757709 0.3232795695 0.9291294217 0.0090971225 0.0198720000 211141922 95654136 760807424 0.4728412330 0.0564059503 -0.2241413593 1008 40.2800000000 0.7825782895 0.3237352230 0.9291294217 0.0090929329 0.0199010000 211160862 95654136 760807424 0.4794870019 0.0593831800 -0.2253222764 1009 40.3200000000 0.7763282061 0.3241837789 0.9291294217 0.0090907599 0.0199040000 211314914 95654136 760807424 0.4868593812 0.0606897846 -0.2282053530 1010 40.3600000000 0.7696576715 0.3246248422 0.9291294217 0.0090891960 0.0198910000 211315922 95654136 760807424 0.4946873486 0.0649668947 -0.2323546857 1011 40.4000000000 0.7634512186 0.3250588940 0.9291294217 0.0090865691 0.0238790000 211318530 95654136 760807424 0.5009001493 0.0655403063 -0.2371602356 1012 40.4400000000 0.7614092231 0.3254900702 0.9291294217 0.0090875873 0.0202110000 211321338 95654136 760807424 0.5064555407 0.0650145411 -0.2375342697 1013 40.4800000000 0.7584891915 0.3259175126 0.9291294217 0.0090921916 0.0199510000 211322146 95654136 760807424 0.5111483335 0.0699675009 -0.2356896549 1014 40.5200000000 0.7539480329 0.3263396334 0.9291294217 0.0090949967 0.0198750000 211324954 95654136 760807424 0.5166661143 0.0729175657 -0.2379094213 1015 40.5600000000 0.7502092719 0.3267572390 0.9291294217 0.0091012850 0.0238840000 211327562 95654136 760807424 0.5228440762 0.0742060766 -0.2412976623 1016 40.6000000000 0.7463462353 0.3271702203 0.9291294217 0.0091062520 0.0199980000 211328570 95654136 760807424 0.5291736126 0.0745779350 -0.2446293086 1017 40.6400000000 0.7408286929 0.3275769641 0.9291294217 0.0091128668 0.0198750000 211331178 95654136 760807424 0.5334151387 0.0756002441 -0.2456623763 1018 40.6800000000 0.7370499372 0.3279791969 0.9291294217 0.0091160786 0.0199150000 211332186 95654136 760807424 0.5396240950 0.0787305832 -0.2470284551 1019 40.7200000000 0.7330557108 0.3283767204 0.9291294217 0.0091159895 0.0199120000 211334794 95654136 760807424 0.5443544388 0.0807478279 -0.2468974590 1020 40.7600000000 0.7244676948 0.3287650449 0.9291294217 0.0091221555 0.0198420000 211337602 95654136 760807424 0.5507713556 0.0838112906 -0.2522363067 1021 40.8000000000 0.7178266048 0.3291461042 0.9291294217 0.0091216453 0.0200710000 211338410 95654136 760807424 0.5580130816 0.0875328109 -0.2556922734 1022 40.8400000000 0.7155636549 0.3295242036 0.9291294217 0.0091191850 0.0208590000 211341218 95654136 760807424 0.5630984306 0.0900186375 -0.2518589199 1023 40.8800000000 0.7028077245 0.3298890946 0.9291294217 0.0091334183 0.0200740000 211342026 95654136 760807424 0.5676354766 0.0928649455 -0.2607764304 1024 40.9200000000 0.6943888068 0.3302450514 0.9291294217 0.0091432291 0.0199160000 211344834 95654136 760807424 0.5746869445 0.0976004750 -0.2662471533 1025 40.9600000000 0.6896409392 0.3305956815 0.9291294217 0.0091408999 0.0200340000 211437554 95654136 760807424 0.5825307965 0.0980614945 -0.2650559843 1026 41.0000000000 0.6822181940 0.3309383935 0.9291294217 0.0091395616 0.0199290000 211643362 95654136 760807424 0.5879122019 0.0988783538 -0.2678527236 1027 41.0400000000 0.6730054617 0.3312714676 0.9291294217 0.0091490114 0.0199520000 211645970 95654136 760807424 0.5923435092 0.0977117866 -0.2753212154 1028 41.0800000000 0.6589506269 0.3315902216 0.9291294217 0.0091637974 0.0199650000 211646978 95654136 760807424 0.5991343260 0.0994013920 -0.2822899520 1029 41.1200000000 0.6397303343 0.3318896775 0.9291294217 0.0091838440 0.0199330000 211649586 95654136 760807424 0.6045641899 0.0987411290 -0.3001002073 1030 41.1600000000 0.6340010762 0.3321829896 0.9291294217 0.0091820881 0.0199560000 211652394 95654136 760807424 0.6125696301 0.1005312502 -0.3040615022 1031 41.2000000000 0.6269823313 0.3324689249 0.9291294217 0.0091817711 0.0199240000 211653202 95654136 760807424 0.6196631789 0.0981402844 -0.3057863116 1032 41.2400000000 0.6153990030 0.3327430820 0.9291294217 0.0091881661 0.0237200000 211656010 95654136 760807424 0.6256588697 0.0972091705 -0.3127936721 1033 41.2800000000 0.6020022631 0.3330037395 0.9291294217 0.0091988960 0.0200800000 211658618 95654136 760807424 0.6318070292 0.0941051319 -0.3191958070 1034 41.3200000000 0.5980720520 0.3332600918 0.9291294217 0.0091970613 0.0199610000 211659626 95654136 760807424 0.6415849328 0.0953867510 -0.3184223473 1035 41.3600000000 0.5923580527 0.3335104280 0.9291294217 0.0091983962 0.0199580000 211662234 95654136 760807424 0.6475539804 0.0958407372 -0.3211058974 1036 41.4000000000 0.5903575420 0.3337583499 0.9291294217 0.0091947797 0.0199430000 211663242 95654136 760807424 0.6536390185 0.0956083834 -0.3210486770 1037 41.4400000000 0.5915665627 0.3340069596 0.9291294217 0.0091943655 0.0199470000 211665850 95654136 760807424 0.6604803801 0.0934122801 -0.3149743378 1038 41.4800000000 0.5838800073 0.3342476850 0.9291294217 0.0091981144 0.0198760000 211668658 95654136 760807424 0.6679437757 0.0919672772 -0.3158899546 1039 41.5200000000 0.5716509819 0.3344761771 0.9291294217 0.0092067291 0.0210790000 211669466 95654136 760807424 0.6762093902 0.0904921070 -0.3237136602 1040 41.5600000000 0.5671272874 0.3346998801 0.9291294217 0.0092042234 0.0199830000 211672274 95654136 760807424 0.6831688285 0.0920814723 -0.3233573437 1041 41.6000000000 0.5612878799 0.3349175439 0.9291294217 0.0092044498 0.0199550000 211673082 95654136 760807424 0.6902716160 0.0917490125 -0.3286718726 1042 41.6400000000 0.5590381026 0.3351326308 0.9291294217 0.0092011087 0.0200040000 211675890 95654136 760807424 0.6976454258 0.0910174251 -0.3232805729 1043 41.6800000000 0.5478423834 0.3353365711 0.9291294217 0.0092064147 0.0199400000 211678498 95654136 760807424 0.7060029507 0.0923042297 -0.3315073252 1044 41.7200000000 0.5349978209 0.3355278176 0.9291294217 0.0092265503 0.0200850000 211679506 95654136 760807424 0.7211105824 0.0929514989 -0.3420411348 1045 41.7600000000 0.5291301608 0.3357130830 0.9291294217 0.0092309932 0.0199750000 211682114 95654136 760807424 0.7281605005 0.0920839012 -0.3442076445 1046 41.8000000000 0.5234341025 0.3358925486 0.9291294217 0.0092313041 0.0199590000 211683122 95654136 760807424 0.7333835363 0.0920991972 -0.3435715735 1047 41.8400000000 0.5230870843 0.3360713399 0.9291294217 0.0092276906 0.0200170000 211685730 95654136 760807424 0.7395806313 0.0905104280 -0.3405218422 1048 41.8800000000 0.5179355741 0.3362448745 0.9291294217 0.0092268160 0.0201850000 211688538 95654136 760807424 0.7490631938 0.0914330557 -0.3407037258 1049 41.9200000000 0.5115238428 0.3364119660 0.9291294217 0.0092261937 0.0236020000 211689346 95654136 760807424 0.7577937841 0.0928555503 -0.3449390233 1050 41.9600000000 0.5074065328 0.3365748179 0.9291294217 0.0092249914 0.0199980000 211692154 95654136 760807424 0.7630316615 0.0923366919 -0.3463457525 1051 42.0000000000 0.5047191978 0.3367348031 0.9291294217 0.0092229202 0.0200270000 211694762 95654136 760807424 0.7703821063 0.0888937488 -0.3447526395 1052 42.0400000000 0.5007769465 0.3368907367 0.9291294217 0.0092207209 0.0199330000 211695770 95654136 760807424 0.7771131992 0.0900765508 -0.3433814347 1053 42.0800000000 0.4983739555 0.3370440920 0.9291294217 0.0092182592 0.0200250000 211698378 95654136 760807424 0.7814148664 0.0910187140 -0.3416158855 1054 42.1200000000 0.4945318997 0.3371935112 0.9291294217 0.0092160197 0.0237870000 211699386 95654136 760807424 0.7847533226 0.0894103050 -0.3393730223 1055 42.1600000000 0.4902350307 0.3373385743 0.9291294217 0.0092267609 0.0202330000 211701994 95654136 760807424 0.7976906300 0.0898692235 -0.3372094035 1056 42.2000000000 0.4847129583 0.3374781333 0.9291294217 0.0092272737 0.0200790000 211819966 95654136 760807424 0.8036031723 0.0860271752 -0.3367578685 1057 42.2400000000 0.4822307825 0.3376150800 0.9291294217 0.0092264094 0.0201440000 211875454 95654136 760807424 0.8113318086 0.0858444870 -0.3339032829 1058 42.2800000000 0.4789406359 0.3377486581 0.9291294217 0.0092232997 0.0200970000 211878262 95654136 760807424 0.8175873756 0.0863859206 -0.3299901485 1059 42.3200000000 0.4768305123 0.3378799913 0.9291294217 0.0092195467 0.0200780000 211879070 95654136 760807424 0.8200369477 0.0868629441 -0.3262235820 1060 42.3600000000 0.4777668715 0.3380119600 0.9291294217 0.0092153695 0.0200610000 211881878 95654136 760807424 0.8259293437 0.0888873488 -0.3204709888 1061 42.4000000000 0.4767940938 0.3381427632 0.9291294217 0.0092112362 0.0201520000 211884486 95654136 760807424 0.8284949064 0.0878985226 -0.3145431280 1062 42.4400000000 0.4761759043 0.3382727379 0.9291294217 0.0092070527 0.0201070000 211885494 95654136 760807424 0.8335040808 0.0889915302 -0.3088031411 1063 42.4800000000 0.4721485674 0.3383986794 0.9291294217 0.0092057693 0.0200790000 211888102 95654136 760807424 0.8370807171 0.0861890167 -0.3048852980 1064 42.5200000000 0.4706249833 0.3385229522 0.9291294217 0.0092023938 0.0239650000 211889110 95654136 760807424 0.8427882195 0.0859935433 -0.3010132313 1065 42.5600000000 0.4680488408 0.3386445728 0.9291294217 0.0091989062 0.0201680000 211891718 95654136 760807424 0.8489953279 0.0862228423 -0.2994264662 1066 42.6000000000 0.4640138447 0.3387621800 0.9291294217 0.0091965316 0.0201710000 211894526 95654136 760807424 0.8513885736 0.0853203610 -0.2961476445 1067 42.6400000000 0.4631151259 0.3388787244 0.9291294217 0.0091925260 0.0202110000 211895334 95654136 760807424 0.8560129404 0.0865195841 -0.2922168970 1068 42.6800000000 0.4614918828 0.3389935308 0.9291294217 0.0091886599 0.0201900000 211898142 95654136 760807424 0.8601746559 0.0876761228 -0.2886771262 1069 42.7200000000 0.4586288035 0.3391054440 0.9291294217 0.0091854981 0.0203320000 211900750 95654136 760807424 0.8677453995 0.0888370425 -0.2847400308 1070 42.7600000000 0.4593903720 0.3392178598 0.9291294217 0.0091848575 0.0202630000 211901758 95654136 760807424 0.8740655780 0.0947490260 -0.2774201334 1071 42.8000000000 0.4546110332 0.3393256032 0.9291294217 0.0091836525 0.0202920000 211904366 95654136 760807424 0.8799585104 0.0944408849 -0.2737328112 1072 42.8400000000 0.4536331892 0.3394322334 0.9291294217 0.0091796552 0.0206180000 211905374 95654136 760807424 0.8821474910 0.0969168544 -0.2673725188 1073 42.8800000000 0.4513901472 0.3395365745 0.9291294217 0.0091783493 0.0202070000 211907982 95654136 760807424 0.8816394806 0.0962110609 -0.2604952455 1074 42.9200000000 0.4501733482 0.3396395882 0.9291294217 0.0091759039 0.0239950000 211910790 95654136 760807424 0.8840224147 0.0966825187 -0.2528744936 1075 42.9600000000 0.4492763877 0.3397415759 0.9291294217 0.0091723015 0.0203690000 211911598 95654136 760807424 0.8877028227 0.0974859968 -0.2445784062 1076 43.0000000000 0.4492022991 0.3398433052 0.9291294217 0.0091695453 0.0202060000 212029006 95654136 760807424 0.8911577463 0.0995814502 -0.2385500520 1077 43.0400000000 0.4486074746 0.3399442933 0.9291294217 0.0091670662 0.0201580000 212085138 95654136 760807424 0.8944715261 0.1007032841 -0.2321896553 1078 43.0800000000 0.4454084933 0.3400421265 0.9291294217 0.0091663234 0.0201380000 212087946 95654136 760807424 0.8965311050 0.0989619568 -0.2286431640 1079 43.1200000000 0.4460416138 0.3401403652 0.9291294217 0.0091639413 0.0202380000 212090554 95654136 760807424 0.8993464112 0.1007801890 -0.2219168395 1080 43.1600000000 0.4429181218 0.3402355298 0.9291294217 0.0091616417 0.0202100000 212091562 95654136 760807424 0.9018732309 0.0984916165 -0.2132512629 1081 43.2000000000 0.4426206350 0.3403302431 0.9291294217 0.0091586546 0.0202400000 212094170 95654136 760807424 0.9023260474 0.0986205861 -0.2048315257 1082 43.2400000000 0.4404078722 0.3404227363 0.9291294217 0.0091552557 0.0202680000 212095178 95654136 760807424 0.9041313529 0.0985089391 -0.1989031881 1083 43.2800000000 0.4373042285 0.3405121929 0.9291294217 0.0091522569 0.0203280000 212097786 95654136 760807424 0.9073003531 0.0954549834 -0.1900716424 1084 43.3200000000 0.4359066784 0.3406001952 0.9291294217 0.0091488084 0.0238310000 212100594 95654136 760807424 0.9087113142 0.0947336778 -0.1799221486 1085 43.3600000000 0.4366983473 0.3406887649 0.9291294217 0.0091472670 0.0242790000 212101402 95654136 760807424 0.9102632403 0.0965885743 -0.1722127050 1086 43.4000000000 0.4373823702 0.3407778014 0.9291294217 0.0091432499 0.0203380000 212104210 95654136 760807424 0.9099929929 0.0971887633 -0.1631149501 1087 43.4400000000 0.4368475080 0.3408661819 0.9291294217 0.0091391284 0.0211770000 212106818 95654136 760807424 0.9104700685 0.0976199284 -0.1541415751 1088 43.4800000000 0.4363039136 0.3409539005 0.9291294217 0.0091354183 0.0203880000 212107826 95654136 760807424 0.9103537798 0.0980810001 -0.1477930397 1089 43.5200000000 0.4350861907 0.3410403397 0.9291294217 0.0091324314 0.0204020000 212110434 95654136 760807424 0.9131156802 0.0980231315 -0.1416256875 1090 43.5600000000 0.4334541559 0.3411251230 0.9291294217 0.0091287019 0.0204060000 212111442 95654136 760807424 0.9141795635 0.0966423824 -0.1321980804 1091 43.6000000000 0.4307598174 0.3412072813 0.9291294217 0.0091274953 0.0203240000 212114050 95654136 760807424 0.9140725732 0.0914221704 -0.1230947375 1092 43.6400000000 0.4304468930 0.3412890025 0.9291294217 0.0091243998 0.0202800000 212116858 95654136 760807424 0.9137086272 0.0903811082 -0.1140533090 1093 43.6800000000 0.4274575114 0.3413678392 0.9291294217 0.0091224318 0.0202960000 212117666 95654136 760807424 0.9154723883 0.0870623738 -0.1060985923 1094 43.7200000000 0.4268839359 0.3414460075 0.9291294217 0.0091188623 0.0280660000 212234490 95654136 760807424 0.9172162414 0.0877631009 -0.0991904736 1095 43.7600000000 0.4267843068 0.3415239420 0.9291294217 0.0091152061 0.0206600000 212291202 95654136 760807424 0.9155395627 0.0892383829 -0.0927248076 1096 43.8000000000 0.4261410832 0.3416011474 0.9291294217 0.0091111966 0.0202890000 212294010 95654136 760807424 0.9156420827 0.0880482867 -0.0843507648 1097 43.8400000000 0.4251054525 0.3416772680 0.9291294217 0.0091074203 0.0203340000 212296618 95654136 760807424 0.9160723686 0.0872789547 -0.0737158433 1098 43.8800000000 0.4242863059 0.3417525040 0.9291294217 0.0091080609 0.0203680000 212297626 95654136 760807424 0.9162227511 0.0855377987 -0.0622599013 1099 43.9200000000 0.4243575931 0.3418276678 0.9291294217 0.0091062344 0.0202780000 212300234 95654136 760807424 0.9159232974 0.0873312876 -0.0545793958 1100 43.9600000000 0.4234043956 0.3419018285 0.9291294217 0.0091026673 0.0204010000 212301242 95654136 760807424 0.9151470661 0.0858292133 -0.0466363952 1101 44.0000000000 0.4215824008 0.3419741996 0.9291294217 0.0090993529 0.0204090000 212303850 95654136 760807424 0.9154807925 0.0839224383 -0.0386302955 1102 44.0400000000 0.4218974710 0.3420467252 0.9291294217 0.0090952706 0.0203800000 212306658 95654136 760807424 0.9142704606 0.0842641219 -0.0296999421 1103 44.0800000000 0.4207285345 0.3421180596 0.9291294217 0.0090925604 0.0205210000 212307466 95654136 760807424 0.9140266180 0.0825020149 -0.0202960186 1104 44.1200000000 0.4180722833 0.3421868587 0.9291294217 0.0090896420 0.0265290000 212310274 95654136 760807424 0.9130954146 0.0786383003 -0.0113103129 1105 44.1600000000 0.4189657867 0.3422563419 0.9291294217 0.0090864108 0.0206230000 212312882 95654136 760807424 0.9147261977 0.0823349133 -0.0001309309 1106 44.2000000000 0.4190227687 0.3423257510 0.9291294217 0.0090823972 0.0204260000 212313890 95654136 760807424 0.9147514701 0.0824822932 0.0113650570 1107 44.2400000000 0.4170853496 0.3423932845 0.9291294217 0.0090789555 0.0204990000 212316498 95654136 760807424 0.9132673144 0.0822276101 0.0210674852 1108 44.2800000000 0.4146926999 0.3424585367 0.9291294217 0.0090760303 0.0203870000 212317506 95654136 760807424 0.9147840142 0.0787781328 0.0302423090 1109 44.3200000000 0.4122918248 0.3425215063 0.9291294217 0.0090729494 0.0205070000 212320114 95654136 760807424 0.9155253768 0.0766772777 0.0389699005 1110 44.3600000000 0.4118258059 0.3425839426 0.9291294217 0.0090693490 0.0206480000 212322922 95654136 760807424 0.9160429239 0.0769243538 0.0496480651 1111 44.4000000000 0.4121145904 0.3426465264 0.9291294217 0.0090658258 0.0205610000 212437334 95654136 760807424 0.9172028899 0.0772701129 0.0605625361 1112 44.4400000000 0.4120878279 0.3427089736 0.9291294217 0.0090620234 0.0204930000 212496594 95654136 760807424 0.9191759229 0.0773962140 0.0732106566 1113 44.4800000000 0.4105721414 0.3427699468 0.9291294217 0.0090587398 0.0204730000 212497402 95654136 760807424 0.9240521789 0.0761765689 0.0849308744 1114 44.5200000000 0.4106643200 0.3428308933 0.9291294217 0.0090553148 0.0205170000 212500210 95654136 760807424 0.9256669283 0.0770425573 0.0934234858 1115 44.5600000000 0.4092384279 0.3428904516 0.9291294217 0.0090516648 0.0204770000 212502818 95654136 760807424 0.9270251393 0.0754159242 0.1027923897 1116 44.6000000000 0.4068298936 0.3429477450 0.9291294217 0.0090489778 0.0206000000 212503826 95654136 760807424 0.9313015938 0.0724300668 0.1139285862 1117 44.6400000000 0.4047206044 0.3430030475 0.9291294217 0.0090462406 0.0203990000 212506434 95654136 760807424 0.9315789938 0.0709773824 0.1236000881 1118 44.6800000000 0.4041026533 0.3430576983 0.9291294217 0.0090429763 0.0242750000 212507442 95654136 760807424 0.9316499829 0.0699687153 0.1323500425 1119 44.7200000000 0.4027559757 0.3431110480 0.9291294217 0.0090391912 0.0212150000 212510050 95654136 760807424 0.9305209517 0.0687310547 0.1431394964 1120 44.7600000000 0.4017150998 0.3431633730 0.9291294217 0.0090366192 0.0205060000 212512858 95654136 760807424 0.9328635335 0.0670718402 0.1541199088 1121 44.8000000000 0.4014677405 0.3432153841 0.9291294217 0.0090329707 0.0204860000 212513666 95654136 760807424 0.9347858429 0.0676416755 0.1650699526 1122 44.8400000000 0.4022902548 0.3432680355 0.9291294217 0.0090291319 0.0205040000 212516474 95654136 760807424 0.9355340004 0.0698910803 0.1754578948 1123 44.8800000000 0.4018099308 0.3433201654 0.9291294217 0.0090255112 0.0246510000 212519082 95654136 760807424 0.9371430278 0.0706784502 0.1866725534 1124 44.9200000000 0.4002859890 0.3433708467 0.9291294217 0.0090220411 0.0207170000 212520090 95654136 760807424 0.9370989203 0.0700687990 0.1963028461 1125 44.9600000000 0.3991174996 0.3434203993 0.9291294217 0.0090190923 0.0206070000 212522698 95654136 760807424 0.9401524663 0.0689953417 0.2060362995 1126 45.0000000000 0.3987417817 0.3434695302 0.9291294217 0.0090152698 0.0207090000 212523706 95654136 760807424 0.9412232041 0.0692093521 0.2154790461 1127 45.0400000000 0.3975854218 0.3435175478 0.9291294217 0.0090123826 0.0206510000 212526314 95654136 760807424 0.9424474239 0.0684150681 0.2226834595 1128 45.0800000000 0.3953936994 0.3435635373 0.9291294217 0.0090105124 0.0206120000 212529122 95654136 760807424 0.9438651800 0.0649132431 0.2307286710 1129 45.1200000000 0.3939999342 0.3436082108 0.9291294217 0.0090072172 0.0206350000 212529930 95654136 760807424 0.9453599453 0.0630598441 0.2401879430 1130 45.1600000000 0.3926812708 0.3436516383 0.9291294217 0.0090046434 0.0207730000 212645494 95654136 760807424 0.9478313923 0.0586335473 0.2484760731 1131 45.2000000000 0.3916626275 0.3436940884 0.9291294217 0.0090018323 0.0206660000 212703366 95654136 760807424 0.9497462511 0.0545136854 0.2553317249 1132 45.2400000000 0.3907965422 0.3437356983 0.9291294217 0.0089979339 0.0206770000 212706174 95654136 760807424 0.9500301480 0.0539249070 0.2618882954 1133 45.2800000000 0.3897207379 0.3437762853 0.9291294217 0.0089943733 0.0263070000 212708782 95654136 760807424 0.9490894675 0.0530675575 0.2696811855 1134 45.3200000000 0.3890849352 0.3438162400 0.9291294217 0.0089907996 0.0220640000 212709790 95654136 760807424 0.9487332106 0.0529754609 0.2784906924 1135 45.3600000000 0.3878732324 0.3438550567 0.9291294217 0.0089873134 0.0247890000 212712398 95654136 760807424 0.9491039515 0.0527688265 0.2849661410 1136 45.4000000000 0.3866927922 0.3438927660 0.9291294217 0.0089843591 0.0208410000 212713406 95654136 760807424 0.9525179267 0.0518835336 0.2930459976 1137 45.4400000000 0.3857425451 0.3439295732 0.9291294217 0.0089809048 0.0208020000 212716014 95654136 760807424 0.9520396590 0.0517533422 0.3000395298 1138 45.4800000000 0.3848148584 0.3439655005 0.9291294217 0.0089775950 0.0207640000 212718822 95654136 760807424 0.9536190033 0.0507329293 0.3062781394 1139 45.5200000000 0.3841840029 0.3440008109 0.9291294217 0.0089740604 0.0207960000 212719630 95654136 760807424 0.9563385248 0.0508068129 0.3137688637 1140 45.5600000000 0.3830622137 0.3440350753 0.9291294217 0.0089709971 0.0207500000 212722438 95654136 760807424 0.9545389414 0.0506631024 0.3180225194 1141 45.6000000000 0.3822627664 0.3440685789 0.9291294217 0.0089676556 0.0209250000 212725046 95654136 760807424 0.9555495977 0.0488309935 0.3236182332 1142 45.6400000000 0.3818261921 0.3441016416 0.9291294217 0.0089646146 0.0208140000 212726054 95654136 760807424 0.9574636221 0.0481052510 0.3318193853 1143 45.6800000000 0.3809639513 0.3441338921 0.9291294217 0.0089610993 0.0208410000 212728662 95654136 760807424 0.9589430690 0.0463709570 0.3383960724 1144 45.7200000000 0.3797981739 0.3441650672 0.9291294217 0.0089584805 0.0207990000 212729670 95654136 760807424 0.9596533179 0.0440429561 0.3445021212 1145 45.7600000000 0.3796341419 0.3441960446 0.9291294217 0.0089546648 0.0208100000 212732278 95654136 760807424 0.9617026448 0.0448189378 0.3518796265 1146 45.8000000000 0.3792551756 0.3442266372 0.9291294217 0.0089512568 0.0208020000 212735086 95654136 760807424 0.9647543430 0.0425156243 0.3595383763 1147 45.8400000000 0.3791404366 0.3442570764 0.9291294217 0.0089473985 0.0207630000 212735894 95654136 760807424 0.9652883410 0.0438897908 0.3657418489 1148 45.8800000000 0.3784170747 0.3442868325 0.9291294217 0.0089436024 0.0208340000 212738702 95654136 760807424 0.9654950500 0.0435700305 0.3719228804 1149 45.9200000000 0.3779847920 0.3443161606 0.9291294217 0.0089420507 0.0208410000 212739510 95654136 760807424 0.9699168205 0.0397726186 0.3801608086 1150 45.9600000000 0.3777096868 0.3443451984 0.9291294217 0.0089386435 0.0208970000 212742318 95654136 760807424 0.9731570482 0.0373553410 0.3871871531 1151 46.0000000000 0.3769740462 0.3443735467 0.9291294217 0.0089367396 0.0246320000 212744926 95654136 760807424 0.9764233828 0.0327692218 0.3957337439 1152 46.0400000000 0.3759092689 0.3444009215 0.9291294217 0.0089342211 0.0209830000 212745934 95654136 760807424 0.9752577543 0.0314286128 0.4041675627 1153 46.0800000000 0.3746928573 0.3444271937 0.9291294217 0.0089333679 0.0248100000 212748542 95654136 760807424 0.9722887278 0.0312837921 0.4109618962 1154 46.1200000000 0.3742090762 0.3444530013 0.9291294217 0.0089300174 0.0210460000 212749550 95654136 760807424 0.9708176851 0.0298371501 0.4187345505 1155 46.1600000000 0.3739053607 0.3444785011 0.9291294217 0.0089266212 0.0209290000 212752158 95654136 760807424 0.9707801342 0.0321741700 0.4291596413 1156 46.2000000000 0.3729760349 0.3445031530 0.9291294217 0.0089250356 0.0209170000 212754966 95654136 760807424 0.9738377929 0.0316825509 0.4381931424 1157 46.2400000000 0.3726766407 0.3445275034 0.9291294217 0.0089228275 0.0208980000 212755774 95654136 760807424 0.9753038883 0.0316891074 0.4485201538 1158 46.2800000000 0.3714379072 0.3445507421 0.9291294217 0.0089230187 0.0210600000 212758582 95654136 760807424 0.9753032327 0.0307650063 0.4683685303 1159 46.3200000000 0.3715782762 0.3445740618 0.9291294217 0.0089193217 0.0210070000 212761190 95654136 760807424 0.9776711464 0.0343595520 0.4770987630 1160 46.3600000000 0.3713186383 0.3445971175 0.9291294217 0.0089162317 0.0209830000 212762198 95654136 760807424 0.9748666883 0.0351794437 0.4869823754 1161 46.4000000000 0.3706014156 0.3446195157 0.9291294217 0.0089148915 0.0210190000 212764806 95654136 760807424 0.9771389365 0.0377900191 0.4957558811 1162 46.4400000000 0.3704109192 0.3446417114 0.9291294217 0.0089113013 0.0210010000 212765814 95654136 760807424 0.9768157601 0.0399867371 0.5060657263 1163 46.4800000000 0.3695550561 0.3446631330 0.9291294217 0.0089082817 0.0210600000 212768422 95654136 760807424 0.9768638611 0.0388029218 0.5152400732 1164 46.5200000000 0.3694596589 0.3446844359 0.9291294217 0.0089050769 0.0210770000 212771230 95654136 760807424 0.9761302471 0.0389482751 0.5243769288 1165 46.5600000000 0.3693538606 0.3447056113 0.9291294217 0.0089022084 0.0219490000 212772038 95654136 760807424 0.9773304462 0.0402069986 0.5357746482 1166 46.6000000000 0.3686462343 0.3447261436 0.9291294217 0.0089004775 0.0212640000 212774846 95654136 760807424 0.9746990800 0.0394735374 0.5455386639 1167 46.6400000000 0.3679757416 0.3447460661 0.9291294217 0.0088973930 0.0210900000 212775654 95654136 760807424 0.9727883935 0.0398698822 0.5543080568 1168 46.6800000000 0.3674556911 0.3447655093 0.9291294217 0.0088943519 0.0211310000 212778462 95654136 760807424 0.9737496376 0.0383278430 0.5637697577 1169 46.7200000000 0.3669337630 0.3447844727 0.9291294217 0.0088930408 0.0323670000 212893554 95654136 760807424 0.9714807868 0.0368820280 0.5720561147 1170 46.7600000000 0.3662959039 0.3448028586 0.9291294217 0.0088897356 0.0220140000 212952878 95654136 760807424 0.9702153802 0.0380375423 0.5803116560 1171 46.8000000000 0.3664403260 0.3448213364 0.9291294217 0.0088885403 0.0212160000 212955486 95654136 760807424 0.9703084230 0.0404168852 0.5918476582 1172 46.8400000000 0.3666150272 0.3448399317 0.9291294217 0.0088854418 0.0212280000 212956494 95654136 760807424 0.9684169888 0.0429684296 0.6025376916 1173 46.8800000000 0.3660435677 0.3448580081 0.9291294217 0.0088833240 0.0212870000 212959102 95654136 760807424 0.9672034383 0.0409775898 0.6117697358 1174 46.9200000000 0.3659573793 0.3448759803 0.9291294217 0.0088809020 0.0213110000 212961910 95654136 760807424 0.9671632051 0.0406504795 0.6215902567 1175 46.9600000000 0.3655308485 0.3448935589 0.9291294217 0.0088784363 0.0212560000 212962718 95654136 760807424 0.9636704922 0.0390805230 0.6291824579 1176 47.0000000000 0.3645334542 0.3449102595 0.9291294217 0.0088763053 0.0213060000 212965526 95654136 760807424 0.9596861601 0.0392618850 0.6470240355 1177 47.0400000000 0.3646036983 0.3449269914 0.9291294217 0.0088734144 0.0213940000 212968134 95654136 760807424 0.9600343704 0.0381728336 0.6566592455 1178 47.0800000000 0.3641101718 0.3449432759 0.9291294217 0.0088704715 0.0212630000 212969142 95654136 760807424 0.9583953023 0.0354055129 0.6654546857 1179 47.1200000000 0.3634294569 0.3449589555 0.9291294217 0.0088671809 0.0214520000 212971750 95654136 760807424 0.9564007521 0.0353959389 0.6729733348 1180 47.1600000000 0.3636525571 0.3449747975 0.9291294217 0.0088663046 0.0330120000 212972758 95654136 760807424 0.9551209807 0.0348123014 0.6821458340 1181 47.2000000000 0.3633353710 0.3449903441 0.9291294217 0.0088634528 0.0221610000 212975366 95654136 760807424 0.9495869875 0.0329200476 0.6897594333 1182 47.2400000000 0.3623086214 0.3450049958 0.9291294217 0.0088597470 0.0214430000 212978174 95654136 760807424 0.9432389736 0.0306144301 0.6937214732 1183 47.2800000000 0.3615850508 0.3450190111 0.9291294217 0.0088579439 0.0333710000 212978982 95654136 760807424 0.9426032901 0.0278831124 0.7030970454 1184 47.3200000000 0.3608779907 0.3450324055 0.9291294217 0.0088554663 0.0222640000 212981790 95654136 760807424 0.9458557963 0.0275976136 0.7153535485 1185 47.3600000000 0.3606935740 0.3450456216 0.9291294217 0.0088546681 0.0214750000 212982598 95654136 760807424 0.9450827837 0.0225930363 0.7243003845 1186 47.4000000000 0.3604031503 0.3450585707 0.9291294217 0.0088539399 0.0214320000 212985406 95654136 760807424 0.9428007603 0.0209756959 0.7328007221 1187 47.4400000000 0.3609786332 0.3450719827 0.9291294217 0.0088516098 0.0215040000 212988014 95654136 760807424 0.9403132200 0.0200094003 0.7428974509 1188 47.4800000000 0.3612618148 0.3450856105 0.9291294217 0.0088485396 0.0280310000 212989022 95654136 760807424 0.9352297187 0.0178587604 0.7511342764 1189 47.5200000000 0.3606032729 0.3450986615 0.9291294217 0.0088471387 0.0217910000 212991630 95654136 760807424 0.9331235886 0.0163006168 0.7587462068 1190 47.5600000000 0.3606749177 0.3451117508 0.9291294217 0.0088453238 0.0214970000 212992638 95654136 760807424 0.9318085313 0.0144768003 0.7684255838 1191 47.6000000000 0.3607989550 0.3451249222 0.9291294217 0.0088421013 0.0214890000 212995246 95654136 760807424 0.9309889674 0.0103425905 0.7779629827 1192 47.6400000000 0.3604719043 0.3451377972 0.9291294217 0.0088385506 0.0253260000 212998054 95654136 760807424 0.9361249804 0.0084796194 0.7881762981 1193 47.6800000000 0.3609741926 0.3451510717 0.9291294217 0.0088356321 0.0215320000 212998862 95654136 760807424 0.9373480082 0.0048833629 0.7975441217 1194 47.7200000000 0.3606953919 0.3451640903 0.9291294217 0.0088329315 0.0214610000 213001670 95654136 760807424 0.9343132973 0.0018188537 0.8049876690 1195 47.7600000000 0.3612059653 0.3451775145 0.9291294217 0.0088300613 0.0217360000 213004278 95654136 760807424 0.9361034036 -0.0006991425 0.8156928420 1196 47.8000000000 0.3616313934 0.3451912719 0.9291294217 0.0088275036 0.0214060000 213005286 95654136 760807424 0.9402994514 -0.0017793432 0.8272319436 1197 47.8400000000 0.3617396355 0.3452050968 0.9291294217 0.0088247652 0.0318340000 213007894 95654136 760807424 0.9432936907 -0.0038445035 0.8374747038 1198 47.8800000000 0.3620425165 0.3452191514 0.9291294217 0.0088224012 0.0221820000 213008902 95654136 760807424 0.9448762536 -0.0049338089 0.8481310010 1199 47.9200000000 0.3623374999 0.3452334286 0.9291294217 0.0088209148 0.0215420000 213011510 95654136 760807424 0.9454421997 -0.0065091173 0.8582978249 1200 47.9600000000 0.3617739081 0.3452472123 0.9291294217 0.0088184506 0.0215550000 213014318 95654136 760807424 0.9432605505 -0.0093150325 0.8648738861 1201 48.0000000000 0.3622631133 0.3452613804 0.9291294217 0.0088166152 0.0251690000 213015126 95654136 760807424 0.9465579391 -0.0107900854 0.8762040138 1202 48.0400000000 0.3631771803 0.3452762854 0.9291294217 0.0088153377 0.0253320000 213017934 95654136 760807424 0.9493244290 -0.0123346196 0.8886659741 1203 48.0800000000 0.3633802831 0.3452913345 0.9291294217 0.0088120596 0.0216020000 213018742 95654136 760807424 0.9505949020 -0.0133609753 0.8984702229 1204 48.1200000000 0.3636370897 0.3453065718 0.9291294217 0.0088119377 0.0215190000 213021550 95654136 760807424 0.9517723918 -0.0152528407 0.9083552361 1205 48.1600000000 0.3642206788 0.3453222682 0.9291294217 0.0088087582 0.0215080000 213024158 95654136 760807424 0.9525513649 -0.0158265457 0.9191448689 1206 48.2000000000 0.3644408286 0.3453381210 0.9291294217 0.0088054586 0.0225020000 213025166 95654136 760807424 0.9552264214 -0.0165313538 0.9291260242 1207 48.2400000000 0.3642584383 0.3453537965 0.9291294217 0.0088023055 0.0216630000 213027774 95654136 760807424 0.9568520784 -0.0189402588 0.9374418855 1208 48.2800000000 0.3649326861 0.3453700042 0.9291294217 0.0087990740 0.0216270000 213028782 95654136 760807424 0.9590256214 -0.0214606654 0.9471530914 1209 48.3200000000 0.3657963872 0.3453868995 0.9291294217 0.0087958688 0.0215400000 213031390 95654136 760807424 0.9607093334 -0.0221413132 0.9575254321 1210 48.3600000000 0.3657853901 0.3454037577 0.9291294217 0.0087928256 0.0215720000 213034198 95654136 760807424 0.9587147236 -0.0228497442 0.9657973647 1211 48.4000000000 0.3657342792 0.3454205460 0.9291294217 0.0087894699 0.0215030000 213035006 95654136 760807424 0.9602983594 -0.0254442357 0.9740384817 1212 48.4400000000 0.3664672077 0.3454379112 0.9291294217 0.0087879605 0.0215830000 213150330 95654136 760807424 0.9625595808 -0.0265558790 0.9931218028 1213 48.4800000000 0.3670158684 0.3454557001 0.9291294217 0.0087869030 0.0215150000 213212634 95654136 760807424 0.9606020451 -0.0268954672 1.0008407831 1214 48.5200000000 0.3666833639 0.3454731858 0.9291294217 0.0087847344 0.0282080000 213906530 95654136 760807424 0.9590587020 -0.0275152326 1.0076198578 1215 48.5600000000 0.3667220473 0.3454906746 0.9291294217 0.0087824081 0.0252040000 213376214 95654136 760807424 0.9579232931 -0.0292620342 1.0146427155 1216 48.6000000000 0.3675973415 0.3455088544 0.9291294217 0.0087815988 0.0216390000 213377222 95654136 760807424 0.9568268061 -0.0308480877 1.0293306112 1217 48.6400000000 0.3677561581 0.3455271349 0.9291294217 0.0087787995 0.0216710000 213379830 95654136 760807424 0.9572545290 -0.0312319733 1.0366791487 1218 48.6800000000 0.3685814738 0.3455460629 0.9291294217 0.0087765260 0.0280940000 213915818 95654136 760807424 0.9556789398 -0.0314946584 1.0442814827 1219 48.7200000000 0.3689056933 0.3455652258 0.9291294217 0.0087739153 0.0282210000 213916690 95654136 760807424 0.9556599259 -0.0337622948 1.0501483679 1220 48.7600000000 0.3691490293 0.3455845568 0.9291294217 0.0087712457 0.0286990000 213919562 95654136 760807424 0.9537692666 -0.0337148421 1.0568422079 1221 48.8000000000 0.3701102138 0.3456046434 0.9291294217 0.0087695736 0.0216320000 213387446 95654136 760807424 0.9516271949 -0.0349492654 1.0640075207 1222 48.8400000000 0.3707320094 0.3456252059 0.9291294217 0.0087665074 0.0214960000 213390254 95654136 760807424 0.9478707910 -0.0339166746 1.0708026886 1223 48.8800000000 0.3712341487 0.3456461453 0.9291294217 0.0087631945 0.0215280000 213392862 95654136 760807424 0.9457606077 -0.0354137309 1.0781788826 1224 48.9200000000 0.3716686070 0.3456674055 0.9291294217 0.0087603313 0.0319760000 213393870 95654136 760807424 0.9451166987 -0.0380336232 1.0845785141 1225 48.9600000000 0.3724053502 0.3456892324 0.9291294217 0.0087585373 0.0221890000 213396478 95654136 760807424 0.9435827732 -0.0412058905 1.0919607878 1226 49.0000000000 0.3726660907 0.3457112363 0.9291294217 0.0087560672 0.0216280000 213397486 95654136 760807424 0.9407978058 -0.0428731553 1.0990219116 1227 49.0400000000 0.3732819259 0.3457337063 0.9291294217 0.0087531458 0.0216130000 213400094 95654136 760807424 0.9374520183 -0.0442345068 1.1062434912 1228 49.0800000000 0.3739933074 0.3457567190 0.9291294217 0.0087501221 0.0215780000 213402902 95654136 760807424 0.9344348907 -0.0449615866 1.1139519215 1229 49.1200000000 0.3745652139 0.3457801596 0.9291294217 0.0087480188 0.0215940000 213403710 95654136 760807424 0.9308871627 -0.0460039228 1.1217390299 1230 49.1600000000 0.3748551607 0.3458037979 0.9291294217 0.0087459270 0.0216440000 213406518 95654136 760807424 0.9279245734 -0.0468421653 1.1306014061 1231 49.2000000000 0.3753131926 0.3458277697 0.9291294217 0.0087432130 0.0215170000 213409126 95654136 760807424 0.9260709882 -0.0487996303 1.1379159689 1232 49.2400000000 0.3750874996 0.3458515195 0.9291294217 0.0087408528 0.0215180000 213410134 95654136 760807424 0.9230470061 -0.0490713641 1.1451002359 1233 49.2800000000 0.3751178086 0.3458752554 0.9291294217 0.0087380396 0.0312930000 213412742 95654136 760807424 0.9187383056 -0.0501762368 1.1516400576 1234 49.3200000000 0.3755689263 0.3458993183 0.9291294217 0.0087350463 0.0221980000 213413750 95654136 760807424 0.9123229980 -0.0515917987 1.1590098143 1235 49.3600000000 0.3766908348 0.3459242507 0.9291294217 0.0087333141 0.0216700000 213416358 95654136 760807424 0.9101818800 -0.0541180484 1.1673275232 1236 49.4000000000 0.3778779507 0.3459501032 0.9291294217 0.0087310187 0.0216260000 213419166 95654136 760807424 0.9060599208 -0.0577414967 1.1741591692 1237 49.4400000000 0.3783318102 0.3459762808 0.9291294217 0.0087276637 0.0215940000 213419974 95654136 760807424 0.9030783176 -0.0578402504 1.1829494238 1238 49.4800000000 0.3792254031 0.3460031380 0.9291294217 0.0087249591 0.0216020000 213422782 95654136 760807424 0.8997061253 -0.0603168830 1.1895658970 1239 49.5200000000 0.3795560598 0.3460302186 0.9291294217 0.0087214629 0.0216720000 213534378 95654136 760807424 0.8977991343 -0.0591263250 1.1979050636 1240 49.5600000000 0.3803924918 0.3460579301 0.9291294217 0.0087182443 0.0216970000 213597750 95654136 760807424 0.8963168859 -0.0595508218 1.2068183422 1241 49.6000000000 0.3801900148 0.3460854338 0.9291294217 0.0087148689 0.0216140000 213600358 95654136 760807424 0.8940590024 -0.0581879877 1.2142033577 1242 49.6400000000 0.3802495003 0.3461129411 0.9291294217 0.0087122658 0.0292360000 213601366 95654136 760807424 0.8918875456 -0.0574558526 1.2205958366 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:27:20 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 -nan 0.0096840000 199163396 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644419193 0.0528082997 0.0567135718 0.0606188439 0.0351157971 0.0223210000 200224462 95654128 760807424 -0.0045655631 0.0008366958 0.0132681141 3 1305031229.5966169834 0.0653331280 0.0595867572 0.0653331280 0.0422144915 0.0177740000 200343410 95654128 760807424 -0.0037277893 -0.0090845255 0.0052311923 4 1305031229.6287899017 0.0605287813 0.0598222632 0.0653331280 0.0347633774 0.0224060000 200418038 95654128 760807424 -0.0075347489 -0.0019482886 0.0114561450 5 1305031229.6646571159 0.0655534267 0.0609684959 0.0655534267 0.0318419070 0.0176430000 200519390 95654128 760807424 -0.0100508612 -0.0102995913 0.0129538570 6 1305031229.6968429089 0.0629781112 0.0613034318 0.0655534267 0.0286142100 0.0183080000 200594758 95654128 760807424 -0.0095640086 -0.0070680892 0.0161295999 7 1305031229.7290771008 0.0638986230 0.0616741734 0.0655534267 0.0262460661 0.0176890000 200697266 95654128 760807424 -0.0195601862 -0.0023653363 0.0180688985 8 1305031229.7648689747 0.0690881833 0.0626009246 0.0690881833 0.0248483578 0.0175480000 200773758 95654128 760807424 -0.0228709728 -0.0053766016 0.0157389436 9 1305031229.7969229221 0.0686563402 0.0632737486 0.0690881833 0.0235556644 0.0224080000 200874774 95654128 760807424 -0.0269514453 -0.0028376635 0.0179995336 10 1305031229.8256299496 0.0720498189 0.0641513556 0.0720498189 0.0228874089 0.0181050000 200951810 95654128 760807424 -0.0334938169 -0.0026031616 0.0174616259 11 1305031229.8630619049 0.0723111406 0.0648931543 0.0723111406 0.0228338615 0.0207140000 201053550 95654128 760807424 -0.0362515785 -0.0029515177 0.0189681929 12 1305031229.8969380856 0.0745179430 0.0656952200 0.0745179430 0.0229774888 0.0177140000 201127366 95654128 760807424 -0.0411268435 -0.0009813178 0.0179279298 13 1305031229.9262549877 0.0786447451 0.0666913373 0.0786447451 0.0224337392 0.0177300000 201229010 95654128 760807424 -0.0471249707 -0.0015187289 0.0161589719 14 1305031229.9662408829 0.0816398412 0.0677590876 0.0816398412 0.0220424232 0.0177140000 201304918 95654128 760807424 -0.0512189269 -0.0011159402 0.0140582835 15 1305031229.9979310036 0.0812783316 0.0686603705 0.0816398412 0.0220367690 0.0177380000 201406854 95654128 760807424 -0.0531742573 -0.0002022719 0.0143082850 16 1305031230.0300021172 0.0822319984 0.0695085973 0.0822319984 0.0214887387 0.0175170000 201482606 95654128 760807424 -0.0565183312 -0.0007678441 0.0143904956 17 1305031230.0656960011 0.0837206393 0.0703445997 0.0837206393 0.0210990252 0.0175110000 201486030 95654128 760807424 -0.0602108389 -0.0034927037 0.0143684894 18 1305031230.0982739925 0.0824734047 0.0710184222 0.0837206393 0.0208441283 0.0171900000 201592838 95654128 760807424 -0.0612273961 0.0000563487 0.0137969395 19 1305031230.1299350262 0.0833239034 0.0716660791 0.0837206393 0.0203972546 0.0171240000 201667154 95654128 760807424 -0.0635128021 0.0002523433 0.0130149480 20 1305031230.1657800674 0.0846138671 0.0723134685 0.0846138671 0.0200110420 0.0171160000 201668970 95654128 760807424 -0.0672029927 -0.0001341339 0.0118354857 21 1305031230.1977820396 0.0854652226 0.0729397425 0.0854652226 0.0198119684 0.0199120000 201772246 95654128 760807424 -0.0703029931 0.0005273127 0.0104433028 22 1305031230.2298529148 0.0891938433 0.0736785653 0.0891938433 0.0197080998 0.0172590000 201846566 95654128 760807424 -0.0744336247 -0.0005198308 0.0076455218 23 1305031230.2655899525 0.0912195370 0.0744412162 0.0912195370 0.0193645744 0.0173940000 201947834 95654128 760807424 -0.0777269080 0.0003105876 0.0050249863 24 1305031230.2979929447 0.0897730067 0.0750800408 0.0912195370 0.0191976703 0.0172540000 202121902 95654128 760807424 -0.0796856210 -0.0008329852 0.0064234054 25 1305031230.3351120949 0.0914392173 0.0757344079 0.0914392173 0.0188833365 0.0171260000 202196774 95654128 760807424 -0.0829545408 -0.0027333843 0.0044843247 26 1305031230.3656799793 0.0944559425 0.0764544669 0.0944559425 0.0185232668 0.0172060000 202297998 95654128 760807424 -0.0856526047 0.0005695249 0.0011800469 27 1305031230.3973290920 0.0958260149 0.0771719317 0.0958260149 0.0182814967 0.0173970000 202471754 95654128 760807424 -0.0892104954 -0.0001101376 0.0004328717 28 1305031230.4368140697 0.1018057391 0.0780517105 0.1018057391 0.0188718840 0.0172040000 202546530 95654128 760807424 -0.0948664024 0.0004416229 -0.0054334668 29 1305031230.4653120041 0.1117136702 0.0792124677 0.1117136702 0.0186200933 0.0172790000 202647498 95654128 760807424 -0.1035236046 -0.0006734927 -0.0141668562 30 1305031230.4972999096 0.1186107025 0.0805257422 0.1186107025 0.0184417907 0.0172810000 202822674 95654128 760807424 -0.1108359843 0.0012560776 -0.0204377398 31 1305031230.5301918983 0.1230157912 0.0818963890 0.1230157912 0.0184576269 0.0172750000 202995258 95654128 760807424 -0.1180534735 -0.0018148199 -0.0238245893 32 1305031230.5661149025 0.1257928014 0.0832681519 0.1257928014 0.0186974236 0.0205410000 203169710 95654128 760807424 -0.1242946759 0.0007788371 -0.0274162143 33 1305031230.5988430977 0.1276874095 0.0846141900 0.1276874095 0.0187299824 0.0174790000 203349894 95654128 760807424 -0.1302894801 0.0001941425 -0.0293452740 34 1305031230.6319139004 0.1306208372 0.0859673266 0.1306208372 0.0187101135 0.0171280000 203528430 95654128 760807424 -0.1345897913 0.0016701573 -0.0332094990 35 1305031230.6660470963 0.1278492063 0.0871639518 0.1306208372 0.0185313879 0.0172310000 203702242 95654128 760807424 -0.1380501837 0.0068136305 -0.0324265361 36 1305031230.6979451180 0.1268032342 0.0882650430 0.1306208372 0.0184795776 0.0172620000 203875986 95654128 760807424 -0.1426008195 0.0058866399 -0.0309551861 37 1305031230.7336409092 0.1314955205 0.0894334342 0.1314955205 0.0185937460 0.0170820000 204048254 95654128 760807424 -0.1466516256 0.0059997393 -0.0371842161 38 1305031230.7659239769 0.1358238608 0.0906542349 0.1358238608 0.0184795552 0.0170400000 204221866 95654128 760807424 -0.1518225074 0.0048538623 -0.0420680977 39 1305031230.7973229885 0.1391435117 0.0918975497 0.1391435117 0.0184669118 0.0170610000 204395426 95654128 760807424 -0.1571808457 0.0002100230 -0.0449482314 40 1305031230.8317570686 0.1464312822 0.0932608930 0.1464312822 0.0182464034 0.0169320000 204566934 95654128 760807424 -0.1609620005 0.0020825837 -0.0543875955 41 1305031230.8655419350 0.1492566019 0.0946266420 0.1492566019 0.0183587952 0.0199040000 204740506 95654128 760807424 -0.1659925282 0.0002919346 -0.0588519052 42 1305031230.8973939419 0.1511896998 0.0959733815 0.1511896998 0.0184689820 0.0177570000 204912410 95654128 760807424 -0.1693562865 0.0024073240 -0.0621685237 43 1305031230.9373099804 0.1532309502 0.0973049529 0.1532309502 0.0182785016 0.0170030000 205085638 95654128 760807424 -0.1710536033 0.0065454347 -0.0666525736 44 1305031230.9650349617 0.1546134204 0.0986074180 0.1546134204 0.0183631489 0.0168650000 205157650 95654128 760807424 -0.1688311696 0.0088189002 -0.0703753680 45 1305031230.9971239567 0.1564156562 0.0998920456 0.1564156562 0.0182173637 0.0167820000 205260438 95654128 760807424 -0.1676122695 0.0109349526 -0.0732584745 46 1305031231.0367500782 0.1553895473 0.1010985130 0.1564156562 0.0181885900 0.0167400000 205332798 95654128 760807424 -0.1714880764 0.0151934763 -0.0704044402 47 1305031231.0644741058 0.1584108025 0.1023179234 0.1584108025 0.0180236631 0.0166970000 205336118 95654128 760807424 -0.1711482555 0.0153655373 -0.0731832460 48 1305031231.0967879295 0.1591439694 0.1035017994 0.1591439694 0.0179141472 0.0162360000 205337862 95654128 760807424 -0.1675556451 0.0165818334 -0.0743616521 49 1305031231.1347110271 0.1614716053 0.1046848566 0.1614716053 0.0178077898 0.0162120000 205341646 95654128 760807424 -0.1731552333 0.0176532157 -0.0730210245 50 1305031231.1652760506 0.1688900143 0.1059689598 0.1688900143 0.0176924943 0.0163000000 205345134 95654128 760807424 -0.1705169529 0.0158286858 -0.0804391354 51 1305031231.1977710724 0.1694810838 0.1072142955 0.1694810838 0.0176005898 0.0195690000 205346878 95654128 760807424 -0.1642910242 0.0242815334 -0.0811351463 52 1305031231.2344679832 0.1450424343 0.1079417598 0.1694810838 0.0179161749 0.0166650000 205451446 95654128 760807424 -0.1491274685 0.0331286751 -0.0560367554 53 1305031231.2656350136 0.1611842960 0.1089463359 0.1694810838 0.0192514717 0.0169900000 205623226 95654128 760807424 -0.1306501031 0.0320731997 -0.0737917200 54 1305031231.2978610992 0.1715931892 0.1101064628 0.1715931892 0.0197118176 0.0169570000 205796374 95654128 760807424 -0.1238354743 0.0311225746 -0.0819179192 55 1305031231.3351519108 0.1683415174 0.1111652820 0.1715931892 0.0196742287 0.0170910000 205970118 95654128 760807424 -0.1171960533 0.0319621116 -0.0751253441 56 1305031231.3650770187 0.1618041843 0.1120695481 0.1715931892 0.0197155641 0.0170950000 206141954 95654128 760807424 -0.1133913249 0.0304207820 -0.0661230013 57 1305031231.3973300457 0.1591589153 0.1128956774 0.1715931892 0.0197798647 0.0170730000 206214790 95654128 760807424 -0.1092272475 0.0308998022 -0.0611308180 58 1305031231.4368579388 0.1570376754 0.1136567463 0.1715931892 0.0196875142 0.0228620000 206319902 95654128 760807424 -0.1062889770 0.0362195335 -0.0562313758 59 1305031231.4649889469 0.1530068219 0.1143236967 0.1715931892 0.0196057110 0.0178180000 206492306 95654128 760807424 -0.1032403484 0.0372322053 -0.0503164828 60 1305031231.4992439747 0.1498552114 0.1149158886 0.1715931892 0.0195308862 0.0173820000 206666910 95654128 760807424 -0.0993922278 0.0358344428 -0.0456987321 61 1305031231.5331959724 0.1477129161 0.1154535448 0.1715931892 0.0195303353 0.0184230000 206841534 95654128 760807424 -0.0961652249 0.0374407768 -0.0421323553 62 1305031231.5650680065 0.1458637863 0.1159440326 0.1715931892 0.0194582604 0.0180500000 207013842 95654128 760807424 -0.0912100747 0.0394563191 -0.0393129662 63 1305031231.6013169289 0.1414303631 0.1163485775 0.1715931892 0.0193480429 0.0179160000 207188186 95654128 760807424 -0.0895478427 0.0399996787 -0.0337766260 64 1305031231.6331589222 0.1383980215 0.1166931001 0.1715931892 0.0192550283 0.0178480000 207261054 95654128 760807424 -0.0865673795 0.0410190821 -0.0295427553 65 1305031231.6650550365 0.1353158057 0.1169796032 0.1715931892 0.0191719152 0.0180590000 207375786 95654128 760807424 -0.0817468539 0.0424351953 -0.0264183506 66 1305031231.7035079002 0.1329728216 0.1172219247 0.1715931892 0.0191904962 0.0177950000 207455562 95654128 760807424 -0.0797254294 0.0461671129 -0.0231717322 67 1305031231.7339379787 0.1277612746 0.1173792285 0.1715931892 0.0192610857 0.0180620000 207565502 95654128 760807424 -0.0758024976 0.0500042103 -0.0177693479 68 1305031231.7655088902 0.1203122810 0.1174223616 0.1715931892 0.0192392908 0.0179680000 207739798 95654128 760807424 -0.0710581392 0.0542810000 -0.0100752814 69 1305031231.8011910915 0.1163161471 0.1174063295 0.1715931892 0.0192837288 0.0234100000 207914902 95654128 760807424 -0.0662168264 0.0555635802 -0.0059449635 70 1305031231.8332920074 0.1120011210 0.1173291122 0.1715931892 0.0193548926 0.0185240000 208087674 95654128 760807424 -0.0633271635 0.0556771271 -0.0012491192 71 1305031231.8649590015 0.1087999493 0.1172089832 0.1715931892 0.0195245042 0.0178980000 208262478 95654128 760807424 -0.0593626313 0.0560269579 0.0015797326 72 1305031231.9012699127 0.1104488969 0.1171150931 0.1715931892 0.0198899831 0.0210890000 208436578 95654128 760807424 -0.0587269217 0.0565083176 -0.0002060258 73 1305031231.9330461025 0.1089775935 0.1170036205 0.1715931892 0.0199379075 0.0209430000 208501962 95654128 760807424 -0.0573344454 0.0545446239 0.0009561201 74 1305031231.9650299549 0.1087275073 0.1168917811 0.1715931892 0.0198775688 0.0181920000 208612810 95654128 760807424 -0.0534330159 0.0547486842 0.0001321817 75 1305031232.0007200241 0.1096923575 0.1167957888 0.1715931892 0.0199324986 0.0178820000 208679974 95654128 760807424 -0.0542950928 0.0548421852 -0.0013283468 76 1305031232.0332028866 0.1067183167 0.1166631905 0.1715931892 0.0199850899 0.0178730000 208681750 95654128 760807424 -0.0491712838 0.0550622568 0.0001446094 77 1305031232.0651450157 0.1040705070 0.1164996491 0.1715931892 0.0200164822 0.0178760000 208791846 95654128 760807424 -0.0443465747 0.0566405468 0.0012428465 78 1305031232.1007990837 0.1026389077 0.1163219473 0.1715931892 0.0200137450 0.0178650000 208857310 95654128 760807424 -0.0437515192 0.0562376045 0.0017900199 79 1305031232.1328380108 0.1013654396 0.1161326244 0.1715931892 0.0199805018 0.0262160000 208967790 95654128 760807424 -0.0421178862 0.0554227233 0.0018518387 80 1305031232.1650519371 0.1010570750 0.1159441801 0.1715931892 0.0198833602 0.0185340000 209034954 95654128 760807424 -0.0391279832 0.0567798764 0.0007877860 81 1305031232.1992239952 0.1013047323 0.1157634462 0.1715931892 0.0198820755 0.0178310000 209036914 95654128 760807424 -0.0344054289 0.0592498295 -0.0008567303 82 1305031232.2364680767 0.0983265713 0.1155508013 0.1715931892 0.0197752672 0.0176810000 209147966 95654128 760807424 -0.0322775245 0.0588287711 0.0004569025 83 1305031232.2626979351 0.0986657962 0.1153473675 0.1715931892 0.0200071229 0.0174630000 209215118 95654128 760807424 -0.0287051573 0.0595713221 -0.0010433769 84 1305031232.2980248928 0.0982606933 0.1151439548 0.1715931892 0.0200818923 0.0173990000 209323870 95654128 760807424 -0.0274315048 0.0623197258 -0.0019078675 85 1305031232.3321430683 0.0977272540 0.1149390524 0.1715931892 0.0201012903 0.0172760000 209391514 95654128 760807424 -0.0290986206 0.0620458573 -0.0017978980 86 1305031232.3647489548 0.0994196758 0.1147585945 0.1715931892 0.0200753840 0.0173670000 209502106 95654128 760807424 -0.0285912789 0.0660754964 -0.0041810907 87 1305031232.4008779526 0.1003273502 0.1145927182 0.1715931892 0.0200269055 0.0172590000 209567914 95654128 760807424 -0.0284524038 0.0677205995 -0.0054328502 88 1305031232.4331440926 0.0998862833 0.1144255996 0.1715931892 0.0199289468 0.0171730000 209571474 95654128 760807424 -0.0282044206 0.0688477606 -0.0057015563 89 1305031232.4647209644 0.0993633345 0.1142563606 0.1715931892 0.0198271551 0.0172340000 209573266 95654128 760807424 -0.0274662841 0.0685941577 -0.0060182349 90 1305031232.5015261173 0.0998810530 0.1140966350 0.1715931892 0.0197270795 0.0172540000 209683238 95654128 760807424 -0.0259875469 0.0670270100 -0.0082318122 91 1305031232.5324640274 0.1001582891 0.1139434664 0.1715931892 0.0196429082 0.0171970000 209750826 95654128 760807424 -0.0239572711 0.0669322535 -0.0095042912 92 1305031232.5647449493 0.0993506387 0.1137848487 0.1715931892 0.0195466824 0.0172680000 209858954 95654128 760807424 -0.0244309567 0.0656285137 -0.0102242250 93 1305031232.6003499031 0.1009068117 0.1136463752 0.1715931892 0.0194453032 0.0172050000 209926866 95654128 760807424 -0.0204179231 0.0649824142 -0.0134827551 94 1305031232.6294269562 0.1012023911 0.1135139923 0.1715931892 0.0194094199 0.0172210000 210036838 95654128 760807424 -0.0170665868 0.0646035597 -0.0157564264 95 1305031232.6647078991 0.0986427590 0.1133574530 0.1715931892 0.0193204557 0.0179420000 210102930 95654128 760807424 -0.0203072689 0.0633273944 -0.0149320140 96 1305031232.7005090714 0.1017769352 0.1132368227 0.1715931892 0.0192502937 0.0173440000 210212702 95654128 760807424 -0.0177514907 0.0646005720 -0.0187961627 97 1305031232.7327980995 0.1047700867 0.1131495367 0.1715931892 0.0192195709 0.0172390000 210280678 95654128 760807424 -0.0148050962 0.0652533695 -0.0232413709 98 1305031232.7684600353 0.1032400504 0.1130484195 0.1715931892 0.0191517718 0.0172230000 210388482 95654128 760807424 -0.0160339940 0.0654081926 -0.0234580562 99 1305031232.8045380116 0.1024845764 0.1129417140 0.1715931892 0.0191292452 0.0171570000 210456454 95654128 760807424 -0.0174085442 0.0655298680 -0.0249129385 100 1305031232.8346450329 0.1067888066 0.1128801849 0.1715931892 0.0191129000 0.0171900000 210459886 95654128 760807424 -0.0157605316 0.0674493313 -0.0306162052 101 1305031232.8685569763 0.1070434377 0.1128223954 0.1715931892 0.0191236464 0.0172220000 210567978 95654128 760807424 -0.0166610032 0.0680957884 -0.0325131565 102 1305031232.9041829109 0.1076269895 0.1127714600 0.1715931892 0.0190633886 0.0172490000 210635978 95654128 760807424 -0.0156831257 0.0732415766 -0.0337225571 103 1305031232.9330000877 0.1098459587 0.1127430571 0.1715931892 0.0189906172 0.0171310000 210637570 95654128 760807424 -0.0140964482 0.0769186839 -0.0355663262 104 1305031232.9683640003 0.1106082946 0.1127225305 0.1715931892 0.0189002512 0.0268700000 210641210 95654128 760807424 -0.0125836758 0.0778536722 -0.0379199237 105 1305031233.0011510849 0.1174763739 0.1127678052 0.1715931892 0.0188279559 0.0183740000 210644898 95654128 760807424 -0.0106840860 0.0855580568 -0.0427151658 106 1305031233.0330219269 0.1160614341 0.1127988772 0.1715931892 0.0187732721 0.0169910000 210646618 95654128 760807424 -0.0101860575 0.0924279839 -0.0380058140 107 1305031233.0688428879 0.1190044358 0.1128568731 0.1715931892 0.0187811237 0.0173290000 210650122 95654128 760807424 -0.0104825534 0.0933396444 -0.0411249511 108 1305031233.1004469395 0.1228319183 0.1129492346 0.1715931892 0.0187666628 0.0175700000 210653602 95654128 760807424 -0.0152254868 0.1001080871 -0.0409884900 109 1305031233.1328918934 0.1247068942 0.1130571030 0.1715931892 0.0197803806 0.0207830000 210655506 95654128 760807424 -0.0112679936 0.0901258811 -0.0480133593 110 1305031233.1684799194 0.1299788356 0.1132109370 0.1715931892 0.0198606099 0.0181370000 210659122 95654128 760807424 -0.0076914253 0.0873251557 -0.0534144603 111 1305031233.2006340027 0.1293099970 0.1133559736 0.1715931892 0.0198929449 0.0179840000 210662626 95654128 760807424 -0.0100455331 0.0872745290 -0.0513572507 112 1305031233.2330091000 0.1237103343 0.1134484232 0.1715931892 0.0198829821 0.0182410000 210664298 95654128 760807424 -0.0188439675 0.0939231813 -0.0411542431 113 1305031233.2684679031 0.1234279126 0.1135367373 0.1715931892 0.0201092751 0.0178750000 210668146 95654128 760807424 -0.0271518826 0.0990750194 -0.0351820625 114 1305031233.3003950119 0.1265169531 0.1136505988 0.1715931892 0.0200350955 0.0180130000 210669882 95654128 760807424 -0.0355143845 0.1006996334 -0.0353633277 115 1305031233.3325300217 0.1197199896 0.1137033761 0.1715931892 0.0204695111 0.0219560000 210673450 95654128 760807424 -0.0445759818 0.1003983989 -0.0246158522 116 1305031233.3686299324 0.1235478595 0.1137882424 0.1715931892 0.0206553095 0.0217100000 210676986 95654128 760807424 -0.0461889580 0.0926603302 -0.0291029625 117 1305031233.4008929729 0.1260004640 0.1138926203 0.1715931892 0.0206834198 0.0183980000 210678978 95654128 760807424 -0.0565288700 0.0949889868 -0.0279497206 118 1305031233.4330079556 0.1304723918 0.1140331269 0.1715931892 0.0209233979 0.0182160000 210682586 95654128 760807424 -0.0736677349 0.0939856470 -0.0290007219 119 1305031233.4687869549 0.1328546107 0.1141912906 0.1715931892 0.0209988966 0.0216790000 210686106 95654128 760807424 -0.0715447366 0.0926551446 -0.0304255113 120 1305031233.5007359982 0.1322153509 0.1143414911 0.1715931892 0.0209647966 0.0185630000 210687882 95654128 760807424 -0.0724946856 0.0939633176 -0.0279139299 121 1305031233.5341610909 0.1369474530 0.1145283172 0.1715931892 0.0210478767 0.0183780000 210797202 95654128 760807424 -0.0808875412 0.0926504284 -0.0305990558 122 1305031233.5697269440 0.1428309381 0.1147603059 0.1715931892 0.0209842079 0.0184460000 210865878 95654128 760807424 -0.0897635147 0.0938789248 -0.0337721817 123 1305031233.6012749672 0.1470938325 0.1150231801 0.1715931892 0.0209248071 0.0182520000 210867582 95654128 760807424 -0.1010528281 0.0929857716 -0.0351485237 124 1305031233.6330409050 0.1519981176 0.1153213651 0.1715931892 0.0209439128 0.0182440000 210871118 95654128 760807424 -0.1058907956 0.0938954130 -0.0390379615 125 1305031233.6717829704 0.1563360393 0.1156494825 0.1715931892 0.0208601166 0.0183430000 210873246 95654128 760807424 -0.1086766571 0.0969288051 -0.0422415026 126 1305031233.7022960186 0.1521071941 0.1159388294 0.1715931892 0.0209992982 0.0282280000 210876750 95654128 760807424 -0.1077598929 0.0973317251 -0.0378772765 127 1305031233.7312009335 0.1479365379 0.1161907799 0.1715931892 0.0210923812 0.0306240000 210880142 95654128 760807424 -0.1014118418 0.1039489806 -0.0324536636 128 1305031233.7691600323 0.1449342668 0.1164153384 0.1715931892 0.0211100749 0.0217550000 210881958 95654128 760807424 -0.0966453701 0.1075188965 -0.0287325755 129 1305031233.7997679710 0.1450497657 0.1166373107 0.1715931892 0.0210751087 0.0186160000 210896838 95654128 760807424 -0.0966722518 0.1066184938 -0.0289688110 130 1305031233.8338310719 0.1446672380 0.1168529255 0.1715931892 0.0210549335 0.0186750000 210925998 95654128 760807424 -0.1003023908 0.0990687162 -0.0309710037 131 1305031233.8655700684 0.1494330764 0.1171016289 0.1715931892 0.0210229855 0.0184300000 211045758 95654128 760807424 -0.1013718396 0.0996628180 -0.0355425775 132 1305031233.8986968994 0.1483626813 0.1173384551 0.1715931892 0.0209506544 0.0285330000 211102494 95654128 760807424 -0.1017956734 0.0983751714 -0.0346661955 133 1305031233.9320030212 0.1430432200 0.1175317240 0.1715931892 0.0209220532 0.0196490000 211106166 95654128 760807424 -0.0992840752 0.0958194360 -0.0302242972 134 1305031233.9681589603 0.1402920783 0.1177015774 0.1715931892 0.0208573873 0.0184440000 211107934 95654128 760807424 -0.0961382166 0.0963752791 -0.0277364962 135 1305031233.9989380836 0.1342626363 0.1178242519 0.1715931892 0.0208076145 0.0184020000 211111406 95654128 760807424 -0.0926437750 0.0903065801 -0.0238351915 136 1305031234.0370678902 0.1360904127 0.1179585619 0.1715931892 0.0207429229 0.0183770000 211115062 95654128 760807424 -0.0905496776 0.0946573988 -0.0245508999 137 1305031234.0687561035 0.1349606812 0.1180826650 0.1715931892 0.0206745107 0.0183320000 211116894 95654128 760807424 -0.0895600468 0.0939664990 -0.0237334725 138 1305031234.0997409821 0.1366474479 0.1182171924 0.1715931892 0.0206139552 0.0183360000 211120366 95654128 760807424 -0.0899542123 0.0926423743 -0.0255492572 139 1305031234.1350688934 0.1366694868 0.1183499427 0.1715931892 0.0205495795 0.0183590000 211239678 95654128 760807424 -0.0891165808 0.0908148214 -0.0256005153 140 1305031234.1659009457 0.1396798640 0.1185022993 0.1715931892 0.0205544679 0.0191050000 211296562 95654128 760807424 -0.0888882801 0.0962821767 -0.0264100917 141 1305031234.2010040283 0.1369878948 0.1186334028 0.1715931892 0.0205397146 0.0184310000 211300338 95654128 760807424 -0.0882552117 0.0872720480 -0.0257292688 142 1305031234.2385749817 0.1378855705 0.1187689814 0.1715931892 0.0204960423 0.0184610000 211420106 95654128 760807424 -0.0877045840 0.0915876478 -0.0244591497 143 1305031234.2655100822 0.1396942884 0.1189153123 0.1715931892 0.0204359651 0.0184740000 211476866 95654128 760807424 -0.0881448016 0.0958002657 -0.0235023871 144 1305031234.3024549484 0.1359851956 0.1190338531 0.1715931892 0.0203700010 0.0183730000 211597550 95654128 760807424 -0.0867240503 0.0889073759 -0.0216106176 145 1305031234.3384580612 0.1357742846 0.1191493044 0.1715931892 0.0203072987 0.0183420000 211653146 95654128 760807424 -0.0864247829 0.0875040665 -0.0207369085 146 1305031234.3661808968 0.1366876662 0.1192694301 0.1715931892 0.0202804239 0.0183560000 211773866 95654128 760807424 -0.0867606625 0.0900768414 -0.0203819647 147 1305031234.4000349045 0.1352602541 0.1193782112 0.1715931892 0.0202138486 0.0183210000 211831058 95654128 760807424 -0.0861795023 0.0870008022 -0.0194067005 148 1305031234.4367709160 0.1309915930 0.1194566800 0.1715931892 0.0201991426 0.0218170000 211949150 95654128 760807424 -0.0835205168 0.0793324262 -0.0176818501 149 1305031234.4676060677 0.1324435174 0.1195438400 0.1715931892 0.0201844037 0.0185270000 212006530 95654128 760807424 -0.0834360793 0.0827282816 -0.0179067999 150 1305031234.4977810383 0.1305918992 0.1196174937 0.1715931892 0.0201228120 0.0183590000 212125602 95654128 760807424 -0.0819704458 0.0806420073 -0.0170582701 151 1305031234.5376710892 0.1307289600 0.1196910796 0.1715931892 0.0201953125 0.0183360000 212300562 95654128 760807424 -0.0792144388 0.0694827288 -0.0216854680 152 1305031234.5690369606 0.1334338933 0.1197814929 0.1715931892 0.0203367879 0.0211680000 212474562 95654128 760807424 -0.0815909281 0.0763840675 -0.0228512492 153 1305031234.5982480049 0.1328811944 0.1198671118 0.1715931892 0.0203018060 0.0182400000 212647366 95654128 760807424 -0.0800697356 0.0728718266 -0.0245555378 154 1305031234.6336491108 0.1325404644 0.1199494063 0.1715931892 0.0202473593 0.0282510000 212821626 95654128 760807424 -0.0790628344 0.0723912567 -0.0258793999 155 1305031234.6658589840 0.1333068460 0.1200355834 0.1715931892 0.0202694924 0.0191910000 212994970 95654128 760807424 -0.0792912319 0.0741584003 -0.0271777306 156 1305031234.6987318993 0.1347839087 0.1201301239 0.1715931892 0.0202143008 0.0218810000 213050678 95654128 760807424 -0.0786219537 0.0744417012 -0.0289531350 157 1305031234.7344369888 0.1354466081 0.1202276811 0.1715931892 0.0201540968 0.0179610000 213170234 95654128 760807424 -0.0782477483 0.0747174174 -0.0311781298 158 1305031234.7689719200 0.1366267651 0.1203314728 0.1715931892 0.0201046939 0.0173860000 213227866 95654128 760807424 -0.0767076015 0.0709959865 -0.0349026248 159 1305031234.8015530109 0.1394581199 0.1204517662 0.1715931892 0.0202502471 0.0171680000 213345246 95654128 760807424 -0.0812157914 0.0804961696 -0.0343784727 160 1305031234.8378078938 0.1358174682 0.1205478018 0.1715931892 0.0201903957 0.0170210000 213403002 95654128 760807424 -0.0772710070 0.0761143714 -0.0339438692 161 1305031234.8693211079 0.1404468119 0.1206713982 0.1715931892 0.0201689566 0.0170190000 213520702 95654128 760807424 -0.0806184337 0.0812736079 -0.0364273489 162 1305031234.9019980431 0.1420992464 0.1208036688 0.1715931892 0.0201150963 0.0170240000 213578414 95654128 760807424 -0.0808489993 0.0848541930 -0.0361887701 163 1305031234.9381608963 0.1471464336 0.1209652809 0.1715931892 0.0201300078 0.0169940000 213582030 95654128 760807424 -0.0838827118 0.0951384157 -0.0341169089 164 1305031234.9730799198 0.1511882544 0.1211495673 0.1715931892 0.0200933562 0.0251670000 213583846 95654128 760807424 -0.0867589265 0.0933085904 -0.0357150473 165 1305031235.0050830841 0.1513306350 0.1213324829 0.1715931892 0.0201188335 0.0180280000 213587494 95654128 760807424 -0.0917412713 0.1005544588 -0.0273519065 166 1305031235.0399720669 0.1507551372 0.1215097278 0.1715931892 0.0200734081 0.0175770000 213591110 95654128 760807424 -0.0917705894 0.0963499397 -0.0254227873 167 1305031235.0729401112 0.1515170485 0.1216894123 0.1715931892 0.0200275513 0.0176090000 213592814 95654128 760807424 -0.0965978578 0.1025449410 -0.0183940008 168 1305031235.0995910168 0.1479203552 0.1218455489 0.1715931892 0.0199715666 0.0177190000 213596174 95654128 760807424 -0.0958170891 0.1004414484 -0.0136078671 169 1305031235.1362709999 0.1478616446 0.1219994903 0.1715931892 0.0199859004 0.0177370000 213599990 95654128 760807424 -0.0939564258 0.0944851264 -0.0141903944 170 1305031235.1663711071 0.1498132050 0.1221631004 0.1715931892 0.0199957117 0.0178690000 213717354 95654128 760807424 -0.1006711125 0.1070496291 -0.0051602283 171 1305031235.1998469830 0.1460236609 0.1223026358 0.1715931892 0.0199878896 0.0179900000 213775246 95654128 760807424 -0.0987542793 0.1049506739 -0.0005344241 172 1305031235.2375700474 0.1483328491 0.1224539743 0.1715931892 0.0199961920 0.0180660000 213778902 95654128 760807424 -0.1009685025 0.1068752334 0.0001745173 173 1305031235.2690389156 0.1475159973 0.1225988414 0.1715931892 0.0199547212 0.0181640000 213780806 95654128 760807424 -0.1022353545 0.1093568727 0.0044343523 174 1305031235.3064870834 0.1486983150 0.1227488384 0.1715931892 0.0199445224 0.0230570000 213784478 95654128 760807424 -0.1040505022 0.1164225489 0.0091906786 175 1305031235.3380000591 0.1494306624 0.1229013060 0.1715931892 0.0199238545 0.0190020000 213786142 95654128 760807424 -0.1052339673 0.1184665784 0.0114891957 176 1305031235.3698880672 0.1476238221 0.1230417748 0.1715931892 0.0199891591 0.0185990000 213789646 95654128 760807424 -0.1038053930 0.1134241670 0.0115481699 177 1305031235.4060161114 0.1536319703 0.1232146008 0.1715931892 0.0200462092 0.0187170000 213793462 95654128 760807424 -0.1072926298 0.1217479557 0.0121768452 178 1305031235.4381530285 0.1516833007 0.1233745373 0.1715931892 0.0200258681 0.0189180000 213795198 95654128 760807424 -0.1076283455 0.1211053953 0.0155046163 179 1305031235.4700589180 0.1510245949 0.1235290069 0.1715931892 0.0200212166 0.0190680000 213798702 95654128 760807424 -0.1068849340 0.1183787733 0.0156425517 180 1305031235.5059850216 0.1533786505 0.1236948383 0.1715931892 0.0200035055 0.0190260000 213802334 95654128 760807424 -0.1077156067 0.1198546365 0.0161324497 181 1305031235.5385539532 0.1532928348 0.1238583631 0.1715931892 0.0199780697 0.0190290000 213804238 95654128 760807424 -0.1081478745 0.1219189912 0.0180567354 182 1305031235.5703649521 0.1535070240 0.1240212678 0.1715931892 0.0199360118 0.0192550000 213807742 95654128 760807424 -0.1087619439 0.1231476068 0.0198177677 183 1305031235.6060059071 0.1543189287 0.1241868288 0.1715931892 0.0198919106 0.0190950000 213811430 95654128 760807424 -0.1092387363 0.1263111234 0.0219365880 184 1305031235.6389510632 0.1531922221 0.1243444668 0.1715931892 0.0198957049 0.0191430000 213813134 95654128 760807424 -0.1095235422 0.1236660704 0.0234338567 185 1305031235.6705160141 0.1557861120 0.1245144217 0.1715931892 0.0198934645 0.0190780000 213816798 95654128 760807424 -0.1115826890 0.1256259531 0.0232505091 186 1305031235.7057778835 0.1579060256 0.1246939464 0.1715931892 0.0198543513 0.0191350000 213934602 95654128 760807424 -0.1141554713 0.1267493069 0.0242316965 187 1305031235.7387969494 0.1580069512 0.1248720908 0.1715931892 0.0198517973 0.0190640000 214109942 95654128 760807424 -0.1168455109 0.1279747933 0.0271423254 188 1305031235.7696299553 0.1599228084 0.1250585308 0.1715931892 0.0198230953 0.0222350000 214168418 95654128 760807424 -0.1193928421 0.1330458075 0.0285700988 189 1305031235.8072249889 0.1609407514 0.1252483838 0.1715931892 0.0197964621 0.0191570000 214286666 95654128 760807424 -0.1213226095 0.1320649981 0.0290337075 190 1305031235.8388121128 0.1575934887 0.1254186212 0.1715931892 0.0200133700 0.0194380000 214345250 95654128 760807424 -0.1228684410 0.1172821894 0.0323189199 191 1305031235.8700668812 0.1548734158 0.1255728348 0.1715931892 0.0201729955 0.0191600000 214465178 95654128 760807424 -0.1229872033 0.1091261655 0.0368580930 192 1305031235.9061110020 0.1536664665 0.1257191558 0.1715931892 0.0201882802 0.0187090000 214522182 95654128 760807424 -0.1232916564 0.1020710692 0.0405189022 193 1305031235.9382328987 0.1530872583 0.1258609594 0.1715931892 0.0201997297 0.0188210000 214641954 95654128 760807424 -0.1243539229 0.0956253707 0.0439849347 194 1305031235.9700109959 0.1527602673 0.1259996157 0.1715931892 0.0202078978 0.0186790000 214700658 95654128 760807424 -0.1252541244 0.0961758941 0.0461397544 195 1305031236.0068531036 0.1540157497 0.1261432882 0.1715931892 0.0201991528 0.0187440000 214702586 95654128 760807424 -0.1281621903 0.0923628733 0.0494677350 196 1305031236.0380480289 0.1530103087 0.1262803648 0.1715931892 0.0202303473 0.0186890000 214822030 95654128 760807424 -0.1279403716 0.0867850631 0.0543200672 197 1305031236.0698781013 0.1528862566 0.1264154201 0.1715931892 0.0203820744 0.0188050000 214879290 95654128 760807424 -0.1289862841 0.0840196833 0.0580709726 198 1305031236.1058719158 0.1535517871 0.1265524724 0.1715931892 0.0203314552 0.0185790000 214882962 95654128 760807424 -0.1302078664 0.0853815377 0.0594731160 199 1305031236.1383249760 0.1531455964 0.1266861062 0.1715931892 0.0202932369 0.0185680000 214886578 95654128 760807424 -0.1309885234 0.0863442495 0.0616653040 200 1305031236.1709330082 0.1534069031 0.1268197102 0.1715931892 0.0202485566 0.0185000000 214888322 95654128 760807424 -0.1313425153 0.0852499604 0.0639867112 201 1305031236.2071900368 0.1513955444 0.1269419780 0.1715931892 0.0202342023 0.0185000000 214892234 95654128 760807424 -0.1307878941 0.0874027312 0.0665692687 202 1305031236.2383749485 0.1505044103 0.1270586237 0.1715931892 0.0202306716 0.0184630000 214895794 95654128 760807424 -0.1325172335 0.0864095613 0.0706501603 203 1305031236.2699589729 0.1520382911 0.1271816763 0.1715931892 0.0201878377 0.0185640000 215013418 95654128 760807424 -0.1337916553 0.0864468664 0.0692090094 204 1305031236.3069939613 0.1534574777 0.1273104792 0.1715931892 0.0201688074 0.0184790000 215072674 95654128 760807424 -0.1348505467 0.0847371593 0.0680364668 205 1305031236.3392169476 0.1508458853 0.1274252861 0.1715931892 0.0201283042 0.0186750000 215076418 95654128 760807424 -0.1321768165 0.0854979083 0.0664808676 206 1305031236.3700959682 0.1506314725 0.1275379375 0.1715931892 0.0200855090 0.0186560000 215078122 95654128 760807424 -0.1305339634 0.0855801031 0.0623301826 207 1305031236.4058690071 0.1485443413 0.1276394177 0.1715931892 0.0200456327 0.0190460000 215081762 95654128 760807424 -0.1286188960 0.0844020173 0.0601155534 208 1305031236.4387879372 0.1484128386 0.1277392899 0.1715931892 0.0200137901 0.0192120000 215085322 95654128 760807424 -0.1272923648 0.0835908949 0.0562981479 209 1305031236.4751410484 0.1435201913 0.1278147966 0.1715931892 0.0199841089 0.0189390000 215087434 95654128 760807424 -0.1236223578 0.0817351118 0.0554750599 210 1305031236.5077209473 0.1411075294 0.1278780954 0.1715931892 0.0199559054 0.0190030000 215091050 95654128 760807424 -0.1203630194 0.0807716250 0.0521917120 211 1305031236.5386450291 0.1387052834 0.1279294090 0.1715931892 0.0200093009 0.0190830000 215092738 95654128 760807424 -0.1177719831 0.0804698169 0.0492782593 212 1305031236.5740950108 0.1327473223 0.1279521350 0.1715931892 0.0199969267 0.0192370000 215096410 95654128 760807424 -0.1123082563 0.0827005953 0.0460605808 213 1305031236.6057569981 0.1312684864 0.1279677048 0.1715931892 0.0200158970 0.0192390000 215100130 95654128 760807424 -0.1108478308 0.0840157419 0.0417693108 214 1305031236.6384010315 0.1299857646 0.1279771350 0.1715931892 0.0200314246 0.0193590000 215101890 95654128 760807424 -0.1073796079 0.0830238089 0.0369001776 215 1305031236.6751470566 0.1292880923 0.1279832324 0.1715931892 0.0199929988 0.0194830000 215105506 95654128 760807424 -0.1061923653 0.0847074538 0.0313693136 216 1305031236.7033619881 0.1280225068 0.1279834143 0.1715931892 0.0199916621 0.0197220000 215223914 95654128 760807424 -0.1048392355 0.0882607400 0.0275613293 217 1305031236.7339220047 0.1298743933 0.1279921284 0.1715931892 0.0200355095 0.0195040000 215281710 95654128 760807424 -0.1037010625 0.0872411504 0.0204377826 218 1305031236.7740409374 0.1291880310 0.1279976142 0.1715931892 0.0199899921 0.0195500000 215285438 95654128 760807424 -0.1037122831 0.0923475325 0.0161756463 219 1305031236.8025879860 0.1325693876 0.1280184899 0.1715931892 0.0201582703 0.0197760000 215288974 95654128 760807424 -0.1028109491 0.0877408013 0.0085137933 220 1305031236.8364150524 0.1308482140 0.1280313523 0.1715931892 0.0201148997 0.0197380000 215290678 95654128 760807424 -0.1002213210 0.0839155465 0.0030144942 221 1305031236.8743979931 0.1304088384 0.1280421102 0.1715931892 0.0200762752 0.0195900000 215294566 95654128 760807424 -0.0978394300 0.0820731074 -0.0037997165 222 1305031236.9060690403 0.1331823468 0.1280652644 0.1715931892 0.0201079552 0.0197490000 215296270 95654128 760807424 -0.0973575711 0.0790218562 -0.0119847972 223 1305031236.9344370365 0.1346227974 0.1280946704 0.1715931892 0.0200792722 0.0194320000 215299662 95654128 760807424 -0.0961837023 0.0795433894 -0.0181359220 224 1305031236.9744000435 0.1336612552 0.1281195212 0.1715931892 0.0200354683 0.0193760000 215303350 95654128 760807424 -0.0944885239 0.0775195584 -0.0246570893 225 1305031237.0074260235 0.1327672005 0.1281401775 0.1715931892 0.0200160737 0.0192850000 215305366 95654128 760807424 -0.0918070599 0.0745636001 -0.0300307237 226 1305031237.0370240211 0.1349273920 0.1281702095 0.1715931892 0.0200314106 0.0193170000 215308830 95654128 760807424 -0.0889116228 0.0748625770 -0.0370615870 227 1305031237.0734269619 0.1328067631 0.1281906348 0.1715931892 0.0199914345 0.0190390000 215312390 95654128 760807424 -0.0854233131 0.0735588893 -0.0415568501 228 1305031237.1059679985 0.1333624721 0.1282133183 0.1715931892 0.0199732681 0.0190170000 215428962 95654128 760807424 -0.0823458806 0.0684608147 -0.0484338552 229 1305031237.1378319263 0.1325761676 0.1282323700 0.1715931892 0.0199724131 0.0189300000 215603046 95654128 760807424 -0.0772050098 0.0681745037 -0.0520327352 230 1305031237.1712269783 0.1367946863 0.1282695975 0.1715931892 0.0200484523 0.0187340000 215777358 95654128 760807424 -0.0768867433 0.0724241957 -0.0583520047 231 1305031237.2042291164 0.1364201307 0.1283048812 0.1715931892 0.0200549048 0.0185920000 215835414 95654128 760807424 -0.0721010417 0.0649329126 -0.0655547455 232 1305031237.2375690937 0.1386402994 0.1283494304 0.1715931892 0.0201287664 0.0187530000 215953106 95654128 760807424 -0.0712140873 0.0713284239 -0.0687057525 233 1305031237.2746589184 0.1365239173 0.1283845140 0.1715931892 0.0200996602 0.0187020000 216011582 95654128 760807424 -0.0667807460 0.0693929270 -0.0715804398 234 1305031237.3058099747 0.1371662021 0.1284220426 0.1715931892 0.0200933360 0.0184560000 216015086 95654128 760807424 -0.0635084957 0.0723155737 -0.0738129690 235 1305031237.3371419907 0.1387481391 0.1284659835 0.1715931892 0.0200752601 0.0183230000 216018590 95654128 760807424 -0.0604186766 0.0694385245 -0.0782002509 236 1305031237.3741660118 0.1421933621 0.1285241503 0.1715931892 0.0200382446 0.0182540000 216020334 95654128 760807424 -0.0606716387 0.0697039664 -0.0849269778 237 1305031237.4057340622 0.1447902620 0.1285927837 0.1715931892 0.0200796325 0.0180960000 216024094 95654128 760807424 -0.0614759028 0.0754232258 -0.0875391364 238 1305031237.4377219677 0.1452846676 0.1286629177 0.1715931892 0.0200687575 0.0180480000 216027582 95654128 760807424 -0.0584111288 0.0760874152 -0.0891738683 239 1305031237.4741280079 0.1464795619 0.1287374643 0.1715931892 0.0200490036 0.0179850000 216029342 95654128 760807424 -0.0567946471 0.0725149736 -0.0949902907 240 1305031237.5060451031 0.1492843628 0.1288230764 0.1715931892 0.0200675223 0.0176730000 216032886 95654128 760807424 -0.0589545853 0.0791715086 -0.0963564217 241 1305031237.5376501083 0.1464147717 0.1288960710 0.1715931892 0.0200261638 0.0176700000 216036590 95654128 760807424 -0.0539716966 0.0769958049 -0.0965062082 242 1305031237.5739479065 0.1502818167 0.1289844418 0.1715931892 0.0199892389 0.0182910000 216038318 95654128 760807424 -0.0552147552 0.0781415030 -0.1012580693 243 1305031237.6068129539 0.1499189436 0.1290705920 0.1715931892 0.0199657455 0.0176970000 216154694 95654128 760807424 -0.0535419621 0.0815385208 -0.1005496234 244 1305031237.6378550529 0.1513788104 0.1291620191 0.1715931892 0.0199414996 0.0175760000 216214974 95654128 760807424 -0.0534947477 0.0826163068 -0.1023409441 245 1305031237.6752760410 0.1518604457 0.1292546658 0.1715931892 0.0199214539 0.0175460000 216330246 95654128 760807424 -0.0516885184 0.0824463144 -0.1027249396 246 1305031237.7071180344 0.1531004012 0.1293515997 0.1715931892 0.0198862829 0.0175180000 216390690 95654128 760807424 -0.0511617810 0.0856582820 -0.1019250378 247 1305031237.7416670322 0.1566155404 0.1294619800 0.1715931892 0.0198566947 0.0174010000 216392434 95654128 760807424 -0.0549727194 0.0913837180 -0.1023034453 248 1305031237.7743060589 0.1498211473 0.1295440734 0.1715931892 0.0198749243 0.0174790000 216395866 95654128 760807424 -0.0520717427 0.0843783766 -0.0982570127 249 1305031237.8064959049 0.1522525400 0.1296352721 0.1715931892 0.0198613810 0.0174680000 216399626 95654128 760807424 -0.0546518974 0.0842146575 -0.1014706939 250 1305031237.8430309296 0.1583712101 0.1297502158 0.1715931892 0.0198658440 0.0174670000 216401466 95654128 760807424 -0.0604178011 0.0974832773 -0.0980971605 251 1305031237.8754220009 0.1499105543 0.1298305359 0.1715931892 0.0201187010 0.0174660000 216404898 95654128 760807424 -0.0489000715 0.0791748464 -0.1003913879 252 1305031237.9077839851 0.1553784907 0.1299319167 0.1715931892 0.0201394604 0.0175230000 216408442 95654128 760807424 -0.0562639199 0.0783111751 -0.1074107662 253 1305031237.9441869259 0.1585038453 0.1300448492 0.1715931892 0.0202326351 0.0174500000 216410458 95654128 760807424 -0.0607237518 0.0938878059 -0.0998339206 254 1305031237.9738099575 0.1577347219 0.1301538644 0.1715931892 0.0202050222 0.0175590000 216413778 95654128 760807424 -0.0629384071 0.0950109959 -0.0960328877 255 1305031238.0069320202 0.1588035375 0.1302662161 0.1715931892 0.0201758910 0.0175240000 216417394 95654128 760807424 -0.0690710247 0.0994150788 -0.0920135453 256 1305031238.0431399345 0.1576191634 0.1303730636 0.1715931892 0.0203965051 0.0177170000 216531122 95654128 760807424 -0.0740347281 0.1074050739 -0.0817912295 257 1305031238.0740320683 0.1605621874 0.1304905310 0.1715931892 0.0204330149 0.0181090000 216751150 95654128 760807424 -0.0828687474 0.1187938452 -0.0715958923 258 1305031238.1065878868 0.1595489979 0.1306031607 0.1715931892 0.0204164160 0.0180690000 216974042 95654128 760807424 -0.0853590593 0.1220506877 -0.0654619411 259 1305031238.1433279514 0.1592693478 0.1307138409 0.1715931892 0.0204567754 0.0184380000 217010426 95654128 760807424 -0.0837735757 0.1191795468 -0.0654516444 260 1305031238.1723001003 0.1594797969 0.1308244792 0.1715931892 0.0205016340 0.0191500000 217151130 95654128 760807424 -0.0888968855 0.1228583902 -0.0602730140 261 1305031238.2054259777 0.1554542184 0.1309188460 0.1715931892 0.0204899131 0.0187100000 217322982 95654128 760807424 -0.0851605535 0.1132376418 -0.0625049397 262 1305031238.2401471138 0.1567606628 0.1310174789 0.1715931892 0.0204571590 0.0188470000 217359470 95654128 760807424 -0.0858424380 0.1138518304 -0.0626908913 263 1305031238.2725269794 0.1542421728 0.1311057858 0.1715931892 0.0204398510 0.0191830000 217363030 95654128 760807424 -0.0839657336 0.1119026169 -0.0601311475 264 1305031238.3060529232 0.1548534185 0.1311957389 0.1715931892 0.0204976373 0.0190670000 217364766 95654128 760807424 -0.0865243152 0.1146105602 -0.0565640591 265 1305031238.3425960541 0.1524223983 0.1312758395 0.1715931892 0.0205882098 0.0192020000 217507354 95654128 760807424 -0.0853768811 0.1102309451 -0.0554342866 266 1305031238.3741040230 0.1566481590 0.1313712242 0.1715931892 0.0206092890 0.0196400000 217681466 95654128 760807424 -0.0887305066 0.1147802323 -0.0555465110 267 1305031238.4060359001 0.1541795582 0.1314566486 0.1715931892 0.0205884484 0.0195350000 217716210 95654128 760807424 -0.0883977860 0.1131580994 -0.0527328961 268 1305031238.4434239864 0.1533442289 0.1315383187 0.1715931892 0.0205610650 0.0193730000 217719826 95654128 760807424 -0.0898099020 0.1124701574 -0.0507503934 269 1305031238.4740819931 0.1529628038 0.1316179636 0.1715931892 0.0205477924 0.0191950000 217721730 95654128 760807424 -0.0917141810 0.1132771745 -0.0489591770 270 1305031238.5058109760 0.1512812674 0.1316907907 0.1715931892 0.0206065585 0.0195920000 217725250 95654128 760807424 -0.0932048187 0.1101372316 -0.0474697538 271 1305031238.5432639122 0.1489800513 0.1317545887 0.1715931892 0.0205783854 0.0195500000 217867382 95654128 760807424 -0.0943178982 0.1068130657 -0.0457882509 272 1305031238.5741839409 0.1519211382 0.1318287304 0.1715931892 0.0205421055 0.0194800000 217902162 95654128 760807424 -0.0970425904 0.1123383567 -0.0461641066 273 1305031238.6058249474 0.1523563862 0.1319039233 0.1715931892 0.0205091975 0.0230450000 218044058 95654128 760807424 -0.0990665555 0.1152220517 -0.0447418690 274 1305031238.6427590847 0.1518312991 0.1319766510 0.1715931892 0.0204831460 0.0196150000 218080986 95654128 760807424 -0.1004081890 0.1177925840 -0.0428831466 275 1305031238.6738131046 0.1519698203 0.1320493534 0.1715931892 0.0204555084 0.0193590000 218220506 95654128 760807424 -0.1013162136 0.1199676022 -0.0418748520 276 1305031238.7051889896 0.1533346921 0.1321264742 0.1715931892 0.0204322947 0.0260330000 218257334 95654128 760807424 -0.1035330743 0.1231793091 -0.0416343510 277 1305031238.7413070202 0.1495079547 0.1321892232 0.1715931892 0.0204719439 0.0198870000 218399734 95654128 760807424 -0.1059867889 0.1161448509 -0.0396239795 278 1305031238.7717959881 0.1479808837 0.1322460277 0.1715931892 0.0204616089 0.0191800000 218434830 95654128 760807424 -0.1075014919 0.1147195920 -0.0381586514 279 1305031238.8070189953 0.1478864998 0.1323020868 0.1715931892 0.0204324657 0.0192510000 218576826 95654128 760807424 -0.1091781259 0.1144180000 -0.0381741971 280 1305031238.8429400921 0.1472191513 0.1323553620 0.1715931892 0.0204356368 0.0191790000 218613958 95654128 760807424 -0.1115703434 0.1110761687 -0.0378459580 281 1305031238.8737230301 0.1438822001 0.1323963828 0.1715931892 0.0204401657 0.0226230000 218615918 95654128 760807424 -0.1126742363 0.1049874276 -0.0354395173 282 1305031238.9061720371 0.1444232315 0.1324390312 0.1715931892 0.0204134779 0.0193140000 218619422 95654128 760807424 -0.1136715412 0.1068009958 -0.0358609594 283 1305031238.9427859783 0.1459802538 0.1324868800 0.1715931892 0.0203772980 0.0191120000 218621350 95654128 760807424 -0.1138088852 0.1116678864 -0.0366163924 284 1305031238.9723079205 0.1432416737 0.1325247490 0.1715931892 0.0203587218 0.0190540000 218624838 95654128 760807424 -0.1152055711 0.1090233400 -0.0337191932 285 1305031239.0104830265 0.1428687125 0.1325610436 0.1715931892 0.0203684581 0.0190230000 218628750 95654128 760807424 -0.1143227667 0.1132845208 -0.0338219479 286 1305031239.0408790112 0.1426703185 0.1325963908 0.1715931892 0.0203553067 0.0224190000 218630454 95654128 760807424 -0.1154138818 0.1121420637 -0.0335488655 287 1305031239.0746610165 0.1424066722 0.1326305729 0.1715931892 0.0203844629 0.0192520000 218634054 95654128 760807424 -0.1184976697 0.1073063463 -0.0329848863 288 1305031239.1109058857 0.1401836425 0.1326567989 0.1715931892 0.0203516950 0.0188330000 218637782 95654128 760807424 -0.1188190952 0.1056166142 -0.0310043283 289 1305031239.1417789459 0.1396908164 0.1326811380 0.1715931892 0.0203307303 0.0190360000 218639670 95654128 760807424 -0.1205680370 0.1030275002 -0.0304289982 290 1305031239.1757500172 0.1380906701 0.1326997916 0.1715931892 0.0202980399 0.0190660000 218643286 95654128 760807424 -0.1206063479 0.1017489731 -0.0294566527 291 1305031239.2096450329 0.1393483281 0.1327226388 0.1715931892 0.0202733283 0.0191570000 218646902 95654128 760807424 -0.1186984181 0.1016902253 -0.0323342010 292 1305031239.2417099476 0.1400449872 0.1327477153 0.1715931892 0.0202420500 0.0192350000 218648662 95654128 760807424 -0.1192379147 0.1027611271 -0.0331576839 293 1305031239.2738199234 0.1382764876 0.1327665848 0.1715931892 0.0202262756 0.0196000000 218652390 95654128 760807424 -0.1174616963 0.1017282307 -0.0326629430 294 1305031239.3101770878 0.1364064664 0.1327789654 0.1715931892 0.0201970799 0.0194300000 218654318 95654128 760807424 -0.1159224436 0.1015039608 -0.0318089761 295 1305031239.3419699669 0.1343741864 0.1327843729 0.1715931892 0.0201687935 0.0192130000 218657878 95654128 760807424 -0.1130140871 0.0988027081 -0.0315222703 296 1305031239.3750240803 0.1339671165 0.1327883687 0.1715931892 0.0201501125 0.0193160000 218661382 95654128 760807424 -0.1123444363 0.0962750316 -0.0321670659 297 1305031239.4106309414 0.1343729943 0.1327937041 0.1715931892 0.0201167039 0.0228110000 218663382 95654128 760807424 -0.1118400246 0.0939001888 -0.0333867632 298 1305031239.4415419102 0.1356861740 0.1328034104 0.1715931892 0.0200841387 0.0195710000 218666886 95654128 760807424 -0.1124391407 0.0933746845 -0.0349991210 299 1305031239.4733181000 0.1341466308 0.1328079028 0.1715931892 0.0200588417 0.0194190000 218670390 95654128 760807424 -0.1096216217 0.0909273997 -0.0354550257 300 1305031239.5097389221 0.1352778226 0.1328161358 0.1715931892 0.0200379540 0.0194700000 218672222 95654128 760807424 -0.1092335135 0.0925150439 -0.0372487903 301 1305031239.5438020229 0.1356422007 0.1328255248 0.1715931892 0.0200157202 0.0194960000 218676038 95654128 760807424 -0.1083467975 0.0931991935 -0.0382469259 302 1305031239.5761160851 0.1356569678 0.1328349004 0.1715931892 0.0200074587 0.0208920000 218679686 95654128 760807424 -0.1060942039 0.0934791490 -0.0392330140 303 1305031239.6111609936 0.1377525777 0.1328511304 0.1715931892 0.0199874641 0.0242210000 218681702 95654128 760807424 -0.1060363054 0.0933738351 -0.0418333709 304 1305031239.6414220333 0.1372996122 0.1328657635 0.1715931892 0.0199633246 0.0211790000 218685182 95654128 760807424 -0.1036709324 0.0947607830 -0.0419855714 305 1305031239.6710560322 0.1391528845 0.1328863770 0.1715931892 0.0199452003 0.0244630000 218686974 95654128 760807424 -0.1023941264 0.0927459896 -0.0452879779 306 1305031239.7075550556 0.1378990859 0.1329027584 0.1715931892 0.0199567779 0.0211010000 218690590 95654128 760807424 -0.1002875045 0.0874155313 -0.0466162898 307 1305031239.7417550087 0.1399690360 0.1329257756 0.1715931892 0.0199347335 0.0208840000 218694406 95654128 760807424 -0.1009036005 0.0826665834 -0.0506379008 308 1305031239.7712600231 0.1371611506 0.1329395268 0.1715931892 0.0199103485 0.0246650000 218695998 95654128 760807424 -0.0971869007 0.0790769979 -0.0505714603 309 1305031239.8060870171 0.1379994899 0.1329559021 0.1715931892 0.0199770372 0.0216660000 218699774 95654128 760807424 -0.0962361023 0.0739692599 -0.0543737710 310 1305031239.8392889500 0.1431043595 0.1329886391 0.1715931892 0.0199853175 0.0208960000 218701550 95654128 760807424 -0.0973288715 0.0740874335 -0.0607359149 311 1305031239.8744299412 0.1435591131 0.1330226277 0.1715931892 0.0199607300 0.0208730000 218705270 95654128 760807424 -0.0957636610 0.0761348456 -0.0623409227 312 1305031239.9090619087 0.1402348131 0.1330457437 0.1715931892 0.0200040820 0.0206910000 218708886 95654128 760807424 -0.0899948776 0.0727893710 -0.0624429137 313 1305031239.9403729439 0.1409851015 0.1330711091 0.1715931892 0.0200105739 0.0205160000 218710750 95654128 760807424 -0.0874024928 0.0738764182 -0.0644553676 314 1305031239.9710669518 0.1414984465 0.1330979477 0.1715931892 0.0200440735 0.0206100000 218849938 95654128 760807424 -0.0849958658 0.0755037591 -0.0661476180 315 1305031240.0088651180 0.1423983872 0.1331274729 0.1715931892 0.0200661123 0.0203950000 218886650 95654128 760807424 -0.0817867741 0.0686583295 -0.0708366930 316 1305031240.0396599770 0.1444751769 0.1331633834 0.1715931892 0.0200659373 0.0202210000 219026338 95654128 760807424 -0.0811323076 0.0698610991 -0.0749161467 317 1305031240.0711870193 0.1458404809 0.1332033742 0.1715931892 0.0200440369 0.0189270000 219064494 95654128 760807424 -0.0794088617 0.0666245297 -0.0792478174 318 1305031240.1093459129 0.1452336609 0.1332412053 0.1715931892 0.0200330053 0.0290590000 219066566 95654128 760807424 -0.0760015696 0.0610013194 -0.0835448056 319 1305031240.1435019970 0.1485432237 0.1332891740 0.1715931892 0.0200319491 0.0195770000 219205474 95654128 760807424 -0.0725676268 0.0538917556 -0.0917730257 320 1305031240.1775770187 0.1509046257 0.1333442223 0.1715931892 0.0200558926 0.0212630000 219379594 95654128 760807424 -0.0755791664 0.0656239390 -0.0920053795 321 1305031240.2093310356 0.1496606469 0.1333950523 0.1715931892 0.0200868098 0.0182110000 219416142 95654128 760807424 -0.0669784024 0.0546930768 -0.0978347585 322 1305031240.2410049438 0.1520680040 0.1334530428 0.1715931892 0.0201507608 0.0178700000 219554850 95654128 760807424 -0.0652920902 0.0534065701 -0.1035561934 323 1305031240.2774341106 0.1515644789 0.1335091154 0.1715931892 0.0201225344 0.0179180000 219593322 95654128 760807424 -0.0680441484 0.0633783191 -0.1027636826 324 1305031240.3089289665 0.1545556039 0.1335740737 0.1715931892 0.0201049290 0.0175490000 219729910 95654128 760807424 -0.0625763759 0.0558006950 -0.1113228425 325 1305031240.3422729969 0.1550682336 0.1336402096 0.1715931892 0.0201356621 0.0177020000 219768394 95654128 760807424 -0.0624153726 0.0596313551 -0.1123284623 326 1305031240.3774259090 0.1558242887 0.1337082589 0.1715931892 0.0201238138 0.0206570000 219905078 95654128 760807424 -0.0591686182 0.0645910129 -0.1133806407 327 1305031240.4091110229 0.1570112556 0.1337795219 0.1715931892 0.0201129324 0.0177190000 220077930 95654128 760807424 -0.0595681444 0.0669467375 -0.1157099679 328 1305031240.4417860508 0.1576307267 0.1338522390 0.1715931892 0.0200894311 0.0265710000 220116502 95654128 760807424 -0.0571915507 0.0705922395 -0.1152819619 329 1305031240.4776389599 0.1604825258 0.1339331821 0.1715931892 0.0200619744 0.0208860000 220253058 95654128 760807424 -0.0547718480 0.0766535103 -0.1165082380 330 1305031240.5084490776 0.1569439471 0.1340029117 0.1715931892 0.0200337450 0.0208230000 220425886 95654128 760807424 -0.0533170700 0.0733722299 -0.1150963902 331 1305031240.5412700176 0.1599639058 0.1340813437 0.1715931892 0.0200645133 0.0207990000 220464562 95654128 760807424 -0.0566819906 0.0791965425 -0.1157258302 332 1305031240.5759088993 0.1648420542 0.1341739964 0.1715931892 0.0200363103 0.0207720000 220466378 95654128 760807424 -0.0524523444 0.0897760391 -0.1137308404 333 1305031240.6101338863 0.1629799008 0.1342605006 0.1715931892 0.0200142320 0.0175110000 220469938 95654128 760807424 -0.0537570007 0.0910869986 -0.1096436977 334 1305031240.6398229599 0.1635524780 0.1343482012 0.1715931892 0.0200121481 0.0172770000 220473514 95654128 760807424 -0.0594966188 0.1009929627 -0.1014933735 335 1305031240.6747570038 0.1578463912 0.1344183450 0.1715931892 0.0199916606 0.0172340000 220475330 95654128 760807424 -0.0571299046 0.0986097306 -0.0943342745 336 1305031240.7079319954 0.1607739478 0.1344967843 0.1715931892 0.0200177344 0.0285980000 220478874 95654128 760807424 -0.0690356418 0.1082043350 -0.0877084136 337 1305031240.7439579964 0.1587009430 0.1345686068 0.1715931892 0.0200213516 0.0192050000 220482346 95654128 760807424 -0.0733029991 0.1190088540 -0.0726799518 338 1305031240.7768330574 0.1546798795 0.1346281076 0.1715931892 0.0200155671 0.0174780000 220484362 95654128 760807424 -0.0704771206 0.1108365878 -0.0745442212 339 1305031240.8096249104 0.1555009633 0.1346896794 0.1715931892 0.0200005110 0.0181650000 220487850 95654128 760807424 -0.0744019821 0.1146053001 -0.0699161589 340 1305031240.8425960541 0.1601350456 0.1347645187 0.1715931892 0.0200212998 0.0176380000 220489538 95654128 760807424 -0.0861607045 0.1305689663 -0.0566313192 341 1305031240.8794100285 0.1530742794 0.1348182130 0.1715931892 0.0200012520 0.0176740000 220493210 95654128 760807424 -0.0789608806 0.1177137867 -0.0610933863 342 1305031240.9084498882 0.1524053663 0.1348696375 0.1715931892 0.0199803290 0.0208910000 220496842 95654128 760807424 -0.0809145644 0.1207332462 -0.0560180694 343 1305031240.9423189163 0.1559160054 0.1349309971 0.1715931892 0.0199819157 0.0184040000 220498562 95654128 760807424 -0.0876168683 0.1273428053 -0.0513390191 344 1305031240.9779360294 0.1516413540 0.1349795737 0.1715931892 0.0199750072 0.0178620000 220502178 95654128 760807424 -0.0823485553 0.1181924418 -0.0541704409 345 1305031241.0083029270 0.1550678909 0.1350378008 0.1715931892 0.0200340175 0.0193880000 220641154 95654128 760807424 -0.0890486091 0.1244393736 -0.0507804304 346 1305031241.0401480198 0.1512768567 0.1350847344 0.1715931892 0.0200964403 0.0197600000 220678362 95654128 760807424 -0.0864976272 0.1230271459 -0.0464906394 347 1305031241.0759329796 0.1537028700 0.1351383890 0.1715931892 0.0200829064 0.0198000000 220682250 95654128 760807424 -0.0888958424 0.1213587448 -0.0501270741 348 1305031241.1065559387 0.1553012431 0.1351963282 0.1715931892 0.0200649098 0.0236310000 220683898 95654128 760807424 -0.0908355564 0.1226666123 -0.0493851192 349 1305031241.1400520802 0.1520524472 0.1352446266 0.1715931892 0.0201222190 0.0242860000 220687634 95654128 760807424 -0.0891245231 0.1183193177 -0.0478188917 350 1305031241.1781818867 0.1520265639 0.1352925750 0.1715931892 0.0201112948 0.0304840000 220826866 95654128 760807424 -0.0899435058 0.1179072484 -0.0464161783 351 1305031241.2106790543 0.1528949142 0.1353427241 0.1715931892 0.0200926842 0.0215880000 220864622 95654128 760807424 -0.0913651139 0.1199174523 -0.0456379093 352 1305031241.2393150330 0.1517301053 0.1353892792 0.1715931892 0.0201504683 0.0208860000 220867958 95654128 760807424 -0.0907253921 0.1192200780 -0.0444715917 353 1305031241.2768468857 0.1481027603 0.1354252947 0.1715931892 0.0201446166 0.0241690000 221005926 95654128 760807424 -0.0896681920 0.1162906066 -0.0429415666 354 1305031241.3063299656 0.1508099288 0.1354687541 0.1715931892 0.0201227132 0.0218430000 221045254 95654128 760807424 -0.0924430117 0.1225174591 -0.0426246449 355 1305031241.3424758911 0.1496985853 0.1355088381 0.1715931892 0.0201751797 0.0211780000 221049070 95654128 760807424 -0.0931379795 0.1244940609 -0.0416154601 356 1305031241.3795149326 0.1465019286 0.1355397176 0.1715931892 0.0202647820 0.0211360000 221050886 95654128 760807424 -0.0939331129 0.1211494729 -0.0414637998 357 1305031241.4096820354 0.1514693946 0.1355843385 0.1715931892 0.0202694927 0.0211550000 221054550 95654128 760807424 -0.0983856469 0.1263130158 -0.0446469896 358 1305031241.4455459118 0.1532002091 0.1356335449 0.1715931892 0.0202527406 0.0209720000 221058166 95654128 760807424 -0.1021526903 0.1335994750 -0.0443520956 359 1305031241.4775071144 0.1438774914 0.1356565085 0.1715931892 0.0204704206 0.0241320000 221060086 95654128 760807424 -0.1005856022 0.1269948930 -0.0374513268 360 1305031241.5098490715 0.1341472119 0.1356523160 0.1715931892 0.0204696440 0.0210340000 221063590 95654128 760807424 -0.0980407819 0.1159109920 -0.0318750106 361 1305031241.5477299690 0.1304015070 0.1356377709 0.1715931892 0.0204425192 0.0210920000 221065718 95654128 760807424 -0.0978413224 0.1106054634 -0.0294703413 362 1305031241.5783948898 0.1361603737 0.1356392145 0.1715931892 0.0204553123 0.0210360000 221069094 95654128 760807424 -0.0999268815 0.1148278564 -0.0342841446 363 1305031241.6092638969 0.1324592084 0.1356304542 0.1715931892 0.0204567250 0.0209970000 221072742 95654128 760807424 -0.0999851227 0.1072929874 -0.0325985141 364 1305031241.6475839615 0.1334639937 0.1356245023 0.1715931892 0.0204302200 0.0212280000 221074670 95654128 760807424 -0.1012511849 0.1060682237 -0.0346693434 365 1305031241.6783659458 0.1371797770 0.1356287634 0.1715931892 0.0204758460 0.0211080000 221078374 95654128 760807424 -0.0992303714 0.1149434969 -0.0375895537 366 1305031241.7098269463 0.1342492253 0.1356249941 0.1715931892 0.0204536222 0.0211280000 221079966 95654128 760807424 -0.0974768177 0.1119775921 -0.0363923199 367 1305031241.7471020222 0.1351606399 0.1356237289 0.1715931892 0.0204319878 0.0211840000 221083878 95654128 760807424 -0.0966016129 0.1127979979 -0.0379530676 368 1305031241.7782680988 0.1347157508 0.1356212615 0.1715931892 0.0204253984 0.0248300000 221087366 95654128 760807424 -0.0961542949 0.1100791991 -0.0386491194 369 1305031241.8098289967 0.1395058632 0.1356317889 0.1715931892 0.0204336601 0.0304540000 221089158 95654128 760807424 -0.0966150537 0.1163049936 -0.0424696282 370 1305031241.8464360237 0.1354553849 0.1356313121 0.1715931892 0.0204342699 0.0220320000 221092814 95654128 760807424 -0.0984744281 0.1059503108 -0.0407791473 371 1305031241.8787989616 0.1412899941 0.1356465647 0.1715931892 0.0205584189 0.0213780000 221094742 95654128 760807424 -0.0991022810 0.1110885143 -0.0460417978 372 1305031241.9114871025 0.1413845122 0.1356619893 0.1715931892 0.0205664154 0.0212650000 221098230 95654128 760807424 -0.0975336134 0.1145868972 -0.0460756682 373 1305031241.9477050304 0.1378511190 0.1356678582 0.1715931892 0.0205744834 0.0212060000 221102046 95654128 760807424 -0.0973260552 0.1093508229 -0.0441054367 374 1305031241.9783430099 0.1398044229 0.1356789186 0.1715931892 0.0207419166 0.0213620000 221103734 95654128 760807424 -0.0975418463 0.1121509224 -0.0458249785 375 1305031242.0105700493 0.1389448643 0.1356876278 0.1715931892 0.0208214488 0.0214460000 221107382 95654128 760807424 -0.0962497815 0.1085407957 -0.0467807204 376 1305031242.0463600159 0.1368076354 0.1356906065 0.1715931892 0.0209036439 0.0213390000 221245610 95654128 760807424 -0.0949199796 0.1062383726 -0.0457256846 377 1305031242.0795490742 0.1375731081 0.1356955999 0.1715931892 0.0210827015 0.0213290000 221284134 95654128 760807424 -0.0958479792 0.1063011065 -0.0468746834 378 1305031242.1105840206 0.1385066956 0.1357030366 0.1715931892 0.0212191289 0.0307480000 221287638 95654128 760807424 -0.0981696472 0.1043536961 -0.0481957644 379 1305031242.1466050148 0.1397642046 0.1357137521 0.1715931892 0.0214232801 0.0219600000 221424766 95654128 760807424 -0.0990069583 0.1043625772 -0.0496273562 380 1305031242.1797080040 0.1418910027 0.1357300080 0.1715931892 0.0215915201 0.0213190000 221465046 95654128 760807424 -0.1020376235 0.1028844938 -0.0516686589 381 1305031242.2087249756 0.1454457939 0.1357555088 0.1715931892 0.0216837821 0.0213340000 221468638 95654128 760807424 -0.1060220674 0.1028649136 -0.0544395186 382 1305031242.2478089333 0.1460305303 0.1357824067 0.1715931892 0.0217868510 0.0212440000 221470566 95654128 760807424 -0.1076749414 0.0987812504 -0.0554878786 383 1305031242.2794981003 0.1476342380 0.1358133515 0.1715931892 0.0218827368 0.0220230000 221474286 95654128 760807424 -0.1079961434 0.0990461633 -0.0567347184 384 1305031242.3097639084 0.1458548903 0.1358395013 0.1715931892 0.0219469651 0.0213090000 221610378 95654128 760807424 -0.1061148196 0.0963551253 -0.0558368191 385 1305031242.3471269608 0.1458105743 0.1358654002 0.1715931892 0.0221222751 0.0213070000 221651190 95654128 760807424 -0.1061317697 0.0920095965 -0.0566048063 386 1305031242.3784790039 0.1476310641 0.1358958812 0.1715931892 0.0223020024 0.0213000000 221654694 95654128 760807424 -0.1051874831 0.0953521952 -0.0580086894 387 1305031242.4109969139 0.1468524039 0.1359241926 0.1715931892 0.0223986936 0.0295720000 221656598 95654128 760807424 -0.1051406413 0.0909367129 -0.0589270368 388 1305031242.4470989704 0.1492278874 0.1359584805 0.1715931892 0.0226285210 0.0217900000 221794782 95654128 760807424 -0.1076096222 0.0895824432 -0.0624406077 389 1305031242.4776470661 0.1487704813 0.1359914162 0.1715931892 0.0227688678 0.0248130000 221833718 95654128 760807424 -0.1049900725 0.0891905576 -0.0638573021 390 1305031242.5097260475 0.1494550407 0.1360259384 0.1715931892 0.0231116329 0.0214800000 221837222 95654128 760807424 -0.1077309251 0.0834324211 -0.0675562173 391 1305031242.5485460758 0.1521733850 0.1360672362 0.1715931892 0.0237442228 0.0248680000 221841150 95654128 760807424 -0.1096808165 0.0880789682 -0.0710777342 392 1305031242.5748429298 0.1540899277 0.1361132124 0.1715931892 0.0239527670 0.0216220000 221977078 95654128 760807424 -0.1087059230 0.0926107615 -0.0730120838 393 1305031242.6061151028 0.1555529237 0.1361626773 0.1715931892 0.0240716287 0.0211650000 222017986 95654128 760807424 -0.1107415631 0.0871104673 -0.0765846893 394 1305031242.6438109875 0.1586392522 0.1362197245 0.1715931892 0.0244375279 0.0212630000 222021658 95654128 760807424 -0.1146290079 0.0886963457 -0.0801951438 395 1305031242.6752018929 0.1623947173 0.1362859903 0.1715931892 0.0248757221 0.0212830000 222023618 95654128 760807424 -0.1221172363 0.0913836733 -0.0840144753 396 1305031242.7139821053 0.1628752947 0.1363531350 0.1715931892 0.0253489691 0.0247860000 222161394 95654128 760807424 -0.1238143891 0.0954475701 -0.0854579061 397 1305031242.7452580929 0.1580913216 0.1364078911 0.1715931892 0.0254153587 0.0222770000 222200610 95654128 760807424 -0.1173566654 0.0912150145 -0.0843547657 398 1305031242.7775399685 0.1590570807 0.1364647986 0.1715931892 0.0256635848 0.0215840000 222204170 95654128 760807424 -0.1220956072 0.0910400972 -0.0864221826 399 1305031242.8140709400 0.1590251327 0.1365213408 0.1715931892 0.0259321002 0.0214020000 222342006 95654128 760807424 -0.1240968630 0.0973910093 -0.0856519938 400 1305031242.8443179131 0.1592513919 0.1365781660 0.1715931892 0.0259788424 0.0244140000 222381090 95654128 760807424 -0.1254285872 0.0977171138 -0.0873931050 401 1305031242.8740880489 0.1604134291 0.1366376055 0.1715931892 0.0260499812 0.0246750000 222384850 95654128 760807424 -0.1293007284 0.0968924835 -0.0896987990 402 1305031242.9137070179 0.1612933725 0.1366989383 0.1715931892 0.0261769806 0.0250060000 222520694 95654128 760807424 -0.1310110241 0.0986454338 -0.0916218609 403 1305031242.9444379807 0.1622542590 0.1367623510 0.1715931892 0.0264264114 0.0214230000 222561878 95654128 760807424 -0.1364041865 0.1028525010 -0.0920443684 404 1305031242.9760620594 0.1610757560 0.1368225327 0.1715931892 0.0264802444 0.0213940000 222565382 95654128 760807424 -0.1359906942 0.1071176007 -0.0909232423 405 1305031243.0141661167 0.1604535431 0.1368808809 0.1715931892 0.0265733775 0.0318990000 222700590 95654128 760807424 -0.1389841884 0.1080990359 -0.0911753997 406 1305031243.0469100475 0.1610888839 0.1369405065 0.1715931892 0.0265814239 0.0220620000 222741898 95654128 760807424 -0.1439202577 0.1103710160 -0.0918809250 407 1305031243.0780448914 0.1622696817 0.1370027403 0.1715931892 0.0265863407 0.0214490000 222743858 95654128 760807424 -0.1466521174 0.1119270921 -0.0936601683 408 1305031243.1136150360 0.1595694721 0.1370580509 0.1715931892 0.0266129248 0.0213750000 222747474 95654128 760807424 -0.1456949115 0.1163505241 -0.0917987674 409 1305031243.1458160877 0.1608118564 0.1371161287 0.1715931892 0.0265828923 0.0213080000 222751290 95654128 760807424 -0.1457723081 0.1195260957 -0.0923568979 410 1305031243.1780760288 0.1616209298 0.1371758965 0.1715931892 0.0265905357 0.0214660000 222753050 95654128 760807424 -0.1479396075 0.1219993532 -0.0921486691 411 1305031243.2136580944 0.1587371081 0.1372283569 0.1715931892 0.0266441201 0.0211620000 222756922 95654128 760807424 -0.1421758831 0.1222226024 -0.0892703906 412 1305031243.2455608845 0.1643206924 0.1372941150 0.1715931892 0.0269738950 0.0213410000 222760482 95654128 760807424 -0.1478065848 0.1182460040 -0.0930082947 413 1305031243.2781798840 0.1663673222 0.1373645101 0.1715931892 0.0270428133 0.0214990000 222762498 95654128 760807424 -0.1526156068 0.1129769310 -0.0937740132 414 1305031243.3142709732 0.1617619991 0.1374234413 0.1715931892 0.0272403567 0.0215940000 222766114 95654128 760807424 -0.1405775547 0.1157365963 -0.0889363214 415 1305031243.3460359573 0.1658452153 0.1374919275 0.1715931892 0.0275972891 0.0214570000 222768130 95654128 760807424 -0.1463809907 0.1147841364 -0.0906051695 416 1305031243.3789350986 0.1649248153 0.1375578719 0.1715931892 0.0276548601 0.0214840000 222771746 95654128 760807424 -0.1462435126 0.1128546447 -0.0887069553 417 1305031243.4139740467 0.1625034064 0.1376176934 0.1715931892 0.0278283726 0.0215860000 222775562 95654128 760807424 -0.1415529847 0.1187768430 -0.0839906037 418 1305031243.4470911026 0.1666363329 0.1376871159 0.1715931892 0.0281107185 0.0250120000 222777378 95654128 760807424 -0.1498649716 0.1124919876 -0.0870626941 419 1305031243.4780371189 0.1653715223 0.1377531885 0.1715931892 0.0282010342 0.0216180000 222781082 95654128 760807424 -0.1477747858 0.1130888611 -0.0845417753 420 1305031243.5154008865 0.1658285707 0.1378200347 0.1715931892 0.0283898424 0.0214590000 222783010 95654128 760807424 -0.1489072889 0.1152109504 -0.0829802528 421 1305031243.5459430218 0.1692703962 0.1378947386 0.1715931892 0.0284717603 0.0216040000 222786770 95654128 760807424 -0.1544541568 0.1152779534 -0.0851983428 422 1305031243.5779840946 0.1668362767 0.1379633204 0.1715931892 0.0284848649 0.0214580000 222790218 95654128 760807424 -0.1555704027 0.1200937703 -0.0808382630 423 1305031243.6140549183 0.1687807292 0.1380361748 0.1715931892 0.0288660530 0.0250690000 222792250 95654128 760807424 -0.1572824866 0.1199786961 -0.0810239315 424 1305031243.6461870670 0.1746216714 0.1381224614 0.1746216714 0.0292259073 0.0217740000 222928650 95654128 760807424 -0.1641507298 0.1147798374 -0.0862345099 425 1305031243.6782801151 0.1698936522 0.1381972171 0.1746216714 0.0292799323 0.0252430000 223101986 95654128 760807424 -0.1626243144 0.1106403768 -0.0817917138 426 1305031243.7142961025 0.1711516678 0.1382745750 0.1746216714 0.0297514353 0.0224640000 223143774 95654128 760807424 -0.1579898894 0.1145617962 -0.0809680521 427 1305031243.7473781109 0.1718308330 0.1383531611 0.1746216714 0.0300827916 0.0217650000 223281026 95654128 760807424 -0.1581759900 0.1087851152 -0.0815103576 428 1305031243.7790360451 0.1693892479 0.1384256753 0.1746216714 0.0301868703 0.0215110000 223453702 95654128 760807424 -0.1580662578 0.1073673666 -0.0774845406 429 1305031243.8141930103 0.1702567786 0.1384998737 0.1746216714 0.0309326280 0.0217190000 223628386 95654128 760807424 -0.1541380882 0.1052049920 -0.0778872296 430 1305031243.8462920189 0.1630358547 0.1385569341 0.1746216714 0.0314087246 0.0248370000 223802718 95654128 760807424 -0.1399136484 0.0963854939 -0.0737311915 431 1305031243.8788089752 0.1635814160 0.1386149955 0.1746216714 0.0315936234 0.0215750000 223975914 95654128 760807424 -0.1395838708 0.0941020250 -0.0734250620 432 1305031243.9140000343 0.1637087613 0.1386730830 0.1746216714 0.0319194296 0.0244880000 224150058 95654128 760807424 -0.1363416612 0.0945198238 -0.0730133429 433 1305031243.9470779896 0.1572769284 0.1387160480 0.1746216714 0.0321483086 0.0214950000 224190550 95654128 760807424 -0.1274581254 0.0995969996 -0.0666634887 434 1305031243.9816520214 0.1526799500 0.1387482229 0.1746216714 0.0323150735 0.0213440000 224325782 95654128 760807424 -0.1218056232 0.1024895087 -0.0618925542 435 1305031244.0112700462 0.1480323672 0.1387695657 0.1746216714 0.0324098030 0.0214580000 224367974 95654128 760807424 -0.1151846573 0.1021661386 -0.0583213195 436 1305031244.0438230038 0.1501517594 0.1387956717 0.1746216714 0.0324288849 0.0213280000 224501654 95654128 760807424 -0.1149056777 0.1136774942 -0.0561632924 437 1305031244.0818090439 0.1496227682 0.1388204476 0.1746216714 0.0324840199 0.0213930000 224544138 95654128 760807424 -0.1147594452 0.1185227036 -0.0536008812 438 1305031244.1127901077 0.1483801603 0.1388422735 0.1746216714 0.0325693263 0.0213560000 224545842 95654128 760807424 -0.1144210324 0.1148814783 -0.0531088039 439 1305031244.1484949589 0.1516719311 0.1388714982 0.1746216714 0.0325696833 0.0213360000 224681018 95654128 760807424 -0.1182134226 0.1226132810 -0.0533657633 440 1305031244.1824309826 0.1461185813 0.1388879688 0.1746216714 0.0326799759 0.0212320000 224723234 95654128 760807424 -0.1152200773 0.1267924607 -0.0461180694 441 1305031244.2124009132 0.1415870488 0.1388940892 0.1746216714 0.0328124261 0.0220370000 224857014 95654128 760807424 -0.1115166023 0.1274863631 -0.0419210605 442 1305031244.2473471165 0.1407878697 0.1388983738 0.1746216714 0.0329993999 0.0249300000 224899354 95654128 760807424 -0.1104244962 0.1320800781 -0.0397694744 443 1305031244.2831470966 0.1368881613 0.1388938360 0.1746216714 0.0331673634 0.0216080000 225033162 95654128 760807424 -0.1075550467 0.1351555884 -0.0368960984 444 1305031244.3137950897 0.1315761209 0.1388773547 0.1746216714 0.0333603915 0.0251120000 225075402 95654128 760807424 -0.1032933742 0.1417572796 -0.0307858121 445 1305031244.3459599018 0.1269413382 0.1388505322 0.1746216714 0.0335670907 0.0215570000 225210850 95654128 760807424 -0.0994821191 0.1487734020 -0.0251625720 446 1305031244.3808560371 0.1280362755 0.1388262850 0.1746216714 0.0337509453 0.0215450000 225251526 95654128 760807424 -0.0984094813 0.1516809911 -0.0278082490 447 1305031244.4130189419 0.1262220144 0.1387980875 0.1746216714 0.0339905031 0.0215100000 225387422 95654128 760807424 -0.0963889360 0.1548289508 -0.0274000186 448 1305031244.4451670647 0.1268034428 0.1387713137 0.1746216714 0.0340702169 0.0251830000 225429910 95654128 760807424 -0.0972948521 0.1638315767 -0.0253170691 449 1305031244.4806590080 0.1309587359 0.1387539138 0.1746216714 0.0341467596 0.0216880000 225563282 95654128 760807424 -0.0996016786 0.1683655083 -0.0284405258 450 1305031244.5142281055 0.1319981068 0.1387389009 0.1746216714 0.0342629034 0.0213690000 225605894 95654128 760807424 -0.0999696925 0.1689518839 -0.0292628855 451 1305031244.5462141037 0.1358965933 0.1387325987 0.1746216714 0.0342538570 0.0212680000 225607798 95654128 760807424 -0.1058283448 0.1753413230 -0.0275147445 452 1305031244.5808050632 0.1351672560 0.1387247107 0.1746216714 0.0343102744 0.0214210000 225611358 95654128 760807424 -0.1068393067 0.1765513420 -0.0245509334 453 1305031244.6132769585 0.1355904788 0.1387177919 0.1746216714 0.0344165551 0.0212900000 225746250 95654128 760807424 -0.1058354601 0.1747253239 -0.0249441024 454 1305031244.6428399086 0.1381554902 0.1387165533 0.1746216714 0.0344105726 0.0212750000 225787026 95654128 760807424 -0.1090873554 0.1781644672 -0.0241548251 455 1305031244.6806099415 0.1382549554 0.1387155388 0.1746216714 0.0344890647 0.0214580000 225790842 95654128 760807424 -0.1114461124 0.1801089495 -0.0208466742 456 1305031244.7152500153 0.1400347054 0.1387184318 0.1746216714 0.0345266739 0.0213870000 225792658 95654128 760807424 -0.1136992946 0.1830848306 -0.0206872877 457 1305031244.7458879948 0.1373142153 0.1387153591 0.1746216714 0.0347570122 0.0214920000 225927482 95654128 760807424 -0.1108518690 0.1805750281 -0.0195831787 458 1305031244.7818510532 0.1380443275 0.1387138939 0.1746216714 0.0348346341 0.0213710000 225970470 95654128 760807424 -0.1107925400 0.1812713444 -0.0204455033 459 1305031244.8140940666 0.1317134947 0.1386986425 0.1746216714 0.0356485761 0.0215300000 225972374 95654128 760807424 -0.1092862710 0.1836627573 -0.0164902471 460 1305031244.8418219090 0.1258944273 0.1386708073 0.1746216714 0.0356491296 0.0245950000 226106742 95654128 760807424 -0.1054657847 0.1859299392 -0.0109900394 461 1305031244.8818008900 0.1302714199 0.1386525873 0.1746216714 0.0356212648 0.0214580000 226148286 95654128 760807424 -0.1072864383 0.1901315749 -0.0137043763 462 1305031244.9149079323 0.1313645095 0.1386368123 0.1746216714 0.0356086283 0.0213670000 226151790 95654128 760807424 -0.1067647636 0.1926278621 -0.0144062927 463 1305031244.9458680153 0.1305937916 0.1386194407 0.1746216714 0.0355731152 0.0213280000 226155422 95654128 760807424 -0.1055397540 0.1950597465 -0.0133271720 464 1305031244.9818000793 0.1353636384 0.1386124239 0.1746216714 0.0355906694 0.0214130000 226157238 95654128 760807424 -0.1087385267 0.1985578388 -0.0126222344 465 1305031245.0140550137 0.1245121807 0.1385821008 0.1746216714 0.0355607604 0.0213960000 226160910 95654128 760807424 -0.1013227999 0.1974292696 -0.0041612172 466 1305031245.0464398861 0.1367462575 0.1385781612 0.1746216714 0.0355340116 0.0211760000 226164414 95654128 760807424 -0.1074418947 0.2024137825 -0.0128541654 467 1305031245.0817689896 0.1304185092 0.1385606888 0.1746216714 0.0355259444 0.0212640000 226298330 95654128 760807424 -0.1074204817 0.2009546012 -0.0049813986 468 1305031245.1143150330 0.1275123954 0.1385370813 0.1746216714 0.0355396544 0.0214320000 226341422 95654128 760807424 -0.1040482000 0.1988261938 -0.0042680544 469 1305031245.1457099915 0.1348755956 0.1385292743 0.1746216714 0.0355291240 0.0279010000 226343382 95654128 760807424 -0.1090054959 0.1977157146 -0.0101578645 470 1305031245.1818709373 0.1302856058 0.1385117346 0.1746216714 0.0355471061 0.0217290000 226346942 95654128 760807424 -0.1091741696 0.1929017007 -0.0067939777 471 1305031245.2140939236 0.1302499324 0.1384941936 0.1746216714 0.0356883554 0.0219990000 226480930 95654128 760807424 -0.1102353856 0.1889374107 -0.0085164644 472 1305031245.2487950325 0.1385589540 0.1384943308 0.1746216714 0.0360522631 0.0214740000 226522522 95654128 760807424 -0.1178815290 0.1873032451 -0.0163217969 473 1305031245.2807950974 0.1444952786 0.1385070178 0.1746216714 0.0361327403 0.0213270000 226526170 95654128 760807424 -0.1221524402 0.1839430332 -0.0239250101 474 1305031245.3143179417 0.1352958530 0.1385002432 0.1746216714 0.0362942358 0.0213070000 226658522 95654128 760807424 -0.1191916689 0.1777997166 -0.0190796573 475 1305031245.3491809368 0.1381014436 0.1384994036 0.1746216714 0.0365630062 0.0214110000 226702286 95654128 760807424 -0.1224232987 0.1773938388 -0.0228311103 476 1305031245.3806860447 0.1396166086 0.1385017507 0.1746216714 0.0368310969 0.0214890000 226836718 95654128 760807424 -0.1219899282 0.1741667539 -0.0285117738 477 1305031245.4133110046 0.1484174281 0.1385225382 0.1746216714 0.0370368532 0.0214080000 226878566 95654128 760807424 -0.1265743673 0.1738618165 -0.0390377305 478 1305031245.4489970207 0.1408581883 0.1385274245 0.1746216714 0.0370190747 0.0246450000 226882126 95654128 760807424 -0.1131701991 0.1576185822 -0.0457622707 479 1305031245.4846711159 0.1417768747 0.1385342084 0.1746216714 0.0373255295 0.0216420000 227014718 95654128 760807424 -0.1160427183 0.1596774310 -0.0475454368 480 1305031245.5124320984 0.1461046636 0.1385499801 0.1746216714 0.0374622223 0.0215530000 227058154 95654128 760807424 -0.1173045933 0.1611138135 -0.0526480041 481 1305031245.5481460094 0.1501506716 0.1385740980 0.1746216714 0.0376207097 0.0214080000 227061946 95654128 760807424 -0.1193664297 0.1603645682 -0.0589277223 482 1305031245.5786890984 0.1464179456 0.1385903716 0.1746216714 0.0376371855 0.0216030000 227194974 95654128 760807424 -0.1151550412 0.1593242586 -0.0575057603 483 1305031245.6104750633 0.1470504254 0.1386078872 0.1746216714 0.0377257944 0.0214940000 227238766 95654128 760807424 -0.1138588414 0.1513245255 -0.0636870265 484 1305031245.6494629383 0.1509830803 0.1386334558 0.1746216714 0.0379357985 0.0215870000 227242438 95654128 760807424 -0.1171417087 0.1532702148 -0.0676453263 485 1305031245.6802349091 0.1504380107 0.1386577951 0.1746216714 0.0379664289 0.0216790000 227375106 95654128 760807424 -0.1174761727 0.1569211334 -0.0657251030 486 1305031245.7110319138 0.1494809836 0.1386800650 0.1746216714 0.0379745724 0.0216750000 227418854 95654128 760807424 -0.1159659848 0.1526445746 -0.0675795376 487 1305031245.7497749329 0.1493135989 0.1387018998 0.1746216714 0.0380304831 0.0225880000 227420926 95654128 760807424 -0.1150868312 0.1540461034 -0.0671629608 488 1305031245.7818500996 0.1466727555 0.1387182335 0.1746216714 0.0380716015 0.0218320000 227424486 95654128 760807424 -0.1112303138 0.1529224366 -0.0657124370 489 1305031245.8135690689 0.1464537978 0.1387340526 0.1746216714 0.0381725251 0.0216710000 227428134 95654128 760807424 -0.1106023863 0.1521133929 -0.0656361803 490 1305031245.8491089344 0.1476981938 0.1387523468 0.1746216714 0.0382249165 0.0218990000 227559426 95654128 760807424 -0.1119578406 0.1494570076 -0.0684521869 491 1305031245.8820281029 0.1500364989 0.1387753288 0.1746216714 0.0382841172 0.0218030000 227603594 95654128 760807424 -0.1146329269 0.1505932361 -0.0701129660 492 1305031245.9126079082 0.1510380954 0.1388002531 0.1746216714 0.0383099878 0.0218730000 227735898 95654128 760807424 -0.1168911681 0.1476856321 -0.0724881589 493 1305031245.9458959103 0.1520101428 0.1388270480 0.1746216714 0.0383723623 0.0218880000 227780078 95654128 760807424 -0.1187614202 0.1440012902 -0.0755050331 494 1305031245.9808180332 0.1530122012 0.1388557629 0.1746216714 0.0384105295 0.0217380000 227783694 95654128 760807424 -0.1187852696 0.1433922350 -0.0776537582 495 1305031246.0110030174 0.1532025337 0.1388847463 0.1746216714 0.0384327670 0.0218660000 227914846 95654128 760807424 -0.1188445762 0.1392874420 -0.0802993700 496 1305031246.0483930111 0.1544158459 0.1389160590 0.1746216714 0.0385346099 0.0217480000 227959150 95654128 760807424 -0.1220317259 0.1364995241 -0.0832771435 497 1305031246.0805249214 0.1567049772 0.1389518516 0.1746216714 0.0386198676 0.0255960000 227960942 95654128 760807424 -0.1259004325 0.1339415759 -0.0869675055 498 1305031246.1123559475 0.1609192938 0.1389959629 0.1746216714 0.0387383330 0.0218550000 228094338 95654128 760807424 -0.1300591230 0.1327746063 -0.0925506949 499 1305031246.1484489441 0.1600183398 0.1390380919 0.1746216714 0.0388490775 0.0217610000 228138774 95654128 760807424 -0.1263466626 0.1304264218 -0.0935685560 500 1305031246.1805961132 0.1599745005 0.1390799647 0.1746216714 0.0389032924 0.0217530000 228140422 95654128 760807424 -0.1247289330 0.1274332404 -0.0949580446 501 1305031246.2111370564 0.1618361324 0.1391253862 0.1746216714 0.0390263523 0.0252490000 228273786 95654128 760807424 -0.1309072673 0.1231290624 -0.0983015299 502 1305031246.2469689846 0.1652907133 0.1391775084 0.1746216714 0.0391872290 0.0221160000 228318178 95654128 760807424 -0.1348546743 0.1225274950 -0.1023822427 503 1305031246.2796959877 0.1660841256 0.1392310007 0.1746216714 0.0392679160 0.0219870000 228320082 95654128 760807424 -0.1364744306 0.1171550825 -0.1053347439 504 1305031246.3124730587 0.1688537002 0.1392897759 0.1746216714 0.0394151512 0.0217960000 228453110 95654128 760807424 -0.1383565366 0.1177733615 -0.1079390198 505 1305031246.3482720852 0.1696233600 0.1393498424 0.1746216714 0.0395592707 0.0219410000 228496002 95654128 760807424 -0.1415323764 0.1126043722 -0.1099138558 506 1305031246.3782060146 0.1728713363 0.1394160904 0.1746216714 0.0397784613 0.0259690000 228630138 95654128 760807424 -0.1447881013 0.1154062748 -0.1119620875 507 1305031246.4156370163 0.1726276129 0.1394815963 0.1746216714 0.0399588775 0.0219320000 228675010 95654128 760807424 -0.1462762207 0.1160993725 -0.1111085713 508 1305031246.4452888966 0.1737452447 0.1395490445 0.1746216714 0.0400686848 0.0218200000 228807062 95654128 760807424 -0.1494320482 0.1143741459 -0.1122543588 509 1305031246.4774649143 0.1746695191 0.1396180434 0.1746695191 0.0401941361 0.0255830000 228851890 95654128 760807424 -0.1519076973 0.1145404503 -0.1128589660 510 1305031246.5163950920 0.1751133949 0.1396876422 0.1751133949 0.0403504469 0.0219020000 228853802 95654128 760807424 -0.1557225883 0.1157822609 -0.1126830578 511 1305031246.5491750240 0.1729985774 0.1397528299 0.1751133949 0.0405096996 0.0218120000 228986978 95654128 760807424 -0.1556057930 0.1192544028 -0.1100091636 512 1305031246.5795109272 0.1705973744 0.1398130732 0.1751133949 0.0406193592 0.0218690000 229031594 95654128 760807424 -0.1580700129 0.1231855899 -0.1071572006 513 1305031246.6164529324 0.1729824841 0.1398777309 0.1751133949 0.0407063895 0.0220330000 229086754 95654128 760807424 -0.1634386182 0.1230747476 -0.1098955870 514 1305031246.6477630138 0.1715419888 0.1399393345 0.1751133949 0.0407680680 0.0250680000 229364050 95654128 760807424 -0.1617317051 0.1260442436 -0.1085823551 515 1305031246.6807579994 0.1717405617 0.1400010844 0.1751133949 0.0408795034 0.0252430000 229366034 95654128 760807424 -0.1682479233 0.1292569190 -0.1090807915 516 1305031246.7169740200 0.1708321124 0.1400608345 0.1751133949 0.0410184031 0.0228510000 229541622 95654128 760807424 -0.1681727916 0.1307861507 -0.1098325029 517 1305031246.7491660118 0.1692437232 0.1401172811 0.1751133949 0.0411209564 0.0221100000 229545350 95654128 760807424 -0.1697246283 0.1338469535 -0.1094354913 518 1305031246.7808170319 0.1686535478 0.1401723704 0.1751133949 0.0412031874 0.0219640000 229718378 95654128 760807424 -0.1726471335 0.1382200122 -0.1092492491 519 1305031246.8168079853 0.1694634259 0.1402288079 0.1751133949 0.0412569153 0.0257060000 229722274 95654128 760807424 -0.1707640439 0.1384204179 -0.1120788455 520 1305031246.8488121033 0.1697301716 0.1402855413 0.1751133949 0.0412976600 0.0221100000 229897326 95654128 760807424 -0.1719461530 0.1396367550 -0.1138070226 521 1305031246.8806428909 0.1667110622 0.1403362621 0.1751133949 0.0413921459 0.0219860000 229899310 95654128 760807424 -0.1740296334 0.1446690410 -0.1118753850 522 1305031246.9166710377 0.1654371172 0.1403843480 0.1751133949 0.0414812526 0.0315270000 230074378 95654128 760807424 -0.1756643206 0.1485360265 -0.1137584820 523 1305031246.9495339394 0.1679566503 0.1404370675 0.1751133949 0.0414760640 0.0226350000 230076378 95654128 760807424 -0.1742267311 0.1495278031 -0.1186652035 524 1305031246.9775969982 0.1711213887 0.1404956254 0.1751133949 0.0414740003 0.0260740000 230251118 95654128 760807424 -0.1772160232 0.1513343155 -0.1236978248 525 1305031247.0167899132 0.1650152355 0.1405423294 0.1751133949 0.0415643373 0.0219500000 230255070 95654128 760807424 -0.1739101112 0.1545583904 -0.1210963055 526 1305031247.0479340553 0.1663492769 0.1405913920 0.1751133949 0.0415418129 0.0220130000 230427302 95654128 760807424 -0.1763072312 0.1558984518 -0.1249445751 527 1305031247.0778899193 0.1646652669 0.1406370730 0.1751133949 0.0415414102 0.0218760000 230431062 95654128 760807424 -0.1741551608 0.1603900492 -0.1253188550 528 1305031247.1162130833 0.1683053076 0.1406894750 0.1751133949 0.0415148687 0.0220040000 230433014 95654128 760807424 -0.1771360040 0.1652970761 -0.1299117506 529 1305031247.1473660469 0.1728326976 0.1407502372 0.1751133949 0.0415174710 0.0220810000 230436798 95654128 760807424 -0.1800357699 0.1679439247 -0.1344197392 530 1305031247.1796920300 0.1687646359 0.1408030945 0.1751133949 0.0414791581 0.0226170000 230612446 95654128 760807424 -0.1755096167 0.1653870791 -0.1324364245 531 1305031247.2169430256 0.1707734466 0.1408595359 0.1751133949 0.0414570959 0.0218040000 230614598 95654128 760807424 -0.1767577827 0.1665697545 -0.1342976689 532 1305031247.2487928867 0.1708732545 0.1409159527 0.1751133949 0.0414316566 0.0216540000 230618126 95654128 760807424 -0.1778846979 0.1701183170 -0.1331432164 533 1305031247.2794220448 0.1753022820 0.1409804673 0.1753022820 0.0414118271 0.0276370000 230620054 95654128 760807424 -0.1815392375 0.1697555780 -0.1368843764 534 1305031247.3166429996 0.1696507335 0.1410341570 0.1753022820 0.0414253014 0.0221980000 230623806 95654128 760807424 -0.1762091964 0.1647271514 -0.1329623759 535 1305031247.3477900028 0.1731286049 0.1410941466 0.1753022820 0.0414973387 0.0220290000 230627558 95654128 760807424 -0.1798550785 0.1654259861 -0.1353421807 536 1305031247.3786110878 0.1740076840 0.1411555525 0.1753022820 0.0415155252 0.0220240000 230629286 95654128 760807424 -0.1814303696 0.1661461741 -0.1358768642 537 1305031247.4168620110 0.1710463762 0.1412112151 0.1753022820 0.0416043965 0.0219170000 230803674 95654128 760807424 -0.1805913001 0.1644768864 -0.1334540844 538 1305031247.4487700462 0.1755575091 0.1412750558 0.1755575091 0.0417796687 0.0220090000 230807258 95654128 760807424 -0.1841817498 0.1666994542 -0.1362256557 539 1305031247.4802629948 0.1769129187 0.1413411742 0.1769129187 0.0418479233 0.0219750000 230809130 95654128 760807424 -0.1874346733 0.1684178561 -0.1362434775 540 1305031247.5178461075 0.1754194200 0.1414042821 0.1769129187 0.0419874722 0.0219810000 230984010 95654128 760807424 -0.1860372424 0.1687261462 -0.1336347014 541 1305031247.5459010601 0.1763131171 0.1414688086 0.1769129187 0.0420937333 0.0254840000 230985826 95654128 760807424 -0.1879526079 0.1693464667 -0.1338250190 542 1305031247.5779209137 0.1769206375 0.1415342179 0.1769206375 0.0422023887 0.0220330000 230989386 95654128 760807424 -0.1894313246 0.1698505878 -0.1338752508 543 1305031247.6152799129 0.1774855703 0.1416004266 0.1774855703 0.0423915766 0.0254360000 231164390 95654128 760807424 -0.1876454502 0.1716891378 -0.1326455474 544 1305031247.6484000683 0.1777237803 0.1416668299 0.1777237803 0.0425390254 0.0220940000 231166174 95654128 760807424 -0.1874804050 0.1698583066 -0.1326312870 545 1305031247.6835579872 0.1773307323 0.1417322682 0.1777237803 0.0427030957 0.0254050000 231341510 95654128 760807424 -0.1877458841 0.1684146971 -0.1312969178 546 1305031247.7159609795 0.1769576669 0.1417967836 0.1777237803 0.0429432760 0.0219320000 231343238 95654128 760807424 -0.1851661950 0.1684235632 -0.1295572966 547 1305031247.7469019890 0.1757578850 0.1418588697 0.1777237803 0.0432290599 0.0220320000 231518910 95654128 760807424 -0.1822638065 0.1656652093 -0.1287366003 548 1305031247.7822608948 0.1726865023 0.1419151245 0.1777237803 0.0433933932 0.0251210000 231522494 95654128 760807424 -0.1829199493 0.1614486128 -0.1276299208 549 1305031247.8139829636 0.1762652993 0.1419776931 0.1777237803 0.0437061235 0.0219140000 231695402 95654128 760807424 -0.1848215461 0.1554635167 -0.1330988854 550 1305031247.8484420776 0.1701935083 0.1420289946 0.1777237803 0.0439583317 0.0251560000 231870254 95654128 760807424 -0.1648899764 0.1478404403 -0.1318303049 551 1305031247.8820719719 0.1713905185 0.1420822823 0.1777237803 0.0440121742 0.0219190000 232043134 95654128 760807424 -0.1686058491 0.1343002915 -0.1371821761 552 1305031247.9173319340 0.1723703742 0.1421371520 0.1777237803 0.0439988787 0.0220280000 232216722 95654128 760807424 -0.1727682650 0.1439012587 -0.1385734528 553 1305031247.9496860504 0.1697338670 0.1421870557 0.1777237803 0.0441079260 0.0220680000 232220354 95654128 760807424 -0.1630889773 0.1519227922 -0.1363196522 554 1305031247.9861450195 0.1701276153 0.1422374899 0.1777237803 0.0442855426 0.0256610000 232394098 95654128 760807424 -0.1576282978 0.1398133039 -0.1424575001 555 1305031248.0181560516 0.1698006690 0.1422871533 0.1777237803 0.0442602533 0.0221200000 232567686 95654128 760807424 -0.1590801775 0.1429865211 -0.1430047750 556 1305031248.0499138832 0.1720722020 0.1423407235 0.1777237803 0.0442976635 0.0218390000 232571158 95654128 760807424 -0.1602877527 0.1481453627 -0.1451628953 557 1305031248.0857460499 0.1663773507 0.1423838773 0.1777237803 0.0445053400 0.0218410000 232747294 95654128 760807424 -0.1459645480 0.1424867511 -0.1436591744 558 1305031248.1175789833 0.1639904678 0.1424225987 0.1777237803 0.0445399277 0.0217120000 232921886 95654128 760807424 -0.1381691247 0.1362337321 -0.1444043219 559 1305031248.1493461132 0.1657989472 0.1424644169 0.1777237803 0.0445532636 0.0253080000 232923758 95654128 760807424 -0.1387357265 0.1422204077 -0.1456701010 560 1305031248.1848630905 0.1606059223 0.1424968125 0.1777237803 0.0447242447 0.0217200000 233097562 95654128 760807424 -0.1239199713 0.1421126872 -0.1413433403 561 1305031248.2167689800 0.1577883959 0.1425240702 0.1777237803 0.0447596667 0.0215890000 233271130 95654128 760807424 -0.1162433624 0.1415806413 -0.1396922171 562 1305031248.2488510609 0.1616968513 0.1425581854 0.1777237803 0.0447806282 0.0215530000 233272746 95654128 760807424 -0.1209970266 0.1445807964 -0.1438630372 563 1305031248.2847399712 0.1586000472 0.1425866790 0.1777237803 0.0448742569 0.0215330000 233447442 95654128 760807424 -0.1118503585 0.1511337757 -0.1383748949 564 1305031248.3161809444 0.1538123190 0.1426065826 0.1777237803 0.0449576019 0.0213450000 233449114 95654128 760807424 -0.1033794284 0.1555252969 -0.1315328628 565 1305031248.3488430977 0.1541145146 0.1426269506 0.1777237803 0.0450288035 0.0217150000 233623410 95654128 760807424 -0.1043736860 0.1479564309 -0.1368931085 566 1305031248.3881969452 0.1576135457 0.1426534287 0.1777237803 0.0450288066 0.0214000000 233627106 95654128 760807424 -0.1091210544 0.1536531299 -0.1403181106 567 1305031248.4155070782 0.1555829793 0.1426762321 0.1777237803 0.0450747716 0.0215050000 233799438 95654128 760807424 -0.1051871032 0.1568036079 -0.1378050148 568 1305031248.4482519627 0.1538255811 0.1426958613 0.1777237803 0.0450966454 0.0247910000 233802894 95654128 760807424 -0.1025751606 0.1551865786 -0.1387366951 569 1305031248.4852969646 0.1503465772 0.1427093072 0.1777237803 0.0451457611 0.0213410000 233976210 95654128 760807424 -0.0998091772 0.1511489153 -0.1395099163 570 1305031248.5154309273 0.1530658603 0.1427274766 0.1777237803 0.0451217416 0.0211320000 233979666 95654128 760807424 -0.0997369066 0.1599339992 -0.1393967271 571 1305031248.5470030308 0.1501222253 0.1427404271 0.1777237803 0.0451508903 0.0212330000 233983322 95654128 760807424 -0.0941680595 0.1679350138 -0.1325750202 572 1305031248.5860579014 0.1460663676 0.1427462417 0.1777237803 0.0452128071 0.0211940000 234154382 95654128 760807424 -0.0908719599 0.1617847532 -0.1346206516 573 1305031248.6180379391 0.1506630182 0.1427600580 0.1777237803 0.0452571734 0.0212680000 234157998 95654128 760807424 -0.0954118893 0.1624787450 -0.1412895769 574 1305031248.6494390965 0.1520086676 0.1427761706 0.1777237803 0.0452437112 0.0219500000 234331938 95654128 760807424 -0.0982214361 0.1648027599 -0.1438354552 575 1305031248.6860280037 0.1513413489 0.1427910666 0.1777237803 0.0452851108 0.0212840000 234333978 95654128 760807424 -0.0982929245 0.1696578264 -0.1430949867 576 1305031248.7199230194 0.1477973312 0.1427997580 0.1777237803 0.0452990976 0.0211100000 234508458 95654128 760807424 -0.0949493796 0.1721723229 -0.1399275213 577 1305031248.7498369217 0.1464156657 0.1428060247 0.1777237803 0.0453710511 0.0210240000 234510274 95654128 760807424 -0.0936496556 0.1761069000 -0.1382254660 578 1305031248.7856750488 0.1401530206 0.1428014348 0.1777237803 0.0454212407 0.0248330000 234513842 95654128 760807424 -0.0850361437 0.1729762554 -0.1341130883 579 1305031248.8181409836 0.1423355192 0.1428006301 0.1777237803 0.0453982897 0.0211960000 234688746 95654128 760807424 -0.0868230611 0.1868119687 -0.1301273704 580 1305031248.8496789932 0.1385019571 0.1427932186 0.1777237803 0.0454380780 0.0210780000 234690418 95654128 760807424 -0.0809783190 0.1891054213 -0.1249355152 581 1305031248.8855929375 0.1352040172 0.1427801563 0.1777237803 0.0454521027 0.0210330000 234864630 95654128 760807424 -0.0766325891 0.1904850304 -0.1206397340 582 1305031248.9178819656 0.1374867558 0.1427710611 0.1777237803 0.0454228044 0.0208850000 234866302 95654128 760807424 -0.0786461383 0.1978821456 -0.1191141382 583 1305031248.9526810646 0.1323208362 0.1427531361 0.1777237803 0.0454414026 0.0210390000 235041022 95654128 760807424 -0.0739073828 0.1997371167 -0.1125705838 584 1305031248.9845540524 0.1317147166 0.1427342347 0.1777237803 0.0454335454 0.0209600000 235044510 95654128 760807424 -0.0715570822 0.2023139000 -0.1108329073 585 1305031249.0169510841 0.1344749182 0.1427201163 0.1777237803 0.0454348835 0.0208050000 235215858 95654128 760807424 -0.0712892041 0.2037891150 -0.1126376092 586 1305031249.0523660183 0.1337649524 0.1427048344 0.1777237803 0.0454100036 0.0207720000 235219426 95654128 760807424 -0.0709089488 0.2049126178 -0.1101417243 587 1305031249.0845029354 0.1359275877 0.1426932888 0.1777237803 0.0453936944 0.0207410000 235221298 95654128 760807424 -0.0732285753 0.2069493383 -0.1086186394 588 1305031249.1168839931 0.1319225878 0.1426749713 0.1777237803 0.0453609591 0.0250090000 235224770 95654128 760807424 -0.0714783072 0.2048208416 -0.1033673733 589 1305031249.1534469128 0.1372456402 0.1426657534 0.1777237803 0.0453311236 0.0211070000 235228554 95654128 760807424 -0.0784674287 0.2092999369 -0.1021852270 590 1305031249.1847391129 0.1409602612 0.1426628628 0.1777237803 0.0453108269 0.0210440000 235400886 95654128 760807424 -0.0838491619 0.2104077041 -0.1028064117 591 1305031249.2168650627 0.1344600320 0.1426489832 0.1777237803 0.0452878508 0.0211630000 235404542 95654128 760807424 -0.0770373195 0.2013144642 -0.1004073843 592 1305031249.2532238960 0.1425801814 0.1426488670 0.1777237803 0.0452596125 0.0211380000 235408126 95654128 760807424 -0.0851440132 0.2036555111 -0.1047305465 593 1305031249.2848041058 0.1346240640 0.1426353344 0.1777237803 0.0452528603 0.0210380000 235580806 95654128 760807424 -0.0812341571 0.1983314455 -0.0977536067 594 1305031249.3174340725 0.1323601604 0.1426180362 0.1777237803 0.0452357656 0.0211960000 235584334 95654128 760807424 -0.0825017020 0.1995140910 -0.0928175449 595 1305031249.3527359962 0.1354384124 0.1426059696 0.1777237803 0.0452015164 0.0209990000 235586246 95654128 760807424 -0.0899392143 0.2058269233 -0.0897389576 596 1305031249.3847539425 0.1237535104 0.1425743379 0.1777237803 0.0451959497 0.0296420000 235589718 95654128 760807424 -0.0790280700 0.1972771287 -0.0823029727 597 1305031249.4178340435 0.1207848117 0.1425378395 0.1777237803 0.0452367551 0.0217440000 235593390 95654128 760807424 -0.0797989145 0.1956558526 -0.0802636817 598 1305031249.4537220001 0.1268588603 0.1425116205 0.1777237803 0.0452787697 0.0247500000 235765626 95654128 760807424 -0.0852480158 0.1970346123 -0.0836359784 599 1305031249.4859149456 0.1316527575 0.1424934922 0.1777237803 0.0453229850 0.0212230000 235769266 95654128 760807424 -0.0889021903 0.1968341023 -0.0890617967 600 1305031249.5177340508 0.1307817549 0.1424739726 0.1777237803 0.0453314396 0.0213240000 235770938 95654128 760807424 -0.0881807134 0.1935663670 -0.0908607244 601 1305031249.5543251038 0.1335692108 0.1424591561 0.1777237803 0.0454516999 0.0248110000 235774722 95654128 760807424 -0.0867923349 0.1881367266 -0.0978465900 602 1305031249.5859050751 0.1418715417 0.1424581800 0.1777237803 0.0456388659 0.0213940000 235948210 95654128 760807424 -0.0942614079 0.1921705157 -0.1033732668 603 1305031249.6180789471 0.1459283531 0.1424639348 0.1777237803 0.0456571571 0.0213280000 235950082 95654128 760807424 -0.0992231742 0.1858647913 -0.1103740931 604 1305031249.6542129517 0.1449014395 0.1424679704 0.1777237803 0.0458706208 0.0220120000 236124346 95654128 760807424 -0.0950299650 0.1836576015 -0.1100349575 605 1305031249.6856739521 0.1453723460 0.1424727710 0.1777237803 0.0459956816 0.0215030000 236297110 95654128 760807424 -0.0954809263 0.1882661283 -0.1054336727 606 1305031249.7177898884 0.1480915844 0.1424820430 0.1777237803 0.0460591965 0.0255030000 236300614 95654128 760807424 -0.0998134613 0.1839756370 -0.1102004126 607 1305031249.7539620399 0.1456224024 0.1424872166 0.1777237803 0.0461093264 0.0215910000 236474034 95654128 760807424 -0.0895392969 0.1828894317 -0.1053350270 608 1305031249.7854170799 0.1447314620 0.1424909078 0.1777237803 0.0461443257 0.0215100000 236646622 95654128 760807424 -0.0871998370 0.1797592640 -0.1049376056 609 1305031249.8186020851 0.1475800276 0.1424992643 0.1777237803 0.0461538482 0.0254570000 236650406 95654128 760807424 -0.0905032754 0.1731791049 -0.1100462377 610 1305031249.8537468910 0.1480925083 0.1425084335 0.1777237803 0.0462551549 0.0217490000 236824370 95654128 760807424 -0.0843973234 0.1694011539 -0.1105824187 611 1305031249.8855249882 0.1516239345 0.1425233525 0.1777237803 0.0462828796 0.0217290000 236996198 95654128 760807424 -0.0885300711 0.1646388322 -0.1149795949 612 1305031249.9170649052 0.1518970430 0.1425386690 0.1777237803 0.0463118753 0.0217020000 237169614 95654128 760807424 -0.0900078565 0.1593005359 -0.1157585979 613 1305031249.9533979893 0.1533150673 0.1425562488 0.1777237803 0.0463160307 0.0252440000 237171558 95654128 760807424 -0.0892502964 0.1541002244 -0.1171854883 614 1305031249.9851789474 0.1570690721 0.1425798853 0.1777237803 0.0463238080 0.0251960000 237345566 95654128 760807424 -0.0923381448 0.1486996412 -0.1221608073 615 1305031250.0164399147 0.1594742090 0.1426073557 0.1777237803 0.0463062607 0.0276920000 237349238 95654128 760807424 -0.0930260271 0.1453778148 -0.1243067309 616 1305031250.0531940460 0.1596028209 0.1426349458 0.1777237803 0.0463711365 0.0219320000 237522074 95654128 760807424 -0.0950283855 0.1365368664 -0.1259719878 617 1305031250.0845069885 0.1620074958 0.1426663438 0.1777237803 0.0464666828 0.0215250000 237525690 95654128 760807424 -0.0997998565 0.1325376928 -0.1281860918 618 1305031250.1208500862 0.1636549085 0.1427003058 0.1777237803 0.0465864179 0.0226650000 237698290 95654128 760807424 -0.1021246910 0.1361944377 -0.1255354434 619 1305031250.1532480717 0.1660016328 0.1427379493 0.1777237803 0.0468517504 0.0253290000 237701906 95654128 760807424 -0.1070231646 0.1401728243 -0.1225591898 620 1305031250.1853280067 0.1674291790 0.1427777739 0.1777237803 0.0468600887 0.0219090000 237875766 95654128 760807424 -0.1087449268 0.1413456053 -0.1210409403 621 1305031250.2214460373 0.1667748690 0.1428164166 0.1777237803 0.0468619498 0.0217610000 238048790 95654128 760807424 -0.1089809164 0.1393044591 -0.1191166490 622 1305031250.2537350655 0.1646401137 0.1428515029 0.1777237803 0.0469626923 0.0218980000 238052262 95654128 760807424 -0.1169173121 0.1338819414 -0.1166845337 623 1305031250.2852239609 0.1651078910 0.1428872274 0.1777237803 0.0469765488 0.0255480000 238224898 95654128 760807424 -0.1200196221 0.1294342130 -0.1174422875 624 1305031250.3208620548 0.1645305902 0.1429219123 0.1777237803 0.0470079318 0.0315080000 238399494 95654128 760807424 -0.1219672188 0.1265279651 -0.1164040491 625 1305031250.3517000675 0.1659952104 0.1429588296 0.1777237803 0.0470241008 0.0225660000 238403110 95654128 760807424 -0.1259060055 0.1249400750 -0.1174766123 626 1305031250.3851490021 0.1715464592 0.1430044967 0.1777237803 0.0470328972 0.0222390000 238574622 95654128 760807424 -0.1320997775 0.1222613752 -0.1213765591 627 1305031250.4215359688 0.1766800880 0.1430582058 0.1777237803 0.0470494924 0.0251480000 238578462 95654128 760807424 -0.1390550584 0.1204397157 -0.1252862960 628 1305031250.4540181160 0.1767909527 0.1431119204 0.1777237803 0.0471371087 0.0221360000 238753866 95654128 760807424 -0.1411906332 0.1210151315 -0.1235124767 629 1305031250.4856131077 0.1715252995 0.1431570927 0.1777237803 0.0471511471 0.0220890000 238755666 95654128 760807424 -0.1428929269 0.1209229752 -0.1164285094 630 1305031250.5215380192 0.1752837449 0.1432080874 0.1777237803 0.0471336641 0.0221460000 238759306 95654128 760807424 -0.1453073770 0.1227403581 -0.1183132827 631 1305031250.5536580086 0.1782338023 0.1432635956 0.1782338023 0.0471217185 0.0220200000 238934342 95654128 760807424 -0.1471571326 0.1249783933 -0.1185856685 632 1305031250.5853788853 0.1731018126 0.1433108080 0.1782338023 0.0471208978 0.0257220000 238937798 95654128 760807424 -0.1487601995 0.1248620525 -0.1123904511 633 1305031250.6213030815 0.1709194779 0.1433544236 0.1782338023 0.0471072727 0.0221530000 238941638 95654128 760807424 -0.1520299762 0.1251102537 -0.1085256636 634 1305031250.6535439491 0.1739542782 0.1434026883 0.1782338023 0.0471297150 0.0222080000 239114578 95654128 760807424 -0.1561115384 0.1268372387 -0.1098619774 635 1305031250.6852970123 0.1704997867 0.1434453609 0.1782338023 0.0471570384 0.0223250000 239118250 95654128 760807424 -0.1521935463 0.1310141087 -0.1049598530 636 1305031250.7216401100 0.1672179997 0.1434827393 0.1782338023 0.0471372311 0.0221330000 239290974 95654128 760807424 -0.1571372598 0.1313820630 -0.1006719917 637 1305031250.7534279823 0.1720482856 0.1435275832 0.1782338023 0.0471137495 0.0222120000 239294670 95654128 760807424 -0.1651019156 0.1316011995 -0.1035918519 638 1305031250.7853651047 0.1718484759 0.1435719733 0.1782338023 0.0470894085 0.0220940000 239298198 95654128 760807424 -0.1623674333 0.1361504793 -0.1021796465 639 1305031250.8217930794 0.1675045341 0.1436094264 0.1782338023 0.0470556416 0.0221130000 239300350 95654128 760807424 -0.1597467959 0.1385918856 -0.0971017703 640 1305031250.8538279533 0.1684139818 0.1436481836 0.1782338023 0.0470311780 0.0220130000 239473358 95654128 760807424 -0.1702667922 0.1390188485 -0.0968852341 641 1305031250.8820140362 0.1683410853 0.1436867060 0.1782338023 0.0469970115 0.0313970000 239475174 95654128 760807424 -0.1719594002 0.1401304454 -0.0962674618 642 1305031250.9217998981 0.1688956916 0.1437259724 0.1782338023 0.0469638533 0.0228790000 239478926 95654128 760807424 -0.1736473292 0.1416018605 -0.0966117606 643 1305031250.9535419941 0.1738319844 0.1437727935 0.1782338023 0.0469462427 0.0220890000 239482710 95654128 760807424 -0.1782358140 0.1398503929 -0.1019397229 644 1305031250.9853079319 0.1788087785 0.1438271972 0.1788087785 0.0469167552 0.0221580000 239484366 95654128 760807424 -0.1852569282 0.1394003928 -0.1062177941 645 1305031251.0214879513 0.1696066111 0.1438671653 0.1788087785 0.0468958489 0.0221600000 239488206 95654128 760807424 -0.1743470579 0.1417042613 -0.0983751863 646 1305031251.0534679890 0.1713715196 0.1439097417 0.1788087785 0.0469039942 0.0234630000 239662874 95654128 760807424 -0.1760996282 0.1405001283 -0.1009465083 647 1305031251.0851860046 0.1746326387 0.1439572269 0.1788087785 0.0469081730 0.0224920000 239664802 95654128 760807424 -0.1820073128 0.1368931979 -0.1053294912 648 1305031251.1214449406 0.1786899120 0.1440108267 0.1788087785 0.0469167485 0.0223770000 239668442 95654128 760807424 -0.1833327264 0.1343700439 -0.1105011553 649 1305031251.1537809372 0.1792171299 0.1440650737 0.1792171299 0.0470168913 0.0225970000 239670426 95654128 760807424 -0.1796349138 0.1323062927 -0.1133616343 650 1305031251.1851599216 0.1787271202 0.1441183999 0.1792171299 0.0470550193 0.0325730000 239845018 95654128 760807424 -0.1759004891 0.1268806607 -0.1161345467 651 1305031251.2204658985 0.1781324446 0.1441706488 0.1792171299 0.0470914124 0.0230770000 239848802 95654136 760807424 -0.1728063971 0.1225636527 -0.1189538017 652 1305031251.2524240017 0.1738107353 0.1442161091 0.1792171299 0.0471641176 0.0258990000 240020498 95654136 760807424 -0.1621772498 0.1240449324 -0.1172793359 653 1305031251.2844820023 0.1741651893 0.1442619729 0.1792171299 0.0473764407 0.0225150000 240024226 95654136 760807424 -0.1585236490 0.1200846508 -0.1203318983 654 1305031251.3190040588 0.1713984311 0.1443034660 0.1792171299 0.0475052463 0.0254710000 240197066 95654136 760807424 -0.1512120366 0.1169012859 -0.1207031757 655 1305031251.3532440662 0.1714642197 0.1443449328 0.1792171299 0.0476127927 0.0224230000 240200738 95654136 760807424 -0.1494947225 0.1138189733 -0.1235427335 656 1305031251.3870069981 0.1697289795 0.1443836280 0.1792171299 0.0476727856 0.0221980000 240375414 95654136 760807424 -0.1388512254 0.1181669459 -0.1220155135 657 1305031251.4210500717 0.1700958908 0.1444227638 0.1792171299 0.0477792866 0.0223880000 240377358 95654136 760807424 -0.1372499019 0.1138447896 -0.1245003492 658 1305031251.4496629238 0.1678076386 0.1444583032 0.1792171299 0.0478564258 0.0223370000 240551450 95654136 760807424 -0.1305803061 0.1123852506 -0.1235509813 659 1305031251.4890139103 0.1655330658 0.1444902831 0.1792171299 0.0479575610 0.0263920000 240725038 95654136 760807424 -0.1255184263 0.1155749708 -0.1212491840 660 1305031251.5207729340 0.1628196687 0.1445180549 0.1792171299 0.0480702624 0.0226180000 240898626 95654136 760807424 -0.1193876639 0.1145413071 -0.1197772920 661 1305031251.5530450344 0.1589258462 0.1445398518 0.1792171299 0.0482008584 0.0222020000 240902298 95654136 760807424 -0.1120801121 0.1117539555 -0.1178434193 662 1305031251.5887598991 0.1587911546 0.1445613795 0.1792171299 0.0482371875 0.0221320000 241073822 95654136 760807424 -0.1109126508 0.1142066717 -0.1172173172 663 1305031251.6208739281 0.1593695581 0.1445837146 0.1792171299 0.0482818800 0.0221810000 241077550 95654136 760807424 -0.1101625636 0.1174256802 -0.1177639216 664 1305031251.6528749466 0.1600730270 0.1446070419 0.1792171299 0.0483565740 0.0221300000 241251702 95654136 760807424 -0.1108994409 0.1165910959 -0.1199184731 665 1305031251.6897680759 0.1626912504 0.1446342362 0.1792171299 0.0483968215 0.0219670000 241424210 95654136 760807424 -0.1142822728 0.1195875704 -0.1214781329 666 1305031251.7204608917 0.1618559659 0.1446600946 0.1792171299 0.0484732193 0.0220370000 241427682 95654136 760807424 -0.1122003049 0.1212360486 -0.1207332909 667 1305031251.7531440258 0.1562191993 0.1446774246 0.1792171299 0.0485856590 0.0318820000 241429554 95654136 760807424 -0.1055940017 0.1150984392 -0.1192887574 668 1305031251.7892498970 0.1592164189 0.1446991896 0.1792171299 0.0486246421 0.0226860000 241602886 95654136 760807424 -0.1072086170 0.1173603460 -0.1213706806 669 1305031251.8209791183 0.1636242867 0.1447274782 0.1792171299 0.0486699682 0.0219050000 241606558 95654136 760807424 -0.1117963791 0.1223438457 -0.1244306862 670 1305031251.8537969589 0.1557322592 0.1447439032 0.1792171299 0.0488039259 0.0217930000 241779130 95654136 760807424 -0.1045610011 0.1175552458 -0.1198054776 671 1305031251.8896539211 0.1549659967 0.1447591374 0.1792171299 0.0488234890 0.0217360000 241782858 95654136 760807424 -0.1027460620 0.1117211133 -0.1219669953 672 1305031251.9219300747 0.1565360874 0.1447766626 0.1792171299 0.0488330535 0.0216580000 241955070 95654136 760807424 -0.1043369994 0.1221878380 -0.1197764874 673 1305031251.9538369179 0.1523518711 0.1447879185 0.1792171299 0.0488498892 0.0216040000 241958686 95654136 760807424 -0.1009090468 0.1314925700 -0.1114493459 674 1305031251.9898068905 0.1507592201 0.1447967780 0.1792171299 0.0488563782 0.0216260000 242133746 95654136 760807424 -0.0981067717 0.1300812066 -0.1111816838 675 1305031252.0221600533 0.1486030519 0.1448024169 0.1792171299 0.0488843659 0.0214790000 242135674 95654136 760807424 -0.0986665711 0.1303804964 -0.1089633927 676 1305031252.0537619591 0.1476844549 0.1448066803 0.1792171299 0.0488925430 0.0217400000 242309186 95654136 760807424 -0.0991521701 0.1366893351 -0.1068673357 677 1305031252.0895619392 0.1460595876 0.1448085309 0.1792171299 0.0489672317 0.0217020000 242311114 95654136 760807424 -0.0974751487 0.1452361345 -0.1026424319 678 1305031252.1221520901 0.1418262720 0.1448041323 0.1792171299 0.0490495069 0.0252300000 242484682 95654136 760807424 -0.0932778493 0.1467775106 -0.0993125588 679 1305031252.1539709568 0.1372957379 0.1447930743 0.1792171299 0.0492121979 0.0216460000 242488242 95654136 760807424 -0.0891231447 0.1491488963 -0.0955791622 680 1305031252.1897890568 0.1336096376 0.1447766281 0.1792171299 0.0492176009 0.0251440000 242660238 95654136 760807424 -0.0881089941 0.1577283740 -0.0884039178 681 1305031252.2220859528 0.1447537541 0.1447765945 0.1792171299 0.0491947393 0.0218500000 242663966 95654136 760807424 -0.1008626819 0.1739339679 -0.0893987343 682 1305031252.2530639172 0.1401855797 0.1447698628 0.1792171299 0.0493002512 0.0217630000 242839886 95654136 760807424 -0.0986440778 0.1755370498 -0.0835233554 683 1305031252.2888779640 0.1308473796 0.1447494785 0.1792171299 0.0493797850 0.0217920000 242841758 95654136 760807424 -0.0913423225 0.1722219586 -0.0759394616 684 1305031252.3206090927 0.1356083155 0.1447361142 0.1792171299 0.0493488779 0.0219370000 242845230 95654136 760807424 -0.0961336792 0.1778721511 -0.0766570494 685 1305031252.3528549671 0.1353770047 0.1447224513 0.1792171299 0.0493505748 0.0274280000 243017662 95654136 760807424 -0.0972339809 0.1810863912 -0.0748082921 686 1305031252.3893189430 0.1346597522 0.1447077826 0.1792171299 0.0493330235 0.0222080000 243021246 95654136 760807424 -0.0966902301 0.1814692169 -0.0747467726 687 1305031252.4217019081 0.1363485903 0.1446956149 0.1792171299 0.0493248947 0.0220180000 243195730 95654136 760807424 -0.0930741429 0.1821035445 -0.0785248429 688 1305031252.4538249969 0.1320654154 0.1446772571 0.1792171299 0.0493078080 0.0230380000 243197386 95654136 760807424 -0.0954963192 0.1823659390 -0.0745512843 689 1305031252.4895589352 0.1350863725 0.1446633371 0.1792171299 0.0492757261 0.0221110000 243201058 95654136 760807424 -0.0989057049 0.1846915931 -0.0758626610 690 1305031252.5221700668 0.1330463439 0.1446465009 0.1792171299 0.0492495874 0.0252620000 243202786 95654136 760807424 -0.0984860212 0.1835533828 -0.0747184157 691 1305031252.5537741184 0.1316054761 0.1446276282 0.1792171299 0.0492214350 0.0220750000 243206442 95654136 760807424 -0.0960048735 0.1823920012 -0.0742923096 692 1305031252.5897459984 0.1373243630 0.1446170743 0.1792171299 0.0491915820 0.0218890000 243209970 95654136 760807424 -0.0990719795 0.1841356158 -0.0789935291 693 1305031252.6221249104 0.1293402761 0.1445950299 0.1792171299 0.0491781254 0.0220570000 243384278 95654136 760807424 -0.0963476002 0.1822387874 -0.0710648894 694 1305031252.6578559875 0.1315078139 0.1445761722 0.1792171299 0.0491605089 0.0317000000 243387806 95654136 760807424 -0.0987236053 0.1824769080 -0.0707543120 695 1305031252.6889979839 0.1327493936 0.1445591553 0.1792171299 0.0491816220 0.0224180000 243389622 95654136 760807424 -0.1040336266 0.1826985478 -0.0691962838 696 1305031252.7216539383 0.1349629611 0.1445453677 0.1792171299 0.0492464483 0.0220850000 243393094 95654136 760807424 -0.1069040596 0.1821062416 -0.0702301338 697 1305031252.7578220367 0.1399582922 0.1445387865 0.1792171299 0.0493391982 0.0219100000 243396934 95654136 760807424 -0.1153059453 0.1791865677 -0.0750497729 698 1305031252.7896919250 0.1376446784 0.1445289095 0.1792171299 0.0495091036 0.0219290000 243568638 95654136 760807424 -0.1106901169 0.1764008552 -0.0754604563 699 1305031252.8224050999 0.1482523382 0.1445342363 0.1792171299 0.0497131299 0.0222540000 243742554 95654136 760807424 -0.1223109141 0.1788489372 -0.0827650651 700 1305031252.8539779186 0.1479230821 0.1445390775 0.1792171299 0.0496983961 0.0222400000 243745914 95654136 760807424 -0.1183172688 0.1766420305 -0.0840186030 701 1305031252.8897290230 0.1473787278 0.1445431284 0.1792171299 0.0497303767 0.0220760000 243747898 95654136 760807424 -0.1150487289 0.1736206859 -0.0851738304 702 1305031252.9206719398 0.1487927735 0.1445491820 0.1792171299 0.0497314893 0.0328700000 243751370 95654136 760807424 -0.1148795858 0.1717192829 -0.0867471471 703 1305031252.9578649998 0.1467978060 0.1445523806 0.1792171299 0.0497922107 0.0323060000 243924550 95654136 760807424 -0.1130971611 0.1665247679 -0.0866055265 704 1305031252.9894239902 0.1515141875 0.1445622696 0.1792171299 0.0498646672 0.0230430000 243927910 95654136 760807424 -0.1176593527 0.1660331935 -0.0900747851 705 1305031253.0196959972 0.1539667547 0.1445756093 0.1792171299 0.0499430946 0.0222770000 244102398 95654136 760807424 -0.1218580008 0.1662416756 -0.0909174979 706 1305031253.0574259758 0.1568843126 0.1445930437 0.1792171299 0.0499958362 0.0224470000 244104254 95654136 760807424 -0.1253175139 0.1632901430 -0.0935406014 707 1305031253.0895500183 0.1558492929 0.1446089648 0.1792171299 0.0500232342 0.0223600000 244280206 95654136 760807424 -0.1235179231 0.1572570056 -0.0960827842 708 1305031253.1197240353 0.1565116346 0.1446257765 0.1792171299 0.0500418028 0.0224270000 244281878 95654136 760807424 -0.1234576926 0.1533007324 -0.0974213406 709 1305031253.1573839188 0.1612411588 0.1446492115 0.1792171299 0.0501571041 0.0223690000 244455190 95654136 760807424 -0.1284388900 0.1470433772 -0.1040000021 710 1305031253.1892180443 0.1633859724 0.1446756013 0.1792171299 0.0502165952 0.0222970000 244458622 95654136 760807424 -0.1340324730 0.1493507773 -0.1035875604 711 1305031253.2180271149 0.1638016403 0.1447025015 0.1792171299 0.0502181654 0.0223090000 244460494 95654136 760807424 -0.1366464645 0.1539357752 -0.1012638137 712 1305031253.2578470707 0.1669362783 0.1447337287 0.1792171299 0.0502015597 0.0256080000 244635746 95654136 760807424 -0.1414696276 0.1520688534 -0.1040436476 713 1305031253.2897419930 0.1667609215 0.1447646224 0.1792171299 0.0501697421 0.0222680000 244637562 95654136 760807424 -0.1411663890 0.1485379338 -0.1045714617 714 1305031253.3220069408 0.1613674462 0.1447878756 0.1792171299 0.0501530624 0.0222950000 244641106 95654136 760807424 -0.1356598437 0.1432939619 -0.1013500392 715 1305031253.3578300476 0.1567199081 0.1448045638 0.1792171299 0.0501275661 0.0222560000 244644834 95654136 760807424 -0.1292207241 0.1355059296 -0.0992807150 716 1305031253.3880970478 0.1578855664 0.1448228333 0.1792171299 0.0500950102 0.0222160000 244817338 95654136 760807424 -0.1300898790 0.1389966458 -0.0988108814 717 1305031253.4213519096 0.1569103003 0.1448396917 0.1792171299 0.0500636423 0.0220970000 244821066 95654136 760807424 -0.1295335144 0.1365762502 -0.0981564075 718 1305031253.4579629898 0.1571628898 0.1448568549 0.1792171299 0.0500342912 0.0221060000 244824634 95654136 760807424 -0.1296486706 0.1383349895 -0.0966729522 719 1305031253.4896900654 0.1572856605 0.1448741412 0.1792171299 0.0500009000 0.0222860000 244826506 95654136 760807424 -0.1309036911 0.1432617903 -0.0937075093 720 1305031253.5207340717 0.1579593271 0.1448923150 0.1792171299 0.0499689219 0.0220770000 244829978 95654136 760807424 -0.1313391924 0.1406883001 -0.0949836373 721 1305031253.5578539371 0.1608326882 0.1449144237 0.1792171299 0.0499381109 0.0222120000 244831962 95654136 760807424 -0.1339615583 0.1381592005 -0.0979545861 722 1305031253.5898048878 0.1665874124 0.1449444417 0.1792171299 0.0499117361 0.0220940000 245006066 95654136 760807424 -0.1424389482 0.1455153376 -0.0989479423 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:27:39 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 -nan 0.0095650000 199188344 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0293967985 0.0273978142 0.0293967985 0.0122532947 0.0222910000 200224754 95654128 760807424 -0.0000512189 0.0078813881 0.0104352748 3 1305031102.2432110310 0.0239448454 0.0262468246 0.0293967985 0.0087729221 0.0176440000 200075578 95654128 760807424 -0.0014772195 0.0065541063 0.0237032287 4 1305031102.2753260136 0.0206664987 0.0248517431 0.0293967985 0.0077520026 0.0188010000 200199126 95654128 760807424 -0.0017937166 0.0074250000 0.0370605662 5 1305031102.3112668991 0.0151143102 0.0229042565 0.0293967985 0.0071916058 0.0205240000 200251546 95654128 760807424 -0.0002048081 0.0047190329 0.0516170524 6 1305031102.3432331085 0.0148207247 0.0215570012 0.0293967985 0.0072500836 0.0187160000 200254050 95654128 760807424 -0.0001770949 0.0067322105 0.0636116415 7 1305031102.3753290176 0.0159072038 0.0207498873 0.0293967985 0.0067049258 0.0176660000 200257630 95654128 760807424 0.0010887964 0.0083463797 0.0759305730 8 1305031102.4112579823 0.0130422721 0.0197864354 0.0293967985 0.0088435889 0.0175980000 200261302 95654128 760807424 -0.0015906175 0.0113058118 0.0862112790 9 1305031102.4432709217 0.0132201109 0.0190568438 0.0293967985 0.0094463346 0.0176780000 200387406 95654128 760807424 -0.0040900675 0.0172785483 0.0960513204 10 1305031102.4753179550 0.0153934136 0.0186905008 0.0293967985 0.0089426291 0.0176130000 200439850 95654128 760807424 -0.0015312491 0.0172374789 0.1103453115 11 1305031102.5112190247 0.0177937951 0.0186089821 0.0293967985 0.0086166413 0.0209220000 200566106 95654128 760807424 -0.0001670406 0.0167230256 0.1243237406 12 1305031102.5432200432 0.0199326873 0.0187192908 0.0293967985 0.0082813873 0.0178910000 200615198 95654128 760807424 -0.0013629720 0.0158951506 0.1377551556 13 1305031102.5752859116 0.0266524088 0.0193295307 0.0293967985 0.0082755087 0.0176680000 200618846 95654128 760807424 -0.0010821735 0.0113853188 0.1531054080 14 1305031102.6112329960 0.0298633222 0.0200819444 0.0298633222 0.0080118977 0.0177380000 200622726 95654128 760807424 -0.0024759702 0.0096447654 0.1660378724 15 1305031102.6432650089 0.0223894976 0.0202357812 0.0298633222 0.0086899452 0.0177880000 200624562 95654128 760807424 -0.0092648910 0.0179799050 0.1736902297 16 1305031102.6752851009 0.0248749685 0.0205257304 0.0298633222 0.0084803398 0.0208790000 200752066 95654128 760807424 -0.0099917576 0.0207336806 0.1868217736 17 1305031102.7112629414 0.0302869808 0.0210999216 0.0302869808 0.0085534954 0.0178970000 200802986 95654128 760807424 -0.0091691362 0.0203097966 0.2007929981 18 1305031102.7432339191 0.0297793671 0.0215821131 0.0302869808 0.0084764381 0.0177170000 200809746 95654128 760807424 -0.0088750590 0.0270409565 0.2122559845 19 1305031102.7754719257 0.0377412438 0.0224325936 0.0377412438 0.0082666468 0.0177650000 200813194 95654136 760807424 -0.0041622710 0.0274648182 0.2270838469 20 1305031102.8112320900 0.0390785262 0.0232648903 0.0390785262 0.0082106858 0.0177470000 200815142 95654136 760807424 -0.0053771902 0.0310450066 0.2393950373 21 1305031102.8432900906 0.0441586189 0.0242598297 0.0441586189 0.0080477284 0.0177900000 200943138 95654136 760807424 -0.0057256161 0.0314008221 0.2536264062 22 1305031102.8753631115 0.0447717793 0.0251921911 0.0447717793 0.0081551684 0.0178490000 200992582 95654136 760807424 -0.0097924899 0.0343657322 0.2651891708 23 1305031102.9111850262 0.0468253605 0.0261327636 0.0468253605 0.0079842716 0.0176780000 200994350 95654136 760807424 -0.0123387435 0.0369306467 0.2769716680 24 1305031102.9432289600 0.0471221358 0.0270073208 0.0471221358 0.0082908711 0.0177030000 200997910 95654136 760807424 -0.0202461034 0.0384959169 0.2865271866 25 1305031102.9752030373 0.0458406471 0.0277606539 0.0471221358 0.0083659445 0.0176520000 201001486 95654136 760807424 -0.0285464600 0.0434480160 0.2963119447 26 1305031103.0112149715 0.0488355309 0.0285712261 0.0488355309 0.0082282317 0.0177130000 201003342 95654136 760807424 -0.0284691807 0.0463993922 0.3075529337 27 1305031103.0432269573 0.0521112718 0.0294430796 0.0521112718 0.0080845621 0.0177350000 201006902 95654136 760807424 -0.0286958832 0.0492543690 0.3191321790 28 1305031103.0753190517 0.0597768910 0.0305264300 0.0597768910 0.0082757217 0.0257080000 201134082 95654136 760807424 -0.0234280247 0.0492397547 0.3321553171 29 1305031103.1112399101 0.0565176047 0.0314226774 0.0597768910 0.0084100188 0.0186010000 201182418 95654136 760807424 -0.0241707433 0.0574083924 0.3393851519 30 1305031103.1433179379 0.0605113246 0.0323922990 0.0605113246 0.0083149722 0.0177310000 201185906 95654136 760807424 -0.0226395559 0.0593608059 0.3497196138 31 1305031103.1754519939 0.0582113937 0.0332251730 0.0605113246 0.0082438500 0.0177020000 201187610 95654136 760807424 -0.0248326492 0.0657875687 0.3572761714 32 1305031103.2112200260 0.0566720217 0.0339578870 0.0605113246 0.0085581128 0.0178420000 201314862 95654136 760807424 -0.0271730050 0.0714910850 0.3642750978 33 1305031103.2432160378 0.0584887676 0.0347012471 0.0605113246 0.0084239782 0.0177690000 201367922 95654136 760807424 -0.0260177702 0.0744718760 0.3717561960 34 1305031103.2753698826 0.0593010969 0.0354247720 0.0605113246 0.0084163803 0.0177710000 201375970 95654136 760807424 -0.0321993195 0.0751447231 0.3776014149 35 1305031103.3112099171 0.0674558505 0.0363399457 0.0674558505 0.0087774653 0.0179430000 201507798 95654136 760807424 -0.0304702036 0.0709476918 0.3864416182 36 1305031103.3432230949 0.0694276169 0.0372590477 0.0694276169 0.0090441828 0.0178820000 201554854 95654136 760807424 -0.0234216694 0.0727675855 0.3906261921 37 1305031103.3753271103 0.0704294816 0.0381555459 0.0704294816 0.0089287781 0.0179090000 201556702 95654136 760807424 -0.0218487121 0.0717697591 0.3918702900 38 1305031103.4112598896 0.0735456347 0.0390868640 0.0735456347 0.0089103971 0.0179090000 201560318 95654136 760807424 -0.0232921951 0.0658213720 0.3912100792 39 1305031103.4432799816 0.0714337602 0.0399162716 0.0735456347 0.0089196076 0.0212910000 201563878 95654136 760807424 -0.0240272228 0.0651364401 0.3867264092 40 1305031103.4752740860 0.0736754090 0.0407602501 0.0736754090 0.0089001601 0.0182340000 201565510 95654136 760807424 -0.0223092008 0.0603866987 0.3835399747 41 1305031103.5113329887 0.0735923499 0.0415610330 0.0736754090 0.0088241703 0.0188500000 201569342 95654136 760807424 -0.0229085181 0.0561345816 0.3779065013 42 1305031103.5434439182 0.0736516789 0.0423250960 0.0736754090 0.0087853831 0.0215230000 201698606 95654136 760807424 -0.0226556640 0.0505678020 0.3707361221 43 1305031103.5754740238 0.0682339296 0.0429276270 0.0736754090 0.0086965380 0.0184440000 201745794 95654136 760807424 -0.0251142811 0.0485615879 0.3597643077 44 1305031103.6112229824 0.0660569519 0.0434532935 0.0736754090 0.0086505705 0.0182590000 201876330 95654136 760807424 -0.0259521250 0.0443956666 0.3502620161 45 1305031103.6434450150 0.0637826249 0.0439050564 0.0736754090 0.0085878978 0.0213750000 201922098 95654136 760807424 -0.0249566305 0.0405007154 0.3404582441 46 1305031103.6755230427 0.0612786002 0.0442827421 0.0736754090 0.0085363602 0.0187150000 202051974 95654136 760807424 -0.0222215988 0.0370580852 0.3298816681 47 1305031103.7116100788 0.0578558482 0.0445715316 0.0736754090 0.0084718370 0.0182950000 202099450 95654136 760807424 -0.0203348491 0.0342285894 0.3183543682 48 1305031103.7433259487 0.0570898466 0.0448323298 0.0736754090 0.0084166209 0.0182310000 202101210 95654136 760807424 -0.0182220731 0.0279653259 0.3070162833 49 1305031103.7753419876 0.0499169491 0.0449360976 0.0736754090 0.0083537248 0.0182560000 202104858 95654136 760807424 -0.0179815143 0.0268716142 0.2919743061 50 1305031103.8112421036 0.0443630107 0.0449246358 0.0736754090 0.0084747484 0.0216900000 202108474 95654136 760807424 -0.0176191349 0.0261626579 0.2774062157 51 1305031103.8432509899 0.0352977365 0.0447358731 0.0736754090 0.0085125384 0.0185340000 202236462 95654136 760807424 -0.0216782466 0.0266286135 0.2615917623 52 1305031103.8753609657 0.0403649323 0.0446518166 0.0736754090 0.0087947663 0.0182850000 202283966 95654136 760807424 -0.0217924025 0.0148673384 0.2521127164 53 1305031103.9112210274 0.0425638482 0.0446124209 0.0736754090 0.0091025713 0.0182770000 202285982 95654136 760807424 -0.0208338983 0.0081399782 0.2407845259 54 1305031103.9432110786 0.0381914712 0.0444935145 0.0736754090 0.0090300884 0.0217460000 202289542 95654136 760807424 -0.0191351213 0.0062273573 0.2261055410 55 1305031103.9753730297 0.0382781476 0.0443805078 0.0736754090 0.0091422413 0.0185850000 202419166 95654136 760807424 -0.0160750747 0.0011236728 0.2140316218 56 1305031104.0112318993 0.0429734476 0.0443553817 0.0736754090 0.0093424710 0.0184710000 202465098 95654136 760807424 -0.0106301215 -0.0051397858 0.2037901729 57 1305031104.0432488918 0.0385227278 0.0442530545 0.0736754090 0.0093357985 0.0183480000 202594914 95654136 760807424 -0.0069402466 -0.0073564881 0.1881880909 58 1305031104.0754249096 0.0326797739 0.0440535151 0.0736754090 0.0093132181 0.0189050000 202642618 95654136 760807424 -0.0048780781 -0.0066131689 0.1721450537 59 1305031104.1112349033 0.0346020646 0.0438933211 0.0736754090 0.0093665425 0.0183860000 202644434 95654136 760807424 -0.0033076184 -0.0131997969 0.1602185369 60 1305031104.1432299614 0.0297438279 0.0436574962 0.0736754090 0.0093436368 0.0217980000 202773566 95654136 760807424 -0.0036387087 -0.0185188521 0.1449579298 61 1305031104.1754240990 0.0253357049 0.0433571389 0.0736754090 0.0093077705 0.0184990000 202821570 95654136 760807424 -0.0037928629 -0.0215751883 0.1302254200 62 1305031104.2112829685 0.0268597323 0.0430910517 0.0736754090 0.0093648505 0.0184020000 202951214 95654136 760807424 -0.0028333180 -0.0263332818 0.1175896004 63 1305031104.2431960106 0.0240463875 0.0427887555 0.0736754090 0.0093061343 0.0182560000 202999182 95654136 760807424 -0.0020489339 -0.0291719362 0.1044478714 64 1305031104.2755460739 0.0219325162 0.0424628767 0.0736754090 0.0092352208 0.0182990000 203002646 95654136 760807424 0.0001178773 -0.0310907867 0.0915493742 65 1305031104.3112189770 0.0231588744 0.0421658921 0.0736754090 0.0092050664 0.0183720000 203143290 95654136 760807424 0.0002123503 -0.0328751430 0.0793728903 66 1305031104.3433420658 0.0216221754 0.0418546236 0.0736754090 0.0091742574 0.0183350000 203198014 95654136 760807424 0.0007231854 -0.0331856906 0.0672676265 67 1305031104.3758370876 0.0226743929 0.0415683515 0.0736754090 0.0092537224 0.0182990000 203199694 95654136 760807424 0.0011687524 -0.0350123271 0.0560829192 68 1305031104.4115090370 0.0217566006 0.0412770023 0.0736754090 0.0092901094 0.0182800000 203203310 95654136 760807424 -0.0007565605 -0.0355443284 0.0447049476 69 1305031104.4432880878 0.0207247157 0.0409791430 0.0736754090 0.0092247887 0.0182630000 203207014 95654136 760807424 -0.0048274617 -0.0357992612 0.0328196660 70 1305031104.4754559994 0.0204693209 0.0406861456 0.0736754090 0.0091616146 0.0183010000 203208718 95654136 760807424 -0.0088850781 -0.0378204361 0.0230864529 71 1305031104.5113289356 0.0214989781 0.0404159038 0.0736754090 0.0093257371 0.0212380000 203212334 95654136 760807424 -0.0089687034 -0.0423353352 0.0154211111 72 1305031104.5433681011 0.0219539925 0.0401594884 0.0736754090 0.0093470452 0.0185360000 203347954 95654136 760807424 -0.0059010773 -0.0450341441 0.0074005490 73 1305031104.5753428936 0.0232041515 0.0399272235 0.0736754090 0.0094218247 0.0271320000 203388338 95654136 760807424 -0.0000122096 -0.0490714796 0.0006346973 74 1305031104.6113359928 0.0302722957 0.0397967515 0.0736754090 0.0096483891 0.0193030000 203523842 95654136 760807424 0.0076041827 -0.0580947883 -0.0039183344 75 1305031104.6432430744 0.0307746269 0.0396764565 0.0736754090 0.0098149592 0.0182800000 203697922 95654136 760807424 0.0116471825 -0.0578444451 -0.0158656184 76 1305031104.6755249500 0.0280598104 0.0395236059 0.0736754090 0.0097681506 0.0183840000 203869954 95654136 760807424 0.0120563032 -0.0612600073 -0.0274535641 77 1305031104.7112770081 0.0277433507 0.0393706155 0.0736754090 0.0098298347 0.0182930000 204044386 95654136 760807424 0.0103260465 -0.0623041764 -0.0381729528 78 1305031104.7432799339 0.0262106154 0.0392018976 0.0736754090 0.0098519567 0.0183510000 204216242 95654136 760807424 0.0116983410 -0.0613729246 -0.0499700382 79 1305031104.7753269672 0.0269601736 0.0390469391 0.0736754090 0.0099030344 0.0211840000 204390374 95654136 760807424 0.0105510168 -0.0578485355 -0.0597776771 80 1305031104.8114650249 0.0313834399 0.0389511453 0.0736754090 0.0099034219 0.0184480000 204564138 95654136 760807424 0.0131225493 -0.0533078946 -0.0682946444 81 1305031104.8432579041 0.0341851935 0.0388923064 0.0736754090 0.0098705771 0.0182850000 204736090 95654136 760807424 0.0110540604 -0.0489478558 -0.0756435841 82 1305031104.8753499985 0.0389621221 0.0388931578 0.0736754090 0.0098623071 0.0180830000 204778506 95654136 760807424 0.0067759459 -0.0433756858 -0.0815423951 83 1305031104.9115340710 0.0405554175 0.0389131850 0.0736754090 0.0098113236 0.0180230000 204913518 95654136 760807424 0.0088279517 -0.0406292826 -0.0848677233 84 1305031104.9432621002 0.0424728170 0.0389555616 0.0736754090 0.0097585588 0.0245960000 204954202 95654136 760807424 0.0084883701 -0.0379782058 -0.0849812329 85 1305031104.9752020836 0.0490181483 0.0390739450 0.0736754090 0.0097318291 0.0185970000 204957906 95654136 760807424 0.0067509962 -0.0303860530 -0.0832931027 86 1305031105.0112900734 0.0471111834 0.0391674013 0.0736754090 0.0096914529 0.0180300000 204961538 95654136 760807424 0.0102300346 -0.0292237028 -0.0790005177 87 1305031105.0433731079 0.0461304337 0.0392474361 0.0736754090 0.0096376100 0.0181770000 205094126 95654136 760807424 0.0095395632 -0.0278797969 -0.0726023912 88 1305031105.0753200054 0.0422573127 0.0392816392 0.0736754090 0.0095864861 0.0182730000 205267822 95654136 760807424 0.0097443517 -0.0290021095 -0.0641161501 89 1305031105.1112990379 0.0344664678 0.0392275362 0.0736754090 0.0095566361 0.0187590000 205308986 95654136 760807424 0.0091371546 -0.0334301665 -0.0540864579 90 1305031105.1431059837 0.0400556810 0.0392367378 0.0736754090 0.0095388264 0.0188250000 205443702 95654136 760807424 0.0034868931 -0.0245611798 -0.0420821384 91 1305031105.1751589775 0.0408597477 0.0392545731 0.0736754090 0.0095453310 0.0190870000 205617534 95654136 760807424 0.0028847165 -0.0195607785 -0.0290419348 92 1305031105.2112679482 0.0260642972 0.0391112005 0.0736754090 0.0098040091 0.0193460000 205658602 95654136 760807424 0.0035467763 -0.0299685393 -0.0151818991 93 1305031105.2432699203 0.0231557675 0.0389396367 0.0736754090 0.0098187974 0.0191290000 205794098 95654136 760807424 0.0016390230 -0.0290503781 -0.0019071773 94 1305031105.2752881050 0.0196561478 0.0387344932 0.0736754090 0.0098700965 0.0194410000 205968482 95654136 760807424 -0.0015769952 -0.0284782145 0.0104437573 95 1305031105.3112900257 0.0123940306 0.0384572252 0.0736754090 0.0098747395 0.0193930000 206141114 95654136 760807424 -0.0020709485 -0.0338812284 0.0244727172 96 1305031105.3433020115 0.0090842042 0.0381512562 0.0736754090 0.0098380730 0.0193060000 206184010 95654136 760807424 -0.0029122804 -0.0365791507 0.0407831296 97 1305031105.3753380775 0.0110622253 0.0378719879 0.0736754090 0.0098763137 0.0194330000 206319202 95654136 760807424 -0.0038724504 -0.0371923596 0.0560894161 98 1305031105.4112861156 0.0115199527 0.0376030895 0.0736754090 0.0099200716 0.0193520000 206360478 95654136 760807424 -0.0072359843 -0.0310812425 0.0664653331 99 1305031105.4433159828 0.0115507431 0.0373399345 0.0736754090 0.0098736465 0.0194010000 206363966 95654136 760807424 -0.0108777182 -0.0321102142 0.0822678134 100 1305031105.4752800465 0.0115784379 0.0370823196 0.0736754090 0.0098273866 0.0194500000 206367454 95654136 760807424 -0.0143147372 -0.0297309067 0.0961689502 101 1305031105.5113320351 0.0118785193 0.0368327770 0.0736754090 0.0098802738 0.0194390000 206369454 95654136 760807424 -0.0160451736 -0.0251640603 0.1093610823 102 1305031105.5432820320 0.0153636178 0.0366222950 0.0736754090 0.0098373255 0.0194840000 206372926 95654136 760807424 -0.0176918805 -0.0251351465 0.1246025264 103 1305031105.5754489899 0.0146149192 0.0364086312 0.0736754090 0.0098323088 0.0194840000 206374598 95654136 760807424 -0.0208142530 -0.0211238153 0.1375442743 104 1305031105.6113779545 0.0209728647 0.0362602104 0.0736754090 0.0097952121 0.0189920000 206378214 95654136 760807424 -0.0202550646 -0.0225994922 0.1532977372 105 1305031105.6432731152 0.0219172277 0.0361236105 0.0736754090 0.0097602390 0.0190970000 206381902 95654136 760807424 -0.0237560123 -0.0201231055 0.1664732397 106 1305031105.6751658916 0.0251634847 0.0360202131 0.0736754090 0.0097329501 0.0232630000 206513838 95654136 760807424 -0.0206078868 -0.0171689671 0.1807850897 107 1305031105.7113089561 0.0345640704 0.0360066043 0.0736754090 0.0097507315 0.0194770000 206557206 95654136 760807424 -0.0164734665 -0.0200713612 0.1978277117 108 1305031105.7433118820 0.0323158279 0.0359724304 0.0736754090 0.0097748558 0.0203070000 206560710 95654136 760807424 -0.0169431325 -0.0133865336 0.2096833587 109 1305031105.7753388882 0.0383449867 0.0359941970 0.0736754090 0.0097314605 0.0193870000 206694146 95654136 760807424 -0.0134887043 -0.0132953273 0.2252778411 110 1305031105.8112831116 0.0394661352 0.0360257601 0.0736754090 0.0096963233 0.0196810000 206737598 95654136 760807424 -0.0145484814 -0.0099170581 0.2399216294 111 1305031105.8432710171 0.0426434837 0.0360853792 0.0736754090 0.0096561299 0.0197500000 206741102 95654136 760807424 -0.0123525178 -0.0073235054 0.2540198565 112 1305031105.8753368855 0.0416527987 0.0361350883 0.0736754090 0.0096502035 0.0197830000 206873162 95654136 760807424 -0.0108583719 -0.0005406011 0.2664102614 113 1305031105.9112620354 0.0444525369 0.0362086941 0.0736754090 0.0096878969 0.0196630000 206916914 95654136 760807424 -0.0109352823 0.0031310280 0.2801681161 114 1305031105.9432721138 0.0441812873 0.0362786291 0.0736754090 0.0096621712 0.0194250000 206918618 95654136 760807424 -0.0107115041 0.0095880348 0.2926749885 115 1305031105.9753289223 0.0461084694 0.0363641060 0.0736754090 0.0096338379 0.0195070000 207052418 95654136 760807424 -0.0110504003 0.0144030349 0.3055074215 116 1305031106.0112850666 0.0502573773 0.0364838755 0.0736754090 0.0096270729 0.0227270000 207096086 95654136 760807424 -0.0096919574 0.0182299465 0.3183958828 117 1305031106.0433549881 0.0524586998 0.0366204125 0.0736754090 0.0095913090 0.0196400000 207229202 95654136 760807424 -0.0113874543 0.0221279338 0.3307994902 118 1305031106.0753300190 0.0542699210 0.0367699846 0.0736754090 0.0095590329 0.0226670000 207272754 95654136 760807424 -0.0124507071 0.0269063003 0.3421799839 119 1305031106.1113269329 0.0530238561 0.0369065718 0.0736754090 0.0095657278 0.0197060000 207276370 95654136 760807424 -0.0151708229 0.0348738469 0.3521887660 120 1305031106.1433548927 0.0584000237 0.0370856839 0.0736754090 0.0095541889 0.0195680000 207409078 95654136 760807424 -0.0174340159 0.0354053006 0.3641389012 121 1305031106.1755340099 0.0622831807 0.0372939276 0.0736754090 0.0095299636 0.0194920000 207452946 95654136 760807424 -0.0166478865 0.0384751260 0.3753904700 122 1305031106.2112751007 0.0688415989 0.0375525151 0.0736754090 0.0094955209 0.0195670000 207456562 95654136 760807424 -0.0179446060 0.0380235761 0.3862523139 123 1305031106.2432670593 0.0699968338 0.0378162901 0.0736754090 0.0094977131 0.0195840000 207458322 95654136 760807424 -0.0185545888 0.0422344990 0.3942590654 124 1305031106.2763850689 0.0688726828 0.0380667448 0.0736754090 0.0094633813 0.0196870000 207461810 95654136 760807424 -0.0192514304 0.0480710790 0.4001796544 125 1305031106.3112380505 0.0687808394 0.0383124576 0.0736754090 0.0094298975 0.0196690000 207463770 95654136 760807424 -0.0204371922 0.0516670756 0.4053911865 126 1305031106.3432579041 0.0657636002 0.0385303238 0.0736754090 0.0094090527 0.0261190000 207467330 95654136 760807424 -0.0202975441 0.0583736300 0.4087432325 127 1305031106.3753879070 0.0688797757 0.0387692959 0.0736754090 0.0093857124 0.0203660000 207600954 95654136 760807424 -0.0156327803 0.0592312291 0.4124823809 128 1305031106.4113199711 0.0779801533 0.0390756307 0.0779801533 0.0093905925 0.0227590000 207643218 95654136 760807424 -0.0137186451 0.0518558659 0.4164706469 129 1305031106.4432780743 0.0789423063 0.0393846747 0.0789423063 0.0094320065 0.0197820000 207658186 95654136 760807424 -0.0174125340 0.0493695997 0.4158924818 130 1305031106.4753448963 0.0779383257 0.0396812412 0.0789423063 0.0094161804 0.0196270000 207687290 95654136 760807424 -0.0204656944 0.0474002957 0.4121034443 131 1305031106.5111289024 0.0796080306 0.0399860259 0.0796080306 0.0094132735 0.0197260000 207688938 95654136 760807424 -0.0222047307 0.0420656838 0.4074788690 132 1305031106.5433020592 0.0766950771 0.0402641248 0.0796080306 0.0093847502 0.0198150000 207692498 95654136 760807424 -0.0204873756 0.0407103524 0.3988330960 133 1305031106.5752820969 0.0734509751 0.0405136500 0.0796080306 0.0093498932 0.0201720000 207696130 95654136 760807424 -0.0206083097 0.0385157727 0.3887462318 134 1305031106.6111509800 0.0691970512 0.0407277052 0.0796080306 0.0093386599 0.0202360000 207697946 95654136 760807424 -0.0216664486 0.0366420299 0.3770798445 135 1305031106.6432070732 0.0700779706 0.0409451146 0.0796080306 0.0093621844 0.0201780000 207701506 95654136 760807424 -0.0208494831 0.0304136593 0.3672150075 136 1305031106.6752789021 0.0633011460 0.0411094971 0.0796080306 0.0093396786 0.0201010000 207704954 95654136 760807424 -0.0242937766 0.0306120925 0.3536557853 137 1305031106.7115080357 0.0623840205 0.0412647856 0.0796080306 0.0093653518 0.0200710000 207706970 95654136 760807424 -0.0262550060 0.0254631899 0.3403455317 138 1305031106.7433409691 0.0593645349 0.0413959432 0.0796080306 0.0093473928 0.0200200000 207710530 95654136 760807424 -0.0267273318 0.0225103479 0.3269397318 139 1305031106.7753899097 0.0568981394 0.0415074698 0.0796080306 0.0093340090 0.0200260000 207712178 95654136 760807424 -0.0245007444 0.0195229426 0.3130774200 140 1305031106.8112890720 0.0523158684 0.0415846727 0.0796080306 0.0093120440 0.0199900000 207715794 95654136 760807424 -0.0236877315 0.0189812910 0.2969188690 141 1305031106.8434159756 0.0557875969 0.0416854026 0.0796080306 0.0093928799 0.0233180000 207719498 95654136 760807424 -0.0234168526 0.0095377285 0.2849022150 142 1305031106.8759050369 0.0549012162 0.0417784717 0.0796080306 0.0094178119 0.0202560000 207721202 95654136 760807424 -0.0197670590 0.0047327164 0.2702946663 143 1305031106.9112429619 0.0475096963 0.0418185502 0.0796080306 0.0094480566 0.0200890000 207724834 95654136 760807424 -0.0193925835 0.0066766068 0.2500900328 144 1305031106.9434390068 0.0500751249 0.0418758876 0.0796080306 0.0095180992 0.0198460000 207728338 95654136 760807424 -0.0173664447 -0.0018112250 0.2371024191 145 1305031106.9755470753 0.0505322218 0.0419355864 0.0796080306 0.0094863443 0.0198060000 207730242 95654136 760807424 -0.0173683222 -0.0090304799 0.2224692553 146 1305031107.0115759373 0.0399380140 0.0419219044 0.0796080306 0.0095121509 0.0234650000 207733914 95654136 760807424 -0.0191720836 -0.0054280516 0.1995044947 147 1305031107.0432810783 0.0386618786 0.0418997274 0.0796080306 0.0094901663 0.0199970000 207879886 95654136 760807424 -0.0193809140 -0.0116076656 0.1842553169 148 1305031107.0754320621 0.0371856093 0.0418678752 0.0796080306 0.0094701485 0.0230510000 207910338 95654136 760807424 -0.0220716558 -0.0199858341 0.1687376201 149 1305031107.1112289429 0.0326332860 0.0418058981 0.0796080306 0.0094434912 0.0193740000 207914154 95654136 760807424 -0.0219419952 -0.0190931130 0.1509414613 150 1305031107.1432600021 0.0283246152 0.0417160229 0.0796080306 0.0094212283 0.0191790000 208058098 95654136 760807424 -0.0191853791 -0.0185626764 0.1353483051 151 1305031107.1753990650 0.0311006922 0.0416457227 0.0796080306 0.0094086842 0.0191220000 208090450 95654136 760807424 -0.0168725569 -0.0268475693 0.1250873059 152 1305031107.2113580704 0.0342587531 0.0415971242 0.0796080306 0.0094347491 0.0191490000 208094066 95654136 760807424 -0.0152595546 -0.0326650068 0.1130545810 153 1305031107.2433779240 0.0277755056 0.0415067868 0.0796080306 0.0094082551 0.0190570000 208096002 95654136 760807424 -0.0155766662 -0.0330181867 0.0970472097 154 1305031107.2753980160 0.0270949807 0.0414132037 0.0796080306 0.0093896870 0.0220180000 208099506 95654136 760807424 -0.0136918342 -0.0375850946 0.0851369575 155 1305031107.3112258911 0.0301862210 0.0413407715 0.0796080306 0.0093846098 0.0191720000 208103138 95654136 760807424 -0.0120398905 -0.0444157124 0.0746912658 156 1305031107.3435089588 0.0292856023 0.0412634948 0.0796080306 0.0093903596 0.0233150000 208104914 95654136 760807424 -0.0083980933 -0.0502885915 0.0638412014 157 1305031107.3754129410 0.0234884638 0.0411502780 0.0796080306 0.0094576001 0.0192280000 208108562 95654136 760807424 -0.0046631419 -0.0465723723 0.0500306636 158 1305031107.4112710953 0.0219283998 0.0410286206 0.0796080306 0.0094388525 0.0189900000 208112194 95654136 760807424 -0.0017482631 -0.0481728017 0.0405301377 159 1305031107.4434189796 0.0179974437 0.0408837704 0.0796080306 0.0094208269 0.0189710000 208113954 95654136 760807424 0.0011294978 -0.0475463048 0.0321832187 160 1305031107.4753770828 0.0155470194 0.0407254157 0.0796080306 0.0093948748 0.0191470000 208117474 95654136 760807424 0.0047574490 -0.0492576808 0.0268886946 161 1305031107.5113520622 0.0139655452 0.0405592053 0.0796080306 0.0093758862 0.0188770000 208119434 95654136 760807424 0.0076389229 -0.0458253995 0.0208828300 162 1305031107.5436050892 0.0130977193 0.0403896900 0.0796080306 0.0093623358 0.0188770000 208123026 95654136 760807424 0.0121615790 -0.0469928049 0.0195779074 163 1305031107.5754539967 0.0104101487 0.0402057664 0.0796080306 0.0093501285 0.0189840000 208267846 95654136 760807424 0.0147360926 -0.0519590452 0.0207632501 164 1305031107.6112709045 0.0123783881 0.0400360873 0.0796080306 0.0093411496 0.0189980000 208298986 95654136 760807424 0.0165029392 -0.0443870537 0.0199458003 165 1305031107.6433229446 0.0120859994 0.0398666928 0.0796080306 0.0093130199 0.0190460000 208302746 95654136 760807424 0.0178891178 -0.0429381840 0.0213068873 166 1305031107.6755681038 0.0100348918 0.0396869832 0.0796080306 0.0092933477 0.0190150000 208306194 95654136 760807424 0.0173130687 -0.0428832807 0.0229449440 167 1305031107.7113070488 0.0093956292 0.0395055978 0.0796080306 0.0092688593 0.0274170000 208308026 95654136 760807424 0.0171811022 -0.0398608744 0.0240790322 168 1305031107.7435379028 0.0100778090 0.0393304324 0.0796080306 0.0092435752 0.0312700000 208311530 95654136 760807424 0.0151462927 -0.0358773172 0.0256016888 169 1305031107.7758018970 0.0089224018 0.0391505032 0.0796080306 0.0092204906 0.0218010000 208457230 95654136 760807424 0.0163317975 -0.0365188494 0.0286641847 170 1305031107.8115959167 0.0104226917 0.0389815161 0.0796080306 0.0091961345 0.0195950000 208488566 95654136 760807424 0.0182749107 -0.0350690968 0.0310018454 171 1305031107.8433320522 0.0136311203 0.0388332682 0.0796080306 0.0091734110 0.0196020000 208492070 95654136 760807424 0.0227314401 -0.0348357596 0.0333873704 172 1305031107.8753581047 0.0179969370 0.0387121267 0.0796080306 0.0091593459 0.0195870000 208495558 95654136 760807424 0.0278238449 -0.0377214998 0.0372553691 173 1305031107.9115409851 0.0181309972 0.0385931607 0.0796080306 0.0091742942 0.0300330000 208497574 95654136 760807424 0.0302447397 -0.0371504091 0.0397776440 174 1305031107.9431219101 0.0195993483 0.0384840008 0.0796080306 0.0091702481 0.0208320000 208501078 95654136 760807424 0.0351759084 -0.0374180116 0.0430767350 175 1305031107.9758069515 0.0193794146 0.0383748318 0.0796080306 0.0091667809 0.0195220000 208502782 95654136 760807424 0.0423720665 -0.0374901071 0.0460453071 176 1305031108.0113201141 0.0215492249 0.0382792317 0.0796080306 0.0091696474 0.0191970000 208646830 95654136 760807424 0.0527335852 -0.0365002453 0.0481924936 177 1305031108.0434179306 0.0236375555 0.0381965104 0.0796080306 0.0091478429 0.0191600000 208680282 95654136 760807424 0.0651662797 -0.0341999903 0.0499330014 178 1305031108.0753519535 0.0252169259 0.0381235914 0.0796080306 0.0091708890 0.0193530000 208822986 95654136 760807424 0.0761367083 -0.0357325040 0.0544459783 179 1305031108.1113779545 0.0182688870 0.0380126712 0.0796080306 0.0091537557 0.0190680000 208856418 95654136 760807424 0.0820244178 -0.0365337580 0.0574839823 180 1305031108.1433339119 0.0154086286 0.0378870932 0.0796080306 0.0091369734 0.0190260000 208859922 95654136 760807424 0.0918749943 -0.0334634967 0.0586622655 181 1305031108.1760580540 0.0083531048 0.0377239220 0.0796080306 0.0091648281 0.0191990000 208861826 95654136 760807424 0.1010777950 -0.0301581863 0.0591539331 182 1305031108.2114748955 0.0123972623 0.0375847645 0.0796080306 0.0091466459 0.0251710000 209006658 95654136 760807424 0.1145818681 -0.0328920409 0.0638417453 183 1305031108.2433469296 0.0226130467 0.0375029519 0.0796080306 0.0091284563 0.0195280000 209040110 95654136 760807424 0.1326275915 -0.0387912840 0.0688872561 184 1305031108.2753579617 0.0169065297 0.0373910148 0.0796080306 0.0091167293 0.0196560000 209041814 95654136 760807424 0.1390174776 -0.0343350917 0.0685932115 185 1305031108.3113319874 0.0130767440 0.0372595863 0.0796080306 0.0091537717 0.0192630000 209186810 95654136 760807424 0.1453414112 -0.0311915632 0.0705890656 186 1305031108.3432779312 0.0123796202 0.0371258230 0.0796080306 0.0091458653 0.0221470000 209218618 95654136 760807424 0.1535092294 -0.0282696411 0.0743707567 187 1305031108.3754100800 0.0146240955 0.0370054930 0.0796080306 0.0091252474 0.0193260000 209222082 95654136 760807424 0.1624340117 -0.0279076081 0.0777601376 188 1305031108.4113609791 0.0182196405 0.0369055682 0.0796080306 0.0091152992 0.0195940000 209225698 95654136 760807424 0.1759628654 -0.0280244295 0.0812324509 189 1305031108.4436099529 0.0203863364 0.0368181649 0.0796080306 0.0091136730 0.0196670000 209368326 95654136 760807424 0.1899890304 -0.0271988809 0.0842500702 190 1305031108.4754710197 0.0266286377 0.0367645358 0.0796080306 0.0091179495 0.0195920000 209401954 95654136 760807424 0.2040415108 -0.0304746907 0.0883447751 191 1305031108.5113780499 0.0342849083 0.0367515534 0.0796080306 0.0092436305 0.0194040000 209405586 95654136 760807424 0.2251225710 -0.0339372046 0.0926956236 192 1305031108.5437369347 0.0383052900 0.0367596458 0.0796080306 0.0092817313 0.0293530000 209407346 95654136 760807424 0.2409507930 -0.0346754678 0.0941840038 193 1305031108.5754139423 0.0333114639 0.0367417796 0.0796080306 0.0093301745 0.0201980000 209410994 95654136 760807424 0.2484835237 -0.0297092646 0.0903554633 194 1305031108.6114070415 0.0349364243 0.0367324736 0.0796080306 0.0093579615 0.0190950000 209554514 95654136 760807424 0.2624697685 -0.0295288786 0.0930435136 195 1305031108.6433029175 0.0327799916 0.0367122045 0.0796080306 0.0093887544 0.0190460000 209586618 95654136 760807424 0.2703673244 -0.0262719728 0.0925260633 196 1305031108.6753749847 0.0321099870 0.0366887238 0.0796080306 0.0093763945 0.0190320000 209590066 95654136 760807424 0.2803848684 -0.0236851647 0.0937585458 197 1305031108.7114109993 0.0351730511 0.0366810300 0.0796080306 0.0093764748 0.0220010000 209591994 95654136 760807424 0.2902641892 -0.0248901751 0.0977431312 198 1305031108.7435019016 0.0373338312 0.0366843270 0.0796080306 0.0093777241 0.0191880000 209735710 95654136 760807424 0.2967312932 -0.0261184499 0.1000324860 199 1305031108.7754929066 0.0370972641 0.0366864021 0.0796080306 0.0093567714 0.0190240000 209769634 95654136 760807424 0.3046929538 -0.0249477681 0.0983660296 200 1305031108.8112440109 0.0402781293 0.0367043607 0.0796080306 0.0093384518 0.0197040000 209771434 95654136 760807424 0.3089812398 -0.0265739746 0.0987418368 201 1305031108.8432641029 0.0416468307 0.0367289501 0.0796080306 0.0111362736 0.0190430000 209775194 95654136 760807424 0.3124972880 -0.0282230638 0.0974895656 202 1305031108.8765149117 0.0403956212 0.0367471019 0.0796080306 0.0113297841 0.0282730000 209778698 95654136 760807424 0.3136039972 -0.0278625805 0.0942253619 203 1305031108.9113640785 0.0429289527 0.0367775544 0.0796080306 0.0115144779 0.0201030000 209780458 95654136 760807424 0.3157860041 -0.0311277639 0.0928770900 204 1305031108.9432430267 0.0449243188 0.0368174895 0.0796080306 0.0116437866 0.0190520000 209784018 95654136 760807424 0.3130284846 -0.0328758918 0.0892927423 205 1305031108.9752678871 0.0414894074 0.0368402794 0.0796080306 0.0116194747 0.0192590000 209787722 95654136 760807424 0.3075575829 -0.0293105859 0.0820424259 206 1305031109.0112690926 0.0380597226 0.0368461990 0.0796080306 0.0115953252 0.0191950000 209789482 95654136 760807424 0.3087718487 -0.0285904091 0.0799339488 207 1305031109.0432770252 0.0387912095 0.0368555952 0.0796080306 0.0115786627 0.0191810000 209793026 95654136 760807424 0.3014715314 -0.0300058164 0.0791998655 208 1305031109.0754098892 0.0351530164 0.0368474097 0.0796080306 0.0115632288 0.0192810000 209796474 95654136 760807424 0.2904455066 -0.0255523436 0.0755689815 209 1305031109.1112821102 0.0343860351 0.0368356328 0.0796080306 0.0115441300 0.0193570000 209798490 95654136 760807424 0.2832121253 -0.0267293043 0.0766794682 210 1305031109.1433339119 0.0369440541 0.0368361491 0.0796080306 0.0115263430 0.0224270000 209802050 95654136 760807424 0.2700579762 -0.0291729886 0.0782676861 211 1305031109.1754639149 0.0328526646 0.0368172700 0.0796080306 0.0115382032 0.0195090000 209803698 95654136 760807424 0.2590381503 -0.0249381401 0.0750417486 212 1305031109.2113790512 0.0234675985 0.0367542999 0.0796080306 0.0115340264 0.0285660000 209807314 95654136 760807424 0.2509740293 -0.0158705320 0.0734306797 213 1305031109.2432899475 0.0256953891 0.0367023801 0.0796080306 0.0115274197 0.0205260000 209811074 95654136 760807424 0.2405323535 -0.0177536067 0.0757674426 214 1305031109.2753078938 0.0342721380 0.0366910238 0.0796080306 0.0115682116 0.0195470000 209812722 95654136 760807424 0.2300950438 -0.0266554113 0.0789406002 215 1305031109.3113288879 0.0299630389 0.0366597309 0.0796080306 0.0115709365 0.0195390000 209816338 95654136 760807424 0.2158705294 -0.0232131332 0.0752936006 216 1305031109.3432478905 0.0245534237 0.0366036831 0.0796080306 0.0115480422 0.0196940000 209819914 95654136 760807424 0.2022868842 -0.0181247219 0.0732567236 217 1305031109.3753969669 0.0286619384 0.0365670852 0.0796080306 0.0115544678 0.0198670000 209821762 95654136 760807424 0.1936390549 -0.0216140170 0.0767471492 218 1305031109.4113290310 0.0290200245 0.0365324657 0.0796080306 0.0115394559 0.0197830000 209964926 95654136 760807424 0.1848597378 -0.0191697590 0.0748757422 219 1305031109.4433019161 0.0243798047 0.0364769741 0.0796080306 0.0115174301 0.0197440000 209999550 95654136 760807424 0.1701679230 -0.0148514714 0.0738825649 220 1305031109.4753630161 0.0246632211 0.0364232752 0.0796080306 0.0115003705 0.0200120000 210001214 95654136 760807424 0.1559893489 -0.0158373397 0.0749528483 221 1305031109.5112729073 0.0265982039 0.0363788179 0.0796080306 0.0114873115 0.0198320000 210005030 95654136 760807424 0.1400932223 -0.0173014663 0.0749372244 222 1305031109.5432939529 0.0211336445 0.0363101459 0.0796080306 0.0114653180 0.0238700000 210006790 95654136 760807424 0.1226766631 -0.0141633851 0.0723029748 223 1305031109.5753619671 0.0168303307 0.0362227925 0.0796080306 0.0114408924 0.0200860000 210150350 95654136 760807424 0.1084656939 -0.0105797742 0.0693432465 224 1305031109.6113100052 0.0155316172 0.0361304212 0.0796080306 0.0114335934 0.0198710000 210185194 95654136 760807424 0.0932003260 -0.0085581504 0.0672129095 225 1305031109.6432290077 0.0151189100 0.0360370367 0.0796080306 0.0114108213 0.0197250000 210187138 95654136 760807424 0.0815210715 -0.0069105886 0.0661850050 226 1305031109.6752629280 0.0122373356 0.0359317283 0.0796080306 0.0113874462 0.0227040000 210190586 95654136 760807424 0.0669030175 -0.0044760695 0.0641689226 227 1305031109.7113120556 0.0123127811 0.0358276800 0.0796080306 0.0113913631 0.0234980000 210194202 95654136 760807424 0.0534292459 -0.0009039314 0.0630619302 228 1305031109.7432739735 0.0131693920 0.0357283016 0.0796080306 0.0113773953 0.0199870000 210335438 95654136 760807424 0.0413383432 0.0000059009 0.0640350878 229 1305031109.7752768993 0.0150236934 0.0356378885 0.0796080306 0.0113592241 0.0197240000 210370534 95654136 760807424 0.0285129659 0.0003172379 0.0662937835 230 1305031109.8113710880 0.0140351392 0.0355439635 0.0796080306 0.0113488589 0.0196880000 210374150 95654136 760807424 0.0132679697 0.0020345538 0.0654487535 231 1305031109.8432960510 0.0141844861 0.0354514982 0.0796080306 0.0113292251 0.0232930000 210375910 95654136 760807424 -0.0007042037 0.0020877635 0.0668598339 232 1305031109.8753058910 0.0135606555 0.0353571411 0.0796080306 0.0113236387 0.0290720000 210518314 95654136 760807424 -0.0187302455 0.0039975899 0.0683496073 233 1305031109.9112648964 0.0176875480 0.0352813059 0.0796080306 0.0113049422 0.0204390000 210551910 95654136 760807424 -0.0332521498 0.0019149827 0.0737574324 234 1305031109.9432990551 0.0167889353 0.0352022787 0.0796080306 0.0113117653 0.0228790000 210555454 95654136 760807424 -0.0445376821 0.0096042659 0.0733858868 235 1305031109.9752581120 0.0175804906 0.0351272924 0.0796080306 0.0113175279 0.0196430000 210558886 95654136 760807424 -0.0605765209 0.0084884763 0.0774191469 236 1305031110.0112559795 0.0194363240 0.0350608052 0.0796080306 0.0113012521 0.0196620000 210699722 95654136 760807424 -0.0737543330 0.0095769046 0.0807352662 237 1305031110.0432989597 0.0204925165 0.0349993357 0.0796080306 0.0112815190 0.0194580000 210735162 95654136 760807424 -0.0865368694 0.0097556645 0.0838304088 238 1305031110.0753190517 0.0198791418 0.0349358054 0.0796080306 0.0112676612 0.0194970000 210738610 95654136 760807424 -0.1002942026 0.0115265176 0.0853082016 239 1305031110.1113250256 0.0200946201 0.0348737084 0.0796080306 0.0112685375 0.0193580000 210740426 95654136 760807424 -0.1156015992 0.0123465536 0.0877582952 240 1305031110.1434319019 0.0234960150 0.0348263014 0.0796080306 0.0112600078 0.0193860000 210743986 95654136 760807424 -0.1301033199 0.0075396197 0.0928822830 241 1305031110.1756410599 0.0217231233 0.0347719313 0.0796080306 0.0112390828 0.0194450000 210887042 95654136 760807424 -0.1406522095 0.0144037921 0.0919950381 242 1305031110.2116370201 0.0238740258 0.0347268987 0.0796080306 0.0112284553 0.0283820000 210920790 95654136 760807424 -0.1528971642 0.0116451345 0.0950946510 243 1305031110.2433230877 0.0273853391 0.0346966865 0.0796080306 0.0112106375 0.0203040000 210924294 95654136 760807424 -0.1650372595 0.0093423966 0.0986408815 244 1305031110.2793209553 0.0298817120 0.0346769530 0.0796080306 0.0111995294 0.0193810000 210927910 95654136 760807424 -0.1720847040 0.0093813138 0.1000792980 245 1305031110.3114039898 0.0285341777 0.0346518804 0.0796080306 0.0111801000 0.0201110000 211068586 95654136 760807424 -0.1875368953 0.0105478037 0.0988953486 246 1305031110.3433549404 0.0281897355 0.0346256116 0.0796080306 0.0111574555 0.0223970000 211104098 95654136 760807424 -0.1989646107 0.0136683136 0.0975916684 247 1305031110.3792810440 0.0294478796 0.0346046491 0.0796080306 0.0111582822 0.0193930000 211244290 95654136 760807424 -0.2106182277 0.0143837472 0.0978670940 248 1305031110.4114689827 0.0290098656 0.0345820895 0.0796080306 0.0111474151 0.0192410000 211279870 95654136 760807424 -0.2235262692 0.0209358186 0.0950476453 249 1305031110.4432599545 0.0294960551 0.0345616636 0.0796080306 0.0111532855 0.0192990000 211422362 95654136 760807424 -0.2314806283 0.0231629778 0.0943566635 250 1305031110.4793310165 0.0317806862 0.0345505397 0.0796080306 0.0111951589 0.0191500000 211456410 95654136 760807424 -0.2479275763 0.0191871859 0.0973905101 251 1305031110.5114290714 0.0329023413 0.0345439732 0.0796080306 0.0111816391 0.0192580000 211598682 95654136 760807424 -0.2617676258 0.0191444810 0.0980035514 252 1305031110.5434079170 0.0324165896 0.0345355312 0.0796080306 0.0111612736 0.0191540000 211634454 95654136 760807424 -0.2708276510 0.0246100370 0.0958873034 253 1305031110.5794260502 0.0344522819 0.0345352021 0.0796080306 0.0111458422 0.0194220000 211776010 95654136 760807424 -0.2777869105 0.0293006245 0.0959268287 254 1305031110.6113069057 0.0386943482 0.0345515767 0.0796080306 0.0111881092 0.0191970000 211811738 95654136 760807424 -0.2859921455 0.0224672779 0.1018005610 255 1305031110.6434180737 0.0388809443 0.0345685546 0.0796080306 0.0111796939 0.0191470000 211815298 95654136 760807424 -0.2982694805 0.0207350999 0.1024068370 256 1305031110.6796059608 0.0372253768 0.0345789329 0.0796080306 0.0111929789 0.0191980000 211955422 95654136 760807424 -0.3042830527 0.0286489911 0.0980143845 257 1305031110.7114119530 0.0402037725 0.0346008194 0.0796080306 0.0111762174 0.0191900000 212014050 95654136 760807424 -0.3090734184 0.0270478036 0.1008057371 258 1305031110.7432489395 0.0404384769 0.0346234460 0.0796080306 0.0111773902 0.0226110000 212066954 95654136 760807424 -0.3172633946 0.0253055990 0.1017908081 259 1305031110.7791929245 0.0416332223 0.0346505107 0.0796080306 0.0111578875 0.0194050000 212070570 95654136 760807424 -0.3188319802 0.0272714756 0.1014304832 260 1305031110.8113861084 0.0420505106 0.0346789723 0.0796080306 0.0111371214 0.0190930000 212074074 95654136 760807424 -0.3196103871 0.0282639451 0.1011471897 261 1305031110.8432180882 0.0423755869 0.0347084612 0.0796080306 0.0111229021 0.0192750000 212240230 95654136 760807424 -0.3234262168 0.0280124545 0.1021009162 262 1305031110.8793129921 0.0431198888 0.0347405659 0.0796080306 0.0111025696 0.0192200000 212251814 95654136 760807424 -0.3232113421 0.0265866816 0.1032008529 263 1305031110.9113330841 0.0431649126 0.0347725976 0.0796080306 0.0110913869 0.0231300000 212255318 95654136 760807424 -0.3207740188 0.0285134800 0.1028924882 264 1305031110.9438619614 0.0437179953 0.0348064817 0.0796080306 0.0111021010 0.0194570000 212257078 95654136 760807424 -0.3174009919 0.0274059381 0.1044239476 265 1305031110.9793450832 0.0441402309 0.0348417034 0.0796080306 0.0111219505 0.0192650000 212260798 95654136 760807424 -0.3066788316 0.0296596531 0.1041814163 266 1305031111.0114309788 0.0477946736 0.0348903988 0.0796080306 0.0111085586 0.0225930000 212264358 95654136 760807424 -0.2960016131 0.0282605328 0.1077501178 267 1305031111.0433270931 0.0435778573 0.0349229361 0.0796080306 0.0111031696 0.0197010000 212266078 95654136 760807424 -0.2927914560 0.0278623197 0.1053278297 268 1305031111.0792829990 0.0391115174 0.0349385651 0.0796080306 0.0110884319 0.0195320000 212269638 95654136 760807424 -0.2883795202 0.0309483707 0.1030723602 269 1305031111.1115078926 0.0417583473 0.0349639175 0.0796080306 0.0110765276 0.0195820000 212271598 95654136 760807424 -0.2803470194 0.0261881817 0.1073078290 270 1305031111.1432569027 0.0420582965 0.0349901930 0.0796080306 0.0110590511 0.0196170000 212275102 95654136 760807424 -0.2728053331 0.0236368831 0.1083324775 271 1305031111.1793260574 0.0417360365 0.0350150854 0.0796080306 0.0110789061 0.0196580000 212278718 95654136 760807424 -0.2615964413 0.0254217181 0.1089863330 272 1305031111.2114329338 0.0377999917 0.0350253240 0.0796080306 0.0110991984 0.0197530000 212443374 95654136 760807424 -0.2539443076 0.0252963528 0.1057646424 273 1305031111.2432360649 0.0381857716 0.0350369007 0.0796080306 0.0111070430 0.0298790000 212455402 95654136 760807424 -0.2485068142 0.0221333876 0.1073118374 274 1305031111.2793080807 0.0415600501 0.0350607078 0.0796080306 0.0111209200 0.0209440000 212459018 95654136 760807424 -0.2389249504 0.0202721693 0.1112668887 275 1305031111.3115470409 0.0328260288 0.0350525817 0.0796080306 0.0111884606 0.0198400000 212460722 95654136 760807424 -0.2295155823 0.0273555163 0.1030596271 276 1305031111.3433969021 0.0326044858 0.0350437118 0.0796080306 0.0111785184 0.0198340000 212626362 95654136 760807424 -0.2219730169 0.0280799828 0.1029780507 277 1305031111.3791339397 0.0385613628 0.0350564109 0.0796080306 0.0112557000 0.0201900000 212638634 95654136 760807424 -0.2026830763 0.0167563949 0.1112066135 278 1305031111.4112958908 0.0326562636 0.0350477773 0.0796080306 0.0112893017 0.0231360000 212640282 95654136 760807424 -0.1931608766 0.0214903653 0.1063738465 279 1305031111.4433860779 0.0353437103 0.0350488380 0.0796080306 0.0113043136 0.0200380000 212643842 95654136 760807424 -0.1713948548 0.0208874363 0.1108161286 280 1305031111.4792590141 0.0356398076 0.0350509486 0.0796080306 0.0113283940 0.0199240000 212647490 95654136 760807424 -0.1579817683 0.0201442428 0.1124666706 281 1305031111.5112640858 0.0325758457 0.0350421404 0.0796080306 0.0114257806 0.0200630000 212649354 95654136 760807424 -0.1482416689 0.0189577900 0.1097074226 282 1305031111.5432500839 0.0345807746 0.0350405044 0.0796080306 0.0114130209 0.0199940000 212652914 95654136 760807424 -0.1400638819 0.0165716130 0.1110201254 283 1305031111.5792369843 0.0324392878 0.0350313128 0.0796080306 0.0114700209 0.0292270000 212654730 95654136 760807424 -0.1283146292 0.0187622029 0.1071216017 284 1305031111.6112709045 0.0288065374 0.0350093946 0.0796080306 0.0114554238 0.0206800000 212658122 95654136 760807424 -0.1090818346 0.0157900751 0.1066870168 285 1305031111.6433949471 0.0369550027 0.0350162212 0.0796080306 0.0114461229 0.0196690000 212661882 95654136 760807424 -0.1012470201 0.0088705346 0.1122054905 286 1305031111.6793200970 0.0291422084 0.0349956827 0.0796080306 0.0115943442 0.0196500000 212663642 95654136 760807424 -0.0747726336 0.0140574584 0.1095016077 287 1305031111.7117600441 0.0276761223 0.0349701790 0.0796080306 0.0115921451 0.0197820000 212667202 95654136 760807424 -0.0489507057 0.0123978667 0.1098652929 288 1305031111.7433860302 0.0318502672 0.0349593460 0.0796080306 0.0116017173 0.0195480000 212670706 95654136 760807424 -0.0280026942 0.0114483349 0.1134379655 289 1305031111.7794229984 0.0373851247 0.0349677397 0.0796080306 0.0117182654 0.0197860000 212672738 95654136 760807424 0.0025632884 0.0085874852 0.1136802062 290 1305031111.8114058971 0.0360843837 0.0349715902 0.0796080306 0.0117358168 0.0195360000 212838122 95654136 760807424 0.0119272899 0.0049585043 0.1144838333 291 1305031111.8432989120 0.0334427468 0.0349663365 0.0796080306 0.0117501056 0.0197700000 212850534 95654136 760807424 0.0234494731 0.0060994164 0.1130150184 292 1305031111.8794419765 0.0260315873 0.0349357380 0.0796080306 0.0117364538 0.0202880000 212852294 95654136 760807424 0.0298047997 0.0054465793 0.1094924435 293 1305031111.9113540649 0.0294607952 0.0349170522 0.0796080306 0.0117320838 0.0208360000 212856038 95654136 760807424 0.0347662158 -0.0004316489 0.1108948812 294 1305031111.9433000088 0.0273265410 0.0348912341 0.0796080306 0.0117233086 0.0203730000 213018878 95654136 760807424 0.0490888022 0.0017089515 0.1106680557 295 1305031111.9794490337 0.0261311159 0.0348615388 0.0796080306 0.0117888825 0.0197890000 213031478 95654136 760807424 0.0704238415 0.0055581937 0.1121824980 296 1305031112.0114328861 0.0298512504 0.0348446122 0.0796080306 0.0117723466 0.0200790000 213035038 95654136 760807424 0.0889138728 0.0042071813 0.1132419705 297 1305031112.0432701111 0.0284088254 0.0348229428 0.0796080306 0.0117588915 0.0199310000 213036942 95654136 760807424 0.1037286744 0.0058336616 0.1110609770 298 1305031112.0793390274 0.0291205533 0.0348038073 0.0796080306 0.0117866140 0.0199920000 213040558 95654136 760807424 0.1207727343 0.0036550290 0.1103403866 299 1305031112.1114230156 0.0245372038 0.0347694708 0.0796080306 0.0118589231 0.0199300000 213044006 95654136 760807424 0.1283152848 0.0040331893 0.1076182202 300 1305031112.1443419456 0.0237029418 0.0347325824 0.0796080306 0.0118432381 0.0195990000 213045710 95654136 760807424 0.1424215734 0.0047252583 0.1061402485 301 1305031112.1793899536 0.0249380637 0.0347000425 0.0796080306 0.0118538689 0.0197040000 213211674 95654136 760807424 0.1613261104 0.0035427692 0.1063402891 302 1305031112.2112538815 0.0290130340 0.0346812113 0.0796080306 0.0118641588 0.0209300000 213224590 95654136 760807424 0.1715495586 -0.0028793369 0.1104484648 303 1305031112.2433691025 0.0329596438 0.0346755296 0.0796080306 0.0118607498 0.0209980000 213226550 95654136 760807424 0.1841237545 -0.0092422273 0.1108620092 304 1305031112.2793529034 0.0298711844 0.0346597258 0.0796080306 0.0118606465 0.0208190000 213230126 95654136 760807424 0.1895104349 -0.0106362877 0.1097621843 305 1305031112.3113119602 0.0330344848 0.0346543972 0.0796080306 0.0118479305 0.0208840000 213232086 95654136 760807424 0.2018099129 -0.0157074202 0.1084107384 306 1305031112.3433229923 0.0304387901 0.0346406207 0.0796080306 0.0118294501 0.0209220000 213235590 95654136 760807424 0.2144832909 -0.0148303267 0.1070689037 307 1305031112.3793599606 0.0299004912 0.0346251805 0.0796080306 0.0118115599 0.0210180000 213239462 95654136 760807424 0.2254586220 -0.0148676326 0.1064232215 308 1305031112.4114420414 0.0298090708 0.0346095438 0.0796080306 0.0118008046 0.0208160000 213241094 95654136 760807424 0.2383795828 -0.0152526340 0.1056385934 309 1305031112.4433910847 0.0320251435 0.0346011800 0.0796080306 0.0117865268 0.0207550000 213244854 95654136 760807424 0.2515379190 -0.0180964898 0.1063261405 310 1305031112.4794180393 0.0323720351 0.0345939892 0.0796080306 0.0117693436 0.0206900000 213246670 95654136 760807424 0.2587243021 -0.0177800115 0.1050408557 311 1305031112.5115039349 0.0338457935 0.0345915835 0.0796080306 0.0117567657 0.0208360000 213250302 95654136 760807424 0.2674083412 -0.0190771762 0.1043941826 312 1305031112.5432119370 0.0349219888 0.0345926425 0.0796080306 0.0117471328 0.0205390000 213253806 95654136 760807424 0.2779218853 -0.0205129851 0.1034899876 313 1305031112.5792520046 0.0352583900 0.0345947694 0.0796080306 0.0117319340 0.0308900000 213255766 95654136 760807424 0.2859308422 -0.0195448119 0.1021939293 314 1305031112.6112608910 0.0316309333 0.0345853305 0.0796080306 0.0117895628 0.0214320000 213259270 95654136 760807424 0.3026030660 -0.0161652174 0.0999940485 315 1305031112.6432459354 0.0326461196 0.0345791743 0.0796080306 0.0117868847 0.0206230000 213261246 95654136 760807424 0.3113662302 -0.0159818735 0.1013747677 316 1305031112.6799519062 0.0353884622 0.0345817353 0.0796080306 0.0117789790 0.0238620000 213264862 95654136 760807424 0.3143593967 -0.0169256758 0.1030873507 317 1305031112.7112510204 0.0354591236 0.0345845031 0.0796080306 0.0117764558 0.0242650000 213268510 95654136 760807424 0.3170850277 -0.0149302315 0.1028288305 318 1305031112.7432448864 0.0301768631 0.0345706426 0.0796080306 0.0117662654 0.0206570000 213270270 95654136 760807424 0.3196615875 -0.0072395569 0.1014532074 319 1305031112.7793099880 0.0360202789 0.0345751869 0.0796080306 0.0117541717 0.0211100000 213274086 95654136 760807424 0.3195766807 -0.0103945890 0.1048648655 320 1305031112.8113100529 0.0417634286 0.0345976501 0.0796080306 0.0117609962 0.0208560000 213277534 95654136 760807424 0.3121047318 -0.0132541098 0.1071801856 321 1305031112.8432860374 0.0406336337 0.0346164538 0.0796080306 0.0117426580 0.0206320000 213279438 95654136 760807424 0.3066373169 -0.0098191183 0.1057532728 322 1305031112.8794209957 0.0404280461 0.0346345023 0.0796080306 0.0117713507 0.0312690000 213283038 95654136 760807424 0.3073306978 -0.0095908511 0.1064446568 323 1305031112.9114110470 0.0427083410 0.0346594987 0.0796080306 0.0117576932 0.0217500000 213284998 95654136 760807424 0.3002775311 -0.0108732525 0.1081278846 324 1305031112.9433209896 0.0440652333 0.0346885287 0.0796080306 0.0117424603 0.0241690000 213288470 95654136 760807424 0.2959537208 -0.0123761212 0.1094187200 325 1305031112.9792780876 0.0424871929 0.0347125246 0.0796080306 0.0117917936 0.0208270000 213292286 95654136 760807424 0.2917734981 -0.0120073482 0.1087857783 326 1305031113.0113530159 0.0377343521 0.0347217940 0.0796080306 0.0117795909 0.0248210000 213293934 95654136 760807424 0.2861044407 -0.0082656667 0.1057141721 327 1305031113.0432310104 0.0374441929 0.0347301194 0.0796080306 0.0117622437 0.0209660000 213297678 95654136 760807424 0.2804971933 -0.0088849002 0.1060468629 328 1305031113.0792510509 0.0418211780 0.0347517385 0.0796080306 0.0117689484 0.0210360000 213299510 95654136 760807424 0.2723537683 -0.0147347003 0.1078071669 329 1305031113.1113159657 0.0369123369 0.0347583056 0.0796080306 0.0117597907 0.0210750000 213303158 95654136 760807424 0.2594353557 -0.0123675363 0.1029810905 330 1305031113.1433060169 0.0309330393 0.0347467139 0.0796080306 0.0117448232 0.0212770000 213306718 95654136 760807424 0.2480591536 -0.0079746787 0.0999110341 331 1305031113.1793429852 0.0348585472 0.0347470518 0.0796080306 0.0117519570 0.0282860000 213308734 95654236 760807424 0.2396260500 -0.0127461180 0.1018619686 332 1305031113.2112588882 0.0323521234 0.0347398381 0.0796080306 0.0117344144 0.0213720000 213312182 95654236 760807424 0.2253676802 -0.0130881080 0.0993624479 333 1305031113.2432270050 0.0269457530 0.0347164325 0.0796080306 0.0117178456 0.0210310000 213314174 95654236 760807424 0.2115546167 -0.0101184472 0.0958535075 334 1305031113.2793118954 0.0329571888 0.0347111653 0.0796080306 0.0117423466 0.0214370000 213317734 95654236 760807424 0.2003984302 -0.0163956285 0.0985172838 335 1305031113.3114519119 0.0357926674 0.0347143936 0.0796080306 0.0117409691 0.0224330000 213321438 95654236 760807424 0.1844045818 -0.0226478875 0.0986050516 336 1305031113.3432519436 0.0254874323 0.0346869325 0.0796080306 0.0117388859 0.0217850000 213323142 95654236 760807424 0.1644231081 -0.0162261706 0.0928421542 337 1305031113.3793120384 0.0223124474 0.0346502129 0.0796080306 0.0117366826 0.0215520000 213326918 95654236 760807424 0.1457724422 -0.0141850812 0.0938278511 338 1305031113.4116249084 0.0223170295 0.0346137242 0.0796080306 0.0117245505 0.0215020000 213330478 95654236 760807424 0.1252044290 -0.0171361994 0.0969191045 339 1305031113.4432659149 0.0138792461 0.0345525606 0.0796080306 0.0117106774 0.0215330000 213332382 95654236 760807424 0.1074740067 -0.0109178498 0.0955422223 340 1305031113.4793109894 0.0130619733 0.0344893529 0.0796080306 0.0117114376 0.0310930000 213335926 95654236 760807424 0.0893342495 -0.0105684875 0.0956233814 341 1305031113.5115230083 0.0129173584 0.0344260920 0.0796080306 0.0116985805 0.0224820000 213337886 95654236 760807424 0.0681212768 -0.0134753548 0.0970831662 342 1305031113.5432419777 0.0153957671 0.0343704477 0.0796080306 0.0117027825 0.0214510000 213341390 95654236 760807424 0.0510593653 -0.0167296175 0.0987702683 343 1305031113.5793011189 0.0126218507 0.0343070407 0.0796080306 0.0116950042 0.0216300000 213345150 95654236 760807424 0.0359786749 -0.0127578061 0.0983455181 344 1305031113.6112680435 0.0124058472 0.0342433745 0.0796080306 0.0116827497 0.0214680000 213346910 95654236 760807424 0.0197690781 -0.0124469865 0.0989552736 345 1305031113.6432220936 0.0133779570 0.0341828950 0.0796080306 0.0116680277 0.0214480000 213350614 95654236 760807424 0.0048689349 -0.0127136782 0.0994675979 346 1305031113.6792879105 0.0140250055 0.0341246352 0.0796080306 0.0116615540 0.0214480000 213352454 95654236 760807424 -0.0135123087 -0.0119531453 0.1003194153 347 1305031113.7119309902 0.0171911940 0.0340758357 0.0796080306 0.0116486578 0.0216010000 213356102 95654236 760807424 -0.0256204158 -0.0141673163 0.1014316678 348 1305031113.7435901165 0.0161939003 0.0340244508 0.0796080306 0.0116321300 0.0246860000 213359662 95654236 760807424 -0.0381775722 -0.0116098216 0.1017214954 349 1305031113.7793200016 0.0168744344 0.0339753104 0.0796080306 0.0116334096 0.0245820000 213361622 95654236 760807424 -0.0579197183 -0.0126832221 0.1024999544 350 1305031113.8112370968 0.0168224182 0.0339263021 0.0796080306 0.0116176818 0.0215260000 213365054 95654236 760807424 -0.0723025575 -0.0119036771 0.1025518402 351 1305031113.8432950974 0.0162263904 0.0338758750 0.0796080306 0.0116056991 0.0216330000 213367014 95654236 760807424 -0.0850914866 -0.0072720936 0.1028623357 352 1305031113.8792810440 0.0222818535 0.0338429374 0.0796080306 0.0116465706 0.0214640000 213370630 95654236 760807424 -0.1081214547 -0.0137694292 0.1062449738 353 1305031113.9112899303 0.0201440826 0.0338041305 0.0796080306 0.0116427333 0.0214360000 213374334 95654236 760807424 -0.1172600389 -0.0093305223 0.1061730757 354 1305031113.9432909489 0.0216182638 0.0337697071 0.0796080306 0.0116274961 0.0214560000 213376022 95654236 760807424 -0.1302188635 -0.0096502388 0.1074751839 355 1305031113.9792931080 0.0214897636 0.0337351157 0.0796080306 0.0116130397 0.0214860000 213379838 95654236 760807424 -0.1444851160 -0.0086179869 0.1080300510 356 1305031114.0112569332 0.0222747810 0.0337029238 0.0796080306 0.0116116616 0.0215260000 213543310 95654236 760807424 -0.1635656059 -0.0058257412 0.1076211184 357 1305031114.0433011055 0.0255054887 0.0336799618 0.0796080306 0.0115970325 0.0310750000 213556246 95654236 760807424 -0.1819649786 -0.0059175463 0.1083103195 358 1305031114.0792849064 0.0245331712 0.0336544121 0.0796080306 0.0115881633 0.0221570000 213559862 95654236 760807424 -0.1954494268 -0.0053982460 0.1096557453 359 1305031114.1112630367 0.0237615686 0.0336268554 0.0796080306 0.0115731462 0.0289720000 213722986 95654236 760807424 -0.2066112459 -0.0017793088 0.1096057817 360 1305031114.1432840824 0.0244526193 0.0336013714 0.0796080306 0.0115709159 0.0217730000 213737662 95654236 760807424 -0.2175287902 -0.0007627341 0.1115324199 361 1305031114.1793370247 0.0257127192 0.0335795192 0.0796080306 0.0115785857 0.0214370000 213901314 95654236 760807424 -0.2253523767 -0.0051042154 0.1149406806 362 1305031114.2113029957 0.0240801945 0.0335532780 0.0796080306 0.0115876328 0.0213060000 213914162 95654236 760807424 -0.2385540307 0.0054285866 0.1122845709 363 1305031114.2433369160 0.0252894722 0.0335305127 0.0796080306 0.0115752821 0.0219590000 213917866 95654236 760807424 -0.2556017041 0.0046470203 0.1146950200 364 1305031114.2793900967 0.0266269688 0.0335115469 0.0796080306 0.0116041163 0.0214300000 214079486 95654236 760807424 -0.2754120231 0.0052752993 0.1164202020 365 1305031114.3114290237 0.0270184241 0.0334937575 0.0796080306 0.0115947454 0.0211900000 214094506 95654236 760807424 -0.2847588658 0.0072652665 0.1177086681 366 1305031114.3433310986 0.0275832266 0.0334776085 0.0796080306 0.0115879374 0.0212170000 214257258 95654236 760807424 -0.2892327905 0.0058855042 0.1205532998 367 1305031114.3793199062 0.0291004870 0.0334656818 0.0796080306 0.0115776515 0.0211810000 214270658 95654236 760807424 -0.2962116301 0.0043071760 0.1227096021 368 1305031114.4113969803 0.0290784352 0.0334537599 0.0796080306 0.0115701358 0.0302550000 214274162 95654236 760807424 -0.3113116026 0.0054688547 0.1234256998 369 1305031114.4433450699 0.0310056973 0.0334471256 0.0796080306 0.0115595039 0.0218650000 214435190 95654236 760807424 -0.3270143569 0.0085563809 0.1242457107 370 1305031114.4793319702 0.0320743285 0.0334434153 0.0796080306 0.0115672696 0.0210120000 214450290 95654236 760807424 -0.3407998979 0.0069562141 0.1259609163 371 1305031114.5112659931 0.0313672461 0.0334378192 0.0796080306 0.0115590338 0.0212480000 214612890 95654236 760807424 -0.3457573950 0.0092710638 0.1257709563 372 1305031114.5432360172 0.0307988040 0.0334307251 0.0796080306 0.0115572072 0.0209910000 214626202 95654236 760807424 -0.3473029733 0.0058499407 0.1276888549 373 1305031114.5792369843 0.0311032012 0.0334244850 0.0796080306 0.0115463226 0.0210930000 214630018 95654236 760807424 -0.3525516689 0.0043473649 0.1292378902 374 1305031114.6113910675 0.0311783329 0.0334184793 0.0796080306 0.0115344066 0.0212440000 214792942 95654236 760807424 -0.3577354550 0.0072058327 0.1288173646 375 1305031114.6441500187 0.0314844362 0.0334133218 0.0796080306 0.0115200274 0.0212150000 214806570 95654236 760807424 -0.3657561243 0.0062188143 0.1301907450 376 1305031114.6792509556 0.0333957374 0.0334132751 0.0796080306 0.0115167591 0.0211750000 214969802 95654236 760807424 -0.3740689456 0.0029798669 0.1331727803 377 1305031114.7113060951 0.0350416563 0.0334175944 0.0796080306 0.0115134087 0.0236270000 214983354 95654236 760807424 -0.3730642498 0.0004091889 0.1354641616 378 1305031114.7432758808 0.0368110985 0.0334265719 0.0796080306 0.0114988148 0.0220460000 214986914 95654236 760807424 -0.3719301820 -0.0016391415 0.1369912177 379 1305031114.7792890072 0.0372234359 0.0334365900 0.0796080306 0.0114868521 0.0197630000 214990530 95654236 760807424 -0.3703997433 -0.0010874659 0.1363602430 380 1305031114.8113029003 0.0370238237 0.0334460301 0.0796080306 0.0114786738 0.0210120000 214992378 95654236 760807424 -0.3690920472 0.0034094173 0.1343678385 381 1305031114.8432080746 0.0363038331 0.0334535309 0.0796080306 0.0114653562 0.0210560000 214995938 95654236 760807424 -0.3676145971 0.0017709763 0.1338876784 382 1305031114.8792810440 0.0347784497 0.0334569993 0.0796080306 0.0114511257 0.0210540000 214997898 95654236 760807424 -0.3641572297 0.0047869743 0.1319509745 383 1305031114.9128789902 0.0336583443 0.0334575250 0.0796080306 0.0114396533 0.0210150000 215001514 95654236 760807424 -0.3599674702 0.0068089124 0.1305323392 384 1305031114.9432640076 0.0340303183 0.0334590166 0.0796080306 0.0114278169 0.0211700000 215005106 95654236 760807424 -0.3481528163 0.0083117262 0.1308488846 385 1305031114.9792799950 0.0324729197 0.0334564553 0.0796080306 0.0114185714 0.0212050000 215006922 95654236 760807424 -0.3416911662 0.0110000288 0.1312482655 386 1305031115.0113000870 0.0312361550 0.0334507033 0.0796080306 0.0114070491 0.0213810000 215169450 95654236 760807424 -0.3344031870 0.0152548011 0.1308565289 387 1305031115.0435299873 0.0335744359 0.0334510230 0.0796080306 0.0114019746 0.0245420000 215185038 95654236 760807424 -0.3236822486 0.0115546240 0.1362074763 388 1305031115.0792379379 0.0302305035 0.0334427227 0.0796080306 0.0113985711 0.0214420000 215346006 95654236 760807424 -0.3160677254 0.0153362369 0.1364880204 389 1305031115.1112298965 0.0320957899 0.0334392601 0.0796080306 0.0113879621 0.0248360000 215361566 95654236 760807424 -0.3019481003 0.0161308087 0.1404352188 390 1305031115.1432940960 0.0312729329 0.0334337054 0.0796080306 0.0113764621 0.0216870000 215522458 95654236 760807424 -0.2915730178 0.0139885303 0.1429206431 391 1305031115.1794400215 0.0278474428 0.0334194183 0.0796080306 0.0113739688 0.0215790000 215538238 95654236 760807424 -0.2858948410 0.0158503465 0.1438742280 392 1305031115.2113740444 0.0327164456 0.0334176250 0.0796080306 0.0113709154 0.0215990000 215541886 95654236 760807424 -0.2726988792 0.0101467017 0.1519732773 393 1305031115.2432971001 0.0335101485 0.0334178605 0.0796080306 0.0113636471 0.0217050000 215702538 95654236 760807424 -0.2617565393 0.0079616206 0.1558099091 394 1305031115.2799661160 0.0294142663 0.0334076991 0.0796080306 0.0113838698 0.0217170000 215718562 95654236 760807424 -0.2496443838 0.0158778913 0.1546632051 395 1305031115.3117039204 0.0326024257 0.0334056604 0.0796080306 0.0113866932 0.0217030000 215878838 95654236 760807424 -0.2301142961 0.0086281104 0.1626343727 396 1305031115.3434259892 0.0278635491 0.0333916652 0.0796080306 0.0113876375 0.0253410000 215894890 95654236 760807424 -0.2143857926 0.0131867593 0.1623088568 397 1305031115.3791658878 0.0211329442 0.0333607868 0.0796080306 0.0114309613 0.0219050000 216058030 95654236 760807424 -0.1955909729 0.0227494724 0.1600261927 398 1305031115.4112370014 0.0240632724 0.0333374262 0.0796080306 0.0114406097 0.0252680000 216072334 95654236 760807424 -0.1777321547 0.0169491954 0.1672311127 399 1305031115.4431591034 0.0252379347 0.0333171267 0.0796080306 0.0114299070 0.0223440000 216075838 95654236 760807424 -0.1593222767 0.0166067537 0.1717729717 400 1305031115.4792408943 0.0250774343 0.0332965275 0.0796080306 0.0114189089 0.0223750000 216236558 95654236 760807424 -0.1414106190 0.0178443752 0.1737714261 401 1305031115.5112531185 0.0308311060 0.0332903793 0.0796080306 0.0114541306 0.0222950000 216252522 95654236 760807424 -0.1154537201 0.0131335575 0.1805012822 402 1305031115.5436201096 0.0329952314 0.0332896451 0.0796080306 0.0114463300 0.0223970000 216415726 95654236 760807424 -0.0912072584 0.0119227860 0.1823568940 403 1305031115.5793149471 0.0319078118 0.0332862162 0.0796080306 0.0114432840 0.0225370000 216430110 95654236 760807424 -0.0760995746 0.0122490497 0.1829190254 404 1305031115.6114239693 0.0337836817 0.0332874476 0.0796080306 0.0114306796 0.0223460000 216433758 95654236 760807424 -0.0587162673 0.0096305236 0.1833201200 405 1305031115.6432540417 0.0347038358 0.0332909448 0.0796080306 0.0114253424 0.0222750000 216437262 95654236 760807424 -0.0401332378 0.0075089070 0.1829663366 406 1305031115.6792409420 0.0349058285 0.0332949224 0.0796080306 0.0114125223 0.0221570000 216439278 95654236 760807424 -0.0246383753 0.0052133538 0.1803344488 407 1305031115.7113199234 0.0317614712 0.0332911547 0.0796080306 0.0114409763 0.0219620000 216442782 95654236 760807424 -0.0053166822 0.0091647422 0.1792472601 408 1305031115.7432498932 0.0356715955 0.0332969891 0.0796080306 0.0114494649 0.0227450000 216444742 95654236 760807424 0.0217822827 0.0073036538 0.1801428050 409 1305031115.7794249058 0.0343877673 0.0332996560 0.0796080306 0.0114593525 0.0219460000 216448358 95654236 760807424 0.0372603685 0.0074406033 0.1793691069 410 1305031115.8112769127 0.0322578177 0.0332971150 0.0796080306 0.0114600065 0.0218210000 216451990 95654236 760807424 0.0554442629 0.0099044405 0.1774713248 411 1305031115.8432240486 0.0353951082 0.0333022196 0.0796080306 0.0114532569 0.0220310000 216453750 95654236 760807424 0.0730947629 0.0078595337 0.1772349477 412 1305031115.8791980743 0.0381198339 0.0333139128 0.0796080306 0.0114456910 0.0253690000 216615830 95654236 760807424 0.0855317935 0.0038583437 0.1776268482 413 1305031115.9111180305 0.0353627987 0.0333188738 0.0796080306 0.0114507431 0.0220890000 216630426 95654236 760807424 0.1039388403 0.0089002615 0.1761310250 414 1305031115.9433109760 0.0362690613 0.0333259998 0.0796080306 0.0114438061 0.0245370000 216634074 95654236 760807424 0.1214817315 0.0111704087 0.1759312302 415 1305031115.9807400703 0.0343727544 0.0333285221 0.0796080306 0.0114503026 0.0251980000 216637690 95654236 760807424 0.1353447437 0.0141963940 0.1761701405 416 1305031116.0113790035 0.0363553315 0.0333357981 0.0796080306 0.0114848948 0.0217770000 216639538 95654236 760807424 0.1519993693 0.0162759405 0.1769549102 417 1305031116.0431640148 0.0392991006 0.0333500986 0.0796080306 0.0114788393 0.0218380000 216643098 95654236 760807424 0.1674495637 0.0168586243 0.1779330522 418 1305031116.0800299644 0.0334662050 0.0333503764 0.0796080306 0.0115003429 0.0217540000 216802942 95654236 760807424 0.1730645597 0.0218823534 0.1783187538 419 1305031116.1112999916 0.0368848145 0.0333588118 0.0796080306 0.0114871844 0.0215560000 216819478 95654236 760807424 0.1882846951 0.0228135753 0.1823800802 420 1305031116.1434469223 0.0428409763 0.0333813884 0.0796080306 0.0114758377 0.0215880000 216981126 95654236 760807424 0.1975082606 0.0192308966 0.1868296117 421 1305031116.1795721054 0.0430728011 0.0334044084 0.0796080306 0.0114719671 0.0214610000 216996098 95654236 760807424 0.2050659955 0.0195378084 0.1878565103 422 1305031116.2113199234 0.0475640893 0.0334379621 0.0796080306 0.0114596620 0.0215550000 216999802 95654236 760807424 0.2149994671 0.0173207447 0.1905711889 423 1305031116.2433199883 0.0519750677 0.0334817851 0.0796080306 0.0114491887 0.0247100000 217003306 95654236 760807424 0.2298255861 0.0156714190 0.1934430301 424 1305031116.2793850899 0.0489633083 0.0335182981 0.0796080306 0.0114552555 0.0210210000 217163106 95654236 760807424 0.2388777137 0.0187606364 0.1908101439 425 1305031116.3113360405 0.0484780595 0.0335534975 0.0796080306 0.0114562224 0.0242030000 217179842 95654236 760807424 0.2498030066 0.0203049071 0.1896772832 426 1305031116.3432919979 0.0575699471 0.0336098742 0.0796080306 0.0114451642 0.0211850000 217181746 95654236 760807424 0.2616560459 0.0132380007 0.1935188472 427 1305031116.3793840408 0.0524847060 0.0336540775 0.0796080306 0.0114328211 0.0212650000 217185306 95654236 760807424 0.2647268772 0.0162117369 0.1895495355 428 1305031116.4113330841 0.0413368344 0.0336720279 0.0796080306 0.0114285827 0.0209760000 217189066 95654236 760807424 0.2637589872 0.0257247202 0.1822071522 429 1305031116.4433689117 0.0405124202 0.0336879729 0.0796080306 0.0114269342 0.0211580000 217190826 95654236 760807424 0.2664892673 0.0266563129 0.1802212000 430 1305031116.4798500538 0.0484236367 0.0337222418 0.0796080306 0.0114210115 0.0210810000 217194626 95654236 760807424 0.2721178234 0.0198514182 0.1813724488 431 1305031116.5112049580 0.0436901860 0.0337453693 0.0796080306 0.0114088000 0.0212020000 217196274 95654236 760807424 0.2677498460 0.0228216760 0.1767476350 432 1305031116.5432620049 0.0397225879 0.0337592055 0.0796080306 0.0113968625 0.0212030000 217199978 95654236 760807424 0.2603792548 0.0247051250 0.1732301414 433 1305031116.5793130398 0.0384015478 0.0337699268 0.0796080306 0.0113921628 0.0244210000 217203562 95654236 760807424 0.2534980178 0.0258027054 0.1716831923 434 1305031116.6112608910 0.0386031643 0.0337810633 0.0796080306 0.0113839965 0.0214870000 217205410 95654236 760807424 0.2471939772 0.0257598702 0.1706092209 435 1305031116.6433548927 0.0355131216 0.0337850451 0.0796080306 0.0113861202 0.0219140000 217208914 95654236 760807424 0.2331688851 0.0263311844 0.1681715250 436 1305031116.6792809963 0.0336703658 0.0337847820 0.0796080306 0.0113887927 0.0212760000 217211042 95654236 760807424 0.2167248726 0.0271937326 0.1674647927 437 1305031116.7116339207 0.0318550095 0.0337803661 0.0796080306 0.0113970507 0.0250260000 217214490 95654236 760807424 0.1967809498 0.0254124217 0.1677627712 438 1305031116.7432909012 0.0327816680 0.0337780859 0.0796080306 0.0114165661 0.0218290000 217218178 95654236 760807424 0.1746481657 0.0226246994 0.1686608046 439 1305031116.7792980671 0.0342296287 0.0337791145 0.0796080306 0.0114322708 0.0217030000 217219994 95654236 760807424 0.1573443264 0.0206777006 0.1684270948 440 1305031116.8113429546 0.0345365256 0.0337808359 0.0796080306 0.0114753651 0.0218450000 217223698 95654236 760807424 0.1446806937 0.0204661787 0.1677992493 441 1305031116.8460888863 0.0334698521 0.0337801307 0.0796080306 0.0115550752 0.0219290000 217227258 95654236 760807424 0.1234137267 0.0199238881 0.1645607650 442 1305031116.8801651001 0.0340879448 0.0337808271 0.0796080306 0.0115644369 0.0217530000 217229218 95654236 760807424 0.1106769443 0.0198870879 0.1624272913 443 1305031116.9120440483 0.0334545635 0.0337800906 0.0796080306 0.0115540289 0.0218190000 217232738 95654236 760807424 0.0932162926 0.0215305574 0.1618715525 444 1305031116.9432959557 0.0288685299 0.0337690286 0.0796080306 0.0115547151 0.0221360000 217391894 95654236 760807424 0.0757450536 0.0253725946 0.1588651240 445 1305031116.9793510437 0.0328648835 0.0337669968 0.0796080306 0.0115792696 0.0219680000 217409386 95654236 760807424 0.0572747067 0.0242852103 0.1582032293 446 1305031117.0113821030 0.0307430401 0.0337602166 0.0796080306 0.0115786010 0.0221320000 217570514 95654236 760807424 0.0369536765 0.0265999045 0.1566153318 447 1305031117.0432610512 0.0290170293 0.0337496055 0.0796080306 0.0115682098 0.0254400000 217586250 95654236 760807424 0.0186962094 0.0294596851 0.1551688910 448 1305031117.0795199871 0.0292518828 0.0337395659 0.0796080306 0.0115958917 0.0221410000 217747738 95654236 760807424 -0.0014247820 0.0319891125 0.1539432257 449 1305031117.1112380028 0.0314539075 0.0337344753 0.0796080306 0.0115999313 0.0252910000 217763454 95654236 760807424 -0.0199259762 0.0329890214 0.1543443799 450 1305031117.1432180405 0.0287180543 0.0337233277 0.0796080306 0.0115931529 0.0222030000 217767214 95654236 760807424 -0.0311319344 0.0388660692 0.1532943547 451 1305031117.1792640686 0.0299109891 0.0337148747 0.0796080306 0.0115925847 0.0285090000 218009326 95654236 760807424 -0.0409049578 0.0405899957 0.1545267701 452 1305031117.2113609314 0.0301220790 0.0337069260 0.0796080306 0.0115976259 0.0220880000 218025414 95654236 760807424 -0.0464748517 0.0431955941 0.1565363705 453 1305031117.2432770729 0.0283932500 0.0336951960 0.0796080306 0.0115935521 0.0224290000 218028918 95654236 760807424 -0.0459911264 0.0480032265 0.1571282595 454 1305031117.2792990208 0.0317713134 0.0336909584 0.0796080306 0.0115825364 0.0222550000 218030934 95654236 760807424 -0.0487227887 0.0451186672 0.1600355506 455 1305031117.3111999035 0.0338290185 0.0336912618 0.0796080306 0.0115766496 0.0219650000 218034366 95654236 760807424 -0.0530571006 0.0417121649 0.1616094410 456 1305031117.3432428837 0.0363824479 0.0336971636 0.0796080306 0.0115706360 0.0219540000 218038126 95654236 760807424 -0.0555462353 0.0379715003 0.1633156836 457 1305031117.3794538975 0.0370335430 0.0337044642 0.0796080306 0.0115635505 0.0220170000 218039942 95654236 760807424 -0.0577435680 0.0346657261 0.1640373021 458 1305031117.4112210274 0.0382439233 0.0337143756 0.0796080306 0.0115510670 0.0219880000 218043646 95654236 760807424 -0.0611852743 0.0299517140 0.1645096391 459 1305031117.4432740211 0.0375300199 0.0337226886 0.0796080306 0.0115413022 0.0220910000 218047118 95654236 760807424 -0.0602060109 0.0259504132 0.1639442146 460 1305031117.4794030190 0.0346081257 0.0337246135 0.0796080306 0.0115356416 0.0284330000 218049902 95654236 760807424 -0.0636860952 0.0222784244 0.1632167548 461 1305031117.5113248825 0.0378734730 0.0337336132 0.0796080306 0.0115272079 0.0221870000 218053390 95654236 760807424 -0.0623106509 0.0120325675 0.1647398323 462 1305031117.5442850590 0.0331305824 0.0337323079 0.0796080306 0.0115228538 0.0252570000 218055238 95654236 760807424 -0.0654088929 0.0104599632 0.1633430123 463 1305031117.5791549683 0.0301776920 0.0337246305 0.0796080306 0.0115114937 0.0222020000 218058894 95654236 760807424 -0.0644041672 0.0032960586 0.1638537198 464 1305031117.6111590862 0.0294917356 0.0337155079 0.0796080306 0.0114994994 0.0220520000 218062542 95654236 760807424 -0.0662222803 -0.0041679936 0.1653288305 465 1305031117.6432840824 0.0301415138 0.0337078219 0.0796080306 0.0114876265 0.0221050000 218064286 95654236 760807424 -0.0680741891 -0.0123509727 0.1683007628 466 1305031117.6792619228 0.0253311098 0.0336898461 0.0796080306 0.0114771688 0.0220180000 218068102 95654236 760807424 -0.0683535412 -0.0182889756 0.1703949124 467 1305031117.7112150192 0.0274919737 0.0336765745 0.0796080306 0.0114663410 0.0228230000 218069734 95654236 760807424 -0.0684047192 -0.0282858312 0.1749920547 468 1305031117.7431840897 0.0292930100 0.0336672079 0.0796080306 0.0114562436 0.0220630000 218073438 95654236 760807424 -0.0691923201 -0.0385757461 0.1791301668 469 1305031117.7794671059 0.0235012788 0.0336455321 0.0796080306 0.0114457918 0.0280520000 218077054 95654236 760807424 -0.0687151551 -0.0444188491 0.1819178760 470 1305031117.8113200665 0.0276355296 0.0336327449 0.0796080306 0.0114392679 0.0221930000 218078958 95654236 760807424 -0.0677553639 -0.0574930683 0.1879185289 471 1305031117.8433070183 0.0290732887 0.0336230645 0.0796080306 0.0114350324 0.0234540000 218239390 95654236 760807424 -0.0646664798 -0.0678768083 0.1928635538 472 1305031117.8794670105 0.0239003208 0.0336024655 0.0796080306 0.0114247115 0.0236960000 218256186 95654236 760807424 -0.0646262690 -0.0750450268 0.1958443224 473 1305031117.9114069939 0.0282469504 0.0335911430 0.0796080306 0.0114138782 0.0219200000 218259634 95654236 760807424 -0.0669730529 -0.0875080600 0.2018115669 474 1305031117.9432721138 0.0266653169 0.0335765316 0.0796080306 0.0114045086 0.0271430000 218263466 95654236 760807424 -0.0679094866 -0.0942886695 0.2052544653 475 1305031117.9792630672 0.0250912532 0.0335586678 0.0796080306 0.0113996101 0.0219000000 218265282 95654236 760807424 -0.0713725835 -0.1023914367 0.2091340423 476 1305031118.0112280846 0.0307691526 0.0335528075 0.0796080306 0.0113928902 0.0218500000 218268962 95654236 760807424 -0.0714475885 -0.1162955910 0.2167740762 477 1305031118.0435490608 0.0332882330 0.0335522528 0.0796080306 0.0113823754 0.0219310000 218272522 95654236 760807424 -0.0714582354 -0.1270731241 0.2227700204 478 1305031118.0793690681 0.0318549685 0.0335487020 0.0796080306 0.0113736397 0.0235820000 218274922 95654236 760807424 -0.0708363131 -0.1358030885 0.2270129770 479 1305031118.1112170219 0.0347484425 0.0335512067 0.0796080306 0.0113640125 0.0235530000 218434378 95654236 760807424 -0.0719467923 -0.1463178843 0.2328390777 480 1305031118.1432559490 0.0365566425 0.0335574680 0.0796080306 0.0113542416 0.0236280000 218451410 95654236 760807424 -0.0718405768 -0.1558955312 0.2372455448 481 1305031118.1793229580 0.0394012108 0.0335696172 0.0796080306 0.0113474278 0.0235850000 218454834 95654236 760807424 -0.0720968619 -0.1688164473 0.2427359670 482 1305031118.2112019062 0.0455307961 0.0335944329 0.0796080306 0.0113366690 0.0234310000 218614982 95654236 760807424 -0.0766038150 -0.1822247505 0.2480512559 483 1305031118.2431728840 0.0469785705 0.0336221433 0.0796080306 0.0113332593 0.0233200000 218632258 95654236 760807424 -0.0767745748 -0.1911876500 0.2515035868 484 1305031118.2791941166 0.0488123670 0.0336535281 0.0796080306 0.0113392033 0.0216240000 218636074 95654236 760807424 -0.0768583044 -0.2026726604 0.2557239830 485 1305031118.3112990856 0.0504635945 0.0336881880 0.0796080306 0.0113284421 0.0217190000 218793274 95654236 760807424 -0.0782701001 -0.2108119279 0.2594818771 486 1305031118.3433239460 0.0478948578 0.0337174199 0.0796080306 0.0113251394 0.0217210000 218812266 95654236 760807424 -0.0748240724 -0.2142509222 0.2607952356 487 1305031118.3792080879 0.0504599214 0.0337517987 0.0796080306 0.0113156376 0.0248510000 218815882 95654236 760807424 -0.0786657557 -0.2222099304 0.2639062703 488 1305031118.4112958908 0.0513986088 0.0337879602 0.0796080306 0.0113076145 0.0217230000 218974618 95654236 760807424 -0.0808625221 -0.2241900414 0.2636466026 489 1305031118.4457030296 0.0511554368 0.0338234765 0.0796080306 0.0112972087 0.0215600000 218993566 95654236 760807424 -0.0778341070 -0.2266233563 0.2657864690 490 1305031118.4792850018 0.0521870553 0.0338609532 0.0796080306 0.0112869423 0.0215890000 218995470 95654236 760807424 -0.0770756304 -0.2296628654 0.2692252994 491 1305031118.5112550259 0.0507986732 0.0338954496 0.0796080306 0.0112774362 0.0215560000 218998974 95654236 760807424 -0.0737180114 -0.2278369516 0.2692700028 492 1305031118.5451989174 0.0491862372 0.0339265284 0.0796080306 0.0112684257 0.0215970000 219002734 95654236 760807424 -0.0733336732 -0.2226000875 0.2681121826 493 1305031118.5792849064 0.0500906520 0.0339593157 0.0796080306 0.0112578394 0.0216220000 219004550 95654236 760807424 -0.0717376694 -0.2208784819 0.2694386244 494 1305031118.6161420345 0.0505569391 0.0339929141 0.0796080306 0.0112479511 0.0216360000 219008382 95654236 760807424 -0.0692108721 -0.2169636786 0.2691873908 495 1305031118.6453309059 0.0485226661 0.0340222672 0.0796080306 0.0112429547 0.0217000000 219011830 95654236 760807424 -0.0719632283 -0.2090108246 0.2658096850 496 1305031118.6792950630 0.0480288155 0.0340505062 0.0796080306 0.0112334772 0.0225770000 219013846 95654236 760807424 -0.0713407397 -0.2020875812 0.2650624514 497 1305031118.7114210129 0.0484809875 0.0340795413 0.0796080306 0.0112285194 0.0219720000 219017294 95654236 760807424 -0.0714832023 -0.1975675225 0.2650186121 498 1305031118.7468008995 0.0499663875 0.0341114426 0.0796080306 0.0112267481 0.0249580000 219019310 95654236 760807424 -0.0746728703 -0.1884637177 0.2598921657 499 1305031118.7792770863 0.0405315161 0.0341243085 0.0796080306 0.0112271146 0.0219310000 219022870 95654236 760807424 -0.0708076805 -0.1699314266 0.2532427907 500 1305031118.8112208843 0.0437009856 0.0341434619 0.0796080306 0.0112485512 0.0223020000 219026518 95654236 760807424 -0.0675982609 -0.1680671126 0.2535919249 501 1305031118.8467741013 0.0389198959 0.0341529957 0.0796080306 0.0112441416 0.0236000000 219029614 95654236 760807424 -0.0651269928 -0.1532774866 0.2490840703 502 1305031118.8792080879 0.0277102888 0.0341401616 0.0796080306 0.0112706370 0.0239250000 219033438 95654236 760807424 -0.0645867139 -0.1308486313 0.2375366241 503 1305031118.9111769199 0.0307920799 0.0341335054 0.0796080306 0.0113013684 0.0239100000 219035054 95654236 760807424 -0.0639199093 -0.1259516776 0.2335183024 504 1305031118.9470090866 0.0289743356 0.0341232689 0.0796080306 0.0112999261 0.0239940000 219038806 95654236 760807424 -0.0623412244 -0.1123628542 0.2267971486 505 1305031118.9793939590 0.0221755411 0.0340996101 0.0796080306 0.0112958994 0.0365360000 219042046 95654236 760807424 -0.0640547425 -0.0956690609 0.2179792970 506 1305031119.0113630295 0.0215594471 0.0340748271 0.0796080306 0.0112957580 0.0247040000 219044214 95654236 760807424 -0.0644858852 -0.0855853111 0.2115077972 507 1305031119.0471799374 0.0254457667 0.0340578073 0.0796080306 0.0112883041 0.0238690000 219048118 95654236 760807424 -0.0666550994 -0.0765778273 0.2059274912 508 1305031119.0792229176 0.0250136312 0.0340400038 0.0796080306 0.0112812541 0.0237200000 219205146 95654236 760807424 -0.0703793094 -0.0658247471 0.1995463371 509 1305031119.1113278866 0.0241900161 0.0340206521 0.0796080306 0.0112767384 0.0222940000 219224722 95654236 760807424 -0.0709293038 -0.0556831360 0.1932651252 510 1305031119.1476290226 0.0239300672 0.0340008667 0.0796080306 0.0112740343 0.0232140000 219228538 95654236 760807424 -0.0734493211 -0.0423589833 0.1854120344 511 1305031119.1792619228 0.0276310667 0.0339884013 0.0796080306 0.0112854104 0.0239710000 219230626 95654236 760807424 -0.0738094747 -0.0367204361 0.1811259091 512 1305031119.2113640308 0.0245820731 0.0339700296 0.0796080306 0.0112756078 0.0222150000 219234330 95654236 760807424 -0.0730624199 -0.0245296992 0.1744076461 513 1305031119.2476599216 0.0259125028 0.0339543229 0.0796080306 0.0112664742 0.0269670000 219315978 95654236 760807424 -0.0731155276 -0.0134289190 0.1680124402 514 1305031119.2792439461 0.0248519480 0.0339366140 0.0796080306 0.0112565725 0.0228450000 219420250 95654236 760807424 -0.0728211850 -0.0026688315 0.1626314223 515 1305031119.3112120628 0.0257762447 0.0339207686 0.0796080306 0.0112473794 0.0226180000 219423706 95654236 760807424 -0.0752936974 0.0063257217 0.1577678174 516 1305031119.3477499485 0.0298712999 0.0339129208 0.0796080306 0.0112367853 0.0222340000 219425690 95654236 760807424 -0.0746042877 0.0144202877 0.1539191455 517 1305031119.3792390823 0.0268603228 0.0338992794 0.0796080306 0.0112285122 0.0223090000 219429162 95654236 760807424 -0.0740455240 0.0287063774 0.1484782994 518 1305031119.4114921093 0.0282153692 0.0338883066 0.0796080306 0.0112190539 0.0222320000 219432834 95654236 760807424 -0.0731606707 0.0374538451 0.1448383927 519 1305031119.4477260113 0.0320345797 0.0338847349 0.0796080306 0.0112085777 0.0223070000 219434674 95654236 760807424 -0.0721205175 0.0465676263 0.1407759339 520 1305031119.4792668819 0.0318733864 0.0338808669 0.0796080306 0.0112058304 0.0222000000 219438218 95654236 760807424 -0.0741157830 0.0583201200 0.1360878348 521 1305031119.5112578869 0.0320367999 0.0338773275 0.0796080306 0.0111988042 0.0253260000 219439890 95654236 760807424 -0.0771837533 0.0692693144 0.1313145608 522 1305031119.5474140644 0.0352031924 0.0338798674 0.0796080306 0.0111884803 0.0275330000 219443730 95654236 760807424 -0.0760194659 0.0807787478 0.1280448437 523 1305031119.5795691013 0.0343840271 0.0338808314 0.0796080306 0.0111870104 0.0223280000 219618822 95654236 760807424 -0.0755318999 0.0953995287 0.1236258298 524 1305031119.6150240898 0.0375168473 0.0338877704 0.0796080306 0.0111900836 0.0221900000 219620806 95654236 760807424 -0.0765286088 0.1023961529 0.1219441667 525 1305031119.6488890648 0.0395893753 0.0338986306 0.0796080306 0.0111956657 0.0220760000 219795214 95654236 760807424 -0.0800776631 0.1167081594 0.1185534820 526 1305031119.6792080402 0.0409577452 0.0339120509 0.0796080306 0.0111867460 0.0219840000 219796974 95654236 760807424 -0.0755122080 0.1293798238 0.1164450943 527 1305031119.7152490616 0.0430157632 0.0339293255 0.0796080306 0.0111810515 0.0251350000 219972886 95654336 760807424 -0.0774740800 0.1373432279 0.1149895340 528 1305031119.7471930981 0.0478169061 0.0339556278 0.0796080306 0.0111768379 0.0221010000 219976614 95654336 760807424 -0.0827400833 0.1433222443 0.1147074029 529 1305031119.7791690826 0.0491458364 0.0339843427 0.0796080306 0.0111688096 0.0250020000 219978286 95654336 760807424 -0.0826501623 0.1526328921 0.1126236618 530 1305031119.8145709038 0.0507247858 0.0340159285 0.0796080306 0.0111621579 0.0222140000 220152566 95654336 760807424 -0.0818612725 0.1629135907 0.1111983582 531 1305031119.8474450111 0.0545704737 0.0340546376 0.0796080306 0.0111548602 0.0258030000 220156150 95654336 760807424 -0.0803432539 0.1734751910 0.1104152501 532 1305031119.8792319298 0.0590023622 0.0341015318 0.0796080306 0.0111514540 0.0220470000 220157966 95654336 760807424 -0.0786562487 0.1786041111 0.1107712835 533 1305031119.9114239216 0.0557067432 0.0341420669 0.0796080306 0.0111680785 0.0217940000 220161438 95654336 760807424 -0.0821595639 0.1947118044 0.1051261127 534 1305031119.9474620819 0.0597537197 0.0341900288 0.0796080306 0.0111643320 0.0217660000 220334682 95654336 760807424 -0.0808313265 0.2002568543 0.1045808420 535 1305031119.9795460701 0.0612486936 0.0342406057 0.0796080306 0.0111542573 0.0217640000 220338170 95654336 760807424 -0.0800121874 0.2062454671 0.1030743867 536 1305031120.0152831078 0.0585634448 0.0342859842 0.0796080306 0.0111754497 0.0217510000 220513614 95654336 760807424 -0.0834024623 0.2202860117 0.0984760076 537 1305031120.0473101139 0.0638956949 0.0343411233 0.0796080306 0.0111867584 0.0216210000 220515342 95654336 760807424 -0.0859466940 0.2185114324 0.1013056785 538 1305031120.0794179440 0.0651151314 0.0343983241 0.0796080306 0.0111839196 0.0216090000 220519014 95654336 760807424 -0.0867018551 0.2181706727 0.1010247767 539 1305031120.1152489185 0.0639799610 0.0344532065 0.0796080306 0.0111824026 0.0219440000 220520742 95654336 760807424 -0.0850550383 0.2232641876 0.0992440879 540 1305031120.1481750011 0.0665992349 0.0345127362 0.0796080306 0.0111911703 0.0307180000 220524470 95654336 760807424 -0.0852641314 0.2191274464 0.1021630168 541 1305031120.1792609692 0.0687204674 0.0345759667 0.0796080306 0.0111816610 0.0346570000 220527886 95654336 760807424 -0.0843975991 0.2171315700 0.1047612578 542 1305031120.2152600288 0.0689883456 0.0346394582 0.0796080306 0.0111721766 0.0232700000 220529886 95654336 760807424 -0.0850698352 0.2147799432 0.1062837094 543 1305031120.2480180264 0.0657677874 0.0346967848 0.0796080306 0.0111641706 0.0218380000 220533414 95654336 760807424 -0.0833250657 0.2111183107 0.1054938808 544 1305031120.2794411182 0.0643463805 0.0347512877 0.0796080306 0.0111563634 0.0217860000 220535270 95654336 760807424 -0.0842125863 0.2052374333 0.1071943119 545 1305031120.3152129650 0.0635719746 0.0348041697 0.0796080306 0.0111465022 0.0219610000 220538798 95654336 760807424 -0.0832353830 0.1967826635 0.1101856306 546 1305031120.3477969170 0.0592903458 0.0348490162 0.0796080306 0.0111375160 0.0337820000 220542526 95654336 760807424 -0.0824702233 0.1879457533 0.1120329052 547 1305031120.3794460297 0.0593671910 0.0348938392 0.0796080306 0.0111281301 0.0230420000 220544198 95654336 760807424 -0.0823348463 0.1782785654 0.1175262854 548 1305031120.4154899120 0.0597033873 0.0349391121 0.0796080306 0.0111204541 0.0228100000 220547942 95654336 760807424 -0.0845309868 0.1747674197 0.1231995970 549 1305031120.4474329948 0.0499320701 0.0349664217 0.0796080306 0.0111495387 0.0221880000 220551470 95654336 760807424 -0.0776443407 0.1490596086 0.1216431782 550 1305031120.4794321060 0.0506239235 0.0349948898 0.0796080306 0.0111406560 0.0222650000 220553342 95654336 760807424 -0.0776165798 0.1361508071 0.1275420934 551 1305031120.5148770809 0.0502428748 0.0350225631 0.0796080306 0.0111307399 0.0238770000 220559558 95654336 760807424 -0.0795412883 0.1234630346 0.1325602531 552 1305031120.5478069782 0.0448838212 0.0350404277 0.0796080306 0.0111217725 0.0238980000 220561934 95654336 760807424 -0.0803088546 0.1151616424 0.1361542046 553 1305031120.5795590878 0.0427898914 0.0350544412 0.0796080306 0.0111155355 0.0239150000 220565470 95654336 760807424 -0.0814101771 0.1075725257 0.1399364471 554 1305031120.6152710915 0.0438965596 0.0350704017 0.0796080306 0.0111105116 0.0275040000 220569238 95654336 760807424 -0.0785246491 0.0964400619 0.1460666955 555 1305031120.6473538876 0.0399077497 0.0350791177 0.0796080306 0.0111033834 0.0239580000 220570902 95654336 760807424 -0.0770028457 0.0879474208 0.1505900323 556 1305031120.6793179512 0.0385942757 0.0350854399 0.0796080306 0.0111233096 0.0239760000 220574582 95654336 760807424 -0.0732879415 0.0808194429 0.1549070030 557 1305031120.7145531178 0.0367648788 0.0350884551 0.0796080306 0.0111135566 0.0238480000 220576430 95654336 760807424 -0.0753920153 0.0725146979 0.1589176506 558 1305031120.7473959923 0.0341218114 0.0350867227 0.0796080306 0.0111094061 0.0258340000 220580126 95654336 760807424 -0.0753410533 0.0609685071 0.1630613506 559 1305031120.7799079418 0.0356364846 0.0350877062 0.0796080306 0.0111034608 0.0258730000 220583686 95654336 760807424 -0.0711007118 0.0499930754 0.1686769426 560 1305031120.8149440289 0.0322344564 0.0350826111 0.0796080306 0.0111087022 0.0223250000 220585614 95654336 760807424 -0.0725250691 0.0444097631 0.1708787978 561 1305031120.8479421139 0.0300337262 0.0350736113 0.0796080306 0.0111060255 0.0222180000 220589142 95654336 760807424 -0.0721806064 0.0335452482 0.1747651100 562 1305031120.8834540844 0.0316535197 0.0350675257 0.0796080306 0.0110987767 0.0240000000 220591230 95654336 760807424 -0.0698785782 0.0225813054 0.1793828011 563 1305031120.9154539108 0.0279621687 0.0350549052 0.0796080306 0.0110990403 0.0360830000 220594766 95654336 760807424 -0.0712066963 0.0172110740 0.1810306609 564 1305031120.9475090504 0.0265701171 0.0350398613 0.0796080306 0.0110896366 0.0225990000 220598438 95654336 760807424 -0.0715570822 0.0060474025 0.1844845116 565 1305031120.9833900928 0.0276095979 0.0350267103 0.0796080306 0.0110825208 0.0222490000 220600222 95654336 760807424 -0.0722575337 -0.0044991439 0.1876927763 566 1305031121.0150289536 0.0295812953 0.0350170895 0.0796080306 0.0110795253 0.0222390000 220603838 95654336 760807424 -0.0713000000 -0.0155058904 0.1910573840 567 1305031121.0477550030 0.0244333409 0.0349984232 0.0796080306 0.0110703360 0.0238170000 220607294 95654336 760807424 -0.0721028745 -0.0226842314 0.1919093579 568 1305031121.0831170082 0.0295831691 0.0349888894 0.0796080306 0.0110625312 0.0287780000 220609270 95654336 760807424 -0.0738611892 -0.0364311300 0.1960622221 569 1305031121.1148779392 0.0291107520 0.0349785587 0.0796080306 0.0110554740 0.0222210000 220784126 95654336 760807424 -0.0742109790 -0.0450219847 0.1976029426 570 1305031121.1473550797 0.0269314107 0.0349644409 0.0796080306 0.0110478471 0.0221000000 220786054 95654336 760807424 -0.0748682916 -0.0547036938 0.1992520243 571 1305031121.1832809448 0.0280016102 0.0349522468 0.0796080306 0.0110389125 0.0220900000 220789622 95654336 760807424 -0.0750063583 -0.0644624084 0.2020417154 572 1305031121.2114310265 0.0295134559 0.0349427384 0.0796080306 0.0110316700 0.0305150000 220963758 95654336 760807424 -0.0740887448 -0.0752586797 0.2047298998 573 1305031121.2472009659 0.0253310632 0.0349259641 0.0796080306 0.0110238546 0.0225600000 220965542 95654336 760807424 -0.0768837631 -0.0819967538 0.2062434852 574 1305031121.2828760147 0.0284789223 0.0349147323 0.0796080306 0.0110164160 0.0220880000 220969310 95654336 760807424 -0.0770451054 -0.0935392007 0.2104600370 575 1305031121.3135879040 0.0318901688 0.0349094722 0.0796080306 0.0110090657 0.0227750000 220970926 95654336 760807424 -0.0758908689 -0.1057298556 0.2145265788 576 1305031121.3475399017 0.0294571966 0.0349000065 0.0796080306 0.0110009167 0.0220830000 221144938 95654336 760807424 -0.0794013441 -0.1128865853 0.2159398645 577 1305031121.3832480907 0.0325008035 0.0348958484 0.0796080306 0.0110082030 0.0252670000 221148522 95654336 760807424 -0.0749153122 -0.1260427535 0.2218333334 578 1305031121.4143280983 0.0330890119 0.0348927224 0.0796080306 0.0110003562 0.0221980000 221150354 95654336 760807424 -0.0760537162 -0.1346827149 0.2235213667 579 1305031121.4473190308 0.0310972556 0.0348861672 0.0796080306 0.0109950920 0.0218470000 221153882 95654336 760807424 -0.0761957243 -0.1422618032 0.2249767184 580 1305031121.4830150604 0.0356589481 0.0348874996 0.0796080306 0.0109958138 0.0250260000 221326366 95654336 760807424 -0.0744487941 -0.1562316865 0.2307269424 581 1305031121.5141639709 0.0357536338 0.0348889903 0.0796080306 0.0110013697 0.0218460000 221329798 95654336 760807424 -0.0798949897 -0.1615740061 0.2295699716 582 1305031121.5472700596 0.0333230160 0.0348862997 0.0796080306 0.0109943464 0.0217860000 221333582 95654336 760807424 -0.0792767406 -0.1675808728 0.2312712818 583 1305031121.5832130909 0.0360938720 0.0348883710 0.0796080306 0.0109861441 0.0217990000 221335366 95654336 760807424 -0.0794561580 -0.1794493645 0.2366493344 584 1305031121.6147189140 0.0380822644 0.0348938400 0.0796080306 0.0109777203 0.0254920000 221509282 95654336 760807424 -0.0796428248 -0.1885634214 0.2386931181 585 1305031121.6471829414 0.0368489064 0.0348971820 0.0796080306 0.0109721585 0.0218210000 221512770 95654336 760807424 -0.0792922601 -0.1946212947 0.2400806248 586 1305031121.6832110882 0.0404848866 0.0349067173 0.0796080306 0.0109670944 0.0218310000 221514810 95654336 760807424 -0.0833127424 -0.2024019957 0.2416866273 587 1305031121.7145280838 0.0435917154 0.0349215129 0.0796080306 0.0109596531 0.0217270000 221518226 95654336 760807424 -0.0848398656 -0.2112813890 0.2445889264 588 1305031121.7471449375 0.0440877713 0.0349371017 0.0796080306 0.0109506675 0.0217840000 221520098 95654336 760807424 -0.0848181471 -0.2161248475 0.2465214431 589 1305031121.7828710079 0.0460019745 0.0349558876 0.0796080306 0.0109417661 0.0217330000 221523682 95654336 760807424 -0.0840667188 -0.2238616049 0.2509430647 590 1305031121.8115448952 0.0461156033 0.0349748024 0.0796080306 0.0109369090 0.0256940000 221527274 95654336 760807424 -0.0811309442 -0.2281139046 0.2533190250 591 1305031121.8473351002 0.0480239540 0.0349968821 0.0796080306 0.0109301140 0.0323530000 221529058 95654336 760807424 -0.0820861161 -0.2308830768 0.2552098334 592 1305031121.8821229935 0.0494052321 0.0350212206 0.0796080306 0.0109233536 0.0229200000 221532786 95654336 760807424 -0.0831359774 -0.2330266684 0.2565699816 593 1305031121.9149429798 0.0496592373 0.0350459053 0.0796080306 0.0109149944 0.0219090000 221534514 95654336 760807424 -0.0826025158 -0.2340220511 0.2577886283 594 1305031121.9473180771 0.0493971817 0.0350700657 0.0796080306 0.0109074946 0.0218120000 221538186 95654336 760807424 -0.0797840655 -0.2350584567 0.2598919868 595 1305031121.9829349518 0.0478468873 0.0350915393 0.0796080306 0.0108990239 0.0218290000 221541770 95654336 760807424 -0.0784437954 -0.2307646722 0.2585347295 596 1305031122.0144240856 0.0478670336 0.0351129747 0.0796080306 0.0108904802 0.0218640000 221543642 95654336 760807424 -0.0800946280 -0.2277574688 0.2581673563 597 1305031122.0473060608 0.0478806458 0.0351343611 0.0796080306 0.0108826514 0.0219660000 221547114 95654336 760807424 -0.0806249604 -0.2218783200 0.2556566894 598 1305031122.0829689503 0.0462529846 0.0351529541 0.0796080306 0.0108746756 0.0219500000 221549098 95654336 760807424 -0.0797011331 -0.2150300443 0.2535499930 599 1305031122.1146879196 0.0447297506 0.0351689421 0.0796080306 0.0108697647 0.0219060000 221552514 95654336 760807424 -0.0815716907 -0.2046693563 0.2483301759 600 1305031122.1507480145 0.0442247242 0.0351840350 0.0796080306 0.0108625606 0.0326220000 221556298 95654336 760807424 -0.0808959305 -0.1956848800 0.2457959056 601 1305031122.1830520630 0.0425767526 0.0351963357 0.0796080306 0.0108669377 0.0230540000 221558026 95654336 760807424 -0.0792607293 -0.1856858730 0.2411605567 602 1305031122.2149689198 0.0365581624 0.0351985979 0.0796080306 0.0108741643 0.0221060000 221561642 95654336 760807424 -0.0816486403 -0.1656005681 0.2332350910 603 1305031122.2513549328 0.0378442518 0.0352029854 0.0796080306 0.0108663160 0.0221840000 221565282 95654336 760807424 -0.0790674984 -0.1590862125 0.2331343144 604 1305031122.2838659286 0.0349873230 0.0352026283 0.0796080306 0.0108592687 0.0224110000 221567226 95654336 760807424 -0.0803091228 -0.1459352672 0.2281774133 605 1305031122.3143088818 0.0284485929 0.0351914646 0.0796080306 0.0108556578 0.0223800000 221741006 95654336 760807424 -0.0824332833 -0.1270543933 0.2216421068 606 1305031122.3513510227 0.0294860657 0.0351820498 0.0796080306 0.0108509845 0.0223140000 221742990 95654336 760807424 -0.0826767236 -0.1168668941 0.2185143679 607 1305031122.3826780319 0.0221036170 0.0351605038 0.0796080306 0.0108479668 0.0242510000 221749782 95654336 760807424 -0.0848580226 -0.0983878970 0.2120995820 608 1305031122.4150080681 0.0231214594 0.0351407027 0.0796080306 0.0108510038 0.0224450000 221753342 95654336 760807424 -0.0842943639 -0.0915664434 0.2086860090 609 1305031122.4512720108 0.0224754848 0.0351199060 0.0796080306 0.0108460001 0.0262380000 221755182 95654336 760807424 -0.0842152312 -0.0792149454 0.2021137178 610 1305031122.4833879471 0.0217155050 0.0350979315 0.0796080306 0.0108457918 0.0225440000 221758854 95654336 760807424 -0.0845516026 -0.0695890635 0.1969883740 611 1305031122.5151350498 0.0197010245 0.0350727320 0.0796080306 0.0108426948 0.0225540000 221931870 95654336 760807424 -0.0826339573 -0.0591889359 0.1916697472 612 1305031122.5515100956 0.0210259780 0.0350497798 0.0796080306 0.0108361976 0.0246610000 221936550 95654336 760807424 -0.0827052966 -0.0480674170 0.1852938384 613 1305031122.5832169056 0.0213352535 0.0350274070 0.0796080306 0.0108301774 0.0245130000 221939702 95654336 760807424 -0.0830608755 -0.0383999534 0.1804130524 614 1305031122.6150169373 0.0242859796 0.0350099128 0.0796080306 0.0108261370 0.0225240000 221941502 95654336 760807424 -0.0868368149 -0.0309863091 0.1760132909 615 1305031122.6488099098 0.0263420884 0.0349958188 0.0796080306 0.0108175685 0.0257430000 222116370 95654336 760807424 -0.0843278691 -0.0198881067 0.1707821041 616 1305031122.6834199429 0.0263036955 0.0349817082 0.0796080306 0.0108106396 0.0226900000 222118282 95654336 760807424 -0.0877824575 -0.0091343429 0.1651858389 617 1305031122.7152190208 0.0269446913 0.0349686823 0.0796080306 0.0108031296 0.0233920000 222121698 95654336 760807424 -0.0878043324 0.0008174283 0.1611431092 618 1305031122.7513089180 0.0274015181 0.0349564377 0.0796080306 0.0108000280 0.0246020000 222125922 95654336 760807424 -0.0845697895 0.0152674988 0.1565414667 619 1305031122.7834379673 0.0250488147 0.0349404318 0.0796080306 0.0107936267 0.0243910000 222127786 95654336 760807424 -0.0877276212 0.0293787979 0.1516733617 620 1305031122.8125650883 0.0271590762 0.0349278812 0.0796080306 0.0107874575 0.0244520000 222131466 95654336 760807424 -0.0863267556 0.0386493281 0.1494734436 621 1305031122.8514859676 0.0327746645 0.0349244139 0.0796080306 0.0107847723 0.0292240000 222135170 95654336 760807424 -0.0828422531 0.0461413041 0.1483666599 622 1305031122.8837749958 0.0316143334 0.0349190922 0.0796080306 0.0107830389 0.0243870000 222137018 95654336 760807424 -0.0856275484 0.0573975444 0.1442525685 623 1305031122.9145851135 0.0344694741 0.0349183705 0.0796080306 0.0107796299 0.0245740000 222140570 95654336 760807424 -0.0891244262 0.0632550493 0.1424182951 624 1305031122.9514129162 0.0384126678 0.0349239704 0.0796080306 0.0107722709 0.0292920000 222142514 95654336 760807424 -0.0895937309 0.0700582415 0.1400817335 625 1305031122.9830000401 0.0374564081 0.0349280223 0.0796080306 0.0107650517 0.0245060000 222146050 95654336 760807424 -0.0924997553 0.0803022981 0.1361144930 626 1305031123.0154619217 0.0391504504 0.0349347673 0.0796080306 0.0107569559 0.0244220000 222321530 95654336 760807424 -0.0911829844 0.0884672105 0.1341948807 627 1305031123.0518379211 0.0433482267 0.0349481859 0.0796080306 0.0107497034 0.0356030000 222323482 95654336 760807424 -0.0903845951 0.0958441645 0.1325850040 628 1305031123.0829920769 0.0413796827 0.0349584272 0.0796080306 0.0107447876 0.0246770000 222327090 95654336 760807424 -0.0919523686 0.1080934256 0.1277455688 629 1305031123.1139390469 0.0408482738 0.0349677910 0.0796080306 0.0107383060 0.0250610000 222328458 95654336 760807424 -0.0927744284 0.1210675985 0.1242873371 630 1305031123.1508400440 0.0440644175 0.0349822301 0.0796080306 0.0107316693 0.0243220000 222332362 95654336 760807424 -0.0921133980 0.1262924075 0.1226273179 631 1305031123.1821761131 0.0453412458 0.0349986469 0.0796080306 0.0107288807 0.0242870000 222335898 95654336 760807424 -0.0896249339 0.1356529593 0.1206583977 632 1305031123.2147240639 0.0472619310 0.0350180508 0.0796080306 0.0107209560 0.0259650000 222337770 95654336 760807424 -0.0877144113 0.1439320445 0.1195210889 633 1305031123.2506411076 0.0473333113 0.0350375062 0.0796080306 0.0107310609 0.0258450000 222341354 95654336 760807424 -0.0909041539 0.1568274796 0.1163835824 634 1305031123.2823629379 0.0502405278 0.0350614858 0.0796080306 0.0107286718 0.0222550000 222343242 95654336 760807424 -0.0911551788 0.1690700054 0.1172512174 635 1305031123.3209919930 0.0542674810 0.0350917314 0.0796080306 0.0107286785 0.0221230000 222346882 95654336 760807424 -0.0888214484 0.1795311719 0.1176546663 636 1305031123.3504929543 0.0558125116 0.0351243113 0.0796080306 0.0107239193 0.0220670000 222350498 95654336 760807424 -0.0883238539 0.1891943812 0.1169459298 637 1305031123.3822629452 0.0574500859 0.0351593596 0.0796080306 0.0107163484 0.0219490000 222352202 95654336 760807424 -0.0869308412 0.1997528076 0.1160265133 638 1305031123.4213430882 0.0624151155 0.0352020802 0.0796080306 0.0107087697 0.0219100000 222356042 95654336 760807424 -0.0854999647 0.2071076035 0.1166827902 639 1305031123.4512660503 0.0620462969 0.0352440899 0.0796080306 0.0107152189 0.0218530000 222359402 95654336 760807424 -0.0862312987 0.2198586911 0.1139882505 640 1305031123.4836049080 0.0633834079 0.0352880576 0.0796080306 0.0107110649 0.0219050000 222532746 95654336 760807424 -0.0839332864 0.2288562804 0.1124760956 641 1305031123.5197250843 0.0676192418 0.0353384963 0.0796080306 0.0107063211 0.0253640000 222536274 95654336 760807424 -0.0813513324 0.2327536047 0.1124548689 642 1305031123.5515730381 0.0684067383 0.0353900044 0.0796080306 0.0106991674 0.0205210000 222538002 95654336 760807424 -0.0774346814 0.2396514565 0.1103670001 643 1305031123.5796160698 0.0709270835 0.0354452721 0.0796080306 0.0106936645 0.0205750000 222713326 95654336 760807424 -0.0756144747 0.2463097423 0.1101201624 644 1305031123.6203870773 0.0705736801 0.0354998193 0.0796080306 0.0106983668 0.0204060000 222717022 95654336 760807424 -0.0741842240 0.2580614090 0.1071505845 645 1305031123.6524300575 0.0719905347 0.0355563940 0.0796080306 0.0106947580 0.0302100000 222718694 95654336 760807424 -0.0720097423 0.2632161379 0.1064376906 646 1305031123.6837849617 0.0752606466 0.0356178557 0.0796080306 0.0106870323 0.0211720000 222893006 95654336 760807424 -0.0669417754 0.2690572441 0.1070319638 647 1305031123.7199749947 0.0769330710 0.0356817123 0.0796080306 0.0106789579 0.0203300000 222896790 95654336 760807424 -0.0649775416 0.2756438255 0.1057442874 648 1305031123.7519800663 0.0795548633 0.0357494178 0.0796080306 0.0106802952 0.0202590000 222898462 95654336 760807424 -0.0653474480 0.2764753401 0.1066503227 649 1305031123.7841379642 0.0803884789 0.0358181991 0.0803884789 0.0106776471 0.0204150000 223073730 95654336 760807424 -0.0638902932 0.2782580256 0.1059723422 650 1305031123.8196959496 0.0810152143 0.0358877330 0.0810152143 0.0106712314 0.0240350000 223077370 95654336 760807424 -0.0622215495 0.2800524235 0.1049401164 651 1305031123.8515510559 0.0814649686 0.0359577441 0.0814649686 0.0106635413 0.0204130000 223079242 95654336 760807424 -0.0620533414 0.2803070545 0.1048842221 652 1305031123.8838191032 0.0835322142 0.0360307111 0.0835322142 0.0106593710 0.0201980000 223082714 95654336 760807424 -0.0618918166 0.2775168717 0.1063692495 653 1305031123.9157938957 0.0822354108 0.0361014686 0.0835322142 0.0106546040 0.0203260000 223084330 95654336 760807424 -0.0612797476 0.2757039070 0.1059753522 654 1305031123.9515299797 0.0776231587 0.0361649575 0.0835322142 0.0106669494 0.0203290000 223087954 95654336 760807424 -0.0628019124 0.2773652971 0.1035569087 655 1305031123.9834210873 0.0818882510 0.0362347640 0.0835322142 0.0106839739 0.0203330000 223091626 95654336 760807424 -0.0640496165 0.2679949105 0.1093336120 656 1305031124.0197370052 0.0803992897 0.0363020880 0.0835322142 0.0106811820 0.0204590000 223093410 95654336 760807424 -0.0633007064 0.2682980299 0.1119302362 657 1305031124.0515310764 0.0771510825 0.0363642630 0.0835322142 0.0106931315 0.0205140000 223096826 95654336 760807424 -0.0635706186 0.2635733783 0.1118866652 658 1305031124.0839018822 0.0774322599 0.0364266764 0.0835322142 0.0106926616 0.0213190000 223100298 95654336 760807424 -0.0657879859 0.2566006482 0.1160403490 659 1305031124.1196689606 0.0755313262 0.0364860158 0.0835322142 0.0106863618 0.0208240000 223102282 95654336 760807424 -0.0656794980 0.2537628710 0.1197156310 660 1305031124.1474580765 0.0711032003 0.0365384660 0.0835322142 0.0106956317 0.0219940000 223105698 95654336 760807424 -0.0649564639 0.2459953427 0.1191456020 661 1305031124.1827070713 0.0714289472 0.0365912504 0.0835322142 0.0106908714 0.0207040000 223109226 95654336 760807424 -0.0679450184 0.2385764271 0.1244312301 662 1305031124.2171790600 0.0694141984 0.0366408319 0.0835322142 0.0106882566 0.0221750000 223111154 95654336 760807424 -0.0680900887 0.2320560962 0.1277732402 663 1305031124.2493400574 0.0646456331 0.0366830714 0.0835322142 0.0107057208 0.0222120000 223114570 95654336 760807424 -0.0701728538 0.2219538391 0.1274919063 664 1305031124.2825551033 0.0636818856 0.0367237323 0.0835322142 0.0107042409 0.0222650000 223116498 95654336 760807424 -0.0728441179 0.2110795677 0.1309323311 665 1305031124.3167819977 0.0619699061 0.0367616965 0.0835322142 0.0107006269 0.0304790000 223120042 95654336 760807424 -0.0717803910 0.2036010325 0.1341049075 666 1305031124.3503708839 0.0605775267 0.0367974560 0.0835322142 0.0106974108 0.0227670000 223123714 95654336 760807424 -0.0717875808 0.1931128651 0.1361363381 667 1305031124.3824319839 0.0615689047 0.0368345946 0.0835322142 0.0106942409 0.0224680000 223296430 95654336 760807424 -0.0706758350 0.1795709282 0.1403425783 668 1305031124.4185550213 0.0585730560 0.0368671372 0.0835322142 0.0106868725 0.0224970000 223300270 95654336 760807424 -0.0706876889 0.1735056341 0.1419911683 669 1305031124.4502561092 0.0562909953 0.0368961714 0.0835322142 0.0106871676 0.0227560000 223301846 95654336 760807424 -0.0719766840 0.1693840623 0.1430993080 670 1305031124.4801259041 0.0546513982 0.0369226717 0.0835322142 0.0106805764 0.0228540000 223305518 95654336 760807424 -0.0726377144 0.1532914042 0.1455005109 671 1305031124.5167369843 0.0505066961 0.0369429161 0.0835322142 0.0106761084 0.0300830000 223483186 95654336 760807424 -0.0730554461 0.1483644843 0.1460898370 672 1305031124.5505030155 0.0497824922 0.0369620227 0.0835322142 0.0106845985 0.0255500000 223485114 95654336 760807424 -0.0736898258 0.1244636178 0.1504397243 673 1305031124.5846059322 0.0483465232 0.0369789387 0.0835322142 0.0106875106 0.0251210000 223488962 95654336 760807424 -0.0711630732 0.1035294831 0.1509879082 674 1305031124.6176528931 0.0420979001 0.0369865336 0.0835322142 0.0106899593 0.0297910000 223490954 95654336 760807424 -0.0719640255 0.0918956250 0.1524998099 675 1305031124.6513130665 0.0404410996 0.0369916515 0.0835322142 0.0106883705 0.0247740000 223665438 95654336 760807424 -0.0715978891 0.0804877505 0.1556500942 676 1305031124.6854729652 0.0413592942 0.0369981125 0.0835322142 0.0106850101 0.0249340000 223669422 95654336 760807424 -0.0691698790 0.0662592575 0.1605330259 677 1305031124.7157909870 0.0353710353 0.0369957091 0.0835322142 0.0106784983 0.0247820000 223671286 95654336 760807424 -0.0685268268 0.0560901836 0.1633647531 678 1305031124.7499411106 0.0344057977 0.0369918892 0.0835322142 0.0106712625 0.0226270000 223674998 95654336 760807424 -0.0697645396 0.0428485610 0.1671748310 679 1305031124.7851779461 0.0340978242 0.0369876270 0.0835322142 0.0106641579 0.0246790000 223678654 95654336 760807424 -0.0709319711 0.0298584774 0.1715888232 680 1305031124.8166410923 0.0279575791 0.0369743475 0.0835322142 0.0106576511 0.0246290000 223680590 95654336 760807424 -0.0701005533 0.0192682538 0.1759688705 681 1305031124.8505589962 0.0294702929 0.0369633283 0.0835322142 0.0106511123 0.0245600000 223684054 95654336 760807424 -0.0698490366 0.0049995929 0.1820103675 682 1305031124.8835940361 0.0309160594 0.0369544613 0.0835322142 0.0106495511 0.0371090000 223685846 95654336 760807424 -0.0662658587 -0.0079502966 0.1888993680 683 1305031124.9187700748 0.0234748572 0.0369347255 0.0835322142 0.0106604016 0.0249330000 223689494 95654336 760807424 -0.0680664480 -0.0152183529 0.1937584877 684 1305031124.9507479668 0.0261720587 0.0369189906 0.0835322142 0.0106652031 0.0248530000 223693302 95654336 760807424 -0.0676841810 -0.0282139108 0.2002974004 685 1305031124.9864599705 0.0309104808 0.0369102190 0.0835322142 0.0106781379 0.0288140000 223695150 95654336 760807424 -0.0691558793 -0.0462127775 0.2082466632 686 1305031125.0194671154 0.0321653001 0.0369033022 0.0835322142 0.0106771573 0.0245450000 223699070 95654336 760807424 -0.0721434578 -0.0565288961 0.2130784392 687 1305031125.0507979393 0.0268409606 0.0368886554 0.0835322142 0.0106847514 0.0245540000 223700494 95654336 760807424 -0.0671656281 -0.0607092381 0.2169216126 688 1305031125.0834798813 0.0315348543 0.0368808738 0.0835322142 0.0106795931 0.0244420000 223704286 95654336 760807424 -0.0690632984 -0.0737120211 0.2223051786 689 1305031125.1190290451 0.0327681266 0.0368749046 0.0835322142 0.0106796834 0.0243460000 223707678 95654336 760807424 -0.0694734231 -0.0866580680 0.2276747376 690 1305031125.1510369778 0.0314790420 0.0368670845 0.0835322142 0.0106790910 0.0385360000 223709558 95654336 760807424 -0.0678596571 -0.0941221491 0.2314491719 691 1305031125.1870639324 0.0241374355 0.0368486624 0.0835322142 0.0106814033 0.0249930000 223713134 95654336 760807424 -0.0704008788 -0.0963193551 0.2320459038 692 1305031125.2190179825 0.0298618954 0.0368385660 0.0835322142 0.0106815140 0.0243210000 223715310 95654336 760807424 -0.0718885660 -0.1098308489 0.2382885665 693 1305031125.2506420612 0.0373871364 0.0368393575 0.0835322142 0.0106746595 0.0292420000 223719046 95654336 760807424 -0.0748199075 -0.1247886717 0.2424636185 694 1305031125.2863960266 0.0317094550 0.0368319658 0.0835322142 0.0106716192 0.0245300000 223722382 95654336 760807424 -0.0755807087 -0.1279047877 0.2432529181 695 1305031125.3191399574 0.0344664976 0.0368285622 0.0835322142 0.0106665377 0.0244720000 223724302 95654336 760807424 -0.0760419816 -0.1378058195 0.2481716573 696 1305031125.3488988876 0.0352537893 0.0368262996 0.0835322142 0.0106653989 0.0223800000 223727862 95654336 760807424 -0.0790754557 -0.1444715559 0.2496584654 697 1305031125.3867919445 0.0328160748 0.0368205461 0.0835322142 0.0106652313 0.0223700000 223731558 95654336 760807424 -0.0774766803 -0.1492024809 0.2518354356 698 1305031125.4195740223 0.0341754071 0.0368167565 0.0835322142 0.0106588853 0.0258500000 223733446 95654336 760807424 -0.0771932974 -0.1553127170 0.2548197508 699 1305031125.4512319565 0.0351817384 0.0368144174 0.0835322142 0.0106576527 0.0223970000 223736918 95654336 760807424 -0.0791852847 -0.1608802080 0.2581162453 700 1305031125.4869990349 0.0384599492 0.0368167681 0.0835322142 0.0106537509 0.0223380000 223738902 95654336 760807424 -0.0790644363 -0.1700768769 0.2623541057 701 1305031125.5193541050 0.0384906940 0.0368191560 0.0835322142 0.0106538298 0.0223700000 223742430 95654336 760807424 -0.0817466527 -0.1710561812 0.2616281211 702 1305031125.5510499477 0.0385565758 0.0368216310 0.0835322142 0.0106494255 0.0255190000 223746046 95654336 760807424 -0.0804545805 -0.1740176678 0.2633595765 703 1305031125.5853030682 0.0390580893 0.0368248123 0.0835322142 0.0106420539 0.0224260000 223747774 95654336 760807424 -0.0797616988 -0.1764374077 0.2646464705 704 1305031125.6178700924 0.0431672409 0.0368338214 0.0835322142 0.0106461494 0.0223860000 223751502 95654336 760807424 -0.0801720172 -0.1823705584 0.2663492858 705 1305031125.6505749226 0.0472498983 0.0368485960 0.0835322142 0.0106442791 0.0223210000 223753190 95654336 760807424 -0.0852398500 -0.1844879985 0.2639135122 706 1305031125.6846020222 0.0449323058 0.0368600460 0.0835322142 0.0106403899 0.0222780000 223756862 95654336 760807424 -0.0887036771 -0.1770658195 0.2567493618 707 1305031125.7156689167 0.0459970050 0.0368729696 0.0835322142 0.0106813309 0.0315070000 223931202 95654336 760807424 -0.0849998370 -0.1776916683 0.2576334178 708 1305031125.7512919903 0.0392966568 0.0368763929 0.0835322142 0.0106869162 0.0228220000 223933186 95654336 760807424 -0.0814068317 -0.1664444059 0.2506133020 709 1305031125.7868049145 0.0374563448 0.0368772109 0.0835322142 0.0106796912 0.0254570000 223936770 95654336 760807424 -0.0794188380 -0.1587045640 0.2473518103 710 1305031125.8194499016 0.0349040069 0.0368744317 0.0835322142 0.0106769941 0.0223920000 223938698 95654336 760807424 -0.0788663030 -0.1496966928 0.2427078635 711 1305031125.8547739983 0.0343257636 0.0368708471 0.0835322142 0.0106761769 0.0331030000 223942170 95654336 760807424 -0.0788038000 -0.1425100863 0.2397622615 712 1305031125.8866450787 0.0364838392 0.0368703035 0.0835322142 0.0106793586 0.0231950000 223945898 95654336 760807424 -0.0813707933 -0.1341077685 0.2350115776 713 1305031125.9193339348 0.0341058075 0.0368664263 0.0835322142 0.0106816215 0.0227360000 223947626 95654336 760807424 -0.0835054517 -0.1221561581 0.2302049994 714 1305031125.9552519321 0.0359244272 0.0368651069 0.0835322142 0.0106845368 0.0291540000 223952394 95654336 760807424 -0.0834570006 -0.1159561276 0.2289596200 715 1305031125.9870939255 0.0341374353 0.0368612920 0.0835322142 0.0106809653 0.0247520000 223956058 95654336 760807424 -0.0805015117 -0.1027728766 0.2252916098 716 1305031126.0195720196 0.0295139346 0.0368510303 0.0835322142 0.0106791713 0.0377510000 223958434 95654336 760807424 -0.0753131285 -0.0893022642 0.2223756760 717 1305031126.0550379753 0.0263939667 0.0368364459 0.0835322142 0.0106729498 0.0248770000 223962026 95654336 760807424 -0.0746522546 -0.0754794627 0.2184359431 718 1305031126.0870759487 0.0280488040 0.0368242068 0.0835322142 0.0106677483 0.0251310000 223963962 95654336 760807424 -0.0751087591 -0.0616431460 0.2150606662 719 1305031126.1194519997 0.0274385419 0.0368111530 0.0835322142 0.0106625201 0.0292390000 223967682 95654336 760807424 -0.0740675256 -0.0492863283 0.2135213315 720 1305031126.1549999714 0.0237685144 0.0367930383 0.0835322142 0.0106624764 0.0249240000 223971418 95654336 760807424 -0.0746209249 -0.0330369622 0.2106683701 721 1305031126.1871740818 0.0249521919 0.0367766154 0.0835322142 0.0106584874 0.0249550000 223973082 95654336 760807424 -0.0744059309 -0.0175999589 0.2074963450 722 1305031126.2194728851 0.0303335898 0.0367676916 0.0835322142 0.0106657127 0.0249200000 223977002 95654336 760807424 -0.0719965771 -0.0101214647 0.2071871012 723 1305031126.2552359104 0.0284417812 0.0367561758 0.0835322142 0.0106686291 0.0316540000 223978850 95654336 760807424 -0.0714968443 0.0050748829 0.2040174156 724 1305031126.2871050835 0.0326126218 0.0367504527 0.0835322142 0.0106625578 0.0252780000 223982530 95654336 760807424 -0.0712346956 0.0172842108 0.2014049888 725 1305031126.3197870255 0.0311876461 0.0367427798 0.0835322142 0.0106596130 0.0251360000 223986250 95654336 760807424 -0.0708401129 0.0318521783 0.1978988498 726 1305031126.3554151058 0.0336628631 0.0367385375 0.0835322142 0.0106553087 0.0254020000 223988242 95654336 760807424 -0.0691716745 0.0428018719 0.1969471872 727 1305031126.3874828815 0.0376895852 0.0367398457 0.0835322142 0.0106513032 0.0252770000 224162822 95654336 760807424 -0.0700453147 0.0529642589 0.1937508583 728 1305031126.4197928905 0.0372667424 0.0367405695 0.0835322142 0.0106508151 0.0251480000 224164766 95654336 760807424 -0.0713293403 0.0647268295 0.1900417358 729 1305031126.4553799629 0.0377896577 0.0367420085 0.0835322142 0.0106505463 0.0251700000 224338714 95654336 760807424 -0.0731487274 0.0773337781 0.1874280274 730 1305031126.4903860092 0.0430676118 0.0367506737 0.0835322142 0.0106538882 0.0229060000 224342482 95654336 760807424 -0.0740993246 0.0854500532 0.1844892204 731 1305031126.5223209858 0.0409671552 0.0367564418 0.0835322142 0.0106552267 0.0260950000 224344154 95654336 760807424 -0.0757849365 0.1019572616 0.1811272204 732 1305031126.5582089424 0.0437020324 0.0367659304 0.0835322142 0.0106521797 0.0243680000 224347938 95654336 760807424 -0.0732479617 0.1148743778 0.1794671714 733 1305031126.5901761055 0.0457972772 0.0367782514 0.0835322142 0.0106451191 0.0228940000 224351410 95654336 760807424 -0.0696788579 0.1218949929 0.1781870872 734 1305031126.6186869144 0.0462197438 0.0367911145 0.0835322142 0.0106384416 0.0228470000 224353170 95654336 760807424 -0.0698157474 0.1311020255 0.1756576896 735 1305031126.6544740200 0.0505836532 0.0368098799 0.0835322142 0.0106458910 0.0227690000 224356794 95654336 760807424 -0.0673387349 0.1348490268 0.1764294356 736 1305031126.6900219917 0.0527555682 0.0368315452 0.0835322142 0.0106420972 0.0237870000 224358778 95654336 760807424 -0.0664700568 0.1408329755 0.1738726497 737 1305031126.7157700062 0.0525727831 0.0368529037 0.0835322142 0.0106372999 0.0229220000 224533946 95654336 760807424 -0.0652567670 0.1485777497 0.1711139679 738 1305031126.7553739548 0.0558315627 0.0368786201 0.0835322142 0.0106307097 0.0227900000 224537842 95654336 760807424 -0.0635591149 0.1502854228 0.1706575751 739 1305031126.7875649929 0.0553573780 0.0369036252 0.0835322142 0.0106294728 0.0228010000 224539514 95654336 760807424 -0.0616281256 0.1589408070 0.1671887040 740 1305031126.8199288845 0.0577129088 0.0369317458 0.0835322142 0.0106236670 0.0283540000 224543154 95654336 760807424 -0.0584344380 0.1600741893 0.1662401855 741 1305031126.8583779335 0.0574858338 0.0369594841 0.0835322142 0.0106168505 0.0228490000 224545050 95654336 760807424 -0.0568574779 0.1645622104 0.1631546170 742 1305031126.8881540298 0.0572613589 0.0369868451 0.0835322142 0.0106112261 0.0263820000 224548650 95654336 760807424 -0.0562505685 0.1683487892 0.1611578614 743 1305031126.9194090366 0.0572652183 0.0370141377 0.0835322142 0.0106046117 0.0227440000 224723198 95654336 760807424 -0.0553231612 0.1696069837 0.1597885787 744 1305031126.9555010796 0.0563204512 0.0370400870 0.0835322142 0.0106002542 0.0259420000 224725182 95654336 760807424 -0.0554516539 0.1722251773 0.1579850763 745 1305031126.9873158932 0.0578633286 0.0370680377 0.0835322142 0.0105941369 0.0227110000 224728710 95654336 760807424 -0.0557323694 0.1697221845 0.1579800099 746 1305031127.0195240974 0.0580069721 0.0370961060 0.0835322142 0.0105893631 0.0226760000 224730510 95654336 760807424 -0.0538255237 0.1705942303 0.1576288342 747 1305031127.0533180237 0.0567496195 0.0371224159 0.0835322142 0.0105869564 0.0226960000 224734038 95654336 760807424 -0.0541869588 0.1717367172 0.1565228701 748 1305031127.0886490345 0.0567397997 0.0371486424 0.0835322142 0.0105900495 0.0227310000 224737822 95654336 760807424 -0.0542882383 0.1686994582 0.1571444273 749 1305031127.1209630966 0.0566465594 0.0371746743 0.0835322142 0.0105907704 0.0259870000 224739438 95654336 760807424 -0.0553988740 0.1657795906 0.1575130969 750 1305031127.1576919556 0.0561602637 0.0371999884 0.0835322142 0.0105841299 0.0237440000 224743278 95654336 760807424 -0.0572689399 0.1644640416 0.1582293212 751 1305031127.1875000000 0.0548594557 0.0372235030 0.0835322142 0.0105820719 0.0228080000 224746694 95654336 760807424 -0.0566589870 0.1640686095 0.1581644416 752 1305031127.2218310833 0.0561679043 0.0372486950 0.0835322142 0.0105803415 0.0227380000 224748622 95654336 760807424 -0.0558346100 0.1606435627 0.1602888852 753 1305031127.2597610950 0.0557429641 0.0372732558 0.0835322142 0.0105767651 0.0228860000 224752262 95654336 760807424 -0.0564057529 0.1576473713 0.1623979509 754 1305031127.2870380878 0.0531687327 0.0372943373 0.0835322142 0.0105823403 0.0250680000 224755502 95654336 760807424 -0.0571554378 0.1580159068 0.1619924456 755 1305031127.3204679489 0.0545212403 0.0373171544 0.0835322142 0.0105803972 0.0250980000 224758822 95654336 760807424 -0.0577712059 0.1504052281 0.1645261645 756 1305031127.3534069061 0.0563945919 0.0373423891 0.0835322142 0.0105750141 0.0228640000 224762494 95654336 760807424 -0.0570302419 0.1457996219 0.1679519713 757 1305031127.3837130070 0.0531542972 0.0373632767 0.0835322142 0.0105725839 0.0251200000 224764294 95654336 760807424 -0.0586221814 0.1467978209 0.1675519496 758 1305031127.4196500778 0.0525707416 0.0373833394 0.0835322142 0.0105658423 0.0288930000 224768214 95654336 760807424 -0.0588224232 0.1426357627 0.1691379845 759 1305031127.4542460442 0.0542920120 0.0374056169 0.0835322142 0.0105680271 0.0251750000 224770462 95654336 760807424 -0.0590999350 0.1384294182 0.1725222915 760 1305031127.4872000217 0.0504664369 0.0374228022 0.0835322142 0.0105815169 0.0250310000 224774198 95654336 760807424 -0.0604953207 0.1409872472 0.1719431281 761 1305031127.5218999386 0.0519331507 0.0374418697 0.0835322142 0.0105808616 0.0264240000 224777782 95654336 760807424 -0.0600637645 0.1364856511 0.1740094870 762 1305031127.5537250042 0.0536156334 0.0374630951 0.0835322142 0.0105812703 0.0251150000 224779726 95654336 760807424 -0.0607561842 0.1327191740 0.1769985855 763 1305031127.5866320133 0.0512509197 0.0374811656 0.0835322142 0.0105776305 0.0228670000 224783254 95654336 760807424 -0.0602784231 0.1335475147 0.1766256094 764 1305031127.6206569672 0.0504815131 0.0374981818 0.0835322142 0.0105708456 0.0229970000 224785182 95654336 760807424 -0.0605332442 0.1337174177 0.1772792041 765 1305031127.6546559334 0.0543140136 0.0375201633 0.0835322142 0.0105668883 0.0228720000 224788654 95654336 760807424 -0.0603041723 0.1275302619 0.1804583967 766 1305031127.6871099472 0.0531623252 0.0375405839 0.0835322142 0.0105619469 0.0290330000 224792638 95654336 760807424 -0.0603695475 0.1272940785 0.1805137694 767 1305031127.7232100964 0.0497616678 0.0375565175 0.0835322142 0.0105570305 0.0229180000 224794422 95654336 760807424 -0.0615289733 0.1306553632 0.1789088547 768 1305031127.7546939850 0.0527990647 0.0375763645 0.0835322142 0.0105538201 0.0230020000 224798038 95654336 760807424 -0.0609431863 0.1261661351 0.1814596355 769 1305031127.7876410484 0.0531787984 0.0375966538 0.0835322142 0.0105500589 0.0229160000 224801622 95654336 760807424 -0.0602703691 0.1242228821 0.1819592416 770 1305031127.8201279640 0.0508427098 0.0376138565 0.0835322142 0.0105443461 0.0228950000 224803438 95654336 760807424 -0.0610375553 0.1253558546 0.1804895699 771 1305031127.8551321030 0.0514064319 0.0376317457 0.0835322142 0.0105376385 0.0230270000 224806966 95654336 760807424 -0.0621532090 0.1239317730 0.1810333878 772 1305031127.8871219158 0.0514026470 0.0376495836 0.0835322142 0.0105313994 0.0230120000 224808894 95654336 760807424 -0.0620899051 0.1226245984 0.1812648326 773 1305031127.9225599766 0.0506823733 0.0376664436 0.0835322142 0.0105263100 0.0229280000 224812478 95654336 760807424 -0.0634919927 0.1222119257 0.1810422987 774 1305031127.9550879002 0.0492425933 0.0376813999 0.0835322142 0.0105202208 0.0229260000 224816150 95654336 760807424 -0.0642682016 0.1229150817 0.1809820086 775 1305031127.9870929718 0.0493181683 0.0376964151 0.0835322142 0.0105138725 0.0267870000 224817822 95654336 760807424 -0.0638366118 0.1211285964 0.1827993989 776 1305031128.0217759609 0.0485925078 0.0377104564 0.0835322142 0.0105109889 0.0230550000 224821606 95654336 760807424 -0.0634425059 0.1221474931 0.1845241189 777 1305031128.0557179451 0.0505286716 0.0377269535 0.0835322142 0.0105103392 0.0230080000 224994630 95654336 760807424 -0.0630390495 0.1189441979 0.1882587373 778 1305031128.0872058868 0.0518538542 0.0377451115 0.0835322142 0.0105043088 0.0240290000 224998302 95654336 760807424 -0.0617086738 0.1163985804 0.1905542761 779 1305031128.1247460842 0.0507815965 0.0377618464 0.0835322142 0.0104996302 0.0230610000 225001942 95654336 760807424 -0.0613152683 0.1159626395 0.1911162138 780 1305031128.1577820778 0.0513245091 0.0377792344 0.0835322142 0.0104965710 0.0301090000 225004958 95654336 760807424 -0.0613071695 0.1144642681 0.1931034029 781 1305031128.1872210503 0.0538198091 0.0377997729 0.0835322142 0.0104914658 0.0230920000 225008318 95654336 760807424 -0.0593679734 0.1114400998 0.1956734210 782 1305031128.2254419327 0.0507332645 0.0378163119 0.0835322142 0.0104906320 0.0231710000 225010358 95654336 760807424 -0.0604601800 0.1128526106 0.1940139085 783 1305031128.2560069561 0.0497133397 0.0378315061 0.0835322142 0.0104865600 0.0231060000 225013774 95654336 760807424 -0.0602407865 0.1131369025 0.1939654499 784 1305031128.2912750244 0.0533948280 0.0378513572 0.0835322142 0.0104844283 0.0265280000 225017558 95654336 760807424 -0.0592204891 0.1086947024 0.1964411288 785 1305031128.3241701126 0.0505691394 0.0378675582 0.0835322142 0.0104809531 0.0230830000 225019230 95654336 760807424 -0.0595365688 0.1113474295 0.1948154271 786 1305031128.3552060127 0.0504147299 0.0378835216 0.0835322142 0.0104745171 0.0230710000 225022902 95654336 760807424 -0.0605685785 0.1106935963 0.1946607232 787 1305031128.3913969994 0.0521342941 0.0379016293 0.0835322142 0.0104685220 0.0230480000 225026486 95654336 760807424 -0.0602832660 0.1084515899 0.1957897246 788 1305031128.4236090183 0.0507795103 0.0379179718 0.0835322142 0.0104623930 0.0231030000 225028358 95654336 760807424 -0.0619659126 0.1089196801 0.1948553473 789 1305031128.4554989338 0.0503994152 0.0379337911 0.0835322142 0.0104576043 0.0231190000 225031830 95654336 760807424 -0.0632129014 0.1082300097 0.1944219768 790 1305031128.4895229340 0.0509825945 0.0379503085 0.0835322142 0.0104519551 0.0232180000 225033814 95654336 760807424 -0.0629468262 0.1071125716 0.1948808432 791 1305031128.5236039162 0.0504131243 0.0379660643 0.0835322142 0.0104455047 0.0231460000 225037286 95654336 760807424 -0.0625489652 0.1068400368 0.1947002262 792 1305031128.5556390285 0.0508520007 0.0379823344 0.0835322142 0.0104406227 0.0240060000 225040958 95654336 760807424 -0.0631240383 0.1048672572 0.1947540939 793 1305031128.5914599895 0.0507944264 0.0379984909 0.0835322142 0.0104345528 0.0274280000 225042742 95654336 760807424 -0.0641454756 0.1043538675 0.1948126256 794 1305031128.6233680248 0.0504129007 0.0380141262 0.0835322142 0.0104285821 0.0231860000 225046414 95654336 760807424 -0.0644974038 0.1036197171 0.1943346262 795 1305031128.6555540562 0.0495692715 0.0380286610 0.0835322142 0.0104240147 0.0231740000 225048086 95654336 760807424 -0.0653460100 0.1039037928 0.1935940385 796 1305031128.6904489994 0.0508633964 0.0380447850 0.0835322142 0.0104203656 0.0232150000 225051870 95654336 760807424 -0.0642799586 0.1015521958 0.1938426495 797 1305031128.7229759693 0.0510836057 0.0380611449 0.0835322142 0.0104149690 0.0265450000 225055342 95654336 760807424 -0.0621159188 0.1010504216 0.1937412620 798 1305031128.7546460629 0.0492593385 0.0380751777 0.0835322142 0.0104116264 0.0232370000 225057214 95654336 760807424 -0.0634245574 0.1025227755 0.1924630553 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:28:02 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 -nan 0.0320680000 207875476 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0023757904 0.0021392212 0.0023757904 0.0024888720 0.0238350000 220506482 95654128 760807424 0.0012535966 0.0008017338 0.0003991825 3 1311867718.7114279270 0.0041158949 0.0027981124 0.0041158949 0.0041525669 0.0257830000 220510578 95654128 760807424 0.0021870739 0.0028618844 0.0005749338 4 1311867718.7410299778 0.0054751830 0.0034673801 0.0054751830 0.0053749264 0.0198160000 220511994 95654128 760807424 0.0040237992 -0.0000246798 0.0020571628 5 1311867718.7767970562 0.0041733584 0.0036085757 0.0054751830 0.0047269215 0.0178860000 220516514 95654128 760807424 0.0023760821 -0.0006795623 0.0017604484 6 1311867718.8094089031 0.0037267066 0.0036282642 0.0054751830 0.0045765081 0.0539540000 220518986 95654128 760807424 0.0005762964 0.0026114089 0.0007859258 7 1311867718.8408079147 0.0033787719 0.0035926225 0.0054751830 0.0044650778 0.0179270000 220522534 95654128 760807424 -0.0000581779 0.0021461248 0.0010347841 8 1311867718.8767778873 0.0037543722 0.0036128412 0.0054751830 0.0044371966 0.0179180000 220526118 95654128 760807424 -0.0012131878 0.0016416633 0.0005379958 9 1311867718.9088680744 0.0051993951 0.0037891250 0.0054751830 0.0043431601 0.0179010000 220529406 95654128 760807424 -0.0000203857 0.0030098273 0.0004782840 10 1311867718.9438331127 0.0046613952 0.0038763520 0.0054751830 0.0041082213 0.0178910000 220534590 95654128 760807424 0.0008289242 0.0025459740 0.0020138903 11 1311867718.9784109592 0.0029233736 0.0037897176 0.0054751830 0.0039685249 0.0249060000 220708266 95654128 760807424 -0.0001527356 0.0014970044 0.0035275300 12 1311867719.0091300011 0.0037229760 0.0037841558 0.0054751830 0.0037930316 0.0184250000 220709826 95654128 760807424 0.0005228940 0.0015535189 0.0036949250 13 1311867719.0441620350 0.0038857583 0.0037919714 0.0054751830 0.0038715368 0.0178820000 220713610 95654128 760807424 0.0002198729 0.0030633057 0.0045247520 14 1311867719.0776190758 0.0044127139 0.0038363101 0.0054751830 0.0037613318 0.0178690000 220717270 95654128 760807424 0.0007239133 0.0029453302 0.0046384945 15 1311867719.1086950302 0.0059524174 0.0039773839 0.0059524174 0.0036276051 0.0178760000 220718942 95654128 760807424 0.0014818162 0.0042224517 0.0044742227 16 1311867719.1437010765 0.0056344336 0.0040809495 0.0059524174 0.0035300804 0.0179340000 220722470 95654128 760807424 0.0011786493 0.0037823578 0.0055802353 17 1311867719.1810290813 0.0055839131 0.0041693592 0.0059524174 0.0035702610 0.0179700000 220727398 95654128 760807424 0.0012425496 0.0027512996 0.0057311924 18 1311867719.2127099037 0.0095843356 0.0044701912 0.0095843356 0.0036448177 0.0179320000 220734070 95654128 760807424 0.0053926436 0.0015571796 0.0065865726 19 1311867719.2412090302 0.0098692244 0.0047543508 0.0098692244 0.0036785353 0.0179210000 220737430 95654128 760807424 0.0050768573 0.0029031979 0.0069462471 20 1311867719.2779469490 0.0069490541 0.0048640860 0.0098692244 0.0039231414 0.0179360000 220739158 95654128 760807424 0.0014102336 0.0021285815 0.0073061665 21 1311867719.3104898930 0.0063200174 0.0049334161 0.0098692244 0.0038651171 0.0185090000 220743018 95654128 760807424 0.0002832722 0.0026436155 0.0071431021 22 1311867719.3413150311 0.0092955986 0.0051316971 0.0098692244 0.0040341191 0.0181090000 220746474 95654128 760807424 0.0030720565 0.0018671525 0.0080941916 23 1311867719.3772718906 0.0084027322 0.0052739160 0.0098692244 0.0039998901 0.0179360000 220748202 95654128 760807424 0.0018185693 -0.0000060301 0.0082572345 24 1311867719.4105761051 0.0089364350 0.0054265210 0.0098692244 0.0039473744 0.0215510000 220751730 95654128 760807424 0.0020405715 -0.0003703764 0.0080421055 25 1311867719.4427709579 0.0109712090 0.0056483085 0.0109712090 0.0039613758 0.0183410000 220926346 95654128 760807424 0.0032661201 -0.0037479696 0.0100166108 26 1311867719.4787840843 0.0100241825 0.0058166113 0.0109712090 0.0039100729 0.0179850000 220928074 95654128 760807424 0.0016361289 -0.0047707530 0.0104685873 27 1311867719.5104370117 0.0087244706 0.0059243098 0.0109712090 0.0039095183 0.0210440000 220931546 95654128 760807424 0.0007572343 -0.0033314312 0.0095452340 28 1311867719.5449650288 0.0089205531 0.0060313185 0.0109712090 0.0039419575 0.0181550000 220935074 95654128 760807424 0.0000377939 -0.0037149256 0.0092526572 29 1311867719.5771939754 0.0088463398 0.0061283882 0.0109712090 0.0038825707 0.0180350000 220937002 95654128 760807424 -0.0006736335 -0.0044579823 0.0106584858 30 1311867719.6112511158 0.0099184709 0.0062547243 0.0109712090 0.0038898926 0.0180250000 220940514 95654128 760807424 0.0002675924 -0.0025180872 0.0108385123 31 1311867719.6421909332 0.0129579622 0.0064709578 0.0129579622 0.0038438381 0.0179680000 220942130 95654128 760807424 0.0028589936 -0.0018061883 0.0115388921 32 1311867719.6770479679 0.0135235544 0.0066913514 0.0135235544 0.0038171766 0.0180840000 221115354 95654128 760807424 0.0027439862 -0.0022332377 0.0128519889 33 1311867719.7107939720 0.0129970098 0.0068824320 0.0135235544 0.0037789964 0.0204980000 221124914 95654128 760807424 0.0017535338 0.0000038028 0.0126800481 34 1311867719.7442650795 0.0152551662 0.0071286889 0.0152551662 0.0037839195 0.0180930000 221132986 95654128 760807424 0.0035534617 0.0000329983 0.0129862344 35 1311867719.7861878872 0.0174411573 0.0074233308 0.0174411573 0.0037620926 0.0180150000 221136794 95654128 760807424 0.0049903877 -0.0009046473 0.0141749838 36 1311867719.8099169731 0.0174369253 0.0077014862 0.0174411573 0.0037259819 0.0180190000 221139986 95654128 760807424 0.0042523332 -0.0017229759 0.0157265421 37 1311867719.8454990387 0.0161762293 0.0079305333 0.0174411573 0.0037129336 0.0180480000 221141970 95654128 760807424 0.0019225117 -0.0043293033 0.0170858800 38 1311867719.8771090508 0.0140459025 0.0080914641 0.0174411573 0.0037006129 0.0180760000 221145442 95654128 760807424 -0.0002133101 -0.0048560603 0.0160552468 39 1311867719.9114089012 0.0135940071 0.0082325550 0.0174411573 0.0037126318 0.0181610000 221320822 95654128 760807424 -0.0011289383 -0.0035705986 0.0168589279 40 1311867719.9461970329 0.0136848642 0.0083688627 0.0174411573 0.0037023043 0.0213270000 221322550 95654128 760807424 -0.0017692891 -0.0049074804 0.0179141015 41 1311867719.9807810783 0.0144382715 0.0085168970 0.0174411573 0.0036717080 0.0182360000 221326262 95654128 760807424 -0.0016094656 -0.0050183428 0.0185893159 42 1311867720.0117020607 0.0124727562 0.0086110842 0.0174411573 0.0036420285 0.0181160000 221327934 95654128 760807424 -0.0033448832 -0.0037158872 0.0173531827 43 1311867720.0452380180 0.0135468561 0.0087258696 0.0174411573 0.0036226672 0.0181580000 221331406 95654128 760807424 -0.0029442059 -0.0041612857 0.0187677443 44 1311867720.0772819519 0.0160446130 0.0088922046 0.0174411573 0.0036029144 0.0263190000 221334934 95654128 760807424 -0.0012118916 -0.0053897589 0.0203286316 45 1311867720.1172130108 0.0174873732 0.0090832084 0.0174873732 0.0035686067 0.0189820000 221507182 95654128 760807424 -0.0000986350 -0.0059935884 0.0209620185 46 1311867720.1451559067 0.0163667127 0.0092415454 0.0174873732 0.0035531985 0.0181540000 221510486 95654128 760807424 -0.0010002836 -0.0049615935 0.0206216369 47 1311867720.1781630516 0.0159988198 0.0093853172 0.0174873732 0.0035322483 0.0181320000 221513958 95654128 760807424 -0.0015022026 -0.0048818118 0.0212723520 48 1311867720.2094950676 0.0149630439 0.0095015199 0.0174873732 0.0035058266 0.0182170000 221515614 95654128 760807424 -0.0023765087 -0.0040985681 0.0211282112 49 1311867720.2421469688 0.0163855739 0.0096420108 0.0174873732 0.0035130409 0.0181560000 221519342 95654128 760807424 -0.0010209713 -0.0042230627 0.0216280762 50 1311867720.2770779133 0.0140451593 0.0097300737 0.0174873732 0.0035236555 0.0182700000 221522870 95654128 760807424 -0.0033218288 -0.0027634106 0.0216969214 51 1311867720.3094570637 0.0147435786 0.0098283778 0.0174873732 0.0035029017 0.0182880000 221524542 95654128 760807424 -0.0024445481 -0.0019307485 0.0217392594 52 1311867720.3430728912 0.0155998021 0.0099393667 0.0174873732 0.0034996472 0.0184210000 221697990 95654128 760807424 -0.0027929987 -0.0044536684 0.0229603574 53 1311867720.3779859543 0.0147704380 0.0100305190 0.0174873732 0.0034696446 0.0183530000 221699862 95654128 760807424 -0.0050727222 -0.0066933371 0.0238298476 54 1311867720.4096798897 0.0137139391 0.0100987305 0.0174873732 0.0035759145 0.0289070000 221703334 95654136 760807424 -0.0057777865 -0.0043861074 0.0235941820 55 1311867720.4461109638 0.0134902056 0.0101603936 0.0174873732 0.0035503006 0.0194170000 221706974 95654136 760807424 -0.0059620542 -0.0031682879 0.0243493766 56 1311867720.4799289703 0.0125672650 0.0102033735 0.0174873732 0.0035445244 0.0184690000 221708702 95654136 760807424 -0.0075261267 -0.0033765472 0.0249594022 57 1311867720.5104389191 0.0121910535 0.0102382451 0.0174873732 0.0035855181 0.0214990000 221712286 95654136 760807424 -0.0075640217 -0.0030230668 0.0238699410 58 1311867720.5467319489 0.0116775045 0.0102630599 0.0174873732 0.0035915897 0.0186640000 221715926 95654136 760807424 -0.0089613320 -0.0033500190 0.0230645854 59 1311867720.5793280602 0.0126368282 0.0103032932 0.0174873732 0.0036580368 0.0216260000 221717598 95654136 760807424 -0.0093096904 -0.0061172359 0.0243728682 60 1311867720.6121249199 0.0132935522 0.0103531309 0.0174873732 0.0036383019 0.0187490000 221721070 95654136 760807424 -0.0093224011 -0.0064590089 0.0241041277 61 1311867720.6463210583 0.0104620457 0.0103549164 0.0174873732 0.0036559291 0.0188160000 221894794 95654136 760807424 -0.0119763324 -0.0043092035 0.0231613759 62 1311867720.6798269749 0.0108061479 0.0103621943 0.0174873732 0.0036509265 0.0222310000 221896394 95654136 760807424 -0.0132367499 -0.0061916406 0.0236871913 63 1311867720.7102439404 0.0120791569 0.0103894477 0.0174873732 0.0036296168 0.0217830000 221899866 95654136 760807424 -0.0139808385 -0.0085816709 0.0242243372 64 1311867720.7451629639 0.0106688738 0.0103938137 0.0174873732 0.0036323129 0.0188530000 221903394 95654136 760807424 -0.0152585059 -0.0076159555 0.0224681012 65 1311867720.7790179253 0.0135466717 0.0104423192 0.0174873732 0.0036174177 0.0187460000 221917154 95654136 760807424 -0.0116730696 -0.0053481041 0.0237222277 66 1311867720.8115909100 0.0129558509 0.0104804030 0.0174873732 0.0035954490 0.0220170000 221933426 95654136 760807424 -0.0130904689 -0.0047153668 0.0250386000 67 1311867720.8467299938 0.0130557725 0.0105188414 0.0174873732 0.0035772598 0.0189520000 221935210 95654136 760807424 -0.0133372173 -0.0041719070 0.0251076352 68 1311867720.8813319206 0.0142876487 0.0105742650 0.0174873732 0.0035751018 0.0188520000 221938738 95654136 760807424 -0.0125812031 -0.0042991950 0.0256573278 69 1311867720.9149661064 0.0148710050 0.0106365366 0.0174873732 0.0035543656 0.0195250000 221942410 95654136 760807424 -0.0126443198 -0.0036360219 0.0267655868 70 1311867720.9500010014 0.0141403917 0.0106865917 0.0174873732 0.0035314543 0.0226360000 221944138 95654136 760807424 -0.0135281710 -0.0034515478 0.0263222773 71 1311867720.9797990322 0.0145044392 0.0107403642 0.0174873732 0.0035096150 0.0190510000 221947482 95654136 760807424 -0.0133775221 -0.0032613801 0.0264500882 72 1311867721.0093889236 0.0145033970 0.0107926285 0.0174873732 0.0035025366 0.0189350000 221950898 95654136 760807424 -0.0140907345 -0.0051152059 0.0262973849 73 1311867721.0478379726 0.0147229591 0.0108464687 0.0174873732 0.0034898665 0.0290490000 221952994 95654136 760807424 -0.0144806392 -0.0062411670 0.0257092956 74 1311867721.0794439316 0.0136580300 0.0108844628 0.0174873732 0.0034692655 0.0227460000 222128922 95654136 760807424 -0.0151158180 -0.0046963501 0.0254583284 75 1311867721.1103579998 0.0148355905 0.0109371445 0.0174873732 0.0034520181 0.0192070000 222132378 95654136 760807424 -0.0144259827 -0.0048601632 0.0260645039 76 1311867721.1467890739 0.0138201071 0.0109750782 0.0174873732 0.0034670415 0.0191290000 222134162 95654136 760807424 -0.0155774448 -0.0036012284 0.0253379885 77 1311867721.1774179935 0.0138483569 0.0110123935 0.0174873732 0.0035034206 0.0191350000 222137834 95654136 760807424 -0.0156618599 -0.0038928166 0.0253631603 78 1311867721.2112360001 0.0143306041 0.0110549347 0.0174873732 0.0034860444 0.0306780000 222139506 95654136 760807424 -0.0155263068 -0.0045136069 0.0249639340 79 1311867721.2469010353 0.0151718408 0.0111070474 0.0174873732 0.0034784491 0.0205810000 222143090 95654136 760807424 -0.0153780663 -0.0052296068 0.0254943613 80 1311867721.2800450325 0.0150800878 0.0111567104 0.0174873732 0.0035014909 0.0192170000 222146546 95654136 760807424 -0.0155225759 -0.0048552854 0.0247458499 81 1311867721.3099579811 0.0167630836 0.0112259249 0.0174873732 0.0035070008 0.0192400000 222148362 95654136 760807424 -0.0146863488 -0.0061744889 0.0252880603 82 1311867721.3483059406 0.0143867983 0.0112644721 0.0174873732 0.0035313005 0.0279170000 222152002 95654136 760807424 -0.0164290424 -0.0037673395 0.0239946656 83 1311867721.3790040016 0.0129366415 0.0112846187 0.0174873732 0.0035111239 0.0199920000 222155362 95654136 760807424 -0.0179305095 -0.0034112311 0.0224857461 84 1311867721.4092550278 0.0125663830 0.0112998778 0.0174873732 0.0034904869 0.0194240000 222327366 95654136 760807424 -0.0186438933 -0.0027057517 0.0226180200 85 1311867721.4478130341 0.0129438844 0.0113192191 0.0174873732 0.0034736480 0.0192720000 222331286 95654136 760807424 -0.0190836191 -0.0030841294 0.0229455996 86 1311867721.4768960476 0.0142636718 0.0113534569 0.0174873732 0.0034623998 0.0193050000 222334646 95654136 760807424 -0.0182640608 -0.0037589299 0.0227007344 87 1311867721.5093359947 0.0133469850 0.0113763710 0.0174873732 0.0034497524 0.0228630000 222336262 95654136 760807424 -0.0198002066 -0.0032605948 0.0234400369 88 1311867721.5451331139 0.0129081691 0.0113937778 0.0174873732 0.0034313230 0.0195870000 222339790 95654136 760807424 -0.0205262229 -0.0033434248 0.0225490481 89 1311867721.5769670010 0.0128391283 0.0114100177 0.0174873732 0.0034130281 0.0193830000 222341550 95654136 760807424 -0.0204207487 -0.0025988780 0.0221374240 90 1311867721.6129651070 0.0157006290 0.0114576912 0.0174873732 0.0034368445 0.0193490000 222345078 95654136 760807424 -0.0185986105 -0.0035459581 0.0234865174 91 1311867721.6496050358 0.0139961848 0.0114855867 0.0174873732 0.0034583799 0.0194790000 222348702 95654136 760807424 -0.0207424611 -0.0041444637 0.0215356201 92 1311867721.6800351143 0.0140127968 0.0115130564 0.0174873732 0.0034400320 0.0189990000 222350318 95654136 760807424 -0.0198620819 -0.0023952546 0.0199020468 93 1311867721.7162289619 0.0131872566 0.0115310585 0.0174873732 0.0034920379 0.0194070000 222354158 95654136 760807424 -0.0219881386 -0.0036240243 0.0210922528 94 1311867721.7467949390 0.0146650663 0.0115643990 0.0174873732 0.0035407580 0.0194040000 222357574 95654136 760807424 -0.0214977507 -0.0044467095 0.0214571673 95 1311867721.7787001133 0.0111996755 0.0115605598 0.0174873732 0.0035371752 0.0194880000 222529454 95654136 760807424 -0.0237459578 -0.0009985121 0.0207997896 96 1311867721.8154830933 0.0117808040 0.0115628541 0.0174873732 0.0035212584 0.0197430000 222533038 95654136 760807424 -0.0237918701 -0.0012313237 0.0209200922 97 1311867721.8485159874 0.0148859024 0.0115971123 0.0174873732 0.0035300007 0.0195660000 222536766 95654136 760807424 -0.0224500503 -0.0042525260 0.0208115950 98 1311867721.8778810501 0.0132646700 0.0116141282 0.0174873732 0.0035275432 0.0194070000 222538382 95654136 760807424 -0.0227390081 -0.0012922587 0.0200316478 99 1311867721.9146931171 0.0142947519 0.0116412052 0.0174873732 0.0035189797 0.0194340000 222541742 95654136 760807424 -0.0234161634 -0.0035209244 0.0203245711 100 1311867721.9467151165 0.0128136240 0.0116529294 0.0174873732 0.0035057536 0.0194490000 222545214 95654136 760807424 -0.0244432744 -0.0021458119 0.0193768032 101 1311867721.9773728848 0.0134758679 0.0116709783 0.0174873732 0.0035016700 0.0194530000 222547086 95654136 760807424 -0.0235094130 -0.0015219490 0.0196167566 102 1311867722.0166850090 0.0139559032 0.0116933795 0.0174873732 0.0035117051 0.0194510000 222550598 95654136 760807424 -0.0241965801 -0.0021041094 0.0205264203 103 1311867722.0475180149 0.0127993012 0.0117041166 0.0174873732 0.0035210541 0.0195470000 222552102 95654136 760807424 -0.0242834371 -0.0006726221 0.0191603154 104 1311867722.0800709724 0.0117596323 0.0117046504 0.0174873732 0.0035174705 0.0225340000 222555630 95654136 760807424 -0.0260079969 -0.0012276539 0.0186395124 105 1311867722.1161251068 0.0130717298 0.0117176702 0.0174873732 0.0035095668 0.0196160000 222559414 95654136 760807424 -0.0259075835 -0.0029563459 0.0181477740 106 1311867722.1479530334 0.0123209534 0.0117233616 0.0174873732 0.0035004212 0.0196140000 222561030 95654136 760807424 -0.0264791772 -0.0022562416 0.0170363076 107 1311867722.1798410416 0.0131055191 0.0117362789 0.0174873732 0.0034888074 0.0195450000 222564502 95654136 760807424 -0.0250347666 -0.0002773146 0.0178535730 108 1311867722.2146399021 0.0145593369 0.0117624183 0.0174873732 0.0034993922 0.0195400000 222568086 95654136 760807424 -0.0254800655 -0.0033949520 0.0182703342 109 1311867722.2469589710 0.0156782046 0.0117983430 0.0174873732 0.0034928038 0.0195310000 222569958 95654136 760807424 -0.0245135091 -0.0039995620 0.0178816393 110 1311867722.2780389786 0.0151199661 0.0118285396 0.0174873732 0.0034792564 0.0230030000 222573430 95654136 760807424 -0.0245268401 -0.0030133296 0.0170844924 111 1311867722.3154170513 0.0143818865 0.0118515427 0.0174873732 0.0034653846 0.0287730000 222577014 95654136 760807424 -0.0259931032 -0.0032588341 0.0175916608 112 1311867722.3488469124 0.0152191836 0.0118816109 0.0174873732 0.0034529322 0.0205480000 222578686 95654136 760807424 -0.0259470381 -0.0038590282 0.0184940919 113 1311867722.3777940273 0.0114583569 0.0118778653 0.0174873732 0.0034571490 0.0192110000 222582302 95654136 760807424 -0.0282617267 -0.0010884537 0.0171288196 114 1311867722.4150679111 0.0140963877 0.0118973260 0.0174873732 0.0034491462 0.0192220000 222583918 95654136 760807424 -0.0274517108 -0.0033748229 0.0187198780 115 1311867722.4467909336 0.0135111911 0.0119113596 0.0174873732 0.0035019783 0.0196770000 222757458 95654136 760807424 -0.0283950530 -0.0037250917 0.0175064970 116 1311867722.4777851105 0.0122693004 0.0119144453 0.0174873732 0.0035724788 0.0192510000 222760874 95654136 760807424 -0.0287498850 -0.0025874714 0.0162890013 117 1311867722.5147399902 0.0132088363 0.0119255085 0.0174873732 0.0035593029 0.0196120000 222762802 95654136 760807424 -0.0274329260 -0.0014667537 0.0180310626 118 1311867722.5469911098 0.0127350055 0.0119323686 0.0174873732 0.0035469039 0.0191830000 222766274 95654136 760807424 -0.0279610958 -0.0008357930 0.0185208861 119 1311867722.5802359581 0.0135817695 0.0119462292 0.0174873732 0.0035409891 0.0230910000 222769746 95654136 760807424 -0.0277608130 -0.0019712236 0.0188000388 120 1311867722.6146309376 0.0135096991 0.0119592581 0.0174873732 0.0035270110 0.0270870000 222771474 95654136 760807424 -0.0285648275 -0.0031050334 0.0183783360 121 1311867722.6560258865 0.0132019129 0.0119695279 0.0174873732 0.0035165442 0.0201220000 222775426 95654136 760807424 -0.0283890553 -0.0025819102 0.0179444794 122 1311867722.6778230667 0.0127489064 0.0119759163 0.0174873732 0.0035060565 0.0192900000 222778674 95654136 760807424 -0.0288479254 -0.0021074368 0.0182820112 123 1311867722.7252709866 0.0144159030 0.0119957536 0.0174873732 0.0036196729 0.0192300000 222780738 95654136 760807424 -0.0282745492 -0.0042415764 0.0180509575 124 1311867722.7449109554 0.0135958977 0.0120086580 0.0174873732 0.0036344258 0.0192280000 222783818 95654136 760807424 -0.0289335120 -0.0040943846 0.0173075199 125 1311867722.7770080566 0.0129614817 0.0120162806 0.0174873732 0.0036744848 0.0193820000 222785746 95654136 760807424 -0.0282686017 -0.0020629033 0.0158034638 126 1311867722.8162860870 0.0127834510 0.0120223692 0.0174873732 0.0036693875 0.0192520000 222789330 95654136 760807424 -0.0291680694 -0.0026633097 0.0156105040 127 1311867722.8466939926 0.0144324712 0.0120413464 0.0174873732 0.0036699310 0.0191900000 222792746 95654136 760807424 -0.0302019697 -0.0052695405 0.0183631591 128 1311867722.8819770813 0.0144212991 0.0120599398 0.0174873732 0.0036606856 0.0187950000 222794530 95654136 760807424 -0.0300689731 -0.0047332989 0.0182562005 129 1311867722.9150629044 0.0149332844 0.0120822138 0.0174873732 0.0036570201 0.0192280000 222821586 95654136 760807424 -0.0288333446 -0.0029428904 0.0178890377 130 1311867722.9485991001 0.0161220711 0.0121132896 0.0174873732 0.0036579865 0.0280160000 222850770 95654136 760807424 -0.0294653960 -0.0049276920 0.0199834965 131 1311867722.9821140766 0.0131436465 0.0121211549 0.0174873732 0.0036490572 0.0198720000 222852442 95654136 760807424 -0.0310697611 -0.0023057347 0.0179732796 132 1311867723.0147259235 0.0131645696 0.0121290596 0.0174873732 0.0036382435 0.0196510000 223025946 95654136 760807424 -0.0306981467 -0.0009713691 0.0180709567 133 1311867723.0460629463 0.0151406089 0.0121517028 0.0174873732 0.0036419937 0.0226020000 223029578 95654136 760807424 -0.0309813786 -0.0035413997 0.0201792102 134 1311867723.0845439434 0.0140689360 0.0121660105 0.0174873732 0.0036300710 0.0193720000 223031418 95654136 760807424 -0.0321324766 -0.0031931656 0.0192169212 135 1311867723.1140980721 0.0137222894 0.0121775385 0.0174873732 0.0036186893 0.0192570000 223034834 95654136 760807424 -0.0329900794 -0.0035259062 0.0180638395 136 1311867723.1505160332 0.0136008011 0.0121880037 0.0174873732 0.0036092161 0.0192370000 223038418 95654136 760807424 -0.0338062793 -0.0032114633 0.0194428042 137 1311867723.1811029911 0.0128899124 0.0121931271 0.0174873732 0.0036011196 0.0192430000 223040234 95654136 760807424 -0.0357524529 -0.0043018283 0.0185377989 138 1311867723.2201359272 0.0118087847 0.0121903420 0.0174873732 0.0035905137 0.0230480000 223043874 95654136 760807424 -0.0367019214 -0.0037445677 0.0174402799 139 1311867723.2486810684 0.0127952145 0.0121946936 0.0174873732 0.0035844797 0.0220080000 223045434 95654136 760807424 -0.0373212472 -0.0052960240 0.0182446595 140 1311867723.2846419811 0.0109831691 0.0121860399 0.0174873732 0.0035786954 0.0193310000 223049018 95654136 760807424 -0.0412322134 -0.0061921086 0.0163046680 141 1311867723.3132460117 0.0115784993 0.0121817311 0.0174873732 0.0035785055 0.0192410000 223052578 95654136 760807424 -0.0399852730 -0.0062819808 0.0151714012 142 1311867723.3499810696 0.0113240248 0.0121756909 0.0174873732 0.0035664237 0.0199050000 223054418 95654136 760807424 -0.0433006994 -0.0072398530 0.0130540095 143 1311867723.3822429180 0.0108495355 0.0121664171 0.0174873732 0.0035588963 0.0192520000 223057946 95654136 760807424 -0.0432871655 -0.0068239970 0.0135146687 144 1311867723.4193739891 0.0104767745 0.0121546834 0.0174873732 0.0035954710 0.0193030000 223231410 95654136 760807424 -0.0426304787 -0.0060470393 0.0128394170 145 1311867723.4455900192 0.0113380244 0.0121490513 0.0174873732 0.0035845632 0.0191470000 223233114 95654136 760807424 -0.0441523530 -0.0067261541 0.0109173711 146 1311867723.4825348854 0.0111169014 0.0121419818 0.0174873732 0.0035896844 0.0191940000 223236754 95654136 760807424 -0.0461951271 -0.0065320600 0.0106918123 147 1311867723.5147960186 0.0104063395 0.0121301747 0.0174873732 0.0035825567 0.0230920000 223240170 95654136 760807424 -0.0470929928 -0.0055692885 0.0106339967 148 1311867723.5451340675 0.0088111144 0.0121077486 0.0174873732 0.0035760214 0.0193150000 223241842 95654136 760807424 -0.0464324281 -0.0034992031 0.0114772646 149 1311867723.5809938908 0.0099827182 0.0120934867 0.0174873732 0.0035666409 0.0191870000 223245626 95654136 760807424 -0.0468777753 -0.0050917412 0.0124207325 150 1311867723.6132669449 0.0092390217 0.0120744569 0.0174873732 0.0035571730 0.0225880000 223247354 95654136 760807424 -0.0469754227 -0.0037102732 0.0118639357 151 1311867723.6453940868 0.0091208862 0.0120548968 0.0174873732 0.0035453970 0.0192450000 223250770 95654136 760807424 -0.0470302366 -0.0031583705 0.0114478935 152 1311867723.6809489727 0.0087623289 0.0120332352 0.0174873732 0.0035358333 0.0224820000 223254354 95654136 760807424 -0.0489511564 -0.0038748845 0.0127101354 153 1311867723.7130429745 0.0099146990 0.0120193885 0.0174873732 0.0035374384 0.0226320000 223256226 95654136 760807424 -0.0501608104 -0.0049002902 0.0118892137 154 1311867723.7471990585 0.0091946069 0.0120010458 0.0174873732 0.0035296818 0.0192880000 223259754 95654136 760807424 -0.0503103472 -0.0040984475 0.0119039342 155 1311867723.7809250355 0.0093443980 0.0119839061 0.0174873732 0.0035229335 0.0191690000 223263282 95654136 760807424 -0.0514498390 -0.0041018617 0.0112946033 156 1311867723.8157649040 0.0093129221 0.0119667845 0.0174873732 0.0035144266 0.0192310000 223435030 95654136 760807424 -0.0514178276 -0.0041516777 0.0110995006 157 1311867723.8468959332 0.0072354353 0.0119366485 0.0174873732 0.0035139504 0.0192220000 223438702 95654136 760807424 -0.0518844724 -0.0020831774 0.0114351017 158 1311867723.8826351166 0.0096745798 0.0119223316 0.0174873732 0.0035161679 0.0218250000 223442230 95654136 760807424 -0.0525918268 -0.0052411342 0.0120559223 159 1311867723.9172909260 0.0093538379 0.0119061775 0.0174873732 0.0035113948 0.0192260000 223443862 95654136 760807424 -0.0529929958 -0.0039414191 0.0100050420 160 1311867723.9490020275 0.0082967617 0.0118836187 0.0174873732 0.0035020753 0.0191220000 223447278 95654136 760807424 -0.0535496846 -0.0023382762 0.0098880762 161 1311867723.9839010239 0.0081689376 0.0118605461 0.0174873732 0.0034942225 0.0191120000 223449262 95654136 760807424 -0.0547397099 -0.0025696801 0.0104242684 162 1311867724.0132899284 0.0066570891 0.0118284260 0.0174873732 0.0034848910 0.0191830000 223622578 95654136 760807424 -0.0537050143 -0.0005755015 0.0101363603 163 1311867724.0475380421 0.0066641392 0.0117967433 0.0174873732 0.0034800597 0.0191130000 223626162 95654136 760807424 -0.0543395430 -0.0006723038 0.0105442749 164 1311867724.0824530125 0.0079047205 0.0117730114 0.0174873732 0.0034866161 0.0186390000 223627890 95654136 760807424 -0.0539395362 -0.0025242318 0.0108517250 165 1311867724.1132431030 0.0077421586 0.0117485820 0.0174873732 0.0034764398 0.0190100000 223631562 95654136 760807424 -0.0538289323 -0.0017860241 0.0099884365 166 1311867724.1547191143 0.0084364396 0.0117286294 0.0174873732 0.0034715377 0.0190870000 223635314 95654136 760807424 -0.0546902865 -0.0022544411 0.0096280556 167 1311867724.1810541153 0.0088797249 0.0117115701 0.0174873732 0.0034699913 0.0190430000 223636818 95654136 760807424 -0.0538880453 -0.0034394092 0.0110011669 168 1311867724.2139430046 0.0084085697 0.0116919093 0.0174873732 0.0034632380 0.0190500000 223640346 95654136 760807424 -0.0544375777 -0.0024849349 0.0102123264 169 1311867724.2507870197 0.0074592098 0.0116668638 0.0174873732 0.0034659698 0.0191030000 223644130 95654136 760807424 -0.0551626980 -0.0008318861 0.0100746108 170 1311867724.2855930328 0.0070994496 0.0116399966 0.0174873732 0.0034612416 0.0190590000 223645858 95654136 760807424 -0.0557451360 -0.0015104017 0.0119357798 171 1311867724.3144888878 0.0076648095 0.0116167499 0.0174873732 0.0034519998 0.0190250000 223649218 95654136 760807424 -0.0558330603 -0.0017369206 0.0109451720 172 1311867724.3517999649 0.0080982624 0.0115962936 0.0174873732 0.0034430202 0.0310810000 223652914 95654136 760807424 -0.0559303723 -0.0018194636 0.0100666238 173 1311867724.3888330460 0.0075820405 0.0115730898 0.0174873732 0.0034369077 0.0204830000 223654874 95654136 760807424 -0.0551884137 -0.0012694554 0.0101000546 174 1311867724.4160330296 0.0095538683 0.0115614851 0.0174873732 0.0034413502 0.0191010000 223658234 95654136 760807424 -0.0544531643 -0.0045324056 0.0121713020 175 1311867724.4509639740 0.0090684174 0.0115472390 0.0174873732 0.0034315562 0.0190860000 223659962 95654136 760807424 -0.0549269915 -0.0042793029 0.0110293292 176 1311867724.4830689430 0.0083486708 0.0115290653 0.0174873732 0.0034226374 0.0190650000 223663434 95654136 760807424 -0.0547879152 -0.0037486758 0.0108420551 177 1311867724.5208630562 0.0083535891 0.0115111248 0.0174873732 0.0034158734 0.0221990000 223667162 95654136 760807424 -0.0545565225 -0.0039417469 0.0105304196 178 1311867724.5523910522 0.0087005999 0.0114953353 0.0174873732 0.0034070157 0.0192300000 223840274 95654136 760807424 -0.0529267751 -0.0042458610 0.0138833541 179 1311867724.5861799717 0.0096893134 0.0114852458 0.0174873732 0.0034255330 0.0190340000 223843746 95654136 760807424 -0.0531900339 -0.0058995439 0.0135212336 180 1311867724.6193559170 0.0075880759 0.0114635949 0.0174873732 0.0034538425 0.0190680000 223847218 95654136 760807424 -0.0543679334 -0.0039685089 0.0109108491 181 1311867724.6529819965 0.0084889494 0.0114471604 0.0174873732 0.0034454445 0.0190490000 223849146 95654136 760807424 -0.0545529090 -0.0044628726 0.0092377868 182 1311867724.6818330288 0.0116417026 0.0114482293 0.0174873732 0.0034457142 0.0190170000 223852506 95654136 760807424 -0.0547055788 -0.0084603447 0.0123567767 183 1311867724.7153129578 0.0089064948 0.0114343400 0.0174873732 0.0034532910 0.0220510000 223856034 95654136 760807424 -0.0563479029 -0.0054943911 0.0094490070 184 1311867724.7518899441 0.0086291227 0.0114190943 0.0174873732 0.0034493895 0.0230030000 223857818 95654136 760807424 -0.0566561967 -0.0042427438 0.0082971239 185 1311867724.7853860855 0.0097875781 0.0114102753 0.0174873732 0.0034465978 0.0191980000 223861546 95654136 760807424 -0.0567479692 -0.0059188418 0.0101904934 186 1311867724.8179960251 0.0102111110 0.0114038281 0.0174873732 0.0034447750 0.0225800000 223863218 95654136 760807424 -0.0569506064 -0.0065885382 0.0111121656 187 1311867724.8547580242 0.0086307162 0.0113889987 0.0174873732 0.0034690033 0.0199000000 223866746 95654136 760807424 -0.0575786382 -0.0045620869 0.0099989753 188 1311867724.8830249310 0.0093209166 0.0113779982 0.0174873732 0.0034630899 0.0190390000 223870106 95654136 760807424 -0.0583119653 -0.0054800604 0.0098072700 189 1311867724.9137279987 0.0096776020 0.0113690014 0.0174873732 0.0034819614 0.0189890000 223871978 95654136 760807424 -0.0585133322 -0.0059528090 0.0094853528 190 1311867724.9535229206 0.0091700610 0.0113574280 0.0174873732 0.0034762691 0.0189730000 223875618 95654136 760807424 -0.0575849749 -0.0052277874 0.0115895122 191 1311867724.9843940735 0.0100160120 0.0113504049 0.0174873732 0.0034722099 0.0195100000 223879106 95654136 760807424 -0.0570793450 -0.0059623243 0.0111975707 192 1311867725.0159099102 0.0104425279 0.0113456764 0.0174873732 0.0034905361 0.0190300000 223880722 95654136 760807424 -0.0576848052 -0.0068794596 0.0106379269 193 1311867725.0518310070 0.0101463227 0.0113394621 0.0174873732 0.0034839455 0.0189900000 223884506 95654136 760807424 -0.0590594932 -0.0071788123 0.0103199724 194 1311867725.0813930035 0.0108673116 0.0113370284 0.0174873732 0.0034770888 0.0220440000 223887922 95654136 760807424 -0.0588196032 -0.0077563273 0.0097522084 195 1311867725.1151220798 0.0125313047 0.0113431529 0.0174873732 0.0034733648 0.0190230000 223889650 95654136 760807424 -0.0586326495 -0.0096703265 0.0112403110 196 1311867725.1557130814 0.0121465661 0.0113472519 0.0174873732 0.0034669361 0.0189310000 223893346 95654136 760807424 -0.0595797710 -0.0095060850 0.0088213338 197 1311867725.1843969822 0.0102553917 0.0113417095 0.0174873732 0.0034602050 0.0188940000 223895106 95654136 760807424 -0.0606019720 -0.0077324267 0.0079761567 198 1311867725.2150099277 0.0122206034 0.0113461483 0.0174873732 0.0034603888 0.0189570000 223898578 95654136 760807424 -0.0601222739 -0.0100354506 0.0091303494 199 1311867725.2516539097 0.0115293311 0.0113470688 0.0174873732 0.0034538830 0.0189160000 223902218 95654136 760807424 -0.0608850904 -0.0093236333 0.0076402593 200 1311867725.2816410065 0.0119686676 0.0113501768 0.0174873732 0.0034474472 0.0189620000 223903834 95654136 760807424 -0.0610237643 -0.0100236982 0.0083264820 201 1311867725.3196239471 0.0126458611 0.0113566230 0.0174873732 0.0034392991 0.0189640000 223907618 95654136 760807424 -0.0608697459 -0.0107271438 0.0093300091 202 1311867725.3517010212 0.0121003836 0.0113603050 0.0174873732 0.0034336643 0.0225460000 223911034 95654136 760807424 -0.0615661554 -0.0101613570 0.0080241291 203 1311867725.3837459087 0.0105696544 0.0113564102 0.0174873732 0.0034647145 0.0197510000 223912594 95654136 760807424 -0.0623532981 -0.0085412944 0.0081478320 204 1311867725.4178969860 0.0132435551 0.0113656609 0.0174873732 0.0034603021 0.0190200000 223916178 95654136 760807424 -0.0625108853 -0.0111745130 0.0081432043 205 1311867725.4492449760 0.0115302820 0.0113664639 0.0174873732 0.0034591772 0.0228880000 223919794 95654136 760807424 -0.0639726818 -0.0086426688 0.0059609921 206 1311867725.4836509228 0.0119753964 0.0113694199 0.0174873732 0.0034622386 0.0194080000 223921522 95654136 760807424 -0.0645821393 -0.0090470137 0.0062540704 207 1311867725.5178139210 0.0127454223 0.0113760673 0.0174873732 0.0034680308 0.0189210000 223925162 95654136 760807424 -0.0658917055 -0.0101372469 0.0075387442 208 1311867725.5497610569 0.0134400567 0.0113859903 0.0174873732 0.0034641263 0.0189750000 224098830 95654136 760807424 -0.0661745965 -0.0105586341 0.0069458927 209 1311867725.5815479755 0.0127346972 0.0113924434 0.0174873732 0.0034668778 0.0189060000 224100702 95654136 760807424 -0.0674032718 -0.0090326052 0.0053509008 210 1311867725.6194949150 0.0126362881 0.0113983665 0.0174873732 0.0034629994 0.0189220000 224104358 95654136 760807424 -0.0680757165 -0.0099774115 0.0079618590 211 1311867725.6515610218 0.0141531099 0.0114114222 0.0174873732 0.0035151213 0.0225450000 224106030 95654136 760807424 -0.0686936602 -0.0115062315 0.0076261964 212 1311867725.6834650040 0.0129154399 0.0114185166 0.0174873732 0.0035072344 0.0190410000 224109502 95654136 760807424 -0.0694995373 -0.0097235786 0.0059981975 213 1311867725.7201809883 0.0133605795 0.0114276342 0.0174873732 0.0035049306 0.0188520000 224113286 95654136 760807424 -0.0693370327 -0.0106240250 0.0079377461 214 1311867725.7515070438 0.0132130953 0.0114359775 0.0174873732 0.0034986251 0.0188660000 224114958 95654136 760807424 -0.0692108274 -0.0105619300 0.0077398913 215 1311867725.7835409641 0.0092154890 0.0114256497 0.0174873732 0.0035038149 0.0188770000 224118374 95654136 760807424 -0.0706891194 -0.0060496558 0.0067671714 216 1311867725.8211829662 0.0122290328 0.0114293690 0.0174873732 0.0035063333 0.0270790000 224122070 95654136 760807424 -0.0708921403 -0.0091993706 0.0060725752 217 1311867725.8517971039 0.0127775511 0.0114355819 0.0174873732 0.0035052918 0.0195820000 224123942 95654136 760807424 -0.0707739592 -0.0093715554 0.0055605620 218 1311867725.8837900162 0.0115501201 0.0114361073 0.0174873732 0.0035050118 0.0188790000 224127302 95654136 760807424 -0.0706441551 -0.0073031895 0.0048215473 219 1311867725.9192690849 0.0123646818 0.0114403473 0.0174873732 0.0035038523 0.0190950000 224130886 95654136 760807424 -0.0715848207 -0.0085300570 0.0055337716 220 1311867725.9511859417 0.0144243483 0.0114539110 0.0174873732 0.0034984751 0.0188630000 224132574 95654136 760807424 -0.0729642138 -0.0109170526 0.0054808296 221 1311867725.9829630852 0.0122998627 0.0114577388 0.0174873732 0.0034938778 0.0188460000 224136190 95654136 760807424 -0.0731556118 -0.0079205921 0.0042929044 222 1311867726.0219368935 0.0136274826 0.0114675124 0.0174873732 0.0034955711 0.0219690000 224138086 95654136 760807424 -0.0729222596 -0.0095235491 0.0053206170 223 1311867726.0504179001 0.0140722441 0.0114791928 0.0174873732 0.0034890451 0.0189240000 224141390 95654136 760807424 -0.0727536306 -0.0103103360 0.0071849143 224 1311867726.0845088959 0.0132607482 0.0114871462 0.0174873732 0.0034812746 0.0188160000 224144974 95654136 760807424 -0.0730326176 -0.0090962052 0.0048990021 225 1311867726.1199669838 0.0162359904 0.0115082522 0.0174873732 0.0034812518 0.0188540000 224146902 95654136 760807424 -0.0732563287 -0.0125890728 0.0057348339 226 1311867726.1506989002 0.0145414481 0.0115216734 0.0174873732 0.0034805904 0.0278110000 224150374 95654136 760807424 -0.0750081614 -0.0109946784 0.0041682012 227 1311867726.1824700832 0.0151709570 0.0115377495 0.0174873732 0.0034735960 0.0218940000 224153846 95654136 760807424 -0.0754101351 -0.0113869756 0.0027973005 228 1311867726.2198660374 0.0161526687 0.0115579904 0.0174873732 0.0034740923 0.0189220000 224155630 95654136 760807424 -0.0763843879 -0.0128589943 0.0031145723 229 1311867726.2506690025 0.0184645988 0.0115881503 0.0184645988 0.0034712718 0.0188740000 224159302 95654136 760807424 -0.0769470185 -0.0154774170 0.0027949933 230 1311867726.2845950127 0.0156409498 0.0116057711 0.0184645988 0.0034726018 0.0188070000 224162774 95654136 760807424 -0.0773554668 -0.0126562826 0.0025451824 231 1311867726.3187239170 0.0145725906 0.0116186145 0.0184645988 0.0034652610 0.0189150000 224164558 95654136 760807424 -0.0766509771 -0.0109950425 0.0017985605 232 1311867726.3524029255 0.0151068773 0.0116336501 0.0184645988 0.0034580020 0.0188880000 224168086 95654136 760807424 -0.0773100257 -0.0119121773 0.0030047568 233 1311867726.3835608959 0.0146409366 0.0116465569 0.0184645988 0.0034511513 0.0224260000 224169902 95654136 760807424 -0.0784339011 -0.0112540927 0.0025283480 234 1311867726.4218099117 0.0145555045 0.0116589883 0.0184645988 0.0034445371 0.0198610000 224173598 95654136 760807424 -0.0776755735 -0.0106180264 0.0027458430 235 1311867726.4504199028 0.0141662648 0.0116696576 0.0184645988 0.0034373209 0.0188820000 224176958 95654136 760807424 -0.0784144178 -0.0098918825 0.0022291909 236 1311867726.4843189716 0.0144667858 0.0116815098 0.0184645988 0.0034312297 0.0298450000 224349250 95654136 760807424 -0.0789852664 -0.0097312136 0.0011540317 237 1311867726.5207901001 0.0139987860 0.0116912874 0.0184645988 0.0034369456 0.0201640000 224353034 95654136 760807424 -0.0789268538 -0.0092158075 0.0024698642 238 1311867726.5524380207 0.0161113795 0.0117098592 0.0184645988 0.0034407525 0.0192020000 224356506 95654136 760807424 -0.0795364156 -0.0120948153 0.0037053730 239 1311867726.5874860287 0.0142292026 0.0117204004 0.0184645988 0.0034377356 0.0221510000 224358290 95654136 760807424 -0.0799473152 -0.0099825151 0.0031069643 240 1311867726.6204600334 0.0135014029 0.0117278212 0.0184645988 0.0034592836 0.0190710000 224361762 95654136 760807424 -0.0795705393 -0.0090932986 0.0037088995 241 1311867726.6509370804 0.0146964509 0.0117401392 0.0184645988 0.0034686559 0.0189500000 224365378 95654136 760807424 -0.0793241411 -0.0108093154 0.0043955604 242 1311867726.6916151047 0.0146147329 0.0117520177 0.0184645988 0.0034617878 0.0189610000 224367330 95654136 760807424 -0.0795806721 -0.0108808586 0.0035310844 243 1311867726.7201170921 0.0141728353 0.0117619799 0.0184645988 0.0034559478 0.0189230000 224370618 95654136 760807424 -0.0781033114 -0.0103229769 0.0044679223 244 1311867726.7513859272 0.0151482662 0.0117758581 0.0184645988 0.0034492735 0.0190010000 224374090 95654136 760807424 -0.0776974484 -0.0116431303 0.0052510896 245 1311867726.7880010605 0.0136522595 0.0117835169 0.0184645988 0.0034426178 0.0191250000 224376130 95654136 760807424 -0.0776440725 -0.0103365164 0.0041790688 246 1311867726.8198299408 0.0142305540 0.0117934642 0.0184645988 0.0034374600 0.0191320000 224379546 95654136 760807424 -0.0780771449 -0.0111356797 0.0032703872 247 1311867726.8500390053 0.0147981420 0.0118056289 0.0184645988 0.0034309166 0.0226550000 224381162 95654136 760807424 -0.0777561963 -0.0117639620 0.0038011828 248 1311867726.8927390575 0.0145054832 0.0118165154 0.0184645988 0.0034275066 0.0200300000 224384970 95654136 760807424 -0.0780850425 -0.0116054360 0.0034960862 249 1311867726.9216780663 0.0127554787 0.0118202863 0.0184645988 0.0034219536 0.0223230000 224388530 95654136 760807424 -0.0777296051 -0.0096850973 0.0039249514 250 1311867726.9543499947 0.0137135610 0.0118278594 0.0184645988 0.0034345270 0.0191520000 224390202 95654136 760807424 -0.0774683282 -0.0107884398 0.0037997160 251 1311867726.9902989864 0.0137968436 0.0118357040 0.0184645988 0.0034326500 0.0190960000 224393730 95654136 760807424 -0.0776209757 -0.0110722939 0.0045836116 252 1311867727.0208179951 0.0136999404 0.0118431018 0.0184645988 0.0034300422 0.0191740000 224397202 95654136 760807424 -0.0773628801 -0.0108870463 0.0034373077 253 1311867727.0536949635 0.0130383642 0.0118478261 0.0184645988 0.0034235977 0.0191370000 224399090 95654136 760807424 -0.0758852363 -0.0102092251 0.0046895724 254 1311867727.0911629200 0.0133399041 0.0118537004 0.0184645988 0.0034175946 0.0286340000 224402730 95654136 760807424 -0.0748039111 -0.0103553571 0.0060410616 255 1311867727.1196689606 0.0132396705 0.0118591356 0.0184645988 0.0034132842 0.0199480000 224405978 95654136 760807424 -0.0748847127 -0.0105768871 0.0057453336 256 1311867727.1514298916 0.0124974586 0.0118616291 0.0184645988 0.0034069754 0.0191870000 224407706 95654136 760807424 -0.0735574365 -0.0094568934 0.0053986469 257 1311867727.1904149055 0.0135032600 0.0118680167 0.0184645988 0.0034298169 0.0192330000 224458594 95654136 760807424 -0.0726195872 -0.0103517063 0.0067740823 258 1311867727.2208960056 0.0123962704 0.0118700642 0.0184645988 0.0034255319 0.0192550000 224511466 95654136 760807424 -0.0733190924 -0.0096876770 0.0045956103 259 1311867727.2544560432 0.0134118926 0.0118760172 0.0184645988 0.0034202666 0.0192900000 224514938 95654136 760807424 -0.0738589764 -0.0110422065 0.0055418797 260 1311867727.2870850563 0.0134602822 0.0118821106 0.0184645988 0.0034148897 0.0192540000 224518466 95654136 760807424 -0.0727818757 -0.0108861644 0.0057995860 261 1311867727.3192501068 0.0141577274 0.0118908294 0.0184645988 0.0034096567 0.0192170000 224520338 95654136 760807424 -0.0712546259 -0.0113729779 0.0060720197 262 1311867727.3502039909 0.0140068559 0.0118989058 0.0184645988 0.0034081070 0.0192680000 224523754 95654136 760807424 -0.0715202689 -0.0116638988 0.0064691389 263 1311867727.3894629478 0.0123066949 0.0119004564 0.0184645988 0.0034029726 0.0272130000 224527338 95654136 760807424 -0.0715988129 -0.0100992005 0.0044213473 264 1311867727.4182970524 0.0131405359 0.0119051536 0.0184645988 0.0033975018 0.0198110000 224528954 95654136 760807424 -0.0701757520 -0.0108676897 0.0056553530 265 1311867727.4495580196 0.0138879772 0.0119126360 0.0184645988 0.0033916441 0.0193010000 224532514 95654136 760807424 -0.0697955266 -0.0117321927 0.0061482117 266 1311867727.4858360291 0.0107389204 0.0119082235 0.0184645988 0.0033970661 0.0193210000 224536154 95654136 760807424 -0.0696193799 -0.0083649307 0.0039637554 267 1311867727.5198891163 0.0110851694 0.0119051409 0.0184645988 0.0033941677 0.0193400000 224537826 95654136 760807424 -0.0685221106 -0.0085081076 0.0056071249 268 1311867727.5494980812 0.0128639108 0.0119087184 0.0184645988 0.0033970124 0.0194060000 224541242 95654136 760807424 -0.0669323057 -0.0098624313 0.0074837944 269 1311867727.5905909538 0.0114774071 0.0119071150 0.0184645988 0.0033970892 0.0193720000 224543394 95654136 760807424 -0.0670883730 -0.0094775520 0.0061321286 270 1311867727.6176431179 0.0109230988 0.0119034705 0.0184645988 0.0034015331 0.0193810000 224546698 95654136 760807424 -0.0661871582 -0.0088868737 0.0057016565 271 1311867727.6497650146 0.0118783833 0.0119033780 0.0184645988 0.0034056578 0.0193300000 224550170 95654136 760807424 -0.0649693608 -0.0101066213 0.0050056493 272 1311867727.6884338856 0.0106460955 0.0118987556 0.0184645988 0.0034043108 0.0196090000 224551842 95654136 760807424 -0.0657269135 -0.0097003402 0.0041185766 273 1311867727.7184689045 0.0110956114 0.0118958137 0.0184645988 0.0034040250 0.0286090000 224555514 95654136 760807424 -0.0651055798 -0.0102694910 0.0033120913 274 1311867727.7523269653 0.0115679922 0.0118946172 0.0184645988 0.0033998531 0.0201610000 224559042 95654136 760807424 -0.0661692694 -0.0115170628 0.0025711006 275 1311867727.7856590748 0.0094237663 0.0118856323 0.0184645988 0.0033959696 0.0221590000 224560714 95654136 760807424 -0.0665072724 -0.0095420983 0.0001979414 276 1311867727.8181309700 0.0090202680 0.0118752506 0.0184645988 0.0033981402 0.0229970000 224564242 95654136 760807424 -0.0670319796 -0.0090114754 0.0000155381 277 1311867727.8548729420 0.0093335975 0.0118660749 0.0184645988 0.0033926475 0.0205020000 224568026 95654136 760807424 -0.0675716996 -0.0093575409 0.0001778218 278 1311867727.8882629871 0.0092278477 0.0118565849 0.0184645988 0.0033884749 0.0195410000 224569738 95654136 760807424 -0.0663209260 -0.0087370668 -0.0010827767 279 1311867727.9193139076 0.0099273603 0.0118496701 0.0184645988 0.0033838974 0.0195130000 224573154 95654136 760807424 -0.0660718754 -0.0093750022 0.0005002161 280 1311867727.9556980133 0.0105308816 0.0118449602 0.0184645988 0.0033787150 0.0194510000 224576738 95654136 760807424 -0.0661133453 -0.0099327294 0.0002750323 281 1311867727.9869389534 0.0093710665 0.0118361563 0.0184645988 0.0033744894 0.0194880000 224578666 95654136 760807424 -0.0657549053 -0.0086671337 0.0002681457 282 1311867728.0179219246 0.0099225789 0.0118293705 0.0184645988 0.0033734870 0.0192210000 224582026 95654136 760807424 -0.0650358722 -0.0090808691 0.0013940980 283 1311867728.0555219650 0.0076927780 0.0118147536 0.0184645988 0.0033684089 0.0192560000 224583866 95654136 760807424 -0.0633478984 -0.0061185267 0.0010685730 284 1311867728.0892169476 0.0089598745 0.0118047012 0.0184645988 0.0033643631 0.0192290000 224587394 95654136 760807424 -0.0618853047 -0.0071030804 -0.0001458367 285 1311867728.1177880764 0.0084334817 0.0117928724 0.0184645988 0.0033747655 0.0196690000 224591010 95654136 760807424 -0.0620931275 -0.0065809307 0.0006266593 286 1311867728.1556169987 0.0097219311 0.0117856313 0.0184645988 0.0033700258 0.0195860000 224592794 95654136 760807424 -0.0605407022 -0.0074259583 0.0000470799 287 1311867728.1882989407 0.0087869801 0.0117751831 0.0184645988 0.0033658073 0.0228610000 224596378 95654136 760807424 -0.0609615706 -0.0067231008 -0.0006026314 288 1311867728.2182519436 0.0095941722 0.0117676101 0.0184645988 0.0033608237 0.0194460000 224599794 95654136 760807424 -0.0608350039 -0.0075849141 -0.0006765695 289 1311867728.2558999062 0.0092653260 0.0117589517 0.0184645988 0.0033554800 0.0194460000 224601778 95654136 760807424 -0.0612778887 -0.0074560591 -0.0015248032 290 1311867728.2875900269 0.0079728803 0.0117458963 0.0184645988 0.0033514669 0.0194940000 224605250 95654136 760807424 -0.0600235611 -0.0056534642 -0.0015705281 291 1311867728.3226509094 0.0070873122 0.0117298874 0.0184645988 0.0033570302 0.0230490000 224608834 95654136 760807424 -0.0610067025 -0.0051940326 -0.0030131522 292 1311867728.3597300053 0.0090915496 0.0117208520 0.0184645988 0.0033818764 0.0197330000 224610546 95654136 760807424 -0.0608346388 -0.0075061340 -0.0020337589 293 1311867728.3861401081 0.0082663335 0.0117090618 0.0184645988 0.0033783162 0.0199790000 224614106 95654136 760807424 -0.0611051656 -0.0066378722 -0.0037125954 294 1311867728.4175701141 0.0090462156 0.0117000045 0.0184645988 0.0034132631 0.0198330000 224615778 95654136 760807424 -0.0606158040 -0.0072165038 -0.0037504788 295 1311867728.4568250179 0.0075957580 0.0116860918 0.0184645988 0.0034080322 0.0224260000 224619418 95654136 760807424 -0.0606016219 -0.0056630480 -0.0050692046 296 1311867728.4875330925 0.0079566715 0.0116734924 0.0184645988 0.0034064250 0.0228510000 224622834 95654136 760807424 -0.0587720238 -0.0057847183 -0.0039025638 297 1311867728.5187420845 0.0093077663 0.0116655270 0.0184645988 0.0034043995 0.0196040000 224624650 95654136 760807424 -0.0592815392 -0.0074839345 -0.0043113604 298 1311867728.5550920963 0.0069499421 0.0116497029 0.0184645988 0.0034000487 0.0219500000 224628290 95654136 760807424 -0.0583206676 -0.0047462396 -0.0055311695 299 1311867728.5878560543 0.0075632976 0.0116360360 0.0184645988 0.0033963551 0.0208590000 224631818 95654136 760807424 -0.0586243384 -0.0057169683 -0.0052316478 300 1311867728.6187679768 0.0081217689 0.0116243218 0.0184645988 0.0033932028 0.0194720000 224633378 95654136 760807424 -0.0584019050 -0.0063142832 -0.0052140229 301 1311867728.6580820084 0.0080676908 0.0116125057 0.0184645988 0.0033887018 0.0234600000 224637274 95654136 760807424 -0.0587683246 -0.0062664631 -0.0066637904 302 1311867728.6893489361 0.0082740169 0.0116014511 0.0184645988 0.0033858933 0.0195470000 224640746 95654136 760807424 -0.0586285852 -0.0063881441 -0.0073615988 303 1311867728.7210168839 0.0082129901 0.0115902681 0.0184645988 0.0033875344 0.0193620000 224642418 95654136 760807424 -0.0565094352 -0.0059985812 -0.0064391447 304 1311867728.7584259510 0.0073332563 0.0115762648 0.0184645988 0.0033847021 0.0195120000 224646002 95654136 760807424 -0.0566220134 -0.0052550239 -0.0069370447 305 1311867728.7858450413 0.0107773012 0.0115736452 0.0184645988 0.0033848567 0.0195140000 224647818 95654136 760807424 -0.0563889444 -0.0089731310 -0.0068518845 306 1311867728.8203740120 0.0079958942 0.0115619532 0.0184645988 0.0033851343 0.0193500000 224651290 95654136 760807424 -0.0562745444 -0.0060715931 -0.0080160871 307 1311867728.8545160294 0.0086435918 0.0115524471 0.0184645988 0.0033813739 0.0225420000 224654818 95654136 760807424 -0.0558547303 -0.0067545180 -0.0074733216 308 1311867728.8860759735 0.0076291473 0.0115397092 0.0184645988 0.0033761986 0.0196570000 224656546 95654136 760807424 -0.0560786016 -0.0058207111 -0.0086146034 309 1311867728.9193949699 0.0082684839 0.0115291227 0.0184645988 0.0033717886 0.0199340000 224660162 95654136 760807424 -0.0550785549 -0.0064354204 -0.0082415370 310 1311867728.9585559368 0.0076635201 0.0115166530 0.0184645988 0.0033936126 0.0195940000 224663970 95654136 760807424 -0.0535307229 -0.0049970509 -0.0088917324 311 1311867728.9886839390 0.0088396976 0.0115080454 0.0184645988 0.0033920339 0.0262940000 224665474 95654136 760807424 -0.0531397350 -0.0064640264 -0.0075952071 312 1311867729.0231020451 0.0066321352 0.0114924175 0.0184645988 0.0033940122 0.0196820000 224669058 95654136 760807424 -0.0545003302 -0.0047960114 -0.0099719688 313 1311867729.0583839417 0.0074849636 0.0114796141 0.0184645988 0.0033898371 0.0227060000 224672842 95654136 760807424 -0.0542772822 -0.0057470826 -0.0097334515 314 1311867729.0882170200 0.0077424864 0.0114677124 0.0184645988 0.0033886786 0.0198000000 224674458 95654136 760807424 -0.0544550493 -0.0057812985 -0.0096139042 315 1311867729.1263229847 0.0063356250 0.0114514201 0.0184645988 0.0034005880 0.0233930000 224678098 95654136 760807424 -0.0548059791 -0.0035060786 -0.0111356508 316 1311867729.1556320190 0.0065234476 0.0114358252 0.0184645988 0.0034014910 0.0198540000 224681458 95654136 760807424 -0.0554418936 -0.0035973121 -0.0107358918 317 1311867729.1888830662 0.0066621560 0.0114207664 0.0184645988 0.0034416021 0.0197170000 224683386 95654136 760807424 -0.0553216711 -0.0035986491 -0.0099002589 318 1311867729.2240469456 0.0067847958 0.0114061878 0.0184645988 0.0034510436 0.0197440000 224686914 95654136 760807424 -0.0547725335 -0.0036119216 -0.0079291789 319 1311867729.2579979897 0.0078621767 0.0113950781 0.0184645988 0.0034486072 0.0197550000 224688698 95654136 760807424 -0.0548703223 -0.0050715636 -0.0061675152 320 1311867729.2880148888 0.0078585325 0.0113840264 0.0184645988 0.0034448348 0.0197690000 224692114 95654136 760807424 -0.0553356335 -0.0056670806 -0.0060950834 321 1311867729.3236539364 0.0062800809 0.0113681262 0.0184645988 0.0034420457 0.0197590000 224695842 95654136 760807424 -0.0541825034 -0.0041116970 -0.0057106097 322 1311867729.3580930233 0.0064844708 0.0113529596 0.0184645988 0.0034568549 0.0197760000 224697626 95654136 760807424 -0.0543050803 -0.0052927919 -0.0048523974 323 1311867729.3882780075 0.0061779665 0.0113369379 0.0184645988 0.0034549213 0.0204530000 224700986 95654136 760807424 -0.0535885505 -0.0048340764 -0.0059043821 324 1311867729.4253289700 0.0052647786 0.0113181967 0.0184645988 0.0034519115 0.0198070000 224704642 95654136 760807424 -0.0520877019 -0.0037451386 -0.0067688688 325 1311867729.4572670460 0.0070661176 0.0113051134 0.0184645988 0.0034498473 0.0200720000 224706514 95654136 760807424 -0.0516356491 -0.0060517010 -0.0050549312 326 1311867729.4887750149 0.0068626483 0.0112914862 0.0184645988 0.0034594801 0.0198610000 224710042 95654136 760807424 -0.0519198179 -0.0064963321 -0.0054563410 327 1311867729.5223650932 0.0072237421 0.0112790466 0.0184645988 0.0034549727 0.0197600000 224713514 95654136 760807424 -0.0511963293 -0.0071573043 -0.0052531268 328 1311867729.5603790283 0.0069826446 0.0112659478 0.0184645988 0.0034519269 0.0210960000 224715698 95654136 760807424 -0.0501966104 -0.0073365909 -0.0060822545 329 1311867729.5890150070 0.0087504415 0.0112583019 0.0184645988 0.0034476627 0.0198110000 224719058 95654136 760807424 -0.0500859357 -0.0096242465 -0.0052852677 330 1311867729.6254830360 0.0060896915 0.0112426395 0.0184645988 0.0034451248 0.0312140000 224720842 95654136 760807424 -0.0493160263 -0.0072605312 -0.0061441441 331 1311867729.6614611149 0.0062742732 0.0112276293 0.0184645988 0.0034403484 0.0219530000 224724626 95654136 760807424 -0.0494558811 -0.0081596384 -0.0054873819 332 1311867729.6888220310 0.0074053220 0.0112161163 0.0184645988 0.0034373435 0.0211190000 224727874 95654136 760807424 -0.0501984954 -0.0092968838 -0.0069436003 333 1311867729.7230739594 0.0056357719 0.0111993585 0.0184645988 0.0034353144 0.0214130000 224729858 95654136 760807424 -0.0484779701 -0.0079630157 -0.0058503277 334 1311867729.7570610046 0.0078666080 0.0111893802 0.0184645988 0.0034337322 0.0198570000 224733218 95654136 760807424 -0.0481725559 -0.0108333826 -0.0047206315 335 1311867729.7899730206 0.0092014745 0.0111834462 0.0184645988 0.0034289106 0.0211600000 224736746 95654136 760807424 -0.0472286120 -0.0124619883 -0.0038036525 336 1311867729.8264250755 0.0090522496 0.0111771033 0.0184645988 0.0034286630 0.0211990000 224738674 95654136 760807424 -0.0468109585 -0.0124756638 -0.0048058233 337 1311867729.8550031185 0.0081532104 0.0111681304 0.0184645988 0.0034247320 0.0212540000 224742034 95654136 760807424 -0.0474652499 -0.0116043752 -0.0055320221 338 1311867729.8881840706 0.0094492072 0.0111630448 0.0184645988 0.0034210997 0.0258600000 224744018 95654136 760807424 -0.0465260409 -0.0131910937 -0.0044991188 339 1311867729.9233629704 0.0091062831 0.0111569776 0.0184645988 0.0034172876 0.0289900000 224747546 95654136 760807424 -0.0469819717 -0.0127506470 -0.0054415762 340 1311867729.9569330215 0.0078978706 0.0111473920 0.0184645988 0.0034137804 0.0216130000 224751274 95654136 760807424 -0.0460694842 -0.0111668557 -0.0059366450 341 1311867729.9865698814 0.0084073907 0.0111393568 0.0184645988 0.0034097378 0.0212410000 224752914 95654136 760807424 -0.0458834916 -0.0122965472 -0.0045204461 342 1311867730.0230469704 0.0117405625 0.0111411148 0.0184645988 0.0034133689 0.0212410000 224756698 95654136 760807424 -0.0462846681 -0.0159378257 -0.0043736170 343 1311867730.0557899475 0.0085539818 0.0111335721 0.0184645988 0.0034182188 0.0247050000 224758426 95654136 760807424 -0.0457908176 -0.0125425328 -0.0050511975 344 1311867730.0871100426 0.0096422853 0.0111292370 0.0184645988 0.0034133026 0.0212980000 224762098 95654136 760807424 -0.0464112163 -0.0135494657 -0.0047328635 345 1311867730.1231229305 0.0111319600 0.0111292448 0.0184645988 0.0034111414 0.0212530000 224765682 95654136 760807424 -0.0454414003 -0.0148685295 -0.0050400649 346 1311867730.1568520069 0.0097729182 0.0111253248 0.0184645988 0.0034074561 0.0211460000 224767610 95654136 760807424 -0.0451848432 -0.0132592460 -0.0050733555 347 1311867730.1882419586 0.0095123434 0.0111206765 0.0184645988 0.0034035618 0.0212780000 224941646 95654136 760807424 -0.0452014245 -0.0130668655 -0.0039872392 348 1311867730.2224810123 0.0085051013 0.0111131604 0.0184645988 0.0034001715 0.0256650000 224943630 95654136 760807424 -0.0447799601 -0.0118086729 -0.0043660267 349 1311867730.2575879097 0.0095218075 0.0111086007 0.0184645988 0.0033957901 0.0214140000 224947158 95654136 760807424 -0.0444131531 -0.0126962904 -0.0035450184 350 1311867730.2914879322 0.0085630203 0.0111013276 0.0184645988 0.0033922157 0.0212480000 224950886 95654136 760807424 -0.0445296168 -0.0113546159 -0.0039921482 351 1311867730.3230810165 0.0091643492 0.0110958092 0.0184645988 0.0033908457 0.0212290000 224952558 95654136 760807424 -0.0447869301 -0.0115855960 -0.0044159694 352 1311867730.3554260731 0.0099170413 0.0110924604 0.0184645988 0.0033901532 0.0212910000 224956230 95654136 760807424 -0.0436143689 -0.0123731541 -0.0031167041 353 1311867730.3982920647 0.0095255170 0.0110880214 0.0184645988 0.0033879977 0.0242260000 224959982 95654136 760807424 -0.0439765938 -0.0117326267 -0.0024404880 354 1311867730.4225230217 0.0078034401 0.0110787430 0.0184645988 0.0033943604 0.0212490000 224961686 95654136 760807424 -0.0439472012 -0.0092711207 -0.0037970734 355 1311867730.4600110054 0.0076082926 0.0110689671 0.0184645988 0.0033906550 0.0211440000 224965270 95654136 760807424 -0.0445804782 -0.0084730601 -0.0042404388 356 1311867730.4948410988 0.0095275473 0.0110646372 0.0184645988 0.0033927265 0.0211460000 224967198 95654136 760807424 -0.0444557369 -0.0104071982 -0.0028660772 357 1311867730.5300729275 0.0074932128 0.0110546332 0.0184645988 0.0033931088 0.0304540000 224970726 95654136 760807424 -0.0439128056 -0.0080982279 -0.0024218003 358 1311867730.5597670078 0.0094031235 0.0110500201 0.0184645988 0.0033891524 0.0217520000 224974342 95654136 760807424 -0.0446575135 -0.0098038446 -0.0023684984 359 1311867730.5940020084 0.0090875272 0.0110445535 0.0184645988 0.0033870865 0.0245600000 224976126 95654136 760807424 -0.0447356775 -0.0090918867 -0.0028720256 360 1311867730.6230149269 0.0088736713 0.0110385233 0.0184645988 0.0033857408 0.0212650000 224979630 95654136 760807424 -0.0439441837 -0.0090620890 -0.0011509709 361 1311867730.6614060402 0.0094393622 0.0110340935 0.0184645988 0.0033811304 0.0212250000 224981470 95654136 760807424 -0.0429169610 -0.0095513342 -0.0007694382 362 1311867730.6922950745 0.0087883770 0.0110278898 0.0184645988 0.0033765151 0.0212910000 225155698 95654136 760807424 -0.0427298434 -0.0088125207 -0.0010821446 363 1311867730.7275629044 0.0095229764 0.0110237441 0.0184645988 0.0033781995 0.0211890000 225159226 95654136 760807424 -0.0419846736 -0.0094355829 -0.0016442133 364 1311867730.7572948933 0.0081135621 0.0110157491 0.0184645988 0.0033790641 0.0212390000 225161042 95654136 760807424 -0.0410361439 -0.0077063902 -0.0017494335 365 1311867730.7932779789 0.0079644350 0.0110073893 0.0184645988 0.0033765357 0.0254990000 225164698 95654136 760807424 -0.0406869054 -0.0070088841 -0.0024796806 366 1311867730.8240480423 0.0117703658 0.0110094739 0.0184645988 0.0033764917 0.0315310000 225166458 95654136 760807424 -0.0432062894 -0.0098943552 -0.0039589317 367 1311867730.8591129780 0.0101719359 0.0110071918 0.0184645988 0.0033736585 0.0219960000 225170042 95654136 760807424 -0.0423597172 -0.0075356029 -0.0041630627 368 1311867730.8922739029 0.0081198635 0.0109993458 0.0184645988 0.0033728367 0.0249770000 225173602 95654136 760807424 -0.0394864492 -0.0057371110 -0.0019148572 369 1311867730.9270720482 0.0083056809 0.0109920459 0.0184645988 0.0033753331 0.0249030000 225175386 95654136 760807424 -0.0386747420 -0.0054204911 -0.0017405176 370 1311867730.9611239433 0.0067981277 0.0109807110 0.0184645988 0.0033750617 0.0213230000 225179058 95654136 760807424 -0.0376246832 -0.0033399705 -0.0016033695 371 1311867730.9928169250 0.0073636253 0.0109709614 0.0184645988 0.0033794357 0.0212040000 225182530 95654136 760807424 -0.0343469270 -0.0035197388 0.0000820843 372 1311867731.0221049786 0.0104734739 0.0109696241 0.0184645988 0.0033800842 0.0246630000 225184346 95654136 760807424 -0.0337337889 -0.0068828333 0.0006408312 373 1311867731.0609729290 0.0074036382 0.0109600638 0.0184645988 0.0033806997 0.0213650000 225187986 95654136 760807424 -0.0339145847 -0.0038146023 0.0007646329 374 1311867731.0900061131 0.0094134780 0.0109559286 0.0184645988 0.0033772803 0.0247490000 225189746 95654136 760807424 -0.0334133469 -0.0060771424 0.0020707911 375 1311867731.1276559830 0.0088935075 0.0109504288 0.0184645988 0.0033916061 0.0213670000 225193386 95654136 760807424 -0.0357920639 -0.0052911155 0.0000017064 376 1311867731.1551880836 0.0080710799 0.0109427709 0.0184645988 0.0033884078 0.0213490000 225196946 95654136 760807424 -0.0354837663 -0.0042441115 0.0002281930 377 1311867731.1935870647 0.0083942665 0.0109360110 0.0184645988 0.0033851584 0.0212530000 225198730 95654136 760807424 -0.0359011516 -0.0044950531 0.0012312359 378 1311867731.2235820293 0.0076793279 0.0109273954 0.0184645988 0.0033809297 0.0213550000 225202402 95654136 760807424 -0.0339522213 -0.0042388374 0.0024955061 379 1311867731.2602028847 0.0070715011 0.0109172216 0.0184645988 0.0033780769 0.0256650000 225204130 95654136 760807424 -0.0330038853 -0.0037348019 0.0040963115 380 1311867731.2900059223 0.0088758674 0.0109118496 0.0184645988 0.0034266942 0.0215060000 225207746 95654136 760807424 -0.0320387296 -0.0055932221 0.0045168912 381 1311867731.3230779171 0.0098909894 0.0109091701 0.0184645988 0.0034633940 0.0213180000 225211274 95654136 760807424 -0.0303782579 -0.0071835150 0.0043071751 382 1311867731.3570859432 0.0109307356 0.0109092266 0.0184645988 0.0034593613 0.0244950000 225213258 95654136 760807424 -0.0280142128 -0.0084748277 0.0051988098 383 1311867731.3915760517 0.0118996687 0.0109118126 0.0184645988 0.0034558133 0.0214650000 225216762 95654136 760807424 -0.0277215056 -0.0099594034 0.0051905606 384 1311867731.4279849529 0.0104149627 0.0109105187 0.0184645988 0.0034593904 0.0293920000 225218802 95654136 760807424 -0.0249232203 -0.0084821284 0.0044908198 385 1311867731.4602010250 0.0087857349 0.0109049998 0.0184645988 0.0034613213 0.0219200000 225392442 95654136 760807424 -0.0262347888 -0.0077399565 0.0030713920 386 1311867731.4926180840 0.0092711281 0.0109007670 0.0184645988 0.0034589071 0.0215040000 225396114 95654136 760807424 -0.0253014360 -0.0082637928 0.0036135307 387 1311867731.5259540081 0.0075462372 0.0108920990 0.0184645988 0.0034586619 0.0214160000 225397786 95654136 760807424 -0.0252576023 -0.0072044609 0.0025705500 388 1311867731.5589148998 0.0090433769 0.0108873342 0.0184645988 0.0034576377 0.0214330000 225401458 95654136 760807424 -0.0243800785 -0.0087929321 0.0020794175 389 1311867731.5967359543 0.0085825045 0.0108814092 0.0184645988 0.0034821389 0.0213910000 225405154 95654136 760807424 -0.0246095322 -0.0081729172 0.0006566107 390 1311867731.6247410774 0.0094752200 0.0108778036 0.0184645988 0.0034908486 0.0215270000 225406858 95654136 760807424 -0.0247511622 -0.0087916814 0.0003560864 391 1311867731.6616659164 0.0090618879 0.0108731593 0.0184645988 0.0035152654 0.0215010000 225410514 95654136 760807424 -0.0258672331 -0.0078951754 0.0002835296 392 1311867731.6925039291 0.0074003655 0.0108643001 0.0184645988 0.0035196904 0.0215460000 225412330 95654136 760807424 -0.0252989717 -0.0063801822 0.0010775710 393 1311867731.7299311161 0.0077084205 0.0108562699 0.0184645988 0.0035172371 0.0313730000 225415970 95654136 760807424 -0.0243090503 -0.0069769341 0.0029979383 394 1311867731.7615330219 0.0080629839 0.0108491803 0.0184645988 0.0035130370 0.0221120000 225419642 95654136 760807424 -0.0251968931 -0.0069697392 0.0013033275 395 1311867731.7939310074 0.0069669769 0.0108393520 0.0184645988 0.0035095627 0.0215010000 225421314 95654136 760807424 -0.0243509412 -0.0062189903 0.0021519142 396 1311867731.8252151012 0.0083002662 0.0108329401 0.0184645988 0.0035181596 0.0215530000 225424930 95654136 760807424 -0.0216115434 -0.0082147885 0.0032826583 397 1311867731.8593230247 0.0069028009 0.0108230405 0.0184645988 0.0035431502 0.0215120000 225426658 95654136 760807424 -0.0212933160 -0.0070596081 0.0031601917 398 1311867731.8910930157 0.0072760419 0.0108141285 0.0184645988 0.0035460810 0.0255000000 225430386 95654136 760807424 -0.0222905967 -0.0078060487 0.0025290237 399 1311867731.9224479198 0.0077075795 0.0108063427 0.0184645988 0.0035421509 0.0217240000 225604298 95654136 760807424 -0.0214226097 -0.0087232580 0.0020658220 400 1311867731.9598410130 0.0073191221 0.0107976246 0.0184645988 0.0035380563 0.0214940000 225606226 95654136 760807424 -0.0210265908 -0.0086962925 0.0017675582 401 1311867731.9915709496 0.0077408599 0.0107900017 0.0184645988 0.0035337827 0.0215040000 225609698 95654136 760807424 -0.0204766560 -0.0094675971 0.0008559945 402 1311867732.0239229202 0.0074430821 0.0107816761 0.0184645988 0.0035422510 0.0240750000 225611570 95654136 760807424 -0.0177389644 -0.0099174269 0.0009990095 403 1311867732.0619950294 0.0108304769 0.0107817972 0.0184645988 0.0035400264 0.0216070000 225615210 95654136 760807424 -0.0178470518 -0.0131959589 0.0004583699 404 1311867732.0918290615 0.0076947031 0.0107741558 0.0184645988 0.0035515814 0.0256960000 225618842 95654136 760807424 -0.0190657414 -0.0099612027 -0.0010446867 405 1311867732.1221950054 0.0097321225 0.0107715829 0.0184645988 0.0035567798 0.0254320000 225620514 95654136 760807424 -0.0169692878 -0.0125568202 -0.0007558249 406 1311867732.1605980396 0.0095172804 0.0107684935 0.0184645988 0.0035545404 0.0223330000 225624298 95654136 760807424 -0.0171876922 -0.0127257640 -0.0018453670 407 1311867732.1931400299 0.0075131473 0.0107604951 0.0184645988 0.0035825485 0.0216070000 225627826 95654136 760807424 -0.0172031298 -0.0108699119 -0.0032181635 408 1311867732.2232089043 0.0082192952 0.0107542667 0.0184645988 0.0036223548 0.0215200000 225629586 95654136 760807424 -0.0163051765 -0.0117653329 -0.0020310236 409 1311867732.2590498924 0.0065305079 0.0107439396 0.0184645988 0.0037244288 0.0216160000 225803778 95654136 760807424 -0.0179123133 -0.0092339031 -0.0054580774 410 1311867732.2903969288 0.0067002359 0.0107340770 0.0184645988 0.0037664616 0.0215010000 225805650 95654136 760807424 -0.0179841518 -0.0097745592 -0.0050000567 411 1311867732.3218240738 0.0100245196 0.0107323505 0.0184645988 0.0037690794 0.0288720000 225809122 95654136 760807424 -0.0174262188 -0.0134873698 -0.0037872542 412 1311867732.3607840538 0.0083285104 0.0107265160 0.0184645988 0.0037697697 0.0218280000 225812962 95654136 760807424 -0.0165881123 -0.0118378177 -0.0059300661 413 1311867732.3899528980 0.0073907063 0.0107184390 0.0184645988 0.0037704638 0.0215290000 225814522 95654136 760807424 -0.0159857627 -0.0112033226 -0.0053437753 414 1311867732.4218940735 0.0078061554 0.0107114045 0.0184645988 0.0037693984 0.0215500000 225818250 95654136 760807424 -0.0149202561 -0.0119007770 -0.0048877276 415 1311867732.4593050480 0.0059658336 0.0106999693 0.0184645988 0.0037705784 0.0219450000 225820034 95654136 760807424 -0.0147830192 -0.0098747248 -0.0065736044 416 1311867732.4918489456 0.0064937305 0.0106898582 0.0184645988 0.0037685835 0.0253520000 225823778 95654136 760807424 -0.0118914172 -0.0114343176 -0.0066244337 417 1311867732.5229809284 0.0071581881 0.0106813890 0.0184645988 0.0037646041 0.0216140000 225827194 95654136 760807424 -0.0126789175 -0.0116661480 -0.0069015748 418 1311867732.5698928833 0.0067051016 0.0106718763 0.0184645988 0.0037644613 0.0215890000 225829458 95654136 760807424 -0.0137121426 -0.0099496832 -0.0078913663 419 1311867732.5926280022 0.0074011781 0.0106640703 0.0184645988 0.0037637206 0.0219640000 225832706 95654136 760807424 -0.0143172676 -0.0095034456 -0.0095161572 420 1311867732.6242370605 0.0085789710 0.0106591058 0.0184645988 0.0037731061 0.0311310000 225834578 95654136 760807424 -0.0125622088 -0.0123249497 -0.0090125771 421 1311867732.6630299091 0.0079307919 0.0106526253 0.0184645988 0.0037740235 0.0224500000 225838218 95654136 760807424 -0.0124784373 -0.0113351122 -0.0092061786 422 1311867732.6922440529 0.0077811447 0.0106458208 0.0184645988 0.0037768783 0.0256110000 225841834 95654136 760807424 -0.0138528477 -0.0080843847 -0.0104478821 423 1311867732.7260940075 0.0067000263 0.0106364927 0.0184645988 0.0037746413 0.0220530000 225843562 95654136 760807424 -0.0115005737 -0.0094452230 -0.0098578082 424 1311867732.7601239681 0.0062742075 0.0106262043 0.0184645988 0.0037711156 0.0251340000 225847234 95654136 760807424 -0.0107234307 -0.0094354609 -0.0096117277 425 1311867732.7919039726 0.0088108759 0.0106219329 0.0184645988 0.0037709623 0.0250920000 225850762 95654136 760807424 -0.0132122096 -0.0100212125 -0.0106122764 426 1311867732.8280360699 0.0092314854 0.0106186690 0.0184645988 0.0037667606 0.0220800000 225852690 95654136 760807424 -0.0132202907 -0.0102791777 -0.0106450506 427 1311867732.8589270115 0.0084947217 0.0106136948 0.0184645988 0.0037694453 0.0220390000 225856162 95654136 760807424 -0.0141616892 -0.0071525434 -0.0109094894 428 1311867732.8912909031 0.0089827757 0.0106098843 0.0184645988 0.0037677503 0.0220840000 225858050 95654136 760807424 -0.0146779194 -0.0064093792 -0.0110848313 429 1311867732.9262781143 0.0343401544 0.0106651996 0.0343401544 0.0045429001 0.1347050000 226116686 95654136 760807424 0.0275122151 -0.0055602966 -0.0142981112 430 1311867732.9602870941 0.0036084349 0.0106487885 0.0343401544 0.0050532815 0.0227330000 226120342 95654136 760807424 -0.0074150860 -0.0070060026 -0.0081480239 431 1311867732.9987640381 0.0028304555 0.0106306485 0.0343401544 0.0050510308 0.0226700000 226122238 95654136 760807424 -0.0084013045 -0.0050004432 -0.0078412080 432 1311867733.0276939869 0.0033727351 0.0106138478 0.0343401544 0.0050467257 0.0226270000 226125838 95654136 760807424 -0.0090208091 -0.0032094545 -0.0082529876 433 1311867733.0607628822 0.0040927343 0.0105987875 0.0343401544 0.0050566583 0.0228240000 226127510 95654136 760807424 -0.0087537421 -0.0061345343 -0.0060339798 434 1311867733.0977020264 0.0034070248 0.0105822166 0.0343401544 0.0050579204 0.0314460000 226131294 95654136 760807424 -0.0087871030 -0.0039757527 -0.0065990449 435 1311867733.1263020039 0.0043847314 0.0105679695 0.0343401544 0.0050526472 0.0230100000 226134654 95654136 760807424 -0.0095310239 -0.0037488206 -0.0079782512 436 1311867733.1625030041 0.0031249064 0.0105508983 0.0343401544 0.0050493644 0.0226390000 226136638 95654136 760807424 -0.0075558177 -0.0051188990 -0.0054163574 437 1311867733.1926651001 0.0034755140 0.0105347075 0.0343401544 0.0050455059 0.0225740000 226140054 95654136 760807424 -0.0080931103 -0.0054550879 -0.0063183950 438 1311867733.2259631157 0.0049193529 0.0105218870 0.0343401544 0.0050492673 0.0226340000 226141982 95654136 760807424 -0.0092222709 -0.0019891553 -0.0076797530 439 1311867733.2618060112 0.0044947043 0.0105081577 0.0343401544 0.0050502905 0.0226630000 226316386 95654136 760807424 -0.0087802978 -0.0045972746 -0.0068519302 440 1311867733.2919199467 0.0041437210 0.0104936931 0.0343401544 0.0050449214 0.0225750000 226319946 95654136 760807424 -0.0080610719 -0.0049001137 -0.0056777284 441 1311867733.3300418854 0.0045148465 0.0104801356 0.0343401544 0.0050446471 0.0221680000 226321786 95654136 760807424 -0.0082399612 -0.0044018831 -0.0062444601 442 1311867733.3602790833 0.0050310148 0.0104678073 0.0343401544 0.0050390816 0.0226160000 226325458 95654136 760807424 -0.0076386817 -0.0060646348 -0.0047469293 443 1311867733.3923840523 0.0054258080 0.0104564258 0.0343401544 0.0050353299 0.0349100000 226328930 95654136 760807424 -0.0075767278 -0.0065220487 -0.0057748505 444 1311867733.4289550781 0.0056116926 0.0104455142 0.0343401544 0.0050351894 0.0234310000 226330914 95654136 760807424 -0.0079920702 -0.0036934712 -0.0069683907 445 1311867733.4588150978 0.0038534007 0.0104307005 0.0343401544 0.0050307345 0.0226200000 226334218 95654136 760807424 -0.0059393486 -0.0040590647 -0.0065767467 446 1311867733.4956119061 0.0040191039 0.0104163247 0.0343401544 0.0050277160 0.0224200000 226336090 95654136 760807424 -0.0057964437 -0.0039705546 -0.0062686456 447 1311867733.5290400982 0.0062707756 0.0104070505 0.0343401544 0.0050279793 0.0258500000 226339618 95654136 760807424 -0.0070930189 -0.0018220984 -0.0079391683 448 1311867733.5630290508 0.0060292576 0.0103972787 0.0343401544 0.0050248678 0.0223100000 226343346 95654136 760807424 -0.0068225502 -0.0052787531 -0.0075613232 449 1311867733.5922229290 0.0056720879 0.0103867549 0.0343401544 0.0050218617 0.0257640000 226344906 95654136 760807424 -0.0057622679 -0.0069573568 -0.0059076631 450 1311867733.6283020973 0.0064584916 0.0103780254 0.0343401544 0.0050213115 0.0225640000 226348690 95654136 760807424 -0.0069175852 -0.0039710347 -0.0063917334 451 1311867733.6601879597 0.0064040041 0.0103692138 0.0343401544 0.0050160250 0.0254440000 226350362 95654136 760807424 -0.0065030237 -0.0038607325 -0.0065660086 452 1311867733.6917510033 0.0054581328 0.0103583486 0.0343401544 0.0050113170 0.0226680000 226525038 95654136 760807424 -0.0051945532 -0.0050710975 -0.0057736738 453 1311867733.7288239002 0.0066018826 0.0103500562 0.0343401544 0.0050070534 0.0226150000 226528622 95654136 760807424 -0.0055298330 -0.0066351988 -0.0059592808 454 1311867733.7597820759 0.0077833794 0.0103444027 0.0343401544 0.0050025980 0.0221470000 226530382 95654136 760807424 -0.0063701593 -0.0053677917 -0.0061748652 455 1311867733.7924160957 0.0079458114 0.0103391311 0.0343401544 0.0050259140 0.0222190000 226533854 95654136 760807424 -0.0058493675 -0.0060210098 -0.0062989928 456 1311867733.8282589912 0.0067324433 0.0103312217 0.0343401544 0.0050252897 0.0228970000 226535838 95654136 760807424 -0.0038763967 -0.0075392853 -0.0049307933 457 1311867733.8608579636 0.0077804183 0.0103256400 0.0343401544 0.0050228427 0.0223060000 226710030 95654136 760807424 -0.0045377417 -0.0067464118 -0.0060320040 458 1311867733.8918149471 0.0094671911 0.0103237657 0.0343401544 0.0050213640 0.0225450000 226713590 95654136 760807424 -0.0057350034 -0.0066908714 -0.0063000591 459 1311867733.9289460182 0.0091039203 0.0103211081 0.0343401544 0.0050170668 0.0226350000 226715374 95654136 760807424 -0.0046998188 -0.0069083995 -0.0056375568 460 1311867733.9595899582 0.0103037860 0.0103210704 0.0343401544 0.0050206095 0.0262990000 226719046 95654136 760807424 -0.0054703727 -0.0073070657 -0.0064251288 461 1311867733.9941790104 0.0117142005 0.0103240924 0.0343401544 0.0050257840 0.0226620000 226893226 95654136 760807424 -0.0058268206 -0.0079983156 -0.0072172484 462 1311867734.0275731087 0.0103684356 0.0103241884 0.0343401544 0.0050256128 0.0222090000 226895210 95654136 760807424 -0.0043179737 -0.0088087525 -0.0063077263 463 1311867734.0599920750 0.0088896919 0.0103210901 0.0343401544 0.0050220141 0.0221670000 226898626 95654136 760807424 -0.0022059327 -0.0069439341 -0.0067066252 464 1311867734.0956780910 0.0109518887 0.0103224496 0.0343401544 0.0050174316 0.0226590000 226900610 95654136 760807424 -0.0039377343 -0.0076354155 -0.0073616081 465 1311867734.1274170876 0.0099357963 0.0103216181 0.0343401544 0.0050129162 0.0225530000 226904138 95654136 760807424 -0.0026807862 -0.0099681821 -0.0062724114 466 1311867734.1618878841 0.0096991193 0.0103202822 0.0343401544 0.0050106558 0.0221740000 226907810 95654136 760807424 -0.0020350092 -0.0090518622 -0.0076017240 467 1311867734.1942350864 0.0090522338 0.0103175669 0.0343401544 0.0050077854 0.0221640000 226909538 95654136 760807424 -0.0004790614 -0.0070815329 -0.0081246104 468 1311867734.2291829586 0.0080444692 0.0103127099 0.0343401544 0.0050062917 0.0223340000 227083450 95654136 760807424 0.0005257648 -0.0100766327 -0.0067215371 469 1311867734.2607750893 0.0076238415 0.0103069767 0.0343401544 0.0050009901 0.0261220000 227085122 95654136 760807424 0.0016502807 -0.0085009057 -0.0079879677 470 1311867734.2941219807 0.0088820560 0.0103039449 0.0343401544 0.0049966542 0.0226410000 227088794 95654136 760807424 0.0012245965 -0.0071333055 -0.0081870733 471 1311867734.3263280392 0.0073342351 0.0102976398 0.0343401544 0.0049958760 0.0222170000 227092266 95654136 760807424 0.0026012855 -0.0087257158 -0.0078738201 472 1311867734.3610401154 0.0056401812 0.0102877723 0.0343401544 0.0049948851 0.0224270000 227094194 95654136 760807424 0.0046881447 -0.0088848732 -0.0073933811 473 1311867734.3941841125 0.0070889993 0.0102810096 0.0343401544 0.0049998708 0.0223760000 227097722 95654136 760807424 0.0047828690 -0.0064871470 -0.0077556935 474 1311867734.4276480675 0.0064067072 0.0102728360 0.0343401544 0.0049952072 0.0224710000 227099650 95654136 760807424 0.0049107755 -0.0077859256 -0.0073666056 475 1311867734.4586091042 0.0063054929 0.0102644837 0.0343401544 0.0049906421 0.0224540000 227103066 95654136 760807424 0.0051350924 -0.0084223105 -0.0072059967 476 1311867734.4938759804 0.0075880028 0.0102588608 0.0343401544 0.0049870035 0.0224930000 227106850 95654136 760807424 0.0045558717 -0.0074695563 -0.0077435770 477 1311867734.5300569534 0.0072429408 0.0102525381 0.0343401544 0.0049834119 0.0224820000 227108634 95654136 760807424 0.0045954622 -0.0088239564 -0.0072797327 478 1311867734.5595300198 0.0068973936 0.0102455190 0.0343401544 0.0049861977 0.0307640000 227282626 95654136 760807424 0.0053466111 -0.0092449952 -0.0062095574 479 1311867734.5953910351 0.0062963297 0.0102372743 0.0343401544 0.0049825599 0.0229510000 227286154 95654136 760807424 0.0060105254 -0.0091152880 -0.0069111050 480 1311867734.6285231113 0.0063491208 0.0102291740 0.0343401544 0.0049778158 0.0224620000 227288082 95654136 760807424 0.0064060297 -0.0089484807 -0.0063902023 481 1311867734.6593229771 0.0051132897 0.0102185381 0.0343401544 0.0049739849 0.0225460000 227291498 95654136 760807424 0.0072195702 -0.0101570301 -0.0055062361 482 1311867734.6947479248 0.0050211069 0.0102077550 0.0343401544 0.0049703162 0.0226790000 227293426 95654136 760807424 0.0071175173 -0.0106124291 -0.0054500103 483 1311867734.7310240269 0.0047720768 0.0101965010 0.0343401544 0.0049716477 0.0224730000 227297066 95654136 760807424 0.0077342000 -0.0107356152 -0.0060088718 484 1311867734.7607629299 0.0059792576 0.0101877877 0.0343401544 0.0049674413 0.0229960000 227300626 95654136 760807424 0.0071979961 -0.0102512641 -0.0066783410 485 1311867734.7976419926 0.0075317770 0.0101823114 0.0343401544 0.0049656817 0.0225890000 227302466 95654136 760807424 0.0063551343 -0.0088215331 -0.0064046266 486 1311867734.8298120499 0.0078367926 0.0101774852 0.0343401544 0.0049620574 0.0330390000 227306138 95654136 760807424 0.0068799928 -0.0078237727 -0.0061356407 487 1311867734.8645250797 0.0083500603 0.0101737328 0.0343401544 0.0049573152 0.0233640000 227478410 95654136 760807424 0.0073606172 -0.0070179268 -0.0063810931 488 1311867734.8943901062 0.0063154274 0.0101658265 0.0343401544 0.0049551848 0.0226060000 227482082 95654136 760807424 0.0087851668 -0.0089490255 -0.0059942282 489 1311867734.9263660908 0.0057913177 0.0101568806 0.0343401544 0.0049514013 0.0226250000 227485498 95654136 760807424 0.0098924302 -0.0088830320 -0.0061058640 490 1311867734.9631719589 0.0072094924 0.0101508656 0.0343401544 0.0049479724 0.0226670000 227487258 95654136 760807424 0.0091006774 -0.0086126262 -0.0068250252 491 1311867734.9948470592 0.0057358723 0.0101418737 0.0343401544 0.0049501251 0.0226620000 227490730 95654136 760807424 0.0090558063 -0.0112315845 -0.0058463165 492 1311867735.0292239189 0.0060044099 0.0101334642 0.0343401544 0.0049513927 0.0225850000 227492770 95654136 760807424 0.0095544728 -0.0105174659 -0.0064880666 493 1311867735.0596508980 0.0072490308 0.0101276135 0.0343401544 0.0049481434 0.0226340000 227496074 95654136 760807424 0.0091761639 -0.0088635050 -0.0069842399 494 1311867735.0952830315 0.0065384428 0.0101203479 0.0343401544 0.0049447152 0.0319880000 227499858 95654136 760807424 0.0093126539 -0.0097437175 -0.0057907030 495 1311867735.1313030720 0.0067930296 0.0101136261 0.0343401544 0.0049424082 0.0231110000 227501642 95654136 760807424 0.0095042083 -0.0093777701 -0.0057586879 496 1311867735.1603751183 0.0061752596 0.0101056858 0.0343401544 0.0049409951 0.0234810000 227505202 95654136 760807424 0.0098390831 -0.0101197138 -0.0061708074 497 1311867735.1994349957 0.0050318954 0.0100954770 0.0343401544 0.0049389460 0.0226520000 227508842 95654136 760807424 0.0104532549 -0.0123366658 -0.0049988376 498 1311867735.2263538837 0.0046222233 0.0100844865 0.0343401544 0.0049365273 0.0227210000 227510658 95654136 760807424 0.0113080833 -0.0115198819 -0.0054971511 499 1311867735.2655019760 0.0052068117 0.0100747116 0.0343401544 0.0049326949 0.0226550000 227514242 95654136 760807424 0.0116470316 -0.0104831317 -0.0052993000 500 1311867735.2961549759 0.0052280664 0.0100650183 0.0343401544 0.0049328827 0.0226990000 227516114 95654136 760807424 0.0115082990 -0.0113386428 -0.0049296068 501 1311867735.3321089745 0.0065759015 0.0100580540 0.0343401544 0.0049304912 0.0227510000 227691158 95654136 760807424 0.0109776817 -0.0099405879 -0.0052617732 502 1311867735.3666970730 0.0059207068 0.0100498123 0.0343401544 0.0049364837 0.0325030000 227694774 95654136 760807424 0.0115946457 -0.0107425489 -0.0054633226 503 1311867735.3943350315 0.0054784445 0.0100407241 0.0343401544 0.0049495503 0.0262870000 227696278 95654136 760807424 0.0133337677 -0.0100552645 -0.0050453944 504 1311867735.4322299957 0.0063234628 0.0100333486 0.0343401544 0.0049534821 0.0228020000 227700174 95654136 760807424 0.0134343859 -0.0090080760 -0.0050435239 505 1311867735.4628560543 0.0065669762 0.0100264845 0.0343401544 0.0049548086 0.0226580000 227701790 95654136 760807424 0.0127717108 -0.0092955027 -0.0043692305 506 1311867735.4973869324 0.0058788606 0.0100182876 0.0343401544 0.0049619356 0.0227140000 227705574 95654136 760807424 0.0133276936 -0.0098466985 -0.0039522704 507 1311867735.5293200016 0.0070375013 0.0100124083 0.0343401544 0.0049581927 0.0226340000 227708990 95654136 760807424 0.0116906483 -0.0098373760 -0.0037374813 508 1311867735.5632629395 0.0050563854 0.0100026524 0.0343401544 0.0049540470 0.0226430000 227710974 95654136 760807424 0.0137876365 -0.0108198421 -0.0032846592 509 1311867735.5976569653 0.0066202325 0.0099960072 0.0343401544 0.0049502755 0.0226360000 227714502 95654136 760807424 0.0121857766 -0.0105406241 -0.0029341592 510 1311867735.6363260746 0.0066894297 0.0099895237 0.0343401544 0.0049483294 0.0326480000 227716486 95654136 760807424 0.0123942615 -0.0106535666 -0.0033140178 511 1311867735.6626520157 0.0051877284 0.0099801268 0.0343401544 0.0049457062 0.0231510000 227720110 95654136 760807424 0.0143510969 -0.0115066953 -0.0026451549 512 1311867735.6952130795 0.0051803319 0.0099707522 0.0343401544 0.0049409469 0.0228020000 227894966 95654136 760807424 0.0136565464 -0.0129763689 -0.0027084893 513 1311867735.7291250229 0.0049563269 0.0099609775 0.0343401544 0.0049444242 0.0227810000 227990902 95654136 760807424 0.0150673166 -0.0118395882 -0.0034006564 514 1311867735.7631659508 0.0059406394 0.0099531558 0.0343401544 0.0049428550 0.0227190000 228097086 95654136 760807424 0.0142904278 -0.0111496495 -0.0041642035 515 1311867735.7963778973 0.0057030055 0.0099449031 0.0343401544 0.0049419415 0.0263590000 228100558 95654136 760807424 0.0139444098 -0.0120313661 -0.0037378620 516 1311867735.8277759552 0.0068469560 0.0099388993 0.0343401544 0.0049453394 0.0227510000 228102374 95654136 760807424 0.0136032002 -0.0104152923 -0.0046466123 517 1311867735.8638889790 0.0061010947 0.0099314761 0.0343401544 0.0049431773 0.0226990000 228105790 95654136 760807424 0.0145205716 -0.0102167940 -0.0049478891 518 1311867735.8951849937 0.0055405223 0.0099229994 0.0343401544 0.0049396271 0.0313180000 228107662 95654136 760807424 0.0147476215 -0.0103701157 -0.0048447964 519 1311867735.9322230816 0.0050274073 0.0099135666 0.0343401544 0.0049349709 0.0230580000 228111302 95654136 760807424 0.0156177767 -0.0100132348 -0.0043084668 520 1311867735.9623689651 0.0051223384 0.0099043527 0.0343401544 0.0049333538 0.0269220000 228114918 95654136 760807424 0.0153433215 -0.0097305514 -0.0037916712 521 1311867735.9945859909 0.0065866644 0.0098979848 0.0343401544 0.0049349835 0.0227450000 228116534 95654136 760807424 0.0139185935 -0.0088750124 -0.0037943900 522 1311867736.0290079117 0.0051635001 0.0098889149 0.0343401544 0.0049334502 0.0235190000 228120318 95654136 760807424 0.0158154946 -0.0092096273 -0.0031130686 523 1311867736.0642199516 0.0045765555 0.0098787574 0.0343401544 0.0049329304 0.0229170000 228293522 95654136 760807424 0.0154749556 -0.0102069238 -0.0029643159 524 1311867736.0946779251 0.0046745436 0.0098688257 0.0343401544 0.0049328750 0.0263940000 228297082 95654136 760807424 0.0172426607 -0.0094773835 -0.0024589975 525 1311867736.1299190521 0.0037235820 0.0098571205 0.0343401544 0.0049394213 0.0227240000 228300666 95654136 760807424 0.0162019189 -0.0107778274 -0.0025337928 526 1311867736.1631360054 0.0037061253 0.0098454266 0.0343401544 0.0049379929 0.0327110000 228302650 95654136 760807424 0.0171249732 -0.0105456132 -0.0023929651 527 1311867736.1942429543 0.0046348022 0.0098355393 0.0343401544 0.0049432549 0.0230830000 228306010 95654136 760807424 0.0167278945 -0.0096939998 -0.0022208476 528 1311867736.2298679352 0.0072510517 0.0098306444 0.0343401544 0.0049444640 0.0226860000 228307994 95654136 760807424 0.0122199832 -0.0088667059 -0.0023873739 529 1311867736.2633900642 0.0056208256 0.0098226863 0.0343401544 0.0049544980 0.0260730000 228311522 95654136 760807424 0.0142337065 -0.0093415808 -0.0029941485 530 1311867736.2995250225 0.0032842392 0.0098103496 0.0343401544 0.0049510959 0.0227220000 228315306 95654136 760807424 0.0146092856 -0.0122918449 -0.0018486232 531 1311867736.3304500580 0.0041699596 0.0097997274 0.0343401544 0.0049490125 0.0228790000 228488002 95654136 760807424 0.0149132283 -0.0108768679 -0.0023672224 532 1311867736.3637149334 0.0036770238 0.0097882186 0.0343401544 0.0049472678 0.0227250000 228491730 95654136 760807424 0.0145967817 -0.0115568405 -0.0027333009 533 1311867736.3943159580 0.0035048791 0.0097764300 0.0343401544 0.0049428228 0.0226550000 228495090 95654136 760807424 0.0139368493 -0.0133534428 -0.0017885102 534 1311867736.4313519001 0.0039226110 0.0097654678 0.0343401544 0.0049549217 0.0316430000 228497186 95654136 760807424 0.0140386606 -0.0121233072 -0.0028475551 535 1311867736.4625089169 0.0042375922 0.0097551353 0.0343401544 0.0049525470 0.0230640000 228500658 95654136 760807424 0.0132790748 -0.0126841776 -0.0027667521 536 1311867736.4987530708 0.0038183457 0.0097440592 0.0343401544 0.0049486953 0.0226690000 228502586 95654136 760807424 0.0144593446 -0.0135538848 -0.0021464103 537 1311867736.5321619511 0.0040518106 0.0097334591 0.0343401544 0.0049573953 0.0226440000 228506114 95654136 760807424 0.0146526862 -0.0124956379 -0.0028523272 538 1311867736.5634689331 0.0044203382 0.0097235834 0.0343401544 0.0049541710 0.0225440000 228509786 95654136 760807424 0.0144054750 -0.0120720491 -0.0033919513 539 1311867736.5958600044 0.0048176073 0.0097144814 0.0343401544 0.0049498478 0.0226110000 228511458 95654136 760807424 0.0131998910 -0.0143499812 -0.0017058153 540 1311867736.6320459843 0.0049401210 0.0097056400 0.0343401544 0.0049583782 0.0262280000 228515242 95654136 760807424 0.0121731106 -0.0146114966 -0.0028729984 541 1311867736.6635379791 0.0045746341 0.0096961557 0.0343401544 0.0049684244 0.0226020000 228516914 95654136 760807424 0.0126742190 -0.0140984375 -0.0033754329 542 1311867736.6945500374 0.0043065925 0.0096862119 0.0343401544 0.0049689326 0.0248390000 228691658 95654136 760807424 0.0130401356 -0.0166797824 -0.0025581629 543 1311867736.7332150936 0.0047721812 0.0096771621 0.0343401544 0.0049689297 0.0226300000 228695298 95654136 760807424 0.0128227947 -0.0150418384 -0.0035047992 544 1311867736.7636179924 0.0046345065 0.0096678925 0.0343401544 0.0049673393 0.0225920000 228697302 95654136 760807424 0.0135522513 -0.0147207566 -0.0043964842 545 1311867736.7952749729 0.0040910230 0.0096576597 0.0343401544 0.0049698024 0.0225650000 228700718 95654136 760807424 0.0136494199 -0.0161378421 -0.0042736144 546 1311867736.8325269222 0.0043265293 0.0096478957 0.0343401544 0.0049693838 0.0226190000 228702702 95654136 760807424 0.0140908463 -0.0152388718 -0.0051400447 547 1311867736.8640279770 0.0054553337 0.0096402311 0.0343401544 0.0049712186 0.0225360000 228706230 95654136 760807424 0.0138830245 -0.0135722356 -0.0065552602 548 1311867736.8945000172 0.0047112787 0.0096312366 0.0343401544 0.0049694360 0.0225610000 228709790 95654136 760807424 0.0132004023 -0.0160241760 -0.0055020303 549 1311867736.9362800121 0.0035928795 0.0096202378 0.0343401544 0.0049676227 0.0225420000 228711742 95654136 760807424 0.0152031295 -0.0154687231 -0.0061036260 550 1311867736.9632000923 0.0076902108 0.0096167287 0.0343401544 0.0049717803 0.0226250000 228885850 95654136 760807424 0.0170538872 -0.0101310378 -0.0071055242 551 1311867736.9954400063 0.0045966879 0.0096076179 0.0343401544 0.0049708166 0.0259740000 228889322 95654136 760807424 0.0145678911 -0.0150137432 -0.0052388590 552 1311867737.0307478905 0.0050905105 0.0095994347 0.0343401544 0.0049675026 0.0226110000 228891250 95654136 760807424 0.0135325026 -0.0157690011 -0.0049197096 553 1311867737.0629029274 0.0055387374 0.0095920917 0.0343401544 0.0049639461 0.0225460000 228894910 95654136 760807424 0.0143520264 -0.0137265883 -0.0057038460 554 1311867737.0977239609 0.0057740360 0.0095851999 0.0343401544 0.0049614998 0.0225360000 228896838 95654136 760807424 0.0145309810 -0.0133828279 -0.0056555807 555 1311867737.1300530434 0.0057891291 0.0095783601 0.0343401544 0.0049576976 0.0225720000 228900254 95654136 760807424 0.0148284063 -0.0133835413 -0.0053325240 556 1311867737.1655049324 0.0070773880 0.0095738620 0.0343401544 0.0049549041 0.0225580000 228904038 95654136 760807424 0.0166162308 -0.0112487869 -0.0057495171 557 1311867737.1952710152 0.0068267705 0.0095689300 0.0343401544 0.0049518196 0.0225680000 228905654 95654136 760807424 0.0176466648 -0.0114491349 -0.0059844698 558 1311867737.2333149910 0.0077500716 0.0095656704 0.0343401544 0.0049476094 0.0262370000 228909550 95654136 760807424 0.0182311889 -0.0106462389 -0.0058991187 559 1311867737.2693018913 0.0089698462 0.0095646046 0.0343401544 0.0049458967 0.0225390000 228911278 95654136 760807424 0.0184097420 -0.0093272692 -0.0059290775 560 1311867737.2957379818 0.0102123432 0.0095657612 0.0343401544 0.0049428738 0.0257350000 228914782 95654136 760807424 0.0186756700 -0.0080235740 -0.0062093488 561 1311867737.3316531181 0.0100486856 0.0095666221 0.0343401544 0.0049387819 0.0227430000 229089098 95654136 760807424 0.0175449308 -0.0084480727 -0.0056228405 562 1311867737.3659460545 0.0104060806 0.0095681158 0.0343401544 0.0049349885 0.0234580000 229090970 95654136 760807424 0.0172955059 -0.0081054065 -0.0055240616 563 1311867737.3967239857 0.0090992162 0.0095672829 0.0343401544 0.0049339553 0.0228650000 229094574 95654136 760807424 0.0180486422 -0.0092446888 -0.0054990607 564 1311867737.4355359077 0.0096688801 0.0095674630 0.0343401544 0.0049296214 0.0225980000 229096614 95654136 760807424 0.0188675839 -0.0086109573 -0.0049103261 565 1311867737.4691100121 0.0083630094 0.0095653313 0.0343401544 0.0049255234 0.0228370000 229100142 95654136 760807424 0.0193533674 -0.0098803863 -0.0040882747 566 1311867737.4959459305 0.0080944393 0.0095627325 0.0343401544 0.0049223500 0.0228200000 229103646 95654136 760807424 0.0182807483 -0.0102256378 -0.0041382052 567 1311867737.5353999138 0.0072841360 0.0095587138 0.0343401544 0.0049197053 0.0228610000 229105542 95654136 760807424 0.0169944931 -0.0115598477 -0.0034050893 568 1311867737.5654399395 0.0082519641 0.0095564132 0.0343401544 0.0049161980 0.0229190000 229109102 95654136 760807424 0.0171653405 -0.0105220284 -0.0033153112 569 1311867737.5958089828 0.0075162002 0.0095528276 0.0343401544 0.0049153521 0.0253570000 229112574 95654136 760807424 0.0182886980 -0.0110038165 -0.0037408150 570 1311867737.6330978870 0.0081563629 0.0095503777 0.0343401544 0.0049122873 0.0265390000 229285514 95654136 760807424 0.0206895024 -0.0101682581 -0.0034879565 571 1311867737.6624519825 0.0080120135 0.0095476835 0.0343401544 0.0049080854 0.0227740000 229289062 95654136 760807424 0.0200275537 -0.0108853905 -0.0025935427 572 1311867737.7032339573 0.0082710451 0.0095454516 0.0343401544 0.0049060644 0.0227070000 229291102 95654136 760807424 0.0204277467 -0.0115067260 -0.0012655327 573 1311867737.7314720154 0.0095111821 0.0095453918 0.0343401544 0.0049052578 0.0227850000 229294462 95654136 760807424 0.0188113675 -0.0106189065 -0.0013268224 574 1311867737.7658560276 0.0082054064 0.0095430573 0.0343401544 0.0049014308 0.0227570000 229298190 95654136 760807424 0.0197465010 -0.0117890881 -0.0017725690 575 1311867737.8011269569 0.0085343299 0.0095413030 0.0343401544 0.0048981960 0.0227590000 229299974 95654136 760807424 0.0187318902 -0.0122730322 -0.0015837145 576 1311867737.8323190212 0.0075405445 0.0095378295 0.0343401544 0.0048945328 0.0232310000 229303646 95654136 760807424 0.0189670511 -0.0137272645 -0.0012035837 577 1311867737.8633110523 0.0089490665 0.0095368091 0.0343401544 0.0048944528 0.0229420000 229305262 95654136 760807424 0.0219088458 -0.0113068614 -0.0021426796 578 1311867737.9004418850 0.0081813559 0.0095344640 0.0343401544 0.0048907393 0.0261080000 229308990 95654136 760807424 0.0221376214 -0.0125604374 -0.0008372668 579 1311867737.9305500984 0.0079732593 0.0095317676 0.0343401544 0.0048912323 0.0259190000 229312406 95654136 760807424 0.0238386430 -0.0130531862 -0.0000092012 580 1311867737.9630560875 0.0095020784 0.0095317165 0.0343401544 0.0048884779 0.0228030000 229314334 95654136 760807424 0.0237470809 -0.0116500100 0.0004959555 581 1311867737.9996941090 0.0082683209 0.0095295419 0.0343401544 0.0048852067 0.0228110000 229317918 95654136 760807424 0.0227860734 -0.0134967407 0.0014376461 582 1311867738.0315399170 0.0105070602 0.0095312215 0.0343401544 0.0048858727 0.0228300000 229320054 95654136 760807424 0.0236403812 -0.0108678220 0.0020249155 583 1311867738.0629770756 0.0121128168 0.0095356496 0.0343401544 0.0048829424 0.0227920000 229323526 95654136 760807424 0.0239257384 -0.0090040304 0.0021771207 584 1311867738.0998299122 0.0111673465 0.0095384436 0.0343401544 0.0048795478 0.0229530000 229499202 95654136 760807424 0.0246763024 -0.0102101220 0.0028964889 585 1311867738.1308510303 0.0083129117 0.0095363487 0.0343401544 0.0048807951 0.0227950000 229500818 95654136 760807424 0.0240948051 -0.0139685841 0.0042917598 586 1311867738.1635079384 0.0088458806 0.0095351704 0.0343401544 0.0048773818 0.0227910000 229504546 95654136 760807424 0.0253166370 -0.0139035955 0.0058504473 587 1311867738.1992070675 0.0097843241 0.0095355949 0.0343401544 0.0048749627 0.0228140000 229508074 95654136 760807424 0.0247925445 -0.0133609567 0.0057069161 588 1311867738.2306089401 0.0074821622 0.0095321027 0.0343401544 0.0048779877 0.0228340000 229509946 95654136 760807424 0.0260483045 -0.0169011261 0.0062510823 589 1311867738.2632689476 0.0073421774 0.0095283846 0.0343401544 0.0048795890 0.0228450000 229513474 95654136 760807424 0.0264302939 -0.0180640277 0.0069172578 590 1311867738.3008689880 0.0092258081 0.0095278718 0.0343401544 0.0048764630 0.0229520000 229515458 95654136 760807424 0.0284757670 -0.0161995310 0.0069939587 591 1311867738.3339769840 0.0083874771 0.0095259422 0.0343401544 0.0048761200 0.0229150000 229518930 95654136 760807424 0.0274261702 -0.0177609436 0.0065259743 592 1311867738.3651630878 0.0081284409 0.0095235815 0.0343401544 0.0048737887 0.0229030000 229522602 95654136 760807424 0.0289039519 -0.0189184137 0.0067110164 593 1311867738.3995900154 0.0090529202 0.0095227878 0.0343401544 0.0048723284 0.0229100000 229524518 95654136 760807424 0.0318295434 -0.0172416158 0.0054061916 594 1311867738.4334011078 0.0085971905 0.0095212296 0.0343401544 0.0048697321 0.0230650000 229699606 95654136 760807424 0.0316674076 -0.0176004544 0.0047066878 595 1311867738.4643430710 0.0078786528 0.0095184690 0.0343401544 0.0048660994 0.0229450000 229701222 95654136 760807424 0.0302768573 -0.0196194686 0.0056184400 596 1311867738.5000250340 0.0091854427 0.0095179102 0.0343401544 0.0048635780 0.0229580000 229705006 95654136 760807424 0.0322968662 -0.0170776099 0.0047912439 597 1311867738.5332009792 0.0114083542 0.0095210768 0.0343401544 0.0048612192 0.0229070000 229708478 95654136 760807424 0.0322689004 -0.0141591262 0.0042703175 598 1311867738.5634350777 0.0100466972 0.0095219557 0.0343401544 0.0048612371 0.0228750000 229710350 95654136 760807424 0.0330425799 -0.0163704567 0.0051568770 599 1311867738.6022439003 0.0098442016 0.0095224937 0.0343401544 0.0048582137 0.0262140000 229713990 95654136 760807424 0.0342554040 -0.0172155928 0.0057960819 600 1311867738.6328980923 0.0100419372 0.0095233594 0.0343401544 0.0048557094 0.0228830000 229715806 95654136 760807424 0.0356916524 -0.0161752179 0.0043889382 601 1311867738.6628730297 0.0094583593 0.0095232513 0.0343401544 0.0048524374 0.0228640000 229719278 95654136 760807424 0.0366591886 -0.0170260966 0.0044287853 602 1311867738.6996099949 0.0094688833 0.0095231610 0.0343401544 0.0048518782 0.0228860000 229723062 95654136 760807424 0.0369203500 -0.0179109145 0.0050177691 603 1311867738.7314729691 0.0090343431 0.0095223503 0.0343401544 0.0048580051 0.0265420000 229724734 95654136 760807424 0.0361898728 -0.0187139567 0.0044003222 604 1311867738.7626600266 0.0090654409 0.0095215939 0.0343401544 0.0048592165 0.0238560000 229899118 95654136 760807424 0.0388860404 -0.0176431648 0.0030494765 605 1311867738.8032259941 0.0092951171 0.0095212195 0.0343401544 0.0048604983 0.0271560000 229902814 95654136 760807424 0.0393621698 -0.0184455886 0.0040675560 606 1311867738.8306779861 0.0103425356 0.0095225748 0.0343401544 0.0048673586 0.0229840000 229904574 95654136 760807424 0.0394215398 -0.0179495849 0.0047539216 607 1311867738.8639259338 0.0110180900 0.0095250386 0.0343401544 0.0048635112 0.0229110000 229908102 95654136 760807424 0.0414371118 -0.0163682215 0.0035358928 608 1311867738.9000120163 0.0089118211 0.0095240300 0.0343401544 0.0048676496 0.0271310000 229910218 95654136 760807424 0.0428154133 -0.0182162989 0.0020911752 609 1311867738.9307610989 0.0094232699 0.0095238646 0.0343401544 0.0048670108 0.0228560000 229913634 95654136 760807424 0.0414917022 -0.0190634057 0.0036179430 610 1311867738.9664750099 0.0095392130 0.0095238897 0.0343401544 0.0048639573 0.0228670000 229917418 95654136 760807424 0.0434607081 -0.0180950612 0.0023292517 611 1311867738.9989941120 0.0103218276 0.0095251957 0.0343401544 0.0048602038 0.0228730000 229919146 95654136 760807424 0.0447862707 -0.0180029087 0.0028024283 612 1311867739.0329539776 0.0103270458 0.0095265059 0.0343401544 0.0048566391 0.0266350000 230093922 95654136 760807424 0.0443288833 -0.0198416598 0.0044196211 613 1311867739.0664470196 0.0098425206 0.0095270214 0.0343401544 0.0048535259 0.0357310000 230095594 95654136 760807424 0.0452417172 -0.0197772440 0.0034900228 614 1311867739.0997900963 0.0106244357 0.0095288087 0.0343401544 0.0048502924 0.0237490000 230099154 95654136 760807424 0.0463732816 -0.0180211924 0.0021695881 615 1311867739.1321549416 0.0092978235 0.0095284332 0.0343401544 0.0048498722 0.0227290000 230102570 95654136 760807424 0.0463296250 -0.0195831191 0.0018085116 616 1311867739.1687150002 0.0098857870 0.0095290133 0.0343401544 0.0048484515 0.0237280000 230104554 95654136 760807424 0.0464157388 -0.0189701747 0.0016634682 617 1311867739.1999289989 0.0123685123 0.0095336154 0.0343401544 0.0048535621 0.0227490000 230107970 95654136 760807424 0.0456259139 -0.0166991334 0.0028262921 618 1311867739.2313010693 0.0128816068 0.0095390328 0.0343401544 0.0048498838 0.0228050000 230109786 95654136 760807424 0.0460212231 -0.0161211547 0.0024021908 619 1311867739.2672259808 0.0123242578 0.0095435324 0.0343401544 0.0048464937 0.0226900000 230113426 95654136 760807424 0.0449285470 -0.0177414082 0.0032773316 620 1311867739.2996931076 0.0137810279 0.0095503671 0.0343401544 0.0048558974 0.0226610000 230117098 95654136 760807424 0.0444500633 -0.0171423461 0.0044163633 621 1311867739.3319859505 0.0131047796 0.0095560908 0.0343401544 0.0048543725 0.0230980000 230290358 95654136 760807424 0.0433153026 -0.0173673145 0.0034417585 622 1311867739.3670029640 0.0120331021 0.0095600731 0.0343401544 0.0048517893 0.0226660000 230294086 95654136 760807424 0.0435991362 -0.0185090099 0.0034486086 623 1311867739.3990058899 0.0118435100 0.0095637383 0.0343401544 0.0048482656 0.0228110000 230297614 95654136 760807424 0.0433402620 -0.0193045847 0.0044085933 624 1311867739.4311320782 0.0109750172 0.0095660000 0.0343401544 0.0048492744 0.0227290000 230299430 95654136 760807424 0.0450509340 -0.0191917475 0.0030466751 625 1311867739.4668490887 0.0101630362 0.0095669553 0.0343401544 0.0048467312 0.0313120000 230303014 95654136 760807424 0.0454866216 -0.0201285388 0.0027056772 626 1311867739.4988598824 0.0096996520 0.0095671672 0.0343401544 0.0048480358 0.0231060000 230304886 95654136 760807424 0.0434017703 -0.0218813047 0.0049027679 627 1311867739.5316400528 0.0102227265 0.0095682128 0.0343401544 0.0048442929 0.0227430000 230308302 95654136 760807424 0.0449445322 -0.0200826284 0.0037353002 628 1311867739.5670249462 0.0116939107 0.0095715976 0.0343401544 0.0048414479 0.0227520000 230312086 95654136 760807424 0.0453107692 -0.0183122344 0.0034327828 629 1311867739.5990490913 0.0108693428 0.0095736608 0.0343401544 0.0048379125 0.0227440000 230313758 95654136 760807424 0.0441521555 -0.0201596431 0.0051676678 630 1311867739.6325490475 0.0141507052 0.0095809260 0.0343401544 0.0048363690 0.0227750000 230317486 95654136 760807424 0.0461355932 -0.0164039582 0.0050927275 631 1311867739.6706740856 0.0138402274 0.0095876761 0.0343401544 0.0048348101 0.0227190000 230319310 95654136 760807424 0.0477314405 -0.0176751129 0.0057829386 632 1311867739.7001221180 0.0149222789 0.0095961169 0.0343401544 0.0048318165 0.0227020000 230322926 95654136 760807424 0.0488054529 -0.0165978279 0.0055139358 633 1311867739.7323939800 0.0176989399 0.0096089176 0.0343401544 0.0048327364 0.0265020000 230326398 95654136 760807424 0.0502457507 -0.0138878878 0.0050517246 634 1311867739.7662999630 0.0167596955 0.0096201964 0.0343401544 0.0048311521 0.0227230000 230328326 95654136 760807424 0.0487590171 -0.0148580736 0.0062402156 635 1311867739.8016180992 0.0159015264 0.0096300882 0.0343401544 0.0048277996 0.0226470000 230331910 95654136 760807424 0.0479179621 -0.0162056461 0.0073058270 636 1311867739.8325679302 0.0171993617 0.0096419896 0.0343401544 0.0048337382 0.0226230000 230333726 95654136 760807424 0.0464870222 -0.0142686581 0.0070548858 637 1311867739.8701560497 0.0170884505 0.0096536795 0.0343401544 0.0048306340 0.0226520000 230337310 95654136 760807424 0.0452457331 -0.0144622885 0.0069976468 638 1311867739.9036860466 0.0144598531 0.0096612127 0.0343401544 0.0048274109 0.0226140000 230341094 95654136 760807424 0.0431347750 -0.0184454396 0.0087539004 639 1311867739.9317240715 0.0152567253 0.0096699694 0.0343401544 0.0048241832 0.0226180000 230342654 95654136 760807424 0.0428831354 -0.0173924658 0.0080340747 640 1311867739.9668979645 0.0188454054 0.0096843060 0.0343401544 0.0048205919 0.0226250000 230346382 95654136 760807424 0.0449389406 -0.0134974075 0.0062751044 641 1311867739.9987080097 0.0150267230 0.0096926405 0.0343401544 0.0048193597 0.0225970000 230349910 95654136 760807424 0.0413354561 -0.0177040081 0.0074894028 642 1311867740.0328791142 0.0149525758 0.0097008335 0.0343401544 0.0048187996 0.0322020000 230351838 95654136 760807424 0.0388465784 -0.0184492934 0.0086644404 643 1311867740.0671849251 0.0173449777 0.0097127218 0.0343401544 0.0048175642 0.0231820000 230355310 95654136 760807424 0.0399034545 -0.0151870660 0.0069653797 644 1311867740.0992529392 0.0136539303 0.0097188417 0.0343401544 0.0048292346 0.0263160000 230528134 95654136 760807424 0.0389410742 -0.0188670028 0.0058165994 645 1311867740.1347720623 0.0120446729 0.0097224476 0.0343401544 0.0048262567 0.0227050000 230531606 95654136 760807424 0.0388790742 -0.0226083826 0.0080803623 646 1311867740.1666491032 0.0149254045 0.0097305017 0.0343401544 0.0048288029 0.0226160000 230535334 95654136 760807424 0.0400282629 -0.0185286105 0.0065004127 647 1311867740.1993310452 0.0163150504 0.0097406788 0.0343401544 0.0048267962 0.0226190000 230537062 95654136 760807424 0.0382577628 -0.0166086499 0.0060111769 648 1311867740.2383539677 0.0152544016 0.0097491876 0.0343401544 0.0048234861 0.0225710000 230540958 95654136 760807424 0.0374473296 -0.0189822614 0.0076352502 649 1311867740.2664349079 0.0158497225 0.0097585875 0.0343401544 0.0048219487 0.0226130000 230542462 95654136 760807424 0.0375368111 -0.0176436752 0.0062656547 650 1311867740.2981588840 0.0171028189 0.0097698863 0.0343401544 0.0048187225 0.0315190000 230546134 95654136 760807424 0.0382480249 -0.0156535991 0.0051239906 651 1311867740.3347120285 0.0163939893 0.0097800616 0.0343401544 0.0048154903 0.0228970000 230549774 95654136 760807424 0.0361381322 -0.0167772882 0.0061768647 652 1311867740.3665161133 0.0151429819 0.0097882869 0.0343401544 0.0048132492 0.0227230000 230551590 95654136 760807424 0.0342597663 -0.0182188489 0.0062757242 653 1311867740.3993780613 0.0152252782 0.0097966131 0.0343401544 0.0048108075 0.0226080000 230555062 95654136 760807424 0.0342581719 -0.0180879347 0.0062436052 654 1311867740.4346680641 0.0142354285 0.0098034003 0.0343401544 0.0048103027 0.0226400000 230557046 95654136 760807424 0.0348203480 -0.0186574962 0.0050449185 655 1311867740.4664289951 0.0152751775 0.0098117541 0.0343401544 0.0048095325 0.0226090000 230560518 95654136 760807424 0.0338079631 -0.0175797418 0.0046597822 656 1311867740.4993040562 0.0159080029 0.0098210472 0.0343401544 0.0048111929 0.0229720000 230564190 95654136 760807424 0.0338787809 -0.0171952248 0.0042323582 657 1311867740.5354259014 0.0145661300 0.0098282696 0.0343401544 0.0048151442 0.0226180000 230565974 95654136 760807424 0.0356152281 -0.0179794524 0.0020353058 658 1311867740.5666589737 0.0140145086 0.0098346316 0.0343401544 0.0048117005 0.0311290000 230569646 95654136 760807424 0.0342413262 -0.0187293887 0.0021921035 659 1311867740.6008880138 0.0148995267 0.0098423174 0.0343401544 0.0048087839 0.0229570000 230573174 95654136 760807424 0.0345735811 -0.0172401033 0.0005033215 660 1311867740.6346809864 0.0153011475 0.0098505883 0.0343401544 0.0048115589 0.0226390000 230575102 95654136 760807424 0.0348362178 -0.0168702565 0.0005924472 661 1311867740.6665890217 0.0152553609 0.0098587650 0.0343401544 0.0048097065 0.0225870000 230578574 95654136 760807424 0.0325509422 -0.0177779291 0.0015191018 662 1311867740.6994900703 0.0141884172 0.0098653052 0.0343401544 0.0048119485 0.0227860000 230580446 95654136 760807424 0.0319965407 -0.0193189066 0.0007765238 663 1311867740.7368240356 0.0117858984 0.0098682020 0.0343401544 0.0048167571 0.0225600000 230583918 95654136 760807424 0.0328091383 -0.0217059907 -0.0002642663 664 1311867740.7668819427 0.0113300811 0.0098704037 0.0343401544 0.0048135470 0.0221520000 230587534 95654136 760807424 0.0339271873 -0.0214646310 -0.0021460615 665 1311867740.7996399403 0.0121499430 0.0098738316 0.0343401544 0.0048099654 0.0220190000 230589262 95654136 760807424 0.0339348093 -0.0212661345 -0.0020314276 666 1311867740.8349099159 0.0133370198 0.0098790315 0.0343401544 0.0048069554 0.0254980000 230592934 95654136 760807424 0.0345563926 -0.0195240323 -0.0030882154 667 1311867740.8668210506 0.0135274185 0.0098845014 0.0343401544 0.0048048724 0.0225510000 230594662 95654136 760807424 0.0359084457 -0.0191922709 -0.0048698266 668 1311867740.8993830681 0.0131364241 0.0098893695 0.0343401544 0.0048034120 0.0224160000 230598334 95654136 760807424 0.0337290019 -0.0207993556 -0.0028215807 669 1311867740.9399120808 0.0155026801 0.0098977601 0.0343401544 0.0048082150 0.0225870000 230772802 95654136 760807424 0.0333721265 -0.0175030846 -0.0043195528 670 1311867740.9665501118 0.0162745882 0.0099072778 0.0343401544 0.0048046569 0.0221130000 230774506 95654136 760807424 0.0340914838 -0.0167856179 -0.0051956694 671 1311867741.0021579266 0.0137880975 0.0099130614 0.0343401544 0.0048021119 0.0221400000 230778090 95654136 760807424 0.0305107310 -0.0205635782 -0.0037461966 672 1311867741.0367169380 0.0138821881 0.0099189679 0.0343401544 0.0047993930 0.0224320000 230780018 95654136 760807424 0.0298098065 -0.0203057285 -0.0043794783 673 1311867741.0666699409 0.0176172201 0.0099304066 0.0343401544 0.0048000413 0.0225060000 230783434 95654136 760807424 0.0312728360 -0.0153386891 -0.0064706341 674 1311867741.1009640694 0.0144752478 0.0099371497 0.0343401544 0.0048061080 0.0225260000 230787162 95654136 760807424 0.0291322544 -0.0193716343 -0.0060506859 675 1311867741.1357901096 0.0144776218 0.0099438763 0.0343401544 0.0048039008 0.0257500000 230788890 95654136 760807424 0.0270508714 -0.0207439866 -0.0047314940 676 1311867741.1675300598 0.0145168733 0.0099506411 0.0343401544 0.0048007343 0.0226250000 230792618 95654136 760807424 0.0287075173 -0.0197141003 -0.0069096573 677 1311867741.2014830112 0.0154407686 0.0099587506 0.0343401544 0.0048023386 0.0225200000 230796090 95654136 760807424 0.0308022704 -0.0187361985 -0.0088741388 678 1311867741.2411060333 0.0120664313 0.0099618592 0.0343401544 0.0048062184 0.0220890000 230798186 95654136 760807424 0.0298708715 -0.0230365284 -0.0086038038 679 1311867741.2668209076 0.0115695056 0.0099642269 0.0343401544 0.0048059909 0.0261280000 230801490 95654136 760807424 0.0298857391 -0.0233915094 -0.0097330585 680 1311867741.2997009754 0.0140784401 0.0099702772 0.0343401544 0.0048055198 0.0221630000 230803362 95654136 760807424 0.0302309804 -0.0203978773 -0.0107303206 681 1311867741.3348419666 0.0131315785 0.0099749194 0.0343401544 0.0048022727 0.0219860000 230806946 95654136 760807424 0.0302947350 -0.0210893657 -0.0115940589 682 1311867741.3701419830 0.0161301773 0.0099839447 0.0343401544 0.0048024821 0.0220100000 230810674 95654136 760807424 0.0306592900 -0.0173113029 -0.0120620700 683 1311867741.4066278934 0.0169342514 0.0099941208 0.0343401544 0.0048014915 0.0220740000 230812514 95654136 760807424 0.0319458134 -0.0157271661 -0.0137781324 684 1311867741.4393060207 0.0165647939 0.0100037271 0.0343401544 0.0047991117 0.0261480000 230816242 95654136 760807424 0.0310621969 -0.0159906596 -0.0125494860 685 1311867741.4667329788 0.0163814351 0.0100130376 0.0343401544 0.0047964700 0.0221130000 230817746 95654136 760807424 0.0299220625 -0.0155837806 -0.0135197323 686 1311867741.5025069714 0.0154631268 0.0100209823 0.0343401544 0.0047943481 0.0219830000 230821530 95654136 760807424 0.0300753210 -0.0160350446 -0.0145395165 687 1311867741.5368049145 0.0147255929 0.0100278304 0.0343401544 0.0047911199 0.0219770000 230825058 95654136 760807424 0.0305043552 -0.0171990711 -0.0132432431 688 1311867741.5688209534 0.0155154187 0.0100358065 0.0343401544 0.0047892742 0.0255670000 230826930 95654136 760807424 0.0318715461 -0.0160021596 -0.0136903338 689 1311867741.6046030521 0.0175177623 0.0100466657 0.0343401544 0.0047957113 0.0219940000 230830458 95654136 760807424 0.0333109610 -0.0140425656 -0.0145172635 690 1311867741.6355440617 0.0161293466 0.0100554811 0.0343401544 0.0047928649 0.0220260000 230832330 95654136 760807424 0.0336400382 -0.0155100431 -0.0143751884 691 1311867741.6679561138 0.0176620819 0.0100664893 0.0343401544 0.0047903565 0.0219870000 230835858 95654136 760807424 0.0345287472 -0.0139198285 -0.0144700948 692 1311867741.7048020363 0.0171158779 0.0100766762 0.0343401544 0.0047918421 0.0220300000 231010154 95654136 760807424 0.0363338664 -0.0141500412 -0.0154621825 693 1311867741.7345991135 0.0160282366 0.0100852643 0.0343401544 0.0047936125 0.0261400000 231011714 95654136 760807424 0.0348502919 -0.0153705142 -0.0151746897 694 1311867741.7702169418 0.0155179929 0.0100930925 0.0343401544 0.0047905815 0.0220950000 231015498 95654136 760807424 0.0344575159 -0.0163759608 -0.0145059992 695 1311867741.8058650494 0.0165196415 0.0101023393 0.0343401544 0.0047882681 0.0218940000 231019082 95654136 760807424 0.0345333554 -0.0153650306 -0.0148220826 696 1311867741.8388509750 0.0167497993 0.0101118903 0.0343401544 0.0047858594 0.0220460000 231021066 95654136 760807424 0.0364704877 -0.0149264373 -0.0160370227 697 1311867741.8683021069 0.0167949628 0.0101214786 0.0343401544 0.0047845107 0.0220260000 231024426 95654136 760807424 0.0379396752 -0.0144689772 -0.0169932712 698 1311867741.9065721035 0.0142496703 0.0101273929 0.0343401544 0.0047823420 0.0224340000 231026466 95654136 760807424 0.0371990949 -0.0173299890 -0.0167115983 699 1311867741.9387769699 0.0147602661 0.0101340208 0.0343401544 0.0047795114 0.0220350000 231029994 95654136 760807424 0.0382425748 -0.0164019242 -0.0180011746 700 1311867741.9665379524 0.0156142749 0.0101418497 0.0343401544 0.0047783523 0.0219730000 231033498 95654136 760807424 0.0419964083 -0.0154805677 -0.0190989915 701 1311867742.0029959679 0.0160714835 0.0101503085 0.0343401544 0.0047756921 0.0219450000 231035282 95654136 760807424 0.0417983383 -0.0152594578 -0.0181752946 702 1311867742.0344839096 0.0153551716 0.0101577229 0.0343401544 0.0047726374 0.0247030000 231038898 95654136 760807424 0.0429070890 -0.0158540588 -0.0190128125 703 1311867742.0674400330 0.0164369736 0.0101666549 0.0343401544 0.0047702380 0.0220090000 231040570 95654136 760807424 0.0435547456 -0.0145380059 -0.0195090398 704 1311867742.1030650139 0.0174282938 0.0101769698 0.0343401544 0.0047671882 0.0220170000 231044298 95654136 760807424 0.0451520979 -0.0130540896 -0.0203391574 705 1311867742.1348879337 0.0178255681 0.0101878188 0.0343401544 0.0047649876 0.0219000000 231047714 95654136 760807424 0.0447569564 -0.0125550423 -0.0201369226 706 1311867742.1672229767 0.0151310414 0.0101948206 0.0343401544 0.0047623492 0.0257490000 231049642 95654136 760807424 0.0455861166 -0.0153282760 -0.0202395972 707 1311867742.2028279305 0.0151884938 0.0102018838 0.0343401544 0.0047606741 0.0219650000 231053282 95654136 760807424 0.0482304059 -0.0150386300 -0.0211493969 708 1311867742.2362670898 0.0145208556 0.0102079840 0.0343401544 0.0047587783 0.0253000000 231055154 95654136 760807424 0.0495216213 -0.0155095700 -0.0221945476 709 1311867742.2674059868 0.0143572418 0.0102138363 0.0343401544 0.0047571208 0.0219990000 231058626 95654136 760807424 0.0493472442 -0.0159056317 -0.0218448061 710 1311867742.3028159142 0.0141107291 0.0102193249 0.0343401544 0.0047568474 0.0218970000 231062410 95654136 760807424 0.0490890890 -0.0167257749 -0.0214659646 711 1311867742.3350739479 0.0149718234 0.0102260091 0.0343401544 0.0047551153 0.0218650000 231064026 95654136 760807424 0.0492206141 -0.0155280698 -0.0222126488 712 1311867742.3694241047 0.0149320122 0.0102326187 0.0343401544 0.0047517851 0.0220080000 231067810 95654136 760807424 0.0494398102 -0.0158745404 -0.0222406518 713 1311867742.4062991142 0.0140560437 0.0102379811 0.0343401544 0.0047486007 0.0218850000 231071394 95654136 760807424 0.0500332266 -0.0169131067 -0.0226170737 714 1311867742.4346439838 0.0155260963 0.0102453874 0.0343401544 0.0047466370 0.0219110000 231073154 95654136 760807424 0.0514398552 -0.0154539403 -0.0230501536 715 1311867742.4666969776 0.0155457323 0.0102528005 0.0343401544 0.0047445971 0.0258840000 231076626 95654136 760807424 0.0519030392 -0.0151617760 -0.0241778363 716 1311867742.5047059059 0.0159063470 0.0102606965 0.0343401544 0.0047429772 0.0219590000 231078610 95654136 760807424 0.0513244681 -0.0150403902 -0.0234574117 717 1311867742.5359389782 0.0170907155 0.0102702223 0.0343401544 0.0047411918 0.0218450000 231082082 95654136 760807424 0.0519259386 -0.0130600072 -0.0250541959 718 1311867742.5678529739 0.0175456125 0.0102803552 0.0343401544 0.0047382070 0.0218670000 231085810 95654136 760807424 0.0524887405 -0.0125823738 -0.0248853620 719 1311867742.6054639816 0.0173112415 0.0102901339 0.0343401544 0.0047350238 0.0219090000 231087594 95654136 760807424 0.0526080653 -0.0130062727 -0.0244757719 720 1311867742.6347279549 0.0165511630 0.0102988298 0.0343401544 0.0047326210 0.0328560000 231261374 95654136 760807424 0.0534919389 -0.0137196677 -0.0252446886 721 1311867742.6724960804 0.0173920877 0.0103086679 0.0343401544 0.0047299563 0.0225510000 231263270 95654136 760807424 0.0540479757 -0.0131269693 -0.0246097129 722 1311867742.7046229839 0.0170693528 0.0103180317 0.0343401544 0.0047269458 0.0219760000 231266886 95654136 760807424 0.0537220873 -0.0135356430 -0.0249281228 723 1311867742.7356119156 0.0167070366 0.0103268685 0.0343401544 0.0047241998 0.0219140000 231270358 95654136 760807424 0.0542034507 -0.0138856973 -0.0255266652 724 1311867742.7726070881 0.0166730508 0.0103356339 0.0343401544 0.0047217441 0.0218850000 231272398 95654136 760807424 0.0535563342 -0.0141588049 -0.0254539736 725 1311867742.8034689426 0.0170237496 0.0103448589 0.0343401544 0.0047238659 0.0242870000 231275870 95654136 760807424 0.0546707399 -0.0139269466 -0.0261901785 726 1311867742.8352251053 0.0163444430 0.0103531228 0.0343401544 0.0047235747 0.0222220000 231279286 95654136 760807424 0.0544292592 -0.0146565009 -0.0264766961 727 1311867742.8705639839 0.0178318303 0.0103634099 0.0343401544 0.0047232831 0.0250660000 231281214 95654136 760807424 0.0566111356 -0.0135728894 -0.0265618544 728 1311867742.9046700001 0.0160486475 0.0103712193 0.0343401544 0.0047235347 0.0256720000 231284742 95654136 760807424 0.0552862920 -0.0153657384 -0.0265431479 729 1311867742.9382069111 0.0165564697 0.0103797038 0.0343401544 0.0047536877 0.0218940000 231286726 95654136 760807424 0.0584686026 -0.0147665963 -0.0289612878 730 1311867742.9707310200 0.0165041480 0.0103880935 0.0343401544 0.0047610264 0.0218610000 231290198 95654136 760807424 0.0576935709 -0.0149984471 -0.0275865104 731 1311867743.0024189949 0.0183428023 0.0103989754 0.0343401544 0.0047629183 0.0218510000 231293814 95654136 760807424 0.0581895858 -0.0127523011 -0.0287142899 732 1311867743.0345149040 0.0176356323 0.0104088616 0.0343401544 0.0047676180 0.0218940000 231295486 95654136 760807424 0.0577327386 -0.0132788764 -0.0283077285 733 1311867743.0722420216 0.0175042562 0.0104185415 0.0343401544 0.0047654942 0.0218800000 231299326 95654136 760807424 0.0588837527 -0.0138968443 -0.0281793159 734 1311867743.1045989990 0.0183674134 0.0104293711 0.0343401544 0.0047631407 0.0218600000 231300998 95654136 760807424 0.0595855303 -0.0129928691 -0.0289077535 735 1311867743.1350400448 0.0183012448 0.0104400811 0.0343401544 0.0047633545 0.0218550000 231304614 95654136 760807424 0.0579721592 -0.0128070368 -0.0285269059 736 1311867743.1704380512 0.0173969548 0.0104495334 0.0343401544 0.0047649868 0.0218640000 231308142 95654136 760807424 0.0582641736 -0.0139722647 -0.0288655832 737 1311867743.2037980556 0.0183537528 0.0104602582 0.0343401544 0.0047643571 0.0314950000 231310070 95654136 760807424 0.0595761687 -0.0126874493 -0.0298718214 738 1311867743.2358140945 0.0169606470 0.0104690663 0.0343401544 0.0047623656 0.0226150000 231313486 95654136 760807424 0.0597800352 -0.0143679455 -0.0294461939 739 1311867743.2708129883 0.0171604939 0.0104781210 0.0343401544 0.0047629086 0.0227810000 231315470 95654136 760807424 0.0601688772 -0.0139388032 -0.0298303831 740 1311867743.3032529354 0.0196167734 0.0104904706 0.0343401544 0.0047748505 0.0219540000 231318942 95654136 760807424 0.0619758554 -0.0118153561 -0.0298066810 741 1311867743.3363931179 0.0185434520 0.0105013383 0.0343401544 0.0047721672 0.0219870000 231322614 95654136 760807424 0.0627449676 -0.0131265679 -0.0295841545 742 1311867743.3707330227 0.0185007099 0.0105121191 0.0343401544 0.0047707911 0.0257730000 231324342 95654136 760807424 0.0621399060 -0.0127290571 -0.0299633183 743 1311867743.4043838978 0.0185941290 0.0105229967 0.0343401544 0.0047681640 0.0219530000 231328070 95654136 760807424 0.0631339848 -0.0128922854 -0.0304208361 744 1311867743.4352641106 0.0165163353 0.0105310522 0.0343401544 0.0047708988 0.0221470000 231501826 95654136 760807424 0.0628495291 -0.0154877817 -0.0298498739 745 1311867743.4768960476 0.0169682465 0.0105396927 0.0343401544 0.0047709522 0.0218670000 231503922 95654136 760807424 0.0624352507 -0.0148469834 -0.0297352821 746 1311867743.5035250187 0.0185139962 0.0105503822 0.0343401544 0.0047695600 0.0322010000 231507282 95654136 760807424 0.0620442815 -0.0124568921 -0.0306858327 747 1311867743.5389750004 0.0175157022 0.0105597066 0.0343401544 0.0047701402 0.0223990000 231509210 95654136 760807424 0.0623741001 -0.0138875609 -0.0304476228 748 1311867743.5749680996 0.0163492151 0.0105674465 0.0343401544 0.0047698573 0.0218990000 231512794 95654136 760807424 0.0626429543 -0.0147827221 -0.0310360435 749 1311867743.6036109924 0.0185983889 0.0105781688 0.0343401544 0.0047822023 0.0258000000 231516354 95654136 760807424 0.0612604730 -0.0118089188 -0.0309980307 750 1311867743.6354589462 0.0175121929 0.0105874141 0.0343401544 0.0047858438 0.0256900000 231518026 95654136 760807424 0.0629826188 -0.0138410814 -0.0312126875 751 1311867743.6759150028 0.0152996155 0.0105936887 0.0343401544 0.0047829954 0.0218840000 231521922 95654136 760807424 0.0619236976 -0.0165360607 -0.0304238796 752 1311867743.7034959793 0.0166251659 0.0106017093 0.0343401544 0.0047826619 0.0253470000 231523482 95654136 760807424 0.0612224527 -0.0150236804 -0.0303792283 753 1311867743.7388861179 0.0172687955 0.0106105633 0.0343401544 0.0047801736 0.0220820000 231527266 95654136 760807424 0.0604977198 -0.0144031523 -0.0306494534 754 1311867743.7733619213 0.0159204900 0.0106176056 0.0343401544 0.0047784681 0.0246710000 231530850 95654136 760807424 0.0601832010 -0.0158743374 -0.0314351134 755 1311867743.8064749241 0.0179638378 0.0106273358 0.0343401544 0.0047775860 0.0219440000 231532666 95654136 760807424 0.0626755506 -0.0144030610 -0.0327846296 756 1311867743.8391659260 0.0174527839 0.0106363641 0.0343401544 0.0047783844 0.0219560000 231536138 95654136 760807424 0.0601558834 -0.0150226168 -0.0318512507 757 1311867743.8726658821 0.0161495227 0.0106436470 0.0343401544 0.0047756939 0.0251590000 231538122 95654136 760807424 0.0582272522 -0.0161766447 -0.0322172642 758 1311867743.9031310081 0.0171554144 0.0106522378 0.0343401544 0.0047726277 0.0220100000 231541538 95654136 760807424 0.0591561757 -0.0150315138 -0.0333571024 759 1311867743.9453630447 0.0168707669 0.0106604308 0.0343401544 0.0047702630 0.0218560000 231545490 95654136 760807424 0.0577799827 -0.0158461053 -0.0325690880 760 1311867743.9741249084 0.0172731858 0.0106691318 0.0343401544 0.0047695624 0.0218500000 231547050 95654136 760807424 0.0579625033 -0.0152024310 -0.0330005065 761 1311867744.0042529106 0.0200144518 0.0106814121 0.0343401544 0.0047693339 0.0218860000 231550610 95654136 760807424 0.0597885288 -0.0116683971 -0.0356273465 762 1311867744.0407259464 0.0183600448 0.0106914891 0.0343401544 0.0047689379 0.0311150000 231554250 95654136 760807424 0.0584663004 -0.0134897493 -0.0343516469 763 1311867744.0716118813 0.0207062997 0.0107046146 0.0343401544 0.0047687928 0.0223420000 231556050 95654136 760807424 0.0613650978 -0.0113365753 -0.0357737616 764 1311867744.1111290455 0.0203500763 0.0107172396 0.0343401544 0.0047670663 0.0222300000 231559578 95654136 760807424 0.0603214949 -0.0116448505 -0.0344478451 765 1311867744.1412119865 0.0208700486 0.0107305112 0.0343401544 0.0047639818 0.0219230000 231561410 95654136 760807424 0.0605656654 -0.0106450217 -0.0351919308 766 1311867744.1734991074 0.0208957773 0.0107437818 0.0343401544 0.0047612892 0.0225340000 231564858 95654136 760807424 0.0609820411 -0.0101768868 -0.0360275134 767 1311867744.2046771049 0.0190742929 0.0107546430 0.0343401544 0.0047623633 0.0218920000 231568474 95654136 760807424 0.0586787760 -0.0119460048 -0.0343673639 768 1311867744.2400228977 0.0179266054 0.0107639815 0.0343401544 0.0047615705 0.0254410000 231570314 95654136 760807424 0.0604357868 -0.0138977831 -0.0333460979 769 1311867744.2773048878 0.0201841984 0.0107762314 0.0343401544 0.0047606800 0.0216900000 231574098 95654136 760807424 0.0605769791 -0.0106240921 -0.0347320288 770 1311867744.3032519817 0.0188161060 0.0107866728 0.0343401544 0.0047587695 0.0216560000 231575682 95654136 760807424 0.0586492494 -0.0122018037 -0.0328142196 771 1311867744.3391230106 0.0150850546 0.0107922479 0.0343401544 0.0047653301 0.0319300000 231579466 95654136 760807424 0.0585967302 -0.0163263325 -0.0328666829 772 1311867744.3707659245 0.0186605006 0.0108024399 0.0343401544 0.0047649705 0.0224330000 231582882 95654136 760807424 0.0596742071 -0.0119827725 -0.0335038863 773 1311867744.4027431011 0.0177084096 0.0108113739 0.0343401544 0.0047647519 0.0220430000 231584810 95654136 760807424 0.0593548343 -0.0125646796 -0.0340632349 774 1311867744.4383800030 0.0152038634 0.0108170490 0.0343401544 0.0047630009 0.0217630000 231588338 95654136 760807424 0.0585642643 -0.0153611600 -0.0339418724 775 1311867744.4717690945 0.0179995950 0.0108263168 0.0343401544 0.0047663793 0.0219320000 231590266 95654136 760807424 0.0588680506 -0.0130978599 -0.0322274901 776 1311867744.5026860237 0.0201542433 0.0108383373 0.0343401544 0.0047636204 0.0217240000 231593738 95654136 760807424 0.0597975515 -0.0101319971 -0.0335493460 777 1311867744.5383169651 0.0175223388 0.0108469396 0.0343401544 0.0047661186 0.0219370000 231597522 95654136 760807424 0.0591849014 -0.0125940936 -0.0344451703 778 1311867744.5726189613 0.0168462973 0.0108546509 0.0343401544 0.0047632084 0.0216660000 231599250 95654136 760807424 0.0584041812 -0.0137208449 -0.0336214416 779 1311867744.6028740406 0.0171396602 0.0108627189 0.0343401544 0.0047634328 0.0315860000 231602866 95654136 760807424 0.0585217588 -0.0128592430 -0.0345021226 780 1311867744.6386809349 0.0176658388 0.0108714409 0.0343401544 0.0047652282 0.0223450000 231606450 95654136 760807424 0.0607151538 -0.0129578579 -0.0344688259 781 1311867744.6707758904 0.0195075814 0.0108824987 0.0343401544 0.0047634273 0.0260830000 231608322 95654136 760807424 0.0590524375 -0.0102496194 -0.0348245949 782 1311867744.7029349804 0.0168087464 0.0108900770 0.0343401544 0.0047683741 0.0218500000 231611794 95654136 760807424 0.0615586974 -0.0131067149 -0.0358960256 783 1311867744.7396171093 0.0195921604 0.0109011908 0.0343401544 0.0047759288 0.0222490000 231613778 95654136 760807424 0.0604678169 -0.0102273170 -0.0346455649 784 1311867744.7705199718 0.0188398287 0.0109113166 0.0343401544 0.0047747403 0.0334310000 231617194 95654136 760807424 0.0593863502 -0.0108141946 -0.0347257555 785 1311867744.8035891056 0.0179182999 0.0109202427 0.0343401544 0.0047736905 0.0225330000 231620922 95654136 760807424 0.0589938015 -0.0128442962 -0.0327572189 786 1311867744.8424170017 0.0166064240 0.0109274770 0.0343401544 0.0047710009 0.0220020000 231622762 95654136 760807424 0.0596931614 -0.0144936256 -0.0332375057 787 1311867744.8727390766 0.0174176414 0.0109357237 0.0343401544 0.0047696844 0.0307040000 231626434 95654136 760807424 0.0601087101 -0.0127128521 -0.0361126177 788 1311867744.9029939175 0.0167746618 0.0109431335 0.0343401544 0.0047668776 0.0224640000 231628050 95654136 760807424 0.0591624044 -0.0151555352 -0.0334435850 789 1311867744.9392940998 0.0168077424 0.0109505665 0.0343401544 0.0047708604 0.0220770000 231631890 95654136 760807424 0.0595136136 -0.0136649543 -0.0362302884 790 1311867744.9708900452 0.0174582228 0.0109588040 0.0343401544 0.0047728418 0.0252030000 231635250 95654136 760807424 0.0618525892 -0.0135036632 -0.0374557935 791 1311867745.0027489662 0.0169534367 0.0109663826 0.0343401544 0.0047743828 0.0221560000 231637122 95654136 760807424 0.0612191819 -0.0137102697 -0.0382291637 792 1311867745.0384869576 0.0176224411 0.0109747867 0.0343401544 0.0047747328 0.0257560000 231640706 95654136 760807424 0.0609724894 -0.0134547474 -0.0380771682 793 1311867745.0729780197 0.0181151126 0.0109837909 0.0343401544 0.0047726974 0.0256130000 231642634 95654136 760807424 0.0602231286 -0.0133405067 -0.0377546810 794 1311867745.1118760109 0.0185074955 0.0109932666 0.0343401544 0.0047756666 0.0217950000 231646274 95654136 760807424 0.0619153231 -0.0134805925 -0.0379050896 795 1311867745.1405589581 0.0172215234 0.0110011009 0.0343401544 0.0047750046 0.0244390000 231649834 95654136 760807424 0.0609282218 -0.0140114827 -0.0393799953 796 1311867745.1729030609 0.0168529283 0.0110084524 0.0343401544 0.0047722389 0.0220380000 231651506 95654136 760807424 0.0603739396 -0.0145360446 -0.0391481481 797 1311867745.2068369389 0.0172400698 0.0110162713 0.0343401544 0.0047698146 0.0221300000 231655234 95654136 760807424 0.0604232401 -0.0147288665 -0.0383617729 798 1311867745.2430789471 0.0174243748 0.0110243015 0.0343401544 0.0047672201 0.0220320000 231658818 95654136 760807424 0.0622659363 -0.0141112776 -0.0405964740 799 1311867745.2729060650 0.0195033941 0.0110349136 0.0343401544 0.0047702866 0.0220520000 231660634 95654136 760807424 0.0610107295 -0.0117833372 -0.0396062061 800 1311867745.3112850189 0.0170791652 0.0110424689 0.0343401544 0.0047705799 0.0220890000 231664218 95654136 760807424 0.0614152364 -0.0146916099 -0.0399947315 801 1311867745.3395059109 0.0170136150 0.0110499235 0.0343401544 0.0047688184 0.0221200000 231666034 95654136 760807424 0.0596146733 -0.0143760405 -0.0403014235 802 1311867745.3733940125 0.0167857539 0.0110570754 0.0343401544 0.0047678532 0.0221010000 231669562 95654136 760807424 0.0616408512 -0.0148650613 -0.0413944349 803 1311867745.4102098942 0.0171425696 0.0110646539 0.0343401544 0.0047663001 0.0220200000 231673346 95654136 760807424 0.0623397976 -0.0144047691 -0.0425622575 804 1311867745.4433169365 0.0176766664 0.0110728778 0.0343401544 0.0047651052 0.0251460000 231675074 95654136 760807424 0.0615649335 -0.0141223585 -0.0415453650 805 1311867745.4708619118 0.0184960980 0.0110820992 0.0343401544 0.0047628685 0.0223920000 231678578 95654136 760807424 0.0610848404 -0.0128383720 -0.0421849787 806 1311867745.5099780560 0.0191355925 0.0110920911 0.0343401544 0.0047619227 0.0221630000 231680474 95654136 760807424 0.0618222766 -0.0120032150 -0.0431915857 807 1311867745.5417380333 0.0166422762 0.0110989686 0.0343401544 0.0047633796 0.0220910000 231684146 95654136 760807424 0.0616102815 -0.0149165755 -0.0435434021 808 1311867745.5704059601 0.0164385736 0.0111055771 0.0343401544 0.0047608453 0.0219750000 231687506 95654136 760807424 0.0613218397 -0.0154284742 -0.0439730212 809 1311867745.6133821011 0.0181230474 0.0111142513 0.0343401544 0.0047604719 0.0221230000 231689714 95654136 760807424 0.0606823675 -0.0142097156 -0.0438898727 810 1311867745.6438291073 0.0175777730 0.0111222310 0.0343401544 0.0047603176 0.0253890000 231863266 95654136 760807424 0.0603921786 -0.0145147331 -0.0449836589 811 1311867745.6709001064 0.0187340192 0.0111316167 0.0343401544 0.0047659047 0.0221350000 231864914 95654136 760807424 0.0600336939 -0.0128490617 -0.0459067635 812 1311867745.7088780403 0.0178819280 0.0111399298 0.0343401544 0.0047672984 0.0221050000 231868610 95654136 760807424 0.0619597957 -0.0135075925 -0.0478882529 813 1311867745.7423269749 0.0190544948 0.0111496649 0.0343401544 0.0047685008 0.0276560000 231872282 95654136 760807424 0.0619114749 -0.0124033596 -0.0476606712 814 1311867745.7760419846 0.0173511300 0.0111572834 0.0343401544 0.0047723145 0.0222260000 231874010 95654136 760807424 0.0616942756 -0.0145002808 -0.0470877700 815 1311867745.8116889000 0.0187953021 0.0111666552 0.0343401544 0.0047784745 0.0221000000 231877794 95654136 760807424 0.0621450506 -0.0125990976 -0.0475539528 816 1311867745.8389890194 0.0180112608 0.0111750432 0.0343401544 0.0047778531 0.0221240000 231881154 95654136 760807424 0.0614406317 -0.0123884166 -0.0495014004 817 1311867745.8709759712 0.0181188639 0.0111835423 0.0343401544 0.0047767189 0.0252490000 231882970 95654136 760807424 0.0608201474 -0.0118731875 -0.0503770895 818 1311867745.9108459949 0.0199956447 0.0111943151 0.0343401544 0.0047749078 0.0228740000 231886666 95654136 760807424 0.0599524900 -0.0096036904 -0.0506287776 819 1311867745.9435789585 0.0194301065 0.0112043710 0.0343401544 0.0047782316 0.0259990000 231888594 95654136 760807424 0.0600783750 -0.0102845673 -0.0520938598 820 1311867745.9732220173 0.0177004114 0.0112122930 0.0343401544 0.0047757452 0.0220980000 231891954 95654136 760807424 0.0592641719 -0.0121007003 -0.0522790886 821 1311867746.0083909035 0.0175432079 0.0112200042 0.0343401544 0.0047746589 0.0250200000 231895682 95654136 760807424 0.0585658811 -0.0120600583 -0.0543400198 822 1311867746.0391409397 0.0162492897 0.0112261226 0.0343401544 0.0047730053 0.0220170000 231897410 95654136 760807424 0.0578170195 -0.0135375820 -0.0550977625 823 1311867746.0728518963 0.0176966954 0.0112339847 0.0343401544 0.0047708808 0.0257010000 231901082 95654136 760807424 0.0591037720 -0.0119911116 -0.0569115654 824 1311867746.1113359928 0.0209158603 0.0112457346 0.0343401544 0.0047693201 0.0220340000 231902866 95654136 760807424 0.0582142174 -0.0087309219 -0.0571726076 825 1311867746.1412689686 0.0182266850 0.0112541963 0.0343401544 0.0047730441 0.0220340000 231906538 95654136 760807424 0.0597445294 -0.0117290812 -0.0597464964 826 1311867746.1721889973 0.0197791848 0.0112645172 0.0343401544 0.0047728462 0.0220480000 231909954 95654136 760807424 0.0589097030 -0.0101943724 -0.0604657643 827 1311867746.2066209316 0.0248304699 0.0112809210 0.0343401544 0.0047715856 0.0218650000 231911882 95654136 760807424 0.0592772886 -0.0053309095 -0.0633750856 828 1311867746.2386920452 0.0227334965 0.0112947526 0.0343401544 0.0047695809 0.0251940000 231915410 95654136 760807424 0.0580911487 -0.0077591622 -0.0629017577 829 1311867746.2704648972 0.0216359235 0.0113072269 0.0343401544 0.0047677759 0.0219670000 231917282 95654136 760807424 0.0563171916 -0.0095218765 -0.0642216876 830 1311867746.3068819046 0.0255593676 0.0113243981 0.0343401544 0.0047710917 0.0253320000 231920810 95654136 760807424 0.0594729185 -0.0068328986 -0.0686614141 831 1311867746.3393440247 0.0301155765 0.0113470108 0.0343401544 0.0047704572 0.0255090000 231924538 95654136 760807424 0.0607044660 -0.0020623724 -0.0677486211 832 1311867746.3797800541 0.0306751318 0.0113702418 0.0343401544 0.0047714142 0.0219580000 232096562 95654136 760807424 0.0634461865 -0.0019288728 -0.0639163107 833 1311867746.4078478813 0.0314156786 0.0113943059 0.0343401544 0.0047712026 0.0217330000 232100122 95654136 760807424 0.0663418993 -0.0021733823 -0.0658748671 834 1311867746.4389901161 0.0358134955 0.0114235855 0.0358134955 0.0047687980 0.0220040000 232103538 95654136 760807424 0.0663888901 0.0018745731 -0.0680407435 835 1311867746.4774639606 0.0338995680 0.0114505029 0.0358134955 0.0047665985 0.0217580000 232105634 95654136 760807424 0.0676830485 -0.0002732507 -0.0650333241 836 1311867746.5066781044 0.0331664756 0.0114764789 0.0358134955 0.0047640556 0.0217120000 232108994 95654136 760807424 0.0675172731 -0.0009971464 -0.0655786246 837 1311867746.5406761169 0.0364193991 0.0115062793 0.0364193991 0.0047684794 0.0220460000 232110922 95654136 760807424 0.0679544285 0.0021171223 -0.0659194291 838 1311867746.5748629570 0.0373120606 0.0115370738 0.0373120606 0.0047656727 0.0222290000 232114506 95654136 760807424 0.0684654117 0.0027513956 -0.0656876042 839 1311867746.6067559719 0.0354691148 0.0115655982 0.0373120606 0.0047652933 0.0221830000 232118122 95654136 760807424 0.0687164217 0.0005283316 -0.0663881227 840 1311867746.6396849155 0.0355175957 0.0115941125 0.0373120606 0.0047682892 0.0216550000 232119906 95654136 760807424 0.0681924224 0.0006919196 -0.0669223741 841 1311867746.6749529839 0.0361452550 0.0116233053 0.0373120606 0.0047730322 0.0221370000 232123634 95654136 760807424 0.0676797703 0.0006714265 -0.0689347684 842 1311867746.7095060349 0.0330258422 0.0116487240 0.0373120606 0.0047759186 0.0256410000 232125362 95654136 760807424 0.0675629824 -0.0032955154 -0.0706239343 843 1311867746.7391049862 0.0325041935 0.0116734636 0.0373120606 0.0047826216 0.0222980000 232128922 95654136 760807424 0.0637244135 -0.0027450141 -0.0696177781 844 1311867746.7751340866 0.0333436206 0.0116991391 0.0373120606 0.0047815934 0.0216000000 232132562 95654136 760807424 0.0651122853 -0.0028042842 -0.0710581839 845 1311867746.8070099354 0.0303985830 0.0117212687 0.0373120606 0.0047792955 0.0219510000 232134434 95654136 760807424 0.0637795627 -0.0056155240 -0.0701573119 846 1311867746.8401610851 0.0310724322 0.0117441424 0.0373120606 0.0047771749 0.0216170000 232137906 95654136 760807424 0.0648701712 -0.0058584558 -0.0712495819 847 1311867746.8748359680 0.0282562450 0.0117636372 0.0373120606 0.0047823932 0.0219860000 232139890 95654136 760807424 0.0633018687 -0.0079751667 -0.0702060089 848 1311867746.9086029530 0.0333950110 0.0117891459 0.0373120606 0.0047858021 0.0258400000 232143362 95654136 760807424 0.0663447604 -0.0038394290 -0.0720431805 849 1311867746.9389610291 0.0323513113 0.0118133652 0.0373120606 0.0047849684 0.0217540000 232147034 95654136 760807424 0.0662204102 -0.0044085365 -0.0696551055 850 1311867746.9748229980 0.0289794672 0.0118335606 0.0373120606 0.0048058524 0.0217750000 232148818 95654136 760807424 0.0662789717 -0.0078945030 -0.0705572814 851 1311867747.0066559315 0.0315716378 0.0118567546 0.0373120606 0.0048103903 0.0217620000 232152434 95654136 760807424 0.0659716055 -0.0056652999 -0.0715368614 852 1311867747.0389339924 0.0291826576 0.0118770901 0.0373120606 0.0048075760 0.0216070000 232155906 95654136 760807424 0.0654127002 -0.0076277405 -0.0695955306 853 1311867747.0749640465 0.0295667481 0.0118978283 0.0373120606 0.0048059285 0.0219120000 232157946 95654136 760807424 0.0655370131 -0.0069915461 -0.0697191581 854 1311867747.1066820621 0.0309048649 0.0119200848 0.0373120606 0.0048136006 0.0216620000 232161362 95654136 760807424 0.0654519498 -0.0053053875 -0.0694718659 855 1311867747.1389479637 0.0337652639 0.0119456347 0.0373120606 0.0048149325 0.0216080000 232163234 95654136 760807424 0.0675620362 -0.0025536448 -0.0685062110 856 1311867747.1744880676 0.0333119370 0.0119705953 0.0373120606 0.0048128484 0.0215060000 232166818 95654136 760807424 0.0672468096 -0.0032225398 -0.0689783171 857 1311867747.2066030502 0.0270011257 0.0119881339 0.0373120606 0.0048258578 0.0252920000 232170490 95654136 760807424 0.0668838024 -0.0098087080 -0.0687995702 858 1311867747.2385439873 0.0321092382 0.0120115850 0.0373120606 0.0048255850 0.0215820000 232172218 95654136 760807424 0.0673054010 -0.0044655204 -0.0706570745 859 1311867747.2745490074 0.0320929922 0.0120349627 0.0373120606 0.0048456247 0.0217360000 232176002 95654136 760807424 0.0671931580 -0.0047353711 -0.0704275221 860 1311867747.3064720631 0.0317611210 0.0120579001 0.0373120606 0.0048511529 0.0215860000 232177562 95654136 760807424 0.0679289103 -0.0049801413 -0.0705447942 861 1311867747.3388469219 0.0307851173 0.0120796506 0.0373120606 0.0048537344 0.0225440000 232181346 95654136 760807424 0.0657476559 -0.0056620082 -0.0698903799 862 1311867747.3758800030 0.0310811084 0.0121016941 0.0373120606 0.0048559422 0.0217040000 232184874 95654136 760807424 0.0659826621 -0.0050431415 -0.0699079037 863 1311867747.4068729877 0.0317798555 0.0121244961 0.0373120606 0.0048548355 0.0216100000 232186746 95654136 760807424 0.0682590678 -0.0054709101 -0.0715052187 864 1311867747.4396450520 0.0327608697 0.0121483808 0.0373120606 0.0048580085 0.0216120000 232190162 95654136 760807424 0.0682080984 -0.0040217224 -0.0717482641 865 1311867747.4756069183 0.0301263761 0.0121691646 0.0373120606 0.0048626764 0.0215880000 232192146 95654136 760807424 0.0668928176 -0.0063108420 -0.0713885799 866 1311867747.5095520020 0.0289093088 0.0121884950 0.0373120606 0.0048635924 0.0252170000 232195730 95654136 760807424 0.0667552352 -0.0077428687 -0.0717660859 867 1311867747.5405330658 0.0315477550 0.0122108241 0.0373120606 0.0048735041 0.0216330000 232199346 95654136 760807424 0.0691252723 -0.0066903383 -0.0763624758 868 1311867747.5766739845 0.0322030187 0.0122338565 0.0373120606 0.0048851855 0.0219100000 232201130 95654136 760807424 0.0691444948 -0.0049900180 -0.0741715878 869 1311867747.6086390018 0.0327103026 0.0122574198 0.0373120606 0.0048829069 0.0215810000 232204802 95654136 760807424 0.0682355314 -0.0043030782 -0.0743524879 870 1311867747.6432039738 0.0314122513 0.0122794368 0.0373120606 0.0048831854 0.0216820000 232208386 95654136 760807424 0.0682490095 -0.0056231627 -0.0742630586 871 1311867747.6760280132 0.0324728005 0.0123026209 0.0373120606 0.0048849408 0.0218300000 232210258 95654136 760807424 0.0678053945 -0.0043462194 -0.0742009580 872 1311867747.7068400383 0.0313500389 0.0123244643 0.0373120606 0.0048827497 0.0215800000 232213674 95654136 760807424 0.0683443546 -0.0061266739 -0.0748058110 873 1311867747.7480750084 0.0330554806 0.0123482112 0.0373120606 0.0048977929 0.0220310000 232215938 95654136 760807424 0.0682237521 -0.0054930537 -0.0791518390 874 1311867747.7826869488 0.0330640562 0.0123719135 0.0373120606 0.0049173291 0.0223060000 232219466 95654136 760807424 0.0665614232 -0.0033368671 -0.0736582056 875 1311867747.8149020672 0.0296589509 0.0123916701 0.0373120606 0.0049409756 0.0318880000 232223138 95654136 760807424 0.0668440759 -0.0077693053 -0.0761362091 876 1311867747.8466539383 0.0340764336 0.0124164244 0.0373120606 0.0049413356 0.0220870000 232224754 95654136 760807424 0.0669088140 -0.0038376586 -0.0792207569 877 1311867747.8827810287 0.0311440621 0.0124377786 0.0373120606 0.0049415574 0.0222900000 232228594 95654136 760807424 0.0652626529 -0.0059143258 -0.0782409757 878 1311867747.9150440693 0.0320043676 0.0124600640 0.0373120606 0.0049412792 0.0256100000 232230322 95654136 760807424 0.0658758134 -0.0047698449 -0.0774267986 879 1311867747.9477820396 0.0331729390 0.0124836282 0.0373120606 0.0049438771 0.0216760000 232233994 95654136 760807424 0.0659159571 -0.0041342867 -0.0787755251 880 1311867747.9826579094 0.0319767594 0.0125057795 0.0373120606 0.0049418771 0.0218180000 232237522 95654136 760807424 0.0652255192 -0.0051912367 -0.0784308165 881 1311867748.0146598816 0.0333544351 0.0125294442 0.0373120606 0.0049400439 0.0218580000 232239394 95654136 760807424 0.0665556416 -0.0041959202 -0.0780648068 882 1311867748.0469269753 0.0329509713 0.0125525979 0.0373120606 0.0049403711 0.0258580000 232242866 95654136 760807424 0.0631816760 -0.0032661285 -0.0766789615 883 1311867748.0828750134 0.0337883160 0.0125766474 0.0373120606 0.0049417424 0.0304550000 232244906 95654136 760807424 0.0642656684 -0.0028428477 -0.0770278424 884 1311867748.1150569916 0.0318989754 0.0125985052 0.0373120606 0.0049415407 0.0220260000 232248322 95654136 760807424 0.0622369200 -0.0035178971 -0.0748058334 885 1311867748.1486010551 0.0319673792 0.0126203910 0.0373120606 0.0049477484 0.0216880000 232252050 95654136 760807424 0.0643790513 -0.0045643700 -0.0764264092 886 1311867748.1831040382 0.0319744088 0.0126422352 0.0373120606 0.0049588101 0.0218300000 232253722 95654136 760807424 0.0622818992 -0.0025271887 -0.0729335025 887 1311867748.2148320675 0.0335818753 0.0126658425 0.0373120606 0.0049668322 0.0216870000 232257450 95654136 760807424 0.0626614094 -0.0017344498 -0.0757501647 888 1311867748.2466599941 0.0325053073 0.0126881842 0.0373120606 0.0049701220 0.0224950000 232260866 95654136 760807424 0.0620399714 -0.0017913841 -0.0739253685 889 1311867748.2827599049 0.0300558992 0.0127077205 0.0373120606 0.0049708409 0.0215930000 232262850 95654136 760807424 0.0602271073 -0.0038476966 -0.0734934881 890 1311867748.3148829937 0.0321257412 0.0127295385 0.0373120606 0.0049847743 0.0219550000 232266322 95654136 760807424 0.0621099100 -0.0027750598 -0.0742734894 891 1311867748.3470869064 0.0292227995 0.0127480494 0.0373120606 0.0049991183 0.0219670000 232268194 95654136 760807424 0.0608113967 -0.0049299970 -0.0727855861 892 1311867748.3826999664 0.0310898684 0.0127686120 0.0373120606 0.0049967877 0.0324080000 232271778 95654136 760807424 0.0590797663 -0.0030695377 -0.0746022388 893 1311867748.4148259163 0.0296683088 0.0127875366 0.0373120606 0.0049950232 0.0224140000 232275394 95654136 760807424 0.0582862794 -0.0045019472 -0.0742878467 894 1311867748.4520189762 0.0294958893 0.0128062261 0.0373120606 0.0050059086 0.0220410000 232277234 95654136 760807424 0.0594780892 -0.0047092005 -0.0733805522 895 1311867748.4831318855 0.0323610790 0.0128280751 0.0373120606 0.0050035865 0.0259020000 232280906 95654136 760807424 0.0598314330 -0.0017694861 -0.0741835013 896 1311867748.5149960518 0.0318609178 0.0128493171 0.0373120606 0.0050050008 0.0256750000 232282578 95654136 760807424 0.0603902787 -0.0026226197 -0.0732527524 897 1311867748.5467929840 0.0292701814 0.0128676235 0.0373120606 0.0050026729 0.0221610000 232286194 95654136 760807424 0.0575690493 -0.0036647250 -0.0713322014 898 1311867748.5827159882 0.0328820981 0.0128899113 0.0373120606 0.0050081907 0.0220260000 232289778 95654136 760807424 0.0608388335 -0.0010056552 -0.0729712918 899 1311867748.6147999763 0.0304574426 0.0129094525 0.0373120606 0.0050079830 0.0220790000 232291706 95654136 760807424 0.0594650619 -0.0026100927 -0.0714198872 900 1311867748.6470849514 0.0295855049 0.0129279815 0.0373120606 0.0050298070 0.0310950000 232295122 95654136 760807424 0.0581040345 -0.0037474697 -0.0715699047 901 1311867748.6827559471 0.0308127757 0.0129478314 0.0373120606 0.0050296089 0.0232950000 232297106 95654136 760807424 0.0572214127 -0.0019697426 -0.0707040131 902 1311867748.7147359848 0.0271140561 0.0129635368 0.0373120606 0.0050521097 0.0222280000 232300578 95654136 760807424 0.0562101603 -0.0045056874 -0.0685047805 903 1311867748.7499361038 0.0285518281 0.0129807995 0.0373120606 0.0050494880 0.0222320000 232304306 95654136 760807424 0.0559422560 -0.0032931920 -0.0692467317 904 1311867748.7828259468 0.0276636425 0.0129970416 0.0373120606 0.0050469544 0.0221890000 232306090 95654136 760807424 0.0545663163 -0.0042375056 -0.0693258792 905 1311867748.8151619434 0.0291751530 0.0130149180 0.0373120606 0.0050443661 0.0221950000 232309762 95654136 760807424 0.0545423888 -0.0029366887 -0.0700755864 906 1311867748.8466329575 0.0295249466 0.0130331410 0.0373120606 0.0050427582 0.0221040000 232313122 95654136 760807424 0.0538624227 -0.0021270476 -0.0687097907 907 1311867748.8829579353 0.0302314088 0.0130521027 0.0373120606 0.0050403849 0.0221940000 232315106 95654136 760807424 0.0538783185 -0.0021183097 -0.0691684335 908 1311867748.9149119854 0.0284474418 0.0130690579 0.0373120606 0.0050380744 0.0317750000 232318634 95654136 760807424 0.0525835864 -0.0034625265 -0.0673945099 909 1311867748.9472498894 0.0273982342 0.0130848216 0.0373120606 0.0050365062 0.0225480000 232320506 95654136 760807424 0.0529433042 -0.0045599286 -0.0669572875 910 1311867748.9829359055 0.0297008101 0.0131030809 0.0373120606 0.0050339848 0.0222330000 232324090 95654136 760807424 0.0521065593 -0.0022901332 -0.0672647059 911 1311867749.0159859657 0.0291376077 0.0131206819 0.0373120606 0.0050315728 0.0222870000 232327762 95654136 760807424 0.0528408289 -0.0027600243 -0.0668519065 912 1311867749.0467190742 0.0274833590 0.0131364305 0.0373120606 0.0050293243 0.0222670000 232329378 95654136 760807424 0.0523045808 -0.0039731059 -0.0660744905 913 1311867749.0828969479 0.0291518625 0.0131539720 0.0373120606 0.0050268461 0.0255750000 232333162 95654136 760807424 0.0529074743 -0.0025860020 -0.0660777986 914 1311867749.1158421040 0.0304648969 0.0131729118 0.0373120606 0.0050242275 0.0223120000 232334890 95654136 760807424 0.0529184639 -0.0012367059 -0.0669728220 915 1311867749.1485249996 0.0283937398 0.0131895465 0.0373120606 0.0050216112 0.0223470000 232338618 95654136 760807424 0.0511530861 -0.0025629005 -0.0651636273 916 1311867749.1829619408 0.0285442695 0.0132063093 0.0373120606 0.0050193473 0.0332470000 232342146 95654136 760807424 0.0518444367 -0.0023128868 -0.0644814372 917 1311867749.2156000137 0.0280629899 0.0132225107 0.0373120606 0.0050187338 0.0229590000 232343962 95654136 760807424 0.0525329970 -0.0032844853 -0.0656039044 918 1311867749.2468719482 0.0296826530 0.0132404412 0.0373120606 0.0050206010 0.0224310000 232347378 95654136 760807424 0.0512792543 -0.0007032559 -0.0635155961 919 1311867749.2828478813 0.0278588217 0.0132563480 0.0373120606 0.0050222643 0.0224240000 232349362 95654136 760807424 0.0505121239 -0.0023021658 -0.0622295178 920 1311867749.3148140907 0.0291391145 0.0132736119 0.0373120606 0.0050200996 0.0224200000 232352890 95654136 760807424 0.0510658026 -0.0015543952 -0.0636806190 921 1311867749.3468968868 0.0272534378 0.0132887909 0.0373120606 0.0050174675 0.0225090000 232356506 95654136 760807424 0.0498906821 -0.0029023900 -0.0618937537 922 1311867749.3828470707 0.0277561042 0.0133044821 0.0373120606 0.0050150067 0.0224450000 232358290 95654136 760807424 0.0495723076 -0.0024117762 -0.0625884831 923 1311867749.4147930145 0.0274840742 0.0133198446 0.0373120606 0.0050128714 0.0224250000 232362018 95654136 760807424 0.0472362824 -0.0022960028 -0.0624719150 924 1311867749.4467489719 0.0276515819 0.0133353551 0.0373120606 0.0050104049 0.0333650000 232365434 95654136 760807424 0.0474365726 -0.0013333343 -0.0612949021 925 1311867749.4829080105 0.0251701307 0.0133481495 0.0373120606 0.0050088499 0.0230750000 232367418 95654136 760807424 0.0489663370 -0.0037362590 -0.0602631941 926 1311867749.5159850121 0.0245876499 0.0133602872 0.0373120606 0.0050072520 0.0224480000 232370890 95654136 760807424 0.0488531180 -0.0038912199 -0.0585643053 927 1311867749.5468530655 0.0261605848 0.0133740955 0.0373120606 0.0050072051 0.0233540000 232372762 95654136 760807424 0.0456273034 -0.0016554398 -0.0569692776 928 1311867749.5830268860 0.0254027396 0.0133870574 0.0373120606 0.0050048712 0.0227410000 232546126 95654136 760807424 0.0468005314 -0.0026415377 -0.0568146482 929 1311867749.6148250103 0.0259612799 0.0134005926 0.0373120606 0.0050026132 0.0224550000 232549742 95654136 760807424 0.0477076992 -0.0028014511 -0.0578424148 930 1311867749.6469049454 0.0253599454 0.0134134521 0.0373120606 0.0050018492 0.0224610000 232551470 95654136 760807424 0.0477467850 -0.0031298208 -0.0566801578 931 1311867749.6829149723 0.0241136272 0.0134249453 0.0373120606 0.0050006867 0.0225910000 232555254 95654136 760807424 0.0435362607 -0.0039061273 -0.0547853522 932 1311867749.7160799503 0.0241925456 0.0134364985 0.0373120606 0.0049982316 0.0326970000 232556926 95654136 760807424 0.0439061262 -0.0040189642 -0.0546259210 933 1311867749.7468609810 0.0258791186 0.0134498347 0.0373120606 0.0049985186 0.0230270000 232560598 95654136 760807424 0.0432808250 -0.0022678832 -0.0552677959 934 1311867749.7828791142 0.0235988386 0.0134607008 0.0373120606 0.0049965363 0.0264030000 232564182 95654136 760807424 0.0438456982 -0.0048284410 -0.0547139421 935 1311867749.8148949146 0.0242248215 0.0134722133 0.0373120606 0.0050021065 0.0225380000 232565998 95654136 760807424 0.0416050926 -0.0042930664 -0.0556252562 936 1311867749.8469030857 0.0238870941 0.0134833403 0.0373120606 0.0049996337 0.0227380000 232569526 95654136 760807424 0.0403281301 -0.0042522862 -0.0544343069 937 1311867749.8829030991 0.0239881575 0.0134945514 0.0373120606 0.0050182908 0.0226240000 232571510 95654136 760807424 0.0390986726 -0.0039500250 -0.0537629500 938 1311867749.9149639606 0.0262573957 0.0135081578 0.0373120606 0.0050374728 0.0225580000 232574926 95654136 760807424 0.0401348099 -0.0018476655 -0.0544412322 939 1311867749.9508709908 0.0255325418 0.0135209634 0.0373120606 0.0050349448 0.0225320000 232578710 95654136 760807424 0.0402441062 -0.0025483486 -0.0545622222 940 1311867749.9827940464 0.0256654564 0.0135338830 0.0373120606 0.0050343632 0.0330790000 232580438 95654136 760807424 0.0403701998 -0.0024018735 -0.0536651202 941 1311867750.0147750378 0.0264777821 0.0135476385 0.0373120606 0.0050318294 0.0229430000 232584110 95654136 760807424 0.0388646349 -0.0014313313 -0.0540201701 942 1311867750.0470709801 0.0255720653 0.0135604033 0.0373120606 0.0050294090 0.0263280000 232587582 95654136 760807424 0.0393848680 -0.0023787981 -0.0539993830 943 1311867750.0829339027 0.0255558435 0.0135731238 0.0373120606 0.0050271792 0.0226390000 232589566 95654136 760807424 0.0393926166 -0.0022943567 -0.0533337407 944 1311867750.1156458855 0.0250512902 0.0135852829 0.0373120606 0.0050265218 0.0225620000 232593038 95654136 760807424 0.0373613983 -0.0025752571 -0.0529734828 945 1311867750.1474790573 0.0249766950 0.0135973373 0.0373120606 0.0050242179 0.0225920000 232594910 95654136 760807424 0.0376170725 -0.0025558020 -0.0531557351 946 1311867750.1828711033 0.0242538936 0.0136086021 0.0373120606 0.0050217952 0.0225930000 232598494 95654136 760807424 0.0359498151 -0.0028948134 -0.0516595170 947 1311867750.2156589031 0.0244391579 0.0136200388 0.0373120606 0.0050205889 0.0225440000 232602166 95654136 760807424 0.0350734144 -0.0026189403 -0.0508617423 948 1311867750.2469079494 0.0251565576 0.0136322082 0.0373120606 0.0050187465 0.0273520000 232603782 95654136 760807424 0.0364665873 -0.0015769908 -0.0509131551 949 1311867750.2829968929 0.0249563754 0.0136441409 0.0373120606 0.0050161277 0.0229790000 232607566 95654136 760807424 0.0357945338 -0.0013104830 -0.0508785509 950 1311867750.3150129318 0.0239736643 0.0136550141 0.0373120606 0.0050135891 0.0226190000 232609294 95654136 760807424 0.0362125784 -0.0018664817 -0.0493484810 951 1311867750.3469090462 0.0229021013 0.0136647376 0.0373120606 0.0050112365 0.0226060000 232612910 95654136 760807424 0.0358240604 -0.0027300080 -0.0489059985 952 1311867750.3828659058 0.0222992413 0.0136738075 0.0373120606 0.0050090069 0.0225980000 232616494 95654136 760807424 0.0356801599 -0.0029026580 -0.0488931201 953 1311867750.4148640633 0.0219098069 0.0136824497 0.0373120606 0.0050065746 0.0226360000 232618422 95654136 760807424 0.0349067040 -0.0032131705 -0.0470961817 954 1311867750.4469859600 0.0234220158 0.0136926589 0.0373120606 0.0050043010 0.0337820000 232621838 95654136 760807424 0.0340453647 -0.0018682372 -0.0461266562 955 1311867750.4829618931 0.0246693380 0.0137041528 0.0373120606 0.0050035904 0.0232200000 232623766 95654136 760807424 0.0354608633 -0.0004107121 -0.0484444723 956 1311867750.5148859024 0.0240151975 0.0137149384 0.0373120606 0.0050017585 0.0227380000 232797278 95654136 760807424 0.0341075733 -0.0010489117 -0.0462744087 957 1311867750.5476069450 0.0238853078 0.0137255657 0.0373120606 0.0049992890 0.0277080000 232801006 95654136 760807424 0.0342694297 -0.0010428673 -0.0463002473 958 1311867750.5827779770 0.0244066603 0.0137367151 0.0373120606 0.0049971235 0.0227450000 232802790 95654136 760807424 0.0351764597 -0.0003618944 -0.0478069931 959 1311867750.6148829460 0.0237568133 0.0137471636 0.0373120606 0.0049945693 0.0227210000 232806406 95654136 760807424 0.0344509967 -0.0005687653 -0.0474707857 960 1311867750.6469810009 0.0241701081 0.0137580208 0.0373120606 0.0049924780 0.0226730000 232809934 95654136 760807424 0.0350288115 -0.0000748007 -0.0478102639 961 1311867750.6829319000 0.0243597664 0.0137690528 0.0373120606 0.0049906880 0.0227110000 232811918 95654136 760807424 0.0338425413 0.0005862779 -0.0473375507 962 1311867750.7149219513 0.0236774571 0.0137793526 0.0373120606 0.0049891959 0.0226220000 232815446 95654136 760807424 0.0339824371 0.0001943100 -0.0468162894 963 1311867750.7469151020 0.0212412626 0.0137871012 0.0373120606 0.0049890884 0.0226790000 232817262 95654136 760807424 0.0317443386 -0.0022218225 -0.0440716371 964 1311867750.7832129002 0.0233290009 0.0137969994 0.0373120606 0.0049871751 0.0226370000 232820790 95654136 760807424 0.0314623192 0.0001530580 -0.0440371782 965 1311867750.8149549961 0.0235553049 0.0138071117 0.0373120606 0.0049857856 0.0263540000 232824350 95654136 760807424 0.0322493538 0.0008021260 -0.0449244753 966 1311867750.8468461037 0.0228461120 0.0138164688 0.0373120606 0.0049840176 0.0257240000 232826022 95654136 760807424 0.0323213711 0.0007074376 -0.0439091772 967 1311867750.8828840256 0.0237769727 0.0138267692 0.0373120606 0.0049814879 0.0227620000 232829862 95654136 760807424 0.0335337035 0.0017896437 -0.0434895381 968 1311867750.9147970676 0.0235239323 0.0138367870 0.0373120606 0.0049797202 0.0227260000 232831478 95654136 760807424 0.0328417681 0.0017834696 -0.0442793183 969 1311867750.9468770027 0.0212856624 0.0138444741 0.0373120606 0.0049781585 0.0263280000 232835150 95654136 760807424 0.0316520520 0.0001844842 -0.0427119732 970 1311867750.9830369949 0.0203652848 0.0138511966 0.0373120606 0.0049775207 0.0227450000 232838790 95654136 760807424 0.0329054743 -0.0007870109 -0.0404781438 971 1311867751.0168409348 0.0209030863 0.0138584591 0.0373120606 0.0049765117 0.0227200000 232840718 95654136 760807424 0.0309639256 -0.0002166659 -0.0398230143 972 1311867751.0470340252 0.0212725922 0.0138660868 0.0373120606 0.0049742951 0.0226570000 232844134 95654136 760807424 0.0289756041 0.0002563537 -0.0400449298 973 1311867751.0828599930 0.0218906105 0.0138743340 0.0373120606 0.0049735582 0.0227200000 232846062 95654136 760807424 0.0310625229 0.0011037658 -0.0411426127 974 1311867751.1174809933 0.0208067037 0.0138814515 0.0373120606 0.0049715370 0.0227810000 233020006 95654136 760807424 0.0311395675 -0.0001230799 -0.0403402224 975 1311867751.1468789577 0.0230892189 0.0138908953 0.0373120606 0.0049723990 0.0267010000 233023566 95654136 760807424 0.0289231725 0.0020422828 -0.0419504344 976 1311867751.1835930347 0.0216116719 0.0138988060 0.0373120606 0.0049721335 0.0227330000 233025406 95654136 760807424 0.0301216636 0.0010185316 -0.0427156463 977 1311867751.2161049843 0.0210859198 0.0139061623 0.0373120606 0.0049714237 0.0227640000 233029078 95654136 760807424 0.0279849619 0.0003328235 -0.0400336273 978 1311867751.2468481064 0.0231991000 0.0139156642 0.0373120606 0.0049693975 0.0226940000 233032494 95654136 760807424 0.0287320074 0.0024946472 -0.0410677083 979 1311867751.2831909657 0.0231281817 0.0139250744 0.0373120606 0.0049679662 0.0233890000 233034534 95654136 760807424 0.0286378749 0.0029985919 -0.0435121171 980 1311867751.3149859905 0.0205151308 0.0139317989 0.0373120606 0.0049654802 0.0229200000 233037950 95654136 760807424 0.0278869346 0.0004903537 -0.0407117531 981 1311867751.3498640060 0.0208028518 0.0139388031 0.0373120606 0.0049665948 0.0227700000 233039934 95654136 760807424 0.0294842869 0.0007511692 -0.0399761423 982 1311867751.3834669590 0.0224653855 0.0139474859 0.0373120606 0.0049649273 0.0227460000 233043462 95654136 760807424 0.0277950466 0.0024308795 -0.0421345532 983 1311867751.4151160717 0.0217490140 0.0139554224 0.0373120606 0.0049640523 0.0227580000 233047134 95654136 760807424 0.0279012639 0.0016554405 -0.0415303707 984 1311867751.4513890743 0.0191918984 0.0139607440 0.0373120606 0.0049654022 0.0263750000 233048862 95654136 760807424 0.0270254426 -0.0010372696 -0.0392012075 985 1311867751.4838130474 0.0222737510 0.0139691836 0.0373120606 0.0049640230 0.0228010000 233052590 95654136 760807424 0.0288345907 0.0023757026 -0.0414058417 986 1311867751.5149779320 0.0220448915 0.0139773740 0.0373120606 0.0049619370 0.0264020000 233054262 95654136 760807424 0.0282042027 0.0022888961 -0.0417557359 987 1311867751.5495769978 0.0224571619 0.0139859655 0.0373120606 0.0049598774 0.0228200000 233057990 95654136 760807424 0.0278831664 0.0026791899 -0.0414295085 988 1311867751.5829720497 0.0229357444 0.0139950239 0.0373120606 0.0049577844 0.0227540000 233061462 95654136 760807424 0.0284740366 0.0030772323 -0.0424972884 989 1311867751.6149520874 0.0219107326 0.0140030277 0.0373120606 0.0049555978 0.0267020000 233063334 95654136 760807424 0.0292151608 0.0021384982 -0.0417067446 990 1311867751.6501350403 0.0211359020 0.0140102326 0.0373120606 0.0049533284 0.0230070000 233237946 95654136 760807424 0.0265531447 0.0014156683 -0.0409149975 991 1311867751.6839730740 0.0215692408 0.0140178603 0.0373120606 0.0049523158 0.0228560000 233239930 95654136 760807424 0.0284311771 0.0019539392 -0.0411109701 992 1311867751.7150709629 0.0202086736 0.0140241010 0.0373120606 0.0049503053 0.0228490000 233243290 95654136 760807424 0.0280851722 0.0007414997 -0.0398266688 993 1311867751.7507519722 0.0206245780 0.0140307480 0.0373120606 0.0049486912 0.0265690000 233247074 95654136 760807424 0.0277797189 0.0010313765 -0.0387505814 994 1311867751.7830109596 0.0212112479 0.0140379719 0.0373120606 0.0049465516 0.0229300000 233248746 95654136 760807424 0.0274826176 0.0017475360 -0.0380154066 995 1311867751.8149600029 0.0220782571 0.0140460525 0.0373120606 0.0049471600 0.0265080000 233252418 95654136 760807424 0.0275163054 0.0023003949 -0.0395508260 996 1311867751.8509531021 0.0226205513 0.0140546615 0.0373120606 0.0049448048 0.0229520000 233256002 95654136 760807424 0.0277961418 0.0031977841 -0.0389501676 997 1311867751.8832330704 0.0225216597 0.0140631540 0.0373120606 0.0049426382 0.0229570000 233257874 95654136 760807424 0.0277692080 0.0029229312 -0.0382322185 998 1311867751.9149179459 0.0228050016 0.0140719133 0.0373120606 0.0049416543 0.0230390000 233261290 95654136 760807424 0.0276290365 0.0036900402 -0.0392198600 999 1311867751.9530611038 0.0214705449 0.0140793194 0.0373120606 0.0049400374 0.0229930000 233263386 95654136 760807424 0.0277993549 0.0029887345 -0.0387707390 1000 1311867751.9829521179 0.0214784872 0.0140867185 0.0373120606 0.0049377040 0.0229790000 233266802 95654136 760807424 0.0270858873 0.0031645878 -0.0384206884 1001 1311867752.0153670311 0.0216284879 0.0140942528 0.0373120606 0.0049353631 0.0229720000 233270418 95654136 760807424 0.0268827192 0.0035682470 -0.0387643278 1002 1311867752.0510330200 0.0195780694 0.0140997256 0.0373120606 0.0049357619 0.0267140000 233272202 95654136 760807424 0.0255181585 0.0019881376 -0.0372978933 1003 1311867752.0828928947 0.0197874289 0.0141053963 0.0373120606 0.0049337297 0.0231080000 233275930 95654136 760807424 0.0238957256 0.0022514407 -0.0352437273 1004 1311867752.1150529385 0.0202673934 0.0141115338 0.0373120606 0.0049327429 0.0232040000 233448778 95654136 760807424 0.0257513560 0.0030896571 -0.0362530425 1005 1311867752.1509859562 0.0189752039 0.0141163732 0.0373120606 0.0049318823 0.0230450000 233452562 95654136 760807424 0.0261479840 0.0022502937 -0.0364465006 1006 1311867752.1829679012 0.0186906774 0.0141209203 0.0373120606 0.0049297455 0.0231750000 233456090 95654136 760807424 0.0249911901 0.0023722243 -0.0354195572 1007 1311867752.2150039673 0.0185305085 0.0141252992 0.0373120606 0.0049277389 0.0241030000 233457962 95654136 760807424 0.0253981445 0.0026631528 -0.0357751623 1008 1311867752.2512340546 0.0191741325 0.0141303080 0.0373120606 0.0049297477 0.0231700000 233461490 95654136 760807424 0.0254128352 0.0040275860 -0.0361670069 1009 1311867752.2833271027 0.0188085698 0.0141349445 0.0373120606 0.0049281535 0.0231750000 233463362 95654136 760807424 0.0255218130 0.0041173552 -0.0354198925 1010 1311867752.3150799274 0.0182660799 0.0141390347 0.0373120606 0.0049279375 0.0231980000 233466778 95654136 760807424 0.0253418833 0.0034665510 -0.0348612070 1011 1311867752.3509979248 0.0190465786 0.0141438889 0.0373120606 0.0049276337 0.0326930000 233470562 95654136 760807424 0.0260182656 0.0046788207 -0.0349896848 1012 1311867752.3829851151 0.0192155223 0.0141489004 0.0373120606 0.0049255058 0.0235880000 233472290 95654136 760807424 0.0265859570 0.0045425454 -0.0353773907 1013 1311867752.4160280228 0.0186544452 0.0141533481 0.0373120606 0.0049233018 0.0232280000 233475962 95654136 760807424 0.0267202370 0.0039283810 -0.0357888378 1014 1311867752.4510710239 0.0183126424 0.0141574500 0.0373120606 0.0049265946 0.0232180000 233479546 95654136 760807424 0.0264322925 0.0033977269 -0.0355483741 1015 1311867752.4829080105 0.0193272550 0.0141625434 0.0373120606 0.0049291308 0.0232150000 233481418 95654136 760807424 0.0259124599 0.0045770849 -0.0346406884 1016 1311867752.5181159973 0.0202080254 0.0141684936 0.0373120606 0.0049315417 0.0232810000 233484946 95654136 760807424 0.0242515765 0.0051188855 -0.0354620516 1017 1311867752.5511059761 0.0184152313 0.0141726694 0.0373120606 0.0049298590 0.0232580000 233486818 95654136 760807424 0.0254814867 0.0035268129 -0.0363698974 1018 1311867752.5830090046 0.0189460274 0.0141773584 0.0373120606 0.0049280932 0.0233260000 233490346 95654136 760807424 0.0281267744 0.0033470825 -0.0360601470 1019 1311867752.6167891026 0.0214232523 0.0141844691 0.0373120606 0.0049268462 0.0327100000 233494018 95654136 760807424 0.0286308601 0.0060460912 -0.0355974026 1020 1311867752.6514921188 0.0230014473 0.0141931132 0.0373120606 0.0049276979 0.0236820000 233495746 95654136 760807424 0.0286211129 0.0077155582 -0.0362639204 1021 1311867752.6830079556 0.0226584077 0.0142014044 0.0373120606 0.0049290834 0.0233200000 233499418 95654136 760807424 0.0302259196 0.0067571895 -0.0359526761 1022 1311867752.7152869701 0.0217218176 0.0142087629 0.0373120606 0.0049275537 0.0232520000 233501146 95654136 760807424 0.0279486906 0.0066060778 -0.0354578197 1023 1311867752.7510609627 0.0208487138 0.0142152536 0.0373120606 0.0049251903 0.0232400000 233504818 95654136 760807424 0.0273874719 0.0054532234 -0.0358396508 1024 1311867752.7830440998 0.0216691177 0.0142225328 0.0373120606 0.0049258501 0.0232590000 233508346 95654136 760807424 0.0266823806 0.0061153630 -0.0375612676 1025 1311867752.8162839413 0.0220522117 0.0142301715 0.0373120606 0.0049240243 0.0234410000 233698634 95654136 760807424 0.0283185020 0.0062311161 -0.0384039059 1026 1311867752.8511059284 0.0215477273 0.0142373036 0.0373120606 0.0049223253 0.0234050000 233906962 95654136 760807424 0.0282826144 0.0060118837 -0.0378451385 1027 1311867752.8833000660 0.0221492164 0.0142450075 0.0373120606 0.0049200544 0.0267060000 233908890 95654136 760807424 0.0288843047 0.0066306768 -0.0380434878 1028 1311867752.9183809757 0.0211382657 0.0142517130 0.0373120606 0.0049187627 0.0234930000 233912474 95654136 760807424 0.0283659827 0.0061539826 -0.0386699885 1029 1311867752.9511129856 0.0193653964 0.0142566826 0.0373120606 0.0049209963 0.0303010000 234055802 95654136 760807424 0.0272259824 0.0047619804 -0.0377438925 1030 1311867752.9828579426 0.0188494697 0.0142611416 0.0373120606 0.0049186278 0.0266860000 234057530 95654136 760807424 0.0259930901 0.0043875817 -0.0379966646 1031 1311867753.0168170929 0.0523451492 0.0142980805 0.0523451492 0.0053830474 0.0370550000 234233622 95654136 760807424 0.0210698582 0.0378019363 -0.0304638967 1032 1311867753.0510199070 0.0480576903 0.0143307933 0.0523451492 0.0054008434 0.0268760000 234237790 95654136 760807424 0.0201711804 0.0328562818 -0.0277519654 1033 1311867753.0829060078 0.0492357388 0.0143645832 0.0523451492 0.0054035771 0.0317150000 234239670 95654136 760807424 0.0161608905 0.0333218500 -0.0265558548 1034 1311867753.1184310913 0.0497085899 0.0143987650 0.0523451492 0.0054021882 0.0267720000 234243246 95654136 760807424 0.0184727907 0.0345954746 -0.0277996007 1035 1311867753.1510760784 0.0479813479 0.0144312119 0.0523451492 0.0054005715 0.0345510000 234245062 95654136 760807424 0.0168382656 0.0321669169 -0.0260506589 1036 1311867753.1830070019 0.0492927916 0.0144648621 0.0523451492 0.0054000279 0.0273640000 234248478 95654136 760807424 0.0180054661 0.0335633792 -0.0259594079 1037 1311867753.2186999321 0.0510327630 0.0145001253 0.0523451492 0.0053974887 0.0266430000 234252254 95654136 760807424 0.0182593297 0.0361914895 -0.0278051086 1038 1311867753.2520470619 0.0495221578 0.0145338652 0.0523451492 0.0053950451 0.0313770000 234253934 95654136 760807424 0.0184388086 0.0346386731 -0.0263997968 1039 1311867753.2829909325 0.0502991639 0.0145682880 0.0523451492 0.0053928501 0.0312510000 234257670 95654136 760807424 0.0168959498 0.0354923792 -0.0264012683 1040 1311867753.3196740150 0.0513834991 0.0146036872 0.0523451492 0.0053911169 0.0270470000 234429758 95654136 760807424 0.0177345853 0.0375430323 -0.0277999211 1041 1311867753.3509368896 0.0496428572 0.0146373464 0.0523451492 0.0053893720 0.0268250000 234433574 95654136 760807424 0.0160218515 0.0358398743 -0.0268220119 1042 1311867753.3829340935 0.0498216897 0.0146711126 0.0523451492 0.0053871830 0.0269490000 234437038 95654136 760807424 0.0158020258 0.0358770564 -0.0251499303 1043 1311867753.4182109833 0.0498116538 0.0147048044 0.0523451492 0.0053849756 0.0404870000 234439214 95654136 760807424 0.0134311840 0.0361420996 -0.0258141253 1044 1311867753.4511721134 0.0481132567 0.0147368048 0.0523451492 0.0053830511 0.0270210000 234442438 95654136 760807424 0.0123714786 0.0342885964 -0.0254544653 1045 1311867753.4831509590 0.0484122038 0.0147690300 0.0523451492 0.0053808864 0.0266430000 234444558 95654136 760807424 0.0106919138 0.0343720429 -0.0257048663 1046 1311867753.5199849606 0.0493826754 0.0148021215 0.0523451492 0.0053795115 0.0243450000 234448198 95654136 760807424 0.0117229065 0.0359891206 -0.0270656534 1047 1311867753.5532789230 0.0487594008 0.0148345544 0.0523451492 0.0053771654 0.0269560000 234623394 95654136 760807424 0.0097991358 0.0349732526 -0.0262589213 1048 1311867753.5832290649 0.0483911075 0.0148665740 0.0523451492 0.0053746156 0.0266860000 234625138 95654136 760807424 0.0086579314 0.0345700234 -0.0265589934 1049 1311867753.6183180809 0.0479812957 0.0148981419 0.0523451492 0.0053722384 0.0269040000 234629114 95654136 760807424 0.0086909020 0.0345918834 -0.0268743355 1050 1311867753.6509299278 0.0480884500 0.0149297517 0.0523451492 0.0053700879 0.0243400000 234632586 95654136 760807424 0.0078496793 0.0346531272 -0.0258911233 1051 1311867753.6830120087 0.0477172844 0.0149609483 0.0523451492 0.0053683752 0.0243010000 234634402 95654136 760807424 0.0063448604 0.0342060812 -0.0263871271 1052 1311867753.7204821110 0.0471730866 0.0149915682 0.0523451492 0.0053659487 0.0243330000 234638098 95654136 760807424 0.0065545589 0.0342106074 -0.0268179886 1053 1311867753.7510209084 0.0462003574 0.0150212061 0.0523451492 0.0053639924 0.0242960000 234810374 95654136 760807424 0.0050927061 0.0327992402 -0.0255887005 1054 1311867753.7865459919 0.0460016876 0.0150505994 0.0523451492 0.0053636698 0.0267250000 234814470 95654136 760807424 0.0054186033 0.0327914283 -0.0252078809 1055 1311867753.8151860237 0.0487354882 0.0150825282 0.0523451492 0.0053622083 0.0247780000 234818030 95654136 760807424 0.0061443467 0.0366151705 -0.0264466200 1056 1311867753.8510670662 0.0469423346 0.0151126985 0.0523451492 0.0053614811 0.0268010000 234819814 95654136 760807424 0.0055952733 0.0345481224 -0.0246209484 1057 1311867753.8831698895 0.0464524925 0.0151423482 0.0523451492 0.0053623471 0.0265800000 234823606 95654136 760807424 0.0044370964 0.0335008763 -0.0230086204 1058 1311867753.9155960083 0.0468759611 0.0151723422 0.0523451492 0.0053603287 0.0266700000 234825286 95654136 760807424 0.0045952969 0.0346619561 -0.0248080622 1059 1311867753.9511620998 0.0465580858 0.0152019793 0.0523451492 0.0053578600 0.0383890000 234999958 95654136 760807424 0.0036566844 0.0346088596 -0.0249507204 1060 1311867753.9859020710 0.0457222722 0.0152307721 0.0523451492 0.0053556809 0.0267800000 235003670 95654136 760807424 0.0015661954 0.0327284560 -0.0230403021 1061 1311867754.0151760578 0.0457760431 0.0152595612 0.0523451492 0.0053532936 0.0267240000 235005622 95654136 760807424 0.0005812809 0.0327103883 -0.0224531833 1062 1311867754.0510439873 0.0469051003 0.0152893592 0.0523451492 0.0053529936 0.0268130000 235009454 95654136 760807424 0.0005621587 0.0345885679 -0.0232593920 1063 1311867754.0839149952 0.0463049375 0.0153185366 0.0523451492 0.0053514900 0.0267330000 235011390 95654136 760807424 -0.0020923866 0.0330698565 -0.0215196516 1064 1311867754.1166028976 0.0459221862 0.0153472995 0.0523451492 0.0053493985 0.0316480000 235185662 95654136 760807424 -0.0028708240 0.0325139575 -0.0206829216 1065 1311867754.1511039734 0.0474503748 0.0153774432 0.0523451492 0.0053504231 0.0267520000 235189334 95654136 760807424 -0.0033479552 0.0345750749 -0.0214223433 1066 1311867754.1832261086 0.0466460064 0.0154067758 0.0523451492 0.0053502697 0.0314500000 235191062 95654136 760807424 -0.0051258514 0.0340330526 -0.0214379448 1067 1311867754.2166349888 0.0449886955 0.0154345002 0.0523451492 0.0053499098 0.0247130000 235194734 95654136 760807424 -0.0072766501 0.0316875763 -0.0201414693 1068 1311867754.2522869110 0.0460787565 0.0154631933 0.0523451492 0.0053517042 0.0271460000 235198894 95654136 760807424 -0.0089430986 0.0326327942 -0.0195647050 1069 1311867754.2873370647 0.0443648882 0.0154902295 0.0523451492 0.0053542302 0.0268280000 235200814 95654136 760807424 -0.0088256150 0.0316367298 -0.0196467768 1070 1311867754.3188319206 0.0439355671 0.0155168140 0.0523451492 0.0053541091 0.0268670000 235204222 95654136 760807424 -0.0095811440 0.0307992753 -0.0191831347 1071 1311867754.3511719704 0.0445265025 0.0155439005 0.0523451492 0.0053549807 0.0269380000 235377718 95654136 760807424 -0.0117223747 0.0306953546 -0.0184006561 1072 1311867754.3868899345 0.0446625911 0.0155710635 0.0523451492 0.0053545107 0.0320970000 235381118 95654136 760807424 -0.0110257966 0.0313372985 -0.0188125595 1073 1311867754.4159760475 0.0442356877 0.0155977779 0.0523451492 0.0053536425 0.0267260000 235384982 95654136 760807424 -0.0127981938 0.0304274745 -0.0176922418 1074 1311867754.4545960426 0.0439143628 0.0156241435 0.0523451492 0.0053634272 0.0312800000 235386830 95654136 760807424 -0.0143795488 0.0295162443 -0.0170144737 1075 1311867754.4863700867 0.0441325642 0.0156506629 0.0523451492 0.0053731194 0.0269020000 235390566 95654136 760807424 -0.0161230452 0.0293432903 -0.0162534714 1076 1311867754.5164580345 0.0443929508 0.0156773751 0.0523451492 0.0053706894 0.0267870000 235392374 95654136 760807424 -0.0152477417 0.0304872394 -0.0169324912 1077 1311867754.5513699055 0.0431598946 0.0157028927 0.0523451492 0.0053702818 0.0314480000 235396110 95654136 760807424 -0.0149979750 0.0292025451 -0.0159617271 1078 1311867754.5835940838 0.0431774929 0.0157283794 0.0523451492 0.0053703356 0.0276580000 235570142 95654136 760807424 -0.0157575626 0.0286677498 -0.0145758921 1079 1311867754.6154909134 0.0437149070 0.0157543169 0.0523451492 0.0053679573 0.0269820000 235571958 95654136 760807424 -0.0152082667 0.0295814369 -0.0148081072 1080 1311867754.6510920525 0.0439683348 0.0157804409 0.0523451492 0.0053659513 0.0268560000 235575422 95654136 760807424 -0.0160533842 0.0294976644 -0.0141095296 1081 1311867754.6872758865 0.0443251953 0.0158068468 0.0523451492 0.0053636458 0.0267730000 235577470 95654136 760807424 -0.0187903251 0.0288381651 -0.0130158477 1082 1311867754.7162959576 0.0446287990 0.0158334845 0.0523451492 0.0053614659 0.0312840000 235581022 95654136 760807424 -0.0191337392 0.0293350480 -0.0135998465 1083 1311867754.7516000271 0.0451576076 0.0158605612 0.0523451492 0.0053592394 0.0267570000 235584742 95654136 760807424 -0.0182906035 0.0307984930 -0.0142581305 1084 1311867754.7865269184 0.0433049202 0.0158858789 0.0523451492 0.0053583617 0.0269920000 235586918 95654136 760807424 -0.0183845554 0.0285331290 -0.0126811415 1085 1311867754.8154470921 0.0435909703 0.0159114136 0.0523451492 0.0053570246 0.0268740000 235590542 95654136 760807424 -0.0188849978 0.0285698902 -0.0119553842 1086 1311867754.8510210514 0.0444282070 0.0159376721 0.0523451492 0.0053623337 0.0268520000 235594318 95654136 760807424 -0.0195013490 0.0295281224 -0.0124064730 1087 1311867754.8877389431 0.0414530411 0.0159611453 0.0523451492 0.0053605727 0.0322900000 235767582 95654136 760807424 -0.0206529759 0.0258247480 -0.0108828098 1088 1311867754.9201259613 0.0420884043 0.0159851593 0.0523451492 0.0053583725 0.0271130000 235771054 95654136 760807424 -0.0221003909 0.0258437060 -0.0095454864 1089 1311867754.9510319233 0.0434856117 0.0160104123 0.0523451492 0.0053565093 0.0269420000 235772806 95654136 760807424 -0.0221852213 0.0279355682 -0.0105245234 1090 1311867754.9837870598 0.0416614264 0.0160339453 0.0523451492 0.0053582516 0.0347410000 235776654 95654136 760807424 -0.0218648054 0.0267386343 -0.0105670001 1091 1311867755.0183880329 0.0416577756 0.0160574319 0.0523451492 0.0053559888 0.0318920000 235780446 95654136 760807424 -0.0225443803 0.0264103487 -0.0093200635 1092 1311867755.0540831089 0.0428611040 0.0160819774 0.0523451492 0.0053618027 0.0268870000 235782166 95654136 760807424 -0.0256885570 0.0266567562 -0.0082633821 1093 1311867755.0850980282 0.0417758562 0.0161054850 0.0523451492 0.0053630724 0.0269980000 235786030 95654136 760807424 -0.0254867747 0.0257648863 -0.0078848768 1094 1311867755.1156959534 0.0424417518 0.0161295584 0.0523451492 0.0053646591 0.0268970000 235787654 95654136 760807424 -0.0276464894 0.0258886721 -0.0074282726 1095 1311867755.1556220055 0.0419740826 0.0161531607 0.0523451492 0.0053629628 0.0267780000 235791614 95654136 760807424 -0.0277475063 0.0255188160 -0.0067642103 1096 1311867755.1847031116 0.0424653403 0.0161771682 0.0523451492 0.0053611355 0.0271290000 235966178 95654136 760807424 -0.0276496820 0.0263594817 -0.0067102555 1097 1311867755.2151238918 0.0432921015 0.0162018855 0.0523451492 0.0053588194 0.0271810000 235967938 95654136 760807424 -0.0269448180 0.0279632956 -0.0071236058 1098 1311867755.2512340546 0.0433761477 0.0162266344 0.0523451492 0.0053565625 0.0271990000 235971586 95654136 760807424 -0.0296571963 0.0267898943 -0.0058035725 1099 1311867755.2832889557 0.0430662706 0.0162510563 0.0523451492 0.0053556388 0.0269890000 235973650 95654136 760807424 -0.0301881582 0.0259713717 -0.0053835157 1100 1311867755.3192110062 0.0430589244 0.0162754271 0.0523451492 0.0053535600 0.0269450000 235977170 95654136 760807424 -0.0298524443 0.0261542089 -0.0070561217 1101 1311867755.3553090096 0.0429202244 0.0162996276 0.0523451492 0.0053516652 0.0272080000 235981202 95654136 760807424 -0.0309927389 0.0249682497 -0.0064454442 1102 1311867755.3900220394 0.0424562730 0.0163233632 0.0523451492 0.0053493104 0.0270300000 235982810 95654136 760807424 -0.0319378674 0.0234628115 -0.0057273125 1103 1311867755.4156589508 0.0451370776 0.0163494863 0.0523451492 0.0053471442 0.0270400000 235986178 95654136 760807424 -0.0306654572 0.0273702182 -0.0082953610 1104 1311867755.4549160004 0.0435224548 0.0163740994 0.0523451492 0.0053447894 0.0270820000 235989882 95654136 760807424 -0.0325003043 0.0248189364 -0.0072036646 1105 1311867755.4860870838 0.0432065986 0.0163983823 0.0523451492 0.0053427447 0.0269450000 235991762 95654136 760807424 -0.0357189998 0.0230294671 -0.0059717470 1106 1311867755.5161950588 0.0442417338 0.0164235571 0.0523451492 0.0053404828 0.0312540000 235995186 95654136 760807424 -0.0340861604 0.0254873987 -0.0071361689 1107 1311867755.5550999641 0.0431435369 0.0164476944 0.0523451492 0.0053384167 0.0271520000 235997218 95654136 760807424 -0.0331979506 0.0251038913 -0.0072870250 1108 1311867755.5854589939 0.0429322049 0.0164715973 0.0523451492 0.0053360150 0.0270970000 236000882 95654136 760807424 -0.0334770307 0.0250550099 -0.0070661851 1109 1311867755.6171119213 0.0439971760 0.0164964175 0.0523451492 0.0053338329 0.0434500000 236004434 95654136 760807424 -0.0333525017 0.0265596788 -0.0077066761 1110 1311867755.6542940140 0.0432795472 0.0165205465 0.0523451492 0.0053316059 0.0272610000 236006466 95654136 760807424 -0.0341194756 0.0255361088 -0.0070773265 1111 1311867755.6831719875 0.0419724509 0.0165434555 0.0523451492 0.0053293899 0.0279480000 236180842 95654136 760807424 -0.0346954986 0.0234177522 -0.0064024688 1112 1311867755.7182741165 0.0427414440 0.0165670148 0.0523451492 0.0053272981 0.0271030000 236182626 95654136 760807424 -0.0351996422 0.0239301007 -0.0070736809 1113 1311867755.7511448860 0.0440166183 0.0165916775 0.0523451492 0.0053255599 0.0314000000 236186618 95654136 760807424 -0.0350257754 0.0254384745 -0.0081453370 1114 1311867755.7863750458 0.0434465706 0.0166157843 0.0523451492 0.0053234068 0.0414020000 236189954 95654136 760807424 -0.0356207117 0.0243790615 -0.0080631133 1115 1311867755.8156878948 0.0433776826 0.0166397860 0.0523451492 0.0053210548 0.0272290000 236192146 95654136 760807424 -0.0363830663 0.0238639321 -0.0082929591 1116 1311867755.8554079533 0.0454920419 0.0166656392 0.0523451492 0.0053190468 0.0272690000 236195794 95654136 760807424 -0.0345491059 0.0274899825 -0.0099841515 1117 1311867755.8848359585 0.0421087816 0.0166884173 0.0523451492 0.0053176629 0.0315460000 236197730 95654136 760807424 -0.0348249935 0.0238565467 -0.0094939554 1118 1311867755.9156229496 0.0429005101 0.0167118629 0.0523451492 0.0053153678 0.0270710000 236201266 95654136 760807424 -0.0360399187 0.0240196642 -0.0084714256 1119 1311867755.9550359249 0.0436982363 0.0167359794 0.0523451492 0.0053130897 0.0272460000 236204986 95654136 760807424 -0.0360028856 0.0256173741 -0.0098604932 1120 1311867755.9855198860 0.0429431759 0.0167593787 0.0523451492 0.0053119078 0.0271640000 236206794 95654136 760807424 -0.0373136364 0.0245322175 -0.0094339801 1121 1311867756.0173881054 0.0433923453 0.0167831369 0.0523451492 0.0053099379 0.0271380000 236210474 95654136 760807424 -0.0372244976 0.0249739680 -0.0086351540 1122 1311867756.0554430485 0.0437719673 0.0168071911 0.0523451492 0.0053077508 0.0282390000 236214122 95654136 760807424 -0.0365722515 0.0261491556 -0.0097928084 1123 1311867756.0835959911 0.0423457474 0.0168299325 0.0523451492 0.0053061946 0.0272180000 236216130 95654136 760807424 -0.0371312387 0.0243983269 -0.0091532646 1124 1311867756.1196908951 0.0415742695 0.0168519470 0.0523451492 0.0053038554 0.0272240000 236219778 95654136 760807424 -0.0384077206 0.0223206915 -0.0074515478 1125 1311867756.1519339085 0.0440619141 0.0168761336 0.0523451492 0.0053017142 0.0272960000 236221290 95654136 760807424 -0.0377233587 0.0258674324 -0.0094528664 1126 1311867756.1836869717 0.0428421684 0.0168991941 0.0523451492 0.0052999228 0.0272420000 236224970 95654136 760807424 -0.0369952768 0.0247900486 -0.0094714658 1127 1311867756.2230648994 0.0431950986 0.0169225267 0.0523451492 0.0052987861 0.0275200000 236228706 95654136 760807424 -0.0385242142 0.0240339767 -0.0078091798 1128 1311867756.2552509308 0.0430815965 0.0169457174 0.0523451492 0.0052984419 0.0319980000 236230442 95654136 760807424 -0.0386702530 0.0241606440 -0.0085282223 1129 1311867756.2851591110 0.0422205925 0.0169681043 0.0523451492 0.0053003310 0.0323380000 236234050 95654136 760807424 -0.0378103219 0.0239581596 -0.0094203418 1130 1311867756.3200058937 0.0428514630 0.0169910100 0.0523451492 0.0052983525 0.0273250000 236235842 95654136 760807424 -0.0375463068 0.0245035756 -0.0084573524 1131 1311867756.3546419144 0.0432936214 0.0170142660 0.0523451492 0.0052960363 0.0275460000 236239818 95654136 760807424 -0.0375852697 0.0247460306 -0.0080116848 1132 1311867756.3843090534 0.0436830930 0.0170378251 0.0523451492 0.0052937537 0.0274390000 236243242 95654136 760807424 -0.0372350961 0.0255875289 -0.0090928627 1133 1311867756.4231688976 0.0425107069 0.0170603078 0.0523451492 0.0052920311 0.0324610000 236245290 95654136 760807424 -0.0369877405 0.0240081623 -0.0084921056 1134 1311867756.4510979652 0.0426096022 0.0170828380 0.0523451492 0.0052897345 0.0318190000 236248658 95654136 760807424 -0.0374825895 0.0236119069 -0.0076859305 1135 1311867756.4865350723 0.0429326892 0.0171056132 0.0523451492 0.0052900371 0.0273780000 236250762 95654136 760807424 -0.0355375372 0.0246328153 -0.0090951277 1136 1311867756.5264549255 0.0425297953 0.0171279936 0.0523451492 0.0052883068 0.0273220000 236254466 95654136 760807424 -0.0352334976 0.0241285916 -0.0088876309 1137 1311867756.5525779724 0.0422245227 0.0171500662 0.0523451492 0.0052863142 0.0408310000 236257834 95654136 760807424 -0.0351910405 0.0238410141 -0.0089199683 1138 1311867756.5897810459 0.0417970940 0.0171717244 0.0523451492 0.0052839950 0.0274670000 236259866 95654136 760807424 -0.0349704400 0.0234557297 -0.0085433507 1139 1311867756.6202929020 0.0428264774 0.0171942483 0.0523451492 0.0052819520 0.0274020000 236263490 95654136 760807424 -0.0361829549 0.0237519741 -0.0077552097 1140 1311867756.6518390179 0.0430605337 0.0172169381 0.0523451492 0.0052799042 0.0275000000 236267026 95654136 760807424 -0.0367331356 0.0235859547 -0.0071240254 1141 1311867756.6839349270 0.0435292758 0.0172399988 0.0523451492 0.0052778431 0.0275170000 236269034 95654136 760807424 -0.0349064246 0.0251210108 -0.0076660332 1142 1311867756.7217059135 0.0415259711 0.0172612650 0.0523451492 0.0052769997 0.0275370000 236272682 95654136 760807424 -0.0366032124 0.0223808810 -0.0069438322 1143 1311867756.7516939640 0.0421462022 0.0172830366 0.0523451492 0.0052748319 0.0274300000 236274562 95654136 760807424 -0.0369324833 0.0227892231 -0.0066636028 1144 1311867756.7872660160 0.0442013815 0.0173065666 0.0523451492 0.0052733380 0.0315430000 236278082 95654136 760807424 -0.0363655947 0.0252864137 -0.0062319865 1145 1311867756.8227219582 0.0412684195 0.0173274940 0.0523451492 0.0052725286 0.0275970000 236282058 95654136 760807424 -0.0361712761 0.0222557597 -0.0064350930 1146 1311867756.8542120457 0.0422123596 0.0173492086 0.0523451492 0.0052736066 0.0275970000 236283866 95654136 760807424 -0.0369542763 0.0227646809 -0.0053606387 1147 1311867756.8841960430 0.0434827805 0.0173719928 0.0523451492 0.0052760797 0.0277140000 236458442 95654136 760807424 -0.0375913866 0.0238845050 -0.0058341930 1148 1311867756.9223539829 0.0424574129 0.0173938443 0.0523451492 0.0052745237 0.0278050000 236460738 95654136 760807424 -0.0376397483 0.0225641876 -0.0051484080 1149 1311867756.9552440643 0.0420837216 0.0174153324 0.0523451492 0.0052722524 0.0275300000 236464402 95654136 760807424 -0.0372111909 0.0222073290 -0.0049867630 1150 1311867756.9841780663 0.0424094908 0.0174370664 0.0523451492 0.0052700004 0.0273500000 236467698 95654136 760807424 -0.0365943164 0.0230338071 -0.0053707082 1151 1311867757.0282740593 0.0412783809 0.0174577800 0.0523451492 0.0052687338 0.0275550000 236470098 95654136 760807424 -0.0382867046 0.0205059052 -0.0042344341 1152 1311867757.0552940369 0.0415188670 0.0174786664 0.0523451492 0.0052670391 0.0274830000 236473650 95654136 760807424 -0.0374161750 0.0211568158 -0.0042346679 1153 1311867757.0858569145 0.0430305786 0.0175008276 0.0523451492 0.0052648606 0.0275430000 236475274 95654136 760807424 -0.0377326906 0.0227656793 -0.0046881340 1154 1311867757.1283040047 0.0411816016 0.0175213482 0.0523451492 0.0052637294 0.0275310000 236479034 95654136 760807424 -0.0388973989 0.0188333970 -0.0021017792 1155 1311867757.1522068977 0.0425675139 0.0175430332 0.0523451492 0.0052653089 0.0277600000 236482490 95654136 760807424 -0.0392187014 0.0201643184 -0.0030113952 1156 1311867757.1851921082 0.0420795865 0.0175642586 0.0523451492 0.0052644087 0.0335410000 236484154 95654136 760807424 -0.0387766100 0.0195036903 -0.0036553445 1157 1311867757.2192370892 0.0412502289 0.0175847305 0.0523451492 0.0052640613 0.0275920000 236488002 95654136 760807424 -0.0390722789 0.0170839746 -0.0030953698 1158 1311867757.2523930073 0.0411327481 0.0176050656 0.0523451492 0.0052717931 0.0274300000 236491666 95654136 760807424 -0.0385968573 0.0165544264 -0.0031318662 1159 1311867757.2835690975 0.0437805168 0.0176276501 0.0523451492 0.0052707153 0.0275290000 236493418 95654136 760807424 -0.0381915234 0.0201376900 -0.0056251190 1160 1311867757.3233768940 0.0418576263 0.0176485380 0.0523451492 0.0052761026 0.0343510000 236497050 95654136 760807424 -0.0370715484 0.0174145121 -0.0055646435 1161 1311867757.3555359840 0.0430457294 0.0176704133 0.0523451492 0.0052745501 0.0275190000 236499170 95654136 760807424 -0.0373163596 0.0180802140 -0.0054276199 1162 1311867757.3833439350 0.0453720987 0.0176942529 0.0523451492 0.0052729341 0.0277150000 236502410 95654136 760807424 -0.0368154049 0.0210492890 -0.0062902272 1163 1311867757.4264349937 0.0436436832 0.0177165654 0.0523451492 0.0052712765 0.0273450000 236506370 95654136 760807424 -0.0367171690 0.0184190720 -0.0053802351 1164 1311867757.4546940327 0.0438510478 0.0177390177 0.0523451492 0.0052694525 0.0274360000 236507994 95654136 760807424 -0.0368363485 0.0186221916 -0.0060878177 1165 1311867757.4884710312 0.0440435410 0.0177615967 0.0523451492 0.0052675241 0.0275220000 236511842 95654136 760807424 -0.0356555656 0.0192763265 -0.0064421552 1166 1311867757.5210690498 0.0434485003 0.0177836266 0.0523451492 0.0052653837 0.0275320000 236513410 95654136 760807424 -0.0366092287 0.0175574217 -0.0052201077 1167 1311867757.5554831028 0.0437709130 0.0178058951 0.0523451492 0.0052635822 0.0276020000 236687378 95654136 760807424 -0.0364385210 0.0177652668 -0.0055815154 1168 1311867757.5887749195 0.0439419784 0.0178282719 0.0523451492 0.0052613627 0.0401680000 236691034 95654136 760807424 -0.0363305807 0.0179213211 -0.0059171831 1169 1311867757.6231749058 0.0441735834 0.0178508085 0.0523451492 0.0052598323 0.0277210000 236693026 95654136 760807424 -0.0371698029 0.0176151395 -0.0058278516 1170 1311867757.6566219330 0.0448911339 0.0178739199 0.0523451492 0.0052576732 0.0276790000 236696434 95654136 760807424 -0.0367102064 0.0186020453 -0.0065980190 1171 1311867757.6914329529 0.0446494445 0.0178967854 0.0523451492 0.0052555641 0.0275390000 236698426 95654136 760807424 -0.0367958099 0.0181583781 -0.0058795111 1172 1311867757.7207450867 0.0443802699 0.0179193822 0.0523451492 0.0052533378 0.0275010000 236701962 95654136 760807424 -0.0363481902 0.0178563520 -0.0055918097 1173 1311867757.7614738941 0.0424660482 0.0179403086 0.0523451492 0.0052517415 0.0331690000 236705738 95654136 760807424 -0.0354197323 0.0158981942 -0.0054986826 1174 1311867757.7876570225 0.0434950553 0.0179620759 0.0523451492 0.0052501627 0.0278500000 236707234 95654136 760807424 -0.0361081101 0.0165123455 -0.0053193257 1175 1311867757.8206570148 0.0430651009 0.0179834402 0.0523451492 0.0052481756 0.0340970000 236711154 95654136 760807424 -0.0369907357 0.0150580145 -0.0050214538 1176 1311867757.8555610180 0.0431094095 0.0180048058 0.0523451492 0.0052461411 0.0275960000 236714690 95654136 760807424 -0.0372934900 0.0146676693 -0.0052192402 1177 1311867757.8887560368 0.0431293100 0.0180261520 0.0523451492 0.0052459890 0.0275410000 236716554 95654136 760807424 -0.0377547964 0.0142919328 -0.0056986012 1178 1311867757.9201729298 0.0434445180 0.0180477296 0.0523451492 0.0052438728 0.0278720000 236720162 95654136 760807424 -0.0380002856 0.0142460233 -0.0058463709 1179 1311867757.9554479122 0.0438228063 0.0180695914 0.0523451492 0.0052416769 0.0245930000 236722146 95654136 760807424 -0.0386801213 0.0141099496 -0.0061429553 1180 1311867757.9904439449 0.0449618064 0.0180923814 0.0523451492 0.0052473701 0.0283270000 236725786 95654136 760807424 -0.0380498916 0.0159234479 -0.0071894666 1181 1311867758.0221159458 0.0439479426 0.0181142743 0.0523451492 0.0052461760 0.0246350000 236900634 95654136 760807424 -0.0362284034 0.0154384011 -0.0075061847 1182 1311867758.0557579994 0.0435681976 0.0181358090 0.0523451492 0.0052442461 0.0275000000 236902610 95654136 760807424 -0.0354980677 0.0151702184 -0.0075541916 1183 1311867758.0871500969 0.0435045362 0.0181572534 0.0523451492 0.0052420709 0.0273510000 236906106 95654136 760807424 -0.0365301631 0.0145204365 -0.0076656179 1184 1311867758.1223280430 0.0431714877 0.0181783802 0.0523451492 0.0052399385 0.0274130000 236908082 95654136 760807424 -0.0366177931 0.0137511427 -0.0078721382 1185 1311867758.1526539326 0.0425453298 0.0181989431 0.0523451492 0.0052409253 0.0320650000 236911762 95654136 760807424 -0.0362156518 0.0128888879 -0.0079804808 1186 1311867758.1877539158 0.0426077545 0.0182195239 0.0523451492 0.0052391676 0.0272560000 236915282 95654136 760807424 -0.0368603058 0.0124733383 -0.0084248912 1187 1311867758.2221779823 0.0411970466 0.0182388815 0.0523451492 0.0052396171 0.0325770000 236917274 95654136 760807424 -0.0371675901 0.0104185967 -0.0086089130 1188 1311867758.2562980652 0.0413239375 0.0182583134 0.0523451492 0.0052376991 0.0276170000 236920866 95654136 760807424 -0.0376438610 0.0103636924 -0.0096867494 1189 1311867758.2902839184 0.0418100953 0.0182781214 0.0523451492 0.0052356462 0.0272640000 236922914 95654136 760807424 -0.0388900600 0.0099044042 -0.0094939908 1190 1311867758.3220090866 0.0420714095 0.0182981158 0.0523451492 0.0052369013 0.0248230000 236926330 95654136 760807424 -0.0388069302 0.0100449827 -0.0103451964 1191 1311867758.3539829254 0.0417456180 0.0183178030 0.0523451492 0.0052348473 0.0399030000 237100286 95654136 760807424 -0.0385762043 0.0098240804 -0.0110145938 1192 1311867758.3902978897 0.0409143791 0.0183367599 0.0523451492 0.0052327665 0.0270890000 237102014 95654136 760807424 -0.0372414812 0.0094818017 -0.0114477091 1193 1311867758.4210340977 0.0409334376 0.0183557009 0.0523451492 0.0052309294 0.0269770000 237105750 95654136 760807424 -0.0380808599 0.0087254057 -0.0110481642 1194 1311867758.4536960125 0.0417376906 0.0183752838 0.0523451492 0.0052289046 0.0272440000 237109158 95654136 760807424 -0.0377806164 0.0098910900 -0.0115325097 1195 1311867758.4900159836 0.0423958525 0.0183953847 0.0523451492 0.0052267552 0.0325430000 237111150 95654136 760807424 -0.0372939706 0.0110002933 -0.0119629456 1196 1311867758.5217890739 0.0427770056 0.0184157707 0.0523451492 0.0052246642 0.0269290000 237114686 95654136 760807424 -0.0386770368 0.0104852933 -0.0113222674 1197 1311867758.5528969765 0.0419691689 0.0184354477 0.0523451492 0.0052226978 0.0270350000 237116366 95654136 760807424 -0.0380087905 0.0099996813 -0.0116730919 1198 1311867758.5893049240 0.0431542471 0.0184560811 0.0523451492 0.0052211614 0.0269410000 237120014 95654136 760807424 -0.0394142158 0.0107453167 -0.0119637083 1199 1311867758.6221299171 0.0431905910 0.0184767104 0.0523451492 0.0052193578 0.0272510000 237123750 95654136 760807424 -0.0402362458 0.0102566136 -0.0120349973 1200 1311867758.6535029411 0.0430228487 0.0184971655 0.0523451492 0.0052172155 0.0243490000 237125478 95654136 760807424 -0.0407042764 0.0096045882 -0.0118757579 1201 1311867758.6911680698 0.0440415181 0.0185184347 0.0523451492 0.0052156926 0.0270270000 237129518 95654136 760807424 -0.0407464914 0.0107618058 -0.0120651918 1202 1311867758.7212190628 0.0434866399 0.0185392070 0.0523451492 0.0052142764 0.0239360000 237131134 95654136 760807424 -0.0399904028 0.0103299841 -0.0119949114 1203 1311867758.7601859570 0.0435528159 0.0185599997 0.0523451492 0.0052125483 0.0268830000 237135102 95654136 760807424 -0.0406803638 0.0099417875 -0.0115679521 1204 1311867758.7879199982 0.0422906056 0.0185797095 0.0523451492 0.0052111746 0.0281950000 237138462 95654136 760807424 -0.0374788456 0.0100777885 -0.0117194727 1205 1311867758.8218998909 0.0407110304 0.0185980757 0.0523451492 0.0052093229 0.0239990000 237140334 95654136 760807424 -0.0394463837 0.0070611415 -0.0111934058 1206 1311867758.8574860096 0.0410605073 0.0186167013 0.0523451492 0.0052081651 0.0238980000 237143918 95654136 760807424 -0.0396706983 0.0070957481 -0.0111691970 1207 1311867758.8875849247 0.0409677066 0.0186352191 0.0523451492 0.0052061646 0.0280570000 237316310 95654136 760807424 -0.0393870361 0.0071163448 -0.0117030386 1208 1311867758.9205179214 0.0398371108 0.0186527703 0.0523451492 0.0052041687 0.0269230000 237319926 95654136 760807424 -0.0384322219 0.0059636771 -0.0114584798 1209 1311867758.9576990604 0.0376554839 0.0186684880 0.0523451492 0.0052040331 0.0239750000 237323822 95654136 760807424 -0.0389115475 0.0026333891 -0.0112945838 1210 1311867758.9880809784 0.0376022942 0.0186841358 0.0523451492 0.0052020170 0.0238950000 237325438 95654136 760807424 -0.0377287567 0.0030808211 -0.0121310921 1211 1311867759.0196750164 0.0374244489 0.0186996109 0.0523451492 0.0051999466 0.0238420000 237329110 95654136 760807424 -0.0365703925 0.0032733143 -0.0124904970 1212 1311867759.0579299927 0.0380365327 0.0187155654 0.0523451492 0.0051978121 0.0238870000 237332750 95654136 760807424 -0.0366614424 0.0038020217 -0.0127475504 1213 1311867759.0873589516 0.0388668366 0.0187321782 0.0523451492 0.0051958216 0.0238610000 237334510 95654136 760807424 -0.0370950960 0.0046176729 -0.0132054808 1214 1311867759.1199090481 0.0385159291 0.0187484745 0.0523451492 0.0051937907 0.0246190000 237337982 95654136 760807424 -0.0368626453 0.0043440904 -0.0132249547 1215 1311867759.1563479900 0.0376734398 0.0187640506 0.0523451492 0.0051928683 0.0280370000 237510686 95654136 760807424 -0.0362260602 0.0036186746 -0.0136901438 1216 1311867759.1888740063 0.0376228467 0.0187795595 0.0523451492 0.0051908056 0.0238470000 237514214 95654136 760807424 -0.0359074138 0.0035789299 -0.0140232723 1217 1311867759.2214748859 0.0355955027 0.0187933770 0.0523451492 0.0051903022 0.0238020000 237517830 95654136 760807424 -0.0332267284 0.0021150799 -0.0144473314 1218 1311867759.2585420609 0.0348721854 0.0188065780 0.0523451492 0.0051882674 0.0278250000 237519670 95654136 760807424 -0.0337025635 0.0007519028 -0.0145227984 1219 1311867759.2957389355 0.0348533057 0.0188197419 0.0523451492 0.0051862403 0.0237540000 237523454 95654136 760807424 -0.0342278220 0.0000386218 -0.0143656097 1220 1311867759.3223690987 0.0343620554 0.0188324815 0.0523451492 0.0051843502 0.0277730000 237524958 95654136 760807424 -0.0336305574 -0.0004830639 -0.0144068394 1221 1311867759.3619010448 0.0322414711 0.0188434635 0.0523451492 0.0051826006 0.0238220000 237528854 95654136 760807424 -0.0326467827 -0.0027472987 -0.0145580508 1222 1311867759.3886260986 0.0307629537 0.0188532175 0.0523451492 0.0051819463 0.0272370000 237532214 95654136 760807424 -0.0318484269 -0.0043835947 -0.0150224566 1223 1311867759.4206190109 0.0306937676 0.0188628991 0.0523451492 0.0051800570 0.0276250000 237704742 95654136 760807424 -0.0301487911 -0.0041039549 -0.0151675977 1224 1311867759.4585750103 0.0326140039 0.0188741337 0.0523451492 0.0051782564 0.0237680000 237708382 95654136 760807424 -0.0299119931 -0.0020467499 -0.0157500543 1225 1311867759.4905979633 0.0314392038 0.0188843909 0.0523451492 0.0051770793 0.0237630000 237710254 95654136 760807424 -0.0301085562 -0.0034746423 -0.0158911981 1226 1311867759.5243968964 0.0316655152 0.0188948159 0.0523451492 0.0051756793 0.0237520000 237713782 95654136 760807424 -0.0299381688 -0.0036196718 -0.0154656749 1227 1311867759.5617649555 0.0328069106 0.0189061542 0.0523451492 0.0051742323 0.0239100000 237717566 95654136 760807424 -0.0305225905 -0.0031110460 -0.0149479769 1228 1311867759.5870699883 0.0331083387 0.0189177195 0.0523451492 0.0051723304 0.0239090000 237719014 95654136 760807424 -0.0300899204 -0.0029315671 -0.0143783204 1229 1311867759.6198399067 0.0324470624 0.0189287279 0.0523451492 0.0051703502 0.0236690000 237722686 95654136 760807424 -0.0292572528 -0.0037597662 -0.0145886131 1230 1311867759.6576719284 0.0328113548 0.0189400146 0.0523451492 0.0051683613 0.0236180000 237726270 95654136 760807424 -0.0302553680 -0.0039084889 -0.0151203619 1231 1311867759.6904048920 0.0336903892 0.0189519971 0.0523451492 0.0051670488 0.0275100000 237898198 95654136 760807424 -0.0330437757 -0.0043707462 -0.0151025075 1232 1311867759.7190918922 0.0306726675 0.0189615106 0.0523451492 0.0051668863 0.0236310000 237901558 95654136 760807424 -0.0321445093 -0.0077628042 -0.0153347077 1233 1311867759.7576398849 0.0307135321 0.0189710418 0.0523451492 0.0051655892 0.0236210000 237903598 95654136 760807424 -0.0311553348 -0.0075533162 -0.0160928108 1234 1311867759.7871410847 0.0306748636 0.0189805263 0.0523451492 0.0051662795 0.0236590000 237907014 95654136 760807424 -0.0310665462 -0.0074048452 -0.0162764285 1235 1311867759.8209869862 0.0309972484 0.0189902564 0.0523451492 0.0051683603 0.0236290000 237910686 95654136 760807424 -0.0308230557 -0.0078174938 -0.0164464824 1236 1311867759.8573861122 0.0323570631 0.0190010710 0.0523451492 0.0051711667 0.0235970000 237912526 95654136 760807424 -0.0311499014 -0.0062488625 -0.0167000107 1237 1311867759.8883268833 0.0319111720 0.0190115076 0.0523451492 0.0051750542 0.0262660000 237916142 95654136 760807424 -0.0281198584 -0.0067313896 -0.0170526374 1238 1311867759.9261589050 0.0289419238 0.0190195290 0.0523451492 0.0051739583 0.0235060000 237917982 95654136 760807424 -0.0289104227 -0.0107570142 -0.0172638204 1239 1311867759.9576280117 0.0298355371 0.0190282586 0.0523451492 0.0051729987 0.0235530000 237921654 95654136 760807424 -0.0293414108 -0.0100843869 -0.0181501117 1240 1311867759.9870700836 0.0303127803 0.0190373590 0.0523451492 0.0051710666 0.0273010000 238095586 95654136 760807424 -0.0304789580 -0.0102991462 -0.0184095595 1241 1311867760.0261199474 0.0270661004 0.0190438286 0.0523451492 0.0051709677 0.0236150000 238097626 95654136 760807424 -0.0305303894 -0.0143061131 -0.0184985381 1242 1311867760.0566520691 0.0277664810 0.0190508517 0.0523451492 0.0051699543 0.0235620000 238101098 95654136 760807424 -0.0302623753 -0.0134999845 -0.0188877266 1243 1311867760.0870590210 0.0280440450 0.0190580867 0.0523451492 0.0051681293 0.0235720000 238102914 95654136 760807424 -0.0303882640 -0.0130579351 -0.0191373900 1244 1311867760.1246991158 0.0264751930 0.0190640490 0.0523451492 0.0051671328 0.0235200000 238106554 95654136 760807424 -0.0312490240 -0.0152926315 -0.0192260034 1245 1311867760.1576859951 0.0271348804 0.0190705316 0.0523451492 0.0051672792 0.0235720000 238110226 95654136 760807424 -0.0303808935 -0.0141358981 -0.0197364930 1246 1311867760.1870229244 0.0299370624 0.0190792528 0.0523451492 0.0051656124 0.0234100000 238111842 95654136 760807424 -0.0300674941 -0.0108428001 -0.0199230928 1247 1311867760.2261290550 0.0289253686 0.0190871486 0.0523451492 0.0051649098 0.0234940000 238285410 95654136 760807424 -0.0308366437 -0.0122548081 -0.0202735737 1248 1311867760.2573459148 0.0261340439 0.0190927951 0.0523451492 0.0051632609 0.0234380000 238288882 95654136 760807424 -0.0304408595 -0.0154003901 -0.0209219400 1249 1311867760.2895119190 0.0282523502 0.0191001287 0.0523451492 0.0051614570 0.0236090000 238290810 95654136 760807424 -0.0302472152 -0.0133123621 -0.0214567408 1250 1311867760.3248739243 0.0276239384 0.0191069477 0.0523451492 0.0051593971 0.0233940000 238294394 95654136 760807424 -0.0305390786 -0.0144740101 -0.0214335397 1251 1311867760.3574841022 0.0258749630 0.0191123578 0.0523451492 0.0051647042 0.0233760000 238296210 95654136 760807424 -0.0320211202 -0.0175963175 -0.0218783151 1252 1311867760.3897368908 0.0278683659 0.0191193514 0.0523451492 0.0051633787 0.0274030000 238470142 95654136 760807424 -0.0326538347 -0.0159161184 -0.0221731346 1253 1311867760.4247770309 0.0265839454 0.0191253088 0.0523451492 0.0051625482 0.0274260000 238473870 95654136 760807424 -0.0293698944 -0.0158591047 -0.0234221704 1254 1311867760.4572839737 0.0245973971 0.0191296725 0.0523451492 0.0051610922 0.0345260000 238475486 95654136 760807424 -0.0308024958 -0.0187906306 -0.0240436252 1255 1311867760.4886090755 0.0285299271 0.0191371627 0.0523451492 0.0051600689 0.0236870000 238479214 95654136 760807424 -0.0317572765 -0.0152116958 -0.0242925454 1256 1311867760.5243430138 0.0294377785 0.0191453639 0.0523451492 0.0051583942 0.0265530000 238480998 95654136 760807424 -0.0311644934 -0.0142168598 -0.0246556886 1257 1311867760.5571060181 0.0274699274 0.0191519864 0.0523451492 0.0051565588 0.0233380000 238656050 95654136 760807424 -0.0313480124 -0.0167630948 -0.0252987072 1258 1311867760.5894339085 0.0281758830 0.0191591596 0.0523451492 0.0051547839 0.0265340000 238659578 95654136 760807424 -0.0317275077 -0.0163669363 -0.0262175724 1259 1311867760.6240029335 0.0285695102 0.0191666341 0.0523451492 0.0051528588 0.0232670000 238661506 95654136 760807424 -0.0305151455 -0.0156880282 -0.0267088301 1260 1311867760.6560370922 0.0281742755 0.0191737830 0.0523451492 0.0051514751 0.0333880000 238664978 95654136 760807424 -0.0304490868 -0.0165319741 -0.0272396542 1261 1311867760.6867549419 0.0249961652 0.0191784003 0.0523451492 0.0051499635 0.0236250000 238666794 95654136 760807424 -0.0306141358 -0.0201333370 -0.0277770050 1262 1311867760.7232599258 0.0252979808 0.0191832494 0.0523451492 0.0051489320 0.0323270000 238670378 95654136 760807424 -0.0279050134 -0.0188134853 -0.0293147694 1263 1311867760.7558701038 0.0242522098 0.0191872628 0.0523451492 0.0051472470 0.0233970000 238674106 95654136 760807424 -0.0277333129 -0.0201376043 -0.0292611439 1264 1311867760.7868170738 0.0236436259 0.0191907884 0.0523451492 0.0051452123 0.0231900000 238845434 95654136 760807424 -0.0288420375 -0.0214626733 -0.0295289140 1265 1311867760.8233850002 0.0272817072 0.0191971844 0.0523451492 0.0051442386 0.0240000000 238849218 95654136 760807424 -0.0277848318 -0.0171929915 -0.0304840486 1266 1311867760.8547210693 0.0263290554 0.0192028178 0.0523451492 0.0051422884 0.0272450000 238852690 95654136 760807424 -0.0290664174 -0.0186319947 -0.0304815639 1267 1311867760.8877849579 0.0249330588 0.0192073405 0.0523451492 0.0051407405 0.0231240000 238854562 95654136 760807424 -0.0293685347 -0.0203607306 -0.0301266462 1268 1311867760.9240860939 0.0258146990 0.0192125513 0.0523451492 0.0051448366 0.0230970000 238858202 95654136 760807424 -0.0287224874 -0.0190577451 -0.0311649982 1269 1311867760.9559810162 0.0252469350 0.0192173066 0.0523451492 0.0051430196 0.0230700000 238860074 95654136 760807424 -0.0288062859 -0.0195999239 -0.0316099003 1270 1311867760.9867389202 0.0245262850 0.0192214869 0.0523451492 0.0051412806 0.0345330000 238863434 95654136 760807424 -0.0298232082 -0.0205949061 -0.0323681571 1271 1311867761.0245900154 0.0264015365 0.0192271360 0.0523451492 0.0051399557 0.0235120000 238867330 95654136 760807424 -0.0264520515 -0.0174260736 -0.0324442983 1272 1311867761.0566051006 0.0269577373 0.0192332135 0.0523451492 0.0051381341 0.0230130000 238869002 95654136 760807424 -0.0263190139 -0.0166076887 -0.0327502824 1273 1311867761.0866270065 0.0254491400 0.0192380964 0.0523451492 0.0051362735 0.0230120000 238872562 95654136 760807424 -0.0260799415 -0.0180127211 -0.0330883674 1274 1311867761.1242640018 0.0256314091 0.0192431147 0.0523451492 0.0051352282 0.0230510000 239044218 95654136 760807424 -0.0258628149 -0.0174270235 -0.0339980796 1275 1311867761.1547141075 0.0274927933 0.0192495851 0.0523451492 0.0051335283 0.0230380000 239047834 95654136 760807424 -0.0255933125 -0.0154487053 -0.0341501981 1276 1311867761.1912519932 0.0238081999 0.0192531576 0.0523451492 0.0051324167 0.0230100000 239051362 95654136 760807424 -0.0265634041 -0.0195687525 -0.0341130123 1277 1311867761.2244689465 0.0252987370 0.0192578918 0.0523451492 0.0051310752 0.0230530000 239053346 95654136 760807424 -0.0274601113 -0.0184530504 -0.0344980136 1278 1311867761.2564349174 0.0263843630 0.0192634681 0.0523451492 0.0051293227 0.0229950000 239056818 95654136 760807424 -0.0262307748 -0.0169730205 -0.0350463353 1279 1311867761.2914810181 0.0246158503 0.0192676529 0.0523451492 0.0051277363 0.0233650000 239058690 95654136 760807424 -0.0268622339 -0.0191212073 -0.0349706896 1280 1311867761.3245120049 0.0272537842 0.0192738921 0.0523451492 0.0051269892 0.0231100000 239232214 95654136 760807424 -0.0287980456 -0.0171142668 -0.0351706631 1281 1311867761.3563210964 0.0301842634 0.0192824092 0.0523451492 0.0051262425 0.0229850000 239235830 95654136 760807424 -0.0255765934 -0.0133308135 -0.0359976962 1282 1311867761.3919639587 0.0278400965 0.0192890844 0.0523451492 0.0051246323 0.0228600000 239237614 95654136 760807424 -0.0267868731 -0.0160515234 -0.0363463722 1283 1311867761.4230949879 0.0265984181 0.0192947815 0.0523451492 0.0051236440 0.0229770000 239241286 95654136 760807424 -0.0280774888 -0.0177763328 -0.0367343239 1284 1311867761.4547801018 0.0292089656 0.0193025028 0.0523451492 0.0051232915 0.0263220000 239244702 95654136 760807424 -0.0269151777 -0.0148141515 -0.0376282223 1285 1311867761.4908668995 0.0286233872 0.0193097564 0.0523451492 0.0051214355 0.0229490000 239246742 95654136 760807424 -0.0278408267 -0.0157354325 -0.0370842181 1286 1311867761.5258040428 0.0252832416 0.0193144014 0.0523451492 0.0051202403 0.0229350000 239250214 95654136 760807424 -0.0292218663 -0.0198817048 -0.0375894196 1287 1311867761.5562748909 0.0276590604 0.0193208852 0.0523451492 0.0051185156 0.0336500000 239252030 95654136 760807424 -0.0279059317 -0.0171768554 -0.0383718498 1288 1311867761.5914149284 0.0305659194 0.0193296159 0.0523451492 0.0051173282 0.0232820000 239255558 95654136 760807424 -0.0261073187 -0.0139794145 -0.0389525443 1289 1311867761.6232030392 0.0273407362 0.0193358309 0.0523451492 0.0051162965 0.0228300000 239259286 95654136 760807424 -0.0264917891 -0.0176602788 -0.0383280739 1290 1311867761.6567790508 0.0288473237 0.0193432041 0.0523451492 0.0051163279 0.0229620000 239430490 95654136 760807424 -0.0279292297 -0.0166108645 -0.0394232199 1291 1311867761.6917459965 0.0292366836 0.0193508675 0.0523451492 0.0051145023 0.0234990000 239434218 95654136 760807424 -0.0266801119 -0.0160331689 -0.0398892500 1292 1311867761.7235610485 0.0255822148 0.0193556905 0.0523451492 0.0051163745 0.0231180000 239435890 95654136 760807424 -0.0262832269 -0.0196072627 -0.0400415324 1293 1311867761.7545659542 0.0248192903 0.0193599161 0.0523451492 0.0051159436 0.0228930000 239439506 95654136 760807424 -0.0283659529 -0.0211875588 -0.0402099788 1294 1311867761.7916970253 0.0293640364 0.0193676472 0.0523451492 0.0051160315 0.0229010000 239443090 95654136 760807424 -0.0280806720 -0.0166050047 -0.0403937250 1295 1311867761.8235230446 0.0295505300 0.0193755105 0.0523451492 0.0051142149 0.0335270000 239444962 95654136 760807424 -0.0283062663 -0.0164391790 -0.0405708961 1296 1311867761.8546519279 0.0309780389 0.0193844630 0.0523451492 0.0051130766 0.0231830000 239448434 95654136 760807424 -0.0268750694 -0.0146044977 -0.0403690971 1297 1311867761.8910980225 0.0325107165 0.0193945835 0.0523451492 0.0051120527 0.0228100000 239450418 95654136 760807424 -0.0260391999 -0.0128287328 -0.0396500900 1298 1311867761.9224560261 0.0315476656 0.0194039464 0.0523451492 0.0051123842 0.0229620000 239453890 95654136 760807424 -0.0229776520 -0.0134178065 -0.0395015329 1299 1311867761.9546790123 0.0271499753 0.0194099095 0.0523451492 0.0051131761 0.0227660000 239626838 95654136 760807424 -0.0242716875 -0.0180536006 -0.0411207043 1300 1311867761.9942779541 0.0287431609 0.0194170889 0.0523451492 0.0051123241 0.0228080000 239628734 95654136 760807424 -0.0262275282 -0.0171881001 -0.0414972417 1301 1311867762.0235669613 0.0285816342 0.0194241332 0.0523451492 0.0051108611 0.0227760000 239632294 95654136 760807424 -0.0261246394 -0.0174191575 -0.0423065349 1302 1311867762.0558550358 0.0268424843 0.0194298308 0.0523451492 0.0051092941 0.0226740000 239635766 95654136 760807424 -0.0242033731 -0.0190220438 -0.0432442240 1303 1311867762.0913889408 0.0285242666 0.0194368104 0.0523451492 0.0051227156 0.0227130000 239637694 95654136 760807424 -0.0247132983 -0.0180276874 -0.0432009324 1304 1311867762.1225299835 0.0307967942 0.0194455221 0.0523451492 0.0051217775 0.0227700000 239641166 95654136 760807424 -0.0257032756 -0.0161398519 -0.0430110507 1305 1311867762.1545391083 0.0291491784 0.0194529578 0.0523451492 0.0051426346 0.0238500000 239643094 95654136 760807424 -0.0252162926 -0.0177208055 -0.0422718935 1306 1311867762.1913030148 0.0283403415 0.0194597629 0.0523451492 0.0051410283 0.0229190000 239816714 95654136 760807424 -0.0255228113 -0.0188794304 -0.0428781547 1307 1311867762.2234869003 0.0294065308 0.0194673732 0.0523451492 0.0051393073 0.0227490000 239820442 95654136 760807424 -0.0264833402 -0.0181944743 -0.0437252149 1308 1311867762.2565600872 0.0272700395 0.0194733386 0.0523451492 0.0051398619 0.0226890000 239822170 95654136 760807424 -0.0220148806 -0.0194442421 -0.0443676785 1309 1311867762.2907900810 0.0291169584 0.0194807058 0.0523451492 0.0051381150 0.0227160000 239825842 95654136 760807424 -0.0217548423 -0.0177651737 -0.0443000607 1310 1311867762.3235380650 0.0316287726 0.0194899791 0.0523451492 0.0051560749 0.0227900000 239827570 95654136 760807424 -0.0208832063 -0.0160775259 -0.0450111367 1311 1311867762.3545570374 0.0328948461 0.0195002040 0.0523451492 0.0051549573 0.0226510000 239831242 95654136 760807424 -0.0212362688 -0.0150725599 -0.0451885164 1312 1311867762.3949799538 0.0336368233 0.0195109789 0.0523451492 0.0051694770 0.0352770000 239834938 95654136 760807424 -0.0213731471 -0.0140212718 -0.0452198870 1313 1311867762.4242470264 0.0309592150 0.0195196980 0.0523451492 0.0051677745 0.0232530000 240006214 95654136 760807424 -0.0231013596 -0.0171497632 -0.0456722416 1314 1311867762.4588010311 0.0316595957 0.0195289369 0.0523451492 0.0051659551 0.0226820000 240009686 95654136 760807424 -0.0226810407 -0.0164842289 -0.0454531349 1315 1311867762.4918160439 0.0279579666 0.0195353468 0.0523451492 0.0051649944 0.0226460000 240011558 95654136 760807424 -0.0223391354 -0.0202150699 -0.0454944819 1316 1311867762.5242910385 0.0299766064 0.0195432809 0.0523451492 0.0051644822 0.0225890000 240015086 95654136 760807424 -0.0239719301 -0.0184359550 -0.0454707108 1317 1311867762.5594940186 0.0326475017 0.0195532309 0.0523451492 0.0051636487 0.0226520000 240018870 95654136 760807424 -0.0244599581 -0.0159302428 -0.0446333475 1318 1311867762.5913679600 0.0304328501 0.0195614856 0.0523451492 0.0051628084 0.0227450000 240020486 95654136 760807424 -0.0243327022 -0.0182265621 -0.0446835756 1319 1311867762.6233699322 0.0314257145 0.0195704805 0.0523451492 0.0051608986 0.0227530000 240194410 95654136 760807424 -0.0222508516 -0.0169089511 -0.0447098278 1320 1311867762.6626110077 0.0313273780 0.0195793872 0.0523451492 0.0051590824 0.0344580000 240198106 95654136 760807424 -0.0234120358 -0.0173043106 -0.0448688827 1321 1311867762.6927230358 0.0319393910 0.0195887437 0.0523451492 0.0051584509 0.0230100000 240199810 95654136 760807424 -0.0201048497 -0.0162372328 -0.0453442819 1322 1311867762.7241640091 0.0316481851 0.0195978659 0.0523451492 0.0051565477 0.0226310000 240203282 95654136 760807424 -0.0201784838 -0.0166919827 -0.0449792594 1323 1311867762.7605299950 0.0311503969 0.0196065979 0.0523451492 0.0051555359 0.0226380000 240205210 95654136 760807424 -0.0202651732 -0.0178229250 -0.0455889180 1324 1311867762.7905199528 0.0315858237 0.0196156457 0.0523451492 0.0051539365 0.0225600000 240378158 95654136 760807424 -0.0205272082 -0.0176643282 -0.0458851866 1325 1311867762.8258841038 0.0328431018 0.0196256287 0.0523451492 0.0051527565 0.0225860000 240381942 95654136 760807424 -0.0194578040 -0.0164765958 -0.0449276716 1326 1311867762.8593358994 0.0323413722 0.0196352182 0.0523451492 0.0051512575 0.0225750000 240383670 95654136 760807424 -0.0215211604 -0.0173657741 -0.0438969918 1327 1311867762.8911890984 0.0318215042 0.0196444016 0.0523451492 0.0051497515 0.0225140000 240387286 95654136 760807424 -0.0222725254 -0.0179451350 -0.0450060107 1328 1311867762.9231870174 0.0319388099 0.0196536594 0.0523451492 0.0051478877 0.0275100000 240389014 95654136 760807424 -0.0227841195 -0.0178821292 -0.0452540033 1329 1311867762.9586219788 0.0266009718 0.0196588869 0.0523451492 0.0051478425 0.0266700000 240392798 95654136 760807424 -0.0240896959 -0.0235238336 -0.0460423380 1330 1311867762.9910819530 0.0293082651 0.0196661420 0.0523451492 0.0051466078 0.0225740000 240396270 95654136 760807424 -0.0236323792 -0.0208224915 -0.0457943045 1331 1311867763.0241999626 0.0323818810 0.0196756956 0.0523451492 0.0051453248 0.0229290000 240398198 95654136 760807424 -0.0226844829 -0.0176353492 -0.0454388186 1332 1311867763.0586409569 0.0333412439 0.0196859550 0.0523451492 0.0051435540 0.0260360000 240570990 95654136 760807424 -0.0238483455 -0.0170419235 -0.0455153063 1333 1311867763.0910348892 0.0318345167 0.0196950687 0.0523451492 0.0051419211 0.0224260000 240572918 95654136 760807424 -0.0237751212 -0.0187838264 -0.0449165739 1334 1311867763.1222279072 0.0326741301 0.0197047981 0.0523451492 0.0051402233 0.0225340000 240576334 95654136 760807424 -0.0239137635 -0.0181818828 -0.0450202078 1335 1311867763.1606709957 0.0318656117 0.0197139073 0.0523451492 0.0051387942 0.0226250000 240580174 95654136 760807424 -0.0241199788 -0.0191274025 -0.0452101603 1336 1311867763.1913530827 0.0307070743 0.0197221358 0.0523451492 0.0051378134 0.0259330000 240581846 95654136 760807424 -0.0230748225 -0.0202645138 -0.0462133475 1337 1311867763.2239060402 0.0313632935 0.0197308427 0.0523451492 0.0051367699 0.0224870000 240585518 95654136 760807424 -0.0188468825 -0.0191669948 -0.0469083488 1338 1311867763.2619409561 0.0290486533 0.0197378067 0.0523451492 0.0051363667 0.0224590000 240589046 95654136 760807424 -0.0165373646 -0.0215571132 -0.0467341170 1339 1311867763.2997210026 0.0295330286 0.0197451220 0.0523451492 0.0051353558 0.0224780000 240591142 95654136 760807424 -0.0207248479 -0.0217271987 -0.0457547531 1340 1311867763.3283360004 0.0312161762 0.0197536825 0.0523451492 0.0051339118 0.0224560000 240594502 95654136 760807424 -0.0193373673 -0.0199785344 -0.0458075702 1341 1311867763.3595879078 0.0320314318 0.0197628382 0.0523451492 0.0051320119 0.0224160000 240596262 95654136 760807424 -0.0176794287 -0.0193149392 -0.0450954735 1342 1311867763.3930239677 0.0316239633 0.0197716765 0.0523451492 0.0051309184 0.0264840000 240599790 95654136 760807424 -0.0160447583 -0.0197715871 -0.0453847945 1343 1311867763.4231410027 0.0314863734 0.0197803993 0.0523451492 0.0051290417 0.0224870000 240603406 95654136 760807424 -0.0171469338 -0.0202070959 -0.0454889201 1344 1311867763.4599080086 0.0320709795 0.0197895441 0.0523451492 0.0051274985 0.0224680000 240605246 95654136 760807424 -0.0176993441 -0.0198321678 -0.0457951799 1345 1311867763.4920830727 0.0333098881 0.0197995964 0.0523451492 0.0051259071 0.0226840000 240608862 95654136 760807424 -0.0171970967 -0.0188208539 -0.0462046191 1346 1311867763.5240089893 0.0356913693 0.0198114031 0.0523451492 0.0051247981 0.0223860000 240610590 95654136 760807424 -0.0136321485 -0.0163776390 -0.0449910834 1347 1311867763.5586268902 0.0319412127 0.0198204081 0.0523451492 0.0051245953 0.0224700000 240614262 95654136 760807424 -0.0146861030 -0.0201442577 -0.0457441062 1348 1311867763.5911428928 0.0287615173 0.0198270410 0.0523451492 0.0051228823 0.0223820000 240617790 95654136 760807424 -0.0157167241 -0.0237623025 -0.0455270670 1349 1311867763.6315419674 0.0307322759 0.0198351249 0.0523451492 0.0051219591 0.0223990000 240619830 95654136 760807424 -0.0161767565 -0.0219615288 -0.0458603352 1350 1311867763.6613171101 0.0276353564 0.0198409029 0.0523451492 0.0051220026 0.0224060000 240623134 95654136 760807424 -0.0158021990 -0.0251775831 -0.0461005643 1351 1311867763.6906011105 0.0270374734 0.0198462297 0.0523451492 0.0051202382 0.0265950000 240625006 95654136 760807424 -0.0144823967 -0.0257869326 -0.0463715158 1352 1311867763.7281720638 0.0289700385 0.0198529781 0.0523451492 0.0051195121 0.0224890000 240797914 95654136 760807424 -0.0145986723 -0.0239897296 -0.0461136363 1353 1311867763.7617700100 0.0303095058 0.0198607065 0.0523451492 0.0051181313 0.0225050000 240801586 95654136 760807424 -0.0171741694 -0.0230918135 -0.0464653820 1354 1311867763.7929420471 0.0322220474 0.0198698360 0.0523451492 0.0051163964 0.0257250000 240803258 95654136 760807424 -0.0161345266 -0.0211373065 -0.0466036610 1355 1311867763.8308730125 0.0324870422 0.0198791476 0.0523451492 0.0051147880 0.0224070000 240807098 95654136 760807424 -0.0167400483 -0.0210393034 -0.0471877828 1356 1311867763.8622579575 0.0352819711 0.0198905066 0.0523451492 0.0051142521 0.0223500000 240810514 95654136 760807424 -0.0151518136 -0.0180924144 -0.0463783555 1357 1311867763.8950018883 0.0361674428 0.0199025014 0.0523451492 0.0051124477 0.0224040000 240812442 95654136 760807424 -0.0152409188 -0.0173874944 -0.0462489165 1358 1311867763.9286549091 0.0365289077 0.0199147447 0.0523451492 0.0051109027 0.0223350000 240815914 95654136 760807424 -0.0182294939 -0.0175061021 -0.0459507667 1359 1311867763.9622230530 0.0373293981 0.0199275590 0.0523451492 0.0051093860 0.0223050000 240817842 95654136 760807424 -0.0167746469 -0.0165660083 -0.0464374796 1360 1311867763.9930698872 0.0351369642 0.0199387424 0.0523451492 0.0051078951 0.0224090000 240821258 95654136 760807424 -0.0186267942 -0.0190865714 -0.0469185039 1361 1311867764.0303530693 0.0352062248 0.0199499603 0.0523451492 0.0051074594 0.0259560000 240825098 95654136 760807424 -0.0162592717 -0.0187615342 -0.0478804298 1362 1311867764.0625600815 0.0375986286 0.0199629182 0.0523451492 0.0051063851 0.0223190000 240826714 95654136 760807424 -0.0141489776 -0.0162443258 -0.0474430099 1363 1311867764.0939369202 0.0324647911 0.0199720905 0.0523451492 0.0051064611 0.0260120000 240999338 95654136 760807424 -0.0160605479 -0.0215022843 -0.0490579829 1364 1311867764.1303229332 0.0327649973 0.0199814695 0.0523451492 0.0051047402 0.0223300000 241001122 95654136 760807424 -0.0152534340 -0.0214245208 -0.0482834242 1365 1311867764.1600530148 0.0352467746 0.0199926528 0.0523451492 0.0051046807 0.0223650000 241004738 95654136 760807424 -0.0171664078 -0.0191248469 -0.0479444601 1366 1311867764.1931879520 0.0329681784 0.0200021517 0.0523451492 0.0051031792 0.0223970000 241008266 95654136 760807424 -0.0176379997 -0.0214541778 -0.0486073196 1367 1311867764.2289299965 0.0331520215 0.0200117713 0.0523451492 0.0051019725 0.0223460000 241010194 95654136 760807424 -0.0178386364 -0.0215533264 -0.0494183451 1368 1311867764.2623479366 0.0336473547 0.0200217388 0.0523451492 0.0051010870 0.0223370000 241182714 95654136 760807424 -0.0189444441 -0.0211816747 -0.0502730198 1369 1311867764.2925939560 0.0301996581 0.0200291734 0.0523451492 0.0051006579 0.0223440000 241184530 95654136 760807424 -0.0168923642 -0.0243711099 -0.0504725128 1370 1311867764.3292350769 0.0314143784 0.0200374837 0.0523451492 0.0051011665 0.0225990000 241188170 95654136 760807424 -0.0156325176 -0.0233388767 -0.0510225892 1371 1311867764.3632280827 0.0339706726 0.0200476465 0.0523451492 0.0051024252 0.0223310000 241191898 95654136 760807424 -0.0167973973 -0.0209715106 -0.0506473221 1372 1311867764.3937499523 0.0320960879 0.0200564282 0.0523451492 0.0051012634 0.0359110000 241193514 95654136 760807424 -0.0178411826 -0.0230957121 -0.0508163273 1373 1311867764.4299139977 0.0303251762 0.0200639072 0.0523451492 0.0051004986 0.0227970000 241197298 95654136 760807424 -0.0177390762 -0.0250093862 -0.0512001440 1374 1311867764.4600350857 0.0294423457 0.0200707329 0.0523451492 0.0050993370 0.0223880000 241200658 95654136 760807424 -0.0184216145 -0.0259050131 -0.0519274324 1375 1311867764.4931490421 0.0299132578 0.0200778911 0.0523451492 0.0050990386 0.0223020000 241202530 95654136 760807424 -0.0188421514 -0.0257798694 -0.0515814833 1376 1311867764.5289220810 0.0270750523 0.0200829762 0.0523451492 0.0051033260 0.0224020000 241375774 95654136 760807424 -0.0193283837 -0.0280907713 -0.0534719080 1377 1311867764.5604650974 0.0318126231 0.0200914945 0.0523451492 0.0051059947 0.0223060000 241377590 95654136 760807424 -0.0170208644 -0.0230542906 -0.0531789474 1378 1311867764.5906419754 0.0311202034 0.0200994979 0.0523451492 0.0051041508 0.0223280000 241381006 95654136 760807424 -0.0184728913 -0.0237555988 -0.0528324917 1379 1311867764.6277070045 0.0304621514 0.0201070125 0.0523451492 0.0051135332 0.0224500000 241384790 95654136 760807424 -0.0175857805 -0.0248623025 -0.0542285852 1380 1311867764.6609039307 0.0314709395 0.0201152473 0.0523451492 0.0051230002 0.0268180000 241386574 95654136 760807424 -0.0205599535 -0.0237635076 -0.0543488786 1381 1311867764.6907351017 0.0327032581 0.0201243624 0.0523451492 0.0051212477 0.0224440000 241390134 95654136 760807424 -0.0197848454 -0.0222862419 -0.0540960319 1382 1311867764.7274560928 0.0340496302 0.0201344386 0.0523451492 0.0051200517 0.0223430000 241391918 95654136 760807424 -0.0174721777 -0.0209926702 -0.0538386852 1383 1311867764.7591719627 0.0324512981 0.0201433445 0.0523451492 0.0051185506 0.0226100000 241395646 95654136 760807424 -0.0198941212 -0.0227952767 -0.0547173582 1384 1311867764.7921779156 0.0316805840 0.0201516806 0.0523451492 0.0051171283 0.0222710000 241399062 95654136 760807424 -0.0196083710 -0.0234237369 -0.0551034100 1385 1311867764.8278260231 0.0318982527 0.0201601619 0.0523451492 0.0051164553 0.0265170000 241401046 95654136 760807424 -0.0239129718 -0.0238220468 -0.0552852117 1386 1311867764.8610520363 0.0308882818 0.0201679022 0.0523451492 0.0051165927 0.0227020000 241404518 95654136 760807424 -0.0219550375 -0.0244848095 -0.0567066707 1387 1311867764.8946199417 0.0332048312 0.0201773016 0.0523451492 0.0051151270 0.0224130000 241406502 95654136 760807424 -0.0220936742 -0.0218856055 -0.0573177822 1388 1311867764.9271790981 0.0308734979 0.0201850078 0.0523451492 0.0051145517 0.0223030000 241409974 95654136 760807424 -0.0221378841 -0.0241506491 -0.0565567613 1389 1311867764.9599800110 0.0325621217 0.0201939186 0.0523451492 0.0051136212 0.0331490000 241413702 95654136 760807424 -0.0227026381 -0.0223357715 -0.0566066504 1390 1311867764.9950439930 0.0319705606 0.0202023910 0.0523451492 0.0051129026 0.0227250000 241415430 95654136 760807424 -0.0224716607 -0.0224787202 -0.0560747460 1391 1311867765.0330669880 0.0306555759 0.0202099059 0.0523451492 0.0051144051 0.0264300000 241419158 95654136 760807424 -0.0222670734 -0.0235122852 -0.0563676246 1392 1311867765.0598719120 0.0302657206 0.0202171299 0.0523451492 0.0051128018 0.0224030000 241422518 95654136 760807424 -0.0224821176 -0.0235508606 -0.0572223067 1393 1311867765.0951199532 0.0280686188 0.0202227663 0.0523451492 0.0051138251 0.0222590000 241424502 95654136 760807424 -0.0234190095 -0.0256091040 -0.0582949445 1394 1311867765.1273620129 0.0335313454 0.0202323133 0.0523451492 0.0051132565 0.0223450000 241427918 95654136 760807424 -0.0229192786 -0.0200572833 -0.0564419366 1395 1311867765.1595649719 0.0348872393 0.0202428187 0.0523451492 0.0051116059 0.0224140000 241429734 95654136 760807424 -0.0242450424 -0.0186693594 -0.0567379668 1396 1311867765.1969060898 0.0326438174 0.0202517019 0.0523451492 0.0051101436 0.0264750000 241433262 95654136 760807424 -0.0245820340 -0.0209187288 -0.0570754595 1397 1311867765.2290871143 0.0347420461 0.0202620744 0.0523451492 0.0051093704 0.0260640000 241436934 95654136 760807424 -0.0283847302 -0.0193774514 -0.0569555722 1398 1311867765.2611060143 0.0329388715 0.0202711422 0.0523451492 0.0051096890 0.0223210000 241438606 95654136 760807424 -0.0238079391 -0.0204265472 -0.0582905337 1399 1311867765.2958459854 0.0313449614 0.0202790577 0.0523451492 0.0051079640 0.0223820000 241442278 95654136 760807424 -0.0234425031 -0.0218880083 -0.0581522062 1400 1311867765.3289039135 0.0312111992 0.0202868664 0.0523451492 0.0051063576 0.0223770000 241444062 95654136 760807424 -0.0227675419 -0.0218031351 -0.0589969456 1401 1311867765.3593490124 0.0335096940 0.0202963045 0.0523451492 0.0051070299 0.0264750000 241447678 95654136 760807424 -0.0255131498 -0.0195129253 -0.0581752993 1402 1311867765.3951449394 0.0335211270 0.0203057373 0.0523451492 0.0051052965 0.0223930000 241451262 95654136 760807424 -0.0249420274 -0.0192217398 -0.0581302717 1403 1311867765.4278709888 0.0324709192 0.0203144082 0.0523451492 0.0051044352 0.0223940000 241453078 95654136 760807424 -0.0275985114 -0.0206467770 -0.0583094917 1404 1311867765.4589679241 0.0330782421 0.0203234992 0.0523451492 0.0051033267 0.0223700000 241456550 95654136 760807424 -0.0264767446 -0.0193824489 -0.0606252402 1405 1311867765.4974000454 0.0341788940 0.0203333607 0.0523451492 0.0051023481 0.0223430000 241458590 95654136 760807424 -0.0284700859 -0.0180460736 -0.0605977438 1406 1311867765.5298929214 0.0356316529 0.0203442414 0.0523451492 0.0051009444 0.0345520000 241462118 95654136 760807424 -0.0258217994 -0.0159270074 -0.0595958158 1407 1311867765.5625720024 0.0316068456 0.0203522461 0.0523451492 0.0051006219 0.0229390000 241465790 95654136 760807424 -0.0254849717 -0.0193860047 -0.0606176741 1408 1311867765.5947990417 0.0325217210 0.0203608892 0.0523451492 0.0050992439 0.0224110000 241467462 95654136 760807424 -0.0254979525 -0.0180986505 -0.0606278554 1409 1311867765.6310911179 0.0327948965 0.0203697139 0.0523451492 0.0050979099 0.0225280000 241471190 95654136 760807424 -0.0263136942 -0.0175260026 -0.0611018315 1410 1311867765.6618249416 0.0303807333 0.0203768139 0.0523451492 0.0050964617 0.0225690000 241474662 95654136 760807424 -0.0266485866 -0.0198048316 -0.0606932044 1411 1311867765.6966838837 0.0288538672 0.0203828218 0.0523451492 0.0050950091 0.0266310000 241476590 95654136 760807424 -0.0277460255 -0.0212617032 -0.0605484173 1412 1311867765.7292089462 0.0302633364 0.0203898193 0.0523451492 0.0050932787 0.0235090000 241480174 95654136 760807424 -0.0265603848 -0.0195719711 -0.0601175092 1413 1311867765.7602009773 0.0308862384 0.0203972478 0.0523451492 0.0050918282 0.0224000000 241481990 95654136 760807424 -0.0277454443 -0.0188558791 -0.0611633584 1414 1311867765.7960450649 0.0292699672 0.0204035227 0.0523451492 0.0050904339 0.0322940000 241485574 95654136 760807424 -0.0291422475 -0.0203692093 -0.0628363937 1415 1311867765.8298408985 0.0295397192 0.0204099793 0.0523451492 0.0050891307 0.0228270000 241489246 95654136 760807424 -0.0295181051 -0.0201151893 -0.0621875897 1416 1311867765.8610999584 0.0318840370 0.0204180825 0.0523451492 0.0050877391 0.0262030000 241490918 95654136 760807424 -0.0282807723 -0.0174544826 -0.0616667047 1417 1311867765.8960449696 0.0308188237 0.0204254225 0.0523451492 0.0050860209 0.0225190000 241494646 95654136 760807424 -0.0290651619 -0.0186648015 -0.0616337359 1418 1311867765.9303019047 0.0293138940 0.0204316908 0.0523451492 0.0050845920 0.0224800000 241496430 95654136 760807424 -0.0288754795 -0.0199915972 -0.0625595450 1419 1311867765.9612519741 0.0285121966 0.0204373853 0.0523451492 0.0050829525 0.0224850000 241499990 95654136 760807424 -0.0310938638 -0.0213488489 -0.0621348098 1420 1311867765.9962689877 0.0314900838 0.0204451689 0.0523451492 0.0050820010 0.0224920000 241503518 95654136 760807424 -0.0302705523 -0.0182318203 -0.0604832582 1421 1311867766.0289440155 0.0315102823 0.0204529557 0.0523451492 0.0050803008 0.0225130000 241505502 95654136 760807424 -0.0303109381 -0.0182515383 -0.0607406311 1422 1311867766.0606811047 0.0329269134 0.0204617279 0.0523451492 0.0050790718 0.0225370000 241508974 95654136 760807424 -0.0253852550 -0.0162810162 -0.0605565682 1423 1311867766.0968139172 0.0326442234 0.0204702890 0.0523451492 0.0050774209 0.0225490000 241510958 95654136 760807424 -0.0268997587 -0.0165460724 -0.0598421469 1424 1311867766.1277561188 0.0335515365 0.0204794753 0.0523451492 0.0050759297 0.0226470000 241514318 95654136 760807424 -0.0275444631 -0.0155422995 -0.0590272173 1425 1311867766.1625239849 0.0325943306 0.0204879769 0.0523451492 0.0050746203 0.0232980000 241518102 95654136 760807424 -0.0279542208 -0.0165229775 -0.0588186607 1426 1311867766.1968889236 0.0317741930 0.0204958915 0.0523451492 0.0050730414 0.0261200000 241519830 95654136 760807424 -0.0278974492 -0.0172664486 -0.0582217686 1427 1311867766.2298009396 0.0328272060 0.0205045329 0.0523451492 0.0050715526 0.0367660000 241523558 95654136 760807424 -0.0274409633 -0.0160498619 -0.0575297326 1428 1311867766.2654640675 0.0314167663 0.0205121746 0.0523451492 0.0050720111 0.0233080000 241527086 95654136 760807424 -0.0273284353 -0.0174232237 -0.0577796176 1429 1311867766.2981679440 0.0309726354 0.0205194947 0.0523451492 0.0050709437 0.0228110000 241698622 95654136 760807424 -0.0278097373 -0.0177237932 -0.0562272072 1430 1311867766.3291699886 0.0327748246 0.0205280648 0.0523451492 0.0050816734 0.0227310000 241702094 95654136 760807424 -0.0282023922 -0.0165996775 -0.0541919246 1431 1311867766.3653209209 0.0329946801 0.0205367767 0.0523451492 0.0050974447 0.0337950000 241704022 95654136 760807424 -0.0273883585 -0.0153231742 -0.0524273850 1432 1311867766.3979220390 0.0348772705 0.0205467910 0.0523451492 0.0051024891 0.0230880000 241707550 95654136 760807424 -0.0269270446 -0.0131721944 -0.0511749834 1433 1311867766.4302849770 0.0310436189 0.0205541160 0.0523451492 0.0051051170 0.0228200000 241711278 95654136 760807424 -0.0280550234 -0.0176256523 -0.0509055331 1434 1311867766.4642350674 0.0307810791 0.0205612478 0.0523451492 0.0051084662 0.0230340000 241712950 95654136 760807424 -0.0277759805 -0.0181495547 -0.0507243648 1435 1311867766.4967210293 0.0293347538 0.0205673618 0.0523451492 0.0051068644 0.0227850000 241716622 95654136 760807424 -0.0265513640 -0.0196065549 -0.0503862388 1436 1311867766.5302040577 0.0296954140 0.0205737183 0.0523451492 0.0051053676 0.0227800000 241718238 95654136 760807424 -0.0285614636 -0.0201439820 -0.0494481996 1437 1311867766.5639820099 0.0273586065 0.0205784399 0.0523451492 0.0051046148 0.0228260000 241721966 95654136 760807424 -0.0286091585 -0.0231391061 -0.0502417274 1438 1311867766.5953519344 0.0289383139 0.0205842534 0.0523451492 0.0051034821 0.0229400000 241725438 95654136 760807424 -0.0282208025 -0.0220190603 -0.0508852676 1439 1311867766.6287128925 0.0294701681 0.0205904285 0.0523451492 0.0051018295 0.0336620000 241727366 95654136 760807424 -0.0281277075 -0.0221574176 -0.0512339510 1440 1311867766.6636400223 0.0279443916 0.0205955354 0.0523451492 0.0051014413 0.0231740000 241730894 95654136 760807424 -0.0250625443 -0.0238640253 -0.0516029112 1441 1311867766.6964800358 0.0266611557 0.0205997447 0.0523451492 0.0051149916 0.0267040000 241732710 95654136 760807424 -0.0238505937 -0.0253778845 -0.0520692542 1442 1311867766.7300829887 0.0267173965 0.0206039872 0.0523451492 0.0051243203 0.0228670000 241736294 95654136 760807424 -0.0205134861 -0.0258667301 -0.0538111404 1443 1311867766.7628269196 0.0281929709 0.0206092464 0.0523451492 0.0051230246 0.0228000000 241739966 95654136 760807424 -0.0232026428 -0.0255946517 -0.0554577671 1444 1311867766.7970418930 0.0296112690 0.0206154805 0.0523451492 0.0051218297 0.0228730000 241741638 95654136 760807424 -0.0205058604 -0.0242388360 -0.0562062263 1445 1311867766.8299551010 0.0347079858 0.0206252331 0.0523451492 0.0051233645 0.0229690000 241745310 95654136 760807424 -0.0204834435 -0.0194400530 -0.0559114665 1446 1311867766.8662180901 0.0344862826 0.0206348189 0.0523451492 0.0051219976 0.0228710000 241748950 95654136 760807424 -0.0203012731 -0.0200279839 -0.0570065677 1447 1311867766.8958721161 0.0325378291 0.0206430449 0.0523451492 0.0051206243 0.0228090000 241750654 95654136 760807424 -0.0214945544 -0.0223933626 -0.0593269430 1448 1311867766.9286260605 0.0336038135 0.0206519957 0.0523451492 0.0051296310 0.0228590000 241754182 95654136 760807424 -0.0208141580 -0.0218004920 -0.0589833520 1449 1311867766.9661469460 0.0338637494 0.0206611135 0.0523451492 0.0051432674 0.0237790000 241756222 95654136 760807424 -0.0187945832 -0.0205954649 -0.0599678978 1450 1311867766.9956479073 0.0305874161 0.0206679592 0.0523451492 0.0051449982 0.0229520000 241929138 95654136 760807424 -0.0207277052 -0.0244165827 -0.0617718734 1451 1311867767.0294270515 0.0288591422 0.0206736044 0.0523451492 0.0051437523 0.0230250000 241932922 95654136 760807424 -0.0201609973 -0.0259397887 -0.0610535182 1452 1311867767.0660951138 0.0312888473 0.0206809152 0.0523451492 0.0051424112 0.0230160000 241934650 95654136 760807424 -0.0178273320 -0.0230782293 -0.0600407161 1453 1311867767.0968320370 0.0316811502 0.0206884859 0.0523451492 0.0051423345 0.0230530000 241938322 95654136 760807424 -0.0178249162 -0.0227536075 -0.0616167784 1454 1311867767.1276900768 0.0300755147 0.0206949419 0.0523451492 0.0051418030 0.0230260000 241939938 95654136 760807424 -0.0179687049 -0.0247954410 -0.0602869317 1455 1311867767.1632909775 0.0313860178 0.0207022897 0.0523451492 0.0051408852 0.0260710000 241943722 95654136 760807424 -0.0193384569 -0.0239574965 -0.0602158718 1456 1311867767.1955349445 0.0323728696 0.0207103052 0.0523451492 0.0051400546 0.0230370000 241947194 95654136 760807424 -0.0196153428 -0.0231205467 -0.0597609580 1457 1311867767.2308650017 0.0294189751 0.0207162824 0.0523451492 0.0051400346 0.0230360000 241949234 95654136 760807424 -0.0172786228 -0.0259948317 -0.0600671619 1458 1311867767.2658200264 0.0314679816 0.0207236566 0.0523451492 0.0051405900 0.0229900000 241952762 95654136 760807424 -0.0198194124 -0.0243274085 -0.0598290376 1459 1311867767.2981290817 0.0310095176 0.0207307066 0.0523451492 0.0051389207 0.0272400000 241954634 95654136 760807424 -0.0195003096 -0.0244862288 -0.0608175881 1460 1311867767.3362140656 0.0294801928 0.0207366994 0.0523451492 0.0051391966 0.0265980000 241958274 95654136 760807424 -0.0198808424 -0.0258464515 -0.0605637170 1461 1311867767.3633511066 0.0284323953 0.0207419668 0.0523451492 0.0051378223 0.0231170000 241961834 95654136 760807424 -0.0220818482 -0.0274080373 -0.0612253882 1462 1311867767.3987689018 0.0303729381 0.0207485543 0.0523451492 0.0051372411 0.0231120000 241963618 95654136 760807424 -0.0187445637 -0.0247824974 -0.0606369674 1463 1311867767.4331369400 0.0317469649 0.0207560720 0.0523451492 0.0051357091 0.0235620000 241967346 95654136 760807424 -0.0197034813 -0.0231916681 -0.0607244745 1464 1311867767.4638109207 0.0297986474 0.0207622487 0.0523451492 0.0051347234 0.0274170000 241970762 95654136 760807424 -0.0204908308 -0.0250944737 -0.0603717081 1465 1311867767.4974899292 0.0317943506 0.0207697791 0.0523451492 0.0051338112 0.0233040000 241972690 95654136 760807424 -0.0220611747 -0.0231112577 -0.0594411641 1466 1311867767.5351889133 0.0298228655 0.0207759545 0.0523451492 0.0051361800 0.0232830000 241976330 95654136 760807424 -0.0228725709 -0.0243261792 -0.0587899648 1467 1311867767.5664100647 0.0287880655 0.0207814160 0.0523451492 0.0051413947 0.0232320000 241978202 95654136 760807424 -0.0232526511 -0.0255698282 -0.0586692169 1468 1311867767.5953979492 0.0296664312 0.0207874685 0.0523451492 0.0051397071 0.0232130000 241981562 95654136 760807424 -0.0228824243 -0.0245636534 -0.0588233583 1469 1311867767.6338059902 0.0291185994 0.0207931398 0.0523451492 0.0051387964 0.0232990000 241985402 95654136 760807424 -0.0232437588 -0.0253234897 -0.0583301894 1470 1311867767.6632149220 0.0277646575 0.0207978823 0.0523451492 0.0051381855 0.0233130000 242156894 95654136 760807424 -0.0208883137 -0.0262641888 -0.0578608885 1471 1311867767.6991050243 0.0301917233 0.0208042683 0.0523451492 0.0051377864 0.0232920000 242160678 95654136 760807424 -0.0218217764 -0.0241428483 -0.0578493066 1472 1311867767.7346129417 0.0314627923 0.0208115092 0.0523451492 0.0051361486 0.0260010000 242162406 95654136 760807424 -0.0223891828 -0.0229853317 -0.0592791922 1473 1311867767.7651679516 0.0313841663 0.0208186868 0.0523451492 0.0051344804 0.0271260000 242166078 95654136 760807424 -0.0210787728 -0.0229911115 -0.0586964451 1474 1311867767.7999849319 0.0305682998 0.0208253012 0.0523451492 0.0051328370 0.0233170000 242169606 95654136 760807424 -0.0207783524 -0.0238559600 -0.0585403219 1475 1311867767.8344929218 0.0303673260 0.0208317704 0.0523451492 0.0051315606 0.0234750000 242171478 95654136 760807424 -0.0204623342 -0.0240005776 -0.0596019700 1476 1311867767.8673300743 0.0305659436 0.0208383654 0.0523451492 0.0051299996 0.0234740000 242174950 95654136 760807424 -0.0200259406 -0.0236726608 -0.0592975132 1477 1311867767.8966870308 0.0293972977 0.0208441602 0.0523451492 0.0051282856 0.0233420000 242176710 95654136 760807424 -0.0204628054 -0.0247384906 -0.0594650805 1478 1311867767.9358460903 0.0326855443 0.0208521719 0.0523451492 0.0051273931 0.0233480000 242180406 95654136 760807424 -0.0221819226 -0.0213934947 -0.0595860146 1479 1311867767.9646739960 0.0307485331 0.0208588632 0.0523451492 0.0051259787 0.0234240000 242184022 95654136 760807424 -0.0224131010 -0.0231534149 -0.0593235381 1480 1311867767.9988079071 0.0298479516 0.0208649369 0.0523451492 0.0051254023 0.0234880000 242185750 95654136 760807424 -0.0248772334 -0.0242801607 -0.0589112751 1481 1311867768.0346310139 0.0314325877 0.0208720724 0.0523451492 0.0051243645 0.0234740000 242189534 95654136 760807424 -0.0262881294 -0.0226814821 -0.0584374852 1482 1311867768.0639820099 0.0316797271 0.0208793650 0.0523451492 0.0051232455 0.0234830000 242192894 95654136 760807424 -0.0252849478 -0.0221300665 -0.0582736209 1483 1311867768.0985600948 0.0302040856 0.0208856527 0.0523451492 0.0051227703 0.0234610000 242194878 95654136 760807424 -0.0253042933 -0.0235017072 -0.0602253824 1484 1311867768.1352849007 0.0315241851 0.0208928215 0.0523451492 0.0051213694 0.0234870000 242367870 95654136 760807424 -0.0253108069 -0.0222149082 -0.0602223389 1485 1311867768.1651999950 0.0326520540 0.0209007402 0.0523451492 0.0051198248 0.0234670000 242369686 95654136 760807424 -0.0258793794 -0.0211526006 -0.0609532110 1486 1311867768.1962070465 0.0317373648 0.0209080327 0.0523451492 0.0051181365 0.0235400000 242373102 95654136 760807424 -0.0257103313 -0.0218841992 -0.0607893057 1487 1311867768.2323460579 0.0302198306 0.0209142948 0.0523451492 0.0051173171 0.0234650000 242376886 95654136 760807424 -0.0262347851 -0.0233696010 -0.0608538911 1488 1311867768.2749121189 0.0333711281 0.0209226664 0.0523451492 0.0051163901 0.0234810000 242378894 95654136 760807424 -0.0235273428 -0.0194305759 -0.0608903319 1489 1311867768.2962079048 0.0336654522 0.0209312243 0.0523451492 0.0051147017 0.0235350000 242382230 95654136 760807424 -0.0237630885 -0.0188176557 -0.0606601201 1490 1311867768.3351829052 0.0308636054 0.0209378903 0.0523451492 0.0051175285 0.0244220000 242554782 95654136 760807424 -0.0274036154 -0.0214859918 -0.0603357926 1491 1311867768.3693380356 0.0291951839 0.0209434284 0.0523451492 0.0051161306 0.0237450000 242558398 95654136 760807424 -0.0273609329 -0.0229268204 -0.0602859855 1492 1311867768.4011199474 0.0331962556 0.0209516408 0.0523451492 0.0051160600 0.0236440000 242561814 95654136 760807424 -0.0265767742 -0.0185602736 -0.0599810146 1493 1311867768.4324789047 0.0343457647 0.0209606121 0.0523451492 0.0051144322 0.0236530000 242563574 95654136 760807424 -0.0265835058 -0.0169958603 -0.0597341955 1494 1311867768.4655070305 0.0332053155 0.0209688080 0.0523451492 0.0051132527 0.0270380000 242567046 95654136 760807424 -0.0285067298 -0.0184688028 -0.0589984283 1495 1311867768.4980540276 0.0330054015 0.0209768592 0.0523451492 0.0051120354 0.0277420000 242568974 95654136 760807424 -0.0251706000 -0.0177918598 -0.0598757938 1496 1311867768.5367710590 0.0354711004 0.0209865479 0.0523451492 0.0051114153 0.0270830000 242572558 95654136 760807424 -0.0241685659 -0.0148065658 -0.0596303493 1497 1311867768.5648899078 0.0349573940 0.0209958804 0.0523451492 0.0051103344 0.0237980000 242746206 95654136 760807424 -0.0247328505 -0.0154844597 -0.0583199523 1498 1311867768.5998411179 0.0326037258 0.0210036293 0.0523451492 0.0051087499 0.0276450000 242747934 95654136 760807424 -0.0268441997 -0.0181856714 -0.0584516153 1499 1311867768.6319470406 0.0335201994 0.0210119793 0.0523451492 0.0051072307 0.0236770000 242751606 95654136 760807424 -0.0261704680 -0.0170238260 -0.0580057204 1500 1311867768.6643230915 0.0364010856 0.0210222387 0.0523451492 0.0051059593 0.0236420000 242755134 95654136 760807424 -0.0234994851 -0.0137225799 -0.0584483147 1501 1311867768.7014238834 0.0340257324 0.0210309019 0.0523451492 0.0051047920 0.0276920000 242757062 95654136 760807424 -0.0241276529 -0.0159287397 -0.0578189120 1502 1311867768.7344141006 0.0298341233 0.0210367629 0.0523451492 0.0051036964 0.0240340000 242930554 95654136 760807424 -0.0251802951 -0.0203648787 -0.0566735268 1503 1311867768.7646389008 0.0322812311 0.0210442443 0.0523451492 0.0051029062 0.0245940000 242932370 95654136 760807424 -0.0234919190 -0.0176433586 -0.0563201979 1504 1311867768.8039369583 0.0346071534 0.0210532622 0.0523451492 0.0051014132 0.0237250000 242936010 95654136 760807424 -0.0225988682 -0.0149917286 -0.0565047860 1505 1311867768.8365039825 0.0346326493 0.0210622850 0.0523451492 0.0050998910 0.0237350000 242939738 95654136 760807424 -0.0242450833 -0.0149762649 -0.0554972887 1506 1311867768.8651020527 0.0326982588 0.0210700114 0.0523451492 0.0050999099 0.0276910000 242941298 95654136 760807424 -0.0225070454 -0.0168423150 -0.0545644164 1507 1311867768.9001519680 0.0352330245 0.0210794096 0.0523451492 0.0050986262 0.0237840000 242945082 95654136 760807424 -0.0222039968 -0.0140703414 -0.0545050800 1508 1311867768.9330470562 0.0351019315 0.0210887083 0.0523451492 0.0050974999 0.0237810000 242946698 95654136 760807424 -0.0227257516 -0.0140605560 -0.0539291129 1509 1311867768.9639101028 0.0331745148 0.0210967175 0.0523451492 0.0050967754 0.0237780000 242950314 95654136 760807424 -0.0213467591 -0.0158693101 -0.0529163033 1510 1311867768.9992640018 0.0332474560 0.0211047643 0.0523451492 0.0050959684 0.0237890000 243123678 95654136 760807424 -0.0222100671 -0.0156506449 -0.0524755493 1511 1311867769.0331530571 0.0332742855 0.0211128183 0.0523451492 0.0050949072 0.0238610000 243125494 95654136 760807424 -0.0217799768 -0.0151424296 -0.0525841303 1512 1311867769.0641028881 0.0325354338 0.0211203729 0.0523451492 0.0050935361 0.0246900000 243128966 95654136 760807424 -0.0220571589 -0.0158434138 -0.0517187975 1513 1311867769.0999929905 0.0315194577 0.0211272461 0.0523451492 0.0050920062 0.0238930000 243130950 95654136 760807424 -0.0219470151 -0.0170277730 -0.0509524718 1514 1311867769.1327989101 0.0317534208 0.0211342647 0.0523451492 0.0050904540 0.0277970000 243134366 95654136 760807424 -0.0211089216 -0.0164859947 -0.0522210486 1515 1311867769.1643240452 0.0319568031 0.0211414083 0.0523451492 0.0050945025 0.0238770000 243138038 95654136 760807424 -0.0207096972 -0.0166407153 -0.0515328571 1516 1311867769.2002429962 0.0334902927 0.0211495540 0.0523451492 0.0050947936 0.0271600000 243139766 95654136 760807424 -0.0201938823 -0.0149465688 -0.0512400568 1517 1311867769.2324860096 0.0337814949 0.0211578809 0.0523451492 0.0050964137 0.0278970000 243313482 95654136 760807424 -0.0195216667 -0.0147880940 -0.0506823994 1518 1311867769.2636189461 0.0331316628 0.0211657687 0.0523451492 0.0050964423 0.0238590000 243316954 95654136 760807424 -0.0210175030 -0.0152480798 -0.0497311093 1519 1311867769.3002018929 0.0346520059 0.0211746471 0.0523451492 0.0051014810 0.0238480000 243318882 95654136 760807424 -0.0219216701 -0.0132438652 -0.0501988456 1520 1311867769.3330841064 0.0360672250 0.0211844449 0.0523451492 0.0051004794 0.0238860000 243322354 95654136 760807424 -0.0220883470 -0.0112763066 -0.0503427871 1521 1311867769.3653230667 0.0376959927 0.0211953006 0.0523451492 0.0050988197 0.0240060000 243324338 95654136 760807424 -0.0208326392 -0.0090616643 -0.0502170138 1522 1311867769.3995320797 0.0364467092 0.0212053212 0.0523451492 0.0050976227 0.0268440000 243497790 95654136 760807424 -0.0208979212 -0.0097561898 -0.0493000299 1523 1311867769.4340240955 0.0351838656 0.0212144995 0.0523451492 0.0050960817 0.0238980000 243501462 95654136 760807424 -0.0221792292 -0.0106549058 -0.0495153926 1524 1311867769.4644269943 0.0358175784 0.0212240816 0.0523451492 0.0050991854 0.0240820000 243503134 95654136 760807424 -0.0232547820 -0.0101002324 -0.0495037772 1525 1311867769.4999239445 0.0357842036 0.0212336292 0.0523451492 0.0051009460 0.0240430000 243506918 95654136 760807424 -0.0230962373 -0.0095396852 -0.0494326428 1526 1311867769.5317490101 0.0325287879 0.0212410310 0.0523451492 0.0051000407 0.0240030000 243508534 95654136 760807424 -0.0227947999 -0.0128502315 -0.0493609309 1527 1311867769.5660109520 0.0337147713 0.0212491998 0.0523451492 0.0050987696 0.0240470000 243512150 95654136 760807424 -0.0243105181 -0.0118146492 -0.0496705323 1528 1311867769.6002509594 0.0354236066 0.0212584762 0.0523451492 0.0050971388 0.0239470000 243515678 95654136 760807424 -0.0236342810 -0.0099829445 -0.0495276265 1529 1311867769.6330249310 0.0351466164 0.0212675594 0.0523451492 0.0050971448 0.0241560000 243687598 95654136 760807424 -0.0217197686 -0.0099535715 -0.0494746193 1530 1311867769.6637229919 0.0361235514 0.0212772692 0.0523451492 0.0050959536 0.0249370000 243691014 95654136 760807424 -0.0228803940 -0.0091982055 -0.0491533242 1531 1311867769.7014029026 0.0358534791 0.0212867899 0.0523451492 0.0050974699 0.0282300000 243693110 95654136 760807424 -0.0208698772 -0.0090653216 -0.0491961353 1532 1311867769.7340829372 0.0370815247 0.0212970998 0.0523451492 0.0050960165 0.0240970000 243696526 95654136 760807424 -0.0213001221 -0.0076272036 -0.0478780270 1533 1311867769.7641069889 0.0374008939 0.0213076045 0.0523451492 0.0051041239 0.0241380000 243700198 95654136 760807424 -0.0218261797 -0.0069505475 -0.0470314175 1534 1311867769.8003458977 0.0374674648 0.0213181390 0.0523451492 0.0051250816 0.0241020000 243871818 95654136 760807424 -0.0234740116 -0.0065796431 -0.0464119390 1535 1311867769.8341090679 0.0373165347 0.0213285614 0.0523451492 0.0051240549 0.0242560000 243875546 95654136 760807424 -0.0228883140 -0.0062988074 -0.0455716923 1536 1311867769.8692820072 0.0381021574 0.0213394817 0.0523451492 0.0051234586 0.0242340000 243879130 95654136 760807424 -0.0258010644 -0.0053768605 -0.0451633446 1537 1311867769.9001140594 0.0397554636 0.0213514635 0.0523451492 0.0051220662 0.0242770000 243881002 95654136 760807424 -0.0257484801 -0.0030127415 -0.0449068770 1538 1311867769.9321451187 0.0420590080 0.0213649274 0.0523451492 0.0051207671 0.0243920000 244055534 95654136 760807424 -0.0264087263 -0.0001721357 -0.0450803675 1539 1311867769.9684319496 0.0380681455 0.0213757807 0.0523451492 0.0051201322 0.0356250000 244057518 95654136 760807424 -0.0270616300 -0.0038404162 -0.0442264564 1540 1311867770.0010259151 0.0390030257 0.0213872270 0.0523451492 0.0051186630 0.0246270000 244061102 95654136 760807424 -0.0261893012 -0.0022398641 -0.0438729003 1541 1311867770.0330319405 0.0392719395 0.0213988329 0.0523451492 0.0051175413 0.0244640000 244064718 95654136 760807424 -0.0241726097 -0.0011780177 -0.0428840965 1542 1311867770.0690810680 0.0376340561 0.0214093616 0.0523451492 0.0051181641 0.0253510000 244066502 95654136 760807424 -0.0244877338 -0.0025555249 -0.0420019850 1543 1311867770.1002650261 0.0380610153 0.0214201533 0.0523451492 0.0051178638 0.0243790000 244070174 95654136 760807424 -0.0243150871 -0.0017825497 -0.0419847071 1544 1311867770.1335709095 0.0375285037 0.0214305862 0.0523451492 0.0051164919 0.0243620000 244071846 95654136 760807424 -0.0233583823 -0.0018877360 -0.0412013717 1545 1311867770.1684958935 0.0371759199 0.0214407774 0.0523451492 0.0051156234 0.0245010000 244246862 95654136 760807424 -0.0245448630 -0.0022147028 -0.0412198268 1546 1311867770.2001299858 0.0375044830 0.0214511678 0.0523451492 0.0051141423 0.0244410000 244250334 95654136 760807424 -0.0232201386 -0.0016154252 -0.0411527790 1547 1311867770.2336180210 0.0383874662 0.0214621157 0.0523451492 0.0051137525 0.0242930000 244252206 95654136 760807424 -0.0244901124 -0.0007770910 -0.0414789692 1548 1311867770.2679719925 0.0374689624 0.0214724560 0.0523451492 0.0051152898 0.0244950000 244255734 95654136 760807424 -0.0254566036 -0.0013223429 -0.0413217247 1549 1311867770.3009040356 0.0386939421 0.0214835738 0.0523451492 0.0051146700 0.0244490000 244257606 95654136 760807424 -0.0232187621 -0.0001782560 -0.0410571210 1550 1311867770.3339090347 0.0361894108 0.0214930615 0.0523451492 0.0051150712 0.0244640000 244261134 95654136 760807424 -0.0238284171 -0.0024483483 -0.0405089520 1551 1311867770.3681850433 0.0360361449 0.0215024381 0.0523451492 0.0051293938 0.0281380000 244264862 95654136 760807424 -0.0234836768 -0.0028583780 -0.0402976014 1552 1311867770.4014930725 0.0363921821 0.0215120320 0.0523451492 0.0051324749 0.0247290000 244266534 95654136 760807424 -0.0230243690 -0.0022519932 -0.0403266475 1553 1311867770.4333899021 0.0361705981 0.0215214708 0.0523451492 0.0051321458 0.0245540000 244440634 95654136 760807424 -0.0247928426 -0.0025348072 -0.0401943438 1554 1311867770.4684588909 0.0360086001 0.0215307933 0.0523451492 0.0051307399 0.0244520000 244444162 95654136 760807424 -0.0268883239 -0.0029342351 -0.0399824083 1555 1311867770.5046019554 0.0357880667 0.0215399620 0.0523451492 0.0051293234 0.0344250000 244446146 95654136 760807424 -0.0258733761 -0.0029362901 -0.0398355946 1556 1311867770.5338129997 0.0356962681 0.0215490599 0.0523451492 0.0051279186 0.0247580000 244449506 95654136 760807424 -0.0251433272 -0.0029603471 -0.0393088572 1557 1311867770.5683600903 0.0355142802 0.0215580292 0.0523451492 0.0051328701 0.0285280000 244451434 95654136 760807424 -0.0242987107 -0.0029729602 -0.0389672630 1558 1311867770.6027359962 0.0362901837 0.0215674850 0.0523451492 0.0051340201 0.0245650000 244454962 95654136 760807424 -0.0227948986 -0.0015399361 -0.0385536589 1559 1311867770.6331069469 0.0359826945 0.0215767314 0.0523451492 0.0051328183 0.0245350000 244458578 95654136 760807424 -0.0231420193 -0.0017050245 -0.0382240750 1560 1311867770.6699299812 0.0359124765 0.0215859210 0.0523451492 0.0051314343 0.0244880000 244460418 95654136 760807424 -0.0244743489 -0.0017556306 -0.0377607755 1561 1311867770.7014191151 0.0359308384 0.0215951106 0.0523451492 0.0051298760 0.0246290000 244464090 95654136 760807424 -0.0242460910 -0.0016393859 -0.0372615047 1562 1311867770.7347331047 0.0359136350 0.0216042774 0.0523451492 0.0051284206 0.0245650000 244465818 95654136 760807424 -0.0231416915 -0.0013812437 -0.0371234827 1563 1311867770.7684218884 0.0362619534 0.0216136553 0.0523451492 0.0051286017 0.0343000000 244640146 95654136 760807424 -0.0266297646 -0.0013276422 -0.0367442407 1564 1311867770.8017508984 0.0352180935 0.0216223538 0.0523451492 0.0051274713 0.0248990000 244643618 95654136 760807424 -0.0266291033 -0.0024643526 -0.0363745056 1565 1311867770.8396499157 0.0389020741 0.0216333951 0.0523451492 0.0051279227 0.0246350000 244645714 95654136 760807424 -0.0267593954 0.0015116548 -0.0364746638 1566 1311867770.8699400425 0.0385918505 0.0216442243 0.0523451492 0.0051269535 0.0292930000 244649130 95654136 760807424 -0.0274006557 0.0010920179 -0.0360875577 1567 1311867770.9027009010 0.0362870321 0.0216535688 0.0523451492 0.0051257981 0.0248990000 244651002 95654136 760807424 -0.0264783558 -0.0010026356 -0.0353166498 1568 1311867770.9355690479 0.0395743437 0.0216649978 0.0523451492 0.0051252674 0.0246800000 244654530 95654136 760807424 -0.0254383981 0.0028094652 -0.0354678333 1569 1311867770.9692869186 0.0381802432 0.0216755238 0.0523451492 0.0051241477 0.0246470000 244658258 95654136 760807424 -0.0242641997 0.0017187755 -0.0348121673 1570 1311867771.0021619797 0.0359727629 0.0216846303 0.0523451492 0.0051250240 0.0247070000 244659930 95654136 760807424 -0.0259329956 -0.0005349972 -0.0346895941 1571 1311867771.0365509987 0.0388886333 0.0216955813 0.0523451492 0.0051330764 0.0370310000 244663602 95654136 760807424 -0.0253768768 0.0029034717 -0.0349362083 1572 1311867771.0685739517 0.0391992517 0.0217067160 0.0523451492 0.0051316158 0.0250900000 244667130 95654136 760807424 -0.0246107243 0.0039711935 -0.0348665565 1573 1311867771.1014111042 0.0375811197 0.0217168078 0.0523451492 0.0051329481 0.0247610000 244669058 95654136 760807424 -0.0254739784 0.0025948496 -0.0341484956 1574 1311867771.1381099224 0.0378550887 0.0217270608 0.0523451492 0.0051320665 0.0247490000 244842922 95654136 760807424 -0.0269996822 0.0029914971 -0.0344386436 1575 1311867771.1686840057 0.0385747477 0.0217377577 0.0523451492 0.0051304874 0.0248040000 244844738 95654136 760807424 -0.0274826847 0.0037850100 -0.0341845751 1576 1311867771.2019159794 0.0369597375 0.0217474164 0.0523451492 0.0051295291 0.0247710000 244848210 95654136 760807424 -0.0290552564 0.0018500676 -0.0331579931 1577 1311867771.2363801003 0.0380125791 0.0217577303 0.0523451492 0.0051281845 0.0247480000 244851938 95654136 760807424 -0.0275045782 0.0035494114 -0.0333973393 1578 1311867771.2705540657 0.0374758989 0.0217676912 0.0523451492 0.0051266469 0.0248040000 244853722 95654136 760807424 -0.0256334599 0.0034686753 -0.0332635716 1579 1311867771.3016860485 0.0349972621 0.0217760696 0.0523451492 0.0051259110 0.0249330000 244857338 95654136 760807424 -0.0231872555 0.0012986700 -0.0324451588 1580 1311867771.3360719681 0.0338793136 0.0217837299 0.0523451492 0.0051243817 0.0248080000 244859066 95654136 760807424 -0.0242236145 0.0002073239 -0.0316456817 1581 1311867771.3679900169 0.0345233232 0.0217917878 0.0523451492 0.0051228415 0.0248840000 244862738 95654136 760807424 -0.0249490459 0.0010712531 -0.0314199701 1582 1311867771.4030399323 0.0360432975 0.0218007964 0.0523451492 0.0051213598 0.0247690000 244866266 95654136 760807424 -0.0241410788 0.0032978207 -0.0314161927 1583 1311867771.4361710548 0.0323177166 0.0218074400 0.0523451492 0.0051203141 0.0248230000 245038454 95654136 760807424 -0.0250689611 -0.0005198391 -0.0305186678 1584 1311867771.4682569504 0.0324389637 0.0218141518 0.0523451492 0.0051196013 0.0287600000 245068998 95654136 760807424 -0.0227130111 0.0006455452 -0.0310322661 1585 1311867771.5008640289 0.0345283598 0.0218221734 0.0523451492 0.0051183549 0.0292010000 245071190 95654136 760807424 -0.0203264579 0.0034930171 -0.0310784411 1586 1311867771.5365910530 0.0322352536 0.0218287391 0.0523451492 0.0051168637 0.0289130000 245074838 95654136 760807424 -0.0203259140 0.0015260270 -0.0302092005 1587 1311867771.5686171055 0.0301092602 0.0218339568 0.0523451492 0.0051158915 0.0288570000 245078758 95654136 760807424 -0.0198006369 -0.0001522368 -0.0300588962 1588 1311867771.6077210903 0.0324839503 0.0218406633 0.0523451492 0.0051156756 0.0400110000 245080662 95654136 760807424 -0.0187444855 0.0029160527 -0.0295900814 1589 1311867771.6366779804 0.0314664654 0.0218467211 0.0523451492 0.0051142654 0.0386810000 245084414 95654136 760807424 -0.0171116162 0.0019305245 -0.0283556357 1590 1311867771.6715440750 0.0282801576 0.0218507673 0.0523451492 0.0051128379 0.0291870000 245088062 95654136 760807424 -0.0196297988 -0.0012470464 -0.0270131435 1591 1311867771.7024850845 0.0332828052 0.0218579527 0.0523451492 0.0051123806 0.0350850000 245260722 95654136 760807424 -0.0183195136 0.0047457949 -0.0278371572 1592 1311867771.7367300987 0.0327650383 0.0218648039 0.0523451492 0.0051117475 0.0350480000 245264194 95654136 760807424 -0.0168929957 0.0046824729 -0.0271731596 1593 1311867771.7697410583 0.0278733354 0.0218685757 0.0523451492 0.0051131648 0.0347970000 245266442 95654136 760807424 -0.0160431582 -0.0001203683 -0.0260581281 1594 1311867771.8023030758 0.0285171047 0.0218727467 0.0523451492 0.0051120123 0.0438940000 245269850 95654136 760807424 -0.0158767775 0.0011477123 -0.0264657289 1595 1311867771.8386220932 0.0290659107 0.0218772565 0.0523451492 0.0051113770 0.0292520000 245273754 95654136 760807424 -0.0156839564 0.0021181593 -0.0269133057 1596 1311867771.8711829185 0.0274648760 0.0218807575 0.0523451492 0.0051098990 0.0288470000 245447822 95654136 760807424 -0.0152026992 0.0005226062 -0.0262858309 1597 1311867771.9016489983 0.0273897573 0.0218842071 0.0523451492 0.0051086544 0.0291200000 245451622 95654136 760807424 -0.0167329181 0.0004831537 -0.0262532290 1598 1311867771.9377520084 0.0283344947 0.0218882436 0.0523451492 0.0051081627 0.0298870000 245453598 95654136 760807424 -0.0177215263 0.0015690138 -0.0265049394 1599 1311867771.9696009159 0.0274436697 0.0218917179 0.0523451492 0.0051075274 0.0291570000 245457334 95654136 760807424 -0.0180901643 0.0007408463 -0.0268704463 1600 1311867772.0018649101 0.0263606217 0.0218945110 0.0523451492 0.0051061285 0.0289370000 245460798 95654136 760807424 -0.0172695275 -0.0004062639 -0.0263148285 1601 1311867772.0375399590 0.0274432302 0.0218979768 0.0523451492 0.0051056357 0.0434280000 245462790 95654136 760807424 -0.0178290009 0.0009505939 -0.0266167838 1602 1311867772.0696671009 0.0274534840 0.0219014446 0.0523451492 0.0051044287 0.0292690000 245466254 95654136 760807424 -0.0163143501 0.0014915577 -0.0267215334 1603 1311867772.1012299061 0.0258124657 0.0219038844 0.0523451492 0.0051031519 0.0290420000 245468262 95654136 760807424 -0.0145377079 0.0000535188 -0.0257636830 1604 1311867772.1369819641 0.0250168443 0.0219058252 0.0523451492 0.0051020126 0.0289680000 245471798 95654136 760807424 -0.0136509612 -0.0004465597 -0.0255131237 1605 1311867772.1690549850 0.0263376459 0.0219085865 0.0523451492 0.0051008449 0.0291380000 245475590 95654136 760807424 -0.0142595991 0.0012325135 -0.0256027747 1606 1311867772.2016880512 0.0265443977 0.0219114730 0.0523451492 0.0050993665 0.0347180000 245477382 95654136 760807424 -0.0154020758 0.0016533604 -0.0258136299 1607 1311867772.2370250225 0.0253795814 0.0219136311 0.0523451492 0.0050979485 0.0291760000 245481118 95654136 760807424 -0.0162133388 0.0004609200 -0.0253905691 1608 1311867772.2710011005 0.0265254062 0.0219164992 0.0523451492 0.0050964983 0.0443890000 245484766 95654136 760807424 -0.0134975212 0.0023758332 -0.0263335332 1609 1311867772.3046050072 0.0271420162 0.0219197468 0.0523451492 0.0050951196 0.0292740000 245658238 95654136 760807424 -0.0120701753 0.0031705562 -0.0260824021 1610 1311867772.3366808891 0.0260144640 0.0219222901 0.0523451492 0.0050936949 0.0290300000 245661782 95654136 760807424 -0.0139023950 0.0018722750 -0.0253559183 1611 1311867772.3689630032 0.0269432850 0.0219254068 0.0523451492 0.0050922834 0.0294040000 245663774 95654136 760807424 -0.0142005412 0.0028452235 -0.0252325740 1612 1311867772.4054839611 0.0290983319 0.0219298565 0.0523451492 0.0050909523 0.0292500000 245667478 95654136 760807424 -0.0125076976 0.0053310911 -0.0257594455 1613 1311867772.4385271072 0.0285205469 0.0219339425 0.0523451492 0.0050895883 0.0251020000 245671150 95654136 760807424 -0.0128987310 0.0046180636 -0.0258110352 1614 1311867772.4697830677 0.0275961328 0.0219374507 0.0523451492 0.0050880175 0.0251860000 245672766 95654136 760807424 -0.0142834233 0.0036681755 -0.0255518258 1615 1311867772.5049729347 0.0316972882 0.0219434939 0.0523451492 0.0050874448 0.0357130000 245676742 95654136 760807424 -0.0138081424 0.0080950167 -0.0267986637 1616 1311867772.5382430553 0.0319729000 0.0219497003 0.0523451492 0.0050862758 0.0295610000 245678606 95654136 760807424 -0.0141758416 0.0087149050 -0.0272127483 1617 1311867772.5713028908 0.0319540538 0.0219558872 0.0523451492 0.0050847892 0.0250750000 245682334 95654136 760807424 -0.0145113412 0.0086986879 -0.0272941999 1618 1311867772.6077790260 0.0325798877 0.0219624534 0.0523451492 0.0050840029 0.0250240000 245685862 95654136 760807424 -0.0132282851 0.0096464371 -0.0276888814 1619 1311867772.6382429600 0.0347124860 0.0219703286 0.0523451492 0.0050825859 0.0294960000 245687870 95654136 760807424 -0.0136971930 0.0120427944 -0.0275199451 1620 1311867772.6695280075 0.0341328792 0.0219778364 0.0523451492 0.0050828773 0.0291540000 245691534 95654136 760807424 -0.0132860858 0.0114908349 -0.0276148487 1621 1311867772.7066609859 0.0338693000 0.0219851722 0.0523451492 0.0050814372 0.0251800000 245693518 95654136 760807424 -0.0126428474 0.0113770654 -0.0267914385 1622 1311867772.7385280132 0.0345605202 0.0219929252 0.0523451492 0.0050801381 0.0348480000 245697118 95654136 760807424 -0.0115603795 0.0121365748 -0.0264156684 1623 1311867772.7712020874 0.0336689278 0.0220001193 0.0523451492 0.0050787957 0.0251050000 245700846 95654136 760807424 -0.0134369871 0.0114780990 -0.0260997564 1624 1311867772.8056819439 0.0329808965 0.0220068809 0.0523451492 0.0050777362 0.0250960000 245702630 95654136 760807424 -0.0146747809 0.0110988412 -0.0258211140 1625 1311867772.8384070396 0.0338042006 0.0220141408 0.0523451492 0.0050761988 0.0251280000 245876786 95654136 760807424 -0.0131780310 0.0120963110 -0.0253472161 1626 1311867772.8747529984 0.0331251174 0.0220209741 0.0523451492 0.0050746553 0.0251030000 245880426 95654136 760807424 -0.0136562716 0.0115696713 -0.0250669718 1627 1311867772.9054989815 0.0328097492 0.0220276052 0.0523451492 0.0050732291 0.0252460000 245882242 95654136 760807424 -0.0153743438 0.0113583654 -0.0245834626 1628 1311867772.9415910244 0.0351523608 0.0220356671 0.0523451492 0.0050744523 0.0288890000 245885770 95654136 760807424 -0.0160626452 0.0141030801 -0.0248723477 1629 1311867772.9716000557 0.0364389494 0.0220445089 0.0523451492 0.0050729177 0.0252410000 245887586 95654136 760807424 -0.0155464336 0.0156426132 -0.0253617261 1630 1311867773.0115981102 0.0331403464 0.0220513161 0.0523451492 0.0050721949 0.0251510000 245891226 95654136 760807424 -0.0158549696 0.0124063883 -0.0242175087 1631 1311867773.0406711102 0.0337980986 0.0220585183 0.0523451492 0.0050711414 0.0292590000 245894842 95654136 760807424 -0.0143721513 0.0132496012 -0.0239104349 1632 1311867773.0706710815 0.0350582600 0.0220664838 0.0523451492 0.0050700315 0.0295180000 245896402 95654136 760807424 -0.0141814556 0.0146676768 -0.0235150084 1633 1311867773.1044468880 0.0330272131 0.0220731959 0.0523451492 0.0050696697 0.0251200000 245900130 95654136 760807424 -0.0150794564 0.0125924982 -0.0228258502 1634 1311867773.1367809772 0.0310470778 0.0220786878 0.0523451492 0.0050689261 0.0251620000 245901802 95654136 760807424 -0.0156275835 0.0105473250 -0.0227137506 1635 1311867773.1702499390 0.0325990990 0.0220851223 0.0523451492 0.0050678437 0.0292050000 245905530 95654136 760807424 -0.0155990021 0.0123466859 -0.0233902913 1636 1311867773.2047750950 0.0328412838 0.0220916970 0.0523451492 0.0050665292 0.0251000000 245909058 95654136 760807424 -0.0149142295 0.0128434179 -0.0239845756 1637 1311867773.2366468906 0.0333697498 0.0220985865 0.0523451492 0.0050651486 0.0250430000 245910930 95654136 760807424 -0.0131849675 0.0135431923 -0.0226691980 1638 1311867773.2714850903 0.0338008553 0.0221057307 0.0523451492 0.0050661023 0.0292240000 246084890 95654136 760807424 -0.0099790320 0.0142742433 -0.0222617239 1639 1311867773.3104391098 0.0334795266 0.0221126702 0.0523451492 0.0050667349 0.0250920000 246086930 95654136 760807424 -0.0117816012 0.0142294522 -0.0210961811 1640 1311867773.3365778923 0.0321071520 0.0221187644 0.0523451492 0.0050655875 0.0252090000 246090178 95654136 760807424 -0.0133407358 0.0130468067 -0.0212870259 1641 1311867773.3720550537 0.0303818919 0.0221237998 0.0523451492 0.0050661077 0.0289400000 246093962 95654136 760807424 -0.0106529417 0.0112895425 -0.0206668228 1642 1311867773.4075679779 0.0294777229 0.0221282784 0.0523451492 0.0050660328 0.0250520000 246095690 95654136 760807424 -0.0104138078 0.0106273172 -0.0200081654 1643 1311867773.4431231022 0.0288867895 0.0221323920 0.0523451492 0.0050656876 0.0251000000 246099474 95654136 760807424 -0.0092966110 0.0101574622 -0.0191535298 1644 1311867773.4752271175 0.0281104818 0.0221360283 0.0523451492 0.0050652163 0.0258810000 246102946 95654136 760807424 -0.0100669842 0.0095949005 -0.0186864343 1645 1311867773.5056390762 0.0284632277 0.0221398746 0.0523451492 0.0050641699 0.0251590000 246104762 95654136 760807424 -0.0110645946 0.0104000708 -0.0189440008 1646 1311867773.5412580967 0.0312920175 0.0221454348 0.0523451492 0.0050633874 0.0292570000 246108346 95654136 760807424 -0.0102396952 0.0136394184 -0.0192514379 1647 1311867773.5752460957 0.0295801330 0.0221499489 0.0523451492 0.0050620745 0.0251910000 246110274 95654136 760807424 -0.0126673607 0.0120440843 -0.0184534825 1648 1311867773.6103789806 0.0275607668 0.0221532322 0.0523451492 0.0050610393 0.0250920000 246113858 95654136 760807424 -0.0134125678 0.0102037052 -0.0180111211 1649 1311867773.6384060383 0.0301961601 0.0221581096 0.0523451492 0.0050601330 0.0249180000 246117362 95654136 760807424 -0.0145500870 0.0132599976 -0.0178947765 1650 1311867773.6767098904 0.0302601792 0.0221630200 0.0523451492 0.0050603013 0.0252020000 246290118 95654136 760807424 -0.0128230415 0.0133882174 -0.0172561519 1651 1311867773.7092239857 0.0286920127 0.0221669746 0.0523451492 0.0050591449 0.0251020000 246293790 95654136 760807424 -0.0113715697 0.0118425675 -0.0161517244 1652 1311867773.7367770672 0.0282742381 0.0221706714 0.0523451492 0.0050582558 0.0250830000 246295294 95654136 760807424 -0.0108165946 0.0114707882 -0.0152727896 1653 1311867773.7767388821 0.0306785069 0.0221758183 0.0523451492 0.0050574322 0.0250060000 246299190 95654136 760807424 -0.0102992011 0.0147349397 -0.0159695130 1654 1311867773.8052179813 0.0302692484 0.0221807116 0.0523451492 0.0050569280 0.0288390000 246302550 95654136 760807424 -0.0134540815 0.0140169980 -0.0148126185 1655 1311867773.8394160271 0.0283716489 0.0221844523 0.0523451492 0.0050563519 0.0290370000 246304478 95654136 760807424 -0.0139293559 0.0119422227 -0.0146705089 1656 1311867773.8739800453 0.0280842576 0.0221880150 0.0523451492 0.0050548993 0.0251080000 246308006 95654136 760807424 -0.0136915874 0.0115583614 -0.0145830112 1657 1311867773.9096889496 0.0299115758 0.0221926762 0.0523451492 0.0050537892 0.0250540000 246309990 95654136 760807424 -0.0138199003 0.0134046413 -0.0150100607 1658 1311867773.9369859695 0.0300822966 0.0221974347 0.0523451492 0.0050528814 0.0250170000 246313294 95654136 760807424 -0.0134965274 0.0133252311 -0.0142384311 1659 1311867773.9740200043 0.0314099379 0.0222029878 0.0523451492 0.0050514582 0.0250520000 246317134 95654136 760807424 -0.0112971924 0.0145787997 -0.0154182315 1660 1311867774.0073120594 0.0321829095 0.0222089998 0.0523451492 0.0050513503 0.0250860000 246318806 95654136 760807424 -0.0096292812 0.0154286483 -0.0161272325 1661 1311867774.0389740467 0.0324488953 0.0222151647 0.0523451492 0.0050512953 0.0250330000 246322534 95654136 760807424 -0.0115175266 0.0155936563 -0.0157036930 1662 1311867774.0735630989 0.0326250196 0.0222214281 0.0523451492 0.0050516808 0.0286380000 246326062 95654136 760807424 -0.0072948309 0.0154582616 -0.0156741701 1663 1311867774.1093399525 0.0329848975 0.0222279004 0.0523451492 0.0050561926 0.0250240000 246328046 95654136 760807424 -0.0082749426 0.0160090942 -0.0160027053 1664 1311867774.1424911022 0.0337338373 0.0222348151 0.0523451492 0.0050580263 0.0250550000 246331574 95654136 760807424 -0.0076161702 0.0166178718 -0.0155618191 1665 1311867774.1754300594 0.0354798026 0.0222427700 0.0523451492 0.0050578556 0.0250490000 246333446 95654136 760807424 -0.0073310160 0.0185727943 -0.0165218748 1666 1311867774.2059481144 0.0368191451 0.0222515193 0.0523451492 0.0050566429 0.0250030000 246336918 95654136 760807424 -0.0052382406 0.0199950226 -0.0159796625 1667 1311867774.2384989262 0.0361796245 0.0222598745 0.0523451492 0.0050555740 0.0250690000 246511850 95654136 760807424 -0.0049562673 0.0193775352 -0.0151765272 1668 1311867774.2744109631 0.0335808434 0.0222666617 0.0523451492 0.0050541905 0.0250300000 246513690 95654136 760807424 -0.0062923944 0.0169135462 -0.0137773314 1669 1311867774.3046739101 0.0333723947 0.0222733158 0.0523451492 0.0050534490 0.0250670000 246517306 95654136 760807424 -0.0064233192 0.0170019437 -0.0131688416 1670 1311867774.3375370502 0.0355893634 0.0222812895 0.0523451492 0.0050536428 0.0312930000 246518978 95654136 760807424 -0.0029362871 0.0189999398 -0.0134838233 1671 1311867774.3727159500 0.0334221125 0.0222879566 0.0523451492 0.0050525075 0.0251010000 246522706 95654136 760807424 -0.0018658570 0.0164823029 -0.0121023618 1672 1311867774.4051818848 0.0337153599 0.0222947912 0.0523451492 0.0050520822 0.0250740000 246526234 95654136 760807424 -0.0013762889 0.0169350449 -0.0118843885 1673 1311867774.4376831055 0.0350442640 0.0223024119 0.0523451492 0.0050521855 0.0288750000 246528106 95654136 760807424 -0.0024288460 0.0190802831 -0.0115919570 1674 1311867774.4740140438 0.0333464630 0.0223090093 0.0523451492 0.0050511479 0.0250530000 246531690 95654136 760807424 -0.0046150223 0.0176374000 -0.0101616299 1675 1311867774.5066258907 0.0339525603 0.0223159607 0.0523451492 0.0050497151 0.0250390000 246533618 95654136 760807424 -0.0049951295 0.0183711108 -0.0104985619 1676 1311867774.5394051075 0.0351343602 0.0223236089 0.0523451492 0.0050487776 0.0250060000 246537090 95654136 760807424 -0.0029192078 0.0193226822 -0.0106985578 1677 1311867774.5727870464 0.0358784497 0.0223316917 0.0523451492 0.0050481128 0.0288590000 246540762 95654136 760807424 -0.0033604228 0.0204180814 -0.0103818243 1678 1311867774.6076970100 0.0358765908 0.0223397638 0.0523451492 0.0050467947 0.0356790000 246542546 95654136 760807424 -0.0048312908 0.0210228022 -0.0101715578 1679 1311867774.6373310089 0.0355229974 0.0223476156 0.0523451492 0.0050454633 0.0251390000 246546162 95654136 760807424 -0.0042325961 0.0208202917 -0.0105144735 1680 1311867774.6731650829 0.0386724360 0.0223573327 0.0523451492 0.0050441152 0.0288450000 246549690 95654136 760807424 -0.0036488911 0.0241820626 -0.0116751818 1681 1311867774.7048470974 0.0390685387 0.0223672740 0.0523451492 0.0050427071 0.0258830000 246551618 95654136 760807424 -0.0042812326 0.0251513906 -0.0112085231 1682 1311867774.7448370457 0.0401268005 0.0223778326 0.0523451492 0.0050430658 0.0250060000 246555314 95654136 760807424 -0.0030489452 0.0264679492 -0.0109723341 1683 1311867774.7731618881 0.0429396816 0.0223900499 0.0523451492 0.0050421373 0.0249510000 246557018 95654136 760807424 -0.0007336342 0.0292207748 -0.0119167296 1684 1311867774.8052101135 0.0416244790 0.0224014718 0.0523451492 0.0050412126 0.0249880000 246731946 95654136 760807424 -0.0002560524 0.0278234277 -0.0098946262 1685 1311867774.8443410397 0.0419567712 0.0224130773 0.0523451492 0.0050401441 0.0287570000 246735786 95654136 760807424 0.0005929423 0.0283825044 -0.0095598241 1686 1311867774.8735189438 0.0427979641 0.0224251680 0.0523451492 0.0050395191 0.0249940000 246737402 95654136 760807424 0.0024270131 0.0289293732 -0.0097073689 1687 1311867774.9063620567 0.0411508977 0.0224362680 0.0523451492 0.0050384228 0.0289780000 246741074 95654136 760807424 0.0017796915 0.0274459664 -0.0085467361 1688 1311867774.9433379173 0.0411097594 0.0224473305 0.0523451492 0.0050369482 0.0251020000 246742914 95654136 760807424 0.0010348922 0.0280423407 -0.0091990111 1689 1311867774.9730870724 0.0429109186 0.0224594463 0.0523451492 0.0050356450 0.0250010000 246746474 95654136 760807424 0.0032259983 0.0295085683 -0.0100957388 1690 1311867775.0104990005 0.0423896201 0.0224712393 0.0523451492 0.0050342640 0.0248850000 246750170 95654136 760807424 0.0034780768 0.0290520452 -0.0096263038 1691 1311867775.0417571068 0.0437567383 0.0224838268 0.0523451492 0.0050330591 0.0249530000 246751986 95654136 760807424 0.0052980697 0.0299593955 -0.0100757852 1692 1311867775.0737869740 0.0433496088 0.0224961589 0.0523451492 0.0050321836 0.0249380000 246755458 95654136 760807424 0.0070540006 0.0290297046 -0.0086487569 1693 1311867775.1060369015 0.0430333279 0.0225082895 0.0523451492 0.0050310564 0.0345020000 246757330 95654136 760807424 0.0046707513 0.0297816433 -0.0084771635 1694 1311867775.1426749229 0.0405956693 0.0225189668 0.0523451492 0.0050297111 0.0250830000 246760914 95654136 760807424 0.0038996395 0.0273149833 -0.0066455826 1695 1311867775.1733469963 0.0376859270 0.0225279149 0.0523451492 0.0050286758 0.0249470000 246764530 95654136 760807424 0.0026699998 0.0244796164 -0.0055301879 1696 1311867775.2047309875 0.0368217938 0.0225363429 0.0523451492 0.0050273228 0.0249600000 246766258 95654136 760807424 0.0005671049 0.0245492700 -0.0064359335 1697 1311867775.2407341003 0.0358309783 0.0225441771 0.0523451492 0.0050265410 0.0248910000 246770042 95654136 760807424 0.0019780686 0.0232967939 -0.0067507895 1698 1311867775.2726259232 0.0368788391 0.0225526192 0.0523451492 0.0050256819 0.0248540000 246773458 95654136 760807424 0.0001620300 0.0253884662 -0.0079755653 1699 1311867775.3058989048 0.0340874977 0.0225594084 0.0523451492 0.0050244540 0.0249480000 246775386 95654136 760807424 -0.0024928474 0.0231739040 -0.0065131811 1700 1311867775.3405869007 0.0347947590 0.0225666056 0.0523451492 0.0050263946 0.0288550000 246778970 95654136 760807424 -0.0039727679 0.0246783663 -0.0076880525 1701 1311867775.3728890419 0.0356120206 0.0225742749 0.0523451492 0.0050267559 0.0247930000 246780898 95654136 760807424 -0.0037876714 0.0258582421 -0.0076319296 1702 1311867775.4055740833 0.0350609645 0.0225816114 0.0523451492 0.0050261548 0.0249650000 246784370 95654136 760807424 -0.0056544957 0.0253194124 -0.0064519295 1703 1311867775.4408710003 0.0351381190 0.0225889846 0.0523451492 0.0050254920 0.0249580000 246788154 95654136 760807424 -0.0040391292 0.0255898144 -0.0070649176 1704 1311867775.4725620747 0.0368312038 0.0225973427 0.0523451492 0.0050244764 0.0248820000 246789770 95654136 760807424 -0.0066645537 0.0280593745 -0.0079162298 1705 1311867775.5057229996 0.0361378416 0.0226052843 0.0523451492 0.0050232321 0.0293190000 246793554 95654136 760807424 -0.0055588065 0.0272099003 -0.0064340411 1706 1311867775.5413000584 0.0353802517 0.0226127726 0.0523451492 0.0050222069 0.0252820000 246795338 95654136 760807424 -0.0068796668 0.0269439239 -0.0062856129 1707 1311867775.5736858845 0.0379658118 0.0226217667 0.0523451492 0.0050208746 0.0248560000 246798954 95654136 760807424 -0.0069151213 0.0299222115 -0.0075524291 1708 1311867775.6086819172 0.0398525894 0.0226318550 0.0523451492 0.0050196167 0.0247920000 246802482 95654136 760807424 -0.0058269333 0.0319288969 -0.0080705490 1709 1311867775.6414420605 0.0413038693 0.0226427807 0.0523451492 0.0050185870 0.0280780000 246804466 95654136 760807424 -0.0071626422 0.0337579325 -0.0085980836 1710 1311867775.6726739407 0.0397308059 0.0226527737 0.0523451492 0.0050178470 0.0249720000 246978758 95654136 760807424 -0.0039001708 0.0321321264 -0.0081563080 1711 1311867775.7051100731 0.0403577052 0.0226631214 0.0523451492 0.0050167766 0.0248500000 246980686 95654136 760807424 -0.0039234478 0.0331198163 -0.0082781846 1712 1311867775.7416241169 0.0413113795 0.0226740141 0.0523451492 0.0050153971 0.0249670000 246984270 95654136 760807424 -0.0038412581 0.0343333818 -0.0085795829 1713 1311867775.7742578983 0.0403213948 0.0226843161 0.0523451492 0.0050144527 0.0249170000 246987942 95654136 760807424 -0.0010833468 0.0331248306 -0.0076528159 1714 1311867775.8062939644 0.0420809798 0.0226956327 0.0523451492 0.0050133718 0.0248540000 246989614 95654136 760807424 0.0010546905 0.0348483510 -0.0084049404 1715 1311867775.8408269882 0.0436803438 0.0227078687 0.0523451492 0.0050121844 0.0248610000 246993398 95654136 760807424 -0.0011894042 0.0374410078 -0.0095889494 1716 1311867775.8729701042 0.0447740406 0.0227207278 0.0523451492 0.0050114049 0.0248000000 246996814 95654136 760807424 0.0006755770 0.0384827517 -0.0092486460 1717 1311867775.9066479206 0.0474624187 0.0227351376 0.0523451492 0.0050100759 0.0377600000 246998798 95654136 760807424 0.0016630766 0.0411555842 -0.0098597370 1718 1311867775.9435749054 0.0472189337 0.0227493890 0.0523451492 0.0050095163 0.0252370000 247002326 95654136 760807424 -0.0002742491 0.0416916087 -0.0099203298 1719 1311867775.9730579853 0.0469181426 0.0227634488 0.0523451492 0.0050085553 0.0247260000 247004142 95654136 760807424 0.0001473788 0.0415849052 -0.0093089500 1720 1311867776.0135231018 0.0454180539 0.0227766200 0.0523451492 0.0050077541 0.0247740000 247007838 95654136 760807424 -0.0037248344 0.0408770852 -0.0081550470 1721 1311867776.0423479080 0.0441695116 0.0227890505 0.0523451492 0.0050067507 0.0250230000 247011342 95654136 760807424 -0.0011639167 0.0392914452 -0.0078946482 1722 1311867776.0782909393 0.0444356464 0.0228016211 0.0523451492 0.0050054797 0.0281480000 247013182 95654136 760807424 -0.0016945188 0.0399060175 -0.0078687370 1723 1311867776.1090068817 0.0436368994 0.0228137136 0.0523451492 0.0050049383 0.0247690000 247016854 95654136 760807424 -0.0004031186 0.0391651280 -0.0073305164 1724 1311867776.1410119534 0.0441620462 0.0228260966 0.0523451492 0.0050037184 0.0287610000 247018526 95654136 760807424 -0.0000679060 0.0396900512 -0.0076110456 1725 1311867776.1773319244 0.0457091555 0.0228393622 0.0523451492 0.0050025080 0.0249290000 247022310 95654136 760807424 0.0013880811 0.0411003828 -0.0085079074 1726 1311867776.2094259262 0.0483193994 0.0228541246 0.0523451492 0.0050012624 0.0249100000 247025782 95654136 760807424 0.0011454842 0.0440877564 -0.0103577171 1727 1311867776.2407069206 0.0480455160 0.0228687114 0.0523451492 0.0050001620 0.0248360000 247027654 95654136 760807424 -0.0006308131 0.0442834385 -0.0098205544 1728 1311867776.2753469944 0.0472296365 0.0228828092 0.0523451492 0.0049987949 0.0247900000 247031238 95654136 760807424 -0.0010522979 0.0437315702 -0.0095147211 1729 1311867776.3120670319 0.0459279418 0.0228961378 0.0523451492 0.0049975799 0.0248310000 247033166 95654136 760807424 -0.0025988987 0.0429262593 -0.0089046489 1730 1311867776.3407590389 0.0457683392 0.0229093587 0.0523451492 0.0049968730 0.0248540000 247036638 95654136 760807424 0.0006757057 0.0423256680 -0.0091453902 1731 1311867776.3730750084 0.0450923145 0.0229221738 0.0523451492 0.0049970325 0.0247520000 247040310 95654136 760807424 -0.0021274786 0.0422608368 -0.0088932244 1732 1311867776.4097070694 0.0443235599 0.0229345303 0.0523451492 0.0049957675 0.0365230000 247042150 95654136 760807424 -0.0038301228 0.0418459512 -0.0081070289 1733 1311867776.4422268867 0.0441989787 0.0229468006 0.0523451492 0.0049947398 0.0251970000 247045822 95654136 760807424 -0.0041265152 0.0419848040 -0.0082949298 1734 1311867776.4727520943 0.0461823642 0.0229602006 0.0523451492 0.0049935873 0.0247310000 247049238 95654136 760807424 -0.0015141314 0.0436874591 -0.0090011256 1735 1311867776.5105879307 0.0451767072 0.0229730055 0.0523451492 0.0049925736 0.0247630000 247051278 95654136 760807424 -0.0011184127 0.0427713618 -0.0079486743 1736 1311867776.5415630341 0.0475127883 0.0229871413 0.0523451492 0.0049916329 0.0246920000 247054694 95654136 760807424 0.0000966762 0.0449759141 -0.0087443991 1737 1311867776.5743160248 0.0491371788 0.0230021960 0.0523451492 0.0049903691 0.0247520000 247056622 95654136 760807424 -0.0009963545 0.0469330475 -0.0094271265 1738 1311867776.6094930172 0.0511814617 0.0230184096 0.0523451492 0.0049889875 0.0355410000 247060206 95654136 760807424 0.0004684607 0.0489546917 -0.0099790562 1739 1311867776.6413109303 0.0513554178 0.0230347046 0.0523451492 0.0049875981 0.0250300000 247234846 95654136 760807424 0.0006705847 0.0493345559 -0.0088098552 1740 1311867776.6763460636 0.0505967289 0.0230505449 0.0523451492 0.0049869768 0.0334310000 247236686 95654136 760807424 0.0042424933 0.0482373573 -0.0074511212 1741 1311867776.7134280205 0.0517191738 0.0230670116 0.0523451492 0.0049857485 0.0252880000 247240470 95654136 760807424 0.0064623458 0.0492084287 -0.0073303068 1742 1311867776.7423970699 0.0535926893 0.0230845350 0.0535926893 0.0049864172 0.0248160000 247242030 95654136 760807424 0.0094436910 0.0504088476 -0.0070661698 1743 1311867776.7739920616 0.0573835969 0.0231042131 0.0573835969 0.0049852644 0.0246940000 247245814 95654136 760807424 0.0095721241 0.0546342731 -0.0086918920 1744 1311867776.8117430210 0.0572929382 0.0231238168 0.0573835969 0.0049849055 0.0250060000 247249510 95654136 760807424 0.0092481002 0.0550698712 -0.0074524949 1745 1311867776.8449618816 0.0584892482 0.0231440835 0.0584892482 0.0049841653 0.0246610000 247251494 95654136 760807424 0.0076773809 0.0571198836 -0.0073972777 1746 1311867776.8748989105 0.0585943907 0.0231643872 0.0585943907 0.0049828940 0.0246730000 247254910 95654136 760807424 0.0084052123 0.0572882146 -0.0060754921 1747 1311867776.9104089737 0.0597725697 0.0231853421 0.0597725697 0.0049818649 0.0246650000 247256894 95654136 760807424 0.0098958900 0.0583336689 -0.0061619910 1748 1311867776.9465129375 0.0590550192 0.0232058625 0.0597725697 0.0049805668 0.0324820000 247260534 95654136 760807424 0.0097712362 0.0579045787 -0.0054886113 1749 1311867776.9780058861 0.0548577718 0.0232239597 0.0597725697 0.0049797638 0.0247250000 247264206 95654136 760807424 0.0075953389 0.0544252619 -0.0020818475 1750 1311867777.0103049278 0.0531891473 0.0232410826 0.0597725697 0.0049787241 0.0246160000 247265990 95654136 760807424 0.0042121294 0.0537130721 -0.0014679518 1751 1311867777.0430829525 0.0501902625 0.0232564734 0.0597725697 0.0049774975 0.0246570000 247269718 95654136 760807424 0.0047566122 0.0504949205 0.0003849835 1752 1311867777.0763421059 0.0522872210 0.0232730434 0.0597725697 0.0049781523 0.0246550000 247273246 95654136 760807424 0.0075015919 0.0519880727 -0.0006136193 1753 1311867777.1087210178 0.0528280810 0.0232899031 0.0597725697 0.0049768741 0.0249630000 247275174 95654136 760807424 0.0061697820 0.0529137217 -0.0005983068 1754 1311867777.1435770988 0.0534414425 0.0233070933 0.0597725697 0.0049755180 0.0282840000 247278814 95654136 760807424 0.0059509533 0.0536241643 -0.0007896090 1755 1311867777.1783010960 0.0520661995 0.0233234802 0.0597725697 0.0049742376 0.0279510000 247280798 95654136 760807424 0.0064860983 0.0523156673 -0.0001803139 1756 1311867777.2115299702 0.0517557301 0.0233396717 0.0597725697 0.0049728935 0.0246870000 247284438 95654136 760807424 0.0055938093 0.0522230193 -0.0004877411 1757 1311867777.2420690060 0.0504519492 0.0233551027 0.0597725697 0.0049717773 0.0246060000 247287998 95654136 760807424 0.0051588742 0.0511340648 0.0006438081 1758 1311867777.2766950130 0.0521354862 0.0233714738 0.0597725697 0.0049715142 0.0245860000 247289782 95654136 760807424 0.0042659738 0.0531279296 -0.0000406791 1759 1311867777.3093490601 0.0513512529 0.0233873805 0.0597725697 0.0049708818 0.0286260000 247293510 95654136 760807424 0.0044988561 0.0523816273 0.0010339328 1760 1311867777.3419890404 0.0530224293 0.0234042186 0.0597725697 0.0049695955 0.0246730000 247295238 95654136 760807424 0.0034987931 0.0542644896 0.0002213918 1761 1311867777.3780329227 0.0527426116 0.0234208786 0.0597725697 0.0049688098 0.0246770000 247299134 95654136 760807424 0.0029310428 0.0541352332 -0.0003087284 1762 1311867777.4108960629 0.0513881408 0.0234367511 0.0597725697 0.0049681410 0.0245360000 247302662 95654136 760807424 0.0046129432 0.0523624495 0.0007377827 1763 1311867777.4411139488 0.0506715104 0.0234521990 0.0597725697 0.0049667761 0.0280450000 247304534 95654136 760807424 0.0027768051 0.0520180538 0.0014856064 1764 1311867777.4770240784 0.0492070466 0.0234667993 0.0597725697 0.0049665594 0.0246180000 247308230 95654136 760807424 0.0057591079 0.0497746095 0.0030042520 1765 1311867777.5098700523 0.0488722399 0.0234811933 0.0597725697 0.0049652384 0.0245770000 247310158 95654136 760807424 0.0061486727 0.0494895652 0.0030687947 1766 1311867777.5421240330 0.0493323840 0.0234958316 0.0597725697 0.0049640580 0.0287010000 247313630 95654136 760807424 0.0072047855 0.0497007146 0.0035559908 1767 1311867777.5777161121 0.0502821654 0.0235109908 0.0597725697 0.0049627082 0.0245920000 247317526 95654136 760807424 0.0064151613 0.0509665906 0.0035013095 1768 1311867777.6086440086 0.0467906594 0.0235241580 0.0597725697 0.0049617935 0.0246890000 247491590 95654136 760807424 0.0065302192 0.0473339073 0.0052514863 1769 1311867777.6407959461 0.0483308174 0.0235381810 0.0597725697 0.0049604436 0.0245380000 247495374 95654136 760807424 0.0071951253 0.0486972146 0.0050586076 1770 1311867777.6765840054 0.0502138212 0.0235532520 0.0597725697 0.0049591131 0.0245210000 247499014 95654136 760807424 0.0069746999 0.0507398993 0.0038855076 1771 1311867777.7086570263 0.0518065579 0.0235692053 0.0597725697 0.0049578046 0.0273220000 247500886 95654136 760807424 0.0064838156 0.0524661019 0.0026432355 1772 1311867777.7411170006 0.0521801189 0.0235853514 0.0597725697 0.0049564882 0.0246130000 247504414 95654136 760807424 0.0048309322 0.0534744300 0.0031506198 1773 1311867777.7797420025 0.0520953238 0.0236014315 0.0597725697 0.0049552238 0.0244990000 247506566 95654136 760807424 0.0033960021 0.0538572446 0.0034157771 1774 1311867777.8103909492 0.0530666858 0.0236180410 0.0597725697 0.0049542430 0.0245080000 247510094 95654136 760807424 0.0036773258 0.0548302010 0.0037408134 1775 1311867777.8421120644 0.0522122309 0.0236341504 0.0597725697 0.0049533815 0.0284320000 247513766 95654136 760807424 0.0061972355 0.0534507334 0.0044393903 1776 1311867777.8771729469 0.0547093637 0.0236516477 0.0597725697 0.0049524540 0.0247480000 247515606 95654136 760807424 0.0046048416 0.0566998795 0.0030705517 1777 1311867777.9091188908 0.0541380718 0.0236688038 0.0597725697 0.0049514536 0.0245520000 247519334 95654136 760807424 0.0028997567 0.0566061400 0.0042451271 1778 1311867777.9424149990 0.0538210906 0.0236857624 0.0597725697 0.0049505004 0.0245490000 247521062 95654136 760807424 0.0032109835 0.0563153103 0.0042233951 1779 1311867777.9770610332 0.0534079783 0.0237024696 0.0597725697 0.0049492669 0.0277490000 247524958 95654136 760807424 0.0037038096 0.0560308658 0.0037898128 1780 1311867778.0100560188 0.0539525636 0.0237194641 0.0597725697 0.0049497158 0.0245270000 247528486 95654136 760807424 0.0028221454 0.0567019135 0.0041379682 1781 1311867778.0413420200 0.0550347120 0.0237370470 0.0597725697 0.0049486935 0.0279810000 247530358 95654136 760807424 0.0021130685 0.0578936897 0.0049910760 1782 1311867778.0773630142 0.0551591516 0.0237546801 0.0597725697 0.0049481692 0.0246470000 247533998 95654136 760807424 0.0048749619 0.0573985353 0.0039865803 1783 1311867778.1094930172 0.0558588579 0.0237726858 0.0597725697 0.0049475522 0.0245540000 247535926 95654136 760807424 0.0006108433 0.0593041144 0.0031709806 1784 1311867778.1418550014 0.0561644472 0.0237908426 0.0597725697 0.0049463446 0.0245820000 247539510 95654136 760807424 -0.0000272826 0.0598131903 0.0042644911 1785 1311867778.1826310158 0.0572442114 0.0238095840 0.0597725697 0.0049458012 0.0245200000 247543406 95654136 760807424 0.0036296607 0.0597923733 0.0025482499 1786 1311867778.2094058990 0.0597552620 0.0238297103 0.0597725697 0.0049460901 0.0245650000 247545022 95654136 760807424 0.0041730981 0.0620255396 0.0028311834 1787 1311867778.2432699203 0.0583727062 0.0238490405 0.0597725697 0.0049459345 0.0296420000 247548806 95654136 760807424 0.0030766418 0.0608455427 0.0042993505 1788 1311867778.2796919346 0.0581136607 0.0238682042 0.0597725697 0.0049454331 0.0247910000 247552446 95654136 760807424 0.0012577838 0.0607144535 0.0037303942 1789 1311867778.3125588894 0.0592204146 0.0238879650 0.0597725697 0.0049440647 0.0245200000 247554374 95654136 760807424 0.0016128878 0.0614292808 0.0038329090 1790 1311867778.3414309025 0.0582830086 0.0239071801 0.0597725697 0.0049434670 0.0244540000 247557846 95654136 760807424 0.0041491045 0.0595963188 0.0039332951 1791 1311867778.3782539368 0.0590990484 0.0239268294 0.0597725697 0.0049429780 0.0246040000 247559942 95654136 760807424 0.0004983169 0.0612181835 0.0027396940 1792 1311867778.4093298912 0.0606744327 0.0239473359 0.0606744327 0.0049418937 0.0248580000 247563414 95654136 760807424 0.0012067265 0.0624685436 0.0027907738 1793 1311867778.4445381165 0.0594106801 0.0239671147 0.0606744327 0.0049408211 0.0244770000 247567254 95654136 760807424 0.0018257148 0.0607875213 0.0023614587 1794 1311867778.4812810421 0.0598167814 0.0239870978 0.0606744327 0.0049401622 0.0246750000 247569150 95654136 760807424 -0.0016818595 0.0619444847 0.0010662533 1795 1311867778.5097670555 0.0591177791 0.0240066692 0.0606744327 0.0049389940 0.0296130000 247572766 95654136 760807424 -0.0029117358 0.0612042658 0.0015817895 1796 1311867778.5484840870 0.0593078062 0.0240263246 0.0606744327 0.0049380246 0.0246960000 247574662 95654136 760807424 -0.0020635496 0.0609056726 0.0003257982 1797 1311867778.5830690861 0.0585463196 0.0240455344 0.0606744327 0.0049375725 0.0245760000 247578502 95654136 760807424 -0.0049718153 0.0603916980 -0.0004563992 1798 1311867778.6150701046 0.0577767417 0.0240642948 0.0606744327 0.0049368071 0.0246390000 247582030 95654136 760807424 -0.0082034068 0.0599379875 0.0007663764 1799 1311867778.6452109814 0.0575390756 0.0240829022 0.0606744327 0.0049360025 0.0245460000 247583902 95654136 760807424 -0.0067411205 0.0592304058 0.0005795304 1800 1311867778.6781129837 0.0569435917 0.0241011582 0.0606744327 0.0049358365 0.0245780000 247587430 95654136 760807424 -0.0023681386 0.0576287024 0.0003389150 1801 1311867778.7125270367 0.0566986874 0.0241192579 0.0606744327 0.0049355900 0.0246800000 247589414 95654136 760807424 -0.0067824335 0.0580223426 0.0009173800 1802 1311867778.7490179539 0.0556901880 0.0241367778 0.0606744327 0.0049359954 0.0287340000 247593110 95654136 760807424 -0.0103221750 0.0573465116 0.0019893139 1803 1311867778.7815420628 0.0556518659 0.0241542571 0.0606744327 0.0049357272 0.0247250000 247596894 95654136 760807424 -0.0079870112 0.0569474660 0.0014099182 1804 1311867778.8090119362 0.0562272370 0.0241720359 0.0606744327 0.0049348129 0.0247550000 247598454 95654136 760807424 -0.0104014203 0.0575434528 0.0012549513 1805 1311867778.8465809822 0.0579629391 0.0241907566 0.0606744327 0.0049351606 0.0286030000 247602350 95654136 760807424 -0.0121675618 0.0588013120 0.0005671958 1806 1311867778.8808300495 0.0566794015 0.0242087459 0.0606744327 0.0049338201 0.0246280000 247605934 95654136 760807424 -0.0133325262 0.0573077723 0.0005139763 1807 1311867778.9117860794 0.0566487387 0.0242266983 0.0606744327 0.0049328851 0.0246130000 247607806 95654136 760807424 -0.0134756481 0.0570036136 0.0005621765 1808 1311867778.9482150078 0.0568240099 0.0242447278 0.0606744327 0.0049321198 0.0246680000 247611502 95654136 760807424 -0.0123716481 0.0565389395 0.0007791364 1809 1311867778.9777760506 0.0552887321 0.0242618886 0.0606744327 0.0049319380 0.0248830000 247613374 95654136 760807424 -0.0144931823 0.0547643490 0.0022678105 1810 1311867779.0105700493 0.0548509657 0.0242787887 0.0606744327 0.0049309726 0.0247280000 247616902 95654136 760807424 -0.0124214077 0.0539090484 0.0019511093 1811 1311867779.0471200943 0.0547673441 0.0242956239 0.0606744327 0.0049297983 0.0349770000 247620798 95654136 760807424 -0.0126257297 0.0534275807 0.0019117186 1812 1311867779.0780360699 0.0555656441 0.0243128811 0.0606744327 0.0049288419 0.0249730000 247622414 95654136 760807424 -0.0119342478 0.0539428033 0.0015369819 1813 1311867779.1124050617 0.0544528626 0.0243295054 0.0606744327 0.0049284785 0.0248740000 247626198 95654136 760807424 -0.0107119689 0.0526732169 0.0019598673 1814 1311867779.1473538876 0.0529542565 0.0243452853 0.0606744327 0.0049281022 0.0248230000 247627870 95654136 760807424 -0.0070359819 0.0507330671 0.0029751153 1815 1311867779.1777000427 0.0540784188 0.0243616672 0.0606744327 0.0049269657 0.0248490000 247631486 95654136 760807424 -0.0088958358 0.0520283356 0.0025176990 1816 1311867779.2123599052 0.0527979061 0.0243773259 0.0606744327 0.0049259127 0.0297680000 247635014 95654136 760807424 -0.0075835213 0.0505643934 0.0027905088 1817 1311867779.2447109222 0.0510421656 0.0243920011 0.0606744327 0.0049254463 0.0291300000 247636942 95654136 760807424 -0.0077465423 0.0487312265 0.0032090205 1818 1311867779.2782809734 0.0505849198 0.0244064087 0.0606744327 0.0049255965 0.0265970000 247640414 95654136 760807424 -0.0123973107 0.0484344214 0.0042036194 1819 1311867779.3104579449 0.0495886430 0.0244202527 0.0606744327 0.0049245591 0.0344850000 247642342 95654136 760807424 -0.0133590577 0.0471293554 0.0056410506 1820 1311867779.3468949795 0.0482560731 0.0244333493 0.0606744327 0.0049239527 0.0251620000 247645982 95654136 760807424 -0.0103661474 0.0456599332 0.0050354959 1821 1311867779.3772010803 0.0476516485 0.0244460996 0.0606744327 0.0049230986 0.0250630000 247649598 95654136 760807424 -0.0090505984 0.0444659591 0.0060850773 1822 1311867779.4088799953 0.0481245816 0.0244590955 0.0606744327 0.0049223499 0.0250720000 247651270 95654136 760807424 -0.0115981679 0.0449106693 0.0061193663 1823 1311867779.4446020126 0.0478946231 0.0244719509 0.0606744327 0.0049221102 0.0249450000 247655054 95654136 760807424 -0.0103796553 0.0444239452 0.0052716066 1824 1311867779.4768970013 0.0491820313 0.0244854981 0.0606744327 0.0049224444 0.0249340000 247658582 95654136 760807424 -0.0103079723 0.0453344360 0.0044301176 1825 1311867779.5098230839 0.0483841933 0.0244985933 0.0606744327 0.0049215014 0.0285080000 247660454 95654136 760807424 -0.0097330920 0.0440167263 0.0047231913 1826 1311867779.5450038910 0.0449304022 0.0245097827 0.0606744327 0.0049212646 0.0363680000 247664038 95654136 760807424 -0.0081549883 0.0398262963 0.0057403669 1827 1311867779.5777029991 0.0438412577 0.0245203637 0.0606744327 0.0049202213 0.0264280000 247665910 95654136 760807424 -0.0106078619 0.0381213091 0.0067792675 1828 1311867779.6092689037 0.0447040163 0.0245314051 0.0606744327 0.0049192662 0.0250320000 247669382 95654136 760807424 -0.0129106613 0.0384894125 0.0067077735 1829 1311867779.6482150555 0.0440472029 0.0245420753 0.0606744327 0.0049186422 0.0250690000 247673222 95654136 760807424 -0.0131751159 0.0376002602 0.0060334513 1830 1311867779.6796278954 0.0423153415 0.0245517874 0.0606744327 0.0049181820 0.0250430000 247674894 95654136 760807424 -0.0090701990 0.0358479656 0.0049597118 1831 1311867779.7129859924 0.0445656814 0.0245627180 0.0606744327 0.0049173424 0.0250240000 247678566 95654136 760807424 -0.0082349814 0.0380632319 0.0031833663 1832 1311867779.7461729050 0.0446042977 0.0245736578 0.0606744327 0.0049162121 0.0250380000 247680350 95654136 760807424 -0.0099816378 0.0377912447 0.0034745303 1833 1311867779.7771708965 0.0435566343 0.0245840140 0.0606744327 0.0049151579 0.0250610000 247683966 95654136 760807424 -0.0104726758 0.0364216156 0.0037437470 1834 1311867779.8130059242 0.0421268530 0.0245935793 0.0606744327 0.0049143112 0.0252140000 247687494 95654136 760807424 -0.0104898317 0.0347116739 0.0036451924 1835 1311867779.8454499245 0.0414495096 0.0246027651 0.0606744327 0.0049131299 0.0252770000 247689422 95654136 760807424 -0.0121407192 0.0338857435 0.0026868661 1836 1311867779.8771400452 0.0408106260 0.0246115929 0.0606744327 0.0049126015 0.0253060000 247692838 95654136 760807424 -0.0131960381 0.0331517421 0.0019457506 1837 1311867779.9128279686 0.0402285308 0.0246200943 0.0606744327 0.0049118901 0.0286130000 247694878 95654136 760807424 -0.0132090086 0.0322824456 0.0017516653 1838 1311867779.9448599815 0.0399194174 0.0246284182 0.0606744327 0.0049106741 0.0252690000 247698350 95654136 760807424 -0.0146657284 0.0312915668 0.0026092727 1839 1311867779.9769320488 0.0395781212 0.0246365474 0.0606744327 0.0049097478 0.0252630000 247702022 95654136 760807424 -0.0123817418 0.0308763608 0.0024148873 1840 1311867780.0130739212 0.0392110758 0.0246444684 0.0606744327 0.0049087222 0.0253320000 247703806 95654136 760807424 -0.0118181529 0.0302832164 0.0020685401 1841 1311867780.0448310375 0.0377070457 0.0246515637 0.0606744327 0.0049079074 0.0253270000 247707478 95654136 760807424 -0.0111658238 0.0287655722 0.0012991243 1842 1311867780.0771219730 0.0391011238 0.0246594082 0.0606744327 0.0049071273 0.0383190000 247710950 95654136 760807424 -0.0114839207 0.0300584547 0.0004950213 1843 1311867780.1143870354 0.0387639701 0.0246670613 0.0606744327 0.0049058715 0.0256650000 247712990 95654136 760807424 -0.0134735219 0.0292278156 0.0002157153 1844 1311867780.1448268890 0.0379245281 0.0246742508 0.0606744327 0.0049065659 0.0253570000 247716406 95654136 760807424 -0.0136169055 0.0282859430 -0.0001989801 1845 1311867780.1773400307 0.0359462872 0.0246803603 0.0606744327 0.0049093496 0.0254490000 247718278 95654136 760807424 -0.0126467021 0.0256037414 0.0005510754 1846 1311867780.2158250809 0.0374441370 0.0246872746 0.0606744327 0.0049127082 0.0295790000 247721974 95654136 760807424 -0.0113558006 0.0274602193 -0.0012772388 1847 1311867780.2454960346 0.0379962623 0.0246944803 0.0606744327 0.0049133974 0.0255000000 247725590 95654136 760807424 -0.0101999529 0.0274583381 -0.0018769111 1848 1311867780.2815570831 0.0383612439 0.0247018757 0.0606744327 0.0049121363 0.0253990000 247727374 95654136 760807424 -0.0093122516 0.0274360050 -0.0026730576 1849 1311867780.3140099049 0.0380890928 0.0247091160 0.0606744327 0.0049111837 0.0253630000 247731046 95654136 760807424 -0.0094278418 0.0265913438 -0.0025090754 1850 1311867780.3464050293 0.0378148705 0.0247162002 0.0606744327 0.0049099259 0.0258810000 247732718 95654136 760807424 -0.0083728852 0.0257607047 -0.0024967589 1851 1311867780.3772649765 0.0387909301 0.0247238040 0.0606744327 0.0049089353 0.0263280000 247736334 95654136 760807424 -0.0095721260 0.0259814505 -0.0036312244 1852 1311867780.4132668972 0.0398154743 0.0247319529 0.0606744327 0.0049079796 0.0256090000 247739974 95654136 760807424 -0.0095429551 0.0268666223 -0.0051536434 1853 1311867780.4451050758 0.0387915224 0.0247395403 0.0606744327 0.0049072794 0.0288180000 247741846 95654136 760807424 -0.0084764333 0.0256160367 -0.0055766916 1854 1311867780.4791510105 0.0389463454 0.0247472031 0.0606744327 0.0049097130 0.0256050000 247745374 95654136 760807424 -0.0065913904 0.0255737677 -0.0067116208 1855 1311867780.5153009892 0.0387017168 0.0247547258 0.0606744327 0.0049096843 0.0254730000 247747414 95654136 760807424 -0.0067368452 0.0254113413 -0.0065542748 1856 1311867780.5455119610 0.0380984470 0.0247619153 0.0606744327 0.0049112512 0.0289750000 247750830 95654136 760807424 -0.0081116082 0.0247336607 -0.0057726344 1857 1311867780.5798339844 0.0373536870 0.0247686960 0.0606744327 0.0049107341 0.0255620000 247754558 95654136 760807424 -0.0091257999 0.0235864278 -0.0056046750 1858 1311867780.6136929989 0.0380144119 0.0247758250 0.0606744327 0.0049134368 0.0348380000 247756230 95654136 760807424 -0.0092778383 0.0239719711 -0.0057042185 1859 1311867780.6459660530 0.0368302204 0.0247823094 0.0606744327 0.0049129030 0.0256860000 247759958 95654136 760807424 -0.0077303797 0.0226129126 -0.0058228890 1860 1311867780.6793959141 0.0388538167 0.0247898747 0.0606744327 0.0049131956 0.0255570000 247763486 95654136 760807424 -0.0074882414 0.0245849397 -0.0066707237 1861 1311867780.7156999111 0.0386067927 0.0247972991 0.0606744327 0.0049121661 0.0255280000 247765470 95654136 760807424 -0.0074213617 0.0240863301 -0.0064457138 1862 1311867780.7469029427 0.0396421291 0.0248052717 0.0606744327 0.0049110020 0.0260810000 247768886 95654136 760807424 -0.0066938922 0.0248068031 -0.0071994648 1863 1311867780.7774689198 0.0397064388 0.0248132701 0.0606744327 0.0049097043 0.0304600000 247770758 95654136 760807424 -0.0064208889 0.0243916977 -0.0069478494 1864 1311867780.8164570332 0.0390888266 0.0248209287 0.0606744327 0.0049085123 0.0256560000 247774454 95654136 760807424 -0.0072007934 0.0233089067 -0.0070008044 1865 1311867780.8460350037 0.0396912545 0.0248289021 0.0606744327 0.0049082201 0.0354030000 247778014 95654136 760807424 -0.0053635887 0.0230041128 -0.0073638400 1866 1311867780.8791809082 0.0377122685 0.0248358063 0.0606744327 0.0049072007 0.0257770000 247779742 95654136 760807424 -0.0053729699 0.0207214393 -0.0073824967 1867 1311867780.9152340889 0.0399793088 0.0248439175 0.0606744327 0.0049062534 0.0255820000 247783526 95654136 760807424 -0.0055073579 0.0228409581 -0.0081751505 1868 1311867780.9457290173 0.0401704870 0.0248521223 0.0606744327 0.0049075297 0.0256500000 247785142 95654136 760807424 -0.0026287702 0.0223706421 -0.0083702635 1869 1311867780.9838399887 0.0410704724 0.0248607998 0.0606744327 0.0049064851 0.0256460000 247788982 95654136 760807424 -0.0041110422 0.0230377633 -0.0089194030 1870 1311867781.0137300491 0.0425621308 0.0248702658 0.0606744327 0.0049053932 0.0297910000 247792398 95654136 760807424 -0.0040040957 0.0243453477 -0.0089218821 1871 1311867781.0463659763 0.0407979637 0.0248787787 0.0606744327 0.0049041699 0.0256780000 247794270 95654136 760807424 -0.0054700142 0.0221301951 -0.0084359907 1872 1311867781.0821859837 0.0393286496 0.0248864977 0.0606744327 0.0049030627 0.0263700000 247797854 95654136 760807424 -0.0074987402 0.0202995148 -0.0092993909 1873 1311867781.1157560349 0.0409972221 0.0248950992 0.0606744327 0.0049022810 0.0369620000 247799782 95654136 760807424 -0.0058086501 0.0215850510 -0.0100321863 1874 1311867781.1459479332 0.0401595347 0.0249032446 0.0606744327 0.0049016693 0.0259060000 247803198 95654136 760807424 -0.0058770604 0.0201870836 -0.0100208307 1875 1311867781.1839950085 0.0391187519 0.0249108262 0.0606744327 0.0049010527 0.0256700000 247807038 95654136 760807424 -0.0066656983 0.0184851475 -0.0103458716 1876 1311867781.2133030891 0.0390615426 0.0249183692 0.0606744327 0.0049003322 0.0256980000 247808598 95654136 760807424 -0.0069600390 0.0181655735 -0.0104762735 1877 1311867781.2467529774 0.0413086377 0.0249271014 0.0606744327 0.0048992242 0.0257280000 247812270 95654136 760807424 -0.0050223740 0.0200510956 -0.0106871640 1878 1311867781.2855589390 0.0391445868 0.0249346719 0.0606744327 0.0048983345 0.0257290000 247815966 95654136 760807424 -0.0049356725 0.0175261870 -0.0110203000 1879 1311867781.3133049011 0.0397500768 0.0249425567 0.0606744327 0.0048989099 0.0257710000 247817670 95654136 760807424 -0.0043240017 0.0179484487 -0.0110866781 1880 1311867781.3465669155 0.0394063145 0.0249502502 0.0606744327 0.0048983444 0.0298230000 247821254 95654136 760807424 -0.0036849873 0.0171441156 -0.0108101182 1881 1311867781.3809239864 0.0384178422 0.0249574100 0.0606744327 0.0048973132 0.0358830000 247823182 95654136 760807424 -0.0034022725 0.0157232713 -0.0104152067 1882 1311867781.4144830704 0.0398117676 0.0249653028 0.0606744327 0.0048964955 0.0257680000 247826654 95654136 760807424 -0.0033584065 0.0168558303 -0.0109532941 1883 1311867781.4457330704 0.0392221771 0.0249728742 0.0606744327 0.0048967948 0.0257300000 247830326 95654136 760807424 -0.0042410973 0.0155507810 -0.0108202836 1884 1311867781.4812419415 0.0366448276 0.0249790695 0.0606744327 0.0048985333 0.0256950000 247832110 95654136 760807424 -0.0066204555 0.0125850346 -0.0107287029 1885 1311867781.5131030083 0.0365209430 0.0249851925 0.0606744327 0.0048978112 0.0263820000 248007358 95654136 760807424 -0.0050769178 0.0118968599 -0.0109493928 1886 1311867781.5451910496 0.0374560133 0.0249918048 0.0606744327 0.0048977676 0.0298530000 248009086 95654136 760807424 -0.0047190939 0.0127282264 -0.0119204558 1887 1311867781.5813419819 0.0365310051 0.0249979199 0.0606744327 0.0048982120 0.0297150000 248012870 95654136 760807424 -0.0061757546 0.0113912951 -0.0127098020 1888 1311867781.6135890484 0.0349579193 0.0250031953 0.0606744327 0.0048989676 0.0257180000 248016286 95654136 760807424 -0.0087753637 0.0091068279 -0.0127468193 1889 1311867781.6467020512 0.0341632627 0.0250080445 0.0606744327 0.0048982590 0.0299870000 248018214 95654136 760807424 -0.0063411347 0.0078954715 -0.0131488098 1890 1311867781.6832339764 0.0345810838 0.0250131096 0.0606744327 0.0048976909 0.0430640000 248021798 95654136 760807424 -0.0052665533 0.0079225712 -0.0137513159 1891 1311867781.7131800652 0.0349697731 0.0250183749 0.0606744327 0.0048966114 0.0265240000 248023614 95654136 760807424 -0.0053065573 0.0079276646 -0.0141383167 1892 1311867781.7453010082 0.0358004831 0.0250240737 0.0606744327 0.0048960514 0.0256140000 248027142 95654136 760807424 -0.0064227302 0.0084080836 -0.0148338387 1893 1311867781.7820630074 0.0348049067 0.0250292405 0.0606744327 0.0048963648 0.0258110000 248030926 95654136 760807424 -0.0067174016 0.0067144930 -0.0147383595 1894 1311867781.8145859241 0.0329533592 0.0250334243 0.0606744327 0.0048986873 0.0256960000 248032598 95654136 760807424 -0.0063193548 0.0044965968 -0.0156284291 1895 1311867781.8453550339 0.0347527117 0.0250385532 0.0606744327 0.0048980148 0.0326180000 248036270 95654136 760807424 -0.0065606846 0.0061327852 -0.0163373686 1896 1311867781.8827259541 0.0351188369 0.0250438698 0.0606744327 0.0048989884 0.0258000000 248039854 95654136 760807424 -0.0059869131 0.0058006886 -0.0167388879 1897 1311867781.9138391018 0.0324983522 0.0250477994 0.0606744327 0.0048996439 0.0298910000 248041726 95654136 760807424 -0.0054157088 0.0020545253 -0.0168120191 1898 1311867781.9470670223 0.0311394148 0.0250510089 0.0606744327 0.0048984667 0.0257790000 248045254 95654136 760807424 -0.0060745804 -0.0000858249 -0.0174541827 1899 1311867781.9856810570 0.0334045626 0.0250554079 0.0606744327 0.0049005661 0.0257560000 248047238 95654136 760807424 -0.0053242501 0.0019728902 -0.0186561253 1900 1311867782.0139210224 0.0321440622 0.0250591387 0.0606744327 0.0049008187 0.0257840000 248050598 95654136 760807424 -0.0051530330 0.0001128158 -0.0190464873 1901 1311867782.0464830399 0.0319631547 0.0250627705 0.0606744327 0.0049018914 0.0256720000 248054326 95654136 760807424 -0.0082612485 -0.0002264599 -0.0200800803 1902 1311867782.0839829445 0.0354217514 0.0250682169 0.0606744327 0.0049051483 0.0257430000 248056054 95654136 760807424 -0.0094492715 0.0031657964 -0.0209182613 1903 1311867782.1135599613 0.0377629101 0.0250748878 0.0606744327 0.0049050878 0.0257020000 248059670 95654136 760807424 -0.0093117477 0.0054798862 -0.0217506289 1904 1311867782.1472380161 0.0373799801 0.0250813505 0.0606744327 0.0049039759 0.0256720000 248061398 95654136 760807424 -0.0105708698 0.0047528897 -0.0219560210 1905 1311867782.1819090843 0.0386205763 0.0250884577 0.0606744327 0.0049031078 0.0256840000 248065182 95654136 760807424 -0.0087993015 0.0061999750 -0.0222922806 1906 1311867782.2144429684 0.0403917842 0.0250964868 0.0606744327 0.0049049931 0.0257870000 248068654 95654136 760807424 -0.0105822887 0.0075497315 -0.0225095395 1907 1311867782.2494089603 0.0397186130 0.0251041544 0.0606744327 0.0049051122 0.0257130000 248070582 95654136 760807424 -0.0099151358 0.0067376439 -0.0221074689 1908 1311867782.2860810757 0.0377382934 0.0251107760 0.0606744327 0.0049039167 0.0255890000 248074222 95654136 760807424 -0.0092499061 0.0044279806 -0.0212580096 1909 1311867782.3144040108 0.0398527719 0.0251184984 0.0606744327 0.0049033368 0.0257000000 248075926 95654136 760807424 -0.0087309014 0.0067518903 -0.0226305071 1910 1311867782.3526129723 0.0408351682 0.0251267270 0.0606744327 0.0049028100 0.0293450000 248079622 95654136 760807424 -0.0088717649 0.0074158739 -0.0224400014 1911 1311867782.3825540543 0.0388377570 0.0251339018 0.0606744327 0.0049019101 0.0254770000 248083182 95654136 760807424 -0.0086670602 0.0051932391 -0.0220699478 1912 1311867782.4147620201 0.0413395688 0.0251423776 0.0606744327 0.0049019988 0.0255270000 248084742 95654136 760807424 -0.0094883125 0.0077886106 -0.0229081903 1913 1311867782.4514210224 0.0410626978 0.0251506997 0.0606744327 0.0049008645 0.0256450000 248088526 95654136 760807424 -0.0093521113 0.0073280479 -0.0226354301 1914 1311867782.4812099934 0.0402238294 0.0251585749 0.0606744327 0.0048997699 0.0254860000 248091998 95654136 760807424 -0.0088481996 0.0064113964 -0.0224434771 1915 1311867782.5149359703 0.0431810431 0.0251679862 0.0606744327 0.0049000516 0.0254910000 248093870 95654136 760807424 -0.0076830052 0.0096432324 -0.0228027981 1916 1311867782.5516130924 0.0422619469 0.0251769078 0.0606744327 0.0049010019 0.0255050000 248097454 95654136 760807424 -0.0076133586 0.0087148054 -0.0231736302 1917 1311867782.5828690529 0.0399437211 0.0251846109 0.0606744327 0.0048998817 0.0256780000 248099270 95654136 760807424 -0.0071691261 0.0063475580 -0.0230743960 1918 1311867782.6142859459 0.0409276411 0.0251928190 0.0606744327 0.0048995204 0.0297190000 248102798 95654136 760807424 -0.0091260066 0.0073148948 -0.0233301893 1919 1311867782.6501080990 0.0412360877 0.0252011792 0.0606744327 0.0048988625 0.0256870000 248106582 95654136 760807424 -0.0108138975 0.0073856115 -0.0233814735 1920 1311867782.6862080097 0.0412426777 0.0252095342 0.0606744327 0.0048984769 0.0260550000 248108366 95654136 760807424 -0.0102590052 0.0075862533 -0.0236949287 1921 1311867782.7131700516 0.0431260802 0.0252188608 0.0606744327 0.0048987467 0.0257530000 248111870 95654136 760807424 -0.0114903683 0.0094913766 -0.0244617704 1922 1311867782.7489991188 0.0427000932 0.0252279562 0.0606744327 0.0048989037 0.0257490000 248113654 95654136 760807424 -0.0118140755 0.0084714731 -0.0246321131 1923 1311867782.7844688892 0.0417590141 0.0252365527 0.0606744327 0.0048993504 0.0256290000 248117438 95654136 760807424 -0.0083077624 0.0077750836 -0.0244708210 1924 1311867782.8159070015 0.0455138385 0.0252470918 0.0606744327 0.0048992465 0.0257190000 248120910 95654136 760807424 -0.0089179995 0.0114996638 -0.0254223738 1925 1311867782.8522670269 0.0453348756 0.0252575270 0.0606744327 0.0048982974 0.0258160000 248122838 95654136 760807424 -0.0096191615 0.0114328004 -0.0255138017 1926 1311867782.8824830055 0.0417802744 0.0252661058 0.0606744327 0.0048981349 0.0286950000 248126310 95654136 760807424 -0.0099943839 0.0072375266 -0.0250069499 1927 1311867782.9145979881 0.0436384417 0.0252756400 0.0606744327 0.0048995384 0.0257720000 248128182 95654136 760807424 -0.0100968406 0.0091842413 -0.0258212425 1928 1311867782.9517209530 0.0469378866 0.0252868756 0.0606744327 0.0048987440 0.0256540000 248131822 95654136 760807424 -0.0110349189 0.0123220906 -0.0271402169 1929 1311867782.9812240601 0.0434817709 0.0252963079 0.0606744327 0.0048984355 0.0258180000 248135382 95654136 760807424 -0.0126059912 0.0081467479 -0.0267564226 1930 1311867783.0143089294 0.0447525568 0.0253063888 0.0606744327 0.0048992388 0.0297360000 248137110 95654136 760807424 -0.0141814277 0.0091609498 -0.0277172755 1931 1311867783.0528459549 0.0453859828 0.0253167874 0.0606744327 0.0048991584 0.0257320000 248140894 95654136 760807424 -0.0129847219 0.0099015702 -0.0288331136 1932 1311867783.0829811096 0.0432149395 0.0253260514 0.0606744327 0.0048991775 0.0265340000 248144366 95654136 760807424 -0.0133466674 0.0068156980 -0.0280016232 1933 1311867783.1137030125 0.0437597074 0.0253355877 0.0606744327 0.0048980572 0.0257740000 248146182 95654136 760807424 -0.0123256100 0.0076679480 -0.0295870099 1934 1311867783.1539480686 0.0438045003 0.0253451373 0.0606744327 0.0048978330 0.0296340000 248149878 95654136 760807424 -0.0104315281 0.0078395158 -0.0305162519 1935 1311867783.1857850552 0.0423884243 0.0253539452 0.0606744327 0.0048968015 0.0257420000 248151750 95654136 760807424 -0.0119069982 0.0061697601 -0.0307824444 1936 1311867783.2169439793 0.0415845774 0.0253623288 0.0606744327 0.0048964207 0.0256150000 248155166 95654136 760807424 -0.0102885673 0.0056871283 -0.0306249931 1937 1311867783.2548489571 0.0434051789 0.0253716436 0.0606744327 0.0048952020 0.0256910000 248159062 95654136 760807424 -0.0094894497 0.0076232301 -0.0310843363 1938 1311867783.2816879749 0.0438992046 0.0253812038 0.0606744327 0.0048948541 0.0256780000 248160622 95654136 760807424 -0.0121843182 0.0077394848 -0.0311147962 1939 1311867783.3132228851 0.0439753793 0.0253907933 0.0606744327 0.0048937217 0.0256320000 248164182 95654136 760807424 -0.0126741733 0.0076187565 -0.0317655876 1940 1311867783.3503270149 0.0463321283 0.0254015878 0.0606744327 0.0048940350 0.0257190000 248166022 95654136 760807424 -0.0145847071 0.0099387160 -0.0328424089 1941 1311867783.3855919838 0.0472838022 0.0254128615 0.0606744327 0.0048928855 0.0257350000 248340070 95654136 760807424 -0.0143304318 0.0106591554 -0.0329126380 1942 1311867783.4198501110 0.0441830344 0.0254225269 0.0606744327 0.0048921464 0.0257650000 248343598 95654136 760807424 -0.0147816734 0.0072392887 -0.0327133089 1943 1311867783.4503099918 0.0456003807 0.0254329118 0.0606744327 0.0048912036 0.0257150000 248345414 95654136 760807424 -0.0131150996 0.0089314962 -0.0337660760 1944 1311867783.4863688946 0.0473317690 0.0254441767 0.0606744327 0.0048905399 0.0257350000 248348998 95654136 760807424 -0.0121430811 0.0101769855 -0.0335241221 1945 1311867783.5186200142 0.0443652347 0.0254539047 0.0606744327 0.0048910351 0.0257150000 248350814 95654136 760807424 -0.0091866953 0.0071309339 -0.0330051519 1946 1311867783.5488419533 0.0466035604 0.0254647730 0.0606744327 0.0048910597 0.0256430000 248354230 95654136 760807424 -0.0085096126 0.0096841138 -0.0342688933 1947 1311867783.5823969841 0.0459520929 0.0254752955 0.0606744327 0.0048906190 0.0256860000 248358014 95654136 760807424 -0.0066625024 0.0087863971 -0.0341889895 1948 1311867783.6168529987 0.0464695059 0.0254860728 0.0606744327 0.0048893866 0.0256690000 248359686 95654136 760807424 -0.0054377895 0.0090487152 -0.0342922173 1949 1311867783.6515829563 0.0484471172 0.0254978537 0.0606744327 0.0048887943 0.0256730000 248363414 95654136 760807424 -0.0051221242 0.0110587049 -0.0348436944 1950 1311867783.6816630363 0.0481228605 0.0255094563 0.0606744327 0.0048878787 0.0292210000 248366886 95654136 760807424 -0.0048126443 0.0105231581 -0.0341003314 1951 1311867783.7179610729 0.0454534292 0.0255196787 0.0606744327 0.0048882016 0.0257650000 248539586 95654136 760807424 -0.0057049389 0.0077144774 -0.0337641239 1952 1311867783.7488200665 0.0465992130 0.0255304777 0.0606744327 0.0048874570 0.0290410000 248543002 95654136 760807424 -0.0059340834 0.0089145880 -0.0336616710 1953 1311867783.7808690071 0.0488569103 0.0255424216 0.0606744327 0.0048878310 0.0256790000 248544874 95654136 760807424 -0.0063054403 0.0112273330 -0.0330426618 1954 1311867783.8168580532 0.0458515398 0.0255528152 0.0606744327 0.0048899581 0.0257210000 248548402 95654136 760807424 -0.0064828941 0.0080815330 -0.0319384001 1955 1311867783.8489229679 0.0462570228 0.0255634056 0.0606744327 0.0048911592 0.0257860000 248552074 95654136 760807424 -0.0057219327 0.0088194190 -0.0323272906 1956 1311867783.8808929920 0.0481527336 0.0255749543 0.0606744327 0.0048900044 0.0256900000 248553746 95654136 760807424 -0.0054024621 0.0110479239 -0.0325427949 1957 1311867783.9168200493 0.0449300744 0.0255848445 0.0606744327 0.0048935875 0.0263310000 248557530 95654136 760807424 -0.0059384471 0.0076933014 -0.0303877778 1958 1311867783.9508318901 0.0464487150 0.0255955002 0.0606744327 0.0048934545 0.0358880000 248559258 95654136 760807424 -0.0063550589 0.0094553567 -0.0300732609 1959 1311867783.9816930294 0.0490558967 0.0256074759 0.0606744327 0.0048928925 0.0259230000 248562874 95654136 760807424 -0.0079901563 0.0119981058 -0.0301261246 1960 1311867784.0175230503 0.0465167165 0.0256181439 0.0606744327 0.0048919816 0.0257500000 248566514 95654136 760807424 -0.0087646386 0.0091777779 -0.0290496387 1961 1311867784.0505928993 0.0439604893 0.0256274975 0.0606744327 0.0048916311 0.0257230000 248568442 95654136 760807424 -0.0114018042 0.0063730404 -0.0287492462 1962 1311867784.0830729008 0.0475089103 0.0256386501 0.0606744327 0.0048909261 0.0297830000 248571858 95654136 760807424 -0.0107570812 0.0102644535 -0.0301346183 1963 1311867784.1187570095 0.0464032032 0.0256492280 0.0606744327 0.0048910720 0.0298920000 248573842 95654136 760807424 -0.0108716507 0.0084884260 -0.0294315610 1964 1311867784.1503119469 0.0430387519 0.0256580822 0.0606744327 0.0048905054 0.0298790000 248577314 95654136 760807424 -0.0101654865 0.0048376909 -0.0291698668 1965 1311867784.1823339462 0.0465460904 0.0256687122 0.0606744327 0.0048894967 0.0257070000 248581042 95654136 760807424 -0.0094231535 0.0084102005 -0.0301475823 1966 1311867784.2173891068 0.0441449918 0.0256781101 0.0606744327 0.0048915198 0.0295240000 248582714 95654136 760807424 -0.0080306670 0.0054896623 -0.0294099711 1967 1311867784.2502059937 0.0426309407 0.0256867287 0.0606744327 0.0048908800 0.0255760000 248586442 95654136 760807424 -0.0086098332 0.0039629443 -0.0291886497 1968 1311867784.2819900513 0.0447705835 0.0256964258 0.0606744327 0.0048907553 0.0258290000 248589858 95654136 760807424 -0.0090607544 0.0061734691 -0.0298965573 1969 1311867784.3176920414 0.0444566980 0.0257059536 0.0606744327 0.0048909593 0.0299450000 248591898 95654136 760807424 -0.0092176534 0.0055646030 -0.0296273567 1970 1311867784.3490819931 0.0425452925 0.0257145015 0.0606744327 0.0048915730 0.0255320000 248595314 95654136 760807424 -0.0087860776 0.0031054248 -0.0288303848 1971 1311867784.3815689087 0.0454815403 0.0257245305 0.0606744327 0.0048931127 0.0256850000 248597242 95654136 760807424 -0.0095699187 0.0060495315 -0.0296802036 1972 1311867784.4190580845 0.0440371595 0.0257338168 0.0606744327 0.0048925742 0.0259030000 248600826 95654136 760807424 -0.0097320471 0.0041880393 -0.0290446617 1973 1311867784.4496140480 0.0424872972 0.0257423082 0.0606744327 0.0048917074 0.0258460000 248604498 95654136 760807424 -0.0089494763 0.0024828666 -0.0285790823 1974 1311867784.4828379154 0.0430266410 0.0257510641 0.0606744327 0.0048908108 0.0370860000 248606226 95654136 760807424 -0.0083691031 0.0029751835 -0.0286787786 1975 1311867784.5185639858 0.0432079881 0.0257599031 0.0606744327 0.0048897788 0.0260350000 248609898 95654136 760807424 -0.0094893547 0.0029743409 -0.0286833141 1976 1311867784.5499279499 0.0418490209 0.0257680454 0.0606744327 0.0048886554 0.0257470000 248611570 95654136 760807424 -0.0099970652 0.0011654992 -0.0279631224 1977 1311867784.5848410130 0.0429516248 0.0257767371 0.0606744327 0.0048875261 0.0257850000 248615354 95654136 760807424 -0.0093079731 0.0022618491 -0.0287782867 1978 1311867784.6179790497 0.0433559343 0.0257856245 0.0606744327 0.0048868018 0.0258560000 248618826 95654136 760807424 -0.0097472258 0.0023131487 -0.0288305525 1979 1311867784.6492750645 0.0416345373 0.0257936330 0.0606744327 0.0048856783 0.0257950000 248620698 95654136 760807424 -0.0094754761 0.0002694121 -0.0285558235 1980 1311867784.6878700256 0.0444174819 0.0258030390 0.0606744327 0.0048864213 0.0258520000 248624338 95654136 760807424 -0.0099684298 0.0029710806 -0.0290246457 1981 1311867784.7168869972 0.0449701622 0.0258127145 0.0606744327 0.0048858701 0.0258820000 248626098 95654136 760807424 -0.0096777976 0.0034568280 -0.0290821400 1982 1311867784.7578089237 0.0424521193 0.0258211097 0.0606744327 0.0048877262 0.0367690000 248629906 95654136 760807424 -0.0110975280 0.0005039400 -0.0284741931 1983 1311867784.7870030403 0.0450424440 0.0258308028 0.0606744327 0.0048870063 0.0260280000 248633466 95654136 760807424 -0.0120103331 0.0030786099 -0.0284368787 1984 1311867784.8199620247 0.0448787920 0.0258404036 0.0606744327 0.0048865340 0.0292260000 248635026 95654136 760807424 -0.0135689396 0.0024090772 -0.0278990623 1985 1311867784.8550779819 0.0421204008 0.0258486051 0.0606744327 0.0048862260 0.0257930000 248638754 95654136 760807424 -0.0145431170 -0.0006924029 -0.0276261829 1986 1311867784.8873779774 0.0462044328 0.0258588548 0.0606744327 0.0048860014 0.0258020000 248642226 95654136 760807424 -0.0149179567 0.0035051396 -0.0283417422 1987 1311867784.9173130989 0.0467439108 0.0258693656 0.0606744327 0.0048858325 0.0258110000 248644098 95654136 760807424 -0.0161464307 0.0036004032 -0.0284584612 1988 1311867784.9491391182 0.0451153107 0.0258790467 0.0606744327 0.0048846980 0.0257860000 248647514 95654136 760807424 -0.0177066345 0.0015967749 -0.0280371122 1989 1311867784.9848570824 0.0457001589 0.0258890120 0.0606744327 0.0048839381 0.0292530000 248649498 95654136 760807424 -0.0187783781 0.0020133883 -0.0283879004 1990 1311867785.0184569359 0.0451988243 0.0258987155 0.0606744327 0.0048827555 0.0258640000 248652970 95654136 760807424 -0.0185619798 0.0013453667 -0.0286342204 1991 1311867785.0500280857 0.0460637584 0.0259088436 0.0606744327 0.0048822395 0.0258330000 248656698 95654136 760807424 -0.0196106080 0.0017076011 -0.0282444246 1992 1311867785.0871460438 0.0466369800 0.0259192492 0.0606744327 0.0048810274 0.0264890000 248658482 95654136 760807424 -0.0185637176 0.0025231401 -0.0286344215 1993 1311867785.1168398857 0.0455685854 0.0259291084 0.0606744327 0.0048801276 0.0299810000 248662154 95654136 760807424 -0.0189063270 0.0012807717 -0.0291704070 1994 1311867785.1499750614 0.0451477282 0.0259387466 0.0606744327 0.0048796062 0.0257650000 248663770 95654136 760807424 -0.0215506554 0.0000686320 -0.0285754204 1995 1311867785.1850368977 0.0472189151 0.0259494134 0.0606744327 0.0048786539 0.0256420000 248667554 95654136 760807424 -0.0204268936 0.0025915026 -0.0287482608 1996 1311867785.2169620991 0.0480954312 0.0259605086 0.0606744327 0.0048774922 0.0258660000 248670970 95654136 760807424 -0.0204643440 0.0033592647 -0.0286848191 1997 1311867785.2491741180 0.0463771522 0.0259707323 0.0606744327 0.0048766474 0.0369830000 248672842 95654136 760807424 -0.0197296683 0.0017206534 -0.0285126586 1998 1311867785.2858769894 0.0467600077 0.0259811373 0.0606744327 0.0048754738 0.0259460000 248676482 95654136 760807424 -0.0192535315 0.0023533856 -0.0286092553 1999 1311867785.3214280605 0.0458107144 0.0259910570 0.0606744327 0.0048768055 0.0258330000 248678578 95654136 760807424 -0.0192284994 0.0011738118 -0.0281639267 2000 1311867785.3573219776 0.0475767963 0.0260018499 0.0606744327 0.0048762407 0.0258130000 248852822 95654136 760807424 -0.0192815010 0.0029567240 -0.0282455795 2001 1311867785.3893299103 0.0483490191 0.0260130179 0.0606744327 0.0048750400 0.0296440000 248856494 95654136 760807424 -0.0192634184 0.0040235445 -0.0290827900 2002 1311867785.4211249352 0.0470937975 0.0260235478 0.0606744327 0.0048739375 0.0258150000 248858166 95654136 760807424 -0.0189918112 0.0025360317 -0.0279009826 2003 1311867785.4570529461 0.0478999689 0.0260344696 0.0606744327 0.0048745880 0.0257790000 248861950 95654136 760807424 -0.0187982824 0.0036727379 -0.0287025739 2004 1311867785.4900350571 0.0475602709 0.0260452110 0.0606744327 0.0048744823 0.0300040000 248865478 95654136 760807424 -0.0189071689 0.0038084963 -0.0292575695 2005 1311867785.5211930275 0.0452729687 0.0260548009 0.0606744327 0.0048733984 0.0282460000 248867294 95654136 760807424 -0.0200770926 0.0014076086 -0.0284613520 2006 1311867785.5571260452 0.0446967222 0.0260640940 0.0606744327 0.0048724104 0.0260690000 248870878 95654136 760807424 -0.0216175858 0.0005872631 -0.0283919703 2007 1311867785.5891211033 0.0456536636 0.0260738546 0.0606744327 0.0048712920 0.0297310000 248872750 95654136 760807424 -0.0200035349 0.0022620116 -0.0293846466 2008 1311867785.6211590767 0.0453634411 0.0260834610 0.0606744327 0.0048870597 0.0257550000 248876278 95654136 760807424 -0.0226387233 0.0015327503 -0.0284535848 2009 1311867785.6570439339 0.0449222066 0.0260928382 0.0606744327 0.0048873257 0.0256100000 248880062 95654136 760807424 -0.0238546971 0.0006563932 -0.0274972711 2010 1311867785.6892280579 0.0466363318 0.0261030588 0.0606744327 0.0048861482 0.0258860000 248881678 95654136 760807424 -0.0224817190 0.0028630923 -0.0284723286 2011 1311867785.7214241028 0.0466631800 0.0261132826 0.0606744327 0.0048876739 0.0257990000 248885350 95654136 760807424 -0.0228169393 0.0027513106 -0.0282254387 2012 1311867785.7573668957 0.0450557396 0.0261226974 0.0606744327 0.0048864864 0.0258800000 248887134 95654136 760807424 -0.0244708899 0.0003754036 -0.0273834616 2013 1311867785.7892301083 0.0460908152 0.0261326170 0.0606744327 0.0048855703 0.0376040000 248890806 95654136 760807424 -0.0253249425 0.0011426951 -0.0276894309 2014 1311867785.8210389614 0.0468391478 0.0261428983 0.0606744327 0.0048846971 0.0260040000 248894278 95654136 760807424 -0.0238955505 0.0020880955 -0.0280503556 2015 1311867785.8574340343 0.0463103987 0.0261529070 0.0606744327 0.0048835570 0.0259310000 248896262 95654136 760807424 -0.0238082055 0.0010065296 -0.0270628128 2016 1311867785.8893110752 0.0461244993 0.0261628135 0.0606744327 0.0048825806 0.0292110000 248899790 95654136 760807424 -0.0233477205 0.0008272902 -0.0279822145 2017 1311867785.9211509228 0.0465888195 0.0261729404 0.0606744327 0.0048818623 0.0257940000 248901662 95654136 760807424 -0.0232783798 0.0014679985 -0.0284191184 2018 1311867785.9588449001 0.0446872003 0.0261821150 0.0606744327 0.0048825343 0.0258230000 248905246 95654136 760807424 -0.0241826922 -0.0008502098 -0.0275168344 2019 1311867785.9892621040 0.0447317176 0.0261913025 0.0606744327 0.0048819482 0.0261590000 248908918 95654136 760807424 -0.0228898991 -0.0006778145 -0.0280379392 2020 1311867786.0210618973 0.0455213785 0.0262008718 0.0606744327 0.0048808817 0.0257930000 248910590 95654136 760807424 -0.0208768751 0.0004152253 -0.0282463245 2021 1311867786.0572268963 0.0446177460 0.0262099846 0.0606744327 0.0048816460 0.0299490000 248914318 95654136 760807424 -0.0233553089 -0.0009979189 -0.0272580106 2022 1311867786.0892500877 0.0433029532 0.0262184381 0.0606744327 0.0048807749 0.0257870000 248917846 95654136 760807424 -0.0225425866 -0.0024927719 -0.0273140967 2023 1311867786.1211619377 0.0448918343 0.0262276686 0.0606744327 0.0048796285 0.0296590000 248919774 95654136 760807424 -0.0222740881 -0.0010249104 -0.0281614475 2024 1311867786.1570990086 0.0433286391 0.0262361177 0.0606744327 0.0048786845 0.0295010000 248923302 95654136 760807424 -0.0236218590 -0.0031763134 -0.0279318821 2025 1311867786.1891019344 0.0420396291 0.0262439219 0.0606744327 0.0048776114 0.0258170000 249095430 95654136 760807424 -0.0241918545 -0.0048547415 -0.0276924688 2026 1311867786.2216470242 0.0434278138 0.0262524036 0.0606744327 0.0048766328 0.0257970000 249098902 95654136 760807424 -0.0235448424 -0.0034413449 -0.0286790729 2027 1311867786.2570950985 0.0426680706 0.0262605021 0.0606744327 0.0048755831 0.0263370000 249102742 95654136 760807424 -0.0239441302 -0.0044648964 -0.0285268016 2028 1311867786.2895779610 0.0401462764 0.0262673492 0.0606744327 0.0048748224 0.0292650000 249104358 95654136 760807424 -0.0249026231 -0.0074024424 -0.0278355256 2029 1311867786.3211650848 0.0412707478 0.0262747436 0.0606744327 0.0048742593 0.0258090000 249107974 95654136 760807424 -0.0247546416 -0.0062290635 -0.0291017033 2030 1311867786.3572299480 0.0415687673 0.0262822776 0.0606744327 0.0048730873 0.0258160000 249109814 95654136 760807424 -0.0247513633 -0.0061728102 -0.0288953800 2031 1311867786.3891439438 0.0401109457 0.0262890864 0.0606744327 0.0048730730 0.0257980000 249113430 95654136 760807424 -0.0258971266 -0.0081783570 -0.0277839657 2032 1311867786.4213869572 0.0413813703 0.0262965137 0.0606744327 0.0048723887 0.0257880000 249116958 95654136 760807424 -0.0267810412 -0.0073524565 -0.0285317600 2033 1311867786.4573409557 0.0413367227 0.0263039118 0.0606744327 0.0048712999 0.0259490000 249118942 95654136 760807424 -0.0269105677 -0.0071871248 -0.0290373247 2034 1311867786.4891700745 0.0390201174 0.0263101636 0.0606744327 0.0048703646 0.0258760000 249122358 95654136 760807424 -0.0273049958 -0.0102390563 -0.0274966639 2035 1311867786.5218079090 0.0384938717 0.0263161507 0.0606744327 0.0048695805 0.0257970000 249124286 95654136 760807424 -0.0270331446 -0.0109030679 -0.0282662157 2036 1311867786.5572519302 0.0390514731 0.0263224057 0.0606744327 0.0048689083 0.0281440000 249127870 95654136 760807424 -0.0273343101 -0.0107059227 -0.0289621055 2037 1311867786.5895760059 0.0373067781 0.0263277982 0.0606744327 0.0048687257 0.0257290000 249131542 95654136 760807424 -0.0275254790 -0.0128581580 -0.0286096092 2038 1311867786.6211080551 0.0373050123 0.0263331844 0.0606744327 0.0048677970 0.0258210000 249133214 95654136 760807424 -0.0261122473 -0.0133996960 -0.0288646054 2039 1311867786.6573529243 0.0377653837 0.0263387912 0.0606744327 0.0048667233 0.0262080000 249308886 95654136 760807424 -0.0261377264 -0.0131460736 -0.0295577925 2040 1311867786.6891629696 0.0363300592 0.0263436889 0.0606744327 0.0048656023 0.0260730000 249312302 95654136 760807424 -0.0279272199 -0.0150529500 -0.0286815185 2041 1311867786.7210969925 0.0371687450 0.0263489927 0.0606744327 0.0048644794 0.0258840000 249314174 95654136 760807424 -0.0281003863 -0.0145917628 -0.0286764372 2042 1311867786.7570719719 0.0379230790 0.0263546607 0.0606744327 0.0048635068 0.0320690000 249317702 95654136 760807424 -0.0281743761 -0.0132808695 -0.0298600234 2043 1311867786.7892940044 0.0376796424 0.0263602040 0.0606744327 0.0048623536 0.0258360000 249319630 95654136 760807424 -0.0288953278 -0.0142476670 -0.0284209847 2044 1311867786.8211419582 0.0380142592 0.0263659056 0.0606744327 0.0048617284 0.0336840000 249323102 95654136 760807424 -0.0304709822 -0.0141585404 -0.0275307894 2045 1311867786.8575630188 0.0398266725 0.0263724879 0.0606744327 0.0048613791 0.0263300000 249326830 95654136 760807424 -0.0283159204 -0.0117345732 -0.0285186134 2046 1311867786.8893759251 0.0377369858 0.0263780424 0.0606744327 0.0048607072 0.0258560000 249328558 95654136 760807424 -0.0285679679 -0.0138481250 -0.0266787000 2047 1311867786.9211881161 0.0360305570 0.0263827578 0.0606744327 0.0048618547 0.0257970000 249332230 95654136 760807424 -0.0286138766 -0.0160962809 -0.0258641187 2048 1311867786.9576020241 0.0387327038 0.0263887881 0.0606744327 0.0048610259 0.0258580000 249334070 95654136 760807424 -0.0271356553 -0.0129390080 -0.0271747094 2049 1311867786.9892089367 0.0364944339 0.0263937201 0.0606744327 0.0048613942 0.0260660000 249714462 95654136 760807424 -0.0280727204 -0.0153026842 -0.0254820362 2050 1311867787.0211400986 0.0351042636 0.0263979691 0.0606744327 0.0048618769 0.0260220000 250127590 95654136 760807424 -0.0292856731 -0.0176048260 -0.0238881465 2051 1311867787.0571250916 0.0368513204 0.0264030658 0.0606744327 0.0048610616 0.0260480000 250129630 95654136 760807424 -0.0273443591 -0.0156101007 -0.0258487668 2052 1311867787.0895950794 0.0353028812 0.0264074030 0.0606744327 0.0048599467 0.0310910000 250133046 95654136 760807424 -0.0275702998 -0.0174492169 -0.0252857078 2053 1311867787.1239550114 0.0341123305 0.0264111560 0.0606744327 0.0048589355 0.0258970000 250134974 95654136 760807424 -0.0307704043 -0.0197173953 -0.0235437844 2054 1311867787.1573429108 0.0357873999 0.0264157208 0.0606744327 0.0048584746 0.0258940000 250138502 95654136 760807424 -0.0270863008 -0.0175023600 -0.0265165791 2055 1311867787.1892991066 0.0354393050 0.0264201119 0.0606744327 0.0048573204 0.0296450000 250142174 95654136 760807424 -0.0271093268 -0.0178863723 -0.0259734690 2056 1311867787.2230238914 0.0342220590 0.0264239066 0.0606744327 0.0048564911 0.0258410000 250143902 95654136 760807424 -0.0295552202 -0.0198945031 -0.0243889131 2057 1311867787.2571809292 0.0379989780 0.0264295338 0.0606744327 0.0048555859 0.0259620000 250318078 95654136 760807424 -0.0286715254 -0.0158326626 -0.0260853712 2058 1311867787.2893400192 0.0359042883 0.0264341376 0.0606744327 0.0048545449 0.0258920000 250321550 95654136 760807424 -0.0297885966 -0.0179901756 -0.0257722810 2059 1311867787.3217399120 0.0343407542 0.0264379777 0.0606744327 0.0048534382 0.0258410000 250323422 95654136 760807424 -0.0313598253 -0.0200680234 -0.0248555150 2060 1311867787.3572421074 0.0368767194 0.0264430450 0.0606744327 0.0048525914 0.0259720000 250327006 95654136 760807424 -0.0301922727 -0.0171631705 -0.0267149527 2061 1311867787.3892920017 0.0370694585 0.0264482010 0.0606744327 0.0048518465 0.0258680000 250328878 95654136 760807424 -0.0309787933 -0.0170923490 -0.0263701156 2062 1311867787.4245440960 0.0360580720 0.0264528614 0.0606744327 0.0048507291 0.0259460000 250332406 95654136 760807424 -0.0330241248 -0.0190772824 -0.0249917954 2063 1311867787.4572229385 0.0372219905 0.0264580815 0.0606744327 0.0048496902 0.0267060000 250336134 95654136 760807424 -0.0338520445 -0.0180386454 -0.0259245150 2064 1311867787.4892969131 0.0366095603 0.0264629999 0.0606744327 0.0048490002 0.0259210000 250337750 95654136 760807424 -0.0326146968 -0.0184767991 -0.0271004774 2065 1311867787.5220890045 0.0340259112 0.0264666623 0.0606744327 0.0048479029 0.0258140000 250341422 95654136 760807424 -0.0345873013 -0.0220716521 -0.0252101589 2066 1311867787.5581040382 0.0364420265 0.0264714907 0.0606744327 0.0048469959 0.0259200000 250343206 95654136 760807424 -0.0344459154 -0.0198993925 -0.0263025928 2067 1311867787.5897688866 0.0368378833 0.0264765059 0.0606744327 0.0048459219 0.0258950000 250346934 95654136 760807424 -0.0325068161 -0.0191678628 -0.0275986977 2068 1311867787.6235499382 0.0348767787 0.0264805679 0.0606744327 0.0048448311 0.0302470000 250350406 95654136 760807424 -0.0338022076 -0.0218759123 -0.0260540638 2069 1311867787.6574609280 0.0338816531 0.0264841450 0.0606744327 0.0048436966 0.0259910000 250522142 95654136 760807424 -0.0351301357 -0.0230144039 -0.0275374595 2070 1311867787.6898610592 0.0351695083 0.0264883408 0.0606744327 0.0048426466 0.0259300000 250525670 95654136 760807424 -0.0347435921 -0.0218129996 -0.0290370509 2071 1311867787.7212240696 0.0355628245 0.0264927225 0.0606744327 0.0048415670 0.0299950000 250527542 95654136 760807424 -0.0344913118 -0.0216102302 -0.0288928747 2072 1311867787.7579810619 0.0354486592 0.0264970449 0.0606744327 0.0048410401 0.0258560000 250531126 95654136 760807424 -0.0358670428 -0.0218081977 -0.0278443508 2073 1311867787.7901558876 0.0344452560 0.0265008791 0.0606744327 0.0048410337 0.0258440000 250534798 95654136 760807424 -0.0345555283 -0.0225895774 -0.0294577312 2074 1311867787.8218519688 0.0337302014 0.0265043648 0.0606744327 0.0048406758 0.0259940000 250536526 95654136 760807424 -0.0336904228 -0.0234887451 -0.0290098991 2075 1311867787.8573749065 0.0331284367 0.0265075571 0.0606744327 0.0048396485 0.0265820000 250540198 95654136 760807424 -0.0343513899 -0.0250994060 -0.0281358380 2076 1311867787.8894400597 0.0325110741 0.0265104489 0.0606744327 0.0048390689 0.0352340000 250543726 95654136 760807424 -0.0333588161 -0.0250153914 -0.0309630949 2077 1311867787.9214320183 0.0333250798 0.0265137299 0.0606744327 0.0048380415 0.0260520000 250545654 95654136 760807424 -0.0329493918 -0.0242474359 -0.0311180633 2078 1311867787.9577279091 0.0312534757 0.0265160109 0.0606744327 0.0048371395 0.0259880000 250549182 95654136 760807424 -0.0343512632 -0.0272008572 -0.0300150849 2079 1311867787.9892189503 0.0327589549 0.0265190137 0.0606744327 0.0048360357 0.0258750000 250550998 95654136 760807424 -0.0353242345 -0.0252780654 -0.0320286602 2080 1311867788.0211091042 0.0335214995 0.0265223803 0.0606744327 0.0048349920 0.0293600000 250554526 95654136 760807424 -0.0342551023 -0.0244900323 -0.0330054276 2081 1311867788.0577259064 0.0334666669 0.0265257173 0.0606744327 0.0048346837 0.0259130000 250728558 95654136 760807424 -0.0368444547 -0.0244027190 -0.0317599252 2082 1311867788.0892241001 0.0331633314 0.0265289054 0.0606744327 0.0048335762 0.0258880000 250730174 95654136 760807424 -0.0372478180 -0.0243922416 -0.0325936414 2083 1311867788.1307280064 0.0340805911 0.0265325308 0.0606744327 0.0048332324 0.0289260000 250734126 95654136 760807424 -0.0373366438 -0.0231939666 -0.0325065628 2084 1311867788.1572849751 0.0343915261 0.0265363019 0.0606744327 0.0048326282 0.0263040000 250735686 95654136 760807424 -0.0389179289 -0.0230102018 -0.0305955447 2085 1311867788.1904621124 0.0338450037 0.0265398073 0.0606744327 0.0048316837 0.0259570000 250739358 95654136 760807424 -0.0392021947 -0.0234295372 -0.0308920052 2086 1311867788.2247180939 0.0347298272 0.0265437334 0.0606744327 0.0048308028 0.0259640000 250742886 95654136 760807424 -0.0377862118 -0.0220599677 -0.0323031135 2087 1311867788.2583730221 0.0336668789 0.0265471465 0.0606744327 0.0048297305 0.0259630000 250744758 95654136 760807424 -0.0389608704 -0.0230821744 -0.0309276748 2088 1311867788.2893440723 0.0328154378 0.0265501486 0.0606744327 0.0048289818 0.0260760000 250748230 95654136 760807424 -0.0389175303 -0.0240298081 -0.0305421241 2089 1311867788.3251628876 0.0326854624 0.0265530856 0.0606744327 0.0048282395 0.0261120000 250750214 95654136 760807424 -0.0390666649 -0.0239127837 -0.0318246335 2090 1311867788.3571081161 0.0322992578 0.0265558349 0.0606744327 0.0048273372 0.0260360000 250753686 95654136 760807424 -0.0396105088 -0.0243659876 -0.0308129285 2091 1311867788.3910779953 0.0322553143 0.0265585606 0.0606744327 0.0048262378 0.0259690000 250757414 95654136 760807424 -0.0413264446 -0.0245555788 -0.0295953956 2092 1311867788.4251430035 0.0315505825 0.0265609469 0.0606744327 0.0048252698 0.0259960000 250759142 95654136 760807424 -0.0423629172 -0.0250704829 -0.0307373367 2093 1311867788.4573140144 0.0312496740 0.0265631871 0.0606744327 0.0048241937 0.0259590000 250762814 95654136 760807424 -0.0425352566 -0.0255845357 -0.0305542555 2094 1311867788.4924380779 0.0306609999 0.0265651440 0.0606744327 0.0048232317 0.0260490000 250766342 95654136 760807424 -0.0435890444 -0.0265155844 -0.0296909939 2095 1311867788.5262899399 0.0305338092 0.0265670384 0.0606744327 0.0048226402 0.0259240000 250768270 95654136 760807424 -0.0435114503 -0.0267113131 -0.0304150470 2096 1311867788.5573079586 0.0311317630 0.0265692162 0.0606744327 0.0048216756 0.0259330000 250771742 95654136 760807424 -0.0428345427 -0.0259125307 -0.0319802500 2097 1311867788.5915369987 0.0326968133 0.0265721383 0.0606744327 0.0048212141 0.0258600000 250773670 95654136 760807424 -0.0435500741 -0.0245331619 -0.0305168424 2098 1311867788.6251940727 0.0342293568 0.0265757880 0.0606744327 0.0048203967 0.0260160000 250777142 95654136 760807424 -0.0439371020 -0.0234402902 -0.0294537004 2099 1311867788.6593029499 0.0333518460 0.0265790163 0.0606744327 0.0048201441 0.0366570000 250780870 95654136 760807424 -0.0440934822 -0.0238757227 -0.0330256298 2100 1311867788.6898009777 0.0350599736 0.0265830548 0.0606744327 0.0048193570 0.0261250000 250952894 95654136 760807424 -0.0450489484 -0.0222285874 -0.0323846824 2101 1311867788.7262809277 0.0365557782 0.0265878015 0.0606744327 0.0048193187 0.0303080000 250956734 95654136 760807424 -0.0457528159 -0.0214613788 -0.0304699168 2102 1311867788.7571070194 0.0373434350 0.0265929183 0.0606744327 0.0048185184 0.0259410000 250958406 95654136 760807424 -0.0475273803 -0.0203875955 -0.0325724334 2103 1311867788.7899940014 0.0360072777 0.0265973950 0.0606744327 0.0048174437 0.0261470000 250962022 95654136 760807424 -0.0482808463 -0.0218153261 -0.0333721302 2104 1311867788.8253190517 0.0351952650 0.0266014814 0.0606744327 0.0048165146 0.0258740000 250965662 95654136 760807424 -0.0511002131 -0.0232145321 -0.0320252031 2105 1311867788.8572509289 0.0351095572 0.0266055233 0.0606744327 0.0048158037 0.0259800000 250967534 95654136 760807424 -0.0519193821 -0.0232240632 -0.0351348370 2106 1311867788.8892900944 0.0342813917 0.0266091680 0.0606744327 0.0048146946 0.0299050000 250970950 95654136 760807424 -0.0524198264 -0.0242298134 -0.0353948213 2107 1311867788.9253408909 0.0338695198 0.0266126138 0.0606744327 0.0048138693 0.0298320000 250972990 95654136 760807424 -0.0533220954 -0.0252545029 -0.0344334841 2108 1311867788.9572029114 0.0329944678 0.0266156413 0.0606744327 0.0048136765 0.0260080000 250976462 95654136 760807424 -0.0527330972 -0.0261602793 -0.0358673446 2109 1311867788.9914720058 0.0345188752 0.0266193887 0.0606744327 0.0048131915 0.0293260000 250980190 95654136 760807424 -0.0525604449 -0.0248351973 -0.0364056602 2110 1311867789.0253350735 0.0357218273 0.0266237026 0.0606744327 0.0048122325 0.0259200000 250981862 95654136 760807424 -0.0535405166 -0.0237724353 -0.0359008275 2111 1311867789.0572888851 0.0352487117 0.0266277884 0.0606744327 0.0048112885 0.0269050000 250985534 95654136 760807424 -0.0528331399 -0.0244388338 -0.0357660502 2112 1311867789.0921590328 0.0352330394 0.0266318628 0.0606744327 0.0048102420 0.0301620000 250989118 95654136 760807424 -0.0542007834 -0.0245842934 -0.0360335447 2113 1311867789.1266920567 0.0351589434 0.0266358984 0.0606744327 0.0048091642 0.0259470000 250991102 95654136 760807424 -0.0549974479 -0.0247046407 -0.0362787917 2114 1311867789.1574180126 0.0357152149 0.0266401932 0.0606744327 0.0048092713 0.0373910000 250994462 95654136 760807424 -0.0552208722 -0.0244155023 -0.0353833288 2115 1311867789.1895699501 0.0354068540 0.0266443382 0.0606744327 0.0048082125 0.0262250000 250996390 95654136 760807424 -0.0560991950 -0.0250209402 -0.0345740058 2116 1311867789.2251811028 0.0357160494 0.0266486254 0.0606744327 0.0048073712 0.0259440000 250999974 95654136 760807424 -0.0570074879 -0.0247547682 -0.0348386429 2117 1311867789.2573940754 0.0356725641 0.0266528880 0.0606744327 0.0048065520 0.0259540000 251003590 95654136 760807424 -0.0578923561 -0.0248384196 -0.0355757102 2118 1311867789.2926049232 0.0360589288 0.0266573290 0.0606744327 0.0048057596 0.0259830000 251005374 95654136 760807424 -0.0586982407 -0.0247720871 -0.0346558467 2119 1311867789.3252000809 0.0345974155 0.0266610761 0.0606744327 0.0048046756 0.0259710000 251009102 95654136 760807424 -0.0611956306 -0.0263018105 -0.0345716625 2120 1311867789.3589100838 0.0362722501 0.0266656097 0.0606744327 0.0048036457 0.0260060000 251010774 95654136 760807424 -0.0616006926 -0.0246119685 -0.0357394218 2121 1311867789.3897531033 0.0363349430 0.0266701685 0.0606744327 0.0048026444 0.0291580000 251014446 95654136 760807424 -0.0622575730 -0.0245609377 -0.0366208851 2122 1311867789.4252359867 0.0370255001 0.0266750485 0.0606744327 0.0048023555 0.0259720000 251018030 95654136 760807424 -0.0636997893 -0.0242590774 -0.0349557884 2123 1311867789.4577910900 0.0379542559 0.0266803614 0.0606744327 0.0048018108 0.0260040000 251019846 95654136 760807424 -0.0652739182 -0.0234714486 -0.0352261215 2124 1311867789.4892559052 0.0364610516 0.0266849662 0.0606744327 0.0048007274 0.0260500000 251023374 95654136 760807424 -0.0664180070 -0.0248760674 -0.0365305208 2125 1311867789.5256059170 0.0364573188 0.0266895650 0.0606744327 0.0047996118 0.0259530000 251025302 95654136 760807424 -0.0671663508 -0.0250379238 -0.0360745154 2126 1311867789.5572779179 0.0374549292 0.0266946286 0.0606744327 0.0047986501 0.0294840000 251198678 95654136 760807424 -0.0682799369 -0.0244722292 -0.0358717404 2127 1311867789.5892720222 0.0375084206 0.0266997127 0.0606744327 0.0047983052 0.0260010000 251202294 95654136 760807424 -0.0679408535 -0.0239903443 -0.0384068340 2128 1311867789.6253700256 0.0372795910 0.0267046844 0.0606744327 0.0047973455 0.0259440000 251204134 95654136 760807424 -0.0683641285 -0.0241488479 -0.0387096666 2129 1311867789.6574499607 0.0360453725 0.0267090718 0.0606744327 0.0047962943 0.0378230000 251207806 95654136 760807424 -0.0699606836 -0.0253254734 -0.0386230871 2130 1311867789.6894960403 0.0363140963 0.0267135812 0.0606744327 0.0047952052 0.0261720000 251211222 95654136 760807424 -0.0708102658 -0.0249000005 -0.0386142135 2131 1311867789.7253561020 0.0363895707 0.0267181218 0.0606744327 0.0047953070 0.0259630000 251213206 95654136 760807424 -0.0701162815 -0.0240401309 -0.0405992344 2132 1311867789.7572269440 0.0372250229 0.0267230500 0.0606744327 0.0047945189 0.0260360000 251216678 95654136 760807424 -0.0703009591 -0.0228462499 -0.0401796773 2133 1311867789.7893610001 0.0369757935 0.0267278567 0.0606744327 0.0047941251 0.0260270000 251218550 95654136 760807424 -0.0713392124 -0.0231307819 -0.0389277190 2134 1311867789.8253350258 0.0362317637 0.0267323103 0.0606744327 0.0047932408 0.0267040000 251222134 95654136 760807424 -0.0728799328 -0.0234385654 -0.0387222990 2135 1311867789.8573670387 0.0381915905 0.0267376776 0.0606744327 0.0047927052 0.0260990000 251225862 95654136 760807424 -0.0731455684 -0.0212610830 -0.0381464213 2136 1311867789.8893530369 0.0390869305 0.0267434591 0.0606744327 0.0047916201 0.0289240000 251227478 95654136 760807424 -0.0734244734 -0.0200701002 -0.0373815224 2137 1311867789.9253480434 0.0409296714 0.0267500975 0.0606744327 0.0047907981 0.0261430000 251231262 95654136 760807424 -0.0739916936 -0.0180959161 -0.0368767790 2138 1311867789.9573481083 0.0410883203 0.0267568039 0.0606744327 0.0047897516 0.0302050000 251232878 95654136 760807424 -0.0747151226 -0.0178865679 -0.0369556248 2139 1311867789.9892580509 0.0411485098 0.0267635321 0.0606744327 0.0047893866 0.0260430000 251236550 95654136 760807424 -0.0753380284 -0.0174080934 -0.0367959104 2140 1311867790.0253860950 0.0397941023 0.0267696211 0.0606744327 0.0047886380 0.0262740000 251411082 95654136 760807424 -0.0761861801 -0.0185606126 -0.0374644734 2141 1311867790.0572309494 0.0395582877 0.0267755944 0.0606744327 0.0047875443 0.0261220000 251412898 95654136 760807424 -0.0763051510 -0.0185160674 -0.0366301239 2142 1311867790.0896899700 0.0373258069 0.0267805198 0.0606744327 0.0047876551 0.0261070000 251416426 95654136 760807424 -0.0774125382 -0.0201252885 -0.0378579497 2143 1311867790.1257700920 0.0387910903 0.0267861243 0.0606744327 0.0047867575 0.0303220000 251418410 95654136 760807424 -0.0774798840 -0.0184017569 -0.0370486714 2144 1311867790.1572160721 0.0387080535 0.0267916849 0.0606744327 0.0047858520 0.0360760000 251421826 95654136 760807424 -0.0785885379 -0.0181520768 -0.0368112363 2145 1311867790.1894400120 0.0375798829 0.0267967144 0.0606744327 0.0047851755 0.0261990000 251425554 95654136 760807424 -0.0791821703 -0.0188668370 -0.0378111824 2146 1311867790.2254109383 0.0380029827 0.0268019363 0.0606744327 0.0047843375 0.0263840000 251427338 95654136 760807424 -0.0781180710 -0.0182213634 -0.0375348926 2147 1311867790.2576739788 0.0377394892 0.0268070307 0.0606744327 0.0047832437 0.0260790000 251431066 95654136 760807424 -0.0781946331 -0.0184865166 -0.0364323817 2148 1311867790.2894508839 0.0369745120 0.0268117641 0.0606744327 0.0047824089 0.0261380000 251434482 95654136 760807424 -0.0795622915 -0.0185601097 -0.0375261419 2149 1311867790.3254859447 0.0369552448 0.0268164842 0.0606744327 0.0047814434 0.0260920000 251436466 95654136 760807424 -0.0798923373 -0.0188505985 -0.0371294878 2150 1311867790.3573629856 0.0365857482 0.0268210281 0.0606744327 0.0047812506 0.0262290000 251439938 95654136 760807424 -0.0800495967 -0.0188614894 -0.0367164984 2151 1311867790.3896288872 0.0358926691 0.0268252455 0.0606744327 0.0047804119 0.0303670000 251441810 95654136 760807424 -0.0815978721 -0.0197683740 -0.0373096764 2152 1311867790.4259679317 0.0363391191 0.0268296664 0.0606744327 0.0047813294 0.0262410000 251445450 95654136 760807424 -0.0810863823 -0.0191641413 -0.0380051956 2153 1311867790.4603750706 0.0350642353 0.0268334911 0.0606744327 0.0047826938 0.0261170000 251449178 95654136 760807424 -0.0819925517 -0.0199746657 -0.0375726260 2154 1311867790.4893760681 0.0356985591 0.0268376067 0.0606744327 0.0047817157 0.0300670000 251450738 95654136 760807424 -0.0839033127 -0.0191009361 -0.0380291156 2155 1311867790.5260839462 0.0370025598 0.0268423237 0.0606744327 0.0047810345 0.0261820000 251624746 95654136 760807424 -0.0828600675 -0.0176514592 -0.0386804156 2156 1311867790.5578188896 0.0365886651 0.0268468442 0.0606744327 0.0047802993 0.0259100000 251626362 95654136 760807424 -0.0834496692 -0.0176277980 -0.0381149054 2157 1311867790.5941619873 0.0344658904 0.0268503765 0.0606744327 0.0047807995 0.0262220000 251630146 95654136 760807424 -0.0845467970 -0.0186785925 -0.0377318971 2158 1311867790.6255199909 0.0345129818 0.0268539273 0.0606744327 0.0047799997 0.0262910000 251633674 95654136 760807424 -0.0848278776 -0.0185930897 -0.0379318036 2159 1311867790.6573970318 0.0352696739 0.0268578252 0.0606744327 0.0047795057 0.0262120000 251635434 95654136 760807424 -0.0855525658 -0.0185512900 -0.0392073095 2160 1311867790.6901810169 0.0359859616 0.0268620512 0.0606744327 0.0047802172 0.0292660000 251638962 95654136 760807424 -0.0862213299 -0.0177369062 -0.0386575051 2161 1311867790.7253530025 0.0375227965 0.0268669845 0.0606744327 0.0047803827 0.0261760000 251640890 95654136 760807424 -0.0882018954 -0.0161072314 -0.0381667465 2162 1311867790.7575750351 0.0383203104 0.0268722820 0.0606744327 0.0047794819 0.0261480000 251644362 95654136 760807424 -0.0890941322 -0.0149461888 -0.0390374362 2163 1311867790.7912769318 0.0399217755 0.0268783151 0.0606744327 0.0047784587 0.0261680000 251648090 95654136 760807424 -0.0898417905 -0.0128709860 -0.0398183390 2164 1311867790.8261909485 0.0395755619 0.0268841826 0.0606744327 0.0047774347 0.0262200000 251649874 95654136 760807424 -0.0898195803 -0.0128495721 -0.0384682007 2165 1311867790.8573698997 0.0382648371 0.0268894392 0.0606744327 0.0047763609 0.0261530000 251653546 95654136 760807424 -0.0908574462 -0.0137523999 -0.0382032841 2166 1311867790.8950428963 0.0381585695 0.0268946420 0.0606744327 0.0047755847 0.0261920000 251657130 95654136 760807424 -0.0909496695 -0.0129451342 -0.0402338356 2167 1311867790.9258179665 0.0380431861 0.0268997867 0.0606744327 0.0047745220 0.0303620000 251659002 95654136 760807424 -0.0902659222 -0.0124779241 -0.0396154448 2168 1311867790.9607090950 0.0379578397 0.0269048872 0.0606744327 0.0047734615 0.0263110000 251832926 95654136 760807424 -0.0910638869 -0.0121916682 -0.0374998823 2169 1311867790.9944651127 0.0363922007 0.0269092613 0.0606744327 0.0047727934 0.0262390000 251834854 95654136 760807424 -0.0928144082 -0.0132610723 -0.0385113135 2170 1311867791.0299000740 0.0375578254 0.0269141685 0.0606744327 0.0047722732 0.0269490000 251838438 95654136 760807424 -0.0928540528 -0.0117371790 -0.0378029682 2171 1311867791.0577330589 0.0382375158 0.0269193842 0.0606744327 0.0047716671 0.0296730000 251841886 95654136 760807424 -0.0924996734 -0.0111260042 -0.0355207995 2172 1311867791.0913140774 0.0374166183 0.0269242172 0.0606744327 0.0047706378 0.0262080000 251843670 95654136 760807424 -0.0942893624 -0.0115304533 -0.0363884829 2173 1311867791.1254060268 0.0367324390 0.0269287309 0.0606744327 0.0047704077 0.0262430000 251847398 95654136 760807424 -0.0948827341 -0.0117297806 -0.0376672931 2174 1311867791.1664540768 0.0372504033 0.0269334786 0.0606744327 0.0047705906 0.0263620000 251849350 95654136 760807424 -0.0944856182 -0.0109743020 -0.0364174917 2175 1311867791.1905651093 0.0355861709 0.0269374569 0.0606744327 0.0047707896 0.0300970000 251852798 95654136 760807424 -0.0964886248 -0.0127358744 -0.0359300710 2176 1311867791.2257969379 0.0335248113 0.0269404842 0.0606744327 0.0047706790 0.0287790000 251856382 95654136 760807424 -0.0973964334 -0.0148728993 -0.0361678340 2177 1311867791.2579009533 0.0325322524 0.0269430527 0.0606744327 0.0047716890 0.0304440000 251858198 95654136 760807424 -0.0965678170 -0.0160290487 -0.0360247754 2178 1311867791.2920219898 0.0325094052 0.0269456084 0.0606744327 0.0047706238 0.0261440000 251861726 95654136 760807424 -0.0961585641 -0.0162347872 -0.0367644578 2179 1311867791.3277790546 0.0325885005 0.0269481981 0.0606744327 0.0047705886 0.0263760000 251863710 95654136 760807424 -0.0967116579 -0.0162177756 -0.0367160104 2180 1311867791.3597049713 0.0329735503 0.0269509620 0.0606744327 0.0047726479 0.0262630000 251867238 95654136 760807424 -0.0967609882 -0.0160120819 -0.0360117294 2181 1311867791.3896780014 0.0324244089 0.0269534716 0.0606744327 0.0047716382 0.0262940000 251870854 95654136 760807424 -0.0974165499 -0.0164560005 -0.0371261723 2182 1311867791.4270040989 0.0328972042 0.0269561956 0.0606744327 0.0047709875 0.0271280000 251872694 95654136 760807424 -0.0981438681 -0.0162661038 -0.0362863652 2183 1311867791.4574470520 0.0324526466 0.0269587135 0.0606744327 0.0047701942 0.0265160000 252045786 95654136 760807424 -0.0995160416 -0.0168023463 -0.0361136608 2184 1311867791.4916520119 0.0326726437 0.0269613297 0.0606744327 0.0047730315 0.0263140000 252049314 95654136 760807424 -0.1009848192 -0.0163715780 -0.0367443599 2185 1311867791.5275359154 0.0352554135 0.0269651257 0.0606744327 0.0047722920 0.0304490000 252051298 95654136 760807424 -0.1013195440 -0.0137189087 -0.0368666165 2186 1311867791.5593819618 0.0354334079 0.0269689995 0.0606744327 0.0047712277 0.0261170000 252054770 95654136 760807424 -0.1010655016 -0.0133445347 -0.0373827629 2187 1311867791.5894811153 0.0353376828 0.0269728261 0.0606744327 0.0047702721 0.0262870000 252056586 95654136 760807424 -0.1016525552 -0.0134202922 -0.0366868190 2188 1311867791.6275899410 0.0345007181 0.0269762666 0.0606744327 0.0047694963 0.0262830000 252060226 95654136 760807424 -0.1036281437 -0.0142685855 -0.0369980820 2189 1311867791.6574349403 0.0350234360 0.0269799428 0.0606744327 0.0047688574 0.0265720000 252063898 95654136 760807424 -0.1042243168 -0.0137178591 -0.0361808278 2190 1311867791.6894969940 0.0351716131 0.0269836833 0.0606744327 0.0047679767 0.0261690000 252065514 95654136 760807424 -0.1031440198 -0.0132710421 -0.0362005569 2191 1311867791.7263259888 0.0353054032 0.0269874814 0.0606744327 0.0047670163 0.0304250000 252069354 95654136 760807424 -0.1041170359 -0.0128944702 -0.0367987938 2192 1311867791.7602820396 0.0356172659 0.0269914184 0.0606744327 0.0047663524 0.0263220000 252071082 95654136 760807424 -0.1045557186 -0.0124466065 -0.0361140817 2193 1311867791.7897930145 0.0356913321 0.0269953855 0.0606744327 0.0047655887 0.0431190000 252074698 95654136 760807424 -0.1065593809 -0.0121935457 -0.0369379520 2194 1311867791.8265190125 0.0362045355 0.0269995829 0.0606744327 0.0047647203 0.0268870000 252078282 95654136 760807424 -0.1066599637 -0.0113929808 -0.0365649350 2195 1311867791.8574469090 0.0366585962 0.0270039834 0.0606744327 0.0047638532 0.0262590000 252080154 95654136 760807424 -0.1068197712 -0.0109090898 -0.0360468440 2196 1311867791.8895421028 0.0358256884 0.0270080006 0.0606744327 0.0047629651 0.0262820000 252083570 95654136 760807424 -0.1067738086 -0.0113833463 -0.0376382880 2197 1311867791.9276258945 0.0366834924 0.0270124045 0.0606744327 0.0047619364 0.0262480000 252085610 95654136 760807424 -0.1066834182 -0.0103686629 -0.0370629318 2198 1311867791.9574968815 0.0367389247 0.0270168297 0.0606744327 0.0047611406 0.0390840000 252089026 95654136 760807424 -0.1048687473 -0.0101174433 -0.0355338901 2199 1311867791.9918000698 0.0353755765 0.0270206308 0.0606744327 0.0047604352 0.0303610000 252092642 95654136 760807424 -0.1081217676 -0.0113137271 -0.0379285403 2200 1311867792.0277240276 0.0341635980 0.0270238776 0.0606744327 0.0047595178 0.0261950000 252094370 95654136 760807424 -0.1070125699 -0.0123100830 -0.0376260802 2201 1311867792.0615789890 0.0334161259 0.0270267819 0.0606744327 0.0047587723 0.0299660000 252098210 95654136 760807424 -0.1051986888 -0.0131059485 -0.0358204842 2202 1311867792.0946090221 0.0316512808 0.0270288820 0.0606744327 0.0047585981 0.0262370000 252101626 95654136 760807424 -0.1067851260 -0.0143654170 -0.0383281671 2203 1311867792.1256630421 0.0320859440 0.0270311776 0.0606744327 0.0047575560 0.0272930000 252103498 95654136 760807424 -0.1077833101 -0.0138798542 -0.0385701172 2204 1311867792.1595768929 0.0319610834 0.0270334144 0.0606744327 0.0047567104 0.0261630000 252277274 95654136 760807424 -0.1053663790 -0.0140452199 -0.0367398039 2205 1311867792.1948819160 0.0297085196 0.0270346276 0.0606744327 0.0047578563 0.0379090000 252279258 95654136 760807424 -0.1065015644 -0.0155371819 -0.0384396836 2206 1311867792.2253580093 0.0299192499 0.0270359352 0.0606744327 0.0047657254 0.0265720000 252282674 95654136 760807424 -0.1069945395 -0.0152750509 -0.0408801585 2207 1311867792.2575860023 0.0308578946 0.0270376669 0.0606744327 0.0047649177 0.0297350000 252286346 95654136 760807424 -0.1063647270 -0.0145336958 -0.0393665098 2208 1311867792.2995440960 0.0303612966 0.0270391722 0.0606744327 0.0047639005 0.0262920000 252288298 95654136 760807424 -0.1067801863 -0.0148670124 -0.0391695015 2209 1311867792.3314530849 0.0280478373 0.0270396288 0.0606744327 0.0047646496 0.0262180000 252291970 95654136 760807424 -0.1078809351 -0.0168079436 -0.0417131968 2210 1311867792.3589100838 0.0262941290 0.0270392915 0.0606744327 0.0047637920 0.0262600000 252293474 95654136 760807424 -0.1078760773 -0.0185945593 -0.0421551876 2211 1311867792.3954761028 0.0268896334 0.0270392238 0.0606744327 0.0047630145 0.0262310000 252297314 95654136 760807424 -0.1064490527 -0.0182931554 -0.0408173949 2212 1311867792.4281890392 0.0271938536 0.0270392937 0.0606744327 0.0047620702 0.0263480000 252300786 95654136 760807424 -0.1074872836 -0.0177719388 -0.0413610153 2213 1311867792.4589219093 0.0246988032 0.0270382361 0.0606744327 0.0047617832 0.0261930000 252302602 95654136 760807424 -0.1093750224 -0.0202180799 -0.0434910990 2214 1311867792.4948880672 0.0259099547 0.0270377265 0.0606744327 0.0047613196 0.0269040000 252306186 95654136 760807424 -0.1094105989 -0.0190627966 -0.0423165672 2215 1311867792.5256149769 0.0256417189 0.0270370962 0.0606744327 0.0047607982 0.0304790000 252308058 95654136 760807424 -0.1103974804 -0.0192674045 -0.0424331650 2216 1311867792.5579619408 0.0265948903 0.0270368967 0.0606744327 0.0047597655 0.0262520000 252311474 95654136 760807424 -0.1110455468 -0.0182402208 -0.0433069803 2217 1311867792.5937440395 0.0261189528 0.0270364826 0.0606744327 0.0047587267 0.0263590000 252315202 95654136 760807424 -0.1113980338 -0.0187250096 -0.0432625711 2218 1311867792.6254990101 0.0272322521 0.0270365709 0.0606744327 0.0047579539 0.0263110000 252316818 95654136 760807424 -0.1112548411 -0.0175256301 -0.0430629961 2219 1311867792.6587610245 0.0272532217 0.0270366685 0.0606744327 0.0047569930 0.0261960000 252320546 95654136 760807424 -0.1121669337 -0.0173725784 -0.0435417593 2220 1311867792.6947619915 0.0261814240 0.0270362833 0.0606744327 0.0047560013 0.0384060000 252494906 95654136 760807424 -0.1117995754 -0.0185393225 -0.0428876430 2221 1311867792.7254660130 0.0252092127 0.0270354606 0.0606744327 0.0047557879 0.0264430000 252496778 95654136 760807424 -0.1114430875 -0.0194439106 -0.0445301607 2222 1311867792.7574810982 0.0256454907 0.0270348351 0.0606744327 0.0047553924 0.0261630000 252500250 95654136 760807424 -0.1108972207 -0.0189347547 -0.0440870114 2223 1311867792.7968890667 0.0259828828 0.0270343619 0.0606744327 0.0047556073 0.0262760000 252502346 95654136 760807424 -0.1118880808 -0.0187936816 -0.0433440693 2224 1311867792.8254449368 0.0264549423 0.0270341014 0.0606744327 0.0047550401 0.0261430000 252505650 95654136 760807424 -0.1123037934 -0.0178553574 -0.0435606651 2225 1311867792.8578031063 0.0283168536 0.0270346779 0.0606744327 0.0047542574 0.0260430000 252509322 95654136 760807424 -0.1123491526 -0.0159900915 -0.0447333716 2226 1311867792.8974819183 0.0287092440 0.0270354302 0.0606744327 0.0047532041 0.0261800000 252511274 95654136 760807424 -0.1118690670 -0.0157602858 -0.0439197831 2227 1311867792.9254279137 0.0277868565 0.0270357676 0.0606744327 0.0047521956 0.0262050000 252514778 95654136 760807424 -0.1127280742 -0.0162940677 -0.0452245027 2228 1311867792.9580180645 0.0260843672 0.0270353405 0.0606744327 0.0047518209 0.0303230000 252516506 95654136 760807424 -0.1142855287 -0.0178569835 -0.0453672111 2229 1311867792.9958879948 0.0277002249 0.0270356388 0.0606744327 0.0047521664 0.0261910000 252520346 95654136 760807424 -0.1149122715 -0.0163222179 -0.0438879840 2230 1311867793.0254249573 0.0284367166 0.0270362671 0.0606744327 0.0047512869 0.0261900000 252523706 95654136 760807424 -0.1159851998 -0.0154445143 -0.0444494449 2231 1311867793.0575890541 0.0283822790 0.0270368704 0.0606744327 0.0047507783 0.0261290000 252525578 95654136 760807424 -0.1162366197 -0.0154588725 -0.0452118516 2232 1311867793.0956139565 0.0301829167 0.0270382800 0.0606744327 0.0047499586 0.0261990000 252698926 95654136 760807424 -0.1168458015 -0.0134218819 -0.0447719730 2233 1311867793.1253910065 0.0306864809 0.0270399137 0.0606744327 0.0047489030 0.0261850000 252700686 95654136 760807424 -0.1169261858 -0.0130102439 -0.0453220345 2234 1311867793.1573770046 0.0293980800 0.0270409693 0.0606744327 0.0047479573 0.0260390000 252704158 95654136 760807424 -0.1175022349 -0.0140357791 -0.0456226990 2235 1311867793.1934790611 0.0297164712 0.0270421664 0.0606744327 0.0047470129 0.0261570000 252707942 95654136 760807424 -0.1184197366 -0.0133598633 -0.0446035042 2236 1311867793.2255470753 0.0288597420 0.0270429793 0.0606744327 0.0047463766 0.0373500000 252709614 95654136 760807424 -0.1185743138 -0.0139934719 -0.0456931554 2237 1311867793.2574770451 0.0280071609 0.0270434103 0.0606744327 0.0047454253 0.0271810000 252713230 95654136 760807424 -0.1194868162 -0.0147498092 -0.0457419641 2238 1311867793.2951428890 0.0264002029 0.0270431229 0.0606744327 0.0047445047 0.0270840000 252716926 95654136 760807424 -0.1203804910 -0.0163323451 -0.0443327911 2239 1311867793.3254458904 0.0259787682 0.0270426475 0.0606744327 0.0047435525 0.0267990000 252718742 95654136 760807424 -0.1210073680 -0.0164228678 -0.0449928232 2240 1311867793.3620529175 0.0270018410 0.0270426293 0.0606744327 0.0047428690 0.0268890000 252722382 95654136 760807424 -0.1205020323 -0.0151060568 -0.0463369042 2241 1311867793.3934969902 0.0284165032 0.0270432424 0.0606744327 0.0047430948 0.0268030000 252724198 95654136 760807424 -0.1213380173 -0.0136396922 -0.0446280614 2242 1311867793.4254410267 0.0282079931 0.0270437619 0.0606744327 0.0047423088 0.0264140000 252897226 95654136 760807424 -0.1220380962 -0.0136570344 -0.0448945723 2243 1311867793.4615969658 0.0284222029 0.0270443764 0.0606744327 0.0047415681 0.0260880000 252901010 95654136 760807424 -0.1224384904 -0.0130591625 -0.0462713316 2244 1311867793.4961650372 0.0274639167 0.0270445634 0.0606744327 0.0047406515 0.0261290000 252902626 95654136 760807424 -0.1224840432 -0.0139974132 -0.0446754135 2245 1311867793.5258960724 0.0269303862 0.0270445125 0.0606744327 0.0047397041 0.0260970000 252906242 95654136 760807424 -0.1223964542 -0.0143585419 -0.0446459167 2246 1311867793.5653350353 0.0269030239 0.0270444495 0.0606744327 0.0047389105 0.0260030000 252908138 95654136 760807424 -0.1216217428 -0.0141163915 -0.0460116751 2247 1311867793.5951368809 0.0258971937 0.0270439390 0.0606744327 0.0047379083 0.0261160000 252911642 95654136 760807424 -0.1219623089 -0.0147926677 -0.0452412143 2248 1311867793.6255569458 0.0256102942 0.0270433012 0.0606744327 0.0047390363 0.0261120000 252915114 95654136 760807424 -0.1240525842 -0.0146607738 -0.0432876684 2249 1311867793.6641399860 0.0263107587 0.0270429755 0.0606744327 0.0047381969 0.0300380000 252917098 95654136 760807424 -0.1242842600 -0.0133268479 -0.0443918034 2250 1311867793.6930859089 0.0260033067 0.0270425134 0.0606744327 0.0047383561 0.0269120000 252920514 95654136 760807424 -0.1236477643 -0.0131965857 -0.0452793650 2251 1311867793.7268340588 0.0287752897 0.0270432832 0.0606744327 0.0047402329 0.0372910000 252922498 95654136 760807424 -0.1252416968 -0.0098475888 -0.0438159257 2252 1311867793.7666549683 0.0294681508 0.0270443600 0.0606744327 0.0047393559 0.0261920000 252926138 95654136 760807424 -0.1249902993 -0.0085691614 -0.0446661562 2253 1311867793.7944359779 0.0301181152 0.0270457243 0.0606744327 0.0047384687 0.0260590000 252929642 95654136 760807424 -0.1262522787 -0.0074533839 -0.0450241975 2254 1311867793.8265230656 0.0289226249 0.0270465570 0.0606744327 0.0047379036 0.0303370000 252931370 95654136 760807424 -0.1277225018 -0.0082865050 -0.0433812737 2255 1311867793.8667359352 0.0285033118 0.0270472030 0.0606744327 0.0047373237 0.0259890000 252935322 95654136 760807424 -0.1253848225 -0.0086731650 -0.0438497253 2256 1311867793.8930900097 0.0279466249 0.0270476016 0.0606744327 0.0047366918 0.0261840000 252938626 95654136 760807424 -0.1253945678 -0.0090672150 -0.0442508049 2257 1311867793.9269030094 0.0260745008 0.0270471705 0.0606744327 0.0047357944 0.0261880000 252940554 95654136 760807424 -0.1261510253 -0.0105827246 -0.0438584574 2258 1311867793.9623370171 0.0264386628 0.0270469010 0.0606744327 0.0047347928 0.0364240000 252944026 95654136 760807424 -0.1265673488 -0.0096432837 -0.0441387296 2259 1311867793.9955279827 0.0236920789 0.0270454159 0.0606744327 0.0047343080 0.0264030000 253115554 95654136 760807424 -0.1277092695 -0.0116867647 -0.0451706350 2260 1311867794.0277070999 0.0249797683 0.0270445019 0.0606744327 0.0047335708 0.0260950000 253119026 95654136 760807424 -0.1289161444 -0.0095899710 -0.0454239473 2261 1311867794.0608921051 0.0257337708 0.0270439222 0.0606744327 0.0047325607 0.0261060000 253122698 95654136 760807424 -0.1284401268 -0.0082371011 -0.0466100089 2262 1311867794.0951509476 0.0279250368 0.0270443117 0.0606744327 0.0047329198 0.0259780000 253124426 95654136 760807424 -0.1298717707 -0.0051320158 -0.0447242148 2263 1311867794.1269369125 0.0280555747 0.0270447586 0.0606744327 0.0047321584 0.0261930000 253298178 95654136 760807424 -0.1291553825 -0.0041291253 -0.0438180976 2264 1311867794.1632831097 0.0275419522 0.0270449782 0.0606744327 0.0047322389 0.0262210000 253299962 95654136 760807424 -0.1274293214 -0.0041553592 -0.0449527651 2265 1311867794.1936271191 0.0279205069 0.0270453648 0.0606744327 0.0047317667 0.0261330000 253303522 95654136 760807424 -0.1286859959 -0.0026282575 -0.0445093922 2266 1311867794.2258520126 0.0273015294 0.0270454778 0.0606744327 0.0047307622 0.0298870000 253306994 95654136 760807424 -0.1294304579 -0.0025256609 -0.0424855985 2267 1311867794.2619779110 0.0288847461 0.0270462891 0.0606744327 0.0047299139 0.0299420000 253478622 95654136 760807424 -0.1297882050 0.0001231839 -0.0428485051 2268 1311867794.2955250740 0.0287606791 0.0270470450 0.0606744327 0.0047289636 0.0297810000 253482094 95654136 760807424 -0.1307327598 0.0010605572 -0.0424180590 2269 1311867794.3254759312 0.0288486797 0.0270478391 0.0606744327 0.0047283828 0.0263060000 253483910 95654136 760807424 -0.1320224404 0.0020785015 -0.0398720466 2270 1311867794.3628959656 0.0284318812 0.0270484488 0.0606744327 0.0047274172 0.0263680000 253487550 95654136 760807424 -0.1319294870 0.0026287637 -0.0394258946 2271 1311867794.3958311081 0.0282771233 0.0270489898 0.0606744327 0.0047263847 0.0305260000 253491278 95654136 760807424 -0.1329895556 0.0036002535 -0.0399031155 2272 1311867794.4267809391 0.0296772420 0.0270501466 0.0606744327 0.0047259160 0.0262040000 253492950 95654136 760807424 -0.1343889534 0.0058598984 -0.0384858809 2273 1311867794.4620559216 0.0288005769 0.0270509167 0.0606744327 0.0047250059 0.0295440000 253496734 95654136 760807424 -0.1341659576 0.0054897293 -0.0381769463 2274 1311867794.4987208843 0.0294687077 0.0270519799 0.0606744327 0.0047245116 0.0263410000 253500262 95654136 760807424 -0.1349241883 0.0068440489 -0.0386190154 2275 1311867794.5290880203 0.0286903121 0.0270527001 0.0606744327 0.0047242209 0.0304800000 253502078 95654136 760807424 -0.1347538233 0.0063191722 -0.0388723351 2276 1311867794.5637059212 0.0318757258 0.0270548191 0.0606744327 0.0047255070 0.0262970000 253505606 95654136 760807424 -0.1353201866 0.0098183528 -0.0372384563 2277 1311867794.5940639973 0.0316682979 0.0270568453 0.0606744327 0.0047246681 0.0263000000 253507478 95654136 760807424 -0.1365097910 0.0103358831 -0.0383926779 2278 1311867794.6319000721 0.0321110263 0.0270590640 0.0606744327 0.0047239509 0.0263000000 253511062 95654136 760807424 -0.1351831704 0.0114078727 -0.0398225449 2279 1311867794.6658101082 0.0334700346 0.0270618770 0.0606744327 0.0047238371 0.0264030000 253514790 95654136 760807424 -0.1353571564 0.0132005205 -0.0381272212 2280 1311867794.6949920654 0.0325886272 0.0270643010 0.0606744327 0.0047229103 0.0262880000 253516406 95654136 760807424 -0.1368232518 0.0127951708 -0.0375085026 2281 1311867794.7305591106 0.0293157902 0.0270652881 0.0606744327 0.0047240255 0.0299130000 253690382 95654136 760807424 -0.1361831725 0.0101784617 -0.0393484831 2282 1311867794.7625899315 0.0293241888 0.0270662780 0.0606744327 0.0047229942 0.0287430000 253691998 95654136 760807424 -0.1362632215 0.0106680002 -0.0392460115 2283 1311867794.7959010601 0.0290080961 0.0270671285 0.0606744327 0.0047225665 0.0263530000 253695726 95654136 760807424 -0.1374553591 0.0108657628 -0.0375374667 2284 1311867794.8306028843 0.0292618070 0.0270680894 0.0606744327 0.0047218734 0.0262480000 253699254 95654136 760807424 -0.1384884566 0.0116228629 -0.0374576412 2285 1311867794.8631660938 0.0278385896 0.0270684266 0.0606744327 0.0047215027 0.0269800000 253701014 95654136 760807424 -0.1380097419 0.0108688250 -0.0396166518 2286 1311867794.8947780132 0.0289976280 0.0270692705 0.0606744327 0.0047209963 0.0262810000 253704486 95654136 760807424 -0.1372686625 0.0123673864 -0.0389229432 2287 1311867794.9343950748 0.0302959047 0.0270706814 0.0606744327 0.0047205255 0.0263190000 253706582 95654136 760807424 -0.1385361850 0.0142751886 -0.0379765891 2288 1311867794.9646499157 0.0311425012 0.0270724610 0.0606744327 0.0047196148 0.0262670000 253709998 95654136 760807424 -0.1388626546 0.0159620065 -0.0391855463 2289 1311867794.9988350868 0.0305442698 0.0270739778 0.0606744327 0.0047187759 0.0304440000 253713782 95654136 760807424 -0.1388088614 0.0161067676 -0.0401791409 2290 1311867795.0307559967 0.0321838520 0.0270762092 0.0606744327 0.0047186838 0.0262610000 253715398 95654136 760807424 -0.1398173124 0.0185524449 -0.0388400629 2291 1311867795.0651550293 0.0341256745 0.0270792862 0.0606744327 0.0047193079 0.0262750000 253719126 95654136 760807424 -0.1424372196 0.0210997909 -0.0372304246 2292 1311867795.0993340015 0.0320535004 0.0270814564 0.0606744327 0.0047196734 0.0262580000 253722654 95654136 760807424 -0.1413262635 0.0197658949 -0.0387238190 2293 1311867795.1310648918 0.0309548751 0.0270831457 0.0606744327 0.0047190852 0.0261950000 253724582 95654136 760807424 -0.1408152729 0.0191645604 -0.0394409932 2294 1311867795.1630289555 0.0303552393 0.0270845720 0.0606744327 0.0047188020 0.0263560000 253727998 95654136 760807424 -0.1428054869 0.0186255332 -0.0373098552 2295 1311867795.1945760250 0.0306571852 0.0270861287 0.0606744327 0.0047185954 0.0265600000 253729926 95654136 760807424 -0.1416670978 0.0191687476 -0.0378621742 2296 1311867795.2313210964 0.0281695630 0.0270866006 0.0606744327 0.0047196147 0.0263670000 253733510 95654136 760807424 -0.1404230446 0.0168028586 -0.0394924693 2297 1311867795.2631359100 0.0263779275 0.0270862921 0.0606744327 0.0047189178 0.0263350000 253737182 95654136 760807424 -0.1413501352 0.0150514320 -0.0383990034 2298 1311867795.2958068848 0.0251398385 0.0270854451 0.0606744327 0.0047187990 0.0291480000 253738910 95654136 760807424 -0.1429233402 0.0144329090 -0.0393953770 2299 1311867795.3314220905 0.0222229548 0.0270833300 0.0606744327 0.0047195116 0.0264030000 253742638 95654136 760807424 -0.1415427327 0.0117758643 -0.0413648635 2300 1311867795.3670549393 0.0210666712 0.0270807141 0.0606744327 0.0047185396 0.0263490000 253914378 95654136 760807424 -0.1422511041 0.0111925248 -0.0413312986 2301 1311867795.3950240612 0.0220983252 0.0270785488 0.0606744327 0.0047192206 0.0263510000 253917882 95654136 760807424 -0.1420120746 0.0120774247 -0.0393671319 2302 1311867795.4294250011 0.0235336442 0.0270770089 0.0606744327 0.0047193282 0.0262730000 253921466 95654136 760807424 -0.1385648251 0.0130279046 -0.0406043977 2303 1311867795.4614660740 0.0225369390 0.0270750375 0.0606744327 0.0047191416 0.0263380000 253923450 95654136 760807424 -0.1386971176 0.0132744685 -0.0417591371 2304 1311867795.4961009026 0.0216191970 0.0270726695 0.0606744327 0.0047189194 0.0298120000 253927034 95654136 760807424 -0.1397404224 0.0130492896 -0.0395944566 2305 1311867795.5292580128 0.0198864732 0.0270695518 0.0606744327 0.0047183098 0.0264260000 253928962 95654136 760807424 -0.1397845745 0.0120067913 -0.0396761000 2306 1311867795.5632829666 0.0201620404 0.0270665564 0.0606744327 0.0047182471 0.0303840000 253932602 95654136 760807424 -0.1376436055 0.0125948135 -0.0408345163 2307 1311867795.5938069820 0.0186325852 0.0270629006 0.0606744327 0.0047176472 0.0264100000 253936274 95654136 760807424 -0.1387907714 0.0124653485 -0.0399041511 2308 1311867795.6295180321 0.0188826695 0.0270593563 0.0606744327 0.0047173883 0.0264780000 254108250 95654136 760807424 -0.1378350407 0.0133694727 -0.0393633582 2309 1311867795.6619150639 0.0175644942 0.0270552442 0.0606744327 0.0047175443 0.0271610000 254111978 95654136 760807424 -0.1377023607 0.0133514721 -0.0396947898 2310 1311867795.6935899258 0.0167498570 0.0270507830 0.0606744327 0.0047166169 0.0265200000 254115450 95654136 760807424 -0.1376180351 0.0138073154 -0.0393447950 2311 1311867795.7300128937 0.0157284308 0.0270458836 0.0606744327 0.0047160014 0.0264100000 254117546 95654136 760807424 -0.1371219456 0.0137402676 -0.0386209078 2312 1311867795.7627360821 0.0157487225 0.0270409973 0.0606744327 0.0047151929 0.0264500000 254121130 95654136 760807424 -0.1364060938 0.0147817098 -0.0392826311 2313 1311867795.7993569374 0.0158838984 0.0270361737 0.0606744327 0.0047159835 0.0264300000 254123170 95654136 760807424 -0.1390586942 0.0167877376 -0.0370654836 2314 1311867795.8297359943 0.0181494299 0.0270323332 0.0606744327 0.0047158042 0.0303510000 254126642 95654136 760807424 -0.1379912198 0.0191153865 -0.0358571373 2315 1311867795.8630819321 0.0180929303 0.0270284717 0.0606744327 0.0047149680 0.0264750000 254130426 95654136 760807424 -0.1377533078 0.0197225939 -0.0367743894 2316 1311867795.9011631012 0.0174266379 0.0270243259 0.0606744327 0.0047140583 0.0264490000 254132322 95654136 760807424 -0.1392357647 0.0196524560 -0.0363102816 2317 1311867795.9300799370 0.0170397535 0.0270200166 0.0606744327 0.0047133620 0.0307870000 254135938 95654136 760807424 -0.1420414597 0.0196282379 -0.0357782245 2318 1311867795.9624390602 0.0169552378 0.0270156746 0.0606744327 0.0047124540 0.0264670000 254137666 95654136 760807424 -0.1434029043 0.0198710561 -0.0367887579 2319 1311867796.0000178814 0.0182099044 0.0270118774 0.0606744327 0.0047118409 0.0265360000 254141562 95654136 760807424 -0.1412402838 0.0212159771 -0.0366984569 2320 1311867796.0296399593 0.0182926543 0.0270081191 0.0606744327 0.0047110205 0.0265020000 254144978 95654136 760807424 -0.1396741271 0.0213091541 -0.0371076316 2321 1311867796.0617599487 0.0203547403 0.0270052525 0.0606744327 0.0047103836 0.0270730000 254146962 95654136 760807424 -0.1386676580 0.0236095414 -0.0374389589 2322 1311867796.0984148979 0.0207943860 0.0270025777 0.0606744327 0.0047093959 0.0304180000 254150546 95654136 760807424 -0.1393312812 0.0247709770 -0.0380417407 2323 1311867796.1296660900 0.0191716105 0.0269992066 0.0606744327 0.0047092489 0.0302090000 254152306 95654136 760807424 -0.1403814554 0.0234252308 -0.0374310836 2324 1311867796.1618049145 0.0186262969 0.0269956038 0.0606744327 0.0047091582 0.0265710000 254155834 95654136 760807424 -0.1411644667 0.0233436022 -0.0373075157 2325 1311867796.1990590096 0.0192411523 0.0269922686 0.0606744327 0.0047085149 0.0265230000 254329754 95654136 760807424 -0.1388535351 0.0241923444 -0.0380121842 2326 1311867796.2292931080 0.0198783446 0.0269892101 0.0606744327 0.0047083849 0.0265760000 254331426 95654136 760807424 -0.1403764337 0.0251987446 -0.0372193456 2327 1311867796.2631280422 0.0198253747 0.0269861316 0.0606744327 0.0047080216 0.0266950000 254335154 95654136 760807424 -0.1431755573 0.0252215657 -0.0368257202 2328 1311867796.3010690212 0.0203105919 0.0269832641 0.0606744327 0.0047070699 0.0267420000 254338794 95654136 760807424 -0.1428002268 0.0262054149 -0.0375945643 2329 1311867796.3299860954 0.0199618228 0.0269802493 0.0606744327 0.0047064269 0.0264610000 254340610 95654136 760807424 -0.1404604465 0.0258426648 -0.0370058306 2330 1311867796.3619849682 0.0199459009 0.0269772302 0.0606744327 0.0047054413 0.0304000000 254344194 95654136 760807424 -0.1385090053 0.0256901830 -0.0366006941 2331 1311867796.3998959064 0.0193883367 0.0269739746 0.0606744327 0.0047047748 0.0265350000 254346122 95654136 760807424 -0.1377952993 0.0254088715 -0.0373333208 2332 1311867796.4297831059 0.0190591142 0.0269705806 0.0606744327 0.0047038140 0.0265920000 254349594 95654136 760807424 -0.1371528059 0.0249748975 -0.0367531851 2333 1311867796.4618980885 0.0183208380 0.0269668730 0.0606744327 0.0047029488 0.0265790000 254353378 95654136 760807424 -0.1379577816 0.0243104175 -0.0359311104 2334 1311867796.5018439293 0.0161560792 0.0269622411 0.0606744327 0.0047022265 0.0265800000 254355330 95654136 760807424 -0.1378467828 0.0218398161 -0.0349591821 2335 1311867796.5301249027 0.0139850769 0.0269566835 0.0606744327 0.0047024931 0.0265900000 254358946 95654136 760807424 -0.1377612352 0.0201044008 -0.0363545083 2336 1311867796.5621480942 0.0138503434 0.0269510729 0.0606744327 0.0047021186 0.0266570000 254360674 95654136 760807424 -0.1387858689 0.0198102333 -0.0354209989 2337 1311867796.6018888950 0.0155514395 0.0269461950 0.0606744327 0.0047017426 0.0301020000 254364626 95654136 760807424 -0.1379603297 0.0216217078 -0.0352188535 2338 1311867796.6323978901 0.0150470147 0.0269411055 0.0606744327 0.0047012052 0.0375650000 254368098 95654136 760807424 -0.1368214339 0.0213894472 -0.0361564867 2339 1311867796.6659901142 0.0163647551 0.0269365838 0.0606744327 0.0047002825 0.0267960000 254370082 95654136 760807424 -0.1358069181 0.0224141050 -0.0348594896 2340 1311867796.7025029659 0.0159490723 0.0269318883 0.0606744327 0.0046994502 0.0308660000 254373610 95654136 760807424 -0.1363928318 0.0218001585 -0.0334682092 2341 1311867796.7335898876 0.0136432722 0.0269262118 0.0606744327 0.0047004817 0.0431530000 254375482 95654136 760807424 -0.1359379739 0.0202436019 -0.0351601392 2342 1311867796.7634348869 0.0149741760 0.0269211084 0.0606744327 0.0046995431 0.0270140000 254379010 95654136 760807424 -0.1342175752 0.0217377767 -0.0347111709 2343 1311867796.7990939617 0.0155983437 0.0269162759 0.0606744327 0.0046991357 0.0270160000 254382794 95654136 760807424 -0.1322971135 0.0221746340 -0.0323877037 2344 1311867796.8303010464 0.0155852810 0.0269114418 0.0606744327 0.0046982017 0.0267570000 254384522 95654136 760807424 -0.1315353215 0.0225478727 -0.0323240273 2345 1311867796.8626410961 0.0149912350 0.0269063586 0.0606744327 0.0046976801 0.0380300000 254388194 95654136 760807424 -0.1307517290 0.0219740290 -0.0316485167 2346 1311867796.8988420963 0.0156925749 0.0269015786 0.0606744327 0.0046971156 0.0268820000 254561374 95654136 760807424 -0.1325605065 0.0226858612 -0.0298089832 2347 1311867796.9308090210 0.0163230654 0.0268970714 0.0606744327 0.0046971463 0.0310870000 254563302 95654136 760807424 -0.1329484731 0.0228323620 -0.0277115814 2348 1311867796.9623529911 0.0150057264 0.0268920069 0.0606744327 0.0046970925 0.0266650000 254566830 95654136 760807424 -0.1302921474 0.0216549505 -0.0281043760 2349 1311867796.9994709492 0.0154407807 0.0268871320 0.0606744327 0.0046961169 0.0267370000 254568870 95654136 760807424 -0.1286651343 0.0218585618 -0.0279608350 2350 1311867797.0328159332 0.0149037475 0.0268820327 0.0606744327 0.0046951866 0.0268160000 254572342 95654136 760807424 -0.1278805286 0.0212198067 -0.0277347229 2351 1311867797.0733079910 0.0140196402 0.0268765616 0.0606744327 0.0046944744 0.0267280000 254576406 95654136 760807424 -0.1271788031 0.0199907124 -0.0268625226 2352 1311867797.0992720127 0.0156219527 0.0268717765 0.0606744327 0.0046935183 0.0305220000 254577910 95654136 760807424 -0.1259128600 0.0216873586 -0.0267656706 2353 1311867797.1336839199 0.0160579309 0.0268671807 0.0606744327 0.0046930305 0.0268060000 254581750 95654136 760807424 -0.1253670603 0.0221435018 -0.0253311675 2354 1311867797.1708030701 0.0166948382 0.0268628594 0.0606744327 0.0046922157 0.0276510000 254583590 95654136 760807424 -0.1234895438 0.0227448903 -0.0249280613 2355 1311867797.1996591091 0.0171489157 0.0268587346 0.0606744327 0.0046914644 0.0267880000 254587206 95654136 760807424 -0.1229433045 0.0236371886 -0.0251199957 2356 1311867797.2372090816 0.0187227447 0.0268552813 0.0606744327 0.0046919814 0.0268690000 254590958 95654136 760807424 -0.1234087870 0.0256236233 -0.0226730704 2357 1311867797.2708179951 0.0187199526 0.0268518297 0.0606744327 0.0046910842 0.0265360000 254592886 95654136 760807424 -0.1219209433 0.0256829523 -0.0221591629 2358 1311867797.3019850254 0.0186796878 0.0268483640 0.0606744327 0.0046902176 0.0265590000 254596414 95654136 760807424 -0.1214470863 0.0256786551 -0.0214959756 2359 1311867797.3296120167 0.0189996604 0.0268450369 0.0606744327 0.0046894320 0.0267760000 254598174 95654136 760807424 -0.1221800745 0.0260223858 -0.0198328122 2360 1311867797.3703179359 0.0208238065 0.0268424855 0.0606744327 0.0046892687 0.0269970000 254601926 95654136 760807424 -0.1220404804 0.0279346313 -0.0190480184 2361 1311867797.3999080658 0.0214564353 0.0268402043 0.0606744327 0.0046884329 0.0268600000 254605598 95654136 760807424 -0.1215988472 0.0285709351 -0.0189560652 2362 1311867797.4322440624 0.0221112836 0.0268382022 0.0606744327 0.0046879134 0.0268400000 254777354 95654136 760807424 -0.1209067851 0.0291139837 -0.0182288438 2363 1311867797.4688720703 0.0226534195 0.0268364312 0.0606744327 0.0046876556 0.0268450000 254781138 95654136 760807424 -0.1206943691 0.0295006782 -0.0173671413 2364 1311867797.5000469685 0.0217035636 0.0268342600 0.0606744327 0.0046867997 0.0268440000 254784666 95654136 760807424 -0.1222221255 0.0290044807 -0.0175022054 2365 1311867797.5296459198 0.0214559138 0.0268319858 0.0606744327 0.0046858975 0.0268150000 254786538 95654136 760807424 -0.1218264550 0.0283263475 -0.0164730940 2366 1311867797.5718441010 0.0209958255 0.0268295191 0.0606744327 0.0046850218 0.0303820000 254790290 95654136 760807424 -0.1224316061 0.0277770068 -0.0160627030 2367 1311867797.5997619629 0.0201211907 0.0268266850 0.0606744327 0.0046844324 0.0269870000 254792106 95654136 760807424 -0.1221006215 0.0267409272 -0.0162752904 2368 1311867797.6303300858 0.0196599774 0.0268236586 0.0606744327 0.0046842435 0.0269640000 254795578 95654136 760807424 -0.1218154132 0.0258491114 -0.0163064841 2369 1311867797.6706480980 0.0204164628 0.0268209540 0.0606744327 0.0046833171 0.0269250000 254799530 95654136 760807424 -0.1223581210 0.0263459142 -0.0158540178 2370 1311867797.7010281086 0.0191081092 0.0268176996 0.0606744327 0.0046825544 0.0267620000 254801202 95654136 760807424 -0.1239850000 0.0248955730 -0.0157697778 2371 1311867797.7299659252 0.0200310461 0.0268148372 0.0606744327 0.0046816348 0.0269420000 254804818 95654136 760807424 -0.1233096123 0.0256082453 -0.0160303134 2372 1311867797.7678339481 0.0198892206 0.0268119175 0.0606744327 0.0046811115 0.0269720000 254806714 95654136 760807424 -0.1222887561 0.0246369932 -0.0160158072 2373 1311867797.8001670837 0.0186409615 0.0268084742 0.0606744327 0.0046803021 0.0310120000 254810498 95654136 760807424 -0.1225652322 0.0229426045 -0.0162378885 2374 1311867797.8302230835 0.0194706544 0.0268053833 0.0606744327 0.0046796715 0.0378290000 254813970 95654136 760807424 -0.1202528179 0.0227220226 -0.0166083928 2375 1311867797.8681600094 0.0185946114 0.0268019261 0.0606744327 0.0046795000 0.0270550000 254816066 95654136 760807424 -0.1194460168 0.0208279397 -0.0167507716 2376 1311867797.8986220360 0.0189143289 0.0267986064 0.0606744327 0.0046786470 0.0268920000 254819482 95654136 760807424 -0.1196526289 0.0212781876 -0.0174863096 2377 1311867797.9362978935 0.0187874716 0.0267952362 0.0606744327 0.0046777270 0.0312250000 254821578 95654136 760807424 -0.1194125935 0.0208481364 -0.0177856870 2378 1311867797.9696850777 0.0202140212 0.0267924686 0.0606744327 0.0046772184 0.0269950000 254825050 95654136 760807424 -0.1189638451 0.0215606596 -0.0165790562 2379 1311867798.0026450157 0.0188122392 0.0267891142 0.0606744327 0.0046772176 0.0269350000 254828778 95654136 760807424 -0.1182610989 0.0195087828 -0.0175945982 2380 1311867798.0362720490 0.0171146970 0.0267850493 0.0606744327 0.0046765392 0.0304620000 254830506 95654136 760807424 -0.1183568686 0.0174212288 -0.0184611939 2381 1311867798.0708239079 0.0178731009 0.0267813063 0.0606744327 0.0046757375 0.0304780000 254834234 95654136 760807424 -0.1168139875 0.0166028012 -0.0179045163 2382 1311867798.1006710529 0.0188881494 0.0267779927 0.0606744327 0.0046749784 0.0269320000 254837650 95654136 760807424 -0.1167681292 0.0174796320 -0.0174266957 2383 1311867798.1315639019 0.0168986842 0.0267738469 0.0606744327 0.0046744655 0.0272540000 254839466 95654136 760807424 -0.1171504185 0.0154814031 -0.0189468935 2384 1311867798.1681389809 0.0161766447 0.0267694018 0.0606744327 0.0046735619 0.0269840000 254843050 95654136 760807424 -0.1163492948 0.0137235718 -0.0184424222 2385 1311867798.2041590214 0.0165870581 0.0267651325 0.0606744327 0.0046726036 0.0311250000 254845090 95654136 760807424 -0.1160544679 0.0144727938 -0.0193643570 2386 1311867798.2401928902 0.0175130218 0.0267612548 0.0606744327 0.0046717266 0.0269390000 254848674 95654136 760807424 -0.1147957742 0.0151639245 -0.0202000570 2387 1311867798.2742829323 0.0176154189 0.0267574233 0.0606744327 0.0046710024 0.0269380000 254852402 95654136 760807424 -0.1141651273 0.0149810817 -0.0194167551 2388 1311867798.3000180721 0.0183963031 0.0267539220 0.0606744327 0.0046706500 0.0268930000 254853906 95654136 760807424 -0.1132625192 0.0155788586 -0.0188256055 2389 1311867798.3389759064 0.0172799546 0.0267499563 0.0606744327 0.0046698428 0.0328270000 254857802 95654136 760807424 -0.1144839227 0.0156957079 -0.0190320536 2390 1311867798.3689808846 0.0174937639 0.0267460834 0.0606744327 0.0046688837 0.0270710000 254859362 95654136 760807424 -0.1138522252 0.0158725902 -0.0185630880 2391 1311867798.4016571045 0.0178367868 0.0267423573 0.0606744327 0.0046679192 0.0270180000 254863090 95654136 760807424 -0.1124539077 0.0156185515 -0.0179452933 2392 1311867798.4377439022 0.0174870063 0.0267384880 0.0606744327 0.0046669897 0.0269390000 254866674 95654136 760807424 -0.1120687872 0.0151924584 -0.0169158410 2393 1311867798.4722189903 0.0174375977 0.0267346012 0.0606744327 0.0046661125 0.0304300000 254868602 95654136 760807424 -0.1115899011 0.0151269874 -0.0167380571 2394 1311867798.4979979992 0.0185092688 0.0267311654 0.0606744327 0.0046654369 0.0269720000 254871906 95654136 760807424 -0.1114604697 0.0162455812 -0.0160941891 2395 1311867798.5371229649 0.0180754550 0.0267275514 0.0606744327 0.0046645736 0.0269230000 254873946 95654136 760807424 -0.1105161607 0.0157498810 -0.0167100001 2396 1311867798.5710020065 0.0195624419 0.0267245609 0.0606744327 0.0046636267 0.0315670000 254877474 95654136 760807424 -0.1086101234 0.0166165717 -0.0168759953 2397 1311867798.6058080196 0.0209101383 0.0267221352 0.0606744327 0.0046632650 0.0270620000 254881202 95654136 760807424 -0.1081300899 0.0183626208 -0.0161879938 2398 1311867798.6374750137 0.0193383228 0.0267190561 0.0606744327 0.0046632866 0.0269860000 254882818 95654136 760807424 -0.1091639996 0.0182993952 -0.0181623399 2399 1311867798.6689419746 0.0209851675 0.0267166659 0.0606744327 0.0046625252 0.0269530000 254886490 95654136 760807424 -0.1076596007 0.0199597441 -0.0174897648 2400 1311867798.7046790123 0.0210137833 0.0267142897 0.0606744327 0.0046617112 0.0270970000 254890074 95654136 760807424 -0.1069626138 0.0198328849 -0.0160842258 2401 1311867798.7372579575 0.0192286689 0.0267111720 0.0606744327 0.0046612648 0.0271710000 255062402 95654136 760807424 -0.1074284464 0.0194888264 -0.0178582724 2402 1311867798.7684650421 0.0190281440 0.0267079734 0.0606744327 0.0046608819 0.0269730000 255065818 95654136 760807424 -0.1065225676 0.0194325671 -0.0172181949 2403 1311867798.8009719849 0.0213993397 0.0267057643 0.0606744327 0.0046604522 0.0306130000 255067690 95654136 760807424 -0.1041699573 0.0212299917 -0.0154306656 2404 1311867798.8353779316 0.0191917773 0.0267026386 0.0606744327 0.0046605726 0.0270270000 255071218 95654136 760807424 -0.1054612920 0.0209837426 -0.0168552008 2405 1311867798.8719079494 0.0209241640 0.0267002360 0.0606744327 0.0046605285 0.0270370000 255075002 95654136 760807424 -0.1042592749 0.0235539731 -0.0160889383 2406 1311867798.9030900002 0.0223098472 0.0266984112 0.0606744327 0.0046601029 0.0269860000 255076618 95654136 760807424 -0.1032418385 0.0252699889 -0.0149348248 2407 1311867798.9344220161 0.0224953871 0.0266966650 0.0606744327 0.0046592748 0.0270820000 255080290 95654136 760807424 -0.1021990627 0.0262985788 -0.0156823583 2408 1311867798.9702930450 0.0234163366 0.0266953028 0.0606744327 0.0046583414 0.0271100000 255082074 95654136 760807424 -0.1012902856 0.0279757101 -0.0158458520 2409 1311867798.9996600151 0.0244117361 0.0266943548 0.0606744327 0.0046617691 0.0271210000 255085690 95654136 760807424 -0.0998326913 0.0291236360 -0.0159984473 2410 1311867799.0381140709 0.0233769305 0.0266929783 0.0606744327 0.0046636810 0.0298740000 255089386 95654136 760807424 -0.0997167304 0.0288767479 -0.0163331740 2411 1311867799.0688700676 0.0246064700 0.0266921129 0.0606744327 0.0046629783 0.0273280000 255261454 95654136 760807424 -0.0997772068 0.0306133740 -0.0157805663 2412 1311867799.1011309624 0.0234298129 0.0266907604 0.0606744327 0.0046623125 0.0281930000 255264926 95654136 760807424 -0.0987549573 0.0297209378 -0.0158390701 2413 1311867799.1368980408 0.0227435138 0.0266891245 0.0606744327 0.0046620441 0.0272470000 255266910 95654136 760807424 -0.0981694758 0.0294026434 -0.0166570693 2414 1311867799.1699140072 0.0257425271 0.0266887324 0.0606744327 0.0046612809 0.0272420000 255270382 95654136 760807424 -0.0949628577 0.0315829962 -0.0152154528 2415 1311867799.2040729523 0.0265459176 0.0266886733 0.0606744327 0.0046619791 0.0272290000 255274110 95654136 760807424 -0.0944227353 0.0325942002 -0.0145523278 2416 1311867799.2358450890 0.0257571116 0.0266882877 0.0606744327 0.0046613720 0.0273340000 255275782 95654136 760807424 -0.0950054824 0.0326870792 -0.0162725225 2417 1311867799.2801609039 0.0255320035 0.0266878093 0.0606744327 0.0046604566 0.0272670000 255279790 95654136 760807424 -0.0952615142 0.0331957899 -0.0168589149 2418 1311867799.2992970943 0.0251818523 0.0266871865 0.0606744327 0.0046597021 0.0272610000 255282870 95654136 760807424 -0.0953127220 0.0331588611 -0.0175751522 2419 1311867799.3363530636 0.0261150692 0.0266869500 0.0606744327 0.0046587776 0.0272660000 255284910 95654136 760807424 -0.0937464610 0.0338681675 -0.0179848131 2420 1311867799.3682019711 0.0248168670 0.0266861772 0.0606744327 0.0046582650 0.0333730000 255288326 95654136 760807424 -0.0930058956 0.0333473645 -0.0197023172 2421 1311867799.4002521038 0.0259414315 0.0266858696 0.0606744327 0.0046575034 0.0313870000 255290254 95654136 760807424 -0.0898921788 0.0339988917 -0.0206331145 2422 1311867799.4359819889 0.0269628335 0.0266859839 0.0606744327 0.0046566235 0.0305970000 255293838 95654136 760807424 -0.0886646882 0.0351458825 -0.0201741457 2423 1311867799.4694008827 0.0231630132 0.0266845300 0.0606744327 0.0046565926 0.0311250000 255297510 95654136 760807424 -0.0903072432 0.0324391648 -0.0208543222 2424 1311867799.5055029392 0.0246695243 0.0266836987 0.0606744327 0.0046559573 0.0311430000 255299294 95654136 760807424 -0.0894939005 0.0344010256 -0.0206659734 2425 1311867799.5358369350 0.0259476025 0.0266833952 0.0606744327 0.0046556077 0.0303210000 255302910 95654136 760807424 -0.0887593627 0.0356445946 -0.0194530115 2426 1311867799.5718040466 0.0259711165 0.0266831016 0.0606744327 0.0046549358 0.0305740000 255304694 95654136 760807424 -0.0878582075 0.0360579789 -0.0204202589 2427 1311867799.6046330929 0.0269569922 0.0266832144 0.0606744327 0.0046543633 0.0273180000 255308310 95654136 760807424 -0.0871047080 0.0372989289 -0.0205806494 2428 1311867799.6362400055 0.0269658472 0.0266833308 0.0606744327 0.0046534556 0.0300420000 255311838 95654136 760807424 -0.0862153471 0.0372507200 -0.0204549339 2429 1311867799.6706030369 0.0245829932 0.0266824661 0.0606744327 0.0046536340 0.0272520000 255313766 95654136 760807424 -0.0879248753 0.0360832959 -0.0213090349 2430 1311867799.7089800835 0.0258517824 0.0266821243 0.0606744327 0.0046527456 0.0306710000 255317406 95654136 760807424 -0.0871407837 0.0378975347 -0.0227042977 2431 1311867799.7397329807 0.0280624907 0.0266826921 0.0606744327 0.0046518941 0.0272470000 255319222 95654136 760807424 -0.0845197812 0.0389055908 -0.0220694952 2432 1311867799.7721259594 0.0261217318 0.0266824614 0.0606744327 0.0046513930 0.0272940000 255322750 95654136 760807424 -0.0852478892 0.0379574597 -0.0239460934 2433 1311867799.8072490692 0.0258743335 0.0266821293 0.0606744327 0.0046504934 0.0272610000 255326478 95654136 760807424 -0.0845308155 0.0377038419 -0.0246612709 2434 1311867799.8393049240 0.0256362725 0.0266816996 0.0606744327 0.0046496083 0.0313900000 255498226 95654136 760807424 -0.0852235258 0.0381895229 -0.0246010236 2435 1311867799.8678040504 0.0244691204 0.0266807909 0.0606744327 0.0046489028 0.0273800000 255501842 95654136 760807424 -0.0858212113 0.0381856076 -0.0260123778 2436 1311867799.9071669579 0.0249317326 0.0266800729 0.0606744327 0.0046483688 0.0313960000 255505538 95654136 760807424 -0.0847474560 0.0389472805 -0.0264788270 2437 1311867799.9347701073 0.0272924993 0.0266803242 0.0606744327 0.0046476207 0.0273740000 255507186 95654136 760807424 -0.0825102404 0.0407533534 -0.0248907842 2438 1311867799.9675478935 0.0259585213 0.0266800282 0.0606744327 0.0046467978 0.0274000000 255510714 95654136 760807424 -0.0836500227 0.0404301174 -0.0250105467 2439 1311867800.0074419975 0.0261153486 0.0266797967 0.0606744327 0.0046460892 0.0273600000 255512810 95654136 760807424 -0.0847526118 0.0420679711 -0.0248255841 2440 1311867800.0354819298 0.0257910956 0.0266794324 0.0606744327 0.0046453822 0.0272450000 255516170 95654136 760807424 -0.0840586945 0.0420102477 -0.0251760278 2441 1311867800.0715930462 0.0267051272 0.0266794430 0.0606744327 0.0046446279 0.0273650000 255519954 95654136 760807424 -0.0825105682 0.0430072471 -0.0248738490 2442 1311867800.1054389477 0.0276391879 0.0266798360 0.0606744327 0.0046438169 0.0274290000 255521682 95654136 760807424 -0.0807520598 0.0440284163 -0.0252107643 2443 1311867800.1350870132 0.0275030471 0.0266801729 0.0606744327 0.0046430030 0.0274090000 255525242 95654136 760807424 -0.0802517980 0.0444424078 -0.0263316873 2444 1311867800.1694350243 0.0283188149 0.0266808434 0.0606744327 0.0046421192 0.0307370000 255526970 95654136 760807424 -0.0779251158 0.0445463769 -0.0256080311 2445 1311867800.2077379227 0.0284274090 0.0266815578 0.0606744327 0.0046414738 0.0275700000 255701002 95654136 760807424 -0.0772175416 0.0453783125 -0.0260382649 2446 1311867800.2413349152 0.0277718436 0.0266820035 0.0606744327 0.0046408145 0.0282140000 255704530 95654136 760807424 -0.0778310224 0.0461221524 -0.0274610184 2447 1311867800.2718439102 0.0296670049 0.0266832234 0.0606744327 0.0046407394 0.0276090000 255706346 95654136 760807424 -0.0758146718 0.0477523506 -0.0260966942 2448 1311867800.3038680553 0.0310799200 0.0266850194 0.0606744327 0.0046399290 0.0273860000 255709762 95654136 760807424 -0.0743268579 0.0491753072 -0.0249943063 2449 1311867800.3359420300 0.0302038807 0.0266864563 0.0606744327 0.0046403115 0.0275290000 255711690 95654136 760807424 -0.0747479945 0.0493749231 -0.0253697503 2450 1311867800.3712899685 0.0295438021 0.0266876225 0.0606744327 0.0046394261 0.0309080000 255715162 95654136 760807424 -0.0740274861 0.0492821522 -0.0253859032 2451 1311867800.4036390781 0.0305668693 0.0266892052 0.0606744327 0.0046387306 0.0311850000 255718890 95654136 760807424 -0.0715575963 0.0498067215 -0.0245057456 2452 1311867800.4360520840 0.0300912540 0.0266905927 0.0606744327 0.0046377954 0.0275130000 255720506 95654136 760807424 -0.0712332577 0.0498651601 -0.0241533760 2453 1311867800.4683868885 0.0297507234 0.0266918402 0.0606744327 0.0046369383 0.0273720000 255724178 95654136 760807424 -0.0706285164 0.0502249338 -0.0253958963 2454 1311867800.5043759346 0.0300181769 0.0266931957 0.0606744327 0.0046360046 0.0274600000 255727818 95654136 760807424 -0.0690141767 0.0506169088 -0.0253540445 2455 1311867800.5355989933 0.0315512717 0.0266951745 0.0606744327 0.0046354968 0.0275750000 255729690 95654136 760807424 -0.0674826875 0.0520527996 -0.0238381438 2456 1311867800.5714819431 0.0304199327 0.0266966911 0.0606744327 0.0046346617 0.0274100000 255733330 95654136 760807424 -0.0674928427 0.0519569293 -0.0242659766 2457 1311867800.6043050289 0.0306864586 0.0266983150 0.0606744327 0.0046337889 0.0275040000 255735202 95654136 760807424 -0.0659998283 0.0521794595 -0.0246208142 2458 1311867800.6356160641 0.0295477007 0.0266994742 0.0606744327 0.0046329625 0.0282520000 255908498 95654136 760807424 -0.0652772784 0.0510496087 -0.0242632367 2459 1311867800.6704459190 0.0292813946 0.0267005242 0.0606744327 0.0046320873 0.0409740000 255912226 95654136 760807424 -0.0641758591 0.0507008508 -0.0240265895 2460 1311867800.7034249306 0.0283283237 0.0267011859 0.0606744327 0.0046312099 0.0278500000 255913898 95654136 760807424 -0.0641112253 0.0502407625 -0.0249154493 2461 1311867800.7352058887 0.0279981587 0.0267017129 0.0606744327 0.0046303341 0.0275500000 255917570 95654136 760807424 -0.0628098920 0.0497944206 -0.0246992316 2462 1311867800.7744410038 0.0289384741 0.0267026214 0.0606744327 0.0046297819 0.0275500000 255919410 95654136 760807424 -0.0609906837 0.0500395671 -0.0231759921 2463 1311867800.8084959984 0.0282282047 0.0267032408 0.0606744327 0.0046294839 0.0275380000 255923138 95654136 760807424 -0.0607195869 0.0499015301 -0.0249808766 2464 1311867800.8347818851 0.0298255272 0.0267045080 0.0606744327 0.0046285785 0.0274890000 255926442 95654136 760807424 -0.0588874407 0.0510142334 -0.0249354579 2465 1311867800.8741569519 0.0315639749 0.0267064794 0.0606744327 0.0046283492 0.0275660000 255928538 95654136 760807424 -0.0577086471 0.0527690239 -0.0240401886 2466 1311867800.9060831070 0.0323699787 0.0267087760 0.0606744327 0.0046276591 0.0275920000 255931954 95654136 760807424 -0.0562029891 0.0530756116 -0.0237840153 2467 1311867800.9397630692 0.0329305120 0.0267112980 0.0606744327 0.0046268454 0.0275860000 255933882 95654136 760807424 -0.0553897768 0.0534721091 -0.0238522869 2468 1311867800.9754400253 0.0328411572 0.0267137817 0.0606744327 0.0046268436 0.0315990000 255937466 95654136 760807424 -0.0546885729 0.0531702414 -0.0239745192 2469 1311867801.0043320656 0.0331500396 0.0267163885 0.0606744327 0.0046267057 0.0276360000 255941026 95654136 760807424 -0.0546694137 0.0534899980 -0.0233694445 2470 1311867801.0391418934 0.0337655954 0.0267192425 0.0606744327 0.0046260272 0.0316780000 255942810 95654136 760807424 -0.0539655350 0.0537107736 -0.0238939691 2471 1311867801.0742049217 0.0348199680 0.0267225208 0.0606744327 0.0046255631 0.0276630000 255946482 95654136 760807424 -0.0530515313 0.0546231046 -0.0246236194 2472 1311867801.1095008850 0.0365468487 0.0267264950 0.0606744327 0.0046255400 0.0275980000 255950066 95654136 760807424 -0.0526271313 0.0560335442 -0.0230522510 2473 1311867801.1356039047 0.0352044478 0.0267299232 0.0606744327 0.0046247146 0.0382820000 255951770 95654136 760807424 -0.0538370200 0.0552839264 -0.0230691284 2474 1311867801.1731019020 0.0350159034 0.0267332725 0.0606744327 0.0046246537 0.0277950000 255955410 95654136 760807424 -0.0533744767 0.0546447933 -0.0230997559 2475 1311867801.2059779167 0.0359924808 0.0267370136 0.0606744327 0.0046242353 0.0276930000 255957282 95654136 760807424 -0.0529736653 0.0546265021 -0.0209056102 2476 1311867801.2351169586 0.0338751003 0.0267398965 0.0606744327 0.0046237721 0.0317300000 255960530 95654136 760807424 -0.0551361255 0.0533677414 -0.0218284391 2477 1311867801.2740859985 0.0319296904 0.0267419917 0.0606744327 0.0046232369 0.0275860000 255964482 95654136 760807424 -0.0562029630 0.0515695363 -0.0226001628 2478 1311867801.3080420494 0.0339502692 0.0267449006 0.0606744327 0.0046230491 0.0274890000 255966154 95654136 760807424 -0.0556990206 0.0532538630 -0.0223549102 2479 1311867801.3364291191 0.0336781517 0.0267476974 0.0606744327 0.0046227799 0.0275590000 255969714 95654136 760807424 -0.0568411760 0.0536269844 -0.0230755862 2480 1311867801.3723030090 0.0349100903 0.0267509886 0.0606744327 0.0046221986 0.0278270000 255971498 95654136 760807424 -0.0569841266 0.0549175404 -0.0218441002 2481 1311867801.4048879147 0.0357604884 0.0267546200 0.0606744327 0.0046213176 0.0276310000 255975170 95654136 760807424 -0.0570624322 0.0558854900 -0.0212538783 2482 1311867801.4369940758 0.0350645110 0.0267579681 0.0606744327 0.0046221093 0.0276360000 255978698 95654136 760807424 -0.0579136312 0.0557144731 -0.0219550785 2483 1311867801.4725570679 0.0362040065 0.0267617724 0.0606744327 0.0046285047 0.0276350000 255980626 95654136 760807424 -0.0583550222 0.0576919392 -0.0216632802 2484 1311867801.5049059391 0.0347451121 0.0267649863 0.0606744327 0.0046279339 0.0322780000 255984042 95654136 760807424 -0.0606292337 0.0575942025 -0.0216085427 2485 1311867801.5366990566 0.0342126302 0.0267679833 0.0606744327 0.0046281770 0.0446980000 255985970 95654136 760807424 -0.0620230287 0.0583564937 -0.0212902557 2486 1311867801.5724411011 0.0348433927 0.0267712317 0.0606744327 0.0046291225 0.0279810000 255989554 95654136 760807424 -0.0608839616 0.0588806234 -0.0196798872 2487 1311867801.6040530205 0.0350980014 0.0267745798 0.0606744327 0.0046283753 0.0317370000 255993170 95654136 760807424 -0.0596242659 0.0590540022 -0.0193360299 2488 1311867801.6371319294 0.0354797505 0.0267780787 0.0606744327 0.0046276732 0.0324430000 255994898 95654136 760807424 -0.0588995926 0.0598938353 -0.0206555966 2489 1311867801.6713359356 0.0378643535 0.0267825328 0.0606744327 0.0046342024 0.0283660000 256168502 95654136 760807424 -0.0560683459 0.0613839105 -0.0184344929 2490 1311867801.7047519684 0.0372469649 0.0267867354 0.0606744327 0.0046344981 0.0278350000 256172030 95654136 760807424 -0.0545370094 0.0601134188 -0.0165900066 2491 1311867801.7362918854 0.0354022048 0.0267901940 0.0606744327 0.0046408484 0.0277350000 256173902 95654136 760807424 -0.0554177910 0.0591485500 -0.0183988363 2492 1311867801.7739040852 0.0372689143 0.0267943989 0.0606744327 0.0046409322 0.0320060000 256177542 95654136 760807424 -0.0533305593 0.0604671501 -0.0183718614 2493 1311867801.8057849407 0.0381265692 0.0267989445 0.0606744327 0.0046404464 0.0312860000 256179358 95654136 760807424 -0.0514530689 0.0603052936 -0.0166554414 2494 1311867801.8389480114 0.0374111235 0.0268031996 0.0606744327 0.0046398926 0.0276730000 256182830 95654136 760807424 -0.0514747910 0.0597955398 -0.0180356875 2495 1311867801.8715689182 0.0366463214 0.0268071448 0.0606744327 0.0046397220 0.0307760000 256186614 95654136 760807424 -0.0511500686 0.0589511208 -0.0197760873 2496 1311867801.9050290585 0.0382358208 0.0268117236 0.0606744327 0.0046409971 0.0317880000 256188286 95654136 760807424 -0.0488215424 0.0599478595 -0.0198692493 2497 1311867801.9403839111 0.0380927622 0.0268162414 0.0606744327 0.0046409130 0.0276830000 256192070 95654136 760807424 -0.0482518710 0.0601827390 -0.0217430051 2498 1311867801.9724469185 0.0392175578 0.0268212059 0.0606744327 0.0046401766 0.0276660000 256193742 95654136 760807424 -0.0464069098 0.0614238828 -0.0235296581 2499 1311867802.0031659603 0.0394192003 0.0268262471 0.0606744327 0.0046423357 0.0276880000 256197358 95654136 760807424 -0.0448463932 0.0621301159 -0.0249633808 2500 1311867802.0413680077 0.0395538285 0.0268313381 0.0606744327 0.0046464449 0.0276980000 256201054 95654136 760807424 -0.0431741923 0.0626957640 -0.0265400987 2501 1311867802.0717110634 0.0394294336 0.0268363754 0.0606744327 0.0046457503 0.0277860000 256373326 95654136 760807424 -0.0417794771 0.0628544018 -0.0276882276 2502 1311867802.1040730476 0.0410763845 0.0268420668 0.0606744327 0.0046463124 0.0276960000 256376742 95654136 760807424 -0.0388785936 0.0644527748 -0.0287345611 2503 1311867802.1390628815 0.0408584066 0.0268476666 0.0606744327 0.0046471502 0.0277500000 256378670 95654136 760807424 -0.0369016714 0.0648451149 -0.0298252180 2504 1311867802.1724100113 0.0398855917 0.0268528735 0.0606744327 0.0046494445 0.0277060000 256382198 95654136 760807424 -0.0363061465 0.0643365085 -0.0317534953 2505 1311867802.2056589127 0.0395941846 0.0268579598 0.0606744327 0.0046528271 0.0315590000 256385870 95654136 760807424 -0.0351923518 0.0644746199 -0.0342887267 2506 1311867802.2409839630 0.0407530889 0.0268635046 0.0606744327 0.0046570469 0.0277420000 256387654 95654136 760807424 -0.0327127129 0.0651814714 -0.0350836627 2507 1311867802.2706429958 0.0404693298 0.0268689317 0.0606744327 0.0046562760 0.0276480000 256391270 95654136 760807424 -0.0311699789 0.0646966621 -0.0366719179 2508 1311867802.3064510822 0.0413515270 0.0268747063 0.0606744327 0.0046567463 0.0276010000 256394798 95654136 760807424 -0.0292779170 0.0645391941 -0.0383606367 2509 1311867802.3400380611 0.0407050177 0.0268802185 0.0606744327 0.0046582055 0.0277440000 256396726 95654136 760807424 -0.0290357228 0.0639302209 -0.0404767953 2510 1311867802.3742809296 0.0399268232 0.0268854164 0.0606744327 0.0046581775 0.0316240000 256570978 95654136 760807424 -0.0292060878 0.0628816336 -0.0423098095 2511 1311867802.4052720070 0.0400256068 0.0268906494 0.0606744327 0.0046601638 0.0278640000 256572850 95654136 760807424 -0.0281694736 0.0622670911 -0.0448054150 2512 1311867802.4389400482 0.0417608060 0.0268965691 0.0606744327 0.0046622078 0.0279760000 256576322 95654136 760807424 -0.0260501616 0.0634015501 -0.0467833728 2513 1311867802.4714379311 0.0413148180 0.0269023066 0.0606744327 0.0046616036 0.0278830000 256580050 95654136 760807424 -0.0249671377 0.0627423078 -0.0502184294 2514 1311867802.5060200691 0.0419787690 0.0269083036 0.0606744327 0.0046608665 0.0276810000 256581778 95654136 760807424 -0.0234862156 0.0630242750 -0.0515963286 2515 1311867802.5389459133 0.0422878973 0.0269144187 0.0606744327 0.0046600632 0.0280290000 256585394 95654136 760807424 -0.0229353085 0.0630973876 -0.0529185310 2516 1311867802.5715909004 0.0433107093 0.0269209355 0.0606744327 0.0046618167 0.0277320000 256587178 95654136 760807424 -0.0213625822 0.0647109151 -0.0575786829 2517 1311867802.6031410694 0.0443087034 0.0269278436 0.0606744327 0.0046612657 0.0277220000 256590794 95654136 760807424 -0.0195323769 0.0659922883 -0.0590897538 2518 1311867802.6396369934 0.0423156060 0.0269339547 0.0606744327 0.0046607068 0.0372250000 256764554 95654136 760807424 -0.0201915149 0.0644216686 -0.0589296147 2519 1311867802.6727440357 0.0422859974 0.0269400492 0.0606744327 0.0046603994 0.0279830000 256766426 95654136 760807424 -0.0189351682 0.0650842264 -0.0622183047 2520 1311867802.7073149681 0.0445185043 0.0269470248 0.0606744327 0.0046602188 0.0277250000 256769954 95654136 760807424 -0.0177627057 0.0679002553 -0.0636964887 2521 1311867802.7416400909 0.0428110249 0.0269533176 0.0606744327 0.0046598704 0.0278130000 256771882 95654136 760807424 -0.0160403550 0.0663951337 -0.0652120709 2522 1311867802.7708799839 0.0412323549 0.0269589794 0.0606744327 0.0046597101 0.0276940000 256775298 95654136 760807424 -0.0166445170 0.0658059940 -0.0672769397 2523 1311867802.8048460484 0.0418917276 0.0269648980 0.0606744327 0.0046590993 0.0318960000 256778914 95654136 760807424 -0.0162304882 0.0669913664 -0.0690836683 2524 1311867802.8393790722 0.0410331227 0.0269704718 0.0606744327 0.0046588139 0.0275700000 256780698 95654136 760807424 -0.0147293741 0.0662500784 -0.0697804987 2525 1311867802.8706729412 0.0408592187 0.0269759723 0.0606744327 0.0046587049 0.0318310000 256784370 95654136 760807424 -0.0123245390 0.0657375380 -0.0700790361 2526 1311867802.9066920280 0.0405709408 0.0269813543 0.0606744327 0.0046583454 0.0276220000 256787954 95654136 760807424 -0.0105508743 0.0654465556 -0.0721878335 2527 1311867802.9404280186 0.0400998257 0.0269865456 0.0606744327 0.0046576000 0.0319090000 256789826 95654136 760807424 -0.0084683225 0.0648631379 -0.0743331164 2528 1311867802.9723958969 0.0404368229 0.0269918661 0.0606744327 0.0046570503 0.0276490000 256793298 95654136 760807424 -0.0073828241 0.0649334341 -0.0748008415 2529 1311867803.0042099953 0.0405729041 0.0269972363 0.0606744327 0.0046563523 0.0277700000 256795170 95654136 760807424 -0.0077343732 0.0654848814 -0.0766371116 2530 1311867803.0404539108 0.0401179343 0.0270024223 0.0606744327 0.0046559307 0.0277030000 256798754 95654136 760807424 -0.0060699461 0.0650111884 -0.0789270550 2531 1311867803.0710830688 0.0387006961 0.0270070443 0.0606744327 0.0046553127 0.0277410000 256802370 95654136 760807424 -0.0062151114 0.0634565577 -0.0785051063 2532 1311867803.1049640179 0.0395135209 0.0270119837 0.0606744327 0.0046544117 0.0277190000 256804042 95654136 760807424 -0.0051068598 0.0640907064 -0.0802626610 2533 1311867803.1399960518 0.0410709232 0.0270175340 0.0606744327 0.0046535246 0.0276820000 256807826 95654136 760807424 -0.0041234833 0.0657660514 -0.0816406980 2534 1311867803.1724820137 0.0418299548 0.0270233795 0.0606744327 0.0046528235 0.0275930000 256809498 95654136 760807424 -0.0030243699 0.0663185269 -0.0824121088 2535 1311867803.2086870670 0.0420007519 0.0270292877 0.0606744327 0.0046522317 0.0277270000 256813338 95654136 760807424 -0.0027201017 0.0664880201 -0.0839111805 2536 1311867803.2400670052 0.0433010459 0.0270357040 0.0606744327 0.0046532200 0.0276160000 256816754 95654136 760807424 -0.0019596189 0.0677559897 -0.0847237632 2537 1311867803.2704820633 0.0432273410 0.0270420862 0.0606744327 0.0046536892 0.0277370000 256989206 95654136 760807424 -0.0017802604 0.0671137124 -0.0852662623 2538 1311867803.3084690571 0.0407761075 0.0270474975 0.0606744327 0.0046544214 0.0276890000 256992902 95654136 760807424 -0.0018801400 0.0642075539 -0.0864855796 2539 1311867803.3390929699 0.0428098962 0.0270537057 0.0606744327 0.0046544694 0.0276880000 256994606 95654136 760807424 -0.0018313425 0.0662462190 -0.0878834054 2540 1311867803.3732869625 0.0425882228 0.0270598216 0.0606744327 0.0046536694 0.0276060000 256998190 95654136 760807424 -0.0029519100 0.0664316490 -0.0890232325 2541 1311867803.4067549706 0.0438741632 0.0270664388 0.0606744327 0.0046528421 0.0277480000 257001918 95654136 760807424 -0.0021936533 0.0676622391 -0.0899618566 2542 1311867803.4397881031 0.0437351950 0.0270729962 0.0606744327 0.0046520206 0.0318210000 257003590 95654136 760807424 -0.0028795749 0.0677748993 -0.0906493589 2543 1311867803.4707190990 0.0428150669 0.0270791865 0.0606744327 0.0046511866 0.0276640000 257007262 95654136 760807424 -0.0039360020 0.0669452250 -0.0912865773 2544 1311867803.5065801144 0.0422043875 0.0270851320 0.0606744327 0.0046510874 0.0318390000 257010846 95654136 760807424 -0.0051058950 0.0667230487 -0.0924180523 2545 1311867803.5397379398 0.0433452800 0.0270915210 0.0606744327 0.0046502634 0.0311660000 257012718 95654136 760807424 -0.0045695025 0.0677679628 -0.0937854871 2546 1311867803.5702500343 0.0426666141 0.0270976385 0.0606744327 0.0046493957 0.0281610000 257016134 95654136 760807424 -0.0046666246 0.0670629367 -0.0944210067 2547 1311867803.6121668816 0.0437716208 0.0271041850 0.0606744327 0.0046486400 0.0278380000 257018342 95654136 760807424 -0.0049563297 0.0684555769 -0.0952883437 2548 1311867803.6394500732 0.0453570336 0.0271113486 0.0606744327 0.0046480527 0.0315990000 257021646 95654136 760807424 -0.0036823426 0.0703655034 -0.0972807407 2549 1311867803.6726729870 0.0456566252 0.0271186241 0.0606744327 0.0046476631 0.0277800000 257025318 95654136 760807424 -0.0047443081 0.0711794868 -0.0972815976 2550 1311867803.7105441093 0.0467498079 0.0271263226 0.0606744327 0.0046473547 0.0276060000 257027214 95654136 760807424 -0.0051464378 0.0731729269 -0.0972724557 2551 1311867803.7378931046 0.0465404429 0.0271339330 0.0606744327 0.0046472570 0.0278250000 257030718 95654136 760807424 -0.0046828752 0.0737615898 -0.0986881927 2552 1311867803.7722349167 0.0460631736 0.0271413504 0.0606744327 0.0046465660 0.0278370000 257032502 95654136 760807424 -0.0051594540 0.0745955706 -0.0995928869 2553 1311867803.8064799309 0.0447285436 0.0271482393 0.0606744327 0.0046459701 0.0279160000 257036230 95654136 760807424 -0.0054249768 0.0741817504 -0.0990132019 2554 1311867803.8385739326 0.0456142724 0.0271554695 0.0606744327 0.0046467018 0.0277310000 257039646 95654136 760807424 -0.0057326029 0.0763979629 -0.0992192626 2555 1311867803.8737049103 0.0451603383 0.0271625164 0.0606744327 0.0046475261 0.0320780000 257212630 95654136 760807424 -0.0064208945 0.0773948804 -0.1003579795 2556 1311867803.9077479839 0.0439717658 0.0271690928 0.0606744327 0.0046478561 0.0305450000 257216158 95654136 760807424 -0.0060872207 0.0771019235 -0.1003250629 2557 1311867803.9400169849 0.0448204875 0.0271759960 0.0606744327 0.0046498274 0.0284770000 257217974 95654136 760807424 -0.0068503213 0.0788886398 -0.1002668440 2558 1311867803.9723939896 0.0465091504 0.0271835539 0.0606744327 0.0046500415 0.0296370000 257221502 95654136 760807424 -0.0069367685 0.0817289948 -0.1016042084 2559 1311867804.0064320564 0.0437214784 0.0271900165 0.0606744327 0.0046497102 0.0289230000 257225174 95654136 760807424 -0.0076721418 0.0794797912 -0.1018181071 2560 1311867804.0387020111 0.0434330553 0.0271963615 0.0606744327 0.0046492771 0.0285670000 257226846 95654136 760807424 -0.0091051692 0.0799556524 -0.1025488973 2561 1311867804.0722310543 0.0440112688 0.0272029272 0.0606744327 0.0046485832 0.0286890000 257230574 95654136 760807424 -0.0107712382 0.0813866928 -0.1040658578 2562 1311867804.1084001064 0.0430652313 0.0272091186 0.0606744327 0.0046480925 0.0285880000 257234102 95654136 760807424 -0.0122882314 0.0806453750 -0.1040403247 2563 1311867804.1399340630 0.0440231040 0.0272156789 0.0606744327 0.0046474758 0.0278890000 257235974 95654136 760807424 -0.0133849382 0.0817311034 -0.1048221067 2564 1311867804.1736989021 0.0451656468 0.0272226797 0.0606744327 0.0046468529 0.0277060000 257239502 95654136 760807424 -0.0135785956 0.0829618946 -0.1059810892 2565 1311867804.2092669010 0.0439140946 0.0272291870 0.0606744327 0.0046460453 0.0278060000 257241430 95654136 760807424 -0.0157535002 0.0814866573 -0.1058075577 2566 1311867804.2408709526 0.0459407941 0.0272364792 0.0606744327 0.0046460157 0.0277400000 257244846 95654136 760807424 -0.0159760267 0.0837528706 -0.1071384475 2567 1311867804.2707660198 0.0483400337 0.0272447003 0.0606744327 0.0046453910 0.0277980000 257248462 95654136 760807424 -0.0165257193 0.0866190493 -0.1082466170 2568 1311867804.3078389168 0.0465441123 0.0272522156 0.0606744327 0.0046449508 0.0277200000 257250190 95654136 760807424 -0.0173800364 0.0848972276 -0.1078426391 2569 1311867804.3404970169 0.0459014513 0.0272594749 0.0606744327 0.0046441332 0.0278240000 257253918 95654136 760807424 -0.0181168709 0.0845504105 -0.1084320098 2570 1311867804.3725171089 0.0472359024 0.0272672479 0.0606744327 0.0046432624 0.0313090000 257255590 95654136 760807424 -0.0174857378 0.0863264427 -0.1097165942 2571 1311867804.4121570587 0.0463923067 0.0272746866 0.0606744327 0.0046425855 0.0278140000 257259486 95654136 760807424 -0.0181618854 0.0855792612 -0.1096325368 2572 1311867804.4434490204 0.0456269979 0.0272818221 0.0606744327 0.0046418930 0.0318930000 257262958 95654136 760807424 -0.0180522315 0.0850467011 -0.1109659597 2573 1311867804.4745810032 0.0468135253 0.0272894131 0.0606744327 0.0046410055 0.0278680000 257264774 95654136 760807424 -0.0178359784 0.0867071152 -0.1126850098 2574 1311867804.5092110634 0.0451584421 0.0272963552 0.0606744327 0.0046409168 0.0276980000 257268302 95654136 760807424 -0.0191851333 0.0851141214 -0.1121063679 2575 1311867804.5393021107 0.0449356921 0.0273032054 0.0606744327 0.0046400825 0.0282190000 257270118 95654136 760807424 -0.0197114013 0.0854764506 -0.1133689657 2576 1311867804.5744440556 0.0468033105 0.0273107754 0.0606744327 0.0046395378 0.0280680000 257273646 95654136 760807424 -0.0195154715 0.0876768976 -0.1151417047 2577 1311867804.6065940857 0.0459029004 0.0273179900 0.0606744327 0.0046386648 0.0278210000 257277374 95654136 760807424 -0.0203737859 0.0869685709 -0.1147869974 2578 1311867804.6414110661 0.0477880687 0.0273259303 0.0606744327 0.0046382286 0.0278030000 257449478 95654136 760807424 -0.0207957942 0.0894482210 -0.1159164011 2579 1311867804.6758968830 0.0486834347 0.0273342116 0.0606744327 0.0046373861 0.0319280000 257453262 95654136 760807424 -0.0202352349 0.0910646394 -0.1166397706 2580 1311867804.7094891071 0.0478071459 0.0273421468 0.0606744327 0.0046365435 0.0403560000 257456734 95654136 760807424 -0.0205337182 0.0906590447 -0.1160875708 2581 1311867804.7431960106 0.0500391573 0.0273509407 0.0606744327 0.0046375613 0.0280760000 257458662 95654136 760807424 -0.0203263275 0.0938483998 -0.1166920289 2582 1311867804.7739880085 0.0513694398 0.0273602430 0.0606744327 0.0046373767 0.0277990000 257462022 95654136 760807424 -0.0205871481 0.0959257036 -0.1165794134 2583 1311867804.8113589287 0.0488431379 0.0273685600 0.0606744327 0.0046408750 0.0319440000 257464062 95654136 760807424 -0.0209881309 0.0938385576 -0.1160376370 2584 1311867804.8407669067 0.0511076525 0.0273777470 0.0606744327 0.0046406679 0.0313830000 257467478 95654136 760807424 -0.0209900159 0.0968240649 -0.1167950556 2585 1311867804.8758749962 0.0529521704 0.0273876404 0.0606744327 0.0046407356 0.0277880000 257471206 95654136 760807424 -0.0205471907 0.0993281677 -0.1165705696 2586 1311867804.9093499184 0.0506356433 0.0273966303 0.0606744327 0.0046405962 0.0279750000 257472934 95654136 760807424 -0.0215317700 0.0967670754 -0.1149439216 2587 1311867804.9418170452 0.0522369482 0.0274062323 0.0606744327 0.0046409397 0.0314430000 257476606 95654136 760807424 -0.0217453130 0.0993302763 -0.1161778346 2588 1311867804.9785380363 0.0535517856 0.0274163349 0.0606744327 0.0046400879 0.0278740000 257478334 95654136 760807424 -0.0210675951 0.1008397788 -0.1156044602 2589 1311867805.0090980530 0.0521350205 0.0274258825 0.0606744327 0.0046394189 0.0280160000 257481950 95654136 760807424 -0.0220870040 0.0992583111 -0.1145050079 2590 1311867805.0401790142 0.0520772450 0.0274354004 0.0606744327 0.0046386624 0.0279710000 257485422 95654136 760807424 -0.0224792697 0.0991428345 -0.1140753478 2591 1311867805.0801899433 0.0522114001 0.0274449627 0.0606744327 0.0046378882 0.0278980000 257487518 95654136 760807424 -0.0224111974 0.0994708315 -0.1141787991 2592 1311867805.1079609394 0.0515645184 0.0274542681 0.0606744327 0.0046380203 0.0288570000 257490934 95654136 760807424 -0.0222955756 0.0986274779 -0.1130424887 2593 1311867805.1444120407 0.0520959422 0.0274637713 0.0606744327 0.0046379702 0.0312750000 257492918 95654136 760807424 -0.0227793250 0.0989694968 -0.1119973958 2594 1311867805.1750040054 0.0526417531 0.0274734775 0.0606744327 0.0046373195 0.0279240000 257496278 95654136 760807424 -0.0231720079 0.0998163745 -0.1121430248 2595 1311867805.2100739479 0.0528621599 0.0274832612 0.0606744327 0.0046375842 0.0385160000 257500062 95654136 760807424 -0.0222590957 0.1005867124 -0.1122085378 2596 1311867805.2393519878 0.0519845188 0.0274926993 0.0606744327 0.0046367683 0.0279270000 257501678 95654136 760807424 -0.0222002603 0.0995784998 -0.1104793474 2597 1311867805.2741580009 0.0518387817 0.0275020740 0.0606744327 0.0046359062 0.0279650000 257505406 95654136 760807424 -0.0223735850 0.0994864479 -0.1101021990 2598 1311867805.3108520508 0.0528897941 0.0275118460 0.0606744327 0.0046354245 0.0278600000 257508990 95654136 760807424 -0.0214045402 0.1006218791 -0.1091056317 2599 1311867805.3395309448 0.0524501987 0.0275214414 0.0606744327 0.0046347658 0.0279040000 257510806 95654136 760807424 -0.0215776581 0.1000549346 -0.1083036587 2600 1311867805.3745789528 0.0527263768 0.0275311356 0.0606744327 0.0046395496 0.0280760000 257685158 95654136 760807424 -0.0200776681 0.1005382463 -0.1081979200 2601 1311867805.4084360600 0.0535379462 0.0275411344 0.0606744327 0.0046388464 0.0278590000 257687142 95654136 760807424 -0.0183940437 0.1020316705 -0.1087871194 2602 1311867805.4401900768 0.0555403009 0.0275518950 0.0606744327 0.0046381872 0.0318830000 257690558 95654136 760807424 -0.0182847530 0.1042009518 -0.1077877879 2603 1311867805.4747269154 0.0538192205 0.0275619862 0.0606744327 0.0046381069 0.0279840000 257694286 95654136 760807424 -0.0186198149 0.1022910625 -0.1061835140 2604 1311867805.5079410076 0.0545330197 0.0275723437 0.0606744327 0.0046379416 0.0278810000 257696014 95654136 760807424 -0.0190566815 0.1031145751 -0.1062894613 2605 1311867805.5406329632 0.0541235097 0.0275825361 0.0606744327 0.0046371183 0.0279660000 257699742 95654136 760807424 -0.0189992655 0.1027204171 -0.1060676873 2606 1311867805.5750451088 0.0535310954 0.0275924933 0.0606744327 0.0046364301 0.0278630000 257701414 95654136 760807424 -0.0185672902 0.1016331837 -0.1044853404 2607 1311867805.6078290939 0.0514856130 0.0276016583 0.0606744327 0.0046363126 0.0279240000 257705142 95654136 760807424 -0.0174099226 0.0992862433 -0.1040670723 2608 1311867805.6431670189 0.0534044020 0.0276115520 0.0606744327 0.0046372138 0.0278930000 257708726 95654136 760807424 -0.0167568251 0.1013217568 -0.1050675884 2609 1311867805.6750800610 0.0529221557 0.0276212533 0.0606744327 0.0046364461 0.0384940000 257710598 95654136 760807424 -0.0161234327 0.1006832793 -0.1050598472 2610 1311867805.7071790695 0.0518989377 0.0276305551 0.0606744327 0.0046358258 0.0279400000 257885078 95654136 760807424 -0.0163247753 0.0992438942 -0.1043936536 2611 1311867805.7425789833 0.0513334498 0.0276396332 0.0606744327 0.0046369034 0.0280000000 257887062 95654136 760807424 -0.0166595932 0.0982224718 -0.1040425152 2612 1311867805.7748079300 0.0526183620 0.0276491962 0.0606744327 0.0046362787 0.0278610000 257890478 95654136 760807424 -0.0164674427 0.0993188024 -0.1043130532 2613 1311867805.8089549541 0.0522437952 0.0276586086 0.0606744327 0.0046356352 0.0278490000 257894206 95654136 760807424 -0.0165412910 0.0987461731 -0.1041582972 2614 1311867805.8436930180 0.0527017824 0.0276681890 0.0606744327 0.0046374842 0.0323730000 257895878 95654136 760807424 -0.0166071206 0.0991328061 -0.1040918753 2615 1311867805.8754489422 0.0533652380 0.0276780158 0.0606744327 0.0046366934 0.0279900000 258070130 95654136 760807424 -0.0149028627 0.0999180675 -0.1031865031 2616 1311867805.9129049778 0.0533573963 0.0276878321 0.0606744327 0.0046408100 0.0373280000 258073770 95654136 760807424 -0.0148867965 0.0994706377 -0.1030044183 2617 1311867805.9434199333 0.0539113246 0.0276978525 0.0606744327 0.0046410949 0.0279400000 258075642 95654136 760807424 -0.0132750217 0.1000178307 -0.1031307802 2618 1311867805.9747679234 0.0553616360 0.0277084193 0.0606744327 0.0046407530 0.0277580000 258079058 95654136 760807424 -0.0140077341 0.1014405787 -0.1038836166 2619 1311867806.0099248886 0.0570535101 0.0277196240 0.0606744327 0.0046410548 0.0278390000 258080986 95654136 760807424 -0.0146050612 0.1027201712 -0.1032003760 2620 1311867806.0427870750 0.0575894788 0.0277310247 0.0606744327 0.0046403176 0.0278970000 258255222 95654136 760807424 -0.0157523248 0.1029026806 -0.1029753312 2621 1311867806.0743720531 0.0596168004 0.0277431902 0.0606744327 0.0046428037 0.0279630000 258258782 95654136 760807424 -0.0138093270 0.1056480706 -0.1036963016 2622 1311867806.1078710556 0.0589376986 0.0277550874 0.0606744327 0.0046421611 0.0320080000 258260510 95654136 760807424 -0.0128959436 0.1049497724 -0.1027874798 2623 1311867806.1461410522 0.0596814677 0.0277672591 0.0606744327 0.0046415412 0.0315620000 258264350 95654136 760807424 -0.0127079142 0.1057754382 -0.1027089357 2624 1311867806.1751658916 0.0616078451 0.0277801557 0.0616078451 0.0046410129 0.0278670000 258265910 95654136 760807424 -0.0109786056 0.1083648205 -0.1029150635 2625 1311867806.2106690407 0.0603137687 0.0277925494 0.0616078451 0.0046411276 0.0287300000 258269694 95654136 760807424 -0.0104522910 0.1071385592 -0.1017637253 2626 1311867806.2435200214 0.0599948317 0.0278048123 0.0616078451 0.0046404365 0.0279580000 258273222 95654136 760807424 -0.0098015880 0.1071459576 -0.1012910157 2627 1311867806.2773389816 0.0620463602 0.0278178468 0.0620463602 0.0046402028 0.0278640000 258275150 95654136 760807424 -0.0094990991 0.1097449809 -0.1011540666 2628 1311867806.3098840714 0.0608401224 0.0278304123 0.0620463602 0.0046393458 0.0279560000 258278566 95654136 760807424 -0.0086150365 0.1086333022 -0.0996912494 2629 1311867806.3459429741 0.0602792092 0.0278427550 0.0620463602 0.0046386728 0.0278530000 258280606 95654136 760807424 -0.0074363230 0.1085667759 -0.0997977927 2630 1311867806.3760368824 0.0614993498 0.0278555521 0.0620463602 0.0046378579 0.0278470000 258284022 95654136 760807424 -0.0068929801 0.1102138907 -0.0998248234 2631 1311867806.4090569019 0.0585528761 0.0278672197 0.0620463602 0.0046465325 0.0401150000 258287694 95654136 760807424 -0.0054084933 0.1071664095 -0.0982961655 2632 1311867806.4434189796 0.0576858371 0.0278785490 0.0620463602 0.0046467396 0.0280120000 258289422 95654136 760807424 -0.0053583854 0.1061622649 -0.0983260795 2633 1311867806.4748079777 0.0615599304 0.0278913410 0.0620463602 0.0046496109 0.0279420000 258293094 95654136 760807424 -0.0047508092 0.1102354228 -0.0986710861 2634 1311867806.5103459358 0.0590633303 0.0279031754 0.0620463602 0.0046496627 0.0279270000 258296678 95654136 760807424 -0.0037100287 0.1073045209 -0.0976330563 2635 1311867806.5426719189 0.0600223467 0.0279153649 0.0620463602 0.0046492267 0.0316610000 258298550 95654136 760807424 -0.0013614306 0.1088635102 -0.0983262584 2636 1311867806.5787520409 0.0641259253 0.0279291018 0.0641259253 0.0046485041 0.0280070000 258302078 95654136 760807424 0.0008328662 0.1135193408 -0.0986511260 2637 1311867806.6116139889 0.0611556992 0.0279417020 0.0641259253 0.0046494908 0.0313470000 258304062 95654136 760807424 0.0012127417 0.1105151698 -0.0975326896 2638 1311867806.6448700428 0.0612399168 0.0279543245 0.0641259253 0.0046487137 0.0317880000 258307534 95654136 760807424 0.0019040634 0.1109962910 -0.0968985930 2639 1311867806.6744968891 0.0637513176 0.0279678891 0.0641259253 0.0046493955 0.0278900000 258311150 95654136 760807424 0.0004888007 0.1138966233 -0.0970179960 2640 1311867806.7064468861 0.0621165931 0.0279808242 0.0641259253 0.0046489749 0.0278690000 258312822 95654136 760807424 0.0010180653 0.1125943288 -0.0958968550 2641 1311867806.7427020073 0.0600233264 0.0279929569 0.0641259253 0.0046487390 0.0282740000 258316606 95654136 760807424 0.0023633037 0.1109724119 -0.0948024169 2642 1311867806.7790679932 0.0610037483 0.0280054515 0.0641259253 0.0046487228 0.0278490000 258318334 95654136 760807424 0.0020147515 0.1128348112 -0.0945376977 2643 1311867806.8067629337 0.0593966544 0.0280173287 0.0641259253 0.0046484279 0.0280970000 258493622 95654136 760807424 0.0024580844 0.1111957952 -0.0933547318 2644 1311867806.8439810276 0.0576562323 0.0280285385 0.0641259253 0.0046475759 0.0280750000 258497206 95654136 760807424 0.0026860724 0.1093233228 -0.0923105478 2645 1311867806.8763918877 0.0604985617 0.0280408145 0.0641259253 0.0046474059 0.0316090000 258499078 95654136 760807424 0.0015270135 0.1122576520 -0.0927187800 2646 1311867806.9124479294 0.0592637174 0.0280526146 0.0641259253 0.0046465588 0.0286890000 258502662 95654136 760807424 0.0008820342 0.1103687659 -0.0915358737 2647 1311867806.9446148872 0.0590262525 0.0280643160 0.0641259253 0.0046459984 0.0280280000 258504478 95654136 760807424 0.0003032107 0.1095653549 -0.0907767788 2648 1311867806.9770460129 0.0607881136 0.0280766739 0.0641259253 0.0046453926 0.0279470000 258508062 95654136 760807424 0.0010721239 0.1115942225 -0.0911913589 2649 1311867807.0138700008 0.0590709969 0.0280883743 0.0641259253 0.0046468038 0.0280830000 258511790 95654136 760807424 0.0018631367 0.1097059324 -0.0902151838 2650 1311867807.0428779125 0.0590182506 0.0281000459 0.0641259253 0.0046459990 0.0280530000 258513462 95654136 760807424 0.0019359377 0.1093021035 -0.0891885757 2651 1311867807.0794920921 0.0604531206 0.0281122501 0.0641259253 0.0046471681 0.0279470000 258517190 95654136 760807424 0.0009241998 0.1104393899 -0.0885787085 2652 1311867807.1121389866 0.0624117441 0.0281251835 0.0641259253 0.0046464574 0.0278920000 258520718 95654136 760807424 0.0003310364 0.1126512662 -0.0883495435 2653 1311867807.1428070068 0.0607163012 0.0281374681 0.0641259253 0.0046456950 0.0280430000 258522590 95654136 760807424 0.0013903358 0.1108975187 -0.0872064084 2654 1311867807.1802010536 0.0613584667 0.0281499855 0.0641259253 0.0046458587 0.0323680000 258697670 95654136 760807424 -0.0004949458 0.1111188829 -0.0873559788 2655 1311867807.2105820179 0.0645303652 0.0281636880 0.0645303652 0.0046460566 0.0324570000 258699486 95654136 760807424 -0.0003196760 0.1147394553 -0.0873136446 2656 1311867807.2429521084 0.0619284771 0.0281764007 0.0645303652 0.0046459727 0.0315470000 258702958 95654136 760807424 0.0005760359 0.1118400916 -0.0859110877 2657 1311867807.2808670998 0.0601529814 0.0281884355 0.0645303652 0.0046453269 0.0280490000 258706798 95654136 760807424 0.0023542163 0.1096888110 -0.0851879269 2658 1311867807.3107318878 0.0624776818 0.0282013359 0.0645303652 0.0046446801 0.0322160000 258708414 95654136 760807424 0.0022199347 0.1118562594 -0.0854330808 2659 1311867807.3434429169 0.0624477938 0.0282142154 0.0645303652 0.0046442511 0.0280810000 258712086 95654136 760807424 0.0017860716 0.1112098843 -0.0851476043 2660 1311867807.3776888847 0.0605069771 0.0282263555 0.0645303652 0.0046456841 0.0280130000 258713814 95654136 760807424 0.0049396902 0.1091345474 -0.0846995115 2661 1311867807.4111731052 0.0635455251 0.0282396284 0.0645303652 0.0046477541 0.0316110000 258717542 95654136 760807424 0.0025280789 0.1114107370 -0.0853274465 2662 1311867807.4426960945 0.0639648959 0.0282530489 0.0645303652 0.0046468916 0.0280170000 258721014 95654136 760807424 0.0030786146 0.1117708310 -0.0854335129 2663 1311867807.4781239033 0.0619721003 0.0282657109 0.0645303652 0.0046506943 0.0281090000 258894358 95654136 760807424 0.0050016101 0.1094477251 -0.0844450817 2664 1311867807.5104010105 0.0608861372 0.0282779558 0.0645303652 0.0046504131 0.0280280000 258897774 95654136 760807424 0.0035246883 0.1071020886 -0.0843396708 2665 1311867807.5430259705 0.0617058836 0.0282904991 0.0645303652 0.0046500080 0.0280660000 258899646 95654136 760807424 0.0043646889 0.1075891033 -0.0849484801 2666 1311867807.5746030807 0.0604680404 0.0283025687 0.0645303652 0.0046506753 0.0279410000 258903118 95654136 760807424 0.0050213635 0.1056490391 -0.0849048346 2667 1311867807.6121149063 0.0602108017 0.0283145328 0.0645303652 0.0046501279 0.0281600000 258906958 95654136 760807424 0.0037911145 0.1041824073 -0.0858077779 2668 1311867807.6434121132 0.0621954054 0.0283272318 0.0645303652 0.0046499070 0.0278740000 258908630 95654136 760807424 0.0042844098 0.1058827788 -0.0869632959 2669 1311867807.6772611141 0.0614086948 0.0283396265 0.0645303652 0.0046495197 0.0320700000 258912358 95654136 760807424 0.0034466679 0.1041247919 -0.0873685405 2670 1311867807.7112979889 0.0587615520 0.0283510205 0.0645303652 0.0046490222 0.0279930000 259085794 95654136 760807424 0.0046940502 0.1013464108 -0.0879232883 2671 1311867807.7441759109 0.0621659793 0.0283636805 0.0645303652 0.0046506029 0.0317410000 259087722 95654136 760807424 0.0043871999 0.1050295979 -0.0887339190 2672 1311867807.7760479450 0.0637213737 0.0283769132 0.0645303652 0.0046498501 0.0280360000 259091138 95654136 760807424 0.0026832158 0.1063833609 -0.0892860815 2673 1311867807.8105859756 0.0616610460 0.0283893652 0.0645303652 0.0046505032 0.0279260000 259093066 95654136 760807424 0.0020900439 0.1039012372 -0.0890130028 2674 1311867807.8429179192 0.0644392148 0.0284028468 0.0645303652 0.0046506278 0.0278590000 259096538 95654136 760807424 0.0016236333 0.1066137776 -0.0884378478 2675 1311867807.8800721169 0.0659444854 0.0284168810 0.0659444854 0.0046504258 0.0280090000 259100266 95654136 760807424 0.0011853437 0.1079815403 -0.0882909223 2676 1311867807.9118909836 0.0639100969 0.0284301446 0.0659444854 0.0046496776 0.0321530000 259101994 95654136 760807424 0.0003827278 0.1057928279 -0.0884074196 2677 1311867807.9477560520 0.0621518940 0.0284427414 0.0659444854 0.0046505690 0.0279500000 259105722 95654136 760807424 0.0017269372 0.1041244864 -0.0881663263 2678 1311867807.9757928848 0.0622612983 0.0284553697 0.0659444854 0.0046500482 0.0278810000 259107282 95654136 760807424 0.0039641354 0.1050302759 -0.0886175931 2679 1311867808.0103120804 0.0627272800 0.0284681625 0.0659444854 0.0046502786 0.0278910000 259111010 95654136 760807424 0.0040893038 0.1060150191 -0.0893971100 2680 1311867808.0437099934 0.0638856143 0.0284813780 0.0659444854 0.0046494715 0.0285340000 259114538 95654136 760807424 0.0036354342 0.1073031276 -0.0903967917 2681 1311867808.0799739361 0.0601047799 0.0284931734 0.0659444854 0.0046657043 0.0289050000 259116522 95654136 760807424 0.0035428561 0.1048222110 -0.0908863619 2682 1311867808.1118609905 0.0602484308 0.0285050135 0.0659444854 0.0046687744 0.0282100000 259290858 95654136 760807424 0.0047352212 0.1046748087 -0.0909018368 2683 1311867808.1470420361 0.0596799217 0.0285166329 0.0659444854 0.0046683719 0.0280760000 259292786 95654136 760807424 0.0046092463 0.1036363021 -0.0912025571 2684 1311867808.1792190075 0.0607910715 0.0285286577 0.0659444854 0.0046690370 0.0280950000 259296202 95654136 760807424 0.0032394973 0.1042346954 -0.0927572325 2685 1311867808.2112250328 0.0581943206 0.0285397063 0.0659444854 0.0046942576 0.0279460000 259299930 95654136 760807424 0.0041251788 0.1006712466 -0.0930764824 2686 1311867808.2432029247 0.0587145053 0.0285509404 0.0659444854 0.0046934138 0.0321820000 259301658 95654136 760807424 0.0057650143 0.1014568433 -0.0941285938 2687 1311867808.2811930180 0.0602368414 0.0285627327 0.0659444854 0.0046932538 0.0314080000 259305442 95654136 760807424 0.0058836499 0.1028827652 -0.0949903429 2688 1311867808.3112449646 0.0603380762 0.0285745539 0.0659444854 0.0046925882 0.0279180000 259308858 95654136 760807424 0.0075706821 0.1033675075 -0.0952807590 2689 1311867808.3454720974 0.0599514954 0.0285862225 0.0659444854 0.0046918491 0.0313650000 259310786 95654136 760807424 0.0078542437 0.1031007916 -0.0957590491 2690 1311867808.3792409897 0.0611168407 0.0285983157 0.0659444854 0.0046914248 0.0277630000 259314258 95654136 760807424 0.0077874032 0.1042164192 -0.0964952707 2691 1311867808.4111659527 0.0607813783 0.0286102752 0.0659444854 0.0046917658 0.0278560000 259316186 95654136 760807424 0.0079174684 0.1039796397 -0.0976706743 2692 1311867808.4447789192 0.0633445606 0.0286231780 0.0659444854 0.0046915372 0.0321480000 259319658 95654136 760807424 0.0076196147 0.1068199128 -0.0988464355 2693 1311867808.4827229977 0.0618495457 0.0286355161 0.0659444854 0.0046910842 0.0280130000 259323554 95654136 760807424 0.0076110484 0.1053010821 -0.0996622965 2694 1311867808.5103700161 0.0604740083 0.0286473344 0.0659444854 0.0046952402 0.0277700000 259325058 95654136 760807424 0.0092147263 0.1041179821 -0.0992247984 2695 1311867808.5431969166 0.0619755238 0.0286597010 0.0659444854 0.0046950580 0.0320990000 259328842 95654136 760807424 0.0101046469 0.1062296405 -0.1005896106 2696 1311867808.5788240433 0.0592929758 0.0286710635 0.0659444854 0.0046944562 0.0313300000 259330570 95654136 760807424 0.0098349005 0.1033174247 -0.1003452912 2697 1311867808.6111960411 0.0583796538 0.0286820789 0.0659444854 0.0046937502 0.0278460000 259334242 95654136 760807424 0.0114696929 0.1026401296 -0.1003568098 2698 1311867808.6424980164 0.0570356995 0.0286925881 0.0659444854 0.0046930279 0.0279150000 259337714 95654136 760807424 0.0117077613 0.1010594964 -0.1003346145 2699 1311867808.6796329021 0.0562908389 0.0287028134 0.0659444854 0.0046922496 0.0314380000 259509618 95654136 760807424 0.0102747316 0.0998501480 -0.1017076448 2700 1311867808.7121589184 0.0570543483 0.0287133140 0.0659444854 0.0046917438 0.0277940000 259513202 95654136 760807424 0.0118005257 0.1008110791 -0.1014532149 2701 1311867808.7424249649 0.0538240783 0.0287226108 0.0659444854 0.0046924010 0.0314050000 259515018 95654136 760807424 0.0128234755 0.0973659903 -0.1015961021 2702 1311867808.7797210217 0.0535465069 0.0287317981 0.0659444854 0.0046919201 0.0278210000 259518602 95654136 760807424 0.0126479855 0.0966514051 -0.1025066078 2703 1311867808.8102169037 0.0571787469 0.0287423223 0.0659444854 0.0046929594 0.0277850000 259522218 95654136 760807424 0.0116950367 0.1000049040 -0.1033763289 2704 1311867808.8426899910 0.0550842881 0.0287520641 0.0659444854 0.0046961893 0.0278750000 259523890 95654136 760807424 0.0118769202 0.0971713066 -0.1031354517 2705 1311867808.8811960220 0.0547207110 0.0287616644 0.0659444854 0.0046953901 0.0278990000 259527786 95654136 760807424 0.0133075481 0.0965188220 -0.1042207256 2706 1311867808.9101860523 0.0584578216 0.0287726386 0.0659444854 0.0046949592 0.0279410000 259531146 95654136 760807424 0.0124559971 0.0999648795 -0.1052698046 2707 1311867808.9424829483 0.0538176708 0.0287818905 0.0659444854 0.0046945929 0.0320890000 259533074 95654136 760807424 0.0140318051 0.0947420225 -0.1059480608 2708 1311867808.9811229706 0.0550358295 0.0287915855 0.0659444854 0.0046961694 0.0312860000 259706578 95654136 760807424 0.0124962125 0.0953805074 -0.1077347472 2709 1311867809.0102269650 0.0578185283 0.0288023005 0.0659444854 0.0046957529 0.0279020000 259708338 95654136 760807424 0.0109465262 0.0977158695 -0.1090497226 2710 1311867809.0425639153 0.0546161272 0.0288118259 0.0659444854 0.0046957093 0.0277830000 259711866 95654136 760807424 0.0112931002 0.0940361097 -0.1086864024 2711 1311867809.0782320499 0.0563713647 0.0288219917 0.0659444854 0.0046964171 0.0277860000 259715594 95654136 760807424 0.0111485282 0.0956591517 -0.1096553281 2712 1311867809.1110110283 0.0598217398 0.0288334223 0.0659444854 0.0046962910 0.0277060000 259717322 95654136 760807424 0.0091714282 0.0987631828 -0.1105703712 2713 1311867809.1425359249 0.0586048141 0.0288443959 0.0659444854 0.0046963204 0.0400660000 259720994 95654136 760807424 0.0113233812 0.0980789736 -0.1106615663 2714 1311867809.1801810265 0.0603733025 0.0288560130 0.0659444854 0.0046963492 0.0283220000 259722778 95654136 760807424 0.0120711979 0.1000294536 -0.1101952642 2715 1311867809.2120649815 0.0639471337 0.0288689379 0.0659444854 0.0046972814 0.0315280000 259726450 95654136 760807424 0.0115155503 0.1038496271 -0.1102671176 2716 1311867809.2422831059 0.0614349693 0.0288809284 0.0659444854 0.0046969492 0.0277970000 259729922 95654136 760807424 0.0111134630 0.1011827514 -0.1111895293 2717 1311867809.2790520191 0.0599429645 0.0288923608 0.0659444854 0.0046966721 0.0278250000 259731794 95654136 760807424 0.0132406792 0.1002606004 -0.1112853214 2718 1311867809.3103950024 0.0604184307 0.0289039598 0.0659444854 0.0046958574 0.0277550000 259735266 95654136 760807424 0.0133367600 0.1007371172 -0.1116333827 2719 1311867809.3436670303 0.0606108159 0.0289156211 0.0659444854 0.0046955003 0.0320730000 259737194 95654136 760807424 0.0159644000 0.1014336869 -0.1114256531 2720 1311867809.3787779808 0.0582407676 0.0289264024 0.0659444854 0.0046949178 0.0380730000 259740666 95654136 760807424 0.0158680454 0.0988361463 -0.1120723113 2721 1311867809.4101309776 0.0600012988 0.0289378228 0.0659444854 0.0046941933 0.0320300000 259744338 95654136 760807424 0.0160327367 0.1002435833 -0.1118798777 2722 1311867809.4475460052 0.0618224144 0.0289499038 0.0659444854 0.0046939190 0.0277450000 259746178 95654136 760807424 0.0160523672 0.1018815786 -0.1122185588 2723 1311867809.4785499573 0.0600469820 0.0289613239 0.0659444854 0.0046932616 0.0280410000 259749906 95654136 760807424 0.0173568949 0.1003372893 -0.1128817052 2724 1311867809.5100600719 0.0605050027 0.0289729039 0.0659444854 0.0046931039 0.0278310000 259753266 95654136 760807424 0.0174775869 0.1011130512 -0.1141339615 2725 1311867809.5460391045 0.0621274225 0.0289850707 0.0659444854 0.0046924576 0.0285350000 259755306 95654136 760807424 0.0180447493 0.1030329913 -0.1140774265 2726 1311867809.5791211128 0.0599023812 0.0289964123 0.0659444854 0.0046917877 0.0320690000 259758778 95654136 760807424 0.0188059472 0.1010427475 -0.1147343516 2727 1311867809.6122300625 0.0590270199 0.0290074246 0.0659444854 0.0046909800 0.0316760000 259930490 95654136 760807424 0.0194804538 0.1005903929 -0.1152475402 2728 1311867809.6463921070 0.0610498004 0.0290191704 0.0659444854 0.0046902306 0.0278380000 259934018 95654136 760807424 0.0205710288 0.1029540524 -0.1148379296 2729 1311867809.6796839237 0.0630640984 0.0290316456 0.0659444854 0.0046896231 0.0278500000 259937690 95654136 760807424 0.0202544499 0.1049921736 -0.1145971119 2730 1311867809.7111020088 0.0606767051 0.0290432372 0.0659444854 0.0046899693 0.0277760000 259939362 95654136 760807424 0.0226493385 0.1030565798 -0.1151912957 2731 1311867809.7464809418 0.0563476346 0.0290532351 0.0659444854 0.0046902969 0.0279060000 259943146 95654136 760807424 0.0235701185 0.0984295756 -0.1168503910 2732 1311867809.7800478935 0.0560137443 0.0290631036 0.0659444854 0.0046897177 0.0280830000 259944818 95654136 760807424 0.0248626284 0.0979395285 -0.1182293072 2733 1311867809.8107759953 0.0548420809 0.0290725360 0.0659444854 0.0046894838 0.0279370000 259948490 95654136 760807424 0.0267353542 0.0965453908 -0.1187903434 2734 1311867809.8470799923 0.0540779680 0.0290816821 0.0659444854 0.0046886584 0.0313870000 259952074 95654136 760807424 0.0268162172 0.0951633602 -0.1208324209 2735 1311867809.8791100979 0.0544338971 0.0290909517 0.0659444854 0.0046879863 0.0378500000 259953946 95654136 760807424 0.0260346029 0.0948734432 -0.1231056526 2736 1311867809.9124441147 0.0566400178 0.0291010208 0.0659444854 0.0046877679 0.0278640000 259957418 95654136 760807424 0.0261899047 0.0966459885 -0.1235970780 2737 1311867809.9469900131 0.0552121550 0.0291105608 0.0659444854 0.0046870193 0.0278640000 260128922 95654136 760807424 0.0270826798 0.0950484872 -0.1251470894 2738 1311867809.9805769920 0.0555791929 0.0291202280 0.0659444854 0.0046867249 0.0278960000 260132338 95654136 760807424 0.0276478343 0.0955186859 -0.1268632263 2739 1311867810.0119459629 0.0560841970 0.0291300724 0.0659444854 0.0046858954 0.0320970000 260135954 95654136 760807424 0.0266208220 0.0956541002 -0.1278905571 2740 1311867810.0470910072 0.0545973070 0.0291393671 0.0659444854 0.0046851214 0.0313060000 260137682 95654136 760807424 0.0270680394 0.0941672847 -0.1274272203 2741 1311867810.0808799267 0.0573758110 0.0291496686 0.0659444854 0.0046852951 0.0277580000 260141354 95654136 760807424 0.0267608948 0.0972692296 -0.1276603490 2742 1311867810.1118919849 0.0573761500 0.0291599627 0.0659444854 0.0046845218 0.0324000000 260144826 95654136 760807424 0.0264423341 0.0974881276 -0.1280065030 2743 1311867810.1474719048 0.0564877912 0.0291699254 0.0659444854 0.0046844310 0.0278860000 260146810 95654136 760807424 0.0269633438 0.0969866514 -0.1273541301 2744 1311867810.1817660332 0.0536232293 0.0291788370 0.0659444854 0.0046841615 0.0319670000 260150282 95654136 760807424 0.0278207213 0.0945183188 -0.1281135380 2745 1311867810.2106039524 0.0537022203 0.0291877708 0.0659444854 0.0046833418 0.0280810000 260152098 95654136 760807424 0.0286571644 0.0952189937 -0.1291108429 2746 1311867810.2471721172 0.0546831153 0.0291970554 0.0659444854 0.0046838341 0.0277960000 260155682 95654136 760807424 0.0285344590 0.0963744670 -0.1291045099 2747 1311867810.2785871029 0.0520873815 0.0292053882 0.0659444854 0.0046838025 0.0284130000 260159298 95654136 760807424 0.0297899302 0.0941695198 -0.1301255226 2748 1311867810.3111360073 0.0535281077 0.0292142393 0.0659444854 0.0046832479 0.0277210000 260161026 95654136 760807424 0.0303265359 0.0958992764 -0.1308804899 2749 1311867810.3463029861 0.0534490049 0.0292230551 0.0659444854 0.0046825931 0.0411790000 260164810 95654136 760807424 0.0305646006 0.0957442448 -0.1311189979 2750 1311867810.3784830570 0.0546294339 0.0292322938 0.0659444854 0.0046823271 0.0280280000 260166538 95654136 760807424 0.0308062676 0.0971030369 -0.1316009909 2751 1311867810.4100239277 0.0524201617 0.0292407227 0.0659444854 0.0046819671 0.0277880000 260170098 95654136 760807424 0.0303801615 0.0947226882 -0.1327880025 2752 1311867810.4462749958 0.0517381653 0.0292488976 0.0659444854 0.0046811392 0.0278280000 260173682 95654136 760807424 0.0307229850 0.0942059979 -0.1339296252 2753 1311867810.4781119823 0.0553520955 0.0292583794 0.0659444854 0.0046810662 0.0278510000 260175498 95654136 760807424 0.0303630680 0.0979874283 -0.1340483427 2754 1311867810.5101990700 0.0578036606 0.0292687444 0.0659444854 0.0046804553 0.0277830000 260178970 95654136 760807424 0.0303747058 0.1009153351 -0.1350987107 2755 1311867810.5459640026 0.0575841628 0.0292790222 0.0659444854 0.0046798319 0.0313800000 260180954 95654136 760807424 0.0308335908 0.1011961624 -0.1360318810 2756 1311867810.5791409016 0.0578874908 0.0292894027 0.0659444854 0.0046790025 0.0309160000 260354634 95654136 760807424 0.0317056812 0.1021880656 -0.1367453933 2757 1311867810.6141140461 0.0597683750 0.0293004578 0.0659444854 0.0046782846 0.0277340000 260358418 95654136 760807424 0.0320448130 0.1046172827 -0.1371741742 2758 1311867810.6471910477 0.0578573868 0.0293108120 0.0659444854 0.0046777951 0.0284550000 260360146 95654136 760807424 0.0328409560 0.1030535698 -0.1368654370 2759 1311867810.6781129837 0.0597911552 0.0293218596 0.0659444854 0.0046774974 0.0278840000 260363762 95654136 760807424 0.0317162983 0.1053032801 -0.1379137188 2760 1311867810.7146449089 0.0632062033 0.0293341365 0.0659444854 0.0046770550 0.0279280000 260367346 95654136 760807424 0.0304501355 0.1090170369 -0.1380454302 2761 1311867810.7468900681 0.0617035143 0.0293458603 0.0659444854 0.0046769720 0.0279760000 260369274 95654136 760807424 0.0313119441 0.1081778705 -0.1385106742 2762 1311867810.7789669037 0.0615696572 0.0293575272 0.0659444854 0.0046769749 0.0279310000 260372746 95654136 760807424 0.0303094145 0.1085207686 -0.1395032108 2763 1311867810.8146491051 0.0608988814 0.0293689428 0.0659444854 0.0046762714 0.0278600000 260374674 95654136 760807424 0.0307618845 0.1084477752 -0.1396453232 2764 1311867810.8460769653 0.0612271242 0.0293804689 0.0659444854 0.0046811047 0.0375070000 260378146 95654136 760807424 0.0304748751 0.1086390093 -0.1407826543 2765 1311867810.8793289661 0.0630688667 0.0293926528 0.0659444854 0.0046806909 0.0279170000 260381874 95654136 760807424 0.0303246193 0.1108805761 -0.1410603970 2766 1311867810.9141631126 0.0629694760 0.0294047919 0.0659444854 0.0046812289 0.0279260000 260383658 95654136 760807424 0.0307569280 0.1113654524 -0.1407150179 2767 1311867810.9458940029 0.0612258390 0.0294162921 0.0659444854 0.0046843278 0.0281160000 260557874 95654136 760807424 0.0313957706 0.1107454747 -0.1407329440 2768 1311867810.9796259403 0.0601747744 0.0294274043 0.0659444854 0.0046835505 0.0279520000 260559546 95654136 760807424 0.0308926217 0.1100257263 -0.1428142488 2769 1311867811.0151500702 0.0602942593 0.0294385515 0.0659444854 0.0046883624 0.0315850000 260563330 95654136 760807424 0.0312070139 0.1099528968 -0.1431602538 2770 1311867811.0469939709 0.0617949143 0.0294502325 0.0659444854 0.0046889048 0.0279240000 260566802 95654136 760807424 0.0314422362 0.1122080386 -0.1428318024 2771 1311867811.0785760880 0.0616569147 0.0294618553 0.0659444854 0.0046883920 0.0379970000 260568674 95654136 760807424 0.0328684077 0.1130103618 -0.1426132619 2772 1311867811.1144239902 0.0624656454 0.0294737614 0.0659444854 0.0046883870 0.0279780000 260572258 95654136 760807424 0.0328213982 0.1147992089 -0.1431238055 2773 1311867811.1461989880 0.0622620843 0.0294855856 0.0659444854 0.0046882714 0.0279410000 260574130 95654136 760807424 0.0323671028 0.1153977513 -0.1437997073 2774 1311867811.1786370277 0.0614432730 0.0294971060 0.0659444854 0.0046874851 0.0315940000 260577658 95654136 760807424 0.0318724848 0.1153091490 -0.1443804651 2775 1311867811.2142488956 0.0612658858 0.0295085542 0.0659444854 0.0046870859 0.0279870000 260581330 95654136 760807424 0.0328632705 0.1160185263 -0.1442485452 2776 1311867811.2464840412 0.0628362074 0.0295205599 0.0659444854 0.0046866982 0.0315040000 260752506 95654136 760807424 0.0326549411 0.1182916537 -0.1442848146 2777 1311867811.2798390388 0.0653027892 0.0295334451 0.0659444854 0.0046863651 0.0280080000 260756234 95654136 760807424 0.0321102142 0.1213612482 -0.1440330297 2778 1311867811.3147039413 0.0631745979 0.0295455549 0.0659444854 0.0046859813 0.0325560000 260759762 95654136 760807424 0.0327054784 0.1201573461 -0.1447649151 2779 1311867811.3470849991 0.0644843206 0.0295581273 0.0659444854 0.0046865348 0.0298020000 260761634 95654136 760807424 0.0322118662 0.1215173006 -0.1446831375 2780 1311867811.3799240589 0.0651061833 0.0295709144 0.0659444854 0.0046859164 0.0289790000 260765106 95654136 760807424 0.0325825475 0.1229378507 -0.1445753723 2781 1311867811.4141869545 0.0660118014 0.0295840179 0.0660118014 0.0046854602 0.0288820000 260767034 95654136 760807424 0.0322841778 0.1243303642 -0.1445313096 2782 1311867811.4464430809 0.0662451684 0.0295971959 0.0662451684 0.0046846777 0.0288750000 260770562 95654136 760807424 0.0318843946 0.1250396818 -0.1454162747 2783 1311867811.4788289070 0.0667915419 0.0296105607 0.0667915419 0.0046842983 0.0289590000 260774290 95654136 760807424 0.0314942487 0.1263618320 -0.1455309242 2784 1311867811.5141620636 0.0680898875 0.0296243823 0.0680898875 0.0046857999 0.0289750000 260946086 95654136 760807424 0.0320596024 0.1293564439 -0.1452458799 2785 1311867811.5465340614 0.0678945705 0.0296381239 0.0680898875 0.0046861109 0.0319570000 260949814 95654136 760807424 0.0327581614 0.1298803687 -0.1449527889 2786 1311867811.5787150860 0.0681543350 0.0296519488 0.0681543350 0.0046878826 0.0281270000 260951486 95654136 760807424 0.0317457207 0.1306632012 -0.1473736018 2787 1311867811.6143789291 0.0698703453 0.0296663795 0.0698703453 0.0046878981 0.0281600000 260955214 95654136 760807424 0.0297881439 0.1326963454 -0.1478615403 2788 1311867811.6465210915 0.0664939061 0.0296795888 0.0698703453 0.0046951265 0.0281300000 260958742 95654136 760807424 0.0322271399 0.1299552172 -0.1462515444 2789 1311867811.6790111065 0.0655665621 0.0296924561 0.0698703453 0.0046961540 0.0281790000 260960558 95654136 760807424 0.0352510735 0.1297515333 -0.1448456794 2790 1311867811.7141160965 0.0655889213 0.0297053223 0.0698703453 0.0046960606 0.0279720000 260964142 95654136 760807424 0.0349810906 0.1301236153 -0.1462212801 2791 1311867811.7471590042 0.0659829080 0.0297183203 0.0698703453 0.0046966093 0.0287820000 260966070 95654136 760807424 0.0338518173 0.1303475946 -0.1472454518 2792 1311867811.7787630558 0.0644578487 0.0297307628 0.0698703453 0.0046964376 0.0280750000 260969542 95654136 760807424 0.0327579118 0.1286515892 -0.1482974589 2793 1311867811.8140239716 0.0644082204 0.0297431787 0.0698703453 0.0046956142 0.0311910000 260973326 95654136 760807424 0.0319040604 0.1283895075 -0.1483703852 2794 1311867811.8467700481 0.0635373592 0.0297552740 0.0698703453 0.0046951252 0.0280750000 260974998 95654136 760807424 0.0329494439 0.1278179735 -0.1480117589 2795 1311867811.8873019218 0.0623072684 0.0297669205 0.0698703453 0.0046944519 0.0280690000 260978894 95654136 760807424 0.0337023325 0.1267547905 -0.1486428529 2796 1311867811.9162950516 0.0641513839 0.0297792182 0.0698703453 0.0046939266 0.0279880000 260982198 95654136 760807424 0.0324256048 0.1284158081 -0.1500423849 2797 1311867811.9480459690 0.0641049817 0.0297914905 0.0698703453 0.0046933537 0.0330750000 261154726 95654136 760807424 0.0320440046 0.1281198263 -0.1492081136 2798 1311867811.9825990200 0.0637068301 0.0298036118 0.0698703453 0.0046926524 0.0280740000 261158310 95654136 760807424 0.0322654136 0.1277362257 -0.1495368183 2799 1311867812.0155920982 0.0640925616 0.0298158623 0.0698703453 0.0046920085 0.0280820000 261160182 95654136 760807424 0.0327432156 0.1281849444 -0.1491457075 2800 1311867812.0471529961 0.0632018372 0.0298277858 0.0698703453 0.0046913731 0.0280930000 261163654 95654136 760807424 0.0318177789 0.1270461231 -0.1501229405 2801 1311867812.0860528946 0.0653142855 0.0298404550 0.0698703453 0.0046909464 0.0325220000 261167550 95654136 760807424 0.0312039666 0.1289378256 -0.1491711289 2802 1311867812.1176469326 0.0643413365 0.0298527680 0.0698703453 0.0046903629 0.0316000000 261169222 95654136 760807424 0.0310818963 0.1278165132 -0.1495957822 2803 1311867812.1501319408 0.0640310273 0.0298649614 0.0698703453 0.0046897729 0.0281050000 261172838 95654136 760807424 0.0309389643 0.1274908930 -0.1507585198 2804 1311867812.1841530800 0.0633054003 0.0298768874 0.0698703453 0.0046890933 0.0280410000 261174622 95654136 760807424 0.0322417431 0.1273473054 -0.1504244953 2805 1311867812.2161788940 0.0619245134 0.0298883126 0.0698703453 0.0046937917 0.0280410000 261178294 95654136 760807424 0.0327303708 0.1269742101 -0.1501154751 2806 1311867812.2469139099 0.0611119904 0.0298994401 0.0698703453 0.0046931558 0.0280570000 261181710 95654136 760807424 0.0329215042 0.1265690923 -0.1508859396 2807 1311867812.2830879688 0.0622912310 0.0299109797 0.0698703453 0.0047015635 0.0281300000 261183750 95654136 760807424 0.0313108452 0.1266870499 -0.1507814676 2808 1311867812.3143959045 0.0625557452 0.0299226053 0.0698703453 0.0047094601 0.0323160000 261187110 95654136 760807424 0.0315139331 0.1279025227 -0.1494078487 2809 1311867812.3466560841 0.0615594089 0.0299338680 0.0698703453 0.0047086897 0.0280890000 261189038 95654136 760807424 0.0330236182 0.1274770051 -0.1490508616 2810 1311867812.3833289146 0.0610624179 0.0299449458 0.0698703453 0.0047081549 0.0282380000 261192678 95654136 760807424 0.0316860788 0.1266445071 -0.1493464559 2811 1311867812.4177269936 0.0614079721 0.0299561386 0.0698703453 0.0047073433 0.0281080000 261196406 95654136 760807424 0.0320977829 0.1270731688 -0.1487505287 2812 1311867812.4586019516 0.0612087622 0.0299672526 0.0698703453 0.0047067178 0.0281170000 261198302 95654136 760807424 0.0338079035 0.1275516152 -0.1486515552 2813 1311867812.4830911160 0.0597678497 0.0299778465 0.0698703453 0.0047062138 0.0280380000 261372054 95654136 760807424 0.0346682966 0.1264486611 -0.1496534944 2814 1311867812.5157220364 0.0607908219 0.0299887964 0.0698703453 0.0047087784 0.0285440000 261375470 95654136 760807424 0.0346764997 0.1273133308 -0.1488545090 2815 1311867812.5469310284 0.0610136464 0.0299998177 0.0698703453 0.0047080195 0.0282530000 261377342 95654136 760807424 0.0351328254 0.1276637465 -0.1492057592 2816 1311867812.5857439041 0.0605736412 0.0300106748 0.0698703453 0.0047074613 0.0316950000 261380982 95654136 760807424 0.0363342427 0.1277745515 -0.1496859789 2817 1311867812.6147639751 0.0602802858 0.0300214202 0.0698703453 0.0047067185 0.0280960000 261382742 95654136 760807424 0.0371888652 0.1278979778 -0.1502498984 2818 1311867812.6462490559 0.0599211715 0.0300320304 0.0698703453 0.0047066495 0.0280740000 261386270 95654136 760807424 0.0371700749 0.1278333515 -0.1507941335 2819 1311867812.6821310520 0.0596797504 0.0300425476 0.0698703453 0.0047062352 0.0279210000 261390054 95654136 760807424 0.0375283472 0.1278115958 -0.1508134156 2820 1311867812.7141439915 0.0598219931 0.0300531076 0.0698703453 0.0047058111 0.0281040000 261391670 95654136 760807424 0.0374331661 0.1282108426 -0.1510834247 2821 1311867812.7468860149 0.0591597930 0.0300634255 0.0698703453 0.0047051079 0.0280410000 261395398 95654136 760807424 0.0377064049 0.1278976649 -0.1515331864 2822 1311867812.7839629650 0.0585560799 0.0300735221 0.0698703453 0.0047045623 0.0280460000 261397238 95654136 760807424 0.0370097980 0.1272566617 -0.1510294527 2823 1311867812.8143351078 0.0590084605 0.0300837718 0.0698703453 0.0047058976 0.0282650000 261400798 95654136 760807424 0.0364590473 0.1275488883 -0.1514334530 2824 1311867812.8463029861 0.0583680384 0.0300937875 0.0698703453 0.0047053692 0.0417400000 261404326 95654136 760807424 0.0372092426 0.1274479628 -0.1513726562 2825 1311867812.8841478825 0.0582395755 0.0301037506 0.0698703453 0.0047096739 0.0289850000 261406366 95654136 760807424 0.0363049433 0.1279315352 -0.1524192989 2826 1311867812.9142088890 0.0569715239 0.0301132580 0.0698703453 0.0047092713 0.0281410000 261409726 95654136 760807424 0.0354530662 0.1267522722 -0.1526671797 2827 1311867812.9470400810 0.0551023707 0.0301220974 0.0698703453 0.0047089881 0.0281390000 261411654 95654136 760807424 0.0352941938 0.1252781302 -0.1528302133 2828 1311867812.9833469391 0.0585495718 0.0301321496 0.0698703453 0.0047102080 0.0280720000 261415182 95654136 760807424 0.0337652564 0.1289652139 -0.1523585320 2829 1311867813.0143780708 0.0575097613 0.0301418270 0.0698703453 0.0047146986 0.0286810000 261418854 95654136 760807424 0.0328636169 0.1287115812 -0.1522189975 2830 1311867813.0462698936 0.0580620915 0.0301516929 0.0698703453 0.0047208921 0.0290780000 261420526 95654136 760807424 0.0322036184 0.1287022978 -0.1512921005 2831 1311867813.0825068951 0.0582892857 0.0301616320 0.0698703453 0.0047263249 0.0291840000 261424366 95654136 760807424 0.0324323364 0.1300936043 -0.1505273432 2832 1311867813.1142160892 0.0588624552 0.0301717664 0.0698703453 0.0047313457 0.0290540000 261427838 95654136 760807424 0.0320426635 0.1306261569 -0.1501295418 2833 1311867813.1504809856 0.0571786799 0.0301812994 0.0698703453 0.0047323471 0.0290170000 261599858 95654136 760807424 0.0319695882 0.1289961934 -0.1498157233 2834 1311867813.1829130650 0.0576722957 0.0301909998 0.0698703453 0.0047318954 0.0290390000 261603386 95654136 760807424 0.0332004279 0.1305023134 -0.1500455141 2835 1311867813.2166841030 0.0577916130 0.0302007355 0.0698703453 0.0047323577 0.0290220000 261605258 95654136 760807424 0.0327064432 0.1312464327 -0.1504460424 2836 1311867813.2536849976 0.0566641912 0.0302100668 0.0698703453 0.0047339255 0.0292260000 261608842 95654136 760807424 0.0322660021 0.1302298903 -0.1509799957 2837 1311867813.2831010818 0.0562379546 0.0302192412 0.0698703453 0.0047405056 0.0281820000 261612458 95654136 760807424 0.0313604660 0.1304462552 -0.1504670233 2838 1311867813.3142321110 0.0567478240 0.0302285888 0.0698703453 0.0047415205 0.0280950000 261614130 95654136 760807424 0.0303935930 0.1314436644 -0.1510900855 2839 1311867813.3517169952 0.0542784408 0.0302370601 0.0698703453 0.0047667043 0.0404900000 261617914 95654136 760807424 0.0304481760 0.1288834959 -0.1518047154 2840 1311867813.3851261139 0.0535338596 0.0302452632 0.0698703453 0.0047661046 0.0281790000 261619642 95654136 760807424 0.0314561501 0.1289934069 -0.1513340473 2841 1311867813.4148280621 0.0528955646 0.0302532358 0.0698703453 0.0047803165 0.0281420000 261623202 95654136 760807424 0.0318478644 0.1299902797 -0.1523287147 2842 1311867813.4501829147 0.0540757366 0.0302616181 0.0698703453 0.0047939930 0.0280280000 261626730 95654136 760807424 0.0312467609 0.1309234798 -0.1523105949 2843 1311867813.4843769073 0.0558993444 0.0302706360 0.0698703453 0.0047947298 0.0280510000 261628714 95654136 760807424 0.0314520337 0.1334028393 -0.1510002017 2844 1311867813.5152790546 0.0562200956 0.0302797602 0.0698703453 0.0048012500 0.0281290000 261632130 95654136 760807424 0.0310193896 0.1349404454 -0.1506995708 2845 1311867813.5519089699 0.0575049482 0.0302893297 0.0698703453 0.0048053187 0.0281250000 261634114 95654136 760807424 0.0299650319 0.1369797885 -0.1494867355 2846 1311867813.5863409042 0.0566295944 0.0302985849 0.0698703453 0.0048049929 0.0280970000 261637642 95654136 760807424 0.0302769709 0.1370074451 -0.1500975043 2847 1311867813.6168019772 0.0565274730 0.0303077977 0.0698703453 0.0048225234 0.0288650000 261641258 95654136 760807424 0.0306447670 0.1371672004 -0.1500696242 2848 1311867813.6515810490 0.0565425903 0.0303170094 0.0698703453 0.0048224053 0.0317980000 261642986 95654136 760807424 0.0302532371 0.1378512681 -0.1493203044 2849 1311867813.6860060692 0.0563496612 0.0303261469 0.0698703453 0.0048222725 0.0281240000 261646714 95654136 760807424 0.0303254724 0.1383738220 -0.1493902057 2850 1311867813.7184169292 0.0562991947 0.0303352602 0.0698703453 0.0048215005 0.0281890000 261650186 95654136 760807424 0.0315816328 0.1394682974 -0.1495195776 2851 1311867813.7506020069 0.0553099923 0.0303440202 0.0698703453 0.0048210670 0.0282140000 261652058 95654136 760807424 0.0326754488 0.1395569146 -0.1500875205 2852 1311867813.7827889919 0.0556028187 0.0303528767 0.0698703453 0.0048203007 0.0280960000 261655586 95654136 760807424 0.0320748426 0.1402832121 -0.1501810253 2853 1311867813.8147668839 0.0560707301 0.0303618910 0.0698703453 0.0048195126 0.0383020000 261657346 95654136 760807424 0.0334056355 0.1419094652 -0.1500067115 2854 1311867813.8517930508 0.0559963286 0.0303708730 0.0698703453 0.0048189835 0.0281580000 261829966 95654136 760807424 0.0333468057 0.1425549984 -0.1500050575 2855 1311867813.8838069439 0.0557147861 0.0303797500 0.0698703453 0.0048192590 0.0281600000 261833582 95654136 760807424 0.0341510139 0.1434192210 -0.1509228349 2856 1311867813.9144020081 0.0543126985 0.0303881299 0.0698703453 0.0048187706 0.0281150000 261835198 95654136 760807424 0.0343481116 0.1432284266 -0.1525329202 2857 1311867813.9523379803 0.0546807460 0.0303966327 0.0698703453 0.0048187453 0.0281510000 261839094 95654136 760807424 0.0344313718 0.1448269933 -0.1517913789 2858 1311867813.9825320244 0.0565015450 0.0304057667 0.0698703453 0.0048181580 0.0281800000 261840710 95654136 760807424 0.0338049270 0.1472844929 -0.1507957131 2859 1311867814.0155770779 0.0560603142 0.0304147400 0.0698703453 0.0048222741 0.0282140000 261844382 95654136 760807424 0.0353720076 0.1478221416 -0.1517416686 2860 1311867814.0528070927 0.0543520004 0.0304231096 0.0698703453 0.0048216784 0.0327680000 261848078 95654136 760807424 0.0369048156 0.1474438608 -0.1518052816 2861 1311867814.0849530697 0.0561780818 0.0304321117 0.0698703453 0.0048219639 0.0281300000 261849894 95654136 760807424 0.0369962938 0.1499963850 -0.1528746486 2862 1311867814.1153879166 0.0561581142 0.0304411005 0.0698703453 0.0048214407 0.0321700000 261853310 95654136 760807424 0.0374699235 0.1504083723 -0.1533522606 2863 1311867814.1526429653 0.0564953834 0.0304502009 0.0698703453 0.0048209715 0.0281500000 261855406 95654136 760807424 0.0393224731 0.1512548923 -0.1518256813 2864 1311867814.1845281124 0.0585622713 0.0304600166 0.0698703453 0.0048214127 0.0282850000 262028098 95654136 760807424 0.0381920971 0.1533971131 -0.1529845744 2865 1311867814.2153480053 0.0575497150 0.0304694719 0.0698703453 0.0048214157 0.0323950000 262031658 95654136 760807424 0.0384388007 0.1526270956 -0.1539369226 2866 1311867814.2520170212 0.0581522733 0.0304791310 0.0698703453 0.0048206142 0.0282150000 262033498 95654136 760807424 0.0376313031 0.1532462090 -0.1545677632 2867 1311867814.2834239006 0.0572136231 0.0304884559 0.0698703453 0.0048200416 0.0400830000 262037226 95654136 760807424 0.0380006582 0.1524085552 -0.1542319804 2868 1311867814.3181779385 0.0588813238 0.0304983558 0.0698703453 0.0048192449 0.0281660000 262040754 95654136 760807424 0.0393932909 0.1549273878 -0.1539766937 2869 1311867814.3510050774 0.0591673143 0.0305083484 0.0698703453 0.0048203320 0.0280850000 262042570 95654136 760807424 0.0384642482 0.1550883353 -0.1553560644 2870 1311867814.3861339092 0.0598097071 0.0305185580 0.0698703453 0.0048198596 0.0281190000 262046154 95654136 760807424 0.0381099880 0.1561881602 -0.1562092155 2871 1311867814.4182898998 0.0610506423 0.0305291926 0.0698703453 0.0048203843 0.0281310000 262048026 95654136 760807424 0.0382903107 0.1580519229 -0.1558354646 2872 1311867814.4512650967 0.0600576550 0.0305394741 0.0698703453 0.0048199354 0.0318860000 262051554 95654136 760807424 0.0382078364 0.1576545388 -0.1567011029 2873 1311867814.4847788811 0.0604899302 0.0305498989 0.0698703453 0.0048194109 0.0280450000 262224814 95654136 760807424 0.0371204689 0.1579870582 -0.1566518992 2874 1311867814.5201790333 0.0604622848 0.0305603069 0.0698703453 0.0048274898 0.0281280000 262226598 95654136 760807424 0.0357527658 0.1586012244 -0.1571487784 2875 1311867814.5517210960 0.0592291728 0.0305702786 0.0698703453 0.0048272043 0.0281650000 262230270 95654136 760807424 0.0363012999 0.1577325910 -0.1572931707 2876 1311867814.5848219395 0.0595763102 0.0305803642 0.0698703453 0.0048264128 0.0322270000 262231886 95654136 760807424 0.0349019542 0.1579086334 -0.1577711850 2877 1311867814.6200098991 0.0589362420 0.0305902202 0.0698703453 0.0048261573 0.0317430000 262235614 95654136 760807424 0.0348545015 0.1577993780 -0.1590101421 2878 1311867814.6503028870 0.0580468588 0.0305997604 0.0698703453 0.0048253855 0.0281250000 262239086 95654136 760807424 0.0332343876 0.1569202989 -0.1579920352 2879 1311867814.6833140850 0.0583157986 0.0306093874 0.0698703453 0.0048245958 0.0317060000 262240958 95654136 760807424 0.0321808085 0.1576293558 -0.1570158303 2880 1311867814.7211821079 0.0580296814 0.0306189083 0.0698703453 0.0048241437 0.0289750000 262244598 95654136 760807424 0.0323680751 0.1586255729 -0.1562617570 2881 1311867814.7502319813 0.0574378334 0.0306282172 0.0698703453 0.0048238689 0.0378500000 262246414 95654136 760807424 0.0329327546 0.1588414609 -0.1568092555 2882 1311867814.7828900814 0.0578994341 0.0306376798 0.0698703453 0.0048236039 0.0282340000 262249886 95654136 760807424 0.0332585685 0.1600957364 -0.1558038443 2883 1311867814.8186480999 0.0576010197 0.0306470323 0.0698703453 0.0048232663 0.0281240000 262253670 95654136 760807424 0.0349145122 0.1610064507 -0.1544456631 2884 1311867814.8526010513 0.0594931617 0.0306570345 0.0698703453 0.0048225078 0.0281770000 262255398 95654136 760807424 0.0346806273 0.1634334624 -0.1536866128 2885 1311867814.8852329254 0.0605341867 0.0306673905 0.0698703453 0.0048222565 0.0281380000 262259070 95654136 760807424 0.0341488607 0.1651965082 -0.1543429047 2886 1311867814.9202771187 0.0608663522 0.0306778544 0.0698703453 0.0048220448 0.0324980000 262262654 95654136 760807424 0.0331930518 0.1660356373 -0.1553651839 2887 1311867814.9503459930 0.0607256666 0.0306882624 0.0698703453 0.0048217371 0.0280870000 262264470 95654136 760807424 0.0339333527 0.1665792316 -0.1539324969 2888 1311867814.9839959145 0.0618144870 0.0306990402 0.0698703453 0.0048239516 0.0322830000 262267998 95654136 760807424 0.0344774649 0.1685748100 -0.1536207646 2889 1311867815.0193099976 0.0610805228 0.0307095565 0.0698703453 0.0048249185 0.0281880000 262269870 95654136 760807424 0.0340048373 0.1675795615 -0.1535953283 2890 1311867815.0509970188 0.0624527037 0.0307205402 0.0698703453 0.0048241668 0.0282580000 262273286 95654136 760807424 0.0350233018 0.1698125601 -0.1525669694 2891 1311867815.0835149288 0.0630303770 0.0307317163 0.0698703453 0.0048240054 0.0331420000 262447178 95654136 760807424 0.0383858345 0.1715250164 -0.1514318436 2892 1311867815.1192519665 0.0644812882 0.0307433862 0.0698703453 0.0048237361 0.0282860000 262448962 95654136 760807424 0.0376405008 0.1732241362 -0.1513846070 2893 1311867815.1505639553 0.0647332966 0.0307551353 0.0698703453 0.0048231815 0.0283860000 262452578 95654136 760807424 0.0381525867 0.1737014502 -0.1508980989 2894 1311867815.1827230453 0.0631941184 0.0307663443 0.0698703453 0.0048229006 0.0282940000 262454306 95654136 760807424 0.0403866097 0.1729661226 -0.1511061043 2895 1311867815.2192549706 0.0632807687 0.0307775755 0.0698703453 0.0048248450 0.0282290000 262458090 95654136 760807424 0.0417624786 0.1738747805 -0.1521065384 2896 1311867815.2503280640 0.0633290410 0.0307888157 0.0698703453 0.0048251173 0.0318810000 262461506 95654136 760807424 0.0416977927 0.1742127389 -0.1525419205 2897 1311867815.2826719284 0.0619827174 0.0307995833 0.0698703453 0.0048244720 0.0326850000 262463434 95654136 760807424 0.0443007536 0.1737809479 -0.1524908990 2898 1311867815.3188140392 0.0606658757 0.0308098892 0.0698703453 0.0048245109 0.0281920000 262467018 95654136 760807424 0.0452936105 0.1730854213 -0.1533456594 2899 1311867815.3506569862 0.0612730086 0.0308203973 0.0698703453 0.0048237628 0.0283250000 262638442 95654136 760807424 0.0439990386 0.1737681329 -0.1542788446 2900 1311867815.3841490746 0.0611492619 0.0308308555 0.0698703453 0.0048233339 0.0283090000 262641970 95654136 760807424 0.0466073528 0.1744083762 -0.1534436941 2901 1311867815.4187209606 0.0593616292 0.0308406903 0.0698703453 0.0048233450 0.0283900000 262645754 95654136 760807424 0.0476035401 0.1734671146 -0.1549771428 2902 1311867815.4505259991 0.0605687164 0.0308509343 0.0698703453 0.0048229725 0.0283210000 262647370 95654136 760807424 0.0460899509 0.1747554690 -0.1543232054 2903 1311867815.4827210903 0.0591582172 0.0308606854 0.0698703453 0.0048224272 0.0323330000 262651098 95654136 760807424 0.0471591428 0.1741296798 -0.1529676169 2904 1311867815.5188379288 0.0582837537 0.0308701286 0.0698703453 0.0048219833 0.0282790000 262654682 95654136 760807424 0.0458175354 0.1734814644 -0.1530927122 2905 1311867815.5508639812 0.0583811849 0.0308795988 0.0698703453 0.0048211767 0.0318820000 262656498 95654136 760807424 0.0447292328 0.1736360043 -0.1531563550 2906 1311867815.5879790783 0.0588813238 0.0308892347 0.0698703453 0.0048211700 0.0283120000 262660138 95654136 760807424 0.0464402586 0.1748219430 -0.1502966136 2907 1311867815.6201279163 0.0612361394 0.0308996739 0.0698703453 0.0048239546 0.0283080000 262662010 95654136 760807424 0.0458201021 0.1772627383 -0.1492965817 2908 1311867815.6522359848 0.0638600290 0.0309110083 0.0698703453 0.0048232036 0.0400490000 262665538 95654136 760807424 0.0455124713 0.1801379919 -0.1501310170 2909 1311867815.6869289875 0.0629846305 0.0309220339 0.0698703453 0.0048246227 0.0284000000 262669266 95654136 760807424 0.0459951870 0.1790366173 -0.1479738653 2910 1311867815.7186810970 0.0655056983 0.0309339183 0.0698703453 0.0048302725 0.0337680000 262670994 95654136 760807424 0.0453049876 0.1816430986 -0.1479058266 2911 1311867815.7527859211 0.0666909963 0.0309462018 0.0698703453 0.0048427760 0.0282760000 262674666 95654136 760807424 0.0439294279 0.1835525930 -0.1467782259 2912 1311867815.7881309986 0.0663679689 0.0309583659 0.0698703453 0.0048428391 0.0283040000 262676450 95654136 760807424 0.0447536968 0.1834397912 -0.1461055279 2913 1311867815.8185119629 0.0686333776 0.0309712993 0.0698703453 0.0048586692 0.0287290000 262680010 95654136 760807424 0.0442596003 0.1849271357 -0.1463393271 2914 1311867815.8516321182 0.0667684227 0.0309835838 0.0698703453 0.0048586831 0.0283530000 262683538 95654136 760807424 0.0458436124 0.1835777014 -0.1462849379 2915 1311867815.8881559372 0.0665935427 0.0309957999 0.0698703453 0.0048580834 0.0284330000 262685578 95654136 760807424 0.0484218374 0.1844244748 -0.1452918947 2916 1311867815.9183700085 0.0686272085 0.0310087050 0.0698703453 0.0048582582 0.0283500000 262688938 95654136 760807424 0.0466614664 0.1862012595 -0.1443549097 2917 1311867815.9544029236 0.0666010305 0.0310209067 0.0698703453 0.0048589555 0.0286310000 262861158 95654136 760807424 0.0486473292 0.1849753261 -0.1448733658 2918 1311867815.9880459309 0.0658961684 0.0310328585 0.0698703453 0.0048636043 0.0327160000 262864686 95654136 760807424 0.0497163497 0.1845284551 -0.1444151551 2919 1311867816.0232369900 0.0658490583 0.0310447859 0.0698703453 0.0048668829 0.0284300000 262868470 95654136 760807424 0.0507261194 0.1854698658 -0.1446662843 2920 1311867816.0513160229 0.0664024949 0.0310568947 0.0698703453 0.0048660694 0.0283690000 262869974 95654136 760807424 0.0523852967 0.1867828965 -0.1436582506 2921 1311867816.0872139931 0.0682994425 0.0310696447 0.0698703453 0.0048666207 0.0283750000 262873814 95654136 760807424 0.0528227724 0.1892582625 -0.1432964355 2922 1311867816.1192660332 0.0689876303 0.0310826214 0.0698703453 0.0048665029 0.0283710000 262877230 95654136 760807424 0.0528144948 0.1906339824 -0.1441298425 2923 1311867816.1530499458 0.0700658485 0.0310959581 0.0700658485 0.0048662658 0.0320320000 262879046 95654136 760807424 0.0512229092 0.1920135021 -0.1443285942 2924 1311867816.1877670288 0.0700732917 0.0311092883 0.0700732917 0.0048669597 0.0324560000 262882630 95654136 760807424 0.0527155995 0.1928239912 -0.1438352466 2925 1311867816.2185130119 0.0680585280 0.0311219205 0.0700732917 0.0048674342 0.0284170000 262884502 95654136 760807424 0.0543084890 0.1915146858 -0.1443861723 2926 1311867816.2509930134 0.0660151243 0.0311338457 0.0700732917 0.0048684035 0.0283770000 262887918 95654136 760807424 0.0545820333 0.1902478784 -0.1456182599 2927 1311867816.2875878811 0.0658004358 0.0311456894 0.0700732917 0.0048684532 0.0284930000 262891702 95654136 760807424 0.0559802800 0.1904012263 -0.1444953978 2928 1311867816.3221759796 0.0669004545 0.0311579008 0.0700732917 0.0048692701 0.0284430000 262893486 95654136 760807424 0.0565202609 0.1914348602 -0.1435839981 2929 1311867816.3515660763 0.0656654835 0.0311696821 0.0700732917 0.0048700787 0.0284520000 262897046 95654136 760807424 0.0556365438 0.1895469576 -0.1433770955 2930 1311867816.3902490139 0.0664800406 0.0311817334 0.0700732917 0.0048698483 0.0283710000 262898886 95654136 760807424 0.0567632169 0.1902002096 -0.1441777349 2931 1311867816.4188189507 0.0679549649 0.0311942797 0.0700732917 0.0048695632 0.0284020000 262902502 95654136 760807424 0.0555211157 0.1911902875 -0.1457150877 2932 1311867816.4527490139 0.0700071901 0.0312075174 0.0700732917 0.0048702355 0.0284300000 262906030 95654136 760807424 0.0573666655 0.1931181401 -0.1440712363 2933 1311867816.4875969887 0.0701304674 0.0312207881 0.0701304674 0.0048703740 0.0284200000 262907958 95654136 760807424 0.0557338148 0.1928938329 -0.1452210099 2934 1311867816.5199189186 0.0708958581 0.0312343106 0.0708958581 0.0048703550 0.0284180000 262911374 95654136 760807424 0.0551248528 0.1932357997 -0.1456051916 2935 1311867816.5529119968 0.0718482509 0.0312481484 0.0718482509 0.0048722248 0.0284570000 262913358 95654136 760807424 0.0537296794 0.1931237429 -0.1453809142 2936 1311867816.5888628960 0.0718375295 0.0312619732 0.0718482509 0.0048714765 0.0326780000 262916942 95654136 760807424 0.0547010005 0.1928438544 -0.1451710761 2937 1311867816.6194050312 0.0729763061 0.0312761762 0.0729763061 0.0048714252 0.0285280000 262920558 95654136 760807424 0.0551672056 0.1938359588 -0.1450065225 2938 1311867816.6509261131 0.0727980584 0.0312903089 0.0729763061 0.0048708139 0.0284270000 262922174 95654136 760807424 0.0541028865 0.1930653304 -0.1455010921 2939 1311867816.6893680096 0.0738712624 0.0313047972 0.0738712624 0.0048711934 0.0322640000 262926070 95654136 760807424 0.0541583002 0.1938173920 -0.1457045972 2940 1311867816.7204029560 0.0727793872 0.0313189042 0.0738712624 0.0048718238 0.0284040000 262929430 95654136 760807424 0.0524803065 0.1922122836 -0.1465464085 2941 1311867816.7523219585 0.0720043927 0.0313327381 0.0738712624 0.0048711094 0.0285110000 262931302 95654136 760807424 0.0509368256 0.1908716261 -0.1475270689 2942 1311867816.7867000103 0.0729221255 0.0313468745 0.0738712624 0.0048705407 0.0322090000 262934830 95654136 760807424 0.0502129570 0.1910662353 -0.1462465525 2943 1311867816.8192241192 0.0739223287 0.0313613412 0.0739223287 0.0048698802 0.0284950000 262936702 95654136 760807424 0.0492616668 0.1912531257 -0.1459501386 2944 1311867816.8584229946 0.0731191933 0.0313755252 0.0739223287 0.0048695320 0.0282780000 262940398 95654136 760807424 0.0490762256 0.1895178556 -0.1472186744 2945 1311867816.8891038895 0.0722113773 0.0313893914 0.0739223287 0.0048689092 0.0284480000 262943958 95654136 760807424 0.0483594276 0.1878839284 -0.1477497667 2946 1311867816.9194529057 0.0724987686 0.0314033457 0.0739223287 0.0048791989 0.0285280000 262945630 95654136 760807424 0.0485329814 0.1882628649 -0.1470579654 2947 1311867816.9566609859 0.0712970123 0.0314168827 0.0739223287 0.0048818047 0.0382370000 262949302 95654136 760807424 0.0458023623 0.1866565794 -0.1491847932 2948 1311867816.9880828857 0.0715624616 0.0314305006 0.0739223287 0.0048995239 0.0286440000 262950974 95654136 760807424 0.0442776307 0.1852746010 -0.1503735334 2949 1311867817.0196158886 0.0700178444 0.0314435855 0.0739223287 0.0048998328 0.0285380000 262954646 95654136 760807424 0.0464176312 0.1838900000 -0.1508135200 2950 1311867817.0547220707 0.0692292526 0.0314563942 0.0739223287 0.0049003693 0.0284450000 262958174 95654136 760807424 0.0462659448 0.1828404516 -0.1519955248 2951 1311867817.0868639946 0.0698472708 0.0314694037 0.0739223287 0.0049001939 0.0285390000 262960046 95654136 760807424 0.0446665697 0.1827155203 -0.1524536610 2952 1311867817.1189420223 0.0676148683 0.0314816481 0.0739223287 0.0049007204 0.0285620000 262963574 95654136 760807424 0.0449735560 0.1798983216 -0.1529736519 2953 1311867817.1549699306 0.0669520423 0.0314936597 0.0739223287 0.0049001200 0.0285450000 262965558 95654136 760807424 0.0447398350 0.1787817180 -0.1536158323 2954 1311867817.1863970757 0.0674320012 0.0315058257 0.0739223287 0.0049001803 0.0286030000 262968974 95654136 760807424 0.0451564528 0.1788614541 -0.1529798806 2955 1311867817.2202200890 0.0666757226 0.0315177275 0.0739223287 0.0048995541 0.0284860000 262972702 95654136 760807424 0.0457536355 0.1775435209 -0.1518090218 2956 1311867817.2567460537 0.0672065392 0.0315298009 0.0739223287 0.0048996660 0.0285290000 262974486 95654136 760807424 0.0464653932 0.1771013737 -0.1525240093 2957 1311867817.2865970135 0.0662159622 0.0315415311 0.0739223287 0.0048992732 0.0285460000 262978102 95654136 760807424 0.0462900177 0.1751699150 -0.1531507671 2958 1311867817.3192870617 0.0652780086 0.0315529362 0.0739223287 0.0048987206 0.0294620000 262981630 95654136 760807424 0.0458138250 0.1731814891 -0.1532797217 2959 1311867817.3578689098 0.0649982840 0.0315642392 0.0739223287 0.0049001116 0.0286760000 262983670 95654136 760807424 0.0452781953 0.1712773144 -0.1548009962 2960 1311867817.3868360519 0.0637929589 0.0315751272 0.0739223287 0.0049001715 0.0286580000 262987030 95654136 760807424 0.0440404825 0.1690126061 -0.1560210735 2961 1311867817.4206850529 0.0638947561 0.0315860423 0.0739223287 0.0048995529 0.0286960000 262988958 95654136 760807424 0.0438295417 0.1679527611 -0.1556497365 2962 1311867817.4551830292 0.0639230162 0.0315969596 0.0739223287 0.0048993960 0.0415560000 262992486 95654136 760807424 0.0425810255 0.1667625010 -0.1561825871 2963 1311867817.4888920784 0.0632235035 0.0316076334 0.0739223287 0.0048993443 0.0286880000 262996270 95654136 760807424 0.0429074094 0.1650667936 -0.1559904516 2964 1311867817.5194959641 0.0629680902 0.0316182139 0.0739223287 0.0048988250 0.0286110000 263167738 95654136 760807424 0.0435328521 0.1639478505 -0.1560196131 2965 1311867817.5576219559 0.0626169518 0.0316286688 0.0739223287 0.0048992564 0.0288220000 263171634 95654136 760807424 0.0431891456 0.1622780114 -0.1576535702 2966 1311867817.5864789486 0.0623713546 0.0316390338 0.0739223287 0.0048985871 0.0288440000 263173194 95654136 760807424 0.0437329337 0.1611165702 -0.1579991281 2967 1311867817.6205849648 0.0627566800 0.0316495217 0.0739223287 0.0048981440 0.0288070000 263176922 95654136 760807424 0.0416982770 0.1601413786 -0.1582789123 2968 1311867817.6566040516 0.0633000433 0.0316601857 0.0739223287 0.0048974192 0.0286190000 263180506 95654136 760807424 0.0415229350 0.1594277918 -0.1577729136 2969 1311867817.6880049706 0.0622271635 0.0316704810 0.0739223287 0.0048970610 0.0409480000 263182378 95654136 760807424 0.0409610607 0.1572140008 -0.1580520868 2970 1311867817.7194509506 0.0617750809 0.0316806173 0.0739223287 0.0048963007 0.0287600000 263185906 95654136 760807424 0.0396802872 0.1555306464 -0.1587165743 2971 1311867817.7552740574 0.0609506406 0.0316904692 0.0739223287 0.0048971871 0.0287960000 263187778 95654136 760807424 0.0401266888 0.1533236355 -0.1581163406 2972 1311867817.7872710228 0.0610641353 0.0317003526 0.0739223287 0.0048984262 0.0323320000 263191306 95654136 760807424 0.0406243950 0.1526000053 -0.1577726007 2973 1311867817.8201289177 0.0621534735 0.0317105959 0.0739223287 0.0048986507 0.0331390000 263195034 95654136 760807424 0.0381904840 0.1520690918 -0.1595112681 2974 1311867817.8596370220 0.0618910342 0.0317207440 0.0739223287 0.0049005136 0.0288920000 263196930 95654136 760807424 0.0369626284 0.1501358747 -0.1592408270 2975 1311867817.8866479397 0.0617888272 0.0317308509 0.0739223287 0.0049006465 0.0322220000 263200434 95654136 760807424 0.0377228037 0.1495696306 -0.1586626321 2976 1311867817.9203889370 0.0614908822 0.0317408509 0.0739223287 0.0049013435 0.0321710000 263203962 95654136 760807424 0.0373572446 0.1484100074 -0.1596289426 2977 1311867817.9569509029 0.0612774529 0.0317507725 0.0739223287 0.0049011545 0.0288170000 263205946 95654136 760807424 0.0364728346 0.1476285309 -0.1597161591 2978 1311867817.9865961075 0.0617760085 0.0317608548 0.0739223287 0.0049010000 0.0287820000 263209362 95654136 760807424 0.0369988717 0.1472101510 -0.1593748033 2979 1311867818.0255188942 0.0609509461 0.0317706535 0.0739223287 0.0049010359 0.0297620000 263211402 95654136 760807424 0.0362267941 0.1456098557 -0.1600366235 2980 1311867818.0579230785 0.0610312223 0.0317804724 0.0739223287 0.0049010990 0.0287920000 263214930 95654136 760807424 0.0370660126 0.1455024183 -0.1597769111 2981 1311867818.0892961025 0.0597714782 0.0317898623 0.0739223287 0.0049005515 0.0286960000 263389610 95654136 760807424 0.0375394747 0.1440330297 -0.1603069603 2982 1311867818.1228859425 0.0600817278 0.0317993498 0.0739223287 0.0049038177 0.0288870000 263391394 95654136 760807424 0.0374540016 0.1428412944 -0.1616216302 2983 1311867818.1594460011 0.0594833195 0.0318086304 0.0739223287 0.0049036867 0.0329480000 263395122 95654136 760807424 0.0370835513 0.1417000145 -0.1614572704 2984 1311867818.1912620068 0.0572649091 0.0318171613 0.0739223287 0.0049158113 0.0422510000 263396850 95654136 760807424 0.0374344960 0.1400095969 -0.1614263356 2985 1311867818.2233390808 0.0576186292 0.0318258050 0.0739223287 0.0049208636 0.0288700000 263400578 95654136 760807424 0.0369160175 0.1390119046 -0.1626283377 2986 1311867818.2556240559 0.0578388311 0.0318345167 0.0739223287 0.0049223429 0.0287600000 263403994 95654136 760807424 0.0367294438 0.1383424252 -0.1631274074 2987 1311867818.2891340256 0.0569015704 0.0318429087 0.0739223287 0.0049241010 0.0287720000 263405922 95654136 760807424 0.0380061232 0.1374032050 -0.1622525305 2988 1311867818.3256890774 0.0574594848 0.0318514819 0.0739223287 0.0049235431 0.0287870000 263409506 95654136 760807424 0.0366231538 0.1370133460 -0.1631110460 2989 1311867818.3582971096 0.0578622147 0.0318601840 0.0739223287 0.0049229642 0.0291320000 263411434 95654136 760807424 0.0364932008 0.1369002908 -0.1635739803 2990 1311867818.3892099857 0.0566741228 0.0318684830 0.0739223287 0.0049225184 0.0290070000 263414906 95654136 760807424 0.0379342400 0.1355706155 -0.1633911878 2991 1311867818.4233601093 0.0555736274 0.0318764085 0.0739223287 0.0049223978 0.0340400000 263418634 95654136 760807424 0.0385433510 0.1338855475 -0.1641034037 2992 1311867818.4555370808 0.0557082184 0.0318843737 0.0739223287 0.0049222731 0.0287870000 263420250 95654136 760807424 0.0375986956 0.1333861500 -0.1654578596 2993 1311867818.4896349907 0.0545052141 0.0318919316 0.0739223287 0.0049218846 0.0333300000 263424034 95654136 760807424 0.0375954323 0.1316395104 -0.1651388258 2994 1311867818.5246019363 0.0533805043 0.0318991088 0.0739223287 0.0049223218 0.0330260000 263427562 95654136 760807424 0.0390183330 0.1302279383 -0.1657259613 2995 1311867818.5566370487 0.0533751883 0.0319062794 0.0739223287 0.0049222577 0.0291590000 263429434 95654136 760807424 0.0378903188 0.1301935464 -0.1666811705 2996 1311867818.5892300606 0.0521797538 0.0319130463 0.0739223287 0.0049252054 0.0289390000 263603714 95654136 760807424 0.0369824357 0.1277637929 -0.1671383679 2997 1311867818.6233239174 0.0514142737 0.0319195532 0.0739223287 0.0049247240 0.0289410000 263605642 95654136 760807424 0.0368957371 0.1266285181 -0.1674224585 2998 1311867818.6555750370 0.0524457917 0.0319263999 0.0739223287 0.0049249610 0.0409090000 263609058 95654136 760807424 0.0364515297 0.1270104796 -0.1671711355 2999 1311867818.6877410412 0.0519997701 0.0319330932 0.0739223287 0.0049249286 0.0290290000 263612786 95654136 760807424 0.0364525206 0.1259125620 -0.1671825647 3000 1311867818.7238090038 0.0528419130 0.0319400628 0.0739223287 0.0049244651 0.0289190000 263614514 95654136 760807424 0.0359825566 0.1261752546 -0.1667507291 3001 1311867818.7561779022 0.0529902466 0.0319470772 0.0739223287 0.0049241488 0.0288920000 263618242 95654136 760807424 0.0347972363 0.1259766817 -0.1669162363 3002 1311867818.7870090008 0.0521772765 0.0319538161 0.0739223287 0.0049239520 0.0289420000 263619858 95654136 760807424 0.0350046232 0.1248941645 -0.1665870696 3003 1311867818.8250839710 0.0519713573 0.0319604820 0.0739223287 0.0049272694 0.0287750000 263623642 95654136 760807424 0.0339390635 0.1245704889 -0.1663148105 3004 1311867818.8546340466 0.0525739379 0.0319673440 0.0739223287 0.0049276062 0.0289110000 263796442 95654136 760807424 0.0330965817 0.1243782341 -0.1656019390 3005 1311867818.8872439861 0.0525486991 0.0319741930 0.0739223287 0.0049369350 0.0290560000 263798426 95654136 760807424 0.0324364044 0.1229019761 -0.1651597917 3006 1311867818.9249579906 0.0515436567 0.0319807031 0.0739223287 0.0049373703 0.0289130000 263802066 95654136 760807424 0.0316991806 0.1207342148 -0.1659049541 3007 1311867818.9544699192 0.0519737415 0.0319873520 0.0739223287 0.0049395419 0.0290080000 263803826 95654136 760807424 0.0309390966 0.1198040843 -0.1654976755 3008 1311867818.9864790440 0.0530199297 0.0319943442 0.0739223287 0.0049415631 0.0290300000 263807298 95654136 760807424 0.0315013528 0.1201757640 -0.1648268253 3009 1311867819.0252439976 0.0528946258 0.0320012901 0.0739223287 0.0049422033 0.0290630000 263811194 95654136 760807424 0.0307007860 0.1192799211 -0.1653871387 3010 1311867819.0550930500 0.0517306253 0.0320078447 0.0739223287 0.0049566397 0.0290940000 263812810 95654136 760807424 0.0301249418 0.1157723442 -0.1657382697 3011 1311867819.0875039101 0.0511336289 0.0320141967 0.0739223287 0.0049594988 0.0294840000 263986566 95654136 760807424 0.0295225121 0.1145580038 -0.1661749333 3012 1311867819.1251850128 0.0525981002 0.0320210306 0.0739223287 0.0049729508 0.0291740000 263990150 95654136 760807424 0.0278591253 0.1146628484 -0.1666876972 3013 1311867819.1578950882 0.0515315868 0.0320275061 0.0739223287 0.0049729352 0.0400780000 263992078 95654136 760807424 0.0270692222 0.1120655313 -0.1668884307 3014 1311867819.1891999245 0.0506593324 0.0320336879 0.0739223287 0.0049732417 0.0292320000 263995550 95654136 760807424 0.0268758368 0.1096850559 -0.1668699533 3015 1311867819.2251279354 0.0517693087 0.0320402337 0.0739223287 0.0049734894 0.0290150000 263997478 95654136 760807424 0.0268211085 0.1088294387 -0.1667116582 3016 1311867819.2586779594 0.0523464307 0.0320469665 0.0739223287 0.0049752180 0.0289260000 264001006 95654136 760807424 0.0264596567 0.1083898991 -0.1671156436 3017 1311867819.2937591076 0.0524438620 0.0320537271 0.0739223287 0.0049746038 0.0288890000 264175746 95654136 760807424 0.0261306278 0.1074432582 -0.1673473120 3018 1311867819.3250200748 0.0528882034 0.0320606305 0.0739223287 0.0049738489 0.0290010000 264177418 95654136 760807424 0.0243186988 0.1064783856 -0.1680149287 3019 1311867819.3568780422 0.0531270616 0.0320676085 0.0739223287 0.0049733010 0.0291350000 264181090 95654136 760807424 0.0237043351 0.1060644984 -0.1686376184 3020 1311867819.3930859566 0.0541519746 0.0320749212 0.0739223287 0.0049761173 0.0289470000 264182874 95654136 760807424 0.0237887260 0.1059493721 -0.1683328152 3021 1311867819.4237139225 0.0542721041 0.0320822688 0.0739223287 0.0049758478 0.0289430000 264186546 95654136 760807424 0.0221367311 0.1052503139 -0.1686522067 3022 1311867819.4571580887 0.0563451722 0.0320902976 0.0739223287 0.0049758438 0.0331020000 264190018 95654136 760807424 0.0211319886 0.1066164151 -0.1684112251 3023 1311867819.4921460152 0.0552745424 0.0320979669 0.0739223287 0.0049764230 0.0290200000 264191946 95654136 760807424 0.0229332838 0.1055311188 -0.1670819223 3024 1311867819.5226500034 0.0557325371 0.0321057825 0.0739223287 0.0049775975 0.0335000000 264195418 95654136 760807424 0.0235274527 0.1058511734 -0.1669327468 3025 1311867819.5550689697 0.0564076863 0.0321138162 0.0739223287 0.0049770891 0.0290190000 264197234 95654136 760807424 0.0208273064 0.1057516485 -0.1680697203 3026 1311867819.5923891068 0.0554435849 0.0321215260 0.0739223287 0.0049780979 0.0290180000 264200930 95654136 760807424 0.0209377240 0.1042169929 -0.1672285348 3027 1311867819.6253750324 0.0576491877 0.0321299593 0.0739223287 0.0049774073 0.0290440000 264204602 95654136 760807424 0.0225254018 0.1059957817 -0.1657460928 3028 1311867819.6557610035 0.0602195933 0.0321392359 0.0739223287 0.0049783670 0.0290470000 264376534 95654136 760807424 0.0209018923 0.1079606190 -0.1659777015 3029 1311867819.6919729710 0.0592362471 0.0321481818 0.0739223287 0.0049788675 0.0289560000 264380318 95654136 760807424 0.0198853035 0.1059797257 -0.1666108519 3030 1311867819.7227339745 0.0568473451 0.0321563333 0.0739223287 0.0049788144 0.0290310000 264383790 95654136 760807424 0.0201472547 0.1029411182 -0.1658632904 3031 1311867819.7567169666 0.0601441450 0.0321655672 0.0739223287 0.0049821338 0.0332480000 264385718 95654136 760807424 0.0213277359 0.1061360314 -0.1651730537 3032 1311867819.7913908958 0.0599049702 0.0321747161 0.0739223287 0.0049827408 0.0291110000 264389246 95654136 760807424 0.0206222255 0.1052316278 -0.1659901887 3033 1311867819.8285260201 0.0555601716 0.0321824264 0.0739223287 0.0049837190 0.0290210000 264391230 95654136 760807424 0.0218029860 0.1002717614 -0.1656930894 3034 1311867819.8552229404 0.0556623153 0.0321901653 0.0739223287 0.0049880144 0.0291000000 264394534 95654136 760807424 0.0207293704 0.1002042666 -0.1665285379 3035 1311867819.8941109180 0.0587466210 0.0321989154 0.0739223287 0.0049877172 0.0290320000 264398486 95654136 760807424 0.0196033306 0.1027451903 -0.1663989127 3036 1311867819.9237871170 0.0560038164 0.0322067563 0.0739223287 0.0049877004 0.0289680000 264400046 95654136 760807424 0.0192473959 0.0993192196 -0.1658408344 3037 1311867819.9576539993 0.0561175793 0.0322146295 0.0739223287 0.0049876665 0.0290020000 264403774 95654136 760807424 0.0180780087 0.0984528214 -0.1660337597 3038 1311867819.9939079285 0.0592438951 0.0322235265 0.0739223287 0.0049885672 0.0289580000 264405614 95654136 760807424 0.0168537293 0.1012038291 -0.1661255062 3039 1311867820.0229809284 0.0553162880 0.0322311253 0.0739223287 0.0049900015 0.0289740000 264409174 95654136 760807424 0.0171578191 0.0968210399 -0.1655839384 3040 1311867820.0577530861 0.0546621978 0.0322385040 0.0739223287 0.0049893225 0.0289920000 264412702 95654136 760807424 0.0193338841 0.0966625586 -0.1656490266 3041 1311867820.0944790840 0.0547737405 0.0322459144 0.0739223287 0.0049886063 0.0289670000 264414686 95654136 760807424 0.0208472703 0.0971853733 -0.1653048545 3042 1311867820.1251690388 0.0532876588 0.0322528315 0.0739223287 0.0049893343 0.0340400000 264418102 95654136 760807424 0.0225566886 0.0956361964 -0.1646681875 3043 1311867820.1551020145 0.0516863093 0.0322592178 0.0739223287 0.0049892880 0.0290500000 264419974 95654136 760807424 0.0216475427 0.0935262665 -0.1646358520 3044 1311867820.1938860416 0.0530884378 0.0322660605 0.0739223287 0.0049893871 0.0298450000 264423614 95654136 760807424 0.0205397401 0.0944193676 -0.1650503576 3045 1311867820.2262499332 0.0522485487 0.0322726229 0.0739223287 0.0049895317 0.0290910000 264427286 95654136 760807424 0.0221232120 0.0938746557 -0.1649658084 3046 1311867820.2557370663 0.0487013347 0.0322780164 0.0739223287 0.0049894590 0.0396550000 264428846 95654136 760807424 0.0219793562 0.0897688568 -0.1646492481 3047 1311867820.2941820621 0.0486081168 0.0322833758 0.0739223287 0.0049891973 0.0290570000 264432798 95654136 760807424 0.0232943669 0.0891989246 -0.1646334678 3048 1311867820.3227488995 0.0484695472 0.0322886863 0.0739223287 0.0049884769 0.0290190000 264436158 95654136 760807424 0.0235137232 0.0886019394 -0.1641928703 3049 1311867820.3565030098 0.0472583212 0.0322935959 0.0739223287 0.0049878526 0.0392390000 264438030 95654136 760807424 0.0230266340 0.0865857601 -0.1639029086 3050 1311867820.3936169147 0.0496710166 0.0322992935 0.0739223287 0.0049879715 0.0291050000 264441670 95654136 760807424 0.0212401468 0.0877572894 -0.1639773399 3051 1311867820.4230690002 0.0484202392 0.0323045773 0.0739223287 0.0049876210 0.0297160000 264614142 95654136 760807424 0.0209756065 0.0858711153 -0.1640282422 3052 1311867820.4605870247 0.0476618186 0.0323096091 0.0739223287 0.0049872388 0.0300710000 264617726 95654136 760807424 0.0216305666 0.0846624151 -0.1635245681 3053 1311867820.4940779209 0.0487750471 0.0323150023 0.0739223287 0.0049870048 0.0300530000 264621454 95654136 760807424 0.0223098639 0.0857087225 -0.1638790518 3054 1311867820.5266289711 0.0484216996 0.0323202763 0.0739223287 0.0049863281 0.0305330000 264623182 95654136 760807424 0.0222583674 0.0848890990 -0.1640916914 3055 1311867820.5596110821 0.0482021011 0.0323254749 0.0739223287 0.0049858719 0.0301690000 264626854 95654136 760807424 0.0219940096 0.0843935087 -0.1645347774 3056 1311867820.5906820297 0.0499796458 0.0323312518 0.0739223287 0.0049851335 0.0300020000 264628470 95654136 760807424 0.0216903631 0.0857787430 -0.1644009799 3057 1311867820.6261150837 0.0514791533 0.0323375155 0.0739223287 0.0049848824 0.0301720000 264632254 95654136 760807424 0.0215802100 0.0869544968 -0.1636625975 3058 1311867820.6602840424 0.0494878180 0.0323431238 0.0739223287 0.0049843251 0.0290740000 264635726 95654136 760807424 0.0204465222 0.0841397941 -0.1631819010 3059 1311867820.6933140755 0.0497153960 0.0323488029 0.0739223287 0.0049837292 0.0291150000 264637710 95654136 760807424 0.0210151337 0.0841718242 -0.1629242897 3060 1311867820.7232019901 0.0511920750 0.0323549608 0.0739223287 0.0049832603 0.0291250000 264641126 95654136 760807424 0.0209164880 0.0852491409 -0.1626956910 3061 1311867820.7605569363 0.0502501503 0.0323608070 0.0739223287 0.0049837939 0.0290070000 264643110 95654136 760807424 0.0208953284 0.0836270303 -0.1613183618 3062 1311867820.7916440964 0.0506126918 0.0323667678 0.0739223287 0.0049835581 0.0290250000 264815730 95654136 760807424 0.0207964089 0.0836856589 -0.1614079028 3063 1311867820.8228490353 0.0531745441 0.0323735610 0.0739223287 0.0049829900 0.0333860000 264819458 95654136 760807424 0.0189195573 0.0855653435 -0.1614656299 3064 1311867820.8588171005 0.0496301576 0.0323791931 0.0739223287 0.0049847955 0.0289790000 264821242 95654136 760807424 0.0206946544 0.0817878693 -0.1611598134 3065 1311867820.8911399841 0.0498326011 0.0323848875 0.0739223287 0.0049841755 0.0292040000 264824858 95654136 760807424 0.0199150536 0.0815646872 -0.1609322727 3066 1311867820.9231750965 0.0502251945 0.0323907063 0.0739223287 0.0049838817 0.0289920000 264828330 95654136 760807424 0.0203428715 0.0818149745 -0.1609622240 3067 1311867820.9593999386 0.0496818386 0.0323963441 0.0739223287 0.0049834882 0.0291290000 264830370 95654136 760807424 0.0176113173 0.0803519413 -0.1616488993 3068 1311867820.9930229187 0.0493081473 0.0324018564 0.0739223287 0.0049830941 0.0321130000 264833898 95654136 760807424 0.0183389243 0.0801052526 -0.1610027701 3069 1311867821.0258319378 0.0512046218 0.0324079831 0.0739223287 0.0049858806 0.0290870000 264835658 95654136 760807424 0.0190482847 0.0823946595 -0.1604666710 3070 1311867821.0608170033 0.0517942570 0.0324142978 0.0739223287 0.0049856896 0.0405760000 264839242 95654136 760807424 0.0167877823 0.0820338875 -0.1602136344 3071 1311867821.0909409523 0.0500809364 0.0324200505 0.0739223287 0.0049857637 0.0292330000 264842858 95654136 760807424 0.0166460257 0.0802454650 -0.1598452628 3072 1311867821.1260650158 0.0533594564 0.0324268667 0.0739223287 0.0049883917 0.0333170000 264844586 95654136 760807424 0.0153370826 0.0835488886 -0.1591268927 3073 1311867821.1620008945 0.0532624014 0.0324336469 0.0739223287 0.0049902811 0.0291470000 264848314 95654136 760807424 0.0146499779 0.0829233378 -0.1589908004 3074 1311867821.1925799847 0.0499714315 0.0324393521 0.0739223287 0.0049919753 0.0291620000 264849986 95654136 760807424 0.0157189965 0.0793756321 -0.1579961181 3075 1311867821.2257659435 0.0509005338 0.0324453558 0.0739223287 0.0049916557 0.0293250000 264853658 95654136 760807424 0.0150149483 0.0797736794 -0.1579815596 3076 1311867821.2620539665 0.0501664765 0.0324511169 0.0739223287 0.0049913580 0.0300280000 264857242 95654136 760807424 0.0146508878 0.0783772022 -0.1587303728 3077 1311867821.2933909893 0.0463131778 0.0324556219 0.0739223287 0.0049910635 0.0419090000 264859114 95654136 760807424 0.0149243949 0.0740946084 -0.1585212946 3078 1311867821.3235690594 0.0483370982 0.0324607816 0.0739223287 0.0049915057 0.0296230000 265033242 95654136 760807424 0.0149452379 0.0759495199 -0.1581797600 3079 1311867821.3590209484 0.0493796356 0.0324662765 0.0739223287 0.0049909178 0.0291930000 265035226 95654136 760807424 0.0136384452 0.0761674047 -0.1587769091 3080 1311867821.3907248974 0.0459158607 0.0324706433 0.0739223287 0.0049915715 0.0294750000 265038586 95654136 760807424 0.0136829447 0.0720410720 -0.1588496715 3081 1311867821.4246149063 0.0465393402 0.0324752095 0.0739223287 0.0049918543 0.0292880000 265042314 95654136 760807424 0.0143334540 0.0724128261 -0.1588695347 3082 1311867821.4626159668 0.0483085737 0.0324803469 0.0739223287 0.0049911863 0.0292970000 265044210 95654136 760807424 0.0125496201 0.0732748136 -0.1593688428 3083 1311867821.4939169884 0.0474081114 0.0324851889 0.0739223287 0.0049905664 0.0292010000 265218354 95654136 760807424 0.0128866108 0.0719115958 -0.1590691209 3084 1311867821.5273780823 0.0468154512 0.0324898355 0.0739223287 0.0049907059 0.0331880000 265221882 95654236 760807424 0.0126792518 0.0710134730 -0.1592858881 3085 1311867821.5590820312 0.0505019724 0.0324956741 0.0739223287 0.0049919129 0.0293770000 265223754 95654236 760807424 0.0106023178 0.0740699843 -0.1596108228 3086 1311867821.5928409100 0.0497053675 0.0325012508 0.0739223287 0.0049919636 0.0297420000 265227170 95654236 760807424 0.0096106064 0.0727264434 -0.1589626372 3087 1311867821.6260631084 0.0495998561 0.0325067897 0.0739223287 0.0049914061 0.0334000000 265229042 95654236 760807424 0.0093883043 0.0724507719 -0.1584210247 3088 1311867821.6634659767 0.0517788753 0.0325130307 0.0739223287 0.0049952482 0.0292590000 265232850 95654236 760807424 0.0066763801 0.0741072446 -0.1584781557 3089 1311867821.6953229904 0.0509042479 0.0325189845 0.0739223287 0.0049945416 0.0332490000 265236466 95654236 760807424 0.0069379266 0.0730931982 -0.1575326324 3090 1311867821.7313649654 0.0536768101 0.0325258317 0.0739223287 0.0049938622 0.0290670000 265238250 95654236 760807424 0.0071347742 0.0757919475 -0.1572638303 3091 1311867821.7634460926 0.0549847335 0.0325330976 0.0739223287 0.0049931404 0.0443790000 265242058 95654236 760807424 0.0063285404 0.0767047778 -0.1572240293 3092 1311867821.7956120968 0.0524815172 0.0325395492 0.0739223287 0.0049927077 0.0293700000 265243618 95654236 760807424 0.0044742338 0.0732718855 -0.1564006358 3093 1311867821.8313920498 0.0527505204 0.0325460836 0.0739223287 0.0049921255 0.0292190000 265247402 95654236 760807424 0.0044422159 0.0731648430 -0.1572036743 3094 1311867821.8633379936 0.0540714301 0.0325530407 0.0739223287 0.0049924164 0.0291750000 265250818 95654236 760807424 0.0049876673 0.0745539293 -0.1569348872 3095 1311867821.8956110477 0.0517151169 0.0325592320 0.0739223287 0.0049916920 0.0292010000 265252746 95654236 760807424 0.0038110365 0.0713125467 -0.1564814597 3096 1311867821.9314410686 0.0513589866 0.0325653043 0.0739223287 0.0049909612 0.0293950000 265426794 95654236 760807424 0.0042848121 0.0703160092 -0.1567250043 3097 1311867821.9633870125 0.0511277281 0.0325712980 0.0739223287 0.0049902322 0.0404050000 265428722 95654236 760807424 0.0049506617 0.0695232823 -0.1576393992 3098 1311867821.9954171181 0.0479560867 0.0325762640 0.0739223287 0.0049897444 0.0293860000 265432194 95654236 760807424 0.0049964786 0.0656585470 -0.1576390713 3099 1311867822.0314009190 0.0485284664 0.0325814116 0.0739223287 0.0049891371 0.0330990000 265435922 95654236 760807424 0.0049724984 0.0656547397 -0.1580315679 3100 1311867822.0633769035 0.0512586609 0.0325874365 0.0739223287 0.0049888218 0.0291300000 265437650 95654236 760807424 0.0039576236 0.0678795725 -0.1584013104 3101 1311867822.0962209702 0.0510123558 0.0325933781 0.0739223287 0.0049880781 0.0291740000 265441266 95654236 760807424 0.0031656334 0.0673369318 -0.1583061516 3102 1311867822.1315379143 0.0515381880 0.0325994854 0.0739223287 0.0049877705 0.0291400000 265444850 95654236 760807424 0.0037806756 0.0674786791 -0.1581609249 3103 1311867822.1634409428 0.0528318956 0.0326060057 0.0739223287 0.0049871308 0.0290600000 265446778 95654236 760807424 0.0029470352 0.0686809048 -0.1579861939 3104 1311867822.1960899830 0.0543993041 0.0326130267 0.0739223287 0.0049865789 0.0332390000 265450194 95654236 760807424 0.0011895386 0.0695389807 -0.1574588567 3105 1311867822.2317450047 0.0533979721 0.0326197207 0.0739223287 0.0049859314 0.0336390000 265452178 95654236 760807424 0.0017594669 0.0682296380 -0.1567179561 3106 1311867822.2634150982 0.0546970889 0.0326268287 0.0739223287 0.0049874126 0.0301810000 265455706 95654236 760807424 0.0018483426 0.0694839209 -0.1560377479 3107 1311867822.2954349518 0.0566463247 0.0326345595 0.0739223287 0.0049886898 0.0292810000 265459322 95654236 760807424 0.0035110943 0.0714545399 -0.1563348323 3108 1311867822.3315870762 0.0542224459 0.0326415054 0.0739223287 0.0049881400 0.0291160000 265461106 95654236 760807424 0.0024390342 0.0683588684 -0.1570422798 3109 1311867822.3635189533 0.0533204265 0.0326481567 0.0739223287 0.0049874263 0.0292150000 265464834 95654236 760807424 0.0000084876 0.0666500852 -0.1570701450 3110 1311867822.3960089684 0.0550169498 0.0326553492 0.0739223287 0.0049868435 0.0291550000 265466450 95654236 760807424 0.0007677808 0.0683496892 -0.1570351124 3111 1311867822.4314260483 0.0545227192 0.0326623783 0.0739223287 0.0049861101 0.0404770000 265470234 95654236 760807424 0.0010603587 0.0675245076 -0.1557776481 3112 1311867822.4634740353 0.0540452264 0.0326692494 0.0739223287 0.0049853214 0.0293430000 265643314 95654236 760807424 0.0012293953 0.0666479766 -0.1556073725 3113 1311867822.4957718849 0.0537877455 0.0326760333 0.0739223287 0.0049848441 0.0332740000 265645130 95654236 760807424 -0.0010706295 0.0654809326 -0.1557634473 3114 1311867822.5315260887 0.0526453778 0.0326824461 0.0739223287 0.0049841224 0.0292200000 265648770 95654236 760807424 -0.0003917773 0.0636454672 -0.1545046270 3115 1311867822.5634500980 0.0517036505 0.0326885524 0.0739223287 0.0049835709 0.0291990000 265650642 95654236 760807424 0.0017363777 0.0621530451 -0.1540366113 3116 1311867822.5955328941 0.0519107692 0.0326947213 0.0739223287 0.0049828965 0.0292050000 265654114 95654236 760807424 0.0007599612 0.0603392906 -0.1541308165 3117 1311867822.6315131187 0.0524264686 0.0327010517 0.0739223287 0.0049822988 0.0300480000 265657898 95654236 760807424 0.0016812350 0.0590828843 -0.1555039734 3118 1311867822.6634640694 0.0515274294 0.0327070896 0.0739223287 0.0049821149 0.0341680000 265829770 95654236 760807424 0.0032235063 0.0574059971 -0.1561867297 3119 1311867822.6954870224 0.0511067323 0.0327129888 0.0739223287 0.0049813220 0.0291380000 265833442 95654236 760807424 0.0015726592 0.0557280555 -0.1572693288 3120 1311867822.7317390442 0.0542678759 0.0327198975 0.0739223287 0.0049809142 0.0292760000 265836970 95654236 760807424 0.0002580161 0.0579916947 -0.1582846045 3121 1311867822.7634871006 0.0531402826 0.0327264404 0.0739223287 0.0049809172 0.0327250000 265838842 95654236 760807424 0.0000745671 0.0562715493 -0.1580657959 3122 1311867822.7954308987 0.0532190241 0.0327330043 0.0739223287 0.0049804219 0.0293940000 265842314 95654236 760807424 -0.0019075690 0.0560755990 -0.1575024575 3123 1311867822.8314750195 0.0562195070 0.0327405248 0.0739223287 0.0049809324 0.0292050000 265844298 95654236 760807424 -0.0023494982 0.0593085214 -0.1586448401 3124 1311867822.8634629250 0.0542208701 0.0327474007 0.0739223287 0.0049817851 0.0292650000 265847770 95654236 760807424 -0.0028226648 0.0579484999 -0.1577380896 3125 1311867822.8955349922 0.0544154234 0.0327543345 0.0739223287 0.0049811488 0.0416450000 265851330 95654236 760807424 -0.0012669080 0.0587943085 -0.1568469107 3126 1311867822.9318330288 0.0548798218 0.0327614123 0.0739223287 0.0049809603 0.0335620000 265853170 95654236 760807424 -0.0030583069 0.0595191829 -0.1567663550 3127 1311867822.9635109901 0.0534389429 0.0327680249 0.0739223287 0.0049808609 0.0292450000 265856842 95654236 760807424 -0.0047000097 0.0577591993 -0.1559896618 3128 1311867822.9979970455 0.0517451726 0.0327740918 0.0739223287 0.0049809384 0.0292400000 265858626 95654236 760807424 -0.0047874828 0.0567814000 -0.1557869464 3129 1311867823.0344979763 0.0531810336 0.0327806137 0.0739223287 0.0049804395 0.0291960000 265862298 95654236 760807424 -0.0046123955 0.0585986227 -0.1553975195 3130 1311867823.0634639263 0.0524025187 0.0327868826 0.0739223287 0.0049799154 0.0293350000 265865658 95654236 760807424 -0.0062986678 0.0574769303 -0.1549461931 3131 1311867823.0971090794 0.0513442531 0.0327928096 0.0739223287 0.0049792824 0.0293760000 265867586 95654236 760807424 -0.0074139866 0.0563325994 -0.1549408436 3132 1311867823.1313869953 0.0498229638 0.0327982471 0.0739223287 0.0049794883 0.0293610000 265871114 95654236 760807424 -0.0067755464 0.0548616387 -0.1545229405 3133 1311867823.1635200977 0.0501742400 0.0328037932 0.0739223287 0.0049792737 0.0333240000 265872986 95654236 760807424 -0.0077109253 0.0546634942 -0.1541979313 3134 1311867823.1954131126 0.0515837818 0.0328097855 0.0739223287 0.0049827388 0.0291610000 265876458 95654236 760807424 -0.0093303705 0.0558795929 -0.1545654088 3135 1311867823.2316908836 0.0491036512 0.0328149829 0.0739223287 0.0049826721 0.0335120000 265880298 95654236 760807424 -0.0103867631 0.0531841964 -0.1541941166 3136 1311867823.2635869980 0.0493715741 0.0328202625 0.0739223287 0.0049873063 0.0293520000 265881970 95654236 760807424 -0.0106510669 0.0538574383 -0.1542173773 3137 1311867823.2955200672 0.0516932644 0.0328262787 0.0739223287 0.0049866764 0.0294620000 266055898 95654236 760807424 -0.0108972881 0.0560399964 -0.1548804790 3138 1311867823.3330919743 0.0483072102 0.0328312121 0.0739223287 0.0049868773 0.0302030000 266059538 95654236 760807424 -0.0127597777 0.0523199588 -0.1542896628 3139 1311867823.3635790348 0.0492282137 0.0328364357 0.0739223287 0.0049863361 0.0336620000 266061410 95654236 760807424 -0.0122739244 0.0535295345 -0.1546268314 3140 1311867823.3954129219 0.0517917275 0.0328424725 0.0739223287 0.0049859347 0.0295630000 266064826 95654236 760807424 -0.0116671240 0.0565543547 -0.1546014845 3141 1311867823.4318161011 0.0519811139 0.0328485656 0.0739223287 0.0049852841 0.0328690000 266066866 95654236 760807424 -0.0136546334 0.0566034988 -0.1539691240 3142 1311867823.4634220600 0.0527441166 0.0328548978 0.0739223287 0.0049889366 0.0293720000 266070338 95654236 760807424 -0.0177834723 0.0571113341 -0.1539156586 3143 1311867823.4969789982 0.0549687743 0.0328619337 0.0739223287 0.0049903200 0.0338560000 266074066 95654236 760807424 -0.0193186626 0.0590903275 -0.1537787467 3144 1311867823.5356218815 0.0537490360 0.0328685772 0.0739223287 0.0049895734 0.0294390000 266075850 95654236 760807424 -0.0189047549 0.0582995452 -0.1530814469 3145 1311867823.5636498928 0.0514151081 0.0328744743 0.0739223287 0.0049900320 0.0294640000 266079466 95654236 760807424 -0.0182450395 0.0561944805 -0.1526643634 3146 1311867823.5974569321 0.0525628068 0.0328807325 0.0739223287 0.0049893252 0.0294130000 266081194 95654236 760807424 -0.0199115891 0.0573617183 -0.1529551148 3147 1311867823.6316640377 0.0547334999 0.0328876765 0.0739223287 0.0050021908 0.0295850000 266084922 95654236 760807424 -0.0215470642 0.0600947440 -0.1530581266 3148 1311867823.6636750698 0.0517895631 0.0328936809 0.0739223287 0.0050069211 0.0335390000 266088394 95654236 760807424 -0.0212004036 0.0573318638 -0.1528811902 3149 1311867823.6956110001 0.0495454669 0.0328989689 0.0739223287 0.0050069349 0.0302590000 266090210 95654236 760807424 -0.0209607743 0.0554530993 -0.1517359763 3150 1311867823.7316160202 0.0487610400 0.0329040045 0.0739223287 0.0050062941 0.0294890000 266263462 95654236 760807424 -0.0203534756 0.0554618686 -0.1522873789 3151 1311867823.7635159492 0.0448697917 0.0329078019 0.0739223287 0.0050060490 0.0295390000 266265334 95654236 760807424 -0.0204286464 0.0516408719 -0.1513872147 3152 1311867823.7964189053 0.0445760898 0.0329115038 0.0739223287 0.0050053568 0.0295080000 266268806 95654236 760807424 -0.0191086642 0.0519147739 -0.1507606804 3153 1311867823.8316709995 0.0469078533 0.0329159428 0.0739223287 0.0050049219 0.0295350000 266272590 95654236 760807424 -0.0200341344 0.0543128885 -0.1504170746 3154 1311867823.8635869026 0.0489443876 0.0329210248 0.0739223287 0.0050043372 0.0295030000 266274262 95654236 760807424 -0.0177901164 0.0571514145 -0.1507862508 3155 1311867823.8993299007 0.0478648990 0.0329257614 0.0739223287 0.0050036197 0.0323820000 266277990 95654236 760807424 -0.0175429750 0.0563890226 -0.1497538090 3156 1311867823.9316000938 0.0482933745 0.0329306307 0.0739223287 0.0050114671 0.0295200000 266281518 95654236 760807424 -0.0168678723 0.0568781793 -0.1488829404 3157 1311867823.9639530182 0.0483780392 0.0329355238 0.0739223287 0.0050210434 0.0330980000 266283446 95654236 760807424 -0.0178145319 0.0575228892 -0.1489084661 3158 1311867823.9956440926 0.0491988696 0.0329406736 0.0739223287 0.0050215961 0.0295650000 266286806 95654236 760807424 -0.0184096750 0.0583607256 -0.1486208141 3159 1311867824.0315599442 0.0484023206 0.0329455681 0.0739223287 0.0050208035 0.0296760000 266288846 95654236 760807424 -0.0184105765 0.0577476695 -0.1478373259 3160 1311867824.0634789467 0.0498319790 0.0329509119 0.0739223287 0.0050213744 0.0296020000 266292318 95654236 760807424 -0.0190314390 0.0596674830 -0.1482475996 3161 1311867824.0966339111 0.0502150655 0.0329563735 0.0739223287 0.0050206460 0.0296450000 266295990 95654236 760807424 -0.0184777435 0.0604959540 -0.1480976492 3162 1311867824.1315801144 0.0483283475 0.0329612350 0.0739223287 0.0050218133 0.0295810000 266297774 95654236 760807424 -0.0189846065 0.0585886054 -0.1467135549 3163 1311867824.1636250019 0.0509687178 0.0329669282 0.0739223287 0.0050212579 0.0295620000 266301446 95654236 760807424 -0.0180731304 0.0616555773 -0.1475896984 3164 1311867824.1974411011 0.0515150875 0.0329727904 0.0739223287 0.0050204973 0.0297490000 266303174 95654236 760807424 -0.0180269461 0.0626876205 -0.1476684213 3165 1311867824.2314341068 0.0490301065 0.0329778638 0.0739223287 0.0050220817 0.0296880000 266306846 95654236 760807424 -0.0196058750 0.0601488836 -0.1457022130 3166 1311867824.2667160034 0.0504342467 0.0329833775 0.0739223287 0.0050213764 0.0296080000 266310430 95654236 760807424 -0.0200237501 0.0621644072 -0.1460373998 3167 1311867824.3015260696 0.0520053282 0.0329893838 0.0739223287 0.0050216395 0.0296780000 266312358 95654236 760807424 -0.0200786889 0.0647888482 -0.1464011818 3168 1311867824.3329520226 0.0495584011 0.0329946139 0.0739223287 0.0050218662 0.0296630000 266315886 95654236 760807424 -0.0197400544 0.0630691499 -0.1459043026 3169 1311867824.3655378819 0.0512283072 0.0330003677 0.0739223287 0.0050236190 0.0297200000 266487986 95654236 760807424 -0.0183180273 0.0656050071 -0.1458916068 3170 1311867824.3960471153 0.0505269691 0.0330058966 0.0739223287 0.0050229253 0.0331190000 266491346 95654236 760807424 -0.0182624236 0.0658440590 -0.1451360583 3171 1311867824.4315910339 0.0529875830 0.0330121980 0.0739223287 0.0050225533 0.0306590000 266495130 95654236 760807424 -0.0202041697 0.0695911646 -0.1440621167 3172 1311867824.4656479359 0.0552636571 0.0330192130 0.0739223287 0.0050218294 0.0333120000 266496914 95654236 760807424 -0.0200517792 0.0729894266 -0.1430201679 3173 1311867824.4978680611 0.0534402356 0.0330256488 0.0739223287 0.0050269985 0.0296990000 266500586 95654236 760807424 -0.0195739344 0.0721211657 -0.1405699700 3174 1311867824.5316801071 0.0516799353 0.0330315260 0.0739223287 0.0050266168 0.0338900000 266504058 95654236 760807424 -0.0173807330 0.0716918036 -0.1403199434 3175 1311867824.5658340454 0.0513232239 0.0330372872 0.0739223287 0.0050259605 0.0341110000 266506042 95654236 760807424 -0.0186961219 0.0720839277 -0.1394289881 3176 1311867824.5956490040 0.0486407802 0.0330422001 0.0739223287 0.0050252079 0.0299400000 266509402 95654236 760807424 -0.0195021126 0.0696204230 -0.1370220333 3177 1311867824.6318910122 0.0505678542 0.0330477166 0.0739223287 0.0050245359 0.0298130000 266682634 95654236 760807424 -0.0196015909 0.0723764151 -0.1373811364 3178 1311867824.6661880016 0.0486884713 0.0330526381 0.0739223287 0.0050246710 0.0298600000 266686106 95654236 760807424 -0.0192814190 0.0710914582 -0.1368202120 3179 1311867824.6979959011 0.0475329682 0.0330571931 0.0739223287 0.0050319121 0.0297460000 266689778 95654236 760807424 -0.0183760840 0.0706762075 -0.1362501532 3180 1311867824.7314980030 0.0478936210 0.0330618587 0.0739223287 0.0050374223 0.0423590000 266691394 95654236 760807424 -0.0193550587 0.0708980635 -0.1346982718 3181 1311867824.7639760971 0.0494930632 0.0330670241 0.0739223287 0.0050368581 0.0347820000 266695178 95654236 760807424 -0.0173344500 0.0731288046 -0.1349679232 3182 1311867824.7997510433 0.0481952913 0.0330717784 0.0739223287 0.0050371513 0.0297970000 266696850 95654236 760807424 -0.0163928457 0.0723939985 -0.1344517469 3183 1311867824.8315179348 0.0468784235 0.0330761160 0.0739223287 0.0050405149 0.0298720000 266700578 95654236 760807424 -0.0169514753 0.0707427040 -0.1332489997 3184 1311867824.8635060787 0.0479658581 0.0330807925 0.0739223287 0.0050404122 0.0299230000 266874482 95654236 760807424 -0.0171044338 0.0722892955 -0.1328436583 3185 1311867824.8995370865 0.0473164655 0.0330852621 0.0739223287 0.0050427030 0.0299990000 266876410 95654236 760807424 -0.0167096984 0.0719937608 -0.1318139881 3186 1311867824.9316530228 0.0460466556 0.0330893303 0.0739223287 0.0050420624 0.0338990000 266879938 95654236 760807424 -0.0157776326 0.0708536282 -0.1309106946 3187 1311867824.9636321068 0.0449752249 0.0330930598 0.0739223287 0.0050426874 0.0298740000 266881810 95654236 760807424 -0.0173039120 0.0696471855 -0.1293319017 3188 1311867824.9996089935 0.0447174236 0.0330967061 0.0739223287 0.0050446973 0.0298060000 266885450 95654236 760807424 -0.0193080194 0.0693697631 -0.1284355521 3189 1311867825.0316529274 0.0459372699 0.0331007326 0.0739223287 0.0050442620 0.0299010000 266889066 95654236 760807424 -0.0186623819 0.0704471990 -0.1281619370 3190 1311867825.0644180775 0.0465197079 0.0331049392 0.0739223287 0.0050439090 0.0298950000 266890682 95654236 760807424 -0.0188698657 0.0707945973 -0.1282804161 3191 1311867825.0997018814 0.0469543375 0.0331092793 0.0739223287 0.0050433113 0.0426120000 266894466 95654236 760807424 -0.0182141084 0.0712126568 -0.1289201826 3192 1311867825.1316909790 0.0437904559 0.0331126255 0.0739223287 0.0050426896 0.0299180000 266897994 95654236 760807424 -0.0214368142 0.0675183609 -0.1275613606 3193 1311867825.1636679173 0.0432152338 0.0331157895 0.0739223287 0.0050419339 0.0299700000 266899866 95654236 760807424 -0.0237363465 0.0664097369 -0.1269118935 3194 1311867825.1996359825 0.0475375578 0.0331203048 0.0739223287 0.0050415005 0.0338110000 266903394 95654236 760807424 -0.0245925933 0.0708698183 -0.1282732785 3195 1311867825.2316811085 0.0470213555 0.0331246557 0.0739223287 0.0050420833 0.0298900000 266905322 95654236 760807424 -0.0267618019 0.0699993297 -0.1276854426 3196 1311867825.2670049667 0.0457794853 0.0331286153 0.0739223287 0.0050415143 0.0300300000 266908906 95654236 760807424 -0.0283839945 0.0682101697 -0.1262053102 3197 1311867825.2996079922 0.0479937904 0.0331332650 0.0739223287 0.0050409999 0.0300260000 266912634 95654236 760807424 -0.0284504704 0.0707437173 -0.1278920323 3198 1311867825.3316459656 0.0472400524 0.0331376761 0.0739223287 0.0050408703 0.0332670000 267084310 95654236 760807424 -0.0305430815 0.0702551901 -0.1279984862 3199 1311867825.3635549545 0.0461777374 0.0331417524 0.0739223287 0.0050401011 0.0299630000 267087982 95654236 760807424 -0.0320267566 0.0687278286 -0.1263578236 3200 1311867825.3995220661 0.0473077968 0.0331461793 0.0739223287 0.0050394560 0.0299160000 267089822 95654236 760807424 -0.0317070708 0.0702816993 -0.1275837570 3201 1311867825.4329199791 0.0474673249 0.0331506533 0.0739223287 0.0050399758 0.0299090000 267093494 95654236 760807424 -0.0328973532 0.0704883710 -0.1271763295 3202 1311867825.4655759335 0.0452217683 0.0331544231 0.0739223287 0.0050394519 0.0309300000 267096910 95654236 760807424 -0.0332082622 0.0680530071 -0.1256575286 3203 1311867825.4996039867 0.0457825996 0.0331583657 0.0739223287 0.0050387328 0.0301610000 267098782 95654236 760807424 -0.0327227153 0.0689834952 -0.1267223507 3204 1311867825.5338120461 0.0449776538 0.0331620547 0.0739223287 0.0050380464 0.0299920000 267102366 95654236 760807424 -0.0331313573 0.0685252100 -0.1270632595 3205 1311867825.5637319088 0.0442033224 0.0331654997 0.0739223287 0.0050381040 0.0411600000 267104182 95654236 760807424 -0.0343284495 0.0677740201 -0.1258399785 3206 1311867825.5995988846 0.0434617698 0.0331687112 0.0739223287 0.0050378825 0.0301890000 267107710 95654236 760807424 -0.0357278101 0.0670234263 -0.1255901456 3207 1311867825.6372098923 0.0442910343 0.0331721794 0.0739223287 0.0050373152 0.0300280000 267111550 95654236 760807424 -0.0372188725 0.0679649189 -0.1263469458 3208 1311867825.6636829376 0.0444938131 0.0331757086 0.0739223287 0.0050365660 0.0335220000 267113054 95654236 760807424 -0.0378220789 0.0682976544 -0.1265786737 3209 1311867825.6997060776 0.0440283939 0.0331790905 0.0739223287 0.0050368252 0.0301050000 267116838 95654236 760807424 -0.0399787836 0.0675277710 -0.1260565817 3210 1311867825.7345299721 0.0468804128 0.0331833588 0.0739223287 0.0050361542 0.0303180000 267120366 95654236 760807424 -0.0399157330 0.0707432479 -0.1265367270 3211 1311867825.7654349804 0.0455486700 0.0331872098 0.0739223287 0.0050355572 0.0300510000 267122182 95654236 760807424 -0.0392381549 0.0693611801 -0.1251548678 3212 1311867825.7998030186 0.0436210483 0.0331904581 0.0739223287 0.0050350247 0.0334200000 267125822 95654236 760807424 -0.0406054147 0.0669437498 -0.1253177226 3213 1311867825.8355960846 0.0444201007 0.0331939532 0.0739223287 0.0050346648 0.0300460000 267127806 95654236 760807424 -0.0408052988 0.0680463016 -0.1276512891 3214 1311867825.8656499386 0.0419354960 0.0331966730 0.0739223287 0.0050341210 0.0300400000 267131166 95654236 760807424 -0.0385539271 0.0659832135 -0.1277370900 3215 1311867825.8996019363 0.0409205221 0.0331990755 0.0739223287 0.0050334571 0.0300310000 267134950 95654236 760807424 -0.0395313054 0.0644450709 -0.1266491413 3216 1311867825.9338490963 0.0425315872 0.0332019774 0.0739223287 0.0050330338 0.0300030000 267136678 95654236 760807424 -0.0390943773 0.0665715337 -0.1284670681 3217 1311867825.9640550613 0.0425044447 0.0332048690 0.0739223287 0.0050324480 0.0299770000 267140294 95654236 760807424 -0.0404108018 0.0666186735 -0.1282736063 3218 1311867825.9996759892 0.0410739593 0.0332073144 0.0739223287 0.0050317416 0.0300410000 267142022 95654236 760807424 -0.0415733792 0.0648169070 -0.1272428483 3219 1311867826.0327920914 0.0440971181 0.0332106974 0.0739223287 0.0050310119 0.0426430000 267145750 95654236 760807424 -0.0410979390 0.0685420856 -0.1290578544 3220 1311867826.0636880398 0.0430499800 0.0332137530 0.0739223287 0.0050305407 0.0299860000 267149222 95654236 760807424 -0.0401641242 0.0681357086 -0.1295233071 3221 1311867826.1009249687 0.0408758186 0.0332161318 0.0739223287 0.0050298117 0.0300900000 267151206 95654236 760807424 -0.0409699380 0.0659572482 -0.1285159588 3222 1311867826.1333520412 0.0429122075 0.0332191412 0.0739223287 0.0050294118 0.0300570000 267154734 95654236 760807424 -0.0422908589 0.0681497902 -0.1290474236 3223 1311867826.1658940315 0.0443001688 0.0332225793 0.0739223287 0.0050286829 0.0301280000 267156606 95654236 760807424 -0.0424703024 0.0696684420 -0.1292829663 3224 1311867826.1998670101 0.0435921475 0.0332257956 0.0739223287 0.0050279554 0.0301690000 267160134 95654236 760807424 -0.0448248163 0.0681241900 -0.1273708344 3225 1311867826.2345190048 0.0452989563 0.0332295392 0.0739223287 0.0050281796 0.0300540000 267333478 95654236 760807424 -0.0464582518 0.0693749636 -0.1272628903 3226 1311867826.2638120651 0.0469082221 0.0332337794 0.0739223287 0.0050283492 0.0327290000 267335094 95654236 760807424 -0.0481730923 0.0704423785 -0.1272710115 3227 1311867826.3011031151 0.0465701483 0.0332379121 0.0739223287 0.0050284739 0.0300260000 267338822 95654236 760807424 -0.0499878228 0.0693858266 -0.1270122230 3228 1311867826.3321969509 0.0455418527 0.0332417238 0.0739223287 0.0050286843 0.0300420000 267342126 95654236 760807424 -0.0513094664 0.0679567531 -0.1281603426 3229 1311867826.3637990952 0.0468498059 0.0332459381 0.0739223287 0.0050289123 0.0302160000 267343998 95654236 760807424 -0.0515393838 0.0696705803 -0.1295611560 3230 1311867826.3997180462 0.0462608784 0.0332499675 0.0739223287 0.0050282378 0.0300710000 267347526 95654236 760807424 -0.0533872321 0.0683818534 -0.1291972101 3231 1311867826.4321830273 0.0448622331 0.0332535615 0.0739223287 0.0050278404 0.0301780000 267349454 95654236 760807424 -0.0526558682 0.0673445910 -0.1300919652 3232 1311867826.4641919136 0.0446444750 0.0332570859 0.0739223287 0.0050272377 0.0300430000 267352982 95654236 760807424 -0.0529513583 0.0673362613 -0.1306743920 3233 1311867826.5007300377 0.0441069715 0.0332604419 0.0739223287 0.0050265330 0.0421670000 267356710 95654236 760807424 -0.0529717915 0.0668908134 -0.1301514357 3234 1311867826.5320169926 0.0450303294 0.0332640813 0.0739223287 0.0050259659 0.0300560000 267358382 95654236 760807424 -0.0505888052 0.0690163523 -0.1306179315 3235 1311867826.5638980865 0.0470454879 0.0332683414 0.0739223287 0.0050253399 0.0300730000 267362110 95654236 760807424 -0.0483146012 0.0716123283 -0.1305337250 3236 1311867826.6006839275 0.0488008410 0.0332731413 0.0739223287 0.0050252710 0.0302190000 267363838 95654236 760807424 -0.0518957227 0.0725915581 -0.1299241930 3237 1311867826.6315999031 0.0506718606 0.0332785163 0.0739223287 0.0050248573 0.0301750000 267367454 95654236 760807424 -0.0531157367 0.0746656880 -0.1304365993 3238 1311867826.6638810635 0.0504277460 0.0332838125 0.0739223287 0.0050243839 0.0301200000 267370926 95654236 760807424 -0.0528744236 0.0744656548 -0.1310315877 3239 1311867826.6997959614 0.0513578467 0.0332893926 0.0739223287 0.0050236660 0.0300480000 267372854 95654236 760807424 -0.0536204726 0.0755620226 -0.1311997920 3240 1311867826.7349510193 0.0499134883 0.0332945235 0.0739223287 0.0050230019 0.0336150000 267376438 95654236 760807424 -0.0538007692 0.0736309960 -0.1297258586 3241 1311867826.7678439617 0.0491303019 0.0332994096 0.0739223287 0.0050222626 0.0301840000 267378254 95654236 760807424 -0.0542554036 0.0730746686 -0.1304642707 3242 1311867826.8019490242 0.0491437167 0.0333042968 0.0739223287 0.0050216106 0.0301210000 267381838 95654236 760807424 -0.0544604324 0.0724338293 -0.1296349764 3243 1311867826.8324790001 0.0488797948 0.0333090996 0.0739223287 0.0050231877 0.0311020000 267385454 95654236 760807424 -0.0557454675 0.0715762973 -0.1293672919 3244 1311867826.8646159172 0.0507132225 0.0333144646 0.0739223287 0.0050226659 0.0302440000 267387070 95654236 760807424 -0.0562247373 0.0732557476 -0.1296233237 3245 1311867826.9008219242 0.0498225428 0.0333195519 0.0739223287 0.0050231892 0.0300740000 267390854 95654236 760807424 -0.0562885813 0.0721752346 -0.1296438128 3246 1311867826.9319140911 0.0485465117 0.0333242429 0.0739223287 0.0050248045 0.0300780000 267394214 95654236 760807424 -0.0555261299 0.0711874589 -0.1299287826 3247 1311867826.9639439583 0.0463675782 0.0333282599 0.0739223287 0.0050266438 0.0334640000 267395974 95654236 760807424 -0.0535573848 0.0695620775 -0.1303348541 3248 1311867827.0083661079 0.0462853462 0.0333322492 0.0739223287 0.0050272295 0.0300930000 267399726 95654236 760807424 -0.0545582473 0.0694032013 -0.1307328194 3249 1311867827.0334970951 0.0454105884 0.0333359667 0.0739223287 0.0050265626 0.0301420000 267401374 95654236 760807424 -0.0538934134 0.0687673017 -0.1311428994 3250 1311867827.0653018951 0.0464227758 0.0333399934 0.0739223287 0.0050274655 0.0301280000 267404678 95654236 760807424 -0.0551631488 0.0696969628 -0.1321299225 3251 1311867827.0995759964 0.0449383184 0.0333435610 0.0739223287 0.0050284776 0.0302360000 267408294 95654236 760807424 -0.0533890463 0.0687852129 -0.1325461864 3252 1311867827.1319890022 0.0456865579 0.0333473566 0.0739223287 0.0050277952 0.0301380000 267409798 95654236 760807424 -0.0532911308 0.0696569160 -0.1328361332 3253 1311867827.1636219025 0.0452838950 0.0333510260 0.0739223287 0.0050276201 0.0301580000 267413526 95654236 760807424 -0.0548325554 0.0684946775 -0.1329983026 3254 1311867827.2006959915 0.0436275490 0.0333541841 0.0739223287 0.0050276107 0.0348050000 267415310 95654236 760807424 -0.0534385890 0.0674196184 -0.1344685853 3255 1311867827.2315700054 0.0449966975 0.0333577609 0.0739223287 0.0050271071 0.0302830000 267418870 95654236 760807424 -0.0525398515 0.0690776259 -0.1352005899 3256 1311867827.2656030655 0.0434857868 0.0333608715 0.0739223287 0.0050269867 0.0345410000 267422230 95654236 760807424 -0.0532847606 0.0674426332 -0.1338542998 3257 1311867827.2999110222 0.0457318164 0.0333646697 0.0739223287 0.0050282253 0.0302580000 267424214 95654236 760807424 -0.0535817072 0.0699116364 -0.1354600489 3258 1311867827.3331999779 0.0477246568 0.0333690773 0.0739223287 0.0050276358 0.0345410000 267427630 95654236 760807424 -0.0506460331 0.0730929151 -0.1361420453 3259 1311867827.3665180206 0.0436409228 0.0333722292 0.0739223287 0.0050275748 0.0344960000 267429502 95654236 760807424 -0.0499473996 0.0688631684 -0.1344844699 3260 1311867827.4023349285 0.0443408974 0.0333755938 0.0739223287 0.0050279745 0.0300990000 267433142 95654236 760807424 -0.0505090840 0.0695552304 -0.1354206800 3261 1311867827.4316511154 0.0453949720 0.0333792796 0.0739223287 0.0050272492 0.0302010000 267436702 95654236 760807424 -0.0519167446 0.0707036108 -0.1363197863 3262 1311867827.4660930634 0.0439054035 0.0333825065 0.0739223287 0.0050268571 0.0303470000 267438430 95654236 760807424 -0.0510999449 0.0694527775 -0.1347050518 3263 1311867827.5022308826 0.0451552421 0.0333861144 0.0739223287 0.0050268935 0.0300700000 267442270 95654236 760807424 -0.0528407134 0.0699621364 -0.1349171102 3264 1311867827.5346870422 0.0467118099 0.0333901970 0.0739223287 0.0050262829 0.0301920000 267445686 95654236 760807424 -0.0534709580 0.0716625825 -0.1368182898 3265 1311867827.5639040470 0.0445761867 0.0333936231 0.0739223287 0.0050256012 0.0310400000 267447558 95654236 760807424 -0.0544045977 0.0687301010 -0.1342897266 3266 1311867827.6014358997 0.0438014008 0.0333968098 0.0739223287 0.0050262723 0.0300640000 267451142 95654236 760807424 -0.0551031642 0.0678270310 -0.1348145902 3267 1311867827.6328499317 0.0448819809 0.0334003253 0.0739223287 0.0050259470 0.0301580000 267453014 95654236 760807424 -0.0549872406 0.0694350302 -0.1356567889 3268 1311867827.6636641026 0.0442015044 0.0334036304 0.0739223287 0.0050252021 0.0301260000 267456486 95654236 760807424 -0.0561504178 0.0683389381 -0.1345732212 3269 1311867827.7023649216 0.0457663760 0.0334074122 0.0739223287 0.0050247890 0.0301300000 267460326 95654236 760807424 -0.0553484447 0.0701688305 -0.1347098947 3270 1311867827.7343521118 0.0456981994 0.0334111709 0.0739223287 0.0050245824 0.0300860000 267461998 95654236 760807424 -0.0554657243 0.0705133304 -0.1355707943 3271 1311867827.7669301033 0.0456705689 0.0334149188 0.0739223287 0.0050249689 0.0301580000 267465614 95654236 760807424 -0.0566128790 0.0696549565 -0.1342015713 3272 1311867827.8077390194 0.0462073684 0.0334188285 0.0739223287 0.0050257846 0.0344270000 267467566 95654236 760807424 -0.0579915196 0.0700368583 -0.1336188316 3273 1311867827.8316879272 0.0496827550 0.0334237976 0.0739223287 0.0050262269 0.0304120000 267470958 95654236 760807424 -0.0580102690 0.0735731423 -0.1345675439 3274 1311867827.8644089699 0.0494455695 0.0334286912 0.0739223287 0.0050259163 0.0302820000 267474542 95654236 760807424 -0.0593268424 0.0727049559 -0.1338699907 3275 1311867827.9007999897 0.0493397750 0.0334335496 0.0739223287 0.0050292964 0.0351180000 267476414 95654236 760807424 -0.0598398596 0.0725620463 -0.1341737211 3276 1311867827.9316790104 0.0524819754 0.0334393641 0.0739223287 0.0050315978 0.0305460000 267479886 95654236 760807424 -0.0580229200 0.0762861744 -0.1353766024 3277 1311867827.9717168808 0.0502410419 0.0334444913 0.0739223287 0.0050330747 0.0302960000 267481926 95654236 760807424 -0.0582417510 0.0738296658 -0.1336401254 3278 1311867827.9999699593 0.0502897538 0.0334496301 0.0739223287 0.0050326131 0.0338730000 267485398 95654236 760807424 -0.0573986992 0.0740548596 -0.1341883391 3279 1311867828.0320069790 0.0525684208 0.0334554608 0.0739223287 0.0050322817 0.0303700000 267489014 95654236 760807424 -0.0568218678 0.0767233968 -0.1351018995 3280 1311867828.0711700916 0.0541927330 0.0334617832 0.0739223287 0.0050347278 0.0338490000 267490854 95654236 760807424 -0.0563597456 0.0781712681 -0.1346347183 3281 1311867828.1003229618 0.0550340004 0.0334683581 0.0739223287 0.0050341003 0.0304760000 267494526 95654236 760807424 -0.0568575449 0.0787500814 -0.1339569837 3282 1311867828.1317639351 0.0569475554 0.0334755120 0.0739223287 0.0050351770 0.0403230000 267497942 95654236 760807424 -0.0542477295 0.0813883767 -0.1350751072 3283 1311867828.1714239120 0.0554041527 0.0334821914 0.0739223287 0.0050353156 0.0303930000 267500038 95654236 760807424 -0.0550980493 0.0794202238 -0.1332733184 3284 1311867828.2080869675 0.0550413579 0.0334887563 0.0739223287 0.0050419770 0.0304640000 267503678 95654236 760807424 -0.0541817993 0.0795243308 -0.1324631423 3285 1311867828.2316999435 0.0572228879 0.0334959813 0.0739223287 0.0050434530 0.0303270000 267505270 95654236 760807424 -0.0526481494 0.0820049345 -0.1332880408 3286 1311867828.2725389004 0.0557425879 0.0335027515 0.0739223287 0.0050427210 0.0304070000 267508966 95654236 760807424 -0.0521364212 0.0804058313 -0.1313695163 3287 1311867828.3008439541 0.0568806045 0.0335098637 0.0739223287 0.0050434246 0.0304830000 267512582 95654236 760807424 -0.0518510118 0.0817379877 -0.1305974126 ================================================ FILE: icra2018_results/1080/violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:29:51 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /home/bruno/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 -nan 0.0134770000 208245864 95654128 750977024 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0590390489 0.0586455464 0.0590390489 0.0043609180 0.0401190000 220876758 95654128 760807424 -0.0046225134 -0.0003272689 -0.0017514409 3 1311867170.5264289379 0.0583505332 0.0585472087 0.0590390489 0.0042434848 0.0185880000 220880854 95654128 760807424 -0.0073903231 -0.0000792317 -0.0047243708 4 1311867170.5623490810 0.0573859438 0.0582568925 0.0590390489 0.0051500397 0.0190690000 220882626 95654128 760807424 -0.0073997155 0.0003928485 -0.0070953500 5 1311867170.5942170620 0.0574107245 0.0580876589 0.0590390489 0.0050078938 0.0178430000 220886978 95654128 760807424 -0.0100922957 -0.0012397963 -0.0084009636 6 1311867170.6260869503 0.0560944453 0.0577554566 0.0590390489 0.0047427619 0.0179850000 220889450 95654128 760807424 -0.0110081639 -0.0026097652 -0.0110545186 7 1311867170.6621398926 0.0553384721 0.0574101731 0.0590390489 0.0045572977 0.0180120000 220893090 95654128 760807424 -0.0127517171 -0.0052603381 -0.0126141608 8 1311867170.6942050457 0.0542543195 0.0570156914 0.0590390489 0.0044051995 0.0180030000 220896506 95654128 760807424 -0.0121891703 -0.0054281484 -0.0152042136 9 1311867170.7263879776 0.0546637475 0.0567543643 0.0590390489 0.0042259030 0.0180020000 220899982 95654128 760807424 -0.0151427621 -0.0068467772 -0.0162141081 10 1311867170.7620189190 0.0561912283 0.0566980507 0.0590390489 0.0040629438 0.0180280000 220905222 95654128 760807424 -0.0192913059 -0.0082850400 -0.0167284943 11 1311867170.7941920757 0.0564558953 0.0566760366 0.0590390489 0.0040313649 0.0180090000 220908582 95654128 760807424 -0.0204102285 -0.0107300542 -0.0180305950 12 1311867170.8262820244 0.0565391704 0.0566646311 0.0590390489 0.0040555570 0.0180410000 220910310 95654128 760807424 -0.0216279849 -0.0139274420 -0.0200612321 13 1311867170.8622210026 0.0554297715 0.0565696419 0.0590390489 0.0043118158 0.0219510000 220914358 95654128 760807424 -0.0204359479 -0.0159170739 -0.0232299287 14 1311867170.8943779469 0.0558725744 0.0565198514 0.0590390489 0.0042175128 0.0183510000 220917774 95654128 760807424 -0.0199496485 -0.0180622749 -0.0254245792 15 1311867170.9263520241 0.0557228923 0.0564667207 0.0590390489 0.0041556092 0.0180110000 220919502 95654128 760807424 -0.0189489443 -0.0204302687 -0.0282479562 16 1311867170.9621469975 0.0556361005 0.0564148070 0.0590390489 0.0041013596 0.0179910000 220923086 95654128 760807424 -0.0204986241 -0.0212311540 -0.0316743925 17 1311867170.9942629337 0.0547381714 0.0563161814 0.0590390489 0.0041524429 0.0181470000 221097822 95654128 760807424 -0.0192059651 -0.0227072854 -0.0353772342 18 1311867171.0262739658 0.0545263477 0.0562167462 0.0590390489 0.0040516388 0.0210120000 221104550 95654128 760807424 -0.0186726786 -0.0261201337 -0.0376239605 19 1311867171.0623519421 0.0542649068 0.0561140178 0.0590390489 0.0046496081 0.0181090000 221108134 95654128 760807424 -0.0196285509 -0.0289097987 -0.0404592790 20 1311867171.0942349434 0.0534053519 0.0559785845 0.0590390489 0.0046528721 0.0213060000 221109750 95654128 760807424 -0.0179294143 -0.0291688908 -0.0434426963 21 1311867171.1262509823 0.0533481613 0.0558533262 0.0590390489 0.0045514598 0.0210470000 221113478 95654128 760807424 -0.0200048480 -0.0315662436 -0.0453118011 22 1311867171.1622469425 0.0538891442 0.0557640452 0.0590390489 0.0049215445 0.0219270000 221117030 95654128 760807424 -0.0188148208 -0.0305615980 -0.0468629152 23 1311867171.1942689419 0.0519554727 0.0555984551 0.0590390489 0.0059261370 0.0192390000 221118630 95654128 760807424 -0.0136132985 -0.0295352489 -0.0488132574 24 1311867171.2262530327 0.0533620343 0.0555052709 0.0590390489 0.0062151615 0.0228350000 221122158 95654128 760807424 -0.0108982408 -0.0307443365 -0.0488661230 25 1311867171.2622439861 0.0525557920 0.0553872918 0.0590390489 0.0060940307 0.0183870000 221125942 95654128 760807424 -0.0060961153 -0.0284453370 -0.0512372740 26 1311867171.2943410873 0.0514977016 0.0552376921 0.0590390489 0.0060203218 0.0180500000 221127502 95654128 760807424 -0.0039204098 -0.0281723551 -0.0529367737 27 1311867171.3263869286 0.0526633486 0.0551423461 0.0590390489 0.0062852773 0.0180710000 221131030 95654128 760807424 -0.0033329180 -0.0285660475 -0.0530911870 28 1311867171.3622460365 0.0530760996 0.0550685516 0.0590390489 0.0062608684 0.0181580000 221134614 95654128 760807424 -0.0022073453 -0.0252446570 -0.0543850251 29 1311867171.3941431046 0.0540105328 0.0550320682 0.0590390489 0.0062017114 0.0180080000 221136430 95654128 760807424 -0.0041216449 -0.0230162777 -0.0555656739 30 1311867171.4262878895 0.0555227064 0.0550484228 0.0590390489 0.0062664526 0.0179710000 221139958 95654128 760807424 -0.0076778210 -0.0265567414 -0.0549822152 31 1311867171.4622440338 0.0551905595 0.0550530078 0.0590390489 0.0062805590 0.0179860000 221141742 95654128 760807424 -0.0064829057 -0.0252007879 -0.0578247160 32 1311867171.4944040775 0.0546005145 0.0550388674 0.0590390489 0.0061971359 0.0181260000 221145158 95654128 760807424 -0.0075039584 -0.0244516246 -0.0607038066 33 1311867171.5261778831 0.0564790145 0.0550825082 0.0590390489 0.0061751828 0.0180580000 221154758 95654128 760807424 -0.0096672233 -0.0243356153 -0.0604178980 34 1311867171.5622971058 0.0554681905 0.0550938518 0.0590390489 0.0061257835 0.0255600000 221162942 95654128 760807424 -0.0102386428 -0.0229408480 -0.0629336163 35 1311867171.5942931175 0.0539136231 0.0550601310 0.0590390489 0.0061151689 0.0185640000 221166358 95654128 760807424 -0.0091559244 -0.0245554466 -0.0643901974 36 1311867171.6263399124 0.0555068441 0.0550725397 0.0590390489 0.0060586165 0.0180630000 221169886 95654128 760807424 -0.0122672524 -0.0242989864 -0.0638681799 37 1311867171.6622560024 0.0564889275 0.0551108204 0.0590390489 0.0059893724 0.0180030000 221171870 95654128 760807424 -0.0141864177 -0.0229121707 -0.0642946959 38 1311867171.6943440437 0.0568313003 0.0551560962 0.0590390489 0.0060365289 0.0180630000 221175286 95654128 760807424 -0.0141563900 -0.0212547611 -0.0650971606 39 1311867171.7262439728 0.0567025989 0.0551957501 0.0590390489 0.0059589485 0.0187540000 221178814 95654128 760807424 -0.0175279938 -0.0227601696 -0.0653908923 40 1311867171.7621190548 0.0569068007 0.0552385264 0.0590390489 0.0058909903 0.0181390000 221180598 95654128 760807424 -0.0191608816 -0.0237961784 -0.0656126216 41 1311867171.7941710949 0.0565076023 0.0552694795 0.0590390489 0.0058541251 0.0211160000 221184198 95654128 760807424 -0.0210634954 -0.0248632040 -0.0665218607 42 1311867171.8262550831 0.0563637279 0.0552955330 0.0590390489 0.0057981482 0.0181290000 221185926 95654128 760807424 -0.0226109419 -0.0251009371 -0.0679218993 43 1311867171.8623590469 0.0561687537 0.0553158405 0.0590390489 0.0057668251 0.0181270000 221189510 95654128 760807424 -0.0263035558 -0.0273613334 -0.0683082268 44 1311867171.8944430351 0.0568310432 0.0553502769 0.0590390489 0.0059275043 0.0180940000 221192982 95654128 760807424 -0.0305834897 -0.0249929875 -0.0695648715 45 1311867171.9262220860 0.0567310862 0.0553809615 0.0590390489 0.0059069075 0.0214070000 221194854 95654128 760807424 -0.0340252481 -0.0260620508 -0.0696500093 46 1311867171.9624669552 0.0567913353 0.0554116218 0.0590390489 0.0058787582 0.0182620000 221198438 95654128 760807424 -0.0347772688 -0.0239567906 -0.0701387376 47 1311867171.9946711063 0.0564099364 0.0554328626 0.0590390489 0.0060289664 0.0180220000 221201910 95654128 760807424 -0.0385048948 -0.0248388592 -0.0699076131 48 1311867172.0262680054 0.0556713231 0.0554378305 0.0590390489 0.0060807869 0.0181150000 221203582 95654128 760807424 -0.0417202748 -0.0250678230 -0.0697225556 49 1311867172.0622880459 0.0561739020 0.0554528524 0.0590390489 0.0060375708 0.0181010000 221207366 95654128 760807424 -0.0450084694 -0.0242567956 -0.0683359131 50 1311867172.0941960812 0.0562476330 0.0554687480 0.0590390489 0.0060217712 0.0181260000 221210838 95654128 760807424 -0.0477274843 -0.0250364523 -0.0666563511 51 1311867172.1263689995 0.0563058630 0.0554851620 0.0590390489 0.0060283393 0.0181250000 221212510 95654128 760807424 -0.0520237535 -0.0259408392 -0.0656501800 52 1311867172.1623349190 0.0562233217 0.0554993574 0.0590390489 0.0060233454 0.0183740000 221216094 95654128 760807424 -0.0550720319 -0.0242309421 -0.0653860345 53 1311867172.1944270134 0.0556566641 0.0555023254 0.0590390489 0.0059915820 0.0286620000 221388682 95654128 760807424 -0.0575667545 -0.0249040537 -0.0647985786 54 1311867172.2264409065 0.0558710359 0.0555091534 0.0590390489 0.0060974981 0.0192240000 221392154 95654128 760807424 -0.0595621541 -0.0221599769 -0.0653319359 55 1311867172.2622280121 0.0561102666 0.0555200827 0.0590390489 0.0060671717 0.0218470000 221395738 95654128 760807424 -0.0609779432 -0.0194986127 -0.0648069754 56 1311867172.2944829464 0.0562159605 0.0555325091 0.0590390489 0.0060134205 0.0183810000 221397410 95654128 760807424 -0.0648277327 -0.0197276808 -0.0641748980 57 1311867172.3263380527 0.0561951734 0.0555441348 0.0590390489 0.0060422317 0.0182790000 221401082 95654128 760807424 -0.0700110719 -0.0179893002 -0.0644125417 58 1311867172.3624010086 0.0554503351 0.0555425176 0.0590390489 0.0059922479 0.0213730000 221404650 95654128 760807424 -0.0750195831 -0.0197272934 -0.0645971820 59 1311867172.3942890167 0.0550226197 0.0555337058 0.0590390489 0.0059449809 0.0184270000 221406322 95654128 760807424 -0.0789323598 -0.0184473898 -0.0652839616 60 1311867172.4265220165 0.0555992834 0.0555347987 0.0590390489 0.0059701248 0.0183470000 221409794 95654128 760807424 -0.0826048478 -0.0198103990 -0.0652315691 61 1311867172.4623498917 0.0548193567 0.0555230702 0.0590390489 0.0060637955 0.0184760000 221583226 95654128 760807424 -0.0804751962 -0.0184982717 -0.0656728968 62 1311867172.4952669144 0.0539526828 0.0554977413 0.0590390489 0.0061154118 0.0184010000 221584842 95654128 760807424 -0.0845737979 -0.0209797472 -0.0664363131 63 1311867172.5263059139 0.0546252280 0.0554838919 0.0590390489 0.0061326391 0.0183350000 221588314 95654128 760807424 -0.0884222463 -0.0212660767 -0.0668180063 64 1311867172.5624930859 0.0546258017 0.0554704843 0.0590390489 0.0060959474 0.0184240000 221591898 95654128 760807424 -0.0885817856 -0.0193933696 -0.0678422898 65 1311867172.5945439339 0.0538425930 0.0554454398 0.0590390489 0.0060680057 0.0186650000 221605458 95654128 760807424 -0.0902871415 -0.0200096462 -0.0689955875 66 1311867172.6263699532 0.0540473685 0.0554242569 0.0590390489 0.0060605626 0.0185520000 221621786 95654128 760807424 -0.0935092866 -0.0198889356 -0.0698496029 67 1311867172.6624419689 0.0533316806 0.0553930244 0.0590390489 0.0060274753 0.0185240000 221623570 95654128 760807424 -0.0944228843 -0.0201974530 -0.0704019591 68 1311867172.6945450306 0.0530726016 0.0553589005 0.0590390489 0.0060178743 0.0219650000 221627026 95654128 760807424 -0.0955701321 -0.0205171052 -0.0706985518 69 1311867172.7263929844 0.0529541634 0.0553240493 0.0590390489 0.0060211999 0.0188170000 221630698 95654128 760807424 -0.0979143754 -0.0187224243 -0.0718376860 70 1311867172.7623739243 0.0522788428 0.0552805463 0.0590390489 0.0060170698 0.0185730000 221632482 95654128 760807424 -0.1014650837 -0.0200596806 -0.0719922259 71 1311867172.7944509983 0.0521421693 0.0552363438 0.0590390489 0.0059965851 0.0196590000 221807230 95654128 760807424 -0.1045993716 -0.0206553545 -0.0721617118 72 1311867172.8263089657 0.0522713102 0.0551951628 0.0590390489 0.0059879584 0.0188790000 221810758 95654128 760807424 -0.1076379791 -0.0217686649 -0.0726744384 73 1311867172.8632309437 0.0520368926 0.0551518988 0.0590390489 0.0059547421 0.0188430000 221812782 95654128 760807424 -0.1111162007 -0.0222493429 -0.0734457374 74 1311867172.8944649696 0.0518972315 0.0551079168 0.0590390489 0.0059165231 0.0188410000 221816142 95654128 760807424 -0.1147274598 -0.0220711511 -0.0742760748 75 1311867172.9263219833 0.0523325838 0.0550709124 0.0590390489 0.0058802219 0.0189320000 221819670 95654128 760807424 -0.1169189140 -0.0221066028 -0.0744395405 76 1311867172.9623310566 0.0527723841 0.0550406686 0.0590390489 0.0058439128 0.0188410000 221821454 95654128 760807424 -0.1176101789 -0.0214431286 -0.0748112574 77 1311867172.9945271015 0.0532046854 0.0550168247 0.0590390489 0.0058142820 0.0218830000 221825070 95654128 760807424 -0.1198074296 -0.0210883096 -0.0751622841 78 1311867173.0262629986 0.0534858741 0.0549971971 0.0590390489 0.0057771400 0.0190860000 221826742 95654128 760807424 -0.1206894070 -0.0206573047 -0.0752686411 79 1311867173.0624630451 0.0533955917 0.0549769236 0.0590390489 0.0057472276 0.0188670000 221830326 95654128 760807424 -0.1194048226 -0.0201660264 -0.0755286887 80 1311867173.0945179462 0.0537252389 0.0549612775 0.0590390489 0.0057873870 0.0190380000 221833782 95654128 760807424 -0.1225537434 -0.0197109077 -0.0760834739 81 1311867173.1267819405 0.0537454486 0.0549462673 0.0590390489 0.0057786590 0.0191190000 221835710 95654128 760807424 -0.1229812428 -0.0181000754 -0.0765409023 82 1311867173.1622309685 0.0531353205 0.0549241826 0.0590390489 0.0057989606 0.0282410000 221839294 95654128 760807424 -0.1228685230 -0.0182013959 -0.0767044723 83 1311867173.1943008900 0.0532627106 0.0549041649 0.0590390489 0.0057669281 0.0199320000 221842710 95654128 760807424 -0.1272916049 -0.0185902398 -0.0767074078 84 1311867173.2264449596 0.0524388142 0.0548748154 0.0590390489 0.0057511745 0.0192010000 221844382 95654128 760807424 -0.1293782294 -0.0193791762 -0.0767547712 85 1311867173.2622020245 0.0525055565 0.0548469418 0.0590390489 0.0057481856 0.0192910000 221848166 95654128 760807424 -0.1307456642 -0.0186579265 -0.0769540071 86 1311867173.2942678928 0.0522962920 0.0548172831 0.0590390489 0.0057293867 0.0195320000 222021942 95654128 760807424 -0.1318603158 -0.0198472962 -0.0763341710 87 1311867173.3262879848 0.0526061617 0.0547918679 0.0590390489 0.0057074180 0.0192570000 222023614 95654128 760807424 -0.1331440508 -0.0199138336 -0.0757587999 88 1311867173.3623280525 0.0529807508 0.0547712870 0.0590390489 0.0056764552 0.0193360000 222027254 95654128 760807424 -0.1358149648 -0.0187428482 -0.0759770200 89 1311867173.3942871094 0.0529226661 0.0547505160 0.0590390489 0.0056686117 0.0193400000 222029070 95654128 760807424 -0.1375315040 -0.0190989710 -0.0757122114 90 1311867173.4262790680 0.0533348657 0.0547347866 0.0590390489 0.0056491377 0.0194260000 222032542 95654128 760807424 -0.1424044222 -0.0180944409 -0.0761733949 91 1311867173.4622900486 0.0525888652 0.0547112050 0.0590390489 0.0056768144 0.0194660000 222036126 95654128 760807424 -0.1446064413 -0.0192187037 -0.0764374286 92 1311867173.4943389893 0.0540126786 0.0547036123 0.0590390489 0.0058344114 0.0194890000 222037798 95654128 760807424 -0.1467668265 -0.0185247231 -0.0764378086 93 1311867173.5263900757 0.0535779372 0.0546915083 0.0590390489 0.0058045289 0.0229130000 222041526 95654128 760807424 -0.1472699195 -0.0180123392 -0.0771193653 94 1311867173.5624370575 0.0528602302 0.0546720266 0.0590390489 0.0058220969 0.0196390000 222045110 95654128 760807424 -0.1493264735 -0.0184956677 -0.0774641857 95 1311867173.5943109989 0.0534648225 0.0546593192 0.0590390489 0.0058263069 0.0195690000 222046726 95654128 760807424 -0.1509626210 -0.0178460106 -0.0774760544 96 1311867173.6263959408 0.0535234809 0.0546474875 0.0590390489 0.0058075120 0.0226010000 222050198 95654128 760807424 -0.1546842158 -0.0185486153 -0.0773942396 97 1311867173.6623299122 0.0535054877 0.0546357144 0.0590390489 0.0057880635 0.0196850000 222053982 95654128 760807424 -0.1558996588 -0.0186892003 -0.0780385360 98 1311867173.6943540573 0.0535257459 0.0546243881 0.0590390489 0.0057585145 0.0196470000 222055654 95654128 760807424 -0.1580634415 -0.0192623772 -0.0786248595 99 1311867173.7267971039 0.0540994592 0.0546190858 0.0590390489 0.0057352879 0.0197920000 222229330 95654128 760807424 -0.1594493538 -0.0188236646 -0.0789578259 100 1311867173.7623970509 0.0532520860 0.0546054158 0.0590390489 0.0057114437 0.0197990000 222232914 95654128 760807424 -0.1602664143 -0.0168103725 -0.0813771933 101 1311867173.7943561077 0.0536678098 0.0545961326 0.0590390489 0.0056925934 0.0283960000 222234658 95654128 760807424 -0.1621773392 -0.0190116111 -0.0808266848 102 1311867173.8265669346 0.0544377267 0.0545945796 0.0590390489 0.0056658864 0.0204470000 222238186 95654128 760807424 -0.1641546786 -0.0184715390 -0.0811167210 103 1311867173.8635799885 0.0536622293 0.0545855277 0.0590390489 0.0056480859 0.0198140000 222239914 95654128 760807424 -0.1658841074 -0.0178851392 -0.0831103921 104 1311867173.8946080208 0.0542515814 0.0545823166 0.0590390489 0.0056510600 0.0198000000 222243386 95654128 760807424 -0.1706325114 -0.0207650941 -0.0828054398 105 1311867173.9266970158 0.0533074178 0.0545701747 0.0590390489 0.0056373724 0.0197900000 222247130 95654128 760807424 -0.1733349264 -0.0216235034 -0.0842258334 106 1311867173.9625461102 0.0525984503 0.0545515736 0.0590390489 0.0056613858 0.0198500000 222248914 95654128 760807424 -0.1731147766 -0.0175841264 -0.0866443589 107 1311867173.9944310188 0.0523017384 0.0545305471 0.0590390489 0.0056612765 0.0198360000 222252330 95654128 760807424 -0.1752185524 -0.0204457399 -0.0861380845 108 1311867174.0264260769 0.0530394129 0.0545167403 0.0590390489 0.0056658867 0.0231500000 222255802 95654128 760807424 -0.1761786789 -0.0197417233 -0.0865202993 109 1311867174.0624630451 0.0523809791 0.0544971461 0.0590390489 0.0056579926 0.0199540000 222257786 95654128 760807424 -0.1763717532 -0.0169886164 -0.0882399306 110 1311867174.0945188999 0.0531227924 0.0544846520 0.0590390489 0.0056554577 0.0199480000 222261258 95654128 760807424 -0.1767747253 -0.0167344678 -0.0878664851 111 1311867174.1264541149 0.0538729019 0.0544791408 0.0590390489 0.0056379126 0.0199890000 222264730 95654128 760807424 -0.1825513989 -0.0169763956 -0.0879827812 112 1311867174.1624329090 0.0529276654 0.0544652883 0.0590390489 0.0056158975 0.0199560000 222266514 95654128 760807424 -0.1832124293 -0.0133997872 -0.0910503939 113 1311867174.1943979263 0.0516503379 0.0544403772 0.0590390489 0.0056432474 0.0233740000 222440066 95654128 760807424 -0.1841246337 -0.0161486454 -0.0905481949 114 1311867174.2267580032 0.0519888736 0.0544188728 0.0590390489 0.0056282761 0.0200810000 222441794 95654128 760807424 -0.1867834032 -0.0176764708 -0.0896191448 115 1311867174.2626769543 0.0517817922 0.0543959417 0.0590390489 0.0056185699 0.0199730000 222445322 95654128 760807424 -0.1885682791 -0.0141623616 -0.0914875418 116 1311867174.2945280075 0.0527950451 0.0543821408 0.0590390489 0.0056481566 0.0206780000 222448794 95654128 760807424 -0.1897886544 -0.0175182484 -0.0894571766 117 1311867174.3265740871 0.0527312346 0.0543680305 0.0590390489 0.0056288679 0.0201840000 222450666 95654128 760807424 -0.1923378259 -0.0170151219 -0.0901428610 118 1311867174.3624329567 0.0519695394 0.0543477043 0.0590390489 0.0056111067 0.0202430000 222454306 95654128 760807424 -0.1958438158 -0.0155173251 -0.0917035714 119 1311867174.3946359158 0.0524313487 0.0543316005 0.0590390489 0.0056039234 0.0201110000 222457722 95654128 760807424 -0.1982770413 -0.0155846095 -0.0912868679 120 1311867174.4266788960 0.0531001724 0.0543213386 0.0590390489 0.0055851183 0.0232660000 222459450 95654128 760807424 -0.2008641213 -0.0168688428 -0.0902507305 121 1311867174.4630160332 0.0520216562 0.0543023330 0.0590390489 0.0056166459 0.0203800000 222463178 95654128 760807424 -0.2032712698 -0.0156269092 -0.0916828886 122 1311867174.4945669174 0.0530181564 0.0542918069 0.0590390489 0.0056077793 0.0201380000 222466650 95654128 760807424 -0.2042913139 -0.0149613889 -0.0908242315 123 1311867174.5267519951 0.0524895564 0.0542771545 0.0590390489 0.0056060214 0.0201630000 222468378 95654128 760807424 -0.2058687955 -0.0165100452 -0.0903644487 124 1311867174.5623500347 0.0526964478 0.0542644069 0.0590390489 0.0056081185 0.0235120000 222471962 95654128 760807424 -0.2073419392 -0.0129736699 -0.0915454850 125 1311867174.5944879055 0.0519047454 0.0542455296 0.0590390489 0.0055899239 0.0202500000 222473778 95654128 760807424 -0.2086669654 -0.0134357950 -0.0917055085 126 1311867174.6265459061 0.0522336885 0.0542295626 0.0590390489 0.0056006762 0.0201910000 222477250 95654128 760807424 -0.2103653699 -0.0135552892 -0.0906472281 127 1311867174.6624910831 0.0517597571 0.0542101153 0.0590390489 0.0055858567 0.0201760000 222480834 95654128 760807424 -0.2143311948 -0.0130851744 -0.0915192142 128 1311867174.6945910454 0.0514024980 0.0541881808 0.0590390489 0.0055730842 0.0202250000 222482506 95654128 760807424 -0.2153213918 -0.0112221269 -0.0920538455 129 1311867174.7265629768 0.0524401143 0.0541746299 0.0590390489 0.0055749259 0.0244900000 222509674 95654128 760807424 -0.2173905969 -0.0149787068 -0.0893600807 130 1311867174.7623760700 0.0528890193 0.0541647406 0.0590390489 0.0055612961 0.0206330000 222710542 95654128 760807424 -0.2213861793 -0.0129439766 -0.0901627168 131 1311867174.7944738865 0.0520848520 0.0541488635 0.0590390489 0.0055548235 0.0211510000 222712102 95654128 760807424 -0.2221712768 -0.0137973856 -0.0904035494 132 1311867174.8273398876 0.0536122844 0.0541447986 0.0590390489 0.0055396845 0.0204110000 222715630 95654128 760807424 -0.2276036292 -0.0141932191 -0.0897405595 133 1311867174.8624229431 0.0523708016 0.0541314602 0.0590390489 0.0055207650 0.0203150000 222719430 95654128 760807424 -0.2282148451 -0.0135766268 -0.0912761614 134 1311867174.8944199085 0.0519742854 0.0541153619 0.0590390489 0.0055066136 0.0202780000 222721046 95654128 760807424 -0.2284461409 -0.0148405749 -0.0909639895 135 1311867174.9270179272 0.0522619374 0.0541016328 0.0590390489 0.0054878351 0.0203140000 222724574 95654128 760807424 -0.2286410630 -0.0139482291 -0.0910237506 136 1311867174.9626429081 0.0524198674 0.0540892669 0.0590390489 0.0054712414 0.0203300000 222728158 95654128 760807424 -0.2311916649 -0.0164892990 -0.0905201361 137 1311867174.9943349361 0.0518503711 0.0540729246 0.0590390489 0.0054820550 0.0203020000 222729974 95654128 760807424 -0.2354758233 -0.0106799379 -0.0944974720 138 1311867175.0265510082 0.0511396974 0.0540516693 0.0590390489 0.0054638121 0.0202730000 222733502 95654128 760807424 -0.2376559824 -0.0115224887 -0.0947334915 139 1311867175.0633120537 0.0513587631 0.0540322959 0.0590390489 0.0054444621 0.0229760000 222735286 95654128 760807424 -0.2402332425 -0.0110749304 -0.0944975987 140 1311867175.0947189331 0.0512708575 0.0540125714 0.0590390489 0.0054493638 0.0203940000 222738758 95654128 760807424 -0.2423958331 -0.0098883482 -0.0948001072 141 1311867175.1265308857 0.0513819419 0.0539939144 0.0590390489 0.0054365781 0.0203560000 222742430 95654128 760807424 -0.2439586669 -0.0089686802 -0.0944650993 142 1311867175.1625180244 0.0511283167 0.0539737341 0.0590390489 0.0054330428 0.0203160000 222744214 95654128 760807424 -0.2454941124 -0.0093031190 -0.0943400264 143 1311867175.1946399212 0.0509245545 0.0539524112 0.0590390489 0.0054139901 0.0203910000 222747630 95654128 760807424 -0.2462943643 -0.0085605606 -0.0943781212 144 1311867175.2270050049 0.0494618826 0.0539212270 0.0590390489 0.0054992090 0.0233520000 222751158 95654128 760807424 -0.2463685721 -0.0068675480 -0.0950823054 145 1311867175.2624669075 0.0500287823 0.0538943825 0.0590390489 0.0055357716 0.0205030000 222753086 95654128 760807424 -0.2496947646 -0.0084448541 -0.0935720280 146 1311867175.2944509983 0.0502655543 0.0538695275 0.0590390489 0.0055232717 0.0244250000 222927782 95654128 760807424 -0.2516795099 -0.0049584652 -0.0940667838 147 1311867175.3267059326 0.0496016927 0.0538404947 0.0590390489 0.0055080367 0.0206280000 222931310 95654128 760807424 -0.2526060045 -0.0042965077 -0.0933657438 148 1311867175.3625650406 0.0505791642 0.0538184586 0.0590390489 0.0055121055 0.0205090000 222933038 95654128 760807424 -0.2550652027 -0.0062074317 -0.0910470486 149 1311867175.3945989609 0.0507906266 0.0537981376 0.0590390489 0.0054940336 0.0282890000 222936710 95654128 760807424 -0.2581114173 -0.0054045934 -0.0908307210 150 1311867175.4266059399 0.0508581474 0.0537785377 0.0590390489 0.0054769612 0.0210320000 222938398 95654128 760807424 -0.2605614364 -0.0032079900 -0.0909684077 151 1311867175.4625999928 0.0506170727 0.0537576008 0.0590390489 0.0054627205 0.0205920000 222942038 95654128 760807424 -0.2651157975 -0.0030097896 -0.0907971635 152 1311867175.4945731163 0.0506615937 0.0537372324 0.0590390489 0.0054449684 0.0206350000 222945510 95654128 760807424 -0.2694261968 -0.0027709468 -0.0907621682 153 1311867175.5264270306 0.0513870940 0.0537218720 0.0590390489 0.0054482898 0.0206240000 222947326 95654128 760807424 -0.2699902952 -0.0009178056 -0.0901545957 154 1311867175.5625700951 0.0503417738 0.0536999233 0.0590390489 0.0054643814 0.0206110000 222950966 95654128 760807424 -0.2715452015 -0.0003100106 -0.0902748927 155 1311867175.5946640968 0.0519796908 0.0536888250 0.0590390489 0.0054940176 0.0206320000 222954382 95654128 760807424 -0.2766405642 -0.0006728921 -0.0891946852 156 1311867175.6264801025 0.0502118021 0.0536665364 0.0590390489 0.0055237667 0.0206080000 222956054 95654128 760807424 -0.2811022997 0.0003202083 -0.0912970826 157 1311867175.6624929905 0.0502745435 0.0536449314 0.0590390489 0.0055492931 0.0207280000 223130634 95654128 760807424 -0.2836658061 0.0010510002 -0.0915430561 158 1311867175.6947000027 0.0501097478 0.0536225568 0.0590390489 0.0055670826 0.0206260000 223134106 95654128 760807424 -0.2879078090 -0.0002513253 -0.0910800621 159 1311867175.7273120880 0.0514445864 0.0536088589 0.0590390489 0.0055528406 0.0301150000 223135834 95654128 760807424 -0.2882956564 0.0027979063 -0.0903375447 160 1311867175.7624969482 0.0516821854 0.0535968171 0.0590390489 0.0055421103 0.0220750000 223139418 95654128 760807424 -0.2914296985 0.0027370930 -0.0902585313 161 1311867175.7948620319 0.0509276241 0.0535802383 0.0590390489 0.0055630996 0.0206850000 223141234 95654128 760807424 -0.2931110263 0.0007490460 -0.0898985192 162 1311867175.8287971020 0.0501813255 0.0535592574 0.0590390489 0.0055514070 0.0206130000 223144818 95654128 760807424 -0.2978848517 0.0018942866 -0.0920916945 163 1311867175.8625519276 0.0498367995 0.0535364202 0.0590390489 0.0055377583 0.0206770000 223148362 95654128 760807424 -0.3007525802 0.0028655005 -0.0928284079 164 1311867175.8946080208 0.0502904914 0.0535166279 0.0590390489 0.0055269601 0.0239500000 223149978 95654128 760807424 -0.3037053943 0.0020411490 -0.0924151912 165 1311867175.9282429218 0.0507352017 0.0534997708 0.0590390489 0.0055161592 0.0206940000 223153706 95654128 760807424 -0.3074457347 0.0016952150 -0.0920257121 166 1311867175.9629371166 0.0504833199 0.0534815994 0.0590390489 0.0054997946 0.0206220000 223157234 95654128 760807424 -0.3087788820 0.0033656764 -0.0929248556 167 1311867175.9983000755 0.0508227721 0.0534656783 0.0590390489 0.0054871932 0.0206550000 223158962 95654128 760807424 -0.3117910326 0.0021538457 -0.0922942460 168 1311867176.0268509388 0.0527730286 0.0534615554 0.0590390489 0.0054885491 0.0206810000 223162322 95654128 760807424 -0.3166683912 0.0013041807 -0.0914290324 169 1311867176.0627059937 0.0510658957 0.0534473799 0.0590390489 0.0055510386 0.0206800000 223166106 95654128 760807424 -0.3182305098 0.0022258442 -0.0936840102 170 1311867176.0946600437 0.0512284152 0.0534343272 0.0590390489 0.0056029407 0.0206780000 223167722 95654128 760807424 -0.3196898401 0.0034085971 -0.0949185640 171 1311867176.1268119812 0.0521399155 0.0534267575 0.0590390489 0.0055923749 0.0239260000 223171250 95654128 760807424 -0.3225776255 0.0044046151 -0.0954403430 172 1311867176.1625900269 0.0518440716 0.0534175558 0.0590390489 0.0056915168 0.0207380000 223345554 95654128 760807424 -0.3229420483 0.0042709582 -0.0954245925 173 1311867176.1946918964 0.0512961186 0.0534052932 0.0590390489 0.0057383631 0.0239200000 223347458 95654128 760807424 -0.3224854171 0.0055578901 -0.0969794393 174 1311867176.2265360355 0.0525044128 0.0534001157 0.0590390489 0.0057317751 0.0207300000 223350930 95654128 760807424 -0.3243005574 0.0061491127 -0.0960569903 175 1311867176.2625019550 0.0524481460 0.0533946759 0.0590390489 0.0057169242 0.0216410000 223352714 95654128 760807424 -0.3267762661 0.0059233545 -0.0968444645 176 1311867176.2946109772 0.0509531125 0.0533808034 0.0590390489 0.0057047060 0.0207450000 223356130 95654128 760807424 -0.3292168975 0.0108913220 -0.1014895886 177 1311867176.3266019821 0.0520035587 0.0533730223 0.0590390489 0.0056914079 0.0207200000 223359802 95654128 760807424 -0.3331866264 0.0083375536 -0.1002930179 178 1311867176.3624560833 0.0518855751 0.0533646659 0.0590390489 0.0056766700 0.0282400000 223361642 95654128 760807424 -0.3340180814 0.0107004959 -0.1017917469 179 1311867176.3952438831 0.0518034473 0.0533559440 0.0590390489 0.0056665477 0.0210630000 223365058 95654128 760807424 -0.3346452117 0.0114348438 -0.1023034975 180 1311867176.4268360138 0.0512857921 0.0533444432 0.0590390489 0.0056519471 0.0235880000 223368530 95654128 760807424 -0.3351752460 0.0132423434 -0.1035559028 181 1311867176.4629659653 0.0517689623 0.0533357388 0.0590390489 0.0056912248 0.0207350000 223370514 95654128 760807424 -0.3363040686 0.0128195416 -0.1026059315 182 1311867176.4945809841 0.0518093593 0.0533273521 0.0590390489 0.0056917895 0.0207290000 223373930 95654128 760807424 -0.3392413557 0.0141826477 -0.1051677093 183 1311867176.5266211033 0.0523827635 0.0533221904 0.0590390489 0.0057134893 0.0206870000 223377458 95654128 760807424 -0.3436799347 0.0156522635 -0.1068402827 184 1311867176.5636389256 0.0526391827 0.0533184785 0.0590390489 0.0057082285 0.0207010000 223379298 95654128 760807424 -0.3443587124 0.0133859199 -0.1057545543 185 1311867176.5946090221 0.0512547009 0.0533073229 0.0590390489 0.0056937076 0.0207100000 223382914 95654128 760807424 -0.3457079232 0.0143460259 -0.1080687791 186 1311867176.6283841133 0.0517542623 0.0532989731 0.0590390489 0.0056873826 0.0207270000 223384642 95654128 760807424 -0.3480683267 0.0156849232 -0.1087618098 187 1311867176.6625781059 0.0510954931 0.0532871898 0.0590390489 0.0056740002 0.0293270000 223388170 95654128 760807424 -0.3504768610 0.0151060522 -0.1095657647 188 1311867176.6945180893 0.0506929681 0.0532733907 0.0590390489 0.0056597054 0.0213920000 223562054 95654128 760807424 -0.3536089659 0.0151347360 -0.1108181328 189 1311867176.7265889645 0.0499763861 0.0532559463 0.0590390489 0.0056476145 0.0207290000 223563982 95654128 760807424 -0.3556152284 0.0153889218 -0.1120385602 190 1311867176.7632329464 0.0508181788 0.0532431159 0.0590390489 0.0056370193 0.0207070000 223567566 95654128 760807424 -0.3587489426 0.0183751509 -0.1129500046 191 1311867176.7947680950 0.0509044640 0.0532308717 0.0590390489 0.0056307730 0.0207110000 223570982 95654128 760807424 -0.3615709841 0.0175028462 -0.1128810421 192 1311867176.8266770840 0.0503946580 0.0532160997 0.0590390489 0.0056169799 0.0299640000 223572710 95654128 760807424 -0.3637161851 0.0164215527 -0.1133480892 193 1311867176.8627309799 0.0500936396 0.0531999212 0.0590390489 0.0056044809 0.0214610000 223576494 95654128 760807424 -0.3655790091 0.0180898048 -0.1146986559 194 1311867176.8949549198 0.0504693575 0.0531858461 0.0590390489 0.0055923403 0.0206990000 223579966 95654128 760807424 -0.3706840277 0.0161151309 -0.1145346239 195 1311867176.9268178940 0.0499770120 0.0531693905 0.0590390489 0.0055970732 0.0206600000 223581638 95654128 760807424 -0.3728248179 0.0172755625 -0.1153270900 196 1311867176.9650609493 0.0493877828 0.0531500966 0.0590390489 0.0056016097 0.0273170000 223585222 95654128 760807424 -0.3739815950 0.0195502117 -0.1168404073 197 1311867176.9947481155 0.0511657521 0.0531400238 0.0590390489 0.0055874106 0.0210160000 223587038 95654128 760807424 -0.3773463964 0.0190517437 -0.1151155382 198 1311867177.0267279148 0.0499927998 0.0531241287 0.0590390489 0.0055818475 0.0206520000 223590510 95654128 760807424 -0.3790047169 0.0184829999 -0.1163154989 199 1311867177.0626339912 0.0497389846 0.0531071180 0.0590390489 0.0055696267 0.0206840000 223594094 95654128 760807424 -0.3813883066 0.0196969006 -0.1173977405 200 1311867177.0946850777 0.0489893667 0.0530865292 0.0590390489 0.0055596094 0.0207880000 223595766 95654128 760807424 -0.3835304081 0.0174558088 -0.1174975559 201 1311867177.1266150475 0.0488911755 0.0530656568 0.0590390489 0.0055458023 0.0207290000 223599438 95654128 760807424 -0.3864011765 0.0174446106 -0.1180259138 202 1311867177.1627299786 0.0500897691 0.0530509247 0.0590390489 0.0055354944 0.0207120000 223603022 95654128 760807424 -0.3892108202 0.0205951687 -0.1182915494 203 1311867177.1946458817 0.0495175086 0.0530335187 0.0590390489 0.0055306418 0.0208180000 223604694 95654128 760807424 -0.3902056515 0.0210097898 -0.1189052463 204 1311867177.2264730930 0.0496711433 0.0530170365 0.0590390489 0.0055173918 0.0206910000 223608166 95654128 760807424 -0.3923953474 0.0209539011 -0.1190204397 205 1311867177.2638640404 0.0500724465 0.0530026726 0.0590390489 0.0055053206 0.0240670000 223782546 95654128 760807424 -0.3964650333 0.0221717618 -0.1202039495 206 1311867177.2946178913 0.0496696755 0.0529864930 0.0590390489 0.0055108257 0.0207490000 223784162 95654128 760807424 -0.3979629874 0.0210535321 -0.1198069900 207 1311867177.3276090622 0.0487897061 0.0529662187 0.0590390489 0.0055025414 0.0207030000 223787690 95654128 760807424 -0.3992943168 0.0223981179 -0.1214075610 208 1311867177.3627710342 0.0489831753 0.0529470694 0.0590390489 0.0054903638 0.0239820000 223791218 95654128 760807424 -0.4041538835 0.0218829084 -0.1221086755 209 1311867177.3946089745 0.0497241877 0.0529316489 0.0590390489 0.0054975455 0.0207330000 223793090 95654128 760807424 -0.4060573876 0.0237340853 -0.1226301566 210 1311867177.4312860966 0.0489136726 0.0529125157 0.0590390489 0.0054854900 0.0206750000 223796730 95654128 760807424 -0.4081531763 0.0236762483 -0.1235035658 211 1311867177.4626040459 0.0484868102 0.0528915408 0.0590390489 0.0054730117 0.0206200000 223798402 95654128 760807424 -0.4090889394 0.0238620229 -0.1237942204 212 1311867177.4946429729 0.0484207459 0.0528704522 0.0590390489 0.0054618330 0.0239160000 223801874 95654128 760807424 -0.4125879705 0.0239893775 -0.1245979220 213 1311867177.5276319981 0.0476056263 0.0528457347 0.0590390489 0.0054506362 0.0207380000 223805546 95654128 760807424 -0.4140862525 0.0253331028 -0.1262326688 214 1311867177.5626399517 0.0484556071 0.0528252201 0.0590390489 0.0054501227 0.0243600000 223807274 95654128 760807424 -0.4179689884 0.0241749603 -0.1256413460 215 1311867177.5947310925 0.0492666960 0.0528086688 0.0590390489 0.0054450071 0.0208160000 223810746 95654128 760807424 -0.4180018604 0.0276244953 -0.1260789335 216 1311867177.6311450005 0.0492105782 0.0527920109 0.0590390489 0.0054355513 0.0207160000 223814386 95654128 760807424 -0.4210251868 0.0275972206 -0.1267368942 217 1311867177.6624829769 0.0479213186 0.0527695654 0.0590390489 0.0054280040 0.0214460000 223816258 95654128 760807424 -0.4218843579 0.0269890185 -0.1277299672 218 1311867177.6945610046 0.0483453088 0.0527492706 0.0590390489 0.0054365357 0.0207520000 223819730 95654128 760807424 -0.4246007502 0.0295201186 -0.1290728152 219 1311867177.7305839062 0.0482774302 0.0527288512 0.0590390489 0.0054297186 0.0206840000 223823258 95654128 760807424 -0.4241482913 0.0316720046 -0.1298483908 220 1311867177.7625379562 0.0481415503 0.0527079999 0.0590390489 0.0054244923 0.0237780000 223824946 95654128 760807424 -0.4250829518 0.0297101736 -0.1292538643 221 1311867177.7945590019 0.0484826006 0.0526888804 0.0590390489 0.0054162994 0.0240850000 223828618 95654128 760807424 -0.4267733693 0.0303134322 -0.1302293539 222 1311867177.8309149742 0.0498474501 0.0526760812 0.0590390489 0.0054211038 0.0208710000 223830402 95654128 760807424 -0.4306533635 0.0309846923 -0.1308206916 223 1311867177.8625319004 0.0497651100 0.0526630275 0.0590390489 0.0054107302 0.0207510000 223833874 95654128 760807424 -0.4297747910 0.0324824005 -0.1314180195 224 1311867177.8946919441 0.0484688170 0.0526443034 0.0590390489 0.0054101025 0.0207800000 223837290 95654128 760807424 -0.4299121797 0.0321828835 -0.1330146939 225 1311867177.9317860603 0.0486935899 0.0526267446 0.0590390489 0.0054002590 0.0209100000 223839386 95654128 760807424 -0.4305789173 0.0318363011 -0.1326809675 226 1311867177.9627909660 0.0487902239 0.0526097689 0.0590390489 0.0054067303 0.0207150000 223842802 95654128 760807424 -0.4335071146 0.0329732150 -0.1344742924 227 1311867177.9947769642 0.0485808440 0.0525920203 0.0590390489 0.0053957189 0.0207360000 223846162 95654128 760807424 -0.4349260628 0.0344821662 -0.1363523155 228 1311867178.0306100845 0.0479930826 0.0525718495 0.0590390489 0.0053881303 0.0236540000 223847946 95654128 760807424 -0.4360020459 0.0323856175 -0.1360663325 229 1311867178.0634479523 0.0475121103 0.0525497546 0.0590390489 0.0053772845 0.0207160000 223851618 95654128 760807424 -0.4374294281 0.0331586935 -0.1376052499 230 1311867178.0951139927 0.0476286374 0.0525283584 0.0590390489 0.0053657297 0.0207310000 223855090 95654128 760807424 -0.4389150739 0.0339614078 -0.1382104009 231 1311867178.1307909489 0.0496529862 0.0525159109 0.0590390489 0.0053552458 0.0207420000 223856874 95654128 760807424 -0.4425693452 0.0333737507 -0.1365728676 232 1311867178.1627469063 0.0484553538 0.0524984085 0.0590390489 0.0053607498 0.0237210000 223860346 95654128 760807424 -0.4436295033 0.0354859345 -0.1395929605 233 1311867178.1950459480 0.0479601771 0.0524789311 0.0590390489 0.0053511766 0.0241930000 224032426 95654128 760807424 -0.4463751316 0.0349969417 -0.1406289041 234 1311867178.2307190895 0.0494684726 0.0524660659 0.0590390489 0.0053407140 0.0208160000 224036010 95654128 760807424 -0.4504551291 0.0324917436 -0.1388771832 235 1311867178.2628939152 0.0482056960 0.0524479367 0.0590390489 0.0053338757 0.0207660000 224039538 95654128 760807424 -0.4511071742 0.0360369980 -0.1418312937 236 1311867178.2954900265 0.0469485857 0.0524246344 0.0590390489 0.0053266097 0.0206920000 224041210 95654128 760807424 -0.4524169862 0.0338507146 -0.1419125646 237 1311867178.3306670189 0.0477353744 0.0524048485 0.0590390489 0.0053184682 0.0236060000 224044938 95654128 760807424 -0.4563833177 0.0339881033 -0.1418830901 238 1311867178.3627231121 0.0467691831 0.0523811692 0.0590390489 0.0053084425 0.0207070000 224048466 95654128 760807424 -0.4571807384 0.0359205082 -0.1433703750 239 1311867178.3949439526 0.0478026010 0.0523620120 0.0590390489 0.0052978646 0.0236600000 224050082 95654128 760807424 -0.4605002701 0.0350790061 -0.1421890855 240 1311867178.4306581020 0.0473398156 0.0523410862 0.0590390489 0.0052937599 0.0239140000 224053666 95654128 760807424 -0.4625577331 0.0369348302 -0.1437134147 241 1311867178.4628739357 0.0464822575 0.0523167757 0.0590390489 0.0052853816 0.0206950000 224057338 95654128 760807424 -0.4624156654 0.0365833156 -0.1434348226 242 1311867178.4946439266 0.0471369624 0.0522953715 0.0590390489 0.0052750163 0.0295440000 224059010 95654128 760807424 -0.4666545391 0.0372350030 -0.1439767629 243 1311867178.5306270123 0.0466612093 0.0522721857 0.0590390489 0.0052676750 0.0211880000 224062610 95654128 760807424 -0.4690296650 0.0388309620 -0.1455033422 244 1311867178.5626420975 0.0472522788 0.0522516123 0.0590390489 0.0052572130 0.0207000000 224066138 95654128 760807424 -0.4719485641 0.0377195142 -0.1443016380 245 1311867178.5947000980 0.0485229641 0.0522363933 0.0590390489 0.0052469294 0.0239680000 224068010 95654128 760807424 -0.4745500982 0.0380723104 -0.1433931291 246 1311867178.6306900978 0.0478824452 0.0522186943 0.0590390489 0.0052369680 0.0215600000 224071538 95654128 760807424 -0.4736421406 0.0397512875 -0.1439450830 247 1311867178.6626410484 0.0478357188 0.0522009495 0.0590390489 0.0052454634 0.0207480000 224073266 95654128 760807424 -0.4742160141 0.0382271968 -0.1423635334 248 1311867178.6946120262 0.0474156365 0.0521816539 0.0590390489 0.0052361917 0.0206960000 224076682 95654128 760807424 -0.4758217633 0.0377254374 -0.1429961026 249 1311867178.7307450771 0.0470003337 0.0521608453 0.0590390489 0.0052306234 0.0233690000 224080466 95654128 760807424 -0.4763447642 0.0410966463 -0.1455165744 250 1311867178.7632350922 0.0475175977 0.0521422724 0.0590390489 0.0052223622 0.0236700000 224082194 95654128 760807424 -0.4812784493 0.0379054844 -0.1448973268 251 1311867178.8006799221 0.0483723916 0.0521272529 0.0590390489 0.0052134881 0.0307040000 224085778 95654128 760807424 -0.4820699990 0.0399357192 -0.1452151537 252 1311867178.8309500217 0.0482388623 0.0521118228 0.0590390489 0.0052051342 0.0211750000 224089194 95654128 760807424 -0.4817033410 0.0426941887 -0.1468125731 253 1311867178.8627939224 0.0480391309 0.0520957252 0.0590390489 0.0052028270 0.0203910000 224091122 95654128 760807424 -0.4817837477 0.0385032445 -0.1441549063 254 1311867178.8952279091 0.0490958728 0.0520839147 0.0590390489 0.0051934034 0.0204350000 224094594 95654128 760807424 -0.4816834033 0.0379445925 -0.1429542601 255 1311867178.9306209087 0.0480006002 0.0520679017 0.0590390489 0.0051896661 0.0207300000 224098122 95654128 760807424 -0.4780418575 0.0397420004 -0.1447683573 256 1311867178.9627609253 0.0489818715 0.0520558469 0.0590390489 0.0051796895 0.0205960000 224099850 95654128 760807424 -0.4809004068 0.0385318175 -0.1444326788 257 1311867178.9946830273 0.0484470576 0.0520418050 0.0590390489 0.0051707631 0.0209400000 224150626 95654128 760807424 -0.4869186282 0.0397915691 -0.1488541067 258 1311867179.0309159756 0.0486656241 0.0520287190 0.0590390489 0.0051695121 0.0204850000 224203610 95654128 760807424 -0.4906261563 0.0418173335 -0.1518897265 259 1311867179.0628120899 0.0493603833 0.0520184165 0.0590390489 0.0051659319 0.0205960000 224207138 95654128 760807424 -0.4916749299 0.0388217717 -0.1493592411 260 1311867179.0968201160 0.0490640476 0.0520070536 0.0590390489 0.0051668374 0.0301500000 224210626 95654128 760807424 -0.4867193699 0.0360404998 -0.1465191096 261 1311867179.1310369968 0.0481740087 0.0519923676 0.0590390489 0.0051601759 0.0217750000 224212498 95654128 760807424 -0.4840789735 0.0391591899 -0.1492936015 262 1311867179.1627540588 0.0505603179 0.0519869017 0.0590390489 0.0052258126 0.0209530000 224215970 95654128 760807424 -0.4882010520 0.0364305303 -0.1480864733 263 1311867179.1957008839 0.0486613922 0.0519742572 0.0590390489 0.0052186447 0.0211020000 224389642 95654128 760807424 -0.4922476411 0.0386443064 -0.1540881693 264 1311867179.2307469845 0.0493026711 0.0519641376 0.0590390489 0.0052143119 0.0205260000 224391370 95654128 760807424 -0.4975406229 0.0405727178 -0.1576139182 265 1311867179.2634611130 0.0495794304 0.0519551387 0.0590390489 0.0052214300 0.0205450000 224395154 95654128 760807424 -0.5016075373 0.0373770334 -0.1571967453 266 1311867179.2959330082 0.0488701649 0.0519435410 0.0590390489 0.0052124327 0.0205670000 224398570 95654128 760807424 -0.5016893744 0.0402637459 -0.1596945077 267 1311867179.3307149410 0.0486464128 0.0519311922 0.0590390489 0.0052028852 0.0208560000 224400298 95654128 760807424 -0.5000845194 0.0406003334 -0.1587899625 268 1311867179.3629300594 0.0470043160 0.0519128084 0.0590390489 0.0051962813 0.0213120000 224403882 95654128 760807424 -0.5000530481 0.0387683585 -0.1592675596 269 1311867179.3948490620 0.0484076068 0.0518997779 0.0590390489 0.0051887679 0.0311270000 224405642 95654128 760807424 -0.5053769946 0.0393954664 -0.1603541374 270 1311867179.4308040142 0.0472065918 0.0518823957 0.0590390489 0.0051829969 0.0211970000 224409282 95654128 760807424 -0.5056768060 0.0431307293 -0.1635727584 271 1311867179.4637460709 0.0469435118 0.0518641711 0.0590390489 0.0051940521 0.0208160000 224584930 95654128 760807424 -0.5072466135 0.0409516208 -0.1615449935 272 1311867179.4949469566 0.0480570160 0.0518501742 0.0590390489 0.0051855969 0.0208650000 224586562 95654128 760807424 -0.5075289607 0.0431074128 -0.1605878621 273 1311867179.5307800770 0.0469713099 0.0518323029 0.0590390489 0.0051801118 0.0203970000 224590346 95654128 760807424 -0.5071405172 0.0454073548 -0.1617000848 274 1311867179.5627610683 0.0463651866 0.0518123499 0.0590390489 0.0051963843 0.0206720000 224593818 95654128 760807424 -0.5083552003 0.0433463566 -0.1602590531 275 1311867179.5946741104 0.0457526147 0.0517903145 0.0590390489 0.0051872849 0.0203900000 224595490 95654128 760807424 -0.5100385547 0.0458276831 -0.1626411676 276 1311867179.6306900978 0.0470637158 0.0517731891 0.0590390489 0.0052035846 0.0207820000 224599018 95654128 760807424 -0.5144873857 0.0464132205 -0.1625206470 277 1311867179.6625750065 0.0468759723 0.0517555096 0.0590390489 0.0051969724 0.0203940000 224602730 95654128 760807424 -0.5136805177 0.0464183427 -0.1613656580 278 1311867179.6946051121 0.0469485819 0.0517382185 0.0590390489 0.0052065648 0.0298340000 224604346 95654128 760807424 -0.5133754015 0.0482873060 -0.1614132077 279 1311867179.7309470177 0.0464887507 0.0517194032 0.0590390489 0.0051979370 0.0239170000 224607986 95654128 760807424 -0.5133467913 0.0470677949 -0.1604324728 280 1311867179.7627270222 0.0459665172 0.0516988572 0.0590390489 0.0052101340 0.0204360000 224611458 95654128 760807424 -0.5141003132 0.0466214307 -0.1603799164 281 1311867179.7948911190 0.0461740978 0.0516791961 0.0590390489 0.0052157063 0.0234020000 224613274 95654128 760807424 -0.5151999593 0.0496058986 -0.1621601731 282 1311867179.8307530880 0.0456402004 0.0516577813 0.0590390489 0.0052070416 0.0238980000 224616914 95654128 760807424 -0.5165647864 0.0484121181 -0.1617781967 283 1311867179.8627979755 0.0464950278 0.0516395383 0.0590390489 0.0051985816 0.0204370000 224618586 95654128 760807424 -0.5188361406 0.0462905243 -0.1596219987 284 1311867179.8948040009 0.0468674898 0.0516227353 0.0590390489 0.0051910713 0.0203260000 224622058 95654128 760807424 -0.5182434320 0.0494836383 -0.1602333039 285 1311867179.9309051037 0.0468254089 0.0516059026 0.0590390489 0.0052056476 0.0206380000 224625842 95654128 760807424 -0.5162904859 0.0508900508 -0.1596698910 286 1311867179.9635379314 0.0477395840 0.0515923840 0.0590390489 0.0051989871 0.0305520000 224627570 95654128 760807424 -0.5193263292 0.0479923375 -0.1572447270 287 1311867179.9958879948 0.0464485064 0.0515744611 0.0590390489 0.0051909463 0.0212450000 224630986 95654128 760807424 -0.5194314122 0.0518078804 -0.1608898789 288 1311867180.0309770107 0.0463257842 0.0515562365 0.0590390489 0.0051826274 0.0204200000 224634570 95654128 760807424 -0.5211466551 0.0525315031 -0.1613941491 289 1311867180.0626471043 0.0463149175 0.0515381005 0.0590390489 0.0051744715 0.0204360000 224636442 95654128 760807424 -0.5216009617 0.0509788655 -0.1598347127 290 1311867180.0947730541 0.0470201597 0.0515225214 0.0590390489 0.0051662860 0.0207680000 224810226 95654128 760807424 -0.5224332809 0.0528064258 -0.1605358273 291 1311867180.1307730675 0.0477686301 0.0515096214 0.0590390489 0.0051578081 0.0204440000 224813810 95654128 760807424 -0.5186653733 0.0526409149 -0.1579925120 292 1311867180.1636900902 0.0471742079 0.0514947741 0.0590390489 0.0051702189 0.0208850000 224815594 95654128 760807424 -0.5159828663 0.0521802418 -0.1578373611 293 1311867180.1949090958 0.0474863686 0.0514810935 0.0590390489 0.0051619988 0.0204520000 224819154 95654128 760807424 -0.5158435702 0.0517191514 -0.1579400003 294 1311867180.2308139801 0.0480185971 0.0514693163 0.0590390489 0.0051575581 0.0205110000 224820882 95654128 760807424 -0.5151769519 0.0523778275 -0.1588003635 295 1311867180.2637619972 0.0471306704 0.0514546091 0.0590390489 0.0051780915 0.0309330000 224824410 95654128 760807424 -0.5161529779 0.0507427081 -0.1602555364 296 1311867180.2947549820 0.0471592695 0.0514400978 0.0590390489 0.0051715872 0.0213500000 224827826 95654128 760807424 -0.5164937973 0.0519341715 -0.1618033499 297 1311867180.3308670521 0.0466760434 0.0514240572 0.0590390489 0.0051680299 0.0204710000 224829810 95654128 760807424 -0.5136086941 0.0514811575 -0.1614572406 298 1311867180.3658289909 0.0474443398 0.0514107024 0.0590390489 0.0051597650 0.0207300000 224833338 95654128 760807424 -0.5113772750 0.0518509671 -0.1607247144 299 1311867180.3964109421 0.0479248799 0.0513990442 0.0590390489 0.0051533000 0.0205590000 224836810 95654128 760807424 -0.5112862587 0.0515447557 -0.1606418192 300 1311867180.4309151173 0.0470562540 0.0513845682 0.0590390489 0.0051453300 0.0205110000 224838538 95654128 760807424 -0.5107496977 0.0510869101 -0.1620132476 301 1311867180.4670670033 0.0464803055 0.0513682750 0.0590390489 0.0051379440 0.0209940000 224842322 95654128 760807424 -0.5104094148 0.0509122647 -0.1631014049 302 1311867180.4947559834 0.0469668023 0.0513537005 0.0590390489 0.0051460463 0.0223910000 224845770 95654128 760807424 -0.5099012852 0.0502901524 -0.1625692546 303 1311867180.5308880806 0.0479641259 0.0513425138 0.0590390489 0.0051422017 0.0224780000 224847810 95654128 760807424 -0.5087182522 0.0522532202 -0.1624591202 304 1311867180.5629510880 0.0481866896 0.0513321328 0.0590390489 0.0051341704 0.0257050000 224851282 95654128 760807424 -0.5072326660 0.0527130365 -0.1620680094 305 1311867180.5946910381 0.0473231524 0.0513189886 0.0590390489 0.0051265556 0.0219720000 224853154 95654128 760807424 -0.5051813126 0.0517955311 -0.1618946791 306 1311867180.6308128834 0.0480416864 0.0513082785 0.0590390489 0.0051182522 0.0221090000 224856738 95654128 760807424 -0.5054184198 0.0513284542 -0.1610866338 307 1311867180.6640911102 0.0478524528 0.0512970217 0.0590390489 0.0051358750 0.0255700000 224860410 95654128 760807424 -0.5051662922 0.0524577983 -0.1618177891 308 1311867180.6957859993 0.0466186553 0.0512818322 0.0590390489 0.0051299267 0.0220930000 224862082 95654128 760807424 -0.5038873553 0.0506099686 -0.1617582440 309 1311867180.7309739590 0.0469878837 0.0512679360 0.0590390489 0.0051266650 0.0256590000 224865866 95654128 760807424 -0.5035957098 0.0525156967 -0.1627774984 310 1311867180.7650830746 0.0479814932 0.0512573345 0.0590390489 0.0051443326 0.0240010000 224867594 95654128 760807424 -0.5027434230 0.0510855131 -0.1602186859 311 1311867180.7949280739 0.0471648239 0.0512441753 0.0590390489 0.0051458251 0.0223620000 224871154 95654128 760807424 -0.5005654693 0.0529928394 -0.1615953594 312 1311867180.8309240341 0.0467775837 0.0512298593 0.0590390489 0.0051387957 0.0243770000 224874794 95654128 760807424 -0.5002925396 0.0512829162 -0.1609314531 313 1311867180.8652698994 0.0473643541 0.0512175095 0.0590390489 0.0051310095 0.0257960000 224876722 95654128 760807424 -0.4991105497 0.0513961762 -0.1597850472 314 1311867180.8966469765 0.0474682115 0.0512055690 0.0590390489 0.0051246973 0.0220310000 224880194 95654128 760807424 -0.4983724654 0.0517127737 -0.1602553725 315 1311867180.9306049347 0.0476362631 0.0511942379 0.0590390489 0.0051313815 0.0224230000 224882122 95654128 760807424 -0.4985011518 0.0518914536 -0.1603793353 316 1311867180.9631829262 0.0477095693 0.0511832105 0.0590390489 0.0051277587 0.0252850000 224885594 95654128 760807424 -0.4977645278 0.0529288203 -0.1611278653 317 1311867180.9948179722 0.0474021360 0.0511712828 0.0590390489 0.0051200559 0.0218550000 224889210 95654128 760807424 -0.4951216877 0.0528802536 -0.1605778635 318 1311867181.0308310986 0.0478149392 0.0511607283 0.0590390489 0.0051152708 0.0223210000 224890994 95654128 760807424 -0.4940679371 0.0515581705 -0.1593705118 319 1311867181.0627830029 0.0492331833 0.0511546858 0.0590390489 0.0051190094 0.0250930000 224894706 95654128 760807424 -0.4921689630 0.0534634218 -0.1591816545 320 1311867181.0948719978 0.0482626148 0.0511456481 0.0590390489 0.0051242927 0.0237010000 224898178 95654128 760807424 -0.4898700714 0.0527758822 -0.1594036520 321 1311867181.1311910152 0.0469927862 0.0511327108 0.0590390489 0.0051221144 0.0220530000 224900162 95654128 760807424 -0.4846013784 0.0509821959 -0.1584346443 322 1311867181.1629528999 0.0479568169 0.0511228478 0.0590390489 0.0051357760 0.0292190000 224903634 95654128 760807424 -0.4834536314 0.0511005670 -0.1582270414 323 1311867181.1972830296 0.0487524197 0.0511155090 0.0590390489 0.0051295064 0.0226250000 224905562 95654128 760807424 -0.4823483229 0.0520137958 -0.1583807468 324 1311867181.2342460155 0.0486404821 0.0511078700 0.0590390489 0.0051234076 0.0225190000 224909202 95654128 760807424 -0.4805875719 0.0509700030 -0.1585569233 325 1311867181.2629361153 0.0480676554 0.0510985155 0.0590390489 0.0051185382 0.0223950000 224912762 95654128 760807424 -0.4799883366 0.0499222763 -0.1593149304 326 1311867181.2948091030 0.0474020950 0.0510871768 0.0590390489 0.0051135040 0.0224370000 224914378 95654128 760807424 -0.4747985899 0.0495726652 -0.1580445170 327 1311867181.3317139149 0.0474657826 0.0510761022 0.0590390489 0.0051098066 0.0259760000 224918218 95654128 760807424 -0.4726694524 0.0505410545 -0.1582685411 328 1311867181.3626708984 0.0481089801 0.0510670561 0.0590390489 0.0051110577 0.0231850000 224919834 95654128 760807424 -0.4714047611 0.0527755544 -0.1587846130 329 1311867181.3948218822 0.0476925261 0.0510567992 0.0590390489 0.0051052865 0.0224800000 224923522 95654128 760807424 -0.4711410403 0.0494999141 -0.1574843079 330 1311867181.4308950901 0.0481290370 0.0510479272 0.0590390489 0.0051006038 0.0256400000 224926994 95654128 760807424 -0.4670718014 0.0522372350 -0.1576717496 331 1311867181.4628310204 0.0492016561 0.0510423493 0.0590390489 0.0050942989 0.0257420000 224928866 95654128 760807424 -0.4661881328 0.0520029813 -0.1568125337 332 1311867181.4963610172 0.0486805886 0.0510352356 0.0590390489 0.0051055491 0.0225020000 224932394 95654128 760807424 -0.4640967250 0.0515381545 -0.1566120535 333 1311867181.5359110832 0.0493357889 0.0510301321 0.0590390489 0.0051028607 0.0222940000 224934434 95654128 760807424 -0.4635752141 0.0495424271 -0.1555869877 334 1311867181.5671720505 0.0495157875 0.0510255982 0.0590390489 0.0050965210 0.0225370000 225108814 95654128 760807424 -0.4617615640 0.0489036478 -0.1554328948 335 1311867181.5948610306 0.0495705158 0.0510212546 0.0590390489 0.0050928388 0.0224950000 225112318 95654128 760807424 -0.4608005881 0.0511421263 -0.1571702659 336 1311867181.6313591003 0.0491312407 0.0510156296 0.0590390489 0.0050914132 0.0224340000 225114158 95654128 760807424 -0.4588157833 0.0487086996 -0.1564827710 337 1311867181.6628570557 0.0502838232 0.0510134581 0.0590390489 0.0050854300 0.0224390000 225117830 95654128 760807424 -0.4570172727 0.0485484265 -0.1559424698 338 1311867181.6949229240 0.0484241433 0.0510057974 0.0590390489 0.0050883190 0.0224290000 225121246 95654128 760807424 -0.4536791146 0.0485736690 -0.1578685939 339 1311867181.7310829163 0.0506708585 0.0510048093 0.0590390489 0.0051181068 0.0255230000 225123230 95654128 760807424 -0.4513942003 0.0468452759 -0.1549389213 340 1311867181.7634840012 0.0503492579 0.0510028812 0.0590390489 0.0051121219 0.0255370000 225126758 95654128 760807424 -0.4506591558 0.0477157347 -0.1568359584 341 1311867181.7948980331 0.0508642085 0.0510024746 0.0590390489 0.0051119314 0.0225510000 225128518 95654128 760807424 -0.4505150914 0.0474196002 -0.1577099562 342 1311867181.8308010101 0.0502060093 0.0510001457 0.0590390489 0.0051109578 0.0266940000 225132102 95654128 760807424 -0.4478351176 0.0450612456 -0.1570598930 343 1311867181.8627979755 0.0508479998 0.0509997022 0.0590390489 0.0051065793 0.0225410000 225135830 95654128 760807424 -0.4459471703 0.0471358746 -0.1574078947 344 1311867181.8949289322 0.0498589128 0.0509963859 0.0590390489 0.0051037408 0.0258320000 225137446 95654128 760807424 -0.4418899119 0.0453445092 -0.1567001790 345 1311867181.9307990074 0.0501493663 0.0509939308 0.0590390489 0.0051073281 0.0225770000 225141286 95654128 760807424 -0.4410292804 0.0428317003 -0.1558358073 346 1311867181.9629189968 0.0500634015 0.0509912414 0.0590390489 0.0051013661 0.0225270000 225142958 95654128 760807424 -0.4392581284 0.0443505384 -0.1570667624 347 1311867181.9955599308 0.0501417965 0.0509887934 0.0590390489 0.0051229748 0.0224920000 225146630 95654128 760807424 -0.4377363622 0.0427608825 -0.1554799080 348 1311867182.0320639610 0.0506170616 0.0509877252 0.0590390489 0.0051158569 0.0225230000 225150214 95654128 760807424 -0.4359479547 0.0432419404 -0.1551536322 349 1311867182.0629000664 0.0502372906 0.0509855750 0.0590390489 0.0051097872 0.0266390000 225152086 95654128 760807424 -0.4342613220 0.0425807871 -0.1550591141 350 1311867182.0948839188 0.0501169264 0.0509830931 0.0590390489 0.0051113127 0.0226140000 225155502 95654128 760807424 -0.4324168265 0.0426405817 -0.1552152336 351 1311867182.1314840317 0.0503205545 0.0509812056 0.0590390489 0.0051051792 0.0226320000 225157542 95654128 760807424 -0.4298426211 0.0416464992 -0.1538409889 352 1311867182.1629920006 0.0504848696 0.0509797955 0.0590390489 0.0050990896 0.0225200000 225161014 95654128 760807424 -0.4288736880 0.0414413884 -0.1536905020 353 1311867182.1994500160 0.0510045625 0.0509798657 0.0590390489 0.0050974499 0.0256430000 225164742 95654128 760807424 -0.4259853661 0.0420433991 -0.1528205276 354 1311867182.2307739258 0.0509848520 0.0509798798 0.0590390489 0.0050956883 0.0225360000 225166358 95654128 760807424 -0.4239739478 0.0408570804 -0.1519531310 355 1311867182.2629120350 0.0514088310 0.0509810881 0.0590390489 0.0050895196 0.0225190000 225170086 95654128 760807424 -0.4236266911 0.0402530842 -0.1515861452 356 1311867182.2973539829 0.0514209419 0.0509823236 0.0590390489 0.0050873371 0.0225980000 225173614 95654128 760807424 -0.4213400781 0.0387763232 -0.1507453471 357 1311867182.3308460712 0.0514677428 0.0509836833 0.0590390489 0.0051023862 0.0225210000 225175486 95654128 760807424 -0.4210140705 0.0391228497 -0.1516430229 358 1311867182.3629670143 0.0520939566 0.0509867847 0.0590390489 0.0051159391 0.0263030000 225179014 95654128 760807424 -0.4198578000 0.0392032079 -0.1509330124 359 1311867182.3990368843 0.0529742911 0.0509923209 0.0590390489 0.0051214767 0.0226200000 225180942 95654128 760807424 -0.4194833338 0.0384763107 -0.1501312554 360 1311867182.4308118820 0.0538955852 0.0510003855 0.0590390489 0.0051173697 0.0225120000 225184414 95654128 760807424 -0.4177066684 0.0374785960 -0.1488671601 361 1311867182.4629440308 0.0540150329 0.0510087363 0.0590390489 0.0051178613 0.0260120000 225188142 95654128 760807424 -0.4143718183 0.0375736207 -0.1486415118 362 1311867182.4969599247 0.0553766191 0.0510208023 0.0590390489 0.0051111316 0.0226400000 225189814 95654128 760807424 -0.4121062160 0.0353863463 -0.1467683166 363 1311867182.5309500694 0.0558153354 0.0510340104 0.0590390489 0.0051090469 0.0225830000 225193542 95654128 760807424 -0.4125318229 0.0349185430 -0.1482289881 364 1311867182.5629699230 0.0557048246 0.0510468423 0.0590390489 0.0051074695 0.0225760000 225195214 95654128 760807424 -0.4119942188 0.0350261107 -0.1506354809 365 1311867182.6036369801 0.0568879545 0.0510628453 0.0590390489 0.0051016887 0.0224320000 225199110 95654128 760807424 -0.4102440774 0.0341270790 -0.1497866362 366 1311867182.6308450699 0.0562472343 0.0510770103 0.0590390489 0.0051137654 0.0227990000 225202414 95654128 760807424 -0.4092484117 0.0333251469 -0.1515995115 367 1311867182.6635921001 0.0571367219 0.0510935218 0.0590390489 0.0051079215 0.0228320000 225204342 95654128 760807424 -0.4076693654 0.0348538756 -0.1520724595 368 1311867182.6970019341 0.0581845231 0.0511127908 0.0590390489 0.0051060002 0.0229370000 225207814 95654128 760807424 -0.4050379992 0.0333733223 -0.1508308649 369 1311867182.7330639362 0.0578790270 0.0511311275 0.0590390489 0.0051039444 0.0227180000 225209798 95654128 760807424 -0.4040778875 0.0313310511 -0.1518021077 370 1311867182.7631130219 0.0571671948 0.0511474412 0.0590390489 0.0050978011 0.0226670000 225213102 95654128 760807424 -0.4003728032 0.0308644082 -0.1522537470 371 1311867182.7970550060 0.0582335889 0.0511665414 0.0590390489 0.0050919557 0.0226780000 225216886 95654128 760807424 -0.3976835907 0.0310596973 -0.1514973491 372 1311867182.8306989670 0.0576163754 0.0511838796 0.0590390489 0.0050855457 0.0227070000 225389866 95654128 760807424 -0.3962099850 0.0302167051 -0.1527979076 373 1311867182.8641169071 0.0570053682 0.0511994868 0.0590390489 0.0050912926 0.0288720000 225393538 95654128 760807424 -0.3946694136 0.0297076199 -0.1535512060 374 1311867182.8969969749 0.0566704497 0.0512141151 0.0590390489 0.0050851780 0.0230610000 225397066 95654128 760807424 -0.3929233849 0.0293497834 -0.1539540142 375 1311867182.9318990707 0.0552594885 0.0512249027 0.0590390489 0.0050843250 0.0226750000 225398994 95654128 760807424 -0.3905736208 0.0292991083 -0.1553535461 376 1311867182.9630720615 0.0554088578 0.0512360303 0.0590390489 0.0050780616 0.0227050000 225402466 95654128 760807424 -0.3878723681 0.0288731176 -0.1539980918 377 1311867182.9983949661 0.0576783232 0.0512531186 0.0590390489 0.0051061667 0.0227350000 225404394 95654128 760807424 -0.3870547414 0.0289405640 -0.1516685933 378 1311867183.0308830738 0.0583712235 0.0512719495 0.0590390489 0.0051000996 0.0227330000 225407866 95654128 760807424 -0.3855239451 0.0303692687 -0.1517956257 379 1311867183.0628600121 0.0564232692 0.0512855414 0.0590390489 0.0051028117 0.0227420000 225411594 95654128 760807424 -0.3819430470 0.0284820702 -0.1520348191 380 1311867183.1000499725 0.0586052351 0.0513048038 0.0590390489 0.0051083040 0.0227180000 225413322 95654128 760807424 -0.3807258010 0.0286804438 -0.1493005455 381 1311867183.1344780922 0.0582111888 0.0513229308 0.0590390489 0.0051023605 0.0264700000 225417106 95654128 760807424 -0.3797106445 0.0300471503 -0.1509482563 382 1311867183.1673240662 0.0573990829 0.0513388369 0.0590390489 0.0050961813 0.0228080000 225418834 95654128 760807424 -0.3787119985 0.0287662204 -0.1511494517 383 1311867183.2004919052 0.0583777092 0.0513572152 0.0590390489 0.0050900794 0.0229830000 225422506 95654128 760807424 -0.3757645786 0.0276875310 -0.1479769051 384 1311867183.2311279774 0.0575108230 0.0513732402 0.0590390489 0.0050846207 0.0227880000 225425922 95654128 760807424 -0.3724042177 0.0290801357 -0.1489402652 385 1311867183.2633349895 0.0571338907 0.0513882029 0.0590390489 0.0050798286 0.0227870000 225427850 95654128 760807424 -0.3733014464 0.0262826551 -0.1489427537 386 1311867183.2991099358 0.0585813969 0.0514068381 0.0590390489 0.0050821501 0.0226870000 225431378 95654128 760807424 -0.3700753748 0.0257595535 -0.1456782818 387 1311867183.3320920467 0.0584404022 0.0514250127 0.0590390489 0.0050817393 0.0227200000 225433306 95654128 760807424 -0.3699210584 0.0272710323 -0.1479865611 388 1311867183.3695240021 0.0594272129 0.0514456370 0.0594272129 0.0050757891 0.0227110000 225436946 95654128 760807424 -0.3702135384 0.0252969079 -0.1470373273 389 1311867183.3986210823 0.0600689203 0.0514678048 0.0600689203 0.0050701829 0.0227090000 225440506 95654128 760807424 -0.3675521612 0.0252842344 -0.1457509845 390 1311867183.4311549664 0.0595503114 0.0514885292 0.0600689203 0.0050718684 0.0328030000 225442178 95654128 760807424 -0.3664841354 0.0257323384 -0.1475963145 391 1311867183.4667448997 0.0582162142 0.0515057355 0.0600689203 0.0050671267 0.0233240000 225445962 95654128 760807424 -0.3635872602 0.0240346026 -0.1480143368 392 1311867183.4988338947 0.0602409765 0.0515280193 0.0602409765 0.0050715753 0.0227020000 225449490 95654128 760807424 -0.3624018133 0.0244409144 -0.1457009166 393 1311867183.5321829319 0.0600997731 0.0515498304 0.0602409765 0.0050678085 0.0227360000 225451362 95654128 760807424 -0.3601674438 0.0251866095 -0.1459386349 394 1311867183.5661609173 0.0574027039 0.0515646854 0.0602409765 0.0050685786 0.0227380000 225454890 95654128 760807424 -0.3560745120 0.0229208507 -0.1466246545 395 1311867183.5985479355 0.0605836622 0.0515875182 0.0605836622 0.0050661638 0.0227070000 225456762 95654128 760807424 -0.3559966385 0.0233291853 -0.1439872384 396 1311867183.6310880184 0.0599250570 0.0516085726 0.0605836622 0.0050735849 0.0229380000 225460234 95654128 760807424 -0.3538441956 0.0238358360 -0.1450743824 397 1311867183.6649260521 0.0608277284 0.0516317947 0.0608277284 0.0050704395 0.0227510000 225463962 95654128 760807424 -0.3536550105 0.0234829709 -0.1447733641 398 1311867183.6993949413 0.0611662827 0.0516557507 0.0611662827 0.0050656725 0.0324220000 225465746 95654128 760807424 -0.3500202596 0.0226303004 -0.1426919252 399 1311867183.7308928967 0.0615640990 0.0516805836 0.0615640990 0.0050635190 0.0232900000 225469306 95654128 760807424 -0.3484259546 0.0223409943 -0.1422933936 400 1311867183.7676479816 0.0603137761 0.0517021666 0.0615640990 0.0050756488 0.0227730000 225471146 95654128 760807424 -0.3440751135 0.0209835917 -0.1415276825 401 1311867183.7971870899 0.0613386966 0.0517261979 0.0615640990 0.0050700923 0.0228180000 225474706 95654128 760807424 -0.3431518078 0.0212896056 -0.1408498287 402 1311867183.8309071064 0.0602894798 0.0517474996 0.0615640990 0.0050655491 0.0228230000 225478178 95654128 760807424 -0.3406271040 0.0185655598 -0.1399130672 403 1311867183.8655049801 0.0605088621 0.0517692399 0.0615640990 0.0050600905 0.0227730000 225480106 95654128 760807424 -0.3378444314 0.0178803280 -0.1388554722 404 1311867183.8970971107 0.0610586926 0.0517922336 0.0615640990 0.0050562603 0.0228010000 225483522 95654128 760807424 -0.3367240429 0.0195613634 -0.1396038979 405 1311867183.9314939976 0.0605382808 0.0518138288 0.0615640990 0.0050505366 0.0228030000 225485506 95654128 760807424 -0.3337085247 0.0174183846 -0.1379791200 406 1311867183.9658319950 0.0597826838 0.0518334565 0.0615640990 0.0050491517 0.0266880000 225488978 95654128 760807424 -0.3322789967 0.0159581155 -0.1379102021 407 1311867183.9966781139 0.0603866577 0.0518544717 0.0615640990 0.0050469328 0.0237230000 225492650 95654128 760807424 -0.3318474591 0.0157445166 -0.1378611773 408 1311867184.0309689045 0.0608809516 0.0518765955 0.0615640990 0.0050698262 0.0228460000 225494378 95654128 760807424 -0.3313999772 0.0154855726 -0.1378447264 409 1311867184.0647850037 0.0608780831 0.0518986040 0.0615640990 0.0050644729 0.0228730000 225498106 95654128 760807424 -0.3305009902 0.0141216787 -0.1368751526 410 1311867184.0968890190 0.0600303523 0.0519184375 0.0615640990 0.0050604121 0.0229610000 225501522 95654128 760807424 -0.3267958164 0.0142455045 -0.1365247965 411 1311867184.1312260628 0.0605446808 0.0519394259 0.0615640990 0.0050542494 0.0228180000 225503450 95654128 760807424 -0.3254191279 0.0136466287 -0.1353308260 412 1311867184.1650640965 0.0608703643 0.0519611030 0.0615640990 0.0050494476 0.0228740000 225506938 95654128 760807424 -0.3245083690 0.0136108370 -0.1351428181 413 1311867184.1969559193 0.0611556061 0.0519833657 0.0615640990 0.0050456361 0.0228340000 225508866 95654128 760807424 -0.3217042983 0.0158335678 -0.1355905384 414 1311867184.2309360504 0.0603475645 0.0520035691 0.0615640990 0.0050406911 0.0228150000 225512394 95654128 760807424 -0.3202521801 0.0126638617 -0.1344152987 415 1311867184.2681369781 0.0611878410 0.0520256999 0.0615640990 0.0050376034 0.0320810000 225516234 95654128 760807424 -0.3181371987 0.0119112208 -0.1329633147 416 1311867184.2983899117 0.0610167682 0.0520473130 0.0615640990 0.0050435486 0.0232730000 225517850 95654128 760807424 -0.3143910766 0.0150889177 -0.1338649392 417 1311867184.3314700127 0.0613090880 0.0520695235 0.0615640990 0.0050397946 0.0229610000 225692866 95654128 760807424 -0.3138158023 0.0136856074 -0.1329259127 418 1311867184.3697841167 0.0609485470 0.0520907652 0.0615640990 0.0050392029 0.0260590000 225694706 95654128 760807424 -0.3121953309 0.0113660172 -0.1324602365 419 1311867184.4000220299 0.0597301610 0.0521089976 0.0615640990 0.0050568775 0.0228920000 225698322 95654128 760807424 -0.3076759875 0.0128931943 -0.1338494122 420 1311867184.4310610294 0.0608422384 0.0521297911 0.0615640990 0.0050541140 0.0271010000 225701794 95654128 760807424 -0.3073253930 0.0128767751 -0.1334102005 421 1311867184.4655809402 0.0619392283 0.0521530914 0.0619392283 0.0050494148 0.0229900000 225703722 95654128 760807424 -0.3055522144 0.0110689364 -0.1314258724 422 1311867184.5037670135 0.0613462962 0.0521748762 0.0619392283 0.0051028498 0.0263420000 225707362 95654128 760807424 -0.3015951216 0.0100400159 -0.1317669749 423 1311867184.5310881138 0.0616188869 0.0521972025 0.0619392283 0.0051391529 0.0332960000 225709122 95654128 760807424 -0.2983550429 0.0113412580 -0.1328062713 424 1311867184.5682930946 0.0622967295 0.0522210221 0.0622967295 0.0051368821 0.0235340000 225712762 95654128 760807424 -0.2957256138 0.0104797529 -0.1322618723 425 1311867184.6018071175 0.0627804101 0.0522458678 0.0627804101 0.0051310683 0.0259330000 225716434 95654128 760807424 -0.2946542203 0.0093682623 -0.1320549846 426 1311867184.6367399693 0.0615835041 0.0522677871 0.0627804101 0.0051309897 0.0229200000 225718218 95654128 760807424 -0.2911639214 0.0081861038 -0.1325422078 427 1311867184.6662440300 0.0617686622 0.0522900374 0.0627804101 0.0051337376 0.0229790000 225721778 95654128 760807424 -0.2884349227 0.0054438775 -0.1302776486 428 1311867184.6994929314 0.0611846000 0.0523108191 0.0627804101 0.0051289908 0.0228750000 225725362 95654128 760807424 -0.2853353918 0.0053518657 -0.1307045072 429 1311867184.7359158993 0.0621991679 0.0523338688 0.0627804101 0.0051306161 0.0229490000 225727234 95654128 760807424 -0.2841024101 0.0053472165 -0.1305758804 430 1311867184.7690689564 0.0615856461 0.0523553846 0.0627804101 0.0051330719 0.0229300000 225730818 95654128 760807424 -0.2806287706 0.0019776251 -0.1285485774 431 1311867184.8001279831 0.0605576746 0.0523744154 0.0627804101 0.0051384408 0.0293190000 225732634 95654128 760807424 -0.2767926455 0.0018429711 -0.1288664788 432 1311867184.8348441124 0.0607097857 0.0523937103 0.0627804101 0.0051326985 0.0233870000 225736138 95654128 760807424 -0.2734407783 0.0014756343 -0.1277479082 433 1311867184.8690660000 0.0614695027 0.0524146705 0.0627804101 0.0051282151 0.0229280000 225739866 95654128 760807424 -0.2719866037 0.0004151848 -0.1262055039 434 1311867184.9055209160 0.0614379793 0.0524354616 0.0627804101 0.0051245901 0.0230480000 225912078 95654128 760807424 -0.2691517770 0.0007845807 -0.1260085255 435 1311867184.9332280159 0.0611544214 0.0524555051 0.0627804101 0.0051253805 0.0229260000 225915582 95654128 760807424 -0.2674397826 -0.0007551067 -0.1250428110 436 1311867184.9656410217 0.0613246821 0.0524758473 0.0627804101 0.0051206258 0.0229250000 225917254 95654128 760807424 -0.2635149360 -0.0028508296 -0.1214298978 437 1311867184.9983251095 0.0613960288 0.0524962596 0.0627804101 0.0051194093 0.0229270000 225920982 95654128 760807424 -0.2611933351 -0.0027323966 -0.1209298968 438 1311867185.0360550880 0.0614551865 0.0525167138 0.0627804101 0.0051149310 0.0229910000 225924566 95654128 760807424 -0.2561051250 -0.0031329147 -0.1183257177 439 1311867185.0652348995 0.0618482195 0.0525379701 0.0627804101 0.0051106819 0.0333140000 225926382 95654128 760807424 -0.2533754706 -0.0043707313 -0.1161465272 440 1311867185.0991280079 0.0614576638 0.0525582421 0.0627804101 0.0051103086 0.0235660000 225929910 95654128 760807424 -0.2514068484 -0.0043126163 -0.1161534563 441 1311867185.1360778809 0.0612441115 0.0525779379 0.0627804101 0.0051089879 0.0229700000 225931894 95654128 760807424 -0.2465937287 -0.0044799382 -0.1138612255 442 1311867185.1648709774 0.0613087602 0.0525976909 0.0627804101 0.0051039711 0.0229620000 225935310 95654128 760807424 -0.2434352338 -0.0069103357 -0.1106526554 443 1311867185.2000720501 0.0618491657 0.0526185746 0.0627804101 0.0051002062 0.0229670000 225938982 95654128 760807424 -0.2401553690 -0.0054807072 -0.1098640710 444 1311867185.2342920303 0.0627951920 0.0526414949 0.0627951920 0.0051032941 0.0229440000 225940766 95654128 760807424 -0.2385907024 -0.0063162916 -0.1079653203 445 1311867185.2663950920 0.0617230348 0.0526619029 0.0627951920 0.0050993853 0.0237340000 225944494 95654128 760807424 -0.2332631648 -0.0084370002 -0.1055725068 446 1311867185.2970550060 0.0617465228 0.0526822720 0.0627951920 0.0051271475 0.0263710000 225947910 95654128 760807424 -0.2290211320 -0.0067917369 -0.1044159234 447 1311867185.3360140324 0.0615378655 0.0527020832 0.0627951920 0.0051215657 0.0357880000 226013326 95654128 760807424 -0.2270792127 -0.0090749953 -0.1026724875 448 1311867185.3681778908 0.0608523265 0.0527202757 0.0627951920 0.0051162357 0.0234170000 226016854 95654128 760807424 -0.2227644473 -0.0107331295 -0.1008309871 449 1311867185.4036509991 0.0618530326 0.0527406159 0.0627951920 0.0051147108 0.0230770000 226018782 95654128 760807424 -0.2212058157 -0.0101386057 -0.0999482200 450 1311867185.4386389256 0.0616543852 0.0527604243 0.0627951920 0.0051096401 0.0286210000 226022374 95654128 760807424 -0.2189397514 -0.0100096455 -0.0997336060 451 1311867185.4655449390 0.0622393340 0.0527814418 0.0627951920 0.0051084468 0.0244820000 226196354 95654128 760807424 -0.2158107609 -0.0132574886 -0.0961209908 452 1311867185.5013909340 0.0626102760 0.0528031870 0.0627951920 0.0051161783 0.0243740000 226198526 95654128 760807424 -0.2136970460 -0.0125680985 -0.0961583331 453 1311867185.5336329937 0.0617013946 0.0528228298 0.0627951920 0.0051240477 0.0243490000 226202262 95654128 760807424 -0.2088574171 -0.0128181325 -0.0954968631 454 1311867185.5666799545 0.0624409132 0.0528440151 0.0627951920 0.0051190911 0.0285360000 226203926 95654128 760807424 -0.2071523815 -0.0144427298 -0.0941553712 455 1311867185.5970540047 0.0609767660 0.0528618892 0.0627951920 0.0051185695 0.0359830000 226207606 95654128 760807424 -0.2018792927 -0.0161463264 -0.0933730453 456 1311867185.6329469681 0.0613389574 0.0528804793 0.0627951920 0.0051290750 0.0250100000 226211510 95654128 760807424 -0.1973114908 -0.0148178469 -0.0931781083 457 1311867185.6664180756 0.0617098138 0.0528997995 0.0627951920 0.0051286037 0.0244030000 226213574 95654128 760807424 -0.1949449033 -0.0164590254 -0.0917480364 458 1311867185.6973390579 0.0616940707 0.0529190010 0.0627951920 0.0051259370 0.0244010000 226217110 95654128 760807424 -0.1933356225 -0.0178782828 -0.0910879299 459 1311867185.7351899147 0.0628221557 0.0529405765 0.0628221557 0.0051243004 0.0283430000 226219286 95654128 760807424 -0.1915565878 -0.0166013017 -0.0903646797 460 1311867185.7649769783 0.0607278198 0.0529575053 0.0628221557 0.0051242964 0.0244560000 226222822 95654128 760807424 -0.1852622330 -0.0211546514 -0.0876173526 461 1311867185.7989649773 0.0615980960 0.0529762484 0.0628221557 0.0051431804 0.0243780000 226226430 95654128 760807424 -0.1831178665 -0.0211659521 -0.0868375301 462 1311867185.8327999115 0.0611194596 0.0529938744 0.0628221557 0.0051378865 0.0244680000 226228406 95654128 760807424 -0.1796072423 -0.0207126699 -0.0866879076 463 1311867185.8649098873 0.0614135861 0.0530120595 0.0628221557 0.0051323738 0.0244760000 226232014 95654128 760807424 -0.1758639365 -0.0209593289 -0.0849070251 464 1311867185.9030420780 0.0616620034 0.0530307016 0.0628221557 0.0051291683 0.0245680000 226235662 95654128 760807424 -0.1742278785 -0.0221769623 -0.0835810080 465 1311867185.9396789074 0.0597926974 0.0530452436 0.0628221557 0.0051272516 0.0244730000 226237766 95654128 760807424 -0.1698524058 -0.0228912756 -0.0833954066 466 1311867185.9650609493 0.0582856871 0.0530564892 0.0628221557 0.0051411005 0.0246090000 226241022 95654128 760807424 -0.1661442965 -0.0275418777 -0.0809316188 467 1311867186.0039470196 0.0594905391 0.0530702666 0.0628221557 0.0051487761 0.0246050000 226243054 95654128 760807424 -0.1651960015 -0.0266977344 -0.0802547485 468 1311867186.0396919250 0.0608268939 0.0530868406 0.0628221557 0.0051523352 0.0244640000 226246830 95654128 760807424 -0.1654511988 -0.0248095002 -0.0800232217 469 1311867186.0653240681 0.0596901365 0.0531009201 0.0628221557 0.0051599107 0.0245800000 226421378 95654128 760807424 -0.1629924178 -0.0288387556 -0.0776994005 470 1311867186.1047339439 0.0599312596 0.0531154527 0.0628221557 0.0051550111 0.0244940000 226423218 95654128 760807424 -0.1636207104 -0.0290476382 -0.0781301111 471 1311867186.1361179352 0.0594459362 0.0531288932 0.0628221557 0.0051514545 0.0374890000 226426898 95654128 760807424 -0.1598252952 -0.0292259455 -0.0773594379 472 1311867186.1649448872 0.0600849986 0.0531436307 0.0628221557 0.0051465622 0.0250920000 226428578 95654128 760807424 -0.1594523937 -0.0303480439 -0.0763537511 473 1311867186.2044749260 0.0597384609 0.0531575733 0.0628221557 0.0051415326 0.0245820000 226432538 95654128 760807424 -0.1576822847 -0.0321602821 -0.0757111758 474 1311867186.2359659672 0.0607485697 0.0531735881 0.0628221557 0.0051397721 0.0245650000 226436018 95654128 760807424 -0.1562181413 -0.0310063511 -0.0750222430 475 1311867186.2674899101 0.0607812777 0.0531896043 0.0628221557 0.0051345699 0.0286250000 226437954 95654128 760807424 -0.1531214416 -0.0315311998 -0.0741555169 476 1311867186.3030838966 0.0617203340 0.0532075260 0.0628221557 0.0051329693 0.0246270000 226441602 95654128 760807424 -0.1515412182 -0.0305870529 -0.0735287294 477 1311867186.3349270821 0.0608896688 0.0532236311 0.0628221557 0.0051332540 0.0245960000 226443482 95654128 760807424 -0.1482973248 -0.0318481028 -0.0724442378 478 1311867186.3670160770 0.0615356192 0.0532410202 0.0628221557 0.0051308464 0.0245780000 226447090 95654128 760807424 -0.1473444104 -0.0346010290 -0.0700809583 479 1311867186.4019849300 0.0612631701 0.0532577679 0.0628221557 0.0051360077 0.0288430000 226450882 95654128 760807424 -0.1447499543 -0.0331018083 -0.0705331415 480 1311867186.4360210896 0.0596556701 0.0532710968 0.0628221557 0.0051315555 0.0245820000 226452546 95654128 760807424 -0.1400168389 -0.0340061374 -0.0696557388 481 1311867186.4659481049 0.0608449839 0.0532868430 0.0628221557 0.0051266781 0.0248270000 226456482 95654128 760807424 -0.1403976530 -0.0377409123 -0.0662543848 482 1311867186.5031139851 0.0605778694 0.0533019696 0.0628221557 0.0051229287 0.0248000000 226460058 95654128 760807424 -0.1377856284 -0.0361686610 -0.0666468069 483 1311867186.5363171101 0.0637187362 0.0533235364 0.0637187362 0.0051274475 0.0247900000 226462122 95654128 760807424 -0.1367953569 -0.0320920274 -0.0649245903 484 1311867186.5651130676 0.0614376627 0.0533403011 0.0637187362 0.0051342110 0.0284230000 226465730 95654128 760807424 -0.1350387186 -0.0380959660 -0.0634720922 485 1311867186.6014220715 0.0620939396 0.0533583498 0.0637187362 0.0051303807 0.0248400000 226467782 95654128 760807424 -0.1342652291 -0.0383566767 -0.0633592531 486 1311867186.6362628937 0.0631005317 0.0533783955 0.0637187362 0.0051267574 0.0293180000 226471246 95654128 760807424 -0.1329485327 -0.0359903239 -0.0640923455 487 1311867186.6650478840 0.0622164123 0.0533965434 0.0637187362 0.0051221386 0.0307640000 226645986 95654128 760807424 -0.1293626279 -0.0366240069 -0.0638771802 488 1311867186.7043809891 0.0547356121 0.0533992874 0.0637187362 0.0052565448 0.0901760000 226735826 95654128 760807424 -0.1194000989 -0.0464194044 -0.0640857592 489 1311867186.7337749004 0.0565061234 0.0534056408 0.0637187362 0.0052745158 0.0254150000 226752250 95654128 760807424 -0.1173113734 -0.0401054360 -0.0651588738 490 1311867186.7673180103 0.0559605137 0.0534108548 0.0637187362 0.0052692766 0.0250640000 226753914 95654128 760807424 -0.1170147657 -0.0416647047 -0.0652354136 491 1311867186.8047299385 0.0561726093 0.0534164796 0.0637187362 0.0052665526 0.0250820000 226757946 95654128 760807424 -0.1162872165 -0.0438008979 -0.0645971000 492 1311867186.8340749741 0.0586482659 0.0534271133 0.0637187362 0.0052782914 0.0257580000 226761498 95654128 760807424 -0.1142228916 -0.0356834531 -0.0659177825 493 1311867186.8775999546 0.0576038472 0.0534355854 0.0637187362 0.0052749076 0.0336000000 226763770 95654128 760807424 -0.1122987419 -0.0371752344 -0.0662981793 494 1311867186.9052100182 0.0602242649 0.0534493276 0.0637187362 0.0052737951 0.0252520000 226767266 95654128 760807424 -0.1113876104 -0.0332484767 -0.0656138137 495 1311867186.9334239960 0.0603314154 0.0534632308 0.0637187362 0.0052686495 0.0250420000 226769202 95654128 760807424 -0.1070667729 -0.0317452513 -0.0653417259 496 1311867186.9663379192 0.0586423427 0.0534736726 0.0637187362 0.0052642805 0.0251050000 226943630 95654128 760807424 -0.1049195603 -0.0322627388 -0.0669001937 497 1311867187.0017139912 0.0605415367 0.0534878937 0.0637187362 0.0052613595 0.0249840000 226947246 95654128 760807424 -0.1029615998 -0.0329455212 -0.0644929782 498 1311867187.0336461067 0.0612247549 0.0535034295 0.0637187362 0.0052667231 0.0250100000 226948982 95654128 760807424 -0.0982609168 -0.0282110162 -0.0660796016 499 1311867187.0749349594 0.0584418923 0.0535133262 0.0637187362 0.0052680470 0.0249990000 226953126 95654128 760807424 -0.0963814631 -0.0315645225 -0.0673664808 500 1311867187.1016030312 0.0598432124 0.0535259860 0.0637187362 0.0052635134 0.0249460000 227126514 95654128 760807424 -0.0937428996 -0.0305304341 -0.0660991222 501 1311867187.1342070103 0.0620800033 0.0535430599 0.0637187362 0.0052621612 0.0289950000 227128386 95654128 760807424 -0.0906885266 -0.0305813439 -0.0638333857 502 1311867187.1710209846 0.0602668114 0.0535564538 0.0637187362 0.0052600740 0.0249120000 227132166 95654128 760807424 -0.0864478573 -0.0291926656 -0.0664481595 503 1311867187.2041370869 0.0586932190 0.0535666661 0.0637187362 0.0052674084 0.0248430000 227134286 95654128 760807424 -0.0843592510 -0.0321633518 -0.0675039440 504 1311867187.2331659794 0.0616994500 0.0535828026 0.0637187362 0.0052728444 0.0292200000 227137766 95654128 760807424 -0.0813456327 -0.0289980378 -0.0657902360 505 1311867187.2707629204 0.0561558157 0.0535878976 0.0637187362 0.0052805669 0.0235120000 227141550 95654128 760807424 -0.0784127563 -0.0342694260 -0.0690197274 506 1311867187.3015060425 0.0568645149 0.0535943732 0.0637187362 0.0052805892 0.0248910000 227143222 95654128 760807424 -0.0770577341 -0.0340601392 -0.0683853179 507 1311867187.3336570263 0.0609722733 0.0536089252 0.0637187362 0.0052941579 0.0249650000 227147158 95654128 760807424 -0.0747240931 -0.0280667506 -0.0672077164 508 1311867187.3707590103 0.0569296107 0.0536154620 0.0637187362 0.0053043021 0.0248800000 227148678 95654128 760807424 -0.0720521584 -0.0343407728 -0.0685156286 509 1311867187.4033529758 0.0612721257 0.0536305046 0.0637187362 0.0053277888 0.0287330000 227152470 95654128 760807424 -0.0748505369 -0.0282387026 -0.0684831440 510 1311867187.4335899353 0.0568815582 0.0536368792 0.0637187362 0.0053632216 0.0251270000 227326166 95654128 760807424 -0.0690606013 -0.0338346288 -0.0697023049 511 1311867187.4763159752 0.0599477030 0.0536492291 0.0637187362 0.0053741537 0.0250300000 227328446 95654128 760807424 -0.0691448674 -0.0296013411 -0.0701768994 512 1311867187.5056400299 0.0604827814 0.0536625759 0.0637187362 0.0053701266 0.0290060000 227331998 95654128 760807424 -0.0667746589 -0.0310777500 -0.0698486343 513 1311867187.5342190266 0.0619875602 0.0536788040 0.0637187362 0.0053754314 0.0249710000 227428086 95654128 760807424 -0.0634694025 -0.0273837149 -0.0712521151 514 1311867187.5709679127 0.0611064099 0.0536932546 0.0637187362 0.0053713314 0.0250080000 227534134 95654128 760807424 -0.0602082945 -0.0297419168 -0.0720861256 515 1311867187.6045789719 0.0609505586 0.0537073464 0.0637187362 0.0053980911 0.0250030000 227537854 95654128 760807424 -0.0569034293 -0.0293434802 -0.0730721951 516 1311867187.6353919506 0.0620411038 0.0537234971 0.0637187362 0.0054003660 0.0250570000 227539794 95654128 760807424 -0.0559560731 -0.0299852602 -0.0733676106 517 1311867187.6707689762 0.0605469160 0.0537366952 0.0637187362 0.0054008356 0.0289680000 227543570 95654128 760807424 -0.0515490770 -0.0280177966 -0.0767913088 518 1311867187.7035770416 0.0588404089 0.0537465479 0.0637187362 0.0053998376 0.0236950000 227547114 95654128 760807424 -0.0479778275 -0.0333947055 -0.0764454678 519 1311867187.7345480919 0.0595725141 0.0537577733 0.0637187362 0.0053999527 0.0250080000 227548834 95654128 760807424 -0.0443735123 -0.0345894285 -0.0754059553 520 1311867187.7707819939 0.0587233827 0.0537673226 0.0637187362 0.0053980070 0.0290940000 227552466 95654128 760807424 -0.0412026048 -0.0287428610 -0.0798488706 521 1311867187.8017508984 0.0573811196 0.0537742588 0.0637187362 0.0054023256 0.0249720000 227554402 95654128 760807424 -0.0406970307 -0.0345137082 -0.0792841539 522 1311867187.8339610100 0.0586733930 0.0537836441 0.0637187362 0.0054021237 0.0295150000 227557810 95654128 760807424 -0.0395766534 -0.0317576341 -0.0799925253 523 1311867187.8708090782 0.0571478866 0.0537900767 0.0637187362 0.0054151588 0.0236790000 227561594 95654128 760807424 -0.0346400850 -0.0324796624 -0.0807382092 524 1311867187.9038810730 0.0573678426 0.0537969045 0.0637187362 0.0054141930 0.0250070000 227563762 95654128 760807424 -0.0317943431 -0.0304300822 -0.0817470253 525 1311867187.9363000393 0.0572473072 0.0538034767 0.0637187362 0.0054095769 0.0243740000 227567378 95654128 760807424 -0.0296638682 -0.0319290720 -0.0816974193 526 1311867187.9713420868 0.0590728372 0.0538134945 0.0637187362 0.0054075879 0.0238220000 227569162 95654128 760807424 -0.0289958678 -0.0317657627 -0.0814090669 527 1311867188.0047569275 0.0592091940 0.0538237330 0.0637187362 0.0054331545 0.0250900000 227573082 95654128 760807424 -0.0234297551 -0.0280170608 -0.0836919099 528 1311867188.0333108902 0.0601743869 0.0538357608 0.0637187362 0.0054449699 0.0236020000 227576442 95654128 760807424 -0.0214776695 -0.0281407963 -0.0835778639 529 1311867188.0698699951 0.0615721606 0.0538503854 0.0637187362 0.0054439386 0.0277690000 227578386 95654128 760807424 -0.0171528291 -0.0281122178 -0.0832644925 530 1311867188.1088800430 0.0609867573 0.0538638502 0.0637187362 0.0054460902 0.0236950000 227582138 95654128 760807424 -0.0138695799 -0.0275768340 -0.0856383294 531 1311867188.1359970570 0.0594852194 0.0538744366 0.0637187362 0.0054580467 0.0236560000 227583842 95654128 760807424 -0.0104233325 -0.0272225365 -0.0871982872 532 1311867188.1703350544 0.0620059222 0.0538897213 0.0637187362 0.0054563544 0.0236660000 227587370 95654128 760807424 -0.0072386665 -0.0278025605 -0.0866921470 533 1311867188.2026720047 0.0613205545 0.0539036629 0.0637187362 0.0054595536 0.0304120000 227591098 95654128 760807424 -0.0048177340 -0.0279190373 -0.0889300555 534 1311867188.2352449894 0.0609647594 0.0539168859 0.0637187362 0.0054658157 0.0238130000 227763830 95654128 760807424 -0.0016000466 -0.0268866979 -0.0905303732 535 1311867188.2706460953 0.0619927272 0.0539319809 0.0637187362 0.0054710951 0.0235790000 227767614 95654128 760807424 -0.0010622924 -0.0276718624 -0.0912778601 536 1311867188.3047339916 0.0622153580 0.0539474350 0.0637187362 0.0054666083 0.0270680000 227771198 95654128 760807424 0.0038517711 -0.0278330967 -0.0917543396 537 1311867188.3398799896 0.0623074584 0.0539630030 0.0637187362 0.0054628884 0.0267690000 227773182 95654128 760807424 0.0070794378 -0.0251469780 -0.0941467732 538 1311867188.3718800545 0.0613435768 0.0539767215 0.0637187362 0.0054585885 0.0235230000 227776598 95654128 760807424 0.0104178898 -0.0253888499 -0.0951768160 539 1311867188.4054470062 0.0604314245 0.0539886969 0.0637187362 0.0054656985 0.0268350000 227778470 95654128 760807424 0.0149329342 -0.0262645409 -0.0953726396 540 1311867188.4398789406 0.0614591204 0.0540025310 0.0637187362 0.0054618883 0.0235650000 227782054 95654128 760807424 0.0167734101 -0.0264458731 -0.0947308838 541 1311867188.4724500179 0.0600298494 0.0540136721 0.0637187362 0.0054601267 0.0344190000 227956222 95654128 760807424 0.0208063740 -0.0233270023 -0.0980815738 542 1311867188.5049159527 0.0589045845 0.0540226959 0.0637187362 0.0054713149 0.0240500000 227958158 95654128 760807424 0.0238904413 -0.0269197114 -0.0970394462 543 1311867188.5389990807 0.0599990673 0.0540337021 0.0637187362 0.0054668854 0.0235460000 227961942 95654128 760807424 0.0266526919 -0.0253435578 -0.0968271568 544 1311867188.5723888874 0.0587539598 0.0540423790 0.0637187362 0.0054688111 0.0267730000 227963614 95654128 760807424 0.0310458653 -0.0214411579 -0.0999863446 545 1311867188.6045958996 0.0580021404 0.0540496447 0.0637187362 0.0054662614 0.0235910000 227967286 95654128 760807424 0.0322233364 -0.0269706007 -0.0980289653 546 1311867188.6398339272 0.0599643663 0.0540604775 0.0637187362 0.0054625000 0.0236610000 227970758 95654128 760807424 0.0364973582 -0.0244772229 -0.0973373875 547 1311867188.6715080738 0.0603901893 0.0540720492 0.0637187362 0.0054637872 0.0235660000 227972686 95654128 760807424 0.0390695110 -0.0223829001 -0.0987051353 548 1311867188.7038300037 0.0616925880 0.0540859553 0.0637187362 0.0054605846 0.0235520000 227976158 95654128 760807424 0.0403153859 -0.0232350044 -0.0980092287 549 1311867188.7393829823 0.0626193359 0.0541014988 0.0637187362 0.0054582201 0.0325790000 227978086 95654128 760807424 0.0431312509 -0.0239341427 -0.0978897661 550 1311867188.7721049786 0.0615716130 0.0541150808 0.0637187362 0.0054546610 0.0239010000 227981614 95654128 760807424 0.0473229475 -0.0219622944 -0.1013171449 551 1311867188.8045220375 0.0618467405 0.0541291128 0.0637187362 0.0054528798 0.0235460000 228155806 95654128 760807424 0.0513860658 -0.0218936633 -0.1023113355 552 1311867188.8402431011 0.0636331141 0.0541463302 0.0637187362 0.0054534948 0.0234390000 228157534 95654128 760807424 0.0543162487 -0.0241243597 -0.1012483388 553 1311867188.8705990314 0.0619519167 0.0541604452 0.0637187362 0.0054488035 0.0233120000 228161282 95654128 760807424 0.0580601506 -0.0234594867 -0.1049259827 554 1311867188.9016311169 0.0612134784 0.0541731763 0.0637187362 0.0054473390 0.0240800000 228164738 95654128 760807424 0.0610324591 -0.0233773217 -0.1067508906 555 1311867188.9401769638 0.0630964115 0.0541892542 0.0637187362 0.0054435623 0.0233760000 228166850 95654128 760807424 0.0640107542 -0.0249381196 -0.1058164984 556 1311867188.9709990025 0.0610749051 0.0542016385 0.0637187362 0.0054404434 0.0232990000 228340514 95654128 760807424 0.0691736639 -0.0258741695 -0.1081113517 557 1311867189.0052258968 0.0607223883 0.0542133454 0.0637187362 0.0054360593 0.0320450000 228342498 95654128 760807424 0.0758379251 -0.0248818174 -0.1091281101 558 1311867189.0400099754 0.0613540895 0.0542261424 0.0637187362 0.0054341539 0.0235870000 228345970 95654128 760807424 0.0790239871 -0.0265057888 -0.1083843559 559 1311867189.0724329948 0.0606717356 0.0542376730 0.0637187362 0.0054324813 0.0231590000 228349754 95654128 760807424 0.0826405734 -0.0276750829 -0.1085889339 560 1311867189.1026360989 0.0598180220 0.0542476379 0.0637187362 0.0054284042 0.0231720000 228351370 95654128 760807424 0.0879752710 -0.0269803274 -0.1092494428 561 1311867189.1417639256 0.0602267087 0.0542582958 0.0637187362 0.0054254328 0.0231490000 228355266 95654128 760807424 0.0914405882 -0.0267855301 -0.1082861274 562 1311867189.1717920303 0.0601534881 0.0542687855 0.0637187362 0.0054221067 0.0232090000 228529302 95654128 760807424 0.0922041014 -0.0270157456 -0.1073689684 563 1311867189.2019069195 0.0603866912 0.0542796521 0.0637187362 0.0054174817 0.0263350000 228532918 95654128 760807424 0.0940519795 -0.0264322944 -0.1066317409 564 1311867189.2390630245 0.0600573234 0.0542898962 0.0637187362 0.0054144302 0.0231650000 228536502 95654128 760807424 0.0962565169 -0.0288918857 -0.1047968417 565 1311867189.2722640038 0.0600781217 0.0543001408 0.0637187362 0.0054101108 0.0314990000 228538374 95654128 760807424 0.0973233953 -0.0289384201 -0.1042142883 566 1311867189.3046789169 0.0603957847 0.0543109105 0.0637187362 0.0054074620 0.0241900000 228541902 95654128 760807424 0.1020070091 -0.0292308256 -0.1029073596 567 1311867189.3397970200 0.0605521686 0.0543219180 0.0637187362 0.0054094323 0.0234210000 228543830 95654128 760807424 0.1048767567 -0.0305167288 -0.1012164429 568 1311867189.3720359802 0.0609355830 0.0543335618 0.0637187362 0.0054546542 0.0264150000 228547302 95654128 760807424 0.1054735258 -0.0302558765 -0.1011811793 569 1311867189.4056949615 0.0602930821 0.0543440355 0.0637187362 0.0054616444 0.0232530000 228551014 95654128 760807424 0.1091237441 -0.0303623453 -0.1009645760 570 1311867189.4405019283 0.0613687411 0.0543563595 0.0637187362 0.0054595414 0.0231050000 228552742 95654128 760807424 0.1128272116 -0.0335134566 -0.0977422372 571 1311867189.4729130268 0.0613552742 0.0543686168 0.0637187362 0.0054558198 0.0230710000 228556470 95654128 760807424 0.1177529991 -0.0343616419 -0.0977832675 572 1311867189.5060400963 0.0612685531 0.0543806796 0.0637187362 0.0054538295 0.0230730000 228559942 95654128 760807424 0.1193393767 -0.0345794633 -0.0977864638 573 1311867189.5394289494 0.0607724302 0.0543918345 0.0637187362 0.0054501915 0.0335600000 228561814 95654128 760807424 0.1240796223 -0.0388987437 -0.0967885181 574 1311867189.5720269680 0.0608700961 0.0544031207 0.0637187362 0.0054475551 0.0236660000 228565342 95654128 760807424 0.1287409067 -0.0416646153 -0.0963910520 575 1311867189.6112909317 0.0608306713 0.0544142990 0.0637187362 0.0054440069 0.0230650000 228567382 95654128 760807424 0.1339443773 -0.0403752774 -0.0982198119 576 1311867189.6424219608 0.0607146658 0.0544252372 0.0637187362 0.0054395257 0.0263610000 228570854 95654128 760807424 0.1376844645 -0.0420804657 -0.0980142802 577 1311867189.6728401184 0.0607195906 0.0544361459 0.0637187362 0.0054355483 0.0231420000 228574526 95654128 760807424 0.1420744807 -0.0437145233 -0.0977922156 578 1311867189.7065870762 0.0614624694 0.0544483022 0.0637187362 0.0054356794 0.0230810000 228576198 95654128 760807424 0.1461739689 -0.0424119830 -0.0981727690 579 1311867189.7401719093 0.0610917024 0.0544597761 0.0637187362 0.0054318979 0.0231540000 228579926 95654128 760807424 0.1506734341 -0.0422309674 -0.0982026458 580 1311867189.7729759216 0.0610014461 0.0544710549 0.0637187362 0.0054288836 0.0232980000 228752578 95654128 760807424 0.1557257921 -0.0435993522 -0.0970627889 581 1311867189.8073968887 0.0609481558 0.0544822031 0.0637187362 0.0054301606 0.0310950000 228756306 95654128 760807424 0.1582819521 -0.0453789383 -0.0953461155 582 1311867189.8405311108 0.0610139072 0.0544934259 0.0637187362 0.0054266034 0.0266640000 228759778 95654128 760807424 0.1637495011 -0.0442439020 -0.0952454954 583 1311867189.8713529110 0.0613279082 0.0545051489 0.0637187362 0.0054229768 0.0232640000 228761650 95654128 760807424 0.1670402139 -0.0461710803 -0.0932805613 584 1311867189.9102680683 0.0623203255 0.0545185310 0.0637187362 0.0054212397 0.0267830000 228765290 95654128 760807424 0.1686474085 -0.0461097360 -0.0919198468 585 1311867189.9402260780 0.0615536906 0.0545305569 0.0637187362 0.0054172764 0.0233190000 228767162 95654128 760807424 0.1725798696 -0.0454995222 -0.0927053839 586 1311867189.9727621078 0.0621791519 0.0545436091 0.0637187362 0.0054128539 0.0268410000 228770634 95654128 760807424 0.1772642881 -0.0451668017 -0.0919170007 587 1311867190.0107009411 0.0625271723 0.0545572098 0.0637187362 0.0054090311 0.0232580000 228774418 95654128 760807424 0.1812698543 -0.0456697345 -0.0913828388 588 1311867190.0402929783 0.0629436746 0.0545714725 0.0637187362 0.0054072628 0.0232250000 228776034 95654128 760807424 0.1860950142 -0.0455497764 -0.0911433250 589 1311867190.0719039440 0.0639694929 0.0545874284 0.0639694929 0.0054045512 0.0232430000 228779706 95654128 760807424 0.1881199330 -0.0482924804 -0.0889218599 590 1311867190.1096539497 0.0644781217 0.0546041922 0.0644781217 0.0054014081 0.0232240000 228783346 95654128 760807424 0.1907115877 -0.0494741611 -0.0886259452 591 1311867190.1396369934 0.0641621798 0.0546203648 0.0644781217 0.0053973900 0.0232290000 228785218 95654128 760807424 0.1956265867 -0.0485358052 -0.0901558623 592 1311867190.1706380844 0.0646190867 0.0546372545 0.0646190867 0.0053993607 0.0240730000 228788578 95654128 760807424 0.1976561993 -0.0502790846 -0.0891759098 593 1311867190.2096021175 0.0654453784 0.0546554807 0.0654453784 0.0053992656 0.0231780000 228790674 95654128 760807424 0.1989855617 -0.0516754016 -0.0889230818 594 1311867190.2394330502 0.0648821071 0.0546726973 0.0654453784 0.0053978823 0.0231690000 228794034 95654128 760807424 0.2048745304 -0.0504632369 -0.0907160714 595 1311867190.2714810371 0.0643467978 0.0546889563 0.0654453784 0.0054023250 0.0231920000 228797762 95654128 760807424 0.2078978270 -0.0534641854 -0.0897544026 596 1311867190.3072700500 0.0640588626 0.0547046776 0.0654453784 0.0053995943 0.0264560000 228970986 95654128 760807424 0.2109929323 -0.0547571070 -0.0896471366 597 1311867190.3414731026 0.0629870370 0.0547185509 0.0654453784 0.0053956651 0.0231390000 228974714 95654128 760807424 0.2152590156 -0.0544715934 -0.0909945667 598 1311867190.3716828823 0.0627880543 0.0547320450 0.0654453784 0.0053989168 0.0264470000 228976330 95654128 760807424 0.2178788036 -0.0537212864 -0.0911087543 599 1311867190.4101090431 0.0627291501 0.0547453958 0.0654453784 0.0053964158 0.0231960000 228980114 95654128 760807424 0.2196899801 -0.0540880635 -0.0908091217 600 1311867190.4394960403 0.0619742759 0.0547574439 0.0654453784 0.0053945994 0.0262570000 228983658 95654128 760807424 0.2221385092 -0.0529383980 -0.0918309167 601 1311867190.4708199501 0.0621490069 0.0547697427 0.0654453784 0.0053910522 0.0231810000 228985418 95654128 760807424 0.2256112844 -0.0556630492 -0.0898689777 602 1311867190.5097529888 0.0627607033 0.0547830167 0.0654453784 0.0053879215 0.0231820000 228989170 95654128 760807424 0.2276471704 -0.0548255667 -0.0893066078 603 1311867190.5405189991 0.0637283772 0.0547978515 0.0654453784 0.0053857155 0.0231390000 228990930 95654128 760807424 0.2326469421 -0.0518250838 -0.0896180570 604 1311867190.5708439350 0.0641091987 0.0548132676 0.0654453784 0.0053828768 0.0262130000 228994346 95654128 760807424 0.2350633442 -0.0534067899 -0.0879952833 605 1311867190.6067750454 0.0642773733 0.0548289108 0.0654453784 0.0053812962 0.0239840000 228998130 95654128 760807424 0.2369280607 -0.0537080169 -0.0871997476 606 1311867190.6389939785 0.0645055398 0.0548448788 0.0654453784 0.0053820609 0.0232170000 228999858 95654128 760807424 0.2412103862 -0.0527650081 -0.0868918896 607 1311867190.6723659039 0.0649977177 0.0548616051 0.0654453784 0.0053780702 0.0231860000 229003530 95654128 760807424 0.2454823405 -0.0552026108 -0.0848205984 608 1311867190.7114980221 0.0658309758 0.0548796468 0.0658309758 0.0053791148 0.0231330000 229007170 95654128 760807424 0.2476405650 -0.0535318814 -0.0843087807 609 1311867190.7392649651 0.0645226017 0.0548954809 0.0658309758 0.0053777012 0.0231810000 229008874 95654128 760807424 0.2497552484 -0.0554576926 -0.0840705931 610 1311867190.7751801014 0.0638292730 0.0549101264 0.0658309758 0.0053737506 0.0231740000 229012458 95654128 760807424 0.2521134019 -0.0564562231 -0.0835568607 611 1311867190.8070900440 0.0634086728 0.0549240357 0.0658309758 0.0053698101 0.0231830000 229014386 95654128 760807424 0.2544871867 -0.0579683892 -0.0825213939 612 1311867190.8414280415 0.0640176237 0.0549388945 0.0658309758 0.0053662966 0.0232300000 229017914 95654128 760807424 0.2549467087 -0.0602914169 -0.0801452920 613 1311867190.8739249706 0.0643975511 0.0549543246 0.0658309758 0.0053647723 0.0267640000 229021586 95654128 760807424 0.2570274472 -0.0587690771 -0.0801638812 614 1311867190.9076139927 0.0639466122 0.0549689700 0.0658309758 0.0053619851 0.0233500000 229023314 95654128 760807424 0.2598745823 -0.0598674044 -0.0793958157 615 1311867190.9393599033 0.0653235614 0.0549858067 0.0658309758 0.0053578008 0.0267370000 229026930 95654128 760807424 0.2641507685 -0.0608155392 -0.0772885233 616 1311867190.9741609097 0.0646123365 0.0550014342 0.0658309758 0.0053538394 0.0232570000 229028714 95654128 760807424 0.2664664090 -0.0621743239 -0.0770509243 617 1311867191.0085949898 0.0635692179 0.0550153204 0.0658309758 0.0053503709 0.0233630000 229203114 95654128 760807424 0.2705048621 -0.0604586862 -0.0782759339 618 1311867191.0396919250 0.0638815388 0.0550296670 0.0658309758 0.0053501020 0.0233140000 229206586 95654128 760807424 0.2729081810 -0.0631343946 -0.0757411197 619 1311867191.0764329433 0.0641424730 0.0550443889 0.0658309758 0.0053560146 0.0232530000 229208570 95654128 760807424 0.2732144594 -0.0662844852 -0.0733750165 620 1311867191.1103041172 0.0638044700 0.0550585180 0.0658309758 0.0053580700 0.0268300000 229212098 95654128 760807424 0.2769802809 -0.0637717918 -0.0743206516 621 1311867191.1388139725 0.0636768192 0.0550723961 0.0658309758 0.0053717140 0.0267670000 229213914 95654128 760807424 0.2803829014 -0.0648999959 -0.0731084868 622 1311867191.1742820740 0.0644638985 0.0550874950 0.0658309758 0.0053679464 0.0232630000 229217442 95654128 760807424 0.2830918729 -0.0662325397 -0.0708591864 623 1311867191.2077920437 0.0646653101 0.0551028687 0.0658309758 0.0053638879 0.0232640000 229221170 95654128 760807424 0.2873049080 -0.0634878427 -0.0711303204 624 1311867191.2408421040 0.0634940565 0.0551163161 0.0658309758 0.0053605797 0.0231930000 229222898 95654128 760807424 0.2900914252 -0.0673470646 -0.0698621795 625 1311867191.2769579887 0.0636190623 0.0551299205 0.0658309758 0.0053575340 0.0232180000 229226626 95654128 760807424 0.2926737964 -0.0685454458 -0.0687247291 626 1311867191.3085029125 0.0628278702 0.0551422176 0.0658309758 0.0053556817 0.0231900000 229229930 95654128 760807424 0.2962146401 -0.0668116584 -0.0696123168 627 1311867191.3404779434 0.0640544519 0.0551564317 0.0658309758 0.0053543675 0.0233200000 229402630 95654128 760807424 0.2978888154 -0.0682255179 -0.0668678731 628 1311867191.3794629574 0.0651049763 0.0551722733 0.0658309758 0.0053508305 0.0234390000 229406326 95654128 760807424 0.2995184362 -0.0691479892 -0.0645585507 629 1311867191.4091579914 0.0646928027 0.0551874093 0.0658309758 0.0053470226 0.0232850000 229408086 95654128 760807424 0.3039921522 -0.0687297210 -0.0650022253 630 1311867191.4415969849 0.0647579283 0.0552026006 0.0658309758 0.0053439759 0.0261940000 229411690 95654128 760807424 0.3083628714 -0.0677241832 -0.0646800101 631 1311867191.4775309563 0.0645339563 0.0552173888 0.0658309758 0.0053406878 0.0233090000 229415418 95654128 760807424 0.3084072471 -0.0705760196 -0.0625875965 632 1311867191.5075590611 0.0639245287 0.0552311659 0.0658309758 0.0053383378 0.0237100000 229416978 95654128 760807424 0.3086792827 -0.0680369586 -0.0633051842 633 1311867191.5390620232 0.0643111765 0.0552455103 0.0658309758 0.0053358857 0.0237140000 229420650 95654128 760807424 0.3136365116 -0.0700454339 -0.0614330433 634 1311867191.5764698982 0.0637750998 0.0552589639 0.0658309758 0.0053322092 0.0270390000 229422434 95654128 760807424 0.3172661960 -0.0702937990 -0.0609177276 635 1311867191.6118669510 0.0640780032 0.0552728522 0.0658309758 0.0053501431 0.0233620000 229426218 95654128 760807424 0.3201328814 -0.0687791780 -0.0601973161 636 1311867191.6451880932 0.0640990585 0.0552867298 0.0658309758 0.0053484111 0.0269940000 229429690 95654128 760807424 0.3215322793 -0.0699731559 -0.0583996736 637 1311867191.6827919483 0.0646842048 0.0553014825 0.0658309758 0.0053453671 0.0236340000 229431786 95654128 760807424 0.3232403100 -0.0703523681 -0.0565150008 638 1311867191.7119400501 0.0646338463 0.0553161101 0.0658309758 0.0053428213 0.0270960000 229435146 95654128 760807424 0.3260798156 -0.0684350207 -0.0568091422 639 1311867191.7457199097 0.0642054901 0.0553300215 0.0658309758 0.0053526789 0.0322280000 229436962 95654128 760807424 0.3255962729 -0.0710281804 -0.0541986525 640 1311867191.7763800621 0.0638457164 0.0553433272 0.0658309758 0.0053558145 0.0238670000 229440378 95654128 760807424 0.3263987005 -0.0702192336 -0.0543646514 641 1311867191.8097250462 0.0627325252 0.0553548549 0.0658309758 0.0053538605 0.0234620000 229444106 95654128 760807424 0.3272179663 -0.0722182840 -0.0535591207 642 1311867191.8395779133 0.0635255575 0.0553675818 0.0658309758 0.0053576920 0.0270850000 229445722 95654128 760807424 0.3296835721 -0.0719489828 -0.0521824583 643 1311867191.8745219707 0.0629625916 0.0553793936 0.0658309758 0.0053593260 0.0265840000 229449450 95654128 760807424 0.3291358948 -0.0700897574 -0.0525252298 644 1311867191.9077119827 0.0628386959 0.0553909764 0.0658309758 0.0053564749 0.0234350000 229452978 95654128 760807424 0.3311887980 -0.0708706751 -0.0511422455 645 1311867191.9391601086 0.0638299733 0.0554040601 0.0658309758 0.0053530539 0.0241960000 229454850 95654128 760807424 0.3317219019 -0.0744932219 -0.0478073657 646 1311867191.9755239487 0.0643143058 0.0554178531 0.0658309758 0.0053514052 0.0235720000 229458378 95654128 760807424 0.3365346193 -0.0706991702 -0.0482454486 647 1311867192.0076289177 0.0634251907 0.0554302292 0.0658309758 0.0053508690 0.0259000000 229460250 95654128 760807424 0.3375084400 -0.0735478550 -0.0468740724 648 1311867192.0447950363 0.0645831674 0.0554443541 0.0658309758 0.0053526624 0.0234540000 229463890 95654128 760807424 0.3366333246 -0.0754741654 -0.0437245630 649 1311867192.0751929283 0.0639357418 0.0554574379 0.0658309758 0.0053503232 0.0234550000 229467450 95654128 760807424 0.3380264938 -0.0746288449 -0.0440013371 650 1311867192.1073920727 0.0633888319 0.0554696400 0.0658309758 0.0053471937 0.0234020000 229469178 95654128 760807424 0.3415209055 -0.0734980032 -0.0446726047 651 1311867192.1433029175 0.0648024976 0.0554839762 0.0658309758 0.0053467151 0.0234800000 229472962 95654128 760807424 0.3408005536 -0.0763247237 -0.0408176593 652 1311867192.1754670143 0.0645499229 0.0554978810 0.0658309758 0.0053482734 0.0234650000 229474634 95654128 760807424 0.3446135223 -0.0728929341 -0.0420705527 653 1311867192.2077538967 0.0644440800 0.0555115812 0.0658309758 0.0053449044 0.0234820000 229478362 95654128 760807424 0.3449453413 -0.0738355666 -0.0408930928 654 1311867192.2451250553 0.0647584945 0.0555257202 0.0658309758 0.0053430192 0.0234430000 229482002 95654128 760807424 0.3441570997 -0.0764761418 -0.0381673016 655 1311867192.2744629383 0.0640735552 0.0555387703 0.0658309758 0.0053403315 0.0235730000 229483762 95654128 760807424 0.3470539153 -0.0735138208 -0.0396511666 656 1311867192.3067719936 0.0636464432 0.0555511296 0.0658309758 0.0053406435 0.0235530000 229487234 95654128 760807424 0.3489657640 -0.0767091066 -0.0378973894 657 1311867192.3427391052 0.0642639175 0.0555643911 0.0658309758 0.0053375475 0.0235030000 229489218 95654128 760807424 0.3493652344 -0.0790448487 -0.0357945263 658 1311867192.3755910397 0.0637515932 0.0555768336 0.0658309758 0.0053359072 0.0234900000 229492746 95654128 760807424 0.3538159132 -0.0770905763 -0.0369694903 659 1311867192.4059340954 0.0641161576 0.0555897916 0.0658309758 0.0053327929 0.0234670000 229496306 95654128 760807424 0.3559482992 -0.0781131685 -0.0359202400 660 1311867192.4447100163 0.0649276823 0.0556039399 0.0658309758 0.0053327291 0.0266010000 229498202 95654128 760807424 0.3563804924 -0.0799978897 -0.0344769992 661 1311867192.4748210907 0.0646999702 0.0556177010 0.0658309758 0.0053298669 0.0234830000 229501818 95654128 760807424 0.3604056537 -0.0796736181 -0.0348979421 662 1311867192.5077190399 0.0657631978 0.0556330265 0.0658309758 0.0053283490 0.0266160000 229505290 95654128 760807424 0.3638509810 -0.0805517137 -0.0335187204 663 1311867192.5427820683 0.0655572191 0.0556479951 0.0658309758 0.0053248155 0.0236170000 229678966 95654128 760807424 0.3647548258 -0.0824564546 -0.0329437256 664 1311867192.5787169933 0.0657156855 0.0556631573 0.0658309758 0.0053239119 0.0266860000 229682494 95654128 760807424 0.3674784601 -0.0795337930 -0.0340604149 665 1311867192.6109929085 0.0653609037 0.0556777404 0.0658309758 0.0053207516 0.0340020000 229684366 95654128 760807424 0.3685843945 -0.0802573189 -0.0339481570 666 1311867192.6435210705 0.0652734712 0.0556921484 0.0658309758 0.0053199142 0.0239180000 229687894 95654128 760807424 0.3689867556 -0.0832251310 -0.0327236243 667 1311867192.6790139675 0.0645225793 0.0557053874 0.0658309758 0.0053162581 0.0233750000 229691678 95654128 760807424 0.3716760874 -0.0834354609 -0.0333218016 668 1311867192.7113289833 0.0656566992 0.0557202846 0.0658309758 0.0053134796 0.0266240000 229693294 95654128 760807424 0.3751517832 -0.0826727375 -0.0323585086 669 1311867192.7439620495 0.0648809448 0.0557339776 0.0658309758 0.0053116258 0.0234720000 229697022 95654128 760807424 0.3739870191 -0.0842657760 -0.0321473442 670 1311867192.7760629654 0.0648280531 0.0557475509 0.0658309758 0.0053109209 0.0271020000 229698694 95654128 760807424 0.3763482869 -0.0817317665 -0.0328712724 671 1311867192.8091869354 0.0643693656 0.0557604001 0.0658309758 0.0053072269 0.0236860000 229702422 95654128 760807424 0.3768485487 -0.0846104771 -0.0316922031 672 1311867192.8422288895 0.0643083528 0.0557731202 0.0658309758 0.0053039750 0.0234580000 229705894 95654128 760807424 0.3767744005 -0.0857229456 -0.0309403818 673 1311867192.8792889118 0.0644447282 0.0557860052 0.0658309758 0.0053005954 0.0271220000 229707934 95654128 760807424 0.3808083236 -0.0838774964 -0.0311875623 674 1311867192.9092190266 0.0645437092 0.0557989989 0.0658309758 0.0052971623 0.0234620000 229711294 95654128 760807424 0.3808213472 -0.0833920538 -0.0309531875 675 1311867192.9434111118 0.0648426041 0.0558123968 0.0658309758 0.0052933578 0.0235700000 229713278 95654128 760807424 0.3799269497 -0.0862822682 -0.0292128250 676 1311867192.9776289463 0.0652901158 0.0558264171 0.0658309758 0.0052911926 0.0234620000 229716750 95654128 760807424 0.3852243125 -0.0825389177 -0.0302544329 677 1311867193.0086810589 0.0641355067 0.0558386905 0.0658309758 0.0052898967 0.0236070000 229720422 95654128 760807424 0.3837798238 -0.0856470913 -0.0293693133 678 1311867193.0430600643 0.0655933693 0.0558530779 0.0658309758 0.0052865357 0.0233680000 229722150 95654128 760807424 0.3851676285 -0.0871570408 -0.0270763896 679 1311867193.0767369270 0.0646937788 0.0558660981 0.0658309758 0.0052860155 0.0236710000 229725822 95654128 760807424 0.3897944987 -0.0838628560 -0.0294859111 680 1311867193.1105849743 0.0636037514 0.0558774770 0.0658309758 0.0052842494 0.0266700000 229729350 95654128 760807424 0.3891217411 -0.0875519216 -0.0284402203 681 1311867193.1429219246 0.0643898398 0.0558899768 0.0658309758 0.0052813789 0.0235020000 229731278 95654128 760807424 0.3903459311 -0.0887730941 -0.0266486537 682 1311867193.1767370701 0.0649318099 0.0559032346 0.0658309758 0.0052939314 0.0337470000 229734750 95654128 760807424 0.3932410777 -0.0826850981 -0.0285765007 683 1311867193.2122681141 0.0649817809 0.0559165268 0.0658309758 0.0052991285 0.0247040000 229736734 95654128 760807424 0.3934337497 -0.0871133134 -0.0260205846 684 1311867193.2432429790 0.0645444468 0.0559291407 0.0658309758 0.0052966174 0.0270230000 229740206 95654128 760807424 0.3961468339 -0.0870727301 -0.0262628905 685 1311867193.2773900032 0.0644234046 0.0559415411 0.0658309758 0.0052934812 0.0236190000 229743934 95654128 760807424 0.3968839943 -0.0856251493 -0.0267854333 686 1311867193.3139379025 0.0647042021 0.0559543146 0.0658309758 0.0052931464 0.0236210000 229745718 95654128 760807424 0.3983808756 -0.0891095623 -0.0247535575 687 1311867193.3426671028 0.0647010878 0.0559670465 0.0658309758 0.0052937471 0.0355770000 229749278 95654128 760807424 0.4006475508 -0.0864300802 -0.0259215739 688 1311867193.3788230419 0.0648494214 0.0559799569 0.0658309758 0.0052901769 0.0242220000 229751062 95654128 760807424 0.4029205739 -0.0852909908 -0.0260384791 689 1311867193.4126739502 0.0648951232 0.0559928962 0.0658309758 0.0052939157 0.0235980000 229754734 95654128 760807424 0.4038734436 -0.0891998708 -0.0243061464 690 1311867193.4440810680 0.0643919706 0.0560050688 0.0658309758 0.0052933213 0.0276050000 229758262 95654128 760807424 0.4063308537 -0.0878649056 -0.0255855601 691 1311867193.4782969952 0.0650603101 0.0560181733 0.0658309758 0.0052899159 0.0237310000 229760190 95654128 760807424 0.4080912769 -0.0860452652 -0.0257123224 692 1311867193.5199069977 0.0655901730 0.0560320057 0.0658309758 0.0052894318 0.0271970000 229763830 95654128 760807424 0.4101766646 -0.0900427848 -0.0237667430 693 1311867193.5431120396 0.0655012652 0.0560456698 0.0658309758 0.0052880058 0.0268590000 229936402 95654128 760807424 0.4122293293 -0.0877173021 -0.0248418581 694 1311867193.5765709877 0.0656475127 0.0560595054 0.0658309758 0.0052844445 0.0236230000 229939874 95654128 760807424 0.4147224724 -0.0862245634 -0.0253737904 695 1311867193.6127800941 0.0655850694 0.0560732112 0.0658309758 0.0052810597 0.0236310000 229943714 95654128 760807424 0.4128522873 -0.0901566967 -0.0238792654 696 1311867193.6461451054 0.0645617098 0.0560854073 0.0658309758 0.0052781629 0.0235430000 229945386 95654128 760807424 0.4163646996 -0.0890263766 -0.0255187526 697 1311867193.6757860184 0.0653749034 0.0560987351 0.0658309758 0.0052747083 0.0235170000 229949002 95654128 760807424 0.4191975594 -0.0873955786 -0.0254762955 698 1311867193.7122890949 0.0658832267 0.0561127530 0.0658832267 0.0052714540 0.0270140000 229952586 95654128 760807424 0.4181050062 -0.0906540751 -0.0233338289 699 1311867193.7430191040 0.0656556487 0.0561264053 0.0658832267 0.0052684956 0.0235270000 229954402 95654128 760807424 0.4211870730 -0.0875580013 -0.0248148702 700 1311867193.7760169506 0.0664422661 0.0561411422 0.0664422661 0.0052650046 0.0235110000 229957874 95654128 760807424 0.4249416888 -0.0861874744 -0.0246485118 701 1311867193.8139710426 0.0662156343 0.0561555138 0.0664422661 0.0052617921 0.0235100000 229959970 95654128 760807424 0.4246627688 -0.0898675844 -0.0232221149 702 1311867193.8436760902 0.0656761974 0.0561690760 0.0664422661 0.0052616955 0.0235280000 229963330 95654128 760807424 0.4257841110 -0.0882241949 -0.0244078990 703 1311867193.8771181107 0.0655041263 0.0561823549 0.0664422661 0.0052586887 0.0267010000 229967058 95654128 760807424 0.4276933968 -0.0878409743 -0.0251069628 704 1311867193.9151229858 0.0657274053 0.0561959132 0.0664422661 0.0052553199 0.0234910000 229968842 95654128 760807424 0.4280434251 -0.0896191150 -0.0242558401 705 1311867193.9425311089 0.0660447627 0.0562098832 0.0664422661 0.0052536015 0.0234800000 229972458 95654128 760807424 0.4309685826 -0.0871918127 -0.0250900239 706 1311867193.9781770706 0.0647298917 0.0562219512 0.0664422661 0.0052534445 0.0234710000 229974242 95654128 760807424 0.4323621690 -0.0897563249 -0.0254610926 707 1311867194.0148570538 0.0659348145 0.0562356893 0.0664422661 0.0052503002 0.0269840000 229977970 95654128 760807424 0.4338218570 -0.0908410251 -0.0240131505 708 1311867194.0433440208 0.0664118007 0.0562500624 0.0664422661 0.0052488136 0.0244960000 229981386 95654128 760807424 0.4356527030 -0.0897331834 -0.0240974780 709 1311867194.0746119022 0.0664913431 0.0562645071 0.0664913431 0.0052473309 0.0235150000 229983202 95654128 760807424 0.4381315708 -0.0888735130 -0.0244819261 710 1311867194.1131060123 0.0661793202 0.0562784716 0.0664913431 0.0052442699 0.0234650000 229986898 95654128 760807424 0.4387101531 -0.0910712630 -0.0237269197 711 1311867194.1428558826 0.0657023713 0.0562917260 0.0664913431 0.0052415119 0.0271610000 229988714 95654128 760807424 0.4412379861 -0.0893055871 -0.0248993468 712 1311867194.1758549213 0.0646326244 0.0563034408 0.0664913431 0.0052464886 0.0266080000 229992186 95654128 760807424 0.4413586855 -0.0885934755 -0.0251448248 713 1311867194.2138450146 0.0656234100 0.0563165123 0.0664913431 0.0052439431 0.0235750000 229996026 95654128 760807424 0.4414698482 -0.0912755430 -0.0225522313 714 1311867194.2451140881 0.0652950406 0.0563290872 0.0664913431 0.0052413234 0.0267780000 229997586 95654128 760807424 0.4444210231 -0.0885205045 -0.0240624566 715 1311867194.2760241032 0.0660611987 0.0563426986 0.0664913431 0.0052383716 0.0235310000 230001202 95654128 760807424 0.4463675618 -0.0888048932 -0.0230023507 716 1311867194.3139200211 0.0658865124 0.0563560279 0.0664913431 0.0052382890 0.0235430000 230004842 95654128 760807424 0.4443897903 -0.0911359340 -0.0219616983 717 1311867194.3447821140 0.0658233687 0.0563692320 0.0664913431 0.0052365998 0.0236090000 230006714 95654128 760807424 0.4457732737 -0.0884880498 -0.0228456333 718 1311867194.3802230358 0.0659666434 0.0563825989 0.0664913431 0.0052335136 0.0234700000 230010242 95654128 760807424 0.4458405077 -0.0897357613 -0.0218132138 719 1311867194.4124519825 0.0667333454 0.0563969949 0.0667333454 0.0052313062 0.0235110000 230012058 95654128 760807424 0.4473266900 -0.0914311111 -0.0201289747 720 1311867194.4447510242 0.0658748597 0.0564101586 0.0667333454 0.0052282870 0.0234700000 230015586 95654128 760807424 0.4470329285 -0.0905581415 -0.0212372914 721 1311867194.4805839062 0.0666494519 0.0564243601 0.0667333454 0.0052269042 0.0235810000 230019258 95654128 760807424 0.4479883015 -0.0893377811 -0.0210347697 722 1311867194.5174930096 0.0655782968 0.0564370387 0.0667333454 0.0052284990 0.0239500000 230021154 95654128 760807424 0.4472394884 -0.0923785418 -0.0206854101 723 1311867194.5439500809 0.0666704476 0.0564511928 0.0667333454 0.0052299114 0.0235560000 230024602 95654128 760807424 0.4487909675 -0.0908092484 -0.0201705657 724 1311867194.5795979500 0.0658245385 0.0564641394 0.0667333454 0.0052270777 0.0235230000 230026330 95654128 760807424 0.4486665428 -0.0906807110 -0.0208534803 725 1311867194.6129479408 0.0660882443 0.0564774141 0.0667333454 0.0052239017 0.0276720000 230030058 95654128 760807424 0.4503679276 -0.0916290730 -0.0200961772 726 1311867194.6493880749 0.0656484365 0.0564900463 0.0667333454 0.0052368112 0.0236600000 230033698 95654128 760807424 0.4491707087 -0.0913927928 -0.0199467000 727 1311867194.6784319878 0.0653163716 0.0565021871 0.0667333454 0.0052382802 0.0235120000 230035458 95654128 760807424 0.4504638016 -0.0914504305 -0.0199654885 728 1311867194.7133309841 0.0657913685 0.0565149469 0.0667333454 0.0052361922 0.0272860000 230038986 95654128 760807424 0.4505762458 -0.0911595747 -0.0191312749 729 1311867194.7475099564 0.0657650754 0.0565276357 0.0667333454 0.0052336427 0.0267860000 230040914 95654128 760807424 0.4513674974 -0.0902593210 -0.0191640146 730 1311867194.7784450054 0.0657775179 0.0565403068 0.0667333454 0.0052309974 0.0236310000 230044386 95654128 760807424 0.4506963789 -0.0902743787 -0.0188101996 731 1311867194.8130390644 0.0657662526 0.0565529278 0.0667333454 0.0052274687 0.0268280000 230048114 95654128 760807424 0.4513951540 -0.0903292373 -0.0185997151 732 1311867194.8476719856 0.0662085414 0.0565661185 0.0667333454 0.0052239914 0.0344440000 230049842 95654128 760807424 0.4521198273 -0.0903878137 -0.0180036239 733 1311867194.8814148903 0.0662950873 0.0565793913 0.0667333454 0.0052205118 0.0244310000 230224658 95654128 760807424 0.4528206587 -0.0900010094 -0.0178078059 734 1311867194.9104089737 0.0666125789 0.0565930605 0.0667333454 0.0052286530 0.0236390000 230228018 95654128 760807424 0.4518214762 -0.0881073922 -0.0180200879 735 1311867194.9451448917 0.0672066659 0.0566075008 0.0672066659 0.0052256422 0.0236560000 230230002 95654128 760807424 0.4500409663 -0.0891646519 -0.0163772143 736 1311867194.9787399769 0.0670019239 0.0566216237 0.0672066659 0.0052222972 0.0235900000 230233530 95654128 760807424 0.4497519732 -0.0891401917 -0.0164387058 737 1311867195.0132799149 0.0663235411 0.0566347877 0.0672066659 0.0052192205 0.0236930000 230235458 95654128 760807424 0.4489853680 -0.0891480669 -0.0166577660 738 1311867195.0464940071 0.0669847056 0.0566488120 0.0672066659 0.0052173809 0.0236270000 230238930 95654128 760807424 0.4461696148 -0.0923775136 -0.0146208527 739 1311867195.0781710148 0.0673669726 0.0566633156 0.0673669726 0.0052203576 0.0236050000 230242602 95654128 760807424 0.4483493865 -0.0892228559 -0.0157926567 740 1311867195.1115310192 0.0669228286 0.0566771798 0.0673669726 0.0052177425 0.0236030000 230244274 95654128 760807424 0.4470004141 -0.0888345242 -0.0166889243 741 1311867195.1458311081 0.0672608837 0.0566914628 0.0673669726 0.0052164279 0.0237090000 230248058 95654128 760807424 0.4453414083 -0.0890002400 -0.0162629690 742 1311867195.1780319214 0.0672546998 0.0567056990 0.0673669726 0.0052151891 0.0271200000 230249730 95654128 760807424 0.4446618855 -0.0857215524 -0.0174607579 743 1311867195.2114748955 0.0658735484 0.0567180379 0.0673669726 0.0052120914 0.0237530000 230253402 95654128 760807424 0.4421173334 -0.0885955319 -0.0173420347 744 1311867195.2436800003 0.0669724345 0.0567318207 0.0673669726 0.0052113146 0.0236900000 230256930 95654128 760807424 0.4438005388 -0.0892582610 -0.0164467320 745 1311867195.2780399323 0.0670269877 0.0567456397 0.0673669726 0.0052100032 0.0237220000 230258858 95654128 760807424 0.4411232471 -0.0871648863 -0.0171391722 746 1311867195.3123180866 0.0680062324 0.0567607344 0.0680062324 0.0052071565 0.0235980000 230262386 95654128 760807424 0.4413649142 -0.0879595578 -0.0161737595 747 1311867195.3425979614 0.0675494894 0.0567751771 0.0680062324 0.0052063275 0.0246850000 230264202 95654128 760807424 0.4382498562 -0.0911207795 -0.0156634431 748 1311867195.3782711029 0.0674625039 0.0567894650 0.0680062324 0.0052035944 0.0236860000 230267786 95654128 760807424 0.4383273125 -0.0887143239 -0.0174379647 749 1311867195.4119830132 0.0675025210 0.0568037682 0.0680062324 0.0052023911 0.0236590000 230271458 95654128 760807424 0.4368622601 -0.0888161063 -0.0178535674 750 1311867195.4435520172 0.0670976862 0.0568174934 0.0680062324 0.0051990519 0.0236300000 230273186 95654128 760807424 0.4327830672 -0.0907364562 -0.0175096150 751 1311867195.4788239002 0.0663904324 0.0568302403 0.0680062324 0.0051973122 0.0325490000 230276914 95654128 760807424 0.4318309724 -0.0868692473 -0.0199362077 752 1311867195.5113179684 0.0662940666 0.0568428252 0.0680062324 0.0051954442 0.0240520000 230280386 95654128 760807424 0.4305302501 -0.0891778693 -0.0194746368 753 1311867195.5439620018 0.0675750077 0.0568570778 0.0680062324 0.0051931176 0.0238030000 230282314 95654128 760807424 0.4300304353 -0.0894009620 -0.0181776118 754 1311867195.5782160759 0.0666364282 0.0568700477 0.0680062324 0.0051914893 0.0236860000 230285842 95654128 760807424 0.4271571040 -0.0873555169 -0.0201226193 755 1311867195.6119859219 0.0669559836 0.0568834066 0.0680062324 0.0051902006 0.0237080000 230287770 95654128 760807424 0.4259817898 -0.0884186998 -0.0195479672 756 1311867195.6430909634 0.0677968040 0.0568978423 0.0680062324 0.0051875100 0.0238490000 230291186 95654128 760807424 0.4245732129 -0.0887334347 -0.0186435357 757 1311867195.6779129505 0.0671294779 0.0569113583 0.0680062324 0.0051846426 0.0237030000 230294970 95654128 760807424 0.4217424095 -0.0869766995 -0.0204458572 758 1311867195.7107300758 0.0664646849 0.0569239616 0.0680062324 0.0051847503 0.0237080000 230296586 95654128 760807424 0.4174165726 -0.0888247713 -0.0202708207 759 1311867195.7458300591 0.0666450039 0.0569367693 0.0680062324 0.0051815268 0.0337460000 230300370 95654128 760807424 0.4142069817 -0.0898033231 -0.0195051990 760 1311867195.7821879387 0.0664330423 0.0569492644 0.0680062324 0.0051786120 0.0241210000 230302098 95654128 760807424 0.4145124257 -0.0887055323 -0.0205939971 761 1311867195.8100500107 0.0675777495 0.0569632309 0.0680062324 0.0051755701 0.0238700000 230305658 95654128 760807424 0.4125919342 -0.0877485573 -0.0199545957 762 1311867195.8458549976 0.0671655461 0.0569766198 0.0680062324 0.0051722400 0.0238460000 230309242 95654128 760807424 0.4089672267 -0.0887940153 -0.0200223923 763 1311867195.8778660297 0.0667200685 0.0569893897 0.0680062324 0.0051696159 0.0273760000 230311170 95654128 760807424 0.4081087112 -0.0865752622 -0.0214488972 764 1311867195.9098269939 0.0664210767 0.0570017348 0.0680062324 0.0051696597 0.0238720000 230314642 95654128 760807424 0.4066505432 -0.0885536745 -0.0208013151 765 1311867195.9458460808 0.0664456859 0.0570140799 0.0680062324 0.0051664285 0.0238950000 230316570 95654128 760807424 0.4046394527 -0.0890430659 -0.0204662737 766 1311867195.9778430462 0.0675498992 0.0570278342 0.0680062324 0.0051648761 0.0238540000 230320098 95654128 760807424 0.4039916694 -0.0861757472 -0.0203311108 767 1311867196.0100569725 0.0659407824 0.0570394547 0.0680062324 0.0051648439 0.0266100000 230323770 95654128 760807424 0.4007177651 -0.0883901566 -0.0210331641 768 1311867196.0498790741 0.0659719035 0.0570510855 0.0680062324 0.0051616906 0.0238130000 230325666 95654128 760807424 0.3989265263 -0.0883134753 -0.0210669506 769 1311867196.0793108940 0.0663851798 0.0570632235 0.0680062324 0.0051610108 0.0239390000 230329338 95654128 760807424 0.3995964825 -0.0857703388 -0.0217878595 770 1311867196.1113979816 0.0667470172 0.0570757998 0.0680062324 0.0051581949 0.0238340000 230332698 95654128 760807424 0.3970640004 -0.0877527595 -0.0204706732 771 1311867196.1473290920 0.0664502382 0.0570879587 0.0680062324 0.0051551387 0.0238200000 230334738 95654128 760807424 0.3940860927 -0.0875706747 -0.0209699795 772 1311867196.1811769009 0.0665523261 0.0571002182 0.0680062324 0.0051540962 0.0238870000 230338266 95654128 760807424 0.3944048285 -0.0864216164 -0.0215275027 773 1311867196.2114949226 0.0671304911 0.0571131940 0.0680062324 0.0051514466 0.0240060000 230340026 95654128 760807424 0.3914870024 -0.0877825543 -0.0204853918 774 1311867196.2462599277 0.0672353804 0.0571262717 0.0680062324 0.0051493147 0.0238590000 230343610 95654128 760807424 0.3910568953 -0.0871072859 -0.0209682956 775 1311867196.2800569534 0.0668471679 0.0571388148 0.0680062324 0.0051463492 0.0238920000 230347338 95654128 760807424 0.3894486427 -0.0871198326 -0.0214079525 776 1311867196.3111600876 0.0674802810 0.0571521415 0.0680062324 0.0051432192 0.0332450000 230348954 95654128 760807424 0.3877493143 -0.0875951126 -0.0206653830 777 1311867196.3484730721 0.0671620741 0.0571650242 0.0680062324 0.0051412462 0.0242460000 230352794 95654128 760807424 0.3862456679 -0.0870257989 -0.0212999340 778 1311867196.3842670918 0.0661660433 0.0571765937 0.0680062324 0.0051381006 0.0238580000 230354522 95654128 760807424 0.3840492964 -0.0861682966 -0.0225933753 779 1311867196.4107549191 0.0676908270 0.0571900908 0.0680062324 0.0051354716 0.0239460000 230358026 95654128 760807424 0.3806574941 -0.0868604034 -0.0202867836 780 1311867196.4463150501 0.0666296333 0.0572021927 0.0680062324 0.0051370358 0.0238460000 230361610 95654128 760807424 0.3778249919 -0.0860027820 -0.0217572600 781 1311867196.4798319340 0.0659513846 0.0572133953 0.0680062324 0.0051355461 0.0238980000 230363538 95654128 760807424 0.3780968487 -0.0864232406 -0.0223198514 782 1311867196.5113470554 0.0664875507 0.0572252548 0.0680062324 0.0051331866 0.0238810000 230366954 95654128 760807424 0.3748247325 -0.0874469727 -0.0208423976 783 1311867196.5468420982 0.0653993413 0.0572356943 0.0680062324 0.0051316385 0.0238760000 230368938 95654128 760807424 0.3729968965 -0.0863378346 -0.0216715317 784 1311867196.5795550346 0.0654297173 0.0572461458 0.0680062324 0.0051316279 0.0272240000 230372466 95654128 760807424 0.3715382814 -0.0851480067 -0.0220868066 785 1311867196.6108930111 0.0660801157 0.0572573993 0.0680062324 0.0051287702 0.0248970000 230376082 95654128 760807424 0.3696661592 -0.0862273425 -0.0206780210 786 1311867196.6521809101 0.0656296536 0.0572680510 0.0680062324 0.0051302311 0.0239110000 230378034 95654128 760807424 0.3675414324 -0.0849728212 -0.0212145783 787 1311867196.6805100441 0.0652218536 0.0572781575 0.0680062324 0.0051455384 0.0238140000 230381594 95654128 760807424 0.3661287129 -0.0835442618 -0.0213126689 788 1311867196.7112100124 0.0657285973 0.0572888814 0.0680062324 0.0051445138 0.0239900000 230385010 95654128 760807424 0.3631826043 -0.0837014094 -0.0205953177 789 1311867196.7464900017 0.0668975413 0.0573010597 0.0680062324 0.0051417044 0.0239790000 230386994 95654128 760807424 0.3622012138 -0.0806113705 -0.0203450434 790 1311867196.7783749104 0.0654883757 0.0573114234 0.0680062324 0.0051387313 0.0275910000 230390522 95654128 760807424 0.3577032089 -0.0815229639 -0.0210927762 791 1311867196.8109180927 0.0657122359 0.0573220439 0.0680062324 0.0051394494 0.0239430000 230392282 95654128 760807424 0.3561687768 -0.0829063505 -0.0201510917 792 1311867196.8488750458 0.0660821125 0.0573331046 0.0680062324 0.0051398680 0.0239070000 230395978 95654128 760807424 0.3532024324 -0.0817415789 -0.0200989097 793 1311867196.8821749687 0.0658551753 0.0573438512 0.0680062324 0.0051366951 0.0275820000 230399650 95654128 760807424 0.3507684767 -0.0809018761 -0.0205740556 794 1311867196.9115700722 0.0670771599 0.0573561098 0.0680062324 0.0051339867 0.0240210000 230401210 95654128 760807424 0.3486991227 -0.0817067400 -0.0190435685 795 1311867196.9482440948 0.0670805424 0.0573683418 0.0680062324 0.0051321960 0.0240330000 230405050 95654128 760807424 0.3453836739 -0.0818324834 -0.0190644506 796 1311867196.9809880257 0.0668178797 0.0573802130 0.0680062324 0.0051300870 0.0239850000 230406778 95654128 760807424 0.3426212370 -0.0806250870 -0.0200961884 797 1311867197.0154891014 0.0675349757 0.0573929543 0.0680062324 0.0051273543 0.0239870000 230410450 95654128 760807424 0.3425877690 -0.0816409513 -0.0195370093 798 1311867197.0490679741 0.0672130883 0.0574052602 0.0680062324 0.0051248577 0.0241210000 230413978 95654128 760807424 0.3389316499 -0.0809916332 -0.0202451721 799 1311867197.0806479454 0.0666269064 0.0574168017 0.0680062324 0.0051233252 0.0242500000 230415738 95654128 760807424 0.3357526362 -0.0818751678 -0.0207884312 800 1311867197.1148109436 0.0670651048 0.0574288621 0.0680062324 0.0051210291 0.0239830000 230419322 95654128 760807424 0.3355057538 -0.0824129134 -0.0204224456 801 1311867197.1468429565 0.0658551976 0.0574393818 0.0680062324 0.0051185498 0.0239830000 230421194 95654128 760807424 0.3317860663 -0.0818955675 -0.0221047048 802 1311867197.1792430878 0.0666709617 0.0574508925 0.0680062324 0.0051170585 0.0276470000 230424722 95654128 760807424 0.3301367164 -0.0811735988 -0.0215320885 803 1311867197.2143619061 0.0658841506 0.0574613947 0.0680062324 0.0051162561 0.0240910000 230428450 95654128 760807424 0.3260771930 -0.0818271190 -0.0220860969 804 1311867197.2459290028 0.0655513778 0.0574714569 0.0680062324 0.0051132884 0.0271250000 230430122 95654128 760807424 0.3249288797 -0.0813144594 -0.0226946436 805 1311867197.2799959183 0.0658132359 0.0574818194 0.0680062324 0.0051120937 0.0241000000 230433906 95654128 760807424 0.3228265047 -0.0818753839 -0.0220856089 806 1311867197.3157260418 0.0661536753 0.0574925785 0.0680062324 0.0051106433 0.0240950000 230437378 95654128 760807424 0.3192320168 -0.0796901137 -0.0226054471 807 1311867197.3468708992 0.0657506064 0.0575028115 0.0680062324 0.0051078796 0.0272700000 230439250 95654128 760807424 0.3162762821 -0.0805948451 -0.0227367915 808 1311867197.3784019947 0.0661320165 0.0575134912 0.0680062324 0.0051051837 0.0240840000 230442666 95654128 760807424 0.3149468303 -0.0805585980 -0.0226404238 809 1311867197.4155099392 0.0660162494 0.0575240014 0.0680062324 0.0051021717 0.0241520000 230444650 95654128 760807424 0.3124611080 -0.0817868114 -0.0227619912 810 1311867197.4478878975 0.0676575899 0.0575365120 0.0680062324 0.0051003802 0.0280640000 230618874 95654128 760807424 0.3121109307 -0.0785203800 -0.0232906304 811 1311867197.4793179035 0.0667584538 0.0575478831 0.0680062324 0.0050974994 0.0242730000 230622434 95654128 760807424 0.3084604740 -0.0801513046 -0.0237845387 812 1311867197.5150759220 0.0657589510 0.0575579952 0.0680062324 0.0050948988 0.0241770000 230624218 95654128 760807424 0.3046856225 -0.0804223046 -0.0254198164 813 1311867197.5469260216 0.0657226890 0.0575680379 0.0680062324 0.0050926121 0.0241340000 230627834 95654128 760807424 0.3049141169 -0.0795785338 -0.0266674235 814 1311867197.5802750587 0.0662722737 0.0575787311 0.0680062324 0.0050899248 0.0279580000 230629562 95654128 760807424 0.3006695211 -0.0805050284 -0.0266338009 815 1311867197.6152749062 0.0657256991 0.0575887273 0.0680062324 0.0050885099 0.0241110000 230633290 95654128 760807424 0.2991900146 -0.0792422369 -0.0285911132 816 1311867197.6470439434 0.0644581243 0.0575971457 0.0680062324 0.0050875451 0.0241260000 230636762 95654128 760807424 0.2972726822 -0.0787705258 -0.0306707267 817 1311867197.6800849438 0.0658891350 0.0576072950 0.0680062324 0.0050876110 0.0241910000 230638690 95654128 760807424 0.2947225273 -0.0790474340 -0.0295817964 818 1311867197.7143290043 0.0648014918 0.0576160899 0.0680062324 0.0050876702 0.0241720000 230642218 95654128 760807424 0.2934269011 -0.0772316009 -0.0320809595 819 1311867197.7463419437 0.0645405054 0.0576245446 0.0680062324 0.0050872517 0.0271770000 230644090 95654128 760807424 0.2902419865 -0.0768031478 -0.0329942070 820 1311867197.7793009281 0.0653313324 0.0576339431 0.0680062324 0.0050848375 0.0277380000 230647618 95654128 760807424 0.2885980606 -0.0784600601 -0.0319664776 821 1311867197.8146750927 0.0646972358 0.0576425464 0.0680062324 0.0050868317 0.0242230000 230651402 95654128 760807424 0.2872488201 -0.0757982805 -0.0347099937 822 1311867197.8467919827 0.0646731481 0.0576510995 0.0680062324 0.0050861992 0.0241170000 230653018 95654128 760807424 0.2854821086 -0.0778383315 -0.0347035713 823 1311867197.8802978992 0.0649994090 0.0576600281 0.0680062324 0.0050849465 0.0241050000 230656690 95654128 760807424 0.2832683027 -0.0776885450 -0.0353800543 824 1311867197.9148609638 0.0655903965 0.0576696524 0.0680062324 0.0050906159 0.0241150000 230660274 95654128 760807424 0.2813044190 -0.0734636411 -0.0374949574 825 1311867197.9470140934 0.0649663955 0.0576784969 0.0680062324 0.0050996975 0.0250770000 230662146 95654128 760807424 0.2785850465 -0.0761533156 -0.0374050178 826 1311867197.9812700748 0.0646573752 0.0576869459 0.0680062324 0.0050967942 0.0275910000 230665674 95654128 760807424 0.2774884105 -0.0754571483 -0.0386171490 827 1311867198.0145471096 0.0644274354 0.0576950965 0.0680062324 0.0050951715 0.0241110000 230667658 95654128 760807424 0.2747341394 -0.0736265630 -0.0400471874 828 1311867198.0463368893 0.0645645335 0.0577033929 0.0680062324 0.0050930158 0.0241500000 230671074 95654128 760807424 0.2713547945 -0.0739990771 -0.0400677249 829 1311867198.0787069798 0.0645266920 0.0577116236 0.0680062324 0.0050932591 0.0240710000 230674802 95654128 760807424 0.2686692774 -0.0735336021 -0.0411115289 830 1311867198.1143770218 0.0645866171 0.0577199068 0.0680062324 0.0050908976 0.0240900000 230676530 95654128 760807424 0.2677923441 -0.0713966638 -0.0423567928 831 1311867198.1463611126 0.0648810267 0.0577285242 0.0680062324 0.0050879386 0.0240830000 230680202 95654128 760807424 0.2651672959 -0.0709859207 -0.0426635295 832 1311867198.1822519302 0.0649689659 0.0577372267 0.0680062324 0.0050857309 0.0241530000 230681986 95654128 760807424 0.2631833255 -0.0710283741 -0.0431332067 833 1311867198.2144989967 0.0646984801 0.0577455835 0.0680062324 0.0050927401 0.0272560000 230685658 95654128 760807424 0.2620441020 -0.0712005347 -0.0439889953 834 1311867198.2464120388 0.0649026707 0.0577541652 0.0680062324 0.0050905954 0.0241410000 230689130 95654128 760807424 0.2585249245 -0.0712999031 -0.0444447324 835 1311867198.2821578979 0.0646708831 0.0577624487 0.0680062324 0.0050887601 0.0241610000 230691114 95654128 760807424 0.2561138272 -0.0684450790 -0.0465330742 836 1311867198.3159120083 0.0648383722 0.0577709127 0.0680062324 0.0050875301 0.0241130000 230694586 95654128 760807424 0.2538013756 -0.0680791065 -0.0473589413 837 1311867198.3481218815 0.0647458434 0.0577792459 0.0680062324 0.0050846765 0.0273770000 230696458 95654128 760807424 0.2502209544 -0.0697819293 -0.0476465076 838 1311867198.3828320503 0.0646198094 0.0577874089 0.0680062324 0.0050878641 0.0248860000 230700042 95654128 760807424 0.2487034351 -0.0664370954 -0.0494894274 839 1311867198.4242680073 0.0643507242 0.0577952317 0.0680062324 0.0050928529 0.0241210000 230703770 95654128 760807424 0.2450356781 -0.0659408271 -0.0509276949 840 1311867198.4497859478 0.0648420155 0.0578036207 0.0680062324 0.0050920786 0.0241120000 230705162 95654128 760807424 0.2406652570 -0.0677124336 -0.0508463010 841 1311867198.4856219292 0.0647090003 0.0578118316 0.0680062324 0.0050959422 0.0240850000 230708834 95654128 760807424 0.2406461686 -0.0658040345 -0.0531057715 842 1311867198.5190339088 0.0648250654 0.0578201609 0.0680062324 0.0050940498 0.0240730000 230712362 95654128 760807424 0.2378460020 -0.0649401620 -0.0544062406 843 1311867198.5499279499 0.0653262734 0.0578290649 0.0680062324 0.0050923705 0.0283230000 230885606 95654128 760807424 0.2328020632 -0.0661625564 -0.0540364012 844 1311867198.5824239254 0.0644306391 0.0578368867 0.0680062324 0.0050897486 0.0242030000 230889078 95654128 760807424 0.2315909117 -0.0633098409 -0.0570810847 845 1311867198.6147489548 0.0644033253 0.0578446576 0.0680062324 0.0050943727 0.0241720000 230890950 95654128 760807424 0.2302018255 -0.0645020753 -0.0571455434 846 1311867198.6482009888 0.0636441931 0.0578515129 0.0680062324 0.0050930819 0.0277440000 230894422 95654128 760807424 0.2267981321 -0.0643900931 -0.0584939122 847 1311867198.6827540398 0.0626707450 0.0578572026 0.0680062324 0.0050926287 0.0242370000 230898150 95654128 760807424 0.2220842242 -0.0630373433 -0.0609440692 848 1311867198.7146520615 0.0626023561 0.0578627983 0.0680062324 0.0050897919 0.0241740000 230899766 95654128 760807424 0.2209689468 -0.0626794323 -0.0617623702 849 1311867198.7467699051 0.0636735186 0.0578696425 0.0680062324 0.0050888717 0.0241750000 230903382 95654128 760807424 0.2188162804 -0.0615448654 -0.0620392598 850 1311867198.7842700481 0.0628949404 0.0578755547 0.0680062324 0.0050861490 0.0240960000 230905166 95654128 760807424 0.2147777081 -0.0598407909 -0.0642696545 851 1311867198.8149418831 0.0632902682 0.0578819174 0.0680062324 0.0050843383 0.0370120000 230908782 95654128 760807424 0.2134932280 -0.0603860840 -0.0641558170 852 1311867198.8464009762 0.0635778978 0.0578886028 0.0680062324 0.0050836808 0.0248830000 230912254 95654128 760807424 0.2107744813 -0.0582013465 -0.0652777404 853 1311867198.8845369816 0.0632032454 0.0578948334 0.0680062324 0.0050825130 0.0241720000 230914182 95654128 760807424 0.2078308612 -0.0579201877 -0.0666349381 854 1311867198.9147930145 0.0631615669 0.0579010005 0.0680062324 0.0050799604 0.0241260000 230917598 95654128 760807424 0.2057291418 -0.0571643226 -0.0676521659 855 1311867198.9465179443 0.0630883723 0.0579070676 0.0680062324 0.0050772053 0.0240710000 230919470 95654128 760807424 0.2051942199 -0.0559816100 -0.0686220676 856 1311867198.9839329720 0.0631498247 0.0579131923 0.0680062324 0.0050748020 0.0240940000 230923166 95654128 760807424 0.2030164450 -0.0544473045 -0.0696145818 857 1311867199.0148730278 0.0622954108 0.0579183058 0.0680062324 0.0050775934 0.0241290000 230926782 95654128 760807424 0.2011348754 -0.0536548235 -0.0712480247 858 1311867199.0468010902 0.0633524805 0.0579246393 0.0680062324 0.0050774907 0.0241590000 230928454 95654128 760807424 0.2004062086 -0.0521969832 -0.0719318613 859 1311867199.0849320889 0.0638480037 0.0579315350 0.0680062324 0.0050784276 0.0275470000 230932350 95654128 760807424 0.2007333636 -0.0502410829 -0.0729595274 860 1311867199.1149818897 0.0640459135 0.0579386447 0.0680062324 0.0050762509 0.0242090000 230935710 95654128 760807424 0.1973648965 -0.0498917624 -0.0736796781 861 1311867199.1465420723 0.0642890856 0.0579460204 0.0680062324 0.0050734213 0.0241720000 230937582 95654128 760807424 0.1973104030 -0.0482951254 -0.0750071108 862 1311867199.1823658943 0.0643296465 0.0579534260 0.0680062324 0.0050719139 0.0272230000 230941166 95654128 760807424 0.1974986345 -0.0463249274 -0.0767256618 863 1311867199.2146680355 0.0650120527 0.0579616051 0.0680062324 0.0050692437 0.0284690000 230943094 95654128 760807424 0.1950251460 -0.0461172350 -0.0771195889 864 1311867199.2467749119 0.0645533353 0.0579692344 0.0680062324 0.0050665133 0.0242040000 230946510 95654128 760807424 0.1932804435 -0.0450446084 -0.0789006427 865 1311867199.2833590508 0.0651084185 0.0579774878 0.0680062324 0.0050635861 0.0272930000 230950350 95654128 760807424 0.1927719414 -0.0432706736 -0.0800320655 866 1311867199.3159129620 0.0649283007 0.0579855142 0.0680062324 0.0050638261 0.0241700000 230951910 95654128 760807424 0.1892226785 -0.0442579873 -0.0808854923 867 1311867199.3465209007 0.0649536252 0.0579935512 0.0680062324 0.0050616751 0.0353750000 230955526 95654128 760807424 0.1880699098 -0.0432107523 -0.0824352428 868 1311867199.3829050064 0.0646505207 0.0580012205 0.0680062324 0.0050588878 0.0246310000 230957366 95654128 760807424 0.1857806742 -0.0427551419 -0.0842220783 869 1311867199.4147589207 0.0647258982 0.0580089589 0.0680062324 0.0050563487 0.0241380000 230960982 95654128 760807424 0.1850322336 -0.0438415967 -0.0846097246 870 1311867199.4512910843 0.0649586841 0.0580169471 0.0680062324 0.0050542215 0.0241650000 230964622 95654128 760807424 0.1826473922 -0.0416912548 -0.0865699351 871 1311867199.4837360382 0.0651721507 0.0580251621 0.0680062324 0.0050520071 0.0241510000 230966494 95654128 760807424 0.1819210351 -0.0408966951 -0.0876797512 872 1311867199.5150198936 0.0647994131 0.0580329307 0.0680062324 0.0050494257 0.0241170000 230969966 95654128 760807424 0.1787654907 -0.0406828336 -0.0891114473 873 1311867199.5544059277 0.0652809590 0.0580412331 0.0680062324 0.0050505309 0.0242100000 230972062 95654128 760807424 0.1763952225 -0.0398066491 -0.0898914114 874 1311867199.5835030079 0.0659833699 0.0580503203 0.0680062324 0.0050479722 0.0242160000 230975478 95654128 760807424 0.1731133014 -0.0383356251 -0.0903692245 875 1311867199.6158308983 0.0651505738 0.0580584348 0.0680062324 0.0050489013 0.0336350000 230979038 95654128 760807424 0.1718259007 -0.0383105241 -0.0914477035 876 1311867199.6538460255 0.0644879639 0.0580657745 0.0680062324 0.0050463851 0.0277450000 230980934 95654128 760807424 0.1683168709 -0.0382197052 -0.0927113965 877 1311867199.6824479103 0.0645995438 0.0580732246 0.0680062324 0.0050436192 0.0242080000 230984494 95654128 760807424 0.1652345210 -0.0382855237 -0.0930228084 878 1311867199.7146759033 0.0648030862 0.0580808896 0.0680062324 0.0050439105 0.0241330000 230988022 95654128 760807424 0.1619030088 -0.0375015438 -0.0936187357 879 1311867199.7511539459 0.0652486756 0.0580890441 0.0680062324 0.0050441359 0.0241040000 230989950 95654128 760807424 0.1587563753 -0.0356216952 -0.0945638195 880 1311867199.7826020718 0.0647846535 0.0580966527 0.0680062324 0.0050436205 0.0241250000 230993422 95654128 760807424 0.1564068794 -0.0370388664 -0.0945985541 881 1311867199.8150150776 0.0646710917 0.0581041152 0.0680062324 0.0050479563 0.0241230000 230995294 95654128 760807424 0.1527729183 -0.0370181501 -0.0952848941 882 1311867199.8519051075 0.0654316545 0.0581124231 0.0680062324 0.0050456125 0.0241100000 230998878 95654128 760807424 0.1513654590 -0.0343059339 -0.0962459147 883 1311867199.8839609623 0.0648471639 0.0581200502 0.0680062324 0.0050471498 0.0277890000 231002606 95654128 760807424 0.1473075598 -0.0369888023 -0.0959103853 884 1311867199.9148159027 0.0643198714 0.0581270636 0.0680062324 0.0050468896 0.0241880000 231004278 95654128 760807424 0.1462906003 -0.0370473601 -0.0965471715 885 1311867199.9520709515 0.0652583912 0.0581351216 0.0680062324 0.0050467062 0.0272190000 231008062 95654128 760807424 0.1434868276 -0.0344103798 -0.0976035893 886 1311867199.9828410149 0.0648590922 0.0581427107 0.0680062324 0.0050446906 0.0277120000 231009678 95654128 760807424 0.1398537904 -0.0359467715 -0.0975792110 887 1311867200.0144031048 0.0640589520 0.0581493806 0.0680062324 0.0050420393 0.0242610000 231013350 95654128 760807424 0.1374573410 -0.0362734646 -0.0983662978 888 1311867200.0539638996 0.0638330430 0.0581557811 0.0680062324 0.0050398761 0.0274350000 231017046 95654128 760807424 0.1362431198 -0.0347188711 -0.0993524864 889 1311867200.0830330849 0.0633432791 0.0581616164 0.0680062324 0.0050373299 0.0241520000 231018806 95654128 760807424 0.1332968026 -0.0366280414 -0.0988704711 890 1311867200.1174468994 0.0627740994 0.0581667989 0.0680062324 0.0050382116 0.0241130000 231022334 95654128 760807424 0.1318074614 -0.0352044962 -0.0998401865 891 1311867200.1517000198 0.0630797148 0.0581723129 0.0680062324 0.0050374519 0.0279120000 231024262 95654128 760807424 0.1294835806 -0.0338401273 -0.0999913812 892 1311867200.1853220463 0.0630831122 0.0581778182 0.0680062324 0.0050369425 0.0241350000 231027846 95654128 760807424 0.1249683723 -0.0359466560 -0.0990974009 893 1311867200.2179059982 0.0632830113 0.0581835351 0.0680062324 0.0050389650 0.0241350000 231031518 95654128 760807424 0.1228202954 -0.0326290987 -0.1003866866 894 1311867200.2522649765 0.0626274496 0.0581885060 0.0680062324 0.0050373125 0.0242170000 231033246 95654128 760807424 0.1213184372 -0.0338249542 -0.0997366533 895 1311867200.2825429440 0.0627673045 0.0581936219 0.0680062324 0.0050346834 0.0241200000 231036862 95654128 760807424 0.1183394417 -0.0342018418 -0.0987939015 896 1311867200.3148880005 0.0625648722 0.0581985006 0.0680062324 0.0050338558 0.0241830000 231040390 95654128 760807424 0.1142229438 -0.0329593457 -0.0993653759 897 1311867200.3514990807 0.0627166480 0.0582035375 0.0680062324 0.0050349328 0.0241600000 231042318 95654128 760807424 0.1114528477 -0.0344604552 -0.0980599672 898 1311867200.3837759495 0.0629195720 0.0582087892 0.0680062324 0.0050484031 0.0241470000 231045846 95654128 760807424 0.1083954945 -0.0327890813 -0.0984785631 899 1311867200.4162800312 0.0625234693 0.0582135886 0.0680062324 0.0050474883 0.0275630000 231047662 95654128 760807424 0.1069564447 -0.0334757604 -0.0981844366 900 1311867200.4522490501 0.0621547028 0.0582179677 0.0680062324 0.0050462830 0.0242150000 231051246 95654128 760807424 0.1017073616 -0.0352437869 -0.0977013633 901 1311867200.4850699902 0.0617085211 0.0582218417 0.0680062324 0.0050466075 0.0250120000 231225526 95654128 760807424 0.1013288796 -0.0346785784 -0.0978834778 902 1311867200.5143918991 0.0616946705 0.0582256919 0.0680062324 0.0050484797 0.0241830000 231227198 95654128 760807424 0.0985932276 -0.0357403122 -0.0969102383 903 1311867200.5505030155 0.0614714250 0.0582292863 0.0680062324 0.0050527355 0.0242420000 231230982 95654128 760807424 0.0962665081 -0.0348302796 -0.0965694711 904 1311867200.5832219124 0.0622730888 0.0582337595 0.0680062324 0.0050581012 0.0242780000 231232654 95654128 760807424 0.0926035196 -0.0336619504 -0.0963338390 905 1311867200.6145610809 0.0615279414 0.0582373995 0.0680062324 0.0050562153 0.0242260000 231236270 95654128 760807424 0.0904677957 -0.0353749916 -0.0956162438 906 1311867200.6504778862 0.0607496202 0.0582401724 0.0680062324 0.0050563596 0.0244350000 231239854 95654128 760807424 0.0854024515 -0.0355127454 -0.0957455114 907 1311867200.6851279736 0.0605364107 0.0582427040 0.0680062324 0.0050551366 0.0273260000 231241838 95654128 760807424 0.0833135843 -0.0354269668 -0.0952931270 908 1311867200.7189719677 0.0602149516 0.0582448761 0.0680062324 0.0050546595 0.0242210000 231245366 95654128 760807424 0.0780623630 -0.0360373184 -0.0951480195 909 1311867200.7503669262 0.0609711371 0.0582478753 0.0680062324 0.0050531587 0.0242490000 231247182 95654128 760807424 0.0783187076 -0.0325617120 -0.0952447131 910 1311867200.7832930088 0.0599904768 0.0582497903 0.0680062324 0.0050563608 0.0241910000 231250710 95654128 760807424 0.0760421902 -0.0346928164 -0.0944972932 911 1311867200.8181068897 0.0603414439 0.0582520863 0.0680062324 0.0050545378 0.0241990000 231254438 95654128 760807424 0.0705839023 -0.0350509025 -0.0933437645 912 1311867200.8501501083 0.0602830797 0.0582543132 0.0680062324 0.0050517737 0.0241500000 231256054 95654128 760807424 0.0694729015 -0.0331863835 -0.0936223194 913 1311867200.8845369816 0.0603231117 0.0582565792 0.0680062324 0.0050531581 0.0243850000 231430398 95654128 760807424 0.0657807291 -0.0329688601 -0.0932993442 914 1311867200.9194929600 0.0603630915 0.0582588839 0.0680062324 0.0050555012 0.0250050000 231433926 95654128 760807424 0.0623585768 -0.0344296172 -0.0922589898 915 1311867200.9512679577 0.0595531687 0.0582602984 0.0680062324 0.0050587192 0.0242850000 231435742 95654128 760807424 0.0607150979 -0.0350634307 -0.0921756178 916 1311867200.9856009483 0.0597772077 0.0582619544 0.0680062324 0.0050667153 0.0243000000 231439326 95654128 760807424 0.0587454773 -0.0353492424 -0.0924138129 917 1311867201.0184400082 0.0599250942 0.0582637681 0.0680062324 0.0050640937 0.0242780000 231441198 95654128 760807424 0.0558698326 -0.0365700386 -0.0920441076 918 1311867201.0555179119 0.0598766133 0.0582655250 0.0680062324 0.0050624189 0.0242520000 231444838 95654128 760807424 0.0527630970 -0.0354442708 -0.0932571888 919 1311867201.0825428963 0.0597807169 0.0582671737 0.0680062324 0.0050614895 0.0242310000 231448342 95654128 760807424 0.0513033532 -0.0364437997 -0.0931601375 920 1311867201.1193449497 0.0601884238 0.0582692621 0.0680062324 0.0050608581 0.0242470000 231450182 95654128 760807424 0.0510084182 -0.0360700749 -0.0929277912 921 1311867201.1506710052 0.0605995841 0.0582717923 0.0680062324 0.0050587991 0.0243160000 231453742 95654128 760807424 0.0505667627 -0.0354410596 -0.0928905755 922 1311867201.1830160618 0.0606944598 0.0582744199 0.0680062324 0.0050566434 0.0242620000 231455414 95654128 760807424 0.0485118553 -0.0355399847 -0.0930294320 923 1311867201.2196528912 0.0608403869 0.0582771999 0.0680062324 0.0050559482 0.0242100000 231459142 95654128 760807424 0.0459329225 -0.0358522460 -0.0929062739 924 1311867201.2503149509 0.0607135147 0.0582798366 0.0680062324 0.0050533349 0.0296110000 231462614 95654128 760807424 0.0448275954 -0.0356258899 -0.0931479633 925 1311867201.2824099064 0.0613343418 0.0582831388 0.0680062324 0.0050514140 0.0243990000 231464486 95654128 760807424 0.0451981798 -0.0338275582 -0.0931498557 926 1311867201.3180539608 0.0614485741 0.0582865572 0.0680062324 0.0050524375 0.0243340000 231468070 95654128 760807424 0.0396193452 -0.0350555703 -0.0932889581 927 1311867201.3522200584 0.0606797077 0.0582891388 0.0680062324 0.0050509979 0.0242980000 231469998 95654128 760807424 0.0382629298 -0.0343513675 -0.0944870710 928 1311867201.3842790127 0.0605523549 0.0582915776 0.0680062324 0.0050517278 0.0265740000 231499646 95654128 760807424 0.0354133286 -0.0318182595 -0.0959401876 929 1311867201.4198760986 0.0604919977 0.0582939462 0.0680062324 0.0050781207 0.0279250000 231503318 95654128 760807424 0.0330867209 -0.0337417386 -0.0941445976 930 1311867201.4558579922 0.0606914572 0.0582965242 0.0680062324 0.0050796062 0.0243210000 231504990 95654128 760807424 0.0320150219 -0.0314556956 -0.0945897996 931 1311867201.4853110313 0.0600635223 0.0582984221 0.0680062324 0.0050771627 0.0243790000 231679446 95654128 760807424 0.0307946354 -0.0301926099 -0.0954280123 932 1311867201.5198690891 0.0597287081 0.0582999568 0.0680062324 0.0050776040 0.0243350000 231683030 95654128 760807424 0.0262131952 -0.0308988709 -0.0951240361 933 1311867201.5527739525 0.0591733642 0.0583008929 0.0680062324 0.0050796904 0.0267660000 231685230 95654128 760807424 0.0234432258 -0.0307015441 -0.0955071896 934 1311867201.5840220451 0.0594803318 0.0583021557 0.0680062324 0.0050771956 0.0267300000 231688894 95654128 760807424 0.0211343840 -0.0302944221 -0.0953449011 935 1311867201.6197049618 0.0599158667 0.0583038816 0.0680062324 0.0050778608 0.0281070000 231690878 95654128 760807424 0.0169380251 -0.0295011923 -0.0958782360 936 1311867201.6515579224 0.0596672520 0.0583053382 0.0680062324 0.0050773342 0.0243540000 231694294 95654128 760807424 0.0143225603 -0.0297090877 -0.0961109921 937 1311867201.6839449406 0.0591472685 0.0583062367 0.0680062324 0.0050748610 0.0266950000 231698598 95654128 760807424 0.0131678162 -0.0290418137 -0.0967824981 938 1311867201.7189009190 0.0603163987 0.0583083797 0.0680062324 0.0050742507 0.0265810000 231700318 95654128 760807424 0.0122368047 -0.0258166399 -0.0970960408 939 1311867201.7507290840 0.0597096235 0.0583098720 0.0680062324 0.0050729916 0.0266220000 231704054 95654128 760807424 0.0106015271 -0.0268916637 -0.0968256295 940 1311867201.7858049870 0.0593062602 0.0583109320 0.0680062324 0.0050774998 0.0361520000 231705662 95654128 760807424 0.0085680168 -0.0262300875 -0.0968036875 941 1311867201.8190178871 0.0597936884 0.0583125077 0.0680062324 0.0050833604 0.0267090000 231709510 95654128 760807424 0.0066619324 -0.0227526948 -0.0983104780 942 1311867201.8505740166 0.0598801263 0.0583141718 0.0680062324 0.0050863304 0.0267070000 231712990 95654128 760807424 0.0047666659 -0.0231790878 -0.0978092626 943 1311867201.8862850666 0.0600189827 0.0583159797 0.0680062324 0.0050840580 0.0268080000 231714982 95654128 760807424 0.0046018558 -0.0236797817 -0.0970552117 944 1311867201.9195730686 0.0608914495 0.0583187080 0.0680062324 0.0050853184 0.0267000000 231718630 95654128 760807424 0.0030176665 -0.0204546116 -0.0980601236 945 1311867201.9516520500 0.0604999438 0.0583210161 0.0680062324 0.0050851803 0.0266270000 231720454 95654128 760807424 0.0021017452 -0.0220715571 -0.0976921171 946 1311867201.9894599915 0.0595517941 0.0583223172 0.0680062324 0.0050827056 0.0308890000 231724342 95654128 760807424 0.0014242628 -0.0232423041 -0.0983899161 947 1311867202.0184879303 0.0599056445 0.0583239891 0.0680062324 0.0050820407 0.0266520000 231727966 95654128 760807424 -0.0030366774 -0.0217259061 -0.0999201760 948 1311867202.0507359505 0.0600372218 0.0583257963 0.0680062324 0.0050795456 0.0381390000 231729702 95654128 760807424 -0.0029254016 -0.0210053585 -0.1002834141 949 1311867202.0866351128 0.0572087280 0.0583246192 0.0680062324 0.0050843042 0.0358950000 231738390 95654128 760807424 -0.0015352269 -0.0268089343 -0.0999832973 950 1311867202.1185920238 0.0577554666 0.0583240201 0.0680062324 0.0050852197 0.0321890000 231742438 95654128 760807424 -0.0027005025 -0.0265357886 -0.0992003754 951 1311867202.1516621113 0.0577667579 0.0583234341 0.0680062324 0.0050829491 0.0274070000 231744430 95654128 760807424 -0.0035794212 -0.0254106317 -0.0995017886 952 1311867202.1866259575 0.0573919341 0.0583224557 0.0680062324 0.0050804149 0.0270420000 231748022 95654128 760807424 -0.0042244140 -0.0253816694 -0.0996558070 953 1311867202.2191269398 0.0577588379 0.0583218643 0.0680062324 0.0050782497 0.0272300000 231749958 95654128 760807424 -0.0085199326 -0.0272903014 -0.0988046229 954 1311867202.2513220310 0.0576739348 0.0583211851 0.0680062324 0.0050759575 0.0270870000 231753438 95654128 760807424 -0.0085711880 -0.0240323506 -0.0997249261 955 1311867202.2868280411 0.0572281368 0.0583200405 0.0680062324 0.0050743434 0.0410540000 231757286 95654128 760807424 -0.0095998663 -0.0237411652 -0.0999886692 956 1311867202.3199880123 0.0567624904 0.0583184113 0.0680062324 0.0050749850 0.0272560000 231758894 95654128 760807424 -0.0105934767 -0.0265996270 -0.0992513299 957 1311867202.3523900509 0.0576425157 0.0583177050 0.0680062324 0.0050749565 0.0271710000 231933630 95654128 760807424 -0.0122801624 -0.0246808808 -0.0989718512 958 1311867202.3883628845 0.0566966422 0.0583160129 0.0680062324 0.0050725221 0.0272460000 231935542 95654128 760807424 -0.0144707561 -0.0242852010 -0.0998580083 959 1311867202.4196391106 0.0571452454 0.0583147921 0.0680062324 0.0050739588 0.0272190000 231939150 95654128 760807424 -0.0151388142 -0.0235252064 -0.0998141617 960 1311867202.4529430866 0.0579442345 0.0583144061 0.0680062324 0.0050718262 0.0272100000 231942686 95654128 760807424 -0.0159913339 -0.0247207545 -0.0984949395 961 1311867202.4875710011 0.0577100217 0.0583137772 0.0680062324 0.0050723006 0.0270990000 231944678 95654128 760807424 -0.0183315296 -0.0226677451 -0.0999381319 962 1311867202.5206449032 0.0582520142 0.0583137130 0.0680062324 0.0050883539 0.0319630000 231948214 95654128 760807424 -0.0189744383 -0.0234428123 -0.0990383402 963 1311867202.5508940220 0.0580243878 0.0583134125 0.0680062324 0.0050863075 0.0272810000 231949838 95654128 760807424 -0.0186337661 -0.0237085484 -0.0991095603 964 1311867202.5864949226 0.0589536019 0.0583140766 0.0680062324 0.0050956252 0.0271440000 231953670 95654128 760807424 -0.0197793674 -0.0226580668 -0.0991681144 965 1311867202.6185030937 0.0588513501 0.0583146334 0.0680062324 0.0051005507 0.0272190000 231957662 95654128 760807424 -0.0208358876 -0.0233940668 -0.0995888039 966 1311867202.6514449120 0.0586506538 0.0583149812 0.0680062324 0.0051071879 0.0272100000 231959398 95654128 760807424 -0.0253534559 -0.0232372619 -0.1008877829 967 1311867202.6866559982 0.0585370213 0.0583152108 0.0680062324 0.0051050527 0.0317960000 231962990 95654128 760807424 -0.0251670573 -0.0221198127 -0.1017379463 968 1311867202.7185359001 0.0582859851 0.0583151807 0.0680062324 0.0051044142 0.0271750000 231966526 95654128 760807424 -0.0275339857 -0.0253483243 -0.1019577086 969 1311867202.7507350445 0.0591982938 0.0583160920 0.0680062324 0.0051018984 0.0272560000 231968334 95654128 760807424 -0.0286661908 -0.0246817656 -0.1024119183 970 1311867202.7897169590 0.0590358377 0.0583168340 0.0680062324 0.0050995635 0.0407760000 231971966 95654128 760807424 -0.0291017946 -0.0230786297 -0.1042706296 971 1311867202.8190000057 0.0588403717 0.0583173732 0.0680062324 0.0050978333 0.0273180000 231973846 95654128 760807424 -0.0322265141 -0.0239616446 -0.1051312909 972 1311867202.8527579308 0.0576455556 0.0583166820 0.0680062324 0.0050954668 0.0271870000 232148138 95654128 760807424 -0.0332066044 -0.0260131471 -0.1057486236 973 1311867202.8873219490 0.0574584380 0.0583158000 0.0680062324 0.0050957628 0.0288030000 232151866 95654128 760807424 -0.0343146361 -0.0238484964 -0.1069722027 974 1311867202.9199879169 0.0578222349 0.0583152932 0.0680062324 0.0050943795 0.0248300000 232153538 95654128 760807424 -0.0348132811 -0.0222377516 -0.1073190123 975 1311867202.9525690079 0.0574683845 0.0583144246 0.0680062324 0.0050961939 0.0248470000 232157266 95654128 760807424 -0.0356094316 -0.0244282819 -0.1068923622 976 1311867202.9868710041 0.0580746122 0.0583141789 0.0680062324 0.0050978220 0.0248610000 232158994 95654128 760807424 -0.0361719429 -0.0226481706 -0.1068176031 977 1311867203.0202019215 0.0574813597 0.0583133265 0.0680062324 0.0050958201 0.0320740000 232162666 95654128 760807424 -0.0362429991 -0.0219481438 -0.1076091379 978 1311867203.0560851097 0.0569582470 0.0583119409 0.0680062324 0.0051000268 0.0274670000 232166698 95654128 760807424 -0.0371206999 -0.0260803364 -0.1066208109 979 1311867203.0865778923 0.0583953522 0.0583120261 0.0680062324 0.0051016226 0.0272320000 232193154 95654128 760807424 -0.0361124612 -0.0237780716 -0.1064612567 980 1311867203.1189930439 0.0583196059 0.0583120338 0.0680062324 0.0051080376 0.0273360000 232196818 95654128 760807424 -0.0360488221 -0.0243930891 -0.1066723838 981 1311867203.1549820900 0.0583245903 0.0583120466 0.0680062324 0.0051187977 0.0319300000 232198738 95654128 760807424 -0.0362329297 -0.0284611806 -0.1055580005 982 1311867203.1877939701 0.0589251816 0.0583126710 0.0680062324 0.0051528075 0.0274890000 232202530 95654128 760807424 -0.0329996347 -0.0295419395 -0.1049034148 983 1311867203.2185909748 0.0599534065 0.0583143401 0.0680062324 0.0051566197 0.0272580000 232206138 95654128 760807424 -0.0329230540 -0.0254839454 -0.1065721214 984 1311867203.2552030087 0.0588110574 0.0583148449 0.0680062324 0.0051590131 0.0277290000 232208242 95654128 760807424 -0.0330512188 -0.0297586769 -0.1066224650 985 1311867203.2864799500 0.0583403707 0.0583148708 0.0680062324 0.0051603124 0.0392130000 232211922 95654128 760807424 -0.0325146057 -0.0323207602 -0.1065483168 986 1311867203.3194670677 0.0594660603 0.0583160384 0.0680062324 0.0051600359 0.0273690000 232215314 95654128 760807424 -0.0330948904 -0.0296016317 -0.1074929833 987 1311867203.3547461033 0.0587831661 0.0583165117 0.0680062324 0.0051579908 0.0273230000 232217250 95654128 760807424 -0.0313738063 -0.0297108199 -0.1084707379 988 1311867203.3865599632 0.0582575426 0.0583164520 0.0680062324 0.0051635759 0.0273600000 232220786 95654128 760807424 -0.0318527892 -0.0312858820 -0.1089539230 989 1311867203.4183609486 0.0587180331 0.0583168580 0.0680062324 0.0051704333 0.0272160000 232222778 95654128 760807424 -0.0324934013 -0.0375575349 -0.1068248972 990 1311867203.4545118809 0.0588027723 0.0583173488 0.0680062324 0.0051690140 0.0271970000 232226298 95654128 760807424 -0.0305872448 -0.0368452631 -0.1074600220 991 1311867203.4864439964 0.0585205033 0.0583175538 0.0680062324 0.0051696076 0.0273790000 232230234 95654128 760807424 -0.0310268290 -0.0373172313 -0.1086456776 992 1311867203.5185539722 0.0581254177 0.0583173602 0.0680062324 0.0051744410 0.0393670000 232232026 95654128 760807424 -0.0323529132 -0.0427675061 -0.1081943512 993 1311867203.5560259819 0.0584166683 0.0583174602 0.0680062324 0.0051726493 0.0275390000 232235618 95654128 760807424 -0.0311630145 -0.0445821807 -0.1084107608 994 1311867203.5876550674 0.0593406335 0.0583184895 0.0680062324 0.0051735651 0.0273220000 232237354 95654128 760807424 -0.0310867988 -0.0429332070 -0.1094984412 995 1311867203.6191980839 0.0578575209 0.0583180262 0.0680062324 0.0051750936 0.0273900000 232241090 95654128 760807424 -0.0318262912 -0.0477750003 -0.1100654826 996 1311867203.6557719707 0.0588811971 0.0583185917 0.0680062324 0.0051726731 0.0274590000 232244682 95654128 760807424 -0.0316473916 -0.0497165546 -0.1094247252 997 1311867203.6866750717 0.0584414341 0.0583187149 0.0680062324 0.0051701088 0.0274150000 232246746 95654128 760807424 -0.0318369493 -0.0509041250 -0.1103948876 998 1311867203.7195260525 0.0588635653 0.0583192608 0.0680062324 0.0051680244 0.0273990000 232250282 95654128 760807424 -0.0316040628 -0.0523228347 -0.1102866083 999 1311867203.7566421032 0.0589799993 0.0583199222 0.0680062324 0.0051665082 0.0393550000 232252130 95654128 760807424 -0.0303617269 -0.0533456206 -0.1106330380 1000 1311867203.7867228985 0.0588984154 0.0583205007 0.0680062324 0.0051641555 0.0275100000 232255738 95654128 760807424 -0.0312106945 -0.0545142628 -0.1114951521 1001 1311867203.8193860054 0.0589629933 0.0583211426 0.0680062324 0.0051618797 0.0274490000 232259474 95654128 760807424 -0.0294759218 -0.0557891987 -0.1116753817 1002 1311867203.8572859764 0.0586443581 0.0583214651 0.0680062324 0.0051607289 0.0274440000 232261378 95654128 760807424 -0.0299730413 -0.0580106191 -0.1124201119 1003 1311867203.8891890049 0.0582058094 0.0583213498 0.0680062324 0.0051610290 0.0475440000 232264986 95654128 760807424 -0.0299863350 -0.0618451461 -0.1124619171 1004 1311867203.9188020229 0.0581636876 0.0583211928 0.0680062324 0.0051600098 0.0288710000 232268594 95654128 760807424 -0.0307452474 -0.0618743263 -0.1139505953 1005 1311867203.9553489685 0.0587727129 0.0583216421 0.0680062324 0.0051585397 0.0274670000 232270514 95654128 760807424 -0.0286997445 -0.0609712638 -0.1147901788 1006 1311867203.9866371155 0.0584120117 0.0583217319 0.0680062324 0.0051582051 0.0276030000 232274050 95654128 760807424 -0.0304879565 -0.0650101453 -0.1150426343 1007 1311867204.0199849606 0.0586438216 0.0583220517 0.0680062324 0.0051576727 0.0249110000 232275922 95654128 760807424 -0.0300264750 -0.0655474514 -0.1161396727 1008 1311867204.0551509857 0.0587649532 0.0583224911 0.0680062324 0.0051561616 0.0249200000 232279506 95654128 760807424 -0.0316237509 -0.0650836229 -0.1184134409 1009 1311867204.0867509842 0.0585455634 0.0583227122 0.0680062324 0.0051551738 0.0249360000 232283178 95654128 760807424 -0.0318077803 -0.0679108724 -0.1186301187 1010 1311867204.1191530228 0.0576355010 0.0583220318 0.0680062324 0.0051532837 0.0249180000 232284850 95654128 760807424 -0.0312158968 -0.0709658042 -0.1199557185 1011 1311867204.1555769444 0.0568970405 0.0583206223 0.0680062324 0.0051507987 0.0248580000 232288578 95654128 760807424 -0.0302251223 -0.0726666823 -0.1213492751 1012 1311867204.1876530647 0.0564987436 0.0583188220 0.0680062324 0.0051492163 0.0248370000 232290250 95654128 760807424 -0.0317550302 -0.0747309625 -0.1224077940 1013 1311867204.2187769413 0.0562172942 0.0583167475 0.0680062324 0.0051485205 0.0248850000 232464198 95654128 760807424 -0.0318529941 -0.0775340050 -0.1225006655 1014 1311867204.2566440105 0.0551706925 0.0583136449 0.0680062324 0.0051478330 0.0248000000 232467838 95654128 760807424 -0.0302446261 -0.0786270797 -0.1243680865 1015 1311867204.2867140770 0.0549723208 0.0583103529 0.0680062324 0.0051453557 0.0247590000 232469654 95654128 760807424 -0.0315182246 -0.0821745843 -0.1244885474 1016 1311867204.3204538822 0.0554124303 0.0583075006 0.0680062324 0.0051438633 0.0256520000 232473126 95654128 760807424 -0.0324241407 -0.0837704241 -0.1247959882 1017 1311867204.3625741005 0.0558048561 0.0583050398 0.0680062324 0.0051417344 0.0248420000 232475334 95654128 760807424 -0.0320642740 -0.0847451016 -0.1251019239 1018 1311867204.3869600296 0.0547836646 0.0583015807 0.0680062324 0.0051395570 0.0247340000 232478582 95654128 760807424 -0.0329792611 -0.0886820927 -0.1255686283 1019 1311867204.4240970612 0.0554168671 0.0582987498 0.0680062324 0.0051384916 0.0247040000 232482422 95654128 760807424 -0.0336451307 -0.0888531432 -0.1263511628 1020 1311867204.4549949169 0.0553315133 0.0582958407 0.0680062324 0.0051387444 0.0248070000 232654254 95654128 760807424 -0.0330901667 -0.0889158845 -0.1272010654 1021 1311867204.4872748852 0.0554232374 0.0582930272 0.0680062324 0.0051367466 0.0283610000 232657926 95654128 760807424 -0.0328817219 -0.0900014862 -0.1277432591 1022 1311867204.5237219334 0.0558305942 0.0582906178 0.0680062324 0.0051344124 0.0282340000 232661566 95654128 760807424 -0.0337536708 -0.0914212391 -0.1280329227 1023 1311867204.5581860542 0.0550992526 0.0582874982 0.0680062324 0.0051333018 0.0246710000 232663494 95654128 760807424 -0.0334812142 -0.0943732411 -0.1282824725 1024 1311867204.5878469944 0.0552011356 0.0582844841 0.0680062324 0.0051311744 0.0245840000 232666910 95654128 760807424 -0.0340951011 -0.0953352302 -0.1284856796 1025 1311867204.6241528988 0.0546498112 0.0582809381 0.0680062324 0.0051289845 0.0247430000 232857310 95654128 760807424 -0.0344338641 -0.0966097564 -0.1288910806 1026 1311867204.6541819572 0.0546758547 0.0582774244 0.0680062324 0.0051265870 0.0247070000 233235914 95654128 760807424 -0.0350374058 -0.0979638696 -0.1291978806 1027 1311867204.6871540546 0.0544028468 0.0582736517 0.0680062324 0.0051243610 0.0277760000 233239586 95654128 760807424 -0.0356470793 -0.0997251347 -0.1294261664 1028 1311867204.7225689888 0.0540412441 0.0582695345 0.0680062324 0.0051229732 0.0246220000 233241370 95654128 760807424 -0.0351929963 -0.1010121852 -0.1294479221 1029 1311867204.7539510727 0.0532444492 0.0582646511 0.0680062324 0.0051210587 0.0245770000 233245042 95654128 760807424 -0.0355624445 -0.1031901091 -0.1292149276 1030 1311867204.7878720760 0.0537350476 0.0582602534 0.0680062324 0.0051221155 0.0280140000 233246770 95654128 760807424 -0.0370200723 -0.1044887081 -0.1280099601 1031 1311867204.8227200508 0.0542462207 0.0582563601 0.0680062324 0.0051203489 0.0248170000 233250498 95654128 760807424 -0.0388999358 -0.1047708839 -0.1271572858 1032 1311867204.8542668819 0.0538786948 0.0582521181 0.0680062324 0.0051195912 0.0245750000 233253970 95654128 760807424 -0.0387191698 -0.1049517468 -0.1267817169 1033 1311867204.8864960670 0.0538052171 0.0582478133 0.0680062324 0.0051179934 0.0246610000 233255842 95654128 760807424 -0.0400949456 -0.1088672429 -0.1251335740 1034 1311867204.9220221043 0.0545140132 0.0582442023 0.0680062324 0.0051159693 0.0246040000 233259426 95654128 760807424 -0.0426768847 -0.1099648550 -0.1242589355 1035 1311867204.9542920589 0.0540693216 0.0582401686 0.0680062324 0.0051149771 0.0246610000 233261298 95654128 760807424 -0.0423662029 -0.1112493053 -0.1237538159 1036 1311867204.9865999222 0.0525390618 0.0582346656 0.0680062324 0.0051157465 0.0246280000 233264770 95654128 760807424 -0.0408546850 -0.1163142845 -0.1227706596 1037 1311867205.0227239132 0.0527800284 0.0582294056 0.0680062324 0.0051209535 0.0245760000 233268554 95654128 760807424 -0.0412888117 -0.1206581146 -0.1208496690 1038 1311867205.0550808907 0.0527352318 0.0582241125 0.0680062324 0.0051353857 0.0245630000 233440774 95654128 760807424 -0.0411210619 -0.1192954257 -0.1204606965 1039 1311867205.0880999565 0.0520067140 0.0582181285 0.0680062324 0.0051343273 0.0283890000 233444334 95654128 760807424 -0.0417162366 -0.1230183467 -0.1197277158 1040 1311867205.1232450008 0.0523771755 0.0582125122 0.0680062324 0.0051332226 0.0245680000 233447918 95654128 760807424 -0.0421960279 -0.1252085268 -0.1190008894 1041 1311867205.1545319557 0.0532594882 0.0582077543 0.0680062324 0.0051456341 0.0245510000 233449734 95654128 760807424 -0.0408656262 -0.1244519353 -0.1185114980 1042 1311867205.1863510609 0.0529128946 0.0582026728 0.0680062324 0.0051536090 0.0253400000 233453206 95654128 760807424 -0.0416789986 -0.1279084682 -0.1176102385 1043 1311867205.2223129272 0.0519592762 0.0581966868 0.0680062324 0.0051547890 0.0246390000 233455190 95654128 760807424 -0.0410819016 -0.1314555854 -0.1170068905 1044 1311867205.2541849613 0.0520245880 0.0581907748 0.0680062324 0.0051555899 0.0275840000 233458662 95654128 760807424 -0.0408450589 -0.1322678179 -0.1164808646 1045 1311867205.2880499363 0.0522264950 0.0581850674 0.0680062324 0.0051536260 0.0282090000 233462390 95654128 760807424 -0.0409650095 -0.1332813948 -0.1160072386 1046 1311867205.3218879700 0.0529610589 0.0581800731 0.0680062324 0.0051545415 0.0280080000 233464062 95654128 760807424 -0.0412517302 -0.1340816766 -0.1151879802 1047 1311867205.3542900085 0.0527283065 0.0581748661 0.0680062324 0.0051582454 0.0245180000 233467790 95654128 760807424 -0.0416770540 -0.1358105391 -0.1146731898 1048 1311867205.3862779140 0.0528418086 0.0581697773 0.0680062324 0.0051658234 0.0245220000 233469462 95654128 760807424 -0.0421450846 -0.1393949240 -0.1129178256 1049 1311867205.4225649834 0.0513234250 0.0581632507 0.0680062324 0.0051715550 0.0244990000 233473246 95654128 760807424 -0.0423529297 -0.1429620236 -0.1128362492 1050 1311867205.4540419579 0.0513736866 0.0581567845 0.0680062324 0.0051768781 0.0243810000 233476718 95654128 760807424 -0.0435504578 -0.1435704976 -0.1127006114 1051 1311867205.4865119457 0.0508379564 0.0581498208 0.0680062324 0.0051783001 0.0278230000 233478590 95654128 760807424 -0.0439411849 -0.1443462372 -0.1118972525 1052 1311867205.5230340958 0.0509543903 0.0581429811 0.0680062324 0.0051883585 0.0245640000 233652278 95654128 760807424 -0.0454548933 -0.1474110186 -0.1103505045 1053 1311867205.5542900562 0.0509532951 0.0581361532 0.0680062324 0.0052121460 0.0244510000 233654150 95654128 760807424 -0.0461934060 -0.1473397017 -0.1098848283 1054 1311867205.5866839886 0.0515884869 0.0581299410 0.0680062324 0.0052097580 0.0281550000 233657622 95654128 760807424 -0.0477568991 -0.1477778405 -0.1084228009 1055 1311867205.6226179600 0.0511212535 0.0581232977 0.0680062324 0.0052145280 0.0254100000 233661406 95654128 760807424 -0.0495287478 -0.1502381712 -0.1075882614 1056 1311867205.6555979252 0.0507131256 0.0581162805 0.0680062324 0.0052131424 0.0243880000 233663078 95654128 760807424 -0.0505510047 -0.1531126648 -0.1066397130 1057 1311867205.6902959347 0.0512496233 0.0581097842 0.0680062324 0.0052108799 0.0244330000 233666862 95654128 760807424 -0.0502833202 -0.1529573053 -0.1059762836 1058 1311867205.7222061157 0.0507205725 0.0581028000 0.0680062324 0.0052090992 0.0274960000 233670334 95654128 760807424 -0.0537471510 -0.1589054167 -0.1053949445 1059 1311867205.7548348904 0.0513956770 0.0580964666 0.0680062324 0.0052076267 0.0244770000 233842634 95654128 760807424 -0.0535922609 -0.1597752124 -0.1043966115 1060 1311867205.7906379700 0.0511895232 0.0580899506 0.0680062324 0.0052062398 0.0244430000 233846162 95654128 760807424 -0.0544271991 -0.1605286300 -0.1046746522 1061 1311867205.8232109547 0.0503566675 0.0580826619 0.0680062324 0.0052201752 0.0244570000 233848090 95654128 760807424 -0.0553131402 -0.1653413028 -0.1041644886 1062 1311867205.8554759026 0.0506671295 0.0580756793 0.0680062324 0.0052252303 0.0335930000 233851618 95654128 760807424 -0.0559606701 -0.1660624743 -0.1036563963 1063 1311867205.8905880451 0.0508042872 0.0580688389 0.0680062324 0.0052244790 0.0245930000 233855290 95654128 760807424 -0.0571290255 -0.1669927984 -0.1036588848 1064 1311867205.9223020077 0.0505922250 0.0580618120 0.0680062324 0.0052298796 0.0243830000 233856962 95654128 760807424 -0.0580138117 -0.1684633493 -0.1035689190 1065 1311867205.9544939995 0.0509115979 0.0580550982 0.0680062324 0.0052279425 0.0243640000 233860634 95654128 760807424 -0.0588516854 -0.1690538675 -0.1035058796 1066 1311867205.9905850887 0.0501706898 0.0580477019 0.0680062324 0.0052346913 0.0243380000 233862474 95654128 760807424 -0.0605565757 -0.1725925058 -0.1034334451 1067 1311867206.0259850025 0.0514224805 0.0580414927 0.0680062324 0.0052405338 0.0243610000 233866202 95654128 760807424 -0.0613051131 -0.1700933576 -0.1035062522 1068 1311867206.0604250431 0.0510509834 0.0580349473 0.0680062324 0.0052563532 0.0243660000 233869674 95654128 760807424 -0.0637684315 -0.1761608273 -0.1024256349 1069 1311867206.0903289318 0.0505823828 0.0580279757 0.0680062324 0.0052552113 0.0244300000 233871490 95654128 760807424 -0.0642546788 -0.1788941175 -0.1025198698 1070 1311867206.1227540970 0.0509169139 0.0580213299 0.0680062324 0.0052534362 0.0347090000 233874962 95654128 760807424 -0.0630685166 -0.1784229577 -0.1024813652 1071 1311867206.1546130180 0.0508019514 0.0580145891 0.0680062324 0.0052516583 0.0248090000 233876834 95654128 760807424 -0.0629941821 -0.1832750738 -0.1017828286 1072 1311867206.1903800964 0.0504848920 0.0580075651 0.0680062324 0.0052512010 0.0274230000 233880474 95654128 760807424 -0.0644563809 -0.1868236512 -0.1020203978 1073 1311867206.2239561081 0.0503966548 0.0580004720 0.0680062324 0.0052502483 0.0243200000 233884202 95654128 760807424 -0.0643965378 -0.1869128793 -0.1026619375 1074 1311867206.2553579807 0.0503705703 0.0579933678 0.0680062324 0.0052493553 0.0244470000 233885818 95654128 760807424 -0.0640867203 -0.1870309561 -0.1031796411 1075 1311867206.2904770374 0.0495246835 0.0579854900 0.0680062324 0.0052482815 0.0244300000 233889546 95654128 760807424 -0.0643406361 -0.1920157820 -0.1030300334 1076 1311867206.3222041130 0.0494789146 0.0579775842 0.0680062324 0.0052463128 0.0245210000 234063222 95654128 760807424 -0.0648795143 -0.1923872828 -0.1036952361 1077 1311867206.3542530537 0.0499426760 0.0579701238 0.0680062324 0.0052446833 0.0244330000 234065150 95654128 760807424 -0.0662332848 -0.1936396509 -0.1036936417 1078 1311867206.3900070190 0.0498909391 0.0579626292 0.0680062324 0.0052455153 0.0244580000 234068678 95654128 760807424 -0.0669020265 -0.1970383823 -0.1033714712 1079 1311867206.4220259190 0.0498851351 0.0579551431 0.0680062324 0.0052462405 0.0245630000 234070550 95654128 760807424 -0.0663995445 -0.1966689527 -0.1039156839 1080 1311867206.4542310238 0.0499415100 0.0579477231 0.0680062324 0.0052448220 0.0248810000 234074078 95654128 760807424 -0.0664896742 -0.1978789717 -0.1038025916 1081 1311867206.4905378819 0.0489240885 0.0579393756 0.0680062324 0.0052597884 0.0247520000 234077806 95654128 760807424 -0.0667266399 -0.2026491165 -0.1033757851 1082 1311867206.5250329971 0.0491007045 0.0579312067 0.0680062324 0.0052614981 0.0324550000 234079590 95654128 760807424 -0.0681082010 -0.2055661976 -0.1036179215 1083 1311867206.5539300442 0.0484306514 0.0579224343 0.0680062324 0.0052650131 0.0261560000 234083206 95654128 760807424 -0.0670023337 -0.2066670507 -0.1042704061 1084 1311867206.5921130180 0.0495717861 0.0579147308 0.0680062324 0.0052634049 0.0280460000 234084990 95654128 760807424 -0.0696635544 -0.2081820965 -0.1045829728 1085 1311867206.6226360798 0.0497177467 0.0579071759 0.0680062324 0.0052719369 0.0242900000 234088606 95654128 760807424 -0.0692489818 -0.2102784812 -0.1049205512 1086 1311867206.6566751003 0.0492515899 0.0578992058 0.0680062324 0.0052705352 0.0356290000 234092134 95654128 760807424 -0.0696757287 -0.2116680145 -0.1052090004 1087 1311867206.6945209503 0.0491145886 0.0578911243 0.0680062324 0.0052686383 0.0247360000 234094174 95654128 760807424 -0.0697033703 -0.2126455605 -0.1058663577 1088 1311867206.7248480320 0.0488579795 0.0578828217 0.0680062324 0.0052763526 0.0244200000 234267850 95654128 760807424 -0.0697657689 -0.2146720141 -0.1057222039 1089 1311867206.7587969303 0.0494529568 0.0578750808 0.0680062324 0.0053246403 0.0243070000 234269834 95654128 760807424 -0.0703387335 -0.2184469253 -0.1059587449 1090 1311867206.7902839184 0.0488847122 0.0578668328 0.0680062324 0.0053438432 0.0243120000 234273306 95654128 760807424 -0.0699863806 -0.2183492333 -0.1064665690 1091 1311867206.8229770660 0.0482792147 0.0578580448 0.0680062324 0.0053445626 0.0244910000 234276978 95654128 760807424 -0.0712342858 -0.2227769643 -0.1070102453 1092 1311867206.8605449200 0.0487857722 0.0578497369 0.0680062324 0.0053430023 0.0245300000 234278762 95654128 760807424 -0.0712181479 -0.2232704610 -0.1075319424 1093 1311867206.8907771111 0.0483575948 0.0578410524 0.0680062324 0.0053408891 0.0242800000 234282378 95654128 760807424 -0.0704824105 -0.2233362645 -0.1085691378 1094 1311867206.9225020409 0.0487563685 0.0578327483 0.0680062324 0.0053384846 0.0280090000 234285850 95654128 760807424 -0.0711791292 -0.2248168290 -0.1089798361 1095 1311867206.9592480659 0.0485342182 0.0578242565 0.0680062324 0.0053365466 0.0242610000 234287890 95654128 760807424 -0.0723036006 -0.2306546271 -0.1092640013 1096 1311867206.9948680401 0.0486026332 0.0578158426 0.0680062324 0.0053419077 0.0243910000 234461362 95654128 760807424 -0.0722574815 -0.2325672060 -0.1094040871 1097 1311867207.0247550011 0.0487755202 0.0578076017 0.0680062324 0.0053441397 0.0241920000 234463234 95654128 760807424 -0.0726333335 -0.2347765416 -0.1099378765 1098 1311867207.0597259998 0.0481036454 0.0577987638 0.0680062324 0.0053426047 0.0241470000 234466818 95654128 760807424 -0.0722411573 -0.2361325324 -0.1106264517 1099 1311867207.0942800045 0.0475166105 0.0577894079 0.0680062324 0.0053479988 0.0279470000 234470490 95654128 760807424 -0.0727498680 -0.2412932813 -0.1105792820 1100 1311867207.1229140759 0.0472990014 0.0577798712 0.0680062324 0.0053526741 0.0241500000 234472050 95654128 760807424 -0.0724352449 -0.2408981472 -0.1117094308 1101 1311867207.1583549976 0.0469992831 0.0577700795 0.0680062324 0.0053583941 0.0241560000 234475834 95654128 760807424 -0.0714486167 -0.2425260693 -0.1121232063 1102 1311867207.1904919147 0.0472486317 0.0577605319 0.0680062324 0.0053579717 0.0346180000 234477450 95654128 760807424 -0.0715763643 -0.2429017872 -0.1121109650 1103 1311867207.2226181030 0.0468717329 0.0577506600 0.0680062324 0.0053580069 0.0245080000 234481178 95654128 760807424 -0.0709170774 -0.2441980988 -0.1119728908 1104 1311867207.2604830265 0.0463919267 0.0577403713 0.0680062324 0.0053579350 0.0242520000 234484818 95654128 760807424 -0.0717277303 -0.2481706738 -0.1115659922 1105 1311867207.2926900387 0.0459267534 0.0577296802 0.0680062324 0.0053590190 0.0274170000 234486690 95654128 760807424 -0.0718663260 -0.2513193488 -0.1111084819 1106 1311867207.3235239983 0.0464897119 0.0577195175 0.0680062324 0.0053644957 0.0242900000 234660186 95654128 760807424 -0.0732356980 -0.2535368204 -0.1106146276 1107 1311867207.3597478867 0.0459016114 0.0577088419 0.0680062324 0.0053632520 0.0243590000 234662226 95654128 760807424 -0.0723085329 -0.2517297864 -0.1109774262 1108 1311867207.3901309967 0.0463901721 0.0576986265 0.0680062324 0.0053640929 0.0241680000 234665642 95654128 760807424 -0.0738466680 -0.2546962202 -0.1098454669 1109 1311867207.4227840900 0.0460896157 0.0576881585 0.0680062324 0.0053623099 0.0242330000 234669314 95654128 760807424 -0.0753483996 -0.2579724789 -0.1092323884 1110 1311867207.4586789608 0.0444849096 0.0576762636 0.0680062324 0.0053626926 0.0298890000 234671098 95654128 760807424 -0.0723212138 -0.2589242756 -0.1090742946 1111 1311867207.4927639961 0.0454901978 0.0576652951 0.0680062324 0.0053625032 0.0242730000 234674826 95654128 760807424 -0.0752119049 -0.2607507706 -0.1085968986 1112 1311867207.5237300396 0.0456019379 0.0576544467 0.0680062324 0.0053659923 0.0279090000 234678298 95654128 760807424 -0.0770452395 -0.2646849453 -0.1081017256 1113 1311867207.5598409176 0.0449187011 0.0576430040 0.0680062324 0.0053648276 0.0242320000 234680226 95654128 760807424 -0.0774876475 -0.2673704326 -0.1081556976 1114 1311867207.5944800377 0.0449594334 0.0576316184 0.0680062324 0.0053657138 0.0241910000 234683810 95654128 760807424 -0.0777425468 -0.2686504722 -0.1078097075 1115 1311867207.6259219646 0.0447464101 0.0576200622 0.0680062324 0.0053634226 0.0241480000 234685626 95654128 760807424 -0.0795204639 -0.2722066939 -0.1075946838 1116 1311867207.6592938900 0.0449489281 0.0576087081 0.0680062324 0.0053625946 0.0240970000 234689210 95654128 760807424 -0.0814129040 -0.2745102644 -0.1077779606 1117 1311867207.6923089027 0.0456971116 0.0575980442 0.0680062324 0.0053636977 0.0249170000 234692882 95654128 760807424 -0.0827713758 -0.2751396596 -0.1075667739 1118 1311867207.7238640785 0.0450969674 0.0575868625 0.0680062324 0.0053666918 0.0276970000 234864490 95654128 760807424 -0.0829469413 -0.2794141769 -0.1072950140 1119 1311867207.7588050365 0.0443876982 0.0575750670 0.0680062324 0.0053644430 0.0241780000 234868106 95654128 760807424 -0.0832532495 -0.2811097801 -0.1078313515 1120 1311867207.7921919823 0.0457379781 0.0575644982 0.0680062324 0.0053634073 0.0241200000 234869834 95654128 760807424 -0.0867546424 -0.2810241282 -0.1079936698 1121 1311867207.8237760067 0.0444177650 0.0575527705 0.0680062324 0.0053641853 0.0272770000 234873506 95654128 760807424 -0.0846333951 -0.2858656943 -0.1071407273 1122 1311867207.8608479500 0.0446223244 0.0575412461 0.0680062324 0.0053633133 0.0279140000 234877090 95654128 760807424 -0.0855678022 -0.2885345519 -0.1070139781 1123 1311867207.8937089443 0.0447980836 0.0575298986 0.0680062324 0.0053615473 0.0241140000 234879018 95654128 760807424 -0.0858033523 -0.2883642912 -0.1071368456 1124 1311867207.9244139194 0.0443027206 0.0575181307 0.0680062324 0.0053616767 0.0240760000 234882434 95654128 760807424 -0.0858490691 -0.2919502556 -0.1066007316 1125 1311867207.9614970684 0.0436627567 0.0575058148 0.0680062324 0.0053618382 0.0241650000 235054258 95654128 760807424 -0.0859507322 -0.2929280698 -0.1066835150 1126 1311867207.9914131165 0.0442138128 0.0574940102 0.0680062324 0.0053855497 0.0277740000 235057674 95654128 760807424 -0.0852822885 -0.2917353511 -0.1066889539 1127 1311867208.0248498917 0.0439797975 0.0574820189 0.0680062324 0.0054086486 0.0241720000 235061458 95654128 760807424 -0.0868878141 -0.2961327136 -0.1062051579 1128 1311867208.0618500710 0.0441851430 0.0574702309 0.0680062324 0.0054075173 0.0240080000 235063074 95654128 760807424 -0.0877570286 -0.2995753884 -0.1060561240 1129 1311867208.0924620628 0.0440865830 0.0574583764 0.0680062324 0.0054060569 0.0240040000 235066690 95654128 760807424 -0.0869071260 -0.2987348139 -0.1061974317 1130 1311867208.1276559830 0.0437090471 0.0574462089 0.0680062324 0.0054053955 0.0243770000 235070218 95654128 760807424 -0.0853276774 -0.2998528183 -0.1058263928 1131 1311867208.1596069336 0.0443695411 0.0574346468 0.0680062324 0.0054038188 0.0240340000 235072090 95654128 760807424 -0.0876377076 -0.2991491854 -0.1068592668 1132 1311867208.1905009747 0.0444644243 0.0574231890 0.0680062324 0.0054043229 0.0239940000 235075450 95654128 760807424 -0.0892035067 -0.3035329282 -0.1069107652 1133 1311867208.2280850410 0.0443814658 0.0574116783 0.0680062324 0.0054022011 0.0239590000 235077546 95654128 760807424 -0.0889677107 -0.3039071262 -0.1073695272 1134 1311867208.2581789494 0.0439311378 0.0573997907 0.0680062324 0.0054002919 0.0270440000 235080962 95654128 760807424 -0.0891264305 -0.3061722219 -0.1076896191 1135 1311867208.2901990414 0.0437075347 0.0573877270 0.0680062324 0.0053979676 0.0276820000 235084578 95654128 760807424 -0.0885307416 -0.3061859012 -0.1081251875 1136 1311867208.3270208836 0.0434853174 0.0573754890 0.0680062324 0.0053976429 0.0239780000 235255622 95654128 760807424 -0.0878731012 -0.3109978735 -0.1077614129 1137 1311867208.3580970764 0.0429225825 0.0573627775 0.0680062324 0.0053984360 0.0272230000 235259294 95654128 760807424 -0.0878561288 -0.3131598830 -0.1077757776 1138 1311867208.3910560608 0.0429529399 0.0573501151 0.0680062324 0.0053973942 0.0240670000 235260910 95654128 760807424 -0.0881660581 -0.3123281002 -0.1083630323 1139 1311867208.4260230064 0.0427416228 0.0573372894 0.0680062324 0.0053957848 0.0239340000 235264694 95654128 760807424 -0.0879259631 -0.3141980171 -0.1083200052 1140 1311867208.4577419758 0.0429318324 0.0573246530 0.0680062324 0.0053970570 0.0271620000 235268166 95654128 760807424 -0.0881401598 -0.3146509528 -0.1090268567 1141 1311867208.4907650948 0.0430546515 0.0573121464 0.0680062324 0.0053951203 0.0239690000 235270094 95654128 760807424 -0.0882336870 -0.3144030273 -0.1090914384 1142 1311867208.5257411003 0.0427273214 0.0572993751 0.0680062324 0.0053938423 0.0272560000 235273678 95654128 760807424 -0.0888722241 -0.3173879087 -0.1084290966 1143 1311867208.5583798885 0.0427848957 0.0572866766 0.0680062324 0.0053918754 0.0239110000 235275550 95654128 760807424 -0.0899169594 -0.3182727695 -0.1083973050 1144 1311867208.5904500484 0.0429750942 0.0572741664 0.0680062324 0.0053899853 0.0239170000 235279078 95654128 760807424 -0.0904031992 -0.3210319877 -0.1074183956 1145 1311867208.6259779930 0.0424616262 0.0572612297 0.0680062324 0.0053880255 0.0239360000 235282750 95654128 760807424 -0.0897640735 -0.3205209374 -0.1070452183 1146 1311867208.6582078934 0.0424357168 0.0572482930 0.0680062324 0.0053861368 0.0239850000 235284478 95654128 760807424 -0.0909340233 -0.3241438866 -0.1062459722 1147 1311867208.6910300255 0.0410866253 0.0572342026 0.0680062324 0.0053869066 0.0240300000 235288150 95654128 760807424 -0.0895760879 -0.3228496313 -0.1054842770 1148 1311867208.7262260914 0.0416175388 0.0572205992 0.0680062324 0.0053856717 0.0239860000 235291734 95654128 760807424 -0.0900667310 -0.3253825605 -0.1049194634 1149 1311867208.7591009140 0.0419448614 0.0572073044 0.0680062324 0.0053836818 0.0240360000 235293606 95654128 760807424 -0.0912017226 -0.3260125220 -0.1042882726 1150 1311867208.7909750938 0.0422455706 0.0571942942 0.0680062324 0.0053829189 0.0342060000 235297022 95654128 760807424 -0.0934611931 -0.3292785883 -0.1040051579 1151 1311867208.8259930611 0.0419302434 0.0571810327 0.0680062324 0.0053821546 0.0242190000 235299006 95654128 760807424 -0.0918573886 -0.3301799297 -0.1030233875 1152 1311867208.8588190079 0.0419578180 0.0571678181 0.0680062324 0.0053902068 0.0237810000 235302534 95654128 760807424 -0.0922533348 -0.3312768042 -0.1031135321 1153 1311867208.8916258812 0.0428045541 0.0571553608 0.0680062324 0.0053949911 0.0238510000 235306150 95654128 760807424 -0.0972394943 -0.3295189440 -0.1030760109 1154 1311867208.9275119305 0.0425804257 0.0571427308 0.0680062324 0.0053939088 0.0276450000 235307878 95654128 760807424 -0.0958375409 -0.3312569857 -0.1032366455 1155 1311867208.9577760696 0.0430675820 0.0571305446 0.0680062324 0.0053935836 0.0245940000 235311494 95654128 760807424 -0.0969591290 -0.3360953629 -0.1026711687 1156 1311867208.9911639690 0.0433807708 0.0571186503 0.0680062324 0.0053924262 0.0271400000 235482814 95654128 760807424 -0.0976867750 -0.3362993598 -0.1031621993 1157 1311867209.0270779133 0.0430427641 0.0571064844 0.0680062324 0.0053937311 0.0237330000 235486598 95654128 760807424 -0.0964652672 -0.3397556841 -0.1029331908 1158 1311867209.0579569340 0.0435532518 0.0570947804 0.0680062324 0.0053915196 0.0275850000 235490014 95654128 760807424 -0.0977353528 -0.3428961933 -0.1034027785 1159 1311867209.0906980038 0.0426841266 0.0570823467 0.0680062324 0.0053947259 0.0237530000 235491942 95654128 760807424 -0.0970129222 -0.3404995799 -0.1044986695 1160 1311867209.1260778904 0.0420811921 0.0570694147 0.0680062324 0.0053936652 0.0237930000 235495414 95654128 760807424 -0.0973630324 -0.3416620195 -0.1056115255 1161 1311867209.1600620747 0.0429918133 0.0570572893 0.0680062324 0.0053946415 0.0237920000 235497398 95654128 760807424 -0.0990411490 -0.3451162577 -0.1057249084 1162 1311867209.1917839050 0.0424458794 0.0570447149 0.0680062324 0.0053941449 0.0385290000 235500870 95654128 760807424 -0.0987060219 -0.3421885073 -0.1070891172 1163 1311867209.2259531021 0.0422649384 0.0570320066 0.0680062324 0.0053924403 0.0246300000 235504542 95654128 760807424 -0.0982084200 -0.3444699943 -0.1070721000 1164 1311867209.2580060959 0.0423113108 0.0570193600 0.0680062324 0.0053912915 0.0237600000 235506270 95654128 760807424 -0.0989367515 -0.3450828493 -0.1076912954 1165 1311867209.2903130054 0.0428982638 0.0570072389 0.0680062324 0.0053896033 0.0238350000 235679346 95654128 760807424 -0.1005005091 -0.3451075554 -0.1082880944 1166 1311867209.3274219036 0.0429878347 0.0569952154 0.0680062324 0.0053907461 0.0240990000 235682930 95654128 760807424 -0.1012595594 -0.3463604152 -0.1089087129 1167 1311867209.3581039906 0.0429283120 0.0569831615 0.0680062324 0.0053889781 0.0294030000 235684746 95654128 760807424 -0.1018064395 -0.3504772186 -0.1090780273 1168 1311867209.3937969208 0.0426525921 0.0569708921 0.0680062324 0.0053918746 0.0238290000 235688330 95654128 760807424 -0.1014866605 -0.3467595279 -0.1102184653 1169 1311867209.4258151054 0.0419199467 0.0569580171 0.0680062324 0.0053938227 0.0272920000 235690258 95654128 760807424 -0.1008753404 -0.3520894051 -0.1098251343 1170 1311867209.4581329823 0.0419559292 0.0569451948 0.0680062324 0.0053918355 0.0237610000 235693674 95654128 760807424 -0.1024058536 -0.3539920449 -0.1105679497 1171 1311867209.4940650463 0.0417802855 0.0569322444 0.0680062324 0.0053916587 0.0237250000 235697514 95654128 760807424 -0.1033126414 -0.3540189862 -0.1111730039 1172 1311867209.5258729458 0.0410269201 0.0569186733 0.0680062324 0.0053904013 0.0270580000 235699130 95654128 760807424 -0.1034513488 -0.3559527695 -0.1116323024 1173 1311867209.5580699444 0.0416168161 0.0569056282 0.0680062324 0.0053885966 0.0237240000 235702802 95654128 760807424 -0.1045517400 -0.3551986217 -0.1114157513 1174 1311867209.5939540863 0.0422772020 0.0568931679 0.0680062324 0.0053865184 0.0237680000 235704586 95654128 760807424 -0.1066502854 -0.3587558568 -0.1109998226 1175 1311867209.6262791157 0.0422987081 0.0568807471 0.0680062324 0.0053843078 0.0341580000 235708202 95654128 760807424 -0.1083626971 -0.3590641618 -0.1118247733 1176 1311867209.6582019329 0.0420120843 0.0568681037 0.0680062324 0.0053831865 0.0240580000 235881250 95654128 760807424 -0.1087344065 -0.3599638641 -0.1123173460 1177 1311867209.6967020035 0.0407189727 0.0568543831 0.0680062324 0.0053954903 0.0236970000 235883234 95654128 760807424 -0.1058946028 -0.3647538424 -0.1115893573 1178 1311867209.7262639999 0.0413556397 0.0568412262 0.0680062324 0.0054086562 0.0237000000 235886650 95654128 760807424 -0.1077227741 -0.3642799854 -0.1124364436 1179 1311867209.7583460808 0.0408033431 0.0568276233 0.0680062324 0.0054094225 0.0236930000 235888578 95654128 760807424 -0.1071734652 -0.3654783964 -0.1131116524 1180 1311867209.7959320545 0.0414432734 0.0568145857 0.0680062324 0.0054078792 0.0236160000 235892218 95654128 760807424 -0.1082283407 -0.3698423505 -0.1132589132 1181 1311867209.8262419701 0.0409620553 0.0568011627 0.0680062324 0.0054066332 0.0236300000 235895834 95654128 760807424 -0.1086442620 -0.3693925440 -0.1147091314 1182 1311867209.8588960171 0.0417722985 0.0567884480 0.0680062324 0.0054076143 0.0274790000 235897506 95654128 760807424 -0.1111786291 -0.3690801859 -0.1159422547 1183 1311867209.8946969509 0.0418992043 0.0567758620 0.0680062324 0.0054080394 0.0274700000 235901290 95654128 760807424 -0.1112398133 -0.3717052639 -0.1161428541 1184 1311867209.9268450737 0.0417584069 0.0567631783 0.0680062324 0.0054084760 0.0235870000 235904706 95654128 760807424 -0.1112323180 -0.3701146245 -0.1170482635 1185 1311867209.9588210583 0.0415626839 0.0567503509 0.0680062324 0.0054065954 0.0236460000 236075946 95654128 760807424 -0.1109593809 -0.3694011569 -0.1176477820 1186 1311867209.9942541122 0.0414282829 0.0567374318 0.0680062324 0.0054105781 0.0236130000 236079530 95654128 760807424 -0.1109126881 -0.3735713959 -0.1175489575 1187 1311867210.0261061192 0.0412035324 0.0567243451 0.0680062324 0.0054094006 0.0237220000 236081346 95654128 760807424 -0.1114550009 -0.3740375936 -0.1184529811 1188 1311867210.0603590012 0.0415423512 0.0567115656 0.0680062324 0.0054082141 0.0236330000 236084986 95654128 760807424 -0.1129927337 -0.3732928336 -0.1195976213 1189 1311867210.0942480564 0.0413417555 0.0566986389 0.0680062324 0.0054063811 0.0275320000 236088658 95654128 760807424 -0.1116701588 -0.3755346537 -0.1192279011 1190 1311867210.1280341148 0.0410479866 0.0566854871 0.0680062324 0.0054047939 0.0235810000 236090386 95654128 760807424 -0.1110623106 -0.3777639270 -0.1194882318 1191 1311867210.1578240395 0.0406034999 0.0566719842 0.0680062324 0.0054072745 0.0235930000 236094002 95654128 760807424 -0.1096354499 -0.3747793138 -0.1200115383 1192 1311867210.1943209171 0.0423752517 0.0566599903 0.0680062324 0.0054059759 0.0238110000 236095842 95654128 760807424 -0.1139452979 -0.3764541745 -0.1210455373 1193 1311867210.2258129120 0.0402768888 0.0566462576 0.0680062324 0.0054098293 0.0238450000 236099458 95654128 760807424 -0.1098530963 -0.3806037605 -0.1211515665 1194 1311867210.2579770088 0.0401634909 0.0566324529 0.0680062324 0.0054106412 0.0275170000 236102930 95654128 760807424 -0.1099775136 -0.3792841434 -0.1220120788 1195 1311867210.2953989506 0.0410482064 0.0566194117 0.0680062324 0.0054088254 0.0236570000 236104970 95654128 760807424 -0.1114296019 -0.3780721128 -0.1224984825 1196 1311867210.3271369934 0.0408695675 0.0566062430 0.0680062324 0.0054099141 0.0236280000 236108386 95654128 760807424 -0.1115617529 -0.3778927028 -0.1228420138 1197 1311867210.3582420349 0.0410681479 0.0565932621 0.0680062324 0.0054155624 0.0236370000 236110258 95654128 760807424 -0.1120196208 -0.3779547811 -0.1233738437 1198 1311867210.3937919140 0.0406851284 0.0565799832 0.0680062324 0.0054138972 0.0236590000 236113842 95654128 760807424 -0.1103166565 -0.3771857023 -0.1232988909 1199 1311867210.4260039330 0.0423240326 0.0565680933 0.0680062324 0.0054159147 0.0236550000 236117458 95654128 760807424 -0.1155631766 -0.3797284961 -0.1242331117 1200 1311867210.4581708908 0.0401225165 0.0565543887 0.0680062324 0.0054169619 0.0237190000 236119186 95654128 760807424 -0.1116307080 -0.3828714788 -0.1241151914 1201 1311867210.4943509102 0.0405521244 0.0565410646 0.0680062324 0.0054472330 0.0269350000 236122914 95654128 760807424 -0.1112482548 -0.3775505424 -0.1246880442 1202 1311867210.5261299610 0.0403227322 0.0565275718 0.0680062324 0.0054550985 0.0276460000 236126386 95654128 760807424 -0.1126497090 -0.3815229237 -0.1254021376 1203 1311867210.5634729862 0.0407831408 0.0565144841 0.0680062324 0.0054558911 0.0237540000 236128426 95654128 760807424 -0.1131959856 -0.3812330961 -0.1255293787 1204 1311867210.5943870544 0.0404182114 0.0565011151 0.0680062324 0.0054546150 0.0236000000 236131898 95654128 760807424 -0.1146305129 -0.3799467385 -0.1272727102 1205 1311867210.6260209084 0.0415635407 0.0564887188 0.0680062324 0.0054645487 0.0277390000 236133658 95654128 760807424 -0.1152749658 -0.3802481592 -0.1267317235 1206 1311867210.6675710678 0.0403724723 0.0564753554 0.0680062324 0.0054740458 0.0238000000 236137466 95654128 760807424 -0.1129802093 -0.3833696246 -0.1268387139 1207 1311867210.6952280998 0.0404791981 0.0564621026 0.0680062324 0.0054812948 0.0236380000 236141082 95654128 760807424 -0.1131397784 -0.3829269111 -0.1277512610 1208 1311867210.7260899544 0.0408789255 0.0564492026 0.0680062324 0.0054793884 0.0238080000 236142586 95654128 760807424 -0.1136766151 -0.3825477660 -0.1279464364 1209 1311867210.7620921135 0.0401384123 0.0564357115 0.0680062324 0.0054804941 0.0275350000 236146426 95654128 760807424 -0.1123556793 -0.3840777576 -0.1281901598 1210 1311867210.7943489552 0.0402048901 0.0564222976 0.0680062324 0.0054886595 0.0235930000 236147874 95654128 760807424 -0.1134270132 -0.3829943538 -0.1289193928 1211 1311867210.8263258934 0.0400521606 0.0564087797 0.0680062324 0.0054873281 0.0236800000 236151546 95654128 760807424 -0.1124248281 -0.3802230060 -0.1289202422 1212 1311867210.8623979092 0.0404817387 0.0563956386 0.0680062324 0.0054862336 0.0274760000 236155130 95654128 760807424 -0.1137971804 -0.3837724626 -0.1287937611 1213 1311867210.8942279816 0.0397994518 0.0563819567 0.0680062324 0.0054854951 0.0237280000 236157058 95654128 760807424 -0.1120418608 -0.3786854148 -0.1292846501 1214 1311867210.9288311005 0.0402976014 0.0563687076 0.0680062324 0.0054834313 0.0238100000 236160586 95654128 760807424 -0.1129796803 -0.3793985844 -0.1290178895 1215 1311867210.9653480053 0.0391138531 0.0563545061 0.0680062324 0.0055019749 0.0236890000 236162570 95654128 760807424 -0.1105464771 -0.3753849566 -0.1292643398 1216 1311867210.9945580959 0.0406215265 0.0563415678 0.0680062324 0.0055156933 0.0236580000 236165986 95654128 760807424 -0.1133404076 -0.3759312928 -0.1288541108 1217 1311867211.0263500214 0.0410032794 0.0563289644 0.0680062324 0.0055164332 0.0280450000 236169658 95654128 760807424 -0.1144318730 -0.3804560602 -0.1281955093 1218 1311867211.0651569366 0.0401063785 0.0563156454 0.0680062324 0.0055339633 0.0238150000 236171498 95654128 760807424 -0.1123739928 -0.3756061494 -0.1286254972 1219 1311867211.0940821171 0.0414329171 0.0563034364 0.0680062324 0.0055395739 0.0238000000 236175058 95654128 760807424 -0.1146557629 -0.3761395514 -0.1285654306 1220 1311867211.1266880035 0.0414490402 0.0562912607 0.0680062324 0.0055422287 0.0238750000 236178530 95654128 760807424 -0.1148253009 -0.3806893826 -0.1281569153 1221 1311867211.1646990776 0.0414123088 0.0562790748 0.0680062324 0.0055415730 0.0236990000 236180626 95654128 760807424 -0.1153648645 -0.3811478913 -0.1288919151 1222 1311867211.1946630478 0.0407702737 0.0562663835 0.0680062324 0.0055405381 0.0238000000 236184042 95654128 760807424 -0.1141422987 -0.3769688606 -0.1296844631 1223 1311867211.2270209789 0.0405042507 0.0562534954 0.0680062324 0.0055515625 0.0237550000 236185914 95654128 760807424 -0.1134573966 -0.3781282008 -0.1292619556 1224 1311867211.2645599842 0.0401845835 0.0562403672 0.0680062324 0.0055504281 0.0237500000 236189554 95654128 760807424 -0.1138658449 -0.3781892955 -0.1299325824 1225 1311867211.2953100204 0.0393904969 0.0562266122 0.0680062324 0.0055484530 0.0282770000 236193226 95654128 760807424 -0.1123503149 -0.3772016168 -0.1301111579 1226 1311867211.3262948990 0.0402439684 0.0562135758 0.0680062324 0.0055472116 0.0237760000 236194842 95654128 760807424 -0.1123334020 -0.3767816126 -0.1292866319 1227 1311867211.3653290272 0.0399281457 0.0562003032 0.0680062324 0.0055452920 0.0238400000 236198738 95654128 760807424 -0.1124550924 -0.3766946197 -0.1297184080 1228 1311867211.3949019909 0.0400099903 0.0561871189 0.0680062324 0.0055453403 0.0238870000 236200354 95654128 760807424 -0.1137437820 -0.3757654428 -0.1304526180 1229 1311867211.4295680523 0.0405688547 0.0561744108 0.0680062324 0.0055503851 0.0238480000 236204026 95654128 760807424 -0.1138594449 -0.3737389743 -0.1300932020 1230 1311867211.4645059109 0.0411483869 0.0561621945 0.0680062324 0.0055509005 0.0237590000 236207554 95654128 760807424 -0.1144753322 -0.3748809695 -0.1294437349 1231 1311867211.4942829609 0.0403463431 0.0561493466 0.0680062324 0.0055495857 0.0246970000 236209370 95654128 760807424 -0.1133162305 -0.3727921844 -0.1298626661 1232 1311867211.5279569626 0.0397603996 0.0561360438 0.0680062324 0.0055484605 0.0277130000 236212842 95654128 760807424 -0.1131828204 -0.3711444139 -0.1298576593 1233 1311867211.5646700859 0.0405634381 0.0561234140 0.0680062324 0.0055490852 0.0238750000 236214882 95654128 760807424 -0.1125194132 -0.3736357987 -0.1292446107 1234 1311867211.5967590809 0.0407872498 0.0561109860 0.0680062324 0.0055517323 0.0276520000 236218354 95654128 760807424 -0.1129848287 -0.3721446097 -0.1291531026 1235 1311867211.6269431114 0.0411087163 0.0560988384 0.0680062324 0.0055600906 0.0238930000 236392654 95654128 760807424 -0.1131357774 -0.3713367879 -0.1291275471 1236 1311867211.6620280743 0.0388537236 0.0560848860 0.0680062324 0.0055748779 0.0238660000 236394438 95654128 760807424 -0.1106344461 -0.3727156818 -0.1292675734 1237 1311867211.6944348812 0.0398832671 0.0560717885 0.0680062324 0.0055811431 0.0240280000 236398110 95654128 760807424 -0.1112397835 -0.3744257390 -0.1286903024 1238 1311867211.7267570496 0.0399077572 0.0560587320 0.0680062324 0.0055828668 0.0278580000 236401526 95654128 760807424 -0.1114928201 -0.3727253377 -0.1291049570 1239 1311867211.7642099857 0.0408883244 0.0560464879 0.0680062324 0.0055813750 0.0242260000 236403622 95654128 760807424 -0.1125095934 -0.3710629344 -0.1296352893 1240 1311867211.7948160172 0.0408660658 0.0560342456 0.0680062324 0.0055818268 0.0241140000 236406926 95654128 760807424 -0.1120857820 -0.3700736165 -0.1301999092 1241 1311867211.8337268829 0.0411325581 0.0560222378 0.0680062324 0.0055819006 0.0241140000 236408966 95654128 760807424 -0.1116681769 -0.3714940846 -0.1303322762 1242 1311867211.8630928993 0.0410326682 0.0560101689 0.0680062324 0.0055808337 0.0241320000 236412382 95654128 760807424 -0.1116068736 -0.3701871634 -0.1310627013 1243 1311867211.8967690468 0.0400748216 0.0559973488 0.0680062324 0.0055794545 0.0240730000 236416054 95654128 760807424 -0.1105842665 -0.3668321073 -0.1321626306 1244 1311867211.9324300289 0.0403857157 0.0559847993 0.0680062324 0.0055828237 0.0247500000 236417838 95654128 760807424 -0.1100371778 -0.3676885664 -0.1319931895 1245 1311867211.9653239250 0.0403859653 0.0559722701 0.0680062324 0.0055814637 0.0237600000 236421566 95654128 760807424 -0.1110015884 -0.3668640256 -0.1333525032 1246 1311867211.9972860813 0.0389110669 0.0559585773 0.0680062324 0.0055809338 0.0238190000 236423182 95654128 760807424 -0.1069935560 -0.3637968600 -0.1335024238 1247 1311867212.0317659378 0.0408452116 0.0559464576 0.0680062324 0.0055818980 0.0277650000 236426966 95654128 760807424 -0.1103475988 -0.3596581817 -0.1344817132 1248 1311867212.0621519089 0.0388671234 0.0559327722 0.0680062324 0.0055831783 0.0239300000 236430382 95654128 760807424 -0.1066182703 -0.3626029193 -0.1343122721 1249 1311867212.0954549313 0.0395244323 0.0559196350 0.0680062324 0.0055851044 0.0238160000 236432254 95654128 760807424 -0.1077808663 -0.3623698056 -0.1345890164 1250 1311867212.1331028938 0.0399059281 0.0559068240 0.0680062324 0.0055841970 0.0277120000 236435894 95654128 760807424 -0.1070706099 -0.3576126695 -0.1343425810 1251 1311867212.1668488979 0.0403435230 0.0558943834 0.0680062324 0.0055841979 0.0239110000 236437766 95654128 760807424 -0.1073045582 -0.3565516472 -0.1345106959 1252 1311867212.1945068836 0.0405966863 0.0558821647 0.0680062324 0.0055823959 0.0276380000 236441126 95654128 760807424 -0.1078020558 -0.3570417762 -0.1349719763 1253 1311867212.2301759720 0.0401278399 0.0558695915 0.0680062324 0.0055838512 0.0241740000 236444854 95654128 760807424 -0.1063392907 -0.3533374965 -0.1361342967 1254 1311867212.2647190094 0.0410160311 0.0558577465 0.0680062324 0.0055851673 0.0270460000 236446638 95654128 760807424 -0.1064000651 -0.3543503582 -0.1361169815 1255 1311867212.2944819927 0.0404899232 0.0558455012 0.0680062324 0.0055836810 0.0277150000 236450254 95654128 760807424 -0.1067102253 -0.3533643484 -0.1380007863 1256 1311867212.3326430321 0.0404445790 0.0558332394 0.0680062324 0.0055857812 0.0238450000 236453894 95654128 760807424 -0.1066831499 -0.3511797786 -0.1391529590 1257 1311867212.3653640747 0.0405770428 0.0558211024 0.0680062324 0.0055838533 0.0240070000 236455766 95654128 760807424 -0.1059744954 -0.3466484249 -0.1399511099 1258 1311867212.3955509663 0.0409677178 0.0558092952 0.0680062324 0.0055957268 0.0238860000 236459182 95654128 760807424 -0.1045138463 -0.3471779227 -0.1397877932 1259 1311867212.4329519272 0.0405161269 0.0557971481 0.0680062324 0.0056125482 0.0238890000 236461222 95654128 760807424 -0.1048291549 -0.3452051580 -0.1404918730 1260 1311867212.4622640610 0.0401698686 0.0557847455 0.0680062324 0.0056181206 0.0340140000 236464638 95654128 760807424 -0.1036325768 -0.3434895575 -0.1410440356 1261 1311867212.4944300652 0.0406583399 0.0557727500 0.0680062324 0.0056216878 0.0241690000 236468310 95654128 760807424 -0.1029461548 -0.3398338854 -0.1414846927 1262 1311867212.5300269127 0.0402470306 0.0557604475 0.0680062324 0.0056258356 0.0239490000 236470094 95654128 760807424 -0.1028508916 -0.3430892825 -0.1422714442 1263 1311867212.5625970364 0.0407424942 0.0557485568 0.0680062324 0.0056382865 0.0239330000 236473766 95654128 760807424 -0.1024056152 -0.3402630091 -0.1435564905 1264 1311867212.5948359966 0.0409413427 0.0557368422 0.0680062324 0.0056363705 0.0238640000 236475438 95654128 760807424 -0.1013488770 -0.3376636505 -0.1443004012 1265 1311867212.6323919296 0.0403158776 0.0557246518 0.0680062324 0.0056393009 0.0238640000 236479166 95654128 760807424 -0.0996277630 -0.3373612761 -0.1454884857 1266 1311867212.6629829407 0.0405999087 0.0557127049 0.0680062324 0.0056421818 0.0238330000 236482582 95654128 760807424 -0.1000648662 -0.3386255503 -0.1462844759 1267 1311867212.6944150925 0.0408748724 0.0557009939 0.0680062324 0.0056426234 0.0239660000 236484510 95654128 760807424 -0.0990896896 -0.3350286186 -0.1471547186 1268 1311867212.7323219776 0.0409448147 0.0556893565 0.0680062324 0.0056409280 0.0327690000 236488094 95654128 760807424 -0.0968542472 -0.3337503672 -0.1470491588 1269 1311867212.7618949413 0.0406518951 0.0556775067 0.0680062324 0.0056391220 0.0248220000 236489854 95654128 760807424 -0.0972511843 -0.3334464431 -0.1482086778 1270 1311867212.7951610088 0.0405203030 0.0556655719 0.0680062324 0.0056371587 0.0276590000 236493382 95654128 760807424 -0.0967575982 -0.3313501477 -0.1490937471 1271 1311867212.8303771019 0.0409323908 0.0556539801 0.0680062324 0.0056354377 0.0239750000 236497222 95654128 760807424 -0.0972535610 -0.3302350938 -0.1501424015 1272 1311867212.8625240326 0.0413957424 0.0556427708 0.0680062324 0.0056353304 0.0240630000 236498838 95654128 760807424 -0.0969683155 -0.3292610943 -0.1508682966 1273 1311867212.8941800594 0.0412810780 0.0556314890 0.0680062324 0.0056428407 0.0238680000 236502510 95654128 760807424 -0.0968254805 -0.3284133673 -0.1518474072 1274 1311867212.9306590557 0.0388234146 0.0556182958 0.0680062324 0.0056522899 0.0238260000 236506094 95654128 760807424 -0.0932515487 -0.3250771761 -0.1536658704 1275 1311867212.9621579647 0.0411852710 0.0556069758 0.0680062324 0.0056678657 0.0239620000 236507966 95654128 760807424 -0.0963960588 -0.3256593049 -0.1537372917 1276 1311867212.9971981049 0.0405835733 0.0555952020 0.0680062324 0.0056706213 0.0275480000 236511494 95654128 760807424 -0.0937200785 -0.3243679702 -0.1541464627 1277 1311867213.0305559635 0.0402705073 0.0555832014 0.0680062324 0.0056741079 0.0239970000 236513478 95654128 760807424 -0.0923882872 -0.3220648468 -0.1545777917 1278 1311867213.0622329712 0.0402092002 0.0555711717 0.0680062324 0.0056728848 0.0239580000 236516894 95654128 760807424 -0.0921953619 -0.3221653104 -0.1551464945 1279 1311867213.0985310078 0.0405905433 0.0555594589 0.0680062324 0.0056716396 0.0272350000 236520678 95654128 760807424 -0.0915453508 -0.3219265640 -0.1551079303 1280 1311867213.1321671009 0.0407045372 0.0555478535 0.0680062324 0.0056707670 0.0277650000 236522406 95654128 760807424 -0.0909264013 -0.3218377531 -0.1559882909 1281 1311867213.1642329693 0.0406517126 0.0555362250 0.0680062324 0.0056693291 0.0239320000 236526078 95654128 760807424 -0.0892132819 -0.3176161051 -0.1569769233 1282 1311867213.1981649399 0.0408858992 0.0555247973 0.0680062324 0.0056698039 0.0248160000 236527806 95654128 760807424 -0.0884411484 -0.3169841766 -0.1573238969 1283 1311867213.2303979397 0.0412645228 0.0555136825 0.0680062324 0.0056693206 0.0238090000 236531478 95654128 760807424 -0.0885552093 -0.3163911104 -0.1581930071 1284 1311867213.2621340752 0.0406122617 0.0555020770 0.0680062324 0.0056698263 0.0334610000 236704770 95654128 760807424 -0.0850306898 -0.3130961955 -0.1590177566 1285 1311867213.2983639240 0.0407731794 0.0554906149 0.0680062324 0.0056715502 0.0241900000 236706754 95654128 760807424 -0.0852523372 -0.3149777055 -0.1594887376 1286 1311867213.3312969208 0.0402885191 0.0554787936 0.0680062324 0.0056749786 0.0238990000 236710282 95654128 760807424 -0.0841937959 -0.3129529059 -0.1602303237 1287 1311867213.3622069359 0.0405817777 0.0554672186 0.0680062324 0.0056735306 0.0239610000 236712098 95654128 760807424 -0.0831961110 -0.3076475561 -0.1608100235 1288 1311867213.3980619907 0.0408766642 0.0554558906 0.0680062324 0.0056716560 0.0238610000 236715682 95654128 760807424 -0.0838186741 -0.3084765971 -0.1610614210 1289 1311867213.4303960800 0.0407609567 0.0554444903 0.0680062324 0.0056714763 0.0238920000 236719410 95654128 760807424 -0.0829098374 -0.3069458008 -0.1615003496 1290 1311867213.4620630741 0.0402790084 0.0554327341 0.0680062324 0.0056694310 0.0238690000 236721026 95654128 760807424 -0.0838646218 -0.3052957356 -0.1632342786 1291 1311867213.4981389046 0.0401139706 0.0554208683 0.0680062324 0.0056709266 0.0240760000 236724810 95654128 760807424 -0.0815179870 -0.3034908175 -0.1622683555 1292 1311867213.5318338871 0.0405607820 0.0554093667 0.0680062324 0.0056722776 0.0300120000 236728338 95654128 760807424 -0.0815043673 -0.2994142175 -0.1623462439 1293 1311867213.5621318817 0.0409110561 0.0553981538 0.0680062324 0.0056703072 0.0240760000 236730154 95654128 760807424 -0.0811638981 -0.2988835573 -0.1617277414 1294 1311867213.5989580154 0.0409516431 0.0553869896 0.0680062324 0.0056730780 0.0240080000 236733794 95654128 760807424 -0.0794182494 -0.2942633331 -0.1617575139 1295 1311867213.6327760220 0.0403001904 0.0553753395 0.0680062324 0.0056721573 0.0239760000 236735666 95654128 760807424 -0.0790803656 -0.2945422828 -0.1619712561 1296 1311867213.6623249054 0.0408590026 0.0553641386 0.0680062324 0.0056733947 0.0240620000 236908434 95654128 760807424 -0.0772454068 -0.2909106612 -0.1613779962 1297 1311867213.6987268925 0.0412421376 0.0553532504 0.0680062324 0.0056732150 0.0240550000 236912218 95654128 760807424 -0.0765259787 -0.2875556648 -0.1612682045 1298 1311867213.7312800884 0.0423954427 0.0553432675 0.0680062324 0.0056770101 0.0240000000 236913946 95654128 760807424 -0.0767110363 -0.2865202129 -0.1603645831 1299 1311867213.7623159885 0.0419773906 0.0553329782 0.0680062324 0.0056844747 0.0240280000 236917562 95654128 760807424 -0.0772403479 -0.2831465304 -0.1611404270 1300 1311867213.7984969616 0.0420209803 0.0553227382 0.0680062324 0.0056828274 0.0275660000 236919234 95654128 760807424 -0.0759140924 -0.2801783085 -0.1609282047 1301 1311867213.8303530216 0.0420987755 0.0553125737 0.0680062324 0.0056808657 0.0242020000 236922906 95654128 760807424 -0.0729902014 -0.2794870138 -0.1593011618 1302 1311867213.8669381142 0.0422267579 0.0553025232 0.0680062324 0.0056876648 0.0241560000 237096718 95654128 760807424 -0.0730569437 -0.2805806994 -0.1586804837 1303 1311867213.8988749981 0.0421280414 0.0552924123 0.0680062324 0.0056858533 0.0241230000 237098590 95654128 760807424 -0.0731483325 -0.2803428173 -0.1591036618 1304 1311867213.9324591160 0.0425784215 0.0552826623 0.0680062324 0.0056907836 0.0241330000 237102062 95654128 760807424 -0.0721579567 -0.2749038935 -0.1594736129 1305 1311867213.9625511169 0.0431636274 0.0552733757 0.0680062324 0.0056886735 0.0281070000 237103878 95654128 760807424 -0.0717003345 -0.2746834755 -0.1590656787 1306 1311867214.0014989376 0.0431449674 0.0552640890 0.0680062324 0.0056872259 0.0242580000 237107630 95654128 760807424 -0.0714807212 -0.2741643488 -0.1600235701 1307 1311867214.0316550732 0.0418987162 0.0552538630 0.0680062324 0.0056881609 0.0275220000 237111190 95654128 760807424 -0.0689622015 -0.2730733454 -0.1602624655 1308 1311867214.0640029907 0.0421404652 0.0552438375 0.0680062324 0.0056868771 0.0247240000 237112918 95654128 760807424 -0.0665415451 -0.2687531412 -0.1605118811 1309 1311867214.0984749794 0.0426401570 0.0552342090 0.0680062324 0.0056849886 0.0241660000 237116646 95654128 760807424 -0.0676218942 -0.2672095895 -0.1611406505 1310 1311867214.1326990128 0.0426956639 0.0552246376 0.0680062324 0.0056837012 0.0241720000 237120118 95654128 760807424 -0.0663816333 -0.2669965625 -0.1607969850 1311 1311867214.1643800735 0.0431653410 0.0552154390 0.0680062324 0.0056870539 0.0281390000 237122046 95654128 760807424 -0.0664899349 -0.2638719082 -0.1611497849 1312 1311867214.2013020515 0.0426038839 0.0552058266 0.0680062324 0.0056869929 0.0241970000 237125574 95654128 760807424 -0.0666948557 -0.2645481527 -0.1616215855 1313 1311867214.2338430882 0.0421725065 0.0551959002 0.0680062324 0.0056851203 0.0275360000 237127502 95654128 760807424 -0.0638452321 -0.2640032172 -0.1611091495 1314 1311867214.2674899101 0.0427624248 0.0551864379 0.0680062324 0.0056839424 0.0282680000 237300998 95654128 760807424 -0.0631872937 -0.2607194781 -0.1610327661 1315 1311867214.3004720211 0.0428439900 0.0551770520 0.0680062324 0.0056818629 0.0243870000 237304670 95654128 760807424 -0.0647672191 -0.2610848546 -0.1610003263 1316 1311867214.3310549259 0.0434728935 0.0551681583 0.0680062324 0.0056803157 0.0278580000 237306286 95654128 760807424 -0.0655602887 -0.2564285696 -0.1619974971 1317 1311867214.3663671017 0.0424715839 0.0551585177 0.0680062324 0.0056792639 0.0243990000 237310070 95654128 760807424 -0.0649713874 -0.2578556538 -0.1626216471 1318 1311867214.3980031013 0.0434345677 0.0551496225 0.0680062324 0.0056774545 0.0242810000 237311742 95654128 760807424 -0.0648046061 -0.2568794489 -0.1623398811 1319 1311867214.4332211018 0.0437956750 0.0551410145 0.0680062324 0.0056762680 0.0243810000 237315470 95654128 760807424 -0.0646549761 -0.2531948686 -0.1633572280 1320 1311867214.4698181152 0.0426637679 0.0551315620 0.0680062324 0.0056777428 0.0243130000 237319222 95654128 760807424 -0.0618426763 -0.2507685125 -0.1645645648 1321 1311867214.5059390068 0.0442934781 0.0551233576 0.0680062324 0.0056804867 0.0247960000 237321206 95654128 760807424 -0.0622130334 -0.2461826205 -0.1648608744 1322 1311867214.5373690128 0.0441060252 0.0551150237 0.0680062324 0.0056784322 0.0243470000 237324678 95654136 760807424 -0.0615812093 -0.2456907034 -0.1650702655 1323 1311867214.5691421032 0.0440593362 0.0551066672 0.0680062324 0.0056763670 0.0242980000 237326550 95654136 760807424 -0.0616834722 -0.2454841137 -0.1648967117 1324 1311867214.6048638821 0.0447234213 0.0550988249 0.0680062324 0.0056747534 0.0414960000 237330134 95654136 760807424 -0.0625853688 -0.2446831763 -0.1645715833 1325 1311867214.6369891167 0.0446793549 0.0550909611 0.0680062324 0.0056733116 0.0253100000 237333750 95654136 760807424 -0.0621013492 -0.2437534481 -0.1646547914 1326 1311867214.6691009998 0.0447896160 0.0550831924 0.0680062324 0.0056716051 0.0242380000 237335478 95654136 760807424 -0.0610538647 -0.2395432442 -0.1655357778 1327 1311867214.7048900127 0.0450048484 0.0550755975 0.0680062324 0.0056713965 0.0242720000 237339206 95654136 760807424 -0.0597640686 -0.2397135645 -0.1653394997 1328 1311867214.7369639874 0.0449564643 0.0550679777 0.0680062324 0.0056753336 0.0297800000 237342678 95654136 760807424 -0.0586367846 -0.2389726788 -0.1651990414 1329 1311867214.7695059776 0.0452951789 0.0550606242 0.0680062324 0.0056749351 0.0243140000 237344606 95654136 760807424 -0.0572192855 -0.2349633276 -0.1655341834 1330 1311867214.8049929142 0.0453553386 0.0550533270 0.0680062324 0.0056731100 0.0244370000 237348190 95654136 760807424 -0.0581902154 -0.2346988171 -0.1661920547 1331 1311867214.8369181156 0.0448003598 0.0550456238 0.0680062324 0.0056737383 0.0243550000 237350006 95654136 760807424 -0.0578160472 -0.2337317020 -0.1669858545 1332 1311867214.8699979782 0.0461857468 0.0550389722 0.0680062324 0.0056731570 0.0243120000 237353534 95654136 760807424 -0.0570726246 -0.2276564389 -0.1675565243 1333 1311867214.9049839973 0.0452491231 0.0550316280 0.0680062324 0.0056716907 0.0243650000 237526842 95654136 760807424 -0.0559522323 -0.2290825546 -0.1673080623 1334 1311867214.9372529984 0.0454210751 0.0550244237 0.0680062324 0.0056698119 0.0242810000 237528514 95654136 760807424 -0.0559056997 -0.2279432416 -0.1677134782 1335 1311867214.9693040848 0.0447504260 0.0550167278 0.0680062324 0.0056678990 0.0279920000 237532186 95654136 760807424 -0.0540836826 -0.2230553180 -0.1694602370 1336 1311867215.0050640106 0.0457590260 0.0550097984 0.0680062324 0.0056659503 0.0264740000 237534026 95654136 760807424 -0.0536206998 -0.2199482024 -0.1685768813 1337 1311867215.0371069908 0.0453967974 0.0550026084 0.0680062324 0.0056648139 0.0243450000 237537586 95654136 760807424 -0.0540601276 -0.2206065804 -0.1682978570 1338 1311867215.0692911148 0.0456480682 0.0549956170 0.0680062324 0.0056634115 0.0242850000 237541114 95654136 760807424 -0.0528123267 -0.2157950699 -0.1687988639 1339 1311867215.1050040722 0.0451291874 0.0549882485 0.0680062324 0.0056614591 0.0243020000 237543098 95654136 760807424 -0.0536075681 -0.2139783800 -0.1690616608 1340 1311867215.1369140148 0.0453293547 0.0549810404 0.0680062324 0.0056597076 0.0243960000 237716610 95654136 760807424 -0.0520689487 -0.2144260705 -0.1669655293 1341 1311867215.1694459915 0.0462506339 0.0549745300 0.0680062324 0.0056604435 0.0243470000 237718594 95654136 760807424 -0.0530029908 -0.2124703526 -0.1664914042 1342 1311867215.2049460411 0.0454727821 0.0549674497 0.0680062324 0.0056594582 0.0244920000 237722122 95654136 760807424 -0.0517593138 -0.2092291564 -0.1669102758 1343 1311867215.2369511127 0.0464564599 0.0549611124 0.0680062324 0.0056576964 0.0253330000 237725738 95654136 760807424 -0.0534983762 -0.2101528943 -0.1654802859 1344 1311867215.2690820694 0.0467760973 0.0549550224 0.0680062324 0.0056559333 0.0355590000 237727466 95654136 760807424 -0.0536633804 -0.2069233656 -0.1656081378 1345 1311867215.3049569130 0.0474978909 0.0549494780 0.0680062324 0.0056543782 0.0247980000 237731250 95654136 760807424 -0.0524373166 -0.2038739771 -0.1654446572 1346 1311867215.3369619846 0.0472378358 0.0549437487 0.0680062324 0.0056535805 0.0336840000 237905278 95654136 760807424 -0.0517818369 -0.2034979910 -0.1654425263 1347 1311867215.3691840172 0.0457898602 0.0549369530 0.0680062324 0.0056551509 0.0247090000 237907150 95654136 760807424 -0.0479919016 -0.1993807256 -0.1669380516 1348 1311867215.4049520493 0.0469243564 0.0549310089 0.0680062324 0.0056537626 0.0243820000 237910734 95654136 760807424 -0.0480317250 -0.1967818439 -0.1665482074 1349 1311867215.4370350838 0.0473288260 0.0549253735 0.0680062324 0.0056531282 0.0243660000 237912550 95654136 760807424 -0.0466934666 -0.1961151212 -0.1660026461 1350 1311867215.4690899849 0.0476494022 0.0549199839 0.0680062324 0.0056539668 0.0243670000 237916078 95654136 760807424 -0.0471448265 -0.1946853250 -0.1664971411 1351 1311867215.5049800873 0.0489168949 0.0549155404 0.0680062324 0.0056544524 0.0243780000 237919862 95654136 760807424 -0.0479408726 -0.1900834143 -0.1672380716 1352 1311867215.5371229649 0.0490253232 0.0549111838 0.0680062324 0.0056527794 0.0244140000 237921478 95654136 760807424 -0.0489466637 -0.1899047196 -0.1669914722 1353 1311867215.5690340996 0.0484377071 0.0549063992 0.0680062324 0.0056522977 0.0278970000 237925206 95654136 760807424 -0.0464683659 -0.1898506135 -0.1668289602 1354 1311867215.6050848961 0.0478979684 0.0549012231 0.0680062324 0.0056503158 0.0348350000 237926990 95654136 760807424 -0.0443250909 -0.1854103059 -0.1684805006 1355 1311867215.6370549202 0.0489039198 0.0548967971 0.0680062324 0.0056487388 0.0246840000 237930662 95654136 760807424 -0.0474500023 -0.1844508499 -0.1674975157 1356 1311867215.6689219475 0.0486583486 0.0548921964 0.0680062324 0.0056477173 0.0244550000 237934134 95654136 760807424 -0.0456944443 -0.1854619682 -0.1659858674 1357 1311867215.7049510479 0.0488140807 0.0548877174 0.0680062324 0.0056464294 0.0245190000 237936118 95654136 760807424 -0.0437857769 -0.1822028905 -0.1661030948 1358 1311867215.7388830185 0.0492536277 0.0548835686 0.0680062324 0.0056446643 0.0244250000 237939646 95654136 760807424 -0.0435739085 -0.1789401174 -0.1662092507 1359 1311867215.7691988945 0.0493357070 0.0548794862 0.0680062324 0.0056435186 0.0247020000 238111218 95654136 760807424 -0.0452551022 -0.1796823144 -0.1657112688 1360 1311867215.8048830032 0.0487073325 0.0548749479 0.0680062324 0.0056445238 0.0245520000 238114802 95654136 760807424 -0.0437389091 -0.1790421605 -0.1656997055 1361 1311867215.8373351097 0.0488717034 0.0548705370 0.0680062324 0.0056429570 0.0280190000 238118474 95654136 760807424 -0.0435828380 -0.1761342138 -0.1666424125 1362 1311867215.8691670895 0.0493220761 0.0548664632 0.0680062324 0.0056411628 0.0351080000 238120202 95654136 760807424 -0.0430132672 -0.1753876954 -0.1665815711 1363 1311867215.9052760601 0.0500460938 0.0548629266 0.0680062324 0.0056421506 0.0248130000 238123986 95654136 760807424 -0.0439832844 -0.1724439859 -0.1677282006 1364 1311867215.9370880127 0.0501646921 0.0548594822 0.0680062324 0.0056401439 0.0245380000 238127402 95654136 760807424 -0.0429739319 -0.1699829102 -0.1687229127 1365 1311867215.9702870846 0.0509441309 0.0548566138 0.0680062324 0.0056383360 0.0245110000 238129330 95654136 760807424 -0.0446528643 -0.1686223745 -0.1689826846 1366 1311867216.0050790310 0.0508353449 0.0548536700 0.0680062324 0.0056374383 0.0245060000 238132914 95654136 760807424 -0.0454643033 -0.1698230058 -0.1688493639 1367 1311867216.0369679928 0.0502279289 0.0548502861 0.0680062324 0.0056354414 0.0246190000 238134730 95654136 760807424 -0.0456051305 -0.1699812114 -0.1695331037 1368 1311867216.0694830418 0.0503467359 0.0548469940 0.0680062324 0.0056348377 0.0245080000 238138258 95654136 760807424 -0.0448410213 -0.1671780348 -0.1701530516 1369 1311867216.1050429344 0.0511441454 0.0548442893 0.0680062324 0.0056338986 0.0281260000 238142042 95654136 760807424 -0.0424041264 -0.1635758430 -0.1694044024 1370 1311867216.1392951012 0.0506932288 0.0548412593 0.0680062324 0.0056323184 0.0340450000 238143770 95654136 760807424 -0.0420956574 -0.1643311083 -0.1686577648 1371 1311867216.1692190170 0.0499542058 0.0548376947 0.0680062324 0.0056305304 0.0248380000 238147386 95654136 760807424 -0.0371499322 -0.1611126512 -0.1688179523 1372 1311867216.2049610615 0.0507712811 0.0548347308 0.0680062324 0.0056287782 0.0284610000 238149170 95654136 760807424 -0.0391246900 -0.1597741395 -0.1676804572 1373 1311867216.2370231152 0.0504455492 0.0548315340 0.0680062324 0.0056278427 0.0246460000 238323614 95654136 760807424 -0.0391991660 -0.1603537351 -0.1664139181 1374 1311867216.2706630230 0.0507465750 0.0548285610 0.0680062324 0.0056267772 0.0245980000 238327198 95654136 760807424 -0.0392237753 -0.1567447186 -0.1664838046 1375 1311867216.3050479889 0.0496634990 0.0548248046 0.0680062324 0.0056252431 0.0246360000 238329126 95654136 760807424 -0.0374060571 -0.1557629257 -0.1660976857 1376 1311867216.3395419121 0.0498742536 0.0548212068 0.0680062324 0.0056241899 0.0246790000 238332710 95654136 760807424 -0.0370504670 -0.1531912684 -0.1653797030 1377 1311867216.3694689274 0.0502720326 0.0548179031 0.0680062324 0.0056226034 0.0279270000 238334470 95654136 760807424 -0.0354535431 -0.1501553804 -0.1648664027 1378 1311867216.4055120945 0.0502726138 0.0548146047 0.0680062324 0.0056206967 0.0354310000 238338110 95654136 760807424 -0.0356740393 -0.1503650099 -0.1633868068 1379 1311867216.4373409748 0.0505198315 0.0548114902 0.0680062324 0.0056188047 0.0250350000 238341670 95654136 760807424 -0.0361005701 -0.1477729082 -0.1634530872 1380 1311867216.4697530270 0.0497891232 0.0548078509 0.0680062324 0.0056175576 0.0246610000 238343454 95654136 760807424 -0.0350416154 -0.1468466073 -0.1631736308 1381 1311867216.5049800873 0.0498916395 0.0548042910 0.0680062324 0.0056162951 0.0247520000 238347182 95654136 760807424 -0.0346547514 -0.1455464214 -0.1626591235 1382 1311867216.5372259617 0.0513582341 0.0548017974 0.0680062324 0.0056163245 0.0248290000 238350654 95654136 760807424 -0.0364572033 -0.1427814662 -0.1623105109 1383 1311867216.5693330765 0.0515161306 0.0547994217 0.0680062324 0.0056143897 0.0248330000 238352526 95654136 760807424 -0.0366263539 -0.1414111108 -0.1621941179 1384 1311867216.6050319672 0.0510521308 0.0547967141 0.0680062324 0.0056132042 0.0248550000 238527446 95654136 760807424 -0.0355677791 -0.1428799480 -0.1612783223 1385 1311867216.6373488903 0.0514413752 0.0547942915 0.0680062324 0.0056118219 0.0248160000 238529318 95654136 760807424 -0.0356244259 -0.1411861926 -0.1614276320 1386 1311867216.6691188812 0.0514296405 0.0547918639 0.0680062324 0.0056102913 0.0248080000 238532790 95654136 760807424 -0.0346988291 -0.1408710778 -0.1613473594 1387 1311867216.7052359581 0.0517234355 0.0547896516 0.0680062324 0.0056100485 0.0248460000 238536574 95654136 760807424 -0.0322897993 -0.1372933388 -0.1614297330 1388 1311867216.7372078896 0.0514334068 0.0547872336 0.0680062324 0.0056080943 0.0247070000 238538190 95654136 760807424 -0.0322726294 -0.1369608641 -0.1616262347 1389 1311867216.7691950798 0.0513706058 0.0547847738 0.0680062324 0.0056064201 0.0249870000 238541918 95654136 760807424 -0.0314781778 -0.1370807439 -0.1612355709 1390 1311867216.8050019741 0.0517641865 0.0547826007 0.0680062324 0.0056050819 0.0287310000 238543702 95654136 760807424 -0.0319203883 -0.1367308348 -0.1612145901 1391 1311867216.8379631042 0.0517546535 0.0547804239 0.0680062324 0.0056032317 0.0287560000 238547374 95654136 760807424 -0.0318452902 -0.1376189888 -0.1605496854 1392 1311867216.8703401089 0.0520567037 0.0547784672 0.0680062324 0.0056018531 0.0248060000 238550846 95654136 760807424 -0.0340249389 -0.1367793083 -0.1608271003 1393 1311867216.9049589634 0.0517153479 0.0547762682 0.0680062324 0.0055999595 0.0249750000 238552830 95654136 760807424 -0.0333681703 -0.1371214241 -0.1607539058 1394 1311867216.9374070168 0.0518346205 0.0547741580 0.0680062324 0.0055981491 0.0247040000 238556246 95654136 760807424 -0.0315819941 -0.1371076405 -0.1604652107 1395 1311867216.9691729546 0.0513884425 0.0547717310 0.0680062324 0.0055966000 0.0368690000 238558118 95654136 760807424 -0.0307855997 -0.1364341974 -0.1604402512 1396 1311867217.0053269863 0.0520367511 0.0547697718 0.0680062324 0.0055966862 0.0251650000 238561758 95654136 760807424 -0.0296688508 -0.1319396496 -0.1608708650 1397 1311867217.0373110771 0.0519685894 0.0547677667 0.0680062324 0.0055948380 0.0248380000 238735138 95654136 760807424 -0.0292269308 -0.1330136806 -0.1601637602 1398 1311867217.0691289902 0.0525706522 0.0547661951 0.0680062324 0.0055948146 0.0280550000 238736810 95654136 760807424 -0.0302858930 -0.1310004890 -0.1609247327 1399 1311867217.1052579880 0.0527828224 0.0547647774 0.0680062324 0.0055933727 0.0247910000 238740650 95654136 760807424 -0.0303584170 -0.1283188909 -0.1616362929 1400 1311867217.1370849609 0.0527464673 0.0547633357 0.0680062324 0.0055936541 0.0249610000 238744066 95654136 760807424 -0.0298249442 -0.1296129525 -0.1608540565 1401 1311867217.1691889763 0.0532776862 0.0547622753 0.0680062324 0.0055928262 0.0248940000 238745994 95654136 760807424 -0.0289849360 -0.1271685064 -0.1611373127 1402 1311867217.2057919502 0.0537551492 0.0547615570 0.0680062324 0.0055909698 0.0248150000 238749578 95654136 760807424 -0.0291942339 -0.1262726188 -0.1609093100 1403 1311867217.2371680737 0.0528836884 0.0547602185 0.0680062324 0.0055899560 0.0361480000 238751450 95654136 760807424 -0.0283951350 -0.1270295829 -0.1609153152 1404 1311867217.2692279816 0.0532022975 0.0547591089 0.0680062324 0.0055886018 0.0254230000 238754922 95654136 760807424 -0.0283261854 -0.1257387400 -0.1610893607 1405 1311867217.3051640987 0.0534664430 0.0547581888 0.0680062324 0.0055868017 0.0248340000 238758706 95654136 760807424 -0.0282248054 -0.1235789061 -0.1613364220 1406 1311867217.3374049664 0.0536534786 0.0547574031 0.0680062324 0.0055848815 0.0248240000 238760378 95654136 760807424 -0.0298204161 -0.1218623072 -0.1615338773 1407 1311867217.3695969582 0.0520876758 0.0547555056 0.0680062324 0.0055837034 0.0248650000 238764050 95654136 760807424 -0.0288743619 -0.1209373027 -0.1623974591 1408 1311867217.4120450020 0.0520892665 0.0547536120 0.0680062324 0.0055820353 0.0249060000 238936926 95654136 760807424 -0.0249524601 -0.1195690110 -0.1613301188 1409 1311867217.4372820854 0.0522655435 0.0547518462 0.0680062324 0.0055801420 0.0249350000 238940374 95654136 760807424 -0.0265287813 -0.1198163629 -0.1610029638 1410 1311867217.4694299698 0.0531555340 0.0547507140 0.0680062324 0.0055797076 0.0249400000 238943902 95654136 760807424 -0.0282428730 -0.1164713800 -0.1615944654 1411 1311867217.5050430298 0.0527396649 0.0547492888 0.0680062324 0.0055779119 0.0354190000 238945886 95654136 760807424 -0.0283209905 -0.1165287122 -0.1615330875 1412 1311867217.5370678902 0.0526672564 0.0547478142 0.0680062324 0.0055759400 0.0252160000 238949302 95654136 760807424 -0.0275963321 -0.1149635911 -0.1619819850 1413 1311867217.5691540241 0.0525399223 0.0547462517 0.0680062324 0.0055740748 0.0258790000 238951174 95654136 760807424 -0.0282364748 -0.1134123579 -0.1626351625 1414 1311867217.6050539017 0.0535705760 0.0547454202 0.0680062324 0.0055727193 0.0249320000 238954814 95654136 760807424 -0.0280291289 -0.1103726774 -0.1620614827 1415 1311867217.6370990276 0.0531145595 0.0547442677 0.0680062324 0.0055709799 0.0250590000 238958430 95654136 760807424 -0.0271965768 -0.1089665815 -0.1619758904 1416 1311867217.6691000462 0.0520617105 0.0547423732 0.0680062324 0.0055708675 0.0251190000 239130230 95654136 760807424 -0.0259044785 -0.1101301610 -0.1611506939 1417 1311867217.7050631046 0.0520779267 0.0547404929 0.0680062324 0.0055689714 0.0249960000 239134014 95654136 760807424 -0.0249729417 -0.1095225215 -0.1607409269 1418 1311867217.7371540070 0.0523046777 0.0547387751 0.0680062324 0.0055677387 0.0249870000 239137430 95654136 760807424 -0.0259001162 -0.1092661470 -0.1604910791 1419 1311867217.7694880962 0.0528559722 0.0547374482 0.0680062324 0.0055664852 0.0338650000 239139358 95654136 760807424 -0.0269300826 -0.1082384884 -0.1604829580 1420 1311867217.8051838875 0.0521891713 0.0547356537 0.0680062324 0.0055651767 0.0252100000 239142942 95654136 760807424 -0.0232433714 -0.1075881198 -0.1604609042 1421 1311867217.8372271061 0.0530064814 0.0547344368 0.0680062324 0.0055638624 0.0283100000 239144758 95654136 760807424 -0.0241812002 -0.1046795920 -0.1612013280 1422 1311867217.8690850735 0.0547255501 0.0547344306 0.0680062324 0.0055635536 0.0286090000 239148286 95654136 760807424 -0.0249144100 -0.0996110439 -0.1615902930 1423 1311867217.9056351185 0.0539834872 0.0547339028 0.0680062324 0.0055624182 0.0250360000 239152126 95654136 760807424 -0.0241187997 -0.1004098877 -0.1610267758 1424 1311867217.9372580051 0.0536226518 0.0547331225 0.0680062324 0.0055610372 0.0250500000 239153686 95654136 760807424 -0.0238645766 -0.0982744098 -0.1618022025 1425 1311867217.9711000919 0.0537875257 0.0547324589 0.0680062324 0.0055592686 0.0297520000 239157470 95654136 760807424 -0.0234099738 -0.0966437683 -0.1612024456 1426 1311867218.0052239895 0.0544996858 0.0547322956 0.0680062324 0.0055576085 0.0250590000 239159198 95654136 760807424 -0.0239859987 -0.0949458927 -0.1603040546 1427 1311867218.0371439457 0.0543539375 0.0547320305 0.0680062324 0.0055565408 0.0290760000 239162814 95654136 760807424 -0.0211352743 -0.0944314450 -0.1591516584 1428 1311867218.0710949898 0.0543057211 0.0547317320 0.0680062324 0.0055549597 0.0251100000 239166230 95654136 760807424 -0.0216603931 -0.0920912847 -0.1597436517 1429 1311867218.1050980091 0.0550326556 0.0547319426 0.0680062324 0.0055539528 0.0250690000 239168214 95654136 760807424 -0.0232213028 -0.0894469917 -0.1596578956 1430 1311867218.1371181011 0.0549724177 0.0547321107 0.0680062324 0.0055523183 0.0250770000 239171686 95654136 760807424 -0.0205943696 -0.0875967443 -0.1591095477 1431 1311867218.1712090969 0.0548663810 0.0547322045 0.0680062324 0.0055514409 0.0289590000 239173614 95654136 760807424 -0.0222461037 -0.0861995220 -0.1590254009 1432 1311867218.2050349712 0.0548346415 0.0547322761 0.0680062324 0.0055507119 0.0251790000 239177142 95654136 760807424 -0.0218836609 -0.0864122286 -0.1578360200 1433 1311867218.2372438908 0.0549715720 0.0547324431 0.0680062324 0.0055489510 0.0251660000 239180758 95654136 760807424 -0.0228551850 -0.0846823975 -0.1580049396 1434 1311867218.2715640068 0.0554816127 0.0547329655 0.0680062324 0.0055472555 0.0250380000 239182542 95654136 760807424 -0.0235479623 -0.0826911703 -0.1579361111 1435 1311867218.3051331043 0.0557699651 0.0547336882 0.0680062324 0.0055454119 0.0304780000 239186270 95654136 760807424 -0.0221928600 -0.0824631304 -0.1572885364 1436 1311867218.3373649120 0.0561783500 0.0547346942 0.0680062324 0.0055439392 0.0251920000 239189686 95654136 760807424 -0.0244582798 -0.0804227442 -0.1583514959 1437 1311867218.3734769821 0.0560140125 0.0547355845 0.0680062324 0.0055420510 0.0252150000 239191726 95654136 760807424 -0.0234025195 -0.0784729868 -0.1591354758 1438 1311867218.4052689075 0.0551871769 0.0547358985 0.0680062324 0.0055413412 0.0251030000 239195198 95654136 760807424 -0.0236927141 -0.0804040730 -0.1591341645 1439 1311867218.4372320175 0.0556247123 0.0547365162 0.0680062324 0.0055399755 0.0251400000 239197070 95654136 760807424 -0.0245090015 -0.0804919749 -0.1590883434 1440 1311867218.4729750156 0.0560062304 0.0547373979 0.0680062324 0.0055383095 0.0250810000 239200598 95654136 760807424 -0.0253356900 -0.0787830129 -0.1596816182 1441 1311867218.5051169395 0.0566473454 0.0547387233 0.0680062324 0.0055381119 0.0251350000 239204326 95654136 760807424 -0.0262376275 -0.0752252340 -0.1605862081 1442 1311867218.5372729301 0.0555280559 0.0547392707 0.0680062324 0.0055381271 0.0251140000 239205942 95654136 760807424 -0.0252909809 -0.0756862611 -0.1605603993 1443 1311867218.5714759827 0.0550107919 0.0547394589 0.0680062324 0.0055363854 0.0253100000 239380390 95654136 760807424 -0.0238462593 -0.0743830502 -0.1607587337 1444 1311867218.6059319973 0.0552564748 0.0547398169 0.0680062324 0.0055347930 0.0251170000 239382174 95654136 760807424 -0.0240509491 -0.0724411458 -0.1604263633 1445 1311867218.6372020245 0.0555191189 0.0547403562 0.0680062324 0.0055341907 0.0252270000 239385734 95654136 760807424 -0.0247568823 -0.0722481087 -0.1595946252 1446 1311867218.6710820198 0.0564628057 0.0547415474 0.0680062324 0.0055335944 0.0252360000 239389318 95654136 760807424 -0.0256148931 -0.0693406686 -0.1593816876 1447 1311867218.7058999538 0.0561891086 0.0547425478 0.0680062324 0.0055338749 0.0251530000 239391134 95654136 760807424 -0.0231282357 -0.0688164160 -0.1587020904 1448 1311867218.7378489971 0.0555709414 0.0547431199 0.0680062324 0.0055343012 0.0290160000 239394606 95654136 760807424 -0.0248175375 -0.0692992806 -0.1582556814 1449 1311867218.7715899944 0.0567944348 0.0547445356 0.0680062324 0.0055346293 0.0254090000 239396534 95654136 760807424 -0.0258904994 -0.0681144074 -0.1574090123 1450 1311867218.8052420616 0.0566494204 0.0547458493 0.0680062324 0.0055336146 0.0259040000 239400118 95654136 760807424 -0.0272535086 -0.0658308268 -0.1580577493 1451 1311867218.8379960060 0.0561697930 0.0547468306 0.0680062324 0.0055327813 0.0253470000 239574778 95654136 760807424 -0.0241832044 -0.0664098337 -0.1565344632 1452 1311867218.8727340698 0.0584296547 0.0547493670 0.0680062324 0.0055437400 0.0253910000 239576506 95654136 760807424 -0.0266893469 -0.0649069920 -0.1552284956 1453 1311867218.9054861069 0.0573845580 0.0547511807 0.0680062324 0.0055469920 0.0252000000 239580122 95654136 760807424 -0.0289191715 -0.0635803789 -0.1559446007 1454 1311867218.9372200966 0.0566042662 0.0547524551 0.0680062324 0.0055476713 0.0252660000 239583650 95654136 760807424 -0.0277650543 -0.0640218407 -0.1552980244 1455 1311867218.9731678963 0.0568346046 0.0547538862 0.0680062324 0.0055461367 0.0290870000 239585634 95654136 760807424 -0.0275610276 -0.0618383437 -0.1554223299 1456 1311867219.0051829815 0.0566189364 0.0547551671 0.0680062324 0.0055443447 0.0252410000 239589162 95654136 760807424 -0.0271981601 -0.0609913617 -0.1551683247 1457 1311867219.0371239185 0.0564878993 0.0547563563 0.0680062324 0.0055428459 0.0252380000 239591034 95654136 760807424 -0.0273542888 -0.0599316247 -0.1549687982 1458 1311867219.0738430023 0.0572231300 0.0547580482 0.0680062324 0.0055473640 0.0252180000 239594618 95654136 760807424 -0.0277758371 -0.0594564006 -0.1532914042 1459 1311867219.1050798893 0.0563455187 0.0547591363 0.0680062324 0.0055520776 0.0281510000 239769734 95654136 760807424 -0.0267361812 -0.0604747459 -0.1527639627 1460 1311867219.1383259296 0.0561618730 0.0547600971 0.0680062324 0.0055501919 0.0285520000 239771406 95654136 760807424 -0.0268249009 -0.0593718439 -0.1527343392 1461 1311867219.1708459854 0.0565879345 0.0547613482 0.0680062324 0.0055483497 0.0252800000 239775134 95654136 760807424 -0.0267630536 -0.0576250255 -0.1524052769 1462 1311867219.2052450180 0.0570060685 0.0547628835 0.0680062324 0.0055475695 0.0253020000 239776918 95654136 760807424 -0.0262063276 -0.0546277240 -0.1523770541 1463 1311867219.2391340733 0.0566450283 0.0547641700 0.0680062324 0.0055480697 0.0262650000 239780590 95654136 760807424 -0.0275562219 -0.0549527556 -0.1516941488 1464 1311867219.2709059715 0.0560737364 0.0547650645 0.0680062324 0.0055471967 0.0252850000 239784062 95654136 760807424 -0.0250515640 -0.0546353944 -0.1511501968 1465 1311867219.3052430153 0.0552422218 0.0547653902 0.0680062324 0.0055515986 0.0253990000 239785990 95654136 760807424 -0.0246414375 -0.0543495938 -0.1514410824 1466 1311867219.3401598930 0.0560871549 0.0547662919 0.0680062324 0.0055509651 0.0253760000 239789518 95654136 760807424 -0.0248594768 -0.0521443784 -0.1510848403 1467 1311867219.3715050220 0.0568093099 0.0547676845 0.0680062324 0.0055494207 0.0288190000 239791334 95654136 760807424 -0.0267257933 -0.0513382182 -0.1506502926 1468 1311867219.4051969051 0.0568567328 0.0547691076 0.0680062324 0.0055488953 0.0290210000 239794918 95654136 760807424 -0.0253410321 -0.0508908406 -0.1497442573 1469 1311867219.4394860268 0.0572415851 0.0547707907 0.0680062324 0.0055470411 0.0292290000 239798646 95654136 760807424 -0.0242629312 -0.0482546724 -0.1498338729 1470 1311867219.4717299938 0.0565002896 0.0547719672 0.0680062324 0.0055456579 0.0253060000 239800318 95654136 760807424 -0.0221674126 -0.0475272238 -0.1497644633 1471 1311867219.5051560402 0.0565607697 0.0547731832 0.0680062324 0.0055438963 0.0253990000 239974422 95654136 760807424 -0.0239557326 -0.0477383584 -0.1493125260 1472 1311867219.5391950607 0.0573448390 0.0547749303 0.0680062324 0.0055427109 0.0291730000 239977894 95654136 760807424 -0.0228373464 -0.0448241979 -0.1491058618 1473 1311867219.5743470192 0.0566562116 0.0547762075 0.0680062324 0.0055410768 0.0253640000 239979878 95654136 760807424 -0.0217854921 -0.0449957624 -0.1486137211 1474 1311867219.6086258888 0.0562753044 0.0547772245 0.0680062324 0.0055394460 0.0254130000 239983350 95654136 760807424 -0.0221946593 -0.0465337150 -0.1477249861 1475 1311867219.6425020695 0.0575810000 0.0547791254 0.0680062324 0.0055483551 0.0287570000 239985278 95654136 760807424 -0.0211184267 -0.0432195179 -0.1479457021 1476 1311867219.6711170673 0.0573273487 0.0547808518 0.0680062324 0.0055617997 0.0417960000 239988638 95654136 760807424 -0.0214101188 -0.0436446443 -0.1477542371 1477 1311867219.7052869797 0.0568977632 0.0547822850 0.0680062324 0.0055602310 0.0262490000 239992366 95654136 760807424 -0.0193437189 -0.0463335291 -0.1468378454 1478 1311867219.7395179272 0.0571457669 0.0547838842 0.0680062324 0.0055596775 0.0253170000 239994094 95654136 760807424 -0.0195086524 -0.0422910117 -0.1482478380 1479 1311867219.7772109509 0.0580015369 0.0547860597 0.0680062324 0.0055710765 0.0254480000 239997878 95654136 760807424 -0.0191391632 -0.0412686802 -0.1480377614 1480 1311867219.8051769733 0.0574840158 0.0547878827 0.0680062324 0.0055703657 0.0256020000 239999494 95654136 760807424 -0.0179719869 -0.0416255556 -0.1482196897 1481 1311867219.8397340775 0.0563079529 0.0547889090 0.0680062324 0.0055687926 0.0331300000 240003278 95654136 760807424 -0.0161293503 -0.0405178703 -0.1493132710 1482 1311867219.8753221035 0.0562276803 0.0547898799 0.0680062324 0.0055778608 0.0293420000 240006806 95654136 760807424 -0.0156794935 -0.0400310680 -0.1493349075 1483 1311867219.9108390808 0.0568661615 0.0547912799 0.0680062324 0.0055925027 0.0254230000 240008678 95654136 760807424 -0.0181819033 -0.0379121602 -0.1494437009 1484 1311867219.9417819977 0.0563106760 0.0547923038 0.0680062324 0.0055949024 0.0299670000 240012150 95654136 760807424 -0.0176514294 -0.0370133743 -0.1493733823 1485 1311867219.9732298851 0.0566735826 0.0547935706 0.0680062324 0.0055938468 0.0294420000 240013910 95654136 760807424 -0.0124345478 -0.0355309397 -0.1483173519 1486 1311867220.0068678856 0.0566928387 0.0547948487 0.0680062324 0.0055955521 0.0294010000 240017494 95654136 760807424 -0.0121270837 -0.0351641923 -0.1480361223 1487 1311867220.0422430038 0.0562026240 0.0547957955 0.0680062324 0.0055940578 0.0255580000 240192070 95654136 760807424 -0.0135819577 -0.0340239331 -0.1484324187 1488 1311867220.0743820667 0.0569814369 0.0547972643 0.0680062324 0.0055924531 0.0354320000 240193742 95654136 760807424 -0.0138791213 -0.0318378322 -0.1486704946 1489 1311867220.1052761078 0.0574739836 0.0547990620 0.0680062324 0.0056000164 0.0256990000 240197414 95654136 760807424 -0.0140566714 -0.0294932313 -0.1487272978 1490 1311867220.1421229839 0.0577430204 0.0548010378 0.0680062324 0.0055982538 0.0254420000 240200942 95654136 760807424 -0.0145501653 -0.0288141742 -0.1480523795 1491 1311867220.1714730263 0.0578915142 0.0548031105 0.0680062324 0.0056038488 0.0255160000 240202814 95654136 760807424 -0.0151460012 -0.0269124918 -0.1476055086 1492 1311867220.2061989307 0.0583661459 0.0548054986 0.0680062324 0.0056066237 0.0287460000 240206398 95654136 760807424 -0.0152786542 -0.0262915064 -0.1473233253 1493 1311867220.2422249317 0.0576374568 0.0548073954 0.0680062324 0.0056091631 0.0255320000 240208382 95654136 760807424 -0.0118735526 -0.0255189836 -0.1473719925 1494 1311867220.2741279602 0.0578357689 0.0548094225 0.0680062324 0.0056075998 0.0254910000 240211798 95654136 760807424 -0.0133289555 -0.0245286040 -0.1476767808 1495 1311867220.3064579964 0.0588351041 0.0548121152 0.0680062324 0.0056182819 0.0255050000 240215470 95654136 760807424 -0.0134033849 -0.0212607011 -0.1483197659 1496 1311867220.3420999050 0.0583929867 0.0548145089 0.0680062324 0.0056202682 0.0359230000 240217142 95654136 760807424 -0.0134633910 -0.0217242986 -0.1480228156 1497 1311867220.3714869022 0.0574780703 0.0548162881 0.0680062324 0.0056623684 0.0257960000 240220758 95654136 760807424 -0.0126245832 -0.0191943608 -0.1487973332 1498 1311867220.4063799381 0.0583758354 0.0548186643 0.0680062324 0.0056617323 0.0255580000 240222598 95654136 760807424 -0.0134309847 -0.0156489611 -0.1491787285 1499 1311867220.4408841133 0.0581246950 0.0548208698 0.0680062324 0.0056610351 0.0255270000 240226326 95654136 760807424 -0.0136705171 -0.0143496310 -0.1489752084 1500 1311867220.4728751183 0.0575630069 0.0548226979 0.0680062324 0.0056621424 0.0255190000 240229742 95654136 760807424 -0.0128834387 -0.0146277221 -0.1487079114 1501 1311867220.5091059208 0.0585908964 0.0548252084 0.0680062324 0.0056608874 0.0255450000 240231782 95654136 760807424 -0.0117530581 -0.0120505784 -0.1485611051 1502 1311867220.5419850349 0.0583269857 0.0548275398 0.0680062324 0.0056591492 0.0257510000 240405486 95654136 760807424 -0.0129755149 -0.0129396012 -0.1478393078 1503 1311867220.5716400146 0.0593039244 0.0548305181 0.0680062324 0.0056573851 0.0256670000 240407246 95654136 760807424 -0.0126490770 -0.0125166113 -0.1467326283 1504 1311867220.6104249954 0.0594878644 0.0548336147 0.0680062324 0.0056567325 0.0355650000 240410886 95654136 760807424 -0.0115958173 -0.0107460851 -0.1474392563 1505 1311867220.6415500641 0.0589130707 0.0548363253 0.0680062324 0.0056564742 0.0259680000 240414446 95654136 760807424 -0.0099601364 -0.0112590548 -0.1474840641 1506 1311867220.6713089943 0.0584354773 0.0548387152 0.0680062324 0.0056548514 0.0255330000 240416118 95654136 760807424 -0.0075838491 -0.0112122269 -0.1479763985 1507 1311867220.7073359489 0.0589130819 0.0548414188 0.0680062324 0.0056566523 0.0256380000 240419902 95654136 760807424 -0.0092860954 -0.0097015733 -0.1491300017 1508 1311867220.7393438816 0.0584989861 0.0548438443 0.0680062324 0.0056553921 0.0255790000 240423374 95654136 760807424 -0.0081346203 -0.0087073417 -0.1498091668 1509 1311867220.7719850540 0.0583756194 0.0548461847 0.0680062324 0.0056540888 0.0257290000 240425190 95654136 760807424 -0.0069537023 -0.0083403187 -0.1501104385 1510 1311867220.8097529411 0.0582376085 0.0548484307 0.0680062324 0.0056530225 0.0256060000 240428886 95654136 760807424 -0.0052908398 -0.0085942438 -0.1500033289 1511 1311867220.8415019512 0.0580660738 0.0548505602 0.0680062324 0.0056518787 0.0292980000 240430782 95654136 760807424 -0.0051180553 -0.0066778385 -0.1509124339 1512 1311867220.8712480068 0.0582857765 0.0548528322 0.0680062324 0.0056535900 0.0337570000 240434254 95654136 760807424 -0.0043765455 -0.0058240900 -0.1504339278 1513 1311867220.9075961113 0.0589579903 0.0548555454 0.0680062324 0.0056577802 0.0257790000 240438038 95654136 760807424 -0.0059157163 -0.0067911777 -0.1492779106 1514 1311867220.9392969608 0.0587040633 0.0548580874 0.0680062324 0.0056560358 0.0255880000 240439710 95654136 760807424 -0.0046184715 -0.0069487980 -0.1489273459 1515 1311867220.9713189602 0.0577516183 0.0548599973 0.0680062324 0.0056691506 0.0256590000 240443382 95654136 760807424 -0.0030231250 -0.0072280392 -0.1490305066 1516 1311867221.0090179443 0.0583846085 0.0548623222 0.0680062324 0.0056674998 0.0257530000 240445222 95654136 760807424 -0.0030427687 -0.0056230910 -0.1484229118 1517 1311867221.0392940044 0.0587398410 0.0548648783 0.0680062324 0.0056660349 0.0290090000 240448838 95654136 760807424 -0.0030739054 -0.0054673897 -0.1477395743 1518 1311867221.0720989704 0.0576131456 0.0548666887 0.0680062324 0.0056643434 0.0291810000 240452310 95654136 760807424 -0.0012303425 -0.0037866323 -0.1489587277 1519 1311867221.1077580452 0.0584057570 0.0548690186 0.0680062324 0.0056635333 0.0265110000 240454294 95654136 760807424 -0.0021892567 -0.0020978148 -0.1484895051 1520 1311867221.1397790909 0.0588501841 0.0548716378 0.0680062324 0.0056621462 0.0376980000 240457822 95654136 760807424 -0.0010726546 -0.0022257864 -0.1476291418 1521 1311867221.1716909409 0.0590256006 0.0548743689 0.0680062324 0.0056629444 0.0259770000 240459582 95654136 760807424 -0.0004356007 0.0003601424 -0.1483444273 1522 1311867221.2083969116 0.0586098172 0.0548768232 0.0680062324 0.0056633989 0.0255390000 240463166 95654136 760807424 0.0007232370 0.0032925596 -0.1495103091 1523 1311867221.2398130894 0.0585969426 0.0548792658 0.0680062324 0.0056628259 0.0256020000 240466894 95654136 760807424 0.0020445040 0.0022454094 -0.1482330412 1524 1311867221.2721240520 0.0582585037 0.0548814831 0.0680062324 0.0056616017 0.0295060000 240468566 95654136 760807424 0.0039267177 0.0025473102 -0.1480924636 1525 1311867221.3075931072 0.0587824173 0.0548840411 0.0680062324 0.0056616924 0.0256230000 240472294 95654136 760807424 0.0032611280 0.0064223735 -0.1494834274 1526 1311867221.3393449783 0.0586337820 0.0548864984 0.0680062324 0.0056604098 0.0293660000 240475766 95654136 760807424 0.0044293716 0.0035587356 -0.1481137723 1527 1311867221.3714220524 0.0590848476 0.0548892478 0.0680062324 0.0056587577 0.0255950000 240477694 95654136 760807424 0.0053015882 0.0038369400 -0.1480451673 1528 1311867221.4073879719 0.0582729913 0.0548914623 0.0680062324 0.0056570853 0.0357660000 240481166 95654136 760807424 0.0075380378 0.0076846252 -0.1505474448 1529 1311867221.4400680065 0.0589733273 0.0548941319 0.0680062324 0.0056555147 0.0262310000 240483094 95654136 760807424 0.0099882670 0.0095761251 -0.1506712586 1530 1311867221.4712409973 0.0600236058 0.0548974845 0.0680062324 0.0056538600 0.0257030000 240486510 95654136 760807424 0.0100259762 0.0120025333 -0.1506835222 1531 1311867221.5081720352 0.0601356104 0.0549009059 0.0680062324 0.0056523470 0.0256610000 240490294 95654136 760807424 0.0107150543 0.0129101789 -0.1508813053 1532 1311867221.5396909714 0.0601340868 0.0549043218 0.0680062324 0.0056506492 0.0255850000 240492022 95654136 760807424 0.0108280145 0.0151725672 -0.1520667672 1533 1311867221.5712790489 0.0606774949 0.0549080877 0.0680062324 0.0056511210 0.0256310000 240495694 95654136 760807424 0.0105700158 0.0163158458 -0.1523977071 1534 1311867221.6073110104 0.0606650859 0.0549118407 0.0680062324 0.0056497903 0.0256100000 240497422 95654136 760807424 0.0094319116 0.0177603792 -0.1539091021 1535 1311867221.6403770447 0.0619628206 0.0549164341 0.0680062324 0.0056500160 0.0255900000 240501206 95654136 760807424 0.0086661503 0.0236113463 -0.1555788070 1536 1311867221.6771481037 0.0610090159 0.0549204006 0.0680062324 0.0056500618 0.0256430000 240504790 95654136 760807424 0.0078312913 0.0237711798 -0.1570820212 1537 1311867221.7072019577 0.0613646992 0.0549245934 0.0680062324 0.0056535452 0.0256450000 240506550 95654136 760807424 0.0073510134 0.0267277882 -0.1584422886 1538 1311867221.7423930168 0.0610616356 0.0549285837 0.0680062324 0.0056524434 0.0256520000 240510134 95654136 760807424 0.0080307145 0.0282924473 -0.1595306396 1539 1311867221.7773499489 0.0621970706 0.0549333066 0.0680062324 0.0056523334 0.0257760000 240683130 95654136 760807424 0.0074990820 0.0333150476 -0.1610870957 1540 1311867221.8074541092 0.0616576597 0.0549376730 0.0680062324 0.0056516001 0.0296280000 240686546 95654136 760807424 0.0057374104 0.0320574641 -0.1613537222 1541 1311867221.8396520615 0.0621743090 0.0549423691 0.0680062324 0.0056530361 0.0257190000 240690274 95654136 760807424 0.0059963944 0.0319472998 -0.1615485102 1542 1311867221.8777329922 0.0622085445 0.0549470813 0.0680062324 0.0056551708 0.0256840000 240692114 95654136 760807424 0.0062925387 0.0344679765 -0.1641568094 1543 1311867221.9077489376 0.0623940267 0.0549519075 0.0680062324 0.0056551210 0.0257020000 240695730 95654136 760807424 0.0065972181 0.0350757837 -0.1649143696 1544 1311867221.9424629211 0.0619451255 0.0549564368 0.0680062324 0.0056561056 0.0357790000 240699258 95654136 760807424 0.0059940428 0.0350405313 -0.1658182889 1545 1311867221.9775359631 0.0626269057 0.0549614015 0.0680062324 0.0056566071 0.0258860000 240701242 95654136 760807424 0.0054224911 0.0398158841 -0.1681288928 1546 1311867222.0090060234 0.0622750297 0.0549661322 0.0680062324 0.0056553020 0.0255760000 240704714 95654136 760807424 0.0053577702 0.0404539667 -0.1689159423 1547 1311867222.0428760052 0.0626466051 0.0549710970 0.0680062324 0.0056547682 0.0289480000 240706474 95654136 760807424 0.0029872507 0.0413416103 -0.1692234129 1548 1311867222.0782530308 0.0625992194 0.0549760247 0.0680062324 0.0056555736 0.0255670000 240709946 95654136 760807424 0.0040705269 0.0446184538 -0.1705114096 1549 1311867222.1110939980 0.0626794845 0.0549809979 0.0680062324 0.0056541208 0.0256630000 240713618 95654136 760807424 0.0045209327 0.0490020588 -0.1715954989 1550 1311867222.1406900883 0.0613716729 0.0549851209 0.0680062324 0.0056748788 0.0256110000 240715234 95654136 760807424 0.0029610128 0.0491383895 -0.1714761257 1551 1311867222.1797990799 0.0620893426 0.0549897013 0.0680062324 0.0056915403 0.0256260000 240719130 95654136 760807424 0.0026561790 0.0514638871 -0.1712326258 1552 1311867222.2081730366 0.0631337240 0.0549949487 0.0680062324 0.0056917025 0.0349520000 240891186 95654136 760807424 0.0025975395 0.0571158193 -0.1716208756 1553 1311867222.2400839329 0.0617060252 0.0549992701 0.0680062324 0.0056967947 0.0266930000 240894858 95654136 760807424 0.0029375213 0.0556699485 -0.1704754531 1554 1311867222.2760300636 0.0625592396 0.0550041350 0.0680062324 0.0056986654 0.0256010000 240898442 95654136 760807424 0.0020954553 0.0586269312 -0.1698030829 1555 1311867222.3077421188 0.0620897003 0.0550086916 0.0680062324 0.0056988469 0.0256230000 240900314 95654136 760807424 0.0010371575 0.0622198321 -0.1704202592 1556 1311867222.3396389484 0.0612076931 0.0550126755 0.0680062324 0.0056994908 0.0295540000 241074370 95654136 760807424 0.0013582055 0.0622055829 -0.1694761217 1557 1311867222.3792359829 0.0613584146 0.0550167511 0.0680062324 0.0057033931 0.0256060000 241076410 95654136 760807424 0.0009799737 0.0631241500 -0.1686106920 1558 1311867222.4102001190 0.0618751198 0.0550211532 0.0680062324 0.0057021169 0.0294530000 241079882 95654136 760807424 0.0003548518 0.0679748878 -0.1688539088 1559 1311867222.4436430931 0.0625790954 0.0550260011 0.0680062324 0.0057004122 0.0257400000 241083554 95654136 760807424 -0.0001140893 0.0696330070 -0.1673248708 1560 1311867222.4781119823 0.0625481009 0.0550308230 0.0680062324 0.0056987498 0.0371180000 241085338 95654136 760807424 -0.0007924040 0.0732459947 -0.1668058634 1561 1311867222.5087089539 0.0639804825 0.0550365563 0.0680062324 0.0056972737 0.0259650000 241088954 95654136 760807424 -0.0003735541 0.0770784989 -0.1654494405 1562 1311867222.5401790142 0.0644201562 0.0550425637 0.0680062324 0.0056960787 0.0256500000 241092426 95654136 760807424 -0.0008648597 0.0773371309 -0.1638417691 1563 1311867222.5774040222 0.0647580922 0.0550487796 0.0680062324 0.0056944062 0.0257480000 241265230 95654136 760807424 -0.0018351872 0.0778602734 -0.1620707214 1564 1311867222.6084389687 0.0650091618 0.0550551482 0.0680062324 0.0056928977 0.0259890000 241268702 95654136 760807424 -0.0013969569 0.0812485740 -0.1615576446 1565 1311867222.6433119774 0.0641784221 0.0550609777 0.0680062324 0.0056939593 0.0258940000 241270630 95654136 760807424 -0.0001120751 0.0805198997 -0.1604435593 1566 1311867222.6796491146 0.0650322065 0.0550673451 0.0680062324 0.0056948426 0.0257270000 241274270 95654136 760807424 -0.0001329312 0.0812334493 -0.1587351859 1567 1311867222.7080249786 0.0642640367 0.0550732140 0.0680062324 0.0056959165 0.0257500000 241277774 95654136 760807424 -0.0006288124 0.0826552883 -0.1587399393 1568 1311867222.7400081158 0.0643880814 0.0550791546 0.0680062324 0.0056964202 0.0298370000 241279502 95654136 760807424 0.0004198292 0.0834675506 -0.1577006131 1569 1311867222.7793939114 0.0645206198 0.0550851721 0.0680062324 0.0056975575 0.0258270000 241283230 95654136 760807424 0.0002227512 0.0836539567 -0.1563429385 1570 1311867222.8093209267 0.0650285855 0.0550915055 0.0680062324 0.0056973610 0.0257120000 241284790 95654136 760807424 0.0008707010 0.0849237815 -0.1557357311 1571 1311867222.8402760029 0.0653114915 0.0550980109 0.0680062324 0.0056957789 0.0256650000 241288462 95654136 760807424 0.0002692637 0.0875044316 -0.1559900343 1572 1311867222.8812980652 0.0643339753 0.0551038862 0.0680062324 0.0056949101 0.0257020000 241292102 95654136 760807424 -0.0006813098 0.0862858519 -0.1553983390 1573 1311867222.9082360268 0.0648322478 0.0551100708 0.0680062324 0.0056931738 0.0289570000 241293862 95654136 760807424 0.0006328328 0.0875597745 -0.1548345089 1574 1311867222.9470820427 0.0649966449 0.0551163520 0.0680062324 0.0056924241 0.0256500000 241297558 95654136 760807424 0.0010841329 0.0896361396 -0.1545554250 1575 1311867222.9831020832 0.0645556524 0.0551223452 0.0680062324 0.0056907333 0.0290140000 241299542 95654136 760807424 -0.0002940135 0.0885838941 -0.1537319869 1576 1311867223.0078310966 0.0650131777 0.0551286211 0.0680062324 0.0056914148 0.0256520000 241302790 95654136 760807424 -0.0003183873 0.0888316408 -0.1528276503 1577 1311867223.0454061031 0.0651213080 0.0551349576 0.0680062324 0.0056899976 0.0256840000 241306630 95654136 760807424 0.0003129537 0.0909544900 -0.1528456807 1578 1311867223.0808250904 0.0647392422 0.0551410440 0.0680062324 0.0056900909 0.0257090000 241308414 95654136 760807424 -0.0001556340 0.0905781984 -0.1522852778 1579 1311867223.1094229221 0.0651070252 0.0551473556 0.0680062324 0.0056897083 0.0257490000 241311974 95654136 760807424 -0.0004133990 0.0920448154 -0.1519183964 1580 1311867223.1473770142 0.0654708445 0.0551538894 0.0680062324 0.0056894514 0.0257600000 241315614 95654136 760807424 -0.0033804888 0.0937589630 -0.1520483792 1581 1311867223.1758580208 0.0649515837 0.0551600866 0.0680062324 0.0056884448 0.0289600000 241317374 95654136 760807424 -0.0015358315 0.0929090306 -0.1510886103 1582 1311867223.2080020905 0.0644827038 0.0551659795 0.0680062324 0.0056869528 0.0257150000 241320790 95654136 760807424 -0.0023236386 0.0931566879 -0.1505408287 1583 1311867223.2450079918 0.0635027736 0.0551712460 0.0680062324 0.0056873449 0.0289910000 241322830 95654136 760807424 -0.0037036873 0.0944503173 -0.1509470195 1584 1311867223.2779359818 0.0630130544 0.0551761966 0.0680062324 0.0056862693 0.0284770000 241326358 95654136 760807424 -0.0037903464 0.0956370384 -0.1509897858 1585 1311867223.3085999489 0.0631041825 0.0551811985 0.0680062324 0.0056852388 0.0257160000 241329974 95654136 760807424 -0.0026943034 0.0967310444 -0.1503263116 1586 1311867223.3452420235 0.0630532652 0.0551861620 0.0680062324 0.0056840280 0.0257130000 241331814 95654136 760807424 -0.0041878396 0.0989240184 -0.1502170563 1587 1311867223.3794689178 0.0617348030 0.0551902884 0.0680062324 0.0056901990 0.0257260000 241335486 95654136 760807424 -0.0052136485 0.0997226089 -0.1498115361 1588 1311867223.4074239731 0.0629915744 0.0551952010 0.0680062324 0.0056896984 0.0256770000 241336990 95654136 760807424 -0.0055219028 0.0999339446 -0.1491332799 1589 1311867223.4458000660 0.0632960647 0.0552002991 0.0680062324 0.0056892124 0.0266450000 241340830 95654136 760807424 -0.0081810476 0.1019930840 -0.1497121155 1590 1311867223.4758329391 0.0646486878 0.0552062415 0.0680062324 0.0056889812 0.0258500000 241515218 95654136 760807424 -0.0099550700 0.1061780900 -0.1502905339 1591 1311867223.5077428818 0.0643611252 0.0552119957 0.0680062324 0.0056877368 0.0256850000 241517090 95654136 760807424 -0.0107061490 0.1069781706 -0.1507863551 1592 1311867223.5466530323 0.0648835897 0.0552180708 0.0680062324 0.0056936289 0.0259220000 241520730 95654136 760807424 -0.0096684555 0.1071997508 -0.1497412920 1593 1311867223.5759539604 0.0658254996 0.0552247296 0.0680062324 0.0056949746 0.0258560000 241522602 95654136 760807424 -0.0090425275 0.1098354235 -0.1500694156 1594 1311867223.6078069210 0.0662172660 0.0552316258 0.0680062324 0.0056935100 0.0258190000 241525962 95654136 760807424 -0.0109148594 0.1120082811 -0.1510021091 1595 1311867223.6502039433 0.0652222559 0.0552378895 0.0680062324 0.0056957533 0.0260010000 241529970 95654136 760807424 -0.0131292995 0.1099912524 -0.1510539651 1596 1311867223.6753880978 0.0655373260 0.0552443428 0.0680062324 0.0056945290 0.0265050000 241531418 95654136 760807424 -0.0114481132 0.1148840040 -0.1528537720 1597 1311867223.7088580132 0.0656842291 0.0552508799 0.0680062324 0.0056928064 0.0262540000 241535146 95654136 760807424 -0.0109820757 0.1166085154 -0.1530910283 1598 1311867223.7452809811 0.0655525625 0.0552573266 0.0680062324 0.0056922629 0.0261020000 241538786 95654136 760807424 -0.0133315958 0.1188514009 -0.1541265696 1599 1311867223.7760720253 0.0660804585 0.0552640952 0.0680062324 0.0056928707 0.0261890000 241540602 95654136 760807424 -0.0123880887 0.1203589812 -0.1539134383 1600 1311867223.8077559471 0.0664735660 0.0552711012 0.0680062324 0.0056912946 0.0260670000 241544018 95654136 760807424 -0.0126722520 0.1237666234 -0.1549668610 1601 1311867223.8438520432 0.0661795884 0.0552779147 0.0680062324 0.0056919646 0.0261280000 241546058 95654136 760807424 -0.0123759601 0.1240854189 -0.1549866647 1602 1311867223.8760919571 0.0667421818 0.0552850709 0.0680062324 0.0056903151 0.0262290000 241549530 95654136 760807424 -0.0115237450 0.1261670291 -0.1548071355 1603 1311867223.9078280926 0.0668966100 0.0552923146 0.0680062324 0.0056889896 0.0257820000 241553146 95654136 760807424 -0.0109143332 0.1296096146 -0.1559822410 1604 1311867223.9491670132 0.0655444264 0.0552987062 0.0680062324 0.0056876426 0.0257160000 241555098 95654136 760807424 -0.0108349808 0.1279280931 -0.1560956240 1605 1311867223.9760739803 0.0661892295 0.0553054915 0.0680062324 0.0056883016 0.0295350000 241558658 95654136 760807424 -0.0111167775 0.1311819404 -0.1566381156 1606 1311867224.0093441010 0.0664803088 0.0553124497 0.0680062324 0.0056893707 0.0256780000 241560330 95654136 760807424 -0.0101262061 0.1331460625 -0.1573268771 1607 1311867224.0470440388 0.0682248324 0.0553204848 0.0682248324 0.0056879354 0.0258040000 241734822 95654136 760807424 -0.0080390964 0.1382185966 -0.1574798226 1608 1311867224.0761411190 0.0683804601 0.0553286067 0.0683804601 0.0056866563 0.0315030000 241738182 95654136 760807424 -0.0109287510 0.1389492303 -0.1578611135 1609 1311867224.1081349850 0.0685880184 0.0553368474 0.0685880184 0.0056850616 0.0258330000 241740054 95654136 760807424 -0.0111914659 0.1399889588 -0.1581141353 1610 1311867224.1458990574 0.0692187548 0.0553454697 0.0692187548 0.0056869631 0.0256720000 241743638 95654136 760807424 -0.0081886025 0.1432514489 -0.1581532657 1611 1311867224.1768929958 0.0693877190 0.0553541862 0.0693877190 0.0056911458 0.0256520000 241745510 95654136 760807424 -0.0080462210 0.1446550339 -0.1588252485 1612 1311867224.2143769264 0.0686991885 0.0553624648 0.0693877190 0.0056899435 0.0256890000 241748982 95654136 760807424 -0.0074469121 0.1460758001 -0.1600087881 1613 1311867224.2470428944 0.0700834915 0.0553715912 0.0700834915 0.0056885906 0.0256850000 241752654 95654136 760807424 -0.0055151498 0.1510013491 -0.1606837213 1614 1311867224.2768630981 0.0696797967 0.0553804563 0.0700834915 0.0056874466 0.0256800000 241754214 95654136 760807424 -0.0036954223 0.1515337080 -0.1610718518 1615 1311867224.3146169186 0.0690747425 0.0553889357 0.0700834915 0.0056863785 0.0286790000 241758110 95654136 760807424 -0.0050297370 0.1511999071 -0.1615859270 1616 1311867224.3456730843 0.0699633211 0.0553979545 0.0700834915 0.0056849393 0.0374920000 241761582 95654136 760807424 -0.0050589214 0.1537207961 -0.1617579609 1617 1311867224.3769209385 0.0694776624 0.0554066618 0.0700834915 0.0056838135 0.0260580000 241763342 95654136 760807424 -0.0055348827 0.1545763165 -0.1627159566 1618 1311867224.4141020775 0.0699530914 0.0554156522 0.0700834915 0.0056841398 0.0256700000 241766982 95654136 760807424 -0.0059575778 0.1550066620 -0.1628011465 1619 1311867224.4464271069 0.0699896589 0.0554246541 0.0700834915 0.0056833075 0.0257480000 241768854 95654136 760807424 -0.0058352449 0.1568019837 -0.1635270566 1620 1311867224.4776859283 0.0708162412 0.0554341551 0.0708162412 0.0056853906 0.0258100000 241772270 95654136 760807424 -0.0066364710 0.1603949964 -0.1649968177 1621 1311867224.5181219578 0.0707226768 0.0554435866 0.0708162412 0.0056903892 0.0256460000 241776166 95654136 760807424 -0.0066865007 0.1606837511 -0.1657924652 1622 1311867224.5470569134 0.0718336627 0.0554536914 0.0718336627 0.0056923280 0.0288980000 241777782 95654136 760807424 -0.0062322980 0.1631740630 -0.1663323641 1623 1311867224.5859119892 0.0745678619 0.0554654685 0.0745678619 0.0056984273 0.0257500000 241781678 95654136 760807424 -0.0062737237 0.1707956493 -0.1677252054 1624 1311867224.6181120872 0.0738449693 0.0554767859 0.0745678619 0.0056974971 0.0372850000 241783294 95654136 760807424 -0.0059718122 0.1707942933 -0.1680419892 1625 1311867224.6502161026 0.0729953721 0.0554875666 0.0745678619 0.0056964326 0.0262020000 241787022 95654136 760807424 -0.0063352608 0.1694868952 -0.1677493900 1626 1311867224.6785190105 0.0730690137 0.0554983793 0.0745678619 0.0056983140 0.0258110000 241790326 95654136 760807424 -0.0054433378 0.1720453650 -0.1683900803 1627 1311867224.7173650265 0.0729209632 0.0555090877 0.0745678619 0.0056990526 0.0257960000 241792422 95654136 760807424 -0.0049698614 0.1735144109 -0.1686912924 1628 1311867224.7520918846 0.0715684146 0.0555189522 0.0745678619 0.0056978990 0.0257530000 241796006 95654136 760807424 -0.0050090267 0.1728775501 -0.1690506339 1629 1311867224.7866261005 0.0710748360 0.0555285015 0.0745678619 0.0056968417 0.0257590000 241797878 95654136 760807424 -0.0064025498 0.1743243635 -0.1696438938 1630 1311867224.8123459816 0.0725776181 0.0555389611 0.0745678619 0.0056992580 0.0256410000 241801238 95654136 760807424 -0.0066416492 0.1777969748 -0.1693092585 1631 1311867224.8458189964 0.0718504116 0.0555489620 0.0745678619 0.0057284287 0.0290870000 241804854 95654136 760807424 -0.0059684878 0.1780613959 -0.1685280651 1632 1311867224.8779430389 0.0723936260 0.0555592835 0.0745678619 0.0057321928 0.0256460000 241806470 95654136 760807424 -0.0057614762 0.1803668439 -0.1679975986 1633 1311867224.9142448902 0.0713652074 0.0555689625 0.0745678619 0.0057371756 0.0289210000 241810310 95654136 760807424 -0.0067066355 0.1798759848 -0.1675468534 1634 1311867224.9471449852 0.0713434592 0.0555786165 0.0745678619 0.0057412078 0.0290360000 241813670 95654136 760807424 -0.0077104885 0.1808219403 -0.1670490950 1635 1311867224.9800488949 0.0694676936 0.0555871113 0.0745678619 0.0057401926 0.0257230000 241815654 95654136 760807424 -0.0078755859 0.1793844104 -0.1667434126 1636 1311867225.0142920017 0.0711489171 0.0555966234 0.0745678619 0.0057407218 0.0257550000 241819014 95654136 760807424 -0.0058185775 0.1859073788 -0.1665670872 1637 1311867225.0493879318 0.0706954971 0.0556058469 0.0745678619 0.0057431389 0.0261280000 241820886 95654136 760807424 -0.0044772876 0.1890707314 -0.1666340530 1638 1311867225.0798690319 0.0696850717 0.0556144423 0.0745678619 0.0057457010 0.0257300000 241824358 95654136 760807424 -0.0052939449 0.1892137080 -0.1669521630 1639 1311867225.1138188839 0.0720682740 0.0556244812 0.0745678619 0.0057477671 0.0347700000 241828030 95654136 760807424 -0.0058625760 0.1950751841 -0.1663400382 1640 1311867225.1472380161 0.0709664226 0.0556338361 0.0745678619 0.0057469452 0.0258680000 241829702 95654136 760807424 -0.0047709588 0.1960947365 -0.1663761586 1641 1311867225.1810939312 0.0710551888 0.0556432336 0.0745678619 0.0057452360 0.0291190000 241833486 95654136 760807424 -0.0052277655 0.1961396635 -0.1649535596 1642 1311867225.2153220177 0.0711599216 0.0556526835 0.0745678619 0.0057437019 0.0257660000 241835214 95654136 760807424 -0.0050604977 0.1959888339 -0.1635607630 1643 1311867225.2483470440 0.0705164894 0.0556617302 0.0745678619 0.0057442141 0.0293490000 241838886 95654136 760807424 -0.0042118882 0.1971079111 -0.1637294441 1644 1311867225.2792909145 0.0701096579 0.0556705185 0.0745678619 0.0057433852 0.0256770000 241842358 95654136 760807424 -0.0049295230 0.1987424940 -0.1640621275 1645 1311867225.3207540512 0.0688469857 0.0556785285 0.0745678619 0.0057438140 0.0257320000 241844510 95654136 760807424 -0.0060211718 0.1975180060 -0.1644726545 1646 1311867225.3462350368 0.0701667964 0.0556873306 0.0745678619 0.0057425337 0.0255970000 241847814 95654136 760807424 -0.0078377733 0.2008120120 -0.1644085795 1647 1311867225.3852069378 0.0710861012 0.0556966802 0.0745678619 0.0057411915 0.0348400000 241849854 95654136 760807424 -0.0070592458 0.2048401535 -0.1645556986 1648 1311867225.4130129814 0.0709272027 0.0557059220 0.0745678619 0.0057395439 0.0259590000 241853158 95654136 760807424 -0.0068139969 0.2044268548 -0.1640379876 1649 1311867225.4504270554 0.0715017915 0.0557155011 0.0745678619 0.0057378672 0.0257720000 241857054 95654136 760807424 -0.0070737512 0.2078791410 -0.1647332758 1650 1311867225.4842948914 0.0712759420 0.0557249317 0.0745678619 0.0057373610 0.0296490000 241858726 95654136 760807424 -0.0078952936 0.2078585923 -0.1645438224 1651 1311867225.5163919926 0.0714547411 0.0557344591 0.0745678619 0.0057382197 0.0257500000 241862454 95654136 760807424 -0.0087843304 0.2085386962 -0.1647454798 1652 1311867225.5493750572 0.0732184127 0.0557450426 0.0745678619 0.0057421513 0.0257790000 241865870 95654136 760807424 -0.0099280672 0.2134545445 -0.1652840972 1653 1311867225.5882349014 0.0733403787 0.0557556871 0.0745678619 0.0057416594 0.0257910000 241867910 95654136 760807424 -0.0110328551 0.2150296420 -0.1655981839 1654 1311867225.6179010868 0.0730801895 0.0557661614 0.0745678619 0.0057409375 0.0291230000 241871326 95654136 760807424 -0.0124490624 0.2144080251 -0.1665533930 1655 1311867225.6461288929 0.0735237226 0.0557768910 0.0745678619 0.0057394400 0.0258530000 241873086 95654136 760807424 -0.0142746465 0.2164299488 -0.1681478173 1656 1311867225.6847119331 0.0745352358 0.0557882185 0.0745678619 0.0057377471 0.0257710000 241876782 95654136 760807424 -0.0143433446 0.2196514159 -0.1691122353 1657 1311867225.7160770893 0.0740906969 0.0557992641 0.0745678619 0.0057363724 0.0258590000 241880454 95654136 760807424 -0.0149379419 0.2189158797 -0.1700640023 1658 1311867225.7506299019 0.0746885315 0.0558106569 0.0746885315 0.0057410906 0.0258200000 241882182 95654136 760807424 -0.0177569333 0.2198649347 -0.1712153554 1659 1311867225.7872900963 0.0771341100 0.0558235101 0.0771341100 0.0057424855 0.0258520000 241885910 95654136 760807424 -0.0188041609 0.2260264158 -0.1724121571 1660 1311867225.8170781136 0.0755335242 0.0558353836 0.0771341100 0.0057468327 0.0267110000 241887470 95654136 760807424 -0.0190589316 0.2247095257 -0.1733955890 1661 1311867225.8520019054 0.0765480176 0.0558478536 0.0771341100 0.0057503532 0.0257910000 241891310 95654136 760807424 -0.0188025143 0.2269840688 -0.1736575514 1662 1311867225.8862910271 0.0761595666 0.0558600748 0.0771341100 0.0057540379 0.0257590000 241894838 95654136 760807424 -0.0194033124 0.2286249995 -0.1748434901 1663 1311867225.9177930355 0.0759926662 0.0558721810 0.0771341100 0.0057523244 0.0351640000 241896654 95654136 760807424 -0.0203355066 0.2292388976 -0.1751641184 1664 1311867225.9504909515 0.0752801970 0.0558838445 0.0771341100 0.0057526395 0.0259960000 241900182 95654136 760807424 -0.0210490003 0.2294497639 -0.1757281274 1665 1311867225.9852480888 0.0760482401 0.0558959552 0.0771341100 0.0057519619 0.0257830000 241902166 95654136 760807424 -0.0209999271 0.2305972874 -0.1753958166 1666 1311867226.0173718929 0.0751863644 0.0559075341 0.0771341100 0.0057506260 0.0258850000 241905638 95654136 760807424 -0.0216597561 0.2303949445 -0.1763207167 1667 1311867226.0511479378 0.0745593533 0.0559187230 0.0771341100 0.0057491161 0.0296760000 241909310 95654136 760807424 -0.0210499298 0.2330971956 -0.1780034602 1668 1311867226.0877819061 0.0744235292 0.0559298170 0.0771341100 0.0057485647 0.0297120000 241911094 95654136 760807424 -0.0214622710 0.2345149517 -0.1781640053 1669 1311867226.1182270050 0.0739336461 0.0559406042 0.0771341100 0.0057545124 0.0257380000 241914766 95654136 760807424 -0.0219559744 0.2342508584 -0.1780003309 1670 1311867226.1477489471 0.0759473890 0.0559525843 0.0771341100 0.0057540947 0.0258080000 241918126 95654136 760807424 -0.0220906679 0.2395299822 -0.1782333106 1671 1311867226.1833140850 0.0762248039 0.0559647161 0.0771341100 0.0057539706 0.0363210000 241920110 95654136 760807424 -0.0216600541 0.2419743240 -0.1781605929 1672 1311867226.2166810036 0.0756029785 0.0559764614 0.0771341100 0.0057527098 0.0260010000 241923582 95654136 760807424 -0.0239920244 0.2424083501 -0.1790750176 1673 1311867226.2487111092 0.0758182853 0.0559883215 0.0771341100 0.0057525921 0.0258520000 241925510 95654136 760807424 -0.0240279268 0.2449487150 -0.1798517555 1674 1311867226.2829930782 0.0754536018 0.0559999495 0.0771341100 0.0057520517 0.0257840000 241929038 95654136 760807424 -0.0220510159 0.2453324795 -0.1800183654 1675 1311867226.3211309910 0.0766289085 0.0560122653 0.0771341100 0.0057507457 0.0297110000 241932934 95654136 760807424 -0.0222212747 0.2488732189 -0.1802890748 1676 1311867226.3455820084 0.0782539174 0.0560255359 0.0782539174 0.0057504214 0.0257740000 241934326 95654136 760807424 -0.0214566607 0.2530185878 -0.1800096929 1677 1311867226.3873078823 0.0766983032 0.0560378632 0.0782539174 0.0057498156 0.0258760000 241938334 95654136 760807424 -0.0209868886 0.2523237765 -0.1802427024 1678 1311867226.4188749790 0.0768239722 0.0560502506 0.0782539174 0.0057484805 0.0364080000 241939950 95654136 760807424 -0.0227965992 0.2540845871 -0.1806614399 1679 1311867226.4472739697 0.0777806416 0.0560631931 0.0782539174 0.0057469846 0.0259890000 241943566 95654136 760807424 -0.0216885004 0.2576880753 -0.1810580790 1680 1311867226.4849569798 0.0785281584 0.0560765651 0.0785281584 0.0057457269 0.0257520000 241947150 95654136 760807424 -0.0215087980 0.2608268857 -0.1816561520 1681 1311867226.5167839527 0.0777935907 0.0560894842 0.0785281584 0.0057452390 0.0257880000 241948966 95654136 760807424 -0.0226362180 0.2598467171 -0.1819463968 1682 1311867226.5462191105 0.0777012184 0.0561023330 0.0785281584 0.0057439761 0.0259070000 241952382 95654136 760807424 -0.0225276891 0.2617568374 -0.1828144491 1683 1311867226.5842289925 0.0779936239 0.0561153403 0.0785281584 0.0057433576 0.0258840000 241954422 95654136 760807424 -0.0213825535 0.2636898458 -0.1827513874 1684 1311867226.6149599552 0.0777833462 0.0561282073 0.0785281584 0.0057421707 0.0297230000 241957838 95654136 760807424 -0.0207987688 0.2642960548 -0.1827419251 1685 1311867226.6545290947 0.0780478939 0.0561412160 0.0785281584 0.0057414393 0.0258290000 241961734 95654136 760807424 -0.0219243485 0.2648577988 -0.1827652752 1686 1311867226.6802148819 0.0777354985 0.0561540240 0.0785281584 0.0057410044 0.0258780000 241963238 95654136 760807424 -0.0217626020 0.2666343451 -0.1836614460 1687 1311867226.7142350674 0.0783264115 0.0561671671 0.0785281584 0.0057406504 0.0257590000 241966966 95654136 760807424 -0.0223397128 0.2690266967 -0.1849710494 1688 1311867226.7506589890 0.0780840814 0.0561801511 0.0785281584 0.0057424333 0.0258220000 241970550 95654136 760807424 -0.0222806372 0.2691857815 -0.1854191869 1689 1311867226.7818078995 0.0800013319 0.0561942548 0.0800013319 0.0057439398 0.0257850000 241972422 95654136 760807424 -0.0235095080 0.2741445899 -0.1863093674 1690 1311867226.8133080006 0.0794457719 0.0562080131 0.0800013319 0.0057462774 0.0295810000 241975838 95654136 760807424 -0.0232223067 0.2740997076 -0.1863591671 1691 1311867226.8513610363 0.0792424455 0.0562216349 0.0800013319 0.0057447494 0.0297640000 241977878 95654136 760807424 -0.0239115898 0.2737202644 -0.1863009483 1692 1311867226.8838679790 0.0808402896 0.0562361849 0.0808402896 0.0057492891 0.0258010000 241981350 95654136 760807424 -0.0243905317 0.2767639160 -0.1864433289 1693 1311867226.9181559086 0.0807388499 0.0562506578 0.0808402896 0.0057476321 0.0258080000 241985078 95654136 760807424 -0.0241970196 0.2785207927 -0.1875976920 1694 1311867226.9514899254 0.0799767226 0.0562646638 0.0808402896 0.0057460921 0.0383150000 241986806 95654136 760807424 -0.0244866237 0.2777047753 -0.1880781651 1695 1311867226.9810149670 0.0814718455 0.0562795352 0.0814718455 0.0057450384 0.0260900000 241990478 95654136 760807424 -0.0252339579 0.2811270356 -0.1883237660 1696 1311867227.0125620365 0.0821182579 0.0562947703 0.0821182579 0.0057434997 0.0262750000 242162818 95654136 760807424 -0.0248235036 0.2838649750 -0.1885645092 1697 1311867227.0480670929 0.0810144618 0.0563093370 0.0821182579 0.0057459576 0.0292730000 242166658 95654136 760807424 -0.0240657181 0.2834998071 -0.1886804104 1698 1311867227.0861930847 0.0808304176 0.0563237782 0.0821182579 0.0057462062 0.0259330000 242170130 95654136 760807424 -0.0249607693 0.2857173681 -0.1888674051 1699 1311867227.1158189774 0.0810353011 0.0563383229 0.0821182579 0.0057455782 0.0258820000 242171890 95654136 760807424 -0.0240479391 0.2871732116 -0.1882238388 1700 1311867227.1503999233 0.0801218748 0.0563523133 0.0821182579 0.0057476348 0.0259370000 242175474 95654136 760807424 -0.0243628491 0.2855706811 -0.1873371452 1701 1311867227.1841590405 0.0805096403 0.0563665151 0.0821182579 0.0057463558 0.0259360000 242177402 95654136 760807424 -0.0244483352 0.2886656225 -0.1874835193 1702 1311867227.2148449421 0.0789171979 0.0563797646 0.0821182579 0.0057452128 0.0371790000 242180762 95654136 760807424 -0.0233259480 0.2883148193 -0.1882800609 1703 1311867227.2480258942 0.0789203718 0.0563930004 0.0821182579 0.0057484202 0.0259210000 242184490 95654136 760807424 -0.0267897658 0.2901040316 -0.1893174201 1704 1311867227.2819800377 0.0801425502 0.0564069380 0.0821182579 0.0057510725 0.0298680000 242186218 95654136 760807424 -0.0257756077 0.2936113179 -0.1889151335 1705 1311867227.3152499199 0.0815292075 0.0564216724 0.0821182579 0.0057514285 0.0305330000 242189946 95654136 760807424 -0.0253853556 0.2965536118 -0.1886094064 1706 1311867227.3479840755 0.0811986625 0.0564361959 0.0821182579 0.0057498408 0.0258570000 242193418 95654136 760807424 -0.0270488095 0.2968935668 -0.1886355132 1707 1311867227.3841071129 0.0812137350 0.0564507111 0.0821182579 0.0057522474 0.0255110000 242195402 95654136 760807424 -0.0270055253 0.2980920970 -0.1884164661 1708 1311867227.4141440392 0.0816971287 0.0564654924 0.0821182579 0.0057544872 0.0291770000 242198818 95654136 760807424 -0.0261633378 0.2991435826 -0.1876615882 1709 1311867227.4479200840 0.0817514732 0.0564802882 0.0821182579 0.0057544786 0.0382950000 242200746 95654136 760807424 -0.0260917544 0.3011076748 -0.1883268505 1710 1311867227.4818758965 0.0817433670 0.0564950619 0.0821182579 0.0057530678 0.0264970000 242204330 95654136 760807424 -0.0269526597 0.3011159003 -0.1881665587 1711 1311867227.5169329643 0.0819595829 0.0565099448 0.0821182579 0.0057523095 0.0264230000 242208002 95654136 760807424 -0.0276525505 0.3020276427 -0.1884739846 1712 1311867227.5501220226 0.0812920555 0.0565244203 0.0821182579 0.0057508160 0.0265850000 242209730 95654136 760807424 -0.0273932703 0.3010892272 -0.1882439554 1713 1311867227.5819540024 0.0815017596 0.0565390013 0.0821182579 0.0057493136 0.0266330000 242213458 95654136 760807424 -0.0292610731 0.3014045656 -0.1880249679 1714 1311867227.6162750721 0.0810710266 0.0565533141 0.0821182579 0.0057498650 0.0263570000 242215130 95654136 760807424 -0.0286835115 0.3021054864 -0.1884469092 1715 1311867227.6503078938 0.0818062127 0.0565680388 0.0821182579 0.0057616602 0.0266190000 242218914 95654136 760807424 -0.0289404485 0.3044749498 -0.1880694628 1716 1311867227.6823980808 0.0815866888 0.0565826184 0.0821182579 0.0057600824 0.0263980000 242222386 95654136 760807424 -0.0288466830 0.3038733006 -0.1874075830 1717 1311867227.7135930061 0.0821268037 0.0565974956 0.0821268037 0.0057608381 0.0264750000 242224146 95654136 760807424 -0.0281814076 0.3056787848 -0.1871482581 1718 1311867227.7496368885 0.0809365362 0.0566116627 0.0821268037 0.0057594525 0.0263960000 242227786 95654136 760807424 -0.0289688800 0.3058645427 -0.1874594986 1719 1311867227.7827620506 0.0822825506 0.0566265963 0.0822825506 0.0057580905 0.0264810000 242229714 95654136 760807424 -0.0295487065 0.3078387976 -0.1862290353 1720 1311867227.8141551018 0.0823478475 0.0566415506 0.0823478475 0.0057587661 0.0264660000 242233130 95654136 760807424 -0.0313868672 0.3106814623 -0.1874134690 1721 1311867227.8497691154 0.0817577913 0.0566561445 0.0823478475 0.0057631053 0.0263730000 242236914 95654136 760807424 -0.0280764699 0.3105564713 -0.1858228147 1722 1311867227.8832869530 0.0809504315 0.0566702527 0.0823478475 0.0057615035 0.0264810000 242238586 95654136 760807424 -0.0281040650 0.3106353879 -0.1858030111 1723 1311867227.9196939468 0.0802585483 0.0566839430 0.0823478475 0.0057600033 0.0266550000 242242426 95654136 760807424 -0.0279934015 0.3103975952 -0.1855279356 1724 1311867227.9516780376 0.0812997520 0.0566982213 0.0823478475 0.0057592223 0.0263780000 242245898 95654136 760807424 -0.0268068481 0.3130789697 -0.1851871163 1725 1311867227.9828588963 0.0809248313 0.0567122657 0.0823478475 0.0057577248 0.0265160000 242418686 95654136 760807424 -0.0267036483 0.3124114275 -0.1844535172 1726 1311867228.0181910992 0.0804447234 0.0567260157 0.0823478475 0.0057567947 0.0264400000 242422214 95654136 760807424 -0.0263667554 0.3136282861 -0.1844237000 1727 1311867228.0516328812 0.0808121189 0.0567399624 0.0823478475 0.0057554458 0.0264300000 242424142 95654136 760807424 -0.0256672464 0.3155181408 -0.1840140820 1728 1311867228.0825328827 0.0803719237 0.0567536384 0.0823478475 0.0057540990 0.0263900000 242427558 95654136 760807424 -0.0249385200 0.3170251846 -0.1845328659 1729 1311867228.1179840565 0.0803968683 0.0567673129 0.0823478475 0.0057532578 0.0264030000 242431286 95654136 760807424 -0.0245132875 0.3176468909 -0.1840427220 1730 1311867228.1511390209 0.0803304389 0.0567809332 0.0823478475 0.0057536559 0.0259400000 242433070 95654136 760807424 -0.0243786052 0.3185715377 -0.1842032522 1731 1311867228.1828610897 0.0805830732 0.0567946837 0.0823478475 0.0057521269 0.0255820000 242436742 95654136 760807424 -0.0242584087 0.3199882507 -0.1843938380 1732 1311867228.2179419994 0.0797140375 0.0568079166 0.0823478475 0.0057586047 0.0256320000 242438414 95654136 760807424 -0.0236226507 0.3204320669 -0.1850826740 1733 1311867228.2541251183 0.0800078809 0.0568213037 0.0823478475 0.0057653154 0.0256390000 242442254 95654136 760807424 -0.0237534512 0.3225210309 -0.1857862025 1734 1311867228.2826519012 0.0814897940 0.0568355301 0.0823478475 0.0057641935 0.0298540000 242445614 95654136 760807424 -0.0242030211 0.3252730370 -0.1852929294 1735 1311867228.3181738853 0.0831181407 0.0568506786 0.0831181407 0.0057635265 0.0299580000 242447598 95654136 760807424 -0.0249013342 0.3277631998 -0.1847154200 1736 1311867228.3504519463 0.0833403021 0.0568659376 0.0833403021 0.0057626504 0.0257130000 242451070 95654136 760807424 -0.0204221811 0.3289427459 -0.1842523068 1737 1311867228.3824779987 0.0827820972 0.0568808576 0.0833403021 0.0057612971 0.0255210000 242452998 95654136 760807424 -0.0191311184 0.3284298778 -0.1839553863 1738 1311867228.4176759720 0.0827864781 0.0568957631 0.0833403021 0.0057600628 0.0255340000 242456470 95654136 760807424 -0.0212799869 0.3305237889 -0.1851244569 1739 1311867228.4483039379 0.0825808793 0.0569105331 0.0833403021 0.0057589237 0.0259530000 242460142 95654136 760807424 -0.0215655081 0.3310667574 -0.1852968782 1740 1311867228.4835319519 0.0825135931 0.0569252475 0.0833403021 0.0057574024 0.0288810000 242461870 95654136 760807424 -0.0209393948 0.3293115199 -0.1843848228 1741 1311867228.5177900791 0.0827542096 0.0569400832 0.0833403021 0.0057578037 0.0264140000 242465598 95654136 760807424 -0.0227547232 0.3291067183 -0.1849633604 1742 1311867228.5529639721 0.0828179270 0.0569549385 0.0833403021 0.0057561951 0.0255990000 242469182 95654136 760807424 -0.0230994187 0.3281464279 -0.1852262020 1743 1311867228.5834119320 0.0825062171 0.0569695978 0.0833403021 0.0057548822 0.0298210000 242470998 95654136 760807424 -0.0243629385 0.3267211318 -0.1858555079 1744 1311867228.6168839931 0.0832180157 0.0569846485 0.0833403021 0.0057534900 0.0297620000 242474582 95654136 760807424 -0.0244950429 0.3252908587 -0.1855201125 1745 1311867228.6513540745 0.0827305391 0.0569994026 0.0833403021 0.0057519483 0.0255600000 242476454 95654136 760807424 -0.0247655045 0.3239077330 -0.1866521984 1746 1311867228.6960909367 0.0842269287 0.0570149968 0.0842269287 0.0057507171 0.0256030000 242480318 95654136 760807424 -0.0245533977 0.3225863278 -0.1864148825 1747 1311867228.7251129150 0.0835389793 0.0570301794 0.0842269287 0.0057501400 0.0256390000 242483822 95654136 760807424 -0.0255095065 0.3229179382 -0.1883760393 1748 1311867228.7533209324 0.0859044194 0.0570466979 0.0859044194 0.0057495475 0.0296070000 242485270 95654136 760807424 -0.0254530571 0.3258310258 -0.1883969605 1749 1311867228.7872729301 0.0855778232 0.0570630107 0.0859044194 0.0057546146 0.0256520000 242488718 95654136 760807424 -0.0268889926 0.3239416480 -0.1887037903 1750 1311867228.8184990883 0.0858222470 0.0570794445 0.0859044194 0.0057599853 0.0256300000 242490334 95654136 760807424 -0.0274297502 0.3220102489 -0.1887087226 1751 1311867228.8512189388 0.0867442042 0.0570963862 0.0867442042 0.0057587988 0.0256420000 242494062 95654136 760807424 -0.0284141563 0.3239996433 -0.1895275265 1752 1311867228.8835051060 0.0849235505 0.0571122692 0.0867442042 0.0057580381 0.0256960000 242497478 95654136 760807424 -0.0289004780 0.3198514581 -0.1904993206 1753 1311867228.9181449413 0.0851498842 0.0571282633 0.0867442042 0.0057564526 0.0256130000 242499462 95654136 760807424 -0.0280642789 0.3188855052 -0.1912418604 1754 1311867228.9496490955 0.0866084322 0.0571450707 0.0867442042 0.0057552983 0.0256010000 242502934 95654136 760807424 -0.0275044590 0.3215197027 -0.1923615634 1755 1311867228.9844760895 0.0848051757 0.0571608315 0.0867442042 0.0057543753 0.0256510000 242504862 95654136 760807424 -0.0284034405 0.3162114024 -0.1923825443 1756 1311867229.0238449574 0.0861994028 0.0571773682 0.0867442042 0.0057546397 0.0260240000 242508558 95654136 760807424 -0.0296694282 0.3145985603 -0.1920354515 1757 1311867229.0509281158 0.0870092288 0.0571943471 0.0870092288 0.0057532705 0.0256620000 242512118 95654136 760807424 -0.0282094516 0.3146879673 -0.1918662488 1758 1311867229.0874319077 0.0859223381 0.0572106884 0.0870092288 0.0057529338 0.0256810000 242513846 95654136 760807424 -0.0281904209 0.3128453791 -0.1929698586 1759 1311867229.1218080521 0.0858357400 0.0572269619 0.0870092288 0.0057514099 0.0256070000 242517630 95654136 760807424 -0.0306804925 0.3093004227 -0.1925823539 1760 1311867229.1517140865 0.0862827748 0.0572434708 0.0870092288 0.0057515422 0.0257270000 242521102 95654136 760807424 -0.0307590906 0.3088616431 -0.1930536330 1761 1311867229.1890540123 0.0870497897 0.0572603966 0.0870497897 0.0057509753 0.0257300000 242523086 95654136 760807424 -0.0300832968 0.3093020320 -0.1937185824 1762 1311867229.2214341164 0.0868460238 0.0572771876 0.0870497897 0.0057501955 0.0256480000 242526558 95654136 760807424 -0.0301723275 0.3062043786 -0.1931923479 1763 1311867229.2532980442 0.0861577690 0.0572935691 0.0870497897 0.0057530943 0.0257350000 242528430 95654136 760807424 -0.0305400603 0.3031948209 -0.1943003684 1764 1311867229.2841351032 0.0866566151 0.0573102148 0.0870497897 0.0057517768 0.0286900000 242531846 95654136 760807424 -0.0309800357 0.3021707833 -0.1945755780 1765 1311867229.3193020821 0.0869766921 0.0573270230 0.0870497897 0.0057540633 0.0257720000 242535630 95654136 760807424 -0.0312173888 0.3007082343 -0.1949786544 1766 1311867229.3502240181 0.0862460211 0.0573433984 0.0870497897 0.0057547621 0.0264410000 242537246 95654136 760807424 -0.0306336433 0.2971034348 -0.1952756345 1767 1311867229.3850710392 0.0872383714 0.0573603169 0.0872383714 0.0057533103 0.0261370000 242540974 95654136 760807424 -0.0305959731 0.2962795496 -0.1955360174 1768 1311867229.4180469513 0.0870055482 0.0573770846 0.0872383714 0.0057524485 0.0257680000 242542646 95654136 760807424 -0.0298348144 0.2945134044 -0.1961830556 1769 1311867229.4483740330 0.0862989575 0.0573934338 0.0872383714 0.0057508756 0.0257340000 242546262 95654136 760807424 -0.0319790915 0.2902043462 -0.1964100152 1770 1311867229.4843358994 0.0861906856 0.0574097035 0.0872383714 0.0057536481 0.0257790000 242549846 95654136 760807424 -0.0314576738 0.2876295447 -0.1963628083 1771 1311867229.5189929008 0.0860169381 0.0574258566 0.0872383714 0.0057524188 0.0260780000 242551718 95654136 760807424 -0.0325887017 0.2865109742 -0.1985359639 1772 1311867229.5504579544 0.0854828656 0.0574416902 0.0872383714 0.0057508613 0.0368440000 242555190 95654136 760807424 -0.0334604941 0.2820718884 -0.1978623718 1773 1311867229.5853381157 0.0847417191 0.0574570878 0.0872383714 0.0057503017 0.0425680000 242557118 95654136 760807424 -0.0327047892 0.2816450894 -0.1998381019 1774 1311867229.6182799339 0.0849016011 0.0574725582 0.0872383714 0.0057489507 0.0263250000 242560590 95654136 760807424 -0.0316034928 0.2797870338 -0.1996985227 1775 1311867229.6503160000 0.0852978006 0.0574882344 0.0872383714 0.0057480030 0.0261910000 242564318 95654136 760807424 -0.0328964554 0.2780291438 -0.1998226792 1776 1311867229.6876978874 0.0849794969 0.0575037137 0.0872383714 0.0057471134 0.0258280000 242566102 95654136 760807424 -0.0335821509 0.2770642340 -0.2010480762 1777 1311867229.7184219360 0.0874386504 0.0575205595 0.0874386504 0.0057484024 0.0257020000 242569718 95654136 760807424 -0.0346410833 0.2803089023 -0.2020828873 1778 1311867229.7500000000 0.0859738812 0.0575365625 0.0874386504 0.0057470982 0.0273560000 242573190 95654136 760807424 -0.0345522910 0.2756597102 -0.2016089857 1779 1311867229.7854330540 0.0870035365 0.0575531263 0.0874386504 0.0057460494 0.0299490000 242575174 95654136 760807424 -0.0356667116 0.2749786377 -0.2017881423 1780 1311867229.8184831142 0.0866509974 0.0575694734 0.0874386504 0.0057451898 0.0257140000 242578646 95654136 760807424 -0.0330942534 0.2732292414 -0.2020253986 1781 1311867229.8494279385 0.0872557312 0.0575861417 0.0874386504 0.0057437987 0.0256880000 242580518 95654136 760807424 -0.0329297297 0.2719812989 -0.2016569376 1782 1311867229.8853340149 0.0873483717 0.0576028433 0.0874386504 0.0057426216 0.0290200000 242584102 95654136 760807424 -0.0339053608 0.2694821060 -0.2017264962 1783 1311867229.9183139801 0.0875933766 0.0576196636 0.0875933766 0.0057424964 0.0257670000 242587774 95654136 760807424 -0.0352429599 0.2689978182 -0.2029287517 1784 1311867229.9534161091 0.0867659599 0.0576360012 0.0875933766 0.0057449123 0.0289390000 242589558 95654136 760807424 -0.0354629755 0.2654477656 -0.2031974196 1785 1311867229.9877750874 0.0853889436 0.0576515490 0.0875933766 0.0057435023 0.0257910000 242593342 95654136 760807424 -0.0355243012 0.2608057857 -0.2034173757 1786 1311867230.0194880962 0.0851862803 0.0576669660 0.0875933766 0.0057419641 0.0348230000 242594958 95654136 760807424 -0.0360527933 0.2596689761 -0.2049121559 1787 1311867230.0512609482 0.0854550973 0.0576825162 0.0875933766 0.0057404613 0.0258950000 242598686 95654136 760807424 -0.0362875946 0.2601813972 -0.2066413015 1788 1311867230.0876040459 0.0852918252 0.0576979576 0.0875933766 0.0057393253 0.0257210000 242602158 95654136 760807424 -0.0359490961 0.2561681569 -0.2060240358 1789 1311867230.1212029457 0.0844503418 0.0577129114 0.0875933766 0.0057382636 0.0258260000 242604198 95654136 760807424 -0.0378283672 0.2530916333 -0.2069018781 1790 1311867230.1508131027 0.0847889706 0.0577280377 0.0875933766 0.0057367517 0.0295790000 242607558 95654136 760807424 -0.0367884487 0.2530080378 -0.2078683525 1791 1311867230.1872301102 0.0848524943 0.0577431826 0.0875933766 0.0057384918 0.0294900000 242609542 95654136 760807424 -0.0390065797 0.2515486777 -0.2089451104 1792 1311867230.2194790840 0.0852524862 0.0577585338 0.0875933766 0.0057469897 0.0259080000 242613014 95654136 760807424 -0.0406553820 0.2499108016 -0.2096243054 1793 1311867230.2494208813 0.0847166255 0.0577735690 0.0875933766 0.0057516650 0.0258310000 242616630 95654136 760807424 -0.0396845229 0.2487107962 -0.2104084343 1794 1311867230.2894790173 0.0860550553 0.0577893335 0.0875933766 0.0057563285 0.0380790000 242618526 95654136 760807424 -0.0388669483 0.2480923682 -0.2104500383 1795 1311867230.3189430237 0.0840568766 0.0578039672 0.0875933766 0.0057549377 0.0261310000 242622086 95654136 760807424 -0.0394487269 0.2442982346 -0.2118618637 1796 1311867230.3552010059 0.0838628560 0.0578184766 0.0875933766 0.0057541444 0.0257960000 242625726 95654136 760807424 -0.0411711559 0.2423855215 -0.2129653096 1797 1311867230.3913140297 0.0849234909 0.0578335601 0.0875933766 0.0057529145 0.0258400000 242627654 95654136 760807424 -0.0409968235 0.2421105653 -0.2130374461 1798 1311867230.4169929028 0.0843127966 0.0578482871 0.0875933766 0.0057520369 0.0298790000 242630958 95654136 760807424 -0.0397362523 0.2391099185 -0.2126367539 1799 1311867230.4538938999 0.0841395780 0.0578629015 0.0875933766 0.0057505747 0.0290910000 242632998 95654136 760807424 -0.0403537489 0.2384272367 -0.2139139473 1800 1311867230.4892110825 0.0834017470 0.0578770898 0.0875933766 0.0057622945 0.0257920000 242636526 95654136 760807424 -0.0389063321 0.2362936586 -0.2144674212 1801 1311867230.5216429234 0.0828406811 0.0578909507 0.0875933766 0.0057607627 0.0289650000 242640254 95654136 760807424 -0.0412325524 0.2348222882 -0.2156225592 1802 1311867230.5564150810 0.0833998322 0.0579051066 0.0875933766 0.0057708515 0.0291040000 242642038 95654136 760807424 -0.0415599048 0.2345499396 -0.2159953266 1803 1311867230.5930590630 0.0815897509 0.0579182428 0.0875933766 0.0057705795 0.0258470000 242645766 95654136 760807424 -0.0410926454 0.2305229753 -0.2165915370 1804 1311867230.6184151173 0.0812853351 0.0579311958 0.0875933766 0.0057690666 0.0258420000 242647214 95654136 760807424 -0.0395254456 0.2295397967 -0.2170918882 1805 1311867230.6534399986 0.0813051313 0.0579441453 0.0875933766 0.0057678005 0.0259010000 242650998 95654136 760807424 -0.0400982276 0.2285130769 -0.2176129520 1806 1311867230.6920781136 0.0810582861 0.0579569438 0.0875933766 0.0057666720 0.0258130000 242825958 95654136 760807424 -0.0408367142 0.2278159708 -0.2188242227 1807 1311867230.7185189724 0.0816624165 0.0579700625 0.0875933766 0.0057654541 0.0257570000 242827606 95654136 760807424 -0.0412436575 0.2276671380 -0.2186923176 1808 1311867230.7529120445 0.0812013894 0.0579829117 0.0875933766 0.0057639808 0.0366770000 242831190 95654136 760807424 -0.0422488451 0.2268342078 -0.2195389271 1809 1311867230.7871611118 0.0804018900 0.0579953047 0.0875933766 0.0057727502 0.0267310000 242833174 95654136 760807424 -0.0412442721 0.2246543914 -0.2185665220 1810 1311867230.8195741177 0.0813483670 0.0580082070 0.0875933766 0.0057798042 0.0259190000 242836590 95654136 760807424 -0.0425917357 0.2246310860 -0.2187797576 1811 1311867230.8534181118 0.0809822455 0.0580208928 0.0875933766 0.0057783056 0.0258690000 242840318 95654136 760807424 -0.0421167351 0.2234061658 -0.2185922265 1812 1311867230.8890159130 0.0798754767 0.0580329538 0.0875933766 0.0057772623 0.0258350000 242842102 95654136 760807424 -0.0421837457 0.2220067680 -0.2193835080 1813 1311867230.9176509380 0.0802430809 0.0580452043 0.0875933766 0.0057761956 0.0297460000 242845718 95654136 760807424 -0.0445145294 0.2229855359 -0.2202992290 1814 1311867230.9559168816 0.0802080855 0.0580574220 0.0875933766 0.0057748789 0.0277680000 242849302 95654136 760807424 -0.0438468568 0.2219679356 -0.2200048417 1815 1311867230.9881010056 0.0811212435 0.0580701293 0.0875933766 0.0057736394 0.0258200000 242851174 95654136 760807424 -0.0446496196 0.2231512964 -0.2205473930 1816 1311867231.0166280270 0.0816299617 0.0580831028 0.0875933766 0.0057723581 0.0258750000 242854590 95654136 760807424 -0.0449040085 0.2232262343 -0.2208677381 1817 1311867231.0603969097 0.0827816799 0.0580966959 0.0875933766 0.0057710500 0.0258340000 242856686 95654136 760807424 -0.0446522608 0.2231304199 -0.2206649929 1818 1311867231.0868620872 0.0832033306 0.0581105059 0.0875933766 0.0057698897 0.0259840000 242859934 95654136 760807424 -0.0455070399 0.2233353853 -0.2213689387 1819 1311867231.1221020222 0.0826548338 0.0581239992 0.0875933766 0.0057686008 0.0299470000 242863774 95654136 760807424 -0.0460327677 0.2206147313 -0.2217478007 1820 1311867231.1523799896 0.0822293013 0.0581372439 0.0875933766 0.0057715724 0.0297850000 242865334 95654136 760807424 -0.0471454337 0.2174191624 -0.2214191556 1821 1311867231.1860070229 0.0823428854 0.0581505364 0.0875933766 0.0057700698 0.0258380000 242869062 95654136 760807424 -0.0479346029 0.2179922760 -0.2234314233 1822 1311867231.2188270092 0.0824401975 0.0581638677 0.0875933766 0.0057695264 0.0258930000 242870734 95654136 760807424 -0.0484715514 0.2161225379 -0.2236159891 1823 1311867231.2522621155 0.0822721645 0.0581770922 0.0875933766 0.0057700112 0.0258310000 242874462 95654136 760807424 -0.0475389920 0.2130964547 -0.2229606956 1824 1311867231.2864110470 0.0820629150 0.0581901875 0.0875933766 0.0057703713 0.0258110000 242877990 95654136 760807424 -0.0486474596 0.2120760828 -0.2245842665 1825 1311867231.3215939999 0.0817237794 0.0582030826 0.0875933766 0.0057689456 0.0258210000 242879974 95654136 760807424 -0.0491289645 0.2104335874 -0.2252617031 1826 1311867231.3525509834 0.0815418884 0.0582158640 0.0875933766 0.0057677873 0.0258410000 242883390 95654136 760807424 -0.0490881018 0.2090490013 -0.2256196737 1827 1311867231.3874650002 0.0813277662 0.0582285142 0.0875933766 0.0057667405 0.0258470000 242885318 95654136 760807424 -0.0507567897 0.2090458274 -0.2273331732 1828 1311867231.4187040329 0.0811738521 0.0582410664 0.0875933766 0.0057652187 0.0258730000 242888790 95654136 760807424 -0.0521214902 0.2079314142 -0.2277582288 1829 1311867231.4542400837 0.0815384611 0.0582538041 0.0875933766 0.0057642037 0.0258280000 242892574 95654136 760807424 -0.0517386086 0.2067873627 -0.2268728763 1830 1311867231.4867990017 0.0816217139 0.0582665735 0.0875933766 0.0057629762 0.0259400000 242894246 95654136 760807424 -0.0508461893 0.2066246271 -0.2266794294 1831 1311867231.5193030834 0.0808544010 0.0582789098 0.0875933766 0.0057615572 0.0296600000 242897918 95654136 760807424 -0.0509137288 0.2056890875 -0.2272347957 1832 1311867231.5524148941 0.0789926425 0.0582902165 0.0875933766 0.0057617045 0.0422020000 242901390 95654136 760807424 -0.0516893119 0.2017174363 -0.2274025232 1833 1311867231.5855851173 0.0789560825 0.0583014908 0.0875933766 0.0057660274 0.0262750000 242903374 95654136 760807424 -0.0508138984 0.2011397183 -0.2270616740 1834 1311867231.6210820675 0.0794826448 0.0583130400 0.0875933766 0.0057758739 0.0259510000 242906902 95654136 760807424 -0.0503320098 0.2009739131 -0.2273369133 1835 1311867231.6522169113 0.0788103491 0.0583242101 0.0875933766 0.0057753817 0.0259450000 242908774 95654136 760807424 -0.0487922616 0.1981994510 -0.2268007398 1836 1311867231.6880500317 0.0780607462 0.0583349599 0.0875933766 0.0057745732 0.0259070000 242912358 95654136 760807424 -0.0529172011 0.1967169493 -0.2282224149 1837 1311867231.7208089828 0.0787771046 0.0583460879 0.0875933766 0.0057734936 0.0258720000 242916086 95654136 760807424 -0.0528495349 0.1973524690 -0.2287952453 1838 1311867231.7523078918 0.0786862001 0.0583571543 0.0875933766 0.0057742412 0.0258770000 242917646 95654136 760807424 -0.0529395416 0.1954823881 -0.2291075438 1839 1311867231.7860589027 0.0786955357 0.0583682138 0.0875933766 0.0057727165 0.0258720000 242921430 95654136 760807424 -0.0536359698 0.1933092922 -0.2292459011 1840 1311867231.8202130795 0.0824635327 0.0583813091 0.0875933766 0.0057758311 0.0258820000 242923158 95654136 760807424 -0.0544826202 0.1981257498 -0.2298735529 1841 1311867231.8521840572 0.0819432288 0.0583941075 0.0875933766 0.0057753361 0.0258960000 242926774 95654136 760807424 -0.0547427498 0.1953595132 -0.2300820202 1842 1311867231.8857500553 0.0809391662 0.0584063470 0.0875933766 0.0057755554 0.0259070000 242930358 95654136 760807424 -0.0516176522 0.1926649064 -0.2299683392 1843 1311867231.9208559990 0.0816075876 0.0584189358 0.0875933766 0.0057746722 0.0258980000 242932342 95654136 760807424 -0.0514291488 0.1917810887 -0.2300395519 1844 1311867231.9533181190 0.0807835907 0.0584310642 0.0875933766 0.0057732585 0.0267350000 242935758 95654136 760807424 -0.0521667153 0.1898942888 -0.2313281894 1845 1311867231.9870491028 0.0793357939 0.0584423946 0.0875933766 0.0057721296 0.0259440000 242937686 95654136 760807424 -0.0530890375 0.1854968965 -0.2317116708 1846 1311867232.0202860832 0.0797115788 0.0584539164 0.0875933766 0.0057708721 0.0258770000 242941214 95654136 760807424 -0.0519241840 0.1839683503 -0.2314418554 1847 1311867232.0522420406 0.0791565850 0.0584651252 0.0875933766 0.0057694085 0.0258660000 242944886 95654136 760807424 -0.0511041172 0.1835257560 -0.2328263670 1848 1311867232.0878489017 0.0793235227 0.0584764122 0.0875933766 0.0057679597 0.0259470000 242946670 95654136 760807424 -0.0523983650 0.1822351962 -0.2332902253 1849 1311867232.1203238964 0.0796632394 0.0584878708 0.0875933766 0.0057685886 0.0259300000 243121222 95654136 760807424 -0.0526514202 0.1808144897 -0.2334582955 1850 1311867232.1545510292 0.0797886178 0.0584993847 0.0875933766 0.0057680930 0.0309490000 243124750 95654136 760807424 -0.0514280051 0.1813743860 -0.2343305498 1851 1311867232.1846179962 0.0778362826 0.0585098314 0.0875933766 0.0057680049 0.0259670000 243126566 95654136 760807424 -0.0517169721 0.1769242436 -0.2347175032 1852 1311867232.2209780216 0.0767680928 0.0585196901 0.0875933766 0.0057670365 0.0259090000 243130150 95654136 760807424 -0.0518965907 0.1735918075 -0.2351621687 1853 1311867232.2531120777 0.0767429397 0.0585295245 0.0875933766 0.0057658412 0.0259180000 243131966 95654136 760807424 -0.0533668287 0.1740508229 -0.2369548380 1854 1311867232.2844479084 0.0766481012 0.0585392972 0.0875933766 0.0057646000 0.0259680000 243135494 95654136 760807424 -0.0554127693 0.1715043336 -0.2368969470 1855 1311867232.3209791183 0.0790550560 0.0585503569 0.0875933766 0.0057646616 0.0259130000 243139278 95654136 760807424 -0.0561479516 0.1747003943 -0.2376095802 1856 1311867232.3544659615 0.0817547739 0.0585628593 0.0875933766 0.0057636206 0.0259620000 243140950 95654136 760807424 -0.0560474843 0.1783350855 -0.2381767482 1857 1311867232.3858909607 0.0811886862 0.0585750434 0.0875933766 0.0057621850 0.0261240000 243144622 95654136 760807424 -0.0555749126 0.1754802316 -0.2378834933 1858 1311867232.4203910828 0.0793998018 0.0585862516 0.0875933766 0.0057613060 0.0375680000 243146350 95654136 760807424 -0.0534672625 0.1723819971 -0.2383044958 1859 1311867232.4544560909 0.0797165707 0.0585976180 0.0875933766 0.0057599209 0.0261690000 243150078 95654136 760807424 -0.0538767278 0.1726063639 -0.2390702069 1860 1311867232.4846010208 0.0774123445 0.0586077335 0.0875933766 0.0057648810 0.0260060000 243153494 95654136 760807424 -0.0531195551 0.1686369181 -0.2387048304 1861 1311867232.5203030109 0.0776078552 0.0586179431 0.0875933766 0.0057647935 0.0261640000 243155478 95654136 760807424 -0.0541068539 0.1685918272 -0.2401639968 1862 1311867232.5550050735 0.0793492272 0.0586290770 0.0875933766 0.0057652084 0.0259880000 243159006 95654136 760807424 -0.0535581820 0.1723454744 -0.2409649193 1863 1311867232.5844318867 0.0776617676 0.0586392932 0.0875933766 0.0057660286 0.0259260000 243160766 95654136 760807424 -0.0522523634 0.1679977477 -0.2407469302 1864 1311867232.6201601028 0.0780702457 0.0586497175 0.0875933766 0.0057648875 0.0259890000 243164350 95654136 760807424 -0.0518648103 0.1665432304 -0.2402134240 1865 1311867232.6554861069 0.0794533417 0.0586608722 0.0875933766 0.0057649149 0.0260650000 243167966 95654136 760807424 -0.0523518845 0.1689615399 -0.2416621149 1866 1311867232.6850490570 0.0788803324 0.0586717080 0.0875933766 0.0057640136 0.0258910000 243169582 95654136 760807424 -0.0540894121 0.1655102968 -0.2412661612 1867 1311867232.7210319042 0.0780283064 0.0586820757 0.0875933766 0.0057625843 0.0259150000 243173366 95654136 760807424 -0.0539918877 0.1623640358 -0.2411928773 1868 1311867232.7539520264 0.0800680220 0.0586935243 0.0875933766 0.0057617795 0.0268510000 243176782 95654136 760807424 -0.0513076074 0.1655082554 -0.2416640818 1869 1311867232.7885808945 0.0798712447 0.0587048553 0.0875933766 0.0057605283 0.0260920000 243178710 95654136 760807424 -0.0523209609 0.1629204452 -0.2416374981 1870 1311867232.8206169605 0.0791649893 0.0587157966 0.0875933766 0.0057596092 0.0259270000 243182238 95654136 760807424 -0.0519543737 0.1588239521 -0.2407125533 1871 1311867232.8539369106 0.0797459856 0.0587270367 0.0875933766 0.0057590510 0.0260620000 243355878 95654136 760807424 -0.0531257167 0.1588839144 -0.2417624146 1872 1311867232.8882710934 0.0787027255 0.0587377074 0.0875933766 0.0057577267 0.0296700000 243359406 95654136 760807424 -0.0535830930 0.1551078111 -0.2416932732 1873 1311867232.9203770161 0.0781672448 0.0587480809 0.0875933766 0.0057570393 0.0341230000 243363134 95654136 760807424 -0.0521234013 0.1523045301 -0.2414446175 1874 1311867232.9559900761 0.0783329681 0.0587585318 0.0875933766 0.0057555596 0.0260100000 243364918 95654136 760807424 -0.0523294136 0.1516490579 -0.2424179465 1875 1311867232.9890038967 0.0801115260 0.0587699200 0.0875933766 0.0057551331 0.0258990000 243368534 95654136 760807424 -0.0527369007 0.1534391791 -0.2430090010 1876 1311867233.0212259293 0.0801479220 0.0587813156 0.0875933766 0.0057539133 0.0293810000 243370262 95654136 760807424 -0.0511368141 0.1515767276 -0.2420955747 1877 1311867233.0569291115 0.0803389773 0.0587928007 0.0875933766 0.0057536125 0.0293110000 243373990 95654136 760807424 -0.0513805114 0.1514783055 -0.2428110242 1878 1311867233.0943200588 0.0818475112 0.0588050769 0.0875933766 0.0057526050 0.0259130000 243377630 95654136 760807424 -0.0506949723 0.1535223424 -0.2434540987 1879 1311867233.1241600513 0.0793716162 0.0588160224 0.0875933766 0.0057529567 0.0260250000 243379334 95654136 760807424 -0.0515665673 0.1486004144 -0.2435140759 1880 1311867233.1530799866 0.0796316788 0.0588270946 0.0875933766 0.0057523281 0.0262820000 243382694 95654136 760807424 -0.0511280671 0.1477009505 -0.2429654896 1881 1311867233.1887679100 0.0802432150 0.0588384801 0.0875933766 0.0057528428 0.0302280000 243384678 95654136 760807424 -0.0518477075 0.1475145817 -0.2435734868 1882 1311867233.2210481167 0.0800452456 0.0588497483 0.0875933766 0.0057514386 0.0259690000 243388150 95654136 760807424 -0.0513036922 0.1458971500 -0.2432809025 1883 1311867233.2590179443 0.0806950852 0.0588613496 0.0875933766 0.0057502060 0.0259620000 243391990 95654136 760807424 -0.0513302162 0.1437653899 -0.2423831522 1884 1311867233.2899589539 0.0812849179 0.0588732517 0.0875933766 0.0057487657 0.0259330000 243393662 95654136 760807424 -0.0508068800 0.1440460831 -0.2425533831 1885 1311867233.3212211132 0.0800653771 0.0588844942 0.0875933766 0.0057490812 0.0259780000 243397334 95654136 760807424 -0.0506704152 0.1410001367 -0.2423363328 1886 1311867233.3533849716 0.0800681040 0.0588957263 0.0875933766 0.0057485590 0.0259830000 243400750 95654136 760807424 -0.0518127307 0.1373510808 -0.2414497435 1887 1311867233.3884561062 0.0807184428 0.0589072910 0.0875933766 0.0057498973 0.0266310000 243572550 95654136 760807424 -0.0517390445 0.1377159357 -0.2426533252 1888 1311867233.4236669540 0.0806422830 0.0589188032 0.0875933766 0.0057533704 0.0269710000 243576078 95654136 760807424 -0.0537295230 0.1361015290 -0.2431548983 1889 1311867233.4522700310 0.0797546208 0.0589298333 0.0875933766 0.0057548521 0.0267140000 243577950 95654136 760807424 -0.0530496053 0.1317782551 -0.2422807962 1890 1311867233.4881610870 0.0799657777 0.0589409634 0.0875933766 0.0057598348 0.0267180000 243581422 95654136 760807424 -0.0544501022 0.1313295662 -0.2434488088 1891 1311867233.5201199055 0.0803698525 0.0589522955 0.0875933766 0.0057599512 0.0269150000 243585150 95654136 760807424 -0.0556188859 0.1309293658 -0.2442728430 1892 1311867233.5526270866 0.0792007819 0.0589629976 0.0875933766 0.0057597566 0.0268650000 243586822 95654136 760807424 -0.0540830046 0.1278310865 -0.2436489463 1893 1311867233.5890851021 0.0789748654 0.0589735691 0.0875933766 0.0057583419 0.0267990000 243590606 95654136 760807424 -0.0536963642 0.1271917820 -0.2441055775 1894 1311867233.6202619076 0.0788741708 0.0589840763 0.0875933766 0.0057568865 0.0269560000 243592278 95654136 760807424 -0.0528616980 0.1260989159 -0.2438479811 1895 1311867233.6539080143 0.0789400637 0.0589946072 0.0875933766 0.0057566304 0.0268290000 243595950 95654136 760807424 -0.0525534190 0.1242566854 -0.2429613620 1896 1311867233.6879289150 0.0775282159 0.0590043823 0.0875933766 0.0057552575 0.0268110000 243599478 95654136 760807424 -0.0522492006 0.1224918291 -0.2437729686 1897 1311867233.7197790146 0.0772881359 0.0590140205 0.0875933766 0.0057542125 0.0268980000 243601406 95654136 760807424 -0.0522247180 0.1220551059 -0.2442999929 1898 1311867233.7577540874 0.0769803375 0.0590234864 0.0875933766 0.0057528198 0.0269350000 243605046 95654136 760807424 -0.0518957153 0.1201347038 -0.2435679287 1899 1311867233.7896089554 0.0752171502 0.0590320139 0.0875933766 0.0057531290 0.0268280000 243606918 95654136 760807424 -0.0532593392 0.1169598997 -0.2442171574 1900 1311867233.8221189976 0.0756791979 0.0590407756 0.0875933766 0.0057532536 0.0268520000 243610446 95654136 760807424 -0.0521459058 0.1182080880 -0.2448797077 1901 1311867233.8562450409 0.0749550387 0.0590491471 0.0875933766 0.0057520655 0.0268560000 243614118 95654136 760807424 -0.0507105365 0.1156551987 -0.2441318333 1902 1311867233.8885691166 0.0747824609 0.0590574191 0.0875933766 0.0057513743 0.0267970000 243615790 95654136 760807424 -0.0527550131 0.1137958169 -0.2441557199 1903 1311867233.9203450680 0.0750198513 0.0590658071 0.0875933766 0.0057500020 0.0268420000 243789886 95654136 760807424 -0.0535971150 0.1139984354 -0.2446716875 1904 1311867233.9552910328 0.0758464783 0.0590746205 0.0875933766 0.0057485044 0.0268600000 243793470 95654136 760807424 -0.0535127297 0.1129160821 -0.2435472161 1905 1311867233.9885900021 0.0746343061 0.0590827883 0.0875933766 0.0057470539 0.0375780000 243795342 95654136 760807424 -0.0548322797 0.1109050885 -0.2445490956 1906 1311867234.0205829144 0.0741468295 0.0590906918 0.0875933766 0.0057459550 0.0262430000 243798814 95654136 760807424 -0.0542833023 0.1108401343 -0.2457045466 1907 1311867234.0566239357 0.0734057948 0.0590981984 0.0875933766 0.0057448481 0.0262630000 243800854 95654136 760807424 -0.0533979535 0.1077008396 -0.2450017631 1908 1311867234.0907170773 0.0717896894 0.0591048501 0.0875933766 0.0057439292 0.0259930000 243804326 95654136 760807424 -0.0542525612 0.1042073742 -0.2456099838 1909 1311867234.1214520931 0.0715525672 0.0591113707 0.0875933766 0.0057425936 0.0259790000 243807998 95654136 760807424 -0.0541394167 0.1031125337 -0.2459690869 1910 1311867234.1561689377 0.0727426857 0.0591185075 0.0875933766 0.0057414490 0.0260470000 243809726 95654136 760807424 -0.0561442040 0.1020673215 -0.2455441952 1911 1311867234.1892559528 0.0723344386 0.0591254232 0.0875933766 0.0057400401 0.0259460000 243813398 95654136 760807424 -0.0580500662 0.0997959152 -0.2458499968 1912 1311867234.2203600407 0.0726096779 0.0591324757 0.0875933766 0.0057401618 0.0291870000 243815070 95654136 760807424 -0.0587778240 0.0997108072 -0.2468509078 1913 1311867234.2588930130 0.0728303716 0.0591396361 0.0875933766 0.0057394444 0.0260090000 243818910 95654136 760807424 -0.0581419840 0.0990325883 -0.2466637194 1914 1311867234.2895319462 0.0714998394 0.0591460939 0.0875933766 0.0057380254 0.0259090000 243822382 95654136 760807424 -0.0595111325 0.0963597521 -0.2469396293 1915 1311867234.3213200569 0.0721697360 0.0591528947 0.0875933766 0.0057391046 0.0308680000 243824254 95654136 760807424 -0.0589153245 0.0972402468 -0.2465909719 1916 1311867234.3570129871 0.0720393062 0.0591596204 0.0875933766 0.0057376938 0.0260690000 243827782 95654136 760807424 -0.0592460893 0.0965259969 -0.2464125603 1917 1311867234.3885769844 0.0713254660 0.0591659667 0.0875933766 0.0057368160 0.0263670000 243829654 95654136 760807424 -0.0590894744 0.0938178748 -0.2451962829 1918 1311867234.4204909801 0.0716419592 0.0591724714 0.0875933766 0.0057353420 0.0260440000 243833182 95654136 760807424 -0.0594786257 0.0940704271 -0.2452275157 1919 1311867234.4579920769 0.0731983408 0.0591797803 0.0875933766 0.0057351388 0.0262240000 243836910 95654136 760807424 -0.0618269704 0.0972118974 -0.2466730475 1920 1311867234.4878959656 0.0732592940 0.0591871134 0.0875933766 0.0057386527 0.0405190000 243838582 95654136 760807424 -0.0626717582 0.0946656764 -0.2451846600 1921 1311867234.5201239586 0.0722884163 0.0591939335 0.0875933766 0.0057373772 0.0264350000 243842254 95654136 760807424 -0.0629938468 0.0920347795 -0.2448667437 1922 1311867234.5594279766 0.0730990916 0.0592011682 0.0875933766 0.0057368083 0.0260070000 243845950 95654136 760807424 -0.0623758473 0.0933895782 -0.2452540696 1923 1311867234.5882380009 0.0738890991 0.0592088062 0.0875933766 0.0057357795 0.0261280000 243847766 95654136 760807424 -0.0641254932 0.0926975682 -0.2441744208 1924 1311867234.6204199791 0.0737351328 0.0592163563 0.0875933766 0.0057343349 0.0260460000 243851238 95654136 760807424 -0.0638473257 0.0908159614 -0.2431839257 1925 1311867234.6590909958 0.0736972764 0.0592238788 0.0875933766 0.0057335505 0.0260370000 243853278 95654136 760807424 -0.0638902858 0.0917868912 -0.2437967807 1926 1311867234.6880459785 0.0728855729 0.0592309721 0.0875933766 0.0057325785 0.0259940000 243856638 95654136 760807424 -0.0636089444 0.0905595645 -0.2436001599 1927 1311867234.7198779583 0.0731499270 0.0592381953 0.0875933766 0.0057320340 0.0296830000 244031450 95654136 760807424 -0.0635177717 0.0891658142 -0.2420755774 1928 1311867234.7586181164 0.0729086846 0.0592452858 0.0875933766 0.0057305653 0.0260400000 244033234 95654136 760807424 -0.0625678226 0.0899091363 -0.2419197857 1929 1311867234.7882609367 0.0728617311 0.0592523446 0.0875933766 0.0057370009 0.0260720000 244036906 95654136 760807424 -0.0625400171 0.0904389396 -0.2411742359 1930 1311867234.8206560612 0.0719591677 0.0592589284 0.0875933766 0.0057356553 0.0260290000 244038578 95654136 760807424 -0.0618468113 0.0882640108 -0.2391715646 1931 1311867234.8590250015 0.0727311522 0.0592659052 0.0875933766 0.0057348296 0.0300940000 244042362 95654136 760807424 -0.0622395873 0.0907181725 -0.2395604551 1932 1311867234.8881230354 0.0733168945 0.0592731780 0.0875933766 0.0057337240 0.0259920000 244045778 95654136 760807424 -0.0617204383 0.0913783312 -0.2386339158 1933 1311867234.9204928875 0.0731037632 0.0592803330 0.0875933766 0.0057325878 0.0260390000 244047706 95654136 760807424 -0.0614886321 0.0893312842 -0.2368673384 1934 1311867234.9566090107 0.0736610070 0.0592877687 0.0875933766 0.0057311453 0.0298500000 244051290 95654136 760807424 -0.0608746670 0.0894017816 -0.2362948954 1935 1311867234.9904088974 0.0747723952 0.0592957711 0.0875933766 0.0057299157 0.0300430000 244053218 95654136 760807424 -0.0609712154 0.0908990651 -0.2366960496 1936 1311867235.0205988884 0.0747363418 0.0593037466 0.0875933766 0.0057285862 0.0261510000 244056634 95654136 760807424 -0.0617461763 0.0882284567 -0.2356959581 1937 1311867235.0563809872 0.0731522143 0.0593108960 0.0875933766 0.0057284153 0.0297110000 244060418 95654136 760807424 -0.0622067973 0.0850620642 -0.2361227572 1938 1311867235.0911149979 0.0733260661 0.0593181278 0.0875933766 0.0057269798 0.0264770000 244062146 95654136 760807424 -0.0619779900 0.0852840766 -0.2366305739 1939 1311867235.1208140850 0.0728168711 0.0593250895 0.0875933766 0.0057255985 0.0262370000 244065818 95654136 760807424 -0.0628790930 0.0836525261 -0.2368271947 1940 1311867235.1564071178 0.0735422000 0.0593324179 0.0875933766 0.0057250923 0.0260530000 244069346 95654136 760807424 -0.0633441433 0.0856634229 -0.2375654727 1941 1311867235.1885681152 0.0728225112 0.0593393680 0.0875933766 0.0057244508 0.0259660000 244071218 95654136 760807424 -0.0623090491 0.0835165530 -0.2363728434 1942 1311867235.2202088833 0.0712693334 0.0593455111 0.0875933766 0.0057237329 0.0298330000 244074690 95654136 760807424 -0.0628741533 0.0799652338 -0.2355977893 1943 1311867235.2576260567 0.0723715276 0.0593522152 0.0875933766 0.0057229402 0.0293350000 244076562 95654136 760807424 -0.0623891242 0.0822136998 -0.2360703796 1944 1311867235.2899661064 0.0715885758 0.0593585096 0.0875933766 0.0057230999 0.0268310000 244080090 95654136 760807424 -0.0633248985 0.0800611377 -0.2352650166 1945 1311867235.3247830868 0.0723242462 0.0593651758 0.0875933766 0.0057223060 0.0270670000 244083874 95654136 760807424 -0.0663558468 0.0806199089 -0.2355181426 1946 1311867235.3567800522 0.0717053860 0.0593715171 0.0875933766 0.0057339227 0.0270120000 244085546 95654136 760807424 -0.0635007322 0.0802045241 -0.2347980142 1947 1311867235.3886280060 0.0707702711 0.0593773717 0.0875933766 0.0057434061 0.0270810000 244089218 95654136 760807424 -0.0626961589 0.0784878433 -0.2343960702 1948 1311867235.4246189594 0.0712485537 0.0593834657 0.0875933766 0.0057422589 0.0271300000 244091002 95654136 760807424 -0.0676178187 0.0797548518 -0.2352007627 1949 1311867235.4564850330 0.0732964352 0.0593906042 0.0875933766 0.0057417746 0.0272750000 244094674 95654136 760807424 -0.0676157176 0.0833118483 -0.2348758280 1950 1311867235.4897930622 0.0727935657 0.0593974775 0.0875933766 0.0057418031 0.0271240000 244098146 95654136 760807424 -0.0679888874 0.0828359202 -0.2339342535 1951 1311867235.5240719318 0.0707546696 0.0594032987 0.0875933766 0.0057413457 0.0365840000 244100074 95654136 760807424 -0.0677240565 0.0791648552 -0.2325456291 1952 1311867235.5577290058 0.0722063854 0.0594098577 0.0875933766 0.0057410652 0.0263750000 244103546 95654136 760807424 -0.0663962811 0.0823274627 -0.2320879400 1953 1311867235.5880639553 0.0706295818 0.0594156026 0.0875933766 0.0057398232 0.0261370000 244105418 95654136 760807424 -0.0663787574 0.0797051191 -0.2314817458 1954 1311867235.6249940395 0.0691572800 0.0594205881 0.0875933766 0.0057393413 0.0260500000 244109058 95654136 760807424 -0.0659285560 0.0754200071 -0.2300823927 1955 1311867235.6563270092 0.0709958151 0.0594265089 0.0875933766 0.0057397674 0.0260910000 244112674 95654136 760807424 -0.0663150325 0.0787218660 -0.2303947210 1956 1311867235.6885619164 0.0700702220 0.0594319505 0.0875933766 0.0057388456 0.0261040000 244114346 95654136 760807424 -0.0682324022 0.0754404068 -0.2296249866 1957 1311867235.7241950035 0.0699990317 0.0594373501 0.0875933766 0.0057378021 0.0261840000 244118130 95654136 760807424 -0.0688397288 0.0750383958 -0.2294964641 1958 1311867235.7561719418 0.0715767890 0.0594435500 0.0875933766 0.0057368931 0.0303020000 244292098 95654136 760807424 -0.0674755499 0.0789724365 -0.2297900617 1959 1311867235.7903280258 0.0693203658 0.0594485918 0.0875933766 0.0057380255 0.0261300000 244293970 95654136 760807424 -0.0672163442 0.0741217583 -0.2284474224 1960 1311867235.8249480724 0.0677641481 0.0594528344 0.0875933766 0.0057368620 0.0261840000 244297498 95654136 760807424 -0.0671669915 0.0711430237 -0.2276831120 1961 1311867235.8562169075 0.0700592324 0.0594582431 0.0875933766 0.0057380605 0.0261810000 244299426 95654136 760807424 -0.0667716265 0.0761148930 -0.2276075184 1962 1311867235.8881049156 0.0692605376 0.0594632392 0.0875933766 0.0057368026 0.0262560000 244302786 95654136 760807424 -0.0681654513 0.0731316954 -0.2258266956 1963 1311867235.9239900112 0.0687932447 0.0594679921 0.0875933766 0.0057355157 0.0265210000 244306626 95654136 760807424 -0.0670430213 0.0723761469 -0.2248738557 1964 1311867235.9563760757 0.0695584044 0.0594731298 0.0875933766 0.0057352519 0.0262600000 244308354 95654136 760807424 -0.0683513209 0.0742070302 -0.2251598537 1965 1311867235.9890949726 0.0682615861 0.0594776023 0.0875933766 0.0057351422 0.0262370000 244311970 95654136 760807424 -0.0691891164 0.0715419948 -0.2243946195 1966 1311867236.0250449181 0.0685244501 0.0594822039 0.0875933766 0.0057338115 0.0262440000 244313754 95654136 760807424 -0.0695355088 0.0721145719 -0.2240281701 1967 1311867236.0599400997 0.0697021559 0.0594873996 0.0875933766 0.0057327446 0.0382920000 244317482 95654136 760807424 -0.0706627890 0.0745588094 -0.2237542719 1968 1311867236.0884859562 0.0687095150 0.0594920857 0.0875933766 0.0057322189 0.0264480000 244320842 95654136 760807424 -0.0696716532 0.0721877441 -0.2220593840 1969 1311867236.1247038841 0.0693891123 0.0594971121 0.0875933766 0.0057314702 0.0261960000 244322882 95654136 760807424 -0.0715989545 0.0728883818 -0.2211569697 1970 1311867236.1581289768 0.0700695291 0.0595024788 0.0875933766 0.0057310983 0.0263450000 244326354 95654136 760807424 -0.0719373226 0.0728746429 -0.2194658071 1971 1311867236.1901528835 0.0690338239 0.0595073146 0.0875933766 0.0057302787 0.0263320000 244328170 95654136 760807424 -0.0709853843 0.0727223381 -0.2188279182 1972 1311867236.2242329121 0.0687261894 0.0595119895 0.0875933766 0.0057288665 0.0262520000 244331698 95654136 760807424 -0.0734081045 0.0721973404 -0.2179539800 1973 1311867236.2599489689 0.0690530166 0.0595168253 0.0875933766 0.0057274847 0.0265720000 244335482 95654136 760807424 -0.0743242502 0.0729967356 -0.2167626619 1974 1311867236.2890419960 0.0695860162 0.0595219262 0.0875933766 0.0057264907 0.0300690000 244337042 95654136 760807424 -0.0760912895 0.0738208219 -0.2161970735 1975 1311867236.3262441158 0.0696364120 0.0595270474 0.0875933766 0.0057255209 0.0302780000 244340882 95654136 760807424 -0.0770970136 0.0740174800 -0.2152727097 1976 1311867236.3568809032 0.0697392747 0.0595322156 0.0875933766 0.0057249142 0.0263170000 244344354 95654136 760807424 -0.0771991536 0.0736537650 -0.2140404582 1977 1311867236.3897418976 0.0705847964 0.0595378061 0.0875933766 0.0057236251 0.0262880000 244346226 95654136 760807424 -0.0785804614 0.0736667737 -0.2121138424 1978 1311867236.4243390560 0.0712808594 0.0595437430 0.0875933766 0.0057239797 0.0262810000 244349754 95654136 760807424 -0.0786796361 0.0754986256 -0.2109157890 1979 1311867236.4566040039 0.0708307773 0.0595494464 0.0875933766 0.0057231398 0.0262830000 244351682 95654136 760807424 -0.0782340616 0.0740685016 -0.2088320702 1980 1311867236.4936130047 0.0708875582 0.0595551727 0.0875933766 0.0057274073 0.0264060000 244355266 95654136 760807424 -0.0797628090 0.0722595155 -0.2066308856 1981 1311867236.5246999264 0.0714771971 0.0595611909 0.0875933766 0.0057262464 0.0262880000 244358938 95654136 760807424 -0.0798551813 0.0731974691 -0.2051551342 1982 1311867236.5602099895 0.0712927654 0.0595671099 0.0875933766 0.0057276021 0.0331810000 244360722 95654136 760807424 -0.0788710415 0.0745123252 -0.2044455260 1983 1311867236.5972909927 0.0695924312 0.0595721656 0.0875933766 0.0057268432 0.0263640000 244364506 95654136 760807424 -0.0791266933 0.0715006292 -0.2026656568 1984 1311867236.6246581078 0.0701157898 0.0595774799 0.0875933766 0.0057254491 0.0263030000 244366010 95654136 760807424 -0.0791234151 0.0713297725 -0.2005013973 1985 1311867236.6600480080 0.0702481419 0.0595828556 0.0875933766 0.0057241548 0.0268770000 244369794 95654136 760807424 -0.0795024708 0.0729352459 -0.1996027529 1986 1311867236.6956660748 0.0715096667 0.0595888610 0.0875933766 0.0057249113 0.0266080000 244373378 95654136 760807424 -0.0783396587 0.0741661862 -0.1961764097 1987 1311867236.7276370525 0.0698736086 0.0595940370 0.0875933766 0.0057244629 0.0263840000 244375194 95654136 760807424 -0.0788664892 0.0714142695 -0.1942221224 1988 1311867236.7619268894 0.0701760501 0.0595993600 0.0875933766 0.0057235274 0.0264050000 244378722 95654136 760807424 -0.0778630748 0.0715847090 -0.1914807558 1989 1311867236.7923469543 0.0701050386 0.0596046418 0.0875933766 0.0057243291 0.0263800000 244380538 95654136 760807424 -0.0767815113 0.0717478171 -0.1899194866 1990 1311867236.8255391121 0.0707941204 0.0596102647 0.0875933766 0.0057233664 0.0359330000 244384122 95654136 760807424 -0.0773176849 0.0717204884 -0.1870406270 1991 1311867236.8583440781 0.0704747289 0.0596157215 0.0875933766 0.0057231562 0.0265560000 244387738 95654136 760807424 -0.0771313608 0.0716506168 -0.1855820566 1992 1311867236.8928480148 0.0703213140 0.0596210958 0.0875933766 0.0057230070 0.0265010000 244389466 95654136 760807424 -0.0770613328 0.0712831095 -0.1834196448 1993 1311867236.9255330563 0.0697862878 0.0596261962 0.0875933766 0.0057218562 0.0265400000 244393138 95654136 760807424 -0.0773366243 0.0690572709 -0.1805852354 1994 1311867236.9581959248 0.0709174275 0.0596318588 0.0875933766 0.0057207666 0.0264930000 244396610 95654136 760807424 -0.0787249058 0.0704635903 -0.1788005233 1995 1311867236.9937291145 0.0709773526 0.0596375458 0.0875933766 0.0057238022 0.0264580000 244398594 95654136 760807424 -0.0790450051 0.0725348964 -0.1772708446 1996 1311867237.0244200230 0.0695238635 0.0596424989 0.0875933766 0.0057299437 0.0350070000 244585094 95654136 760807424 -0.0731871650 0.0703604221 -0.1737314761 1997 1311867237.0603060722 0.0668932050 0.0596461297 0.0875933766 0.0057348323 0.0278690000 244587078 95654136 760807424 -0.0777401775 0.0697323531 -0.1750632524 1998 1311867237.0927588940 0.0671842471 0.0596499025 0.0875933766 0.0057479437 0.0278510000 244590606 95654136 760807424 -0.0776228309 0.0719790235 -0.1741393954 1999 1311867237.1276650429 0.0644368380 0.0596522972 0.0875933766 0.0057498276 0.0278970000 244594334 95654136 760807424 -0.0800637305 0.0663439035 -0.1718329340 2000 1311867237.1566579342 0.0647696406 0.0596548558 0.0875933766 0.0057498193 0.0278780000 244595894 95654136 760807424 -0.0797546282 0.0671162158 -0.1700539887 2001 1311867237.1925950050 0.0667612255 0.0596584072 0.0875933766 0.0057504841 0.0279470000 244599678 95654136 760807424 -0.0795341432 0.0701846182 -0.1676617414 2002 1311867237.2254281044 0.0657229722 0.0596614365 0.0875933766 0.0057495223 0.0279570000 244601406 95654136 760807424 -0.0818350166 0.0658980682 -0.1652232707 2003 1311867237.2569580078 0.0648509637 0.0596640274 0.0875933766 0.0057493027 0.0317250000 244605078 95654136 760807424 -0.0819031373 0.0649970993 -0.1641105115 2004 1311867237.2944281101 0.0659648180 0.0596671715 0.0875933766 0.0057483807 0.0279260000 244608662 95654136 760807424 -0.0826244578 0.0679877624 -0.1632620990 2005 1311867237.3250501156 0.0660288036 0.0596703444 0.0875933766 0.0057469806 0.0280180000 244610534 95654136 760807424 -0.0836517513 0.0668208599 -0.1611942053 2006 1311867237.3565309048 0.0656752065 0.0596733378 0.0875933766 0.0057471359 0.0316400000 244614006 95654136 760807424 -0.0837743580 0.0665498972 -0.1602608263 2007 1311867237.3934979439 0.0666149855 0.0596767965 0.0875933766 0.0057464399 0.0279570000 244615934 95654136 760807424 -0.0836880952 0.0683901310 -0.1581630111 2008 1311867237.4248709679 0.0653353408 0.0596796145 0.0875933766 0.0057457233 0.0278460000 244619462 95654136 760807424 -0.0845762342 0.0659703240 -0.1566749662 2009 1311867237.4579510689 0.0650960356 0.0596823106 0.0875933766 0.0057446876 0.0283260000 244623134 95654136 760807424 -0.0860321075 0.0635541975 -0.1541827321 2010 1311867237.4933559895 0.0658462718 0.0596853773 0.0875933766 0.0057450069 0.0280800000 244624918 95654136 760807424 -0.0859799460 0.0668258816 -0.1534533203 2011 1311867237.5253219604 0.0644382313 0.0596877407 0.0875933766 0.0057472749 0.0280160000 244628590 95654136 760807424 -0.0848502591 0.0633972660 -0.1504400074 2012 1311867237.5581231117 0.0652401000 0.0596905003 0.0875933766 0.0057468036 0.0280710000 244632118 95654136 760807424 -0.0855167806 0.0624834448 -0.1476817727 2013 1311867237.5925350189 0.0662026405 0.0596937354 0.0875933766 0.0057484445 0.0313030000 244633990 95654136 760807424 -0.0857064351 0.0655379221 -0.1468223929 2014 1311867237.6261129379 0.0644951165 0.0596961194 0.0875933766 0.0057478529 0.0312550000 244637574 95654136 760807424 -0.0867302716 0.0627620593 -0.1453654170 2015 1311867237.6569290161 0.0651353151 0.0596988187 0.0875933766 0.0057467410 0.0281210000 244639390 95654136 760807424 -0.0862827897 0.0617755912 -0.1421437413 2016 1311867237.6925010681 0.0653233603 0.0597016087 0.0875933766 0.0057457083 0.0281540000 244642918 95654136 760807424 -0.0882982612 0.0624954104 -0.1411036253 2017 1311867237.7243609428 0.0662384927 0.0597048496 0.0875933766 0.0057442973 0.0315360000 244817342 95654136 760807424 -0.0862308219 0.0630740747 -0.1382286996 2018 1311867237.7617940903 0.0652202144 0.0597075826 0.0875933766 0.0057431392 0.0280530000 244819238 95654136 760807424 -0.0874166712 0.0598406121 -0.1353791654 2019 1311867237.7926809788 0.0664000064 0.0597108974 0.0875933766 0.0057427072 0.0281640000 244822798 95654136 760807424 -0.0879503042 0.0639151484 -0.1342724413 2020 1311867237.8255820274 0.0660701394 0.0597140455 0.0875933766 0.0057414581 0.0289760000 244824526 95654136 760807424 -0.0881802738 0.0637939200 -0.1322833598 2021 1311867237.8612699509 0.0650181845 0.0597166700 0.0875933766 0.0057409501 0.0281320000 244828366 95654136 760807424 -0.0889027715 0.0608421750 -0.1292737722 2022 1311867237.8926060200 0.0656321570 0.0597195956 0.0875933766 0.0057409042 0.0384420000 244949670 95654136 760807424 -0.0891821980 0.0632520691 -0.1274717748 2023 1311867237.9253590107 0.0645197034 0.0597219683 0.0875933766 0.0057412929 0.0330900000 244951806 95654136 760807424 -0.0888052359 0.0609398112 -0.1249840856 2024 1311867237.9613509178 0.0657171607 0.0597249304 0.0875933766 0.0057399962 0.0374300000 244955454 95654136 760807424 -0.0891171321 0.0615709797 -0.1214668006 2025 1311867237.9928910732 0.0649143010 0.0597274930 0.0875933766 0.0057386412 0.0384370000 244957518 95654136 760807424 -0.0895106196 0.0613190830 -0.1203621328 2026 1311867238.0245919228 0.0664264932 0.0597307996 0.0875933766 0.0057379050 0.0327260000 244960870 95654136 760807424 -0.0888567343 0.0645521581 -0.1186340675 2027 1311867238.0607950687 0.0647409111 0.0597332712 0.0875933766 0.0057383535 0.0330300000 244964718 95654136 760807424 -0.0886963457 0.0593605638 -0.1152579635 2028 1311867238.0932629108 0.0637076050 0.0597352310 0.0875933766 0.0057374775 0.0329190000 244966326 95654136 760807424 -0.0890429169 0.0551506802 -0.1121004447 2029 1311867238.1251931190 0.0651907995 0.0597379198 0.0875933766 0.0057385885 0.0379640000 244970062 95654136 760807424 -0.0885986313 0.0589910857 -0.1110880449 2030 1311867238.1608469486 0.0646515265 0.0597403403 0.0875933766 0.0057430620 0.0387250000 244973582 95654136 760807424 -0.0877701268 0.0597234517 -0.1096856445 2031 1311867238.1928510666 0.0655067191 0.0597431795 0.0875933766 0.0057476109 0.0332210000 244975518 95654136 760807424 -0.0895705447 0.0589903630 -0.1062116474 2032 1311867238.2246770859 0.0656961650 0.0597461091 0.0875933766 0.0057464926 0.0375930000 244979182 95654136 760807424 -0.0879449546 0.0606401265 -0.1045305878 2033 1311867238.2605938911 0.0658135265 0.0597490935 0.0875933766 0.0057463808 0.0329590000 244981102 95654136 760807424 -0.0858244449 0.0607845969 -0.1017960310 2034 1311867238.2926790714 0.0641392395 0.0597512519 0.0875933766 0.0057517971 0.0329620000 244984582 95654136 760807424 -0.0862000361 0.0552981310 -0.0987003446 2035 1311867238.3257811069 0.0649828091 0.0597538227 0.0875933766 0.0057630700 0.0332030000 244988686 95654136 760807424 -0.0849187747 0.0570327975 -0.0965851918 2036 1311867238.3604390621 0.0657180473 0.0597567521 0.0875933766 0.0057632998 0.0374660000 244990478 95654136 760807424 -0.0858914405 0.0576148406 -0.0948722884 2037 1311867238.3936378956 0.0655495226 0.0597595959 0.0875933766 0.0057649848 0.0329780000 244994270 95654136 760807424 -0.0844767913 0.0547780506 -0.0910949782 2038 1311867238.4264049530 0.0649446994 0.0597621401 0.0875933766 0.0057685914 0.0329180000 244996134 95654136 760807424 -0.0829861090 0.0525374524 -0.0887776315 2039 1311867238.4616210461 0.0654562339 0.0597649327 0.0875933766 0.0057678050 0.0332330000 244999854 95654136 760807424 -0.0822325423 0.0547202788 -0.0875432342 2040 1311867238.4932549000 0.0652129129 0.0597676032 0.0875933766 0.0057710350 0.0338360000 245003406 95654136 760807424 -0.0826946646 0.0521269627 -0.0844547749 2041 1311867238.5248661041 0.0647291988 0.0597700342 0.0875933766 0.0057707984 0.0330460000 245005398 95654136 760807424 -0.0816887617 0.0487267300 -0.0814067051 2042 1311867238.5605928898 0.0651731342 0.0597726802 0.0875933766 0.0057759624 0.0330260000 245009174 95654136 760807424 -0.0789183006 0.0509985127 -0.0791726932 2043 1311867238.5929119587 0.0654395446 0.0597754540 0.0875933766 0.0057823212 0.0446980000 245010926 95654136 760807424 -0.0807500258 0.0499499440 -0.0768440142 2044 1311867238.6249868870 0.0649843961 0.0597780024 0.0875933766 0.0057809871 0.0332250000 245014518 95654136 760807424 -0.0813002884 0.0488569699 -0.0745850354 2045 1311867238.6608479023 0.0647187606 0.0597804184 0.0875933766 0.0057797646 0.0331900000 245018494 95654136 760807424 -0.0799950212 0.0484783687 -0.0717169344 2046 1311867238.6929359436 0.0641857311 0.0597825715 0.0875933766 0.0057791177 0.0329060000 245020102 95654136 760807424 -0.0781527758 0.0471015386 -0.0681741312 2047 1311867238.7246360779 0.0651261359 0.0597851820 0.0875933766 0.0057803696 0.0386330000 245023910 95654136 760807424 -0.0791585669 0.0478915051 -0.0657192916 2048 1311867238.7627971172 0.0641803071 0.0597873280 0.0875933766 0.0057790802 0.0330280000 245198530 95654136 760807424 -0.0793744475 0.0474113263 -0.0626300126 2049 1311867238.7949919701 0.0644236282 0.0597895908 0.0875933766 0.0057780917 0.0333580000 245577418 95654136 760807424 -0.0790628567 0.0467050001 -0.0592276156 2050 1311867238.8246819973 0.0641983524 0.0597917414 0.0875933766 0.0057814658 0.0375710000 245990314 95654136 760807424 -0.0778763443 0.0448649935 -0.0552550778 2051 1311867238.8630580902 0.0637424067 0.0597936676 0.0875933766 0.0057805880 0.0333950000 245992730 95654136 760807424 -0.0774387643 0.0460443124 -0.0526263490 2052 1311867238.8933889866 0.0648604259 0.0597961368 0.0875933766 0.0057798517 0.0384030000 245996210 95654136 760807424 -0.0778254569 0.0471523553 -0.0491427891 2053 1311867238.9278979301 0.0637315512 0.0597980537 0.0875933766 0.0057790739 0.0332480000 246000058 95654136 760807424 -0.0773741007 0.0441448763 -0.0458116271 2054 1311867238.9628050327 0.0625884607 0.0597994122 0.0875933766 0.0057786931 0.0334250000 246001906 95654136 760807424 -0.0780883655 0.0409545861 -0.0425470397 2055 1311867238.9937820435 0.0635773689 0.0598012506 0.0875933766 0.0057782138 0.0332980000 246005530 95654136 760807424 -0.0748039559 0.0425888970 -0.0389460959 2056 1311867239.0287299156 0.0638276488 0.0598032090 0.0875933766 0.0057797660 0.0391620000 246007506 95654136 760807424 -0.0751254484 0.0437617004 -0.0364417657 2057 1311867239.0619978905 0.0625935420 0.0598045655 0.0875933766 0.0057807638 0.0486810000 246011354 95654136 760807424 -0.0758269355 0.0384979844 -0.0320188887 2058 1311867239.0939240456 0.0635575205 0.0598063891 0.0875933766 0.0057813746 0.0333010000 246014650 95654136 760807424 -0.0771288499 0.0399556868 -0.0290263686 2059 1311867239.1358110905 0.0622507446 0.0598075762 0.0875933766 0.0057811990 0.0389370000 246016866 95654136 760807424 -0.0747358501 0.0399003774 -0.0261416249 2060 1311867239.1620550156 0.0625431836 0.0598089042 0.0875933766 0.0057812240 0.0426310000 246020362 95654136 760807424 -0.0746347904 0.0380706042 -0.0223467518 2061 1311867239.1936569214 0.0631603152 0.0598105303 0.0875933766 0.0057804473 0.0391270000 246022114 95654136 760807424 -0.0732503161 0.0387634970 -0.0191044584 2062 1311867239.2294950485 0.0630746782 0.0598121133 0.0875933766 0.0057795858 0.0333400000 246025890 95654136 760807424 -0.0732050017 0.0377437584 -0.0153543744 2063 1311867239.2609150410 0.0627817661 0.0598135528 0.0875933766 0.0057791651 0.0333040000 246029626 95654136 760807424 -0.0737856105 0.0347977057 -0.0116990237 2064 1311867239.2928791046 0.0631609038 0.0598151746 0.0875933766 0.0057778798 0.0336300000 246031306 95654136 760807424 -0.0712713301 0.0346304253 -0.0079500824 2065 1311867239.3295290470 0.0634477809 0.0598169337 0.0875933766 0.0057774244 0.0334740000 246035210 95654136 760807424 -0.0719372556 0.0347496197 -0.0049165655 2066 1311867239.3615000248 0.0631795377 0.0598185613 0.0875933766 0.0057768726 0.0336090000 246038746 95654136 760807424 -0.0701318458 0.0319120921 -0.0011831583 2067 1311867239.3928411007 0.0629381910 0.0598200706 0.0875933766 0.0057763465 0.0337310000 246040682 95654136 760807424 -0.0701059252 0.0301135816 0.0016312522 2068 1311867239.4293289185 0.0636981055 0.0598219458 0.0875933766 0.0057817438 0.0336670000 246044274 95654136 760807424 -0.0698786676 0.0297731757 0.0050244476 2069 1311867239.4619059563 0.0628388003 0.0598234039 0.0875933766 0.0057858562 0.0335590000 246046194 95654136 760807424 -0.0677071437 0.0271405894 0.0078674387 2070 1311867239.4938249588 0.0628311634 0.0598248570 0.0875933766 0.0057850491 0.0374690000 246049610 95654136 760807424 -0.0678587332 0.0237734225 0.0112289302 2071 1311867239.5295019150 0.0633741543 0.0598265708 0.0875933766 0.0057861840 0.0287230000 246225290 95654136 760807424 -0.0653181076 0.0238435417 0.0145195732 2072 1311867239.5617070198 0.0632183552 0.0598282077 0.0875933766 0.0057917148 0.0285970000 246226962 95654136 760807424 -0.0657743514 0.0229622070 0.0170119014 2073 1311867239.5944910049 0.0628784224 0.0598296791 0.0875933766 0.0057913484 0.0289350000 246230634 95654136 760807424 -0.0664984509 0.0196629036 0.0198674165 2074 1311867239.6284430027 0.0621434599 0.0598307947 0.0875933766 0.0058003668 0.0291340000 246232362 95654136 760807424 -0.0648168251 0.0166223384 0.0231861752 2075 1311867239.6623089314 0.0624667518 0.0598320651 0.0875933766 0.0057998686 0.0290410000 246236146 95654136 760807424 -0.0631689057 0.0180760156 0.0256917141 2076 1311867239.6931240559 0.0629002303 0.0598335430 0.0875933766 0.0058140715 0.0290540000 246239506 95654136 760807424 -0.0631478354 0.0192494784 0.0277541764 2077 1311867239.7284948826 0.0630163550 0.0598350754 0.0875933766 0.0058144920 0.0351720000 246242066 95654136 760807424 -0.0637954772 0.0164501462 0.0315842927 2078 1311867239.7614610195 0.0627122223 0.0598364600 0.0875933766 0.0058136135 0.0342160000 246245714 95654136 760807424 -0.0619660094 0.0143452948 0.0350479819 2079 1311867239.7926149368 0.0631695688 0.0598380632 0.0875933766 0.0058132750 0.0339660000 246247538 95654136 760807424 -0.0606007650 0.0182568002 0.0372117013 2080 1311867239.8308320045 0.0631868392 0.0598396732 0.0875933766 0.0058141510 0.0323770000 246251234 95654136 760807424 -0.0622874014 0.0179806240 0.0401344746 2081 1311867239.8608438969 0.0627329871 0.0598410636 0.0875933766 0.0058232477 0.0336860000 246255106 95654136 760807424 -0.0622952282 0.0154792024 0.0438745804 2082 1311867239.8929069042 0.0636453032 0.0598428908 0.0875933766 0.0058241937 0.0320280000 246256778 95654136 760807424 -0.0595976114 0.0170679204 0.0475017242 2083 1311867239.9306600094 0.0620848872 0.0598439671 0.0875933766 0.0058257156 0.0337200000 246260874 95654136 760807424 -0.0611011237 0.0141053060 0.0499570742 2084 1311867239.9613699913 0.0629200637 0.0598454431 0.0875933766 0.0058269873 0.0376020000 246264346 95654136 760807424 -0.0607761182 0.0149597442 0.0530464426 2085 1311867239.9948220253 0.0629488528 0.0598469316 0.0875933766 0.0058257411 0.0287040000 246266218 95654136 760807424 -0.0614031367 0.0145423245 0.0558373109 2086 1311867240.0292289257 0.0624779798 0.0598481929 0.0875933766 0.0058264153 0.0336940000 246269810 95654136 760807424 -0.0594386905 0.0144902654 0.0587387271 2087 1311867240.0618810654 0.0632213503 0.0598498091 0.0875933766 0.0058250631 0.0337540000 246271802 95654136 760807424 -0.0605256036 0.0134034436 0.0619457141 2088 1311867240.0945510864 0.0631983355 0.0598514128 0.0875933766 0.0058243458 0.0341720000 246275282 95654136 760807424 -0.0612213165 0.0144054042 0.0642921105 2089 1311867240.1297509670 0.0630921498 0.0598529642 0.0875933766 0.0058234901 0.0337040000 246279258 95654136 760807424 -0.0602876544 0.0129761193 0.0679173395 2090 1311867240.1617240906 0.0632565618 0.0598545927 0.0875933766 0.0058232379 0.0287330000 246280930 95654136 760807424 -0.0594729558 0.0143073779 0.0705742612 2091 1311867240.1963129044 0.0636318922 0.0598563992 0.0875933766 0.0058225710 0.0486460000 246284714 95654136 760807424 -0.0605792217 0.0137949567 0.0737063587 2092 1311867240.2291030884 0.0639123917 0.0598583380 0.0875933766 0.0058212994 0.0337790000 246458342 95654136 760807424 -0.0588273667 0.0134957926 0.0767956525 2093 1311867240.2612760067 0.0639248267 0.0598602809 0.0875933766 0.0058206220 0.0341930000 246462326 95654136 760807424 -0.0568542704 0.0143813593 0.0794034004 2094 1311867240.2981250286 0.0632669106 0.0598619077 0.0875933766 0.0058192646 0.0287140000 246465742 95654136 760807424 -0.0582968220 0.0127307707 0.0814976096 2095 1311867240.3289160728 0.0636018962 0.0598636929 0.0875933766 0.0058193093 0.0389830000 246467742 95654136 760807424 -0.0572537743 0.0123783648 0.0844654515 2096 1311867240.3609399796 0.0638195202 0.0598655802 0.0875933766 0.0058180604 0.0337750000 246471334 95654136 760807424 -0.0575849898 0.0103859529 0.0875686482 2097 1311867240.3967890739 0.0640168861 0.0598675599 0.0875933766 0.0058173754 0.0397330000 246473142 95654136 760807424 -0.0573414378 0.0101619679 0.0898056477 2098 1311867240.4286890030 0.0633694530 0.0598692290 0.0875933766 0.0058171059 0.0338140000 246476694 95654136 760807424 -0.0561070964 0.0072239377 0.0923153237 2099 1311867240.4650850296 0.0637224689 0.0598710648 0.0875933766 0.0058182454 0.0391400000 246480470 95654136 760807424 -0.0575312302 0.0067292349 0.0945694372 2100 1311867240.4972898960 0.0630473718 0.0598725773 0.0875933766 0.0058195330 0.0336050000 246482206 95654136 760807424 -0.0558818355 0.0052056387 0.0962469876 2101 1311867240.5309979916 0.0627732053 0.0598739579 0.0875933766 0.0058214921 0.0337400000 246486126 95654136 760807424 -0.0556726977 0.0028410084 0.0982176811 2102 1311867240.5608210564 0.0637823418 0.0598758173 0.0875933766 0.0058214433 0.0337700000 246489606 95654136 760807424 -0.0564625226 0.0035376868 0.1005544662 2103 1311867240.5965991020 0.0632696971 0.0598774311 0.0875933766 0.0058201566 0.0335800000 246491654 95654136 760807424 -0.0568095446 0.0017627289 0.1016351208 2104 1311867240.6290791035 0.0633597299 0.0598790862 0.0875933766 0.0058201176 0.0388680000 246495062 95654136 760807424 -0.0553440675 -0.0005514910 0.1037863493 2105 1311867240.6622560024 0.0631010681 0.0598806168 0.0875933766 0.0058222943 0.0338300000 246496998 95654136 760807424 -0.0551968738 -0.0003511386 0.1049016938 2106 1311867240.6968801022 0.0632559434 0.0598822195 0.0875933766 0.0058212659 0.0342400000 246500590 95654136 760807424 -0.0569712929 -0.0010272063 0.1063505784 2107 1311867240.7291979790 0.0626952797 0.0598835546 0.0875933766 0.0058223318 0.0296170000 246504262 95654136 760807424 -0.0573067553 -0.0018673118 0.1072149500 2108 1311867240.7625629902 0.0624716766 0.0598847824 0.0875933766 0.0058219735 0.0291900000 246505934 95654136 760807424 -0.0567825884 -0.0012701580 0.1083883196 2109 1311867240.7965719700 0.0626625642 0.0598860995 0.0875933766 0.0058208230 0.0287830000 246509718 95654136 760807424 -0.0578310080 -0.0017927636 0.1103512645 2110 1311867240.8293309212 0.0622608401 0.0598872250 0.0875933766 0.0058196141 0.0287850000 246511390 95654136 760807424 -0.0584637374 0.0000260585 0.1116369143 2111 1311867240.8621098995 0.0626419038 0.0598885299 0.0875933766 0.0058185932 0.0300170000 246515118 95654136 760807424 -0.0593243130 0.0006011978 0.1138765961 2112 1311867240.8973500729 0.0625332966 0.0598897821 0.0875933766 0.0058178334 0.0340340000 246519214 95654136 760807424 -0.0596762523 0.0004303360 0.1163571104 2113 1311867240.9290270805 0.0625589117 0.0598910453 0.0875933766 0.0058171197 0.0338060000 246521094 95654136 760807424 -0.0596923977 0.0033422045 0.1181113422 2114 1311867240.9614369869 0.0626906827 0.0598923697 0.0875933766 0.0058157767 0.0289240000 246524566 95654136 760807424 -0.0608506389 0.0034554389 0.1203904524 2115 1311867240.9968450069 0.0625023618 0.0598936037 0.0875933766 0.0058148958 0.0339640000 246696866 95654136 760807424 -0.0606929511 0.0042540324 0.1228584796 2116 1311867241.0315620899 0.0621981882 0.0598946928 0.0875933766 0.0058170216 0.0345600000 246700650 95654136 760807424 -0.0618307106 0.0045817606 0.1257660389 2117 1311867241.0633668900 0.0630258843 0.0598961719 0.0875933766 0.0058261270 0.0341160000 246704274 95654136 760807424 -0.0629434660 0.0084747290 0.1276213229 2118 1311867241.0990099907 0.0621502921 0.0598972362 0.0875933766 0.0058311663 0.0315210000 246706114 95654136 760807424 -0.0636899918 0.0050038169 0.1310755461 2119 1311867241.1285290718 0.0630002692 0.0598987006 0.0875933766 0.0058313282 0.0289890000 246709674 95654136 760807424 -0.0644109026 0.0063348999 0.1333916783 2120 1311867241.1641499996 0.0626122802 0.0598999806 0.0875933766 0.0058351100 0.0290220000 246713314 95654136 760807424 -0.0656188205 0.0075716497 0.1353930086 2121 1311867241.1980121136 0.0624067597 0.0599011624 0.0875933766 0.0058363005 0.0402260000 246715570 95654136 760807424 -0.0657145679 0.0058418345 0.1380395144 2122 1311867241.2313330173 0.0633249655 0.0599027759 0.0875933766 0.0058377536 0.0341120000 246719218 95654136 760807424 -0.0677812323 0.0065025175 0.1404798180 2123 1311867241.2640700340 0.0639618263 0.0599046879 0.0875933766 0.0058364972 0.0338150000 246721098 95654136 760807424 -0.0683444068 0.0084495433 0.1424716562 2124 1311867241.3000609875 0.0631855428 0.0599062325 0.0875933766 0.0058426463 0.0338410000 246724802 95654136 760807424 -0.0688006505 0.0066979472 0.1445127130 2125 1311867241.3294849396 0.0633299351 0.0599078437 0.0875933766 0.0058445616 0.0320360000 246728362 95654136 760807424 -0.0699565709 0.0075208964 0.1457939148 2126 1311867241.3612549305 0.0639155209 0.0599097287 0.0875933766 0.0058439979 0.0341310000 246730218 95654136 760807424 -0.0721973702 0.0067586401 0.1479057670 2127 1311867241.3981139660 0.0635051131 0.0599114191 0.0875933766 0.0058474950 0.0288890000 246733946 95654136 760807424 -0.0730626956 0.0048993910 0.1496455371 2128 1311867241.4300589561 0.0640747324 0.0599133755 0.0875933766 0.0058616808 0.0327030000 246735674 95654136 760807424 -0.0732076988 0.0062359055 0.1515976042 2129 1311867241.4652009010 0.0640839264 0.0599153345 0.0875933766 0.0058632346 0.0289530000 246739402 95654136 760807424 -0.0762710124 0.0066439337 0.1528924406 2130 1311867241.4969789982 0.0637034103 0.0599171129 0.0875933766 0.0058679474 0.0289270000 246742818 95654136 760807424 -0.0773302838 0.0059682815 0.1548823416 2131 1311867241.5331718922 0.0641341880 0.0599190918 0.0875933766 0.0058695986 0.0290100000 246744858 95654136 760807424 -0.0781918839 0.0066671735 0.1564609706 2132 1311867241.5656960011 0.0638727695 0.0599209463 0.0875933766 0.0058693544 0.0289440000 246748330 95654136 760807424 -0.0802259967 0.0068416544 0.1576576531 2133 1311867241.6002480984 0.0638540760 0.0599227902 0.0875933766 0.0058695091 0.0319150000 246750258 95654136 760807424 -0.0804956928 0.0051139090 0.1590878218 2134 1311867241.6291201115 0.0640707165 0.0599247340 0.0875933766 0.0058682957 0.0343730000 246754186 95654136 760807424 -0.0809238181 0.0054126452 0.1598980129 2135 1311867241.6646790504 0.0640375316 0.0599266603 0.0875933766 0.0058726445 0.0327280000 246757914 95654136 760807424 -0.0805426463 0.0071449336 0.1612578332 2136 1311867241.6999258995 0.0635735914 0.0599283677 0.0875933766 0.0058736452 0.0342900000 246759954 95654136 760807424 -0.0818854645 0.0059135025 0.1622055322 2137 1311867241.7297649384 0.0639873520 0.0599302671 0.0875933766 0.0058835617 0.0291350000 246763514 95654136 760807424 -0.0817627311 0.0062278928 0.1626683027 2138 1311867241.7676639557 0.0641970709 0.0599322628 0.0875933766 0.0058830735 0.0290310000 246767210 95654136 760807424 -0.0811946765 0.0091144554 0.1636875421 2139 1311867241.7974851131 0.0636252984 0.0599339893 0.0875933766 0.0058828350 0.0298500000 246768970 95654136 760807424 -0.0825483724 0.0065832227 0.1646098495 2140 1311867241.8296549320 0.0638975501 0.0599358414 0.0875933766 0.0058826089 0.0292840000 246772442 95654136 760807424 -0.0823003650 0.0066443905 0.1662587076 2141 1311867241.8668920994 0.0631836951 0.0599373584 0.0875933766 0.0058818862 0.0291810000 246774482 95654136 760807424 -0.0836708620 0.0064157466 0.1668037474 2142 1311867241.8979690075 0.0633285493 0.0599389416 0.0875933766 0.0058808599 0.0290750000 246777898 95654136 760807424 -0.0832580701 0.0071159541 0.1681348383 2143 1311867241.9292619228 0.0638280660 0.0599407564 0.0875933766 0.0058806821 0.0293240000 246781570 95654136 760807424 -0.0841933340 0.0078829546 0.1705323756 2144 1311867241.9654040337 0.0628896356 0.0599421318 0.0875933766 0.0058795931 0.0290730000 246783354 95654136 760807424 -0.0848415345 0.0087671354 0.1720332205 2145 1311867241.9974029064 0.0632029921 0.0599436520 0.0875933766 0.0058805406 0.0329350000 246787026 95654136 760807424 -0.0863819867 0.0071015367 0.1743056029 2146 1311867242.0296339989 0.0637758225 0.0599454377 0.0875933766 0.0058807873 0.0342630000 246789338 95654136 760807424 -0.0863910690 0.0065315389 0.1768757403 2147 1311867242.0670061111 0.0633233115 0.0599470110 0.0875933766 0.0058804886 0.0322520000 246793178 95654136 760807424 -0.0865349323 0.0102311503 0.1777250767 2148 1311867242.0972509384 0.0634804890 0.0599486561 0.0875933766 0.0058804183 0.0402340000 246796594 95654136 760807424 -0.0901958421 0.0088437935 0.1791726351 2149 1311867242.1308040619 0.0640266687 0.0599505537 0.0875933766 0.0058824402 0.0293860000 246798466 95654136 760807424 -0.0909288302 0.0099161873 0.1806716174 2150 1311867242.1670179367 0.0634950921 0.0599522023 0.0875933766 0.0058837617 0.0292030000 246972550 95654136 760807424 -0.0902293026 0.0104132174 0.1819270253 2151 1311867242.1982409954 0.0639326274 0.0599540528 0.0875933766 0.0058849176 0.0292560000 246974366 95654136 760807424 -0.0898583755 0.0087198243 0.1844930649 2152 1311867242.2334370613 0.0637294874 0.0599558072 0.0875933766 0.0058877167 0.0292490000 246977950 95654136 760807424 -0.0917533264 0.0099197440 0.1854831874 2153 1311867242.2696599960 0.0638441443 0.0599576132 0.0875933766 0.0058865844 0.0329720000 246981734 95654136 760807424 -0.0921015590 0.0098482799 0.1874068528 2154 1311867242.2982430458 0.0639991462 0.0599594895 0.0875933766 0.0058856236 0.0296010000 246983294 95654136 760807424 -0.0907549337 0.0089850947 0.1896009445 2155 1311867242.3293490410 0.0637411997 0.0599612443 0.0875933766 0.0058848100 0.0298250000 246986966 95654136 760807424 -0.0918876007 0.0102273906 0.1907581985 2156 1311867242.3659460545 0.0644292086 0.0599633167 0.0875933766 0.0058856055 0.0298480000 246990550 95654136 760807424 -0.0927415118 0.0088704750 0.1932206601 2157 1311867242.3974800110 0.0649867207 0.0599656456 0.0875933766 0.0058854085 0.0298640000 246992422 95654136 760807424 -0.0925081447 0.0095330728 0.1948323250 2158 1311867242.4322769642 0.0647822618 0.0599678776 0.0875933766 0.0058840837 0.0298290000 246996006 95654136 760807424 -0.0933759212 0.0099548390 0.1959302276 2159 1311867242.4648990631 0.0647130832 0.0599700754 0.0875933766 0.0058853586 0.0298450000 246997822 95654136 760807424 -0.0925850943 0.0075498377 0.1978005767 2160 1311867242.4975609779 0.0642005429 0.0599720340 0.0875933766 0.0058843724 0.0303520000 247001294 95654136 760807424 -0.0943527594 0.0069909529 0.1984107494 2161 1311867242.5292570591 0.0642999932 0.0599740367 0.0875933766 0.0058832785 0.0292070000 247004966 95654136 760807424 -0.0940630734 0.0072728344 0.1998276711 2162 1311867242.5650939941 0.0642516389 0.0599760153 0.0875933766 0.0058823856 0.0291410000 247006806 95654136 760807424 -0.0945928991 0.0071906624 0.2010809034 2163 1311867242.5985031128 0.0642418712 0.0599779875 0.0875933766 0.0058810562 0.0322370000 247010534 95654136 760807424 -0.0958430693 0.0063185515 0.2023809254 2164 1311867242.6305589676 0.0641472042 0.0599799141 0.0875933766 0.0058803530 0.0291680000 247012150 95654136 760807424 -0.0942533165 0.0059917392 0.2038468122 2165 1311867242.6692740917 0.0635869950 0.0599815802 0.0875933766 0.0058797887 0.0345030000 247016942 95654136 760807424 -0.0960320458 0.0040221619 0.2057929635 2166 1311867242.6981039047 0.0635807663 0.0599832419 0.0875933766 0.0058785479 0.0329080000 247020302 95654136 760807424 -0.0966563150 0.0043147528 0.2072515637 2167 1311867242.7372829914 0.0633080676 0.0599847762 0.0875933766 0.0058789664 0.0292530000 247022342 95654136 760807424 -0.0947786719 0.0058326391 0.2090298235 2168 1311867242.7656900883 0.0633700192 0.0599863376 0.0875933766 0.0058796693 0.0349430000 247026334 95654136 760807424 -0.0950248837 0.0032524006 0.2114340812 2169 1311867242.7994089127 0.0632566810 0.0599878454 0.0875933766 0.0058824207 0.0292150000 247028206 95654136 760807424 -0.0968199596 0.0033086347 0.2128359824 2170 1311867242.8355538845 0.0626293942 0.0599890627 0.0875933766 0.0058831765 0.0406260000 247202574 95654136 760807424 -0.0960419923 0.0046361904 0.2143563628 2171 1311867242.8666720390 0.0625174642 0.0599902273 0.0875933766 0.0058845938 0.0293680000 247206246 95654136 760807424 -0.0955894440 0.0023410667 0.2164807171 2172 1311867242.8980929852 0.0641239211 0.0599921305 0.0875933766 0.0059085030 0.0294680000 247207862 95654136 760807424 -0.0960328802 0.0022546214 0.2190804929 2173 1311867242.9335498810 0.0628800020 0.0599934595 0.0875933766 0.0059300273 0.0291810000 247211646 95654136 760807424 -0.0970938578 0.0045561865 0.2200011462 2174 1311867242.9649999142 0.0630201921 0.0599948517 0.0875933766 0.0059323119 0.0348840000 247215566 95654136 760807424 -0.0981086791 0.0041874098 0.2214502245 2175 1311867242.9970819950 0.0628796890 0.0599961781 0.0875933766 0.0059318342 0.0292590000 247217382 95654136 760807424 -0.0988160595 0.0028778338 0.2230491936 2176 1311867243.0332529545 0.0633222833 0.0599977066 0.0875933766 0.0059305937 0.0291640000 247220966 95654136 760807424 -0.0972276032 0.0032280595 0.2250070870 2177 1311867243.0648689270 0.0624456480 0.0599988311 0.0875933766 0.0059293913 0.0329570000 247222838 95654136 760807424 -0.0979539901 0.0038353861 0.2264760584 2178 1311867243.0972158909 0.0626844689 0.0600000641 0.0875933766 0.0059283160 0.0292230000 247226310 95654136 760807424 -0.0996957719 0.0022241122 0.2285715789 2179 1311867243.1357100010 0.0617508776 0.0600008676 0.0875933766 0.0059340111 0.0291810000 247230150 95654136 760807424 -0.0993465111 0.0033627651 0.2303684354 2180 1311867243.1655960083 0.0630095527 0.0600022478 0.0875933766 0.0059397333 0.0323990000 247231766 95654136 760807424 -0.1004225761 0.0013514648 0.2328112870 2181 1311867243.1977169514 0.0626795292 0.0600034753 0.0875933766 0.0059396234 0.0329920000 247235382 95654136 760807424 -0.1003919095 0.0022059511 0.2338865995 2182 1311867243.2358860970 0.0621441826 0.0600044564 0.0875933766 0.0059403473 0.0292980000 247237278 95654136 760807424 -0.1019953564 0.0006679418 0.2356283665 2183 1311867243.2649240494 0.0628426597 0.0600057565 0.0875933766 0.0059394223 0.0293070000 247240782 95654136 760807424 -0.1028822064 0.0009961359 0.2374422103 2184 1311867243.2970221043 0.0626503006 0.0600069674 0.0875933766 0.0059381843 0.0405160000 247244310 95654136 760807424 -0.1036151052 -0.0002633125 0.2392283529 2185 1311867243.3327538967 0.0623505004 0.0600080400 0.0875933766 0.0059377052 0.0293070000 247246238 95654136 760807424 -0.1037725657 -0.0002266362 0.2408969700 2186 1311867243.3681559563 0.0628237277 0.0600093280 0.0875933766 0.0059363958 0.0323170000 247249822 95654136 760807424 -0.1051648557 -0.0021292623 0.2431396544 2187 1311867243.4021821022 0.0630244315 0.0600107067 0.0875933766 0.0059350649 0.0329640000 247251750 95654136 760807424 -0.1063296869 -0.0018783888 0.2444920540 2188 1311867243.4344329834 0.0631216541 0.0600121285 0.0875933766 0.0059345919 0.0348560000 247255990 95654136 760807424 -0.1046617180 -0.0019769811 0.2466050386 2189 1311867243.4665510654 0.0628328472 0.0600134171 0.0875933766 0.0059336929 0.0402120000 247259662 95654136 760807424 -0.1068932265 -0.0010568935 0.2479678094 2190 1311867243.4982140064 0.0628504157 0.0600147125 0.0875933766 0.0059337362 0.0298620000 247261278 95654136 760807424 -0.1070822328 -0.0018523295 0.2498033345 2191 1311867243.5339779854 0.0631911531 0.0600161623 0.0875933766 0.0059324940 0.0350100000 247265118 95654136 760807424 -0.1076527536 -0.0016202307 0.2516752183 2192 1311867243.5669720173 0.0625047907 0.0600172976 0.0875933766 0.0059313492 0.0293130000 247268646 95654136 760807424 -0.1067949086 -0.0012379512 0.2532000542 2193 1311867243.5978341103 0.0628825277 0.0600186041 0.0875933766 0.0059304695 0.0292790000 247270462 95654136 760807424 -0.1066067591 -0.0027626199 0.2554321587 2194 1311867243.6333720684 0.0634002686 0.0600201454 0.0875933766 0.0059334060 0.0292750000 247273990 95654136 760807424 -0.1073829234 -0.0024009573 0.2568663061 2195 1311867243.6661529541 0.0635346100 0.0600217466 0.0875933766 0.0059320760 0.0292650000 247275918 95654136 760807424 -0.1064750925 -0.0020930201 0.2585400939 2196 1311867243.6981849670 0.0638582557 0.0600234936 0.0875933766 0.0059313998 0.0329010000 247281254 95654136 760807424 -0.1064943597 -0.0013504957 0.2600311935 2197 1311867243.7344710827 0.0645919964 0.0600255730 0.0875933766 0.0059314237 0.0292390000 247285094 95654136 760807424 -0.1085240245 -0.0020569351 0.2625580728 2198 1311867243.7666299343 0.0643991381 0.0600275628 0.0875933766 0.0059312620 0.0291050000 247286822 95654136 760807424 -0.1069100499 -0.0013803456 0.2640939951 2199 1311867243.7979769707 0.0645350590 0.0600296126 0.0875933766 0.0059300058 0.0293130000 247461894 95654136 760807424 -0.1076302975 -0.0023248359 0.2657291889 2200 1311867243.8330240250 0.0640455857 0.0600314381 0.0875933766 0.0059288885 0.0292260000 247463622 95654136 760807424 -0.1062352210 -0.0014762224 0.2675491273 2201 1311867243.8647689819 0.0649280474 0.0600336628 0.0875933766 0.0059290835 0.0353970000 247469086 95654136 760807424 -0.1060163230 -0.0026196423 0.2700336874 2202 1311867243.8968739510 0.0647781044 0.0600358174 0.0875933766 0.0059278479 0.0323910000 247472614 95654136 760807424 -0.1046152785 -0.0034491792 0.2718190551 2203 1311867243.9329960346 0.0653156862 0.0600382141 0.0875933766 0.0059276157 0.0329250000 247474542 95654136 760807424 -0.1050509065 -0.0037548535 0.2736497223 2204 1311867243.9660589695 0.0648314655 0.0600403889 0.0875933766 0.0059269416 0.0292280000 247478070 95654136 760807424 -0.1042677909 -0.0044136364 0.2747858465 2205 1311867244.0016739368 0.0645197928 0.0600424203 0.0875933766 0.0059264655 0.0325310000 247480054 95654136 760807424 -0.1037183553 -0.0043811467 0.2761885822 2206 1311867244.0341379642 0.0641786680 0.0600442953 0.0875933766 0.0059254377 0.0387680000 247483846 95654136 760807424 -0.1022071838 -0.0047807433 0.2778396010 2207 1311867244.0655789375 0.0641707405 0.0600461650 0.0875933766 0.0059241934 0.0347380000 247487582 95654136 760807424 -0.1020146385 -0.0045347712 0.2791285813 2208 1311867244.1010930538 0.0643466935 0.0600481128 0.0875933766 0.0059229574 0.0348660000 247489430 95654136 760807424 -0.1025358215 -0.0054062442 0.2812515795 2209 1311867244.1353089809 0.0637229010 0.0600497763 0.0875933766 0.0059221182 0.0292520000 247493158 95654136 760807424 -0.1013501659 -0.0051114606 0.2824972868 2210 1311867244.1648418903 0.0642854497 0.0600516929 0.0875933766 0.0059210484 0.0325640000 247496518 95654136 760807424 -0.1009950861 -0.0066816034 0.2851076424 2211 1311867244.2024741173 0.0636153370 0.0600533047 0.0875933766 0.0059197367 0.0294610000 247498614 95654136 760807424 -0.1000109315 -0.0056892629 0.2871325612 2212 1311867244.2330279350 0.0636637956 0.0600549369 0.0875933766 0.0059189196 0.0292950000 247502030 95654136 760807424 -0.0994790569 -0.0070828977 0.2892554402 2213 1311867244.2649021149 0.0631913543 0.0600563542 0.0875933766 0.0059184383 0.0392230000 247504166 95654136 760807424 -0.0975569412 -0.0072020767 0.2910575271 2214 1311867244.3010311127 0.0630692169 0.0600577150 0.0875933766 0.0059180357 0.0345030000 247507870 95654136 760807424 -0.0962632075 -0.0064387596 0.2934530377 2215 1311867244.3355190754 0.0629093423 0.0600590024 0.0875933766 0.0059170067 0.0291050000 247511598 95654136 760807424 -0.0970379114 -0.0055836621 0.2951338589 2216 1311867244.3649079800 0.0636429340 0.0600606197 0.0875933766 0.0059160472 0.0396010000 247513286 95654136 760807424 -0.0965124890 -0.0087859537 0.2978902161 2217 1311867244.4008760452 0.0639169887 0.0600623592 0.0875933766 0.0059174762 0.0294500000 247517070 95654136 760807424 -0.0961058661 -0.0055062855 0.2997663915 2218 1311867244.4329938889 0.0633637160 0.0600638476 0.0875933766 0.0059195739 0.0293700000 247518742 95654136 760807424 -0.0962807909 -0.0073877191 0.3018243909 2219 1311867244.4654510021 0.0637224913 0.0600654964 0.0875933766 0.0059187179 0.0292210000 247522470 95654136 760807424 -0.0965166539 -0.0070204763 0.3039820790 2220 1311867244.5052490234 0.0632068813 0.0600669114 0.0875933766 0.0059179817 0.0365600000 247526166 95654136 760807424 -0.0934800878 -0.0068586236 0.3068028688 2221 1311867244.5330989361 0.0634295344 0.0600684254 0.0875933766 0.0059168003 0.0292980000 247527870 95654136 760807424 -0.0921926647 -0.0051199161 0.3090196252 2222 1311867244.5669400692 0.0632285103 0.0600698476 0.0875933766 0.0059155499 0.0302090000 247531342 95654136 760807424 -0.0922439620 -0.0047081569 0.3110106289 2223 1311867244.6027030945 0.0635609254 0.0600714181 0.0875933766 0.0059192306 0.0292550000 247533214 95654136 760807424 -0.0915113464 -0.0043153055 0.3138541281 2224 1311867244.6328020096 0.0635860935 0.0600729984 0.0875933766 0.0059191767 0.0347630000 247536958 95654136 760807424 -0.0904416442 -0.0033952028 0.3161126673 2225 1311867244.6672449112 0.0634124875 0.0600744993 0.0875933766 0.0059199406 0.0292260000 247540742 95654136 760807424 -0.0890788510 -0.0047582523 0.3186411858 2226 1311867244.7012600899 0.0633906424 0.0600759890 0.0875933766 0.0059192990 0.0324660000 247542470 95654136 760807424 -0.0892842188 -0.0039927857 0.3205483854 2227 1311867244.7346320152 0.0637732223 0.0600776492 0.0875933766 0.0059182885 0.0322250000 247546142 95654136 760807424 -0.0894195214 -0.0049287975 0.3229568303 2228 1311867244.7650001049 0.0639662743 0.0600793945 0.0875933766 0.0059170743 0.0292320000 247549558 95654136 760807424 -0.0886251703 -0.0036142711 0.3251241446 2229 1311867244.8015320301 0.0642630458 0.0600812715 0.0875933766 0.0059159211 0.0293460000 247722082 95654136 760807424 -0.0883421451 -0.0043500932 0.3277298808 2230 1311867244.8331909180 0.0641163886 0.0600830809 0.0875933766 0.0059152346 0.0292340000 247725498 95654136 760807424 -0.0874978900 -0.0053751203 0.3297767341 2231 1311867244.8651568890 0.0644368306 0.0600850324 0.0875933766 0.0059145278 0.0292670000 247727426 95654136 760807424 -0.0877491087 -0.0041015539 0.3318082690 2232 1311867244.9013550282 0.0636746660 0.0600866407 0.0875933766 0.0059135247 0.0292630000 247731010 95654136 760807424 -0.0871162862 -0.0033895809 0.3331880867 2233 1311867244.9328739643 0.0640807077 0.0600884293 0.0875933766 0.0059123804 0.0300880000 247734570 95654136 760807424 -0.0871741995 -0.0060212594 0.3359942436 2234 1311867244.9652509689 0.0638537854 0.0600901148 0.0875933766 0.0059123974 0.0448420000 247736298 95654136 760807424 -0.0868455842 -0.0038205965 0.3379428089 2235 1311867245.0022718906 0.0635648891 0.0600916695 0.0875933766 0.0059133938 0.0296170000 247740194 95654136 760807424 -0.0862553343 -0.0045364830 0.3398862481 2236 1311867245.0349979401 0.0644084290 0.0600936001 0.0875933766 0.0059141147 0.0292650000 247741810 95654136 760807424 -0.0874136314 -0.0049192412 0.3422986865 2237 1311867245.0664730072 0.0640648976 0.0600953754 0.0875933766 0.0059128614 0.0325210000 247745482 95654136 760807424 -0.0865840986 -0.0036917597 0.3443032801 2238 1311867245.1041638851 0.0639794469 0.0600971109 0.0875933766 0.0059123340 0.0292940000 247749066 95654136 760807424 -0.0879983157 -0.0040526679 0.3460454345 2239 1311867245.1338050365 0.0644629598 0.0600990608 0.0875933766 0.0059111500 0.0293630000 247750882 95654136 760807424 -0.0875636637 -0.0054460047 0.3482197821 2240 1311867245.1749250889 0.0642969459 0.0601009348 0.0875933766 0.0059099656 0.0293480000 247754690 95654136 760807424 -0.0889414996 -0.0051486618 0.3504829109 2241 1311867245.2108979225 0.0645126775 0.0601029035 0.0875933766 0.0059089697 0.0378840000 247756674 95654136 760807424 -0.0893715397 -0.0049502696 0.3530844748 2242 1311867245.2429010868 0.0650774911 0.0601051223 0.0875933766 0.0059079126 0.0326320000 247760202 95654136 760807424 -0.0887636691 -0.0057586064 0.3556574285 2243 1311867245.2755670547 0.0645677447 0.0601071119 0.0875933766 0.0059076762 0.0292610000 247763874 95654136 760807424 -0.0888266861 -0.0057163108 0.3574180305 2244 1311867245.3120090961 0.0646260455 0.0601091257 0.0875933766 0.0059065710 0.0294150000 247765658 95654136 760807424 -0.0898691863 -0.0053488584 0.3597444892 2245 1311867245.3430099487 0.0654000863 0.0601114824 0.0875933766 0.0059055048 0.0293740000 247769330 95654136 760807424 -0.0908831879 -0.0054590749 0.3625256121 2246 1311867245.3749370575 0.0654851347 0.0601138750 0.0875933766 0.0059045658 0.0294830000 247772746 95654136 760807424 -0.0917855799 -0.0061285570 0.3646502495 2247 1311867245.4122350216 0.0645065010 0.0601158299 0.0875933766 0.0059043278 0.0294120000 247774842 95654136 760807424 -0.0918886214 -0.0056196121 0.3668985367 2248 1311867245.4428830147 0.0654766858 0.0601182146 0.0875933766 0.0059073887 0.0378330000 247778146 95654136 760807424 -0.0931104049 -0.0053067640 0.3691629171 2249 1311867245.4751451015 0.0648553893 0.0601203209 0.0875933766 0.0059063175 0.0293110000 247780074 95654136 760807424 -0.0949861333 -0.0053657051 0.3703725636 2250 1311867245.5108819008 0.0651443154 0.0601225538 0.0875933766 0.0059051848 0.0292340000 247783658 95654136 760807424 -0.0955693573 -0.0057402463 0.3735747933 2251 1311867245.5429608822 0.0645753145 0.0601245320 0.0875933766 0.0059040291 0.0293400000 247787330 95654136 760807424 -0.0946401879 -0.0038839024 0.3756050169 2252 1311867245.5749409199 0.0654964894 0.0601269174 0.0875933766 0.0059031430 0.0329500000 247789002 95654136 760807424 -0.0972980782 -0.0054258713 0.3784721494 2253 1311867245.6109130383 0.0672473162 0.0601300778 0.0875933766 0.0059050047 0.0294950000 247792786 95654136 760807424 -0.0969903544 -0.0056775846 0.3821076155 2254 1311867245.6428189278 0.0653791726 0.0601324066 0.0875933766 0.0059097847 0.0292670000 247794402 95654136 760807424 -0.0984698981 -0.0048902887 0.3831578493 2255 1311867245.6751749516 0.0663702711 0.0601351728 0.0875933766 0.0059087673 0.0316980000 247798130 95654136 760807424 -0.0994236171 -0.0055563869 0.3856684268 2256 1311867245.7109169960 0.0666766092 0.0601380724 0.0875933766 0.0059086504 0.0293100000 247801714 95654136 760807424 -0.1005442515 -0.0059540728 0.3878734112 2257 1311867245.7429819107 0.0661477298 0.0601407351 0.0875933766 0.0059075257 0.0297680000 247803530 95654136 760807424 -0.1017269492 -0.0057312725 0.3892090321 2258 1311867245.7752521038 0.0661729649 0.0601434065 0.0875933766 0.0059113526 0.0300140000 247807058 95654136 760807424 -0.1004071832 -0.0068072341 0.3919830322 2259 1311867245.8110349178 0.0672553480 0.0601465548 0.0875933766 0.0059129345 0.0293960000 247809042 95654136 760807424 -0.1009135023 -0.0071901130 0.3945371509 2260 1311867245.8428230286 0.0658482388 0.0601490777 0.0875933766 0.0059117098 0.0294240000 247812570 95654136 760807424 -0.1013244465 -0.0066917231 0.3948037922 2261 1311867245.8757770061 0.0668771863 0.0601520534 0.0875933766 0.0059104364 0.0292990000 247816186 95654136 760807424 -0.1030862257 -0.0070872321 0.3969786167 2262 1311867245.9110751152 0.0662348568 0.0601547425 0.0875933766 0.0059095164 0.0386760000 247817970 95654136 760807424 -0.1023811325 -0.0063882582 0.3984513581 2263 1311867245.9428870678 0.0665389076 0.0601575636 0.0875933766 0.0059085154 0.0304460000 247821642 95654136 760807424 -0.1039078385 -0.0072279056 0.4003103077 2264 1311867245.9751350880 0.0662006959 0.0601602329 0.0875933766 0.0059073824 0.0326810000 247825114 95654136 760807424 -0.1041719690 -0.0065336367 0.4016465247 2265 1311867246.0112419128 0.0658752769 0.0601627561 0.0875933766 0.0059064187 0.0293450000 247827098 95654136 760807424 -0.1041271985 -0.0068075424 0.4041474462 2266 1311867246.0429229736 0.0661352649 0.0601653918 0.0875933766 0.0059051685 0.0293870000 247830514 95654136 760807424 -0.1059163436 -0.0060783718 0.4062708020 2267 1311867246.0752329826 0.0658362135 0.0601678932 0.0875933766 0.0059041983 0.0293580000 247832386 95654136 760807424 -0.1057603583 -0.0057885102 0.4082192183 2268 1311867246.1109249592 0.0660588667 0.0601704907 0.0875933766 0.0059041721 0.0294660000 248008086 95654136 760807424 -0.1096874997 -0.0051498660 0.4098750353 2269 1311867246.1430890560 0.0668215081 0.0601734219 0.0875933766 0.0059030283 0.0325160000 248011814 95654136 760807424 -0.1097683981 -0.0047456049 0.4125317931 2270 1311867246.1749811172 0.0661948323 0.0601760745 0.0875933766 0.0059022470 0.0293560000 248013430 95654136 760807424 -0.1100049466 -0.0034104339 0.4141956568 2271 1311867246.2109639645 0.0657996088 0.0601785508 0.0875933766 0.0059016202 0.0294900000 248017214 95654136 760807424 -0.1097315699 -0.0026694397 0.4164189696 2272 1311867246.2429399490 0.0662041157 0.0601812029 0.0875933766 0.0059012583 0.0293480000 248018886 95654136 760807424 -0.1113353670 -0.0013590012 0.4183063209 2273 1311867246.2750649452 0.0666924119 0.0601840675 0.0875933766 0.0059000233 0.0293090000 248022558 95654136 760807424 -0.1124904603 -0.0012430766 0.4204433560 2274 1311867246.3108720779 0.0663535818 0.0601867805 0.0875933766 0.0058995783 0.0293750000 248026142 95654136 760807424 -0.1125329658 -0.0006392449 0.4224876761 2275 1311867246.3429319859 0.0671235994 0.0601898297 0.0875933766 0.0058985736 0.0293720000 248028014 95654136 760807424 -0.1130675301 -0.0002263070 0.4251978993 2276 1311867246.3752970695 0.0665279478 0.0601926144 0.0875933766 0.0058976306 0.0392830000 248031486 95654136 760807424 -0.1136657745 0.0006018896 0.4261052012 2277 1311867246.4109311104 0.0666829124 0.0601954648 0.0875933766 0.0058974655 0.0294280000 248033470 95654136 760807424 -0.1146061346 0.0013927593 0.4280305207 2278 1311867246.4430770874 0.0677175745 0.0601987669 0.0875933766 0.0058964388 0.0293620000 248036942 95654136 760807424 -0.1146587133 0.0015937235 0.4308595657 2279 1311867246.4751329422 0.0677141771 0.0602020645 0.0875933766 0.0058951995 0.0294400000 248040614 95654136 760807424 -0.1158959270 0.0027398288 0.4319971204 2280 1311867246.5109679699 0.0675990954 0.0602053089 0.0875933766 0.0058940854 0.0293440000 248042398 95654136 760807424 -0.1161333770 0.0021896665 0.4333641231 2281 1311867246.5431129932 0.0685806498 0.0602089806 0.0875933766 0.0058929059 0.0294200000 248046014 95654136 760807424 -0.1164217293 0.0021874993 0.4354565144 2282 1311867246.5752038956 0.0687028542 0.0602127028 0.0875933766 0.0058916213 0.0326560000 248049542 95654136 760807424 -0.1159869507 0.0028102929 0.4367434680 2283 1311867246.6111249924 0.0685323104 0.0602163469 0.0875933766 0.0058907633 0.0330510000 248051526 95654136 760807424 -0.1167304292 0.0030894373 0.4375599325 2284 1311867246.6431870461 0.0689959824 0.0602201909 0.0875933766 0.0058900709 0.0299020000 248054998 95654136 760807424 -0.1176999956 0.0021752021 0.4392277300 2285 1311867246.6751689911 0.0685433596 0.0602238334 0.0875933766 0.0058888531 0.0297450000 248056870 95654136 760807424 -0.1164818630 0.0033494951 0.4399095774 2286 1311867246.7110559940 0.0690521374 0.0602276953 0.0875933766 0.0058876544 0.0295210000 248060454 95654136 760807424 -0.1180344820 0.0020814091 0.4408144355 2287 1311867246.7433049679 0.0692742839 0.0602316510 0.0875933766 0.0058864829 0.0293950000 248064182 95654136 760807424 -0.1187289953 0.0024632630 0.4415269196 2288 1311867246.7749860287 0.0691458136 0.0602355470 0.0875933766 0.0058853646 0.0294450000 248065798 95654136 760807424 -0.1167827994 0.0025402496 0.4423114955 2289 1311867246.8111929893 0.0696513504 0.0602396605 0.0875933766 0.0058843078 0.0295210000 248069582 95654136 760807424 -0.1182690114 0.0012714235 0.4428353012 2290 1311867246.8430919647 0.0691203251 0.0602435385 0.0875933766 0.0058830273 0.0321630000 248071310 95654136 760807424 -0.1179960966 0.0013808548 0.4428672791 2291 1311867246.8750779629 0.0690197125 0.0602473693 0.0875933766 0.0058820229 0.0295180000 248074926 95654136 760807424 -0.1179343089 0.0020650311 0.4432553053 2292 1311867246.9111549854 0.0692424402 0.0602512938 0.0875933766 0.0058808771 0.0328550000 248078510 95654136 760807424 -0.1186153367 0.0006708199 0.4438380003 2293 1311867246.9430611134 0.0696480796 0.0602553918 0.0875933766 0.0058797376 0.0294200000 248080326 95654136 760807424 -0.1185634434 0.0011521967 0.4447899461 2294 1311867246.9751238823 0.0687384754 0.0602590898 0.0875933766 0.0058788238 0.0294520000 248083854 95654136 760807424 -0.1184813529 0.0007006133 0.4446130693 2295 1311867247.0109090805 0.0687715486 0.0602627989 0.0875933766 0.0058775627 0.0293640000 248085838 95654136 760807424 -0.1190262437 0.0005061689 0.4450549185 2296 1311867247.0440731049 0.0687308386 0.0602664871 0.0875933766 0.0058763197 0.0302810000 248089366 95654136 760807424 -0.1201491132 0.0000003484 0.4453554749 2297 1311867247.0751919746 0.0689241290 0.0602702562 0.0875933766 0.0058750674 0.0294740000 248092982 95654136 760807424 -0.1208078936 -0.0003118152 0.4458027184 2298 1311867247.1112151146 0.0689306706 0.0602740249 0.0875933766 0.0058738540 0.0327070000 248094766 95654136 760807424 -0.1205965132 0.0003144814 0.4463705122 2299 1311867247.1430439949 0.0689069852 0.0602777800 0.0875933766 0.0058729369 0.0329310000 248098438 95654136 760807424 -0.1210591570 -0.0000261889 0.4466270208 2300 1311867247.1751630306 0.0698569715 0.0602819448 0.0875933766 0.0058726858 0.0293750000 248101910 95654136 760807424 -0.1222733781 0.0003153512 0.4475282133 2301 1311867247.2113189697 0.0721330941 0.0602870953 0.0875933766 0.0058723738 0.0293130000 248103894 95654136 760807424 -0.1242707223 -0.0012021931 0.4493101537 2302 1311867247.2437279224 0.0707089752 0.0602916226 0.0875933766 0.0058714602 0.0293130000 248107366 95654136 760807424 -0.1215712279 0.0000937161 0.4484525323 2303 1311867247.2777190208 0.0697590858 0.0602957335 0.0875933766 0.0058703420 0.0294540000 248109350 95654136 760807424 -0.1210629642 -0.0009533155 0.4472258985 2304 1311867247.3109691143 0.0715155900 0.0603006032 0.0875933766 0.0058695606 0.0326950000 248112766 95654136 760807424 -0.1247422323 -0.0026001770 0.4473754466 2305 1311867247.3432049751 0.0707991272 0.0603051579 0.0875933766 0.0058685502 0.0293260000 248116438 95654136 760807424 -0.1248023957 -0.0022618808 0.4459001124 2306 1311867247.3753070831 0.0710220039 0.0603098053 0.0875933766 0.0058674404 0.0293390000 248118110 95654136 760807424 -0.1256328672 -0.0036321848 0.4451484680 2307 1311867247.4116749763 0.0711172745 0.0603144899 0.0875933766 0.0058665485 0.0293520000 248121950 95654136 760807424 -0.1247483268 -0.0045408509 0.4444075823 2308 1311867247.4440929890 0.0712294877 0.0603192191 0.0875933766 0.0058656895 0.0293590000 248123566 95654136 760807424 -0.1248475090 -0.0052143410 0.4431349933 2309 1311867247.4751029015 0.0705637410 0.0603236559 0.0875933766 0.0058647217 0.0294030000 248127238 95654136 760807424 -0.1237760112 -0.0060633998 0.4414812624 2310 1311867247.5110449791 0.0700584352 0.0603278701 0.0875933766 0.0058676655 0.0294580000 248130822 95654136 760807424 -0.1205900609 -0.0057505253 0.4402181804 2311 1311867247.5430850983 0.0706065744 0.0603323178 0.0875933766 0.0058722225 0.0330180000 248132694 95654136 760807424 -0.1234992594 -0.0069370572 0.4379918873 2312 1311867247.5751209259 0.0694306195 0.0603362531 0.0875933766 0.0058820623 0.0293830000 248136110 95654136 760807424 -0.1203460842 -0.0079559200 0.4364717901 2313 1311867247.6114599705 0.0702802315 0.0603405523 0.0875933766 0.0058867017 0.0334320000 248138150 95654136 760807424 -0.1196485460 -0.0074166320 0.4344733059 2314 1311867247.6431109905 0.0708005354 0.0603450726 0.0875933766 0.0058869159 0.0294300000 248141566 95654136 760807424 -0.1216554493 -0.0092633814 0.4322946668 2315 1311867247.6750760078 0.0708332807 0.0603496031 0.0875933766 0.0058903342 0.0293680000 248145238 95654136 760807424 -0.1196559221 -0.0118438005 0.4307438135 2316 1311867247.7112369537 0.0711808428 0.0603542798 0.0875933766 0.0058900041 0.0326480000 248147078 95654136 760807424 -0.1181983873 -0.0127218440 0.4276421964 2317 1311867247.7431221008 0.0696671158 0.0603582992 0.0875933766 0.0058889564 0.0293850000 248150694 95654136 760807424 -0.1160238385 -0.0134373447 0.4237542748 2318 1311867247.7750411034 0.0694682449 0.0603622292 0.0875933766 0.0058877577 0.0337070000 248154166 95654136 760807424 -0.1165827215 -0.0145758484 0.4211352170 2319 1311867247.8111629486 0.0691702664 0.0603660274 0.0875933766 0.0058865394 0.0294770000 248156150 95654136 760807424 -0.1154648289 -0.0146426708 0.4181414247 2320 1311867247.8438889980 0.0689119920 0.0603697111 0.0875933766 0.0058857926 0.0293580000 248159678 95654136 760807424 -0.1141800955 -0.0143370098 0.4157710671 2321 1311867247.8752439022 0.0689004809 0.0603733865 0.0875933766 0.0058850291 0.0294410000 248161494 95654136 760807424 -0.1133097410 -0.0161065292 0.4141153097 2322 1311867247.9113290310 0.0691041946 0.0603771466 0.0875933766 0.0058840706 0.0325360000 248165078 95654136 760807424 -0.1126204804 -0.0158960372 0.4119336605 2323 1311867247.9430620670 0.0683209747 0.0603805662 0.0875933766 0.0058833012 0.0398330000 248168806 95654136 760807424 -0.1118354052 -0.0153043699 0.4092305601 2324 1311867247.9769830704 0.0685436279 0.0603840787 0.0875933766 0.0058823639 0.0295370000 248170534 95654136 760807424 -0.1105317175 -0.0166280735 0.4077751637 2325 1311867248.0109910965 0.0698258877 0.0603881397 0.0875933766 0.0058812000 0.0348100000 248174206 95654136 760807424 -0.1114449054 -0.0179162379 0.4064769149 2326 1311867248.0431969166 0.0685554296 0.0603916510 0.0875933766 0.0058800260 0.0294200000 248175934 95654136 760807424 -0.1103732288 -0.0176991373 0.4031663835 2327 1311867248.0751419067 0.0684806332 0.0603951271 0.0875933766 0.0058792031 0.0293040000 248179550 95654136 760807424 -0.1097126752 -0.0181970038 0.4008213878 2328 1311867248.1121830940 0.0694895685 0.0603990337 0.0875933766 0.0058781338 0.0294920000 248183190 95654136 760807424 -0.1100676432 -0.0192368142 0.3990675509 2329 1311867248.1431720257 0.0686244220 0.0604025654 0.0875933766 0.0058769507 0.0294040000 248185006 95654136 760807424 -0.1088630334 -0.0184019729 0.3959149420 2330 1311867248.1757500172 0.0688224062 0.0604061791 0.0875933766 0.0058757064 0.0294190000 248188422 95654136 760807424 -0.1088534817 -0.0191282686 0.3935099244 2331 1311867248.2111859322 0.0684797391 0.0604096426 0.0875933766 0.0058744829 0.0298730000 248190462 95654136 760807424 -0.1085001007 -0.0188805424 0.3910544515 2332 1311867248.2431430817 0.0684396178 0.0604130860 0.0875933766 0.0058732304 0.0318850000 248193934 95654136 760807424 -0.1084128171 -0.0193500035 0.3885092437 2333 1311867248.2755289078 0.0679361820 0.0604163107 0.0875933766 0.0058719961 0.0296320000 248197606 95654136 760807424 -0.1075041294 -0.0185617544 0.3856628835 2334 1311867248.3112230301 0.0676978752 0.0604194305 0.0875933766 0.0058712402 0.0295780000 248199334 95654136 760807424 -0.1069986895 -0.0183133427 0.3832737803 2335 1311867248.3434588909 0.0680306256 0.0604226901 0.0875933766 0.0058709188 0.0295750000 248202894 95654136 760807424 -0.1063891053 -0.0175086092 0.3810130954 2336 1311867248.3752219677 0.0676084906 0.0604257662 0.0875933766 0.0058712206 0.0294890000 248206366 95654136 760807424 -0.1068645865 -0.0171106346 0.3779428303 2337 1311867248.4115560055 0.0670993403 0.0604286218 0.0875933766 0.0058720607 0.0330760000 248208406 95654136 760807424 -0.1052269712 -0.0168929379 0.3758389652 2338 1311867248.4431369305 0.0680368319 0.0604318759 0.0875933766 0.0058708735 0.0295750000 248211822 95654136 760807424 -0.1047767401 -0.0170101915 0.3741918802 2339 1311867248.4759230614 0.0673738047 0.0604348439 0.0875933766 0.0058697193 0.0406780000 248213750 95654136 760807424 -0.1043461114 -0.0161183029 0.3711013496 2340 1311867248.5111510754 0.0668738559 0.0604375956 0.0875933766 0.0058693751 0.0296200000 248217278 95654136 760807424 -0.1028540134 -0.0157572720 0.3689427972 2341 1311867248.5431890488 0.0679535568 0.0604408061 0.0875933766 0.0058682249 0.0294800000 248221006 95654136 760807424 -0.1015983224 -0.0162743665 0.3675679266 2342 1311867248.5751869678 0.0671830252 0.0604436850 0.0875933766 0.0058670919 0.0294770000 248222622 95654136 760807424 -0.1007568389 -0.0158423297 0.3648352623 2343 1311867248.6114389896 0.0671533570 0.0604465487 0.0875933766 0.0058662432 0.0294370000 248226462 95654136 760807424 -0.1009725705 -0.0161425248 0.3623878956 2344 1311867248.6432449818 0.0675802529 0.0604495921 0.0875933766 0.0058651877 0.0294640000 248228078 95654136 760807424 -0.0998767838 -0.0151890768 0.3602401912 2345 1311867248.6753089428 0.0669904426 0.0604523813 0.0875933766 0.0058639503 0.0295150000 248231694 95654136 760807424 -0.0993006080 -0.0146890692 0.3574800193 2346 1311867248.7112829685 0.0672706068 0.0604552877 0.0875933766 0.0058628400 0.0320150000 248235334 95654136 760807424 -0.0988333374 -0.0145950252 0.3548964858 2347 1311867248.7433049679 0.0674639493 0.0604582739 0.0875933766 0.0058632053 0.0296230000 248237150 95654144 760807424 -0.0965629146 -0.0150607415 0.3529567122 2348 1311867248.7762219906 0.0667709038 0.0604609624 0.0875933766 0.0058630257 0.0295750000 248240678 95654144 760807424 -0.0979295075 -0.0128277065 0.3492789268 2349 1311867248.8111898899 0.0670262128 0.0604637573 0.0875933766 0.0058624662 0.0298700000 248242606 95654144 760807424 -0.0972010419 -0.0130710034 0.3467865288 2350 1311867248.8433189392 0.0677161887 0.0604668435 0.0875933766 0.0058677725 0.0294670000 248246078 95654144 760807424 -0.0960552692 -0.0145245213 0.3452731669 2351 1311867248.8755309582 0.0665547848 0.0604694330 0.0875933766 0.0058691256 0.0294610000 248249806 95654144 760807424 -0.0938289836 -0.0119806454 0.3410984278 2352 1311867248.9111700058 0.0663795844 0.0604719458 0.0875933766 0.0058679501 0.0294730000 248251590 95654144 760807424 -0.0940252841 -0.0118444366 0.3375064731 2353 1311867248.9430971146 0.0676034465 0.0604749766 0.0875933766 0.0058669262 0.0384980000 248255206 95654144 760807424 -0.0919767767 -0.0137901986 0.3362039924 2354 1311867248.9766070843 0.0670909882 0.0604777871 0.0875933766 0.0058657957 0.0294980000 248258790 95654144 760807424 -0.0908237696 -0.0121341571 0.3324094415 2355 1311867249.0112600327 0.0663143843 0.0604802655 0.0875933766 0.0058645960 0.0295280000 248260662 95654144 760807424 -0.0880658329 -0.0113906041 0.3287538588 2356 1311867249.0432310104 0.0670186803 0.0604830407 0.0875933766 0.0058634664 0.0330270000 248264134 95654144 760807424 -0.0878561512 -0.0120576238 0.3261633813 2357 1311867249.0799250603 0.0669755042 0.0604857953 0.0875933766 0.0058622712 0.0295660000 248266174 95654144 760807424 -0.0872585475 -0.0115852924 0.3231382072 2358 1311867249.1120550632 0.0660776496 0.0604881667 0.0875933766 0.0058611465 0.0295210000 248269646 95654144 760807424 -0.0847223476 -0.0116541153 0.3197599053 2359 1311867249.1435980797 0.0660446584 0.0604905222 0.0875933766 0.0058603716 0.0298030000 248273318 95654144 760807424 -0.0828616694 -0.0109109851 0.3170312941 2360 1311867249.1785130501 0.0672386214 0.0604933815 0.0875933766 0.0058592684 0.0320050000 248274990 95654144 760807424 -0.0817349479 -0.0121187828 0.3154055476 2361 1311867249.2113580704 0.0659629703 0.0604956982 0.0875933766 0.0058585211 0.0327070000 248278718 95654144 760807424 -0.0802917704 -0.0091307405 0.3111124337 2362 1311867249.2432780266 0.0664371848 0.0604982136 0.0875933766 0.0058579689 0.0294350000 248280446 95654144 760807424 -0.0778991953 -0.0114429835 0.3090284765 2363 1311867249.2773559093 0.0670306161 0.0605009781 0.0875933766 0.0058569436 0.0294610000 248284174 95654144 760807424 -0.0772546902 -0.0099820504 0.3064849377 2364 1311867249.3112919331 0.0658240020 0.0605032298 0.0875933766 0.0058563481 0.0301670000 248287646 95654144 760807424 -0.0763838589 -0.0087380838 0.3023772240 2365 1311867249.3437249660 0.0666724294 0.0605058383 0.0875933766 0.0058551809 0.0301790000 248289574 95654144 760807424 -0.0753954723 -0.0103148678 0.3006906509 2366 1311867249.3768579960 0.0665706694 0.0605084016 0.0875933766 0.0058555128 0.0301400000 248293102 95654144 760807424 -0.0726247132 -0.0107800234 0.2984628677 2367 1311867249.4112169743 0.0662052482 0.0605108084 0.0875933766 0.0058552785 0.0300310000 248295030 95654144 760807424 -0.0717650652 -0.0095703173 0.2948827147 2368 1311867249.4432210922 0.0656132475 0.0605129632 0.0875933766 0.0058540737 0.0300220000 248298446 95654144 760807424 -0.0710284635 -0.0093668187 0.2916314304 2369 1311867249.4764440060 0.0669597685 0.0605156845 0.0875933766 0.0058529314 0.0301110000 248302174 95654144 760807424 -0.0707267448 -0.0108200647 0.2903266847 2370 1311867249.5111339092 0.0666823313 0.0605182865 0.0875933766 0.0058518224 0.0300990000 248303902 95654144 760807424 -0.0708807409 -0.0103994906 0.2870653868 2371 1311867249.5432300568 0.0651393831 0.0605202355 0.0875933766 0.0058507478 0.0301550000 248478790 95654144 760807424 -0.0684111118 -0.0100856898 0.2831933796 2372 1311867249.5759820938 0.0660375804 0.0605225615 0.0875933766 0.0058498368 0.0300260000 248482318 95654144 760807424 -0.0697712451 -0.0111798970 0.2811192870 2373 1311867249.6112229824 0.0667654201 0.0605251923 0.0875933766 0.0058490865 0.0300480000 248484246 95654144 760807424 -0.0689819902 -0.0101487376 0.2791818082 2374 1311867249.6433780193 0.0654532537 0.0605272681 0.0875933766 0.0058480967 0.0300970000 248487718 95654144 760807424 -0.0679204911 -0.0097559281 0.2755886018 2375 1311867249.6751029491 0.0655366331 0.0605293773 0.0875933766 0.0058504009 0.0300910000 248489590 95654144 760807424 -0.0675504431 -0.0107437670 0.2737582624 2376 1311867249.7111389637 0.0662696436 0.0605317933 0.0875933766 0.0058508248 0.0301130000 248493118 95654144 760807424 -0.0676571578 -0.0091362856 0.2711235285 2377 1311867249.7432470322 0.0654066280 0.0605338441 0.0875933766 0.0058498441 0.0300770000 248496846 95654144 760807424 -0.0668012798 -0.0084054153 0.2679234147 2378 1311867249.7751579285 0.0646555126 0.0605355774 0.0875933766 0.0058521067 0.0300120000 248498462 95654144 760807424 -0.0673695654 -0.0091220662 0.2656687200 2379 1311867249.8111488819 0.0661178231 0.0605379238 0.0875933766 0.0058521567 0.0302540000 248502302 95654144 760807424 -0.0656910166 -0.0071829571 0.2642368376 2380 1311867249.8433248997 0.0648912415 0.0605397529 0.0875933766 0.0058514023 0.0299640000 248503918 95654144 760807424 -0.0640440285 -0.0056365882 0.2607813179 2381 1311867249.8784089088 0.0651508272 0.0605416896 0.0875933766 0.0058505775 0.0305140000 248507702 95654144 760807424 -0.0660359785 -0.0057557025 0.2582970560 2382 1311867249.9112401009 0.0663781241 0.0605441398 0.0875933766 0.0058494767 0.0293940000 248511174 95654144 760807424 -0.0647603944 -0.0061170901 0.2569195628 2383 1311867249.9432768822 0.0656588003 0.0605462861 0.0875933766 0.0058484552 0.0294820000 248513102 95654144 760807424 -0.0633080900 -0.0030857951 0.2535048723 2384 1311867249.9751698971 0.0656711087 0.0605484358 0.0875933766 0.0058479040 0.0294400000 248516518 95654144 760807424 -0.0628269240 -0.0019437347 0.2505318820 2385 1311867250.0117108822 0.0659775883 0.0605507121 0.0875933766 0.0058473838 0.0331470000 248518558 95654144 760807424 -0.0621322393 -0.0020156051 0.2481167316 2386 1311867250.0434269905 0.0666881278 0.0605532844 0.0875933766 0.0058466312 0.0294700000 248522030 95654144 760807424 -0.0623474307 -0.0033683763 0.2457757443 2387 1311867250.0767190456 0.0665123463 0.0605557809 0.0875933766 0.0058458460 0.0293830000 248525758 95654144 760807424 -0.0619693473 -0.0021394938 0.2426080257 2388 1311867250.1116099358 0.0661033988 0.0605581040 0.0875933766 0.0058446484 0.0295750000 248527486 95654144 760807424 -0.0598033555 -0.0016599341 0.2394853085 2389 1311867250.1432220936 0.0665003806 0.0605605913 0.0875933766 0.0058434485 0.0294100000 248531102 95654144 760807424 -0.0598968416 -0.0026122394 0.2368182689 2390 1311867250.1758980751 0.0663780719 0.0605630254 0.0875933766 0.0058429683 0.0405790000 248545190 95654144 760807424 -0.0588294975 -0.0007378809 0.2334863842 2391 1311867250.2133369446 0.0663043037 0.0605654266 0.0875933766 0.0058418714 0.0296750000 248547174 95654144 760807424 -0.0586290956 -0.0011186477 0.2302313894 2392 1311867250.2457129955 0.0659837872 0.0605676918 0.0875933766 0.0058408024 0.0302300000 248550702 95654144 760807424 -0.0587093532 -0.0017456426 0.2275222242 2393 1311867250.2751679420 0.0656146631 0.0605698009 0.0875933766 0.0058398403 0.0294580000 248552462 95654144 760807424 -0.0571809709 -0.0024284187 0.2250072360 2394 1311867250.3114409447 0.0665822998 0.0605723124 0.0875933766 0.0058391614 0.0294290000 248556102 95654144 760807424 -0.0567160845 0.0005511162 0.2226437926 2395 1311867250.3431971073 0.0663170740 0.0605747110 0.0875933766 0.0058381127 0.0293200000 248559718 95654144 760807424 -0.0570328943 0.0006029546 0.2200264931 2396 1311867250.3780639172 0.0677076429 0.0605776880 0.0875933766 0.0058372125 0.0335270000 248567038 95654144 760807424 -0.0577345751 -0.0012662141 0.2193873227 2397 1311867250.4116489887 0.0667969808 0.0605802827 0.0875933766 0.0058365588 0.0352200000 248571854 95654144 760807424 -0.0554271452 0.0010441949 0.2155965120 2398 1311867250.4441781044 0.0655675381 0.0605823624 0.0875933766 0.0058353773 0.0356280000 248573534 95654144 760807424 -0.0540587977 0.0020845677 0.2123399228 2399 1311867250.4793250561 0.0660202578 0.0605846292 0.0875933766 0.0058345524 0.0297330000 248577318 95654144 760807424 -0.0546732992 0.0016815210 0.2100538462 2400 1311867250.5113220215 0.0668656826 0.0605872463 0.0875933766 0.0058334304 0.0296920000 248580790 95654144 760807424 -0.0531682447 0.0007702001 0.2090754211 2401 1311867250.5443398952 0.0666329637 0.0605897643 0.0875933766 0.0058334662 0.0358060000 248582854 95654144 760807424 -0.0541943014 0.0026734024 0.2059002668 2402 1311867250.5793490410 0.0658974722 0.0605919740 0.0875933766 0.0058330365 0.0296600000 248758250 95654144 760807424 -0.0526039787 0.0027038949 0.2031641155 2403 1311867250.6114881039 0.0670699328 0.0605946697 0.0875933766 0.0058328148 0.0297570000 248760178 95654144 760807424 -0.0520479791 0.0042694970 0.2016169876 2404 1311867250.6433761120 0.0669660792 0.0605973201 0.0875933766 0.0058322217 0.0327380000 248763650 95654144 760807424 -0.0511423498 0.0035389038 0.1995531172 2405 1311867250.6795539856 0.0671185553 0.0606000316 0.0875933766 0.0058323304 0.0296530000 248767378 95654144 760807424 -0.0519391708 0.0054413481 0.1963205785 2406 1311867250.7112920284 0.0670324042 0.0606027051 0.0875933766 0.0058313275 0.0296340000 248769050 95654144 760807424 -0.0507811680 0.0035682931 0.1946104765 2407 1311867250.7445890903 0.0673114359 0.0606054923 0.0875933766 0.0058309728 0.0296210000 248772778 95654144 760807424 -0.0501719341 0.0025329988 0.1929860860 2408 1311867250.7792830467 0.0669791698 0.0606081391 0.0875933766 0.0058313852 0.0296440000 248776250 95654144 760807424 -0.0497318842 0.0050783623 0.1895265132 2409 1311867250.8145580292 0.0668918714 0.0606107476 0.0875933766 0.0058302608 0.0297010000 248778234 95654144 760807424 -0.0490322858 0.0036889631 0.1878716052 2410 1311867250.8433599472 0.0669879690 0.0606133937 0.0875933766 0.0058291343 0.0295930000 248781594 95654144 760807424 -0.0498357750 0.0022987225 0.1861465424 2411 1311867250.8792760372 0.0665548295 0.0606158580 0.0875933766 0.0058297082 0.0296480000 248783578 95654144 760807424 -0.0494434386 0.0022354266 0.1839983016 2412 1311867250.9116361141 0.0664490610 0.0606182764 0.0875933766 0.0058287245 0.0296480000 248787106 95654144 760807424 -0.0495827869 0.0011970768 0.1818835288 2413 1311867250.9433720112 0.0668800697 0.0606208715 0.0875933766 0.0058286442 0.0295820000 248790722 95654144 760807424 -0.0508995987 0.0019376979 0.1796985716 2414 1311867250.9793050289 0.0660611689 0.0606231251 0.0875933766 0.0058274983 0.0297930000 248792506 95654144 760807424 -0.0485209525 0.0029415058 0.1770893037 2415 1311867251.0112459660 0.0658275411 0.0606252801 0.0875933766 0.0058265167 0.0295980000 248796178 95654144 760807424 -0.0498883165 0.0023768733 0.1751455516 2416 1311867251.0437910557 0.0662919432 0.0606276256 0.0875933766 0.0058254218 0.0295200000 248797850 95654144 760807424 -0.0490911677 0.0020507418 0.1735111922 2417 1311867251.0793159008 0.0660510436 0.0606298695 0.0875933766 0.0058247624 0.0295530000 248801634 95654144 760807424 -0.0485491715 0.0033827804 0.1708330363 2418 1311867251.1115839481 0.0657596961 0.0606319910 0.0875933766 0.0058235594 0.0336430000 248805162 95654144 760807424 -0.0494432226 0.0030443333 0.1690671444 2419 1311867251.1432809830 0.0663312748 0.0606343470 0.0875933766 0.0058227027 0.0299070000 248807034 95654144 760807424 -0.0493247993 0.0016391535 0.1678476036 2420 1311867251.1794250011 0.0660562441 0.0606365875 0.0875933766 0.0058225516 0.0302130000 248810618 95654144 760807424 -0.0496725813 0.0033383295 0.1649944335 2421 1311867251.2113831043 0.0652383789 0.0606384883 0.0875933766 0.0058226226 0.0302630000 248812490 95654144 760807424 -0.0485023111 0.0023721014 0.1625559926 2422 1311867251.2472319603 0.0660945773 0.0606407410 0.0875933766 0.0058221236 0.0302090000 248816074 95654144 760807424 -0.0500374846 0.0017299498 0.1615024805 2423 1311867251.2793700695 0.0665704608 0.0606431883 0.0875933766 0.0058212561 0.0302260000 248819690 95654144 760807424 -0.0501765534 0.0010212566 0.1597686410 2424 1311867251.3133869171 0.0662943050 0.0606455196 0.0875933766 0.0058203990 0.0302930000 248821474 95654144 760807424 -0.0500590838 0.0020499893 0.1572028995 2425 1311867251.3432419300 0.0654521883 0.0606475017 0.0875933766 0.0058236384 0.0382230000 248825034 95654144 760807424 -0.0499678627 0.0014048303 0.1554625928 2426 1311867251.3801820278 0.0654033646 0.0606494621 0.0875933766 0.0058226076 0.0358300000 248830082 95654144 760807424 -0.0494228266 0.0017447146 0.1528546214 2427 1311867251.4113550186 0.0656925812 0.0606515400 0.0875933766 0.0058214852 0.0296110000 248831954 95654144 760807424 -0.0507553741 0.0011803720 0.1513637900 2428 1311867251.4433960915 0.0650757849 0.0606533622 0.0875933766 0.0058204482 0.0296040000 248835370 95654144 760807424 -0.0495551080 0.0020950024 0.1485599428 2429 1311867251.4793379307 0.0649897233 0.0606551474 0.0875933766 0.0058193045 0.0295690000 248837354 95654144 760807424 -0.0495799445 0.0008454204 0.1469058692 2430 1311867251.5175099373 0.0648081228 0.0606568565 0.0875933766 0.0058183495 0.0295070000 248841050 95654144 760807424 -0.0504103675 0.0000057118 0.1451183110 2431 1311867251.5431749821 0.0650632381 0.0606586691 0.0875933766 0.0058172815 0.0295660000 248844498 95654144 760807424 -0.0496844500 0.0002525684 0.1433604956 2432 1311867251.5795340538 0.0651804656 0.0606605283 0.0875933766 0.0058164362 0.0514540000 248846722 95654144 760807424 -0.0486253910 0.0013276056 0.1412072033 2433 1311867251.6119680405 0.0652744994 0.0606624248 0.0875933766 0.0058153307 0.0295890000 248850450 95654144 760807424 -0.0484164692 0.0004557854 0.1398445517 2434 1311867251.6432960033 0.0649892688 0.0606642024 0.0875933766 0.0058144021 0.0295510000 248852066 95654144 760807424 -0.0486451387 0.0013668641 0.1373348236 2435 1311867251.6797280312 0.0649719685 0.0606659715 0.0875933766 0.0058162528 0.0295910000 248855850 95654144 760807424 -0.0492911041 0.0001937640 0.1353925169 2436 1311867251.7123379707 0.0643342957 0.0606674774 0.0875933766 0.0058154299 0.0296660000 248859378 95654144 760807424 -0.0474185199 0.0022844633 0.1326929927 2437 1311867251.7434990406 0.0636412203 0.0606686977 0.0875933766 0.0058144340 0.0357060000 248861458 95654144 760807424 -0.0478861369 0.0015034473 0.1302675903 2438 1311867251.7797439098 0.0655841157 0.0606707138 0.0875933766 0.0058133755 0.0331430000 248865098 95654144 760807424 -0.0491871051 -0.0012736360 0.1303783953 2439 1311867251.8112530708 0.0649510771 0.0606724688 0.0875933766 0.0058126593 0.0295020000 248866970 95654144 760807424 -0.0486457497 0.0009425837 0.1275345832 2440 1311867251.8433279991 0.0642391667 0.0606739306 0.0875933766 0.0058119585 0.0294700000 248870442 95654144 760807424 -0.0488656797 0.0023194524 0.1249076724 2441 1311867251.8805420399 0.0647284910 0.0606755916 0.0875933766 0.0058112161 0.0295040000 248874170 95654144 760807424 -0.0491166748 0.0009620453 0.1241815016 2442 1311867251.9112489223 0.0639304668 0.0606769244 0.0875933766 0.0058100845 0.0352680000 248876034 95654144 760807424 -0.0474538393 0.0027011381 0.1216554344 2443 1311867251.9432179928 0.0637361333 0.0606781767 0.0875933766 0.0058092178 0.0294640000 248879650 95654144 760807424 -0.0477274694 0.0025687462 0.1196888089 2444 1311867251.9800109863 0.0636381209 0.0606793878 0.0875933766 0.0058083296 0.0294970000 248883290 95654144 760807424 -0.0480699465 0.0018918001 0.1181145832 2445 1311867252.0119040012 0.0632453635 0.0606804373 0.0875933766 0.0058072694 0.0296590000 248885218 95654144 760807424 -0.0488894694 0.0016798142 0.1160841957 2446 1311867252.0441029072 0.0638841838 0.0606817471 0.0875933766 0.0058061067 0.0295940000 248888690 95654144 760807424 -0.0482747778 0.0022807997 0.1143945530 2447 1311867252.0794539452 0.0643970370 0.0606832654 0.0875933766 0.0058050978 0.0356700000 248890882 95654144 760807424 -0.0468719937 0.0026595891 0.1121649146 2448 1311867252.1122460365 0.0643093064 0.0606847466 0.0875933766 0.0058048025 0.0295240000 248894466 95654144 760807424 -0.0486608930 0.0012490610 0.1096336618 2449 1311867252.1432950497 0.0640221909 0.0606861094 0.0875933766 0.0058048431 0.0294670000 248898026 95654144 760807424 -0.0488740392 0.0000521046 0.1068215147 2450 1311867252.1794359684 0.0640194342 0.0606874699 0.0875933766 0.0058037150 0.0330960000 248899810 95654144 760807424 -0.0481664017 -0.0005694958 0.1037420258 2451 1311867252.2113459110 0.0638595968 0.0606887641 0.0875933766 0.0058040980 0.0295230000 249074642 95654144 760807424 -0.0473183990 -0.0011113063 0.1010249257 2452 1311867252.2432808876 0.0640160665 0.0606901211 0.0875933766 0.0058031964 0.0413260000 249076826 95654144 760807424 -0.0485142656 -0.0026465752 0.0981952250 2453 1311867252.2794110775 0.0645851567 0.0606917090 0.0875933766 0.0058025466 0.0294140000 249080610 95654144 760807424 -0.0493029244 -0.0039287983 0.0957270935 2454 1311867252.3112668991 0.0638043582 0.0606929774 0.0875933766 0.0058019482 0.0352880000 249084210 95654144 760807424 -0.0490410216 -0.0042553823 0.0922815800 2455 1311867252.3450291157 0.0638187975 0.0606942506 0.0875933766 0.0058009022 0.0353330000 249086146 95654144 760807424 -0.0496564135 -0.0060597118 0.0895840749 2456 1311867252.3794589043 0.0639883578 0.0606955919 0.0875933766 0.0057998847 0.0353900000 249089794 95654144 760807424 -0.0515114740 -0.0087628420 0.0869088769 2457 1311867252.4111969471 0.0654402897 0.0606975230 0.0875933766 0.0058015778 0.0389260000 249262006 95654144 760807424 -0.0513263345 -0.0068962793 0.0843254253 2458 1311867252.4456050396 0.0647391826 0.0606991672 0.0875933766 0.0058043778 0.0294240000 249265534 95654144 760807424 -0.0485090949 -0.0072289486 0.0806379020 2459 1311867252.4792900085 0.0640109330 0.0607005140 0.0875933766 0.0058129517 0.0387800000 249269206 95654144 760807424 -0.0484284684 -0.0100478977 0.0784788355 2460 1311867252.5112249851 0.0638017431 0.0607017747 0.0875933766 0.0058125684 0.0294740000 249270934 95654144 760807424 -0.0484677218 -0.0097850561 0.0746358335 2461 1311867252.5432820320 0.0628298372 0.0607026394 0.0875933766 0.0058116301 0.0330100000 249274606 95654144 760807424 -0.0473919474 -0.0097966287 0.0703974888 2462 1311867252.5791800022 0.0626690537 0.0607034381 0.0875933766 0.0058105838 0.0295000000 249278190 95654144 760807424 -0.0482522137 -0.0113458224 0.0674929395 2463 1311867252.6112799644 0.0627438873 0.0607042666 0.0875933766 0.0058098862 0.0353330000 249280702 95654144 760807424 -0.0495513380 -0.0135210920 0.0646362528 2464 1311867252.6432769299 0.0628272891 0.0607051282 0.0875933766 0.0058089053 0.0354210000 249284166 95654144 760807424 -0.0493591130 -0.0124759972 0.0608741194 2465 1311867252.6792490482 0.0629644468 0.0607060447 0.0875933766 0.0058096181 0.0409380000 249285846 95654144 760807424 -0.0484904908 -0.0147779752 0.0587023124 2466 1311867252.7112491131 0.0623773970 0.0607067225 0.0875933766 0.0058093754 0.0403560000 249289310 95654144 760807424 -0.0495089442 -0.0155972382 0.0551379584 2467 1311867252.7432410717 0.0632871464 0.0607077685 0.0875933766 0.0058082750 0.0353020000 249292862 95654144 760807424 -0.0493048877 -0.0154145742 0.0523981303 2468 1311867252.7792730331 0.0630095303 0.0607087011 0.0875933766 0.0058073992 0.0352480000 249294710 95654144 760807424 -0.0483102873 -0.0148986522 0.0485435911 2469 1311867252.8112781048 0.0627383143 0.0607095231 0.0875933766 0.0058063257 0.0354070000 249298502 95654144 760807424 -0.0481508151 -0.0160168502 0.0453179181 2470 1311867252.8433189392 0.0626038536 0.0607102901 0.0875933766 0.0058053406 0.0351820000 249300494 95654144 760807424 -0.0474036038 -0.0178840794 0.0427138731 2471 1311867252.8792660236 0.0627227426 0.0607111045 0.0875933766 0.0058055887 0.0352810000 249304414 95654144 760807424 -0.0457951650 -0.0160791352 0.0389685296 2472 1311867252.9112188816 0.0615186468 0.0607114312 0.0875933766 0.0058049147 0.0353580000 249308134 95654144 760807424 -0.0454404727 -0.0170366708 0.0357487537 2473 1311867252.9446918964 0.0620804392 0.0607119848 0.0875933766 0.0058042266 0.0405890000 249309942 95654144 760807424 -0.0440896638 -0.0200381950 0.0348410457 2474 1311867252.9806020260 0.0624241196 0.0607126768 0.0875933766 0.0058049309 0.0352760000 249313718 95654144 760807424 -0.0434562005 -0.0176942740 0.0310450234 2475 1311867253.0113809109 0.0612684377 0.0607129014 0.0875933766 0.0058045033 0.0350790000 249315398 95654144 760807424 -0.0429403149 -0.0163482334 0.0270575546 2476 1311867253.0434310436 0.0621597618 0.0607134857 0.0875933766 0.0058038295 0.0354880000 249319062 95654144 760807424 -0.0423585176 -0.0210171901 0.0265473966 2477 1311867253.0799300671 0.0616218075 0.0607138524 0.0875933766 0.0058084540 0.0354200000 249323038 95654144 760807424 -0.0411211662 -0.0193958655 0.0226755254 2478 1311867253.1113030910 0.0607491285 0.0607138667 0.0875933766 0.0058089520 0.0411520000 249324646 95654144 760807424 -0.0396143049 -0.0177799705 0.0182684641 2479 1311867253.1440761089 0.0609753877 0.0607139722 0.0875933766 0.0058084945 0.0326030000 249328318 95654144 760807424 -0.0407694541 -0.0212268271 0.0162540991 2480 1311867253.1794049740 0.0612316541 0.0607141809 0.0875933766 0.0058074100 0.0293090000 249501466 95654144 760807424 -0.0413706750 -0.0208518337 0.0131329708 2481 1311867253.2112159729 0.0614403598 0.0607144736 0.0875933766 0.0058067262 0.0326270000 249503394 95654144 760807424 -0.0397589877 -0.0187492594 0.0101117315 2482 1311867253.2458410263 0.0606826805 0.0607144608 0.0875933766 0.0058059269 0.0293280000 249506922 95654144 760807424 -0.0390147455 -0.0189831164 0.0069498690 2483 1311867253.2793951035 0.0608606413 0.0607145197 0.0875933766 0.0058048031 0.0293590000 249508794 95654144 760807424 -0.0382979363 -0.0206581745 0.0048469836 2484 1311867253.3114080429 0.0603406914 0.0607143692 0.0875933766 0.0058036881 0.0294560000 249512322 95654144 760807424 -0.0360711589 -0.0203492492 0.0024089715 2485 1311867253.3445611000 0.0600136444 0.0607140872 0.0875933766 0.0058093770 0.0293910000 249516050 95654144 760807424 -0.0356948413 -0.0221407507 0.0004495496 2486 1311867253.3794078827 0.0604891479 0.0607139967 0.0875933766 0.0058134198 0.0293290000 249517722 95654144 760807424 -0.0347991362 -0.0223023165 -0.0017271331 2487 1311867253.4129528999 0.0602258518 0.0607138004 0.0875933766 0.0058139396 0.0295810000 249521506 95654144 760807424 -0.0333518013 -0.0220599435 -0.0043754382 2488 1311867253.4444990158 0.0596122108 0.0607133577 0.0875933766 0.0058132192 0.0293010000 249523122 95654144 760807424 -0.0300665535 -0.0223234091 -0.0068387087 2489 1311867253.4804859161 0.0601402819 0.0607131274 0.0875933766 0.0058129855 0.0354430000 249527546 95654144 760807424 -0.0295049101 -0.0220592953 -0.0091122100 2490 1311867253.5113739967 0.0600648299 0.0607128671 0.0875933766 0.0058125635 0.0355810000 249531338 95654144 760807424 -0.0286780931 -0.0257384162 -0.0102302348 2491 1311867253.5441629887 0.0603572428 0.0607127243 0.0875933766 0.0058117940 0.0350660000 249533090 95654144 760807424 -0.0275387187 -0.0245622303 -0.0128938621 2492 1311867253.5794069767 0.0598841123 0.0607123918 0.0875933766 0.0058109686 0.0374150000 249536866 95654144 760807424 -0.0269885957 -0.0247472879 -0.0161238499 2493 1311867253.6118021011 0.0601426028 0.0607121632 0.0875933766 0.0058099120 0.0370940000 249538858 95654144 760807424 -0.0271627847 -0.0268639326 -0.0178852901 2494 1311867253.6447649002 0.0606217794 0.0607121270 0.0875933766 0.0058091935 0.0372140000 249542266 95654144 760807424 -0.0250829905 -0.0254792441 -0.0208062325 2495 1311867253.6799790859 0.0604285188 0.0607120133 0.0875933766 0.0058084047 0.0371990000 249546242 95654144 760807424 -0.0243379809 -0.0265722163 -0.0237511992 2496 1311867253.7115769386 0.0611394458 0.0607121846 0.0875933766 0.0058083597 0.0377190000 249547722 95654144 760807424 -0.0257848166 -0.0288659669 -0.0258400440 2497 1311867253.7435369492 0.0609275252 0.0607122708 0.0875933766 0.0058088723 0.0373950000 249551658 95654144 760807424 -0.0249364488 -0.0314980671 -0.0285943132 2498 1311867253.7806150913 0.0602073595 0.0607120687 0.0875933766 0.0058084731 0.0375250000 249555050 95654144 760807424 -0.0263878945 -0.0328020714 -0.0335405581 2499 1311867253.8113009930 0.0597181506 0.0607116710 0.0875933766 0.0058075017 0.0375710000 249556858 95654144 760807424 -0.0274442490 -0.0330531821 -0.0376629382 2500 1311867253.8469560146 0.0597761348 0.0607112967 0.0875933766 0.0058068405 0.0376280000 249560634 95654144 760807424 -0.0294270441 -0.0351300128 -0.0413219295 2501 1311867253.8792059422 0.0596064664 0.0607108550 0.0875933766 0.0058058594 0.0368490000 249562386 95654144 760807424 -0.0311951973 -0.0372190140 -0.0448255576 2502 1311867253.9114460945 0.0594072267 0.0607103339 0.0875933766 0.0058051257 0.0374710000 249566050 95654144 760807424 -0.0330770612 -0.0364817977 -0.0495793112 2503 1311867253.9461600780 0.0592727289 0.0607097596 0.0875933766 0.0058040654 0.0377240000 249570026 95654144 760807424 -0.0330490135 -0.0368758887 -0.0536234938 2504 1311867253.9794149399 0.0599320382 0.0607094490 0.0875933766 0.0058030156 0.0357370000 249571834 95654144 760807424 -0.0350928083 -0.0375645198 -0.0564102679 2505 1311867254.0119979382 0.0590247735 0.0607087765 0.0875933766 0.0058027696 0.0418400000 249575370 95654144 760807424 -0.0373175517 -0.0396403223 -0.0603374951 2506 1311867254.0457749367 0.0593416020 0.0607082309 0.0875933766 0.0058016355 0.0354260000 249747422 95654144 760807424 -0.0384079702 -0.0393723547 -0.0633165613 2507 1311867254.0793740749 0.0602770001 0.0607080589 0.0875933766 0.0058029984 0.0352910000 249751094 95654144 760807424 -0.0407491960 -0.0406962819 -0.0658154339 2508 1311867254.1113519669 0.0599386059 0.0607077521 0.0875933766 0.0058022125 0.0411490000 249754502 95654144 760807424 -0.0412310809 -0.0411933921 -0.0689840391 2509 1311867254.1476950645 0.0601369813 0.0607075246 0.0875933766 0.0058011399 0.0405830000 249756478 95654144 760807424 -0.0422251597 -0.0402310491 -0.0727756992 2510 1311867254.1795129776 0.0600596331 0.0607072665 0.0875933766 0.0058002063 0.0356160000 249759830 95654144 760807424 -0.0414968580 -0.0412754491 -0.0753241405 2511 1311867254.2114939690 0.0580984913 0.0607062276 0.0875933766 0.0058042216 0.0353740000 249761822 95654144 760807424 -0.0414822102 -0.0416189581 -0.0792501867 2512 1311867254.2469160557 0.0584097169 0.0607053133 0.0875933766 0.0058043155 0.0362330000 249765598 95654144 760807424 -0.0414590575 -0.0403417274 -0.0832535103 2513 1311867254.2798569202 0.0583785586 0.0607043875 0.0875933766 0.0058040710 0.0355960000 249769406 95654144 760807424 -0.0403248668 -0.0371269286 -0.0882945582 2514 1311867254.3114631176 0.0584547482 0.0607034926 0.0875933766 0.0058069834 0.0356470000 249771014 95654144 760807424 -0.0426470451 -0.0378731303 -0.0910951197 2515 1311867254.3475589752 0.0594864674 0.0607030087 0.0875933766 0.0058069574 0.0476900000 249775046 95654144 760807424 -0.0425334238 -0.0420017764 -0.0922045484 2516 1311867254.3794488907 0.0598536432 0.0607026711 0.0875933766 0.0058059534 0.0358870000 249778526 95654144 760807424 -0.0433828533 -0.0409624167 -0.0964045525 2517 1311867254.4115350246 0.0600967221 0.0607024304 0.0875933766 0.0058098089 0.0358460000 249780134 95654144 760807424 -0.0442306660 -0.0372848734 -0.1022465453 2518 1311867254.4483439922 0.0605547689 0.0607023717 0.0875933766 0.0058089593 0.0358530000 249783782 95654144 760807424 -0.0481358543 -0.0391962752 -0.1064073965 2519 1311867254.4794480801 0.0612810925 0.0607026015 0.0875933766 0.0058079601 0.0290890000 249785598 95654144 760807424 -0.0493746884 -0.0403071120 -0.1089468747 2520 1311867254.5114428997 0.0607208237 0.0607026087 0.0875933766 0.0058068214 0.0359720000 249789454 95654144 760807424 -0.0500445627 -0.0386250690 -0.1138961762 2521 1311867254.5500459671 0.0609596260 0.0607027107 0.0875933766 0.0058065892 0.0329380000 249793294 95654144 760807424 -0.0512193628 -0.0371242799 -0.1191019490 2522 1311867254.5794870853 0.0612448230 0.0607029256 0.0875933766 0.0058082672 0.0355410000 249794782 95654144 760807424 -0.0511748344 -0.0361339301 -0.1223763973 2523 1311867254.6114809513 0.0606895424 0.0607029203 0.0875933766 0.0058073549 0.0330140000 249798454 95654144 760807424 -0.0509058386 -0.0324322991 -0.1276526451 2524 1311867254.6452929974 0.0602253452 0.0607027311 0.0875933766 0.0058072070 0.0291190000 249800182 95654144 760807424 -0.0520023443 -0.0330478959 -0.1315794885 2525 1311867254.6794900894 0.0606271848 0.0607027012 0.0875933766 0.0058071204 0.0291150000 249803966 95654144 760807424 -0.0531624779 -0.0345592722 -0.1341433376 2526 1311867254.7113230228 0.0604157038 0.0607025876 0.0875933766 0.0058063073 0.0324230000 249807438 95654144 760807424 -0.0519444570 -0.0324666612 -0.1379852146 2527 1311867254.7453329563 0.0602772832 0.0607024192 0.0875933766 0.0058074118 0.0291280000 249809310 95654144 760807424 -0.0513909720 -0.0305886008 -0.1424236596 2528 1311867254.7794649601 0.0606927201 0.0607024154 0.0875933766 0.0058097337 0.0413990000 249812838 95654144 760807424 -0.0524393991 -0.0295856670 -0.1464178711 2529 1311867254.8115739822 0.0600892343 0.0607021730 0.0875933766 0.0058089359 0.0291910000 249814710 95654144 760807424 -0.0520192124 -0.0305382181 -0.1495068967 2530 1311867254.8482780457 0.0599927232 0.0607018925 0.0875933766 0.0058096884 0.0291020000 249818406 95654144 760807424 -0.0510899723 -0.0289259423 -0.1531932950 2531 1311867254.8794910908 0.0601185262 0.0607016620 0.0875933766 0.0058088411 0.0290750000 249821966 95654144 760807424 -0.0489044636 -0.0278178100 -0.1561276913 2532 1311867254.9138929844 0.0610664599 0.0607018061 0.0875933766 0.0058084701 0.0296300000 249823694 95654144 760807424 -0.0494312085 -0.0287898928 -0.1573974341 2533 1311867254.9490759373 0.0610098913 0.0607019278 0.0875933766 0.0058078921 0.0290510000 249827478 95654144 760807424 -0.0502336770 -0.0274686981 -0.1612453759 2534 1311867254.9819579124 0.0610591955 0.0607020687 0.0875933766 0.0058070338 0.0330830000 249831006 95654144 760807424 -0.0499668010 -0.0254866779 -0.1649003774 2535 1311867255.0154359341 0.0603875183 0.0607019447 0.0875933766 0.0058078540 0.0415120000 249832878 95654144 760807424 -0.0492626987 -0.0274434239 -0.1668920070 2536 1311867255.0494379997 0.0600027256 0.0607016689 0.0875933766 0.0058069163 0.0291490000 249836406 95654144 760807424 -0.0478980951 -0.0261728261 -0.1704313010 2537 1311867255.0822079182 0.0602183789 0.0607014784 0.0875933766 0.0058058828 0.0291800000 249838278 95654144 760807424 -0.0491331629 -0.0237425901 -0.1736836284 2538 1311867255.1176838875 0.0609129108 0.0607015618 0.0875933766 0.0058047482 0.0290450000 249841750 95654144 760807424 -0.0496136770 -0.0238042139 -0.1756936163 2539 1311867255.1510150433 0.0603549257 0.0607014252 0.0875933766 0.0058044552 0.0289820000 249845422 95654144 760807424 -0.0471697263 -0.0254703723 -0.1770597994 2540 1311867255.1838800907 0.0603579655 0.0607012900 0.0875933766 0.0058040245 0.0290750000 249846982 95654144 760807424 -0.0458059125 -0.0236177221 -0.1803313941 2541 1311867255.2169129848 0.0608539209 0.0607013501 0.0875933766 0.0058039207 0.0290720000 249850654 95654144 760807424 -0.0487353019 -0.0215947572 -0.1838721335 2542 1311867255.2459371090 0.0608268231 0.0607013994 0.0875933766 0.0058032706 0.0392520000 249852270 95654144 760807424 -0.0503395982 -0.0218839366 -0.1862695515 2543 1311867255.2793660164 0.0612066239 0.0607015981 0.0875933766 0.0058112638 0.0290360000 249855942 95654144 760807424 -0.0505304486 -0.0205320567 -0.1890267879 2544 1311867255.3138630390 0.0606900193 0.0607015936 0.0875933766 0.0058105291 0.0290330000 249859470 95654144 760807424 -0.0475231931 -0.0218568221 -0.1910407990 2545 1311867255.3468410969 0.0600159243 0.0607013241 0.0875933766 0.0058103822 0.0330430000 249861398 95654144 760807424 -0.0449828506 -0.0244533382 -0.1927038729 2546 1311867255.3794751167 0.0605000854 0.0607012451 0.0875933766 0.0058095611 0.0289940000 249864870 95654144 760807424 -0.0445883311 -0.0242453068 -0.1955190897 2547 1311867255.4137639999 0.0612580515 0.0607014637 0.0875933766 0.0058127156 0.0290330000 250036570 95654144 760807424 -0.0464284569 -0.0220224243 -0.1993559003 2548 1311867255.4455530643 0.0607950799 0.0607015005 0.0875933766 0.0058117140 0.0289560000 250040042 95654144 760807424 -0.0442847982 -0.0231566615 -0.2011758983 2549 1311867255.4794819355 0.0608725101 0.0607015675 0.0875933766 0.0058119823 0.0383110000 250043770 95654144 760807424 -0.0451598987 -0.0234288238 -0.2047459781 2550 1311867255.5156099796 0.0619166270 0.0607020440 0.0875933766 0.0058130044 0.0290990000 250045554 95654144 760807424 -0.0442710817 -0.0209862776 -0.2083497792 2551 1311867255.5457780361 0.0608943626 0.0607021194 0.0875933766 0.0058141480 0.0290370000 250049170 95654144 760807424 -0.0447130278 -0.0222660434 -0.2109184116 2552 1311867255.5794420242 0.0605434217 0.0607020572 0.0875933766 0.0058131968 0.0290020000 250052642 95654144 760807424 -0.0434631780 -0.0241267178 -0.2137398720 2553 1311867255.6153330803 0.0607293099 0.0607020679 0.0875933766 0.0058136852 0.0289400000 250054626 95654144 760807424 -0.0420402251 -0.0211549066 -0.2179015875 2554 1311867255.6456480026 0.0610974319 0.0607022227 0.0875933766 0.0058134219 0.0288660000 250058098 95654144 760807424 -0.0398848802 -0.0179621261 -0.2215355188 2555 1311867255.6801021099 0.0610476509 0.0607023579 0.0875933766 0.0058129497 0.0323010000 250060026 95654144 760807424 -0.0399342328 -0.0210732147 -0.2225506157 2556 1311867255.7182919979 0.0605368279 0.0607022931 0.0875933766 0.0058137641 0.0401210000 250063666 95654144 760807424 -0.0399988256 -0.0227427557 -0.2255888581 2557 1311867255.7457749844 0.0612028837 0.0607024889 0.0875933766 0.0058134238 0.0291750000 250067226 95654144 760807424 -0.0387212783 -0.0172066335 -0.2307883352 2558 1311867255.7810928822 0.0615574308 0.0607028231 0.0875933766 0.0058156758 0.0288870000 250068954 95654144 760807424 -0.0379068926 -0.0167205781 -0.2338227779 2559 1311867255.8176100254 0.0602364056 0.0607026409 0.0875933766 0.0058200331 0.0288960000 250072738 95654144 760807424 -0.0383425467 -0.0219465215 -0.2347282171 2560 1311867255.8457250595 0.0608572848 0.0607027013 0.0875933766 0.0058202386 0.0289000000 250074298 95654144 760807424 -0.0402105339 -0.0187270306 -0.2389378399 2561 1311867255.8793790340 0.0618026219 0.0607031308 0.0875933766 0.0058192954 0.0327140000 250078026 95654144 760807424 -0.0396551490 -0.0156911425 -0.2427761257 2562 1311867255.9140310287 0.0617729835 0.0607035484 0.0875933766 0.0058182508 0.0290170000 250251938 95654144 760807424 -0.0398107953 -0.0180191416 -0.2440872043 2563 1311867255.9459080696 0.0609588362 0.0607036480 0.0875933766 0.0058172047 0.0391320000 250253810 95654144 760807424 -0.0410063118 -0.0220398102 -0.2452146858 2564 1311867255.9794859886 0.0605308600 0.0607035806 0.0875933766 0.0058160808 0.0289790000 250257282 95654144 760807424 -0.0405043587 -0.0205589868 -0.2500226200 2565 1311867256.0177969933 0.0601792522 0.0607033762 0.0875933766 0.0058151625 0.0329540000 250259378 95654144 760807424 -0.0394937471 -0.0206660330 -0.2529250681 2566 1311867256.0460140705 0.0601001456 0.0607031411 0.0875933766 0.0058145448 0.0294130000 250262738 95654144 760807424 -0.0417098217 -0.0214730538 -0.2553013265 2567 1311867256.0856881142 0.0602278113 0.0607029559 0.0875933766 0.0058184436 0.0296740000 250266578 95654144 760807424 -0.0421215966 -0.0207820479 -0.2587678730 2568 1311867256.1167299747 0.0610857829 0.0607031050 0.0875933766 0.0058191673 0.0296850000 250268250 95654144 760807424 -0.0398663916 -0.0182647090 -0.2619702816 2569 1311867256.1452269554 0.0611993223 0.0607032981 0.0875933766 0.0058195605 0.0297050000 250271810 95654144 760807424 -0.0417664722 -0.0174411982 -0.2646965683 2570 1311867256.1795060635 0.0624541603 0.0607039794 0.0875933766 0.0058209152 0.0295450000 250275394 95654144 760807424 -0.0445200056 -0.0189047828 -0.2659723461 2571 1311867256.2177491188 0.0614661127 0.0607042758 0.0875933766 0.0058212986 0.0297240000 250277434 95654144 760807424 -0.0437377878 -0.0195391010 -0.2694759071 2572 1311867256.2454690933 0.0618854985 0.0607047351 0.0875933766 0.0058207529 0.0296700000 250280738 95654144 760807424 -0.0426933393 -0.0187203251 -0.2722168565 2573 1311867256.2847039700 0.0633225515 0.0607057525 0.0875933766 0.0058201477 0.0300290000 250282834 95654144 760807424 -0.0458653569 -0.0192784667 -0.2746718824 2574 1311867256.3143420219 0.0631261691 0.0607066929 0.0875933766 0.0058220978 0.0331030000 250456866 95654144 760807424 -0.0474871024 -0.0205676015 -0.2777320147 2575 1311867256.3471789360 0.0623675548 0.0607073378 0.0875933766 0.0058224270 0.0288910000 250460594 95654144 760807424 -0.0455095842 -0.0198486838 -0.2824995220 2576 1311867256.3848650455 0.0632116422 0.0607083100 0.0875933766 0.0058216701 0.0289930000 250462378 95654144 760807424 -0.0449151210 -0.0213849396 -0.2848982811 2577 1311867256.4158649445 0.0620727502 0.0607088395 0.0875933766 0.0058207422 0.0288120000 250465994 95654144 760807424 -0.0464633405 -0.0226419717 -0.2895273566 2578 1311867256.4452838898 0.0620492101 0.0607093594 0.0875933766 0.0058221901 0.0407840000 250467610 95654144 760807424 -0.0495298132 -0.0212008599 -0.2954888940 2579 1311867256.4844601154 0.0627955049 0.0607101683 0.0875933766 0.0058229654 0.0290980000 250471450 95654144 760807424 -0.0508663952 -0.0206048191 -0.2993637323 2580 1311867256.5135829449 0.0620214418 0.0607106766 0.0875933766 0.0058223061 0.0290610000 250645706 95654144 760807424 -0.0523655675 -0.0244023837 -0.3010978103 2581 1311867256.5478789806 0.0603294782 0.0607105289 0.0875933766 0.0058413684 0.0324160000 250647634 95654144 760807424 -0.0490136296 -0.0263008699 -0.3043327034 2582 1311867256.5836489201 0.0612899400 0.0607107533 0.0875933766 0.0058527706 0.0423140000 250651274 95654144 760807424 -0.0469893068 -0.0249671303 -0.3082151115 2583 1311867256.6160368919 0.0613540299 0.0607110023 0.0875933766 0.0058518264 0.0291580000 250653090 95654144 760807424 -0.0494152494 -0.0259119906 -0.3107900918 2584 1311867256.6452310085 0.0612011254 0.0607111920 0.0875933766 0.0058509876 0.0288960000 250656506 95654144 760807424 -0.0504409969 -0.0278663803 -0.3128889501 2585 1311867256.6832759380 0.0619873106 0.0607116856 0.0875933766 0.0058500381 0.0408980000 250660402 95654144 760807424 -0.0507617705 -0.0258764401 -0.3173355758 2586 1311867256.7140300274 0.0623868778 0.0607123334 0.0875933766 0.0058493378 0.0290470000 250661962 95654144 760807424 -0.0503563359 -0.0234685745 -0.3210701942 2587 1311867256.7463369370 0.0609434135 0.0607124228 0.0875933766 0.0058482444 0.0289260000 250665634 95654144 760807424 -0.0517574102 -0.0261726100 -0.3237242401 2588 1311867256.7827401161 0.0621862747 0.0607129923 0.0875933766 0.0058479319 0.0288710000 250669274 95654144 760807424 -0.0483758189 -0.0233825762 -0.3269238174 2589 1311867256.8140430450 0.0610791110 0.0607131337 0.0875933766 0.0058478052 0.0288950000 250671090 95654144 760807424 -0.0473899171 -0.0260067489 -0.3289916515 2590 1311867256.8477399349 0.0619720705 0.0607136197 0.0875933766 0.0058469490 0.0289730000 250674618 95654144 760807424 -0.0513573587 -0.0291123465 -0.3305468261 2591 1311867256.8838980198 0.0610305816 0.0607137421 0.0875933766 0.0058481187 0.0289370000 250676546 95654144 760807424 -0.0470647775 -0.0293679871 -0.3346122801 2592 1311867256.9148108959 0.0609586649 0.0607138366 0.0875933766 0.0058470839 0.0339720000 250680018 95654144 760807424 -0.0460920334 -0.0277809091 -0.3394307494 2593 1311867256.9465379715 0.0609195679 0.0607139159 0.0875933766 0.0058462148 0.0289950000 250683690 95654144 760807424 -0.0469251275 -0.0295901969 -0.3427157402 2594 1311867256.9814610481 0.0608100817 0.0607139530 0.0875933766 0.0058452645 0.0288810000 250855910 95654144 760807424 -0.0462809317 -0.0316851772 -0.3453590274 2595 1311867257.0129959583 0.0596849509 0.0607135564 0.0875933766 0.0058443951 0.0289360000 250859638 95654144 760807424 -0.0452218279 -0.0329718478 -0.3497437835 2596 1311867257.0451910496 0.0599784330 0.0607132733 0.0875933766 0.0058447189 0.0289850000 250861254 95654144 760807424 -0.0436452068 -0.0292907506 -0.3555545211 2597 1311867257.0841369629 0.0609054044 0.0607133473 0.0875933766 0.0058439262 0.0286920000 250865094 95654144 760807424 -0.0435020626 -0.0273635332 -0.3597973287 2598 1311867257.1134428978 0.0610033758 0.0607134589 0.0875933766 0.0058429722 0.0288250000 250868566 95654144 760807424 -0.0443393439 -0.0288939551 -0.3610826433 2599 1311867257.1474308968 0.0629525855 0.0607143204 0.0875933766 0.0058424181 0.0348140000 250870494 95654144 760807424 -0.0434329957 -0.0255158395 -0.3642767072 2600 1311867257.1821229458 0.0633463189 0.0607153327 0.0875933766 0.0058414423 0.0287170000 250874022 95654144 760807424 -0.0427842289 -0.0242337901 -0.3674684465 2601 1311867257.2147839069 0.0624160096 0.0607159866 0.0875933766 0.0058435510 0.0288830000 250875894 95654144 760807424 -0.0420524254 -0.0272198692 -0.3684133887 2602 1311867257.2457039356 0.0629405752 0.0607168415 0.0875933766 0.0058465971 0.0288240000 250879310 95654144 760807424 -0.0431623533 -0.0266592596 -0.3716173470 2603 1311867257.2824490070 0.0643111765 0.0607182224 0.0875933766 0.0058455951 0.0287840000 250883150 95654144 760807424 -0.0416335203 -0.0218663923 -0.3767413795 2604 1311867257.3133430481 0.0634703189 0.0607192793 0.0875933766 0.0058448462 0.0290900000 251055274 95654144 760807424 -0.0404223092 -0.0229975022 -0.3792519867 2605 1311867257.3452849388 0.0635181889 0.0607203537 0.0875933766 0.0058445360 0.0324010000 251058890 95654144 760807424 -0.0397993065 -0.0235002972 -0.3812211156 2606 1311867257.3839631081 0.0636120886 0.0607214633 0.0875933766 0.0058441688 0.0315390000 251062530 95654144 760807424 -0.0403510407 -0.0225412734 -0.3850851655 2607 1311867257.4198129177 0.0648433045 0.0607230444 0.0875933766 0.0058455786 0.0288040000 251064514 95654144 760807424 -0.0377419740 -0.0194582082 -0.3888584375 2608 1311867257.4458611012 0.0643529817 0.0607244363 0.0875933766 0.0058457033 0.0326560000 251067818 95654144 760807424 -0.0365852602 -0.0203735270 -0.3901760876 2609 1311867257.4851269722 0.0647721663 0.0607259877 0.0875933766 0.0058449273 0.0288550000 251069914 95654144 760807424 -0.0376407430 -0.0198962037 -0.3931158483 2610 1311867257.5166249275 0.0664652959 0.0607281867 0.0875933766 0.0058444118 0.0320570000 251073386 95654144 760807424 -0.0356254168 -0.0148173515 -0.3975194991 2611 1311867257.5537879467 0.0661230758 0.0607302529 0.0875933766 0.0058440614 0.0290050000 251246950 95654144 760807424 -0.0344272256 -0.0166336298 -0.3987851143 2612 1311867257.5836200714 0.0663607568 0.0607324085 0.0875933766 0.0058498188 0.0287380000 251248566 95654144 760807424 -0.0360854454 -0.0165710337 -0.4009189606 2613 1311867257.6154460907 0.0669404417 0.0607347843 0.0875933766 0.0058532811 0.0323350000 251252182 95654144 760807424 -0.0364770405 -0.0137612838 -0.4051367939 2614 1311867257.6519720554 0.0687447712 0.0607378486 0.0875933766 0.0058523202 0.0328730000 251254022 95654144 760807424 -0.0359379426 -0.0100615602 -0.4079060853 2615 1311867257.6842958927 0.0669370741 0.0607402192 0.0875933766 0.0058514519 0.0288180000 251257694 95654144 760807424 -0.0342767946 -0.0127406549 -0.4093713164 2616 1311867257.7187778950 0.0662110969 0.0607423106 0.0875933766 0.0058509215 0.0288100000 251261278 95654144 760807424 -0.0347302184 -0.0145305172 -0.4105786979 2617 1311867257.7527809143 0.0658701062 0.0607442700 0.0875933766 0.0058512056 0.0288370000 251433042 95654144 760807424 -0.0310121626 -0.0142980954 -0.4125922322 2618 1311867257.7838430405 0.0667683557 0.0607465710 0.0875933766 0.0058512079 0.0288120000 251436514 95654144 760807424 -0.0318587907 -0.0121554574 -0.4154821336 2619 1311867257.8181409836 0.0665901452 0.0607488022 0.0875933766 0.0058507085 0.0289110000 251438442 95654144 760807424 -0.0333473720 -0.0124538923 -0.4175735712 2620 1311867257.8530700207 0.0688917041 0.0607519102 0.0875933766 0.0058570710 0.0329180000 251441970 95654144 760807424 -0.0323891751 -0.0089177648 -0.4201580882 2621 1311867257.8854579926 0.0680606738 0.0607546987 0.0875933766 0.0058587805 0.0288720000 251445586 95654144 760807424 -0.0307664163 -0.0101937791 -0.4218661785 2622 1311867257.9152529240 0.0670692548 0.0607571070 0.0875933766 0.0058592185 0.0287660000 251447202 95654144 760807424 -0.0270575918 -0.0113660954 -0.4233437479 2623 1311867257.9559030533 0.0670463294 0.0607595048 0.0875933766 0.0058582119 0.0288090000 251451154 95654144 760807424 -0.0287099872 -0.0125549501 -0.4248776734 2624 1311867257.9850780964 0.0666018501 0.0607617313 0.0875933766 0.0058573094 0.0288230000 251454514 95654144 760807424 -0.0293863844 -0.0135070644 -0.4265449941 2625 1311867258.0135710239 0.0656152517 0.0607635802 0.0875933766 0.0058564047 0.0288380000 251456330 95654144 760807424 -0.0263101775 -0.0158398021 -0.4270899296 2626 1311867258.0526609421 0.0670659468 0.0607659802 0.0875933766 0.0058573154 0.0297250000 251459970 95654144 760807424 -0.0262014549 -0.0160363652 -0.4276115894 2627 1311867258.0836610794 0.0688543767 0.0607690592 0.0875933766 0.0058577676 0.0333760000 251461786 95654144 760807424 -0.0264618136 -0.0151814222 -0.4283389151 2628 1311867258.1137859821 0.0675298721 0.0607716318 0.0875933766 0.0058574079 0.0287370000 251465258 95654144 760807424 -0.0264593270 -0.0165949836 -0.4308844209 2629 1311867258.1501069069 0.0669515654 0.0607739824 0.0875933766 0.0058570948 0.0288610000 251468986 95654144 760807424 -0.0240911767 -0.0164651889 -0.4339495003 2630 1311867258.1848480701 0.0689591020 0.0607770947 0.0875933766 0.0058561984 0.0287930000 251640406 95654144 760807424 -0.0232783891 -0.0142821847 -0.4356020391 2631 1311867258.2162730694 0.0692663565 0.0607803213 0.0875933766 0.0058551842 0.0288150000 251644134 95654144 760807424 -0.0229878575 -0.0151312016 -0.4364318848 2632 1311867258.2524979115 0.0690446272 0.0607834612 0.0875933766 0.0058568237 0.0288330000 251645918 95654144 760807424 -0.0225007068 -0.0169378240 -0.4368052781 2633 1311867258.2857830524 0.0672727749 0.0607859258 0.0875933766 0.0058565210 0.0287730000 251649590 95654144 760807424 -0.0203260835 -0.0193204600 -0.4383585751 2634 1311867258.3132910728 0.0674585477 0.0607884591 0.0875933766 0.0058554171 0.0365750000 251653006 95654144 760807424 -0.0190049987 -0.0202331562 -0.4384962320 2635 1311867258.3510708809 0.0683967620 0.0607913465 0.0875933766 0.0058574472 0.0287530000 251654990 95654144 760807424 -0.0214054734 -0.0197006948 -0.4398131967 2636 1311867258.3812119961 0.0678111017 0.0607940095 0.0875933766 0.0058571615 0.0288300000 251658350 95654144 760807424 -0.0211359821 -0.0191191025 -0.4421948493 2637 1311867258.4142711163 0.0685098991 0.0607969355 0.0875933766 0.0058563077 0.0294190000 251660222 95654144 760807424 -0.0203918349 -0.0188927222 -0.4425110817 2638 1311867258.4507009983 0.0689922422 0.0608000422 0.0875933766 0.0058561184 0.0288340000 251663862 95654144 760807424 -0.0213153157 -0.0187584534 -0.4432157278 2639 1311867258.4826059341 0.0670809597 0.0608024222 0.0875933766 0.0058561045 0.0287610000 251667590 95654144 760807424 -0.0196146779 -0.0216891915 -0.4436531961 2640 1311867258.5139899254 0.0663847476 0.0608045367 0.0875933766 0.0058567428 0.0288260000 251669206 95654144 760807424 -0.0207451414 -0.0248097666 -0.4432823956 2641 1311867258.5500509739 0.0668398291 0.0608068220 0.0875933766 0.0058661298 0.0410040000 251672990 95654144 760807424 -0.0198244043 -0.0254585519 -0.4432819486 2642 1311867258.5836040974 0.0665029362 0.0608089779 0.0875933766 0.0058704960 0.0290100000 251676462 95654144 760807424 -0.0195387509 -0.0258473642 -0.4458509386 2643 1311867258.6141679287 0.0674721897 0.0608114990 0.0875933766 0.0058701857 0.0321420000 251678278 95654144 760807424 -0.0183260683 -0.0255180467 -0.4467779994 2644 1311867258.6506860256 0.0677318200 0.0608141164 0.0875933766 0.0058694919 0.0328150000 251681862 95654144 760807424 -0.0178507287 -0.0247466043 -0.4499289393 2645 1311867258.6856470108 0.0679365247 0.0608168092 0.0875933766 0.0058690902 0.0288980000 251683846 95654144 760807424 -0.0183998849 -0.0274668373 -0.4500312209 2646 1311867258.7134239674 0.0678592324 0.0608194707 0.0875933766 0.0058681249 0.0288670000 251687150 95654144 760807424 -0.0177445039 -0.0282624904 -0.4524180889 2647 1311867258.7543559074 0.0691489801 0.0608226175 0.0875933766 0.0058680837 0.0289020000 251860814 95654144 760807424 -0.0146045107 -0.0264516510 -0.4557861686 2648 1311867258.7843589783 0.0692338943 0.0608257940 0.0875933766 0.0058680110 0.0342290000 251862430 95654144 760807424 -0.0144513883 -0.0258577354 -0.4586506188 2649 1311867258.8193690777 0.0676714033 0.0608283782 0.0875933766 0.0058669775 0.0289560000 251866214 95654144 760807424 -0.0174742825 -0.0304889902 -0.4591720104 2650 1311867258.8514409065 0.0676718950 0.0608309606 0.0875933766 0.0058659889 0.0288410000 251867942 95654144 760807424 -0.0166137163 -0.0297816917 -0.4622814357 2651 1311867258.8846011162 0.0682009310 0.0608337407 0.0875933766 0.0058654148 0.0288480000 251871558 95654144 760807424 -0.0149081340 -0.0297998004 -0.4640551209 2652 1311867258.9178969860 0.0671592504 0.0608361259 0.0875933766 0.0058646138 0.0288520000 251875086 95654144 760807424 -0.0127843097 -0.0327300765 -0.4647535384 2653 1311867258.9506199360 0.0677058622 0.0608387153 0.0875933766 0.0058643215 0.0287830000 251876958 95654144 760807424 -0.0131914550 -0.0327490978 -0.4669092894 2654 1311867258.9841670990 0.0688233078 0.0608417238 0.0875933766 0.0058640303 0.0287860000 251880542 95654144 760807424 -0.0115980022 -0.0304553844 -0.4708648920 2655 1311867259.0194389820 0.0686737597 0.0608446737 0.0875933766 0.0058633674 0.0387520000 251882414 95654144 760807424 -0.0107195927 -0.0324540362 -0.4718525410 2656 1311867259.0497961044 0.0682746693 0.0608474712 0.0875933766 0.0058648977 0.0288070000 251885886 95654144 760807424 -0.0058809323 -0.0347652398 -0.4727972746 2657 1311867259.0845470428 0.0677584559 0.0608500722 0.0875933766 0.0058644174 0.0288050000 251889558 95654144 760807424 -0.0056281779 -0.0344177037 -0.4769836068 2658 1311867259.1189930439 0.0684203655 0.0608529203 0.0875933766 0.0058636179 0.0290460000 251891342 95654144 760807424 -0.0043469863 -0.0328143612 -0.4801391661 2659 1311867259.1506030560 0.0686820298 0.0608558647 0.0875933766 0.0058644034 0.0288620000 251895014 95654144 760807424 -0.0031721178 -0.0344821699 -0.4802673459 2660 1311867259.1837821007 0.0695837066 0.0608591459 0.0875933766 0.0058644542 0.0321300000 251898486 95654144 760807424 -0.0010998291 -0.0317646228 -0.4842896163 2661 1311867259.2191979885 0.0700006783 0.0608625812 0.0875933766 0.0058633600 0.0328740000 251900526 95654144 760807424 0.0012730777 -0.0308553781 -0.4868020415 2662 1311867259.2532899380 0.0703131258 0.0608661314 0.0875933766 0.0058622822 0.0322300000 251904054 95654144 760807424 0.0031044320 -0.0337732360 -0.4865334034 2663 1311867259.2815980911 0.0684031099 0.0608689617 0.0875933766 0.0058619308 0.0288060000 251905814 95654144 760807424 0.0048627341 -0.0348657779 -0.4901018739 2664 1311867259.3212718964 0.0704747438 0.0608725674 0.0875933766 0.0058625535 0.0287370000 251909510 95654144 760807424 0.0072282446 -0.0311905369 -0.4939941764 2665 1311867259.3519039154 0.0700509548 0.0608760115 0.0875933766 0.0058630124 0.0288530000 251913182 95654144 760807424 0.0062699243 -0.0319815576 -0.4969070554 2666 1311867259.3840188980 0.0706203952 0.0608796666 0.0875933766 0.0058621245 0.0322630000 252084470 95654144 760807424 0.0082562873 -0.0330654047 -0.4982278645 2667 1311867259.4204289913 0.0708271265 0.0608833964 0.0875933766 0.0058630084 0.0329220000 252088254 95654144 760807424 0.0120003037 -0.0334435813 -0.5014393926 2668 1311867259.4579179287 0.0707332417 0.0608870882 0.0875933766 0.0058619408 0.0287770000 252090094 95654144 760807424 0.0129604321 -0.0335485190 -0.5051366687 2669 1311867259.4850549698 0.0703689381 0.0608906408 0.0875933766 0.0058625359 0.0292150000 252093542 95654144 760807424 0.0145525988 -0.0342064612 -0.5081284046 2670 1311867259.5189819336 0.0698392764 0.0608939924 0.0875933766 0.0058616523 0.0396200000 252097070 95654144 760807424 0.0143484622 -0.0353288352 -0.5118904114 2671 1311867259.5505928993 0.0701802894 0.0608974691 0.0875933766 0.0058606394 0.0328840000 252268798 95654144 760807424 0.0149059277 -0.0359324217 -0.5147477388 2672 1311867259.5823240280 0.0712222978 0.0609013332 0.0875933766 0.0058600504 0.0293330000 252272326 95654144 760807424 0.0195436310 -0.0343818069 -0.5186237097 2673 1311867259.6192719936 0.0717892423 0.0609054065 0.0875933766 0.0058607274 0.0296450000 252274254 95654144 760807424 0.0202823002 -0.0344447345 -0.5221595168 2674 1311867259.6494839191 0.0727988929 0.0609098543 0.0875933766 0.0058599267 0.0296480000 252277614 95654144 760807424 0.0204071179 -0.0323237032 -0.5263120532 2675 1311867259.6828589439 0.0750228912 0.0609151302 0.0875933766 0.0058597137 0.0295840000 252281342 95654144 760807424 0.0232603475 -0.0284333304 -0.5304772854 2676 1311867259.7201991081 0.0728320479 0.0609195834 0.0875933766 0.0058589615 0.0296470000 252283182 95654144 760807424 0.0238129310 -0.0325407758 -0.5315148234 2677 1311867259.7557690144 0.0717435107 0.0609236267 0.0875933766 0.0058582273 0.0296480000 252286966 95654144 760807424 0.0234459788 -0.0340390429 -0.5341646671 2678 1311867259.7817859650 0.0730910972 0.0609281702 0.0875933766 0.0058576386 0.0295270000 252290270 95654144 760807424 0.0235443227 -0.0311820786 -0.5372152328 2679 1311867259.8177011013 0.0734650716 0.0609328499 0.0875933766 0.0058568342 0.0295490000 252292254 95654144 760807424 0.0235944204 -0.0303316694 -0.5399519205 2680 1311867259.8548939228 0.0731559619 0.0609374108 0.0875933766 0.0058559425 0.0296460000 252295838 95654144 760807424 0.0252844021 -0.0305721890 -0.5420233607 2681 1311867259.8818409443 0.0710011274 0.0609411645 0.0875933766 0.0058552187 0.0296990000 252297598 95654144 760807424 0.0223905388 -0.0341954045 -0.5429921150 2682 1311867259.9219179153 0.0734312832 0.0609458215 0.0875933766 0.0058544601 0.0295440000 252301294 95654144 760807424 0.0229466707 -0.0297158025 -0.5464941263 2683 1311867259.9520130157 0.0720116645 0.0609499460 0.0875933766 0.0058536999 0.0295690000 252304910 95654144 760807424 0.0253104586 -0.0314370990 -0.5479142070 2684 1311867259.9923639297 0.0690712184 0.0609529718 0.0875933766 0.0058530787 0.0296900000 252306806 95654144 760807424 0.0216006506 -0.0368865952 -0.5489948988 2685 1311867260.0219469070 0.0712571666 0.0609568095 0.0875933766 0.0058527507 0.0296500000 252310366 95654144 760807424 0.0236150008 -0.0320089832 -0.5527814627 2686 1311867260.0493209362 0.0716693625 0.0609607977 0.0875933766 0.0058521493 0.0296090000 252311870 95654144 760807424 0.0276968274 -0.0301024076 -0.5554274917 2687 1311867260.0888080597 0.0733541399 0.0609654101 0.0875933766 0.0058513228 0.0295310000 252315766 95654144 760807424 0.0293130260 -0.0284113102 -0.5567835569 2688 1311867260.1210498810 0.0736988783 0.0609701472 0.0875933766 0.0058559730 0.0296010000 252319238 95654144 760807424 0.0287922677 -0.0273312815 -0.5596988201 2689 1311867260.1513869762 0.0739133209 0.0609749606 0.0875933766 0.0058568087 0.0296040000 252491866 95654144 760807424 0.0291740224 -0.0258017443 -0.5631918907 2690 1311867260.1908860207 0.0757130384 0.0609804394 0.0875933766 0.0058567329 0.0293170000 252495506 95654144 760807424 0.0292918943 -0.0225845929 -0.5667888522 2691 1311867260.2204439640 0.0749908909 0.0609856459 0.0875933766 0.0058565805 0.0287270000 252497322 95654144 760807424 0.0292668417 -0.0230639204 -0.5697792172 2692 1311867260.2496669292 0.0742435232 0.0609905708 0.0875933766 0.0058557628 0.0287060000 252500794 95654144 760807424 0.0294565558 -0.0244489722 -0.5720204711 2693 1311867260.2869880199 0.0769864470 0.0609965106 0.0875933766 0.0058553380 0.0312880000 252504578 95654144 760807424 0.0325857885 -0.0182885453 -0.5777773261 2694 1311867260.3195590973 0.0765757188 0.0610022935 0.0875933766 0.0058544572 0.0287900000 252506250 95654144 760807424 0.0335589200 -0.0185535345 -0.5798220038 2695 1311867260.3505260944 0.0744571164 0.0610072860 0.0875933766 0.0058539235 0.0287550000 252509922 95654144 760807424 0.0308047067 -0.0214871969 -0.5821174383 2696 1311867260.3868899345 0.0776328817 0.0610134528 0.0875933766 0.0058558124 0.0287150000 252513506 95654144 760807424 0.0317961648 -0.0157306474 -0.5862735510 2697 1311867260.4211299419 0.0786547586 0.0610199939 0.0875933766 0.0058549743 0.0286710000 252515378 95654144 760807424 0.0329456367 -0.0129713500 -0.5895662904 2698 1311867260.4521770477 0.0776977018 0.0610261754 0.0875933766 0.0058540171 0.0286970000 252518794 95654144 760807424 0.0345937870 -0.0133212600 -0.5917629600 2699 1311867260.4867470264 0.0779595003 0.0610324493 0.0875933766 0.0058547606 0.0287430000 252520722 95654144 760807424 0.0356879421 -0.0128295086 -0.5938024521 2700 1311867260.5192930698 0.0799167007 0.0610394435 0.0875933766 0.0058567351 0.0287680000 252524082 95654144 760807424 0.0366984606 -0.0088751707 -0.5970548987 2701 1311867260.5527870655 0.0793795586 0.0610462336 0.0875933766 0.0058565412 0.0295480000 252698002 95654144 760807424 0.0367813893 -0.0090475632 -0.5991359353 2702 1311867260.5880448818 0.0794076994 0.0610530291 0.0875933766 0.0058561798 0.0288330000 252699786 95654144 760807424 0.0360969752 -0.0093184412 -0.6015144587 2703 1311867260.6196188927 0.0778420344 0.0610592403 0.0875933766 0.0058554964 0.0287450000 252703458 95654144 760807424 0.0361989886 -0.0121433772 -0.6034606695 2704 1311867260.6493411064 0.0782263801 0.0610655891 0.0875933766 0.0058545380 0.0283960000 252705018 95654144 760807424 0.0408640914 -0.0111149121 -0.6063579321 2705 1311867260.6865339279 0.0777372420 0.0610717524 0.0875933766 0.0058544327 0.0287400000 252708858 95654144 760807424 0.0429766849 -0.0149955554 -0.6078152061 2706 1311867260.7188229561 0.0765040740 0.0610774554 0.0875933766 0.0058534023 0.0287000000 252712330 95654144 760807424 0.0421752371 -0.0173099134 -0.6107044816 2707 1311867260.7493369579 0.0795267075 0.0610842708 0.0875933766 0.0058538190 0.0284310000 252714090 95654144 760807424 0.0430522151 -0.0123623759 -0.6150046587 2708 1311867260.7859649658 0.0784780383 0.0610906939 0.0875933766 0.0058558217 0.0288170000 252717730 95654144 760807424 0.0444565900 -0.0154925548 -0.6167094111 2709 1311867260.8179080486 0.0787456557 0.0610972111 0.0875933766 0.0058559644 0.0323980000 252719658 95654144 760807424 0.0485459566 -0.0159521569 -0.6199766397 2710 1311867260.8514599800 0.0774821490 0.0611032572 0.0875933766 0.0058594035 0.0327600000 252723130 95654144 760807424 0.0497965850 -0.0179280806 -0.6233766675 2711 1311867260.8867430687 0.0772639960 0.0611092183 0.0875933766 0.0058598701 0.0286260000 252726802 95654144 760807424 0.0507072881 -0.0205604639 -0.6255939007 2712 1311867260.9177849293 0.0779293254 0.0611154204 0.0875933766 0.0058597794 0.0286840000 252728474 95654144 760807424 0.0527944565 -0.0188507549 -0.6299794912 2713 1311867260.9494459629 0.0770291612 0.0611212862 0.0875933766 0.0058739039 0.0287650000 252732146 95654144 760807424 0.0526876785 -0.0204603076 -0.6331747770 2714 1311867260.9869680405 0.0756745338 0.0611266485 0.0875933766 0.0058859617 0.0287050000 252735786 95654144 760807424 0.0527886525 -0.0253607687 -0.6349476576 2715 1311867261.0202260017 0.0769089833 0.0611324615 0.0875933766 0.0058864872 0.0287040000 252737658 95654144 760807424 0.0527253114 -0.0252595339 -0.6380090714 2716 1311867261.0519640446 0.0774774030 0.0611384795 0.0875933766 0.0058865452 0.0325180000 252741130 95654144 760807424 0.0519916154 -0.0253061801 -0.6414406896 2717 1311867261.0871579647 0.0796034634 0.0611452756 0.0875933766 0.0058859327 0.0286680000 252743114 95654144 760807424 0.0539308786 -0.0252656359 -0.6441078186 2718 1311867261.1197659969 0.0802410617 0.0611523013 0.0875933766 0.0058857761 0.0288590000 252916818 95654144 760807424 0.0549903326 -0.0268225931 -0.6471533775 2719 1311867261.1530790329 0.0815140530 0.0611597899 0.0875933766 0.0058872973 0.0288170000 252920546 95654144 760807424 0.0557275377 -0.0254681520 -0.6515456438 2720 1311867261.1872630119 0.0820944980 0.0611674865 0.0875933766 0.0058905254 0.0404000000 252922274 95654144 760807424 0.0548076779 -0.0264973547 -0.6542122960 2721 1311867261.2191090584 0.0811893567 0.0611748448 0.0875933766 0.0058958005 0.0288830000 253095482 95654144 760807424 0.0526906066 -0.0277215932 -0.6580710411 2722 1311867261.2548229694 0.0813793540 0.0611822675 0.0875933766 0.0058954620 0.0287130000 253097210 95654144 760807424 0.0563332923 -0.0276132580 -0.6625518799 2723 1311867261.2879600525 0.0841936991 0.0611907182 0.0875933766 0.0058946908 0.0290050000 253100994 95654144 760807424 0.0572369210 -0.0242572464 -0.6654726863 2724 1311867261.3185029030 0.0850958452 0.0611994940 0.0875933766 0.0059000298 0.0351200000 253104466 95654144 760807424 0.0565190613 -0.0222900007 -0.6692088842 2725 1311867261.3546299934 0.0848759189 0.0612081826 0.0875933766 0.0059008856 0.0286670000 253106394 95654144 760807424 0.0547824912 -0.0228336975 -0.6716272831 2726 1311867261.3858330250 0.0868628696 0.0612175937 0.0875933766 0.0059000636 0.0282280000 253109810 95654144 760807424 0.0529024526 -0.0188504402 -0.6757401824 2727 1311867261.4186379910 0.0849940553 0.0612263126 0.0875933766 0.0058992669 0.0282910000 253111682 95654144 760807424 0.0503436737 -0.0209152102 -0.6776835322 2728 1311867261.4558680058 0.0788931400 0.0612327887 0.0875933766 0.0059004165 0.0326970000 253115322 95654144 760807424 0.0479942150 -0.0296225622 -0.6777581573 2729 1311867261.4862189293 0.0819250494 0.0612403711 0.0875933766 0.0059029674 0.0295090000 253118938 95654144 760807424 0.0483143479 -0.0259623490 -0.6796495318 2730 1311867261.5178630352 0.0843116939 0.0612488221 0.0875933766 0.0059026124 0.0294810000 253120666 95654144 760807424 0.0502653606 -0.0227869358 -0.6820195913 2731 1311867261.5556519032 0.0826529562 0.0612566596 0.0875933766 0.0059015779 0.0294620000 253124450 95654144 760807424 0.0483314581 -0.0244565457 -0.6835407019 2732 1311867261.5857899189 0.0789975226 0.0612631533 0.0875933766 0.0059053396 0.0296130000 253127866 95654144 760807424 0.0459189601 -0.0304487497 -0.6834089756 2733 1311867261.6174640656 0.0814143717 0.0612705266 0.0875933766 0.0059045679 0.0296870000 253129794 95654144 760807424 0.0467827357 -0.0253710821 -0.6872583628 2734 1311867261.6652009487 0.0808971748 0.0612777053 0.0875933766 0.0059053613 0.0295680000 253133658 95654144 760807424 0.0453319848 -0.0265652854 -0.6889291406 2735 1311867261.6889929771 0.0802363902 0.0612846372 0.0875933766 0.0059044638 0.0286020000 253135306 95654144 760807424 0.0454499796 -0.0273100380 -0.6910218596 2736 1311867261.7193109989 0.0801131576 0.0612915190 0.0875933766 0.0059062912 0.0320450000 253138666 95654144 760807424 0.0439267904 -0.0259239059 -0.6945706606 2737 1311867261.7601549625 0.0810301676 0.0612987308 0.0875933766 0.0059085017 0.0328600000 253312138 95654144 760807424 0.0433966108 -0.0239092149 -0.6983667612 2738 1311867261.7876880169 0.0843191892 0.0613071385 0.0875933766 0.0059114788 0.0282630000 253313698 95654144 760807424 0.0450188778 -0.0175107289 -0.7025445104 2739 1311867261.8213939667 0.0820674598 0.0613147181 0.0875933766 0.0059150979 0.0391220000 253317426 95654144 760807424 0.0452139378 -0.0200792346 -0.7047044039 2740 1311867261.8598148823 0.0821035653 0.0613223052 0.0875933766 0.0059149784 0.0286870000 253319210 95654144 760807424 0.0422229469 -0.0192577504 -0.7071480751 2741 1311867261.8885459900 0.0849395618 0.0613309215 0.0875933766 0.0059207656 0.0282490000 253322826 95654144 760807424 0.0457717553 -0.0133523829 -0.7107216716 2742 1311867261.9212360382 0.0818675533 0.0613384112 0.0875933766 0.0059231980 0.0281940000 253326298 95654144 760807424 0.0467227101 -0.0168548431 -0.7126469016 2743 1311867261.9592299461 0.0830970854 0.0613463436 0.0875933766 0.0059222698 0.0287110000 253328394 95654144 760807424 0.0458290204 -0.0139977550 -0.7155331969 2744 1311867261.9886140823 0.0852936804 0.0613550708 0.0875933766 0.0059225101 0.0282360000 253331754 95654144 760807424 0.0460671932 -0.0095374919 -0.7185539603 2745 1311867262.0219531059 0.0854415596 0.0613638454 0.0875933766 0.0059220060 0.0282340000 253333682 95654144 760807424 0.0434855446 -0.0087933922 -0.7207992673 2746 1311867262.0576629639 0.0862790719 0.0613729187 0.0875933766 0.0059211069 0.0310460000 253337266 95654144 760807424 0.0460546426 -0.0072883647 -0.7235730886 2747 1311867262.0944681168 0.0879423246 0.0613825909 0.0879423246 0.0059201555 0.0288540000 253340994 95654144 760807424 0.0473551825 -0.0035274634 -0.7278249264 2748 1311867262.1180479527 0.0887547731 0.0613925516 0.0887547731 0.0059191358 0.0286940000 253342442 95654144 760807424 0.0481791496 -0.0010739397 -0.7308909893 2749 1311867262.1539878845 0.0875637010 0.0614020719 0.0887547731 0.0059195987 0.0282120000 253346226 95654144 760807424 0.0465814024 -0.0007853624 -0.7345070243 2750 1311867262.1906540394 0.0862854421 0.0614111204 0.0887547731 0.0059186199 0.0283140000 253349754 95654144 760807424 0.0478014275 -0.0023583518 -0.7369158864 2751 1311867262.2200620174 0.0855990499 0.0614199128 0.0887547731 0.0059177535 0.0286510000 253351626 95654144 760807424 0.0482922308 -0.0023951016 -0.7399046421 2752 1311867262.2557590008 0.0853267014 0.0614285999 0.0887547731 0.0059167558 0.0283790000 253525058 95654144 760807424 0.0491747782 -0.0018611785 -0.7433845997 2753 1311867262.2893559933 0.0882142112 0.0614383295 0.0887547731 0.0059202186 0.0282880000 253526986 95654144 760807424 0.0509432778 0.0041554691 -0.7490792274 2754 1311867262.3192830086 0.0882587805 0.0614480682 0.0887547731 0.0059194286 0.0402510000 253530458 95654144 760807424 0.0505694076 0.0052053006 -0.7524981499 2755 1311867262.3543510437 0.0896785110 0.0614583152 0.0896785110 0.0059232622 0.0287200000 253534186 95654144 760807424 0.0527837984 0.0080445241 -0.7570704818 2756 1311867262.3862760067 0.0922066718 0.0614694721 0.0922066718 0.0059222179 0.0287110000 253535802 95654144 760807424 0.0542112999 0.0127550382 -0.7617116570 2757 1311867262.4192481041 0.0898591354 0.0614797694 0.0922066718 0.0059213447 0.0287480000 253539530 95654144 760807424 0.0513828769 0.0099148732 -0.7646947503 2758 1311867262.4579370022 0.0895862728 0.0614899603 0.0922066718 0.0059205891 0.0319780000 253541370 95654144 760807424 0.0523534641 0.0097182579 -0.7692403197 2759 1311867262.4882910252 0.0910165235 0.0615006622 0.0922066718 0.0059239227 0.0329230000 253545042 95654144 760807424 0.0526108630 0.0130521748 -0.7743244767 2760 1311867262.5228719711 0.0910633504 0.0615113733 0.0922066718 0.0059229553 0.0282160000 253548570 95654144 760807424 0.0534297414 0.0135585144 -0.7788910866 2761 1311867262.5554070473 0.0912906677 0.0615221590 0.0922066718 0.0059232952 0.0389260000 253550442 95654144 760807424 0.0486327112 0.0154350875 -0.7831165195 2762 1311867262.5873200893 0.0947792605 0.0615341999 0.0947792605 0.0059312636 0.0286680000 253553970 95654144 760807424 0.0519445725 0.0215998627 -0.7890530825 2763 1311867262.6235508919 0.0955553278 0.0615465130 0.0955553278 0.0059342858 0.0327790000 253555954 95654144 760807424 0.0520818904 0.0245049484 -0.7937835455 2764 1311867262.6548008919 0.0934575275 0.0615580583 0.0955553278 0.0059340560 0.0283640000 253559370 95654144 760807424 0.0532622077 0.0226294734 -0.7972310185 2765 1311867262.6901140213 0.0933502764 0.0615695564 0.0955553278 0.0059344423 0.0282370000 253563098 95654144 760807424 0.0501031280 0.0240834579 -0.8011546731 2766 1311867262.7234799862 0.0940128043 0.0615812857 0.0955553278 0.0059335889 0.0285070000 253564826 95654144 760807424 0.0504608490 0.0253984835 -0.8040856123 2767 1311867262.7550880909 0.0944179893 0.0615931529 0.0955553278 0.0059368442 0.0285970000 253568498 95654144 760807424 0.0514508337 0.0254412238 -0.8064550757 2768 1311867262.7890789509 0.0941478088 0.0616049140 0.0955553278 0.0059381220 0.0316900000 253571970 95654144 760807424 0.0501659736 0.0260987580 -0.8105658293 2769 1311867262.8232269287 0.0960263833 0.0616173450 0.0960263833 0.0059390116 0.0281790000 253574010 95654144 760807424 0.0515661947 0.0280201118 -0.8134411573 2770 1311867262.8561139107 0.0950547531 0.0616294163 0.0960263833 0.0059400654 0.0283450000 253747026 95654144 760807424 0.0511386655 0.0276522078 -0.8168802857 2771 1311867262.8878281116 0.0953676105 0.0616415917 0.0960263833 0.0059403915 0.0281720000 253748898 95654144 760807424 0.0521070324 0.0279577952 -0.8199275732 2772 1311867262.9221930504 0.0963140205 0.0616540998 0.0963140205 0.0059408855 0.0283020000 253752482 95654144 760807424 0.0528024547 0.0283369515 -0.8215893507 2773 1311867262.9539968967 0.0948533788 0.0616660722 0.0963140205 0.0059405812 0.0282300000 253756154 95654144 760807424 0.0560767017 0.0257591847 -0.8235887885 2774 1311867262.9877319336 0.0947564691 0.0616780009 0.0963140205 0.0059410059 0.0282010000 253757882 95654144 760807424 0.0545912050 0.0270994790 -0.8273888230 2775 1311867263.0238440037 0.0936771333 0.0616895321 0.0963140205 0.0059400230 0.0321030000 253761666 95654144 760807424 0.0543895513 0.0249981973 -0.8290814161 2776 1311867263.0552799702 0.0943144709 0.0617012846 0.0963140205 0.0059390439 0.0394260000 253933114 95654144 760807424 0.0569708981 0.0258245505 -0.8314647675 2777 1311867263.0870039463 0.0950563550 0.0617132958 0.0963140205 0.0059381928 0.0282850000 253936786 95654144 760807424 0.0571316332 0.0272629559 -0.8338221908 2778 1311867263.1226899624 0.0967136398 0.0617258949 0.0967136398 0.0059375535 0.0282520000 253940370 95654144 760807424 0.0572015680 0.0298646502 -0.8363156915 2779 1311867263.1537079811 0.0966040269 0.0617384455 0.0967136398 0.0059401628 0.0282610000 253942186 95654144 760807424 0.0575476810 0.0295825750 -0.8378634453 2780 1311867263.1884229183 0.0979871079 0.0617514846 0.0979871079 0.0059392900 0.0282330000 253945714 95654144 760807424 0.0574117228 0.0319895409 -0.8402345777 2781 1311867263.2225809097 0.0987255871 0.0617647799 0.0987255871 0.0059384991 0.0328750000 254117578 95654144 760807424 0.0555432737 0.0351913571 -0.8446964025 2782 1311867263.2536139488 0.0982598513 0.0617778982 0.0987255871 0.0059380976 0.0282350000 254120994 95654144 760807424 0.0542712733 0.0350393243 -0.8469378948 2783 1311867263.2884469032 0.0988894552 0.0617912333 0.0988894552 0.0059380599 0.0281860000 254124722 95654144 760807424 0.0548915304 0.0350400880 -0.8481754661 2784 1311867263.3236269951 0.0985836089 0.0618044489 0.0988894552 0.0059556173 0.0283130000 254126506 95654144 760807424 0.0535674244 0.0355936587 -0.8518031240 2785 1311867263.3539469242 0.0974152908 0.0618172356 0.0988894552 0.0059561348 0.0283210000 254130122 95654144 760807424 0.0536309779 0.0341347791 -0.8537935615 2786 1311867263.3856530190 0.0977739990 0.0618301418 0.0988894552 0.0059552439 0.0324570000 254133594 95654144 760807424 0.0521163754 0.0335574336 -0.8544676900 2787 1311867263.4221460819 0.1004174426 0.0618439873 0.1004174426 0.0059541939 0.0281570000 254135578 95654152 760807424 0.0542748012 0.0369723178 -0.8575221896 2788 1311867263.4549560547 0.1015767604 0.0618582386 0.1015767604 0.0059534235 0.0281920000 254138994 95654152 760807424 0.0541854128 0.0397850983 -0.8616876006 2789 1311867263.4876389503 0.0993920639 0.0618716964 0.1015767604 0.0059524085 0.0287300000 254140978 95654152 760807424 0.0558051206 0.0348853692 -0.8611084819 2790 1311867263.5235950947 0.0985476747 0.0618848419 0.1015767604 0.0059590479 0.0281700000 254144618 95654152 760807424 0.0578903258 0.0343135893 -0.8646306992 2791 1311867263.5535099506 0.0973320007 0.0618975425 0.1015767604 0.0059591314 0.0282910000 254148178 95654152 760807424 0.0591931716 0.0340625383 -0.8687486649 2792 1311867263.5855040550 0.1014994681 0.0619117265 0.1015767604 0.0059587260 0.0282030000 254149794 95654152 760807424 0.0613002591 0.0397250876 -0.8722309470 2793 1311867263.6236140728 0.1006174162 0.0619255846 0.1015767604 0.0059604532 0.0283120000 254153690 95654152 760807424 0.0628913715 0.0384070165 -0.8753880858 2794 1311867263.6543920040 0.0976789817 0.0619383811 0.1015767604 0.0059612439 0.0282510000 254155250 95654152 760807424 0.0653601214 0.0351220369 -0.8783496022 2795 1311867263.6903779507 0.0965981930 0.0619507818 0.1015767604 0.0059604566 0.0282290000 254159090 95654152 760807424 0.0680329502 0.0338452235 -0.8813532591 2796 1311867263.7227630615 0.1008350328 0.0619646889 0.1015767604 0.0059623888 0.0283190000 254162562 95654152 760807424 0.0695729330 0.0409615673 -0.8862942457 2797 1311867263.7559669018 0.1017004699 0.0619788955 0.1017004699 0.0059623178 0.0282390000 254164434 95654152 760807424 0.0714492574 0.0421336368 -0.8885253668 2798 1311867263.7911560535 0.1003987119 0.0619926266 0.1017004699 0.0059628640 0.0283260000 254167962 95654152 760807424 0.0717121065 0.0410990603 -0.8914996982 2799 1311867263.8235189915 0.1008771211 0.0620065189 0.1017004699 0.0059619303 0.0319270000 254169890 95654152 760807424 0.0724972785 0.0421212725 -0.8943067789 2800 1311867263.8555519581 0.1003835946 0.0620202250 0.1017004699 0.0059617421 0.0287770000 254173306 95654152 760807424 0.0754027590 0.0418178737 -0.8972192407 2801 1311867263.8925390244 0.0994202048 0.0620335774 0.1017004699 0.0059613313 0.0284400000 254177146 95654152 760807424 0.0786524415 0.0389442816 -0.8981375694 2802 1311867263.9255890846 0.1037761569 0.0620484748 0.1037761569 0.0059605880 0.0284790000 254347938 95654152 760807424 0.0796752274 0.0462526381 -0.9032079577 2803 1311867263.9557209015 0.1054033786 0.0620639421 0.1054033786 0.0059599557 0.0284070000 254351554 95654152 760807424 0.0833196789 0.0481231064 -0.9055323005 2804 1311867263.9913449287 0.1018932387 0.0620781466 0.1054033786 0.0059596945 0.0284800000 254355138 95654152 760807424 0.0820981935 0.0443721600 -0.9081988335 2805 1311867264.0265080929 0.1039690301 0.0620930809 0.1054033786 0.0059596165 0.0283950000 254357122 95654152 760807424 0.0837606713 0.0460851043 -0.9095649123 2806 1311867264.0539839268 0.1038678065 0.0621079686 0.1054033786 0.0059590602 0.0284340000 254360482 95654152 760807424 0.0846145079 0.0472230241 -0.9126614332 2807 1311867264.0935840607 0.1030729935 0.0621225625 0.1054033786 0.0059582964 0.0284010000 254362578 95654152 760807424 0.0877465308 0.0456615537 -0.9140990376 2808 1311867264.1232929230 0.1015935466 0.0621366191 0.1054033786 0.0059579234 0.0282690000 254365994 95654152 760807424 0.0897741765 0.0440163799 -0.9158719182 2809 1311867264.1547811031 0.1056596264 0.0621521132 0.1056596264 0.0059577476 0.0282950000 254369554 95654152 760807424 0.0915633738 0.0495983772 -0.9177376032 2810 1311867264.1908740997 0.1052380353 0.0621674463 0.1056596264 0.0059581408 0.0282860000 254540866 95654152 760807424 0.0920650959 0.0504636802 -0.9206458330 2811 1311867264.2230439186 0.1004204229 0.0621810546 0.1056596264 0.0059614833 0.0284170000 254544594 95654152 760807424 0.0922261551 0.0458417125 -0.9234725237 2812 1311867264.2549281120 0.0987823904 0.0621940707 0.1056596264 0.0059628459 0.0283570000 254546210 95654152 760807424 0.0950793549 0.0422148481 -0.9239093661 2813 1311867264.2910940647 0.1015538871 0.0622080628 0.1056596264 0.0059683600 0.0286170000 254549994 95654152 760807424 0.0946635753 0.0488784425 -0.9294154644 2814 1311867264.3223540783 0.1001472473 0.0622215451 0.1056596264 0.0059706802 0.0283180000 254553466 95654152 760807424 0.0947933123 0.0474072583 -0.9315433502 2815 1311867264.3539710045 0.0992977396 0.0622347161 0.1056596264 0.0059734512 0.0282560000 254555282 95654152 760807424 0.0936732739 0.0473304614 -0.9339867830 2816 1311867264.3903570175 0.0990700275 0.0622477968 0.1056596264 0.0059752243 0.0282010000 254558866 95654152 760807424 0.0915290788 0.0490965173 -0.9379991293 2817 1311867264.4247128963 0.0983146951 0.0622606001 0.1056596264 0.0059784437 0.0281830000 254560850 95654152 760807424 0.0916188136 0.0483372360 -0.9394481182 2818 1311867264.4536709785 0.1010724977 0.0622743729 0.1056596264 0.0059786104 0.0329810000 254564210 95654152 760807424 0.0894154608 0.0534357540 -0.9425905943 2819 1311867264.4911220074 0.1019196361 0.0622884365 0.1056596264 0.0059776594 0.0282510000 254568050 95654152 760807424 0.0896104351 0.0555443875 -0.9449555874 2820 1311867264.5220930576 0.1003454328 0.0623019319 0.1056596264 0.0059775614 0.0282460000 254569666 95654152 760807424 0.0894760787 0.0534952097 -0.9457541108 2821 1311867264.5544660091 0.1021550372 0.0623160592 0.1056596264 0.0059782731 0.0282070000 254573338 95654152 760807424 0.0907021016 0.0565388240 -0.9485387802 2822 1311867264.5919189453 0.1022290885 0.0623302027 0.1056596264 0.0059791738 0.0281260000 254576978 95654152 760807424 0.0924863666 0.0568619110 -0.9509425163 2823 1311867264.6239540577 0.1011421382 0.0623439512 0.1056596264 0.0059807928 0.0328460000 254747994 95654152 760807424 0.0941107124 0.0551623441 -0.9522634149 2824 1311867264.6537890434 0.1025271565 0.0623581804 0.1056596264 0.0059801307 0.0331110000 254751466 95654152 760807424 0.0939380154 0.0573899187 -0.9544073939 2825 1311867264.6908979416 0.1004007980 0.0623716468 0.1056596264 0.0059792744 0.0283160000 254753394 95654152 760807424 0.0927692875 0.0556514971 -0.9570586681 2826 1311867264.7228040695 0.1001152173 0.0623850026 0.1056596264 0.0059789457 0.0282530000 254756922 95654152 760807424 0.0919409394 0.0554917827 -0.9588795900 2827 1311867264.7547140121 0.1012010872 0.0623987331 0.1056596264 0.0059788014 0.0282020000 254760538 95654152 760807424 0.0937154591 0.0556241795 -0.9593362212 2828 1311867264.7909140587 0.1048279405 0.0624137364 0.1056596264 0.0059786238 0.0281620000 254762322 95654152 760807424 0.0933824480 0.0606461242 -0.9619606733 2829 1311867264.8233439922 0.1062802151 0.0624292424 0.1062802151 0.0059778520 0.0283760000 254766050 95654152 760807424 0.0948591977 0.0623622425 -0.9629650116 2830 1311867264.8540790081 0.1068088338 0.0624449242 0.1068088338 0.0059770357 0.0383980000 254767666 95654152 760807424 0.0946528614 0.0624114126 -0.9628555179 2831 1311867264.8904409409 0.1037408635 0.0624595113 0.1068088338 0.0059760586 0.0285550000 254771450 95654152 760807424 0.0928198919 0.0590212718 -0.9638279676 2832 1311867264.9235579967 0.1028599739 0.0624737770 0.1068088338 0.0059755840 0.0283690000 254774978 95654152 760807424 0.0975235030 0.0574042201 -0.9640176296 2833 1311867264.9598839283 0.0989140868 0.0624866398 0.1068088338 0.0059749371 0.0284030000 254776962 95654152 760807424 0.0972917452 0.0529324524 -0.9651087523 2834 1311867264.9916839600 0.1031760573 0.0625009974 0.1068088338 0.0059744095 0.0291590000 254780434 95654152 760807424 0.0991684124 0.0586414151 -0.9669843912 2835 1311867265.0220029354 0.1035915241 0.0625154914 0.1068088338 0.0059735266 0.0286030000 254782250 95654152 760807424 0.1026926041 0.0589939877 -0.9678458571 2836 1311867265.0581490993 0.1050569937 0.0625304919 0.1068088338 0.0059726199 0.0283290000 254785834 95654152 760807424 0.1039102599 0.0605321564 -0.9684117436 2837 1311867265.0911719799 0.1050285026 0.0625454718 0.1068088338 0.0059719958 0.0328050000 254789450 95654152 760807424 0.1028205231 0.0606690943 -0.9688164592 2838 1311867265.1217110157 0.1044833660 0.0625602491 0.1068088338 0.0059712831 0.0283690000 254791066 95654152 760807424 0.1019212157 0.0611558482 -0.9710562229 2839 1311867265.1582090855 0.1041711420 0.0625749060 0.1068088338 0.0059705600 0.0288340000 254794850 95654152 760807424 0.1010453478 0.0613175370 -0.9725162983 2840 1311867265.1899518967 0.1049900204 0.0625898409 0.1068088338 0.0059710795 0.0295940000 254798266 95654152 760807424 0.1019458622 0.0620934218 -0.9735941291 2841 1311867265.2225220203 0.1034955457 0.0626042392 0.1068088338 0.0059712328 0.0297120000 254800194 95654152 760807424 0.1014341414 0.0600675195 -0.9742715359 2842 1311867265.2581849098 0.1040338874 0.0626188168 0.1068088338 0.0059730419 0.0295790000 254803666 95654152 760807424 0.1017036214 0.0602542609 -0.9763455987 2843 1311867265.2915129662 0.1057215929 0.0626339779 0.1068088338 0.0059747884 0.0296330000 254805594 95654152 760807424 0.1013684422 0.0624963902 -0.9789280295 2844 1311867265.3220860958 0.1028553098 0.0626481204 0.1068088338 0.0059746263 0.0295730000 254809066 95654152 760807424 0.1015612110 0.0587159917 -0.9806343913 2845 1311867265.3585588932 0.1056448594 0.0626632335 0.1068088338 0.0059748517 0.0296730000 254983066 95654152 760807424 0.1006790772 0.0614190623 -0.9816551805 2846 1311867265.3912470341 0.1078146547 0.0626790983 0.1078146547 0.0059749426 0.0296000000 254984738 95654152 760807424 0.1025408953 0.0636726841 -0.9835162163 2847 1311867265.4244530201 0.1073671207 0.0626947949 0.1078146547 0.0059739609 0.0296770000 254988522 95654152 760807424 0.1006566882 0.0623017997 -0.9843202829 2848 1311867265.4604411125 0.1081252396 0.0627107466 0.1081252396 0.0059733727 0.0296330000 254990194 95654152 760807424 0.1007473990 0.0626507252 -0.9857900739 2849 1311867265.4902420044 0.1077152267 0.0627265432 0.1081252396 0.0059724023 0.0296060000 254993866 95654152 760807424 0.1010525599 0.0634659380 -0.9890166521 2850 1311867265.5230569839 0.1032599136 0.0627407654 0.1081252396 0.0059716092 0.0297320000 254997394 95654152 760807424 0.0996188298 0.0595670901 -0.9922633171 2851 1311867265.5594520569 0.1038789749 0.0627551948 0.1081252396 0.0059706037 0.0296420000 254999322 95654152 760807424 0.0992848352 0.0594329983 -0.9927455783 2852 1311867265.5932300091 0.1025284678 0.0627691405 0.1081252396 0.0059707832 0.0295320000 255002906 95654152 760807424 0.1023220345 0.0581334494 -0.9954377413 2853 1311867265.6250700951 0.1008912176 0.0627825026 0.1081252396 0.0059700052 0.0295210000 255004666 95654152 760807424 0.1005097032 0.0567633696 -0.9978317022 2854 1311867265.6610729694 0.1023535430 0.0627963678 0.1081252396 0.0059693810 0.0295550000 255008250 95654152 760807424 0.1013631299 0.0596986078 -1.0007957220 2855 1311867265.6956009865 0.1050335541 0.0628111619 0.1081252396 0.0059683979 0.0296890000 255011978 95654152 760807424 0.1039273888 0.0635575950 -1.0026277304 2856 1311867265.7221889496 0.1052453667 0.0628260198 0.1081252396 0.0059675789 0.0286040000 255013538 95654152 760807424 0.1014476568 0.0639348626 -1.0030347109 2857 1311867265.7626268864 0.1068509892 0.0628414293 0.1081252396 0.0059672829 0.0283390000 255017434 95654152 760807424 0.1026706621 0.0672742948 -1.0047873259 2858 1311867265.7925920486 0.1073201895 0.0628569922 0.1081252396 0.0059677801 0.0282430000 255020850 95654152 760807424 0.1059870496 0.0680304915 -1.0051500797 2859 1311867265.8224210739 0.1061478183 0.0628721341 0.1081252396 0.0059675062 0.0361820000 255022666 95654152 760807424 0.1050053164 0.0670565963 -1.0054097176 2860 1311867265.8593389988 0.1091463268 0.0628883139 0.1091463268 0.0059670758 0.0379750000 255026250 95654152 760807424 0.1038405746 0.0707720220 -1.0051782131 2861 1311867265.8943600655 0.1109018922 0.0629050960 0.1109018922 0.0059668504 0.0282920000 255028178 95654152 760807424 0.1035009995 0.0737036541 -1.0061911345 2862 1311867265.9256451130 0.1100280359 0.0629215611 0.1109018922 0.0059660012 0.0284100000 255031650 95654152 760807424 0.1034337431 0.0727822408 -1.0068778992 2863 1311867265.9620978832 0.1045542359 0.0629361027 0.1109018922 0.0059652745 0.0283480000 255035434 95654152 760807424 0.1027142256 0.0654749125 -1.0075235367 2864 1311867265.9908990860 0.1089630723 0.0629521736 0.1109018922 0.0059655292 0.0283830000 255036994 95654152 760807424 0.1022706926 0.0723471120 -1.0104508400 2865 1311867266.0233469009 0.1093680412 0.0629683746 0.1109018922 0.0059645729 0.0283160000 255040722 95654152 760807424 0.1035830155 0.0730901510 -1.0120706558 2866 1311867266.0634260178 0.1084619462 0.0629842481 0.1109018922 0.0059638574 0.0291320000 255042618 95654152 760807424 0.1021624655 0.0717952400 -1.0129559040 2867 1311867266.0954639912 0.1066779122 0.0629994883 0.1109018922 0.0059628986 0.0283580000 255046234 95654152 760807424 0.1000829041 0.0699313655 -1.0143851042 2868 1311867266.1241600513 0.1080742776 0.0630152048 0.1109018922 0.0059628338 0.0283450000 255049650 95654152 760807424 0.1010110974 0.0722092390 -1.0159125328 2869 1311867266.1634809971 0.1056108549 0.0630300516 0.1109018922 0.0059663720 0.0283860000 255051746 95654152 760807424 0.1060601026 0.0694362000 -1.0176919699 2870 1311867266.1922690868 0.1065745875 0.0630452239 0.1109018922 0.0059654449 0.0282970000 255055106 95654152 760807424 0.1067223176 0.0693024546 -1.0166664124 2871 1311867266.2255198956 0.1051302478 0.0630598826 0.1109018922 0.0059648807 0.0283460000 255057034 95654152 760807424 0.1034808382 0.0692442656 -1.0194343328 2872 1311867266.2597849369 0.0996817648 0.0630726340 0.1109018922 0.0059645414 0.0283350000 255060506 95654152 760807424 0.1033991650 0.0634823665 -1.0216325521 2873 1311867266.2915120125 0.1040829569 0.0630869083 0.1109018922 0.0059636277 0.0282810000 255064178 95654152 760807424 0.1056422219 0.0692040920 -1.0231577158 2874 1311867266.3258039951 0.1049473137 0.0631014735 0.1109018922 0.0059628350 0.0282330000 255065850 95654152 760807424 0.1057920605 0.0704687387 -1.0246285200 2875 1311867266.3601551056 0.1029587612 0.0631153370 0.1109018922 0.0059620732 0.0283640000 255240262 95654152 760807424 0.1031250954 0.0685248300 -1.0264353752 2876 1311867266.3913159370 0.1045620367 0.0631297482 0.1109018922 0.0059611221 0.0285200000 255243734 95654152 760807424 0.1021157056 0.0708970428 -1.0283409357 2877 1311867266.4254870415 0.0983277857 0.0631419825 0.1109018922 0.0059633668 0.0283900000 255245662 95654152 760807424 0.1027738228 0.0624693111 -1.0291699171 2878 1311867266.4612910748 0.1024679467 0.0631556468 0.1109018922 0.0059630863 0.0285060000 255249246 95654152 760807424 0.1029945239 0.0670963302 -1.0304155350 2879 1311867266.4912600517 0.0970152766 0.0631674077 0.1109018922 0.0059627518 0.0284620000 255419866 95654152 760807424 0.1014586017 0.0604961663 -1.0320657492 2880 1311867266.5284929276 0.0966922194 0.0631790483 0.1109018922 0.0059618054 0.0283120000 255423562 95654152 760807424 0.1001122966 0.0596611202 -1.0336505175 2881 1311867266.5587360859 0.1002499387 0.0631919156 0.1109018922 0.0059612443 0.0322920000 255427122 95654152 760807424 0.1024115756 0.0636244640 -1.0351723433 2882 1311867266.5906820297 0.1054385081 0.0632065744 0.1109018922 0.0059602838 0.0283360000 255428794 95654152 760807424 0.1050055325 0.0704163238 -1.0379253626 2883 1311867266.6256470680 0.1042590514 0.0632208139 0.1109018922 0.0059628859 0.0283410000 255432522 95654152 760807424 0.1007808074 0.0696924105 -1.0398472548 2884 1311867266.6596419811 0.1049616188 0.0632352871 0.1109018922 0.0059619531 0.0322690000 255434250 95654152 760807424 0.1005965546 0.0702668130 -1.0406156778 2885 1311867266.6914939880 0.1089837328 0.0632511445 0.1109018922 0.0059620721 0.0283590000 255437922 95654152 760807424 0.1068108156 0.0716736317 -1.0378351212 2886 1311867266.7260789871 0.1038520262 0.0632652127 0.1109018922 0.0059614007 0.0320120000 255441450 95654152 760807424 0.1042146310 0.0657784790 -1.0392829180 2887 1311867266.7576239109 0.1038313657 0.0632792640 0.1109018922 0.0059609725 0.0282750000 255443378 95654152 760807424 0.1072719544 0.0653506666 -1.0405707359 2888 1311867266.7898240089 0.1038020104 0.0632932954 0.1109018922 0.0059602851 0.0289710000 255446850 95654152 760807424 0.1070164964 0.0657373220 -1.0420612097 2889 1311867266.8257129192 0.1032279506 0.0633071185 0.1109018922 0.0059603403 0.0286100000 255448834 95654152 760807424 0.1039534882 0.0648227856 -1.0411541462 2890 1311867266.8575000763 0.1054681018 0.0633217070 0.1109018922 0.0059597637 0.0322740000 255452306 95654152 760807424 0.1039829701 0.0672495961 -1.0410526991 2891 1311867266.8898739815 0.1088874564 0.0633374683 0.1109018922 0.0059596357 0.0283710000 255455978 95654152 760807424 0.1019028872 0.0718525946 -1.0407893658 2892 1311867266.9266190529 0.1078688279 0.0633528664 0.1109018922 0.0059588369 0.0292060000 255457762 95654152 760807424 0.0993351936 0.0703797415 -1.0392358303 2893 1311867266.9576549530 0.1100237221 0.0633689987 0.1109018922 0.0059582535 0.0296310000 255461434 95654152 760807424 0.1004972234 0.0722465217 -1.0376715660 2894 1311867266.9920771122 0.1147603467 0.0633867566 0.1147603467 0.0059593438 0.0296630000 255464962 95654152 760807424 0.1008513719 0.0774675235 -1.0353468657 2895 1311867267.0259480476 0.1098618135 0.0634028102 0.1147603467 0.0059598693 0.0297680000 255466834 95654152 760807424 0.0998385102 0.0724167749 -1.0349396467 2896 1311867267.0603609085 0.1126862317 0.0634198279 0.1147603467 0.0059592165 0.0297440000 255470306 95654152 760807424 0.1033515111 0.0744944885 -1.0324354172 2897 1311867267.0929799080 0.1075001732 0.0634350438 0.1147603467 0.0059583246 0.0297090000 255472066 95654152 760807424 0.0992952436 0.0684751272 -1.0315958261 2898 1311867267.1266899109 0.1036498696 0.0634489205 0.1147603467 0.0059590843 0.0296900000 255475538 95654152 760807424 0.0959814787 0.0655333325 -1.0327105522 2899 1311867267.1586909294 0.1015490890 0.0634620631 0.1147603467 0.0059590126 0.0297270000 255479266 95654152 760807424 0.0959134251 0.0627094209 -1.0322202444 2900 1311867267.1916129589 0.1013558432 0.0634751299 0.1147603467 0.0059580784 0.0293390000 255480938 95654152 760807424 0.0975076929 0.0608037971 -1.0303097963 2901 1311867267.2262039185 0.1071650609 0.0634901902 0.1147603467 0.0059576645 0.0284680000 255484610 95654152 760807424 0.0970490053 0.0684716254 -1.0309875011 2902 1311867267.2587449551 0.1044031829 0.0635042884 0.1147603467 0.0059567188 0.0315650000 255486282 95654152 760807424 0.0958143026 0.0653699115 -1.0302608013 2903 1311867267.2920761108 0.1015151814 0.0635173821 0.1147603467 0.0059566658 0.0284950000 255490010 95654152 760807424 0.0981441811 0.0600322448 -1.0276968479 2904 1311867267.3265810013 0.1012922004 0.0635303899 0.1147603467 0.0059558806 0.0284580000 255493594 95654152 760807424 0.0985100046 0.0596315302 -1.0276800394 2905 1311867267.3609950542 0.1043471545 0.0635444404 0.1147603467 0.0059557148 0.0285250000 255495466 95654152 760807424 0.0991850644 0.0630383492 -1.0269169807 2906 1311867267.3945980072 0.0999277830 0.0635569605 0.1147603467 0.0059554723 0.0284510000 255498938 95654152 760807424 0.0989044905 0.0568349510 -1.0254374743 2907 1311867267.4286189079 0.1027939618 0.0635704579 0.1147603467 0.0059545013 0.0285070000 255500922 95654152 760807424 0.1001898572 0.0592261180 -1.0239623785 2908 1311867267.4595789909 0.1056985855 0.0635849449 0.1147603467 0.0059542882 0.0285490000 255504338 95654152 760807424 0.1006912440 0.0624691397 -1.0235023499 2909 1311867267.4935429096 0.1043981537 0.0635989749 0.1147603467 0.0059537928 0.0285030000 255508066 95654152 760807424 0.0986543372 0.0614606552 -1.0233236551 2910 1311867267.5264101028 0.1073463485 0.0636140083 0.1147603467 0.0059530364 0.0322990000 255509738 95654152 760807424 0.1019739881 0.0645216852 -1.0226032734 2911 1311867267.5577969551 0.1066178754 0.0636287812 0.1147603467 0.0059544362 0.0284960000 255513466 95654152 760807424 0.1024218947 0.0621290728 -1.0196309090 2912 1311867267.5954480171 0.1047338545 0.0636428970 0.1147603467 0.0059543898 0.0285510000 255517050 95654152 760807424 0.0937118009 0.0614376068 -1.0191556215 2913 1311867267.6272020340 0.1068185344 0.0636577187 0.1147603467 0.0059540452 0.0284750000 255518922 95654152 760807424 0.0947978571 0.0642052293 -1.0183078051 2914 1311867267.6608970165 0.1013165414 0.0636706421 0.1147603467 0.0059539815 0.0286050000 255522394 95654152 760807424 0.0938741937 0.0573781058 -1.0169476271 2915 1311867267.6955730915 0.1014828756 0.0636836137 0.1147603467 0.0059530739 0.0284850000 255524378 95654152 760807424 0.0924086049 0.0578787737 -1.0164294243 2916 1311867267.7264549732 0.1040687561 0.0636974632 0.1147603467 0.0059641489 0.0285820000 255527794 95654152 760807424 0.0909169242 0.0616235808 -1.0154209137 2917 1311867267.7624979019 0.1022625118 0.0637106840 0.1147603467 0.0059731076 0.0285000000 255531634 95654152 760807424 0.0906557441 0.0587913431 -1.0137511492 2918 1311867267.7957980633 0.1044159383 0.0637246337 0.1147603467 0.0059721475 0.0413350000 255533306 95654152 760807424 0.0926674157 0.0607381389 -1.0120048523 2919 1311867267.8323969841 0.1101342961 0.0637405329 0.1147603467 0.0059724704 0.0286740000 255537146 95654152 760807424 0.0929926112 0.0681272969 -1.0117257833 2920 1311867267.8601078987 0.1107410640 0.0637566290 0.1147603467 0.0059716712 0.0285010000 255538650 95654152 760807424 0.0913851410 0.0686892495 -1.0097566843 2921 1311867267.8989579678 0.1054770574 0.0637709119 0.1147603467 0.0059757150 0.0285440000 255542546 95654152 760807424 0.0935039222 0.0598527938 -1.0049368143 2922 1311867267.9282948971 0.1015288830 0.0637838338 0.1147603467 0.0059753044 0.0334580000 255545906 95654152 760807424 0.0915150568 0.0552104935 -1.0038342476 2923 1311867267.9643011093 0.1060713083 0.0637983010 0.1147603467 0.0059757858 0.0287070000 255547890 95654152 760807424 0.0909361094 0.0611803010 -1.0032488108 2924 1311867267.9947459698 0.1046017110 0.0638122556 0.1147603467 0.0059749425 0.0286320000 255551362 95654152 760807424 0.0887030736 0.0596323498 -1.0024805069 2925 1311867268.0287120342 0.1046881825 0.0638262303 0.1147603467 0.0059739975 0.0286550000 255553234 95654152 760807424 0.0876172930 0.0585553683 -1.0000712872 2926 1311867268.0588328838 0.1072117463 0.0638410579 0.1147603467 0.0059735826 0.0287020000 255556706 95654152 760807424 0.0861859098 0.0616834052 -0.9992640615 2927 1311867268.0946080685 0.1074855551 0.0638559689 0.1147603467 0.0059730555 0.0321850000 255560490 95654152 760807424 0.0836941525 0.0618056208 -0.9977249503 2928 1311867268.1253910065 0.1087788567 0.0638713114 0.1147603467 0.0059722401 0.0288110000 255562106 95654152 760807424 0.0846338868 0.0608360060 -0.9933328032 2929 1311867268.1606659889 0.1108267754 0.0638873426 0.1147603467 0.0059735534 0.0285720000 255565834 95654152 760807424 0.0861672387 0.0624910370 -0.9906318188 2930 1311867268.1981959343 0.1127087176 0.0639040052 0.1147603467 0.0059728388 0.0286210000 255569474 95654152 760807424 0.0869078040 0.0646316633 -0.9890307784 2931 1311867268.2290298939 0.1090527251 0.0639194091 0.1147603467 0.0059721668 0.0286200000 255571346 95654152 760807424 0.0841994137 0.0600889437 -0.9870068431 2932 1311867268.2579200268 0.1069182679 0.0639340745 0.1147603467 0.0059718750 0.0285560000 255574706 95654152 760807424 0.0820569992 0.0571642369 -0.9852711558 2933 1311867268.2951550484 0.1081143320 0.0639491376 0.1147603467 0.0059722335 0.0394370000 255576690 95654152 760807424 0.0810424313 0.0581713989 -0.9834044576 2934 1311867268.3274168968 0.1037250683 0.0639626945 0.1147603467 0.0059730424 0.0288270000 255580162 95654152 760807424 0.0829327777 0.0503106490 -0.9785833359 2935 1311867268.3586890697 0.1011778936 0.0639753743 0.1147603467 0.0059724317 0.0286510000 255583890 95654152 760807424 0.0819045901 0.0469974130 -0.9770756960 2936 1311867268.3934800625 0.1052915230 0.0639894466 0.1147603467 0.0059717881 0.0329910000 255585618 95654152 760807424 0.0802731737 0.0523619279 -0.9758008718 2937 1311867268.4261479378 0.1025171056 0.0640025646 0.1147603467 0.0059709303 0.0286300000 255589290 95654152 760807424 0.0789948106 0.0478390902 -0.9723329544 2938 1311867268.4581170082 0.1051109135 0.0640165566 0.1147603467 0.0059722927 0.0326410000 255590962 95654152 760807424 0.0774443448 0.0510034561 -0.9707534909 2939 1311867268.4943540096 0.1051880196 0.0640305652 0.1147603467 0.0059714126 0.0286080000 255594746 95654152 760807424 0.0766211525 0.0507358015 -0.9681506753 2940 1311867268.5280330181 0.1036157757 0.0640440296 0.1147603467 0.0059705890 0.0316230000 255598274 95654152 760807424 0.0730383620 0.0482240468 -0.9653110504 2941 1311867268.5616149902 0.1031989455 0.0640573430 0.1147603467 0.0059715606 0.0288420000 255600202 95654152 760807424 0.0697486401 0.0471131876 -0.9628139138 2942 1311867268.5949339867 0.1048563793 0.0640712108 0.1147603467 0.0059733605 0.0286700000 255603674 95654152 760807424 0.0678189248 0.0493851379 -0.9616889954 2943 1311867268.6294579506 0.1011366546 0.0640838053 0.1147603467 0.0059780076 0.0331840000 255605658 95654152 760807424 0.0668186098 0.0449831188 -0.9601539969 2944 1311867268.6639370918 0.1041667312 0.0640974204 0.1147603467 0.0059805637 0.0289360000 255609242 95654152 760807424 0.0643365830 0.0476960726 -0.9572787285 2945 1311867268.6937808990 0.1044736505 0.0641111305 0.1147603467 0.0059800401 0.0287090000 255612802 95654152 760807424 0.0633696765 0.0475812592 -0.9552695751 2946 1311867268.7282569408 0.1026206389 0.0641242023 0.1147603467 0.0059790356 0.0289680000 255614530 95654152 760807424 0.0605588555 0.0441352576 -0.9518769979 2947 1311867268.7629311085 0.1039621457 0.0641377204 0.1147603467 0.0059792767 0.0287960000 255618314 95654152 760807424 0.0603447929 0.0455133393 -0.9505411983 2948 1311867268.7951219082 0.1037506238 0.0641511576 0.1147603467 0.0059783389 0.0415780000 255621730 95654152 760807424 0.0605442189 0.0459218547 -0.9493283033 2949 1311867268.8264629841 0.1011010334 0.0641636873 0.1147603467 0.0059806472 0.0290020000 255623602 95654152 760807424 0.0649703369 0.0411302857 -0.9451855421 2950 1311867268.8615820408 0.0968382731 0.0641747634 0.1147603467 0.0059811954 0.0290780000 255627130 95654152 760807424 0.0626632422 0.0368667878 -0.9436860085 2951 1311867268.8947710991 0.0988454670 0.0641865122 0.1147603467 0.0059861480 0.0287430000 255629002 95654152 760807424 0.0624023974 0.0388068967 -0.9403570890 2952 1311867268.9271900654 0.0964890122 0.0641974548 0.1147603467 0.0059918717 0.0287260000 255632530 95654152 760807424 0.0621500127 0.0350813381 -0.9365946054 2953 1311867268.9633738995 0.0962251723 0.0642083006 0.1147603467 0.0059909740 0.0288010000 255636370 95654152 760807424 0.0613918193 0.0335776731 -0.9322800040 2954 1311867268.9942259789 0.0941557810 0.0642184385 0.1147603467 0.0059901704 0.0297460000 255637930 95654152 760807424 0.0596584342 0.0311922301 -0.9302368760 2955 1311867269.0293419361 0.0936423540 0.0642283959 0.1147603467 0.0059903683 0.0334420000 255641770 95654152 760807424 0.0544343181 0.0310348179 -0.9283961654 2956 1311867269.0628340244 0.0949030668 0.0642387730 0.1147603467 0.0059899190 0.0289000000 255643498 95654152 760807424 0.0547960103 0.0310656521 -0.9241529703 2957 1311867269.0942130089 0.0969313681 0.0642498290 0.1147603467 0.0059897935 0.0287930000 255647002 95654152 760807424 0.0582554005 0.0317880362 -0.9204582572 2958 1311867269.1263980865 0.0995394215 0.0642617592 0.1147603467 0.0059890704 0.0290030000 255650474 95654152 760807424 0.0572601743 0.0339152254 -0.9172064662 2959 1311867269.1618270874 0.0977817476 0.0642730873 0.1147603467 0.0059884331 0.0287960000 255652402 95654152 760807424 0.0550436564 0.0321459919 -0.9148371220 2960 1311867269.1941618919 0.0958879218 0.0642837680 0.1147603467 0.0059882232 0.0288570000 255655874 95654152 760807424 0.0521372892 0.0293522775 -0.9113788009 2961 1311867269.2266249657 0.0967307463 0.0642947261 0.1147603467 0.0059902355 0.0288740000 255657746 95654152 760807424 0.0496678203 0.0309530273 -0.9096873999 2962 1311867269.2623720169 0.0945580825 0.0643049433 0.1147603467 0.0059911314 0.0413290000 255661330 95654152 760807424 0.0508825108 0.0269237794 -0.9054341912 2963 1311867269.2948200703 0.0920558199 0.0643143091 0.1147603467 0.0060215170 0.0289410000 255665058 95654152 760807424 0.0450658351 0.0253590848 -0.9040957093 2964 1311867269.3261830807 0.0964056179 0.0643251362 0.1147603467 0.0060326560 0.0296210000 255666674 95654152 760807424 0.0426349305 0.0302129015 -0.9010535479 2965 1311867269.3641560078 0.0991974175 0.0643368975 0.1147603467 0.0060350679 0.0290200000 255670514 95654152 760807424 0.0390352421 0.0340962261 -0.8981410265 2966 1311867269.3967740536 0.0981027633 0.0643482818 0.1147603467 0.0060369490 0.0288680000 255673986 95654152 760807424 0.0353350602 0.0332773924 -0.8957707286 2967 1311867269.4275820255 0.1007541642 0.0643605521 0.1147603467 0.0060393703 0.0287450000 255675858 95654152 760807424 0.0360126197 0.0356597267 -0.8910557032 2968 1311867269.4626441002 0.0965240821 0.0643713888 0.1147603467 0.0060389750 0.0289620000 255679386 95654152 760807424 0.0351011679 0.0310225990 -0.8870428801 2969 1311867269.4938280582 0.1012083814 0.0643837960 0.1147603467 0.0060577553 0.0332530000 255681202 95654152 760807424 0.0354079194 0.0360803306 -0.8832250834 2970 1311867269.5278589725 0.1002034396 0.0643958565 0.1147603467 0.0060830099 0.0290220000 255684786 95654152 760807424 0.0352278873 0.0361329801 -0.8805555701 2971 1311867269.5634589195 0.0985879153 0.0644073651 0.1147603467 0.0060830068 0.0288810000 255688570 95654152 760807424 0.0359734520 0.0330969766 -0.8747237921 2972 1311867269.5962390900 0.0986189246 0.0644188764 0.1147603467 0.0060831564 0.0289410000 255690242 95654152 760807424 0.0347481109 0.0336285308 -0.8729192615 2973 1311867269.6306080818 0.0940595269 0.0644288464 0.1147603467 0.0060824124 0.0289630000 255693970 95654152 760807424 0.0324911438 0.0285812318 -0.8702230453 2974 1311867269.6631560326 0.0952022672 0.0644391938 0.1147603467 0.0060815191 0.0290050000 255695698 95654152 760807424 0.0304255690 0.0305234864 -0.8685957193 2975 1311867269.6964600086 0.0998700261 0.0644511034 0.1147603467 0.0060876281 0.0294170000 255868558 95654152 760807424 0.0296765827 0.0362444222 -0.8664559722 2976 1311867269.7280869484 0.0963250473 0.0644618137 0.1147603467 0.0060872320 0.0290050000 255872086 95654152 760807424 0.0284118336 0.0309114642 -0.8625655770 2977 1311867269.7622261047 0.0972711742 0.0644728346 0.1147603467 0.0060867379 0.0290870000 255874014 95654152 760807424 0.0259888601 0.0322592556 -0.8613629341 2978 1311867269.7974090576 0.0982772261 0.0644841860 0.1147603467 0.0060864212 0.0291040000 255877542 95654152 760807424 0.0229952559 0.0340600088 -0.8604773283 2979 1311867269.8295869827 0.0989801660 0.0644957657 0.1147603467 0.0061011171 0.0291220000 255879414 95654152 760807424 0.0224436447 0.0349854678 -0.8587052822 2980 1311867269.8676230907 0.0965679437 0.0645065282 0.1147603467 0.0061006533 0.0290050000 255882998 95654152 760807424 0.0219419319 0.0304648858 -0.8549940586 2981 1311867269.8953619003 0.0969319791 0.0645174056 0.1147603467 0.0060997442 0.0291670000 255886558 95654152 760807424 0.0191871729 0.0307516828 -0.8537589312 2982 1311867269.9344720840 0.0957787931 0.0645278890 0.1147603467 0.0060987716 0.0290960000 255888398 95654152 760807424 0.0188882500 0.0290893298 -0.8518361449 2983 1311867269.9627900124 0.0957524925 0.0645383565 0.1147603467 0.0061026127 0.0290670000 255892014 95654152 760807424 0.0196443964 0.0280790702 -0.8497520685 2984 1311867269.9987258911 0.0957665965 0.0645488217 0.1147603467 0.0061018875 0.0335260000 255895598 95654152 760807424 0.0204557702 0.0277753305 -0.8483045101 2985 1311867270.0306990147 0.0968862325 0.0645596550 0.1147603467 0.0061026515 0.0291190000 255897414 95654152 760807424 0.0219471641 0.0284496732 -0.8464338183 2986 1311867270.0660951138 0.0978027135 0.0645707880 0.1147603467 0.0061019915 0.0291090000 255900998 95654152 760807424 0.0215296913 0.0284551363 -0.8434806466 2987 1311867270.0948200226 0.0982915983 0.0645820772 0.1147603467 0.0061015557 0.0295130000 255902702 95654152 760807424 0.0218013357 0.0279228780 -0.8405504227 2988 1311867270.1336340904 0.0990745723 0.0645936208 0.1147603467 0.0061005905 0.0326940000 256076674 95654152 760807424 0.0201856140 0.0291736592 -0.8391913772 2989 1311867270.1624090672 0.0973208025 0.0646045700 0.1147603467 0.0060996314 0.0291200000 256080234 95654152 760807424 0.0178616624 0.0256355852 -0.8352019191 2990 1311867270.1943540573 0.0953451023 0.0646148512 0.1147603467 0.0060989257 0.0337540000 256081906 95654152 760807424 0.0166978389 0.0233075507 -0.8335413933 2991 1311867270.2323369980 0.0962598622 0.0646254312 0.1147603467 0.0061006821 0.0331370000 256085746 95654152 760807424 0.0173060857 0.0244012401 -0.8311952949 2992 1311867270.2655749321 0.0961811766 0.0646359779 0.1147603467 0.0061021725 0.0290930000 256087418 95654152 760807424 0.0191572290 0.0223764013 -0.8273550272 2993 1311867270.2960460186 0.0966452435 0.0646466727 0.1147603467 0.0061013954 0.0294100000 256091034 95654152 760807424 0.0162975565 0.0224520005 -0.8252087235 2994 1311867270.3346099854 0.0967115462 0.0646573824 0.1147603467 0.0061016981 0.0337180000 256094730 95654152 760807424 0.0151747223 0.0236038249 -0.8244287968 2995 1311867270.3624660969 0.0943989381 0.0646673128 0.1147603467 0.0061007499 0.0291860000 256096490 95654152 760807424 0.0148544339 0.0191161335 -0.8203986287 2996 1311867270.3957469463 0.0934703276 0.0646769266 0.1147603467 0.0061013569 0.0291650000 256099962 95654152 760807424 0.0154688777 0.0174236465 -0.8176147938 2997 1311867270.4334359169 0.0980215147 0.0646880526 0.1147603467 0.0061086865 0.0376050000 256102058 95654152 760807424 0.0167496726 0.0225831997 -0.8155288100 2998 1311867270.4641909599 0.0957906991 0.0646984270 0.1147603467 0.0061083489 0.0410120000 256105530 95654152 760807424 0.0151313441 0.0194604360 -0.8131533265 2999 1311867270.4954609871 0.0958469212 0.0647088133 0.1147603467 0.0061077852 0.0335740000 256109090 95654152 760807424 0.0135965608 0.0176529698 -0.8087247014 3000 1311867270.5331869125 0.0962575078 0.0647193296 0.1147603467 0.0061068226 0.0292620000 256110986 95654152 760807424 0.0157343578 0.0171668082 -0.8055723310 3001 1311867270.5629880428 0.0898499563 0.0647277037 0.1147603467 0.0061076374 0.0292630000 256284882 95654152 760807424 0.0165349655 0.0085167317 -0.8032705188 3002 1311867270.5944859982 0.0882092863 0.0647355256 0.1147603467 0.0061067339 0.0293120000 256288242 95654152 760807424 0.0153321149 0.0059751379 -0.8017322421 3003 1311867270.6312110424 0.0901386067 0.0647439849 0.1147603467 0.0061074558 0.0330050000 256290226 95654152 760807424 0.0163740385 0.0065282974 -0.7984134555 3004 1311867270.6644439697 0.0899449363 0.0647523740 0.1147603467 0.0061074922 0.0292810000 256293698 95654152 760807424 0.0186324921 0.0051854015 -0.7956272960 3005 1311867270.6950180531 0.0882441923 0.0647601916 0.1147603467 0.0061070304 0.0293650000 256295514 95654152 760807424 0.0165352747 0.0029905248 -0.7941085100 3006 1311867270.7318449020 0.0871187598 0.0647676296 0.1147603467 0.0061071235 0.0297450000 256299154 95654152 760807424 0.0165553000 -0.0002310821 -0.7902089357 3007 1311867270.7623898983 0.0893006101 0.0647757882 0.1147603467 0.0061064158 0.0294710000 256302770 95654152 760807424 0.0167139843 0.0034563178 -0.7903466821 3008 1311867270.7960500717 0.0894094929 0.0647839776 0.1147603467 0.0061057186 0.0295050000 256304498 95654152 760807424 0.0155233685 0.0031366469 -0.7886813879 3009 1311867270.8322730064 0.0910352021 0.0647927018 0.1147603467 0.0061103222 0.0296940000 256308282 95654152 760807424 0.0135917114 0.0048186211 -0.7872235775 3010 1311867270.8635489941 0.0915794224 0.0648016011 0.1147603467 0.0061117819 0.0294270000 256309954 95654152 760807424 0.0141268857 0.0054979669 -0.7854534388 3011 1311867270.8945889473 0.0902137011 0.0648100408 0.1147603467 0.0061112243 0.0294510000 256313570 95654152 760807424 0.0137035493 0.0024767560 -0.7825070620 3012 1311867270.9326179028 0.0920004696 0.0648190682 0.1147603467 0.0061143581 0.0294520000 256317210 95654152 760807424 0.0152062364 0.0038189134 -0.7801789641 3013 1311867270.9624550343 0.0976355448 0.0648299598 0.1147603467 0.0061196513 0.0294650000 256319026 95654152 760807424 0.0173976198 0.0099571422 -0.7782005668 3014 1311867270.9944560528 0.0893638134 0.0648380998 0.1147603467 0.0061214989 0.0295900000 256322498 95654152 760807424 0.0159462579 -0.0007660137 -0.7756310105 3015 1311867271.0306649208 0.0858586505 0.0648450718 0.1147603467 0.0061208253 0.0296690000 256324426 95654152 760807424 0.0152024589 -0.0069243740 -0.7722730041 3016 1311867271.0623910427 0.0892175138 0.0648531528 0.1147603467 0.0061213035 0.0293470000 256327898 95654152 760807424 0.0163089130 -0.0031664493 -0.7717306614 3017 1311867271.0983459949 0.0859043449 0.0648601303 0.1147603467 0.0061252898 0.0331580000 256331682 95654152 760807424 0.0178514868 -0.0089191031 -0.7688041925 3018 1311867271.1322019100 0.0844105482 0.0648666083 0.1147603467 0.0061244339 0.0303200000 256333354 95654152 760807424 0.0175435767 -0.0120774992 -0.7665373683 3019 1311867271.1643741131 0.0860414878 0.0648736221 0.1147603467 0.0061242955 0.0293750000 256337026 95654152 760807424 0.0170763116 -0.0104766171 -0.7658433318 3020 1311867271.1988029480 0.0850728825 0.0648803106 0.1147603467 0.0061233284 0.0417190000 256340610 95654152 760807424 0.0190737620 -0.0119861010 -0.7647849917 3021 1311867271.2320818901 0.0835251287 0.0648864824 0.1147603467 0.0061233324 0.0294100000 256342426 95654152 760807424 0.0204061922 -0.0148122432 -0.7623969316 3022 1311867271.2645740509 0.0868023261 0.0648937345 0.1147603467 0.0061270552 0.0293790000 256345898 95654152 760807424 0.0207263455 -0.0111718997 -0.7612602711 3023 1311867271.2998549938 0.0871271715 0.0649010892 0.1147603467 0.0061279142 0.0338430000 256347882 95654152 760807424 0.0213565733 -0.0123297134 -0.7571933270 3024 1311867271.3354289532 0.0853718743 0.0649078587 0.1147603467 0.0061294502 0.0293940000 256351410 95654152 760807424 0.0200270303 -0.0164604671 -0.7537424564 3025 1311867271.3673670292 0.0857367739 0.0649147443 0.1147603467 0.0061291724 0.0292930000 256355138 95654152 760807424 0.0190446861 -0.0160158090 -0.7527669668 3026 1311867271.3988809586 0.0857004672 0.0649216133 0.1147603467 0.0061288747 0.0292820000 256356810 95654152 760807424 0.0203718971 -0.0178622808 -0.7490217090 3027 1311867271.4355340004 0.0860721469 0.0649286006 0.1147603467 0.0061283309 0.0332250000 256360594 95654152 760807424 0.0201048478 -0.0189633574 -0.7462082505 3028 1311867271.4657170773 0.0865239277 0.0649357325 0.1147603467 0.0061312308 0.0301000000 256362154 95654152 760807424 0.0232895613 -0.0196808837 -0.7432818413 3029 1311867271.4997088909 0.0878473073 0.0649432965 0.1147603467 0.0061349797 0.0293260000 256365938 95654152 760807424 0.0202635098 -0.0195608586 -0.7410947680 3030 1311867271.5323960781 0.0856371969 0.0649501262 0.1147603467 0.0061353047 0.0294050000 256369410 95654152 760807424 0.0209284332 -0.0231558159 -0.7385134697 3031 1311867271.5676190853 0.0851376355 0.0649567866 0.1147603467 0.0061347395 0.0338990000 256371338 95654152 760807424 0.0215964988 -0.0257035773 -0.7348639369 3032 1311867271.5991230011 0.0878036022 0.0649643218 0.1147603467 0.0061340272 0.0294210000 256374810 95654152 760807424 0.0206979085 -0.0234746765 -0.7322760820 3033 1311867271.6349890232 0.0845467299 0.0649707782 0.1147603467 0.0061342061 0.0294130000 256376738 95654152 760807424 0.0205796063 -0.0289864503 -0.7274967432 3034 1311867271.6658320427 0.0825726464 0.0649765798 0.1147603467 0.0061335303 0.0294680000 256380210 95654152 760807424 0.0204403382 -0.0331008770 -0.7225373387 3035 1311867271.7005228996 0.0843868181 0.0649829752 0.1147603467 0.0061360766 0.0294240000 256383938 95654152 760807424 0.0212253518 -0.0318822935 -0.7182801366 3036 1311867271.7349541187 0.0857186541 0.0649898052 0.1147603467 0.0061362811 0.0293960000 256385722 95654152 760807424 0.0193881020 -0.0318430625 -0.7131858468 3037 1311867271.7661850452 0.0860548019 0.0649967413 0.1147603467 0.0061367822 0.0294770000 256389338 95654152 760807424 0.0190786254 -0.0331719071 -0.7080335021 3038 1311867271.7994530201 0.0861531645 0.0650037052 0.1147603467 0.0061392001 0.0293720000 256392922 95654152 760807424 0.0180215817 -0.0338984542 -0.7041582465 3039 1311867271.8341000080 0.0855679214 0.0650104720 0.1147603467 0.0061387377 0.0299830000 256394794 95654152 760807424 0.0192667209 -0.0352790393 -0.7000438571 3040 1311867271.8629150391 0.0836547762 0.0650166050 0.1147603467 0.0061388081 0.0295620000 256398210 95654152 760807424 0.0181473047 -0.0394635089 -0.6950674057 3041 1311867271.9009630680 0.0834031031 0.0650226512 0.1147603467 0.0061380587 0.0295140000 256400250 95654152 760807424 0.0190529600 -0.0401686095 -0.6909317970 3042 1311867271.9304800034 0.0866143480 0.0650297491 0.1147603467 0.0061376392 0.0341540000 256403666 95654152 760807424 0.0202212632 -0.0371846668 -0.6865223646 3043 1311867271.9669768810 0.0858524069 0.0650365919 0.1147603467 0.0061376115 0.0341890000 256407394 95654152 760807424 0.0173207596 -0.0396837182 -0.6802981496 3044 1311867271.9994390011 0.0841837823 0.0650428820 0.1147603467 0.0061366768 0.0296000000 256409066 95654152 760807424 0.0156529713 -0.0425000489 -0.6754280925 3045 1311867272.0337600708 0.0858104825 0.0650497022 0.1147603467 0.0061360867 0.0339920000 256412794 95654152 760807424 0.0141187096 -0.0407282375 -0.6710543633 3046 1311867272.0626399517 0.0809216276 0.0650549130 0.1147603467 0.0061365335 0.0297530000 256414410 95654152 760807424 0.0142888576 -0.0483057201 -0.6653084755 3047 1311867272.0988030434 0.0804777592 0.0650599746 0.1147603467 0.0061359665 0.0296700000 256418194 95654152 760807424 0.0146833500 -0.0502547696 -0.6602672338 3048 1311867272.1336209774 0.0804150328 0.0650650124 0.1147603467 0.0061349712 0.0297640000 256421778 95654152 760807424 0.0151702370 -0.0524033345 -0.6549953222 3049 1311867272.1659350395 0.0790989995 0.0650696152 0.1147603467 0.0061357064 0.0424210000 256423650 95654152 760807424 0.0151493838 -0.0556203127 -0.6507575512 3050 1311867272.1987910271 0.0806072727 0.0650747095 0.1147603467 0.0061355982 0.0298410000 256427178 95654152 760807424 0.0167185105 -0.0548375882 -0.6479167938 3051 1311867272.2319760323 0.0779144466 0.0650789179 0.1147603467 0.0061354404 0.0297620000 256429050 95654152 760807424 0.0162986889 -0.0604285374 -0.6430595517 3052 1311867272.2655110359 0.0802396163 0.0650838853 0.1147603467 0.0061384441 0.0335160000 256432578 95654152 760807424 0.0170193799 -0.0581431128 -0.6410967112 3053 1311867272.2982270718 0.0800500885 0.0650887875 0.1147603467 0.0061376002 0.0297070000 256436306 95654152 760807424 0.0154523477 -0.0606167093 -0.6369038820 3054 1311867272.3315019608 0.0781717673 0.0650930714 0.1147603467 0.0061416727 0.0297780000 256437978 95654152 760807424 0.0159452185 -0.0639855042 -0.6339737177 3055 1311867272.3696749210 0.0778378397 0.0650972431 0.1147603467 0.0061423506 0.0297690000 256441818 95654152 760807424 0.0162997656 -0.0648341402 -0.6321476698 3056 1311867272.3987050056 0.0782362819 0.0651015426 0.1147603467 0.0061419481 0.0333920000 256445178 95654152 760807424 0.0130656948 -0.0662185624 -0.6291943789 3057 1311867272.4335730076 0.0786226243 0.0651059655 0.1147603467 0.0061413429 0.0296480000 256447162 95654152 760807424 0.0116875647 -0.0669948012 -0.6262944341 3058 1311867272.4686141014 0.0792206973 0.0651105812 0.1147603467 0.0061405381 0.0297830000 256450690 95654152 760807424 0.0106129581 -0.0678704008 -0.6227437854 3059 1311867272.5011420250 0.0788761228 0.0651150812 0.1147603467 0.0061395556 0.0335410000 256452562 95654152 760807424 0.0101991622 -0.0688631609 -0.6203710437 3060 1311867272.5325479507 0.0787798911 0.0651195469 0.1147603467 0.0061386578 0.0299070000 256456034 95654152 760807424 0.0099444697 -0.0703180283 -0.6169871688 3061 1311867272.5676600933 0.0797545016 0.0651243280 0.1147603467 0.0061383776 0.0297820000 256629638 95654152 760807424 0.0086657461 -0.0703943819 -0.6137128472 3062 1311867272.5996229649 0.0783726722 0.0651286547 0.1147603467 0.0061379393 0.0336710000 256631366 95654152 760807424 0.0087260855 -0.0723310262 -0.6115558147 3063 1311867272.6315360069 0.0769477189 0.0651325133 0.1147603467 0.0061370622 0.0345170000 256634982 95654152 760807424 0.0097325603 -0.0751448348 -0.6077249050 3064 1311867272.6661291122 0.0776491091 0.0651365984 0.1147603467 0.0061362682 0.0298300000 256636710 95654152 760807424 0.0099949185 -0.0740419701 -0.6055619717 3065 1311867272.6987280846 0.0763492510 0.0651402567 0.1147603467 0.0061354680 0.0301010000 256640438 95654152 760807424 0.0101435492 -0.0752582178 -0.6036555767 3066 1311867272.7307109833 0.0751930103 0.0651435354 0.1147603467 0.0061352519 0.0342770000 256643910 95654152 760807424 0.0087861568 -0.0780984908 -0.5999429226 3067 1311867272.7686150074 0.0747389421 0.0651466640 0.1147603467 0.0061386743 0.0343630000 256645894 95654152 760807424 0.0105189467 -0.0785229281 -0.5970073342 3068 1311867272.7996079922 0.0762791559 0.0651502926 0.1147603467 0.0061380482 0.0297780000 256649310 95654152 760807424 0.0112027414 -0.0764522925 -0.5955598354 3069 1311867272.8310160637 0.0773385987 0.0651542640 0.1147603467 0.0061376749 0.0298940000 256651182 95654152 760807424 0.0116697233 -0.0741705745 -0.5946848989 3070 1311867272.8674850464 0.0771687552 0.0651581776 0.1147603467 0.0061370390 0.0346820000 256654822 95654152 760807424 0.0137121798 -0.0745340362 -0.5919303298 3071 1311867272.8996291161 0.0766256973 0.0651619117 0.1147603467 0.0061364750 0.0299390000 256658438 95654152 760807424 0.0154532399 -0.0756115466 -0.5887165070 3072 1311867272.9314110279 0.0754533410 0.0651652618 0.1147603467 0.0061363957 0.0300030000 256660110 95654152 760807424 0.0180749428 -0.0781405941 -0.5855409503 3073 1311867272.9664669037 0.0737977549 0.0651680709 0.1147603467 0.0061355748 0.0298380000 256663894 95654152 760807424 0.0181604903 -0.0801894367 -0.5845897198 3074 1311867272.9987599850 0.0746975318 0.0651711709 0.1147603467 0.0061351581 0.0299140000 256667366 95654152 760807424 0.0211883746 -0.0793838277 -0.5817145109 3075 1311867273.0328490734 0.0741722956 0.0651740981 0.1147603467 0.0061342053 0.0298750000 256669350 95654152 760807424 0.0213181656 -0.0810549110 -0.5798166990 3076 1311867273.0662739277 0.0733092353 0.0651767428 0.1147603467 0.0061334345 0.0298580000 256672822 95654152 760807424 0.0269518532 -0.0811977908 -0.5781614184 3077 1311867273.0999150276 0.0733960867 0.0651794141 0.1147603467 0.0061325684 0.0298720000 256674694 95654152 760807424 0.0286184270 -0.0803886056 -0.5777591467 3078 1311867273.1310710907 0.0764369443 0.0651830715 0.1147603467 0.0061325811 0.0299870000 256678166 95654152 760807424 0.0309037082 -0.0767727196 -0.5753911138 3079 1311867273.1665740013 0.0750817508 0.0651862864 0.1147603467 0.0061316341 0.0303120000 256681950 95654152 760807424 0.0310221910 -0.0780619159 -0.5746034384 3080 1311867273.1997520924 0.0739172623 0.0651891211 0.1147603467 0.0061307416 0.0301330000 256683622 95654152 760807424 0.0329545476 -0.0793016851 -0.5730041265 3081 1311867273.2331819534 0.0720262527 0.0651913402 0.1147603467 0.0061306675 0.0310530000 256687406 95654152 760807424 0.0337506644 -0.0826178715 -0.5705028176 3082 1311867273.2668380737 0.0711299479 0.0651932671 0.1147603467 0.0061303994 0.0299550000 256689078 95654152 760807424 0.0334645920 -0.0840841681 -0.5690692067 3083 1311867273.2985589504 0.0724936947 0.0651956351 0.1147603467 0.0061296208 0.0336470000 256692806 95654152 760807424 0.0345940441 -0.0811160281 -0.5683607459 3084 1311867273.3308010101 0.0717661306 0.0651977656 0.1147603467 0.0061292020 0.0341880000 256696222 95654152 760807424 0.0361521654 -0.0819305778 -0.5660194755 3085 1311867273.3663508892 0.0708947927 0.0651996123 0.1147603467 0.0061282390 0.0300430000 256698206 95654152 760807424 0.0366824567 -0.0837994441 -0.5623390675 3086 1311867273.3992459774 0.0710048154 0.0652014934 0.1147603467 0.0061276372 0.0299430000 256701678 95654152 760807424 0.0386248082 -0.0828899518 -0.5604602098 3087 1311867273.4308409691 0.0743322745 0.0652044512 0.1147603467 0.0061274968 0.0300940000 256703606 95654152 760807424 0.0410553366 -0.0778864175 -0.5572469831 3088 1311867273.4663250446 0.0735736191 0.0652071614 0.1147603467 0.0061276894 0.0301960000 256707134 95654152 760807424 0.0419941209 -0.0799452141 -0.5528630614 3089 1311867273.4997849464 0.0734399259 0.0652098266 0.1147603467 0.0061273594 0.0301420000 256710806 95654152 760807424 0.0412407964 -0.0796910599 -0.5502670407 3090 1311867273.5318419933 0.0748862848 0.0652129582 0.1147603467 0.0061278186 0.0302010000 256712534 95654152 760807424 0.0437881425 -0.0771440417 -0.5464976430 3091 1311867273.5687909126 0.0758625641 0.0652164035 0.1147603467 0.0061271713 0.0301920000 256716374 95654152 760807424 0.0435782336 -0.0755693838 -0.5429153442 3092 1311867273.6000390053 0.0736432821 0.0652191289 0.1147603467 0.0061265385 0.0301320000 256889046 95654152 760807424 0.0411835276 -0.0802946538 -0.5383540392 3093 1311867273.6349599361 0.0736034960 0.0652218397 0.1147603467 0.0061261789 0.0304880000 256891030 95654152 760807424 0.0418583043 -0.0807970837 -0.5345398188 3094 1311867273.6673769951 0.0754773766 0.0652251543 0.1147603467 0.0061253881 0.0300980000 256894558 95654152 760807424 0.0432149582 -0.0784692839 -0.5309687257 3095 1311867273.6987860203 0.0756292269 0.0652285159 0.1147603467 0.0061251796 0.0347110000 256896374 95654152 760807424 0.0428306013 -0.0792430192 -0.5268219113 3096 1311867273.7346739769 0.0765773803 0.0652321815 0.1147603467 0.0061260571 0.0304630000 256899958 95654152 760807424 0.0447123423 -0.0767391920 -0.5235651135 3097 1311867273.7665960789 0.0784208626 0.0652364401 0.1147603467 0.0061268326 0.0301340000 256903630 95654152 760807424 0.0480630398 -0.0742417052 -0.5205487013 3098 1311867273.7990698814 0.0765083209 0.0652400785 0.1147603467 0.0061264547 0.0429990000 257076234 95654152 760807424 0.0480530821 -0.0776280910 -0.5163202882 3099 1311867273.8358130455 0.0746513456 0.0652431154 0.1147603467 0.0061264655 0.0301790000 257080018 95654152 760807424 0.0492628552 -0.0802923515 -0.5128188729 3100 1311867273.8668060303 0.0743658319 0.0652460582 0.1147603467 0.0061273837 0.0301040000 257081690 95654152 760807424 0.0482348241 -0.0815569088 -0.5095072389 3101 1311867273.8990719318 0.0746163204 0.0652490799 0.1147603467 0.0061298604 0.0301390000 257085418 95654152 760807424 0.0476531945 -0.0824470222 -0.5063745379 3102 1311867273.9384820461 0.0745020136 0.0652520628 0.1147603467 0.0061289458 0.0301870000 257089058 95654152 760807424 0.0484289601 -0.0827331841 -0.5031505823 3103 1311867273.9669051170 0.0750534311 0.0652552215 0.1147603467 0.0061280701 0.0301850000 257090818 95654152 760807424 0.0479102656 -0.0809009671 -0.5016885996 3104 1311867273.9996581078 0.0743088797 0.0652581382 0.1147603467 0.0061271344 0.0300920000 257094346 95654152 760807424 0.0445086360 -0.0838362202 -0.4975483418 3105 1311867274.0348489285 0.0744415298 0.0652610958 0.1147603467 0.0061264352 0.0338760000 257096218 95654152 760807424 0.0457618460 -0.0819211230 -0.4951603413 3106 1311867274.0670020580 0.0724807531 0.0652634203 0.1147603467 0.0061281742 0.0300760000 257099746 95654152 760807424 0.0448501445 -0.0832707509 -0.4928698838 3107 1311867274.1025679111 0.0705109388 0.0652651092 0.1147603467 0.0061279956 0.0339130000 257103530 95654152 760807424 0.0417943932 -0.0869963244 -0.4883122146 3108 1311867274.1350569725 0.0704847053 0.0652667886 0.1147603467 0.0061271941 0.0339970000 257105258 95654152 760807424 0.0421082824 -0.0863999426 -0.4849175513 3109 1311867274.1667969227 0.0705440491 0.0652684860 0.1147603467 0.0061268258 0.0304670000 257108874 95654152 760807424 0.0403335318 -0.0875328630 -0.4799092412 3110 1311867274.2008550167 0.0701385215 0.0652700520 0.1147603467 0.0061302310 0.0306550000 257112346 95654152 760807424 0.0373194702 -0.0891052410 -0.4748561382 3111 1311867274.2389180660 0.0679584220 0.0652709161 0.1147603467 0.0061308926 0.0306080000 257114442 95654152 760807424 0.0352771357 -0.0931817442 -0.4701403081 3112 1311867274.2668540478 0.0697585940 0.0652723582 0.1147603467 0.0061302323 0.0429800000 257117802 95654152 760807424 0.0354486629 -0.0905544832 -0.4670911133 3113 1311867274.3018939495 0.0694530532 0.0652737011 0.1147603467 0.0061317154 0.0304900000 257119730 95654152 760807424 0.0325270183 -0.0923152864 -0.4621972144 3114 1311867274.3358139992 0.0689061135 0.0652748676 0.1147603467 0.0061319981 0.0302190000 257123258 95654152 760807424 0.0295438785 -0.0946106985 -0.4575893879 3115 1311867274.3679759502 0.0677554607 0.0652756640 0.1147603467 0.0061315490 0.0306310000 257126986 95654152 760807424 0.0305716321 -0.0957365856 -0.4541564882 3116 1311867274.4007549286 0.0684030950 0.0652766676 0.1147603467 0.0061310982 0.0306750000 257128602 95654152 760807424 0.0285362341 -0.0961440876 -0.4501100183 3117 1311867274.4357678890 0.0682888925 0.0652776340 0.1147603467 0.0061337198 0.0307450000 257132386 95654152 760807424 0.0273500830 -0.0982841402 -0.4455158412 3118 1311867274.4689209461 0.0689196885 0.0652788021 0.1147603467 0.0061365716 0.0341820000 257303466 95654152 760807424 0.0265570302 -0.0978477448 -0.4424030185 3119 1311867274.4997699261 0.0683336928 0.0652797815 0.1147603467 0.0061362688 0.0408550000 257307026 95654152 760807424 0.0244994946 -0.1002298594 -0.4390943646 3120 1311867274.5345981121 0.0687314048 0.0652808878 0.1147603467 0.0061359813 0.0306400000 257310554 95654152 760807424 0.0217502192 -0.1014802605 -0.4357394874 3121 1311867274.5686841011 0.0687517151 0.0652819999 0.1147603467 0.0061352468 0.0307070000 257312426 95654152 760807424 0.0214916356 -0.1025610194 -0.4323190749 3122 1311867274.6001191139 0.0687702000 0.0652831172 0.1147603467 0.0061349468 0.0311430000 257315898 95654152 760807424 0.0209830366 -0.1036936119 -0.4293822944 3123 1311867274.6349270344 0.0668571889 0.0652836212 0.1147603467 0.0061350413 0.0303060000 257317882 95654152 760807424 0.0198813640 -0.1074279696 -0.4257910550 3124 1311867274.6665649414 0.0670964345 0.0652842015 0.1147603467 0.0061365483 0.0340950000 257321298 95654152 760807424 0.0205235127 -0.1076920182 -0.4229222238 3125 1311867274.6988699436 0.0670919716 0.0652847800 0.1147603467 0.0061357624 0.0307110000 257495606 95654152 760807424 0.0203367937 -0.1081041843 -0.4198151529 3126 1311867274.7355759144 0.0667155460 0.0652852377 0.1147603467 0.0061386580 0.0421180000 257497334 95654152 760807424 0.0187807735 -0.1087825522 -0.4171940386 3127 1311867274.7669000626 0.0668305457 0.0652857319 0.1147603467 0.0061379599 0.0303620000 257501006 95654152 760807424 0.0162937939 -0.1098725349 -0.4140486419 3128 1311867274.8040020466 0.0657418668 0.0652858777 0.1147603467 0.0061377625 0.0487950000 257504646 95654152 760807424 0.0160026364 -0.1107559875 -0.4112716019 3129 1311867274.8350889683 0.0647827089 0.0652857169 0.1147603467 0.0061379482 0.0307120000 257506518 95654152 760807424 0.0144510157 -0.1140779629 -0.4066278338 3130 1311867274.8671360016 0.0644424707 0.0652854475 0.1147603467 0.0061372209 0.0307740000 257509990 95654152 760807424 0.0135710454 -0.1143726483 -0.4035096765 3131 1311867274.9044289589 0.0641448796 0.0652850832 0.1147603467 0.0061362871 0.0307680000 257511974 95654152 760807424 0.0105623733 -0.1162642911 -0.3993056417 3132 1311867274.9350550175 0.0633213744 0.0652844562 0.1147603467 0.0061354833 0.0302790000 257515446 95654152 760807424 0.0108828479 -0.1162398681 -0.3964189291 3133 1311867274.9666490555 0.0640065372 0.0652840483 0.1147603467 0.0061347103 0.0351730000 257519062 95654152 760807424 0.0102403676 -0.1159605235 -0.3924786150 3134 1311867275.0030829906 0.0609519593 0.0652826660 0.1147603467 0.0061365154 0.0307460000 257520902 95654152 760807424 0.0086681936 -0.1216427237 -0.3875206709 3135 1311867275.0368080139 0.0624740198 0.0652817701 0.1147603467 0.0061420476 0.0347750000 257524574 95654152 760807424 0.0084450413 -0.1190513447 -0.3837526143 3136 1311867275.0664451122 0.0618842915 0.0652806868 0.1147603467 0.0061439302 0.0303100000 257526190 95654152 760807424 0.0076005147 -0.1204803139 -0.3801878095 3137 1311867275.1023271084 0.0598478504 0.0652789549 0.1147603467 0.0061440588 0.0310120000 257529974 95654152 760807424 0.0064169583 -0.1242409945 -0.3764173388 3138 1311867275.1351230145 0.0591657944 0.0652770068 0.1147603467 0.0061432616 0.0308170000 257533446 95654152 760807424 0.0052610803 -0.1266070455 -0.3724361956 3139 1311867275.1667180061 0.0605317317 0.0652754951 0.1147603467 0.0061424444 0.0307420000 257705482 95654152 760807424 0.0049126288 -0.1250800043 -0.3688258827 3140 1311867275.2041749954 0.0591508150 0.0652735445 0.1147603467 0.0061421722 0.0406230000 257709122 95654152 760807424 0.0042585954 -0.1271639019 -0.3650951982 3141 1311867275.2371780872 0.0589823090 0.0652715416 0.1147603467 0.0061414101 0.0308860000 257711050 95654152 760807424 0.0044930819 -0.1276361346 -0.3615893722 3142 1311867275.2668180466 0.0598770492 0.0652698247 0.1147603467 0.0061427776 0.0308160000 257714410 95654152 760807424 0.0034498181 -0.1271483153 -0.3579466641 3143 1311867275.3026800156 0.0600709058 0.0652681706 0.1147603467 0.0061447076 0.0307010000 257718194 95654152 760807424 0.0038968483 -0.1257184446 -0.3547971249 3144 1311867275.3351879120 0.0616642907 0.0652670243 0.1147603467 0.0061448123 0.0342530000 257719866 95654152 760807424 0.0028055725 -0.1234744042 -0.3510057032 3145 1311867275.3669109344 0.0616104417 0.0652658616 0.1147603467 0.0061459370 0.0341670000 257723538 95654152 760807424 0.0000133244 -0.1254764795 -0.3459303677 3146 1311867275.4038369656 0.0613554195 0.0652646187 0.1147603467 0.0061454436 0.0309510000 257727066 95654152 760807424 0.0002931761 -0.1249073669 -0.3421873748 3147 1311867275.4349598885 0.0601527207 0.0652629943 0.1147603467 0.0061460053 0.0414340000 257728938 95654152 760807424 -0.0006325459 -0.1286893487 -0.3374707699 3148 1311867275.4669399261 0.0601854324 0.0652613813 0.1147603467 0.0061452084 0.0308980000 257732354 95654152 760807424 -0.0026210127 -0.1293810904 -0.3329307735 3149 1311867275.5037291050 0.0612546988 0.0652601090 0.1147603467 0.0061444200 0.0318910000 257734394 95654152 760807424 -0.0043213489 -0.1271551251 -0.3294999003 3150 1311867275.5353329182 0.0614131689 0.0652588877 0.1147603467 0.0061451927 0.0311780000 257908778 95654152 760807424 -0.0048587359 -0.1275001615 -0.3254301846 3151 1311867275.5668909550 0.0609792061 0.0652575295 0.1147603467 0.0061483606 0.0308700000 257912394 95654152 760807424 -0.0065728612 -0.1295159161 -0.3212442398 3152 1311867275.6028299332 0.0602254309 0.0652559330 0.1147603467 0.0061493028 0.0310650000 257914234 95654152 760807424 -0.0084524490 -0.1312084943 -0.3173263371 3153 1311867275.6383280754 0.0595649928 0.0652541281 0.1147603467 0.0061497886 0.0308970000 257918018 95654152 760807424 -0.0087677781 -0.1314121187 -0.3142067790 3154 1311867275.6682209969 0.0584473424 0.0652519700 0.1147603467 0.0061493475 0.0427740000 257919578 95654152 760807424 -0.0106309839 -0.1339007765 -0.3113442659 3155 1311867275.7045888901 0.0588352345 0.0652499361 0.1147603467 0.0061487434 0.0310060000 257923362 95654152 760807424 -0.0123801241 -0.1347009987 -0.3073892891 3156 1311867275.7349820137 0.0592194609 0.0652480253 0.1147603467 0.0061479605 0.0308470000 257926722 95654152 760807424 -0.0133540565 -0.1333759576 -0.3056297004 3157 1311867275.7792279720 0.0578749105 0.0652456899 0.1147603467 0.0061480173 0.0308770000 257929042 95654152 760807424 -0.0149822272 -0.1339768916 -0.3034090400 3158 1311867275.8028490543 0.0579637103 0.0652433840 0.1147603467 0.0061480086 0.0309030000 257932234 95654152 760807424 -0.0167022068 -0.1360546798 -0.2992313504 3159 1311867275.8355960846 0.0587030314 0.0652413136 0.1147603467 0.0061489840 0.0310670000 257934050 95654152 760807424 -0.0177033786 -0.1352566928 -0.2955750227 3160 1311867275.8701560497 0.0589455068 0.0652393212 0.1147603467 0.0061481873 0.0308440000 257937634 95654152 760807424 -0.0197944939 -0.1346472949 -0.2927233279 3161 1311867275.9032120705 0.0571158230 0.0652367513 0.1147603467 0.0061484103 0.0437160000 257941362 95654152 760807424 -0.0213763919 -0.1369509697 -0.2899082601 3162 1311867275.9371318817 0.0555106662 0.0652336754 0.1147603467 0.0061475467 0.0311260000 257943090 95654152 760807424 -0.0221452489 -0.1387488246 -0.2867760062 3163 1311867275.9683859348 0.0562215596 0.0652308262 0.1147603467 0.0061468682 0.0345000000 257946762 95654152 760807424 -0.0233560037 -0.1372837722 -0.2839083672 3164 1311867276.0048470497 0.0574648306 0.0652283717 0.1147603467 0.0061483739 0.0308780000 257950346 95654152 760807424 -0.0254399627 -0.1352956146 -0.2808857560 3165 1311867276.0387539864 0.0551057383 0.0652251734 0.1147603467 0.0061499847 0.0309560000 257952274 95654152 760807424 -0.0279336553 -0.1403716356 -0.2764498591 3166 1311867276.0739030838 0.0571744107 0.0652226305 0.1147603467 0.0061531091 0.0312280000 257955858 95654152 760807424 -0.0286821723 -0.1372577697 -0.2732239366 3167 1311867276.1051371098 0.0573803671 0.0652201543 0.1147603467 0.0061539873 0.0309250000 257957730 95654152 760807424 -0.0295948200 -0.1363451779 -0.2707833946 3168 1311867276.1382379532 0.0576984100 0.0652177800 0.1147603467 0.0061560916 0.0402660000 257961146 95654152 760807424 -0.0341311432 -0.1391674578 -0.2662944198 3169 1311867276.1709389687 0.0563441329 0.0652149798 0.1147603467 0.0061588974 0.0318340000 257964818 95654152 760807424 -0.0342429727 -0.1405969560 -0.2636355758 3170 1311867276.2042279243 0.0566197522 0.0652122684 0.1147603467 0.0061581030 0.0309620000 257966602 95654152 760807424 -0.0346196815 -0.1397048831 -0.2610546947 3171 1311867276.2357859612 0.0572754256 0.0652097655 0.1147603467 0.0061571613 0.0309750000 257970218 95654152 760807424 -0.0354366042 -0.1395042390 -0.2576459646 3172 1311867276.2747719288 0.0571832247 0.0652072350 0.1147603467 0.0061563327 0.0310230000 257972114 95654152 760807424 -0.0360398516 -0.1394484937 -0.2542947531 3173 1311867276.3027520180 0.0575523190 0.0652048225 0.1147603467 0.0061565579 0.0310350000 257975618 95654152 760807424 -0.0372335613 -0.1396478266 -0.2520139813 3174 1311867276.3387188911 0.0573912747 0.0652023608 0.1147603467 0.0061558901 0.0310750000 257979202 95654152 760807424 -0.0397585109 -0.1410220861 -0.2487169653 3175 1311867276.3729600906 0.0566061661 0.0651996533 0.1147603467 0.0061552381 0.0405800000 257981130 95654152 760807424 -0.0404954962 -0.1429862827 -0.2460412383 3176 1311867276.4031929970 0.0560891964 0.0651967848 0.1147603467 0.0061560439 0.0310040000 257984546 95654152 760807424 -0.0416906625 -0.1450404078 -0.2436470389 3177 1311867276.4360129833 0.0554422401 0.0651937144 0.1147603467 0.0061560847 0.0311880000 258156454 95654152 760807424 -0.0429356471 -0.1456786990 -0.2417890280 3178 1311867276.4737091064 0.0552494861 0.0651905853 0.1147603467 0.0061576869 0.0311400000 258160150 95654152 760807424 -0.0450937040 -0.1477106810 -0.2389823049 3179 1311867276.5048420429 0.0542593859 0.0651871468 0.1147603467 0.0061572522 0.0318590000 258163766 95654152 760807424 -0.0453885458 -0.1476595849 -0.2376963496 3180 1311867276.5387470722 0.0551179610 0.0651839804 0.1147603467 0.0061565514 0.0311610000 258165494 95654152 760807424 -0.0444088653 -0.1463429332 -0.2352674007 3181 1311867276.5746779442 0.0548248067 0.0651807238 0.1147603467 0.0061556206 0.0311450000 258169278 95654152 760807424 -0.0464406833 -0.1470351666 -0.2326288819 3182 1311867276.6041920185 0.0545549132 0.0651773844 0.1147603467 0.0061546875 0.0434550000 258172582 95654152 760807424 -0.0469573438 -0.1460053921 -0.2311417758 3183 1311867276.6361470222 0.0547989085 0.0651741238 0.1147603467 0.0061537649 0.0311320000 258174398 95654152 760807424 -0.0487612896 -0.1476441920 -0.2278677225 3184 1311867276.6710920334 0.0546358190 0.0651708141 0.1147603467 0.0061535973 0.0311910000 258177982 95654152 760807424 -0.0494607948 -0.1490306854 -0.2239231020 3185 1311867276.7029719353 0.0558311716 0.0651678817 0.1147603467 0.0061547356 0.0311640000 258179854 95654152 760807424 -0.0485184528 -0.1476254016 -0.2212484628 3186 1311867276.7360780239 0.0541474000 0.0651644226 0.1147603467 0.0061545907 0.0311200000 258183326 95654152 760807424 -0.0500381552 -0.1499617249 -0.2196631879 3187 1311867276.7721960545 0.0526711494 0.0651605026 0.1147603467 0.0061589855 0.0312360000 258187166 95654152 760807424 -0.0515357256 -0.1509550512 -0.2180202156 3188 1311867276.8029088974 0.0531951562 0.0651567493 0.1147603467 0.0061668982 0.0311920000 258188782 95654152 760807424 -0.0519430153 -0.1504200995 -0.2167328298 3189 1311867276.8375699520 0.0533396378 0.0651530437 0.1147603467 0.0061683454 0.0312820000 258192510 95654152 760807424 -0.0518673360 -0.1500845104 -0.2144222260 3190 1311867276.8740971088 0.0542873293 0.0651496376 0.1147603467 0.0061686702 0.0311690000 258194350 95654152 760807424 -0.0556113385 -0.1522042453 -0.2113054842 3191 1311867276.9029750824 0.0546194017 0.0651463376 0.1147603467 0.0061694244 0.0311070000 258197910 95654152 760807424 -0.0558316149 -0.1513926685 -0.2098146975 3192 1311867276.9374980927 0.0531965010 0.0651425939 0.1147603467 0.0061719941 0.0310830000 258201438 95654152 760807424 -0.0545808412 -0.1516840011 -0.2079793811 3193 1311867276.9726910591 0.0530621223 0.0651388105 0.1147603467 0.0061715432 0.0312470000 258203422 95654152 760807424 -0.0557996370 -0.1527458131 -0.2051263899 3194 1311867277.0050029755 0.0529816151 0.0651350042 0.1147603467 0.0061715870 0.0311600000 258206950 95654152 760807424 -0.0565652438 -0.1521429867 -0.2028311789 3195 1311867277.0356070995 0.0536156446 0.0651313988 0.1147603467 0.0061707223 0.0346520000 258208766 95654152 760807424 -0.0565798804 -0.1509339660 -0.1998166591 3196 1311867277.0711610317 0.0536900423 0.0651278189 0.1147603467 0.0061700252 0.0344150000 258212294 95654152 760807424 -0.0577437654 -0.1513890326 -0.1964131147 3197 1311867277.1039769650 0.0531854443 0.0651240834 0.1147603467 0.0061700534 0.0312680000 258216022 95654152 760807424 -0.0592968389 -0.1533571333 -0.1929618418 3198 1311867277.1350269318 0.0538601764 0.0651205612 0.1147603467 0.0061716028 0.0312930000 258217582 95654152 760807424 -0.0585973561 -0.1507517248 -0.1904487163 3199 1311867277.1708490849 0.0534895100 0.0651169254 0.1147603467 0.0061719709 0.0320080000 258221366 95654152 760807424 -0.0584848747 -0.1487748474 -0.1876543313 3200 1311867277.2029759884 0.0544590056 0.0651135948 0.1147603467 0.0061712265 0.0313160000 258224894 95654152 760807424 -0.0596054196 -0.1479685903 -0.1838088185 3201 1311867277.2351000309 0.0551157668 0.0651104714 0.1147603467 0.0061705412 0.0313140000 258226766 95654152 760807424 -0.0619298220 -0.1492844671 -0.1796254963 3202 1311867277.2733149529 0.0536926463 0.0651069056 0.1147603467 0.0061705724 0.0348360000 258230462 95654152 760807424 -0.0629935637 -0.1511257589 -0.1764368266 3203 1311867277.3063778877 0.0532670058 0.0651032091 0.1147603467 0.0061696251 0.0353720000 258402490 95654152 760807424 -0.0625103489 -0.1509671956 -0.1733255535 3204 1311867277.3396029472 0.0535861105 0.0650996145 0.1147603467 0.0061690482 0.0314410000 258406018 95654152 760807424 -0.0613583513 -0.1485499442 -0.1707007289 3205 1311867277.3773889542 0.0529513806 0.0650958241 0.1147603467 0.0061691046 0.0315070000 258409802 95654152 760807424 -0.0622794405 -0.1497516036 -0.1674005836 3206 1311867277.4055531025 0.0519271642 0.0650917166 0.1147603467 0.0061684551 0.0314220000 258411306 95654152 760807424 -0.0611463934 -0.1531302929 -0.1639169306 3207 1311867277.4425079823 0.0513081439 0.0650874186 0.1147603467 0.0061682894 0.0346000000 258415090 95654152 760807424 -0.0639162883 -0.1537887603 -0.1613787413 3208 1311867277.4723749161 0.0531760044 0.0650837056 0.1147603467 0.0061772555 0.0313680000 258416706 95654152 760807424 -0.0639003664 -0.1506923139 -0.1591051519 3209 1311867277.5057780743 0.0525026619 0.0650797850 0.1147603467 0.0061802663 0.0313910000 258420322 95654152 760807424 -0.0643573478 -0.1518483609 -0.1555883437 3210 1311867277.5401940346 0.0514772236 0.0650755475 0.1147603467 0.0061888777 0.0314910000 258423906 95654152 760807424 -0.0661668777 -0.1556949019 -0.1517897844 3211 1311867277.5715351105 0.0521236919 0.0650715139 0.1147603467 0.0061938817 0.0314690000 258425778 95654152 760807424 -0.0660507306 -0.1544189304 -0.1499819010 3212 1311867277.6027710438 0.0530750342 0.0650677790 0.1147603467 0.0061932255 0.0355220000 258429194 95654152 760807424 -0.0650625005 -0.1529516578 -0.1478060335 3213 1311867277.6416130066 0.0519935600 0.0650637098 0.1147603467 0.0061954202 0.0314450000 258431234 95654152 760807424 -0.0661701784 -0.1568068862 -0.1449500471 3214 1311867277.6713008881 0.0517259203 0.0650595599 0.1147603467 0.0061949057 0.0346190000 258434706 95654152 760807424 -0.0666313842 -0.1583902240 -0.1430679113 3215 1311867277.7063589096 0.0511469431 0.0650552325 0.1147603467 0.0061956903 0.0313050000 258438378 95654152 760807424 -0.0651398301 -0.1550999433 -0.1425117701 3216 1311867277.7401409149 0.0509607308 0.0650508499 0.1147603467 0.0061956192 0.0313900000 258440106 95654152 760807424 -0.0646867156 -0.1538296193 -0.1400414854 3217 1311867277.7720079422 0.0518762842 0.0650467546 0.1147603467 0.0061946961 0.0353850000 258443778 95654152 760807424 -0.0659621730 -0.1547757685 -0.1359006464 3218 1311867277.8036880493 0.0522505976 0.0650427782 0.1147603467 0.0061945193 0.0314250000 258447250 95654152 760807424 -0.0651468039 -0.1531575620 -0.1327630281 3219 1311867277.8400499821 0.0530525222 0.0650390533 0.1147603467 0.0061937642 0.0314690000 258449234 95654152 760807424 -0.0638524294 -0.1504724026 -0.1298253387 3220 1311867277.8711171150 0.0515398756 0.0650348610 0.1147603467 0.0061952426 0.0314010000 258452706 95654152 760807424 -0.0651418492 -0.1553077251 -0.1256117374 3221 1311867277.9031610489 0.0516036116 0.0650306911 0.1147603467 0.0061943535 0.0314530000 258454578 95654152 760807424 -0.0644987375 -0.1567661911 -0.1216547415 3222 1311867277.9393019676 0.0506384932 0.0650262243 0.1147603467 0.0061941090 0.0314910000 258458162 95654152 760807424 -0.0630191043 -0.1558470130 -0.1190612987 3223 1311867277.9714229107 0.0511989817 0.0650219341 0.1147603467 0.0061951238 0.0314040000 258461834 95654152 760807424 -0.0628208369 -0.1560069621 -0.1151521280 3224 1311867278.0041360855 0.0511334985 0.0650176263 0.1147603467 0.0061942431 0.0434730000 258463506 95654152 760807424 -0.0637487024 -0.1586506814 -0.1114400104 3225 1311867278.0394210815 0.0510404184 0.0650132923 0.1147603467 0.0061950929 0.0315540000 258467234 95654152 760807424 -0.0621636361 -0.1590785384 -0.1079035476 3226 1311867278.0712630749 0.0504968353 0.0650087924 0.1147603467 0.0061946549 0.0314220000 258639570 95654152 760807424 -0.0606927946 -0.1594470888 -0.1050063819 3227 1311867278.1056289673 0.0504100733 0.0650042685 0.1147603467 0.0061937204 0.0353880000 258643354 95654152 760807424 -0.0600147434 -0.1583895981 -0.1022075638 3228 1311867278.1391980648 0.0511458479 0.0649999753 0.1147603467 0.0061931918 0.0313630000 258646826 95654152 760807424 -0.0608776659 -0.1609733254 -0.0971785933 3229 1311867278.1710369587 0.0499881320 0.0649953262 0.1147603467 0.0061922359 0.0313330000 258648698 95654152 760807424 -0.0589226633 -0.1601432711 -0.0946092308 3230 1311867278.2038609982 0.0507838726 0.0649909264 0.1147603467 0.0061941032 0.0322600000 258652226 95654152 760807424 -0.0585084967 -0.1591220945 -0.0907832980 3231 1311867278.2388060093 0.0502251238 0.0649863564 0.1147603467 0.0062008096 0.0355450000 258654210 95654152 760807424 -0.0587744415 -0.1611174196 -0.0867200121 3232 1311867278.2707629204 0.0506182276 0.0649819108 0.1147603467 0.0062022754 0.0308900000 258657626 95654152 760807424 -0.0585037246 -0.1629450470 -0.0826397985 3233 1311867278.3027629852 0.0502166711 0.0649773437 0.1147603467 0.0062013385 0.0342270000 258661298 95654152 760807424 -0.0579628199 -0.1610786021 -0.0807153806 3234 1311867278.3421599865 0.0498812906 0.0649726758 0.1147603467 0.0062012410 0.0347540000 258663194 95654152 760807424 -0.0576836057 -0.1624312103 -0.0767535865 3235 1311867278.3714361191 0.0507794544 0.0649682884 0.1147603467 0.0062003958 0.0313220000 258666754 95654152 760807424 -0.0590346605 -0.1648545414 -0.0727164894 3236 1311867278.4035348892 0.0507982038 0.0649639095 0.1147603467 0.0061994539 0.0313140000 258840510 95654152 760807424 -0.0575590432 -0.1636127532 -0.0699664652 3237 1311867278.4391169548 0.0499736145 0.0649592786 0.1147603467 0.0061987630 0.0308700000 258842438 95654152 760807424 -0.0566849522 -0.1626994312 -0.0675472990 3238 1311867278.4713339806 0.0505741201 0.0649548360 0.1147603467 0.0061983572 0.0313520000 258845966 95654152 760807424 -0.0583183393 -0.1651121378 -0.0638537556 3239 1311867278.5041239262 0.0505519286 0.0649503893 0.1147603467 0.0061976967 0.0308580000 258847838 95654152 760807424 -0.0594921671 -0.1673139036 -0.0607608818 3240 1311867278.5423910618 0.0498088449 0.0649457160 0.1147603467 0.0061970363 0.0318990000 259022358 95654152 760807424 -0.0585224517 -0.1681290269 -0.0575517900 3241 1311867278.5710260868 0.0493468866 0.0649409030 0.1147603467 0.0061971050 0.0311520000 259025918 95654152 760807424 -0.0567267947 -0.1651407629 -0.0557507910 3242 1311867278.6069030762 0.0495214984 0.0649361469 0.1147603467 0.0061966177 0.0345340000 259027702 95654152 760807424 -0.0569256134 -0.1659720838 -0.0520916097 3243 1311867278.6393239498 0.0499316044 0.0649315201 0.1147603467 0.0061960542 0.0307680000 259031374 95654152 760807424 -0.0579550937 -0.1679265797 -0.0482504070 3244 1311867278.6709709167 0.0491972901 0.0649266699 0.1147603467 0.0061980086 0.0307800000 259033102 95654152 760807424 -0.0555992089 -0.1670864671 -0.0452146903 3245 1311867278.7069129944 0.0504399948 0.0649222056 0.1147603467 0.0061974295 0.0430520000 259036830 95654152 760807424 -0.0531966984 -0.1631934494 -0.0414889157 3246 1311867278.7390680313 0.0514042377 0.0649180411 0.1147603467 0.0061978389 0.0311320000 259040302 95654152 760807424 -0.0551384762 -0.1662372947 -0.0367820635 3247 1311867278.7718300819 0.0515496954 0.0649139239 0.1147603467 0.0061984832 0.0312400000 259042174 95654152 760807424 -0.0558500625 -0.1681263298 -0.0337071940 3248 1311867278.8068239689 0.0509270988 0.0649096176 0.1147603467 0.0061980046 0.0352780000 259045758 95654152 760807424 -0.0529223904 -0.1639732867 -0.0319497474 3249 1311867278.8386530876 0.0513522327 0.0649054449 0.1147603467 0.0061980544 0.0350260000 259047686 95654152 760807424 -0.0525460616 -0.1643608660 -0.0287387017 3250 1311867278.8741700649 0.0512006544 0.0649012280 0.1147603467 0.0061981393 0.0309290000 259051214 95654152 760807424 -0.0552236997 -0.1708087176 -0.0245807040 3251 1311867278.9090650082 0.0496846363 0.0648965474 0.1147603467 0.0061977906 0.0342390000 259054942 95654152 760807424 -0.0530380681 -0.1692580879 -0.0228821244 3252 1311867278.9392769337 0.0503516458 0.0648920748 0.1147603467 0.0062002973 0.0340010000 259056614 95654152 760807424 -0.0516130701 -0.1630513668 -0.0211802162 3253 1311867278.9711430073 0.0513819419 0.0648879217 0.1147603467 0.0062002071 0.0313520000 259060286 95654152 760807424 -0.0542646237 -0.1668778360 -0.0164215975 3254 1311867279.0073111057 0.0514125265 0.0648837805 0.1147603467 0.0062025421 0.0308540000 259063870 95654152 760807424 -0.0556343533 -0.1715940088 -0.0119656790 3255 1311867279.0397729874 0.0502442122 0.0648792829 0.1147603467 0.0062040374 0.0471540000 259235970 95654152 760807424 -0.0537335873 -0.1669030637 -0.0111360010 3256 1311867279.0738539696 0.0497977696 0.0648746510 0.1147603467 0.0062034800 0.0310540000 259239498 95654152 760807424 -0.0540365279 -0.1670563817 -0.0079837134 3257 1311867279.1068439484 0.0514286608 0.0648705227 0.1147603467 0.0062029379 0.0314280000 259241370 95654152 760807424 -0.0562470332 -0.1689956039 -0.0038511800 3258 1311867279.1392490864 0.0502362549 0.0648660309 0.1147603467 0.0062022257 0.0309150000 259244898 95654152 760807424 -0.0552465096 -0.1692846119 -0.0010786494 3259 1311867279.1712040901 0.0506350324 0.0648616642 0.1147603467 0.0062097690 0.0367510000 259248514 95654152 760807424 -0.0531666391 -0.1658826023 0.0012835688 3260 1311867279.2070438862 0.0506705679 0.0648573111 0.1147603467 0.0062099536 0.0354030000 259250298 95654152 760807424 -0.0542034432 -0.1641155928 0.0040437584 3261 1311867279.2411210537 0.0514867976 0.0648532110 0.1147603467 0.0062103949 0.0309660000 259254026 95654152 760807424 -0.0564120822 -0.1678759307 0.0087062884 3262 1311867279.2717759609 0.0505749285 0.0648488338 0.1147603467 0.0062102540 0.0313180000 259255642 95654152 760807424 -0.0540599674 -0.1656049490 0.0110260285 3263 1311867279.3067219257 0.0502741002 0.0648443672 0.1147603467 0.0062096085 0.0314180000 259259426 95654152 760807424 -0.0520223379 -0.1647674888 0.0137760146 3264 1311867279.3388090134 0.0508345366 0.0648400749 0.1147603467 0.0062103538 0.0309350000 259262898 95654152 760807424 -0.0533280633 -0.1662573367 0.0174352676 3265 1311867279.3804929256 0.0500684269 0.0648355507 0.1147603467 0.0062110638 0.0347490000 259265050 95654152 760807424 -0.0533278883 -0.1642710865 0.0204527341 3266 1311867279.4089910984 0.0510148369 0.0648313190 0.1147603467 0.0062118971 0.0355950000 259268298 95654152 760807424 -0.0521919765 -0.1611814797 0.0231947768 3267 1311867279.4410970211 0.0509401672 0.0648270670 0.1147603467 0.0062124125 0.0312240000 259440730 95654152 760807424 -0.0528529212 -0.1617448777 0.0267238002 3268 1311867279.4725570679 0.0521291904 0.0648231815 0.1147603467 0.0062116194 0.0314490000 259444202 95654152 760807424 -0.0537997447 -0.1644544154 0.0310240928 3269 1311867279.5095710754 0.0505988710 0.0648188302 0.1147603467 0.0062111775 0.0362120000 259448042 95654152 760807424 -0.0530626513 -0.1629361510 0.0326089077 3270 1311867279.5407390594 0.0507107265 0.0648145158 0.1147603467 0.0062115573 0.0314480000 259449546 95654152 760807424 -0.0539396591 -0.1612575501 0.0348697975 3271 1311867279.5734229088 0.0521262437 0.0648106368 0.1147603467 0.0062116482 0.0314250000 259453330 95654152 760807424 -0.0555332899 -0.1644611806 0.0389984101 3272 1311867279.6121640205 0.0517361648 0.0648066410 0.1147603467 0.0062113190 0.0355690000 259456970 95654152 760807424 -0.0563959107 -0.1662685573 0.0422953032 3273 1311867279.6389439106 0.0512239449 0.0648024910 0.1147603467 0.0062126683 0.0413430000 259458674 95654152 760807424 -0.0544789545 -0.1622224003 0.0431383066 3274 1311867279.6749770641 0.0517742112 0.0647985117 0.1147603467 0.0062155881 0.0316120000 259462314 95654152 760807424 -0.0551503040 -0.1650722921 0.0472698882 3275 1311867279.7107980251 0.0509667136 0.0647942883 0.1147603467 0.0062153470 0.0312080000 259464186 95654152 760807424 -0.0543732680 -0.1635051370 0.0492114872 3276 1311867279.7410199642 0.0506712645 0.0647899772 0.1147603467 0.0062148181 0.0315010000 259467602 95654152 760807424 -0.0532219000 -0.1612097025 0.0510899946 3277 1311867279.7777059078 0.0508907251 0.0647857358 0.1147603467 0.0062144940 0.0317150000 259471442 95654152 760807424 -0.0539934114 -0.1617123336 0.0546030849 3278 1311867279.8118851185 0.0526422486 0.0647820312 0.1147603467 0.0062141749 0.0316700000 259644262 95654152 760807424 -0.0552352816 -0.1639261246 0.0590552315 3279 1311867279.8438251019 0.0503511615 0.0647776302 0.1147603467 0.0062134764 0.0315730000 259647934 95654152 760807424 -0.0535376146 -0.1640770584 0.0606897660 3280 1311867279.8808829784 0.0496250056 0.0647730105 0.1147603467 0.0062159645 0.0316540000 259649718 95654152 760807424 -0.0519921929 -0.1620194167 0.0631776378 3281 1311867279.9088180065 0.0503457524 0.0647686133 0.1147603467 0.0062175967 0.0312760000 259653334 95654152 760807424 -0.0513178185 -0.1653281301 0.0672583953 3282 1311867279.9440410137 0.0504045300 0.0647642367 0.1147603467 0.0062173422 0.0313180000 259656918 95654152 760807424 -0.0512928665 -0.1667393297 0.0705168247 3283 1311867279.9795188904 0.0487431362 0.0647593567 0.1147603467 0.0062215565 0.0317220000 259658846 95654152 760807424 -0.0491846316 -0.1626354754 0.0713681728 3284 1311867280.0113790035 0.0501218289 0.0647548994 0.1147603467 0.0062233059 0.0357890000 259662262 95654152 760807424 -0.0503838994 -0.1647873819 0.0760565251 3285 1311867280.0401859283 0.0505686998 0.0647505810 0.1147603467 0.0062232868 0.0354130000 259664022 95654152 760807424 -0.0501010790 -0.1651289165 0.0793590844 3286 1311867280.0785079002 0.0496691316 0.0647459913 0.1147603467 0.0062246665 0.0350170000 259839742 95654152 760807424 -0.0470559485 -0.1610215008 0.0815949216 3287 1311867280.1111929417 0.0512381755 0.0647418819 0.1147603467 0.0062242035 0.0423380000 259843414 95654152 760807424 -0.0475873873 -0.1633310318 0.0858517140 3288 1311867280.1450068951 0.0524263754 0.0647381363 0.1147603467 0.0062232842 0.0320830000 259845198 95654152 760807424 -0.0490039736 -0.1653750539 0.0896739140 3289 1311867280.1753098965 0.0509356894 0.0647339397 0.1147603467 0.0062248474 0.0320360000 259848758 95654152 760807424 -0.0465939641 -0.1640515924 0.0910343602 3290 1311867280.2123339176 0.0512075126 0.0647298284 0.1147603467 0.0062257164 0.0395660000 259904110 95654152 760807424 -0.0450857580 -0.1621036083 0.0941729918 3291 1311867280.2422859669 0.0529354513 0.0647262445 0.1147603467 0.0062249439 0.0315980000 260076822 95654152 760807424 -0.0456978008 -0.1645694673 0.0988238007 3292 1311867280.2794580460 0.0509189591 0.0647220503 0.1147603467 0.0062300577 0.0318490000 260080462 95654152 760807424 -0.0439264439 -0.1608486772 0.0990061089 3293 1311867280.3114728928 0.0517828017 0.0647181210 0.1147603467 0.0062311492 0.0353420000 260082334 95654152 760807424 -0.0449936315 -0.1620224863 0.1024190336 3294 1311867280.3445079327 0.0538589880 0.0647148244 0.1147603467 0.0062315031 0.0353700000 260085750 95654152 760807424 -0.0455104448 -0.1639368534 0.1073376760 3295 1311867280.3755340576 0.0524812937 0.0647111116 0.1147603467 0.0062309490 0.0319240000 260089422 95654152 760807424 -0.0431646965 -0.1596489102 0.1079678237 3296 1311867280.4071900845 0.0542007685 0.0647079228 0.1147603467 0.0062310544 0.0357190000 260091038 95654152 760807424 -0.0438662134 -0.1618113816 0.1125206053 3297 1311867280.4424109459 0.0539558306 0.0647046616 0.1147603467 0.0062320773 0.0319730000 260094822 95654152 760807424 -0.0427769125 -0.1616851687 0.1151219755 3298 1311867280.4782869816 0.0526506156 0.0647010067 0.1147603467 0.0062320334 0.0320260000 260267786 95654152 760807424 -0.0419225022 -0.1595134586 0.1168944687 3299 1311867280.5091259480 0.0528977253 0.0646974288 0.1147603467 0.0062315671 0.0323070000 260271458 95654152 760807424 -0.0411700644 -0.1596056670 0.1198336929 3300 1311867280.5455989838 0.0531997234 0.0646939447 0.1147603467 0.0062307266 0.0320800000 260274986 95654152 760807424 -0.0417039916 -0.1593356282 0.1229457483 3301 1311867280.5782079697 0.0530081019 0.0646904046 0.1147603467 0.0062320867 0.0320850000 260276858 95654152 760807424 -0.0418728814 -0.1576971710 0.1248626709 3302 1311867280.6130499840 0.0535903350 0.0646870430 0.1147603467 0.0062320776 0.0322910000 260280386 95654152 760807424 -0.0424284376 -0.1573092490 0.1278512180 3303 1311867280.6422739029 0.0543322600 0.0646839080 0.1147603467 0.0062333393 0.0321370000 260282202 95654152 760807424 -0.0418387800 -0.1596916318 0.1313026547 3304 1311867280.6755290031 0.0533488058 0.0646804773 0.1147603467 0.0062329923 0.0321500000 260285730 95654152 760807424 -0.0416432694 -0.1592906862 0.1326088160 3305 1311867280.7094879150 0.0534672774 0.0646770845 0.1147603467 0.0062321265 0.0321730000 260289458 95654152 760807424 -0.0407857485 -0.1597584486 0.1351567656 3306 1311867280.7411808968 0.0536944605 0.0646737625 0.1147603467 0.0062323118 0.0322020000 260291074 95654152 760807424 -0.0406732932 -0.1605313718 0.1386114657 3307 1311867280.7752668858 0.0529878624 0.0646702288 0.1147603467 0.0062325879 0.0323000000 260294802 95654152 760807424 -0.0404488072 -0.1596498638 0.1393058151 3308 1311867280.8076250553 0.0534667782 0.0646668420 0.1147603467 0.0062317538 0.0364030000 260298274 95654152 760807424 -0.0396693610 -0.1596588194 0.1423523128 3309 1311867280.8401010036 0.0538707338 0.0646635794 0.1147603467 0.0062311706 0.0323030000 260300202 95654152 760807424 -0.0403584391 -0.1591936350 0.1445995569 3310 1311867280.8754839897 0.0532913655 0.0646601436 0.1147603467 0.0062302894 0.0363330000 260303730 95654152 760807424 -0.0405179150 -0.1584281325 0.1465456188 3311 1311867280.9079110622 0.0538148358 0.0646568681 0.1147603467 0.0062293785 0.0322620000 260305602 95654152 760807424 -0.0406264663 -0.1585840881 0.1496791244 3312 1311867280.9394528866 0.0539182462 0.0646536258 0.1147603467 0.0062285353 0.0322590000 260480758 95654152 760807424 -0.0410910025 -0.1573931426 0.1519330442 3313 1311867280.9766991138 0.0540441759 0.0646504234 0.1147603467 0.0062276645 0.0323010000 260484430 95654152 760807424 -0.0409399606 -0.1580379307 0.1552003026 3314 1311867281.0075190067 0.0543694384 0.0646473211 0.1147603467 0.0062267951 0.0322670000 260486102 95654152 760807424 -0.0412797257 -0.1580739021 0.1578197181 3315 1311867281.0433430672 0.0546357818 0.0646443010 0.1147603467 0.0062260577 0.0323410000 260489886 95654152 760807424 -0.0419745408 -0.1594171673 0.1607440710 3316 1311867281.0752780437 0.0546750948 0.0646412946 0.1147603467 0.0062251572 0.0322840000 260491502 95654152 760807424 -0.0423448756 -0.1593016088 0.1631579846 3317 1311867281.1074900627 0.0546459742 0.0646382813 0.1147603467 0.0062246624 0.0322920000 260495230 95654152 760807424 -0.0416893102 -0.1584471762 0.1656603962 3318 1311867281.1451520920 0.0540896207 0.0646351021 0.1147603467 0.0062242535 0.0322770000 260498814 95654152 760807424 -0.0408526696 -0.1573726982 0.1678393334 3319 1311867281.1786689758 0.0548613556 0.0646321573 0.1147603467 0.0062240178 0.0328120000 260500798 95654152 760807424 -0.0402380340 -0.1590408832 0.1710183024 3320 1311867281.2083299160 0.0536867380 0.0646288605 0.1147603467 0.0062230880 0.0325400000 260504214 95654152 760807424 -0.0390020609 -0.1577390283 0.1717581749 3321 1311867281.2457950115 0.0550235771 0.0646259682 0.1147603467 0.0062236255 0.0406200000 260509910 95654152 760807424 -0.0387789048 -0.1588092446 0.1760434061 3322 1311867281.2754399776 0.0558634922 0.0646233305 0.1147603467 0.0062229014 0.0453650000 260513334 95654152 760807424 -0.0386479013 -0.1590736508 0.1786613315 3323 1311867281.3072988987 0.0552420504 0.0646205073 0.1147603467 0.0062256205 0.0404740000 260517254 95654152 760807424 -0.0380465947 -0.1585754752 0.1802969575 3324 1311867281.3465099335 0.0543984585 0.0646174321 0.1147603467 0.0062278300 0.0405350000 260519030 95654152 760807424 -0.0354224443 -0.1580979079 0.1825286895 3325 1311867281.3751530647 0.0565973818 0.0646150201 0.1147603467 0.0062269292 0.0326300000 260522590 95654152 760807424 -0.0359309763 -0.1603370458 0.1868039519 3326 1311867281.4080700874 0.0549566969 0.0646121162 0.1147603467 0.0062261088 0.0409250000 260526246 95654152 760807424 -0.0360597074 -0.1591511220 0.1870050877 3327 1311867281.4434111118 0.0551268347 0.0646092652 0.1147603467 0.0062254173 0.0405950000 260528550 95654152 760807424 -0.0356692597 -0.1588534117 0.1895964891 3328 1311867281.4753720760 0.0568307154 0.0646069279 0.1147603467 0.0062245575 0.0333330000 260531966 95654152 760807424 -0.0361693427 -0.1606848985 0.1934972405 3329 1311867281.5101969242 0.0555463061 0.0646042061 0.1147603467 0.0062242628 0.0327770000 260533950 95654152 760807424 -0.0364227742 -0.1600205302 0.1942907423 3330 1311867281.5435659885 0.0546452329 0.0646012155 0.1147603467 0.0062243592 0.0468990000 260537670 95654152 760807424 -0.0347338282 -0.1590612233 0.1961238682 3331 1311867281.5754749775 0.0566644482 0.0645988328 0.1147603467 0.0062235901 0.0407380000 260541406 95654152 760807424 -0.0350136347 -0.1608339846 0.2000516802 3332 1311867281.6111190319 0.0563315488 0.0645963516 0.1147603467 0.0062243298 0.0406220000 260548958 95654152 760807424 -0.0350450315 -0.1599060446 0.2016915679 3333 1311867281.6435608864 0.0562002175 0.0645938325 0.1147603467 0.0062234601 0.0326510000 260552686 95654152 760807424 -0.0343523324 -0.1596808285 0.2034045756 3334 1311867281.6755120754 0.0569519959 0.0645915404 0.1147603467 0.0062235444 0.0359120000 260554358 95654152 760807424 -0.0341336764 -0.1616932154 0.2060606927 3335 1311867281.7089190483 0.0566348992 0.0645891546 0.1147603467 0.0062227447 0.0560690000 260558222 95654152 760807424 -0.0340840891 -0.1613744646 0.2071998268 3336 1311867281.7452239990 0.0555991642 0.0645864598 0.1147603467 0.0062221045 0.0325550000 260561862 95654152 760807424 -0.0322921835 -0.1599909067 0.2080239058 3337 1311867281.7755289078 0.0575167425 0.0645843412 0.1147603467 0.0062218989 0.0327160000 260563622 95654152 760807424 -0.0325457118 -0.1620849967 0.2113370001 3338 1311867281.8075580597 0.0578588620 0.0645823263 0.1147603467 0.0062213630 0.0325810000 260567094 95654152 760807424 -0.0323537886 -0.1640065908 0.2131652832 3339 1311867281.8447821140 0.0568023100 0.0645799963 0.1147603467 0.0062205368 0.0326300000 260569134 95654152 760807424 -0.0300366189 -0.1643763036 0.2141683996 3340 1311867281.8756659031 0.0576887950 0.0645779331 0.1147603467 0.0062196867 0.0327020000 260572606 95654152 760807424 -0.0296775065 -0.1639940888 0.2161228210 3341 1311867281.9077229500 0.0577583723 0.0645758919 0.1147603467 0.0062191963 0.0359980000 260576278 95654152 760807424 -0.0284294467 -0.1640007496 0.2177550942 3342 1311867281.9444870949 0.0561445989 0.0645733691 0.1147603467 0.0062199549 0.0326310000 260578006 95654152 760807424 -0.0263139587 -0.1631922871 0.2178250104 3343 1311867281.9785399437 0.0577446073 0.0645713264 0.1147603467 0.0062215105 0.0326480000 260581734 95654152 760807424 -0.0263966620 -0.1640779376 0.2204755098 3344 1311867282.0098121166 0.0578241646 0.0645693087 0.1147603467 0.0062208381 0.0327110000 260585206 95654152 760807424 -0.0243505631 -0.1652159989 0.2223351449 3345 1311867282.0436799526 0.0561790168 0.0645668004 0.1147603467 0.0062206131 0.0328680000 260587078 95654152 760807424 -0.0219513997 -0.1626365334 0.2226038873 3346 1311867282.0755469799 0.0567141362 0.0645644535 0.1147603467 0.0062199126 0.0326290000 260590550 95654152 760807424 -0.0207283981 -0.1634096950 0.2249641865 3347 1311867282.1077909470 0.0569642261 0.0645621827 0.1147603467 0.0062190779 0.0333940000 260592422 95654152 760807424 -0.0213469211 -0.1634056568 0.2262390256 3348 1311867282.1464140415 0.0567574985 0.0645598516 0.1147603467 0.0062182299 0.0431460000 260596062 95654152 760807424 -0.0192651600 -0.1624899656 0.2286387831 3349 1311867282.1797480583 0.0561155938 0.0645573301 0.1147603467 0.0062173920 0.0327010000 260599790 95654152 760807424 -0.0184293538 -0.1616487801 0.2299124151 3350 1311867282.2136330605 0.0575917885 0.0645552509 0.1147603467 0.0062170350 0.0337190000 260601518 95654152 760807424 -0.0193251222 -0.1643213928 0.2327786684 3351 1311867282.2453169823 0.0572246388 0.0645530633 0.1147603467 0.0062164065 0.0338260000 260605190 95654152 760807424 -0.0181616377 -0.1633338332 0.2341796756 3352 1311867282.2844099998 0.0572537184 0.0645508857 0.1147603467 0.0062160491 0.0338740000 260606974 95654152 760807424 -0.0175093487 -0.1638651490 0.2361125648 3353 1311867282.3187301159 0.0571898296 0.0645486903 0.1147603467 0.0062160035 0.0339250000 260610702 95654152 760807424 -0.0169175286 -0.1650718302 0.2379726321 3354 1311867282.3445549011 0.0570532419 0.0645464555 0.1147603467 0.0062152874 0.0337780000 260614006 95654152 760807424 -0.0159525350 -0.1640208960 0.2392864525 3355 1311867282.3837130070 0.0569657870 0.0645441960 0.1147603467 0.0062161408 0.0339510000 260615822 95654152 760807424 -0.0149045913 -0.1624046713 0.2407235503 3356 1311867282.4114849567 0.0573695153 0.0645420582 0.1147603467 0.0062163116 0.0338390000 260789750 95654152 760807424 -0.0140786422 -0.1643238664 0.2428368181 3357 1311867282.4437038898 0.0571155138 0.0645398459 0.1147603467 0.0062154942 0.0329080000 260791678 95654152 760807424 -0.0135946665 -0.1644276381 0.2443108559 3358 1311867282.4754569530 0.0567796864 0.0645375350 0.1147603467 0.0062151055 0.0327600000 260795094 95654152 760807424 -0.0123941302 -0.1634958982 0.2459431142 3359 1311867282.5128560066 0.0583400354 0.0645356899 0.1147603467 0.0062145724 0.0328220000 260798934 95654152 760807424 -0.0136244567 -0.1656414717 0.2483291030 3360 1311867282.5435400009 0.0579941981 0.0645337430 0.1147603467 0.0062136588 0.0367030000 260800606 95654152 760807424 -0.0124142021 -0.1662203670 0.2494854927 3361 1311867282.5755639076 0.0573348515 0.0645316012 0.1147603467 0.0062130093 0.0328810000 260804278 95654152 760807424 -0.0105486279 -0.1648556143 0.2508862615 3362 1311867282.6112899780 0.0578649081 0.0645296182 0.1147603467 0.0062122215 0.0411260000 260807806 95654152 760807424 -0.0113146799 -0.1672568023 0.2525216043 3363 1311867282.6437261105 0.0583064817 0.0645277677 0.1147603467 0.0062115589 0.0327690000 260809678 95654152 760807424 -0.0112812407 -0.1669032723 0.2539076805 3364 1311867282.6766591072 0.0580173619 0.0645258324 0.1147603467 0.0062109693 0.0413130000 260815070 95654152 760807424 -0.0110310689 -0.1651679575 0.2543474138 3365 1311867282.7147250175 0.0580236763 0.0645239001 0.1147603467 0.0062103611 0.0411340000 260817302 95654152 760807424 -0.0112446062 -0.1664444059 0.2553162277 3366 1311867282.7462520599 0.0589555949 0.0645222458 0.1147603467 0.0062096312 0.0327220000 260820774 95654152 760807424 -0.0111236731 -0.1691981852 0.2567433715 3367 1311867282.7754290104 0.0584885217 0.0645204538 0.1147603467 0.0062092939 0.0328310000 260824222 95654152 760807424 -0.0115405517 -0.1685812175 0.2569442093 3368 1311867282.8116350174 0.0585208908 0.0645186725 0.1147603467 0.0062085741 0.0408750000 260826014 95654152 760807424 -0.0131295938 -0.1693702042 0.2576733530 3369 1311867282.8475370407 0.0580638461 0.0645167565 0.1147603467 0.0062088674 0.0484230000 260829862 95654152 760807424 -0.0126673756 -0.1691169888 0.2592732310 3370 1311867282.8757910728 0.0573841371 0.0645146400 0.1147603467 0.0062081507 0.0327180000 260831478 95654152 760807424 -0.0134160491 -0.1660107225 0.2598276734 3371 1311867282.9114630222 0.0571471602 0.0645124545 0.1147603467 0.0062075388 0.0362360000 260835206 95654152 760807424 -0.0122790560 -0.1661160737 0.2615526021 3372 1311867282.9456479549 0.0581645519 0.0645105719 0.1147603467 0.0062067940 0.0328380000 260838734 95654152 760807424 -0.0128521975 -0.1674499959 0.2638874054 3373 1311867282.9811890125 0.0577669106 0.0645085726 0.1147603467 0.0062077787 0.0328610000 260840662 95654152 760807424 -0.0152678639 -0.1641455442 0.2645324767 3374 1311867283.0114879608 0.0576999262 0.0645065547 0.1147603467 0.0062074955 0.0366990000 260844134 95654152 760807424 -0.0155793298 -0.1648067683 0.2655182183 3375 1311867283.0462460518 0.0589873046 0.0645049193 0.1147603467 0.0062089051 0.0365700000 260846062 95654152 760807424 -0.0154314321 -0.1672775745 0.2679612637 3376 1311867283.0752930641 0.0587902181 0.0645032266 0.1147603467 0.0062086308 0.0439540000 260849478 95654152 760807424 -0.0157981459 -0.1663348824 0.2688487172 3377 1311867283.1116878986 0.0568548664 0.0645009617 0.1147603467 0.0062091917 0.0415610000 260853318 95654152 760807424 -0.0163982864 -0.1641352624 0.2689545751 3378 1311867283.1435511112 0.0576831773 0.0644989435 0.1147603467 0.0062095878 0.0330410000 260854990 95654152 760807424 -0.0169527959 -0.1678142101 0.2701854110 3379 1311867283.1788220406 0.0585061386 0.0644971699 0.1147603467 0.0062120784 0.0328020000 260858662 95654152 760807424 -0.0176269952 -0.1669201553 0.2712450027 3380 1311867283.2158269882 0.0592019968 0.0644956033 0.1147603467 0.0062121760 0.0329290000 260862302 95654152 760807424 -0.0174233485 -0.1660681665 0.2720674276 3381 1311867283.2441749573 0.0591747798 0.0644940296 0.1147603467 0.0062134604 0.0364800000 260864062 95654152 760807424 -0.0168031920 -0.1689429134 0.2728096545 3382 1311867283.2776839733 0.0590784438 0.0644924283 0.1147603467 0.0062132727 0.0334650000 260867590 95654152 760807424 -0.0173955094 -0.1688254029 0.2734080255 3383 1311867283.3134660721 0.0585581660 0.0644906741 0.1147603467 0.0062123960 0.0330020000 260869574 95654152 760807424 -0.0168500189 -0.1679627150 0.2741516531 3384 1311867283.3498029709 0.0598565564 0.0644893047 0.1147603467 0.0062117636 0.0369690000 260873270 95654152 760807424 -0.0164555721 -0.1696864367 0.2765893638 3385 1311867283.3852219582 0.0600684136 0.0644879987 0.1147603467 0.0062111720 0.0328010000 260877054 95654152 760807424 -0.0167604703 -0.1699122638 0.2777560651 3386 1311867283.4173080921 0.0595123768 0.0644865292 0.1147603467 0.0062103019 0.0331560000 260878670 95654152 760807424 -0.0153397759 -0.1700167209 0.2781783938 3387 1311867283.4492650032 0.0599294379 0.0644851837 0.1147603467 0.0062097750 0.0329580000 260882342 95654152 760807424 -0.0160459783 -0.1694785058 0.2789197564 3388 1311867283.4853370190 0.0605936348 0.0644840351 0.1147603467 0.0062091938 0.0362910000 260884126 95654152 760807424 -0.0149355112 -0.1707596332 0.2804178298 3389 1311867283.5172159672 0.0593863390 0.0644825309 0.1147603467 0.0062083573 0.0362270000 260887798 95654152 760807424 -0.0145683559 -0.1700631380 0.2798906565 3390 1311867283.5495610237 0.0593921617 0.0644810293 0.1147603467 0.0062074600 0.0328050000 260891270 95654152 760807424 -0.0143762296 -0.1701256484 0.2804810405 3391 1311867283.5853879452 0.0598739497 0.0644796707 0.1147603467 0.0062065965 0.0360190000 260893198 95654152 760807424 -0.0152676143 -0.1697631776 0.2812861502 3392 1311867283.6173179150 0.0593089610 0.0644781463 0.1147603467 0.0062057764 0.0329040000 260896670 95654152 760807424 -0.0154034588 -0.1693372875 0.2813146114 3393 1311867283.6493821144 0.0594382323 0.0644766609 0.1147603467 0.0062050138 0.0329890000 260898598 95654152 760807424 -0.0149853835 -0.1692113727 0.2822256088 3394 1311867283.6852879524 0.0589081682 0.0644750203 0.1147603467 0.0062046135 0.0365480000 260902182 95654152 760807424 -0.0143507468 -0.1692855507 0.2826859653 3395 1311867283.7179150581 0.0586190894 0.0644732954 0.1147603467 0.0062038427 0.0329160000 260905798 95654152 760807424 -0.0149355959 -0.1678212285 0.2829344273 3396 1311867283.7492079735 0.0590677150 0.0644717036 0.1147603467 0.0062029997 0.0356720000 260907470 95654152 760807424 -0.0148026319 -0.1683525741 0.2839293778 3397 1311867283.7853169441 0.0596215688 0.0644702759 0.1147603467 0.0062021246 0.0330600000 260911254 95654152 760807424 -0.0151993223 -0.1678344607 0.2849267125 3398 1311867283.8174130917 0.0594808869 0.0644688075 0.1147603467 0.0062014232 0.0330650000 260914670 95654152 760807424 -0.0155245950 -0.1673364639 0.2852810919 3399 1311867283.8494520187 0.0592735782 0.0644672791 0.1147603467 0.0062005565 0.0328870000 260916598 95654152 760807424 -0.0160759967 -0.1667354405 0.2854990661 3400 1311867283.8853459358 0.0598672405 0.0644659261 0.1147603467 0.0061996750 0.0330310000 260920126 95654152 760807424 -0.0168102141 -0.1666294485 0.2864466310 3401 1311867283.9175400734 0.0602673218 0.0644646916 0.1147603467 0.0061989400 0.0417620000 260924174 95654152 760807424 -0.0172727238 -0.1671660990 0.2872245014 3402 1311867283.9498898983 0.0598063022 0.0644633223 0.1147603467 0.0061981853 0.0373330000 260927646 95654152 760807424 -0.0178519245 -0.1668178439 0.2870588303 3403 1311867283.9856629372 0.0611738451 0.0644623557 0.1147603467 0.0061973001 0.0374390000 260931486 95654152 760807424 -0.0201585386 -0.1681570113 0.2882939279 3404 1311867284.0172998905 0.0609071106 0.0644613112 0.1147603467 0.0061964337 0.0418050000 260933166 95654152 760807424 -0.0195944384 -0.1672181636 0.2885671556 3405 1311867284.0497789383 0.0592048615 0.0644597675 0.1147603467 0.0061956401 0.0328820000 260936894 95654152 760807424 -0.0192499720 -0.1654212326 0.2874254584 3406 1311867284.0853729248 0.0597145967 0.0644583743 0.1147603467 0.0061953112 0.0364020000 260938622 95654152 760807424 -0.0191114396 -0.1680077463 0.2885216475 3407 1311867284.1175038815 0.0592738725 0.0644568526 0.1147603467 0.0061946321 0.0330780000 260942294 95654152 760807424 -0.0194582641 -0.1677430570 0.2886028290 3408 1311867284.1494109631 0.0580375642 0.0644549690 0.1147603467 0.0061937490 0.0329750000 260945766 95654152 760807424 -0.0189508963 -0.1665020734 0.2883370221 3409 1311867284.1874890327 0.0588915534 0.0644533370 0.1147603467 0.0061929853 0.0329350000 260947806 95654152 760807424 -0.0213853084 -0.1664199382 0.2892135084 3410 1311867284.2173368931 0.0594289824 0.0644518636 0.1147603467 0.0061923191 0.0415860000 260951734 95654152 760807424 -0.0208574086 -0.1665407717 0.2903392315 3411 1311867284.2494308949 0.0587519892 0.0644501926 0.1147603467 0.0061914196 0.0335950000 260953606 95654152 760807424 -0.0202629827 -0.1656644791 0.2900736332 3412 1311867284.2853159904 0.0592474192 0.0644486677 0.1147603467 0.0061905486 0.0332310000 260957134 95654152 760807424 -0.0208013970 -0.1658619642 0.2905978858 3413 1311867284.3178350925 0.0594290048 0.0644471970 0.1147603467 0.0061897570 0.0365060000 260960862 95654152 760807424 -0.0223090630 -0.1642140895 0.2905810475 3414 1311867284.3494238853 0.0581614189 0.0644453558 0.1147603467 0.0061888723 0.0332020000 260962534 95654152 760807424 -0.0213096030 -0.1621317416 0.2899030149 3415 1311867284.3854329586 0.0590423942 0.0644437737 0.1147603467 0.0061882605 0.0332760000 260966318 95654152 760807424 -0.0201596431 -0.1627070904 0.2914316952 3416 1311867284.4175798893 0.0590587109 0.0644421972 0.1147603467 0.0061873704 0.0330950000 260969790 95654152 760807424 -0.0197169762 -0.1622425020 0.2918112874 3417 1311867284.4495139122 0.0592393577 0.0644406746 0.1147603467 0.0061865174 0.0331900000 260971662 95654152 760807424 -0.0203817282 -0.1619485766 0.2920397818 3418 1311867284.4854190350 0.0597278476 0.0644392958 0.1147603467 0.0061856187 0.0372550000 260975190 95654152 760807424 -0.0202509668 -0.1618099660 0.2928617299 3419 1311867284.5177299976 0.0595724285 0.0644378723 0.1147603467 0.0061847919 0.0363120000 260977118 95654152 760807424 -0.0200540405 -0.1616110355 0.2930611074 3420 1311867284.5494539738 0.0593162216 0.0644363747 0.1147603467 0.0061840913 0.0331230000 260980590 95654152 760807424 -0.0191147793 -0.1602313370 0.2932960391 3421 1311867284.5854179859 0.0594481491 0.0644349166 0.1147603467 0.0061833495 0.0364610000 260984318 95654152 760807424 -0.0171028674 -0.1609500945 0.2940951288 3422 1311867284.6174941063 0.0602375790 0.0644336901 0.1147603467 0.0061825657 0.0353600000 260985990 95654152 760807424 -0.0186992288 -0.1618528515 0.2946870029 3423 1311867284.6495230198 0.0591075420 0.0644321341 0.1147603467 0.0061819013 0.0328840000 260989718 95654152 760807424 -0.0166093614 -0.1597879082 0.2944636643 3424 1311867284.6853780746 0.0599009953 0.0644308107 0.1147603467 0.0061813115 0.0329040000 260991446 95654152 760807424 -0.0161091071 -0.1612399966 0.2956382632 3425 1311867284.7174859047 0.0607615262 0.0644297394 0.1147603467 0.0061804476 0.0331490000 260995118 95654152 760807424 -0.0163940564 -0.1622751355 0.2965929210 3426 1311867284.7498660088 0.0586890094 0.0644280638 0.1147603467 0.0061804020 0.0328990000 260998646 95654152 760807424 -0.0159477610 -0.1588297784 0.2951598763 3427 1311867284.7854089737 0.0598285645 0.0644267216 0.1147603467 0.0061796121 0.0330690000 261000574 95654152 760807424 -0.0159324575 -0.1601115167 0.2966765165 3428 1311867284.8186919689 0.0603162274 0.0644255225 0.1147603467 0.0061787912 0.0329660000 261004102 95654152 760807424 -0.0160133783 -0.1602050811 0.2972868085 3429 1311867284.8492770195 0.0588299483 0.0644238907 0.1147603467 0.0061784366 0.0330140000 261005918 95654152 760807424 -0.0153691350 -0.1574296802 0.2962192595 3430 1311867284.8853850365 0.0603536293 0.0644227040 0.1147603467 0.0061776755 0.0331950000 261009446 95654152 760807424 -0.0152311102 -0.1595480591 0.2978418767 3431 1311867284.9174609184 0.0601577237 0.0644214610 0.1147603467 0.0061770743 0.0427340000 261014518 95654152 760807424 -0.0136718135 -0.1596407294 0.2981172204 3432 1311867284.9492468834 0.0597587191 0.0644201023 0.1147603467 0.0061764668 0.0332010000 261016190 95654152 760807424 -0.0143515365 -0.1588179618 0.2974802554 3433 1311867284.9852581024 0.0603648946 0.0644189211 0.1147603467 0.0061756672 0.0332560000 261020030 95654152 760807424 -0.0148786455 -0.1589674205 0.2977143526 3434 1311867285.0175390244 0.0609129965 0.0644179002 0.1147603467 0.0061749449 0.0331510000 261023446 95654152 760807424 -0.0154548148 -0.1597298384 0.2978767157 3435 1311867285.0493679047 0.0597517416 0.0644165417 0.1147603467 0.0061742214 0.0331120000 261025318 95654152 760807424 -0.0151733989 -0.1591521651 0.2964915335 3436 1311867285.0853259563 0.0603566132 0.0644153602 0.1147603467 0.0061733821 0.0418460000 261029222 95654152 760807424 -0.0155317727 -0.1603975147 0.2963810563 3437 1311867285.1177120209 0.0612696595 0.0644144449 0.1147603467 0.0061725939 0.0332320000 261031094 95654152 760807424 -0.0164183024 -0.1618950665 0.2960880101 3438 1311867285.1502749920 0.0605927221 0.0644133333 0.1147603467 0.0061717744 0.0362180000 261034622 95654152 760807424 -0.0170951039 -0.1623297781 0.2945572138 3439 1311867285.1855800152 0.0606951825 0.0644122521 0.1147603467 0.0061709725 0.0331790000 261038294 95654152 760807424 -0.0167357195 -0.1624187976 0.2938734591 3440 1311867285.2187609673 0.0611701645 0.0644113097 0.1147603467 0.0061700854 0.0415800000 261040206 95654152 760807424 -0.0171690378 -0.1632605046 0.2934677005 3441 1311867285.2493660450 0.0604523569 0.0644101591 0.1147603467 0.0061692106 0.0419470000 261044014 95654152 760807424 -0.0166242030 -0.1641244292 0.2921347916 3442 1311867285.2853620052 0.0602620095 0.0644089540 0.1147603467 0.0061683244 0.0365540000 261045798 95654152 760807424 -0.0176623240 -0.1647115946 0.2908880711 3443 1311867285.3175029755 0.0608561970 0.0644079221 0.1147603467 0.0061674619 0.0569290000 261049470 95654152 760807424 -0.0175247155 -0.1657006443 0.2909517884 3444 1311867285.3493449688 0.0601401590 0.0644066829 0.1147603467 0.0061667104 0.0343240000 261052942 95654152 760807424 -0.0176528692 -0.1644319296 0.2899852991 3445 1311867285.3855409622 0.0588572808 0.0644050721 0.1147603467 0.0061658949 0.0343400000 261054982 95654152 760807424 -0.0171908960 -0.1634236425 0.2887495160 3446 1311867285.4175810814 0.0598746426 0.0644037574 0.1147603467 0.0061652242 0.0454640000 261058590 95654152 760807424 -0.0185711682 -0.1650756598 0.2894780636 3447 1311867285.4492840767 0.0596665479 0.0644023831 0.1147603467 0.0061643896 0.0343890000 261060462 95654152 760807424 -0.0183042902 -0.1650982648 0.2896271646 3448 1311867285.4853799343 0.0591760203 0.0644008673 0.1147603467 0.0061635230 0.0343230000 261063990 95654152 760807424 -0.0180735532 -0.1644813567 0.2896986902 3449 1311867285.5176479816 0.0593344420 0.0643993983 0.1147603467 0.0061627951 0.0343980000 261067718 95654152 760807424 -0.0181437302 -0.1638614237 0.2904837132 3450 1311867285.5494589806 0.0588894710 0.0643978013 0.1147603467 0.0061620172 0.0342930000 261069390 95654152 760807424 -0.0180345587 -0.1636385322 0.2907562256 3451 1311867285.5855739117 0.0584624484 0.0643960814 0.1147603467 0.0061611889 0.0445630000 261073366 95654152 760807424 -0.0178689808 -0.1628956199 0.2910763919 3452 1311867285.6175510883 0.0600587465 0.0643948249 0.1147603467 0.0061604128 0.0450610000 261076902 95654152 760807424 -0.0202354025 -0.1644189358 0.2926510572 3453 1311867285.6494030952 0.0591469929 0.0643933051 0.1147603467 0.0061596434 0.0343140000 261078774 95654152 760807424 -0.0200675633 -0.1622328162 0.2926177084 3454 1311867285.6856529713 0.0585564114 0.0643916152 0.1147603467 0.0061589047 0.0343860000 261082358 95654152 760807424 -0.0193652306 -0.1617806107 0.2928456962 3455 1311867285.7177190781 0.0603169613 0.0643904359 0.1147603467 0.0061581968 0.0343760000 261084230 95654152 760807424 -0.0209204853 -0.1638877243 0.2944501936 3456 1311867285.7497379780 0.0597536713 0.0643890942 0.1147603467 0.0061574253 0.0343620000 261087702 95654152 760807424 -0.0210649315 -0.1626952291 0.2942048311 3457 1311867285.7854781151 0.0595748797 0.0643877016 0.1147603467 0.0061565399 0.0343020000 261091542 95654152 760807424 -0.0211902913 -0.1626078933 0.2942078412 3458 1311867285.8179709911 0.0604619607 0.0643865663 0.1147603467 0.0061556768 0.0336600000 261093158 95654152 760807424 -0.0224891379 -0.1642173976 0.2948362827 3459 1311867285.8496279716 0.0599245802 0.0643852764 0.1147603467 0.0061548800 0.0327500000 261096830 95654152 760807424 -0.0222539473 -0.1630119234 0.2945564091 3460 1311867285.8852860928 0.0600007996 0.0643840092 0.1147603467 0.0061540313 0.0327900000 261098670 95654152 760807424 -0.0226890221 -0.1641727090 0.2945379317 3461 1311867285.9187369347 0.0608567484 0.0643829900 0.1147603467 0.0061532391 0.0327320000 261102342 95654152 760807424 -0.0235488378 -0.1658834815 0.2952629626 3462 1311867285.9496929646 0.0590364113 0.0643814457 0.1147603467 0.0061526206 0.0330560000 261105814 95654152 760807424 -0.0222126395 -0.1635744572 0.2940822244 3463 1311867285.9858360291 0.0590785742 0.0643799144 0.1147603467 0.0061517873 0.0331540000 261107742 95654152 760807424 -0.0234761331 -0.1639975905 0.2941137254 3464 1311867286.0184700489 0.0600241646 0.0643786570 0.1147603467 0.0061510529 0.0350890000 261111214 95654152 760807424 -0.0246771462 -0.1663459390 0.2950184941 3465 1311867286.0494220257 0.0590313636 0.0643771137 0.1147603467 0.0061504761 0.0333880000 261113086 95654152 760807424 -0.0242558848 -0.1642109901 0.2945208251 3466 1311867286.0854020119 0.0594464913 0.0643756912 0.1147603467 0.0061503804 0.0331990000 261116614 95654152 760807424 -0.0246741921 -0.1645796150 0.2949595451 3467 1311867286.1240980625 0.0600363836 0.0643744396 0.1147603467 0.0061499521 0.0331320000 261120398 95654152 760807424 -0.0257893987 -0.1649710387 0.2958694100 3468 1311867286.1506319046 0.0599202923 0.0643731552 0.1147603467 0.0061493833 0.0338650000 261121902 95654152 760807424 -0.0256250221 -0.1646291018 0.2958507240 3469 1311867286.1857590675 0.0599488020 0.0643718798 0.1147603467 0.0061485522 0.0333380000 261125630 95654152 760807424 -0.0248049442 -0.1643589437 0.2965998352 3470 1311867286.2179830074 0.0599309877 0.0643706000 0.1147603467 0.0061478687 0.0331960000 261129102 95654152 760807424 -0.0250490960 -0.1641868949 0.2971220315 3471 1311867286.2525210381 0.0595884584 0.0643692223 0.1147603467 0.0061469839 0.0417750000 261130974 95654152 760807424 -0.0251797959 -0.1636308134 0.2971465588 3472 1311867286.2861630917 0.0592984594 0.0643677618 0.1147603467 0.0061461311 0.0333670000 261134446 95654152 760807424 -0.0246579573 -0.1630424261 0.2972086370 3473 1311867286.3203520775 0.0599403121 0.0643664870 0.1147603467 0.0061453666 0.0332160000 261136318 95654152 760807424 -0.0257504005 -0.1633942425 0.2975625098 3474 1311867286.3524320126 0.0599812679 0.0643652247 0.1147603467 0.0061447837 0.0332710000 261139790 95654152 760807424 -0.0252258293 -0.1631699950 0.2980521023 3475 1311867286.3855628967 0.0590404794 0.0643636924 0.1147603467 0.0061440787 0.0333620000 261143462 95654152 760807424 -0.0254969485 -0.1610410213 0.2972062230 3476 1311867286.4177770615 0.0595583469 0.0643623099 0.1147603467 0.0061432193 0.0332330000 261145190 95654152 760807424 -0.0280304160 -0.1620602012 0.2969012260 3477 1311867286.4494199753 0.0599113032 0.0643610298 0.1147603467 0.0061427722 0.0332280000 261148862 95654152 760807424 -0.0261525437 -0.1630347818 0.2977123857 3478 1311867286.4855709076 0.0588542558 0.0643594465 0.1147603467 0.0061423531 0.0365870000 261150590 95654152 760807424 -0.0257373285 -0.1621826589 0.2969168723 3479 1311867286.5190370083 0.0587694384 0.0643578397 0.1147603467 0.0061415060 0.0333780000 261154374 95654152 760807424 -0.0255479738 -0.1624231637 0.2967794836 3480 1311867286.5512158871 0.0595566891 0.0643564601 0.1147603467 0.0061406235 0.0331360000 261157790 95654152 760807424 -0.0257048216 -0.1632186472 0.2974914908 3481 1311867286.5855200291 0.0582066774 0.0643546934 0.1147603467 0.0061398849 0.0418290000 261161814 95654152 760807424 -0.0249912459 -0.1622316837 0.2963893414 3482 1311867286.6190819740 0.0580887906 0.0643528939 0.1147603467 0.0061390285 0.0422430000 261165350 95654152 760807424 -0.0249948595 -0.1618867815 0.2965841889 3483 1311867286.6500060558 0.0595881566 0.0643515259 0.1147603467 0.0061383233 0.0417740000 261167230 95654152 760807424 -0.0247947648 -0.1642235965 0.2978358865 3484 1311867286.6856429577 0.0593903251 0.0643501019 0.1147603467 0.0061374751 0.0333270000 261170758 95654152 760807424 -0.0244466867 -0.1644858718 0.2976667285 3485 1311867286.7176160812 0.0590015166 0.0643485671 0.1147603467 0.0061366851 0.0479340000 261174558 95654152 760807424 -0.0231687408 -0.1646888256 0.2975354791 3486 1311867286.7495489120 0.0588425919 0.0643469877 0.1147603467 0.0061366207 0.0332570000 261176286 95654152 760807424 -0.0237129573 -0.1645600647 0.2974072993 3487 1311867286.7856459618 0.0584526695 0.0643452973 0.1147603467 0.0061362628 0.0340510000 261180014 95654152 760807424 -0.0230304450 -0.1643628329 0.2973566651 3488 1311867286.8176259995 0.0575789586 0.0643433574 0.1147603467 0.0061355493 0.0333920000 261183542 95654152 760807424 -0.0222244542 -0.1627940834 0.2968107760 3489 1311867286.8535819054 0.0579881929 0.0643415359 0.1147603467 0.0061348589 0.0365000000 261185526 95654152 760807424 -0.0227617659 -0.1628305465 0.2971525192 3490 1311867286.8868150711 0.0590967201 0.0643400331 0.1147603467 0.0061342906 0.0333470000 261188998 95654152 760807424 -0.0231651831 -0.1645540297 0.2982268333 3491 1311867286.9174380302 0.0573003292 0.0643380166 0.1147603467 0.0061334609 0.0332360000 261190814 95654152 760807424 -0.0200468693 -0.1626093984 0.2975205183 3492 1311867286.9543609619 0.0569955334 0.0643359139 0.1147603467 0.0061326429 0.0361940000 261194454 95654152 760807424 -0.0199525915 -0.1620605439 0.2972854972 3493 1311867286.9854118824 0.0586273409 0.0643342797 0.1147603467 0.0061320015 0.0428180000 261198454 95654152 760807424 -0.0208449308 -0.1641776711 0.2985832393 3494 1311867287.0174310207 0.0586542375 0.0643326540 0.1147603467 0.0061311590 0.0331550000 261200126 95654152 760807424 -0.0209440701 -0.1632303894 0.2984659076 3495 1311867287.0547020435 0.0579173565 0.0643308184 0.1147603467 0.0061329480 0.0331890000 261203966 95654152 760807424 -0.0206307936 -0.1608777344 0.2972085178 3496 1311867287.0856859684 0.0579801537 0.0643290019 0.1147603467 0.0061329613 0.0442300000 261205958 95654152 760807424 -0.0201176498 -0.1611372232 0.2976114750 3497 1311867287.1178219318 0.0586362518 0.0643273740 0.1147603467 0.0061324306 0.0574950000 261209638 95654160 760807424 -0.0198879652 -0.1621238887 0.2980506420 3498 1311867287.1537048817 0.0578305013 0.0643255167 0.1147603467 0.0061319359 0.0421450000 261213158 95654160 760807424 -0.0182408709 -0.1599188298 0.2976002991 3499 1311867287.1874449253 0.0585208647 0.0643238577 0.1147603467 0.0061312522 0.0472360000 261215278 95654160 760807424 -0.0188293625 -0.1611563712 0.2979947627 3500 1311867287.2175579071 0.0591622926 0.0643223830 0.1147603467 0.0061307933 0.0477370000 261218758 95654160 760807424 -0.0189782456 -0.1624276042 0.2984049618 3501 1311867287.2536680698 0.0586394779 0.0643207598 0.1147603467 0.0061300867 0.0421390000 261220806 95654160 760807424 -0.0187848713 -0.1616065502 0.2977646589 3502 1311867287.2870221138 0.0586957745 0.0643191536 0.1147603467 0.0061292458 0.0424550000 261224398 95654160 760807424 -0.0188804734 -0.1612181515 0.2976933122 3503 1311867287.3175630569 0.0590282828 0.0643176432 0.1147603467 0.0061285711 0.0422630000 261228078 95654160 760807424 -0.0190354902 -0.1615941972 0.2978454530 3504 1311867287.3540940285 0.0584250726 0.0643159615 0.1147603467 0.0061277488 0.0485890000 261229854 95654160 760807424 -0.0186871700 -0.1607760191 0.2970380485 3505 1311867287.3855540752 0.0585115813 0.0643143055 0.1147603467 0.0061268923 0.0420940000 261233590 95654160 760807424 -0.0186658204 -0.1615769118 0.2968989313 3506 1311867287.4175760746 0.0598520339 0.0643130327 0.1147603467 0.0061260618 0.0424180000 261237070 95654160 760807424 -0.0189202726 -0.1636759192 0.2977910340 3507 1311867287.4535288811 0.0597179607 0.0643117225 0.1147603467 0.0061252701 0.0332150000 261239054 95654160 760807424 -0.0198521558 -0.1633936912 0.2970812917 3508 1311867287.4867310524 0.0580046177 0.0643099245 0.1147603467 0.0061271460 0.0333660000 261242526 95654160 760807424 -0.0189836714 -0.1618686914 0.2965943813 3509 1311867287.5174999237 0.0587173179 0.0643083308 0.1147603467 0.0061290409 0.0333680000 261244398 95654160 760807424 -0.0187117252 -0.1621120423 0.2965418994 3510 1311867287.5534870625 0.0580825843 0.0643065570 0.1147603467 0.0061283058 0.0418790000 261248238 95654160 760807424 -0.0182368550 -0.1608545631 0.2963062525 3511 1311867287.5869519711 0.0585227534 0.0643049097 0.1147603467 0.0061275237 0.0510130000 261252030 95654160 760807424 -0.0187632889 -0.1614988893 0.2966042757 3512 1311867287.6176569462 0.0595362745 0.0643035519 0.1147603467 0.0061270667 0.0341130000 261253646 95654160 760807424 -0.0190073512 -0.1636564881 0.2973899841 3513 1311867287.6539158821 0.0590234213 0.0643020489 0.1147603467 0.0061262121 0.0330480000 261257486 95654160 760807424 -0.0182233844 -0.1624564230 0.2969233096 3514 1311867287.6875660419 0.0580297001 0.0643002639 0.1147603467 0.0061259872 0.0332850000 261259158 95654160 760807424 -0.0182762221 -0.1607042849 0.2962787151 3515 1311867287.7176280022 0.0582924895 0.0642985547 0.1147603467 0.0061254931 0.0420220000 261263030 95654160 760807424 -0.0180587750 -0.1611702442 0.2967292964 3516 1311867287.7553908825 0.0589990057 0.0642970475 0.1147603467 0.0061249592 0.0421310000 261266734 95654160 760807424 -0.0203381926 -0.1620542258 0.2966187000 3517 1311867287.7872428894 0.0578553416 0.0642952159 0.1147603467 0.0061242384 0.0476920000 261268614 95654160 760807424 -0.0192563906 -0.1596101522 0.2960203290 3518 1311867287.8260099888 0.0576661490 0.0642933315 0.1147603467 0.0061235581 0.0421310000 261272446 95654160 760807424 -0.0182448458 -0.1597385556 0.2964362502 3519 1311867287.8536510468 0.0594280101 0.0642919489 0.1147603467 0.0061228647 0.0422610000 261274142 95654160 760807424 -0.0179559328 -0.1622697711 0.2981149852 3520 1311867287.8931109905 0.0579575077 0.0642901494 0.1147603467 0.0061224914 0.0478080000 261277790 95654160 760807424 -0.0164704099 -0.1593504995 0.2973529398 3521 1311867287.9175710678 0.0580485091 0.0642883767 0.1147603467 0.0061217201 0.0369780000 261281238 95654160 760807424 -0.0158602241 -0.1590309143 0.2975592017 3522 1311867287.9535610676 0.0602213256 0.0642872219 0.1147603467 0.0061245232 0.0334470000 261282966 95654160 760807424 -0.0160668679 -0.1623332351 0.2998853624 3523 1311867287.9868519306 0.0600557365 0.0642860208 0.1147603467 0.0061243243 0.0429510000 261286638 95654160 760807424 -0.0142378761 -0.1626561433 0.2992091477 3524 1311867288.0178821087 0.0586457849 0.0642844203 0.1147603467 0.0061254791 0.0481330000 261290366 95654160 760807424 -0.0131828608 -0.1598529816 0.2978809476 3525 1311867288.0536389351 0.0599420965 0.0642831885 0.1147603467 0.0061263300 0.0428980000 261292542 95654160 760807424 -0.0135249933 -0.1632960886 0.2990646958 3526 1311867288.0854179859 0.0602269880 0.0642820381 0.1147603467 0.0061255369 0.0334710000 261295958 95654160 760807424 -0.0139176417 -0.1636408865 0.2991167903 3527 1311867288.1175940037 0.0590171888 0.0642805454 0.1147603467 0.0061247450 0.0333250000 261297886 95654160 760807424 -0.0124928989 -0.1628272682 0.2982195914 3528 1311867288.1540820599 0.0600095317 0.0642793348 0.1147603467 0.0061248692 0.0370470000 261301470 95654160 760807424 -0.0126976110 -0.1655283272 0.2989192903 3529 1311867288.1854550838 0.0607537329 0.0642783357 0.1147603467 0.0061241864 0.0368910000 261305142 95654160 760807424 -0.0125810774 -0.1666500419 0.2991525829 3530 1311867288.2175340652 0.0581345297 0.0642765953 0.1147603467 0.0061239672 0.0335040000 261306702 95654160 760807424 -0.0118992617 -0.1625568569 0.2966847718 3531 1311867288.2535810471 0.0590401106 0.0642751123 0.1147603467 0.0061231953 0.0418910000 261310926 95654160 760807424 -0.0126752229 -0.1641901731 0.2970379293 3532 1311867288.2854719162 0.0607832819 0.0642741236 0.1147603467 0.0061225660 0.0333440000 261312542 95654160 760807424 -0.0138142360 -0.1670858115 0.2979883850 3533 1311867288.3175830841 0.0589789897 0.0642726249 0.1147603467 0.0061220654 0.0334060000 261316270 95654160 760807424 -0.0143880202 -0.1647049934 0.2962778807 3534 1311867288.3535211086 0.0594464540 0.0642712592 0.1147603467 0.0061213528 0.0333650000 261319854 95654160 760807424 -0.0149819683 -0.1658950895 0.2967197597 3535 1311867288.3858890533 0.0597654283 0.0642699846 0.1147603467 0.0061206844 0.0366380000 261321726 95654160 760807424 -0.0159913916 -0.1665384769 0.2969016433 3536 1311867288.4177610874 0.0587954149 0.0642684364 0.1147603467 0.0061200611 0.0433120000 261325198 95654160 760807424 -0.0152954031 -0.1648362279 0.2965197265 3537 1311867288.4560298920 0.0582960695 0.0642667478 0.1147603467 0.0061192175 0.0334130000 261327238 95654160 760807424 -0.0155757191 -0.1642239243 0.2963545322 3538 1311867288.4854650497 0.0590991639 0.0642652872 0.1147603467 0.0061183659 0.0334320000 261330710 95654160 760807424 -0.0174988694 -0.1654377133 0.2969022095 3539 1311867288.5176889896 0.0589353330 0.0642637812 0.1147603467 0.0061175184 0.0337320000 261334326 95654160 760807424 -0.0175454430 -0.1649356037 0.2969151437 3540 1311867288.5544929504 0.0583455227 0.0642621093 0.1147603467 0.0061166727 0.0335690000 261336110 95654160 760807424 -0.0175472386 -0.1642625183 0.2965211570 3541 1311867288.5874340534 0.0589594468 0.0642606118 0.1147603467 0.0061158375 0.0333320000 261339782 95654160 760807424 -0.0202870984 -0.1646087617 0.2965229154 3542 1311867288.6175410748 0.0587713085 0.0642590621 0.1147603467 0.0061149911 0.0334970000 261343198 95654160 760807424 -0.0195848253 -0.1647341251 0.2964281738 3543 1311867288.6551198959 0.0587751083 0.0642575142 0.1147603467 0.0061141731 0.0472980000 261345878 95654160 760807424 -0.0198203512 -0.1644420028 0.2961704433 3544 1311867288.6874110699 0.0593664423 0.0642561341 0.1147603467 0.0061135138 0.0334960000 261349350 95654160 760807424 -0.0221017655 -0.1636519730 0.2960481644 3545 1311867288.7177178860 0.0596436262 0.0642548330 0.1147603467 0.0061127038 0.0334860000 261351166 95654160 760807424 -0.0219630506 -0.1637117118 0.2960623205 3546 1311867288.7560660839 0.0587900653 0.0642532919 0.1147603467 0.0061118709 0.0334780000 261354806 95654160 760807424 -0.0213700216 -0.1626580358 0.2951855659 3547 1311867288.7855091095 0.0595649034 0.0642519701 0.1147603467 0.0061110343 0.0333840000 261358422 95654160 760807424 -0.0216552913 -0.1643714905 0.2953877747 3548 1311867288.8192400932 0.0596053712 0.0642506605 0.1147603467 0.0061103597 0.0374240000 261360206 95654160 760807424 -0.0221002847 -0.1640519500 0.2951264977 3549 1311867288.8543450832 0.0586857907 0.0642490925 0.1147603467 0.0061097223 0.0335850000 261363934 95654160 760807424 -0.0218217801 -0.1620919704 0.2939773202 3550 1311867288.8855559826 0.0589120649 0.0642475891 0.1147603467 0.0061089160 0.0423720000 261365606 95654160 760807424 -0.0214691646 -0.1624808162 0.2941953540 3551 1311867288.9176120758 0.0589336418 0.0642460926 0.1147603467 0.0061082331 0.0331400000 261369222 95654160 760807424 -0.0215641614 -0.1630014628 0.2939360738 3552 1311867288.9599480629 0.0590130575 0.0642446193 0.1147603467 0.0061075286 0.0331830000 261373030 95654160 760807424 -0.0218828041 -0.1629053801 0.2938324511 3553 1311867288.9855918884 0.0594067425 0.0642432577 0.1147603467 0.0061067221 0.0333720000 261374734 95654160 760807424 -0.0222336072 -0.1629929394 0.2940407097 3554 1311867289.0176560879 0.0590404645 0.0642417938 0.1147603467 0.0061059864 0.0335290000 261378150 95654160 760807424 -0.0203656405 -0.1621868163 0.2941207290 3555 1311867289.0535120964 0.0589458719 0.0642403041 0.1147603467 0.0061056448 0.0334580000 261380190 95654160 760807424 -0.0203984883 -0.1629754454 0.2940373719 3556 1311867289.0855109692 0.0586357899 0.0642387280 0.1147603467 0.0061048811 0.0334950000 261383606 95654160 760807424 -0.0214132182 -0.1624932587 0.2935130894 3557 1311867289.1175429821 0.0588711537 0.0642372190 0.1147603467 0.0061040545 0.0372310000 261387278 95654160 760807424 -0.0211097728 -0.1626514345 0.2937219441 3558 1311867289.1545929909 0.0590922087 0.0642357729 0.1147603467 0.0061033038 0.0334870000 261389174 95654160 760807424 -0.0209628791 -0.1633035690 0.2938853204 3559 1311867289.1856400967 0.0588690005 0.0642342650 0.1147603467 0.0061024624 0.0335060000 261392734 95654160 760807424 -0.0204976182 -0.1626095474 0.2938877642 3560 1311867289.2185060978 0.0585854910 0.0642326783 0.1147603467 0.0061018751 0.0369190000 261396262 95654160 760807424 -0.0200420134 -0.1629149616 0.2938640118 3561 1311867289.2550480366 0.0591336228 0.0642312463 0.1147603467 0.0061015936 0.0335450000 261398302 95654160 760807424 -0.0204156041 -0.1639890522 0.2942787707 3562 1311867289.2853870392 0.0592844076 0.0642298576 0.1147603467 0.0061008810 0.0334670000 261401774 95654160 760807424 -0.0204758458 -0.1645123512 0.2943513691 3563 1311867289.3176290989 0.0581074655 0.0642281392 0.1147603467 0.0061002963 0.0336750000 261403590 95654160 760807424 -0.0196380783 -0.1624832898 0.2934053540 3564 1311867289.3539168835 0.0588035025 0.0642266172 0.1147603467 0.0060994677 0.0428450000 261407174 95654160 760807424 -0.0215058308 -0.1635445058 0.2936407924 3565 1311867289.3861899376 0.0593051650 0.0642252367 0.1147603467 0.0060986296 0.0333930000 261410902 95654160 760807424 -0.0220268108 -0.1641808152 0.2941678762 3566 1311867289.4177041054 0.0582039505 0.0642235482 0.1147603467 0.0060984711 0.0335180000 261412518 95654160 760807424 -0.0213624891 -0.1617024094 0.2933675647 3567 1311867289.4536058903 0.0582117438 0.0642218628 0.1147603467 0.0060976542 0.0335840000 261416302 95654160 760807424 -0.0213248339 -0.1623604596 0.2936927378 3568 1311867289.4859669209 0.0593082570 0.0642204856 0.1147603467 0.0060970408 0.0335360000 261418030 95654160 760807424 -0.0223162808 -0.1639643461 0.2947178781 3569 1311867289.5183238983 0.0585312173 0.0642188915 0.1147603467 0.0060962910 0.0335540000 261421646 95654160 760807424 -0.0224117003 -0.1621723920 0.2943493724 3570 1311867289.5548820496 0.0583021380 0.0642172342 0.1147603467 0.0060956437 0.0330840000 261425286 95654160 760807424 -0.0227974914 -0.1622752845 0.2945870459 3571 1311867289.5856130123 0.0597850010 0.0642159930 0.1147603467 0.0060952473 0.0415790000 261428822 95654160 760807424 -0.0234189276 -0.1643060893 0.2958994508 3572 1311867289.6176490784 0.0575580820 0.0642141291 0.1147603467 0.0060945794 0.0335230000 261432238 95654160 760807424 -0.0222476628 -0.1610535532 0.2945181727 3573 1311867289.6536390781 0.0575510561 0.0642122643 0.1147603467 0.0060937454 0.0336630000 261434222 95654160 760807424 -0.0240847245 -0.1609668434 0.2947908342 3574 1311867289.6856849194 0.0582913570 0.0642106076 0.1147603467 0.0060933098 0.0335810000 261437694 95654160 760807424 -0.0248951185 -0.1624608338 0.2962653041 3575 1311867289.7204349041 0.0573613495 0.0642086917 0.1147603467 0.0060925169 0.0420110000 261441862 95654160 760807424 -0.0237737838 -0.1606754959 0.2966332138 3576 1311867289.7564179897 0.0569331497 0.0642066572 0.1147603467 0.0060922071 0.0422640000 261443654 95654160 760807424 -0.0249197576 -0.1594598591 0.2966164649 3577 1311867289.7855679989 0.0589262731 0.0642051810 0.1147603467 0.0060917427 0.0427600000 261447462 95654160 760807424 -0.0252776407 -0.1613588780 0.2988904119 3578 1311867289.8240370750 0.0588547103 0.0642036856 0.1147603467 0.0060909590 0.0485340000 261451166 95654160 760807424 -0.0259574596 -0.1615852267 0.2991062701 3579 1311867289.8541870117 0.0581365377 0.0642019904 0.1147603467 0.0060901136 0.0332050000 261453038 95654160 760807424 -0.0261551626 -0.1609882116 0.2988184392 3580 1311867289.8855679035 0.0591688566 0.0642005845 0.1147603467 0.0060894886 0.0335300000 261456454 95654160 760807424 -0.0278683733 -0.1619412899 0.2997064888 3581 1311867289.9200530052 0.0600884259 0.0641994362 0.1147603467 0.0060910164 0.0423290000 261458446 95654160 760807424 -0.0279843807 -0.1622608304 0.3004333675 3582 1311867289.9536409378 0.0589793213 0.0641979788 0.1147603467 0.0060917091 0.0424170000 261462038 95654160 760807424 -0.0279569663 -0.1620826572 0.3004212379 3583 1311867289.9855279922 0.0597207882 0.0641967293 0.1147603467 0.0060908693 0.0426160000 261465718 95654160 760807424 -0.0284767039 -0.1630529165 0.3014751077 3584 1311867290.0232169628 0.0596462600 0.0641954596 0.1147603467 0.0060902199 0.0481160000 261467550 95654160 760807424 -0.0288733579 -0.1635587662 0.3015963435 3585 1311867290.0535910130 0.0590151139 0.0641940146 0.1147603467 0.0060896994 0.0336070000 261471166 95654160 760807424 -0.0299713928 -0.1630064249 0.3010503352 3586 1311867290.0854740143 0.0594894402 0.0641927027 0.1147603467 0.0060890460 0.0335740000 261472894 95654160 760807424 -0.0297754891 -0.1639596820 0.3020507693 3587 1311867290.1248800755 0.0592149384 0.0641913150 0.1147603467 0.0060886534 0.0337480000 261476678 95654160 760807424 -0.0294033773 -0.1640517563 0.3023325205 3588 1311867290.1536118984 0.0576492846 0.0641894916 0.1147603467 0.0060879751 0.0335910000 261480094 95654160 760807424 -0.0278852265 -0.1620013565 0.3016186953 3589 1311867290.1856379509 0.0584707111 0.0641878982 0.1147603467 0.0060872865 0.0369150000 261482022 95654160 760807424 -0.0290674549 -0.1635084152 0.3022320271 3590 1311867290.2225489616 0.0583322644 0.0641862671 0.1147603467 0.0060865702 0.0369430000 261485550 95654160 760807424 -0.0289599802 -0.1631551087 0.3025135994 3591 1311867290.2540318966 0.0575623624 0.0641844225 0.1147603467 0.0060868316 0.0374730000 261487422 95654160 760807424 -0.0279594772 -0.1606432796 0.3022901118 3592 1311867290.2892379761 0.0589922816 0.0641829771 0.1147603467 0.0060865567 0.0333880000 261491006 95654160 760807424 -0.0284382030 -0.1626557261 0.3039480448 3593 1311867290.3220748901 0.0594991818 0.0641816735 0.1147603467 0.0060861839 0.0372970000 261494678 95654160 760807424 -0.0285778847 -0.1629338264 0.3043043613 3594 1311867290.3587789536 0.0586702600 0.0641801400 0.1147603467 0.0060854867 0.0337840000 261496462 95654160 760807424 -0.0287098084 -0.1617278457 0.3034466803 3595 1311867290.3864240646 0.0588047281 0.0641786447 0.1147603467 0.0060846475 0.0347320000 261499966 95654160 760807424 -0.0288271252 -0.1621087492 0.3035791218 3596 1311867290.4216320515 0.0591880530 0.0641772569 0.1147603467 0.0060838935 0.0337280000 261503606 95654160 760807424 -0.0295903794 -0.1627800465 0.3039218187 3597 1311867290.4578390121 0.0583904125 0.0641756481 0.1147603467 0.0060836216 0.0364290000 261505366 95654160 760807424 -0.0294355266 -0.1625962406 0.3034307063 3598 1311867290.4859950542 0.0593013503 0.0641742934 0.1147603467 0.0060828106 0.0425890000 261509750 95654160 760807424 -0.0302574858 -0.1639166027 0.3038344979 3599 1311867290.5223400593 0.0592091084 0.0641729138 0.1147603467 0.0060822275 0.0428290000 261511670 95654160 760807424 -0.0298710782 -0.1641158760 0.3037396371 3600 1311867290.5537059307 0.0589776337 0.0641714707 0.1147603467 0.0060815748 0.0430900000 261515334 95654160 760807424 -0.0311981104 -0.1636330485 0.3029471338 3601 1311867290.5855538845 0.0587521531 0.0641699657 0.1147603467 0.0060821297 0.0335950000 261519062 95654160 760807424 -0.0314234123 -0.1634529680 0.3027565777 3602 1311867290.6221020222 0.0585639030 0.0641684093 0.1147603467 0.0060815153 0.0336370000 261520790 95654160 760807424 -0.0317782760 -0.1630697548 0.3021616638 3603 1311867290.6536018848 0.0586277805 0.0641668716 0.1147603467 0.0060818159 0.0336270000 261524462 95654160 760807424 -0.0313406959 -0.1623783410 0.3019615412 3604 1311867290.6857531071 0.0594442338 0.0641655612 0.1147603467 0.0060810008 0.0345780000 261526078 95654160 760807424 -0.0324385166 -0.1630719900 0.3020581901 3605 1311867290.7256150246 0.0599632412 0.0641643955 0.1147603467 0.0060802753 0.0534910000 261530222 95654160 760807424 -0.0314669386 -0.1633522660 0.3023317754 3606 1311867290.7539739609 0.0590266325 0.0641629707 0.1147603467 0.0060797749 0.0335550000 261533582 95654160 760807424 -0.0317447335 -0.1612272263 0.3011237383 3607 1311867290.7866060734 0.0593804531 0.0641616448 0.1147603467 0.0060790144 0.0486510000 261535526 95654160 760807424 -0.0313186795 -0.1622729748 0.3011089265 3608 1311867290.8231720924 0.0602853745 0.0641605704 0.1147603467 0.0060785542 0.0337230000 261539166 95654160 760807424 -0.0315656625 -0.1631754190 0.3013133109 3609 1311867290.8556039333 0.0593059137 0.0641592253 0.1147603467 0.0060778254 0.0432830000 261541038 95654160 760807424 -0.0305790678 -0.1628071815 0.3001714945 3610 1311867290.8876988888 0.0603133552 0.0641581599 0.1147603467 0.0060793030 0.0334860000 261544510 95654160 760807424 -0.0308887493 -0.1630559713 0.2999649942 3611 1311867290.9227120876 0.0606881306 0.0641571990 0.1147603467 0.0060785421 0.0400370000 261548238 95654160 760807424 -0.0302659459 -0.1639123559 0.2999746501 3612 1311867290.9537110329 0.0599242114 0.0641560271 0.1147603467 0.0060803732 0.0423300000 261550102 95654160 760807424 -0.0297857020 -0.1646395922 0.2995621860 3613 1311867290.9906909466 0.0588908158 0.0641545698 0.1147603467 0.0060797302 0.0426430000 261554134 95654160 760807424 -0.0282072593 -0.1628469080 0.2986066639 3614 1311867291.0239291191 0.0595822893 0.0641533046 0.1147603467 0.0060794402 0.0427700000 261557726 95654160 760807424 -0.0281188171 -0.1655792743 0.2987877429 3615 1311867291.0558199883 0.0588889048 0.0641518483 0.1147603467 0.0060787038 0.0422770000 261559662 95654160 760807424 -0.0270249154 -0.1637338698 0.2980689108 3616 1311867291.0934820175 0.0586305372 0.0641503214 0.1147603467 0.0060779693 0.0427530000 261563310 95654160 760807424 -0.0264403336 -0.1636971831 0.2974915802 3617 1311867291.1203110218 0.0593480915 0.0641489937 0.1147603467 0.0060781730 0.0431720000 261565134 95654160 760807424 -0.0248414110 -0.1659296006 0.2981804013 3618 1311867291.1541891098 0.0593146086 0.0641476575 0.1147603467 0.0060806466 0.0429340000 261568614 95654160 760807424 -0.0248047374 -0.1639138162 0.2971264422 3619 1311867291.1891989708 0.0585201718 0.0641461026 0.1147603467 0.0060821896 0.0442150000 261572462 95654160 760807424 -0.0245305672 -0.1642527282 0.2964821756 3620 1311867291.2211010456 0.0590179004 0.0641446859 0.1147603467 0.0060815253 0.0431600000 261574198 95654160 760807424 -0.0243668072 -0.1647869796 0.2965025902 3621 1311867291.2543909550 0.0592838302 0.0641433435 0.1147603467 0.0060808317 0.0421960000 261577990 95654160 760807424 -0.0245097652 -0.1647243947 0.2963778973 3622 1311867291.2877960205 0.0589910559 0.0641419210 0.1147603467 0.0060800797 0.0485850000 261579598 95654160 760807424 -0.0236816015 -0.1646389365 0.2958175838 3623 1311867291.3210899830 0.0592137016 0.0641405608 0.1147603467 0.0060794296 0.0463360000 261583462 95654160 760807424 -0.0215272009 -0.1654914171 0.2958480716 3624 1311867291.3547959328 0.0588952266 0.0641391134 0.1147603467 0.0060787812 0.0462510000 261586982 95654160 760807424 -0.0225955993 -0.1652009040 0.2947303355 3625 1311867291.3878760338 0.0588789172 0.0641376623 0.1147603467 0.0060782948 0.0462310000 261588918 95654160 760807424 -0.0223753508 -0.1640469283 0.2944741547 3626 1311867291.4223349094 0.0589848794 0.0641362412 0.1147603467 0.0060780446 0.0468800000 261592510 95654160 760807424 -0.0209599920 -0.1652645767 0.2945626676 3627 1311867291.4536559582 0.0586845018 0.0641347381 0.1147603467 0.0060772482 0.0444050000 261594446 95654160 760807424 -0.0205650032 -0.1651670635 0.2939221561 3628 1311867291.4883999825 0.0584652238 0.0641331754 0.1147603467 0.0060765914 0.0430570000 261598038 95654160 760807424 -0.0217423439 -0.1643946022 0.2932375669 3629 1311867291.5201730728 0.0590134971 0.0641317646 0.1147603467 0.0060760059 0.0442170000 261601830 95654160 760807424 -0.0218239520 -0.1656065881 0.2936349213 3630 1311867291.5536448956 0.0588792562 0.0641303177 0.1147603467 0.0060752210 0.0430490000 261603566 95654160 760807424 -0.0220776778 -0.1653501242 0.2932915390 3631 1311867291.5895080566 0.0587383509 0.0641288327 0.1147603467 0.0060746779 0.0538910000 261607414 95654160 760807424 -0.0213537645 -0.1653122306 0.2927833200 3632 1311867291.6206870079 0.0587611347 0.0641273548 0.1147603467 0.0060743243 0.0428320000 261611022 95654160 760807424 -0.0217132382 -0.1655783206 0.2928896546 3633 1311867291.6539781094 0.0581221618 0.0641257018 0.1147603467 0.0060736853 0.0427660000 261613014 95654160 760807424 -0.0207034796 -0.1655981392 0.2924730182 3634 1311867291.6896810532 0.0583969466 0.0641241254 0.1147603467 0.0060729574 0.0428890000 261616662 95654160 760807424 -0.0206078179 -0.1654204279 0.2923409939 3635 1311867291.7202739716 0.0582374483 0.0641225060 0.1147603467 0.0060721495 0.0429990000 261618542 95654160 760807424 -0.0213203114 -0.1658996791 0.2918092906 3636 1311867291.7537178993 0.0582930893 0.0641209027 0.1147603467 0.0060715300 0.0425840000 261622134 95654160 760807424 -0.0219439026 -0.1659953743 0.2916223705 3637 1311867291.7890019417 0.0582377017 0.0641192851 0.1147603467 0.0060709748 0.0474790000 261625982 95654160 760807424 -0.0215505585 -0.1653988063 0.2915700972 3638 1311867291.8217189312 0.0580087155 0.0641176055 0.1147603467 0.0060704749 0.0427190000 261627662 95654160 760807424 -0.0209930986 -0.1657713056 0.2915416062 3639 1311867291.8538639545 0.0575736724 0.0641158072 0.1147603467 0.0060697982 0.0427320000 261631454 95654160 760807424 -0.0207340959 -0.1655895859 0.2910929024 3640 1311867291.8879489899 0.0582079254 0.0641141841 0.1147603467 0.0060693495 0.0424110000 261633062 95654160 760807424 -0.0208712798 -0.1660077721 0.2913190126 3641 1311867291.9206929207 0.0581546463 0.0641125474 0.1147603467 0.0060688750 0.0422670000 261636910 95654160 760807424 -0.0205202550 -0.1666575074 0.2914257050 3642 1311867291.9537200928 0.0585149489 0.0641110104 0.1147603467 0.0060686167 0.0425660000 261640390 95654160 760807424 -0.0204076990 -0.1666451395 0.2915460467 3643 1311867291.9902889729 0.0582232736 0.0641093942 0.1147603467 0.0060684504 0.0502370000 261642494 95654160 760807424 -0.0202133972 -0.1668121368 0.2916992605 3644 1311867292.0225260258 0.0591279902 0.0641080272 0.1147603467 0.0060703822 0.0432960000 261646158 95654160 760807424 -0.0196273662 -0.1669895649 0.2921362817 3645 1311867292.0536830425 0.0589625724 0.0641066156 0.1147603467 0.0060695815 0.0422860000 261647910 95654160 760807424 -0.0189939123 -0.1665641516 0.2920574546 3646 1311867292.0922849178 0.0584790744 0.0641050721 0.1147603467 0.0060700038 0.0434710000 261651742 95654160 760807424 -0.0194706973 -0.1659664959 0.2924806178 3647 1311867292.1243879795 0.0582854301 0.0641034763 0.1147603467 0.0060691908 0.0426060000 261655422 95654160 760807424 -0.0198920909 -0.1655534357 0.2923853397 3648 1311867292.1602649689 0.0582787246 0.0641018796 0.1147603467 0.0060683791 0.0437440000 261657270 95654160 760807424 -0.0195148978 -0.1653771996 0.2927134335 3649 1311867292.1899850368 0.0582396649 0.0641002731 0.1147603467 0.0060675612 0.0585010000 261660950 95654160 760807424 -0.0192063600 -0.1655767858 0.2930124402 3650 1311867292.2207419872 0.0589147061 0.0640988524 0.1147603467 0.0060670316 0.0431000000 261664374 95654160 760807424 -0.0196872596 -0.1655016690 0.2937416136 3651 1311867292.2576909065 0.0586872101 0.0640973702 0.1147603467 0.0060662302 0.0431720000 261666478 95654160 760807424 -0.0199306346 -0.1654819250 0.2936861217 3652 1311867292.2878270149 0.0589077026 0.0640959491 0.1147603467 0.0060654397 0.0428070000 261669958 95654160 760807424 -0.0202651806 -0.1666498184 0.2939566076 3653 1311867292.3217270374 0.0581490323 0.0640943212 0.1147603467 0.0060663427 0.0427460000 261671894 95654160 760807424 -0.0201321058 -0.1661489755 0.2942450345 3654 1311867292.3621709347 0.0583677404 0.0640927540 0.1147603467 0.0060679597 0.0431160000 261675710 95654160 760807424 -0.0201256070 -0.1654756665 0.2940799594 3655 1311867292.3953619003 0.0587600768 0.0640912950 0.1147603467 0.0060671850 0.0505860000 261679502 95654160 760807424 -0.0204425566 -0.1661824286 0.2945391536 3656 1311867292.4259300232 0.0590521134 0.0640899166 0.1147603467 0.0060664615 0.0431180000 261681054 95654160 760807424 -0.0209860206 -0.1672314852 0.2946670353 3657 1311867292.4565210342 0.0585728362 0.0640884080 0.1147603467 0.0060657922 0.0429550000 261684678 95654160 760807424 -0.0208459161 -0.1677830666 0.2942871153 3658 1311867292.4883699417 0.0587589853 0.0640869511 0.1147603467 0.0060649861 0.0431760000 261686470 95654160 760807424 -0.0212439112 -0.1680934429 0.2943997979 3659 1311867292.5229649544 0.0586297251 0.0640854596 0.1147603467 0.0060641732 0.0437510000 261690262 95654160 760807424 -0.0213328935 -0.1677124649 0.2944238186 3660 1311867292.5581150055 0.0580453090 0.0640838093 0.1147603467 0.0060633890 0.0426150000 261693854 95654160 760807424 -0.0223144945 -0.1669068187 0.2939301729 3661 1311867292.5882439613 0.0580559820 0.0640821628 0.1147603467 0.0060626568 0.0572050000 261695790 95654160 760807424 -0.0215432253 -0.1667218804 0.2944615483 3662 1311867292.6230869293 0.0578141361 0.0640804512 0.1147603467 0.0060618729 0.0430590000 261699510 95654160 760807424 -0.0210910290 -0.1667233706 0.2945480347 3663 1311867292.6595211029 0.0577578656 0.0640787251 0.1147603467 0.0060610989 0.0424160000 261701486 95654160 760807424 -0.0207535736 -0.1670625061 0.2947078049 3664 1311867292.6880218983 0.0589413159 0.0640773230 0.1147603467 0.0060602838 0.0431890000 261704854 95654160 760807424 -0.0220621303 -0.1672806591 0.2956927419 3665 1311867292.7206969261 0.0583053939 0.0640757481 0.1147603467 0.0060594690 0.0429330000 261708646 95654160 760807424 -0.0213333499 -0.1670486480 0.2953061759 3666 1311867292.7561879158 0.0585249923 0.0640742340 0.1147603467 0.0060588494 0.0432630000 261710622 95654160 760807424 -0.0213464238 -0.1675791442 0.2956164777 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 12:44:38 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.1008680000 954998708 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0030307258 0.0015153629 0.0030307258 0.0051709064 0.1130550000 958086585 0 402718720 -0.0004180265 -0.0040805521 0.0006781573 3 0.0800000000 0.0062998314 0.0031101857 0.0062998314 0.0043165851 0.1136400000 957775897 0 402718720 -0.0005358841 -0.0099249166 0.0005373082 4 0.1200000000 0.0035533810 0.0032209845 0.0062998314 0.0069081271 0.1145270000 957778305 0 402718720 0.0011465740 -0.0100325225 0.0018682312 5 0.1600000000 0.0070286286 0.0039825134 0.0070286286 0.0064735718 0.1158150000 957780313 0 402718720 0.0026940033 -0.0110032139 0.0027393242 6 0.2000000000 0.0037572624 0.0039449715 0.0070286286 0.0058317788 0.1156180000 957783121 0 402718720 0.0021845391 -0.0134021454 0.0027424688 7 0.2400000000 0.0055279690 0.0041711140 0.0070286286 0.0055040406 0.1160330000 957785129 0 402718720 0.0024463842 -0.0153440339 0.0031496249 8 0.2800000000 0.0094472757 0.0048306342 0.0094472757 0.0053506113 0.1161890000 957787137 0 402718720 0.0038651915 -0.0161758885 0.0041413233 9 0.3200000000 0.0107924109 0.0054930539 0.0107924109 0.0050553289 0.1167180000 957789145 0 402718720 0.0039572981 -0.0175238084 0.0041809333 10 0.3600000000 0.0107345218 0.0060172006 0.0107924109 0.0047750809 0.1167880000 957792753 0 402718720 0.0053117895 -0.0188581366 0.0043938621 11 0.4000000000 0.0117914975 0.0065421367 0.0117914975 0.0045950528 0.1160470000 957794761 0 402718720 0.0058871335 -0.0203279033 0.0047953073 12 0.4400000000 0.0134356376 0.0071165951 0.0134356376 0.0044389751 0.1158550000 957796769 0 402718720 0.0062686279 -0.0214786883 0.0047358926 13 0.4800000000 0.0158972926 0.0077920334 0.0158972926 0.0044962996 0.1277300000 957798777 0 402718720 0.0069575459 -0.0221605469 0.0048729512 14 0.5200000000 0.0174537580 0.0084821566 0.0174537580 0.0044903153 0.1183490000 957800785 0 402718720 0.0076059415 -0.0226107948 0.0050756638 15 0.5600000000 0.0184577554 0.0091471965 0.0184577554 0.0043480618 0.1179820000 957802793 0 402718720 0.0080166701 -0.0228761397 0.0048254151 16 0.6000000000 0.0185376294 0.0097340986 0.0185376294 0.0042059394 0.1158730000 957804801 0 402718720 0.0080020335 -0.0231413469 0.0046061110 17 0.6400000000 0.0193494540 0.0102997077 0.0193494540 0.0040869963 0.1170700000 957806809 0 402718720 0.0074606277 -0.0232412554 0.0042647514 18 0.6800000000 0.0200928114 0.0108437690 0.0200928114 0.0039863295 0.1166360000 957812017 0 402718720 0.0078618126 -0.0228382908 0.0042670798 19 0.7200000000 0.0203633979 0.0113448021 0.0203633979 0.0040373232 0.1471540000 957814025 0 402718720 0.0092678173 -0.0226247404 0.0042521507 20 0.7600000000 0.0205555987 0.0118053420 0.0205555987 0.0039331416 0.1174890000 957816033 0 402718720 0.0096269837 -0.0228300802 0.0038411394 21 0.8000000000 0.0212746486 0.0122562613 0.0212746486 0.0038362685 0.1174750000 957818041 0 402718720 0.0093654105 -0.0226109754 0.0041641234 22 0.8400000000 0.0210003294 0.0126537190 0.0212746486 0.0037444314 0.1174190000 957820049 0 402718720 0.0085959435 -0.0226487424 0.0039193216 23 0.8800000000 0.0203421526 0.0129879987 0.0212746486 0.0036586187 0.1175040000 957822057 0 402718720 0.0088683143 -0.0228751805 0.0039064405 24 0.9200000000 0.0204354487 0.0132983091 0.0212746486 0.0035865326 0.1153050000 957824065 0 402718720 0.0099250413 -0.0232788995 0.0042307675 25 0.9600000000 0.0207524020 0.0135964728 0.0212746486 0.0035196011 0.1173400000 957826073 0 402718720 0.0111902887 -0.0237325467 0.0046489770 26 1.0000000000 0.0211903471 0.0138885449 0.0212746486 0.0034528690 0.1172380000 957828081 0 402718720 0.0107417507 -0.0246430431 0.0045155226 27 1.0400000000 0.0221941266 0.0141961590 0.0221941266 0.0034019649 0.1171700000 957830089 0 402718720 0.0111594740 -0.0249387398 0.0048612929 28 1.0800000000 0.0217655376 0.0144664940 0.0221941266 0.0033608794 0.1156450000 957832097 0 402718720 0.0128533309 -0.0257083289 0.0048873676 29 1.1200000000 0.0228701513 0.0147562753 0.0228701513 0.0035455269 0.1272850000 957834105 0 402718720 0.0144188385 -0.0261632446 0.0052306731 30 1.1600000000 0.0223137159 0.0150081900 0.0228701513 0.0037918977 0.1177880000 957836113 0 402718720 0.0139191179 -0.0271053538 0.0052173911 31 1.2000000000 0.0229507629 0.0152644020 0.0229507629 0.0039675007 0.1160140000 957838121 0 402718720 0.0159501098 -0.0274806637 0.0056579472 32 1.2400000000 0.0240169205 0.0155379182 0.0240169205 0.0044082933 0.1177280000 957840129 0 402718720 0.0181184839 -0.0272773672 0.0062722769 33 1.2800000000 0.0236050580 0.0157823770 0.0240169205 0.0047293168 0.1170510000 957842137 0 402718720 0.0180938412 -0.0274116751 0.0069031036 34 1.3200000000 0.0237178039 0.0160157719 0.0240169205 0.0049302259 0.1162600000 957850545 0 402718720 0.0178449620 -0.0277337935 0.0076857656 35 1.3600000000 0.0244149882 0.0162557495 0.0244149882 0.0053823760 0.1162020000 957852553 0 402718720 0.0183208361 -0.0277648028 0.0085224314 36 1.4000000000 0.0232446678 0.0164498861 0.0244149882 0.0057295331 0.1163550000 957854561 0 402718720 0.0192373432 -0.0283374544 0.0091805551 37 1.4400000000 0.0238274802 0.0166492805 0.0244149882 0.0061909200 0.1168570000 957856569 0 402718720 0.0203717593 -0.0288420934 0.0098647401 38 1.4800000000 0.0234962367 0.0168294636 0.0244149882 0.0081837202 0.1178750000 957858577 0 402718720 0.0221177787 -0.0293802656 0.0114349192 39 1.5200000000 0.0243510548 0.0170223249 0.0244149882 0.0085111446 0.1161600000 957860585 0 402718720 0.0238478929 -0.0299650002 0.0126958154 40 1.5600000000 0.0249798466 0.0172212630 0.0249798466 0.0086526110 0.1165020000 957862593 0 402718720 0.0251252223 -0.0307523273 0.0132877249 41 1.6000000000 0.0228461511 0.0173584554 0.0249798466 0.0087845791 0.1173330000 957864601 0 402718720 0.0263259634 -0.0322534554 0.0142027745 42 1.6400000000 0.0242436789 0.0175223892 0.0249798466 0.0089377644 0.1192080000 957866609 0 402718720 0.0284370761 -0.0334082246 0.0149423378 43 1.6800000000 0.0272649415 0.0177489602 0.0272649415 0.0092463732 0.1208630000 957868617 0 402718720 0.0310343206 -0.0339408331 0.0162411071 44 1.7200000000 0.0295970850 0.0180182358 0.0295970850 0.0095288147 0.1205200000 957870625 0 402718720 0.0330974646 -0.0345772579 0.0177350156 45 1.7600000000 0.0287632421 0.0182570137 0.0295970850 0.0098377362 0.1315460000 957872633 0 402718720 0.0348860808 -0.0358843468 0.0186619889 46 1.8000000000 0.0200604312 0.0182962184 0.0295970850 0.0109506756 0.1272270000 957874641 0 402718720 0.0617508329 -0.0279770792 0.0123147899 47 1.8400000000 0.0201091059 0.0183347905 0.0295970850 0.0108605143 0.1271330000 957876649 0 402718720 0.1221675202 -0.0313045681 0.0012807474 48 1.8800000000 0.0231858958 0.0184358552 0.0295970850 0.0110193526 0.1211490000 957878657 0 402718720 0.1248530820 -0.0345843658 0.0026668692 49 1.9200000000 0.0251792558 0.0185734756 0.0295970850 0.0111831481 0.1313940000 957880665 0 402718720 0.1276023090 -0.0375085622 0.0034907993 50 1.9600000000 0.0274671651 0.0187513494 0.0295970850 0.0112863649 0.1574940000 957882673 0 402718720 0.1305546165 -0.0399123058 0.0044001965 51 2.0000000000 0.0288412031 0.0189491897 0.0295970850 0.0113611295 0.1553120000 957884681 0 402718720 0.1335948557 -0.0422274098 0.0046392148 52 2.0400000000 0.0300754718 0.0191631566 0.0300754718 0.0114281386 0.1548000000 957886689 0 402718720 0.1370837241 -0.0442752466 0.0049953149 53 2.0800000000 0.0312042162 0.0193903464 0.0312042162 0.0114658584 0.1524990000 957888697 0 402718720 0.1388889402 -0.0461859070 0.0053207111 54 2.1200000000 0.0332861207 0.0196476756 0.0332861207 0.0115031466 0.1517670000 957890705 0 402718720 0.1425562203 -0.0477929302 0.0054566427 55 2.1600000000 0.0237678401 0.0197225877 0.0332861207 0.0115176667 0.1594950000 957892713 0 402718720 0.1446311772 -0.0365153588 0.0017210053 56 2.2000000000 0.0256906543 0.0198291603 0.0332861207 0.0115955366 0.1470070000 957894721 0 402718720 0.1459153742 -0.0399215743 0.0022382415 57 2.2400000000 0.0264974125 0.0199461472 0.0332861207 0.0117551116 0.1454570000 957896729 0 402718720 0.1458789706 -0.0432401523 0.0030267194 58 2.2800000000 0.0283577200 0.0200911743 0.0332861207 0.0119249962 0.1438260000 957898737 0 402718720 0.1479291916 -0.0461634658 0.0032454391 59 2.3200000000 0.0306222681 0.0202696674 0.0332861207 0.0121806430 0.1432220000 957900745 0 402718720 0.1503460407 -0.0487393662 0.0033484220 60 2.3600000000 0.0322039090 0.0204685714 0.0332861207 0.0123590013 0.1431880000 957902753 0 402718720 0.1535933018 -0.0510257334 0.0027317614 61 2.4000000000 0.0340659730 0.0206914797 0.0340659730 0.0126415823 0.1441010000 957904761 0 402718720 0.1563608348 -0.0529716723 0.0028507081 62 2.4400000000 0.0310320687 0.0208582634 0.0340659730 0.0128610685 0.1147290000 957906769 0 402718720 0.1592538953 -0.0502463318 0.0008394172 63 2.4800000000 0.0300823636 0.0210046776 0.0340659730 0.0130701120 0.1218570000 957908777 0 402718720 0.1624419242 -0.0488173775 -0.0004603955 64 2.5200000000 0.0308122654 0.0211579212 0.0340659730 0.0132111877 0.1127020000 957910785 0 402718720 0.1659025997 -0.0515508652 -0.0018113790 65 2.5600000000 0.0298890900 0.0212922469 0.0340659730 0.0133122279 0.1325300000 957912793 0 402718720 0.1698861420 -0.0503774732 -0.0039404347 66 2.6000000000 0.0292327479 0.0214125575 0.0340659730 0.0133969704 0.1162650000 957927601 0 402718720 0.1741082072 -0.0507118106 -0.0063432679 67 2.6400000000 0.0290718228 0.0215268749 0.0340659730 0.0135044897 0.1175770000 957929609 0 402718720 0.1773452759 -0.0510522574 -0.0083885593 68 2.6800000000 0.0291266683 0.0216386366 0.0340659730 0.0136204137 0.1179200000 957931617 0 402718720 0.1819687188 -0.0508316979 -0.0111819217 69 2.7200000000 0.0298430212 0.0217575407 0.0340659730 0.0137327878 0.1181480000 957933625 0 402718720 0.1851207465 -0.0536040775 -0.0128024127 70 2.7600000000 0.0309276134 0.0218885417 0.0340659730 0.0139157932 0.1297520000 957935633 0 402718720 0.1879724264 -0.0559509210 -0.0135455253 71 2.8000000000 0.0299313404 0.0220018206 0.0340659730 0.0140277851 0.1208280000 957937641 0 402718720 0.1918465644 -0.0544394739 -0.0160437487 72 2.8400000000 0.0295673050 0.0221068967 0.0340659730 0.0141875909 0.1227130000 957939649 0 402718720 0.1943916827 -0.0541905053 -0.0175877474 73 2.8800000000 0.0311262906 0.0222304501 0.0340659730 0.0143174022 0.1204030000 957941657 0 402718720 0.1970871985 -0.0562288836 -0.0185085852 74 2.9200000000 0.0298996270 0.0223340876 0.0340659730 0.0143986075 0.1237640000 957943665 0 402718720 0.2011954784 -0.0554029271 -0.0215123631 75 2.9600000000 0.0318258740 0.0224606448 0.0340659730 0.0145431932 0.1320340000 957945673 0 402718720 0.2033636272 -0.0571216419 -0.0220328048 76 3.0000000000 0.0297831334 0.0225569933 0.0340659730 0.0145754802 0.1255820000 957947681 0 402718720 0.2075569481 -0.0577342585 -0.0254407525 77 3.0400000000 0.0307070240 0.0226628379 0.0340659730 0.0146437712 0.1220780000 957949689 0 402718720 0.2104727179 -0.0599387847 -0.0272690337 78 3.0800000000 0.0300101563 0.0227570342 0.0340659730 0.0146621878 0.1376160000 957951697 0 402718720 0.2152206600 -0.0601221509 -0.0308504533 79 3.1200000000 0.0299763661 0.0228484182 0.0340659730 0.0147132473 0.1247040000 957953705 0 402718720 0.2192791402 -0.0604487918 -0.0334235206 80 3.1600000000 0.0300289840 0.0229381753 0.0340659730 0.0151451121 0.1247410000 957955713 0 402718720 0.2279175520 -0.0616245493 -0.0395868234 81 3.2000000000 0.0300682634 0.0230262010 0.0340659730 0.0151712639 0.1250540000 957957721 0 402718720 0.2319813073 -0.0619874597 -0.0420864150 82 3.2400000000 0.0297000855 0.0231075899 0.0340659730 0.0151720461 0.1221190000 957959729 0 402718720 0.2344302237 -0.0646845624 -0.0442944281 83 3.2800000000 0.0300895385 0.0231917097 0.0340659730 0.0152244482 0.1251260000 957961737 0 402718720 0.2384154052 -0.0652534068 -0.0464771651 84 3.3200000000 0.0297098402 0.0232693065 0.0340659730 0.0152128530 0.1222590000 957963745 0 402718720 0.2399727851 -0.0679134876 -0.0477786139 85 3.3600000000 0.0299188960 0.0233475370 0.0340659730 0.0152285454 0.1379120000 957965753 0 402718720 0.2440270334 -0.0693486109 -0.0501211695 86 3.4000000000 0.0308114570 0.0234343268 0.0340659730 0.0152670074 0.1214210000 957967761 0 402718720 0.2460011393 -0.0714506209 -0.0511292778 87 3.4400000000 0.0304066129 0.0235144680 0.0340659730 0.0152950758 0.1254040000 957969769 0 402718720 0.2500568926 -0.0714379176 -0.0536196828 88 3.4800000000 0.0305785928 0.0235947421 0.0340659730 0.0153173932 0.1246710000 957971777 0 402718720 0.2539076805 -0.0707614049 -0.0562096983 89 3.5200000000 0.0314385965 0.0236828753 0.0340659730 0.0153160275 0.1339020000 957973785 0 402718720 0.2562080026 -0.0722595602 -0.0579686388 90 3.5600000000 0.0312101152 0.0237665113 0.0340659730 0.0153236545 0.1215520000 957975793 0 402718720 0.2582892179 -0.0741234720 -0.0595006719 91 3.6000000000 0.0319547616 0.0238564921 0.0340659730 0.0153409606 0.1210530000 957977801 0 402718720 0.2610354722 -0.0755953938 -0.0609562360 92 3.6400000000 0.0312644057 0.0239370129 0.0340659730 0.0153417095 0.1250990000 957979809 0 402718720 0.2646918595 -0.0739219412 -0.0633023232 93 3.6800000000 0.0313426591 0.0240166435 0.0340659730 0.0153014560 0.1208050000 957981817 0 402718720 0.2658686042 -0.0755259916 -0.0649054721 94 3.7200000000 0.0319866464 0.0241014308 0.0340659730 0.0152629303 0.1205220000 957983825 0 402718720 0.2685824335 -0.0766985342 -0.0661532879 95 3.7600000000 0.0328571051 0.0241935958 0.0340659730 0.0152201749 0.1298130000 957985833 0 402718720 0.2717845440 -0.0772544369 -0.0680978149 96 3.8000000000 0.0330489874 0.0242858394 0.0340659730 0.0151752927 0.1198110000 957987841 0 402718720 0.2743145823 -0.0777814090 -0.0703594536 97 3.8400000000 0.0333528854 0.0243793141 0.0340659730 0.0151383345 0.1195670000 957989849 0 402718720 0.2767156959 -0.0783487111 -0.0723015666 98 3.8800000000 0.0331504978 0.0244688160 0.0340659730 0.0150965068 0.1212900000 957991857 0 402718720 0.2777814269 -0.0792195573 -0.0730029643 99 3.9200000000 0.0331761576 0.0245567689 0.0340659730 0.0150410443 0.1409600000 957993865 0 402718720 0.2799732387 -0.0799480975 -0.0750485733 100 3.9600000000 0.0329069048 0.0246402703 0.0340659730 0.0149888617 0.1213000000 957995873 0 402718720 0.2814643085 -0.0810712054 -0.0763301998 101 4.0000000000 0.0345504321 0.0247383907 0.0345504321 0.0149383252 0.1211710000 957997881 0 402718720 0.2843367159 -0.0808781907 -0.0776144341 102 4.0400000000 0.0349478275 0.0248384832 0.0349478275 0.0148926831 0.1207880000 957999889 0 402718720 0.2864767313 -0.0806446224 -0.0791365728 103 4.0800000000 0.0351588912 0.0249386814 0.0351588912 0.0148467220 0.1211840000 958001897 0 402718720 0.2887848318 -0.0803593099 -0.0803696811 104 4.1200000000 0.0355823226 0.0250410241 0.0355823226 0.0147932369 0.1274530000 958003905 0 402718720 0.2906090021 -0.0797887668 -0.0816079900 105 4.1600000000 0.0360429622 0.0251458044 0.0360429622 0.0147451959 0.1211160000 958005913 0 402718720 0.2930867672 -0.0790262818 -0.0833689794 106 4.2000000000 0.0358815901 0.0252470854 0.0360429622 0.0146887496 0.1209730000 958007921 0 402718720 0.2947120965 -0.0783653408 -0.0845872536 107 4.2400000000 0.0354867131 0.0253427829 0.0360429622 0.0146258402 0.1330910000 958009929 0 402718720 0.2955012023 -0.0779748335 -0.0853394419 108 4.2800000000 0.0362772383 0.0254440278 0.0362772383 0.0145618030 0.1312740000 958011937 0 402718720 0.2986349761 -0.0765172690 -0.0879733860 109 4.3200000000 0.0361209735 0.0255419815 0.0362772383 0.0144947330 0.1193650000 958013945 0 402718720 0.3001912832 -0.0757062584 -0.0892382637 110 4.3600000000 0.0364452451 0.0256411021 0.0364452451 0.0144305405 0.1180830000 958015953 0 402718720 0.3011291623 -0.0749361888 -0.0902914554 111 4.4000000000 0.0372685716 0.0257458540 0.0372685716 0.0143667334 0.1196740000 958017961 0 402718720 0.3023719490 -0.0736352801 -0.0915086344 112 4.4400000000 0.0381373316 0.0258564922 0.0381373316 0.0143087927 0.1197000000 958019969 0 402718720 0.3045832515 -0.0718769208 -0.0935306698 113 4.4800000000 0.0386758409 0.0259699378 0.0386758409 0.0142457699 0.1196150000 958021977 0 402718720 0.3061368763 -0.0699653104 -0.0945667550 114 4.5200000000 0.0384291410 0.0260792290 0.0386758409 0.0141826854 0.1318800000 958023985 0 402718720 0.3069716692 -0.0681922436 -0.0956306607 115 4.5600000000 0.0388154760 0.0261899790 0.0388154760 0.0141226427 0.1197270000 958025993 0 402718720 0.3081197739 -0.0661076531 -0.0970509276 116 4.6000000000 0.0385650545 0.0262966607 0.0388154760 0.0140655807 0.1206290000 958028001 0 402718720 0.3085317910 -0.0643979684 -0.0981121883 117 4.6400000000 0.0389307514 0.0264046444 0.0389307514 0.0140233165 0.1206050000 958030009 0 402718720 0.3093309104 -0.0622205734 -0.0994187966 118 4.6800000000 0.0379652381 0.0265026155 0.0389307514 0.0139882674 0.1207930000 958032017 0 402718720 0.3096423745 -0.0607430637 -0.1000889018 119 4.7200000000 0.0388338193 0.0266062391 0.0389307514 0.0139491615 0.1202990000 958034025 0 402718720 0.3100995421 -0.0589011498 -0.1004231721 120 4.7600000000 0.0385342948 0.0267056395 0.0389307514 0.0139028583 0.1204010000 958036033 0 402718720 0.3098109961 -0.0576264113 -0.1013808772 121 4.8000000000 0.0386938378 0.0268047156 0.0389307514 0.0138588360 0.1206020000 958038041 0 402718720 0.3092205226 -0.0564527847 -0.1009990424 122 4.8400000000 0.0406984538 0.0269185987 0.0406984538 0.0138327453 0.1207500000 958040049 0 402718720 0.3085516691 -0.0537145138 -0.1013542935 123 4.8800000000 0.0408810005 0.0270321141 0.0408810005 0.0137866504 0.1210210000 958042057 0 402718720 0.3078758121 -0.0516386665 -0.1011331975 124 4.9200000000 0.0402021855 0.0271383244 0.0408810005 0.0137460606 0.1205210000 958044065 0 402718720 0.3069051504 -0.0499767736 -0.1012711823 125 4.9600000000 0.0409511514 0.0272488270 0.0409511514 0.0137048797 0.1202040000 958046073 0 402718720 0.3066295087 -0.0477898903 -0.1007825360 126 5.0000000000 0.0407247134 0.0273557785 0.0409511514 0.0136659149 0.1204650000 958048081 0 402718720 0.3062510490 -0.0457099564 -0.1008943841 127 5.0400000000 0.0398945175 0.0274545087 0.0409511514 0.0136373474 0.1206150000 958050089 0 402718720 0.3048449457 -0.0433637798 -0.1003940180 128 5.0800000000 0.0378548503 0.0275357614 0.0409511514 0.0136104496 0.1204830000 958052097 0 402718720 0.3032777011 -0.0398316756 -0.1001831666 129 5.1200000000 0.0370041430 0.0276091597 0.0409511514 0.0135834588 0.1183340000 958054105 0 402718720 0.3028945625 -0.0363076217 -0.1004430577 130 5.1600000000 0.0362241305 0.0276754287 0.0409511514 0.0135625963 0.1201500000 958081713 0 402718720 0.3012224138 -0.0347208418 -0.0992934480 131 5.2000000000 0.0356014445 0.0277359326 0.0409511514 0.0135439083 0.1205620000 958083721 0 402718720 0.2990161479 -0.0340016261 -0.0981273875 132 5.2400000000 0.0353699476 0.0277937661 0.0409511514 0.0135246865 0.1209610000 958085729 0 402718720 0.2969994545 -0.0334964655 -0.0970012099 133 5.2800000000 0.0355161466 0.0278518291 0.0409511514 0.0134935491 0.1215090000 958087737 0 402718720 0.2958517969 -0.0328159966 -0.0953606889 134 5.3200000000 0.0362957940 0.0279148437 0.0409511514 0.0134565360 0.1363030000 958089745 0 402718720 0.2943397760 -0.0318799578 -0.0938390419 135 5.3600000000 0.0359441824 0.0279743203 0.0409511514 0.0134208163 0.1203980000 958091753 0 402718720 0.2918344140 -0.0312451348 -0.0917518884 136 5.4000000000 0.0363144949 0.0280356451 0.0409511514 0.0133880386 0.1229630000 958093761 0 402718720 0.2904295325 -0.0300196595 -0.0903894976 137 5.4400000000 0.0368926898 0.0281002951 0.0409511514 0.0133562477 0.1220080000 958095769 0 402718720 0.2896405458 -0.0279837698 -0.0891326517 138 5.4800000000 0.0354346298 0.0281534425 0.0409511514 0.0134170971 0.1225490000 958097777 0 402718720 0.2858510315 -0.0266247615 -0.0862205774 139 5.5200000000 0.0355884358 0.0282069316 0.0409511514 0.0133859481 0.1390730000 958099785 0 402718720 0.2838686109 -0.0259813592 -0.0844641626 140 5.5600000000 0.0358971059 0.0282618614 0.0409511514 0.0133667929 0.1429870000 958101793 0 402718720 0.2828603089 -0.0244267043 -0.0831447914 141 5.6000000000 0.0361343361 0.0283176946 0.0409511514 0.0133436266 0.1276640000 958103801 0 402718720 0.2813179493 -0.0229001027 -0.0815787911 142 5.6400000000 0.0365783200 0.0283758680 0.0409511514 0.0133176478 0.1282040000 958105809 0 402718720 0.2801461816 -0.0208113343 -0.0801875144 143 5.6800000000 0.0357464887 0.0284274108 0.0409511514 0.0132996684 0.1268110000 958107817 0 402718720 0.2776869237 -0.0195407253 -0.0787095949 144 5.7200000000 0.0353116468 0.0284752180 0.0409511514 0.0132703946 0.1507020000 958109825 0 402718720 0.2749579251 -0.0188779421 -0.0773830190 145 5.7600000000 0.0366923548 0.0285318879 0.0409511514 0.0132396757 0.1290730000 958111833 0 402718720 0.2736988366 -0.0167049505 -0.0755728260 146 5.8000000000 0.0359167568 0.0285824692 0.0409511514 0.0132118362 0.1292960000 958113841 0 402718720 0.2713189423 -0.0152766677 -0.0742852613 147 5.8400000000 0.0356712751 0.0286306924 0.0409511514 0.0131893057 0.1293600000 958115849 0 402718720 0.2684700191 -0.0140469009 -0.0720911473 148 5.8800000000 0.0355019681 0.0286771199 0.0409511514 0.0131696805 0.1296540000 958117857 0 402718720 0.2666638494 -0.0126952231 -0.0713461116 149 5.9200000000 0.0349288248 0.0287190777 0.0409511514 0.0131488989 0.1295300000 958119865 0 402718720 0.2634561956 -0.0121110128 -0.0693950802 150 5.9600000000 0.0340521336 0.0287546314 0.0409511514 0.0131303407 0.1295470000 958121873 0 402718720 0.2595216036 -0.0125165461 -0.0672080368 151 6.0000000000 0.0343782492 0.0287918739 0.0409511514 0.0131074260 0.1422390000 958123881 0 402718720 0.2559955418 -0.0125446776 -0.0650423840 152 6.0400000000 0.0336688012 0.0288239589 0.0409511514 0.0130908006 0.1300230000 958125889 0 402718720 0.2524609566 -0.0131617123 -0.0627744794 153 6.0800000000 0.0350384228 0.0288645763 0.0409511514 0.0130732366 0.1300590000 958127897 0 402718720 0.2489915639 -0.0122783259 -0.0601514690 154 6.1200000000 0.0353163406 0.0289064709 0.0409511514 0.0130660160 0.1407730000 958129905 0 402718720 0.2462027371 -0.0108720297 -0.0584203601 155 6.1600000000 0.0344748013 0.0289423956 0.0409511514 0.0130607950 0.1300230000 958131913 0 402718720 0.2418483943 -0.0107501708 -0.0560624227 156 6.2000000000 0.0348396040 0.0289801982 0.0409511514 0.0130575972 0.1418210000 958133921 0 402718720 0.2376033217 -0.0102218529 -0.0533773117 157 6.2400000000 0.0355076380 0.0290217743 0.0409511514 0.0130591477 0.1277820000 958135929 0 402718720 0.2336531878 -0.0088727856 -0.0515855141 158 6.2800000000 0.0353826843 0.0290620332 0.0409511514 0.0130741777 0.1275260000 958137937 0 402718720 0.2307778448 -0.0075846352 -0.0500413664 159 6.3200000000 0.0350774266 0.0290998659 0.0409511514 0.0130812589 0.1276920000 958139945 0 402718720 0.2269575000 -0.0071258447 -0.0483232923 160 6.3600000000 0.0354152173 0.0291393368 0.0409511514 0.0130808859 0.1297980000 958141953 0 402718720 0.2240636498 -0.0062275375 -0.0467318334 161 6.4000000000 0.0355762914 0.0291793179 0.0409511514 0.0130819450 0.1291160000 958143961 0 402718720 0.2212907672 -0.0052039265 -0.0454118811 162 6.4400000000 0.0349166393 0.0292147335 0.0409511514 0.0130948380 0.1437970000 958145969 0 402718720 0.2167942971 -0.0051816278 -0.0438523106 163 6.4800000000 0.0346890390 0.0292483182 0.0409511514 0.0130934983 0.1314580000 958147977 0 402718720 0.2126604915 -0.0056029800 -0.0419534557 164 6.5200000000 0.0343166701 0.0292792227 0.0409511514 0.0130873865 0.1291100000 958149985 0 402718720 0.2093940079 -0.0064480975 -0.0403128341 165 6.5600000000 0.0363679305 0.0293221846 0.0409511514 0.0130727669 0.1293390000 958151993 0 402718720 0.2064415067 -0.0050373608 -0.0383416452 166 6.6000000000 0.0351443626 0.0293572580 0.0409511514 0.0130848605 0.1295920000 958154001 0 402718720 0.2005656511 -0.0051783086 -0.0358414911 167 6.6400000000 0.0350174643 0.0293911514 0.0409511514 0.0131021179 0.1299600000 958156009 0 402718720 0.1964589506 -0.0052826698 -0.0337487645 168 6.6800000000 0.0362930484 0.0294322341 0.0409511514 0.0131002296 0.1326340000 958158017 0 402718720 0.1934852600 -0.0040255976 -0.0318622589 169 6.7200000000 0.0350865200 0.0294656915 0.0409511514 0.0131443489 0.1329790000 958160025 0 402718720 0.1891319156 -0.0040988154 -0.0302367490 170 6.7600000000 0.0347740203 0.0294969169 0.0409511514 0.0131628155 0.1333920000 958162033 0 402718720 0.1851851642 -0.0048687248 -0.0288355574 171 6.8000000000 0.0364219286 0.0295374141 0.0409511514 0.0131711162 0.1343860000 958164041 0 402718720 0.1836948842 -0.0036885443 -0.0278720707 172 6.8400000000 0.0364121012 0.0295773832 0.0409511514 0.0131904340 0.1358800000 958166049 0 402718720 0.1815501899 -0.0027058243 -0.0268938821 173 6.8800000000 0.0357235819 0.0296129103 0.0409511514 0.0132168586 0.1363830000 958168057 0 402718720 0.1803918034 -0.0025522036 -0.0265778936 174 6.9200000000 0.0347308964 0.0296423240 0.0409511514 0.0132488962 0.1369080000 958170065 0 402718720 0.1785957515 -0.0035013743 -0.0252210461 175 6.9600000000 0.0355307199 0.0296759720 0.0409511514 0.0132887369 0.1374720000 958172073 0 402718720 0.1787393540 -0.0033245659 -0.0248228498 176 7.0000000000 0.0361776799 0.0297129135 0.0409511514 0.0132976475 0.1391670000 958174081 0 402718720 0.1788969785 -0.0025700820 -0.0248810314 177 7.0400000000 0.0368383937 0.0297531705 0.0409511514 0.0133380716 0.1403490000 958176089 0 402718720 0.1769562215 -0.0011684776 -0.0239964873 178 7.0800000000 0.0363844931 0.0297904251 0.0409511514 0.0133813231 0.1406520000 958178097 0 402718720 0.1744831949 -0.0004222287 -0.0235467330 179 7.1200000000 0.0351669975 0.0298204618 0.0409511514 0.0134445432 0.1422410000 958180105 0 402718720 0.1722283065 -0.0009662049 -0.0229528490 180 7.1600000000 0.0362799466 0.0298563479 0.0409511514 0.0134735673 0.1445650000 958182113 0 402718720 0.1716829836 -0.0004024661 -0.0226429924 181 7.2000000000 0.0363749526 0.0298923623 0.0409511514 0.0134635315 0.1462820000 958184121 0 402718720 0.1690517068 -0.0002340648 -0.0219698995 182 7.2400000000 0.0368477590 0.0299305787 0.0409511514 0.0134571733 0.1502060000 958186129 0 402718720 0.1688235402 0.0005257528 -0.0219784025 183 7.2800000000 0.0370108038 0.0299692685 0.0409511514 0.0134429368 0.1537010000 958188137 0 402718720 0.1645367593 0.0011259662 -0.0207945574 184 7.3200000000 0.0359312296 0.0300016704 0.0409511514 0.0134473199 0.1548860000 958190145 0 402718720 0.1621323973 0.0008067887 -0.0205578320 185 7.3600000000 0.0365061387 0.0300368297 0.0409511514 0.0134344540 0.1559510000 958192153 0 402718720 0.1574945152 0.0007632949 -0.0201310758 186 7.4000000000 0.0360971130 0.0300694119 0.0409511514 0.0134495265 0.1555510000 958194161 0 402718720 0.1569955349 0.0007593511 -0.0196732786 187 7.4400000000 0.0354163498 0.0300980051 0.0409511514 0.0134685492 0.1535400000 958196169 0 402718720 0.1542773545 -0.0002722288 -0.0194841083 188 7.4800000000 0.0355519429 0.0301270155 0.0409511514 0.0134842292 0.1775290000 958198177 0 402718720 0.1514141113 -0.0012284378 -0.0185283627 189 7.5200000000 0.0366276652 0.0301614104 0.0409511514 0.0135166983 0.1555310000 958200185 0 402718720 0.1495740861 -0.0008259621 -0.0176953692 190 7.5600000000 0.0357424505 0.0301907843 0.0409511514 0.0135723305 0.1569580000 958202193 0 402718720 0.1464860141 -0.0016184906 -0.0170057770 191 7.6000000000 0.0370875448 0.0302268930 0.0409511514 0.0136087869 0.1574720000 958204201 0 402718720 0.1456205696 -0.0007601315 -0.0167270992 192 7.6400000000 0.0367243700 0.0302607340 0.0409511514 0.0136317204 0.1576010000 958206209 0 402718720 0.1428446174 -0.0007525004 -0.0164551362 193 7.6800000000 0.0369297825 0.0302952887 0.0409511514 0.0136655146 0.1693000000 958208217 0 402718720 0.1415523738 -0.0002552781 -0.0159500409 194 7.7200000000 0.0362729803 0.0303261015 0.0409511514 0.0136711952 0.1563630000 958210225 0 402718720 0.1389540583 -0.0011810171 -0.0162572414 195 7.7600000000 0.0374338329 0.0303625514 0.0409511514 0.0136660814 0.1670840000 958212233 0 402718720 0.1400862783 -0.0001501835 -0.0161339827 196 7.8000000000 0.0370641164 0.0303967431 0.0409511514 0.0136529357 0.1566430000 958214241 0 402718720 0.1364770979 -0.0003623911 -0.0162432753 197 7.8400000000 0.0344267301 0.0304171999 0.0409511514 0.0136717994 0.1602360000 958216249 0 402718720 0.1389022321 0.0025637650 -0.0161997732 198 7.8800000000 0.0361105315 0.0304459541 0.0409511514 0.0136739774 0.1571180000 958218257 0 402718720 0.1375799477 0.0015915375 -0.0160260256 199 7.9200000000 0.0344107151 0.0304658775 0.0409511514 0.0137029427 0.1716200000 958220265 0 402718720 0.1415878236 0.0043592989 -0.0158201605 200 7.9600000000 0.0361983553 0.0304945399 0.0409511514 0.0137134356 0.1561870000 958222273 0 402718720 0.1410736740 0.0039805043 -0.0157397781 201 8.0000000000 0.0364281647 0.0305240604 0.0409511514 0.0137289965 0.1593970000 958224281 0 402718720 0.1430705637 0.0041435566 -0.0154266283 202 8.0400000000 0.0355297513 0.0305488411 0.0409511514 0.0137331974 0.1639800000 958226289 0 402718720 0.1396463662 0.0041695498 -0.0154298106 203 8.0800000000 0.0354843922 0.0305731541 0.0409511514 0.0137166272 0.1654180000 958228297 0 402718720 0.1358340830 0.0052971966 -0.0151160276 204 8.1200000000 0.0352532677 0.0305960959 0.0409511514 0.0136884508 0.1660890000 958230305 0 402718720 0.1336115003 0.0074598510 -0.0145306243 205 8.1600000000 0.0338711366 0.0306120717 0.0409511514 0.0136654080 0.1762610000 958232313 0 402718720 0.1308425814 0.0070781317 -0.0139895706 206 8.1999999990 0.0330726020 0.0306240160 0.0409511514 0.0136502903 0.1674210000 958234321 0 402718720 0.1278735548 0.0053713988 -0.0125528844 207 8.2400000000 0.0338323079 0.0306395150 0.0409511514 0.0136440238 0.1674040000 958236329 0 402718720 0.1259390116 0.0061241193 -0.0116519760 208 8.2799999990 0.0321280137 0.0306466712 0.0409511514 0.0136666174 0.1676880000 958238337 0 402718720 0.1249973178 0.0048931977 -0.0099344198 209 8.3200000000 0.0332460292 0.0306591083 0.0409511514 0.0136770295 0.1711380000 958240345 0 402718720 0.1236949041 0.0057878699 -0.0092754643 210 8.3599999990 0.0343992449 0.0306769185 0.0409511514 0.0136885888 0.1944300000 958242353 0 402718720 0.1216039136 0.0083148116 -0.0085831592 211 8.4000000000 0.0337873027 0.0306916597 0.0409511514 0.0137241324 0.1753390000 958244361 0 402718720 0.1193519011 0.0094128782 -0.0077532874 212 8.4399999990 0.0320017673 0.0306978394 0.0409511514 0.0137551039 0.1882680000 958246369 0 402718720 0.1185923889 0.0081281224 -0.0058768131 213 8.4800000000 0.0334418714 0.0307107222 0.0409511514 0.0137635339 0.1759530000 958248377 0 402718720 0.1158158109 0.0082098683 -0.0049898778 214 8.5200000000 0.0330197029 0.0307215118 0.0409511514 0.0137813475 0.1727930000 958250385 0 402718720 0.1140935272 0.0084857978 -0.0035463001 215 8.5600000000 0.0323682092 0.0307291709 0.0409511514 0.0138159600 0.1737580000 958252393 0 402718720 0.1123760343 0.0073981900 -0.0023192959 216 8.6000000000 0.0329014659 0.0307392278 0.0409511514 0.0138341743 0.1743870000 958254401 0 402718720 0.1136871725 0.0107129840 -0.0000106028 217 8.6400000000 0.0326796509 0.0307481699 0.0409511514 0.0138369670 0.1760890000 958256409 0 402718720 0.1137657538 0.0125018144 0.0013791600 218 8.6800000000 0.0315340124 0.0307517746 0.0409511514 0.0138491790 0.1756510000 958258417 0 402718720 0.1151442900 0.0127875190 0.0035674130 219 8.7200000000 0.0310540758 0.0307531550 0.0409511514 0.0138771906 0.1759990000 958260425 0 402718720 0.1167962775 0.0124850394 0.0070197321 220 8.7600000000 0.0307838507 0.0307532945 0.0409511514 0.0138910182 0.1940480000 958262433 0 402718720 0.1174301282 0.0108033018 0.0103938188 221 8.8000000000 0.0311951041 0.0307552937 0.0409511514 0.0139169092 0.1826770000 958264441 0 402718720 0.1186959967 0.0108115813 0.0127046229 222 8.8400000000 0.0320011936 0.0307609058 0.0409511514 0.0139440383 0.1844300000 958266449 0 402718720 0.1182869151 0.0121463733 0.0144358892 223 8.8800000000 0.0315790400 0.0307645746 0.0409511514 0.0139836804 0.1852090000 958268457 0 402718720 0.1172704101 0.0114466911 0.0164397266 224 8.9200000000 0.0320075192 0.0307701235 0.0409511514 0.0140015939 0.1864600000 958270465 0 402718720 0.1143552512 0.0108341668 0.0175306331 225 8.9600000000 0.0312132668 0.0307720930 0.0409511514 0.0141446099 0.2058190000 958272473 0 402718720 0.0727576017 0.0060499827 0.0029170364 226 9.0000000000 0.0331156924 0.0307824629 0.0409511514 0.0141476959 0.1872530000 958274481 0 402718720 0.0682269782 0.0073972251 0.0020723538 227 9.0400000000 0.0325725898 0.0307903489 0.0409511514 0.0141553997 0.1871250000 958276489 0 402718720 0.0646797270 0.0067051561 0.0026190565 228 9.0800000000 0.0328420661 0.0307993477 0.0409511514 0.0141631019 0.1869350000 958278497 0 402718720 0.0610855930 0.0065256152 0.0027677782 229 9.1200000000 0.0328723527 0.0308084001 0.0409511514 0.0141693507 0.1877080000 958280505 0 402718720 0.0569228157 0.0060614371 0.0025206427 230 9.1600000000 0.0331423394 0.0308185477 0.0409511514 0.0141787831 0.1884330000 958282513 0 402718720 0.0524391010 0.0061734356 0.0025637627 231 9.2000000000 0.0330310315 0.0308281255 0.0409511514 0.0141841069 0.1910490000 958284521 0 402718720 0.0485090464 0.0058627222 0.0020280981 232 9.2400000000 0.0329973027 0.0308374754 0.0409511514 0.0141902828 0.1921040000 958286529 0 402718720 0.0448235460 0.0052420967 0.0023837683 233 9.2800000000 0.0332641900 0.0308478905 0.0409511514 0.0142024742 0.1926770000 958288537 0 402718720 0.0419298485 0.0058824313 0.0015681785 234 9.3200000000 0.0332735851 0.0308582567 0.0409511514 0.0142060776 0.1926860000 958290545 0 402718720 0.0380828567 0.0059896740 0.0008480730 235 9.3600000000 0.0330830552 0.0308677239 0.0409511514 0.0142263419 0.1920660000 958292553 0 402718720 0.0352249555 0.0054374230 0.0007716154 236 9.4000000000 0.0329878256 0.0308767074 0.0409511514 0.0142641776 0.1927140000 958294561 0 402718720 0.0325530246 0.0044289259 0.0004870987 237 9.4400000000 0.0326931290 0.0308843717 0.0409511514 0.0142953702 0.2122280000 958296569 0 402718720 0.0297441296 0.0019534715 0.0000956554 238 9.4800000000 0.0324541777 0.0308909675 0.0409511514 0.0143210203 0.1949430000 958298577 0 402718720 0.0263640583 -0.0017531284 -0.0001434245 239 9.5200000000 0.0331579335 0.0309004527 0.0409511514 0.0143333467 0.1932020000 958300585 0 402718720 0.0238615740 -0.0021630528 -0.0005917897 240 9.5600000000 0.0321585201 0.0309056946 0.0409511514 0.0144875026 0.1937250000 958302593 0 402718720 0.0211449582 -0.0072956430 0.0005679061 241 9.6000000000 0.0330988504 0.0309147949 0.0409511514 0.0144849805 0.1926800000 958304601 0 402718720 0.0185645260 -0.0082374960 -0.0003262015 242 9.6400000000 0.0327793732 0.0309224997 0.0409511514 0.0144990858 0.1920890000 958306609 0 402718720 0.0171779860 -0.0103152124 0.0001889281 243 9.6800000000 0.0326950401 0.0309297941 0.0409511514 0.0145147483 0.1912380000 958308617 0 402718720 0.0153856240 -0.0128534641 -0.0000782849 244 9.7200000000 0.0329952724 0.0309382592 0.0409511514 0.0145242487 0.1910100000 958310625 0 402718720 0.0137911569 -0.0138429012 0.0002925207 245 9.7600000000 0.0333347432 0.0309480408 0.0409511514 0.0145225918 0.1897310000 958312633 0 402718720 0.0119638853 -0.0133858724 0.0000484098 246 9.8000000000 0.0330136195 0.0309564374 0.0409511514 0.0145271899 0.1893980000 958314641 0 402718720 0.0100947572 -0.0143991262 0.0000516494 247 9.8400000000 0.0331312492 0.0309652424 0.0409511514 0.0145337307 0.2005700000 958316649 0 402718720 0.0071677850 -0.0149829118 -0.0008030012 248 9.8800000000 0.0327140279 0.0309722939 0.0409511514 0.0145316646 0.1990950000 958318657 0 402718720 0.0039844662 -0.0178838093 -0.0011998366 249 9.9200000000 0.0326853953 0.0309791738 0.0409511514 0.0145336688 0.1856470000 958320665 0 402718720 0.0001810749 -0.0209132992 -0.0029690408 250 9.9600000000 0.0331750959 0.0309879575 0.0409511514 0.0145267306 0.1850970000 958322673 0 402718720 -0.0027751953 -0.0213830154 -0.0037423661 251 10.0000000000 0.0328958966 0.0309955589 0.0409511514 0.0145279328 0.1844520000 958324681 0 402718720 -0.0059693889 -0.0234569944 -0.0047623245 252 10.0400000000 0.0329510123 0.0310033186 0.0409511514 0.0145341149 0.1840710000 958326689 0 402718720 -0.0094350167 -0.0255823936 -0.0060813376 253 10.0800000000 0.0330340192 0.0310113451 0.0409511514 0.0145313693 0.1808700000 958328697 0 402718720 -0.0123333549 -0.0262965951 -0.0069846502 254 10.1200000000 0.0325166248 0.0310172714 0.0409511514 0.0145295569 0.1826920000 958330705 0 402718720 -0.0149848927 -0.0276210178 -0.0074396627 255 10.1600000000 0.0323527046 0.0310225084 0.0409511514 0.0145237183 0.1821340000 958332713 0 402718720 -0.0177024696 -0.0284910481 -0.0086105624 256 10.2000000000 0.0325425901 0.0310284462 0.0409511514 0.0145226300 0.1835160000 958334721 0 402718720 -0.0201391708 -0.0298491642 -0.0090478780 257 10.2400000000 0.0324412100 0.0310339433 0.0409511514 0.0146316951 0.1945400000 958336729 0 402718720 -0.0242647529 -0.0332726091 -0.0100865737 258 10.2800000000 0.0326559320 0.0310402301 0.0409511514 0.0146345638 0.1949010000 958389937 0 402718720 -0.0270878561 -0.0344219133 -0.0115738362 259 10.3200000000 0.0327092186 0.0310466741 0.0409511514 0.0146260750 0.1938080000 958391945 0 402718720 -0.0291682053 -0.0356096141 -0.0125101777 260 10.3600000000 0.0325793400 0.0310525690 0.0409511514 0.0146153444 0.1810360000 958393953 0 402718720 -0.0311131347 -0.0372660048 -0.0132607576 261 10.4000000000 0.0325842835 0.0310584376 0.0409511514 0.0145972742 0.1821440000 958395961 0 402718720 -0.0329679437 -0.0385345183 -0.0142490305 262 10.4400000000 0.0324356481 0.0310636941 0.0409511514 0.0145793805 0.1816060000 958397969 0 402718720 -0.0351018049 -0.0401013009 -0.0151690347 263 10.4800000000 0.0324242748 0.0310688674 0.0409511514 0.0145619176 0.1892070000 958399977 0 402718720 -0.0372195430 -0.0412646532 -0.0162842702 264 10.5200000000 0.0324131474 0.0310739594 0.0409511514 0.0145459289 0.1801530000 958401985 0 402718720 -0.0389460884 -0.0425536744 -0.0167493857 265 10.5600000000 0.0323241875 0.0310786772 0.0409511514 0.0145312034 0.2168710000 958403993 0 402718720 -0.0417480767 -0.0444416292 -0.0189795103 266 10.6000000000 0.0323128961 0.0310833172 0.0409511514 0.0145225371 0.1788980000 958406001 0 402718720 -0.0445294455 -0.0465232506 -0.0205870401 267 10.6400000000 0.0325828493 0.0310889334 0.0409511514 0.0145248185 0.1786920000 958408009 0 402718720 -0.0469126664 -0.0475867391 -0.0220704786 268 10.6800000000 0.0324790925 0.0310941206 0.0409511514 0.0145310580 0.1771890000 958410017 0 402718720 -0.0494087301 -0.0492322855 -0.0237472001 269 10.7200000000 0.0324641280 0.0310992135 0.0409511514 0.0145427898 0.1761610000 958412025 0 402718720 -0.0517765060 -0.0511166379 -0.0253418572 270 10.7600000000 0.0324712656 0.0311042952 0.0409511514 0.0145489668 0.2542670000 958414033 0 402718720 -0.0544072166 -0.0528916344 -0.0277970340 271 10.8000000000 0.0324916653 0.0311094146 0.0409511514 0.0145541818 0.2253280000 958416041 0 402718720 -0.0567859560 -0.0547500178 -0.0295612998 272 10.8400000000 0.0325696506 0.0311147832 0.0409511514 0.0145712382 0.2246540000 958418049 0 402718720 -0.0591632575 -0.0565225594 -0.0315818302 273 10.8800000000 0.0326046124 0.0311202404 0.0409511514 0.0145874134 0.2175560000 958420057 0 402718720 -0.0617287420 -0.0583899543 -0.0338343233 274 10.9200000000 0.0326896161 0.0311259681 0.0409511514 0.0145980824 0.1742700000 958422065 0 402718720 -0.0637018234 -0.0600209273 -0.0353031717 275 10.9600000000 0.0326154903 0.0311313845 0.0409511514 0.0146066743 0.1754450000 958424073 0 402718720 -0.0658018887 -0.0619961061 -0.0369730182 276 11.0000000000 0.0329461768 0.0311379598 0.0409511514 0.0146063477 0.1883970000 958426081 0 402718720 -0.0677264929 -0.0628766418 -0.0387867540 277 11.0400000000 0.0318294615 0.0311404562 0.0409511514 0.0149353618 0.1781290000 958428089 0 402718720 -0.0757839605 -0.0691167340 -0.0456292965 278 11.0800000000 0.0325771049 0.0311456240 0.0409511514 0.0149277585 0.1724460000 958430097 0 402718720 -0.0775788501 -0.0720105320 -0.0473690256 279 11.1200000000 0.0327710025 0.0311514498 0.0409511514 0.0149146305 0.1721520000 958432105 0 402718720 -0.0790736154 -0.0746311769 -0.0482554175 280 11.1600000000 0.0332404785 0.0311589106 0.0409511514 0.0149058084 0.1828430000 958434113 0 402718720 -0.0801671222 -0.0760827661 -0.0489230230 281 11.2000000000 0.0331585631 0.0311660268 0.0409511514 0.0149045640 0.1727840000 958436121 0 402718720 -0.0813981742 -0.0782403499 -0.0498714112 282 11.2400000000 0.0336103402 0.0311746946 0.0409511514 0.0149028355 0.1705620000 958438129 0 402718720 -0.0826702863 -0.0795443878 -0.0512439273 283 11.2800000000 0.0334370919 0.0311826889 0.0409511514 0.0148955778 0.1698310000 958440137 0 402718720 -0.0836506486 -0.0816440284 -0.0520589016 284 11.3200000000 0.0337505788 0.0311917308 0.0409511514 0.0149017466 0.1835440000 958442145 0 402718720 -0.0848010704 -0.0833190382 -0.0531340651 285 11.3600000000 0.0337665267 0.0312007651 0.0409511514 0.0148982586 0.1699600000 958444153 0 402718720 -0.0858829767 -0.0852373615 -0.0543128625 286 11.4000000000 0.0337601230 0.0312097139 0.0409511514 0.0148865927 0.1694080000 958446161 0 402718720 -0.0867373198 -0.0875825211 -0.0552194007 287 11.4400000000 0.0340823978 0.0312197233 0.0409511514 0.0148704088 0.1693720000 958448169 0 402718720 -0.0874437541 -0.0893965289 -0.0559678264 288 11.4800000000 0.0340308212 0.0312294840 0.0409511514 0.0148496940 0.1687790000 958450177 0 402718720 -0.0884869620 -0.0915698186 -0.0572187454 289 11.5200000000 0.0341331214 0.0312395312 0.0409511514 0.0148349132 0.1685340000 958452185 0 402718720 -0.0889072716 -0.0940427557 -0.0577972867 290 11.5600000000 0.0347281285 0.0312515609 0.0409511514 0.0148203187 0.1795640000 958454193 0 402718720 -0.0895009190 -0.0956336558 -0.0584475398 291 11.6000000000 0.0347240306 0.0312634938 0.0409511514 0.0147981904 0.1679710000 958456201 0 402718720 -0.0898670331 -0.0973730758 -0.0587706231 292 11.6400000000 0.0345981307 0.0312749137 0.0409511514 0.0147735593 0.1676190000 958458209 0 402718720 -0.0906121284 -0.0993717834 -0.0599857084 293 11.6800000000 0.0347130597 0.0312866480 0.0409511514 0.0147482943 0.1921270000 958460217 0 402718720 -0.0909099504 -0.1013577357 -0.0603491478 294 11.7200000000 0.0351286083 0.0312997159 0.0409511514 0.0147244533 0.1686720000 958462225 0 402718720 -0.0910908431 -0.1027993783 -0.0610787123 295 11.7600000000 0.0341434479 0.0313093557 0.0409511514 0.0147072520 0.1800940000 958464233 0 402718720 -0.0911878869 -0.1066480651 -0.0611766614 296 11.8000000000 0.0346592963 0.0313206731 0.0409511514 0.0146875896 0.1683410000 958466241 0 402718720 -0.0911850184 -0.1093352064 -0.0614505336 297 11.8400000000 0.0353750698 0.0313343242 0.0409511514 0.0146735354 0.1657670000 958468249 0 402718720 -0.0915356949 -0.1110413298 -0.0623185448 298 11.8800000000 0.0349936634 0.0313466039 0.0409511514 0.0147070412 0.1673350000 958470257 0 402718720 -0.0925274938 -0.1143554971 -0.0641703308 299 11.9200000000 0.0355099812 0.0313605282 0.0409511514 0.0147099598 0.1671690000 958472265 0 402718720 -0.0933167636 -0.1164894029 -0.0654986352 300 11.9600000000 0.0356928706 0.0313749694 0.0409511514 0.0147227313 0.1769230000 958474273 0 402718720 -0.0936770290 -0.1185352802 -0.0660993904 301 12.0000000000 0.0357875079 0.0313896290 0.0409511514 0.0147286277 0.1647420000 958476281 0 402718720 -0.0943570286 -0.1205422953 -0.0672232434 302 12.0400000000 0.0357235298 0.0314039796 0.0409511514 0.0147646256 0.1886290000 958478289 0 402718720 -0.0962163582 -0.1236307472 -0.0703282058 303 12.0800000000 0.0360556804 0.0314193318 0.0409511514 0.0147501605 0.1643280000 958480297 0 402718720 -0.0976491123 -0.1256583780 -0.0724237114 304 12.1200000000 0.0361943059 0.0314350389 0.0409511514 0.0147378846 0.1635240000 958482305 0 402718720 -0.0991183221 -0.1276398897 -0.0748715773 305 12.1600000000 0.0366023928 0.0314519811 0.0409511514 0.0147309550 0.1627730000 958484313 0 402718720 -0.1003866568 -0.1291714758 -0.0768504441 306 12.2000000000 0.0364308842 0.0314682520 0.0409511514 0.0147314273 0.1618950000 958486321 0 402718720 -0.1011950895 -0.1311591566 -0.0784476921 307 12.2400000000 0.0366946086 0.0314852760 0.0409511514 0.0147442307 0.1709990000 958488329 0 402718720 -0.1024978533 -0.1331059039 -0.0804884061 308 12.2800000000 0.0369370207 0.0315029764 0.0409511514 0.0147604247 0.1580730000 958490337 0 402718720 -0.1040286794 -0.1349315047 -0.0830487832 309 12.3200000000 0.0369439311 0.0315205847 0.0409511514 0.0147592722 0.1570650000 958492345 0 402718720 -0.1056732163 -0.1366790384 -0.0860403925 310 12.3600000000 0.0370818973 0.0315385244 0.0409511514 0.0147592682 0.1560720000 958494353 0 402718720 -0.1073150858 -0.1384143382 -0.0891353786 311 12.4000000000 0.0373325944 0.0315571549 0.0409511514 0.0147589031 0.1689660000 958496361 0 402718720 -0.1085986868 -0.1397796869 -0.0919703469 312 12.4400000000 0.0374219194 0.0315759522 0.0409511514 0.0147519664 0.1653890000 958498369 0 402718720 -0.1098796725 -0.1409868151 -0.0946652964 313 12.4800000000 0.0374327749 0.0315946641 0.0409511514 0.0147438626 0.1549070000 958500377 0 402718720 -0.1111575738 -0.1423728168 -0.0971380994 314 12.5200000000 0.0375022963 0.0316134782 0.0409511514 0.0147424690 0.1527610000 958502385 0 402718720 -0.1121964753 -0.1437425166 -0.0993295386 315 12.5600000000 0.0377090834 0.0316328293 0.0409511514 0.0147446512 0.1520290000 958504393 0 402718720 -0.1135449037 -0.1448722184 -0.1018502042 316 12.6000000000 0.0377088860 0.0316520574 0.0409511514 0.0147426081 0.1511070000 958506401 0 402718720 -0.1148100942 -0.1460154802 -0.1043764725 317 12.6400000000 0.0378689133 0.0316716689 0.0409511514 0.0147321166 0.1505470000 958508409 0 402718720 -0.1160498112 -0.1469556391 -0.1069794670 318 12.6800000000 0.0379234403 0.0316913285 0.0409511514 0.0147176863 0.1494740000 958510417 0 402718720 -0.1173365265 -0.1477979273 -0.1094267592 319 12.7200000000 0.0380135737 0.0317111475 0.0409511514 0.0147336491 0.1477700000 958512425 0 402718720 -0.1193725541 -0.1492122412 -0.1140440330 320 12.7600000000 0.0379770808 0.0317307285 0.0409511514 0.0147227398 0.1469340000 958514433 0 402718720 -0.1204652488 -0.1500681639 -0.1162193343 321 12.8000000000 0.0382345095 0.0317509895 0.0409511514 0.0147107646 0.1459990000 958516441 0 402718720 -0.1217436716 -0.1505319923 -0.1185874417 322 12.8400000000 0.0381783992 0.0317709504 0.0409511514 0.0146967757 0.1554720000 958518449 0 402718720 -0.1231055483 -0.1511444151 -0.1207046136 323 12.8800000000 0.0383534729 0.0317913298 0.0409511514 0.0146830184 0.1584590000 958520457 0 402718720 -0.1241454035 -0.1516019255 -0.1223886609 324 12.9200000000 0.0386598483 0.0318125289 0.0409511514 0.0146696981 0.1567290000 958522465 0 402718720 -0.1254376918 -0.1518010944 -0.1245004758 325 12.9600000000 0.0387916006 0.0318340030 0.0409511514 0.0146500212 0.1432480000 958524473 0 402718720 -0.1266459972 -0.1516593695 -0.1264407337 326 13.0000000000 0.0387867913 0.0318553305 0.0409511514 0.0146304674 0.1427160000 958526481 0 402718720 -0.1280477345 -0.1515205204 -0.1285407096 327 13.0400000000 0.0392287709 0.0318778793 0.0409511514 0.0146108145 0.1415370000 958528489 0 402718720 -0.1293317527 -0.1507915705 -0.1302550882 328 13.0800000000 0.0394583978 0.0319009906 0.0409511514 0.0145906922 0.1412400000 958530497 0 402718720 -0.1307100952 -0.1498779356 -0.1322386861 329 13.1200000000 0.0398703367 0.0319252136 0.0409511514 0.0145731027 0.1421480000 958532505 0 402718720 -0.1319415569 -0.1485348046 -0.1338698864 330 13.1600000000 0.0400666147 0.0319498845 0.0409511514 0.0145558536 0.1421200000 958534513 0 402718720 -0.1332517266 -0.1469307840 -0.1353844553 331 13.2000000000 0.0402340814 0.0319749123 0.0409511514 0.0145402808 0.1396670000 958536521 0 402718720 -0.1344330460 -0.1450415403 -0.1370025724 332 13.2400000000 0.0404675379 0.0320004925 0.0409511514 0.0145232886 0.1514590000 958538529 0 402718720 -0.1356754899 -0.1428649575 -0.1381219774 333 13.2800000000 0.0406585336 0.0320264926 0.0409511514 0.0145108797 0.1417670000 958540537 0 402718720 -0.1369720995 -0.1404671818 -0.1396219879 334 13.3200000000 0.0420191325 0.0320564107 0.0420191325 0.0145357228 0.1411090000 958542545 0 402718720 -0.1391759366 -0.1362736970 -0.1418163627 335 13.3600000000 0.0413110852 0.0320840366 0.0420191325 0.0145237240 0.1408000000 958544553 0 402718720 -0.1401513219 -0.1326393932 -0.1426016986 336 13.4000000000 0.0407424793 0.0321098057 0.0420191325 0.0145121575 0.1408680000 958546561 0 402718720 -0.1411899328 -0.1291733086 -0.1433138251 337 13.4400000000 0.0398242511 0.0321326973 0.0420191325 0.0145013454 0.1398450000 958548569 0 402718720 -0.1421215534 -0.1257690489 -0.1438686848 338 13.4800000000 0.0389983207 0.0321530098 0.0420191325 0.0145027248 0.1388330000 958550577 0 402718720 -0.1429375410 -0.1227662489 -0.1443679333 339 13.5200000000 0.0385081135 0.0321717564 0.0420191325 0.0145136073 0.1385830000 958552585 0 402718720 -0.1440033913 -0.1196506545 -0.1448513716 340 13.5600000000 0.0380573869 0.0321890670 0.0420191325 0.0145153352 0.1512570000 958554593 0 402718720 -0.1448171735 -0.1169082448 -0.1447498053 341 13.6000000000 0.0377742052 0.0322054458 0.0420191325 0.0145111499 0.1513540000 958556601 0 402718720 -0.1456283480 -0.1140002012 -0.1448198259 342 13.6400000000 0.0376359746 0.0322213245 0.0420191325 0.0145053532 0.1641020000 958558609 0 402718720 -0.1468375623 -0.1108533219 -0.1454230547 343 13.6800000000 0.0372275598 0.0322359199 0.0420191325 0.0145136976 0.1392170000 958560617 0 402718720 -0.1477545649 -0.1081065536 -0.1455596536 344 13.7200000000 0.0370909050 0.0322500333 0.0420191325 0.0145266921 0.1389750000 958562625 0 402718720 -0.1484947056 -0.1051818728 -0.1457294971 345 13.7600000000 0.0371566601 0.0322642554 0.0420191325 0.0146780125 0.1389620000 958564633 0 402718720 -0.1501189768 -0.0996555313 -0.1457929462 346 13.8000000000 0.0378524363 0.0322804062 0.0420191325 0.0146806845 0.1384490000 958566641 0 402718720 -0.1507741660 -0.0979351103 -0.1457166970 347 13.8400000000 0.0368620045 0.0322936096 0.0420191325 0.0146878423 0.1389550000 958568649 0 402718720 -0.1516519338 -0.0943128094 -0.1461084038 348 13.8800000000 0.0372233130 0.0323077754 0.0420191325 0.0146717227 0.1379280000 958570657 0 402718720 -0.1524920762 -0.0917147473 -0.1463270485 349 13.9200000000 0.0362866707 0.0323191763 0.0420191325 0.0146521896 0.1442350000 958572665 0 402718720 -0.1532902420 -0.0871614665 -0.1465657204 350 13.9600000000 0.0367903858 0.0323319512 0.0420191325 0.0146357999 0.1419150000 958574673 0 402718720 -0.1540961415 -0.0851425976 -0.1467652023 351 14.0000000000 0.0360812508 0.0323426329 0.0420191325 0.0146355631 0.1452700000 958576681 0 402718720 -0.1547882855 -0.0811194032 -0.1467100680 352 14.0400000000 0.0366809964 0.0323549578 0.0420191325 0.0146305539 0.1502300000 958578689 0 402718720 -0.1555397660 -0.0787580982 -0.1466474682 353 14.0800000000 0.0359083302 0.0323650240 0.0420191325 0.0146432157 0.1446140000 958580697 0 402718720 -0.1561826468 -0.0745015591 -0.1463140249 354 14.1200000000 0.0365399271 0.0323768176 0.0420191325 0.0146670261 0.1399660000 958582705 0 402718720 -0.1567135602 -0.0720820203 -0.1460081935 355 14.1600000000 0.0364746153 0.0323883607 0.0420191325 0.0146894795 0.1403480000 958584713 0 402718720 -0.1572261304 -0.0691136867 -0.1456155479 356 14.2000000000 0.0359138362 0.0323982637 0.0420191325 0.0147008036 0.1466650000 958586721 0 402718720 -0.1577106267 -0.0651392937 -0.1454084367 357 14.2400000000 0.0365037471 0.0324097636 0.0420191325 0.0147019904 0.1427570000 958588729 0 402718720 -0.1582020223 -0.0628040656 -0.1449634880 358 14.2800000000 0.0363676250 0.0324208191 0.0420191325 0.0147067672 0.1421570000 958590737 0 402718720 -0.1586349756 -0.0601317771 -0.1442902088 359 14.3200000000 0.0357206352 0.0324300108 0.0420191325 0.0147153307 0.1822400000 958592745 0 402718720 -0.1588752270 -0.0564439185 -0.1435488611 360 14.3600000000 0.0362049825 0.0324404968 0.0420191325 0.0147150741 0.1432710000 958594753 0 402718720 -0.1591287553 -0.0540090352 -0.1431543976 361 14.4000000000 0.0355256870 0.0324490431 0.0420191325 0.0147127832 0.1699240000 958596761 0 402718720 -0.1591957957 -0.0504472926 -0.1421371847 362 14.4400000000 0.0358215794 0.0324583595 0.0420191325 0.0147161888 0.1444400000 958598769 0 402718720 -0.1593305320 -0.0482388772 -0.1415034086 363 14.4800000000 0.0357239805 0.0324673557 0.0420191325 0.0147185188 0.1446700000 958600777 0 402718720 -0.1593105346 -0.0461857133 -0.1407051086 364 14.5200000000 0.0357907750 0.0324764859 0.0420191325 0.0147213108 0.1455170000 958602785 0 402718720 -0.1594006866 -0.0434136800 -0.1401018053 365 14.5600000000 0.0356921442 0.0324852960 0.0420191325 0.0147273957 0.1446320000 958604793 0 402718720 -0.1593334526 -0.0414613746 -0.1393010020 366 14.6000000000 0.0353784151 0.0324932007 0.0420191325 0.0148212092 0.1504230000 958606801 0 402718720 -0.1584566534 -0.0349042900 -0.1372366101 367 14.6400000000 0.0355656259 0.0325015724 0.0420191325 0.0148342274 0.1477760000 958608809 0 402718720 -0.1581435502 -0.0322833583 -0.1365279853 368 14.6800000000 0.0355842970 0.0325099494 0.0420191325 0.0148452467 0.1477780000 958610817 0 402718720 -0.1573242247 -0.0294833891 -0.1348521709 369 14.7200000000 0.0351752043 0.0325171723 0.0420191325 0.0148682089 0.1545350000 958612825 0 402718720 -0.1555459946 -0.0217974633 -0.1317543834 370 14.7600000000 0.0356954075 0.0325257621 0.0420191325 0.0148737455 0.1519730000 958614833 0 402718720 -0.1543617994 -0.0192265734 -0.1297124177 371 14.8000000000 0.0358684324 0.0325347720 0.0420191325 0.0148754717 0.1534940000 958616841 0 402718720 -0.1531275809 -0.0169357378 -0.1275095791 372 14.8400000000 0.0359655768 0.0325439946 0.0420191325 0.0148743477 0.1542560000 958618849 0 402718720 -0.1520116180 -0.0149213066 -0.1250697821 373 14.8800000000 0.0361465625 0.0325536529 0.0420191325 0.0148698189 0.1544600000 958620857 0 402718720 -0.1505506784 -0.0121570332 -0.1223917454 374 14.9200000000 0.0348096788 0.0325596851 0.0420191325 0.0148631166 0.1717940000 958622865 0 402718720 -0.1487175375 -0.0074052415 -0.1194800511 375 14.9600000000 0.0358599201 0.0325684857 0.0420191325 0.0148578080 0.1578420000 958624873 0 402718720 -0.1474706829 -0.0058233142 -0.1171286628 376 15.0000000000 0.0359139740 0.0325773833 0.0420191325 0.0148664621 0.1581430000 958626881 0 402718720 -0.1458866447 -0.0035772203 -0.1145648286 377 15.0400000000 0.0359175354 0.0325862431 0.0420191325 0.0148878081 0.1698480000 958628889 0 402718720 -0.1439951509 -0.0013000122 -0.1119391620 378 15.0800000000 0.0360418223 0.0325953849 0.0420191325 0.0149002221 0.1716570000 958630897 0 402718720 -0.1420830488 0.0014365560 -0.1097693145 379 15.1200000000 0.0359653495 0.0326042766 0.0420191325 0.0148976079 0.1603250000 958632905 0 402718720 -0.1399296671 0.0039972486 -0.1073257774 380 15.1600000000 0.0356147699 0.0326121989 0.0420191325 0.0149050556 0.1610680000 958634913 0 402718720 -0.1377882957 0.0063159862 -0.1048419252 381 15.2000000000 0.0352489129 0.0326191194 0.0420191325 0.0149113516 0.1619690000 958636921 0 402718720 -0.1357648373 0.0083692446 -0.1028816104 382 15.2400000000 0.0350937769 0.0326255976 0.0420191325 0.0149083074 0.1623330000 958638929 0 402718720 -0.1336019188 0.0101271085 -0.1007319316 383 15.2800000000 0.0350646339 0.0326319658 0.0420191325 0.0149054565 0.1639960000 958640937 0 402718720 -0.1315840781 0.0117656905 -0.0987336412 384 15.3200000000 0.0348866545 0.0326378374 0.0420191325 0.0149247693 0.1745670000 958642945 0 402718720 -0.1294898540 0.0132146515 -0.0966834947 385 15.3600000000 0.0346983559 0.0326431894 0.0420191325 0.0149291724 0.1655780000 958644953 0 402718720 -0.1270516962 0.0139503321 -0.0945431963 386 15.4000000000 0.0349740796 0.0326492280 0.0420191325 0.0149300749 0.1662430000 958646961 0 402718720 -0.1247947812 0.0157708693 -0.0926436484 387 15.4400000000 0.0347674452 0.0326547014 0.0420191325 0.0149319014 0.1665190000 958648969 0 402718720 -0.1220988557 0.0167799760 -0.0900106058 388 15.4800000000 0.0346671268 0.0326598881 0.0420191325 0.0149424039 0.1664410000 958650977 0 402718720 -0.1192071512 0.0176098924 -0.0875160694 389 15.5200000000 0.0348225459 0.0326654476 0.0420191325 0.0149472913 0.1785070000 958652985 0 402718720 -0.1169266775 0.0190744307 -0.0856980309 390 15.5600000000 0.0346349962 0.0326704978 0.0420191325 0.0149410664 0.2091350000 958654993 0 402718720 -0.1139385253 0.0195063204 -0.0825950578 391 15.6000000000 0.0346534811 0.0326755693 0.0420191325 0.0149400477 0.2140230000 958657001 0 402718720 -0.1115242913 0.0202040542 -0.0803569555 392 15.6400000000 0.0344594903 0.0326801201 0.0420191325 0.0149405529 0.2152150000 958659009 0 402718720 -0.1084919944 0.0201569460 -0.0776250660 393 15.6800000000 0.0344882682 0.0326847210 0.0420191325 0.0149401723 0.2160530000 958661017 0 402718720 -0.1059378535 0.0205753408 -0.0755206048 394 15.7200000000 0.0346693657 0.0326897582 0.0420191325 0.0149450814 0.1872370000 958663025 0 402718720 -0.1031407565 0.0217998382 -0.0736226887 395 15.7600000000 0.0344250873 0.0326941514 0.0420191325 0.0149507594 0.1714470000 958665033 0 402718720 -0.1003936902 0.0220462494 -0.0716966316 396 15.8000000000 0.0345461443 0.0326988282 0.0420191325 0.0149456132 0.1725960000 958667041 0 402718720 -0.0974122360 0.0227322560 -0.0699573085 397 15.8400000000 0.0347000211 0.0327038690 0.0420191325 0.0149371942 0.1716130000 958669049 0 402718720 -0.0941145867 0.0240565781 -0.0676304325 398 15.8800000000 0.0346360356 0.0327087237 0.0420191325 0.0149322160 0.1756250000 958671057 0 402718720 -0.0925136879 0.0248651765 -0.0676747188 399 15.9200000000 0.0346906446 0.0327136909 0.0420191325 0.0149281100 0.1767230000 958673065 0 402718720 -0.0893209279 0.0256754737 -0.0656759739 400 15.9600000000 0.0344354287 0.0327179952 0.0420191325 0.0149235432 0.1772530000 958675073 0 402718720 -0.0874390975 0.0252083186 -0.0648920760 401 16.0000000000 0.0344786905 0.0327223860 0.0420191325 0.0149119444 0.1799290000 958677081 0 402718720 -0.0855059549 0.0245245099 -0.0635263324 402 16.0400000000 0.0346398465 0.0327271558 0.0420191325 0.0149046910 0.1807360000 958679089 0 402718720 -0.0834514648 0.0245863423 -0.0623569340 403 16.0800000000 0.0342045985 0.0327308219 0.0420191325 0.0149046092 0.1815080000 958681097 0 402718720 -0.0818548948 0.0233153198 -0.0615117624 404 16.1200000000 0.0344903506 0.0327351772 0.0420191325 0.0149122622 0.1820600000 958683105 0 402718720 -0.0800582096 0.0230615810 -0.0608540215 405 16.1600000000 0.0348163992 0.0327403160 0.0420191325 0.0149152994 0.1827880000 958685113 0 402718720 -0.0776885822 0.0241111666 -0.0599593520 406 16.2000000000 0.0346230417 0.0327449532 0.0420191325 0.0149125973 0.1835070000 958687121 0 402718720 -0.0753634200 0.0245446861 -0.0585807227 407 16.2400000000 0.0344987623 0.0327492624 0.0420191325 0.0149192972 0.1842920000 958689129 0 402718720 -0.0725176707 0.0247363895 -0.0571602210 408 16.2800000000 0.0345329642 0.0327536342 0.0420191325 0.0149243109 0.1851420000 958691137 0 402718720 -0.0698496103 0.0250619482 -0.0561101176 409 16.3200000000 0.0345210619 0.0327579555 0.0420191325 0.0149161563 0.1997590000 958693145 0 402718720 -0.0667451695 0.0252691340 -0.0543165766 410 16.3600000000 0.0343054682 0.0327617299 0.0420191325 0.0149189840 0.1974890000 958695153 0 402718720 -0.0636384636 0.0248928331 -0.0524682514 411 16.3999999990 0.0340080038 0.0327647622 0.0420191325 0.0149289137 0.1855470000 958697161 0 402718720 -0.0605029836 0.0235699266 -0.0506364554 412 16.4400000000 0.0343074426 0.0327685066 0.0420191325 0.0149328959 0.1835460000 958699169 0 402718720 -0.0584104583 0.0231904313 -0.0494955145 413 16.4800000000 0.0340101831 0.0327715131 0.0420191325 0.0149381962 0.1977290000 958701177 0 402718720 -0.0556160919 0.0219285432 -0.0474807732 414 16.5200000000 0.0343101956 0.0327752297 0.0420191325 0.0149322900 0.1890930000 958703185 0 402718720 -0.0534583479 0.0217703283 -0.0465326346 415 16.5599999990 0.0345164910 0.0327794255 0.0420191325 0.0149231506 0.2009440000 958705193 0 402718720 -0.0513340123 0.0221352112 -0.0456843898 416 16.6000000000 0.0344858058 0.0327835274 0.0420191325 0.0149111023 0.1906170000 958707201 0 402718720 -0.0498716421 0.0223879796 -0.0450826026 417 16.6400000000 0.0345261469 0.0327877063 0.0420191325 0.0149026564 0.1883030000 958709209 0 402718720 -0.0476904213 0.0228854772 -0.0440647826 418 16.6800000000 0.0342244953 0.0327911436 0.0420191325 0.0148933853 0.2052350000 958711217 0 402718720 -0.0468059629 0.0221505482 -0.0437963828 419 16.7199999990 0.0342323333 0.0327945832 0.0420191325 0.0148872472 0.1877240000 958713225 0 402718720 -0.0446607657 0.0214085542 -0.0427135713 420 16.7600000000 0.0340072252 0.0327974705 0.0420191325 0.0148850482 0.2133220000 958715233 0 402718720 -0.0428707451 0.0200887155 -0.0411887094 421 16.8000000000 0.0338682756 0.0328000139 0.0420191325 0.0148848021 0.1928260000 958717241 0 402718720 -0.0407996215 0.0185227115 -0.0395320319 422 16.8400000000 0.0344005264 0.0328038066 0.0420191325 0.0148800147 0.1932840000 958719249 0 402718720 -0.0391486101 0.0185824186 -0.0387754589 423 16.8799999990 0.0341055393 0.0328068840 0.0420191325 0.0148758573 0.1936270000 958721257 0 402718720 -0.0371454619 0.0178543478 -0.0376725011 424 16.9200000000 0.0339903049 0.0328096751 0.0420191325 0.0148667650 0.1939380000 958723265 0 402718720 -0.0346012414 0.0167469084 -0.0364579931 425 16.9600000000 0.0341503173 0.0328128296 0.0420191325 0.0148730920 0.2071690000 958725273 0 402718720 -0.0321833082 0.0164682716 -0.0342916362 426 17.0000000000 0.0333354659 0.0328140564 0.0420191325 0.0148677922 0.1942840000 958727281 0 402718720 -0.0298213307 0.0133702150 -0.0326619297 427 17.0400000000 0.0337765329 0.0328163104 0.0420191325 0.0148635771 0.1948410000 958729289 0 402718720 -0.0269784834 0.0119195664 -0.0317207463 428 17.0800000000 0.0340105705 0.0328191008 0.0420191325 0.0148582740 0.1947750000 958731297 0 402718720 -0.0241664834 0.0115027241 -0.0303323492 429 17.1200000000 0.0339489356 0.0328217344 0.0420191325 0.0148520256 0.1936510000 958733305 0 402718720 -0.0217193346 0.0109674018 -0.0292136706 430 17.1600000000 0.0345382057 0.0328257262 0.0420191325 0.0148440104 0.1935330000 958735313 0 402718720 -0.0193438791 0.0127621051 -0.0286726616 431 17.2000000000 0.0341154188 0.0328287185 0.0420191325 0.0148376975 0.1935900000 958737321 0 402718720 -0.0169042423 0.0129944272 -0.0283030830 432 17.2400000000 0.0330314934 0.0328291879 0.0420191325 0.0148376295 0.1906520000 958739329 0 402718720 -0.0143555952 0.0093527464 -0.0268936027 433 17.2800000000 0.0328991339 0.0328293495 0.0420191325 0.0148496532 0.2062400000 958741337 0 402718720 -0.0128824413 0.0054358449 -0.0250668153 434 17.3200000000 0.0332217105 0.0328302535 0.0420191325 0.0148541638 0.2059530000 958743345 0 402718720 -0.0105013996 0.0028962090 -0.0233723745 435 17.3600000000 0.0330000594 0.0328306439 0.0420191325 0.0148585669 0.2062930000 958745353 0 402718720 -0.0082486467 -0.0002998885 -0.0223164782 436 17.4000000000 0.0332296379 0.0328315590 0.0420191325 0.0148574495 0.1953670000 958747361 0 402718720 -0.0068317028 -0.0022568877 -0.0211586859 437 17.4400000000 0.0334262066 0.0328329197 0.0420191325 0.0148532654 0.1951210000 958749369 0 402718720 -0.0061251861 -0.0031739459 -0.0207696315 438 17.4800000000 0.0334521867 0.0328343336 0.0420191325 0.0148682308 0.1947010000 958751377 0 402718720 -0.0058548758 -0.0035809155 -0.0195420943 439 17.5200000000 0.0332367867 0.0328352504 0.0420191325 0.0148772122 0.1937700000 958753385 0 402718720 -0.0061777695 -0.0044218926 -0.0187772270 440 17.5600000000 0.0332515277 0.0328361964 0.0420191325 0.0148809124 0.2020240000 958755393 0 402718720 -0.0075042131 -0.0049118083 -0.0184510276 441 17.6000000000 0.0331422910 0.0328368905 0.0420191325 0.0148933008 0.1950100000 958757401 0 402718720 -0.0088315886 -0.0054645115 -0.0173459575 442 17.6400000000 0.0327176116 0.0328366207 0.0420191325 0.0149860376 0.1916920000 958759409 0 402718720 -0.0162299294 -0.0080285184 -0.0174212474 443 17.6800000000 0.0332054980 0.0328374533 0.0420191325 0.0149950117 0.1945630000 958761417 0 402718720 -0.0210314058 -0.0081487633 -0.0174763910 444 17.7200000000 0.0330938399 0.0328380308 0.0420191325 0.0149999777 0.2113220000 958763425 0 402718720 -0.0240690261 -0.0082625942 -0.0166793969 445 17.7600000000 0.0321574174 0.0328365013 0.0420191325 0.0150049079 0.1944750000 958765433 0 402718720 -0.0262437295 -0.0114768958 -0.0158508979 446 17.8000000000 0.0323572122 0.0328354267 0.0420191325 0.0150135093 0.1940190000 958767441 0 402718720 -0.0281452313 -0.0137318075 -0.0149410143 447 17.8400000000 0.0317805372 0.0328330668 0.0420191325 0.0150118868 0.1907750000 958769449 0 402718720 -0.0278722551 -0.0175779238 -0.0131679438 448 17.8800000000 0.0318828076 0.0328309456 0.0420191325 0.0150033207 0.1925350000 958771457 0 402718720 -0.0272124503 -0.0205112752 -0.0118751228 449 17.9200000000 0.0319137909 0.0328289030 0.0420191325 0.0149944498 0.1911790000 958773465 0 402718720 -0.0284227468 -0.0233764835 -0.0097736418 450 17.9600000000 0.0317155197 0.0328264288 0.0420191325 0.0149816198 0.1921540000 958775473 0 402718720 -0.0281445645 -0.0264662076 -0.0080281021 451 18.0000000000 0.0320101306 0.0328246188 0.0420191325 0.0149739852 0.1903020000 958777481 0 402718720 -0.0278207734 -0.0274885930 -0.0050153392 452 18.0400000000 0.0316761136 0.0328220779 0.0420191325 0.0149680859 0.1900350000 958779489 0 402718720 -0.0275418870 -0.0294426847 -0.0019142552 453 18.0800000000 0.0316547416 0.0328195010 0.0420191325 0.0149577543 0.1898640000 958781497 0 402718720 -0.0267418511 -0.0309040714 0.0013501509 454 18.1200000000 0.0316815749 0.0328169945 0.0420191325 0.0149456790 0.1997100000 958783505 0 402718720 -0.0261838418 -0.0315115638 0.0053294408 455 18.1600000000 0.0312654749 0.0328135846 0.0420191325 0.0149305888 0.1887760000 958785513 0 402718720 -0.0248854663 -0.0327067226 0.0092442753 456 18.2000000000 0.0312054884 0.0328100581 0.0420191325 0.0149215212 0.1899310000 958787521 0 402718720 -0.0237242188 -0.0337635688 0.0142635722 457 18.2400000000 0.0309419315 0.0328059703 0.0420191325 0.0149151453 0.1937440000 958789529 0 402718720 -0.0220525619 -0.0303692967 0.0186789222 458 18.2800000000 0.0308671743 0.0328017371 0.0420191325 0.0149040061 0.1921070000 958791537 0 402718720 -0.0208842251 -0.0295463409 0.0248987395 459 18.3200000000 0.0307401996 0.0327972457 0.0420191325 0.0148890362 0.1906900000 958793545 0 402718720 -0.0185851622 -0.0292555988 0.0310184509 460 18.3600000000 0.0307314266 0.0327927548 0.0420191325 0.0148746543 0.1901520000 958795553 0 402718720 -0.0170995053 -0.0255615618 0.0374845490 461 18.4000000000 0.0306002442 0.0327879988 0.0420191325 0.0148596592 0.1893990000 958797561 0 402718720 -0.0163087714 -0.0256349649 0.0447243974 462 18.4400000000 0.0305585191 0.0327831731 0.0420191325 0.0148441362 0.1885150000 958799569 0 402718720 -0.0128123369 -0.0250031035 0.0523874499 463 18.4800000000 0.0305908974 0.0327784382 0.0420191325 0.0148312649 0.1844440000 958801577 0 402718720 -0.0120456060 -0.0227420982 0.0604280047 464 18.5200000000 0.0306887515 0.0327739345 0.0420191325 0.0148181262 0.1844370000 958803585 0 402718720 -0.0109479139 -0.0207341667 0.0695258901 465 18.5600000000 0.0304710567 0.0327689821 0.0420191325 0.0148063544 0.1858160000 958805593 0 402718720 -0.0068229889 -0.0139624346 0.0889882296 466 18.6000000000 0.0304625444 0.0327640327 0.0420191325 0.0147915898 0.1839220000 958807601 0 402718720 -0.0041118348 -0.0100454791 0.0993068144 467 18.6400000000 0.0303368922 0.0327588354 0.0420191325 0.0147765002 0.1835490000 958809609 0 402718720 -0.0012972474 -0.0089304876 0.1102500036 468 18.6800000000 0.0302514769 0.0327534778 0.0420191325 0.0147630067 0.1836810000 958811617 0 402718720 0.0006538732 -0.0040568449 0.1213142052 469 18.7200000000 0.0301281549 0.0327478801 0.0420191325 0.0147520312 0.1833140000 958813625 0 402718720 0.0022473810 -0.0006177977 0.1328154653 470 18.7600000000 0.0299443230 0.0327419151 0.0420191325 0.0147453079 0.1936150000 958815633 0 402718720 0.0042686560 0.0047032246 0.1445531100 471 18.8000000000 0.0297528207 0.0327355688 0.0420191325 0.0147381664 0.1844210000 958817641 0 402718720 0.0056985556 0.0107015893 0.1568676084 472 18.8400000000 0.0295919366 0.0327289085 0.0420191325 0.0147232449 0.1811080000 958819649 0 402718720 0.0088285357 0.0170656964 0.1686053574 473 18.8800000000 0.0291682612 0.0327213807 0.0420191325 0.0147078952 0.1840950000 958821657 0 402718720 0.0113922963 0.0249978974 0.1804223806 474 18.9200000000 0.0293489248 0.0327142659 0.0420191325 0.0146961322 0.1800870000 958823665 0 402718720 0.0148185529 0.0310742650 0.1915981025 475 18.9600000000 0.0291556455 0.0327067740 0.0420191325 0.0146880477 0.1796660000 958825673 0 402718720 0.0184402168 0.0361165702 0.2042069882 476 19.0000000000 0.0289599393 0.0326989025 0.0420191325 0.0146783581 0.1809910000 958827681 0 402718720 0.0216874350 0.0390686952 0.2161969692 477 19.0400000000 0.0286224466 0.0326903565 0.0420191325 0.0146653790 0.1832490000 958829689 0 402718720 0.0233389027 0.0461522453 0.2279076427 478 19.0800000000 0.0284289867 0.0326814415 0.0420191325 0.0146525651 0.1804170000 958831697 0 402718720 0.0269033033 0.0536925979 0.2389961928 479 19.1200000000 0.0285590366 0.0326728352 0.0420191325 0.0146419543 0.1795090000 958833705 0 402718720 0.0304900855 0.0568542592 0.2507748306 480 19.1600000000 0.0284170341 0.0326639690 0.0420191325 0.0146332188 0.1909590000 958835713 0 402718720 0.0341364481 0.0617877878 0.2619092166 481 19.2000000000 0.0279178061 0.0326541017 0.0420191325 0.0146197075 0.1844120000 958837721 0 402718720 0.0351010002 0.0723550990 0.2720478475 482 19.2400000000 0.0280113369 0.0326444694 0.0420191325 0.0146177663 0.1795020000 958839729 0 402718720 0.0389067233 0.0765786618 0.2835718989 483 19.2800000000 0.0277633667 0.0326343636 0.0420191325 0.0146194095 0.1824020000 958841737 0 402718720 0.0413581617 0.0774932727 0.2950884700 484 19.3200000000 0.0276177209 0.0326239986 0.0420191325 0.0146176493 0.1815910000 958843745 0 402718720 0.0447860807 0.0789223760 0.3062450290 485 19.3600000000 0.0275931526 0.0326136257 0.0420191325 0.0146050834 0.1812610000 958845753 0 402718720 0.0468990803 0.0825545713 0.3173658252 486 19.4000000000 0.0272687692 0.0326026281 0.0420191325 0.0145900361 0.1847690000 958847761 0 402718720 0.0500637852 0.0897860974 0.3273871243 487 19.4400000000 0.0273856409 0.0325919156 0.0420191325 0.0145752176 0.1806230000 958849769 0 402718720 0.0504231565 0.0937088951 0.3390577435 488 19.4800000000 0.0272154268 0.0325808982 0.0420191325 0.0145605210 0.1809250000 958851777 0 402718720 0.0524044074 0.0965778306 0.3500725031 489 19.5200000000 0.0269059259 0.0325692929 0.0420191325 0.0145461857 0.1994370000 958853785 0 402718720 0.0532114916 0.1045840383 0.3605473042 490 19.5600000000 0.0270408522 0.0325580104 0.0420191325 0.0145320172 0.1923860000 958855793 0 402718720 0.0535283647 0.1097723544 0.3712513745 491 19.6000000000 0.0266840551 0.0325460472 0.0420191325 0.0145174351 0.2064710000 958857801 0 402718720 0.0564444698 0.1163156256 0.3814479411 492 19.6400000000 0.0267073084 0.0325341798 0.0420191325 0.0145026759 0.2468120000 958859809 0 402718720 0.0567766353 0.1206665412 0.3916485906 493 19.6800000000 0.0265802033 0.0325221028 0.0420191325 0.0144882282 0.2001930000 958861817 0 402718720 0.0573099144 0.1233650893 0.4025273919 494 19.7200000000 0.0264091734 0.0325097284 0.0420191325 0.0144735614 0.2013570000 958863825 0 402718720 0.0576631688 0.1246966422 0.4137349129 495 19.7600000000 0.0262928233 0.0324971690 0.0420191325 0.0144599934 0.2120420000 958865833 0 402718720 0.0583470576 0.1296293736 0.4248234630 496 19.8000000000 0.0262009259 0.0324844750 0.0420191325 0.0144471619 0.2144520000 958867841 0 402718720 0.0584285259 0.1364427060 0.4352274239 497 19.8400000000 0.0260811280 0.0324715910 0.0420191325 0.0144348941 0.2056410000 958869849 0 402718720 0.0583340935 0.1427398473 0.4461663663 498 19.8800000000 0.0259581748 0.0324585118 0.0420191325 0.0144257398 0.2344800000 958871857 0 402718720 0.0570353195 0.1497131586 0.4568183422 499 19.9200000000 0.0258069374 0.0324451820 0.0420191325 0.0144176664 0.2088210000 958873865 0 402718720 0.0563157126 0.1561610997 0.4684075117 500 19.9600000000 0.0256004892 0.0324314926 0.0420191325 0.0144075430 0.2074480000 958875873 0 402718720 0.0552430972 0.1582529545 0.4795594513 501 20.0000000000 0.0254982859 0.0324176539 0.0420191325 0.0143984862 0.2312950000 958877881 0 402718720 0.0537982397 0.1613238454 0.4903362989 502 20.0400000000 0.0254057124 0.0324036859 0.0420191325 0.0143888046 0.2079480000 958879889 0 402718720 0.0523842163 0.1661509871 0.5013425350 503 20.0800000000 0.0252939723 0.0323895513 0.0420191325 0.0143767292 0.2075200000 958881897 0 402718720 0.0502194725 0.1727649122 0.5120539665 504 20.1200000000 0.0251119714 0.0323751116 0.0420191325 0.0143624910 0.2036200000 958883905 0 402718720 0.0475476794 0.1779793054 0.5228685141 505 20.1600000000 0.0249993112 0.0323605061 0.0420191325 0.0143485208 0.2195210000 958885913 0 402718720 0.0459352136 0.1844499260 0.5334157348 506 20.2000000000 0.0247603860 0.0323454861 0.0420191325 0.0143378048 0.2101390000 958887921 0 402718720 0.0441307239 0.1938707083 0.5432730317 507 20.2400000000 0.0246925466 0.0323303915 0.0420191325 0.0143340399 0.2063410000 958889929 0 402718720 0.0412679240 0.1990178972 0.5536949039 508 20.2800000000 0.0245658867 0.0323151071 0.0420191325 0.0143323980 0.2045020000 958891937 0 402718720 0.0390572622 0.2037717849 0.5637209415 509 20.3200000000 0.0244403426 0.0322996360 0.0420191325 0.0143434088 0.2115800000 958893945 0 402718720 0.0364395790 0.2105144262 0.5731683373 510 20.3600000000 0.0243059769 0.0322839622 0.0420191325 0.0143446322 0.2003340000 958895953 0 402718720 0.0325586349 0.2152420282 0.5825574994 511 20.4000000000 0.0241937768 0.0322681301 0.0420191325 0.0143427618 0.1989450000 958897961 0 402718720 0.0304944515 0.2201710790 0.5912237763 512 20.4400000000 0.0240924228 0.0322521619 0.0420191325 0.0143480537 0.2015970000 958899969 0 402718720 0.0301433653 0.2268110812 0.5991191864 513 20.4800000000 0.0239446778 0.0322359680 0.0420191325 0.0143487339 0.2145910000 958901977 0 402718720 0.0285505354 0.2311986834 0.6073477864 514 20.5200000000 0.0238122735 0.0322195795 0.0420191325 0.0143518997 0.2019480000 959006385 0 402718720 0.0271849725 0.2335103154 0.6158062220 515 20.5600000000 0.0237490460 0.0322031319 0.0420191325 0.0143579941 0.2025120000 959008393 0 402718720 0.0269211587 0.2354758680 0.6228450537 516 20.6000000000 0.0237073004 0.0321866671 0.0420191325 0.0143725042 0.2044640000 959010401 0 402718720 0.0269079376 0.2410878539 0.6299659610 517 20.6400000000 0.0235851128 0.0321700296 0.0420191325 0.0143866321 0.2051130000 959012409 0 402718720 0.0271684006 0.2448192537 0.6364852786 518 20.6800000000 0.0234969668 0.0321532863 0.0420191325 0.0144048425 0.2042450000 959014417 0 402718720 0.0272924956 0.2479846179 0.6429174542 519 20.7200000000 0.0234598033 0.0321365358 0.0420191325 0.0144237703 0.2158410000 959016425 0 402718720 0.0292512644 0.2517629862 0.6485580802 520 20.7600000000 0.0233769529 0.0321196905 0.0420191325 0.0144518370 0.2039600000 959018433 0 402718720 0.0304689836 0.2548118830 0.6540551186 521 20.8000000000 0.0233008098 0.0321027636 0.0420191325 0.0144768668 0.2055160000 959020441 0 402718720 0.0324238390 0.2555788457 0.6593835354 522 20.8400000000 0.0232869387 0.0320858751 0.0420191325 0.0145048960 0.2055560000 959022449 0 402718720 0.0339828022 0.2558635175 0.6645613909 523 20.8800000000 0.0239337794 0.0320702879 0.0420191325 0.0145340142 0.2202200000 959024457 0 402718720 0.0362446681 0.2549867034 0.6690197587 524 20.9200000000 0.0233102888 0.0320535704 0.0420191325 0.0145679331 0.2049290000 959026465 0 402718720 0.0385404639 0.2590957880 0.6731913686 525 20.9600000000 0.0241031349 0.0320384267 0.0420191325 0.0145848481 0.1994600000 959028473 0 402718720 0.0414205454 0.2598661482 0.6770185828 526 21.0000000000 0.0239578895 0.0320230644 0.0420191325 0.0145967174 0.2108690000 959030481 0 402718720 0.0444414727 0.2594684958 0.6807355881 527 21.0400000000 0.0245910604 0.0320089620 0.0420191325 0.0146139455 0.2096850000 959032489 0 402718720 0.0474204719 0.2603792250 0.6841875315 528 21.0800000000 0.0246211514 0.0319949699 0.0420191325 0.0146244384 0.1955840000 959034497 0 402718720 0.0510405712 0.2619718909 0.6871532202 529 21.1200000000 0.0243117493 0.0319804458 0.0420191325 0.0146272107 0.2647360000 959036505 0 402718720 0.0538466498 0.2624249160 0.6901234984 530 21.1600000000 0.0245646834 0.0319664538 0.0420191325 0.0146323469 0.2518660000 959038513 0 402718720 0.0571982488 0.2633206248 0.6928547621 531 21.2000000000 0.0243187360 0.0319520514 0.0420191325 0.0146422838 0.2498400000 959040521 0 402718720 0.0608806573 0.2637712061 0.6954729557 532 21.2400000000 0.0242392141 0.0319375535 0.0420191325 0.0146572323 0.2365870000 959042529 0 402718720 0.0645154566 0.2632170916 0.6978275776 533 21.2800000000 0.0244247075 0.0319234581 0.0420191325 0.0146750587 0.1861970000 959044537 0 402718720 0.0684175938 0.2632440329 0.7000575662 534 21.3200000000 0.0244661625 0.0319094932 0.0420191325 0.0146917637 0.1874170000 959046545 0 402718720 0.0724232942 0.2631691992 0.7023012638 535 21.3600000000 0.0246691089 0.0318959597 0.0420191325 0.0147086131 0.1864590000 959048553 0 402718720 0.0761266053 0.2633919120 0.7046494484 536 21.4000000000 0.0248038378 0.0318827282 0.0420191325 0.0147254629 0.1849890000 959050561 0 402718720 0.0798303932 0.2637470961 0.7068068981 537 21.4400000000 0.0249511711 0.0318698202 0.0420191325 0.0147444417 0.1839350000 959052569 0 402718720 0.0843292698 0.2641779780 0.7090765238 538 21.4800000000 0.0251209419 0.0318572759 0.0420191325 0.0147534821 0.1830020000 959054577 0 402718720 0.0889945254 0.2649187148 0.7109966278 539 21.5200000000 0.0252174847 0.0318449571 0.0420191325 0.0147636939 0.1967040000 959056585 0 402718720 0.0940331668 0.2660149634 0.7126375437 540 21.5600000000 0.0247933213 0.0318318986 0.0420191325 0.0147657214 0.1824740000 959058593 0 402718720 0.0977718607 0.2667883933 0.7148467898 541 21.6000000000 0.0248067193 0.0318189130 0.0420191325 0.0147693764 0.1822540000 959060601 0 402718720 0.1023297459 0.2668821514 0.7167077661 542 21.6400000000 0.0254546963 0.0318071709 0.0420191325 0.0147770504 0.1799710000 959062609 0 402718720 0.1062427983 0.2676128149 0.7185999155 543 21.6800000000 0.0254098233 0.0317953894 0.0420191325 0.0147936810 0.1907210000 959064617 0 402718720 0.1101332605 0.2684003115 0.7206763029 544 21.7200000000 0.0254147649 0.0317836603 0.0420191325 0.0148084386 0.1899960000 959066625 0 402718720 0.1132340580 0.2689669430 0.7228458524 545 21.7600000000 0.0258064177 0.0317726929 0.0420191325 0.0148229873 0.1758420000 959068633 0 402718720 0.1175440922 0.2703733146 0.7249751091 546 21.8000000000 0.0236630142 0.0317578400 0.0420191325 0.0148990106 0.1749020000 959070641 0 402718720 0.1227560118 0.2737548947 0.7295553088 547 21.8400000000 0.0249328036 0.0317453628 0.0420191325 0.0149076425 0.1718820000 959072649 0 402718720 0.1268443912 0.2733379602 0.7317031622 548 21.8800000000 0.0259463266 0.0317347806 0.0420191325 0.0149209571 0.1978460000 959074657 0 402718720 0.1311874092 0.2741686106 0.7334569693 549 21.9200000000 0.0261535030 0.0317246144 0.0420191325 0.0149421340 0.1830850000 959076665 0 402718720 0.1348285228 0.2757002115 0.7356016040 550 21.9600000000 0.0259063262 0.0317140357 0.0420191325 0.0149590568 0.1690310000 959078673 0 402718720 0.1399964541 0.2769391835 0.7371818423 551 22.0000000000 0.0265492648 0.0317046622 0.0420191325 0.0149864506 0.1677500000 959080681 0 402718720 0.1433963925 0.2787517309 0.7387657762 552 22.0400000000 0.0261499584 0.0316945993 0.0420191325 0.0149975027 0.1669520000 959082689 0 402718720 0.1478662640 0.2815725207 0.7401389480 553 22.0800000000 0.0249912050 0.0316824775 0.0420191325 0.0149941019 0.1775630000 959084697 0 402718720 0.1521734446 0.2826394737 0.7417230606 554 22.1200000000 0.0250840001 0.0316705669 0.0420191325 0.0149876125 0.1645180000 959086705 0 402718720 0.1555088460 0.2817361355 0.7438102365 555 22.1600000000 0.0268453415 0.0316618728 0.0420191325 0.0149798502 0.1632550000 959088713 0 402718720 0.1614758223 0.2817399502 0.7449322343 556 22.2000000000 0.0278798547 0.0316550706 0.0420191325 0.0149790051 0.1622370000 959090721 0 402718720 0.1669748276 0.2836876214 0.7461536527 557 22.2400000000 0.0273916516 0.0316474163 0.0420191325 0.0149752819 0.1616000000 959092729 0 402718720 0.1715192348 0.2859230638 0.7476667166 558 22.2800000000 0.0275799446 0.0316401269 0.0420191325 0.0149747150 0.1602330000 959094737 0 402718720 0.1767465621 0.2886040509 0.7491793633 559 22.3200000000 0.0274337102 0.0316326020 0.0420191325 0.0149717559 0.1700690000 959096745 0 402718720 0.1822544932 0.2913770378 0.7505887151 560 22.3600000000 0.0266790837 0.0316237565 0.0420191325 0.0149680435 0.1583990000 959098753 0 402718720 0.1864283979 0.2930621207 0.7530476451 561 22.4000000000 0.0273050573 0.0316160583 0.0420191325 0.0149644375 0.1592250000 959100761 0 402718720 0.1905368567 0.2947080135 0.7548292279 562 22.4400000000 0.0279551372 0.0316095442 0.0420191325 0.0149621209 0.1587170000 959102769 0 402718720 0.1956960857 0.2972956300 0.7560210228 563 22.4800000000 0.0276966002 0.0316025940 0.0420191325 0.0149550870 0.1580510000 959104777 0 402718720 0.2015848458 0.3010628223 0.7566670179 564 22.5200000000 0.0264429841 0.0315934458 0.0420191325 0.0149457608 0.1573360000 959106785 0 402718720 0.2060369402 0.3041137457 0.7582589388 565 22.5600000000 0.0257600825 0.0315831212 0.0420191325 0.0149359283 0.1566540000 959108793 0 402718720 0.2095134556 0.3058050871 0.7599216104 566 22.6000000000 0.0266600344 0.0315744232 0.0420191325 0.0149267982 0.1560070000 959110801 0 402718720 0.2145340294 0.3080287874 0.7612549067 567 22.6400000000 0.0263010990 0.0315651228 0.0420191325 0.0149156389 0.1527140000 959112809 0 402718720 0.2192243934 0.3105213046 0.7622973323 568 22.6800000000 0.0260730032 0.0315554536 0.0420191325 0.0149060583 0.1543830000 959114817 0 402718720 0.2236069888 0.3125903308 0.7637050152 569 22.7200000000 0.0259603374 0.0315456203 0.0420191325 0.0148947155 0.1650880000 959116825 0 402718720 0.2285363227 0.3141060472 0.7641997933 570 22.7600000000 0.0267509948 0.0315372087 0.0420191325 0.0148840887 0.1526070000 959118833 0 402718720 0.2329374701 0.3161164522 0.7650279999 571 22.8000000000 0.0269401502 0.0315291578 0.0420191325 0.0148720259 0.1512760000 959120841 0 402718720 0.2379817665 0.3185991049 0.7657848597 572 22.8400000000 0.0269854106 0.0315212142 0.0420191325 0.0148594953 0.1961430000 959122849 0 402718720 0.2434350103 0.3214334846 0.7655600309 573 22.8800000000 0.0263206512 0.0315121382 0.0420191325 0.0148481706 0.1953420000 959124857 0 402718720 0.2480440289 0.3243795335 0.7661005259 574 22.9200000000 0.0261970609 0.0315028785 0.0420191325 0.0148369299 0.1942610000 959126865 0 402718720 0.2522011101 0.3275954127 0.7663593292 575 22.9600000000 0.0257517565 0.0314928765 0.0420191325 0.0148241903 0.1933520000 959128873 0 402718720 0.2561517060 0.3308643997 0.7669769526 576 23.0000000000 0.0262830667 0.0314838317 0.0420191325 0.0148113882 0.1925040000 959130881 0 402718720 0.2597083151 0.3336710930 0.7675797939 577 23.0400000000 0.0263655540 0.0314749612 0.0420191325 0.0147985472 0.1608850000 959132889 0 402718720 0.2634609938 0.3371202052 0.7679653168 578 23.0800000000 0.0257028304 0.0314649748 0.0420191325 0.0147859016 0.1616140000 959134897 0 402718720 0.2662986219 0.3395778537 0.7683612108 579 23.1200000000 0.0269876141 0.0314572419 0.0420191325 0.0147736450 0.1606120000 959136905 0 402718720 0.2698387802 0.3417959213 0.7681735158 580 23.1600000000 0.0276960898 0.0314507571 0.0420191325 0.0147615392 0.1479670000 959138913 0 402718720 0.2744334340 0.3468455076 0.7679473162 581 23.2000000000 0.0266896393 0.0314425624 0.0420191325 0.0147489521 0.1462450000 959140921 0 402718720 0.2780793309 0.3524813354 0.7676393390 582 23.2400000000 0.0256343391 0.0314325827 0.0420191325 0.0147363952 0.1428970000 959142929 0 402718720 0.2807080150 0.3570312560 0.7675333619 583 23.2800000000 0.0259095207 0.0314231092 0.0420191325 0.0147238615 0.1555160000 959144937 0 402718720 0.2838428319 0.3617730141 0.7676069140 584 23.3200000000 0.0247910805 0.0314117529 0.0420191325 0.0147124169 0.1435600000 959146945 0 402718720 0.2861925960 0.3658100069 0.7669204473 585 23.3600000000 0.0242203027 0.0313994599 0.0420191325 0.0147004511 0.1429180000 959148953 0 402718720 0.2886806726 0.3684636950 0.7664925456 586 23.4000000000 0.0246276390 0.0313879039 0.0420191325 0.0146883351 0.1422940000 959150961 0 402718720 0.2910137177 0.3709728420 0.7664860487 587 23.4400000000 0.0248635840 0.0313767892 0.0420191325 0.0146758458 0.1419040000 959152969 0 402718720 0.2931801379 0.3739566207 0.7662491202 588 23.4800000000 0.0244557001 0.0313650186 0.0420191325 0.0146634533 0.1420270000 959154977 0 402718720 0.2953534722 0.3771332800 0.7661223412 589 23.5200000000 0.0241786707 0.0313528177 0.0420191325 0.0146511095 0.1515020000 959156985 0 402718720 0.2979873419 0.3801793754 0.7659479380 590 23.5600000000 0.0236324910 0.0313397324 0.0420191325 0.0146387330 0.1427940000 959158993 0 402718720 0.2999579608 0.3825491965 0.7661736608 591 23.6000000000 0.0240401421 0.0313273811 0.0420191325 0.0146264411 0.1424460000 959161001 0 402718720 0.3018628359 0.3848607540 0.7667007446 592 23.6400000000 0.0240109041 0.0313150222 0.0420191325 0.0146150156 0.1420400000 959163009 0 402718720 0.3040720224 0.3875309527 0.7663828731 593 23.6800000000 0.0222101547 0.0312996683 0.0420191325 0.0146059441 0.1415370000 959165017 0 402718720 0.3092519939 0.3929727376 0.7659701109 594 23.7200000000 0.0224192068 0.0312847180 0.0420191325 0.0145936436 0.1535050000 959167025 0 402718720 0.3103379607 0.3933537900 0.7667771578 595 23.7600000000 0.0234058704 0.0312714763 0.0420191325 0.0145816676 0.1400420000 959169033 0 402718720 0.3115180135 0.3942193091 0.7673078775 596 23.8000000000 0.0240247194 0.0312593173 0.0420191325 0.0145694882 0.1397650000 959171041 0 402718720 0.3129251301 0.3959705532 0.7680445313 597 23.8400000000 0.0238764454 0.0312469507 0.0420191325 0.0145575392 0.1667590000 959173049 0 402718720 0.3141359091 0.3982148468 0.7684997916 598 23.8800000000 0.0231103525 0.0312333443 0.0420191325 0.0145462826 0.1799470000 959175057 0 402718720 0.3147806823 0.4000564516 0.7692587376 599 23.9200000000 0.0232746825 0.0312200577 0.0420191325 0.0145361941 0.1793880000 959177065 0 402718720 0.3155124485 0.4017262757 0.7701592445 600 23.9600000000 0.0230568741 0.0312064524 0.0420191325 0.0145263533 0.1787900000 959179073 0 402718720 0.3157148659 0.4036999345 0.7709284425 601 24.0000000000 0.0223591700 0.0311917315 0.0420191325 0.0145173533 0.1778800000 959181081 0 402718720 0.3174628615 0.4081856608 0.7718660831 602 24.0400000000 0.0225707199 0.0311774109 0.0420191325 0.0145068931 0.1604250000 959183089 0 402718720 0.3172814846 0.4082144797 0.7729982138 603 24.0800000000 0.0230826568 0.0311639867 0.0420191325 0.0144964589 0.1509660000 959185097 0 402718720 0.3177703619 0.4088489711 0.7739021182 604 24.1200000000 0.0235818699 0.0311514336 0.0420191325 0.0144846535 0.1379750000 959187105 0 402718720 0.3184440434 0.4095994234 0.7747876644 605 24.1600000000 0.0241100620 0.0311397949 0.0420191325 0.0144727821 0.1377020000 959189113 0 402718720 0.3203075230 0.4135435522 0.7755647302 606 24.2000000000 0.0236868039 0.0311274963 0.0420191325 0.0144608191 0.1375670000 959191121 0 402718720 0.3203483224 0.4155339003 0.7768100500 607 24.2400000000 0.0235550497 0.0311150211 0.0420191325 0.0144491627 0.1371200000 959193129 0 402718720 0.3209467828 0.4172956049 0.7773471475 608 24.2800000000 0.0234822556 0.0311024672 0.0420191325 0.0144374406 0.1361900000 959195137 0 402718720 0.3214096725 0.4183731079 0.7782951593 609 24.3200000000 0.0234791972 0.0310899495 0.0420191325 0.0144257853 0.1750450000 959197145 0 402718720 0.3219159245 0.4196657240 0.7787286043 610 24.3600000000 0.0242213234 0.0310786895 0.0420191325 0.0144140326 0.1758550000 959199153 0 402718720 0.3225059509 0.4216722846 0.7791550159 611 24.4000000000 0.0244501177 0.0310678407 0.0420191325 0.0144022417 0.1755820000 959201161 0 402718720 0.3231914937 0.4238373637 0.7795782089 612 24.4400000000 0.0240365509 0.0310563517 0.0420191325 0.0143904780 0.1756240000 959203169 0 402718720 0.3229521811 0.4260537326 0.7804791927 613 24.4800000000 0.0243056640 0.0310453392 0.0420191325 0.0143789756 0.1760850000 959205177 0 402718720 0.3233668208 0.4282819331 0.7811023593 614 24.5200000000 0.0239603929 0.0310338002 0.0420191325 0.0143678492 0.1756190000 959207185 0 402718720 0.3231736124 0.4304261804 0.7819103003 615 24.5600000000 0.0238978881 0.0310221970 0.0420191325 0.0143570574 0.1756660000 959209193 0 402718720 0.3224102259 0.4332117140 0.7829070091 616 24.6000000000 0.0235820357 0.0310101189 0.0420191325 0.0143460583 0.1755350000 959211201 0 402718720 0.3215186894 0.4354294240 0.7842189670 617 24.6400000000 0.0238371156 0.0309984933 0.0420191325 0.0143346707 0.1759230000 959213209 0 402718720 0.3203082681 0.4371254146 0.7856154442 618 24.6800000000 0.0241136327 0.0309873527 0.0420191325 0.0143252303 0.1706010000 959215217 0 402718720 0.3193153739 0.4387203753 0.7871420383 619 24.7200000000 0.0241952222 0.0309763800 0.0420191325 0.0143159806 0.1372150000 959217225 0 402718720 0.3178821504 0.4414606392 0.7884854674 620 24.7600000000 0.0238947831 0.0309649580 0.0420191325 0.0143074913 0.1377270000 959219233 0 402718720 0.3161289096 0.4433211386 0.7899083495 621 24.8000000000 0.0244867466 0.0309545261 0.0420191325 0.0142995676 0.1373440000 959221241 0 402718720 0.3139804900 0.4445178509 0.7919355035 622 24.8400000000 0.0248514470 0.0309447141 0.0420191325 0.0142924235 0.1492820000 959223249 0 402718720 0.3118530810 0.4461001158 0.7942825556 623 24.8800000000 0.0258000046 0.0309364561 0.0420191325 0.0142880337 0.1371650000 959225257 0 402718720 0.3098062277 0.4484514594 0.7964847088 624 24.9200000000 0.0251426734 0.0309271712 0.0420191325 0.0142818746 0.1374050000 959227265 0 402718720 0.3083336055 0.4501300752 0.7983250022 625 24.9600000000 0.0257657878 0.0309189130 0.0420191325 0.0142749474 0.1376010000 959229273 0 402718720 0.3062452376 0.4519672692 0.8004294038 626 25.0000000000 0.0258172899 0.0309107635 0.0420191325 0.0142683192 0.1355380000 959231281 0 402718720 0.3040880561 0.4553725421 0.8023429513 627 25.0400000000 0.0225067772 0.0308973600 0.0420191325 0.0142661607 0.1575080000 959233289 0 402718720 0.3051597476 0.4623850584 0.8018426299 628 25.0800000000 0.0231297892 0.0308849912 0.0420191325 0.0142655805 0.1391290000 959235297 0 402718720 0.3016066551 0.4640240073 0.8043786883 629 25.1200000000 0.0240458027 0.0308741181 0.0420191325 0.0142679432 0.1495580000 959237305 0 402718720 0.2994276583 0.4652089477 0.8059731722 630 25.1600000000 0.0241773892 0.0308634884 0.0420191325 0.0142623477 0.1390590000 959239313 0 402718720 0.2963967025 0.4666392505 0.8081292510 631 25.2000000000 0.0247747693 0.0308538391 0.0420191325 0.0142567898 0.1392920000 959241321 0 402718720 0.2935854793 0.4683273435 0.8099395037 632 25.2400000000 0.0241256859 0.0308431933 0.0420191325 0.0142503950 0.1389730000 959243329 0 402718720 0.2906331122 0.4691209793 0.8124201298 633 25.2800000000 0.0246161576 0.0308333559 0.0420191325 0.0142419061 0.1385450000 959245337 0 402718720 0.2868731320 0.4701845646 0.8146086335 634 25.3200000000 0.0251700263 0.0308244232 0.0420191325 0.0142334131 0.1380650000 959247345 0 402718720 0.2833696604 0.4723720253 0.8170965314 635 25.3600000000 0.0248779003 0.0308150586 0.0420191325 0.0142260253 0.1402230000 959249353 0 402718720 0.2795516849 0.4748932421 0.8198149800 636 25.4000000000 0.0243005771 0.0308048157 0.0420191325 0.0142198698 0.1385540000 959251361 0 402718720 0.2756997049 0.4766382575 0.8221887946 637 25.4400000000 0.0242359061 0.0307945035 0.0420191325 0.0142133324 0.1408350000 959253369 0 402718720 0.2715858817 0.4778360426 0.8250239491 638 25.4800000000 0.0239502341 0.0307837758 0.0420191325 0.0142060086 0.1396160000 959255377 0 402718720 0.2669926286 0.4792755544 0.8282427788 639 25.5200000000 0.0233005807 0.0307720650 0.0420191325 0.0141989199 0.1536830000 959257385 0 402718720 0.2626487315 0.4802882671 0.8313518763 640 25.5600000000 0.0226216260 0.0307593299 0.0420191325 0.0141905815 0.1428070000 959259393 0 402718720 0.2582114637 0.4803276658 0.8347534537 641 25.6000000000 0.0227630399 0.0307468552 0.0420191325 0.0141824719 0.1406490000 959261401 0 402718720 0.2533913255 0.4803380668 0.8379379511 642 25.6400000000 0.0235514808 0.0307356475 0.0420191325 0.0141783942 0.1432420000 959263409 0 402718720 0.2490198463 0.4819627702 0.8409101367 643 25.6800000000 0.0235395487 0.0307244560 0.0420191325 0.0141758865 0.1438860000 959265417 0 402718720 0.2443067878 0.4831205606 0.8439991474 644 25.7200000000 0.0231305566 0.0307126642 0.0420191325 0.0141724450 0.1444070000 959267425 0 402718720 0.2400209606 0.4835005403 0.8468087912 645 25.7600000000 0.0237102881 0.0307018078 0.0420191325 0.0141665317 0.1632380000 959269433 0 402718720 0.2357234210 0.4847400486 0.8493916392 646 25.8000000000 0.0238100179 0.0306911394 0.0420191325 0.0141609354 0.1457330000 959271441 0 402718720 0.2313786894 0.4862109721 0.8522620201 647 25.8400000000 0.0235270504 0.0306800667 0.0420191325 0.0141548947 0.1479570000 959273449 0 402718720 0.2266411334 0.4867469072 0.8553263545 648 25.8800000000 0.0245555881 0.0306706153 0.0420191325 0.0141472791 0.1479190000 959275457 0 402718720 0.2220696807 0.4876453578 0.8580995202 649 25.9200000000 0.0249161273 0.0306617486 0.0420191325 0.0141394642 0.1733540000 959277465 0 402718720 0.2176412940 0.4890916049 0.8608170152 650 25.9600000000 0.0217154492 0.0306479851 0.0420191325 0.0141334348 0.1591680000 959279473 0 402718720 0.2150972039 0.4961658716 0.8625210524 651 26.0000000000 0.0218854491 0.0306345249 0.0420191325 0.0141324373 0.1560420000 959281481 0 402718720 0.2116999626 0.4978695810 0.8647661805 652 26.0400000000 0.0218753368 0.0306210906 0.0420191325 0.0141293308 0.1574370000 959283489 0 402718720 0.2079240382 0.5000423789 0.8666324019 653 26.0800000000 0.0224655513 0.0306086013 0.0420191325 0.0141282338 0.1537460000 959285497 0 402718720 0.2024305761 0.5008343458 0.8691866398 654 26.1200000000 0.0219371095 0.0305953421 0.0420191325 0.0141281066 0.1595080000 959287505 0 402718720 0.1988714039 0.5027548671 0.8712683320 655 26.1600000000 0.0214650407 0.0305814027 0.0420191325 0.0141239990 0.1650330000 959289513 0 402718720 0.1962749064 0.5066854954 0.8727971315 656 26.2000000000 0.0228505172 0.0305696178 0.0420191325 0.0141197196 0.1578980000 959291521 0 402718720 0.1862305105 0.5084658265 0.8767096400 657 26.2400000000 0.0216617975 0.0305560595 0.0420191325 0.0141177269 0.1641430000 959293529 0 402718720 0.1837506145 0.5101159215 0.8783277869 658 26.2800000000 0.0216711909 0.0305425567 0.0420191325 0.0141107637 0.1652220000 959295537 0 402718720 0.1800562441 0.5120276809 0.8798920512 659 26.3200000000 0.0212603081 0.0305284713 0.0420191325 0.0141065711 0.1818870000 959297545 0 402718720 0.1768814176 0.5162286162 0.8811733723 660 26.3600000000 0.0214333199 0.0305146908 0.0420191325 0.0141040986 0.1686600000 959299553 0 402718720 0.1729635447 0.5169822574 0.8827085495 661 26.4000000000 0.0215750597 0.0305011664 0.0420191325 0.0141025112 0.1697720000 959301561 0 402718720 0.1701824814 0.5206386447 0.8834221363 662 26.4400000000 0.0214583091 0.0304875065 0.0420191325 0.0140969308 0.1702080000 959303569 0 402718720 0.1676403433 0.5236378312 0.8842036128 663 26.4800000000 0.0216746461 0.0304742141 0.0420191325 0.0140936960 0.1643820000 959305577 0 402718720 0.1631026566 0.5230196714 0.8858559728 664 26.5200000000 0.0214010160 0.0304605496 0.0420191325 0.0140924099 0.1724350000 959307585 0 402718720 0.1614452451 0.5249984860 0.8866677284 665 26.5600000000 0.0230110288 0.0304493473 0.0420191325 0.0140902346 0.1680120000 959309593 0 402718720 0.1574942768 0.5254251957 0.8879820108 666 26.6000000000 0.0233154465 0.0304386358 0.0420191325 0.0140854444 0.1674440000 959311601 0 402718720 0.1545161903 0.5262678266 0.8890085220 667 26.6400000000 0.0236526132 0.0304284618 0.0420191325 0.0140800749 0.1825380000 959313609 0 402718720 0.1505792439 0.5278539062 0.8899672627 668 26.6800000000 0.0235212576 0.0304181217 0.0420191325 0.0140747987 0.1709360000 959315617 0 402718720 0.1466747522 0.5299751163 0.8909953237 669 26.7200000000 0.0210323781 0.0304040922 0.0420191325 0.0140718209 0.1789410000 959317625 0 402718720 0.1436831802 0.5345766544 0.8916844130 670 26.7600000000 0.0216870103 0.0303910816 0.0420191325 0.0140652270 0.1719380000 959319633 0 402718720 0.1387495846 0.5328894854 0.8930194974 671 26.8000000000 0.0211805310 0.0303773550 0.0420191325 0.0140604989 0.1779060000 959321641 0 402718720 0.1357889175 0.5327495933 0.8944771886 672 26.8400000000 0.0221863743 0.0303651660 0.0420191325 0.0140526431 0.1856110000 959323649 0 402718720 0.1312434524 0.5315981507 0.8960386515 673 26.8800000000 0.0212243367 0.0303515838 0.0420191325 0.0140436850 0.1778620000 959325657 0 402718720 0.1280753464 0.5327215791 0.8972349167 674 26.9200000000 0.0209260490 0.0303375994 0.0420191325 0.0140398848 0.1779590000 959327665 0 402718720 0.1241256073 0.5324718952 0.8987488151 675 26.9600000000 0.0214896910 0.0303244913 0.0420191325 0.0140360021 0.1730990000 959329673 0 402718720 0.1196308956 0.5317649841 0.8998978734 676 27.0000000000 0.0218652897 0.0303119777 0.0420191325 0.0140281372 0.1932870000 959331681 0 402718720 0.1152098253 0.5316288471 0.9007610679 677 27.0400000000 0.0215911493 0.0302990962 0.0420191325 0.0140213094 0.1738150000 959333689 0 402718720 0.1105457395 0.5320475101 0.9014993310 678 27.0800000000 0.0215219222 0.0302861505 0.0420191325 0.0140139557 0.1742850000 959335697 0 402718720 0.1058495864 0.5317670703 0.9024993777 679 27.1200000000 0.0214468092 0.0302731323 0.0420191325 0.0140051960 0.1963160000 959337705 0 402718720 0.1006771699 0.5307419300 0.9035247564 680 27.1600000000 0.0209386423 0.0302594051 0.0420191325 0.0139996844 0.1782400000 959339713 0 402718720 0.0961966440 0.5307481885 0.9048002958 681 27.2000000000 0.0209344309 0.0302457120 0.0420191325 0.0139947689 0.1772040000 959341721 0 402718720 0.0936978757 0.5305072665 0.9055302143 682 27.2400000000 0.0208733454 0.0302319696 0.0420191325 0.0139897440 0.1767750000 959343729 0 402718720 0.0900685415 0.5299679041 0.9063006043 683 27.2800000000 0.0208709501 0.0302182638 0.0420191325 0.0139846186 0.1779580000 959345737 0 402718720 0.0874378309 0.5288389325 0.9072532654 684 27.3200000000 0.0222253930 0.0302065784 0.0420191325 0.0139752674 0.1728900000 959347745 0 402718720 0.0813752487 0.5279165506 0.9084430933 685 27.3600000000 0.0212341771 0.0301934800 0.0420191325 0.0139693481 0.1777810000 959349753 0 402718720 0.0788523480 0.5300086141 0.9092294574 686 27.4000000000 0.0218242556 0.0301812799 0.0420191325 0.0139643505 0.1852910000 959351761 0 402718720 0.0745372698 0.5284784436 0.9104198813 687 27.4400000000 0.0211026948 0.0301680651 0.0420191325 0.0139607927 0.1773740000 959353769 0 402718720 0.0711845830 0.5300410986 0.9117351174 688 27.4800000000 0.0210029185 0.0301547437 0.0420191325 0.0139580768 0.1770200000 959355777 0 402718720 0.0691383630 0.5306127071 0.9127791524 689 27.5200000000 0.0227008127 0.0301439252 0.0420191325 0.0139536719 0.1824670000 959357785 0 402718720 0.0647957996 0.5294973850 0.9136108756 690 27.5600000000 0.0233871937 0.0301341328 0.0420191325 0.0139472794 0.1704300000 959359793 0 402718720 0.0613112897 0.5297135711 0.9146773219 691 27.6000000000 0.0212233346 0.0301212373 0.0420191325 0.0139425474 0.1761520000 959361801 0 402718720 0.0585755333 0.5322333574 0.9155946970 692 27.6400000000 0.0224048551 0.0301100865 0.0420191325 0.0139367996 0.1728300000 959363809 0 402718720 0.0545457415 0.5318493843 0.9168469310 693 27.6800000000 0.0223514382 0.0300988907 0.0420191325 0.0139308549 0.1717710000 959365817 0 402718720 0.0503012985 0.5313085318 0.9178839922 694 27.7200000000 0.0211963151 0.0300860628 0.0420191325 0.0139236807 0.1750440000 959367825 0 402718720 0.0483013541 0.5329058170 0.9190967679 695 27.7600000000 0.0210683141 0.0300730876 0.0420191325 0.0139180046 0.1745430000 959369833 0 402718720 0.0456190854 0.5332989693 0.9201666713 696 27.8000000000 0.0211192369 0.0300602229 0.0420191325 0.0139126963 0.1701590000 959371841 0 402718720 0.0413936265 0.5316487551 0.9214620590 697 27.8400000000 0.0219969507 0.0300486544 0.0420191325 0.0139089373 0.1704070000 959373849 0 402718720 0.0376536921 0.5313412547 0.9224814177 698 27.8800000000 0.0209668055 0.0300356431 0.0420191325 0.0139054957 0.1727890000 959375857 0 402718720 0.0354302451 0.5326198339 0.9235255718 699 27.9200000000 0.0215056781 0.0300234400 0.0420191325 0.0139003105 0.1716120000 959377865 0 402718720 0.0313321650 0.5327396393 0.9245677590 700 27.9600000000 0.0216362141 0.0300114583 0.0420191325 0.0138976921 0.1712740000 959379873 0 402718720 0.0274626613 0.5326966643 0.9256437421 701 28.0000000000 0.0222647674 0.0300004074 0.0420191325 0.0138941707 0.1714110000 959381881 0 402718720 0.0242015421 0.5327908993 0.9265758991 702 28.0400000000 0.0236524586 0.0299913647 0.0420191325 0.0138895908 0.1712490000 959383889 0 402718720 0.0195320956 0.5334801674 0.9271684289 703 28.0800000000 0.0232955050 0.0299818400 0.0420191325 0.0138853654 0.1709230000 959385897 0 402718720 0.0166981816 0.5342800021 0.9283807278 704 28.1200000000 0.0228363834 0.0299716902 0.0420191325 0.0138806841 0.1709660000 959387905 0 402718720 0.0136471251 0.5346237421 0.9294388294 705 28.1600000000 0.0226938147 0.0299613670 0.0420191325 0.0138761680 0.1862760000 959389913 0 402718720 0.0104915397 0.5345131159 0.9309048653 706 28.2000000000 0.0221386459 0.0299502866 0.0420191325 0.0138716760 0.1730030000 959391921 0 402718720 0.0077170995 0.5339466929 0.9320577383 707 28.2400000000 0.0219514463 0.0299389729 0.0420191325 0.0138671111 0.1712170000 959393929 0 402718720 0.0035718554 0.5337280035 0.9332343340 708 28.2800000000 0.0219174027 0.0299276430 0.0420191325 0.0138613527 0.1733490000 959395937 0 402718720 0.0008880135 0.5332162976 0.9344288111 709 28.3200000000 0.0230068211 0.0299178816 0.0420191325 0.0138541081 0.1870260000 959397945 0 402718720 -0.0026817296 0.5334252119 0.9354587793 710 28.3600000000 0.0228135120 0.0299078754 0.0420191325 0.0138479119 0.1739960000 959399953 0 402718720 -0.0067875707 0.5337267518 0.9364330173 711 28.4000000000 0.0228727832 0.0298979808 0.0420191325 0.0138429536 0.1734970000 959401961 0 402718720 -0.0107988250 0.5333607197 0.9377180338 712 28.4400000000 0.0232376698 0.0298886264 0.0420191325 0.0138364463 0.1716990000 959403969 0 402718720 -0.0156553574 0.5330049396 0.9386067986 713 28.4800000000 0.0236043893 0.0298798126 0.0420191325 0.0138299173 0.1735860000 959405977 0 402718720 -0.0200712737 0.5333864093 0.9395938516 714 28.5200000000 0.0230446756 0.0298702396 0.0420191325 0.0138239775 0.1728040000 959407985 0 402718720 -0.0240480807 0.5332008004 0.9410245419 715 28.5600000000 0.0232063215 0.0298609194 0.0420191325 0.0138161898 0.1729850000 959409993 0 402718720 -0.0285199005 0.5334224105 0.9422808290 716 28.6000000000 0.0226876736 0.0298509009 0.0420191325 0.0138108930 0.1729330000 959412001 0 402718720 -0.0330700651 0.5328689814 0.9434588552 717 28.6400000000 0.0232690200 0.0298417212 0.0420191325 0.0138038343 0.1726760000 959414009 0 402718720 -0.0375889800 0.5325942039 0.9442853332 718 28.6800000000 0.0235100295 0.0298329027 0.0420191325 0.0137976573 0.1729050000 959416017 0 402718720 -0.0426743552 0.5330345631 0.9451013803 719 28.7200000000 0.0228355024 0.0298231705 0.0420191325 0.0137947521 0.1855230000 959418025 0 402718720 -0.0471092835 0.5323152542 0.9460136294 720 28.7600000000 0.0236080177 0.0298145384 0.0420191325 0.0137956689 0.1727930000 959420033 0 402718720 -0.0511325747 0.5317955017 0.9468864202 721 28.8000000000 0.0229909737 0.0298050743 0.0420191325 0.0137925944 0.1706120000 959422041 0 402718720 -0.0548167005 0.5313233733 0.9481123090 722 28.8400000000 0.0226580799 0.0297951755 0.0420191325 0.0137880686 0.1740450000 959424049 0 402718720 -0.0597714223 0.5305729508 0.9489909410 723 28.8800000000 0.0232596751 0.0297861360 0.0420191325 0.0137817458 0.1722930000 959426057 0 402718720 -0.0638765618 0.5302090049 0.9498741031 724 28.9200000000 0.0231426824 0.0297769600 0.0420191325 0.0137747597 0.1743000000 959428065 0 402718720 -0.0690755770 0.5297588110 0.9505842328 725 28.9600000000 0.0228053518 0.0297673440 0.0420191325 0.0137677207 0.1713600000 959430073 0 402718720 -0.0732185170 0.5292549729 0.9518300295 726 29.0000000000 0.0232432112 0.0297583576 0.0420191325 0.0137611357 0.1736380000 959432081 0 402718720 -0.0769419819 0.5288607478 0.9525505304 727 29.0400000000 0.0234080628 0.0297496226 0.0420191325 0.0137568919 0.1753750000 959434089 0 402718720 -0.0805554017 0.5286494493 0.9533869028 728 29.0800000000 0.0231372360 0.0297405397 0.0420191325 0.0137537924 0.1755270000 959436097 0 402718720 -0.0834925622 0.5278953910 0.9541329145 729 29.1200000000 0.0232319385 0.0297316116 0.0420191325 0.0137534053 0.1756860000 959438105 0 402718720 -0.0865608230 0.5277397633 0.9547916651 730 29.1600000000 0.0230648443 0.0297224790 0.0420191325 0.0137513680 0.1738810000 959440113 0 402718720 -0.0891565904 0.5268000364 0.9557020068 731 29.2000000000 0.0230656397 0.0297133725 0.0420191325 0.0137489166 0.1743950000 959442121 0 402718720 -0.0931997672 0.5257034302 0.9559728503 732 29.2400000000 0.0232641008 0.0297045621 0.0420191325 0.0137454910 0.1746260000 959444129 0 402718720 -0.0969000608 0.5256731510 0.9563592672 733 29.2800000000 0.0227665883 0.0296950969 0.0420191325 0.0137415511 0.1759930000 959446137 0 402718720 -0.0998203456 0.5245375633 0.9570459723 734 29.3200000000 0.0230765771 0.0296860798 0.0420191325 0.0137347114 0.1962900000 959448145 0 402718720 -0.1023338288 0.5236436129 0.9574373364 735 29.3600000000 0.0231319591 0.0296771626 0.0420191325 0.0137274912 0.1739440000 959450153 0 402718720 -0.1056407392 0.5233801007 0.9575338364 736 29.4000000000 0.0226422120 0.0296676043 0.0420191325 0.0137222793 0.1749560000 959452161 0 402718720 -0.1087770164 0.5223668814 0.9576806426 737 29.4400000000 0.0226036422 0.0296580195 0.0420191325 0.0137169999 0.1877740000 959454169 0 402718720 -0.1116115302 0.5205898285 0.9578859806 738 29.4800000000 0.0223312788 0.0296480917 0.0420191325 0.0137100818 0.1729850000 959456177 0 402718720 -0.1132593006 0.5193043351 0.9584791064 739 29.5200000000 0.0220291559 0.0296377819 0.0420191325 0.0137044091 0.1859370000 959458185 0 402718720 -0.1147458255 0.5175632238 0.9589039683 740 29.5600000000 0.0226646531 0.0296283588 0.0420191325 0.0137010969 0.1891870000 959460193 0 402718720 -0.1161926016 0.5152402520 0.9590972662 741 29.6000000000 0.0225550476 0.0296188131 0.0420191325 0.0136991556 0.1773690000 959462201 0 402718720 -0.1181240082 0.5140451193 0.9595457315 742 29.6400000000 0.0221065804 0.0296086888 0.0420191325 0.0136956490 0.1896330000 959464209 0 402718720 -0.1197689846 0.5132088661 0.9600263834 743 29.6800000000 0.0219994392 0.0295984476 0.0420191325 0.0136930524 0.1754070000 959466217 0 402718720 -0.1210527793 0.5118313432 0.9601421356 744 29.7200000000 0.0219802652 0.0295882081 0.0420191325 0.0136941310 0.1772700000 959468225 0 402718720 -0.1241546869 0.5080807805 0.9609355927 745 29.7600000000 0.0222060475 0.0295782992 0.0420191325 0.0136870446 0.1906700000 959470233 0 402718720 -0.1250592172 0.5055367351 0.9615320563 746 29.8000000000 0.0226820763 0.0295690549 0.0420191325 0.0136792289 0.1768600000 959472241 0 402718720 -0.1264131069 0.5044348836 0.9618306756 747 29.8400000000 0.0222671516 0.0295592799 0.0420191325 0.0136715840 0.1760460000 959474249 0 402718720 -0.1276232451 0.5031927228 0.9623920918 748 29.8800000000 0.0223985985 0.0295497068 0.0420191325 0.0136624608 0.1737880000 959476257 0 402718720 -0.1283668727 0.5016228557 0.9627770782 749 29.9200000000 0.0222015567 0.0295398962 0.0420191325 0.0136534785 0.1867460000 959478265 0 402718720 -0.1294775754 0.5005816817 0.9631597996 750 29.9600000000 0.0220617168 0.0295299253 0.0420191325 0.0136444338 0.1760030000 959480273 0 402718720 -0.1306591928 0.5002531409 0.9635055661 751 30.0000000000 0.0215533413 0.0295193040 0.0420191325 0.0136355305 0.1757570000 959482281 0 402718720 -0.1310963184 0.4973811805 0.9642915130 752 30.0400000000 0.0220801178 0.0295094115 0.0420191325 0.0136267445 0.1756270000 959484289 0 402718720 -0.1315223724 0.4951157272 0.9651253819 753 30.0800000000 0.0219528135 0.0294993762 0.0420191325 0.0136201307 0.1753530000 959486297 0 402718720 -0.1323388815 0.4941187799 0.9659286141 754 30.1200000000 0.0216407925 0.0294889536 0.0420191325 0.0136137824 0.1855480000 959488305 0 402718720 -0.1320357323 0.4926309586 0.9669268727 755 30.1600000000 0.0214925446 0.0294783624 0.0420191325 0.0136074274 0.1766270000 959490313 0 402718720 -0.1321758926 0.4914142787 0.9681255221 756 30.2000000000 0.0206937920 0.0294667426 0.0420191325 0.0135994631 0.1765220000 959492321 0 402718720 -0.1324660182 0.4912222624 0.9689825177 757 30.2400000000 0.0203664359 0.0294547210 0.0420191325 0.0135927275 0.1752820000 959494329 0 402718720 -0.1327925622 0.4898262620 0.9701051712 758 30.2800000000 0.0203226805 0.0294426735 0.0420191325 0.0135876991 0.1745670000 959496337 0 402718720 -0.1335642636 0.4911404252 0.9711841345 759 30.3200000000 0.0201271754 0.0294304001 0.0420191325 0.0135837674 0.1747120000 959498345 0 402718720 -0.1339974999 0.4903036952 0.9723319411 760 30.3600000000 0.0202723481 0.0294183500 0.0420191325 0.0135830157 0.1751990000 959500353 0 402718720 -0.1335908026 0.4879833758 0.9735327959 761 30.4000000000 0.0201986581 0.0294062348 0.0420191325 0.0135777294 0.1748850000 959502361 0 402718720 -0.1330804229 0.4877565205 0.9750757813 762 30.4400000000 0.0200411249 0.0293939446 0.0420191325 0.0135690454 0.1747310000 959504369 0 402718720 -0.1323165745 0.4872913361 0.9764862061 763 30.4800000000 0.0201293696 0.0293818023 0.0420191325 0.0135603287 0.2024540000 959506377 0 402718720 -0.1312371939 0.4847995043 0.9781510234 764 30.5200000000 0.0199142918 0.0293694103 0.0420191325 0.0135551732 0.2049310000 959508385 0 402718720 -0.1222544387 0.4829962254 0.9800627828 765 30.5600000000 0.0197724346 0.0293568652 0.0420191325 0.0135494849 0.1767240000 959510393 0 402718720 -0.1240263209 0.4815796316 0.9816876650 766 30.6000000000 0.0199264884 0.0293445540 0.0420191325 0.0135473193 0.1767590000 959512401 0 402718720 -0.1238969713 0.4800103307 0.9831674695 767 30.6400000000 0.0200257171 0.0293324043 0.0420191325 0.0135522802 0.1745550000 959514409 0 402718720 -0.1220857427 0.4770886302 0.9848942757 768 30.6800000000 0.0197106320 0.0293198759 0.0420191325 0.0135604522 0.1847740000 959516417 0 402718720 -0.1118911430 0.4761608243 0.9872150421 769 30.7200000000 0.0196401738 0.0293072886 0.0420191325 0.0136146926 0.1849590000 959518425 0 402718720 -0.1051974073 0.4739940166 0.9909739494 770 30.7600000000 0.0195027776 0.0292945554 0.0420191325 0.0136496609 0.1731500000 959520433 0 402718720 -0.1065277979 0.4694976509 0.9920518994 771 30.8000000000 0.0195576064 0.0292819264 0.0420191325 0.0136694115 0.1846390000 959522441 0 402718720 -0.0974980071 0.4670203328 0.9939228892 772 30.8400000000 0.0193984080 0.0292691240 0.0420191325 0.0136949271 0.1752540000 959524449 0 402718720 -0.0996929556 0.4660012722 0.9944197536 773 30.8800000000 0.0195689257 0.0292565752 0.0420191325 0.0137215189 0.1754690000 959526457 0 402718720 -0.0989134461 0.4631466866 0.9957466722 774 30.9200000000 0.0194399953 0.0292438923 0.0420191325 0.0137415595 0.1967610000 959528465 0 402718720 -0.0878293812 0.4589114785 0.9978265166 775 30.9600000000 0.0191655960 0.0292308880 0.0420191325 0.0137654555 0.1769320000 959530473 0 402718720 -0.0893786624 0.4571860135 0.9982616305 776 31.0000000000 0.0193052255 0.0292180972 0.0420191325 0.0137863705 0.1836690000 959532481 0 402718720 -0.0806013867 0.4542618990 1.0005626678 777 31.0400000000 0.0189382173 0.0292048670 0.0420191325 0.0138021919 0.1741070000 959534489 0 402718720 -0.0819550827 0.4525930583 1.0014749765 778 31.0800000000 0.0191985760 0.0291920054 0.0420191325 0.0138076491 0.1853060000 959536497 0 402718720 -0.0743021592 0.4487138391 1.0037822723 779 31.1200000000 0.0187617466 0.0291786161 0.0420191325 0.0138102515 0.1742400000 959538505 0 402718720 -0.0758051500 0.4457857907 1.0051159859 780 31.1600000000 0.0191809516 0.0291657986 0.0420191325 0.0138077076 0.1741630000 959540513 0 402718720 -0.0755361542 0.4429884553 1.0065994263 781 31.2000000000 0.0191207640 0.0291529369 0.0420191325 0.0138068502 0.1827780000 959542521 0 402718720 -0.0662976950 0.4387827218 1.0095605850 782 31.2400000000 0.0186534487 0.0291395104 0.0420191325 0.0138066258 0.1738160000 959544529 0 402718720 -0.0681058168 0.4352582693 1.0109782219 783 31.2800000000 0.0190133862 0.0291265779 0.0420191325 0.0138033602 0.1819590000 959546537 0 402718720 -0.0607445538 0.4307708442 1.0140008926 784 31.3200000000 0.0185207184 0.0291130501 0.0420191325 0.0138010820 0.1830200000 959548545 0 402718720 -0.0626162663 0.4262353182 1.0151156187 785 31.3600000000 0.0187423453 0.0290998390 0.0420191325 0.0137962927 0.1848780000 959550553 0 402718720 -0.0625109524 0.4218209684 1.0165199041 786 31.4000000000 0.0189337917 0.0290869051 0.0420191325 0.0137895171 0.1720080000 959552561 0 402718720 -0.0615303591 0.4182417393 1.0178433657 787 31.4400000000 0.0188771952 0.0290739321 0.0420191325 0.0137861351 0.1936800000 959554569 0 402718720 -0.0535521880 0.4115651846 1.0208437443 788 31.4800000000 0.0183537789 0.0290603279 0.0420191325 0.0137853748 0.1730680000 959556577 0 402718720 -0.0551146157 0.4071761370 1.0219936371 789 31.5200000000 0.0185940191 0.0290470626 0.0420191325 0.0137848685 0.1721720000 959558585 0 402718720 -0.0552850589 0.4025226235 1.0232917070 790 31.5600000000 0.0187785365 0.0290340644 0.0420191325 0.0137846000 0.1800540000 959560593 0 402718720 -0.0486953221 0.3954752684 1.0263693333 791 31.6000000000 0.0184138585 0.0290206381 0.0420191325 0.0138169283 0.2281030000 959562601 0 402718720 -0.0522898883 0.3871847987 1.0280097723 792 31.6400000000 0.0182928629 0.0290070930 0.0420191325 0.0138144558 0.2158080000 959564609 0 402718720 -0.0521738119 0.3831888437 1.0298855305 793 31.6800000000 0.0186048988 0.0289939754 0.0420191325 0.0138118221 0.2263530000 959566617 0 402718720 -0.0461973175 0.3761376143 1.0332740545 794 31.7200000000 0.0181765221 0.0289803515 0.0420191325 0.0138077928 0.2155760000 959568625 0 402718720 -0.0481069535 0.3750534654 1.0342751741 795 31.7600000000 0.0184927601 0.0289671595 0.0420191325 0.0138031500 0.2259440000 959570633 0 402718720 -0.0461953059 0.3734403551 1.0364642143 796 31.8000000000 0.0186134111 0.0289541523 0.0420191325 0.0138000023 0.2263110000 959572641 0 402718720 -0.0458018631 0.3680589199 1.0387333632 797 31.8400000000 0.0185879134 0.0289411457 0.0420191325 0.0138006567 0.2257410000 959574649 0 402718720 -0.0457446612 0.3623318076 1.0413641930 798 31.8800000000 0.0186538659 0.0289282544 0.0420191325 0.0138676955 0.2129220000 959576657 0 402718720 -0.0444367938 0.3442055285 1.0478491783 799 31.9200000000 0.0181337502 0.0289147444 0.0420191325 0.0138848018 0.1692390000 959578665 0 402718720 -0.0455821157 0.3362998068 1.0502127409 800 31.9600000000 0.0180920698 0.0289012160 0.0420191325 0.0138912998 0.1689250000 959580673 0 402718720 -0.0464770496 0.3320257664 1.0524233580 801 32.0000000000 0.0178352781 0.0288874009 0.0420191325 0.0138860712 0.1688530000 959582681 0 402718720 -0.0470589064 0.3283604980 1.0553846359 802 32.0400000000 0.0178166684 0.0288735970 0.0420191325 0.0138775050 0.1685990000 959584689 0 402718720 -0.0479324646 0.3204300106 1.0580995083 803 32.0800000000 0.0177845713 0.0288597875 0.0420191325 0.0138690313 0.1676950000 959586697 0 402718720 -0.0486734249 0.3111477494 1.0613170862 804 32.1199999990 0.0182135291 0.0288465459 0.0420191325 0.0138622108 0.1812560000 959588705 0 402718720 -0.0490226075 0.2957350314 1.0687520504 805 32.1600000000 0.0179187767 0.0288329710 0.0420191325 0.0138545439 0.1651180000 959590713 0 402718720 -0.0503374189 0.2918886542 1.0717703104 806 32.2000000000 0.0176954214 0.0288191527 0.0420191325 0.0138459479 0.1654060000 959592721 0 402718720 -0.0523386896 0.2868623435 1.0750281811 807 32.2400000000 0.0179171488 0.0288056434 0.0420191325 0.0138381371 0.1672550000 959594729 0 402718720 -0.0527776219 0.2783477306 1.0789840221 808 32.2800000000 0.0174753089 0.0287916207 0.0420191325 0.0138299705 0.1641420000 959596737 0 402718720 -0.0554866008 0.2726610601 1.0823580027 809 32.3200000000 0.0179033540 0.0287781618 0.0420191325 0.0138224730 0.1711460000 959598745 0 402718720 -0.0552437715 0.2586492300 1.0877511501 810 32.3600000000 0.0178526025 0.0287646734 0.0420191325 0.0138139599 0.1677770000 959600753 0 402718720 -0.0563954674 0.2469580919 1.0921037197 811 32.4000000000 0.0177210309 0.0287510561 0.0420191325 0.0138062662 0.1624660000 959602761 0 402718720 -0.0589708872 0.2435633093 1.0957559347 812 32.4399999990 0.0177599415 0.0287375203 0.0420191325 0.0138001693 0.1663400000 959604769 0 402718720 -0.0605501719 0.2371681333 1.1002597809 813 32.4800000000 0.0176848378 0.0287239253 0.0420191325 0.0137928327 0.1660060000 959606777 0 402718720 -0.0620030761 0.2277305126 1.1052000523 814 32.5200000000 0.0176528729 0.0287103245 0.0420191325 0.0137848515 0.1754720000 959608785 0 402718720 -0.0630462244 0.2166738659 1.1103670597 815 32.5600000000 0.0176316258 0.0286967310 0.0420191325 0.0137774345 0.1665500000 959610793 0 402718720 -0.0641265512 0.2069226652 1.1153966188 816 32.6000000000 0.0176765490 0.0286832259 0.0420191325 0.0137693116 0.1667350000 959612801 0 402718720 -0.0652344450 0.1998849511 1.1206445694 817 32.6400000000 0.0176434610 0.0286697133 0.0420191325 0.0137630346 0.1654650000 959614809 0 402718720 -0.0661415383 0.1870654225 1.1276583672 818 32.6800000000 0.0175986178 0.0286561790 0.0420191325 0.0137546565 0.1646590000 959616817 0 402718720 -0.0669687688 0.1707948148 1.1345695257 819 32.7200000000 0.0173508059 0.0286423751 0.0420191325 0.0137470775 0.1869730000 959618825 0 402718720 -0.0680956915 0.1608760953 1.1397514343 820 32.7599999990 0.0173361115 0.0286285870 0.0420191325 0.0137388561 0.1607950000 959620833 0 402718720 -0.0701919645 0.1546862870 1.1439259052 821 32.7999999990 0.0174402576 0.0286149593 0.0420191325 0.0137306586 0.1642100000 959622841 0 402718720 -0.0714212805 0.1459727436 1.1487443447 822 32.8400000000 0.0173997898 0.0286013156 0.0420191325 0.0137234490 0.1620360000 959624849 0 402718720 -0.0715406239 0.1343556792 1.1543085575 823 32.8800000000 0.0173466206 0.0285876403 0.0420191325 0.0137170714 0.1807630000 959626857 0 402718720 -0.0714392662 0.1225130633 1.1600608826 824 32.9200000000 0.0172922369 0.0285739323 0.0420191325 0.0137096597 0.1903550000 959628865 0 402718720 -0.0711297244 0.1117742062 1.1658066511 825 32.9600000000 0.0173174478 0.0285602881 0.0420191325 0.0137016726 0.1621210000 959630873 0 402718720 -0.0713579953 0.1021864936 1.1706410646 826 33.0000000000 0.0169132333 0.0285461876 0.0420191325 0.0136944389 0.1564610000 959632881 0 402718720 -0.0728451163 0.0936907008 1.1750999689 827 33.0400000000 0.0171373487 0.0285323921 0.0420191325 0.0136877328 0.1589660000 959634889 0 402718720 -0.0720364079 0.0835693181 1.1800544262 828 33.0800000000 0.0172061119 0.0285187130 0.0420191325 0.0136812614 0.1724760000 959636897 0 402718720 -0.0718606785 0.0759028718 1.1838523149 829 33.1199999990 0.0171538591 0.0285050039 0.0420191325 0.0136781030 0.1596550000 959638905 0 402718720 -0.0716889575 0.0650986880 1.1881928444 830 33.1600000000 0.0172191299 0.0284914065 0.0420191325 0.0136741334 0.1591910000 959640913 0 402718720 -0.0711551085 0.0519325919 1.1933959723 831 33.2000000000 0.0172574334 0.0284778879 0.0420191325 0.0136675736 0.1567720000 959642921 0 402718720 -0.0705404803 0.0404159315 1.1978387833 832 33.2400000000 0.0168569833 0.0284639204 0.0420191325 0.0136635269 0.1534890000 959644929 0 402718720 -0.0711274073 0.0323154144 1.2006597519 833 33.2800000000 0.0171119682 0.0284502926 0.0420191325 0.0136587939 0.1569850000 959646937 0 402718720 -0.0705847666 0.0222333930 1.2043809891 834 33.3200000000 0.0171085745 0.0284366934 0.0420191325 0.0136512049 0.1669320000 959648945 0 402718720 -0.0702369064 0.0132448766 1.2073800564 835 33.3600000000 0.0171474908 0.0284231734 0.0420191325 0.0136434428 0.1565430000 959650953 0 402718720 -0.0693466812 0.0060215504 1.2098404169 836 33.4000000000 0.0171280969 0.0284096626 0.0420191325 0.0136395262 0.1577000000 959652961 0 402718720 -0.0678472146 -0.0022552980 1.2129795551 837 33.4399999990 0.0172381550 0.0283963155 0.0420191325 0.0136385837 0.1579990000 959654969 0 402718720 -0.0666959956 -0.0130541129 1.2165284157 838 33.4800000000 0.0172110833 0.0283829680 0.0420191325 0.0136338294 0.1574190000 959656977 0 402718720 -0.0656058043 -0.0230007153 1.2194652557 839 33.5200000000 0.0170805659 0.0283694967 0.0420191325 0.0136259080 0.1506390000 959658985 0 402718720 -0.0652559102 -0.0314270034 1.2213920355 840 33.5600000000 0.0170478374 0.0283560185 0.0420191325 0.0136180390 0.1520870000 959660993 0 402718720 -0.0650110394 -0.0378514417 1.2225774527 841 33.6000000000 0.0175086409 0.0283431203 0.0420191325 0.0136172140 0.1615560000 959663001 0 402718720 -0.0620387569 -0.0504349880 1.2267383337 842 33.6400000000 0.0174515527 0.0283301850 0.0420191325 0.0136096892 0.1550870000 959665009 0 402718720 -0.0605810396 -0.0634638816 1.2308380604 843 33.6800000000 0.0182344709 0.0283182090 0.0420191325 0.0136019691 0.1516000000 959667017 0 402718720 -0.0583329350 -0.0696974471 1.2318911552 844 33.7200000000 0.0180591345 0.0283060537 0.0420191325 0.0135995341 0.1631700000 959669025 0 402718720 -0.0576403514 -0.0765649527 1.2326958179 845 33.7599999990 0.0179281570 0.0282937722 0.0420191325 0.0136018359 0.1557270000 959671033 0 402718720 -0.0578251593 -0.0873223618 1.2343119383 846 33.7999999990 0.0180027485 0.0282816079 0.0420191325 0.0135989722 0.1509190000 959673041 0 402718720 -0.0571737774 -0.0927421376 1.2347151041 847 33.8400000000 0.0178852510 0.0282693335 0.0420191325 0.0135986546 0.1509530000 959675049 0 402718720 -0.0570341237 -0.0978292897 1.2347314358 848 33.8800000000 0.0179980341 0.0282572212 0.0420191325 0.0135960312 0.1549080000 959677057 0 402718720 -0.0554975495 -0.1093705446 1.2380098104 849 33.9200000000 0.0188210644 0.0282461067 0.0420191325 0.0135891739 0.1632010000 959679065 0 402718720 -0.0539715514 -0.1169112846 1.2395578623 850 33.9600000000 0.0196482744 0.0282359916 0.0420191325 0.0135837196 0.1514530000 959681073 0 402718720 -0.0537863560 -0.1210881025 1.2390307188 851 34.0000000000 0.0193591136 0.0282255605 0.0420191325 0.0135770649 0.1682610000 959683081 0 402718720 -0.0549996570 -0.1279062182 1.2394468784 852 34.0400000000 0.0196502805 0.0282154956 0.0420191325 0.0135699294 0.1499160000 959685089 0 402718720 -0.0554436184 -0.1327126324 1.2391122580 853 34.0800000000 0.0195450298 0.0282053310 0.0420191325 0.0135670800 0.1504340000 959687097 0 402718720 -0.0559304953 -0.1370193064 1.2386133671 854 34.1199999990 0.0192028712 0.0281947894 0.0420191325 0.0135659522 0.1652120000 959689105 0 402718720 -0.0566681363 -0.1442549825 1.2388926744 855 34.1600000000 0.0195822008 0.0281847162 0.0420191325 0.0135597835 0.1514810000 959691113 0 402718720 -0.0564361736 -0.1499287039 1.2393050194 856 34.2000000000 0.0188799407 0.0281738462 0.0420191325 0.0135531590 0.1561050000 959693121 0 402718720 -0.0573184341 -0.1512695849 1.2377488613 857 34.2400000000 0.0192939658 0.0281634846 0.0420191325 0.0135508063 0.1509650000 959695129 0 402718720 -0.0567673333 -0.1541459560 1.2365491390 858 34.2800000000 0.0191002283 0.0281529214 0.0420191325 0.0135510489 0.1502410000 959697137 0 402718720 -0.0559240952 -0.1571646631 1.2358076572 859 34.3200000000 0.0194073673 0.0281427403 0.0420191325 0.0135554327 0.1486030000 959699145 0 402718720 -0.0549527816 -0.1592973620 1.2342919111 860 34.3600000000 0.0192793068 0.0281324339 0.0420191325 0.0135541067 0.1517970000 959701153 0 402718720 -0.0536862388 -0.1613961607 1.2331377268 861 34.4000000000 0.0194332749 0.0281223304 0.0420191325 0.0135514537 0.1518320000 959703161 0 402718720 -0.0512601584 -0.1626316756 1.2326011658 862 34.4400000000 0.0193053763 0.0281121019 0.0420191325 0.0135614145 0.1520420000 959705169 0 402718720 -0.0493761040 -0.1654945910 1.2321622372 863 34.4800000000 0.0195834264 0.0281022193 0.0420191325 0.0135715652 0.1521640000 959707177 0 402718720 -0.0478896685 -0.1695890278 1.2318865061 864 34.5200000000 0.0204531141 0.0280933662 0.0420191325 0.0135790771 0.1631330000 959709185 0 402718720 -0.0469236188 -0.1699955165 1.2297167778 865 34.5600000000 0.0197224375 0.0280836888 0.0420191325 0.0135823021 0.1506940000 959711193 0 402718720 -0.0463421308 -0.1705936939 1.2281248569 866 34.6000000000 0.0193400402 0.0280735922 0.0420191325 0.0135815673 0.1526060000 959713201 0 402718720 -0.0454685502 -0.1743559539 1.2275876999 867 34.6400000000 0.0201639719 0.0280644692 0.0420191325 0.0135772554 0.1529690000 959715209 0 402718720 -0.0438542590 -0.1767972559 1.2268332243 868 34.6800000000 0.0203416571 0.0280555720 0.0420191325 0.0135714456 0.1508490000 959717217 0 402718720 -0.0425194353 -0.1778179556 1.2253344059 869 34.7200000000 0.0199781675 0.0280462769 0.0420191325 0.0135652717 0.1647800000 959719225 0 402718720 -0.0420819558 -0.1800491810 1.2245272398 870 34.7600000000 0.0198626947 0.0280368705 0.0420191325 0.0135586205 0.1531150000 959721233 0 402718720 -0.0415232219 -0.1826969236 1.2237740755 871 34.8000000000 0.0197854843 0.0280273971 0.0420191325 0.0135536497 0.1533420000 959723241 0 402718720 -0.0414175726 -0.1861732155 1.2229081392 872 34.8400000000 0.0199009888 0.0280180778 0.0420191325 0.0135482514 0.1518560000 959725249 0 402718720 -0.0417613909 -0.1904056370 1.2228013277 873 34.8800000000 0.0203813072 0.0280093301 0.0420191325 0.0135411121 0.1525300000 959727257 0 402718720 -0.0413536131 -0.1935540885 1.2223228216 874 34.9200000000 0.0205419306 0.0280007861 0.0420191325 0.0135342901 0.1636680000 959729265 0 402718720 -0.0409045517 -0.1955004334 1.2212492228 875 34.9600000000 0.0202055518 0.0279918773 0.0420191325 0.0135276523 0.1535080000 959731273 0 402718720 -0.0412799641 -0.1983240396 1.2206364870 876 35.0000000000 0.0203447770 0.0279831477 0.0420191325 0.0135201592 0.1535520000 959733281 0 402718720 -0.0408372618 -0.2012410760 1.2204782963 877 35.0400000000 0.0204501599 0.0279745582 0.0420191325 0.0135125504 0.1535650000 959735289 0 402718720 -0.0407055169 -0.2035185099 1.2193694115 878 35.0800000000 0.0201819856 0.0279656828 0.0420191325 0.0135051333 0.1534010000 959737297 0 402718720 -0.0408166237 -0.2068469077 1.2185229063 879 35.1200000000 0.0204220787 0.0279571008 0.0420191325 0.0134975712 0.1522470000 959739305 0 402718720 -0.0406706221 -0.2102695704 1.2179790735 880 35.1600000000 0.0211821049 0.0279494020 0.0420191325 0.0134903721 0.1522780000 959741313 0 402718720 -0.0401458405 -0.2156259567 1.2157737017 881 35.2000000000 0.0209447257 0.0279414511 0.0420191325 0.0134834536 0.1525690000 959743321 0 402718720 -0.0404687449 -0.2167038321 1.2140619755 882 35.2400000000 0.0201983266 0.0279326721 0.0420191325 0.0134784931 0.1510020000 959745329 0 402718720 -0.0411092415 -0.2186512500 1.2127699852 883 35.2800000000 0.0202353876 0.0279239549 0.0420191325 0.0134745090 0.1535800000 959747337 0 402718720 -0.0416135453 -0.2213852704 1.2113732100 884 35.3200000000 0.0204178784 0.0279154638 0.0420191325 0.0134740865 0.1794510000 959749345 0 402718720 -0.0423995368 -0.2237182260 1.2094219923 885 35.3600000000 0.0203190725 0.0279068804 0.0420191325 0.0134773127 0.1528800000 959751353 0 402718720 -0.0438279323 -0.2257957458 1.2077279091 886 35.4000000000 0.0204770789 0.0278984946 0.0420191325 0.0134809679 0.1544010000 959753361 0 402718720 -0.0456560887 -0.2277748138 1.2059544325 887 35.4400000000 0.0207087807 0.0278903889 0.0420191325 0.0134861598 0.1547790000 959755369 0 402718720 -0.0473909490 -0.2289526314 1.2040563822 888 35.4800000000 0.0202484149 0.0278817831 0.0420191325 0.0134896174 0.1543580000 959757377 0 402718720 -0.0493707433 -0.2306253612 1.2021684647 889 35.5200000000 0.0205502138 0.0278735361 0.0420191325 0.0134991728 0.1524610000 959759385 0 402718720 -0.0504986346 -0.2323835045 1.2004890442 890 35.5600000000 0.0207776111 0.0278655632 0.0420191325 0.0135063492 0.1544140000 959761393 0 402718720 -0.0519955270 -0.2329413444 1.1986774206 891 35.6000000000 0.0200172178 0.0278567547 0.0420191325 0.0135126288 0.1525160000 959763401 0 402718720 -0.0539801903 -0.2351885438 1.1973108053 892 35.6400000000 0.0207804572 0.0278488216 0.0420191325 0.0135231789 0.1664850000 959765409 0 402718720 -0.0554172322 -0.2371441871 1.1953979731 893 35.6800000000 0.0208816957 0.0278410197 0.0420191325 0.0135350868 0.1542400000 959767417 0 402718720 -0.0574051701 -0.2377688289 1.1935011148 894 35.7200000000 0.0203629024 0.0278326549 0.0420191325 0.0135489817 0.1669620000 959769425 0 402718720 -0.0595370047 -0.2394425571 1.1921718121 895 35.7600000000 0.0206635054 0.0278246447 0.0420191325 0.0135660686 0.1535830000 959771433 0 402718720 -0.0615367107 -0.2419776917 1.1909366846 896 35.8000000000 0.0216184314 0.0278177181 0.0420191325 0.0135905087 0.1509530000 959773441 0 402718720 -0.0632731542 -0.2430316508 1.1891764402 897 35.8400000000 0.0218234565 0.0278110355 0.0420191325 0.0136091052 0.1541340000 959775449 0 402718720 -0.0648821443 -0.2427848577 1.1880623102 898 35.8800000000 0.0213357322 0.0278038247 0.0420191325 0.0136197840 0.1658450000 959777457 0 402718720 -0.0664012656 -0.2429364026 1.1867129803 899 35.9200000000 0.0215383209 0.0277968553 0.0420191325 0.0136304331 0.1647560000 959779465 0 402718720 -0.0673972592 -0.2432807088 1.1864515543 900 35.9600000000 0.0216837376 0.0277900630 0.0420191325 0.0136350446 0.1516530000 959781473 0 402718720 -0.0684635118 -0.2438723147 1.1855711937 901 36.0000000000 0.0199736673 0.0277813877 0.0420191325 0.0136449755 0.1652880000 959783481 0 402718720 -0.0597346202 -0.2432151586 1.1876677275 902 36.0400000000 0.0201866776 0.0277729679 0.0420191325 0.0136633099 0.1513190000 959785489 0 402718720 -0.0643741190 -0.2442917228 1.1857798100 903 36.0800000000 0.0203306433 0.0277647261 0.0420191325 0.0136788180 0.1507410000 959787497 0 402718720 -0.0681886524 -0.2447083443 1.1835085154 904 36.1200000000 0.0202391036 0.0277564013 0.0420191325 0.0137013266 0.1610620000 959789505 0 402718720 -0.0708301887 -0.2454217523 1.1823446751 905 36.1600000000 0.0205166899 0.0277484016 0.0420191325 0.0137249401 0.1517710000 959791513 0 402718720 -0.0724764392 -0.2460740060 1.1810169220 906 36.2000000000 0.0205364134 0.0277404414 0.0420191325 0.0137509421 0.1515850000 959793521 0 402718720 -0.0741910338 -0.2459186316 1.1799361706 907 36.2400000000 0.0200506356 0.0277319631 0.0420191325 0.0137739024 0.1514240000 959795529 0 402718720 -0.0755234286 -0.2467315048 1.1793625355 908 36.2800000000 0.0204612650 0.0277239557 0.0420191325 0.0137892137 0.1495340000 959797537 0 402718720 -0.0765820220 -0.2470659018 1.1787489653 909 36.3200000000 0.0202465300 0.0277157297 0.0420191325 0.0137988048 0.1494090000 959799545 0 402718720 -0.0779918730 -0.2471318245 1.1780585051 910 36.3600000000 0.0200020783 0.0277072532 0.0420191325 0.0138061856 0.1472670000 959801553 0 402718720 -0.0793922991 -0.2474712729 1.1775286198 911 36.4000000000 0.0197881181 0.0276985604 0.0420191325 0.0138137349 0.1469400000 959803561 0 402718720 -0.0805836245 -0.2483354658 1.1771792173 912 36.4400000000 0.0199141223 0.0276900248 0.0420191325 0.0138192151 0.1487000000 959805569 0 402718720 -0.0819601938 -0.2499233037 1.1770603657 913 36.4800000000 0.0199370552 0.0276815330 0.0420191325 0.0138700471 0.1621290000 959807577 0 402718720 -0.0784475207 -0.2498166114 1.1787953377 914 36.5200000000 0.0194308348 0.0276725060 0.0420191325 0.0138997519 0.1594930000 959809585 0 402718720 -0.0821529478 -0.2502720952 1.1774232388 915 36.5600000000 0.0194673259 0.0276635386 0.0420191325 0.0139208131 0.1475200000 959811593 0 402718720 -0.0849470273 -0.2506557107 1.1767660379 916 36.6000000000 0.0194976330 0.0276546239 0.0420191325 0.0139403597 0.1486100000 959813601 0 402718720 -0.0875059217 -0.2508153617 1.1759465933 917 36.6400000000 0.0194721650 0.0276457008 0.0420191325 0.0139542350 0.1741740000 959815609 0 402718720 -0.0899398103 -0.2511565089 1.1753114462 918 36.6800000000 0.0194336157 0.0276367552 0.0420191325 0.0139689293 0.1481080000 959817617 0 402718720 -0.0920430049 -0.2516129017 1.1748406887 919 36.7200000000 0.0194313414 0.0276278265 0.0420191325 0.0139868822 0.1461820000 959819625 0 402718720 -0.0937860683 -0.2521418333 1.1746361256 920 36.7600000000 0.0195417628 0.0276190373 0.0420191325 0.0140044632 0.1472380000 959821633 0 402718720 -0.0953342021 -0.2520675063 1.1741652489 921 36.8000000000 0.0191103071 0.0276097988 0.0420191325 0.0140162630 0.1463690000 959823641 0 402718720 -0.0973683670 -0.2521750033 1.1741021872 922 36.8400000000 0.0191997401 0.0276006772 0.0420191325 0.0140250312 0.1466190000 959825649 0 402718720 -0.0994556099 -0.2530124485 1.1742644310 923 36.8800000000 0.0195953771 0.0275920041 0.0420191325 0.0140310381 0.1454300000 959827657 0 402718720 -0.1014418826 -0.2539057732 1.1747139692 924 36.9200000000 0.0199257825 0.0275837073 0.0420191325 0.0140338571 0.1641490000 959829665 0 402718720 -0.1032924950 -0.2548606098 1.1747059822 925 36.9600000000 0.0201386698 0.0275756586 0.0420191325 0.0140372283 0.1445420000 959831673 0 402718720 -0.1049457416 -0.2552177012 1.1747679710 926 37.0000000000 0.0198548362 0.0275673208 0.0420191325 0.0140417594 0.1455010000 959833681 0 402718720 -0.1063141078 -0.2550747395 1.1747921705 927 37.0400000000 0.0194523521 0.0275585668 0.0420191325 0.0140489424 0.1449950000 959835689 0 402718720 -0.1075556725 -0.2553487420 1.1752195358 928 37.0800000000 0.0197547060 0.0275501575 0.0420191325 0.0140595127 0.1446330000 959837697 0 402718720 -0.1088954806 -0.2553336620 1.1753758192 929 37.1200000000 0.0195206832 0.0275415143 0.0420191325 0.0140721891 0.1545940000 959839705 0 402718720 -0.1106436625 -0.2542930841 1.1747000217 930 37.1600000000 0.0189960282 0.0275323256 0.0420191325 0.0140826897 0.1417830000 959841713 0 402718720 -0.1126195788 -0.2532262802 1.1739957333 931 37.2000000000 0.0203042440 0.0275245618 0.0420191325 0.0140914039 0.1547390000 959843721 0 402718720 -0.1076677740 -0.2541071773 1.1782491207 932 37.2400000000 0.0194710381 0.0275159207 0.0420191325 0.0141215711 0.1402840000 959845729 0 402718720 -0.1121063903 -0.2542715371 1.1756441593 933 37.2800000000 0.0192546472 0.0275070662 0.0420191325 0.0141573218 0.1396770000 959847737 0 402718720 -0.1154597774 -0.2537114024 1.1731212139 934 37.3200000000 0.0190893617 0.0274980537 0.0420191325 0.0141892406 0.1480480000 959849745 0 402718720 -0.1185342968 -0.2522775531 1.1715308428 935 37.3600000000 0.0205395594 0.0274906114 0.0420191325 0.0141995140 0.1484330000 959851753 0 402718720 -0.1150340736 -0.2521467209 1.1739708185 936 37.4000000000 0.0190216992 0.0274815634 0.0420191325 0.0142255919 0.1384830000 959853761 0 402718720 -0.1198993400 -0.2512865663 1.1708223820 937 37.4400000000 0.0206435043 0.0274742656 0.0420191325 0.0142305348 0.1466970000 959855769 0 402718720 -0.1180144027 -0.2504366636 1.1727745533 938 37.4800000000 0.0185670480 0.0274647697 0.0420191325 0.0142439422 0.1350140000 959857777 0 402718720 -0.1229596883 -0.2491407096 1.1695947647 939 37.5200000000 0.0207112674 0.0274575774 0.0420191325 0.0142480357 0.1449460000 959859785 0 402718720 -0.1205895171 -0.2502608299 1.1719955206 940 37.5600000000 0.0191181414 0.0274487057 0.0420191325 0.0142581596 0.1347930000 959861793 0 402718720 -0.1250188351 -0.2494849712 1.1689215899 941 37.6000000000 0.0207924694 0.0274416321 0.0420191325 0.0142614410 0.1433720000 959863801 0 402718720 -0.1232563183 -0.2495560646 1.1703536510 942 37.6400000000 0.0187285021 0.0274323825 0.0420191325 0.0142698906 0.1329520000 959865809 0 402718720 -0.1279328614 -0.2483028024 1.1662660837 943 37.6800000000 0.0208720732 0.0274254256 0.0420191325 0.0142750290 0.1393300000 959867817 0 402718720 -0.1256076545 -0.2497595847 1.1684845686 944 37.7200000000 0.0187796783 0.0274162670 0.0420191325 0.0142849894 0.1449670000 959869825 0 402718720 -0.1297259629 -0.2489652783 1.1658122540 945 37.7600000000 0.0182866044 0.0274066060 0.0420191325 0.0142905838 0.1303470000 959871833 0 402718720 -0.1323109418 -0.2485074401 1.1659165621 946 37.8000000000 0.0209333990 0.0273997633 0.0420191325 0.0142940147 0.1370320000 959873841 0 402718720 -0.1293871105 -0.2502039969 1.1693853140 947 37.8400000000 0.0195709690 0.0273914963 0.0420191325 0.0143016422 0.1275900000 959875849 0 402718720 -0.1330404133 -0.2494380623 1.1668908596 948 37.8800000000 0.0186320543 0.0273822564 0.0420191325 0.0143033181 0.1265650000 959877857 0 402718720 -0.1357155591 -0.2488724738 1.1672706604 949 37.9200000000 0.0208563805 0.0273753798 0.0420191325 0.0143063118 0.1354360000 959879865 0 402718720 -0.1334730238 -0.2439487725 1.1795601845 950 37.9600000000 0.0195448864 0.0273671372 0.0420191325 0.0143112779 0.1247800000 959881873 0 402718720 -0.1375165582 -0.2400222868 1.1854209900 951 38.0000000000 0.0206738561 0.0273600991 0.0420191325 0.0143162562 0.1332850000 959883881 0 402718720 -0.1365518570 -0.2375859618 1.1923769712 952 38.0400000000 0.0193844829 0.0273517213 0.0420191325 0.0143224787 0.1234970000 959885889 0 402718720 -0.1398647279 -0.2365238816 1.1903238297 953 38.0800000000 0.0187639836 0.0273427101 0.0420191325 0.0143203345 0.1494370000 959887897 0 402718720 -0.1421299279 -0.2359608859 1.1896846294 954 38.1200000000 0.0206944868 0.0273357413 0.0420191325 0.0143226212 0.1539560000 959889905 0 402718720 -0.1397528052 -0.2360832244 1.1942946911 955 38.1600000000 0.0197914466 0.0273278415 0.0420191325 0.0143295940 0.1230000000 959891913 0 402718720 -0.1425182670 -0.2363286763 1.1911989450 956 38.2000000000 0.0195024740 0.0273196560 0.0420191325 0.0143324348 0.1224740000 959893921 0 402718720 -0.1444116235 -0.2356175184 1.1907377243 957 38.2400000000 0.0209522080 0.0273130024 0.0420191325 0.0143330510 0.1316710000 959895929 0 402718720 -0.1430851072 -0.2350891232 1.1922993660 958 38.2800000000 0.0208556652 0.0273062620 0.0420191325 0.0143337925 0.1218170000 959897937 0 402718720 -0.1458287686 -0.2358582616 1.1896555424 959 38.3200000000 0.0212947316 0.0272999934 0.0420191325 0.0143338514 0.1337820000 959899945 0 402718720 -0.1476684660 -0.2360809892 1.1896554232 960 38.3600000000 0.0227407794 0.0272952442 0.0420191325 0.0143325040 0.1305730000 959901953 0 402718720 -0.1465007812 -0.2350691706 1.1927063465 961 38.4000000000 0.0244275872 0.0272922602 0.0420191325 0.0143319629 0.1199760000 959903961 0 402718720 -0.1492595524 -0.2353588194 1.1935247183 962 38.4400000000 0.0303349439 0.0272954231 0.0420191325 0.0143371171 0.1293720000 959905969 0 402718720 -0.1488795429 -0.2354091853 1.2001607418 963 38.4800000000 0.0360720903 0.0273045370 0.0420191325 0.0143374161 0.1190260000 959907977 0 402718720 -0.1517714858 -0.2361316383 1.2041254044 964 38.5200000000 0.0449727103 0.0273228649 0.0449727103 0.0143471175 0.1386980000 959909985 0 402718720 -0.1515143216 -0.2353933901 1.2147560120 965 38.5600000000 0.0514676496 0.0273478854 0.0514676496 0.0143506465 0.1307880000 959911993 0 402718720 -0.1546528935 -0.2345163226 1.2202115059 966 38.6000000000 0.0648186579 0.0273866751 0.0648186579 0.0143731803 0.1272060000 959914001 0 402718720 -0.1539886296 -0.2345598191 1.2333751917 967 38.6400000000 0.0734549165 0.0274343154 0.0734549165 0.0143807375 0.1390430000 959916009 0 402718720 -0.1554574519 -0.2329854071 1.2445851564 968 38.6800000000 0.0864486918 0.0274952807 0.0864486918 0.0143936287 0.1263700000 959918017 0 402718720 -0.1568133086 -0.2340876162 1.2554651499 969 38.7200000000 0.0929288343 0.0275628076 0.0929288343 0.0144063417 0.1165890000 959920025 0 402718720 -0.1599896848 -0.2324297577 1.2625854015 970 38.7600000000 0.1112266108 0.0276490589 0.1112266108 0.0144330886 0.1260230000 959922033 0 402718720 -0.1595700532 -0.2330017090 1.2795194387 971 38.8000000000 0.1255451590 0.0277498788 0.1255451590 0.0144454784 0.1253990000 959924041 0 402718720 -0.1610677689 -0.2334929705 1.2918050289 972 38.8400000000 0.1392100602 0.0278645498 0.1392100602 0.0144564244 0.1250230000 959926049 0 402718720 -0.1626030505 -0.2325053513 1.3051025867 973 38.8800000000 0.1557239741 0.0279959572 0.1557239741 0.0144716496 0.1260500000 959928057 0 402718720 -0.1638046950 -0.2322797030 1.3205134869 974 38.9200000000 0.1708950996 0.0281426709 0.1708950996 0.0144825360 0.1343950000 959930065 0 402718720 -0.1651333272 -0.2311598510 1.3359320164 975 38.9600000000 0.1888488233 0.0283074977 0.1888488233 0.0144991758 0.1255320000 959932073 0 402718720 -0.1665213704 -0.2299051434 1.3534085751 976 39.0000000000 0.2075258493 0.0284911231 0.2075258493 0.0145161171 0.1240560000 959934081 0 402718720 -0.1679320484 -0.2302846760 1.3705019951 977 39.0400000000 0.2256765664 0.0286929506 0.2256765664 0.0145304765 0.1291740000 959936089 0 402718720 -0.1692129374 -0.2289940715 1.3881837130 978 39.0800000000 0.2460968345 0.0289152449 0.2460968345 0.0145487990 0.1221880000 959938097 0 402718720 -0.1704498231 -0.2284858227 1.4066938162 979 39.1200000000 0.2657327354 0.0291571423 0.2657327354 0.0145680444 0.1219040000 959940105 0 402718720 -0.1715205312 -0.2291717082 1.4235545397 980 39.1600000000 0.2854705751 0.0294186866 0.2854705751 0.0145853919 0.1228430000 959942113 0 402718720 -0.1728757620 -0.2282081693 1.4415867329 981 39.2000000000 0.3046162724 0.0296992142 0.3046162724 0.0146032465 0.1237430000 959944121 0 402718720 -0.1739346981 -0.2279262990 1.4601465464 982 39.2400000000 0.3241644204 0.0299990769 0.3241644204 0.0146166609 0.1236800000 959946129 0 402718720 -0.1751502305 -0.2272388488 1.4779692888 983 39.2800000000 0.3462974727 0.0303208454 0.3462974727 0.0146389979 0.1281850000 959948137 0 402718720 -0.1762010306 -0.2261932343 1.4986028671 984 39.3200000000 0.3714155257 0.0306674863 0.3714155257 0.0146672498 0.1329630000 959950145 0 402718720 -0.1773167849 -0.2253330946 1.5228136778 985 39.3600000000 0.4089712501 0.0310515510 0.4089712501 0.0147328787 0.1272600000 959952153 0 402718720 -0.1785263717 -0.2245095819 1.5577493906 986 39.4000000000 0.4505655468 0.0314770216 0.4505655468 0.0148160262 0.1265800000 959954161 0 402718720 -0.1795420796 -0.2235055268 1.5977530479 987 39.4400000000 0.4900292456 0.0319416136 0.4900292456 0.0148713231 0.1393640000 959956169 0 402718720 -0.1810346991 -0.2227242887 1.6355456114 988 39.4800000000 0.5522737503 0.0324682655 0.5522737503 0.0150602860 0.1421360000 959958177 0 402718720 -0.1816186905 -0.2228040993 1.6963210106 989 39.5200000000 0.6153279543 0.0330576080 0.6153279543 0.0151820107 0.1371370000 959960185 0 402718720 -0.1839631200 -0.2208201289 1.7567816973 990 39.5600000000 0.6971897483 0.0337284485 0.6971897483 0.0153995862 0.1360030000 959962193 0 402718720 -0.1863397807 -0.2181752026 1.8374106884 991 39.6000000000 0.7722241879 0.0344736511 0.7722241879 0.0155913402 0.1477950000 959964201 0 402718720 -0.1886992157 -0.2161411941 1.9097508192 992 39.6400000000 0.8292462230 0.0352748331 0.8292462230 0.0157033321 0.1480070000 959966209 0 402718720 -0.1905119717 -0.2143338025 1.9647302628 993 39.6800000000 0.8707326055 0.0361161803 0.8707326055 0.0157625354 0.1395480000 959968217 0 402718720 -0.1917951703 -0.2135421783 2.0043275356 994 39.7200000000 0.9073922634 0.0369927156 0.9073922634 0.0158562397 0.1479210000 959970225 0 402718720 -0.1915558577 -0.2154856622 2.0374615192 995 39.7600000000 0.9291021824 0.0378893080 0.9291021824 0.0158587158 0.1645930000 959972233 0 402718720 -0.1926573962 -0.2138336450 2.0560352802 996 39.8000000000 0.9540396333 0.0388091377 0.9540396333 0.0158767332 0.1647530000 959974241 0 402718720 -0.1947312653 -0.2102005631 2.0785067081 997 39.8400000000 0.9717635512 0.0397448994 0.9717635512 0.0159230030 0.1479230000 959976249 0 402718720 -0.1943657249 -0.2107795775 2.0946781635 998 39.8800000000 0.9816277623 0.0406886698 0.9816277623 0.0159173305 0.1312000000 959978257 0 402718720 -0.1964488477 -0.2067633420 2.1024250984 999 39.9200000000 1.0020604134 0.0416510039 1.0020604134 0.0160145860 0.1481440000 959980265 0 402718720 -0.1960287392 -0.2074359804 2.1182246208 1000 39.9600000000 1.0072472095 0.0426166001 1.0072472095 0.0160078728 0.1316860000 959982273 0 402718720 -0.1979870200 -0.2033542544 2.1215252876 1001 40.0000000000 1.0137996674 0.0435868129 1.0137996674 0.0160011225 0.1319230000 959984281 0 402718720 -0.1999483258 -0.1992906630 2.1256296635 1002 40.0400000000 1.0208845139 0.0445621599 1.0208845139 0.0159958033 0.1319490000 959986289 0 402718720 -0.2012099028 -0.1961517781 2.1305077076 1003 40.0800000000 1.0347433090 0.0455493794 1.0347433090 0.0161339584 0.1482710000 959988297 0 402718720 -0.1980114877 -0.2023747861 2.1427979469 1004 40.1200000000 1.0372942686 0.0465371731 1.0372942686 0.0161262125 0.1321190000 959990305 0 402718720 -0.1994086504 -0.1989938468 2.1418919563 1005 40.1600000000 1.0395654440 0.0475252610 1.0395654440 0.0161184759 0.1182030000 959992313 0 402718720 -0.2008781135 -0.1949122250 2.1433219910 1006 40.2000000000 1.0451117754 0.0485168977 1.0451117754 0.0161118781 0.1073340000 959994321 0 402718720 -0.2020367235 -0.1915108413 2.1461839676 1007 40.2400000000 1.0592057705 0.0495205609 1.0592057705 0.0162516515 0.1209740000 959996329 0 402718720 -0.1990146488 -0.1992894262 2.1569344997 1008 40.2800000000 1.0619271994 0.0505249325 1.0619271994 0.0162481907 0.1073440000 959998337 0 402718720 -0.2009507269 -0.1938698143 2.1573109627 1009 40.3200000000 1.0689874887 0.0515343107 1.0689874887 0.0162428040 0.1079180000 960000345 0 402718720 -0.2023442239 -0.1889585257 2.1613330841 1010 40.3600000000 1.0779082775 0.0525505225 1.0779082775 0.0163630945 0.1207900000 960002353 0 402718720 -0.1994839907 -0.1975619197 2.1668524742 1011 40.4000000000 1.0799242258 0.0535667181 1.0799242258 0.0163552822 0.1088200000 960004361 0 402718720 -0.2011772990 -0.1915443689 2.1649789810 1012 40.4400000000 1.0815986395 0.0545825599 1.0815986395 0.0163474701 0.1078700000 960006369 0 402718720 -0.2021387219 -0.1867814809 2.1636812687 1013 40.4800000000 1.0838661194 0.0555986345 1.0838661194 0.0163398563 0.1094320000 960008377 0 402718720 -0.2028074414 -0.1828215569 2.1633167267 1014 40.5200000000 1.0852462053 0.0566140660 1.0852462053 0.0164552409 0.1341360000 960010385 0 402718720 -0.2003248334 -0.1917525530 2.1626336575 1015 40.5600000000 1.0849932432 0.0576272475 1.0852462053 0.0164482092 0.1101060000 960012393 0 402718720 -0.2023012787 -0.1835795343 2.1600561142 1016 40.6000000000 1.0858229399 0.0586392511 1.0858229399 0.0164403840 0.1100530000 960014401 0 402718720 -0.2034424990 -0.1780128032 2.1591119766 1017 40.6400000000 1.0880993605 0.0596515030 1.0880993605 0.0164329845 0.1095070000 960016409 0 402718720 -0.2042313069 -0.1732767820 2.1586370468 1018 40.6800000000 1.0912106037 0.0606648223 1.0912106037 0.0164267696 0.1098960000 960018417 0 402718720 -0.2051472664 -0.1679957956 2.1595878601 1019 40.7200000000 1.0947515965 0.0616796278 1.0947515965 0.0164235294 0.1112700000 960020425 0 402718720 -0.2060438991 -0.1635266244 2.1610076427 1020 40.7600000000 1.0976406336 0.0626952758 1.0976406336 0.0164203278 0.1124870000 960022433 0 402718720 -0.2067237198 -0.1601507068 2.1624155045 1021 40.8000000000 1.1013346910 0.0637125524 1.1013346910 0.0164177199 0.1127500000 960024441 0 402718720 -0.2074196339 -0.1564955860 2.1639468670 1022 40.8400000000 1.1034932137 0.0647299503 1.1034932137 0.0164142006 0.1126950000 960026449 0 402718720 -0.2081001997 -0.1532379240 2.1649315357 1023 40.8800000000 1.1053048372 0.0657471301 1.1053048372 0.0164099908 0.1121380000 960028457 0 402718720 -0.2088933736 -0.1492864192 2.1655826569 1024 40.9200000000 1.1077932119 0.0667647532 1.1077932119 0.0164104383 0.1218060000 960030465 0 402718720 -0.2097165734 -0.1455537826 2.1664001942 1025 40.9600000000 1.1094703674 0.0677820270 1.1094703674 0.0164132453 0.1113230000 960032473 0 402718720 -0.2102681249 -0.1417897493 2.1667444706 1026 41.0000000000 1.1118273735 0.0687996150 1.1118273735 0.0164108386 0.1116400000 960239281 0 402718720 -0.2111185193 -0.1356564164 2.1664113998 1027 41.0400000000 1.1126663685 0.0698160384 1.1126663685 0.0164101510 0.1140580000 960241289 0 402718720 -0.2118269801 -0.1317240447 2.1651077271 1028 41.0800000000 1.1130020618 0.0708308108 1.1130020618 0.0164098321 0.1128650000 960243297 0 402718720 -0.2123733014 -0.1271811277 2.1640653610 1029 41.1200000000 1.1143069267 0.0718448789 1.1143069267 0.0164073174 0.1140790000 960245305 0 402718720 -0.2128648460 -0.1235226989 2.1633036137 1030 41.1600000000 1.1148192883 0.0728574754 1.1148192883 0.0164061438 0.1127840000 960247313 0 402718720 -0.2132755816 -0.1217885241 2.1618938446 1031 41.2000000000 1.1162619591 0.0738695069 1.1162619591 0.0164047855 0.1140320000 960249321 0 402718720 -0.2138653100 -0.1174215749 2.1610841751 1032 41.2400000000 1.1169145107 0.0748802095 1.1169145107 0.0164003837 0.1142710000 960251329 0 402718720 -0.2140947133 -0.1146668568 2.1599283218 1033 41.2800000000 1.1175954342 0.0758896143 1.1175954342 0.0163951874 0.1390530000 960253337 0 402718720 -0.2144658864 -0.1126016229 2.1592624187 1034 41.3200000000 1.1205182076 0.0768998934 1.1205182076 0.0163994372 0.1305300000 960255345 0 402718720 -0.2153121382 -0.1052479446 2.1588456631 1035 41.3600000000 1.1192500591 0.0779069950 1.1205182076 0.0163953499 0.1136620000 960257353 0 402718720 -0.2154673636 -0.1050336808 2.1566069126 1036 41.4000000000 1.1200634241 0.0789129375 1.1205182076 0.0163942296 0.1134640000 960259361 0 402718720 -0.2161890417 -0.1014118493 2.1555902958 1037 41.4400000000 1.1199022532 0.0799167845 1.1205182076 0.0163934847 0.1144780000 960261369 0 402718720 -0.2166071087 -0.0978625268 2.1542644501 1038 41.4800000000 1.1201012135 0.0809188890 1.1205182076 0.0163908224 0.1141700000 960263377 0 402718720 -0.2170925736 -0.0955164731 2.1526110172 1039 41.5200000000 1.1205703020 0.0819195159 1.1205703020 0.0163901383 0.1133250000 960265385 0 402718720 -0.2176676840 -0.0914656222 2.1515293121 1040 41.5600000000 1.1202623844 0.0829179225 1.1205703020 0.0163888988 0.1123030000 960267393 0 402718720 -0.2180239707 -0.0877335966 2.1498486996 1041 41.6000000000 1.1200292110 0.0839141870 1.1205703020 0.0163859491 0.1133030000 960269401 0 402718720 -0.2184407413 -0.0839059204 2.1485600471 1042 41.6400000000 1.1200639009 0.0849085725 1.1205703020 0.0163846658 0.1131210000 960271409 0 402718720 -0.2187542170 -0.0796348304 2.1472523212 1043 41.6800000000 1.1197952032 0.0859007936 1.1205703020 0.0163853354 0.1130280000 960273417 0 402718720 -0.2189525217 -0.0758287236 2.1455423832 1044 41.7200000000 1.1195541620 0.0868908831 1.1205703020 0.0163843820 0.1397180000 960275425 0 402718720 -0.2190565765 -0.0729215071 2.1444842815 1045 41.7600000000 1.1194397211 0.0878789681 1.1205703020 0.0163841868 0.1135720000 960277433 0 402718720 -0.2193198353 -0.0712984949 2.1442909241 1046 41.8000000000 1.1197365522 0.0888654476 1.1205703020 0.0163837836 0.1135160000 960279441 0 402718720 -0.2195031643 -0.0695621818 2.1436460018 1047 41.8400000000 1.1202601194 0.0898505428 1.1205703020 0.0163827453 0.1122010000 960281449 0 402718720 -0.2196253091 -0.0700026080 2.1438794136 1048 41.8800000000 1.1206738949 0.0908341529 1.1206738949 0.0163771209 0.1134430000 960283457 0 402718720 -0.2198778093 -0.0673835576 2.1432380676 1049 41.9200000000 1.1202476025 0.0918154812 1.1206738949 0.0163740579 0.1118300000 960285465 0 402718720 -0.2200436294 -0.0663990900 2.1416165829 1050 41.9600000000 1.1191941500 0.0927939371 1.1206738949 0.0163681828 0.1182090000 960287473 0 402718720 -0.2201443166 -0.0637159497 2.1395161152 1051 42.0000000000 1.1179987192 0.0937693936 1.1206738949 0.0163627882 0.1117090000 960289481 0 402718720 -0.2200272679 -0.0624727383 2.1374573708 1052 42.0400000000 1.1177250147 0.0947427354 1.1206738949 0.0163578174 0.1124010000 960291489 0 402718720 -0.2201638520 -0.0609261133 2.1367619038 1053 42.0800000000 1.1170592308 0.0957135963 1.1206738949 0.0163530671 0.1115690000 960293497 0 402718720 -0.2202610075 -0.0592854246 2.1350426674 1054 42.1200000000 1.1165908575 0.0966821706 1.1206738949 0.0163492362 0.1124820000 960295505 0 402718720 -0.2203534991 -0.0585825071 2.1340374947 1055 42.1600000000 1.1165192127 0.0976488407 1.1206738949 0.0163442556 0.1120830000 960297513 0 402718720 -0.2207369208 -0.0560001396 2.1337289810 1056 42.2000000000 1.1165702343 0.0986137284 1.1206738949 0.0163429742 0.1235330000 960299521 0 402718720 -0.2209594548 -0.0537794009 2.1337103844 1057 42.2400000000 1.1166362762 0.0995768529 1.1206738949 0.0163417247 0.1111800000 960301529 0 402718720 -0.2211154997 -0.0530833304 2.1333620548 1058 42.2800000000 1.1166874170 0.1005382050 1.1206738949 0.0163365531 0.1108310000 960303537 0 402718720 -0.2213257998 -0.0519182310 2.1337821484 1059 42.3200000000 1.1165856123 0.1014976454 1.1206738949 0.0163326310 0.1098340000 960305545 0 402718720 -0.2216065079 -0.0521529578 2.1340014935 1060 42.3600000000 1.1173186302 0.1024559671 1.1206738949 0.0163288144 0.1203520000 960307553 0 402718720 -0.2220167816 -0.0516908504 2.1349763870 1061 42.4000000000 1.1172204018 0.1034123898 1.1206738949 0.0163239830 0.1106820000 960309561 0 402718720 -0.2224696428 -0.0505662858 2.1353695393 1062 42.4400000000 1.1154706478 0.1043653637 1.1206738949 0.0163342580 0.1100230000 960311569 0 402718720 -0.2231359780 -0.0480442233 2.1360991001 1063 42.4800000000 1.1155654192 0.1053166337 1.1206738949 0.0163275548 0.1100260000 960313577 0 402718720 -0.2231698632 -0.0452933311 2.1370208263 1064 42.5200000000 1.1028549671 0.1062541697 1.1206738949 0.0163392152 0.1362680000 960315585 0 402718720 -0.2221172899 -0.0479070805 2.1254501343 1065 42.5600000000 1.1043392420 0.1071913388 1.1206738949 0.0163366900 0.1211520000 960317593 0 402718720 -0.2220645100 -0.0481472462 2.1283154488 1066 42.6000000000 1.1055208445 0.1081278580 1.1206738949 0.0163315012 0.1092380000 960319601 0 402718720 -0.2219516188 -0.0463662073 2.1302793026 1067 42.6400000000 1.1064929962 0.1090635330 1.1206738949 0.0163283631 0.1089570000 960321609 0 402718720 -0.2218539715 -0.0452529602 2.1322333813 1068 42.6800000000 1.1065589190 0.1099975174 1.1206738949 0.0163265931 0.1211910000 960323617 0 402718720 -0.2214514315 -0.0455038063 2.1334517002 1069 42.7200000000 1.1066517830 0.1109298413 1.1206738949 0.0163247226 0.1212240000 960325625 0 402718720 -0.2210465372 -0.0450314097 2.1342072487 1070 42.7600000000 1.1067756414 0.1118605383 1.1206738949 0.0163212915 0.1093380000 960327633 0 402718720 -0.2207532227 -0.0439283997 2.1347446442 1071 42.8000000000 1.1069905758 0.1127896980 1.1206738949 0.0163182709 0.1083110000 960329641 0 402718720 -0.2207163274 -0.0435092710 2.1367740631 1072 42.8400000000 1.0951166153 0.1137060478 1.1206738949 0.0163205189 0.1346930000 960331649 0 402718720 -0.2202404141 -0.0437374823 2.1265008450 1073 42.8800000000 1.0982974768 0.1146236539 1.1206738949 0.0163181444 0.1074430000 960333657 0 402718720 -0.2202937752 -0.0421299525 2.1301724911 1074 42.9200000000 1.1007523537 0.1155418371 1.1206738949 0.0163177627 0.1072070000 960335665 0 402718720 -0.2203503251 -0.0419674590 2.1331686974 1075 42.9600000000 1.1030085087 0.1164604107 1.1206738949 0.0163132490 0.1069090000 960337673 0 402718720 -0.2201985866 -0.0412279814 2.1358757019 1076 43.0000000000 1.0913449526 0.1173664373 1.1206738949 0.0163344415 0.1425900000 960339681 0 402718720 -0.2197461277 -0.0413256772 2.1261348724 1077 43.0400000000 1.0939059258 0.1182731592 1.1206738949 0.0163338959 0.1073200000 960341689 0 402718720 -0.2196408063 -0.0408983007 2.1314783096 1078 43.0800000000 1.0956854820 0.1191798496 1.1206738949 0.0163327141 0.1069480000 960343697 0 402718720 -0.2192911208 -0.0406649485 2.1355204582 1079 43.1200000000 1.0881072283 0.1200778361 1.1206738949 0.0163278887 0.1192760000 960345705 0 402718720 -0.2190722972 -0.0405092463 2.1311235428 1080 43.1600000000 1.0907297134 0.1209765878 1.1206738949 0.0163265623 0.1269130000 960347713 0 402718720 -0.2188680321 -0.0399571061 2.1358938217 1081 43.2000000000 1.0863410234 0.1218696169 1.1206738949 0.0163195386 0.1313780000 960349721 0 402718720 -0.2187114209 -0.0414679497 2.1342129707 1082 43.2400000000 1.0881148577 0.1227626347 1.1206738949 0.0163187612 0.1168410000 960351729 0 402718720 -0.2186493874 -0.0403442085 2.1381094456 1083 43.2800000000 1.0898987055 0.1236556504 1.1206738949 0.0163219179 0.1039760000 960353737 0 402718720 -0.2183344662 -0.0409662724 2.1421222687 1084 43.3200000000 1.0917985439 0.1245487712 1.1206738949 0.0163179659 0.1038830000 960355745 0 402718720 -0.2178490162 -0.0409930050 2.1455280781 1085 43.3600000000 1.0925171375 0.1254409079 1.1206738949 0.0163118990 0.1038350000 960357753 0 402718720 -0.2174660265 -0.0413396731 2.1475994587 1086 43.4000000000 1.0926882029 0.1263315592 1.1206738949 0.0163061175 0.1037510000 960359761 0 402718720 -0.2170403600 -0.0405949578 2.1492402554 1087 43.4400000000 1.0810725689 0.1272098858 1.1206738949 0.0163099937 0.1179690000 960361769 0 402718720 -0.2171089500 -0.0398316979 2.1395766735 1088 43.4800000000 1.0845735073 0.1280898156 1.1206738949 0.0163058904 0.1041150000 960363777 0 402718720 -0.2165967226 -0.0386115313 2.1445236206 1089 43.5200000000 1.0867996216 0.1289701736 1.1206738949 0.0163045085 0.1165130000 960365785 0 402718720 -0.2159406543 -0.0390707441 2.1489117146 1090 43.5600000000 1.0892791748 0.1298511910 1.1206738949 0.0163020636 0.1145670000 960367793 0 402718720 -0.2151633203 -0.0396611802 2.1529536247 1091 43.6000000000 1.0794752836 0.1307216072 1.1206738949 0.0163096630 0.1189440000 960369801 0 402718720 -0.2151073217 -0.0379633680 2.1450140476 1092 43.6400000000 1.0794692039 0.1315904237 1.1206738949 0.0163051687 0.1198180000 960371809 0 402718720 -0.2144953460 -0.0380775556 2.1475162506 1093 43.6800000000 1.0795460939 0.1324577207 1.1206738949 0.0162995141 0.1186800000 960373817 0 402718720 -0.2137824148 -0.0375357307 2.1504993439 1094 43.7200000000 1.0797029734 0.1333235756 1.1206738949 0.0162939992 0.1203100000 960375825 0 402718720 -0.2130328715 -0.0369169302 2.1529440880 1095 43.7600000000 1.0795342922 0.1341876950 1.1206738949 0.0162887401 0.1202220000 960377833 0 402718720 -0.2124606222 -0.0375270583 2.1555752754 1096 43.8000000000 1.0835195780 0.1350538737 1.1206738949 0.0162898676 0.1059440000 960379841 0 402718720 -0.2113789320 -0.0391588062 2.1622722149 1097 43.8400000000 1.0871998072 0.1359218281 1.1206738949 0.0162876898 0.1058480000 960381849 0 402718720 -0.2103205174 -0.0407241769 2.1683292389 1098 43.8800000000 1.0903066397 0.1367910310 1.1206738949 0.0162828697 0.1059720000 960383857 0 402718720 -0.2093148828 -0.0416244939 2.1737222672 1099 43.9200000000 1.0932233334 0.1376613061 1.1206738949 0.0162776371 0.1058670000 960385865 0 402718720 -0.2083329260 -0.0418692492 2.1783752441 1100 43.9600000000 1.0827310085 0.1385204604 1.1206738949 0.0163135833 0.1318820000 960387873 0 402718720 -0.2091715485 -0.0349177569 2.1700952053 1101 44.0000000000 1.0864291191 0.1393814128 1.1206738949 0.0163222747 0.1068860000 960389881 0 402718720 -0.2078766078 -0.0379608981 2.1757333279 1102 44.0400000000 1.0832308531 0.1402379005 1.1206738949 0.0163205574 0.1198450000 960391889 0 402718720 -0.2079500705 -0.0350284316 2.1750869751 1103 44.0800000000 1.0835001469 0.1410930794 1.1206738949 0.0163146798 0.1213140000 960393897 0 402718720 -0.2072622031 -0.0342316516 2.1778147221 1104 44.1200000000 1.0835589170 0.1419467622 1.1206738949 0.0163081452 0.1215210000 960395905 0 402718720 -0.2066296339 -0.0341198482 2.1800007820 1105 44.1600000000 1.0844883919 0.1427997410 1.1206738949 0.0163022373 0.1164070000 960397913 0 402718720 -0.2060264200 -0.0338156447 2.1835353374 1106 44.2000000000 1.0845625401 0.1436512445 1.1206738949 0.0162959754 0.1205080000 960399921 0 402718720 -0.2053383142 -0.0330327749 2.1859376431 1107 44.2400000000 1.0847494602 0.1445013783 1.1206738949 0.0162899276 0.1205970000 960401929 0 402718720 -0.2047475874 -0.0331340693 2.1881711483 1108 44.2800000000 1.0846189260 0.1453498599 1.1206738949 0.0162832754 0.1334550000 960403937 0 402718720 -0.2042508572 -0.0333168656 2.1901214123 1109 44.3200000000 1.0844931602 0.1461966979 1.1206738949 0.0162773940 0.1481360000 960405945 0 402718720 -0.2036182582 -0.0320216343 2.1921882629 1110 44.3600000000 1.0846701860 0.1470421695 1.1206738949 0.0162706869 0.1493510000 960407953 0 402718720 -0.2029632628 -0.0319135897 2.1938376427 1111 44.4000000000 1.0848516226 0.1478862824 1.1206738949 0.0162639552 0.1494960000 960409961 0 402718720 -0.2023590207 -0.0316988379 2.1961822510 1112 44.4400000000 1.0881065130 0.1487318042 1.1206738949 0.0162604798 0.1333680000 960411969 0 402718720 -0.2009475082 -0.0331626646 2.2015304565 1113 44.4800000000 1.0919053555 0.1495792198 1.1206738949 0.0162582937 0.1336940000 960413977 0 402718720 -0.1993765086 -0.0361226760 2.2073726654 1114 44.5200000000 1.0853304863 0.1504192119 1.1206738949 0.0162682621 0.1383030000 960415985 0 402718720 -0.2000197768 -0.0294214450 2.2032847404 1115 44.5600000000 1.0895832777 0.1512615115 1.1206738949 0.0162677404 0.1084850000 960417993 0 402718720 -0.1981818974 -0.0333520845 2.2094206810 1116 44.6000000000 1.0866707563 0.1520996919 1.1206738949 0.0162701954 0.1225640000 960420001 0 402718720 -0.1983819604 -0.0287622735 2.2085506916 1117 44.6400000000 1.0866055489 0.1529363130 1.1206738949 0.0162636570 0.1226080000 960422009 0 402718720 -0.1975362599 -0.0277234949 2.2107779980 1118 44.6800000000 1.0877540112 0.1537724648 1.1206738949 0.0162582756 0.1517540000 960424017 0 402718720 -0.1965264082 -0.0273431856 2.2149064541 1119 44.7200000000 1.0908957720 0.1546099298 1.1206738949 0.0162617341 0.1233710000 960426025 0 402718720 -0.1958175600 -0.0248307940 2.2210812569 1120 44.7600000000 1.0933805704 0.1554481179 1.1206738949 0.0162593147 0.1444340000 960428033 0 402718720 -0.1949522942 -0.0246636085 2.2266325951 1121 44.8000000000 1.0961248875 0.1562872586 1.1206738949 0.0162571476 0.1105340000 960430041 0 402718720 -0.1924672723 -0.0311158467 2.2318043709 1122 44.8400000000 1.0971004963 0.1571257731 1.1206738949 0.0162529708 0.1110410000 960432049 0 402718720 -0.1902147979 -0.0381078422 2.2360863686 1123 44.8800000000 1.0977842808 0.1579634031 1.1206738949 0.0162502894 0.1110550000 960434057 0 402718720 -0.1880678982 -0.0463785417 2.2402105331 1124 44.9200000000 1.0832740068 0.1587866332 1.1206738949 0.0163157321 0.1264010000 960436065 0 402718720 -0.1908636391 -0.0296697710 2.2277524471 1125 44.9600000000 1.0820831060 0.1596073412 1.1206738949 0.0163118838 0.1120260000 960438073 0 402718720 -0.1882798374 -0.0338017531 2.2290825844 1126 45.0000000000 1.0786112547 0.1604235080 1.1206738949 0.0163107829 0.1125020000 960440081 0 402718720 -0.1856504232 -0.0422189869 2.2288918495 1127 45.0400000000 1.0597115755 0.1612214566 1.1206738949 0.0163996222 0.1279820000 960442089 0 402718720 -0.1873971075 -0.0338708498 2.2124142647 1128 45.0800000000 1.0551787615 0.1620139720 1.1206738949 0.0163977571 0.1136470000 960444097 0 402718720 -0.1840345711 -0.0446076952 2.2107198238 1129 45.1200000000 1.0470196009 0.1627978565 1.1206738949 0.0163985445 0.1190460000 960446105 0 402718720 -0.1804148108 -0.0620590299 2.2056474686 1130 45.1600000000 0.9705820680 0.1635127098 1.1206738949 0.0164246046 0.1584610000 960448113 0 402718720 -0.1823549271 -0.0755491480 2.1306328773 1131 45.2000000000 0.9232630134 0.1641844607 1.1206738949 0.0165192282 0.1475070000 960450121 0 402718720 -0.1797730625 -0.0468705073 2.0869417191 1132 45.2400000000 0.8976283669 0.1648323794 1.1206738949 0.0165920491 0.1581950000 960452129 0 402718720 -0.1775588244 -0.0390848182 2.0634515285 1133 45.2800000000 0.8532341719 0.1654399714 1.1206738949 0.0168026316 0.1508050000 960454137 0 402718720 -0.1760079116 -0.0198191833 2.0208799839 1134 45.3200000000 0.8156219721 0.1660133241 1.1206738949 0.0169575894 0.1524700000 960456145 0 402718720 -0.1739614904 -0.0113124913 1.9851591587 1135 45.3600000000 0.7769731283 0.1665516147 1.1206738949 0.0171912616 0.1523000000 960458153 0 402718720 -0.1716090590 0.0034264810 1.9498280287 1136 45.4000000000 0.7377368808 0.1670544187 1.1206738949 0.0174370671 0.1517370000 960460161 0 402718720 -0.1692845672 0.0263806358 1.9115853310 1137 45.4400000000 0.7158832550 0.1675371177 1.1206738949 0.0175898416 0.1491690000 960462169 0 402718720 -0.1664299369 0.0973877236 1.8852188587 1138 45.4800000000 0.7209675908 0.1680234362 1.1206738949 0.0177168854 0.1518440000 960464177 0 402718720 -0.1597389579 0.1698196530 1.8739854097 1139 45.5200000000 0.7124680877 0.1685014386 1.1206738949 0.0189289162 0.1549090000 960466185 0 402718720 -0.1587686986 0.3657732308 1.7760595083 1140 45.5600000000 0.7032406330 0.1689705080 1.1206738949 0.0192824909 0.1676000000 960468193 0 402718720 -0.1570178270 0.4316792786 1.7177453041 1141 45.6000000000 0.7045725584 0.1694399226 1.1206738949 0.0194112709 0.1572080000 960470201 0 402718720 -0.1543457061 0.4710904956 1.6884831190 1142 45.6400000000 0.7102160454 0.1699134569 1.1206738949 0.0194966257 0.1579060000 960472209 0 402718720 -0.1521266252 0.4943499267 1.6776303053 1143 45.6800000000 0.7248386145 0.1703989557 1.1206738949 0.0195287641 0.1589060000 960474217 0 402718720 -0.1499132961 0.5279312134 1.6724016666 1144 45.7200000000 0.7422738671 0.1708988464 1.1206738949 0.0195655990 0.1585110000 960476225 0 402718720 -0.1475796402 0.5649888515 1.6652301550 1145 45.7600000000 0.7640815973 0.1714169099 1.1206738949 0.0196316199 0.1613140000 960478233 0 402718720 -0.1449995488 0.5992712379 1.6588565111 1146 45.8000000000 0.7754377127 0.1719439787 1.1206738949 0.0196475698 0.1654590000 960480241 0 402718720 -0.1420125067 0.6381393075 1.6379168034 1147 45.8400000000 0.7877716422 0.1724808816 1.1206738949 0.0196665848 0.1655490000 960482249 0 402718720 -0.1381419301 0.6779928207 1.6100668907 1148 45.8800000000 0.7901525497 0.1730189231 1.1206738949 0.0196800198 0.1496880000 960484257 0 402718720 -0.1338616163 0.7044993043 1.5781871080 1149 45.9200000000 0.7693345547 0.1735379097 1.1206738949 0.0197551326 0.1523550000 960486265 0 402718720 -0.1284984052 0.7169619203 1.5232887268 1150 45.9600000000 0.7580533028 0.1740461840 1.1206738949 0.0197727635 0.1656620000 960488273 0 402718720 -0.1250504851 0.7210023999 1.4907778502 1151 46.0000000000 0.7426168919 0.1745401638 1.1206738949 0.0197925437 0.1757700000 960490281 0 402718720 -0.1207055524 0.7246215343 1.4455709457 1152 46.0400000000 0.7410213947 0.1750319009 1.1206738949 0.0198559269 0.1610840000 960492289 0 402718720 -0.1169516817 0.7356263995 1.4040396214 1153 46.0800000000 0.7279961109 0.1755114883 1.1206738949 0.0198739649 0.1841310000 960494297 0 402718720 -0.1147507727 0.7325851917 1.3837562799 1154 46.1200000000 0.7138662934 0.1759780003 1.1206738949 0.0198941066 0.1681570000 960496305 0 402718720 -0.1116621271 0.7248205543 1.3630489111 1155 46.1600000000 0.6943663359 0.1764268213 1.1206738949 0.0199194157 0.1837100000 960498313 0 402718720 -0.1086915657 0.7101793885 1.3415968418 1156 46.2000000000 0.6838195324 0.1768657424 1.1206738949 0.0199633859 0.1731730000 960500321 0 402718720 -0.1052993536 0.7059838176 1.3079928160 1157 46.2400000000 0.6880055070 0.1773075226 1.1206738949 0.0200775873 0.1771200000 960502329 0 402718720 -0.1011416540 0.7152776718 1.2682285309 1158 46.2800000000 0.6752722859 0.1777375440 1.1206738949 0.0201069513 0.1799270000 960504337 0 402718720 -0.0987193808 0.7047305703 1.2504302263 1159 46.3200000000 0.6346201301 0.1781317481 1.1206738949 0.0201602978 0.1810690000 960506345 0 402718720 -0.0971487388 0.6669873595 1.2392854691 1160 46.3600000000 0.5790172219 0.1784773391 1.1206738949 0.0202388418 0.2122340000 960508353 0 402718720 -0.0947237760 0.6135256290 1.2271144390 1161 46.4000000000 0.5259737372 0.1787766469 1.1206738949 0.0203218471 0.2029880000 960510361 0 402718720 -0.0927213058 0.5580496192 1.2116687298 1162 46.4400000000 0.4655747712 0.1790234611 1.1206738949 0.0204638790 0.1995840000 960512369 0 402718720 -0.0912751704 0.4964060187 1.1948741674 1163 46.4800000000 0.4345686436 0.1792431904 1.1206738949 0.0204937661 0.1884170000 960514377 0 402718720 -0.0891777202 0.4648556709 1.1901121140 1164 46.5200000000 0.4055188000 0.1794375853 1.1206738949 0.0205290678 0.1903690000 960516385 0 402718720 -0.0871206969 0.4352839589 1.1876646280 1165 46.5600000000 0.3965066075 0.1796239106 1.1206738949 0.0205249208 0.1914090000 960518393 0 402718720 -0.0842359439 0.4275025129 1.1889479160 1166 46.6000000000 0.3627819717 0.1797809930 1.1206738949 0.0205664015 0.1942740000 960520401 0 402718720 -0.0836573839 0.3950560987 1.1911544800 1167 46.6400000000 0.3191277087 0.1799003989 1.1206738949 0.0206243168 0.1974120000 960522409 0 402718720 -0.0829066709 0.3482959867 1.2009201050 1168 46.6800000000 0.3181812167 0.1800187900 1.1206738949 0.0206165871 0.1920790000 960524417 0 402718720 -0.0812912956 0.3462917209 1.2069560289 1169 46.7200000000 0.3136130273 0.1801330708 1.1206738949 0.0206096805 0.1926480000 960526425 0 402718720 -0.0784590393 0.3415087759 1.2122486830 1170 46.7600000000 0.2998264432 0.1802353728 1.1206738949 0.0206108412 0.1984270000 960528433 0 402718720 -0.0775557905 0.3271338940 1.2178289890 1171 46.8000000000 0.2906593680 0.1803296717 1.1206738949 0.0206076975 0.1982260000 960530441 0 402718720 -0.0759790689 0.3153178096 1.2227234840 1172 46.8400000000 0.2844706774 0.1804185292 1.1206738949 0.0206018778 0.1944090000 960532449 0 402718720 -0.0743406415 0.3068465889 1.2265228033 1173 46.8800000000 0.2831209898 0.1805060846 1.1206738949 0.0205955567 0.1867370000 960534457 0 402718720 -0.0708247721 0.3057563305 1.2299861908 1174 46.9200000000 0.2731932998 0.1805850346 1.1206738949 0.0205937795 0.1975340000 960536465 0 402718720 -0.0709328353 0.2942596674 1.2326543331 1175 46.9600000000 0.2716545165 0.1806625405 1.1206738949 0.0205889593 0.1883770000 960538473 0 402718720 -0.0672768652 0.2918223143 1.2359796762 1176 47.0000000000 0.2663969100 0.1807354439 1.1206738949 0.0205859062 0.1982390000 960540481 0 402718720 -0.0683417320 0.2847478390 1.2366170883 1177 47.0400000000 0.2651638687 0.1808071758 1.1206738949 0.0205801968 0.1891340000 960542489 0 402718720 -0.0649841130 0.2830004990 1.2396366596 1178 47.0800000000 0.2631357312 0.1808770642 1.1206738949 0.0205741809 0.1876520000 960544497 0 402718720 -0.0627779737 0.2821167707 1.2421598434 1179 47.1200000000 0.2618482411 0.1809457420 1.1206738949 0.0205664836 0.1895220000 960546505 0 402718720 -0.0608619452 0.2810637653 1.2439899445 1180 47.1600000000 0.2605793774 0.1810132281 1.1206738949 0.0205588585 0.2287050000 960548513 0 402718720 -0.0589019507 0.2794339061 1.2458131313 1181 47.2000000000 0.2587335408 0.1810790370 1.1206738949 0.0205513865 0.2371210000 960550521 0 402718720 -0.0570076071 0.2780909836 1.2478001118 1182 47.2400000000 0.2574254274 0.1811436279 1.1206738949 0.0205448455 0.2375510000 960552529 0 402718720 -0.0554981716 0.2769328654 1.2495614290 1183 47.2800000000 0.2539894283 0.1812052051 1.1206738949 0.0205394991 0.2493870000 960554537 0 402718720 -0.0578291528 0.2727780342 1.2488996983 1184 47.3200000000 0.2537212074 0.1812664517 1.1206738949 0.0205310278 0.1944340000 960556545 0 402718720 -0.0546083227 0.2720233798 1.2513165474 1185 47.3600000000 0.2531615198 0.1813271226 1.1206738949 0.0205233555 0.1912950000 960558553 0 402718720 -0.0522628874 0.2704800963 1.2534071207 1186 47.4000000000 0.2509182990 0.1813857999 1.1206738949 0.0205172912 0.1915960000 960560561 0 402718720 -0.0508828573 0.2696621120 1.2544752359 1187 47.4400000000 0.2501954436 0.1814437692 1.1206738949 0.0205095972 0.1900540000 960562569 0 402718720 -0.0497734658 0.2693582773 1.2551419735 1188 47.4800000000 0.2503813207 0.1815017975 1.1206738949 0.0205012269 0.1922360000 960564577 0 402718720 -0.0485663004 0.2679450214 1.2561873198 1189 47.5200000000 0.2504701912 0.1815598029 1.1206738949 0.0204926134 0.1925280000 960566585 0 402718720 -0.0470693745 0.2647624016 1.2575113773 1190 47.5600000000 0.2482662797 0.1816158587 1.1206738949 0.0204854414 0.2024960000 960568593 0 402718720 -0.0457375422 0.2630760372 1.2588951588 1191 47.6000000000 0.2473921776 0.1816710865 1.1206738949 0.0204777086 0.1941910000 960570601 0 402718720 -0.0447832383 0.2621383667 1.2599573135 1192 47.6400000000 0.2463557124 0.1817253521 1.1206738949 0.0204730008 0.2082510000 960572609 0 402718720 -0.0496620722 0.2603893876 1.2573733330 1193 47.6800000000 0.2451127917 0.1817784850 1.1206738949 0.0204660030 0.1951370000 960574617 0 402718720 -0.0466031656 0.2602244020 1.2597550154 1194 47.7200000000 0.2454278916 0.1818317927 1.1206738949 0.0204592998 0.1949680000 960576625 0 402718720 -0.0443674438 0.2605387270 1.2615835667 1195 47.7600000000 0.2445267588 0.1818842571 1.1206738949 0.0204546154 0.2093370000 960578633 0 402718720 -0.0487366281 0.2600222826 1.2597703934 1196 47.8000000000 0.2449745536 0.1819370082 1.1206738949 0.0204490848 0.1954960000 960580641 0 402718720 -0.0454716943 0.2611038685 1.2621730566 1197 47.8400000000 0.2434123158 0.1819883660 1.1206738949 0.0204440168 0.2092000000 960582649 0 402718720 -0.0484931953 0.2579021454 1.2614724636 1198 47.8800000000 0.2435169816 0.1820397254 1.1206738949 0.0204359710 0.1943750000 960584657 0 402718720 -0.0443687029 0.2556340992 1.2645528316 1199 47.9200000000 0.2427575290 0.1820903658 1.1206738949 0.0204322740 0.2082110000 960586665 0 402718720 -0.0480814055 0.2562719882 1.2630523443 1200 47.9600000000 0.2423470169 0.1821405797 1.1206738949 0.0204291232 0.2063600000 960588673 0 402718720 -0.0446505770 0.2552572489 1.2653412819 1201 48.0000000000 0.2412030548 0.1821897574 1.1206738949 0.0204244855 0.1967900000 960590681 0 402718720 -0.0423133299 0.2545094490 1.2671546936 1202 48.0400000000 0.2410119474 0.1822386943 1.1206738949 0.0204173342 0.1980910000 960592689 0 402718720 -0.0406312011 0.2533641160 1.2682560682 1203 48.0800000000 0.2416418344 0.1822880735 1.1206738949 0.0204125034 0.2124840000 960594697 0 402718720 -0.0463132858 0.2548952103 1.2655917406 1204 48.1200000000 0.2415473759 0.1823372922 1.1206738949 0.0204052102 0.1978350000 960596705 0 402718720 -0.0434797630 0.2548146546 1.2674423456 1205 48.1600000000 0.2416590154 0.1823865218 1.1206738949 0.0203979907 0.2210290000 960598713 0 402718720 -0.0411019363 0.2545340657 1.2686831951 1206 48.2000000000 0.2414563894 0.1824355018 1.1206738949 0.0203924658 0.1991280000 960600721 0 402718720 -0.0394843742 0.2532577217 1.2692661285 1207 48.2400000000 0.2410975397 0.1824841034 1.1206738949 0.0203865686 0.2092350000 960602729 0 402718720 -0.0380289480 0.2521009445 1.2700814009 1208 48.2800000000 0.2409911156 0.1825325363 1.1206738949 0.0203802119 0.2484690000 960604737 0 402718720 -0.0364762880 0.2513305545 1.2707448006 1209 48.3200000000 0.2406999022 0.1825806483 1.1206738949 0.0203761564 0.2485210000 960606745 0 402718720 -0.0349328592 0.2512835264 1.2711029053 1210 48.3600000000 0.2410558313 0.1826289749 1.1206738949 0.0203706159 0.2485370000 960608753 0 402718720 -0.0333181173 0.2514969110 1.2715787888 1211 48.4000000000 0.2415585816 0.1826776368 1.1206738949 0.0203649140 0.2486720000 960610761 0 402718720 -0.0309697185 0.2506397665 1.2724324465 1212 48.4400000000 0.2415998727 0.1827262525 1.1206738949 0.0203637162 0.2640380000 960612769 0 402718720 -0.0324775726 0.2499371618 1.2714329958 1213 48.4800000000 0.2413754612 0.1827746031 1.1206738949 0.0203562678 0.2482430000 960614777 0 402718720 -0.0278408527 0.2495549470 1.2724771500 1214 48.5200000000 0.2414653301 0.1828229480 1.1206738949 0.0203493570 0.2483050000 960616785 0 402718720 -0.0234233048 0.2496160269 1.2734779119 1215 48.5600000000 0.2415450364 0.1828712789 1.1206738949 0.0203444066 0.2091730000 960618793 0 402718720 -0.0261949934 0.2488426268 1.2723218203 1216 48.6000000000 0.2417857498 0.1829197283 1.1206738949 0.0203418812 0.1966900000 960620801 0 402718720 -0.0208541919 0.2474428266 1.2738608122 1217 48.6400000000 0.2405459136 0.1829670793 1.1206738949 0.0203384559 0.1964660000 960622809 0 402718720 -0.0167894885 0.2472817153 1.2746688128 1218 48.6800000000 0.2409156859 0.1830146562 1.1206738949 0.0203354138 0.1968380000 960624817 0 402718720 -0.0135650048 0.2476704568 1.2754780054 1219 48.7200000000 0.2415914834 0.1830627094 1.1206738949 0.0203299306 0.1961930000 960626825 0 402718720 -0.0102294143 0.2477606237 1.2764573097 1220 48.7600000000 0.2412490249 0.1831104031 1.1206738949 0.0203248244 0.2115770000 960628833 0 402718720 -0.0136384582 0.2471292764 1.2758817673 1221 48.8000000000 0.2412985861 0.1831580592 1.1206738949 0.0203235661 0.1966630000 960630841 0 402718720 -0.0082159080 0.2449142337 1.2777979374 1222 48.8400000000 0.2395524532 0.1832042085 1.1206738949 0.0203212624 0.1972960000 960632849 0 402718720 -0.0038015442 0.2444304228 1.2792341709 1223 48.8800000000 0.2394671440 0.1832502125 1.1206738949 0.0203202218 0.1967190000 960634857 0 402718720 -0.0003357959 0.2444245219 1.2800874710 1224 48.9200000000 0.2395604104 0.1832962176 1.1206738949 0.0203166579 0.1965360000 960636865 0 402718720 0.0027921682 0.2454925776 1.2809410095 1225 48.9600000000 0.2401557714 0.1833426336 1.1206738949 0.0203135968 0.1951030000 960638873 0 402718720 0.0058163120 0.2457355559 1.2819201946 1226 49.0000000000 0.2397940159 0.1833886787 1.1206738949 0.0203101120 0.1952590000 960640881 0 402718720 0.0087677306 0.2459789813 1.2828396559 1227 49.0400000000 0.2396562248 0.1834345366 1.1206738949 0.0203059467 0.1949480000 960642889 0 402718720 0.0116863558 0.2461999208 1.2840043306 1228 49.0800000000 0.2398597002 0.1834804854 1.1206738949 0.0203011893 0.1955010000 960644897 0 402718720 0.0148525219 0.2464860529 1.2850368023 1229 49.1200000000 0.2397683859 0.1835262851 1.1206738949 0.0202959214 0.2147620000 960646905 0 402718720 0.0180597585 0.2467239201 1.2859845161 1230 49.1600000000 0.2393772453 0.1835716924 1.1206738949 0.0202916139 0.2120480000 960648913 0 402718720 0.0205672067 0.2463277280 1.2868965864 1231 49.2000000000 0.2386844456 0.1836164631 1.1206738949 0.0202852944 0.1966790000 960650921 0 402718720 0.0230709519 0.2472778857 1.2872769833 1232 49.2400000000 0.2385923415 0.1836610864 1.1206738949 0.0202791505 0.2065660000 960652929 0 402718720 0.0204570238 0.2481150329 1.2868971825 1233 49.2800000000 0.2387878150 0.1837057959 1.1206738949 0.0202720871 0.1944670000 960654937 0 402718720 0.0249240696 0.2488205284 1.2879419327 1234 49.3200000000 0.2394935042 0.1837510047 1.1206738949 0.0202653380 0.2093080000 960656945 0 402718720 0.0287922788 0.2491366267 1.2888303995 1235 49.3600000000 0.2390646785 0.1837957931 1.1206738949 0.0202613435 0.1955060000 960658953 0 402718720 0.0322797410 0.2490866780 1.2898333073 1236 49.4000000000 0.2378923446 0.1838395605 1.1206738949 0.0202629530 0.1953870000 960660961 0 402718720 0.0348054953 0.2476920336 1.2908747196 1237 49.4400000000 0.2366077304 0.1838822187 1.1206738949 0.0202620807 0.1930760000 960662969 0 402718720 0.0371244885 0.2480671108 1.2912523746 1238 49.4800000000 0.2364694625 0.1839246963 1.1206738949 0.0202637390 0.1955960000 960664977 0 402718720 0.0388549455 0.2497702390 1.2911418676 1239 49.5200000000 0.2367044538 0.1839672950 1.1206738949 0.0202670870 0.1954940000 960666985 0 402718720 0.0414363742 0.2502659261 1.2910069227 1240 49.5600000000 0.2369477600 0.1840100211 1.1206738949 0.0202688400 0.2058740000 960668993 0 402718720 0.0441388451 0.2488675117 1.2916333675 1241 49.6000000000 0.2360209078 0.1840519316 1.1206738949 0.0202647583 0.1964990000 960671001 0 402718720 0.0477441251 0.2486785352 1.2918157578 1242 49.6400000000 0.2361662090 0.1840938916 1.1206738949 0.0202586606 0.1964960000 960673009 0 402718720 0.0506058708 0.2501298487 1.2918080091 1243 49.6800000000 0.2374015599 0.1841367779 1.1206738949 0.0202509585 0.1964010000 960675017 0 402718720 0.0535644330 0.2512955964 1.2921282053 1244 49.7200000000 0.2371870577 0.1841794228 1.1206738949 0.0202428437 0.1962610000 960677025 0 402718720 0.0567286611 0.2524738014 1.2919342518 1245 49.7600000000 0.2365231514 0.1842214659 1.1206738949 0.0202347409 0.1929520000 960679033 0 402718720 0.0592636988 0.2534577847 1.2913583517 1246 49.8000000000 0.2373299003 0.1842640891 1.1206738949 0.0202275500 0.1951960000 960681041 0 402718720 0.0614849851 0.2545611262 1.2913514376 1247 49.8400000000 0.2371976972 0.1843065379 1.1206738949 0.0202200273 0.2074530000 960683049 0 402718720 0.0630989224 0.2557873428 1.2909616232 1248 49.8800000000 0.2372049391 0.1843489244 1.1206738949 0.0202126371 0.1948370000 960685057 0 402718720 0.0648247451 0.2564314604 1.2906742096 1249 49.9200000000 0.2371769398 0.1843912206 1.1206738949 0.0202045500 0.1946130000 960687065 0 402718720 0.0663822144 0.2559333444 1.2908179760 1250 49.9600000000 0.2359715700 0.1844324849 1.1206738949 0.0201965201 0.1961290000 960689073 0 402718720 0.0682525709 0.2565829754 1.2906347513 1251 50.0000000000 0.2359421551 0.1844736597 1.1206738949 0.0201885628 0.1945950000 960691081 0 402718720 0.0697124377 0.2587451041 1.2895658016 1252 50.0400000000 0.2366468161 0.1845153316 1.1206738949 0.0201810715 0.1954060000 960693089 0 402718720 0.0709732622 0.2605195642 1.2887262106 1253 50.0800000000 0.2366564870 0.1845569446 1.1206738949 0.0201731790 0.1954410000 960695097 0 402718720 0.0720641017 0.2614319026 1.2881883383 1254 50.1200000000 0.2367908508 0.1845985985 1.1206738949 0.0201653956 0.1946590000 960697105 0 402718720 0.0738498122 0.2621085942 1.2878140211 1255 50.1600000000 0.2366696298 0.1846400893 1.1206738949 0.0201578502 0.2198990000 960699113 0 402718720 0.0755577087 0.2622994781 1.2874728441 1256 50.2000000000 0.2361659408 0.1846811131 1.1206738949 0.0201505467 0.1910600000 960701121 0 402718720 0.0777454674 0.2621825933 1.2872235775 1257 50.2400000000 0.2363063544 0.1847221833 1.1206738949 0.0201427763 0.1946190000 960703129 0 402718720 0.0799553022 0.2620531619 1.2874072790 1258 50.2800000000 0.2355753928 0.1847626071 1.1206738949 0.0201347904 0.2067570000 960705137 0 402718720 0.0813664123 0.2632241845 1.2864780426 1259 50.3200000000 0.2360160649 0.1848033168 1.1206738949 0.0201268188 0.1937820000 960707145 0 402718720 0.0844259262 0.2643406689 1.2860277891 1260 50.3600000000 0.2362048626 0.1848441117 1.1206738949 0.0201198449 0.2076270000 960709153 0 402718720 0.0851603076 0.2667672038 1.2843685150 1261 50.4000000000 0.2366736233 0.1848852136 1.1206738949 0.0201124787 0.1921310000 960711161 0 402718720 0.0896119103 0.2678122520 1.2840118408 1262 50.4400000000 0.2359250188 0.1849256572 1.1206738949 0.0201045447 0.1974700000 960713169 0 402718720 0.0906556770 0.2688060105 1.2828797102 1263 50.4800000000 0.2350292951 0.1849653275 1.1206738949 0.0200965954 0.1927270000 960715177 0 402718720 0.0943228602 0.2700940073 1.2820419073 1264 50.5200000000 0.2348205298 0.1850047699 1.1206738949 0.0200888333 0.1953330000 960717185 0 402718720 0.0938274637 0.2708886862 1.2809188366 1265 50.5600000000 0.2354155630 0.1850446203 1.1206738949 0.0200814396 0.2010480000 960719193 0 402718720 0.0973602831 0.2707092166 1.2808207273 1266 50.6000000000 0.2342289686 0.1850834705 1.1206738949 0.0200742000 0.1893720000 960721201 0 402718720 0.1000497267 0.2705904245 1.2803311348 1267 50.6400000000 0.2330823988 0.1851213545 1.1206738949 0.0200666944 0.1906070000 960723209 0 402718720 0.1020615622 0.2719678581 1.2793388367 1268 50.6800000000 0.2335644811 0.1851595588 1.1206738949 0.0200597317 0.1913980000 960725217 0 402718720 0.1063962728 0.2733827829 1.2778236866 1269 50.7200000000 0.2324102372 0.1851967934 1.1206738949 0.0200524615 0.1887200000 960727225 0 402718720 0.1087247357 0.2724698484 1.2774358988 1270 50.7600000000 0.2315903306 0.1852333237 1.1206738949 0.0200450282 0.1978250000 960729233 0 402718720 0.1104892641 0.2724398673 1.2768414021 1271 50.8000000000 0.2326022834 0.1852705928 1.1206738949 0.0200374620 0.2079710000 960731241 0 402718720 0.1079926565 0.2756795585 1.2741869688 1272 50.8400000000 0.2325593084 0.1853077695 1.1206738949 0.0200303880 0.1899320000 960733249 0 402718720 0.1090997383 0.2764127851 1.2731926441 1273 50.8800000000 0.2323288471 0.1853447067 1.1206738949 0.0200229753 0.1863040000 960735257 0 402718720 0.1097222939 0.2776298523 1.2721304893 1274 50.9200000000 0.2324247062 0.1853816611 1.1206738949 0.0200155827 0.1828820000 960737265 0 402718720 0.1117967293 0.2799974978 1.2708591223 1275 50.9600000000 0.2330689579 0.1854190629 1.1206738949 0.0200078627 0.1813610000 960739273 0 402718720 0.1147828251 0.2809233069 1.2706360817 1276 51.0000000000 0.2320818305 0.1854556325 1.1206738949 0.0200001133 0.1842800000 960741281 0 402718720 0.1155883148 0.2802469134 1.2703629732 1277 51.0400000000 0.2319806814 0.1854920656 1.1206738949 0.0199925510 0.1827090000 960743289 0 402718720 0.1176178902 0.2796193361 1.2703243494 1278 51.0800000000 0.2318030745 0.1855283027 1.1206738949 0.0199847330 0.1814300000 960745297 0 402718720 0.1196334139 0.2791417241 1.2703164816 1279 51.1200000000 0.2316005528 0.1855643248 1.1206738949 0.0199770677 0.1780900000 960747305 0 402718720 0.1213671491 0.2782472372 1.2701288462 1280 51.1600000000 0.2310606241 0.1855998688 1.1206738949 0.0199700627 0.1896660000 960749313 0 402718720 0.1204709336 0.2772506475 1.2698328495 1281 51.2000000000 0.2316068262 0.1856357836 1.1206738949 0.0199626702 0.1973680000 960751321 0 402718720 0.1208573133 0.2809130251 1.2677898407 1282 51.2400000000 0.2307269275 0.1856709561 1.1206738949 0.0199549605 0.2051290000 960753329 0 402718720 0.1211567149 0.2810991108 1.2674006224 1283 51.2800000000 0.2304677367 0.1857058718 1.1206738949 0.0199471970 0.1782660000 960755337 0 402718720 0.1220207736 0.2802872360 1.2674218416 1284 51.3200000000 0.2314203233 0.1857414749 1.1206738949 0.0199394221 0.1811280000 960757345 0 402718720 0.1226301715 0.2818702161 1.2668869495 1285 51.3600000000 0.2304208130 0.1857762449 1.1206738949 0.0199317158 0.1954270000 960759353 0 402718720 0.1240308359 0.2817269862 1.2668844461 1286 51.4000000000 0.2302926183 0.1858108610 1.1206738949 0.0199239758 0.1756950000 960761361 0 402718720 0.1251499653 0.2816477716 1.2668988705 1287 51.4400000000 0.2300304323 0.1858452197 1.1206738949 0.0199166620 0.1873470000 960763369 0 402718720 0.1259532273 0.2808918953 1.2669749260 1288 51.4800000000 0.2302706838 0.1858797115 1.1206738949 0.0199100449 0.1737740000 960765377 0 402718720 0.1267206520 0.2796454430 1.2673898935 1289 51.5200000000 0.2311147451 0.1859148046 1.1206738949 0.0199024626 0.1772030000 960767385 0 402718720 0.1270474643 0.2824881077 1.2662075758 1290 51.5600000000 0.2311780155 0.1859498924 1.1206738949 0.0198974506 0.1848490000 960769393 0 402718720 0.1298563182 0.2831528187 1.2660499811 1291 51.6000000000 0.2302920222 0.1859842395 1.1206738949 0.0198942876 0.1684900000 960771401 0 402718720 0.1302358657 0.2824558616 1.2661834955 1292 51.6400000000 0.2301495671 0.1860184232 1.1206738949 0.0198901598 0.1678440000 960773409 0 402718720 0.1311892867 0.2826951146 1.2656080723 1293 51.6800000000 0.2312223613 0.1860533837 1.1206738949 0.0198853530 0.1736800000 960775417 0 402718720 0.1317870915 0.2847054899 1.2646933794 1294 51.7200000000 0.2306240499 0.1860878278 1.1206738949 0.0198782981 0.1683010000 960777425 0 402718720 0.1330703646 0.2835695148 1.2648130655 1295 51.7600000000 0.2311445922 0.1861226206 1.1206738949 0.0198739629 0.1715670000 960779433 0 402718720 0.1331510395 0.2834185362 1.2641282082 1296 51.8000000000 0.2310454547 0.1861572833 1.1206738949 0.0198763023 0.1690020000 960781441 0 402718720 0.1342117786 0.2852985561 1.2629731894 1297 51.8400000000 0.2316473573 0.1861923566 1.1206738949 0.0198716056 0.1814130000 960783449 0 402718720 0.1348457634 0.2852589786 1.2628059387 1298 51.8800000000 0.2321900427 0.1862277940 1.1206738949 0.0198664613 0.1814420000 960785457 0 402718720 0.1360621452 0.2885905206 1.2616574764 1299 51.9200000000 0.2327644676 0.1862636190 1.1206738949 0.0198633078 0.1816450000 960787465 0 402718720 0.1372463554 0.2907432616 1.2609179020 1300 51.9600000000 0.2331987172 0.1862997229 1.1206738949 0.0198618091 0.1790880000 960789473 0 402718720 0.1381772608 0.2924133241 1.2603759766 1301 52.0000000000 0.2335328609 0.1863360282 1.1206738949 0.0198590673 0.1709210000 960791481 0 402718720 0.1392986774 0.2945045233 1.2594263554 1302 52.0400000000 0.2338939309 0.1863725550 1.1206738949 0.0198597679 0.1687700000 960793489 0 402718720 0.1408726275 0.2982921302 1.2578773499 1303 52.0800000000 0.2311904132 0.1864069509 1.1206738949 0.0198587823 0.1606550000 960795497 0 402718720 0.1430350691 0.2999778092 1.2570014000 1304 52.1200000000 0.2297800630 0.1864402125 1.1206738949 0.0198561210 0.1718610000 960797505 0 402718720 0.1440333277 0.3001085520 1.2561483383 1305 52.1600000000 0.2273917645 0.1864715930 1.1206738949 0.0198532038 0.1611120000 960799513 0 402718720 0.1453021467 0.3002159894 1.2553031445 1306 52.2000000000 0.2261672020 0.1865019878 1.1206738949 0.0198475097 0.1616110000 960801521 0 402718720 0.1464505643 0.3032007813 1.2539950609 1307 52.2400000000 0.2266654968 0.1865327173 1.1206738949 0.0198401220 0.1625170000 960803529 0 402718720 0.1479979753 0.3068610430 1.2524886131 1308 52.2800000000 0.2335923463 0.1865686956 1.1206738949 0.0198332380 0.1720960000 960805537 0 402718720 0.1489371508 0.3160174787 1.2487988472 1309 52.3200000000 0.2289985269 0.1866011095 1.1206738949 0.0198268775 0.1632470000 960807545 0 402718720 0.1503040940 0.3137618899 1.2485822439 1310 52.3600000000 0.2339347005 0.1866372420 1.1206738949 0.0198217380 0.1828550000 960809553 0 402718720 0.1504612565 0.3210848868 1.2459617853 1311 52.4000000000 0.2343951464 0.1866736707 1.1206738949 0.0198176904 0.1730130000 960811561 0 402718720 0.1504722983 0.3265734017 1.2442671061 1312 52.4400000000 0.2288544327 0.1867058206 1.1206738949 0.0198129902 0.1636760000 960813569 0 402718720 0.1518127322 0.3268485665 1.2433578968 1313 52.4800000000 0.2346383631 0.1867423267 1.1206738949 0.0198066178 0.1745510000 960815577 0 402718720 0.1525865942 0.3381069303 1.2397940159 1314 52.5200000000 0.2350042462 0.1867790558 1.1206738949 0.0198004923 0.1742780000 960817585 0 402718720 0.1541276425 0.3449375629 1.2365231514 1315 52.5600000000 0.2353076935 0.1868159597 1.1206738949 0.0197930973 0.1869200000 960819593 0 402718720 0.1554560065 0.3518389165 1.2335991859 1316 52.6000000000 0.2355508953 0.1868529923 1.1206738949 0.0197855759 0.1757040000 960821601 0 402718720 0.1564667374 0.3580456972 1.2310751677 1317 52.6400000000 0.2356482148 0.1868900426 1.1206738949 0.0197790613 0.1740540000 960823609 0 402718720 0.1579076350 0.3654977381 1.2280472517 1318 52.6800000000 0.2359248251 0.1869272465 1.1206738949 0.0197724945 0.1768070000 960825617 0 402718720 0.1587943882 0.3740707338 1.2250965834 1319 52.7200000000 0.2360593528 0.1869644960 1.1206738949 0.0197654934 0.2014890000 960827625 0 402718720 0.1598522365 0.3821901083 1.2221856117 1320 52.7600000000 0.2362256199 0.1870018151 1.1206738949 0.0197589090 0.2254190000 960829633 0 402718720 0.1603900194 0.3915514946 1.2194486856 1321 52.8000000000 0.2363839000 0.1870391974 1.1206738949 0.0197536632 0.2262950000 960831641 0 402718720 0.1618924290 0.4025555253 1.2157393694 1322 52.8400000000 0.2365952879 0.1870766831 1.1206738949 0.0197463535 0.2266450000 960833649 0 402718720 0.1629540920 0.4117307067 1.2126121521 1323 52.8800000000 0.2367235124 0.1871142090 1.1206738949 0.0197397329 0.2196730000 960835657 0 402718720 0.1640568227 0.4205222428 1.2094786167 1324 52.9200000000 0.2369462699 0.1871518466 1.1206738949 0.0197350656 0.1791850000 960837665 0 402718720 0.1652489156 0.4323197007 1.2056034803 1325 52.9600000000 0.2371217906 0.1871895597 1.1206738949 0.0197294406 0.1931420000 960839673 0 402718720 0.1660139859 0.4434402585 1.2021534443 1326 53.0000000000 0.2372640073 0.1872273233 1.1206738949 0.0197242749 0.1809360000 960841681 0 402718720 0.1671922058 0.4539147615 1.1985683441 1327 53.0400000000 0.2374209613 0.1872651482 1.1206738949 0.0197179875 0.1804760000 960843689 0 402718720 0.1681095064 0.4643453956 1.1950606108 1328 53.0800000000 0.2375038415 0.1873029785 1.1206738949 0.0197136292 0.1796670000 960845697 0 402718720 0.1691869348 0.4765510559 1.1913493872 1329 53.1200000000 0.2376265526 0.1873408442 1.1206738949 0.0197066653 0.1795700000 960847705 0 402718720 0.1693360955 0.4857760370 1.1887431145 1330 53.1600000000 0.2377449274 0.1873787420 1.1206738949 0.0196993372 0.1912200000 960849713 0 402718720 0.1695898324 0.4940763712 1.1858842373 1331 53.2000000000 0.2379372120 0.1874167274 1.1206738949 0.0196964062 0.1820520000 960851721 0 402718720 0.1703960150 0.5066619515 1.1819616556 1332 53.2400000000 0.2383579463 0.1874549715 1.1206738949 0.0196915041 0.1821760000 960853729 0 402718720 0.1714823693 0.5205745101 1.1779116392 1333 53.2800000000 0.2385908961 0.1874933331 1.1206738949 0.0196841649 0.1825030000 960855737 0 402718720 0.1715820581 0.5314193368 1.1743831635 1334 53.3200000000 0.2386179119 0.1875316573 1.1206738949 0.0196776369 0.1828500000 960857745 0 402718720 0.1712683141 0.5419875979 1.1709979773 1335 53.3600000000 0.2386141270 0.1875699214 1.1206738949 0.0196708662 0.1832700000 960859753 0 402718720 0.1712129265 0.5526755452 1.1678127050 1336 53.4000000000 0.2387036085 0.1876081951 1.1206738949 0.0196635849 0.1960870000 960861761 0 402718720 0.1707273424 0.5624565482 1.1651926041 1337 53.4400000000 0.2387501746 0.1876464464 1.1206738949 0.0196562639 0.1837190000 960863769 0 402718720 0.1701017618 0.5703535080 1.1625281572 1338 53.4800000000 0.2389117628 0.1876847613 1.1206738949 0.0196493136 0.1832400000 960865777 0 402718720 0.1703137904 0.5807351470 1.1596575975 1339 53.5200000000 0.2392151952 0.1877232455 1.1206738949 0.0196477073 0.2223600000 960867785 0 402718720 0.1710747778 0.5937888622 1.1563309431 1340 53.5600000000 0.2393690795 0.1877617872 1.1206738949 0.0196493354 0.2331190000 960869793 0 402718720 0.1695738137 0.6136538982 1.1515917778 1341 53.6000000000 0.2394656092 0.1878003434 1.1206738949 0.0196448845 0.2333120000 960871801 0 402718720 0.1693867296 0.6254397631 1.1490064859 1342 53.6400000000 0.2392016351 0.1878386454 1.1206738949 0.0196378771 0.2282400000 960873809 0 402718720 0.1690929532 0.6351661682 1.1472011805 1343 53.6800000000 0.2373488992 0.1878755108 1.1206738949 0.0196311737 0.2139180000 960875817 0 402718720 0.1666326374 0.6393464208 1.1471168995 1344 53.7200000000 0.2390192002 0.1879135641 1.1206738949 0.0196239378 0.1815140000 960877825 0 402718720 0.1661758721 0.6472336054 1.1459360123 1345 53.7600000000 0.2393576801 0.1879518125 1.1206738949 0.0196182475 0.1842840000 960879833 0 402718720 0.1658530086 0.6550812721 1.1453481913 1346 53.8000000000 0.2397082001 0.1879902645 1.1206738949 0.0196128022 0.1845600000 960881841 0 402718720 0.1642834693 0.6604909897 1.1456766129 1347 53.8400000000 0.2397162616 0.1880286654 1.1206738949 0.0196316526 0.1858720000 960883849 0 402718720 0.1637111753 0.6770785451 1.1450122595 1348 53.8800000000 0.2411022633 0.1880680375 1.1206738949 0.0196265638 0.1839430000 960885857 0 402718720 0.1641679853 0.6877133846 1.1446274519 1349 53.9200000000 0.2414027750 0.1881075740 1.1206738949 0.0196194844 0.1867520000 960887865 0 402718720 0.1626805067 0.6935234070 1.1451623440 1350 53.9600000000 0.2414824516 0.1881471110 1.1206738949 0.0196123353 0.1965660000 960889873 0 402718720 0.1624721438 0.6985225081 1.1451281309 1351 54.0000000000 0.2391762137 0.1881848823 1.1206738949 0.0196051445 0.1791610000 960891881 0 402718720 0.1615242064 0.6990571618 1.1459281445 1352 54.0400000000 0.2416110784 0.1882243987 1.1206738949 0.0195981426 0.1879330000 960893889 0 402718720 0.1602817029 0.7041804790 1.1462960243 1353 54.0800000000 0.2421710938 0.1882642707 1.1206738949 0.0195952859 0.1878860000 960895897 0 402718720 0.1598182917 0.7103500366 1.1464376450 1354 54.1200000000 0.2424244285 0.1883042708 1.1206738949 0.0195914828 0.1885850000 960897905 0 402718720 0.1586044878 0.7146523595 1.1468522549 1355 54.1600000000 0.2426144034 0.1883443520 1.1206738949 0.0195883285 0.1884470000 960899913 0 402718720 0.1573043764 0.7183826566 1.1471469402 1356 54.2000000000 0.2427592129 0.1883844810 1.1206738949 0.0195861093 0.1881470000 960901921 0 402718720 0.1561179608 0.7229573727 1.1475783587 1357 54.2400000000 0.2426010072 0.1884244342 1.1206738949 0.0195825281 0.1837430000 960903929 0 402718720 0.1544603556 0.7262488008 1.1479076147 1358 54.2800000000 0.2426219136 0.1884643440 1.1206738949 0.0195764061 0.1823280000 960905937 0 402718720 0.1518799812 0.7276601195 1.1487237215 1359 54.3200000000 0.2433011681 0.1885046949 1.1206738949 0.0195697850 0.1864080000 960907945 0 402718720 0.1485995501 0.7303795218 1.1492917538 1360 54.3600000000 0.2433180809 0.1885449988 1.1206738949 0.0195652259 0.2026510000 960909953 0 402718720 0.1475023776 0.7367852926 1.1495512724 1361 54.4000000000 0.2433070242 0.1885852354 1.1206738949 0.0195581934 0.1807040000 960911961 0 402718720 0.1439721733 0.7385646105 1.1506016254 1362 54.4400000000 0.2429614365 0.1886251592 1.1206738949 0.0195517128 0.1804080000 960913969 0 402718720 0.1409268230 0.7412288189 1.1516668797 1363 54.4800000000 0.2431606650 0.1886651706 1.1206738949 0.0195450578 0.1824560000 960915977 0 402718720 0.1379916519 0.7454977632 1.1526254416 1364 54.5200000000 0.2433227450 0.1887052421 1.1206738949 0.0195382970 0.1811540000 960917985 0 402718720 0.1341049373 0.7475295663 1.1544762850 1365 54.5600000000 0.2431178540 0.1887451049 1.1206738949 0.0195318357 0.2048190000 960919993 0 402718720 0.1294514537 0.7475247383 1.1568095684 1366 54.6000000000 0.2435826659 0.1887852495 1.1206738949 0.0195279750 0.1833570000 960922001 0 402718720 0.1254120618 0.7501699328 1.1589418650 1367 54.6400000000 0.2438542694 0.1888255341 1.1206738949 0.0195293679 0.1831660000 960924009 0 402718720 0.1226027980 0.7562305927 1.1609479189 1368 54.6800000000 0.2440396100 0.1888658952 1.1206738949 0.0195254207 0.1848190000 960926017 0 402718720 0.1178440973 0.7583361268 1.1635117531 1369 54.7200000000 0.2439662069 0.1889061438 1.1206738949 0.0195230708 0.1839120000 960928025 0 402718720 0.1128197610 0.7622951269 1.1660622358 1370 54.7600000000 0.2441854030 0.1889464936 1.1206738949 0.0195206441 0.1948880000 960930033 0 402718720 0.1085642427 0.7687540054 1.1680183411 1371 54.8000000000 0.2443626523 0.1889869139 1.1206738949 0.0195149373 0.1834420000 960932041 0 402718720 0.1031611562 0.7732765079 1.1704370975 1372 54.8400000000 0.2443008721 0.1890272302 1.1206738949 0.0195110181 0.1832460000 960934049 0 402718720 0.0984767154 0.7801655531 1.1724891663 1373 54.8800000000 0.2444204241 0.1890675748 1.1206738949 0.0195066110 0.1952520000 960936057 0 402718720 0.0923575088 0.7853339911 1.1750917435 1374 54.9200000000 0.2442749292 0.1891077549 1.1206738949 0.0195022813 0.1825990000 960938065 0 402718720 0.0850516856 0.7884891033 1.1783394814 1375 54.9600000000 0.2441085428 0.1891477554 1.1206738949 0.0195000649 0.1821770000 960940073 0 402718720 0.0774797797 0.7929872870 1.1813962460 1376 55.0000000000 0.2441826612 0.1891877517 1.1206738949 0.0194991583 0.1824870000 960942081 0 402718720 0.0699390918 0.7980898023 1.1842259169 1377 55.0400000000 0.2442751080 0.1892277571 1.1206738949 0.0194992039 0.1821790000 960944089 0 402718720 0.0620128438 0.8027360439 1.1872630119 1378 55.0800000000 0.2442628592 0.1892676955 1.1206738949 0.0194991506 0.1809050000 960946097 0 402718720 0.0533334538 0.8064989448 1.1909518242 1379 55.1200000000 0.2442973554 0.1893076009 1.1206738949 0.0194984029 0.1837540000 960948105 0 402718720 0.0449328721 0.8107428551 1.1939724684 1380 55.1600000000 0.2443635315 0.1893474965 1.1206738949 0.0195025218 0.2185690000 960950113 0 402718720 0.0374433175 0.8161991239 1.1962711811 1381 55.2000000000 0.2444281578 0.1893873812 1.1206738949 0.0195060286 0.1841550000 960952121 0 402718720 0.0292701907 0.8204311132 1.1993781328 1382 55.2400000000 0.2444516122 0.1894272250 1.1206738949 0.0195095477 0.1820180000 960954129 0 402718720 0.0202120617 0.8238750696 1.2029591799 1383 55.2800000000 0.2444691956 0.1894670240 1.1206738949 0.0195164566 0.1844190000 960956137 0 402718720 0.0133469598 0.8293719888 1.2050851583 1384 55.3200000000 0.2445902377 0.1895068529 1.1206738949 0.0195209203 0.1842950000 960958145 0 402718720 0.0051929420 0.8335843086 1.2078198195 1385 55.3600000000 0.2444059253 0.1895464912 1.1206738949 0.0195269473 0.1835670000 960960153 0 402718720 -0.0020062346 0.8377576470 1.2104703188 1386 55.4000000000 0.2441933006 0.1895859189 1.1206738949 0.0195314212 0.1823220000 960962161 0 402718720 -0.0087556494 0.8416934013 1.2125597000 1387 55.4400000000 0.2439384758 0.1896251061 1.1206738949 0.0195367083 0.1817980000 960964169 0 402718720 -0.0164409764 0.8438559771 1.2156494856 1388 55.4800000000 0.2436148226 0.1896640036 1.1206738949 0.0195402731 0.1816900000 960966177 0 402718720 -0.0240700655 0.8451719284 1.2190493345 1389 55.5200000000 0.2435598671 0.1897028055 1.1206738949 0.0195430302 0.1817030000 960968185 0 402718720 -0.0301329773 0.8476555347 1.2219089270 1390 55.5600000000 0.2436868548 0.1897416429 1.1206738949 0.0195484960 0.1917360000 960970193 0 402718720 -0.0360922590 0.8508068323 1.2247972488 1391 55.6000000000 0.2438015193 0.1897805070 1.1206738949 0.0195495431 0.1821010000 960972201 0 402718720 -0.0406732745 0.8549134135 1.2273669243 1392 55.6400000000 0.2438429743 0.1898193449 1.1206738949 0.0195468291 0.1937770000 960974209 0 402718720 -0.0460212305 0.8575868011 1.2307903767 1393 55.6800000000 0.2437430024 0.1898580554 1.1206738949 0.0195429114 0.2023690000 960976217 0 402718720 -0.0504313521 0.8602762222 1.2340543270 1394 55.7200000000 0.2438313961 0.1898967737 1.1206738949 0.0195390806 0.1822120000 960978225 0 402718720 -0.0547282994 0.8621501923 1.2371833324 1395 55.7600000000 0.2438676655 0.1899354625 1.1206738949 0.0195364390 0.1810350000 960980233 0 402718720 -0.0576439686 0.8638371825 1.2405188084 1396 55.8000000000 0.2439708114 0.1899741698 1.1206738949 0.0195401446 0.1801570000 960982241 0 402718720 -0.0590200573 0.8680652380 1.2433068752 1397 55.8400000000 0.2441213131 0.1900129294 1.1206738949 0.0195443264 0.1787330000 960984249 0 402718720 -0.0626980588 0.8702443242 1.2482813597 1398 55.8800000000 0.2440119237 0.1900515553 1.1206738949 0.0195464817 0.1755590000 960986257 0 402718720 -0.0659893304 0.8721712232 1.2538858652 1399 55.9200000000 0.2440299839 0.1900901389 1.1206738949 0.0195485703 0.1779830000 960988265 0 402718720 -0.0679482818 0.8755895495 1.2588719130 1400 55.9600000000 0.2435375303 0.1901283156 1.1206738949 0.0195477026 0.1732840000 960990273 0 402718720 -0.0686459690 0.8796556592 1.2625018358 1401 56.0000000000 0.2439799607 0.1901667536 1.1206738949 0.0195433509 0.1777180000 960992281 0 402718720 -0.0709089041 0.8833479285 1.2677626610 1402 56.0400000000 0.2437716872 0.1902049882 1.1206738949 0.0195401009 0.1742910000 960994289 0 402718720 -0.0736951083 0.8853711486 1.2735872269 1403 56.0800000000 0.2437307835 0.1902431391 1.1206738949 0.0195392143 0.1738840000 960996297 0 402718720 -0.0754920095 0.8876562715 1.2787516117 1404 56.1200000000 0.2438892126 0.1902813486 1.1206738949 0.0195410724 0.1762740000 960998305 0 402718720 -0.0761771724 0.8924444318 1.2837448120 1405 56.1600000000 0.2440498322 0.1903196180 1.1206738949 0.0195412428 0.1734750000 961000313 0 402718720 -0.0772824660 0.8961724639 1.2892161608 1406 56.2000000000 0.2443026155 0.1903580127 1.1206738949 0.0195752123 0.1776590000 961002321 0 402718720 -0.0789060369 0.9064121246 1.3023438454 1407 56.2400000000 0.2443440408 0.1903963823 1.1206738949 0.0195748382 0.1768930000 961004329 0 402718720 -0.0789313391 0.9127258658 1.3090405464 1408 56.2800000000 0.2441995591 0.1904345948 1.1206738949 0.0195723905 0.1747930000 961006337 0 402718720 -0.0810420811 0.9160681963 1.3174128532 1409 56.3200000000 0.2440610081 0.1904726547 1.1206738949 0.0195733659 0.1762740000 961008345 0 402718720 -0.0822889283 0.9187846780 1.3251867294 1410 56.3600000000 0.2442281991 0.1905107792 1.1206738949 0.0195853152 0.1852120000 961010353 0 402718720 -0.0823519006 0.9259000421 1.3321138620 1411 56.4000000000 0.2441983521 0.1905488285 1.1206738949 0.0195902047 0.1755630000 961012361 0 402718720 -0.0834609643 0.9309322834 1.3401008844 1412 56.4400000000 0.2441316694 0.1905867767 1.1206738949 0.0195928107 0.1741710000 961014369 0 402718720 -0.0860071033 0.9333052039 1.3487905264 1413 56.4800000000 0.2440058738 0.1906245822 1.1206738949 0.0195971648 0.1730350000 961016377 0 402718720 -0.0868382528 0.9394636154 1.3568139076 1414 56.5200000000 0.2441433072 0.1906624313 1.1206738949 0.0195977410 0.1756620000 961018385 0 402718720 -0.0868454650 0.9469395280 1.3639497757 1415 56.5600000000 0.2442747205 0.1907003199 1.1206738949 0.0195947413 0.1732240000 961020393 0 402718720 -0.0879220441 0.9524811506 1.3713750839 1416 56.6000000000 0.2442647070 0.1907381478 1.1206738949 0.0195940400 0.1753750000 961022401 0 402718720 -0.0881225765 0.9592860341 1.3773128986 1417 56.6400000000 0.2442554682 0.1907759159 1.1206738949 0.0195932560 0.1754870000 961024409 0 402718720 -0.0887232646 0.9651117325 1.3828997612 1418 56.6800000000 0.2441337854 0.1908135448 1.1206738949 0.0195929577 0.1747400000 961026417 0 402718720 -0.0894529745 0.9700860381 1.3889132738 1419 56.7200000000 0.2440953553 0.1908510937 1.1206738949 0.0195953368 0.1737850000 961028425 0 402718720 -0.0906109661 0.9745502472 1.3949613571 1420 56.7600000000 0.2438999861 0.1908884521 1.1206738949 0.0195976845 0.1832130000 961030433 0 402718720 -0.0912643448 0.9797158241 1.4005645514 1421 56.8000000000 0.2439524680 0.1909257948 1.1206738949 0.0195981214 0.1701700000 961032441 0 402718720 -0.0927143767 0.9836850762 1.4062874317 1422 56.8400000000 0.2439419776 0.1909630776 1.1206738949 0.0195998602 0.1975920000 961034449 0 402718720 -0.0938033685 0.9881374240 1.4114059210 1423 56.8800000000 0.2439233512 0.1910002949 1.1206738949 0.0196005547 0.2044590000 961036457 0 402718720 -0.0936765522 0.9935826063 1.4157414436 1424 56.9200000000 0.2440182269 0.1910375266 1.1206738949 0.0195975296 0.2206560000 961038465 0 402718720 -0.0941751152 0.9990946651 1.4210067987 1425 56.9600000000 0.2439411581 0.1910746520 1.1206738949 0.0195925191 0.2198750000 961040473 0 402718720 -0.0969334096 1.0006066561 1.4278136492 1426 57.0000000000 0.2437779754 0.1911116109 1.1206738949 0.0195904165 0.2192840000 961042481 0 402718720 -0.0974796340 1.0043982267 1.4329935312 1427 57.0400000000 0.2439504564 0.1911486388 1.1206738949 0.0195888357 0.1964400000 961044489 0 402718720 -0.0983043164 1.0098428726 1.4386588335 1428 57.0800000000 0.2440404147 0.1911856778 1.1206738949 0.0195864054 0.1712910000 961046497 0 402718720 -0.0997360572 1.0140135288 1.4457591772 1429 57.1200000000 0.2442757934 0.1912228298 1.1206738949 0.0195837007 0.1710840000 961048505 0 402718720 -0.1008223966 1.0188239813 1.4515939951 1430 57.1600000000 0.2441932112 0.1912598720 1.1206738949 0.0195810135 0.1791620000 961050513 0 402718720 -0.1017140150 1.0235034227 1.4581700563 1431 57.2000000000 0.2442915589 0.1912969312 1.1206738949 0.0195796177 0.1680820000 961052521 0 402718720 -0.1041049138 1.0267966986 1.4657691717 1432 57.2400000000 0.2443162054 0.1913339558 1.1206738949 0.0195788566 0.1704010000 961054529 0 402718720 -0.1059327722 1.0304975510 1.4721838236 1433 57.2800000000 0.2444821298 0.1913710446 1.1206738949 0.0195774272 0.1692990000 961056537 0 402718720 -0.1073718593 1.0353590250 1.4788340330 1434 57.3200000000 0.2445097715 0.1914081008 1.1206738949 0.0195790018 0.1680150000 961058545 0 402718720 -0.1096308902 1.0392781496 1.4863222837 1435 57.3600000000 0.2445623726 0.1914451422 1.1206738949 0.0195832081 0.1674850000 961060553 0 402718720 -0.1118626893 1.0433056355 1.4933089018 1436 57.4000000000 0.2447273731 0.1914822468 1.1206738949 0.0195879884 0.1795660000 961062561 0 402718720 -0.1136262789 1.0478507280 1.5001138449 1437 57.4400000000 0.2447991967 0.1915193497 1.1206738949 0.0195955917 0.1669070000 961064569 0 402718720 -0.1161117703 1.0525181293 1.5091239214 1438 57.4800000000 0.2448244393 0.1915564186 1.1206738949 0.0196027327 0.1672210000 961066577 0 402718720 -0.1165101901 1.0593178272 1.5158156157 1439 57.5200000000 0.2450589985 0.1915935990 1.1206738949 0.0196078039 0.1668590000 961068585 0 402718720 -0.1170024574 1.0674884319 1.5222257376 1440 57.5600000000 0.2452328503 0.1916308485 1.1206738949 0.0196086268 0.1754600000 961070593 0 402718720 -0.1183369532 1.0727834702 1.5294028521 1441 57.6000000000 0.2453653067 0.1916681382 1.1206738949 0.0196108374 0.1676770000 961072601 0 402718720 -0.1197842136 1.0771857500 1.5364481211 1442 57.6400000000 0.2453543246 0.1917053686 1.1206738949 0.0196093625 0.1791360000 961074609 0 402718720 -0.1195238531 1.0833233595 1.5415179729 1443 57.6800000000 0.2454802096 0.1917426346 1.1206738949 0.0196053289 0.1649940000 961076617 0 402718720 -0.1203517020 1.0883414745 1.5481410027 1444 57.7200000000 0.2455998957 0.1917799318 1.1206738949 0.0196005253 0.1644970000 961078625 0 402718720 -0.1216455400 1.0905435085 1.5540047884 1445 57.7600000000 0.2456083447 0.1918171833 1.1206738949 0.0195983809 0.1620360000 961080633 0 402718720 -0.1221346557 1.0947681665 1.5604515076 1446 57.8000000000 0.2456369102 0.1918544031 1.1206738949 0.0195940535 0.1635180000 961082641 0 402718720 -0.1216507182 1.1008200645 1.5652266741 1447 57.8400000000 0.2457418889 0.1918916439 1.1206738949 0.0195879292 0.1629960000 961084649 0 402718720 -0.1225863770 1.1028691530 1.5707837343 1448 57.8800000000 0.2458558679 0.1919289120 1.1206738949 0.0195836733 0.1625510000 961086657 0 402718720 -0.1234593391 1.1048064232 1.5763082504 1449 57.9200000000 0.2459313422 0.1919661808 1.1206738949 0.0195802643 0.1620650000 961088665 0 402718720 -0.1233590320 1.1084403992 1.5809973478 1450 57.9600000000 0.2460179478 0.1920034579 1.1206738949 0.0195760886 0.1724470000 961090673 0 402718720 -0.1233922467 1.1120716333 1.5858265162 1451 58.0000000000 0.2460785061 0.1920407253 1.1206738949 0.0195707874 0.1603250000 961092681 0 402718720 -0.1236979589 1.1148519516 1.5905562639 1452 58.0400000000 0.2462195009 0.1920780385 1.1206738949 0.0195660374 0.1613810000 961094689 0 402718720 -0.1231513843 1.1183717251 1.5961097479 1453 58.0800000000 0.2463650852 0.1921154005 1.1206738949 0.0195609533 0.1603560000 961096697 0 402718720 -0.1224925518 1.1217432022 1.6016525030 1454 58.1200000000 0.2461604923 0.1921525705 1.1206738949 0.0195548636 0.1535120000 961098705 0 402718720 -0.1213293374 1.1228291988 1.6064827442 1455 58.1600000000 0.2456898987 0.1921893659 1.1206738949 0.0195491852 0.1678090000 961100713 0 402718720 -0.1204243898 1.1237676144 1.6109977961 1456 58.2000000000 0.2454040647 0.1922259144 1.1206738949 0.0195440280 0.1642480000 961102721 0 402718720 -0.1183384210 1.1245940924 1.6145293713 1457 58.2400000000 0.2464947850 0.1922631614 1.1206738949 0.0195396323 0.1571930000 961104729 0 402718720 -0.1156893224 1.1284724474 1.6177889109 1458 58.2800000000 0.2465841025 0.1923004186 1.1206738949 0.0195340850 0.1540270000 961106737 0 402718720 -0.1127210110 1.1318238974 1.6220184565 1459 58.3200000000 0.2460842580 0.1923372821 1.1206738949 0.0195277976 0.1520520000 961108745 0 402718720 -0.1097410917 1.1328349113 1.6255207062 1460 58.3600000000 0.2460008860 0.1923740380 1.1206738949 0.0195211104 0.1485400000 961110753 0 402718720 -0.1063963249 1.1335893869 1.6286250353 1461 58.4000000000 0.2456036359 0.1924104717 1.1206738949 0.0195144366 0.1467240000 961112761 0 402718720 -0.1024888754 1.1350960732 1.6325246096 1462 58.4400000000 0.2456403226 0.1924468806 1.1206738949 0.0195078373 0.1597890000 961114769 0 402718720 -0.0979645103 1.1364518404 1.6367909908 1463 58.4800000000 0.2411088645 0.1924801424 1.1206738949 0.0195014831 0.1431130000 961116777 0 402718720 -0.0942349285 1.1336829662 1.6424345970 1464 58.5200000000 0.2390653044 0.1925119628 1.1206738949 0.0194948754 0.1422620000 961118785 0 402718720 -0.0894745812 1.1332676411 1.6468493938 1465 58.5600000000 0.2379898578 0.1925430058 1.1206738949 0.0194882494 0.1412130000 961120793 0 402718720 -0.0842421502 1.1335312128 1.6507966518 1466 58.6000000000 0.2461579144 0.1925795780 1.1206738949 0.0194820004 0.1467890000 961122801 0 402718720 -0.0775246173 1.1423103809 1.6500884295 1467 58.6400000000 0.2451768070 0.1926154316 1.1206738949 0.0194753876 0.1417620000 961124809 0 402718720 -0.0720347315 1.1433604956 1.6540895700 1468 58.6800000000 0.2451584041 0.1926512238 1.1206738949 0.0194689905 0.1373620000 961126817 0 402718720 -0.0667578056 1.1445184946 1.6570283175 1469 58.7200000000 0.2449985594 0.1926868585 1.1206738949 0.0194624186 0.1382280000 961128825 0 402718720 -0.0611578450 1.1455527544 1.6597057581 1470 58.7600000000 0.2464715838 0.1927234467 1.1206738949 0.0194567074 0.1419010000 961130833 0 402718720 -0.0545817167 1.1504591703 1.6608504057 1471 58.8000000000 0.2450001538 0.1927589850 1.1206738949 0.0194501587 0.1357940000 961132841 0 402718720 -0.0492210165 1.1518738270 1.6640684605 1472 58.8400000000 0.2465972602 0.1927955599 1.1206738949 0.0194438916 0.1474610000 961134849 0 402718720 -0.0434142537 1.1559679508 1.6665513515 1473 58.8800000000 0.2466955930 0.1928321519 1.1206738949 0.0194377277 0.1370420000 961136857 0 402718720 -0.0376571268 1.1587715149 1.6683734655 1474 58.9200000000 0.2467130721 0.1928687061 1.1206738949 0.0194320176 0.1354880000 961138865 0 402718720 -0.0319713764 1.1611678600 1.6690531969 1475 58.9600000000 0.2467215955 0.1929052165 1.1206738949 0.0194257399 0.1337110000 961140873 0 402718720 -0.0261182599 1.1637206078 1.6696566343 1476 59.0000000000 0.2467564195 0.1929417011 1.1206738949 0.0194191894 0.1314290000 961142881 0 402718720 -0.0206379909 1.1670755148 1.6699752808 1477 59.0400000000 0.2455344498 0.1929773089 1.1206738949 0.0194126465 0.1263950000 961144889 0 402718720 -0.0157988034 1.1684337854 1.6719303131 1478 59.0800000000 0.2426019311 0.1930108844 1.1206738949 0.0194061012 0.1220540000 961146897 0 402718720 -0.0111050233 1.1682943106 1.6754711866 1479 59.1200000000 0.2381388545 0.1930413969 1.1206738949 0.0194001738 0.1203970000 961148905 0 402718720 -0.0024091527 1.1691268682 1.6789391041 1480 59.1600000000 0.2339732796 0.1930690536 1.1206738949 0.0193941175 0.1197260000 961150913 0 402718720 0.0014630188 1.1680464745 1.6824562550 1481 59.2000000000 0.2316573113 0.1930951091 1.1206738949 0.0193877063 0.1189530000 961152921 0 402718720 0.0048190407 1.1672804356 1.6845546961 1482 59.2400000000 0.2287553102 0.1931191714 1.1206738949 0.0193813464 0.1184430000 961154929 0 402718720 0.0081341937 1.1670836210 1.6869442463 1483 59.2800000000 0.2279364169 0.1931426489 1.1206738949 0.0193749822 0.1177180000 961156937 0 402718720 0.0113624511 1.1690397263 1.6875572205 1484 59.3200000000 0.2280621678 0.1931661796 1.1206738949 0.0193689010 0.1152880000 961158945 0 402718720 0.0146321319 1.1713600159 1.6877195835 1485 59.3600000000 0.2284819186 0.1931899612 1.1206738949 0.0193631324 0.1287090000 961160953 0 402718720 0.0178988483 1.1733448505 1.6874089241 1486 59.4000000000 0.2288238406 0.1932139410 1.1206738949 0.0193567691 0.1163650000 961162961 0 402718720 0.0205870029 1.1751524210 1.6869140863 1487 59.4400000000 0.2271398157 0.1932367560 1.1206738949 0.0193503415 0.1474100000 961164969 0 402718720 0.0230364297 1.1751937866 1.6875489950 1488 59.4800000000 0.2422425151 0.1932696899 1.1206738949 0.0193449630 0.1227930000 961166977 0 402718720 0.0254241023 1.1928260326 1.6784720421 1489 59.5200000000 0.2400589436 0.1933011132 1.1206738949 0.0193385296 0.1160420000 961168985 0 402718720 0.0278435294 1.1922554970 1.6789405346 1490 59.5600000000 0.2355222255 0.1933294495 1.1206738949 0.0193326956 0.1105770000 961170993 0 402718720 0.0304767098 1.1903368235 1.6776890755 1491 59.6000000000 0.2341859788 0.1933568516 1.1206738949 0.0193269453 0.1087570000 961173001 0 402718720 0.0326384418 1.1912957430 1.6753326654 1492 59.6400000000 0.2320268452 0.1933827698 1.1206738949 0.0193207170 0.1212280000 961175009 0 402718720 0.0346398689 1.1909615993 1.6766272783 1493 59.6800000000 0.2309935093 0.1934079612 1.1206738949 0.0193142584 0.1093180000 961177017 0 402718720 0.0373356231 1.1935999393 1.6774111986 1494 59.7200000000 0.2303869575 0.1934327129 1.1206738949 0.0193077895 0.1088140000 961179025 0 402718720 0.0395954251 1.1948742867 1.6783473492 1495 59.7600000000 0.2308977246 0.1934577731 1.1206738949 0.0193020814 0.1098320000 961181033 0 402718720 0.0415558144 1.1970630884 1.6765316725 1496 59.8000000000 0.2402877212 0.1934890766 1.1206738949 0.0192964311 0.1176280000 961183041 0 402718720 0.0432110354 1.2082458735 1.6816606522 1497 59.8400000000 0.2393473536 0.1935197100 1.1206738949 0.0192917107 0.1080220000 961185049 0 402718720 0.0450389087 1.2095941305 1.6791468859 1498 59.8800000000 0.2378420979 0.1935492977 1.1206738949 0.0192854739 0.1079220000 961187057 0 402718720 0.0469833165 1.2113707066 1.6791083813 1499 59.9200000000 0.2365904897 0.1935780110 1.1206738949 0.0192790920 0.1058400000 961189065 0 402718720 0.0484753326 1.2119359970 1.6804236174 1500 59.9600000000 0.2369807363 0.1936069461 1.1206738949 0.0192728437 0.1071110000 961191073 0 402718720 0.0500170141 1.2131267786 1.6796491146 1501 60.0000000000 0.2369942218 0.1936358517 1.1206738949 0.0192666558 0.1066860000 961193081 0 402718720 0.0513266511 1.2140612602 1.6782376766 1502 60.0400000000 0.2354731411 0.1936637061 1.1206738949 0.0192604030 0.1158960000 961195089 0 402718720 0.0523382500 1.2134139538 1.6775728464 1503 60.0800000000 0.2398279160 0.1936944208 1.1206738949 0.0192541931 0.1089870000 961197097 0 402718720 0.0536086485 1.2184090614 1.6833971739 1504 60.1200000000 0.2378808260 0.1937238001 1.1206738949 0.0192480966 0.1073850000 961199105 0 402718720 0.0547916219 1.2175796032 1.6821757555 1505 60.1600000000 0.2397862077 0.1937544063 1.1206738949 0.0192419192 0.1092770000 961201113 0 402718720 0.0563548915 1.2199881077 1.6828558445 1506 60.2000000000 0.2397286147 0.1937849337 1.1206738949 0.0192358850 0.1081090000 961203121 0 402718720 0.0579903536 1.2206512690 1.6838873625 1507 60.2400000000 0.2397893220 0.1938154608 1.1206738949 0.0192297800 0.1190790000 961205129 0 402718720 0.0594032630 1.2199033499 1.6839807034 1508 60.2800000000 0.2397544980 0.1938459244 1.1206738949 0.0192239911 0.1070690000 961207137 0 402718720 0.0607753918 1.2200261354 1.6860468388 1509 60.3200000000 0.2398318946 0.1938763988 1.1206738949 0.0192178620 0.1054490000 961209145 0 402718720 0.0625025854 1.2203093767 1.6874403954 1510 60.3600000000 0.2360306382 0.1939043156 1.1206738949 0.0192116476 0.0990000000 961211153 0 402718720 0.0637642741 1.2157505751 1.6881649494 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 12:48:52 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.1198340000 954998708 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0002914428 0.0001457214 0.0002914428 0.0020543386 0.1412660000 957791657 0 402718720 0.0002576366 0.0005310783 0.0001826170 3 0.0800000000 0.0004575807 0.0002496745 0.0004575807 0.0017299560 0.1425290000 957480969 0 402718720 0.0003169646 -0.0020086665 -0.0006931318 4 0.1200000000 0.0004246485 0.0002934180 0.0004575807 0.0014812560 0.1418110000 957483377 0 402718720 0.0004796197 -0.0013548768 -0.0006147901 5 0.1600000000 0.0006736197 0.0003694583 0.0006736197 0.0014687719 0.1426460000 957485385 0 402718720 0.0005452507 -0.0009305010 -0.0004298980 6 0.2000000000 0.0006571013 0.0004173988 0.0006736197 0.0016122809 0.1426260000 957488193 0 402718720 0.0006313116 -0.0019516179 -0.0007426783 7 0.2400000000 0.0007785360 0.0004689899 0.0007785360 0.0016036886 0.1428560000 957490201 0 402718720 0.0006579758 -0.0021564988 -0.0008142746 8 0.2800000000 0.0007657159 0.0005060806 0.0007785360 0.0016113062 0.1426860000 957492209 0 402718720 0.0005132071 -0.0009043808 -0.0003788133 9 0.3200000000 0.0007769944 0.0005361821 0.0007785360 0.0015158172 0.1427610000 957494217 0 402718720 0.0007062656 -0.0008353018 -0.0003089358 10 0.3600000000 0.0007578428 0.0005583482 0.0007785360 0.0014554848 0.1429020000 957497825 0 402718720 0.0007058932 -0.0015183770 -0.0004736031 11 0.4000000000 0.0007899872 0.0005794063 0.0007899872 0.0013905465 0.1429540000 957499833 0 402718720 0.0006103133 -0.0008904867 -0.0003014771 12 0.4400000000 0.0008149633 0.0005990360 0.0008149633 0.0013428028 0.1426770000 957501841 0 402718720 0.0006533800 -0.0000866794 -0.0000066326 13 0.4800000000 0.0007847900 0.0006133248 0.0008149633 0.0013143690 0.1427050000 957503849 0 402718720 0.0005742029 0.0004037413 0.0003143606 14 0.5200000000 0.0007725436 0.0006246976 0.0008149633 0.0014180374 0.1425700000 957505857 0 402718720 0.0007185687 0.0004872703 0.0004009104 15 0.5600000000 0.0008258293 0.0006381064 0.0008258293 0.0015058938 0.1444270000 957507865 0 402718720 0.0007671415 0.0005712861 0.0004755184 16 0.6000000000 0.0008129579 0.0006490346 0.0008258293 0.0014903027 0.1831270000 957509873 0 402718720 0.0010690460 0.0005243153 0.0004196161 17 0.6400000000 0.0008736401 0.0006622467 0.0008736401 0.0014551366 0.1831040000 957511881 0 402718720 0.0010282139 0.0003621154 0.0004575023 18 0.6800000000 0.0008957467 0.0006752189 0.0008957467 0.0014297943 0.1831750000 957517089 0 402718720 0.0010211807 -0.0002855957 0.0002168434 19 0.7200000000 0.0008397871 0.0006838804 0.0008957467 0.0015664228 0.1828770000 957519097 0 402718720 0.0008904802 -0.0002151655 0.0001455346 20 0.7600000000 0.0008188996 0.0006906313 0.0008957467 0.0017824468 0.1833790000 957521105 0 402718720 0.0006805861 -0.0004511911 0.0000468907 21 0.8000000000 0.0009577657 0.0007033520 0.0009577657 0.0019830317 0.1617960000 957523113 0 402718720 0.0007437011 -0.0005472701 -0.0000902079 22 0.8400000000 0.0008393513 0.0007095338 0.0009577657 0.0020046927 0.1435740000 957525121 0 402718720 0.0007198920 -0.0004002971 0.0000060766 23 0.8800000000 0.0009259677 0.0007189440 0.0009577657 0.0020143236 0.1437100000 957527129 0 402718720 0.0004912936 -0.0005280175 -0.0000568980 24 0.9200000000 0.0009945870 0.0007304291 0.0009945870 0.0019797342 0.1442110000 957529137 0 402718720 0.0005700621 -0.0003526160 -0.0000486157 25 0.9600000000 0.0009868252 0.0007406849 0.0009945870 0.0019405254 0.1436690000 957531145 0 402718720 0.0002763969 -0.0003291234 -0.0000494970 26 1.0000000000 0.0009846282 0.0007500674 0.0009945870 0.0019032921 0.1557250000 957533153 0 402718720 0.0004315933 -0.0000767965 -0.0000018776 27 1.0400000000 0.0009465406 0.0007573442 0.0009945870 0.0018736292 0.1587350000 957535161 0 402718720 0.0001224487 -0.0000967839 -0.0000268392 28 1.0800000000 0.0009420776 0.0007639418 0.0009945870 0.0018679600 0.1424970000 957537169 0 402718720 0.0000084998 -0.0002123610 0.0000079318 29 1.1200000000 0.0009395301 0.0007699966 0.0009945870 0.0018453809 0.1429480000 957539177 0 402718720 -0.0003402380 0.0000325993 0.0001156331 30 1.1600000000 0.0009081897 0.0007746030 0.0009945870 0.0018347854 0.1446150000 957541185 0 402718720 -0.0001608298 0.0004398620 0.0000888342 31 1.2000000000 0.0009573795 0.0007804990 0.0009945870 0.0018286604 0.1442020000 957543193 0 402718720 -0.0003290085 0.0002394324 0.0000663741 32 1.2400000000 0.0009801518 0.0007867382 0.0009945870 0.0018058796 0.1550450000 957545201 0 402718720 -0.0005377722 -0.0001775220 0.0000323861 33 1.2800000000 0.0009833234 0.0007926953 0.0009945870 0.0018225679 0.1439500000 957547209 0 402718720 -0.0007750055 -0.0000378196 0.0001884561 34 1.3200000000 0.0009793647 0.0007981856 0.0009945870 0.0018263317 0.1450020000 957555617 0 402718720 -0.0012330759 -0.0003529237 0.0002597984 35 1.3600000000 0.0009890853 0.0008036398 0.0009945870 0.0018178694 0.1444130000 957557625 0 402718720 -0.0015807091 -0.0011491084 0.0000277142 36 1.4000000000 0.0010653049 0.0008109083 0.0010653049 0.0018013811 0.1571760000 957559633 0 402718720 -0.0018435677 -0.0013323824 0.0000051381 37 1.4400000000 0.0009764084 0.0008153813 0.0010653049 0.0017775533 0.1443520000 957561641 0 402718720 -0.0020525376 -0.0008965685 0.0002431711 38 1.4800000000 0.0010503383 0.0008215644 0.0010653049 0.0017535552 0.1564430000 957563649 0 402718720 -0.0022167009 -0.0013387194 0.0002744595 39 1.5200000000 0.0010735631 0.0008280259 0.0010735631 0.0017446502 0.1554480000 957565657 0 402718720 -0.0027704723 -0.0028814746 -0.0000497602 40 1.5600000000 0.0010202461 0.0008328314 0.0010735631 0.0018691154 0.1426050000 957567665 0 402718720 -0.0030631605 -0.0025104359 0.0003490478 41 1.6000000000 0.0010399134 0.0008378822 0.0010735631 0.0020499679 0.1892790000 957569673 0 402718720 -0.0034069682 -0.0012881341 0.0010615619 42 1.6400000000 0.0010803631 0.0008436555 0.0010803631 0.0021361135 0.1622080000 957571681 0 402718720 -0.0039436314 -0.0015620856 0.0014199257 43 1.6800000000 0.0010614009 0.0008487194 0.0010803631 0.0021591722 0.1423550000 957573689 0 402718720 -0.0041735838 -0.0016940433 0.0019552123 44 1.7200000000 0.0010709943 0.0008537711 0.0010803631 0.0021464846 0.1417860000 957575697 0 402718720 -0.0046051769 -0.0013328765 0.0026029132 45 1.7600000000 0.0011050560 0.0008593552 0.0011050560 0.0021524055 0.1427400000 957577705 0 402718720 -0.0048907814 -0.0017812592 0.0031567290 46 1.8000000000 0.0010610414 0.0008637397 0.0011050560 0.0022888169 0.1555530000 957579713 0 402718720 -0.0052161389 -0.0029085858 0.0037044061 47 1.8400000000 0.0010728205 0.0008681882 0.0011050560 0.0024670897 0.1553390000 957581721 0 402718720 -0.0052517238 -0.0033048298 0.0045957877 48 1.8800000000 0.0010728526 0.0008724520 0.0011050560 0.0026830316 0.1421510000 957583729 0 402718720 -0.0055705542 -0.0033987053 0.0060322727 49 1.9200000000 0.0010966149 0.0008770268 0.0011050560 0.0030013591 0.1439000000 957585737 0 402718720 -0.0055202860 -0.0047760224 0.0070743789 50 1.9600000000 0.0010707565 0.0008809014 0.0011050560 0.0032999786 0.1439580000 957587745 0 402718720 -0.0055059721 -0.0053352476 0.0085820016 51 2.0000000000 0.0010687025 0.0008845838 0.0011050560 0.0034952394 0.1436230000 957589753 0 402718720 -0.0054250695 -0.0051877834 0.0104800640 52 2.0400000000 0.0010814809 0.0008883702 0.0011050560 0.0036497336 0.1511930000 957591761 0 402718720 -0.0048514828 -0.0053065424 0.0124021163 53 2.0800000000 0.0010926173 0.0008922240 0.0011050560 0.0037196020 0.1828100000 957593769 0 402718720 -0.0044627814 -0.0065201465 0.0140533745 54 2.1200000000 0.0010604092 0.0008953385 0.0011050560 0.0037954063 0.1845660000 957595777 0 402718720 -0.0035291126 -0.0072403965 0.0158395693 55 2.1600000000 0.0010517519 0.0008981824 0.0011050560 0.0037999075 0.1817910000 957597785 0 402718720 -0.0031631279 -0.0070164916 0.0183323622 56 2.2000000000 0.0010631818 0.0009011288 0.0011050560 0.0037842176 0.1833440000 957599793 0 402718720 -0.0026609700 -0.0067375740 0.0208449326 57 2.2400000000 0.0010417544 0.0009035959 0.0011050560 0.0038058440 0.1833120000 957601801 0 402718720 -0.0015393238 -0.0068750484 0.0232608113 58 2.2800000000 0.0010687471 0.0009064433 0.0011050560 0.0038658735 0.1829850000 957603809 0 402718720 -0.0008393067 -0.0058482122 0.0261066575 59 2.3200000000 0.0010615431 0.0009090722 0.0011050560 0.0039771864 0.1833220000 957605817 0 402718720 0.0004146066 -0.0060810125 0.0287529379 60 2.3600000000 0.0010825454 0.0009119634 0.0011050560 0.0042842492 0.1832680000 957607825 0 402718720 0.0013389952 -0.0073558087 0.0311642028 61 2.4000000000 0.0010654522 0.0009144796 0.0011050560 0.0045525984 0.1831270000 957609833 0 402718720 0.0026151396 -0.0073969648 0.0340852849 62 2.4400000000 0.0010431575 0.0009165550 0.0011050560 0.0048140513 0.1761660000 957611841 0 402718720 0.0038681468 -0.0074630473 0.0369985364 63 2.4800000000 0.0010704731 0.0009189982 0.0011050560 0.0050060086 0.1556340000 957613849 0 402718720 0.0053130933 -0.0081092501 0.0397000574 64 2.5200000000 0.0010202598 0.0009205804 0.0011050560 0.0051431193 0.1431330000 957615857 0 402718720 0.0068567838 -0.0077981162 0.0428435467 65 2.5600000000 0.0010555177 0.0009226564 0.0011050560 0.0054010469 0.1435150000 957617865 0 402718720 0.0080820648 -0.0081397332 0.0456999876 66 2.6000000000 0.0010351015 0.0009243601 0.0011050560 0.0057554642 0.1433510000 957632673 0 402718720 0.0098275030 -0.0091044800 0.0482499488 67 2.6400000000 0.0012045242 0.0009285416 0.0012045242 0.0060400982 0.1584780000 957634681 0 402718720 0.0120426472 -0.0075079338 0.0516151153 68 2.6800000000 0.0010379005 0.0009301498 0.0012045242 0.0064607072 0.1553650000 957636689 0 402718720 0.0122796148 -0.0074343644 0.0544127934 69 2.7200000000 0.0010208939 0.0009314650 0.0012045242 0.0066812020 0.1406030000 957638697 0 402718720 0.0140609462 -0.0082650622 0.0570884347 70 2.7600000000 0.0010313940 0.0009328925 0.0012045242 0.0068093125 0.1392060000 957640705 0 402718720 0.0155670168 -0.0089869546 0.0595701672 71 2.8000000000 0.0010175069 0.0009340843 0.0012045242 0.0068355467 0.1412220000 957642713 0 402718720 0.0168179572 -0.0082857590 0.0625929609 72 2.8400000000 0.0009879618 0.0009348326 0.0012045242 0.0068266125 0.1401890000 957644721 0 402718720 0.0182622038 -0.0085620116 0.0652742311 73 2.8800000000 0.0010239732 0.0009360537 0.0012045242 0.0068161673 0.1394920000 957646729 0 402718720 0.0196079090 -0.0090490216 0.0677426904 74 2.9200000000 0.0010153168 0.0009371248 0.0012045242 0.0068313917 0.1382380000 957648737 0 402718720 0.0211039446 -0.0082249232 0.0706285760 75 2.9600000000 0.0010089446 0.0009380824 0.0012045242 0.0069013008 0.1402420000 957650745 0 402718720 0.0224400852 -0.0078721046 0.0733375922 76 3.0000000000 0.0010521146 0.0009395828 0.0012045242 0.0070772018 0.1399860000 957652753 0 402718720 0.0239498578 -0.0090613849 0.0755382702 77 3.0400000000 0.0010767061 0.0009413637 0.0012045242 0.0072409153 0.1511350000 957654761 0 402718720 0.0250698011 -0.0101912245 0.0776417851 78 3.0800000000 0.0010220049 0.0009423975 0.0012045242 0.0074731126 0.1613050000 957656769 0 402718720 0.0265514497 -0.0095477281 0.0804634467 79 3.1200000000 0.0010240838 0.0009434315 0.0012045242 0.0076773764 0.1541930000 957658777 0 402718720 0.0273549352 -0.0093095629 0.0831950828 80 3.1600000000 0.0010609876 0.0009449010 0.0012045242 0.0078212717 0.1424490000 957660785 0 402718720 0.0284427423 -0.0103359204 0.0854343399 81 3.2000000000 0.0010250158 0.0009458900 0.0012045242 0.0079751786 0.1428030000 957662793 0 402718720 0.0297383051 -0.0105970120 0.0879570767 82 3.2400000000 0.0010291801 0.0009469058 0.0012045242 0.0081524320 0.1412890000 957664801 0 402718720 0.0302784182 -0.0108442316 0.0904757157 83 3.2800000000 0.0010357638 0.0009479764 0.0012045242 0.0083405582 0.1563790000 957666809 0 402718720 0.0313617364 -0.0117397849 0.0928760543 84 3.3200000000 0.0010231369 0.0009488711 0.0012045242 0.0084486174 0.1557110000 957668817 0 402718720 0.0321037844 -0.0119429724 0.0954185203 85 3.3600000000 0.0009767156 0.0009491987 0.0012045242 0.0085187956 0.1418480000 957670825 0 402718720 0.0326521546 -0.0115751764 0.0981874019 86 3.4000000000 0.0009714318 0.0009494572 0.0012045242 0.0085820545 0.1439340000 957672833 0 402718720 0.0334420465 -0.0117150368 0.1007667035 87 3.4400000000 0.0009468052 0.0009494267 0.0012045242 0.0086553878 0.1561750000 957674841 0 402718720 0.0342691392 -0.0116602369 0.1036144793 88 3.4800000000 0.0009740611 0.0009497067 0.0012045242 0.0087433853 0.1465160000 957676849 0 402718720 0.0350775756 -0.0119864233 0.1063810140 89 3.5200000000 0.0009447467 0.0009496509 0.0012045242 0.0088275078 0.1446040000 957678857 0 402718720 0.0358547084 -0.0119589716 0.1092832834 90 3.5600000000 0.0009556977 0.0009497181 0.0012045242 0.0089455137 0.1451240000 957680865 0 402718720 0.0363141932 -0.0119190905 0.1122476533 91 3.6000000000 0.0009458388 0.0009496755 0.0012045242 0.0090855088 0.1456570000 957682873 0 402718720 0.0375249237 -0.0124855936 0.1152555048 92 3.6400000000 0.0009603600 0.0009497916 0.0012045242 0.0091760229 0.1444770000 957684881 0 402718720 0.0380613580 -0.0127018346 0.1184263527 93 3.6800000000 0.0009518234 0.0009498135 0.0012045242 0.0091791335 0.1463030000 957686889 0 402718720 0.0385114551 -0.0132183591 0.1213698536 94 3.7200000000 0.0008923730 0.0009492024 0.0012045242 0.0091578993 0.1473750000 957688897 0 402718720 0.0392509513 -0.0130443843 0.1245465130 95 3.7600000000 0.0009131114 0.0009488225 0.0012045242 0.0091469785 0.1477070000 957690905 0 402718720 0.0400855280 -0.0132206623 0.1276173145 96 3.8000000000 0.0008639543 0.0009479385 0.0012045242 0.0091675006 0.1484510000 957692913 0 402718720 0.0409737714 -0.0131052844 0.1308618039 97 3.8400000000 0.0008203519 0.0009466231 0.0012045242 0.0092848212 0.1589300000 957694921 0 402718720 0.0414936654 -0.0116828065 0.1344786137 98 3.8800000000 0.0008855969 0.0009460004 0.0012045242 0.0094097651 0.1493980000 957696929 0 402718720 0.0421104021 -0.0117287198 0.1376439184 99 3.9200000000 0.0008633889 0.0009451660 0.0012045242 0.0095395537 0.1496660000 957698937 0 402718720 0.0431264564 -0.0117242411 0.1408687532 100 3.9600000000 0.0008024404 0.0009437387 0.0012045242 0.0096524242 0.1505620000 957700945 0 402718720 0.0433130711 -0.0101669757 0.1444670260 101 4.0000000000 0.0008521780 0.0009428322 0.0012045242 0.0097023416 0.1508600000 957702953 0 402718720 0.0438434295 -0.0095383106 0.1478528231 102 4.0400000000 0.0008913264 0.0009423272 0.0012045242 0.0097157421 0.1509480000 957704961 0 402718720 0.0445505828 -0.0098132957 0.1508177519 103 4.0800000000 0.0008119610 0.0009410615 0.0012045242 0.0097287286 0.1503970000 957706969 0 402718720 0.0448323339 -0.0086713033 0.1541998088 104 4.1200000000 0.0008712922 0.0009403907 0.0012045242 0.0097356410 0.1512310000 957708977 0 402718720 0.0456640907 -0.0085553126 0.1573372632 105 4.1600000000 0.0008552827 0.0009395801 0.0012045242 0.0097414240 0.1522880000 957710985 0 402718720 0.0461301021 -0.0084480429 0.1600829512 106 4.2000000000 0.0008133752 0.0009383895 0.0012045242 0.0097312664 0.1525530000 957712993 0 402718720 0.0462091230 -0.0077464515 0.1629073322 107 4.2400000000 0.0008861228 0.0009379010 0.0012045242 0.0097074964 0.1537770000 957715001 0 402718720 0.0468392670 -0.0083253002 0.1653666198 108 4.2800000000 0.0008010074 0.0009366335 0.0012045242 0.0096959041 0.1545000000 957717009 0 402718720 0.0469306298 -0.0074847736 0.1681135893 109 4.3200000000 0.0007952885 0.0009353367 0.0012045242 0.0096791529 0.1680500000 957719017 0 402718720 0.0470971577 -0.0065992596 0.1707954705 110 4.3600000000 0.0008103137 0.0009342002 0.0012045242 0.0096428702 0.1562340000 957721025 0 402718720 0.0474650264 -0.0062391008 0.1733498126 111 4.4000000000 0.0008053231 0.0009330391 0.0012045242 0.0096108539 0.1566970000 957723033 0 402718720 0.0479400158 -0.0060163820 0.1758709550 112 4.4400000000 0.0007844187 0.0009317122 0.0012045242 0.0095795950 0.1775390000 957725041 0 402718720 0.0483830534 -0.0058118124 0.1782708019 113 4.4800000000 0.0007825754 0.0009303924 0.0012045242 0.0095465949 0.1576280000 957727049 0 402718720 0.0480299592 -0.0050913510 0.1806861162 114 4.5200000000 0.0008541318 0.0009297234 0.0012045242 0.0095151138 0.1574230000 957729057 0 402718720 0.0483169593 -0.0051818681 0.1830920726 115 4.5600000000 0.0008569556 0.0009290906 0.0012045242 0.0094860029 0.1572530000 957731065 0 402718720 0.0486366227 -0.0052396343 0.1854231656 116 4.6000000000 0.0008574756 0.0009284733 0.0012045242 0.0094654254 0.1576000000 957733073 0 402718720 0.0484312512 -0.0045659728 0.1879842877 117 4.6400000000 0.0009389003 0.0009285624 0.0012045242 0.0094348633 0.1701550000 957735081 0 402718720 0.0485992357 -0.0047727013 0.1903997064 118 4.6800000000 0.0009633549 0.0009288572 0.0012045242 0.0094077743 0.1591410000 957737089 0 402718720 0.0485467911 -0.0045968825 0.1930416822 119 4.7200000000 0.0010758430 0.0009300924 0.0012045242 0.0093823162 0.1600650000 957739097 0 402718720 0.0489097908 -0.0044102962 0.1959357262 120 4.7600000000 0.0011541971 0.0009319600 0.0012045242 0.0093577376 0.1601020000 957741105 0 402718720 0.0489866696 -0.0046178787 0.1986728162 121 4.8000000000 0.0012522812 0.0009346072 0.0012522812 0.0093446223 0.1603220000 957743113 0 402718720 0.0490806289 -0.0044307173 0.2016452849 122 4.8400000000 0.0013665094 0.0009381474 0.0013665094 0.0093510918 0.1715910000 957745121 0 402718720 0.0490083173 -0.0043248204 0.2046703398 123 4.8800000000 0.0014743612 0.0009425069 0.0014743612 0.0093368534 0.1598350000 957747129 0 402718720 0.0489782095 -0.0041454346 0.2077509910 124 4.9200000000 0.0015605070 0.0009474908 0.0015605070 0.0093144233 0.1580860000 957749137 0 402718720 0.0489418581 -0.0038023326 0.2107781023 125 4.9600000000 0.0017478077 0.0009538933 0.0017478077 0.0092937999 0.1606150000 957751145 0 402718720 0.0490805916 -0.0033971921 0.2139902562 126 5.0000000000 0.0018884226 0.0009613102 0.0018884226 0.0092813419 0.1604950000 957753153 0 402718720 0.0492453612 -0.0033785936 0.2170802057 127 5.0400000000 0.0020232275 0.0009696717 0.0020232275 0.0092832462 0.1694190000 957755161 0 402718720 0.0496122241 -0.0032540443 0.2202659547 128 5.0800000000 0.0021290968 0.0009787298 0.0021290968 0.0093005578 0.1622820000 957757169 0 402718720 0.0499868579 -0.0027162354 0.2233976573 129 5.1200000000 0.0022729242 0.0009887623 0.0022729242 0.0092856011 0.1634250000 957759177 0 402718720 0.0504232235 -0.0026162569 0.2264430374 130 5.1600000000 0.0023429766 0.0009991793 0.0023429766 0.0092739831 0.1615350000 957786785 0 402718720 0.0509990752 -0.0032896197 0.2290730476 131 5.2000000000 0.0023943207 0.0010098292 0.0023943207 0.0092642172 0.1641460000 957788793 0 402718720 0.0515083335 -0.0031264217 0.2317939252 132 5.2400000000 0.0024827798 0.0010209879 0.0024827798 0.0092435300 0.1748520000 957790801 0 402718720 0.0517258570 -0.0026339483 0.2346579581 133 5.2800000000 0.0027044823 0.0010336458 0.0027044823 0.0092383513 0.1653850000 957792809 0 402718720 0.0522807091 -0.0030437752 0.2371213436 134 5.3200000000 0.0028347434 0.0010470868 0.0028347434 0.0092653645 0.1657310000 957794817 0 402718720 0.0527355187 -0.0024388118 0.2400345057 135 5.3600000000 0.0029439896 0.0010611380 0.0029439896 0.0092675519 0.1661350000 957796825 0 402718720 0.0532049574 -0.0026391237 0.2423023283 136 5.4000000000 0.0031373273 0.0010764041 0.0031373273 0.0092749455 0.1669950000 957798833 0 402718720 0.0537875220 -0.0033103738 0.2444494367 137 5.4400000000 0.0033064536 0.0010926818 0.0033064536 0.0092737290 0.1770060000 957800841 0 402718720 0.0543918498 -0.0036049082 0.2467863709 138 5.4800000000 0.0033256905 0.0011088630 0.0033256905 0.0092549064 0.1673110000 957802849 0 402718720 0.0548169240 -0.0035634786 0.2490531206 139 5.5200000000 0.0035005966 0.0011260697 0.0035005966 0.0092440596 0.1679030000 957804857 0 402718720 0.0550663322 -0.0037069633 0.2511986196 140 5.5600000000 0.0037740048 0.0011449836 0.0037740048 0.0092364162 0.1685940000 957806865 0 402718720 0.0551656187 -0.0040594172 0.2532838285 141 5.6000000000 0.0020992889 0.0011517517 0.0037740048 0.0092998659 0.1771180000 957808873 0 402718720 0.0565999411 -0.0046946486 0.2588236332 142 5.6400000000 0.0032925946 0.0011668280 0.0037740048 0.0092963623 0.1827080000 957810881 0 402718720 0.0554778986 -0.0051995092 0.2596767247 143 5.6800000000 0.0037863092 0.0011851461 0.0037863092 0.0092963991 0.2067800000 957812889 0 402718720 0.0549672171 -0.0055971425 0.2611626983 144 5.7200000000 0.0039787302 0.0012045460 0.0039787302 0.0092921650 0.1712910000 957814897 0 402718720 0.0543537848 -0.0056031444 0.2629384696 145 5.7600000000 0.0041234475 0.0012246763 0.0041234475 0.0092818058 0.1714800000 957816905 0 402718720 0.0536433868 -0.0055859853 0.2646006048 146 5.8000000000 0.0043871785 0.0012463373 0.0043871785 0.0092818197 0.1717820000 957818913 0 402718720 0.0528700314 -0.0053579197 0.2662891746 147 5.8400000000 0.0046288730 0.0012693477 0.0046288730 0.0092734391 0.1868720000 957820921 0 402718720 0.0520664677 -0.0060689272 0.2676739395 148 5.8800000000 0.0046790070 0.0012923860 0.0046790070 0.0092555542 0.1723280000 957822929 0 402718720 0.0511642732 -0.0068504899 0.2690010071 149 5.9200000000 0.0048499634 0.0013162623 0.0048499634 0.0092384138 0.1715410000 957824937 0 402718720 0.0501189008 -0.0070583429 0.2705664337 150 5.9600000000 0.0051046018 0.0013415179 0.0051046018 0.0092218007 0.1708740000 957826945 0 402718720 0.0490582474 -0.0073207295 0.2723284364 151 6.0000000000 0.0051809428 0.0013669446 0.0051809428 0.0092034278 0.1720290000 957828953 0 402718720 0.0478884913 -0.0075451341 0.2740009129 152 6.0400000000 0.0053764074 0.0013933226 0.0053764074 0.0091882225 0.1719790000 957830961 0 402718720 0.0466905832 -0.0077634957 0.2757157683 153 6.0800000000 0.0057223956 0.0014216172 0.0057223956 0.0091749160 0.1721850000 957832969 0 402718720 0.0454271734 -0.0079695377 0.2776725888 154 6.1200000000 0.0058517330 0.0014503842 0.0058517330 0.0091594607 0.1724800000 957834977 0 402718720 0.0441258810 -0.0083591752 0.2795412242 155 6.1600000000 0.0058696992 0.0014788959 0.0058696992 0.0091407893 0.1740360000 957836985 0 402718720 0.0426967889 -0.0085879341 0.2815207839 156 6.2000000000 0.0066668815 0.0015121522 0.0066668815 0.0091468331 0.1736880000 957838993 0 402718720 0.0394823849 -0.0094127664 0.2849594653 157 6.2400000000 0.0064793685 0.0015437906 0.0066668815 0.0091305523 0.1878590000 957841001 0 402718720 0.0381779596 -0.0096490243 0.2873985171 158 6.2800000000 0.0065333094 0.0015753698 0.0066668815 0.0091139210 0.1739550000 957843009 0 402718720 0.0366988704 -0.0100550819 0.2893712223 159 6.3200000000 0.0066148047 0.0016070644 0.0066668815 0.0091009884 0.1719160000 957845017 0 402718720 0.0350330472 -0.0103037674 0.2912729084 160 6.3600000000 0.0067751766 0.0016393651 0.0067751766 0.0090853867 0.1735770000 957847025 0 402718720 0.0334212519 -0.0102701439 0.2932424545 161 6.4000000000 0.0069051883 0.0016720720 0.0069051883 0.0090769521 0.1731690000 957849033 0 402718720 0.0317082927 -0.0102912085 0.2950586975 162 6.4400000000 0.0069166934 0.0017044462 0.0069166934 0.0090850230 0.1741010000 957851041 0 402718720 0.0299363732 -0.0105553577 0.2968573868 163 6.4800000000 0.0069840150 0.0017368362 0.0069840150 0.0090774171 0.1739000000 957853049 0 402718720 0.0283701289 -0.0106928376 0.2984820902 164 6.5200000000 0.0072307992 0.0017703360 0.0072307992 0.0090630593 0.1742230000 957855057 0 402718720 0.0267557632 -0.0106916595 0.3001576364 165 6.5600000000 0.0074216691 0.0018045865 0.0074216691 0.0090553643 0.1744070000 957857065 0 402718720 0.0251109153 -0.0108815245 0.3019336164 166 6.6000000000 0.0074759624 0.0018387514 0.0074759624 0.0090407118 0.1746170000 957859073 0 402718720 0.0236510299 -0.0110679893 0.3036485612 167 6.6400000000 0.0076356553 0.0018734634 0.0076356553 0.0090293975 0.1862130000 957861081 0 402718720 0.0220988560 -0.0108512435 0.3056384921 168 6.6800000000 0.0076615042 0.0019079161 0.0076615042 0.0090143327 0.1752760000 957863089 0 402718720 0.0206263531 -0.0112897297 0.3071238101 169 6.7200000000 0.0076407753 0.0019418383 0.0076615042 0.0090001513 0.1754690000 957865097 0 402718720 0.0191786587 -0.0115719978 0.3085955083 170 6.7600000000 0.0078278501 0.0019764619 0.0078278501 0.0089851688 0.1753750000 957867105 0 402718720 0.0179987159 -0.0117431516 0.3101304471 171 6.8000000000 0.0079845749 0.0020115971 0.0079845749 0.0089722568 0.1756450000 957869113 0 402718720 0.0169235393 -0.0123768337 0.3114570677 172 6.8400000000 0.0079123862 0.0020459040 0.0079845749 0.0089560849 0.1969300000 957871121 0 402718720 0.0157772861 -0.0130338632 0.3125785291 173 6.8800000000 0.0078820139 0.0020796387 0.0079845749 0.0089417044 0.1780610000 957873129 0 402718720 0.0148318578 -0.0136464983 0.3135329783 174 6.9200000000 0.0080093211 0.0021137173 0.0080093211 0.0089505238 0.1779680000 957875137 0 402718720 0.0139687937 -0.0141770123 0.3144338131 175 6.9600000000 0.0081539592 0.0021482330 0.0081539592 0.0089666061 0.1755260000 957877145 0 402718720 0.0130690532 -0.0147346845 0.3153920770 176 7.0000000000 0.0080938302 0.0021820148 0.0081539592 0.0089760640 0.1777870000 957879153 0 402718720 0.0122411093 -0.0152574955 0.3160548210 177 7.0400000000 0.0082499888 0.0022162972 0.0082499888 0.0090007728 0.1894990000 957881161 0 402718720 0.0115948804 -0.0157998502 0.3167613745 178 7.0800000000 0.0083277868 0.0022506314 0.0083277868 0.0090067033 0.1757770000 957883169 0 402718720 0.0109906727 -0.0163116455 0.3173897862 179 7.1200000000 0.0083953571 0.0022849594 0.0083953571 0.0090135701 0.1754370000 957885177 0 402718720 0.0104877725 -0.0166739020 0.3180845380 180 7.1600000000 0.0084664579 0.0023193011 0.0084664579 0.0090401290 0.1749210000 957887185 0 402718720 0.0100370720 -0.0171335321 0.3188517094 181 7.2000000000 0.0084046824 0.0023529220 0.0084664579 0.0090596151 0.1723840000 957889193 0 402718720 0.0095144091 -0.0175384618 0.3193406761 182 7.2400000000 0.0084199021 0.0023862570 0.0084664579 0.0090778484 0.1907060000 957891201 0 402718720 0.0090272073 -0.0177806485 0.3197824955 183 7.2800000000 0.0084462753 0.0024193719 0.0084664579 0.0091024737 0.1745280000 957893209 0 402718720 0.0086123031 -0.0180257242 0.3199286759 184 7.3200000000 0.0080478778 0.0024499616 0.0084664579 0.0092517302 0.1792580000 957895217 0 402718720 0.0079347612 -0.0181871504 0.3210076392 185 7.3600000000 0.0080171758 0.0024800547 0.0084664579 0.0092734201 0.1782970000 957897225 0 402718720 0.0076427879 -0.0183953326 0.3212577403 186 7.4000000000 0.0083367927 0.0025115425 0.0084664579 0.0092698320 0.1729460000 957899233 0 402718720 0.0070617539 -0.0188667420 0.3218016922 187 7.4400000000 0.0080294507 0.0025410500 0.0084664579 0.0092590405 0.1889270000 957901241 0 402718720 0.0067650266 -0.0188435353 0.3234850168 188 7.4800000000 0.0082527045 0.0025714312 0.0084664579 0.0092450370 0.1705450000 957903249 0 402718720 0.0065014018 -0.0192398746 0.3245032132 189 7.5200000000 0.0082203494 0.0026013196 0.0084664579 0.0092406374 0.1699980000 957905257 0 402718720 0.0063225599 -0.0195249561 0.3258887529 190 7.5600000000 0.0082243029 0.0026309143 0.0084664579 0.0092522530 0.1694400000 957907265 0 402718720 0.0063137016 -0.0193867404 0.3274077475 191 7.6000000000 0.0080857472 0.0026594736 0.0084664579 0.0092436968 0.1745130000 957909273 0 402718720 0.0066168457 -0.0192777421 0.3290181756 192 7.6400000000 0.0080383010 0.0026874883 0.0084664579 0.0092322508 0.1854450000 957911281 0 402718720 0.0067036934 -0.0195105337 0.3308466077 193 7.6800000000 0.0079512997 0.0027147620 0.0084664579 0.0092218569 0.1685730000 957913289 0 402718720 0.0067013656 -0.0197932608 0.3324460983 194 7.7200000000 0.0079036849 0.0027415090 0.0084664579 0.0092097891 0.1692470000 957915297 0 402718720 0.0068596457 -0.0198941007 0.3338500857 195 7.7600000000 0.0078881849 0.0027679022 0.0084664579 0.0091961320 0.1701750000 957917305 0 402718720 0.0070794877 -0.0200613774 0.3350275755 196 7.8000000000 0.0078439908 0.0027938006 0.0084664579 0.0091826598 0.1707100000 957919313 0 402718720 0.0072462186 -0.0203251950 0.3360609412 197 7.8400000000 0.0079019461 0.0028197303 0.0084664579 0.0091695638 0.1836940000 957921321 0 402718720 0.0074666119 -0.0206813291 0.3369019330 198 7.8800000000 0.0078411736 0.0028450911 0.0084664579 0.0091557157 0.1725050000 957923329 0 402718720 0.0076915864 -0.0208077151 0.3379884362 199 7.9200000000 0.0076931561 0.0028694532 0.0084664579 0.0091454702 0.1733260000 957925337 0 402718720 0.0079629682 -0.0210229140 0.3386137784 200 7.9600000000 0.0077814832 0.0028940134 0.0084664579 0.0091398678 0.1720420000 957927345 0 402718720 0.0081963362 -0.0213991199 0.3393021226 201 8.0000000000 0.0078287954 0.0029185646 0.0084664579 0.0091277908 0.1947140000 957929353 0 402718720 0.0083362898 -0.0216186568 0.3400310874 202 8.0400000000 0.0078041316 0.0029427505 0.0084664579 0.0091186405 0.1979980000 957931361 0 402718720 0.0086063612 -0.0217353124 0.3404631019 203 8.0800000000 0.0076506967 0.0029659424 0.0084664579 0.0091129233 0.1784890000 957933369 0 402718720 0.0087134596 -0.0217648242 0.3410089314 204 8.1200000000 0.0077562253 0.0029894242 0.0084664579 0.0091113746 0.1782930000 957935377 0 402718720 0.0088351509 -0.0217496492 0.3414459229 205 8.1600000000 0.0077944612 0.0030128634 0.0084664579 0.0091125636 0.1766690000 957937385 0 402718720 0.0089107258 -0.0217193421 0.3419605792 206 8.1999999990 0.0078581069 0.0030363840 0.0084664579 0.0091138110 0.1783860000 957939393 0 402718720 0.0089236517 -0.0215499271 0.3420106471 207 8.2400000000 0.0078261802 0.0030595231 0.0084664579 0.0091434388 0.1910180000 957941401 0 402718720 0.0090054004 -0.0214517899 0.3424051404 208 8.2799999990 0.0076963124 0.0030818153 0.0084664579 0.0091788284 0.1806580000 957943409 0 402718720 0.0089971842 -0.0214237683 0.3426932395 209 8.3200000000 0.0077304691 0.0031040577 0.0084664579 0.0092061398 0.1803910000 957945417 0 402718720 0.0089723477 -0.0215987917 0.3426069617 210 8.3599999990 0.0077701737 0.0031262773 0.0084664579 0.0092041576 0.1805050000 957947425 0 402718720 0.0088637453 -0.0215655956 0.3427211940 211 8.4000000000 0.0077663870 0.0031482683 0.0084664579 0.0091956046 0.1817320000 957949433 0 402718720 0.0088519808 -0.0214241054 0.3426015675 212 8.4399999990 0.0077175363 0.0031698215 0.0084664579 0.0091934408 0.1906130000 957951441 0 402718720 0.0088437749 -0.0212785248 0.3421302438 213 8.4800000000 0.0077509792 0.0031913293 0.0084664579 0.0092038005 0.1804380000 957953449 0 402718720 0.0088641029 -0.0213040058 0.3417920470 214 8.5200000000 0.0077258949 0.0032125188 0.0084664579 0.0092007051 0.1787140000 957955457 0 402718720 0.0088843172 -0.0212634448 0.3413026929 215 8.5600000000 0.0077687362 0.0032337105 0.0084664579 0.0091917476 0.1776290000 957957465 0 402718720 0.0088039609 -0.0209726356 0.3408104479 216 8.6000000000 0.0077701327 0.0032547125 0.0084664579 0.0091968258 0.1775070000 957959473 0 402718720 0.0087227290 -0.0207281020 0.3402840495 217 8.6400000000 0.0077482378 0.0032754200 0.0084664579 0.0092066640 0.1775810000 957961481 0 402718720 0.0085702194 -0.0204665251 0.3398540020 218 8.6800000000 0.0077543594 0.0032959656 0.0084664579 0.0092216688 0.1898320000 957963489 0 402718720 0.0084612267 -0.0201887209 0.3393235207 219 8.7200000000 0.0077157337 0.0033161472 0.0084664579 0.0092352556 0.1769150000 957965497 0 402718720 0.0083428975 -0.0198396854 0.3389618695 220 8.7600000000 0.0077104783 0.0033361214 0.0084664579 0.0092454754 0.1764910000 957967505 0 402718720 0.0082274880 -0.0194661655 0.3383955956 221 8.8000000000 0.0077368645 0.0033560343 0.0084664579 0.0092601544 0.1738430000 957969513 0 402718720 0.0081417542 -0.0192543995 0.3379743695 222 8.8400000000 0.0076709818 0.0033754710 0.0084664579 0.0092649066 0.1774640000 957971521 0 402718720 0.0079696896 -0.0189107247 0.3374922276 223 8.8800000000 0.0077638323 0.0033951497 0.0084664579 0.0092759081 0.1763030000 957973529 0 402718720 0.0076805996 -0.0185577720 0.3366469741 224 8.9200000000 0.0077514490 0.0034145975 0.0084664579 0.0093032716 0.1751350000 957975537 0 402718720 0.0074017509 -0.0185214523 0.3360069692 225 8.9600000000 0.0076889712 0.0034335947 0.0084664579 0.0093237576 0.1749010000 957977545 0 402718720 0.0070590242 -0.0181786492 0.3352538347 226 9.0000000000 0.0076307240 0.0034521661 0.0084664579 0.0093536521 0.1721260000 957979553 0 402718720 0.0067421012 -0.0179068781 0.3345313966 227 9.0400000000 0.0076272204 0.0034705584 0.0084664579 0.0093721507 0.1743290000 957981561 0 402718720 0.0063411817 -0.0175773278 0.3337405026 228 9.0800000000 0.0076617333 0.0034889407 0.0084664579 0.0094010591 0.1746140000 957983569 0 402718720 0.0059863888 -0.0173285753 0.3329010308 229 9.1200000000 0.0076149823 0.0035069584 0.0084664579 0.0094318560 0.1740510000 957985577 0 402718720 0.0055932067 -0.0173263457 0.3319923282 230 9.1600000000 0.0076712449 0.0035250640 0.0084664579 0.0094417758 0.2058610000 957987585 0 402718720 0.0051584165 -0.0171047729 0.3308999836 231 9.2000000000 0.0076565491 0.0035429492 0.0084664579 0.0094586098 0.1758780000 957989593 0 402718720 0.0046158521 -0.0167803969 0.3298935592 232 9.2400000000 0.0077057993 0.0035608925 0.0084664579 0.0094793023 0.1886230000 957991601 0 402718720 0.0040898332 -0.0165051594 0.3288886547 233 9.2800000000 0.0076678130 0.0035785188 0.0084664579 0.0095076317 0.1769620000 957993609 0 402718720 0.0034813401 -0.0161178242 0.3282147348 234 9.3200000000 0.0075851553 0.0035956411 0.0084664579 0.0095371499 0.1744410000 957995617 0 402718720 0.0028916406 -0.0157802533 0.3270601928 235 9.3600000000 0.0076679895 0.0036129703 0.0084664579 0.0095490742 0.1882390000 957997625 0 402718720 0.0022702483 -0.0155429170 0.3260005713 236 9.4000000000 0.0076447385 0.0036300540 0.0084664579 0.0095528664 0.1852310000 957999633 0 402718720 0.0015638797 -0.0150905466 0.3249286711 237 9.4400000000 0.0077294814 0.0036473512 0.0084664579 0.0095626500 0.2257930000 958001641 0 402718720 0.0008005215 -0.0148756290 0.3238293827 238 9.4800000000 0.0081230029 0.0036661565 0.0084664579 0.0096418069 0.2246130000 958003649 0 402718720 -0.0009876317 -0.0141513711 0.3213693500 239 9.5200000000 0.0080703851 0.0036845842 0.0084664579 0.0096706238 0.2233990000 958005657 0 402718720 -0.0019478800 -0.0133402310 0.3202653527 240 9.5600000000 0.0082331495 0.0037035366 0.0084664579 0.0096989512 0.2227550000 958007665 0 402718720 -0.0030167049 -0.0124131134 0.3189323545 241 9.6000000000 0.0084601622 0.0037232736 0.0084664579 0.0097677274 0.2218700000 958009673 0 402718720 -0.0040758206 -0.0120473169 0.3178761899 242 9.6400000000 0.0086104255 0.0037434684 0.0086104255 0.0098399952 0.2209970000 958011681 0 402718720 -0.0051362230 -0.0116085690 0.3167694807 243 9.6800000000 0.0088192793 0.0037643566 0.0088192793 0.0098975437 0.2205120000 958013689 0 402718720 -0.0061518750 -0.0111445002 0.3151748478 244 9.7200000000 0.0091017289 0.0037862310 0.0091017289 0.0099515374 0.2194960000 958015697 0 402718720 -0.0072816545 -0.0106009673 0.3137945831 245 9.7600000000 0.0090787141 0.0038078330 0.0091017289 0.0099966227 0.1702260000 958017705 0 402718720 -0.0082892869 -0.0100929961 0.3124776185 246 9.8000000000 0.0093278857 0.0038302722 0.0093278857 0.0100243166 0.1679780000 958019713 0 402718720 -0.0094147474 -0.0095747737 0.3109175265 247 9.8400000000 0.0095118927 0.0038532747 0.0095118927 0.0100638377 0.1675620000 958021721 0 402718720 -0.0105289761 -0.0088081267 0.3095296323 248 9.8800000000 0.0095116384 0.0038760907 0.0095118927 0.0101143527 0.1687050000 958023729 0 402718720 -0.0116253430 -0.0078269364 0.3078410923 249 9.9200000000 0.0094199143 0.0038983551 0.0095118927 0.0101671574 0.1682790000 958025737 0 402718720 -0.0126018664 -0.0069744978 0.3062656224 250 9.9600000000 0.0090510463 0.0039189658 0.0095118927 0.0102108708 0.1677510000 958027745 0 402718720 -0.0136295194 -0.0056126346 0.3049777746 251 10.0000000000 0.0085230945 0.0039373090 0.0095118927 0.0102545118 0.1794780000 958029753 0 402718720 -0.0147484280 -0.0034798088 0.3036117554 252 10.0400000000 0.0081772944 0.0039541343 0.0095118927 0.0103149679 0.1765890000 958031761 0 402718720 -0.0157960709 -0.0019181888 0.3021436334 253 10.0800000000 0.0080709020 0.0039704061 0.0095118927 0.0103499624 0.1657610000 958033769 0 402718720 -0.0167074371 -0.0006750172 0.3004487157 254 10.1200000000 0.0081029041 0.0039866758 0.0095118927 0.0103862355 0.1647410000 958035777 0 402718720 -0.0176902898 0.0002988149 0.2988911271 255 10.1600000000 0.0081920028 0.0040031673 0.0095118927 0.0104368177 0.1645590000 958037785 0 402718720 -0.0187186524 0.0010701973 0.2973506451 256 10.2000000000 0.0082306163 0.0040196808 0.0095118927 0.0104803718 0.1624290000 958039793 0 402718720 -0.0196141507 0.0018548395 0.2958213091 257 10.2400000000 0.0083435895 0.0040365053 0.0095118927 0.0105235045 0.1866420000 958041801 0 402718720 -0.0206022412 0.0026553713 0.2943243086 258 10.2800000000 0.0083461944 0.0040532095 0.0095118927 0.0105363833 0.1650820000 958095009 0 402718720 -0.0214291122 0.0034971931 0.2927310467 259 10.3200000000 0.0083326995 0.0040697327 0.0095118927 0.0105384992 0.1654900000 958097017 0 402718720 -0.0223303009 0.0042981450 0.2911991775 260 10.3600000000 0.0085644731 0.0040870201 0.0095118927 0.0105574483 0.1669240000 958099025 0 402718720 -0.0233402103 0.0051699113 0.2896020114 261 10.4000000000 0.0085487096 0.0041041147 0.0095118927 0.0105906219 0.1645530000 958101033 0 402718720 -0.0242064167 0.0058276695 0.2881031334 262 10.4400000000 0.0085835056 0.0041212116 0.0095118927 0.0106024693 0.1775650000 958103041 0 402718720 -0.0250411052 0.0065086968 0.2864298224 263 10.4800000000 0.0086265299 0.0041383421 0.0095118927 0.0106022128 0.1630770000 958105049 0 402718720 -0.0259644501 0.0073219649 0.2848860323 264 10.5200000000 0.0086848885 0.0041555639 0.0095118927 0.0106063100 0.1642980000 958107057 0 402718720 -0.0269427672 0.0080334190 0.2832987905 265 10.5600000000 0.0087219793 0.0041727956 0.0095118927 0.0106311799 0.1619800000 958109065 0 402718720 -0.0278555304 0.0082334988 0.2819404900 266 10.6000000000 0.0086684003 0.0041896964 0.0095118927 0.0106301939 0.1645240000 958111073 0 402718720 -0.0285891872 0.0086587351 0.2803948224 267 10.6400000000 0.0087023834 0.0042065979 0.0095118927 0.0106137843 0.1871920000 958113081 0 402718720 -0.0294704288 0.0093508242 0.2786820233 268 10.6800000000 0.0087033510 0.0042233768 0.0095118927 0.0106045621 0.1636060000 958115089 0 402718720 -0.0303507373 0.0097424630 0.2769834697 269 10.7200000000 0.0087046204 0.0042400357 0.0095118927 0.0106029818 0.1705570000 958117097 0 402718720 -0.0312364940 0.0099825887 0.2756078243 270 10.7600000000 0.0087934081 0.0042569000 0.0095118927 0.0106078819 0.2114860000 958119105 0 402718720 -0.0320456363 0.0101869656 0.2738808095 271 10.8000000000 0.0088884719 0.0042739907 0.0095118927 0.0106022058 0.2112620000 958121113 0 402718720 -0.0327319130 0.0106598800 0.2717438936 272 10.8400000000 0.0089351749 0.0042911274 0.0095118927 0.0105885855 0.2109140000 958123121 0 402718720 -0.0336649120 0.0111839650 0.2700860798 273 10.8800000000 0.0090684406 0.0043086267 0.0095118927 0.0105938073 0.2100320000 958125129 0 402718720 -0.0345994756 0.0114544053 0.2682320178 274 10.9200000000 0.0090322401 0.0043258662 0.0095118927 0.0105929934 0.1725890000 958127137 0 402718720 -0.0354546793 0.0116702672 0.2666543722 275 10.9600000000 0.0090011191 0.0043428671 0.0095118927 0.0105795324 0.1612310000 958129145 0 402718720 -0.0359873101 0.0117670773 0.2646991313 276 11.0000000000 0.0090016201 0.0043597467 0.0095118927 0.0105645452 0.1623510000 958131153 0 402718720 -0.0367499478 0.0118580665 0.2629744709 277 11.0400000000 0.0090554375 0.0043766986 0.0095118927 0.0105555120 0.1708540000 958133161 0 402718720 -0.0376191549 0.0119265867 0.2614080012 278 11.0800000000 0.0091318944 0.0043938036 0.0095118927 0.0105483527 0.1602250000 958135169 0 402718720 -0.0383631885 0.0119512156 0.2596819103 279 11.1200000000 0.0090196999 0.0044103839 0.0095118927 0.0105336625 0.1592100000 958137177 0 402718720 -0.0390061438 0.0119635649 0.2581264675 280 11.1600000000 0.0091153877 0.0044271875 0.0095118927 0.0105157314 0.1589220000 958139185 0 402718720 -0.0397667699 0.0122657437 0.2564147115 281 11.2000000000 0.0092174765 0.0044442348 0.0095118927 0.0104995420 0.1585660000 958141193 0 402718720 -0.0405536816 0.0124743339 0.2547271848 282 11.2400000000 0.0092696492 0.0044613462 0.0095118927 0.0104832902 0.1579330000 958143201 0 402718720 -0.0414566807 0.0127247805 0.2531030178 283 11.2800000000 0.0093244007 0.0044785301 0.0095118927 0.0104658490 0.1588170000 958145209 0 402718720 -0.0423963256 0.0129938470 0.2515346706 284 11.3200000000 0.0093200300 0.0044955776 0.0095118927 0.0104477667 0.1583390000 958147217 0 402718720 -0.0432267748 0.0130989756 0.2501234710 285 11.3600000000 0.0093336422 0.0045125533 0.0095118927 0.0104297072 0.1577730000 958149225 0 402718720 -0.0442081839 0.0132703353 0.2483922839 286 11.4000000000 0.0092671597 0.0045291778 0.0095118927 0.0104117539 0.1585840000 958151233 0 402718720 -0.0451732390 0.0133959986 0.2465682030 287 11.4400000000 0.0093111303 0.0045458397 0.0095118927 0.0103938775 0.1765850000 958153241 0 402718720 -0.0461862944 0.0132642007 0.2448696792 288 11.4800000000 0.0093770809 0.0045626148 0.0095118927 0.0103762077 0.1578180000 958155249 0 402718720 -0.0472266860 0.0130656846 0.2428843826 289 11.5200000000 0.0093720704 0.0045792565 0.0095118927 0.0103590742 0.1572370000 958157257 0 402718720 -0.0488798097 0.0127902636 0.2415175587 290 11.5600000000 0.0094918944 0.0045961967 0.0095118927 0.0103415460 0.1550790000 958159265 0 402718720 -0.0502075031 0.0123972762 0.2395335734 291 11.6000000000 0.0095779728 0.0046133162 0.0095779728 0.0103280724 0.1673480000 958161273 0 402718720 -0.0517438725 0.0120625440 0.2377780229 292 11.6400000000 0.0094646560 0.0046299303 0.0095779728 0.0103106898 0.1537720000 958163281 0 402718720 -0.0532535613 0.0114891939 0.2362437248 293 11.6800000000 0.0093160747 0.0046459240 0.0095779728 0.0102997453 0.1522670000 958165289 0 402718720 -0.0548589230 0.0111730276 0.2346294522 294 11.7200000000 0.0094188647 0.0046621585 0.0095779728 0.0102826775 0.1535240000 958167297 0 402718720 -0.0567156002 0.0108497329 0.2327357531 295 11.7600000000 0.0094785569 0.0046784853 0.0095779728 0.0102672543 0.1529380000 958169305 0 402718720 -0.0587736182 0.0106429914 0.2311779261 296 11.8000000000 0.0094807995 0.0046947093 0.0095779728 0.0102505352 0.1524950000 958171313 0 402718720 -0.0608546324 0.0104746502 0.2295817882 297 11.8400000000 0.0094498284 0.0047107198 0.0095779728 0.0102334985 0.1614490000 958173321 0 402718720 -0.0629589707 0.0103639131 0.2280701548 298 11.8800000000 0.0093406532 0.0047262565 0.0095779728 0.0102210039 0.1517750000 958175329 0 402718720 -0.0650134757 0.0103105661 0.2265002877 299 11.9200000000 0.0094303042 0.0047419891 0.0095779728 0.0102114425 0.1530460000 958177337 0 402718720 -0.0673656613 0.0103168385 0.2250406593 300 11.9600000000 0.0094540920 0.0047576961 0.0095779728 0.0101971131 0.1525170000 958179345 0 402718720 -0.0697310567 0.0100390976 0.2234982401 301 12.0000000000 0.0095577911 0.0047736433 0.0095779728 0.0101863995 0.1529730000 958181353 0 402718720 -0.0720963478 0.0100310044 0.2219265848 302 12.0400000000 0.0096820369 0.0047898962 0.0096820369 0.0101737961 0.1526220000 958183361 0 402718720 -0.0745822340 0.0101453476 0.2204407454 303 12.0800000000 0.0096694753 0.0048060004 0.0096820369 0.0101600508 0.1640220000 958185369 0 402718720 -0.0769761801 0.0101764547 0.2187738270 304 12.1200000000 0.0095512094 0.0048216097 0.0096820369 0.0101493239 0.1513210000 958187377 0 402718720 -0.0793681070 0.0101419259 0.2173449844 305 12.1600000000 0.0096327178 0.0048373838 0.0096820369 0.0101412035 0.1517530000 958189385 0 402718720 -0.0818644688 0.0103871711 0.2156989872 306 12.2000000000 0.0096924631 0.0048532501 0.0096924631 0.0101271131 0.1524510000 958191393 0 402718720 -0.0844393447 0.0105996281 0.2143084407 307 12.2400000000 0.0096999248 0.0048690373 0.0096999248 0.0101108199 0.1634480000 958193401 0 402718720 -0.0868952051 0.0106474496 0.2127526402 308 12.2800000000 0.0095355865 0.0048841884 0.0096999248 0.0100950653 0.1527760000 958195409 0 402718720 -0.0892565846 0.0103473058 0.2114614248 309 12.3200000000 0.0094924113 0.0048991018 0.0096999248 0.0100853475 0.1552900000 958197417 0 402718720 -0.0916326344 0.0100600552 0.2101158798 310 12.3600000000 0.0096435891 0.0049144066 0.0096999248 0.0100763281 0.1558300000 958199425 0 402718720 -0.0941096619 0.0099880407 0.2086589783 311 12.4000000000 0.0098238969 0.0049301927 0.0098238969 0.0100604845 0.1546640000 958201433 0 402718720 -0.0966025963 0.0095652910 0.2076886892 312 12.4400000000 0.0097285053 0.0049455719 0.0098238969 0.0100445741 0.1677060000 958203441 0 402718720 -0.0991353169 0.0093048206 0.2065700740 313 12.4800000000 0.0097887572 0.0049610454 0.0098238969 0.0100298384 0.1561440000 958205449 0 402718720 -0.1015077606 0.0089460723 0.2054173499 314 12.5200000000 0.0098528387 0.0049766243 0.0098528387 0.0100142556 0.1560500000 958207457 0 402718720 -0.1041445881 0.0084842341 0.2045315951 315 12.5600000000 0.0097905956 0.0049919068 0.0098528387 0.0099999420 0.1573430000 958209465 0 402718720 -0.1062161103 0.0074447957 0.2036594898 316 12.6000000000 0.0096459454 0.0050066347 0.0098528387 0.0099889356 0.1582140000 958211473 0 402718720 -0.1087322086 0.0069350875 0.2029207647 317 12.6400000000 0.0095112650 0.0050208449 0.0098528387 0.0099787022 0.1693930000 958213481 0 402718720 -0.1107433215 0.0061625596 0.2019595206 318 12.6800000000 0.0094849756 0.0050348831 0.0098528387 0.0099807485 0.1594680000 958215489 0 402718720 -0.1126937345 0.0054074717 0.2011736780 319 12.7200000000 0.0096715931 0.0050494182 0.0098528387 0.0099767222 0.1587990000 958217497 0 402718720 -0.1145756468 0.0048564663 0.1999172419 320 12.7600000000 0.0099854022 0.0050648432 0.0099854022 0.0099624295 0.1823430000 958219505 0 402718720 -0.1161836237 0.0040965150 0.1987352073 321 12.8000000000 0.0100410711 0.0050803454 0.0100410711 0.0099472242 0.1600940000 958221513 0 402718720 -0.1176673248 0.0032759339 0.1974308640 322 12.8400000000 0.0099474033 0.0050954605 0.0100410711 0.0099346814 0.1721330000 958223521 0 402718720 -0.1190644354 0.0021356300 0.1963304281 323 12.8800000000 0.0101630883 0.0051111498 0.0101630883 0.0099283652 0.1591930000 958225529 0 402718720 -0.1206157804 0.0015522050 0.1949973255 324 12.9200000000 0.0102162734 0.0051269063 0.0102162734 0.0099168611 0.1607660000 958227537 0 402718720 -0.1222718060 0.0010310190 0.1934531778 325 12.9600000000 0.0101413522 0.0051423354 0.0102162734 0.0099042958 0.1612150000 958229545 0 402718720 -0.1238176972 0.0002988042 0.1920330822 326 13.0000000000 0.0100748874 0.0051574659 0.0102162734 0.0098947121 0.1610340000 958231553 0 402718720 -0.1251164973 -0.0004813521 0.1905044317 327 13.0400000000 0.0101647815 0.0051727788 0.0102162734 0.0098858022 0.1720790000 958233561 0 402718720 -0.1265234798 -0.0011488276 0.1888514012 328 13.0800000000 0.0102381734 0.0051882221 0.0102381734 0.0098738076 0.1593400000 958235569 0 402718720 -0.1277425289 -0.0018666082 0.1874105036 329 13.1200000000 0.0102118906 0.0052034916 0.0102381734 0.0098638726 0.1607910000 958237577 0 402718720 -0.1289619654 -0.0025234288 0.1856434792 330 13.1600000000 0.0102589652 0.0052188112 0.0102589652 0.0098535250 0.1613760000 958239585 0 402718720 -0.1302561313 -0.0033200805 0.1838827431 331 13.2000000000 0.0103541464 0.0052343258 0.0103541464 0.0098436803 0.1606900000 958241593 0 402718720 -0.1316279620 -0.0038967510 0.1818763018 332 13.2400000000 0.0103071649 0.0052496055 0.0103541464 0.0098348782 0.1608600000 958243601 0 402718720 -0.1329444051 -0.0045766989 0.1799511462 333 13.2800000000 0.0104552200 0.0052652379 0.0104552200 0.0098298535 0.1583440000 958245609 0 402718720 -0.1341003627 -0.0049131452 0.1774959564 334 13.3200000000 0.0104366969 0.0052807213 0.0104552200 0.0098199027 0.1606750000 958247617 0 402718720 -0.1354489177 -0.0051562535 0.1751808226 335 13.3600000000 0.0100604314 0.0052949891 0.0104552200 0.0098115037 0.1612170000 958249625 0 402718720 -0.1365852803 -0.0062444229 0.1732361764 336 13.4000000000 0.0102816094 0.0053098303 0.0104552200 0.0098368094 0.1613180000 958251633 0 402718720 -0.1375996023 -0.0065412740 0.1706332564 337 13.4400000000 0.0105383378 0.0053253451 0.0105383378 0.0098458539 0.1737290000 958253641 0 402718720 -0.1388450563 -0.0063630110 0.1672630459 338 13.4800000000 0.0104908319 0.0053406276 0.0105383378 0.0098433612 0.1624170000 958255649 0 402718720 -0.1401579380 -0.0065475274 0.1648564041 339 13.5200000000 0.0106600132 0.0053563190 0.0106600132 0.0098418526 0.1615530000 958257657 0 402718720 -0.1413973123 -0.0063429936 0.1621522903 340 13.5600000000 0.0108321207 0.0053724243 0.0108321207 0.0098295803 0.1626780000 958259665 0 402718720 -0.1426205486 -0.0060329684 0.1593809426 341 13.6000000000 0.0108338064 0.0053884401 0.0108338064 0.0098151283 0.1628220000 958261673 0 402718720 -0.1438626200 -0.0058560586 0.1568706036 342 13.6400000000 0.0106841931 0.0054039248 0.0108338064 0.0098007492 0.1618080000 958263681 0 402718720 -0.1450606138 -0.0059062187 0.1542189717 343 13.6800000000 0.0105144139 0.0054188242 0.0108338064 0.0097869511 0.1609030000 958265689 0 402718720 -0.1459875107 -0.0062993909 0.1516477615 344 13.7200000000 0.0105810817 0.0054338307 0.0108338064 0.0097807034 0.1610970000 958267697 0 402718720 -0.1469884366 -0.0063018692 0.1483698189 345 13.7600000000 0.0107265366 0.0054491719 0.0108338064 0.0097721456 0.1611610000 958269705 0 402718720 -0.1479947120 -0.0061410894 0.1452574879 346 13.8000000000 0.0106794620 0.0054642883 0.0108338064 0.0097584692 0.1587410000 958271713 0 402718720 -0.1489932686 -0.0059935325 0.1424613446 347 13.8400000000 0.0106389914 0.0054792010 0.0108338064 0.0097444005 0.1731830000 958273721 0 402718720 -0.1498874277 -0.0061555323 0.1395483911 348 13.8800000000 0.0105262399 0.0054937040 0.0108338064 0.0097308555 0.1609460000 958275729 0 402718720 -0.1508983672 -0.0063814404 0.1370116770 349 13.9200000000 0.0105575901 0.0055082137 0.0108338064 0.0097186784 0.1609600000 958277737 0 402718720 -0.1517517120 -0.0068052448 0.1341703087 350 13.9600000000 0.0105756540 0.0055226921 0.0108338064 0.0097084903 0.1626680000 958279745 0 402718720 -0.1524086148 -0.0071635223 0.1309624761 351 14.0000000000 0.0105277784 0.0055369516 0.0108338064 0.0096978942 0.1794750000 958281753 0 402718720 -0.1531441361 -0.0076403203 0.1281679869 352 14.0400000000 0.0105330609 0.0055511451 0.0108338064 0.0096911142 0.1734330000 958283761 0 402718720 -0.1538355500 -0.0079707876 0.1250888258 353 14.0800000000 0.0105240000 0.0055652325 0.0108338064 0.0096830093 0.1611280000 958285769 0 402718720 -0.1545947939 -0.0082220025 0.1222728118 354 14.1200000000 0.0106534632 0.0055796061 0.0108338064 0.0096716769 0.1613860000 958287777 0 402718720 -0.1554690152 -0.0081300717 0.1194033846 355 14.1600000000 0.0105660511 0.0055936524 0.0108338064 0.0096581563 0.1610750000 958289785 0 402718720 -0.1562200338 -0.0081380932 0.1169848666 356 14.2000000000 0.0105686625 0.0056076271 0.0108338064 0.0096446569 0.1626320000 958291793 0 402718720 -0.1569617242 -0.0082722418 0.1143015102 357 14.2400000000 0.0107194595 0.0056219460 0.0108338064 0.0096313430 0.1600040000 958293801 0 402718720 -0.1576792747 -0.0082193818 0.1116310656 358 14.2800000000 0.0106783835 0.0056360701 0.0108338064 0.0096218907 0.1597660000 958295809 0 402718720 -0.1585351378 -0.0080336556 0.1095020548 359 14.3200000000 0.0103870267 0.0056493040 0.0108338064 0.0096147188 0.1620340000 958297817 0 402718720 -0.1591467708 -0.0086088032 0.1069622114 360 14.3600000000 0.0103216553 0.0056622827 0.0108338064 0.0096024740 0.1620180000 958299825 0 402718720 -0.1593946815 -0.0094749359 0.1046418324 361 14.4000000000 0.0104185008 0.0056754578 0.0108338064 0.0095991076 0.1626590000 958301833 0 402718720 -0.1598750353 -0.0097251041 0.1023937166 362 14.4400000000 0.0104762930 0.0056887198 0.0108338064 0.0095881322 0.1621740000 958303841 0 402718720 -0.1603377908 -0.0098182904 0.0995923355 363 14.4800000000 0.0102353785 0.0057012451 0.0108338064 0.0095754870 0.1608550000 958305849 0 402718720 -0.1607764810 -0.0102061974 0.0975297168 364 14.5200000000 0.0101517905 0.0057134718 0.0108338064 0.0095672996 0.1585820000 958307857 0 402718720 -0.1609614342 -0.0104784984 0.0951257721 365 14.5600000000 0.0100387149 0.0057253218 0.0108338064 0.0095567581 0.1608800000 958309865 0 402718720 -0.1614319682 -0.0097914692 0.0926704034 366 14.6000000000 0.0098026069 0.0057364619 0.0108338064 0.0095470182 0.1604980000 958311873 0 402718720 -0.1618933529 -0.0093344105 0.0902074724 367 14.6400000000 0.0096983202 0.0057472572 0.0108338064 0.0095381676 0.1728680000 958313881 0 402718720 -0.1619987935 -0.0104371756 0.0878711119 368 14.6800000000 0.0098869558 0.0057585064 0.0108338064 0.0095287514 0.1627010000 958315889 0 402718720 -0.1621997207 -0.0112584876 0.0854461789 369 14.7200000000 0.0098172026 0.0057695055 0.0108338064 0.0095193962 0.1745460000 958317897 0 402718720 -0.1625427306 -0.0111779170 0.0832321197 370 14.7600000000 0.0096286424 0.0057799356 0.0108338064 0.0095074707 0.1613470000 958319905 0 402718720 -0.1630458385 -0.0105617857 0.0810084045 371 14.8000000000 0.0095575629 0.0057901179 0.0108338064 0.0094948987 0.1595170000 958321913 0 402718720 -0.1635764986 -0.0098579926 0.0782804489 372 14.8400000000 0.0094780186 0.0058000316 0.0108338064 0.0094883339 0.1592450000 958323921 0 402718720 -0.1639523953 -0.0097700171 0.0753509402 373 14.8800000000 0.0096279634 0.0058102942 0.0108338064 0.0094816789 0.1607750000 958325929 0 402718720 -0.1644152552 -0.0096016461 0.0725779906 374 14.9200000000 0.0098118614 0.0058209936 0.0108338064 0.0094866355 0.1594080000 958327937 0 402718720 -0.1651741415 -0.0095010540 0.0702516213 375 14.9600000000 0.0097771278 0.0058315433 0.0108338064 0.0095005556 0.1569530000 958329945 0 402718720 -0.1656908542 -0.0106184743 0.0683569312 376 15.0000000000 0.0098976884 0.0058423575 0.0108338064 0.0094910780 0.1596270000 958331953 0 402718720 -0.1662226319 -0.0113433478 0.0659912974 377 15.0400000000 0.0101995356 0.0058539150 0.0108338064 0.0094791825 0.1703770000 958333961 0 402718720 -0.1670358479 -0.0107427556 0.0636257306 378 15.0800000000 0.0100472560 0.0058650085 0.0108338064 0.0094890556 0.1593220000 958335969 0 402718720 -0.1674604863 -0.0109958630 0.0608569346 379 15.1200000000 0.0098777087 0.0058755961 0.0108338064 0.0094847653 0.1592860000 958337977 0 402718720 -0.1679994762 -0.0117570721 0.0584575012 380 15.1600000000 0.0100585623 0.0058866039 0.0108338064 0.0094723013 0.1589600000 958339985 0 402718720 -0.1686065942 -0.0118480297 0.0556092151 381 15.2000000000 0.0100132842 0.0058974351 0.0108338064 0.0094611693 0.1599610000 958341993 0 402718720 -0.1695411056 -0.0117803961 0.0534985177 382 15.2400000000 0.0100085568 0.0059081972 0.0108338064 0.0094500033 0.1836130000 958344001 0 402718720 -0.1699561775 -0.0121886162 0.0505625978 383 15.2800000000 0.0101333521 0.0059192289 0.0108338064 0.0094377444 0.1590570000 958346009 0 402718720 -0.1707198173 -0.0122217219 0.0483881235 384 15.3200000000 0.0101796119 0.0059303236 0.0108338064 0.0094263244 0.1706830000 958348017 0 402718720 -0.1718274802 -0.0120419562 0.0458142236 385 15.3600000000 0.0101905940 0.0059413893 0.0108338064 0.0094165278 0.1581340000 958350025 0 402718720 -0.1730465740 -0.0117203230 0.0435384624 386 15.4000000000 0.0101650581 0.0059523314 0.0108338064 0.0094059118 0.1570800000 958352033 0 402718720 -0.1738245636 -0.0115892440 0.0406509601 387 15.4400000000 0.0102363015 0.0059634011 0.0108338064 0.0093941961 0.1549550000 958354041 0 402718720 -0.1748032719 -0.0111763794 0.0380176492 388 15.4800000000 0.0102588348 0.0059744718 0.0108338064 0.0093861167 0.1555260000 958356049 0 402718720 -0.1764123887 -0.0104928026 0.0359407254 389 15.5200000000 0.0102185775 0.0059853821 0.0108338064 0.0093827548 0.1596990000 958358057 0 402718720 -0.1772483438 -0.0100496588 0.0331797376 390 15.5600000000 0.0101852510 0.0059961510 0.0108338064 0.0093765372 0.1618630000 958360065 0 402718720 -0.1787163168 -0.0096997730 0.0309449509 391 15.6000000000 0.0103695532 0.0060073362 0.0108338064 0.0093675697 0.1534280000 958362073 0 402718720 -0.1802706718 -0.0089308210 0.0286100656 392 15.6400000000 0.0103510823 0.0060184172 0.0108338064 0.0093681154 0.1656460000 958364081 0 402718720 -0.1815644652 -0.0083100842 0.0261061862 393 15.6800000000 0.0103847506 0.0060295274 0.0108338064 0.0093662807 0.1527050000 958366089 0 402718720 -0.1825384498 -0.0080730692 0.0237139203 394 15.7200000000 0.0104629174 0.0060407797 0.0108338064 0.0093618935 0.1652220000 958368097 0 402718720 -0.1838032454 -0.0076759439 0.0214220975 395 15.7600000000 0.0105919018 0.0060523015 0.0108338064 0.0093555590 0.1547530000 958370105 0 402718720 -0.1855551600 -0.0069810287 0.0188266207 396 15.8000000000 0.0106605459 0.0060639385 0.0108338064 0.0093514632 0.1553680000 958372113 0 402718720 -0.1864928752 -0.0061890720 0.0159743316 397 15.8400000000 0.0106118927 0.0060753943 0.0108338064 0.0093557230 0.1562460000 958374121 0 402718720 -0.1878742576 -0.0054534567 0.0138887456 398 15.8800000000 0.0103712715 0.0060861880 0.0108338064 0.0093650255 0.1547670000 958376129 0 402718720 -0.1890493482 -0.0056085782 0.0114041837 399 15.9200000000 0.0103727337 0.0060969312 0.0108338064 0.0093574792 0.1573380000 958378137 0 402718720 -0.1901757419 -0.0057221861 0.0091960514 400 15.9600000000 0.0106912684 0.0061084170 0.0108338064 0.0093470332 0.1705960000 958380145 0 402718720 -0.1913673878 -0.0049365768 0.0067127962 401 16.0000000000 0.0105824303 0.0061195742 0.0108338064 0.0093514337 0.1598160000 958382153 0 402718720 -0.1923461258 -0.0046372628 0.0044145240 402 16.0400000000 0.0106175886 0.0061307633 0.0108338064 0.0093479140 0.1619530000 958384161 0 402718720 -0.1935335994 -0.0043206783 0.0022372359 403 16.0800000000 0.0107699167 0.0061422748 0.0108338064 0.0093502477 0.1632090000 958386169 0 402718720 -0.1945728064 -0.0038064383 0.0000140980 404 16.1200000000 0.0108907949 0.0061540286 0.0108907949 0.0093669120 0.1638400000 958388177 0 402718720 -0.1949153394 -0.0034669172 -0.0025838034 405 16.1600000000 0.0106323203 0.0061650861 0.0108907949 0.0093872443 0.1642670000 958390185 0 402718720 -0.1959584057 -0.0034243434 -0.0043317708 406 16.2000000000 0.0109789213 0.0061769428 0.0109789213 0.0093830089 0.1664480000 958392193 0 402718720 -0.1965741366 -0.0024121050 -0.0067255259 407 16.2400000000 0.0108215213 0.0061883546 0.0109789213 0.0093985821 0.1780260000 958394201 0 402718720 -0.1975136250 -0.0020759702 -0.0084884316 408 16.2800000000 0.0108889872 0.0061998757 0.0109789213 0.0094038632 0.1668410000 958396209 0 402718720 -0.1979247481 -0.0020150386 -0.0105844447 409 16.3200000000 0.0109536601 0.0062114987 0.0109789213 0.0093971889 0.1678900000 958398217 0 402718720 -0.1985713392 -0.0020266538 -0.0126653267 410 16.3600000000 0.0113741439 0.0062240905 0.0113741439 0.0093880872 0.1794870000 958400225 0 402718720 -0.1989921033 -0.0013619493 -0.0148234684 411 16.3999999990 0.0113701550 0.0062366113 0.0113741439 0.0093949365 0.1665220000 958402233 0 402718720 -0.1995033771 -0.0008593717 -0.0169120207 412 16.4400000000 0.0113836052 0.0062491040 0.0113836052 0.0094005172 0.1663790000 958404241 0 402718720 -0.2000468224 -0.0002290968 -0.0191040374 413 16.4800000000 0.0113509074 0.0062614571 0.0113836052 0.0093989550 0.1851440000 958406249 0 402718720 -0.2007429600 -0.0000553918 -0.0211141743 414 16.5200000000 0.0114144236 0.0062739038 0.0114144236 0.0093913750 0.1681950000 958408257 0 402718720 -0.2010948807 0.0000621027 -0.0232917387 415 16.5599999990 0.0117785484 0.0062871680 0.0117785484 0.0093807997 0.1682180000 958410265 0 402718720 -0.2014171779 0.0005392836 -0.0258125663 416 16.6000000000 0.0117360502 0.0063002663 0.0117785484 0.0093741064 0.1688290000 958412273 0 402718720 -0.2018890381 0.0007341512 -0.0279875584 417 16.6400000000 0.0119351158 0.0063137791 0.0119351158 0.0093689169 0.1904920000 958414281 0 402718720 -0.2026129216 0.0011293067 -0.0303722527 418 16.6800000000 0.0120368004 0.0063274706 0.0120368004 0.0093686566 0.1667850000 958416289 0 402718720 -0.2036968321 0.0020066125 -0.0328309722 419 16.7199999990 0.0121313836 0.0063413224 0.0121313836 0.0093810826 0.1658880000 958418297 0 402718720 -0.2041573972 0.0031590497 -0.0355731212 420 16.7600000000 0.0115612708 0.0063537508 0.0121313836 0.0094023264 0.1636840000 958420305 0 402718720 -0.2043257952 0.0037297690 -0.0380961634 421 16.8000000000 0.0116394497 0.0063663060 0.0121313836 0.0093991475 0.1659010000 958422313 0 402718720 -0.2047005445 0.0042874799 -0.0408664122 422 16.8400000000 0.0117484219 0.0063790598 0.0121313836 0.0093943793 0.1740280000 958424321 0 402718720 -0.2043931484 0.0049272073 -0.0437185615 423 16.8799999990 0.0116947461 0.0063916264 0.0121313836 0.0093894529 0.2166660000 958426329 0 402718720 -0.2051090747 0.0055946624 -0.0462521426 424 16.9200000000 0.0118446182 0.0064044872 0.0121313836 0.0093844725 0.2170320000 958428337 0 402718720 -0.2054490000 0.0064591588 -0.0492720604 425 16.9600000000 0.0115928063 0.0064166951 0.0121313836 0.0094005404 0.2170130000 958430345 0 402718720 -0.2052067518 0.0070499359 -0.0523566231 426 17.0000000000 0.0113045145 0.0064281688 0.0121313836 0.0093991225 0.2169350000 958432353 0 402718720 -0.2050351202 0.0074738222 -0.0552566797 427 17.0400000000 0.0110913450 0.0064390896 0.0121313836 0.0093888610 0.2169870000 958434361 0 402718720 -0.2050353736 0.0073963506 -0.0580556616 428 17.0800000000 0.0113479393 0.0064505589 0.0121313836 0.0093780493 0.2173550000 958436369 0 402718720 -0.2036518753 0.0077611697 -0.0615059473 429 17.1200000000 0.0112561164 0.0064617606 0.0121313836 0.0093681518 0.2173570000 958438377 0 402718720 -0.2031140178 0.0080246879 -0.0646688566 430 17.1600000000 0.0113056842 0.0064730256 0.0121313836 0.0093575227 0.2173700000 958440385 0 402718720 -0.2034427822 0.0082422998 -0.0676124021 431 17.2000000000 0.0116152437 0.0064849565 0.0121313836 0.0093468022 0.1801380000 958442393 0 402718720 -0.2030616105 0.0087288432 -0.0711450279 432 17.2400000000 0.0116167823 0.0064968357 0.0121313836 0.0093411990 0.1665560000 958444401 0 402718720 -0.2030013353 0.0091668265 -0.0740989298 433 17.2800000000 0.0114882076 0.0065083631 0.0121313836 0.0093387995 0.1660650000 958446409 0 402718720 -0.2030844688 0.0096216733 -0.0773616508 434 17.3200000000 0.0115564549 0.0065199947 0.0121313836 0.0093318969 0.1662120000 958448417 0 402718720 -0.2028552443 0.0099252127 -0.0804688334 435 17.3600000000 0.0119850058 0.0065325579 0.0121313836 0.0093227617 0.1633600000 958450425 0 402718720 -0.2029777616 0.0108233914 -0.0839100853 436 17.4000000000 0.0116701787 0.0065443414 0.0121313836 0.0093305432 0.1660180000 958452433 0 402718720 -0.2022996694 0.0116117047 -0.0871119127 437 17.4400000000 0.0113536753 0.0065553468 0.0121313836 0.0093457564 0.1754310000 958454441 0 402718720 -0.2016447932 0.0122388676 -0.0899474174 438 17.4800000000 0.0112255150 0.0065660093 0.0121313836 0.0093428935 0.1671030000 958456449 0 402718720 -0.2005861551 0.0127103385 -0.0931748152 439 17.5200000000 0.0111739254 0.0065765057 0.0121313836 0.0093414002 0.1679370000 958458457 0 402718720 -0.1985320896 0.0132416701 -0.0963186026 440 17.5600000000 0.0110843703 0.0065867508 0.0121313836 0.0093458367 0.1677830000 958460465 0 402718720 -0.1977435052 0.0135928299 -0.0989649147 441 17.6000000000 0.0111089796 0.0065970053 0.0121313836 0.0093502436 0.1817170000 958462473 0 402718720 -0.1969922036 0.0141097819 -0.1015822813 442 17.6400000000 0.0109188333 0.0066067832 0.0121313836 0.0093609145 0.1673880000 958464481 0 402718720 -0.1967464834 0.0140171144 -0.1042953357 443 17.6800000000 0.0107646743 0.0066161689 0.0121313836 0.0093633779 0.1668550000 958466489 0 402718720 -0.1965254098 0.0136202732 -0.1066263169 444 17.7200000000 0.0109700728 0.0066259750 0.0121313836 0.0093565283 0.1665830000 958468497 0 402718720 -0.1963975430 0.0133473165 -0.1092894599 445 17.7600000000 0.0114045730 0.0066367135 0.0121313836 0.0093460363 0.1665600000 958470505 0 402718720 -0.1964358091 0.0136446198 -0.1121278480 446 17.8000000000 0.0113177560 0.0066472091 0.0121313836 0.0093362874 0.1664810000 958472513 0 402718720 -0.1963785142 0.0138800107 -0.1148086190 447 17.8400000000 0.0115185603 0.0066581069 0.0121313836 0.0093295312 0.1784290000 958474521 0 402718720 -0.1965728700 0.0142267933 -0.1173805967 448 17.8800000000 0.0112876054 0.0066684407 0.0121313836 0.0093204734 0.1684060000 958476529 0 402718720 -0.1961804479 0.0145150004 -0.1198238730 449 17.9200000000 0.0108032143 0.0066776495 0.0121313836 0.0093129168 0.1679130000 958478537 0 402718720 -0.1956546158 0.0140522271 -0.1220041960 450 17.9600000000 0.0115498593 0.0066884766 0.0121313836 0.0093026835 0.1640410000 958480545 0 402718720 -0.1957392991 0.0141670816 -0.1270777285 451 18.0000000000 0.0112228598 0.0066985307 0.0121313836 0.0093086821 0.1677320000 958482553 0 402718720 -0.1958685964 0.0143031450 -0.1296615005 452 18.0400000000 0.0107361572 0.0067074635 0.0121313836 0.0093149013 0.1653250000 958484561 0 402718720 -0.1961907893 0.0136505701 -0.1317407936 453 18.0800000000 0.0107930442 0.0067164824 0.0121313836 0.0093200229 0.1674850000 958486569 0 402718720 -0.1963571310 0.0129647925 -0.1340950727 454 18.1200000000 0.0112084504 0.0067263766 0.0121313836 0.0093155098 0.1666810000 958488577 0 402718720 -0.1967817545 0.0130323302 -0.1369646341 455 18.1600000000 0.0117359199 0.0067373866 0.0121313836 0.0093053820 0.1661410000 958490585 0 402718720 -0.1973702610 0.0136413360 -0.1400079727 456 18.2000000000 0.0117478417 0.0067483745 0.0121313836 0.0092959254 0.1651460000 958492593 0 402718720 -0.1977983713 0.0145976217 -0.1427088231 457 18.2400000000 0.0111112958 0.0067579213 0.0121313836 0.0092976838 0.1786880000 958494601 0 402718720 -0.1982423216 0.0150354216 -0.1450888962 458 18.2800000000 0.0113134841 0.0067678680 0.0121313836 0.0092948503 0.1671570000 958496609 0 402718720 -0.1989945620 0.0155613860 -0.1478994936 459 18.3200000000 0.0110447239 0.0067771858 0.0121313836 0.0093106856 0.1647810000 958498617 0 402718720 -0.1999635696 0.0160170011 -0.1504855454 460 18.3600000000 0.0108363833 0.0067860101 0.0121313836 0.0093161002 0.1646240000 958500625 0 402718720 -0.2002892196 0.0163962692 -0.1533741057 461 18.4000000000 0.0109018516 0.0067949382 0.0121313836 0.0093131569 0.1662220000 958502633 0 402718720 -0.2010794580 0.0166192800 -0.1562192440 462 18.4400000000 0.0104725389 0.0068028983 0.0121313836 0.0093340571 0.1656780000 958504641 0 402718720 -0.2014935613 0.0163064916 -0.1586715281 463 18.4800000000 0.0106057478 0.0068111118 0.0121313836 0.0093402855 0.1649320000 958506649 0 402718720 -0.2020126283 0.0163175818 -0.1616286337 464 18.5200000000 0.0103441020 0.0068187260 0.0121313836 0.0093407787 0.1649570000 958508657 0 402718720 -0.2028199732 0.0159620810 -0.1641119868 465 18.5600000000 0.0105860531 0.0068268278 0.0121313836 0.0093386026 0.1622060000 958510665 0 402718720 -0.2035658211 0.0161271412 -0.1672266722 466 18.6000000000 0.0110828346 0.0068359609 0.0121313836 0.0093297725 0.1644640000 958512673 0 402718720 -0.2049221843 0.0168609805 -0.1705954224 467 18.6400000000 0.0113215093 0.0068455659 0.0121313836 0.0093198186 0.1747440000 958514681 0 402718720 -0.2062282264 0.0177805368 -0.1737571508 468 18.6800000000 0.0114080710 0.0068553149 0.0121313836 0.0093105558 0.1660980000 958516689 0 402718720 -0.2073986679 0.0188466627 -0.1768930852 469 18.7200000000 0.0110567417 0.0068642731 0.0121313836 0.0093099966 0.1645190000 958518697 0 402718720 -0.2082740515 0.0196319595 -0.1797244847 470 18.7600000000 0.0117574362 0.0068746841 0.0121313836 0.0093008514 0.1661940000 958520705 0 402718720 -0.2097263783 0.0215632040 -0.1831941158 471 18.8000000000 0.0106180832 0.0068826319 0.0121313836 0.0093290410 0.1660130000 958522713 0 402718720 -0.2104659379 0.0225501116 -0.1857617348 472 18.8400000000 0.0102949673 0.0068898614 0.0121313836 0.0094176810 0.1838860000 958524721 0 402718720 -0.2113271803 0.0240727235 -0.1887342483 473 18.8800000000 0.0096993549 0.0068958011 0.0121313836 0.0094817053 0.1658670000 958526729 0 402718720 -0.2123180479 0.0244004186 -0.1916492283 474 18.9200000000 0.0100946454 0.0069025498 0.0121313836 0.0094826001 0.1654670000 958528737 0 402718720 -0.2140511125 0.0244398583 -0.1944800317 475 18.9600000000 0.0105731217 0.0069102773 0.0121313836 0.0094790614 0.1651370000 958530745 0 402718720 -0.2154413909 0.0252472237 -0.1973829418 476 19.0000000000 0.0105939368 0.0069180161 0.0121313836 0.0094954512 0.1654210000 958532753 0 402718720 -0.2165647149 0.0268622451 -0.2002348453 477 19.0400000000 0.0107647935 0.0069260806 0.0121313836 0.0094945056 0.1764420000 958534761 0 402718720 -0.2173536271 0.0286367312 -0.2032985836 478 19.0800000000 0.0111536551 0.0069349249 0.0121313836 0.0094861397 0.1636210000 958536769 0 402718720 -0.2184330374 0.0303769354 -0.2060041577 479 19.1200000000 0.0108255418 0.0069430472 0.0121313836 0.0094842532 0.1615510000 958538777 0 402718720 -0.2196726352 0.0316845588 -0.2084356397 480 19.1600000000 0.0106123295 0.0069506916 0.0121313836 0.0094860792 0.1646620000 958540785 0 402718720 -0.2206751704 0.0328626595 -0.2110401988 481 19.2000000000 0.0105173942 0.0069581068 0.0121313836 0.0094828837 0.1643980000 958542793 0 402718720 -0.2216155380 0.0337122567 -0.2134181261 482 19.2400000000 0.0105483504 0.0069655554 0.0121313836 0.0094805564 0.1641500000 958544801 0 402718720 -0.2227222770 0.0347137190 -0.2159905881 483 19.2800000000 0.0099015143 0.0069716340 0.0121313836 0.0094996696 0.1613610000 958546809 0 402718720 -0.2235241383 0.0347506963 -0.2179945707 484 19.3200000000 0.0101286583 0.0069781568 0.0121313836 0.0094978123 0.1623760000 958548817 0 402718720 -0.2241306603 0.0349074639 -0.2200649381 485 19.3600000000 0.0102353785 0.0069848727 0.0121313836 0.0094896980 0.1619130000 958550825 0 402718720 -0.2244558483 0.0350262411 -0.2218850553 486 19.4000000000 0.0104753533 0.0069920548 0.0121313836 0.0094812352 0.1615740000 958552833 0 402718720 -0.2247698009 0.0354247354 -0.2239572406 487 19.4400000000 0.0106478967 0.0069995616 0.0121313836 0.0094751122 0.1735730000 958554841 0 402718720 -0.2252921462 0.0362861976 -0.2260288149 488 19.4800000000 0.0105817607 0.0070069022 0.0121313836 0.0094713937 0.1747610000 958556849 0 402718720 -0.2256276160 0.0370896086 -0.2281775326 489 19.5200000000 0.0101152351 0.0070132587 0.0121313836 0.0094748818 0.1604800000 958558857 0 402718720 -0.2258693427 0.0372137278 -0.2299307287 490 19.5600000000 0.0103125004 0.0070199918 0.0121313836 0.0094700851 0.1601310000 958560865 0 402718720 -0.2260506153 0.0377266407 -0.2319801599 491 19.6000000000 0.0104555525 0.0070269889 0.0121313836 0.0094623346 0.1597110000 958562873 0 402718720 -0.2268741280 0.0378438458 -0.2339622974 492 19.6400000000 0.0107071726 0.0070344690 0.0121313836 0.0094539361 0.1593190000 958564881 0 402718720 -0.2267088741 0.0385148339 -0.2360360175 493 19.6800000000 0.0104068387 0.0070413095 0.0121313836 0.0094489479 0.1582750000 958566889 0 402718720 -0.2268733978 0.0389596820 -0.2378736138 494 19.7200000000 0.0106531121 0.0070486208 0.0121313836 0.0094415125 0.1575520000 958568897 0 402718720 -0.2265531719 0.0396982543 -0.2399078310 495 19.7600000000 0.0101559339 0.0070548982 0.0121313836 0.0094432813 0.1566730000 958570905 0 402718720 -0.2274294049 0.0397555456 -0.2418628335 496 19.8000000000 0.0102003571 0.0070612399 0.0121313836 0.0094440103 0.1557400000 958572913 0 402718720 -0.2287907153 0.0398017950 -0.2442652136 497 19.8400000000 0.0100934803 0.0070673409 0.0121313836 0.0094407574 0.1667880000 958574921 0 402718720 -0.2292966247 0.0393836275 -0.2462193370 498 19.8800000000 0.0097725000 0.0070727730 0.0121313836 0.0094354709 0.1565150000 958576929 0 402718720 -0.2284035832 0.0379909314 -0.2475491911 499 19.9200000000 0.0103048403 0.0070792501 0.0121313836 0.0094267274 0.1560180000 958578937 0 402718720 -0.2277821004 0.0375780985 -0.2498360276 500 19.9600000000 0.0106006851 0.0070862930 0.0121313836 0.0094176071 0.1556020000 958580945 0 402718720 -0.2270347029 0.0378408097 -0.2522455156 501 20.0000000000 0.0096358219 0.0070913818 0.0121313836 0.0094300747 0.1527470000 958582953 0 402718720 -0.2274731845 0.0367887020 -0.2543637753 502 20.0400000000 0.0096118841 0.0070964028 0.0121313836 0.0094477234 0.1530240000 958584961 0 402718720 -0.2283609211 0.0360054150 -0.2571524978 503 20.0800000000 0.0103144450 0.0071028005 0.0121313836 0.0094402673 0.1754760000 958586969 0 402718720 -0.2280849963 0.0364077017 -0.2601817250 504 20.1200000000 0.0105866725 0.0071097129 0.0121313836 0.0094315405 0.1535140000 958588977 0 402718720 -0.2276562601 0.0367550813 -0.2625885606 505 20.1600000000 0.0109632220 0.0071173436 0.0121313836 0.0094232114 0.1543000000 958590985 0 402718720 -0.2274087518 0.0375399403 -0.2654021680 506 20.2000000000 0.0110723982 0.0071251599 0.0121313836 0.0094149236 0.1521040000 958592993 0 402718720 -0.2276046872 0.0384165682 -0.2678296566 507 20.2400000000 0.0103464900 0.0071315136 0.0121313836 0.0094098444 0.1730710000 958595001 0 402718720 -0.2280787081 0.0380121954 -0.2701678574 508 20.2800000000 0.0104577458 0.0071380613 0.0121313836 0.0094034052 0.1539460000 958597009 0 402718720 -0.2279190421 0.0378619209 -0.2729676068 509 20.3200000000 0.0103119127 0.0071442968 0.0121313836 0.0094003494 0.1526900000 958599017 0 402718720 -0.2271063030 0.0375265405 -0.2750766873 510 20.3600000000 0.0106980335 0.0071512649 0.0121313836 0.0094029670 0.1504650000 958601025 0 402718720 -0.2267141044 0.0381226540 -0.2774857581 511 20.4000000000 0.0108057046 0.0071584165 0.0121313836 0.0093960971 0.1540680000 958603033 0 402718720 -0.2266439646 0.0385387167 -0.2801271379 512 20.4400000000 0.0108912336 0.0071657071 0.0121313836 0.0093878554 0.1524280000 958605041 0 402718720 -0.2263808548 0.0390743092 -0.2829787433 513 20.4800000000 0.0113045676 0.0071737751 0.0121313836 0.0093805327 0.1659770000 958607049 0 402718720 -0.2240254134 0.0401486307 -0.2860271931 514 20.5200000000 0.0108114947 0.0071808523 0.0121313836 0.0093750001 0.1531000000 958711457 0 402718720 -0.2230685800 0.0405753814 -0.2889271379 515 20.5600000000 0.0106161665 0.0071875229 0.0121313836 0.0093684895 0.1529660000 958713465 0 402718720 -0.2216823548 0.0402245559 -0.2916688919 516 20.6000000000 0.0106306877 0.0071941957 0.0121313836 0.0093652564 0.1529170000 958715473 0 402718720 -0.2193723470 0.0397307388 -0.2943701446 517 20.6400000000 0.0108913928 0.0072013469 0.0121313836 0.0093580583 0.1619380000 958717481 0 402718720 -0.2172613442 0.0397835635 -0.2968871295 518 20.6800000000 0.0110397078 0.0072087569 0.0121313836 0.0093528621 0.1529300000 958719489 0 402718720 -0.2153953910 0.0404047929 -0.2994481623 519 20.7200000000 0.0110247731 0.0072161095 0.0121313836 0.0093482258 0.1534140000 958721497 0 402718720 -0.2139723897 0.0410228074 -0.3020644486 520 20.7600000000 0.0105933463 0.0072226042 0.0121313836 0.0093432912 0.1530370000 958723505 0 402718720 -0.2130829543 0.0411049873 -0.3043380082 521 20.8000000000 0.0110809403 0.0072300098 0.0121313836 0.0093352725 0.1534900000 958725513 0 402718720 -0.2121643424 0.0417558476 -0.3066940308 522 20.8400000000 0.0115272952 0.0072382422 0.0121313836 0.0093273372 0.1538760000 958727521 0 402718720 -0.2115759254 0.0433341973 -0.3091796935 523 20.8800000000 0.0111762248 0.0072457718 0.0121313836 0.0093189316 0.1538580000 958729529 0 402718720 -0.2108752877 0.0441899858 -0.3113773465 524 20.9200000000 0.0110287732 0.0072529912 0.0121313836 0.0093113813 0.1542290000 958731537 0 402718720 -0.2104913294 0.0443524644 -0.3137609363 525 20.9600000000 0.0112012699 0.0072605118 0.0121313836 0.0093054872 0.1547370000 958733545 0 402718720 -0.2099706829 0.0443901755 -0.3161259592 526 21.0000000000 0.0114437258 0.0072684646 0.0121313836 0.0093011679 0.1550580000 958735553 0 402718720 -0.2094695121 0.0447269715 -0.3183936775 527 21.0400000000 0.0115389107 0.0072765680 0.0121313836 0.0092962043 0.1673730000 958737561 0 402718720 -0.2090007961 0.0448540822 -0.3203147054 528 21.0800000000 0.0118461195 0.0072852224 0.0121313836 0.0092974356 0.1557610000 958739569 0 402718720 -0.2081342638 0.0448219255 -0.3222422302 529 21.1200000000 0.0116885770 0.0072935463 0.0121313836 0.0092964366 0.1540410000 958741577 0 402718720 -0.2074188888 0.0440834276 -0.3240629435 530 21.1600000000 0.0117836092 0.0073020182 0.0121313836 0.0092975655 0.1563600000 958743585 0 402718720 -0.2075055093 0.0438612029 -0.3258952200 531 21.2000000000 0.0119734630 0.0073108156 0.0121313836 0.0093040138 0.1567570000 958745593 0 402718720 -0.2070009708 0.0439355969 -0.3278037608 532 21.2400000000 0.0117203575 0.0073191042 0.0121313836 0.0093147061 0.1569340000 958747601 0 402718720 -0.2062520683 0.0428042226 -0.3293745220 533 21.2800000000 0.0118482215 0.0073276016 0.0121313836 0.0093228106 0.1696120000 958749609 0 402718720 -0.2057436556 0.0422942154 -0.3309791088 534 21.3200000000 0.0116338087 0.0073356657 0.0121313836 0.0093169839 0.1576580000 958751617 0 402718720 -0.2051737309 0.0416404121 -0.3323282301 535 21.3600000000 0.0115529085 0.0073435484 0.0121313836 0.0093141807 0.1575970000 958753625 0 402718720 -0.2049582154 0.0407125913 -0.3336648941 536 21.4000000000 0.0119676497 0.0073521754 0.0121313836 0.0093127268 0.1838170000 958755633 0 402718720 -0.2047119439 0.0404341295 -0.3353182375 537 21.4400000000 0.0116250711 0.0073601324 0.0121313836 0.0093112563 0.1700340000 958757641 0 402718720 -0.2047798038 0.0397990532 -0.3364894986 538 21.4800000000 0.0120773958 0.0073689006 0.0121313836 0.0093217226 0.1587380000 958759649 0 402718720 -0.2042846382 0.0392004624 -0.3377909362 539 21.5200000000 0.0119752763 0.0073774467 0.0121313836 0.0093386939 0.1587660000 958761657 0 402718720 -0.2039577961 0.0382757969 -0.3390180171 540 21.5600000000 0.0120926527 0.0073861786 0.0121313836 0.0093463641 0.1610540000 958763665 0 402718720 -0.2037516683 0.0378537364 -0.3402632475 541 21.6000000000 0.0120748905 0.0073948453 0.0121313836 0.0093507524 0.1623130000 958765673 0 402718720 -0.2039633244 0.0375704952 -0.3415226042 542 21.6400000000 0.0117705790 0.0074029186 0.0121313836 0.0093515011 0.1607760000 958767681 0 402718720 -0.2040176392 0.0365033336 -0.3426318765 543 21.6800000000 0.0116982860 0.0074108291 0.0121313836 0.0093541890 0.1639020000 958769689 0 402718720 -0.2045707703 0.0355873667 -0.3437139094 544 21.7200000000 0.0115579246 0.0074184524 0.0121313836 0.0093511879 0.1648950000 958771697 0 402718720 -0.2050566226 0.0346412361 -0.3449020684 545 21.7600000000 0.0114958789 0.0074259339 0.0121313836 0.0093463587 0.1648940000 958773705 0 402718720 -0.2052859068 0.0333593898 -0.3459055126 546 21.8000000000 0.0116629079 0.0074336939 0.0121313836 0.0093522595 0.1660420000 958775713 0 402718720 -0.2055950165 0.0322511457 -0.3469035327 547 21.8400000000 0.0118349884 0.0074417402 0.0121313836 0.0093758411 0.1763580000 958777721 0 402718720 -0.2054495513 0.0306054428 -0.3479433358 548 21.8800000000 0.0118038142 0.0074497002 0.0121313836 0.0093895952 0.1674380000 958779729 0 402718720 -0.2057465464 0.0295645930 -0.3490442038 549 21.9200000000 0.0115624573 0.0074571915 0.0121313836 0.0094006720 0.1706670000 958781737 0 402718720 -0.2062392384 0.0263353232 -0.3499956429 550 21.9600000000 0.0117917452 0.0074650725 0.0121313836 0.0094093005 0.1703980000 958783745 0 402718720 -0.2069105506 0.0252467226 -0.3510525227 551 22.0000000000 0.0121062705 0.0074734958 0.0121313836 0.0094063862 0.1696340000 958785753 0 402718720 -0.2074637264 0.0250844937 -0.3522055745 552 22.0400000000 0.0117564294 0.0074812547 0.0121313836 0.0094035984 0.1838930000 958787761 0 402718720 -0.2081060559 0.0245320257 -0.3530213535 553 22.0800000000 0.0116522545 0.0074887972 0.0121313836 0.0094038933 0.1746250000 958789769 0 402718720 -0.2088763267 0.0226463620 -0.3538704515 554 22.1200000000 0.0119853970 0.0074969138 0.0121313836 0.0094116199 0.1756070000 958791777 0 402718720 -0.2093679756 0.0220797099 -0.3547640443 555 22.1600000000 0.0123744663 0.0075057022 0.0123744663 0.0094144144 0.1771420000 958793785 0 402718720 -0.2096578032 0.0229800753 -0.3558690250 556 22.2000000000 0.0121522937 0.0075140594 0.0123744663 0.0094081601 0.1794270000 958795793 0 402718720 -0.2097813934 0.0229331944 -0.3567546010 557 22.2400000000 0.0115014836 0.0075212181 0.0123744663 0.0094011505 0.1906890000 958797801 0 402718720 -0.2099128664 0.0220004991 -0.3573857248 558 22.2800000000 0.0115614971 0.0075284588 0.0123744663 0.0093997062 0.1790770000 958799809 0 402718720 -0.2097052187 0.0214966480 -0.3580182195 559 22.3200000000 0.0116775483 0.0075358811 0.0123744663 0.0094029280 0.1813230000 958801817 0 402718720 -0.2099201083 0.0209875200 -0.3588638902 560 22.3600000000 0.0117548294 0.0075434149 0.0123744663 0.0094004585 0.1815100000 958803825 0 402718720 -0.2102365941 0.0210388452 -0.3596111536 561 22.4000000000 0.0116398046 0.0075507169 0.0123744663 0.0093982584 0.1782480000 958805833 0 402718720 -0.2100379616 0.0205224473 -0.3603118956 562 22.4400000000 0.0115187941 0.0075577775 0.0123744663 0.0093951702 0.1812640000 958807841 0 402718720 -0.2104745209 0.0199907366 -0.3609220386 563 22.4800000000 0.0115914010 0.0075649420 0.0123744663 0.0093924923 0.1816970000 958809849 0 402718720 -0.2105372101 0.0194510631 -0.3616060615 564 22.5200000000 0.0115889953 0.0075720769 0.0123744663 0.0093927693 0.1823300000 958811857 0 402718720 -0.2106294781 0.0193420500 -0.3621286452 565 22.5600000000 0.0115551464 0.0075791266 0.0123744663 0.0093955976 0.1826870000 958813865 0 402718720 -0.2111385018 0.0184874628 -0.3627731204 566 22.6000000000 0.0115808295 0.0075861967 0.0123744663 0.0093953191 0.2072680000 958815873 0 402718720 -0.2110455185 0.0182037298 -0.3633033633 567 22.6400000000 0.0116190612 0.0075933093 0.0123744663 0.0093937675 0.2011820000 958817881 0 402718720 -0.2111439705 0.0177630056 -0.3640854955 568 22.6800000000 0.0115709659 0.0076003123 0.0123744663 0.0093932574 0.1861970000 958819889 0 402718720 -0.2115314007 0.0171638317 -0.3644124866 569 22.7200000000 0.0119450949 0.0076079481 0.0123744663 0.0093991376 0.1994200000 958821897 0 402718720 -0.2116831094 0.0164421983 -0.3650290370 570 22.7600000000 0.0119419154 0.0076155515 0.0123744663 0.0094021316 0.1876260000 958823905 0 402718720 -0.2120135128 0.0160751287 -0.3655466437 571 22.8000000000 0.0121309534 0.0076234594 0.0123744663 0.0094071956 0.1873850000 958825913 0 402718720 -0.2121175379 0.0148492549 -0.3662685752 572 22.8400000000 0.0123069705 0.0076316474 0.0123744663 0.0094174154 0.1877460000 958827921 0 402718720 -0.2120919824 0.0149497231 -0.3669537306 573 22.8800000000 0.0121635403 0.0076395564 0.0123744663 0.0094171721 0.1888990000 958829929 0 402718720 -0.2122233659 0.0146253416 -0.3676854968 574 22.9200000000 0.0120175350 0.0076471836 0.0123744663 0.0094194003 0.1901170000 958831937 0 402718720 -0.2119168490 0.0139463600 -0.3686723113 575 22.9600000000 0.0119080702 0.0076545938 0.0123744663 0.0094242632 0.1906290000 958833945 0 402718720 -0.2118295729 0.0134117128 -0.3694718778 576 23.0000000000 0.0119227692 0.0076620038 0.0123744663 0.0094319348 0.1912660000 958835953 0 402718720 -0.2119590789 0.0125345914 -0.3704295456 577 23.0400000000 0.0118055716 0.0076691851 0.0123744663 0.0094400061 0.2157560000 958837961 0 402718720 -0.2116486281 0.0116203008 -0.3712742031 578 23.0800000000 0.0116657298 0.0076760995 0.0123744663 0.0094490868 0.1935270000 958839969 0 402718720 -0.2115505785 0.0107015092 -0.3720347583 579 23.1200000000 0.0114615504 0.0076826374 0.0123744663 0.0094556201 0.1937550000 958841977 0 402718720 -0.2114926428 0.0100441920 -0.3728425205 580 23.1600000000 0.0113140196 0.0076888984 0.0123744663 0.0094626148 0.2058610000 958843985 0 402718720 -0.2116067857 0.0095630940 -0.3735375702 581 23.2000000000 0.0109602874 0.0076945290 0.0123744663 0.0094663045 0.1920520000 958845993 0 402718720 -0.2116837949 0.0089998608 -0.3740022182 582 23.2400000000 0.0108531583 0.0076999562 0.0123744663 0.0094682693 0.1913190000 958848001 0 402718720 -0.2110652924 0.0086702993 -0.3745835125 583 23.2800000000 0.0112343375 0.0077060186 0.0123744663 0.0094747131 0.2037200000 958850009 0 402718720 -0.2102653831 0.0083320411 -0.3752528131 584 23.3200000000 0.0108497608 0.0077114018 0.0123744663 0.0094762487 0.1909020000 958852017 0 402718720 -0.2104848325 0.0073967357 -0.3756575286 585 23.3600000000 0.0109752379 0.0077169810 0.0123744663 0.0094867698 0.1909510000 958854025 0 402718720 -0.2100275904 0.0067762327 -0.3759345412 586 23.4000000000 0.0113510238 0.0077231824 0.0123744663 0.0095022658 0.1903800000 958856033 0 402718720 -0.2096383423 0.0065828357 -0.3763515353 587 23.4400000000 0.0112104136 0.0077291232 0.0123744663 0.0095073766 0.1906040000 958858041 0 402718720 -0.2094579041 0.0062637595 -0.3766844273 588 23.4800000000 0.0111339083 0.0077349136 0.0123744663 0.0095132955 0.1903280000 958860049 0 402718720 -0.2089486420 0.0057563707 -0.3766118288 589 23.5200000000 0.0112149501 0.0077408220 0.0123744663 0.0095203151 0.1899200000 958862057 0 402718720 -0.2087529004 0.0055147759 -0.3768910468 590 23.5600000000 0.0111971041 0.0077466801 0.0123744663 0.0095250282 0.2024040000 958864065 0 402718720 -0.2086380422 0.0052791308 -0.3771542013 591 23.6000000000 0.0108359056 0.0077519072 0.0123744663 0.0095252079 0.1896510000 958866073 0 402718720 -0.2087057531 0.0042356532 -0.3771046400 592 23.6400000000 0.0110218748 0.0077574308 0.0123744663 0.0095357391 0.2025550000 958868081 0 402718720 -0.2087166756 0.0034040448 -0.3773284256 593 23.6800000000 0.0110480208 0.0077629799 0.0123744663 0.0095409326 0.2111290000 958870089 0 402718720 -0.2087295651 0.0030136895 -0.3774142265 594 23.7200000000 0.0109959543 0.0077684226 0.0123744663 0.0095396990 0.1910070000 958872097 0 402718720 -0.2086478472 0.0026921222 -0.3778088987 595 23.7600000000 0.0109198289 0.0077737191 0.0123744663 0.0095411882 0.1904700000 958874105 0 402718720 -0.2086345255 0.0018922152 -0.3778908253 596 23.8000000000 0.0110351769 0.0077791913 0.0123744663 0.0095453866 0.1905100000 958876113 0 402718720 -0.2090936452 0.0013207616 -0.3779708147 597 23.8400000000 0.0111143235 0.0077847778 0.0123744663 0.0095451179 0.2114790000 958878121 0 402718720 -0.2090527266 0.0010399091 -0.3779000342 598 23.8800000000 0.0110261953 0.0077901982 0.0123744663 0.0095424091 0.1901850000 958880129 0 402718720 -0.2090975940 0.0006151713 -0.3779545724 599 23.9200000000 0.0106865410 0.0077950335 0.0123744663 0.0095369181 0.1871070000 958882137 0 402718720 -0.2090300769 -0.0001969674 -0.3778307438 600 23.9600000000 0.0106435213 0.0077997810 0.0123744663 0.0095318518 0.1895110000 958884145 0 402718720 -0.2088097036 -0.0010948537 -0.3778806031 601 24.0000000000 0.0108208684 0.0078048078 0.0123744663 0.0095287517 0.2000700000 958886153 0 402718720 -0.2087772638 -0.0020490461 -0.3777642548 602 24.0400000000 0.0108620944 0.0078098863 0.0123744663 0.0095288354 0.2440660000 958888161 0 402718720 -0.2085897923 -0.0031573309 -0.3776171803 603 24.0800000000 0.0110936640 0.0078153321 0.0123744663 0.0095363603 0.2438240000 958890169 0 402718720 -0.2083713710 -0.0041527557 -0.3772924244 604 24.1200000000 0.0111110415 0.0078207885 0.0123744663 0.0095399500 0.2427060000 958892177 0 402718720 -0.2081604302 -0.0046571740 -0.3769280016 605 24.1600000000 0.0112213958 0.0078264094 0.0123744663 0.0095374987 0.2427770000 958894185 0 402718720 -0.2081957459 -0.0048377644 -0.3767083585 606 24.2000000000 0.0110102724 0.0078316633 0.0123744663 0.0095313114 0.2419520000 958896193 0 402718720 -0.2079899460 -0.0052062711 -0.3766153157 607 24.2400000000 0.0110194823 0.0078369150 0.0123744663 0.0095246888 0.2415000000 958898201 0 402718720 -0.2076228559 -0.0055991635 -0.3765247464 608 24.2800000000 0.0109755667 0.0078420773 0.0123744663 0.0095178439 0.2413590000 958900209 0 402718720 -0.2072014809 -0.0059850682 -0.3764192462 609 24.3200000000 0.0107661495 0.0078468787 0.0123744663 0.0095111445 0.2031450000 958902217 0 402718720 -0.2077935338 -0.0070219720 -0.3763097823 610 24.3600000000 0.0112683130 0.0078524876 0.0123744663 0.0095102630 0.1844960000 958904225 0 402718720 -0.2074253410 -0.0076752692 -0.3763716817 611 24.4000000000 0.0112363286 0.0078580258 0.0123744663 0.0095050393 0.2043990000 958906233 0 402718720 -0.2071222365 -0.0085989498 -0.3760976195 612 24.4400000000 0.0113892499 0.0078637958 0.0123744663 0.0095022370 0.2413370000 958908241 0 402718720 -0.2069363594 -0.0089457519 -0.3763492107 613 24.4800000000 0.0116905868 0.0078700385 0.0123744663 0.0094970855 0.2400730000 958910249 0 402718720 -0.2060374171 -0.0083295517 -0.3761777878 614 24.5200000000 0.0116302595 0.0078761627 0.0123744663 0.0094894583 0.2411250000 958912257 0 402718720 -0.2058202326 -0.0083415546 -0.3760269582 615 24.5600000000 0.0117656784 0.0078824871 0.0123744663 0.0094823410 0.1872530000 958914265 0 402718720 -0.2058993429 -0.0097901523 -0.3756938875 616 24.6000000000 0.0118015064 0.0078888491 0.0123744663 0.0094804429 0.1836160000 958916273 0 402718720 -0.2059863806 -0.0114775235 -0.3758063912 617 24.6400000000 0.0118720764 0.0078953049 0.0123744663 0.0094821739 0.2183700000 958918281 0 402718720 -0.2056188285 -0.0119588198 -0.3757973909 618 24.6800000000 0.0117321713 0.0079015135 0.0123744663 0.0094827122 0.1844770000 958920289 0 402718720 -0.2051828206 -0.0125401923 -0.3760615885 619 24.7200000000 0.0119766248 0.0079080968 0.0123744663 0.0094953212 0.1854320000 958922297 0 402718720 -0.2044446170 -0.0128214639 -0.3760606647 620 24.7600000000 0.0122719686 0.0079151353 0.0123744663 0.0095003116 0.1832080000 958924305 0 402718720 -0.2039272934 -0.0123483911 -0.3765435219 621 24.8000000000 0.0119059319 0.0079215617 0.0123744663 0.0094935558 0.1984970000 958926313 0 402718720 -0.2033635974 -0.0120892469 -0.3769346476 622 24.8400000000 0.0118131712 0.0079278183 0.0123744663 0.0094859443 0.1822730000 958928321 0 402718720 -0.2022234797 -0.0125592723 -0.3769055605 623 24.8800000000 0.0118626878 0.0079341344 0.0123744663 0.0094785520 0.1845930000 958930329 0 402718720 -0.2013323903 -0.0129967779 -0.3767962158 624 24.9200000000 0.0119187962 0.0079405200 0.0123744663 0.0094713813 0.1846140000 958932337 0 402718720 -0.2006518543 -0.0137797184 -0.3769072890 625 24.9600000000 0.0118285250 0.0079467408 0.0123744663 0.0094658432 0.1841520000 958934345 0 402718720 -0.1995322108 -0.0136546269 -0.3770714104 626 25.0000000000 0.0120484745 0.0079532931 0.0123744663 0.0094584665 0.1823800000 958936353 0 402718720 -0.1981392503 -0.0134886112 -0.3768003881 627 25.0400000000 0.0120940506 0.0079598972 0.0123744663 0.0094509923 0.1928970000 958938361 0 402718720 -0.1968675405 -0.0142654004 -0.3766340315 628 25.0800000000 0.0122766495 0.0079667710 0.0123744663 0.0094464885 0.1846500000 958940369 0 402718720 -0.1954178214 -0.0141379526 -0.3766200542 629 25.1200000000 0.0124851530 0.0079739545 0.0124851530 0.0094400174 0.1805650000 958942377 0 402718720 -0.1936455965 -0.0129321190 -0.3769410849 630 25.1600000000 0.0122016594 0.0079806651 0.0124851530 0.0094366477 0.1964330000 958944385 0 402718720 -0.1925282478 -0.0129021415 -0.3767324984 631 25.2000000000 0.0120206531 0.0079870676 0.0124851530 0.0094303666 0.1828130000 958946393 0 402718720 -0.1908418834 -0.0133959856 -0.3765020967 632 25.2400000000 0.0121687762 0.0079936842 0.0124851530 0.0094229296 0.1830790000 958948401 0 402718720 -0.1891636848 -0.0135359010 -0.3763350546 633 25.2800000000 0.0124597326 0.0080007396 0.0124851530 0.0094155321 0.1828320000 958950409 0 402718720 -0.1875265241 -0.0127129592 -0.3761858046 634 25.3200000000 0.0123258447 0.0080075615 0.0124851530 0.0094098808 0.1832950000 958952417 0 402718720 -0.1856416017 -0.0127193779 -0.3756388426 635 25.3600000000 0.0122942682 0.0080143123 0.0124851530 0.0094046026 0.1832840000 958954425 0 402718720 -0.1836036593 -0.0130439289 -0.3749248981 636 25.4000000000 0.0124970451 0.0080213606 0.0124970451 0.0093984012 0.1830590000 958956433 0 402718720 -0.1817003489 -0.0130168190 -0.3748665154 637 25.4400000000 0.0124570169 0.0080283239 0.0124970451 0.0093926196 0.1955440000 958958441 0 402718720 -0.1795241684 -0.0127958301 -0.3745614886 638 25.4800000000 0.0123291621 0.0080350651 0.0124970451 0.0093887198 0.1863930000 958960449 0 402718720 -0.1777844876 -0.0136560863 -0.3739541471 639 25.5200000000 0.0124888225 0.0080420349 0.0124970451 0.0093814372 0.1841870000 958962457 0 402718720 -0.1755005568 -0.0137935383 -0.3738780320 640 25.5600000000 0.0125647197 0.0080491016 0.0125647197 0.0093744990 0.1867340000 958964465 0 402718720 -0.1731238961 -0.0135266017 -0.3733583987 641 25.6000000000 0.0125518553 0.0080561262 0.0125647197 0.0093677365 0.1844970000 958966473 0 402718720 -0.1703843176 -0.0130925803 -0.3728597760 642 25.6400000000 0.0124951014 0.0080630405 0.0125647197 0.0093624288 0.1839990000 958968481 0 402718720 -0.1682127714 -0.0134674609 -0.3725113869 643 25.6800000000 0.0126472479 0.0080701699 0.0126472479 0.0093551592 0.1839120000 958970489 0 402718720 -0.1657166630 -0.0130329710 -0.3724062443 644 25.7200000000 0.0125621716 0.0080771451 0.0126472479 0.0093486625 0.1839370000 958972497 0 402718720 -0.1632694006 -0.0131905852 -0.3717401028 645 25.7600000000 0.0125136822 0.0080840234 0.0126472479 0.0093415015 0.2096420000 958974505 0 402718720 -0.1607259065 -0.0138073293 -0.3711023927 646 25.8000000000 0.0127226645 0.0080912040 0.0127226645 0.0093360764 0.1858460000 958976513 0 402718720 -0.1582050174 -0.0135754580 -0.3706490099 647 25.8400000000 0.0127269924 0.0080983690 0.0127269924 0.0093288565 0.2044830000 958978521 0 402718720 -0.1555479616 -0.0131447939 -0.3699313998 648 25.8800000000 0.0126175974 0.0081053432 0.0127269924 0.0093226064 0.1856810000 958980529 0 402718720 -0.1533455998 -0.0135868071 -0.3690509498 649 25.9200000000 0.0126252426 0.0081123076 0.0127269924 0.0093154242 0.1851550000 958982537 0 402718720 -0.1507654637 -0.0140028642 -0.3686286211 650 25.9600000000 0.0127391713 0.0081194258 0.0127391713 0.0093087528 0.1828960000 958984545 0 402718720 -0.1481616199 -0.0136844153 -0.3680991828 651 26.0000000000 0.0127778146 0.0081265816 0.0127778146 0.0093016082 0.1843960000 958986553 0 402718720 -0.1456545889 -0.0131859165 -0.3675593734 652 26.0400000000 0.0127181616 0.0081336239 0.0127778146 0.0092946436 0.1831560000 958988561 0 402718720 -0.1432448626 -0.0129577210 -0.3675789237 653 26.0800000000 0.0127067352 0.0081406271 0.0127778146 0.0092876292 0.1829560000 958990569 0 402718720 -0.1409950852 -0.0131507646 -0.3674186766 654 26.1200000000 0.0126315448 0.0081474939 0.0127778146 0.0092813161 0.1830210000 958992577 0 402718720 -0.1358458102 -0.0124867512 -0.3666181266 655 26.1600000000 0.0126142241 0.0081543134 0.0127778146 0.0092743854 0.1830050000 958994585 0 402718720 -0.1333042085 -0.0129662910 -0.3655742109 656 26.2000000000 0.0127525516 0.0081613229 0.0127778146 0.0092676417 0.1830270000 958996593 0 402718720 -0.1304455400 -0.0126919458 -0.3646564484 657 26.2400000000 0.0127497036 0.0081683067 0.0127778146 0.0092606217 0.1827630000 958998601 0 402718720 -0.1277507544 -0.0127644772 -0.3635630608 658 26.2800000000 0.0127952676 0.0081753386 0.0127952676 0.0092536875 0.1848580000 959000609 0 402718720 -0.1250967234 -0.0129728336 -0.3627641797 659 26.3200000000 0.0129668340 0.0081826094 0.0129668340 0.0092475625 0.1836730000 959002617 0 402718720 -0.1224699169 -0.0126778949 -0.3624888957 660 26.3600000000 0.0128150284 0.0081896282 0.0129668340 0.0092405454 0.1825670000 959004625 0 402718720 -0.1199431270 -0.0129591757 -0.3617867231 661 26.4000000000 0.0128031624 0.0081966079 0.0129668340 0.0092340438 0.1824760000 959006633 0 402718720 -0.1171072274 -0.0132795228 -0.3607178926 662 26.4400000000 0.0128805134 0.0082036833 0.0129668340 0.0092284940 0.1823940000 959008641 0 402718720 -0.1143524200 -0.0131900301 -0.3599939942 663 26.4800000000 0.0127170002 0.0082104907 0.0129668340 0.0092215349 0.1824780000 959010649 0 402718720 -0.1118553802 -0.0135863740 -0.3594453633 664 26.5200000000 0.0126010487 0.0082171030 0.0129668340 0.0092149516 0.1819450000 959012657 0 402718720 -0.1095126495 -0.0146119846 -0.3587575555 665 26.5600000000 0.0125760436 0.0082236578 0.0129668340 0.0092103050 0.1793010000 959014665 0 402718720 -0.1073411405 -0.0161818583 -0.3584206700 666 26.6000000000 0.0127197243 0.0082304086 0.0129668340 0.0092102629 0.1815110000 959016673 0 402718720 -0.1048213169 -0.0169527568 -0.3580300808 667 26.6400000000 0.0127422651 0.0082371730 0.0129668340 0.0092086820 0.1810340000 959018681 0 402718720 -0.1023909301 -0.0176529307 -0.3577911258 668 26.6800000000 0.0126947844 0.0082438461 0.0129668340 0.0092047236 0.1838780000 959020689 0 402718720 -0.0999914631 -0.0182451978 -0.3573756218 669 26.7200000000 0.0126107521 0.0082503736 0.0129668340 0.0091999255 0.1842180000 959022697 0 402718720 -0.0977057144 -0.0192412119 -0.3573246598 670 26.7600000000 0.0126603693 0.0082569557 0.0129668340 0.0091994479 0.1846470000 959024705 0 402718720 -0.0953617170 -0.0196996666 -0.3575426042 671 26.8000000000 0.0127176251 0.0082636035 0.0129668340 0.0091961120 0.1953970000 959026713 0 402718720 -0.0928223580 -0.0194811299 -0.3580105901 672 26.8400000000 0.0125766695 0.0082700217 0.0129668340 0.0091896273 0.1827720000 959028721 0 402718720 -0.0905429125 -0.0206313562 -0.3581938148 673 26.8800000000 0.0126622841 0.0082765481 0.0129668340 0.0091916573 0.2014990000 959030729 0 402718720 -0.0880613551 -0.0215296727 -0.3584209085 674 26.9200000000 0.0128919343 0.0082833959 0.0129668340 0.0091988200 0.1828890000 959032737 0 402718720 -0.0853165463 -0.0210909136 -0.3587564826 675 26.9600000000 0.0128473528 0.0082901573 0.0129668340 0.0091944213 0.1802920000 959034745 0 402718720 -0.0826925859 -0.0210149642 -0.3596118093 676 27.0000000000 0.0126707777 0.0082966375 0.0129668340 0.0091882172 0.1832710000 959036753 0 402718720 -0.0802527666 -0.0221625473 -0.3598060012 677 27.0400000000 0.0127599332 0.0083032303 0.0129668340 0.0091850076 0.2051470000 959038761 0 402718720 -0.0775372162 -0.0223281290 -0.3608496189 678 27.0800000000 0.0127470726 0.0083097846 0.0129668340 0.0091804521 0.1854920000 959040769 0 402718720 -0.0748640522 -0.0226310156 -0.3615185022 679 27.1200000000 0.0127721941 0.0083163566 0.0129668340 0.0091775080 0.1849210000 959042777 0 402718720 -0.0723987594 -0.0230972972 -0.3623862267 680 27.1600000000 0.0128944591 0.0083230891 0.0129668340 0.0091761520 0.1850520000 959044785 0 402718720 -0.0695986599 -0.0228457507 -0.3636337519 681 27.2000000000 0.0128461858 0.0083297310 0.0129668340 0.0091698341 0.1832890000 959046793 0 402718720 -0.0669140816 -0.0228806939 -0.3646901250 682 27.2400000000 0.0128394002 0.0083363434 0.0129668340 0.0091637186 0.1826150000 959048801 0 402718720 -0.0642803088 -0.0231490992 -0.3660910726 683 27.2800000000 0.0128563493 0.0083429613 0.0129668340 0.0091586418 0.1823750000 959050809 0 402718720 -0.0614817701 -0.0232134331 -0.3674515486 684 27.3200000000 0.0128304288 0.0083495219 0.0129668340 0.0091520949 0.1850400000 959052817 0 402718720 -0.0587254465 -0.0233490970 -0.3692200184 685 27.3600000000 0.0125933308 0.0083557172 0.0129668340 0.0091454571 0.1846280000 959054825 0 402718720 -0.0561964139 -0.0249833744 -0.3705666065 686 27.4000000000 0.0126468269 0.0083619725 0.0129668340 0.0091446544 0.1960430000 959056833 0 402718720 -0.0536151677 -0.0259546377 -0.3723651767 687 27.4400000000 0.0127091780 0.0083683003 0.0129668340 0.0091466142 0.1846760000 959058841 0 402718720 -0.0506701358 -0.0259590019 -0.3744813204 688 27.4800000000 0.0127091371 0.0083746097 0.0129668340 0.0091473269 0.1847690000 959060849 0 402718720 -0.0476571880 -0.0260248575 -0.3765573204 689 27.5200000000 0.0126513382 0.0083808168 0.0129668340 0.0091481507 0.1849850000 959062857 0 402718720 -0.0448975675 -0.0263400096 -0.3786647022 690 27.5600000000 0.0121785440 0.0083863208 0.0129668340 0.0091542655 0.1895430000 959064865 0 402718720 -0.0418253765 -0.0249425787 -0.3816309869 691 27.6000000000 0.0124807721 0.0083922462 0.0129668340 0.0091476893 0.1796720000 959066873 0 402718720 -0.0383911058 -0.0244090762 -0.3834851384 692 27.6400000000 0.0123444172 0.0083979574 0.0129668340 0.0091444944 0.1928210000 959068881 0 402718720 -0.0352849215 -0.0241405107 -0.3858358264 693 27.6800000000 0.0123071112 0.0084035983 0.0129668340 0.0091408187 0.1815500000 959070889 0 402718720 -0.0323717967 -0.0248788297 -0.3878751993 694 27.7200000000 0.0123261400 0.0084092504 0.0129668340 0.0091342220 0.1803260000 959072897 0 402718720 -0.0293949060 -0.0252185706 -0.3901723921 695 27.7600000000 0.0122967307 0.0084148439 0.0129668340 0.0091278756 0.1811830000 959074905 0 402718720 -0.0264023840 -0.0257100463 -0.3920905590 696 27.8000000000 0.0122823203 0.0084204006 0.0129668340 0.0091233962 0.1808630000 959076913 0 402718720 -0.0235376265 -0.0260820072 -0.3937114179 697 27.8400000000 0.0119468886 0.0084254601 0.0129668340 0.0091216738 0.1953520000 959078921 0 402718720 -0.0180382729 -0.0247281678 -0.3992289901 698 27.8800000000 0.0121731805 0.0084308294 0.0129668340 0.0091152173 0.1807320000 959080929 0 402718720 -0.0154227661 -0.0261527505 -0.4004163444 699 27.9200000000 0.0118728578 0.0084357536 0.0129668340 0.0091348802 0.1870870000 959082937 0 402718720 -0.0110421628 -0.0260124803 -0.4050231576 700 27.9600000000 0.0121498248 0.0084410594 0.0129668340 0.0091291183 0.1828800000 959084945 0 402718720 -0.0087056309 -0.0270558987 -0.4063766897 701 28.0000000000 0.0121743558 0.0084463851 0.0129668340 0.0091258162 0.1962880000 959086953 0 402718720 -0.0065368977 -0.0281083696 -0.4076186121 702 28.0400000000 0.0122442823 0.0084517952 0.0129668340 0.0091308906 0.1942940000 959088961 0 402718720 -0.0045127780 -0.0291024502 -0.4089748561 703 28.0800000000 0.0124457097 0.0084574764 0.0129668340 0.0091491968 0.1817670000 959090969 0 402718720 -0.0023504198 -0.0291239023 -0.4109360576 704 28.1200000000 0.0124548562 0.0084631545 0.0129668340 0.0091557048 0.1814890000 959092977 0 402718720 -0.0000404205 -0.0290747713 -0.4126406014 705 28.1600000000 0.0123278191 0.0084686363 0.0129668340 0.0091560118 0.1816160000 959094985 0 402718720 0.0018752279 -0.0297983550 -0.4140427709 706 28.2000000000 0.0123942383 0.0084741966 0.0129668340 0.0091619835 0.1817510000 959096993 0 402718720 0.0039599915 -0.0303140897 -0.4154742360 707 28.2400000000 0.0125027820 0.0084798948 0.0129668340 0.0091667106 0.1795670000 959099001 0 402718720 0.0063782530 -0.0296646971 -0.4170333743 708 28.2800000000 0.0123761212 0.0084853979 0.0129668340 0.0091604195 0.1817480000 959101009 0 402718720 0.0088900449 -0.0292799622 -0.4186011553 709 28.3200000000 0.0121786408 0.0084906070 0.0129668340 0.0091540241 0.1818940000 959103017 0 402718720 0.0110415258 -0.0300578959 -0.4194889665 710 28.3600000000 0.0123539194 0.0084960483 0.0129668340 0.0091516795 0.1839820000 959105025 0 402718720 0.0133444779 -0.0306928344 -0.4203945398 711 28.4000000000 0.0125443647 0.0085017421 0.0129668340 0.0091494978 0.1963780000 959107033 0 402718720 0.0159052256 -0.0303180479 -0.4216837287 712 28.4400000000 0.0123328157 0.0085071229 0.0129668340 0.0091430679 0.1835410000 959109041 0 402718720 0.0181885473 -0.0308936629 -0.4223040640 713 28.4800000000 0.0122887287 0.0085124267 0.0129668340 0.0091376927 0.1789200000 959111049 0 402718720 0.0204553828 -0.0316604078 -0.4227970839 714 28.5200000000 0.0125088701 0.0085180239 0.0129668340 0.0091358288 0.1962050000 959113057 0 402718720 0.0230531264 -0.0314944163 -0.4236262441 715 28.5600000000 0.0126308706 0.0085237761 0.0129668340 0.0091303655 0.2176810000 959115065 0 402718720 0.0259572156 -0.0306579378 -0.4244235456 716 28.6000000000 0.0125452457 0.0085293927 0.0129668340 0.0091252870 0.1812260000 959117073 0 402718720 0.0287512355 -0.0300989393 -0.4248467088 717 28.6400000000 0.0124127762 0.0085348089 0.0129668340 0.0091218723 0.1809800000 959119081 0 402718720 0.0314952917 -0.0302011520 -0.4251848459 718 28.6800000000 0.0124761062 0.0085402982 0.0129668340 0.0091158526 0.1806630000 959121089 0 402718720 0.0341810584 -0.0304069612 -0.4252527654 719 28.7200000000 0.0125126988 0.0085458230 0.0129668340 0.0091095172 0.1806100000 959123097 0 402718720 0.0370060354 -0.0307954215 -0.4250035584 720 28.7600000000 0.0126601830 0.0085515374 0.0129668340 0.0091060086 0.1807340000 959125105 0 402718720 0.0400831401 -0.0312118568 -0.4245635271 721 28.8000000000 0.0116585763 0.0085558468 0.0129668340 0.0091095028 0.1846560000 959127113 0 402718720 0.0438168049 -0.0285744164 -0.4240359068 722 28.8400000000 0.0125473673 0.0085613752 0.0129668340 0.0091033202 0.1920420000 959129121 0 402718720 0.0469698422 -0.0294202995 -0.4239070714 723 28.8800000000 0.0127370181 0.0085671506 0.0129668340 0.0090973056 0.1801510000 959131129 0 402718720 0.0502575785 -0.0294606704 -0.4233976007 724 28.9200000000 0.0127386432 0.0085729124 0.0129668340 0.0090911038 0.1800240000 959133137 0 402718720 0.0536334440 -0.0292521436 -0.4226143360 725 28.9600000000 0.0127510661 0.0085786753 0.0129668340 0.0090849380 0.1773510000 959135145 0 402718720 0.0572111309 -0.0292225108 -0.4216601253 726 29.0000000000 0.0127276443 0.0085843902 0.0129668340 0.0090799892 0.1800330000 959137153 0 402718720 0.0605347976 -0.0292859413 -0.4207707942 727 29.0400000000 0.0117143784 0.0085886955 0.0129668340 0.0090824362 0.1841250000 959139161 0 402718720 0.0649790019 -0.0268889349 -0.4190880656 728 29.0800000000 0.0126673784 0.0085942981 0.0129668340 0.0090765697 0.1799720000 959141169 0 402718720 0.0683606789 -0.0274528973 -0.4185722768 729 29.1200000000 0.0127516557 0.0086000009 0.0129668340 0.0090703498 0.1955390000 959143177 0 402718720 0.0716356039 -0.0281058438 -0.4174771011 730 29.1600000000 0.0117415702 0.0086043045 0.0129668340 0.0090756050 0.1843860000 959145185 0 402718720 0.0756045207 -0.0267986581 -0.4155705571 731 29.2000000000 0.0117347315 0.0086085868 0.0129668340 0.0090801328 0.1871780000 959147193 0 402718720 0.0795341134 -0.0261961110 -0.4140817523 732 29.2400000000 0.0128041906 0.0086143185 0.0129668340 0.0090770983 0.2041820000 959149201 0 402718720 0.0824240744 -0.0274052229 -0.4135442078 733 29.2800000000 0.0117835971 0.0086186423 0.0129668340 0.0090756739 0.1862880000 959151209 0 402718720 0.0864445567 -0.0255743358 -0.4121463001 734 29.3200000000 0.0117517998 0.0086229109 0.0129668340 0.0090709523 0.1828000000 959153217 0 402718720 0.0899864659 -0.0252641700 -0.4109562635 735 29.3600000000 0.0125245983 0.0086282193 0.0129668340 0.0090648840 0.1810880000 959155225 0 402718720 0.0925716385 -0.0264958329 -0.4104375541 736 29.4000000000 0.0127067333 0.0086337607 0.0129668340 0.0090587778 0.2279020000 959157233 0 402718720 0.0953991637 -0.0270824712 -0.4094147384 737 29.4400000000 0.0129063856 0.0086395581 0.0129668340 0.0090543100 0.2366580000 959159241 0 402718720 0.0982382223 -0.0273644701 -0.4084785283 738 29.4800000000 0.0118479291 0.0086439054 0.0129668340 0.0090512515 0.2420160000 959161249 0 402718720 0.1019444913 -0.0254949573 -0.4068597257 739 29.5200000000 0.0124860797 0.0086491046 0.0129668340 0.0090451992 0.2119280000 959163257 0 402718720 0.1041200012 -0.0269801933 -0.4061181843 740 29.5600000000 0.0127445757 0.0086546390 0.0129668340 0.0090424754 0.1790750000 959165265 0 402718720 0.1064708382 -0.0281612854 -0.4049793482 741 29.6000000000 0.0130562400 0.0086605791 0.0130562400 0.0090495042 0.1838470000 959167273 0 402718720 0.1087233275 -0.0287325885 -0.4039737582 742 29.6400000000 0.0132174278 0.0086667204 0.0132174278 0.0090518450 0.1952260000 959169281 0 402718720 0.1113409549 -0.0286135487 -0.4031391144 743 29.6800000000 0.0131527623 0.0086727581 0.0132174278 0.0090489610 0.1824870000 959171289 0 402718720 0.1137845963 -0.0283645894 -0.4022453427 744 29.7200000000 0.0130154649 0.0086785951 0.0132174278 0.0090440354 0.1822900000 959173297 0 402718720 0.1160976365 -0.0283669326 -0.4012866914 745 29.7600000000 0.0132072102 0.0086846738 0.0132174278 0.0090401338 0.1794140000 959175305 0 402718720 0.1185961515 -0.0278546587 -0.4004622698 746 29.8000000000 0.0129649825 0.0086904115 0.0132174278 0.0090361387 0.1821720000 959177313 0 402718720 0.1210463643 -0.0268738810 -0.3997687995 747 29.8400000000 0.0125354473 0.0086955588 0.0132174278 0.0090359798 0.1820270000 959179321 0 402718720 0.1228970438 -0.0272369348 -0.3986923099 748 29.8800000000 0.0132523086 0.0087016507 0.0132523086 0.0090434199 0.1821720000 959181329 0 402718720 0.1257790923 -0.0280334838 -0.3978418410 749 29.9200000000 0.0131718954 0.0087076190 0.0132523086 0.0090375187 0.1821610000 959183337 0 402718720 0.1283285171 -0.0274834204 -0.3967529833 750 29.9600000000 0.0130224181 0.0087133720 0.0132523086 0.0090319406 0.1821990000 959185345 0 402718720 0.1303687096 -0.0272271596 -0.3958151340 751 30.0000000000 0.0131470030 0.0087192757 0.0132523086 0.0090259735 0.1822460000 959187353 0 402718720 0.1324169785 -0.0268092621 -0.3952068388 752 30.0400000000 0.0130509194 0.0087250358 0.0132523086 0.0090223813 0.1843820000 959189361 0 402718720 0.1343714446 -0.0261524729 -0.3947731853 753 30.0800000000 0.0128587801 0.0087305255 0.0132523086 0.0090193026 0.1847470000 959191369 0 402718720 0.1359828115 -0.0262555908 -0.3943589926 754 30.1200000000 0.0130971028 0.0087363168 0.0132523086 0.0090133444 0.1795390000 959193377 0 402718720 0.1378007084 -0.0263057817 -0.3940899670 755 30.1600000000 0.0130245788 0.0087419966 0.0132523086 0.0090080061 0.1821550000 959195385 0 402718720 0.1394204199 -0.0262267962 -0.3937532306 756 30.2000000000 0.0129207689 0.0087475241 0.0132523086 0.0090021193 0.2038840000 959197393 0 402718720 0.1408067495 -0.0269733910 -0.3931582868 757 30.2400000000 0.0131752286 0.0087533731 0.0132523086 0.0090023989 0.1849220000 959199401 0 402718720 0.1423264891 -0.0281236246 -0.3925786614 758 30.2800000000 0.0136788851 0.0087598711 0.0136788851 0.0090190817 0.1848050000 959201409 0 402718720 0.1440600604 -0.0286421385 -0.3924798667 759 30.3200000000 0.0124014439 0.0087646690 0.0136788851 0.0090366732 0.1897310000 959203417 0 402718720 0.1467249691 -0.0263069663 -0.3921107948 760 30.3600000000 0.0132502001 0.0087705710 0.0136788851 0.0090387254 0.1813510000 959205425 0 402718720 0.1484034657 -0.0278859343 -0.3917145729 761 30.4000000000 0.0136250984 0.0087769501 0.0136788851 0.0090469309 0.1831210000 959207433 0 402718720 0.1503990293 -0.0287482813 -0.3914528489 762 30.4400000000 0.0139791640 0.0087837772 0.0139791640 0.0090619807 0.1946740000 959209441 0 402718720 0.1525022238 -0.0291072205 -0.3910123706 763 30.4800000000 0.0125663988 0.0087887347 0.0139791640 0.0090775248 0.1906470000 959211449 0 402718720 0.1555428207 -0.0267185271 -0.3907004297 764 30.5200000000 0.0134763559 0.0087948704 0.0139791640 0.0090832686 0.1891380000 959213457 0 402718720 0.1574644297 -0.0284299720 -0.3905136585 765 30.5600000000 0.0139953904 0.0088016684 0.0139953904 0.0090992664 0.1987330000 959215465 0 402718720 0.1595209837 -0.0292912889 -0.3903281093 766 30.6000000000 0.0126943951 0.0088067503 0.0139953904 0.0091198657 0.1895320000 959217473 0 402718720 0.1625830382 -0.0266204700 -0.3901973963 767 30.6400000000 0.0136140380 0.0088130180 0.0139953904 0.0091186080 0.1853060000 959219481 0 402718720 0.1648363173 -0.0275709592 -0.3903329670 768 30.6800000000 0.0137696974 0.0088194720 0.0139953904 0.0091164192 0.1855600000 959221489 0 402718720 0.1671004742 -0.0280695111 -0.3901650310 769 30.7200000000 0.0141506176 0.0088264045 0.0141506176 0.0091176493 0.1858480000 959223497 0 402718720 0.1694692224 -0.0280783623 -0.3903325498 770 30.7600000000 0.0141236726 0.0088332841 0.0141506176 0.0091137171 0.1857870000 959225505 0 402718720 0.1717839241 -0.0274796654 -0.3905753195 771 30.8000000000 0.0136982938 0.0088395941 0.0141506176 0.0091081071 0.1856030000 959227513 0 402718720 0.1739661694 -0.0275512747 -0.3905606568 772 30.8400000000 0.0140673378 0.0088463658 0.0141506176 0.0091107285 0.1964800000 959229521 0 402718720 0.1759736985 -0.0281500053 -0.3905799687 773 30.8800000000 0.0143366437 0.0088534684 0.0143366437 0.0091101743 0.1879950000 959231529 0 402718720 0.1784757376 -0.0279427953 -0.3905939460 774 30.9200000000 0.0141904503 0.0088603637 0.0143366437 0.0091047655 0.1869260000 959233537 0 402718720 0.1806371510 -0.0276463833 -0.3906358480 775 30.9600000000 0.0142818913 0.0088673592 0.0143366437 0.0090990258 0.1827240000 959235545 0 402718720 0.1825443506 -0.0273708086 -0.3908229768 776 31.0000000000 0.0140618691 0.0088740532 0.0143366437 0.0090960175 0.1825570000 959237553 0 402718720 0.1844425648 -0.0269091595 -0.3909464180 777 31.0400000000 0.0139949806 0.0088806438 0.0143366437 0.0090919370 0.1853870000 959239561 0 402718720 0.1860398203 -0.0269246399 -0.3910204768 778 31.0800000000 0.0143867545 0.0088877211 0.0143867545 0.0090867796 0.1984440000 959241569 0 402718720 0.1877270937 -0.0263552517 -0.3916108906 779 31.1200000000 0.0140768168 0.0088943823 0.0143867545 0.0090969361 0.1854230000 959243577 0 402718720 0.1892024726 -0.0250186995 -0.3922333419 780 31.1600000000 0.0135883326 0.0089004002 0.0143867545 0.0091297537 0.1849040000 959245585 0 402718720 0.1904692054 -0.0239416659 -0.3924780190 781 31.2000000000 0.0134852529 0.0089062707 0.0143867545 0.0091644433 0.1849500000 959247593 0 402718720 0.1917052120 -0.0235626139 -0.3926817775 782 31.2400000000 0.0135387117 0.0089121945 0.0143867545 0.0091970395 0.1957820000 959249601 0 402718720 0.1928324103 -0.0232685674 -0.3928220570 783 31.2800000000 0.0134076821 0.0089179359 0.0143867545 0.0092276402 0.2072020000 959251609 0 402718720 0.1935519874 -0.0231356025 -0.3931506276 784 31.3200000000 0.0133905634 0.0089236408 0.0143867545 0.0092432758 0.1854880000 959253617 0 402718720 0.1941449046 -0.0233987924 -0.3933441937 785 31.3600000000 0.0135955494 0.0089295922 0.0143867545 0.0092417077 0.1833810000 959255625 0 402718720 0.1947828531 -0.0240033902 -0.3934352994 786 31.4000000000 0.0139674554 0.0089360017 0.0143867545 0.0092361664 0.1957440000 959257633 0 402718720 0.1956931651 -0.0238248538 -0.3938216865 787 31.4400000000 0.0138260629 0.0089422153 0.0143867545 0.0092363307 0.1958820000 959259641 0 402718720 0.1966041774 -0.0229531378 -0.3940843642 788 31.4800000000 0.0136439260 0.0089481819 0.0143867545 0.0092389885 0.1830170000 959261649 0 402718720 0.1972890496 -0.0222461969 -0.3943313360 789 31.5200000000 0.0136576677 0.0089541508 0.0143867545 0.0092431969 0.1850750000 959263657 0 402718720 0.1981803477 -0.0212426484 -0.3947077990 790 31.5600000000 0.0132799167 0.0089596265 0.0143867545 0.0092719249 0.1851990000 959265665 0 402718720 0.1989190578 -0.0199001264 -0.3949221075 791 31.6000000000 0.0130228959 0.0089647634 0.0143867545 0.0093060152 0.1828240000 959267673 0 402718720 0.1997285038 -0.0193083305 -0.3950754404 792 31.6400000000 0.0131537998 0.0089700526 0.0143867545 0.0093182000 0.1815840000 959269681 0 402718720 0.2007272691 -0.0190292187 -0.3949765265 793 31.6800000000 0.0132909222 0.0089755013 0.0143867545 0.0093284265 0.1783990000 959271689 0 402718720 0.2017989308 -0.0183468647 -0.3948323131 794 31.7200000000 0.0132537177 0.0089808895 0.0143867545 0.0093504771 0.1807800000 959273697 0 402718720 0.2028682828 -0.0172287654 -0.3947075009 795 31.7600000000 0.0130978329 0.0089860680 0.0143867545 0.0093792935 0.1783050000 959275705 0 402718720 0.2035614401 -0.0164353214 -0.3943736255 796 31.8000000000 0.0130827278 0.0089912146 0.0143867545 0.0094127692 0.1794560000 959277713 0 402718720 0.2042849809 -0.0155268144 -0.3941181302 797 31.8400000000 0.0129344417 0.0089961622 0.0143867545 0.0094928820 0.1903670000 959279721 0 402718720 0.2052343339 -0.0142961983 -0.3937049508 798 31.8800000000 0.0129048731 0.0090010603 0.0143867545 0.0095941792 0.1774260000 959281729 0 402718720 0.2057214677 -0.0138006750 -0.3933721185 799 31.9200000000 0.0129672391 0.0090060243 0.0143867545 0.0096496706 0.1763250000 959283737 0 402718720 0.2061305791 -0.0137014873 -0.3931060731 800 31.9600000000 0.0130929984 0.0090111330 0.0143867545 0.0096697532 0.1759180000 959285745 0 402718720 0.2067934424 -0.0136295641 -0.3927851617 801 32.0000000000 0.0131898010 0.0090163498 0.0143867545 0.0096730611 0.1760780000 959287753 0 402718720 0.2076194882 -0.0135088153 -0.3921781182 802 32.0400000000 0.0132507207 0.0090216295 0.0143867545 0.0096756334 0.1909400000 959289761 0 402718720 0.2086162269 -0.0132878115 -0.3915562332 803 32.0800000000 0.0134031503 0.0090270860 0.0143867545 0.0096742376 0.1762010000 959291769 0 402718720 0.2096408457 -0.0130163664 -0.3909544051 804 32.1199999990 0.0134653142 0.0090326062 0.0143867545 0.0096733220 0.1762200000 959293777 0 402718720 0.2104803026 -0.0128133222 -0.3901356459 805 32.1600000000 0.0135179972 0.0090381781 0.0143867545 0.0096742990 0.1777400000 959295785 0 402718720 0.2112491280 -0.0125869280 -0.3895293176 806 32.2000000000 0.0135401674 0.0090437637 0.0143867545 0.0096735873 0.1758940000 959297793 0 402718720 0.2119884044 -0.0126279956 -0.3887468874 807 32.2400000000 0.0136331953 0.0090494507 0.0143867545 0.0096686631 0.1872240000 959299801 0 402718720 0.2128024846 -0.0126515077 -0.3881523609 808 32.2800000000 0.0136795212 0.0090551810 0.0143867545 0.0096635182 0.1760320000 959301809 0 402718720 0.2134663463 -0.0124767618 -0.3874626756 809 32.3200000000 0.0136493919 0.0090608599 0.0143867545 0.0096596708 0.1758650000 959303817 0 402718720 0.2141994536 -0.0123079419 -0.3868087530 810 32.3600000000 0.0136807794 0.0090665635 0.0143867545 0.0096562901 0.1760060000 959305825 0 402718720 0.2149466425 -0.0124328993 -0.3858431876 811 32.4000000000 0.0137789892 0.0090723741 0.0143867545 0.0096506247 0.1757470000 959307833 0 402718720 0.2158196270 -0.0126339635 -0.3849016726 812 32.4399999990 0.0139443744 0.0090783741 0.0143867545 0.0096449056 0.1909670000 959309841 0 402718720 0.2168060690 -0.0129310451 -0.3837635815 813 32.4800000000 0.0140232537 0.0090844564 0.0143867545 0.0096397373 0.1782710000 959311849 0 402718720 0.2178390920 -0.0129076764 -0.3828560114 814 32.5200000000 0.0140658785 0.0090905761 0.0143867545 0.0096368113 0.1782710000 959313857 0 402718720 0.2186432332 -0.0131487940 -0.3817500472 815 32.5600000000 0.0141741335 0.0090968136 0.0143867545 0.0096386044 0.1784110000 959315865 0 402718720 0.2194985598 -0.0133813294 -0.3806142509 816 32.6000000000 0.0142410444 0.0091031178 0.0143867545 0.0096412246 0.1789980000 959317873 0 402718720 0.2203822583 -0.0132421497 -0.3796746135 817 32.6400000000 0.0142133553 0.0091093726 0.0143867545 0.0096434576 0.1774070000 959319881 0 402718720 0.2211444825 -0.0132946894 -0.3785544336 818 32.6800000000 0.0141589288 0.0091155457 0.0143867545 0.0096470574 0.1770370000 959321889 0 402718720 0.2217883915 -0.0132200066 -0.3775387704 819 32.7200000000 0.0140104303 0.0091215223 0.0143867545 0.0096489804 0.1766050000 959323897 0 402718720 0.2223683894 -0.0130793769 -0.3763563037 820 32.7599999990 0.0141565520 0.0091276626 0.0143867545 0.0096517977 0.1771990000 959325905 0 402718720 0.2227312922 -0.0134439841 -0.3751935065 821 32.7999999990 0.0142606832 0.0091339148 0.0143867545 0.0096551044 0.1772190000 959327913 0 402718720 0.2229539305 -0.0136753814 -0.3743259013 822 32.8400000000 0.0142697860 0.0091401628 0.0143867545 0.0096583884 0.1892810000 959329921 0 402718720 0.2228971124 -0.0142293712 -0.3732935488 823 32.8800000000 0.0143151535 0.0091464508 0.0143867545 0.0096697226 0.1780780000 959331929 0 402718720 0.2230288684 -0.0147590544 -0.3721685708 824 32.9200000000 0.0143826678 0.0091528054 0.0143867545 0.0096785013 0.1783910000 959333937 0 402718720 0.2229955345 -0.0153396530 -0.3710888922 825 32.9600000000 0.0144035956 0.0091591700 0.0144035956 0.0096900652 0.1789230000 959335945 0 402718720 0.2228386253 -0.0157975182 -0.3702169061 826 33.0000000000 0.0144692343 0.0091655986 0.0144692343 0.0097010779 0.1791790000 959337953 0 402718720 0.2227076590 -0.0159018543 -0.3694343567 827 33.0400000000 0.0143811153 0.0091719052 0.0144692343 0.0097062797 0.1798460000 959339961 0 402718720 0.2224166095 -0.0162093956 -0.3686574101 828 33.0800000000 0.0143335043 0.0091781390 0.0144692343 0.0097147219 0.1796650000 959341969 0 402718720 0.2218468040 -0.0167291965 -0.3681189120 829 33.1199999990 0.0144173224 0.0091844589 0.0144692343 0.0097236730 0.1927800000 959343977 0 402718720 0.2213420123 -0.0167999640 -0.3675711453 830 33.1600000000 0.0142498277 0.0091905617 0.0144692343 0.0097240947 0.1800680000 959345985 0 402718720 0.2208088487 -0.0167945959 -0.3666967750 831 33.2000000000 0.0146241551 0.0091971004 0.0146241551 0.0097269842 0.1927640000 959347993 0 402718720 0.2201575637 -0.0167840365 -0.3645260930 832 33.2400000000 0.0141973132 0.0092031102 0.0146241551 0.0097219630 0.1915030000 959350001 0 402718720 0.2193153501 -0.0167694837 -0.3640526235 833 33.2800000000 0.0142628569 0.0092091844 0.0146241551 0.0097175163 0.1830720000 959352009 0 402718720 0.2186190784 -0.0170175526 -0.3630526066 834 33.3200000000 0.0143651608 0.0092153666 0.0146241551 0.0097133849 0.1803030000 959354017 0 402718720 0.2179505974 -0.0169505384 -0.3620298207 835 33.3600000000 0.0142582236 0.0092214059 0.0146241551 0.0097077170 0.1834030000 959356025 0 402718720 0.2174025774 -0.0167768840 -0.3609357476 836 33.4000000000 0.0142460493 0.0092274163 0.0146241551 0.0097020235 0.1803590000 959358033 0 402718720 0.2165780663 -0.0170549508 -0.3597271144 837 33.4399999990 0.0142941950 0.0092334698 0.0146241551 0.0096971619 0.1830750000 959360041 0 402718720 0.2155432850 -0.0174692422 -0.3588311374 838 33.4800000000 0.0142964022 0.0092395115 0.0146241551 0.0096923788 0.1820890000 959362049 0 402718720 0.2144269943 -0.0176166762 -0.3582599461 839 33.5200000000 0.0142227598 0.0092454510 0.0146241551 0.0096868552 0.1838180000 959364057 0 402718720 0.2131761163 -0.0177341066 -0.3578894138 840 33.5600000000 0.0140865166 0.0092512141 0.0146241551 0.0096816151 0.1955710000 959366065 0 402718720 0.2118473649 -0.0184064489 -0.3572880626 841 33.6000000000 0.0141089708 0.0092569903 0.0146241551 0.0096791995 0.1816030000 959368073 0 402718720 0.2104105055 -0.0194869023 -0.3561915457 842 33.6400000000 0.0143721560 0.0092630653 0.0146241551 0.0096844090 0.1998160000 959370081 0 402718720 0.2092058361 -0.0203145519 -0.3553347290 843 33.6800000000 0.0145304361 0.0092693137 0.0146241551 0.0096855714 0.1845340000 959372089 0 402718720 0.2080955803 -0.0205549467 -0.3544369340 844 33.7200000000 0.0144386739 0.0092754385 0.0146241551 0.0096829769 0.1845550000 959374097 0 402718720 0.2068509012 -0.0209248438 -0.3533122241 845 33.7599999990 0.0146407792 0.0092817880 0.0146407792 0.0096836647 0.1949750000 959376105 0 402718720 0.2055829018 -0.0213157423 -0.3527728617 846 33.7999999990 0.0147437556 0.0092882443 0.0147437556 0.0096835876 0.1823140000 959378113 0 402718720 0.2043225616 -0.0212830156 -0.3521576226 847 33.8400000000 0.0146367187 0.0092945589 0.0147437556 0.0096797946 0.1823550000 959380121 0 402718720 0.2031400204 -0.0210947562 -0.3512619138 848 33.8800000000 0.0145585630 0.0093007664 0.0147437556 0.0096742177 0.1825130000 959382129 0 402718720 0.2019322366 -0.0208541043 -0.3504225910 849 33.9200000000 0.0135863228 0.0093058142 0.0147437556 0.0096715226 0.1911760000 959384137 0 402718720 0.1988550276 -0.0195410624 -0.3536199033 850 33.9600000000 0.0139087038 0.0093112294 0.0147437556 0.0096675628 0.1825590000 959386145 0 402718720 0.1988968551 -0.0201002490 -0.3498724103 851 34.0000000000 0.0135482010 0.0093162082 0.0147437556 0.0096644931 0.1934160000 959388153 0 402718720 0.1962521374 -0.0197379291 -0.3522953391 852 34.0400000000 0.0134933619 0.0093211109 0.0147437556 0.0096609546 0.2031810000 959390161 0 402718720 0.1944701225 -0.0198229700 -0.3526533842 853 34.0800000000 0.0135666877 0.0093260882 0.0147437556 0.0096581412 0.1848750000 959392169 0 402718720 0.1942373067 -0.0204642378 -0.3497155905 854 34.1199999990 0.0135226650 0.0093310022 0.0147437556 0.0096544030 0.2065990000 959394177 0 402718720 0.1918383837 -0.0208327621 -0.3513057828 855 34.1600000000 0.0134391459 0.0093358070 0.0147437556 0.0096498573 0.1975950000 959396185 0 402718720 0.1914066225 -0.0222266950 -0.3479796648 856 34.2000000000 0.0137656983 0.0093409821 0.0147437556 0.0096473798 0.1852750000 959398193 0 402718720 0.1903026551 -0.0235670935 -0.3460847437 857 34.2400000000 0.0140939169 0.0093465282 0.0147437556 0.0096479845 0.1975980000 959400201 0 402718720 0.1892535388 -0.0239511505 -0.3450437188 858 34.2800000000 0.0140318759 0.0093519889 0.0147437556 0.0096436850 0.1860520000 959402209 0 402718720 0.1880176514 -0.0244367085 -0.3437171876 859 34.3200000000 0.0140990196 0.0093575152 0.0147437556 0.0096410144 0.1836120000 959404217 0 402718720 0.1866422445 -0.0249961317 -0.3420892954 860 34.3600000000 0.0142137688 0.0093631620 0.0147437556 0.0096370683 0.1835830000 959406225 0 402718720 0.1852800250 -0.0249763262 -0.3407462835 861 34.4000000000 0.0141013591 0.0093686651 0.0147437556 0.0096315991 0.1833140000 959408233 0 402718720 0.1838508397 -0.0249907020 -0.3393555284 862 34.4400000000 0.0141325472 0.0093741917 0.0147437556 0.0096261139 0.1974800000 959410241 0 402718720 0.1823496968 -0.0251670592 -0.3377478123 863 34.4800000000 0.0142563283 0.0093798488 0.0147437556 0.0096205947 0.1862370000 959412249 0 402718720 0.1808301508 -0.0250549801 -0.3362506926 864 34.5200000000 0.0142408032 0.0093854749 0.0147437556 0.0096155439 0.1841450000 959414257 0 402718720 0.1789763421 -0.0247452147 -0.3342533410 865 34.5600000000 0.0141216964 0.0093909503 0.0147437556 0.0096117365 0.1828300000 959416265 0 402718720 0.1771247238 -0.0248968545 -0.3321241736 866 34.6000000000 0.0141820535 0.0093964828 0.0147437556 0.0096062326 0.1871030000 959418273 0 402718720 0.1750875115 -0.0252501685 -0.3297234774 867 34.6400000000 0.0143867070 0.0094022385 0.0147437556 0.0096010153 0.1870700000 959420281 0 402718720 0.1729415953 -0.0249739774 -0.3279841840 868 34.6800000000 0.0143379718 0.0094079248 0.0147437556 0.0095970849 0.1872590000 959422289 0 402718720 0.1706829071 -0.0243735369 -0.3259674013 869 34.7200000000 0.0143403485 0.0094136008 0.0147437556 0.0095946608 0.1852650000 959424297 0 402718720 0.1683954895 -0.0236213896 -0.3239041567 870 34.7600000000 0.0142378854 0.0094191460 0.0147437556 0.0095973108 0.1846680000 959426305 0 402718720 0.1658572108 -0.0230106674 -0.3214666843 871 34.8000000000 0.0140812248 0.0094244985 0.0147437556 0.0096003281 0.1970150000 959428313 0 402718720 0.1631759703 -0.0233248342 -0.3189686239 872 34.8400000000 0.0142623866 0.0094300466 0.0147437556 0.0095948473 0.1956210000 959430321 0 402718720 0.1602663547 -0.0240702610 -0.3161619008 873 34.8800000000 0.0147435414 0.0094361330 0.0147437556 0.0095933742 0.1993110000 959432329 0 402718720 0.1574981660 -0.0234673359 -0.3139985204 874 34.9200000000 0.0147102382 0.0094421675 0.0147437556 0.0095886615 0.1870140000 959434337 0 402718720 0.1547267735 -0.0221361071 -0.3118979931 875 34.9600000000 0.0144725963 0.0094479166 0.0147437556 0.0095918304 0.1818100000 959436345 0 402718720 0.1518153548 -0.0214156806 -0.3096432686 876 35.0000000000 0.0144107351 0.0094535819 0.0147437556 0.0095951697 0.1843840000 959438353 0 402718720 0.1488411725 -0.0210288763 -0.3073833287 877 35.0400000000 0.0144687844 0.0094593005 0.0147437556 0.0095963664 0.1818930000 959440361 0 402718720 0.1458536237 -0.0204670895 -0.3050609827 878 35.0800000000 0.0143410815 0.0094648606 0.0147437556 0.0096011282 0.1842920000 959442369 0 402718720 0.1427614242 -0.0204438437 -0.3026511371 879 35.1200000000 0.0144532556 0.0094705357 0.0147437556 0.0095994364 0.1841430000 959444377 0 402718720 0.1397585422 -0.0200173799 -0.3006326854 880 35.1600000000 0.0144747142 0.0094762222 0.0147437556 0.0096060064 0.1837180000 959446385 0 402718720 0.1368228346 -0.0190742835 -0.2981535494 881 35.2000000000 0.0143962866 0.0094818069 0.0147437556 0.0096225414 0.1863500000 959448393 0 402718720 0.1334567368 -0.0191658624 -0.2966178954 882 35.2400000000 0.0144641511 0.0094874558 0.0147437556 0.0096240404 0.1970520000 959450401 0 402718720 0.1307257414 -0.0191904325 -0.2937232256 883 35.2800000000 0.0144589823 0.0094930860 0.0147437556 0.0096201540 0.1895770000 959452409 0 402718720 0.1273093820 -0.0191128179 -0.2919311225 884 35.3200000000 0.0144865075 0.0094987347 0.0147437556 0.0096156927 0.1889340000 959454417 0 402718720 0.1245247051 -0.0182301030 -0.2900291085 885 35.3600000000 0.0144551033 0.0095043351 0.0147437556 0.0096123174 0.1889460000 959456425 0 402718720 0.1216259673 -0.0177431963 -0.2880606353 886 35.4000000000 0.0144487396 0.0095099157 0.0147437556 0.0096078936 0.1860690000 959458433 0 402718720 0.1186162904 -0.0178091116 -0.2858645618 887 35.4400000000 0.0144681511 0.0095155056 0.0147437556 0.0096026296 0.1990250000 959460441 0 402718720 0.1157155037 -0.0177724138 -0.2839855254 888 35.4800000000 0.0144822774 0.0095210988 0.0147437556 0.0095973194 0.1874940000 959462449 0 402718720 0.1128916740 -0.0177433789 -0.2821217775 889 35.5200000000 0.0145056685 0.0095267058 0.0147437556 0.0095936370 0.1886520000 959464457 0 402718720 0.1102696583 -0.0172322169 -0.2803772986 890 35.5600000000 0.0145174600 0.0095323134 0.0147437556 0.0095888571 0.1894430000 959466465 0 402718720 0.1077049226 -0.0166332237 -0.2785725296 891 35.6000000000 0.0145350313 0.0095379281 0.0147437556 0.0095835960 0.1904500000 959468473 0 402718720 0.1051383242 -0.0158429388 -0.2769207954 892 35.6400000000 0.0145267518 0.0095435209 0.0147437556 0.0095783029 0.2046460000 959470481 0 402718720 0.1026117355 -0.0153784547 -0.2752992511 893 35.6800000000 0.0145126227 0.0095490854 0.0147437556 0.0095729973 0.2122130000 959472489 0 402718720 0.1000683606 -0.0148901138 -0.2737421393 894 35.7200000000 0.0145226605 0.0095546487 0.0147437556 0.0095678273 0.2035630000 959474497 0 402718720 0.0975808352 -0.0143941576 -0.2723266184 895 35.7600000000 0.0145575199 0.0095602385 0.0147437556 0.0095629908 0.1900700000 959476505 0 402718720 0.0950970650 -0.0140474616 -0.2710690796 896 35.8000000000 0.0145602142 0.0095658188 0.0147437556 0.0095579138 0.1880910000 959478513 0 402718720 0.0926439017 -0.0139240911 -0.2696413100 897 35.8400000000 0.0145179331 0.0095713396 0.0147437556 0.0095526939 0.1976160000 959480521 0 402718720 0.0902693570 -0.0134028466 -0.2684762180 898 35.8800000000 0.0145333828 0.0095768653 0.0147437556 0.0095476527 0.1858750000 959482529 0 402718720 0.0878294632 -0.0127170235 -0.2674145997 899 35.9200000000 0.0145413289 0.0095823875 0.0147437556 0.0095430158 0.1837340000 959484537 0 402718720 0.0852333605 -0.0125458213 -0.2666063309 900 35.9600000000 0.0145913316 0.0095879530 0.0147437556 0.0095377948 0.1764060000 959486545 0 402718720 0.0826976672 -0.0128717329 -0.2661991715 901 36.0000000000 0.0145560093 0.0095934669 0.0147437556 0.0095342770 0.1781120000 959488553 0 402718720 0.0803307295 -0.0126764113 -0.2660197616 902 36.0400000000 0.0145391133 0.0095989499 0.0147437556 0.0095290451 0.1772860000 959490561 0 402718720 0.0779731497 -0.0123286024 -0.2657650113 903 36.0800000000 0.0145732258 0.0096044585 0.0147437556 0.0095238450 0.1926790000 959492569 0 402718720 0.0754296035 -0.0123962890 -0.2654931545 904 36.1200000000 0.0144432914 0.0096098112 0.0147437556 0.0095186513 0.1763560000 959494577 0 402718720 0.0730375051 -0.0122001953 -0.2650028467 905 36.1600000000 0.0144987507 0.0096152133 0.0147437556 0.0095137759 0.1735800000 959496585 0 402718720 0.0705965534 -0.0117554106 -0.2645798028 906 36.2000000000 0.0144188358 0.0096205153 0.0147437556 0.0095103052 0.1715590000 959498593 0 402718720 0.0679813102 -0.0116759455 -0.2643626630 907 36.2400000000 0.0144012747 0.0096257863 0.0147437556 0.0095067873 0.1737310000 959500601 0 402718720 0.0653547943 -0.0118890936 -0.2647765577 908 36.2800000000 0.0143907899 0.0096310341 0.0147437556 0.0095016311 0.1736250000 959502609 0 402718720 0.0626938418 -0.0120522780 -0.2651973665 909 36.3200000000 0.0143992677 0.0096362797 0.0147437556 0.0094964082 0.1737050000 959504617 0 402718720 0.0600600578 -0.0120691983 -0.2651185989 910 36.3600000000 0.0144204414 0.0096415370 0.0147437556 0.0094912404 0.1738820000 959506625 0 402718720 0.0574414693 -0.0118929148 -0.2650603652 911 36.4000000000 0.0143886507 0.0096467479 0.0147437556 0.0094864426 0.1707920000 959508633 0 402718720 0.0547829568 -0.0121504990 -0.2653980553 912 36.4400000000 0.0143953795 0.0096519547 0.0147437556 0.0094812591 0.1839620000 959510641 0 402718720 0.0522691198 -0.0119695272 -0.2652512193 913 36.4800000000 0.0143859312 0.0096571398 0.0147437556 0.0094763280 0.1747600000 959512649 0 402718720 0.0498146378 -0.0116437385 -0.2650970221 914 36.5200000000 0.0143677564 0.0096622936 0.0147437556 0.0094727850 0.1749290000 959514657 0 402718720 0.0471709184 -0.0117909219 -0.2650730312 915 36.5600000000 0.0143526914 0.0096674197 0.0147437556 0.0094689696 0.1755360000 959516665 0 402718720 0.0447231717 -0.0119958920 -0.2654334605 916 36.6000000000 0.0143764848 0.0096725607 0.0147437556 0.0094640262 0.1756450000 959518673 0 402718720 0.0423361436 -0.0121791540 -0.2653768063 917 36.6400000000 0.0143392682 0.0096776498 0.0147437556 0.0094588665 0.1737600000 959520681 0 402718720 0.0399161987 -0.0127689326 -0.2656329870 918 36.6800000000 0.0143516120 0.0096827412 0.0147437556 0.0094540268 0.1765140000 959522689 0 402718720 0.0376606435 -0.0128592653 -0.2653726041 919 36.7200000000 0.0143862581 0.0096878593 0.0147437556 0.0094488850 0.1744140000 959524697 0 402718720 0.0355969556 -0.0126667377 -0.2650960982 920 36.7600000000 0.0143891806 0.0096929694 0.0147437556 0.0094440159 0.1772970000 959526705 0 402718720 0.0335486792 -0.0128673865 -0.2650893629 921 36.8000000000 0.0143560674 0.0096980325 0.0147437556 0.0094389227 0.1783280000 959528713 0 402718720 0.0317374729 -0.0126477620 -0.2649169266 922 36.8400000000 0.0144322896 0.0097031673 0.0147437556 0.0094342361 0.2111050000 959530721 0 402718720 0.0301105417 -0.0122300070 -0.2644540668 923 36.8800000000 0.0144237867 0.0097082817 0.0147437556 0.0094304740 0.2098820000 959532729 0 402718720 0.0285303108 -0.0121146524 -0.2641980946 924 36.9200000000 0.0143879466 0.0097133463 0.0147437556 0.0094280172 0.2310250000 959534737 0 402718720 0.0270633046 -0.0123074269 -0.2644034624 925 36.9600000000 0.0144047458 0.0097184181 0.0147437556 0.0094237336 0.2315560000 959536745 0 402718720 0.0255184248 -0.0125655392 -0.2641772032 926 37.0000000000 0.0144287394 0.0097235048 0.0147437556 0.0094187241 0.2318030000 959538753 0 402718720 0.0242294632 -0.0123247858 -0.2641602159 927 37.0400000000 0.0144416718 0.0097285945 0.0147437556 0.0094141882 0.2034750000 959540761 0 402718720 0.0230792053 -0.0121969208 -0.2641548514 928 37.0800000000 0.0144134527 0.0097336429 0.0147437556 0.0094111216 0.1779760000 959542769 0 402718720 0.0220357105 -0.0113760596 -0.2634949982 929 37.1200000000 0.0144270407 0.0097386950 0.0147437556 0.0094102287 0.1782150000 959544777 0 402718720 0.0210450459 -0.0112108495 -0.2631603479 930 37.1600000000 0.0144434813 0.0097437539 0.0147437556 0.0094095064 0.1802260000 959546785 0 402718720 0.0202005636 -0.0110200690 -0.2629018426 931 37.2000000000 0.0144439107 0.0097488024 0.0147437556 0.0094077866 0.1907520000 959548793 0 402718720 0.0193813462 -0.0107043944 -0.2625962198 932 37.2400000000 0.0144785270 0.0097538772 0.0147437556 0.0094048900 0.1964800000 959550801 0 402718720 0.0187164228 -0.0105818994 -0.2624924481 933 37.2800000000 0.0144479061 0.0097589083 0.0147437556 0.0094019417 0.2323950000 959552809 0 402718720 0.0180072859 -0.0101333959 -0.2620235384 934 37.3200000000 0.0144421402 0.0097639225 0.0147437556 0.0093996184 0.2325450000 959554817 0 402718720 0.0174878724 -0.0094056400 -0.2615544498 935 37.3600000000 0.0144374194 0.0097689209 0.0147437556 0.0093995376 0.2316870000 959556825 0 402718720 0.0170893259 -0.0090281395 -0.2614079118 936 37.4000000000 0.0143873002 0.0097738550 0.0147437556 0.0093977944 0.2316010000 959558833 0 402718720 0.0166670159 -0.0088413721 -0.2613011897 937 37.4400000000 0.0144691365 0.0097788660 0.0147437556 0.0093943795 0.2316540000 959560841 0 402718720 0.0163864791 -0.0089568170 -0.2613043487 938 37.4800000000 0.0144831752 0.0097838812 0.0147437556 0.0093910298 0.2322880000 959562849 0 402718720 0.0161059219 -0.0090256911 -0.2613136172 939 37.5200000000 0.0145174898 0.0097889224 0.0147437556 0.0093867442 0.2321220000 959564857 0 402718720 0.0160997231 -0.0088710580 -0.2615655065 940 37.5600000000 0.0145314010 0.0097939676 0.0147437556 0.0093825207 0.1819650000 959566865 0 402718720 0.0160892047 -0.0085929278 -0.2616708875 941 37.6000000000 0.0145462044 0.0097990178 0.0147437556 0.0093789267 0.1768450000 959568873 0 402718720 0.0160240158 -0.0081006726 -0.2615086734 942 37.6400000000 0.0145896291 0.0098041033 0.0147437556 0.0093758199 0.1867420000 959570881 0 402718720 0.0161473639 -0.0076743015 -0.2615889013 943 37.6800000000 0.0145711889 0.0098091586 0.0147437556 0.0093742361 0.1792150000 959572889 0 402718720 0.0162454229 -0.0074281748 -0.2618201375 944 37.7200000000 0.0145759545 0.0098142081 0.0147437556 0.0093719869 0.1789230000 959574897 0 402718720 0.0163722653 -0.0069528641 -0.2619666457 945 37.7600000000 0.0145645915 0.0098192350 0.0147437556 0.0093695896 0.1787790000 959576905 0 402718720 0.0165238045 -0.0066598905 -0.2621393502 946 37.8000000000 0.0145586738 0.0098242450 0.0147437556 0.0093672333 0.1764100000 959578913 0 402718720 0.0165347364 -0.0065005831 -0.2622263730 947 37.8400000000 0.0145727741 0.0098292593 0.0147437556 0.0093638674 0.1995170000 959580921 0 402718720 0.0166767202 -0.0062486357 -0.2621429265 948 37.8800000000 0.0145800961 0.0098342707 0.0147437556 0.0093612571 0.1750160000 959582929 0 402718720 0.0167790763 -0.0060664844 -0.2621992230 949 37.9200000000 0.0145960627 0.0098392884 0.0147437556 0.0093583442 0.1723290000 959584937 0 402718720 0.0169875585 -0.0058109676 -0.2623686492 950 37.9600000000 0.0146140931 0.0098443145 0.0147437556 0.0093544290 0.1750100000 959586945 0 402718720 0.0172459986 -0.0054024137 -0.2626608014 951 38.0000000000 0.0146070095 0.0098493226 0.0147437556 0.0093502156 0.1743890000 959588953 0 402718720 0.0174518023 -0.0051373960 -0.2627153695 952 38.0400000000 0.0146056199 0.0098543187 0.0147437556 0.0093478753 0.1874280000 959590961 0 402718720 0.0175881367 -0.0048912745 -0.2626044154 953 38.0800000000 0.0146263475 0.0098593261 0.0147437556 0.0093437713 0.1720560000 959592969 0 402718720 0.0179443453 -0.0046606944 -0.2629651427 954 38.1200000000 0.0146242725 0.0098643208 0.0147437556 0.0093389935 0.1770990000 959594977 0 402718720 0.0181864575 -0.0043068957 -0.2629905641 955 38.1600000000 0.0146341175 0.0098693153 0.0147437556 0.0093344742 0.1771740000 959596985 0 402718720 0.0183530096 -0.0042985864 -0.2630317211 956 38.2000000000 0.0146448519 0.0098743107 0.0147437556 0.0093296334 0.1773120000 959598993 0 402718720 0.0186580811 -0.0039587212 -0.2632426620 957 38.2400000000 0.0146216005 0.0098792713 0.0147437556 0.0093248811 0.1856860000 959601001 0 402718720 0.0187878534 -0.0040596817 -0.2634651065 958 38.2800000000 0.0146612413 0.0098842629 0.0147437556 0.0093201846 0.1744730000 959603009 0 402718720 0.0189467706 -0.0038981079 -0.2634521425 959 38.3200000000 0.0146721331 0.0098892554 0.0147437556 0.0093154723 0.1773050000 959605017 0 402718720 0.0192272570 -0.0038903982 -0.2637687325 960 38.3600000000 0.0146589614 0.0098942239 0.0147437556 0.0093108841 0.1743590000 959607025 0 402718720 0.0193870179 -0.0037737812 -0.2635808885 961 38.4000000000 0.0146688465 0.0098991923 0.0147437556 0.0093063640 0.1763880000 959609033 0 402718720 0.0196930915 -0.0036474066 -0.2637941837 962 38.4400000000 0.0146756843 0.0099041574 0.0147437556 0.0093017217 0.1847440000 959611041 0 402718720 0.0199546870 -0.0035386845 -0.2640574574 963 38.4800000000 0.0146519793 0.0099090877 0.0147437556 0.0092969885 0.1739360000 959613049 0 402718720 0.0202266350 -0.0036548516 -0.2641619146 964 38.5200000000 0.0146799246 0.0099140367 0.0147437556 0.0092922345 0.1733990000 959615057 0 402718720 0.0205548964 -0.0034773096 -0.2642857432 965 38.5600000000 0.0146595789 0.0099189543 0.0147437556 0.0092874997 0.1760670000 959617065 0 402718720 0.0208303593 -0.0033904389 -0.2642422318 966 38.6000000000 0.0146419453 0.0099238436 0.0147437556 0.0092829011 0.1730260000 959619073 0 402718720 0.0210901890 -0.0033918372 -0.2644017637 967 38.6400000000 0.0146490447 0.0099287300 0.0147437556 0.0092781322 0.1726790000 959621081 0 402718720 0.0213840865 -0.0033738608 -0.2645551562 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 12:51:48 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0854410000 954998708 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025287711 0.0012643855 0.0025287711 0.0016397671 0.1007130000 957791673 0 402718720 0.0001299634 -0.0014884740 0.0010924200 3 0.0800000000 0.0054393951 0.0026560554 0.0054393951 0.0017417348 0.1313080000 957480985 0 402718720 -0.0038464726 -0.0031208314 0.0017430612 4 0.1200000000 0.0070545794 0.0037556864 0.0070545794 0.0015666187 0.1347800000 957483393 0 402718720 -0.0022835433 -0.0055196011 0.0010540604 5 0.1600000000 0.0088745272 0.0047794546 0.0088745272 0.0013914135 0.1034430000 957485401 0 402718720 -0.0046052579 -0.0063757766 0.0030157084 6 0.2000000000 0.0103131067 0.0057017299 0.0103131067 0.0012780662 0.1020740000 957488209 0 402718720 -0.0038738092 -0.0083495043 0.0025823819 7 0.2400000000 0.0119185001 0.0065898399 0.0119185001 0.0012584144 0.1024640000 957490217 0 402718720 -0.0038071992 -0.0100463117 0.0033046110 8 0.2800000000 0.0135558555 0.0074605919 0.0135558555 0.0012240344 0.1024810000 957492225 0 402718720 -0.0048608119 -0.0114232767 0.0035655268 9 0.3200000000 0.0144807398 0.0082406083 0.0144807398 0.0012497160 0.1027680000 957494233 0 402718720 -0.0066043856 -0.0128953950 0.0038602457 10 0.3600000000 0.0163755231 0.0090540998 0.0163755231 0.0012943616 0.1029030000 957497841 0 402718720 -0.0065556695 -0.0135725420 0.0049268845 11 0.4000000000 0.0167401358 0.0097528303 0.0167401358 0.0015246640 0.1030740000 957499849 0 402718720 -0.0074137240 -0.0147807272 0.0057328264 12 0.4400000000 0.0182647314 0.0104621554 0.0182647314 0.0018481476 0.1032000000 957501857 0 402718720 -0.0073582283 -0.0164845604 0.0053341179 13 0.4800000000 0.0193451047 0.0111454592 0.0193451047 0.0019800947 0.1030720000 957503865 0 402718720 -0.0093400916 -0.0176561046 0.0061515854 14 0.5200000000 0.0214695334 0.0118828931 0.0214695334 0.0019409300 0.1033620000 957505873 0 402718720 -0.0093011064 -0.0186498612 0.0061076679 15 0.5600000000 0.0228035096 0.0126109342 0.0228035096 0.0018742804 0.1032600000 957507881 0 402718720 -0.0118530262 -0.0187623464 0.0071659717 16 0.6000000000 0.0224542823 0.0132261434 0.0228035096 0.0018625575 0.1033270000 957509889 0 402718720 -0.0114539163 -0.0202749595 0.0060798074 17 0.6400000000 0.0233325493 0.0138206379 0.0233325493 0.0018291955 0.1034710000 957511897 0 402718720 -0.0131952623 -0.0224127918 0.0048572728 18 0.6800000000 0.0240801778 0.0143906123 0.0240801778 0.0017754257 0.1034630000 957517105 0 402718720 -0.0144715058 -0.0229751356 0.0059956321 19 0.7200000000 0.0250138305 0.0149497291 0.0250138305 0.0017854601 0.1034360000 957519113 0 402718720 -0.0159157012 -0.0236096159 0.0058136112 20 0.7600000000 0.0247093588 0.0154377106 0.0250138305 0.0018978272 0.1035540000 957521121 0 402718720 -0.0188429896 -0.0245496798 0.0053398223 21 0.8000000000 0.0254345182 0.0159137490 0.0254345182 0.0018594586 0.1036090000 957523129 0 402718720 -0.0216496736 -0.0243281890 0.0058507752 22 0.8400000000 0.0259122662 0.0163682271 0.0259122662 0.0018368883 0.1039480000 957525137 0 402718720 -0.0269974042 -0.0255693458 0.0054589054 23 0.8800000000 0.0263549592 0.0168024328 0.0263549592 0.0017965707 0.1032710000 957527145 0 402718720 -0.0269539990 -0.0269647632 0.0039919186 24 0.9200000000 0.0289953463 0.0173104709 0.0289953463 0.0017855034 0.1031480000 957529153 0 402718720 -0.0342008770 -0.0279234201 0.0038767806 25 0.9600000000 0.0310145747 0.0178586350 0.0310145747 0.0017854470 0.1031170000 957531161 0 402718720 -0.0355914570 -0.0287085474 0.0036456578 26 1.0000000000 0.0304963384 0.0183447006 0.0310145747 0.0017539318 0.1024570000 957533169 0 402718720 -0.0414979830 -0.0296909865 0.0043281587 27 1.0400000000 0.0316579416 0.0188377836 0.0316579416 0.0018706396 0.1010730000 957535177 0 402718720 -0.0470244847 -0.0315132104 0.0024473795 28 1.0800000000 0.0337483585 0.0193703041 0.0337483585 0.0020599066 0.1011480000 957537185 0 402718720 -0.0515168905 -0.0317406654 0.0026433829 29 1.1200000000 0.0356502309 0.0199316809 0.0356502309 0.0022478998 0.1006780000 957539193 0 402718720 -0.0572139993 -0.0333457813 0.0003220402 30 1.1600000000 0.0347423963 0.0204253714 0.0356502309 0.0022636754 0.1004330000 957541201 0 402718720 -0.0664601550 -0.0331988707 0.0019721261 31 1.2000000000 0.0364829749 0.0209433586 0.0364829749 0.0022764184 0.1002300000 957543209 0 402718720 -0.0729487613 -0.0341700502 0.0006261502 32 1.2400000000 0.0382113047 0.0214829819 0.0382113047 0.0023218811 0.0999590000 957545217 0 402718720 -0.0794317126 -0.0354668461 -0.0012844390 33 1.2800000000 0.0381665193 0.0219885437 0.0382113047 0.0023876074 0.0995680000 957547225 0 402718720 -0.0849513635 -0.0358024389 -0.0015753196 34 1.3200000000 0.0218515787 0.0219845153 0.0382113047 0.0027804025 0.1088210000 957555633 0 402718720 -0.1156088188 -0.0208012946 -0.0059581092 35 1.3600000000 0.0268682577 0.0221240508 0.0382113047 0.0031693368 0.1010040000 957557641 0 402718720 -0.1185500920 -0.0249102898 -0.0073852800 36 1.4000000000 0.0308544151 0.0223665609 0.0382113047 0.0037789307 0.1018570000 957559649 0 402718720 -0.1235262752 -0.0278646164 -0.0082689170 37 1.4400000000 0.0266294982 0.0224817754 0.0382113047 0.0037840219 0.1054690000 957561657 0 402718720 -0.1348884702 -0.0258409027 -0.0080649657 38 1.4800000000 0.0256932527 0.0225662880 0.0382113047 0.0037387665 0.1053700000 957563665 0 402718720 -0.1467658430 -0.0254645832 -0.0075777187 39 1.5200000000 0.0295781624 0.0227460796 0.0382113047 0.0036983199 0.1027340000 957565673 0 402718720 -0.1497568041 -0.0298991837 -0.0099416552 40 1.5600000000 0.0270554405 0.0228538137 0.0382113047 0.0036960098 0.1048520000 957567681 0 402718720 -0.1597777903 -0.0290885363 -0.0099353399 41 1.6000000000 0.0262281075 0.0229361135 0.0382113047 0.0037139740 0.1050090000 957569689 0 402718720 -0.1702587157 -0.0294066370 -0.0084354756 42 1.6400000000 0.0270827562 0.0230348431 0.0382113047 0.0036705536 0.1047970000 957571697 0 402718720 -0.1834101081 -0.0287543293 -0.0060616471 43 1.6800000000 0.0302673876 0.0232030418 0.0382113047 0.0036372183 0.1023000000 957573705 0 402718720 -0.1894478053 -0.0313228555 -0.0020644097 44 1.7200000000 0.0334907956 0.0234368544 0.0382113047 0.0036462169 0.1023160000 957575713 0 402718720 -0.1955589950 -0.0351694711 -0.0033172294 45 1.7600000000 0.0372201242 0.0237431493 0.0382113047 0.0036376837 0.1023110000 957577721 0 402718720 -0.2029472291 -0.0366479531 0.0010926703 46 1.8000000000 0.0399332494 0.0240951080 0.0399332494 0.0036301377 0.1028730000 957579729 0 402718720 -0.2087791264 -0.0387606509 0.0018931039 47 1.8400000000 0.0405031852 0.0244442160 0.0405031852 0.0037292330 0.1031460000 957581737 0 402718720 -0.2119688690 -0.0412026756 0.0017841451 48 1.8800000000 0.0419606976 0.0248091427 0.0419606976 0.0037528014 0.1035510000 957583745 0 402718720 -0.2160404027 -0.0428293757 0.0031852757 49 1.9200000000 0.0443253890 0.0252074334 0.0443253890 0.0037167951 0.1040850000 957585753 0 402718720 -0.2228748500 -0.0440044738 0.0044872290 50 1.9600000000 0.0251257382 0.0252057995 0.0443253890 0.0038285261 0.1122860000 957587761 0 402718720 -0.2402839810 -0.0258800425 0.0048962841 51 2.0000000000 0.0293606892 0.0252872680 0.0443253890 0.0038229762 0.1047100000 957589769 0 402718720 -0.2385752201 -0.0301972609 0.0030141706 52 2.0400000000 0.0334381796 0.0254440163 0.0443253890 0.0037936002 0.1047920000 957591777 0 402718720 -0.2414525002 -0.0336759388 0.0031365873 53 2.0800000000 0.0354230069 0.0256322991 0.0443253890 0.0038162636 0.1052360000 957593785 0 402718720 -0.2433161885 -0.0379729792 0.0004575610 54 2.1200000000 0.0257971138 0.0256353512 0.0443253890 0.0040163499 0.1105240000 957595793 0 402718720 -0.2575371265 -0.0302405246 0.0038882759 55 2.1600000000 0.0308331400 0.0257298565 0.0443253890 0.0040614229 0.1053840000 957597801 0 402718720 -0.2591746747 -0.0343596525 0.0047704158 56 2.2000000000 0.0257688053 0.0257305520 0.0443253890 0.0041034068 0.1106740000 957599809 0 402718720 -0.2797282338 -0.0290275663 0.0126839336 57 2.2400000000 0.0277191009 0.0257654388 0.0443253890 0.0040747011 0.1058110000 957601817 0 402718720 -0.2843263149 -0.0335929692 0.0137338955 58 2.2800000000 0.0278730262 0.0258017765 0.0443253890 0.0040783783 0.1083880000 957603825 0 402718720 -0.2936116159 -0.0343836509 0.0165377744 59 2.3200000000 0.0288522821 0.0258534800 0.0443253890 0.0042146067 0.1085350000 957605833 0 402718720 -0.3075748384 -0.0329939164 0.0223935042 60 2.3600000000 0.0308214463 0.0259362794 0.0443253890 0.0043364499 0.1063500000 957607841 0 402718720 -0.3106923997 -0.0366377495 0.0209909584 61 2.4000000000 0.0325498022 0.0260446979 0.0443253890 0.0044659625 0.1060550000 957609849 0 402718720 -0.3168129623 -0.0397193506 0.0210937522 62 2.4400000000 0.0259500667 0.0260431715 0.0443253890 0.0045557907 0.1115630000 957611857 0 402718720 -0.3417988122 -0.0328017510 0.0298591591 63 2.4800000000 0.0271196943 0.0260602592 0.0443253890 0.0047056971 0.1082960000 957613865 0 402718720 -0.3502700329 -0.0350685231 0.0312795155 64 2.5200000000 0.0281341393 0.0260926636 0.0443253890 0.0050626094 0.1081790000 957615873 0 402718720 -0.3626129329 -0.0348395035 0.0360035859 65 2.5600000000 0.0282041710 0.0261251483 0.0443253890 0.0053582360 0.1081960000 957617881 0 402718720 -0.3763764501 -0.0350633003 0.0397206396 66 2.6000000000 0.0292572640 0.0261726046 0.0443253890 0.0054482864 0.1080140000 957632689 0 402718720 -0.3868734837 -0.0347769558 0.0418707915 67 2.6400000000 0.0304030087 0.0262357450 0.0443253890 0.0055031707 0.1077920000 957634697 0 402718720 -0.3969427943 -0.0333972611 0.0443409532 68 2.6800000000 0.0303287283 0.0262959359 0.0443253890 0.0054833296 0.1080240000 957636705 0 402718720 -0.4080921113 -0.0335354842 0.0436051562 69 2.7200000000 0.0300617423 0.0263505128 0.0443253890 0.0054447503 0.1079290000 957638713 0 402718720 -0.4176730812 -0.0330047756 0.0480060205 70 2.7600000000 0.0359050892 0.0264870068 0.0443253890 0.0054117256 0.1053160000 957640721 0 402718720 -0.4255506396 -0.0368224792 0.0489052199 71 2.8000000000 0.0407838710 0.0266883710 0.0443253890 0.0054336834 0.1055920000 957642729 0 402718720 -0.4319913685 -0.0409388766 0.0468924642 72 2.8400000000 0.0274528489 0.0266989888 0.0443253890 0.0063421985 0.1147500000 957644737 0 402718720 -0.4500240088 -0.0229389481 0.0466595180 73 2.8800000000 0.0307744816 0.0267548175 0.0443253890 0.0063853335 0.1102880000 957646745 0 402718720 -0.4595657289 -0.0247804038 0.0490525663 74 2.9200000000 0.0376999937 0.0269027252 0.0443253890 0.0064312550 0.1076190000 957648753 0 402718720 -0.4606725574 -0.0297948420 0.0474420451 75 2.9600000000 0.0447088405 0.0271401401 0.0447088405 0.0064513365 0.1078140000 957650761 0 402718720 -0.4608924091 -0.0328792036 0.0461349413 76 3.0000000000 0.0292250775 0.0271675735 0.0447088405 0.0065978895 0.1165370000 957652769 0 402718720 -0.4614025652 -0.0148398308 0.0345627777 77 3.0400000000 0.0324592590 0.0272362967 0.0447088405 0.0065956388 0.1114980000 957654777 0 402718720 -0.4612865448 -0.0176454224 0.0284325890 78 3.0800000000 0.0291533824 0.0272608747 0.0447088405 0.0065650170 0.1126910000 957656785 0 402718720 -0.4602002800 -0.0132124675 0.0205187332 79 3.1200000000 0.0369988717 0.0273841405 0.0447088405 0.0065436504 0.1066410000 957658793 0 402718720 -0.4658416510 -0.0177112240 0.0200514421 80 3.1600000000 0.0433623381 0.0275838680 0.0447088405 0.0065239508 0.1069600000 957660801 0 402718720 -0.4683994353 -0.0210210383 0.0177086387 81 3.2000000000 0.0288720466 0.0275997714 0.0447088405 0.0065051668 0.1164130000 957662809 0 402718720 -0.4826793373 -0.0080224862 0.0175279863 82 3.2400000000 0.0302602705 0.0276322165 0.0447088405 0.0065134938 0.1121460000 957664817 0 402718720 -0.4907172024 -0.0092516616 0.0172949638 83 3.2800000000 0.0310991760 0.0276739871 0.0447088405 0.0065530650 0.1125420000 957666825 0 402718720 -0.4982210696 -0.0079810172 0.0142717483 84 3.3200000000 0.0305939000 0.0277087480 0.0447088405 0.0065416928 0.1145360000 957668833 0 402718720 -0.5109133124 -0.0086318525 0.0144421319 85 3.3600000000 0.0289670769 0.0277235519 0.0447088405 0.0065222333 0.1176950000 957670841 0 402718720 -0.5249251127 -0.0061140466 0.0145211453 86 3.4000000000 0.0297176074 0.0277467385 0.0447088405 0.0065640885 0.1161200000 957672849 0 402718720 -0.5395296216 -0.0061182976 0.0186407473 87 3.4400000000 0.0292837787 0.0277644057 0.0447088405 0.0066830794 0.1168160000 957674857 0 402718720 -0.5494118333 -0.0068325927 0.0182414986 88 3.4800000000 0.0292448271 0.0277812286 0.0447088405 0.0068290480 0.1176180000 957676865 0 402718720 -0.5624701381 -0.0064605195 0.0185035802 89 3.5200000000 0.0290764011 0.0277957811 0.0447088405 0.0069597245 0.1183980000 957678873 0 402718720 -0.5718448758 -0.0060954560 0.0185939632 90 3.5600000000 0.0286796000 0.0278056014 0.0447088405 0.0070502983 0.1183620000 957680881 0 402718720 -0.5794239640 -0.0075059123 0.0173030496 91 3.6000000000 0.0285775028 0.0278140838 0.0447088405 0.0070892531 0.1187860000 957682889 0 402718720 -0.5939463377 -0.0086608352 0.0202692933 92 3.6400000000 0.0288140289 0.0278249528 0.0447088405 0.0070975800 0.1198110000 957684897 0 402718720 -0.6090553999 -0.0067604417 0.0254389383 93 3.6800000000 0.0287293084 0.0278346770 0.0447088405 0.0070760626 0.1218880000 957686905 0 402718720 -0.6138435006 -0.0076084579 0.0220236052 94 3.7200000000 0.0305860136 0.0278639465 0.0447088405 0.0070499640 0.1195450000 957688913 0 402718720 -0.6201151609 -0.0116574150 0.0218276493 95 3.7600000000 0.0289389584 0.0278752625 0.0447088405 0.0070276577 0.1238370000 957690921 0 402718720 -0.6339994669 -0.0088373823 0.0281240493 96 3.8000000000 0.0288605671 0.0278855261 0.0447088405 0.0069985026 0.1249110000 957692929 0 402718720 -0.6441480517 -0.0093087927 0.0276534613 97 3.8400000000 0.0299656484 0.0279069706 0.0447088405 0.0069630898 0.1223000000 957694937 0 402718720 -0.6491930485 -0.0130544640 0.0296895038 98 3.8800000000 0.0288360678 0.0279164512 0.0447088405 0.0069343648 0.1259830000 957696945 0 402718720 -0.6642312407 -0.0126216933 0.0336160138 99 3.9200000000 0.0317338035 0.0279550103 0.0447088405 0.0069089896 0.1239650000 957698953 0 402718720 -0.6686323881 -0.0139348004 0.0369947553 100 3.9600000000 0.0329259373 0.0280047196 0.0447088405 0.0068745636 0.1244150000 957700961 0 402718720 -0.6763901711 -0.0155101512 0.0411487892 101 4.0000000000 0.0328641720 0.0280528330 0.0447088405 0.0068415888 0.1253360000 957702969 0 402718720 -0.6850274205 -0.0171493217 0.0471488722 102 4.0400000000 0.0335680656 0.0281069039 0.0447088405 0.0068172499 0.1255800000 957704977 0 402718720 -0.6883450150 -0.0192580950 0.0488782674 103 4.0800000000 0.0301538128 0.0281267768 0.0447088405 0.0067867758 0.1284370000 957706985 0 402718720 -0.7005942464 -0.0165425092 0.0551853143 104 4.1200000000 0.0291378517 0.0281364987 0.0447088405 0.0067580176 0.1293390000 957708993 0 402718720 -0.7136658430 -0.0173346959 0.0678965300 105 4.1600000000 0.0311890952 0.0281655710 0.0447088405 0.0067606825 0.1264680000 957711001 0 402718720 -0.7154092789 -0.0194491241 0.0698389933 106 4.2000000000 0.0324386396 0.0282058830 0.0447088405 0.0067693764 0.1269840000 957713009 0 402718720 -0.7212719321 -0.0199815780 0.0749461502 107 4.2400000000 0.0297433920 0.0282202522 0.0447088405 0.0067459192 0.1301540000 957715017 0 402718720 -0.7229714394 -0.0207925364 0.0711285546 108 4.2800000000 0.0292998105 0.0282302481 0.0447088405 0.0067148467 0.1306040000 957717025 0 402718720 -0.7326917052 -0.0213366821 0.0795230046 109 4.3200000000 0.0318036191 0.0282630313 0.0447088405 0.0066980313 0.1273270000 957719033 0 402718720 -0.7332860231 -0.0236102510 0.0807694197 110 4.3600000000 0.0318563022 0.0282956974 0.0447088405 0.0067023126 0.1273180000 957721041 0 402718720 -0.7411412001 -0.0242265444 0.0891251862 111 4.4000000000 0.0316860229 0.0283262409 0.0447088405 0.0067009989 0.1271640000 957723049 0 402718720 -0.7474730015 -0.0253596380 0.0958119854 112 4.4400000000 0.0326439440 0.0283647918 0.0447088405 0.0067027748 0.1268600000 957725057 0 402718720 -0.7548483610 -0.0256754439 0.1036903113 113 4.4800000000 0.0331365764 0.0284070200 0.0447088405 0.0067085119 0.1267830000 957727065 0 402718720 -0.7587054968 -0.0262334477 0.1079162657 114 4.5200000000 0.0299806818 0.0284208241 0.0447088405 0.0067400198 0.1299180000 957729073 0 402718720 -0.7710773349 -0.0235086698 0.1200714558 115 4.5600000000 0.0314812399 0.0284474364 0.0447088405 0.0067639617 0.1264590000 957731081 0 402718720 -0.7710482478 -0.0248903912 0.1219691038 116 4.6000000000 0.0300723650 0.0284614444 0.0447088405 0.0067964344 0.1291760000 957733089 0 402718720 -0.7820557952 -0.0210192781 0.1338930726 117 4.6400000000 0.0327222608 0.0284978616 0.0447088405 0.0068085260 0.1248000000 957735097 0 402718720 -0.7884957194 -0.0205403306 0.1443116665 118 4.6800000000 0.0332845449 0.0285384267 0.0447088405 0.0067804062 0.1256080000 957737105 0 402718720 -0.7933996320 -0.0225636028 0.1484864801 119 4.7200000000 0.0342969708 0.0285868179 0.0447088405 0.0067550394 0.1250030000 957739113 0 402718720 -0.7993178964 -0.0239482187 0.1555224657 120 4.7600000000 0.0356377959 0.0286455760 0.0447088405 0.0067279074 0.1253810000 957741121 0 402718720 -0.8054533601 -0.0239264406 0.1637403518 121 4.8000000000 0.0308507532 0.0286638006 0.0447088405 0.0067152231 0.1290970000 957743129 0 402718720 -0.8171821833 -0.0198844932 0.1815568060 122 4.8400000000 0.0341868363 0.0287090714 0.0447088405 0.0066896303 0.1254510000 957745137 0 402718720 -0.8170869350 -0.0215589348 0.1822553277 123 4.8800000000 0.0368230008 0.0287750383 0.0447088405 0.0066687431 0.1256940000 957747145 0 402718720 -0.8214533925 -0.0198644754 0.1884769946 124 4.9200000000 0.0301116779 0.0287858177 0.0447088405 0.0066437799 0.1326280000 957749153 0 402718720 -0.8339369297 -0.0128396135 0.2045866251 125 4.9600000000 0.0321321674 0.0288125885 0.0447088405 0.0066361797 0.1268380000 957751161 0 402718720 -0.8371277452 -0.0148743670 0.2094775736 126 5.0000000000 0.0338180400 0.0288523143 0.0447088405 0.0066180681 0.1272500000 957753169 0 402718720 -0.8412071466 -0.0152770681 0.2167241722 127 5.0400000000 0.0298013836 0.0288597872 0.0447088405 0.0065939173 0.1342200000 957755177 0 402718720 -0.8525789976 -0.0105637806 0.2338149697 128 5.0800000000 0.0325345919 0.0288884967 0.0447088405 0.0065688464 0.1280910000 957757185 0 402718720 -0.8565876484 -0.0132776797 0.2394373268 129 5.1200000000 0.0335852802 0.0289249058 0.0447088405 0.0065451537 0.1284310000 957759193 0 402718720 -0.8601189256 -0.0139019005 0.2460722476 130 5.1600000000 0.0302994531 0.0289354793 0.0447088405 0.0065345536 0.1326620000 957786801 0 402718720 -0.8702972531 -0.0108855339 0.2643135488 131 5.2000000000 0.0315904729 0.0289557464 0.0447088405 0.0065653361 0.1293280000 957788809 0 402718720 -0.8731815815 -0.0115010068 0.2682675421 132 5.2400000000 0.0300288759 0.0289638762 0.0447088405 0.0065734617 0.1323110000 957790817 0 402718720 -0.8743350506 -0.0103579592 0.2660946250 133 5.2800000000 0.0297541078 0.0289698178 0.0447088405 0.0065720098 0.1317020000 957792825 0 402718720 -0.8846619129 -0.0098696100 0.2851399779 134 5.3200000000 0.0297113732 0.0289753518 0.0447088405 0.0065989594 0.1306360000 957794833 0 402718720 -0.8933766484 -0.0073682731 0.3014596105 135 5.3600000000 0.0293064918 0.0289778046 0.0447088405 0.0066171088 0.1304430000 957796841 0 402718720 -0.8967955709 -0.0066063278 0.3054091334 136 5.4000000000 0.0290350039 0.0289782252 0.0447088405 0.0066507977 0.1304500000 957798849 0 402718720 -0.9037927985 -0.0062707523 0.3175013363 137 5.4400000000 0.0297371540 0.0289837649 0.0447088405 0.0067038109 0.1271490000 957800857 0 402718720 -0.9086432457 -0.0065721450 0.3265660107 138 5.4800000000 0.0286819898 0.0289815781 0.0447088405 0.0067422423 0.1323570000 957802865 0 402718720 -0.9147435427 -0.0063898172 0.3314043581 139 5.5200000000 0.0283466298 0.0289770101 0.0447088405 0.0067831431 0.1324890000 957804873 0 402718720 -0.9208824635 -0.0081027513 0.3366597891 140 5.5600000000 0.0283620376 0.0289726174 0.0447088405 0.0068521664 0.1322680000 957806881 0 402718720 -0.9301227331 -0.0073744687 0.3508803248 141 5.6000000000 0.0283570122 0.0289682515 0.0447088405 0.0068843381 0.1320380000 957808889 0 402718720 -0.9355167150 -0.0061295237 0.3563421965 142 5.6400000000 0.0281277727 0.0289623326 0.0447088405 0.0069173440 0.1321810000 957810897 0 402718720 -0.9446986914 -0.0058533098 0.3709600866 143 5.6800000000 0.0296418779 0.0289670847 0.0447088405 0.0069942695 0.1287650000 957812905 0 402718720 -0.9492313266 -0.0050425059 0.3806876838 144 5.7200000000 0.0282448344 0.0289620690 0.0447088405 0.0070340308 0.1320680000 957814913 0 402718720 -0.9560986757 -0.0019922061 0.3886790276 145 5.7600000000 0.0277786665 0.0289539076 0.0447088405 0.0070325871 0.1322090000 957816921 0 402718720 -0.9617770314 -0.0024339980 0.3954041600 146 5.8000000000 0.0277887173 0.0289459269 0.0447088405 0.0070231678 0.1323400000 957818929 0 402718720 -0.9675484300 -0.0023386853 0.4047916830 147 5.8400000000 0.0276772417 0.0289372964 0.0447088405 0.0070059661 0.1325580000 957820937 0 402718720 -0.9776909947 -0.0029907904 0.4256040454 148 5.8800000000 0.0274560414 0.0289272879 0.0447088405 0.0069845826 0.1331480000 957822945 0 402718720 -0.9791210890 -0.0029213415 0.4289385080 149 5.9200000000 0.0297969524 0.0289331246 0.0447088405 0.0069684303 0.1297770000 957824953 0 402718720 -0.9824543595 -0.0044051036 0.4396469593 150 5.9600000000 0.0302838981 0.0289421297 0.0447088405 0.0069494342 0.1295830000 957826961 0 402718720 -0.9859101772 -0.0051286258 0.4483444393 151 6.0000000000 0.0309567116 0.0289554713 0.0447088405 0.0069301929 0.1296220000 957828969 0 402718720 -0.9889466763 -0.0053448132 0.4579650164 152 6.0400000000 0.0316950493 0.0289734949 0.0447088405 0.0069164233 0.1294660000 957830977 0 402718720 -0.9917102456 -0.0046964376 0.4685838223 153 6.0800000000 0.0306441765 0.0289844143 0.0447088405 0.0069044107 0.1293950000 957832985 0 402718720 -0.9956016541 -0.0046985867 0.4771629274 154 6.1200000000 0.0277615990 0.0289764740 0.0447088405 0.0069182534 0.1323680000 957834993 0 402718720 -1.0010900497 -0.0025136820 0.4897342026 155 6.1600000000 0.0268931370 0.0289630331 0.0447088405 0.0069763602 0.1288240000 957837001 0 402718720 -1.0030856133 -0.0025391255 0.4974772930 156 6.2000000000 0.0270094164 0.0289505099 0.0447088405 0.0070845872 0.1316720000 957839009 0 402718720 -1.0075888634 -0.0014977154 0.5121476054 157 6.2400000000 0.0270106569 0.0289381542 0.0447088405 0.0071718568 0.1280750000 957841017 0 402718720 -1.0097014904 -0.0008261722 0.5228551626 158 6.2800000000 0.0267048292 0.0289240192 0.0447088405 0.0072450975 0.1309830000 957843025 0 402718720 -1.0127831697 -0.0001829616 0.5391960740 159 6.3200000000 0.0265714992 0.0289092235 0.0447088405 0.0072731861 0.1274590000 957845033 0 402718720 -1.0135622025 -0.0006953704 0.5471166372 160 6.3600000000 0.0278351102 0.0289025103 0.0447088405 0.0073123165 0.1273420000 957847041 0 402718720 -1.0139305592 -0.0004479962 0.5619489551 161 6.4000000000 0.0293192118 0.0289050985 0.0447088405 0.0072974614 0.1269540000 957849049 0 402718720 -1.0136094093 -0.0014526249 0.5727880597 162 6.4400000000 0.0294561256 0.0289084999 0.0447088405 0.0072771604 0.1269250000 957851057 0 402718720 -1.0136232376 -0.0033480395 0.5838913321 163 6.4800000000 0.0313234851 0.0289233157 0.0447088405 0.0072601731 0.1267670000 957853065 0 402718720 -1.0139170885 -0.0038562624 0.5966407657 164 6.5200000000 0.0332155265 0.0289494878 0.0447088405 0.0072417915 0.1272920000 957855073 0 402718720 -1.0135710239 -0.0043787113 0.6084790826 165 6.5600000000 0.0263392273 0.0289336680 0.0447088405 0.0072380721 0.1330290000 957857081 0 402718720 -1.0164723396 0.0035848897 0.6265833974 166 6.6000000000 0.0314441435 0.0289487913 0.0447088405 0.0072477413 0.1248870000 957859089 0 402718720 -1.0144475698 -0.0007685410 0.6379575729 167 6.6400000000 0.0346577801 0.0289829769 0.0447088405 0.0072499915 0.1252400000 957861097 0 402718720 -1.0125098228 -0.0019922277 0.6481326818 168 6.6800000000 0.0352232531 0.0290201214 0.0447088405 0.0072491523 0.1254490000 957863105 0 402718720 -1.0115559101 -0.0023357628 0.6601497531 169 6.7200000000 0.0334161334 0.0290461333 0.0447088405 0.0072356340 0.1270580000 957865113 0 402718720 -1.0117393732 -0.0027140060 0.6742728949 170 6.7600000000 0.0263882913 0.0290304989 0.0447088405 0.0072259025 0.1331080000 957867121 0 402718720 -1.0159443617 0.0062133726 0.6922060251 171 6.8000000000 0.0297614336 0.0290347734 0.0447088405 0.0072207551 0.1267420000 957869129 0 402718720 -1.0142247677 0.0056835767 0.7016546726 172 6.8400000000 0.0311622303 0.0290471423 0.0447088405 0.0072021441 0.1266990000 957871137 0 402718720 -1.0129704475 0.0056128874 0.7138025165 173 6.8800000000 0.0324811451 0.0290669921 0.0447088405 0.0071824121 0.1268680000 957873145 0 402718720 -1.0127538443 0.0059212651 0.7272930741 174 6.9200000000 0.0333444774 0.0290915753 0.0447088405 0.0071623136 0.1247100000 957875153 0 402718720 -1.0135393143 0.0068584881 0.7397065163 175 6.9600000000 0.0261330958 0.0290746697 0.0447088405 0.0071446245 0.1308970000 957877161 0 402718720 -1.0152977705 0.0147924786 0.7525287867 176 7.0000000000 0.0266877785 0.0290611078 0.0447088405 0.0071280385 0.1281720000 957879169 0 402718720 -1.0165122747 0.0146230841 0.7670719028 177 7.0400000000 0.0264048260 0.0290461006 0.0447088405 0.0071378235 0.1283370000 957881177 0 402718720 -1.0155740976 0.0125148501 0.7742032409 178 7.0800000000 0.0292466786 0.0290472274 0.0447088405 0.0071221209 0.1248470000 957883185 0 402718720 -1.0137232542 0.0092041120 0.7816656232 179 7.1200000000 0.0270579103 0.0290361139 0.0447088405 0.0071068244 0.1275500000 957885193 0 402718720 -1.0138612986 0.0139715374 0.7948559523 180 7.1600000000 0.0307254605 0.0290454992 0.0447088405 0.0070886166 0.1264490000 957887201 0 402718720 -1.0119144917 0.0127894403 0.8072533011 181 7.2000000000 0.0324871540 0.0290645139 0.0447088405 0.0070726030 0.1262560000 957889209 0 402718720 -1.0095238686 0.0117426412 0.8183608651 182 7.2400000000 0.0333128199 0.0290878562 0.0447088405 0.0070546851 0.1265490000 957891217 0 402718720 -1.0092505217 0.0112454509 0.8315204382 183 7.2800000000 0.0254679024 0.0290680750 0.0447088405 0.0070458636 0.1327440000 957893225 0 402718720 -1.0133893490 0.0194609594 0.8488056064 184 7.3200000000 0.0280853231 0.0290627340 0.0447088405 0.0070272739 0.1262490000 957895233 0 402718720 -1.0105658770 0.0164959785 0.8593089581 185 7.3600000000 0.0299460180 0.0290675085 0.0447088405 0.0070113570 0.1260240000 957897241 0 402718720 -1.0081951618 0.0150451688 0.8736465573 186 7.4000000000 0.0250498448 0.0290459082 0.0447088405 0.0069981616 0.1320320000 957899249 0 402718720 -1.0099651814 0.0195745416 0.8928489089 187 7.4400000000 0.0255829077 0.0290273894 0.0447088405 0.0069913872 0.1284450000 957901257 0 402718720 -1.0067163706 0.0191229731 0.9012686014 188 7.4800000000 0.0298657902 0.0290318490 0.0447088405 0.0070034900 0.1247990000 957903265 0 402718720 -1.0030623674 0.0185060091 0.9159564376 189 7.5200000000 0.0247441083 0.0290091626 0.0447088405 0.0069879733 0.1297240000 957905273 0 402718720 -1.0024133921 0.0262537319 0.9340821505 190 7.5600000000 0.0282349922 0.0290050880 0.0447088405 0.0069752909 0.1228130000 957907281 0 402718720 -0.9990463257 0.0217341334 0.9481492043 191 7.6000000000 0.0243731160 0.0289808368 0.0447088405 0.0069626492 0.1285930000 957909289 0 402718720 -0.9989357591 0.0278013181 0.9649963379 192 7.6400000000 0.0311543457 0.0289921572 0.0447088405 0.0069613507 0.1228190000 957911297 0 402718720 -0.9934921861 0.0272472035 0.9794326425 193 7.6800000000 0.0241641272 0.0289671415 0.0447088405 0.0069683683 0.1284270000 957913305 0 402718720 -0.9953280687 0.0345289074 0.9980665445 194 7.7200000000 0.0245338157 0.0289442893 0.0447088405 0.0069634658 0.1254810000 957915313 0 402718720 -0.9954938889 0.0300999880 1.0140872002 195 7.7600000000 0.0245731436 0.0289218732 0.0447088405 0.0069657976 0.1249550000 957917321 0 402718720 -0.9942815900 0.0298030339 1.0269708633 196 7.8000000000 0.0250629205 0.0289021846 0.0447088405 0.0070015455 0.1240560000 957919329 0 402718720 -0.9922665358 0.0329304710 1.0435425043 197 7.8400000000 0.0250050575 0.0288824022 0.0447088405 0.0070258239 0.1253110000 957921337 0 402718720 -0.9905095100 0.0364911146 1.0554847717 198 7.8800000000 0.0249575377 0.0288625797 0.0447088405 0.0070434274 0.1252370000 957923345 0 402718720 -0.9893573523 0.0402321592 1.0719660521 199 7.9200000000 0.0242999513 0.0288396519 0.0447088405 0.0070358393 0.1250650000 957925353 0 402718720 -0.9874972701 0.0418787785 1.0876629353 200 7.9600000000 0.0236561447 0.0288137344 0.0447088405 0.0070256003 0.1248560000 957927361 0 402718720 -0.9875473380 0.0409961604 1.1015758514 201 8.0000000000 0.0236541349 0.0287880647 0.0447088405 0.0070401930 0.1245740000 957929369 0 402718720 -0.9868789911 0.0414746031 1.1200640202 202 8.0400000000 0.0234227180 0.0287615036 0.0447088405 0.0070563646 0.1240680000 957931377 0 402718720 -0.9841480255 0.0425617546 1.1306188107 203 8.0800000000 0.0237258207 0.0287366973 0.0447088405 0.0070652713 0.1237920000 957933385 0 402718720 -0.9817937613 0.0440768711 1.1475539207 204 8.1200000000 0.0232227370 0.0287096681 0.0447088405 0.0070567358 0.1234590000 957935393 0 402718720 -0.9800388217 0.0440453030 1.1601475477 205 8.1600000000 0.0242182631 0.0286877588 0.0447088405 0.0070485105 0.1205310000 957937401 0 402718720 -0.9768161178 0.0420479402 1.1713402271 206 8.1999999990 0.0264218040 0.0286767590 0.0447088405 0.0070397018 0.1197230000 957939409 0 402718720 -0.9728922844 0.0400262736 1.1841230392 207 8.2400000000 0.0300200284 0.0286832482 0.0447088405 0.0070339042 0.1193880000 957941417 0 402718720 -0.9675062299 0.0394763909 1.1974236965 208 8.2799999990 0.0336217284 0.0287069909 0.0447088405 0.0070198606 0.1194900000 957943425 0 402718720 -0.9624107480 0.0380962268 1.2099242210 209 8.3200000000 0.0374222025 0.0287486905 0.0447088405 0.0070143336 0.1195110000 957945433 0 402718720 -0.9569152594 0.0362667888 1.2226918936 210 8.3599999990 0.0406948999 0.0288055772 0.0447088405 0.0070327669 0.1194440000 957947441 0 402718720 -0.9504866004 0.0338286161 1.2343668938 211 8.4000000000 0.0416190140 0.0288663044 0.0447088405 0.0070491513 0.1191910000 957949449 0 402718720 -0.9451674819 0.0311167818 1.2473267317 212 8.4399999990 0.0434919558 0.0289352933 0.0447088405 0.0070343541 0.1187830000 957951457 0 402718720 -0.9375497699 0.0322211944 1.2594660521 213 8.4800000000 0.0477388576 0.0290235730 0.0477388576 0.0070320263 0.1188860000 957953465 0 402718720 -0.9300290942 0.0319027379 1.2732076645 214 8.5200000000 0.0234214626 0.0289973949 0.0477388576 0.0071659498 0.1281180000 957955473 0 402718720 -0.9292350411 0.0556366704 1.2874684334 215 8.5600000000 0.0280744899 0.0289931023 0.0477388576 0.0071702298 0.1178130000 957957481 0 402718720 -0.9202558398 0.0505567119 1.2983403206 216 8.6000000000 0.0231578704 0.0289660873 0.0477388576 0.0071568384 0.1226030000 957959489 0 402718720 -0.9122329950 0.0597230047 1.3095816374 217 8.6400000000 0.0260469280 0.0289526350 0.0477388576 0.0071751649 0.1197660000 957961497 0 402718720 -0.9025976062 0.0598819442 1.3260936737 218 8.6800000000 0.0261160880 0.0289396233 0.0477388576 0.0072217082 0.1195320000 957963505 0 402718720 -0.8940606117 0.0595685244 1.3356812000 219 8.7200000000 0.0324704200 0.0289557457 0.0477388576 0.0072178631 0.1158750000 957965513 0 402718720 -0.8824487925 0.0561228879 1.3469860554 220 8.7600000000 0.0401551016 0.0290066518 0.0477388576 0.0072165120 0.1153490000 957967521 0 402718720 -0.8700156212 0.0534512997 1.3588063717 221 8.8000000000 0.0448091105 0.0290781562 0.0477388576 0.0072453450 0.1154020000 957969529 0 402718720 -0.8591648340 0.0500137024 1.3705408573 222 8.8400000000 0.0472918004 0.0291601996 0.0477388576 0.0072488687 0.1149170000 957971537 0 402718720 -0.8493269682 0.0491917543 1.3842532635 223 8.8800000000 0.0499254465 0.0292533173 0.0499254465 0.0072472797 0.1151250000 957973545 0 402718720 -0.8381107450 0.0497056544 1.3949909210 224 8.9200000000 0.0532358177 0.0293603820 0.0532358177 0.0072491997 0.1164920000 957975553 0 402718720 -0.8265915513 0.0494003296 1.4057756662 225 8.9600000000 0.0543713458 0.0294715419 0.0543713458 0.0072446883 0.1161910000 957977561 0 402718720 -0.8159372807 0.0509344488 1.4142386913 226 9.0000000000 0.0542355031 0.0295811169 0.0543713458 0.0072300327 0.1152660000 957979569 0 402718720 -0.8057013750 0.0549611337 1.4249687195 227 9.0400000000 0.0308974702 0.0295869158 0.0543713458 0.0072566126 0.1237140000 957981577 0 402718720 -0.7992950082 0.0836224556 1.4338465929 228 9.0800000000 0.0326043554 0.0296001502 0.0543713458 0.0072641772 0.1175750000 957983585 0 402718720 -0.7874549627 0.0877305120 1.4475356340 229 9.1200000000 0.0306084622 0.0296045533 0.0543713458 0.0073237533 0.1194000000 957985593 0 402718720 -0.7773310542 0.0937200189 1.4551098347 230 9.1600000000 0.0298220329 0.0296054989 0.0543713458 0.0074221571 0.1185500000 957987601 0 402718720 -0.7666773200 0.0986061469 1.4619672298 231 9.2000000000 0.0292012207 0.0296037488 0.0543713458 0.0076282275 0.1175390000 957989609 0 402718720 -0.7575572133 0.1002659351 1.4694451094 232 9.2400000000 0.0287498571 0.0296000682 0.0543713458 0.0077874590 0.1167570000 957991617 0 402718720 -0.7482069731 0.1036695614 1.4777947664 233 9.2800000000 0.0277625136 0.0295921817 0.0543713458 0.0079283989 0.1161080000 957993625 0 402718720 -0.7388390899 0.1075140536 1.4851546288 234 9.3200000000 0.0267249830 0.0295799287 0.0543713458 0.0080305472 0.1151800000 957995633 0 402718720 -0.7291393876 0.1122821197 1.4920952320 235 9.3600000000 0.0252114739 0.0295613395 0.0543713458 0.0081075709 0.1152310000 957997641 0 402718720 -0.7194486856 0.1171420440 1.4993607998 236 9.4000000000 0.0242788177 0.0295389560 0.0543713458 0.0081664835 0.1147320000 957999649 0 402718720 -0.7102671862 0.1207827628 1.5079019070 237 9.4400000000 0.0240324568 0.0295157218 0.0543713458 0.0081937198 0.1149340000 958001657 0 402718720 -0.7003948689 0.1252310872 1.5142153502 238 9.4800000000 0.0238832049 0.0294920558 0.0543713458 0.0082137314 0.1147390000 958003665 0 402718720 -0.6896179914 0.1313578486 1.5219752789 239 9.5200000000 0.0236972645 0.0294678098 0.0543713458 0.0082556064 0.1150330000 958005673 0 402718720 -0.6789628267 0.1367965937 1.5294153690 240 9.5600000000 0.0234443694 0.0294427121 0.0543713458 0.0083077584 0.1157310000 958007681 0 402718720 -0.6688878536 0.1418328285 1.5380773544 241 9.6000000000 0.0234621391 0.0294178965 0.0543713458 0.0083594069 0.1137330000 958009689 0 402718720 -0.6595966816 0.1426975876 1.5467642546 242 9.6400000000 0.0233448800 0.0293928013 0.0543713458 0.0083788890 0.1145110000 958011697 0 402718720 -0.6498667002 0.1454414874 1.5552910566 243 9.6800000000 0.0227874797 0.0293656190 0.0543713458 0.0083924479 0.1175630000 958013705 0 402718720 -0.6390869021 0.1519818008 1.5630209446 244 9.7200000000 0.0226208828 0.0293379766 0.0543713458 0.0084363377 0.1177650000 958015713 0 402718720 -0.6278371215 0.1585766226 1.5710865259 245 9.7600000000 0.0258019716 0.0293235439 0.0543713458 0.0084913435 0.1124220000 958017721 0 402718720 -0.6166312695 0.1580375433 1.5792918205 246 9.8000000000 0.0261629261 0.0293106959 0.0543713458 0.0085085144 0.1126010000 958019729 0 402718720 -0.6062028408 0.1605301946 1.5880167484 247 9.8400000000 0.0252088122 0.0292940891 0.0543713458 0.0085130310 0.1128450000 958021737 0 402718720 -0.5970166326 0.1616619676 1.5975253582 248 9.8800000000 0.0248569585 0.0292761974 0.0543713458 0.0084976557 0.1126810000 958023745 0 402718720 -0.5878016949 0.1637484282 1.6058648825 249 9.9200000000 0.0242497008 0.0292560107 0.0543713458 0.0084815347 0.1122220000 958025753 0 402718720 -0.5779779553 0.1666209698 1.6131596565 250 9.9600000000 0.0226809364 0.0292297104 0.0543713458 0.0084651827 0.1144010000 958027761 0 402718720 -0.5687726736 0.1703725904 1.6227991581 251 10.0000000000 0.0225221645 0.0292029871 0.0543713458 0.0084486634 0.1127460000 958029769 0 402718720 -0.5587525964 0.1735854000 1.6314377785 252 10.0400000000 0.0223447960 0.0291757720 0.0543713458 0.0084346111 0.1117000000 958031777 0 402718720 -0.5502626896 0.1728492677 1.6417765617 253 10.0800000000 0.0220762659 0.0291477108 0.0543713458 0.0084188497 0.1109700000 958033785 0 402718720 -0.5427510738 0.1699924618 1.6515702009 254 10.1200000000 0.0231596939 0.0291241359 0.0543713458 0.0084378232 0.1076460000 958035793 0 402718720 -0.5327376127 0.1726777107 1.6595644951 255 10.1600000000 0.0233299546 0.0291014136 0.0543713458 0.0084532461 0.1074020000 958037801 0 402718720 -0.5218349099 0.1794171333 1.6687217951 256 10.2000000000 0.0228211582 0.0290768814 0.0543713458 0.0084402959 0.1075830000 958039809 0 402718720 -0.5107914805 0.1848154217 1.6775468588 257 10.2400000000 0.0224945936 0.0290512693 0.0543713458 0.0084256706 0.1076870000 958041817 0 402718720 -0.5015137792 0.1848383993 1.6861206293 258 10.2800000000 0.0238767415 0.0290312130 0.0543713458 0.0084094459 0.1076330000 958095025 0 402718720 -0.4908336699 0.1886067539 1.6949677467 259 10.3200000000 0.0245660469 0.0290139730 0.0543713458 0.0084019049 0.1076280000 958097033 0 402718720 -0.4802072644 0.1917929202 1.7013133764 260 10.3600000000 0.0214191265 0.0289847621 0.0543713458 0.0084099213 0.1132200000 958099041 0 402718720 -0.4710932970 0.1964709461 1.7099398375 261 10.4000000000 0.0232867803 0.0289629307 0.0543713458 0.0084077039 0.1071170000 958101049 0 402718720 -0.4610156417 0.1941596866 1.7162884474 262 10.4400000000 0.0237049963 0.0289428623 0.0543713458 0.0083945439 0.1064740000 958103057 0 402718720 -0.4514020085 0.1940180212 1.7234641314 263 10.4800000000 0.0234971270 0.0289221560 0.0543713458 0.0083803962 0.1065180000 958105065 0 402718720 -0.4406210184 0.1957333833 1.7296983004 264 10.5200000000 0.0232453533 0.0289006530 0.0543713458 0.0083694796 0.1074190000 958107073 0 402718720 -0.4303560853 0.1956528276 1.7357835770 265 10.5600000000 0.0227629077 0.0288774917 0.0543713458 0.0083538927 0.1072620000 958109081 0 402718720 -0.4192186296 0.1980304122 1.7425171137 266 10.6000000000 0.0212742556 0.0288489081 0.0543713458 0.0083434648 0.1101740000 958111089 0 402718720 -0.4076782763 0.2017845213 1.7465839386 267 10.6400000000 0.0210950729 0.0288198675 0.0543713458 0.0083394937 0.1102690000 958113097 0 402718720 -0.3964813054 0.2010394484 1.7506769896 268 10.6800000000 0.0220319796 0.0287945396 0.0543713458 0.0083316319 0.1072050000 958115105 0 402718720 -0.3848112226 0.1996587068 1.7573313713 269 10.7200000000 0.0217431709 0.0287683263 0.0543713458 0.0083199477 0.1067160000 958117113 0 402718720 -0.3729496300 0.1998947412 1.7601549625 270 10.7600000000 0.0207055919 0.0287384643 0.0543713458 0.0083116720 0.1129910000 958119121 0 402718720 -0.3479773998 0.2055205107 1.7698098421 271 10.8000000000 0.0206407439 0.0287085835 0.0543713458 0.0083275816 0.1135730000 958121129 0 402718720 -0.3336628675 0.2093293518 1.7731354237 272 10.8400000000 0.0205143504 0.0286784576 0.0543713458 0.0083879062 0.1112590000 958123137 0 402718720 -0.3217182159 0.2076193690 1.7769643068 273 10.8800000000 0.0204525292 0.0286483260 0.0543713458 0.0083956600 0.1113580000 958125145 0 402718720 -0.3091281652 0.2084089965 1.7815033197 274 10.9200000000 0.0203668587 0.0286181017 0.0543713458 0.0084035983 0.1118300000 958127153 0 402718720 -0.2958796918 0.2097094357 1.7852284908 275 10.9600000000 0.0203131437 0.0285879018 0.0543713458 0.0084084977 0.1122080000 958129161 0 402718720 -0.2829841673 0.2097660899 1.7880604267 276 11.0000000000 0.0202025920 0.0285575203 0.0543713458 0.0084052692 0.1121420000 958131169 0 402718720 -0.2695479989 0.2117511481 1.7919304371 277 11.0400000000 0.0200228970 0.0285267093 0.0543713458 0.0084107029 0.1154950000 958133177 0 402718720 -0.2560516894 0.2133850008 1.7952293158 278 11.0800000000 0.0199311078 0.0284957899 0.0543713458 0.0084157323 0.1129830000 958135185 0 402718720 -0.2424768507 0.2152581960 1.7988691330 279 11.1200000000 0.0198092423 0.0284646553 0.0543713458 0.0084249700 0.1161740000 958137193 0 402718720 -0.2285695076 0.2171422094 1.8026852608 280 11.1600000000 0.0197176207 0.0284334159 0.0543713458 0.0084327868 0.1166940000 958139201 0 402718720 -0.2145848423 0.2197426707 1.8059248924 281 11.2000000000 0.0196630340 0.0284022046 0.0543713458 0.0084384000 0.1142840000 958141209 0 402718720 -0.2014319301 0.2206704170 1.8087975979 282 11.2400000000 0.0196148455 0.0283710437 0.0543713458 0.0084333554 0.1148430000 958143217 0 402718720 -0.1895849556 0.2197496891 1.8133748770 283 11.2800000000 0.0204274654 0.0283429746 0.0543713458 0.0084185854 0.1119870000 958145225 0 402718720 -0.1768876910 0.2204561085 1.8166104555 284 11.3200000000 0.0195178315 0.0283119001 0.0543713458 0.0084076043 0.1159620000 958147233 0 402718720 -0.1646991968 0.2233400941 1.8214507103 285 11.3600000000 0.0192463957 0.0282800913 0.0543713458 0.0084047467 0.1173290000 958149241 0 402718720 -0.1531965882 0.2246910781 1.8256705999 286 11.4000000000 0.0190301314 0.0282477488 0.0543713458 0.0083961524 0.1180360000 958151249 0 402718720 -0.1427187622 0.2249154449 1.8296947479 287 11.4400000000 0.0189009365 0.0282151815 0.0543713458 0.0083816060 0.1183700000 958153257 0 402718720 -0.1332378238 0.2246599942 1.8338302374 288 11.4800000000 0.0187907759 0.0281824579 0.0543713458 0.0083677732 0.1185420000 958155265 0 402718720 -0.1243893579 0.2246931940 1.8378618956 289 11.5200000000 0.0186871309 0.0281496021 0.0543713458 0.0083543920 0.1184660000 958157273 0 402718720 -0.1158950552 0.2246678323 1.8443382978 290 11.5600000000 0.0185949858 0.0281166551 0.0543713458 0.0083452749 0.1188050000 958159281 0 402718720 -0.1076004207 0.2251991481 1.8501758575 291 11.6000000000 0.0184497237 0.0280834354 0.0543713458 0.0083339932 0.1186930000 958161289 0 402718720 -0.1001031622 0.2244177163 1.8572087288 292 11.6400000000 0.0183157474 0.0280499845 0.0543713458 0.0083213194 0.1190590000 958163297 0 402718720 -0.0921001360 0.2255798876 1.8630206585 293 11.6800000000 0.0182307251 0.0280164716 0.0543713458 0.0083071183 0.1197590000 958165305 0 402718720 -0.0851530358 0.2259208262 1.8698080778 294 11.7200000000 0.0181742050 0.0279829945 0.0543713458 0.0082942464 0.1204450000 958167313 0 402718720 -0.0790597200 0.2252275944 1.8769856691 295 11.7600000000 0.0184815228 0.0279507861 0.0543713458 0.0082855466 0.1182710000 958169321 0 402718720 -0.0733792931 0.2248629183 1.8836809397 296 11.8000000000 0.0190293081 0.0279206460 0.0543713458 0.0082763856 0.1186940000 958171329 0 402718720 -0.0674866736 0.2244491577 1.8897849321 297 11.8400000000 0.0194522999 0.0278921331 0.0543713458 0.0082675712 0.1193470000 958173337 0 402718720 -0.0626010820 0.2235062718 1.8967846632 298 11.8800000000 0.0200373605 0.0278657748 0.0543713458 0.0082622056 0.1201920000 958175345 0 402718720 -0.0577012524 0.2222314030 1.9040321112 299 11.9200000000 0.0178190321 0.0278321736 0.0543713458 0.0082523300 0.1269290000 958177353 0 402718720 -0.0528766438 0.2246743888 1.9139961004 300 11.9600000000 0.0195043199 0.0278044141 0.0543713458 0.0082400230 0.1217160000 958179361 0 402718720 -0.0477666445 0.2236674428 1.9210520983 301 12.0000000000 0.0179340485 0.0277716222 0.0543713458 0.0082265578 0.1258050000 958181369 0 402718720 -0.0433039777 0.2256523222 1.9312410355 302 12.0400000000 0.0176952165 0.0277382566 0.0543713458 0.0082152857 0.1268160000 958183377 0 402718720 -0.0393841863 0.2257288694 1.9411647320 303 12.0800000000 0.0175374132 0.0277045905 0.0543713458 0.0082087322 0.1273930000 958185385 0 402718720 -0.0352404118 0.2262180448 1.9510743618 304 12.1200000000 0.0173317920 0.0276704694 0.0543713458 0.0082065110 0.1280850000 958187393 0 402718720 -0.0314010642 0.2266624123 1.9613053799 305 12.1600000000 0.0171149001 0.0276358610 0.0543713458 0.0082027901 0.1288260000 958189401 0 402718720 -0.0277879760 0.2268183082 1.9726569653 306 12.2000000000 0.0168930441 0.0276007538 0.0543713458 0.0081953677 0.1288540000 958191409 0 402718720 -0.0242487546 0.2270195633 1.9841935635 307 12.2400000000 0.0167427491 0.0275653857 0.0543713458 0.0081963790 0.1291740000 958193417 0 402718720 -0.0210465025 0.2278809249 1.9956921339 308 12.2800000000 0.0166406743 0.0275299158 0.0543713458 0.0081992617 0.1296850000 958195425 0 402718720 -0.0184674188 0.2281101942 2.0072970390 309 12.3200000000 0.0162837934 0.0274935206 0.0543713458 0.0082096803 0.1328290000 958197433 0 402718720 -0.0166203231 0.2281398326 2.0183794498 310 12.3600000000 0.0161009319 0.0274567703 0.0543713458 0.0082273687 0.1328320000 958199441 0 402718720 -0.0150186634 0.2278003842 2.0302913189 311 12.4000000000 0.0159360841 0.0274197263 0.0543713458 0.0082401048 0.1330140000 958201449 0 402718720 -0.0128673958 0.2287900001 2.0410494804 312 12.4400000000 0.0155763524 0.0273817668 0.0543713458 0.0082746607 0.1334640000 958203457 0 402718720 -0.0106514050 0.2289125323 2.0650000572 313 12.4800000000 0.0153448395 0.0273433101 0.0543713458 0.0082678164 0.1311680000 958205465 0 402718720 -0.0101180086 0.2289494276 2.0756318569 314 12.5200000000 0.0151300346 0.0273044144 0.0543713458 0.0082593514 0.1312710000 958207473 0 402718720 -0.0101222815 0.2280528843 2.0882320404 315 12.5600000000 0.0147676468 0.0272646151 0.0543713458 0.0082581359 0.1312530000 958209481 0 402718720 -0.0097652134 0.2286860347 2.0997123718 316 12.6000000000 0.0144550418 0.0272240785 0.0543713458 0.0082471617 0.1315190000 958211489 0 402718720 -0.0096527608 0.2293129414 2.1120004654 317 12.6400000000 0.0140131088 0.0271824035 0.0543713458 0.0082341778 0.1323630000 958213497 0 402718720 -0.0100325579 0.2291661948 2.1237049103 318 12.6800000000 0.0139136612 0.0271406779 0.0543713458 0.0082211930 0.1357320000 958215505 0 402718720 -0.0106986836 0.2287969738 2.1349771023 319 12.7200000000 0.0136261638 0.0270983126 0.0543713458 0.0082082850 0.1369530000 958217513 0 402718720 -0.0114808977 0.2292983234 2.1450395584 320 12.7600000000 0.0133463172 0.0270553377 0.0543713458 0.0081954468 0.1384480000 958219521 0 402718720 -0.0127280243 0.2298045605 2.1553056240 321 12.8000000000 0.0130657507 0.0270117564 0.0543713458 0.0081855486 0.1393840000 958221529 0 402718720 -0.0149096819 0.2290310562 2.1658766270 322 12.8400000000 0.0127789099 0.0269675550 0.0543713458 0.0081753785 0.1402530000 958223537 0 402718720 -0.0165786538 0.2297299355 2.1751391888 323 12.8800000000 0.0124908928 0.0269227356 0.0543713458 0.0081669708 0.1416740000 958225545 0 402718720 -0.0185761936 0.2289898694 2.1837451458 324 12.9200000000 0.0122003946 0.0268772963 0.0543713458 0.0081557098 0.1427540000 958227553 0 402718720 -0.0206028540 0.2287402749 2.1928579807 325 12.9600000000 0.0119295772 0.0268313033 0.0543713458 0.0081434359 0.1439520000 958229561 0 402718720 -0.0220212508 0.2299594283 2.2017798424 326 13.0000000000 0.0117026223 0.0267848963 0.0543713458 0.0081318976 0.1485950000 958231569 0 402718720 -0.0240096785 0.2299441099 2.2088971138 327 13.0400000000 0.0114367474 0.0267379601 0.0543713458 0.0081214024 0.1498970000 958233577 0 402718720 -0.0260436051 0.2307162881 2.2185025215 328 13.0800000000 0.0112264240 0.0266906688 0.0543713458 0.0081097715 0.1512910000 958235585 0 402718720 -0.0266262610 0.2337351143 2.2247712612 329 13.1200000000 0.0110098384 0.0266430067 0.0543713458 0.0080984261 0.1531720000 958237593 0 402718720 -0.0282796659 0.2348834127 2.2338128090 330 13.1600000000 0.0108263120 0.0265950773 0.0543713458 0.0080878328 0.1544530000 958239601 0 402718720 -0.0302163884 0.2354952544 2.2420113087 331 13.2000000000 0.0106961019 0.0265470442 0.0543713458 0.0080761525 0.1589160000 958241609 0 402718720 -0.0319952667 0.2364433706 2.2522411346 332 13.2400000000 0.0106413132 0.0264991353 0.0543713458 0.0080653739 0.1579940000 958243617 0 402718720 -0.0338654406 0.2372237444 2.2611668110 333 13.2800000000 0.0105377557 0.0264512033 0.0543713458 0.0080537116 0.1599080000 958245625 0 402718720 -0.0360244997 0.2378066331 2.2710487843 334 13.3200000000 0.0104520265 0.0264033015 0.0543713458 0.0080428059 0.1608250000 958247633 0 402718720 -0.0383411981 0.2380527407 2.2795486450 335 13.3600000000 0.0103352992 0.0263553374 0.0543713458 0.0080308178 0.1613800000 958249641 0 402718720 -0.0404479280 0.2392802835 2.2884421349 336 13.4000000000 0.0102059813 0.0263072738 0.0543713458 0.0080188947 0.1618690000 958251649 0 402718720 -0.0419669226 0.2414154708 2.2964007854 337 13.4400000000 0.0100756558 0.0262591088 0.0543713458 0.0080183802 0.1625520000 958253657 0 402718720 -0.0436961986 0.2440278679 2.3039538860 338 13.4800000000 0.0099257566 0.0262107852 0.0543713458 0.0080258413 0.1647950000 958255665 0 402718720 -0.0455402173 0.2458830774 2.3102710247 339 13.5200000000 0.0098262830 0.0261624534 0.0543713458 0.0080434163 0.1675660000 958257673 0 402718720 -0.0479755104 0.2460687310 2.3158872128 340 13.5600000000 0.0097469818 0.0261141726 0.0543713458 0.0080402556 0.1693100000 958259681 0 402718720 -0.0503618121 0.2466281950 2.3210015297 341 13.6000000000 0.0097030858 0.0260660462 0.0543713458 0.0080338090 0.1691070000 958261689 0 402718720 -0.0525281578 0.2472007275 2.3258349895 342 13.6400000000 0.0096124792 0.0260179364 0.0543713458 0.0080259959 0.1706480000 958263697 0 402718720 -0.0546639748 0.2477062643 2.3315343857 343 13.6800000000 0.0095488280 0.0259699215 0.0543713458 0.0080144478 0.1718130000 958265705 0 402718720 -0.0566425212 0.2481161058 2.3364052773 344 13.7200000000 0.0095148450 0.0259220869 0.0543713458 0.0080028346 0.1722130000 958267713 0 402718720 -0.0577401519 0.2498544306 2.3419504166 345 13.7600000000 0.0094453143 0.0258743282 0.0543713458 0.0079952575 0.1728080000 958269721 0 402718720 -0.0596662164 0.2498503625 2.3474686146 346 13.8000000000 0.0093967542 0.0258267051 0.0543713458 0.0079900329 0.1727860000 958271729 0 402718720 -0.0613404214 0.2498237193 2.3525402546 347 13.8400000000 0.0093293898 0.0257791624 0.0543713458 0.0079791269 0.1755170000 958273737 0 402718720 -0.0636758655 0.2485855967 2.3570914268 348 13.8800000000 0.0092758508 0.0257317391 0.0543713458 0.0079684499 0.1750060000 958275745 0 402718720 -0.0642622486 0.2508731484 2.3628616333 349 13.9200000000 0.0091810860 0.0256843161 0.0543713458 0.0079662190 0.1753600000 958277753 0 402718720 -0.0659343153 0.2506911457 2.3686351776 350 13.9600000000 0.0091063762 0.0256369505 0.0543713458 0.0079572570 0.1756870000 958279761 0 402718720 -0.0679522976 0.2493997812 2.3774631023 351 14.0000000000 0.0091028819 0.0255898449 0.0543713458 0.0079466868 0.1758160000 958281769 0 402718720 -0.0680305660 0.2501262128 2.3817570210 352 14.0400000000 0.0093067782 0.0255435862 0.0543713458 0.0079378606 0.1715650000 958283777 0 402718720 -0.0687059388 0.2495533973 2.3866786957 353 14.0800000000 0.0092618894 0.0254974624 0.0543713458 0.0079265888 0.1691740000 958285785 0 402718720 -0.0690747350 0.2486477792 2.3909604549 354 14.1200000000 0.0090415366 0.0254509767 0.0543713458 0.0079154609 0.1734580000 958287793 0 402718720 -0.0687057376 0.2494286150 2.3955917358 355 14.1600000000 0.0092148902 0.0254052413 0.0543713458 0.0079045776 0.1693660000 958289801 0 402718720 -0.0693526268 0.2478671223 2.4005916119 356 14.2000000000 0.0090096239 0.0253591862 0.0543713458 0.0078952638 0.1760270000 958291809 0 402718720 -0.0690049380 0.2479448318 2.4050633907 357 14.2400000000 0.0089793047 0.0253133042 0.0543713458 0.0078846301 0.1764690000 958293817 0 402718720 -0.0686783716 0.2484802455 2.4106776714 358 14.2800000000 0.0090907486 0.0252679898 0.0543713458 0.0078744722 0.1711090000 958295825 0 402718720 -0.0690796077 0.2470212728 2.4162666798 359 14.3200000000 0.0090037026 0.0252226853 0.0543713458 0.0078647719 0.1724610000 958297833 0 402718720 -0.0696998760 0.2453663796 2.4217228889 360 14.3600000000 0.0090355547 0.0251777211 0.0543713458 0.0078562232 0.1724270000 958299841 0 402718720 -0.0698841438 0.2440496385 2.4278888702 361 14.4000000000 0.0090187145 0.0251329593 0.0543713458 0.0078517945 0.1726810000 958301849 0 402718720 -0.0700224862 0.2439462841 2.4343659878 362 14.4400000000 0.0089683644 0.0250883057 0.0543713458 0.0078449893 0.1729080000 958303857 0 402718720 -0.0700579956 0.2442351133 2.4409203529 363 14.4800000000 0.0089543955 0.0250438597 0.0543713458 0.0078345054 0.1732460000 958305865 0 402718720 -0.0699592084 0.2451313138 2.4481098652 364 14.5200000000 0.0085631656 0.0249985831 0.0543713458 0.0078249021 0.1688240000 958307873 0 402718720 -0.0702378005 0.2448127121 2.4549765587 365 14.5600000000 0.0086526647 0.0249537997 0.0543713458 0.0078142632 0.1733640000 958309881 0 402718720 -0.0708676651 0.2440078706 2.4622886181 366 14.6000000000 0.0087341247 0.0249094837 0.0543713458 0.0078038620 0.1737690000 958311889 0 402718720 -0.0710474700 0.2447351366 2.4702007771 367 14.6400000000 0.0082303369 0.0248640364 0.0543713458 0.0077936230 0.1694890000 958313897 0 402718720 -0.0708758608 0.2459495962 2.4767858982 368 14.6800000000 0.0082427450 0.0248188698 0.0543713458 0.0077841190 0.1738220000 958315905 0 402718720 -0.0711422488 0.2467775196 2.4848420620 369 14.7200000000 0.0083222911 0.0247741637 0.0543713458 0.0077830575 0.1785170000 958317913 0 402718720 -0.0720007047 0.2465128899 2.4924650192 370 14.7600000000 0.0082712630 0.0247295612 0.0543713458 0.0077806077 0.1789260000 958319921 0 402718720 -0.0722355247 0.2469689697 2.5003643036 371 14.8000000000 0.0082286699 0.0246850844 0.0543713458 0.0077741561 0.1791760000 958321929 0 402718720 -0.0723228231 0.2467473000 2.5076129436 372 14.8400000000 0.0081916442 0.0246407472 0.0543713458 0.0077699327 0.1799540000 958323937 0 402718720 -0.0725549161 0.2463136017 2.5146615505 373 14.8800000000 0.0081576491 0.0245965566 0.0543713458 0.0077696209 0.1807460000 958325945 0 402718720 -0.0727128237 0.2461783439 2.5220098495 374 14.9200000000 0.0081201550 0.0245525021 0.0543713458 0.0077655716 0.1811420000 958327953 0 402718720 -0.0729152113 0.2455466241 2.5293576717 375 14.9600000000 0.0080856355 0.0245085904 0.0543713458 0.0077685368 0.1824110000 958329961 0 402718720 -0.0726836994 0.2451719940 2.5363373756 376 15.0000000000 0.0080473451 0.0244648105 0.0543713458 0.0077680804 0.1829330000 958331969 0 402718720 -0.0717183724 0.2465142161 2.5437400341 377 15.0400000000 0.0079974215 0.0244211304 0.0543713458 0.0077605904 0.1892240000 958333977 0 402718720 -0.0694710091 0.2476965338 2.5569458008 378 15.0800000000 0.0079177208 0.0243774706 0.0543713458 0.0077503536 0.1909760000 958335985 0 402718720 -0.0675353557 0.2489470840 2.5634014606 379 15.1200000000 0.0078447610 0.0243338487 0.0543713458 0.0077401382 0.1876620000 958337993 0 402718720 -0.0656514019 0.2495110482 2.5690584183 380 15.1600000000 0.0077953739 0.0242903264 0.0543713458 0.0077310675 0.1870120000 958340001 0 402718720 -0.0628979653 0.2506605685 2.5744106770 381 15.2000000000 0.0077751721 0.0242469795 0.0543713458 0.0077211336 0.2285740000 958342009 0 402718720 -0.0605446212 0.2516937852 2.5795047283 382 15.2400000000 0.0077421912 0.0242037733 0.0543713458 0.0077124930 0.1954770000 958344017 0 402718720 -0.0583212674 0.2521788180 2.5843105316 383 15.2800000000 0.0076948199 0.0241606690 0.0543713458 0.0077031264 0.1965370000 958346025 0 402718720 -0.0556485429 0.2532294989 2.5888204575 384 15.3200000000 0.0076458105 0.0241176615 0.0543713458 0.0076930998 0.1975700000 958348033 0 402718720 -0.0528333597 0.2539519668 2.5926284790 385 15.3600000000 0.0076200231 0.0240748105 0.0543713458 0.0076838066 0.1986070000 958350041 0 402718720 -0.0503236204 0.2535643578 2.5951991081 386 15.4000000000 0.0075797657 0.0240320772 0.0543713458 0.0076802342 0.1993980000 958352049 0 402718720 -0.0472720228 0.2542541325 2.5973362923 387 15.4400000000 0.0075279432 0.0239894309 0.0543713458 0.0076801170 0.1999300000 958354057 0 402718720 -0.0435769260 0.2564105093 2.5994656086 388 15.4800000000 0.0074712918 0.0239468584 0.0543713458 0.0076705509 0.2000740000 958356065 0 402718720 -0.0405473225 0.2577004731 2.6003682613 389 15.5200000000 0.0074192518 0.0239043710 0.0543713458 0.0076611404 0.2001360000 958358073 0 402718720 -0.0379250310 0.2578665018 2.6013364792 390 15.5600000000 0.0073399274 0.0238618980 0.0543713458 0.0076513662 0.1995910000 958360081 0 402718720 -0.0340552740 0.2609760463 2.6024999619 391 15.6000000000 0.0073140524 0.0238195762 0.0543713458 0.0076564271 0.1992930000 958362089 0 402718720 -0.0308699533 0.2613320053 2.6038408279 392 15.6400000000 0.0072094062 0.0237772033 0.0543713458 0.0076472527 0.1968790000 958364097 0 402718720 -0.0280340351 0.2611343265 2.6041755676 393 15.6800000000 0.0069881738 0.0237344831 0.0543713458 0.0076382018 0.1936620000 958366105 0 402718720 -0.0258741844 0.2596040666 2.6045036316 394 15.7200000000 0.0066243303 0.0236910563 0.0543713458 0.0076306592 0.1921250000 958368113 0 402718720 -0.0239031706 0.2577119470 2.6049304008 395 15.7600000000 0.0072145914 0.0236493438 0.0543713458 0.0076344065 0.2053240000 958370121 0 402718720 -0.0206187684 0.2579762936 2.6063609123 396 15.8000000000 0.0084177731 0.0236108802 0.0543713458 0.0076284153 0.2046600000 958372129 0 402718720 -0.0171160139 0.2580712438 2.6083288193 397 15.8400000000 0.0379681587 0.0236470446 0.0543713458 0.0077496056 0.2132850000 958374137 0 402718720 -0.0150511544 0.2576724589 2.6395940781 398 15.8800000000 0.0672416463 0.0237565788 0.0672416463 0.0078549365 0.2199400000 958376145 0 402718720 -0.0126979901 0.2558420002 2.6684799194 399 15.9200000000 0.1077010036 0.0239669658 0.1077010036 0.0080905190 0.2171560000 958378153 0 402718720 -0.0090955831 0.2580007315 2.7075743675 400 15.9600000000 0.1069175005 0.0241743422 0.1077010036 0.0080840485 0.2290060000 958380161 0 402718720 -0.0047884071 0.2588123083 2.7073018551 401 16.0000000000 0.1046952084 0.0243751423 0.1077010036 0.0080797241 0.2123300000 958382169 0 402718720 -0.0002065643 0.2593980730 2.7057349682 402 16.0400000000 0.1038197577 0.0245727658 0.1077010036 0.0080721897 0.2059460000 958384177 0 402718720 0.0053655533 0.2599347234 2.7051498890 403 16.0800000000 0.1031551883 0.0247677594 0.1077010036 0.0080674533 0.2010670000 958386185 0 402718720 0.0100164302 0.2594370544 2.7061259747 404 16.1200000000 0.1026187837 0.0249604599 0.1077010036 0.0080592919 0.1959910000 958388193 0 402718720 0.0149709499 0.2598483264 2.7047266960 405 16.1600000000 0.1021858603 0.0251511399 0.1077010036 0.0080513126 0.1902830000 958390201 0 402718720 0.0203792416 0.2602766752 2.7058506012 406 16.2000000000 0.1019271761 0.0253402435 0.1077010036 0.0080430491 0.1818900000 958392209 0 402718720 0.0262528174 0.2619216442 2.7082297802 407 16.2400000000 0.1015616357 0.0255275196 0.1077010036 0.0080357014 0.1766640000 958394217 0 402718720 0.0313489847 0.2626655996 2.7098760605 408 16.2800000000 0.1012833193 0.0257131956 0.1077010036 0.0080375587 0.1746980000 958396225 0 402718720 0.0366035178 0.2631741762 2.7124733925 409 16.3200000000 0.1010363847 0.0258973599 0.1077010036 0.0080400924 0.1739870000 958398233 0 402718720 0.0432178341 0.2666608989 2.7148518562 410 16.3600000000 0.1008420512 0.0260801518 0.1077010036 0.0080319996 0.1730920000 958400241 0 402718720 0.0493239947 0.2696871161 2.7190625668 411 16.3999999990 0.1007269025 0.0262617741 0.1077010036 0.0080268612 0.1716530000 958402249 0 402718720 0.0527374744 0.2682823837 2.7206215858 412 16.4400000000 0.1005722508 0.0264421393 0.1077010036 0.0080423484 0.1701120000 958404257 0 402718720 0.0578295775 0.2680927813 2.7267222404 413 16.4800000000 0.1004041433 0.0266212240 0.1077010036 0.0080563466 0.1709770000 958406265 0 402718720 0.0639829487 0.2694447339 2.7333424091 414 16.5200000000 0.1003213599 0.0267992437 0.1077010036 0.0080529521 0.1692960000 958408273 0 402718720 0.0687209666 0.2672782838 2.7368144989 415 16.5599999990 0.1002449840 0.0269762214 0.1077010036 0.0080665237 0.1668100000 958410281 0 402718720 0.0718000457 0.2614152133 2.7423176765 416 16.6000000000 0.0999429002 0.0271516221 0.1077010036 0.0081428048 0.1640230000 958412289 0 402718720 0.0780242234 0.2612913847 2.7477023602 417 16.6400000000 0.0995952785 0.0273253478 0.1077010036 0.0081724575 0.1611710000 958414297 0 402718720 0.0842360780 0.2626343369 2.7489573956 418 16.6800000000 0.0993146896 0.0274975712 0.1077010036 0.0081754961 0.1587930000 958416305 0 402718720 0.0863905475 0.2590079606 2.7480847836 419 16.7199999990 0.0989439264 0.0276680875 0.1077010036 0.0082034345 0.1564590000 958418313 0 402718720 0.0940014645 0.2615845501 2.7533600330 420 16.7600000000 0.0981503725 0.0278359025 0.1077010036 0.0081941427 0.1523780000 958420321 0 402718720 0.1012868658 0.2622198462 2.7524535656 421 16.8000000000 0.0978077427 0.0280021064 0.1077010036 0.0082052942 0.1502190000 958422329 0 402718720 0.1052278355 0.2561762035 2.7529749870 422 16.8400000000 0.2164842784 0.0284487466 0.2164842784 0.0087573721 0.1637890000 958424337 0 402718720 0.1116168723 0.4184527695 2.8013174534 423 16.8799999990 0.3064228892 0.0291058959 0.3064228892 0.0089024757 0.1745800000 958426345 0 402718720 0.1196577698 0.5134394169 2.8229439259 424 16.9200000000 0.4143117368 0.0300144002 0.4143117368 0.0091260525 0.1909190000 958428353 0 402718720 0.1253564656 0.6223554611 2.8422365189 425 16.9600000000 0.4543263316 0.0310127812 0.4543263316 0.0091565564 0.1884500000 958430361 0 402718720 0.1340449452 0.6639083624 2.8470842838 426 17.0000000000 0.4970028102 0.0321066545 0.4970028102 0.0091630778 0.1874340000 958432369 0 402718720 0.1407660246 0.7083405852 2.8516187668 427 17.0400000000 0.6375250816 0.0335244963 0.6375250816 0.0096864005 0.1976310000 958434377 0 402718720 0.1520375907 0.8520599008 2.8554396629 428 17.0800000000 0.6677898765 0.0350064247 0.6677898765 0.0096788499 0.1983850000 958436385 0 402718720 0.1579040736 0.8811005950 2.8554213047 429 17.1200000000 0.6766602993 0.0365021214 0.6766602993 0.0096677231 0.1955210000 958438393 0 402718720 0.1693112105 0.8888182640 2.8552491665 430 17.1600000000 0.6723045707 0.0379807318 0.6766602993 0.0096585069 0.1904290000 958440401 0 402718720 0.1779180616 0.8804730177 2.8483247757 431 17.2000000000 0.6676845551 0.0394417615 0.6766602993 0.0096497671 0.1863170000 958442409 0 402718720 0.1887968779 0.8706528544 2.8466553688 432 17.2400000000 0.6669850945 0.0408944081 0.6766602993 0.0096522039 0.1835630000 958444417 0 402718720 0.2040872574 0.8681308031 2.8429181576 433 17.2800000000 0.6620241404 0.0423288879 0.6766602993 0.0096471963 0.1783360000 958446425 0 402718720 0.2180811167 0.8609803319 2.8386242390 434 17.3200000000 0.6620546579 0.0437568274 0.6766602993 0.0096401961 0.1737140000 958448433 0 402718720 0.2291030735 0.8554016948 2.8327281475 435 17.3600000000 0.6593893766 0.0451720747 0.6766602993 0.0096546121 0.1689450000 958450441 0 402718720 0.2405420840 0.8515878916 2.8275840282 436 17.4000000000 0.6547519565 0.0465701937 0.6766602993 0.0096654437 0.1657050000 958452449 0 402718720 0.2556383014 0.8510396481 2.8191745281 437 17.4400000000 0.6511346102 0.0479536363 0.6766602993 0.0096547044 0.1623590000 958454457 0 402718720 0.2725613713 0.8533313274 2.8089103699 438 17.4800000000 0.6493772864 0.0493267496 0.6766602993 0.0097018138 0.1625800000 958456465 0 402718720 0.2855374813 0.8526939154 2.8008511066 439 17.5200000000 0.6465955377 0.0506872708 0.6766602993 0.0097763078 0.1628880000 958458473 0 402718720 0.2926705182 0.8434695005 2.7922971249 440 17.5600000000 0.6431427598 0.0520337605 0.6766602993 0.0097891606 0.1610360000 958460481 0 402718720 0.2987236083 0.8300070763 2.7871272564 441 17.6000000000 0.6413158178 0.0533700010 0.6766602993 0.0097874028 0.1579030000 958462489 0 402718720 0.3072825670 0.8200765252 2.7824177742 442 17.6400000000 0.6381736994 0.0546930863 0.6766602993 0.0098433870 0.1532940000 958464497 0 402718720 0.3212347925 0.8175696135 2.7735698223 443 17.6800000000 0.6325008273 0.0559973927 0.6766602993 0.0098867661 0.1489010000 958466505 0 402718720 0.3422897458 0.8163177967 2.7544577122 444 17.7200000000 0.6286317110 0.0572871097 0.6766602993 0.0098775017 0.1448090000 958468513 0 402718720 0.3524335921 0.8111562133 2.7443156242 445 17.7600000000 0.6249302626 0.0585627122 0.6766602993 0.0098690578 0.1446330000 958470521 0 402718720 0.3602403104 0.8043087125 2.7367010117 446 17.8000000000 0.6209684610 0.0598237117 0.6766602993 0.0098602667 0.1424110000 958472529 0 402718720 0.3681549132 0.8003340960 2.7273030281 447 17.8400000000 0.6206429601 0.0610783409 0.6766602993 0.0098512720 0.1402030000 958474537 0 402718720 0.3758040369 0.7964230180 2.7210471630 448 17.8800000000 0.6182619929 0.0623220544 0.6766602993 0.0098424690 0.1371760000 958476545 0 402718720 0.3838435709 0.7915126681 2.7147965431 449 17.9200000000 0.6162717938 0.0635557955 0.6766602993 0.0098346260 0.1347660000 958478553 0 402718720 0.3921147883 0.7870008945 2.7078366280 450 17.9600000000 0.6153202057 0.0647819386 0.6766602993 0.0098274150 0.1316600000 958480561 0 402718720 0.4005588889 0.7807851434 2.7043735981 451 18.0000000000 0.6140547395 0.0659998384 0.6766602993 0.0098298622 0.1289670000 958482569 0 402718720 0.4106417000 0.7787883282 2.6993222237 452 18.0400000000 0.6118915677 0.0672075634 0.6766602993 0.0098243373 0.1266590000 958484577 0 402718720 0.4204167426 0.7766171098 2.6926865578 453 18.0800000000 0.6106269360 0.0684071647 0.6766602993 0.0098146950 0.1246000000 958486585 0 402718720 0.4293977320 0.7712247968 2.6877613068 454 18.1200000000 0.6079069376 0.0695954902 0.6766602993 0.0098143399 0.1228550000 958488593 0 402718720 0.4374539256 0.7679019570 2.6815350056 455 18.1600000000 0.6061723232 0.0707747799 0.6766602993 0.0098066950 0.1214840000 958490601 0 402718720 0.4496566355 0.7649524808 2.6763966084 456 18.2000000000 0.6052181125 0.0719468048 0.6766602993 0.0097991660 0.1175380000 958492609 0 402718720 0.4601990879 0.7600710392 2.6715304852 457 18.2400000000 0.6032233834 0.0731093356 0.6766602993 0.0097992957 0.1159310000 958494617 0 402718720 0.4700167179 0.7550992370 2.6667275429 458 18.2800000000 0.6019946337 0.0742641070 0.6766602993 0.0098107794 0.1148110000 958496625 0 402718720 0.4805650413 0.7556632161 2.6624324322 459 18.3200000000 0.5980879664 0.0754053354 0.6766602993 0.0098071581 0.1144430000 958498633 0 402718720 0.4940378070 0.7548884749 2.6536233425 460 18.3600000000 0.5962690115 0.0765376478 0.6766602993 0.0098000574 0.1144260000 958500641 0 402718720 0.5020139217 0.7488304973 2.6500508785 461 18.4000000000 0.5951066017 0.0776625262 0.6766602993 0.0097923195 0.1156950000 958502649 0 402718720 0.5155504346 0.7454468608 2.6476707458 462 18.4400000000 0.5935953259 0.0787792639 0.6766602993 0.0097846354 0.1136180000 958504657 0 402718720 0.5269256234 0.7446263433 2.6422977448 463 18.4800000000 0.5910252929 0.0798856268 0.6766602993 0.0097746632 0.1149030000 958506665 0 402718720 0.5371680856 0.7400315404 2.6355228424 464 18.5200000000 0.5932219028 0.0809919550 0.6766602993 0.0097699908 0.1157690000 958508673 0 402718720 0.5460996032 0.7369893193 2.6370022297 465 18.5600000000 0.5914549232 0.0820897248 0.6766602993 0.0097651202 0.1133650000 958510681 0 402718720 0.5550720096 0.7311071754 2.6340212822 466 18.6000000000 0.5909745693 0.0831817523 0.6766602993 0.0097747080 0.1202840000 958512689 0 402718720 0.5673607588 0.7313565612 2.6316645145 467 18.6400000000 0.5912669897 0.0842697293 0.6766602993 0.0097679929 0.1139540000 958514697 0 402718720 0.5831151009 0.7289835811 2.6312522888 468 18.6800000000 0.5966431499 0.0853645443 0.6766602993 0.0097681168 0.1168940000 958516705 0 402718720 0.5980602503 0.7258270383 2.6428263187 469 18.7200000000 0.5806007981 0.0864204851 0.6766602993 0.0098166048 0.1342710000 958518713 0 402718720 0.6079410315 0.7003440261 2.6542897224 470 18.7600000000 0.5954930186 0.0875036182 0.6766602993 0.0101808958 0.1428850000 958520721 0 402718720 0.5904757380 0.6866487265 2.7036879063 471 18.8000000000 0.7077965736 0.0888205884 0.7077965736 0.0104662447 0.1487470000 958522729 0 402718720 0.6001593471 0.7703119516 2.7768852711 472 18.8400000000 0.7326445580 0.0901846222 0.7326445580 0.0105183545 0.1499060000 958524737 0 402718720 0.6075527072 0.7776538730 2.8076767921 473 18.8800000000 0.7378602028 0.0915539152 0.7378602028 0.0105169854 0.1490130000 958526745 0 402718720 0.6282329559 0.7786118984 2.8115143776 474 18.9200000000 0.7378888130 0.0929174909 0.7378888130 0.0105121685 0.1478930000 958528753 0 402718720 0.6388196945 0.7763482928 2.8052847385 475 18.9600000000 0.7256968021 0.0942496579 0.7378888130 0.0105413157 0.1367090000 958530761 0 402718720 0.6365446448 0.7673098445 2.7918798923 476 19.0000000000 0.7614318132 0.0956513011 0.7614318132 0.0106395881 0.1391260000 958532769 0 402718720 0.6319457293 0.7840078473 2.8262369633 477 19.0400000000 0.7716245651 0.0970684358 0.7716245651 0.0106547054 0.1474290000 958534777 0 402718720 0.6176512241 0.7869496346 2.8295872211 478 19.0800000000 0.8097423315 0.0985593854 0.8097423315 0.0108642537 0.1441210000 958536785 0 402718720 0.5872240663 0.8006883860 2.8704276085 479 19.1200000000 0.8058015108 0.1000358825 0.8097423315 0.0108599502 0.1530090000 958538793 0 402718720 0.5911493897 0.7952292562 2.8657288551 480 19.1600000000 0.8025649190 0.1014994847 0.8097423315 0.0108678932 0.1390870000 958540801 0 402718720 0.5995859504 0.7907126546 2.8651704788 481 19.2000000000 0.8674510121 0.1030918995 0.8674510121 0.0114569350 0.1561580000 958542809 0 402718720 0.4965201616 0.8111242056 2.9086933136 482 19.2400000000 1.4368636608 0.1058590608 1.4368636608 0.0235940759 0.1885910000 958544817 0 402718720 0.4851211607 1.5388752222 2.7346234322 483 19.2800000000 1.4507864714 0.1086435896 1.4507864714 0.0235784659 0.1837820000 958546825 0 402718720 0.4842914641 1.5467787981 2.7440009117 484 19.3200000000 1.4376766682 0.1113895257 1.4507864714 0.0235643865 0.1822010000 958548833 0 402718720 0.4976743758 1.5333976746 2.7413144112 485 19.3600000000 1.4255775213 0.1140991917 1.4507864714 0.0235507740 0.1817590000 958550841 0 402718720 0.5063248277 1.5235629082 2.7371418476 486 19.4000000000 1.4431166649 0.1168337955 1.4507864714 0.0235445126 0.1827320000 958552849 0 402718720 0.4943773150 1.5412249565 2.7352387905 487 19.4400000000 1.5776183605 0.1198333532 1.5776183605 0.0239534439 0.1976580000 958554857 0 402718720 0.4908845127 1.6893228292 2.6827273369 488 19.4800000000 1.5874290466 0.1228407214 1.5874290466 0.0239366852 0.2025520000 958556865 0 402718720 0.4880694449 1.6948924065 2.6824755669 489 19.5200000000 1.5780854225 0.1258166819 1.5874290466 0.0239166012 0.2018460000 958558873 0 402718720 0.5000924468 1.6859788895 2.6774847507 490 19.5600000000 1.5630601645 0.1287498319 1.5874290466 0.0239014232 0.2081340000 958560881 0 402718720 0.5065608025 1.6703671217 2.6671280861 491 19.6000000000 1.6205284595 0.1317880776 1.6205284595 0.0241906106 0.2022360000 958562889 0 402718720 0.3674162924 1.6959332228 2.6749436855 492 19.6400000000 1.6226840019 0.1348183538 1.6226840019 0.0241921225 0.2176730000 958564897 0 402718720 0.2970114946 1.6799986362 2.6571738720 493 19.6800000000 1.7958225012 0.1381875306 1.7958225012 0.0270200167 0.2228920000 958566905 0 402718720 -0.0699400902 1.6926870346 2.7344470024 494 19.7200000000 1.9147015810 0.1417837129 1.9147015810 0.0279047186 0.2220030000 958568913 0 402718720 -0.2872314155 1.6883485317 2.7559194565 495 19.7600000000 1.9033168554 0.1453423657 1.9147015810 0.0278968762 0.2250380000 958570921 0 402718720 -0.3070433438 1.6596179008 2.7368180752 496 19.8000000000 1.8969782591 0.1488738897 1.9147015810 0.0278821290 0.2247060000 958572929 0 402718720 -0.3189377785 1.6471735239 2.7187006474 497 19.8400000000 1.8911588192 0.1523794932 1.9147015810 0.0278620617 0.2257030000 958574937 0 402718720 -0.3287816942 1.6293638945 2.7045204639 498 19.8800000000 1.8821986914 0.1558530257 1.9147015810 0.0278438215 0.2247310000 958576945 0 402718720 -0.3320360184 1.6163054705 2.6904115677 499 19.9200000000 1.8787153959 0.1593056557 1.9147015810 0.0278237432 0.2288720000 958578953 0 402718720 -0.3378001451 1.6067126989 2.6792652607 500 19.9600000000 1.8730956316 0.1627332357 1.9147015810 0.0278022176 0.2311180000 958580961 0 402718720 -0.3343869448 1.6003171206 2.6700019836 501 20.0000000000 1.8663418293 0.1661336520 1.9147015810 0.0277786884 0.2336430000 958582969 0 402718720 -0.3259375691 1.5940190554 2.6643545628 502 20.0400000000 1.8617244959 0.1695113230 1.9147015810 0.0277566734 0.2345810000 958584977 0 402718720 -0.3218592405 1.5856456757 2.6601967812 503 20.0800000000 1.8541197777 0.1728604452 1.9147015810 0.0277377596 0.2330620000 958586985 0 402718720 -0.3151836097 1.5781267881 2.6516549587 504 20.1200000000 1.8495767117 0.1761872632 1.9147015810 0.0277117744 0.2345850000 958588993 0 402718720 -0.3098924756 1.5721670389 2.6465234756 505 20.1600000000 1.9042814970 0.1796092320 1.9147015810 0.0277901809 0.2456640000 958591001 0 402718720 -0.3885735273 1.5811275244 2.6406602859 506 20.2000000000 1.9049212933 0.1830189396 1.9147015810 0.0277689011 0.2385740000 958593009 0 402718720 -0.3848472536 1.5865775347 2.6353659630 507 20.2400000000 1.8844991922 0.1863749164 1.9147015810 0.0277584530 0.2387870000 958595017 0 402718720 -0.3605249822 1.5792434216 2.6258471012 508 20.2800000000 1.8811577559 0.1897111031 1.9147015810 0.0277311754 0.2374680000 958597025 0 402718720 -0.3684087694 1.5717605352 2.6169533730 509 20.3200000000 1.8788626194 0.1930296719 1.9147015810 0.0277050994 0.2462430000 958599033 0 402718720 -0.3648831248 1.5670335293 2.6084799767 510 20.3600000000 1.8718740940 0.1963215237 1.9147015810 0.0276848504 0.2355350000 958601041 0 402718720 -0.3516658843 1.5633687973 2.6012129784 511 20.4000000000 1.8485687971 0.1995548843 1.9147015810 0.0276881653 0.2330330000 958603049 0 402718720 -0.3248010278 1.5562355518 2.5865197182 512 20.4400000000 1.9000808001 0.2028762240 1.9147015810 0.0277330390 0.2411520000 958605057 0 402718720 -0.3798398077 1.5835208893 2.5739722252 513 20.4800000000 1.8739162683 0.2061336120 1.9147015810 0.0277171896 0.2379930000 958607065 0 402718720 -0.3498192728 1.5622215271 2.5782823563 514 20.5200000000 1.8800354004 0.2093902303 1.9147015810 0.0276952395 0.2413480000 958711473 0 402718720 -0.3650525212 1.5572298765 2.5699729919 515 20.5600000000 1.8512213230 0.2125782518 1.9147015810 0.0277027516 0.2265430000 958713481 0 402718720 -0.3259105682 1.5478209257 2.5587117672 516 20.6000000000 1.8398283720 0.2157318373 1.9147015810 0.0276786838 0.2232540000 958715489 0 402718720 -0.3119441569 1.5390580893 2.5495591164 517 20.6400000000 1.8328622580 0.2188597492 1.9147015810 0.0276543129 0.2210380000 958717497 0 402718720 -0.3092111349 1.5338340998 2.5481522083 518 20.6800000000 1.8349069357 0.2219795314 1.9147015810 0.0276328672 0.2186620000 958719505 0 402718720 -0.2961466610 1.5309064388 2.5412282944 519 20.7200000000 1.8343191147 0.2250861587 1.9147015810 0.0276106422 0.2174300000 958721513 0 402718720 -0.3083395660 1.5324304104 2.5392889977 520 20.7600000000 1.8234386444 0.2281599135 1.9147015810 0.0275885296 0.2142010000 958723521 0 402718720 -0.3052308857 1.5299483538 2.5333933830 521 20.8000000000 1.8163102865 0.2312081867 1.9147015810 0.0275621718 0.2113340000 958725529 0 402718720 -0.3014124632 1.5229063034 2.5269184113 522 20.8400000000 1.8108077049 0.2342342395 1.9147015810 0.0275371457 0.2093800000 958727537 0 402718720 -0.2923040986 1.5164985657 2.5235273838 523 20.8800000000 1.8118159771 0.2372506481 1.9147015810 0.0275140368 0.2083740000 958729545 0 402718720 -0.3055638671 1.5159202814 2.5250737667 524 20.9200000000 1.8075996637 0.2402474974 1.9147015810 0.0275008160 0.2069040000 958731553 0 402718720 -0.2824573219 1.5106530190 2.5169575214 525 20.9600000000 1.8079359531 0.2432335707 1.9147015810 0.0274774221 0.2041770000 958733561 0 402718720 -0.2839634717 1.5081806183 2.5154552460 526 21.0000000000 1.8102223873 0.2462126368 1.9147015810 0.0274553099 0.2018440000 958735569 0 402718720 -0.2757922411 1.5039063692 2.5132446289 527 21.0400000000 1.8055201769 0.2491714747 1.9147015810 0.0274401567 0.2014910000 958737577 0 402718720 -0.2712081671 1.4995535612 2.5076687336 528 21.0800000000 1.8045009375 0.2521171744 1.9147015810 0.0274179943 0.2006830000 958739585 0 402718720 -0.2669159770 1.4978064299 2.5054149628 529 21.1200000000 1.8015687466 0.2550461944 1.9147015810 0.0274011111 0.2017810000 958741593 0 402718720 -0.2476811707 1.4919097424 2.4971027374 530 21.1600000000 1.7992851734 0.2579598529 1.9147015810 0.0273817643 0.2041790000 958743601 0 402718720 -0.2497182488 1.4906717539 2.4942464828 531 21.2000000000 1.7949014902 0.2608542816 1.9147015810 0.0273635212 0.2071700000 958745609 0 402718720 -0.2358917445 1.4848093987 2.4871332645 532 21.2400000000 1.7921197414 0.2637326001 1.9147015810 0.0273430981 0.2098410000 958747617 0 402718720 -0.2320309281 1.4812867641 2.4818584919 533 21.2800000000 1.7891530991 0.2665945522 1.9147015810 0.0273207800 0.2083600000 958749625 0 402718720 -0.2308391929 1.4777934551 2.4781248569 534 21.3200000000 1.7840309143 0.2694361934 1.9147015810 0.0273035898 0.2683280000 958751633 0 402718720 -0.2169245481 1.4710341692 2.4711039066 535 21.3600000000 1.7769390345 0.2722539557 1.9147015810 0.0272877386 0.2518210000 958753641 0 402718720 -0.2048580050 1.4666115046 2.4614505768 536 21.4000000000 1.7738023996 0.2750553520 1.9147015810 0.0272640516 0.2133530000 958755649 0 402718720 -0.2050817758 1.4628883600 2.4584891796 537 21.4400000000 1.7678128481 0.2778351612 1.9147015810 0.0272450887 0.2134530000 958757657 0 402718720 -0.1898875833 1.4552541971 2.4502677917 538 21.4800000000 1.7631340027 0.2805959397 1.9147015810 0.0272239527 0.2145220000 958759665 0 402718720 -0.1858228892 1.4508161545 2.4444878101 539 21.5200000000 1.7581616640 0.2833372490 1.9147015810 0.0272025537 0.2140660000 958761673 0 402718720 -0.1837032884 1.4460185766 2.4384334087 540 21.5600000000 1.7508460283 0.2860548578 1.9147015810 0.0271848177 0.2164120000 958763681 0 402718720 -0.1742191613 1.4403997660 2.4286589622 541 21.6000000000 1.7452321053 0.2887520431 1.9147015810 0.0271627721 0.2164470000 958765689 0 402718720 -0.1689369380 1.4372917414 2.4212157726 542 21.6400000000 1.7395727634 0.2914288341 1.9147015810 0.0271396051 0.2137370000 958767697 0 402718720 -0.1605091244 1.4295498133 2.4140489101 543 21.6800000000 1.7380256653 0.2940929167 1.9147015810 0.0271167950 0.2148110000 958769705 0 402718720 -0.1570781320 1.4252282381 2.4120678902 544 21.7200000000 1.7324069738 0.2967368764 1.9147015810 0.0270991770 0.2154620000 958771713 0 402718720 -0.1517847329 1.4209512472 2.4045989513 545 21.7600000000 1.7273769379 0.2993619040 1.9147015810 0.0270803170 0.2141460000 958773721 0 402718720 -0.1437697262 1.4145783186 2.3978755474 546 21.8000000000 1.7240325212 0.3019711908 1.9147015810 0.0270618526 0.2134320000 958775729 0 402718720 -0.1394591779 1.4122351408 2.3932852745 547 21.8400000000 1.7176482677 0.3045592659 1.9147015810 0.0270437844 0.2125530000 958777737 0 402718720 -0.1319146305 1.4078298807 2.3847696781 548 21.8800000000 1.7143737078 0.3071319200 1.9147015810 0.0270209841 0.2110850000 958779745 0 402718720 -0.1329609156 1.4052649736 2.3809754848 549 21.9200000000 1.7112330198 0.3096894812 1.9147015810 0.0269990324 0.2099870000 958781753 0 402718720 -0.1288366020 1.4013522863 2.3772921562 550 21.9600000000 1.7064989805 0.3122291349 1.9147015810 0.0269780123 0.2052280000 958783761 0 402718720 -0.1261333525 1.3996062279 2.3709990978 551 22.0000000000 1.7022142410 0.3147517939 1.9147015810 0.0269548062 0.2041370000 958785769 0 402718720 -0.1219290793 1.3956239223 2.3653986454 552 22.0400000000 1.6984182596 0.3172584360 1.9147015810 0.0269327921 0.2025760000 958787777 0 402718720 -0.1153399050 1.3931721449 2.3601765633 553 22.0800000000 1.6963692904 0.3197523074 1.9147015810 0.0269092202 0.2037240000 958789785 0 402718720 -0.1152384058 1.3912053108 2.3579277992 554 22.1200000000 1.6931743622 0.3222314085 1.9147015810 0.0268865788 0.2009690000 958791793 0 402718720 -0.1112818122 1.3861850500 2.3541915417 555 22.1600000000 1.6878861189 0.3246920477 1.9147015810 0.0268675228 0.1995750000 958793801 0 402718720 -0.1071347073 1.3842531443 2.3471920490 556 22.2000000000 1.6822082996 0.3271336237 1.9147015810 0.0268449792 0.1987360000 958795809 0 402718720 -0.1030396223 1.3818244934 2.3394815922 557 22.2400000000 1.6805014610 0.3295633684 1.9147015810 0.0268209773 0.1967800000 958797817 0 402718720 -0.1016259491 1.3771740198 2.3379652500 558 22.2800000000 1.6771541834 0.3319784057 1.9147015810 0.0267983379 0.1950330000 958799825 0 402718720 -0.1002795249 1.3712518215 2.3344244957 559 22.3200000000 1.6730808020 0.3343775156 1.9147015810 0.0267806141 0.1939610000 958801833 0 402718720 -0.0983198211 1.3703914881 2.3289165497 560 22.3600000000 1.6705467701 0.3367635321 1.9147015810 0.0267585680 0.1921600000 958803841 0 402718720 -0.0977477953 1.3681794405 2.3260562420 561 22.4000000000 1.6674250364 0.3391354777 1.9147015810 0.0267369093 0.1930410000 958805849 0 402718720 -0.0908879712 1.3638638258 2.3219544888 562 22.4400000000 1.6641311646 0.3414931213 1.9147015810 0.0267160584 0.1916730000 958807857 0 402718720 -0.0903291032 1.3623459339 2.3184568882 563 22.4800000000 1.6597696543 0.3438346427 1.9147015810 0.0266943806 0.1922660000 958809865 0 402718720 -0.0841942206 1.3581216335 2.3123743534 564 22.5200000000 1.6573544741 0.3461635785 1.9147015810 0.0266716816 0.1921220000 958811873 0 402718720 -0.0809683949 1.3535612822 2.3092851639 565 22.5600000000 1.6531717777 0.3484768674 1.9147015810 0.0266524724 0.1943800000 958813881 0 402718720 -0.0722152367 1.3464796543 2.3035881519 566 22.6000000000 1.6500755548 0.3507765117 1.9147015810 0.0266353968 0.1939550000 958815889 0 402718720 -0.0683416575 1.3423600197 2.2996952534 567 22.6400000000 1.6473630667 0.3530632605 1.9147015810 0.0266173343 0.1938640000 958817897 0 402718720 -0.0639961958 1.3390682936 2.2958946228 568 22.6800000000 1.6447221041 0.3553373077 1.9147015810 0.0265978675 0.1909210000 958819905 0 402718720 -0.0580413677 1.3335430622 2.2918293476 569 22.7200000000 1.6406447887 0.3575961961 1.9147015810 0.0265800283 0.1909540000 958821913 0 402718720 -0.0512504540 1.3274662495 2.2860145569 570 22.7600000000 1.6340098381 0.3598355183 1.9147015810 0.0265644867 0.1898990000 958823921 0 402718720 -0.0476437360 1.3239624500 2.2772223949 571 22.8000000000 1.6286247969 0.3620575661 1.9147015810 0.0265436664 0.1913800000 958825929 0 402718720 -0.0447083935 1.3204293251 2.2698268890 572 22.8400000000 1.6257355213 0.3642667933 1.9147015810 0.0265226075 0.1902370000 958827937 0 402718720 -0.0406261049 1.3127167225 2.2660582066 573 22.8800000000 1.6208069324 0.3664597080 1.9147015810 0.0265054704 0.1887100000 958829945 0 402718720 -0.0366343819 1.3071060181 2.2595560551 574 22.9200000000 1.6155599356 0.3686358408 1.9147015810 0.0264857922 0.1882850000 958831953 0 402718720 -0.0356760696 1.3039689064 2.2527136803 575 22.9600000000 1.6111379862 0.3707967141 1.9147015810 0.0264649256 0.1869510000 958833961 0 402718720 -0.0320730396 1.2961684465 2.2470786572 576 23.0000000000 1.6082519293 0.3729450738 1.9147015810 0.0264446550 0.1865040000 958835969 0 402718720 -0.0293011647 1.2892187834 2.2436702251 577 23.0400000000 1.6021497250 0.3750754112 1.9147015810 0.0264288041 0.1861760000 958837977 0 402718720 -0.0260895807 1.2854137421 2.2352149487 578 23.0800000000 1.5971609354 0.3771897460 1.9147015810 0.0264087153 0.1866640000 958839985 0 402718720 -0.0223888196 1.2796064615 2.2286195755 579 23.1200000000 1.5933976173 0.3792902777 1.9147015810 0.0263883841 0.1863330000 958841993 0 402718720 -0.0184657257 1.2727689743 2.2232952118 580 23.1600000000 1.5883636475 0.3813748870 1.9147015810 0.0263687735 0.1864520000 958844001 0 402718720 -0.0140818600 1.2663891315 2.2164433002 581 23.2000000000 1.5828677416 0.3834428609 1.9147015810 0.0263483641 0.1864070000 958846009 0 402718720 -0.0109165516 1.2613649368 2.2089397907 582 23.2400000000 1.5775364637 0.3854945681 1.9147015810 0.0263276031 0.1864850000 958848017 0 402718720 -0.0068235477 1.2535576820 2.2017462254 583 23.2800000000 1.5741282701 0.3875333910 1.9147015810 0.0263066483 0.1858910000 958850025 0 402718720 -0.0025691125 1.2462204695 2.1968159676 584 23.3200000000 1.5674362183 0.3895537725 1.9147015810 0.0262905288 0.1862430000 958852033 0 402718720 0.0010918108 1.2400746346 2.1877932549 585 23.3600000000 1.5616166592 0.3915572988 1.9147015810 0.0262720830 0.1861820000 958854041 0 402718720 0.0052909199 1.2333670855 2.1796126366 586 23.4000000000 1.5572572947 0.3935465480 1.9147015810 0.0262531210 0.1865370000 958856049 0 402718720 0.0102260876 1.2249187231 2.1734740734 587 23.4400000000 1.5522632599 0.3955205117 1.9147015810 0.0262384862 0.1864520000 958858057 0 402718720 0.0135737769 1.2191398144 2.1664302349 588 23.4800000000 1.5370841026 0.3974619464 1.9147015810 0.0262490170 0.1920060000 958860065 0 402718720 0.0241312254 1.2064075470 2.1444747448 589 23.5200000000 1.5310658216 0.3993865709 1.9147015810 0.0262301764 0.1910160000 958862073 0 402718720 0.0270557310 1.2020990849 2.1359314919 590 23.5600000000 1.5238479376 0.4012924377 1.9147015810 0.0262105353 0.1927520000 958864081 0 402718720 0.0304450560 1.1968748569 2.1258795261 591 23.6000000000 1.5189918280 0.4031836380 1.9147015810 0.0261901090 0.1924360000 958866089 0 402718720 0.0347564220 1.1889784336 2.1186752319 592 23.6400000000 1.5129427910 0.4050582312 1.9147015810 0.0261711510 0.1952520000 958868097 0 402718720 0.0403223075 1.1797382832 2.1096756458 593 23.6800000000 1.5063929558 0.4069154567 1.9147015810 0.0261544757 0.1958350000 958870105 0 402718720 0.0445817187 1.1729184389 2.1001331806 594 23.7200000000 1.5002946854 0.4087561624 1.9147015810 0.0261375386 0.1930560000 958872113 0 402718720 0.0488858372 1.1664522886 2.0910744667 595 23.7600000000 1.4953213930 0.4105823225 1.9147015810 0.0261196393 0.1940710000 958874121 0 402718720 0.0509436168 1.1603542566 2.0840451717 596 23.8000000000 1.4880462885 0.4123901479 1.9147015810 0.0261044449 0.1943520000 958876129 0 402718720 0.0554656163 1.1545488834 2.0732109547 597 23.8400000000 1.4812834263 0.4141805889 1.9147015810 0.0260866032 0.1960530000 958878137 0 402718720 0.0579563528 1.1497803926 2.0637354851 598 23.8800000000 1.4744018316 0.4159535341 1.9147015810 0.0260685143 0.1994810000 958880145 0 402718720 0.0628969967 1.1423045397 2.0534284115 599 23.9200000000 1.4675425291 0.4177091084 1.9147015810 0.0260497632 0.2015040000 958882153 0 402718720 0.0649936050 1.1379771233 2.0437777042 600 23.9600000000 1.4615441561 0.4194488335 1.9147015810 0.0260308968 0.2031350000 958884161 0 402718720 0.0685334504 1.1319950819 2.0346362591 601 24.0000000000 1.4554494619 0.4211726282 1.9147015810 0.0260125699 0.2038530000 958886169 0 402718720 0.0707689449 1.1258722544 2.0261380672 602 24.0400000000 1.4490237236 0.4228800221 1.9147015810 0.0259954069 0.2068930000 958888177 0 402718720 0.0749437883 1.1191347837 2.0162391663 603 24.0800000000 1.4433790445 0.4245723919 1.9147015810 0.0259769576 0.2081470000 958890185 0 402718720 0.0761587545 1.1139513254 2.0082955360 604 24.1200000000 1.4380531311 0.4262503402 1.9147015810 0.0259580658 0.2090670000 958892193 0 402718720 0.0770908669 1.1094551086 2.0007729530 605 24.1600000000 1.4334275723 0.4279150959 1.9147015810 0.0259390292 0.2107370000 958894201 0 402718720 0.0786564127 1.1036061049 1.9939837456 606 24.2000000000 1.4299659729 0.4295686452 1.9147015810 0.0259192376 0.2112610000 958896209 0 402718720 0.0801752210 1.0968847275 1.9890491962 607 24.2400000000 1.4237122536 0.4312064436 1.9147015810 0.0259010265 0.2122850000 958898217 0 402718720 0.0842993930 1.0894091129 1.9793694019 608 24.2800000000 1.4179121256 0.4328293148 1.9147015810 0.0258820124 0.2138040000 958900225 0 402718720 0.0856714472 1.0853822231 1.9711015224 609 24.3200000000 1.4144382477 0.4344411521 1.9147015810 0.0258630277 0.2149130000 958902233 0 402718720 0.0885665715 1.0780609846 1.9655447006 610 24.3600000000 1.4116928577 0.4360432041 1.9147015810 0.0258435624 0.2153700000 958904241 0 402718720 0.0907145217 1.0700842142 1.9611967802 611 24.4000000000 1.4056484699 0.4376301194 1.9147015810 0.0258267902 0.2179570000 958906249 0 402718720 0.0959426612 1.0621845722 1.9513670206 612 24.4400000000 1.4002978802 0.4392031060 1.9147015810 0.0258088913 0.2195030000 958908257 0 402718720 0.0976860896 1.0572247505 1.9433652163 613 24.4800000000 1.3969999552 0.4407655804 1.9147015810 0.0257887991 0.2200970000 958910265 0 402718720 0.0993659124 1.0510361195 1.9384416342 614 24.5200000000 1.3917508125 0.4423144163 1.9147015810 0.0257702164 0.2212550000 958912273 0 402718720 0.1039053202 1.0420335531 1.9297748804 615 24.5600000000 1.3882789612 0.4438525700 1.9147015810 0.0257508441 0.2213770000 958914281 0 402718720 0.1066849455 1.0363061428 1.9240087271 616 24.6000000000 1.3842952251 0.4453792627 1.9147015810 0.0257318584 0.2233230000 958916289 0 402718720 0.1106258333 1.0279743671 1.9172012806 617 24.6400000000 1.3797404766 0.4468936244 1.9147015810 0.0257144157 0.2234930000 958918297 0 402718720 0.1140579358 1.0207496881 1.9096003771 618 24.6800000000 1.3748571873 0.4483951836 1.9147015810 0.0256976551 0.2235750000 958920305 0 402718720 0.1191806123 1.0123784542 1.9010386467 619 24.7200000000 1.3685704470 0.4498817349 1.9147015810 0.0256827406 0.2235470000 958922313 0 402718720 0.1253885031 1.0036317110 1.8901399374 620 24.7600000000 1.3632085323 0.4513548427 1.9147015810 0.0256675585 0.2244650000 958924321 0 402718720 0.1270921826 0.9988582730 1.8821370602 621 24.8000000000 1.3587255478 0.4528159871 1.9147015810 0.0256496144 0.2239460000 958926329 0 402718720 0.1304432303 0.9927251935 1.8745014668 622 24.8400000000 1.3545416594 0.4542657068 1.9147015810 0.0256313890 0.2237510000 958928337 0 402718720 0.1338512450 0.9851900339 1.8671375513 623 24.8800000000 1.3490314484 0.4557019279 1.9147015810 0.0256153644 0.2257570000 958930345 0 402718720 0.1368857175 0.9795777202 1.8582127094 624 24.9200000000 1.3430315256 0.4571239305 1.9147015810 0.0255988108 0.2267990000 958932353 0 402718720 0.1395037472 0.9737558365 1.8486950397 625 24.9600000000 1.3387033939 0.4585344576 1.9147015810 0.0255814450 0.2258190000 958934361 0 402718720 0.1417678744 0.9665834904 1.8414660692 626 25.0000000000 1.3353041410 0.4599350482 1.9147015810 0.0255639026 0.2313240000 958936369 0 402718720 0.1445023566 0.9596067667 1.8352344036 627 25.0400000000 1.3302259445 0.4613230719 1.9147015810 0.0255488712 0.2268930000 958938377 0 402718720 0.1468406022 0.9535049200 1.8269823790 628 25.0800000000 1.3240962029 0.4626969145 1.9147015810 0.0255340651 0.2326400000 958940385 0 402718720 0.1479995102 0.9490448833 1.8176305294 629 25.1200000000 1.3207492828 0.4640610677 1.9147015810 0.0255159180 0.2276040000 958942393 0 402718720 0.1487755924 0.9444380403 1.8124321699 630 25.1600000000 1.3155004978 0.4654125589 1.9147015810 0.0254996788 0.2276940000 958944401 0 402718720 0.1498479247 0.9383522868 1.8042557240 631 25.2000000000 1.3099384308 0.4667509517 1.9147015810 0.0254835439 0.2259570000 958946409 0 402718720 0.1504043490 0.9336848855 1.7959668636 632 25.2400000000 1.3065392971 0.4680797307 1.9147015810 0.0254653585 0.2240350000 958948417 0 402718720 0.1498891413 0.9287227988 1.7909972668 633 25.2800000000 1.3003147840 0.4693944780 1.9147015810 0.0254497540 0.2263600000 958950425 0 402718720 0.1513469368 0.9229575396 1.7813516855 634 25.3200000000 1.2943032980 0.4706955961 1.9147015810 0.0254331297 0.2234620000 958952433 0 402718720 0.1504638344 0.9187556505 1.7728382349 635 25.3600000000 1.2903485298 0.4719863881 1.9147015810 0.0254154393 0.2175310000 958954441 0 402718720 0.1495886147 0.9147313833 1.7672635317 636 25.4000000000 1.2862788439 0.4732667221 1.9147015810 0.0253994005 0.2196850000 958956449 0 402718720 0.1508862078 0.9077954888 1.7603693008 637 25.4400000000 1.2815601826 0.4745356287 1.9147015810 0.0253828227 0.2185650000 958958457 0 402718720 0.1502481848 0.9032425284 1.7534470558 638 25.4800000000 1.2780317068 0.4757950269 1.9147015810 0.0253670803 0.2164800000 958960465 0 402718720 0.1510774195 0.8969953060 1.7474206686 639 25.5200000000 1.2745796442 0.4770450811 1.9147015810 0.0253505544 0.2148620000 958962473 0 402718720 0.1493054479 0.8909562230 1.7425247431 640 25.5600000000 1.2710454464 0.4782857066 1.9147015810 0.0253335824 0.2091190000 958964481 0 402718720 0.1485485733 0.8857548833 1.7373194695 641 25.6000000000 1.2669739723 0.4795161096 1.9147015810 0.0253164538 0.2081530000 958966489 0 402718720 0.1471832842 0.8801595569 1.7313587666 642 25.6400000000 1.2633256912 0.4807369968 1.9147015810 0.0252986881 0.2067290000 958968497 0 402718720 0.1447756141 0.8751805425 1.7264652252 643 25.6800000000 1.2596838474 0.4819484226 1.9147015810 0.0252809164 0.2061300000 958970505 0 402718720 0.1438085437 0.8690961003 1.7209606171 644 25.7200000000 1.2558248043 0.4831500940 1.9147015810 0.0252628505 0.2051430000 958972513 0 402718720 0.1411229521 0.8641475439 1.7159016132 645 25.7600000000 1.2524187565 0.4843427586 1.9147015810 0.0252447816 0.2042300000 958974521 0 402718720 0.1397001296 0.8580762148 1.7106360197 646 25.8000000000 1.2487943172 0.4855261202 1.9147015810 0.0252264474 0.2018810000 958976529 0 402718720 0.1358856559 0.8528848886 1.7064646482 647 25.8400000000 1.2433389425 0.4866973919 1.9147015810 0.0252091393 0.2074190000 958978537 0 402718720 0.1320687383 0.8484282494 1.6993325949 648 25.8800000000 1.2391040325 0.4878585133 1.9147015810 0.0251911629 0.2065060000 958980545 0 402718720 0.1281812191 0.8437473178 1.6941282749 649 25.9200000000 1.2353482246 0.4890102694 1.9147015810 0.0251734077 0.2057420000 958982553 0 402718720 0.1242207587 0.8371043205 1.6894365549 650 25.9600000000 1.2292764187 0.4901491404 1.9147015810 0.0251597763 0.2038800000 958984561 0 402718720 0.1161176488 0.8229756951 1.6818645000 651 26.0000000000 1.2176513672 0.4912666553 1.9147015810 0.0251585732 0.2021550000 958986569 0 402718720 0.1055485159 0.8129183054 1.6679688692 652 26.0400000000 1.2112255096 0.4923708867 1.9147015810 0.0251429207 0.2011960000 958988577 0 402718720 0.0998187512 0.8081539273 1.6600785255 653 26.0800000000 1.2031421661 0.4934593573 1.9147015810 0.0251273823 0.2001840000 958990585 0 402718720 0.0929021463 0.8054586053 1.6510912180 654 26.1200000000 1.1972872019 0.4945355466 1.9147015810 0.0251121077 0.1994320000 958992593 0 402718720 0.0854561850 0.8005323410 1.6449073553 655 26.1600000000 1.1916818619 0.4955998922 1.9147015810 0.0250970420 0.1982760000 958994601 0 402718720 0.0800362676 0.7928975821 1.6382448673 656 26.2000000000 1.1850593090 0.4966508974 1.9147015810 0.0250827565 0.1945200000 958996609 0 402718720 0.0724407211 0.7882431746 1.6309096813 657 26.2400000000 1.1789016724 0.4976893308 1.9147015810 0.0250684138 0.1958400000 958998617 0 402718720 0.0647306144 0.7837508321 1.6242612600 658 26.2800000000 1.1714218855 0.4987132405 1.9147015810 0.0250550123 0.1947430000 959000625 0 402718720 0.0569883958 0.7793793678 1.6158978939 659 26.3200000000 1.1633186340 0.4997217464 1.9147015810 0.0250413309 0.1938410000 959002633 0 402718720 0.0481477752 0.7765156627 1.6075474024 660 26.3600000000 1.1564997435 0.5007168646 1.9147015810 0.0250270602 0.1931440000 959004641 0 402718720 0.0402829722 0.7725937366 1.6002173424 661 26.4000000000 1.1481163502 0.5016962889 1.9147015810 0.0250129202 0.1924920000 959006649 0 402718720 0.0315614976 0.7690479755 1.5913276672 662 26.4400000000 1.1403053999 0.5026609552 1.9147015810 0.0249985576 0.1915820000 959008657 0 402718720 0.0218112525 0.7676009536 1.5838146210 663 26.4800000000 1.1343811750 0.5036137761 1.9147015810 0.0249897218 0.1910170000 959010665 0 402718720 0.0140308635 0.7624710202 1.5775490999 664 26.5200000000 1.1291801929 0.5045558942 1.9147015810 0.0249794119 0.1901480000 959012673 0 402718720 0.0078008408 0.7542786598 1.5713092089 665 26.5600000000 1.1228847504 0.5054857120 1.9147015810 0.0249638744 0.1898260000 959014681 0 402718720 -0.0000947485 0.7502283454 1.5648396015 666 26.6000000000 1.1153414249 0.5064014113 1.9147015810 0.0249487981 0.1889950000 959016689 0 402718720 -0.0081990622 0.7469630837 1.5568157434 667 26.6400000000 1.1083111763 0.5073038247 1.9147015810 0.0249331764 0.1890160000 959018697 0 402718720 -0.0169029366 0.7454968095 1.5500450134 668 26.6800000000 1.0999329090 0.5081909940 1.9147015810 0.0249208489 0.1880960000 959020705 0 402718720 -0.0251563154 0.7441217303 1.5411137342 669 26.7200000000 1.0930885077 0.5090652803 1.9147015810 0.0249144142 0.1876580000 959022713 0 402718720 -0.0334575474 0.7406559587 1.5340726376 670 26.7600000000 1.0876530409 0.5099288441 1.9147015810 0.0249062456 0.1872930000 959024721 0 402718720 -0.0404834300 0.7361074090 1.5284023285 671 26.8000000000 1.0818231106 0.5107811455 1.9147015810 0.0248930543 0.1869250000 959026729 0 402718720 -0.0470993221 0.7317338586 1.5219131708 672 26.8400000000 1.0745859146 0.5116201407 1.9147015810 0.0248783869 0.1865530000 959028737 0 402718720 -0.0536222570 0.7289260030 1.5138547421 673 26.8800000000 1.0688730478 0.5124481540 1.9147015810 0.0248641940 0.1863580000 959030745 0 402718720 -0.0597342476 0.7249441147 1.5074684620 674 26.9200000000 1.0629612207 0.5132649389 1.9147015810 0.0248494316 0.1861160000 959032753 0 402718720 -0.0657069907 0.7214026451 1.5007846355 675 26.9600000000 1.0569289923 0.5140703671 1.9147015810 0.0248346359 0.1859630000 959034761 0 402718720 -0.0720480159 0.7190293074 1.4943776131 676 27.0000000000 1.0492242575 0.5148620149 1.9147015810 0.0248209008 0.1860600000 959036769 0 402718720 -0.0784228593 0.7180914879 1.4858386517 677 27.0400000000 1.0429271460 0.5156420225 1.9147015810 0.0248084078 0.1860970000 959038777 0 402718720 -0.0852864459 0.7172901034 1.4793876410 678 27.0800000000 1.0371637344 0.5164112286 1.9147015810 0.0247979354 0.1836980000 959040785 0 402718720 -0.0910600647 0.7149018049 1.4729586840 679 27.1200000000 1.0307646990 0.5171687447 1.9147015810 0.0247879447 0.1836510000 959042793 0 402718720 -0.0970998853 0.7120522857 1.4657098055 680 27.1600000000 1.0254325867 0.5179161915 1.9147015810 0.0247775035 0.1803160000 959044801 0 402718720 -0.1015788764 0.7070144415 1.4593410492 681 27.2000000000 1.0198923349 0.5186533078 1.9147015810 0.0247628538 0.1797660000 959046809 0 402718720 -0.1070297435 0.7039964199 1.4530806541 682 27.2400000000 1.0129834414 0.5193781320 1.9147015810 0.0247488447 0.1845740000 959048817 0 402718720 -0.1123980209 0.7025459409 1.4449748993 683 27.2800000000 1.0063189268 0.5200910761 1.9147015810 0.0247367451 0.1810970000 959050825 0 402718720 -0.1172667667 0.7002187967 1.4371324778 684 27.3200000000 1.0006303787 0.5207936189 1.9147015810 0.0247261226 0.1820080000 959052833 0 402718720 -0.1226386726 0.6966862082 1.4303644896 685 27.3600000000 0.9948379397 0.5214856544 1.9147015810 0.0247144054 0.1824430000 959054841 0 402718720 -0.1268053055 0.6923298240 1.4229837656 686 27.4000000000 0.9872531891 0.5221646158 1.9147015810 0.0247013608 0.1824820000 959056849 0 402718720 -0.1317515075 0.6899777651 1.4137344360 687 27.4400000000 0.9799193144 0.5228309254 1.9147015810 0.0246924602 0.1822340000 959058857 0 402718720 -0.1362970322 0.6876478791 1.4045892954 688 27.4800000000 0.9735441804 0.5234860319 1.9147015810 0.0246889572 0.1820500000 959060865 0 402718720 -0.1411002725 0.6839386225 1.3966023922 689 27.5200000000 0.9669381380 0.5241296489 1.9147015810 0.0246842693 0.1821920000 959062873 0 402718720 -0.1457173079 0.6800168753 1.3883436918 690 27.5600000000 0.9603894353 0.5247619095 1.9147015810 0.0246777912 0.1822180000 959064881 0 402718720 -0.1493867189 0.6755031347 1.3796052933 691 27.6000000000 0.9522337914 0.5253805374 1.9147015810 0.0246702960 0.1823260000 959066889 0 402718720 -0.1543154269 0.6734054685 1.3693579435 692 27.6400000000 0.9442290068 0.5259858097 1.9147015810 0.0246684127 0.1799620000 959068897 0 402718720 -0.1588869989 0.6706112623 1.3592398167 693 27.6800000000 0.9382561445 0.5265807164 1.9147015810 0.0246714980 0.1803780000 959070905 0 402718720 -0.1623679549 0.6651337147 1.3508375883 694 27.7200000000 0.9325810671 0.5271657313 1.9147015810 0.0246680696 0.1806420000 959072913 0 402718720 -0.1649056971 0.6581961513 1.3424180746 695 27.7600000000 0.9279180169 0.5277423533 1.9147015810 0.0246569640 0.1814010000 959074921 0 402718720 -0.1677467972 0.6519604921 1.3351902962 696 27.8000000000 0.9209122658 0.5283072526 1.9147015810 0.0246449427 0.1840650000 959076929 0 402718720 -0.1709488779 0.6478744149 1.3254858255 697 27.8400000000 0.9133638144 0.5288597011 1.9147015810 0.0246339885 0.1847000000 959078937 0 402718720 -0.1746473163 0.6446444988 1.3154114485 698 27.8800000000 0.9050395489 0.5293986407 1.9147015810 0.0246243061 0.1858900000 959080945 0 402718720 -0.1794429421 0.6423941851 1.3047962189 699 27.9200000000 0.8973895907 0.5299250941 1.9147015810 0.0246168289 0.1865090000 959082953 0 402718720 -0.1838854998 0.6401836872 1.2949566841 700 27.9600000000 0.8897736669 0.5304391635 1.9147015810 0.0246131177 0.1874170000 959084961 0 402718720 -0.1882544905 0.6367892623 1.2849458456 701 28.0000000000 0.8830835819 0.5309422226 1.9147015810 0.0246104676 0.1878390000 959086969 0 402718720 -0.1925308704 0.6332262754 1.2761293650 702 28.0400000000 0.8771067858 0.5314353345 1.9147015810 0.0246070721 0.1888390000 959088977 0 402718720 -0.1966117024 0.6288050413 1.2679893970 703 28.0800000000 0.8719584942 0.5319197202 1.9147015810 0.0245980597 0.1900920000 959090985 0 402718720 -0.2006588131 0.6252368689 1.2612667084 704 28.1200000000 0.8634351492 0.5323906228 1.9147015810 0.0245887940 0.1915270000 959092993 0 402718720 -0.2064405382 0.6255953908 1.2512336969 705 28.1600000000 0.8561798334 0.5328498983 1.9147015810 0.0245879726 0.1925720000 959095001 0 402718720 -0.2118551284 0.6244866848 1.2425757647 706 28.2000000000 0.8517189026 0.5333015541 1.9147015810 0.0245873132 0.1935430000 959097009 0 402718720 -0.2162773162 0.6203231812 1.2369227409 707 28.2400000000 0.8451470137 0.5337426368 1.9147015810 0.0245781671 0.1938140000 959099017 0 402718720 -0.2212830782 0.6189243793 1.2291293144 708 28.2800000000 0.8381823301 0.5341726363 1.9147015810 0.0245682265 0.1941300000 959101025 0 402718720 -0.2271554172 0.6186357141 1.2213082314 709 28.3200000000 0.8358820081 0.5345981785 1.9147015810 0.0245578395 0.1959620000 959103033 0 402718720 -0.2311688960 0.6130881310 1.2182806730 710 28.3600000000 0.8312245011 0.5350159620 1.9147015810 0.0245436927 0.1971810000 959105041 0 402718720 -0.2355360538 0.6103553772 1.2125982046 711 28.4000000000 0.8224887252 0.5354202838 1.9147015810 0.0245310974 0.1975720000 959107049 0 402718720 -0.2422358543 0.6134610176 1.2034223080 712 28.4400000000 0.8167692423 0.5358154368 1.9147015810 0.0245200746 0.1979450000 959109057 0 402718720 -0.2480276674 0.6119224429 1.1972373724 713 28.4800000000 0.8160967827 0.5362085383 1.9147015810 0.0245035520 0.1935870000 959111065 0 402718720 -0.2519152164 0.6074211597 1.1968135834 714 28.5200000000 0.8078296185 0.5365889600 1.9147015810 0.0244992478 0.1986690000 959113073 0 402718720 -0.2590791881 0.6107271910 1.1887482405 715 28.5600000000 0.7998564839 0.5369571663 1.9147015810 0.0244855626 0.1985220000 959115081 0 402718720 -0.2666708231 0.6135749221 1.1811581850 716 28.6000000000 0.7962604761 0.5373193217 1.9147015810 0.0244753817 0.1938510000 959117089 0 402718720 -0.2735526860 0.6140518188 1.1792840958 717 28.6400000000 0.7929633856 0.5376758686 1.9147015810 0.0244610609 0.1936920000 959119097 0 402718720 -0.2805412710 0.6148826480 1.1778811216 718 28.6800000000 0.7875024676 0.5380238165 1.9147015810 0.0244462784 0.1984280000 959121105 0 402718720 -0.2884448469 0.6181564927 1.1741398573 719 28.7200000000 0.7825486660 0.5383639067 1.9147015810 0.0244354119 0.1980080000 959123113 0 402718720 -0.2962332964 0.6195914745 1.1707605124 720 28.7600000000 0.7788038254 0.5386978510 1.9147015810 0.0244234230 0.1929640000 959125121 0 402718720 -0.3045297265 0.6212357283 1.1695059538 721 28.8000000000 0.7760264277 0.5390270168 1.9147015810 0.0244086483 0.1978420000 959127129 0 402718720 -0.3128439188 0.6223976016 1.1694132090 722 28.8400000000 0.7720671892 0.5393497872 1.9147015810 0.0243935690 0.1977560000 959129137 0 402718720 -0.3217856884 0.6242973804 1.1680865288 723 28.8800000000 0.7691463828 0.5396676248 1.9147015810 0.0243780436 0.1948930000 959131145 0 402718720 -0.3311087489 0.6259154081 1.1683343649 724 28.9200000000 0.7653369904 0.5399793228 1.9147015810 0.0243628234 0.1953730000 959133153 0 402718720 -0.3408974111 0.6281645298 1.1675857306 725 28.9600000000 0.7613595724 0.5402846749 1.9147015810 0.0243480820 0.1949350000 959135161 0 402718720 -0.3512121737 0.6307916045 1.1668399572 726 29.0000000000 0.7585785985 0.5405853552 1.9147015810 0.0243373616 0.1900490000 959137169 0 402718720 -0.3611611426 0.6326165795 1.1675432920 727 29.0400000000 0.7547463775 0.5408799371 1.9147015810 0.0243263753 0.1897380000 959139177 0 402718720 -0.3720539510 0.6347439885 1.1670825481 728 29.0800000000 0.7512146235 0.5411688583 1.9147015810 0.0243142851 0.1917480000 959141185 0 402718720 -0.3829484284 0.6375122070 1.1671293974 729 29.1200000000 0.7475191355 0.5414519177 1.9147015810 0.0242999460 0.1961870000 959143193 0 402718720 -0.3940632641 0.6407546401 1.1669752598 730 29.1600000000 0.7447937727 0.5417304682 1.9147015810 0.0242849621 0.1961510000 959145201 0 402718720 -0.4049180448 0.6427297592 1.1678526402 731 29.2000000000 0.7409630418 0.5420030162 1.9147015810 0.0242708424 0.1939770000 959147209 0 402718720 -0.4161500633 0.6454440355 1.1673629284 732 29.2400000000 0.7360705137 0.5422681357 1.9147015810 0.0242582000 0.1939900000 959149217 0 402718720 -0.4281590581 0.6493815780 1.1657615900 733 29.2800000000 0.7324203849 0.5425275521 1.9147015810 0.0242458946 0.2152320000 959151225 0 402718720 -0.4405266345 0.6534428596 1.1659891605 734 29.3200000000 0.7291851640 0.5427818541 1.9147015810 0.0242329446 0.2486120000 959153233 0 402718720 -0.4529192746 0.6584377885 1.1668474674 735 29.3600000000 0.7260721326 0.5430312286 1.9147015810 0.0242201249 0.2478600000 959155241 0 402718720 -0.4648218155 0.6630808711 1.1675556898 736 29.4000000000 0.7229106426 0.5432756300 1.9147015810 0.0242077459 0.2456430000 959157249 0 402718720 -0.4766956866 0.6686542630 1.1681768894 737 29.4400000000 0.7203518152 0.5435158962 1.9147015810 0.0241953956 0.1937480000 959159257 0 402718720 -0.4880711436 0.6733174920 1.1692168713 738 29.4800000000 0.7176570892 0.5437518598 1.9147015810 0.0241877442 0.1935710000 959161265 0 402718720 -0.4996758401 0.6781716347 1.1700738668 739 29.5200000000 0.7157297134 0.5439845768 1.9147015810 0.0241879583 0.1932560000 959163273 0 402718720 -0.5107376575 0.6828463674 1.1716530323 740 29.5600000000 0.7142979503 0.5442147300 1.9147015810 0.0241867662 0.1927590000 959165281 0 402718720 -0.5210431218 0.6873242259 1.1735581160 741 29.6000000000 0.7123768926 0.5444416695 1.9147015810 0.0241889450 0.1871380000 959167289 0 402718720 -0.5313407779 0.6936286092 1.1745175123 742 29.6400000000 0.7109840512 0.5446661202 1.9147015810 0.0241932728 0.1915070000 959169297 0 402718720 -0.5412515402 0.6989303231 1.1764256954 743 29.6800000000 0.7114306688 0.5448905678 1.9147015810 0.0241843676 0.1923750000 959171305 0 402718720 -0.5494370461 0.7025924921 1.1798670292 744 29.7200000000 0.7112632990 0.5451141870 1.9147015810 0.0241692741 0.1879620000 959173313 0 402718720 -0.5569714904 0.7070234418 1.1817740202 745 29.7600000000 0.7099429965 0.5453354337 1.9147015810 0.0241545991 0.1924470000 959175321 0 402718720 -0.5648033619 0.7103480101 1.1829220057 746 29.8000000000 0.7096994519 0.5455557608 1.9147015810 0.0241394637 0.1874730000 959177329 0 402718720 -0.5718590021 0.7144573927 1.1843446493 747 29.8400000000 0.7080187201 0.5457732481 1.9147015810 0.0241282140 0.1911360000 959179337 0 402718720 -0.5794342160 0.7176849842 1.1848610640 748 29.8800000000 0.7066013217 0.5459882589 1.9147015810 0.0241207982 0.1902640000 959181345 0 402718720 -0.5867044330 0.7221207023 1.1851477623 749 29.9200000000 0.7057583928 0.5462015701 1.9147015810 0.0241124544 0.1892960000 959183353 0 402718720 -0.5931922793 0.7261425257 1.1859358549 750 29.9600000000 0.7049057484 0.5464131757 1.9147015810 0.0241049798 0.1886920000 959185361 0 402718720 -0.5993059278 0.7299121022 1.1865205765 751 30.0000000000 0.7042598128 0.5466233576 1.9147015810 0.0240974159 0.1880950000 959187369 0 402718720 -0.6048917770 0.7329532504 1.1871989965 752 30.0400000000 0.7040421367 0.5468326911 1.9147015810 0.0240838539 0.1784640000 959189377 0 402718720 -0.6090789437 0.7391586900 1.1863510609 753 30.0800000000 0.7025103569 0.5470394344 1.9147015810 0.0240833879 0.1870930000 959191385 0 402718720 -0.6151432395 0.7388861179 1.1874129772 754 30.1200000000 0.7019985318 0.5472449504 1.9147015810 0.0240736617 0.1772110000 959193393 0 402718720 -0.6191359758 0.7436306477 1.1864085197 755 30.1600000000 0.7012274861 0.5474489008 1.9147015810 0.0240687123 0.1766800000 959195401 0 402718720 -0.6239326000 0.7465093732 1.1856923103 756 30.2000000000 0.6996768713 0.5476502605 1.9147015810 0.0240635749 0.1761650000 959197409 0 402718720 -0.6293814182 0.7495095730 1.1847552061 757 30.2400000000 0.6977120042 0.5478484927 1.9147015810 0.0240544572 0.1756900000 959199417 0 402718720 -0.6350002885 0.7523616552 1.1833926439 758 30.2800000000 0.6964433193 0.5480445281 1.9147015810 0.0240450207 0.1749720000 959201425 0 402718720 -0.6407514215 0.7548452616 1.1825593710 759 30.3200000000 0.6943228841 0.5482372532 1.9147015810 0.0240446906 0.1747800000 959203433 0 402718720 -0.6471890807 0.7578381896 1.1809017658 760 30.3600000000 0.6909702420 0.5484250598 1.9147015810 0.0240456518 0.1737460000 959205441 0 402718720 -0.6541266441 0.7619988322 1.1774722338 761 30.4000000000 0.6881401539 0.5486086538 1.9147015810 0.0240423203 0.1726070000 959207449 0 402718720 -0.6606515050 0.7653812766 1.1743911505 762 30.4400000000 0.6848778725 0.5487874848 1.9147015810 0.0240354122 0.1715610000 959209457 0 402718720 -0.6675940752 0.7678605318 1.1713062525 763 30.4800000000 0.6803736687 0.5489599438 1.9147015810 0.0240391110 0.1795260000 959211465 0 402718720 -0.6770310402 0.7655975819 1.1701406240 764 30.5200000000 0.6770399809 0.5491275878 1.9147015810 0.0240271069 0.1691330000 959213473 0 402718720 -0.6839368343 0.7694885731 1.1662640572 765 30.5600000000 0.6736161113 0.5492903179 1.9147015810 0.0240149740 0.1667820000 959215481 0 402718720 -0.6912984848 0.7728498578 1.1625591516 766 30.6000000000 0.6689490080 0.5494465303 1.9147015810 0.0240122534 0.1748720000 959217489 0 402718720 -0.7007061243 0.7716156244 1.1595156193 767 30.6400000000 0.6656872630 0.5495980828 1.9147015810 0.0239991276 0.1638290000 959219497 0 402718720 -0.7078610659 0.7757561803 1.1558442116 768 30.6800000000 0.6606388688 0.5497426671 1.9147015810 0.0239967648 0.1720440000 959221505 0 402718720 -0.7173928618 0.7750161290 1.1515294313 769 30.7200000000 0.6575630903 0.5498828757 1.9147015810 0.0239846049 0.1619000000 959223513 0 402718720 -0.7246060967 0.7793542147 1.1482071877 770 30.7600000000 0.6523368955 0.5500159329 1.9147015810 0.0239798713 0.1706100000 959225521 0 402718720 -0.7342373133 0.7793368101 1.1432778835 771 30.8000000000 0.6481516361 0.5501432166 1.9147015810 0.0239692051 0.1698630000 959227529 0 402718720 -0.7425359488 0.7808209062 1.1390863657 772 30.8400000000 0.6445393562 0.5502654914 1.9147015810 0.0239587422 0.1704900000 959229537 0 402718720 -0.7506998777 0.7813588381 1.1356902122 773 30.8800000000 0.6407201290 0.5503825090 1.9147015810 0.0239489234 0.1709010000 959231545 0 402718720 -0.7590453029 0.7823215127 1.1319630146 774 30.9200000000 0.6374949813 0.5504950574 1.9147015810 0.0239407647 0.1701210000 959233553 0 402718720 -0.7671280503 0.7830138206 1.1289781332 775 30.9600000000 0.6352756619 0.5506044517 1.9147015810 0.0239295093 0.1601220000 959235561 0 402718720 -0.7741248608 0.7845224142 1.1271703243 776 31.0000000000 0.6307069063 0.5507076766 1.9147015810 0.0239281420 0.1690020000 959237569 0 402718720 -0.7834689021 0.7825427651 1.1226919889 777 31.0400000000 0.6275562048 0.5508065807 1.9147015810 0.0239199807 0.1589250000 959239577 0 402718720 -0.7903482318 0.7855220437 1.1189945936 778 31.0800000000 0.6227165461 0.5508990100 1.9147015810 0.0239184820 0.1674860000 959241585 0 402718720 -0.7993968725 0.7843726873 1.1142537594 779 31.1200000000 0.6204591393 0.5509883041 1.9147015810 0.0239050626 0.1577840000 959243593 0 402718720 -0.8056983352 0.7871348262 1.1116935015 780 31.1600000000 0.6162191033 0.5510719333 1.9147015810 0.0239014935 0.1666130000 959245601 0 402718720 -0.8145245314 0.7854282260 1.1076623201 781 31.2000000000 0.6126953959 0.5511508366 1.9147015810 0.0238914600 0.1661940000 959247609 0 402718720 -0.8218098879 0.7855941057 1.1039744616 782 31.2400000000 0.6099236608 0.5512259937 1.9147015810 0.0238790024 0.1659490000 959249617 0 402718720 -0.8287419677 0.7852011919 1.1012969017 783 31.2800000000 0.6071582437 0.5512974269 1.9147015810 0.0238661732 0.1661900000 959251625 0 402718720 -0.8357324004 0.7852038145 1.0985556841 784 31.3200000000 0.6047409773 0.5513655947 1.9147015810 0.0238543672 0.1653080000 959253633 0 402718720 -0.8422200084 0.7849646807 1.0962350368 785 31.3600000000 0.6025816202 0.5514308381 1.9147015810 0.0238412120 0.1640130000 959255641 0 402718720 -0.8483667374 0.7842274308 1.0942748785 786 31.4000000000 0.6003992558 0.5514931389 1.9147015810 0.0238275017 0.1652360000 959257649 0 402718720 -0.8545647264 0.7837793231 1.0922273397 787 31.4400000000 0.5980384350 0.5515522816 1.9147015810 0.0238139889 0.1651830000 959259657 0 402718720 -0.8602114320 0.7842760682 1.0896755457 788 31.4800000000 0.5965985060 0.5516094468 1.9147015810 0.0238001810 0.1654150000 959261665 0 402718720 -0.8655322194 0.7843678594 1.0883766413 789 31.5200000000 0.5950655937 0.5516645243 1.9147015810 0.0237863707 0.1654890000 959263673 0 402718720 -0.8707169294 0.7834386230 1.0871176720 790 31.5600000000 0.5937675238 0.5517178193 1.9147015810 0.0237728317 0.1656310000 959265681 0 402718720 -0.8758922219 0.7828483582 1.0860990286 791 31.6000000000 0.5924257040 0.5517692831 1.9147015810 0.0237606489 0.1640430000 959267689 0 402718720 -0.8806777000 0.7822656035 1.0849711895 792 31.6400000000 0.5916519165 0.5518196399 1.9147015810 0.0237481378 0.1640350000 959269697 0 402718720 -0.8850321174 0.7814728618 1.0845799446 793 31.6800000000 0.5910634995 0.5518691278 1.9147015810 0.0237340929 0.1643210000 959271705 0 402718720 -0.8889737725 0.7803598046 1.0844620466 794 31.7200000000 0.5908501744 0.5519182223 1.9147015810 0.0237204645 0.1647010000 959273713 0 402718720 -0.8925072551 0.7791988850 1.0848090649 795 31.7600000000 0.5906041861 0.5519668839 1.9147015810 0.0237089199 0.1653820000 959275721 0 402718720 -0.8959503770 0.7780720592 1.0851039886 796 31.8000000000 0.5906428695 0.5520154718 1.9147015810 0.0236998280 0.1657510000 959277729 0 402718720 -0.8994488120 0.7771288753 1.0857377052 797 31.8400000000 0.5909704566 0.5520643488 1.9147015810 0.0236942778 0.1677560000 959279737 0 402718720 -0.9022990465 0.7763372660 1.0866613388 798 31.8800000000 0.5909945369 0.5521131335 1.9147015810 0.0236892482 0.1682480000 959281745 0 402718720 -0.9053484797 0.7749184966 1.0873366594 799 31.9200000000 0.5912831426 0.5521621573 1.9147015810 0.0236822831 0.1689410000 959283753 0 402718720 -0.9082691669 0.7733734846 1.0883748531 800 31.9600000000 0.5918157101 0.5522117243 1.9147015810 0.0236748424 0.1696610000 959285761 0 402718720 -0.9109945297 0.7718319893 1.0897208452 801 32.0000000000 0.5933401585 0.5522630706 1.9147015810 0.0236676477 0.1611200000 959287769 0 402718720 -0.9133848548 0.7709237933 1.0939083099 802 32.0400000000 0.5935753584 0.5523145822 1.9147015810 0.0236600404 0.1712250000 959289777 0 402718720 -0.9163164496 0.7695211172 1.0932006836 803 32.0800000000 0.5951641202 0.5523679440 1.9147015810 0.0236510455 0.1619530000 959291785 0 402718720 -0.9176598191 0.7709431648 1.0959941149 804 32.1199999990 0.5966246724 0.5524229897 1.9147015810 0.0236428793 0.1622450000 959293793 0 402718720 -0.9188439846 0.7720981836 1.0983135700 805 32.1600000000 0.5971837640 0.5524785931 1.9147015810 0.0236343275 0.1717270000 959295801 0 402718720 -0.9220348001 0.7699164152 1.0986675024 806 32.2000000000 0.5989230275 0.5525362165 1.9147015810 0.0236271403 0.1630690000 959297809 0 402718720 -0.9228810072 0.7702103853 1.1027193069 807 32.2400000000 0.6000130773 0.5525950478 1.9147015810 0.0236217493 0.1727320000 959299817 0 402718720 -0.9253458977 0.7674978375 1.1034110785 808 32.2800000000 0.6021927595 0.5526564311 1.9147015810 0.0236128910 0.1641140000 959301825 0 402718720 -0.9265117049 0.7670354843 1.1083103418 809 32.3200000000 0.6040256023 0.5527199282 1.9147015810 0.0236047558 0.1739900000 959303833 0 402718720 -0.9287048578 0.7645056248 1.1098737717 810 32.3600000000 0.6060596108 0.5527857797 1.9147015810 0.0235957369 0.1650720000 959305841 0 402718720 -0.9299601912 0.7632609606 1.1149113178 811 32.4000000000 0.6081490517 0.5528540451 1.9147015810 0.0235836409 0.1655190000 959307849 0 402718720 -0.9318206310 0.7607092857 1.1191241741 812 32.4399999990 0.6100918055 0.5529245350 1.9147015810 0.0235721189 0.1662200000 959309857 0 402718720 -0.9338282347 0.7583111525 1.1223931313 813 32.4800000000 0.6123106480 0.5529975806 1.9147015810 0.0235618643 0.1665240000 959311865 0 402718720 -0.9358672500 0.7570859790 1.1257095337 814 32.5200000000 0.6145153046 0.5530731552 1.9147015810 0.0235515680 0.1670620000 959313873 0 402718720 -0.9378302693 0.7557638884 1.1293311119 815 32.5600000000 0.6167049408 0.5531512311 1.9147015810 0.0235401354 0.1677120000 959315881 0 402718720 -0.9398696423 0.7540861368 1.1334788799 816 32.6000000000 0.6197547913 0.5532328531 1.9147015810 0.0235299733 0.1683490000 959317889 0 402718720 -0.9418655038 0.7516741157 1.1386405230 817 32.6400000000 0.6220835447 0.5533171256 1.9147015810 0.0235185320 0.1690980000 959319897 0 402718720 -0.9441928864 0.7492800355 1.1433106661 818 32.6800000000 0.6248658299 0.5534045935 1.9147015810 0.0235067955 0.1696280000 959321905 0 402718720 -0.9468078613 0.7474402189 1.1476849318 819 32.7200000000 0.6276000142 0.5534951862 1.9147015810 0.0234966582 0.1704040000 959323913 0 402718720 -0.9494134188 0.7473601699 1.1515582800 820 32.7599999990 0.6304638386 0.5535890504 1.9147015810 0.0234865122 0.1709300000 959325921 0 402718720 -0.9519915581 0.7473325729 1.1556216478 821 32.7999999990 0.6343287826 0.5536873936 1.9147015810 0.0234820360 0.1716130000 959327929 0 402718720 -0.9541772008 0.7487552762 1.1603933573 822 32.8400000000 0.6380302310 0.5537900004 1.9147015810 0.0234853791 0.1720520000 959329937 0 402718720 -0.9559014440 0.7502087951 1.1652903557 823 32.8800000000 0.6416434646 0.5538967482 1.9147015810 0.0234946308 0.1825290000 959331945 0 402718720 -0.9576138854 0.7540657520 1.1667642593 824 32.9200000000 0.6450960040 0.5540074270 1.9147015810 0.0234902239 0.1830930000 959333953 0 402718720 -0.9606726766 0.7562267780 1.1712691784 825 32.9600000000 0.6491590142 0.5541227622 1.9147015810 0.0234855257 0.1790540000 959335961 0 402718720 -0.9635989070 0.7573311329 1.1771360636 826 33.0000000000 0.6528635025 0.5542423031 1.9147015810 0.0234787289 0.1795180000 959337969 0 402718720 -0.9668859839 0.7592207193 1.1821855307 827 33.0400000000 0.6569591761 0.5543665073 1.9147015810 0.0234749738 0.1796160000 959339977 0 402718720 -0.9700687528 0.7596211433 1.1878157854 828 33.0800000000 0.6611034870 0.5544954167 1.9147015810 0.0234800682 0.1851120000 959341985 0 402718720 -0.9732122421 0.7590357661 1.1935951710 829 33.1199999990 0.6653111577 0.5546290906 1.9147015810 0.0234878371 0.1853010000 959343993 0 402718720 -0.9767436385 0.7593390346 1.1995930672 830 33.1600000000 0.6694554090 0.5547674356 1.9147015810 0.0234948883 0.1863390000 959346001 0 402718720 -0.9800191522 0.7593604326 1.2055219412 831 33.2000000000 0.6748712063 0.5549119648 1.9147015810 0.0235044822 0.1863900000 959348009 0 402718720 -0.9830489755 0.7588124871 1.2132525444 832 33.2400000000 0.6795030236 0.5550617137 1.9147015810 0.0235104604 0.1873650000 959350017 0 402718720 -0.9866399169 0.7585668564 1.2199214697 833 33.2800000000 0.6840572357 0.5552165703 1.9147015810 0.0235096877 0.1874780000 959352025 0 402718720 -0.9906535745 0.7590425611 1.2263239622 834 33.3200000000 0.6889450550 0.5553769162 1.9147015810 0.0235055064 0.1830360000 959354033 0 402718720 -0.9943892956 0.7576352954 1.2341462374 835 33.3600000000 0.6928595304 0.5555415660 1.9147015810 0.0235093989 0.1880170000 959356041 0 402718720 -0.9984423518 0.7585616708 1.2390834093 836 33.4000000000 0.6974607110 0.5557113257 1.9147015810 0.0235133975 0.1883420000 959358049 0 402718720 -1.0022372007 0.7588147521 1.2455856800 837 33.4399999990 0.7014530897 0.5558854497 1.9147015810 0.0235197516 0.1888290000 959360057 0 402718720 -1.0062360764 0.7596346736 1.2511458397 838 33.4800000000 0.7062057853 0.5560648296 1.9147015810 0.0235316185 0.1893180000 959362065 0 402718720 -1.0093595982 0.7586572170 1.2580752373 839 33.5200000000 0.7104771137 0.5562488728 1.9147015810 0.0235464368 0.1874910000 959364073 0 402718720 -1.0128014088 0.7597863078 1.2638916969 840 33.5600000000 0.7130009532 0.5564354824 1.9147015810 0.0235501660 0.1879160000 959366081 0 402718720 -1.0168690681 0.7594735026 1.2677217722 841 33.6000000000 0.7161886096 0.5566254386 1.9147015810 0.0235444963 0.1884580000 959368089 0 402718720 -1.0206493139 0.7601788640 1.2721437216 842 33.6400000000 0.7192114592 0.5568185336 1.9147015810 0.0235350746 0.1887980000 959370097 0 402718720 -1.0242743492 0.7606189251 1.2763903141 843 33.6800000000 0.7226593494 0.5570152606 1.9147015810 0.0235264956 0.1868540000 959372105 0 402718720 -1.0274418592 0.7598128915 1.2825126648 844 33.7200000000 0.7267934084 0.5572164195 1.9147015810 0.0235241670 0.1917670000 959374113 0 402718720 -1.0305175781 0.7584894300 1.2877490520 845 33.7599999990 0.7306824923 0.5574217048 1.9147015810 0.0235257564 0.1925640000 959376121 0 402718720 -1.0330398083 0.7585096955 1.2931963205 846 33.7999999990 0.7334945798 0.5576298288 1.9147015810 0.0235242805 0.1926760000 959378129 0 402718720 -1.0361843109 0.7586232424 1.2972589731 847 33.8400000000 0.7359497547 0.5578403600 1.9147015810 0.0235121587 0.1839940000 959380137 0 402718720 -1.0369501114 0.7558558583 1.3051861525 848 33.8800000000 0.7395938039 0.5580546919 1.9147015810 0.0235054404 0.1939620000 959382145 0 402718720 -1.0412546396 0.7553603053 1.3068573475 849 33.9200000000 0.7423669696 0.5582717853 1.9147015810 0.0234920030 0.1851550000 959384153 0 402718720 -1.0422631502 0.7522614002 1.3143392801 850 33.9600000000 0.7446066737 0.5584910028 1.9147015810 0.0234782520 0.1853760000 959386161 0 402718720 -1.0442987680 0.7496213317 1.3206422329 851 34.0000000000 0.7470352054 0.5587125588 1.9147015810 0.0234650016 0.1858960000 959388169 0 402718720 -1.0470361710 0.7482019663 1.3255298138 852 34.0400000000 0.7509338856 0.5589381707 1.9147015810 0.0234524458 0.1857910000 959390177 0 402718720 -1.0489526987 0.7458313107 1.3311963081 853 34.0800000000 0.7547262907 0.5591676996 1.9147015810 0.0234512881 0.1998490000 959392185 0 402718720 -1.0523543358 0.7463756800 1.3310170174 854 34.1199999990 0.7562973499 0.5593985305 1.9147015810 0.0234391252 0.1864050000 959394193 0 402718720 -1.0531361103 0.7443572879 1.3379414082 855 34.1600000000 0.7591137290 0.5596321156 1.9147015810 0.0234285705 0.1866150000 959396201 0 402718720 -1.0533069372 0.7438001633 1.3437660933 856 34.2000000000 0.7625914216 0.5598692176 1.9147015810 0.0234239776 0.1985650000 959398209 0 402718720 -1.0573611259 0.7440536022 1.3429931402 857 34.2400000000 0.7635852098 0.5601069258 1.9147015810 0.0234103745 0.1849140000 959400217 0 402718720 -1.0581368208 0.7442976236 1.3470621109 858 34.2800000000 0.7653436065 0.5603461294 1.9147015810 0.0233968752 0.1850890000 959402225 0 402718720 -1.0599468946 0.7440455556 1.3493219614 859 34.3200000000 0.7686240077 0.5605885950 1.9147015810 0.0233836471 0.1849480000 959404233 0 402718720 -1.0609930754 0.7406516075 1.3533802032 860 34.3600000000 0.7700977921 0.5608322103 1.9147015810 0.0233702371 0.1851480000 959406241 0 402718720 -1.0619153976 0.7363793254 1.3582271338 861 34.4000000000 0.7718200088 0.5610772600 1.9147015810 0.0233576858 0.1871620000 959408249 0 402718720 -1.0636178255 0.7334286571 1.3628178835 862 34.4400000000 0.7737994194 0.5613240375 1.9147015810 0.0233446462 0.1877690000 959410257 0 402718720 -1.0649851561 0.7303664088 1.3667638302 863 34.4800000000 0.7761468291 0.5615729631 1.9147015810 0.0233319157 0.1873240000 959412265 0 402718720 -1.0655262470 0.7257558107 1.3713608980 864 34.5200000000 0.7775188088 0.5618229004 1.9147015810 0.0233197378 0.1879750000 959414273 0 402718720 -1.0660251379 0.7226539254 1.3760887384 865 34.5600000000 0.7778093219 0.5620725957 1.9147015810 0.0233066886 0.1878320000 959416281 0 402718720 -1.0669490099 0.7214885950 1.3792159557 866 34.6000000000 0.7782791257 0.5623222568 1.9147015810 0.0232935946 0.1880480000 959418289 0 402718720 -1.0683631897 0.7204244137 1.3806954622 867 34.6400000000 0.7804699540 0.5625738689 1.9147015810 0.0232804308 0.1881060000 959420297 0 402718720 -1.0700795650 0.7192203403 1.3821244240 868 34.6800000000 0.7820549607 0.5628267273 1.9147015810 0.0232682132 0.1882500000 959422305 0 402718720 -1.0712896585 0.7167319655 1.3839167356 869 34.7200000000 0.7837601304 0.5630809660 1.9147015810 0.0232559335 0.1880200000 959424313 0 402718720 -1.0714751482 0.7143800259 1.3869014978 870 34.7600000000 0.7840063572 0.5633349032 1.9147015810 0.0232429763 0.1881410000 959426321 0 402718720 -1.0717442036 0.7119101286 1.3895887136 871 34.8000000000 0.7843418121 0.5635886425 1.9147015810 0.0232300128 0.1882840000 959428329 0 402718720 -1.0726364851 0.7101840377 1.3914122581 872 34.8400000000 0.7853003144 0.5638428990 1.9147015810 0.0232177470 0.1882920000 959430337 0 402718720 -1.0739542246 0.7078233361 1.3930525780 873 34.8800000000 0.7863704562 0.5640977988 1.9147015810 0.0232058474 0.1882690000 959432345 0 402718720 -1.0753273964 0.7062278390 1.3951252699 874 34.9200000000 0.7869189978 0.5643527430 1.9147015810 0.0231938186 0.1884100000 959434353 0 402718720 -1.0767802000 0.7048194408 1.3967924118 875 34.9600000000 0.7869355083 0.5646071233 1.9147015810 0.0231822867 0.1883580000 959436361 0 402718720 -1.0788338184 0.7048653960 1.3975057602 876 35.0000000000 0.7880815268 0.5648622310 1.9147015810 0.0231708538 0.1884130000 959438369 0 402718720 -1.0806361437 0.7051361203 1.3976819515 877 35.0400000000 0.7888386250 0.5651176203 1.9147015810 0.0231582065 0.1885230000 959440377 0 402718720 -1.0823750496 0.7056573033 1.3979375362 878 35.0800000000 0.7893360257 0.5653729943 1.9147015810 0.0231450513 0.1884390000 959442385 0 402718720 -1.0839275122 0.7066739798 1.3976478577 879 35.1200000000 0.7903674841 0.5656289608 1.9147015810 0.0231319270 0.1884920000 959444393 0 402718720 -1.0851378441 0.7070989609 1.3979843855 880 35.1600000000 0.7905632257 0.5658845679 1.9147015810 0.0231188515 0.1884560000 959446401 0 402718720 -1.0865076780 0.7081357241 1.3981422186 881 35.2000000000 0.7914874554 0.5661406438 1.9147015810 0.0231058031 0.1886160000 959448409 0 402718720 -1.0881438255 0.7093843222 1.3977822065 882 35.2400000000 0.7936927676 0.5663986394 1.9147015810 0.0230928127 0.1883740000 959450417 0 402718720 -1.0883790255 0.7073866725 1.3996567726 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 12:54:12 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.1635070000 954998708 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0003882339 0.0001941170 0.0003882339 0.0010334660 0.1857220000 958086569 0 402718720 -0.0001939286 0.0036084331 0.0017813982 3 0.0800000000 0.0007171431 0.0003684590 0.0007171431 0.0018865664 0.1915890000 957775881 0 402718720 -0.0019467204 -0.0020309580 0.0017661451 4 0.1200000000 0.0008667303 0.0004930268 0.0008667303 0.0023544411 0.1917340000 957778289 0 402718720 -0.0023174451 -0.0007925446 0.0006180039 5 0.1600000000 0.0010551389 0.0006054492 0.0010551389 0.0042429367 0.1947580000 957780297 0 402718720 -0.0001182645 0.0056782276 0.0036432808 6 0.2000000000 0.0012209694 0.0007080359 0.0012209694 0.0040669904 0.1943040000 957783105 0 402718720 0.0030023123 -0.0044097491 0.0027601412 7 0.2400000000 0.0012693885 0.0007882291 0.0012693885 0.0039259416 0.2075550000 957785113 0 402718720 0.0032086128 -0.0144207831 -0.0003562252 8 0.2800000000 0.0012088948 0.0008408123 0.0012693885 0.0036450875 0.2041830000 957787121 0 402718720 0.0010070577 -0.0127789089 -0.0012679999 9 0.3200000000 0.0010876625 0.0008682401 0.0012693885 0.0045207613 0.1920410000 957789129 0 402718720 -0.0001111546 -0.0090667261 0.0016689929 10 0.3600000000 0.0014996337 0.0009313795 0.0014996337 0.0042864655 0.1907570000 957792737 0 402718720 -0.0020217150 -0.0159810837 -0.0001118680 11 0.4000000000 0.0013576406 0.0009701305 0.0014996337 0.0041263668 0.1909460000 957794745 0 402718720 -0.0019434819 -0.0125960624 -0.0013916029 12 0.4400000000 0.0015243466 0.0010163152 0.0015243466 0.0041889959 0.1963460000 957796753 0 402718720 -0.0009503953 -0.0024543519 0.0015405682 13 0.4800000000 0.0015206365 0.0010551091 0.0015243466 0.0040144674 0.2019530000 957798761 0 402718720 0.0010171368 -0.0045938129 0.0015784675 14 0.5200000000 0.0016961659 0.0011008989 0.0016961659 0.0039715252 0.1957140000 957800769 0 402718720 0.0039401907 -0.0121010784 -0.0011733491 15 0.5600000000 0.0013432961 0.0011170587 0.0016961659 0.0039339086 0.1916730000 957802777 0 402718720 0.0065081450 -0.0107602766 -0.0013718503 16 0.6000000000 0.0014868001 0.0011401676 0.0016961659 0.0038090102 0.1911210000 957804785 0 402718720 0.0077330787 -0.0094452314 -0.0010757805 17 0.6400000000 0.0016912270 0.0011725828 0.0016961659 0.0037093758 0.2031310000 957806793 0 402718720 0.0074938457 -0.0129351728 -0.0028987210 18 0.6800000000 0.0015151761 0.0011916158 0.0016961659 0.0036010969 0.1881240000 957812001 0 402718720 0.0066670463 -0.0120905964 -0.0042948434 19 0.7200000000 0.0017876725 0.0012229872 0.0017876725 0.0036703856 0.1970580000 957814009 0 402718720 0.0073415558 -0.0077868863 -0.0040914719 20 0.7600000000 0.0016812264 0.0012458991 0.0017876725 0.0039493400 0.1914070000 957816017 0 402718720 0.0067611421 -0.0091093415 -0.0066858605 21 0.8000000000 0.0018797101 0.0012760806 0.0018797101 0.0041361054 0.1974780000 957818025 0 402718720 0.0094311917 -0.0058907038 -0.0064875097 22 0.8400000000 0.0017250123 0.0012964866 0.0018797101 0.0040712425 0.1902500000 957820033 0 402718720 0.0095293503 -0.0033431321 -0.0061294753 23 0.8800000000 0.0019212655 0.0013236509 0.0019212655 0.0040456994 0.2286430000 957822041 0 402718720 0.0122269168 -0.0094469329 -0.0100599090 24 0.9200000000 0.0017558881 0.0013416608 0.0019212655 0.0040361148 0.1935590000 957824049 0 402718720 0.0142301433 -0.0084283464 -0.0099113602 25 0.9600000000 0.0018948318 0.0013637876 0.0019212655 0.0039531785 0.1926180000 957826057 0 402718720 0.0143042924 -0.0111001823 -0.0129500655 26 1.0000000000 0.0018949527 0.0013842171 0.0019212655 0.0038740595 0.1925240000 957828065 0 402718720 0.0126408627 -0.0115286382 -0.0139670689 27 1.0400000000 0.0020059568 0.0014072445 0.0020059568 0.0038132885 0.1920960000 957830073 0 402718720 0.0137037691 -0.0154564166 -0.0164125655 28 1.0800000000 0.0019863725 0.0014279276 0.0020059568 0.0037455664 0.1932830000 957832081 0 402718720 0.0125784390 -0.0176739004 -0.0178424548 29 1.1200000000 0.0020037030 0.0014477819 0.0020059568 0.0037662299 0.2066310000 957834089 0 402718720 0.0137585318 -0.0197235160 -0.0190349612 30 1.1600000000 0.0018450569 0.0014610244 0.0020059568 0.0037350568 0.1941520000 957836097 0 402718720 0.0169659890 -0.0190159827 -0.0194323249 31 1.2000000000 0.0021458259 0.0014831148 0.0021458259 0.0037428392 0.1968800000 957838105 0 402718720 0.0218958352 -0.0174805336 -0.0208284613 32 1.2400000000 0.0018789636 0.0014954851 0.0021458259 0.0037875209 0.1927840000 957840113 0 402718720 0.0221786294 -0.0146773541 -0.0219450761 33 1.2800000000 0.0021611152 0.0015156557 0.0021611152 0.0040350544 0.2076300000 957842121 0 402718720 0.0235135574 -0.0102993017 -0.0220286269 34 1.3200000000 0.0021958833 0.0015356624 0.0021958833 0.0042472791 0.1938240000 957850529 0 402718720 0.0317796804 -0.0078672180 -0.0243406873 35 1.3600000000 0.0021008567 0.0015518108 0.0021958833 0.0041875749 0.1871390000 957852537 0 402718720 0.0309633575 -0.0092801452 -0.0259293634 36 1.4000000000 0.0021286532 0.0015678342 0.0021958833 0.0041381747 0.1856270000 957854545 0 402718720 0.0313458480 -0.0115517741 -0.0293287262 37 1.4400000000 0.0021157230 0.0015826420 0.0021958833 0.0040813110 0.1848130000 957856553 0 402718720 0.0339461081 -0.0126458220 -0.0316047892 38 1.4800000000 0.0021566844 0.0015977484 0.0021958833 0.0040264582 0.1841180000 957858561 0 402718720 0.0338492207 -0.0126483059 -0.0318736061 39 1.5200000000 0.0021345613 0.0016115128 0.0021958833 0.0039988739 0.1834750000 957860569 0 402718720 0.0346387587 -0.0119365854 -0.0328074135 40 1.5600000000 0.0021127011 0.0016240425 0.0021958833 0.0041973644 0.1835500000 957862577 0 402718720 0.0376102589 -0.0116425222 -0.0336462110 41 1.6000000000 0.0023540098 0.0016418466 0.0023540098 0.0044635919 0.1879120000 957864585 0 402718720 0.0432807654 -0.0096688904 -0.0342807882 42 1.6400000000 0.0022285499 0.0016558157 0.0023540098 0.0044258275 0.1813930000 957866593 0 402718720 0.0436223410 -0.0099327108 -0.0355457142 43 1.6800000000 0.0022246395 0.0016690442 0.0023540098 0.0044121686 0.1951280000 957868601 0 402718720 0.0454198048 -0.0101173939 -0.0370664783 44 1.7200000000 0.0021789225 0.0016806323 0.0023540098 0.0043822910 0.1781600000 957870609 0 402718720 0.0473816544 -0.0092673395 -0.0372756347 45 1.7600000000 0.0021326374 0.0016906769 0.0023540098 0.0045693924 0.1774910000 957872617 0 402718720 0.0492041074 -0.0077257119 -0.0384219289 46 1.8000000000 0.0022150541 0.0017020764 0.0023540098 0.0046632033 0.1738910000 957874625 0 402718720 0.0507023148 -0.0068861474 -0.0391050465 47 1.8400000000 0.0024195150 0.0017173410 0.0024195150 0.0046732405 0.1809090000 957876633 0 402718720 0.0524869859 -0.0040458925 -0.0395064838 48 1.8800000000 0.0021778375 0.0017269347 0.0024195150 0.0046569479 0.1753320000 957878641 0 402718720 0.0543605313 -0.0032752932 -0.0393005051 49 1.9200000000 0.0022763701 0.0017381477 0.0024195150 0.0046884046 0.1847370000 957880649 0 402718720 0.0554877371 -0.0055020479 -0.0411555767 50 1.9600000000 0.0023213776 0.0017498123 0.0024195150 0.0046622639 0.1915220000 957882657 0 402718720 0.0509127937 -0.0035087585 -0.0431812629 51 2.0000000000 0.0022672324 0.0017599578 0.0024195150 0.0046595862 0.1758030000 957884665 0 402718720 0.0501263849 0.0006666402 -0.0423165001 52 2.0400000000 0.0023652131 0.0017715973 0.0024195150 0.0046342849 0.1742780000 957886673 0 402718720 0.0501658469 -0.0010073605 -0.0425398834 53 2.0800000000 0.0024405441 0.0017842189 0.0024405441 0.0046003641 0.1709730000 957888681 0 402718720 0.0504353307 -0.0051826374 -0.0448343456 54 2.1200000000 0.0022428944 0.0017927129 0.0024405441 0.0046220814 0.1725450000 957890689 0 402718720 0.0507735424 -0.0043765311 -0.0444332473 55 2.1600000000 0.0021925690 0.0017999830 0.0024405441 0.0046144458 0.1817280000 957892697 0 402718720 0.0516599715 -0.0022827168 -0.0443632342 56 2.2000000000 0.0022697356 0.0018083715 0.0024405441 0.0046225457 0.1698900000 957894705 0 402718720 0.0530546717 -0.0027908231 -0.0452464744 57 2.2400000000 0.0023482090 0.0018178423 0.0024405441 0.0046390921 0.1707120000 957896713 0 402718720 0.0533402339 -0.0052833240 -0.0475350507 58 2.2800000000 0.0025689905 0.0018307931 0.0025689905 0.0048104680 0.1746120000 957898721 0 402718720 0.0571404882 -0.0035934178 -0.0470067188 59 2.3200000000 0.0026044827 0.0018439065 0.0026044827 0.0049709744 0.1738320000 957900729 0 402718720 0.0609250106 -0.0008016909 -0.0477208495 60 2.3600000000 0.0026260256 0.0018569418 0.0026260256 0.0050209485 0.1840910000 957902737 0 402718720 0.0642588958 -0.0051404419 -0.0503228046 61 2.4000000000 0.0025684014 0.0018686051 0.0026260256 0.0050101760 0.1666210000 957904745 0 402718720 0.0640236661 -0.0078699980 -0.0517065935 62 2.4400000000 0.0024080256 0.0018773054 0.0026260256 0.0050544022 0.1657540000 957906753 0 402718720 0.0660891756 -0.0071851900 -0.0511814393 63 2.4800000000 0.0026783904 0.0018900211 0.0026783904 0.0050909567 0.1702590000 957908761 0 402718720 0.0724301562 -0.0050562466 -0.0512449406 64 2.5200000000 0.0026642731 0.0019021188 0.0026783904 0.0050666833 0.1695920000 957910769 0 402718720 0.0747839585 -0.0091891773 -0.0551530384 65 2.5600000000 0.0024821251 0.0019110419 0.0026783904 0.0050566850 0.1726330000 957912777 0 402718720 0.0759564713 -0.0088133980 -0.0549783632 66 2.6000000000 0.0025757537 0.0019211133 0.0026783904 0.0050189880 0.1620730000 957927585 0 402718720 0.0728048831 -0.0126225930 -0.0567808636 67 2.6400000000 0.0024369590 0.0019288125 0.0026783904 0.0050502441 0.1598720000 957929593 0 402718720 0.0730717033 -0.0144218793 -0.0585780591 68 2.6800000000 0.0027541285 0.0019409495 0.0027541285 0.0051322420 0.1643950000 957931601 0 402718720 0.0783797726 -0.0166707672 -0.0589997321 69 2.7200000000 0.0023672024 0.0019471271 0.0027541285 0.0051499886 0.1609910000 957933609 0 402718720 0.0797845274 -0.0166952386 -0.0601100102 70 2.7600000000 0.0027633647 0.0019587876 0.0027633647 0.0052037483 0.1748170000 957935617 0 402718720 0.0824580193 -0.0146075701 -0.0608540922 71 2.8000000000 0.0027495690 0.0019699254 0.0027633647 0.0052470631 0.1627470000 957937625 0 402718720 0.0849830732 -0.0139199756 -0.0625932664 72 2.8400000000 0.0023679684 0.0019754538 0.0027633647 0.0052634596 0.1580520000 957939633 0 402718720 0.0865468830 -0.0147400461 -0.0634090379 73 2.8800000000 0.0027483064 0.0019860408 0.0027633647 0.0053158470 0.1614530000 957941641 0 402718720 0.0892933160 -0.0116774198 -0.0657265037 74 2.9200000000 0.0028378856 0.0019975522 0.0028378856 0.0054343136 0.1618290000 957943649 0 402718720 0.0912254676 -0.0117974663 -0.0687614158 75 2.9600000000 0.0028569810 0.0020090113 0.0028569810 0.0054759902 0.1718130000 957945657 0 402718720 0.0968053490 -0.0118477140 -0.0702112615 76 3.0000000000 0.0028264741 0.0020197674 0.0028569810 0.0054961211 0.1589290000 957947665 0 402718720 0.1002163813 -0.0103626484 -0.0719306692 77 3.0400000000 0.0022815824 0.0020231675 0.0028569810 0.0055166456 0.1514700000 957949673 0 402718720 0.1028738841 -0.0105564063 -0.0728533566 78 3.0800000000 0.0028911552 0.0020342956 0.0028911552 0.0054911951 0.1569170000 957951681 0 402718720 0.1061266288 -0.0120878629 -0.0764957443 79 3.1200000000 0.0028702139 0.0020448768 0.0028911552 0.0055141725 0.1563480000 957953689 0 402718720 0.1098570228 -0.0107135633 -0.0769849345 80 3.1600000000 0.0028414016 0.0020548334 0.0028911552 0.0054978325 0.1675120000 957955697 0 402718720 0.1136277840 -0.0110425306 -0.0798503086 81 3.2000000000 0.0029430005 0.0020657984 0.0029430005 0.0054773482 0.1677350000 957957705 0 402718720 0.1192800105 -0.0124094319 -0.0814532340 82 3.2400000000 0.0029347858 0.0020763958 0.0029430005 0.0054508429 0.1546650000 957959713 0 402718720 0.1233360469 -0.0138708949 -0.0837716982 83 3.2800000000 0.0021264758 0.0020769992 0.0029430005 0.0054338654 0.1475110000 957961721 0 402718720 0.1247435957 -0.0148399798 -0.0857040063 84 3.3200000000 0.0029173617 0.0020870035 0.0029430005 0.0054140664 0.1646860000 957963729 0 402718720 0.1314363629 -0.0144078517 -0.0886911005 85 3.3600000000 0.0028966451 0.0020965287 0.0029430005 0.0053846616 0.1507980000 957965737 0 402718720 0.1419917941 -0.0111503312 -0.0887685940 86 3.4000000000 0.0018577703 0.0020937525 0.0029430005 0.0054110320 0.1446620000 957967745 0 402718720 0.1440494359 -0.0102213947 -0.0908332989 87 3.4400000000 0.0017678123 0.0020900060 0.0029430005 0.0054078402 0.1458490000 957969753 0 402718720 0.1459834427 -0.0105162803 -0.0936272815 88 3.4800000000 0.0028922819 0.0020991228 0.0029430005 0.0053797450 0.1615350000 957971761 0 402718720 0.1522506773 -0.0068647172 -0.0946386084 89 3.5200000000 0.0019396056 0.0020973305 0.0029430005 0.0053595585 0.1453600000 957973769 0 402718720 0.1546677351 -0.0075010536 -0.0956140608 90 3.5600000000 0.0017809332 0.0020938149 0.0029430005 0.0053322621 0.1564240000 957975777 0 402718720 0.1575243324 -0.0075798132 -0.0970880315 91 3.6000000000 0.0028546706 0.0021021760 0.0029430005 0.0053782922 0.1477060000 957977785 0 402718720 0.1644381732 -0.0060281539 -0.0983094648 92 3.6400000000 0.0028971331 0.0021108168 0.0029430005 0.0054547325 0.1472700000 957979793 0 402718720 0.1738345325 -0.0032201821 -0.0982870683 93 3.6800000000 0.0028776452 0.0021190623 0.0029430005 0.0054698227 0.1478060000 957981801 0 402718720 0.1819654852 0.0007601754 -0.0997446701 94 3.7200000000 0.0029976286 0.0021284087 0.0029976286 0.0054461564 0.1478020000 957983809 0 402718720 0.1903032660 0.0002172070 -0.1023088247 95 3.7600000000 0.0030175229 0.0021377678 0.0030175229 0.0054187592 0.1466780000 957985817 0 402718720 0.1964354813 0.0002121015 -0.1047839969 96 3.8000000000 0.0030820577 0.0021476042 0.0030820577 0.0054036549 0.1462000000 957987825 0 402718720 0.2039256990 -0.0009962154 -0.1067652851 97 3.8400000000 0.0030547914 0.0021569566 0.0030820577 0.0053778729 0.1434380000 957989833 0 402718720 0.2118432224 0.0004567825 -0.1098656878 98 3.8800000000 0.0031278648 0.0021668639 0.0031278648 0.0053511350 0.1436800000 957991841 0 402718720 0.2203851491 0.0006078994 -0.1106899753 99 3.9200000000 0.0031468030 0.0021767622 0.0031468030 0.0053611385 0.1435060000 957993849 0 402718720 0.2286089510 -0.0000054564 -0.1125906631 100 3.9600000000 0.0031819690 0.0021868143 0.0031819690 0.0053360638 0.1443570000 957995857 0 402718720 0.2362660468 0.0004133649 -0.1130118966 101 4.0000000000 0.0031512326 0.0021963630 0.0031819690 0.0053255152 0.1439790000 957997865 0 402718720 0.2448963225 0.0024853835 -0.1143301353 102 4.0400000000 0.0019541215 0.0021939881 0.0031819690 0.0053461540 0.1405220000 957999873 0 402718720 0.2483413368 0.0012674213 -0.1158779189 103 4.0800000000 0.0031081501 0.0022028634 0.0031819690 0.0053202938 0.1403470000 958001881 0 402718720 0.2576069832 0.0051586400 -0.1156236306 104 4.1200000000 0.0031515046 0.0022119850 0.0031819690 0.0052956298 0.1415140000 958003889 0 402718720 0.2680374384 0.0078306748 -0.1163256839 105 4.1600000000 0.0031953971 0.0022213508 0.0031953971 0.0052876396 0.1549160000 958005897 0 402718720 0.2746449113 0.0092011662 -0.1165759712 106 4.2000000000 0.0032492287 0.0022310478 0.0032492287 0.0052999995 0.1417630000 958007905 0 402718720 0.2815676332 0.0075068325 -0.1190994754 107 4.2400000000 0.0032656051 0.0022407165 0.0032656051 0.0052772191 0.1426010000 958009913 0 402718720 0.2894890308 0.0065852581 -0.1203103736 108 4.2800000000 0.0032523160 0.0022500832 0.0032656051 0.0052608711 0.1416720000 958011921 0 402718720 0.2981435061 0.0067418320 -0.1220750809 109 4.3200000000 0.0034316122 0.0022609229 0.0034316122 0.0052409632 0.1441970000 958013929 0 402718720 0.3153148293 0.0065531195 -0.1246539578 110 4.3600000000 0.0032862672 0.0022702442 0.0034316122 0.0052373759 0.1504500000 958015937 0 402718720 0.3273338974 0.0074597890 -0.1253696829 111 4.4000000000 0.0033446501 0.0022799236 0.0034316122 0.0052138624 0.1531630000 958017945 0 402718720 0.3371126056 0.0067616515 -0.1270623952 112 4.4400000000 0.0025937555 0.0022827256 0.0034316122 0.0051936843 0.1370310000 958019953 0 402718720 0.3409490883 0.0028745744 -0.1290723681 113 4.4800000000 0.0032920456 0.0022916577 0.0034316122 0.0051713297 0.1377660000 958021961 0 402718720 0.3518305123 0.0019344731 -0.1304047406 114 4.5200000000 0.0033079246 0.0023005723 0.0034316122 0.0051551824 0.1391090000 958023969 0 402718720 0.3627982736 0.0018333996 -0.1312971711 115 4.5600000000 0.0033374361 0.0023095885 0.0034316122 0.0051423449 0.1385330000 958025977 0 402718720 0.3727828860 -0.0000177651 -0.1325938404 116 4.6000000000 0.0033886214 0.0023188905 0.0034316122 0.0051222297 0.1509140000 958027985 0 402718720 0.3806793392 -0.0029457759 -0.1341944933 117 4.6400000000 0.0034055091 0.0023281778 0.0034316122 0.0051267831 0.1379520000 958029993 0 402718720 0.3881561458 -0.0054621208 -0.1353448033 118 4.6800000000 0.0033768520 0.0023370649 0.0034316122 0.0051400146 0.1348670000 958032001 0 402718720 0.3974271715 -0.0055805328 -0.1357124448 119 4.7200000000 0.0033884572 0.0023459001 0.0034316122 0.0051784464 0.1487540000 958034009 0 402718720 0.4115480781 -0.0048997169 -0.1338303238 120 4.7600000000 0.0033978519 0.0023546664 0.0034316122 0.0051570124 0.1523300000 958036017 0 402718720 0.4227998853 -0.0030114816 -0.1324203908 121 4.8000000000 0.0034966890 0.0023641046 0.0034966890 0.0051525468 0.1373630000 958038025 0 402718720 0.4312398732 -0.0041030943 -0.1339130849 122 4.8400000000 0.0035005009 0.0023734193 0.0035005009 0.0051514871 0.1365610000 958040033 0 402718720 0.4402772486 -0.0036343038 -0.1344349533 123 4.8800000000 0.0035132666 0.0023826864 0.0035132666 0.0051313308 0.1340340000 958042041 0 402718720 0.4517447054 -0.0013775522 -0.1324630976 124 4.9200000000 0.0036396210 0.0023928230 0.0036396210 0.0051119588 0.1361590000 958044049 0 402718720 0.4582335949 0.0001488961 -0.1292468011 125 4.9600000000 0.0036924575 0.0024032200 0.0036924575 0.0051036752 0.1349940000 958046057 0 402718720 0.4616668820 -0.0000656663 -0.1277967244 126 5.0000000000 0.0036436839 0.0024130650 0.0036924575 0.0050895492 0.1331200000 958048065 0 402718720 0.4709686935 -0.0000412657 -0.1260652989 127 5.0400000000 0.0036842474 0.0024230743 0.0036924575 0.0050722723 0.1363090000 958050073 0 402718720 0.4811779857 -0.0001764489 -0.1238918230 128 5.0800000000 0.0036821619 0.0024329109 0.0036924575 0.0050663726 0.1359260000 958052081 0 402718720 0.4930610359 0.0010823732 -0.1205547452 129 5.1200000000 0.0037087507 0.0024428011 0.0037087507 0.0050590635 0.1360740000 958054089 0 402718720 0.5042008162 0.0024149958 -0.1170087680 130 5.1600000000 0.0037752776 0.0024530510 0.0037752776 0.0050410908 0.1427810000 958081697 0 402718720 0.5108767748 0.0033421733 -0.1145466641 131 5.2000000000 0.0039141211 0.0024642042 0.0039141211 0.0050755683 0.1351990000 958083705 0 402718720 0.5175769329 0.0026556416 -0.1114232466 132 5.2400000000 0.0038248545 0.0024745121 0.0039141211 0.0050616276 0.1332960000 958085713 0 402718720 0.5283134580 0.0030544244 -0.1076138541 133 5.2800000000 0.0038343617 0.0024847366 0.0039141211 0.0050425570 0.1382330000 958087721 0 402718720 0.5389282107 0.0039385138 -0.1031937972 134 5.3200000000 0.0039213486 0.0024954575 0.0039213486 0.0050898151 0.1752330000 958089729 0 402718720 0.5475151539 0.0037312428 -0.1005027965 135 5.3600000000 0.0038947489 0.0025058227 0.0039213486 0.0051037464 0.1395160000 958091737 0 402718720 0.5573081970 0.0046834592 -0.0970828012 136 5.4000000000 0.0040543145 0.0025172086 0.0040543145 0.0051307303 0.1513850000 958093745 0 402718720 0.5714303851 0.0125525016 -0.0908371583 137 5.4400000000 0.0038863500 0.0025272024 0.0040543145 0.0051272532 0.1350150000 958095753 0 402718720 0.5766429901 0.0160846952 -0.0870523527 138 5.4800000000 0.0040177759 0.0025380036 0.0040543145 0.0051728886 0.1348230000 958097761 0 402718720 0.5802221298 0.0152731836 -0.0841876715 139 5.5200000000 0.0039009470 0.0025478090 0.0040543145 0.0051544398 0.1340820000 958099769 0 402718720 0.5890872478 0.0157636777 -0.0792166814 140 5.5600000000 0.0039087958 0.0025575303 0.0040543145 0.0051379292 0.1330800000 958101777 0 402718720 0.5975136161 0.0169881433 -0.0740917027 141 5.6000000000 0.0039192298 0.0025671878 0.0040543145 0.0051198734 0.1453870000 958103785 0 402718720 0.6061491966 0.0179555453 -0.0692370534 142 5.6400000000 0.0039341692 0.0025768144 0.0040543145 0.0051049724 0.1337480000 958105793 0 402718720 0.6170749068 0.0184191819 -0.0640323237 143 5.6800000000 0.0039611896 0.0025864953 0.0040543145 0.0050950543 0.1319560000 958107801 0 402718720 0.6261444688 0.0203893650 -0.0587831885 144 5.7200000000 0.0040458259 0.0025966296 0.0040543145 0.0051135535 0.1456060000 958109809 0 402718720 0.6321429610 0.0205366891 -0.0543427654 145 5.7600000000 0.0039929757 0.0026062595 0.0040543145 0.0051006937 0.1322260000 958111817 0 402718720 0.6401041150 0.0209162496 -0.0490514524 146 5.8000000000 0.0039767949 0.0026156468 0.0040543145 0.0050855314 0.1319610000 958113825 0 402718720 0.6498996615 0.0223785620 -0.0428840220 147 5.8400000000 0.0039171749 0.0026245007 0.0040543145 0.0050682742 0.1310220000 958115833 0 402718720 0.6592555642 0.0262462348 -0.0367671028 148 5.8800000000 0.0040819859 0.0026343486 0.0040819859 0.0050915207 0.1311510000 958117841 0 402718720 0.6635389328 0.0261603035 -0.0320643149 149 5.9200000000 0.0040155151 0.0026436181 0.0040819859 0.0050768198 0.1309990000 958119849 0 402718720 0.6692813635 0.0255216397 -0.0276736058 150 5.9600000000 0.0038971484 0.0026519750 0.0040819859 0.0050821351 0.1307660000 958121857 0 402718720 0.6772214770 0.0284909606 -0.0216728393 151 6.0000000000 0.0038542778 0.0026599373 0.0040819859 0.0050790268 0.1310110000 958123865 0 402718720 0.6849819422 0.0306794625 -0.0169163141 152 6.0400000000 0.0040454618 0.0026690526 0.0040819859 0.0050872759 0.1419760000 958125873 0 402718720 0.6983616948 0.0303435586 -0.0079047512 153 6.0800000000 0.0039551766 0.0026774586 0.0040819859 0.0051057877 0.1304070000 958127881 0 402718720 0.7060858011 0.0313268602 -0.0024990081 154 6.1200000000 0.0040238150 0.0026862012 0.0040819859 0.0050893841 0.1303080000 958129889 0 402718720 0.7123118043 0.0330428854 0.0025297508 155 6.1600000000 0.0040652058 0.0026950980 0.0040819859 0.0050891111 0.1285400000 958131897 0 402718720 0.7165555954 0.0331043750 0.0067754108 156 6.2000000000 0.0039799847 0.0027033345 0.0040819859 0.0051024040 0.1296080000 958133905 0 402718720 0.7251713872 0.0345485881 0.0124246478 157 6.2400000000 0.0041064378 0.0027122714 0.0041064378 0.0051123880 0.1298430000 958135913 0 402718720 0.7319690585 0.0357531682 0.0183884967 158 6.2800000000 0.0041087535 0.0027211099 0.0041087535 0.0051218226 0.1298390000 958137921 0 402718720 0.7365732789 0.0366623364 0.0241570026 159 6.3200000000 0.0040516607 0.0027294782 0.0041087535 0.0051515556 0.1295940000 958139929 0 402718720 0.7438685894 0.0387646332 0.0310145766 160 6.3600000000 0.0042682234 0.0027390953 0.0042682234 0.0052057409 0.1277010000 958141937 0 402718720 0.7575134039 0.0424853191 0.0452470519 161 6.4000000000 0.0041201110 0.0027476730 0.0042682234 0.0052305854 0.1276020000 958143945 0 402718720 0.7614229918 0.0448120460 0.0521190949 162 6.4400000000 0.0040181442 0.0027555155 0.0042682234 0.0052205907 0.1393070000 958145953 0 402718720 0.7664716244 0.0471780859 0.0598556697 163 6.4800000000 0.0039647310 0.0027629340 0.0042682234 0.0052296168 0.1289430000 958147961 0 402718720 0.7729125023 0.0480163917 0.0679462925 164 6.5200000000 0.0039410829 0.0027701178 0.0042682234 0.0052400842 0.1289610000 958149969 0 402718720 0.7806473374 0.0479283258 0.0760342777 165 6.5600000000 0.0039441083 0.0027772329 0.0042682234 0.0052466556 0.1300820000 958151977 0 402718720 0.7893341184 0.0507063158 0.0848554745 166 6.6000000000 0.0039693499 0.0027844143 0.0042682234 0.0052689780 0.1302130000 958153985 0 402718720 0.7973358631 0.0546688810 0.0939115509 167 6.6400000000 0.0040439186 0.0027919563 0.0042682234 0.0053199347 0.1400690000 958155993 0 402718720 0.8017267585 0.0565982535 0.1020743772 168 6.6800000000 0.0038962802 0.0027985296 0.0042682234 0.0053244078 0.1287700000 958158001 0 402718720 0.8086860180 0.0589743517 0.1108892485 169 6.7200000000 0.0039222832 0.0028051790 0.0042682234 0.0053183858 0.1288800000 958160009 0 402718720 0.8174862266 0.0635400191 0.1214957163 170 6.7600000000 0.0039200275 0.0028117370 0.0042682234 0.0053318522 0.1397890000 958162017 0 402718720 0.8231530786 0.0649555400 0.1297683567 171 6.8000000000 0.0039411774 0.0028183419 0.0042682234 0.0053163504 0.1289940000 958164025 0 402718720 0.8325630426 0.0677797794 0.1400122195 172 6.8400000000 0.0040375614 0.0028254304 0.0042682234 0.0053008780 0.1304090000 958166033 0 402718720 0.8407405019 0.0704818666 0.1502694041 173 6.8800000000 0.0039787525 0.0028320970 0.0042682234 0.0052860606 0.1289970000 958168041 0 402718720 0.8445323706 0.0704556182 0.1574949473 174 6.9200000000 0.0039122282 0.0028383046 0.0042682234 0.0052783938 0.1290370000 958170049 0 402718720 0.8528645039 0.0726808235 0.1672872007 175 6.9600000000 0.0038918396 0.0028443248 0.0042682234 0.0052662553 0.1291140000 958172057 0 402718720 0.8625745177 0.0764471367 0.1777749509 176 7.0000000000 0.0040571825 0.0028512161 0.0042682234 0.0052513774 0.1295920000 958174065 0 402718720 0.8695515990 0.0789998695 0.1877011210 177 7.0400000000 0.0040120692 0.0028577746 0.0042682234 0.0052909529 0.1303600000 958176073 0 402718720 0.8742123246 0.0788791701 0.1958895326 178 7.0800000000 0.0039687706 0.0028640161 0.0042682234 0.0053191610 0.1295680000 958178081 0 402718720 0.8784831762 0.0788844079 0.2037319690 179 7.1200000000 0.0039327713 0.0028699868 0.0042682234 0.0053048584 0.1316280000 958180089 0 402718720 0.8844794631 0.0814085007 0.2129374295 180 7.1600000000 0.0038100588 0.0028752094 0.0042682234 0.0052954936 0.1336340000 958182097 0 402718720 0.8906422853 0.0827462375 0.2220885903 181 7.2000000000 0.0039158328 0.0028809587 0.0042682234 0.0052809997 0.1344950000 958184105 0 402718720 0.8945523500 0.0835244954 0.2309090942 182 7.2400000000 0.0037000333 0.0028854591 0.0042682234 0.0052676727 0.1478410000 958186113 0 402718720 0.9001302123 0.0853598416 0.2395846397 183 7.2800000000 0.0037449428 0.0028901558 0.0042682234 0.0052534033 0.1331840000 958188121 0 402718720 0.9054288268 0.0875841379 0.2489519566 184 7.3200000000 0.0036313820 0.0028941842 0.0042682234 0.0052458370 0.1344070000 958190129 0 402718720 0.9108033180 0.0882281885 0.2565353215 185 7.3600000000 0.0021457204 0.0028901384 0.0042682234 0.0052418567 0.1292880000 958192137 0 402718720 0.9126217961 0.0875005350 0.2631379664 186 7.4000000000 0.0036092610 0.0028940047 0.0042682234 0.0052277754 0.1356980000 958194145 0 402718720 0.9199641347 0.0893963501 0.2720237374 187 7.4400000000 0.0037003618 0.0028983167 0.0042682234 0.0052269878 0.1370030000 958196153 0 402718720 0.9250162244 0.0904610157 0.2793056369 188 7.4800000000 0.0037861082 0.0029030390 0.0042682234 0.0052136617 0.1374850000 958198161 0 402718720 0.9292441010 0.0913816020 0.2859705985 189 7.5200000000 0.0027655491 0.0029023116 0.0042682234 0.0052020127 0.1333730000 958200169 0 402718720 0.9313372374 0.0908785388 0.2925797105 190 7.5600000000 0.0037120057 0.0029065731 0.0042682234 0.0051962177 0.1592550000 958202177 0 402718720 0.9374547601 0.0919723660 0.3004256487 191 7.6000000000 0.0039387788 0.0029119774 0.0042682234 0.0051862931 0.1808340000 958204185 0 402718720 0.9414691925 0.0939215869 0.3085897267 192 7.6400000000 0.0040996410 0.0029181631 0.0042682234 0.0051731528 0.1820590000 958206193 0 402718720 0.9444317222 0.0954937041 0.3169984519 193 7.6800000000 0.0043495288 0.0029255795 0.0043495288 0.0051606318 0.1835840000 958208201 0 402718720 0.9501469135 0.0973960459 0.3323294520 194 7.7200000000 0.0041079423 0.0029316742 0.0043495288 0.0051472523 0.1410980000 958210209 0 402718720 0.9535560012 0.0998340175 0.3411498666 195 7.7600000000 0.0040506106 0.0029374123 0.0043495288 0.0051341134 0.1482000000 958212217 0 402718720 0.9582210183 0.1014283672 0.3597728908 196 7.8000000000 0.0043642516 0.0029446921 0.0043642516 0.0051269325 0.1574310000 958214225 0 402718720 0.9588878155 0.1004416868 0.3683659434 197 7.8400000000 0.0043537337 0.0029518446 0.0043642516 0.0051150435 0.1575400000 958216233 0 402718720 0.9614702463 0.1012364551 0.3785602152 198 7.8800000000 0.0044339360 0.0029593299 0.0044339360 0.0051021699 0.1462590000 958218241 0 402718720 0.9636116624 0.1019134149 0.3895016015 199 7.9200000000 0.0045006555 0.0029670752 0.0045006555 0.0050968748 0.1470280000 958220249 0 402718720 0.9638087749 0.1010551527 0.3995255828 200 7.9600000000 0.0045156945 0.0029748183 0.0045156945 0.0050860318 0.1474970000 958222257 0 402718720 0.9659602642 0.1018984467 0.4104884267 201 8.0000000000 0.0041472837 0.0029806515 0.0045156945 0.0050745150 0.1522600000 958224265 0 402718720 0.9679492712 0.1016932875 0.4221303761 202 8.0400000000 0.0041389791 0.0029863858 0.0045156945 0.0050626556 0.1640910000 958226273 0 402718720 0.9676861763 0.1020395160 0.4324451387 203 8.0800000000 0.0041510887 0.0029921232 0.0045156945 0.0050504339 0.1528540000 958228281 0 402718720 0.9675364494 0.1023445874 0.4431119263 204 8.1200000000 0.0041364124 0.0029977325 0.0045156945 0.0050411662 0.1546310000 958230289 0 402718720 0.9676662683 0.1037508845 0.4538073242 205 8.1600000000 0.0041683563 0.0030034429 0.0045156945 0.0050525957 0.1536820000 958232297 0 402718720 0.9688150883 0.1055704132 0.4655386508 206 8.1999999990 0.0041745682 0.0030091279 0.0045156945 0.0050596006 0.1538620000 958234305 0 402718720 0.9694688916 0.1077008769 0.4777162075 207 8.2400000000 0.0041914321 0.0030148396 0.0045156945 0.0050553441 0.1523300000 958236313 0 402718720 0.9703521132 0.1100864559 0.4905178547 208 8.2799999990 0.0041813566 0.0030204478 0.0045156945 0.0050559892 0.1541570000 958238321 0 402718720 0.9700189829 0.1131418422 0.5022591949 209 8.3200000000 0.0046338690 0.0030281675 0.0046338690 0.0050512660 0.1502700000 958240329 0 402718720 0.9706266522 0.1147573963 0.5137479305 210 8.3599999990 0.0042253137 0.0030338682 0.0046338690 0.0050397683 0.1561330000 958242337 0 402718720 0.9708749652 0.1162163839 0.5259921551 211 8.4000000000 0.0042061042 0.0030394238 0.0046338690 0.0050358787 0.1569220000 958244345 0 402718720 0.9713025093 0.1183286309 0.5383704901 212 8.4399999990 0.0042145359 0.0030449668 0.0046338690 0.0050289607 0.1729410000 958246353 0 402718720 0.9703655243 0.1200784743 0.5507315993 213 8.4800000000 0.0042071734 0.0030504232 0.0046338690 0.0050210450 0.1712320000 958248361 0 402718720 0.9690882564 0.1220575497 0.5622543693 214 8.5200000000 0.0041973931 0.0030557829 0.0046338690 0.0050167267 0.1568990000 958250369 0 402718720 0.9683570862 0.1242331788 0.5735767484 215 8.5600000000 0.0042099948 0.0030611513 0.0046338690 0.0050076629 0.1750500000 958252377 0 402718720 0.9685098529 0.1274763942 0.5857247710 216 8.6000000000 0.0041863061 0.0030663603 0.0046338690 0.0049991345 0.1596910000 958254385 0 402718720 0.9691536427 0.1296991259 0.5980769992 217 8.6400000000 0.0041832393 0.0030715073 0.0046338690 0.0049924829 0.1580870000 958256393 0 402718720 0.9680223465 0.1312892884 0.6089701056 218 8.6800000000 0.0041733379 0.0030765615 0.0046338690 0.0049871717 0.1626730000 958258401 0 402718720 0.9663307071 0.1327971071 0.6196522713 219 8.7200000000 0.0041706911 0.0030815576 0.0046338690 0.0049804117 0.1761020000 958260409 0 402718720 0.9635533690 0.1338452995 0.6299848557 220 8.7600000000 0.0041751019 0.0030865282 0.0046338690 0.0049708116 0.1633640000 958262417 0 402718720 0.9602301717 0.1341583133 0.6395584345 221 8.8000000000 0.0041722152 0.0030914408 0.0046338690 0.0049599759 0.1627810000 958264425 0 402718720 0.9605767131 0.1364862770 0.6516402364 222 8.8400000000 0.0041672303 0.0030962867 0.0046338690 0.0049509058 0.1897480000 958266433 0 402718720 0.9589774013 0.1371763945 0.6623820662 223 8.8800000000 0.0045769322 0.0031029264 0.0046338690 0.0049399006 0.1728730000 958268441 0 402718720 0.9566556215 0.1372136325 0.6717545986 224 8.9200000000 0.0041693258 0.0031076871 0.0046338690 0.0049295266 0.1654340000 958270449 0 402718720 0.9545654655 0.1377396584 0.6823644042 225 8.9600000000 0.0043851770 0.0031133648 0.0046338690 0.0049223337 0.1582740000 958272457 0 402718720 0.9545682669 0.1393852681 0.6935693026 226 9.0000000000 0.0041563720 0.0031179799 0.0046338690 0.0049118213 0.1672840000 958274465 0 402718720 0.9553531408 0.1416684687 0.7155798078 227 9.0400000000 0.0044108196 0.0031236752 0.0046338690 0.0049009501 0.1628130000 958276473 0 402718720 0.9558491111 0.1438558549 0.7261607051 228 9.0800000000 0.0044533578 0.0031295072 0.0046338690 0.0048918019 0.1632640000 958278481 0 402718720 0.9534536004 0.1454258412 0.7351965308 229 9.1200000000 0.0044163428 0.0031351265 0.0046338690 0.0049033469 0.1636060000 958280489 0 402718720 0.9536622167 0.1471760422 0.7463607192 230 9.1600000000 0.0043507898 0.0031404120 0.0046338690 0.0049003517 0.1648890000 958282497 0 402718720 0.9542909861 0.1485427916 0.7566015124 231 9.2000000000 0.0041650860 0.0031448479 0.0046338690 0.0048958390 0.1830810000 958284505 0 402718720 0.9534247518 0.1498360485 0.7753663063 232 9.2400000000 0.0043454063 0.0031500227 0.0046338690 0.0048886305 0.1647840000 958286513 0 402718720 0.9542789459 0.1523482203 0.7872371078 233 9.2800000000 0.0043044561 0.0031549773 0.0046338690 0.0048896446 0.1658740000 958288521 0 402718720 0.9549952149 0.1549063623 0.7993053794 234 9.3200000000 0.0042851819 0.0031598073 0.0046338690 0.0048887015 0.1665080000 958290529 0 402718720 0.9540407062 0.1575793624 0.8100904226 235 9.3600000000 0.0042358870 0.0031643863 0.0046338690 0.0048868561 0.1679850000 958292537 0 402718720 0.9538798928 0.1588152051 0.8209272623 236 9.4000000000 0.0042043393 0.0031687929 0.0046338690 0.0048816959 0.1701970000 958294545 0 402718720 0.9553098679 0.1595605910 0.8304805756 237 9.4400000000 0.0042807758 0.0031734848 0.0046338690 0.0048892645 0.1690910000 958296553 0 402718720 0.9561720490 0.1621243656 0.8414706588 238 9.4800000000 0.0042982530 0.0031782107 0.0046338690 0.0048874172 0.2037920000 958298561 0 402718720 0.9569518566 0.1637745947 0.8522574902 239 9.5200000000 0.0042540040 0.0031827120 0.0046338690 0.0048937410 0.1969080000 958300569 0 402718720 0.9587509632 0.1659594029 0.8630270362 240 9.5600000000 0.0043149381 0.0031874296 0.0046338690 0.0048913967 0.1675080000 958302577 0 402718720 0.9585285783 0.1668544412 0.8725351691 241 9.6000000000 0.0042877179 0.0031919951 0.0046338690 0.0048812625 0.1671780000 958304585 0 402718720 0.9567850828 0.1683046669 0.8822685480 242 9.6400000000 0.0041241199 0.0031958468 0.0046338690 0.0048837444 0.1811600000 958306593 0 402718720 0.9577890635 0.1708324105 0.8945515752 243 9.6800000000 0.0042064041 0.0032000055 0.0046338690 0.0048745513 0.1658500000 958308601 0 402718720 0.9609094262 0.1731590182 0.9081047773 244 9.7200000000 0.0042012553 0.0032041090 0.0046338690 0.0048645149 0.1668710000 958310609 0 402718720 0.9622604847 0.1769102067 0.9201515317 245 9.7600000000 0.0041794926 0.0032080901 0.0046338690 0.0048566881 0.1656370000 958312617 0 402718720 0.9621590376 0.1777381152 0.9298111200 246 9.8000000000 0.0041541955 0.0032119361 0.0046338690 0.0048467764 0.1775240000 958314625 0 402718720 0.9638194442 0.1804417074 0.9415011406 247 9.8400000000 0.0041929106 0.0032159077 0.0046338690 0.0048371249 0.1617890000 958316633 0 402718720 0.9640447497 0.1831383258 0.9531688094 248 9.8800000000 0.0041103708 0.0032195144 0.0046338690 0.0048315453 0.1622470000 958318641 0 402718720 0.9638782740 0.1862635761 0.9632844329 249 9.9200000000 0.0041322829 0.0032231801 0.0046338690 0.0048218394 0.1614010000 958320649 0 402718720 0.9653126001 0.1874261796 0.9740322828 250 9.9600000000 0.0041391454 0.0032268440 0.0046338690 0.0048126026 0.1607150000 958322657 0 402718720 0.9658624530 0.1893037558 0.9848653674 251 10.0000000000 0.0041001113 0.0032303231 0.0046338690 0.0048046592 0.1605710000 958324665 0 402718720 0.9653480053 0.1901103258 0.9940466881 252 10.0400000000 0.0040069232 0.0032334049 0.0046338690 0.0047951082 0.1792960000 958326673 0 402718720 0.9657717943 0.1917069852 1.0036536455 253 10.0800000000 0.0039895237 0.0032363935 0.0046338690 0.0047862675 0.1588740000 958328681 0 402718720 0.9659602642 0.1934951693 1.0130659342 254 10.1200000000 0.0039447658 0.0032391823 0.0046338690 0.0047808451 0.1596840000 958330689 0 402718720 0.9662425518 0.1954727322 1.0223901272 255 10.1600000000 0.0039305179 0.0032418935 0.0046338690 0.0047717755 0.1561680000 958332697 0 402718720 0.9655516148 0.1972343326 1.0315575600 256 10.2000000000 0.0040074284 0.0032448838 0.0046338690 0.0047715249 0.1515760000 958334705 0 402718720 0.9646557570 0.1978599876 1.0389411449 257 10.2400000000 0.0038306441 0.0032471631 0.0046338690 0.0047845802 0.1677260000 958336713 0 402718720 0.9635266662 0.1996938437 1.0480190516 258 10.2800000000 0.0037993239 0.0032493032 0.0046338690 0.0047859614 0.1550340000 958389921 0 402718720 0.9637370110 0.2015088946 1.0576347113 259 10.3200000000 0.0040900274 0.0032525493 0.0046338690 0.0047935799 0.1490510000 958391929 0 402718720 0.9633805752 0.2024909407 1.0652678013 260 10.3600000000 0.0042032795 0.0032562059 0.0046338690 0.0048003368 0.1492310000 958393937 0 402718720 0.9613205791 0.2032720447 1.0727158785 261 10.4000000000 0.0037811254 0.0032582171 0.0046338690 0.0047926985 0.1579020000 958395945 0 402718720 0.9593787193 0.2059674561 1.0828557014 262 10.4400000000 0.0037876975 0.0032602380 0.0046338690 0.0047835495 0.1614140000 958397953 0 402718720 0.9602681398 0.2073068321 1.0919960737 263 10.4800000000 0.0038296820 0.0032624032 0.0046338690 0.0047744416 0.1478840000 958399961 0 402718720 0.9597908258 0.2089803368 1.1015858650 264 10.5200000000 0.0039632143 0.0032650578 0.0046338690 0.0047679168 0.1428850000 958401969 0 402718720 0.9582006931 0.2096201777 1.1093323231 265 10.5600000000 0.0038496109 0.0032672636 0.0046338690 0.0047604992 0.1418890000 958403977 0 402718720 0.9567525983 0.2098154277 1.1168683767 266 10.6000000000 0.0037674168 0.0032691439 0.0046338690 0.0047520088 0.1456780000 958405985 0 402718720 0.9573754668 0.2108780891 1.1256438494 267 10.6400000000 0.0038035794 0.0032711456 0.0046338690 0.0047450095 0.1427230000 958407993 0 402718720 0.9565927982 0.2122336477 1.1342675686 268 10.6800000000 0.0038132649 0.0032731684 0.0046338690 0.0047388029 0.1438480000 958410001 0 402718720 0.9554553032 0.2143463790 1.1436506510 269 10.7200000000 0.0038139566 0.0032751788 0.0046338690 0.0047348596 0.1432060000 958412009 0 402718720 0.9537364244 0.2151249647 1.1528531313 270 10.7600000000 0.0038104823 0.0032771614 0.0046338690 0.0047287796 0.1427320000 958414017 0 402718720 0.9516995549 0.2175208032 1.1619677544 271 10.8000000000 0.0038402528 0.0032792392 0.0046338690 0.0047216690 0.1407150000 958416025 0 402718720 0.9496126175 0.2194697708 1.1719077826 272 10.8400000000 0.0038503001 0.0032813387 0.0046338690 0.0047129498 0.1543330000 958418033 0 402718720 0.9468082786 0.2213394493 1.1811468601 273 10.8800000000 0.0051136017 0.0032880503 0.0051136017 0.0047067270 0.1359390000 958420041 0 402718720 0.9439341426 0.2226279527 1.1893196106 274 10.9200000000 0.0036558199 0.0032893925 0.0051136017 0.0046987966 0.1459140000 958422049 0 402718720 0.9413195848 0.2238009572 1.2006106377 275 10.9600000000 0.0038558594 0.0032914524 0.0051136017 0.0046929477 0.1397430000 958424057 0 402718720 0.9389168620 0.2275307029 1.2101043463 276 11.0000000000 0.0053272336 0.0032988284 0.0053272336 0.0046899588 0.1474890000 958426065 0 402718720 0.9363133907 0.2277789265 1.2171150446 277 11.0400000000 0.0036743735 0.0033001841 0.0053272336 0.0046834016 0.1537080000 958428073 0 402718720 0.9347560406 0.2288938761 1.2293010950 278 11.0800000000 0.0036889494 0.0033015826 0.0053272336 0.0046749408 0.1433400000 958430081 0 402718720 0.9296814203 0.2299994379 1.2382401228 279 11.1200000000 0.0056260433 0.0033099140 0.0056260433 0.0046676995 0.1342760000 958432089 0 402718720 0.9263824821 0.2312981784 1.2464027405 280 11.1600000000 0.0036861841 0.0033112578 0.0056260433 0.0046619882 0.1436520000 958434097 0 402718720 0.9224514365 0.2325774431 1.2582784891 281 11.2000000000 0.0037006100 0.0033126434 0.0056260433 0.0046539045 0.1532950000 958436105 0 402718720 0.9203705788 0.2363504022 1.2677234411 282 11.2400000000 0.0037075004 0.0033140436 0.0056260433 0.0046463028 0.1563170000 958438113 0 402718720 0.9169356227 0.2374161333 1.2764178514 283 11.2800000000 0.0036891715 0.0033153691 0.0056260433 0.0046389543 0.1559960000 958440121 0 402718720 0.9137601256 0.2405655682 1.2859855890 284 11.3200000000 0.0037079311 0.0033167514 0.0056260433 0.0046317052 0.1428810000 958442129 0 402718720 0.9087925553 0.2432248145 1.2969768047 285 11.3600000000 0.0055472716 0.0033245778 0.0056260433 0.0046276532 0.1327080000 958444137 0 402718720 0.9054068923 0.2450505197 1.3048368692 286 11.4000000000 0.0036734447 0.0033257976 0.0056260433 0.0046275266 0.1598350000 958446145 0 402718720 0.9052634835 0.2472815663 1.3163710833 287 11.4400000000 0.0037011937 0.0033271056 0.0056260433 0.0046202932 0.1415220000 958448153 0 402718720 0.9027751088 0.2506963611 1.3253605366 288 11.4800000000 0.0037042352 0.0033284151 0.0056260433 0.0046123772 0.1407460000 958450161 0 402718720 0.8957133889 0.2516555488 1.3320984840 289 11.5200000000 0.0056048180 0.0033362919 0.0056260433 0.0046101267 0.1317860000 958452169 0 402718720 0.8914423585 0.2516550720 1.3384238482 290 11.5600000000 0.0037047404 0.0033375624 0.0056260433 0.0046079704 0.1540400000 958454177 0 402718720 0.8872446418 0.2511865497 1.3482174873 291 11.6000000000 0.0038394837 0.0033392872 0.0056260433 0.0046002603 0.1342380000 958456185 0 402718720 0.8849486709 0.2537653148 1.3565192223 292 11.6400000000 0.0052107205 0.0033456962 0.0056260433 0.0045933817 0.1294080000 958458193 0 402718720 0.8828863502 0.2552660108 1.3635115623 293 11.6800000000 0.0049791704 0.0033512712 0.0056260433 0.0045858579 0.1293390000 958460201 0 402718720 0.8811645508 0.2570044696 1.3700922728 294 11.7200000000 0.0055065346 0.0033586021 0.0056260433 0.0045825510 0.1301280000 958462209 0 402718720 0.8773736358 0.2568358779 1.3764470816 295 11.7600000000 0.0038672686 0.0033603264 0.0056260433 0.0045893229 0.1344350000 958464217 0 402718720 0.8748800755 0.2564430237 1.3850313425 296 11.8000000000 0.0045558750 0.0033643654 0.0056260433 0.0046026571 0.1397260000 958466225 0 402718720 0.8729678392 0.2572740316 1.3923300505 297 11.8400000000 0.0048597953 0.0033694005 0.0056260433 0.0046293270 0.1302610000 958468233 0 402718720 0.8688979745 0.2573598027 1.3994591236 298 11.8800000000 0.0036915597 0.0033704816 0.0056260433 0.0046472018 0.1343940000 958470241 0 402718720 0.8650977015 0.2563511729 1.4088975191 299 11.9200000000 0.0035437951 0.0033710612 0.0056260433 0.0046460747 0.1459300000 958472249 0 402718720 0.8631517291 0.2559105158 1.4170782566 300 11.9600000000 0.0034758407 0.0033714105 0.0056260433 0.0046448752 0.1331060000 958474257 0 402718720 0.8613709807 0.2552580237 1.4247314930 301 12.0000000000 0.0034811231 0.0033717750 0.0056260433 0.0046404686 0.1329420000 958476265 0 402718720 0.8604859114 0.2559410632 1.4343105555 302 12.0400000000 0.0034450551 0.0033720176 0.0056260433 0.0046338720 0.1323770000 958478273 0 402718720 0.8598110676 0.2562709153 1.4429632425 303 12.0800000000 0.0034098011 0.0033721423 0.0056260433 0.0046279178 0.1320270000 958480281 0 402718720 0.8577594757 0.2555590868 1.4505237341 304 12.1200000000 0.0033687034 0.0033721310 0.0056260433 0.0046221081 0.1316260000 958482289 0 402718720 0.8566511869 0.2563835680 1.4601240158 305 12.1600000000 0.0034052588 0.0033722396 0.0056260433 0.0046146528 0.1309310000 958484297 0 402718720 0.8556894660 0.2574158013 1.4697662592 306 12.2000000000 0.0033347837 0.0033721172 0.0056260433 0.0046071957 0.1403610000 958486305 0 402718720 0.8529754281 0.2583868206 1.4786434174 307 12.2400000000 0.0032370517 0.0033716773 0.0056260433 0.0046012675 0.1298510000 958488313 0 402718720 0.8508982062 0.2601528466 1.4882504940 308 12.2800000000 0.0032138105 0.0033711647 0.0056260433 0.0045999872 0.1286590000 958490321 0 402718720 0.8498438001 0.2609150410 1.4979950190 309 12.3200000000 0.0031653703 0.0033704987 0.0056260433 0.0045982770 0.1389990000 958492329 0 402718720 0.8484081626 0.2615467906 1.5071260929 310 12.3600000000 0.0031591237 0.0033698169 0.0056260433 0.0046067916 0.1274750000 958494337 0 402718720 0.8473721743 0.2641681433 1.5171263218 311 12.4000000000 0.0032217966 0.0033693409 0.0056260433 0.0046252655 0.1263800000 958496345 0 402718720 0.8461570740 0.2664695382 1.5273408890 312 12.4400000000 0.0029570435 0.0033680194 0.0056260433 0.0046353377 0.1300710000 958498353 0 402718720 0.8450883031 0.2650296092 1.5350990295 313 12.4800000000 0.0029891417 0.0033668090 0.0056260433 0.0046356393 0.1249530000 958500361 0 402718720 0.8440327048 0.2662102282 1.5447014570 314 12.5200000000 0.0029672892 0.0033655366 0.0056260433 0.0046337183 0.1242640000 958502369 0 402718720 0.8424388170 0.2673660219 1.5539211035 315 12.5600000000 0.0028075071 0.0033637651 0.0056260433 0.0046298873 0.1345360000 958504377 0 402718720 0.8411179185 0.2682006657 1.5621117353 316 12.6000000000 0.0027220421 0.0033617343 0.0056260433 0.0046226200 0.1243460000 958506385 0 402718720 0.8419802189 0.2676458061 1.5701198578 317 12.6400000000 0.0027257730 0.0033597281 0.0056260433 0.0046157735 0.1230820000 958508393 0 402718720 0.8413627148 0.2688575089 1.5790846348 318 12.6800000000 0.0027657661 0.0033578603 0.0056260433 0.0046109505 0.1229340000 958510401 0 402718720 0.8410835862 0.2705112398 1.5880575180 319 12.7200000000 0.0025691118 0.0033553878 0.0056260433 0.0046056100 0.1273160000 958512409 0 402718720 0.8384258747 0.2731164992 1.5985673666 320 12.7600000000 0.0027404604 0.0033534661 0.0056260433 0.0046037866 0.1220930000 958514417 0 402718720 0.8361633420 0.2744390070 1.6075156927 321 12.8000000000 0.0026951565 0.0033514153 0.0056260433 0.0046146581 0.1214940000 958516425 0 402718720 0.8342602849 0.2764816582 1.6168404818 322 12.8400000000 0.0026112820 0.0033491168 0.0056260433 0.0046207281 0.1211040000 958518433 0 402718720 0.8330622911 0.2787071764 1.6258486509 323 12.8800000000 0.0025681620 0.0033466989 0.0056260433 0.0046342218 0.1203650000 958520441 0 402718720 0.8318803310 0.2801391184 1.6337972879 324 12.9200000000 0.0025107351 0.0033441188 0.0056260433 0.0046477689 0.1518760000 958522449 0 402718720 0.8307248950 0.2802295089 1.6407586336 325 12.9600000000 0.0024706314 0.0033414312 0.0056260433 0.0046594516 0.1210470000 958524457 0 402718720 0.8304221034 0.2806650102 1.6479550600 326 13.0000000000 0.0024844788 0.0033388025 0.0056260433 0.0046703478 0.1201700000 958526465 0 402718720 0.8293853998 0.2813601494 1.6561104059 327 13.0400000000 0.0024804624 0.0033361776 0.0056260433 0.0047741562 0.1240060000 958528473 0 402718720 0.8257811666 0.2859205008 1.6756495237 328 13.0800000000 0.0024744722 0.0033335504 0.0056260433 0.0047943682 0.1224440000 958530481 0 402718720 0.8239539266 0.2865529954 1.6835147142 329 13.1200000000 0.0024651962 0.0033309110 0.0056260433 0.0047989961 0.1218220000 958532489 0 402718720 0.8217454553 0.2875199616 1.6914527416 330 13.1600000000 0.0024714493 0.0033283066 0.0056260433 0.0047986357 0.1215430000 958534497 0 402718720 0.8204888105 0.2878120542 1.6987091303 331 13.2000000000 0.0024705192 0.0033257151 0.0056260433 0.0047991179 0.1339750000 958536505 0 402718720 0.8197034597 0.2877461314 1.7054501772 332 13.2400000000 0.0024488110 0.0033230738 0.0056260433 0.0047950987 0.1209110000 958538513 0 402718720 0.8185891509 0.2891735435 1.7131328583 333 13.2800000000 0.0023966744 0.0033202919 0.0056260433 0.0047916172 0.1208360000 958540521 0 402718720 0.8175519705 0.2906239033 1.7206393480 334 13.3200000000 0.0023757985 0.0033174640 0.0056260433 0.0047916401 0.1207980000 958542529 0 402718720 0.8169645071 0.2907529175 1.7266939878 335 13.3600000000 0.0023718465 0.0033146413 0.0056260433 0.0047993792 0.1323340000 958544537 0 402718720 0.8147863150 0.2935812175 1.7354129553 336 13.4000000000 0.0023807352 0.0033118618 0.0056260433 0.0048086070 0.1230860000 958546545 0 402718720 0.8124936223 0.2944495976 1.7415734529 337 13.4400000000 0.0023880177 0.0033091204 0.0056260433 0.0048262333 0.1237600000 958548553 0 402718720 0.8109463453 0.2937087417 1.7466862202 338 13.4800000000 0.0023959549 0.0033064188 0.0056260433 0.0048529928 0.1237680000 958550561 0 402718720 0.8075039387 0.2937640548 1.7521287203 339 13.5200000000 0.0024128710 0.0033037829 0.0056260433 0.0048744561 0.1253170000 958552569 0 402718720 0.8056179881 0.2954057455 1.7597196102 340 13.5600000000 0.0024059066 0.0033011421 0.0056260433 0.0048944702 0.1254820000 958554577 0 402718720 0.8011210561 0.2955899537 1.7654206753 341 13.6000000000 0.0024053792 0.0032985152 0.0056260433 0.0049075260 0.1257900000 958556585 0 402718720 0.7974275947 0.2966242433 1.7726911306 342 13.6400000000 0.0024141453 0.0032959294 0.0056260433 0.0049155849 0.1260870000 958558593 0 402718720 0.7937899828 0.2988255024 1.7808043957 343 13.6800000000 0.0024133732 0.0032933563 0.0056260433 0.0049282305 0.1263710000 958560601 0 402718720 0.7894735932 0.3022277951 1.7892349958 344 13.7200000000 0.0024191749 0.0032908151 0.0056260433 0.0049315845 0.1262720000 958562609 0 402718720 0.7855040431 0.3041643500 1.7950850725 345 13.7600000000 0.0024028206 0.0032882412 0.0056260433 0.0049325866 0.1382010000 958564617 0 402718720 0.7838651538 0.3031863272 1.7997515202 346 13.8000000000 0.0011791409 0.0032821455 0.0056260433 0.0049321078 0.1151640000 958566625 0 402718720 0.7795792222 0.3034453392 1.8037017584 347 13.8400000000 0.0023847644 0.0032795594 0.0056260433 0.0049417661 0.1253970000 958568633 0 402718720 0.7773950100 0.3028740883 1.8094657660 348 13.8800000000 0.0023722651 0.0032769522 0.0056260433 0.0049543061 0.1248980000 958570641 0 402718720 0.7727869749 0.3033342659 1.8161330223 349 13.9200000000 0.0023760381 0.0032743708 0.0056260433 0.0049635892 0.1251380000 958572649 0 402718720 0.7666091919 0.3037758470 1.8234995604 350 13.9600000000 0.0023430001 0.0032717098 0.0056260433 0.0049728921 0.1362320000 958574657 0 402718720 0.7606744766 0.3049973845 1.8311294317 351 14.0000000000 0.0023405410 0.0032690569 0.0056260433 0.0049758626 0.1249750000 958576665 0 402718720 0.7552393079 0.3065975308 1.8376027346 352 14.0400000000 0.0014904644 0.0032640040 0.0056260433 0.0049710860 0.1159450000 958578673 0 402718720 0.7481451631 0.3064351082 1.8412896395 353 14.0800000000 0.0022797508 0.0032612158 0.0056260433 0.0049744506 0.1254170000 958580681 0 402718720 0.7452916503 0.3051675260 1.8467565775 354 14.1200000000 0.0022659365 0.0032584043 0.0056260433 0.0049757270 0.1242690000 958582689 0 402718720 0.7392590046 0.3074344993 1.8558456898 355 14.1600000000 0.0010923652 0.0032523028 0.0056260433 0.0049736130 0.1253790000 958584697 0 402718720 0.7318747044 0.3081516027 1.8607550859 356 14.2000000000 0.0022705602 0.0032495450 0.0056260433 0.0049980783 0.1268410000 958586705 0 402718720 0.7271289229 0.3083047569 1.8653802872 357 14.2400000000 0.0014306320 0.0032444501 0.0056260433 0.0049970410 0.1170280000 958588713 0 402718720 0.7189401984 0.3089982271 1.8715497255 358 14.2800000000 0.0022752124 0.0032417427 0.0056260433 0.0050081567 0.1268680000 958590721 0 402718720 0.7141374350 0.3097659349 1.8773123026 359 14.3200000000 0.0022813745 0.0032390676 0.0056260433 0.0050018196 0.1392080000 958592729 0 402718720 0.7051681876 0.3133460283 1.8848830462 360 14.3600000000 0.0022689754 0.0032363729 0.0056260433 0.0050023543 0.1294720000 958594737 0 402718720 0.6892148256 0.3165159225 1.8968011141 361 14.4000000000 0.0022789091 0.0032337206 0.0056260433 0.0049966653 0.1267850000 958596745 0 402718720 0.6792961359 0.3214427233 1.9054572582 362 14.4400000000 0.0023016236 0.0032311458 0.0056260433 0.0049919452 0.1317290000 958598753 0 402718720 0.6624043584 0.3207784593 1.9117273092 363 14.4800000000 0.0020406924 0.0032278663 0.0056260433 0.0049865227 0.1175980000 958600761 0 402718720 0.6564090848 0.3194873035 1.9156509638 364 14.5200000000 0.0028298914 0.0032267729 0.0056260433 0.0049876138 0.1389870000 958602769 0 402718720 0.6498225927 0.3190532029 1.9218194485 365 14.5600000000 0.0031599461 0.0032265898 0.0056260433 0.0049810581 0.1397720000 958604777 0 402718720 0.6418319345 0.3191128075 1.9270296097 366 14.6000000000 0.0023036369 0.0032240681 0.0056260433 0.0049974480 0.1340220000 958606785 0 402718720 0.6241092682 0.3265172243 1.9414703846 367 14.6400000000 0.0026200658 0.0032224223 0.0056260433 0.0049925638 0.1315470000 958608793 0 402718720 0.6148028970 0.3303114772 1.9466184378 368 14.6800000000 0.0020874245 0.0032193381 0.0056260433 0.0049995417 0.1185140000 958610801 0 402718720 0.6051340103 0.3311116695 1.9505786896 369 14.7200000000 0.0025092349 0.0032174137 0.0056260433 0.0050078439 0.1183890000 958612809 0 402718720 0.5958106518 0.3304501772 1.9519989491 370 14.7600000000 0.0023466756 0.0032150604 0.0056260433 0.0050010689 0.1184040000 958614817 0 402718720 0.5878711939 0.3288403451 1.9535067081 371 14.8000000000 0.0023497855 0.0032127281 0.0056260433 0.0050162252 0.1195870000 958616825 0 402718720 0.5795631409 0.3289585412 1.9601620436 372 14.8400000000 0.0027334811 0.0032114398 0.0056260433 0.0050309784 0.1196020000 958618833 0 402718720 0.5711356401 0.3308479786 1.9653834105 373 14.8800000000 0.0030352930 0.0032109675 0.0056260433 0.0050333041 0.1181190000 958620841 0 402718720 0.5615245104 0.3322850168 1.9700696468 374 14.9200000000 0.0030854119 0.0032106318 0.0056260433 0.0050297308 0.1166290000 958622849 0 402718720 0.5503020287 0.3333038986 1.9734071493 375 14.9600000000 0.0026834805 0.0032092261 0.0056260433 0.0050388428 0.1277830000 958624857 0 402718720 0.5393856168 0.3333936334 1.9746128321 376 15.0000000000 0.0025981625 0.0032076009 0.0056260433 0.0050322684 0.1159860000 958626865 0 402718720 0.5302000642 0.3327701688 1.9797855616 377 15.0400000000 0.0031391822 0.0032074194 0.0056260433 0.0050264279 0.1155080000 958628873 0 402718720 0.5098172426 0.3332680762 1.9867984056 378 15.0800000000 0.0027744754 0.0032062741 0.0056260433 0.0050207423 0.1155170000 958630881 0 402718720 0.5003665686 0.3340826035 1.9905561209 379 15.1200000000 0.0024900369 0.0032043843 0.0056260433 0.0050145954 0.1148790000 958632889 0 402718720 0.4924919009 0.3338810802 1.9934480190 380 15.1600000000 0.0023755408 0.0032022031 0.0056260433 0.0050114821 0.1151580000 958634897 0 402718720 0.4848568141 0.3327450752 1.9971356392 381 15.2000000000 0.0023517143 0.0031999709 0.0056260433 0.0050235172 0.1203900000 958636905 0 402718720 0.4766596556 0.3341365159 2.0033326149 382 15.2400000000 0.0022597683 0.0031975096 0.0056260433 0.0050338837 0.1145310000 958638913 0 402718720 0.4660219252 0.3342168629 2.0043478012 383 15.2800000000 0.0022286701 0.0031949800 0.0056260433 0.0050464157 0.1146890000 958640921 0 402718720 0.4574373364 0.3340011537 2.0065608025 384 15.3200000000 0.0022946452 0.0031926354 0.0056260433 0.0050560941 0.1242360000 958642929 0 402718720 0.4491585493 0.3347934484 2.0122432709 385 15.3600000000 0.0022831175 0.0031902730 0.0056260433 0.0050592923 0.1258160000 958644937 0 402718720 0.4408054948 0.3353814185 2.0145823956 386 15.4000000000 0.0022757777 0.0031879038 0.0056260433 0.0050558736 0.1240000000 958646945 0 402718720 0.4338503480 0.3349978924 2.0181124210 387 15.4400000000 0.0023184114 0.0031856571 0.0056260433 0.0050611992 0.1147140000 958648953 0 402718720 0.4273275733 0.3359772265 2.0213716030 388 15.4800000000 0.0022728050 0.0031833044 0.0056260433 0.0050660090 0.1252690000 958650961 0 402718720 0.4210326970 0.3364947736 2.0256810188 389 15.5200000000 0.0023408076 0.0031811386 0.0056260433 0.0050682401 0.1150120000 958652969 0 402718720 0.4131829739 0.3376881778 2.0291647911 390 15.5600000000 0.0022854963 0.0031788420 0.0056260433 0.0050795722 0.1241200000 958654977 0 402718720 0.4051042497 0.3380150199 2.0328154564 391 15.6000000000 0.0022844241 0.0031765545 0.0056260433 0.0050769632 0.1240610000 958656985 0 402718720 0.3983443081 0.3383424282 2.0362312794 392 15.6400000000 0.0022918507 0.0031742976 0.0056260433 0.0050833943 0.1242580000 958658993 0 402718720 0.3915989995 0.3390571773 2.0411183834 393 15.6800000000 0.0024134591 0.0031723617 0.0056260433 0.0050794302 0.1148450000 958661001 0 402718720 0.3845786154 0.3392055631 2.0433990955 394 15.7200000000 0.0023320145 0.0031702288 0.0056260433 0.0050769217 0.1242250000 958663009 0 402718720 0.3782760203 0.3389860690 2.0473413467 395 15.7600000000 0.0023458900 0.0031681419 0.0056260433 0.0050769400 0.1244780000 958665017 0 402718720 0.3717432916 0.3396849930 2.0535101891 396 15.8000000000 0.0023741792 0.0031661369 0.0056260433 0.0050743238 0.1258830000 958667025 0 402718720 0.3645884097 0.3413663507 2.0586376190 397 15.8400000000 0.0025756725 0.0031646496 0.0056260433 0.0050736306 0.1151020000 958669033 0 402718720 0.3581312895 0.3412989974 2.0606386662 398 15.8800000000 0.0024272446 0.0031627968 0.0056260433 0.0050690475 0.1250620000 958671041 0 402718720 0.3532990217 0.3411659002 2.0683999062 399 15.9200000000 0.0025278239 0.0031612054 0.0056260433 0.0050723255 0.1170280000 958673049 0 402718720 0.3451389074 0.3431523740 2.0715425014 400 15.9600000000 0.0025012593 0.0031595555 0.0056260433 0.0050694802 0.1264020000 958675057 0 402718720 0.3400977850 0.3416213989 2.0753815174 401 16.0000000000 0.0025254497 0.0031579742 0.0056260433 0.0050662298 0.1156130000 958677065 0 402718720 0.3341124356 0.3409714401 2.0790410042 402 16.0400000000 0.0025926102 0.0031565678 0.0056260433 0.0050687391 0.1382440000 958679073 0 402718720 0.3285267651 0.3412996233 2.0865206718 403 16.0800000000 0.0026512821 0.0031553140 0.0056260433 0.0050650542 0.1215450000 958681081 0 402718720 0.3224138021 0.3419371247 2.0925877094 404 16.1200000000 0.0027089634 0.0031542092 0.0056260433 0.0050606334 0.1165200000 958683089 0 402718720 0.3152906001 0.3419564068 2.0965697765 405 16.1600000000 0.0027574210 0.0031532295 0.0056260433 0.0050566325 0.1579750000 958685097 0 402718720 0.3101593554 0.3407936394 2.1011681557 406 16.2000000000 0.0028229016 0.0031524159 0.0056260433 0.0050661207 0.1277900000 958687105 0 402718720 0.3039734960 0.3418082893 2.1096727848 407 16.2400000000 0.0028940423 0.0031517810 0.0056260433 0.0050689649 0.1222240000 958689113 0 402718720 0.2964800596 0.3439001441 2.1151039600 408 16.2800000000 0.0029526837 0.0031512931 0.0056260433 0.0050730042 0.1255370000 958691121 0 402718720 0.2911267281 0.3443891704 2.1197178364 409 16.3200000000 0.0028635759 0.0031505896 0.0056260433 0.0050790393 0.1264300000 958693129 0 402718720 0.2840360403 0.3454055190 2.1265614033 410 16.3600000000 0.0027455851 0.0031496018 0.0056260433 0.0050775656 0.1358530000 958695137 0 402718720 0.2786019742 0.3459638655 2.1304986477 411 16.3999999990 0.0023956324 0.0031477673 0.0056260433 0.0050744502 0.1227150000 958697145 0 402718720 0.2721982598 0.3462222815 2.1337680817 412 16.4400000000 0.0020269873 0.0031450470 0.0056260433 0.0050725626 0.1252920000 958699153 0 402718720 0.2659952641 0.3461828530 2.1390967369 413 16.4800000000 0.0018516309 0.0031419152 0.0056260433 0.0050828516 0.1286510000 958701161 0 402718720 0.2595807016 0.3475383818 2.1462688446 414 16.5200000000 0.0017908409 0.0031386517 0.0056260433 0.0050898145 0.1275800000 958703169 0 402718720 0.2529252172 0.3491507173 2.1516015530 415 16.5599999990 0.0019238817 0.0031357246 0.0056260433 0.0051045757 0.1397830000 958705177 0 402718720 0.2465916872 0.3514722586 2.1582803726 416 16.6000000000 0.0022304894 0.0031335485 0.0056260433 0.0051066756 0.1274490000 958707185 0 402718720 0.2412129939 0.3527560830 2.1622581482 417 16.6400000000 0.0019447788 0.0031306978 0.0056260433 0.0051107637 0.1221680000 958709193 0 402718720 0.2358397841 0.3533726037 2.1660213470 418 16.6800000000 0.0024987538 0.0031291859 0.0056260433 0.0051243828 0.1315860000 958711201 0 402718720 0.2252354026 0.3551132977 2.1751048565 419 16.7199999990 0.0024739241 0.0031276221 0.0056260433 0.0051311363 0.1300720000 958713209 0 402718720 0.2190460265 0.3567808867 2.1814990044 420 16.7600000000 0.0020129276 0.0031249680 0.0056260433 0.0051395407 0.1300320000 958715217 0 402718720 0.2125742286 0.3587136865 2.1873676777 421 16.8000000000 0.0014498938 0.0031209892 0.0056260433 0.0051460154 0.1296570000 958717225 0 402718720 0.2064117789 0.3595047593 2.1924731731 422 16.8400000000 0.0013801861 0.0031168641 0.0056260433 0.0051544447 0.1293680000 958719233 0 402718720 0.2006266266 0.3596651554 2.1972098351 423 16.8799999990 0.0015073237 0.0031130591 0.0056260433 0.0051693768 0.1289880000 958721241 0 402718720 0.1955602169 0.3595125675 2.2024412155 424 16.9200000000 0.0016112360 0.0031095170 0.0056260433 0.0052510385 0.1300400000 958723249 0 402718720 0.1835674942 0.3612698019 2.2120900154 425 16.9600000000 0.0018268157 0.0031064989 0.0056260433 0.0052587989 0.1395600000 958725257 0 402718720 0.1787125319 0.3619809449 2.2156214714 426 17.0000000000 0.0018324002 0.0031035081 0.0056260433 0.0052788994 0.1309380000 958727265 0 402718720 0.1731244624 0.3635028899 2.2206449509 427 17.0400000000 0.0018331246 0.0031005329 0.0056260433 0.0052898937 0.1307550000 958729273 0 402718720 0.1676600128 0.3652199209 2.2250800133 428 17.0800000000 0.0018618495 0.0030976388 0.0056260433 0.0052988302 0.1307530000 958731281 0 402718720 0.1626952440 0.3672141731 2.2289876938 429 17.1200000000 0.0018576476 0.0030947484 0.0056260433 0.0053037333 0.1427170000 958733289 0 402718720 0.1576664746 0.3675174713 2.2311968803 430 17.1600000000 0.0019119284 0.0030919976 0.0056260433 0.0053078659 0.1306600000 958735297 0 402718720 0.1528027058 0.3678466380 2.2346150875 431 17.2000000000 0.0019377535 0.0030893196 0.0056260433 0.0053119882 0.1303190000 958737305 0 402718720 0.1481673867 0.3674525619 2.2382848263 432 17.2400000000 0.0019565588 0.0030866974 0.0056260433 0.0053126754 0.1302590000 958739313 0 402718720 0.1428891271 0.3680278063 2.2427694798 433 17.2800000000 0.0019513251 0.0030840753 0.0056260433 0.0053129582 0.1300840000 958741321 0 402718720 0.1390790194 0.3694495857 2.2465059757 434 17.3200000000 0.0019555117 0.0030814750 0.0056260433 0.0053126457 0.1304420000 958743329 0 402718720 0.1335603297 0.3706182837 2.2488701344 435 17.3600000000 0.0019375919 0.0030788453 0.0056260433 0.0053113766 0.1314960000 958745337 0 402718720 0.1283343583 0.3691726923 2.2503144741 436 17.4000000000 0.0019367340 0.0030762258 0.0056260433 0.0053150018 0.1319670000 958747345 0 402718720 0.1233628541 0.3688878119 2.2530832291 437 17.4400000000 0.0019216508 0.0030735838 0.0056260433 0.0053140411 0.1321810000 958749353 0 402718720 0.1171373874 0.3701713085 2.2561104298 438 17.4800000000 0.0019599202 0.0030710412 0.0056260433 0.0053136958 0.1318110000 958751361 0 402718720 0.1120683253 0.3687779605 2.2583804131 439 17.5200000000 0.0019341833 0.0030684515 0.0056260433 0.0053126265 0.1317990000 958753369 0 402718720 0.1072241217 0.3686670363 2.2607145309 440 17.5600000000 0.0019331311 0.0030658712 0.0056260433 0.0053117739 0.1321200000 958755377 0 402718720 0.1020809487 0.3683682084 2.2627379894 441 17.6000000000 0.0019061865 0.0030632416 0.0056260433 0.0053102461 0.1323920000 958757385 0 402718720 0.0963975191 0.3680213094 2.2641453743 442 17.6400000000 0.0043997467 0.0030662653 0.0056260433 0.0053231321 0.1231240000 958759393 0 402718720 0.0898789987 0.3681946695 2.2636783123 443 17.6800000000 0.0019258707 0.0030636911 0.0056260433 0.0053226939 0.1329250000 958761401 0 402718720 0.0857060626 0.3677350879 2.2671074867 444 17.7200000000 0.0044467254 0.0030668060 0.0056260433 0.0053301333 0.1489330000 958763409 0 402718720 0.0789658949 0.3687977493 2.2677977085 445 17.7600000000 0.0019870815 0.0030643797 0.0056260433 0.0053344641 0.1533030000 958765417 0 402718720 0.0754755661 0.3670418262 2.2710428238 446 17.8000000000 0.0039796224 0.0030664318 0.0056260433 0.0053490065 0.1244350000 958767425 0 402718720 0.0688634068 0.3673290610 2.2712149620 447 17.8400000000 0.0020360837 0.0030641268 0.0056260433 0.0053504595 0.1349920000 958769433 0 402718720 0.0643076673 0.3657313287 2.2760062218 448 17.8800000000 0.0041898545 0.0030666395 0.0056260433 0.0053607385 0.1379910000 958771441 0 402718720 0.0566455238 0.3670377731 2.2764360905 449 17.9200000000 0.0057053114 0.0030725163 0.0057053114 0.0053606753 0.1252660000 958773449 0 402718720 0.0506353602 0.3671807647 2.2765824795 450 17.9600000000 0.0065588634 0.0030802637 0.0065588634 0.0053578075 0.1252830000 958775457 0 402718720 0.0451337695 0.3664493263 2.2775814533 451 18.0000000000 0.0021244520 0.0030781444 0.0065588634 0.0053771423 0.1385900000 958777465 0 402718720 0.0338291600 0.3620170951 2.2842748165 452 18.0400000000 0.0045087640 0.0030813095 0.0065588634 0.0053821499 0.1249330000 958779473 0 402718720 0.0270426720 0.3633342683 2.2849018574 453 18.0800000000 0.0056017796 0.0030868735 0.0065588634 0.0053869818 0.1376620000 958781481 0 402718720 0.0203233529 0.3625768721 2.2865581512 454 18.1200000000 0.0021932842 0.0030849052 0.0065588634 0.0053898400 0.1388430000 958783489 0 402718720 0.0144101288 0.3602654934 2.2923686504 455 18.1600000000 0.0043265079 0.0030876340 0.0065588634 0.0053922653 0.1349920000 958785497 0 402718720 0.0067675351 0.3618492484 2.2942540646 456 18.2000000000 0.0056671305 0.0030932908 0.0065588634 0.0053919292 0.1248430000 958787505 0 402718720 0.0007782590 0.3614719808 2.2951068878 457 18.2400000000 0.0065064454 0.0031007594 0.0065588634 0.0053866225 0.1248490000 958789513 0 402718720 -0.0063137794 0.3617950380 2.2971308231 458 18.2800000000 0.0022734161 0.0030989530 0.0065588634 0.0054402731 0.1387090000 958791521 0 402718720 -0.0118871154 0.3590440750 2.3017587662 459 18.3200000000 0.0043024202 0.0031015749 0.0065588634 0.0054351278 0.1247320000 958793529 0 402718720 -0.0189296361 0.3593744338 2.3015909195 460 18.3600000000 0.0053766253 0.0031065207 0.0065588634 0.0054297683 0.1248220000 958795537 0 402718720 -0.0250764731 0.3590447903 2.3024845123 461 18.4000000000 0.0057545430 0.0031122648 0.0065588634 0.0054246233 0.1248870000 958797545 0 402718720 -0.0322294906 0.3580193818 2.3048617840 462 18.4400000000 0.0023890075 0.0031106993 0.0065588634 0.0054466388 0.1390950000 958799553 0 402718720 -0.0381454639 0.3551705182 2.3105120659 463 18.4800000000 0.0035247006 0.0031115934 0.0065588634 0.0054421807 0.1249230000 958801561 0 402718720 -0.0440877900 0.3560201228 2.3100168705 464 18.5200000000 0.0043708798 0.0031143074 0.0065588634 0.0054409855 0.1254750000 958803569 0 402718720 -0.0510727353 0.3552143276 2.3101158142 465 18.5600000000 0.0024360945 0.0031128489 0.0065588634 0.0054465473 0.1494810000 958805577 0 402718720 -0.0570981838 0.3528310359 2.3146457672 466 18.6000000000 0.0047746138 0.0031164149 0.0065588634 0.0054503187 0.1253120000 958807585 0 402718720 -0.0638918951 0.3531960845 2.3156683445 467 18.6400000000 0.0061074952 0.0031228198 0.0065588634 0.0054523138 0.1239450000 958809593 0 402718720 -0.0702175424 0.3545283377 2.3158469200 468 18.6800000000 0.0066960203 0.0031304548 0.0066960203 0.0054532707 0.1239700000 958811601 0 402718720 -0.0754385516 0.3540953696 2.3152501583 469 18.7200000000 0.0025816134 0.0031292846 0.0066960203 0.0054712740 0.1386380000 958813609 0 402718720 -0.0807607695 0.3512667418 2.3204066753 470 18.7600000000 0.0038533558 0.0031308252 0.0066960203 0.0054680638 0.1237230000 958815617 0 402718720 -0.0869823545 0.3510834277 2.3200123310 471 18.8000000000 0.0026555364 0.0031298161 0.0066960203 0.0054753540 0.1397260000 958817625 0 402718720 -0.1003796607 0.3460992575 2.3221709728 472 18.8400000000 0.0048061726 0.0031333677 0.0066960203 0.0054830151 0.1255630000 958819633 0 402718720 -0.1057060882 0.3463791311 2.3219046593 473 18.8800000000 0.0066631562 0.0031408302 0.0066960203 0.0054922029 0.1255500000 958821641 0 402718720 -0.1080482453 0.3457031250 2.3194913864 474 18.9200000000 0.0078202337 0.0031507024 0.0078202337 0.0054997355 0.1256430000 958823649 0 402718720 -0.1104676872 0.3446136415 2.3188076019 475 18.9600000000 0.0027725014 0.0031499062 0.0078202337 0.0055165997 0.1393640000 958825657 0 402718720 -0.1128550544 0.3403501213 2.3240463734 476 19.0000000000 0.0027566818 0.0031490801 0.0078202337 0.0055329574 0.1382120000 958827665 0 402718720 -0.1179185435 0.3376612961 2.3243265152 477 19.0400000000 0.0046557724 0.0031522388 0.0078202337 0.0055670691 0.1245850000 958829673 0 402718720 -0.1205730736 0.3365899026 2.3221509457 478 19.0800000000 0.0027887169 0.0031514783 0.0078202337 0.0055795357 0.1372740000 958831681 0 402718720 -0.1262574196 0.3331757486 2.3297598362 479 19.1200000000 0.0066768043 0.0031588380 0.0078202337 0.0056162975 0.1255610000 958833689 0 402718720 -0.1274916679 0.3358406425 2.3272440434 480 19.1600000000 0.0028589747 0.0031582133 0.0078202337 0.0056202509 0.1383060000 958835697 0 402718720 -0.1267067194 0.3326514661 2.3294215202 481 19.2000000000 0.0067903204 0.0031657645 0.0078202337 0.0056910483 0.1287510000 958837705 0 402718720 -0.1290189922 0.3345658183 2.3276689053 482 19.2400000000 0.0029834602 0.0031653862 0.0078202337 0.0056949071 0.1453330000 958839713 0 402718720 -0.1288189292 0.3323227167 2.3311378956 483 19.2800000000 0.0069812266 0.0031732865 0.0078202337 0.0057669346 0.1253100000 958841721 0 402718720 -0.1304806024 0.3338346481 2.3294901848 484 19.3200000000 0.0031854503 0.0031733117 0.0078202337 0.0057763673 0.1394590000 958843729 0 402718720 -0.1291650236 0.3308717012 2.3335254192 485 19.3600000000 0.0031947608 0.0031733559 0.0078202337 0.0057996293 0.1622850000 958845737 0 402718720 -0.1287741512 0.3308308721 2.3337109089 486 19.4000000000 0.0032376770 0.0031734882 0.0078202337 0.0058119484 0.1416960000 958847745 0 402718720 -0.1297983378 0.3309391439 2.3367896080 487 19.4400000000 0.0032604951 0.0031736669 0.0078202337 0.0058235649 0.1421570000 958849753 0 402718720 -0.1291822642 0.3310998976 2.3390369415 488 19.4800000000 0.0032536299 0.0031738308 0.0078202337 0.0058384192 0.1423580000 958851761 0 402718720 -0.1292320788 0.3300422728 2.3417570591 489 19.5200000000 0.0032984226 0.0031740855 0.0078202337 0.0058478203 0.1418360000 958853769 0 402718720 -0.1315016896 0.3305717409 2.3473250866 490 19.5600000000 0.0093272785 0.0031866431 0.0093272785 0.0059464658 0.1282970000 958855777 0 402718720 -0.1312654912 0.3353343308 2.3437070847 491 19.6000000000 0.0033999498 0.0031870775 0.0093272785 0.0059742568 0.1421330000 958857785 0 402718720 -0.1301553100 0.3318084180 2.3519103527 492 19.6400000000 0.0032799577 0.0031872663 0.0093272785 0.0059778739 0.1560400000 958859793 0 402718720 -0.1293245256 0.3319292963 2.3550612926 493 19.6800000000 0.0031561789 0.0031872032 0.0093272785 0.0059863660 0.1439090000 958861801 0 402718720 -0.1271666884 0.3333928585 2.3553819656 494 19.7200000000 0.0030600084 0.0031869458 0.0093272785 0.0060100337 0.1430040000 958863809 0 402718720 -0.1281875521 0.3331727087 2.3604764938 495 19.7600000000 0.0102708116 0.0032012566 0.0102708116 0.0061754205 0.1390090000 958865817 0 402718720 -0.1296080202 0.3377459645 2.3604428768 496 19.8000000000 0.0167729631 0.0032286189 0.0167729631 0.0062823726 0.1315320000 958867825 0 402718720 -0.1302824914 0.3429966867 2.3602344990 497 19.8400000000 0.0033699246 0.0032289032 0.0167729631 0.0064871959 0.1446190000 958869833 0 402718720 -0.1278852671 0.3353004158 2.3721303940 498 19.8800000000 0.0098761152 0.0032422510 0.0167729631 0.0065959026 0.1311040000 958871841 0 402718720 -0.1275491118 0.3402051628 2.3695571423 499 19.9200000000 0.0032069865 0.0032421804 0.0167729631 0.0066551468 0.1435870000 958873849 0 402718720 -0.1269153506 0.3353439569 2.3794775009 500 19.9600000000 0.0029174380 0.0032415309 0.0167729631 0.0066562868 0.1451400000 958875857 0 402718720 -0.1263980865 0.3362317383 2.3825006485 501 20.0000000000 0.0029020540 0.0032408533 0.0167729631 0.0066602399 0.1455160000 958877865 0 402718720 -0.1257479340 0.3367766440 2.3851504326 502 20.0400000000 0.0028314863 0.0032400378 0.0167729631 0.0066666349 0.1458270000 958879873 0 402718720 -0.1255192608 0.3371610343 2.3885946274 503 20.0800000000 0.0029255187 0.0032394125 0.0167729631 0.0066734016 0.1455970000 958881881 0 402718720 -0.1265784651 0.3381963372 2.3920769691 504 20.1200000000 0.0036606926 0.0032402484 0.0167729631 0.0066832520 0.1465770000 958883889 0 402718720 -0.1267553568 0.3391907811 2.3953881264 505 20.1600000000 0.0037759193 0.0032413091 0.0167729631 0.0066913252 0.1588340000 958885897 0 402718720 -0.1272824705 0.3401487768 2.3978974819 506 20.2000000000 0.0037430981 0.0032423008 0.0167729631 0.0066986714 0.1487810000 958887905 0 402718720 -0.1269025654 0.3403097093 2.4002406597 507 20.2400000000 0.0039129821 0.0032436237 0.0167729631 0.0067058041 0.1488640000 958889913 0 402718720 -0.1274637133 0.3401038945 2.4030718803 508 20.2800000000 0.0043777898 0.0032458563 0.0167729631 0.0067152771 0.1480390000 958891921 0 402718720 -0.1293464601 0.3400617838 2.4066722393 509 20.3200000000 0.0046763318 0.0032486666 0.0167729631 0.0067250930 0.1472970000 958893929 0 402718720 -0.1292390078 0.3398325443 2.4096186161 510 20.3600000000 0.0050048530 0.0032521101 0.0167729631 0.0067290650 0.1478820000 958895937 0 402718720 -0.1287747771 0.3407704234 2.4093875885 511 20.4000000000 0.0132292509 0.0032716349 0.0167729631 0.0068751530 0.1364080000 958897945 0 402718720 -0.1297454983 0.3463136852 2.4044435024 512 20.4400000000 0.0059518213 0.0032768696 0.0167729631 0.0069298823 0.1513210000 958899953 0 402718720 -0.1321921796 0.3416801989 2.4131374359 513 20.4800000000 0.0083162142 0.0032866929 0.0167729631 0.0069361168 0.1528660000 958901961 0 402718720 -0.1322387457 0.3442949653 2.4128599167 514 20.5200000000 0.0133469254 0.0033062653 0.0167729631 0.0070332844 0.1377730000 959006369 0 402718720 -0.1336380690 0.3474526405 2.4086787701 515 20.5600000000 0.0077805943 0.0033149533 0.0167729631 0.0070823702 0.1511600000 959008377 0 402718720 -0.1351043582 0.3436583579 2.4149947166 516 20.6000000000 0.0083817253 0.0033247727 0.0167729631 0.0070833385 0.1687850000 959010385 0 402718720 -0.1366226375 0.3441859782 2.4148695469 517 20.6400000000 0.0095920041 0.0033368950 0.0167729631 0.0070852271 0.1661970000 959012393 0 402718720 -0.1377116442 0.3449621201 2.4138684273 518 20.6800000000 0.0181081165 0.0033654108 0.0181081165 0.0071101042 0.1554330000 959014401 0 402718720 -0.1392201781 0.3528014421 2.4139125347 519 20.7200000000 0.0176881850 0.0033930077 0.0181081165 0.0071100945 0.1551450000 959016409 0 402718720 -0.1423133463 0.3522759080 2.4149563313 520 20.7600000000 0.0182594676 0.0034215971 0.0182594676 0.0071123069 0.1530890000 959018417 0 402718720 -0.1441137642 0.3512219787 2.4154348373 521 20.8000000000 0.0236475132 0.0034604184 0.0236475132 0.0071244770 0.1543620000 959020425 0 402718720 -0.1463017911 0.3559872210 2.4144852161 522 20.8400000000 0.0296242069 0.0035105406 0.0296242069 0.0071427368 0.1681100000 959022433 0 402718720 -0.1491694599 0.3607241511 2.4146630764 523 20.8800000000 0.0504116192 0.0036002176 0.0504116192 0.0072159122 0.1612330000 959024441 0 402718720 -0.1496680975 0.3820897937 2.4093720913 524 20.9200000000 0.0622012727 0.0037120517 0.0622012727 0.0073125892 0.1458150000 959026449 0 402718720 -0.1508404016 0.3919299841 2.4033448696 525 20.9600000000 0.0638188347 0.0038265408 0.0638188347 0.0073263107 0.1582660000 959028457 0 402718720 -0.1538459212 0.3908106387 2.4004793167 526 21.0000000000 0.0573515408 0.0039282994 0.0638188347 0.0074043481 0.1589070000 959030465 0 402718720 -0.1573762894 0.3854023814 2.4048447609 527 21.0400000000 0.0723558888 0.0040581430 0.0723558888 0.0074458760 0.1589320000 959032473 0 402718720 -0.1600313336 0.4003164172 2.4009070396 528 21.0800000000 0.0772631764 0.0041967889 0.0772631764 0.0074956499 0.1418790000 959034481 0 402718720 -0.1638959050 0.4027631879 2.3955936432 529 21.1200000000 0.0686815530 0.0043186882 0.0772631764 0.0075438365 0.1570390000 959036489 0 402718720 -0.1685997695 0.3934538066 2.3990099430 530 21.1600000000 0.0724720061 0.0044472794 0.0772631764 0.0075586031 0.1606600000 959038497 0 402718720 -0.1709230989 0.3977213502 2.3913516998 531 21.2000000000 0.0728460774 0.0045760907 0.0772631764 0.0075644525 0.1369780000 959040505 0 402718720 -0.1740953177 0.3968552351 2.3861672878 532 21.2400000000 0.0755457655 0.0047094923 0.0772631764 0.0075833528 0.1358330000 959042513 0 402718720 -0.1784236729 0.3987450302 2.3816194534 533 21.2800000000 0.0753650442 0.0048420544 0.0772631764 0.0075873440 0.1341420000 959044521 0 402718720 -0.1820752025 0.3977453709 2.3779845238 534 21.3200000000 0.0733226538 0.0049702952 0.0772631764 0.0075879578 0.1330620000 959046529 0 402718720 -0.1860518903 0.3930831850 2.3759832382 535 21.3600000000 0.0607152209 0.0050744913 0.0772631764 0.0077472317 0.1548760000 959048537 0 402718720 -0.1921482086 0.3800643384 2.3845188618 536 21.4000000000 0.0819172934 0.0052178547 0.0819172934 0.0077979706 0.1345450000 959050545 0 402718720 -0.1958628595 0.4005089402 2.3758635521 537 21.4400000000 0.0964502022 0.0053877474 0.0964502022 0.0078184088 0.1332490000 959052553 0 402718720 -0.2001059502 0.4153189659 2.3687729836 538 21.4800000000 0.0798233524 0.0055261035 0.0964502022 0.0078203554 0.1317500000 959054561 0 402718720 -0.2049005032 0.3992965519 2.3669867516 539 21.5200000000 0.0929305553 0.0056882639 0.0964502022 0.0078365225 0.1317350000 959056569 0 402718720 -0.2092254907 0.4108956158 2.3615279198 540 21.5600000000 0.0900762603 0.0058445380 0.0964502022 0.0078380057 0.1318040000 959058577 0 402718720 -0.2142120898 0.4075933099 2.3586232662 541 21.6000000000 0.0820992514 0.0059854894 0.0964502022 0.0079576954 0.1461780000 959060585 0 402718720 -0.2196862251 0.3995404243 2.3649964333 542 21.6400000000 0.0812814757 0.0061244119 0.0964502022 0.0079706256 0.1458240000 959062593 0 402718720 -0.2238299400 0.3958022296 2.3636767864 543 21.6800000000 0.0925748944 0.0062836209 0.0964502022 0.0080056487 0.1315670000 959064601 0 402718720 -0.2277393639 0.4046370685 2.3565840721 544 21.7200000000 0.0770104304 0.0064136334 0.0964502022 0.0082130554 0.1427310000 959066609 0 402718720 -0.2357614040 0.3860987127 2.3521409035 545 21.7600000000 0.0766696930 0.0065425436 0.0964502022 0.0082063489 0.1405940000 959068617 0 402718720 -0.2405363321 0.3879739046 2.3454461098 546 21.8000000000 0.0767267793 0.0066710861 0.0964502022 0.0082016517 0.1309460000 959070625 0 402718720 -0.2449984998 0.3871639073 2.3404366970 547 21.8400000000 0.0830608532 0.0068107384 0.0964502022 0.0082056310 0.1296640000 959072633 0 402718720 -0.2495692819 0.3909920156 2.3350000381 548 21.8800000000 0.0754877329 0.0069360613 0.0964502022 0.0082006900 0.1299550000 959074641 0 402718720 -0.2553319931 0.3880064189 2.3296000957 549 21.9200000000 0.0792314932 0.0070677470 0.0964502022 0.0082058037 0.1289740000 959076649 0 402718720 -0.2604120374 0.3943715990 2.3226957321 550 21.9600000000 0.0768516809 0.0071946269 0.0964502022 0.0082170998 0.1283490000 959078657 0 402718720 -0.2637226582 0.3844902217 2.3199369907 551 22.0000000000 0.0756400600 0.0073188473 0.0964502022 0.0082235162 0.1278420000 959080665 0 402718720 -0.2680417597 0.3818434477 2.3141427040 552 22.0400000000 0.0844339579 0.0074585486 0.0964502022 0.0082227155 0.1555730000 959082673 0 402718720 -0.2736313939 0.3967752457 2.3044934273 553 22.0800000000 0.0814887062 0.0075924187 0.0964502022 0.0082162281 0.1282510000 959084681 0 402718720 -0.2776934505 0.3948794603 2.2989439964 554 22.1200000000 0.0768764839 0.0077174801 0.0964502022 0.0082110040 0.1270770000 959086689 0 402718720 -0.2818058431 0.3880069852 2.2944467068 555 22.1600000000 0.0845166519 0.0078558570 0.0964502022 0.0082104336 0.1454720000 959088697 0 402718720 -0.2857125401 0.3963055015 2.2868607044 556 22.2000000000 0.0796766356 0.0079850311 0.0964502022 0.0082067418 0.1268500000 959090705 0 402718720 -0.2890892327 0.3897615373 2.2821538448 557 22.2400000000 0.0660949871 0.0080893578 0.0964502022 0.0082417754 0.1419380000 959092713 0 402718720 -0.2941201329 0.3786100745 2.2791948318 558 22.2800000000 0.0696903393 0.0081997538 0.0964502022 0.0082441056 0.1263290000 959094721 0 402718720 -0.2971979380 0.3808338046 2.2714860439 559 22.3200000000 0.0620048419 0.0082960062 0.0964502022 0.0082493873 0.1413500000 959096729 0 402718720 -0.3008163273 0.3716288209 2.2670621872 560 22.3600000000 0.0641218871 0.0083956953 0.0964502022 0.0082455857 0.1355480000 959098737 0 402718720 -0.3037379980 0.3726222813 2.2587041855 561 22.4000000000 0.0527550429 0.0084747672 0.0964502022 0.0082432971 0.1358420000 959100745 0 402718720 -0.3068831563 0.3608681560 2.2522265911 562 22.4400000000 0.0335074812 0.0085193094 0.0964502022 0.0082591045 0.1407420000 959102753 0 402718720 -0.3103415668 0.3370534778 2.2491462231 563 22.4800000000 0.0565922596 0.0086046965 0.0964502022 0.0083351185 0.1409830000 959104761 0 402718720 -0.3132954538 0.3583787382 2.2429740429 564 22.5200000000 0.0608812347 0.0086973854 0.0964502022 0.0083365396 0.1355400000 959106769 0 402718720 -0.3163567781 0.3636669219 2.2360770702 565 22.5600000000 0.0082609747 0.0086966130 0.0964502022 0.0084644214 0.1701400000 959108777 0 402718720 -0.3235093653 0.3124507368 2.2229652405 566 22.6000000000 0.0244342033 0.0087244179 0.0964502022 0.0084756260 0.1358360000 959110785 0 402718720 -0.3271263242 0.3259827495 2.2155947685 567 22.6400000000 0.0107612079 0.0087280101 0.0964502022 0.0084836088 0.1396890000 959112793 0 402718720 -0.3303713500 0.3104131818 2.2086222172 568 22.6800000000 0.0072726519 0.0087254479 0.0964502022 0.0084788321 0.1348240000 959114801 0 402718720 -0.3336929083 0.3079744279 2.2012307644 569 22.7200000000 0.0068096300 0.0087220809 0.0964502022 0.0084750881 0.1368500000 959116809 0 402718720 -0.3372365534 0.3073720038 2.1939353943 570 22.7600000000 0.0069253710 0.0087189288 0.0964502022 0.0084728142 0.1349250000 959118817 0 402718720 -0.3404113352 0.3039502800 2.1888856888 571 22.8000000000 0.0074874829 0.0087167721 0.0964502022 0.0084691120 0.1341280000 959120825 0 402718720 -0.3427835405 0.3009104431 2.1819629669 572 22.8400000000 0.0065120221 0.0087129177 0.0964502022 0.0084703391 0.1346600000 959122833 0 402718720 -0.3458971977 0.3050107658 2.1739892960 573 22.8800000000 0.0120559083 0.0087187519 0.0964502022 0.0084802372 0.1332550000 959124841 0 402718720 -0.3500357568 0.3102234900 2.1664226055 574 22.9200000000 0.0055368207 0.0087132084 0.0964502022 0.0084800114 0.1352300000 959126849 0 402718720 -0.3546639085 0.3022547662 2.1615784168 575 22.9600000000 0.0080301547 0.0087120205 0.0964502022 0.0084754667 0.1509740000 959128857 0 402718720 -0.3573433459 0.3030676842 2.1521198750 576 23.0000000000 0.0068186470 0.0087087334 0.0964502022 0.0084828576 0.1341010000 959130865 0 402718720 -0.3607694507 0.2971566916 2.1470286846 577 23.0400000000 0.0056163087 0.0087033739 0.0964502022 0.0084870771 0.1466540000 959132873 0 402718720 -0.3649038970 0.2934250534 2.1405837536 578 23.0800000000 0.0480422489 0.0087714342 0.0964502022 0.0086277555 0.1666510000 959134881 0 402718720 -0.3671311736 0.3378832340 2.1268172264 579 23.1200000000 0.0372150950 0.0088205597 0.0964502022 0.0086474525 0.1639390000 959136889 0 402718720 -0.3687059581 0.3266073763 2.1221568584 580 23.1600000000 0.0394622348 0.0088733902 0.0964502022 0.0086696713 0.1345290000 959138897 0 402718720 -0.3699850142 0.3291393816 2.1183180809 581 23.2000000000 0.1008226126 0.0090316505 0.1008226126 0.0089945413 0.1568470000 959140905 0 402718720 -0.3750933707 0.3898393512 2.1027801037 582 23.2400000000 0.0867892206 0.0091652546 0.1008226126 0.0090846498 0.1399190000 959142913 0 402718720 -0.3822685480 0.3711491227 2.1020197868 583 23.2800000000 0.0716995224 0.0092725175 0.1008226126 0.0091448795 0.1403040000 959144921 0 402718720 -0.3844571710 0.3560129106 2.0980720520 584 23.3200000000 0.0623949505 0.0093634805 0.1008226126 0.0091773222 0.1363340000 959146929 0 402718720 -0.3878639638 0.3462893367 2.0925140381 585 23.3600000000 0.0583694093 0.0094472514 0.1008226126 0.0091834966 0.1476010000 959148937 0 402718720 -0.3942316175 0.3395846784 2.0801973343 586 23.4000000000 0.0768760666 0.0095623176 0.1008226126 0.0092528123 0.1381050000 959150945 0 402718720 -0.3974201977 0.3569519222 2.0767104626 587 23.4400000000 0.0908589512 0.0097008127 0.1008226126 0.0092863342 0.1393420000 959152953 0 402718720 -0.4020402431 0.3708981872 2.0718209743 588 23.4800000000 0.0992113948 0.0098530416 0.1008226126 0.0092976094 0.1619790000 959154961 0 402718720 -0.4089598060 0.3773811460 2.0656673908 589 23.5200000000 0.1205383837 0.0100409624 0.1205383837 0.0093597671 0.1354980000 959156969 0 402718720 -0.4141634703 0.3957171142 2.0561196804 590 23.5600000000 0.1307817250 0.0102456077 0.1307817250 0.0093568300 0.1452060000 959158977 0 402718720 -0.4213732183 0.4039128423 2.0504138470 591 23.6000000000 0.1374626160 0.0104608649 0.1374626160 0.0093681529 0.1382010000 959160985 0 402718720 -0.4269112051 0.4085408151 2.0405948162 592 23.6400000000 0.1356644481 0.0106723575 0.1374626160 0.0093633966 0.1476050000 959162993 0 402718720 -0.4340963364 0.4065254629 2.0346562862 593 23.6800000000 0.1381257474 0.0108872873 0.1381257474 0.0093610318 0.1556970000 959165001 0 402718720 -0.4401729107 0.4092078507 2.0270955563 594 23.7200000000 0.1389727592 0.0111029194 0.1389727592 0.0093591452 0.1613800000 959167009 0 402718720 -0.4475132823 0.4073497355 2.0199110508 595 23.7600000000 0.1498801410 0.0113361584 0.1498801410 0.0093629356 0.1526460000 959169017 0 402718720 -0.4561404288 0.4145292342 2.0114021301 596 23.8000000000 0.1540739387 0.0115756514 0.1540739387 0.0093641675 0.1538460000 959171025 0 402718720 -0.4636669755 0.4159868062 2.0032815933 597 23.8400000000 0.1632574797 0.0118297248 0.1632574797 0.0093671149 0.1443450000 959173033 0 402718720 -0.4670422375 0.4254995286 1.9932538271 598 23.8800000000 0.1743476689 0.0121014939 0.1743476689 0.0093830741 0.1456020000 959175041 0 402718720 -0.4750662148 0.4358349144 1.9830272198 599 23.9200000000 0.1804904789 0.0123826108 0.1804904789 0.0093787852 0.1559510000 959177049 0 402718720 -0.4846805334 0.4417113960 1.9760850668 600 23.9600000000 0.1819099337 0.0126651563 0.1819099337 0.0093764691 0.1628760000 959179057 0 402718720 -0.4907328784 0.4419145882 1.9680713415 601 24.0000000000 0.1693924814 0.0129259339 0.1819099337 0.0093760318 0.1633360000 959181065 0 402718720 -0.4983037710 0.4283755720 1.9615921974 602 24.0400000000 0.1731996089 0.0131921692 0.1819099337 0.0093897314 0.1710700000 959183073 0 402718720 -0.5147805810 0.4305057824 1.9447811842 603 24.0800000000 0.1623409986 0.0134395139 0.1819099337 0.0093865226 0.1661590000 959185081 0 402718720 -0.5240089297 0.4187090993 1.9380458593 604 24.1200000000 0.1608005017 0.0136834890 0.1819099337 0.0093877055 0.1613420000 959187089 0 402718720 -0.5358905196 0.4148174822 1.9297335148 605 24.1600000000 0.1596324146 0.0139247269 0.1819099337 0.0093909915 0.1770760000 959189097 0 402718720 -0.5422310829 0.4134601951 1.9216892719 606 24.2000000000 0.1601969898 0.0141661003 0.1819099337 0.0093884928 0.1630240000 959191105 0 402718720 -0.5476200581 0.4137530327 1.9131994247 607 24.2400000000 0.1594354510 0.0144054238 0.1819099337 0.0093839995 0.1634530000 959193113 0 402718720 -0.5545579791 0.4116234183 1.9047465324 608 24.2800000000 0.1596397907 0.0146442961 0.1819099337 0.0093796373 0.1636400000 959195121 0 402718720 -0.5627229214 0.4104379714 1.8956943750 609 24.3200000000 0.1600431204 0.0148830462 0.1819099337 0.0093763922 0.1642120000 959197129 0 402718720 -0.5709295273 0.4105220735 1.8875941038 610 24.3600000000 0.1601884216 0.0151212517 0.1819099337 0.0093735117 0.1638840000 959199137 0 402718720 -0.5759882331 0.4099766612 1.8793938160 611 24.4000000000 0.1603390723 0.0153589241 0.1819099337 0.0093697835 0.1652420000 959201145 0 402718720 -0.5808334947 0.4093565941 1.8709120750 612 24.4400000000 0.1604911983 0.0155960683 0.1819099337 0.0093669321 0.1655690000 959203153 0 402718720 -0.5874915123 0.4080355465 1.8623267412 613 24.4800000000 0.1612710059 0.0158337110 0.1819099337 0.0093647705 0.1660770000 959205161 0 402718720 -0.5946478248 0.4081947803 1.8533477783 614 24.5200000000 0.1611885726 0.0160704453 0.1819099337 0.0093626977 0.1671430000 959207169 0 402718720 -0.6013613343 0.4072600603 1.8456376791 615 24.5600000000 0.1616289020 0.0163071257 0.1819099337 0.0093600696 0.1798790000 959209177 0 402718720 -0.6070315838 0.4071099758 1.8369580507 616 24.6000000000 0.1620979607 0.0165437991 0.1819099337 0.0093571543 0.1663910000 959211185 0 402718720 -0.6144829392 0.4067755342 1.8274914026 617 24.6400000000 0.1623899490 0.0167801786 0.1819099337 0.0093541558 0.1688130000 959213193 0 402718720 -0.6216611266 0.4066983759 1.8184639215 618 24.6800000000 0.1630443484 0.0170168520 0.1819099337 0.0093506471 0.1707350000 959215201 0 402718720 -0.6260448098 0.4072594941 1.8096005917 619 24.7200000000 0.1635683328 0.0172536073 0.1819099337 0.0093459725 0.1735970000 959217209 0 402718720 -0.6294209957 0.4079833329 1.8020879030 620 24.7600000000 0.1643401384 0.0174908436 0.1819099337 0.0093557934 0.1906770000 959219217 0 402718720 -0.6418577433 0.4076340497 1.7830926180 621 24.8000000000 0.1648712903 0.0177281712 0.1819099337 0.0093528356 0.1839580000 959221225 0 402718720 -0.6463476419 0.4069397151 1.7746614218 622 24.8400000000 0.1652651429 0.0179653689 0.1819099337 0.0093491082 0.1857760000 959223233 0 402718720 -0.6532989740 0.4051685035 1.7647351027 623 24.8800000000 0.1656725854 0.0182024592 0.1819099337 0.0093442855 0.2011540000 959225241 0 402718720 -0.6586792469 0.4043842852 1.7556056976 624 24.9200000000 0.1661125869 0.0184394946 0.1819099337 0.0093386611 0.2024150000 959227249 0 402718720 -0.6643203497 0.4034901857 1.7462174892 625 24.9600000000 0.1667121947 0.0186767309 0.1819099337 0.0093327082 0.1919350000 959229257 0 402718720 -0.6699903607 0.4030059874 1.7356458902 626 25.0000000000 0.1671551317 0.0189139169 0.1819099337 0.0093270946 0.1925110000 959231265 0 402718720 -0.6770386696 0.4026671052 1.7250359058 627 25.0400000000 0.1676125675 0.0191510758 0.1819099337 0.0093225273 0.2087180000 959233273 0 402718720 -0.6821802258 0.4019322097 1.7150948048 628 25.0800000000 0.1680708230 0.0193882092 0.1819099337 0.0093173828 0.1964100000 959235281 0 402718720 -0.6875861287 0.4006050527 1.7050890923 629 25.1200000000 0.1687275171 0.0196256325 0.1819099337 0.0093113975 0.2006140000 959237289 0 402718720 -0.6945981383 0.4008103013 1.6926355362 630 25.1600000000 0.1691750735 0.0198630126 0.1819099337 0.0093079786 0.2164180000 959239297 0 402718720 -0.6989401579 0.4004129171 1.6825951338 631 25.2000000000 0.1696746796 0.0201004321 0.1819099337 0.0093008113 0.2037280000 959241305 0 402718720 -0.7021882534 0.3998567164 1.6724765301 632 25.2400000000 0.1703214496 0.0203381235 0.1819099337 0.0092936342 0.2088650000 959243313 0 402718720 -0.7091908455 0.3991188705 1.6596301794 633 25.2800000000 0.1708970517 0.0205759733 0.1819099337 0.0092883628 0.2201140000 959245321 0 402718720 -0.7155407071 0.3980683684 1.6475385427 634 25.3200000000 0.1713910401 0.0208138520 0.1819099337 0.0092825409 0.2020270000 959247329 0 402718720 -0.7185896039 0.3971871734 1.6374392509 635 25.3600000000 0.1717811227 0.0210515957 0.1819099337 0.0092770163 0.2119590000 959249337 0 402718720 -0.7194445729 0.3966996670 1.6288731098 636 25.4000000000 0.1723741591 0.0212895243 0.1819099337 0.0092848234 0.2055760000 959251345 0 402718720 -0.7287591100 0.3959280252 1.6147518158 637 25.4400000000 0.1730007082 0.0215276894 0.1819099337 0.0092780679 0.2022680000 959253353 0 402718720 -0.7378662825 0.3966708183 1.6005550623 638 25.4800000000 0.1734390110 0.0217657949 0.1819099337 0.0092749619 0.1925240000 959255361 0 402718720 -0.7380078435 0.3972626925 1.5910513401 639 25.5200000000 0.1739179790 0.0220039048 0.1819099337 0.0092681333 0.1918330000 959257369 0 402718720 -0.7425113320 0.3970644176 1.5793950558 640 25.5600000000 0.1745499820 0.0222422580 0.1819099337 0.0092624063 0.1880800000 959259377 0 402718720 -0.7467455268 0.3965987861 1.5669326782 641 25.6000000000 0.1750937998 0.0224807160 0.1819099337 0.0092558976 0.1850020000 959261385 0 402718720 -0.7492009401 0.3962955773 1.5558301210 642 25.6400000000 0.1757133156 0.0227193960 0.1819099337 0.0092491014 0.1660320000 959263393 0 402718720 -0.7524999976 0.3952964842 1.5438706875 643 25.6800000000 0.1762289554 0.0229581356 0.1819099337 0.0092425390 0.1392510000 959265401 0 402718720 -0.7552124262 0.3941822648 1.5321911573 644 25.7200000000 0.1766988039 0.0231968634 0.1819099337 0.0092365831 0.1389200000 959267409 0 402718720 -0.7588320971 0.3925526142 1.5209236145 645 25.7600000000 0.1773106754 0.0234357995 0.1819099337 0.0092307075 0.1504370000 959269417 0 402718720 -0.7642044425 0.3920173347 1.5085549355 646 25.8000000000 0.1778863966 0.0236748871 0.1819099337 0.0092249348 0.1391190000 959271425 0 402718720 -0.7670945525 0.3915131986 1.4964586496 647 25.8400000000 0.1784198880 0.0239140602 0.1819099337 0.0092191405 0.1402520000 959273433 0 402718720 -0.7696438432 0.3918297589 1.4849129915 648 25.8800000000 0.1788632274 0.0241531793 0.1819099337 0.0092132587 0.1392850000 959275441 0 402718720 -0.7701249123 0.3906339109 1.4757707119 649 25.9200000000 0.1794386506 0.0243924481 0.1819099337 0.0092095526 0.1392580000 959277449 0 402718720 -0.7744740844 0.3894802332 1.4638713598 650 25.9600000000 0.1799176186 0.0246317176 0.1819099337 0.0092053221 0.1592610000 959279457 0 402718720 -0.7786174417 0.3878397346 1.4518111944 651 26.0000000000 0.1805230230 0.0248711820 0.1819099337 0.0092011152 0.1395570000 959281465 0 402718720 -0.7810055017 0.3860944510 1.4416575432 652 26.0400000000 0.1810730100 0.0251107554 0.1819099337 0.0091975517 0.1406640000 959283473 0 402718720 -0.7832015157 0.3847639859 1.4304511547 653 26.0800000000 0.1816140264 0.0253504235 0.1819099337 0.0091945687 0.1399880000 959285481 0 402718720 -0.7878211141 0.3821839392 1.4182984829 654 26.1200000000 0.1821376085 0.0255901592 0.1821376085 0.0091911943 0.1401540000 959287489 0 402718720 -0.7910252213 0.3797469139 1.4074580669 655 26.1600000000 0.1826725155 0.0258299796 0.1826725155 0.0091875397 0.1520480000 959289497 0 402718720 -0.7943956256 0.3767896295 1.3965059519 656 26.2000000000 0.1831608564 0.0260698133 0.1831608564 0.0091848666 0.1406370000 959291505 0 402718720 -0.7987262607 0.3747666180 1.3852453232 657 26.2400000000 0.1836702526 0.0263096922 0.1836702526 0.0091802406 0.1408380000 959293513 0 402718720 -0.8041118979 0.3720742166 1.3735979795 658 26.2800000000 0.1841381490 0.0265495530 0.1841381490 0.0091751968 0.1412010000 959295521 0 402718720 -0.8064160943 0.3697810769 1.3639073372 659 26.3200000000 0.1846891791 0.0267895221 0.1846891791 0.0091712066 0.1415960000 959297529 0 402718720 -0.8106688857 0.3683918417 1.3524204493 660 26.3600000000 0.1851927489 0.0270295270 0.1851927489 0.0091660663 0.1402380000 959299537 0 402718720 -0.8138648272 0.3663237691 1.3413044214 661 26.4000000000 0.1857084632 0.0272695859 0.1857084632 0.0091627529 0.1420300000 959301545 0 402718720 -0.8178792000 0.3648674786 1.3297164440 662 26.4400000000 0.1862352937 0.0275097154 0.1862352937 0.0091591960 0.1423290000 959303553 0 402718720 -0.8232921958 0.3635926247 1.3174831867 663 26.4800000000 0.1868445128 0.0277500394 0.1868445128 0.0091544821 0.1430080000 959305561 0 402718720 -0.8285093307 0.3631402552 1.3042715788 664 26.5200000000 0.1874259263 0.0279905151 0.1874259263 0.0091506155 0.1435030000 959307569 0 402718720 -0.8327520490 0.3614092767 1.2922821045 665 26.5600000000 0.1885374933 0.0282319391 0.1885374933 0.0091610699 0.1444230000 959309577 0 402718720 -0.8412668109 0.3606084287 1.2677698135 666 26.6000000000 0.1891700923 0.0284735880 0.1891700923 0.0091568471 0.1450790000 959311585 0 402718720 -0.8463412523 0.3611992598 1.2540019751 667 26.6400000000 0.1896284968 0.0287151996 0.1896284968 0.0091517826 0.1467470000 959313593 0 402718720 -0.8497602940 0.3611353040 1.2420680523 668 26.6800000000 0.1902220696 0.0289569763 0.1902220696 0.0091468512 0.1460080000 959315601 0 402718720 -0.8553425670 0.3609966338 1.2284792662 669 26.7200000000 0.1906849295 0.0291987221 0.1906849295 0.0091433349 0.1462960000 959317609 0 402718720 -0.8586323261 0.3614476025 1.2162400484 670 26.7600000000 0.1912372261 0.0294405706 0.1912372261 0.0091377962 0.1586820000 959319617 0 402718720 -0.8616945148 0.3629387915 1.2037237883 671 26.8000000000 0.1918824911 0.0296826599 0.1918824911 0.0091335488 0.1469150000 959321625 0 402718720 -0.8673579097 0.3619698286 1.1905783415 672 26.8400000000 0.1925727129 0.0299250559 0.1925727129 0.0091307246 0.1471620000 959323633 0 402718720 -0.8724010587 0.3604957461 1.1779475212 673 26.8800000000 0.1932747811 0.0301677746 0.1932747811 0.0091279164 0.1474390000 959325641 0 402718720 -0.8762504458 0.3589424491 1.1651346684 674 26.9200000000 0.1937838197 0.0304105284 0.1937838197 0.0091234046 0.1594020000 959327649 0 402718720 -0.8772222400 0.3577165604 1.1535737514 675 26.9600000000 0.1944422275 0.0306535383 0.1944422275 0.0091228819 0.1566290000 959329657 0 402718720 -0.8788197041 0.3560389578 1.1414239407 676 27.0000000000 0.1949377805 0.0308965623 0.1949377805 0.0091254925 0.1487240000 959331665 0 402718720 -0.8825423121 0.3551992178 1.1283019781 677 27.0400000000 0.1955098957 0.0311397135 0.1955098957 0.0091258940 0.1483690000 959333673 0 402718720 -0.8862441778 0.3546269536 1.1159631014 678 27.0800000000 0.1959373206 0.0313827778 0.1959373206 0.0091249100 0.1467900000 959335681 0 402718720 -0.8892931342 0.3545427024 1.1053957939 679 27.1200000000 0.1965120733 0.0316259727 0.1965120733 0.0091245534 0.1468750000 959337689 0 402718720 -0.8921803236 0.3535933793 1.0944455862 680 27.1600000000 0.1968832910 0.0318689981 0.1968832910 0.0091228928 0.1479240000 959339697 0 402718720 -0.8950367570 0.3532031178 1.0850818157 681 27.2000000000 0.1974079609 0.0321120803 0.1974079609 0.0091214859 0.1432010000 959341705 0 402718720 -0.8980084658 0.3530144095 1.0747036934 682 27.2400000000 0.1977458298 0.0323549450 0.1977458298 0.0091200276 0.1696010000 959343713 0 402718720 -0.9018798470 0.3532207608 1.0632395744 683 27.2800000000 0.1982679367 0.0325978630 0.1982679367 0.0091156193 0.1496390000 959345721 0 402718720 -0.9071658850 0.3534103930 1.0513739586 684 27.3200000000 0.1993616223 0.0328416697 0.1993616223 0.0091130070 0.1651080000 959347729 0 402718720 -0.9080824852 0.3522750735 1.0420697927 685 27.3600000000 0.1995852441 0.0330850910 0.1995852441 0.0091115028 0.1637230000 959349737 0 402718720 -0.9085335135 0.3518248498 1.0324146748 686 27.4000000000 0.1997984946 0.0333281134 0.1997984946 0.0091149118 0.1510810000 959351745 0 402718720 -0.9143087268 0.3511776328 1.0194096565 687 27.4400000000 0.2005655766 0.0335715450 0.2005655766 0.0091116064 0.1467910000 959353753 0 402718720 -0.9183132648 0.3498128355 1.0081893206 688 27.4800000000 0.2006171793 0.0338143439 0.2006171793 0.0091070275 0.1468340000 959355761 0 402718720 -0.9206853509 0.3496528864 0.9987719059 689 27.5200000000 0.2013553977 0.0340575094 0.2013553977 0.0091036187 0.1638240000 959357769 0 402718720 -0.9259624481 0.3495001793 0.9855509996 690 27.5600000000 0.2018028051 0.0343006185 0.2018028051 0.0090996925 0.1521850000 959359777 0 402718720 -0.9267634153 0.3493928611 0.9751024246 691 27.6000000000 0.2022955716 0.0345437371 0.2022955716 0.0090945228 0.1503440000 959361785 0 402718720 -0.9287735224 0.3486395776 0.9643830061 692 27.6400000000 0.2028041631 0.0347868880 0.2028041631 0.0090887554 0.1507650000 959363793 0 402718720 -0.9314053655 0.3466998637 0.9519638419 693 27.6800000000 0.2032718062 0.0350300120 0.2032718062 0.0090825350 0.1509710000 959365801 0 402718720 -0.9336959720 0.3462697864 0.9398998618 694 27.7200000000 0.2039660066 0.0352734356 0.2039660066 0.0090770667 0.1510500000 959367809 0 402718720 -0.9356991053 0.3447659314 0.9278157353 695 27.7600000000 0.2045344412 0.0355169766 0.2045344412 0.0090720717 0.1645670000 959369817 0 402718720 -0.9382200837 0.3420541883 0.9153816700 696 27.8000000000 0.2050193250 0.0357605145 0.2050193250 0.0090662285 0.1648530000 959371825 0 402718720 -0.9406813383 0.3405907154 0.9027177095 697 27.8400000000 0.2063785344 0.0360053036 0.2063785344 0.0090644327 0.1576640000 959373833 0 402718720 -0.9452283382 0.3342402279 0.8764285445 698 27.8800000000 0.2069513798 0.0362502120 0.2069513798 0.0090592353 0.1522220000 959375841 0 402718720 -0.9455047250 0.3313409984 0.8656678796 699 27.9200000000 0.2073072791 0.0364949289 0.2073072791 0.0090660976 0.1536730000 959377849 0 402718720 -0.9485264421 0.3332421184 0.8512234688 700 27.9600000000 0.2078682333 0.0367397479 0.2078682333 0.0090597417 0.1541660000 959379857 0 402718720 -0.9495807886 0.3344447613 0.8363175392 701 28.0000000000 0.2084119171 0.0369846440 0.2084119171 0.0090577168 0.1524350000 959381865 0 402718720 -0.9479608536 0.3337712884 0.8242663145 702 28.0400000000 0.2088571787 0.0372294767 0.2088571787 0.0090514121 0.1513970000 959383873 0 402718720 -0.9481931925 0.3347465396 0.8113257885 703 28.0800000000 0.2097496837 0.0374748824 0.2097496837 0.0090455812 0.1543050000 959385881 0 402718720 -0.9515773058 0.3335045278 0.7962754369 704 28.1200000000 0.2104679495 0.0377206111 0.2104679495 0.0090455898 0.1534700000 959387889 0 402718720 -0.9510672092 0.3305780888 0.7833757997 705 28.1600000000 0.2112571299 0.0379667622 0.2112571299 0.0090399448 0.1644050000 959389897 0 402718720 -0.9515326023 0.3269781470 0.7693678737 706 28.2000000000 0.2120141685 0.0382132883 0.2120141685 0.0090351018 0.1559650000 959391905 0 402718720 -0.9521842599 0.3236692250 0.7558736205 707 28.2400000000 0.2125748545 0.0384599100 0.2125748545 0.0090350821 0.1555370000 959393913 0 402718720 -0.9524605870 0.3240659833 0.7412589788 708 28.2800000000 0.2132033259 0.0387067228 0.2132033259 0.0090329541 0.1534440000 959395921 0 402718720 -0.9556959867 0.3259115219 0.7257416844 709 28.3200000000 0.2140247673 0.0389539979 0.2140247673 0.0090330079 0.1658490000 959397929 0 402718720 -0.9562031031 0.3236479759 0.7118607163 710 28.3600000000 0.2144444883 0.0392011676 0.2144444883 0.0090280554 0.1540870000 959399937 0 402718720 -0.9533988237 0.3229669631 0.7018296719 711 28.4000000000 0.2150215656 0.0394484536 0.2150215656 0.0090239245 0.1527380000 959401945 0 402718720 -0.9548275471 0.3223420382 0.6890131831 712 28.4400000000 0.2155503035 0.0396957877 0.2155503035 0.0090184293 0.1527980000 959403953 0 402718720 -0.9551892281 0.3204388320 0.6773547530 713 28.4800000000 0.2161017954 0.0399432015 0.2161017954 0.0090132306 0.1647370000 959405961 0 402718720 -0.9535913467 0.3177775741 0.6670473218 714 28.5200000000 0.2164680064 0.0401904351 0.2164680064 0.0090148794 0.1525370000 959407969 0 402718720 -0.9544327855 0.3175443411 0.6556360126 715 28.5600000000 0.2169514894 0.0404376533 0.2169514894 0.0090147758 0.1780070000 959409977 0 402718720 -0.9564403892 0.3199781775 0.6408222318 716 28.6000000000 0.2176474333 0.0406851530 0.2176474333 0.0090105632 0.1692610000 959411985 0 402718720 -0.9567726254 0.3199807107 0.6279936433 717 28.6400000000 0.2200124562 0.0409352608 0.2200124562 0.0090098726 0.1475750000 959413993 0 402718720 -0.9554757476 0.3181340992 0.6191700697 718 28.6800000000 0.2188989669 0.0411831212 0.2200124562 0.0090054309 0.1469370000 959416001 0 402718720 -0.9561402202 0.3161529899 0.6106917262 719 28.7200000000 0.2191011608 0.0414305732 0.2200124562 0.0090034892 0.1530460000 959418009 0 402718720 -0.9591140747 0.3154371381 0.5978773236 720 28.7600000000 0.2183654457 0.0416763161 0.2200124562 0.0089981768 0.1560210000 959420017 0 402718720 -0.9610626101 0.3135717809 0.5871569514 721 28.8000000000 0.2198371589 0.0419234185 0.2200124562 0.0089965468 0.1508780000 959422025 0 402718720 -0.9602365494 0.3163007200 0.5758171082 722 28.8400000000 0.2208219767 0.0421712005 0.2208219767 0.0089967631 0.1553610000 959424033 0 402718720 -0.9661337733 0.3193527758 0.5631204844 723 28.8800000000 0.2209422588 0.0424184633 0.2209422588 0.0089944644 0.1502390000 959426041 0 402718720 -0.9720647335 0.3190219700 0.5518027544 724 28.9200000000 0.2187511325 0.0426620167 0.2209422588 0.0089958760 0.1460590000 959428049 0 402718720 -0.9751293659 0.3170533478 0.5435556769 725 28.9600000000 0.2222403884 0.0429097111 0.2222403884 0.0089932923 0.1649190000 959430057 0 402718720 -0.9798672199 0.3210326731 0.5307816863 726 29.0000000000 0.2224295586 0.0431569836 0.2224295586 0.0089944556 0.1501480000 959432065 0 402718720 -0.9826297760 0.3189843595 0.5174775124 727 29.0400000000 0.2235942334 0.0434051779 0.2235942334 0.0089942723 0.1528130000 959434073 0 402718720 -0.9933515787 0.3189374208 0.4972707033 728 29.0800000000 0.2241745889 0.0436534875 0.2241745889 0.0089936880 0.1547870000 959436081 0 402718720 -1.0043473244 0.3186615407 0.4829211831 729 29.1200000000 0.2249711305 0.0439022085 0.2249711305 0.0090178430 0.1492370000 959438089 0 402718720 -1.0074412823 0.3136461973 0.4750069082 730 29.1600000000 0.2251430452 0.0441504837 0.2251430452 0.0090137192 0.1496640000 959440097 0 402718720 -1.0103149414 0.3135750592 0.4660399854 731 29.2000000000 0.2257302999 0.0443988829 0.2257302999 0.0090090789 0.1546880000 959442105 0 402718720 -1.0190901756 0.3166851997 0.4518933594 732 29.2400000000 0.2258394361 0.0446467525 0.2258394361 0.0090115805 0.1620520000 959444113 0 402718720 -1.0246818066 0.3179248869 0.4409664571 733 29.2800000000 0.2260362357 0.0448942142 0.2260362357 0.0090104527 0.1484150000 959446121 0 402718720 -1.0282592773 0.3207707405 0.4308763146 734 29.3200000000 0.2272278816 0.0451426252 0.2272278816 0.0090062978 0.1544960000 959448129 0 402718720 -1.0365868807 0.3260164559 0.4182457328 735 29.3600000000 0.2275129855 0.0453907482 0.2275129855 0.0090304460 0.1617120000 959450137 0 402718720 -1.0416074991 0.3243804872 0.4086902440 736 29.4000000000 0.2278386950 0.0456386394 0.2278386950 0.0090333549 0.1496830000 959452145 0 402718720 -1.0443221331 0.3255264163 0.4005652368 737 29.4400000000 0.2286359370 0.0458869397 0.2286359370 0.0090280510 0.1543480000 959454153 0 402718720 -1.0497545004 0.3309662938 0.3881016374 738 29.4800000000 0.2286787033 0.0461346250 0.2286787033 0.0090453822 0.1520220000 959456161 0 402718720 -1.0546398163 0.3320372999 0.3777070940 739 29.5200000000 0.2286337614 0.0463815792 0.2286787033 0.0090636223 0.1471260000 959458169 0 402718720 -1.0551266670 0.3301015496 0.3722070158 740 29.5600000000 0.2295638770 0.0466291228 0.2295638770 0.0090593432 0.1499950000 959460177 0 402718720 -1.0577303171 0.3305091560 0.3631238043 741 29.6000000000 0.2299529910 0.0468765234 0.2299529910 0.0090542800 0.1498780000 959462185 0 402718720 -1.0600013733 0.3311998248 0.3523632288 742 29.6400000000 0.2303019911 0.0471237276 0.2303019911 0.0090502168 0.1622960000 959464193 0 402718720 -1.0625072718 0.3325633705 0.3422228396 743 29.6800000000 0.2270965576 0.0473659521 0.2303019911 0.0090494176 0.1459770000 959466201 0 402718720 -1.0656909943 0.3314577937 0.3344876170 744 29.7200000000 0.2315182239 0.0476134686 0.2315182239 0.0090474183 0.1564270000 959468209 0 402718720 -1.0721893311 0.3376146555 0.3245395124 745 29.7600000000 0.2288906276 0.0478567937 0.2315182239 0.0090641278 0.1481770000 959470217 0 402718720 -1.0751575232 0.3355511725 0.3196548223 746 29.8000000000 0.2320300937 0.0481036748 0.2320300937 0.0090655417 0.1563020000 959472225 0 402718720 -1.0802438259 0.3395404816 0.3107704520 747 29.8400000000 0.2322559357 0.0483501972 0.2322559357 0.0090903277 0.1630960000 959474233 0 402718720 -1.0754576921 0.3383389413 0.3055365384 748 29.8800000000 0.2323861867 0.0485962346 0.2323861867 0.0090884453 0.1572870000 959476241 0 402718720 -1.0733705759 0.3353549838 0.3024911880 749 29.9200000000 0.2325139195 0.0488417856 0.2325139195 0.0090864111 0.1497260000 959478249 0 402718720 -1.0775440931 0.3355511129 0.2944185138 750 29.9600000000 0.2334503382 0.0490879303 0.2334503382 0.0090810163 0.1542810000 959480257 0 402718720 -1.0808720589 0.3390354812 0.2842369080 751 30.0000000000 0.2318412960 0.0493312770 0.2334503382 0.0090875910 0.1454700000 959482265 0 402718720 -1.0821605921 0.3360918462 0.2796333730 752 30.0400000000 0.2315765917 0.0495736245 0.2334503382 0.0090841728 0.1450770000 959484273 0 402718720 -1.0846263170 0.3346500397 0.2758628726 753 30.0800000000 0.2341709137 0.0498187736 0.2341709137 0.0090797273 0.1546360000 959486281 0 402718720 -1.0892727375 0.3407290578 0.2661809325 754 30.1200000000 0.2345424742 0.0500637653 0.2345424742 0.0090924983 0.1451290000 959488289 0 402718720 -1.0882219076 0.3380069137 0.2612057626 755 30.1600000000 0.2352269292 0.0503090145 0.2352269292 0.0090916251 0.1546860000 959490297 0 402718720 -1.0841348171 0.3358023167 0.2589094639 756 30.2000000000 0.2328880727 0.0505505212 0.2352269292 0.0090858288 0.1451460000 959492305 0 402718720 -1.0861974955 0.3332038224 0.2519269586 757 30.2400000000 0.2326294482 0.0507910482 0.2352269292 0.0090817029 0.1463910000 959494313 0 402718720 -1.0882736444 0.3320523798 0.2452284247 758 30.2800000000 0.2321936786 0.0510303656 0.2352269292 0.0090774031 0.1439070000 959496321 0 402718720 -1.0907454491 0.3319762647 0.2387646586 759 30.3200000000 0.2353796810 0.0512732501 0.2353796810 0.0090726480 0.1495840000 959498329 0 402718720 -1.0922418833 0.3377499282 0.2283192128 760 30.3600000000 0.2361401916 0.0515164961 0.2361401916 0.0090818201 0.1447960000 959500337 0 402718720 -1.0888464451 0.3357885182 0.2227856219 761 30.4000000000 0.2355306596 0.0517583018 0.2361401916 0.0090792810 0.1571170000 959502345 0 402718720 -1.0883576870 0.3337986469 0.2180955559 762 30.4400000000 0.2343353033 0.0519979042 0.2361401916 0.0090750340 0.1430890000 959504353 0 402718720 -1.0914785862 0.3325337172 0.2107359171 763 30.4800000000 0.2360497862 0.0522391255 0.2361401916 0.0090767412 0.1446780000 959506361 0 402718720 -1.0920078754 0.3315781653 0.2027604878 764 30.5200000000 0.2353838533 0.0524788438 0.2361401916 0.0090734567 0.1429140000 959508369 0 402718720 -1.0910077095 0.3321647644 0.1960058361 765 30.5600000000 0.2375580817 0.0527207774 0.2375580817 0.0090689769 0.1593700000 959510377 0 402718720 -1.0904040337 0.3331991732 0.1869056374 766 30.6000000000 0.2396786362 0.0529648477 0.2396786362 0.0090672879 0.1439710000 959512385 0 402718720 -1.0857467651 0.3298251033 0.1828001589 767 30.6400000000 0.2384421527 0.0532066695 0.2396786362 0.0090615791 0.1487610000 959514393 0 402718720 -1.0856058598 0.3287106752 0.1728674471 768 30.6800000000 0.2389807403 0.0534485628 0.2396786362 0.0090577416 0.1472120000 959516401 0 402718720 -1.0853737593 0.3279595673 0.1635439247 769 30.7200000000 0.2396695614 0.0536907228 0.2396786362 0.0090582430 0.1474070000 959518409 0 402718720 -1.0791213512 0.3225085735 0.1610455215 770 30.7600000000 0.2386574298 0.0539309393 0.2396786362 0.0090542256 0.1410200000 959520417 0 402718720 -1.0781810284 0.3210344315 0.1534761041 771 30.8000000000 0.2390755415 0.0541710749 0.2396786362 0.0090501408 0.1419860000 959522425 0 402718720 -1.0782040358 0.3194475770 0.1435512453 772 30.8400000000 0.2406639457 0.0544126460 0.2406639457 0.0090458079 0.1457380000 959524433 0 402718720 -1.0718960762 0.3167156577 0.1374469250 773 30.8800000000 0.2409331352 0.0546539403 0.2409331352 0.0090468941 0.1457990000 959526441 0 402718720 -1.0663577318 0.3150332272 0.1307367682 774 30.9200000000 0.2387105674 0.0548917396 0.2409331352 0.0090479580 0.1406670000 959528449 0 402718720 -1.0678964853 0.3137481511 0.1217586175 775 30.9600000000 0.2389635295 0.0551292515 0.2409331352 0.0090460990 0.1498650000 959530457 0 402718720 -1.0698398352 0.3134097457 0.1135844588 776 31.0000000000 0.2392257601 0.0553664893 0.2409331352 0.0090424804 0.1401560000 959532465 0 402718720 -1.0711098909 0.3135567009 0.1069143862 777 31.0400000000 0.2409711480 0.0556053628 0.2409711480 0.0090388375 0.1402810000 959534473 0 402718720 -1.0674610138 0.3141673207 0.1002699956 778 31.0800000000 0.2402933091 0.0558427509 0.2409711480 0.0090358878 0.1402420000 959536481 0 402718720 -1.0680093765 0.3134012222 0.0927793458 779 31.1200000000 0.2393984497 0.0560783808 0.2409711480 0.0090341224 0.1401560000 959538489 0 402718720 -1.0677402020 0.3154923320 0.0848932043 780 31.1600000000 0.2430434823 0.0563180796 0.2430434823 0.0090432157 0.1486540000 959540497 0 402718720 -1.0675963163 0.3247234523 0.0754825547 781 31.2000000000 0.2433879673 0.0565576057 0.2433879673 0.0090384567 0.1448430000 959542505 0 402718720 -1.0625900030 0.3254765272 0.0676961467 782 31.2400000000 0.2431189120 0.0567961752 0.2433879673 0.0090342176 0.1631730000 959544513 0 402718720 -1.0585563183 0.3234300911 0.0611104779 783 31.2800000000 0.2438508272 0.0570350700 0.2438508272 0.0090303888 0.1593380000 959546521 0 402718720 -1.0538473129 0.3241275847 0.0566453040 784 31.3200000000 0.2421902865 0.0572712374 0.2438508272 0.0090247718 0.1436810000 959548529 0 402718720 -1.0531041622 0.3222720921 0.0479163155 785 31.3600000000 0.2423409671 0.0575069950 0.2438508272 0.0090208048 0.1568700000 959550537 0 402718720 -1.0540977716 0.3206608593 0.0421084203 786 31.4000000000 0.2449870259 0.0577455192 0.2449870259 0.0090184379 0.1429160000 959552545 0 402718720 -1.0504050255 0.3185887039 0.0377318822 787 31.4400000000 0.2450061142 0.0579834615 0.2450061142 0.0090136009 0.1432090000 959554553 0 402718720 -1.0472735167 0.3157255650 0.0338679552 788 31.4800000000 0.2441005260 0.0582196507 0.2450061142 0.0090083027 0.1426460000 959556561 0 402718720 -1.0447634459 0.3144778907 0.0287856515 789 31.5200000000 0.2435417771 0.0584545330 0.2450061142 0.0090030954 0.1424930000 959558569 0 402718720 -1.0432006121 0.3137494028 0.0224824827 790 31.5600000000 0.2429625392 0.0586880874 0.2450061142 0.0089976357 0.1389410000 959560577 0 402718720 -1.0413599014 0.3128955960 0.0192968473 791 31.6000000000 0.2417226136 0.0589194838 0.2450061142 0.0089922227 0.1409060000 959562585 0 402718720 -1.0422539711 0.3135170341 0.0123595493 792 31.6400000000 0.2434747964 0.0591525081 0.2450061142 0.0089885646 0.1407340000 959564593 0 402718720 -1.0426473618 0.3123481572 0.0068731890 793 31.6800000000 0.2444141805 0.0593861294 0.2450061142 0.0089833241 0.1521250000 959566601 0 402718720 -1.0399734974 0.3101708889 0.0056749275 794 31.7200000000 0.2435261607 0.0596180438 0.2450061142 0.0089787233 0.1401960000 959568609 0 402718720 -1.0417288542 0.3103383183 -0.0021700298 795 31.7600000000 0.2442195714 0.0598502470 0.2450061142 0.0089743302 0.1408190000 959570617 0 402718720 -1.0430878401 0.3101482093 -0.0074857417 796 31.8000000000 0.2453325093 0.0600832649 0.2453325093 0.0089695643 0.1402300000 959572625 0 402718720 -1.0404331684 0.3090391457 -0.0103439456 797 31.8400000000 0.2450196296 0.0603153055 0.2453325093 0.0089640327 0.1398480000 959574633 0 402718720 -1.0385233164 0.3084035814 -0.0147641562 798 31.8800000000 0.2449844778 0.0605467205 0.2453325093 0.0089585573 0.1392540000 959576641 0 402718720 -1.0390034914 0.3058993816 -0.0180131197 799 31.9200000000 0.2474834919 0.0607806839 0.2474834919 0.0089630490 0.1464620000 959578649 0 402718720 -1.0421899557 0.3136347532 -0.0272566937 800 31.9600000000 0.2477544844 0.0610144012 0.2477544844 0.0089636780 0.1393540000 959580657 0 402718720 -1.0437549353 0.3087880015 -0.0324090719 801 32.0000000000 0.2479908764 0.0612478300 0.2479908764 0.0089673914 0.1425150000 959582665 0 402718720 -1.0384508371 0.2981411517 -0.0293529071 802 32.0400000000 0.2469324470 0.0614793570 0.2479908764 0.0089715303 0.1393420000 959584673 0 402718720 -1.0385055542 0.2963268161 -0.0337898806 803 32.0800000000 0.2462086082 0.0617094058 0.2479908764 0.0089723809 0.1700230000 959586681 0 402718720 -1.0400133133 0.2967648804 -0.0413963087 804 32.1199999990 0.2473900318 0.0619403519 0.2479908764 0.0089686782 0.1384790000 959588689 0 402718720 -1.0400260687 0.2947356403 -0.0445573144 805 32.1600000000 0.2486407459 0.0621722778 0.2486407459 0.0089675868 0.1382450000 959590697 0 402718720 -1.0405461788 0.2919613719 -0.0494620651 806 32.2000000000 0.2473891824 0.0624020755 0.2486407459 0.0089808016 0.1368170000 959592705 0 402718720 -1.0376420021 0.2937164605 -0.0666983873 807 32.2400000000 0.2469096929 0.0626307095 0.2486407459 0.0089802806 0.1365230000 959594713 0 402718720 -1.0363796949 0.2948496938 -0.0721409470 808 32.2800000000 0.2448415905 0.0628562180 0.2486407459 0.0089804925 0.1493300000 959596721 0 402718720 -1.0369658470 0.2989875972 -0.0807491764 809 32.3200000000 0.2459613681 0.0630825532 0.2486407459 0.0089770547 0.1372740000 959598729 0 402718720 -1.0396654606 0.2994742095 -0.0882757381 810 32.3600000000 0.2503741086 0.0633137773 0.2503741086 0.0089859344 0.1442500000 959600737 0 402718720 -1.0436074734 0.2995036542 -0.0932122990 811 32.4000000000 0.2510699034 0.0635452892 0.2510699034 0.0089821846 0.1398050000 959602745 0 402718720 -1.0442452431 0.2940492630 -0.0990839899 812 32.4399999990 0.2509889007 0.0637761311 0.2510699034 0.0089856953 0.1418140000 959604753 0 402718720 -1.0437836647 0.2860261500 -0.1000639722 813 32.4800000000 0.2515039742 0.0640070386 0.2515039742 0.0090197631 0.1571890000 959606761 0 402718720 -1.0450497866 0.2968739569 -0.1125778630 814 32.5200000000 0.2523522973 0.0642384210 0.2523522973 0.0090284670 0.1482100000 959608769 0 402718720 -1.0517863035 0.3082326949 -0.1297041625 815 32.5600000000 0.2526218593 0.0644695663 0.2526218593 0.0090526471 0.1456250000 959610777 0 402718720 -1.0535818338 0.2994003594 -0.1315850466 816 32.6000000000 0.2516546249 0.0646989598 0.2526218593 0.0090478310 0.1440370000 959612785 0 402718720 -1.0531265736 0.2950343192 -0.1357515752 817 32.6400000000 0.2502692640 0.0649260960 0.2526218593 0.0090428825 0.1659090000 959614793 0 402718720 -1.0554662943 0.2939296365 -0.1432108879 818 32.6800000000 0.2507216632 0.0651532299 0.2526218593 0.0090388480 0.1440940000 959616801 0 402718720 -1.0598046780 0.2915290594 -0.1513224393 819 32.7200000000 0.2528244853 0.0653823768 0.2528244853 0.0090367768 0.1467410000 959618809 0 402718720 -1.0621836185 0.2868800759 -0.1565820724 820 32.7599999990 0.2518438399 0.0656097688 0.2528244853 0.0090323855 0.1470140000 959620817 0 402718720 -1.0625513792 0.2865259945 -0.1630643904 821 32.7999999990 0.2515943944 0.0658363031 0.2528244853 0.0090286049 0.1473970000 959622825 0 402718720 -1.0653181076 0.2872114182 -0.1715628207 822 32.8400000000 0.2524037361 0.0660632707 0.2528244853 0.0090245373 0.1479610000 959624833 0 402718720 -1.0681804419 0.2860947549 -0.1784545779 823 32.8800000000 0.2522804141 0.0662895370 0.2528244853 0.0090207129 0.1604130000 959626841 0 402718720 -1.0696679354 0.2867889404 -0.1848720014 824 32.9200000000 0.2519155443 0.0665148113 0.2528244853 0.0090164108 0.1509990000 959628849 0 402718720 -1.0734280348 0.2879128158 -0.1941374689 825 32.9600000000 0.2546545863 0.0667428595 0.2546545863 0.0090172078 0.1517090000 959630857 0 402718720 -1.0742474794 0.2845800817 -0.1986272484 826 33.0000000000 0.2534873784 0.0669689425 0.2546545863 0.0090126596 0.1522340000 959632865 0 402718720 -1.0732078552 0.2845672071 -0.2042195946 827 33.0400000000 0.2543847263 0.0671955637 0.2546545863 0.0090087545 0.1515320000 959634873 0 402718720 -1.0768196583 0.2834425271 -0.2137392759 828 33.0800000000 0.2559514344 0.0674235298 0.2559514344 0.0090146258 0.1534180000 959636881 0 402718720 -1.0782313347 0.2751800120 -0.2162285000 829 33.1199999990 0.2540948391 0.0676487062 0.2559514344 0.0090162276 0.1527720000 959638889 0 402718720 -1.0764526129 0.2750169635 -0.2218278199 830 33.1600000000 0.2566951513 0.0678764730 0.2566951513 0.0090356308 0.1609450000 959640897 0 402718720 -1.0855245590 0.2824101150 -0.2351939380 831 33.2000000000 0.2567749321 0.0681037877 0.2567749321 0.0090319822 0.1540440000 959642905 0 402718720 -1.0857716799 0.2789397240 -0.2398648858 832 33.2400000000 0.2575669289 0.0683315078 0.2575669289 0.0090290799 0.1546080000 959644913 0 402718720 -1.0828022957 0.2752659023 -0.2418357432 833 33.2800000000 0.2564768493 0.0685573726 0.2575669289 0.0090272540 0.1658180000 959646921 0 402718720 -1.0818368196 0.2737089694 -0.2489610910 834 33.3200000000 0.2559508681 0.0687820650 0.2575669289 0.0090256871 0.1568600000 959648929 0 402718720 -1.0845880508 0.2717206478 -0.2560931146 835 33.3600000000 0.2557466030 0.0690059746 0.2575669289 0.0090236891 0.1569160000 959650937 0 402718720 -1.0865540504 0.2712992430 -0.2646424472 836 33.4000000000 0.2556990981 0.0692292918 0.2575669289 0.0090215780 0.1571030000 959652945 0 402718720 -1.0872596502 0.2720956504 -0.2725823522 837 33.4399999990 0.2566399276 0.0694531993 0.2575669289 0.0090187504 0.1561290000 959654953 0 402718720 -1.0871974230 0.2713491321 -0.2794249654 838 33.4800000000 0.2575356960 0.0696776414 0.2575669289 0.0090152183 0.1538970000 959656961 0 402718720 -1.0864320993 0.2689850926 -0.2859132588 839 33.5200000000 0.2573018670 0.0699012698 0.2575669289 0.0090129826 0.1556760000 959658969 0 402718720 -1.0843369961 0.2697816789 -0.2967389226 840 33.5600000000 0.2596470416 0.0701271577 0.2596470416 0.0090103485 0.1551230000 959660977 0 402718720 -1.0782374144 0.2658971548 -0.3022311330 841 33.6000000000 0.2596246898 0.0703524817 0.2596470416 0.0090066044 0.1673450000 959662985 0 402718720 -1.0745131969 0.2628076971 -0.3086917102 842 33.6400000000 0.2593616843 0.0705769582 0.2596470416 0.0090083796 0.1523680000 959664993 0 402718720 -1.0731719732 0.2612395883 -0.3173030615 843 33.6800000000 0.2607564628 0.0708025567 0.2607564628 0.0090233458 0.1626340000 959667001 0 402718720 -1.0662890673 0.2589334548 -0.3338197172 844 33.7200000000 0.2601402104 0.0710268904 0.2607564628 0.0090208213 0.1526610000 959669009 0 402718720 -1.0641990900 0.2572200298 -0.3433040977 845 33.7599999990 0.2592237592 0.0712496086 0.2607564628 0.0090210751 0.1508900000 959671017 0 402718720 -1.0640704632 0.2584546804 -0.3538126945 846 33.7999999990 0.2629754841 0.0714762349 0.2629754841 0.0090319812 0.1593160000 959673025 0 402718720 -1.0643475056 0.2676033676 -0.3659746051 847 33.8400000000 0.2632535100 0.0717026544 0.2632535100 0.0090289163 0.1674860000 959675033 0 402718720 -1.0598441362 0.2692294419 -0.3766244352 848 33.8800000000 0.2639186382 0.0719293241 0.2639186382 0.0090285182 0.1541860000 959677041 0 402718720 -1.0512602329 0.2680078149 -0.3846198022 849 33.9200000000 0.2635702789 0.0721550497 0.2639186382 0.0090248710 0.1506460000 959679049 0 402718720 -1.0493997335 0.2635421753 -0.3927161396 850 33.9600000000 0.2648562491 0.0723817569 0.2648562491 0.0090200499 0.1546800000 959681057 0 402718720 -1.0421649218 0.2621437609 -0.4022743404 851 34.0000000000 0.2653329968 0.0726084917 0.2653329968 0.0090148657 0.1526030000 959683065 0 402718720 -1.0350335836 0.2595911324 -0.4098918140 852 34.0400000000 0.2658017278 0.0728352443 0.2658017278 0.0090104786 0.1519880000 959685073 0 402718720 -1.0317307711 0.2598720193 -0.4196663499 853 34.0800000000 0.2662449479 0.0730619848 0.2662449479 0.0090058482 0.1707160000 959687081 0 402718720 -1.0263350010 0.2622067928 -0.4296337962 854 34.1199999990 0.2656839192 0.0732875375 0.2662449479 0.0090019097 0.1485180000 959689089 0 402718720 -1.0232956409 0.2613833845 -0.4376243949 855 34.1600000000 0.2671576738 0.0735142862 0.2671576738 0.0089973494 0.1506930000 959691097 0 402718720 -1.0191296339 0.2599238157 -0.4460473657 856 34.2000000000 0.2675863206 0.0737410058 0.2675863206 0.0089943761 0.1484380000 959693105 0 402718720 -1.0123881102 0.2598003447 -0.4536795914 857 34.2400000000 0.2667971551 0.0739662755 0.2675863206 0.0089893835 0.1581470000 959695113 0 402718720 -1.0085266829 0.2572936714 -0.4610426426 858 34.2800000000 0.2672405243 0.0741915369 0.2675863206 0.0089850400 0.1450440000 959697121 0 402718720 -1.0037147999 0.2551666498 -0.4671870768 859 34.3200000000 0.2664085627 0.0744153053 0.2675863206 0.0089837970 0.1455970000 959699129 0 402718720 -0.9995707273 0.2563674450 -0.4764203727 860 34.3600000000 0.2667931914 0.0746390005 0.2675863206 0.0089797669 0.1451490000 959701137 0 402718720 -0.9956223965 0.2566576004 -0.4855189621 861 34.4000000000 0.2680068910 0.0748635857 0.2680068910 0.0089757931 0.1446560000 959703145 0 402718720 -0.9906511903 0.2547919452 -0.4928911924 862 34.4400000000 0.2684689462 0.0750881859 0.2684689462 0.0089714808 0.1440520000 959705153 0 402718720 -0.9861699343 0.2536949515 -0.5002278090 863 34.4800000000 0.2680611312 0.0753117930 0.2684689462 0.0089668443 0.1549710000 959707161 0 402718720 -0.9805674553 0.2543826997 -0.5074961782 864 34.5200000000 0.2680693269 0.0755348920 0.2684689462 0.0089630320 0.1438430000 959709169 0 402718720 -0.9766929746 0.2565317452 -0.5165386200 865 34.5600000000 0.2705458999 0.0757603383 0.2705458999 0.0089635522 0.1438870000 959711177 0 402718720 -0.9717592001 0.2531319857 -0.5230368376 866 34.6000000000 0.2726162076 0.0759876545 0.2726162076 0.0089615266 0.1416620000 959713185 0 402718720 -0.9686847925 0.2439588457 -0.5260429382 867 34.6400000000 0.2705237567 0.0762120330 0.2726162076 0.0089725565 0.1421000000 959715193 0 402718720 -0.9639412165 0.2389399409 -0.5416334867 868 34.6800000000 0.2706214786 0.0764360070 0.2726162076 0.0089713691 0.1385540000 959717201 0 402718720 -0.9580202103 0.2369219363 -0.5482630730 869 34.7200000000 0.2699727118 0.0766587190 0.2726162076 0.0089709709 0.1372820000 959719209 0 402718720 -0.9557855725 0.2363964170 -0.5560812950 870 34.7600000000 0.2708687186 0.0768819488 0.2726162076 0.0089704041 0.1384900000 959721217 0 402718720 -0.9513574243 0.2358363122 -0.5652009845 871 34.8000000000 0.2723513246 0.0771063683 0.2726162076 0.0089675522 0.1375640000 959723225 0 402718720 -0.9454099536 0.2336718887 -0.5708188415 872 34.8400000000 0.2718483508 0.0773296963 0.2726162076 0.0089679667 0.1367830000 959725233 0 402718720 -0.9432590604 0.2314144522 -0.5773604512 873 34.8800000000 0.2742641866 0.0775552799 0.2742641866 0.0089778781 0.1538990000 959727241 0 402718720 -0.9361640215 0.2381615192 -0.5868839025 874 34.9200000000 0.2726603746 0.0777785123 0.2742641866 0.0089738174 0.1369680000 959729249 0 402718720 -0.9345945716 0.2373467684 -0.5947081447 875 34.9600000000 0.2714866698 0.0779998930 0.2742641866 0.0089703040 0.1482590000 959731257 0 402718720 -0.9297435880 0.2399250567 -0.6023266315 876 35.0000000000 0.2726068795 0.0782220471 0.2742641866 0.0089664955 0.1327520000 959733265 0 402718720 -0.9251320362 0.2396309376 -0.6096719503 877 35.0400000000 0.2753416896 0.0784468130 0.2753416896 0.0089627580 0.1365450000 959735273 0 402718720 -0.9168750048 0.2384442836 -0.6145398021 878 35.0800000000 0.2750267088 0.0786707081 0.2753416896 0.0089584244 0.1327970000 959737281 0 402718720 -0.9128089547 0.2346760929 -0.6197957397 879 35.1200000000 0.2722759843 0.0788909643 0.2753416896 0.0089576025 0.1448530000 959739289 0 402718720 -0.9092656374 0.2359117866 -0.6288548708 880 35.1600000000 0.2738687396 0.0791125300 0.2753416896 0.0089538964 0.1316890000 959741297 0 402718720 -0.9017030001 0.2350116223 -0.6360425353 881 35.2000000000 0.2743634880 0.0793341542 0.2753416896 0.0089494980 0.1313410000 959743305 0 402718720 -0.8966590166 0.2328438610 -0.6406073570 882 35.2400000000 0.2734112442 0.0795541963 0.2753416896 0.0089452514 0.1303960000 959745313 0 402718720 -0.8896983862 0.2319004536 -0.6482051611 883 35.2800000000 0.2731001377 0.0797733876 0.2753416896 0.0089411659 0.1389610000 959747321 0 402718720 -0.8872709870 0.2311394811 -0.6569774151 884 35.3200000000 0.2737041116 0.0799927663 0.2753416896 0.0089373727 0.1426670000 959749329 0 402718720 -0.8795937300 0.2314781398 -0.6635594368 885 35.3600000000 0.2770136893 0.0802153888 0.2770136893 0.0089352030 0.1302700000 959751337 0 402718720 -0.8726655245 0.2269992232 -0.6690850854 886 35.4000000000 0.2788057029 0.0804395313 0.2788057029 0.0089323741 0.1406170000 959753345 0 402718720 -0.8714294434 0.2209714204 -0.6754165292 887 35.4400000000 0.2767853737 0.0806608908 0.2788057029 0.0089282964 0.1271910000 959755353 0 402718720 -0.8683689237 0.2181945890 -0.6848285198 888 35.4800000000 0.2774533033 0.0808825039 0.2788057029 0.0089243642 0.1267230000 959757361 0 402718720 -0.8637570739 0.2143616378 -0.6921948791 889 35.5200000000 0.2772557437 0.0811033962 0.2788057029 0.0089218956 0.1262770000 959759369 0 402718720 -0.8595340252 0.2111008912 -0.6992250085 890 35.5600000000 0.2758470178 0.0813222092 0.2788057029 0.0089238024 0.1255870000 959761377 0 402718720 -0.8548305631 0.2104470432 -0.7075844407 891 35.6000000000 0.2747889459 0.0815393436 0.2788057029 0.0089248830 0.1256870000 959763385 0 402718720 -0.8487900496 0.2108312398 -0.7187360525 892 35.6400000000 0.2754718363 0.0817567567 0.2788057029 0.0089230801 0.1251900000 959765393 0 402718720 -0.8448086977 0.2115288228 -0.7278599143 893 35.6800000000 0.2779146135 0.0819764184 0.2788057029 0.0089220284 0.1250410000 959767401 0 402718720 -0.8385473490 0.2110465914 -0.7352787852 894 35.7200000000 0.2779651880 0.0821956452 0.2788057029 0.0089210676 0.1248240000 959769409 0 402718720 -0.8306474686 0.2124844640 -0.7418535948 895 35.7600000000 0.2775720954 0.0824139429 0.2788057029 0.0089197145 0.1371990000 959771417 0 402718720 -0.8249760270 0.2130172700 -0.7517744303 896 35.8000000000 0.2768773437 0.0826309779 0.2788057029 0.0089172318 0.1230950000 959773425 0 402718720 -0.8196853399 0.2140613794 -0.7597606778 897 35.8400000000 0.2752863467 0.0828457554 0.2788057029 0.0089157966 0.1250330000 959775433 0 402718720 -0.8119117022 0.2194970250 -0.7700953484 898 35.8800000000 0.2777671516 0.0830628171 0.2788057029 0.0089197772 0.1250260000 959777441 0 402718720 -0.8047160506 0.2226056457 -0.7777721882 899 35.9200000000 0.2798410654 0.0832817028 0.2798410654 0.0089240447 0.1262540000 959779449 0 402718720 -0.7980861068 0.2224045396 -0.7859626412 900 35.9600000000 0.2830089927 0.0835036220 0.2830089927 0.0089283936 0.1248260000 959781457 0 402718720 -0.7900030017 0.2177492231 -0.7916121483 901 36.0000000000 0.2835040092 0.0837255980 0.2835040092 0.0089282292 0.1266990000 959783465 0 402718720 -0.7868986130 0.2116813362 -0.7968651652 902 36.0400000000 0.2816332877 0.0839450079 0.2835040092 0.0089277723 0.1224800000 959785473 0 402718720 -0.7798999548 0.2102686018 -0.8080238104 903 36.0800000000 0.2840037644 0.0841665569 0.2840037644 0.0089319730 0.1369490000 959787481 0 402718720 -0.7749122381 0.2087326348 -0.8170410395 904 36.1200000000 0.2844218314 0.0843880782 0.2844218314 0.0089306868 0.1248940000 959789489 0 402718720 -0.7624371052 0.2080306411 -0.8143801689 905 36.1600000000 0.2851762474 0.0846099436 0.2851762474 0.0089679341 0.1245580000 959791497 0 402718720 -0.7386723757 0.2078102380 -0.8407050371 906 36.2000000000 0.2832704484 0.0848292157 0.2851762474 0.0089645102 0.1197260000 959793505 0 402718720 -0.7305330038 0.2038448602 -0.8472425938 907 36.2400000000 0.2835393846 0.0850483007 0.2851762474 0.0089618712 0.1183360000 959795513 0 402718720 -0.7242512107 0.1989476383 -0.8525160551 908 36.2800000000 0.2865940332 0.0852702674 0.2865940332 0.0089713579 0.1273040000 959797521 0 402718720 -0.7214026451 0.2025128752 -0.8611693978 909 36.3200000000 0.2843384743 0.0854892643 0.2865940332 0.0089688355 0.1214080000 959799529 0 402718720 -0.7111487389 0.2036605924 -0.8642343879 910 36.3600000000 0.2851991057 0.0857087257 0.2865940332 0.0089680866 0.1220680000 959801537 0 402718720 -0.7024669647 0.2035763264 -0.8660044074 911 36.4000000000 0.2861105502 0.0859287057 0.2865940332 0.0089663952 0.1225440000 959803545 0 402718720 -0.6968590021 0.2021886557 -0.8680669069 912 36.4400000000 0.2853692174 0.0861473905 0.2865940332 0.0089638645 0.1229460000 959805553 0 402718720 -0.6890802979 0.2019497603 -0.8735833168 913 36.4800000000 0.2858225405 0.0863660928 0.2865940332 0.0089620161 0.1368270000 959807561 0 402718720 -0.6818199158 0.2013091743 -0.8785694242 914 36.5200000000 0.2863164246 0.0865848568 0.2865940332 0.0089592152 0.1252980000 959809569 0 402718720 -0.6761504412 0.1986710429 -0.8828018904 915 36.5600000000 0.2858876288 0.0868026740 0.2865940332 0.0089562114 0.1366900000 959811577 0 402718720 -0.6679297686 0.1981374174 -0.8855793476 916 36.6000000000 0.2844263613 0.0870184204 0.2865940332 0.0089532023 0.1252250000 959813585 0 402718720 -0.6587826014 0.1987912059 -0.8897281289 917 36.6400000000 0.2860696614 0.0872354883 0.2865940332 0.0089497615 0.1248390000 959815593 0 402718720 -0.6521927118 0.1958540678 -0.8934413791 918 36.6800000000 0.2862854898 0.0874523184 0.2865940332 0.0089472633 0.1506880000 959817601 0 402718720 -0.6461751461 0.1915030032 -0.8978735209 919 36.7200000000 0.2843098044 0.0876665267 0.2865940332 0.0089437152 0.1257190000 959819609 0 402718720 -0.6386383772 0.1915774047 -0.9009332061 920 36.7600000000 0.2833895087 0.0878792691 0.2865940332 0.0089395702 0.1249540000 959821617 0 402718720 -0.6320680976 0.1919223815 -0.9061334133 921 36.8000000000 0.2836434245 0.0880918252 0.2865940332 0.0089393080 0.1247960000 959823625 0 402718720 -0.6219497323 0.1947627962 -0.9093710184 922 36.8400000000 0.2869620025 0.0883075195 0.2869620025 0.0089390132 0.1248910000 959825633 0 402718720 -0.6123979092 0.1934056431 -0.9127065539 923 36.8800000000 0.2874037921 0.0885232251 0.2874037921 0.0089346617 0.1360580000 959827641 0 402718720 -0.6049872637 0.1915818304 -0.9145032167 924 36.9200000000 0.2886013687 0.0887397599 0.2886013687 0.0089337206 0.1500450000 959829649 0 402718720 -0.5938512087 0.1962377876 -0.9218280315 925 36.9600000000 0.2882218957 0.0889554163 0.2886013687 0.0089343071 0.1270670000 959831657 0 402718720 -0.5830599070 0.1955977827 -0.9267897010 926 37.0000000000 0.2881900966 0.0891705725 0.2886013687 0.0089387638 0.1276010000 959833665 0 402718720 -0.5667916536 0.1968918294 -0.9342185855 927 37.0400000000 0.2878834307 0.0893849337 0.2886013687 0.0089385704 0.1275910000 959835673 0 402718720 -0.5548941493 0.1973341405 -0.9380105734 928 37.0800000000 0.2886244655 0.0895996315 0.2886244655 0.0089350985 0.1277260000 959837681 0 402718720 -0.5466282368 0.1936991215 -0.9408330321 929 37.1200000000 0.2885196209 0.0898137542 0.2886244655 0.0089314310 0.1270710000 959839689 0 402718720 -0.5372862816 0.1905314922 -0.9442381859 930 37.1600000000 0.2880592644 0.0900269214 0.2886244655 0.0089281010 0.1262410000 959841697 0 402718720 -0.5269759893 0.1897746027 -0.9475861788 931 37.2000000000 0.2884034812 0.0902400004 0.2886244655 0.0089242661 0.1239260000 959843705 0 402718720 -0.5190590024 0.1875816137 -0.9516456723 932 37.2400000000 0.2881497443 0.0904523499 0.2886244655 0.0089220502 0.1250240000 959845713 0 402718720 -0.5090574622 0.1887922734 -0.9534555078 933 37.2800000000 0.2881423831 0.0906642364 0.2886244655 0.0089197588 0.1349540000 959847721 0 402718720 -0.4978521168 0.1904012710 -0.9575297832 934 37.3200000000 0.2885276675 0.0908760816 0.2886244655 0.0089182537 0.1249240000 959849729 0 402718720 -0.4869461358 0.1919298917 -0.9617276192 935 37.3600000000 0.2888095379 0.0910877751 0.2888095379 0.0089180906 0.1231870000 959851737 0 402718720 -0.4760051370 0.1925126910 -0.9639347196 936 37.4000000000 0.2894895971 0.0912997429 0.2894895971 0.0089157730 0.1219660000 959853745 0 402718720 -0.4657260478 0.1911730617 -0.9643450379 937 37.4400000000 0.2899309695 0.0915117293 0.2899309695 0.0089129296 0.1217830000 959855753 0 402718720 -0.4543223977 0.1898181885 -0.9654319286 938 37.4800000000 0.2895915210 0.0917229017 0.2899309695 0.0089088012 0.1231460000 959857761 0 402718720 -0.4453268647 0.1866624057 -0.9674050808 939 37.5200000000 0.2867666185 0.0919306160 0.2899309695 0.0089052195 0.1236660000 959859769 0 402718720 -0.4336407483 0.1868567914 -0.9703285694 940 37.5600000000 0.2858865857 0.0921369522 0.2899309695 0.0089024380 0.1236220000 959861777 0 402718720 -0.4228927493 0.1879636943 -0.9711016417 941 37.6000000000 0.2865405381 0.0923435447 0.2899309695 0.0088984455 0.1241050000 959863785 0 402718720 -0.4136053622 0.1863538921 -0.9727547765 942 37.6400000000 0.2875329852 0.0925507522 0.2899309695 0.0088949138 0.1230500000 959865793 0 402718720 -0.4045317471 0.1842927039 -0.9751945734 943 37.6800000000 0.2881225049 0.0927581453 0.2899309695 0.0088930413 0.1343510000 959867801 0 402718720 -0.3940042257 0.1841516346 -0.9767820835 944 37.7200000000 0.2883605659 0.0929653513 0.2899309695 0.0088895612 0.1363280000 959869809 0 402718720 -0.3860434592 0.1829322875 -0.9765340090 945 37.7600000000 0.2891270220 0.0931729298 0.2899309695 0.0088865245 0.1365410000 959871817 0 402718720 -0.3752467334 0.1820193231 -0.9764766097 946 37.8000000000 0.2891362309 0.0933800792 0.2899309695 0.0088834560 0.1257140000 959873825 0 402718720 -0.3650881648 0.1802834123 -0.9771966934 947 37.8400000000 0.2889266312 0.0935865697 0.2899309695 0.0088846132 0.1245670000 959875833 0 402718720 -0.3546455503 0.1781535745 -0.9794614315 948 37.8800000000 0.2890874743 0.0937927943 0.2899309695 0.0088842279 0.1264350000 959877841 0 402718720 -0.3448339999 0.1759418845 -0.9809376001 949 37.9200000000 0.2878213227 0.0939972501 0.2899309695 0.0088838233 0.1268910000 959879849 0 402718720 -0.3343992233 0.1746897548 -0.9834703803 950 37.9600000000 0.2875072062 0.0942009448 0.2899309695 0.0088814104 0.1264250000 959881857 0 402718720 -0.3243421018 0.1740547717 -0.9854753017 951 38.0000000000 0.2881593704 0.0944048968 0.2899309695 0.0088786149 0.1251260000 959883865 0 402718720 -0.3152104914 0.1727651954 -0.9867020845 952 38.0400000000 0.2882550359 0.0946085209 0.2899309695 0.0088770231 0.1245780000 959885873 0 402718720 -0.3051422834 0.1704446673 -0.9889333844 953 38.0800000000 0.2881019115 0.0948115570 0.2899309695 0.0088752255 0.1342160000 959887881 0 402718720 -0.2954090238 0.1697030514 -0.9901111126 954 38.1200000000 0.2878943682 0.0950139499 0.2899309695 0.0088727050 0.1244780000 959889889 0 402718720 -0.2847869098 0.1686333716 -0.9918428063 955 38.1600000000 0.2861564755 0.0952140991 0.2899309695 0.0088711843 0.1222600000 959891897 0 402718720 -0.2747186124 0.1678927988 -0.9930554032 956 38.2000000000 0.2857343853 0.0954133881 0.2899309695 0.0088681144 0.1219670000 959893905 0 402718720 -0.2630836368 0.1670035869 -0.9950536489 957 38.2400000000 0.2851935029 0.0956116955 0.2899309695 0.0088642647 0.1212160000 959895913 0 402718720 -0.2516164482 0.1660675406 -0.9974771142 958 38.2800000000 0.2853097916 0.0958097102 0.2899309695 0.0088604145 0.1206720000 959897921 0 402718720 -0.2423544079 0.1644216180 -0.9998445511 959 38.3200000000 0.2833900452 0.0960053101 0.2899309695 0.0088571670 0.1202390000 959899929 0 402718720 -0.2315460742 0.1651352048 -1.0018556118 960 38.3600000000 0.2817838192 0.0961988294 0.2899309695 0.0088562073 0.1195100000 959901937 0 402718720 -0.2185931355 0.1673690826 -1.0031530857 961 38.4000000000 0.2861818075 0.0963965224 0.2899309695 0.0088622921 0.1190010000 959903945 0 402718720 -0.2093741745 0.1655058712 -1.0042850971 962 38.4400000000 0.2877679169 0.0965954532 0.2899309695 0.0088612823 0.1184250000 959905953 0 402718720 -0.1994850487 0.1645279229 -1.0054969788 963 38.4800000000 0.2902917266 0.0967965916 0.2902917266 0.0088647075 0.1329440000 959907961 0 402718720 -0.1892176867 0.1646014005 -1.0103996992 964 38.5200000000 0.2909066975 0.0969979506 0.2909066975 0.0088651081 0.1221250000 959909969 0 402718720 -0.1793262661 0.1630799919 -1.0114343166 965 38.5600000000 0.2908540070 0.0971988377 0.2909066975 0.0088626993 0.1213970000 959911977 0 402718720 -0.1686635911 0.1605966538 -1.0147563219 966 38.6000000000 0.2883436978 0.0973967102 0.2909066975 0.0088588425 0.1159730000 959913985 0 402718720 -0.1586550176 0.1561107486 -1.0145431757 967 38.6400000000 0.2856183648 0.0975913552 0.2909066975 0.0088563872 0.1147340000 959915993 0 402718720 -0.1478108466 0.1522617042 -1.0143799782 968 38.6800000000 0.2838149667 0.0977837349 0.2909066975 0.0088532339 0.1140540000 959918001 0 402718720 -0.1381449699 0.1485869437 -1.0152676105 969 38.7200000000 0.2827254832 0.0979745933 0.2909066975 0.0088498768 0.1118390000 959920009 0 402718720 -0.1284028590 0.1472617686 -1.0153045654 970 38.7600000000 0.2826633453 0.0981649941 0.2909066975 0.0088462714 0.1127640000 959922017 0 402718720 -0.1220401153 0.1449554563 -1.0162779093 971 38.8000000000 0.2825150490 0.0983548499 0.2909066975 0.0088432378 0.1120030000 959924025 0 402718720 -0.1126512811 0.1446920633 -1.0171867609 972 38.8400000000 0.2837944031 0.0985456314 0.2909066975 0.0088443511 0.1117110000 959926033 0 402718720 -0.1039213762 0.1456881016 -1.0177361965 973 38.8800000000 0.2859740853 0.0987382608 0.2909066975 0.0088531808 0.1196290000 959928041 0 402718720 -0.0950399563 0.1475535333 -1.0177946091 974 38.9200000000 0.2880455554 0.0989326215 0.2909066975 0.0088603555 0.1105450000 959930049 0 402718720 -0.0876760110 0.1474300325 -1.0171349049 975 38.9600000000 0.2885563374 0.0991271073 0.2909066975 0.0088593617 0.1101620000 959932057 0 402718720 -0.0794264525 0.1460534781 -1.0160677433 976 39.0000000000 0.2884847522 0.0993211213 0.2909066975 0.0088562424 0.1097030000 959934065 0 402718720 -0.0713245496 0.1440491825 -1.0154384375 977 39.0400000000 0.2868949771 0.0995131109 0.2909066975 0.0088528079 0.1102190000 959936073 0 402718720 -0.0610063784 0.1422870010 -1.0162464380 978 39.0800000000 0.2856264114 0.0997034108 0.2909066975 0.0088489615 0.1103380000 959938081 0 402718720 -0.0515924469 0.1393937767 -1.0139569044 979 39.1200000000 0.2836916745 0.0998913457 0.2909066975 0.0088490863 0.1122520000 959940089 0 402718720 -0.0431952737 0.1353928149 -1.0133986473 980 39.1600000000 0.2824611366 0.1000776414 0.2909066975 0.0088478268 0.1108810000 959942097 0 402718720 -0.0318440087 0.1339537799 -1.0139653683 981 39.2000000000 0.2806807160 0.1002617424 0.2909066975 0.0088446198 0.1131570000 959944105 0 402718720 -0.0199322812 0.1334881783 -1.0135592222 982 39.2400000000 0.2805957794 0.1004453820 0.2909066975 0.0088418111 0.1138000000 959946113 0 402718720 -0.0143467197 0.1320425421 -1.0132248402 983 39.2800000000 0.2809328735 0.1006289908 0.2909066975 0.0088401552 0.1232020000 959948121 0 402718720 -0.0051994626 0.1310840845 -1.0147705078 984 39.3200000000 0.2897591889 0.1008211963 0.2909066975 0.0088502367 0.1181090000 959950129 0 402718720 0.0057162978 0.1393638849 -1.0300633907 985 39.3600000000 0.2882671356 0.1010114968 0.2909066975 0.0088487604 0.1124480000 959952137 0 402718720 0.0129632503 0.1352943331 -1.0308780670 986 39.4000000000 0.2865509391 0.1011996706 0.2909066975 0.0088454682 0.1133090000 959954145 0 402718720 0.0210925415 0.1323511004 -1.0290329456 987 39.4400000000 0.2853994370 0.1013862965 0.2909066975 0.0088425376 0.1126730000 959956153 0 402718720 0.0307147782 0.1300132275 -1.0281317234 988 39.4800000000 0.2844905853 0.1015716248 0.2909066975 0.0088392419 0.1111040000 959958161 0 402718720 0.0412570611 0.1282333881 -1.0282828808 989 39.5200000000 0.2830714285 0.1017551433 0.2909066975 0.0088359981 0.1097040000 959960169 0 402718720 0.0500216261 0.1258858293 -1.0294299126 990 39.5600000000 0.2818637788 0.1019370712 0.2909066975 0.0088325562 0.1104500000 959962177 0 402718720 0.0597318672 0.1248289645 -1.0298862457 991 39.6000000000 0.2810524702 0.1021178133 0.2909066975 0.0088299245 0.1098290000 959964185 0 402718720 0.0695499703 0.1258196533 -1.0280967951 992 39.6400000000 0.2798761427 0.1022970051 0.2909066975 0.0088277997 0.1093820000 959966193 0 402718720 0.0792877227 0.1270082891 -1.0268409252 993 39.6800000000 0.2794676423 0.1024754247 0.2909066975 0.0088294768 0.1199170000 959968201 0 402718720 0.0885927305 0.1287094355 -1.0231676102 994 39.7200000000 0.2797193527 0.1026537385 0.2909066975 0.0088314992 0.1081090000 959970209 0 402718720 0.0982868820 0.1297043860 -1.0212000608 995 39.7600000000 0.2812063396 0.1028331884 0.2909066975 0.0088330568 0.1059660000 959972217 0 402718720 0.1066719890 0.1298261881 -1.0203107595 996 39.8000000000 0.2824939489 0.1030135707 0.2909066975 0.0088308215 0.1081710000 959974225 0 402718720 0.1162076145 0.1299728304 -1.0193068981 997 39.8400000000 0.2829293013 0.1031940278 0.2909066975 0.0088289022 0.1074740000 959976233 0 402718720 0.1268213391 0.1303711683 -1.0185050964 998 39.8800000000 0.2840586305 0.1033752548 0.2909066975 0.0088266007 0.1055540000 959978241 0 402718720 0.1359017193 0.1304616332 -1.0178089142 999 39.9200000000 0.2855755985 0.1035576375 0.2909066975 0.0088233464 0.1083330000 959980249 0 402718720 0.1483865082 0.1360771954 -1.0158476830 1000 39.9600000000 0.2868452966 0.1037409252 0.2909066975 0.0088230945 0.1087490000 959982257 0 402718720 0.1570681632 0.1365391910 -1.0165876150 1001 40.0000000000 0.2851286232 0.1039221317 0.2909066975 0.0088199513 0.1054100000 959984265 0 402718720 0.1665781885 0.1335671693 -1.0159841776 1002 40.0400000000 0.2832931280 0.1041011447 0.2909066975 0.0088165905 0.1039850000 959986273 0 402718720 0.1774486899 0.1328624487 -1.0134906769 1003 40.0800000000 0.2817409039 0.1042782531 0.2909066975 0.0088144751 0.1300130000 959988281 0 402718720 0.1889697611 0.1335889250 -1.0118490458 1004 40.1200000000 0.2826496363 0.1044559138 0.2909066975 0.0088161456 0.1052510000 959990289 0 402718720 0.1976015419 0.1335507929 -1.0095183849 1005 40.1600000000 0.2818364799 0.1046324119 0.2909066975 0.0088132855 0.1071930000 959992297 0 402718720 0.2072124034 0.1329436749 -1.0081042051 1006 40.2000000000 0.2803987861 0.1048071300 0.2909066975 0.0088106108 0.1075980000 959994305 0 402718720 0.2175724059 0.1337166876 -1.0051093102 1007 40.2400000000 0.2795976102 0.1049807054 0.2909066975 0.0088089690 0.1078860000 959996313 0 402718720 0.2274794132 0.1342836767 -1.0014915466 1008 40.2800000000 0.2798539400 0.1051541908 0.2909066975 0.0088076510 0.1082060000 959998321 0 402718720 0.2355547100 0.1341567189 -0.9978745580 1009 40.3200000000 0.2792098820 0.1053266939 0.2909066975 0.0088051347 0.1175750000 960000329 0 402718720 0.2442870587 0.1340520680 -0.9942171574 1010 40.3600000000 0.2784253657 0.1054980788 0.2909066975 0.0088032213 0.1081440000 960002337 0 402718720 0.2544123828 0.1339262128 -0.9908789992 1011 40.4000000000 0.2781094611 0.1056688121 0.2909066975 0.0088015808 0.1081150000 960004345 0 402718720 0.2625077963 0.1329805404 -0.9882931113 1012 40.4400000000 0.2772423625 0.1058383512 0.2909066975 0.0087975706 0.1210750000 960006353 0 402718720 0.2707783878 0.1306273788 -0.9870184660 1013 40.4800000000 0.2753263712 0.1060056641 0.2909066975 0.0087939555 0.1243900000 960008361 0 402718720 0.2801482677 0.1293562353 -0.9833918214 1014 40.5200000000 0.2736229599 0.1061709672 0.2909066975 0.0087898747 0.1096090000 960010369 0 402718720 0.2877461016 0.1277170330 -0.9795193672 1015 40.5600000000 0.2723892629 0.1063347290 0.2909066975 0.0087863503 0.1117210000 960012377 0 402718720 0.2960833013 0.1251316816 -0.9781669974 1016 40.6000000000 0.2719707191 0.1064977566 0.2909066975 0.0087824800 0.1248980000 960014385 0 402718720 0.3037299514 0.1225668788 -0.9767144322 1017 40.6400000000 0.2710530162 0.1066595612 0.2909066975 0.0087794982 0.1108650000 960016393 0 402718720 0.3108963668 0.1221452504 -0.9733619094 1018 40.6800000000 0.2716940939 0.1068216776 0.2909066975 0.0087757005 0.1246380000 960018401 0 402718720 0.3193884790 0.1225879341 -0.9709810019 1019 40.7200000000 0.2720382512 0.1069838136 0.2909066975 0.0087717547 0.1122160000 960020409 0 402718720 0.3263053298 0.1233633906 -0.9668093920 1020 40.7600000000 0.2723238766 0.1071459117 0.2909066975 0.0087680772 0.1108190000 960022417 0 402718720 0.3350264430 0.1236460656 -0.9632997513 1021 40.8000000000 0.2721441686 0.1073075163 0.2909066975 0.0087645494 0.1125160000 960024425 0 402718720 0.3431394100 0.1238801777 -0.9595299959 1022 40.8400000000 0.2712399065 0.1074679198 0.2909066975 0.0087605116 0.1112060000 960026433 0 402718720 0.3505663574 0.1237897724 -0.9537986517 1023 40.8800000000 0.2705736160 0.1076273584 0.2909066975 0.0087564059 0.1236820000 960028441 0 402718720 0.3579254448 0.1235098615 -0.9480626583 1024 40.9200000000 0.2699119151 0.1077858394 0.2909066975 0.0087529274 0.1133540000 960030449 0 402718720 0.3672113121 0.1235746592 -0.9440395832 1025 40.9600000000 0.2702166736 0.1079443085 0.2909066975 0.0087503689 0.1123530000 960032457 0 402718720 0.3768353164 0.1244553179 -0.9390533566 1026 41.0000000000 0.2708258331 0.1081030624 0.2909066975 0.0087483546 0.1159900000 960239265 0 402718720 0.3830421567 0.1248586923 -0.9337022901 1027 41.0400000000 0.2705580592 0.1082612464 0.2909066975 0.0087444999 0.1164450000 960241273 0 402718720 0.3914218247 0.1233095676 -0.9312102199 1028 41.0800000000 0.2694058120 0.1084180019 0.2909066975 0.0087411512 0.1164520000 960243281 0 402718720 0.4024468064 0.1239269525 -0.9247753024 1029 41.1200000000 0.2681289911 0.1085732118 0.2909066975 0.0087387681 0.1154850000 960245289 0 402718720 0.4110862911 0.1226891130 -0.9210461974 1030 41.1600000000 0.2683618069 0.1087283463 0.2909066975 0.0087377604 0.1160610000 960247297 0 402718720 0.4192727506 0.1225755662 -0.9174485207 1031 41.2000000000 0.2700367868 0.1088848046 0.2909066975 0.0087383459 0.1169720000 960249305 0 402718720 0.4283349812 0.1234493479 -0.9136159420 1032 41.2400000000 0.2712260187 0.1090421119 0.2909066975 0.0087382915 0.1172810000 960251313 0 402718720 0.4370724857 0.1245081350 -0.9097484946 1033 41.2800000000 0.2718097568 0.1091996798 0.2909066975 0.0087385470 0.1312230000 960253321 0 402718720 0.4471072257 0.1261069328 -0.9053871632 1034 41.3200000000 0.2730744481 0.1093581661 0.2909066975 0.0087407534 0.1221680000 960255329 0 402718720 0.4573352039 0.1279564053 -0.8995260000 1035 41.3600000000 0.2734439671 0.1095167031 0.2909066975 0.0087470018 0.1180710000 960257337 0 402718720 0.4635580480 0.1281072795 -0.8971884251 1036 41.4000000000 0.2740177512 0.1096754879 0.2909066975 0.0087453475 0.1308560000 960259345 0 402718720 0.4701434076 0.1263128817 -0.8941982985 1037 41.4400000000 0.2727222741 0.1098327172 0.2909066975 0.0087417213 0.1542300000 960261353 0 402718720 0.4796158373 0.1241693050 -0.8902190328 1038 41.4800000000 0.2703815401 0.1099873885 0.2909066975 0.0087380885 0.1543810000 960263361 0 402718720 0.4888149798 0.1236768812 -0.8842326999 1039 41.5200000000 0.2686732709 0.1101401179 0.2909066975 0.0087344338 0.1551770000 960265369 0 402718720 0.4978946447 0.1236758009 -0.8791391253 1040 41.5600000000 0.2664382160 0.1102904046 0.2909066975 0.0087310612 0.1551250000 960267377 0 402718720 0.5050388575 0.1243114248 -0.8729947209 1041 41.6000000000 0.2657191157 0.1104397117 0.2909066975 0.0087278631 0.1524990000 960269385 0 402718720 0.5122067332 0.1236633062 -0.8701798320 1042 41.6400000000 0.2656412721 0.1105886575 0.2909066975 0.0087277363 0.1194560000 960271393 0 402718720 0.5224936604 0.1253536642 -0.8652430177 1043 41.6800000000 0.2658409774 0.1107375092 0.2909066975 0.0087357971 0.1314030000 960273401 0 402718720 0.5287832618 0.1268503666 -0.8606054783 1044 41.7200000000 0.2698384225 0.1108899047 0.2909066975 0.0087729808 0.1241470000 960275409 0 402718720 0.5430460572 0.1311825067 -0.8571783900 1045 41.7600000000 0.2704812884 0.1110426237 0.2909066975 0.0087821183 0.1210850000 960277417 0 402718720 0.5506355762 0.1319394857 -0.8546367288 1046 41.8000000000 0.2692526281 0.1111938761 0.2909066975 0.0087855557 0.1211040000 960279425 0 402718720 0.5559841990 0.1318480223 -0.8482636213 1047 41.8400000000 0.2674227953 0.1113430919 0.2909066975 0.0087830615 0.1214370000 960281433 0 402718720 0.5623486042 0.1300365925 -0.8439866304 1048 41.8800000000 0.2662290931 0.1114908839 0.2909066975 0.0087807293 0.1332900000 960283441 0 402718720 0.5703445673 0.1294973940 -0.8377891183 1049 41.9200000000 0.2648586035 0.1116370876 0.2909066975 0.0087794004 0.1408920000 960285449 0 402718720 0.5771738291 0.1285336018 -0.8324311972 1050 41.9600000000 0.2627178133 0.1117809740 0.2909066975 0.0087757711 0.1206830000 960287457 0 402718720 0.5825619102 0.1269021332 -0.8283352256 1051 42.0000000000 0.2623813450 0.1119242665 0.2909066975 0.0087723703 0.1223310000 960289465 0 402718720 0.5902248621 0.1256057471 -0.8247866631 1052 42.0400000000 0.2609916329 0.1120659655 0.2909066975 0.0087694563 0.1225260000 960291473 0 402718720 0.5968691707 0.1255809665 -0.8188108802 1053 42.0800000000 0.2590008676 0.1122055048 0.2909066975 0.0087657227 0.1229000000 960293481 0 402718720 0.6024478674 0.1252485663 -0.8138849139 1054 42.1200000000 0.2584967911 0.1123443011 0.2909066975 0.0087625772 0.1228170000 960295489 0 402718720 0.6084709167 0.1250953227 -0.8081557155 1055 42.1600000000 0.2562789321 0.1124807321 0.2909066975 0.0087594653 0.1212440000 960297497 0 402718720 0.6191812158 0.1233976930 -0.7972791195 1056 42.2000000000 0.2552661300 0.1126159455 0.2909066975 0.0087554135 0.1222210000 960299505 0 402718720 0.6252394915 0.1227654815 -0.7901628017 1057 42.2400000000 0.2541184723 0.1127498173 0.2909066975 0.0087514060 0.1340290000 960301513 0 402718720 0.6308386922 0.1224607378 -0.7822645903 1058 42.2800000000 0.2530293465 0.1128824067 0.2909066975 0.0087488636 0.1213910000 960303521 0 402718720 0.6364897490 0.1228617206 -0.7729834914 1059 42.3200000000 0.2512186170 0.1130130358 0.2909066975 0.0087468324 0.1213650000 960305529 0 402718720 0.6397246122 0.1235127375 -0.7658342719 1060 42.3600000000 0.2507028282 0.1131429318 0.2909066975 0.0087452369 0.1219390000 960307537 0 402718720 0.6437445283 0.1241841838 -0.7578911781 1061 42.4000000000 0.2496782392 0.1132716173 0.2909066975 0.0087423615 0.1230580000 960309545 0 402718720 0.6479687095 0.1243999153 -0.7505862117 1062 42.4400000000 0.2489705533 0.1133993941 0.2909066975 0.0087404047 0.1356750000 960311553 0 402718720 0.6522843242 0.1251046807 -0.7426129580 1063 42.4800000000 0.2488334626 0.1135268015 0.2909066975 0.0087411297 0.1338690000 960313561 0 402718720 0.6570858955 0.1260390431 -0.7344021797 1064 42.5200000000 0.2487951815 0.1136539334 0.2909066975 0.0087420239 0.1235820000 960315569 0 402718720 0.6611157060 0.1265455931 -0.7270138264 1065 42.5600000000 0.2478968054 0.1137799831 0.2909066975 0.0087406392 0.1236070000 960317577 0 402718720 0.6643719673 0.1266318560 -0.7203470469 1066 42.6000000000 0.2464655042 0.1139044535 0.2909066975 0.0087381935 0.1226040000 960319585 0 402718720 0.6678752303 0.1268060207 -0.7124223113 1067 42.6400000000 0.2457543761 0.1140280242 0.2909066975 0.0087369110 0.1227080000 960321593 0 402718720 0.6714143157 0.1270169020 -0.7056663036 1068 42.6800000000 0.2440826595 0.1141497982 0.2909066975 0.0087342640 0.1347440000 960323601 0 402718720 0.6734046340 0.1271122098 -0.6983898282 1069 42.7200000000 0.2461746633 0.1142733014 0.2909066975 0.0087342343 0.1247820000 960325609 0 402718720 0.6799593568 0.1322782934 -0.6899986863 1070 42.7600000000 0.2449720353 0.1143954497 0.2909066975 0.0087419086 0.1267260000 960327617 0 402718720 0.6841137409 0.1356967241 -0.6794391870 1071 42.8000000000 0.2433363199 0.1145158427 0.2909066975 0.0087500089 0.1275750000 960329625 0 402718720 0.6874315143 0.1361992508 -0.6668031216 1072 42.8400000000 0.2414434701 0.1146342453 0.2909066975 0.0087468322 0.1277910000 960331633 0 402718720 0.6907157898 0.1367230713 -0.6554601192 1073 42.8800000000 0.2402737439 0.1147513371 0.2909066975 0.0087455605 0.1282990000 960333641 0 402718720 0.6917508841 0.1363277435 -0.6445990205 1074 42.9200000000 0.2388791442 0.1148669124 0.2909066975 0.0087434678 0.1278930000 960335649 0 402718720 0.6962483525 0.1371491104 -0.6352766156 1075 42.9600000000 0.2368516177 0.1149803865 0.2909066975 0.0087410789 0.1290410000 960337657 0 402718720 0.6988821626 0.1374064982 -0.6241690516 1076 43.0000000000 0.2355104536 0.1150924033 0.2909066975 0.0087407650 0.1292220000 960339665 0 402718720 0.7018148303 0.1387885809 -0.6168363094 1077 43.0400000000 0.2341342568 0.1152029343 0.2909066975 0.0087409353 0.1295750000 960341673 0 402718720 0.7064514160 0.1390095949 -0.6087443829 1078 43.0800000000 0.2324698269 0.1153117162 0.2909066975 0.0087409758 0.1285210000 960343681 0 402718720 0.7085601687 0.1387239844 -0.6013221145 1079 43.1200000000 0.2307394147 0.1154186927 0.2909066975 0.0087391752 0.1271620000 960345689 0 402718720 0.7106180191 0.1382774562 -0.5939176679 1080 43.1600000000 0.2295642197 0.1155243830 0.2909066975 0.0087356686 0.1306680000 960347697 0 402718720 0.7165948749 0.1393549144 -0.5842640996 1081 43.2000000000 0.2283413112 0.1156287465 0.2909066975 0.0087336659 0.1312310000 960349705 0 402718720 0.7196552157 0.1386169195 -0.5755878091 1082 43.2400000000 0.2240589708 0.1157289593 0.2909066975 0.0087298919 0.1286050000 960351713 0 402718720 0.7210241556 0.1361132413 -0.5670496225 1083 43.2800000000 0.2238820493 0.1158288236 0.2909066975 0.0087259143 0.1419170000 960353721 0 402718720 0.7256352305 0.1371148825 -0.5562031865 1084 43.3200000000 0.2224106491 0.1159271463 0.2909066975 0.0087224521 0.1343820000 960355729 0 402718720 0.7306798100 0.1367633939 -0.5454865098 1085 43.3600000000 0.2169328183 0.1160202391 0.2909066975 0.0087189860 0.1303370000 960357737 0 402718720 0.7320833206 0.1335201114 -0.5377115011 1086 43.4000000000 0.2147852182 0.1161111829 0.2909066975 0.0087151273 0.1319830000 960359745 0 402718720 0.7351318002 0.1324661821 -0.5295068622 1087 43.4400000000 0.2126549929 0.1161999997 0.2909066975 0.0087113272 0.1328000000 960361753 0 402718720 0.7385317683 0.1317037791 -0.5205641389 1088 43.4800000000 0.2107116580 0.1162868670 0.2909066975 0.0087074001 0.1570640000 960363761 0 402718720 0.7402108908 0.1302834302 -0.5135501623 1089 43.5200000000 0.2093897313 0.1163723609 0.2909066975 0.0087034575 0.1331590000 960365769 0 402718720 0.7430334687 0.1293279976 -0.5056473017 1090 43.5600000000 0.2068437636 0.1164553622 0.2909066975 0.0086996776 0.1335690000 960367777 0 402718720 0.7471055984 0.1284473687 -0.4960315228 1091 43.6000000000 0.2054230273 0.1165369091 0.2909066975 0.0086981163 0.1320080000 960369785 0 402718720 0.7506511211 0.1282137781 -0.4871957302 1092 43.6400000000 0.2027676105 0.1166158750 0.2909066975 0.0086961453 0.1340470000 960371793 0 402718720 0.7530981898 0.1279747039 -0.4797084033 1093 43.6800000000 0.2007435411 0.1166928445 0.2909066975 0.0086951966 0.1330870000 960373801 0 402718720 0.7571786642 0.1277437955 -0.4710149467 1094 43.7200000000 0.1975923479 0.1167667928 0.2909066975 0.0086935673 0.1331180000 960375809 0 402718720 0.7593117356 0.1273490340 -0.4644592702 1095 43.7600000000 0.1953801960 0.1168385859 0.2909066975 0.0086906980 0.1594150000 960377817 0 402718720 0.7602690458 0.1266911626 -0.4584515691 1096 43.8000000000 0.1927724779 0.1169078686 0.2909066975 0.0086871604 0.1738670000 960379825 0 402718720 0.7630716562 0.1261651665 -0.4514312148 1097 43.8400000000 0.1900005043 0.1169744982 0.2909066975 0.0086839523 0.1352170000 960381833 0 402718720 0.7672091722 0.1260523498 -0.4422353208 1098 43.8800000000 0.1893934608 0.1170404535 0.2909066975 0.0086874475 0.1446200000 960383841 0 402718720 0.7715659142 0.1269112825 -0.4321022630 1099 43.9200000000 0.1873205304 0.1171044027 0.2909066975 0.0086899040 0.1319930000 960385849 0 402718720 0.7736035585 0.1271172464 -0.4254843891 1100 43.9600000000 0.1836411059 0.1171648906 0.2909066975 0.0086876451 0.1343290000 960387857 0 402718720 0.7757677436 0.1263801008 -0.4190655649 1101 44.0000000000 0.1801491529 0.1172220970 0.2909066975 0.0086840491 0.1345920000 960389865 0 402718720 0.7802586555 0.1250137091 -0.4120427072 1102 44.0400000000 0.1769576371 0.1172763035 0.2909066975 0.0086803086 0.1348510000 960391873 0 402718720 0.7836321592 0.1229582280 -0.4052062333 1103 44.0800000000 0.1727688313 0.1173266140 0.2909066975 0.0086770035 0.1468420000 960393881 0 402718720 0.7880960703 0.1202309430 -0.3971896172 1104 44.1200000000 0.1697844118 0.1173741301 0.2909066975 0.0086732173 0.1354010000 960395889 0 402718720 0.7917683125 0.1178428084 -0.3882675469 1105 44.1600000000 0.1665443033 0.1174186280 0.2909066975 0.0086695960 0.1369160000 960397897 0 402718720 0.7963992357 0.1155706272 -0.3784282804 1106 44.2000000000 0.1641939878 0.1174609204 0.2909066975 0.0086665843 0.1361550000 960399905 0 402718720 0.8012793660 0.1139567569 -0.3686980307 1107 44.2400000000 0.1613787562 0.1175005932 0.2909066975 0.0086647165 0.1355800000 960401913 0 402718720 0.8061584234 0.1123485416 -0.3592062294 1108 44.2800000000 0.1591033489 0.1175381408 0.2909066975 0.0086632860 0.1356480000 960403921 0 402718720 0.8107309937 0.1104988530 -0.3498746157 1109 44.3200000000 0.1551190466 0.1175720280 0.2909066975 0.0086603638 0.1488070000 960405929 0 402718720 0.8146235347 0.1079734117 -0.3410598040 1110 44.3600000000 0.1507891268 0.1176019534 0.2909066975 0.0086572935 0.1342920000 960407937 0 402718720 0.8182044029 0.1063628718 -0.3320780098 1111 44.4000000000 0.1495882720 0.1176307439 0.2909066975 0.0086563726 0.1346190000 960409945 0 402718720 0.8214493394 0.1053683758 -0.3228380382 1112 44.4400000000 0.1469878107 0.1176571442 0.2909066975 0.0086557419 0.1376240000 960411953 0 402718720 0.8257092237 0.1038741171 -0.3126433194 1113 44.4800000000 0.1450276375 0.1176817358 0.2909066975 0.0086620642 0.1493450000 960413961 0 402718720 0.8283218741 0.1032348573 -0.3021231294 1114 44.5200000000 0.1450249404 0.1177062809 0.2909066975 0.0086681976 0.1392400000 960415969 0 402718720 0.8271548152 0.1031389758 -0.2949750125 1115 44.5600000000 0.1433514208 0.1177292810 0.2909066975 0.0086678944 0.1422300000 960417977 0 402718720 0.8279154897 0.1022707075 -0.2865350842 1116 44.6000000000 0.1392104626 0.1177485294 0.2909066975 0.0086651269 0.1449480000 960419985 0 402718720 0.8358441591 0.1009265035 -0.2758089006 1117 44.6400000000 0.1333551109 0.1177625012 0.2909066975 0.0086619111 0.1456600000 960421993 0 402718720 0.8413373232 0.0983736366 -0.2664012611 1118 44.6800000000 0.1304972619 0.1177738919 0.2909066975 0.0086584084 0.1421860000 960424001 0 402718720 0.8440352678 0.0955121815 -0.2580789328 1119 44.7200000000 0.1274029166 0.1177824969 0.2909066975 0.0086550360 0.1453640000 960426009 0 402718720 0.8526008725 0.0946343094 -0.2476695627 1120 44.7600000000 0.1244852841 0.1177884816 0.2909066975 0.0086518807 0.1455860000 960428017 0 402718720 0.8581073880 0.0931276456 -0.2367722988 1121 44.8000000000 0.1215833798 0.1177918668 0.2909066975 0.0086483879 0.1417670000 960430025 0 402718720 0.8608044982 0.0916521996 -0.2265432626 1122 44.8400000000 0.1204634160 0.1177942479 0.2909066975 0.0086450285 0.1428670000 960432033 0 402718720 0.8622260094 0.0920370221 -0.2170992792 1123 44.8800000000 0.1185015514 0.1177948777 0.2909066975 0.0086414109 0.1510770000 960434041 0 402718720 0.8666358590 0.0929172114 -0.2063301206 1124 44.9200000000 0.1176347062 0.1177947352 0.2909066975 0.0086382991 0.1663960000 960436049 0 402718720 0.8712434173 0.0941666588 -0.1961877197 1125 44.9600000000 0.1149390489 0.1177921968 0.2909066975 0.0086347949 0.1543530000 960438057 0 402718720 0.8769724965 0.0952091292 -0.1864021122 1126 45.0000000000 0.1131768376 0.1177880979 0.2909066975 0.0086311611 0.1437060000 960440065 0 402718720 0.8824765086 0.0957796946 -0.1772163659 1127 45.0400000000 0.1110609546 0.1177821289 0.2909066975 0.0086276371 0.1420110000 960442073 0 402718720 0.8871786594 0.0951754749 -0.1693643779 1128 45.0800000000 0.1092043221 0.1177745244 0.2909066975 0.0086239931 0.1431270000 960444081 0 402718720 0.8912968636 0.0943287387 -0.1602556705 1129 45.1200000000 0.1077490300 0.1177656445 0.2909066975 0.0086202602 0.1428740000 960446089 0 402718720 0.8948659301 0.0943521708 -0.1504561901 1130 45.1600000000 0.1074915826 0.1177565524 0.2909066975 0.0086166644 0.1432390000 960448097 0 402718720 0.8971244693 0.0946632698 -0.1417209655 1131 45.2000000000 0.1070410460 0.1177470780 0.2909066975 0.0086129118 0.1421910000 960450105 0 402718720 0.8990057111 0.0944488645 -0.1345211864 1132 45.2400000000 0.1073400676 0.1177378845 0.2909066975 0.0086094440 0.1448390000 960452113 0 402718720 0.9012508392 0.0939168409 -0.1272013336 1133 45.2800000000 0.1063025743 0.1177277916 0.2909066975 0.0086058900 0.1560680000 960454121 0 402718720 0.9051389694 0.0927779749 -0.1187083051 1134 45.3200000000 0.1048233286 0.1177164120 0.2909066975 0.0086022448 0.1459980000 960456129 0 402718720 0.9091441035 0.0927930772 -0.1098971739 1135 45.3600000000 0.1056947783 0.1177058202 0.2909066975 0.0085997945 0.1467760000 960458137 0 402718720 0.9108275175 0.0934456363 -0.1023108289 1136 45.4000000000 0.1043649539 0.1176940765 0.2909066975 0.0085963932 0.1490940000 960460145 0 402718720 0.9139264226 0.0953845456 -0.0937543884 1137 45.4400000000 0.1039111465 0.1176819543 0.2909066975 0.0085928885 0.1471120000 960462153 0 402718720 0.9152729511 0.0973315090 -0.0862922817 1138 45.4800000000 0.1042259708 0.1176701301 0.2909066975 0.0085893101 0.1484840000 960464161 0 402718720 0.9167841077 0.0994489715 -0.0794556439 1139 45.5200000000 0.1041257679 0.1176582386 0.2909066975 0.0085858509 0.1491620000 960466169 0 402718720 0.9201216102 0.1019609794 -0.0717423111 1140 45.5600000000 0.1049687713 0.1176471075 0.2909066975 0.0085832591 0.1472890000 960468177 0 402718720 0.9194194674 0.1044602394 -0.0664957240 1141 45.6000000000 0.1051472574 0.1176361524 0.2909066975 0.0085795495 0.1500190000 960470185 0 402718720 0.9200602174 0.1051545218 -0.0603063703 1142 45.6400000000 0.1040541232 0.1176242592 0.2909066975 0.0085759569 0.1502990000 960472193 0 402718720 0.9237653613 0.1067545190 -0.0522390194 1143 45.6800000000 0.1048625186 0.1176130940 0.2909066975 0.0085724302 0.1629980000 960474201 0 402718720 0.9272605181 0.1077366322 -0.0449700393 1144 45.7200000000 0.1043028831 0.1176014592 0.2909066975 0.0085688243 0.1509120000 960476209 0 402718720 0.9313598275 0.1083704680 -0.0380902030 1145 45.7600000000 0.1064466015 0.1175917170 0.2909066975 0.0085653514 0.1545100000 960478217 0 402718720 0.9352022409 0.1129795909 -0.0304567758 1146 45.8000000000 0.1060787886 0.1175816708 0.2909066975 0.0085617992 0.1540010000 960480225 0 402718720 0.9416522980 0.1135653257 -0.0226142835 1147 45.8400000000 0.1041597053 0.1175699690 0.2909066975 0.0085581425 0.1531850000 960482233 0 402718720 0.9456264377 0.1125265211 -0.0164095908 1148 45.8800000000 0.1031168252 0.1175573792 0.2909066975 0.0085544517 0.1529070000 960484241 0 402718720 0.9494006634 0.1118160039 -0.0095529268 1149 45.9200000000 0.1049098223 0.1175463717 0.2909066975 0.0085510910 0.1563210000 960486249 0 402718720 0.9534598589 0.1141172051 -0.0009349913 1150 45.9600000000 0.1034745425 0.1175341353 0.2909066975 0.0085475749 0.1513760000 960488257 0 402718720 0.9559323192 0.1128883064 0.0059871878 1151 46.0000000000 0.1046304330 0.1175229245 0.2909066975 0.0085439722 0.1580200000 960490265 0 402718720 0.9586402178 0.1141697839 0.0152124474 1152 46.0400000000 0.1049311236 0.1175119941 0.2909066975 0.0085407639 0.1577850000 960492273 0 402718720 0.9611681104 0.1148307770 0.0246735942 1153 46.0800000000 0.1045737192 0.1175007727 0.2909066975 0.0085379646 0.1707630000 960494281 0 402718720 0.9631289244 0.1141853184 0.0327968858 1154 46.1200000000 0.1046852469 0.1174896674 0.2909066975 0.0085342982 0.1715640000 960496289 0 402718720 0.9635654092 0.1147593707 0.0410374701 1155 46.1600000000 0.1055622399 0.1174793406 0.2909066975 0.0085309652 0.1631040000 960498297 0 402718720 0.9638508558 0.1194196045 0.0518486947 1156 46.2000000000 0.1046516970 0.1174682440 0.2909066975 0.0085276825 0.1590240000 960500305 0 402718720 0.9667586088 0.1204889044 0.0616475791 1157 46.2400000000 0.1044015735 0.1174569505 0.2909066975 0.0085245394 0.1809790000 960502313 0 402718720 0.9701017141 0.1224792153 0.0722191632 1158 46.2800000000 0.1043261439 0.1174456112 0.2909066975 0.0085209889 0.1668260000 960504321 0 402718720 0.9729863405 0.1272355914 0.0933247358 1159 46.3200000000 0.1038486063 0.1174338796 0.2909066975 0.0085173816 0.1645620000 960506329 0 402718720 0.9763501287 0.1293089688 0.1019643247 1160 46.3600000000 0.1040028259 0.1174223011 0.2909066975 0.0085137160 0.1679650000 960508337 0 402718720 0.9759930968 0.1332388371 0.1122384965 1161 46.4000000000 0.1035912037 0.1174103880 0.2909066975 0.0085109470 0.1704900000 960510345 0 402718720 0.9767699838 0.1371759623 0.1216442138 1162 46.4400000000 0.1034440547 0.1173983688 0.2909066975 0.0085075944 0.1714340000 960512353 0 402718720 0.9784416556 0.1401726007 0.1322515756 1163 46.4800000000 0.1033345312 0.1173862761 0.2909066975 0.0085039581 0.1815670000 960514361 0 402718720 0.9784775972 0.1412107199 0.1423070729 1164 46.5200000000 0.1035380289 0.1173743789 0.2909066975 0.0085008242 0.1857680000 960516369 0 402718720 0.9791088700 0.1439507455 0.1516770273 1165 46.5600000000 0.1036564559 0.1173626039 0.2909066975 0.0084976833 0.1731660000 960518377 0 402718720 0.9818774462 0.1490096748 0.1633348614 1166 46.6000000000 0.1035388336 0.1173507482 0.2909066975 0.0084943134 0.1753570000 960520385 0 402718720 0.9816377163 0.1509554833 0.1740851551 1167 46.6400000000 0.1040354967 0.1173393384 0.2909066975 0.0084908325 0.1759480000 960522393 0 402718720 0.9805316925 0.1546190083 0.1837580204 1168 46.6800000000 0.1040526554 0.1173279628 0.2909066975 0.0084873162 0.1831000000 960524401 0 402718720 0.9807780981 0.1554493904 0.1937207133 1169 46.7200000000 0.1039564759 0.1173165244 0.2909066975 0.0084842194 0.1825560000 960526409 0 402718720 0.9806569815 0.1574013680 0.2028849125 1170 46.7600000000 0.1041783243 0.1173052951 0.2909066975 0.0084810769 0.1775150000 960528417 0 402718720 0.9788687229 0.1597311199 0.2120544910 1171 46.8000000000 0.1043288186 0.1172942136 0.2909066975 0.0084793550 0.1775060000 960530425 0 402718720 0.9794163108 0.1649186164 0.2236376107 1172 46.8400000000 0.1045831069 0.1172833680 0.2909066975 0.0084758061 0.1783670000 960532433 0 402718720 0.9773778319 0.1697652340 0.2344357222 1173 46.8800000000 0.1041846126 0.1172722011 0.2909066975 0.0084722596 0.1751430000 960534441 0 402718720 0.9773800373 0.1703757048 0.2444979399 1174 46.9200000000 0.1040827110 0.1172609664 0.2909066975 0.0084688297 0.1757730000 960536449 0 402718720 0.9774968624 0.1728564054 0.2547697127 1175 46.9600000000 0.1045483574 0.1172501472 0.2909066975 0.0084654616 0.1881220000 960538457 0 402718720 0.9768042564 0.1734003425 0.2632538974 1176 47.0000000000 0.1043845937 0.1172392071 0.2909066975 0.0084618907 0.1826470000 960540465 0 402718720 0.9760851264 0.1773241609 0.2829201818 1177 47.0400000000 0.1050947830 0.1172288890 0.2909066975 0.0084583206 0.1799340000 960542473 0 402718720 0.9750573039 0.1801563948 0.2928738892 1178 47.0800000000 0.1045660898 0.1172181396 0.2909066975 0.0084549245 0.1934440000 960544481 0 402718720 0.9780522585 0.1793543547 0.3027122319 1179 47.1200000000 0.1050158665 0.1172077899 0.2909066975 0.0084514653 0.1810680000 960546489 0 402718720 0.9756680131 0.1798133552 0.3110913336 1180 47.1600000000 0.1053477898 0.1171977390 0.2909066975 0.0084508860 0.1866220000 960548497 0 402718720 0.9752100706 0.1830330789 0.3207621872 1181 47.2000000000 0.1050454751 0.1171874492 0.2909066975 0.0084480727 0.1829380000 960550505 0 402718720 0.9738278985 0.1838283539 0.3293110132 1182 47.2400000000 0.1046967432 0.1171768818 0.2909066975 0.0084446445 0.1797940000 960552513 0 402718720 0.9706763625 0.1812927872 0.3341613114 1183 47.2800000000 0.1050871164 0.1171666622 0.2909066975 0.0084414520 0.1852610000 960554521 0 402718720 0.9686265588 0.1819095910 0.3450542688 1184 47.3200000000 0.1045119613 0.1171559741 0.2909066975 0.0084380836 0.1865450000 960556529 0 402718720 0.9711605906 0.1831554770 0.3584764600 1185 47.3600000000 0.1043405160 0.1171451594 0.2909066975 0.0084354654 0.2009800000 960558537 0 402718720 0.9755648375 0.1808565408 0.3684882522 1186 47.4000000000 0.1046495885 0.1171346235 0.2909066975 0.0084338671 0.1907820000 960560545 0 402718720 0.9745011926 0.1805243343 0.3777191043 1187 47.4400000000 0.1049612984 0.1171243679 0.2909066975 0.0084303817 0.1912470000 960562553 0 402718720 0.9754407406 0.1826127172 0.3881528080 1188 47.4800000000 0.1047652662 0.1171139647 0.2909066975 0.0084272502 0.1903300000 960564561 0 402718720 0.9757938385 0.1826393902 0.3971659243 1189 47.5200000000 0.1044179127 0.1171032867 0.2909066975 0.0084266860 0.1942720000 960566569 0 402718720 0.9756784439 0.1816671938 0.4058292508 1190 47.5600000000 0.1042893231 0.1170925187 0.2909066975 0.0084236279 0.1967100000 960568577 0 402718720 0.9757859111 0.1820616424 0.4163736403 1191 47.6000000000 0.1047698483 0.1170821722 0.2909066975 0.0084200979 0.1985270000 960570585 0 402718720 0.9780389071 0.1811642200 0.4269133806 1192 47.6400000000 0.1050476059 0.1170720761 0.2909066975 0.0084166013 0.1997850000 960572593 0 402718720 0.9831656218 0.1814826280 0.4378834069 1193 47.6800000000 0.1056231782 0.1170624794 0.2909066975 0.0084131007 0.2007450000 960574601 0 402718720 0.9870442152 0.1815570593 0.4477694035 1194 47.7200000000 0.1057404280 0.1170529969 0.2909066975 0.0084096722 0.2012660000 960576609 0 402718720 0.9865781069 0.1800651997 0.4562845230 1195 47.7600000000 0.1062709019 0.1170439742 0.2909066975 0.0084065113 0.2129860000 960578617 0 402718720 0.9888703227 0.1810989529 0.4673783481 1196 47.8000000000 0.1068433747 0.1170354453 0.2909066975 0.0084032207 0.2013120000 960580625 0 402718720 0.9932156801 0.1829514802 0.4792890251 1197 47.8400000000 0.1069421247 0.1170270131 0.2909066975 0.0083998975 0.2003620000 960582633 0 402718720 0.9973945618 0.1833878458 0.4901627600 1198 47.8800000000 0.1070669964 0.1170186993 0.2909066975 0.0083966428 0.1998730000 960584641 0 402718720 0.9999606013 0.1852104813 0.5012550354 1199 47.9200000000 0.1071343049 0.1170104554 0.2909066975 0.0083938887 0.1973030000 960586649 0 402718720 1.0023565292 0.1854997277 0.5119572282 1200 47.9600000000 0.1072612107 0.1170023310 0.2909066975 0.0083906468 0.1991730000 960588657 0 402718720 1.0025706291 0.1837089956 0.5197727084 1201 48.0000000000 0.1075224429 0.1169944377 0.2909066975 0.0083896550 0.1986540000 960590665 0 402718720 1.0075340271 0.1853218079 0.5316463709 1202 48.0400000000 0.1074100062 0.1169864640 0.2909066975 0.0083893863 0.2019360000 960592673 0 402718720 1.0126887560 0.1873488575 0.5447717309 1203 48.0800000000 0.1078533381 0.1169788720 0.2909066975 0.0083863975 0.1967590000 960594681 0 402718720 1.0152636766 0.1883496344 0.5549378991 1204 48.1200000000 0.1079691499 0.1169713888 0.2909066975 0.0083873572 0.1962000000 960596689 0 402718720 1.0181632042 0.1889612675 0.5656310320 1205 48.1600000000 0.1081260741 0.1169640483 0.2909066975 0.0083846328 0.2097480000 960598697 0 402718720 1.0214395523 0.1911672354 0.5773655772 1206 48.2000000000 0.1084150448 0.1169569596 0.2909066975 0.0083812329 0.1950340000 960600705 0 402718720 1.0248866081 0.1925230473 0.5876969099 1207 48.2400000000 0.1089579016 0.1169503324 0.2909066975 0.0083778130 0.1956900000 960602713 0 402718720 1.0267279148 0.1923782676 0.5967470407 1208 48.2800000000 0.1090816557 0.1169438186 0.2909066975 0.0083745168 0.1940910000 960604721 0 402718720 1.0304669142 0.1931536347 0.6071079373 1209 48.3200000000 0.1093059853 0.1169375011 0.2909066975 0.0083715782 0.1936350000 960606729 0 402718720 1.0340818167 0.1953312308 0.6178604960 1210 48.3600000000 0.1093340367 0.1169312172 0.2909066975 0.0083681705 0.1929470000 960608737 0 402718720 1.0341358185 0.1958278120 0.6270878315 1211 48.4000000000 0.1093333140 0.1169249432 0.2909066975 0.0083648491 0.1925710000 960610745 0 402718720 1.0363082886 0.1959093958 0.6364863515 1212 48.4400000000 0.1097635180 0.1169190344 0.2909066975 0.0083625689 0.2159160000 960612753 0 402718720 1.0413599014 0.1995950043 0.6572359800 1213 48.4800000000 0.1101676151 0.1169134685 0.2909066975 0.0083607866 0.1870340000 960614761 0 402718720 1.0418115854 0.2014491856 0.6648612022 1214 48.5200000000 0.1104074717 0.1169081094 0.2909066975 0.0083590121 0.1848580000 960616769 0 402718720 1.0411106348 0.2016788721 0.6724602580 1215 48.5600000000 0.1101938933 0.1169025833 0.2909066975 0.0083571128 0.1998690000 960618777 0 402718720 1.0406357050 0.2016541660 0.6804518700 1216 48.6000000000 0.1102146059 0.1168970833 0.2909066975 0.0083600271 0.1871150000 960620785 0 402718720 1.0404244661 0.2041015178 0.6966814399 1217 48.6400000000 0.1100559682 0.1168914620 0.2909066975 0.0083566128 0.1859090000 960622793 0 402718720 1.0414345264 0.2050262094 0.7047153711 1218 48.6800000000 0.1100587845 0.1168858522 0.2909066975 0.0083543119 0.1850210000 960624801 0 402718720 1.0420960188 0.2062017918 0.7127982974 1219 48.7200000000 0.1105277911 0.1168806364 0.2909066975 0.0083524355 0.1779640000 960626809 0 402718720 1.0428019762 0.2058266550 0.7191312909 1220 48.7600000000 0.1104706675 0.1168753824 0.2909066975 0.0083507139 0.1774270000 960628817 0 402718720 1.0420101881 0.2072664499 0.7261580229 1221 48.8000000000 0.1104302406 0.1168701038 0.2909066975 0.0083484519 0.1765980000 960630825 0 402718720 1.0414155722 0.2083569020 0.7334948182 1222 48.8400000000 0.1101798192 0.1168646289 0.2909066975 0.0083457618 0.1759070000 960632833 0 402718720 1.0398284197 0.2105541229 0.7408254743 1223 48.8800000000 0.1102185547 0.1168591947 0.2909066975 0.0083424399 0.1761330000 960634841 0 402718720 1.0391066074 0.2108490467 0.7491126060 1224 48.9200000000 0.1101560146 0.1168537182 0.2909066975 0.0083396238 0.1751940000 960636849 0 402718720 1.0387246609 0.2107475698 0.7566943765 1225 48.9600000000 0.1102916226 0.1168483614 0.2909066975 0.0083374344 0.1744840000 960638857 0 402718720 1.0380109549 0.2111094743 0.7647491693 1226 49.0000000000 0.1102427170 0.1168429735 0.2909066975 0.0083353302 0.1736820000 960640865 0 402718720 1.0365018845 0.2116156071 0.7727634907 1227 49.0400000000 0.1101279110 0.1168375007 0.2909066975 0.0083325158 0.1852620000 960642873 0 402718720 1.0349406004 0.2122734040 0.7808166146 1228 49.0800000000 0.1098982543 0.1168318499 0.2909066975 0.0083297457 0.1703860000 960644881 0 402718720 1.0328342915 0.2138668448 0.7893146276 1229 49.1200000000 0.1098674461 0.1168261831 0.2909066975 0.0083275823 0.1720350000 960646889 0 402718720 1.0305470228 0.2147244066 0.7979567647 1230 49.1600000000 0.1100166291 0.1168206469 0.2909066975 0.0083257146 0.1712600000 960648897 0 402718720 1.0288574696 0.2153003663 0.8074378371 1231 49.2000000000 0.1100474894 0.1168151447 0.2909066975 0.0083231617 0.1700480000 960650905 0 402718720 1.0276910067 0.2159688771 0.8157333732 1232 49.2400000000 0.1100954115 0.1168096904 0.2909066975 0.0083209065 0.1666360000 960652913 0 402718720 1.0259703398 0.2164599001 0.8237641454 1233 49.2800000000 0.1096665561 0.1168038971 0.2909066975 0.0083179546 0.1681380000 960654921 0 402718720 1.0223740339 0.2165308446 0.8310663104 1234 49.3200000000 0.1094009504 0.1167978980 0.2909066975 0.0083146507 0.1809270000 960656929 0 402718720 1.0192762613 0.2163641155 0.8398066759 1235 49.3600000000 0.1089261025 0.1167915241 0.2909066975 0.0083116141 0.1838130000 960658937 0 402718720 1.0163499117 0.2161352038 0.8490344882 1236 49.4000000000 0.1088453755 0.1167850951 0.2909066975 0.0083084274 0.1681530000 960660945 0 402718720 1.0144884586 0.2164523154 0.8565469384 1237 49.4400000000 0.1087376326 0.1167785895 0.2909066975 0.0083051858 0.1719720000 960662953 0 402718720 1.0132794380 0.2169650644 0.8667626381 1238 49.4800000000 0.1086661741 0.1167720367 0.2909066975 0.0083018479 0.1713840000 960664961 0 402718720 1.0121561289 0.2172288597 0.8748021722 1239 49.5200000000 0.1086035743 0.1167654439 0.2909066975 0.0082985064 0.1714770000 960666969 0 402718720 1.0103179216 0.2193729877 0.8833637834 1240 49.5600000000 0.1084821001 0.1167587638 0.2909066975 0.0082951998 0.1711520000 960668977 0 402718720 1.0089775324 0.2215431333 0.8929120898 1241 49.6000000000 0.1088352129 0.1167523789 0.2909066975 0.0082919053 0.1856090000 960670985 0 402718720 1.0072414875 0.2236455828 0.8998028040 1242 49.6400000000 0.1083706319 0.1167456304 0.2909066975 0.0082892726 0.1779600000 960672993 0 402718720 1.0058705807 0.2239987403 0.9065568447 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 12:57:21 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 -nan 0.0891880000 955104716 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 1305031229.5644419193 0.0543010011 0.0574599225 0.0606188439 0.0575153381 0.1213510000 958783313 0 402718720 0.0013284700 0.0021752336 0.0096041132 3 1305031229.5966169834 0.0526675507 0.0558624653 0.0606188439 0.0579647856 0.1237360000 958473521 0 402718720 0.0134079093 -0.0028591044 0.0144224884 4 1305031229.6287899017 0.0486773960 0.0540661979 0.0606188439 0.0479727241 0.1353250000 958476769 0 402718720 0.0181358289 0.0010306403 0.0209806003 5 1305031229.6646571159 0.0491789617 0.0530887507 0.0606188439 0.0428248044 0.1235130000 958479729 0 402718720 0.0175253730 -0.0027237725 0.0255013797 6 1305031229.6968429089 0.0501717925 0.0526025910 0.0606188439 0.0383581214 0.1253490000 958483489 0 402718720 0.0196009818 -0.0042263656 0.0289251935 7 1305031229.7290771008 0.0478394106 0.0519221367 0.0606188439 0.0365899692 0.1269850000 958486337 0 402718720 0.0188578963 -0.0035913121 0.0342985764 8 1305031229.7648689747 0.0481392033 0.0514492700 0.0606188439 0.0339869540 0.1396570000 958489353 0 402718720 0.0209826995 -0.0045066881 0.0390034020 9 1305031229.7969229221 0.0484870560 0.0511201351 0.0606188439 0.0320859854 0.1662790000 958492257 0 402718720 0.0224368423 -0.0050595035 0.0428216048 10 1305031229.8256299496 0.0477969609 0.0507878177 0.0606188439 0.0303554424 0.1281220000 958496649 0 402718720 0.0242736358 -0.0046691340 0.0481707267 11 1305031229.8630619049 0.0489462428 0.0506204018 0.0606188439 0.0293537754 0.1281110000 958499777 0 402718720 0.0271918997 -0.0042655244 0.0526886657 12 1305031229.8969380856 0.0514053963 0.0506858180 0.0606188439 0.0295535678 0.1446860000 958502681 0 402718720 0.0292403698 -0.0042482386 0.0566195957 13 1305031229.9262549877 0.0545278452 0.0509813586 0.0606188439 0.0285069042 0.1335280000 958505529 0 402718720 0.0354145095 -0.0009442313 0.0630855188 14 1305031229.9662408829 0.0574268810 0.0514417530 0.0606188439 0.0275768616 0.1255940000 958508657 0 402718720 0.0361473560 -0.0010335783 0.0666272044 15 1305031229.9979310036 0.0596220940 0.0519871091 0.0606188439 0.0274243849 0.1261650000 958511505 0 402718720 0.0372347124 -0.0007461096 0.0704527646 16 1305031230.0300021172 0.0623174421 0.0526327549 0.0623174421 0.0266433481 0.1246450000 958514409 0 402718720 0.0380391851 -0.0008334771 0.0736957416 17 1305031230.0656960011 0.0661082938 0.0534254337 0.0661082938 0.0260515936 0.1383530000 958517425 0 402718720 0.0387159586 -0.0020515858 0.0765585452 18 1305031230.0982739925 0.0683723763 0.0542558194 0.0683723763 0.0254789620 0.1258850000 958523529 0 402718720 0.0387335606 -0.0019630718 0.0788486004 19 1305031230.1299350262 0.0697996691 0.0550739167 0.0697996691 0.0247975237 0.1248120000 958526433 0 402718720 0.0379552059 -0.0011828672 0.0806997269 20 1305031230.1657800674 0.0730104670 0.0559707442 0.0730104670 0.0243059502 0.1251860000 958529449 0 402718720 0.0373985618 -0.0016948212 0.0830458999 21 1305031230.1977820396 0.0752740055 0.0568899471 0.0752740055 0.0238611370 0.1260420000 958532353 0 402718720 0.0367177837 -0.0025651273 0.0849365816 22 1305031230.2298529148 0.0773490071 0.0578199044 0.0773490071 0.0234054419 0.1414040000 958535257 0 402718720 0.0355404131 -0.0029859419 0.0865849555 23 1305031230.2655899525 0.0797924325 0.0587752317 0.0797924325 0.0230280284 0.1295570000 958538273 0 402718720 0.0341802798 -0.0036525498 0.0885188803 24 1305031230.2979929447 0.0816814005 0.0597296554 0.0816814005 0.0225720843 0.1318540000 958541177 0 402718720 0.0327462330 -0.0035213826 0.0907625705 25 1305031230.3351120949 0.0850001648 0.0607404758 0.0850001648 0.0222203550 0.1348920000 958544249 0 402718720 0.0319447406 -0.0050287484 0.0929222479 26 1305031230.3656799793 0.0852364749 0.0616826296 0.0852364749 0.0218208532 0.1377150000 958547097 0 402718720 0.0296407621 -0.0044475943 0.0945995227 27 1305031230.3973290920 0.0855085179 0.0625650699 0.0855085179 0.0214035499 0.1521490000 958550057 0 402718720 0.0264845714 -0.0055126874 0.0962198153 28 1305031230.4368140697 0.0881865025 0.0634801211 0.0881865025 0.0220572152 0.1417680000 958553129 0 402718720 0.0242606364 -0.0068245260 0.0982412025 29 1305031230.4653120041 0.0899600536 0.0643932222 0.0899600536 0.0219108086 0.1470480000 958555921 0 402718720 0.0204983801 -0.0107391439 0.0993928909 30 1305031230.4972999096 0.0905907825 0.0652664742 0.0905907825 0.0216545408 0.1534520000 958558881 0 402718720 0.0156043777 -0.0137171149 0.0998757482 31 1305031230.5301918983 0.0913188159 0.0661068723 0.0913188159 0.0213662750 0.1598070000 958561729 0 402718720 0.0103128795 -0.0178383999 0.0999418572 32 1305031230.5661149025 0.0910457224 0.0668862114 0.0913188159 0.0224671219 0.1901360000 958564801 0 402718720 0.0037897532 -0.0194351785 0.0972089991 33 1305031230.5988430977 0.0878484398 0.0675214304 0.0913188159 0.0225074512 0.1804200000 958567705 0 402718720 -0.0025823519 -0.0180214196 0.0902533904 34 1305031230.6319139004 0.0749979094 0.0677413269 0.0913188159 0.0222906182 0.1862120000 958577065 0 402718720 -0.0222409740 -0.0171540845 0.0720386058 35 1305031230.6660470963 0.0749665871 0.0679477629 0.0913188159 0.0225606095 0.1807630000 958580025 0 402718720 -0.0267182514 -0.0151037844 0.0681249201 36 1305031230.6979451180 0.0755623281 0.0681592786 0.0913188159 0.0226304380 0.1863990000 958582873 0 402718720 -0.0270062089 -0.0096849082 0.0625571907 37 1305031230.7336409092 0.0799308643 0.0684774296 0.0913188159 0.0239732674 0.2104070000 958585833 0 402718720 -0.0267179701 0.0081263063 0.0423396751 38 1305031230.7659239769 0.0852582231 0.0689190294 0.0913188159 0.0244563509 0.2097560000 958588793 0 402718720 -0.0261545870 0.0120735979 0.0348376669 39 1305031230.7973229885 0.0885162801 0.0694215230 0.0913188159 0.0244105322 0.2391450000 958591697 0 402718720 -0.0277949777 0.0142580559 0.0277583748 40 1305031230.8317570686 0.0905171707 0.0699489142 0.0913188159 0.0242995524 0.2179240000 958594657 0 402718720 -0.0323747247 0.0150744393 0.0193661414 41 1305031230.8655419350 0.0973870829 0.0706181378 0.0973870829 0.0252460262 0.2148480000 958597561 0 402718720 -0.0477817282 0.0218243822 -0.0045603956 42 1305031230.8973939419 0.1024665982 0.0713764345 0.1024665982 0.0252266778 0.2131520000 958600521 0 402718720 -0.0503225178 0.0212216023 -0.0126009677 43 1305031230.9373099804 0.1210344881 0.0725312729 0.1210344881 0.0251869578 0.2226960000 958603593 0 402718720 -0.0623537786 0.0364600345 -0.0396458060 44 1305031230.9650349617 0.1216802225 0.0736482945 0.1216802225 0.0250810623 0.2183580000 958606385 0 402718720 -0.0624724329 0.0386519544 -0.0404164791 45 1305031230.9971239567 0.1220209450 0.0747232423 0.1220209450 0.0249124997 0.2361780000 958609345 0 402718720 -0.0640880242 0.0406039581 -0.0408535786 46 1305031231.0367500782 0.1191667318 0.0756894051 0.1220209450 0.0248397956 0.2205430000 958612417 0 402718720 -0.0675574988 0.0395892002 -0.0387437940 47 1305031231.0644741058 0.1165148392 0.0765580314 0.1220209450 0.0246521162 0.2337750000 958615153 0 402718720 -0.0692963675 0.0374811813 -0.0362471528 48 1305031231.0967879295 0.1151964515 0.0773629985 0.1220209450 0.0244648911 0.2223500000 958618113 0 402718720 -0.0694188550 0.0360419117 -0.0341280885 49 1305031231.1347110271 0.1138837934 0.0781083208 0.1220209450 0.0242257786 0.2230520000 958621129 0 402718720 -0.0694159567 0.0328579396 -0.0318192393 50 1305031231.1652760506 0.1127292886 0.0788007402 0.1220209450 0.0240622311 0.2252890000 958624033 0 402718720 -0.0692474768 0.0305193514 -0.0295844097 51 1305031231.1977710724 0.1118783876 0.0794493215 0.1220209450 0.0241156732 0.2292020000 958626993 0 402718720 -0.0659986958 0.0332252160 -0.0258144122 52 1305031231.2344679832 0.1132100299 0.0800985659 0.1220209450 0.0252595096 0.2326960000 958630009 0 402718720 -0.0617374815 0.0358581953 -0.0232019033 53 1305031231.2656350136 0.1348061562 0.0811307846 0.1348061562 0.0252738564 0.2466320000 958632857 0 402718720 -0.0580720827 0.0569631234 -0.0396046266 54 1305031231.2978610992 0.1321618259 0.0820758039 0.1348061562 0.0266524930 0.2444390000 958635817 0 402718720 -0.0578639731 0.0562341549 -0.0352535173 55 1305031231.3351519108 0.1125789732 0.0826304069 0.1348061562 0.0282799170 0.2947760000 958638833 0 402718720 -0.0497508347 0.0506640449 -0.0104331132 56 1305031231.3650770187 0.1117100492 0.0831496863 0.1348061562 0.0280325044 0.2546670000 958641681 0 402718720 -0.0443273522 0.0531362072 -0.0056383475 57 1305031231.3973300457 0.1068341359 0.0835652029 0.1348061562 0.0279491346 0.2600180000 958644641 0 402718720 -0.0399909019 0.0545487516 0.0028927736 58 1305031231.4368579388 0.1212036088 0.0842141410 0.1348061562 0.0277909361 0.2676260000 958647713 0 402718720 -0.0289456043 0.0686019808 -0.0040498171 59 1305031231.4649889469 0.1285210401 0.0849651053 0.1348061562 0.0281110612 0.2696430000 958650505 0 402718720 -0.0227603111 0.0763162151 -0.0067057642 60 1305031231.4992439747 0.1388462484 0.0858631244 0.1388462484 0.0279801739 0.2985270000 958653409 0 402718720 -0.0165852308 0.0864193961 -0.0118889399 61 1305031231.5331959724 0.1421812624 0.0867863726 0.1421812624 0.0279662648 0.2855810000 958656481 0 402718720 -0.0025669960 0.0930244401 -0.0049760621 62 1305031231.5650680065 0.1426483095 0.0876873715 0.1426483095 0.0284998701 0.2864830000 958659329 0 402718720 0.0047247261 0.0965870693 -0.0008899251 63 1305031231.6013169289 0.1427498758 0.0885613795 0.1427498758 0.0287442306 0.2724990000 958662345 0 402718720 0.0109630516 0.0987208113 0.0032135418 64 1305031231.6331589222 0.1371883303 0.0893211756 0.1427498758 0.0291222971 0.2696730000 958665305 0 402718720 0.0142377187 0.0961050913 0.0098106721 65 1305031231.6650550365 0.1302511990 0.0899508683 0.1427498758 0.0291450447 0.2814590000 958668153 0 402718720 0.0163805895 0.0926128030 0.0173861030 66 1305031231.7035079002 0.1230432615 0.0904522682 0.1427498758 0.0298439827 0.2635880000 958684081 0 402718720 0.0225003790 0.0905854031 0.0293107424 67 1305031231.7339379787 0.1218715310 0.0909212124 0.1427498758 0.0302435119 0.2518550000 958686873 0 402718720 0.0267039221 0.0925851762 0.0339856595 68 1305031231.7655088902 0.1248807609 0.0914206176 0.1427498758 0.0304422507 0.2447850000 958689777 0 402718720 0.0364984274 0.0979909971 0.0410951823 69 1305031231.8011910915 0.1311933398 0.0919970338 0.1427498758 0.0308828413 0.2323060000 958692793 0 402718720 0.0530807897 0.1009299457 0.0527174883 70 1305031231.8332920074 0.1308871657 0.0925526071 0.1427498758 0.0309498567 0.2332730000 958695697 0 402718720 0.0561195463 0.1013271511 0.0528214537 71 1305031231.8649590015 0.1298804432 0.0930783513 0.1427498758 0.0311247519 0.2014880000 958698601 0 402718720 0.0585711785 0.0997690633 0.0522634126 72 1305031231.9012699127 0.1298403740 0.0935889350 0.1427498758 0.0315087951 0.1865690000 958701617 0 402718720 0.0620100275 0.0973140448 0.0513823293 73 1305031231.9330461025 0.1266577691 0.0940419327 0.1427498758 0.0314883418 0.1764800000 958704521 0 402718720 0.0560775399 0.0954547822 0.0422006585 74 1305031231.9650299549 0.1259169281 0.0944726759 0.1427498758 0.0313990915 0.1717980000 958707425 0 402718720 0.0584113933 0.0944411606 0.0406132005 75 1305031232.0007200241 0.1235036775 0.0948597559 0.1427498758 0.0314363026 0.1771260000 958710441 0 402718720 0.0519189313 0.0942254663 0.0320521519 76 1305031232.0332028866 0.1217846721 0.0952140311 0.1427498758 0.0313162924 0.1860480000 958713401 0 402718720 0.0483092070 0.0928108245 0.0255217087 77 1305031232.0651450157 0.1213998497 0.0955541067 0.1427498758 0.0312510329 0.1566810000 958716249 0 402718720 0.0427467600 0.0935365409 0.0177558325 78 1305031232.1007990837 0.1213085726 0.0958842921 0.1427498758 0.0312124712 0.1500750000 958719265 0 402718720 0.0377331600 0.0938896760 0.0116350567 79 1305031232.1328380108 0.1210927591 0.0962033866 0.1427498758 0.0310702347 0.1412970000 958722225 0 402718720 0.0366285071 0.0927731693 0.0083394162 80 1305031232.1650519371 0.1227642521 0.0965353975 0.1427498758 0.0309290868 0.1701760000 958725073 0 402718720 0.0356275253 0.0952260196 0.0044513484 81 1305031232.1992239952 0.1240627244 0.0968752410 0.1427498758 0.0308904880 0.1459470000 958728033 0 402718720 0.0330083929 0.0964841992 -0.0002148444 82 1305031232.2364680767 0.1249276549 0.0972173436 0.1427498758 0.0307836683 0.1483650000 958731105 0 402718720 0.0340080038 0.0983811468 -0.0021677651 83 1305031232.2626979351 0.1224042252 0.0975208000 0.1427498758 0.0309425515 0.1373610000 958733841 0 402718720 0.0514735691 0.0975586697 0.0110625029 84 1305031232.2980248928 0.1227508262 0.0978211575 0.1427498758 0.0311271213 0.1343350000 958736857 0 402718720 0.0660950020 0.1000242159 0.0237593781 85 1305031232.3321430683 0.1193251088 0.0980741451 0.1427498758 0.0310996118 0.1287350000 958739817 0 402718720 0.0668026134 0.0957926512 0.0259824917 86 1305031232.3647489548 0.1139210463 0.0982584114 0.1427498758 0.0309813996 0.1359630000 958742665 0 402718720 0.0653678477 0.0904193819 0.0271675475 87 1305031232.4008779526 0.1088356897 0.0983799893 0.1427498758 0.0308927601 0.1400730000 958745737 0 402718720 0.0629875213 0.0849691853 0.0282506328 88 1305031232.4331440926 0.0956147090 0.0983485657 0.1427498758 0.0307314759 0.1518630000 958748697 0 402718720 0.0497315861 0.0722078010 0.0262666345 89 1305031232.4647209644 0.0943400562 0.0983035263 0.1427498758 0.0305720901 0.1358580000 958751489 0 402718720 0.0492960736 0.0700748116 0.0259391926 90 1305031232.5015261173 0.0923470482 0.0982373432 0.1427498758 0.0304277922 0.1477000000 958754561 0 402718720 0.0464044847 0.0676562265 0.0239958111 91 1305031232.5324640274 0.0919673666 0.0981684423 0.1427498758 0.0302763659 0.1386840000 958757465 0 402718720 0.0446558222 0.0657907575 0.0215314422 92 1305031232.5647449493 0.0913766995 0.0980946190 0.1427498758 0.0301325722 0.1407660000 958760369 0 402718720 0.0433090292 0.0651793182 0.0193138067 93 1305031232.6003499031 0.0915822610 0.0980245937 0.1427498758 0.0299816378 0.1414160000 958763329 0 402718720 0.0422872454 0.0656618476 0.0169574339 94 1305031232.6294269562 0.0909361541 0.0979491848 0.1427498758 0.0299156137 0.1431420000 958766121 0 402718720 0.0396278389 0.0656605959 0.0139682097 95 1305031232.6647078991 0.0889464617 0.0978544192 0.1427498758 0.0297886501 0.1601390000 958769193 0 402718720 0.0336183049 0.0641638264 0.0100907451 96 1305031232.7005090714 0.0877751037 0.0977494264 0.1427498758 0.0296655901 0.1469100000 958772153 0 402718720 0.0275641475 0.0617102385 0.0062068966 97 1305031232.7327980995 0.0867393836 0.0976359208 0.1427498758 0.0296018425 0.1478580000 958775057 0 402718720 0.0226121414 0.0598979555 0.0026437012 98 1305031232.7684600353 0.0849331766 0.0975063009 0.1427498758 0.0295263179 0.1477140000 958778073 0 402718720 0.0162394829 0.0570248179 -0.0009536916 99 1305031232.8045380116 0.0828465447 0.0973582226 0.1427498758 0.0294267865 0.1499150000 958781089 0 402718720 0.0068463017 0.0520796664 -0.0052270200 100 1305031232.8346450329 0.0831279382 0.0972159198 0.1427498758 0.0293533414 0.1572890000 958783937 0 402718720 0.0011027029 0.0511179268 -0.0089224568 101 1305031232.8685569763 0.0833058581 0.0970781964 0.1427498758 0.0292697964 0.1459370000 958786953 0 402718720 -0.0045071482 0.0498339869 -0.0121238977 102 1305031232.9041829109 0.0827223212 0.0969374525 0.1427498758 0.0291715477 0.1459260000 958789913 0 402718720 -0.0108558582 0.0481705107 -0.0148465177 103 1305031232.9330000877 0.0834713131 0.0968067133 0.1427498758 0.0290760475 0.1460340000 958792705 0 402718720 -0.0150832636 0.0478252433 -0.0167289972 104 1305031232.9683640003 0.0829338580 0.0966733204 0.1427498758 0.0289363996 0.1461560000 958795777 0 402718720 -0.0165273026 0.0469271801 -0.0183148701 105 1305031233.0011510849 0.0824497864 0.0965378582 0.1427498758 0.0288569855 0.1604340000 958798681 0 402718720 -0.0166557841 0.0476474129 -0.0184926633 106 1305031233.0330219269 0.0808123425 0.0963895043 0.1427498758 0.0290248034 0.1515100000 958801585 0 402718720 -0.0201245453 0.0487303846 -0.0168756638 107 1305031233.0688428879 0.0796679854 0.0962332284 0.1427498758 0.0292311806 0.1532280000 958804489 0 402718720 -0.0201833826 0.0501710400 -0.0155455209 108 1305031233.1004469395 0.0793218464 0.0960766415 0.1427498758 0.0291159380 0.1641960000 958807337 0 402718720 -0.0128182713 0.0622049309 -0.0107818218 109 1305031233.1328918934 0.0764349997 0.0958964430 0.1427498758 0.0294381002 0.1538420000 958810241 0 402718720 -0.0137808667 0.0560509488 -0.0091344770 110 1305031233.1684799194 0.0739559308 0.0956969838 0.1427498758 0.0294884330 0.1937010000 958813257 0 402718720 -0.0060685384 0.0457106270 -0.0056962459 111 1305031233.2006340027 0.0726939514 0.0954897493 0.1427498758 0.0294036783 0.1597760000 958816161 0 402718720 -0.0120015405 0.0401694812 -0.0034420062 112 1305031233.2330091000 0.0711366534 0.0952723109 0.1427498758 0.0294049882 0.1652420000 958819065 0 402718720 -0.0181836076 0.0354742594 0.0001567915 113 1305031233.2684679031 0.0724384859 0.0950702417 0.1427498758 0.0300160606 0.1644200000 958822081 0 402718720 -0.0275452845 0.0324271433 0.0031165420 114 1305031233.3003950119 0.0686524659 0.0948385068 0.1427498758 0.0301460408 0.1673390000 958824985 0 402718720 -0.0288253743 0.0357455090 0.0100143496 115 1305031233.3325300217 0.0631879047 0.0945632842 0.1427498758 0.0300749754 0.1789080000 958827889 0 402718720 -0.0299183931 0.0265711565 0.0218451470 116 1305031233.3686299324 0.0649997145 0.0943084258 0.1427498758 0.0300478068 0.1564860000 958830793 0 402718720 -0.0177245345 0.0251228772 0.0294555947 117 1305031233.4008929729 0.0663773865 0.0940696990 0.1427498758 0.0299959553 0.1515720000 958833753 0 402718720 -0.0141032804 0.0240293015 0.0358284377 118 1305031233.4330079556 0.0697407052 0.0938635211 0.1427498758 0.0300791442 0.1633180000 958836713 0 402718720 -0.0260955915 0.0066078440 0.0401772372 119 1305031233.4687869549 0.0731861219 0.0936897614 0.1427498758 0.0301434586 0.1716130000 958839617 0 402718720 -0.0298670158 0.0015354455 0.0418621488 120 1305031233.5007359982 0.0739426911 0.0935252025 0.1427498758 0.0300637419 0.1765300000 958842577 0 402718720 -0.0316024683 -0.0005751302 0.0446977429 121 1305031233.5341610909 0.0762440488 0.0933823830 0.1427498758 0.0300620131 0.1692560000 958845537 0 402718720 -0.0339031816 -0.0034460344 0.0463313684 122 1305031233.5697269440 0.0768913329 0.0932472105 0.1427498758 0.0299628554 0.1418610000 958848497 0 402718720 -0.0360353142 -0.0053673279 0.0489683859 123 1305031233.6012749672 0.0781136826 0.0931241737 0.1427498758 0.0298958314 0.1608630000 958851401 0 402718720 -0.0378899537 -0.0071254768 0.0504260659 124 1305031233.6330409050 0.0781632587 0.0930035211 0.1427498758 0.0298502523 0.1444630000 958854305 0 402718720 -0.0400472768 -0.0078801932 0.0516031049 125 1305031233.6717829704 0.0744677857 0.0928552352 0.1427498758 0.0297858371 0.1611520000 958857433 0 402718720 -0.0256073996 -0.0037867907 0.0664834604 126 1305031233.7022960186 0.0731863752 0.0926991332 0.1427498758 0.0298363691 0.1570980000 958860337 0 402718720 -0.0232577641 -0.0017575100 0.0705228522 127 1305031233.7312009335 0.0702012777 0.0925219847 0.1427498758 0.0299353538 0.1554040000 958863129 0 402718720 -0.0227028206 0.0017472262 0.0725966319 128 1305031233.7691600323 0.0683383644 0.0923330502 0.1427498758 0.0299854690 0.1552610000 958866145 0 402718720 -0.0202470850 0.0043057855 0.0751029924 129 1305031233.7997679710 0.0686340407 0.0921493369 0.1427498758 0.0298825885 0.1551330000 958868993 0 402718720 -0.0182888713 0.0042886268 0.0758481547 130 1305031233.8338310719 0.0702709854 0.0919810419 0.1427498758 0.0298288118 0.1577420000 958897553 0 402718720 -0.0173625126 0.0009578132 0.0750506967 131 1305031233.8655700684 0.0713304281 0.0918234036 0.1427498758 0.0297601694 0.1482350000 958900457 0 402718720 -0.0177759640 -0.0010276504 0.0741179958 132 1305031233.8986968994 0.0706227794 0.0916627929 0.1427498758 0.0296478090 0.1506910000 958903473 0 402718720 -0.0180576611 -0.0013295042 0.0744099468 133 1305031233.9320030212 0.0701813176 0.0915012780 0.1427498758 0.0295697320 0.1488760000 958906377 0 402718720 -0.0173252784 -0.0017099647 0.0750114769 134 1305031233.9681589603 0.0688018128 0.0913318790 0.1427498758 0.0294743898 0.1491330000 958909393 0 402718720 -0.0162891001 -0.0008521973 0.0750409365 135 1305031233.9989380836 0.0687251911 0.0911644221 0.1427498758 0.0293925986 0.1469160000 958912297 0 402718720 -0.0141259059 -0.0008832029 0.0751086771 136 1305031234.0370678902 0.0659758374 0.0909792119 0.1427498758 0.0292938114 0.1530310000 958915369 0 402718720 -0.0105534382 0.0038717436 0.0756103918 137 1305031234.0687561035 0.0648956522 0.0907888209 0.1427498758 0.0291904526 0.1468650000 958918217 0 402718720 -0.0092501463 0.0049017370 0.0754716098 138 1305031234.0997409821 0.0633580089 0.0905900469 0.1427498758 0.0290949240 0.1490350000 958921121 0 402718720 -0.0081493631 0.0079488792 0.0740038007 139 1305031234.1350688934 0.0628203973 0.0903902653 0.1427498758 0.0290065209 0.1446950000 958924081 0 402718720 -0.0078162011 0.0089003844 0.0725510567 140 1305031234.1659009457 0.0581064932 0.0901596669 0.1427498758 0.0289781536 0.1694450000 958926985 0 402718720 -0.0078498609 0.0158020947 0.0726651996 141 1305031234.2010040283 0.0584530048 0.0899347970 0.1427498758 0.0289360285 0.1464580000 958929945 0 402718720 -0.0074282181 0.0151261473 0.0722310618 142 1305031234.2385749817 0.0574033223 0.0897057021 0.1427498758 0.0288334424 0.1499810000 958933073 0 402718720 -0.0082428809 0.0160137415 0.0715466142 143 1305031234.2655100822 0.0524133258 0.0894449162 0.1427498758 0.0287627602 0.1568630000 958935753 0 402718720 -0.0080312230 0.0243252348 0.0732970461 144 1305031234.3024549484 0.0523581691 0.0891873694 0.1427498758 0.0286627796 0.1533220000 958938881 0 402718720 -0.0079841614 0.0239386316 0.0731972754 145 1305031234.3384580612 0.0523870699 0.0889335742 0.1427498758 0.0285955330 0.1775240000 958941897 0 402718720 -0.0086294683 0.0242145974 0.0723281205 146 1305031234.3661808968 0.0476074889 0.0886505188 0.1427498758 0.0285491119 0.1687240000 958944633 0 402718720 -0.0102249701 0.0308944844 0.0734678209 147 1305031234.4000349045 0.0479178876 0.0883734261 0.1427498758 0.0284557147 0.1634710000 958947593 0 402718720 -0.0105975727 0.0305474121 0.0728585273 148 1305031234.4367709160 0.0483561978 0.0881030394 0.1427498758 0.0284335421 0.1658190000 958950665 0 402718720 -0.0096833361 0.0301281270 0.0718123540 149 1305031234.4676060677 0.0483327284 0.0878361246 0.1427498758 0.0283407610 0.1679350000 958953513 0 402718720 -0.0089472551 0.0314467885 0.0707605407 150 1305031234.4977810383 0.0479315929 0.0875700944 0.1427498758 0.0282479967 0.1703200000 958956361 0 402718720 -0.0081167659 0.0335456207 0.0703342333 151 1305031234.5376710892 0.0494790599 0.0873178359 0.1427498758 0.0283166013 0.1704690000 958959489 0 402718720 -0.0063974420 0.0327000245 0.0673409849 152 1305031234.5690369606 0.0497854091 0.0870709120 0.1427498758 0.0282922143 0.1698750000 958962337 0 402718720 -0.0060737785 0.0347738974 0.0652807653 153 1305031234.5982480049 0.0497042388 0.0868266854 0.1427498758 0.0282038528 0.1707090000 958965241 0 402718720 -0.0054446426 0.0360539891 0.0640852749 154 1305031234.6336491108 0.0511467755 0.0865949977 0.1427498758 0.0281183258 0.1754110000 958968145 0 402718720 0.0016094131 0.0414146855 0.0678217113 155 1305031234.6658589840 0.0531051978 0.0863789344 0.1427498758 0.0280780893 0.1782920000 958971105 0 402718720 0.0032362801 0.0396668725 0.0656653196 156 1305031234.6987318993 0.0631237105 0.0862298625 0.1427498758 0.0280171795 0.1729570000 958974065 0 402718720 0.0193430074 0.0491398349 0.0794266909 157 1305031234.7344369888 0.0772521496 0.0861726796 0.1427498758 0.0279766272 0.1837820000 958976969 0 402718720 0.0331225134 0.0571251437 0.0938588455 158 1305031234.7689719200 0.0899994448 0.0861968996 0.1427498758 0.0279364163 0.1643840000 958979985 0 402718720 0.0447643958 0.0589332096 0.1012760401 159 1305031234.8015530109 0.0948833227 0.0862515312 0.1427498758 0.0279459653 0.1647300000 958982945 0 402718720 0.0460424796 0.0667550713 0.1063322350 160 1305031234.8378078938 0.0988545269 0.0863302999 0.1427498758 0.0278742867 0.1649060000 958986017 0 402718720 0.0504842922 0.0629477277 0.1057052985 161 1305031234.8693211079 0.1001569927 0.0864161800 0.1427498758 0.0278053259 0.1548410000 958988809 0 402718720 0.0515290387 0.0621033013 0.1046703830 162 1305031234.9019980431 0.1006594524 0.0865041015 0.1427498758 0.0277212668 0.1557850000 958991769 0 402718720 0.0508977585 0.0636733323 0.1057713255 163 1305031234.9381608963 0.0926181227 0.0865416108 0.1427498758 0.0278124077 0.1656520000 958994785 0 402718720 0.0347966403 0.0799585506 0.1097922996 164 1305031234.9730799198 0.0922900289 0.0865766621 0.1427498758 0.0277312351 0.1655870000 958997801 0 402718720 0.0350537710 0.0784825608 0.1136370972 165 1305031235.0050830841 0.0875560120 0.0865825976 0.1427498758 0.0277478810 0.1664540000 959000649 0 402718720 0.0300456937 0.0792286471 0.1174570993 166 1305031235.0399720669 0.0833547115 0.0865631525 0.1427498758 0.0276704073 0.1883990000 959003665 0 402718720 0.0283991806 0.0755855292 0.1182733551 167 1305031235.0729401112 0.0751530528 0.0864948285 0.1427498758 0.0276133138 0.1985940000 959006569 0 402718720 0.0212704893 0.0742590800 0.1184049621 168 1305031235.0995910168 0.0689515397 0.0863904042 0.1427498758 0.0275498754 0.1736620000 959009361 0 402718720 0.0172867514 0.0722185522 0.1183660105 169 1305031235.1362709999 0.0613838509 0.0862424364 0.1427498758 0.0275088005 0.1878790000 959012377 0 402718720 0.0139722601 0.0661709905 0.1153706387 170 1305031235.1663711071 0.0537943654 0.0860515654 0.1427498758 0.0274791128 0.1872690000 959015225 0 402718720 0.0079955477 0.0641039163 0.1139662862 171 1305031235.1998469830 0.0394191816 0.0857788614 0.1427498758 0.0274829280 0.1873310000 959018073 0 402718720 -0.0091225589 0.0644134358 0.1057497859 172 1305031235.2375700474 0.0327226259 0.0854703949 0.1427498758 0.0274751586 0.1995230000 959021145 0 402718720 -0.0169508848 0.0620025173 0.1024945900 173 1305031235.2690389156 0.0289495364 0.0851436848 0.1427498758 0.0274379719 0.1874970000 959024049 0 402718720 -0.0262433663 0.0590026192 0.0987358540 174 1305031235.3064870834 0.0295817461 0.0848243633 0.1427498758 0.0274459215 0.1998050000 959027121 0 402718720 -0.0327694826 0.0575232469 0.0968425125 175 1305031235.3380000591 0.0308216028 0.0845157761 0.1427498758 0.0273825219 0.2047130000 959029969 0 402718720 -0.0393154509 0.0555961207 0.0969927683 176 1305031235.3698880672 0.0346891060 0.0842326700 0.1427498758 0.0273405694 0.1939820000 959032873 0 402718720 -0.0439089350 0.0515232161 0.0960258469 177 1305031235.4060161114 0.0381860808 0.0839725198 0.1427498758 0.0273954690 0.2012330000 959035889 0 402718720 -0.0464165621 0.0505980924 0.0973766446 178 1305031235.4381530285 0.0392314978 0.0837211657 0.1427498758 0.0273560881 0.1928960000 959038793 0 402718720 -0.0521239527 0.0513864011 0.1010700092 179 1305031235.4700589180 0.0388260558 0.0834703550 0.1427498758 0.0272900583 0.1905570000 959041697 0 402718720 -0.0491148494 0.0482653268 0.1044862419 180 1305031235.5059850216 0.0427948162 0.0832443798 0.1427498758 0.0272395104 0.1940330000 959044713 0 402718720 -0.0502668843 0.0476005599 0.1059554592 181 1305031235.5385539532 0.0452720933 0.0830345882 0.1427498758 0.0271740898 0.1760830000 959047617 0 402718720 -0.0508736148 0.0468051471 0.1072385237 182 1305031235.5703649521 0.0459257215 0.0828306933 0.1427498758 0.0271047645 0.1804700000 959050521 0 402718720 -0.0472858585 0.0455443934 0.1099126935 183 1305031235.6060059071 0.0353032351 0.0825709804 0.1427498758 0.0271166591 0.1735390000 959053593 0 402718720 -0.0334795564 0.0500543676 0.1234444901 184 1305031235.6389510632 0.0393067002 0.0823358485 0.1427498758 0.0270608422 0.1559160000 959056497 0 402718720 -0.0338832512 0.0481621884 0.1255892366 185 1305031235.6705160141 0.0450812578 0.0821344723 0.1427498758 0.0270028758 0.1637810000 959059345 0 402718720 -0.0361067951 0.0444585606 0.1285155416 186 1305031235.7057778835 0.0548747629 0.0819879147 0.1427498758 0.0269349329 0.1513020000 959062361 0 402718720 -0.0392331220 0.0391458757 0.1301954091 187 1305031235.7387969494 0.0650197417 0.0818971758 0.1427498758 0.0269103941 0.1463840000 959065321 0 402718720 -0.0419381224 0.0318291821 0.1337203681 188 1305031235.7696299553 0.0720495582 0.0818447949 0.1427498758 0.0268588405 0.1423020000 959068169 0 402718720 -0.0463989638 0.0292011146 0.1353355497 189 1305031235.8072249889 0.0780583322 0.0818247607 0.1427498758 0.0268007547 0.1312550000 959071353 0 402718720 -0.0505687855 0.0299183596 0.1345548928 190 1305031235.8388121128 0.0840345696 0.0818363913 0.1427498758 0.0267731232 0.1410540000 959074257 0 402718720 -0.0545278788 0.0284235179 0.1361878961 191 1305031235.8700668812 0.0893412307 0.0818756836 0.1427498758 0.0267457747 0.1257890000 959077217 0 402718720 -0.0577822402 0.0273914430 0.1381631196 192 1305031235.9061110020 0.0942699015 0.0819402368 0.1427498758 0.0266807365 0.1238700000 959080289 0 402718720 -0.0594087318 0.0272785313 0.1401204616 193 1305031235.9382328987 0.0990452245 0.0820288637 0.1427498758 0.0266297705 0.1241990000 959083305 0 402718720 -0.0611395761 0.0260520559 0.1421134621 194 1305031235.9700109959 0.1024003848 0.0821338716 0.1427498758 0.0265744651 0.1234970000 959086209 0 402718720 -0.0628915131 0.0261292700 0.1445860863 195 1305031236.0068531036 0.1076941937 0.0822649501 0.1427498758 0.0265169704 0.1343500000 959089337 0 402718720 -0.0645621344 0.0250149574 0.1476545781 196 1305031236.0380480289 0.1115494445 0.0824143608 0.1427498758 0.0264551537 0.1354410000 959092241 0 402718720 -0.0661875233 0.0247631893 0.1504365951 197 1305031236.0698781013 0.1150058061 0.0825797996 0.1427498758 0.0264424424 0.1206690000 959095201 0 402718720 -0.0677347630 0.0244585034 0.1535810977 198 1305031236.1058719158 0.1196324006 0.0827669340 0.1427498758 0.0263867938 0.1200830000 959098273 0 402718720 -0.0689256713 0.0231158137 0.1569356173 199 1305031236.1383249760 0.1226887703 0.0829675462 0.1427498758 0.0263238543 0.1321150000 959101289 0 402718720 -0.0699813440 0.0223843139 0.1597522795 200 1305031236.1709330082 0.1251810491 0.0831786137 0.1427498758 0.0262591390 0.1311480000 959104249 0 402718720 -0.0706621036 0.0222072843 0.1616673917 201 1305031236.2071900368 0.1265173405 0.0833942293 0.1427498758 0.0262030373 0.1209770000 959107377 0 402718720 -0.0710097477 0.0230193622 0.1633454561 202 1305031236.2383749485 0.1284460127 0.0836172579 0.1427498758 0.0261676787 0.1207910000 959110337 0 402718720 -0.0720640123 0.0216536950 0.1656577438 203 1305031236.2699589729 0.1309648305 0.0838504972 0.1427498758 0.0261044865 0.1220840000 959113241 0 402718720 -0.0728480220 0.0188993700 0.1670402288 204 1305031236.3069939613 0.1316927224 0.0840850179 0.1427498758 0.0260984248 0.1224870000 959116369 0 402718720 -0.0724136755 0.0159942601 0.1678455323 205 1305031236.3392169476 0.1332172751 0.0843246875 0.1427498758 0.0260489350 0.1568590000 959119329 0 402718720 -0.0715876743 0.0120356707 0.1682071388 206 1305031236.3700959682 0.1332719773 0.0845622957 0.1427498758 0.0260018891 0.1222190000 959122233 0 402718720 -0.0702918395 0.0088623120 0.1663154960 207 1305031236.4058690071 0.1310498863 0.0847868734 0.1427498758 0.0259800531 0.1221760000 959125305 0 402718720 -0.0683346242 0.0062824879 0.1640460491 208 1305031236.4387879372 0.1281622201 0.0849954087 0.1427498758 0.0259179459 0.1355140000 959128265 0 402718720 -0.0654349178 0.0043732254 0.1614650786 209 1305031236.4751410484 0.1234562695 0.0851794320 0.1427498758 0.0258560972 0.1243710000 959131393 0 402718720 -0.0612425916 0.0032176466 0.1583156586 210 1305031236.5077209473 0.1179540828 0.0853355017 0.1427498758 0.0257999482 0.1376930000 959134409 0 402718720 -0.0565347634 0.0032415916 0.1545895338 211 1305031236.5386450291 0.1145634428 0.0854740228 0.1427498758 0.0257593690 0.1368400000 959137313 0 402718720 -0.0525124259 0.0013727030 0.1511926949 212 1305031236.5740950108 0.1091214940 0.0855855675 0.1427498758 0.0256989894 0.1246370000 959140385 0 402718720 -0.0493764840 0.0002463200 0.1467407048 213 1305031236.6057569981 0.1072345823 0.0856872060 0.1427498758 0.0256423446 0.1253680000 959143289 0 402718720 -0.0466896035 -0.0030074231 0.1423273534 214 1305031236.6384010315 0.1048498973 0.0857767513 0.1427498758 0.0256122678 0.1255240000 959146249 0 402718720 -0.0435823239 -0.0052816560 0.1369974613 215 1305031236.6751470566 0.0992915779 0.0858396110 0.1427498758 0.0255715808 0.1425230000 959149265 0 402718720 -0.0409679823 -0.0057240068 0.1312601417 216 1305031236.7033619881 0.0954618156 0.0858841582 0.1427498758 0.0255193936 0.1290150000 959152057 0 402718720 -0.0381745696 -0.0061306511 0.1253843904 217 1305031236.7339220047 0.0862513110 0.0858858502 0.1427498758 0.0255090898 0.1381370000 959154905 0 402718720 -0.0361874439 0.0000222031 0.1155470386 218 1305031236.7740409374 0.0820269957 0.0858681490 0.1427498758 0.0254858846 0.1323790000 959158033 0 402718720 -0.0337640122 -0.0009683007 0.1098869666 219 1305031236.8025879860 0.0774681419 0.0858297928 0.1427498758 0.0255844224 0.1395800000 959160937 0 402718720 -0.0300400164 0.0023211211 0.1028939039 220 1305031236.8364150524 0.0705871657 0.0857605081 0.1427498758 0.0255288546 0.1397860000 959163841 0 402718720 -0.0262915120 0.0054693231 0.0969021991 221 1305031236.8743979931 0.0659945458 0.0856710694 0.1427498758 0.0254848909 0.1391190000 959166913 0 402718720 -0.0240793321 0.0063856039 0.0899242088 222 1305031236.9060690403 0.0632726178 0.0855701755 0.1427498758 0.0254837317 0.1447380000 959169817 0 402718720 -0.0216356255 0.0079086665 0.0826227143 223 1305031236.9344370365 0.0627701506 0.0854679332 0.1427498758 0.0254420493 0.1486420000 959172609 0 402718720 -0.0207649544 0.0075256159 0.0749633983 224 1305031236.9744000435 0.0608334765 0.0853579579 0.1427498758 0.0253981739 0.1618190000 959175681 0 402718720 -0.0202791132 0.0061362823 0.0682802275 225 1305031237.0074260235 0.0604898445 0.0852474330 0.1427498758 0.0253444175 0.1692450000 959178697 0 402718720 -0.0229344647 0.0049554124 0.0587488040 226 1305031237.0370240211 0.0588654950 0.0851306988 0.1427498758 0.0253214203 0.1639740000 959181545 0 402718720 -0.0206621904 0.0061063832 0.0542431511 227 1305031237.0734269619 0.0578759126 0.0850106336 0.1427498758 0.0252694244 0.1683540000 959184505 0 402718720 -0.0170934796 0.0060580615 0.0494576246 228 1305031237.1059679985 0.0596661121 0.0848994734 0.1427498758 0.0252227657 0.1705380000 959187465 0 402718720 -0.0134071698 0.0056156558 0.0441972502 229 1305031237.1378319263 0.0617097542 0.0847982083 0.1427498758 0.0251750740 0.1772570000 959190369 0 402718720 -0.0068746428 0.0080213416 0.0399623103 230 1305031237.1712269783 0.0600404441 0.0846905658 0.1427498758 0.0252103768 0.1941690000 959193329 0 402718720 -0.0033256905 0.0158251021 0.0378030725 231 1305031237.2042291164 0.0619542524 0.0845921402 0.1427498758 0.0252195744 0.1767510000 959196177 0 402718720 -0.0001054703 0.0146143474 0.0321805179 232 1305031237.2375690937 0.0647462308 0.0845065975 0.1427498758 0.0252173688 0.1774760000 959199193 0 402718720 0.0047872830 0.0204805601 0.0300434940 233 1305031237.2746589184 0.0687419474 0.0844389381 0.1427498758 0.0251744234 0.1878290000 959202209 0 402718720 0.0112130484 0.0229337532 0.0290279612 234 1305031237.3058099747 0.0738134012 0.0843935298 0.1427498758 0.0251320264 0.1726280000 959205113 0 402718720 0.0170570128 0.0271766614 0.0279557966 235 1305031237.3371419907 0.0823338032 0.0843847650 0.1427498758 0.0251264681 0.1743250000 959208017 0 402718720 0.0261934698 0.0308505110 0.0305855833 236 1305031237.3741660118 0.0925632119 0.0844194194 0.1427498758 0.0250881899 0.1745180000 959210977 0 402718720 0.0362717770 0.0369995497 0.0354780070 237 1305031237.4057340622 0.0959844366 0.0844682170 0.1427498758 0.0250892482 0.1666410000 959213937 0 402718720 0.0396097787 0.0381006636 0.0338414460 238 1305031237.4377219677 0.1014332920 0.0845394988 0.1427498758 0.0250828280 0.1809910000 959216841 0 402718720 0.0443353429 0.0394298099 0.0327520370 239 1305031237.4741280079 0.1061580107 0.0846299528 0.1427498758 0.0250529435 0.1619600000 959219801 0 402718720 0.0486470945 0.0414308533 0.0326984599 240 1305031237.5060451031 0.1102325693 0.0847366304 0.1427498758 0.0250284984 0.1753210000 959222761 0 402718720 0.0524801798 0.0433204770 0.0337357856 241 1305031237.5376501083 0.1141253859 0.0848585754 0.1427498758 0.0249783796 0.1605850000 959225665 0 402718720 0.0562275499 0.0450219922 0.0333129279 242 1305031237.5739479065 0.1176748797 0.0849941800 0.1427498758 0.0249444391 0.1620190000 959228625 0 402718720 0.0592631735 0.0459519625 0.0334961005 243 1305031237.6068129539 0.1190119088 0.0851341707 0.1427498758 0.0249031184 0.1602980000 959231641 0 402718720 0.0602755249 0.0482796244 0.0339708664 244 1305031237.6378550529 0.1194913685 0.0852749789 0.1427498758 0.0248610654 0.1613100000 959234489 0 402718720 0.0598507002 0.0511057898 0.0337945856 245 1305031237.6752760410 0.1204930693 0.0854187262 0.1427498758 0.0248238195 0.1783150000 959237505 0 402718720 0.0598244965 0.0532574654 0.0344466902 246 1305031237.7071180344 0.1196982339 0.0855580738 0.1427498758 0.0247763698 0.1612420000 959240465 0 402718720 0.0580947995 0.0555896387 0.0344317108 247 1305031237.7416670322 0.1167280525 0.0856842680 0.1427498758 0.0247435276 0.1628540000 959243425 0 402718720 0.0539218597 0.0580547340 0.0346796736 248 1305031237.7743060589 0.1182809249 0.0858157061 0.1427498758 0.0247668590 0.1642870000 959246273 0 402718720 0.0556764156 0.0575886220 0.0351203568 249 1305031237.8064959049 0.1177985296 0.0859441512 0.1427498758 0.0247289418 0.1752300000 959249233 0 402718720 0.0567055680 0.0549288094 0.0340434276 250 1305031237.8430309296 0.1087607294 0.0860354175 0.1427498758 0.0247424571 0.1814430000 959252305 0 402718720 0.0415080152 0.0644554421 0.0320349522 251 1305031237.8754220009 0.1120411530 0.0861390260 0.1427498758 0.0249274506 0.1650510000 959255153 0 402718720 0.0483897328 0.0596463159 0.0318651982 252 1305031237.9077839851 0.1113788337 0.0862391840 0.1427498758 0.0249084325 0.1765570000 959258113 0 402718720 0.0501124971 0.0550409518 0.0311261564 253 1305031237.9441869259 0.1092180833 0.0863300097 0.1427498758 0.0249873531 0.1656060000 959261129 0 402718720 0.0467941388 0.0573555753 0.0327215903 254 1305031237.9738099575 0.1095806956 0.0864215478 0.1427498758 0.0249442418 0.1680030000 959263865 0 402718720 0.0458352529 0.0592020489 0.0351390876 255 1305031238.0069320202 0.1071504354 0.0865028376 0.1427498758 0.0249036072 0.1849910000 959266881 0 402718720 0.0433101431 0.0582921058 0.0381207019 256 1305031238.0431399345 0.1042778492 0.0865722712 0.1427498758 0.0250870225 0.1756990000 959269897 0 402718720 0.0416756421 0.0557382964 0.0397953726 257 1305031238.0740320683 0.0994746312 0.0866224749 0.1427498758 0.0251038598 0.1907460000 959272745 0 402718720 0.0364684761 0.0554602072 0.0421102718 258 1305031238.1065878868 0.0841000229 0.0866126980 0.1427498758 0.0250893268 0.1852860000 959326849 0 402718720 0.0205127057 0.0527848229 0.0350901932 259 1305031238.1433279514 0.0770353824 0.0865757199 0.1427498758 0.0251141583 0.1846250000 959329865 0 402718720 0.0131020313 0.0491009690 0.0325854458 260 1305031238.1723001003 0.0620248280 0.0864812934 0.1427498758 0.0250832312 0.1903810000 959332769 0 402718720 -0.0081956359 0.0506093800 0.0280510485 261 1305031238.2054259777 0.0551302321 0.0863611744 0.1427498758 0.0250437330 0.1930040000 959335617 0 402718720 -0.0142072523 0.0391679853 0.0249011200 262 1305031238.2401471138 0.0510578379 0.0862264289 0.1427498758 0.0250195825 0.1976960000 959338633 0 402718720 -0.0183057487 0.0323885456 0.0260516573 263 1305031238.2725269794 0.0477111451 0.0860799829 0.1427498758 0.0249746241 0.1968370000 959341593 0 402718720 -0.0223573539 0.0288026929 0.0291552972 264 1305031238.3060529232 0.0435082428 0.0859187263 0.1427498758 0.0251465792 0.2108560000 959344497 0 402718720 -0.0288373716 0.0306226611 0.0338010788 265 1305031238.3425960541 0.0425003320 0.0857548833 0.1427498758 0.0251335298 0.2134220000 959347513 0 402718720 -0.0309300963 0.0261900555 0.0373067707 266 1305031238.3741040230 0.0454561263 0.0856033843 0.1427498758 0.0251559300 0.1909770000 959350417 0 402718720 -0.0294715334 0.0235216264 0.0410335325 267 1305031238.4060359001 0.0477816723 0.0854617299 0.1427498758 0.0251105737 0.2068640000 959353321 0 402718720 -0.0279373340 0.0218530670 0.0443166718 268 1305031238.4434239864 0.0528052971 0.0853398775 0.1427498758 0.0250649127 0.1736820000 959356337 0 402718720 -0.0232187174 0.0210675541 0.0475018546 269 1305031238.4740819931 0.0549012460 0.0852267228 0.1427498758 0.0250212576 0.1673570000 959359241 0 402718720 -0.0204843879 0.0206874274 0.0519373566 270 1305031238.5058109760 0.0572006851 0.0851229226 0.1427498758 0.0250331410 0.1750840000 959362145 0 402718720 -0.0195590071 0.0175668411 0.0557856709 271 1305031238.5432639122 0.0621209145 0.0850380444 0.1427498758 0.0249886613 0.1546550000 959365217 0 402718720 -0.0198589638 0.0122800553 0.0580086224 272 1305031238.5741839409 0.0635119677 0.0849589044 0.1427498758 0.0249467081 0.1505530000 959368009 0 402718720 -0.0212554764 0.0103749726 0.0612575673 273 1305031238.6058249474 0.0660992712 0.0848898215 0.1427498758 0.0249060078 0.1488940000 959370969 0 402718720 -0.0224426780 0.0080091609 0.0637780949 274 1305031238.6427590847 0.0684579164 0.0848298510 0.1427498758 0.0248685044 0.1473790000 959374041 0 402718720 -0.0241841637 0.0058327615 0.0665888786 275 1305031238.6738131046 0.0726604387 0.0847855986 0.1427498758 0.0248248284 0.1603390000 959376833 0 402718720 -0.0274053272 0.0034496507 0.0673178360 276 1305031238.7051889896 0.0751507804 0.0847506899 0.1427498758 0.0247823051 0.1414010000 959379737 0 402718720 -0.0308467019 0.0020104740 0.0685170889 277 1305031238.7413070202 0.0771599635 0.0847232865 0.1427498758 0.0247638291 0.1397270000 959382809 0 402718720 -0.0337688439 0.0012142163 0.0696267262 278 1305031238.7717959881 0.0796258673 0.0847049505 0.1427498758 0.0247391235 0.1362740000 959385713 0 402718720 -0.0369859673 -0.0000131415 0.0702938214 279 1305031238.8070189953 0.0821493492 0.0846957906 0.1427498758 0.0247176803 0.1349570000 959388729 0 402718720 -0.0396612883 0.0003198759 0.0712803453 280 1305031238.8429400921 0.0830864236 0.0846900429 0.1427498758 0.0246770121 0.1323140000 959391801 0 402718720 -0.0418184586 0.0006140209 0.0729042441 281 1305031238.8737230301 0.0870267004 0.0846983584 0.1427498758 0.0246772407 0.1317220000 959394761 0 402718720 -0.0423414558 -0.0015577412 0.0740224347 282 1305031238.9061720371 0.0900750756 0.0847174248 0.1427498758 0.0246510283 0.1321760000 959397665 0 402718720 -0.0428260602 -0.0037368406 0.0754885599 283 1305031238.9427859783 0.0922022387 0.0847438729 0.1427498758 0.0246076903 0.1322750000 959400793 0 402718720 -0.0432835519 -0.0046240669 0.0772940814 284 1305031238.9723079205 0.0943432450 0.0847776735 0.1427498758 0.0245772082 0.1309850000 959403697 0 402718720 -0.0437369756 -0.0059614456 0.0784690008 285 1305031239.0104830265 0.0967748463 0.0848197688 0.1427498758 0.0245691175 0.1450670000 959406825 0 402718720 -0.0443940051 -0.0067213187 0.0796727836 286 1305031239.0408790112 0.0982936770 0.0848668804 0.1427498758 0.0245296349 0.1301690000 959409729 0 402718720 -0.0448980667 -0.0072729900 0.0809821114 287 1305031239.0746610165 0.1009825617 0.0849230326 0.1427498758 0.0245393803 0.1301830000 959412745 0 402718720 -0.0453814045 -0.0093090963 0.0817184150 288 1305031239.1109058857 0.1035336107 0.0849876526 0.1427498758 0.0244968260 0.1296010000 959415873 0 402718720 -0.0459112339 -0.0117998952 0.0825565532 289 1305031239.1417789459 0.1051237583 0.0850573277 0.1427498758 0.0244656833 0.1297800000 959418777 0 402718720 -0.0466391258 -0.0141049773 0.0829864219 290 1305031239.1757500172 0.1074638814 0.0851345917 0.1427498758 0.0244448119 0.1430670000 959421793 0 402718720 -0.0465872176 -0.0172449034 0.0829187557 291 1305031239.2096450329 0.1076239273 0.0852118747 0.1427498758 0.0244087703 0.1314000000 959424809 0 402718720 -0.0458889306 -0.0178555101 0.0821090490 292 1305031239.2417099476 0.1077800021 0.0852891628 0.1427498758 0.0243787589 0.1324140000 959427769 0 402718720 -0.0451398566 -0.0188510697 0.0813930258 293 1305031239.2738199234 0.1071546227 0.0853637889 0.1427498758 0.0243597307 0.1321630000 959430729 0 402718720 -0.0439446680 -0.0195949208 0.0806160346 294 1305031239.3101770878 0.1066550314 0.0854362081 0.1427498758 0.0243188251 0.1315830000 959433857 0 402718720 -0.0427512228 -0.0200689360 0.0794690400 295 1305031239.3419699669 0.1053275988 0.0855036365 0.1427498758 0.0242814773 0.1435730000 959436817 0 402718720 -0.0414793976 -0.0198328272 0.0780625418 296 1305031239.3750240803 0.1033918858 0.0855640698 0.1427498758 0.0242575465 0.1297900000 959439721 0 402718720 -0.0403404236 -0.0193964411 0.0761512741 297 1305031239.4106309414 0.1011090726 0.0856164099 0.1427498758 0.0242194416 0.1294450000 959442737 0 402718720 -0.0392068289 -0.0181918833 0.0741486475 298 1305031239.4415419102 0.1002276465 0.0856654409 0.1427498758 0.0241826704 0.1294260000 959445641 0 402718720 -0.0376241207 -0.0184634272 0.0721897855 299 1305031239.4733181000 0.0972668007 0.0857042414 0.1427498758 0.0241430686 0.1324450000 959448545 0 402718720 -0.0366381258 -0.0167418476 0.0698287413 300 1305031239.5097389221 0.0945032164 0.0857335713 0.1427498758 0.0241043767 0.1439140000 959451561 0 402718720 -0.0350433253 -0.0148145780 0.0672073811 301 1305031239.5438020229 0.0920240656 0.0857544700 0.1427498758 0.0240726269 0.1330060000 959454577 0 402718720 -0.0338418484 -0.0138263069 0.0648144037 302 1305031239.5761160851 0.0885097757 0.0857635935 0.1427498758 0.0240448800 0.1344510000 959457481 0 402718720 -0.0326054320 -0.0107734259 0.0618392117 303 1305031239.6111609936 0.0854299366 0.0857624923 0.1427498758 0.0240128571 0.1363450000 959460497 0 402718720 -0.0313869826 -0.0080595035 0.0589571893 304 1305031239.6414220333 0.0836282000 0.0857554716 0.1427498758 0.0239768149 0.1363910000 959463345 0 402718720 -0.0302742552 -0.0067070350 0.0558589958 305 1305031239.6710560322 0.0804448053 0.0857380596 0.1427498758 0.0239538559 0.1546210000 959466137 0 402718720 -0.0290884543 -0.0037541171 0.0532561280 306 1305031239.7075550556 0.0783505663 0.0857139175 0.1427498758 0.0239632469 0.1356050000 959469153 0 402718720 -0.0276631601 -0.0025595226 0.0496506095 307 1305031239.7417550087 0.0777118132 0.0856878520 0.1427498758 0.0239265058 0.1386350000 959472169 0 402718720 -0.0262658726 -0.0023490672 0.0457248725 308 1305031239.7712600231 0.0770774186 0.0856598961 0.1427498758 0.0238928782 0.1394980000 959474961 0 402718720 -0.0243966561 -0.0022064897 0.0421740897 309 1305031239.8060870171 0.0765986070 0.0856305715 0.1427498758 0.0239623956 0.1582320000 959477921 0 402718720 -0.0215196237 -0.0040562842 0.0391179360 310 1305031239.8392889500 0.0732327700 0.0855905786 0.1427498758 0.0239464216 0.1708050000 959480881 0 402718720 -0.0228697527 -0.0014190631 0.0348924361 311 1305031239.8744299412 0.0692016855 0.0855378812 0.1427498758 0.0239132819 0.1795070000 959483785 0 402718720 -0.0243895706 -0.0000466304 0.0330431052 312 1305031239.9090619087 0.0674558282 0.0854799259 0.1427498758 0.0239268749 0.1719130000 959486801 0 402718720 -0.0218350962 0.0016407452 0.0317122191 313 1305031239.9403729439 0.0661723316 0.0854182403 0.1427498758 0.0239060106 0.1777480000 959489649 0 402718720 -0.0201648213 0.0032584746 0.0296417773 314 1305031239.9710669518 0.0652244538 0.0853539289 0.1427498758 0.0239017798 0.1805360000 959492553 0 402718720 -0.0181538500 0.0057100537 0.0276300907 315 1305031240.0088651180 0.0662149712 0.0852931703 0.1427498758 0.0239353831 0.1947330000 959495681 0 402718720 -0.0155742997 0.0049242214 0.0240593329 316 1305031240.0396599770 0.0672141686 0.0852359582 0.1427498758 0.0239061232 0.1810650000 959498473 0 402718720 -0.0127575872 0.0063463226 0.0212349277 317 1305031240.0711870193 0.0689600483 0.0851846147 0.1427498758 0.0238708261 0.1813290000 959501377 0 402718720 -0.0095120361 0.0072267256 0.0188265704 318 1305031240.1093459129 0.0717879906 0.0851424869 0.1427498758 0.0238778527 0.1798370000 959504449 0 402718720 -0.0040400643 0.0071253777 0.0164289586 319 1305031240.1435019970 0.0776936784 0.0851191364 0.1427498758 0.0238735386 0.1824740000 959507465 0 402718720 0.0072135814 0.0107648047 0.0184592195 320 1305031240.1775770187 0.0805066898 0.0851047225 0.1427498758 0.0238678325 0.1846660000 959510369 0 402718720 0.0112316683 0.0134314150 0.0170447715 321 1305031240.2093310356 0.0901540667 0.0851204526 0.1427498758 0.0238793138 0.1791390000 959513329 0 402718720 0.0255680308 0.0172740705 0.0241652820 322 1305031240.2410049438 0.0983680561 0.0851615942 0.1427498758 0.0239123421 0.1709360000 959516177 0 402718720 0.0348730050 0.0198627859 0.0240820125 323 1305031240.2774341106 0.1008679271 0.0852102206 0.1427498758 0.0238918405 0.1664570000 959519193 0 402718720 0.0382069796 0.0219320692 0.0236331113 324 1305031240.3089289665 0.1096521392 0.0852856586 0.1427498758 0.0238577832 0.1719680000 959522041 0 402718720 0.0472737774 0.0289848931 0.0284238160 325 1305031240.3422729969 0.1141965538 0.0853746152 0.1427498758 0.0238354330 0.1831080000 959525001 0 402718720 0.0512660183 0.0350958779 0.0316694602 326 1305031240.3774259090 0.1141552031 0.0854628992 0.1427498758 0.0238431106 0.1661190000 959528017 0 402718720 0.0460819043 0.0520361029 0.0352763161 327 1305031240.4091110229 0.1145194098 0.0855517571 0.1427498758 0.0238085803 0.1602930000 959530865 0 402718720 0.0459139496 0.0545240454 0.0319619551 328 1305031240.4417860508 0.1143177524 0.0856394583 0.1427498758 0.0237722300 0.1565580000 959533825 0 402718720 0.0441432819 0.0575226061 0.0308659934 329 1305031240.4776389599 0.1127244085 0.0857217834 0.1427498758 0.0237467700 0.1611680000 959536841 0 402718720 0.0327087380 0.0729230493 0.0321964696 330 1305031240.5084490776 0.1141633689 0.0858079700 0.1427498758 0.0237328226 0.1555840000 959539633 0 402718720 0.0314007364 0.0767144486 0.0329108499 331 1305031240.5412700176 0.1138424501 0.0858926663 0.1427498758 0.0237298799 0.1589600000 959542593 0 402718720 0.0240945984 0.0842347518 0.0337263532 332 1305031240.5759088993 0.1180991158 0.0859896737 0.1427498758 0.0237072229 0.1595760000 959545609 0 402718720 0.0184482280 0.0944112837 0.0374397375 333 1305031240.6101338863 0.1175320894 0.0860843956 0.1427498758 0.0236761845 0.1939550000 959548569 0 402718720 0.0179883502 0.0941962227 0.0386357494 334 1305031240.6398229599 0.1161041334 0.0861742751 0.1427498758 0.0236613922 0.1605990000 959551361 0 402718720 0.0171530023 0.0930034593 0.0404835157 335 1305031240.6747570038 0.1128275022 0.0862538370 0.1427498758 0.0236302655 0.1780940000 959554377 0 402718720 0.0203850903 0.0868667290 0.0419053696 336 1305031240.7079319954 0.1085149571 0.0863200903 0.1427498758 0.0236321488 0.1671870000 959557337 0 402718720 0.0201389659 0.0816964209 0.0429398529 337 1305031240.7439579964 0.1050406843 0.0863756410 0.1427498758 0.0236103214 0.1724350000 959560241 0 402718720 0.0212170631 0.0772104263 0.0437175073 338 1305031240.7768330574 0.0996065810 0.0864147858 0.1427498758 0.0235820910 0.1798700000 959563257 0 402718720 0.0250768121 0.0647567436 0.0400970690 339 1305031240.8096249104 0.0956891850 0.0864421439 0.1427498758 0.0235690640 0.1744430000 959566161 0 402718720 0.0231676511 0.0610300042 0.0401062146 340 1305031240.8425960541 0.0895613879 0.0864513182 0.1427498758 0.0235462564 0.1907120000 959569065 0 402718720 0.0179503895 0.0589204654 0.0389654785 341 1305031240.8794100285 0.0844000801 0.0864453028 0.1427498758 0.0235254610 0.1917910000 959572137 0 402718720 0.0145562300 0.0549637750 0.0363076404 342 1305031240.9084498882 0.0762935430 0.0864156193 0.1427498758 0.0235040980 0.1824650000 959574985 0 402718720 0.0066729253 0.0511112101 0.0326579660 343 1305031240.9423189163 0.0615247004 0.0863430510 0.1427498758 0.0234987366 0.1864740000 959577889 0 402718720 -0.0184614416 0.0479892641 0.0187517088 344 1305031240.9779360294 0.0588413663 0.0862631043 0.1427498758 0.0234665767 0.1845530000 959580905 0 402718720 -0.0224080533 0.0428013951 0.0171690229 345 1305031241.0083029270 0.0550248995 0.0861725588 0.1427498758 0.0235422903 0.2022160000 959583753 0 402718720 -0.0311473589 0.0433040969 0.0176620558 346 1305031241.0401480198 0.0515898988 0.0860726089 0.1427498758 0.0235662722 0.1922870000 959586545 0 402718720 -0.0398439690 0.0397982895 0.0178256258 347 1305031241.0759329796 0.0518729649 0.0859740508 0.1427498758 0.0235513856 0.1941610000 959589617 0 402718720 -0.0436126851 0.0346620642 0.0178743992 348 1305031241.1065559387 0.0520459227 0.0858765562 0.1427498758 0.0235242220 0.1976320000 959592465 0 402718720 -0.0512542985 0.0306081232 0.0194606800 349 1305031241.1400520802 0.0545452721 0.0857867817 0.1427498758 0.0235180148 0.2097890000 959595369 0 402718720 -0.0590085946 0.0278743114 0.0204243362 350 1305031241.1781818867 0.0586912669 0.0857093660 0.1427498758 0.0235649481 0.2127010000 959598441 0 402718720 -0.0669471473 0.0272227451 0.0217501987 351 1305031241.2106790543 0.0605578274 0.0856377092 0.1427498758 0.0235351151 0.2003820000 959601401 0 402718720 -0.0707715228 0.0259466469 0.0243035685 352 1305031241.2393150330 0.0599671490 0.0855647815 0.1427498758 0.0235564148 0.1904350000 959604137 0 402718720 -0.0646847188 0.0229054857 0.0278136823 353 1305031241.2768468857 0.0489709713 0.0854611163 0.1427498758 0.0235624734 0.1924100000 959607265 0 402718720 -0.0410225987 0.0248365831 0.0433440655 354 1305031241.3063299656 0.0466585383 0.0853515045 0.1427498758 0.0235340201 0.1801740000 959610113 0 402718720 -0.0314987339 0.0297474507 0.0511688404 355 1305031241.3424758911 0.0470930599 0.0852437342 0.1427498758 0.0235255977 0.1714000000 959613129 0 402718720 -0.0283658132 0.0301935673 0.0562703200 356 1305031241.3795149326 0.0526664034 0.0851522248 0.1427498758 0.0235597966 0.1683340000 959616145 0 402718720 -0.0273321718 0.0267777406 0.0583861731 357 1305031241.4096820354 0.0578002334 0.0850756086 0.1427498758 0.0235531614 0.1640280000 959618993 0 402718720 -0.0277706664 0.0236990787 0.0603362620 358 1305031241.4455459118 0.0626461059 0.0850129564 0.1427498758 0.0235420754 0.1518860000 959622009 0 402718720 -0.0294888411 0.0220329706 0.0627870932 359 1305031241.4775071144 0.0668991059 0.0849625000 0.1427498758 0.0237616220 0.1496450000 959624913 0 402718720 -0.0296106916 0.0189256519 0.0643389672 360 1305031241.5098490715 0.0706304461 0.0849226887 0.1427498758 0.0237632107 0.1567500000 959627817 0 402718720 -0.0303099621 0.0158924684 0.0648509115 361 1305031241.5477299690 0.0737188905 0.0848916533 0.1427498758 0.0237337685 0.1681260000 959630945 0 402718720 -0.0310169440 0.0125337290 0.0651038513 362 1305031241.5783948898 0.0747179016 0.0848635490 0.1427498758 0.0237164449 0.1445990000 959633737 0 402718720 -0.0311655197 0.0115118185 0.0648402870 363 1305031241.6092638969 0.0755001530 0.0848377545 0.1427498758 0.0237065927 0.1446800000 959636585 0 402718720 -0.0307100862 0.0099328812 0.0643309280 364 1305031241.6475839615 0.0774842799 0.0848175526 0.1427498758 0.0236759912 0.1457840000 959639713 0 402718720 -0.0296456702 0.0067876489 0.0631118640 365 1305031241.6783659458 0.0740127340 0.0847879504 0.1427498758 0.0236905746 0.1670570000 959642617 0 402718720 -0.0286879633 0.0101710139 0.0616811216 366 1305031241.7098269463 0.0721837208 0.0847535126 0.1427498758 0.0236697244 0.1460730000 959645409 0 402718720 -0.0275537893 0.0118870437 0.0604891926 367 1305031241.7471020222 0.0704737008 0.0847146030 0.1427498758 0.0236420805 0.1457660000 959648537 0 402718720 -0.0270443782 0.0130921360 0.0591105297 368 1305031241.7782680988 0.0703098476 0.0846754597 0.1427498758 0.0236297770 0.1462790000 959651441 0 402718720 -0.0261451323 0.0130832866 0.0582120977 369 1305031241.8098289967 0.0683761686 0.0846312882 0.1427498758 0.0236260156 0.1454760000 959654233 0 402718720 -0.0259259492 0.0153118437 0.0574137643 370 1305031241.8464360237 0.0698855817 0.0845914349 0.1427498758 0.0236276608 0.1556450000 959657305 0 402718720 -0.0261163116 0.0128312325 0.0560440943 371 1305031241.8787989616 0.0699248910 0.0845519024 0.1427498758 0.0237053132 0.1470690000 959660265 0 402718720 -0.0266135614 0.0129585555 0.0550770462 372 1305031241.9114871025 0.0673042983 0.0845055379 0.1427498758 0.0237276821 0.1474320000 959663169 0 402718720 -0.0275574122 0.0158126149 0.0548089817 373 1305031241.9477050304 0.0677510798 0.0844606198 0.1427498758 0.0237292155 0.1497220000 959666185 0 402718720 -0.0275286194 0.0151258642 0.0545447469 374 1305031241.9783430099 0.0677589253 0.0844159629 0.1427498758 0.0238578469 0.1497560000 959669089 0 402718720 -0.0285287648 0.0150624430 0.0536831319 375 1305031242.0105700493 0.0674999952 0.0843708536 0.1427498758 0.0239566484 0.1682470000 959671937 0 402718720 -0.0303119943 0.0154102705 0.0526526310 376 1305031242.0463600159 0.0689806342 0.0843299222 0.1427498758 0.0240401204 0.1492820000 959674953 0 402718720 -0.0317342803 0.0139938807 0.0512479581 377 1305031242.0795490742 0.0713591948 0.0842955171 0.1427498758 0.0241576370 0.1472490000 959677857 0 402718720 -0.0330257267 0.0116166547 0.0497162268 378 1305031242.1105840206 0.0742573366 0.0842689610 0.1427498758 0.0242527424 0.1448700000 959680761 0 402718720 -0.0358914360 0.0079946835 0.0470873900 379 1305031242.1466050148 0.0771784186 0.0842502525 0.1427498758 0.0243926996 0.1424850000 959683777 0 402718720 -0.0388801172 0.0045210919 0.0444184579 380 1305031242.1797080040 0.0800634027 0.0842392344 0.1427498758 0.0244908154 0.1533400000 959686737 0 402718720 -0.0420631953 0.0008267135 0.0418272689 381 1305031242.2087249756 0.0823596194 0.0842343011 0.1427498758 0.0245364704 0.1399900000 959689529 0 402718720 -0.0454529151 -0.0027538782 0.0393895134 382 1305031242.2478089333 0.0845138505 0.0842350329 0.1427498758 0.0246122070 0.1386860000 959692657 0 402718720 -0.0476276688 -0.0063886903 0.0375532508 383 1305031242.2794981003 0.0863447860 0.0842405414 0.1427498758 0.0246627348 0.1386400000 959695561 0 402718720 -0.0502239019 -0.0089763422 0.0350601859 384 1305031242.3097639084 0.0881584212 0.0842507442 0.1427498758 0.0247023140 0.1391460000 959698353 0 402718720 -0.0520458221 -0.0119293081 0.0327589326 385 1305031242.3471269608 0.0897134244 0.0842649330 0.1427498758 0.0248179908 0.1522290000 959701481 0 402718720 -0.0540399142 -0.0147788888 0.0299757849 386 1305031242.3784790039 0.0904707313 0.0842810102 0.1427498758 0.0249265667 0.1371570000 959704385 0 402718720 -0.0559766404 -0.0163114276 0.0277319960 387 1305031242.4109969139 0.0915803909 0.0842998716 0.1427498758 0.0249948182 0.1365440000 959707289 0 402718720 -0.0570705459 -0.0184241366 0.0255339369 388 1305031242.4470989704 0.0925713480 0.0843211898 0.1427498758 0.0251459209 0.1383620000 959710361 0 402718720 -0.0583194420 -0.0207492001 0.0227557402 389 1305031242.4776470661 0.0939958170 0.0843460604 0.1427498758 0.0252551724 0.1370360000 959713265 0 402718720 -0.0595964156 -0.0223597530 0.0193099510 390 1305031242.5097260475 0.0959099457 0.0843757113 0.1427498758 0.0255167557 0.1486560000 959716169 0 402718720 -0.0614430420 -0.0248279329 0.0154708596 391 1305031242.5485460758 0.0966268480 0.0844070442 0.1427498758 0.0259768891 0.1397450000 959719297 0 402718720 -0.0641095787 -0.0249898415 0.0118241291 392 1305031242.5748429298 0.0982979462 0.0844424801 0.1427498758 0.0261258698 0.1386460000 959721977 0 402718720 -0.0673364773 -0.0250147637 0.0076448913 393 1305031242.6061151028 0.1002079993 0.0844825960 0.1427498758 0.0262411265 0.1394800000 959724937 0 402718720 -0.0699098632 -0.0258092470 0.0037650324 394 1305031242.6438109875 0.1030234918 0.0845296541 0.1427498758 0.0264762083 0.1380310000 959728009 0 402718720 -0.0736032426 -0.0274189096 0.0001376990 395 1305031242.6752018929 0.1047678068 0.0845808899 0.1427498758 0.0267839794 0.1729860000 959730969 0 402718720 -0.0780817568 -0.0280557834 -0.0027507842 396 1305031242.7139821053 0.1062704399 0.0846356615 0.1427498758 0.0272035306 0.1440520000 959734153 0 402718720 -0.0813659057 -0.0269267261 -0.0055969977 397 1305031242.7452580929 0.1092599779 0.0846976875 0.1427498758 0.0272831197 0.1435050000 959737057 0 402718720 -0.0853662863 -0.0272045154 -0.0091626868 398 1305031242.7775399685 0.1118787751 0.0847659817 0.1427498758 0.0274438768 0.1441320000 959740017 0 402718720 -0.0896792114 -0.0277805664 -0.0120567298 399 1305031242.8140709400 0.1144275367 0.0848403214 0.1427498758 0.0276580352 0.1444950000 959743089 0 402718720 -0.0940346196 -0.0269499645 -0.0140080238 400 1305031242.8443179131 0.1164345518 0.0849193070 0.1427498758 0.0277119394 0.1561450000 959745993 0 402718720 -0.0974109769 -0.0257383995 -0.0158121176 401 1305031242.8740880489 0.1201147586 0.0850070762 0.1427498758 0.0277530186 0.1572930000 959748953 0 402718720 -0.1018426418 -0.0260788929 -0.0178847592 402 1305031242.9137070179 0.1287904233 0.0851159900 0.1427498758 0.0278471031 0.1525090000 959752193 0 402718720 -0.1125344113 -0.0277919658 -0.0240000319 403 1305031242.9444379807 0.1296302229 0.0852264472 0.1427498758 0.0280106987 0.1448450000 959755097 0 402718720 -0.1162659526 -0.0247769188 -0.0243389588 404 1305031242.9760620594 0.1299391538 0.0853371222 0.1427498758 0.0280810063 0.1466720000 959758001 0 402718720 -0.1197174489 -0.0208556689 -0.0252445843 405 1305031243.0141661167 0.1320750415 0.0854525244 0.1427498758 0.0281400008 0.1441940000 959761129 0 402718720 -0.1237978339 -0.0191068146 -0.0255857408 406 1305031243.0469100475 0.1336356699 0.0855712021 0.1427498758 0.0281400975 0.1432540000 959764257 0 402718720 -0.1280591190 -0.0176629871 -0.0261088014 407 1305031243.0780448914 0.1346838772 0.0856918721 0.1427498758 0.0281301215 0.1698930000 959767217 0 402718720 -0.1311837733 -0.0151508870 -0.0277443528 408 1305031243.1136150360 0.1347016990 0.0858119942 0.1427498758 0.0281358136 0.1524810000 959770233 0 402718720 -0.1339279711 -0.0122411232 -0.0288173966 409 1305031243.1458160877 0.1345389187 0.0859311310 0.1427498758 0.0281034370 0.1426050000 959773249 0 402718720 -0.1363199055 -0.0091925189 -0.0307597518 410 1305031243.1780760288 0.1333909631 0.0860468866 0.1427498758 0.0280960227 0.1557260000 959776209 0 402718720 -0.1376919150 -0.0081611685 -0.0312207527 411 1305031243.2136580944 0.1326316595 0.0861602316 0.1427498758 0.0281320287 0.1568380000 959779281 0 402718720 -0.1370547861 -0.0105180340 -0.0303033944 412 1305031243.2455608845 0.1337210685 0.0862756705 0.1427498758 0.0284215714 0.1448700000 959782241 0 402718720 -0.1353963166 -0.0137747517 -0.0305411015 413 1305031243.2781798840 0.1347333789 0.0863930015 0.1427498758 0.0285219870 0.1449230000 959785257 0 402718720 -0.1339126527 -0.0185415037 -0.0296112876 414 1305031243.3142709732 0.1264101565 0.0864896613 0.1427498758 0.0285768517 0.1565880000 959788273 0 402718720 -0.1212365180 -0.0160438679 -0.0227411706 415 1305031243.3460359573 0.1292373091 0.0865926677 0.1427498758 0.0289407466 0.1633610000 959791289 0 402718720 -0.1206257939 -0.0193018075 -0.0230210926 416 1305031243.3789350986 0.1307634413 0.0866988475 0.1427498758 0.0289986203 0.1435250000 959794305 0 402718720 -0.1204868853 -0.0211846121 -0.0216157641 417 1305031243.4139740467 0.1226629764 0.0867850924 0.1427498758 0.0290784925 0.1528610000 959797321 0 402718720 -0.1114954203 -0.0133997062 -0.0152925448 418 1305031243.4470911026 0.1260477304 0.0868790221 0.1427498758 0.0293266750 0.1444290000 959800337 0 402718720 -0.1133216396 -0.0155722406 -0.0153431268 419 1305031243.4780371189 0.1247719526 0.0869694587 0.1427498758 0.0293593309 0.1652950000 959803241 0 402718720 -0.1110220924 -0.0121336058 -0.0129181482 420 1305031243.5154008865 0.1234782562 0.0870563844 0.1427498758 0.0294882482 0.1778990000 959806369 0 402718720 -0.1124881506 -0.0064433333 -0.0120801674 421 1305031243.5459430218 0.1249972954 0.0871465053 0.1427498758 0.0295676520 0.1444870000 959809329 0 402718720 -0.1147439554 -0.0063506626 -0.0115364231 422 1305031243.5779840946 0.1206723303 0.0872259504 0.1427498758 0.0295720057 0.1533770000 959812177 0 402718720 -0.1135564819 -0.0001001817 -0.0091984347 423 1305031243.6140549183 0.1185849085 0.0873000851 0.1427498758 0.0298429421 0.1539250000 959815193 0 402718720 -0.1126376987 0.0038239411 -0.0076978025 424 1305031243.6461870670 0.1213579252 0.0873804102 0.1427498758 0.0301735538 0.1464060000 959818209 0 402718720 -0.1147085950 0.0002189064 -0.0090305163 425 1305031243.6782801151 0.1240251735 0.0874666331 0.1427498758 0.0302326279 0.1526960000 959821113 0 402718720 -0.1160431802 -0.0029188930 -0.0102412533 426 1305031243.7142961025 0.1139256880 0.0875287436 0.1427498758 0.0305559685 0.1810870000 959824073 0 402718720 -0.1081311107 0.0063617374 -0.0051682498 427 1305031243.7473781109 0.1157036275 0.0875947269 0.1427498758 0.0308765614 0.1489550000 959827033 0 402718720 -0.1082260534 0.0015391182 -0.0053348369 428 1305031243.7790360451 0.1176087260 0.0876648531 0.1427498758 0.0310927067 0.1832690000 959829881 0 402718720 -0.1083195359 -0.0028528650 -0.0056395549 429 1305031243.8141930103 0.1039875746 0.0877029014 0.1427498758 0.0315483092 0.1716340000 959832841 0 402718720 -0.0925722867 0.0050493334 0.0036406661 430 1305031243.8462920189 0.1063414067 0.0877462468 0.1427498758 0.0319280310 0.1648470000 959835745 0 402718720 -0.0880121067 -0.0001404949 0.0033834463 431 1305031243.8788089752 0.0991050005 0.0877726012 0.1427498758 0.0320660234 0.1768080000 959838705 0 402718720 -0.0783011913 0.0037926694 0.0094725108 432 1305031243.9140000343 0.0919453129 0.0877822602 0.1427498758 0.0323180221 0.1779670000 959841609 0 402718720 -0.0713746846 0.0078551788 0.0143795954 433 1305031243.9470779896 0.0846277326 0.0877749750 0.1427498758 0.0324453753 0.1819220000 959844625 0 402718720 -0.0680447966 0.0139651373 0.0181955155 434 1305031243.9816520214 0.0824576989 0.0877627232 0.1427498758 0.0325753221 0.1771830000 959847585 0 402718720 -0.0657161996 0.0149917081 0.0195980873 435 1305031244.0112700462 0.0761806071 0.0877360976 0.1427498758 0.0326270851 0.2090290000 959850433 0 402718720 -0.0602605119 0.0210905299 0.0240826551 436 1305031244.0438230038 0.0688833222 0.0876928573 0.1427498758 0.0326316010 0.1918890000 959853337 0 402718720 -0.0604408942 0.0315283202 0.0272263177 437 1305031244.0818090439 0.0642840192 0.0876392902 0.1427498758 0.0326505252 0.1913920000 959856409 0 402718720 -0.0601021536 0.0371756889 0.0305315666 438 1305031244.1127901077 0.0657476932 0.0875893094 0.1427498758 0.0327279543 0.1916490000 959859313 0 402718720 -0.0589042939 0.0365333594 0.0310384147 439 1305031244.1484949589 0.0619454645 0.0875308951 0.1427498758 0.0327241064 0.2145290000 959862329 0 402718720 -0.0608082972 0.0432908386 0.0334829278 440 1305031244.1824309826 0.0582850464 0.0874644273 0.1427498758 0.0327970098 0.2134660000 959865233 0 402718720 -0.0608632714 0.0470885187 0.0370861739 441 1305031244.2124009132 0.0583734624 0.0873984614 0.1427498758 0.0329008724 0.2021050000 959868137 0 402718720 -0.0595458522 0.0494467951 0.0382759422 442 1305031244.2473471165 0.0529671051 0.0873205624 0.1427498758 0.0330516448 0.2111690000 959871097 0 402718720 -0.0559898652 0.0569942370 0.0429113507 443 1305031244.2831470966 0.0520634390 0.0872409752 0.1427498758 0.0331870229 0.2058030000 959874113 0 402718720 -0.0535753965 0.0602416359 0.0439237021 444 1305031244.3137950897 0.0440715253 0.0871437467 0.1427498758 0.0333077144 0.2249440000 959876905 0 402718720 -0.0472865961 0.0707586780 0.0495709032 445 1305031244.3459599018 0.0390664078 0.0870357077 0.1427498758 0.0334779106 0.2224860000 959879865 0 402718720 -0.0383397713 0.0800916031 0.0551380664 446 1305031244.3808560371 0.0399594344 0.0869301556 0.1427498758 0.0336544249 0.2030140000 959882825 0 402718720 -0.0357334092 0.0833878368 0.0534685515 447 1305031244.4130189419 0.0381127968 0.0868209445 0.1427498758 0.0338606048 0.2098050000 959885729 0 402718720 -0.0268023219 0.0925473645 0.0580720492 448 1305031244.4451670647 0.0357667580 0.0867069842 0.1427498758 0.0339320827 0.2070880000 959888633 0 402718720 -0.0264784731 0.1020324305 0.0577549748 449 1305031244.4806590080 0.0364637598 0.0865950840 0.1427498758 0.0340108866 0.1965960000 959891649 0 402718720 -0.0286522489 0.1058380678 0.0545862727 450 1305031244.5142281055 0.0380285792 0.0864871584 0.1427498758 0.0341134474 0.1955840000 959894609 0 402718720 -0.0300026331 0.1100177541 0.0532812998 451 1305031244.5462141037 0.0350775123 0.0863731680 0.1427498758 0.0340917742 0.2015810000 959897513 0 402718720 -0.0330872871 0.1194116697 0.0551140383 452 1305031244.5808050632 0.0352207832 0.0862599991 0.1427498758 0.0341423174 0.2039820000 959900473 0 402718720 -0.0357717350 0.1200535446 0.0553226098 453 1305031244.6132769585 0.0361827388 0.0861494532 0.1427498758 0.0342287042 0.1907790000 959903433 0 402718720 -0.0373619683 0.1207853705 0.0557263643 454 1305031244.6428399086 0.0351155289 0.0860370437 0.1427498758 0.0342191247 0.2104520000 959906225 0 402718720 -0.0390111543 0.1232618019 0.0570306405 455 1305031244.6806099415 0.0337563306 0.0859221410 0.1427498758 0.0342765890 0.1897800000 959909241 0 402718720 -0.0391361825 0.1269614697 0.0602575317 456 1305031244.7152500153 0.0338563174 0.0858079616 0.1427498758 0.0342993070 0.1876520000 959912257 0 402718720 -0.0429515168 0.1279606223 0.0604116432 457 1305031244.7458879948 0.0349836051 0.0856967486 0.1427498758 0.0344794423 0.1861630000 959915105 0 402718720 -0.0449754633 0.1281514019 0.0602504648 458 1305031244.7818510532 0.0361657813 0.0855886023 0.1427498758 0.0345689846 0.1853610000 959918177 0 402718720 -0.0453453586 0.1282234490 0.0596602336 459 1305031244.8140940666 0.0309281778 0.0854695165 0.1427498758 0.0354094638 0.2071640000 959921081 0 402718720 -0.0392946377 0.1330662221 0.0645091161 460 1305031244.8418219090 0.0282687582 0.0853451670 0.1427498758 0.0353947416 0.1954390000 959923817 0 402718720 -0.0356486179 0.1361533552 0.0662378892 461 1305031244.8818008900 0.0289325807 0.0852227969 0.1427498758 0.0353641470 0.1880220000 959926945 0 402718720 -0.0373588949 0.1385462135 0.0640615299 462 1305031244.9149079323 0.0257304870 0.0850940257 0.1427498758 0.0353408620 0.1949350000 959929849 0 402718720 -0.0357942097 0.1449024230 0.0657519549 463 1305031244.9458680153 0.0264324844 0.0849673269 0.1427498758 0.0353046550 0.1884770000 959932697 0 402718720 -0.0361956134 0.1466592252 0.0648024008 464 1305031244.9818000793 0.0278504323 0.0848442302 0.1427498758 0.0353274660 0.1860500000 959935713 0 402718720 -0.0356333926 0.1495859176 0.0657392442 465 1305031245.0140550137 0.0260276124 0.0847177428 0.1427498758 0.0352916721 0.1882870000 959938617 0 402718720 -0.0334185883 0.1505080611 0.0677554160 466 1305031245.0464398861 0.0268668924 0.0845935994 0.1427498758 0.0352568914 0.2093210000 959941521 0 402718720 -0.0339467078 0.1524900496 0.0679204389 467 1305031245.0817689896 0.0251633767 0.0844663398 0.1427498758 0.0352360315 0.1906700000 959944537 0 402718720 -0.0323368646 0.1529860198 0.0709257945 468 1305031245.1143150330 0.0258724838 0.0843411392 0.1427498758 0.0352337926 0.1924840000 959947385 0 402718720 -0.0312848166 0.1520090252 0.0720255673 469 1305031245.1457099915 0.0273617618 0.0842196480 0.1427498758 0.0352168618 0.1958280000 959950345 0 402718720 -0.0321804807 0.1515591741 0.0725663081 470 1305031245.1818709373 0.0279413071 0.0840999069 0.1427498758 0.0352285450 0.1982660000 959953305 0 402718720 -0.0303949323 0.1489130855 0.0743526518 471 1305031245.2140939236 0.0310809240 0.0839873400 0.1427498758 0.0353088215 0.2030140000 959956209 0 402718720 -0.0286031552 0.1440480649 0.0745569542 472 1305031245.2487950325 0.0322570540 0.0838777420 0.1427498758 0.0356559997 0.2124550000 959959225 0 402718720 -0.0402940772 0.1432259232 0.0672179237 473 1305031245.2807950974 0.0336413085 0.0837715339 0.1427498758 0.0357405742 0.2067830000 959962073 0 402718720 -0.0399386808 0.1380768120 0.0663184077 474 1305031245.3143179417 0.0344428495 0.0836674649 0.1427498758 0.0358866756 0.2096350000 959964977 0 402718720 -0.0381228663 0.1322400570 0.0662797615 475 1305031245.3491809368 0.0346764512 0.0835643259 0.1427498758 0.0361382795 0.2189350000 959968049 0 402718720 -0.0454033315 0.1267370433 0.0589606017 476 1305031245.3806860447 0.0367873535 0.0834660550 0.1427498758 0.0363555847 0.2288170000 959970841 0 402718720 -0.0481569283 0.1191480085 0.0524228327 477 1305031245.4133110046 0.0396807492 0.0833742619 0.1427498758 0.0365163610 0.2173910000 959973745 0 402718720 -0.0524239354 0.1123588309 0.0450832695 478 1305031245.4489970207 0.0448807292 0.0832937315 0.1427498758 0.0365061255 0.2313240000 959976705 0 402718720 -0.0512806401 0.1010885388 0.0375632681 479 1305031245.4846711159 0.0446624570 0.0832130816 0.1427498758 0.0367482089 0.2158630000 959979721 0 402718720 -0.0484330021 0.0979527459 0.0367403068 480 1305031245.5124320984 0.0479963943 0.0831397135 0.1427498758 0.0368336896 0.2416540000 959982513 0 402718720 -0.0545264482 0.0922610238 0.0291176382 481 1305031245.5481460094 0.0509426817 0.0830727758 0.1427498758 0.0369759463 0.2352220000 959985473 0 402718720 -0.0591869801 0.0861456394 0.0228571165 482 1305031245.5786890984 0.0514022037 0.0830070693 0.1427498758 0.0370013099 0.2168390000 959988377 0 402718720 -0.0580858663 0.0821836963 0.0218347162 483 1305031245.6104750633 0.0565889627 0.0829523734 0.1427498758 0.0370646497 0.2216850000 959991225 0 402718720 -0.0621636659 0.0749404356 0.0147018051 484 1305031245.6494629383 0.0577020608 0.0829002033 0.1427498758 0.0372519436 0.2247470000 959994297 0 402718720 -0.0670346618 0.0720996633 0.0110456767 485 1305031245.6802349091 0.0581119768 0.0828490936 0.1427498758 0.0372791689 0.2277950000 959997201 0 402718720 -0.0682272315 0.0699579492 0.0104920622 486 1305031245.7110319138 0.0606341138 0.0828033837 0.1427498758 0.0372897459 0.2206580000 960000105 0 402718720 -0.0713535547 0.0664234832 0.0072222962 487 1305031245.7497749329 0.0613383055 0.0827593076 0.1427498758 0.0373578530 0.2094360000 960003177 0 402718720 -0.0720903575 0.0647509247 0.0066212690 488 1305031245.7818500996 0.0631647035 0.0827191547 0.1427498758 0.0374020037 0.2056140000 960006137 0 402718720 -0.0720704570 0.0633033887 0.0050996118 489 1305031245.8135690689 0.0648094192 0.0826825295 0.1427498758 0.0375020973 0.2030940000 960008985 0 402718720 -0.0724286288 0.0623455979 0.0040336582 490 1305031245.8491089344 0.0708547831 0.0826583912 0.1427498758 0.0375231805 0.2031770000 960012001 0 402718720 -0.0774304569 0.0567932501 -0.0015454119 491 1305031245.8820281029 0.0712983757 0.0826352548 0.1427498758 0.0375499099 0.2109240000 960014961 0 402718720 -0.0744355321 0.0549282506 -0.0008319387 492 1305031245.9126079082 0.0732726678 0.0826162251 0.1427498758 0.0375588163 0.2082870000 960017809 0 402718720 -0.0713177547 0.0524232611 -0.0012644215 493 1305031245.9458959103 0.0749518350 0.0826006787 0.1427498758 0.0376099933 0.1828930000 960020713 0 402718720 -0.0700558126 0.0489371158 -0.0019456387 494 1305031245.9808180332 0.0764185712 0.0825881643 0.1427498758 0.0376423281 0.1793960000 960023729 0 402718720 -0.0701571330 0.0464444868 -0.0033546328 495 1305031246.0110030174 0.0815050900 0.0825859763 0.1427498758 0.0376503532 0.1820310000 960026577 0 402718720 -0.0735612661 0.0401367433 -0.0083283540 496 1305031246.0483930111 0.0830165595 0.0825868444 0.1427498758 0.0377359984 0.1832450000 960029705 0 402718720 -0.0735191777 0.0374720357 -0.0102921836 497 1305031246.0805249214 0.0858104676 0.0825933305 0.1427498758 0.0378052605 0.1680920000 960032497 0 402718720 -0.0743415505 0.0339038037 -0.0126881879 498 1305031246.1123559475 0.0880118832 0.0826042112 0.1427498758 0.0379078426 0.1679460000 960035457 0 402718720 -0.0754073486 0.0308383647 -0.0147338267 499 1305031246.1484489441 0.0928068608 0.0826246574 0.1427498758 0.0380054341 0.1779310000 960038417 0 402718720 -0.0812677816 0.0250100847 -0.0201055035 500 1305031246.1805961132 0.0936733484 0.0826467547 0.1427498758 0.0380664903 0.1678340000 960041265 0 402718720 -0.0823256373 0.0243261959 -0.0217618346 501 1305031246.2111370564 0.1003953218 0.0826821810 0.1427498758 0.0381478719 0.1866160000 960044169 0 402718720 -0.0909123272 0.0165946912 -0.0285047777 502 1305031246.2469689846 0.1017935649 0.0827202515 0.1427498758 0.0382802933 0.1675640000 960047185 0 402718720 -0.0926265940 0.0150780678 -0.0303823669 503 1305031246.2796959877 0.1085863411 0.0827716751 0.1427498758 0.0383434591 0.1744950000 960050089 0 402718720 -0.0998073816 0.0086690495 -0.0368731469 504 1305031246.3124730587 0.1094330475 0.0828245747 0.1427498758 0.0384740717 0.1681000000 960053049 0 402718720 -0.1012068689 0.0096185496 -0.0384030305 505 1305031246.3482720852 0.1164498851 0.0828911595 0.1427498758 0.0385853269 0.1739730000 960056065 0 402718720 -0.1093598306 0.0037697630 -0.0441877693 506 1305031246.3782060146 0.1165901721 0.0829577583 0.1427498758 0.0387406255 0.2049800000 960058913 0 402718720 -0.1115019247 0.0062597157 -0.0451489538 507 1305031246.4156370163 0.1175369769 0.0830259619 0.1427498758 0.0389037804 0.1700230000 960062041 0 402718720 -0.1146702841 0.0081958035 -0.0455703586 508 1305031246.4452888966 0.1206792742 0.0831000826 0.1427498758 0.0389900197 0.1900370000 960064889 0 402718720 -0.1191148832 0.0068101715 -0.0471565276 509 1305031246.4774649143 0.1225407347 0.0831775691 0.1427498758 0.0390887716 0.1778480000 960067905 0 402718720 -0.1233319640 0.0081375958 -0.0487638675 510 1305031246.5163950920 0.1247488335 0.0832590814 0.1427498758 0.0392184008 0.1812210000 960071033 0 402718720 -0.1276880205 0.0100366781 -0.0500178859 511 1305031246.5491750240 0.1240272745 0.0833388626 0.1427498758 0.0393518396 0.1854810000 960074049 0 402718720 -0.1299572438 0.0141197294 -0.0496616550 512 1305031246.5795109272 0.1232155636 0.0834167468 0.1427498758 0.0394471056 0.1753660000 960076953 0 402718720 -0.1321936399 0.0178537089 -0.0491153225 513 1305031246.6164529324 0.1264577657 0.0835006474 0.1427498758 0.0395170660 0.1826680000 960080081 0 402718720 -0.1362035573 0.0188130401 -0.0512294732 514 1305031246.6477630138 0.1269015223 0.0835850849 0.1427498758 0.0395749940 0.1745210000 960185441 0 402718720 -0.1382412910 0.0227129050 -0.0520167835 515 1305031246.6807579994 0.1298266053 0.0836748743 0.1427498758 0.0396514631 0.1831660000 960188457 0 402718720 -0.1447517425 0.0224144738 -0.0541608445 516 1305031246.7169740200 0.1289944649 0.0837627029 0.1427498758 0.0398030353 0.1888070000 960191585 0 402718720 -0.1448965669 0.0272256378 -0.0543154813 517 1305031246.7491660118 0.1281014532 0.0838484645 0.1427498758 0.0398891438 0.1756230000 960194545 0 402718720 -0.1454881579 0.0315040462 -0.0548459329 518 1305031246.7808170319 0.1317737103 0.0839409843 0.1427498758 0.0399465504 0.1802360000 960197561 0 402718720 -0.1517169476 0.0313979946 -0.0582950786 519 1305031246.8168079853 0.1326648593 0.0840348646 0.1427498758 0.0400197105 0.1710930000 960200689 0 402718720 -0.1521251053 0.0360927321 -0.0606530495 520 1305031246.8488121033 0.1364871860 0.0841357345 0.1427498758 0.0400396697 0.1760480000 960203705 0 402718720 -0.1586740166 0.0361821018 -0.0646470934 521 1305031246.8806428909 0.1333694309 0.0842302329 0.1427498758 0.0401184498 0.1691900000 960206721 0 402718720 -0.1581311375 0.0412335880 -0.0643068552 522 1305031246.9166710377 0.1321401149 0.0843220143 0.1427498758 0.0401971433 0.1696690000 960209849 0 402718720 -0.1575603038 0.0441117287 -0.0659028292 523 1305031246.9495339394 0.1398220956 0.0844281330 0.1427498758 0.0401876035 0.1730860000 960212865 0 402718720 -0.1652235985 0.0427192189 -0.0732643753 524 1305031246.9775969982 0.1407249570 0.0845355697 0.1427498758 0.0401705139 0.1750600000 960215713 0 402718720 -0.1664959043 0.0440644994 -0.0754095018 525 1305031247.0167899132 0.1422301084 0.0846454641 0.1427498758 0.0402402045 0.1635850000 960218897 0 402718720 -0.1705760211 0.0449298844 -0.0785207823 526 1305031247.0479340553 0.1451906860 0.0847605690 0.1451906860 0.0402142782 0.1680700000 960221913 0 402718720 -0.1758311689 0.0451145284 -0.0834448785 527 1305031247.0778899193 0.1423195004 0.0848697890 0.1451906860 0.0401998947 0.1512440000 960224873 0 402718720 -0.1755783111 0.0474538691 -0.0840023234 528 1305031247.1162130833 0.1381538808 0.0849707059 0.1451906860 0.0401720741 0.1483690000 960228057 0 402718720 -0.1747513264 0.0526040047 -0.0853412971 529 1305031247.1473660469 0.1422353834 0.0850789567 0.1451906860 0.0401566452 0.1583660000 960231073 0 402718720 -0.1793697625 0.0515376702 -0.0903479308 530 1305031247.1796920300 0.1431580931 0.0851885400 0.1451906860 0.0401199559 0.1515420000 960234089 0 402718720 -0.1792657375 0.0486203991 -0.0913197696 531 1305031247.2169430256 0.1408218592 0.0852933108 0.1451906860 0.0400919481 0.1881540000 960237273 0 402718720 -0.1779660285 0.0490221754 -0.0910828114 532 1305031247.2487928867 0.1388446987 0.0853939713 0.1451906860 0.0400691098 0.1766480000 960240233 0 402718720 -0.1770400405 0.0486256555 -0.0902798697 533 1305031247.2794220448 0.1407398582 0.0854978097 0.1451906860 0.0400490993 0.1776990000 960243193 0 402718720 -0.1772560775 0.0462289602 -0.0916999653 534 1305031247.3166429996 0.1432054192 0.0856058764 0.1451906860 0.0400573232 0.1782750000 960246377 0 402718720 -0.1771405488 0.0411749184 -0.0918079838 535 1305031247.3477900028 0.1466407627 0.0857199603 0.1466407627 0.0401283287 0.1654250000 960249393 0 402718720 -0.1784038097 0.0375808105 -0.0919584259 536 1305031247.3786110878 0.1419245154 0.0858248196 0.1466407627 0.0401316280 0.1693860000 960252353 0 402718720 -0.1722415537 0.0391385108 -0.0879681483 537 1305031247.4168620110 0.1417633891 0.0859289882 0.1466407627 0.0401737180 0.1564400000 960255593 0 402718720 -0.1694815457 0.0380383246 -0.0854552686 538 1305031247.4487700462 0.1422354281 0.0860336470 0.1466407627 0.0403055901 0.1555050000 960258609 0 402718720 -0.1684440821 0.0383210368 -0.0840090439 539 1305031247.4802629948 0.1396208853 0.0861330668 0.1466407627 0.0403655855 0.1557210000 960261513 0 402718720 -0.1660631448 0.0403960124 -0.0801665112 540 1305031247.5178461075 0.1403338462 0.0862334386 0.1466407627 0.0404501997 0.1560150000 960264753 0 402718720 -0.1635500938 0.0401939154 -0.0774909556 541 1305031247.5459010601 0.1390432268 0.0863310537 0.1466407627 0.0405408893 0.1687780000 960267601 0 402718720 -0.1605770141 0.0405535176 -0.0746636614 542 1305031247.5779209137 0.1382533461 0.0864268513 0.1466407627 0.0406080176 0.1681820000 960270561 0 402718720 -0.1582217664 0.0414348766 -0.0731602833 543 1305031247.6152799129 0.1377874762 0.0865214381 0.1466407627 0.0407536827 0.1723200000 960273633 0 402718720 -0.1549485028 0.0415921919 -0.0711517259 544 1305031247.6484000683 0.1404396594 0.0866205525 0.1466407627 0.0408952006 0.1505910000 960276649 0 402718720 -0.1561082751 0.0376509167 -0.0715351924 545 1305031247.6835579872 0.1338016391 0.0867071233 0.1466407627 0.0410279837 0.1772660000 960279665 0 402718720 -0.1468143165 0.0400468074 -0.0653468594 546 1305031247.7159609795 0.1298999488 0.0867862310 0.1466407627 0.0412099874 0.1642630000 960282625 0 402718720 -0.1399828643 0.0411446020 -0.0607357509 547 1305031247.7469019890 0.1273433864 0.0868603757 0.1466407627 0.0414504928 0.1657140000 960285585 0 402718720 -0.1356392354 0.0406272188 -0.0583212636 548 1305031247.7822608948 0.1314919591 0.0869418202 0.1466407627 0.0416564244 0.1588580000 960288601 0 402718720 -0.1385474354 0.0315551572 -0.0605918467 549 1305031247.8139829636 0.1289091557 0.0870182635 0.1466407627 0.0419063036 0.1765660000 960291393 0 402718720 -0.1284836978 0.0293447133 -0.0571964458 550 1305031247.8484420776 0.1289896965 0.0870945751 0.1466407627 0.0420742903 0.1679020000 960294521 0 402718720 -0.1263100207 0.0267020706 -0.0582533740 551 1305031247.8820719719 0.1307161450 0.0871737432 0.1466407627 0.0421392654 0.1710180000 960297425 0 402718720 -0.1254232973 0.0232225899 -0.0619561225 552 1305031247.9173319340 0.1230513528 0.0872387388 0.1466407627 0.0421208141 0.1824340000 960300441 0 402718720 -0.1178680435 0.0328017920 -0.0616489202 553 1305031247.9496860504 0.1194021776 0.0872969006 0.1466407627 0.0421862337 0.1838080000 960303289 0 402718720 -0.1126155630 0.0365308076 -0.0617668256 554 1305031247.9861450195 0.1211387664 0.0873579870 0.1466407627 0.0423480659 0.1858310000 960306361 0 402718720 -0.1079077721 0.0307158865 -0.0645508990 555 1305031248.0181560516 0.1195596233 0.0874160079 0.1466407627 0.0423279952 0.1889610000 960309209 0 402718720 -0.1062491909 0.0308933835 -0.0671064556 556 1305031248.0499138832 0.1140729040 0.0874639520 0.1466407627 0.0423512266 0.2013520000 960312113 0 402718720 -0.0978670120 0.0362979323 -0.0649107546 557 1305031248.0857460499 0.1132311448 0.0875102127 0.1466407627 0.0425579514 0.1948690000 960315073 0 402718720 -0.0945060626 0.0330879577 -0.0684792921 558 1305031248.1175789833 0.1102990657 0.0875510529 0.1466407627 0.0425846531 0.2135160000 960317977 0 402718720 -0.0832102448 0.0360564888 -0.0660469756 559 1305031248.1493461132 0.1072419062 0.0875862780 0.1466407627 0.0425940124 0.2189260000 960320881 0 402718720 -0.0911566913 0.0366694033 -0.0728758946 560 1305031248.1848630905 0.1048774049 0.0876171550 0.1466407627 0.0427480383 0.2014440000 960323841 0 402718720 -0.0866018012 0.0359788686 -0.0732501075 561 1305031248.2167689800 0.0993065089 0.0876379917 0.1466407627 0.0427730156 0.2083280000 960326745 0 402718720 -0.0798848346 0.0423467979 -0.0707200319 562 1305031248.2488510609 0.0986910015 0.0876576590 0.1466407627 0.0427943919 0.2008520000 960329593 0 402718720 -0.0781096071 0.0411669575 -0.0719079152 563 1305031248.2847399712 0.0912279263 0.0876640005 0.1466407627 0.0428579391 0.2215270000 960332665 0 402718720 -0.0674408451 0.0514230765 -0.0644817948 564 1305031248.3161809444 0.0871001109 0.0876630007 0.1466407627 0.0429076432 0.2281260000 960335569 0 402718720 -0.0606797300 0.0596803017 -0.0599032938 565 1305031248.3488430977 0.0901052579 0.0876673232 0.1466407627 0.0429693451 0.2050160000 960338417 0 402718720 -0.0564936250 0.0560809486 -0.0613212958 566 1305031248.3881969452 0.0894136578 0.0876704086 0.1466407627 0.0429723808 0.2098750000 960341545 0 402718720 -0.0541715994 0.0582886972 -0.0615144074 567 1305031248.4155070782 0.0888553932 0.0876724986 0.1466407627 0.0430032851 0.2117100000 960344337 0 402718720 -0.0521435812 0.0608029626 -0.0615357459 568 1305031248.4482519627 0.0896361768 0.0876759557 0.1466407627 0.0430173094 0.2129440000 960347241 0 402718720 -0.0490941182 0.0624555722 -0.0622236505 569 1305031248.4852969646 0.0906941146 0.0876812601 0.1466407627 0.0430577900 0.2117030000 960350257 0 402718720 -0.0449206978 0.0648440346 -0.0622949749 570 1305031248.5154309273 0.0867031738 0.0876795441 0.1466407627 0.0430279064 0.2227310000 960353161 0 402718720 -0.0426421091 0.0771902576 -0.0577523150 571 1305031248.5470030308 0.0870324746 0.0876784109 0.1466407627 0.0430622928 0.2294460000 960356065 0 402718720 -0.0402797908 0.0806707740 -0.0579930134 572 1305031248.5860579014 0.0884735808 0.0876798010 0.1466407627 0.0431023133 0.2187700000 960359137 0 402718720 -0.0331359506 0.0867653713 -0.0557281300 573 1305031248.6180379391 0.0886230841 0.0876814473 0.1466407627 0.0431589836 0.2212900000 960361985 0 402718720 -0.0355925262 0.0875895992 -0.0601577573 574 1305031248.6494390965 0.0883707404 0.0876826481 0.1466407627 0.0431437709 0.2174450000 960364889 0 402718720 -0.0331433564 0.0963829607 -0.0584921986 575 1305031248.6860280037 0.0888435766 0.0876846671 0.1466407627 0.0431802089 0.2186920000 960367961 0 402718720 -0.0280069914 0.1047234386 -0.0541935526 576 1305031248.7199230194 0.0902327448 0.0876890909 0.1466407627 0.0431760554 0.2289500000 960370865 0 402718720 -0.0229919180 0.1134323701 -0.0503007360 577 1305031248.7498369217 0.0929942504 0.0876982853 0.1466407627 0.0432277502 0.2206060000 960373713 0 402718720 -0.0166476388 0.1205412075 -0.0456392802 578 1305031248.7856750488 0.0985873044 0.0877171244 0.1466407627 0.0432644863 0.2298580000 960376729 0 402718720 -0.0061102482 0.1273507476 -0.0397977605 579 1305031248.8181409836 0.0959479809 0.0877313400 0.1466407627 0.0432394213 0.2203550000 960379633 0 402718720 -0.0069933366 0.1379649788 -0.0373235419 580 1305031248.8496789932 0.0931136012 0.0877406198 0.1466407627 0.0432854846 0.2141750000 960382537 0 402718720 -0.0065182718 0.1384698302 -0.0405523852 581 1305031248.8855929375 0.0892770514 0.0877432643 0.1466407627 0.0433126294 0.2263110000 960385553 0 402718720 -0.0055730049 0.1396625340 -0.0428057499 582 1305031248.9178819656 0.0842077136 0.0877371894 0.1466407627 0.0432962930 0.2261710000 960388457 0 402718720 -0.0074627106 0.1410768181 -0.0441833846 583 1305031248.9526810646 0.0798675790 0.0877236910 0.1466407627 0.0433161954 0.2130440000 960391473 0 402718720 -0.0085508209 0.1435266137 -0.0457599759 584 1305031248.9845540524 0.0749504641 0.0877018190 0.1466407627 0.0433156354 0.2075010000 960394377 0 402718720 -0.0095494865 0.1455946714 -0.0461201221 585 1305031249.0169510841 0.0721037462 0.0876751556 0.1466407627 0.0433147589 0.2029080000 960397281 0 402718720 -0.0100601949 0.1470576674 -0.0447369702 586 1305031249.0523660183 0.0683012307 0.0876420943 0.1466407627 0.0432870965 0.2196170000 960400297 0 402718720 -0.0125847533 0.1546628624 -0.0396230556 587 1305031249.0845029354 0.0662656575 0.0876056779 0.1466407627 0.0432696116 0.1998670000 960403201 0 402718720 -0.0126175061 0.1544652283 -0.0366395749 588 1305031249.1168839931 0.0640727058 0.0875656558 0.1466407627 0.0432349236 0.2258700000 960406105 0 402718720 -0.0137276594 0.1540547907 -0.0336324573 589 1305031249.1534469128 0.0621097386 0.0875224370 0.1466407627 0.0432187158 0.2082560000 960409121 0 402718720 -0.0199092496 0.1624133289 -0.0278180949 590 1305031249.1847391129 0.0610061437 0.0874774941 0.1466407627 0.0431937731 0.2176440000 960412025 0 402718720 -0.0194791369 0.1617724299 -0.0236631706 591 1305031249.2168650627 0.0599991940 0.0874309995 0.1466407627 0.0431634050 0.2225700000 960414929 0 402718720 -0.0196653772 0.1593207568 -0.0218731482 592 1305031249.2532238960 0.0606579036 0.0873857747 0.1466407627 0.0431359169 0.2103620000 960417945 0 402718720 -0.0182835273 0.1596162170 -0.0179238822 593 1305031249.2848041058 0.0640216097 0.0873463747 0.1466407627 0.0431139334 0.2174060000 960420793 0 402718720 -0.0123451436 0.1607870013 -0.0131815663 594 1305031249.3174340725 0.0632474348 0.0873058041 0.1466407627 0.0430877253 0.2164770000 960423753 0 402718720 -0.0130518861 0.1608868241 -0.0104710599 595 1305031249.3527359962 0.0622443259 0.0872636840 0.1466407627 0.0430544960 0.2155800000 960426713 0 402718720 -0.0140945567 0.1614761353 -0.0074675167 596 1305031249.3847539425 0.0637198091 0.0872241809 0.1466407627 0.0430316660 0.2319420000 960429617 0 402718720 -0.0129633164 0.1586183459 -0.0078364545 597 1305031249.4178340435 0.0652636737 0.0871873961 0.1466407627 0.0430598051 0.2232710000 960432521 0 402718720 -0.0118868081 0.1569119394 -0.0080574164 598 1305031249.4537220001 0.0666432008 0.0871530412 0.1466407627 0.0430889029 0.2471400000 960435537 0 402718720 -0.0133497342 0.1540782452 -0.0091971010 599 1305031249.4859149456 0.0657101944 0.0871172435 0.1466407627 0.0431209760 0.2291460000 960438441 0 402718720 -0.0162601974 0.1491184235 -0.0127715562 600 1305031249.5177340508 0.0664718598 0.0870828345 0.1466407627 0.0431235070 0.2388510000 960441345 0 402718720 -0.0167805627 0.1408133060 -0.0180621594 601 1305031249.5543251038 0.0684393942 0.0870518138 0.1466407627 0.0432105500 0.2393480000 960444361 0 402718720 -0.0165687613 0.1311713457 -0.0238440093 602 1305031249.5859050751 0.0679070130 0.0870200118 0.1466407627 0.0433269566 0.2280340000 960447209 0 402718720 -0.0205256864 0.1286262423 -0.0268975683 603 1305031249.6180789471 0.0671381578 0.0869870403 0.1466407627 0.0433496938 0.2323590000 960450113 0 402718720 -0.0254723839 0.1180287823 -0.0333079174 604 1305031249.6542129517 0.0688085109 0.0869569434 0.1466407627 0.0435677976 0.2264630000 960453073 0 402718720 -0.0242303442 0.1153825819 -0.0332353637 605 1305031249.6856739521 0.0651259273 0.0869208590 0.1466407627 0.0436798497 0.2295190000 960455977 0 402718720 -0.0370345972 0.1131998748 -0.0392186008 606 1305031249.7177898884 0.0628889799 0.0868812025 0.1466407627 0.0437456992 0.2329440000 960458881 0 402718720 -0.0436256453 0.1047032028 -0.0426593870 607 1305031249.7539620399 0.0656616688 0.0868462444 0.1466407627 0.0438182816 0.2357560000 960461841 0 402718720 -0.0440688431 0.1024253368 -0.0440182537 608 1305031249.7854170799 0.0663522333 0.0868125372 0.1466407627 0.0438635616 0.2266730000 960464689 0 402718720 -0.0547857136 0.0971827731 -0.0501769185 609 1305031249.8186020851 0.0693114400 0.0867837997 0.1466407627 0.0438736963 0.2219960000 960467705 0 402718720 -0.0596889295 0.0911420807 -0.0539276153 610 1305031249.8537468910 0.0703476965 0.0867568553 0.1466407627 0.0439898968 0.2175310000 960470609 0 402718720 -0.0601215623 0.0915469453 -0.0539740436 611 1305031249.8855249882 0.0725764111 0.0867336467 0.1466407627 0.0440087899 0.2408900000 960473513 0 402718720 -0.0692671314 0.0877629668 -0.0580092296 612 1305031249.9170649052 0.0755628794 0.0867153938 0.1466407627 0.0440118214 0.2104310000 960476473 0 402718720 -0.0743944570 0.0798787698 -0.0612417459 613 1305031249.9533979893 0.0790735558 0.0867029275 0.1466407627 0.0440087233 0.2060810000 960479433 0 402718720 -0.0770472735 0.0731005073 -0.0640030131 614 1305031249.9851789474 0.0809479207 0.0866935546 0.1466407627 0.0440045755 0.1962390000 960482337 0 402718720 -0.0792425200 0.0700518787 -0.0649070963 615 1305031250.0164399147 0.0836943462 0.0866886778 0.1466407627 0.0439878184 0.1932180000 960485241 0 402718720 -0.0815268829 0.0660930797 -0.0666547716 616 1305031250.0531940460 0.0878668502 0.0866905904 0.1466407627 0.0440473949 0.2084710000 960488257 0 402718720 -0.0845159739 0.0582986400 -0.0690159500 617 1305031250.0845069885 0.0900514051 0.0866960375 0.1466407627 0.0441193697 0.2036150000 960491105 0 402718720 -0.0900110900 0.0565844923 -0.0698873773 618 1305031250.1208500862 0.0918654054 0.0867044021 0.1466407627 0.0442065087 0.1878950000 960494177 0 402718720 -0.0939891785 0.0570700504 -0.0696071088 619 1305031250.1532480717 0.0940895304 0.0867163329 0.1466407627 0.0444477756 0.1929650000 960497025 0 402718720 -0.0995007902 0.0553308018 -0.0681555942 620 1305031250.1853280067 0.0956647545 0.0867307658 0.1466407627 0.0444557408 0.2002820000 960499873 0 402718720 -0.1012395248 0.0513623767 -0.0667397305 621 1305031250.2214460373 0.0995863155 0.0867514672 0.1466407627 0.0444568592 0.1994020000 960502945 0 402718720 -0.1049137414 0.0452435575 -0.0674020648 622 1305031250.2537350655 0.1019362509 0.0867758800 0.1466407627 0.0445478203 0.2066110000 960505849 0 402718720 -0.1077234745 0.0394237302 -0.0656141937 623 1305031250.2852239609 0.1052057147 0.0868054624 0.1466407627 0.0445611285 0.2004200000 960508697 0 402718720 -0.1117858738 0.0339974836 -0.0656210110 624 1305031250.3208620548 0.1082624719 0.0868398486 0.1466407627 0.0445877564 0.2080990000 960511657 0 402718720 -0.1147128269 0.0313196108 -0.0657976940 625 1305031250.3517000675 0.1104860753 0.0868776826 0.1466407627 0.0446012318 0.2142960000 960514505 0 402718720 -0.1176357567 0.0292266887 -0.0657114163 626 1305031250.3851490021 0.1176607087 0.0869268568 0.1466407627 0.0446075292 0.2012240000 960517409 0 402718720 -0.1245791912 0.0240348037 -0.0683233291 627 1305031250.4215359688 0.1228981465 0.0869842272 0.1466407627 0.0446150379 0.2135660000 960520481 0 402718720 -0.1314774305 0.0209465455 -0.0701446012 628 1305031250.4540181160 0.1226682365 0.0870410489 0.1466407627 0.0446999075 0.1942160000 960523497 0 402718720 -0.1340024918 0.0244835615 -0.0676353872 629 1305031250.4856131077 0.1228993163 0.0870980573 0.1466407627 0.0446997177 0.1933210000 960526345 0 402718720 -0.1373836249 0.0261749644 -0.0654512942 630 1305031250.5215380192 0.1297337413 0.0871657330 0.1466407627 0.0446765590 0.1990310000 960529417 0 402718720 -0.1463527530 0.0218044594 -0.0675599873 631 1305031250.5536580086 0.1313998401 0.0872358346 0.1466407627 0.0446643991 0.1922950000 960532433 0 402718720 -0.1493349820 0.0235203281 -0.0657874420 632 1305031250.5853788853 0.1316275001 0.0873060746 0.1466407627 0.0446525340 0.1915470000 960535337 0 402718720 -0.1525943428 0.0238730498 -0.0633362681 633 1305031250.6213030815 0.1332433820 0.0873786453 0.1466407627 0.0446333454 0.1918190000 960538409 0 402718720 -0.1562571079 0.0247709136 -0.0622621663 634 1305031250.6535439491 0.1364894211 0.0874561071 0.1466407627 0.0446521917 0.1913850000 960541481 0 402718720 -0.1599517912 0.0253393874 -0.0617992468 635 1305031250.6852970123 0.1365717947 0.0875334547 0.1466407627 0.0446731019 0.1918920000 960544385 0 402718720 -0.1626673788 0.0272465255 -0.0592300743 636 1305031250.7216401100 0.1362903118 0.0876101164 0.1466407627 0.0446506284 0.1912950000 960547457 0 402718720 -0.1651448011 0.0301080663 -0.0571801551 637 1305031250.7534279823 0.1434427798 0.0876977658 0.1466407627 0.0446209063 0.2315100000 960550417 0 402718720 -0.1731283665 0.0278354660 -0.0591738038 638 1305031250.7853651047 0.1422701031 0.0877833024 0.1466407627 0.0445957123 0.1920980000 960553377 0 402718720 -0.1732663810 0.0304558985 -0.0570455529 639 1305031250.8217930794 0.1405826956 0.0878659305 0.1466407627 0.0445642817 0.1901650000 960556561 0 402718720 -0.1734195501 0.0317618810 -0.0546022244 640 1305031250.8538279533 0.1395159513 0.0879466337 0.1466407627 0.0445327553 0.1900130000 960559577 0 402718720 -0.1732106209 0.0322967023 -0.0534884892 641 1305031250.8820140362 0.1385811567 0.0880256267 0.1466407627 0.0444994097 0.1881010000 960562425 0 402718720 -0.1718258858 0.0326004066 -0.0526647083 642 1305031250.9217998981 0.1383637786 0.0881040350 0.1466407627 0.0444677052 0.2025060000 960565609 0 402718720 -0.1712791026 0.0330454558 -0.0531526729 643 1305031250.9535419941 0.1385052949 0.0881824196 0.1466407627 0.0444462744 0.1871260000 960568625 0 402718720 -0.1720261276 0.0333932824 -0.0548733026 644 1305031250.9853079319 0.1382711083 0.0882601970 0.1466407627 0.0444159438 0.1889470000 960571529 0 402718720 -0.1718409657 0.0315215550 -0.0547418110 645 1305031251.0214879513 0.1383742392 0.0883378932 0.1466407627 0.0443941461 0.2049680000 960574601 0 402718720 -0.1707650572 0.0305050667 -0.0557529591 646 1305031251.0534679890 0.1371208429 0.0884134086 0.1466407627 0.0443966488 0.2269540000 960577561 0 402718720 -0.1695474386 0.0289455708 -0.0565424599 647 1305031251.0851860046 0.1365142912 0.0884877531 0.1466407627 0.0443951086 0.2268900000 960580521 0 402718720 -0.1681028754 0.0257829465 -0.0576516204 648 1305031251.1214449406 0.1374078095 0.0885632470 0.1466407627 0.0443949578 0.2283790000 960583593 0 402718720 -0.1665576249 0.0221375786 -0.0601144023 649 1305031251.1537809372 0.1372842491 0.0886383179 0.1466407627 0.0444907637 0.1976060000 960586609 0 402718720 -0.1644906402 0.0185332596 -0.0633252412 650 1305031251.1851599216 0.1379676014 0.0887142091 0.1466407627 0.0445169009 0.1958280000 960589513 0 402718720 -0.1624907851 0.0133720636 -0.0656546950 651 1305031251.2204658985 0.1306465715 0.0887786214 0.1466407627 0.0445268008 0.2065920000 960592529 0 402718720 -0.1511378139 0.0141700292 -0.0636376739 652 1305031251.2524240017 0.1314961016 0.0888441390 0.1466407627 0.0445809152 0.2114720000 960595433 0 402718720 -0.1483480483 0.0104625113 -0.0669338703 653 1305031251.2844820023 0.1317882985 0.0889099034 0.1466407627 0.0447763490 0.1961550000 960598393 0 402718720 -0.1437112242 0.0062602391 -0.0699634030 654 1305031251.3190040588 0.1239683628 0.0889635096 0.1466407627 0.0448495445 0.2079200000 960601409 0 402718720 -0.1296077371 0.0085203471 -0.0664132237 655 1305031251.3532440662 0.1245939210 0.0890179072 0.1466407627 0.0449407792 0.1952740000 960604313 0 402718720 -0.1264692992 0.0041363314 -0.0686785132 656 1305031251.3870069981 0.1129847541 0.0890544420 0.1466407627 0.0449747351 0.2104430000 960607273 0 402718720 -0.1106112897 0.0129910083 -0.0612452403 657 1305031251.4210500717 0.1166800037 0.0890964900 0.1466407627 0.0450665426 0.1999120000 960610233 0 402718720 -0.1090719700 0.0066033266 -0.0647634119 658 1305031251.4496629238 0.1113895625 0.0891303701 0.1466407627 0.0451208632 0.2241040000 960613025 0 402718720 -0.0993177965 0.0090413345 -0.0606294051 659 1305031251.4890139103 0.1103677675 0.0891625968 0.1466407627 0.0452148416 0.2062820000 960616097 0 402718720 -0.0977312848 0.0071234647 -0.0611072667 660 1305031251.5207729340 0.1049772725 0.0891865584 0.1466407627 0.0453014991 0.2109130000 960619057 0 402718720 -0.0899538919 0.0101809520 -0.0572635904 661 1305031251.5530450344 0.1044789255 0.0892096936 0.1466407627 0.0454153527 0.2002310000 960621961 0 402718720 -0.0855687261 0.0079631796 -0.0571508743 662 1305031251.5887598991 0.0970285088 0.0892215045 0.1466407627 0.0454351168 0.2411810000 960624921 0 402718720 -0.0773795098 0.0159181245 -0.0513567664 663 1305031251.6208739281 0.0967060179 0.0892327934 0.1466407627 0.0454852096 0.2249950000 960627881 0 402718720 -0.0744317845 0.0142537644 -0.0509474874 664 1305031251.6528749466 0.0917377993 0.0892365660 0.1466407627 0.0455466249 0.2572840000 960630785 0 402718720 -0.0653608143 0.0196020417 -0.0458798259 665 1305031251.6897680759 0.0914458707 0.0892398882 0.1466407627 0.0455848854 0.2543670000 960633801 0 402718720 -0.0636327565 0.0190315563 -0.0452276431 666 1305031251.7204608917 0.0851162672 0.0892336966 0.1466407627 0.0456293227 0.2663400000 960636705 0 402718720 -0.0567439087 0.0265116058 -0.0381298363 667 1305031251.7531440258 0.0863720924 0.0892294063 0.1466407627 0.0457113583 0.2319280000 960639609 0 402718720 -0.0528441742 0.0238612592 -0.0383046158 668 1305031251.7892498970 0.0829674006 0.0892200321 0.1466407627 0.0457445153 0.2352440000 960642625 0 402718720 -0.0488780141 0.0300555583 -0.0338075832 669 1305031251.8209791183 0.0824927911 0.0892099764 0.1466407627 0.0457804402 0.2354090000 960645529 0 402718720 -0.0469400808 0.0294663440 -0.0319713987 670 1305031251.8537969589 0.0824234858 0.0891998473 0.1466407627 0.0458757095 0.2597530000 960648433 0 402718720 -0.0346913971 0.0329085737 -0.0228399783 671 1305031251.8896539211 0.0827122107 0.0891901787 0.1466407627 0.0458667285 0.2521880000 960651393 0 402718720 -0.0259877928 0.0400017872 -0.0154138198 672 1305031251.9219300747 0.0787089989 0.0891745817 0.1466407627 0.0458540399 0.2554540000 960654353 0 402718720 -0.0243090019 0.0504930876 -0.0089765601 673 1305031251.9538369179 0.0767349079 0.0891560978 0.1466407627 0.0458633852 0.2579810000 960657201 0 402718720 -0.0223718304 0.0580342896 -0.0032614057 674 1305031251.9898068905 0.0754923746 0.0891358252 0.1466407627 0.0458601057 0.2514390000 960660217 0 402718720 -0.0224709902 0.0592760965 -0.0025645676 675 1305031252.0221600533 0.0738919452 0.0891132417 0.1466407627 0.0458858422 0.2560920000 960663177 0 402718720 -0.0199497975 0.0657341853 0.0024065042 676 1305031252.0537619591 0.0700886771 0.0890850988 0.1466407627 0.0458999781 0.2539240000 960666081 0 402718720 -0.0182400849 0.0750042796 0.0072887517 677 1305031252.0895619392 0.0670539811 0.0890525566 0.1466407627 0.0459465467 0.2692140000 960669041 0 402718720 -0.0170651991 0.0852262601 0.0112015698 678 1305031252.1221520901 0.0629254431 0.0890140210 0.1466407627 0.0459991533 0.2494800000 960672001 0 402718720 -0.0185515154 0.0894620121 0.0088280495 679 1305031252.1539709568 0.0574220344 0.0889674938 0.1466407627 0.0461038744 0.2537770000 960674793 0 402718720 -0.0196638294 0.1038917229 0.0123788612 680 1305031252.1897890568 0.0490994677 0.0889088643 0.1466407627 0.0460866753 0.2504570000 960677809 0 402718720 -0.0318561047 0.1185620949 0.0085102031 681 1305031252.2220859528 0.0470603481 0.0888474128 0.1466407627 0.0460705692 0.2472540000 960680769 0 402718720 -0.0406908467 0.1300906986 0.0073332237 682 1305031252.2530639172 0.0444384627 0.0887822970 0.1466407627 0.0461715192 0.2539800000 960683673 0 402718720 -0.0366394147 0.1312603951 0.0113685066 683 1305031252.2888779640 0.0417071730 0.0887133730 0.1466407627 0.0462406174 0.2380020000 960686577 0 402718720 -0.0380384512 0.1292353123 0.0085852752 684 1305031252.3206090927 0.0428190231 0.0886462760 0.1466407627 0.0462189634 0.2402000000 960689481 0 402718720 -0.0345405526 0.1342858970 0.0124963652 685 1305031252.3528549671 0.0425738916 0.0885790170 0.1466407627 0.0462219194 0.2346990000 960692329 0 402718720 -0.0303203072 0.1366538256 0.0161681995 686 1305031252.3893189430 0.0422251783 0.0885114458 0.1466407627 0.0462079587 0.2403580000 960695345 0 402718720 -0.0309158824 0.1358981133 0.0142342290 687 1305031252.4217019081 0.0427138731 0.0884447827 0.1466407627 0.0461947338 0.2417320000 960698305 0 402718720 -0.0316881277 0.1366454065 0.0129780816 688 1305031252.4538249969 0.0426406227 0.0883782069 0.1466407627 0.0461714100 0.2275230000 960701209 0 402718720 -0.0313116349 0.1375682056 0.0144463079 689 1305031252.4895589352 0.0430843793 0.0883124684 0.1466407627 0.0461415226 0.2278110000 960704113 0 402718720 -0.0321341716 0.1382527798 0.0149057517 690 1305031252.5221700668 0.0434586667 0.0882474628 0.1466407627 0.0461146518 0.2305350000 960707073 0 402718720 -0.0325254761 0.1379937679 0.0152388494 691 1305031252.5537741184 0.0443466417 0.0881839305 0.1466407627 0.0460888538 0.2314190000 960709977 0 402718720 -0.0336180776 0.1380307823 0.0148007674 692 1305031252.5897459984 0.0442876145 0.0881204966 0.1466407627 0.0460597415 0.2343580000 960712937 0 402718720 -0.0353778489 0.1390057653 0.0147420755 693 1305031252.6221249104 0.0461345240 0.0880599107 0.1466407627 0.0460342848 0.2385110000 960715897 0 402718720 -0.0322017334 0.1416488290 0.0203109514 694 1305031252.6578559875 0.0486268662 0.0880030908 0.1466407627 0.0460151877 0.2365530000 960718857 0 402718720 -0.0311237350 0.1411206424 0.0214427467 695 1305031252.6889979839 0.0502785370 0.0879488109 0.1466407627 0.0460290875 0.2356570000 960721705 0 402718720 -0.0303214099 0.1392527521 0.0233737212 696 1305031252.7216539383 0.0506943576 0.0878952843 0.1466407627 0.0461064824 0.2462150000 960724609 0 402718720 -0.0347963758 0.1380232871 0.0204705764 697 1305031252.7578220367 0.0525825992 0.0878446205 0.1466407627 0.0462120797 0.2598300000 960727681 0 402718720 -0.0337264538 0.1307355911 0.0178826693 698 1305031252.7896919250 0.0528973900 0.0877945529 0.1466407627 0.0463244101 0.2430840000 960730529 0 402718720 -0.0379241556 0.1260155588 0.0108799171 699 1305031252.8224050999 0.0537003651 0.0877457772 0.1466407627 0.0464181042 0.2420330000 960733489 0 402718720 -0.0454023071 0.1230181009 0.0027660942 700 1305031252.8539779186 0.0562890656 0.0877008390 0.1466407627 0.0464095349 0.2344730000 960736281 0 402718720 -0.0443863757 0.1167188957 0.0000729152 701 1305031252.8897290230 0.0585071482 0.0876591933 0.1466407627 0.0464389972 0.2447490000 960739297 0 402718720 -0.0441750139 0.1138838902 -0.0015052794 702 1305031252.9206719398 0.0602187142 0.0876201043 0.1466407627 0.0464477166 0.2359380000 960742201 0 402718720 -0.0477265716 0.1092190072 -0.0050010146 703 1305031252.9578649998 0.0621462055 0.0875838683 0.1466407627 0.0465229772 0.2503330000 960745329 0 402718720 -0.0523045659 0.1025154889 -0.0084740855 704 1305031252.9894239902 0.0640694648 0.0875504671 0.1466407627 0.0465768779 0.2433400000 960748121 0 402718720 -0.0584995672 0.0974452794 -0.0119584510 705 1305031253.0196959972 0.0658445954 0.0875196787 0.1466407627 0.0466466608 0.2718430000 960751025 0 402718720 -0.0652654991 0.0925254822 -0.0151423933 706 1305031253.0574259758 0.0705871955 0.0874956950 0.1466407627 0.0466854885 0.2449880000 960754097 0 402718720 -0.0723047927 0.0838227719 -0.0199985914 707 1305031253.0895500183 0.0727369338 0.0874748198 0.1466407627 0.0467213988 0.2552100000 960756945 0 402718720 -0.0735320672 0.0783156157 -0.0216869637 708 1305031253.1197240353 0.0774705559 0.0874606895 0.1466407627 0.0467338836 0.2427120000 960759849 0 402718720 -0.0762476400 0.0720425472 -0.0249038283 709 1305031253.1573839188 0.0821974799 0.0874532660 0.1466407627 0.0468125709 0.2416620000 960762865 0 402718720 -0.0834239423 0.0654093474 -0.0299439076 710 1305031253.1892180443 0.0828506351 0.0874467835 0.1466407627 0.0468384743 0.2398300000 960765713 0 402718720 -0.0886389092 0.0634356290 -0.0303607881 711 1305031253.2180271149 0.0815441012 0.0874384815 0.1466407627 0.0468280200 0.2665690000 960768617 0 402718720 -0.0903438255 0.0635137856 -0.0286999308 712 1305031253.2578470707 0.0831186548 0.0874324143 0.1466407627 0.0468070478 0.2787950000 960771745 0 402718720 -0.0936766416 0.0602864660 -0.0292516258 713 1305031253.2897419930 0.0833742097 0.0874267226 0.1466407627 0.0467778906 0.2486760000 960774593 0 402718720 -0.0922497138 0.0568409003 -0.0272606630 714 1305031253.3220069408 0.0827512965 0.0874201744 0.1466407627 0.0467535588 0.2362970000 960777553 0 402718720 -0.0866832435 0.0534075946 -0.0239515584 715 1305031253.3578300476 0.0832285136 0.0874143119 0.1466407627 0.0467259508 0.2376550000 960780513 0 402718720 -0.0805526972 0.0511116944 -0.0213185828 716 1305031253.3880970478 0.0820071921 0.0874067601 0.1466407627 0.0466937809 0.2436490000 960783361 0 402718720 -0.0791711435 0.0514880307 -0.0190189425 717 1305031253.4213519096 0.0821786672 0.0873994685 0.1466407627 0.0466627695 0.2527920000 960786321 0 402718720 -0.0777893960 0.0513073243 -0.0178682171 718 1305031253.4579629898 0.0821878687 0.0873922100 0.1466407627 0.0466321964 0.2429250000 960789337 0 402718720 -0.0772163197 0.0526689515 -0.0167373437 719 1305031253.4896900654 0.0812109783 0.0873836130 0.1466407627 0.0466002210 0.2439640000 960792241 0 402718720 -0.0798834041 0.0545181409 -0.0164160132 720 1305031253.5207340717 0.0823864713 0.0873766725 0.1466407627 0.0465700388 0.2437640000 960795145 0 402718720 -0.0801237375 0.0534146316 -0.0169342589 721 1305031253.5578539371 0.0837145224 0.0873715932 0.1466407627 0.0465397411 0.2427300000 960798161 0 402718720 -0.0823691189 0.0532974154 -0.0178576298 722 1305031253.5898048878 0.0829347298 0.0873654480 0.1466407627 0.0465117665 0.2537440000 960801065 0 402718720 -0.0869239494 0.0549961440 -0.0174296871 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 12:59:38 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 -nan 0.0975940000 955104884 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 1305031102.2112140656 0.0217167400 0.0235577850 0.0253988300 0.0240796134 0.1347620000 958783593 0 402718720 -0.0023057605 0.0007952502 0.0125142531 3 1305031102.2432110310 0.0218875688 0.0230010462 0.0253988300 0.0192100197 0.1474200000 958473801 0 402718720 -0.0037540202 0.0053057950 0.0258689355 4 1305031102.2753260136 0.0166562106 0.0214148373 0.0253988300 0.0157429415 0.1467440000 958477105 0 402718720 -0.0044969367 0.0041011656 0.0388864614 5 1305031102.3112668991 0.0125662591 0.0196451217 0.0253988300 0.0141420367 0.1333200000 958480121 0 402718720 -0.0033542537 0.0037876994 0.0516033247 6 1305031102.3432331085 0.0089150956 0.0178567840 0.0253988300 0.0148704103 0.1333180000 958483825 0 402718720 -0.0042429348 0.0023660089 0.0636258498 7 1305031102.3753290176 0.0086902948 0.0165472856 0.0253988300 0.0137453296 0.1351210000 958486673 0 402718720 -0.0045886729 0.0031365601 0.0755111203 8 1305031102.4112579823 0.0069235177 0.0153443146 0.0253988300 0.0147478336 0.1349530000 958489745 0 402718720 -0.0065046046 0.0048697554 0.0872637630 9 1305031102.4432709217 0.0075808521 0.0144817076 0.0253988300 0.0167589626 0.1468390000 958492649 0 402718720 -0.0082813120 0.0075830659 0.0996254236 10 1305031102.4753179550 0.0111134779 0.0141448847 0.0253988300 0.0160557785 0.1344330000 958497097 0 402718720 -0.0071151247 0.0112046925 0.1126651466 11 1305031102.5112190247 0.0133506507 0.0140726816 0.0253988300 0.0161420102 0.1328610000 958500113 0 402718720 -0.0073604118 0.0107376268 0.1251643747 12 1305031102.5432200432 0.0163581055 0.0142631336 0.0253988300 0.0153939531 0.1325670000 958503073 0 402718720 -0.0085551599 0.0107777212 0.1370539516 13 1305031102.5752859116 0.0188128389 0.0146131109 0.0253988300 0.0158704840 0.1326240000 958505921 0 402718720 -0.0114423363 0.0102427835 0.1486853659 14 1305031102.6112329960 0.0235428307 0.0152509480 0.0253988300 0.0167576306 0.1325870000 958508937 0 402718720 -0.0129723484 0.0076806913 0.1597711891 15 1305031102.6432650089 0.0261449702 0.0159772162 0.0261449702 0.0169593416 0.1321720000 958511841 0 402718720 -0.0159874205 0.0083160428 0.1706583351 16 1305031102.6752851009 0.0239358507 0.0164746308 0.0261449702 0.0170214630 0.1393830000 958514745 0 402718720 -0.0179077499 0.0152710006 0.1823402494 17 1305031102.7112629414 0.0265365206 0.0170665067 0.0265365206 0.0168199982 0.1449810000 958517761 0 402718720 -0.0183707699 0.0179031957 0.1947535276 18 1305031102.7432339191 0.0301269591 0.0177920874 0.0301269591 0.0164407427 0.1303980000 958523921 0 402718720 -0.0191883687 0.0194295123 0.2075116932 19 1305031102.7754719257 0.0298184808 0.0184250555 0.0301269591 0.0165115752 0.1330630000 958526769 0 402718720 -0.0187094063 0.0254282933 0.2203723490 20 1305031102.8112320900 0.0337692946 0.0191922674 0.0337692946 0.0161415623 0.1293520000 958529785 0 402718720 -0.0199238900 0.0273337010 0.2330044806 21 1305031102.8432900906 0.0353444330 0.0199614182 0.0353444330 0.0157427444 0.1292230000 958532745 0 402718720 -0.0219708309 0.0307043791 0.2455422729 22 1305031102.8753631115 0.0382998846 0.0207949848 0.0382998846 0.0154377200 0.1268780000 958535593 0 402718720 -0.0247216690 0.0325039700 0.2572772503 23 1305031102.9111850262 0.0411002412 0.0216778221 0.0411002412 0.0151347506 0.1268190000 958538609 0 402718720 -0.0272424556 0.0351259895 0.2687966824 24 1305031102.9432289600 0.0426373780 0.0225511369 0.0426373780 0.0152291379 0.1387670000 958541569 0 402718720 -0.0292217340 0.0386299901 0.2801072896 25 1305031102.9752030373 0.0453506447 0.0234631172 0.0453506447 0.0162018326 0.1258350000 958544361 0 402718720 -0.0328906141 0.0411665291 0.2913641036 26 1305031103.0112149715 0.0483040065 0.0244185360 0.0483040065 0.0158894760 0.1256120000 958547433 0 402718720 -0.0335344523 0.0442040488 0.3029482961 27 1305031103.0432269573 0.0512413792 0.0254119747 0.0512413792 0.0155941973 0.1363150000 958550393 0 402718720 -0.0334231555 0.0471101142 0.3143698871 28 1305031103.0753190517 0.0541891977 0.0264397326 0.0541891977 0.0159712305 0.1246690000 958553241 0 402718720 -0.0323140547 0.0496934205 0.3251507878 29 1305031103.1112399101 0.0580520108 0.0275298112 0.0580520108 0.0159053624 0.1250460000 958556257 0 402718720 -0.0319543891 0.0512614660 0.3349368870 30 1305031103.1433179379 0.0572034083 0.0285189311 0.0580520108 0.0156648339 0.1290660000 958559161 0 402718720 -0.0317797475 0.0575091802 0.3443075716 31 1305031103.1754519939 0.0596270598 0.0295224191 0.0596270598 0.0154236336 0.1241670000 958562065 0 402718720 -0.0325600877 0.0595759377 0.3532643914 32 1305031103.2112200260 0.0603760220 0.0304865942 0.0603760220 0.0161097077 0.1241390000 958565081 0 402718720 -0.0330633298 0.0643611029 0.3620283902 33 1305031103.2432160378 0.0616957359 0.0314323258 0.0616957359 0.0158962815 0.1302390000 958568041 0 402718720 -0.0329675749 0.0682079196 0.3710325658 34 1305031103.2753698826 0.0645278096 0.0324057224 0.0645278096 0.0160676954 0.1419680000 958577289 0 402718720 -0.0328823179 0.0698047727 0.3792882860 35 1305031103.3112099171 0.0699869618 0.0334794721 0.0699869618 0.0166337761 0.1243150000 958580305 0 402718720 -0.0339866765 0.0672905818 0.3866483569 36 1305031103.3432230949 0.0762722492 0.0346681603 0.0762722492 0.0173796281 0.1235970000 958583265 0 402718720 -0.0338200890 0.0623863190 0.3917612433 37 1305031103.3753271103 0.0769594535 0.0358111682 0.0769594535 0.0173537612 0.1152120000 958586113 0 402718720 -0.0325151496 0.0623947643 0.3943503499 38 1305031103.4112598896 0.0775272548 0.0369089600 0.0775272548 0.0172791538 0.1147420000 958589129 0 402718720 -0.0310768262 0.0614210404 0.3950700164 39 1305031103.4432799816 0.0794976726 0.0380009783 0.0794976726 0.0171883674 0.1242870000 958592089 0 402718720 -0.0316814296 0.0579462610 0.3937083185 40 1305031103.4752740860 0.0805305764 0.0390642182 0.0805305764 0.0169930650 0.1146480000 958594937 0 402718720 -0.0316944122 0.0543985553 0.3908637464 41 1305031103.5113329887 0.0843516141 0.0401687888 0.0843516141 0.0169749827 0.1368020000 958597953 0 402718720 -0.0295101963 0.0473208651 0.3869644105 42 1305031103.5434439182 0.0841164812 0.0412151625 0.0843516141 0.0169006925 0.1196210000 958600913 0 402718720 -0.0293510146 0.0425349101 0.3802959025 43 1305031103.5754740238 0.0832295418 0.0421922411 0.0843516141 0.0167489848 0.1201610000 958603761 0 402718720 -0.0287705213 0.0377188437 0.3721597493 44 1305031103.6112229824 0.0809803158 0.0430737882 0.0843516141 0.0166629830 0.1305970000 958606777 0 402718720 -0.0275119524 0.0346991904 0.3629988730 45 1305031103.6434450150 0.0791871771 0.0438763080 0.0843516141 0.0164815390 0.1207800000 958609737 0 402718720 -0.0264321808 0.0302144773 0.3532446325 46 1305031103.6755230427 0.0770627186 0.0445977517 0.0843516141 0.0163567630 0.1194780000 958612585 0 402718720 -0.0242245048 0.0260954257 0.3428208530 47 1305031103.7116100788 0.0747818500 0.0452399665 0.0843516141 0.0161975579 0.1195990000 958615601 0 402718720 -0.0218416415 0.0223269407 0.3316753507 48 1305031103.7433259487 0.0722394213 0.0458024552 0.0843516141 0.0160763641 0.1192340000 958618561 0 402718720 -0.0195341576 0.0181590337 0.3199526966 49 1305031103.7753419876 0.0699818954 0.0462959131 0.0843516141 0.0159091771 0.1305910000 958621409 0 402718720 -0.0184666105 0.0126630887 0.3073974848 50 1305031103.8112421036 0.0666939914 0.0467038747 0.0843516141 0.0161653571 0.1301120000 958624425 0 402718720 -0.0173591729 0.0103701288 0.2941682935 51 1305031103.8432509899 0.0629464537 0.0470223566 0.0843516141 0.0161904717 0.1188030000 958627385 0 402718720 -0.0156319551 0.0082206884 0.2813559175 52 1305031103.8753609657 0.0604459979 0.0472805036 0.0843516141 0.0161755198 0.1207390000 958630233 0 402718720 -0.0159526560 0.0048955758 0.2690958977 53 1305031103.9112210274 0.0644291639 0.0476040632 0.0843516141 0.0172107061 0.1256120000 958633249 0 402718720 -0.0159313325 -0.0061005354 0.2567032576 54 1305031103.9432110786 0.0645969287 0.0479187459 0.0843516141 0.0171138835 0.1413910000 958636209 0 402718720 -0.0140226353 -0.0137273101 0.2432524264 55 1305031103.9753730297 0.0611764975 0.0481597959 0.0843516141 0.0170817274 0.1254570000 958639113 0 402718720 -0.0130809210 -0.0169747006 0.2288467884 56 1305031104.0112318993 0.0606411472 0.0483826772 0.0843516141 0.0172874547 0.1290770000 958642073 0 402718720 -0.0109916236 -0.0223523825 0.2144795060 57 1305031104.0432488918 0.0579731092 0.0485509304 0.0843516141 0.0172445456 0.1299920000 958645033 0 402718720 -0.0079984898 -0.0279638954 0.1995942593 58 1305031104.0754249096 0.0522295199 0.0486143544 0.0843516141 0.0172708112 0.1311100000 958647881 0 402718720 -0.0055038636 -0.0290002320 0.1839388013 59 1305031104.1112349033 0.0477046184 0.0485989351 0.0843516141 0.0171868575 0.1369070000 958650897 0 402718720 -0.0059483224 -0.0298094563 0.1689575911 60 1305031104.1432299614 0.0440633595 0.0485233422 0.0843516141 0.0171366008 0.1296770000 958653857 0 402718720 -0.0059392331 -0.0349297523 0.1544958502 61 1305031104.1754240990 0.0402033329 0.0483869486 0.0843516141 0.0170884161 0.1310160000 958656705 0 402718720 -0.0061297333 -0.0383743532 0.1403324008 62 1305031104.2112829685 0.0389930792 0.0482354346 0.0843516141 0.0169941251 0.1312280000 958659721 0 402718720 -0.0060025617 -0.0408116132 0.1266985536 63 1305031104.2431960106 0.0354482904 0.0480324640 0.0843516141 0.0168770770 0.1337560000 958662681 0 402718720 -0.0054260911 -0.0440081432 0.1132615879 64 1305031104.2755460739 0.0320889987 0.0477833474 0.0843516141 0.0167527871 0.1462240000 958665529 0 402718720 -0.0035200051 -0.0459763594 0.1003668606 65 1305031104.3112189770 0.0310970228 0.0475266347 0.0843516141 0.0166666932 0.1362920000 958668545 0 402718720 -0.0023556454 -0.0472305976 0.0876713544 66 1305031104.3433420658 0.0276555642 0.0472255579 0.0843516141 0.0165924639 0.1356950000 958684305 0 402718720 -0.0005672910 -0.0477924049 0.0755094439 67 1305031104.3758370876 0.0267677810 0.0469202179 0.0843516141 0.0165414893 0.1394070000 958687153 0 402718720 0.0010058978 -0.0479263477 0.0637388825 68 1305031104.4115090370 0.0244600531 0.0465899214 0.0843516141 0.0164974053 0.1393870000 958690169 0 402718720 0.0004136882 -0.0480566695 0.0525520779 69 1305031104.4432880878 0.0223911796 0.0462392150 0.0843516141 0.0164331023 0.1519830000 958693073 0 402718720 -0.0007773343 -0.0485263802 0.0420341045 70 1305031104.4754559994 0.0211682860 0.0458810588 0.0843516141 0.0163714183 0.1416310000 958695977 0 402718720 -0.0029546276 -0.0491917804 0.0323451906 71 1305031104.5113289356 0.0234451909 0.0455650607 0.0843516141 0.0164814060 0.1421930000 958698993 0 402718720 -0.0048599825 -0.0510648191 0.0231763739 72 1305031104.5433681011 0.0227856673 0.0452486802 0.0843516141 0.0164682156 0.1451570000 958701953 0 402718720 -0.0042892750 -0.0544334762 0.0135224480 73 1305031104.5753428936 0.0218482614 0.0449281266 0.0843516141 0.0165854628 0.1465310000 958704745 0 402718720 -0.0030721654 -0.0561322942 0.0035220643 74 1305031104.6113359928 0.0239821132 0.0446450723 0.0843516141 0.0173368802 0.1618510000 958707817 0 402718720 0.0006126817 -0.0595731772 -0.0078647006 75 1305031104.6432430744 0.0215344578 0.0443369308 0.0843516141 0.0173406788 0.1494530000 958710721 0 402718720 0.0049385559 -0.0626256093 -0.0213277917 76 1305031104.6755249500 0.0220474284 0.0440436479 0.0843516141 0.0172337761 0.1624660000 958713625 0 402718720 0.0072310190 -0.0575677902 -0.0354488604 77 1305031104.7112770081 0.0247456636 0.0437930247 0.0843516141 0.0174457014 0.1627840000 958716641 0 402718720 0.0099077988 -0.0553821363 -0.0497391298 78 1305031104.7432799339 0.0289808083 0.0436031245 0.0843516141 0.0173614783 0.1784480000 958719545 0 402718720 0.0121922512 -0.0504844226 -0.0638693050 79 1305031104.7753269672 0.0369258784 0.0435186024 0.0843516141 0.0172812633 0.1646860000 958722393 0 402718720 0.0165177993 -0.0438037999 -0.0759311989 80 1305031104.8114650249 0.0439408123 0.0435238800 0.0843516141 0.0172154563 0.1521480000 958725465 0 402718720 0.0193195883 -0.0379518345 -0.0862331167 81 1305031104.8432579041 0.0519549251 0.0436279670 0.0843516141 0.0171475589 0.1525460000 958728369 0 402718720 0.0240422506 -0.0313654095 -0.0943679661 82 1305031104.8753499985 0.0549043342 0.0437654837 0.0843516141 0.0171948144 0.1488240000 958731273 0 402718720 0.0243368912 -0.0282171927 -0.0995419472 83 1305031104.9115340710 0.0583387092 0.0439410647 0.0843516141 0.0171423262 0.1504980000 958734289 0 402718720 0.0247047916 -0.0240833163 -0.1022071391 84 1305031104.9432621002 0.0615292676 0.0441504481 0.0843516141 0.0170500968 0.1665410000 958737193 0 402718720 0.0257652625 -0.0204743836 -0.1023147181 85 1305031104.9752020836 0.0633897334 0.0443767926 0.0843516141 0.0170651199 0.1621350000 958740097 0 402718720 0.0259584635 -0.0173743758 -0.0996033996 86 1305031105.0112900734 0.0711371005 0.0446879590 0.0843516141 0.0171897725 0.1601800000 958743113 0 402718720 0.0252236240 -0.0070276447 -0.0932318717 87 1305031105.0433731079 0.0719605237 0.0450014367 0.0843516141 0.0171528891 0.1580670000 958746017 0 402718720 0.0233728066 -0.0036308637 -0.0854468644 88 1305031105.0753200054 0.0686356872 0.0452700077 0.0843516141 0.0170907847 0.1595790000 958748921 0 402718720 0.0197173003 -0.0040196907 -0.0762026310 89 1305031105.1112990379 0.0654689297 0.0454969619 0.0843516141 0.0170064146 0.1744180000 958751937 0 402718720 0.0165774133 -0.0042602061 -0.0657460466 90 1305031105.1431059837 0.0597425550 0.0456552463 0.0843516141 0.0169986201 0.1636290000 958754841 0 402718720 0.0114508532 -0.0064770440 -0.0541289970 91 1305031105.1751589775 0.0609652102 0.0458234877 0.0843516141 0.0174756357 0.1684630000 958757745 0 402718720 0.0064245341 -0.0005828027 -0.0390991233 92 1305031105.2112679482 0.0563570634 0.0459379830 0.0843516141 0.0175116409 0.1657770000 958760761 0 402718720 -0.0004415491 -0.0007667008 -0.0231452547 93 1305031105.2432699203 0.0449832566 0.0459277172 0.0843516141 0.0175328227 0.1780360000 958763665 0 402718720 -0.0042134882 -0.0082226703 -0.0088812178 94 1305031105.2752881050 0.0396626592 0.0458610676 0.0843516141 0.0176867440 0.1769660000 958766569 0 402718720 -0.0092715230 -0.0089451550 0.0063885329 95 1305031105.3112900257 0.0328757688 0.0457243803 0.0843516141 0.0176831595 0.1676560000 958769585 0 402718720 -0.0140336351 -0.0108327158 0.0219276380 96 1305031105.3433020115 0.0242539551 0.0455007300 0.0843516141 0.0176244312 0.1775630000 958772489 0 402718720 -0.0159273259 -0.0148829911 0.0370038189 97 1305031105.3753380775 0.0154636670 0.0451910696 0.0843516141 0.0178103659 0.1659270000 958775393 0 402718720 -0.0153716737 -0.0195592903 0.0510122180 98 1305031105.4112861156 0.0111258933 0.0448434657 0.0843516141 0.0178438822 0.1652390000 958778409 0 402718720 -0.0155107724 -0.0197450910 0.0650518611 99 1305031105.4433159828 0.0103657190 0.0444952056 0.0843516141 0.0177571582 0.1777510000 958781313 0 402718720 -0.0177360456 -0.0156764854 0.0793025047 100 1305031105.4752800465 0.0058218292 0.0441084719 0.0843516141 0.0177007997 0.1624190000 958784217 0 402718720 -0.0180914812 -0.0178499799 0.0931710750 101 1305031105.5113320351 0.0056544277 0.0437277388 0.0843516141 0.0176822862 0.1617320000 958787233 0 402718720 -0.0189603064 -0.0165434144 0.1070447713 102 1305031105.5432820320 0.0074020331 0.0433716044 0.0843516141 0.0176242588 0.1595060000 958790137 0 402718720 -0.0190506522 -0.0153441504 0.1209909916 103 1305031105.5754489899 0.0092577506 0.0430404019 0.0843516141 0.0175458560 0.1556470000 958793041 0 402718720 -0.0208870173 -0.0154904565 0.1345148683 104 1305031105.6113779545 0.0114404410 0.0427365562 0.0843516141 0.0174672981 0.1538200000 958796057 0 402718720 -0.0223339573 -0.0138699161 0.1482210010 105 1305031105.6432731152 0.0156632159 0.0424787148 0.0843516141 0.0174402799 0.1532140000 958798961 0 402718720 -0.0232769642 -0.0142893502 0.1620735377 106 1305031105.6751658916 0.0176888201 0.0422448479 0.0843516141 0.0174084715 0.1524740000 958801865 0 402718720 -0.0243863240 -0.0118005173 0.1762215197 107 1305031105.7113089561 0.0204368234 0.0420410346 0.0843516141 0.0175056330 0.1508560000 958804881 0 402718720 -0.0237822775 -0.0092075579 0.1898148358 108 1305031105.7433118820 0.0240181386 0.0418741559 0.0843516141 0.0174357963 0.1516080000 958807785 0 402718720 -0.0244927257 -0.0084016724 0.2035883218 109 1305031105.7753388882 0.0228555147 0.0416996730 0.0843516141 0.0173644478 0.1877490000 958810689 0 402718720 -0.0250576511 -0.0026152472 0.2174204439 110 1305031105.8112831116 0.0271789432 0.0415676663 0.0843516141 0.0173010254 0.1510500000 958813705 0 402718720 -0.0253089946 -0.0012890660 0.2311413586 111 1305031105.8432710171 0.0292847008 0.0414570090 0.0843516141 0.0172254590 0.1511310000 958816609 0 402718720 -0.0261256378 0.0016561889 0.2449380755 112 1305031105.8753368855 0.0303242728 0.0413576096 0.0843516141 0.0171745389 0.1538410000 958819513 0 402718720 -0.0254631694 0.0061510983 0.2584494948 113 1305031105.9112620354 0.0318376608 0.0412733622 0.0843516141 0.0172065683 0.1531440000 958822529 0 402718720 -0.0252320394 0.0121600768 0.2724471688 114 1305031105.9432721138 0.0345094390 0.0412140296 0.0843516141 0.0171454360 0.1571360000 958825433 0 402718720 -0.0243734773 0.0155545576 0.2857045829 115 1305031105.9753289223 0.0363556780 0.0411717830 0.0843516141 0.0171212099 0.1452530000 958828337 0 402718720 -0.0249776412 0.0204225015 0.2985693514 116 1305031106.0112850666 0.0404299311 0.0411653877 0.0843516141 0.0170690578 0.1411570000 958831353 0 402718720 -0.0245287418 0.0242122877 0.3113259077 117 1305031106.0433549881 0.0425808020 0.0411774853 0.0843516141 0.0169982192 0.1423700000 958834313 0 402718720 -0.0252162386 0.0283883959 0.3236014247 118 1305031106.0753300190 0.0460299179 0.0412186076 0.0843516141 0.0169374341 0.1349270000 958837161 0 402718720 -0.0253933445 0.0315933414 0.3356228471 119 1305031106.1113269329 0.0489021763 0.0412831754 0.0843516141 0.0169357154 0.1502570000 958840177 0 402718720 -0.0290008131 0.0360580422 0.3470176756 120 1305031106.1433548927 0.0507292561 0.0413618928 0.0843516141 0.0168720225 0.1330470000 958843137 0 402718720 -0.0296084713 0.0403413065 0.3585250974 121 1305031106.1755340099 0.0559870861 0.0414827621 0.0843516141 0.0168060752 0.1298540000 958845985 0 402718720 -0.0310560949 0.0410775170 0.3694925904 122 1305031106.2112751007 0.0601231530 0.0416355522 0.0843516141 0.0167409128 0.1285260000 958849001 0 402718720 -0.0325512141 0.0429710224 0.3793535829 123 1305031106.2432670593 0.0652063712 0.0418271849 0.0843516141 0.0166768791 0.1261580000 958851961 0 402718720 -0.0339264683 0.0430588201 0.3884106576 124 1305031106.2763850689 0.0673740357 0.0420332079 0.0843516141 0.0166163350 0.1420000000 958854865 0 402718720 -0.0344957113 0.0458907671 0.3960981965 125 1305031106.3112380505 0.0675287992 0.0422371726 0.0843516141 0.0165634191 0.1258490000 958857825 0 402718720 -0.0343110673 0.0499699600 0.4029962420 126 1305031106.3432579041 0.0690483451 0.0424499597 0.0843516141 0.0165864394 0.1262700000 958860785 0 402718720 -0.0341830775 0.0524583496 0.4091720283 127 1305031106.3753879070 0.0688119903 0.0426575347 0.0843516141 0.0166155029 0.1211940000 958863633 0 402718720 -0.0350606665 0.0556927994 0.4137851894 128 1305031106.4113199711 0.0698839948 0.0428702415 0.0843516141 0.0166607997 0.1305300000 958866649 0 402718720 -0.0356450975 0.0565413348 0.4166495800 129 1305031106.4432780743 0.0806433707 0.0431630564 0.0843516141 0.0168395497 0.1261060000 958869553 0 402718720 -0.0368295833 0.0455781147 0.4185365438 130 1305031106.4753448963 0.0812873617 0.0434563203 0.0843516141 0.0169003453 0.1173380000 958898057 0 402718720 -0.0386429466 0.0434111208 0.4162029922 131 1305031106.5111289024 0.0820877478 0.0437512167 0.0843516141 0.0169152519 0.1180240000 958900905 0 402718720 -0.0403431021 0.0400447771 0.4119934738 132 1305031106.5433020592 0.0857106745 0.0440690914 0.0857106745 0.0168792158 0.1256130000 958903865 0 402718720 -0.0394623354 0.0323106758 0.4062029123 133 1305031106.5752820969 0.0840125978 0.0443694185 0.0857106745 0.0168306751 0.1253960000 958906713 0 402718720 -0.0379215851 0.0291600619 0.3976015449 134 1305031106.6111509800 0.0816153958 0.0446473735 0.0857106745 0.0168497614 0.1310360000 958909729 0 402718720 -0.0380893499 0.0266206414 0.3877225220 135 1305031106.6432070732 0.0797640905 0.0449074974 0.0857106745 0.0168250258 0.1217340000 958912689 0 402718720 -0.0379323550 0.0232570823 0.3773937821 136 1305031106.6752789021 0.0812138617 0.0451744559 0.0857106745 0.0167856277 0.1370780000 958915537 0 402718720 -0.0375201777 0.0159650426 0.3662348092 137 1305031106.7115080357 0.0789229795 0.0454207955 0.0857106745 0.0168060859 0.1211210000 958918553 0 402718720 -0.0369153433 0.0135939941 0.3534585536 138 1305031106.7433409691 0.0789844915 0.0456640107 0.0857106745 0.0168006269 0.1249440000 958921513 0 402718720 -0.0361982770 0.0075017144 0.3408180475 139 1305031106.7753899097 0.0776136890 0.0458938645 0.0857106745 0.0167450440 0.1245100000 958924361 0 402718720 -0.0346230380 0.0030056452 0.3272843361 140 1305031106.8112890720 0.0760531947 0.0461092883 0.0857106745 0.0167118869 0.1246740000 958927377 0 402718720 -0.0323602296 -0.0000338218 0.3128831387 141 1305031106.8434159756 0.0731819570 0.0463012930 0.0857106745 0.0166895742 0.1259080000 958930281 0 402718720 -0.0303611699 -0.0029954950 0.2983025610 142 1305031106.8759050369 0.0740339607 0.0464965935 0.0857106745 0.0168350639 0.1252280000 958933185 0 402718720 -0.0298202578 -0.0117412703 0.2829798460 143 1305031106.9112429619 0.0718604550 0.0466739632 0.0857106745 0.0168461102 0.1245050000 958936201 0 402718720 -0.0286772046 -0.0151198637 0.2656100094 144 1305031106.9434390068 0.0650699735 0.0468017133 0.0857106745 0.0168034534 0.1323420000 958939105 0 402718720 -0.0279500745 -0.0154383108 0.2478880286 145 1305031106.9755470753 0.0638693273 0.0469194209 0.0857106745 0.0168076656 0.1251110000 958942009 0 402718720 -0.0291192010 -0.0228684451 0.2305241674 146 1305031107.0115759373 0.0619506761 0.0470223747 0.0857106745 0.0167739120 0.1279840000 958945081 0 402718720 -0.0303739421 -0.0279690959 0.2122172564 147 1305031107.0432810783 0.0525618494 0.0470600582 0.0857106745 0.0167995399 0.1496870000 958947985 0 402718720 -0.0292000808 -0.0245275665 0.1940847486 148 1305031107.0754320621 0.0503749996 0.0470824565 0.0857106745 0.0168415873 0.1294090000 958950833 0 402718720 -0.0304365605 -0.0309185181 0.1777971238 149 1305031107.1112289429 0.0499266163 0.0471015448 0.0857106745 0.0167918326 0.1500730000 958953849 0 402718720 -0.0311714374 -0.0362931117 0.1613505483 150 1305031107.1432600021 0.0437917560 0.0470794796 0.0857106745 0.0167843814 0.1326300000 958956809 0 402718720 -0.0289672539 -0.0358387940 0.1453345418 151 1305031107.1753990650 0.0392624736 0.0470277113 0.0857106745 0.0167385389 0.1294630000 958959657 0 402718720 -0.0281135943 -0.0372417979 0.1305052042 152 1305031107.2113580704 0.0406642370 0.0469858463 0.0857106745 0.0168224334 0.1303270000 958962673 0 402718720 -0.0286523476 -0.0437580161 0.1161205173 153 1305031107.2433779240 0.0365156420 0.0469174136 0.0857106745 0.0167768136 0.1350100000 958965577 0 402718720 -0.0272044297 -0.0467557684 0.1016027555 154 1305031107.2753980160 0.0321494676 0.0468215179 0.0857106745 0.0167352732 0.1456410000 958968481 0 402718720 -0.0248508342 -0.0473024473 0.0877713412 155 1305031107.3112258911 0.0314560197 0.0467223856 0.0857106745 0.0167206852 0.1390730000 958971497 0 402718720 -0.0255110338 -0.0501591004 0.0740697533 156 1305031107.3435089588 0.0280891545 0.0466029418 0.0857106745 0.0167810148 0.1419890000 958974457 0 402718720 -0.0258370768 -0.0538935885 0.0605076924 157 1305031107.3754129410 0.0234819297 0.0464556742 0.0857106745 0.0168334409 0.1493480000 958977305 0 402718720 -0.0242100712 -0.0538663678 0.0478172600 158 1305031107.4112710953 0.0200334769 0.0462884451 0.0857106745 0.0168128604 0.1529470000 958980321 0 402718720 -0.0198841058 -0.0501936413 0.0375713892 159 1305031107.4434189796 0.0173008945 0.0461061335 0.0857106745 0.0167637534 0.1663040000 958983281 0 402718720 -0.0179562904 -0.0486505404 0.0294734072 160 1305031107.4753770828 0.0179645959 0.0459302489 0.0857106745 0.0167222290 0.1519240000 958986185 0 402718720 -0.0160955843 -0.0466312207 0.0237386487 161 1305031107.5113520622 0.0207692068 0.0457739691 0.0857106745 0.0166995812 0.1520860000 958989145 0 402718720 -0.0141312955 -0.0449154079 0.0198331531 162 1305031107.5436050892 0.0243263748 0.0456415766 0.0857106745 0.0167171404 0.1524730000 958992105 0 402718720 -0.0125267748 -0.0410168320 0.0183267053 163 1305031107.5754539967 0.0246961676 0.0455130771 0.0857106745 0.0166914391 0.1532530000 958994953 0 402718720 -0.0099938754 -0.0408121943 0.0177773833 164 1305031107.6112709045 0.0230959281 0.0453763872 0.0857106745 0.0166522379 0.1647520000 958997969 0 402718720 -0.0074545355 -0.0419108346 0.0176817439 165 1305031107.6433229446 0.0229187571 0.0452402804 0.0857106745 0.0166409590 0.1536680000 959000929 0 402718720 -0.0047246977 -0.0379763469 0.0192526150 166 1305031107.6755681038 0.0220262054 0.0451004365 0.0857106745 0.0166117096 0.1506690000 959003777 0 402718720 -0.0038107911 -0.0369750969 0.0209289603 167 1305031107.7113070488 0.0207501333 0.0449546263 0.0857106745 0.0165698936 0.1531550000 959006793 0 402718720 -0.0039309375 -0.0360919647 0.0229395609 168 1305031107.7435379028 0.0208332222 0.0448110465 0.0857106745 0.0165510766 0.1534110000 959009697 0 402718720 -0.0041261455 -0.0333196409 0.0254046116 169 1305031107.7758018970 0.0209046435 0.0446695885 0.0857106745 0.0165092706 0.1663540000 959012601 0 402718720 -0.0053042993 -0.0310444515 0.0278640538 170 1305031107.8115959167 0.0198580530 0.0445236383 0.0857106745 0.0164621410 0.1554520000 959015617 0 402718720 -0.0052025313 -0.0311583057 0.0303591061 171 1305031107.8433320522 0.0193511583 0.0443764308 0.0857106745 0.0164220022 0.1562280000 959018521 0 402718720 -0.0047004400 -0.0304103270 0.0328855515 172 1305031107.8753581047 0.0190030672 0.0442289113 0.0857106745 0.0164010639 0.1568270000 959021425 0 402718720 -0.0041940873 -0.0306854118 0.0349000506 173 1305031107.9115409851 0.0194072984 0.0440854338 0.0857106745 0.0163862504 0.1565100000 959024441 0 402718720 -0.0025856523 -0.0320667475 0.0364645012 174 1305031107.9431219101 0.0213397574 0.0439547115 0.0857106745 0.0163907870 0.1558840000 959027345 0 402718720 -0.0013007993 -0.0322655328 0.0377587900 175 1305031107.9758069515 0.0247243848 0.0438448239 0.0857106745 0.0163859296 0.1559170000 959030249 0 402718720 0.0022052389 -0.0315829143 0.0387560837 176 1305031108.0113201141 0.0277117323 0.0437531586 0.0857106745 0.0163550576 0.1544200000 959033265 0 402718720 0.0064699692 -0.0313027389 0.0401765592 177 1305031108.0434179306 0.0295652598 0.0436730010 0.0857106745 0.0163219418 0.1591170000 959036169 0 402718720 0.0140200555 -0.0273388214 0.0417725705 178 1305031108.0753519535 0.0317706168 0.0436061337 0.0857106745 0.0162887655 0.1562810000 959039017 0 402718720 0.0225019362 -0.0234610606 0.0437516756 179 1305031108.1113779545 0.0408068746 0.0435904953 0.0857106745 0.0162510624 0.1619190000 959042033 0 402718720 0.0269354042 -0.0240077935 0.0458034724 180 1305031108.1433339119 0.0440166704 0.0435928630 0.0857106745 0.0162245464 0.1784530000 959044937 0 402718720 0.0350511707 -0.0223249812 0.0484963655 181 1305031108.1760580540 0.0491769724 0.0436237144 0.0857106745 0.0162708381 0.1543020000 959047841 0 402718720 0.0454736240 -0.0179897957 0.0516890660 182 1305031108.2114748955 0.0522627123 0.0436711814 0.0857106745 0.0162715427 0.1534390000 959050857 0 402718720 0.0541209467 -0.0140003432 0.0559754819 183 1305031108.2433469296 0.0526507907 0.0437202503 0.0857106745 0.0162783633 0.1541150000 959053761 0 402718720 0.0642089397 -0.0173716415 0.0592068322 184 1305031108.2753579617 0.0524658449 0.0437677807 0.0857106745 0.0162369810 0.1682870000 959056665 0 402718720 0.0752660632 -0.0205956995 0.0618834160 185 1305031108.3113319874 0.0577568412 0.0438433973 0.0857106745 0.0163836923 0.1545800000 959059681 0 402718720 0.0843673050 -0.0150043741 0.0656092986 186 1305031108.3432779312 0.0587894320 0.0439237523 0.0857106745 0.0163676696 0.1534110000 959062641 0 402718720 0.0937194526 -0.0122768208 0.0696201101 187 1305031108.3754100800 0.0576478355 0.0439971431 0.0857106745 0.0163400588 0.1542750000 959065489 0 402718720 0.1052022427 -0.0119700124 0.0733150691 188 1305031108.4113609791 0.0599554107 0.0440820275 0.0857106745 0.0163032934 0.1550200000 959068505 0 402718720 0.1170867458 -0.0127907842 0.0769018456 189 1305031108.4436099529 0.0574469604 0.0441527415 0.0857106745 0.0163139063 0.1662300000 959071465 0 402718720 0.1308010817 -0.0141516384 0.0798601806 190 1305031108.4754710197 0.0569056869 0.0442198622 0.0857106745 0.0163190757 0.1642940000 959074313 0 402718720 0.1428441852 -0.0151098175 0.0824381337 191 1305031108.5113780499 0.0607849099 0.0443065902 0.0857106745 0.0165833371 0.1513770000 959077329 0 402718720 0.1550205052 -0.0179355443 0.0836044550 192 1305031108.5437369347 0.0626105294 0.0444019232 0.0857106745 0.0166165898 0.1511040000 959080289 0 402718720 0.1656245738 -0.0203749221 0.0835102275 193 1305031108.5754139423 0.0648469925 0.0445078562 0.0857106745 0.0166507113 0.1630960000 959083137 0 402718720 0.1750174016 -0.0192068461 0.0840795711 194 1305031108.6114070415 0.0708675236 0.0446437308 0.0857106745 0.0166438822 0.1654030000 959086153 0 402718720 0.1828559488 -0.0119182458 0.0853739306 195 1305031108.6433029175 0.0732730180 0.0447905477 0.0857106745 0.0166141269 0.1502790000 959089113 0 402718720 0.1919323355 -0.0115456702 0.0865745693 196 1305031108.6753749847 0.0753887743 0.0449466611 0.0857106745 0.0166138216 0.1608420000 959091961 0 402718720 0.2004451007 -0.0074123805 0.0883338004 197 1305031108.7114109993 0.0796362907 0.0451227506 0.0857106745 0.0166245549 0.1596930000 959094921 0 402718720 0.2096021920 -0.0047577014 0.0897789896 198 1305031108.7435019016 0.0818423852 0.0453082033 0.0857106745 0.0165989977 0.1584740000 959097881 0 402718720 0.2174225748 -0.0059984461 0.0906050950 199 1305031108.7754929066 0.0824779943 0.0454949861 0.0857106745 0.0165593003 0.1557140000 959100729 0 402718720 0.2254134417 -0.0061677354 0.0910275057 200 1305031108.8112440109 0.0835493580 0.0456852580 0.0857106745 0.0165204664 0.1453440000 959103745 0 402718720 0.2334693223 -0.0047542932 0.0910753608 201 1305031108.8432641029 0.0840447024 0.0458761010 0.0857106745 0.0179451120 0.1445280000 959106705 0 402718720 0.2407855839 -0.0054905401 0.0900119841 202 1305031108.8765149117 0.0771489143 0.0460309169 0.0857106745 0.0179765799 0.1450820000 959109609 0 402718720 0.2479039282 -0.0059595169 0.0880734921 203 1305031108.9113640785 0.0719912574 0.0461588004 0.0857106745 0.0180625377 0.1453690000 959112569 0 402718720 0.2532479167 -0.0060200514 0.0856444314 204 1305031108.9432430267 0.0706928000 0.0462790651 0.0857106745 0.0181271534 0.1618480000 959115529 0 402718720 0.2557388842 -0.0095872525 0.0825040489 205 1305031108.9752678871 0.0692420006 0.0463910794 0.0857106745 0.0181066448 0.1448150000 959118433 0 402718720 0.2544662058 -0.0103598665 0.0800196454 206 1305031109.0112690926 0.0619447753 0.0464665828 0.0857106745 0.0180815062 0.1523270000 959121393 0 402718720 0.2544865012 -0.0053354329 0.0780541003 207 1305031109.0432770252 0.0595762357 0.0465299144 0.0857106745 0.0180588556 0.1576820000 959124353 0 402718720 0.2510629892 -0.0075165033 0.0761541873 208 1305031109.0754098892 0.0584187806 0.0465870724 0.0857106745 0.0180525759 0.1475940000 959127201 0 402718720 0.2451572269 -0.0080364496 0.0749036595 209 1305031109.1112821102 0.0531216785 0.0466183385 0.0857106745 0.0180271798 0.1531950000 959130217 0 402718720 0.2381330729 -0.0042679226 0.0746900439 210 1305031109.1433339119 0.0505356453 0.0466369923 0.0857106745 0.0180052630 0.1495200000 959133177 0 402718720 0.2316147089 -0.0073827454 0.0737171024 211 1305031109.1754639149 0.0489363037 0.0466478895 0.0857106745 0.0180150415 0.1538910000 959136025 0 402718720 0.2233616859 -0.0091193086 0.0729506612 212 1305031109.2113790512 0.0418624841 0.0466253169 0.0857106745 0.0180214832 0.1680460000 959139041 0 402718720 0.2152830213 -0.0052914806 0.0735263675 213 1305031109.2432899475 0.0376590565 0.0465832217 0.0857106745 0.0179866263 0.1700440000 959142001 0 402718720 0.2074978352 -0.0028746517 0.0752128214 214 1305031109.2753078938 0.0371639654 0.0465392065 0.0857106745 0.0181023922 0.1719850000 959144849 0 402718720 0.1973318756 -0.0069682263 0.0754671022 215 1305031109.3113288879 0.0341609009 0.0464816330 0.0857106745 0.0181693742 0.1548180000 959147865 0 402718720 0.1865650862 -0.0130931372 0.0746768713 216 1305031109.3432478905 0.0300955437 0.0464057715 0.0857106745 0.0182025153 0.1546790000 959150825 0 402718720 0.1759045273 -0.0093427785 0.0751454532 217 1305031109.3753969669 0.0282059070 0.0463219011 0.0857106745 0.0181698392 0.1543860000 959153673 0 402718720 0.1642030925 -0.0083016548 0.0761911348 218 1305031109.4113290310 0.0251513142 0.0462247884 0.0857106745 0.0181303868 0.1539500000 959156689 0 402718720 0.1525894701 -0.0113038402 0.0762552693 219 1305031109.4433019161 0.0233390406 0.0461202872 0.0857106745 0.0181127586 0.1663220000 959159593 0 402718720 0.1409624219 -0.0095015028 0.0766923428 220 1305031109.4753630161 0.0237079374 0.0460184129 0.0857106745 0.0181017063 0.1545850000 959162441 0 402718720 0.1280703098 -0.0098379180 0.0766072348 221 1305031109.5112729073 0.0240855534 0.0459191692 0.0857106745 0.0180841486 0.1667760000 959165457 0 402718720 0.1144362614 -0.0131538613 0.0755317211 222 1305031109.5432939529 0.0260563679 0.0458296971 0.0857106745 0.0180640043 0.1529180000 959168417 0 402718720 0.1007779986 -0.0157596096 0.0736511871 223 1305031109.5753619671 0.0245554429 0.0457342969 0.0857106745 0.0180262299 0.1655070000 959171321 0 402718720 0.0890262574 -0.0142543409 0.0718024895 224 1305031109.6113100052 0.0217536781 0.0456272406 0.0857106745 0.0180106843 0.1561660000 959174281 0 402718720 0.0767022446 -0.0124476338 0.0700384751 225 1305031109.6432290077 0.0218416601 0.0455215269 0.0857106745 0.0179714075 0.1565200000 959177241 0 402718720 0.0648569167 -0.0117436219 0.0686337352 226 1305031109.6752629280 0.0203449223 0.0454101260 0.0857106745 0.0179341131 0.1560180000 959180089 0 402718720 0.0544872656 -0.0097848587 0.0679400116 227 1305031109.7113120556 0.0190781206 0.0452941259 0.0857106745 0.0179543597 0.1591600000 959183105 0 402718720 0.0429305434 -0.0083893212 0.0677997991 228 1305031109.7432739735 0.0188768432 0.0451782607 0.0857106745 0.0179155421 0.1700560000 959186065 0 402718720 0.0305372737 -0.0052459808 0.0685342103 229 1305031109.7752768993 0.0199723598 0.0450681912 0.0857106745 0.0178998106 0.1620110000 959188913 0 402718720 0.0195089877 -0.0064596082 0.0695801377 230 1305031109.8113710880 0.0200871266 0.0449595779 0.0857106745 0.0178710172 0.1506030000 959191929 0 402718720 0.0066768522 -0.0066970633 0.0705775395 231 1305031109.8432960510 0.0202528909 0.0448526225 0.0857106745 0.0178389959 0.1535890000 959194889 0 402718720 -0.0056056827 -0.0046360535 0.0721119568 232 1305031109.8753058910 0.0210231971 0.0447499095 0.0857106745 0.0178094186 0.1519420000 959197737 0 402718720 -0.0186068136 -0.0038062148 0.0745763928 233 1305031109.9112648964 0.0234032962 0.0446582931 0.0857106745 0.0177905272 0.1615110000 959200753 0 402718720 -0.0297821183 -0.0050017270 0.0770849884 234 1305031109.9432990551 0.0251749735 0.0445750311 0.0857106745 0.0177847160 0.1578780000 959203713 0 402718720 -0.0435608290 -0.0047065243 0.0803130418 235 1305031109.9752581120 0.0257204697 0.0444947989 0.0857106745 0.0177512592 0.1503520000 959206561 0 402718720 -0.0541892350 -0.0002985634 0.0837667137 236 1305031110.0112559795 0.0288474970 0.0444284968 0.0857106745 0.0177174070 0.1491630000 959209577 0 402718720 -0.0679377243 -0.0020555109 0.0872048438 237 1305031110.0432989597 0.0296726152 0.0443662357 0.0857106745 0.0176813666 0.1489130000 959212537 0 402718720 -0.0820905864 -0.0014443612 0.0906713754 238 1305031110.0753190517 0.0312166307 0.0443109852 0.0857106745 0.0176566423 0.1478950000 959215385 0 402718720 -0.0952284634 -0.0017432348 0.0942085981 239 1305031110.1113250256 0.0329599679 0.0442634914 0.0857106745 0.0176728985 0.1590320000 959218401 0 402718720 -0.1083612964 -0.0004304862 0.0977712572 240 1305031110.1434319019 0.0358492546 0.0442284321 0.0857106745 0.0177010931 0.1442010000 959221361 0 402718720 -0.1214523539 -0.0038698139 0.1013593078 241 1305031110.1756410599 0.0381970890 0.0442034058 0.0857106745 0.0176647851 0.1398920000 959224209 0 402718720 -0.1311730742 -0.0048033614 0.1042615399 242 1305031110.2116370201 0.0408138148 0.0441893992 0.0857106745 0.0176374004 0.1418500000 959227281 0 402718720 -0.1405145079 -0.0026137575 0.1069756523 243 1305031110.2433230877 0.0443013459 0.0441898599 0.0857106745 0.0176389398 0.1411300000 959230185 0 402718720 -0.1508282125 -0.0063959486 0.1095653474 244 1305031110.2793209553 0.0480974764 0.0442058747 0.0857106745 0.0176242619 0.1468560000 959233201 0 402718720 -0.1585309654 -0.0079784244 0.1107287109 245 1305031110.3114039898 0.0483550988 0.0442228103 0.0857106745 0.0175899957 0.1435050000 959236049 0 402718720 -0.1688462943 -0.0075727063 0.1112382486 246 1305031110.3433549404 0.0501986481 0.0442471024 0.0857106745 0.0175596662 0.1607530000 959238953 0 402718720 -0.1764482409 -0.0069574043 0.1117615178 247 1305031110.3792810440 0.0515904203 0.0442768324 0.0857106745 0.0175529579 0.1465890000 959241969 0 402718720 -0.1878100187 -0.0047094682 0.1119861901 248 1305031110.4114689827 0.0530374981 0.0443121577 0.0857106745 0.0175356777 0.1472330000 959244873 0 402718720 -0.1983758211 -0.0039276192 0.1126985550 249 1305031110.4432599545 0.0542031527 0.0443518805 0.0857106745 0.0175049671 0.1690480000 959247777 0 402718720 -0.2082042247 0.0005757121 0.1137396991 250 1305031110.4793310165 0.0582937673 0.0444076481 0.0857106745 0.0175365508 0.1513310000 959250849 0 402718720 -0.2195919901 0.0001713710 0.1152012348 251 1305031110.5114290714 0.0616122447 0.0444761923 0.0857106745 0.0175193455 0.1524790000 959253697 0 402718720 -0.2298264056 -0.0026685526 0.1172339246 252 1305031110.5434079170 0.0630783662 0.0445500104 0.0857106745 0.0174954871 0.1653630000 959256657 0 402718720 -0.2401196510 -0.0010566774 0.1184616759 253 1305031110.5794260502 0.0659251660 0.0446344972 0.0857106745 0.0174921806 0.1542180000 959259673 0 402718720 -0.2503983378 0.0021373646 0.1202068552 254 1305031110.6113069057 0.0676400810 0.0447250704 0.0857106745 0.0175102092 0.1542270000 959262521 0 402718720 -0.2613679171 0.0019824167 0.1223731712 255 1305031110.6434180737 0.0710765496 0.0448284095 0.0857106745 0.0175370699 0.1549600000 959265481 0 402718720 -0.2699555755 -0.0035395536 0.1245084479 256 1305031110.6796059608 0.0726767629 0.0449371922 0.0857106745 0.0175475956 0.1520490000 959268441 0 402718720 -0.2771692872 -0.0030336254 0.1246809661 257 1305031110.7114119530 0.0722079650 0.0450433041 0.0857106745 0.0175179529 0.1522230000 959271345 0 402718720 -0.2848165929 -0.0002194984 0.1251252294 258 1305031110.7432489395 0.0724938214 0.0451497015 0.0857106745 0.0175251849 0.1507690000 959325449 0 402718720 -0.2920379937 -0.0020363817 0.1259137541 259 1305031110.7791929245 0.0734976828 0.0452591531 0.0857106745 0.0174925059 0.1658060000 959328465 0 402718720 -0.2979527414 -0.0038529902 0.1264502853 260 1305031110.8113861084 0.0736735836 0.0453684394 0.0857106745 0.0174600934 0.1521670000 959331369 0 402718720 -0.3005557358 -0.0029342268 0.1268205643 261 1305031110.8432180882 0.0728300661 0.0454736564 0.0857106745 0.0174382029 0.1532040000 959334273 0 402718720 -0.3047272563 -0.0023729352 0.1271340400 262 1305031110.8793129921 0.0729035139 0.0455783505 0.0857106745 0.0174061323 0.1527470000 959337289 0 402718720 -0.3075273633 -0.0044999458 0.1274837852 263 1305031110.9113330841 0.0729514062 0.0456824305 0.0857106745 0.0173874893 0.1544210000 959340193 0 402718720 -0.3083704412 -0.0043694247 0.1283178926 264 1305031110.9438619614 0.0725801587 0.0457843159 0.0857106745 0.0173770967 0.1771470000 959343153 0 402718720 -0.3081856966 -0.0048125670 0.1288804114 265 1305031110.9793450832 0.0715493262 0.0458815423 0.0857106745 0.0174053081 0.1555980000 959346057 0 402718720 -0.3058324456 -0.0039570625 0.1294135153 266 1305031111.0114309788 0.0695953220 0.0459706919 0.0857106745 0.0173993409 0.1572140000 959349017 0 402718720 -0.3006379008 -0.0010090641 0.1292132586 267 1305031111.0433270931 0.0698642507 0.0460601809 0.0857106745 0.0173683588 0.1696760000 959351921 0 402718720 -0.2932258248 -0.0019698672 0.1293524057 268 1305031111.0792829990 0.0684882179 0.0461438676 0.0857106745 0.0173577317 0.1569320000 959354881 0 402718720 -0.2845544815 -0.0009684734 0.1293091923 269 1305031111.1115078926 0.0681355447 0.0462256210 0.0857106745 0.0173361074 0.1688810000 959357841 0 402718720 -0.2784700096 -0.0015158276 0.1296101362 270 1305031111.1432569027 0.0681620166 0.0463068669 0.0857106745 0.0173177939 0.1574850000 959360745 0 402718720 -0.2705266774 -0.0031986758 0.1293390989 271 1305031111.1793260574 0.0671431124 0.0463837534 0.0857106745 0.0173756274 0.1643700000 959363761 0 402718720 -0.2558925152 -0.0030357046 0.1286925972 272 1305031111.2114329338 0.0646816269 0.0464510250 0.0857106745 0.0173603877 0.1585490000 959366609 0 402718720 -0.2444992512 -0.0012355979 0.1268536896 273 1305031111.2432360649 0.0632046834 0.0465123937 0.0857106745 0.0173953336 0.1530380000 959369513 0 402718720 -0.2364073992 -0.0013691710 0.1262982041 274 1305031111.2793080807 0.0614473149 0.0465669007 0.0857106745 0.0174364787 0.1642970000 959372529 0 402718720 -0.2309238315 -0.0046886760 0.1253061742 275 1305031111.3115470409 0.0590129942 0.0466121593 0.0857106745 0.0174432395 0.1582730000 959375433 0 402718720 -0.2151764184 -0.0031988816 0.1238851324 276 1305031111.3433969021 0.0565994196 0.0466483450 0.0857106745 0.0175839442 0.1495390000 959378337 0 402718720 -0.2098094225 -0.0005484374 0.1239977181 277 1305031111.3791339397 0.0564081818 0.0466835791 0.0857106745 0.0176938363 0.1494360000 959381353 0 402718720 -0.2030629814 -0.0027741031 0.1238647997 278 1305031111.4112958908 0.0577639900 0.0467234367 0.0857106745 0.0176672591 0.1864340000 959384201 0 402718720 -0.1823541373 -0.0064640515 0.1247395799 279 1305031111.4433860779 0.0538922213 0.0467491312 0.0857106745 0.0176586447 0.1803020000 959387161 0 402718720 -0.1728845388 -0.0021856385 0.1239208430 280 1305031111.4792590141 0.0535019599 0.0467732485 0.0857106745 0.0181013443 0.1562690000 959390177 0 402718720 -0.1568479091 -0.0041702823 0.1240637824 281 1305031111.5112640858 0.0509715192 0.0467881889 0.0857106745 0.0181010802 0.1517730000 959393025 0 402718720 -0.1430559456 -0.0044130790 0.1219862625 282 1305031111.5432500839 0.0495888442 0.0467981203 0.0857106745 0.0180800493 0.1561500000 959395985 0 402718720 -0.1347435266 -0.0058220737 0.1202341542 283 1305031111.5792369843 0.0473197065 0.0467999634 0.0857106745 0.0181013075 0.1502230000 959399001 0 402718720 -0.1185701042 -0.0063860910 0.1182787716 284 1305031111.6112709045 0.0443662740 0.0467913941 0.0857106745 0.0181846517 0.1551060000 959401793 0 402718720 -0.1078025103 -0.0035620129 0.1170792505 285 1305031111.6433949471 0.0475182533 0.0467939445 0.0857106745 0.0182013556 0.1373570000 959404753 0 402718720 -0.1005288437 -0.0078455834 0.1168420315 286 1305031111.6793200970 0.0453457981 0.0467888810 0.0857106745 0.0184197662 0.1461810000 959407713 0 402718720 -0.0787391365 -0.0093424516 0.1157358661 287 1305031111.7117600441 0.0388180166 0.0467611080 0.0857106745 0.0184393260 0.1414910000 959410673 0 402718720 -0.0636960566 -0.0025482711 0.1140326038 288 1305031111.7433860302 0.0391651355 0.0467347331 0.0857106745 0.0185208159 0.1405200000 959413577 0 402718720 -0.0502259545 -0.0053253388 0.1130940244 289 1305031111.7794229984 0.0372808129 0.0467020205 0.0857106745 0.0186136079 0.1488100000 959416593 0 402718720 -0.0348458514 -0.0038425452 0.1118601263 290 1305031111.8114058971 0.0383190922 0.0466731139 0.0857106745 0.0186401290 0.1251810000 959419441 0 402718720 -0.0280523282 -0.0028423883 0.1106040627 291 1305031111.8432989120 0.0417443141 0.0466561764 0.0857106745 0.0186215959 0.1231710000 959422345 0 402718720 -0.0216681622 -0.0031146191 0.1091496274 292 1305031111.8794419765 0.0405220613 0.0466351692 0.0857106745 0.0186122163 0.1313190000 959425305 0 402718720 -0.0076338765 0.0015470036 0.1087139323 293 1305031111.9113540649 0.0438241139 0.0466255751 0.0857106745 0.0186346052 0.1261640000 959428265 0 402718720 0.0013847661 -0.0002717865 0.1093337089 294 1305031111.9433000088 0.0456141829 0.0466221350 0.0857106745 0.0186033733 0.1394910000 959431169 0 402718720 0.0134189408 -0.0033141305 0.1098014489 295 1305031111.9794490337 0.0450939350 0.0466169547 0.0857106745 0.0187542748 0.1335160000 959434129 0 402718720 0.0293439683 -0.0017263896 0.1100948378 296 1305031112.0114328861 0.0419278890 0.0466011132 0.0857106745 0.0187769188 0.1345980000 959437089 0 402718720 0.0430890620 0.0007526401 0.1089733317 297 1305031112.0432701111 0.0468813963 0.0466020570 0.0857106745 0.0187464393 0.1368770000 959439993 0 402718720 0.0492924079 -0.0005232390 0.1078194082 298 1305031112.0793390274 0.0505701117 0.0466153726 0.0857106745 0.0187888603 0.1310740000 959443009 0 402718720 0.0600761473 0.0012584735 0.1065474898 299 1305031112.1114230156 0.0543555245 0.0466412594 0.0857106745 0.0188447140 0.1398620000 959445857 0 402718720 0.0675483793 0.0006141202 0.1054194272 300 1305031112.1443419456 0.0568842739 0.0466754028 0.0857106745 0.0188245019 0.1343740000 959448761 0 402718720 0.0767791495 0.0014344520 0.1051049456 301 1305031112.1793899536 0.0622384585 0.0467271073 0.0857106745 0.0189017243 0.1357580000 959451665 0 402718720 0.0874846801 0.0029000903 0.1047820151 302 1305031112.2112538815 0.0674572736 0.0467957502 0.0857106745 0.0188967150 0.1369590000 959454569 0 402718720 0.0961002409 -0.0003646465 0.1047192290 303 1305031112.2433691025 0.0723494291 0.0468800858 0.0857106745 0.0189106225 0.1372340000 959457529 0 402718720 0.1056294516 -0.0066194204 0.1035505608 304 1305031112.2793529034 0.0782913938 0.0469834124 0.0857106745 0.0188944957 0.1489370000 959460489 0 402718720 0.1160525233 -0.0064401622 0.1025420055 305 1305031112.3113119602 0.0792814195 0.0470893075 0.0857106745 0.0188848021 0.1371930000 959463449 0 402718720 0.1272591054 -0.0070770727 0.1014743671 306 1305031112.3433229923 0.0789632499 0.0471934708 0.0857106745 0.0188638478 0.1387880000 959466353 0 402718720 0.1394218355 -0.0074097700 0.1001213938 307 1305031112.3793599606 0.0811040998 0.0473039288 0.0857106745 0.0188393212 0.1435070000 959469425 0 402718720 0.1517571956 -0.0043452373 0.0992460549 308 1305031112.4114420414 0.0795037970 0.0474084739 0.0857106745 0.0188205523 0.1401400000 959472273 0 402718720 0.1642729491 -0.0031443788 0.0988772437 309 1305031112.4433910847 0.0772854239 0.0475051630 0.0857106745 0.0188068499 0.1410610000 959475233 0 402718720 0.1772351116 -0.0032178105 0.0981886834 310 1305031112.4794180393 0.0786448941 0.0476056138 0.0857106745 0.0187899370 0.1424590000 959478249 0 402718720 0.1894575655 -0.0041086269 0.0972227156 311 1305031112.5115039349 0.0756518170 0.0476957945 0.0857106745 0.0187738642 0.1428640000 959481097 0 402718720 0.2013460845 -0.0027012355 0.0963490009 312 1305031112.5432119370 0.0737786293 0.0477793933 0.0857106745 0.0187563136 0.1411350000 959484001 0 402718720 0.2122623920 -0.0034460681 0.0955654457 313 1305031112.5792520046 0.0746501237 0.0478652423 0.0857106745 0.0187284727 0.1700260000 959486961 0 402718720 0.2226057798 -0.0026652350 0.0951703638 314 1305031112.6112608910 0.0725185722 0.0479437561 0.0857106745 0.0187757874 0.1603310000 959489865 0 402718720 0.2328447849 -0.0008975351 0.0949329063 315 1305031112.6432459354 0.0714196786 0.0480182828 0.0857106745 0.0188063078 0.1462590000 959492825 0 402718720 0.2409129441 0.0022737184 0.0952596590 316 1305031112.6799519062 0.0745608360 0.0481022782 0.0857106745 0.0188015747 0.1415820000 959495841 0 402718720 0.2453591079 0.0028577684 0.0955879018 317 1305031112.7112510204 0.0756564215 0.0481891998 0.0857106745 0.0187958762 0.1395070000 959498689 0 402718720 0.2486867160 0.0031744738 0.0962987170 318 1305031112.7432448864 0.0760252476 0.0482767346 0.0857106745 0.0187895024 0.1386250000 959501649 0 402718720 0.2507368028 0.0061976286 0.0978245884 319 1305031112.7793099880 0.0747702569 0.0483597864 0.0857106745 0.0187888694 0.1385600000 959504665 0 402718720 0.2519524693 0.0104322676 0.0999794304 320 1305031112.8113100529 0.0728002712 0.0484361629 0.0857106745 0.0187982839 0.1375960000 959507513 0 402718720 0.2528382242 0.0084268907 0.1008481383 321 1305031112.8432860374 0.0715711340 0.0485082344 0.0857106745 0.0188085551 0.1373700000 959510417 0 402718720 0.2515029609 0.0079989983 0.1024784520 322 1305031112.8794209957 0.0676543638 0.0485676945 0.0857106745 0.0188253359 0.1395390000 959513433 0 402718720 0.2506426573 0.0094521912 0.1041862220 323 1305031112.9114110470 0.0638051629 0.0486148693 0.0857106745 0.0187996362 0.1402600000 959516393 0 402718720 0.2500265241 0.0100170756 0.1051082015 324 1305031112.9433209896 0.0606713630 0.0486520807 0.0857106745 0.0187737313 0.1507210000 959519297 0 402718720 0.2474612296 0.0093621612 0.1055622101 325 1305031112.9792780876 0.0563410781 0.0486757391 0.0857106745 0.0187892015 0.1417650000 959522313 0 402718720 0.2435245365 0.0072183372 0.1055978164 326 1305031113.0113530159 0.0542091429 0.0486927128 0.0857106745 0.0187657381 0.1421400000 959525161 0 402718720 0.2386482954 0.0055882563 0.1054295748 327 1305031113.0432310104 0.0518323779 0.0487023142 0.0857106745 0.0187466902 0.1541380000 959528121 0 402718720 0.2319034338 0.0057004616 0.1053686962 328 1305031113.0792510509 0.0494969562 0.0487047369 0.0857106745 0.0187563229 0.1441260000 959531137 0 402718720 0.2225725502 0.0013016028 0.1043114811 329 1305031113.1113159657 0.0491567031 0.0487061106 0.0857106745 0.0187497869 0.1575530000 959533985 0 402718720 0.2140073925 -0.0033352217 0.1023715958 330 1305031113.1433060169 0.0469112024 0.0487006715 0.0857106745 0.0187338923 0.1469920000 959536945 0 402718720 0.2035198361 -0.0006149445 0.1015977263 331 1305031113.1793429852 0.0417358018 0.0486796296 0.0857106745 0.0187506105 0.1459990000 959539961 0 402718720 0.1935820580 -0.0013756177 0.1006771997 332 1305031113.2112588882 0.0426475517 0.0486614607 0.0857106745 0.0187383820 0.1460290000 959542809 0 402718720 0.1832802743 -0.0070638414 0.0987703726 333 1305031113.2432270050 0.0387092903 0.0486315743 0.0857106745 0.0187350267 0.1473940000 959545769 0 402718720 0.1732046902 -0.0058449027 0.0980714858 334 1305031113.2793118954 0.0329804420 0.0485847146 0.0857106745 0.0187538482 0.1581750000 959548729 0 402718720 0.1619511992 -0.0069904160 0.0978317112 335 1305031113.3114519119 0.0352851637 0.0485450145 0.0857106745 0.0188203300 0.1524700000 959551633 0 402718720 0.1496527493 -0.0146446172 0.0966055915 336 1305031113.3432519436 0.0318461582 0.0484953155 0.0857106745 0.0188325783 0.1514750000 959554537 0 402718720 0.1368476152 -0.0145256035 0.0953757241 337 1305031113.3793120384 0.0204832405 0.0484121936 0.0857106745 0.0188782533 0.1567250000 959557497 0 402718720 0.1238841340 -0.0078200093 0.0971065387 338 1305031113.4116249084 0.0220591724 0.0483342261 0.0857106745 0.0189005470 0.1514490000 959560457 0 402718720 0.1082246155 -0.0121820671 0.0985339805 339 1305031113.4432659149 0.0217450894 0.0482557921 0.0857106745 0.0188833850 0.1653850000 959563361 0 402718720 0.0930219665 -0.0146277184 0.0991514325 340 1305031113.4793109894 0.0167749189 0.0481632013 0.0857106745 0.0189095466 0.1577290000 959566321 0 402718720 0.0757832155 -0.0113295857 0.1013751775 341 1305031113.5115230083 0.0178281851 0.0480742423 0.0857106745 0.0188894648 0.1541030000 959569281 0 402718720 0.0602142476 -0.0129164876 0.1034032404 342 1305031113.5432419777 0.0202639904 0.0479929258 0.0857106745 0.0188825018 0.1569900000 959572185 0 402718720 0.0433422476 -0.0162185580 0.1043310612 343 1305031113.5793011189 0.0204393994 0.0479125948 0.0857106745 0.0188575791 0.1561220000 959575145 0 402718720 0.0258284118 -0.0181818381 0.1047518700 344 1305031113.6112680435 0.0204170328 0.0478326658 0.0857106745 0.0188330472 0.1649280000 959578105 0 402718720 0.0111667430 -0.0161324851 0.1059844568 345 1305031113.6432220936 0.0217568744 0.0477570838 0.0857106745 0.0188105520 0.1502350000 959581009 0 402718720 -0.0014868354 -0.0166886635 0.1066600829 346 1305031113.6792879105 0.0227387976 0.0476847766 0.0857106745 0.0187916981 0.1539640000 959584081 0 402718720 -0.0150496662 -0.0181411114 0.1071069092 347 1305031113.7119309902 0.0240270179 0.0476165986 0.0857106745 0.0187673303 0.1760370000 959586929 0 402718720 -0.0295669623 -0.0184692889 0.1071336418 348 1305031113.7435901165 0.0239039771 0.0475484589 0.0857106745 0.0187418682 0.1551660000 959589889 0 402718720 -0.0433219112 -0.0185280852 0.1073517054 349 1305031113.7793200016 0.0237542484 0.0474802807 0.0857106745 0.0187308701 0.1685610000 959592849 0 402718720 -0.0566167906 -0.0179116018 0.1077478081 350 1305031113.8112370968 0.0249504223 0.0474159097 0.0857106745 0.0187057707 0.1552590000 959595697 0 402718720 -0.0716541111 -0.0184263047 0.1087373868 351 1305031113.8432950974 0.0241805706 0.0473497121 0.0857106745 0.0186903370 0.1567600000 959598657 0 402718720 -0.0846677050 -0.0149659747 0.1095949411 352 1305031113.8792810440 0.0252637397 0.0472869679 0.0857106745 0.0187308380 0.1574430000 959601673 0 402718720 -0.0982572883 -0.0159817096 0.1106421277 353 1305031113.9112899303 0.0273124073 0.0472303827 0.0857106745 0.0187044671 0.1583610000 959604577 0 402718720 -0.1123727635 -0.0182818212 0.1117437258 354 1305031113.9432909489 0.0264960006 0.0471718110 0.0857106745 0.0186891695 0.1663470000 959607481 0 402718720 -0.1237007603 -0.0144055765 0.1122352481 355 1305031113.9792931080 0.0270734299 0.0471151958 0.0857106745 0.0186664599 0.1587570000 959610497 0 402718720 -0.1390727460 -0.0131127117 0.1129503027 356 1305031114.0112569332 0.0271061435 0.0470589906 0.0857106745 0.0186562157 0.1599040000 959613401 0 402718720 -0.1552649140 -0.0113375401 0.1138634905 357 1305031114.0433011055 0.0286301300 0.0470073692 0.0857106745 0.0186611215 0.1616510000 959616305 0 402718720 -0.1713553965 -0.0098218387 0.1155205965 358 1305031114.0792849064 0.0295255929 0.0469585374 0.0857106745 0.0186589773 0.1589000000 959619321 0 402718720 -0.1834583431 -0.0105717098 0.1167602688 359 1305031114.1112630367 0.0308424104 0.0469136457 0.0857106745 0.0186388514 0.1886760000 959622225 0 402718720 -0.1992966533 -0.0086078634 0.1187045723 360 1305031114.1432840824 0.0317331105 0.0468714775 0.0857106745 0.0186176279 0.1637990000 959625185 0 402718720 -0.2101107240 -0.0062157647 0.1204321608 361 1305031114.1793370247 0.0333165862 0.0468339294 0.0857106745 0.0186286008 0.1623640000 959628201 0 402718720 -0.2222899795 -0.0062521687 0.1222831234 362 1305031114.2113029957 0.0341230370 0.0467988164 0.0857106745 0.0186252028 0.1666920000 959631049 0 402718720 -0.2338845432 -0.0043500406 0.1239869222 363 1305031114.2433369160 0.0362495184 0.0467697550 0.0857106745 0.0186370492 0.1653920000 959633953 0 402718720 -0.2515510321 0.0018145542 0.1270691305 364 1305031114.2793900967 0.0370128639 0.0467429503 0.0857106745 0.0186898647 0.1753190000 959636969 0 402718720 -0.2632173002 -0.0007526737 0.1296809316 365 1305031114.3114290237 0.0396625437 0.0467235520 0.0857106745 0.0186703848 0.1681650000 959639873 0 402718720 -0.2736233175 0.0002722881 0.1329203099 366 1305031114.3433310986 0.0420948900 0.0467109053 0.0857106745 0.0186567014 0.1706560000 959642833 0 402718720 -0.2810991108 0.0022953423 0.1353410482 367 1305031114.3793199062 0.0446214341 0.0467052120 0.0857106745 0.0186407078 0.1845810000 959645849 0 402718720 -0.2892210484 0.0029945155 0.1373189986 368 1305031114.4113969803 0.0458696112 0.0467029413 0.0857106745 0.0186243001 0.1730500000 959648753 0 402718720 -0.2990266979 0.0020837174 0.1391302943 369 1305031114.4433450699 0.0468656309 0.0467033822 0.0857106745 0.0186153232 0.1747430000 959651657 0 402718720 -0.3108442426 0.0016909040 0.1413880736 370 1305031114.4793319702 0.0487957001 0.0467090371 0.0857106745 0.0186245361 0.1768030000 959654673 0 402718720 -0.3202874959 0.0002513203 0.1436347514 371 1305031114.5112659931 0.0501237400 0.0467182412 0.0857106745 0.0186026924 0.1939740000 959657521 0 402718720 -0.3289442956 -0.0007921200 0.1466086954 372 1305031114.5432360172 0.0521676317 0.0467328901 0.0857106745 0.0185885813 0.1811050000 959660481 0 402718720 -0.3342571557 0.0002006483 0.1492923200 373 1305031114.5792369843 0.0532132313 0.0467502636 0.0857106745 0.0185697844 0.1776340000 959663497 0 402718720 -0.3395007849 -0.0032988836 0.1511956453 374 1305031114.6113910675 0.0541949905 0.0467701693 0.0857106745 0.0185512483 0.1896490000 959666345 0 402718720 -0.3436534107 -0.0042483150 0.1530736983 375 1305031114.6441500187 0.0554208010 0.0467932377 0.0857106745 0.0185359103 0.1804740000 959669305 0 402718720 -0.3489080667 -0.0036976375 0.1551782489 376 1305031114.6792509556 0.0564627014 0.0468189543 0.0857106745 0.0185290580 0.1925700000 959672209 0 402718720 -0.3555357754 -0.0071178558 0.1570511609 377 1305031114.7113060951 0.0574631020 0.0468471881 0.0857106745 0.0185252932 0.1990690000 959675057 0 402718720 -0.3592784405 -0.0110741118 0.1579362303 378 1305031114.7432758808 0.0588094927 0.0468788344 0.0857106745 0.0185047118 0.1803030000 959678017 0 402718720 -0.3608784974 -0.0130604347 0.1585130543 379 1305031114.7792890072 0.0593470670 0.0469117322 0.0857106745 0.0184874034 0.2002100000 959681033 0 402718720 -0.3618611991 -0.0140602943 0.1583656967 380 1305031114.8113029003 0.0595397130 0.0469449637 0.0857106745 0.0184723529 0.1822230000 959683881 0 402718720 -0.3608538508 -0.0128683448 0.1580596268 381 1305031114.8432080746 0.0597906262 0.0469786793 0.0857106745 0.0184490670 0.1835360000 959686841 0 402718720 -0.3604011834 -0.0124413688 0.1579936743 382 1305031114.8792810440 0.0589069240 0.0470099051 0.0857106745 0.0184248524 0.1826810000 959689801 0 402718720 -0.3587544858 -0.0114672631 0.1574007422 383 1305031114.9128789902 0.0589659773 0.0470411220 0.0857106745 0.0184051070 0.1828240000 959692817 0 402718720 -0.3555170596 -0.0102447495 0.1573612690 384 1305031114.9432640076 0.0582589060 0.0470703350 0.0857106745 0.0183821257 0.2029620000 959695609 0 402718720 -0.3520583808 -0.0074157030 0.1577455550 385 1305031114.9792799950 0.0567605346 0.0470955043 0.0857106745 0.0183631468 0.1840120000 959698625 0 402718720 -0.3458515704 -0.0046466067 0.1576121300 386 1305031115.0113000870 0.0559296682 0.0471183908 0.0857106745 0.0183476284 0.1834930000 959701529 0 402718720 -0.3398629427 -0.0014980065 0.1582916528 387 1305031115.0435299873 0.0550719686 0.0471389426 0.0857106745 0.0183410979 0.1823360000 959704489 0 402718720 -0.3323033750 0.0001580850 0.1590918899 388 1305031115.0792379379 0.0539959148 0.0471566153 0.0857106745 0.0183198232 0.1973640000 959707505 0 402718720 -0.3172385991 0.0000782070 0.1604182869 389 1305031115.1112298965 0.0527096763 0.0471708905 0.0857106745 0.0183163351 0.2299020000 959710353 0 402718720 -0.3040626049 0.0018993915 0.1612882763 390 1305031115.1432940960 0.0510874391 0.0471809329 0.0857106745 0.0183024043 0.2180670000 959713313 0 402718720 -0.2947240770 0.0016589157 0.1622739583 391 1305031115.1794400215 0.0486402698 0.0471846652 0.0857106745 0.0183064059 0.2197630000 959716329 0 402718720 -0.2821194828 0.0019329243 0.1636602283 392 1305031115.2113740444 0.0484215245 0.0471878205 0.0857106745 0.0183052220 0.2098740000 959719177 0 402718720 -0.2742290795 0.0000081187 0.1657376587 393 1305031115.2432971001 0.0478694737 0.0471895550 0.0857106745 0.0183117165 0.1855240000 959722137 0 402718720 -0.2523629367 -0.0035715110 0.1678733826 394 1305031115.2799661160 0.0447935164 0.0471834737 0.0857106745 0.0183343877 0.1816660000 959725097 0 402718720 -0.2397601902 -0.0008299525 0.1703000069 395 1305031115.3117039204 0.0434009209 0.0471738976 0.0857106745 0.0183558610 0.1944130000 959728057 0 402718720 -0.2244716287 0.0002235850 0.1725782454 396 1305031115.3434259892 0.0426464155 0.0471624645 0.0857106745 0.0183406302 0.1783910000 959730961 0 402718720 -0.2069061100 -0.0020693478 0.1741868556 397 1305031115.3791658878 0.0393526703 0.0471427925 0.0857106745 0.0185751492 0.1736580000 959733865 0 402718720 -0.1960353553 0.0057799290 0.1763472259 398 1305031115.4112370014 0.0445991084 0.0471364013 0.0857106745 0.0185611230 0.1756120000 959736769 0 402718720 -0.1898696721 0.0040919823 0.1804861873 399 1305031115.4431591034 0.0436813757 0.0471277421 0.0857106745 0.0186166283 0.1752550000 959739673 0 402718720 -0.1639424115 0.0021180031 0.1845093369 400 1305031115.4792408943 0.0456217341 0.0471239771 0.0857106745 0.0185994576 0.1769340000 959742689 0 402718720 -0.1468295157 0.0021807379 0.1876180321 401 1305031115.5112531185 0.0474231914 0.0471247233 0.0857106745 0.0186793999 0.1675480000 959745537 0 402718720 -0.1279781312 0.0002017851 0.1898578405 402 1305031115.5436201096 0.0476276875 0.0471259744 0.0857106745 0.0187111491 0.1633050000 959748497 0 402718720 -0.1072262526 -0.0015192586 0.1903551519 403 1305031115.5793149471 0.0484567098 0.0471292765 0.0857106745 0.0186897624 0.1595710000 959751513 0 402718720 -0.0916211978 -0.0016303575 0.1894869655 404 1305031115.6114239693 0.0494366288 0.0471349878 0.0857106745 0.0186697596 0.1736550000 959754361 0 402718720 -0.0769772455 -0.0026392767 0.1886917651 405 1305031115.6432540417 0.0483275689 0.0471379324 0.0857106745 0.0186487742 0.1676410000 959757265 0 402718720 -0.0594341718 -0.0031688281 0.1873243004 406 1305031115.6792409420 0.0511376187 0.0471477839 0.0857106745 0.0186322125 0.1530270000 959760281 0 402718720 -0.0442860872 -0.0041817161 0.1860369295 407 1305031115.7113199234 0.0497151986 0.0471540920 0.0857106745 0.0186512476 0.1517070000 959763185 0 402718720 -0.0266158544 -0.0037507773 0.1845279187 408 1305031115.7432498932 0.0458456390 0.0471508850 0.0857106745 0.0186911697 0.1516950000 959766145 0 402718720 -0.0077998419 -0.0013971719 0.1826204509 409 1305031115.7794249058 0.0484298691 0.0471540121 0.0857106745 0.0186896553 0.1483520000 959769161 0 402718720 0.0078617726 -0.0024823449 0.1806053072 410 1305031115.8112769127 0.0482031219 0.0471565709 0.0857106745 0.0186874999 0.1521740000 959772009 0 402718720 0.0196889807 -0.0006429398 0.1788726896 411 1305031115.8432240486 0.0459011532 0.0471535164 0.0857106745 0.0186781826 0.1423180000 959774969 0 402718720 0.0345954560 0.0025476855 0.1775912642 412 1305031115.8791980743 0.0522339046 0.0471658474 0.0857106745 0.0186697969 0.1371310000 959777873 0 402718720 0.0463114642 -0.0001205808 0.1768360436 413 1305031115.9111180305 0.0543024018 0.0471831272 0.0857106745 0.0186591736 0.1367540000 959780777 0 402718720 0.0568143427 0.0002441542 0.1761601120 414 1305031115.9433109760 0.0514765047 0.0471934977 0.0857106745 0.0186553995 0.1403880000 959783625 0 402718720 0.0701949671 0.0053536403 0.1761436164 415 1305031115.9807400703 0.0565072186 0.0472159404 0.0857106745 0.0186479378 0.1477170000 959786641 0 402718720 0.0806637332 0.0069497465 0.1770208776 416 1305031116.0113790035 0.0564599149 0.0472381615 0.0857106745 0.0186933641 0.1338160000 959789489 0 402718720 0.0924431980 0.0097074723 0.1776492298 417 1305031116.0431640148 0.0577560738 0.0472633843 0.0857106745 0.0186755268 0.1330970000 959792449 0 402718720 0.1020007059 0.0124703320 0.1788402498 418 1305031116.0800299644 0.0639031306 0.0473031923 0.0857106745 0.0186727260 0.1307450000 959795465 0 402718720 0.1107863337 0.0146050770 0.1807397306 419 1305031116.1112999916 0.0649627820 0.0473453393 0.0857106745 0.0186538063 0.1294000000 959798313 0 402718720 0.1208876818 0.0170346722 0.1829659343 420 1305031116.1434469223 0.0682329610 0.0473950717 0.0857106745 0.0186345400 0.1434430000 959801217 0 402718720 0.1300856471 0.0165536124 0.1851577014 421 1305031116.1795721054 0.0733295903 0.0474566739 0.0857106745 0.0186166166 0.1266660000 959804233 0 402718720 0.1397445053 0.0165711623 0.1869984269 422 1305031116.2113199234 0.0743192434 0.0475203293 0.0857106745 0.0185968357 0.1239770000 959807137 0 402718720 0.1491567940 0.0184818860 0.1889039725 423 1305031116.2433199883 0.0754194632 0.0475862847 0.0857106745 0.0185809130 0.1224230000 959810041 0 402718720 0.1592276394 0.0184374359 0.1899384111 424 1305031116.2793850899 0.0798608437 0.0476624039 0.0857106745 0.0185964011 0.1211630000 959813113 0 402718720 0.1676933020 0.0185155906 0.1896415204 425 1305031116.3113360405 0.0811404064 0.0477411757 0.0857106745 0.0185925870 0.1337700000 959815961 0 402718720 0.1750056297 0.0192913804 0.1898066550 426 1305031116.3432919979 0.0811674818 0.0478196412 0.0857106745 0.0185755269 0.1163420000 959818865 0 402718720 0.1823170781 0.0192177054 0.1886282265 427 1305031116.3793840408 0.0832122043 0.0479025278 0.0857106745 0.0185591896 0.1167910000 959821825 0 402718720 0.1875628531 0.0177336279 0.1860325485 428 1305031116.4113330841 0.0827118456 0.0479838579 0.0857106745 0.0185406460 0.1150720000 959824785 0 402718720 0.1927832812 0.0169624481 0.1841088235 429 1305031116.4433689117 0.0788942426 0.0480559101 0.0857106745 0.0185279170 0.1160310000 959827745 0 402718720 0.1978974342 0.0189501867 0.1826173961 430 1305031116.4798500538 0.0750739276 0.0481187427 0.0857106745 0.0185113441 0.1241690000 959830761 0 402718720 0.1997507215 0.0202282332 0.1802380979 431 1305031116.5112049580 0.0738387778 0.0481784180 0.0857106745 0.0184927865 0.1159770000 959833609 0 402718720 0.1978826523 0.0189582445 0.1778666824 432 1305031116.5432620049 0.0727942735 0.0482353991 0.0857106745 0.0184718845 0.1155970000 959836513 0 402718720 0.1940554231 0.0170829576 0.1760822088 433 1305031116.5793130398 0.0668741018 0.0482784446 0.0857106745 0.0184778512 0.1201210000 959839529 0 402718720 0.1885839701 0.0184796639 0.1744395494 434 1305031116.6112608910 0.0637682006 0.0483141353 0.0857106745 0.0184727074 0.1209220000 959842377 0 402718720 0.1813446730 0.0179526489 0.1728202999 435 1305031116.6433548927 0.0612264425 0.0483438188 0.0857106745 0.0184664187 0.1382740000 959845281 0 402718720 0.1720891148 0.0175310522 0.1713797152 436 1305031116.6792809963 0.0558750778 0.0483610923 0.0857106745 0.0184532743 0.1224110000 959848409 0 402718720 0.1621529162 0.0162740350 0.1705647260 437 1305031116.7116339207 0.0550784878 0.0483764639 0.0857106745 0.0184339150 0.1226560000 959851257 0 402718720 0.1497446001 0.0148141980 0.1696352214 438 1305031116.7432909012 0.0551676415 0.0483919689 0.0857106745 0.0184277597 0.1221190000 959854161 0 402718720 0.1356081963 0.0137197105 0.1692091525 439 1305031116.7792980671 0.0527037233 0.0484017907 0.0857106745 0.0184268797 0.1229120000 959857177 0 402718720 0.1212156862 0.0119287726 0.1687259078 440 1305031116.8113429546 0.0541567020 0.0484148700 0.0857106745 0.0184662468 0.1240110000 959860081 0 402718720 0.1062961146 0.0092031676 0.1677159518 441 1305031116.8460888863 0.0516250245 0.0484221493 0.0857106745 0.0185615895 0.1250440000 959863041 0 402718720 0.0918067470 0.0072277510 0.1662183553 442 1305031116.8801651001 0.0498421043 0.0484253618 0.0857106745 0.0185409775 0.1479380000 959866001 0 402718720 0.0783924386 0.0084450068 0.1654095203 443 1305031116.9120440483 0.0506237037 0.0484303242 0.0857106745 0.0185315932 0.1233220000 959868905 0 402718720 0.0643988326 0.0072808987 0.1650855243 444 1305031116.9432959557 0.0482316911 0.0484298769 0.0857106745 0.0185243676 0.1247800000 959871809 0 402718720 0.0504408218 0.0091289012 0.1646543890 445 1305031116.9793510437 0.0473820753 0.0484275222 0.0857106745 0.0185239236 0.1441630000 959874769 0 402718720 0.0346912220 0.0102247261 0.1641761214 446 1305031117.0113821030 0.0477818884 0.0484260746 0.0857106745 0.0185193483 0.1256340000 959877729 0 402718720 0.0196902249 0.0112558883 0.1636875570 447 1305031117.0432610512 0.0466327406 0.0484220627 0.0857106745 0.0184994551 0.1295260000 959880633 0 402718720 0.0043132198 0.0150396572 0.1635495424 448 1305031117.0795199871 0.0473342761 0.0484196346 0.0857106745 0.0185029542 0.1300460000 959883649 0 402718720 -0.0105734738 0.0177386049 0.1641619802 449 1305031117.1112380028 0.0499439500 0.0484230295 0.0857106745 0.0185029544 0.1218850000 959886497 0 402718720 -0.0203234665 0.0178683922 0.1653534770 450 1305031117.1432180405 0.0519493297 0.0484308657 0.0857106745 0.0184854069 0.1337810000 959889457 0 402718720 -0.0301132575 0.0190824699 0.1667851061 451 1305031117.1792640686 0.0516360775 0.0484379726 0.0857106745 0.0184716651 0.1271160000 959892473 0 402718720 -0.0409469530 0.0229234342 0.1678814590 452 1305031117.2113609314 0.0530447140 0.0484481645 0.0857106745 0.0184742637 0.1250570000 959895377 0 402718720 -0.0481502861 0.0231173784 0.1695489287 453 1305031117.2432770729 0.0538802296 0.0484601559 0.0857106745 0.0184709558 0.1254470000 959898281 0 402718720 -0.0529913567 0.0241044853 0.1715957671 454 1305031117.2792990208 0.0539562181 0.0484722617 0.0857106745 0.0184562584 0.1269590000 959901297 0 402718720 -0.0570718646 0.0248361994 0.1733859479 455 1305031117.3111999035 0.0554472059 0.0484875913 0.0857106745 0.0184444319 0.1269300000 959904145 0 402718720 -0.0618493855 0.0231326688 0.1747801602 456 1305031117.3432428837 0.0575820096 0.0485075352 0.0857106745 0.0184342207 0.1259690000 959907105 0 402718720 -0.0659037679 0.0196863674 0.1755027175 457 1305031117.3794538975 0.0583343431 0.0485290380 0.0857106745 0.0184246586 0.1269690000 959910121 0 402718720 -0.0681630746 0.0157754160 0.1755881906 458 1305031117.4112210274 0.0588851534 0.0485516496 0.0857106745 0.0184056565 0.1260880000 959913025 0 402718720 -0.0699281171 0.0115943057 0.1751659214 459 1305031117.4432740211 0.0584002919 0.0485731064 0.0857106745 0.0183868188 0.1289000000 959915929 0 402718720 -0.0710554793 0.0073486702 0.1744264960 460 1305031117.4794030190 0.0550562069 0.0485872001 0.0857106745 0.0183718099 0.1473730000 959918945 0 402718720 -0.0707865730 0.0037727633 0.1735528409 461 1305031117.5113248825 0.0535262227 0.0485979138 0.0857106745 0.0183534982 0.1289180000 959921849 0 402718720 -0.0714596212 -0.0013796460 0.1726230830 462 1305031117.5442850590 0.0512752607 0.0486037089 0.0857106745 0.0183360357 0.1292190000 959924697 0 402718720 -0.0713860467 -0.0063384539 0.1718025655 463 1305031117.5791549683 0.0456824899 0.0485973996 0.0857106745 0.0183179903 0.1289670000 959927769 0 402718720 -0.0719932020 -0.0100322459 0.1715955138 464 1305031117.6111590862 0.0426784493 0.0485846432 0.0857106745 0.0182993875 0.1286960000 959930617 0 402718720 -0.0722219869 -0.0143090338 0.1727975309 465 1305031117.6432840824 0.0410723016 0.0485684877 0.0857106745 0.0182819011 0.1425840000 959933577 0 402718720 -0.0727808550 -0.0203876868 0.1746827066 466 1305031117.6792619228 0.0365473367 0.0485426912 0.0857106745 0.0182671327 0.1416050000 959936593 0 402718720 -0.0728587434 -0.0260554310 0.1773967296 467 1305031117.7112150192 0.0355058163 0.0485147750 0.0857106745 0.0182486322 0.1291430000 959939441 0 402718720 -0.0725978315 -0.0327837169 0.1808550954 468 1305031117.7431840897 0.0373589396 0.0484909377 0.0857106745 0.0182359498 0.1362320000 959942345 0 402718720 -0.0689537451 -0.0440958291 0.1856228262 469 1305031117.7794671059 0.0319125317 0.0484555893 0.0857106745 0.0182165704 0.1304360000 959945361 0 402718720 -0.0702052042 -0.0498282649 0.1887787730 470 1305031117.8113200665 0.0296887942 0.0484156600 0.0857106745 0.0181997281 0.1392220000 959948265 0 402718720 -0.0698121414 -0.0566501915 0.1925831437 471 1305031117.8433070183 0.0328771882 0.0483826696 0.0857106745 0.0181957154 0.1395280000 959951057 0 402718720 -0.0666694492 -0.0695686862 0.1975129247 472 1305031117.8794670105 0.0258346051 0.0483348982 0.0857106745 0.0181790037 0.1319670000 959954073 0 402718720 -0.0680121481 -0.0747491345 0.2005710006 473 1305031117.9114069939 0.0243640076 0.0482842198 0.0857106745 0.0181611739 0.1327470000 959956921 0 402718720 -0.0698382780 -0.0818281770 0.2043023705 474 1305031117.9432721138 0.0266341474 0.0482385446 0.0857106745 0.0181435163 0.1412920000 959959825 0 402718720 -0.0685092211 -0.0930710956 0.2098734826 475 1305031117.9792630672 0.0210321713 0.0481812680 0.0857106745 0.0181379365 0.1448620000 959962841 0 402718720 -0.0709300414 -0.0979883224 0.2141233981 476 1305031118.0112280846 0.0242926404 0.0481310818 0.0857106745 0.0181257280 0.1403490000 959965689 0 402718720 -0.0711748675 -0.1094284281 0.2202328891 477 1305031118.0435490608 0.0266803652 0.0480861117 0.0857106745 0.0181086113 0.1419950000 959968649 0 402718720 -0.0720482990 -0.1200171486 0.2257080823 478 1305031118.0793690681 0.0230024792 0.0480336355 0.0857106745 0.0180921985 0.1367120000 959971665 0 402718720 -0.0736141428 -0.1260014623 0.2300462872 479 1305031118.1112170219 0.0250119809 0.0479855736 0.0857106745 0.0180821434 0.1439670000 959974513 0 402718720 -0.0719703734 -0.1365358233 0.2355526239 480 1305031118.1432559490 0.0262523182 0.0479402960 0.0857106745 0.0180654395 0.1618370000 959977473 0 402718720 -0.0737561658 -0.1450041085 0.2399473637 481 1305031118.1793229580 0.0256605502 0.0478939764 0.0857106745 0.0180484908 0.1381630000 959980489 0 402718720 -0.0753043443 -0.1533298492 0.2440952361 482 1305031118.2112019062 0.0297973938 0.0478564316 0.0857106745 0.0180398222 0.1410940000 959983337 0 402718720 -0.0767069831 -0.1652568132 0.2486557215 483 1305031118.2431728840 0.0305353925 0.0478205702 0.0857106745 0.0180310606 0.1371280000 959986241 0 402718720 -0.0788653269 -0.1722626090 0.2517323494 484 1305031118.2791941166 0.0303901210 0.0477845569 0.0857106745 0.0180364323 0.1414280000 959989257 0 402718720 -0.0785714686 -0.1811654419 0.2553899884 485 1305031118.3112990856 0.0330265313 0.0477541280 0.0857106745 0.0180188689 0.1441800000 959992161 0 402718720 -0.0795652568 -0.1902803332 0.2588586509 486 1305031118.3433239460 0.0322300792 0.0477221855 0.0857106745 0.0180111390 0.1412990000 959995065 0 402718720 -0.0791780129 -0.1947799474 0.2616344988 487 1305031118.3792080879 0.0324472226 0.0476908201 0.0857106745 0.0179946521 0.1457320000 959998081 0 402718720 -0.0815368593 -0.1988699883 0.2649459243 488 1305031118.4112958908 0.0349197946 0.0476646499 0.0857106745 0.0179911344 0.1488540000 960000985 0 402718720 -0.0846275091 -0.2029509842 0.2686095834 489 1305031118.4457030296 0.0339440666 0.0476365915 0.0857106745 0.0179743147 0.1474320000 960003945 0 402718720 -0.0817677155 -0.2051502019 0.2717492580 490 1305031118.4792850018 0.0343231969 0.0476094213 0.0857106745 0.0179564635 0.1496490000 960006849 0 402718720 -0.0812612399 -0.2075382471 0.2750840783 491 1305031118.5112550259 0.0356722288 0.0475851093 0.0857106745 0.0179408530 0.1500120000 960009753 0 402718720 -0.0808525458 -0.2095050216 0.2774432898 492 1305031118.5451989174 0.0353465267 0.0475602341 0.0857106745 0.0179350343 0.1481160000 960012713 0 402718720 -0.0801264495 -0.2079104483 0.2795180082 493 1305031118.5792849064 0.0325511545 0.0475297897 0.0857106745 0.0179171211 0.1637170000 960015729 0 402718720 -0.0750950798 -0.2036024332 0.2800049186 494 1305031118.6161420345 0.0356060751 0.0475056527 0.0857106745 0.0179016916 0.1502640000 960018745 0 402718720 -0.0756876096 -0.2019646317 0.2802386880 495 1305031118.6453309059 0.0322816707 0.0474748971 0.0857106745 0.0178862861 0.1750410000 960021593 0 402718720 -0.0729129687 -0.1958683431 0.2790364325 496 1305031118.6792950630 0.0324442163 0.0474445934 0.0857106745 0.0178720115 0.1647230000 960024609 0 402718720 -0.0709453747 -0.1895932853 0.2777240276 497 1305031118.7114210129 0.0355136432 0.0474205874 0.0857106745 0.0178627357 0.1564300000 960027457 0 402718720 -0.0746371374 -0.1850090921 0.2758180797 498 1305031118.7468008995 0.0422612801 0.0474102274 0.0857106745 0.0178574804 0.1538190000 960030473 0 402718720 -0.0747897401 -0.1828433275 0.2735748291 499 1305031118.7792770863 0.0363491625 0.0473880609 0.0857106745 0.0178879117 0.1621260000 960033433 0 402718720 -0.0730531365 -0.1686677784 0.2701422572 500 1305031118.8112208843 0.0345987193 0.0473624822 0.0857106745 0.0178959247 0.1713050000 960036281 0 402718720 -0.0681996644 -0.1597099602 0.2665501237 501 1305031118.8467741013 0.0437038317 0.0473551795 0.0857106745 0.0179116542 0.1581280000 960039297 0 402718720 -0.0678941384 -0.1573153734 0.2615075707 502 1305031118.8792080879 0.0378927626 0.0473363301 0.0857106745 0.0179628550 0.1620100000 960042257 0 402718720 -0.0665580928 -0.1416047662 0.2548260093 503 1305031118.9111769199 0.0360012315 0.0473137951 0.0857106745 0.0179676928 0.1615850000 960045105 0 402718720 -0.0656423494 -0.1300810874 0.2486021966 504 1305031118.9470090866 0.0416015387 0.0473024613 0.0857106745 0.0179520543 0.1610780000 960048121 0 402718720 -0.0668554828 -0.1219794080 0.2418050915 505 1305031118.9793939590 0.0390255861 0.0472860714 0.0857106745 0.0179472074 0.1726040000 960051081 0 402718720 -0.0676693544 -0.1091001704 0.2350116968 506 1305031119.0113630295 0.0384733416 0.0472686549 0.0857106745 0.0179357915 0.1585800000 960053929 0 402718720 -0.0688126236 -0.0978216156 0.2288026661 507 1305031119.0471799374 0.0441624857 0.0472625284 0.0857106745 0.0179223099 0.1580980000 960056945 0 402718720 -0.0709555447 -0.0896304026 0.2222577035 508 1305031119.0792229176 0.0458500944 0.0472597480 0.0857106745 0.0179097452 0.1581760000 960059793 0 402718720 -0.0729828030 -0.0813074559 0.2156246156 509 1305031119.1113278866 0.0459925532 0.0472572584 0.0857106745 0.0178953318 0.1585100000 960062753 0 402718720 -0.0740787908 -0.0718981698 0.2088819295 510 1305031119.1476290226 0.0486705974 0.0472600297 0.0857106745 0.0178833211 0.1816180000 960065769 0 402718720 -0.0736145154 -0.0617279634 0.2022981048 511 1305031119.1792619228 0.0486127734 0.0472626769 0.0857106745 0.0178772674 0.1601930000 960068673 0 402718720 -0.0742570236 -0.0523909815 0.1958935261 512 1305031119.2113640308 0.0490162261 0.0472661018 0.0857106745 0.0178653217 0.1782800000 960071577 0 402718720 -0.0732427239 -0.0441721566 0.1896467209 513 1305031119.2476599216 0.0501701273 0.0472717627 0.0857106745 0.0178548773 0.1610090000 960074593 0 402718720 -0.0732686743 -0.0326050445 0.1834802181 514 1305031119.2792439461 0.0498172045 0.0472767149 0.0857106745 0.0178397126 0.1608910000 960179897 0 402718720 -0.0738005266 -0.0229204781 0.1781671196 515 1305031119.3112120628 0.0532538220 0.0472883209 0.0857106745 0.0178236198 0.1541230000 960182801 0 402718720 -0.0737993419 -0.0176689327 0.1742213219 516 1305031119.3477499485 0.0545391440 0.0473023729 0.0857106745 0.0178089108 0.1603260000 960185817 0 402718720 -0.0741466433 -0.0065706251 0.1689969301 517 1305031119.3792390823 0.0538305007 0.0473149999 0.0857106745 0.0177975115 0.1625350000 960188721 0 402718720 -0.0734732747 0.0037320405 0.1646685451 518 1305031119.4114921093 0.0538173504 0.0473275527 0.0857106745 0.0177873970 0.1610600000 960191625 0 402718720 -0.0723041669 0.0139065990 0.1607245207 519 1305031119.4477260113 0.0608426966 0.0473535934 0.0857106745 0.0177715534 0.1527370000 960194697 0 402718720 -0.0717956051 0.0195843242 0.1577219814 520 1305031119.4792668819 0.0593904927 0.0473767413 0.0857106745 0.0177587277 0.1697950000 960197489 0 402718720 -0.0741558522 0.0311740600 0.1525914967 521 1305031119.5112578869 0.0591627136 0.0473993631 0.0857106745 0.0177464379 0.1588150000 960200393 0 402718720 -0.0745754912 0.0427390710 0.1488945037 522 1305031119.5474140644 0.0662136525 0.0474354058 0.0857106745 0.0177294753 0.1483960000 960203465 0 402718720 -0.0747938529 0.0485582091 0.1462588310 523 1305031119.5795691013 0.0636926368 0.0474664904 0.0857106745 0.0177285466 0.1565110000 960206369 0 402718720 -0.0754245743 0.0631691888 0.1423867047 524 1305031119.6150240898 0.0678300411 0.0475053521 0.0857106745 0.0177182526 0.1451950000 960209385 0 402718720 -0.0760962367 0.0694877580 0.1406227797 525 1305031119.6488890648 0.0704545900 0.0475490650 0.0857106745 0.0177180227 0.1639280000 960212345 0 402718720 -0.0787543952 0.0816608071 0.1375787109 526 1305031119.6792080402 0.0706102178 0.0475929075 0.0857106745 0.0177099469 0.1529650000 960215137 0 402718720 -0.0795657262 0.0934127420 0.1355385035 527 1305031119.7152490616 0.0753062218 0.0476454944 0.0857106745 0.0176957913 0.1436110000 960218153 0 402718720 -0.0799497813 0.0991485640 0.1350384802 528 1305031119.7471930981 0.0821985602 0.0477109358 0.0857106745 0.0176889393 0.1417510000 960221113 0 402718720 -0.0822466835 0.1040534526 0.1340243220 529 1305031119.7791690826 0.0814861134 0.0477747830 0.0857106745 0.0176744532 0.1486830000 960224017 0 402718720 -0.0842891037 0.1163459420 0.1319884807 530 1305031119.8145709038 0.0865540877 0.0478479515 0.0865540877 0.0176645171 0.1545380000 960226921 0 402718720 -0.0843788609 0.1202295050 0.1315679103 531 1305031119.8474450111 0.0876158178 0.0479228439 0.0876158178 0.0176548022 0.1478030000 960229937 0 402718720 -0.0833613649 0.1330107898 0.1296175420 532 1305031119.8792319298 0.0914720371 0.0480047033 0.0914720371 0.0176486506 0.1486870000 960232785 0 402718720 -0.0848046765 0.1364266574 0.1280654222 533 1305031119.9114239216 0.0890272781 0.0480816687 0.0914720371 0.0176568282 0.1567980000 960235689 0 402718720 -0.0859274417 0.1489964128 0.1251331419 534 1305031119.9474620819 0.0938917994 0.0481674555 0.0938917994 0.0176442310 0.1369510000 960238761 0 402718720 -0.0867697150 0.1534639150 0.1239582524 535 1305031119.9795460701 0.0958850682 0.0482566473 0.0958850682 0.0176308052 0.1461810000 960241665 0 402718720 -0.0878045931 0.1577712297 0.1224564910 536 1305031120.0152831078 0.0969673768 0.0483475255 0.0969673768 0.0176343089 0.1343360000 960244625 0 402718720 -0.0881384611 0.1632698178 0.1214561164 537 1305031120.0473101139 0.0989270061 0.0484417145 0.0989270061 0.0176303073 0.1319070000 960247585 0 402718720 -0.0903081447 0.1676610857 0.1204701215 538 1305031120.0794179440 0.1002034470 0.0485379259 0.1002034470 0.0176284684 0.1313720000 960250489 0 402718720 -0.0926170871 0.1682942957 0.1195236221 539 1305031120.1152489185 0.1000850126 0.0486335606 0.1002034470 0.0176192799 0.1311480000 960253449 0 402718720 -0.0931622908 0.1697062552 0.1190534905 540 1305031120.1481750011 0.0980825797 0.0487251328 0.1002034470 0.0176179989 0.1488330000 960256409 0 402718720 -0.0929476768 0.1708561629 0.1187516078 541 1305031120.1792609692 0.0965820774 0.0488135930 0.1002034470 0.0176085019 0.1339430000 960259257 0 402718720 -0.0925501511 0.1690892875 0.1182609648 542 1305031120.2152600288 0.0946420953 0.0488981474 0.1002034470 0.0175937254 0.1348630000 960262273 0 402718720 -0.0920897648 0.1655901074 0.1176348925 543 1305031120.2480180264 0.0896810293 0.0489732540 0.1002034470 0.0175787834 0.1349330000 960265233 0 402718720 -0.0918135419 0.1630680561 0.1172538176 544 1305031120.2794411182 0.0855095908 0.0490404164 0.1002034470 0.0175633128 0.1341040000 960268137 0 402718720 -0.0930979103 0.1596276462 0.1170926020 545 1305031120.3152129650 0.0814063475 0.0490998034 0.1002034470 0.0175474120 0.1446460000 960271097 0 402718720 -0.0940438136 0.1552257538 0.1175862774 546 1305031120.3477969170 0.0752312392 0.0491476632 0.1002034470 0.0175315552 0.1691920000 960274057 0 402718720 -0.0950754210 0.1493887454 0.1188427061 547 1305031120.3794460297 0.0720871538 0.0491896001 0.1002034470 0.0175161104 0.1340920000 960276961 0 402718720 -0.0951604769 0.1428847611 0.1213746443 548 1305031120.4154899120 0.0759206265 0.0492383794 0.1002034470 0.0175477350 0.1415670000 960279921 0 402718720 -0.0933213010 0.1252847165 0.1262942702 549 1305031120.4474329948 0.0675773695 0.0492717837 0.1002034470 0.0175376512 0.1337420000 960282881 0 402718720 -0.0933365449 0.1203882694 0.1288354993 550 1305031120.4794321060 0.0639693961 0.0492985066 0.1002034470 0.0175219374 0.1494900000 960285785 0 402718720 -0.0919919237 0.1154740304 0.1326820254 551 1305031120.5148770809 0.0618469343 0.0493212806 0.1002034470 0.0175109411 0.1315030000 960288745 0 402718720 -0.0906050801 0.1067010537 0.1365356892 552 1305031120.5478069782 0.0570120439 0.0493352131 0.1002034470 0.0174976582 0.1318760000 960291705 0 402718720 -0.0892727748 0.0984537676 0.1407849491 553 1305031120.5795590878 0.0549980700 0.0493454533 0.1002034470 0.0174867314 0.1325380000 960294609 0 402718720 -0.0869768113 0.0920594037 0.1456000209 554 1305031120.6152710915 0.0550775267 0.0493558000 0.1002034470 0.0174799473 0.1537860000 960297513 0 402718720 -0.0813443437 0.0821595564 0.1510448009 555 1305031120.6473538876 0.0492635407 0.0493556338 0.1002034470 0.0174668953 0.1466090000 960300473 0 402718720 -0.0821158364 0.0758741051 0.1546465307 556 1305031120.6793179512 0.0471064262 0.0493515885 0.1002034470 0.0174753052 0.1477160000 960303321 0 402718720 -0.0803125799 0.0704746395 0.1591226459 557 1305031120.7145531178 0.0451368466 0.0493440216 0.1002034470 0.0174600754 0.1362440000 960306337 0 402718720 -0.0792458132 0.0636133328 0.1635466516 558 1305031120.7473959923 0.0425940342 0.0493319249 0.1002034470 0.0174490777 0.1445800000 960309297 0 402718720 -0.0761661381 0.0535380691 0.1686221361 559 1305031120.7799079418 0.0408623889 0.0493167736 0.1002034470 0.0174366664 0.1417700000 960312257 0 402718720 -0.0762514696 0.0461855941 0.1722444594 560 1305031120.8149440289 0.0399022661 0.0492999620 0.1002034470 0.0174301443 0.1542420000 960315217 0 402718720 -0.0763150677 0.0386333242 0.1760582477 561 1305031120.8479421139 0.0353129208 0.0492750297 0.1002034470 0.0174149719 0.1467530000 960318177 0 402718720 -0.0769289955 0.0325483941 0.1796291620 562 1305031120.8834540844 0.0372943692 0.0492537118 0.1002034470 0.0174072557 0.1531190000 960321137 0 402718720 -0.0762778074 0.0194990002 0.1834483296 563 1305031120.9154539108 0.0348297842 0.0492280920 0.1002034470 0.0174030797 0.1481610000 960324041 0 402718720 -0.0778996274 0.0143372379 0.1862299740 564 1305031120.9475090504 0.0322249383 0.0491979446 0.1002034470 0.0173881083 0.1511890000 960326945 0 402718720 -0.0794752389 0.0056707510 0.1893372983 565 1305031120.9833900928 0.0320641212 0.0491676192 0.1002034470 0.0173756613 0.1632820000 960329961 0 402718720 -0.0804974660 -0.0029307292 0.1924224645 566 1305031121.0150289536 0.0329479910 0.0491389626 0.1002034470 0.0173669720 0.1515080000 960332809 0 402718720 -0.0819290504 -0.0125157684 0.1952067912 567 1305031121.0477550030 0.0285011809 0.0491025644 0.1002034470 0.0173522538 0.1510590000 960335825 0 402718720 -0.0828447789 -0.0180008393 0.1974093169 568 1305031121.0831170082 0.0305490736 0.0490698998 0.1002034470 0.0173420215 0.1595830000 960338785 0 402718720 -0.0843583494 -0.0295288227 0.2002241015 569 1305031121.1148779392 0.0288233235 0.0490343171 0.1002034470 0.0173277434 0.1529930000 960341633 0 402718720 -0.0847705007 -0.0362385176 0.2018678784 570 1305031121.1473550797 0.0253943950 0.0489928436 0.1002034470 0.0173135908 0.1629450000 960344593 0 402718720 -0.0855152607 -0.0431434065 0.2039502859 571 1305031121.1832809448 0.0273919348 0.0489550136 0.1002034470 0.0172985403 0.1627290000 960347609 0 402718720 -0.0874961913 -0.0538834743 0.2066259980 572 1305031121.2114310265 0.0256356597 0.0489142455 0.1002034470 0.0172855953 0.1679430000 960350345 0 402718720 -0.0877191946 -0.0605838671 0.2086496353 573 1305031121.2472009659 0.0226443484 0.0488683992 0.1002034470 0.0172720934 0.1560010000 960353361 0 402718720 -0.0880265757 -0.0671852380 0.2114228308 574 1305031121.2828760147 0.0251904279 0.0488271484 0.1002034470 0.0172570968 0.1639930000 960356377 0 402718720 -0.0898346901 -0.0778686702 0.2150475830 575 1305031121.3135879040 0.0252008140 0.0487860591 0.1002034470 0.0172490149 0.1720980000 960359225 0 402718720 -0.0890365690 -0.0878779963 0.2181650698 576 1305031121.3475399017 0.0244277567 0.0487437704 0.1002034470 0.0172383153 0.1616890000 960362185 0 402718720 -0.0901447833 -0.0955251306 0.2216856927 577 1305031121.3832480907 0.0243144631 0.0487014319 0.1002034470 0.0172316351 0.1583310000 960365201 0 402718720 -0.0909106359 -0.1022703052 0.2246525139 578 1305031121.4143280983 0.0243837591 0.0486593598 0.1002034470 0.0172181543 0.1630090000 960368049 0 402718720 -0.0905777588 -0.1122365966 0.2275306433 579 1305031121.4473190308 0.0249993540 0.0486184963 0.1002034470 0.0172096171 0.1795190000 960371009 0 402718720 -0.0923733190 -0.1177844703 0.2306675315 580 1305031121.4830150604 0.0250810198 0.0485779144 0.1002034470 0.0172093631 0.1651170000 960373969 0 402718720 -0.0922116190 -0.1249663755 0.2332525253 581 1305031121.5141639709 0.0270466376 0.0485408554 0.1002034470 0.0171993779 0.1692120000 960376817 0 402718720 -0.0937140808 -0.1354061365 0.2361769825 582 1305031121.5472700596 0.0284465794 0.0485063292 0.1002034470 0.0171929877 0.1655370000 960379833 0 402718720 -0.0954736620 -0.1407410353 0.2388957590 583 1305031121.5832130909 0.0294879824 0.0484737077 0.1002034470 0.0171798159 0.1648780000 960382849 0 402718720 -0.0967183188 -0.1470167488 0.2414630204 584 1305031121.6147189140 0.0312340967 0.0484441878 0.1002034470 0.0171663291 0.1709410000 960385697 0 402718720 -0.0986566320 -0.1568085253 0.2440818846 585 1305031121.6471829414 0.0315205902 0.0484152585 0.1002034470 0.0171587492 0.1786100000 960388601 0 402718720 -0.0981701091 -0.1631495655 0.2459608018 586 1305031121.6832110882 0.0336321630 0.0483900314 0.1002034470 0.0171500184 0.1661630000 960391673 0 402718720 -0.1000215039 -0.1688378900 0.2488915473 587 1305031121.7145280838 0.0364448056 0.0483696818 0.1002034470 0.0171359497 0.1726140000 960394521 0 402718720 -0.1026967242 -0.1785907000 0.2516650558 588 1305031121.7471449375 0.0363496132 0.0483492395 0.1002034470 0.0171231537 0.1692080000 960397425 0 402718720 -0.1010130942 -0.1871106178 0.2553699911 589 1305031121.7828710079 0.0366031118 0.0483292970 0.1002034470 0.0171098322 0.1697790000 960400441 0 402718720 -0.0999564826 -0.1954165399 0.2592646778 590 1305031121.8115448952 0.0370993279 0.0483102632 0.1002034470 0.0170993631 0.1884960000 960403233 0 402718720 -0.0988973081 -0.2004218698 0.2621059120 591 1305031121.8473351002 0.0373953991 0.0482917947 0.1002034470 0.0170864636 0.1673200000 960406249 0 402718720 -0.0968640521 -0.2045749426 0.2653526962 592 1305031121.8821229935 0.0369210467 0.0482725874 0.1002034470 0.0170720540 0.1684380000 960409209 0 402718720 -0.0953729749 -0.2082028091 0.2679351568 593 1305031121.9149429798 0.0376544632 0.0482546816 0.1002034470 0.0170586398 0.1809050000 960412169 0 402718720 -0.0956202000 -0.2107290477 0.2697279155 594 1305031121.9473180771 0.0392032266 0.0482394434 0.1002034470 0.0170458891 0.1696300000 960415073 0 402718720 -0.0965379179 -0.2123840302 0.2707591951 595 1305031121.9829349518 0.0381189622 0.0482224342 0.1002034470 0.0170323098 0.1820950000 960418089 0 402718720 -0.0951228812 -0.2114709467 0.2713186443 596 1305031122.0144240856 0.0386650451 0.0482063983 0.1002034470 0.0170188783 0.1699500000 960420993 0 402718720 -0.0959772989 -0.2091802657 0.2709799409 597 1305031122.0473060608 0.0405145474 0.0481935142 0.1002034470 0.0170051033 0.1715960000 960423897 0 402718720 -0.0968058035 -0.2066363990 0.2698383331 598 1305031122.0829689503 0.0412394144 0.0481818852 0.1002034470 0.0169909560 0.1723240000 960426913 0 402718720 -0.0972150788 -0.2018309534 0.2678516507 599 1305031122.1146879196 0.0417145416 0.0481710883 0.1002034470 0.0169775124 0.1726450000 960429761 0 402718720 -0.0975167975 -0.1957038641 0.2651163936 600 1305031122.1507480145 0.0387860425 0.0481554466 0.1002034470 0.0169726471 0.1889780000 960432777 0 402718720 -0.0981730521 -0.1796444803 0.2610968351 601 1305031122.1830520630 0.0402180590 0.0481422396 0.1002034470 0.0169712378 0.1714330000 960435737 0 402718720 -0.0970252380 -0.1751862913 0.2578359246 602 1305031122.2149689198 0.0372362398 0.0481241234 0.1002034470 0.0170038970 0.1801050000 960438585 0 402718720 -0.0991729870 -0.1574686617 0.2538754940 603 1305031122.2513549328 0.0408261754 0.0481120206 0.1002034470 0.0169912042 0.1731080000 960441657 0 402718720 -0.0984372944 -0.1510770470 0.2505456209 604 1305031122.2838659286 0.0394645147 0.0480977036 0.1002034470 0.0169830627 0.1778680000 960444617 0 402718720 -0.0985525027 -0.1396151185 0.2453942299 605 1305031122.3143088818 0.0375279374 0.0480802329 0.1002034470 0.0170025293 0.1901700000 960447409 0 402718720 -0.1003989056 -0.1237033084 0.2415953726 606 1305031122.3513510227 0.0424985923 0.0480710222 0.1002034470 0.0169960437 0.1824800000 960450425 0 402718720 -0.0995367840 -0.1185056791 0.2375080436 607 1305031122.3826780319 0.0398999751 0.0480575609 0.1002034470 0.0169858728 0.1768100000 960453385 0 402718720 -0.0963564515 -0.1080900580 0.2320294231 608 1305031122.4150080681 0.0429757312 0.0480492026 0.1002034470 0.0169844455 0.1684560000 960456177 0 402718720 -0.0951214060 -0.1033159867 0.2269516587 609 1305031122.4512720108 0.0440052040 0.0480425622 0.1002034470 0.0169733127 0.1747590000 960459249 0 402718720 -0.0930275992 -0.0924108326 0.2208046615 610 1305031122.4833879471 0.0424674936 0.0480334228 0.1002034470 0.0169623625 0.1926920000 960462153 0 402718720 -0.0903114006 -0.0825117007 0.2152595818 611 1305031122.5151350498 0.0425214916 0.0480244016 0.1002034470 0.0169551163 0.1718670000 960465057 0 402718720 -0.0879373178 -0.0739644542 0.2099633664 612 1305031122.5515100956 0.0452076383 0.0480197990 0.1002034470 0.0169476256 0.1845120000 960468073 0 402718720 -0.0865003467 -0.0635889471 0.2044751644 613 1305031122.5832169056 0.0461069867 0.0480166786 0.1002034470 0.0169348021 0.1711960000 960470977 0 402718720 -0.0872163400 -0.0545675121 0.1991329640 614 1305031122.6150169373 0.0504965857 0.0480207176 0.1002034470 0.0169273214 0.1638600000 960473825 0 402718720 -0.0883436948 -0.0499581359 0.1945775151 615 1305031122.6488099098 0.0524726026 0.0480279564 0.1002034470 0.0169140330 0.1817710000 960476841 0 402718720 -0.0886266679 -0.0386717580 0.1884492487 616 1305031122.6834199429 0.0519253016 0.0480342833 0.1002034470 0.0169005328 0.1710000000 960479801 0 402718720 -0.0884750485 -0.0276486315 0.1833638549 617 1305031122.7152190208 0.0527734905 0.0480419643 0.1002034470 0.0168888211 0.1844270000 960482649 0 402718720 -0.0879264027 -0.0183332004 0.1791197956 618 1305031122.7513089180 0.0554815829 0.0480540025 0.1002034470 0.0168842889 0.1721210000 960485721 0 402718720 -0.0871841535 -0.0066520125 0.1751041114 619 1305031122.7834379673 0.0538297445 0.0480633333 0.1002034470 0.0168754640 0.1703660000 960488625 0 402718720 -0.0861510858 0.0065705529 0.1718101352 620 1305031122.8125650883 0.0579480268 0.0480792763 0.1002034470 0.0168636568 0.1789340000 960491473 0 402718720 -0.0873337761 0.0124818459 0.1698882282 621 1305031122.8514859676 0.0630928427 0.0481034528 0.1002034470 0.0168634676 0.1578430000 960494545 0 402718720 -0.0873630196 0.0191216320 0.1674603224 622 1305031122.8837749958 0.0611667521 0.0481244549 0.1002034470 0.0168564021 0.1631770000 960497505 0 402718720 -0.0888529345 0.0315497890 0.1640024781 623 1305031122.9145851135 0.0654320642 0.0481522359 0.1002034470 0.0168491844 0.1511880000 960500297 0 402718720 -0.0907839760 0.0352675617 0.1620405316 624 1305031122.9514129162 0.0709292889 0.0481887376 0.1002034470 0.0168372807 0.1502070000 960503369 0 402718720 -0.0922785029 0.0400632061 0.1596956402 625 1305031122.9830000401 0.0692762956 0.0482224777 0.1002034470 0.0168289309 0.1703830000 960506273 0 402718720 -0.0934260115 0.0508688763 0.1565105766 626 1305031123.0154619217 0.0727794394 0.0482617061 0.1002034470 0.0168161544 0.1468280000 960509121 0 402718720 -0.0932543278 0.0549128093 0.1546090096 627 1305031123.0518379211 0.0744674504 0.0483035015 0.1002034470 0.0168058463 0.1561990000 960512193 0 402718720 -0.0924714059 0.0636058822 0.1509475857 628 1305031123.0829920769 0.0776561201 0.0483502414 0.1002034470 0.0167946605 0.1475080000 960515097 0 402718720 -0.0920338482 0.0684656724 0.1490830928 629 1305031123.1139390469 0.0738847479 0.0483908368 0.1002034470 0.0167906234 0.1571900000 960517889 0 402718720 -0.0923357680 0.0827087462 0.1456080228 630 1305031123.1508400440 0.0803053901 0.0484414948 0.1002034470 0.0167778235 0.1650490000 960520961 0 402718720 -0.0928789079 0.0869299173 0.1445976645 631 1305031123.1821761131 0.0799415484 0.0484914156 0.1002034470 0.0167758176 0.1569490000 960523865 0 402718720 -0.0932539105 0.0982958004 0.1424713284 632 1305031123.2147240639 0.0800679401 0.0485413785 0.1002034470 0.0167660483 0.1552430000 960526769 0 402718720 -0.0924417898 0.1095028147 0.1411993206 633 1305031123.2506411076 0.0873989835 0.0486027649 0.1002034470 0.0167703266 0.1563440000 960529785 0 402718720 -0.0932875797 0.1150415465 0.1414475888 634 1305031123.2823629379 0.0882717073 0.0486653342 0.1002034470 0.0167596445 0.1487290000 960532689 0 402718720 -0.0945500806 0.1263218969 0.1409309655 635 1305031123.3209919930 0.0959029570 0.0487397242 0.1002034470 0.0167506326 0.1524430000 960535761 0 402718720 -0.0956647918 0.1306141168 0.1411245167 636 1305031123.3504929543 0.0996444970 0.0488197631 0.1002034470 0.0167403665 0.1381560000 960538609 0 402718720 -0.0954301804 0.1365693510 0.1412025988 637 1305031123.3822629452 0.0978754759 0.0488967737 0.1002034470 0.0167292602 0.1439370000 960541513 0 402718720 -0.0944082215 0.1493506283 0.1392690837 638 1305031123.4213430882 0.1053420827 0.0489852460 0.1053420827 0.0167177418 0.1334030000 960544585 0 402718720 -0.0952630863 0.1524203718 0.1389402002 639 1305031123.4512660503 0.1096183881 0.0490801335 0.1096183881 0.0167102308 0.1496320000 960547377 0 402718720 -0.0954707637 0.1564454585 0.1385616213 640 1305031123.4836049080 0.1131170020 0.0491801911 0.1131170020 0.0166995417 0.1513940000 960550337 0 402718720 -0.0957780480 0.1615843326 0.1379905492 641 1305031123.5197250843 0.1187087744 0.0492886600 0.1187087744 0.0166884712 0.1291430000 960553297 0 402718720 -0.0960459113 0.1662799865 0.1374324411 642 1305031123.5515730381 0.1215331107 0.0494011903 0.1215331107 0.0166758922 0.1273450000 960556257 0 402718720 -0.0958949551 0.1709827930 0.1365692616 643 1305031123.5796160698 0.1133852676 0.0495006990 0.1215331107 0.0166705979 0.1418490000 960558993 0 402718720 -0.0916247591 0.1892201006 0.1326573938 644 1305031123.6203870773 0.1200412065 0.0496102340 0.1215331107 0.0166621596 0.1293310000 960562121 0 402718720 -0.0925829709 0.1911857873 0.1327134967 645 1305031123.6524300575 0.1228499040 0.0497237838 0.1228499040 0.0166508575 0.1290750000 960565025 0 402718720 -0.0920073241 0.1954455227 0.1325379312 646 1305031123.6837849617 0.1250884086 0.0498404473 0.1250884086 0.0166381262 0.1277920000 960567929 0 402718720 -0.0907950029 0.1998719126 0.1323698312 647 1305031123.7199749947 0.1285041720 0.0499620296 0.1285041720 0.0166256517 0.1254030000 960570945 0 402718720 -0.0901360437 0.2042438388 0.1319951117 648 1305031123.7519800663 0.1293202043 0.0500844959 0.1293202043 0.0166189876 0.1237450000 960573849 0 402718720 -0.0896154568 0.2075940520 0.1312769502 649 1305031123.7841379642 0.1294627488 0.0502068045 0.1294627488 0.0166105612 0.1248800000 960576697 0 402718720 -0.0889226496 0.2099408209 0.1304250509 650 1305031123.8196959496 0.1291664839 0.0503282809 0.1294627488 0.0165990857 0.1432700000 960579769 0 402718720 -0.0875093639 0.2121671736 0.1294521093 651 1305031123.8515510559 0.1276867241 0.0504471111 0.1294627488 0.0165865759 0.1254510000 960582673 0 402718720 -0.0863828734 0.2134814113 0.1284228712 652 1305031123.8838191032 0.1266051829 0.0505639179 0.1294627488 0.0165761451 0.1259340000 960585577 0 402718720 -0.0860385820 0.2133174688 0.1277982742 653 1305031123.9157938957 0.1240497902 0.0506764537 0.1294627488 0.0165655494 0.1260450000 960588425 0 402718720 -0.0851951987 0.2122122943 0.1269786805 654 1305031123.9515299797 0.1209225729 0.0507838637 0.1294627488 0.0165653948 0.1262950000 960591497 0 402718720 -0.0855561793 0.2117728442 0.1265274137 655 1305031123.9834210873 0.1190835014 0.0508881380 0.1294627488 0.0165606886 0.1382340000 960594401 0 402718720 -0.0871147513 0.2096692175 0.1271280348 656 1305031124.0197370052 0.1157576516 0.0509870244 0.1294627488 0.0165679163 0.1278030000 960597417 0 402718720 -0.0886061862 0.2052759826 0.1281192303 657 1305031124.0515310764 0.1129391640 0.0510813199 0.1294627488 0.0165678705 0.1297600000 960600265 0 402718720 -0.0884029716 0.2018853575 0.1290894449 658 1305031124.0839018822 0.1099853441 0.0511708397 0.1294627488 0.0165581921 0.1304830000 960603169 0 402718720 -0.0890190974 0.1986205578 0.1305654794 659 1305031124.1196689606 0.1055579185 0.0512533694 0.1294627488 0.0165623615 0.1294220000 960606185 0 402718720 -0.0896425173 0.1927775890 0.1325525939 660 1305031124.1474580765 0.1027224138 0.0513313528 0.1294627488 0.0165651219 0.1490570000 960609033 0 402718720 -0.0877573788 0.1886135489 0.1346598715 661 1305031124.1827070713 0.0994211063 0.0514041058 0.1294627488 0.0165556476 0.1281260000 960611993 0 402718720 -0.0874966308 0.1841867417 0.1366304606 662 1305031124.2171790600 0.0952074081 0.0514702740 0.1294627488 0.0165623774 0.1265640000 960614953 0 402718720 -0.0875329897 0.1771436483 0.1387256235 663 1305031124.2493400574 0.0928028077 0.0515326156 0.1294627488 0.0165719641 0.1389790000 960617801 0 402718720 -0.0862776712 0.1709298193 0.1407522857 664 1305031124.2825551033 0.0895681679 0.0515898981 0.1294627488 0.0165601365 0.1378970000 960620761 0 402718720 -0.0866065919 0.1657371819 0.1425154656 665 1305031124.3167819977 0.0855880976 0.0516410232 0.1294627488 0.0165653882 0.1393540000 960623721 0 402718720 -0.0874118209 0.1577187330 0.1443272680 666 1305031124.3503708839 0.0843021497 0.0516900639 0.1294627488 0.0165575669 0.1315310000 960626625 0 402718720 -0.0863007009 0.1495391428 0.1464524865 667 1305031124.3824319839 0.0823295340 0.0517360002 0.1294627488 0.0165487873 0.1323400000 960629585 0 402718720 -0.0843901783 0.1417160630 0.1484676600 668 1305031124.4185550213 0.0828052089 0.0517825110 0.1294627488 0.0165557955 0.1420090000 960632657 0 402718720 -0.0785424337 0.1264666766 0.1522093117 669 1305031124.4502561092 0.0780813321 0.0518218216 0.1294627488 0.0165436739 0.1332740000 960635449 0 402718720 -0.0800959021 0.1196686924 0.1520569175 670 1305031124.4801259041 0.0743948743 0.0518555127 0.1294627488 0.0165314005 0.1495490000 960638353 0 402718720 -0.0808078945 0.1119273230 0.1525636166 671 1305031124.5167369843 0.0679507926 0.0518794997 0.1294627488 0.0165195868 0.1335330000 960641369 0 402718720 -0.0812716931 0.1037741229 0.1533986032 672 1305031124.5505030155 0.0642993674 0.0518979817 0.1294627488 0.0165073791 0.1327520000 960644329 0 402718720 -0.0809666663 0.0959619284 0.1550234705 673 1305031124.5846059322 0.0646069720 0.0519168658 0.1294627488 0.0164959945 0.1502200000 960647289 0 402718720 -0.0787146837 0.0831467286 0.1583825946 674 1305031124.6176528931 0.0568784252 0.0519242271 0.1294627488 0.0164964108 0.1323030000 960650249 0 402718720 -0.0800465569 0.0750326589 0.1599745899 675 1305031124.6513130665 0.0539489426 0.0519272267 0.1294627488 0.0164902240 0.1473210000 960653153 0 402718720 -0.0801789463 0.0666486323 0.1629564911 676 1305031124.6854729652 0.0542288944 0.0519306316 0.1294627488 0.0164860014 0.1418110000 960656113 0 402718720 -0.0769078210 0.0528159067 0.1669973880 677 1305031124.7157909870 0.0464137346 0.0519224825 0.1294627488 0.0164743845 0.1379530000 960659017 0 402718720 -0.0778034106 0.0457809642 0.1695995480 678 1305031124.7499411106 0.0450138524 0.0519122928 0.1294627488 0.0164627511 0.1458890000 960661977 0 402718720 -0.0767222345 0.0347073004 0.1738522798 679 1305031124.7851779461 0.0439144671 0.0519005140 0.1294627488 0.0164513535 0.1604660000 960664937 0 402718720 -0.0766423866 0.0231360309 0.1780509204 680 1305031124.8166410923 0.0360050201 0.0518771382 0.1294627488 0.0164405086 0.1608310000 960667841 0 402718720 -0.0778229609 0.0162292831 0.1822577417 681 1305031124.8505589962 0.0357422978 0.0518534454 0.1294627488 0.0164287269 0.1528000000 960670801 0 402718720 -0.0777040124 0.0044217021 0.1881853193 682 1305031124.8835940361 0.0354265980 0.0518293591 0.1294627488 0.0164245030 0.1533930000 960673705 0 402718720 -0.0772262365 -0.0072918744 0.1940856874 683 1305031124.9187700748 0.0304228868 0.0517980173 0.1294627488 0.0164257872 0.1521340000 960676721 0 402718720 -0.0792264417 -0.0151151689 0.1999397427 684 1305031124.9507479668 0.0299910735 0.0517661358 0.1294627488 0.0164154788 0.1530650000 960679569 0 402718720 -0.0807372630 -0.0232892968 0.2061859816 685 1305031124.9864599705 0.0311559830 0.0517360479 0.1294627488 0.0164460093 0.1682190000 960682585 0 402718720 -0.0807766318 -0.0394364148 0.2125025690 686 1305031125.0194671154 0.0331325158 0.0517089291 0.1294627488 0.0164389726 0.1552910000 960685545 0 402718720 -0.0835497081 -0.0498234704 0.2178427577 687 1305031125.0507979393 0.0297500435 0.0516769657 0.1294627488 0.0164378523 0.1580930000 960688393 0 402718720 -0.0823282525 -0.0545768701 0.2230571508 688 1305031125.0834798813 0.0296176523 0.0516449027 0.1294627488 0.0164282775 0.1585510000 960691353 0 402718720 -0.0828412026 -0.0622951910 0.2284337282 689 1305031125.1190290451 0.0292155556 0.0516123492 0.1294627488 0.0164227969 0.1631180000 960694369 0 402718720 -0.0845219791 -0.0734241977 0.2331755161 690 1305031125.1510369778 0.0288355015 0.0515793393 0.1294627488 0.0164140633 0.1755440000 960697217 0 402718720 -0.0852836296 -0.0817593560 0.2369640172 691 1305031125.1870639324 0.0245293323 0.0515401931 0.1294627488 0.0164139583 0.1705430000 960700289 0 402718720 -0.0861826837 -0.0856450424 0.2410327941 692 1305031125.2190179825 0.0263674948 0.0515038164 0.1294627488 0.0164057872 0.1609320000 960703193 0 402718720 -0.0889932439 -0.0944039747 0.2447076738 693 1305031125.2506420612 0.0302001126 0.0514730751 0.1294627488 0.0163976116 0.1643600000 960706041 0 402718720 -0.0914614275 -0.1069461554 0.2479595542 694 1305031125.2863960266 0.0279963445 0.0514392470 0.1294627488 0.0163872286 0.1585550000 960709057 0 402718720 -0.0930977240 -0.1123540178 0.2505931258 695 1305031125.3191399574 0.0266849417 0.0514036293 0.1294627488 0.0163786001 0.1694620000 960712017 0 402718720 -0.0933130085 -0.1179490611 0.2534516156 696 1305031125.3488988876 0.0291752443 0.0513716919 0.1294627488 0.0163683206 0.1619890000 960714809 0 402718720 -0.0961427689 -0.1265979260 0.2564644217 697 1305031125.3867919445 0.0280303992 0.0513382037 0.1294627488 0.0163680180 0.1590140000 960717937 0 402718720 -0.0976697877 -0.1298160702 0.2595389187 698 1305031125.4195740223 0.0272540338 0.0513036992 0.1294627488 0.0163573784 0.1579710000 960720841 0 402718720 -0.0969849974 -0.1346725076 0.2625413835 699 1305031125.4512319565 0.0299935751 0.0512732126 0.1294627488 0.0163526798 0.1611430000 960723745 0 402718720 -0.0993388370 -0.1406423151 0.2660037577 700 1305031125.4869990349 0.0329085700 0.0512469774 0.1294627488 0.0163518069 0.1653810000 960726761 0 402718720 -0.0996323302 -0.1506188661 0.2683961391 701 1305031125.5193541050 0.0331493393 0.0512211605 0.1294627488 0.0163463139 0.1583800000 960729721 0 402718720 -0.0998159871 -0.1534905881 0.2706412077 702 1305031125.5510499477 0.0338704214 0.0511964443 0.1294627488 0.0163371466 0.1582360000 960732569 0 402718720 -0.1002611220 -0.1559921652 0.2720063329 703 1305031125.5853030682 0.0347641110 0.0511730698 0.1294627488 0.0163255717 0.1574790000 960735529 0 402718720 -0.1003335193 -0.1582323164 0.2728895545 704 1305031125.6178700924 0.0378043056 0.0511540800 0.1294627488 0.0163331836 0.1559730000 960738489 0 402718720 -0.1010502651 -0.1625105143 0.2727243006 705 1305031125.6505749226 0.0423210561 0.0511415509 0.1294627488 0.0163249248 0.1681080000 960741393 0 402718720 -0.1023278162 -0.1674084365 0.2714108229 706 1305031125.6846020222 0.0435112007 0.0511307431 0.1294627488 0.0163213726 0.1584780000 960744297 0 402718720 -0.1027378663 -0.1669723243 0.2694074810 707 1305031125.7156689167 0.0437661335 0.0511203264 0.1294627488 0.0163389087 0.1598540000 960747201 0 402718720 -0.1019037813 -0.1645474136 0.2669616640 708 1305031125.7512919903 0.0376451612 0.0511012936 0.1294627488 0.0163380546 0.1911210000 960750217 0 402718720 -0.0979951769 -0.1554384977 0.2633973360 709 1305031125.7868049145 0.0399515890 0.0510855677 0.1294627488 0.0163304628 0.1627510000 960753233 0 402718720 -0.0988441035 -0.1507535726 0.2605694532 710 1305031125.8194499016 0.0398582034 0.0510697545 0.1294627488 0.0163225732 0.1801030000 960756193 0 402718720 -0.0977244228 -0.1449559778 0.2571098804 711 1305031125.8547739983 0.0356889740 0.0510481219 0.1294627488 0.0163184064 0.1704370000 960759097 0 402718720 -0.0978423506 -0.1311814189 0.2531180680 712 1305031125.8866450787 0.0413168631 0.0510344544 0.1294627488 0.0163148693 0.1640040000 960762057 0 402718720 -0.0985600799 -0.1277299374 0.2494793683 713 1305031125.9193339348 0.0396535285 0.0510184924 0.1294627488 0.0163184619 0.1705090000 960765017 0 402718720 -0.0995398313 -0.1148648858 0.2465663105 714 1305031125.9552519321 0.0445337035 0.0510094100 0.1294627488 0.0163165416 0.1669520000 960767977 0 402718720 -0.1000382006 -0.1121419966 0.2436059862 715 1305031125.9870939255 0.0445709042 0.0510004051 0.1294627488 0.0163106219 0.1960090000 960770881 0 402718720 -0.0971508697 -0.1009980887 0.2402007282 716 1305031126.0195720196 0.0427303053 0.0509888547 0.1294627488 0.0163027269 0.1768650000 960773841 0 402718720 -0.0952357054 -0.0888331160 0.2375554442 717 1305031126.0550379753 0.0410408676 0.0509749802 0.1294627488 0.0162977906 0.1782090000 960776801 0 402718720 -0.0916442946 -0.0770687312 0.2351842821 718 1305031126.0870759487 0.0467078611 0.0509690372 0.1294627488 0.0162888881 0.1679520000 960779705 0 402718720 -0.0883695409 -0.0698991045 0.2330047786 719 1305031126.1194519997 0.0456147194 0.0509615903 0.1294627488 0.0162797290 0.1858360000 960782665 0 402718720 -0.0876854509 -0.0561483540 0.2301958501 720 1305031126.1549999714 0.0492292903 0.0509591843 0.1294627488 0.0162705275 0.1790210000 960785569 0 402718720 -0.0851712152 -0.0491027832 0.2287885696 721 1305031126.1871740818 0.0502303429 0.0509581734 0.1294627488 0.0162689811 0.1729480000 960788529 0 402718720 -0.0846011117 -0.0321443118 0.2267914414 722 1305031126.2194728851 0.0554491989 0.0509643937 0.1294627488 0.0162783031 0.1744430000 960791489 0 402718720 -0.0813715905 -0.0264455359 0.2247781605 723 1305031126.2552359104 0.0537140742 0.0509681968 0.1294627488 0.0162768835 0.1675500000 960794505 0 402718720 -0.0772416368 -0.0120189143 0.2218277305 724 1305031126.2871050835 0.0614054687 0.0509826130 0.1294627488 0.0162696495 0.1560040000 960797353 0 402718720 -0.0758270249 -0.0042892913 0.2199407220 725 1305031126.3197870255 0.0598000959 0.0509947750 0.1294627488 0.0162636017 0.1744710000 960800313 0 402718720 -0.0758459046 0.0108305579 0.2168765515 726 1305031126.3554151058 0.0645729899 0.0510134778 0.1294627488 0.0162549895 0.1509140000 960803273 0 402718720 -0.0756357163 0.0171393938 0.2150292844 727 1305031126.3874828815 0.0673525706 0.0510359525 0.1294627488 0.0162520821 0.1542590000 960806233 0 402718720 -0.0792240724 0.0293563996 0.2115811408 728 1305031126.4197928905 0.0714912489 0.0510640504 0.1294627488 0.0162420239 0.1428420000 960809081 0 402718720 -0.0794631690 0.0358007103 0.2098099887 729 1305031126.4553799629 0.0754538029 0.0510975069 0.1294627488 0.0162416777 0.1385490000 960812041 0 402718720 -0.0802287757 0.0421643481 0.2075223476 730 1305031126.4903860092 0.0821253210 0.0511400107 0.1294627488 0.0162394126 0.1618870000 960815057 0 402718720 -0.0808540508 0.0488431230 0.2047603428 731 1305031126.5223209858 0.0786819458 0.0511776878 0.1294627488 0.0162428858 0.1444560000 960817961 0 402718720 -0.0819057599 0.0634977892 0.2009422481 732 1305031126.5582089424 0.0851602405 0.0512241120 0.1294627488 0.0162417695 0.1500390000 960820977 0 402718720 -0.0811132044 0.0692911372 0.1997532547 733 1305031126.5901761055 0.0872477069 0.0512732574 0.1294627488 0.0162310243 0.1375490000 960823881 0 402718720 -0.0794179365 0.0753725246 0.1979632974 734 1305031126.6186869144 0.0891957358 0.0513249229 0.1294627488 0.0162200627 0.1366320000 960826673 0 402718720 -0.0789267197 0.0817756876 0.1965439916 735 1305031126.6544740200 0.0911376923 0.0513790900 0.1294627488 0.0162227582 0.1457400000 960829745 0 402718720 -0.0785202831 0.0865735263 0.1947590113 736 1305031126.6900219917 0.0954677165 0.0514389930 0.1294627488 0.0162126154 0.1345720000 960832761 0 402718720 -0.0777316988 0.0905212015 0.1928817779 737 1305031126.7157700062 0.0960895047 0.0514995771 0.1294627488 0.0162028503 0.1450030000 960835441 0 402718720 -0.0765491650 0.0956115872 0.1907369196 738 1305031126.7553739548 0.0971685648 0.0515614592 0.1294627488 0.0161934515 0.1324250000 960838569 0 402718720 -0.0758535266 0.0989052877 0.1882742494 739 1305031126.7875649929 0.0988603830 0.0516254632 0.1294627488 0.0161843270 0.1601870000 960841473 0 402718720 -0.0747473091 0.1024350822 0.1857362390 740 1305031126.8199288845 0.0985616073 0.0516888904 0.1294627488 0.0161762691 0.1528320000 960844377 0 402718720 -0.0736214519 0.1064570248 0.1831722260 741 1305031126.8583779335 0.0986610204 0.0517522806 0.1294627488 0.0161656222 0.1311750000 960847505 0 402718720 -0.0724977553 0.1102029830 0.1806460023 742 1305031126.8881540298 0.0980601981 0.0518146902 0.1294627488 0.0161553925 0.1314200000 960850353 0 402718720 -0.0724955946 0.1128389314 0.1782624125 743 1305031126.9194090366 0.0971225202 0.0518756698 0.1294627488 0.0161447600 0.1302440000 960853201 0 402718720 -0.0724832714 0.1148805767 0.1762954146 744 1305031126.9555010796 0.0964711010 0.0519356099 0.1294627488 0.0161366282 0.1281730000 960856217 0 402718720 -0.0723767951 0.1164115444 0.1746741384 745 1305031126.9873158932 0.0962431803 0.0519950831 0.1294627488 0.0161265606 0.1412330000 960859177 0 402718720 -0.0726847872 0.1169245094 0.1732969582 746 1305031127.0195240974 0.0957939103 0.0520537947 0.1294627488 0.0161163488 0.1297060000 960862025 0 402718720 -0.0723876506 0.1168533713 0.1722810566 747 1305031127.0533180237 0.0947396010 0.0521109377 0.1294627488 0.0161091747 0.1312130000 960864985 0 402718720 -0.0716345459 0.1173903197 0.1716985554 748 1305031127.0886490345 0.0926657766 0.0521651554 0.1294627488 0.0161017544 0.1312000000 960868001 0 402718720 -0.0713652149 0.1179821491 0.1715388894 749 1305031127.1209630966 0.0920757428 0.0522184405 0.1294627488 0.0160971883 0.1318530000 960870849 0 402718720 -0.0719237253 0.1169789732 0.1715950221 750 1305031127.1576919556 0.0908907056 0.0522700036 0.1294627488 0.0160869166 0.1342320000 960873921 0 402718720 -0.0721315369 0.1155824140 0.1716726273 751 1305031127.1875000000 0.0897757336 0.0523199446 0.1294627488 0.0160792180 0.1348180000 960876769 0 402718720 -0.0715392828 0.1146654710 0.1721609831 752 1305031127.2218310833 0.0883370787 0.0523678397 0.1294627488 0.0160719933 0.1461440000 960879729 0 402718720 -0.0711374804 0.1142827645 0.1728051603 753 1305031127.2597610950 0.0862148777 0.0524127893 0.1294627488 0.0160661500 0.1342110000 960882801 0 402718720 -0.0714220107 0.1123370454 0.1735348850 754 1305031127.2870380878 0.0851405561 0.0524561948 0.1294627488 0.0160631039 0.1346590000 960885537 0 402718720 -0.0713282675 0.1109456867 0.1745875031 755 1305031127.3204679489 0.0839161426 0.0524978637 0.1294627488 0.0160538305 0.1469670000 960888497 0 402718720 -0.0721557215 0.1098551154 0.1759315133 756 1305031127.3534069061 0.0839697793 0.0525394932 0.1294627488 0.0160465911 0.1347580000 960891401 0 402718720 -0.0728343278 0.1064904183 0.1772834212 757 1305031127.3837130070 0.0834072605 0.0525802696 0.1294627488 0.0160378427 0.1360740000 960894305 0 402718720 -0.0727660879 0.1044913307 0.1788491756 758 1305031127.4196500778 0.0818220526 0.0526188472 0.1294627488 0.0160289119 0.1346920000 960897265 0 402718720 -0.0727193505 0.1034282148 0.1807101518 759 1305031127.4542460442 0.0816256776 0.0526570643 0.1294627488 0.0160277049 0.1361440000 960900281 0 402718720 -0.0733552799 0.1010350436 0.1823087186 760 1305031127.4872000217 0.0808872208 0.0526942093 0.1294627488 0.0160299071 0.1496150000 960903185 0 402718720 -0.0736372843 0.0996787474 0.1840514392 761 1305031127.5218999386 0.0806074217 0.0527308889 0.1294627488 0.0160200784 0.1352630000 960906201 0 402718720 -0.0733947158 0.0993751809 0.1859258562 762 1305031127.5537250042 0.0813111141 0.0527683958 0.1294627488 0.0160185370 0.1341310000 960909049 0 402718720 -0.0740461498 0.0967904180 0.1875897944 763 1305031127.5866320133 0.0813317820 0.0528058314 0.1294627488 0.0160093138 0.1349320000 960912009 0 402718720 -0.0737648159 0.0952497721 0.1888785958 764 1305031127.6206569672 0.0811081827 0.0528428764 0.1294627488 0.0159995838 0.1347570000 960914969 0 402718720 -0.0734087303 0.0950908512 0.1903448701 765 1305031127.6546559334 0.0817754567 0.0528806967 0.1294627488 0.0159901666 0.1335330000 960917873 0 402718720 -0.0735795572 0.0936682448 0.1914754808 766 1305031127.6871099472 0.0820550174 0.0529187833 0.1294627488 0.0159799676 0.1347660000 960920833 0 402718720 -0.0732002482 0.0917844847 0.1922724694 767 1305031127.7232100964 0.0815548897 0.0529561185 0.1294627488 0.0159710536 0.1346990000 960923849 0 402718720 -0.0727723241 0.0918660760 0.1929991990 768 1305031127.7546939850 0.0813387260 0.0529930751 0.1294627488 0.0159615830 0.1346350000 960926697 0 402718720 -0.0727761462 0.0912358686 0.1935179681 769 1305031127.7876410484 0.0816216022 0.0530303033 0.1294627488 0.0159565414 0.1349710000 960929713 0 402718720 -0.0730899721 0.0892669559 0.1937803924 770 1305031127.8201279640 0.0810129866 0.0530666445 0.1294627488 0.0159475126 0.1484990000 960932561 0 402718720 -0.0729343221 0.0888476670 0.1937189400 771 1305031127.8551321030 0.0806562901 0.0531024287 0.1294627488 0.0159371601 0.1346090000 960935521 0 402718720 -0.0735935047 0.0886658058 0.1938041002 772 1305031127.8871219158 0.0806092322 0.0531380593 0.1294627488 0.0159280714 0.1349040000 960938481 0 402718720 -0.0745215714 0.0876450911 0.1939024478 773 1305031127.9225599766 0.0807931870 0.0531738356 0.1294627488 0.0159190296 0.1344580000 960941497 0 402718720 -0.0751078799 0.0871859118 0.1944583207 774 1305031127.9550879002 0.0802791491 0.0532088554 0.1294627488 0.0159105320 0.1342460000 960944401 0 402718720 -0.0752051324 0.0875141546 0.1953662634 775 1305031127.9870929718 0.0793228671 0.0532425509 0.1294627488 0.0159003973 0.1469250000 960947305 0 402718720 -0.0753970668 0.0874534771 0.1966556907 776 1305031128.0217759609 0.0789765418 0.0532757133 0.1294627488 0.0158929455 0.1625330000 960950321 0 402718720 -0.0752286464 0.0873250589 0.1983772516 777 1305031128.0557179451 0.0787784755 0.0533085354 0.1294627488 0.0158860638 0.1356940000 960953225 0 402718720 -0.0750536919 0.0864494890 0.2005987614 778 1305031128.0872058868 0.0798968598 0.0533427106 0.1294627488 0.0158773063 0.1361710000 960956129 0 402718720 -0.0753961653 0.0841194540 0.2023284137 779 1305031128.1247460842 0.0804724768 0.0533775370 0.1294627488 0.0158680556 0.1353070000 960959201 0 402718720 -0.0747004673 0.0826142728 0.2040088773 780 1305031128.1577820778 0.0805140510 0.0534123274 0.1294627488 0.0158593190 0.1485590000 960962161 0 402718720 -0.0735537261 0.0815845504 0.2056795657 781 1305031128.1872210503 0.0813145936 0.0534480537 0.1294627488 0.0158515368 0.1355520000 960964953 0 402718720 -0.0733656064 0.0795770288 0.2066632360 782 1305031128.2254419327 0.0814794749 0.0534838995 0.1294627488 0.0158444147 0.1346000000 960968025 0 402718720 -0.0720573813 0.0786311105 0.2074530870 783 1305031128.2560069561 0.0808702707 0.0535188757 0.1294627488 0.0158348940 0.1345820000 960970873 0 402718720 -0.0712953061 0.0786705464 0.2080765218 784 1305031128.2912750244 0.0813852698 0.0535544196 0.1294627488 0.0158276565 0.1330840000 960973889 0 402718720 -0.0714887157 0.0775705650 0.2085077614 785 1305031128.3241701126 0.0812566951 0.0535897091 0.1294627488 0.0158187220 0.1347780000 960976793 0 402718720 -0.0713845938 0.0772149414 0.2085758001 786 1305031128.3552060127 0.0807937682 0.0536243199 0.1294627488 0.0158091174 0.1346390000 960979697 0 402718720 -0.0715492964 0.0772880167 0.2085469514 787 1305031128.3913969994 0.0807362273 0.0536587696 0.1294627488 0.0157991904 0.1347110000 960982713 0 402718720 -0.0728078932 0.0765888318 0.2084713578 788 1305031128.4236090183 0.0808007941 0.0536932138 0.1294627488 0.0157892463 0.1348020000 960985617 0 402718720 -0.0732956380 0.0757402405 0.2083233297 789 1305031128.4554989338 0.0804761946 0.0537271592 0.1294627488 0.0157809253 0.1343910000 960988521 0 402718720 -0.0738510117 0.0754319429 0.2081847936 790 1305031128.4895229340 0.0803591311 0.0537608706 0.1294627488 0.0157714265 0.1464070000 960991537 0 402718720 -0.0742056072 0.0748097673 0.2081632763 791 1305031128.5236039162 0.0802258775 0.0537943283 0.1294627488 0.0157616329 0.1335230000 960994441 0 402718720 -0.0746521950 0.0739548206 0.2081410885 792 1305031128.5556390285 0.0799722299 0.0538273812 0.1294627488 0.0157523365 0.1346600000 960997345 0 402718720 -0.0749651343 0.0734145492 0.2080026269 793 1305031128.5914599895 0.0803248957 0.0538607954 0.1294627488 0.0157435933 0.1340860000 961000361 0 402718720 -0.0754017308 0.0720108971 0.2077921480 794 1305031128.6233680248 0.0803939179 0.0538942125 0.1294627488 0.0157345696 0.1340640000 961003265 0 402718720 -0.0755328164 0.0708913952 0.2074896395 795 1305031128.6555540562 0.0801096708 0.0539271879 0.1294627488 0.0157265854 0.1466220000 961006169 0 402718720 -0.0752765313 0.0706247464 0.2073217481 796 1305031128.6904489994 0.0799646005 0.0539598982 0.1294627488 0.0157181262 0.1337990000 961009185 0 402718720 -0.0751356557 0.0701575875 0.2069593817 797 1305031128.7229759693 0.0796758533 0.0539921641 0.1294627488 0.0157094005 0.1535250000 961012089 0 402718720 -0.0747265294 0.0697339550 0.2065837532 798 1305031128.7546460629 0.0791323036 0.0540236681 0.1294627488 0.0157007559 0.1601290000 961014993 0 402718720 -0.0747205541 0.0697590783 0.2060474008 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:01:44 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 -nan 0.1276110000 960279644 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 1311867718.6768438816 0.0027229167 0.0023127843 0.0027229167 0.0021582129 0.1060770000 976388601 0 402718720 0.0005169673 -0.0010942587 0.0001797079 3 1311867718.7114279270 0.0031995513 0.0026083733 0.0031995513 0.0034751438 0.1288830000 976078865 0 402718720 0.0005409417 -0.0010935970 0.0002242683 4 1311867718.7410299778 0.0041529406 0.0029945151 0.0041529406 0.0042844355 0.1096090000 976082057 0 402718720 0.0010218472 -0.0015514682 0.0003014610 5 1311867718.7767970562 0.0055240276 0.0035004176 0.0055240276 0.0043341716 0.1100010000 976085073 0 402718720 0.0021301867 -0.0026189117 0.0001469932 6 1311867718.8094089031 0.0056028431 0.0038508219 0.0056028431 0.0041703986 0.1116070000 976088777 0 402718720 0.0020322260 -0.0026803548 0.0002582482 7 1311867718.8408079147 0.0062578642 0.0041946851 0.0062578642 0.0038598055 0.1116420000 976091625 0 402718720 0.0026876219 -0.0024254236 0.0003465009 8 1311867718.8767778873 0.0070302403 0.0045491295 0.0070302403 0.0036780810 0.1244150000 976094641 0 402718720 0.0029814087 -0.0028204881 0.0004534879 9 1311867718.9088680744 0.0079929754 0.0049317790 0.0079929754 0.0035523673 0.1121900000 976097489 0 402718720 0.0037121400 -0.0027851828 0.0006460219 10 1311867718.9438331127 0.0086711021 0.0053057113 0.0086711021 0.0033985117 0.1162350000 976102105 0 402718720 0.0044354796 -0.0028037913 0.0010428175 11 1311867718.9784109592 0.0095560504 0.0056921058 0.0095560504 0.0033703323 0.1168170000 976105121 0 402718720 0.0048617283 -0.0037254551 0.0012518374 12 1311867719.0091300011 0.0099222343 0.0060446165 0.0099222343 0.0032174050 0.1444880000 976107913 0 402718720 0.0048088687 -0.0041618226 0.0013777412 13 1311867719.0441620350 0.0108104292 0.0064112175 0.0108104292 0.0031161377 0.1199630000 976110929 0 402718720 0.0055907220 -0.0042314716 0.0016271645 14 1311867719.0776190758 0.0118955960 0.0068029588 0.0118955960 0.0031031646 0.1198400000 976113889 0 402718720 0.0065814294 -0.0046501020 0.0017764507 15 1311867719.1086950302 0.0124966996 0.0071825415 0.0124966996 0.0029933884 0.1208090000 976116793 0 402718720 0.0069195004 -0.0050438484 0.0020175052 16 1311867719.1437010765 0.0134302201 0.0075730214 0.0134302201 0.0029043802 0.1218230000 976119753 0 402718720 0.0076495381 -0.0050758203 0.0022301273 17 1311867719.1810290813 0.0144190295 0.0079757278 0.0144190295 0.0028888199 0.1224100000 976122769 0 402718720 0.0082621248 -0.0055736508 0.0025814788 18 1311867719.2127099037 0.0148748215 0.0083590108 0.0148748215 0.0028234041 0.1299610000 976128873 0 402718720 0.0084288502 -0.0059010778 0.0028533894 19 1311867719.2412090302 0.0157023631 0.0087455030 0.0157023631 0.0028010640 0.1215010000 976131665 0 402718720 0.0087147262 -0.0063789217 0.0030912412 20 1311867719.2779469490 0.0170079786 0.0091586268 0.0170079786 0.0031220764 0.1226870000 976134625 0 402718720 0.0094199432 -0.0066748252 0.0032741667 21 1311867719.3104898930 0.0180278476 0.0095809706 0.0180278476 0.0031008416 0.1239290000 976137585 0 402718720 0.0101840906 -0.0067507117 0.0034052785 22 1311867719.3413150311 0.0193963572 0.0100271246 0.0193963572 0.0032201506 0.1245090000 976140489 0 402718720 0.0111436546 -0.0071410225 0.0034851348 23 1311867719.3772718906 0.0210452341 0.0105061728 0.0210452341 0.0032580040 0.1250320000 976143449 0 402718720 0.0122168250 -0.0079130773 0.0034747783 24 1311867719.4105761051 0.0215957966 0.0109682405 0.0215957966 0.0032139849 0.1243640000 976146409 0 402718720 0.0124892853 -0.0081542041 0.0034862536 25 1311867719.4427709579 0.0226443559 0.0114352851 0.0226443559 0.0032988961 0.1250160000 976149369 0 402718720 0.0133481380 -0.0086143874 0.0035934821 26 1311867719.4787840843 0.0232544877 0.0118898698 0.0232544877 0.0033792888 0.1236380000 976152329 0 402718720 0.0132321864 -0.0100216521 0.0035410211 27 1311867719.5104370117 0.0230178181 0.0123020160 0.0232544877 0.0035867425 0.1253010000 976155233 0 402718720 0.0125922123 -0.0103839636 0.0036535035 28 1311867719.5449650288 0.0237061065 0.0127093050 0.0237061065 0.0036216726 0.1363840000 976158193 0 402718720 0.0126838712 -0.0101487897 0.0040005981 29 1311867719.5771939754 0.0249653142 0.0131319260 0.0249653142 0.0036305276 0.1400740000 976161153 0 402718720 0.0133536160 -0.0108867381 0.0040475819 30 1311867719.6112511158 0.0255263541 0.0135450736 0.0255263541 0.0035902254 0.1277900000 976164113 0 402718720 0.0132173095 -0.0112196663 0.0043088007 31 1311867719.6421909332 0.0261509456 0.0139517146 0.0261509456 0.0035459832 0.1283370000 976166961 0 402718720 0.0135939652 -0.0106698899 0.0046814848 32 1311867719.6770479679 0.0270636734 0.0143614633 0.0270636734 0.0034945196 0.1286030000 976169977 0 402718720 0.0138400849 -0.0110429544 0.0051468019 33 1311867719.7107939720 0.0279019661 0.0147717816 0.0279019661 0.0034448918 0.1369960000 976172881 0 402718720 0.0142876906 -0.0107122678 0.0056484295 34 1311867719.7442650795 0.0289834719 0.0151897725 0.0289834719 0.0034002388 0.1304490000 976182185 0 402718720 0.0150893042 -0.0100088352 0.0061905785 35 1311867719.7861878872 0.0304513630 0.0156258179 0.0304513630 0.0033762563 0.1299670000 976185425 0 402718720 0.0157423224 -0.0103716683 0.0066386713 36 1311867719.8099169731 0.0313422978 0.0160623868 0.0313422978 0.0033425703 0.1320350000 976188049 0 402718720 0.0160466507 -0.0108184721 0.0070267851 37 1311867719.8454990387 0.0328115448 0.0165150668 0.0328115448 0.0034057321 0.1322770000 976191065 0 402718720 0.0168614518 -0.0118074846 0.0070709083 38 1311867719.8771090508 0.0328110270 0.0169439078 0.0328115448 0.0033626640 0.1520140000 976193969 0 402718720 0.0166804679 -0.0120184785 0.0073744920 39 1311867719.9114089012 0.0345185585 0.0173945399 0.0345185585 0.0033543082 0.1380460000 976196985 0 402718720 0.0177460592 -0.0124605373 0.0076793008 40 1311867719.9461970329 0.0354876854 0.0178468685 0.0354876854 0.0033173400 0.1335010000 976199945 0 402718720 0.0184008591 -0.0133070378 0.0080118338 41 1311867719.9807810783 0.0374699123 0.0183254793 0.0374699123 0.0032976608 0.1461720000 976202905 0 402718720 0.0196958240 -0.0139902243 0.0080936300 42 1311867720.0117020607 0.0390104242 0.0188179780 0.0390104242 0.0032670048 0.1345740000 976205809 0 402718720 0.0208828580 -0.0141553562 0.0083345585 43 1311867720.0452380180 0.0417777672 0.0193519266 0.0417777672 0.0032434418 0.1373920000 976208713 0 402718720 0.0233802851 -0.0141271185 0.0086773746 44 1311867720.0772819519 0.0447969027 0.0199302215 0.0447969027 0.0032695375 0.1355950000 976211673 0 402718720 0.0261830743 -0.0145134246 0.0091030328 45 1311867720.1172130108 0.0467181727 0.0205255093 0.0467181727 0.0032587377 0.1369360000 976214801 0 402718720 0.0279737432 -0.0147277815 0.0095863007 46 1311867720.1451559067 0.0470468290 0.0211020598 0.0470468290 0.0032239066 0.1360590000 976217537 0 402718720 0.0281287022 -0.0150352884 0.0100269895 47 1311867720.1781630516 0.0480730869 0.0216759114 0.0480730869 0.0031955271 0.1357480000 976220441 0 402718720 0.0292366035 -0.0148297939 0.0103726145 48 1311867720.2094950676 0.0489987843 0.0222451379 0.0489987843 0.0031675760 0.1489590000 976223345 0 402718720 0.0301193595 -0.0146548487 0.0108581977 49 1311867720.2421469688 0.0500771515 0.0228131382 0.0500771515 0.0031371784 0.1368440000 976226305 0 402718720 0.0311655588 -0.0142626287 0.0113436384 50 1311867720.2770779133 0.0517180450 0.0233912363 0.0517180450 0.0031744314 0.1388050000 976229265 0 402718720 0.0324593410 -0.0142860869 0.0120477071 51 1311867720.3094570637 0.0525960550 0.0239638798 0.0525960550 0.0031503526 0.1393300000 976232169 0 402718720 0.0334126763 -0.0135908071 0.0129424836 52 1311867720.3430728912 0.0540892817 0.0245432145 0.0540892817 0.0031599527 0.1399540000 976235129 0 402718720 0.0347172022 -0.0134482067 0.0138177155 53 1311867720.3779859543 0.0560313985 0.0251373312 0.0560313985 0.0032288989 0.1694350000 976238033 0 402718720 0.0359857753 -0.0146904346 0.0142064700 54 1311867720.4096798897 0.0581997745 0.0257495986 0.0581997745 0.0034603951 0.1424150000 976240937 0 402718720 0.0371737033 -0.0155699430 0.0146400696 55 1311867720.4461109638 0.0593337305 0.0263602192 0.0593337305 0.0034530954 0.1410290000 976244009 0 402718720 0.0382291265 -0.0155541822 0.0152032943 56 1311867720.4799289703 0.0609393120 0.0269777030 0.0609393120 0.0035159881 0.1410120000 976246969 0 402718720 0.0395020060 -0.0158371031 0.0152621847 57 1311867720.5104389191 0.0614261404 0.0275820616 0.0614261404 0.0035496838 0.1412910000 976249817 0 402718720 0.0399547331 -0.0161779448 0.0151894456 58 1311867720.5467319489 0.0630880818 0.0281942343 0.0630880818 0.0036333695 0.1529770000 976252889 0 402718720 0.0407003462 -0.0163224135 0.0155882519 59 1311867720.5793280602 0.0634688586 0.0287921093 0.0634688586 0.0036750036 0.1550240000 976255793 0 402718720 0.0410356447 -0.0168096200 0.0158088952 60 1311867720.6121249199 0.0653159618 0.0294008402 0.0653159618 0.0036614196 0.1424600000 976258697 0 402718720 0.0421882868 -0.0172588136 0.0158921331 61 1311867720.6463210583 0.0660585091 0.0300017856 0.0660585091 0.0036527905 0.1423900000 976261713 0 402718720 0.0422480032 -0.0175834745 0.0162882693 62 1311867720.6798269749 0.0669302642 0.0305974062 0.0669302642 0.0036362629 0.1427070000 976264561 0 402718720 0.0424578376 -0.0180492327 0.0162918307 63 1311867720.7102439404 0.0682217926 0.0311946187 0.0682217926 0.0036283131 0.1432670000 976267465 0 402718720 0.0430026427 -0.0190087724 0.0162211545 64 1311867720.7451629639 0.0691331849 0.0317874088 0.0691331849 0.0036231384 0.1411660000 976270425 0 402718720 0.0430348851 -0.0192418862 0.0163060986 65 1311867720.7790179253 0.1112897694 0.0330105220 0.1112897694 0.0049898545 0.1524810000 976273441 0 402718720 0.0858101025 -0.0169422571 0.0258437879 66 1311867720.8115909100 0.1123186201 0.0342121599 0.1123186201 0.0049645098 0.1420530000 976289145 0 402718720 0.0860224813 -0.0182965603 0.0259778742 67 1311867720.8467299938 0.1132825837 0.0353923155 0.1132825837 0.0049556998 0.1421730000 976292161 0 402718720 0.0864490867 -0.0188105069 0.0265713856 68 1311867720.8813319206 0.1134544909 0.0365402886 0.1134544909 0.0049442896 0.1531820000 976295121 0 402718720 0.0862709284 -0.0191045329 0.0269570705 69 1311867720.9149661064 0.1145509183 0.0376708775 0.1145509183 0.0049184934 0.1432930000 976298025 0 402718720 0.0868029967 -0.0199060533 0.0272728596 70 1311867720.9500010014 0.1151654422 0.0387779427 0.1151654422 0.0048857725 0.1438290000 976300985 0 402718720 0.0870738253 -0.0204034280 0.0276044346 71 1311867720.9797990322 0.1155309007 0.0398589702 0.1155309007 0.0048576282 0.1439600000 976303777 0 402718720 0.0871913061 -0.0206257310 0.0277734101 72 1311867721.0093889236 0.1155599952 0.0409103734 0.1155599952 0.0048239088 0.1427900000 976306625 0 402718720 0.0870063603 -0.0210823901 0.0277714562 73 1311867721.0478379726 0.1162328646 0.0419421883 0.1162328646 0.0047926967 0.1562850000 976309753 0 402718720 0.0872946158 -0.0214298256 0.0278103426 74 1311867721.0794439316 0.1170850694 0.0429576327 0.1170850694 0.0047661445 0.1447040000 976312601 0 402718720 0.0878487453 -0.0219059084 0.0279933233 75 1311867721.1103579998 0.1176121905 0.0439530268 0.1176121905 0.0047435381 0.1445640000 976315505 0 402718720 0.0880051330 -0.0221869051 0.0281463563 76 1311867721.1467890739 0.1188978329 0.0449391426 0.1188978329 0.0047332911 0.1434290000 976318521 0 402718720 0.0884878561 -0.0227204431 0.0280949324 77 1311867721.1774179935 0.1197690070 0.0459109591 0.1197690070 0.0047676178 0.1450880000 976321425 0 402718720 0.0894582272 -0.0230995677 0.0282065533 78 1311867721.2112360001 0.1199582815 0.0468602837 0.1199582815 0.0047388783 0.1446480000 976324329 0 402718720 0.0892066956 -0.0236732960 0.0283567831 79 1311867721.2469010353 0.1209128946 0.0477976585 0.1209128946 0.0047279351 0.1449060000 976327345 0 402718720 0.0898814127 -0.0242718998 0.0283947904 80 1311867721.2800450325 0.1217848808 0.0487224988 0.1217848808 0.0047158688 0.1446790000 976330249 0 402718720 0.0901451707 -0.0249088127 0.0284948908 81 1311867721.3099579811 0.1227373555 0.0496362625 0.1227373555 0.0047017106 0.1449940000 976333097 0 402718720 0.0907340422 -0.0255364012 0.0286475960 82 1311867721.3483059406 0.1241345033 0.0505447776 0.1241345033 0.0046798990 0.1436460000 976336169 0 402718720 0.0917124078 -0.0258355383 0.0287367254 83 1311867721.3790040016 0.1248753741 0.0514403270 0.1248753741 0.0046540854 0.1647990000 976338961 0 402718720 0.0920046121 -0.0257900208 0.0288340021 84 1311867721.4092550278 0.1251904070 0.0523183041 0.1251904070 0.0046284512 0.1672130000 976341809 0 402718720 0.0917331725 -0.0262377728 0.0291150771 85 1311867721.4478130341 0.1258524209 0.0531834114 0.1258524209 0.0046016053 0.1459560000 976344993 0 402718720 0.0917953923 -0.0265687909 0.0294853505 86 1311867721.4768960476 0.1263313591 0.0540339689 0.1263313591 0.0045785938 0.1477920000 976347785 0 402718720 0.0918026865 -0.0268884078 0.0297083333 87 1311867721.5093359947 0.1269848049 0.0548724842 0.1269848049 0.0045698121 0.1475810000 976350633 0 402718720 0.0919804499 -0.0273654833 0.0299481209 88 1311867721.5451331139 0.1286823750 0.0557112330 0.1286823750 0.0045482398 0.1589180000 976353593 0 402718720 0.0931314752 -0.0282048360 0.0300844163 89 1311867721.5769670010 0.1295622885 0.0565410201 0.1295622885 0.0045262511 0.1479090000 976356385 0 402718720 0.0937381983 -0.0282361191 0.0304245856 90 1311867721.6129651070 0.1305778623 0.0573636517 0.1305778623 0.0045459876 0.1480010000 976359345 0 402718720 0.0941833928 -0.0288051348 0.0303645451 91 1311867721.6496050358 0.1311247051 0.0581742127 0.1311247051 0.0045686448 0.1473440000 976362417 0 402718720 0.0943642855 -0.0292209424 0.0301117375 92 1311867721.6800351143 0.1316269636 0.0589726122 0.1316269636 0.0045672861 0.1480410000 976365265 0 402718720 0.0945553705 -0.0288774855 0.0302931219 93 1311867721.7162289619 0.1316913217 0.0597545338 0.1316913217 0.0045588394 0.1639550000 976368337 0 402718720 0.0945588648 -0.0289887451 0.0305276997 94 1311867721.7467949390 0.1326672435 0.0605302009 0.1326672435 0.0045933007 0.1489570000 976371185 0 402718720 0.0946249962 -0.0299732871 0.0304970033 95 1311867721.7787001133 0.1329161227 0.0612921580 0.1329161227 0.0045699919 0.1496330000 976374089 0 402718720 0.0945798233 -0.0300113335 0.0306527093 96 1311867721.8154830933 0.1336297691 0.0620456748 0.1336297691 0.0045493000 0.1492210000 976377105 0 402718720 0.0947989598 -0.0303803440 0.0306988899 97 1311867721.8485159874 0.1341386884 0.0627889017 0.1341386884 0.0045287084 0.1477830000 976380065 0 402718720 0.0947281346 -0.0311764088 0.0305082910 98 1311867721.8778810501 0.1340256482 0.0635158073 0.1341386884 0.0045083544 0.1612310000 976382913 0 402718720 0.0943343192 -0.0311207082 0.0303783845 99 1311867721.9146931171 0.1341784298 0.0642295712 0.1341784298 0.0044861735 0.1483640000 976385705 0 402718720 0.0942070037 -0.0311718602 0.0302413292 100 1311867721.9467151165 0.1345347613 0.0649326231 0.1345347613 0.0044643430 0.1501260000 976388609 0 402718720 0.0941729322 -0.0316154584 0.0301013514 101 1311867721.9773728848 0.1347622722 0.0656240057 0.1347622722 0.0044682877 0.1502550000 976391513 0 402718720 0.0943579227 -0.0316302814 0.0298895389 102 1311867722.0166850090 0.1354109347 0.0663081913 0.1354109347 0.0044990737 0.1490850000 976394473 0 402718720 0.0943839476 -0.0321865566 0.0298042558 103 1311867722.0475180149 0.1360494792 0.0669852912 0.1360494792 0.0045020823 0.1507830000 976397209 0 402718720 0.0950491726 -0.0326247476 0.0295734424 104 1311867722.0800709724 0.1366446167 0.0676550924 0.1366446167 0.0044903193 0.1505600000 976400169 0 402718720 0.0952114537 -0.0329949483 0.0295450855 105 1311867722.1161251068 0.1372547448 0.0683179462 0.1372547448 0.0044754936 0.1504420000 976403185 0 402718720 0.0951961353 -0.0339015350 0.0295281708 106 1311867722.1479530334 0.1375429034 0.0689710119 0.1375429034 0.0044709570 0.1491040000 976406033 0 402718720 0.0949811190 -0.0343864486 0.0293614455 107 1311867722.1798410416 0.1385855079 0.0696216146 0.1385855079 0.0044517400 0.1634000000 976408937 0 402718720 0.0957324654 -0.0342739075 0.0298810638 108 1311867722.2146399021 0.1389938295 0.0702639500 0.1389938295 0.0044526588 0.1610090000 976411953 0 402718720 0.0958891064 -0.0349229388 0.0297894515 109 1311867722.2469589710 0.1399436146 0.0709032129 0.1399436146 0.0044350985 0.1493280000 976414857 0 402718720 0.0965063348 -0.0354787596 0.0298370980 110 1311867722.2780389786 0.1406171173 0.0715369757 0.1406171173 0.0044165770 0.1505100000 976417761 0 402718720 0.0970270783 -0.0353090279 0.0302404277 111 1311867722.3154170513 0.1401765943 0.0721553507 0.1406171173 0.0043967263 0.1509440000 976420777 0 402718720 0.0964403078 -0.0355872400 0.0301365834 112 1311867722.3488469124 0.1410769820 0.0727707224 0.1410769820 0.0043883825 0.1495610000 976423681 0 402718720 0.0969447047 -0.0363748893 0.0301562082 113 1311867722.3777940273 0.1409643143 0.0733742055 0.1410769820 0.0043724411 0.1514850000 976426529 0 402718720 0.0967429727 -0.0362675041 0.0303684212 114 1311867722.4150679111 0.1416396648 0.0739730253 0.1416396648 0.0043557511 0.1518400000 976429377 0 402718720 0.0969873294 -0.0368658081 0.0305572227 115 1311867722.4467909336 0.1417484581 0.0745623769 0.1417484581 0.0043846099 0.1524460000 976432281 0 402718720 0.0967568457 -0.0376988314 0.0308949556 116 1311867722.4777851105 0.1430680901 0.0751529434 0.1430680901 0.0044192432 0.1518300000 976435129 0 402718720 0.0975587517 -0.0376181267 0.0313353091 117 1311867722.5147399902 0.1437210441 0.0757389955 0.1437210441 0.0044034467 0.1577860000 976438089 0 402718720 0.0978538916 -0.0380205438 0.0319410637 118 1311867722.5469911098 0.1437810212 0.0763156229 0.1437810212 0.0043883363 0.1525390000 976440993 0 402718720 0.0976916999 -0.0382483825 0.0321858115 119 1311867722.5802359581 0.1442922205 0.0768868548 0.1442922205 0.0043772083 0.1528940000 976443897 0 402718720 0.0979856402 -0.0388028622 0.0326907262 120 1311867722.6146309376 0.1454529911 0.0774582392 0.1454529911 0.0043607374 0.1529930000 976446857 0 402718720 0.0989667848 -0.0395450071 0.0328277312 121 1311867722.6560258865 0.1463036537 0.0780272096 0.1463036537 0.0043470235 0.1529150000 976450041 0 402718720 0.0995676294 -0.0402470864 0.0328647383 122 1311867722.6778230667 0.1472023875 0.0785942193 0.1472023875 0.0043378191 0.1532240000 976452721 0 402718720 0.1002746373 -0.0406964049 0.0330236666 123 1311867722.7252709866 0.1477348208 0.0791563380 0.1477348208 0.0044013988 0.1532650000 976456017 0 402718720 0.1003938243 -0.0409840234 0.0331585333 124 1311867722.7449109554 0.1478518546 0.0797103341 0.1478518546 0.0044178152 0.1533420000 976458529 0 402718720 0.1004961133 -0.0413137302 0.0326918177 125 1311867722.7770080566 0.1475584507 0.0802531190 0.1478518546 0.0044585643 0.1545530000 976461489 0 402718720 0.0998331308 -0.0412692353 0.0325716808 126 1311867722.8162860870 0.1476881504 0.0807883177 0.1478518546 0.0044409018 0.1543900000 976464505 0 402718720 0.0994776711 -0.0413896181 0.0331292488 127 1311867722.8466939926 0.1487393230 0.0813233650 0.1487393230 0.0044608522 0.1545950000 976467353 0 402718720 0.0997709185 -0.0427782685 0.0337433629 128 1311867722.8819770813 0.1500754207 0.0818604904 0.1500754207 0.0044483707 0.1546860000 976470369 0 402718720 0.1002174616 -0.0437126085 0.0346728340 129 1311867722.9150629044 0.1525684893 0.0824086144 0.1525684893 0.0044480711 0.1542380000 976473105 0 402718720 0.1021755934 -0.0432324111 0.0358238630 130 1311867722.9485991001 0.1531464010 0.0829527512 0.1531464010 0.0044633260 0.1545990000 976501721 0 402718720 0.1022894308 -0.0440165773 0.0361143909 131 1311867722.9821140766 0.1541458517 0.0834962100 0.1541458517 0.0044477735 0.1550400000 976504625 0 402718720 0.1024271101 -0.0449894257 0.0371020325 132 1311867723.0147259235 0.1550524533 0.0840383028 0.1550524533 0.0044322074 0.1555300000 976507529 0 402718720 0.1030634940 -0.0444302969 0.0379487462 133 1311867723.0460629463 0.1558983475 0.0845786039 0.1558983475 0.0044460594 0.1744940000 976510377 0 402718720 0.1031393334 -0.0451353751 0.0386279449 134 1311867723.0845439434 0.1583509594 0.0851291438 0.1583509594 0.0044445908 0.1571670000 976513449 0 402718720 0.1047171727 -0.0464667417 0.0395660102 135 1311867723.1140980721 0.1592839509 0.0856784387 0.1592839509 0.0044305083 0.1579400000 976516297 0 402718720 0.1049252227 -0.0469738208 0.0403089337 136 1311867723.1505160332 0.1610025913 0.0862322928 0.1610025913 0.0044229834 0.1581660000 976519313 0 402718720 0.1058106869 -0.0479178019 0.0407843366 137 1311867723.1811029911 0.1616490334 0.0867827799 0.1616490334 0.0044093312 0.1569700000 976522161 0 402718720 0.1055455878 -0.0491544679 0.0411378071 138 1311867723.2201359272 0.1625107676 0.0873315334 0.1625107676 0.0043935634 0.1693010000 976525233 0 402718720 0.1055908725 -0.0499871150 0.0420407020 139 1311867723.2486810684 0.1650481671 0.0878906459 0.1650481671 0.0043919091 0.1568730000 976528025 0 402718720 0.1076099947 -0.0507915728 0.0424613953 140 1311867723.2846419811 0.1600232124 0.0884058785 0.1650481671 0.0044270055 0.1583580000 976531041 0 402718720 0.1022764444 -0.0507702753 0.0397981852 141 1311867723.3132460117 0.1588044167 0.0889051590 0.1650481671 0.0044140215 0.1588870000 976533833 0 402718720 0.1007552892 -0.0510545671 0.0391346067 142 1311867723.3499810696 0.1581697017 0.0893929374 0.1650481671 0.0044019798 0.1597790000 976536905 0 402718720 0.0995852277 -0.0508387983 0.0391924754 143 1311867723.3822429180 0.1585309058 0.0898764197 0.1650481671 0.0043906944 0.1749780000 976539865 0 402718720 0.0995066687 -0.0512281545 0.0397279300 144 1311867723.4193739891 0.1591838300 0.0903577212 0.1650481671 0.0044077149 0.1594410000 976542881 0 402718720 0.0999963060 -0.0516450927 0.0405986570 145 1311867723.4455900192 0.1591172069 0.0908319245 0.1650481671 0.0043968208 0.1596530000 976545617 0 402718720 0.0996456742 -0.0515118614 0.0404316112 146 1311867723.4825348854 0.1596511304 0.0913032890 0.1650481671 0.0043959338 0.1583270000 976548689 0 402718720 0.0992771760 -0.0516540222 0.0409048051 147 1311867723.5147960186 0.1599243581 0.0917700989 0.1650481671 0.0043824755 0.1613300000 976551537 0 402718720 0.0990872383 -0.0517007411 0.0410553887 148 1311867723.5451340675 0.1602152139 0.0922325659 0.1650481671 0.0043701207 0.1837940000 976554441 0 402718720 0.0987112522 -0.0520024672 0.0414869413 149 1311867723.5809938908 0.1607010961 0.0926920863 0.1650481671 0.0043591874 0.1819680000 976557457 0 402718720 0.0985536650 -0.0523686670 0.0418598317 150 1311867723.6132669449 0.1624319702 0.0931570188 0.1650481671 0.0043508179 0.1601930000 976560417 0 402718720 0.0998537764 -0.0526298285 0.0426130518 151 1311867723.6453940868 0.1621762067 0.0936140996 0.1650481671 0.0043373326 0.1615800000 976563265 0 402718720 0.0992964506 -0.0525969975 0.0427969694 152 1311867723.6809489727 0.1627327800 0.0940688277 0.1650481671 0.0043246036 0.1617250000 976566281 0 402718720 0.0994613990 -0.0531710275 0.0429248661 153 1311867723.7130429745 0.1633745134 0.0945218060 0.1650481671 0.0043132956 0.1796610000 976569185 0 402718720 0.0995826051 -0.0536354184 0.0434860364 154 1311867723.7471990585 0.1644013971 0.0949755696 0.1650481671 0.0043021423 0.1621880000 976572145 0 402718720 0.1002466530 -0.0538718440 0.0433017351 155 1311867723.7809250355 0.1649449021 0.0954269847 0.1650481671 0.0042917443 0.1606540000 976575105 0 402718720 0.1001089588 -0.0547116362 0.0432784297 156 1311867723.8157649040 0.1665773988 0.0958830771 0.1665773988 0.0042852672 0.1632740000 976578065 0 402718720 0.1011246368 -0.0554307550 0.0431672372 157 1311867723.8468959332 0.1681074798 0.0963431051 0.1681074798 0.0042737207 0.1611890000 976580969 0 402718720 0.1023811996 -0.0554114021 0.0435278714 158 1311867723.8826351166 0.1668832451 0.0967895617 0.1681074798 0.0042729466 0.1732020000 976583929 0 402718720 0.1006551161 -0.0559067577 0.0427402258 159 1311867723.9172909260 0.1672335863 0.0972326059 0.1681074798 0.0042671125 0.1637500000 976586777 0 402718720 0.1006646678 -0.0560215488 0.0426970758 160 1311867723.9490020275 0.1674824357 0.0976716673 0.1681074798 0.0042561853 0.1638120000 976589625 0 402718720 0.1008912176 -0.0552136004 0.0425550155 161 1311867723.9839010239 0.1690743119 0.0981151620 0.1690743119 0.0042564788 0.1848410000 976592641 0 402718720 0.1019939929 -0.0561166555 0.0429263748 162 1311867724.0132899284 0.1688213646 0.0985516200 0.1690743119 0.0042551005 0.1641360000 976595433 0 402718720 0.1016623452 -0.0560242161 0.0426768921 163 1311867724.0475380421 0.1702314019 0.0989913733 0.1702314019 0.0042450004 0.1642660000 976598449 0 402718720 0.1028882191 -0.0559342802 0.0429936647 164 1311867724.0824530125 0.1704099327 0.0994268523 0.1704099327 0.0042376135 0.1642990000 976601409 0 402718720 0.1027207151 -0.0563064590 0.0430279039 165 1311867724.1132431030 0.1696469188 0.0998524285 0.1704099327 0.0042259662 0.1658180000 976604313 0 402718720 0.1017535999 -0.0562407747 0.0426207446 166 1311867724.1547191143 0.1699462235 0.1002746803 0.1704099327 0.0042219614 0.1635000000 976607497 0 402718720 0.1019489020 -0.0557507575 0.0422813967 167 1311867724.1810541153 0.1701799482 0.1006932747 0.1704099327 0.0042137522 0.1659220000 976610233 0 402718720 0.1018916517 -0.0559422746 0.0425866470 168 1311867724.2139430046 0.1701481491 0.1011066966 0.1704099327 0.0042053802 0.1660580000 976613193 0 402718720 0.1014648974 -0.0563401282 0.0428153351 169 1311867724.2507870197 0.1695903540 0.1015119253 0.1704099327 0.0042020479 0.1659220000 976616209 0 402718720 0.1006047502 -0.0558823496 0.0426070243 170 1311867724.2855930328 0.1707433611 0.1019191690 0.1707433611 0.0041953170 0.1662740000 976619169 0 402718720 0.1015691236 -0.0558497496 0.0428399444 171 1311867724.3144888878 0.1710258126 0.1023233015 0.1710258126 0.0041839447 0.1800200000 976621961 0 402718720 0.1015626490 -0.0563478321 0.0423254929 172 1311867724.3517999649 0.1709494442 0.1027222907 0.1710258126 0.0041871277 0.1683690000 976625089 0 402718720 0.1010773107 -0.0566223972 0.0425836705 173 1311867724.3888330460 0.1704044491 0.1031135170 0.1710258126 0.0041814636 0.1681960000 976628049 0 402718720 0.1003533304 -0.0565484054 0.0422944315 174 1311867724.4160330296 0.1705032438 0.1035008143 0.1710258126 0.0041764722 0.1808850000 976630841 0 402718720 0.1004412398 -0.0567900166 0.0420755707 175 1311867724.4509639740 0.1703094691 0.1038825780 0.1710258126 0.0041664442 0.1807590000 976633801 0 402718720 0.0999175385 -0.0574296229 0.0415010974 176 1311867724.4830689430 0.1703368127 0.1042601589 0.1710258126 0.0041547705 0.1811160000 976636705 0 402718720 0.0996313319 -0.0578875504 0.0409451649 177 1311867724.5208630562 0.1689228266 0.1046254847 0.1710258126 0.0041474730 0.1677480000 976639665 0 402718720 0.0976160243 -0.0583365038 0.0406585932 178 1311867724.5523910522 0.1672494411 0.1049773047 0.1710258126 0.0041380416 0.1873210000 976642625 0 402718720 0.0958878919 -0.0585859716 0.0391404107 179 1311867724.5861799717 0.1650458276 0.1053128830 0.1710258126 0.0041336824 0.1705360000 976645529 0 402718720 0.0932996869 -0.0589500554 0.0378988944 180 1311867724.6193559170 0.1641149223 0.1056395610 0.1710258126 0.0041702597 0.1704560000 976648433 0 402718720 0.0922396556 -0.0589052141 0.0367640778 181 1311867724.6529819965 0.1621749699 0.1059519114 0.1710258126 0.0041771179 0.1698670000 976651393 0 402718720 0.0897435993 -0.0587673038 0.0363151543 182 1311867724.6818330288 0.1590198874 0.1062434936 0.1710258126 0.0041680835 0.1708850000 976654185 0 402718720 0.0860963985 -0.0590669177 0.0346041732 183 1311867724.7153129578 0.1557030976 0.1065137647 0.1710258126 0.0041859625 0.1910280000 976657145 0 402718720 0.0823608041 -0.0582246110 0.0335190147 184 1311867724.7518899441 0.1532338709 0.1067676783 0.1710258126 0.0041939299 0.1717530000 976660161 0 402718720 0.0794691667 -0.0570764467 0.0332086049 185 1311867724.7853860855 0.1507155001 0.1070052341 0.1710258126 0.0041959442 0.1821610000 976663121 0 402718720 0.0765479803 -0.0567772575 0.0324527286 186 1311867724.8179960251 0.1482452005 0.1072269544 0.1710258126 0.0041852745 0.1715110000 976666025 0 402718720 0.0735981837 -0.0567742325 0.0313787758 187 1311867724.8547580242 0.1461502612 0.1074351004 0.1710258126 0.0042226609 0.1720630000 976668985 0 402718720 0.0709864199 -0.0566023886 0.0310362168 188 1311867724.8830249310 0.1441851407 0.1076305793 0.1710258126 0.0042188392 0.1864850000 976671777 0 402718720 0.0686705336 -0.0562873445 0.0306186527 189 1311867724.9137279987 0.1427867115 0.1078165906 0.1710258126 0.0042154077 0.1735150000 976674681 0 402718720 0.0667322055 -0.0565598011 0.0295874272 190 1311867724.9535229206 0.1409299970 0.1079908717 0.1710258126 0.0042165754 0.1728400000 976677753 0 402718720 0.0646654218 -0.0562507324 0.0287098344 191 1311867724.9843940735 0.1394670010 0.1081556682 0.1710258126 0.0042066183 0.1734970000 976680657 0 402718720 0.0630784333 -0.0561379977 0.0278355330 192 1311867725.0159099102 0.1382827908 0.1083125803 0.1710258126 0.0042195161 0.1729920000 976683505 0 402718720 0.0617992505 -0.0563863330 0.0274453666 193 1311867725.0518310070 0.1364258528 0.1084582449 0.1710258126 0.0042161461 0.1845720000 976686521 0 402718720 0.0593157299 -0.0568062961 0.0273018442 194 1311867725.0813930035 0.1352993697 0.1085966012 0.1710258126 0.0042082875 0.1737690000 976689369 0 402718720 0.0578864776 -0.0566125028 0.0270154346 195 1311867725.1151220798 0.1344514340 0.1087291901 0.1710258126 0.0041978471 0.1735650000 976692329 0 402718720 0.0566792302 -0.0571407974 0.0263168272 196 1311867725.1557130814 0.1329247802 0.1088526370 0.1710258126 0.0041977831 0.1838250000 976695457 0 402718720 0.0546269752 -0.0571723059 0.0259978585 197 1311867725.1843969822 0.1316964179 0.1089685953 0.1710258126 0.0041957174 0.1817980000 976698249 0 402718720 0.0529464260 -0.0573084541 0.0257315040 198 1311867725.2150099277 0.1300795823 0.1090752164 0.1710258126 0.0041880739 0.2157650000 976701153 0 402718720 0.0505958498 -0.0581078902 0.0247490723 199 1311867725.2516539097 0.1281339377 0.1091709889 0.1710258126 0.0041854489 0.2156880000 976704225 0 402718720 0.0480382778 -0.0580254868 0.0244588330 200 1311867725.2816410065 0.1259601861 0.1092549349 0.1710258126 0.0041803763 0.2159700000 976707073 0 402718720 0.0455214977 -0.0580251142 0.0235179681 201 1311867725.3196239471 0.1250572801 0.1093335535 0.1710258126 0.0041762599 0.2075950000 976710089 0 402718720 0.0440859348 -0.0581801273 0.0228981134 202 1311867725.3517010212 0.1233327463 0.1094028564 0.1710258126 0.0041803846 0.1715500000 976712937 0 402718720 0.0417037271 -0.0583852157 0.0232290644 203 1311867725.3837459087 0.1223658919 0.1094667138 0.1710258126 0.0042149933 0.1839850000 976715729 0 402718720 0.0407071300 -0.0580166318 0.0230344627 204 1311867725.4178969860 0.1215873733 0.1095261288 0.1710258126 0.0042174128 0.1741610000 976718745 0 402718720 0.0394118875 -0.0581647716 0.0228331443 205 1311867725.4492449760 0.1198989823 0.1095767280 0.1710258126 0.0042340742 0.1749690000 976721593 0 402718720 0.0369915888 -0.0579063632 0.0227544773 206 1311867725.4836509228 0.1192698702 0.1096237821 0.1710258126 0.0042608541 0.1876840000 976724553 0 402718720 0.0356496423 -0.0577309467 0.0225809142 207 1311867725.5178139210 0.1182570830 0.1096654889 0.1710258126 0.0042579304 0.1892590000 976727625 0 402718720 0.0340841003 -0.0574844666 0.0217336547 208 1311867725.5497610569 0.1174296215 0.1097028165 0.1710258126 0.0042481167 0.1772740000 976730473 0 402718720 0.0322174169 -0.0579343028 0.0217194296 209 1311867725.5815479755 0.1165830791 0.1097357364 0.1710258126 0.0042392563 0.1772480000 976733377 0 402718720 0.0306079630 -0.0577679910 0.0214154217 210 1311867725.6194949150 0.1164409369 0.1097676659 0.1710258126 0.0042313311 0.1776320000 976736449 0 402718720 0.0297075380 -0.0580533296 0.0211278126 211 1311867725.6515610218 0.1159851179 0.1097971325 0.1710258126 0.0042951758 0.1755560000 976739353 0 402718720 0.0283031408 -0.0585702322 0.0210394692 212 1311867725.6834650040 0.1157352030 0.1098251423 0.1710258126 0.0042914958 0.1760530000 976742257 0 402718720 0.0270708501 -0.0589223318 0.0217905696 213 1311867725.7201809883 0.1152863801 0.1098507819 0.1710258126 0.0042834615 0.1889630000 976745273 0 402718720 0.0255576894 -0.0594224781 0.0224510022 214 1311867725.7515070438 0.1153938025 0.1098766838 0.1710258126 0.0042734054 0.1786360000 976748177 0 402718720 0.0247684494 -0.0602165796 0.0221981984 215 1311867725.7835409641 0.1037924737 0.1098483852 0.1710258126 0.0043041537 0.1809240000 976751025 0 402718720 0.0111220023 -0.0585677624 0.0207928643 216 1311867725.8211829662 0.1006257161 0.1098056877 0.1710258126 0.0043295156 0.1759620000 976754153 0 402718720 0.0058298898 -0.0596698187 0.0199961551 217 1311867725.8517971039 0.0990620106 0.1097561776 0.1710258126 0.0043203389 0.1898220000 976757057 0 402718720 0.0029618347 -0.0601417497 0.0192582365 218 1311867725.8837900162 0.0981115326 0.1097027618 0.1710258126 0.0043401164 0.1867640000 976759849 0 402718720 0.0011600074 -0.0597212650 0.0194407441 219 1311867725.9192690849 0.0980820134 0.1096496990 0.1710258126 0.0043313174 0.1777520000 976762865 0 402718720 -0.0002698996 -0.0604296215 0.0196864586 220 1311867725.9511859417 0.0984140486 0.1095986279 0.1710258126 0.0043235643 0.1773880000 976765769 0 402718720 -0.0013248808 -0.0613873377 0.0205911770 221 1311867725.9829630852 0.0989419073 0.1095504074 0.1710258126 0.0043230187 0.1778900000 976768617 0 402718720 -0.0015289671 -0.0614735410 0.0216005519 222 1311867726.0219368935 0.1011026800 0.1095123546 0.1710258126 0.0043165227 0.1761700000 976771745 0 402718720 -0.0012644804 -0.0629513413 0.0242038090 223 1311867726.0504179001 0.1026016548 0.1094813649 0.1710258126 0.0043082284 0.1907290000 976774481 0 402718720 -0.0016051659 -0.0646915957 0.0259506237 224 1311867726.0845088959 0.1037583351 0.1094558157 0.1710258126 0.0043107772 0.1787230000 976777497 0 402718720 -0.0020562869 -0.0659347996 0.0284401700 225 1311867726.1199669838 0.1059023291 0.1094400224 0.1710258126 0.0043020730 0.1790830000 976780457 0 402718720 -0.0017762677 -0.0677303821 0.0307231303 226 1311867726.1506989002 0.1068662107 0.1094286339 0.1710258126 0.0042994883 0.1902230000 976783361 0 402718720 -0.0020265244 -0.0686888173 0.0319644921 227 1311867726.1824700832 0.1080346853 0.1094224931 0.1710258126 0.0043047643 0.1975480000 976786265 0 402718720 -0.0026390962 -0.0698623657 0.0341876931 228 1311867726.2198660374 0.1093140393 0.1094220175 0.1710258126 0.0043281187 0.1803970000 976789281 0 402718720 -0.0030127240 -0.0709905997 0.0360796526 229 1311867726.2506690025 0.1115460172 0.1094312926 0.1710258126 0.0043235458 0.1793950000 976792185 0 402718720 -0.0029308428 -0.0729955956 0.0384006836 230 1311867726.2845950127 0.1139845550 0.1094510894 0.1710258126 0.0043258417 0.1789240000 976795089 0 402718720 -0.0029302817 -0.0749404281 0.0414346159 231 1311867726.3187239170 0.1162156239 0.1094803731 0.1710258126 0.0043266572 0.1813590000 976798105 0 402718720 -0.0027059291 -0.0764295459 0.0436617732 232 1311867726.3524029255 0.1184330061 0.1095189620 0.1710258126 0.0043240827 0.1811310000 976801065 0 402718720 -0.0021944840 -0.0774205923 0.0462773591 233 1311867726.3835608959 0.1206066906 0.1095665488 0.1710258126 0.0043175128 0.1938930000 976803913 0 402718720 -0.0023643966 -0.0789265782 0.0485801958 234 1311867726.4218099117 0.1221642792 0.1096203853 0.1710258126 0.0043144221 0.1810150000 976807041 0 402718720 -0.0023499569 -0.0794637203 0.0505178794 235 1311867726.4504199028 0.1243550107 0.1096830858 0.1710258126 0.0043082330 0.1822450000 976809833 0 402718720 -0.0024855137 -0.0807542503 0.0532716438 236 1311867726.4843189716 0.1263233721 0.1097535955 0.1710258126 0.0043037420 0.1828540000 976812793 0 402718720 -0.0027090963 -0.0820800588 0.0555189811 237 1311867726.5207901001 0.1290127039 0.1098348575 0.1710258126 0.0043038900 0.1824830000 976815809 0 402718720 -0.0027006445 -0.0837487727 0.0585932657 238 1311867726.5524380207 0.1319882125 0.1099279389 0.1710258126 0.0043073086 0.2021470000 976818713 0 402718720 -0.0015369360 -0.0851211399 0.0614119917 239 1311867726.5874860287 0.1345725656 0.1100310545 0.1710258126 0.0043051639 0.1828400000 976821729 0 402718720 -0.0014494215 -0.0865282118 0.0645166039 240 1311867726.6204600334 0.1365006566 0.1101413445 0.1710258126 0.0043202609 0.1837790000 976824633 0 402718720 -0.0006080108 -0.0873605758 0.0664999187 241 1311867726.6509370804 0.1386588216 0.1102596743 0.1710258126 0.0043259353 0.1819030000 976827481 0 402718720 0.0001866732 -0.0887239054 0.0682480112 242 1311867726.6916151047 0.1392093152 0.1103793009 0.1710258126 0.0043171351 0.1817310000 976830665 0 402718720 0.0005780885 -0.0891529620 0.0683419853 243 1311867726.7201170921 0.1400540471 0.1105014192 0.1710258126 0.0043099706 0.1977230000 976833401 0 402718720 0.0015492579 -0.0895297751 0.0686473176 244 1311867726.7513859272 0.1394408643 0.1106200234 0.1710258126 0.0043060690 0.1848490000 976836305 0 402718720 0.0014746243 -0.0895596817 0.0677270889 245 1311867726.7880010605 0.1378667355 0.1107312345 0.1710258126 0.0043062748 0.1848660000 976839377 0 402718720 0.0011899314 -0.0891784728 0.0657510981 246 1311867726.8198299408 0.1360822916 0.1108342876 0.1710258126 0.0042976607 0.1857230000 976842225 0 402718720 0.0010295124 -0.0881280825 0.0638195649 247 1311867726.8500390053 0.1351376176 0.1109326816 0.1710258126 0.0042921071 0.1860110000 976845073 0 402718720 0.0012673170 -0.0875716135 0.0624031574 248 1311867726.8927390575 0.1348485947 0.1110291168 0.1710258126 0.0042834900 0.1868690000 976848313 0 402718720 0.0014964842 -0.0875773951 0.0618228801 249 1311867726.9216780663 0.1337680370 0.1111204377 0.1710258126 0.0042768645 0.1856250000 976851105 0 402718720 0.0012660446 -0.0867554173 0.0610838905 250 1311867726.9543499947 0.1324133575 0.1112056094 0.1710258126 0.0042846906 0.1866800000 976854009 0 402718720 0.0014325188 -0.0857455060 0.0600166135 251 1311867726.9902989864 0.1308116615 0.1112837212 0.1710258126 0.0042793980 0.1878510000 976856969 0 402718720 0.0005680132 -0.0853294358 0.0583798811 252 1311867727.0208179951 0.1294685751 0.1113558833 0.1710258126 0.0042758955 0.1866550000 976859873 0 402718720 0.0009263642 -0.0842988417 0.0565613545 253 1311867727.0536949635 0.1278200150 0.1114209589 0.1710258126 0.0042737925 0.1975040000 976862777 0 402718720 0.0006271140 -0.0836687684 0.0548904911 254 1311867727.0911629200 0.1269427836 0.1114820685 0.1710258126 0.0042694862 0.1871970000 976865849 0 402718720 0.0006002798 -0.0831668749 0.0542378984 255 1311867727.1196689606 0.1251672357 0.1115357358 0.1710258126 0.0042671028 0.1851640000 976868529 0 402718720 0.0002920227 -0.0824410692 0.0520367399 256 1311867727.1514298916 0.1233665869 0.1115819501 0.1710258126 0.0042627327 0.1878510000 976871489 0 402718720 -0.0005634973 -0.0818459243 0.0506666414 257 1311867727.1904149055 0.1222716048 0.1116235440 0.1710258126 0.0042693770 0.1885770000 976874505 0 402718720 -0.0002762615 -0.0808499455 0.0500711650 258 1311867727.2208960056 0.1203450859 0.1116573485 0.1710258126 0.0042619706 0.2071180000 976928609 0 402718720 -0.0009677840 -0.0797962397 0.0487089008 259 1311867727.2544560432 0.1173133850 0.1116791864 0.1710258126 0.0042659040 0.1866560000 976931513 0 402718720 -0.0022481913 -0.0785114169 0.0454312190 260 1311867727.2870850563 0.1148684472 0.1116914528 0.1710258126 0.0042631339 0.2016230000 976934473 0 402718720 -0.0026450711 -0.0770550817 0.0428138301 261 1311867727.3192501068 0.1121620461 0.1116932559 0.1710258126 0.0042654764 0.1871970000 976937377 0 402718720 -0.0029126054 -0.0756197646 0.0394734442 262 1311867727.3502039909 0.1094197780 0.1116845785 0.1710258126 0.0042763194 0.2102890000 976940225 0 402718720 -0.0037544253 -0.0745476186 0.0361739025 263 1311867727.3894629478 0.1063834950 0.1116644223 0.1710258126 0.0042817543 0.2026880000 976943241 0 402718720 -0.0039824583 -0.0722298995 0.0332552232 264 1311867727.4182970524 0.1031060293 0.1116320041 0.1710258126 0.0042779383 0.1896930000 976946089 0 402718720 -0.0046739914 -0.0702485889 0.0304451510 265 1311867727.4495580196 0.1000334099 0.1115882358 0.1710258126 0.0042787022 0.1900560000 976948881 0 402718720 -0.0055589271 -0.0683003366 0.0276116114 266 1311867727.4858360291 0.0977735594 0.1115363010 0.1710258126 0.0042725196 0.1912040000 976951953 0 402718720 -0.0059680226 -0.0663708672 0.0260337498 267 1311867727.5198891163 0.0955646411 0.1114764820 0.1710258126 0.0042731521 0.1915400000 976954857 0 402718720 -0.0065772026 -0.0648355857 0.0239258502 268 1311867727.5494980812 0.0936693996 0.1114100377 0.1710258126 0.0042737248 0.2058290000 976957705 0 402718720 -0.0074359528 -0.0642885715 0.0218003150 269 1311867727.5905909538 0.0911417603 0.1113346909 0.1710258126 0.0042732355 0.1906130000 976960889 0 402718720 -0.0083656088 -0.0633638129 0.0199262444 270 1311867727.6176431179 0.0896644071 0.1112544306 0.1710258126 0.0042665648 0.1909970000 976963625 0 402718720 -0.0092734629 -0.0629510880 0.0188481435 271 1311867727.6497650146 0.0875152797 0.1111668323 0.1710258126 0.0042655419 0.1919230000 976966529 0 402718720 -0.0106392745 -0.0623089857 0.0169862341 272 1311867727.6884338856 0.0851513967 0.1110711873 0.1710258126 0.0042645494 0.1914590000 976969433 0 402718720 -0.0123230554 -0.0617380477 0.0149465706 273 1311867727.7184689045 0.0824360102 0.1109662965 0.1710258126 0.0042585098 0.1917050000 976972337 0 402718720 -0.0149144577 -0.0609842502 0.0127688861 274 1311867727.7523269653 0.0800763294 0.1108535594 0.1710258126 0.0042532728 0.1914780000 976975297 0 402718720 -0.0184248537 -0.0613376386 0.0111122746 275 1311867727.7856590748 0.0773317739 0.1107316620 0.1710258126 0.0042603244 0.1894940000 976978201 0 402718720 -0.0225708392 -0.0611687563 0.0109647503 276 1311867727.8181309700 0.0747156516 0.1106011692 0.1710258126 0.0042728620 0.1900790000 976981161 0 402718720 -0.0260387454 -0.0603771359 0.0098906858 277 1311867727.8548729420 0.0721613392 0.1104623973 0.1710258126 0.0042719539 0.1895110000 976984177 0 402718720 -0.0295643751 -0.0598161817 0.0085472157 278 1311867727.8882629871 0.0696915761 0.1103157396 0.1710258126 0.0042704176 0.2029630000 976987137 0 402718720 -0.0332353935 -0.0593725368 0.0075766435 279 1311867727.9193139076 0.0680081844 0.1101640997 0.1710258126 0.0042694211 0.1902690000 976989985 0 402718720 -0.0358876400 -0.0589456670 0.0071877479 280 1311867727.9556980133 0.0658705682 0.1100059085 0.1710258126 0.0042664037 0.1895620000 976993001 0 402718720 -0.0391151607 -0.0583886467 0.0060366173 281 1311867727.9869389534 0.0638549179 0.1098416701 0.1710258126 0.0042628756 0.2017470000 976995961 0 402718720 -0.0419110768 -0.0576756224 0.0046534422 282 1311867728.0179219246 0.0625300407 0.1096738983 0.1710258126 0.0042593274 0.1888210000 976998753 0 402718720 -0.0439234227 -0.0573200770 0.0040628021 283 1311867728.0555219650 0.0605834313 0.1095004338 0.1710258126 0.0042575601 0.1981550000 977001825 0 402718720 -0.0465623029 -0.0564035401 0.0031932350 284 1311867728.0892169476 0.0594169609 0.1093240835 0.1710258126 0.0042523588 0.1890220000 977004785 0 402718720 -0.0476913452 -0.0557108372 0.0028169269 285 1311867728.1177880764 0.0580243170 0.1091440843 0.1710258126 0.0042617493 0.2009680000 977007633 0 402718720 -0.0505866930 -0.0550988168 0.0018083835 286 1311867728.1556169987 0.0571730062 0.1089623673 0.1710258126 0.0042655724 0.1881350000 977010649 0 402718720 -0.0530570112 -0.0548163280 0.0013325175 287 1311867728.1882989407 0.0563552268 0.1087790671 0.1710258126 0.0042596413 0.1875470000 977013665 0 402718720 -0.0550860167 -0.0543419905 0.0002816917 288 1311867728.2182519436 0.0556484275 0.1085945858 0.1710258126 0.0042618195 0.2046190000 977016513 0 402718720 -0.0581208356 -0.0540500730 -0.0006343315 289 1311867728.2558999062 0.0549883544 0.1084090971 0.1710258126 0.0042636210 0.1880800000 977019529 0 402718720 -0.0624440759 -0.0535790250 -0.0016623248 290 1311867728.2875900269 0.0552607104 0.1082258268 0.1710258126 0.0042773989 0.1894390000 977022433 0 402718720 -0.0678205714 -0.0536542833 -0.0019377491 291 1311867728.3226509094 0.0550128669 0.1080429644 0.1710258126 0.0042765420 0.1874350000 977025449 0 402718720 -0.0710219890 -0.0531509854 -0.0022375067 292 1311867728.3597300053 0.0559003577 0.1078643938 0.1710258126 0.0042749609 0.1898440000 977028409 0 402718720 -0.0745205954 -0.0533762425 -0.0027659440 293 1311867728.3861401081 0.0554576665 0.1076855312 0.1710258126 0.0042738644 0.2178140000 977031201 0 402718720 -0.0776951537 -0.0519858077 -0.0049381009 294 1311867728.4175701141 0.0567587949 0.1075123111 0.1710258126 0.0043321786 0.1884520000 977034105 0 402718720 -0.0800864324 -0.0520545878 -0.0057911472 295 1311867728.4568250179 0.0575592294 0.1073429786 0.1710258126 0.0043279619 0.1878320000 977037177 0 402718720 -0.0835797563 -0.0514910221 -0.0072485628 296 1311867728.4875330925 0.0576990172 0.1071752625 0.1710258126 0.0043228985 0.1985920000 977040025 0 402718720 -0.0856277049 -0.0507088229 -0.0079226056 297 1311867728.5187420845 0.0596704446 0.1070153136 0.1710258126 0.0043202084 0.1860610000 977042873 0 402718720 -0.0900808573 -0.0506595038 -0.0080704652 298 1311867728.5550920963 0.0622409508 0.1068650641 0.1710258126 0.0043318937 0.1992600000 977045945 0 402718720 -0.0953084007 -0.0503782481 -0.0086852880 299 1311867728.5878560543 0.0660573691 0.1067285835 0.1710258126 0.0043442857 0.1875820000 977048905 0 402718720 -0.1020337269 -0.0499587096 -0.0097073605 300 1311867728.6187679768 0.0702600181 0.1066070216 0.1710258126 0.0043585398 0.1865670000 977051697 0 402718720 -0.1089328378 -0.0492757894 -0.0110349944 301 1311867728.6580820084 0.0723229498 0.1064931210 0.1710258126 0.0043585882 0.1871560000 977054825 0 402718720 -0.1121530905 -0.0485297963 -0.0122163743 302 1311867728.6893489361 0.0745355040 0.1063873011 0.1710258126 0.0043530917 0.1871550000 977057729 0 402718720 -0.1150857061 -0.0483062714 -0.0132754967 303 1311867728.7210168839 0.0759624988 0.1062868892 0.1710258126 0.0043483981 0.1981020000 977060633 0 402718720 -0.1171902120 -0.0481130965 -0.0138450479 304 1311867728.7584259510 0.0793474540 0.1061982727 0.1710258126 0.0043487668 0.1869930000 977063649 0 402718720 -0.1210517734 -0.0482334457 -0.0148756001 305 1311867728.7858450413 0.0807063729 0.1061146927 0.1710258126 0.0043438233 0.1881640000 977066497 0 402718720 -0.1223930940 -0.0486763939 -0.0142940870 306 1311867728.8203740120 0.0803429037 0.1060304711 0.1710258126 0.0043370642 0.1881870000 977069401 0 402718720 -0.1216768995 -0.0485106632 -0.0149718923 307 1311867728.8545160294 0.0810675398 0.1059491586 0.1710258126 0.0043304972 0.1886040000 977072361 0 402718720 -0.1225119382 -0.0482844003 -0.0152423205 308 1311867728.8860759735 0.0827408507 0.1058738070 0.1710258126 0.0043254327 0.2194060000 977075321 0 402718720 -0.1243395060 -0.0481914766 -0.0170341507 309 1311867728.9193949699 0.0841501206 0.1058035038 0.1710258126 0.0043199461 0.1869320000 977078169 0 402718720 -0.1261875182 -0.0476113036 -0.0177516118 310 1311867728.9585559368 0.0855957046 0.1057383173 0.1710258126 0.0043407804 0.1883090000 977081409 0 402718720 -0.1277507544 -0.0468950160 -0.0190178230 311 1311867728.9886839390 0.0879235566 0.1056810352 0.1710258126 0.0043377814 0.1877300000 977084145 0 402718720 -0.1299856603 -0.0471188352 -0.0194989573 312 1311867729.0231020451 0.0893792510 0.1056287859 0.1710258126 0.0043349321 0.1873250000 977087161 0 402718720 -0.1312876195 -0.0469513163 -0.0193227753 313 1311867729.0583839417 0.0909321010 0.1055818316 0.1710258126 0.0043334925 0.1994040000 977090177 0 402718720 -0.1332027912 -0.0463050008 -0.0194500796 314 1311867729.0882170200 0.0933898017 0.1055430035 0.1710258126 0.0043298827 0.1868230000 977093025 0 402718720 -0.1359551996 -0.0465191193 -0.0190206412 315 1311867729.1263229847 0.0936720073 0.1055053178 0.1710258126 0.0043454105 0.2055200000 977096097 0 402718720 -0.1371582896 -0.0455501676 -0.0187972225 316 1311867729.1556320190 0.0946794897 0.1054710588 0.1710258126 0.0043396702 0.1874490000 977098889 0 402718720 -0.1392536461 -0.0447051935 -0.0187226981 317 1311867729.1888830662 0.0963697284 0.1054423480 0.1710258126 0.0043689033 0.1876410000 977101849 0 402718720 -0.1418933719 -0.0443895608 -0.0188455842 318 1311867729.2240469456 0.0989115238 0.1054218108 0.1710258126 0.0043753287 0.2082850000 977104809 0 402718720 -0.1447991282 -0.0440267809 -0.0191940796 319 1311867729.2579979897 0.1014505252 0.1054093616 0.1710258126 0.0043695122 0.1874210000 977107825 0 402718720 -0.1473958492 -0.0444005616 -0.0186721291 320 1311867729.2880148888 0.1047739536 0.1054073760 0.1710258126 0.0043659930 0.1849260000 977110673 0 402718720 -0.1506949812 -0.0449774005 -0.0183334798 321 1311867729.3236539364 0.1090430692 0.1054187021 0.1710258126 0.0043676511 0.1870800000 977113633 0 402718720 -0.1549821645 -0.0447545126 -0.0183017217 322 1311867729.3580930233 0.1131186187 0.1054426149 0.1710258126 0.0043810936 0.1843460000 977116649 0 402718720 -0.1585135162 -0.0447687842 -0.0185711272 323 1311867729.3882780075 0.1161749363 0.1054758419 0.1710258126 0.0043799728 0.1947100000 977119441 0 402718720 -0.1611504555 -0.0446698815 -0.0182666238 324 1311867729.4253289700 0.1195052490 0.1055191426 0.1710258126 0.0043785122 0.1862830000 977122513 0 402718720 -0.1643056422 -0.0439614430 -0.0185820796 325 1311867729.4572670460 0.1216437146 0.1055687566 0.1710258126 0.0043768092 0.1868330000 977125417 0 402718720 -0.1658563763 -0.0433967002 -0.0197613575 326 1311867729.4887750149 0.1239670739 0.1056251932 0.1710258126 0.0043866194 0.1864740000 977128377 0 402718720 -0.1678679138 -0.0432052128 -0.0205895938 327 1311867729.5223650932 0.1269821227 0.1056905049 0.1710258126 0.0043841628 0.1859760000 977131281 0 402718720 -0.1705095172 -0.0433695763 -0.0207854379 328 1311867729.5603790283 0.1294669062 0.1057629939 0.1710258126 0.0043821438 0.2001500000 977134353 0 402718720 -0.1726045758 -0.0434318669 -0.0215821955 329 1311867729.5890150070 0.1309110224 0.1058394317 0.1710258126 0.0043762948 0.1847670000 977137145 0 402718720 -0.1737488210 -0.0435128622 -0.0222200472 330 1311867729.6254830360 0.1333708316 0.1059228602 0.1710258126 0.0043740101 0.1853310000 977140161 0 402718720 -0.1760973483 -0.0432373695 -0.0220912881 331 1311867729.6614611149 0.1357717365 0.1060130381 0.1710258126 0.0043692916 0.1824200000 977143177 0 402718720 -0.1783274859 -0.0433202870 -0.0221154802 332 1311867729.6888220310 0.1368123293 0.1061058070 0.1710258126 0.0043647275 0.1838290000 977145857 0 402718720 -0.1792659611 -0.0431476012 -0.0227589440 333 1311867729.7230739594 0.1392736286 0.1062054101 0.1710258126 0.0043607467 0.1948560000 977148873 0 402718720 -0.1815730780 -0.0432434268 -0.0229838807 334 1311867729.7570610046 0.1412485987 0.1063103298 0.1710258126 0.0043578567 0.1844510000 977151665 0 402718720 -0.1831412017 -0.0431631170 -0.0230056606 335 1311867729.7899730206 0.1445432752 0.1064244580 0.1710258126 0.0043527915 0.1832910000 977154625 0 402718720 -0.1861565262 -0.0435938761 -0.0229075588 336 1311867729.8264250755 0.1471628994 0.1065457034 0.1710258126 0.0043524713 0.1829630000 977157585 0 402718720 -0.1885390282 -0.0433851816 -0.0225870963 337 1311867729.8550031185 0.1508962363 0.1066773073 0.1710258126 0.0043520400 0.1828440000 977160377 0 402718720 -0.1921889335 -0.0431308411 -0.0220163465 338 1311867729.8881840706 0.1535779834 0.1068160667 0.1710258126 0.0043481983 0.1830140000 977163393 0 402718720 -0.1946994960 -0.0433086343 -0.0223131627 339 1311867729.9233629704 0.1565931439 0.1069629017 0.1710258126 0.0043433362 0.1825660000 977166353 0 402718720 -0.1976608187 -0.0428425744 -0.0223187804 340 1311867729.9569330215 0.1604137272 0.1071201101 0.1710258126 0.0043473003 0.1803940000 977169313 0 402718720 -0.2015193999 -0.0428230874 -0.0214139279 341 1311867729.9865698814 0.1638827175 0.1072865693 0.1710258126 0.0043451932 0.1818380000 977172105 0 402718720 -0.2048468739 -0.0430558547 -0.0217395332 342 1311867730.0230469704 0.1668819934 0.1074608249 0.1710258126 0.0043409669 0.1977650000 977175121 0 402718720 -0.2077619880 -0.0426509194 -0.0220890176 343 1311867730.0557899475 0.1698087752 0.1076425974 0.1710258126 0.0043374668 0.1817090000 977178081 0 402718720 -0.2107651830 -0.0421641208 -0.0215359163 344 1311867730.0871100426 0.1725495458 0.1078312804 0.1725495458 0.0043335747 0.1814770000 977180985 0 402718720 -0.2133191973 -0.0422687195 -0.0215403382 345 1311867730.1231229305 0.1738744527 0.1080227099 0.1738744527 0.0043284718 0.1813200000 977184001 0 402718720 -0.2145105153 -0.0422042273 -0.0212345291 346 1311867730.1568520069 0.1755762994 0.1082179515 0.1755762994 0.0043229354 0.1813830000 977186961 0 402718720 -0.2161924243 -0.0421209522 -0.0206981152 347 1311867730.1882419586 0.1777595729 0.1084183596 0.1777595729 0.0043208103 0.1814300000 977189809 0 402718720 -0.2183009684 -0.0414778404 -0.0210087877 348 1311867730.2224810123 0.1803281605 0.1086249969 0.1803281605 0.0043161074 0.2013770000 977192825 0 402718720 -0.2209301889 -0.0411500037 -0.0203808304 349 1311867730.2575879097 0.1820295900 0.1088353253 0.1820295900 0.0043106418 0.1807050000 977195785 0 402718720 -0.2227644324 -0.0404846258 -0.0202426091 350 1311867730.2914879322 0.1823288798 0.1090453069 0.1823288798 0.0043061574 0.1798120000 977198745 0 402718720 -0.2229924351 -0.0399262980 -0.0205082409 351 1311867730.3230810165 0.1824911982 0.1092545544 0.1824911982 0.0043036051 0.1775080000 977201649 0 402718720 -0.2231600434 -0.0395664833 -0.0205614194 352 1311867730.3554260731 0.1846594363 0.1094687728 0.1846594363 0.0043049255 0.1793020000 977204553 0 402718720 -0.2249713838 -0.0398525707 -0.0203872360 353 1311867730.3982920647 0.1848580092 0.1096823401 0.1848580092 0.0043031048 0.1921490000 977207737 0 402718720 -0.2250032723 -0.0394221656 -0.0201213248 354 1311867730.4225230217 0.1856439561 0.1098969209 0.1856439561 0.0043029575 0.1801020000 977210473 0 402718720 -0.2260842174 -0.0385504887 -0.0195378382 355 1311867730.4600110054 0.1859404296 0.1101111280 0.1859404296 0.0042976754 0.1801050000 977213489 0 402718720 -0.2263475955 -0.0387735665 -0.0196502525 356 1311867730.4948410988 0.1874841452 0.1103284679 0.1874841452 0.0042990939 0.1792970000 977216449 0 402718720 -0.2276075184 -0.0390137881 -0.0195239857 357 1311867730.5300729275 0.1887094080 0.1105480224 0.1887094080 0.0042934531 0.1925390000 977219409 0 402718720 -0.2286774665 -0.0387800559 -0.0192041472 358 1311867730.5597670078 0.1884817481 0.1107657144 0.1887094080 0.0042877961 0.1969830000 977222257 0 402718720 -0.2282822281 -0.0386451818 -0.0194299798 359 1311867730.5940020084 0.1910740137 0.1109894143 0.1910740137 0.0042863383 0.1813500000 977225273 0 402718720 -0.2306886315 -0.0386489332 -0.0192817580 360 1311867730.6230149269 0.1911357194 0.1112120430 0.1911357194 0.0042863737 0.1912690000 977228009 0 402718720 -0.2305829078 -0.0377772078 -0.0195095297 361 1311867730.6614060402 0.1942566335 0.1114420834 0.1942566335 0.0042838760 0.1896450000 977231081 0 402718720 -0.2333264947 -0.0378657617 -0.0188667458 362 1311867730.6922950745 0.1951564401 0.1116733385 0.1951564401 0.0042781759 0.1773060000 977233985 0 402718720 -0.2338443100 -0.0377351716 -0.0189455282 363 1311867730.7275629044 0.1965288073 0.1119071001 0.1965288073 0.0042783868 0.2024190000 977236945 0 402718720 -0.2348480225 -0.0375169255 -0.0194148794 364 1311867730.7572948933 0.1976324916 0.1121426095 0.1976324916 0.0042736188 0.1796010000 977239793 0 402718720 -0.2355733663 -0.0367673188 -0.0194983352 365 1311867730.7932779789 0.1987458169 0.1123798785 0.1987458169 0.0042690324 0.1801010000 977242865 0 402718720 -0.2360672206 -0.0363541245 -0.0199450012 366 1311867730.8240480423 0.1983095109 0.1126146589 0.1987458169 0.0042639445 0.1778010000 977245657 0 402718720 -0.2345596403 -0.0372277498 -0.0207889229 367 1311867730.8591129780 0.1982102990 0.1128478896 0.1987458169 0.0042591828 0.1777980000 977248673 0 402718720 -0.2338325977 -0.0366233476 -0.0208941214 368 1311867730.8922739029 0.1992399991 0.1130826507 0.1992399991 0.0042558129 0.1971420000 977251465 0 402718720 -0.2342703044 -0.0357962362 -0.0203648545 369 1311867730.9270720482 0.2001972347 0.1133187336 0.2001972347 0.0042549472 0.1931080000 977254481 0 402718720 -0.2345049828 -0.0351743959 -0.0197112523 370 1311867730.9611239433 0.2017403841 0.1135577110 0.2017403841 0.0042550834 0.1805830000 977257385 0 402718720 -0.2354466617 -0.0345963798 -0.0191214811 371 1311867730.9928169250 0.2022749335 0.1137968410 0.2022749335 0.0042558205 0.1810390000 977260289 0 402718720 -0.2352690548 -0.0347594880 -0.0185872689 372 1311867731.0221049786 0.2037272006 0.1140385893 0.2037272006 0.0042524682 0.1811240000 977263137 0 402718720 -0.2361191213 -0.0348721668 -0.0184896160 373 1311867731.0609729290 0.2060015649 0.1142851388 0.2060015649 0.0042500910 0.1914780000 977266209 0 402718720 -0.2376969159 -0.0344206430 -0.0181168169 374 1311867731.0900061131 0.2059486508 0.1145302284 0.2060015649 0.0042488487 0.1806990000 977269001 0 402718720 -0.2370086759 -0.0342711546 -0.0186816361 375 1311867731.1276559830 0.2062430978 0.1147747961 0.2062430978 0.0042446422 0.1806660000 977272073 0 402718720 -0.2364276946 -0.0347331837 -0.0186671522 376 1311867731.1551880836 0.2072215080 0.1150206650 0.2072215080 0.0042394619 0.1805830000 977274865 0 402718720 -0.2370651662 -0.0340516455 -0.0178587437 377 1311867731.1935870647 0.2075473070 0.1152660938 0.2075473070 0.0042367456 0.1805620000 977277881 0 402718720 -0.2368348092 -0.0337717235 -0.0172606912 378 1311867731.2235820293 0.2081755847 0.1155118861 0.2081755847 0.0042315625 0.1937150000 977280785 0 402718720 -0.2369179279 -0.0337799489 -0.0163228065 379 1311867731.2602028847 0.2100763619 0.1157613966 0.2100763619 0.0042292151 0.1813790000 977283745 0 402718720 -0.2379353046 -0.0339229554 -0.0158056542 380 1311867731.2900059223 0.2131229341 0.1160176111 0.2131229341 0.0042865446 0.1810890000 977286593 0 402718720 -0.2397707254 -0.0339375027 -0.0155861909 381 1311867731.3230779171 0.2134469450 0.1162733312 0.2134469450 0.0043208331 0.1813700000 977289553 0 402718720 -0.2397778630 -0.0338681825 -0.0159891136 382 1311867731.3570859432 0.2115211785 0.1165226711 0.2134469450 0.0043284973 0.1935870000 977292569 0 402718720 -0.2371948510 -0.0337401032 -0.0163557641 383 1311867731.3915760517 0.2089318037 0.1167639482 0.2134469450 0.0043618808 0.1943800000 977295473 0 402718720 -0.2338232547 -0.0342341624 -0.0167482123 384 1311867731.4279849529 0.2079883665 0.1170015118 0.2134469450 0.0043600931 0.1821360000 977298545 0 402718720 -0.2322185189 -0.0356164835 -0.0160929244 385 1311867731.4602010250 0.2054041773 0.1172311291 0.2134469450 0.0043577544 0.1794900000 977301449 0 402718720 -0.2290427536 -0.0366765633 -0.0154937683 386 1311867731.4926180840 0.2023339421 0.1174516027 0.2134469450 0.0043619858 0.1943520000 977304353 0 402718720 -0.2253995836 -0.0372230187 -0.0142127648 387 1311867731.5259540081 0.1655924022 0.1175759975 0.2134469450 0.0047688827 0.1922300000 977307257 0 402718720 -0.1873496473 -0.0379339382 -0.0063482411 388 1311867731.5589148998 0.1654531211 0.1176993922 0.2134469450 0.0047667448 0.1975160000 977310161 0 402718720 -0.1857734025 -0.0403792635 -0.0054161949 389 1311867731.5967359543 0.1626657248 0.1178149869 0.2134469450 0.0048211709 0.1808880000 977313289 0 402718720 -0.1825071275 -0.0416116193 -0.0040812856 390 1311867731.6247410774 0.1596600860 0.1179222820 0.2134469450 0.0048203115 0.1828730000 977316025 0 402718720 -0.1785684079 -0.0427356586 -0.0027161350 391 1311867731.6616659164 0.1563970447 0.1180206829 0.2134469450 0.0048156825 0.1827450000 977319097 0 402718720 -0.1744299531 -0.0430098139 -0.0019005490 392 1311867731.6925039291 0.1533873230 0.1181109039 0.2134469450 0.0048329962 0.1841890000 977321945 0 402718720 -0.1709759831 -0.0431438349 -0.0010933814 393 1311867731.7299311161 0.1491598636 0.1181899089 0.2134469450 0.0048686830 0.1967870000 977325017 0 402718720 -0.1658572704 -0.0434907749 -0.0004515223 394 1311867731.7615330219 0.1445365548 0.1182567786 0.2134469450 0.0049048372 0.1836140000 977327921 0 402718720 -0.1604418904 -0.0438293330 -0.0001903957 395 1311867731.7939310074 0.1409223080 0.1183141597 0.2134469450 0.0049161035 0.1855890000 977330825 0 402718720 -0.1558972001 -0.0444839224 0.0009759546 396 1311867731.8252151012 0.1375045627 0.1183626203 0.2134469450 0.0049270742 0.2069100000 977333673 0 402718720 -0.1514271498 -0.0461578555 0.0019675044 397 1311867731.8593230247 0.1349873692 0.1184044962 0.2134469450 0.0049228855 0.1859750000 977336633 0 402718720 -0.1475903839 -0.0474925078 0.0031019780 398 1311867731.8910930157 0.1314006597 0.1184371499 0.2134469450 0.0049590458 0.2085030000 977339593 0 402718720 -0.1432305127 -0.0484710149 0.0035541491 399 1311867731.9224479198 0.1283770502 0.1184620619 0.2134469450 0.0049576027 0.1989920000 977342497 0 402718720 -0.1391498297 -0.0498770587 0.0044037257 400 1311867731.9598410130 0.1257882714 0.1184803775 0.2134469450 0.0049610956 0.1856780000 977345457 0 402718720 -0.1355211884 -0.0507565401 0.0051109679 401 1311867731.9915709496 0.1230458394 0.1184917627 0.2134469450 0.0049689114 0.1856740000 977348361 0 402718720 -0.1320000887 -0.0510559827 0.0054438571 402 1311867732.0239229202 0.1218196899 0.1185000411 0.2134469450 0.0049962585 0.1871710000 977351265 0 402718720 -0.1297765821 -0.0521518327 0.0055627567 403 1311867732.0619950294 0.1211786196 0.1185066877 0.2134469450 0.0049963890 0.2002050000 977354337 0 402718720 -0.1280322373 -0.0533397719 0.0058817076 404 1311867732.0918290615 0.1213353798 0.1185136894 0.2134469450 0.0050098413 0.1886120000 977357185 0 402718720 -0.1272719651 -0.0537840426 0.0058509829 405 1311867732.1221950054 0.1218415797 0.1185219064 0.2134469450 0.0050111336 0.1876730000 977360089 0 402718720 -0.1271256357 -0.0550476089 0.0058496580 406 1311867732.1605980396 0.1218048632 0.1185299925 0.2134469450 0.0050188457 0.2000700000 977363105 0 402718720 -0.1266725510 -0.0554130189 0.0054626609 407 1311867732.1931400299 0.1234368086 0.1185420486 0.2134469450 0.0050395890 0.1865900000 977366065 0 402718720 -0.1274135113 -0.0559231825 0.0054422040 408 1311867732.2232089043 0.1237825453 0.1185548929 0.2134469450 0.0050725127 0.1981630000 977368857 0 402718720 -0.1276232302 -0.0566931739 0.0050833561 409 1311867732.2590498924 0.1249023899 0.1185704125 0.2134469450 0.0051283257 0.1871270000 977371873 0 402718720 -0.1278286576 -0.0567924343 0.0051111546 410 1311867732.2903969288 0.1252900958 0.1185868019 0.2134469450 0.0051521034 0.1870830000 977374777 0 402718720 -0.1281224936 -0.0571221970 0.0053207423 411 1311867732.3218240738 0.1270269454 0.1186073376 0.2134469450 0.0051479381 0.1865020000 977377681 0 402718720 -0.1292166412 -0.0577281676 0.0048500784 412 1311867732.3607840538 0.1279510409 0.1186300165 0.2134469450 0.0051443761 0.1864150000 977380753 0 402718720 -0.1294303238 -0.0576741174 0.0047152024 413 1311867732.3899528980 0.1295689195 0.1186565029 0.2134469450 0.0051388772 0.1962280000 977383545 0 402718720 -0.1306082308 -0.0579338409 0.0046989229 414 1311867732.4218940735 0.1309452951 0.1186861860 0.2134469450 0.0051361379 0.1863780000 977386505 0 402718720 -0.1310392320 -0.0585994609 0.0042382046 415 1311867732.4593050480 0.1315536499 0.1187171919 0.2134469450 0.0051336056 0.1852230000 977389521 0 402718720 -0.1311436743 -0.0587216765 0.0039730202 416 1311867732.4918489456 0.1320602000 0.1187492665 0.2134469450 0.0051278462 0.1855070000 977392481 0 402718720 -0.1307966113 -0.0591671243 0.0033614861 417 1311867732.5229809284 0.1345768869 0.1187872224 0.2134469450 0.0051227701 0.1849860000 977395329 0 402718720 -0.1326222420 -0.0595388077 0.0027665955 418 1311867732.5698928833 0.1355080754 0.1188272244 0.2134469450 0.0051171355 0.1941590000 977398625 0 402718720 -0.1331000626 -0.0588220321 0.0025904058 419 1311867732.5926280022 0.1367553025 0.1188700122 0.2134469450 0.0051121989 0.1854720000 977401305 0 402718720 -0.1341857761 -0.0587289184 0.0024234925 420 1311867732.6242370605 0.1372594982 0.1189137967 0.2134469450 0.0051119806 0.1853420000 977404209 0 402718720 -0.1342080683 -0.0588734262 0.0018993388 421 1311867732.6630299091 0.1381383836 0.1189594608 0.2134469450 0.0051150301 0.1849350000 977407281 0 402718720 -0.1346511692 -0.0588598214 0.0019287936 422 1311867732.6922440529 0.1375478506 0.1190035091 0.2134469450 0.0051098908 0.1854280000 977410129 0 402718720 -0.1339590251 -0.0580902137 0.0020239057 423 1311867732.7260940075 0.1376411766 0.1190475698 0.2134469450 0.0051057249 0.2181710000 977413089 0 402718720 -0.1336729378 -0.0581676513 0.0017322756 424 1311867732.7601239681 0.1382238567 0.1190927969 0.2134469450 0.0051024372 0.1840900000 977415993 0 402718720 -0.1340756565 -0.0581506193 0.0012141105 425 1311867732.7919039726 0.1388996691 0.1191394013 0.2134469450 0.0050970706 0.1856580000 977418953 0 402718720 -0.1347837150 -0.0575667657 0.0011349870 426 1311867732.8280360699 0.1398317963 0.1191879750 0.2134469450 0.0050912378 0.1857230000 977421913 0 402718720 -0.1355821192 -0.0573293604 0.0008697411 427 1311867732.8589270115 0.1403844506 0.1192376154 0.2134469450 0.0050868767 0.1865660000 977424817 0 402718720 -0.1362604201 -0.0570504926 0.0006827030 428 1311867732.8912909031 0.1417840123 0.1192902939 0.2134469450 0.0050827743 0.2021260000 977427721 0 402718720 -0.1376962513 -0.0566880964 0.0007939911 429 1311867732.9262781143 0.1425643861 0.1193445459 0.2134469450 0.0050771571 0.1880920000 977430737 0 402718720 -0.1384970993 -0.0560596548 0.0011170278 430 1311867732.9602870941 0.1425719112 0.1193985630 0.2134469450 0.0050790296 0.2001220000 977433641 0 402718720 -0.1382463425 -0.0562159866 0.0011732209 431 1311867732.9987640381 0.1423230469 0.1194517521 0.2134469450 0.0050743153 0.1871880000 977436769 0 402718720 -0.1378922313 -0.0561579876 0.0014126903 432 1311867733.0276939869 0.1440234929 0.1195086311 0.2134469450 0.0050698714 0.1882980000 977439617 0 402718720 -0.1397006065 -0.0557472743 0.0019956953 433 1311867733.0607628822 0.1455288976 0.1195687241 0.2134469450 0.0050717247 0.1967880000 977442521 0 402718720 -0.1409553140 -0.0564189106 0.0020563323 434 1311867733.0977020264 0.1468657553 0.1196316205 0.2134469450 0.0050670821 0.1864860000 977445537 0 402718720 -0.1422372013 -0.0563059933 0.0022209338 435 1311867733.1263020039 0.1473762989 0.1196954014 0.2134469450 0.0050621178 0.1990340000 977448329 0 402718720 -0.1428675801 -0.0557414331 0.0025802341 436 1311867733.1625030041 0.1501633972 0.1197652821 0.2134469450 0.0050583517 0.1874010000 977451345 0 402718720 -0.1453156471 -0.0567885786 0.0025244227 437 1311867733.1926651001 0.1509527415 0.1198366493 0.2134469450 0.0050529959 0.1870230000 977454193 0 402718720 -0.1460729539 -0.0568211712 0.0024662630 438 1311867733.2259631157 0.1517058313 0.1199094100 0.2134469450 0.0050476018 0.2014100000 977457153 0 402718720 -0.1466486007 -0.0563537292 0.0028147365 439 1311867733.2618060112 0.1528000236 0.1199843316 0.2134469450 0.0050470432 0.1880540000 977460169 0 402718720 -0.1474392861 -0.0564471185 0.0029173091 440 1311867733.2919199467 0.1539446861 0.1200615143 0.2134469450 0.0050415707 0.1877420000 977462961 0 402718720 -0.1484987140 -0.0564324856 0.0026145994 441 1311867733.3300418854 0.1548670083 0.1201404383 0.2134469450 0.0050429422 0.1870580000 977466033 0 402718720 -0.1491433829 -0.0563232936 0.0027576191 442 1311867733.3602790833 0.1557596624 0.1202210248 0.2134469450 0.0050407846 0.1999300000 977468937 0 402718720 -0.1495860219 -0.0567995310 0.0025439933 443 1311867733.3923840523 0.1575065702 0.1203051908 0.2134469450 0.0050373140 0.1990690000 977471841 0 402718720 -0.1509342790 -0.0568456464 0.0024958926 444 1311867733.4289550781 0.1579853594 0.1203900560 0.2134469450 0.0050323952 0.1875450000 977474857 0 402718720 -0.1512141824 -0.0559804253 0.0023504489 445 1311867733.4588150978 0.1595480740 0.1204780516 0.2134469450 0.0050274553 0.1979930000 977477593 0 402718720 -0.1526516825 -0.0558588579 0.0024395045 446 1311867733.4956119061 0.1610330790 0.1205689821 0.2134469450 0.0050232174 0.1993390000 977480497 0 402718720 -0.1539765745 -0.0556815937 0.0025331699 447 1311867733.5290400982 0.1612854898 0.1206600705 0.2134469450 0.0050239524 0.1864960000 977483457 0 402718720 -0.1542024016 -0.0550432466 0.0026046918 448 1311867733.5630290508 0.1618238688 0.1207519540 0.2134469450 0.0050190595 0.1984120000 977486417 0 402718720 -0.1544444859 -0.0549586378 0.0025114145 449 1311867733.5922229290 0.1627171636 0.1208454177 0.2134469450 0.0050141183 0.1876230000 977489209 0 402718720 -0.1549836397 -0.0554309376 0.0024070770 450 1311867733.6283020973 0.1636640280 0.1209405702 0.2134469450 0.0050094083 0.2248650000 977492225 0 402718720 -0.1556061804 -0.0556098782 0.0025517230 451 1311867733.6601879597 0.1632420272 0.1210343650 0.2134469450 0.0050062542 0.1873960000 977495129 0 402718720 -0.1549947709 -0.0554333963 0.0025889750 452 1311867733.6917510033 0.1641805470 0.1211298211 0.2134469450 0.0050021451 0.1887600000 977498033 0 402718720 -0.1556198746 -0.0555681735 0.0025032847 453 1311867733.7288239002 0.1662958115 0.1212295253 0.2134469450 0.0049988660 0.1892790000 977501049 0 402718720 -0.1573137790 -0.0556399301 0.0026138972 454 1311867733.7597820759 0.1680677384 0.1213326932 0.2134469450 0.0049941846 0.1885490000 977503841 0 402718720 -0.1587489098 -0.0558274612 0.0026858591 455 1311867733.7924160957 0.1695351750 0.1214386327 0.2134469450 0.0050144614 0.1889920000 977506745 0 402718720 -0.1599428058 -0.0558315106 0.0028263428 456 1311867733.8282589912 0.1703844666 0.1215459701 0.2134469450 0.0050103837 0.1871050000 977509761 0 402718720 -0.1599222273 -0.0563603304 0.0023246789 457 1311867733.8608579636 0.1724919230 0.1216574492 0.2134469450 0.0050080636 0.1875020000 977512553 0 402718720 -0.1617628485 -0.0561297201 0.0022042491 458 1311867733.8918149471 0.1742582917 0.1217722982 0.2134469450 0.0050035133 0.1965540000 977515345 0 402718720 -0.1632135659 -0.0558604933 0.0022253550 459 1311867733.9289460182 0.1779395640 0.1218946669 0.2134469450 0.0050003891 0.1862170000 977518361 0 402718720 -0.1663432419 -0.0563002042 0.0022749966 460 1311867733.9595899582 0.1791570485 0.1220191504 0.2134469450 0.0049988260 0.1867620000 977521265 0 402718720 -0.1673964709 -0.0561029576 0.0019507752 461 1311867733.9941790104 0.1815999746 0.1221483929 0.2134469450 0.0050085943 0.1862190000 977524225 0 402718720 -0.1690752804 -0.0561816543 0.0021305708 462 1311867734.0275731087 0.1837852448 0.1222818060 0.2134469450 0.0050081815 0.1838430000 977527241 0 402718720 -0.1712087989 -0.0564376712 0.0021873217 463 1311867734.0599920750 0.1855658591 0.1224184887 0.2134469450 0.0050041265 0.1977050000 977530089 0 402718720 -0.1727551520 -0.0563260019 0.0023126125 464 1311867734.0956780910 0.1873953491 0.1225585250 0.2134469450 0.0049992784 0.1857290000 977533105 0 402718720 -0.1743798107 -0.0561321378 0.0021961390 465 1311867734.1274170876 0.1900492609 0.1227036664 0.2134469450 0.0049947207 0.1845000000 977536065 0 402718720 -0.1765590757 -0.0570446402 0.0019580610 466 1311867734.1618878841 0.1914696842 0.1228512329 0.2134469450 0.0049925260 0.1840780000 977538969 0 402718720 -0.1776995361 -0.0567684695 0.0018037731 467 1311867734.1942350864 0.1935975403 0.1230027239 0.2134469450 0.0049886705 0.1843860000 977541929 0 402718720 -0.1795493364 -0.0562979169 0.0018852248 468 1311867734.2291829586 0.1953987926 0.1231574164 0.2134469450 0.0049881718 0.1986730000 977544833 0 402718720 -0.1809564829 -0.0570251197 0.0016896197 469 1311867734.2607750893 0.1973150522 0.1233155350 0.2134469450 0.0049834981 0.1847310000 977547737 0 402718720 -0.1825746000 -0.0571637936 0.0016097224 470 1311867734.2941219807 0.1989892572 0.1234765429 0.2134469450 0.0049785555 0.1837470000 977550641 0 402718720 -0.1841386408 -0.0567024536 0.0017658180 471 1311867734.3263280392 0.1999325156 0.1236388699 0.2134469450 0.0049767227 0.1838180000 977553545 0 402718720 -0.1847594529 -0.0569797754 0.0020311533 472 1311867734.3610401154 0.2006669939 0.1238020650 0.2134469450 0.0049741054 0.1835080000 977556505 0 402718720 -0.1852977127 -0.0568009689 0.0021308181 473 1311867734.3941841125 0.2012590617 0.1239658219 0.2134469450 0.0049735312 0.1912480000 977559465 0 402718720 -0.1858816594 -0.0560084395 0.0025364871 474 1311867734.4276480675 0.2026542574 0.1241318313 0.2134469450 0.0049686979 0.1845210000 977562425 0 402718720 -0.1870221943 -0.0564418398 0.0028853621 475 1311867734.4586091042 0.2038798630 0.1242997218 0.2134469450 0.0049651666 0.1849170000 977565273 0 402718720 -0.1880154461 -0.0570820533 0.0031605761 476 1311867734.4938759804 0.2037611455 0.1244666576 0.2134469450 0.0049604252 0.1850250000 977568289 0 402718720 -0.1876740307 -0.0565645657 0.0034720036 477 1311867734.5300569534 0.2033996880 0.1246321357 0.2134469450 0.0049566824 0.2009190000 977571305 0 402718720 -0.1870311350 -0.0565863326 0.0038551167 478 1311867734.5595300198 0.2052395493 0.1248007704 0.2134469450 0.0049610634 0.2061910000 977574097 0 402718720 -0.1884011179 -0.0569226295 0.0041120988 479 1311867734.5953910351 0.2046544552 0.1249674796 0.2134469450 0.0049574441 0.1844510000 977577057 0 402718720 -0.1880618334 -0.0565902628 0.0044981297 480 1311867734.6285231113 0.2043358833 0.1251328304 0.2134469450 0.0049527356 0.1950420000 977580017 0 402718720 -0.1872191578 -0.0565773398 0.0045646555 481 1311867734.6593229771 0.2054291666 0.1252997667 0.2134469450 0.0049479842 0.1845900000 977582865 0 402718720 -0.1882084161 -0.0572141372 0.0046750871 482 1311867734.6947479248 0.2055992782 0.1254663632 0.2134469450 0.0049435069 0.1844820000 977585825 0 402718720 -0.1884393841 -0.0575927831 0.0046753427 483 1311867734.7310240269 0.2072949409 0.1256357805 0.2134469450 0.0049429459 0.1854040000 977588897 0 402718720 -0.1897923499 -0.0575019345 0.0048427945 484 1311867734.7607629299 0.2056604624 0.1258011208 0.2134469450 0.0049400996 0.1977690000 977591689 0 402718720 -0.1877454817 -0.0570641421 0.0044786464 485 1311867734.7976419926 0.2063276470 0.1259671548 0.2134469450 0.0049358766 0.1959530000 977594761 0 402718720 -0.1882235110 -0.0570574887 0.0047775232 486 1311867734.8298120499 0.2064354867 0.1261327275 0.2134469450 0.0049313417 0.1845400000 977597665 0 402718720 -0.1881025732 -0.0566646941 0.0049727960 487 1311867734.8645250797 0.2066213787 0.1262980020 0.2134469450 0.0049272241 0.1844590000 977600625 0 402718720 -0.1880133450 -0.0566546246 0.0053034173 488 1311867734.8943901062 0.2068049014 0.1264629751 0.2134469450 0.0049234950 0.1851300000 977603529 0 402718720 -0.1878139824 -0.0571734346 0.0052972329 489 1311867734.9263660908 0.2071596384 0.1266279990 0.2134469450 0.0049185061 0.1848860000 977606377 0 402718720 -0.1878455430 -0.0573385879 0.0054819481 490 1311867734.9631719589 0.2073065937 0.1267926492 0.2134469450 0.0049150412 0.1826960000 977609169 0 402718720 -0.1874427646 -0.0573284887 0.0052901153 491 1311867734.9948470592 0.2078449130 0.1269577251 0.2134469450 0.0049135935 0.1966590000 977612073 0 402718720 -0.1882105172 -0.0579671562 0.0050813239 492 1311867735.0292239189 0.2090627551 0.1271246052 0.2134469450 0.0049144567 0.1833740000 977615145 0 402718720 -0.1890955716 -0.0578898750 0.0050244913 493 1311867735.0596508980 0.2097556144 0.1272922137 0.2134469450 0.0049099461 0.1961240000 977617881 0 402718720 -0.1899478883 -0.0577048920 0.0052262773 494 1311867735.0952830315 0.2093762755 0.1274583758 0.2134469450 0.0049073719 0.1839990000 977620897 0 402718720 -0.1895126402 -0.0579429269 0.0051852162 495 1311867735.1313030720 0.2101886421 0.1276255077 0.2134469450 0.0049044172 0.1841880000 977623913 0 402718720 -0.1902672797 -0.0579488948 0.0054794364 496 1311867735.1603751183 0.2103551775 0.1277923014 0.2134469450 0.0048996024 0.1834160000 977626705 0 402718720 -0.1903023422 -0.0580341332 0.0057758787 497 1311867735.1994349957 0.2103657871 0.1279584452 0.2134469450 0.0048986605 0.1812690000 977629777 0 402718720 -0.1901033968 -0.0584238656 0.0056831916 498 1311867735.2263538837 0.2091870606 0.1281215549 0.2134469450 0.0048965734 0.1977420000 977632625 0 402718720 -0.1888872236 -0.0579674803 0.0059299725 499 1311867735.2655019760 0.2079251856 0.1282814820 0.2134469450 0.0048924679 0.1837670000 977635641 0 402718720 -0.1875218600 -0.0573989898 0.0063959137 500 1311867735.2961549759 0.2086547762 0.1284422286 0.2134469450 0.0048926500 0.1825770000 977638545 0 402718720 -0.1881929636 -0.0577201657 0.0068925382 501 1311867735.3321089745 0.2083993405 0.1286018236 0.2134469450 0.0048919030 0.1815750000 977641561 0 402718720 -0.1878577173 -0.0573740341 0.0073262118 502 1311867735.3666970730 0.2075234056 0.1287590379 0.2134469450 0.0048955593 0.1823930000 977644409 0 402718720 -0.1868474036 -0.0570930652 0.0075562955 503 1311867735.3943350315 0.2068289965 0.1289142466 0.2134469450 0.0049034947 0.1940710000 977647145 0 402718720 -0.1859722137 -0.0569416322 0.0077777538 504 1311867735.4322299957 0.2069704384 0.1290691200 0.2134469450 0.0049013509 0.2036750000 977650273 0 402718720 -0.1859948188 -0.0568226352 0.0082963752 505 1311867735.4628560543 0.2086616606 0.1292267290 0.2134469450 0.0049103320 0.1807880000 977653121 0 402718720 -0.1869067997 -0.0570654571 0.0086402521 506 1311867735.4973869324 0.2088887244 0.1293841637 0.2134469450 0.0049142926 0.1810750000 977656137 0 402718720 -0.1874199510 -0.0573817082 0.0091343727 507 1311867735.5293200016 0.2099115551 0.1295429949 0.2134469450 0.0049100953 0.1805800000 977658985 0 402718720 -0.1882105023 -0.0574812256 0.0096312929 508 1311867735.5632629395 0.2103243619 0.1297020133 0.2134469450 0.0049058566 0.2094150000 977662001 0 402718720 -0.1883736551 -0.0577248111 0.0099420436 509 1311867735.5976569653 0.2114527971 0.1298626239 0.2134469450 0.0049022306 0.1804800000 977664961 0 402718720 -0.1892042458 -0.0582564622 0.0103350235 510 1311867735.6363260746 0.2125922889 0.1300248389 0.2134469450 0.0049014496 0.1801840000 977667977 0 402718720 -0.1901315451 -0.0585251562 0.0104989111 511 1311867735.6626520157 0.2140996605 0.1301893689 0.2140996605 0.0048975610 0.1793840000 977670769 0 402718720 -0.1913018376 -0.0595097914 0.0104026496 512 1311867735.6952130795 0.2148797810 0.1303547799 0.2148797810 0.0048932203 0.1888910000 977673673 0 402718720 -0.1918794662 -0.0604186244 0.0101842554 513 1311867735.7291250229 0.2163146436 0.1305223430 0.2163146436 0.0048918673 0.1895510000 977676633 0 402718720 -0.1931463778 -0.0603717677 0.0101780742 514 1311867735.7631659508 0.2165640593 0.1306897393 0.2165640593 0.0048881381 0.1771060000 977782049 0 402718720 -0.1933860183 -0.0599944219 0.0101158787 515 1311867735.7963778973 0.2160916626 0.1308555683 0.2165640593 0.0048874860 0.1751320000 977784953 0 402718720 -0.1926549822 -0.0601032600 0.0098636644 516 1311867735.8277759552 0.2175256759 0.1310235336 0.2175256759 0.0048922036 0.1758730000 977787801 0 402718720 -0.1939565092 -0.0595921241 0.0101273591 517 1311867735.8638889790 0.2183271199 0.1311923993 0.2183271199 0.0048885243 0.1759320000 977790649 0 402718720 -0.1946989000 -0.0589731932 0.0106518585 518 1311867735.8951849937 0.2194030434 0.1313626901 0.2194030434 0.0048839738 0.1966050000 977793553 0 402718720 -0.1957885027 -0.0586177409 0.0110830655 519 1311867735.9322230816 0.2209145576 0.1315352371 0.2209145576 0.0048808566 0.1762330000 977796625 0 402718720 -0.1973261684 -0.0582624301 0.0116620744 520 1311867735.9623689651 0.2216560543 0.1317085464 0.2216560543 0.0048784917 0.1749460000 977799473 0 402718720 -0.1982545704 -0.0581133962 0.0121490918 521 1311867735.9945859909 0.2226379514 0.1318830750 0.2226379514 0.0048764396 0.1756230000 977802321 0 402718720 -0.1994011849 -0.0578078292 0.0126135796 522 1311867736.0290079117 0.2231420279 0.1320579005 0.2231420279 0.0048737114 0.1751960000 977805337 0 402718720 -0.2000126094 -0.0576650500 0.0130693745 523 1311867736.0642199516 0.2235185057 0.1322327774 0.2235185057 0.0048698678 0.1868450000 977808353 0 402718720 -0.2004193664 -0.0575524382 0.0134312036 524 1311867736.0946779251 0.2242608070 0.1324084034 0.2242608070 0.0048655361 0.1743770000 977811145 0 402718720 -0.2012855709 -0.0575072207 0.0138094416 525 1311867736.1299190521 0.2244655788 0.1325837504 0.2244655788 0.0048710274 0.1731250000 977814161 0 402718720 -0.2016133219 -0.0574148633 0.0139997574 526 1311867736.1631360054 0.2242392004 0.1327580003 0.2244655788 0.0048672916 0.1731860000 977817177 0 402718720 -0.2018251121 -0.0573423095 0.0139870690 527 1311867736.1942429543 0.2259740680 0.1329348809 0.2259740680 0.0048691540 0.1719880000 977819969 0 402718720 -0.2036774755 -0.0573135950 0.0141473524 528 1311867736.2298679352 0.2267705500 0.1331126000 0.2267705500 0.0048677214 0.1948270000 977822985 0 402718720 -0.2050773203 -0.0575216338 0.0145159401 529 1311867736.2633900642 0.2272057831 0.1332904699 0.2272057831 0.0048684301 0.1728610000 977825945 0 402718720 -0.2056606859 -0.0577417947 0.0147640007 530 1311867736.2995250225 0.2275692075 0.1334683543 0.2275692075 0.0048659669 0.1723550000 977828961 0 402718720 -0.2061793655 -0.0581185147 0.0148004033 531 1311867736.3304500580 0.2291143090 0.1336484785 0.2291143090 0.0048626050 0.1706320000 977831753 0 402718720 -0.2079187632 -0.0581514165 0.0153645035 532 1311867736.3637149334 0.2309467345 0.1338313700 0.2309467345 0.0048601631 0.1914660000 977834713 0 402718720 -0.2097376734 -0.0587605909 0.0157458801 533 1311867736.3943159580 0.2324341983 0.1340163659 0.2324341983 0.0048566704 0.1716390000 977837505 0 402718720 -0.2111126781 -0.0596482605 0.0156477205 534 1311867736.4313519001 0.2331159264 0.1342019456 0.2331159264 0.0048643427 0.1817440000 977840633 0 402718720 -0.2116637081 -0.0595961250 0.0159071609 535 1311867736.4625089169 0.2344479114 0.1343893212 0.2344479114 0.0048625070 0.1712050000 977843537 0 402718720 -0.2131367624 -0.0601532161 0.0160592608 536 1311867736.4987530708 0.2361517251 0.1345791765 0.2361517251 0.0048587172 0.1699180000 977846497 0 402718720 -0.2146449834 -0.0610239282 0.0161683504 537 1311867736.5321619511 0.2372283489 0.1347703295 0.2372283489 0.0048610832 0.1692820000 977849457 0 402718720 -0.2156658173 -0.0607555322 0.0165235996 538 1311867736.5634689331 0.2373967171 0.1349610849 0.2373967171 0.0048574400 0.1900760000 977852361 0 402718720 -0.2159544379 -0.0607944243 0.0166693348 539 1311867736.5958600044 0.2389452010 0.1351540053 0.2389452010 0.0048537878 0.1681500000 977855265 0 402718720 -0.2174724787 -0.0622281209 0.0167066846 540 1311867736.6320459843 0.2398055941 0.1353478045 0.2398055941 0.0048569783 0.1683340000 977858281 0 402718720 -0.2180024236 -0.0624140985 0.0168365669 541 1311867736.6635379791 0.2394988537 0.1355403203 0.2398055941 0.0048673660 0.1804260000 977861185 0 402718720 -0.2180978954 -0.0629755855 0.0167921521 542 1311867736.6945500374 0.2419736385 0.1357366918 0.2419736385 0.0048688810 0.1803190000 977863977 0 402718720 -0.2204025388 -0.0645427033 0.0166255627 543 1311867736.7332150936 0.2426054329 0.1359335035 0.2426054329 0.0048647876 0.1686910000 977867049 0 402718720 -0.2209636867 -0.0651912391 0.0167796947 544 1311867736.7636179924 0.2435423285 0.1361313138 0.2435423285 0.0048639651 0.1682330000 977869953 0 402718720 -0.2212634385 -0.0654109120 0.0168329310 545 1311867736.7952749729 0.2454250902 0.1363318528 0.2454250902 0.0048710002 0.1678730000 977872801 0 402718720 -0.2231937647 -0.0663393661 0.0166934412 546 1311867736.8325269222 0.2492891848 0.1365387344 0.2492891848 0.0048734650 0.1673460000 977875817 0 402718720 -0.2267039567 -0.0667679012 0.0170823708 547 1311867736.8640279770 0.2499422431 0.1367460534 0.2499422431 0.0048727609 0.1680440000 977878777 0 402718720 -0.2272250503 -0.0661253184 0.0173635073 548 1311867736.8945000172 0.2522411346 0.1369568109 0.2522411346 0.0048712845 0.1906480000 977881569 0 402718720 -0.2292799056 -0.0665936694 0.0175324660 549 1311867736.9362800121 0.2543754876 0.1371706882 0.2543754876 0.0048713842 0.1684540000 977884753 0 402718720 -0.2310082316 -0.0666264966 0.0177484546 550 1311867736.9632000923 0.2555421591 0.1373859091 0.2555421591 0.0048675088 0.1691530000 977887545 0 402718720 -0.2322122306 -0.0660442188 0.0184461307 551 1311867736.9954400063 0.2569670081 0.1376029347 0.2569670081 0.0048658444 0.1674810000 977890449 0 402718720 -0.2332913876 -0.0668337792 0.0189453103 552 1311867737.0307478905 0.2580328286 0.1378211048 0.2580328286 0.0048616897 0.1816070000 977893409 0 402718720 -0.2341636419 -0.0678258538 0.0191801544 553 1311867737.0629029274 0.2577188611 0.1380379181 0.2580328286 0.0048574963 0.1693660000 977896369 0 402718720 -0.2338219732 -0.0671651214 0.0195025634 554 1311867737.0977239609 0.2592859864 0.1382567774 0.2592859864 0.0048540783 0.1702540000 977899329 0 402718720 -0.2353674769 -0.0674376190 0.0195173305 555 1311867737.1300530434 0.2597148120 0.1384756207 0.2597148120 0.0048497657 0.1857960000 977902177 0 402718720 -0.2357446700 -0.0677469075 0.0194852278 556 1311867737.1655049324 0.2596404552 0.1386935431 0.2597148120 0.0048455908 0.1697250000 977905193 0 402718720 -0.2356341928 -0.0673455819 0.0195527989 557 1311867737.1952710152 0.2604735494 0.1389121786 0.2604735494 0.0048414461 0.1702810000 977908041 0 402718720 -0.2362865955 -0.0674350783 0.0194849912 558 1311867737.2333149910 0.2611258924 0.1391311996 0.2611258924 0.0048376982 0.1872800000 977911169 0 402718720 -0.2367512286 -0.0679278299 0.0194542464 559 1311867737.2693018913 0.2611197233 0.1393494260 0.2611258924 0.0048390599 0.1711840000 977914129 0 402718720 -0.2361346930 -0.0675387979 0.0196700525 560 1311867737.2957379818 0.2617917359 0.1395680730 0.2617917359 0.0048353506 0.1695160000 977916865 0 402718720 -0.2366178185 -0.0673649833 0.0200198777 561 1311867737.3316531181 0.2621054053 0.1397864996 0.2621054053 0.0048312911 0.1899870000 977919937 0 402718720 -0.2367303073 -0.0673372522 0.0202829260 562 1311867737.3659460545 0.2619991899 0.1400039599 0.2621054053 0.0048269980 0.1839110000 977922841 0 402718720 -0.2367641479 -0.0670863837 0.0205344297 563 1311867737.3967239857 0.2631445229 0.1402226820 0.2631445229 0.0048247849 0.1954890000 977925745 0 402718720 -0.2376720905 -0.0672053173 0.0210081767 564 1311867737.4355359077 0.2640811503 0.1404422892 0.2640811503 0.0048214364 0.1718880000 977928817 0 402718720 -0.2384822518 -0.0672017932 0.0217008777 565 1311867737.4691100121 0.2650067210 0.1406627573 0.2650067210 0.0048171810 0.1707780000 977931777 0 402718720 -0.2392727584 -0.0672299191 0.0221759193 566 1311867737.4959459305 0.2653368711 0.1408830295 0.2653368711 0.0048129270 0.1705120000 977934513 0 402718720 -0.2396593839 -0.0674001127 0.0226929076 567 1311867737.5353999138 0.2662715018 0.1411041732 0.2662715018 0.0048095873 0.1715260000 977937641 0 402718720 -0.2403033525 -0.0677508414 0.0231995545 568 1311867737.5654399395 0.2656446695 0.1413234347 0.2662715018 0.0048058435 0.1841160000 977940433 0 402718720 -0.2391225696 -0.0677329078 0.0234588347 569 1311867737.5958089828 0.2664726973 0.1415433806 0.2664726973 0.0048026401 0.1696110000 977943337 0 402718720 -0.2396103144 -0.0679246709 0.0240799896 570 1311867737.6330978870 0.2678251565 0.1417649276 0.2678251565 0.0047988024 0.1718620000 977946409 0 402718720 -0.2406786531 -0.0679175407 0.0246518422 571 1311867737.6624519825 0.2692281902 0.1419881558 0.2692281902 0.0047954067 0.1716340000 977949257 0 402718720 -0.2418425828 -0.0684046149 0.0250661373 572 1311867737.7032339573 0.2703161836 0.1422125054 0.2703161836 0.0047920031 0.1724130000 977952329 0 402718720 -0.2425640076 -0.0692996979 0.0253384151 573 1311867737.7314720154 0.2711265683 0.1424374864 0.2711265683 0.0047884521 0.1719330000 977955121 0 402718720 -0.2430083603 -0.0698575899 0.0257054623 574 1311867737.7658560276 0.2714411318 0.1426622314 0.2714411318 0.0047844427 0.1704660000 977958081 0 402718720 -0.2430316061 -0.0699096397 0.0259341318 575 1311867737.8011269569 0.2718575597 0.1428869189 0.2718575597 0.0047815628 0.1726810000 977961097 0 402718720 -0.2432187051 -0.0698331445 0.0263346061 576 1311867737.8323190212 0.2717666626 0.1431106685 0.2718575597 0.0047777774 0.1719700000 977964001 0 402718720 -0.2429051399 -0.0699750036 0.0267755464 577 1311867737.8633110523 0.2726173699 0.1433351168 0.2726173699 0.0047792016 0.1729700000 977966849 0 402718720 -0.2432104349 -0.0697176829 0.0272819921 578 1311867737.9004418850 0.2726447582 0.1435588359 0.2726447582 0.0047755070 0.1937520000 977969809 0 402718720 -0.2427086979 -0.0704609156 0.0278732236 579 1311867737.9305500984 0.2727800906 0.1437820160 0.2727800906 0.0047776321 0.1741940000 977972657 0 402718720 -0.2425473034 -0.0705926120 0.0284140743 580 1311867737.9630560875 0.2738837004 0.1440063292 0.2738837004 0.0047742424 0.1854350000 977975617 0 402718720 -0.2432813495 -0.0705772042 0.0290590338 581 1311867737.9996941090 0.2748416960 0.1442315192 0.2748416960 0.0047712892 0.1723960000 977978633 0 402718720 -0.2437742949 -0.0710791498 0.0297379717 582 1311867738.0315399170 0.2756898999 0.1444573927 0.2756898999 0.0047680969 0.1743390000 977981537 0 402718720 -0.2442534119 -0.0708459467 0.0305585023 583 1311867738.0629770756 0.2748142183 0.1446809893 0.2756898999 0.0047640766 0.1865910000 977984441 0 402718720 -0.2428119928 -0.0706020072 0.0315350257 584 1311867738.0998299122 0.2752194107 0.1449045140 0.2756898999 0.0047615149 0.1735540000 977987401 0 402718720 -0.2426251322 -0.0708842576 0.0321500599 585 1311867738.1308510303 0.2747707665 0.1451265076 0.2756898999 0.0047594355 0.1863780000 977990249 0 402718720 -0.2414878160 -0.0717230290 0.0330523737 586 1311867738.1635079384 0.2754264176 0.1453488624 0.2756898999 0.0047561402 0.1732320000 977993209 0 402718720 -0.2416124046 -0.0724880546 0.0337446332 587 1311867738.1992070675 0.2766864300 0.1455726061 0.2766864300 0.0047532776 0.1738170000 977996169 0 402718720 -0.2422003001 -0.0730758831 0.0344953649 588 1311867738.2306089401 0.2773329914 0.1457966884 0.2773329914 0.0047533184 0.1885170000 977999073 0 402718720 -0.2424667925 -0.0740443841 0.0348590948 589 1311867738.2632689476 0.2779022455 0.1460209763 0.2779022455 0.0047551678 0.1863210000 978002033 0 402718720 -0.2424724996 -0.0751204491 0.0348443501 590 1311867738.3008689880 0.2786608338 0.1462457896 0.2786608338 0.0047518321 0.1902410000 978005049 0 402718720 -0.2425978780 -0.0759633705 0.0351495408 591 1311867738.3339769840 0.2805466354 0.1464730330 0.2805466354 0.0047504246 0.1744560000 978007953 0 402718720 -0.2439743578 -0.0765935779 0.0353140384 592 1311867738.3651630878 0.2819311321 0.1467018474 0.2819311321 0.0047466958 0.1749160000 978010857 0 402718720 -0.2451743633 -0.0768735260 0.0353543200 593 1311867738.3995900154 0.2828653157 0.1469314653 0.2828653157 0.0047432314 0.1846040000 978013873 0 402718720 -0.2456265390 -0.0768349320 0.0354538076 594 1311867738.4334011078 0.2826158404 0.1471598902 0.2828653157 0.0047400422 0.1758540000 978016833 0 402718720 -0.2452276051 -0.0766354278 0.0355065055 595 1311867738.4643430710 0.2842659950 0.1473903207 0.2842659950 0.0047364398 0.1757100000 978019681 0 402718720 -0.2460501939 -0.0770917460 0.0355482213 596 1311867738.5000250340 0.2842006087 0.1476198681 0.2842659950 0.0047331324 0.1763250000 978022697 0 402718720 -0.2453941107 -0.0767780915 0.0356840231 597 1311867738.5332009792 0.2842398584 0.1478487123 0.2842659950 0.0047295835 0.1756520000 978025601 0 402718720 -0.2447206378 -0.0761517435 0.0359441824 598 1311867738.5634350777 0.2844996750 0.1480772256 0.2844996750 0.0047268829 0.1910260000 978028505 0 402718720 -0.2442818433 -0.0766531304 0.0361356698 599 1311867738.6022439003 0.2843329608 0.1483046976 0.2844996750 0.0047246220 0.1751920000 978031577 0 402718720 -0.2431294173 -0.0769787133 0.0361763537 600 1311867738.6328980923 0.2845499516 0.1485317731 0.2845499516 0.0047209139 0.1733490000 978034425 0 402718720 -0.2424274981 -0.0768890306 0.0362414904 601 1311867738.6628730297 0.2849587798 0.1487587731 0.2849587798 0.0047186956 0.1750860000 978037329 0 402718720 -0.2419769913 -0.0771839023 0.0362413265 602 1311867738.6996099949 0.2855660021 0.1489860276 0.2855660021 0.0047176212 0.1734800000 978040345 0 402718720 -0.2415921539 -0.0777854100 0.0362810344 603 1311867738.7314729691 0.2860242724 0.1492132884 0.2860242724 0.0047209268 0.2029830000 978043249 0 402718720 -0.2412550002 -0.0778480619 0.0363976285 604 1311867738.7626600266 0.2868289351 0.1494411289 0.2868289351 0.0047202457 0.1757820000 978046097 0 402718720 -0.2411482781 -0.0775638446 0.0365865268 605 1311867738.8032259941 0.2876881063 0.1496696363 0.2876881063 0.0047240813 0.1759920000 978049225 0 402718720 -0.2409808785 -0.0777857229 0.0367743857 606 1311867738.8306779861 0.2879221737 0.1498977758 0.2879221737 0.0047237625 0.1761570000 978052017 0 402718720 -0.2405691147 -0.0779689550 0.0368624032 607 1311867738.8639259338 0.2863817215 0.1501226258 0.2879221737 0.0047198870 0.1755260000 978054977 0 402718720 -0.2383140326 -0.0776900947 0.0366783664 608 1311867738.9000120163 0.2874622643 0.1503485133 0.2879221737 0.0047219454 0.1885590000 978057993 0 402718720 -0.2386431098 -0.0776041076 0.0367379747 609 1311867738.9307610989 0.2884906232 0.1505753477 0.2884906232 0.0047257442 0.1758970000 978060841 0 402718720 -0.2391599566 -0.0775777027 0.0370551534 610 1311867738.9664750099 0.2884310186 0.1508013406 0.2884906232 0.0047220405 0.1752160000 978063857 0 402718720 -0.2386334389 -0.0772730634 0.0372337885 611 1311867738.9989941120 0.2888660431 0.1510273057 0.2888660431 0.0047188798 0.1759730000 978066817 0 402718720 -0.2386227995 -0.0770240054 0.0371317714 612 1311867739.0329539776 0.2881388068 0.1512513441 0.2888660431 0.0047176900 0.1755310000 978069777 0 402718720 -0.2373952270 -0.0778198093 0.0370094068 613 1311867739.0664470196 0.2865916789 0.1514721277 0.2888660431 0.0047192155 0.1859350000 978072681 0 402718720 -0.2353255600 -0.0779888853 0.0369506553 614 1311867739.0997900963 0.2856727839 0.1516906955 0.2888660431 0.0047154899 0.1745610000 978075473 0 402718720 -0.2340760678 -0.0776235163 0.0368518718 615 1311867739.1321549416 0.2850686908 0.1519075703 0.2888660431 0.0047134904 0.1851650000 978078321 0 402718720 -0.2331449240 -0.0777748004 0.0369517244 616 1311867739.1687150002 0.2849563658 0.1521235586 0.2888660431 0.0047102433 0.1723520000 978081337 0 402718720 -0.2329677939 -0.0774947703 0.0371377617 617 1311867739.1999289989 0.2858628035 0.1523403159 0.2888660431 0.0047078186 0.1737730000 978084185 0 402718720 -0.2338798195 -0.0773501396 0.0376177244 618 1311867739.2313010693 0.2849532664 0.1525549000 0.2888660431 0.0047046415 0.1979370000 978087033 0 402718720 -0.2328676283 -0.0777030066 0.0378075615 619 1311867739.2672259808 0.2845082283 0.1527680717 0.2888660431 0.0047023597 0.1735220000 978090105 0 402718720 -0.2325449884 -0.0782681704 0.0378863625 620 1311867739.2996931076 0.2848296463 0.1529810743 0.2888660431 0.0047036736 0.1723920000 978093009 0 402718720 -0.2329591066 -0.0787721425 0.0381972827 621 1311867739.3319859505 0.2840343416 0.1531921101 0.2888660431 0.0047006663 0.1709270000 978095913 0 402718720 -0.2321762592 -0.0786457434 0.0384185277 622 1311867739.3670029640 0.2840805352 0.1534025417 0.2888660431 0.0046997847 0.1712000000 978098873 0 402718720 -0.2325108051 -0.0783855692 0.0386217311 623 1311867739.3990058899 0.2831585705 0.1536108178 0.2888660431 0.0046963938 0.1855470000 978101833 0 402718720 -0.2318350524 -0.0782802254 0.0388615914 624 1311867739.4311320782 0.2817209959 0.1538161226 0.2888660431 0.0046939703 0.1853060000 978104681 0 402718720 -0.2303985059 -0.0781473964 0.0390314683 625 1311867739.4668490887 0.2832188308 0.1540231669 0.2888660431 0.0046905798 0.1733510000 978107697 0 402718720 -0.2319141775 -0.0784197748 0.0395303518 626 1311867739.4988598824 0.2844820619 0.1542315677 0.2888660431 0.0046975051 0.1730160000 978110601 0 402718720 -0.2331276238 -0.0789701492 0.0400829539 627 1311867739.5316400528 0.2839972377 0.1544385305 0.2888660431 0.0046940041 0.1717730000 978113449 0 402718720 -0.2324530631 -0.0787538067 0.0404551923 628 1311867739.5670249462 0.2851934135 0.1546467389 0.2888660431 0.0046918513 0.1724220000 978116465 0 402718720 -0.2336172611 -0.0785044432 0.0414193273 629 1311867739.5990490913 0.2864348292 0.1548562589 0.2888660431 0.0046881759 0.1714230000 978119369 0 402718720 -0.2348743677 -0.0789818913 0.0421290472 630 1311867739.6325490475 0.2872911394 0.1550664730 0.2888660431 0.0046845100 0.1722850000 978122329 0 402718720 -0.2359999120 -0.0785327852 0.0427623466 631 1311867739.6706740856 0.2886601090 0.1552781904 0.2888660431 0.0046823314 0.1701240000 978125401 0 402718720 -0.2376716286 -0.0787873641 0.0434410088 632 1311867739.7001221180 0.2893829048 0.1554903814 0.2893829048 0.0046794991 0.1725740000 978128249 0 402718720 -0.2385022491 -0.0786101520 0.0441230386 633 1311867739.7323939800 0.2888323963 0.1557010323 0.2893829048 0.0046770441 0.1814030000 978131153 0 402718720 -0.2381378114 -0.0782965049 0.0448787324 634 1311867739.7662999630 0.2893885076 0.1559118958 0.2893885076 0.0046738968 0.1919690000 978134113 0 402718720 -0.2388517708 -0.0783731863 0.0456500947 635 1311867739.8016180992 0.2895280719 0.1561223150 0.2895280719 0.0046709578 0.1722440000 978137129 0 402718720 -0.2392706275 -0.0788014457 0.0461456440 636 1311867739.8325679302 0.2898137271 0.1563325216 0.2898137271 0.0046703608 0.1708600000 978139977 0 402718720 -0.2398555875 -0.0783896297 0.0466566384 637 1311867739.8701560497 0.2898659110 0.1565421501 0.2898659110 0.0046670726 0.1708140000 978142993 0 402718720 -0.2404733747 -0.0784123018 0.0471913330 638 1311867739.9036860466 0.2906551659 0.1567523586 0.2906551659 0.0046640990 0.1711570000 978146009 0 402718720 -0.2419586480 -0.0792483985 0.0473807529 639 1311867739.9317240715 0.2913953960 0.1569630676 0.2913953960 0.0046607709 0.1828140000 978148801 0 402718720 -0.2432002425 -0.0792263374 0.0476138331 640 1311867739.9668979645 0.2914856672 0.1571732592 0.2914856672 0.0046578818 0.1711100000 978151761 0 402718720 -0.2437491715 -0.0788999200 0.0478987247 641 1311867739.9987080097 0.2931719720 0.1573854256 0.2931719720 0.0046550884 0.1698370000 978154721 0 402718720 -0.2460962385 -0.0792514533 0.0485070646 642 1311867740.0328791142 0.2933524847 0.1575972123 0.2933524847 0.0046517633 0.1692120000 978157681 0 402718720 -0.2468784153 -0.0793435723 0.0487592742 643 1311867740.0671849251 0.2925198972 0.1578070454 0.2933524847 0.0046487862 0.1692530000 978160585 0 402718720 -0.2464984506 -0.0787561536 0.0487972386 644 1311867740.0992529392 0.2929249108 0.1580168558 0.2933524847 0.0046480390 0.1704270000 978163545 0 402718720 -0.2471636683 -0.0793981329 0.0490687229 645 1311867740.1347720623 0.2937951982 0.1582273648 0.2937951982 0.0046455468 0.1699190000 978166449 0 402718720 -0.2487495542 -0.0800205693 0.0492510051 646 1311867740.1666491032 0.2940513194 0.1584376186 0.2940513194 0.0046422671 0.1683300000 978169409 0 402718720 -0.2491686195 -0.0797227472 0.0492213517 647 1311867740.1993310452 0.2936978638 0.1586466762 0.2940513194 0.0046389472 0.1963890000 978172369 0 402718720 -0.2492263615 -0.0794403479 0.0494297668 648 1311867740.2383539677 0.2948062718 0.1588567990 0.2948062718 0.0046370440 0.1677500000 978175497 0 402718720 -0.2508550584 -0.0799208507 0.0493950062 649 1311867740.2664349079 0.2942222357 0.1590653745 0.2948062718 0.0046360808 0.1698750000 978178233 0 402718720 -0.2506258786 -0.0795947313 0.0493169725 650 1311867740.2981588840 0.2953655720 0.1592750671 0.2953655720 0.0046339707 0.1695620000 978181137 0 402718720 -0.2520979047 -0.0789950863 0.0496119410 651 1311867740.3347120285 0.2946026325 0.1594829435 0.2953655720 0.0046306542 0.1695810000 978184209 0 402718720 -0.2517612576 -0.0794471875 0.0493260995 652 1311867740.3665161133 0.2939816713 0.1596892299 0.2953655720 0.0046293094 0.1677590000 978187057 0 402718720 -0.2513527274 -0.0792568251 0.0489101447 653 1311867740.3993780613 0.2933311462 0.1598938883 0.2953655720 0.0046267578 0.1690680000 978189961 0 402718720 -0.2508061230 -0.0793632865 0.0485654026 654 1311867740.4346680641 0.2939932048 0.1600989331 0.2953655720 0.0046255345 0.1697620000 978192977 0 402718720 -0.2513355613 -0.0794002637 0.0482707582 655 1311867740.4664289951 0.2945767343 0.1603042427 0.2953655720 0.0046230414 0.1694310000 978195881 0 402718720 -0.2520370185 -0.0792636275 0.0480227061 656 1311867740.4993040562 0.2954770625 0.1605102988 0.2954770625 0.0046225779 0.1687890000 978198785 0 402718720 -0.2525617778 -0.0791850984 0.0478790142 657 1311867740.5354259014 0.2964459062 0.1607172024 0.2964459062 0.0046236600 0.1690580000 978201801 0 402718720 -0.2531301379 -0.0792819336 0.0477812029 658 1311867740.5666589737 0.2968001664 0.1609240154 0.2968001664 0.0046206244 0.1800880000 978204705 0 402718720 -0.2533051074 -0.0791916028 0.0475937128 659 1311867740.6008880138 0.2984108031 0.1611326448 0.2984108031 0.0046197900 0.1811810000 978207665 0 402718720 -0.2548331022 -0.0787535906 0.0476380326 660 1311867740.6346809864 0.2989096344 0.1613413978 0.2989096344 0.0046185564 0.1678650000 978210625 0 402718720 -0.2553794682 -0.0787955448 0.0476771593 661 1311867740.6665890217 0.2987138629 0.1615492230 0.2989096344 0.0046155211 0.1679190000 978213529 0 402718720 -0.2553825080 -0.0787398592 0.0473282859 662 1311867740.6994900703 0.2998177707 0.1617580879 0.2998177707 0.0046132554 0.1807280000 978216433 0 402718720 -0.2566427886 -0.0790231079 0.0469582975 663 1311867740.7368240356 0.2996382713 0.1619660520 0.2998177707 0.0046120115 0.1674610000 978219337 0 402718720 -0.2566083372 -0.0790120363 0.0466365330 664 1311867740.7668819427 0.3002958298 0.1621743800 0.3002958298 0.0046094048 0.1839820000 978222185 0 402718720 -0.2575142980 -0.0790618360 0.0465159677 665 1311867740.7996399403 0.3022243977 0.1623849815 0.3022243977 0.0046069327 0.1657580000 978225145 0 402718720 -0.2597272396 -0.0793980211 0.0468454771 666 1311867740.8349099159 0.3026375771 0.1625955710 0.3026375771 0.0046037418 0.1681340000 978228049 0 402718720 -0.2604604959 -0.0789612159 0.0465429574 667 1311867740.8668210506 0.3029922247 0.1628060607 0.3029922247 0.0046007983 0.1656030000 978231009 0 402718720 -0.2611372769 -0.0790715143 0.0466582403 668 1311867740.8993830681 0.3034737408 0.1630166411 0.3034737408 0.0045974747 0.1785420000 978233913 0 402718720 -0.2623076439 -0.0792966485 0.0463905744 669 1311867740.9399120808 0.3031426966 0.1632260970 0.3034737408 0.0045969721 0.1775370000 978237097 0 402718720 -0.2625694275 -0.0789108127 0.0460786745 670 1311867740.9665501118 0.3026260436 0.1634341567 0.3034737408 0.0045936412 0.1667950000 978239833 0 402718720 -0.2625262141 -0.0785266012 0.0456682779 671 1311867741.0021579266 0.3036556244 0.1636431305 0.3036556244 0.0045909568 0.1667500000 978242849 0 402718720 -0.2640371323 -0.0790352672 0.0454925746 672 1311867741.0367169380 0.3034684956 0.1638512040 0.3036556244 0.0045877653 0.1675220000 978245809 0 402718720 -0.2641657293 -0.0790261850 0.0451028049 673 1311867741.0666699409 0.3030984402 0.1640581093 0.3036556244 0.0045855968 0.1677670000 978248657 0 402718720 -0.2641564906 -0.0783342198 0.0447752587 674 1311867741.1009640694 0.3038467169 0.1642655107 0.3038467169 0.0045870521 0.1675340000 978251617 0 402718720 -0.2653631270 -0.0791201741 0.0444569662 675 1311867741.1357901096 0.3036993444 0.1644720794 0.3038467169 0.0045842601 0.1681170000 978254577 0 402718720 -0.2657254338 -0.0793488249 0.0438401140 676 1311867741.1675300598 0.3032726645 0.1646774057 0.3038467169 0.0045812641 0.1653960000 978257537 0 402718720 -0.2653195560 -0.0797090754 0.0434026271 677 1311867741.2014830112 0.3037772775 0.1648828708 0.3038467169 0.0045823897 0.1679610000 978260441 0 402718720 -0.2657396197 -0.0801115409 0.0429440923 678 1311867741.2411060333 0.3046821058 0.1650890644 0.3046821058 0.0045844294 0.1672220000 978263569 0 402718720 -0.2668021321 -0.0809144899 0.0426815189 679 1311867741.2668209076 0.3053559661 0.1652956430 0.3053559661 0.0045849133 0.1774610000 978266305 0 402718720 -0.2673100829 -0.0808494240 0.0425761379 680 1311867741.2997009754 0.3060965240 0.1655027031 0.3060965240 0.0045815954 0.1791060000 978269209 0 402718720 -0.2678652704 -0.0807361975 0.0422847122 681 1311867741.3348419666 0.3066888452 0.1657100249 0.3066888452 0.0045784028 0.1658840000 978272225 0 402718720 -0.2684180737 -0.0801719129 0.0418810695 682 1311867741.3701419830 0.3066509366 0.1659166832 0.3066888452 0.0045750699 0.1652430000 978275185 0 402718720 -0.2680837512 -0.0794268474 0.0414678901 683 1311867741.4066278934 0.3070809841 0.1661233659 0.3070809841 0.0045732289 0.1658550000 978278257 0 402718720 -0.2680608332 -0.0793757364 0.0413608178 684 1311867741.4393060207 0.3072589934 0.1663297045 0.3072589934 0.0045711475 0.1752510000 978281217 0 402718720 -0.2680010498 -0.0786786228 0.0413582399 685 1311867741.4667329788 0.3065754473 0.1665344428 0.3072589934 0.0045679842 0.1660800000 978283953 0 402718720 -0.2669396996 -0.0780681074 0.0410452448 686 1311867741.5025069714 0.3073766828 0.1667397522 0.3073766828 0.0045658416 0.1638810000 978286969 0 402718720 -0.2671728134 -0.0775564089 0.0414425246 687 1311867741.5368049145 0.3078989089 0.1669452241 0.3078989089 0.0045640338 0.1637920000 978289929 0 402718720 -0.2672645748 -0.0775556266 0.0413345955 688 1311867741.5688209534 0.3072125614 0.1671491010 0.3078989089 0.0045607932 0.1645840000 978292833 0 402718720 -0.2661188245 -0.0769913867 0.0411038287 689 1311867741.6046030521 0.3078582883 0.1673533233 0.3078989089 0.0045665175 0.1668980000 978295793 0 402718720 -0.2663501501 -0.0767607018 0.0413375534 690 1311867741.6355440617 0.3086102307 0.1675580435 0.3086102307 0.0045637349 0.1667800000 978298697 0 402718720 -0.2665996850 -0.0766160414 0.0413416438 691 1311867741.6679561138 0.3082282543 0.1677616183 0.3086102307 0.0045606396 0.1667080000 978301657 0 402718720 -0.2656244934 -0.0764197037 0.0411667638 692 1311867741.7048020363 0.3095328808 0.1679664901 0.3095328808 0.0045622759 0.1772430000 978304673 0 402718720 -0.2661128044 -0.0760492086 0.0410874113 693 1311867741.7345991135 0.3093043864 0.1681704409 0.3095328808 0.0045604624 0.1659500000 978307465 0 402718720 -0.2653213143 -0.0760877505 0.0407315530 694 1311867741.7702169418 0.3097243905 0.1683744091 0.3097243905 0.0045572523 0.1808970000 978310481 0 402718720 -0.2649101615 -0.0762423500 0.0406069979 695 1311867741.8058650494 0.3097694814 0.1685778552 0.3097694814 0.0045539875 0.1670940000 978313497 0 402718720 -0.2640759051 -0.0761078522 0.0402753875 696 1311867741.8388509750 0.3099375665 0.1687809583 0.3099375665 0.0045517255 0.1671810000 978316513 0 402718720 -0.2636415958 -0.0761177987 0.0399978682 697 1311867741.8683021069 0.3104562461 0.1689842227 0.3104562461 0.0045490100 0.1670120000 978319305 0 402718720 -0.2635055184 -0.0761533678 0.0398674756 698 1311867741.9065721035 0.3105766475 0.1691870772 0.3105766475 0.0045458211 0.1912790000 978322377 0 402718720 -0.2629670501 -0.0758738443 0.0394456610 699 1311867741.9387769699 0.3113096952 0.1693903999 0.3113096952 0.0045433926 0.2070640000 978325337 0 402718720 -0.2628132999 -0.0757639557 0.0392376669 700 1311867741.9665379524 0.3113193810 0.1695931556 0.3113193810 0.0045410666 0.1680710000 978328073 0 402718720 -0.2621053159 -0.0759333745 0.0388706438 701 1311867742.0029959679 0.3115558326 0.1697956701 0.3115558326 0.0045381392 0.1641140000 978331089 0 402718720 -0.2613249719 -0.0761836097 0.0388424359 702 1311867742.0344839096 0.3122408986 0.1699985836 0.3122408986 0.0045350425 0.1662370000 978333937 0 402718720 -0.2611662745 -0.0760080069 0.0387401469 703 1311867742.0674400330 0.3120685518 0.1702006746 0.3122408986 0.0045323062 0.1658300000 978336841 0 402718720 -0.2602019310 -0.0757423267 0.0385243893 704 1311867742.1030650139 0.3133074939 0.1704039513 0.3133074939 0.0045300158 0.1669890000 978339801 0 402718720 -0.2601641715 -0.0754123926 0.0383597836 705 1311867742.1348879337 0.3137638867 0.1706072987 0.3137638867 0.0045278340 0.1661020000 978342649 0 402718720 -0.2595631778 -0.0753928795 0.0381563678 706 1311867742.1672229767 0.3133583069 0.1708094956 0.3137638867 0.0045254587 0.1658780000 978345609 0 402718720 -0.2586611807 -0.0749403909 0.0380610637 707 1311867742.2028279305 0.3134481311 0.1710112476 0.3137638867 0.0045228341 0.1932760000 978348681 0 402718720 -0.2578099966 -0.0746339634 0.0379219539 708 1311867742.2362670898 0.3138836920 0.1712130448 0.3138836920 0.0045209793 0.1659980000 978351585 0 402718720 -0.2574098110 -0.0743759945 0.0378927477 709 1311867742.2674059868 0.3139678240 0.1714143915 0.3139678240 0.0045183269 0.1803910000 978354489 0 402718720 -0.2568218708 -0.0748469532 0.0379562341 710 1311867742.3028159142 0.3143022358 0.1716156420 0.3143022358 0.0045158221 0.1663650000 978357505 0 402718720 -0.2567316592 -0.0748194605 0.0376720428 711 1311867742.3350739479 0.3147769868 0.1718169941 0.3147769868 0.0045132206 0.1666950000 978360353 0 402718720 -0.2568306923 -0.0746110603 0.0374586359 712 1311867742.3694241047 0.3147232831 0.1720177051 0.3147769868 0.0045100759 0.1782950000 978363369 0 402718720 -0.2565834224 -0.0748566613 0.0370485075 713 1311867742.4062991142 0.3159573972 0.1722195841 0.3159573972 0.0045070044 0.1659940000 978366385 0 402718720 -0.2574803531 -0.0748353004 0.0365988463 714 1311867742.4346439838 0.3158630431 0.1724207654 0.3159573972 0.0045039840 0.1835240000 978369177 0 402718720 -0.2570987940 -0.0749501958 0.0362332612 715 1311867742.4666969776 0.3165964186 0.1726224097 0.3165964186 0.0045014549 0.1656960000 978372081 0 402718720 -0.2574830055 -0.0748022422 0.0359979346 716 1311867742.5047059059 0.3166861832 0.1728236161 0.3166861832 0.0044983982 0.1631900000 978375097 0 402718720 -0.2571226954 -0.0746840015 0.0359006375 717 1311867742.5359389782 0.3168551624 0.1730244969 0.3168551624 0.0044956022 0.1649700000 978378001 0 402718720 -0.2569555640 -0.0742936879 0.0357718319 718 1311867742.5678529739 0.3165411353 0.1732243808 0.3168551624 0.0044931457 0.1659170000 978380961 0 402718720 -0.2562351823 -0.0739613622 0.0356991850 719 1311867742.6054639816 0.3168477416 0.1734241351 0.3168551624 0.0044902098 0.1785170000 978383977 0 402718720 -0.2561698556 -0.0741620660 0.0356772766 720 1311867742.6347279549 0.3159315884 0.1736220621 0.3168551624 0.0044874610 0.1655430000 978386769 0 402718720 -0.2550419271 -0.0738411024 0.0355945826 721 1311867742.6724960804 0.3165804744 0.1738203401 0.3168551624 0.0044846606 0.2126230000 978389897 0 402718720 -0.2554009855 -0.0739683583 0.0357593372 722 1311867742.7046229839 0.3167943060 0.1740183650 0.3168551624 0.0044815555 0.2062070000 978392745 0 402718720 -0.2553546727 -0.0741408616 0.0357485004 723 1311867742.7356119156 0.3165385723 0.1742154884 0.3168551624 0.0044784850 0.2058010000 978395649 0 402718720 -0.2547629178 -0.0741221458 0.0355689675 724 1311867742.7726070881 0.3174287379 0.1744132967 0.3174287379 0.0044761285 0.2058810000 978398721 0 402718720 -0.2551323771 -0.0746279433 0.0356052555 725 1311867742.8034689426 0.3178562522 0.1746111491 0.3178562522 0.0044767066 0.1944800000 978401625 0 402718720 -0.2555911839 -0.0746326298 0.0355765000 726 1311867742.8352251053 0.3183760941 0.1748091724 0.3183760941 0.0044760474 0.1643910000 978404473 0 402718720 -0.2554571629 -0.0746484473 0.0354598388 727 1311867742.8705639839 0.3189575076 0.1750074507 0.3189575076 0.0044734093 0.1643720000 978407433 0 402718720 -0.2558200061 -0.0745313689 0.0355006717 728 1311867742.9046700001 0.3185596168 0.1752046378 0.3189575076 0.0044704211 0.1624730000 978410393 0 402718720 -0.2550211251 -0.0745629221 0.0353428014 729 1311867742.9382069111 0.3179415464 0.1754004360 0.3189575076 0.0044886827 0.1645240000 978413409 0 402718720 -0.2544146478 -0.0743604004 0.0352514274 730 1311867742.9707310200 0.3177690208 0.1755954614 0.3189575076 0.0044893612 0.1650600000 978416313 0 402718720 -0.2538851500 -0.0742074624 0.0350541845 731 1311867743.0024189949 0.3181592524 0.1757904872 0.3189575076 0.0044904841 0.1640740000 978419161 0 402718720 -0.2540381849 -0.0741821453 0.0351485200 732 1311867743.0345149040 0.3182560205 0.1759851122 0.3189575076 0.0044911027 0.1645150000 978422065 0 402718720 -0.2537449896 -0.0738462955 0.0351511501 733 1311867743.0722420216 0.3184454739 0.1761794647 0.3189575076 0.0044894653 0.1644030000 978425137 0 402718720 -0.2534344494 -0.0741792247 0.0349867158 734 1311867743.1045989990 0.3182878792 0.1763730729 0.3189575076 0.0044868627 0.1658510000 978428041 0 402718720 -0.2529505491 -0.0741751343 0.0349690653 735 1311867743.1350400448 0.3188797235 0.1765669595 0.3189575076 0.0044854663 0.1661860000 978430889 0 402718720 -0.2529131174 -0.0741869658 0.0348526053 736 1311867743.1704380512 0.3184890151 0.1767597883 0.3189575076 0.0044887067 0.1854890000 978433849 0 402718720 -0.2523837686 -0.0745576322 0.0345176011 737 1311867743.2037980556 0.3184320629 0.1769520167 0.3189575076 0.0044865630 0.1655480000 978436809 0 402718720 -0.2519147694 -0.0743343905 0.0342757739 738 1311867743.2358140945 0.3188377619 0.1771442738 0.3189575076 0.0044844745 0.1645650000 978439657 0 402718720 -0.2518015206 -0.0742805451 0.0343358815 739 1311867743.2708129883 0.3183593154 0.1773353631 0.3189575076 0.0044860509 0.1869910000 978442673 0 402718720 -0.2512218356 -0.0736635625 0.0343814828 740 1311867743.3032529354 0.3185386956 0.1775261785 0.3189575076 0.0044933661 0.1656820000 978445577 0 402718720 -0.2513430417 -0.0735507235 0.0344284289 741 1311867743.3363931179 0.3187231421 0.1777167277 0.3189575076 0.0044906095 0.1651250000 978448481 0 402718720 -0.2514468133 -0.0729909986 0.0345806889 742 1311867743.3707330227 0.3184587955 0.1779064070 0.3189575076 0.0044880088 0.1650770000 978451441 0 402718720 -0.2510472238 -0.0726163834 0.0346834399 743 1311867743.4043838978 0.3189159632 0.1780961911 0.3189575076 0.0044851222 0.1633180000 978454401 0 402718720 -0.2514320314 -0.0726454109 0.0348502658 744 1311867743.4352641106 0.3191377223 0.1782857630 0.3191377223 0.0044897770 0.1881630000 978457305 0 402718720 -0.2516498268 -0.0729279295 0.0347258896 745 1311867743.4768960476 0.3192733228 0.1784750081 0.3192733228 0.0044892911 0.1667450000 978460433 0 402718720 -0.2517062128 -0.0726003721 0.0346823633 746 1311867743.5035250187 0.3197934330 0.1786644429 0.3197934330 0.0044869302 0.1668360000 978463225 0 402718720 -0.2520115376 -0.0724095330 0.0347332284 747 1311867743.5389750004 0.3200346529 0.1788536936 0.3200346529 0.0044878647 0.1670260000 978466185 0 402718720 -0.2524402142 -0.0726242661 0.0345981792 748 1311867743.5749680996 0.3194857240 0.1790417043 0.3200346529 0.0044878919 0.1655490000 978469201 0 402718720 -0.2512894273 -0.0720372498 0.0342109799 749 1311867743.6036109924 0.3199109435 0.1792297807 0.3200346529 0.0044916618 0.1775970000 978471993 0 402718720 -0.2522223890 -0.0719886795 0.0343281031 750 1311867743.6354589462 0.3202112913 0.1794177561 0.3202112913 0.0044915047 0.1675730000 978474897 0 402718720 -0.2527037263 -0.0719079673 0.0340663642 751 1311867743.6759150028 0.3198431134 0.1796047406 0.3202112913 0.0044886110 0.1676740000 978478025 0 402718720 -0.2524201870 -0.0725007877 0.0337506644 752 1311867743.7034959793 0.3205290437 0.1797921399 0.3205290437 0.0044857815 0.1796540000 978480817 0 402718720 -0.2532894611 -0.0724799037 0.0338442624 753 1311867743.7388861179 0.3197322786 0.1799779834 0.3205290437 0.0044837385 0.1663410000 978483833 0 402718720 -0.2527269423 -0.0724818483 0.0332661010 754 1311867743.7733619213 0.3200570047 0.1801637646 0.3205290437 0.0044809376 0.1825790000 978486849 0 402718720 -0.2532626688 -0.0730483010 0.0330595449 755 1311867743.8064749241 0.3205354512 0.1803496873 0.3205354512 0.0044784821 0.1670700000 978489697 0 402718720 -0.2538990676 -0.0732179806 0.0329073779 756 1311867743.8391659260 0.3216817677 0.1805366345 0.3216817677 0.0044763727 0.1673690000 978492601 0 402718720 -0.2553270757 -0.0737036392 0.0327702314 757 1311867743.8726658821 0.3204641044 0.1807214793 0.3216817677 0.0044740738 0.1674340000 978495617 0 402718720 -0.2543405294 -0.0740446746 0.0322702900 758 1311867743.9031310081 0.3207160830 0.1809061687 0.3216817677 0.0044713336 0.1673930000 978498465 0 402718720 -0.2545206845 -0.0740751401 0.0318541415 759 1311867743.9453630447 0.3220285475 0.1810921007 0.3220285475 0.0044688058 0.1775440000 978501649 0 402718720 -0.2559960485 -0.0744402856 0.0317931324 760 1311867743.9741249084 0.3217914701 0.1812772315 0.3220285475 0.0044670896 0.1663990000 978504441 0 402718720 -0.2558930516 -0.0739500970 0.0312685333 761 1311867744.0042529106 0.3214287460 0.1814613990 0.3220285475 0.0044659974 0.1666990000 978507233 0 402718720 -0.2555592954 -0.0728826821 0.0310859047 762 1311867744.0407259464 0.3213033378 0.1816449186 0.3220285475 0.0044643376 0.1652290000 978510305 0 402718720 -0.2554539144 -0.0727828965 0.0309381038 763 1311867744.0716118813 0.3208577335 0.1818273732 0.3220285475 0.0044620716 0.1668750000 978513153 0 402718720 -0.2551256120 -0.0723980963 0.0309244413 764 1311867744.1111290455 0.3207952976 0.1820092684 0.3220285475 0.0044592368 0.1848160000 978516113 0 402718720 -0.2551259398 -0.0722503662 0.0306311660 765 1311867744.1412119865 0.3209737837 0.1821909213 0.3220285475 0.0044569868 0.1679800000 978518961 0 402718720 -0.2553432584 -0.0712590367 0.0304350592 766 1311867744.1734991074 0.3202686310 0.1823711794 0.3220285475 0.0044543281 0.1824410000 978521921 0 402718720 -0.2544362545 -0.0703217611 0.0302394610 767 1311867744.2046771049 0.3214741945 0.1825525393 0.3220285475 0.0044564035 0.1692230000 978524769 0 402718720 -0.2556126714 -0.0708779171 0.0302295983 768 1311867744.2400228977 0.3216679692 0.1827336792 0.3220285475 0.0044545618 0.1693940000 978527841 0 402718720 -0.2558636367 -0.0710701719 0.0301432740 769 1311867744.2773048878 0.3214082420 0.1829140102 0.3220285475 0.0044519906 0.1824310000 978530857 0 402718720 -0.2556012273 -0.0698531196 0.0300465319 770 1311867744.3032519817 0.3208544254 0.1830931536 0.3220285475 0.0044501802 0.1690750000 978533593 0 402718720 -0.2552079260 -0.0702323616 0.0298328474 771 1311867744.3391230106 0.3213289082 0.1832724477 0.3220285475 0.0044498439 0.1683090000 978536609 0 402718720 -0.2555106282 -0.0706953630 0.0299466271 772 1311867744.3707659245 0.3208579421 0.1834506673 0.3220285475 0.0044471995 0.1681240000 978539457 0 402718720 -0.2548699379 -0.0701489374 0.0297584869 773 1311867744.4027431011 0.3218049705 0.1836296508 0.3220285475 0.0044452554 0.1680720000 978542417 0 402718720 -0.2556712925 -0.0700591877 0.0299522299 774 1311867744.4383800030 0.3228201866 0.1838094836 0.3228201866 0.0044428852 0.1699940000 978545377 0 402718720 -0.2566556931 -0.0704722852 0.0297910031 775 1311867744.4717690945 0.3235224485 0.1839897584 0.3235224485 0.0044413094 0.1680790000 978548337 0 402718720 -0.2571717501 -0.0706468597 0.0300677847 776 1311867744.5026860237 0.3225632012 0.1841683324 0.3235224485 0.0044385326 0.1692190000 978551241 0 402718720 -0.2561549842 -0.0698660314 0.0295489151 777 1311867744.5383169651 0.3226427436 0.1843465491 0.3235224485 0.0044383913 0.1692140000 978554257 0 402718720 -0.2561131418 -0.0702458546 0.0292221569 778 1311867744.5726189613 0.3224420846 0.1845240498 0.3235224485 0.0044356269 0.1690770000 978557217 0 402718720 -0.2558503747 -0.0708734691 0.0289867185 779 1311867744.6028740406 0.3231060505 0.1847019471 0.3235224485 0.0044358019 0.1793400000 978560065 0 402718720 -0.2560137212 -0.0706725419 0.0289890021 780 1311867744.6386809349 0.3227035701 0.1848788723 0.3235224485 0.0044360739 0.1702280000 978563081 0 402718720 -0.2559805512 -0.0706241354 0.0287608262 781 1311867744.6707758904 0.3217726648 0.1850541524 0.3235224485 0.0044334015 0.1701830000 978565985 0 402718720 -0.2551422715 -0.0703722164 0.0282629784 782 1311867744.7029349804 0.3234924674 0.1852311835 0.3235224485 0.0044362435 0.1702760000 978568889 0 402718720 -0.2561860383 -0.0702631995 0.0286008865 783 1311867744.7396171093 0.3216461539 0.1854054044 0.3235224485 0.0044395204 0.1804500000 978571905 0 402718720 -0.2548901439 -0.0693653300 0.0283097029 784 1311867744.7705199718 0.3222834468 0.1855799938 0.3235224485 0.0044370503 0.1837900000 978574753 0 402718720 -0.2555397749 -0.0700709745 0.0283776671 785 1311867744.8035891056 0.3227631748 0.1857547494 0.3235224485 0.0044376332 0.1702250000 978577713 0 402718720 -0.2556225955 -0.0706603155 0.0283079650 786 1311867744.8424170017 0.3222382665 0.1859283926 0.3235224485 0.0044353905 0.1708960000 978580785 0 402718720 -0.2548922896 -0.0707652643 0.0283173602 787 1311867744.8727390766 0.3220911026 0.1861014074 0.3235224485 0.0044364287 0.1701790000 978583689 0 402718720 -0.2553782761 -0.0711895898 0.0280086733 788 1311867744.9029939175 0.3223628104 0.1862743280 0.3235224485 0.0044336927 0.1695830000 978586537 0 402718720 -0.2556614578 -0.0719483271 0.0278730392 789 1311867744.9392940998 0.3224152029 0.1864468766 0.3235224485 0.0044352697 0.1797490000 978589609 0 402718720 -0.2550494075 -0.0720698535 0.0276567880 790 1311867744.9708900452 0.3220941424 0.1866185820 0.3235224485 0.0044356335 0.1683840000 978592401 0 402718720 -0.2551736534 -0.0720866323 0.0272041503 791 1311867745.0027489662 0.3221989572 0.1867899858 0.3235224485 0.0044389840 0.1814270000 978595305 0 402718720 -0.2547987700 -0.0720585510 0.0266142040 792 1311867745.0384869576 0.3221878409 0.1869609427 0.3235224485 0.0044388838 0.1693370000 978598321 0 402718720 -0.2550302148 -0.0724205077 0.0267833248 793 1311867745.0729780197 0.3215827942 0.1871307054 0.3235224485 0.0044385561 0.1698660000 978601281 0 402718720 -0.2543015480 -0.0726999491 0.0266098995 794 1311867745.1118760109 0.3214794099 0.1872999103 0.3235224485 0.0044394226 0.1849670000 978604353 0 402718720 -0.2544435263 -0.0722740591 0.0262525249 795 1311867745.1405589581 0.3205288649 0.1874674939 0.3235224485 0.0044379571 0.1702440000 978607145 0 402718720 -0.2533946335 -0.0722297430 0.0259153768 796 1311867745.1729030609 0.3214876056 0.1876358609 0.3235224485 0.0044354021 0.1694610000 978610049 0 402718720 -0.2541990280 -0.0728571862 0.0260422118 797 1311867745.2068369389 0.3223474920 0.1878048843 0.3235224485 0.0044327475 0.1685970000 978613009 0 402718720 -0.2550729811 -0.0730188340 0.0261413213 798 1311867745.2430789471 0.3213080764 0.1879721815 0.3235224485 0.0044307688 0.1686110000 978616025 0 402718720 -0.2537699342 -0.0725178719 0.0261339862 799 1311867745.2729060650 0.3232336342 0.1881414699 0.3235224485 0.0044287362 0.1911010000 978618873 0 402718720 -0.2555350363 -0.0725486204 0.0264627002 800 1311867745.3112850189 0.3222911656 0.1883091571 0.3235224485 0.0044271942 0.1693070000 978621889 0 402718720 -0.2545616925 -0.0725460425 0.0261369981 801 1311867745.3395059109 0.3218605220 0.1884758879 0.3235224485 0.0044244914 0.1690350000 978624737 0 402718720 -0.2540252805 -0.0725004971 0.0258039627 802 1311867745.3733940125 0.3217568696 0.1886420736 0.3235224485 0.0044232525 0.1696090000 978627697 0 402718720 -0.2538375854 -0.0725112930 0.0253996998 803 1311867745.4102098942 0.3213970959 0.1888073974 0.3235224485 0.0044208292 0.1690090000 978630713 0 402718720 -0.2531636059 -0.0728700459 0.0251895729 804 1311867745.4433169365 0.3228052258 0.1889740614 0.3235224485 0.0044189479 0.1803760000 978633673 0 402718720 -0.2545153499 -0.0725276545 0.0252138712 805 1311867745.4708619118 0.3212723434 0.1891384071 0.3235224485 0.0044165057 0.1679540000 978636409 0 402718720 -0.2530337870 -0.0721390024 0.0246774107 806 1311867745.5099780560 0.3223419189 0.1893036720 0.3235224485 0.0044151641 0.1679250000 978639537 0 402718720 -0.2538489699 -0.0722794086 0.0244699866 807 1311867745.5417380333 0.3223650157 0.1894685559 0.3235224485 0.0044138909 0.1675720000 978642441 0 402718720 -0.2536114156 -0.0726037696 0.0243294444 808 1311867745.5704059601 0.3216641843 0.1896321644 0.3235224485 0.0044115471 0.1678460000 978645233 0 402718720 -0.2529525161 -0.0734003112 0.0238901544 809 1311867745.6133821011 0.3214365542 0.1897950870 0.3235224485 0.0044097219 0.1945580000 978648473 0 402718720 -0.2527201474 -0.0734697059 0.0235067122 810 1311867745.6438291073 0.3207654655 0.1899567788 0.3235224485 0.0044105876 0.2041610000 978651377 0 402718720 -0.2520470321 -0.0732981712 0.0229797792 811 1311867745.6709001064 0.3215687871 0.1901190624 0.3235224485 0.0044152338 0.1648960000 978654057 0 402718720 -0.2527465820 -0.0729004592 0.0229402687 812 1311867745.7088780403 0.3222822249 0.1902818250 0.3235224485 0.0044135204 0.1778370000 978657185 0 402718720 -0.2531254590 -0.0726587400 0.0226039570 813 1311867745.7423269749 0.3213564157 0.1904430483 0.3235224485 0.0044131376 0.1805380000 978660089 0 402718720 -0.2523938417 -0.0727669597 0.0224250574 814 1311867745.7760419846 0.3223781586 0.1906051308 0.3235224485 0.0044169089 0.1785150000 978663049 0 402718720 -0.2529110610 -0.0732803196 0.0228007082 815 1311867745.8116889000 0.3218125403 0.1907661214 0.3235224485 0.0044200102 0.1659250000 978666065 0 402718720 -0.2521635592 -0.0730586946 0.0230583046 816 1311867745.8389890194 0.3218374252 0.1909267480 0.3235224485 0.0044192662 0.1679520000 978668857 0 402718720 -0.2522881329 -0.0731879845 0.0232895315 817 1311867745.8709759712 0.3234019578 0.1910888964 0.3235224485 0.0044175668 0.1678060000 978671705 0 402718720 -0.2538384795 -0.0732115954 0.0236756988 818 1311867745.9108459949 0.3230543733 0.1912502234 0.3235224485 0.0044175405 0.1672480000 978674833 0 402718720 -0.2532419860 -0.0726590008 0.0235093143 819 1311867745.9435789585 0.3237086833 0.1914119553 0.3237086833 0.0044180184 0.1855070000 978677793 0 402718720 -0.2538528144 -0.0732287541 0.0232385285 820 1311867745.9732220173 0.3240895867 0.1915737573 0.3240895867 0.0044155368 0.1663590000 978680585 0 402718720 -0.2538219988 -0.0746562257 0.0240649581 821 1311867746.0083909035 0.3241667449 0.1917352591 0.3241667449 0.0044139737 0.1662460000 978683545 0 402718720 -0.2535357475 -0.0750603378 0.0244202223 822 1311867746.0391409397 0.3238289654 0.1918959571 0.3241667449 0.0044120592 0.1661520000 978686505 0 402718720 -0.2528606653 -0.0753266588 0.0247724149 823 1311867746.0728518963 0.3236994445 0.1920561071 0.3241667449 0.0044095911 0.1655270000 978689409 0 402718720 -0.2524267733 -0.0751818120 0.0245199595 824 1311867746.1113359928 0.3244408667 0.1922167682 0.3244408667 0.0044080373 0.1902840000 978692425 0 402718720 -0.2526715994 -0.0755245388 0.0247553345 825 1311867746.1412689686 0.3257470131 0.1923786231 0.3257470131 0.0044058418 0.1652180000 978695329 0 402718720 -0.2535917759 -0.0765217468 0.0252571516 826 1311867746.1721889973 0.3263912499 0.1925408660 0.3263912499 0.0044042508 0.1649040000 978698177 0 402718720 -0.2540117204 -0.0765900388 0.0254608765 827 1311867746.2066209316 0.3260759115 0.1927023352 0.3263912499 0.0044019842 0.1622340000 978701137 0 402718720 -0.2534034848 -0.0762705281 0.0253860895 828 1311867746.2386920452 0.3263334930 0.1928637255 0.3263912499 0.0044001142 0.1639800000 978704097 0 402718720 -0.2539342940 -0.0772564784 0.0253356583 829 1311867746.2704648972 0.3266084492 0.1930250581 0.3266084492 0.0043974942 0.1773690000 978707001 0 402718720 -0.2542199194 -0.0780940801 0.0256872885 830 1311867746.3068819046 0.3247797489 0.1931837987 0.3266084492 0.0043958312 0.1635700000 978709961 0 402718720 -0.2526897192 -0.0775220245 0.0248446390 831 1311867746.3393440247 0.3242817223 0.1933415579 0.3266084492 0.0043967018 0.1644640000 978712921 0 402718720 -0.2518084645 -0.0777314380 0.0248114616 832 1311867746.3797800541 0.3250720799 0.1934998878 0.3266084492 0.0043943528 0.1624930000 978716049 0 402718720 -0.2529080212 -0.0779409111 0.0251901988 833 1311867746.4078478813 0.3251216114 0.1936578971 0.3266084492 0.0043927247 0.1624310000 978718841 0 402718720 -0.2531612515 -0.0774184391 0.0248354562 834 1311867746.4389901161 0.3241845071 0.1938144038 0.3266084492 0.0043904787 0.1731990000 978721689 0 402718720 -0.2524426579 -0.0767316073 0.0245024525 835 1311867746.4774639606 0.3233015537 0.1939694783 0.3266084492 0.0043898284 0.1627480000 978724817 0 402718720 -0.2516685426 -0.0771004483 0.0244768206 836 1311867746.5066781044 0.3236380219 0.1941245842 0.3266084492 0.0043877120 0.1628620000 978727609 0 402718720 -0.2519232929 -0.0768598840 0.0242262688 837 1311867746.5406761169 0.3232470453 0.1942788524 0.3266084492 0.0043868930 0.1605070000 978730569 0 402718720 -0.2517491877 -0.0764836520 0.0242931042 838 1311867746.5748629570 0.3232597411 0.1944327675 0.3266084492 0.0043846235 0.1630670000 978733585 0 402718720 -0.2519137859 -0.0764642879 0.0242118649 839 1311867746.6067559719 0.3228095472 0.1945857792 0.3266084492 0.0043820478 0.1734760000 978736433 0 402718720 -0.2514052391 -0.0765446052 0.0244046357 840 1311867746.6396849155 0.3234118819 0.1947391436 0.3266084492 0.0043828193 0.1627610000 978739449 0 402718720 -0.2520332634 -0.0766317919 0.0245244894 841 1311867746.6749529839 0.3227664232 0.1948913758 0.3266084492 0.0043837144 0.1619940000 978742409 0 402718720 -0.2512549758 -0.0767092034 0.0242318809 842 1311867746.7095060349 0.3231776655 0.1950437348 0.3266084492 0.0043814679 0.1613770000 978745369 0 402718720 -0.2515347302 -0.0772576407 0.0243673772 843 1311867746.7391049862 0.3234874010 0.1951960998 0.3266084492 0.0043800846 0.1735730000 978748161 0 402718720 -0.2517034709 -0.0776046887 0.0247114319 844 1311867746.7751340866 0.3232269883 0.1953477951 0.3266084492 0.0043775043 0.1725940000 978751233 0 402718720 -0.2514711320 -0.0776351914 0.0244128294 845 1311867746.8070099354 0.3232139945 0.1954991161 0.3266084492 0.0043750209 0.1606720000 978754137 0 402718720 -0.2513231039 -0.0778122693 0.0244032238 846 1311867746.8401610851 0.3225718737 0.1956493203 0.3266084492 0.0043727587 0.1600160000 978757041 0 402718720 -0.2505060434 -0.0786685795 0.0245409794 847 1311867746.8748359680 0.3226703107 0.1957992860 0.3266084492 0.0043714731 0.1705110000 978760057 0 402718720 -0.2505095899 -0.0788103864 0.0240458585 848 1311867746.9086029530 0.3224927485 0.1959486887 0.3266084492 0.0043691462 0.1593610000 978762961 0 402718720 -0.2500490844 -0.0783409625 0.0240530167 849 1311867746.9389610291 0.3227745891 0.1960980714 0.3266084492 0.0043670525 0.1605240000 978765865 0 402718720 -0.2500875294 -0.0790567026 0.0242237002 850 1311867746.9748229980 0.3229015172 0.1962472519 0.3266084492 0.0043699027 0.1604350000 978768881 0 402718720 -0.2494270951 -0.0790497363 0.0242235567 851 1311867747.0066559315 0.3220496476 0.1963950808 0.3266084492 0.0043735516 0.1602310000 978771729 0 402718720 -0.2492540926 -0.0787686333 0.0237942468 852 1311867747.0389339924 0.3223358095 0.1965428986 0.3266084492 0.0043714884 0.1603340000 978774633 0 402718720 -0.2494284809 -0.0790213048 0.0241004936 853 1311867747.0749640465 0.3221344352 0.1966901336 0.3266084492 0.0043714561 0.1572500000 978777705 0 402718720 -0.2485375255 -0.0794290900 0.0243075360 854 1311867747.1066820621 0.3214158118 0.1968361825 0.3266084492 0.0043755730 0.1585240000 978780553 0 402718720 -0.2481676638 -0.0792587548 0.0248030908 855 1311867747.1389479637 0.3210375011 0.1969814472 0.3266084492 0.0043730362 0.1591090000 978783457 0 402718720 -0.2475702763 -0.0787925124 0.0248287823 856 1311867747.1744880676 0.3213151097 0.1971266968 0.3266084492 0.0043710963 0.1593980000 978786473 0 402718720 -0.2476747036 -0.0790556520 0.0248255450 857 1311867747.2066030502 0.3220870495 0.1972725081 0.3266084492 0.0043686128 0.1598640000 978789377 0 402718720 -0.2482087612 -0.0794773176 0.0254571941 858 1311867747.2385439873 0.3225046694 0.1974184664 0.3266084492 0.0043684712 0.1592270000 978792337 0 402718720 -0.2482178360 -0.0797971115 0.0253324248 859 1311867747.2745490074 0.3209352195 0.1975622577 0.3266084492 0.0043914574 0.1683380000 978795353 0 402718720 -0.2464940101 -0.0799064785 0.0247590020 860 1311867747.3064720631 0.3220090866 0.1977069633 0.3266084492 0.0043996431 0.1591480000 978798145 0 402718720 -0.2474964410 -0.0802844167 0.0252249949 861 1311867747.3388469219 0.3220427334 0.1978513719 0.3266084492 0.0044075304 0.1583510000 978801161 0 402718720 -0.2474020272 -0.0810888559 0.0256565362 862 1311867747.3758800030 0.3224914670 0.1979959660 0.3266084492 0.0044087738 0.1584790000 978804121 0 402718720 -0.2474401295 -0.0810863152 0.0259375218 863 1311867747.4068729877 0.3217024207 0.1981393106 0.3266084492 0.0044070107 0.1563960000 978807025 0 402718720 -0.2466943860 -0.0808587223 0.0258430503 864 1311867747.4396450520 0.3219071031 0.1982825604 0.3266084492 0.0044107812 0.1586910000 978809873 0 402718720 -0.2466698736 -0.0810675994 0.0261693615 865 1311867747.4756069183 0.3225031793 0.1984261680 0.3266084492 0.0044108134 0.1579200000 978812889 0 402718720 -0.2473138422 -0.0812305063 0.0262723546 866 1311867747.5095520020 0.3218856156 0.1985687309 0.3266084492 0.0044094050 0.1570310000 978815905 0 402718720 -0.2467003316 -0.0806400329 0.0261968765 867 1311867747.5405330658 0.3221845925 0.1987113098 0.3266084492 0.0044103244 0.1571220000 978818753 0 402718720 -0.2468413860 -0.0808822215 0.0260186829 868 1311867747.5766739845 0.3214659095 0.1988527321 0.3266084492 0.0044081575 0.1577280000 978821769 0 402718720 -0.2459161729 -0.0814853087 0.0260895863 869 1311867747.6086390018 0.3230504990 0.1989956524 0.3266084492 0.0044064230 0.1636780000 978824673 0 402718720 -0.2471870929 -0.0821254924 0.0271731447 870 1311867747.6432039738 0.3224431872 0.1991375462 0.3266084492 0.0044041015 0.1562130000 978827689 0 402718720 -0.2465567142 -0.0818515718 0.0271711759 871 1311867747.6760280132 0.3221860230 0.1992788188 0.3266084492 0.0044084949 0.1674210000 978830593 0 402718720 -0.2464261353 -0.0818162039 0.0270582698 872 1311867747.7068400383 0.3242169023 0.1994220964 0.3266084492 0.0044073127 0.1559740000 978833441 0 402718720 -0.2484477460 -0.0822853073 0.0278667808 873 1311867747.7480750084 0.3240413070 0.1995648447 0.3266084492 0.0044125652 0.1544370000 978836737 0 402718720 -0.2487633526 -0.0820923150 0.0274640918 874 1311867747.7826869488 0.3228435516 0.1997058958 0.3266084492 0.0044108293 0.1705420000 978839697 0 402718720 -0.2478325814 -0.0818362758 0.0269471314 875 1311867747.8149020672 0.3227851391 0.1998465578 0.3266084492 0.0044091303 0.1567410000 978842601 0 402718720 -0.2482932657 -0.0820141435 0.0266024973 876 1311867747.8466539383 0.3234429955 0.1999876496 0.3266084492 0.0044070894 0.1561750000 978845449 0 402718720 -0.2487953305 -0.0821439177 0.0271724332 877 1311867747.8827810287 0.3234587908 0.2001284377 0.3266084492 0.0044079647 0.1564720000 978848521 0 402718720 -0.2489218116 -0.0818947479 0.0274231378 878 1311867747.9150440693 0.3241074085 0.2002696438 0.3266084492 0.0044061716 0.1674730000 978851481 0 402718720 -0.2503347397 -0.0812629387 0.0268503632 879 1311867747.9477820396 0.3239621520 0.2004103634 0.3266084492 0.0044037739 0.1568190000 978854385 0 402718720 -0.2505292296 -0.0809640288 0.0268498752 880 1311867747.9826579094 0.3232875466 0.2005499966 0.3266084492 0.0044014023 0.1569770000 978857345 0 402718720 -0.2503121793 -0.0809320956 0.0264699068 881 1311867748.0146598816 0.3234297931 0.2006894742 0.3266084492 0.0043992606 0.1575050000 978860249 0 402718720 -0.2510247231 -0.0806322470 0.0264366549 882 1311867748.0469269753 0.3230482340 0.2008282029 0.3266084492 0.0043973566 0.1574980000 978863153 0 402718720 -0.2512300909 -0.0796443224 0.0265824273 883 1311867748.0828750134 0.3229919970 0.2009665538 0.3266084492 0.0043948925 0.1578170000 978866225 0 402718720 -0.2517636716 -0.0794597790 0.0264013130 884 1311867748.1150569916 0.3224254549 0.2011039507 0.3266084492 0.0043932588 0.1674780000 978869073 0 402718720 -0.2515032589 -0.0790158808 0.0267519616 885 1311867748.1486010551 0.3243943453 0.2012432619 0.3266084492 0.0043923510 0.1583650000 978872033 0 402718720 -0.2538670599 -0.0788145214 0.0267194379 886 1311867748.1831040382 0.3221640587 0.2013797414 0.3266084492 0.0043912415 0.1596900000 978874937 0 402718720 -0.2521675229 -0.0779324472 0.0256837569 887 1311867748.2148320675 0.3234747648 0.2015173908 0.3266084492 0.0043896859 0.1593550000 978877897 0 402718720 -0.2536367178 -0.0778232068 0.0262527857 888 1311867748.2466599941 0.3227799833 0.2016539478 0.3266084492 0.0043902374 0.1592830000 978880745 0 402718720 -0.2530116737 -0.0778232887 0.0261830371 889 1311867748.2827599049 0.3225565255 0.2017899462 0.3266084492 0.0043885244 0.1822220000 978883761 0 402718720 -0.2530555427 -0.0774289370 0.0258913729 890 1311867748.3148829937 0.3221531808 0.2019251857 0.3266084492 0.0043947359 0.1598790000 978886665 0 402718720 -0.2526818514 -0.0773831233 0.0262417048 891 1311867748.3470869064 0.3229107261 0.2020609720 0.3266084492 0.0043982468 0.1594490000 978889569 0 402718720 -0.2536590695 -0.0781567097 0.0258576833 892 1311867748.3826999664 0.3232910931 0.2021968802 0.3266084492 0.0044006453 0.1601150000 978892585 0 402718720 -0.2539109290 -0.0780918524 0.0265037436 893 1311867748.4148259163 0.3234683871 0.2023326826 0.3266084492 0.0043994355 0.1596160000 978895433 0 402718720 -0.2542577982 -0.0776892975 0.0262442622 894 1311867748.4520189762 0.3235023320 0.2024682191 0.3266084492 0.0044118756 0.1684550000 978898505 0 402718720 -0.2548589408 -0.0779032409 0.0260490719 895 1311867748.4831318855 0.3233835995 0.2026033201 0.3266084492 0.0044094255 0.1607060000 978901409 0 402718720 -0.2548720539 -0.0776343569 0.0258511286 896 1311867748.5149960518 0.3230300844 0.2027377249 0.3266084492 0.0044082270 0.1604570000 978904313 0 402718720 -0.2544896305 -0.0772756562 0.0257067513 897 1311867748.5467929840 0.3234989345 0.2028723528 0.3266084492 0.0044064043 0.1610650000 978907161 0 402718720 -0.2552691698 -0.0775194541 0.0259713773 898 1311867748.5827159882 0.3241118491 0.2030073634 0.3266084492 0.0044041931 0.1610510000 978910177 0 402718720 -0.2560399771 -0.0775213316 0.0261157956 899 1311867748.6147999763 0.3237001002 0.2031416156 0.3266084492 0.0044032009 0.1714350000 978913137 0 402718720 -0.2558911443 -0.0768502280 0.0263174605 900 1311867748.6470849514 0.3238768876 0.2032757659 0.3266084492 0.0044141827 0.1744270000 978915985 0 402718720 -0.2560662329 -0.0768263042 0.0270625018 901 1311867748.6827559471 0.3236371279 0.2034093523 0.3266084492 0.0044121537 0.1618630000 978919001 0 402718720 -0.2558361888 -0.0772731453 0.0273215901 902 1311867748.7147359848 0.3233468533 0.2035423207 0.3266084492 0.0044319416 0.1623400000 978921905 0 402718720 -0.2555938363 -0.0779307410 0.0276991203 903 1311867748.7499361038 0.3234020472 0.2036750557 0.3266084492 0.0044297016 0.1622860000 978924865 0 402718720 -0.2558799088 -0.0783392116 0.0278399177 904 1311867748.7828259468 0.3239644170 0.2038081192 0.3266084492 0.0044286786 0.1744070000 978927881 0 402718720 -0.2565640211 -0.0785330012 0.0283182170 905 1311867748.8151619434 0.3230305016 0.2039398566 0.3266084492 0.0044262648 0.1625260000 978930785 0 402718720 -0.2559303939 -0.0786690563 0.0281922817 906 1311867748.8466329575 0.3241498470 0.2040725387 0.3266084492 0.0044244025 0.1623030000 978933577 0 402718720 -0.2573714256 -0.0788751021 0.0286779124 907 1311867748.8829579353 0.3237504661 0.2042044879 0.3266084492 0.0044240655 0.1634890000 978936593 0 402718720 -0.2573379874 -0.0789010674 0.0288209356 908 1311867748.9149119854 0.3233674467 0.2043357247 0.3266084492 0.0044224601 0.1630650000 978939553 0 402718720 -0.2578140795 -0.0781013519 0.0283760652 909 1311867748.9472498894 0.3239033520 0.2044672622 0.3266084492 0.0044200957 0.1762340000 978942457 0 402718720 -0.2590892613 -0.0775765404 0.0278947297 910 1311867748.9829359055 0.3225197792 0.2045969903 0.3266084492 0.0044186799 0.1641340000 978945473 0 402718720 -0.2587808073 -0.0762350857 0.0263885986 911 1311867749.0159859657 0.3210552931 0.2047248259 0.3266084492 0.0044164094 0.1640090000 978948377 0 402718720 -0.2578520775 -0.0754874274 0.0255498011 912 1311867749.0467190742 0.3204163313 0.2048516807 0.3266084492 0.0044142828 0.1645770000 978951225 0 402718720 -0.2577763796 -0.0748751983 0.0249445513 913 1311867749.0828969479 0.3201455772 0.2049779609 0.3266084492 0.0044121271 0.1645990000 978954241 0 402718720 -0.2578679919 -0.0747176334 0.0250671115 914 1311867749.1158421040 0.3187088668 0.2051023930 0.3266084492 0.0044104296 0.1728730000 978957201 0 402718720 -0.2566148341 -0.0742835030 0.0247787852 915 1311867749.1485249996 0.3183012903 0.2052261077 0.3266084492 0.0044081609 0.1652660000 978960161 0 402718720 -0.2564148307 -0.0740498230 0.0247676112 916 1311867749.1829619408 0.3184162676 0.2053496777 0.3266084492 0.0044063609 0.1661180000 978963121 0 402718720 -0.2571746111 -0.0739267841 0.0245484672 917 1311867749.2156000137 0.3179577589 0.2054724782 0.3266084492 0.0044041388 0.1868050000 978965969 0 402718720 -0.2569700181 -0.0734767839 0.0241477340 918 1311867749.2468719482 0.3177104890 0.2055947418 0.3266084492 0.0044052624 0.1656540000 978968817 0 402718720 -0.2567007244 -0.0740649626 0.0237551089 919 1311867749.2828478813 0.3181028068 0.2057171663 0.3266084492 0.0044065230 0.1860380000 978971833 0 402718720 -0.2573425770 -0.0740228221 0.0241488554 920 1311867749.3148140907 0.3186321855 0.2058399000 0.3266084492 0.0044075160 0.1658270000 978974793 0 402718720 -0.2580602765 -0.0735222697 0.0238934923 921 1311867749.3468968868 0.3186172545 0.2059623510 0.3266084492 0.0044058699 0.1664520000 978977641 0 402718720 -0.2585291862 -0.0731722862 0.0238914099 922 1311867749.3828470707 0.3189133704 0.2060848575 0.3266084492 0.0044037378 0.1666630000 978980657 0 402718720 -0.2592228055 -0.0731276944 0.0237210002 923 1311867749.4147930145 0.3178723454 0.2062059707 0.3266084492 0.0044017674 0.1645870000 978983617 0 402718720 -0.2585558593 -0.0724928677 0.0234674010 924 1311867749.4467489719 0.3189725280 0.2063280125 0.3266084492 0.0043999011 0.1802800000 978986465 0 402718720 -0.2599721849 -0.0719319209 0.0236634817 925 1311867749.4829080105 0.3169876933 0.2064476445 0.3266084492 0.0043991022 0.1677640000 978989481 0 402718720 -0.2589112818 -0.0715897828 0.0231132042 926 1311867749.5159850121 0.3171995282 0.2065672470 0.3266084492 0.0043967823 0.1682790000 978992385 0 402718720 -0.2595872581 -0.0721855462 0.0234797746 927 1311867749.5468530655 0.3173988461 0.2066868064 0.3266084492 0.0043952935 0.1681010000 978995289 0 402718720 -0.2603380978 -0.0724075809 0.0237067547 928 1311867749.5830268860 0.3167617023 0.2068054216 0.3266084492 0.0043930501 0.1675640000 978998305 0 402718720 -0.2603571713 -0.0727728531 0.0237941872 929 1311867749.6148250103 0.3158002496 0.2069227465 0.3266084492 0.0043910484 0.1677320000 979001153 0 402718720 -0.2601816952 -0.0730211660 0.0233731419 930 1311867749.6469049454 0.3158417344 0.2070398637 0.3266084492 0.0043900831 0.1676730000 979004113 0 402718720 -0.2604754865 -0.0733805820 0.0235624127 931 1311867749.6829149723 0.3157768250 0.2071566596 0.3266084492 0.0043884003 0.1801520000 979007129 0 402718720 -0.2613769174 -0.0738991946 0.0234070290 932 1311867749.7160799503 0.3157036602 0.2072731263 0.3266084492 0.0043865546 0.1676960000 979010033 0 402718720 -0.2617790103 -0.0741569698 0.0228506066 933 1311867749.7468609810 0.3155639172 0.2073891936 0.3266084492 0.0043876821 0.1675050000 979012937 0 402718720 -0.2617682517 -0.0747233257 0.0227535889 934 1311867749.7828791142 0.3143672943 0.2075037312 0.3266084492 0.0043862303 0.1763840000 979015953 0 402718720 -0.2612248659 -0.0750865489 0.0224667303 935 1311867749.8148949146 0.3140461147 0.2076176803 0.3266084492 0.0043856296 0.1670230000 979018801 0 402718720 -0.2614168525 -0.0749364048 0.0225895196 936 1311867749.8469030857 0.3132553399 0.2077305410 0.3266084492 0.0043833315 0.1678820000 979021761 0 402718720 -0.2609831393 -0.0746425837 0.0223175958 937 1311867749.8829030991 0.3145735860 0.2078445678 0.3266084492 0.0044035709 0.1670720000 979024777 0 402718720 -0.2624441087 -0.0748775974 0.0224106591 938 1311867749.9149639606 0.3133837581 0.2079570829 0.3266084492 0.0044148702 0.1649240000 979027625 0 402718720 -0.2620604038 -0.0744709596 0.0221904255 939 1311867749.9508709908 0.3121695220 0.2080680653 0.3266084492 0.0044130058 0.1674210000 979030641 0 402718720 -0.2613340318 -0.0742491037 0.0217843503 940 1311867749.9827940464 0.3117429614 0.2081783577 0.3266084492 0.0044132245 0.1677810000 979033601 0 402718720 -0.2613324821 -0.0743133947 0.0215861592 941 1311867750.0147750378 0.3107761741 0.2082873883 0.3266084492 0.0044111261 0.1675140000 979036505 0 402718720 -0.2608219683 -0.0745308474 0.0211751554 942 1311867750.0470709801 0.3100821674 0.2083954507 0.3266084492 0.0044090362 0.1672490000 979039409 0 402718720 -0.2604936659 -0.0747485682 0.0207632277 943 1311867750.0829339027 0.3104386628 0.2085036620 0.3266084492 0.0044080855 0.1676170000 979042425 0 402718720 -0.2610589266 -0.0749209672 0.0209927447 944 1311867750.1156458855 0.3099584281 0.2086111352 0.3266084492 0.0044063611 0.1845460000 979045329 0 402718720 -0.2609403431 -0.0749156028 0.0207725558 945 1311867750.1474790573 0.3107105792 0.2087191770 0.3266084492 0.0044055555 0.1673560000 979048233 0 402718720 -0.2619766295 -0.0745601803 0.0209943894 946 1311867750.1828711033 0.3101306260 0.2088263772 0.3266084492 0.0044041075 0.1673640000 979051249 0 402718720 -0.2616412342 -0.0746445805 0.0207562447 947 1311867750.2156589031 0.3094336689 0.2089326152 0.3266084492 0.0044020729 0.1877640000 979054153 0 402718720 -0.2613085508 -0.0742149353 0.0205514748 948 1311867750.2469079494 0.3103755713 0.2090396225 0.3266084492 0.0044008119 0.1682110000 979057001 0 402718720 -0.2624553442 -0.0739905909 0.0210395399 949 1311867750.2829968929 0.3105031848 0.2091465388 0.3266084492 0.0044001133 0.1692700000 979060017 0 402718720 -0.2629539073 -0.0734404400 0.0213269554 950 1311867750.3150129318 0.3103865385 0.2092531072 0.3266084492 0.0043978015 0.1697830000 979062977 0 402718720 -0.2631121576 -0.0731719360 0.0214844141 951 1311867750.3469090462 0.3088563383 0.2093578425 0.3266084492 0.0043974879 0.1800140000 979065825 0 402718720 -0.2617880404 -0.0735012814 0.0210778937 952 1311867750.3828659058 0.3091328442 0.2094626481 0.3266084492 0.0043952095 0.1687230000 979068841 0 402718720 -0.2621184587 -0.0729386955 0.0212554261 953 1311867750.4148640633 0.3085310161 0.2095666024 0.3266084492 0.0043931910 0.1690210000 979071801 0 402718720 -0.2617580593 -0.0728761926 0.0213319492 954 1311867750.4469859600 0.3080039322 0.2096697861 0.3266084492 0.0043909758 0.1684390000 979074649 0 402718720 -0.2616232932 -0.0731407851 0.0210972540 955 1311867750.4829618931 0.3078352213 0.2097725772 0.3266084492 0.0043892164 0.1692030000 979077609 0 402718720 -0.2615818679 -0.0735304952 0.0206674989 956 1311867750.5148859024 0.3076117933 0.2098749194 0.3266084492 0.0043871461 0.1688870000 979080457 0 402718720 -0.2616524994 -0.0733912364 0.0201945212 957 1311867750.5476069450 0.3067151010 0.2099761109 0.3266084492 0.0043852944 0.1681610000 979083417 0 402718720 -0.2609162331 -0.0737516731 0.0198480580 958 1311867750.5827779770 0.3061924875 0.2100765455 0.3266084492 0.0043852273 0.1686090000 979086433 0 402718720 -0.2606684864 -0.0733456686 0.0197163243 959 1311867750.6148829460 0.3064113557 0.2101769989 0.3266084492 0.0043841665 0.1688940000 979089281 0 402718720 -0.2611441314 -0.0731459334 0.0196126327 960 1311867750.6469810009 0.3057769537 0.2102765822 0.3266084492 0.0043819361 0.1687770000 979092241 0 402718720 -0.2609378994 -0.0731819123 0.0195574313 961 1311867750.6829319000 0.3054726422 0.2103756415 0.3266084492 0.0043818747 0.1689620000 979095257 0 402718720 -0.2610865533 -0.0725417584 0.0195667427 962 1311867750.7149219513 0.3038299680 0.2104727874 0.3266084492 0.0043812144 0.1679630000 979098217 0 402718720 -0.2596813738 -0.0720857531 0.0193863865 963 1311867750.7469151020 0.3036894798 0.2105695856 0.3266084492 0.0043794732 0.1692000000 979101065 0 402718720 -0.2596974969 -0.0723296255 0.0196882039 964 1311867750.7832129002 0.3029363751 0.2106654018 0.3266084492 0.0043796497 0.1818250000 979104025 0 402718720 -0.2592586279 -0.0722363517 0.0198502503 965 1311867750.8149549961 0.3020314872 0.2107600817 0.3266084492 0.0043774784 0.1696740000 979106817 0 402718720 -0.2584379315 -0.0716564059 0.0203630943 966 1311867750.8468461037 0.3019772470 0.2108545094 0.3266084492 0.0043778375 0.1698550000 979109721 0 402718720 -0.2585268617 -0.0717331395 0.0204765387 967 1311867750.8828840256 0.3017687201 0.2109485262 0.3266084492 0.0043756680 0.1680270000 979112793 0 402718720 -0.2585478425 -0.0713789687 0.0204089899 968 1311867750.9147970676 0.3003308177 0.2110408632 0.3266084492 0.0043745677 0.1807010000 979115641 0 402718720 -0.2571986616 -0.0711160451 0.0203830227 969 1311867750.9468770027 0.3004152477 0.2111330969 0.3266084492 0.0043738335 0.1820770000 979118545 0 402718720 -0.2574054301 -0.0708685294 0.0203994121 970 1311867750.9830369949 0.2996111810 0.2112243114 0.3266084492 0.0043721411 0.1708150000 979121617 0 402718720 -0.2567879260 -0.0709198639 0.0202756263 971 1311867751.0168409348 0.2993418276 0.2113150606 0.3266084492 0.0043710758 0.1686010000 979124577 0 402718720 -0.2568543553 -0.0710916817 0.0199243166 972 1311867751.0470340252 0.2986993194 0.2114049621 0.3266084492 0.0043703186 0.1690890000 979127425 0 402718720 -0.2566649914 -0.0708791763 0.0196690541 973 1311867751.0828599930 0.2975567281 0.2114935045 0.3266084492 0.0043680845 0.1691700000 979130385 0 402718720 -0.2558244765 -0.0708468407 0.0191212334 974 1311867751.1174809933 0.2970234156 0.2115813176 0.3266084492 0.0043659035 0.1759740000 979133401 0 402718720 -0.2556334734 -0.0711461678 0.0188180134 975 1311867751.1468789577 0.2969015241 0.2116688255 0.3266084492 0.0043661393 0.1688270000 979136193 0 402718720 -0.2556397021 -0.0709366798 0.0183794275 976 1311867751.1835930347 0.2957011163 0.2117549242 0.3266084492 0.0043654007 0.1690170000 979139265 0 402718720 -0.2549562752 -0.0707610250 0.0181679167 977 1311867751.2161049843 0.2960253060 0.2118411784 0.3266084492 0.0043634331 0.1818200000 979142169 0 402718720 -0.2555860281 -0.0706152767 0.0179619230 978 1311867751.2468481064 0.2969471216 0.2119281988 0.3266084492 0.0043630144 0.1686270000 979145017 0 402718720 -0.2564660907 -0.0708036125 0.0177896358 979 1311867751.2831909657 0.2965161502 0.2120146012 0.3266084492 0.0043641133 0.1687930000 979148089 0 402718720 -0.2563243508 -0.0699267685 0.0176772606 980 1311867751.3149859905 0.2958332896 0.2121001305 0.3266084492 0.0043619501 0.1693340000 979150937 0 402718720 -0.2557772696 -0.0696996078 0.0176756773 981 1311867751.3498640060 0.2965498567 0.2121862158 0.3266084492 0.0043599762 0.1820190000 979153953 0 402718720 -0.2568062246 -0.0702599660 0.0174980480 982 1311867751.3834669590 0.2965601981 0.2122721364 0.3266084492 0.0043580958 0.1686820000 979156913 0 402718720 -0.2571766675 -0.0700501502 0.0169701800 983 1311867751.4151160717 0.2956216037 0.2123569273 0.3266084492 0.0043582114 0.1685950000 979159817 0 402718720 -0.2560074031 -0.0700680688 0.0164546333 984 1311867751.4513890743 0.2951526642 0.2124410693 0.3266084492 0.0043583447 0.1810750000 979162777 0 402718720 -0.2559212744 -0.0706448033 0.0161727201 985 1311867751.4838130474 0.2946759760 0.2125245565 0.3266084492 0.0043562956 0.1695360000 979165737 0 402718720 -0.2553294897 -0.0706536099 0.0155097218 986 1311867751.5149779320 0.2940583825 0.2126072480 0.3266084492 0.0043556140 0.1681340000 979168641 0 402718720 -0.2551564872 -0.0702967942 0.0154687455 987 1311867751.5495769978 0.2933769524 0.2126890815 0.3266084492 0.0043537763 0.1692380000 979171601 0 402718720 -0.2546648085 -0.0704925731 0.0154384524 988 1311867751.5829720497 0.2913669944 0.2127687151 0.3266084492 0.0043520937 0.1694060000 979174505 0 402718720 -0.2523580492 -0.0704920143 0.0152608790 989 1311867751.6149520874 0.2904239893 0.2128472340 0.3266084492 0.0043504258 0.1806680000 979177409 0 402718720 -0.2515333593 -0.0705496594 0.0150430864 990 1311867751.6501350403 0.2889408171 0.2129240962 0.3266084492 0.0043489650 0.1706070000 979180369 0 402718720 -0.2505319715 -0.0708232969 0.0147030707 991 1311867751.6839730740 0.2888251841 0.2130006866 0.3266084492 0.0043468242 0.1703060000 979183385 0 402718720 -0.2505205870 -0.0710433871 0.0145482505 992 1311867751.7150709629 0.2879178226 0.2130762080 0.3266084492 0.0043460239 0.1700260000 979186177 0 402718720 -0.2497314215 -0.0712206066 0.0141882310 993 1311867751.7507519722 0.2870266438 0.2131506797 0.3266084492 0.0043440222 0.1703300000 979189193 0 402718720 -0.2490970492 -0.0716640651 0.0140669039 994 1311867751.7830109596 0.2871593833 0.2132251351 0.3266084492 0.0043427058 0.1799640000 979192097 0 402718720 -0.2495005727 -0.0716799796 0.0138652558 995 1311867751.8149600029 0.2861630321 0.2132984395 0.3266084492 0.0043417714 0.1703870000 979195001 0 402718720 -0.2486696541 -0.0716515407 0.0137578351 996 1311867751.8509531021 0.2851052284 0.2133705347 0.3266084492 0.0043410971 0.1709270000 979198017 0 402718720 -0.2477774620 -0.0717819408 0.0134957340 997 1311867751.8832330704 0.2852193415 0.2134425997 0.3266084492 0.0043396287 0.1705220000 979200921 0 402718720 -0.2482624650 -0.0720001385 0.0134956362 998 1311867751.9149179459 0.2847849131 0.2135140850 0.3266084492 0.0043402182 0.1705170000 979203769 0 402718720 -0.2483124435 -0.0715081543 0.0134522766 999 1311867751.9530611038 0.2835684419 0.2135842095 0.3266084492 0.0043382965 0.1806490000 979206897 0 402718720 -0.2473015636 -0.0716496557 0.0132319434 1000 1311867751.9829521179 0.2844341099 0.2136550594 0.3266084492 0.0043373474 0.1714570000 979209745 0 402718720 -0.2484317422 -0.0719342232 0.0134341717 1001 1311867752.0153670311 0.2841966748 0.2137255305 0.3266084492 0.0043377135 0.1724280000 979212593 0 402718720 -0.2486132681 -0.0714682713 0.0133855790 1002 1311867752.0510330200 0.2827748060 0.2137944420 0.3266084492 0.0043364183 0.1729630000 979215609 0 402718720 -0.2471832782 -0.0712564066 0.0132311070 1003 1311867752.0828928947 0.2811948657 0.2138616408 0.3266084492 0.0043350610 0.1734510000 979218569 0 402718720 -0.2458674461 -0.0717884228 0.0130016711 1004 1311867752.1150529385 0.2795139253 0.2139270315 0.3266084492 0.0043330712 0.1874350000 979221417 0 402718720 -0.2441234738 -0.0722531602 0.0125200283 1005 1311867752.1509859562 0.2781073153 0.2139908925 0.3266084492 0.0043322958 0.1746210000 979224433 0 402718720 -0.2434313893 -0.0721824914 0.0121443309 1006 1311867752.1829679012 0.2785086036 0.2140550254 0.3266084492 0.0043324798 0.1757040000 979227393 0 402718720 -0.2442357540 -0.0723604336 0.0120222559 1007 1311867752.2150039673 0.2788803279 0.2141194001 0.3266084492 0.0043307239 0.1753450000 979230297 0 402718720 -0.2450845391 -0.0723557398 0.0118273702 1008 1311867752.2512340546 0.2786077559 0.2141833766 0.3266084492 0.0043301224 0.1758140000 979233257 0 402718720 -0.2448434234 -0.0722804219 0.0117384465 1009 1311867752.2833271027 0.2789560258 0.2142475715 0.3266084492 0.0043288174 0.1882870000 979236161 0 402718720 -0.2453460097 -0.0721900314 0.0118600363 1010 1311867752.3150799274 0.2772808373 0.2143099807 0.3266084492 0.0043299252 0.1770270000 979239009 0 402718720 -0.2440600246 -0.0723695606 0.0115358634 1011 1311867752.3509979248 0.2779658139 0.2143729440 0.3266084492 0.0043299645 0.1771640000 979242025 0 402718720 -0.2445112020 -0.0724523887 0.0117529044 1012 1311867752.3829851151 0.2779299021 0.2144357473 0.3266084492 0.0043278322 0.1763750000 979244985 0 402718720 -0.2445344776 -0.0727921352 0.0116649838 1013 1311867752.4160280228 0.2764911950 0.2144970064 0.3266084492 0.0043263189 0.1766680000 979247889 0 402718720 -0.2430796325 -0.0732669756 0.0112850294 1014 1311867752.4510710239 0.2761992514 0.2145578567 0.3266084492 0.0043322018 0.1838910000 979250905 0 402718720 -0.2431199849 -0.0734271556 0.0111531820 1015 1311867752.4829080105 0.2758968472 0.2146182892 0.3266084492 0.0043318314 0.1762130000 979253809 0 402718720 -0.2426154166 -0.0738551915 0.0108994981 1016 1311867752.5181159973 0.2754268646 0.2146781402 0.3266084492 0.0043322578 0.1767660000 979256769 0 402718720 -0.2423983961 -0.0742451176 0.0105430167 1017 1311867752.5511059761 0.2748699784 0.2147373258 0.3266084492 0.0043317605 0.1763690000 979259673 0 402718720 -0.2416093647 -0.0742803216 0.0102890348 1018 1311867752.5830090046 0.2749659419 0.2147964895 0.3266084492 0.0043298945 0.1764690000 979262633 0 402718720 -0.2420147955 -0.0740488917 0.0100995349 1019 1311867752.6167891026 0.2739671767 0.2148545569 0.3266084492 0.0043282331 0.1871810000 979265537 0 402718720 -0.2408477962 -0.0742943212 0.0095361508 1020 1311867752.6514921188 0.2740148008 0.2149125572 0.3266084492 0.0043284043 0.1762110000 979268497 0 402718720 -0.2407444865 -0.0744815543 0.0094571393 1021 1311867752.6830079556 0.2742331028 0.2149706576 0.3266084492 0.0043303674 0.1766340000 979271401 0 402718720 -0.2409552485 -0.0746329576 0.0091912802 1022 1311867752.7152869701 0.2726056278 0.2150270519 0.3266084492 0.0043331267 0.1740760000 979274361 0 402718720 -0.2391839623 -0.0749751553 0.0085134506 1023 1311867752.7510609627 0.2727558613 0.2150834828 0.3266084492 0.0043311498 0.1758580000 979277265 0 402718720 -0.2393646985 -0.0754957944 0.0082254596 1024 1311867752.7830440998 0.2721235752 0.2151391860 0.3266084492 0.0043374131 0.1858810000 979280225 0 402718720 -0.2387748659 -0.0756061301 0.0075797248 1025 1311867752.8162839413 0.2710549533 0.2151937380 0.3266084492 0.0043353426 0.1751900000 979283129 0 402718720 -0.2376271635 -0.0755184218 0.0070424052 1026 1311867752.8511059284 0.2708166838 0.2152479514 0.3266084492 0.0043332666 0.1749580000 979490889 0 402718720 -0.2372629791 -0.0751855820 0.0066549461 1027 1311867752.8833000660 0.2707051039 0.2153019505 0.3266084492 0.0043316015 0.1739350000 979493849 0 402718720 -0.2372503132 -0.0747306496 0.0065355464 1028 1311867752.9183809757 0.2698292434 0.2153549927 0.3266084492 0.0043297020 0.1753670000 979496865 0 402718720 -0.2358604819 -0.0745036528 0.0062318807 1029 1311867752.9511129856 0.2693661153 0.2154074816 0.3266084492 0.0043325332 0.1761250000 979499713 0 402718720 -0.2354209274 -0.0744794905 0.0060145301 1030 1311867752.9828579426 0.2693353891 0.2154598388 0.3266084492 0.0043308349 0.1759730000 979502673 0 402718720 -0.2354130596 -0.0745074823 0.0057568029 1031 1311867753.0168170929 0.2684816718 0.2155112664 0.3266084492 0.0043288197 0.1753280000 979505577 0 402718720 -0.2342768461 -0.0746509135 0.0054233414 1032 1311867753.0510199070 0.2689085901 0.2155630080 0.3266084492 0.0043267309 0.1873440000 979508537 0 402718720 -0.2347574532 -0.0747388527 0.0049311966 1033 1311867753.0829060078 0.2685510218 0.2156143032 0.3266084492 0.0043268982 0.1754440000 979511385 0 402718720 -0.2345450372 -0.0746559724 0.0044821664 1034 1311867753.1184310913 0.2677999735 0.2156647729 0.3266084492 0.0043249224 0.1881060000 979514457 0 402718720 -0.2337931693 -0.0742520690 0.0039830161 1035 1311867753.1510760784 0.2673612833 0.2157147212 0.3266084492 0.0043228534 0.1914430000 979517305 0 402718720 -0.2334699035 -0.0743135959 0.0036254688 1036 1311867753.1830070019 0.2663857043 0.2157636315 0.3266084492 0.0043218862 0.1752010000 979520153 0 402718720 -0.2327860147 -0.0745044649 0.0033819934 1037 1311867753.2186999321 0.2652106881 0.2158113143 0.3266084492 0.0043208827 0.1741950000 979523225 0 402718720 -0.2316914797 -0.0738705695 0.0030932052 1038 1311867753.2520470619 0.2640976608 0.2158578329 0.3266084492 0.0043188587 0.1736610000 979526073 0 402718720 -0.2307470888 -0.0734447092 0.0029419430 1039 1311867753.2829909325 0.2634071708 0.2159035974 0.3266084492 0.0043169196 0.1953050000 979528977 0 402718720 -0.2305320203 -0.0732860342 0.0027465133 1040 1311867753.3196740150 0.2615982294 0.2159475346 0.3266084492 0.0043189482 0.1745400000 979532049 0 402718720 -0.2293345779 -0.0723975748 0.0021872642 1041 1311867753.3509368896 0.2601291835 0.2159899761 0.3266084492 0.0043170794 0.1733760000 979534841 0 402718720 -0.2280417383 -0.0720243827 0.0021031848 1042 1311867753.3829340935 0.2608955503 0.2160330717 0.3266084492 0.0043158666 0.1741580000 979537801 0 402718720 -0.2292561978 -0.0722446740 0.0019579930 1043 1311867753.4182109833 0.2616088688 0.2160767685 0.3266084492 0.0043147324 0.1728990000 979540817 0 402718720 -0.2303363830 -0.0720868334 0.0018155018 1044 1311867753.4511721134 0.2604260445 0.2161192487 0.3266084492 0.0043132055 0.1820600000 979543665 0 402718720 -0.2297824770 -0.0714324489 0.0012838750 1045 1311867753.4831509590 0.2598936260 0.2161611380 0.3266084492 0.0043115630 0.1722470000 979546625 0 402718720 -0.2299039960 -0.0715365037 0.0005891309 1046 1311867753.5199849606 0.2594283223 0.2162025024 0.3266084492 0.0043099550 0.1714220000 979549697 0 402718720 -0.2301984727 -0.0713691786 0.0000205419 1047 1311867753.5532789230 0.2588519156 0.2162432373 0.3266084492 0.0043080311 0.1707050000 979552601 0 402718720 -0.2303872854 -0.0712644383 -0.0005115621 1048 1311867753.5832290649 0.2585034668 0.2162835619 0.3266084492 0.0043064570 0.1697330000 979555449 0 402718720 -0.2306719571 -0.0711544156 -0.0007624361 1049 1311867753.6183180809 0.2570595145 0.2163224332 0.3266084492 0.0043051558 0.1813790000 979558465 0 402718720 -0.2301236391 -0.0706121176 -0.0011826530 1050 1311867753.6509299278 0.2564919889 0.2163606899 0.3266084492 0.0043031566 0.1685900000 979561369 0 402718720 -0.2301122099 -0.0705771893 -0.0012572618 1051 1311867753.6830120087 0.2554413080 0.2163978742 0.3266084492 0.0043013336 0.1686480000 979564217 0 402718720 -0.2294915766 -0.0704983175 -0.0015335493 1052 1311867753.7204821110 0.2551450133 0.2164347060 0.3266084492 0.0042993482 0.1665690000 979567345 0 402718720 -0.2296488434 -0.0702500939 -0.0017588588 1053 1311867753.7510209084 0.2545047402 0.2164708599 0.3266084492 0.0042977777 0.1672280000 979570137 0 402718720 -0.2298119217 -0.0700337589 -0.0018438923 1054 1311867753.7865459919 0.2527042031 0.2165052369 0.3266084492 0.0042985019 0.1844080000 979573153 0 402718720 -0.2288447767 -0.0702860802 -0.0020377529 1055 1311867753.8151860237 0.2531445622 0.2165399661 0.3266084492 0.0043000807 0.1659330000 979575945 0 402718720 -0.2294086665 -0.0694883764 -0.0019827301 1056 1311867753.8510670662 0.2522196770 0.2165737537 0.3266084492 0.0043010846 0.1655050000 979578961 0 402718720 -0.2295003831 -0.0689209849 -0.0019251732 1057 1311867753.8831698895 0.2508001924 0.2166061345 0.3266084492 0.0043062614 0.1657630000 979581921 0 402718720 -0.2285691798 -0.0695604831 -0.0020907647 1058 1311867753.9155960083 0.2500503361 0.2166377452 0.3266084492 0.0043052409 0.1670010000 979584769 0 402718720 -0.2284841835 -0.0692457035 -0.0022241438 1059 1311867753.9511620998 0.2506510317 0.2166698635 0.3266084492 0.0043069974 0.1763270000 979587785 0 402718720 -0.2298689187 -0.0683895648 -0.0019397982 1060 1311867753.9859020710 0.2500192225 0.2167013252 0.3266084492 0.0043057611 0.1650390000 979590801 0 402718720 -0.2301073372 -0.0681870505 -0.0019777813 1061 1311867754.0151760578 0.2486432046 0.2167314306 0.3266084492 0.0043048317 0.1642840000 979593593 0 402718720 -0.2299521565 -0.0681739822 -0.0018580843 1062 1311867754.0510439873 0.2481367886 0.2167610025 0.3266084492 0.0043110315 0.1636520000 979596665 0 402718720 -0.2301373333 -0.0677851066 -0.0015849337 1063 1311867754.0839149952 0.2471139431 0.2167895566 0.3266084492 0.0043098413 0.1609440000 979599569 0 402718720 -0.2298793048 -0.0671679676 -0.0014561317 1064 1311867754.1166028976 0.2468244582 0.2168177849 0.3266084492 0.0043078895 0.1723270000 979602473 0 402718720 -0.2305186689 -0.0671455339 -0.0010989599 1065 1311867754.1511039734 0.2464543283 0.2168456126 0.3266084492 0.0043135272 0.1826210000 979605377 0 402718720 -0.2308899462 -0.0668360516 -0.0009099958 1066 1311867754.1832261086 0.2449989468 0.2168720229 0.3266084492 0.0043129736 0.1594730000 979608337 0 402718720 -0.2302600145 -0.0657981932 -0.0005921745 1067 1311867754.2166349888 0.2430806160 0.2168965858 0.3266084492 0.0043163783 0.1615920000 979611241 0 402718720 -0.2296579927 -0.0657152012 -0.0005023567 1068 1311867754.2522869110 0.2421772033 0.2169202567 0.3266084492 0.0043199054 0.1734920000 979614257 0 402718720 -0.2298370749 -0.0659035221 -0.0002849257 1069 1311867754.2873370647 0.2407315373 0.2169425311 0.3266084492 0.0043298097 0.1798230000 979617273 0 402718720 -0.2298029065 -0.0649471804 -0.0002715178 1070 1311867754.3188319206 0.2429798692 0.2169668651 0.3266084492 0.0043282752 0.1721380000 979620177 0 402718720 -0.2332957536 -0.0648557693 0.0001622487 1071 1311867754.3511719704 0.2431809753 0.2169913413 0.3266084492 0.0043327857 0.1592380000 979623081 0 402718720 -0.2345841676 -0.0648181438 0.0004628449 1072 1311867754.3868899345 0.2440864146 0.2170166166 0.3266084492 0.0043314156 0.1578780000 979626041 0 402718720 -0.2366778851 -0.0640835613 0.0006383866 1073 1311867754.4159760475 0.2442260236 0.2170419749 0.3266084492 0.0043308418 0.1571720000 979628945 0 402718720 -0.2373598218 -0.0637773946 0.0008702301 1074 1311867754.4545960426 0.2440854162 0.2170671550 0.3266084492 0.0043378079 0.1687010000 979631961 0 402718720 -0.2382823229 -0.0638685971 0.0013372115 1075 1311867754.4863700867 0.2445648313 0.2170927342 0.3266084492 0.0043505289 0.1580040000 979634865 0 402718720 -0.2391901761 -0.0642646104 0.0017913075 1076 1311867754.5164580345 0.2455678582 0.2171191981 0.3266084492 0.0043509117 0.1583280000 979637713 0 402718720 -0.2405894250 -0.0645486265 0.0022613441 1077 1311867754.5513699055 0.2450711429 0.2171451516 0.3266084492 0.0043500123 0.1579040000 979640617 0 402718720 -0.2405597568 -0.0640917793 0.0025657129 1078 1311867754.5835940838 0.2452599108 0.2171712321 0.3266084492 0.0043500569 0.1580680000 979643577 0 402718720 -0.2411720306 -0.0646898150 0.0027771678 1079 1311867754.6154909134 0.2456081361 0.2171975869 0.3266084492 0.0043490402 0.1709820000 979646425 0 402718720 -0.2419226468 -0.0649469197 0.0030935290 1080 1311867754.6510920525 0.2453233153 0.2172236293 0.3266084492 0.0043472834 0.1575860000 979649385 0 402718720 -0.2420850247 -0.0646258667 0.0032452662 1081 1311867754.6872758865 0.2448584586 0.2172491934 0.3266084492 0.0043465160 0.1608640000 979652401 0 402718720 -0.2421449572 -0.0649433732 0.0033261708 1082 1311867754.7162959576 0.2458459735 0.2172756230 0.3266084492 0.0043448040 0.1572470000 979655193 0 402718720 -0.2433361858 -0.0656949729 0.0037219755 1083 1311867754.7516000271 0.2460107207 0.2173021558 0.3266084492 0.0043445620 0.1571200000 979658209 0 402718720 -0.2439000607 -0.0652183145 0.0041288207 1084 1311867754.7865269184 0.2445644587 0.2173273056 0.3266084492 0.0043438146 0.1721240000 979661169 0 402718720 -0.2429662049 -0.0649811402 0.0042220601 1085 1311867754.8154470921 0.2441122979 0.2173519922 0.3266084492 0.0043429197 0.1571010000 979663961 0 402718720 -0.2429140061 -0.0657534301 0.0042693401 1086 1311867754.8510210514 0.2429025471 0.2173755194 0.3266084492 0.0043543379 0.1567070000 979666977 0 402718720 -0.2425122559 -0.0657499284 0.0044253338 1087 1311867754.8877389431 0.2416512370 0.2173978522 0.3266084492 0.0043529182 0.1562960000 979670049 0 402718720 -0.2419814020 -0.0658268631 0.0044210418 1088 1311867754.9201259613 0.2414740622 0.2174199811 0.3266084492 0.0043509366 0.1570580000 979672953 0 402718720 -0.2423937917 -0.0670513064 0.0043933275 1089 1311867754.9510319233 0.2405171841 0.2174411906 0.3266084492 0.0043499529 0.1688290000 979675801 0 402718720 -0.2420661002 -0.0672672316 0.0044235555 1090 1311867754.9837870598 0.2385956496 0.2174605984 0.3266084492 0.0043498207 0.1553430000 979678761 0 402718720 -0.2413296998 -0.0667323843 0.0046035959 1091 1311867755.0183880329 0.2371369302 0.2174786335 0.3266084492 0.0043485419 0.1558100000 979681721 0 402718720 -0.2405567169 -0.0664073378 0.0049858354 1092 1311867755.0540831089 0.2362154126 0.2174957917 0.3266084492 0.0043487750 0.1553920000 979684737 0 402718720 -0.2401628643 -0.0665185079 0.0054181246 1093 1311867755.0850980282 0.2362371832 0.2175129385 0.3266084492 0.0043491870 0.1559960000 979687641 0 402718720 -0.2405158281 -0.0667726398 0.0057903244 1094 1311867755.1156959534 0.2359293550 0.2175297725 0.3266084492 0.0043513215 0.1675280000 979690433 0 402718720 -0.2407545298 -0.0668088570 0.0060522198 1095 1311867755.1556220055 0.2354712635 0.2175461574 0.3266084492 0.0043494769 0.1560280000 979693561 0 402718720 -0.2409332693 -0.0669570118 0.0062663858 1096 1311867755.1847031116 0.2353709340 0.2175624209 0.3266084492 0.0043482547 0.1810220000 979696465 0 402718720 -0.2413005382 -0.0675030798 0.0063167033 1097 1311867755.2151238918 0.2350105047 0.2175783262 0.3266084492 0.0043464022 0.1551780000 979699257 0 402718720 -0.2414569408 -0.0668016076 0.0064626997 1098 1311867755.2512340546 0.2343805730 0.2175936288 0.3266084492 0.0043461845 0.1562820000 979702273 0 402718720 -0.2414982319 -0.0670792311 0.0065809195 1099 1311867755.2832889557 0.2342872173 0.2176088186 0.3266084492 0.0043456764 0.1569250000 979705177 0 402718720 -0.2417264581 -0.0682388395 0.0063638887 1100 1311867755.3192110062 0.2341490835 0.2176238552 0.3266084492 0.0043448029 0.1563720000 979708193 0 402718720 -0.2419310808 -0.0682976916 0.0061849761 1101 1311867755.3553090096 0.2339445651 0.2176386787 0.3266084492 0.0043430406 0.1560070000 979711265 0 402718720 -0.2422875613 -0.0684962496 0.0059486199 1102 1311867755.3900220394 0.2345580012 0.2176540320 0.3266084492 0.0043412563 0.1679920000 979714169 0 402718720 -0.2431637049 -0.0701674074 0.0055858633 1103 1311867755.4156589508 0.2347428501 0.2176695250 0.3266084492 0.0043410464 0.1538010000 979716961 0 402718720 -0.2436753809 -0.0698935539 0.0053773429 1104 1311867755.4549160004 0.2338188440 0.2176841530 0.3266084492 0.0043396942 0.1548720000 979720033 0 402718720 -0.2434972078 -0.0693245083 0.0053540342 1105 1311867755.4860870838 0.2341952920 0.2176990952 0.3266084492 0.0043377793 0.1556330000 979722881 0 402718720 -0.2441579998 -0.0703478158 0.0053781467 1106 1311867755.5161950588 0.2340185195 0.2177138506 0.3266084492 0.0043363272 0.1562290000 979725673 0 402718720 -0.2441530526 -0.0701940507 0.0055161715 1107 1311867755.5550999641 0.2334154397 0.2177280345 0.3266084492 0.0043344291 0.1556970000 979728801 0 402718720 -0.2438855171 -0.0697128773 0.0055157975 1108 1311867755.5854589939 0.2337261438 0.2177424732 0.3266084492 0.0043325115 0.1550670000 979731705 0 402718720 -0.2443916351 -0.0695103407 0.0055206777 1109 1311867755.6171119213 0.2335980535 0.2177567704 0.3266084492 0.0043310607 0.1736470000 979734553 0 402718720 -0.2445376366 -0.0691658631 0.0054303166 1110 1311867755.6542940140 0.2333971411 0.2177708608 0.3266084492 0.0043292403 0.1560150000 979737625 0 402718720 -0.2445414066 -0.0688990653 0.0054691359 1111 1311867755.6831719875 0.2333014160 0.2177848397 0.3266084492 0.0043274019 0.1545080000 979740417 0 402718720 -0.2447097450 -0.0693166927 0.0050361967 1112 1311867755.7182741165 0.2330494672 0.2177985669 0.3266084492 0.0043257312 0.1557180000 979743433 0 402718720 -0.2448221594 -0.0698557422 0.0045996020 1113 1311867755.7511448860 0.2337762564 0.2178129224 0.3266084492 0.0043248412 0.1551870000 979746337 0 402718720 -0.2458850294 -0.0700949430 0.0041767992 1114 1311867755.7863750458 0.2335931361 0.2178270878 0.3266084492 0.0043229627 0.1653850000 979749297 0 402718720 -0.2459820509 -0.0700231194 0.0037716900 1115 1311867755.8156878948 0.2323069274 0.2178400742 0.3266084492 0.0043214889 0.1550920000 979752201 0 402718720 -0.2447565347 -0.0706609711 0.0034625654 1116 1311867755.8554079533 0.2315158546 0.2178523285 0.3266084492 0.0043212174 0.1549900000 979755217 0 402718720 -0.2442767471 -0.0699055344 0.0034650108 1117 1311867755.8848359585 0.2313892990 0.2178644475 0.3266084492 0.0043195223 0.1558130000 979758121 0 402718720 -0.2445643991 -0.0693543851 0.0034927533 1118 1311867755.9156229496 0.2308816463 0.2178760908 0.3266084492 0.0043185876 0.1554890000 979761025 0 402718720 -0.2442327738 -0.0700401962 0.0032140769 1119 1311867755.9550359249 0.2304354757 0.2178873146 0.3266084492 0.0043179974 0.1698400000 979764041 0 402718720 -0.2441377640 -0.0694932565 0.0032782403 1120 1311867755.9855198860 0.2303456068 0.2178984380 0.3266084492 0.0043170703 0.1550030000 979766889 0 402718720 -0.2441690117 -0.0691637769 0.0033886514 1121 1311867756.0173881054 0.2304432690 0.2179096288 0.3266084492 0.0043152908 0.1558650000 979769737 0 402718720 -0.2443661988 -0.0696011558 0.0033626875 1122 1311867756.0554430485 0.2297373861 0.2179201705 0.3266084492 0.0043140166 0.1559400000 979772753 0 402718720 -0.2437975407 -0.0692166016 0.0034042681 1123 1311867756.0835959911 0.2298585027 0.2179308012 0.3266084492 0.0043123054 0.1686500000 979775601 0 402718720 -0.2441005558 -0.0687977523 0.0035136829 1124 1311867756.1196908951 0.2304200232 0.2179419126 0.3266084492 0.0043121533 0.1683890000 979778617 0 402718720 -0.2444874346 -0.0697783977 0.0035091348 1125 1311867756.1519339085 0.2294212729 0.2179521165 0.3266084492 0.0043103547 0.1564420000 979781353 0 402718720 -0.2434917688 -0.0696977600 0.0033300053 1126 1311867756.1836869717 0.2301981449 0.2179629922 0.3266084492 0.0043092429 0.1568710000 979784145 0 402718720 -0.2444231808 -0.0691488385 0.0035999666 1127 1311867756.2230648994 0.2304831743 0.2179741015 0.3266084492 0.0043123255 0.1568810000 979787049 0 402718720 -0.2444554716 -0.0698890239 0.0037342799 1128 1311867756.2552509308 0.2300874889 0.2179848403 0.3266084492 0.0043140570 0.1766590000 979789953 0 402718720 -0.2440099269 -0.0699742287 0.0037356417 1129 1311867756.2851591110 0.2299645692 0.2179954512 0.3266084492 0.0043136304 0.1735650000 979792857 0 402718720 -0.2438500822 -0.0690279156 0.0039290511 1130 1311867756.3200058937 0.2298472226 0.2180059395 0.3266084492 0.0043125660 0.1577740000 979795817 0 402718720 -0.2436425686 -0.0690444484 0.0039129728 1131 1311867756.3546419144 0.2302920371 0.2180168026 0.3266084492 0.0043108432 0.1574070000 979798833 0 402718720 -0.2438754886 -0.0696135759 0.0039312379 1132 1311867756.3843090534 0.2305776030 0.2180278987 0.3266084492 0.0043094789 0.1562950000 979801625 0 402718720 -0.2442082316 -0.0694001988 0.0041108532 1133 1311867756.4231688976 0.2303205878 0.2180387484 0.3266084492 0.0043077923 0.1564820000 979804641 0 402718720 -0.2438189834 -0.0692888349 0.0042912094 1134 1311867756.4510979652 0.2303788364 0.2180496303 0.3266084492 0.0043063983 0.1696380000 979807377 0 402718720 -0.2437419295 -0.0699555799 0.0043559507 1135 1311867756.4865350723 0.2301003039 0.2180602476 0.3266084492 0.0043100724 0.1579060000 979810449 0 402718720 -0.2435032874 -0.0696811900 0.0045490232 1136 1311867756.5264549255 0.2308501899 0.2180715064 0.3266084492 0.0043090188 0.1589330000 979813521 0 402718720 -0.2440062463 -0.0700168088 0.0047944696 1137 1311867756.5525779724 0.2304603159 0.2180824024 0.3266084492 0.0043072148 0.1587190000 979816313 0 402718720 -0.2434700876 -0.0701395273 0.0048322887 1138 1311867756.5897810459 0.2300795466 0.2180929447 0.3266084492 0.0043055256 0.1590070000 979819385 0 402718720 -0.2429700494 -0.0700581819 0.0049390295 1139 1311867756.6202929020 0.2305679172 0.2181038973 0.3266084492 0.0043037451 0.1717670000 979822177 0 402718720 -0.2433163375 -0.0704837516 0.0049718618 1140 1311867756.6518390179 0.2307648808 0.2181150034 0.3266084492 0.0043018564 0.1589950000 979825081 0 402718720 -0.2433797270 -0.0710641816 0.0053042253 1141 1311867756.6839349270 0.2300396562 0.2181254545 0.3266084492 0.0043007990 0.1592680000 979827929 0 402718720 -0.2427609861 -0.0708854944 0.0054887435 1142 1311867756.7217059135 0.2297142595 0.2181356023 0.3266084492 0.0043014746 0.1602040000 979830945 0 402718720 -0.2425811440 -0.0707758963 0.0057208305 1143 1311867756.7516939640 0.2293542176 0.2181454173 0.3266084492 0.0042999118 0.1601830000 979833793 0 402718720 -0.2421755195 -0.0711499527 0.0058222949 1144 1311867756.7872660160 0.2292457223 0.2181551204 0.3266084492 0.0042981391 0.1590360000 979836809 0 402718720 -0.2419968247 -0.0713182390 0.0059038070 1145 1311867756.8227219582 0.2291892618 0.2181647572 0.3266084492 0.0042962683 0.1602420000 979839825 0 402718720 -0.2421043813 -0.0710622072 0.0060997661 1146 1311867756.8542120457 0.2292026877 0.2181743889 0.3266084492 0.0043031234 0.1600170000 979842673 0 402718720 -0.2419752926 -0.0717552304 0.0063301157 1147 1311867756.8841960430 0.2293749750 0.2181841540 0.3266084492 0.0043114068 0.1595180000 979845577 0 402718720 -0.2423711419 -0.0716964081 0.0066841426 1148 1311867756.9223539829 0.2286048084 0.2181932312 0.3266084492 0.0043106125 0.1717520000 979848593 0 402718720 -0.2417429984 -0.0719876662 0.0067971461 1149 1311867756.9552440643 0.2286444604 0.2182023272 0.3266084492 0.0043090154 0.1746060000 979851553 0 402718720 -0.2417522520 -0.0726476908 0.0067709535 1150 1311867756.9841780663 0.2281960398 0.2182110174 0.3266084492 0.0043075208 0.1608970000 979854345 0 402718720 -0.2414806187 -0.0721897185 0.0068647694 1151 1311867757.0282740593 0.2278041691 0.2182193520 0.3266084492 0.0043084209 0.1606570000 979857585 0 402718720 -0.2413770258 -0.0726385117 0.0069211652 1152 1311867757.0552940369 0.2280108035 0.2182278515 0.3266084492 0.0043067659 0.1601280000 979860377 0 402718720 -0.2413928062 -0.0734411180 0.0068200943 1153 1311867757.0858569145 0.2280335873 0.2182363561 0.3266084492 0.0043054083 0.1640630000 979863225 0 402718720 -0.2415089160 -0.0731090605 0.0069470434 1154 1311867757.1283040047 0.2279722542 0.2182447927 0.3266084492 0.0043114740 0.1710200000 979866353 0 402718720 -0.2413965315 -0.0741631538 0.0068912753 1155 1311867757.1522068977 0.2282238305 0.2182534326 0.3266084492 0.0043106007 0.1608670000 979868977 0 402718720 -0.2413810641 -0.0754982457 0.0066342996 1156 1311867757.1851921082 0.2292509526 0.2182629460 0.3266084492 0.0043088285 0.1595550000 979871937 0 402718720 -0.2423066050 -0.0754978284 0.0067307362 1157 1311867757.2192370892 0.2294475436 0.2182726129 0.3266084492 0.0043075587 0.1588600000 979874953 0 402718720 -0.2423222661 -0.0761233941 0.0064635654 1158 1311867757.2523930073 0.2301905751 0.2182829047 0.3266084492 0.0043241023 0.1582580000 979877857 0 402718720 -0.2426808029 -0.0772896931 0.0059650000 1159 1311867757.2835690975 0.2303817421 0.2182933438 0.3266084492 0.0043259500 0.1893360000 979880705 0 402718720 -0.2429125905 -0.0766205862 0.0056877290 1160 1311867757.3233768940 0.2316205502 0.2183048327 0.3266084492 0.0043347962 0.1576820000 979883833 0 402718720 -0.2437967062 -0.0761819184 0.0055385996 1161 1311867757.3555359840 0.2325067818 0.2183170653 0.3266084492 0.0043331042 0.1569560000 979886793 0 402718720 -0.2446058095 -0.0766904205 0.0055178781 1162 1311867757.3833439350 0.2328045517 0.2183295330 0.3266084492 0.0043322678 0.1568390000 979889529 0 402718720 -0.2449344397 -0.0761781856 0.0057825013 1163 1311867757.4264349937 0.2331574410 0.2183422827 0.3266084492 0.0043319866 0.1569870000 979892657 0 402718720 -0.2450598925 -0.0766610652 0.0057736477 1164 1311867757.4546940327 0.2334811240 0.2183552886 0.3266084492 0.0043314015 0.1669840000 979895449 0 402718720 -0.2453232259 -0.0769842938 0.0058223763 1165 1311867757.4884710312 0.2330774963 0.2183679256 0.3266084492 0.0043295875 0.1574930000 979898465 0 402718720 -0.2449078411 -0.0763179660 0.0057988828 1166 1311867757.5210690498 0.2330388427 0.2183805079 0.3266084492 0.0043309880 0.1571870000 979901201 0 402718720 -0.2445931584 -0.0773624927 0.0057822126 1167 1311867757.5554831028 0.2336195260 0.2183935662 0.3266084492 0.0043294961 0.1562130000 979904217 0 402718720 -0.2451745570 -0.0776520595 0.0059151133 1168 1311867757.5887749195 0.2337899804 0.2184067481 0.3266084492 0.0043282451 0.1554060000 979907177 0 402718720 -0.2453558743 -0.0772918835 0.0060945707 1169 1311867757.6231749058 0.2335865945 0.2184197334 0.3266084492 0.0043270752 0.1688420000 979910137 0 402718720 -0.2453254014 -0.0776007548 0.0062136888 1170 1311867757.6566219330 0.2337163389 0.2184328074 0.3266084492 0.0043253699 0.1551150000 979913041 0 402718720 -0.2454411387 -0.0773627907 0.0064925211 1171 1311867757.6914329529 0.2334748060 0.2184456528 0.3266084492 0.0043240139 0.1544110000 979916001 0 402718720 -0.2453134656 -0.0768934935 0.0066217138 1172 1311867757.7207450867 0.2335821986 0.2184585680 0.3266084492 0.0043222010 0.1545360000 979918905 0 402718720 -0.2454541624 -0.0773089454 0.0068249302 1173 1311867757.7614738941 0.2332912683 0.2184712131 0.3266084492 0.0043205414 0.1539270000 979921977 0 402718720 -0.2451971024 -0.0776967257 0.0069273445 1174 1311867757.7876570225 0.2337702364 0.2184842446 0.3266084492 0.0043187182 0.1537760000 979924769 0 402718720 -0.2456585318 -0.0779059827 0.0070618344 1175 1311867757.8206570148 0.2338832319 0.2184973501 0.3266084492 0.0043169761 0.1531470000 979927729 0 402718720 -0.2456863672 -0.0786689892 0.0068443441 1176 1311867757.8555610180 0.2342945635 0.2185107831 0.3266084492 0.0043153968 0.1509730000 979930633 0 402718720 -0.2461897284 -0.0790600032 0.0067295060 1177 1311867757.8887560368 0.2347946018 0.2185246182 0.3266084492 0.0043163910 0.1552810000 979933593 0 402718720 -0.2466594875 -0.0790477023 0.0065117544 1178 1311867757.9201729298 0.2348375767 0.2185384662 0.3266084492 0.0043146661 0.1515500000 979936441 0 402718720 -0.2467219234 -0.0792724341 0.0064192521 1179 1311867757.9554479122 0.2349976599 0.2185524265 0.3266084492 0.0043131311 0.1513040000 979939457 0 402718720 -0.2468129247 -0.0793432519 0.0062647066 1180 1311867757.9904439449 0.2350894064 0.2185664409 0.3266084492 0.0043183193 0.1497750000 979942529 0 402718720 -0.2467788607 -0.0790333152 0.0061172335 1181 1311867758.0221159458 0.2348894626 0.2185802622 0.3266084492 0.0043170911 0.1497060000 979945377 0 402718720 -0.2464960814 -0.0791768357 0.0058260867 1182 1311867758.0557579994 0.2348806262 0.2185940527 0.3266084492 0.0043154255 0.1492230000 979948393 0 402718720 -0.2464720309 -0.0793182552 0.0057576890 1183 1311867758.0871500969 0.2353343666 0.2186082034 0.3266084492 0.0043136713 0.1485610000 979951185 0 402718720 -0.2469096780 -0.0796065778 0.0054987990 1184 1311867758.1223280430 0.2353817374 0.2186223703 0.3266084492 0.0043119665 0.1588440000 979954201 0 402718720 -0.2468635291 -0.0798601955 0.0052549639 1185 1311867758.1526539326 0.2358041853 0.2186368697 0.3266084492 0.0043144173 0.1482560000 979957049 0 402718720 -0.2472862005 -0.0801842660 0.0050385632 1186 1311867758.1877539158 0.2358164787 0.2186513550 0.3266084492 0.0043129577 0.1476160000 979960065 0 402718720 -0.2473244816 -0.0802851990 0.0046152715 1187 1311867758.2221779823 0.2360216528 0.2186659888 0.3266084492 0.0043129839 0.1457240000 979963025 0 402718720 -0.2475105822 -0.0806687251 0.0041975966 1188 1311867758.2562980652 0.2368120700 0.2186812633 0.3266084492 0.0043112751 0.1460430000 979965985 0 402718720 -0.2484311163 -0.0809612274 0.0039144061 1189 1311867758.2902839184 0.2362657785 0.2186960526 0.3266084492 0.0043100007 0.1593070000 979969001 0 402718720 -0.2479762733 -0.0813071951 0.0034113091 1190 1311867758.3220090866 0.2354528606 0.2187101340 0.3266084492 0.0043103421 0.1452120000 979971849 0 402718720 -0.2472022921 -0.0815078318 0.0030391451 1191 1311867758.3539829254 0.2347751260 0.2187236226 0.3266084492 0.0043089970 0.1445530000 979974809 0 402718720 -0.2467735708 -0.0814098045 0.0026736839 1192 1311867758.3902978897 0.2346376032 0.2187369733 0.3266084492 0.0043073769 0.1446440000 979977769 0 402718720 -0.2468991429 -0.0813466534 0.0024418400 1193 1311867758.4210340977 0.2350817472 0.2187506739 0.3266084492 0.0043056338 0.1445590000 979980673 0 402718720 -0.2474638820 -0.0820676908 0.0020798589 1194 1311867758.4536960125 0.2353680879 0.2187645913 0.3266084492 0.0043043540 0.1555730000 979983577 0 402718720 -0.2479260713 -0.0818037614 0.0020376563 1195 1311867758.4900159836 0.2347711325 0.2187779859 0.3266084492 0.0043030768 0.1537020000 979986537 0 402718720 -0.2477440983 -0.0803797171 0.0020926285 1196 1311867758.5217890739 0.2353502512 0.2187918423 0.3266084492 0.0043015893 0.1426530000 979989441 0 402718720 -0.2483298331 -0.0809576288 0.0021506231 1197 1311867758.5528969765 0.2357248962 0.2188059885 0.3266084492 0.0042998901 0.1427850000 979992345 0 402718720 -0.2487336993 -0.0817025527 0.0021991357 1198 1311867758.5893049240 0.2354908735 0.2188199158 0.3266084492 0.0042985497 0.1421700000 979995361 0 402718720 -0.2487493604 -0.0810644478 0.0023245171 1199 1311867758.6221299171 0.2347682416 0.2188332172 0.3266084492 0.0042986854 0.1415670000 979998265 0 402718720 -0.2482083440 -0.0812947676 0.0022075416 1200 1311867758.6535029411 0.2359935641 0.2188475175 0.3266084492 0.0042969429 0.1419920000 980001225 0 402718720 -0.2493571341 -0.0823134333 0.0024241800 1201 1311867758.6911680698 0.2359983027 0.2188617979 0.3266084492 0.0042970511 0.1487420000 980004241 0 402718720 -0.2495328635 -0.0815832391 0.0026231823 1202 1311867758.7212190628 0.2354491353 0.2188755977 0.3266084492 0.0042969335 0.1416990000 980007089 0 402718720 -0.2489282042 -0.0819505826 0.0026244540 1203 1311867758.7601859570 0.2361855954 0.2188899867 0.3266084492 0.0042955878 0.1412260000 980010161 0 402718720 -0.2497690618 -0.0820831731 0.0028585922 1204 1311867758.7879199982 0.2364250869 0.2189045507 0.3266084492 0.0042938993 0.1414090000 980012953 0 402718720 -0.2501328886 -0.0819950402 0.0030819196 1205 1311867758.8218998909 0.2362172157 0.2189189181 0.3266084492 0.0042933129 0.1413350000 980015857 0 402718720 -0.2499568760 -0.0824329779 0.0031321880 1206 1311867758.8574860096 0.2371300757 0.2189340185 0.3266084492 0.0042931774 0.1530820000 980018873 0 402718720 -0.2508210242 -0.0832474083 0.0034235972 1207 1311867758.8875849247 0.2376391441 0.2189495157 0.3266084492 0.0042914713 0.1402830000 980021721 0 402718720 -0.2512752414 -0.0830981135 0.0036261925 1208 1311867758.9205179214 0.2377551943 0.2189650834 0.3266084492 0.0042899562 0.1408290000 980024513 0 402718720 -0.2513074875 -0.0832690969 0.0035563791 1209 1311867758.9576990604 0.2383506298 0.2189811177 0.3266084492 0.0042903931 0.1407270000 980027641 0 402718720 -0.2517091036 -0.0844976977 0.0034971042 1210 1311867758.9880809784 0.2392735183 0.2189978883 0.3266084492 0.0042886907 0.1393090000 980030489 0 402718720 -0.2524431944 -0.0852068439 0.0034275849 1211 1311867759.0196750164 0.2385470867 0.2190140313 0.3266084492 0.0042869912 0.1574390000 980033393 0 402718720 -0.2518662512 -0.0846967548 0.0031834615 1212 1311867759.0579299927 0.2390313148 0.2190305472 0.3266084492 0.0042857560 0.1384250000 980036465 0 402718720 -0.2526243925 -0.0841697156 0.0033134476 1213 1311867759.0873589516 0.2394368351 0.2190473702 0.3266084492 0.0042847228 0.1385370000 980039257 0 402718720 -0.2533062994 -0.0835144147 0.0035481509 1214 1311867759.1199090481 0.2394034863 0.2190641380 0.3266084492 0.0042832590 0.1372820000 980042161 0 402718720 -0.2535122931 -0.0829429701 0.0036298416 1215 1311867759.1563479900 0.2392545789 0.2190807557 0.3266084492 0.0042818011 0.1374150000 980045065 0 402718720 -0.2533699572 -0.0830850452 0.0036737996 1216 1311867759.1888740063 0.2396406829 0.2190976635 0.3266084492 0.0042800679 0.1526220000 980048025 0 402718720 -0.2538501918 -0.0833507478 0.0036972489 1217 1311867759.2214748859 0.2391889244 0.2191141724 0.3266084492 0.0042787556 0.1376860000 980050873 0 402718720 -0.2534429431 -0.0838176608 0.0037687833 1218 1311867759.2585420609 0.2388420105 0.2191303693 0.3266084492 0.0042772207 0.1373080000 980053945 0 402718720 -0.2531163394 -0.0840829015 0.0035818475 1219 1311867759.2957389355 0.2392961532 0.2191469122 0.3266084492 0.0042756459 0.1367720000 980056961 0 402718720 -0.2535462081 -0.0846042633 0.0036616614 1220 1311867759.3223690987 0.2393751591 0.2191634927 0.3266084492 0.0042739157 0.1488390000 980059697 0 402718720 -0.2536348104 -0.0848020390 0.0035884837 1221 1311867759.3619010448 0.2399968356 0.2191805552 0.3266084492 0.0042732670 0.1482870000 980062825 0 402718720 -0.2539740205 -0.0850045085 0.0037479517 1222 1311867759.3886260986 0.2411326766 0.2191985193 0.3266084492 0.0042730697 0.1363550000 980065617 0 402718720 -0.2550711334 -0.0859125406 0.0039048183 1223 1311867759.4206190109 0.2419201136 0.2192170979 0.3266084492 0.0042727404 0.1355380000 980068521 0 402718720 -0.2557468712 -0.0861850083 0.0040717619 1224 1311867759.4585750103 0.2417193800 0.2192354821 0.3266084492 0.0042713670 0.1351760000 980071593 0 402718720 -0.2555072606 -0.0859856233 0.0041455342 1225 1311867759.4905979633 0.2410708666 0.2192533069 0.3266084492 0.0042705136 0.1348000000 980074497 0 402718720 -0.2550483644 -0.0854030624 0.0040576509 1226 1311867759.5243968964 0.2413801104 0.2192713549 0.3266084492 0.0042691186 0.1449760000 980077457 0 402718720 -0.2550452352 -0.0859326273 0.0042438810 1227 1311867759.5617649555 0.2417513430 0.2192896760 0.3266084492 0.0042674794 0.1352770000 980080473 0 402718720 -0.2553658485 -0.0860671625 0.0044493284 1228 1311867759.5870699883 0.2418388724 0.2193080385 0.3266084492 0.0042657686 0.1354200000 980083153 0 402718720 -0.2552632391 -0.0865737870 0.0045333100 1229 1311867759.6198399067 0.2423018366 0.2193267479 0.3266084492 0.0042641021 0.1342870000 980086057 0 402718720 -0.2554922700 -0.0873792544 0.0047058738 1230 1311867759.6576719284 0.2430128604 0.2193460049 0.3266084492 0.0042625571 0.1337190000 980089073 0 402718720 -0.2558601797 -0.0877098516 0.0047959420 1231 1311867759.6904048920 0.2434795350 0.2193656097 0.3266084492 0.0042610422 0.1478900000 980092033 0 402718720 -0.2561300993 -0.0879803374 0.0046890164 1232 1311867759.7190918922 0.2442118675 0.2193857771 0.3266084492 0.0042596566 0.1334950000 980094825 0 402718720 -0.2565998733 -0.0886272117 0.0046020122 1233 1311867759.7576398849 0.2438625097 0.2194056285 0.3266084492 0.0042586765 0.1339730000 980097897 0 402718720 -0.2561999261 -0.0886598527 0.0044579664 1234 1311867759.7871410847 0.2439847440 0.2194255467 0.3266084492 0.0042600437 0.1331400000 980100745 0 402718720 -0.2563689351 -0.0884136856 0.0044247927 1235 1311867759.8209869862 0.2446771413 0.2194459933 0.3266084492 0.0042662950 0.1330670000 980103649 0 402718720 -0.2570285797 -0.0893244669 0.0045104483 1236 1311867759.8573861122 0.2459441423 0.2194674320 0.3266084492 0.0042730938 0.1474740000 980106721 0 402718720 -0.2579640150 -0.0896106958 0.0044492641 1237 1311867759.8883268833 0.2460158616 0.2194888939 0.3266084492 0.0042772384 0.1326690000 980109569 0 402718720 -0.2580520213 -0.0898102149 0.0041973479 1238 1311867759.9261589050 0.2464351803 0.2195106599 0.3266084492 0.0042769294 0.1317530000 980112641 0 402718720 -0.2583641112 -0.0908642113 0.0038168768 1239 1311867759.9576280117 0.2467404306 0.2195326371 0.3266084492 0.0042765901 0.1313620000 980115545 0 402718720 -0.2586960495 -0.0909936652 0.0035472682 1240 1311867759.9870700836 0.2464163899 0.2195543176 0.3266084492 0.0042758892 0.1323450000 980118337 0 402718720 -0.2585237622 -0.0905634314 0.0032509828 1241 1311867760.0261199474 0.2471275032 0.2195765361 0.3266084492 0.0042761593 0.1316890000 980121409 0 402718720 -0.2593361139 -0.0910722092 0.0028430535 1242 1311867760.0566520691 0.2477519661 0.2195992216 0.3266084492 0.0042759033 0.1308740000 980124313 0 402718720 -0.2600395977 -0.0912880599 0.0028028346 1243 1311867760.0870590210 0.2479946017 0.2196220658 0.3266084492 0.0042742724 0.1434510000 980127161 0 402718720 -0.2605486810 -0.0904482529 0.0029092829 1244 1311867760.1246991158 0.2476529181 0.2196445987 0.3266084492 0.0042734114 0.1304900000 980130233 0 402718720 -0.2604345977 -0.0904843137 0.0027354530 1245 1311867760.1576859951 0.2480011433 0.2196673750 0.3266084492 0.0042732659 0.1296200000 980133137 0 402718720 -0.2606875300 -0.0909622386 0.0025088971 1246 1311867760.1870229244 0.2481512427 0.2196902353 0.3266084492 0.0042717329 0.1449210000 980135985 0 402718720 -0.2610463500 -0.0904433727 0.0024292648 1247 1311867760.2261290550 0.2484062761 0.2197132634 0.3266084492 0.0042719498 0.1291090000 980139057 0 402718720 -0.2614342868 -0.0909721032 0.0021530832 1248 1311867760.2573459148 0.2490826398 0.2197367965 0.3266084492 0.0042703705 0.1293950000 980141961 0 402718720 -0.2621580958 -0.0916090161 0.0018117501 1249 1311867760.2895119190 0.2487590909 0.2197600330 0.3266084492 0.0042687386 0.1274320000 980144921 0 402718720 -0.2620302141 -0.0914345682 0.0016085727 1250 1311867760.3248739243 0.2488327771 0.2197832912 0.3266084492 0.0042672398 0.1278390000 980147937 0 402718720 -0.2622404099 -0.0915276334 0.0013611573 1251 1311867760.3574841022 0.2501451075 0.2198075612 0.3266084492 0.0042753019 0.1397710000 980150785 0 402718720 -0.2635436058 -0.0925874338 0.0012487225 1252 1311867760.3897368908 0.2501753569 0.2198318166 0.3266084492 0.0042736979 0.1271610000 980153745 0 402718720 -0.2637005746 -0.0929036513 0.0005006856 1253 1311867760.4247770309 0.2497661710 0.2198557068 0.3266084492 0.0042761870 0.1265540000 980156705 0 402718720 -0.2637087107 -0.0924036130 0.0001375233 1254 1311867760.4572839737 0.2505617738 0.2198801933 0.3266084492 0.0042748781 0.1264170000 980159553 0 402718720 -0.2641619444 -0.0926844627 -0.0001782443 1255 1311867760.4886090755 0.2513395250 0.2199052605 0.3266084492 0.0042732549 0.1258160000 980162513 0 402718720 -0.2649401128 -0.0930554941 -0.0004626300 1256 1311867760.5243430138 0.2518164217 0.2199306674 0.3266084492 0.0042717641 0.1401700000 980165529 0 402718720 -0.2652565837 -0.0929035842 -0.0006184362 1257 1311867760.5571060181 0.2522073686 0.2199563450 0.3266084492 0.0042702013 0.1251870000 980168433 0 402718720 -0.2654945850 -0.0933092088 -0.0009632461 1258 1311867760.5894339085 0.2524636686 0.2199821855 0.3266084492 0.0042687686 0.1246350000 980171393 0 402718720 -0.2656872571 -0.0936648399 -0.0011622719 1259 1311867760.6240029335 0.2530502379 0.2200084508 0.3266084492 0.0042673910 0.1233930000 980174353 0 402718720 -0.2661337256 -0.0935331061 -0.0013659606 1260 1311867760.6560370922 0.2531181872 0.2200347284 0.3266084492 0.0042657513 0.1355220000 980177257 0 402718720 -0.2660111487 -0.0937171876 -0.0016442765 1261 1311867760.6867549419 0.2542400956 0.2200618540 0.3266084492 0.0042648430 0.1349100000 980180105 0 402718720 -0.2671166360 -0.0947963223 -0.0018188279 1262 1311867760.7232599258 0.2540017664 0.2200887477 0.3266084492 0.0042632863 0.1235310000 980183121 0 402718720 -0.2667929828 -0.0949505344 -0.0021917161 1263 1311867760.7558701038 0.2546002865 0.2201160728 0.3266084492 0.0042616232 0.1237540000 980186081 0 402718720 -0.2674412727 -0.0949318707 -0.0024947831 1264 1311867760.7868170738 0.2553951144 0.2201439834 0.3266084492 0.0042600593 0.1232330000 980188929 0 402718720 -0.2679890394 -0.0958651081 -0.0027949554 1265 1311867760.8233850002 0.2520870566 0.2201692348 0.3266084492 0.0042586639 0.1420760000 980191945 0 402718720 -0.2644795477 -0.0960803479 -0.0034742346 1266 1311867760.8547210693 0.2515693009 0.2201940374 0.3266084492 0.0042572495 0.1225190000 980194849 0 402718720 -0.2637855709 -0.0957352966 -0.0035019973 1267 1311867760.8877849579 0.2521628141 0.2202192693 0.3266084492 0.0042556757 0.1221860000 980197753 0 402718720 -0.2642607391 -0.0964004770 -0.0037669486 1268 1311867760.9240860939 0.2527429760 0.2202449189 0.3266084492 0.0042579921 0.1219040000 980200825 0 402718720 -0.2648315132 -0.0961084887 -0.0038996050 1269 1311867760.9559810162 0.2522249818 0.2202701199 0.3266084492 0.0042563967 0.1212210000 980203729 0 402718720 -0.2644156218 -0.0955625996 -0.0040475791 1270 1311867760.9867389202 0.2522830367 0.2202953269 0.3266084492 0.0042550333 0.1219340000 980206521 0 402718720 -0.2645002007 -0.0958483741 -0.0042272690 1271 1311867761.0245900154 0.2524623275 0.2203206353 0.3266084492 0.0042534180 0.1322080000 980209649 0 402718720 -0.2647470236 -0.0961593911 -0.0045113070 1272 1311867761.0566051006 0.2514477968 0.2203451064 0.3266084492 0.0042518758 0.1203400000 980212553 0 402718720 -0.2638553083 -0.0954227298 -0.0048540495 1273 1311867761.0866270065 0.2518431246 0.2203698495 0.3266084492 0.0042507402 0.1196130000 980215345 0 402718720 -0.2643002272 -0.0955531523 -0.0049221702 1274 1311867761.1242640018 0.2531404495 0.2203955721 0.3266084492 0.0042511774 0.1200240000 980218473 0 402718720 -0.2657061219 -0.0958097652 -0.0050440677 1275 1311867761.1547141075 0.2543296516 0.2204221871 0.3266084492 0.0042499151 0.1197700000 980221321 0 402718720 -0.2670193315 -0.0953217894 -0.0051023336 1276 1311867761.1912519932 0.2537409067 0.2204482989 0.3266084492 0.0042495899 0.1328210000 980224281 0 402718720 -0.2665530741 -0.0956731737 -0.0053854096 1277 1311867761.2244689465 0.2545516193 0.2204750047 0.3266084492 0.0042480579 0.1185530000 980227297 0 402718720 -0.2674266398 -0.0963829085 -0.0054422929 1278 1311867761.2564349174 0.2556458414 0.2205025250 0.3266084492 0.0042486399 0.1184070000 980230201 0 402718720 -0.2686648965 -0.0957599804 -0.0054546176 1279 1311867761.2914810181 0.2555944324 0.2205299620 0.3266084492 0.0042471087 0.1175940000 980233105 0 402718720 -0.2687599361 -0.0957245082 -0.0057913717 1280 1311867761.3245120049 0.2560583651 0.2205577185 0.3266084492 0.0042458372 0.1183180000 980236121 0 402718720 -0.2692359090 -0.0967156440 -0.0058040502 1281 1311867761.3563210964 0.2553254962 0.2205848596 0.3266084492 0.0042442216 0.1283320000 980238969 0 402718720 -0.2687163651 -0.0962162763 -0.0060758782 1282 1311867761.3919639587 0.2550019622 0.2206117061 0.3266084492 0.0042426698 0.1179610000 980241985 0 402718720 -0.2685834467 -0.0964730605 -0.0065236506 1283 1311867761.4230949879 0.2559655905 0.2206392617 0.3266084492 0.0042419884 0.1174320000 980244889 0 402718720 -0.2697152197 -0.0969241634 -0.0068720351 1284 1311867761.4547801018 0.2555613816 0.2206664596 0.3266084492 0.0042406633 0.1171740000 980247737 0 402718720 -0.2694780231 -0.0961583555 -0.0072515029 1285 1311867761.4908668995 0.2557244599 0.2206937421 0.3266084492 0.0042390645 0.1170670000 980250809 0 402718720 -0.2697148919 -0.0959550887 -0.0075679086 1286 1311867761.5258040428 0.2566652298 0.2207217137 0.3266084492 0.0042374593 0.1173680000 980253713 0 402718720 -0.2706117332 -0.0969910920 -0.0079935370 1287 1311867761.5562748909 0.2572821081 0.2207501212 0.3266084492 0.0042360087 0.1166650000 980256561 0 402718720 -0.2710655034 -0.0974564999 -0.0081641385 1288 1311867761.5914149284 0.2563222647 0.2207777393 0.3266084492 0.0042350893 0.1163990000 980259521 0 402718720 -0.2700574100 -0.0969687775 -0.0087431567 1289 1311867761.6232030392 0.2569170892 0.2208057760 0.3266084492 0.0042347438 0.1163790000 980262481 0 402718720 -0.2705232799 -0.0978944600 -0.0092814229 1290 1311867761.6567790508 0.2574614584 0.2208341913 0.3266084492 0.0042349182 0.1153220000 980265385 0 402718720 -0.2708768547 -0.0985193104 -0.0094364593 1291 1311867761.6917459965 0.2567466795 0.2208620088 0.3266084492 0.0042333709 0.1148570000 980268345 0 402718720 -0.2701257467 -0.0979382470 -0.0098321615 1292 1311867761.7235610485 0.2573884130 0.2208902801 0.3266084492 0.0042340582 0.1146160000 980271249 0 402718720 -0.2705012858 -0.0986677781 -0.0099039674 1293 1311867761.7545659542 0.2582520843 0.2209191755 0.3266084492 0.0042328183 0.1139350000 980274097 0 402718720 -0.2711539865 -0.0994723514 -0.0100755915 1294 1311867761.7916970253 0.2579495609 0.2209477925 0.3266084492 0.0042324607 0.1257730000 980277113 0 402718720 -0.2706151307 -0.0993726403 -0.0103135286 1295 1311867761.8235230446 0.2574996054 0.2209760178 0.3266084492 0.0042308830 0.1132750000 980280017 0 402718720 -0.2700920701 -0.0992147028 -0.0105179790 1296 1311867761.8546519279 0.2571167350 0.2210039042 0.3266084492 0.0042292798 0.1274160000 980282921 0 402718720 -0.2696480453 -0.0989983827 -0.0106996847 1297 1311867761.8910980225 0.2581818104 0.2210325687 0.3266084492 0.0042285589 0.1126230000 980285937 0 402718720 -0.2705723345 -0.0986440480 -0.0105505157 1298 1311867761.9224560261 0.2578903139 0.2210609645 0.3266084492 0.0042277965 0.1126450000 980288841 0 402718720 -0.2700271010 -0.0987258628 -0.0105550475 1299 1311867761.9546790123 0.2580581009 0.2210894458 0.3266084492 0.0042275859 0.1126060000 980291801 0 402718720 -0.2698046565 -0.0997318849 -0.0109219365 1300 1311867761.9942779541 0.2591354549 0.2211187119 0.3266084492 0.0042263808 0.1107050000 980294929 0 402718720 -0.2705298364 -0.1006255075 -0.0112637971 1301 1311867762.0235669613 0.2593144774 0.2211480707 0.3266084492 0.0042272928 0.1231050000 980297721 0 402718720 -0.2704238594 -0.1007073075 -0.0116034253 1302 1311867762.0558550358 0.2594685256 0.2211775027 0.3266084492 0.0042258546 0.1107770000 980300625 0 402718720 -0.2704651952 -0.1005347148 -0.0118894745 1303 1311867762.0913889408 0.2596324086 0.2212070153 0.3266084492 0.0042470863 0.1105740000 980303585 0 402718720 -0.2706681788 -0.1007849127 -0.0120617896 1304 1311867762.1225299835 0.2603558302 0.2212370374 0.3266084492 0.0042458488 0.1104930000 980306489 0 402718720 -0.2712519169 -0.1005573720 -0.0118067507 1305 1311867762.1545391083 0.2606698871 0.2212672541 0.3266084492 0.0042669285 0.1101740000 980309449 0 402718720 -0.2710413635 -0.1006710082 -0.0118258605 1306 1311867762.1913030148 0.2609791458 0.2212976614 0.3266084492 0.0042659470 0.1433460000 980312409 0 402718720 -0.2707839608 -0.1019424051 -0.0117430687 1307 1311867762.2234869003 0.2626855671 0.2213293277 0.3266084492 0.0042644253 0.1095100000 980315369 0 402718720 -0.2721299827 -0.1023104563 -0.0114713674 1308 1311867762.2565600872 0.2632510662 0.2213613780 0.3266084492 0.0042629399 0.1093020000 980318329 0 402718720 -0.2724668682 -0.1022083834 -0.0116318353 1309 1311867762.2907900810 0.2631558180 0.2213933065 0.3266084492 0.0042616580 0.1082120000 980321233 0 402718720 -0.2722476423 -0.1023428813 -0.0115915872 1310 1311867762.3235380650 0.2633182704 0.2214253103 0.3266084492 0.0042857552 0.1083180000 980324193 0 402718720 -0.2723480165 -0.1028420329 -0.0116079738 1311 1311867762.3545570374 0.2639255226 0.2214577285 0.3266084492 0.0042846117 0.1083660000 980327097 0 402718720 -0.2728014886 -0.1027577370 -0.0115771154 1312 1311867762.3949799538 0.2643625736 0.2214904303 0.3266084492 0.0043031135 0.1079240000 980330225 0 402718720 -0.2731175125 -0.1025483906 -0.0115061197 1313 1311867762.4242470264 0.2642636597 0.2215230070 0.3266084492 0.0043016208 0.1067300000 980333073 0 402718720 -0.2727250457 -0.1035988256 -0.0117712235 1314 1311867762.4588010311 0.2641350925 0.2215554363 0.3266084492 0.0043000592 0.1065510000 980335977 0 402718720 -0.2723095119 -0.1040801927 -0.0118713072 1315 1311867762.4918160439 0.2642920017 0.2215879356 0.3266084492 0.0042984366 0.1061800000 980338881 0 402718720 -0.2726196349 -0.1039547399 -0.0120745245 1316 1311867762.5242910385 0.2645469904 0.2216205793 0.3266084492 0.0042972074 0.1186790000 980341841 0 402718720 -0.2728374302 -0.1043456495 -0.0119856000 1317 1311867762.5594940186 0.2641122639 0.2216528433 0.3266084492 0.0042956737 0.1059880000 980344857 0 402718720 -0.2724986672 -0.1044786945 -0.0119836107 1318 1311867762.5913679600 0.2636969388 0.2216847432 0.3266084492 0.0042944110 0.1054780000 980347705 0 402718720 -0.2723541558 -0.1042175815 -0.0118786581 1319 1311867762.6233699322 0.2639912963 0.2217168179 0.3266084492 0.0042929668 0.1055610000 980350609 0 402718720 -0.2725162208 -0.1052118763 -0.0117035108 1320 1311867762.6626110077 0.2646188736 0.2217493195 0.3266084492 0.0042913907 0.1048990000 980353737 0 402718720 -0.2732287943 -0.1058409661 -0.0117071634 1321 1311867762.6927230358 0.2644551694 0.2217816479 0.3266084492 0.0042898392 0.1163240000 980356473 0 402718720 -0.2731029987 -0.1061266810 -0.0118225673 1322 1311867762.7241640091 0.2632919550 0.2218130475 0.3266084492 0.0042892618 0.1038070000 980359377 0 402718720 -0.2719004452 -0.1067123786 -0.0120484009 1323 1311867762.7605299950 0.2637519240 0.2218447474 0.3266084492 0.0042877269 0.1033080000 980362337 0 402718720 -0.2727063894 -0.1070043892 -0.0120848669 1324 1311867762.7905199528 0.2636269331 0.2218763049 0.3266084492 0.0042863472 0.1026080000 980365185 0 402718720 -0.2726840377 -0.1069368348 -0.0122853024 1325 1311867762.8258841038 0.2632176280 0.2219075059 0.3266084492 0.0042848547 0.1015750000 980368201 0 402718720 -0.2724902332 -0.1058555767 -0.0118972808 1326 1311867762.8593358994 0.2638866603 0.2219391644 0.3266084492 0.0042843399 0.1158200000 980371161 0 402718720 -0.2729032338 -0.1069667265 -0.0114557175 1327 1311867762.8911890984 0.2638334930 0.2219707351 0.3266084492 0.0042830675 0.1014840000 980374009 0 402718720 -0.2727511823 -0.1074267477 -0.0113642095 1328 1311867762.9231870174 0.2629536986 0.2220015958 0.3266084492 0.0042816988 0.1011370000 980376969 0 402718720 -0.2720058560 -0.1072318181 -0.0113020875 1329 1311867762.9586219788 0.2630757093 0.2220325018 0.3266084492 0.0042803911 0.1010170000 980379985 0 402718720 -0.2721934617 -0.1073805988 -0.0112630716 1330 1311867762.9910819530 0.2633431256 0.2220635624 0.3266084492 0.0042788064 0.1006490000 980382889 0 402718720 -0.2724662423 -0.1079158634 -0.0112182805 1331 1311867763.0241999626 0.2638517022 0.2220949585 0.3266084492 0.0042774260 0.1227890000 980385849 0 402718720 -0.2728632689 -0.1075957492 -0.0110661723 1332 1311867763.0586409569 0.2650270164 0.2221271897 0.3266084492 0.0042761059 0.0999910000 980388753 0 402718720 -0.2738099098 -0.1083275676 -0.0108808931 1333 1311867763.0910348892 0.2648020685 0.2221592039 0.3266084492 0.0042750248 0.0995510000 980391713 0 402718720 -0.2733534873 -0.1090646014 -0.0112506086 1334 1311867763.1222279072 0.2643883824 0.2221908600 0.3266084492 0.0042734630 0.0984530000 980394561 0 402718720 -0.2728347480 -0.1084005609 -0.0112989638 1335 1311867763.1606709957 0.2650958002 0.2222229985 0.3266084492 0.0042719087 0.0988450000 980397633 0 402718720 -0.2733724713 -0.1084080115 -0.0112168305 1336 1311867763.1913530827 0.2648579478 0.2222549109 0.3266084492 0.0042710903 0.1105620000 980400537 0 402718720 -0.2728496492 -0.1089311317 -0.0113652684 1337 1311867763.2239060402 0.2639760077 0.2222861159 0.3266084492 0.0042698168 0.0982890000 980403441 0 402718720 -0.2718833089 -0.1079233065 -0.0112167150 1338 1311867763.2619409561 0.2644151449 0.2223176024 0.3266084492 0.0042683207 0.0985600000 980406401 0 402718720 -0.2720492780 -0.1074483544 -0.0108493678 1339 1311867763.2997210026 0.2646469176 0.2223492151 0.3266084492 0.0042677135 0.0978910000 980409529 0 402718720 -0.2720891535 -0.1070349887 -0.0104871485 1340 1311867763.3283360004 0.2617770135 0.2223786388 0.3266084492 0.0042665802 0.0978010000 980412321 0 402718720 -0.2688730061 -0.1066515073 -0.0106902225 1341 1311867763.3595879078 0.2617959380 0.2224080328 0.3266084492 0.0042654212 0.1191370000 980415113 0 402718720 -0.2686512768 -0.1064640135 -0.0103958836 1342 1311867763.3930239677 0.2612968683 0.2224370110 0.3266084492 0.0042638823 0.0982220000 980418073 0 402718720 -0.2677972913 -0.1068096831 -0.0104568284 1343 1311867763.4231410027 0.2615102530 0.2224661050 0.3266084492 0.0042624262 0.0973720000 980420921 0 402718720 -0.2675904036 -0.1070245281 -0.0103226146 1344 1311867763.4599080086 0.2608568966 0.2224946696 0.3266084492 0.0042608446 0.0991350000 980423993 0 402718720 -0.2666141391 -0.1065869331 -0.0101524740 1345 1311867763.4920830727 0.2628614008 0.2225246821 0.3266084492 0.0042593656 0.0984130000 980426841 0 402718720 -0.2680152059 -0.1078507006 -0.0099878674 1346 1311867763.5240089893 0.2625367045 0.2225544087 0.3266084492 0.0042583534 0.1098670000 980429801 0 402718720 -0.2673491240 -0.1080363095 -0.0100011751 1347 1311867763.5586268902 0.2627211213 0.2225842281 0.3266084492 0.0042568562 0.0984760000 980432705 0 402718720 -0.2673701942 -0.1075249314 -0.0099408403 1348 1311867763.5911428928 0.2630151808 0.2226142213 0.3266084492 0.0042556872 0.0983800000 980435665 0 402718720 -0.2673965693 -0.1085779443 -0.0100159915 1349 1311867763.6315419674 0.2628563046 0.2226440524 0.3266084492 0.0042548892 0.0971140000 980438737 0 402718720 -0.2670871615 -0.1089838594 -0.0101158582 1350 1311867763.6613171101 0.2629166543 0.2226738839 0.3266084492 0.0042535755 0.0972570000 980441473 0 402718720 -0.2671908438 -0.1084168777 -0.0100153973 1351 1311867763.6906011105 0.2625793219 0.2227034217 0.3266084492 0.0042523779 0.1101940000 980444377 0 402718720 -0.2667683661 -0.1087653786 -0.0100249946 1352 1311867763.7281720638 0.2621510327 0.2227325989 0.3266084492 0.0042510716 0.0965550000 980447449 0 402718720 -0.2663320601 -0.1083905846 -0.0101864515 1353 1311867763.7617700100 0.2624907494 0.2227619841 0.3266084492 0.0042498428 0.0962980000 980450353 0 402718720 -0.2665663362 -0.1085816249 -0.0102148429 1354 1311867763.7929420471 0.2634303570 0.2227920198 0.3266084492 0.0042483507 0.0956960000 980453257 0 402718720 -0.2673144341 -0.1095075160 -0.0102750426 1355 1311867763.8308730125 0.2636188269 0.2228221503 0.3266084492 0.0042471104 0.0951960000 980456329 0 402718720 -0.2674030662 -0.1100766808 -0.0106075164 1356 1311867763.8622579575 0.2646811604 0.2228530197 0.3266084492 0.0042461324 0.1087380000 980459177 0 402718720 -0.2685174346 -0.1100218073 -0.0108331135 1357 1311867763.8950018883 0.2644880414 0.2228837014 0.3266084492 0.0042448376 0.0950420000 980462137 0 402718720 -0.2681738436 -0.1109008193 -0.0112484377 1358 1311867763.9286549091 0.2645916045 0.2229144142 0.3266084492 0.0042446605 0.0941620000 980465041 0 402718720 -0.2683593631 -0.1106289104 -0.0117659224 1359 1311867763.9622230530 0.2644828558 0.2229450017 0.3266084492 0.0042440560 0.1062590000 980468001 0 402718720 -0.2684344053 -0.1093821600 -0.0119849313 1360 1311867763.9930698872 0.2656054497 0.2229763697 0.3266084492 0.0042427912 0.0939940000 980470849 0 402718720 -0.2695402205 -0.1099754795 -0.0119396420 1361 1311867764.0303530693 0.2657333612 0.2230077855 0.3266084492 0.0042426256 0.1039380000 980473921 0 402718720 -0.2694196999 -0.1111902744 -0.0122484230 1362 1311867764.0625600815 0.2651444077 0.2230387228 0.3266084492 0.0042419190 0.0925170000 980476769 0 402718720 -0.2686891854 -0.1108488590 -0.0124846436 1363 1311867764.0939369202 0.2663143575 0.2230704731 0.3266084492 0.0042405470 0.0925670000 980479673 0 402718720 -0.2697170377 -0.1110905707 -0.0123572638 1364 1311867764.1303229332 0.2671984434 0.2231028250 0.3266084492 0.0042391680 0.0921290000 980482689 0 402718720 -0.2704416215 -0.1121145710 -0.0126008801 1365 1311867764.1600530148 0.2671630085 0.2231351035 0.3266084492 0.0042393019 0.0918750000 980485537 0 402718720 -0.2703495622 -0.1117792204 -0.0125399427 1366 1311867764.1931879520 0.2672327757 0.2231673859 0.3266084492 0.0042379003 0.0922040000 980488497 0 402718720 -0.2705196738 -0.1113866195 -0.0128144734 1367 1311867764.2289299965 0.2689029872 0.2232008428 0.3266084492 0.0042374086 0.0916700000 980491457 0 402718720 -0.2720958889 -0.1120875999 -0.0128891636 1368 1311867764.2623479366 0.2677876651 0.2232334355 0.3266084492 0.0042364782 0.0909240000 980494417 0 402718720 -0.2712857425 -0.1111365631 -0.0133132590 1369 1311867764.2925939560 0.2677397430 0.2232659456 0.3266084492 0.0042349591 0.0912890000 980497265 0 402718720 -0.2713834941 -0.1112984046 -0.0135271829 1370 1311867764.3292350769 0.2694289982 0.2232996412 0.3266084492 0.0042373435 0.0905370000 980500337 0 402718720 -0.2731835842 -0.1126283407 -0.0138067808 1371 1311867764.3632280827 0.2692319453 0.2233331440 0.3266084492 0.0042378311 0.1024530000 980503297 0 402718720 -0.2731830478 -0.1127565652 -0.0141439773 1372 1311867764.3937499523 0.2695674598 0.2233668425 0.3266084492 0.0042364747 0.0910840000 980506145 0 402718720 -0.2739197612 -0.1120111793 -0.0140851038 1373 1311867764.4299139977 0.2695792913 0.2234005005 0.3266084492 0.0042369562 0.0892150000 980509161 0 402718720 -0.2741068304 -0.1135052219 -0.0144387251 1374 1311867764.4600350857 0.2698069513 0.2234342752 0.3266084492 0.0042383648 0.0881920000 980511953 0 402718720 -0.2746740878 -0.1135048717 -0.0148367817 1375 1311867764.4931490421 0.2689447999 0.2234673738 0.3266084492 0.0042429978 0.0884660000 980514857 0 402718720 -0.2745884061 -0.1120728403 -0.0148511901 1376 1311867764.5289220810 0.2697928846 0.2235010406 0.3266084492 0.0042512795 0.0885460000 980517873 0 402718720 -0.2756569684 -0.1135516986 -0.0152729144 1377 1311867764.5604650974 0.2690306306 0.2235341049 0.3266084492 0.0042513738 0.0870570000 980520721 0 402718720 -0.2750184536 -0.1144209579 -0.0159311257 1378 1311867764.5906419754 0.2691510022 0.2235672086 0.3266084492 0.0042504634 0.0984870000 980523569 0 402718720 -0.2755343020 -0.1144485250 -0.0161735602 1379 1311867764.6277070045 0.2682424486 0.2235996054 0.3266084492 0.0042641632 0.0871340000 980526585 0 402718720 -0.2745686471 -0.1150326654 -0.0167783536 1380 1311867764.6609039307 0.2688719332 0.2236324115 0.3266084492 0.0042714511 0.0868530000 980529601 0 402718720 -0.2753510475 -0.1152592227 -0.0171777420 1381 1311867764.6907351017 0.2695164382 0.2236656367 0.3266084492 0.0042701531 0.0870320000 980532393 0 402718720 -0.2762329578 -0.1149507463 -0.0172052383 1382 1311867764.7274560928 0.2694571912 0.2236987709 0.3266084492 0.0042697829 0.0867980000 980535409 0 402718720 -0.2768376768 -0.1149902567 -0.0174745023 1383 1311867764.7591719627 0.2711776793 0.2237331013 0.3266084492 0.0042685638 0.0850600000 980538369 0 402718720 -0.2787415087 -0.1156669036 -0.0175606739 1384 1311867764.7921779156 0.2720191181 0.2237679901 0.3266084492 0.0042680899 0.0856030000 980541217 0 402718720 -0.2796691060 -0.1155774295 -0.0174057651 1385 1311867764.8278260231 0.2724616230 0.2238031479 0.3266084492 0.0042684941 0.0851530000 980544233 0 402718720 -0.2803035676 -0.1165975034 -0.0176676475 1386 1311867764.8610520363 0.2726393640 0.2238383833 0.3266084492 0.0042671335 0.0937850000 980547137 0 402718720 -0.2808076143 -0.1168650836 -0.0183163416 1387 1311867764.8946199417 0.2718770504 0.2238730182 0.3266084492 0.0042663719 0.0847450000 980550153 0 402718720 -0.2805440426 -0.1155460402 -0.0180709958 1388 1311867764.9271790981 0.2719758749 0.2239076745 0.3266084492 0.0042675162 0.0849770000 980553057 0 402718720 -0.2807767391 -0.1166739464 -0.0182944648 1389 1311867764.9599800110 0.2721210122 0.2239423853 0.3266084492 0.0042662916 0.0849710000 980556017 0 402718720 -0.2813243568 -0.1166826710 -0.0184825286 1390 1311867764.9950439930 0.2720470428 0.2239769930 0.3266084492 0.0042655195 0.0861010000 980558977 0 402718720 -0.2816961110 -0.1156256124 -0.0181951113 1391 1311867765.0330669880 0.2730599642 0.2240122791 0.3266084492 0.0042656224 0.1006810000 980561937 0 402718720 -0.2832863927 -0.1152725369 -0.0181733463 1392 1311867765.0598719120 0.2731287181 0.2240475639 0.3266084492 0.0042648170 0.0870280000 980564729 0 402718720 -0.2837375998 -0.1143546104 -0.0183147304 1393 1311867765.0951199532 0.2739549279 0.2240833911 0.3266084492 0.0042657157 0.0872630000 980567745 0 402718720 -0.2845214903 -0.1145892665 -0.0182751156 1394 1311867765.1273620129 0.2728881836 0.2241184017 0.3266084492 0.0042657049 0.0868350000 980570593 0 402718720 -0.2838422954 -0.1145758256 -0.0185556747 1395 1311867765.1595649719 0.2733291984 0.2241536783 0.3266084492 0.0042643135 0.0869260000 980573441 0 402718720 -0.2845219672 -0.1147666276 -0.0186019838 1396 1311867765.1969060898 0.2732706070 0.2241888623 0.3266084492 0.0042628635 0.0981450000 980576401 0 402718720 -0.2846540213 -0.1147294566 -0.0186933484 1397 1311867765.2290871143 0.2733265758 0.2242240361 0.3266084492 0.0042616073 0.0996790000 980579305 0 402718720 -0.2847498357 -0.1154247820 -0.0189594869 1398 1311867765.2611060143 0.2736528218 0.2242593929 0.3266084492 0.0042605574 0.0864480000 980582209 0 402718720 -0.2854333222 -0.1147689447 -0.0191731658 1399 1311867765.2958459854 0.2733699977 0.2242944969 0.3266084492 0.0042592545 0.0868680000 980585113 0 402718720 -0.2850981355 -0.1155434996 -0.0194731615 1400 1311867765.3289039135 0.2751177847 0.2243307993 0.3266084492 0.0042580212 0.0862460000 980588129 0 402718720 -0.2868664265 -0.1162845790 -0.0198416170 1401 1311867765.3593490124 0.2758890688 0.2243676003 0.3266084492 0.0042568563 0.0872010000 980590977 0 402718720 -0.2877757847 -0.1160636619 -0.0201157033 1402 1311867765.3951449394 0.2756891847 0.2244042063 0.3266084492 0.0042555140 0.0863420000 980593993 0 402718720 -0.2878858745 -0.1157216355 -0.0206081551 1403 1311867765.4278709888 0.2749431431 0.2244402284 0.3266084492 0.0042559644 0.0854870000 980596841 0 402718720 -0.2870256901 -0.1167043746 -0.0212789029 1404 1311867765.4589679241 0.2762217820 0.2244771098 0.3266084492 0.0042554095 0.0992960000 980599745 0 402718720 -0.2885187268 -0.1159751862 -0.0211307090 1405 1311867765.4974000454 0.2748744488 0.2245129798 0.3266084492 0.0042540457 0.1045500000 980602817 0 402718720 -0.2873836458 -0.1158701256 -0.0215443075 1406 1311867765.5298929214 0.2752762139 0.2245490845 0.3266084492 0.0042525762 0.1069300000 980605777 0 402718720 -0.2878453732 -0.1162154824 -0.0217427891 1407 1311867765.5625720024 0.2740742862 0.2245842837 0.3266084492 0.0042511311 0.0870740000 980608681 0 402718720 -0.2869425118 -0.1149894223 -0.0219545849 1408 1311867765.5947990417 0.2742573321 0.2246195628 0.3266084492 0.0042518109 0.0880510000 980611585 0 402718720 -0.2874783874 -0.1145011261 -0.0219921842 1409 1311867765.6310911179 0.2741051912 0.2246546839 0.3266084492 0.0042507955 0.0877020000 980614545 0 402718720 -0.2876075804 -0.1139280796 -0.0222411230 1410 1311867765.6618249416 0.2748748362 0.2246903011 0.3266084492 0.0042495630 0.0878610000 980617449 0 402718720 -0.2886325121 -0.1130639315 -0.0220619142 1411 1311867765.6966838837 0.2749397457 0.2247259137 0.3266084492 0.0042483416 0.0888980000 980620409 0 402718720 -0.2888133526 -0.1132348478 -0.0223259386 1412 1311867765.7292089462 0.2760677934 0.2247622748 0.3266084492 0.0042471372 0.0886940000 980623425 0 402718720 -0.2901328206 -0.1136986092 -0.0224037506 1413 1311867765.7602009773 0.2753207088 0.2247980557 0.3266084492 0.0042458470 0.0887460000 980626273 0 402718720 -0.2896554768 -0.1131765917 -0.0225083828 1414 1311867765.7960450649 0.2757907510 0.2248341184 0.3266084492 0.0042443726 0.0889790000 980629289 0 402718720 -0.2903524935 -0.1134035587 -0.0226183441 1415 1311867765.8298408985 0.2702133656 0.2248661886 0.3266084492 0.0042442706 0.0887410000 980632193 0 402718720 -0.2849206626 -0.1124793738 -0.0237152595 1416 1311867765.8610999584 0.2694107294 0.2248976466 0.3266084492 0.0042427791 0.1002090000 980635097 0 402718720 -0.2840909958 -0.1119786426 -0.0237771664 1417 1311867765.8960449696 0.2688545287 0.2249286677 0.3266084492 0.0042419683 0.0902690000 980638057 0 402718720 -0.2837624848 -0.1114226058 -0.0235202387 1418 1311867765.9303019047 0.2690608501 0.2249597905 0.3266084492 0.0042408904 0.0905080000 980641073 0 402718720 -0.2839159071 -0.1109760478 -0.0230303407 1419 1311867765.9612519741 0.2683201134 0.2249903475 0.3266084492 0.0042396267 0.0908110000 980643865 0 402718720 -0.2831003666 -0.1104490608 -0.0227333549 1420 1311867765.9962689877 0.2675794065 0.2250203398 0.3266084492 0.0042381842 0.0915470000 980646825 0 402718720 -0.2821291089 -0.1104791239 -0.0225727670 1421 1311867766.0289440155 0.2681507170 0.2250506919 0.3266084492 0.0042367076 0.0914190000 980649841 0 402718720 -0.2825194597 -0.1105303839 -0.0224348847 1422 1311867766.0606811047 0.2690142393 0.2250816086 0.3266084492 0.0042356310 0.0920580000 980652745 0 402718720 -0.2831423879 -0.1107396781 -0.0220130831 1423 1311867766.0968139172 0.2668963671 0.2251109935 0.3266084492 0.0042343565 0.0917890000 980655761 0 402718720 -0.2807418108 -0.1099950969 -0.0219291989 1424 1311867766.1277561188 0.2655203342 0.2251393709 0.3266084492 0.0042329383 0.0929750000 980658553 0 402718720 -0.2791194618 -0.1099839211 -0.0218596011 1425 1311867766.1625239849 0.2648415267 0.2251672320 0.3266084492 0.0042323059 0.1048350000 980661569 0 402718720 -0.2782933116 -0.1095654145 -0.0215945151 1426 1311867766.1968889236 0.2637877464 0.2251943152 0.3266084492 0.0042309282 0.1048120000 980664529 0 402718720 -0.2772063017 -0.1088424847 -0.0211841110 1427 1311867766.2298009396 0.2625625730 0.2252205017 0.3266084492 0.0042295857 0.1061800000 980667489 0 402718720 -0.2759310603 -0.1085852608 -0.0207731854 1428 1311867766.2654640675 0.2613651156 0.2252458131 0.3266084492 0.0042283868 0.0954150000 980670449 0 402718720 -0.2748660445 -0.1081097797 -0.0203656722 1429 1311867766.2981679440 0.2600600719 0.2252701758 0.3266084492 0.0042281101 0.0964900000 980673353 0 402718720 -0.2735634446 -0.1071885154 -0.0195454396 1430 1311867766.3291699886 0.2588357031 0.2252936482 0.3266084492 0.0042491173 0.0974960000 980676257 0 402718720 -0.2724211216 -0.1067628190 -0.0186762400 1431 1311867766.3653209209 0.2578384280 0.2253163908 0.3266084492 0.0042650139 0.1127260000 980679217 0 402718720 -0.2710419595 -0.1067249551 -0.0180984233 1432 1311867766.3979220390 0.2582813799 0.2253394111 0.3266084492 0.0042701696 0.0982610000 980682177 0 402718720 -0.2711292505 -0.1063765213 -0.0173244309 1433 1311867766.4302849770 0.2582545877 0.2253623805 0.3266084492 0.0042721409 0.0991130000 980685137 0 402718720 -0.2707445920 -0.1070339903 -0.0169529561 1434 1311867766.4642350674 0.2576427758 0.2253848912 0.3266084492 0.0042769703 0.0991910000 980688041 0 402718720 -0.2697247565 -0.1076360792 -0.0166443642 1435 1311867766.4967210293 0.2577257454 0.2254074284 0.3266084492 0.0042757006 0.0997090000 980690945 0 402718720 -0.2694528103 -0.1074998304 -0.0162873007 1436 1311867766.5302040577 0.2577470839 0.2254299491 0.3266084492 0.0042742616 0.1133930000 980693793 0 402718720 -0.2690169513 -0.1079788655 -0.0160853919 1437 1311867766.5639820099 0.2582510710 0.2254527891 0.3266084492 0.0042729665 0.1011050000 980696753 0 402718720 -0.2689151466 -0.1093667746 -0.0162199978 1438 1311867766.5953519344 0.2581275105 0.2254755114 0.3266084492 0.0042716193 0.1007930000 980699657 0 402718720 -0.2682626843 -0.1099021509 -0.0164446402 1439 1311867766.6287128925 0.2585849464 0.2254985201 0.3266084492 0.0042701773 0.1019030000 980702617 0 402718720 -0.2682563663 -0.1098949760 -0.0168201216 1440 1311867766.6636400223 0.2586281896 0.2255215268 0.3266084492 0.0042693948 0.1009020000 980705577 0 402718720 -0.2675820589 -0.1110730171 -0.0175203849 1441 1311867766.6964800358 0.2600829005 0.2255455111 0.3266084492 0.0042843679 0.1163040000 980708425 0 402718720 -0.2681947947 -0.1115054414 -0.0180554967 1442 1311867766.7300829887 0.2609057426 0.2255700328 0.3266084492 0.0042930027 0.1010510000 980711441 0 402718720 -0.2686040103 -0.1119139344 -0.0187123008 1443 1311867766.7628269196 0.2607147396 0.2255943881 0.3266084492 0.0042918259 0.1127330000 980714345 0 402718720 -0.2680890858 -0.1118118912 -0.0196411163 1444 1311867766.7970418930 0.2632009685 0.2256204314 0.3266084492 0.0042911527 0.1013250000 980717249 0 402718720 -0.2698090076 -0.1132926941 -0.0204679165 1445 1311867766.8299551010 0.2625815868 0.2256460101 0.3266084492 0.0042901428 0.1010530000 980720153 0 402718720 -0.2688527107 -0.1129395738 -0.0216405112 1446 1311867766.8662180901 0.2636147141 0.2256722678 0.3266084492 0.0042887291 0.1142090000 980723225 0 402718720 -0.2694408298 -0.1125443652 -0.0224090479 1447 1311867766.8958721161 0.2632255554 0.2256982203 0.3266084492 0.0042875780 0.1019840000 980725961 0 402718720 -0.2683467567 -0.1138300300 -0.0237040147 1448 1311867766.9286260605 0.2637437284 0.2257244948 0.3266084492 0.0042949116 0.1028530000 980728921 0 402718720 -0.2686708868 -0.1142023578 -0.0244867876 1449 1311867766.9661469460 0.2623523176 0.2257497728 0.3266084492 0.0043133148 0.1031610000 980731993 0 402718720 -0.2667610645 -0.1128535494 -0.0253736116 1450 1311867766.9956479073 0.2616668940 0.2257745433 0.3266084492 0.0043136315 0.1041980000 980734785 0 402718720 -0.2659560144 -0.1126825362 -0.0257629752 1451 1311867767.0294270515 0.2622081637 0.2257996526 0.3266084492 0.0043135879 0.1196010000 980737801 0 402718720 -0.2662553191 -0.1133250073 -0.0259206016 1452 1311867767.0660951138 0.2634135783 0.2258255575 0.3266084492 0.0043129885 0.1050670000 980740761 0 402718720 -0.2671832442 -0.1138568744 -0.0257487688 1453 1311867767.0968320370 0.2622646093 0.2258506360 0.3266084492 0.0043118592 0.1057130000 980743665 0 402718720 -0.2661812305 -0.1129044592 -0.0258740988 1454 1311867767.1276900768 0.2629877329 0.2258761773 0.3266084492 0.0043133348 0.1210250000 980746513 0 402718720 -0.2670251429 -0.1131516322 -0.0255395938 1455 1311867767.1632909775 0.2633916736 0.2259019612 0.3266084492 0.0043119613 0.1057620000 980749529 0 402718720 -0.2673816681 -0.1139982417 -0.0255187172 1456 1311867767.1955349445 0.2628582716 0.2259273432 0.3266084492 0.0043107366 0.1222030000 980752433 0 402718720 -0.2671994269 -0.1134577841 -0.0255956165 1457 1311867767.2308650017 0.2616679966 0.2259518736 0.3266084492 0.0043097407 0.1062110000 980755505 0 402718720 -0.2659068406 -0.1136123165 -0.0258858036 1458 1311867767.2658200264 0.2614911199 0.2259762489 0.3266084492 0.0043084011 0.1061320000 980758465 0 402718720 -0.2659303546 -0.1135182083 -0.0257658847 1459 1311867767.2981290817 0.2618830502 0.2260008594 0.3266084492 0.0043075060 0.1068160000 980761369 0 402718720 -0.2665848136 -0.1136016697 -0.0256910343 1460 1311867767.3362140656 0.2608370781 0.2260247199 0.3266084492 0.0043098222 0.1077320000 980764441 0 402718720 -0.2657727599 -0.1130208895 -0.0257548764 1461 1311867767.3633511066 0.2614015341 0.2260489340 0.3266084492 0.0043084909 0.1288400000 980767233 0 402718720 -0.2663324773 -0.1135451123 -0.0256661046 1462 1311867767.3987689018 0.2598950565 0.2260720845 0.3266084492 0.0043080296 0.1086780000 980770249 0 402718720 -0.2657604218 -0.1134086028 -0.0258970857 1463 1311867767.4331369400 0.2598010600 0.2260951392 0.3266084492 0.0043067233 0.1091970000 980773209 0 402718720 -0.2657182515 -0.1128625274 -0.0257329363 1464 1311867767.4638109207 0.2601666152 0.2261184121 0.3266084492 0.0043055511 0.1097090000 980776057 0 402718720 -0.2662778199 -0.1127726883 -0.0256098323 1465 1311867767.4974899292 0.2602327168 0.2261416983 0.3266084492 0.0043041439 0.1100040000 980779017 0 402718720 -0.2665509284 -0.1131570190 -0.0256785527 1466 1311867767.5351889133 0.2594373822 0.2261644102 0.3266084492 0.0043079460 0.1224400000 980782089 0 402718720 -0.2658773661 -0.1122576743 -0.0256532002 1467 1311867767.5664100647 0.2591654360 0.2261869058 0.3266084492 0.0043121598 0.1108490000 980784993 0 402718720 -0.2659325004 -0.1120224074 -0.0255281944 1468 1311867767.5953979492 0.2590246797 0.2262092749 0.3266084492 0.0043107914 0.1112640000 980787785 0 402718720 -0.2661160231 -0.1120179892 -0.0253629908 1469 1311867767.6338059902 0.2587043047 0.2262313954 0.3266084492 0.0043097519 0.1115420000 980790857 0 402718720 -0.2662887275 -0.1117440984 -0.0252476018 1470 1311867767.6632149220 0.2587378919 0.2262535086 0.3266084492 0.0043084553 0.1121090000 980793705 0 402718720 -0.2664662600 -0.1118867546 -0.0251159463 1471 1311867767.6991050243 0.2596524060 0.2262762135 0.3266084492 0.0043077409 0.1351970000 980796721 0 402718720 -0.2675625682 -0.1122072116 -0.0251540616 1472 1311867767.7346129417 0.2597990334 0.2262989872 0.3266084492 0.0043063875 0.1120880000 980799681 0 402718720 -0.2679704726 -0.1125224382 -0.0253183581 1473 1311867767.7651679516 0.2599860430 0.2263218569 0.3266084492 0.0043049763 0.1125420000 980802585 0 402718720 -0.2684643269 -0.1123327985 -0.0256842226 1474 1311867767.7999849319 0.2602132559 0.2263448497 0.3266084492 0.0043035375 0.1253900000 980805545 0 402718720 -0.2687086165 -0.1127074510 -0.0257637817 1475 1311867767.8344929218 0.2601289749 0.2263677542 0.3266084492 0.0043024221 0.1255240000 980808449 0 402718720 -0.2686414719 -0.1135175526 -0.0260904413 1476 1311867767.8673300743 0.2599151731 0.2263904828 0.3266084492 0.0043009833 0.1222860000 980811353 0 402718720 -0.2685066462 -0.1135708913 -0.0263794996 1477 1311867767.8966870308 0.2591306567 0.2264126494 0.3266084492 0.0042995855 0.1132260000 980814145 0 402718720 -0.2678177655 -0.1129933819 -0.0265323482 1478 1311867767.9358460903 0.2587867677 0.2264345534 0.3266084492 0.0042981985 0.1129290000 980817273 0 402718720 -0.2677099705 -0.1121399850 -0.0262731835 1479 1311867767.9646739960 0.2586773038 0.2264563538 0.3266084492 0.0042969289 0.1150700000 980820121 0 402718720 -0.2677688301 -0.1115921810 -0.0261913426 1480 1311867767.9988079071 0.2591712475 0.2264784585 0.3266084492 0.0042956142 0.1255120000 980823081 0 402718720 -0.2684126794 -0.1117387414 -0.0264696293 1481 1311867768.0346310139 0.2584473789 0.2265000445 0.3266084492 0.0042942494 0.1154930000 980826097 0 402718720 -0.2677870095 -0.1113767847 -0.0266498402 1482 1311867768.0639820099 0.2580766976 0.2265213513 0.3266084492 0.0042935217 0.1155340000 980828889 0 402718720 -0.2675158381 -0.1113534644 -0.0270524248 1483 1311867768.0985600948 0.2578642964 0.2265424861 0.3266084492 0.0042921231 0.1153540000 980831905 0 402718720 -0.2676679492 -0.1112896726 -0.0277183857 1484 1311867768.1352849007 0.2580903172 0.2265637448 0.3266084492 0.0042909132 0.1154670000 980834921 0 402718720 -0.2682467103 -0.1111843735 -0.0280179549 1485 1311867768.1651999950 0.2581149638 0.2265849914 0.3266084492 0.0042896667 0.1152100000 980837769 0 402718720 -0.2686389685 -0.1105982140 -0.0282907709 1486 1311867768.1962070465 0.2576022446 0.2266058644 0.3266084492 0.0042884298 0.1278270000 980840617 0 402718720 -0.2685226798 -0.1098274216 -0.0287969969 1487 1311867768.2323460579 0.2568069696 0.2266261745 0.3266084492 0.0042876830 0.1168830000 980843633 0 402718720 -0.2679503858 -0.1096945256 -0.0291752480 1488 1311867768.2749121189 0.2566723824 0.2266463668 0.3266084492 0.0042868710 0.1168710000 980846873 0 402718720 -0.2682494521 -0.1090613678 -0.0293903891 1489 1311867768.2962079048 0.2556618452 0.2266658534 0.3266084492 0.0042854662 0.1172950000 980849441 0 402718720 -0.2674399614 -0.1078468412 -0.0294579808 1490 1311867768.3351829052 0.2539332807 0.2266841536 0.3266084492 0.0042890170 0.1186160000 980852569 0 402718720 -0.2659121752 -0.1074386016 -0.0297171623 1491 1311867768.3693380356 0.2522046864 0.2267012700 0.3266084492 0.0042883528 0.1399560000 980855417 0 402718720 -0.2643175423 -0.1076306850 -0.0303326957 1492 1311867768.4011199474 0.2514988780 0.2267178904 0.3266084492 0.0042886975 0.1203530000 980858265 0 402718720 -0.2637676895 -0.1069949567 -0.0304363631 1493 1311867768.4324789047 0.2507679164 0.2267339989 0.3266084492 0.0042873105 0.1207890000 980861057 0 402718720 -0.2633164227 -0.1059157476 -0.0304420777 1494 1311867768.4655070305 0.2507974505 0.2267501057 0.3266084492 0.0042865872 0.1205650000 980863961 0 402718720 -0.2634336352 -0.1063926518 -0.0304958932 1495 1311867768.4980540276 0.2507650256 0.2267661692 0.3266084492 0.0042856741 0.1210380000 980866921 0 402718720 -0.2635094225 -0.1062903404 -0.0305288509 1496 1311867768.5367710590 0.2493682802 0.2267812775 0.3266084492 0.0042854846 0.1462400000 980869937 0 402718720 -0.2620814443 -0.1046535671 -0.0303846076 1497 1311867768.5648899078 0.2481744140 0.2267955682 0.3266084492 0.0042860151 0.1219940000 980872785 0 402718720 -0.2609454095 -0.1043623537 -0.0302800629 1498 1311867768.5998411179 0.2479530722 0.2268096920 0.3266084492 0.0042846166 0.1239180000 980875745 0 402718720 -0.2606762350 -0.1050079390 -0.0301198885 1499 1311867768.6319470406 0.2479148805 0.2268237715 0.3266084492 0.0042832822 0.1246200000 980878649 0 402718720 -0.2606391609 -0.1048384979 -0.0298773162 1500 1311867768.6643230915 0.2469060570 0.2268371597 0.3266084492 0.0042823939 0.1251670000 980881609 0 402718720 -0.2598184645 -0.1038991213 -0.0296392553 1501 1311867768.7014238834 0.2470615506 0.2268506337 0.3266084492 0.0042813438 0.1396830000 980884569 0 402718720 -0.2600215971 -0.1034175381 -0.0292058587 1502 1311867768.7344141006 0.2472903728 0.2268642420 0.3266084492 0.0042800345 0.1262280000 980887585 0 402718720 -0.2603938878 -0.1037476286 -0.0289222375 1503 1311867768.7646389008 0.2468620539 0.2268775473 0.3266084492 0.0042790439 0.1259360000 980890433 0 402718720 -0.2599127293 -0.1037894115 -0.0285802279 1504 1311867768.8039369583 0.2463467866 0.2268904923 0.3266084492 0.0042778810 0.1271310000 980893505 0 402718720 -0.2593237758 -0.1033523306 -0.0282365605 1505 1311867768.8365039825 0.2467031330 0.2269036568 0.3266084492 0.0042765995 0.1277720000 980896465 0 402718720 -0.2595008016 -0.1035231575 -0.0278188959 1506 1311867768.8651020527 0.2467768341 0.2269168528 0.3266084492 0.0042757148 0.1380410000 980899257 0 402718720 -0.2594116330 -0.1041936725 -0.0275156759 1507 1311867768.9001519680 0.2460155040 0.2269295261 0.3266084492 0.0042744740 0.1278910000 980902273 0 402718720 -0.2585645616 -0.1039566547 -0.0273575131 1508 1311867768.9330470562 0.2464472651 0.2269424689 0.3266084492 0.0042734608 0.1287480000 980905121 0 402718720 -0.2585737109 -0.1041698009 -0.0268227533 1509 1311867768.9639101028 0.2458511591 0.2269549995 0.3266084492 0.0042722312 0.1281730000 980907969 0 402718720 -0.2579049170 -0.1043576896 -0.0266037360 1510 1311867768.9992640018 0.2461490780 0.2269677108 0.3266084492 0.0042722671 0.1294310000 980910985 0 402718720 -0.2580892742 -0.1043039188 -0.0262769945 1511 1311867769.0331530571 0.2458980531 0.2269802392 0.3266084492 0.0042715279 0.1423520000 980913833 0 402718720 -0.2578051984 -0.1035129279 -0.0259334352 1512 1311867769.0641028881 0.2454270571 0.2269924394 0.3266084492 0.0042704742 0.1307550000 980916737 0 402718720 -0.2573408782 -0.1033269018 -0.0258225389 1513 1311867769.0999929905 0.2455765754 0.2270047224 0.3266084492 0.0042691186 0.1413700000 980919753 0 402718720 -0.2575169504 -0.1037724316 -0.0257119611 1514 1311867769.1327989101 0.2452720255 0.2270167880 0.3266084492 0.0042677477 0.1308210000 980922601 0 402718720 -0.2572597563 -0.1038983241 -0.0256628953 1515 1311867769.1643240452 0.2444091439 0.2270282681 0.3266084492 0.0042732088 0.1302890000 980925505 0 402718720 -0.2566099167 -0.1038041413 -0.0255502127 1516 1311867769.2002429962 0.2444469780 0.2270397580 0.3266084492 0.0042731438 0.1439480000 980928465 0 402718720 -0.2565110624 -0.1035837233 -0.0254463144 1517 1311867769.2324860096 0.2436327487 0.2270506960 0.3266084492 0.0042751635 0.1319380000 980931369 0 402718720 -0.2558358610 -0.1027878821 -0.0254049860 1518 1311867769.2636189461 0.2436524034 0.2270616326 0.3266084492 0.0042751177 0.1449650000 980934273 0 402718720 -0.2555913627 -0.1030779481 -0.0252908673 1519 1311867769.3002018929 0.2435218692 0.2270724688 0.3266084492 0.0042808951 0.1329340000 980937233 0 402718720 -0.2554424107 -0.1028250754 -0.0252356157 1520 1311867769.3330841064 0.2423281670 0.2270825055 0.3266084492 0.0042801896 0.1335840000 980940137 0 402718720 -0.2542490065 -0.1019952372 -0.0252617411 1521 1311867769.3653230667 0.2414053380 0.2270919222 0.3266084492 0.0042788621 0.1433470000 980943153 0 402718720 -0.2535503805 -0.1005676016 -0.0250838846 1522 1311867769.3995320797 0.2409716249 0.2271010416 0.3266084492 0.0042776926 0.1354000000 980946113 0 402718720 -0.2532586455 -0.0998592451 -0.0249517001 1523 1311867769.4340240955 0.2406608015 0.2271099449 0.3266084492 0.0042766920 0.1357880000 980949017 0 402718720 -0.2530171573 -0.0996449664 -0.0249592066 1524 1311867769.4644269943 0.2402281910 0.2271185527 0.3266084492 0.0042846766 0.1364040000 980951921 0 402718720 -0.2525915802 -0.0996355936 -0.0249211192 1525 1311867769.4999239445 0.2397900522 0.2271268619 0.3266084492 0.0042868319 0.1365510000 980954937 0 402718720 -0.2521122098 -0.0992373824 -0.0251521450 1526 1311867769.5317490101 0.2408367693 0.2271358461 0.3266084492 0.0042854786 0.1484120000 980957785 0 402718720 -0.2529906034 -0.0995957404 -0.0250343587 1527 1311867769.5660109520 0.2408917397 0.2271448545 0.3266084492 0.0042841395 0.1376860000 980960633 0 402718720 -0.2531702220 -0.0999763161 -0.0249639694 1528 1311867769.6002509594 0.2403278947 0.2271534822 0.3266084492 0.0042828694 0.1378610000 980963593 0 402718720 -0.2526820302 -0.0996486694 -0.0250746924 1529 1311867769.6330249310 0.2406294793 0.2271622958 0.3266084492 0.0042855866 0.1506620000 980966553 0 402718720 -0.2527152598 -0.1001968086 -0.0248928461 1530 1311867769.6637229919 0.2401710749 0.2271707982 0.3266084492 0.0042845684 0.1380870000 980969401 0 402718720 -0.2523922622 -0.1000952497 -0.0246357638 1531 1311867769.7014029026 0.2395144701 0.2271788607 0.3266084492 0.0042892019 0.1580320000 980972529 0 402718720 -0.2518207431 -0.0993979350 -0.0242513716 1532 1311867769.7340829372 0.2396101058 0.2271869751 0.3266084492 0.0042879963 0.1385740000 980975377 0 402718720 -0.2518704832 -0.0984741896 -0.0236038882 1533 1311867769.7641069889 0.2397433370 0.2271951658 0.3266084492 0.0042950772 0.1646490000 980978281 0 402718720 -0.2519807220 -0.0978293419 -0.0229197517 1534 1311867769.8003458977 0.2391565591 0.2272029634 0.3266084492 0.0043193571 0.1412840000 980981241 0 402718720 -0.2516901195 -0.0979246348 -0.0225349944 1535 1311867769.8341090679 0.2384035587 0.2272102602 0.3266084492 0.0043186818 0.1425150000 980984201 0 402718720 -0.2507779896 -0.0982261002 -0.0223904643 1536 1311867769.8692820072 0.2383044362 0.2272174829 0.3266084492 0.0043177263 0.1540610000 980987217 0 402718720 -0.2504067123 -0.0985013470 -0.0220756084 1537 1311867769.9001140594 0.2376913428 0.2272242974 0.3266084492 0.0043169818 0.1432840000 980990121 0 402718720 -0.2497799993 -0.0974741355 -0.0216575265 1538 1311867769.9321451187 0.2369098365 0.2272305949 0.3266084492 0.0043158957 0.1446770000 980992969 0 402718720 -0.2490758449 -0.0962585881 -0.0215798505 1539 1311867769.9684319496 0.2369589508 0.2272369161 0.3266084492 0.0043147210 0.1445010000 980995985 0 402718720 -0.2491481751 -0.0962553248 -0.0214352943 1540 1311867770.0010259151 0.2365134954 0.2272429399 0.3266084492 0.0043135987 0.1457380000 980999001 0 402718720 -0.2485430539 -0.0959105417 -0.0210711993 1541 1311867770.0330319405 0.2365150303 0.2272489568 0.3266084492 0.0043123262 0.1678840000 981001849 0 402718720 -0.2485375106 -0.0954754129 -0.0208115149 1542 1311867770.0690810680 0.2353327423 0.2272541992 0.3266084492 0.0043128492 0.1477670000 981004865 0 402718720 -0.2474137247 -0.0957535952 -0.0208482035 1543 1311867770.1002650261 0.2355121821 0.2272595511 0.3266084492 0.0043141449 0.1471690000 981007769 0 402718720 -0.2475437969 -0.0959377140 -0.0204102956 1544 1311867770.1335709095 0.2349475175 0.2272645304 0.3266084492 0.0043130961 0.1482130000 981010673 0 402718720 -0.2469354570 -0.0957237780 -0.0202348456 1545 1311867770.1684958935 0.2347026765 0.2272693447 0.3266084492 0.0043118854 0.1480440000 981013689 0 402718720 -0.2467745394 -0.0956778228 -0.0201662797 1546 1311867770.2001299858 0.2346232831 0.2272741014 0.3266084492 0.0043105733 0.1605570000 981016593 0 402718720 -0.2468292415 -0.0957597420 -0.0198712163 1547 1311867770.2336180210 0.2344361097 0.2272787311 0.3266084492 0.0043099751 0.1501770000 981019497 0 402718720 -0.2470986098 -0.0958949327 -0.0196063332 1548 1311867770.2679719925 0.2344494611 0.2272833633 0.3266084492 0.0043111583 0.1496830000 981022457 0 402718720 -0.2468693554 -0.0964463651 -0.0195589811 1549 1311867770.3009040356 0.2336965501 0.2272875035 0.3266084492 0.0043107281 0.1497920000 981025361 0 402718720 -0.2462273091 -0.0965260044 -0.0194598064 1550 1311867770.3339090347 0.2345942557 0.2272922176 0.3266084492 0.0043121213 0.1632310000 981028321 0 402718720 -0.2472691238 -0.0969267860 -0.0192553848 1551 1311867770.3681850433 0.2331895232 0.2272960198 0.3266084492 0.0043300850 0.1637140000 981031281 0 402718720 -0.2462902069 -0.0964252353 -0.0195798296 1552 1311867770.4014930725 0.2326325327 0.2272994583 0.3266084492 0.0043350938 0.1517540000 981034185 0 402718720 -0.2458424717 -0.0960269198 -0.0195758399 1553 1311867770.4333899021 0.2327819467 0.2273029885 0.3266084492 0.0043359843 0.1521560000 981037145 0 402718720 -0.2462120652 -0.0959301293 -0.0192348398 1554 1311867770.4684588909 0.2327900529 0.2273065195 0.3266084492 0.0043346711 0.1635560000 981040105 0 402718720 -0.2461722344 -0.0964595303 -0.0191135593 1555 1311867770.5046019554 0.2319655865 0.2273095157 0.3266084492 0.0043334100 0.1651470000 981043121 0 402718720 -0.2455407381 -0.0964635909 -0.0192912798 1556 1311867770.5338129997 0.2321114093 0.2273126017 0.3266084492 0.0043321040 0.1655960000 981045913 0 402718720 -0.2457231730 -0.0962192193 -0.0189597420 1557 1311867770.5683600903 0.2322474569 0.2273157712 0.3266084492 0.0043375245 0.1532630000 981048873 0 402718720 -0.2459309548 -0.0961229056 -0.0186755080 1558 1311867770.6027359962 0.2321684957 0.2273188859 0.3266084492 0.0043391510 0.1536120000 981051833 0 402718720 -0.2457482964 -0.0953871980 -0.0183487292 1559 1311867770.6331069469 0.2310370505 0.2273212709 0.3266084492 0.0043385005 0.1536740000 981054681 0 402718720 -0.2445958257 -0.0954624712 -0.0182589926 1560 1311867770.6699299812 0.2312724590 0.2273238037 0.3266084492 0.0043371351 0.1541710000 981057753 0 402718720 -0.2443839759 -0.0957434028 -0.0180175751 1561 1311867770.7014191151 0.2316431701 0.2273265707 0.3266084492 0.0043358702 0.1695750000 981060657 0 402718720 -0.2444070429 -0.0961773843 -0.0177077446 1562 1311867770.7347331047 0.2314170748 0.2273291895 0.3266084492 0.0043347967 0.1537520000 981063617 0 402718720 -0.2440688014 -0.0955815911 -0.0174432732 1563 1311867770.7684218884 0.2316042632 0.2273319247 0.3266084492 0.0043335128 0.1555340000 981066521 0 402718720 -0.2440996319 -0.0957397595 -0.0171935521 1564 1311867770.8017508984 0.2318000793 0.2273347815 0.3266084492 0.0043321364 0.1546260000 981069425 0 402718720 -0.2440998256 -0.0965335816 -0.0168713182 1565 1311867770.8396499157 0.2307677418 0.2273369751 0.3266084492 0.0043313947 0.1547560000 981072553 0 402718720 -0.2429421693 -0.0958273336 -0.0166826583 1566 1311867770.8699400425 0.2304251790 0.2273389471 0.3266084492 0.0043306552 0.1874040000 981075401 0 402718720 -0.2424183786 -0.0959736332 -0.0163931623 1567 1311867770.9027009010 0.2304337919 0.2273409222 0.3266084492 0.0043296222 0.1566400000 981078305 0 402718720 -0.2423241138 -0.0961800292 -0.0162642542 1568 1311867770.9355690479 0.2298446298 0.2273425189 0.3266084492 0.0043293482 0.1562430000 981081265 0 402718720 -0.2418751717 -0.0952503681 -0.0159187447 1569 1311867770.9692869186 0.2301528454 0.2273443101 0.3266084492 0.0043285516 0.1576950000 981084225 0 402718720 -0.2420120537 -0.0952591896 -0.0156364311 1570 1311867771.0021619797 0.2303342372 0.2273462145 0.3266084492 0.0043296432 0.1564930000 981087129 0 402718720 -0.2421117425 -0.0954484791 -0.0153900813 1571 1311867771.0365509987 0.2303185314 0.2273481065 0.3266084492 0.0043391761 0.1650140000 981090033 0 402718720 -0.2424627095 -0.0945106000 -0.0150209786 1572 1311867771.0685739517 0.2298957109 0.2273497271 0.3266084492 0.0043380458 0.1576390000 981092993 0 402718720 -0.2422023267 -0.0936109200 -0.0147978198 1573 1311867771.1014111042 0.2290699035 0.2273508207 0.3266084492 0.0043406566 0.1577440000 981095953 0 402718720 -0.2412198931 -0.0937423408 -0.0145817120 1574 1311867771.1381099224 0.2283548564 0.2273514585 0.3266084492 0.0043395159 0.1581160000 981098969 0 402718720 -0.2403823733 -0.0934623480 -0.0144055886 1575 1311867771.1686840057 0.2279964834 0.2273518681 0.3266084492 0.0043382392 0.1623570000 981101817 0 402718720 -0.2399400324 -0.0932630301 -0.0141087519 1576 1311867771.2019159794 0.2282408029 0.2273524321 0.3266084492 0.0043369919 0.1637000000 981104721 0 402718720 -0.2399269640 -0.0937618613 -0.0139549384 1577 1311867771.2363801003 0.2279876769 0.2273528349 0.3266084492 0.0043356710 0.1639910000 981107681 0 402718720 -0.2394409925 -0.0935896114 -0.0137931230 1578 1311867771.2705540657 0.2281487882 0.2273533393 0.3266084492 0.0043345824 0.1649580000 981110697 0 402718720 -0.2392729074 -0.0931353122 -0.0135652479 1579 1311867771.3016860485 0.2280290127 0.2273537673 0.3266084492 0.0043332790 0.1647980000 981113545 0 402718720 -0.2389185429 -0.0930550545 -0.0132338842 1580 1311867771.3360719681 0.2282029688 0.2273543047 0.3266084492 0.0043319220 0.1652610000 981116505 0 402718720 -0.2386706769 -0.0932800099 -0.0131161259 1581 1311867771.3679900169 0.2276443690 0.2273544882 0.3266084492 0.0043305880 0.1787380000 981119409 0 402718720 -0.2379622012 -0.0927387327 -0.0130915260 1582 1311867771.4030399323 0.2263521403 0.2273538546 0.3266084492 0.0043293444 0.1671680000 981122369 0 402718720 -0.2364781499 -0.0917522386 -0.0130792605 1583 1311867771.4361710548 0.2265813947 0.2273533666 0.3266084492 0.0043282171 0.1677580000 981125329 0 402718720 -0.2363212705 -0.0922314972 -0.0129974820 1584 1311867771.4682569504 0.2264649272 0.2273528057 0.3266084492 0.0043268911 0.1679320000 981128233 0 402718720 -0.2358743250 -0.0917566270 -0.0127153406 1585 1311867771.5008640289 0.2255522013 0.2273516697 0.3266084492 0.0043259385 0.1816530000 981131137 0 402718720 -0.2346837223 -0.0906981379 -0.0125087705 1586 1311867771.5365910530 0.2241160572 0.2273496296 0.3266084492 0.0043248046 0.1799340000 981134153 0 402718720 -0.2327725738 -0.0904563367 -0.0126392487 1587 1311867771.5686171055 0.2235945165 0.2273472634 0.3266084492 0.0043235490 0.1691690000 981137113 0 402718720 -0.2318754196 -0.0906735435 -0.0126648434 1588 1311867771.6077210903 0.2235080451 0.2273448458 0.3266084492 0.0043234944 0.1702990000 981140185 0 402718720 -0.2312927842 -0.0903271511 -0.0122948438 1589 1311867771.6366779804 0.2225205898 0.2273418098 0.3266084492 0.0043222024 0.1708350000 981142977 0 402718720 -0.2300426811 -0.0902385414 -0.0122526130 1590 1311867771.6715440750 0.2219562680 0.2273384226 0.3266084492 0.0043213382 0.1705310000 981145993 0 402718720 -0.2291084975 -0.0907350257 -0.0120190922 1591 1311867771.7024850845 0.2216810733 0.2273348668 0.3266084492 0.0043207069 0.1871610000 981148897 0 402718720 -0.2285111845 -0.0900951549 -0.0114383232 1592 1311867771.7367300987 0.2210264504 0.2273309042 0.3266084492 0.0043200743 0.1724490000 981151801 0 402718720 -0.2274309248 -0.0896683261 -0.0112351971 1593 1311867771.7697410583 0.2210112065 0.2273269370 0.3266084492 0.0043195635 0.1716830000 981154761 0 402718720 -0.2268655151 -0.0901677385 -0.0110329026 1594 1311867771.8023030758 0.2207979858 0.2273228411 0.3266084492 0.0043182874 0.1847320000 981157665 0 402718720 -0.2259624451 -0.0899377763 -0.0108063053 1595 1311867771.8386220932 0.2210937291 0.2273189357 0.3266084492 0.0043174800 0.1726050000 981160737 0 402718720 -0.2258638740 -0.0898166746 -0.0105696404 1596 1311867771.8711829185 0.2213883549 0.2273152198 0.3266084492 0.0043161956 0.2037890000 981163585 0 402718720 -0.2256435454 -0.0904026106 -0.0104772933 1597 1311867771.9016489983 0.2207898051 0.2273111337 0.3266084492 0.0043150384 0.1725610000 981166489 0 402718720 -0.2245103866 -0.0910217687 -0.0107675036 1598 1311867771.9377520084 0.2210394591 0.2273072090 0.3266084492 0.0043143011 0.1723640000 981169505 0 402718720 -0.2242271006 -0.0909398049 -0.0107276943 1599 1311867771.9696009159 0.2201482952 0.2273027319 0.3266084492 0.0043134108 0.1709700000 981172409 0 402718720 -0.2228928506 -0.0908842385 -0.0110399341 1600 1311867772.0018649101 0.2199975550 0.2272981662 0.3266084492 0.0043124744 0.1726750000 981175369 0 402718720 -0.2223466784 -0.0909018889 -0.0112593733 1601 1311867772.0375399590 0.2205809206 0.2272939705 0.3266084492 0.0043119164 0.1870320000 981178329 0 402718720 -0.2226682156 -0.0905041769 -0.0109661259 1602 1311867772.0696671009 0.2207979411 0.2272899156 0.3266084492 0.0043105860 0.1725120000 981181289 0 402718720 -0.2227530330 -0.0904241949 -0.0109227980 1603 1311867772.1012299061 0.2204569429 0.2272856530 0.3266084492 0.0043095931 0.1722530000 981184137 0 402718720 -0.2223072946 -0.0902940035 -0.0110872881 1604 1311867772.1369819641 0.2208165675 0.2272816199 0.3266084492 0.0043083621 0.1718280000 981187041 0 402718720 -0.2225482911 -0.0901974663 -0.0108476616 1605 1311867772.1690549850 0.2212206721 0.2272778436 0.3266084492 0.0043070543 0.1720150000 981190001 0 402718720 -0.2228598595 -0.0899231285 -0.0104952790 1606 1311867772.2016880512 0.2208425552 0.2272738365 0.3266084492 0.0043058133 0.1817740000 981192961 0 402718720 -0.2222700566 -0.0899773687 -0.0103855049 1607 1311867772.2370250225 0.2208814472 0.2272698587 0.3266084492 0.0043046396 0.1838400000 981195865 0 402718720 -0.2221183181 -0.0904528648 -0.0103857592 1608 1311867772.2710011005 0.2206093371 0.2272657166 0.3266084492 0.0043035418 0.1712660000 981198881 0 402718720 -0.2217515707 -0.0903506875 -0.0101094600 1609 1311867772.3046050072 0.2204942703 0.2272615081 0.3266084492 0.0043022362 0.1712490000 981201841 0 402718720 -0.2216745317 -0.0900773704 -0.0101198331 1610 1311867772.3366808891 0.2205530703 0.2272573414 0.3266084492 0.0043010806 0.1837750000 981204689 0 402718720 -0.2217597365 -0.0906507000 -0.0101634273 1611 1311867772.3689630032 0.2207276970 0.2272532882 0.3266084492 0.0042997969 0.1972860000 981207649 0 402718720 -0.2220918387 -0.0907827243 -0.0100516826 1612 1311867772.4054839611 0.2210421711 0.2272494352 0.3266084492 0.0042987694 0.1713980000 981210721 0 402718720 -0.2224518508 -0.0907623842 -0.0096862596 1613 1311867772.4385271072 0.2210683078 0.2272456031 0.3266084492 0.0042975382 0.1710590000 981213625 0 402718720 -0.2227870673 -0.0908710584 -0.0096502993 1614 1311867772.4697830677 0.2214730680 0.2272420266 0.3266084492 0.0042962294 0.1710680000 981216473 0 402718720 -0.2232626230 -0.0915737748 -0.0095861405 1615 1311867772.5049729347 0.2210853100 0.2272382143 0.3266084492 0.0042951948 0.1708780000 981219489 0 402718720 -0.2232216746 -0.0915283412 -0.0095241778 1616 1311867772.5382430553 0.2203890383 0.2272339760 0.3266084492 0.0042941741 0.1901270000 981222393 0 402718720 -0.2228881419 -0.0912820771 -0.0095933657 1617 1311867772.5713028908 0.2204246819 0.2272297649 0.3266084492 0.0042935145 0.1710350000 981225353 0 402718720 -0.2231845111 -0.0911096558 -0.0096002668 1618 1311867772.6077790260 0.2204185575 0.2272255553 0.3266084492 0.0042932654 0.1822360000 981228313 0 402718720 -0.2236279696 -0.0909928530 -0.0093560601 1619 1311867772.6382429600 0.2197028548 0.2272209088 0.3266084492 0.0042920147 0.1710640000 981231161 0 402718720 -0.2231727988 -0.0907809287 -0.0093225231 1620 1311867772.6695280075 0.2190715969 0.2272158783 0.3266084492 0.0042917327 0.1705450000 981234065 0 402718720 -0.2227999866 -0.0910945013 -0.0092854388 1621 1311867772.7066609859 0.2190125734 0.2272108177 0.3266084492 0.0042905165 0.1803510000 981237081 0 402718720 -0.2228021920 -0.0912643299 -0.0091639534 1622 1311867772.7385280132 0.2189957350 0.2272057529 0.3266084492 0.0042892270 0.1842990000 981239985 0 402718720 -0.2228827924 -0.0910585523 -0.0089181839 1623 1311867772.7712020874 0.2191703618 0.2272008020 0.3266084492 0.0042880140 0.1711220000 981242945 0 402718720 -0.2230466902 -0.0916453078 -0.0086702481 1624 1311867772.8056819439 0.2191431671 0.2271958404 0.3266084492 0.0042871071 0.1719380000 981245961 0 402718720 -0.2230121046 -0.0920017436 -0.0082813716 1625 1311867772.8384070396 0.2188031971 0.2271906757 0.3266084492 0.0042859896 0.1912210000 981248809 0 402718720 -0.2226631641 -0.0916261375 -0.0078256335 1626 1311867772.8747529984 0.2182438374 0.2271851733 0.3266084492 0.0042847836 0.1915710000 981251881 0 402718720 -0.2219458818 -0.0918735638 -0.0076778815 1627 1311867772.9054989815 0.2180601358 0.2271795648 0.3266084492 0.0042836811 0.1708440000 981254729 0 402718720 -0.2215721160 -0.0923691317 -0.0076129013 1628 1311867772.9415910244 0.2177788615 0.2271737904 0.3266084492 0.0042833187 0.1706820000 981257689 0 402718720 -0.2209898531 -0.0922745541 -0.0074351546 1629 1311867772.9716000557 0.2177471817 0.2271680037 0.3266084492 0.0042821013 0.1712490000 981260537 0 402718720 -0.2206778824 -0.0922098085 -0.0071507497 1630 1311867773.0115981102 0.2177308798 0.2271622140 0.3266084492 0.0042811172 0.1713290000 981263609 0 402718720 -0.2202836573 -0.0926628634 -0.0072565726 1631 1311867773.0406711102 0.2175473571 0.2271563189 0.3266084492 0.0042801999 0.2013150000 981266457 0 402718720 -0.2198839784 -0.0924522653 -0.0069928989 1632 1311867773.0706710815 0.2175170630 0.2271504125 0.3266084492 0.0042789313 0.1705280000 981269249 0 402718720 -0.2196853757 -0.0921728536 -0.0066345418 1633 1311867773.1044468880 0.2173777670 0.2271444281 0.3266084492 0.0042784328 0.1703650000 981272209 0 402718720 -0.2191357464 -0.0930496082 -0.0065249936 1634 1311867773.1367809772 0.2175486088 0.2271385555 0.3266084492 0.0042774709 0.1702350000 981275113 0 402718720 -0.2187534273 -0.0940435603 -0.0062263575 1635 1311867773.1702499390 0.2175941020 0.2271327179 0.3266084492 0.0042764399 0.1703670000 981278073 0 402718720 -0.2185155302 -0.0940961465 -0.0058583901 1636 1311867773.2047750950 0.2172871530 0.2271266998 0.3266084492 0.0042751684 0.1805040000 981281033 0 402718720 -0.2180795074 -0.0939986333 -0.0057501504 1637 1311867773.2366468906 0.2174357176 0.2271207798 0.3266084492 0.0042740593 0.1692770000 981283937 0 402718720 -0.2179338336 -0.0940013453 -0.0052781082 1638 1311867773.2714850903 0.2167480290 0.2271144473 0.3266084492 0.0042732541 0.1703410000 981286953 0 402718720 -0.2172341645 -0.0936072990 -0.0049849064 1639 1311867773.3104391098 0.2164804339 0.2271079592 0.3266084492 0.0042728698 0.1678030000 981290025 0 402718720 -0.2165855169 -0.0936555490 -0.0046252524 1640 1311867773.3365778923 0.2186598331 0.2271028079 0.3266084492 0.0042718732 0.1685230000 981292705 0 402718720 -0.2187108994 -0.0937486514 -0.0039414829 1641 1311867773.3720550537 0.2190901339 0.2270979251 0.3266084492 0.0042708395 0.1989580000 981295721 0 402718720 -0.2189052701 -0.0942506045 -0.0036592593 1642 1311867773.4075679779 0.2190645039 0.2270930326 0.3266084492 0.0042703976 0.1684950000 981298681 0 402718720 -0.2185768336 -0.0941957906 -0.0032637708 1643 1311867773.4431231022 0.2192247361 0.2270882436 0.3266084492 0.0042702893 0.1673440000 981301697 0 402718720 -0.2185251564 -0.0941904336 -0.0028437474 1644 1311867773.4752271175 0.2194306254 0.2270835857 0.3266084492 0.0042696284 0.1667800000 981304601 0 402718720 -0.2183117121 -0.0949684903 -0.0024856075 1645 1311867773.5056390762 0.2191112936 0.2270787393 0.3266084492 0.0042686829 0.1673590000 981307449 0 402718720 -0.2175678909 -0.0952084735 -0.0022019383 1646 1311867773.5412580967 0.2186423689 0.2270736139 0.3266084492 0.0042676013 0.1762900000 981310465 0 402718720 -0.2168181986 -0.0948579088 -0.0017526633 1647 1311867773.5752460957 0.2183833122 0.2270683375 0.3266084492 0.0042666942 0.1791600000 981313425 0 402718720 -0.2163676471 -0.0952902734 -0.0014854724 1648 1311867773.6103789806 0.2183022797 0.2270630183 0.3266084492 0.0042656594 0.1660320000 981316441 0 402718720 -0.2158097029 -0.0957815424 -0.0012696752 1649 1311867773.6384060383 0.2178632766 0.2270574393 0.3266084492 0.0042661239 0.1655400000 981319177 0 402718720 -0.2151229531 -0.0952981189 -0.0008862010 1650 1311867773.6767098904 0.2176495194 0.2270517375 0.3266084492 0.0042673674 0.1651170000 981322249 0 402718720 -0.2148328871 -0.0951553956 -0.0007934557 1651 1311867773.7092239857 0.2180488110 0.2270462845 0.3266084492 0.0042662001 0.1930270000 981325153 0 402718720 -0.2149412483 -0.0955170989 -0.0005747059 1652 1311867773.7367770672 0.2180292308 0.2270408263 0.3266084492 0.0042652447 0.1649430000 981327889 0 402718720 -0.2148183882 -0.0955091417 -0.0001152472 1653 1311867773.7767388821 0.2170898914 0.2270348063 0.3266084492 0.0042647159 0.1638510000 981331017 0 402718720 -0.2136677355 -0.0951766223 0.0000796666 1654 1311867773.8052179813 0.2165625840 0.2270284749 0.3266084492 0.0042647054 0.1827520000 981333809 0 402718720 -0.2131674737 -0.0955020860 0.0001544856 1655 1311867773.8394160271 0.2163610607 0.2270220293 0.3266084492 0.0042639418 0.1639420000 981336769 0 402718720 -0.2128611952 -0.0963707492 0.0003511956 1656 1311867773.8739800453 0.2161036581 0.2270154361 0.3266084492 0.0042629274 0.1830490000 981339729 0 402718720 -0.2125971019 -0.0970262215 0.0005865469 1657 1311867773.9096889496 0.2152231038 0.2270083194 0.3266084492 0.0042622034 0.1767690000 981342745 0 402718720 -0.2115855068 -0.0972446650 0.0007825278 1658 1311867773.9369859695 0.2150583714 0.2270011120 0.3266084492 0.0042614118 0.1640750000 981345481 0 402718720 -0.2113523632 -0.0974930152 0.0008643065 1659 1311867773.9740200043 0.2148901522 0.2269938118 0.3266084492 0.0042602869 0.1764010000 981348553 0 402718720 -0.2110828012 -0.0976384580 0.0012041221 1660 1311867774.0073120594 0.2153580636 0.2269868023 0.3266084492 0.0042604276 0.1627830000 981351457 0 402718720 -0.2111300230 -0.0980235860 0.0013706123 1661 1311867774.0389740467 0.2153792381 0.2269798140 0.3266084492 0.0042624161 0.1797690000 981354417 0 402718720 -0.2111266106 -0.0985999554 0.0016265101 1662 1311867774.0735630989 0.2157968581 0.2269730854 0.3266084492 0.0042634673 0.1631600000 981357377 0 402718720 -0.2109865099 -0.0985735580 0.0018117815 1663 1311867774.1093399525 0.2160069942 0.2269664913 0.3266084492 0.0042670044 0.1629040000 981360393 0 402718720 -0.2112176716 -0.0983141884 0.0020676025 1664 1311867774.1424911022 0.2165090144 0.2269602067 0.3266084492 0.0042680846 0.1627510000 981363353 0 402718720 -0.2114194334 -0.0989870280 0.0022176022 1665 1311867774.1754300594 0.2162386775 0.2269537674 0.3266084492 0.0042685748 0.1739940000 981366257 0 402718720 -0.2109674364 -0.0991778448 0.0026380382 1666 1311867774.2059481144 0.2160450518 0.2269472195 0.3266084492 0.0042673749 0.1868560000 981369161 0 402718720 -0.2105100602 -0.0988858566 0.0030609847 1667 1311867774.2384989262 0.2158100903 0.2269405386 0.3266084492 0.0042662429 0.1619400000 981372009 0 402718720 -0.2101092339 -0.0990630388 0.0034264438 1668 1311867774.2744109631 0.2156576812 0.2269337743 0.3266084492 0.0042651166 0.1624320000 981375081 0 402718720 -0.2097099870 -0.0996106490 0.0036531666 1669 1311867774.3046739101 0.2158154696 0.2269271126 0.3266084492 0.0042642272 0.1613540000 981377929 0 402718720 -0.2096538246 -0.0995488986 0.0042164889 1670 1311867774.3375370502 0.2152079046 0.2269200951 0.3266084492 0.0042630183 0.1603990000 981380833 0 402718720 -0.2089920640 -0.0990182087 0.0044279103 1671 1311867774.3727159500 0.2149410099 0.2269129263 0.3266084492 0.0042618585 0.1716500000 981383793 0 402718720 -0.2084164023 -0.0996643677 0.0046221814 1672 1311867774.4051818848 0.2144955099 0.2269054996 0.3266084492 0.0042613245 0.1705100000 981386753 0 402718720 -0.2077029496 -0.0998410657 0.0051245266 1673 1311867774.4376831055 0.2139991820 0.2268977852 0.3266084492 0.0042603885 0.1586710000 981389657 0 402718720 -0.2071323991 -0.0994668230 0.0054346444 1674 1311867774.4740140438 0.2136439830 0.2268898677 0.3266084492 0.0042601729 0.1585310000 981392673 0 402718720 -0.2067366540 -0.0999742746 0.0055428967 1675 1311867774.5066258907 0.2137261778 0.2268820088 0.3266084492 0.0042589916 0.1580620000 981395633 0 402718720 -0.2067041099 -0.1007054523 0.0057986388 1676 1311867774.5394051075 0.2132646143 0.2268738839 0.3266084492 0.0042579363 0.1843950000 981398537 0 402718720 -0.2062644511 -0.1007433981 0.0059966333 1677 1311867774.5727870464 0.2129853517 0.2268656021 0.3266084492 0.0042573139 0.1582490000 981401441 0 402718720 -0.2058200538 -0.1007673368 0.0065328642 1678 1311867774.6076970100 0.2127502859 0.2268571901 0.3266084492 0.0042562395 0.1571210000 981404457 0 402718720 -0.2055184543 -0.1005846560 0.0067846021 1679 1311867774.6373310089 0.2129417807 0.2268489022 0.3266084492 0.0042552517 0.1565430000 981407305 0 402718720 -0.2056340128 -0.1003474742 0.0070827520 1680 1311867774.6731650829 0.2127644271 0.2268405186 0.3266084492 0.0042542368 0.1559990000 981410265 0 402718720 -0.2054339796 -0.1001357138 0.0074491529 1681 1311867774.7048470974 0.2130256593 0.2268323003 0.3266084492 0.0042531083 0.1678050000 981413225 0 402718720 -0.2053215802 -0.1004463956 0.0076344279 1682 1311867774.7448370457 0.2133954018 0.2268243117 0.3266084492 0.0042546858 0.1543090000 981416353 0 402718720 -0.2053627223 -0.1000609323 0.0080694286 1683 1311867774.7731618881 0.2134813964 0.2268163836 0.3266084492 0.0042534769 0.1652870000 981419089 0 402718720 -0.2053188831 -0.0998086855 0.0084974058 1684 1311867774.8052101135 0.2134556174 0.2268084497 0.3266084492 0.0042530446 0.1720610000 981422049 0 402718720 -0.2050431520 -0.1001620591 0.0088951346 1685 1311867774.8443410397 0.2133047134 0.2268004356 0.3266084492 0.0042518571 0.1533330000 981425121 0 402718720 -0.2045909613 -0.1003249735 0.0092723351 1686 1311867774.8735189438 0.2135600448 0.2267925825 0.3266084492 0.0042511170 0.1527050000 981427969 0 402718720 -0.2045079917 -0.1006268188 0.0097589120 1687 1311867774.9063620567 0.2137295902 0.2267848391 0.3266084492 0.0042502807 0.1525430000 981430873 0 402718720 -0.2043770999 -0.1009966955 0.0101040816 1688 1311867774.9433379173 0.2139056921 0.2267772093 0.3266084492 0.0042490336 0.1509180000 981433945 0 402718720 -0.2041405290 -0.1011999249 0.0103969416 1689 1311867774.9730870724 0.2138065100 0.2267695298 0.3266084492 0.0042478213 0.1513520000 981436737 0 402718720 -0.2038288265 -0.1011335403 0.0106851049 1690 1311867775.0104990005 0.2143143862 0.2267621599 0.3266084492 0.0042465897 0.1510950000 981439865 0 402718720 -0.2041171342 -0.1012972146 0.0109434221 1691 1311867775.0417571068 0.2140687704 0.2267546534 0.3266084492 0.0042453448 0.1570980000 981442713 0 402718720 -0.2038453370 -0.1011706218 0.0111278379 1692 1311867775.0737869740 0.2138313055 0.2267470155 0.3266084492 0.0042444769 0.1508180000 981445617 0 402718720 -0.2034722716 -0.1007102653 0.0113141462 1693 1311867775.1060369015 0.2139200568 0.2267394391 0.3266084492 0.0042434733 0.1498670000 981448521 0 402718720 -0.2035589367 -0.1006449312 0.0113897994 1694 1311867775.1426749229 0.2145293951 0.2267322312 0.3266084492 0.0042422405 0.1498240000 981451537 0 402718720 -0.2038645446 -0.1011574864 0.0116333654 1695 1311867775.1733469963 0.2144761682 0.2267250005 0.3266084492 0.0042411076 0.1496790000 981454385 0 402718720 -0.2037354857 -0.1012461632 0.0118668051 1696 1311867775.2047309875 0.2143926919 0.2267177291 0.3266084492 0.0042399092 0.1705200000 981457345 0 402718720 -0.2036318034 -0.1011989266 0.0118620573 1697 1311867775.2407341003 0.2140787542 0.2267102813 0.3266084492 0.0042394236 0.1495560000 981460361 0 402718720 -0.2033208162 -0.1008934081 0.0119006624 1698 1311867775.2726259232 0.2140996009 0.2267028545 0.3266084492 0.0042387347 0.1497130000 981463209 0 402718720 -0.2034298480 -0.1007369682 0.0120589836 1699 1311867775.3058989048 0.2140586674 0.2266954124 0.3266084492 0.0042376776 0.1496820000 981466169 0 402718720 -0.2032236457 -0.1009855121 0.0121308798 1700 1311867775.3405869007 0.2141926587 0.2266880578 0.3266084492 0.0042383653 0.1485520000 981469185 0 402718720 -0.2031423002 -0.1005615294 0.0123696728 1701 1311867775.3728890419 0.2138999104 0.2266805398 0.3266084492 0.0042388140 0.1586060000 981472145 0 402718720 -0.2029242814 -0.1002581343 0.0123573616 1702 1311867775.4055740833 0.2149033248 0.2266736201 0.3266084492 0.0042383673 0.1480170000 981475049 0 402718720 -0.2035558969 -0.1009297445 0.0128852166 1703 1311867775.4408710003 0.2147972733 0.2266666464 0.3266084492 0.0042388822 0.1605310000 981478065 0 402718720 -0.2030541450 -0.1009166241 0.0130628450 1704 1311867775.4725620747 0.2143923640 0.2266594432 0.3266084492 0.0042386640 0.1469710000 981480913 0 402718720 -0.2027363330 -0.1006596386 0.0131792473 1705 1311867775.5057229996 0.2146244943 0.2266523845 0.3266084492 0.0042376812 0.1473390000 981483929 0 402718720 -0.2028476298 -0.1006063372 0.0134883346 1706 1311867775.5413000584 0.2146271616 0.2266453357 0.3266084492 0.0042371858 0.1595580000 981486945 0 402718720 -0.2027379870 -0.1007907242 0.0136230355 1707 1311867775.5736858845 0.2143058479 0.2266381070 0.3266084492 0.0042361095 0.1462230000 981489793 0 402718720 -0.2022029608 -0.1006689519 0.0138671994 1708 1311867775.6086819172 0.2145565003 0.2266310335 0.3266084492 0.0042352284 0.1463650000 981492753 0 402718720 -0.2022362798 -0.1006012484 0.0139280008 1709 1311867775.6414420605 0.2148300111 0.2266241282 0.3266084492 0.0042340163 0.1456740000 981495769 0 402718720 -0.2022284716 -0.1007833108 0.0141117079 1710 1311867775.6726739407 0.2149418890 0.2266172965 0.3266084492 0.0042330656 0.1456050000 981498561 0 402718720 -0.2023091316 -0.1005510166 0.0142583549 1711 1311867775.7051100731 0.2146385610 0.2266102955 0.3266084492 0.0042319705 0.1460380000 981501521 0 402718720 -0.2019050568 -0.1003968045 0.0142557966 1712 1311867775.7416241169 0.2146025896 0.2266032817 0.3266084492 0.0042308203 0.1450430000 981504537 0 402718720 -0.2016575933 -0.1005084813 0.0146410847 1713 1311867775.7742578983 0.2149481326 0.2265964777 0.3266084492 0.0042304816 0.1571560000 981507441 0 402718720 -0.2018374652 -0.1005171016 0.0151454993 1714 1311867775.8062939644 0.2141932249 0.2265892413 0.3266084492 0.0042297068 0.1446600000 981510345 0 402718720 -0.2009891868 -0.1001103222 0.0151078701 1715 1311867775.8408269882 0.2144909501 0.2265821869 0.3266084492 0.0042285477 0.1439730000 981513361 0 402718720 -0.2010734230 -0.1000143364 0.0152791003 1716 1311867775.8729701042 0.2144535035 0.2265751189 0.3266084492 0.0042274608 0.1637580000 981516209 0 402718720 -0.2008163035 -0.1000698656 0.0156374983 1717 1311867775.9066479206 0.2146481723 0.2265681725 0.3266084492 0.0042262601 0.1450400000 981519225 0 402718720 -0.2009468973 -0.1000555605 0.0158274323 1718 1311867775.9435749054 0.2146455646 0.2265612327 0.3266084492 0.0042252736 0.1447510000 981522185 0 402718720 -0.2007769495 -0.1000415385 0.0160699226 1719 1311867775.9730579853 0.2145759612 0.2265542604 0.3266084492 0.0042244072 0.1437790000 981525033 0 402718720 -0.2004383504 -0.0999159589 0.0161922760 1720 1311867776.0135231018 0.2153220177 0.2265477301 0.3266084492 0.0042234077 0.1437410000 981528161 0 402718720 -0.2008339465 -0.1004715860 0.0164105985 1721 1311867776.0423479080 0.2149825692 0.2265410100 0.3266084492 0.0042225173 0.1552210000 981530897 0 402718720 -0.2002940029 -0.1004996225 0.0164526105 1722 1311867776.0782909393 0.2150192857 0.2265343191 0.3266084492 0.0042213184 0.1438820000 981533969 0 402718720 -0.2000784725 -0.1005688310 0.0165637266 1723 1311867776.1090068817 0.2150494903 0.2265276535 0.3266084492 0.0042204916 0.1427560000 981536873 0 402718720 -0.1999135911 -0.1004383639 0.0167261716 1724 1311867776.1410119534 0.2153583765 0.2265211748 0.3266084492 0.0042193454 0.1440970000 981539777 0 402718720 -0.2002010942 -0.1002972424 0.0169505049 1725 1311867776.1773319244 0.2153899074 0.2265147219 0.3266084492 0.0042182652 0.1434860000 981542793 0 402718720 -0.2001612335 -0.1002797410 0.0170402229 1726 1311867776.2094259262 0.2154724151 0.2265083243 0.3266084492 0.0042170452 0.1603290000 981545697 0 402718720 -0.2001281977 -0.1000523195 0.0170196239 1727 1311867776.2407069206 0.2154174745 0.2265019023 0.3266084492 0.0042159896 0.1433200000 981548601 0 402718720 -0.2000696063 -0.0999730155 0.0170226637 1728 1311867776.2753469944 0.2159868926 0.2264958172 0.3266084492 0.0042149074 0.1438420000 981551617 0 402718720 -0.2005870342 -0.0998487473 0.0171336588 1729 1311867776.3120670319 0.2164023817 0.2264899795 0.3266084492 0.0042137453 0.1429480000 981554577 0 402718720 -0.2008259892 -0.0998559669 0.0172784794 1730 1311867776.3407590389 0.2165314257 0.2264842231 0.3266084492 0.0042126419 0.1429910000 981557481 0 402718720 -0.2009160072 -0.0997920111 0.0173973572 1731 1311867776.3730750084 0.2161174268 0.2264782342 0.3266084492 0.0042114562 0.1435660000 981560385 0 402718720 -0.2004052848 -0.0997792184 0.0175002757 1732 1311867776.4097070694 0.2160760611 0.2264722283 0.3266084492 0.0042103666 0.1423930000 981563457 0 402718720 -0.2002767622 -0.0996475816 0.0175851975 1733 1311867776.4422268867 0.2157714814 0.2264660536 0.3266084492 0.0042093967 0.1423720000 981566361 0 402718720 -0.1998982430 -0.0993041918 0.0175940134 1734 1311867776.4727520943 0.2160854936 0.2264600671 0.3266084492 0.0042082015 0.1423810000 981569209 0 402718720 -0.2002466321 -0.0992152467 0.0177118499 1735 1311867776.5105879307 0.2155523598 0.2264537803 0.3266084492 0.0042070922 0.1421230000 981572281 0 402718720 -0.1996150464 -0.0989918634 0.0177306291 1736 1311867776.5415630341 0.2155791223 0.2264475161 0.3266084492 0.0042059900 0.1710790000 981575129 0 402718720 -0.1996081471 -0.0987682641 0.0180742592 1737 1311867776.5743160248 0.2151537091 0.2264410142 0.3266084492 0.0042048193 0.1424840000 981578089 0 402718720 -0.1990531981 -0.0985937491 0.0182298087 1738 1311867776.6094930172 0.2152968943 0.2264346021 0.3266084492 0.0042036298 0.1426730000 981581105 0 402718720 -0.1990808547 -0.0984287634 0.0185255650 1739 1311867776.6413109303 0.2154870182 0.2264283068 0.3266084492 0.0042024292 0.1550050000 981584009 0 402718720 -0.1990261972 -0.0985466465 0.0190370101 1740 1311867776.6763460636 0.2154565156 0.2264220012 0.3266084492 0.0042012570 0.1406650000 981587081 0 402718720 -0.1988056153 -0.0985130891 0.0194283687 1741 1311867776.7134280205 0.2148430198 0.2264153504 0.3266084492 0.0042001616 0.1526380000 981590097 0 402718720 -0.1979886442 -0.0982090905 0.0196105149 1742 1311867776.7423970699 0.2145038396 0.2264085126 0.3266084492 0.0041993441 0.1412420000 981592889 0 402718720 -0.1977091283 -0.0979997367 0.0197987743 1743 1311867776.7739920616 0.2141192257 0.2264014619 0.3266084492 0.0041984552 0.1413310000 981595905 0 402718720 -0.1970686316 -0.0981726721 0.0200197026 1744 1311867776.8117430210 0.2139962614 0.2263943488 0.3266084492 0.0041983706 0.1411310000 981599033 0 402718720 -0.1967693865 -0.0981194228 0.0203027818 1745 1311867776.8449618816 0.2142682225 0.2263873998 0.3266084492 0.0041975511 0.1409470000 981602049 0 402718720 -0.1967288703 -0.0981161147 0.0205744952 1746 1311867776.8748989105 0.2144047022 0.2263805368 0.3266084492 0.0041964265 0.1600670000 981604897 0 402718720 -0.1966878474 -0.0982324705 0.0210071635 1747 1311867776.9104089737 0.2139733881 0.2263734348 0.3266084492 0.0041955159 0.1414360000 981607913 0 402718720 -0.1961008906 -0.0981176794 0.0213063676 1748 1311867776.9465129375 0.2135840654 0.2263661183 0.3266084492 0.0041944484 0.1407350000 981610985 0 402718720 -0.1955670416 -0.0980699658 0.0215237290 1749 1311867776.9780058861 0.2135196477 0.2263587732 0.3266084492 0.0041942921 0.1410550000 981613889 0 402718720 -0.1954214871 -0.0980641395 0.0217522774 1750 1311867777.0103049278 0.2136764675 0.2263515262 0.3266084492 0.0041936872 0.1422890000 981616905 0 402718720 -0.1954665780 -0.0979911312 0.0222520437 1751 1311867777.0430829525 0.2140087783 0.2263444772 0.3266084492 0.0041924935 0.1451610000 981619865 0 402718720 -0.1957493573 -0.0979822353 0.0224635601 1752 1311867777.0763421059 0.2136667967 0.2263372411 0.3266084492 0.0041915519 0.1429190000 981622825 0 402718720 -0.1952538192 -0.0981021225 0.0227307193 1753 1311867777.1087210178 0.2138113081 0.2263300957 0.3266084492 0.0041903892 0.1422620000 981625785 0 402718720 -0.1952899247 -0.0981952250 0.0230731759 1754 1311867777.1435770988 0.2139422894 0.2263230331 0.3266084492 0.0041892069 0.1423170000 981628857 0 402718720 -0.1953908652 -0.0980833545 0.0233715549 1755 1311867777.1783010960 0.2142459154 0.2263161515 0.3266084492 0.0041880253 0.1420840000 981631873 0 402718720 -0.1954648644 -0.0979567766 0.0238080658 1756 1311867777.2115299702 0.2144691944 0.2263094050 0.3266084492 0.0041868565 0.1623330000 981634945 0 402718720 -0.1957228929 -0.0979518443 0.0240468737 1757 1311867777.2420690060 0.2140131444 0.2263024065 0.3266084492 0.0041857353 0.1422330000 981637737 0 402718720 -0.1950060725 -0.0979835391 0.0243253224 1758 1311867777.2766950130 0.2134709507 0.2262951076 0.3266084492 0.0041848550 0.1421240000 981640753 0 402718720 -0.1944171190 -0.0979008675 0.0244082492 1759 1311867777.3093490601 0.2135752589 0.2262878763 0.3266084492 0.0041848062 0.1424540000 981643713 0 402718720 -0.1944035441 -0.0979681090 0.0248232521 1760 1311867777.3419890404 0.2133627683 0.2262805325 0.3266084492 0.0041836342 0.1414350000 981646673 0 402718720 -0.1942488402 -0.0981801823 0.0250724424 1761 1311867777.3780329227 0.2132967412 0.2262731596 0.3266084492 0.0041831671 0.1524040000 981649801 0 402718720 -0.1942552030 -0.0981606990 0.0252494048 1762 1311867777.4108960629 0.2130193263 0.2262656375 0.3266084492 0.0041821126 0.1421320000 981652761 0 402718720 -0.1940429807 -0.0981445462 0.0255064815 1763 1311867777.4411139488 0.2133478075 0.2262583103 0.3266084492 0.0041810213 0.1428740000 981655665 0 402718720 -0.1943880618 -0.0983971730 0.0257181395 1764 1311867777.4770240784 0.2131043673 0.2262508535 0.3266084492 0.0041798860 0.1425270000 981658793 0 402718720 -0.1941954792 -0.0985469446 0.0259063561 1765 1311867777.5098700523 0.2131221145 0.2262434151 0.3266084492 0.0041787413 0.1419170000 981661753 0 402718720 -0.1943502426 -0.0984207615 0.0262972265 1766 1311867777.5421240330 0.2125584036 0.2262356659 0.3266084492 0.0041776037 0.1635190000 981664657 0 402718720 -0.1939485073 -0.0980934277 0.0264832042 1767 1311867777.5777161121 0.2122226655 0.2262277355 0.3266084492 0.0041764544 0.1417190000 981667785 0 402718720 -0.1939056665 -0.0979427993 0.0267368462 1768 1311867777.6086440086 0.2116519064 0.2262194913 0.3266084492 0.0041755022 0.1415430000 981670689 0 402718720 -0.1934106350 -0.0978092924 0.0272390824 1769 1311867777.6407959461 0.2112119049 0.2262110076 0.3266084492 0.0041743506 0.1419190000 981673705 0 402718720 -0.1931766123 -0.0978237689 0.0276204925 1770 1311867777.6765840054 0.2107619047 0.2262022793 0.3266084492 0.0041732176 0.1418020000 981676777 0 402718720 -0.1929737329 -0.0978683084 0.0280463900 1771 1311867777.7086570263 0.2106634825 0.2261935053 0.3266084492 0.0041720748 0.1521410000 981679681 0 402718720 -0.1929908693 -0.0979467034 0.0285197478 1772 1311867777.7411170006 0.2101604640 0.2261844573 0.3266084492 0.0041711705 0.1417210000 981682641 0 402718720 -0.1924281418 -0.0981409177 0.0287518017 1773 1311867777.7797420025 0.2098592073 0.2261752496 0.3266084492 0.0041701296 0.1415010000 981685825 0 402718720 -0.1922824830 -0.0981895477 0.0289577041 1774 1311867777.8103909492 0.2099297345 0.2261660920 0.3266084492 0.0041691164 0.1415110000 981688785 0 402718720 -0.1924954057 -0.0980587974 0.0292225461 1775 1311867777.8421120644 0.2098599225 0.2261569055 0.3266084492 0.0041680905 0.1416020000 981691689 0 402718720 -0.1924906671 -0.0978841633 0.0296974946 1776 1311867777.8771729469 0.2097752839 0.2261476816 0.3266084492 0.0041669752 0.1550490000 981694761 0 402718720 -0.1925514638 -0.0978448391 0.0300126467 1777 1311867777.9091188908 0.2095009685 0.2261383137 0.3266084492 0.0041659285 0.1426010000 981697721 0 402718720 -0.1925739348 -0.0979872793 0.0303353872 1778 1311867777.9424149990 0.2091604471 0.2261287649 0.3266084492 0.0041649427 0.1420930000 981700681 0 402718720 -0.1925317049 -0.0978448987 0.0304218493 1779 1311867777.9770610332 0.2090909332 0.2261191877 0.3266084492 0.0041639839 0.1422760000 981703809 0 402718720 -0.1928851753 -0.0972049832 0.0306272302 1780 1311867778.0100560188 0.2092002630 0.2261096826 0.3266084492 0.0041654394 0.1413570000 981706769 0 402718720 -0.1934228987 -0.0972426087 0.0307070911 1781 1311867778.0413420200 0.2095955908 0.2261004103 0.3266084492 0.0041644573 0.1543640000 981709673 0 402718720 -0.1939918399 -0.0977638736 0.0309808087 1782 1311867778.0773630142 0.2087510824 0.2260906744 0.3266084492 0.0041645272 0.1419640000 981712745 0 402718720 -0.1931934208 -0.0974810347 0.0308723096 1783 1311867778.1094930172 0.2088877559 0.2260810261 0.3266084492 0.0041642134 0.1414120000 981715705 0 402718720 -0.1933870167 -0.0976357609 0.0307390727 1784 1311867778.1418550014 0.2094775140 0.2260717192 0.3266084492 0.0041630927 0.1422900000 981718721 0 402718720 -0.1942016035 -0.0975608975 0.0308364183 1785 1311867778.1826310158 0.2096384764 0.2260625129 0.3266084492 0.0041629341 0.1418420000 981721849 0 402718720 -0.1948132217 -0.0973961353 0.0308367740 1786 1311867778.2094058990 0.2099843621 0.2260535106 0.3266084492 0.0041625762 0.1746740000 981724697 0 402718720 -0.1952046454 -0.0978280082 0.0307251383 1787 1311867778.2432699203 0.2099670470 0.2260445086 0.3266084492 0.0041616256 0.1424950000 981727713 0 402718720 -0.1953221560 -0.0980085507 0.0307574049 1788 1311867778.2796919346 0.2096943259 0.2260353642 0.3266084492 0.0041613330 0.1407200000 981730785 0 402718720 -0.1951829940 -0.0983392224 0.0307535492 1789 1311867778.3125588894 0.2094799280 0.2260261102 0.3266084492 0.0041603295 0.1420780000 981733745 0 402718720 -0.1950454861 -0.0988884345 0.0307854153 1790 1311867778.3414309025 0.2079488486 0.2260160112 0.3266084492 0.0041600011 0.1425090000 981736649 0 402718720 -0.1933604628 -0.0989601836 0.0305685103 1791 1311867778.3782539368 0.2076039910 0.2260057309 0.3266084492 0.0041597004 0.1425470000 981739777 0 402718720 -0.1930161119 -0.0992674232 0.0305161774 1792 1311867778.4093298912 0.2077042907 0.2259955180 0.3266084492 0.0041586690 0.1421440000 981742681 0 402718720 -0.1931213439 -0.0995924324 0.0305798128 1793 1311867778.4445381165 0.2077633739 0.2259853495 0.3266084492 0.0041575238 0.1427530000 981745753 0 402718720 -0.1932836026 -0.0996077135 0.0304488074 1794 1311867778.4812810421 0.2078438252 0.2259752372 0.3266084492 0.0041567098 0.1425740000 981748881 0 402718720 -0.1932174414 -0.0998011008 0.0303908661 1795 1311867778.5097670555 0.2083728760 0.2259654309 0.3266084492 0.0041557213 0.1430940000 981751729 0 402718720 -0.1938961148 -0.1001504138 0.0303952117 1796 1311867778.5484840870 0.2082982361 0.2259555939 0.3266084492 0.0041549928 0.1597880000 981754857 0 402718720 -0.1939101666 -0.1004540026 0.0304687340 1797 1311867778.5830690861 0.2078900188 0.2259455407 0.3266084492 0.0041540056 0.1437480000 981757929 0 402718720 -0.1934284270 -0.1007185057 0.0303175990 1798 1311867778.6150701046 0.2082614750 0.2259357053 0.3266084492 0.0041530250 0.1441220000 981760889 0 402718720 -0.1938355416 -0.1011583209 0.0303021669 1799 1311867778.6452109814 0.2086695731 0.2259261077 0.3266084492 0.0041525746 0.1434410000 981763793 0 402718720 -0.1946076900 -0.1012310758 0.0302057993 1800 1311867778.6781129837 0.2084639817 0.2259164065 0.3266084492 0.0041517374 0.1429830000 981766753 0 402718720 -0.1944605708 -0.1013441533 0.0301296953 1801 1311867778.7125270367 0.2088717520 0.2259069425 0.3266084492 0.0041511823 0.1567690000 981769769 0 402718720 -0.1949851513 -0.1016524732 0.0301214792 1802 1311867778.7490179539 0.2094758004 0.2258978242 0.3266084492 0.0041501026 0.1443730000 981772897 0 402718720 -0.1958772391 -0.1014776528 0.0300791245 1803 1311867778.7815420628 0.2093691081 0.2258886569 0.3266084492 0.0041494285 0.1442870000 981775913 0 402718720 -0.1960853189 -0.1012839079 0.0299747195 1804 1311867778.8090119362 0.2099682242 0.2258798318 0.3266084492 0.0041483671 0.1435090000 981778705 0 402718720 -0.1966765821 -0.1018546745 0.0299952384 1805 1311867778.8465809822 0.2099432498 0.2258710027 0.3266084492 0.0041485357 0.1432270000 981781833 0 402718720 -0.1967742592 -0.1023259833 0.0299513470 1806 1311867778.8808300495 0.2110020965 0.2258627696 0.3266084492 0.0041474555 0.1583270000 981784849 0 402718720 -0.1979681551 -0.1024196595 0.0299808588 1807 1311867778.9117860794 0.2111562788 0.2258546310 0.3266084492 0.0041469194 0.1429760000 981787753 0 402718720 -0.1982726753 -0.1026060134 0.0299417768 1808 1311867778.9482150078 0.2115779370 0.2258467346 0.3266084492 0.0041466853 0.1434380000 981790881 0 402718720 -0.1987852007 -0.1032760888 0.0298156384 1809 1311867778.9777760506 0.2123571634 0.2258392777 0.3266084492 0.0041457134 0.1432700000 981793785 0 402718720 -0.1997207403 -0.1036966220 0.0297726225 1810 1311867779.0105700493 0.2130448371 0.2258322089 0.3266084492 0.0041452277 0.1435820000 981796745 0 402718720 -0.2005009353 -0.1037986577 0.0296318196 1811 1311867779.0471200943 0.2135438025 0.2258254235 0.3266084492 0.0041441779 0.1442400000 981799873 0 402718720 -0.2010062635 -0.1039946675 0.0293347742 1812 1311867779.0780360699 0.2142925113 0.2258190587 0.3266084492 0.0041430876 0.1439940000 981802721 0 402718720 -0.2016545385 -0.1043229923 0.0289775580 1813 1311867779.1124050617 0.2148867548 0.2258130288 0.3266084492 0.0041430007 0.1434890000 981805737 0 402718720 -0.2022348791 -0.1043779254 0.0288112946 1814 1311867779.1473538876 0.2155236900 0.2258073566 0.3266084492 0.0041419011 0.1441010000 981808641 0 402718720 -0.2025606930 -0.1047037318 0.0287360717 1815 1311867779.1777000427 0.2156676650 0.2258017700 0.3266084492 0.0041407879 0.1427600000 981811489 0 402718720 -0.2024499178 -0.1051193252 0.0286449883 1816 1311867779.2123599052 0.2159374952 0.2257963381 0.3266084492 0.0041400441 0.1599980000 981814449 0 402718720 -0.2025721222 -0.1054293662 0.0285179764 1817 1311867779.2447109222 0.2153046280 0.2257905639 0.3266084492 0.0041389783 0.1441870000 981817409 0 402718720 -0.2017772347 -0.1054827496 0.0280920248 1818 1311867779.2782809734 0.2155384868 0.2257849247 0.3266084492 0.0041384960 0.1441840000 981820313 0 402718720 -0.2018735558 -0.1054445282 0.0281492658 1819 1311867779.3104579449 0.2157347798 0.2257793996 0.3266084492 0.0041374519 0.1439360000 981823273 0 402718720 -0.2020665258 -0.1051720157 0.0278673992 1820 1311867779.3468949795 0.2157450467 0.2257738863 0.3266084492 0.0041368974 0.1581100000 981826345 0 402718720 -0.2020419985 -0.1046975404 0.0275773294 1821 1311867779.3772010803 0.2155936211 0.2257682958 0.3266084492 0.0041363396 0.1562460000 981829193 0 402718720 -0.2016295344 -0.1049668342 0.0271812119 1822 1311867779.4088799953 0.2155574113 0.2257626916 0.3266084492 0.0041352206 0.1431790000 981832097 0 402718720 -0.2014193237 -0.1050993130 0.0269917846 1823 1311867779.4446020126 0.2156168669 0.2257571261 0.3266084492 0.0041343379 0.1441280000 981835113 0 402718720 -0.2012286782 -0.1051293015 0.0266775638 1824 1311867779.4768970013 0.2160394192 0.2257517984 0.3266084492 0.0041340691 0.1450370000 981838073 0 402718720 -0.2015685290 -0.1054866835 0.0265209470 1825 1311867779.5098230839 0.2164520025 0.2257467026 0.3266084492 0.0041331052 0.1441390000 981840977 0 402718720 -0.2018049806 -0.1058771387 0.0266135745 1826 1311867779.5450038910 0.2164707035 0.2257416227 0.3266084492 0.0041323163 0.1681770000 981843993 0 402718720 -0.2018979043 -0.1057691872 0.0261864606 1827 1311867779.5777029991 0.2167347670 0.2257366928 0.3266084492 0.0041315250 0.1451570000 981846897 0 402718720 -0.2021262944 -0.1061161160 0.0260336418 1828 1311867779.6092689037 0.2169545889 0.2257318886 0.3266084492 0.0041308974 0.1458710000 981849801 0 402718720 -0.2022052407 -0.1063626260 0.0257755127 1829 1311867779.6482150555 0.2172693163 0.2257272617 0.3266084492 0.0041303453 0.1452930000 981852873 0 402718720 -0.2025177032 -0.1061623320 0.0255142674 1830 1311867779.6796278954 0.2170718163 0.2257225320 0.3266084492 0.0041297250 0.1452750000 981855777 0 402718720 -0.2023862302 -0.1057580635 0.0249592252 1831 1311867779.7129859924 0.2172584832 0.2257179093 0.3266084492 0.0041287629 0.1460880000 981858681 0 402718720 -0.2024324238 -0.1057542264 0.0247900300 1832 1311867779.7461729050 0.2176536471 0.2257135074 0.3266084492 0.0041281443 0.1455570000 981861697 0 402718720 -0.2026511133 -0.1060739309 0.0248413924 1833 1311867779.7771708965 0.2173919082 0.2257089676 0.3266084492 0.0041271300 0.1444290000 981864545 0 402718720 -0.2022723556 -0.1061587557 0.0244604647 1834 1311867779.8130059242 0.2175245732 0.2257045050 0.3266084492 0.0041264449 0.1458230000 981867505 0 402718720 -0.2022025436 -0.1062797084 0.0242077876 1835 1311867779.8454499245 0.2174874246 0.2257000270 0.3266084492 0.0041254748 0.1457110000 981870465 0 402718720 -0.2020099908 -0.1066704169 0.0239015166 1836 1311867779.8771400452 0.2173039764 0.2256954540 0.3266084492 0.0041246456 0.1608700000 981873313 0 402718720 -0.2016045153 -0.1069815457 0.0236981828 1837 1311867779.9128279686 0.2170092911 0.2256907255 0.3266084492 0.0041239940 0.1466640000 981876385 0 402718720 -0.2011063099 -0.1071426943 0.0233625583 1838 1311867779.9448599815 0.2168116122 0.2256858947 0.3266084492 0.0041230172 0.1467250000 981879289 0 402718720 -0.2009688318 -0.1069521531 0.0230612382 1839 1311867779.9769320488 0.2170668542 0.2256812079 0.3266084492 0.0041224637 0.1466290000 981882193 0 402718720 -0.2011635602 -0.1069951355 0.0229206793 1840 1311867780.0130739212 0.2171360254 0.2256765637 0.3266084492 0.0041218674 0.1461140000 981885209 0 402718720 -0.2013711184 -0.1067822203 0.0226005614 1841 1311867780.0448310375 0.2168518603 0.2256717703 0.3266084492 0.0041217833 0.1563130000 981888113 0 402718720 -0.2013424635 -0.1062484309 0.0220198669 1842 1311867780.0771219730 0.2166379690 0.2256668660 0.3266084492 0.0041209938 0.1461360000 981891017 0 402718720 -0.2012064308 -0.1060003191 0.0219609607 1843 1311867780.1143870354 0.2163754702 0.2256618245 0.3266084492 0.0041200726 0.1449600000 981894089 0 402718720 -0.2010330707 -0.1057605594 0.0215298273 1844 1311867780.1448268890 0.2162952572 0.2256567450 0.3266084492 0.0041217578 0.1458630000 981896937 0 402718720 -0.2012584060 -0.1058819294 0.0212809574 1845 1311867780.1773400307 0.2163930386 0.2256517241 0.3266084492 0.0041245189 0.1475460000 981899841 0 402718720 -0.2012664080 -0.1058463305 0.0210022945 1846 1311867780.2158250809 0.2157494724 0.2256463599 0.3266084492 0.0041271968 0.1681460000 981902969 0 402718720 -0.2010401487 -0.1055646390 0.0206287056 1847 1311867780.2454960346 0.2163568735 0.2256413304 0.3266084492 0.0041293382 0.1471900000 981905817 0 402718720 -0.2013065368 -0.1057750881 0.0205143802 1848 1311867780.2815570831 0.2162684947 0.2256362585 0.3266084492 0.0041283103 0.1480290000 981908833 0 402718720 -0.2013870776 -0.1059218943 0.0201975033 1849 1311867780.3140099049 0.2163073570 0.2256312131 0.3266084492 0.0041273705 0.1480580000 981911737 0 402718720 -0.2013481110 -0.1063907295 0.0198934041 1850 1311867780.3464050293 0.2166771144 0.2256263731 0.3266084492 0.0041262961 0.1481310000 981914641 0 402718720 -0.2016574591 -0.1066912860 0.0196266677 1851 1311867780.3772649765 0.2167479843 0.2256215765 0.3266084492 0.0041255577 0.1482600000 981917489 0 402718720 -0.2018265277 -0.1071615219 0.0190530438 1852 1311867780.4132668972 0.2167644352 0.2256167941 0.3266084492 0.0041251063 0.1490370000 981920561 0 402718720 -0.2016612887 -0.1076160595 0.0185634587 1853 1311867780.4451050758 0.2171393931 0.2256122191 0.3266084492 0.0041245937 0.1488870000 981923465 0 402718720 -0.2021857053 -0.1075300053 0.0181315299 1854 1311867780.4791510105 0.2168478370 0.2256074918 0.3266084492 0.0041267276 0.1760830000 981926425 0 402718720 -0.2023970485 -0.1073613092 0.0177174769 1855 1311867780.5153009892 0.2171453238 0.2256029300 0.3266084492 0.0041266718 0.1507420000 981929497 0 402718720 -0.2024499476 -0.1074547693 0.0175156202 1856 1311867780.5455119610 0.2163153589 0.2255979259 0.3266084492 0.0041307193 0.1503740000 981932345 0 402718720 -0.2019088566 -0.1077287719 0.0173657667 1857 1311867780.5798339844 0.2167068571 0.2255931381 0.3266084492 0.0041304494 0.1503970000 981935305 0 402718720 -0.2022707015 -0.1078639701 0.0172090586 1858 1311867780.6136929989 0.2177990079 0.2255889432 0.3266084492 0.0041329211 0.1511640000 981938209 0 402718720 -0.2030267417 -0.1079372913 0.0169726312 1859 1311867780.6459660530 0.2183931917 0.2255850724 0.3266084492 0.0041319220 0.1526290000 981941169 0 402718720 -0.2037493736 -0.1080205515 0.0167490207 1860 1311867780.6793959141 0.2189510465 0.2255815057 0.3266084492 0.0041315056 0.1526350000 981944129 0 402718720 -0.2047125101 -0.1074471027 0.0165179968 1861 1311867780.7156999111 0.2192670107 0.2255781127 0.3266084492 0.0041306349 0.1700040000 981947145 0 402718720 -0.2054415196 -0.1068871245 0.0161806010 1862 1311867780.7469029427 0.2193653286 0.2255747760 0.3266084492 0.0041295506 0.1544820000 981949993 0 402718720 -0.2056856006 -0.1069422737 0.0159614179 1863 1311867780.7774689198 0.2194982767 0.2255715144 0.3266084492 0.0041285214 0.1550250000 981952897 0 402718720 -0.2059102654 -0.1070523635 0.0154621648 1864 1311867780.8164570332 0.2196314931 0.2255683277 0.3266084492 0.0041275692 0.1682040000 981956025 0 402718720 -0.2061508298 -0.1070872843 0.0151052466 1865 1311867780.8460350037 0.2198489159 0.2255652609 0.3266084492 0.0041275026 0.1659790000 981958817 0 402718720 -0.2067379355 -0.1076378301 0.0148220891 1866 1311867780.8791809082 0.2206873298 0.2255626468 0.3266084492 0.0041266620 0.1667370000 981961777 0 402718720 -0.2076005042 -0.1080340445 0.0144444350 1867 1311867780.9152340889 0.2204847038 0.2255599270 0.3266084492 0.0041258181 0.1570130000 981964793 0 402718720 -0.2076171637 -0.1075855568 0.0138998991 1868 1311867780.9457290173 0.2207282931 0.2255573405 0.3266084492 0.0041253612 0.1567390000 981967641 0 402718720 -0.2079764456 -0.1077778190 0.0135181965 1869 1311867780.9838399887 0.2207710296 0.2255547796 0.3266084492 0.0041244678 0.1574270000 981970713 0 402718720 -0.2079563886 -0.1081557497 0.0131612038 1870 1311867781.0137300491 0.2207297534 0.2255521993 0.3266084492 0.0041234765 0.1573430000 981973561 0 402718720 -0.2080900669 -0.1079189256 0.0128586860 1871 1311867781.0463659763 0.2212398499 0.2255498945 0.3266084492 0.0041226680 0.1581980000 981976465 0 402718720 -0.2086929381 -0.1080816463 0.0124223018 1872 1311867781.0821859837 0.2214552462 0.2255477072 0.3266084492 0.0041216411 0.1595110000 981979481 0 402718720 -0.2088040113 -0.1087034345 0.0119155329 1873 1311867781.1157560349 0.2220721543 0.2255458516 0.3266084492 0.0041206516 0.1592070000 981982441 0 402718720 -0.2094815522 -0.1090870649 0.0115796011 1874 1311867781.1459479332 0.2219637185 0.2255439401 0.3266084492 0.0041205160 0.1593910000 981985289 0 402718720 -0.2096242160 -0.1095615253 0.0111545939 1875 1311867781.1839950085 0.2223954201 0.2255422609 0.3266084492 0.0041201609 0.1589670000 981988361 0 402718720 -0.2099035233 -0.1101855561 0.0106461998 1876 1311867781.2133030891 0.2221405208 0.2255404476 0.3266084492 0.0041194382 0.1713070000 981991153 0 402718720 -0.2097561657 -0.1101611406 0.0101824515 1877 1311867781.2467529774 0.2226214707 0.2255388925 0.3266084492 0.0041185564 0.1595900000 981994057 0 402718720 -0.2102252245 -0.1097231284 0.0094929291 1878 1311867781.2855589390 0.2230578065 0.2255375713 0.3266084492 0.0041175184 0.1604570000 981997185 0 402718720 -0.2105245143 -0.1097939461 0.0087735681 1879 1311867781.3133049011 0.2237799168 0.2255366359 0.3266084492 0.0041169255 0.1603560000 981999921 0 402718720 -0.2111445367 -0.1095595211 0.0083236480 1880 1311867781.3465669155 0.2239349782 0.2255357840 0.3266084492 0.0041163458 0.1603340000 982002937 0 402718720 -0.2114972472 -0.1092012078 0.0077824378 1881 1311867781.3809239864 0.2248827368 0.2255354368 0.3266084492 0.0041153988 0.1903990000 982005897 0 402718720 -0.2125909925 -0.1091121733 0.0073092990 1882 1311867781.4144830704 0.2249755710 0.2255351393 0.3266084492 0.0041144790 0.1610210000 982008801 0 402718720 -0.2129236758 -0.1086563244 0.0068993918 1883 1311867781.4457330704 0.2244405001 0.2255345580 0.3266084492 0.0041171193 0.1597360000 982011705 0 402718720 -0.2130978703 -0.1085384414 0.0063171592 1884 1311867781.4812419415 0.2258639783 0.2255347328 0.3266084492 0.0041178808 0.1616080000 982014721 0 402718720 -0.2139831930 -0.1088313982 0.0060508619 1885 1311867781.5131030083 0.2266134322 0.2255353051 0.3266084492 0.0041179316 0.1805820000 982017569 0 402718720 -0.2149715424 -0.1086573154 0.0059209601 1886 1311867781.5451910496 0.2275917083 0.2255363954 0.3266084492 0.0041177112 0.1724670000 982020529 0 402718720 -0.2162563950 -0.1083842888 0.0057073752 1887 1311867781.5813419819 0.2276584804 0.2255375200 0.3266084492 0.0041184675 0.1616060000 982023545 0 402718720 -0.2167755216 -0.1084393188 0.0051259417 1888 1311867781.6135890484 0.2283730060 0.2255390219 0.3266084492 0.0041177609 0.1618180000 982026393 0 402718720 -0.2173390090 -0.1088175476 0.0047104205 1889 1311867781.6467020512 0.2283926010 0.2255405325 0.3266084492 0.0041167632 0.1717090000 982029353 0 402718720 -0.2174724638 -0.1087545529 0.0042829784 1890 1311867781.6832339764 0.2293392420 0.2255425424 0.3266084492 0.0041163524 0.1607880000 982032369 0 402718720 -0.2185275406 -0.1090257168 0.0040337685 1891 1311867781.7131800652 0.2294171900 0.2255445914 0.3266084492 0.0041153755 0.1816440000 982035217 0 402718720 -0.2187374830 -0.1091735959 0.0036298488 1892 1311867781.7453010082 0.2290288955 0.2255464330 0.3266084492 0.0041145207 0.1617120000 982038177 0 402718720 -0.2185097635 -0.1093810499 0.0033124457 1893 1311867781.7820630074 0.2297109962 0.2255486330 0.3266084492 0.0041144884 0.1613410000 982041193 0 402718720 -0.2192836255 -0.1098757163 0.0031819295 1894 1311867781.8145859241 0.2300681621 0.2255510192 0.3266084492 0.0041164281 0.1614040000 982044097 0 402718720 -0.2199223042 -0.1104247645 0.0027676444 1895 1311867781.8453550339 0.2297540903 0.2255532372 0.3266084492 0.0041154984 0.1596410000 982047001 0 402718720 -0.2198006958 -0.1101983562 0.0023476153 1896 1311867781.8827259541 0.2297084630 0.2255554287 0.3266084492 0.0041158539 0.1850700000 982050017 0 402718720 -0.2201216519 -0.1104662940 0.0018418104 1897 1311867781.9138391018 0.2298200130 0.2255576768 0.3266084492 0.0041152491 0.1608260000 982052921 0 402718720 -0.2199959159 -0.1116267964 0.0012917585 1898 1311867781.9470670223 0.2302701175 0.2255601597 0.3266084492 0.0041142093 0.1604270000 982055881 0 402718720 -0.2204333544 -0.1124575809 0.0007726238 1899 1311867781.9856810570 0.2304482758 0.2255627337 0.3266084492 0.0041163018 0.1607460000 982058897 0 402718720 -0.2211351246 -0.1124174818 0.0002701434 1900 1311867782.0139210224 0.2313035876 0.2255657552 0.3266084492 0.0041157550 0.1604860000 982061689 0 402718720 -0.2219788730 -0.1132201999 -0.0003443204 1901 1311867782.0464830399 0.2316680104 0.2255689652 0.3266084492 0.0041153917 0.1737880000 982064649 0 402718720 -0.2224090993 -0.1135063916 -0.0009306500 1902 1311867782.0839829445 0.2316863388 0.2255721815 0.3266084492 0.0041158620 0.1596240000 982067609 0 402718720 -0.2227873206 -0.1127699018 -0.0013964098 1903 1311867782.1135599613 0.2316507250 0.2255753757 0.3266084492 0.0041157274 0.1589380000 982070457 0 402718720 -0.2232042402 -0.1120195612 -0.0015916188 1904 1311867782.1472380161 0.2316700667 0.2255785767 0.3266084492 0.0041146986 0.1595790000 982073417 0 402718720 -0.2233488560 -0.1119133011 -0.0016679085 1905 1311867782.1819090843 0.2315410972 0.2255817066 0.3266084492 0.0041138267 0.1593370000 982076433 0 402718720 -0.2233938724 -0.1113717556 -0.0017488798 1906 1311867782.2144429684 0.2315060198 0.2255848149 0.3266084492 0.0041133661 0.1596290000 982079337 0 402718720 -0.2231958359 -0.1111781448 -0.0019532312 1907 1311867782.2494089603 0.2316762209 0.2255880091 0.3266084492 0.0041139410 0.1596100000 982082297 0 402718720 -0.2235024422 -0.1115050018 -0.0021027566 1908 1311867782.2860810757 0.2323317528 0.2255915436 0.3266084492 0.0041129093 0.1590040000 982085369 0 402718720 -0.2241045237 -0.1115947813 -0.0021952232 1909 1311867782.3144040108 0.2318466455 0.2255948202 0.3266084492 0.0041120580 0.1713940000 982088105 0 402718720 -0.2236548364 -0.1112536415 -0.0025975886 1910 1311867782.3526129723 0.2322674990 0.2255983138 0.3266084492 0.0041117833 0.1583170000 982091233 0 402718720 -0.2239366323 -0.1116257086 -0.0027665719 1911 1311867782.3825540543 0.2328338027 0.2256021000 0.3266084492 0.0041107706 0.1783640000 982094025 0 402718720 -0.2245318145 -0.1117833704 -0.0029588772 1912 1311867782.4147620201 0.2326698154 0.2256057965 0.3266084492 0.0041099649 0.1582130000 982096817 0 402718720 -0.2242950052 -0.1113593131 -0.0030755645 1913 1311867782.4514210224 0.2326870859 0.2256094982 0.3266084492 0.0041089534 0.1576920000 982099833 0 402718720 -0.2242487669 -0.1116848662 -0.0033239159 1914 1311867782.4812099934 0.2329675406 0.2256133425 0.3266084492 0.0041079386 0.1570340000 982102737 0 402718720 -0.2243752629 -0.1116305739 -0.0034087324 1915 1311867782.5149359703 0.2330374867 0.2256172193 0.3266084492 0.0041072665 0.1570140000 982105641 0 402718720 -0.2244485319 -0.1109368280 -0.0034170172 1916 1311867782.5516130924 0.2334675640 0.2256213166 0.3266084492 0.0041066413 0.1817660000 982108657 0 402718720 -0.2246546000 -0.1113350838 -0.0033426352 1917 1311867782.5828690529 0.2336357683 0.2256254973 0.3266084492 0.0041057511 0.1570210000 982111505 0 402718720 -0.2247760892 -0.1111961678 -0.0035046893 1918 1311867782.6142859459 0.2335257381 0.2256296163 0.3266084492 0.0041047393 0.1695420000 982114465 0 402718720 -0.2245334536 -0.1109677702 -0.0036777935 1919 1311867782.6501080990 0.2337627411 0.2256338545 0.3266084492 0.0041040115 0.1576580000 982117481 0 402718720 -0.2246079594 -0.1111708060 -0.0038652699 1920 1311867782.6862080097 0.2343189418 0.2256383780 0.3266084492 0.0041047831 0.1573700000 982120497 0 402718720 -0.2243575156 -0.1111208797 -0.0040680501 1921 1311867782.7131700516 0.2345908880 0.2256430383 0.3266084492 0.0041039798 0.1876400000 982123233 0 402718720 -0.2247754782 -0.1107063666 -0.0043293838 1922 1311867782.7489991188 0.2349120826 0.2256478609 0.3266084492 0.0041040759 0.1579120000 982126249 0 402718720 -0.2250810266 -0.1111215055 -0.0046762601 1923 1311867782.7844688892 0.2350965887 0.2256527745 0.3266084492 0.0041030470 0.1573020000 982129265 0 402718720 -0.2252608687 -0.1115047559 -0.0050697341 1924 1311867782.8159070015 0.2351279408 0.2256576992 0.3266084492 0.0041024111 0.1578350000 982132169 0 402718720 -0.2261838466 -0.1110130847 -0.0053767860 1925 1311867782.8522670269 0.2353802621 0.2256627499 0.3266084492 0.0041014113 0.1581020000 982135129 0 402718720 -0.2260215580 -0.1114076152 -0.0059301849 1926 1311867782.8824830055 0.2364793420 0.2256683660 0.3266084492 0.0041004557 0.1672590000 982138033 0 402718720 -0.2269839793 -0.1125143170 -0.0062656086 1927 1311867782.9145979881 0.2361429185 0.2256738017 0.3266084492 0.0041004394 0.1549640000 982140937 0 402718720 -0.2269368172 -0.1116718128 -0.0068234801 1928 1311867782.9517209530 0.2364296913 0.2256793804 0.3266084492 0.0040994906 0.1686070000 982144009 0 402718720 -0.2274312973 -0.1116455942 -0.0073451777 1929 1311867782.9812240601 0.2372288257 0.2256853677 0.3266084492 0.0040984807 0.1558880000 982146801 0 402718720 -0.2283198684 -0.1124175712 -0.0078697139 1930 1311867783.0143089294 0.2371222526 0.2256912936 0.3266084492 0.0040979280 0.1554320000 982149761 0 402718720 -0.2285241187 -0.1119732633 -0.0084222779 1931 1311867783.0528459549 0.2374115586 0.2256973631 0.3266084492 0.0040973180 0.1860810000 982152777 0 402718720 -0.2289982885 -0.1119950265 -0.0088867024 1932 1311867783.0829811096 0.2382414043 0.2257038559 0.3266084492 0.0040966668 0.1555560000 982155681 0 402718720 -0.2298087329 -0.1124702469 -0.0091242660 1933 1311867783.1137030125 0.2384806722 0.2257104657 0.3266084492 0.0040960022 0.1544320000 982158529 0 402718720 -0.2303010523 -0.1118757948 -0.0094384551 1934 1311867783.1539480686 0.2386883646 0.2257171761 0.3266084492 0.0040950048 0.1546590000 982161657 0 402718720 -0.2306717485 -0.1119007692 -0.0097760353 1935 1311867783.1857850552 0.2391157448 0.2257241004 0.3266084492 0.0040941666 0.1539060000 982164561 0 402718720 -0.2311707139 -0.1120928153 -0.0098868934 1936 1311867783.2169439793 0.2397286892 0.2257313342 0.3266084492 0.0040937103 0.1662260000 982167409 0 402718720 -0.2321269512 -0.1119388714 -0.0100499466 1937 1311867783.2548489571 0.2397345752 0.2257385635 0.3266084492 0.0040927338 0.1537000000 982170537 0 402718720 -0.2322330326 -0.1117252335 -0.0102869803 1938 1311867783.2816879749 0.2399381995 0.2257458905 0.3266084492 0.0040917988 0.1663110000 982173329 0 402718720 -0.2324540317 -0.1121402159 -0.0104872137 1939 1311867783.3132228851 0.2399057597 0.2257531932 0.3266084492 0.0040910374 0.1532240000 982176121 0 402718720 -0.2324023098 -0.1123520508 -0.0105910208 1940 1311867783.3503270149 0.2424070835 0.2257617776 0.3266084492 0.0040908375 0.1529300000 982179193 0 402718720 -0.2352610976 -0.1116639376 -0.0105318194 1941 1311867783.3855919838 0.2435486168 0.2257709414 0.3266084492 0.0040902802 0.1660330000 982182209 0 402718720 -0.2364240140 -0.1118825004 -0.0106417825 1942 1311867783.4198501110 0.2437658757 0.2257802076 0.3266084492 0.0040893119 0.1530810000 982185169 0 402718720 -0.2366240174 -0.1123797372 -0.0107647106 1943 1311867783.4503099918 0.2434620857 0.2257893079 0.3266084492 0.0040884007 0.1519870000 982188017 0 402718720 -0.2366244197 -0.1119359508 -0.0110115577 1944 1311867783.4863688946 0.2434419394 0.2257983884 0.3266084492 0.0040882960 0.1522760000 982191033 0 402718720 -0.2366027832 -0.1124874577 -0.0112470463 1945 1311867783.5186200142 0.2444310784 0.2258079682 0.3266084492 0.0040873517 0.1511810000 982193881 0 402718720 -0.2376020998 -0.1127540618 -0.0112124262 1946 1311867783.5488419533 0.2443152964 0.2258174787 0.3266084492 0.0040872130 0.1564850000 982196729 0 402718720 -0.2377923727 -0.1123384908 -0.0113926157 1947 1311867783.5823969841 0.2440614700 0.2258268490 0.3266084492 0.0040862754 0.1513870000 982199745 0 402718720 -0.2374390811 -0.1128467023 -0.0117424224 1948 1311867783.6168529987 0.2443497777 0.2258363577 0.3266084492 0.0040852685 0.1501170000 982202649 0 402718720 -0.2377769202 -0.1128887683 -0.0117934262 1949 1311867783.6515829563 0.2444408983 0.2258459034 0.3266084492 0.0040843283 0.1628250000 982205609 0 402718720 -0.2379148751 -0.1125017554 -0.0119370818 1950 1311867783.6816630363 0.2451606840 0.2258558084 0.3266084492 0.0040840538 0.1502220000 982208513 0 402718720 -0.2387107760 -0.1124003604 -0.0117719220 1951 1311867783.7179610729 0.2453283221 0.2258657892 0.3266084492 0.0040839331 0.1687470000 982211529 0 402718720 -0.2388239354 -0.1127033085 -0.0118789105 1952 1311867783.7488200665 0.2449539006 0.2258755679 0.3266084492 0.0040829597 0.1498450000 982214377 0 402718720 -0.2385049462 -0.1116634160 -0.0117915533 1953 1311867783.7808690071 0.2452794164 0.2258855033 0.3266084492 0.0040827246 0.1510610000 982217281 0 402718720 -0.2387153357 -0.1113597900 -0.0115049910 1954 1311867783.8168580532 0.2456165105 0.2258956011 0.3266084492 0.0040837803 0.1516150000 982220241 0 402718720 -0.2386894673 -0.1122706831 -0.0113620618 1955 1311867783.8489229679 0.2456706911 0.2259057162 0.3266084492 0.0040849813 0.1514530000 982223145 0 402718720 -0.2390126586 -0.1104777902 -0.0107940445 1956 1311867783.8808929920 0.2447481751 0.2259153494 0.3266084492 0.0040841229 0.1805620000 982226049 0 402718720 -0.2381482273 -0.1100173369 -0.0107860817 1957 1311867783.9168200493 0.2452076077 0.2259252074 0.3266084492 0.0040906304 0.1536200000 982229065 0 402718720 -0.2383946031 -0.1105611473 -0.0103481729 1958 1311867783.9508318901 0.2447935343 0.2259348440 0.3266084492 0.0040897019 0.1660480000 982232025 0 402718720 -0.2380839139 -0.1103121713 -0.0100054238 1959 1311867783.9816930294 0.2447390705 0.2259444429 0.3266084492 0.0040910521 0.1539610000 982234873 0 402718720 -0.2380920798 -0.1102074459 -0.0094791465 1960 1311867784.0175230503 0.2450211346 0.2259541759 0.3266084492 0.0040908390 0.1535860000 982237945 0 402718720 -0.2382619828 -0.1114488319 -0.0094349217 1961 1311867784.0505928993 0.2452113628 0.2259639959 0.3266084492 0.0040905308 0.1750530000 982240905 0 402718720 -0.2385755926 -0.1113744751 -0.0093075624 1962 1311867784.0830729008 0.2448128164 0.2259736029 0.3266084492 0.0040899074 0.1542160000 982243753 0 402718720 -0.2386210710 -0.1106769070 -0.0092495056 1963 1311867784.1187570095 0.2454640120 0.2259835318 0.3266084492 0.0040894387 0.1539840000 982246769 0 402718720 -0.2392429411 -0.1116845235 -0.0090764612 1964 1311867784.1503119469 0.2448296696 0.2259931276 0.3266084492 0.0040888674 0.1663710000 982249673 0 402718720 -0.2389436066 -0.1118199006 -0.0090513509 1965 1311867784.1823339462 0.2442940176 0.2260024410 0.3266084492 0.0040878930 0.1542040000 982252633 0 402718720 -0.2387623787 -0.1113817841 -0.0086551905 1966 1311867784.2173891068 0.2445174307 0.2260118586 0.3266084492 0.0040875012 0.1647730000 982255537 0 402718720 -0.2390806377 -0.1124022678 -0.0084413895 1967 1311867784.2502059937 0.2447870374 0.2260214037 0.3266084492 0.0040876112 0.1527760000 982258497 0 402718720 -0.2397025526 -0.1125767678 -0.0083291391 1968 1311867784.2819900513 0.2443815917 0.2260307330 0.3266084492 0.0040869423 0.1530380000 982261345 0 402718720 -0.2395425737 -0.1121349707 -0.0081533212 1969 1311867784.3176920414 0.2447913438 0.2260402610 0.3266084492 0.0040868438 0.1638880000 982264417 0 402718720 -0.2400314659 -0.1128582060 -0.0079151681 1970 1311867784.3490819931 0.2452908009 0.2260500329 0.3266084492 0.0040864040 0.1525470000 982267265 0 402718720 -0.2403058261 -0.1133192033 -0.0076174643 1971 1311867784.3815689087 0.2446692735 0.2260594795 0.3266084492 0.0040860363 0.1678890000 982270225 0 402718720 -0.2399788946 -0.1125467867 -0.0075266999 1972 1311867784.4190580845 0.2449747622 0.2260690714 0.3266084492 0.0040854199 0.1530170000 982273241 0 402718720 -0.2401759624 -0.1135246679 -0.0073133367 1973 1311867784.4496140480 0.2450126112 0.2260786728 0.3266084492 0.0040844562 0.1648230000 982276145 0 402718720 -0.2399994731 -0.1139326394 -0.0070549548 1974 1311867784.4828379154 0.2451984733 0.2260883586 0.3266084492 0.0040838939 0.1523400000 982279105 0 402718720 -0.2403876334 -0.1134095117 -0.0068682330 1975 1311867784.5185639858 0.2453542948 0.2260981135 0.3266084492 0.0040829927 0.1635080000 982282009 0 402718720 -0.2403584868 -0.1138396338 -0.0066801896 1976 1311867784.5499279499 0.2450322509 0.2261076956 0.3266084492 0.0040820937 0.1648780000 982284913 0 402718720 -0.2403111756 -0.1145214811 -0.0066458550 1977 1311867784.5848410130 0.2446903586 0.2261170950 0.3266084492 0.0040811093 0.1649590000 982287929 0 402718720 -0.2402866483 -0.1139805168 -0.0066058040 1978 1311867784.6179790497 0.2447023690 0.2261264910 0.3266084492 0.0040804852 0.1523580000 982290833 0 402718720 -0.2404118776 -0.1145653948 -0.0065137809 1979 1311867784.6492750645 0.2451413572 0.2261360993 0.3266084492 0.0040795362 0.1515070000 982293737 0 402718720 -0.2409447134 -0.1151667312 -0.0062789200 1980 1311867784.6878700256 0.2448505312 0.2261455510 0.3266084492 0.0040790705 0.1508190000 982296809 0 402718720 -0.2410073429 -0.1141942888 -0.0062234830 1981 1311867784.7168869972 0.2447991520 0.2261549673 0.3266084492 0.0040784021 0.1698290000 982299601 0 402718720 -0.2412067950 -0.1144800410 -0.0061779441 1982 1311867784.7578089237 0.2444812357 0.2261642136 0.3266084492 0.0040808514 0.1509780000 982302841 0 402718720 -0.2414230853 -0.1146228537 -0.0060286019 1983 1311867784.7870030403 0.2447809577 0.2261736018 0.3266084492 0.0040798240 0.1509020000 982305633 0 402718720 -0.2417081147 -0.1142791957 -0.0057170615 1984 1311867784.8199620247 0.2442190349 0.2261826973 0.3266084492 0.0040801826 0.1515810000 982308425 0 402718720 -0.2415242493 -0.1152512878 -0.0057431846 1985 1311867784.8550779819 0.2445593178 0.2261919550 0.3266084492 0.0040795292 0.1499880000 982311385 0 402718720 -0.2420375496 -0.1155272573 -0.0057335659 1986 1311867784.8873779774 0.2445220351 0.2262011847 0.3266084492 0.0040785077 0.1603720000 982314289 0 402718720 -0.2423154414 -0.1151491404 -0.0055117235 1987 1311867784.9173130989 0.2452861369 0.2262107896 0.3266084492 0.0040778326 0.1500830000 982317193 0 402718720 -0.2428911328 -0.1157893389 -0.0056320429 1988 1311867784.9491391182 0.2450401187 0.2262202611 0.3266084492 0.0040770301 0.1497550000 982320041 0 402718720 -0.2430573702 -0.1161828265 -0.0056495965 1989 1311867784.9848570824 0.2452889830 0.2262298482 0.3266084492 0.0040762999 0.1498160000 982323057 0 402718720 -0.2435300499 -0.1161623821 -0.0054999255 1990 1311867785.0184569359 0.2453955561 0.2262394792 0.3266084492 0.0040753068 0.1498870000 982325961 0 402718720 -0.2436507940 -0.1166650206 -0.0057362434 1991 1311867785.0500280857 0.2455045432 0.2262491553 0.3266084492 0.0040743110 0.1638700000 982328921 0 402718720 -0.2440278381 -0.1167115346 -0.0056602159 1992 1311867785.0871460438 0.2455997169 0.2262588694 0.3266084492 0.0040733031 0.1490380000 982331937 0 402718720 -0.2443096191 -0.1160858274 -0.0055352002 1993 1311867785.1168398857 0.2456508428 0.2262685994 0.3266084492 0.0040724855 0.1594240000 982334841 0 402718720 -0.2445294559 -0.1160933226 -0.0057529830 1994 1311867785.1499750614 0.2459286153 0.2262784590 0.3266084492 0.0040715583 0.1479020000 982337689 0 402718720 -0.2446875572 -0.1166334823 -0.0057099354 1995 1311867785.1850368977 0.2459732890 0.2262883311 0.3266084492 0.0040705634 0.1474650000 982340705 0 402718720 -0.2448936850 -0.1157719865 -0.0057649612 1996 1311867785.2169620991 0.2460183948 0.2262982159 0.3266084492 0.0040695833 0.1481020000 982343553 0 402718720 -0.2451331615 -0.1156790182 -0.0059185615 1997 1311867785.2491741180 0.2461721003 0.2263081678 0.3266084492 0.0040685958 0.1481740000 982346457 0 402718720 -0.2453884333 -0.1156623289 -0.0058154538 1998 1311867785.2858769894 0.2462395132 0.2263181434 0.3266084492 0.0040677126 0.1607700000 982349529 0 402718720 -0.2456016690 -0.1153893471 -0.0058133448 1999 1311867785.3214280605 0.2454596460 0.2263277190 0.3266084492 0.0040671627 0.1483840000 982352657 0 402718720 -0.2451816797 -0.1153130010 -0.0061054020 2000 1311867785.3573219776 0.2453784794 0.2263372444 0.3266084492 0.0040665123 0.1475170000 982355617 0 402718720 -0.2452304214 -0.1155407429 -0.0061558955 2001 1311867785.3893299103 0.2458668500 0.2263470043 0.3266084492 0.0040656661 0.1479880000 982358521 0 402718720 -0.2460261881 -0.1150973067 -0.0060366048 2002 1311867785.4211249352 0.2453445643 0.2263564936 0.3266084492 0.0040650295 0.1481310000 982361425 0 402718720 -0.2457459122 -0.1149796173 -0.0061387829 2003 1311867785.4570529461 0.2454936653 0.2263660478 0.3266084492 0.0040661816 0.1484110000 982364441 0 402718720 -0.2459632903 -0.1154227704 -0.0062228916 2004 1311867785.4900350571 0.2458606958 0.2263757757 0.3266084492 0.0040655496 0.1479450000 982367401 0 402718720 -0.2466619909 -0.1142895296 -0.0059310598 2005 1311867785.5211930275 0.2456248403 0.2263853762 0.3266084492 0.0040646254 0.1488240000 982370249 0 402718720 -0.2468845397 -0.1140144393 -0.0059206570 2006 1311867785.5571260452 0.2441718429 0.2263942429 0.3266084492 0.0040655242 0.1602710000 982373265 0 402718720 -0.2463112473 -0.1142248660 -0.0060623740 2007 1311867785.5891211033 0.2446394116 0.2264033336 0.3266084492 0.0040651060 0.1493550000 982376169 0 402718720 -0.2470264137 -0.1141268089 -0.0058255815 2008 1311867785.6211590767 0.2432013601 0.2264116992 0.3266084492 0.0040772414 0.1498830000 982379129 0 402718720 -0.2461927980 -0.1136016399 -0.0061626309 2009 1311867785.6570439339 0.2433306426 0.2264201208 0.3266084492 0.0040815751 0.1499710000 982382145 0 402718720 -0.2464520782 -0.1141908690 -0.0062311296 2010 1311867785.6892280579 0.2437684089 0.2264287517 0.3266084492 0.0040806761 0.1606580000 982384993 0 402718720 -0.2469933778 -0.1145392433 -0.0063041677 2011 1311867785.7214241028 0.2433395833 0.2264371609 0.3266084492 0.0040824770 0.1737120000 982387897 0 402718720 -0.2470552921 -0.1139714792 -0.0064331209 2012 1311867785.7573668957 0.2432007045 0.2264454927 0.3266084492 0.0040820395 0.1506640000 982390913 0 402718720 -0.2473084629 -0.1143487915 -0.0067077968 2013 1311867785.7892301083 0.2434386909 0.2264539344 0.3266084492 0.0040818627 0.1507730000 982393817 0 402718720 -0.2476573139 -0.1148672402 -0.0066584731 2014 1311867785.8210389614 0.2437797934 0.2264625371 0.3266084492 0.0040809190 0.1505750000 982396721 0 402718720 -0.2480198592 -0.1149621978 -0.0065762484 2015 1311867785.8574340343 0.2448991090 0.2264716868 0.3266084492 0.0040805837 0.1756310000 982399737 0 402718720 -0.2495653331 -0.1146951690 -0.0064390562 2016 1311867785.8893110752 0.2449058443 0.2264808307 0.3266084492 0.0040797256 0.1503650000 982402697 0 402718720 -0.2495808899 -0.1151441559 -0.0063005160 2017 1311867785.9211509228 0.2450176626 0.2264900210 0.3266084492 0.0040796386 0.1508270000 982405601 0 402718720 -0.2501345277 -0.1146543324 -0.0061458484 2018 1311867785.9588449001 0.2454414815 0.2264994122 0.3266084492 0.0040801253 0.1505600000 982408617 0 402718720 -0.2507457137 -0.1146501452 -0.0061072516 2019 1311867785.9892621040 0.2456585765 0.2265089017 0.3266084492 0.0040792359 0.1515160000 982411521 0 402718720 -0.2513810396 -0.1144435108 -0.0059315944 2020 1311867786.0210618973 0.2452821732 0.2265181954 0.3266084492 0.0040783379 0.1642200000 982414425 0 402718720 -0.2514028251 -0.1139994040 -0.0057567167 2021 1311867786.0572268963 0.2453422397 0.2265275096 0.3266084492 0.0040783352 0.1520220000 982417385 0 402718720 -0.2520583868 -0.1142029613 -0.0056260601 2022 1311867786.0892500877 0.2455547154 0.2265369197 0.3266084492 0.0040777409 0.1519640000 982420345 0 402718720 -0.2525818646 -0.1149999872 -0.0054435460 2023 1311867786.1211619377 0.2453418672 0.2265462152 0.3266084492 0.0040770044 0.1513930000 982423305 0 402718720 -0.2528610229 -0.1148566604 -0.0052670753 2024 1311867786.1570990086 0.2452231646 0.2265554430 0.3266084492 0.0040760596 0.1511440000 982426265 0 402718720 -0.2534407377 -0.1142284796 -0.0052415184 2025 1311867786.1891019344 0.2458070070 0.2265649499 0.3266084492 0.0040753601 0.1601400000 982429113 0 402718720 -0.2544290125 -0.1151915193 -0.0050494783 2026 1311867786.2216470242 0.2456170917 0.2265743538 0.3266084492 0.0040744518 0.1510540000 982432017 0 402718720 -0.2548244894 -0.1150890961 -0.0050585940 2027 1311867786.2570950985 0.2454213500 0.2265836517 0.3266084492 0.0040735299 0.1627930000 982435089 0 402718720 -0.2552154958 -0.1146102995 -0.0050138026 2028 1311867786.2895779610 0.2456626743 0.2265930595 0.3266084492 0.0040731926 0.1521270000 982437937 0 402718720 -0.2558011711 -0.1153494120 -0.0048973388 2029 1311867786.3211650848 0.2460513711 0.2266026496 0.3266084492 0.0040729265 0.1510460000 982440785 0 402718720 -0.2563512921 -0.1156605259 -0.0048612515 2030 1311867786.3572299480 0.2458109260 0.2266121118 0.3266084492 0.0040720550 0.1625930000 982443857 0 402718720 -0.2565024197 -0.1151360720 -0.0047877813 2031 1311867786.3891439438 0.2457502484 0.2266215349 0.3266084492 0.0040712777 0.1521280000 982446705 0 402718720 -0.2567366064 -0.1156353951 -0.0046778200 2032 1311867786.4213869572 0.2456937134 0.2266309208 0.3266084492 0.0040707331 0.1510540000 982449665 0 402718720 -0.2566730380 -0.1168001220 -0.0044640987 2033 1311867786.4573409557 0.2460550815 0.2266404752 0.3266084492 0.0040712245 0.1509750000 982452681 0 402718720 -0.2574063241 -0.1160299256 -0.0042143925 2034 1311867786.4891700745 0.2455574274 0.2266497756 0.3266084492 0.0040714703 0.1510430000 982455529 0 402718720 -0.2573280632 -0.1162889376 -0.0039980658 2035 1311867786.5218079090 0.2451998144 0.2266588911 0.3266084492 0.0040716272 0.1737140000 982458489 0 402718720 -0.2571269870 -0.1172421053 -0.0037933809 2036 1311867786.5572519302 0.2451625615 0.2266679793 0.3266084492 0.0040707211 0.1515320000 982461505 0 402718720 -0.2574315965 -0.1169805527 -0.0036212446 2037 1311867786.5895760059 0.2454992384 0.2266772239 0.3266084492 0.0040700715 0.1618780000 982464409 0 402718720 -0.2583238184 -0.1172052622 -0.0034170628 2038 1311867786.6211080551 0.2460793555 0.2266867441 0.3266084492 0.0040700212 0.1507490000 982467313 0 402718720 -0.2590555251 -0.1179164350 -0.0030722083 2039 1311867786.6573529243 0.2450803965 0.2266957650 0.3266084492 0.0040702246 0.1508490000 982470329 0 402718720 -0.2582988739 -0.1178843081 -0.0031151064 2040 1311867786.6891629696 0.2450150847 0.2267047451 0.3266084492 0.0040694645 0.1627960000 982473177 0 402718720 -0.2585605085 -0.1178681701 -0.0028617899 2041 1311867786.7210969925 0.2453287691 0.2267138700 0.3266084492 0.0040686918 0.1504600000 982476081 0 402718720 -0.2591939270 -0.1181723550 -0.0026305767 2042 1311867786.7570719719 0.2448545992 0.2267227538 0.3266084492 0.0040680744 0.1506530000 982479041 0 402718720 -0.2591338158 -0.1177185401 -0.0026364059 2043 1311867786.7892940044 0.2444542348 0.2267314330 0.3266084492 0.0040672491 0.1764620000 982482001 0 402718720 -0.2591027021 -0.1169408560 -0.0024454701 2044 1311867786.8211419582 0.2447076440 0.2267402276 0.3266084492 0.0040663272 0.1504310000 982484905 0 402718720 -0.2595748007 -0.1175513938 -0.0020523297 2045 1311867786.8575630188 0.2440262139 0.2267486804 0.3266084492 0.0040668102 0.1614660000 982487865 0 402718720 -0.2594271302 -0.1175449416 -0.0016877363 2046 1311867786.8893759251 0.2440765053 0.2267571495 0.3266084492 0.0040683360 0.1514810000 982490825 0 402718720 -0.2593806684 -0.1167384312 -0.0013388405 2047 1311867786.9211881161 0.2436466813 0.2267654004 0.3266084492 0.0040708538 0.1515540000 982493729 0 402718720 -0.2594532967 -0.1172481030 -0.0010760685 2048 1311867786.9576020241 0.2439192086 0.2267737763 0.3266084492 0.0040698785 0.1621900000 982496801 0 402718720 -0.2597823143 -0.1171910167 -0.0007778318 2049 1311867786.9892089367 0.2426187694 0.2267815093 0.3266084492 0.0040701026 0.1513080000 982499593 0 402718720 -0.2591244876 -0.1165173277 -0.0007205328 2050 1311867787.0211400986 0.2433532625 0.2267895931 0.3266084492 0.0040691956 0.1628080000 982912153 0 402718720 -0.2595740259 -0.1172587797 -0.0006065475 2051 1311867787.0571250916 0.2434276491 0.2267977053 0.3266084492 0.0040684063 0.1506830000 982915225 0 402718720 -0.2596568763 -0.1179827154 -0.0002508094 2052 1311867787.0895950794 0.2431203276 0.2268056598 0.3266084492 0.0040677128 0.1501710000 982918073 0 402718720 -0.2596651018 -0.1172995120 -0.0000598570 2053 1311867787.1239550114 0.2431737781 0.2268136325 0.3266084492 0.0040675414 0.1509670000 982921033 0 402718720 -0.2599684298 -0.1182733923 0.0000166216 2054 1311867787.1573429108 0.2432642281 0.2268216416 0.3266084492 0.0040675377 0.1506550000 982923993 0 402718720 -0.2604034245 -0.1183428839 0.0000552712 2055 1311867787.1892991066 0.2424685359 0.2268292557 0.3266084492 0.0040667508 0.1593100000 982926897 0 402718720 -0.2599990964 -0.1171916798 0.0000571055 2056 1311867787.2230238914 0.2423830926 0.2268368207 0.3266084492 0.0040662604 0.1506270000 982929857 0 402718720 -0.2600757182 -0.1182400584 0.0002500888 2057 1311867787.2571809292 0.2427302450 0.2268445473 0.3266084492 0.0040659989 0.1624410000 982932817 0 402718720 -0.2607584894 -0.1181302518 0.0004717436 2058 1311867787.2893400192 0.2422083616 0.2268520127 0.3266084492 0.0040650630 0.1506960000 982935721 0 402718720 -0.2606653869 -0.1176053435 0.0006515256 2059 1311867787.3217399120 0.2423760146 0.2268595522 0.3266084492 0.0040650060 0.1505720000 982938625 0 402718720 -0.2610730231 -0.1185840815 0.0006166597 2060 1311867787.3572421074 0.2428470105 0.2268673131 0.3266084492 0.0040647554 0.1618530000 982941641 0 402718720 -0.2614789307 -0.1190197766 0.0006567799 2061 1311867787.3892920017 0.2417947352 0.2268745560 0.3266084492 0.0040638511 0.1503140000 982944545 0 402718720 -0.2609340847 -0.1182208806 0.0003916582 2062 1311867787.4245440960 0.2419602424 0.2268818720 0.3266084492 0.0040635538 0.1504990000 982947505 0 402718720 -0.2616914809 -0.1186516434 0.0002049835 2063 1311867787.4572229385 0.2421644032 0.2268892799 0.3266084492 0.0040626976 0.1502280000 982950465 0 402718720 -0.2620058060 -0.1191993579 0.0001818743 2064 1311867787.4892969131 0.2418153584 0.2268965115 0.3266084492 0.0040617895 0.1508220000 982953313 0 402718720 -0.2619433999 -0.1186314821 -0.0000148406 2065 1311867787.5220890045 0.2419187278 0.2269037862 0.3266084492 0.0040609494 0.1657440000 982956217 0 402718720 -0.2624233663 -0.1190717220 -0.0000882351 2066 1311867787.5581040382 0.2421751916 0.2269111780 0.3266084492 0.0040601524 0.1501170000 982959233 0 402718720 -0.2628997862 -0.1196741536 -0.0002998280 2067 1311867787.5897688866 0.2411245108 0.2269180543 0.3266084492 0.0040596610 0.1500260000 982962193 0 402718720 -0.2623796165 -0.1189300492 -0.0007994663 2068 1311867787.6235499382 0.2412189096 0.2269249696 0.3266084492 0.0040589349 0.1605950000 982965097 0 402718720 -0.2631015480 -0.1187761426 -0.0008958575 2069 1311867787.6574609280 0.2417590171 0.2269321393 0.3266084492 0.0040582240 0.1498670000 982968057 0 402718720 -0.2638880908 -0.1195303649 -0.0010008026 2070 1311867787.6898610592 0.2417831868 0.2269393137 0.3266084492 0.0040577455 0.1620840000 982971017 0 402718720 -0.2641356885 -0.1196349412 -0.0012424412 2071 1311867787.7212240696 0.2410775721 0.2269461405 0.3266084492 0.0040568590 0.1501170000 982973921 0 402718720 -0.2637310326 -0.1189703420 -0.0013898741 2072 1311867787.7579810619 0.2402512133 0.2269525619 0.3266084492 0.0040571745 0.1508080000 982976937 0 402718720 -0.2635213137 -0.1185251549 -0.0015265330 2073 1311867787.7901558876 0.2406040579 0.2269591472 0.3266084492 0.0040565251 0.1510230000 982979841 0 402718720 -0.2642052174 -0.1186853349 -0.0018079160 2074 1311867787.8218519688 0.2397340983 0.2269653068 0.3266084492 0.0040566444 0.1503690000 982982801 0 402718720 -0.2637210190 -0.1184950024 -0.0022008757 2075 1311867787.8573749065 0.2405931801 0.2269718745 0.3266084492 0.0040563913 0.1588670000 982985705 0 402718720 -0.2648783326 -0.1192923561 -0.0022307518 2076 1311867787.8894400597 0.2408244610 0.2269785472 0.3266084492 0.0040555403 0.1608960000 982988665 0 402718720 -0.2652548552 -0.1199815124 -0.0024351168 2077 1311867787.9214320183 0.2398139238 0.2269847270 0.3266084492 0.0040549294 0.1515860000 982991625 0 402718720 -0.2647759616 -0.1194557995 -0.0028649569 2078 1311867787.9577279091 0.2398499548 0.2269909181 0.3266084492 0.0040541416 0.1514550000 982994585 0 402718720 -0.2654427886 -0.1197837219 -0.0030741100 2079 1311867787.9892189503 0.2399158776 0.2269971350 0.3266084492 0.0040532939 0.1514570000 982997433 0 402718720 -0.2659763992 -0.1197714508 -0.0033022137 2080 1311867788.0211091042 0.2396756411 0.2270032305 0.3266084492 0.0040529589 0.1632940000 983000393 0 402718720 -0.2662683725 -0.1191045120 -0.0039379606 2081 1311867788.0577259064 0.2400412112 0.2270094957 0.3266084492 0.0040522437 0.1523070000 983003465 0 402718720 -0.2672862709 -0.1187930778 -0.0041487417 2082 1311867788.0892241001 0.2403607219 0.2270159084 0.3266084492 0.0040518903 0.1514270000 983006313 0 402718720 -0.2680500448 -0.1187211871 -0.0040702214 2083 1311867788.1307280064 0.2407677174 0.2270225103 0.3266084492 0.0040533372 0.1518940000 983009497 0 402718720 -0.2690904438 -0.1188295409 -0.0041105403 2084 1311867788.1572849751 0.2398916036 0.2270286855 0.3266084492 0.0040526914 0.1519700000 983012289 0 402718720 -0.2690618336 -0.1180053875 -0.0038827125 2085 1311867788.1904621124 0.2389131784 0.2270343855 0.3266084492 0.0040520987 0.1532420000 983015193 0 402718720 -0.2690355778 -0.1176613718 -0.0037492937 2086 1311867788.2247180939 0.2383640110 0.2270398168 0.3266084492 0.0040514752 0.1526330000 983018153 0 402718720 -0.2692847550 -0.1166858897 -0.0038257218 2087 1311867788.2583730221 0.2383447438 0.2270452336 0.3266084492 0.0040518818 0.1533380000 983021057 0 402718720 -0.2700760067 -0.1162045747 -0.0036740934 2088 1311867788.2893440723 0.2382746339 0.2270506117 0.3266084492 0.0040522158 0.1540610000 983023961 0 402718720 -0.2706415951 -0.1163898408 -0.0034883253 2089 1311867788.3251628876 0.2389131039 0.2270562902 0.3266084492 0.0040517058 0.1533420000 983026977 0 402718720 -0.2718167305 -0.1164584160 -0.0029839384 2090 1311867788.3571081161 0.2400983125 0.2270625304 0.3266084492 0.0040512050 0.1544660000 983029881 0 402718720 -0.2734801471 -0.1162376702 -0.0026846325 2091 1311867788.3910779953 0.2402426898 0.2270688337 0.3266084492 0.0040506887 0.1543700000 983032841 0 402718720 -0.2744120061 -0.1161584109 -0.0022011104 2092 1311867788.4251430035 0.2414510846 0.2270757086 0.3266084492 0.0040502680 0.1549570000 983035801 0 402718720 -0.2760823667 -0.1167313010 -0.0018780655 2093 1311867788.4573140144 0.2414427847 0.2270825729 0.3266084492 0.0040496358 0.1660090000 983038705 0 402718720 -0.2765151560 -0.1169900745 -0.0018647239 2094 1311867788.4924380779 0.2417641729 0.2270895842 0.3266084492 0.0040492136 0.1544300000 983041665 0 402718720 -0.2772810161 -0.1173928007 -0.0014000934 2095 1311867788.5262899399 0.2410932928 0.2270962685 0.3266084492 0.0040485113 0.1638200000 983044625 0 402718720 -0.2772206962 -0.1175309792 -0.0013145515 2096 1311867788.5573079586 0.2424163520 0.2271035778 0.3266084492 0.0040480040 0.1544030000 983047529 0 402718720 -0.2791100740 -0.1176701039 -0.0013613761 2097 1311867788.5915369987 0.2424151301 0.2271108794 0.3266084492 0.0040472491 0.1535780000 983050489 0 402718720 -0.2798607349 -0.1173912063 -0.0015379627 2098 1311867788.6251940727 0.2426827550 0.2271183016 0.3266084492 0.0040468306 0.1544420000 983053393 0 402718720 -0.2809338272 -0.1176286787 -0.0013662857 2099 1311867788.6593029499 0.2413100898 0.2271250629 0.3266084492 0.0040460413 0.1539740000 983056353 0 402718720 -0.2800112367 -0.1176192313 -0.0016700642 2100 1311867788.6898009777 0.2427465916 0.2271325017 0.3266084492 0.0040456841 0.1645550000 983059257 0 402718720 -0.2822383344 -0.1172765195 -0.0019271142 2101 1311867788.7262809277 0.2430090606 0.2271400583 0.3266084492 0.0040452013 0.1542400000 983062329 0 402718720 -0.2832789123 -0.1179206893 -0.0019439373 2102 1311867788.7571070194 0.2416427732 0.2271469578 0.3266084492 0.0040444830 0.1653820000 983065233 0 402718720 -0.2825257480 -0.1182811856 -0.0023847332 2103 1311867788.7899940014 0.2431772500 0.2271545804 0.3266084492 0.0040445320 0.1537990000 983068081 0 402718720 -0.2847724557 -0.1178946197 -0.0026525923 2104 1311867788.8253190517 0.2432314456 0.2271622215 0.3266084492 0.0040447011 0.1533000000 983071153 0 402718720 -0.2856637836 -0.1184623241 -0.0028946544 2105 1311867788.8572509289 0.2430713028 0.2271697793 0.3266084492 0.0040438110 0.1811790000 983074057 0 402718720 -0.2859744728 -0.1192336902 -0.0032252290 2106 1311867788.8892900944 0.2436588407 0.2271776088 0.3266084492 0.0040436165 0.1540330000 983076905 0 402718720 -0.2871976197 -0.1190476865 -0.0036180073 2107 1311867788.9253408909 0.2428335547 0.2271850393 0.3266084492 0.0040438503 0.1535510000 983079977 0 402718720 -0.2873308361 -0.1190790534 -0.0037849720 2108 1311867788.9572029114 0.2432196736 0.2271926458 0.3266084492 0.0040432949 0.1764850000 983082881 0 402718720 -0.2879729271 -0.1193032041 -0.0039290506 2109 1311867788.9914720058 0.2436744571 0.2272004608 0.3266084492 0.0040428091 0.1530520000 983085841 0 402718720 -0.2892058492 -0.1197636276 -0.0039946986 2110 1311867789.0253350735 0.2437556684 0.2272083069 0.3266084492 0.0040424448 0.1540110000 983088745 0 402718720 -0.2899155617 -0.1194626167 -0.0040303990 2111 1311867789.0572888851 0.2431249619 0.2272158468 0.3266084492 0.0040417522 0.1539900000 983091649 0 402718720 -0.2900028825 -0.1186045110 -0.0040157456 2112 1311867789.0921590328 0.2428971529 0.2272232716 0.3266084492 0.0040416673 0.1539290000 983094665 0 402718720 -0.2904555798 -0.1188851148 -0.0038441010 2113 1311867789.1266920567 0.2428146005 0.2272306504 0.3266084492 0.0040410789 0.1550200000 983097681 0 402718720 -0.2909967601 -0.1185361221 -0.0037689107 2114 1311867789.1574180126 0.2432827652 0.2272382436 0.3266084492 0.0040405875 0.1539820000 983100473 0 402718720 -0.2917205095 -0.1185314804 -0.0038092784 2115 1311867789.1895699501 0.2445515841 0.2272464296 0.3266084492 0.0040396620 0.1711500000 983103433 0 402718720 -0.2933175862 -0.1192602739 -0.0038472619 2116 1311867789.2251811028 0.2430360615 0.2272538916 0.3266084492 0.0040389152 0.1550790000 983106449 0 402718720 -0.2923524380 -0.1192986667 -0.0038876610 2117 1311867789.2573940754 0.2433274835 0.2272614843 0.3266084492 0.0040389941 0.1548690000 983109297 0 402718720 -0.2932253182 -0.1191453412 -0.0040280689 2118 1311867789.2926049232 0.2437100857 0.2272692504 0.3266084492 0.0040384201 0.1547300000 983112313 0 402718720 -0.2943207920 -0.1193886995 -0.0044037383 2119 1311867789.3252000809 0.2438367605 0.2272770689 0.3266084492 0.0040375592 0.1547560000 983115273 0 402718720 -0.2949348688 -0.1201839000 -0.0045282831 2120 1311867789.3589100838 0.2436304092 0.2272847827 0.3266084492 0.0040367279 0.1660490000 983118177 0 402718720 -0.2953821421 -0.1204750389 -0.0049122567 2121 1311867789.3897531033 0.2444574237 0.2272928792 0.3266084492 0.0040362919 0.1548220000 983121081 0 402718720 -0.2969100773 -0.1202005818 -0.0051754550 2122 1311867789.4252359867 0.2442811280 0.2273008850 0.3266084492 0.0040360915 0.1548060000 983124097 0 402718720 -0.2974857390 -0.1204009503 -0.0055312105 2123 1311867789.4577910900 0.2435656339 0.2273085462 0.3266084492 0.0040354571 0.1542340000 983126945 0 402718720 -0.2974559367 -0.1207966506 -0.0057866294 2124 1311867789.4892559052 0.2441928536 0.2273164955 0.3266084492 0.0040349519 0.1663900000 983129905 0 402718720 -0.2986388803 -0.1207312196 -0.0061028036 2125 1311867789.5256059170 0.2450730950 0.2273248516 0.3266084492 0.0040347545 0.1641370000 983132865 0 402718720 -0.3002389073 -0.1209829375 -0.0063378583 2126 1311867789.5572779179 0.2449267209 0.2273331309 0.3266084492 0.0040341236 0.1655460000 983135769 0 402718720 -0.3009113669 -0.1211990342 -0.0064640930 2127 1311867789.5892720222 0.2449673116 0.2273414215 0.3266084492 0.0040332449 0.1532140000 983138617 0 402718720 -0.3015698493 -0.1214850247 -0.0065657408 2128 1311867789.6253700256 0.2456050813 0.2273500041 0.3266084492 0.0040327225 0.1533510000 983141689 0 402718720 -0.3030955493 -0.1209312230 -0.0067900904 2129 1311867789.6574499607 0.2447947264 0.2273581979 0.3266084492 0.0040318655 0.1538630000 983144593 0 402718720 -0.3030680120 -0.1203465387 -0.0069966810 2130 1311867789.6894960403 0.2446315885 0.2273663075 0.3266084492 0.0040310158 0.1640270000 983147441 0 402718720 -0.3037477732 -0.1199477911 -0.0070026433 2131 1311867789.7253561020 0.2442679554 0.2273742388 0.3266084492 0.0040329733 0.1538980000 983150457 0 402718720 -0.3042836785 -0.1187870502 -0.0073908437 2132 1311867789.7572269440 0.2434536517 0.2273817808 0.3266084492 0.0040324016 0.1665400000 983153361 0 402718720 -0.3044312000 -0.1175948083 -0.0076168622 2133 1311867789.7893610001 0.2426085919 0.2273889194 0.3266084492 0.0040323417 0.1556650000 983156265 0 402718720 -0.3043949604 -0.1169045493 -0.0077321148 2134 1311867789.8253350258 0.2437261939 0.2273965752 0.3266084492 0.0040318717 0.1562560000 983159281 0 402718720 -0.3058803678 -0.1171717867 -0.0077396347 2135 1311867789.8573670387 0.2429891974 0.2274038785 0.3266084492 0.0040310695 0.1769640000 983162241 0 402718720 -0.3056345582 -0.1169580966 -0.0077581923 2136 1311867789.8893530369 0.2412677705 0.2274103691 0.3266084492 0.0040303310 0.1569000000 983165089 0 402718720 -0.3047429025 -0.1165731326 -0.0077816099 2137 1311867789.9253480434 0.2418822199 0.2274171411 0.3266084492 0.0040294301 0.1572800000 983168105 0 402718720 -0.3063336313 -0.1163537055 -0.0076666633 2138 1311867789.9573481083 0.2418001443 0.2274238684 0.3266084492 0.0040290559 0.1575210000 983170953 0 402718720 -0.3071385622 -0.1160382628 -0.0076385797 2139 1311867789.9892580509 0.2424647361 0.2274309002 0.3266084492 0.0040290315 0.1572320000 983173857 0 402718720 -0.3083164692 -0.1161158010 -0.0076154554 2140 1311867790.0253860950 0.2423405647 0.2274378673 0.3266084492 0.0040283357 0.1859050000 983176929 0 402718720 -0.3091516793 -0.1158548445 -0.0075867474 2141 1311867790.0572309494 0.2420273870 0.2274446816 0.3266084492 0.0040275929 0.1579860000 983179777 0 402718720 -0.3095855713 -0.1152785718 -0.0074873879 2142 1311867790.0896899700 0.2418088466 0.2274513876 0.3266084492 0.0040274723 0.1579450000 983182737 0 402718720 -0.3099088967 -0.1149768531 -0.0074156844 2143 1311867790.1257700920 0.2428453118 0.2274585710 0.3266084492 0.0040272376 0.1580530000 983185753 0 402718720 -0.3117019832 -0.1147144288 -0.0073840935 2144 1311867790.1572160721 0.2416260093 0.2274651789 0.3266084492 0.0040267159 0.1578450000 983188601 0 402718720 -0.3111085892 -0.1145306528 -0.0072280057 2145 1311867790.1894400120 0.2427542061 0.2274723067 0.3266084492 0.0040260935 0.1735360000 983191561 0 402718720 -0.3127581477 -0.1143530086 -0.0071475948 2146 1311867790.2254109383 0.2430305928 0.2274795566 0.3266084492 0.0040259643 0.1582390000 983194577 0 402718720 -0.3135949671 -0.1141081229 -0.0067717736 2147 1311867790.2576739788 0.2421584725 0.2274863935 0.3266084492 0.0040254776 0.1591130000 983197537 0 402718720 -0.3134231269 -0.1138293669 -0.0066842358 2148 1311867790.2894508839 0.2429467589 0.2274935911 0.3266084492 0.0040253287 0.1741840000 983200385 0 402718720 -0.3145733476 -0.1138329804 -0.0066779945 2149 1311867790.3254859447 0.2449256033 0.2275017027 0.3266084492 0.0040261934 0.1620630000 983203401 0 402718720 -0.3171755075 -0.1139766499 -0.0064225039 2150 1311867790.3573629856 0.2439915687 0.2275093725 0.3266084492 0.0040269288 0.1713260000 983206305 0 402718720 -0.3166293800 -0.1138638407 -0.0064680013 2151 1311867790.3896288872 0.2438368946 0.2275169631 0.3266084492 0.0040262554 0.1615460000 983209209 0 402718720 -0.3171010017 -0.1139674932 -0.0065123579 2152 1311867790.4259679317 0.2442876548 0.2275247562 0.3266084492 0.0040282896 0.1621720000 983212281 0 402718720 -0.3178838491 -0.1138273850 -0.0067978906 2153 1311867790.4603750706 0.2455757856 0.2275331403 0.3266084492 0.0040293588 0.1617840000 983215241 0 402718720 -0.3199128509 -0.1137114018 -0.0067519764 2154 1311867790.4893760681 0.2454292029 0.2275414486 0.3266084492 0.0040289133 0.1615270000 983218033 0 402718720 -0.3201952577 -0.1137204096 -0.0065411609 2155 1311867790.5260839462 0.2458175272 0.2275499294 0.3266084492 0.0040296795 0.1709510000 983221049 0 402718720 -0.3210538030 -0.1131077036 -0.0067674313 2156 1311867790.5578188896 0.2457441092 0.2275583682 0.3266084492 0.0040301906 0.1624560000 983223897 0 402718720 -0.3214055300 -0.1124697551 -0.0066664759 2157 1311867790.5941619873 0.2469449341 0.2275673560 0.3266084492 0.0040326821 0.1619890000 983226913 0 402718720 -0.3226796687 -0.1124949306 -0.0066947923 2158 1311867790.6255199909 0.2467006892 0.2275762222 0.3266084492 0.0040326331 0.1623030000 983229873 0 402718720 -0.3230768144 -0.1126760393 -0.0067876880 2159 1311867790.6573970318 0.2474510968 0.2275854278 0.3266084492 0.0040336161 0.1621050000 983232665 0 402718720 -0.3246627748 -0.1127117127 -0.0070019737 2160 1311867790.6901810169 0.2480448037 0.2275948998 0.3266084492 0.0040333012 0.1732430000 983235625 0 402718720 -0.3258484900 -0.1127243266 -0.0068982705 2161 1311867790.7253530025 0.2478431165 0.2276042696 0.3266084492 0.0040326360 0.1623920000 983238585 0 402718720 -0.3262685239 -0.1124396473 -0.0070367302 2162 1311867790.7575750351 0.2463605404 0.2276129450 0.3266084492 0.0040320231 0.1616560000 983241489 0 402718720 -0.3254330754 -0.1118667424 -0.0072435909 2163 1311867790.7912769318 0.2474905699 0.2276221349 0.3266084492 0.0040339681 0.1737300000 983244449 0 402718720 -0.3270959854 -0.1111756563 -0.0071499562 2164 1311867790.8261909485 0.2467738241 0.2276309850 0.3266084492 0.0040334345 0.1624920000 983247465 0 402718720 -0.3270361423 -0.1102508008 -0.0072118365 2165 1311867790.8573698997 0.2457975298 0.2276393760 0.3266084492 0.0040327864 0.1773950000 983250369 0 402718720 -0.3264253139 -0.1099457443 -0.0071493122 2166 1311867790.8950428963 0.2461228967 0.2276479095 0.3266084492 0.0040325463 0.1621920000 983253385 0 402718720 -0.3270632625 -0.1092666611 -0.0068472894 2167 1311867790.9258179665 0.2456350923 0.2276562100 0.3266084492 0.0040321412 0.1630130000 983256289 0 402718720 -0.3269888163 -0.1080607027 -0.0070224362 2168 1311867790.9607090950 0.2447235435 0.2276640824 0.3266084492 0.0040321900 0.1633530000 983259249 0 402718720 -0.3267802596 -0.1073232740 -0.0070306067 2169 1311867790.9944651127 0.2444567084 0.2276718245 0.3266084492 0.0040323537 0.1630590000 983262209 0 402718720 -0.3268698454 -0.1070812643 -0.0066090086 2170 1311867791.0299000740 0.2447874397 0.2276797119 0.3266084492 0.0040324780 0.1849920000 983265225 0 402718720 -0.3274908960 -0.1069237515 -0.0064703804 2171 1311867791.0577330589 0.2442701012 0.2276873537 0.3266084492 0.0040320738 0.1892420000 983267905 0 402718720 -0.3276347518 -0.1062399521 -0.0065743509 2172 1311867791.0913140774 0.2446238399 0.2276951513 0.3266084492 0.0040313091 0.1632970000 983270921 0 402718720 -0.3282714188 -0.1061693653 -0.0065863533 2173 1311867791.1254060268 0.2445874810 0.2277029251 0.3266084492 0.0040331239 0.1616130000 983273881 0 402718720 -0.3287319839 -0.1057549194 -0.0065579568 2174 1311867791.1664540768 0.2436990738 0.2277102830 0.3266084492 0.0040336772 0.1632930000 983277065 0 402718720 -0.3285359442 -0.1045752168 -0.0065341266 2175 1311867791.1905651093 0.2436223626 0.2277175989 0.3266084492 0.0040345666 0.1833800000 983279745 0 402718720 -0.3287782967 -0.1040884331 -0.0067078169 2176 1311867791.2257969379 0.2470847666 0.2277264992 0.3266084492 0.0040349111 0.1636680000 983282761 0 402718720 -0.3325861394 -0.1051261127 -0.0062666358 2177 1311867791.2579009533 0.2467886657 0.2277352554 0.3266084492 0.0040355941 0.1634200000 983285609 0 402718720 -0.3329750597 -0.1057320163 -0.0061865547 2178 1311867791.2920219898 0.2482376397 0.2277446688 0.3266084492 0.0040349127 0.1625360000 983288569 0 402718720 -0.3348896801 -0.1061278433 -0.0059243562 2179 1311867791.3277790546 0.2473496944 0.2277536661 0.3266084492 0.0040359054 0.1609970000 983291585 0 402718720 -0.3343301415 -0.1063496545 -0.0060733557 2180 1311867791.3597049713 0.2482035905 0.2277630468 0.3266084492 0.0040372983 0.1850410000 983294545 0 402718720 -0.3358980715 -0.1064796001 -0.0060280073 2181 1311867791.3896780014 0.2476285398 0.2277721552 0.3266084492 0.0040365531 0.1621500000 983297393 0 402718720 -0.3360030651 -0.1061706692 -0.0061868685 2182 1311867791.4270040989 0.2478237599 0.2277813447 0.3266084492 0.0040365451 0.1617190000 983300465 0 402718720 -0.3371070623 -0.1057918742 -0.0060357885 2183 1311867791.4574470520 0.2490359396 0.2277910812 0.3266084492 0.0040357867 0.1616890000 983303313 0 402718720 -0.3388615549 -0.1059983671 -0.0056820917 2184 1311867791.4916520119 0.2494550496 0.2278010006 0.3266084492 0.0040378630 0.1611980000 983306273 0 402718720 -0.3397813439 -0.1057195365 -0.0054689129 2185 1311867791.5275359154 0.2477322966 0.2278101224 0.3266084492 0.0040372206 0.1731040000 983309289 0 402718720 -0.3385747373 -0.1054388881 -0.0056872750 2186 1311867791.5593819618 0.2483978719 0.2278195404 0.3266084492 0.0040382881 0.1607810000 983312193 0 402718720 -0.3396843076 -0.1056131646 -0.0054085962 2187 1311867791.5894811153 0.2469074279 0.2278282683 0.3266084492 0.0040377661 0.1617780000 983315041 0 402718720 -0.3387805521 -0.1047190726 -0.0054772068 2188 1311867791.6275899410 0.2467000633 0.2278368935 0.3266084492 0.0040373922 0.1599120000 983318113 0 402718720 -0.3390387297 -0.1045064852 -0.0055535501 2189 1311867791.6574349403 0.2472312003 0.2278457534 0.3266084492 0.0040372773 0.1609890000 983321017 0 402718720 -0.3398495615 -0.1041471511 -0.0056037745 2190 1311867791.6894969940 0.2486461401 0.2278552512 0.3266084492 0.0040366393 0.1606610000 983323865 0 402718720 -0.3413533270 -0.1048501134 -0.0054242760 2191 1311867791.7263259888 0.2504654229 0.2278655708 0.3266084492 0.0040361049 0.1604720000 983326937 0 402718720 -0.3433479071 -0.1049971804 -0.0053271432 2192 1311867791.7602820396 0.2488286346 0.2278751343 0.3266084492 0.0040352983 0.1725850000 983329897 0 402718720 -0.3419094980 -0.1049666107 -0.0055085057 2193 1311867791.7897930145 0.2471573949 0.2278839269 0.3266084492 0.0040348444 0.1704510000 983332745 0 402718720 -0.3403430283 -0.1044479907 -0.0055884174 2194 1311867791.8265190125 0.2489928901 0.2278935481 0.3266084492 0.0040351959 0.1593850000 983335761 0 402718720 -0.3423126936 -0.1045906767 -0.0054867170 2195 1311867791.8574469090 0.2485589087 0.2279029629 0.3266084492 0.0040349663 0.1761160000 983338665 0 402718720 -0.3421207070 -0.1041488275 -0.0054461337 2196 1311867791.8895421028 0.2485097498 0.2279123466 0.3266084492 0.0040340773 0.1587630000 983341513 0 402718720 -0.3422524333 -0.1041140929 -0.0056379624 2197 1311867791.9276258945 0.2501318157 0.2279224602 0.3266084492 0.0040339644 0.1579560000 983344585 0 402718720 -0.3440161049 -0.1043890044 -0.0056275041 2198 1311867791.9574968815 0.2488541901 0.2279319833 0.3266084492 0.0040334282 0.1592030000 983347433 0 402718720 -0.3431709409 -0.1037464589 -0.0057824785 2199 1311867791.9918000698 0.2486247569 0.2279413934 0.3266084492 0.0040326873 0.1707010000 983350281 0 402718720 -0.3430649042 -0.1037252694 -0.0057179583 2200 1311867792.0277240276 0.2512475550 0.2279519871 0.3266084492 0.0040334690 0.1585400000 983353241 0 402718720 -0.3458141088 -0.1040941775 -0.0055564973 2201 1311867792.0615789890 0.2510906756 0.2279624999 0.3266084492 0.0040327156 0.1590150000 983356313 0 402718720 -0.3460274935 -0.1043019965 -0.0054729017 2202 1311867792.0946090221 0.2514451742 0.2279731641 0.3266084492 0.0040321421 0.1581600000 983359161 0 402718720 -0.3465565145 -0.1042616740 -0.0056529553 2203 1311867792.1256630421 0.2528433800 0.2279844534 0.3266084492 0.0040318481 0.1580290000 983362065 0 402718720 -0.3482240736 -0.1040899530 -0.0057500182 2204 1311867792.1595768929 0.2520501912 0.2279953725 0.3266084492 0.0040315955 0.1576780000 983365025 0 402718720 -0.3480525613 -0.1031621695 -0.0056963251 2205 1311867792.1948819160 0.2509804964 0.2280057966 0.3266084492 0.0040350719 0.1782530000 983368041 0 402718720 -0.3472570777 -0.1034813300 -0.0056855013 2206 1311867792.2253580093 0.2521613538 0.2280167465 0.3266084492 0.0040421107 0.1568760000 983370889 0 402718720 -0.3491840363 -0.1031932831 -0.0058645071 2207 1311867792.2575860023 0.2525261343 0.2280278518 0.3266084492 0.0040412707 0.1679740000 983373793 0 402718720 -0.3501593173 -0.1026463881 -0.0058858674 2208 1311867792.2995440960 0.2523665428 0.2280388748 0.3266084492 0.0040406820 0.1694760000 983376977 0 402718720 -0.3506278098 -0.1026586145 -0.0059431922 2209 1311867792.3314530849 0.2525490224 0.2280499704 0.3266084492 0.0040402840 0.1560130000 983379881 0 402718720 -0.3512972593 -0.1023961306 -0.0058073043 2210 1311867792.3589100838 0.2529224753 0.2280612249 0.3266084492 0.0040396532 0.1671640000 983382617 0 402718720 -0.3519666493 -0.1025599167 -0.0059867268 2211 1311867792.3954761028 0.2529902458 0.2280724999 0.3266084492 0.0040388439 0.1562290000 983385689 0 402718720 -0.3525617123 -0.1024471894 -0.0062190606 2212 1311867792.4281890392 0.2511901557 0.2280829509 0.3266084492 0.0040384452 0.1558680000 983388593 0 402718720 -0.3512865305 -0.1025028899 -0.0066725090 2213 1311867792.4589219093 0.2519976497 0.2280937574 0.3266084492 0.0040381965 0.1552750000 983391441 0 402718720 -0.3523635566 -0.1028373912 -0.0068216748 2214 1311867792.4948880672 0.2524749637 0.2281047697 0.3266084492 0.0040377289 0.1665840000 983394457 0 402718720 -0.3532984853 -0.1028600037 -0.0067851730 2215 1311867792.5256149769 0.2521824539 0.2281156399 0.3266084492 0.0040370002 0.1620950000 983397361 0 402718720 -0.3532783389 -0.1027985364 -0.0069242013 2216 1311867792.5579619408 0.2526812255 0.2281267255 0.3266084492 0.0040364468 0.1535290000 983400209 0 402718720 -0.3541889787 -0.1027076244 -0.0069211973 2217 1311867792.5937440395 0.2527029514 0.2281378108 0.3266084492 0.0040356126 0.1535760000 983403169 0 402718720 -0.3543693423 -0.1027795151 -0.0069603557 2218 1311867792.6254990101 0.2518022358 0.2281484801 0.3266084492 0.0040350561 0.1531760000 983406017 0 402718720 -0.3540299237 -0.1025326699 -0.0071757156 2219 1311867792.6587610245 0.2502761781 0.2281584520 0.3266084492 0.0040346535 0.1523790000 983408977 0 402718720 -0.3528922796 -0.1020861119 -0.0072951075 2220 1311867792.6947619915 0.2502556741 0.2281684057 0.3266084492 0.0040340733 0.1746210000 983411993 0 402718720 -0.3532313406 -0.1024690941 -0.0073269447 2221 1311867792.7254660130 0.2500350475 0.2281782511 0.3266084492 0.0040337502 0.1508370000 983414897 0 402718720 -0.3528984785 -0.1028785184 -0.0074419570 2222 1311867792.7574810982 0.2508805990 0.2281884682 0.3266084492 0.0040328520 0.1505420000 983417801 0 402718720 -0.3542848527 -0.1030004993 -0.0072988924 2223 1311867792.7968890667 0.2499180883 0.2281982431 0.3266084492 0.0040335167 0.1499100000 983420929 0 402718720 -0.3537975252 -0.1030551642 -0.0074458290 2224 1311867792.8254449368 0.2510496676 0.2282085180 0.3266084492 0.0040330975 0.1495950000 983423665 0 402718720 -0.3552143872 -0.1030583307 -0.0072250767 2225 1311867792.8578031063 0.2508452237 0.2282186918 0.3266084492 0.0040330790 0.1571050000 983426569 0 402718720 -0.3557454944 -0.1025699303 -0.0070602009 2226 1311867792.8974819183 0.2478198409 0.2282274974 0.3266084492 0.0040327462 0.1484000000 983429753 0 402718720 -0.3534756303 -0.1023157686 -0.0074339379 2227 1311867792.9254279137 0.2478004843 0.2282362863 0.3266084492 0.0040320039 0.1474000000 983432489 0 402718720 -0.3537894189 -0.1022825241 -0.0074631739 2228 1311867792.9580180645 0.2490060925 0.2282456085 0.3266084492 0.0040321071 0.1473260000 983435449 0 402718720 -0.3552882969 -0.1020679474 -0.0075939996 2229 1311867792.9958879948 0.2490817010 0.2282549562 0.3266084492 0.0040318166 0.1466020000 983438521 0 402718720 -0.3564465046 -0.1018852666 -0.0073557189 2230 1311867793.0254249573 0.2477978021 0.2282637199 0.3266084492 0.0040312597 0.1562700000 983441313 0 402718720 -0.3557527065 -0.1020044461 -0.0073087234 2231 1311867793.0575890541 0.2464578152 0.2282718750 0.3266084492 0.0040307403 0.1448580000 983444217 0 402718720 -0.3554268181 -0.1013083458 -0.0074095037 2232 1311867793.0956139565 0.2494349033 0.2282813566 0.3266084492 0.0040299601 0.1445000000 983447345 0 402718720 -0.3592827320 -0.1011591256 -0.0068241968 2233 1311867793.1253910065 0.2482917458 0.2282903178 0.3266084492 0.0040295156 0.1705540000 983450137 0 402718720 -0.3586075902 -0.1011940762 -0.0068807905 2234 1311867793.1573770046 0.2492432445 0.2282996969 0.3266084492 0.0040290199 0.1437760000 983453041 0 402718720 -0.3601166308 -0.1010730118 -0.0066026519 2235 1311867793.1934790611 0.2476575524 0.2283083582 0.3266084492 0.0040288946 0.1546300000 983456057 0 402718720 -0.3591617942 -0.1004958227 -0.0065079308 2236 1311867793.2255470753 0.2476546466 0.2283170104 0.3266084492 0.0040282475 0.1422540000 983458961 0 402718720 -0.3595618904 -0.1004932672 -0.0062675024 2237 1311867793.2574770451 0.2488571256 0.2283261924 0.3266084492 0.0040273993 0.1419460000 983461809 0 402718720 -0.3610611558 -0.1007736921 -0.0058860481 2238 1311867793.2951428890 0.2484503388 0.2283351844 0.3266084492 0.0040268043 0.1410260000 983464937 0 402718720 -0.3613453507 -0.1008514613 -0.0057083894 2239 1311867793.3254458904 0.2490849197 0.2283444518 0.3266084492 0.0040259827 0.1402230000 983467785 0 402718720 -0.3623206317 -0.1006762236 -0.0052200118 2240 1311867793.3620529175 0.2475404739 0.2283530214 0.3266084492 0.0040258526 0.1514710000 983470857 0 402718720 -0.3614055216 -0.0999801829 -0.0053274101 2241 1311867793.3934969902 0.2447234541 0.2283603264 0.3266084492 0.0040261171 0.1393840000 983473705 0 402718720 -0.3592525423 -0.0992476046 -0.0054884343 2242 1311867793.4254410267 0.2433679551 0.2283670203 0.3266084492 0.0040257254 0.1392010000 983476609 0 402718720 -0.3584218621 -0.0988317132 -0.0053642229 2243 1311867793.4615969658 0.2412073463 0.2283727449 0.3266084492 0.0040261525 0.1379070000 983479625 0 402718720 -0.3565433919 -0.0985906944 -0.0051099560 2244 1311867793.4961650372 0.2390560806 0.2283775057 0.3266084492 0.0040256665 0.1374320000 983482473 0 402718720 -0.3548524976 -0.0979809016 -0.0051874956 2245 1311867793.5258960724 0.2375155091 0.2283815761 0.3266084492 0.0040251733 0.1467120000 983485321 0 402718720 -0.3535840213 -0.0978477374 -0.0048796465 2246 1311867793.5653350353 0.2359603941 0.2283849505 0.3266084492 0.0040247713 0.1363240000 983488449 0 402718720 -0.3523803949 -0.0975576267 -0.0049918992 2247 1311867793.5951368809 0.2345153540 0.2283876787 0.3266084492 0.0040249613 0.1356240000 983491185 0 402718720 -0.3510380685 -0.0969358161 -0.0049956087 2248 1311867793.6255569458 0.2336407900 0.2283900155 0.3266084492 0.0040247624 0.1463250000 983494089 0 402718720 -0.3504335582 -0.0968504101 -0.0048621432 2249 1311867793.6641399860 0.2320493609 0.2283916426 0.3266084492 0.0040244945 0.1348750000 983497105 0 402718720 -0.3491930962 -0.0965079740 -0.0049854997 2250 1311867793.6930859089 0.2308409214 0.2283927312 0.3266084492 0.0040271038 0.1354530000 983499953 0 402718720 -0.3485219777 -0.0956904143 -0.0053012497 2251 1311867793.7268340588 0.2291943729 0.2283930873 0.3266084492 0.0040271772 0.1353000000 983502969 0 402718720 -0.3470880687 -0.0956071541 -0.0054703942 2252 1311867793.7666549683 0.2270486057 0.2283924903 0.3266084492 0.0040265452 0.1475810000 983506041 0 402718720 -0.3456506133 -0.0952297002 -0.0060295924 2253 1311867793.7944359779 0.2263468206 0.2283915823 0.3266084492 0.0040268828 0.1355200000 983508777 0 402718720 -0.3451854587 -0.0949214026 -0.0063830148 2254 1311867793.8265230656 0.2259244472 0.2283904878 0.3266084492 0.0040263882 0.1348180000 983511737 0 402718720 -0.3453793228 -0.0943037048 -0.0067607323 2255 1311867793.8667359352 0.2261570245 0.2283894973 0.3266084492 0.0040261857 0.1475120000 983514921 0 402718720 -0.3459321260 -0.0943905339 -0.0066085169 2256 1311867793.8930900097 0.2263272554 0.2283885832 0.3266084492 0.0040253698 0.1348010000 983517657 0 402718720 -0.3463785946 -0.0946380273 -0.0065191700 2257 1311867793.9269030094 0.2254968137 0.2283873020 0.3266084492 0.0040245793 0.1344400000 983520617 0 402718720 -0.3460948169 -0.0944336429 -0.0067075081 2258 1311867793.9623370171 0.2249369472 0.2283857739 0.3266084492 0.0040238133 0.1350190000 983523521 0 402718720 -0.3460186422 -0.0943985805 -0.0069523975 2259 1311867793.9955279827 0.2253826410 0.2283844445 0.3266084492 0.0040236510 0.1347120000 983526537 0 402718720 -0.3470137119 -0.0940897837 -0.0072490326 2260 1311867794.0277070999 0.2245056927 0.2283827282 0.3266084492 0.0040234333 0.1348770000 983529441 0 402718720 -0.3467851579 -0.0933080912 -0.0072946819 2261 1311867794.0608921051 0.2240386605 0.2283808069 0.3266084492 0.0040226347 0.1343990000 983532345 0 402718720 -0.3466070294 -0.0928170010 -0.0074278689 2262 1311867794.0951509476 0.2241868526 0.2283789528 0.3266084492 0.0040218784 0.1350820000 983535305 0 402718720 -0.3470035493 -0.0921522453 -0.0074451473 2263 1311867794.1269369125 0.2243383974 0.2283771674 0.3266084492 0.0040225823 0.1350130000 983538265 0 402718720 -0.3472941220 -0.0915539786 -0.0074236598 2264 1311867794.1632831097 0.2230983078 0.2283748357 0.3266084492 0.0040231489 0.1356690000 983541281 0 402718720 -0.3465907872 -0.0901781321 -0.0076660728 2265 1311867794.1936271191 0.2238535285 0.2283728395 0.3266084492 0.0040235965 0.1361740000 983544073 0 402718720 -0.3474511206 -0.0894668028 -0.0075638164 2266 1311867794.2258520126 0.2241494060 0.2283709757 0.3266084492 0.0040227883 0.1487880000 983546977 0 402718720 -0.3480563760 -0.0889152139 -0.0072227558 2267 1311867794.2619779110 0.2244512439 0.2283692467 0.3266084492 0.0040222807 0.1365240000 983549993 0 402718720 -0.3485960066 -0.0882326141 -0.0071566533 2268 1311867794.2955250740 0.2243641764 0.2283674808 0.3266084492 0.0040219081 0.1363260000 983552897 0 402718720 -0.3486744165 -0.0873745456 -0.0071608559 2269 1311867794.3254759312 0.2247695178 0.2283658951 0.3266084492 0.0040212946 0.1547960000 983555745 0 402718720 -0.3494134247 -0.0863120109 -0.0066326414 2270 1311867794.3628959656 0.2248275876 0.2283643363 0.3266084492 0.0040217517 0.1579040000 983558817 0 402718720 -0.3498933911 -0.0850915834 -0.0065553710 2271 1311867794.3958311081 0.2248440087 0.2283627862 0.3266084492 0.0040211435 0.1366230000 983561777 0 402718720 -0.3502248228 -0.0844219252 -0.0063057910 2272 1311867794.4267809391 0.2249046415 0.2283612642 0.3266084492 0.0040205890 0.1369780000 983564681 0 402718720 -0.3505725563 -0.0837849900 -0.0064418144 2273 1311867794.4620559216 0.2254147530 0.2283599678 0.3266084492 0.0040197485 0.1370380000 983567697 0 402718720 -0.3514655828 -0.0833654478 -0.0062920172 2274 1311867794.4987208843 0.2256575823 0.2283587795 0.3266084492 0.0040191596 0.1366160000 983570657 0 402718720 -0.3521224856 -0.0829074234 -0.0064068055 2275 1311867794.5290880203 0.2259214669 0.2283577081 0.3266084492 0.0040183770 0.1367120000 983573505 0 402718720 -0.3529492915 -0.0824636072 -0.0063435207 2276 1311867794.5637059212 0.2246486843 0.2283560785 0.3266084492 0.0040185036 0.1363200000 983576465 0 402718720 -0.3522997200 -0.0820512846 -0.0065168478 2277 1311867794.5940639973 0.2249570191 0.2283545857 0.3266084492 0.0040178780 0.1370020000 983579369 0 402718720 -0.3530080914 -0.0820036232 -0.0065354933 2278 1311867794.6319000721 0.2248954922 0.2283530672 0.3266084492 0.0040189184 0.1468900000 983582385 0 402718720 -0.3532376885 -0.0816418305 -0.0068773082 2279 1311867794.6658101082 0.2248146534 0.2283515146 0.3266084492 0.0040190135 0.1436420000 983585345 0 402718720 -0.3535001874 -0.0808589533 -0.0068758107 2280 1311867794.6949920654 0.2246438712 0.2283498885 0.3266084492 0.0040190756 0.1361140000 983588193 0 402718720 -0.3538314700 -0.0801278651 -0.0069398643 2281 1311867794.7305591106 0.2244428545 0.2283481756 0.3266084492 0.0040188994 0.1354240000 983591209 0 402718720 -0.3538679183 -0.0795644894 -0.0069587724 2282 1311867794.7625899315 0.2241387814 0.2283463310 0.3266084492 0.0040184443 0.1355830000 983594057 0 402718720 -0.3536639214 -0.0792756826 -0.0071751480 2283 1311867794.7959010601 0.2236608267 0.2283442786 0.3266084492 0.0040178370 0.1345730000 983597017 0 402718720 -0.3534832299 -0.0786277056 -0.0072570662 2284 1311867794.8306028843 0.2233854085 0.2283421075 0.3266084492 0.0040175569 0.1586300000 983599977 0 402718720 -0.3534545600 -0.0783060864 -0.0073479512 2285 1311867794.8631660938 0.2239544243 0.2283401873 0.3266084492 0.0040167425 0.1348080000 983602769 0 402718720 -0.3541320562 -0.0782027170 -0.0074778204 2286 1311867794.8947780132 0.2247619480 0.2283386220 0.3266084492 0.0040165104 0.1349620000 983605673 0 402718720 -0.3551622629 -0.0778330639 -0.0072395885 2287 1311867794.9343950748 0.2238004506 0.2283366377 0.3266084492 0.0040158072 0.1343460000 983608801 0 402718720 -0.3547622561 -0.0771428943 -0.0075478274 2288 1311867794.9646499157 0.2236418873 0.2283345858 0.3266084492 0.0040150823 0.1340570000 983611649 0 402718720 -0.3547844291 -0.0766501725 -0.0077080447 2289 1311867794.9988350868 0.2230874002 0.2283322934 0.3266084492 0.0040147595 0.1518510000 983614665 0 402718720 -0.3544087708 -0.0761897564 -0.0079856794 2290 1311867795.0307559967 0.2229107916 0.2283299260 0.3266084492 0.0040140728 0.1335030000 983617513 0 402718720 -0.3542846739 -0.0758881643 -0.0080782603 2291 1311867795.0651550293 0.2224781066 0.2283273717 0.3266084492 0.0040132932 0.1445160000 983620473 0 402718720 -0.3543106616 -0.0750334337 -0.0080873128 2292 1311867795.0993340015 0.2221331447 0.2283246692 0.3266084492 0.0040127307 0.1332680000 983623433 0 402718720 -0.3542646766 -0.0744328201 -0.0082276538 2293 1311867795.1310648918 0.2218764275 0.2283218570 0.3266084492 0.0040119625 0.1332830000 983626393 0 402718720 -0.3541685343 -0.0740101337 -0.0081767682 2294 1311867795.1630289555 0.2218065709 0.2283190169 0.3266084492 0.0040115171 0.1442500000 983629241 0 402718720 -0.3545432091 -0.0735419542 -0.0082741287 2295 1311867795.1945760250 0.2216064632 0.2283160920 0.3266084492 0.0040108338 0.1331300000 983632201 0 402718720 -0.3548533916 -0.0735075697 -0.0083758347 2296 1311867795.2313210964 0.2220495045 0.2283133627 0.3266084492 0.0040103214 0.1327470000 983635217 0 402718720 -0.3556146324 -0.0733342171 -0.0086342413 2297 1311867795.2631359100 0.2219769061 0.2283106041 0.3266084492 0.0040095333 0.1330330000 983638121 0 402718720 -0.3559177220 -0.0731566250 -0.0088983933 2298 1311867795.2958068848 0.2220878303 0.2283078962 0.3266084492 0.0040086977 0.1325000000 983641081 0 402718720 -0.3562350571 -0.0733389929 -0.0089003677 2299 1311867795.3314220905 0.2217038721 0.2283050236 0.3266084492 0.0040089255 0.1574800000 983644041 0 402718720 -0.3560458720 -0.0730848163 -0.0092040356 2300 1311867795.3670549393 0.2217683792 0.2283021816 0.3266084492 0.0040083200 0.1330770000 983647169 0 402718720 -0.3561604321 -0.0727368668 -0.0091268215 2301 1311867795.3950240612 0.2216213644 0.2282992782 0.3266084492 0.0040081429 0.1327960000 983649905 0 402718720 -0.3564018905 -0.0720923841 -0.0092039984 2302 1311867795.4294250011 0.2212150395 0.2282962007 0.3266084492 0.0040076685 0.1331100000 983652921 0 402718720 -0.3561043739 -0.0718018487 -0.0092397574 2303 1311867795.4614660740 0.2211872190 0.2282931139 0.3266084492 0.0040085558 0.1324290000 983655937 0 402718720 -0.3555662930 -0.0715451837 -0.0092362128 2304 1311867795.4961009026 0.2213499248 0.2282901004 0.3266084492 0.0040077455 0.1530740000 983658953 0 402718720 -0.3556705415 -0.0708391592 -0.0091754058 2305 1311867795.5292580128 0.2213920057 0.2282871077 0.3266084492 0.0040069150 0.1331680000 983661913 0 402718720 -0.3556839526 -0.0702573434 -0.0089015933 2306 1311867795.5632829666 0.2208013684 0.2282838615 0.3266084492 0.0040066448 0.1328170000 983664985 0 402718720 -0.3549163342 -0.0693148151 -0.0090627167 2307 1311867795.5938069820 0.2204809189 0.2282804792 0.3266084492 0.0040060758 0.1329980000 983667889 0 402718720 -0.3542474508 -0.0683498532 -0.0090911472 2308 1311867795.6295180321 0.2205502689 0.2282771299 0.3266084492 0.0040055343 0.1330930000 983670961 0 402718720 -0.3541361392 -0.0672113821 -0.0090645757 2309 1311867795.6619150639 0.2205256373 0.2282737728 0.3266084492 0.0040049018 0.1543760000 983673921 0 402718720 -0.3537931144 -0.0660119876 -0.0088956766 2310 1311867795.6935899258 0.2203481942 0.2282703418 0.3266084492 0.0040042440 0.1333170000 983676825 0 402718720 -0.3533271551 -0.0646039844 -0.0089528132 2311 1311867795.7300128937 0.2202191204 0.2282668579 0.3266084492 0.0040036941 0.1326970000 983679953 0 402718720 -0.3527626991 -0.0630043522 -0.0088650240 2312 1311867795.7627360821 0.2198702544 0.2282632262 0.3266084492 0.0040030256 0.1338790000 983682969 0 402718720 -0.3521093428 -0.0617953725 -0.0088868802 2313 1311867795.7993569374 0.2198111713 0.2282595720 0.3266084492 0.0040024696 0.1338080000 983686041 0 402718720 -0.3519945741 -0.0607952662 -0.0088115083 2314 1311867795.8297359943 0.2200859487 0.2282560398 0.3266084492 0.0040017738 0.1413980000 983688945 0 402718720 -0.3522600830 -0.0601809956 -0.0088317171 2315 1311867795.8630819321 0.2200069875 0.2282524765 0.3266084492 0.0040011581 0.1464070000 983691961 0 402718720 -0.3518278897 -0.0604192391 -0.0089702019 2316 1311867795.9011631012 0.2205336839 0.2282491437 0.3266084492 0.0040005033 0.1461660000 983695089 0 402718720 -0.3523419499 -0.0598909371 -0.0090314001 2317 1311867795.9300799370 0.2204656750 0.2282457844 0.3266084492 0.0039996749 0.1454710000 983697937 0 402718720 -0.3523214161 -0.0595576875 -0.0090373000 2318 1311867795.9624390602 0.2207372636 0.2282425452 0.3266084492 0.0039989173 0.1346780000 983700897 0 402718720 -0.3525761962 -0.0593036413 -0.0092037870 2319 1311867796.0000178814 0.2207320333 0.2282393065 0.3266084492 0.0039983316 0.1623870000 983704025 0 402718720 -0.3523432314 -0.0592053048 -0.0094511425 2320 1311867796.0296399593 0.2210986316 0.2282362286 0.3266084492 0.0039976290 0.1345140000 983706873 0 402718720 -0.3523984849 -0.0598198362 -0.0094397496 2321 1311867796.0617599487 0.2209347785 0.2282330828 0.3266084492 0.0039971403 0.1346920000 983709889 0 402718720 -0.3520176411 -0.0597061850 -0.0095737735 2322 1311867796.0984148979 0.2206795216 0.2282298297 0.3266084492 0.0039963670 0.1347460000 983712905 0 402718720 -0.3516843915 -0.0590063259 -0.0097129997 2323 1311867796.1296660900 0.2210344225 0.2282267323 0.3266084492 0.0039960447 0.1348040000 983715697 0 402718720 -0.3519462943 -0.0584432818 -0.0097401310 2324 1311867796.1618049145 0.2217080295 0.2282239273 0.3266084492 0.0039952399 0.1485950000 983718657 0 402718720 -0.3523758352 -0.0586414821 -0.0095773032 2325 1311867796.1990590096 0.2210788280 0.2282208542 0.3266084492 0.0039945757 0.1347680000 983721785 0 402718720 -0.3514381647 -0.0582763143 -0.0095602525 2326 1311867796.2292931080 0.2206564546 0.2282176021 0.3266084492 0.0039937648 0.1351630000 983724689 0 402718720 -0.3509362042 -0.0579972416 -0.0096489871 2327 1311867796.2631280422 0.2203007191 0.2282141999 0.3266084492 0.0039931153 0.1347230000 983727649 0 402718720 -0.3503406048 -0.0576361865 -0.0097553562 2328 1311867796.3010690212 0.2203683555 0.2282108297 0.3266084492 0.0039924189 0.1349000000 983730721 0 402718720 -0.3499451876 -0.0575450547 -0.0096777510 2329 1311867796.3299860954 0.2202369273 0.2282074059 0.3266084492 0.0039916118 0.1442900000 983733569 0 402718720 -0.3495080471 -0.0572432764 -0.0097189620 2330 1311867796.3619849682 0.2208947688 0.2282042675 0.3266084492 0.0039909484 0.1344650000 983736585 0 402718720 -0.3499297202 -0.0570806898 -0.0095412936 2331 1311867796.3998959064 0.2206443548 0.2282010243 0.3266084492 0.0039901987 0.1344570000 983739545 0 402718720 -0.3492067158 -0.0568680279 -0.0094902469 2332 1311867796.4297831059 0.2204747945 0.2281977111 0.3266084492 0.0039893678 0.1346080000 983742449 0 402718720 -0.3487176001 -0.0567887053 -0.0092343288 2333 1311867796.4618980885 0.2208762467 0.2281945729 0.3266084492 0.0039885511 0.1342580000 983745465 0 402718720 -0.3490149975 -0.0565283448 -0.0092836581 2334 1311867796.5018439293 0.2206238508 0.2281913292 0.3266084492 0.0039878900 0.1649340000 983748649 0 402718720 -0.3484810591 -0.0564767495 -0.0093694599 2335 1311867796.5301249027 0.2209136784 0.2281882125 0.3266084492 0.0039871179 0.1347950000 983751497 0 402718720 -0.3484742045 -0.0564833321 -0.0092695449 2336 1311867796.5621480942 0.2217069715 0.2281854380 0.3266084492 0.0039863857 0.1348250000 983754457 0 402718720 -0.3489492834 -0.0565060377 -0.0088711474 2337 1311867796.6018888950 0.2217449099 0.2281826821 0.3266084492 0.0039858155 0.1456390000 983757641 0 402718720 -0.3484499454 -0.0565747321 -0.0087313484 2338 1311867796.6323978901 0.2206075490 0.2281794421 0.3266084492 0.0039851864 0.1349320000 983760545 0 402718720 -0.3468264341 -0.0564884655 -0.0088897850 2339 1311867796.6659901142 0.2207644880 0.2281762719 0.3266084492 0.0039844425 0.1475500000 983763561 0 402718720 -0.3464324474 -0.0566198044 -0.0085747531 2340 1311867796.7025029659 0.2211116105 0.2281732528 0.3266084492 0.0039838640 0.1543760000 983766521 0 402718720 -0.3462304175 -0.0565853231 -0.0084513398 2341 1311867796.7335898876 0.2225484997 0.2281708501 0.3266084492 0.0039839336 0.1363970000 983769425 0 402718720 -0.3467359841 -0.0564621016 -0.0080122482 2342 1311867796.7634348869 0.2223782837 0.2281683768 0.3266084492 0.0039831694 0.1362760000 983772385 0 402718720 -0.3459280729 -0.0562484972 -0.0077600982 2343 1311867796.7990939617 0.2218024880 0.2281656598 0.3266084492 0.0039829006 0.1374430000 983775401 0 402718720 -0.3447883725 -0.0559003688 -0.0073981425 2344 1311867796.8303010464 0.2220272720 0.2281630410 0.3266084492 0.0039822312 0.1667550000 983778361 0 402718720 -0.3444646895 -0.0555850789 -0.0066160071 2345 1311867796.8626410961 0.2221052647 0.2281604578 0.3266084492 0.0039816797 0.1378480000 983781265 0 402718720 -0.3439710438 -0.0551813468 -0.0061756945 2346 1311867796.8988420963 0.2220864743 0.2281578687 0.3266084492 0.0039811614 0.1389370000 983784337 0 402718720 -0.3431220949 -0.0547952540 -0.0055365991 2347 1311867796.9308090210 0.2230157703 0.2281556778 0.3266084492 0.0039807216 0.1389690000 983787297 0 402718720 -0.3434602916 -0.0547802709 -0.0049186647 2348 1311867796.9623529911 0.2235925943 0.2281537344 0.3266084492 0.0039799846 0.1405960000 983790257 0 402718720 -0.3435961902 -0.0550256446 -0.0042329966 2349 1311867796.9994709492 0.2242274284 0.2281520629 0.3266084492 0.0039795974 0.1403790000 983793329 0 402718720 -0.3436583281 -0.0555441752 -0.0035881724 2350 1311867797.0328159332 0.2244206965 0.2281504751 0.3266084492 0.0039788728 0.1402890000 983796233 0 402718720 -0.3436104059 -0.0556009300 -0.0033147640 2351 1311867797.0733079910 0.2247649729 0.2281490350 0.3266084492 0.0039785799 0.1407190000 983799529 0 402718720 -0.3434186578 -0.0556136370 -0.0026112483 2352 1311867797.0992720127 0.2255849987 0.2281479449 0.3266084492 0.0039780968 0.1417560000 983802265 0 402718720 -0.3439175785 -0.0556715541 -0.0018286584 2353 1311867797.1336839199 0.2263447344 0.2281471785 0.3266084492 0.0039782421 0.1423320000 983805337 0 402718720 -0.3441018164 -0.0558374859 -0.0009582472 2354 1311867797.1708030701 0.2271256447 0.2281467446 0.3266084492 0.0039776260 0.1546370000 983808409 0 402718720 -0.3443552852 -0.0555262379 -0.0001928915 2355 1311867797.1996591091 0.2278851718 0.2281466335 0.3266084492 0.0039780013 0.1436640000 983811257 0 402718720 -0.3446260095 -0.0553994924 0.0004525554 2356 1311867797.2372090816 0.2277464569 0.2281464637 0.3266084492 0.0039773004 0.1445770000 983814441 0 402718720 -0.3437118530 -0.0549170040 0.0010238881 2357 1311867797.2708179951 0.2283221036 0.2281465382 0.3266084492 0.0039768958 0.1444780000 983817401 0 402718720 -0.3440140784 -0.0546282455 0.0017184973 2358 1311867797.3019850254 0.2291767597 0.2281469751 0.3266084492 0.0039764859 0.1463270000 983820361 0 402718720 -0.3445860744 -0.0545323826 0.0024256639 2359 1311867797.3296120167 0.2285870314 0.2281471616 0.3266084492 0.0039757576 0.1569520000 983823153 0 402718720 -0.3439074159 -0.0541146398 0.0030152472 2360 1311867797.3703179359 0.2292383313 0.2281476240 0.3266084492 0.0039753495 0.1459430000 983826337 0 402718720 -0.3446879387 -0.0539212525 0.0035482075 2361 1311867797.3999080658 0.2300429642 0.2281484268 0.3266084492 0.0039747319 0.1589590000 983829241 0 402718720 -0.3456682563 -0.0537064373 0.0041598985 2362 1311867797.4322440624 0.2292141616 0.2281488780 0.3266084492 0.0039740050 0.1466550000 983832257 0 402718720 -0.3449942470 -0.0536234379 0.0047312058 2363 1311867797.4688720703 0.2289862335 0.2281492323 0.3266084492 0.0039738110 0.1469840000 983835273 0 402718720 -0.3450717926 -0.0534860902 0.0052183666 2364 1311867797.5000469685 0.2282407135 0.2281492710 0.3266084492 0.0039730059 0.1567020000 983838233 0 402718720 -0.3444241881 -0.0533634759 0.0054864208 2365 1311867797.5296459198 0.2283171713 0.2281493420 0.3266084492 0.0039724190 0.1474430000 983841137 0 402718720 -0.3446460366 -0.0534797683 0.0059013572 2366 1311867797.5718441010 0.2283732444 0.2281494366 0.3266084492 0.0039716410 0.1475480000 983844321 0 402718720 -0.3450314403 -0.0534328856 0.0063737542 2367 1311867797.5997619629 0.2290763706 0.2281498282 0.3266084492 0.0039710650 0.1477880000 983847169 0 402718720 -0.3458967507 -0.0533652157 0.0066479249 2368 1311867797.6303300858 0.2297057211 0.2281504853 0.3266084492 0.0039703251 0.1483610000 983850073 0 402718720 -0.3467653096 -0.0534604117 0.0069771120 2369 1311867797.6706480980 0.2301532328 0.2281513307 0.3266084492 0.0039695081 0.1605980000 983853257 0 402718720 -0.3474348485 -0.0539498851 0.0072941049 2370 1311867797.7010281086 0.2302786112 0.2281522283 0.3266084492 0.0039687027 0.1481350000 983856161 0 402718720 -0.3477579057 -0.0542756394 0.0073945373 2371 1311867797.7299659252 0.2304924279 0.2281532153 0.3266084492 0.0039679640 0.1484470000 983859009 0 402718720 -0.3482027948 -0.0546052195 0.0077701327 2372 1311867797.7678339481 0.2294996083 0.2281537829 0.3266084492 0.0039673130 0.1483930000 983862137 0 402718720 -0.3474009633 -0.0548393503 0.0076720556 2373 1311867797.8001670837 0.2301593125 0.2281546281 0.3266084492 0.0039665558 0.1481140000 983865153 0 402718720 -0.3481065631 -0.0551656298 0.0078764195 2374 1311867797.8302230835 0.2307401597 0.2281557172 0.3266084492 0.0039657350 0.1785420000 983868057 0 402718720 -0.3487516046 -0.0553222224 0.0078125652 2375 1311867797.8681600094 0.2298183441 0.2281564172 0.3266084492 0.0039655461 0.1481380000 983871185 0 402718720 -0.3478575647 -0.0555277541 0.0078472085 2376 1311867797.8986220360 0.2312025279 0.2281576992 0.3266084492 0.0039648355 0.1482230000 983874033 0 402718720 -0.3490727842 -0.0562794283 0.0079785548 2377 1311867797.9362978935 0.2319152951 0.2281592801 0.3266084492 0.0039640786 0.1484190000 983877161 0 402718720 -0.3496559858 -0.0564319044 0.0080692843 2378 1311867797.9696850777 0.2313136458 0.2281606065 0.3266084492 0.0039633111 0.1485080000 983880065 0 402718720 -0.3490281701 -0.0567184165 0.0081591196 2379 1311867798.0026450157 0.2316259742 0.2281620632 0.3266084492 0.0039625304 0.1596680000 983883025 0 402718720 -0.3493262231 -0.0568162315 0.0081179235 2380 1311867798.0362720490 0.2325734943 0.2281639167 0.3266084492 0.0039618084 0.1489890000 983885985 0 402718720 -0.3500314951 -0.0574086905 0.0083355457 2381 1311867798.0708239079 0.2326731682 0.2281658106 0.3266084492 0.0039613759 0.1495540000 983888945 0 402718720 -0.3501151502 -0.0575781763 0.0083172945 2382 1311867798.1006710529 0.2306868583 0.2281668690 0.3266084492 0.0039618443 0.1611890000 983891793 0 402718720 -0.3479256928 -0.0578984395 0.0082662189 2383 1311867798.1315639019 0.2322170138 0.2281685686 0.3266084492 0.0039613557 0.1492620000 983894641 0 402718720 -0.3491541743 -0.0584387407 0.0083196461 2384 1311867798.1681389809 0.2340032905 0.2281710160 0.3266084492 0.0039608174 0.1627140000 983897657 0 402718720 -0.3505144119 -0.0589003041 0.0083412146 2385 1311867798.2041590214 0.2330098897 0.2281730449 0.3266084492 0.0039604592 0.1494520000 983900729 0 402718720 -0.3490428627 -0.0589315146 0.0081017623 2386 1311867798.2401928902 0.2350948155 0.2281759459 0.3266084492 0.0039606298 0.1623460000 983903745 0 402718720 -0.3505113125 -0.0597234294 0.0083128251 2387 1311867798.2742829323 0.2359630018 0.2281792082 0.3266084492 0.0039600572 0.1502790000 983906705 0 402718720 -0.3509218097 -0.0597462952 0.0083803525 2388 1311867798.3000180721 0.2350558639 0.2281820878 0.3266084492 0.0039593955 0.1499880000 983909441 0 402718720 -0.3495164514 -0.0595851094 0.0085633760 2389 1311867798.3389759064 0.2357258201 0.2281852455 0.3266084492 0.0039589147 0.1502800000 983912569 0 402718720 -0.3495082557 -0.0597528629 0.0086244103 2390 1311867798.3689808846 0.2358457297 0.2281884507 0.3266084492 0.0039581467 0.1635280000 983915361 0 402718720 -0.3490546346 -0.0597215444 0.0087055601 2391 1311867798.4016571045 0.2358179241 0.2281916417 0.3266084492 0.0039573952 0.1514300000 983918321 0 402718720 -0.3484829664 -0.0594846755 0.0089276312 2392 1311867798.4377439022 0.2348516434 0.2281944259 0.3266084492 0.0039569702 0.1513510000 983921337 0 402718720 -0.3468438387 -0.0594616197 0.0089155799 2393 1311867798.4722189903 0.2340818644 0.2281968862 0.3266084492 0.0039566851 0.1513840000 983924297 0 402718720 -0.3455426395 -0.0592306852 0.0089063998 2394 1311867798.4979979992 0.2349992394 0.2281997276 0.3266084492 0.0039561025 0.1647040000 983927033 0 402718720 -0.3460830450 -0.0593332201 0.0090413364 2395 1311867798.5371229649 0.2356415987 0.2282028349 0.3266084492 0.0039554239 0.1522410000 983930105 0 402718720 -0.3460003734 -0.0596023835 0.0090196207 2396 1311867798.5710020065 0.2352131903 0.2282057607 0.3266084492 0.0039547128 0.1531080000 983933065 0 402718720 -0.3451173902 -0.0597929023 0.0088703493 2397 1311867798.6058080196 0.2351217866 0.2282086460 0.3266084492 0.0039540979 0.1528570000 983936025 0 402718720 -0.3443596661 -0.0597727522 0.0086328210 2398 1311867798.6374750137 0.2363181561 0.2282120278 0.3266084492 0.0039548244 0.1538340000 983938873 0 402718720 -0.3448426127 -0.0597536936 0.0088895503 2399 1311867798.6689419746 0.2363018095 0.2282154000 0.3266084492 0.0039542958 0.1641500000 983941777 0 402718720 -0.3442341387 -0.0592211820 0.0089690033 2400 1311867798.7046790123 0.2361482233 0.2282187053 0.3266084492 0.0039539920 0.1546650000 983944793 0 402718720 -0.3434758186 -0.0588270053 0.0091460031 2401 1311867798.7372579575 0.2369788885 0.2282223539 0.3266084492 0.0039536465 0.1557630000 983947753 0 402718720 -0.3433541059 -0.0586047992 0.0090234885 2402 1311867798.7684650421 0.2370989472 0.2282260494 0.3266084492 0.0039530564 0.1558460000 983950601 0 402718720 -0.3428168893 -0.0580439568 0.0091962377 2403 1311867798.8009719849 0.2352068275 0.2282289544 0.3266084492 0.0039535017 0.1563600000 983953505 0 402718720 -0.3402668238 -0.0572760068 0.0091246031 2404 1311867798.8353779316 0.2377301306 0.2282329066 0.3266084492 0.0039544714 0.1652290000 983956465 0 402718720 -0.3415977359 -0.0571459793 0.0091681844 2405 1311867798.8719079494 0.2379836142 0.2282369610 0.3266084492 0.0039538716 0.1575010000 983959481 0 402718720 -0.3406544328 -0.0564929359 0.0091500198 2406 1311867798.9030900002 0.2373456806 0.2282407468 0.3266084492 0.0039531125 0.1585550000 983962329 0 402718720 -0.3392351270 -0.0560050197 0.0088053336 2407 1311867798.9344220161 0.2383817583 0.2282449599 0.3266084492 0.0039526122 0.1585720000 983965233 0 402718720 -0.3392681479 -0.0553051867 0.0086762235 2408 1311867798.9702930450 0.2375466079 0.2282488227 0.3266084492 0.0039519886 0.1717820000 983968249 0 402718720 -0.3373000324 -0.0544717014 0.0085414276 2409 1311867798.9996600151 0.2373909950 0.2282526177 0.3266084492 0.0039538293 0.1725850000 983971097 0 402718720 -0.3371306658 -0.0538416356 0.0083830571 2410 1311867799.0381140709 0.2386344969 0.2282569256 0.3266084492 0.0039554649 0.1606830000 983974225 0 402718720 -0.3365999460 -0.0533464588 0.0083880648 2411 1311867799.0688700676 0.2385845482 0.2282612091 0.3266084492 0.0039550580 0.1613760000 983977073 0 402718720 -0.3356106281 -0.0534004122 0.0082608294 2412 1311867799.1011309624 0.2378877103 0.2282652002 0.3266084492 0.0039554012 0.1615430000 983979977 0 402718720 -0.3343286812 -0.0529724434 0.0081400890 2413 1311867799.1368980408 0.2382054776 0.2282693197 0.3266084492 0.0039548530 0.1613430000 983982993 0 402718720 -0.3335956037 -0.0526245683 0.0081852544 2414 1311867799.1699140072 0.2379037738 0.2282733108 0.3266084492 0.0039541124 0.1621040000 983985897 0 402718720 -0.3326018453 -0.0520688742 0.0078434069 2415 1311867799.2040729523 0.2366415113 0.2282767758 0.3266084492 0.0039574065 0.1689590000 983988857 0 402718720 -0.3307291269 -0.0516584516 0.0072020777 2416 1311867799.2358450890 0.2373280525 0.2282805222 0.3266084492 0.0039567721 0.1622350000 983991761 0 402718720 -0.3307417929 -0.0517717190 0.0068618138 2417 1311867799.2801609039 0.2388468683 0.2282848939 0.3266084492 0.0039561670 0.1632470000 983995001 0 402718720 -0.3311927915 -0.0517614298 0.0063171666 2418 1311867799.2992970943 0.2378364354 0.2282888441 0.3266084492 0.0039554224 0.1634890000 983997513 0 402718720 -0.3299374282 -0.0515751876 0.0055794297 2419 1311867799.3363530636 0.2378982902 0.2282928166 0.3266084492 0.0039553539 0.1634070000 984000585 0 402718720 -0.3294399381 -0.0510372892 0.0051150983 2420 1311867799.3682019711 0.2384097129 0.2282969971 0.3266084492 0.0039552983 0.1638420000 984003433 0 402718720 -0.3295243979 -0.0506591424 0.0046006725 2421 1311867799.4002521038 0.2388380915 0.2283013511 0.3266084492 0.0039545907 0.1643510000 984006393 0 402718720 -0.3294274211 -0.0502151586 0.0042535015 2422 1311867799.4359819889 0.2384644300 0.2283055473 0.3266084492 0.0039538870 0.1643900000 984009409 0 402718720 -0.3287579119 -0.0493582301 0.0038689773 2423 1311867799.4694008827 0.2385840267 0.2283097893 0.3266084492 0.0039531812 0.1759260000 984012313 0 402718720 -0.3284268379 -0.0487490445 0.0037226712 2424 1311867799.5055029392 0.2377260178 0.2283136739 0.3266084492 0.0039524624 0.1646370000 984015329 0 402718720 -0.3273021579 -0.0480424501 0.0033064391 2425 1311867799.5358369350 0.2352491766 0.2283165339 0.3266084492 0.0039520934 0.1650270000 984018177 0 402718720 -0.3247829378 -0.0475426055 0.0028259619 2426 1311867799.5718040466 0.2367838174 0.2283200242 0.3266084492 0.0039516693 0.1653430000 984021193 0 402718720 -0.3262822032 -0.0468738414 0.0025205007 2427 1311867799.6046330929 0.2366295159 0.2283234479 0.3266084492 0.0039512762 0.1654370000 984024041 0 402718720 -0.3260400593 -0.0462561995 0.0022503017 2428 1311867799.6362400055 0.2357530147 0.2283265079 0.3266084492 0.0039505981 0.1715100000 984027001 0 402718720 -0.3251040280 -0.0455998853 0.0015942405 2429 1311867799.6706030369 0.2371536195 0.2283301419 0.3266084492 0.0039505000 0.1660820000 984029961 0 402718720 -0.3260787427 -0.0453626476 0.0010741606 2430 1311867799.7089800835 0.2378723770 0.2283340688 0.3266084492 0.0039498313 0.1664930000 984033033 0 402718720 -0.3265508413 -0.0448952056 0.0005176846 2431 1311867799.7397329807 0.2368014157 0.2283375518 0.3266084492 0.0039494154 0.1667570000 984035881 0 402718720 -0.3255659044 -0.0444688685 -0.0001686222 2432 1311867799.7721259594 0.2359756380 0.2283406925 0.3266084492 0.0039488758 0.1660710000 984038841 0 402718720 -0.3244795203 -0.0439381599 -0.0007846213 2433 1311867799.8072490692 0.2371315509 0.2283443057 0.3266084492 0.0039488543 0.1665450000 984041801 0 402718720 -0.3255437911 -0.0434762351 -0.0013092514 2434 1311867799.8393049240 0.2344676852 0.2283468215 0.3266084492 0.0039484517 0.1664200000 984044705 0 402718720 -0.3228464723 -0.0426943600 -0.0020006925 2435 1311867799.8678040504 0.2351327538 0.2283496083 0.3266084492 0.0039481547 0.1669940000 984047553 0 402718720 -0.3232902288 -0.0421812944 -0.0023142810 2436 1311867799.9071669579 0.2362619042 0.2283528564 0.3266084492 0.0039477394 0.1803450000 984050681 0 402718720 -0.3242342472 -0.0413538702 -0.0022713805 2437 1311867799.9347701073 0.2349224836 0.2283555521 0.3266084492 0.0039470245 0.1860690000 984053361 0 402718720 -0.3226693869 -0.0405690148 -0.0023087219 2438 1311867799.9675478935 0.2348699719 0.2283582242 0.3266084492 0.0039462927 0.1873450000 984056321 0 402718720 -0.3224944472 -0.0401021801 -0.0021627124 2439 1311867800.0074419975 0.2358774394 0.2283613071 0.3266084492 0.0039456199 0.1685580000 984059449 0 402718720 -0.3230469525 -0.0394780189 -0.0022074697 2440 1311867800.0354819298 0.2364612818 0.2283646267 0.3266084492 0.0039449487 0.1684050000 984062241 0 402718720 -0.3233387172 -0.0387962125 -0.0023638264 2441 1311867800.0715930462 0.2359823436 0.2283677475 0.3266084492 0.0039452242 0.1686870000 984065257 0 402718720 -0.3222695291 -0.0381314158 -0.0024011056 2442 1311867800.1054389477 0.2355598658 0.2283706927 0.3266084492 0.0039444801 0.1689380000 984068217 0 402718720 -0.3212632239 -0.0376072526 -0.0027710670 2443 1311867800.1350870132 0.2361527979 0.2283738781 0.3266084492 0.0039437954 0.1817990000 984071009 0 402718720 -0.3214288652 -0.0372006968 -0.0030634017 2444 1311867800.1694350243 0.2356884032 0.2283768710 0.3266084492 0.0039432745 0.1700790000 984073969 0 402718720 -0.3203919232 -0.0367715545 -0.0032835703 2445 1311867800.2077379227 0.2351372689 0.2283796360 0.3266084492 0.0039425588 0.1695630000 984077097 0 402718720 -0.3190012872 -0.0364753902 -0.0035343699 2446 1311867800.2413349152 0.2352690995 0.2283824526 0.3266084492 0.0039420245 0.1696210000 984080057 0 402718720 -0.3184084594 -0.0358646065 -0.0035441730 2447 1311867800.2718439102 0.2357824296 0.2283854767 0.3266084492 0.0039413237 0.1820160000 984082905 0 402718720 -0.3182050884 -0.0356162824 -0.0032636207 2448 1311867800.3038680553 0.2350984216 0.2283882189 0.3266084492 0.0039411879 0.1851040000 984085753 0 402718720 -0.3169469535 -0.0350225605 -0.0031107597 2449 1311867800.3359420300 0.2347068936 0.2283907990 0.3266084492 0.0039405863 0.1701170000 984088713 0 402718720 -0.3157380223 -0.0346481539 -0.0030263183 2450 1311867800.3712899685 0.2346944809 0.2283933719 0.3266084492 0.0039398218 0.1701440000 984091617 0 402718720 -0.3145279586 -0.0342279635 -0.0027397424 2451 1311867800.4036390781 0.2351205349 0.2283961166 0.3266084492 0.0039392013 0.1704070000 984094577 0 402718720 -0.3140412271 -0.0340083465 -0.0027676518 2452 1311867800.4360520840 0.2350668460 0.2283988371 0.3266084492 0.0039386600 0.1705230000 984097425 0 402718720 -0.3131023645 -0.0336561091 -0.0027673177 2453 1311867800.4683868885 0.2350510955 0.2284015490 0.3266084492 0.0039379278 0.1803620000 984100329 0 402718720 -0.3121187091 -0.0332894810 -0.0027080290 2454 1311867800.5043759346 0.2359718233 0.2284046339 0.3266084492 0.0039375264 0.1706340000 984103401 0 402718720 -0.3119030297 -0.0327241793 -0.0023530268 2455 1311867800.5355989933 0.2363065928 0.2284078526 0.3266084492 0.0039370162 0.1709030000 984106305 0 402718720 -0.3114400804 -0.0322994553 -0.0024765600 2456 1311867800.5714819431 0.2371201962 0.2284114000 0.3266084492 0.0039364516 0.1712610000 984109377 0 402718720 -0.3110356629 -0.0320681296 -0.0023263283 2457 1311867800.6043050289 0.2358571142 0.2284144304 0.3266084492 0.0039357243 0.1714390000 984112281 0 402718720 -0.3088268936 -0.0319075696 -0.0023260645 2458 1311867800.6356160641 0.2361191958 0.2284175650 0.3266084492 0.0039349730 0.1721810000 984115185 0 402718720 -0.3080304861 -0.0320596471 -0.0022730343 2459 1311867800.6704459190 0.2348968685 0.2284201999 0.3266084492 0.0039352078 0.1713430000 984118145 0 402718720 -0.3059288561 -0.0314260498 -0.0023555416 2460 1311867800.7034249306 0.2352164239 0.2284229626 0.3266084492 0.0039348034 0.1709640000 984121049 0 402718720 -0.3054786921 -0.0310145859 -0.0021587433 2461 1311867800.7352058887 0.2366255969 0.2284262956 0.3266084492 0.0039342818 0.1713160000 984123953 0 402718720 -0.3058064580 -0.0307605565 -0.0020524866 2462 1311867800.7744410038 0.2353817523 0.2284291208 0.3266084492 0.0039351487 0.1719090000 984127025 0 402718720 -0.3037500083 -0.0306840707 -0.0020305398 2463 1311867800.8084959984 0.2357719839 0.2284321020 0.3266084492 0.0039346133 0.1828710000 984129985 0 402718720 -0.3034473360 -0.0304892734 -0.0018869174 2464 1311867800.8347818851 0.2356890291 0.2284350472 0.3266084492 0.0039339421 0.1719780000 984132721 0 402718720 -0.3027893901 -0.0302717760 -0.0016982898 2465 1311867800.8741569519 0.2351395190 0.2284377671 0.3266084492 0.0039336023 0.1723280000 984135849 0 402718720 -0.3017098904 -0.0298825279 -0.0017726922 2466 1311867800.9060831070 0.2343479097 0.2284401637 0.3266084492 0.0039328888 0.1895090000 984138697 0 402718720 -0.3005092740 -0.0293570738 -0.0018810082 2467 1311867800.9397630692 0.2358957380 0.2284431858 0.3266084492 0.0039323515 0.1721390000 984141657 0 402718720 -0.3015668392 -0.0295756273 -0.0018528617 2468 1311867800.9754400253 0.2349196225 0.2284458100 0.3266084492 0.0039324878 0.1880970000 984144673 0 402718720 -0.2999638021 -0.0296222046 -0.0019795373 2469 1311867801.0043320656 0.2354283035 0.2284486381 0.3266084492 0.0039322996 0.1728050000 984147465 0 402718720 -0.3000632524 -0.0301821269 -0.0020064136 2470 1311867801.0391418934 0.2359381467 0.2284516703 0.3266084492 0.0039321293 0.1850280000 984150481 0 402718720 -0.3001915514 -0.0306212865 -0.0019238400 2471 1311867801.0742049217 0.2344779372 0.2284541091 0.3266084492 0.0039314281 0.1731170000 984153385 0 402718720 -0.2983881235 -0.0303395167 -0.0020055100 2472 1311867801.1095008850 0.2346330881 0.2284566086 0.3266084492 0.0039311772 0.1723910000 984156401 0 402718720 -0.2984043062 -0.0303193033 -0.0017030238 2473 1311867801.1356039047 0.2342430949 0.2284589485 0.3266084492 0.0039304990 0.1827400000 984159137 0 402718720 -0.2978169620 -0.0302534997 -0.0015583052 2474 1311867801.1731019020 0.2335994393 0.2284610263 0.3266084492 0.0039300523 0.1723620000 984162209 0 402718720 -0.2971777916 -0.0299081132 -0.0013161531 2475 1311867801.2059779167 0.2320865691 0.2284624912 0.3266084492 0.0039307588 0.1732240000 984165113 0 402718720 -0.2958989441 -0.0300155226 -0.0014211449 2476 1311867801.2351169586 0.2320509255 0.2284639405 0.3266084492 0.0039301283 0.1801920000 984167793 0 402718720 -0.2958194911 -0.0308506340 -0.0013340992 2477 1311867801.2740859985 0.2329816669 0.2284657643 0.3266084492 0.0039293656 0.1731200000 984170977 0 402718720 -0.2968137264 -0.0312310997 -0.0011128440 2478 1311867801.3080420494 0.2319750339 0.2284671805 0.3266084492 0.0039293405 0.2018990000 984173881 0 402718720 -0.2961516082 -0.0311133228 -0.0010848931 2479 1311867801.3364291191 0.2312212437 0.2284682915 0.3266084492 0.0039289032 0.1729320000 984176673 0 402718720 -0.2956205904 -0.0305131953 -0.0011004956 2480 1311867801.3723030090 0.2296792269 0.2284687797 0.3266084492 0.0039287226 0.1729850000 984179689 0 402718720 -0.2943851650 -0.0299618840 -0.0012382402 2481 1311867801.4048879147 0.2296740860 0.2284692656 0.3266084492 0.0039279349 0.1727180000 984182593 0 402718720 -0.2944523394 -0.0300916974 -0.0011890874 2482 1311867801.4369940758 0.2292342782 0.2284695738 0.3266084492 0.0039282229 0.1730690000 984185553 0 402718720 -0.2943045199 -0.0296665877 -0.0010435514 2483 1311867801.4725570679 0.2290728986 0.2284698168 0.3266084492 0.0039330765 0.1830050000 984188513 0 402718720 -0.2937534451 -0.0295968000 -0.0007008836 2484 1311867801.5049059391 0.2288003713 0.2284699498 0.3266084492 0.0039330775 0.1843240000 984191361 0 402718720 -0.2934239209 -0.0291010663 -0.0003010524 2485 1311867801.5366990566 0.2299548835 0.2284705474 0.3266084492 0.0039337791 0.1735110000 984194321 0 402718720 -0.2938326299 -0.0289098006 0.0001274409 2486 1311867801.5724411011 0.2296428233 0.2284710190 0.3266084492 0.0039337418 0.1734760000 984197337 0 402718720 -0.2933997810 -0.0285886079 0.0005870091 2487 1311867801.6040530205 0.2289535850 0.2284712130 0.3266084492 0.0039330398 0.1731210000 984200185 0 402718720 -0.2921735644 -0.0283903070 0.0010351053 2488 1311867801.6371319294 0.2296377867 0.2284716819 0.3266084492 0.0039324472 0.1902850000 984203145 0 402718720 -0.2921155989 -0.0281066615 0.0014885562 2489 1311867801.6713359356 0.2288405299 0.2284718301 0.3266084492 0.0039391739 0.1736630000 984206105 0 402718720 -0.2912048697 -0.0276394151 0.0015985961 2490 1311867801.7047519684 0.2274919748 0.2284714365 0.3266084492 0.0039409743 0.1733280000 984209065 0 402718720 -0.2888994515 -0.0278208032 0.0017239795 2491 1311867801.7362918854 0.2290999442 0.2284716889 0.3266084492 0.0039456189 0.1738260000 984211969 0 402718720 -0.2890137136 -0.0286733285 0.0018998752 2492 1311867801.7739040852 0.2297691703 0.2284722095 0.3266084492 0.0039458747 0.1737410000 984215041 0 402718720 -0.2885112166 -0.0292517375 0.0017637131 2493 1311867801.8057849407 0.2288472056 0.2284723599 0.3266084492 0.0039452573 0.1854040000 984217889 0 402718720 -0.2866350710 -0.0292817391 0.0012146903 2494 1311867801.8389480114 0.2298223972 0.2284729012 0.3266084492 0.0039446203 0.1749950000 984220793 0 402718720 -0.2863226235 -0.0303532537 0.0006594277 2495 1311867801.8715689182 0.2305666953 0.2284737404 0.3266084492 0.0039444816 0.1736660000 984223809 0 402718720 -0.2858449221 -0.0314156227 -0.0002711354 2496 1311867801.9050290585 0.2297917157 0.2284742685 0.3266084492 0.0039458945 0.1737000000 984226713 0 402718720 -0.2838139832 -0.0317610428 -0.0013327455 2497 1311867801.9403839111 0.2298657745 0.2284748257 0.3266084492 0.0039460111 0.1737930000 984229729 0 402718720 -0.2826664746 -0.0320513546 -0.0023699191 2498 1311867801.9724469185 0.2296977192 0.2284753153 0.3266084492 0.0039456933 0.1956790000 984232633 0 402718720 -0.2813682854 -0.0318780765 -0.0037234956 2499 1311867802.0031659603 0.2304939032 0.2284761231 0.3266084492 0.0039514653 0.1737550000 984235481 0 402718720 -0.2808521390 -0.0314085409 -0.0048905998 2500 1311867802.0413680077 0.2306465954 0.2284769912 0.3266084492 0.0039564708 0.1743690000 984238609 0 402718720 -0.2792203426 -0.0307801943 -0.0064037610 2501 1311867802.0717110634 0.2306905240 0.2284778763 0.3266084492 0.0039566854 0.1867750000 984241457 0 402718720 -0.2778748870 -0.0304613356 -0.0078828773 2502 1311867802.1040730476 0.2316868305 0.2284791589 0.3266084492 0.0039572828 0.1748310000 984244305 0 402718720 -0.2771148682 -0.0303000435 -0.0095721232 2503 1311867802.1390628815 0.2298055440 0.2284796888 0.3266084492 0.0039581227 0.1878830000 984247265 0 402718720 -0.2733346820 -0.0296458416 -0.0113957021 2504 1311867802.1724100113 0.2286808193 0.2284797691 0.3266084492 0.0039631964 0.1756730000 984250225 0 402718720 -0.2708656490 -0.0292314943 -0.0135463625 2505 1311867802.2056589127 0.2293280065 0.2284801077 0.3266084492 0.0039668448 0.1760510000 984253129 0 402718720 -0.2694804668 -0.0290028416 -0.0154855698 2506 1311867802.2409839630 0.2283922285 0.2284800726 0.3266084492 0.0039733078 0.1759450000 984256145 0 402718720 -0.2668558657 -0.0287747812 -0.0176289137 2507 1311867802.2706429958 0.2285512090 0.2284801010 0.3266084492 0.0039726994 0.1891600000 984258993 0 402718720 -0.2652580142 -0.0293931719 -0.0198918935 2508 1311867802.3064510822 0.2272523940 0.2284796115 0.3266084492 0.0039737629 0.1765040000 984261953 0 402718720 -0.2626045048 -0.0299457870 -0.0221811030 2509 1311867802.3400380611 0.2284775525 0.2284796107 0.3266084492 0.0039763926 0.1759150000 984264913 0 402718720 -0.2623242438 -0.0311204772 -0.0242312923 2510 1311867802.3742809296 0.2293992043 0.2284799771 0.3266084492 0.0039762198 0.1770720000 984267761 0 402718720 -0.2615272701 -0.0321814306 -0.0263742637 2511 1311867802.4052720070 0.2289538234 0.2284801658 0.3266084492 0.0039780447 0.1882310000 984270665 0 402718720 -0.2597406805 -0.0333485454 -0.0285279099 2512 1311867802.4389400482 0.2287756652 0.2284802834 0.3266084492 0.0039811643 0.1776060000 984273569 0 402718720 -0.2584122121 -0.0339945517 -0.0304902233 2513 1311867802.4714379311 0.2285300940 0.2284803032 0.3266084492 0.0039813745 0.1881840000 984276529 0 402718720 -0.2570196986 -0.0346582867 -0.0326147787 2514 1311867802.5060200691 0.2290072441 0.2284805128 0.3266084492 0.0039816674 0.1777820000 984279489 0 402718720 -0.2562122345 -0.0350605473 -0.0347253308 2515 1311867802.5389459133 0.2296519876 0.2284809786 0.3266084492 0.0039819907 0.1775640000 984282337 0 402718720 -0.2555489540 -0.0357530043 -0.0367294922 2516 1311867802.5715909004 0.2313133627 0.2284821044 0.3266084492 0.0039866696 0.1772610000 984285353 0 402718720 -0.2558394969 -0.0357301384 -0.0390351042 2517 1311867802.6031410694 0.2318971902 0.2284834612 0.3266084492 0.0039874230 0.1880430000 984288201 0 402718720 -0.2549486756 -0.0353194289 -0.0410541855 2518 1311867802.6396369934 0.2328743488 0.2284852050 0.3266084492 0.0039874029 0.1777290000 984291217 0 402718720 -0.2543346882 -0.0360758230 -0.0430916212 2519 1311867802.6727440357 0.2336421758 0.2284872522 0.3266084492 0.0039868284 0.1771180000 984294121 0 402718720 -0.2536476254 -0.0359152965 -0.0450912081 2520 1311867802.7073149681 0.2342531979 0.2284895403 0.3266084492 0.0039872088 0.1769680000 984297081 0 402718720 -0.2530710995 -0.0350294672 -0.0468468703 2521 1311867802.7416400909 0.2345567495 0.2284919469 0.3266084492 0.0039866860 0.1767330000 984300041 0 402718720 -0.2519156933 -0.0344339162 -0.0486606397 2522 1311867802.7708799839 0.2340345085 0.2284941446 0.3266084492 0.0039859214 0.1965930000 984302889 0 402718720 -0.2499299198 -0.0340583846 -0.0506712981 2523 1311867802.8048460484 0.2329394668 0.2284959066 0.3266084492 0.0039853189 0.1941410000 984305737 0 402718720 -0.2475320697 -0.0335529633 -0.0524324588 2524 1311867802.8393790722 0.2332736999 0.2284977995 0.3266084492 0.0039848337 0.1780900000 984308753 0 402718720 -0.2465223074 -0.0332481898 -0.0537496880 2525 1311867802.8706729412 0.2335394472 0.2284997962 0.3266084492 0.0039844429 0.1775510000 984311657 0 402718720 -0.2452925295 -0.0334522873 -0.0554137789 2526 1311867802.9066920280 0.2340323478 0.2285019864 0.3266084492 0.0039845958 0.1777240000 984314673 0 402718720 -0.2446179688 -0.0334572606 -0.0569133274 2527 1311867802.9404280186 0.2334136367 0.2285039301 0.3266084492 0.0039840863 0.1775330000 984317577 0 402718720 -0.2425794303 -0.0332407057 -0.0585943796 2528 1311867802.9723958969 0.2339443415 0.2285060822 0.3266084492 0.0039834355 0.1976990000 984320481 0 402718720 -0.2418100685 -0.0336592980 -0.0599243455 2529 1311867803.0042099953 0.2331069857 0.2285079014 0.3266084492 0.0039839381 0.1780570000 984323385 0 402718720 -0.2401366830 -0.0334713459 -0.0613226146 2530 1311867803.0404539108 0.2330685109 0.2285097040 0.3266084492 0.0039833909 0.1772170000 984326401 0 402718720 -0.2385706753 -0.0335226469 -0.0628426895 2531 1311867803.0710830688 0.2322805673 0.2285111939 0.3266084492 0.0039829871 0.1779390000 984329249 0 402718720 -0.2370093316 -0.0338580906 -0.0642343685 2532 1311867803.1049640179 0.2330483645 0.2285129858 0.3266084492 0.0039823503 0.1774870000 984332153 0 402718720 -0.2368545234 -0.0344290063 -0.0656433553 2533 1311867803.1399960518 0.2334092706 0.2285149188 0.3266084492 0.0039816352 0.1888990000 984335169 0 402718720 -0.2364431024 -0.0345512405 -0.0670262724 2534 1311867803.1724820137 0.2330257893 0.2285166990 0.3266084492 0.0039810681 0.1768280000 984338073 0 402718720 -0.2356604040 -0.0345849171 -0.0683663189 2535 1311867803.2086870670 0.2335797101 0.2285186962 0.3266084492 0.0039806030 0.1780780000 984341145 0 402718720 -0.2356445044 -0.0347591154 -0.0694493875 2536 1311867803.2400670052 0.2334925383 0.2285206575 0.3266084492 0.0039811061 0.1895610000 984343993 0 402718720 -0.2356365025 -0.0349579789 -0.0706430450 2537 1311867803.2704820633 0.2345345765 0.2285230280 0.3266084492 0.0039823736 0.1889710000 984346841 0 402718720 -0.2362930179 -0.0355064310 -0.0716491416 2538 1311867803.3084690571 0.2348951250 0.2285255387 0.3266084492 0.0039821572 0.1964970000 984349969 0 402718720 -0.2367624193 -0.0363670774 -0.0726579204 2539 1311867803.3390929699 0.2353338450 0.2285282202 0.3266084492 0.0039822245 0.1888240000 984352705 0 402718720 -0.2374411076 -0.0364976227 -0.0734895170 2540 1311867803.3732869625 0.2357756943 0.2285310735 0.3266084492 0.0039815331 0.1755620000 984355721 0 402718720 -0.2379026115 -0.0367619321 -0.0742133930 2541 1311867803.4067549706 0.2361928970 0.2285340888 0.3266084492 0.0039809491 0.1758350000 984358681 0 402718720 -0.2384672612 -0.0366416648 -0.0747942254 2542 1311867803.4397881031 0.2356162071 0.2285368748 0.3266084492 0.0039804063 0.1877450000 984361585 0 402718720 -0.2377799302 -0.0366041996 -0.0756455436 2543 1311867803.4707190990 0.2356095910 0.2285396561 0.3266084492 0.0039797893 0.1867370000 984364489 0 402718720 -0.2376255691 -0.0368938111 -0.0764231533 2544 1311867803.5065801144 0.2366701216 0.2285428520 0.3266084492 0.0039797050 0.1754630000 984367505 0 402718720 -0.2384076566 -0.0371555798 -0.0771277398 2545 1311867803.5397379398 0.2369051278 0.2285461378 0.3266084492 0.0039791172 0.1751970000 984370409 0 402718720 -0.2387235165 -0.0371500738 -0.0780973583 2546 1311867803.5702500343 0.2370943725 0.2285494953 0.3266084492 0.0039785021 0.1758360000 984373257 0 402718720 -0.2390222847 -0.0372922793 -0.0791481137 2547 1311867803.6121668816 0.2374579608 0.2285529929 0.3266084492 0.0039781440 0.1757070000 984376497 0 402718720 -0.2395878732 -0.0373854227 -0.0798074976 2548 1311867803.6394500732 0.2368159443 0.2285562358 0.3266084492 0.0039775971 0.1905230000 984379233 0 402718720 -0.2391520739 -0.0367011055 -0.0806047246 2549 1311867803.6726729870 0.2369468510 0.2285595276 0.3266084492 0.0039772637 0.1771730000 984382137 0 402718720 -0.2396533340 -0.0361822657 -0.0813459605 2550 1311867803.7105441093 0.2378634512 0.2285631762 0.3266084492 0.0039773750 0.2010570000 984385265 0 402718720 -0.2409304082 -0.0359153710 -0.0818079486 2551 1311867803.7378931046 0.2381321639 0.2285669272 0.3266084492 0.0039771208 0.1787640000 984388001 0 402718720 -0.2413729131 -0.0350707509 -0.0825654194 2552 1311867803.7722349167 0.2368819714 0.2285701855 0.3266084492 0.0039766909 0.1802620000 984391017 0 402718720 -0.2402055264 -0.0343086012 -0.0836111754 2553 1311867803.8064799309 0.2380578667 0.2285739018 0.3266084492 0.0039760350 0.1899000000 984393977 0 402718720 -0.2413129807 -0.0341136195 -0.0841259882 2554 1311867803.8385739326 0.2394393086 0.2285781560 0.3266084492 0.0039772020 0.1806290000 984396825 0 402718720 -0.2424311191 -0.0335968100 -0.0842612162 2555 1311867803.8737049103 0.2391020656 0.2285822750 0.3266084492 0.0039784534 0.1792220000 984399897 0 402718720 -0.2420860380 -0.0327725820 -0.0848591626 2556 1311867803.9077479839 0.2392588556 0.2285864521 0.3266084492 0.0039793452 0.1819880000 984402857 0 402718720 -0.2423054427 -0.0323016383 -0.0855877027 2557 1311867803.9400169849 0.2403690219 0.2285910600 0.3266084492 0.0039814056 0.1810640000 984405705 0 402718720 -0.2435143590 -0.0315281451 -0.0859690383 2558 1311867803.9723939896 0.2416467071 0.2285961639 0.3266084492 0.0039816871 0.1823810000 984408665 0 402718720 -0.2452125400 -0.0307707582 -0.0863111019 2559 1311867804.0064320564 0.2415128350 0.2286012114 0.3266084492 0.0039811482 0.1818620000 984411569 0 402718720 -0.2453984022 -0.0305564832 -0.0871173590 2560 1311867804.0387020111 0.2412686944 0.2286061596 0.3266084492 0.0039805507 0.1807430000 984414473 0 402718720 -0.2455927134 -0.0301939398 -0.0877126381 2561 1311867804.0722310543 0.2414031178 0.2286111565 0.3266084492 0.0039799041 0.1807660000 984417433 0 402718720 -0.2463579923 -0.0292755179 -0.0884382054 2562 1311867804.1084001064 0.2420837581 0.2286164151 0.3266084492 0.0039799446 0.1814150000 984420393 0 402718720 -0.2476222664 -0.0294549447 -0.0888335705 2563 1311867804.1399340630 0.2420481145 0.2286216558 0.3266084492 0.0039794067 0.1815700000 984423297 0 402718720 -0.2481607497 -0.0292552859 -0.0895979702 2564 1311867804.1736989021 0.2430078536 0.2286272666 0.3266084492 0.0039788625 0.1818110000 984426257 0 402718720 -0.2495458424 -0.0289917793 -0.0900399908 2565 1311867804.2092669010 0.2429415137 0.2286328472 0.3266084492 0.0039785398 0.1813180000 984429217 0 402718720 -0.2501502037 -0.0292769484 -0.0909974650 2566 1311867804.2408709526 0.2429754734 0.2286384367 0.3266084492 0.0039782131 0.1816870000 984432065 0 402718720 -0.2506959736 -0.0291287582 -0.0916505530 2567 1311867804.2707660198 0.2429016829 0.2286439931 0.3266084492 0.0039775888 0.1818710000 984434913 0 402718720 -0.2510454357 -0.0283814166 -0.0921242982 2568 1311867804.3078389168 0.2429257929 0.2286495545 0.3266084492 0.0039774038 0.1970250000 984437873 0 402718720 -0.2516401112 -0.0282274839 -0.0927376971 2569 1311867804.3404970169 0.2434085310 0.2286552995 0.3266084492 0.0039766663 0.1813140000 984440833 0 402718720 -0.2525345981 -0.0280117318 -0.0933869556 2570 1311867804.3725171089 0.2432006598 0.2286609592 0.3266084492 0.0039760305 0.1813560000 984443737 0 402718720 -0.2527835369 -0.0272148009 -0.0941239595 2571 1311867804.4121570587 0.2435899973 0.2286667659 0.3266084492 0.0039754848 0.1811640000 984446865 0 402718720 -0.2535171807 -0.0269035418 -0.0946829021 2572 1311867804.4434490204 0.2437260002 0.2286726210 0.3266084492 0.0039747424 0.1803770000 984449769 0 402718720 -0.2537621558 -0.0268625822 -0.0954037830 2573 1311867804.4745810032 0.2439025491 0.2286785401 0.3266084492 0.0039740394 0.1930700000 984452617 0 402718720 -0.2539609671 -0.0265264809 -0.0959823877 2574 1311867804.5092110634 0.2437640429 0.2286844008 0.3266084492 0.0039744709 0.1809200000 984455577 0 402718720 -0.2538607419 -0.0265652537 -0.0967457294 2575 1311867804.5393021107 0.2455657274 0.2286909567 0.3266084492 0.0039740392 0.1805610000 984458425 0 402718720 -0.2556683123 -0.0270604100 -0.0973985493 2576 1311867804.5744440556 0.2452206910 0.2286973735 0.3266084492 0.0039734519 0.1934350000 984461385 0 402718720 -0.2553132176 -0.0263084657 -0.0981148705 2577 1311867804.6065940857 0.2455599755 0.2287039170 0.3266084492 0.0039727412 0.1808060000 984464345 0 402718720 -0.2554388344 -0.0265304856 -0.0986760408 2578 1311867804.6414110661 0.2465199381 0.2287108278 0.3266084492 0.0039725169 0.1853450000 984467305 0 402718720 -0.2560447156 -0.0263878405 -0.0991012976 2579 1311867804.6758968830 0.2456196547 0.2287173842 0.3266084492 0.0039718712 0.1821510000 984470321 0 402718720 -0.2549330592 -0.0254321396 -0.0996265486 2580 1311867804.7094891071 0.2464477271 0.2287242564 0.3266084492 0.0039711637 0.1809260000 984473225 0 402718720 -0.2555552423 -0.0250149909 -0.0999735892 2581 1311867804.7431960106 0.2479426414 0.2287317025 0.3266084492 0.0039724057 0.1810290000 984476185 0 402718720 -0.2565750778 -0.0244484842 -0.1001005098 2582 1311867804.7739880085 0.2480815053 0.2287391966 0.3266084492 0.0039720562 0.1809250000 984478977 0 402718720 -0.2565948069 -0.0236015599 -0.1005584598 2583 1311867804.8113589287 0.2480043024 0.2287466550 0.3266084492 0.0039747812 0.1818850000 984482049 0 402718720 -0.2567043900 -0.0236761793 -0.1008194685 2584 1311867804.8407669067 0.2481754869 0.2287541739 0.3266084492 0.0039744642 0.1823160000 984484897 0 402718720 -0.2566128671 -0.0230862349 -0.1009954065 2585 1311867804.8758749962 0.2483420521 0.2287617514 0.3266084492 0.0039750863 0.1826400000 984487857 0 402718720 -0.2565405071 -0.0226004049 -0.1011006162 2586 1311867804.9093499184 0.2483921051 0.2287693425 0.3266084492 0.0039749926 0.1950520000 984490817 0 402718720 -0.2560727596 -0.0233544484 -0.1013576612 2587 1311867804.9418170452 0.2488175482 0.2287770921 0.3266084492 0.0039759943 0.1952010000 984493721 0 402718720 -0.2562421858 -0.0233287979 -0.1011261642 2588 1311867804.9785380363 0.2483939528 0.2287846720 0.3266084492 0.0039752813 0.2136320000 984496681 0 402718720 -0.2555217147 -0.0227679014 -0.1011246145 2589 1311867805.0090980530 0.2482964844 0.2287922084 0.3266084492 0.0039746917 0.1842610000 984499529 0 402718720 -0.2549950182 -0.0228401404 -0.1011364236 2590 1311867805.0401790142 0.2484606951 0.2287998024 0.3266084492 0.0039739990 0.1819120000 984502433 0 402718720 -0.2546642721 -0.0230921246 -0.1006736830 2591 1311867805.0801899433 0.2483816892 0.2288073601 0.3266084492 0.0039735796 0.1831900000 984505561 0 402718720 -0.2538624108 -0.0230569653 -0.1004385650 2592 1311867805.1079609394 0.2494065911 0.2288153073 0.3266084492 0.0039736859 0.1833740000 984508409 0 402718720 -0.2538398206 -0.0231616180 -0.1000440791 2593 1311867805.1444120407 0.2496079355 0.2288233261 0.3266084492 0.0039747787 0.1928160000 984511425 0 402718720 -0.2532168329 -0.0235234089 -0.0996386632 2594 1311867805.1750040054 0.2498632818 0.2288314371 0.3266084492 0.0039743721 0.1843570000 984514217 0 402718720 -0.2527931333 -0.0234776642 -0.0992371589 2595 1311867805.2100739479 0.2493186891 0.2288393320 0.3266084492 0.0039751376 0.1844240000 984517233 0 402718720 -0.2516693771 -0.0232723597 -0.0987349898 2596 1311867805.2393519878 0.2489322275 0.2288470719 0.3266084492 0.0039744279 0.1843290000 984520081 0 402718720 -0.2507203817 -0.0232076943 -0.0983489230 2597 1311867805.2741580009 0.2497924268 0.2288551371 0.3266084492 0.0039737996 0.1840760000 984523041 0 402718720 -0.2508043051 -0.0232697073 -0.0975818262 2598 1311867805.3108520508 0.2498974651 0.2288632366 0.3266084492 0.0039732283 0.1845800000 984526057 0 402718720 -0.2501249611 -0.0234145764 -0.0971816778 2599 1311867805.3395309448 0.2498892844 0.2288713266 0.3266084492 0.0039725336 0.1837930000 984528905 0 402718720 -0.2495464385 -0.0238512643 -0.0970707461 2600 1311867805.3745789528 0.2504670322 0.2288796327 0.3266084492 0.0039761412 0.1835640000 984531865 0 402718720 -0.2493695021 -0.0240795612 -0.0965693891 2601 1311867805.4084360600 0.2503031194 0.2288878693 0.3266084492 0.0039754426 0.1962360000 984534881 0 402718720 -0.2487341613 -0.0237712692 -0.0962475315 2602 1311867805.4401900768 0.2503481209 0.2288961169 0.3266084492 0.0039747429 0.1835700000 984537729 0 402718720 -0.2485458404 -0.0230340976 -0.0958702713 2603 1311867805.4747269154 0.2501790524 0.2289042932 0.3266084492 0.0039758017 0.1941880000 984540689 0 402718720 -0.2481179088 -0.0232145321 -0.0953200012 2604 1311867805.5079410076 0.2502524257 0.2289124914 0.3266084492 0.0039758416 0.1841800000 984543649 0 402718720 -0.2476936579 -0.0230491254 -0.0946141854 2605 1311867805.5406329632 0.2501575053 0.2289206469 0.3266084492 0.0039752033 0.1835240000 984546609 0 402718720 -0.2471628785 -0.0226896144 -0.0940148756 2606 1311867805.5750451088 0.2500301898 0.2289287472 0.3266084492 0.0039745026 0.1838740000 984549513 0 402718720 -0.2465118319 -0.0234164894 -0.0934625566 2607 1311867805.6078290939 0.2508591712 0.2289371594 0.3266084492 0.0039744063 0.1831880000 984552473 0 402718720 -0.2468092591 -0.0241242610 -0.0931017399 2608 1311867805.6431670189 0.2506579161 0.2289454879 0.3266084492 0.0039763735 0.2026760000 984555489 0 402718720 -0.2463759929 -0.0240389109 -0.0927997380 2609 1311867805.6750800610 0.2514011264 0.2289540949 0.3266084492 0.0039759103 0.1828080000 984558393 0 402718720 -0.2469026893 -0.0240555964 -0.0924921781 2610 1311867805.7071790695 0.2513488829 0.2289626753 0.3266084492 0.0039755980 0.1816610000 984561353 0 402718720 -0.2465637624 -0.0243594982 -0.0923961252 2611 1311867805.7425789833 0.2516587079 0.2289713677 0.3266084492 0.0039775740 0.1806440000 984564369 0 402718720 -0.2462217212 -0.0243660156 -0.0921736360 2612 1311867805.7748079300 0.2518075705 0.2289801105 0.3266084492 0.0039769224 0.1800700000 984567217 0 402718720 -0.2460711598 -0.0240328163 -0.0918792635 2613 1311867805.8089549541 0.2516543865 0.2289887880 0.3266084492 0.0039767071 0.2104560000 984570177 0 402718720 -0.2456247061 -0.0234756824 -0.0917546973 2614 1311867805.8436930180 0.2513000071 0.2289973233 0.3266084492 0.0039790376 0.1789670000 984573081 0 402718720 -0.2450716794 -0.0230855998 -0.0913744569 2615 1311867805.8754489422 0.2514539063 0.2290059109 0.3266084492 0.0039784208 0.1781760000 984575985 0 402718720 -0.2449415922 -0.0230529718 -0.0909719989 2616 1311867805.9129049778 0.2517139614 0.2290145913 0.3266084492 0.0039831201 0.1770930000 984579057 0 402718720 -0.2446054071 -0.0232448950 -0.0904917344 2617 1311867805.9434199333 0.2520307302 0.2290233862 0.3266084492 0.0039841663 0.1754220000 984581961 0 402718720 -0.2445203513 -0.0235879626 -0.0903663561 2618 1311867805.9747679234 0.2512833774 0.2290318889 0.3266084492 0.0039837092 0.1858830000 984584809 0 402718720 -0.2435518056 -0.0229212716 -0.0903609619 2619 1311867806.0099248886 0.2521742284 0.2290407252 0.3266084492 0.0039839101 0.1741780000 984587769 0 402718720 -0.2439475656 -0.0230247863 -0.0899377018 2620 1311867806.0427870750 0.2520461679 0.2290495059 0.3266084492 0.0039834611 0.1741370000 984590785 0 402718720 -0.2432453930 -0.0232305322 -0.0896988139 2621 1311867806.0743720531 0.2520131469 0.2290582673 0.3266084492 0.0039885004 0.1715180000 984593577 0 402718720 -0.2429313362 -0.0226483867 -0.0894120932 2622 1311867806.1078710556 0.2523604333 0.2290671545 0.3266084492 0.0039878476 0.1730300000 984596537 0 402718720 -0.2426117063 -0.0224695820 -0.0890997052 2623 1311867806.1461410522 0.2526610494 0.2290761495 0.3266084492 0.0039874101 0.1813740000 984599609 0 402718720 -0.2417352647 -0.0225924011 -0.0886122957 2624 1311867806.1751658916 0.2528001964 0.2290851907 0.3266084492 0.0039871243 0.1732170000 984602401 0 402718720 -0.2411664575 -0.0220181216 -0.0882165134 2625 1311867806.2106690407 0.2526549697 0.2290941696 0.3266084492 0.0039876700 0.1858060000 984605417 0 402718720 -0.2399306297 -0.0220973659 -0.0878509879 2626 1311867806.2435200214 0.2527616322 0.2291031824 0.3266084492 0.0039870484 0.1733530000 984608377 0 402718720 -0.2391499281 -0.0219820514 -0.0874318555 2627 1311867806.2773389816 0.2526899278 0.2291121609 0.3266084492 0.0039869305 0.1728210000 984611337 0 402718720 -0.2383123487 -0.0210768841 -0.0869742334 2628 1311867806.3098840714 0.2519868016 0.2291208651 0.3266084492 0.0039861743 0.1942300000 984614185 0 402718720 -0.2368262559 -0.0209682360 -0.0867961198 2629 1311867806.3459429741 0.2523898482 0.2291297160 0.3266084492 0.0039863076 0.1734630000 984617257 0 402718720 -0.2364428788 -0.0206314754 -0.0863906816 2630 1311867806.3760368824 0.2520681918 0.2291384379 0.3266084492 0.0039856970 0.1733490000 984620105 0 402718720 -0.2355301976 -0.0198627934 -0.0860018954 2631 1311867806.4090569019 0.2514595687 0.2291469218 0.3266084492 0.0039947700 0.1734230000 984623009 0 402718720 -0.2339080125 -0.0200736504 -0.0860411078 2632 1311867806.4434189796 0.2517704368 0.2291555173 0.3266084492 0.0039956758 0.1996290000 984625969 0 402718720 -0.2335061729 -0.0203929003 -0.0857610777 2633 1311867806.4748079777 0.2514962554 0.2291640022 0.3266084492 0.0039975396 0.1743100000 984628873 0 402718720 -0.2327005118 -0.0200986266 -0.0855502784 2634 1311867806.5103459358 0.2520738244 0.2291727000 0.3266084492 0.0039969871 0.1731090000 984631889 0 402718720 -0.2323592752 -0.0206056461 -0.0852670968 2635 1311867806.5426719189 0.2520459294 0.2291813805 0.3266084492 0.0039969709 0.1715260000 984634793 0 402718720 -0.2317778468 -0.0206707362 -0.0849789158 2636 1311867806.5787520409 0.2522622943 0.2291901366 0.3266084492 0.0039963484 0.1733120000 984637753 0 402718720 -0.2315943241 -0.0196701828 -0.0847570077 2637 1311867806.6116139889 0.2520982325 0.2291988237 0.3266084492 0.0039968550 0.1853360000 984640769 0 402718720 -0.2309760749 -0.0196988471 -0.0843774006 2638 1311867806.6448700428 0.2525875568 0.2292076898 0.3266084492 0.0039961455 0.1832630000 984643673 0 402718720 -0.2310741246 -0.0193232168 -0.0837304443 2639 1311867806.6744968891 0.2523086071 0.2292164435 0.3266084492 0.0039963994 0.1735150000 984646521 0 402718720 -0.2306342572 -0.0183270946 -0.0831186771 2640 1311867806.7064468861 0.2524418235 0.2292252410 0.3266084492 0.0039957480 0.1867410000 984649425 0 402718720 -0.2304943353 -0.0182036255 -0.0825283527 2641 1311867806.7427020073 0.2524733841 0.2292340438 0.3266084492 0.0039951894 0.1741560000 984652441 0 402718720 -0.2298594713 -0.0182739068 -0.0820556134 2642 1311867806.7790679932 0.2517280281 0.2292425578 0.3266084492 0.0039957170 0.1759210000 984655401 0 402718720 -0.2291111350 -0.0177248307 -0.0813012719 2643 1311867806.8067629337 0.2516379654 0.2292510312 0.3266084492 0.0039952844 0.1884580000 984658249 0 402718720 -0.2286364287 -0.0177383944 -0.0807518214 2644 1311867806.8439810276 0.2520536482 0.2292596555 0.3266084492 0.0039946060 0.1754100000 984661265 0 402718720 -0.2285593152 -0.0182729568 -0.0800256804 2645 1311867806.8763918877 0.2517639399 0.2292681638 0.3266084492 0.0039941480 0.1749140000 984664169 0 402718720 -0.2281510383 -0.0175433867 -0.0796052739 2646 1311867806.9124479294 0.2521991134 0.2292768300 0.3266084492 0.0039935284 0.1757580000 984667185 0 402718720 -0.2281269878 -0.0180622004 -0.0793574080 2647 1311867806.9446148872 0.2516724467 0.2292852908 0.3266084492 0.0039930005 0.1754780000 984670033 0 402718720 -0.2269957215 -0.0186062399 -0.0792073458 2648 1311867806.9770460129 0.2513194084 0.2292936118 0.3266084492 0.0039926619 0.1882040000 984673049 0 402718720 -0.2264583856 -0.0182185955 -0.0789877027 2649 1311867807.0138700008 0.2512787879 0.2293019112 0.3266084492 0.0039931156 0.1760910000 984676009 0 402718720 -0.2256917208 -0.0186646916 -0.0787111819 2650 1311867807.0428779125 0.2510956824 0.2293101353 0.3266084492 0.0039926342 0.1748510000 984678913 0 402718720 -0.2247565687 -0.0195029918 -0.0782287419 2651 1311867807.0794920921 0.2509810030 0.2293183099 0.3266084492 0.0039958866 0.1748940000 984681873 0 402718720 -0.2238997817 -0.0197818223 -0.0777245611 2652 1311867807.1121389866 0.2511899173 0.2293265571 0.3266084492 0.0039952256 0.1744780000 984684833 0 402718720 -0.2236190587 -0.0198001768 -0.0772153139 2653 1311867807.1428070068 0.2507254779 0.2293346231 0.3266084492 0.0039945420 0.1845030000 984687737 0 402718720 -0.2224409282 -0.0202865507 -0.0768433660 2654 1311867807.1802010536 0.2508887053 0.2293427444 0.3266084492 0.0039948839 0.1728660000 984690641 0 402718720 -0.2220529318 -0.0201091692 -0.0763302222 2655 1311867807.2105820179 0.2501739562 0.2293505904 0.3266084492 0.0039954550 0.1742310000 984693489 0 402718720 -0.2212244570 -0.0189687926 -0.0758849531 2656 1311867807.2429521084 0.2496541589 0.2293582349 0.3266084492 0.0039948012 0.1735470000 984696393 0 402718720 -0.2202772349 -0.0193667449 -0.0754820406 2657 1311867807.2808670998 0.2502407134 0.2293660943 0.3266084492 0.0039941495 0.1733520000 984699465 0 402718720 -0.2200576961 -0.0201583300 -0.0751540959 2658 1311867807.3107318878 0.2509423792 0.2293742118 0.3266084492 0.0039935672 0.1826910000 984702313 0 402718720 -0.2200604975 -0.0202056542 -0.0745843649 2659 1311867807.3434429169 0.2508707345 0.2293822962 0.3266084492 0.0039930262 0.1731080000 984705217 0 402718720 -0.2193905860 -0.0204215031 -0.0745218843 2660 1311867807.3776888847 0.2510305643 0.2293904347 0.3266084492 0.0039930019 0.1717260000 984708177 0 402718720 -0.2187859118 -0.0212337095 -0.0744806007 2661 1311867807.4111731052 0.2518314719 0.2293988680 0.3266084492 0.0039943237 0.2073550000 984711137 0 402718720 -0.2192828804 -0.0213056840 -0.0742585957 2662 1311867807.4426960945 0.2514381111 0.2294071472 0.3266084492 0.0039938193 0.1711280000 984714041 0 402718720 -0.2183856219 -0.0214439053 -0.0744737610 2663 1311867807.4781239033 0.2511678636 0.2294153187 0.3266084492 0.0039969246 0.1970200000 984717001 0 402718720 -0.2172048837 -0.0226117801 -0.0747158080 2664 1311867807.5104010105 0.2516578138 0.2294236680 0.3266084492 0.0039967387 0.1701630000 984719849 0 402718720 -0.2170193791 -0.0236832686 -0.0745984465 2665 1311867807.5430259705 0.2516179085 0.2294319960 0.3266084492 0.0039968163 0.1691850000 984722753 0 402718720 -0.2165643573 -0.0239528883 -0.0746696144 2666 1311867807.5746030807 0.2518521845 0.2294404057 0.3266084492 0.0039975733 0.1680920000 984725657 0 402718720 -0.2161940634 -0.0260815304 -0.0748555064 2667 1311867807.6121149063 0.2515794039 0.2294487068 0.3266084492 0.0039985614 0.1778330000 984728729 0 402718720 -0.2154792398 -0.0273720138 -0.0753517747 2668 1311867807.6434121132 0.2514826655 0.2294569654 0.3266084492 0.0039995497 0.1660360000 984731633 0 402718720 -0.2153479457 -0.0274857040 -0.0757157207 2669 1311867807.6772611141 0.2508866191 0.2294649945 0.3266084492 0.0039990729 0.1652950000 984734593 0 402718720 -0.2146122009 -0.0282159243 -0.0764789283 2670 1311867807.7112979889 0.2515237927 0.2294732562 0.3266084492 0.0039989601 0.1670950000 984737553 0 402718720 -0.2151626199 -0.0292907562 -0.0768009052 2671 1311867807.7441759109 0.2510904670 0.2294813495 0.3266084492 0.0040009709 0.1624900000 984740513 0 402718720 -0.2152528614 -0.0283815470 -0.0769682452 2672 1311867807.7760479450 0.2502094209 0.2294891070 0.3266084492 0.0040004265 0.1745350000 984743361 0 402718720 -0.2146467268 -0.0280984342 -0.0773313120 2673 1311867807.8105859756 0.2495389879 0.2294966079 0.3266084492 0.0040002676 0.1777790000 984746321 0 402718720 -0.2142303884 -0.0287860949 -0.0775818974 2674 1311867807.8429179192 0.2488487959 0.2295038451 0.3266084492 0.0040002879 0.1614520000 984749225 0 402718720 -0.2138176262 -0.0285818782 -0.0776581541 2675 1311867807.8800721169 0.2475952059 0.2295106082 0.3266084492 0.0040002513 0.1619350000 984752185 0 402718720 -0.2133216113 -0.0276477635 -0.0779495686 2676 1311867807.9118909836 0.2478937209 0.2295174778 0.3266084492 0.0040006023 0.1626570000 984755145 0 402718720 -0.2138486356 -0.0280980077 -0.0780812874 2677 1311867807.9477560520 0.2476554960 0.2295242533 0.3266084492 0.0040006715 0.1637030000 984758105 0 402718720 -0.2135218829 -0.0292365979 -0.0782868043 2678 1311867807.9757928848 0.2473310232 0.2295309026 0.3266084492 0.0040000314 0.1755110000 984760897 0 402718720 -0.2134727836 -0.0289793592 -0.0783610940 2679 1311867808.0103120804 0.2478137165 0.2295377271 0.3266084492 0.0040016462 0.1639460000 984763857 0 402718720 -0.2136828452 -0.0286965109 -0.0785479546 2680 1311867808.0437099934 0.2477497011 0.2295445226 0.3266084492 0.0040011111 0.1637870000 984766817 0 402718720 -0.2135856301 -0.0285304096 -0.0792338848 2681 1311867808.0799739361 0.2489597797 0.2295517644 0.3266084492 0.0040276720 0.1647880000 984769833 0 402718720 -0.2140097171 -0.0292092524 -0.0801496804 2682 1311867808.1118609905 0.2496270239 0.2295592496 0.3266084492 0.0040303370 0.1654540000 984772737 0 402718720 -0.2143651694 -0.0294904690 -0.0809501857 2683 1311867808.1470420361 0.2489417344 0.2295664738 0.3266084492 0.0040297936 0.1795810000 984775697 0 402718720 -0.2135219425 -0.0295581818 -0.0817557126 2684 1311867808.1792190075 0.2486717403 0.2295735920 0.3266084492 0.0040306225 0.1649920000 984778545 0 402718720 -0.2133905590 -0.0289298333 -0.0828982592 2685 1311867808.2112250328 0.2487216592 0.2295807235 0.3266084492 0.0040505445 0.1650710000 984781505 0 402718720 -0.2139623165 -0.0299357232 -0.0839030519 2686 1311867808.2432029247 0.2489364147 0.2295879296 0.3266084492 0.0040499474 0.1767380000 984784465 0 402718720 -0.2136523128 -0.0306393653 -0.0848641768 2687 1311867808.2811930180 0.2491984516 0.2295952279 0.3266084492 0.0040504458 0.1635300000 984787481 0 402718720 -0.2137309760 -0.0304113794 -0.0857276022 2688 1311867808.3112449646 0.2498265505 0.2296027544 0.3266084492 0.0040501981 0.1735350000 984790329 0 402718720 -0.2140201926 -0.0305323061 -0.0861763135 2689 1311867808.3454720974 0.2510452271 0.2296107286 0.3266084492 0.0040498730 0.1644200000 984793289 0 402718720 -0.2147937268 -0.0309191402 -0.0865204558 2690 1311867808.3792409897 0.2504659295 0.2296184814 0.3266084492 0.0040495584 0.1629860000 984796193 0 402718720 -0.2142097801 -0.0306036342 -0.0869418457 2691 1311867808.4111659527 0.2509707510 0.2296264161 0.3266084492 0.0040495849 0.1826060000 984799153 0 402718720 -0.2144979686 -0.0304883830 -0.0876370594 2692 1311867808.4447789192 0.2503524125 0.2296341152 0.3266084492 0.0040493896 0.1628450000 984802057 0 402718720 -0.2139556855 -0.0294401608 -0.0880767331 2693 1311867808.4827229977 0.2509790063 0.2296420413 0.3266084492 0.0040503374 0.1638830000 984805185 0 402718720 -0.2144455016 -0.0299735162 -0.0882543474 2694 1311867808.5103700161 0.2509413064 0.2296499475 0.3266084492 0.0040549477 0.1631480000 984807921 0 402718720 -0.2141487151 -0.0302219652 -0.0887337998 2695 1311867808.5431969166 0.2511444986 0.2296579232 0.3266084492 0.0040548450 0.1624060000 984810937 0 402718720 -0.2144286782 -0.0295894146 -0.0890786573 2696 1311867808.5788240433 0.2521634698 0.2296662710 0.3266084492 0.0040543089 0.1640170000 984813897 0 402718720 -0.2151955813 -0.0302838292 -0.0895052403 2697 1311867808.6111960411 0.2514929473 0.2296743639 0.3266084492 0.0040535812 0.1635320000 984816801 0 402718720 -0.2145992815 -0.0304194055 -0.0898438022 2698 1311867808.6424980164 0.2521456480 0.2296826928 0.3266084492 0.0040529538 0.1739890000 984819705 0 402718720 -0.2152415812 -0.0307949763 -0.0901826024 2699 1311867808.6796329021 0.2522500455 0.2296910542 0.3266084492 0.0040525394 0.1634380000 984822665 0 402718720 -0.2154957950 -0.0306590684 -0.0906033814 2700 1311867808.7121589184 0.2528380156 0.2296996271 0.3266084492 0.0040518950 0.1630840000 984825681 0 402718720 -0.2160695940 -0.0306795035 -0.0910859108 2701 1311867808.7424249649 0.2520802915 0.2297079132 0.3266084492 0.0040516967 0.1635990000 984828529 0 402718720 -0.2148342729 -0.0314383060 -0.0918116346 2702 1311867808.7797210217 0.2530729473 0.2297165605 0.3266084492 0.0040521181 0.1761300000 984831545 0 402718720 -0.2155149430 -0.0319084674 -0.0921307206 2703 1311867808.8102169037 0.2518501580 0.2297247490 0.3266084492 0.0040522521 0.1778880000 984834393 0 402718720 -0.2142527103 -0.0314575210 -0.0929879248 2704 1311867808.8426899910 0.2530507445 0.2297333755 0.3266084492 0.0040551833 0.1642010000 984837297 0 402718720 -0.2149039805 -0.0327084586 -0.0939201936 2705 1311867808.8811960220 0.2537409961 0.2297422508 0.3266084492 0.0040545796 0.1637660000 984840425 0 402718720 -0.2153401524 -0.0328658186 -0.0945740640 2706 1311867808.9101860523 0.2539110184 0.2297511823 0.3266084492 0.0040539741 0.1618670000 984843217 0 402718720 -0.2154045403 -0.0329098515 -0.0949660018 2707 1311867808.9424829483 0.2544566393 0.2297603088 0.3266084492 0.0040536626 0.1639050000 984846177 0 402718720 -0.2154664248 -0.0344991684 -0.0957129225 2708 1311867808.9811229706 0.2547863722 0.2297695503 0.3266084492 0.0040555390 0.1635240000 984849249 0 402718720 -0.2156452090 -0.0347727872 -0.0964703113 2709 1311867809.0102269650 0.2547677755 0.2297787782 0.3266084492 0.0040553175 0.1743430000 984852041 0 402718720 -0.2156753540 -0.0347343460 -0.0972042382 2710 1311867809.0425639153 0.2548949122 0.2297880461 0.3266084492 0.0040550193 0.1637820000 984855001 0 402718720 -0.2150333375 -0.0364401825 -0.0981221348 2711 1311867809.0782320499 0.2550606132 0.2297973684 0.3266084492 0.0040563026 0.1611170000 984857961 0 402718720 -0.2152189910 -0.0359876901 -0.0985474139 2712 1311867809.1110110283 0.2544754744 0.2298064680 0.3266084492 0.0040557705 0.1622450000 984860921 0 402718720 -0.2146412879 -0.0353050753 -0.0993175432 2713 1311867809.1425359249 0.2547307611 0.2298156549 0.3266084492 0.0040556985 0.1776180000 984863825 0 402718720 -0.2144831270 -0.0360465534 -0.0999274328 2714 1311867809.1801810265 0.2553895414 0.2298250779 0.3266084492 0.0040558926 0.1623320000 984866841 0 402718720 -0.2149996459 -0.0356340148 -0.1005190760 2715 1311867809.2120649815 0.2555744946 0.2298345620 0.3266084492 0.0040564154 0.1624810000 984869745 0 402718720 -0.2152776271 -0.0340962783 -0.1005219296 2716 1311867809.2422831059 0.2543949783 0.2298436049 0.3266084492 0.0040557452 0.1660420000 984872649 0 402718720 -0.2137789726 -0.0340174697 -0.1010597125 2717 1311867809.2790520191 0.2552902400 0.2298529706 0.3266084492 0.0040550644 0.1632930000 984875553 0 402718720 -0.2141213268 -0.0345506929 -0.1012881771 2718 1311867809.3103950024 0.2548651397 0.2298621730 0.3266084492 0.0040543801 0.1628120000 984878457 0 402718720 -0.2132027298 -0.0344307385 -0.1014804915 2719 1311867809.3436670303 0.2553322911 0.2298715405 0.3266084492 0.0040537550 0.1636700000 984881417 0 402718720 -0.2130447477 -0.0345772617 -0.1017263085 2720 1311867809.3787779808 0.2551783323 0.2298808444 0.3266084492 0.0040530427 0.1632310000 984884321 0 402718720 -0.2120880634 -0.0352396145 -0.1021999642 2721 1311867809.4101309776 0.2554033995 0.2298902243 0.3266084492 0.0040526167 0.1823040000 984887225 0 402718720 -0.2116050571 -0.0356200486 -0.1027667895 2722 1311867809.4475460052 0.2568562627 0.2299001310 0.3266084492 0.0040526958 0.1637250000 984890297 0 402718720 -0.2119544297 -0.0361579023 -0.1029246673 2723 1311867809.4785499573 0.2566505969 0.2299099549 0.3266084492 0.0040524604 0.1644940000 984893257 0 402718720 -0.2110170275 -0.0364722349 -0.1034192070 2724 1311867809.5100600719 0.2562030852 0.2299196073 0.3266084492 0.0040525046 0.1632200000 984896049 0 402718720 -0.2098468691 -0.0362273790 -0.1041224524 2725 1311867809.5460391045 0.2563376427 0.2299293020 0.3266084492 0.0040519500 0.1626030000 984899121 0 402718720 -0.2091797739 -0.0356575958 -0.1046069115 2726 1311867809.5791211128 0.2571672201 0.2299392939 0.3266084492 0.0040512923 0.1632650000 984902025 0 402718720 -0.2089048028 -0.0358019285 -0.1049870476 2727 1311867809.6122300625 0.2575780749 0.2299494291 0.3266084492 0.0040508696 0.1634960000 984904985 0 402718720 -0.2087381035 -0.0351767279 -0.1054834276 2728 1311867809.6463921070 0.2571882606 0.2299594140 0.3266084492 0.0040502854 0.1731840000 984907945 0 402718720 -0.2075970620 -0.0344759896 -0.1059573069 2729 1311867809.6796839237 0.2570441365 0.2299693388 0.3266084492 0.0040497556 0.1632690000 984910849 0 402718720 -0.2065653801 -0.0337735005 -0.1060365587 2730 1311867809.7111020088 0.2563802302 0.2299790131 0.3266084492 0.0040492474 0.1641430000 984913753 0 402718720 -0.2047494650 -0.0340813883 -0.1066905335 2731 1311867809.7464809418 0.2569940984 0.2299889051 0.3266084492 0.0040485892 0.1635980000 984916769 0 402718720 -0.2041143924 -0.0348243751 -0.1075656340 2732 1311867809.7800478935 0.2581387758 0.2299992089 0.3266084492 0.0040480079 0.1623880000 984919673 0 402718720 -0.2040450573 -0.0352915972 -0.1083365306 2733 1311867809.8107759953 0.2575132847 0.2300092762 0.3266084492 0.0040479866 0.1633380000 984922577 0 402718720 -0.2023892552 -0.0354115963 -0.1096657366 2734 1311867809.8470799923 0.2581137121 0.2300195558 0.3266084492 0.0040473736 0.1629060000 984925593 0 402718720 -0.2019450217 -0.0364554971 -0.1109262109 2735 1311867809.8791100979 0.2586447597 0.2300300221 0.3266084492 0.0040469874 0.1615110000 984928497 0 402718720 -0.2016241997 -0.0371368006 -0.1126269922 2736 1311867809.9124441147 0.2591655850 0.2300406711 0.3266084492 0.0040465338 0.1606600000 984931401 0 402718720 -0.2012540698 -0.0378718115 -0.1138875037 2737 1311867809.9469900131 0.2589495480 0.2300512333 0.3266084492 0.0040463340 0.1594940000 984934361 0 402718720 -0.2004325092 -0.0385040268 -0.1150824055 2738 1311867809.9805769920 0.2596904933 0.2300620585 0.3266084492 0.0040474904 0.1698140000 984937209 0 402718720 -0.2010735422 -0.0385347120 -0.1160859615 2739 1311867810.0119459629 0.2591758370 0.2300726878 0.3266084492 0.0040468677 0.1576140000 984940057 0 402718720 -0.2005399615 -0.0383812971 -0.1171172112 2740 1311867810.0470910072 0.2595699430 0.2300834532 0.3266084492 0.0040462632 0.1567020000 984943017 0 402718720 -0.2007969171 -0.0388921164 -0.1173974201 2741 1311867810.0808799267 0.2593021095 0.2300941131 0.3266084492 0.0040463429 0.1573090000 984945921 0 402718720 -0.2009450197 -0.0380773544 -0.1177772582 2742 1311867810.1118919849 0.2581481338 0.2301043443 0.3266084492 0.0040456183 0.1571060000 984948825 0 402718720 -0.1998398453 -0.0378478356 -0.1181752756 2743 1311867810.1474719048 0.2583216131 0.2301146313 0.3266084492 0.0040449602 0.1701250000 984951841 0 402718720 -0.1999291629 -0.0382010005 -0.1185734719 2744 1311867810.1817660332 0.2580915391 0.2301248270 0.3266084492 0.0040443626 0.1566950000 984954745 0 402718720 -0.1997649968 -0.0381161943 -0.1190037504 2745 1311867810.2106039524 0.2576253712 0.2301348454 0.3266084492 0.0040436826 0.1560660000 984957593 0 402718720 -0.1993798018 -0.0375898108 -0.1197737902 2746 1311867810.2471721172 0.2576994300 0.2301448835 0.3266084492 0.0040450915 0.1568780000 984960609 0 402718720 -0.1990661025 -0.0372975804 -0.1204276159 2747 1311867810.2785871029 0.2582215965 0.2301551043 0.3266084492 0.0040444221 0.1569470000 984963457 0 402718720 -0.1996747106 -0.0370874219 -0.1211665645 2748 1311867810.3111360073 0.2589697242 0.2301655900 0.3266084492 0.0040440511 0.1576480000 984966417 0 402718720 -0.2004615068 -0.0370364487 -0.1216391325 2749 1311867810.3463029861 0.2593526542 0.2301762074 0.3266084492 0.0040435796 0.1566990000 984969433 0 402718720 -0.2006382048 -0.0374691077 -0.1220083758 2750 1311867810.3784830570 0.2606364489 0.2301872838 0.3266084492 0.0040434583 0.1570110000 984972393 0 402718720 -0.2018273324 -0.0382122286 -0.1225249022 2751 1311867810.4100239277 0.2609820068 0.2301984778 0.3266084492 0.0040433621 0.1690600000 984975185 0 402718720 -0.2021850348 -0.0386165753 -0.1232035160 2752 1311867810.4462749958 0.2617468238 0.2302099416 0.3266084492 0.0040427756 0.1573480000 984978201 0 402718720 -0.2028720975 -0.0389301181 -0.1237865686 2753 1311867810.4781119823 0.2619594634 0.2302214743 0.3266084492 0.0040420987 0.1832630000 984981049 0 402718720 -0.2032067329 -0.0381558165 -0.1243380383 2754 1311867810.5101990700 0.2623775899 0.2302331505 0.3266084492 0.0040414454 0.1574670000 984983953 0 402718720 -0.2036715150 -0.0374351367 -0.1245991215 2755 1311867810.5459640026 0.2624173164 0.2302448325 0.3266084492 0.0040408773 0.1577280000 984986969 0 402718720 -0.2034264803 -0.0373279303 -0.1250923574 2756 1311867810.5791409016 0.2623410523 0.2302564785 0.3266084492 0.0040401605 0.1580420000 984989873 0 402718720 -0.2034501880 -0.0366205275 -0.1255172342 2757 1311867810.6141140461 0.2629716694 0.2302683447 0.3266084492 0.0040395520 0.1592540000 984992889 0 402718720 -0.2041295469 -0.0365166254 -0.1257902086 2758 1311867810.6471910477 0.2630595565 0.2302802342 0.3266084492 0.0040389928 0.1701930000 984995849 0 402718720 -0.2041391432 -0.0368287601 -0.1260441691 2759 1311867810.6781129837 0.2628535628 0.2302920404 0.3266084492 0.0040384677 0.1616000000 984998697 0 402718720 -0.2041137218 -0.0361333713 -0.1263241768 2760 1311867810.7146449089 0.2619213164 0.2303035003 0.3266084492 0.0040379876 0.1623810000 985001713 0 402718720 -0.2029633522 -0.0357962996 -0.1266603470 2761 1311867810.7468900681 0.2623108923 0.2303150930 0.3266084492 0.0040373388 0.1625130000 985004673 0 402718720 -0.2033021152 -0.0358625874 -0.1271168739 2762 1311867810.7789669037 0.2625970840 0.2303267809 0.3266084492 0.0040375195 0.1738280000 985007577 0 402718720 -0.2034456134 -0.0357356183 -0.1275833249 2763 1311867810.8146491051 0.2628714442 0.2303385596 0.3266084492 0.0040368275 0.1758550000 985010537 0 402718720 -0.2032146305 -0.0361605249 -0.1281233579 2764 1311867810.8460769653 0.2638470531 0.2303506828 0.3266084492 0.0040401074 0.1629600000 985013441 0 402718720 -0.2043578327 -0.0357566886 -0.1283184588 2765 1311867810.8793289661 0.2634386718 0.2303626495 0.3266084492 0.0040398434 0.1629690000 985016401 0 402718720 -0.2037700564 -0.0352201648 -0.1282933801 2766 1311867810.9141631126 0.2642785311 0.2303749112 0.3266084492 0.0040401100 0.1635720000 985019417 0 402718720 -0.2041303813 -0.0355595537 -0.1280567199 2767 1311867810.9458940029 0.2645951509 0.2303872785 0.3266084492 0.0040447852 0.1634430000 985022265 0 402718720 -0.2037211657 -0.0356908701 -0.1282836348 2768 1311867810.9796259403 0.2634131908 0.2303992098 0.3266084492 0.0040443249 0.1765620000 985025169 0 402718720 -0.2022979259 -0.0349880829 -0.1288969666 2769 1311867811.0151500702 0.2640080452 0.2304113474 0.3266084492 0.0040484244 0.1634880000 985028185 0 402718720 -0.2027615756 -0.0349081643 -0.1294118911 2770 1311867811.0469939709 0.2643133402 0.2304235864 0.3266084492 0.0040487452 0.1635900000 985031089 0 402718720 -0.2026877701 -0.0344793200 -0.1297229826 2771 1311867811.0785760880 0.2646922171 0.2304359532 0.3266084492 0.0040488632 0.1632400000 985033993 0 402718720 -0.2026077658 -0.0343438722 -0.1302306205 2772 1311867811.1144239902 0.2644526064 0.2304482248 0.3266084492 0.0040490397 0.1630410000 985037009 0 402718720 -0.2021422386 -0.0337728970 -0.1306765527 2773 1311867811.1461989880 0.2651510537 0.2304607393 0.3266084492 0.0040496373 0.1817150000 985039913 0 402718720 -0.2025114149 -0.0333380960 -0.1308614612 2774 1311867811.1786370277 0.2650516033 0.2304732090 0.3266084492 0.0040491929 0.1633950000 985042873 0 402718720 -0.2019776553 -0.0328406878 -0.1311872005 2775 1311867811.2142488956 0.2638570070 0.2304852392 0.3266084492 0.0040486837 0.1635690000 985045777 0 402718720 -0.2002968341 -0.0325211473 -0.1317308098 2776 1311867811.2464840412 0.2632859349 0.2304970550 0.3266084492 0.0040482266 0.1638400000 985048737 0 402718720 -0.1996968687 -0.0315550938 -0.1320373118 2777 1311867811.2798390388 0.2633048892 0.2305088691 0.3266084492 0.0040477670 0.1755030000 985051697 0 402718720 -0.1995054334 -0.0309027601 -0.1322594285 2778 1311867811.3147039413 0.2642008662 0.2305209973 0.3266084492 0.0040487410 0.1636230000 985054657 0 402718720 -0.2001021504 -0.0307622384 -0.1326441318 2779 1311867811.3470849991 0.2636391521 0.2305329146 0.3266084492 0.0040493536 0.1634670000 985057561 0 402718720 -0.1993961334 -0.0304415114 -0.1331010163 2780 1311867811.3799240589 0.2645984292 0.2305451683 0.3266084492 0.0040490507 0.1625950000 985060465 0 402718720 -0.2000637054 -0.0298459437 -0.1333159357 2781 1311867811.4141869545 0.2643648684 0.2305573293 0.3266084492 0.0040490904 0.1636200000 985063425 0 402718720 -0.1992621124 -0.0296433736 -0.1335036308 2782 1311867811.4464430809 0.2644269764 0.2305695039 0.3266084492 0.0040485099 0.1640650000 985066385 0 402718720 -0.1989057511 -0.0292270612 -0.1341407150 2783 1311867811.4788289070 0.2641580999 0.2305815731 0.3266084492 0.0040485374 0.1649870000 985069345 0 402718720 -0.1983884126 -0.0285211131 -0.1348305494 2784 1311867811.5141620636 0.2647272944 0.2305938381 0.3266084492 0.0040500489 0.1646290000 985072249 0 402718720 -0.1983149052 -0.0282462779 -0.1348492503 2785 1311867811.5465340614 0.2642868161 0.2306059361 0.3266084492 0.0040501920 0.1771090000 985075209 0 402718720 -0.1970923841 -0.0280268434 -0.1352367550 2786 1311867811.5787150860 0.2638706863 0.2306178761 0.3266084492 0.0040528600 0.1640540000 985078113 0 402718720 -0.1962781549 -0.0269171391 -0.1361559182 2787 1311867811.6143789291 0.2625624239 0.2306293381 0.3266084492 0.0040542154 0.1643570000 985081073 0 402718720 -0.1947222352 -0.0261120833 -0.1364793479 2788 1311867811.6465210915 0.2617071271 0.2306404850 0.3266084492 0.0040585337 0.1745320000 985084033 0 402718720 -0.1934255809 -0.0263778251 -0.1364795268 2789 1311867811.6790111065 0.2627104819 0.2306519838 0.3266084492 0.0040588565 0.1644630000 985086881 0 402718720 -0.1938954592 -0.0260892436 -0.1362313926 2790 1311867811.7141160965 0.2614715695 0.2306630302 0.3266084492 0.0040595981 0.1635480000 985089897 0 402718720 -0.1925106943 -0.0245248787 -0.1365629435 2791 1311867811.7471590042 0.2615141869 0.2306740840 0.3266084492 0.0040593897 0.1755860000 985092857 0 402718720 -0.1925495714 -0.0239639524 -0.1370037496 2792 1311867811.7787630558 0.2611145377 0.2306849868 0.3266084492 0.0040587860 0.1638250000 985095761 0 402718720 -0.1919486523 -0.0240586307 -0.1375373602 2793 1311867811.8140239716 0.2608994246 0.2306958047 0.3266084492 0.0040581707 0.1766270000 985098777 0 402718720 -0.1917150021 -0.0237268601 -0.1377898902 2794 1311867811.8467700481 0.2605811954 0.2307065010 0.3266084492 0.0040575917 0.1767090000 985101681 0 402718720 -0.1912840903 -0.0233462360 -0.1379709393 2795 1311867811.8873019218 0.2601232231 0.2307170257 0.3266084492 0.0040573519 0.1641310000 985104809 0 402718720 -0.1906270236 -0.0232640933 -0.1382562518 2796 1311867811.9162950516 0.2596243918 0.2307273646 0.3266084492 0.0040568356 0.1631950000 985107545 0 402718720 -0.1901534498 -0.0231239442 -0.1387276202 2797 1311867811.9480459690 0.2600106001 0.2307378341 0.3266084492 0.0040563914 0.1627100000 985110393 0 402718720 -0.1904347986 -0.0232230034 -0.1389305890 2798 1311867811.9825990200 0.2599217594 0.2307482643 0.3266084492 0.0040560121 0.1752250000 985113409 0 402718720 -0.1900290251 -0.0235573947 -0.1394281387 2799 1311867812.0155920982 0.2596088052 0.2307585754 0.3266084492 0.0040554359 0.1623720000 985116313 0 402718720 -0.1893577278 -0.0236332361 -0.1395650506 2800 1311867812.0471529961 0.2587735355 0.2307685807 0.3266084492 0.0040548446 0.1617080000 985119217 0 402718720 -0.1884714216 -0.0233096723 -0.1400508881 2801 1311867812.0860528946 0.2599136531 0.2307789859 0.3266084492 0.0040543029 0.1616610000 985122345 0 402718720 -0.1893464327 -0.0236525517 -0.1400348991 2802 1311867812.1176469326 0.2597366571 0.2307893206 0.3266084492 0.0040539427 0.1612460000 985125249 0 402718720 -0.1889141500 -0.0237470549 -0.1399446577 2803 1311867812.1501319408 0.2586859465 0.2307992730 0.3266084492 0.0040532467 0.1881910000 985128097 0 402718720 -0.1875724792 -0.0234760325 -0.1401520818 2804 1311867812.1841530800 0.2591481805 0.2308093832 0.3266084492 0.0040525820 0.1610940000 985131113 0 402718720 -0.1876336187 -0.0235720165 -0.1400179416 2805 1311867812.2161788940 0.2599390447 0.2308197681 0.3266084492 0.0040588978 0.1612780000 985134017 0 402718720 -0.1876470298 -0.0238318667 -0.1398702264 2806 1311867812.2469139099 0.2600892782 0.2308301991 0.3266084492 0.0040585287 0.1610800000 985136865 0 402718720 -0.1875330508 -0.0236719344 -0.1399330348 2807 1311867812.2830879688 0.2596612275 0.2308404702 0.3266084492 0.0040684970 0.1606700000 985139937 0 402718720 -0.1870601922 -0.0234446600 -0.1399926096 2808 1311867812.3143959045 0.2596897483 0.2308507442 0.3266084492 0.0040773600 0.1712620000 985142729 0 402718720 -0.1862976104 -0.0233016834 -0.1398124844 2809 1311867812.3466560841 0.2591058612 0.2308608030 0.3266084492 0.0040767072 0.1594610000 985145689 0 402718720 -0.1852284819 -0.0231578052 -0.1396023929 2810 1311867812.3833289146 0.2585222125 0.2308706469 0.3266084492 0.0040769784 0.1592370000 985148761 0 402718720 -0.1842919588 -0.0228286721 -0.1395756751 2811 1311867812.4177269936 0.2593388259 0.2308807743 0.3266084492 0.0040764064 0.1587660000 985151721 0 402718720 -0.1845370084 -0.0227160193 -0.1396184713 2812 1311867812.4586019516 0.2594915926 0.2308909489 0.3266084492 0.0040758478 0.1722440000 985154849 0 402718720 -0.1839765459 -0.0230562165 -0.1394072175 2813 1311867812.4830911160 0.2596271932 0.2309011644 0.3266084492 0.0040755044 0.1745800000 985157417 0 402718720 -0.1840600371 -0.0229502991 -0.1397114396 2814 1311867812.5157220364 0.2594226003 0.2309112999 0.3266084492 0.0040793749 0.1574100000 985160265 0 402718720 -0.1839047521 -0.0227368958 -0.1397507638 2815 1311867812.5469310284 0.2590539157 0.2309212973 0.3266084492 0.0040787279 0.1573320000 985163169 0 402718720 -0.1831903756 -0.0225084629 -0.1400563419 2816 1311867812.5857439041 0.2591336668 0.2309313159 0.3266084492 0.0040781415 0.1565410000 985166241 0 402718720 -0.1828337759 -0.0226391274 -0.1400382221 2817 1311867812.6147639751 0.2581913471 0.2309409929 0.3266084492 0.0040774623 0.1559050000 985169033 0 402718720 -0.1816470921 -0.0224757548 -0.1403103620 2818 1311867812.6462490559 0.2589039207 0.2309509158 0.3266084492 0.0040777024 0.1657480000 985171993 0 402718720 -0.1821821034 -0.0224607475 -0.1403649151 2819 1311867812.6821310520 0.2584277093 0.2309606628 0.3266084492 0.0040771579 0.1546920000 985175009 0 402718720 -0.1817047149 -0.0220269784 -0.1406511664 2820 1311867812.7141439915 0.2577767074 0.2309701721 0.3266084492 0.0040769123 0.1545110000 985177857 0 402718720 -0.1811209768 -0.0217929594 -0.1407472491 2821 1311867812.7468860149 0.2573238015 0.2309795140 0.3266084492 0.0040763660 0.1534860000 985180817 0 402718720 -0.1808275729 -0.0214041751 -0.1411185414 2822 1311867812.7839629650 0.2580386996 0.2309891027 0.3266084492 0.0040760243 0.1536580000 985183889 0 402718720 -0.1816180199 -0.0213160310 -0.1409453452 2823 1311867812.8143351078 0.2573883832 0.2309984542 0.3266084492 0.0040773057 0.1533890000 985186681 0 402718720 -0.1810808033 -0.0210001040 -0.1411385238 2824 1311867812.8463029861 0.2571835816 0.2310077265 0.3266084492 0.0040769656 0.1531160000 985189641 0 402718720 -0.1812969744 -0.0202336684 -0.1414287090 2825 1311867812.8841478825 0.2570680976 0.2310169514 0.3266084492 0.0040806953 0.1522460000 985192713 0 402718720 -0.1816446632 -0.0199187491 -0.1416752636 2826 1311867812.9142088890 0.2573357224 0.2310262645 0.3266084492 0.0040804799 0.1516750000 985195505 0 402718720 -0.1821146309 -0.0201420914 -0.1416742504 2827 1311867812.9470400810 0.2578243613 0.2310357439 0.3266084492 0.0040799546 0.1511740000 985198465 0 402718720 -0.1829136610 -0.0200131685 -0.1413837820 2828 1311867812.9833469391 0.2576897442 0.2310451689 0.3266084492 0.0040800981 0.1618680000 985201425 0 402718720 -0.1833330095 -0.0191624910 -0.1412090361 2829 1311867813.0143780708 0.2575013340 0.2310545207 0.3266084492 0.0040870553 0.1503100000 985204329 0 402718720 -0.1832208186 -0.0188418403 -0.1413074136 2830 1311867813.0462698936 0.2572327554 0.2310637709 0.3266084492 0.0040950249 0.1511180000 985207233 0 402718720 -0.1836618632 -0.0185210612 -0.1411034167 2831 1311867813.0825068951 0.2555700839 0.2310724274 0.3266084492 0.0041005834 0.1506620000 985210305 0 402718720 -0.1823757291 -0.0179269668 -0.1415584385 2832 1311867813.1142160892 0.2568939924 0.2310815451 0.3266084492 0.0041057342 0.1514820000 985213209 0 402718720 -0.1843902171 -0.0178406630 -0.1411891431 2833 1311867813.1504809856 0.2572254241 0.2310907735 0.3266084492 0.0041059238 0.1690280000 985216169 0 402718720 -0.1846335232 -0.0184554309 -0.1412295848 2834 1311867813.1829130650 0.2559832931 0.2310995570 0.3266084492 0.0041059711 0.1501360000 985219129 0 402718720 -0.1840570718 -0.0175904073 -0.1415489167 2835 1311867813.2166841030 0.2571594715 0.2311087492 0.3266084492 0.0041063595 0.1499710000 985222033 0 402718720 -0.1857389957 -0.0172295757 -0.1415240616 2836 1311867813.2536849976 0.2566904128 0.2311177695 0.3266084492 0.0041067603 0.1618050000 985225049 0 402718720 -0.1856478304 -0.0173735414 -0.1416261345 2837 1311867813.2831010818 0.2565567195 0.2311267364 0.3266084492 0.0041145650 0.1493690000 985227897 0 402718720 -0.1854885668 -0.0166447312 -0.1417368203 2838 1311867813.3142321110 0.2570123971 0.2311358575 0.3266084492 0.0041159502 0.1598330000 985230801 0 402718720 -0.1864956021 -0.0160223264 -0.1418917030 2839 1311867813.3517169952 0.2565031052 0.2311447928 0.3266084492 0.0041349709 0.1495310000 985233817 0 402718720 -0.1864073873 -0.0164365731 -0.1417191029 2840 1311867813.3851261139 0.2579204142 0.2311542208 0.3266084492 0.0041346007 0.1492000000 985236777 0 402718720 -0.1877669990 -0.0166057777 -0.1412576735 2841 1311867813.4148280621 0.2571368217 0.2311633664 0.3266084492 0.0041529574 0.1485930000 985239569 0 402718720 -0.1866130531 -0.0161308181 -0.1412093341 2842 1311867813.4501829147 0.2560606301 0.2311721269 0.3266084492 0.0041683757 0.1487120000 985242529 0 402718720 -0.1857827604 -0.0155942906 -0.1414288729 2843 1311867813.4843769073 0.2567288876 0.2311811162 0.3266084492 0.0041689274 0.1677320000 985245545 0 402718720 -0.1863156557 -0.0147591755 -0.1411214918 2844 1311867813.5152790546 0.2558327317 0.2311897842 0.3266084492 0.0041752580 0.1482290000 985248393 0 402718720 -0.1855347902 -0.0143291038 -0.1410128027 2845 1311867813.5519089699 0.2565432787 0.2311986958 0.3266084492 0.0041790638 0.1476140000 985251409 0 402718720 -0.1864169687 -0.0134877190 -0.1410091370 2846 1311867813.5863409042 0.2566265166 0.2312076303 0.3266084492 0.0041785360 0.1483670000 985254369 0 402718720 -0.1870077848 -0.0121168541 -0.1411061883 2847 1311867813.6168019772 0.2563893795 0.2312164753 0.3266084492 0.0041943123 0.1473440000 985257217 0 402718720 -0.1872200519 -0.0118028289 -0.1410676241 2848 1311867813.6515810490 0.2568419278 0.2312254730 0.3266084492 0.0041941872 0.1538370000 985260177 0 402718720 -0.1875151098 -0.0113703525 -0.1410337985 2849 1311867813.6860060692 0.2569182515 0.2312344912 0.3266084492 0.0041939481 0.1477970000 985263137 0 402718720 -0.1873914003 -0.0106513379 -0.1413273811 2850 1311867813.7184169292 0.2567975223 0.2312434607 0.3266084492 0.0041933113 0.1462500000 985266041 0 402718720 -0.1872721612 -0.0099702450 -0.1416107714 2851 1311867813.7506020069 0.2564562559 0.2312523042 0.3266084492 0.0041928567 0.1570820000 985268945 0 402718720 -0.1870856434 -0.0091872513 -0.1421875507 2852 1311867813.7827889919 0.2576131523 0.2312615471 0.3266084492 0.0041922982 0.1463940000 985271905 0 402718720 -0.1883241385 -0.0081081986 -0.1425874084 2853 1311867813.8147668839 0.2585066855 0.2312710968 0.3266084492 0.0041916826 0.1603850000 985274697 0 402718720 -0.1890121996 -0.0075239842 -0.1425783038 2854 1311867813.8517930508 0.2591274679 0.2312808572 0.3266084492 0.0041912095 0.1459000000 985277825 0 402718720 -0.1893037856 -0.0071901018 -0.1429556906 2855 1311867813.8838069439 0.2590343654 0.2312905783 0.3266084492 0.0041914632 0.1446540000 985280673 0 402718720 -0.1886401176 -0.0061955769 -0.1436273009 2856 1311867813.9144020081 0.2615824044 0.2313011846 0.3266084492 0.0041914067 0.1443240000 985283521 0 402718720 -0.1912286431 -0.0055539203 -0.1437205076 2857 1311867813.9523379803 0.2619138360 0.2313118996 0.3266084492 0.0041913191 0.1442220000 985286649 0 402718720 -0.1912016273 -0.0047135199 -0.1437231898 2858 1311867813.9825320244 0.2623175383 0.2313227483 0.3266084492 0.0041909092 0.1540350000 985289497 0 402718720 -0.1914050877 -0.0028286339 -0.1440842450 2859 1311867814.0155770779 0.2638834119 0.2313341372 0.3266084492 0.0041945698 0.1436230000 985292401 0 402718720 -0.1919833571 -0.0021359592 -0.1440386921 2860 1311867814.0528070927 0.2634905875 0.2313453807 0.3266084492 0.0041939298 0.1419660000 985295529 0 402718720 -0.1914623678 -0.0017798389 -0.1443644315 2861 1311867814.0849530697 0.2616853714 0.2313559854 0.3266084492 0.0041938439 0.1413540000 985298377 0 402718720 -0.1895960718 -0.0003261909 -0.1450109482 2862 1311867814.1153879166 0.2623375654 0.2313668105 0.3266084492 0.0041937511 0.1421220000 985301225 0 402718720 -0.1898969859 0.0000589479 -0.1449494511 2863 1311867814.1526429653 0.2620401978 0.2313775242 0.3266084492 0.0041935404 0.1557600000 985304353 0 402718720 -0.1887966841 0.0002299229 -0.1449171901 2864 1311867814.1845281124 0.2597410381 0.2313874277 0.3266084492 0.0041942659 0.1392930000 985307257 0 402718720 -0.1859820336 0.0009224828 -0.1455134749 2865 1311867814.2153480053 0.2576964498 0.2313966106 0.3266084492 0.0041944669 0.1388290000 985310049 0 402718720 -0.1834580004 0.0007629144 -0.1457447559 2866 1311867814.2520170212 0.2543831468 0.2314046310 0.3266084492 0.0041961389 0.1384400000 985313121 0 402718720 -0.1798714548 0.0016772612 -0.1463735104 2867 1311867814.2834239006 0.2521347702 0.2314118616 0.3266084492 0.0041957200 0.1372740000 985316081 0 402718720 -0.1770429313 0.0018429031 -0.1469530612 2868 1311867814.3181779385 0.2508379221 0.2314186350 0.3266084492 0.0041957013 0.1476460000 985319041 0 402718720 -0.1754230261 0.0024715243 -0.1474670470 2869 1311867814.3510050774 0.2487623096 0.2314246802 0.3266084492 0.0041986439 0.1349230000 985321889 0 402718720 -0.1730533540 0.0032206154 -0.1482484341 2870 1311867814.3861339092 0.2494299114 0.2314309538 0.3266084492 0.0041980131 0.1355470000 985324905 0 402718720 -0.1735818386 0.0034979715 -0.1484776437 2871 1311867814.4182898998 0.2484879494 0.2314368949 0.3266084492 0.0041974513 0.1355180000 985327809 0 402718720 -0.1722888649 0.0038755189 -0.1490400583 2872 1311867814.4512650967 0.2479196638 0.2314426341 0.3266084492 0.0041968459 0.1358060000 985330769 0 402718720 -0.1716124564 0.0045206584 -0.1497777998 2873 1311867814.4847788811 0.2482859641 0.2314484967 0.3266084492 0.0041961772 0.1506120000 985333673 0 402718720 -0.1719780862 0.0049686292 -0.1498455703 2874 1311867814.5201790333 0.2478406429 0.2314542003 0.3266084492 0.0042031917 0.1355230000 985336689 0 402718720 -0.1717974693 0.0056754760 -0.1501346081 2875 1311867814.5517210960 0.2478657067 0.2314599086 0.3266084492 0.0042026193 0.1358210000 985339593 0 402718720 -0.1720791608 0.0056858757 -0.1501919478 2876 1311867814.5848219395 0.2486880869 0.2314658990 0.3266084492 0.0042020385 0.1349020000 985342441 0 402718720 -0.1733552516 0.0057696970 -0.1501666456 2877 1311867814.6200098991 0.2475066632 0.2314714745 0.3266084492 0.0042018146 0.1346330000 985345401 0 402718720 -0.1727237701 0.0058392910 -0.1504638195 2878 1311867814.6503028870 0.2504285872 0.2314780614 0.3266084492 0.0042017531 0.1473570000 985348305 0 402718720 -0.1764948666 0.0060406248 -0.1503142864 2879 1311867814.6833140850 0.2511676252 0.2314849004 0.3266084492 0.0042012305 0.1351890000 985351209 0 402718720 -0.1774313450 0.0058778711 -0.1497871131 2880 1311867814.7211821079 0.2505294681 0.2314915131 0.3266084492 0.0042011637 0.1361460000 985354281 0 402718720 -0.1774975061 0.0069453535 -0.1497995704 2881 1311867814.7502319813 0.2531123459 0.2314990177 0.3266084492 0.0042007522 0.1361790000 985357129 0 402718720 -0.1807004809 0.0074134483 -0.1490320861 2882 1311867814.7828900814 0.2516099513 0.2315059959 0.3266084492 0.0042005480 0.1368540000 985360033 0 402718720 -0.1794370860 0.0081353867 -0.1491075009 2883 1311867814.8186480999 0.2528334260 0.2315133935 0.3266084492 0.0042005108 0.1629970000 985363049 0 402718720 -0.1807133257 0.0088452473 -0.1482838988 2884 1311867814.8526010513 0.2527318895 0.2315207508 0.3266084492 0.0042001369 0.1364390000 985366009 0 402718720 -0.1803504676 0.0088051669 -0.1479805857 2885 1311867814.8852329254 0.2523124814 0.2315279577 0.3266084492 0.0041999136 0.1475820000 985368913 0 402718720 -0.1800320596 0.0095190480 -0.1479547173 2886 1311867814.9202771187 0.2531561553 0.2315354518 0.3266084492 0.0041993582 0.1494400000 985371929 0 402718720 -0.1809899956 0.0099974694 -0.1475585252 2887 1311867814.9503459930 0.2527808845 0.2315428108 0.3266084492 0.0041990273 0.1371640000 985374777 0 402718720 -0.1802477986 0.0102519458 -0.1474012285 2888 1311867814.9839959145 0.2547919750 0.2315508611 0.3266084492 0.0042007641 0.1463140000 985377737 0 402718720 -0.1822420508 0.0109789437 -0.1469867826 2889 1311867815.0193099976 0.2551978230 0.2315590463 0.3266084492 0.0042032555 0.1370060000 985380641 0 402718720 -0.1824269593 0.0113722086 -0.1466265917 2890 1311867815.0509970188 0.2565959096 0.2315677096 0.3266084492 0.0042026810 0.1373990000 985383489 0 402718720 -0.1834843457 0.0119055212 -0.1463350356 2891 1311867815.0835149288 0.2576173842 0.2315767202 0.3266084492 0.0042033683 0.1377230000 985386393 0 402718720 -0.1837998629 0.0119433543 -0.1460465342 2892 1311867815.1192519665 0.2593221664 0.2315863140 0.3266084492 0.0042028372 0.1483880000 985389409 0 402718720 -0.1849124134 0.0126722846 -0.1460392624 2893 1311867815.1505639553 0.2613380849 0.2315965981 0.3266084492 0.0042034990 0.1535490000 985392257 0 402718720 -0.1861545593 0.0124556823 -0.1457852423 2894 1311867815.1827230453 0.2622763813 0.2316071992 0.3266084492 0.0042034279 0.1379320000 985395217 0 402718720 -0.1861013621 0.0127754724 -0.1458647847 2895 1311867815.2192549706 0.2644899786 0.2316185577 0.3266084492 0.0042051612 0.1370910000 985398233 0 402718720 -0.1876043528 0.0136190075 -0.1458659023 2896 1311867815.2503280640 0.2648180127 0.2316300216 0.3266084492 0.0042047217 0.1378950000 985401081 0 402718720 -0.1870518327 0.0138272000 -0.1456110030 2897 1311867815.2826719284 0.2652430832 0.2316416243 0.3266084492 0.0042041968 0.1386360000 985404041 0 402718720 -0.1866708547 0.0142725538 -0.1452216804 2898 1311867815.3188140392 0.2662960291 0.2316535824 0.3266084492 0.0042035633 0.1494700000 985407057 0 402718720 -0.1873131096 0.0147097167 -0.1450331360 2899 1311867815.3506569862 0.2668184638 0.2316657124 0.3266084492 0.0042028902 0.1396550000 985409905 0 402718720 -0.1872499138 0.0150455553 -0.1450224072 2900 1311867815.3841490746 0.2662820518 0.2316776490 0.3266084492 0.0042024207 0.1504630000 985412865 0 402718720 -0.1861118525 0.0154446280 -0.1448220313 2901 1311867815.4187209606 0.2676021755 0.2316900325 0.3266084492 0.0042031047 0.1403910000 985415881 0 402718720 -0.1872581989 0.0158211421 -0.1444104016 2902 1311867815.4505259991 0.2674389184 0.2317023513 0.3266084492 0.0042025355 0.1410140000 985418729 0 402718720 -0.1868791431 0.0162782930 -0.1440492272 2903 1311867815.4827210903 0.2678795457 0.2317148133 0.3266084492 0.0042024738 0.1420080000 985421689 0 402718720 -0.1870678067 0.0164533127 -0.1435235888 2904 1311867815.5188379288 0.2683924437 0.2317274433 0.3266084492 0.0042020753 0.1415960000 985424705 0 402718720 -0.1874650568 0.0168869551 -0.1430799812 2905 1311867815.5508639812 0.2673630416 0.2317397103 0.3266084492 0.0042014819 0.1413000000 985427553 0 402718720 -0.1864249855 0.0176189505 -0.1430920511 2906 1311867815.5879790783 0.2666621506 0.2317517276 0.3266084492 0.0042015460 0.1411010000 985430625 0 402718720 -0.1853285879 0.0179540105 -0.1425716430 2907 1311867815.6201279163 0.2671480179 0.2317639039 0.3266084492 0.0042021322 0.1411290000 985433529 0 402718720 -0.1858395636 0.0184667651 -0.1418333352 2908 1311867815.6522359848 0.2658650279 0.2317756305 0.3266084492 0.0042016975 0.1530810000 985436489 0 402718720 -0.1842167228 0.0191074032 -0.1416324973 2909 1311867815.6869289875 0.2664866745 0.2317875628 0.3266084492 0.0042027297 0.1407280000 985439449 0 402718720 -0.1844134331 0.0189112220 -0.1411416829 2910 1311867815.7186810970 0.2665890455 0.2317995221 0.3266084492 0.0042053802 0.1414640000 985442409 0 402718720 -0.1845858693 0.0197750069 -0.1409265548 2911 1311867815.7527859211 0.2672473192 0.2318116993 0.3266084492 0.0042191560 0.1419080000 985445313 0 402718720 -0.1845259666 0.0197325591 -0.1406886727 2912 1311867815.7881309986 0.2676402628 0.2318240030 0.3266084492 0.0042185415 0.1411750000 985448329 0 402718720 -0.1846114546 0.0197235011 -0.1405972689 2913 1311867815.8185119629 0.2661773562 0.2318357962 0.3266084492 0.0042377786 0.1544650000 985451121 0 402718720 -0.1830723137 0.0202439036 -0.1405007690 2914 1311867815.8516321182 0.2671776414 0.2318479245 0.3266084492 0.0042377147 0.1677510000 985454081 0 402718720 -0.1836763173 0.0200590696 -0.1399919838 2915 1311867815.8881559372 0.2675597668 0.2318601755 0.3266084492 0.0042372186 0.1415600000 985457153 0 402718720 -0.1837223470 0.0206634775 -0.1396528929 2916 1311867815.9183700085 0.2670793831 0.2318722534 0.3266084492 0.0042371231 0.1420190000 985459945 0 402718720 -0.1831590086 0.0218684953 -0.1392563134 2917 1311867815.9544029236 0.2681999207 0.2318847072 0.3266084492 0.0042367359 0.1421900000 985462961 0 402718720 -0.1837443113 0.0219381899 -0.1388012022 2918 1311867815.9880459309 0.2673313320 0.2318968548 0.3266084492 0.0042410316 0.1565790000 985465921 0 402718720 -0.1826201528 0.0224793740 -0.1387062371 2919 1311867816.0232369900 0.2669614255 0.2319088673 0.3266084492 0.0042446776 0.1426170000 985468937 0 402718720 -0.1815858930 0.0232562516 -0.1386069655 2920 1311867816.0513160229 0.2676387429 0.2319211036 0.3266084492 0.0042441819 0.1423950000 985471673 0 402718720 -0.1816168725 0.0236297548 -0.1381516457 2921 1311867816.0872139931 0.2675572038 0.2319333035 0.3266084492 0.0042438459 0.1426180000 985474745 0 402718720 -0.1808970869 0.0241492614 -0.1378805637 2922 1311867816.1192660332 0.2678171694 0.2319455841 0.3266084492 0.0042432085 0.1424400000 985477593 0 402718720 -0.1802736521 0.0243378878 -0.1376478523 2923 1311867816.1530499458 0.2674020529 0.2319577143 0.3266084492 0.0042427675 0.1551680000 985480441 0 402718720 -0.1792208999 0.0250676498 -0.1374762952 2924 1311867816.1877670288 0.2673655748 0.2319698237 0.3266084492 0.0042427923 0.1429070000 985483457 0 402718720 -0.1786038876 0.0254236348 -0.1371112913 2925 1311867816.2185130119 0.2678234279 0.2319820813 0.3266084492 0.0042425684 0.1433260000 985486361 0 402718720 -0.1786333025 0.0259302352 -0.1369787306 2926 1311867816.2509930134 0.2677009404 0.2319942887 0.3266084492 0.0042454238 0.1429720000 985489209 0 402718720 -0.1782574356 0.0265650656 -0.1367785782 2927 1311867816.2875878811 0.2670415342 0.2320062625 0.3266084492 0.0042453892 0.1426450000 985492225 0 402718720 -0.1771669090 0.0268814806 -0.1366764158 2928 1311867816.3221759796 0.2666358650 0.2320180895 0.3266084492 0.0042449623 0.1532670000 985495241 0 402718720 -0.1764540821 0.0271695387 -0.1367469132 2929 1311867816.3515660763 0.2658964694 0.2320296561 0.3266084492 0.0042448569 0.1430070000 985498033 0 402718720 -0.1752932221 0.0272900071 -0.1369846612 2930 1311867816.3902490139 0.2660555243 0.2320412690 0.3266084492 0.0042442019 0.1426310000 985501105 0 402718720 -0.1752552092 0.0273226649 -0.1374653429 2931 1311867816.4188189507 0.2665394545 0.2320530391 0.3266084492 0.0042434966 0.1526540000 985503953 0 402718720 -0.1758094430 0.0273417979 -0.1377564669 2932 1311867816.4527490139 0.2661893666 0.2320646818 0.3266084492 0.0042430392 0.1544820000 985506913 0 402718720 -0.1754324287 0.0272245388 -0.1382786185 2933 1311867816.4875969887 0.2676698864 0.2320768213 0.3266084492 0.0042449649 0.1533190000 985509873 0 402718720 -0.1772061288 0.0272516012 -0.1385826468 2934 1311867816.5199189186 0.2680782974 0.2320890918 0.3266084492 0.0042451579 0.1552400000 985512721 0 402718720 -0.1777372062 0.0268492550 -0.1390933394 2935 1311867816.5529119968 0.2672872543 0.2321010843 0.3266084492 0.0042466763 0.1429340000 985515737 0 402718720 -0.1772200614 0.0265233144 -0.1392388344 2936 1311867816.5888628960 0.2673364878 0.2321130855 0.3266084492 0.0042460819 0.1434770000 985518753 0 402718720 -0.1774544716 0.0262856428 -0.1394897550 2937 1311867816.6194050312 0.2680701613 0.2321253283 0.3266084492 0.0042454946 0.1429840000 985521601 0 402718720 -0.1786297113 0.0257069822 -0.1394987404 2938 1311867816.6509261131 0.2678108215 0.2321374744 0.3266084492 0.0042449229 0.1519960000 985524449 0 402718720 -0.1789015830 0.0253762342 -0.1397850215 2939 1311867816.6893680096 0.2687253654 0.2321499235 0.3266084492 0.0042446025 0.1433350000 985527577 0 402718720 -0.1806555986 0.0248055737 -0.1398989111 2940 1311867816.7204029560 0.2690538764 0.2321624759 0.3266084492 0.0042452901 0.1436180000 985530369 0 402718720 -0.1818669736 0.0240035169 -0.1402504146 2941 1311867816.7523219585 0.2684059441 0.2321747994 0.3266084492 0.0042446868 0.1439130000 985533273 0 402718720 -0.1819913983 0.0230475049 -0.1404960603 2942 1311867816.7867000103 0.2685824633 0.2321871746 0.3266084492 0.0042444466 0.1448700000 985536233 0 402718720 -0.1826566607 0.0224512406 -0.1409118921 2943 1311867816.8192241192 0.2679412067 0.2321993234 0.3266084492 0.0042440144 0.1656630000 985539137 0 402718720 -0.1826459914 0.0217457321 -0.1410517991 2944 1311867816.8584229946 0.2676145434 0.2322113530 0.3266084492 0.0042438234 0.1445030000 985542265 0 402718720 -0.1830481291 0.0210657176 -0.1415881515 2945 1311867816.8891038895 0.2677567303 0.2322234228 0.3266084492 0.0042432354 0.1452810000 985545057 0 402718720 -0.1834415942 0.0203536246 -0.1419198215 2946 1311867816.9194529057 0.2673552036 0.2322353480 0.3266084492 0.0042508244 0.1449200000 985547961 0 402718720 -0.1829035729 0.0193756819 -0.1423883438 2947 1311867816.9566609859 0.2683578134 0.2322476054 0.3266084492 0.0042525193 0.1460020000 985550865 0 402718720 -0.1844974905 0.0180222783 -0.1426018029 2948 1311867816.9880828857 0.2673951387 0.2322595279 0.3266084492 0.0042699950 0.1796620000 985553769 0 402718720 -0.1843032688 0.0172706358 -0.1431398392 2949 1311867817.0196158886 0.2682694197 0.2322717388 0.3266084492 0.0042697788 0.1472250000 985556673 0 402718720 -0.1853669286 0.0164483618 -0.1432622373 2950 1311867817.0547220707 0.2689250708 0.2322841636 0.3266084492 0.0042700117 0.1466950000 985559633 0 402718720 -0.1867740899 0.0162768662 -0.1434127092 2951 1311867817.0868639946 0.2676411569 0.2322961450 0.3266084492 0.0042698556 0.1470070000 985562537 0 402718720 -0.1855200231 0.0155989593 -0.1439699680 2952 1311867817.1189420223 0.2686459720 0.2323084586 0.3266084492 0.0042697124 0.1476620000 985565497 0 402718720 -0.1867984235 0.0148891369 -0.1441669017 2953 1311867817.1549699306 0.2697375119 0.2323211335 0.3266084492 0.0042692218 0.1567020000 985568513 0 402718720 -0.1885166019 0.0144921830 -0.1441104859 2954 1311867817.1863970757 0.2687045932 0.2323334502 0.3266084492 0.0042701965 0.1480450000 985571361 0 402718720 -0.1876143366 0.0142793842 -0.1444538087 2955 1311867817.2202200890 0.2689273357 0.2323458339 0.3266084492 0.0042700206 0.1483760000 985574321 0 402718720 -0.1877991110 0.0133524798 -0.1445816904 2956 1311867817.2567460537 0.2694429159 0.2323583837 0.3266084492 0.0042706294 0.1500080000 985577337 0 402718720 -0.1885423064 0.0127981445 -0.1446164846 2957 1311867817.2865970135 0.2677752972 0.2323703610 0.3266084492 0.0042708769 0.1485050000 985580185 0 402718720 -0.1870869100 0.0119156446 -0.1452979445 2958 1311867817.3192870617 0.2672524452 0.2323821535 0.3266084492 0.0042706765 0.1607010000 985583145 0 402718720 -0.1869587004 0.0110694487 -0.1458448172 2959 1311867817.3578689098 0.2687219679 0.2323944346 0.3266084492 0.0042719636 0.1493080000 985586217 0 402718720 -0.1891460270 0.0102442596 -0.1455512345 2960 1311867817.3868360519 0.2692230344 0.2324068767 0.3266084492 0.0042725778 0.1609390000 985589009 0 402718720 -0.1898623556 0.0088673076 -0.1457865983 2961 1311867817.4206850529 0.2675414383 0.2324187424 0.3266084492 0.0042720966 0.1495180000 985591969 0 402718720 -0.1885128915 0.0079066968 -0.1462853402 2962 1311867817.4551830292 0.2671745420 0.2324304763 0.3266084492 0.0042718832 0.1489800000 985594929 0 402718720 -0.1883310378 0.0059481338 -0.1464330256 2963 1311867817.4888920784 0.2668951750 0.2324421080 0.3266084492 0.0042718999 0.1582230000 985597945 0 402718720 -0.1883090734 0.0046089999 -0.1468015909 2964 1311867817.5194959641 0.2661606073 0.2324534840 0.3266084492 0.0042722933 0.1508550000 985600737 0 402718720 -0.1880082786 0.0040294928 -0.1471906602 2965 1311867817.5576219559 0.2683222890 0.2324655814 0.3266084492 0.0042721305 0.1504650000 985603865 0 402718720 -0.1906975955 0.0022708306 -0.1472064555 2966 1311867817.5864789486 0.2677319944 0.2324774717 0.3266084492 0.0042718083 0.1510490000 985606657 0 402718720 -0.1904327869 0.0008138248 -0.1473639905 2967 1311867817.6205849648 0.2685920596 0.2324896438 0.3266084492 0.0042711322 0.1518950000 985609617 0 402718720 -0.1919926554 -0.0000864824 -0.1473401040 2968 1311867817.6566040516 0.2654106021 0.2325007357 0.3266084492 0.0042708894 0.1613200000 985612633 0 402718720 -0.1894583851 -0.0009080465 -0.1476406753 2969 1311867817.6880049706 0.2654977441 0.2325118496 0.3266084492 0.0042709885 0.1529470000 985615537 0 402718720 -0.1900209635 -0.0022879201 -0.1478298306 2970 1311867817.7194509506 0.2657891810 0.2325230541 0.3266084492 0.0042705811 0.1531440000 985618497 0 402718720 -0.1906085014 -0.0035665485 -0.1479619741 2971 1311867817.7552740574 0.2645118237 0.2325338211 0.3266084492 0.0042709961 0.1531480000 985621401 0 402718720 -0.1897712946 -0.0043427185 -0.1483087838 2972 1311867817.7872710228 0.2640772760 0.2325444346 0.3266084492 0.0042719335 0.1668980000 985624361 0 402718720 -0.1895403117 -0.0053671207 -0.1482385099 2973 1311867817.8201289177 0.2625666857 0.2325545329 0.3266084492 0.0042739430 0.1695940000 985627321 0 402718720 -0.1884013265 -0.0061482149 -0.1484712362 2974 1311867817.8596370220 0.2646932602 0.2325653395 0.3266084492 0.0042763722 0.1563310000 985630449 0 402718720 -0.1908436269 -0.0080065839 -0.1478772163 2975 1311867817.8866479397 0.2654534578 0.2325763943 0.3266084492 0.0042766960 0.1569540000 985633185 0 402718720 -0.1915853769 -0.0091954311 -0.1472959369 2976 1311867817.9203889370 0.2653247118 0.2325873984 0.3266084492 0.0042769904 0.1573180000 985636145 0 402718720 -0.1917518675 -0.0100754686 -0.1471362114 2977 1311867817.9569509029 0.2637161016 0.2325978548 0.3266084492 0.0042769423 0.1583400000 985639161 0 402718720 -0.1905155778 -0.0104786512 -0.1472525001 2978 1311867817.9865961075 0.2638122737 0.2326083365 0.3266084492 0.0042774874 0.1683990000 985642009 0 402718720 -0.1904946417 -0.0120713916 -0.1473298073 2979 1311867818.0255188942 0.2639842629 0.2326188689 0.3266084492 0.0042778162 0.1592380000 985645081 0 402718720 -0.1908079237 -0.0127825905 -0.1473150998 2980 1311867818.0579230785 0.2642304599 0.2326294768 0.3266084492 0.0042782753 0.1717550000 985648041 0 402718720 -0.1908065975 -0.0137207368 -0.1473519355 2981 1311867818.0892961025 0.2630194724 0.2326396714 0.3266084492 0.0042782807 0.1789570000 985650833 0 402718720 -0.1896279752 -0.0145443063 -0.1479224414 2982 1311867818.1228859425 0.2629239559 0.2326498271 0.3266084492 0.0042818413 0.1604920000 985653849 0 402718720 -0.1899830699 -0.0149850799 -0.1479543298 2983 1311867818.1594460011 0.2651502192 0.2326607223 0.3266084492 0.0042831280 0.1756210000 985656809 0 402718720 -0.1919628531 -0.0165866967 -0.1479972601 2984 1311867818.1912620068 0.2617611289 0.2326704744 0.3266084492 0.0042954083 0.1597980000 985659769 0 402718720 -0.1883991808 -0.0169533975 -0.1487573981 2985 1311867818.2233390808 0.2626208365 0.2326805080 0.3266084492 0.0043000502 0.1618850000 985662729 0 402718720 -0.1899273694 -0.0166729260 -0.1488361508 2986 1311867818.2556240559 0.2602698803 0.2326897476 0.3266084492 0.0043018005 0.1622280000 985665577 0 402718720 -0.1873246133 -0.0174219571 -0.1493598968 2987 1311867818.2891340256 0.2579659820 0.2326982097 0.3266084492 0.0043025055 0.1608140000 985668537 0 402718720 -0.1849672496 -0.0180450566 -0.1498928517 2988 1311867818.3256890774 0.2594809234 0.2327071731 0.3266084492 0.0043019271 0.1747250000 985671553 0 402718720 -0.1866971999 -0.0184606221 -0.1500225216 2989 1311867818.3582971096 0.2592015266 0.2327160371 0.3266084492 0.0043014196 0.1619660000 985674513 0 402718720 -0.1863424033 -0.0195879918 -0.1503531337 2990 1311867818.3892099857 0.2585740089 0.2327246852 0.3266084492 0.0043014716 0.1623040000 985677417 0 402718720 -0.1854067147 -0.0205125324 -0.1508096457 2991 1311867818.4233601093 0.2593241036 0.2327335784 0.3266084492 0.0043019205 0.1624830000 985680377 0 402718720 -0.1864304990 -0.0212898292 -0.1509493738 2992 1311867818.4555370808 0.2583099306 0.2327421266 0.3266084492 0.0043016403 0.1635740000 985683225 0 402718720 -0.1858620048 -0.0212918650 -0.1514046490 2993 1311867818.4896349907 0.2583848536 0.2327506942 0.3266084492 0.0043017680 0.1783800000 985686241 0 402718720 -0.1863028854 -0.0220778566 -0.1517407745 2994 1311867818.5246019363 0.2592900991 0.2327595584 0.3266084492 0.0043028311 0.1649310000 985689201 0 402718720 -0.1877760291 -0.0224091895 -0.1513581723 2995 1311867818.5566370487 0.2592727840 0.2327684109 0.3266084492 0.0043031711 0.1648670000 985692105 0 402718720 -0.1885568202 -0.0227126423 -0.1515073329 2996 1311867818.5892300606 0.2583281696 0.2327769422 0.3266084492 0.0043068592 0.1641710000 985695009 0 402718720 -0.1880936027 -0.0238172039 -0.1521137655 2997 1311867818.6233239174 0.2574741542 0.2327851828 0.3266084492 0.0043068752 0.1758290000 985697969 0 402718720 -0.1882892251 -0.0237373337 -0.1520000696 2998 1311867818.6555750370 0.2587804198 0.2327938537 0.3266084492 0.0043076392 0.1775430000 985700817 0 402718720 -0.1909292638 -0.0242655072 -0.1517192274 2999 1311867818.6877410412 0.2580104768 0.2328022620 0.3266084492 0.0043080123 0.1660320000 985703777 0 402718720 -0.1905828118 -0.0255612172 -0.1519302875 3000 1311867818.7238090038 0.2585651577 0.2328108497 0.3266084492 0.0043074019 0.1660510000 985706737 0 402718720 -0.1923738122 -0.0254954491 -0.1518295705 3001 1311867818.7561779022 0.2582512796 0.2328193270 0.3266084492 0.0043070085 0.1666790000 985709697 0 402718720 -0.1925374717 -0.0256997552 -0.1520320177 3002 1311867818.7870090008 0.2585934103 0.2328279126 0.3266084492 0.0043074229 0.1678240000 985712545 0 402718720 -0.1935850978 -0.0263557266 -0.1519257426 3003 1311867818.8250839710 0.2578154504 0.2328362335 0.3266084492 0.0043084022 0.1674280000 985715561 0 402718720 -0.1936668903 -0.0263486020 -0.1518034041 3004 1311867818.8546340466 0.2621611953 0.2328459954 0.3266084492 0.0043102862 0.1789030000 985718409 0 402718720 -0.2003191710 -0.0240727421 -0.1512267441 3005 1311867818.8872439861 0.2590388358 0.2328547119 0.3266084492 0.0043242049 0.1702920000 985721425 0 402718720 -0.1975588650 -0.0255509373 -0.1512692124 3006 1311867818.9249579906 0.2584262490 0.2328632187 0.3266084492 0.0043249259 0.1693270000 985724497 0 402718720 -0.1980256289 -0.0261618961 -0.1514667571 3007 1311867818.9544699192 0.2541521192 0.2328702985 0.3266084492 0.0043313513 0.1825780000 985727289 0 402718720 -0.1944779903 -0.0258085597 -0.1519085467 3008 1311867818.9864790440 0.2508536279 0.2328762770 0.3266084492 0.0043339925 0.1837870000 985730193 0 402718720 -0.1917654872 -0.0264034849 -0.1518016458 3009 1311867819.0252439976 0.2511002123 0.2328823334 0.3266084492 0.0043354192 0.1839650000 985733321 0 402718720 -0.1926221997 -0.0278315786 -0.1519136876 3010 1311867819.0550930500 0.2408201098 0.2328849706 0.3266084492 0.0043712254 0.1736480000 985736169 0 402718720 -0.1825491488 -0.0290384404 -0.1531947553 3011 1311867819.0875039101 0.2211100012 0.2328810599 0.3266084492 0.0043963687 0.1771410000 985739073 0 402718720 -0.1626276970 -0.0276749916 -0.1563020945 3012 1311867819.1251850128 0.2395669669 0.2328832797 0.3266084492 0.0044525050 0.1833380000 985742089 0 402718720 -0.1831283718 -0.0299938042 -0.1533481330 3013 1311867819.1578950882 0.2264050692 0.2328811296 0.3266084492 0.0044685906 0.2026000000 985745049 0 402718720 -0.1703327298 -0.0302289221 -0.1552312374 3014 1311867819.1891999245 0.2243201733 0.2328782892 0.3266084492 0.0044713675 0.1715530000 985747953 0 402718720 -0.1683166921 -0.0315245874 -0.1555783153 3015 1311867819.2251279354 0.2249655873 0.2328756648 0.3266084492 0.0044719834 0.1716840000 985750913 0 402718720 -0.1696069539 -0.0329302400 -0.1548644900 3016 1311867819.2586779594 0.2192569524 0.2328711493 0.3266084492 0.0044760276 0.1739150000 985753873 0 402718720 -0.1636641771 -0.0338536426 -0.1559315324 3017 1311867819.2937591076 0.2214191407 0.2328673534 0.3266084492 0.0044753352 0.1830070000 985756833 0 402718720 -0.1663877815 -0.0352222025 -0.1562655419 3018 1311867819.3250200748 0.2239900380 0.2328644120 0.3266084492 0.0044746629 0.1799130000 985759737 0 402718720 -0.1689568609 -0.0370068960 -0.1555940807 3019 1311867819.3568780422 0.2269057631 0.2328624383 0.3266084492 0.0044747303 0.1709130000 985762641 0 402718720 -0.1720999628 -0.0376593359 -0.1551582962 3020 1311867819.3930859566 0.2228009552 0.2328591067 0.3266084492 0.0044817325 0.1737060000 985765657 0 402718720 -0.1684363186 -0.0372086689 -0.1550092548 3021 1311867819.4237139225 0.2320543230 0.2328588403 0.3266084492 0.0044847656 0.1816720000 985768561 0 402718720 -0.1788419485 -0.0376349613 -0.1542891562 3022 1311867819.4571580887 0.2277734429 0.2328571575 0.3266084492 0.0044855316 0.1741810000 985771465 0 402718720 -0.1744952649 -0.0380847119 -0.1542174220 3023 1311867819.4921460152 0.2255462408 0.2328547390 0.3266084492 0.0044857326 0.1868230000 985774425 0 402718720 -0.1714521796 -0.0396176465 -0.1543394923 3024 1311867819.5226500034 0.2264215946 0.2328526117 0.3266084492 0.0044854952 0.1714630000 985777329 0 402718720 -0.1723589301 -0.0402318873 -0.1543130726 3025 1311867819.5550689697 0.2281534076 0.2328510582 0.3266084492 0.0044850640 0.1723190000 985780177 0 402718720 -0.1741095781 -0.0413924865 -0.1541908681 3026 1311867819.5923891068 0.2211591601 0.2328471944 0.3266084492 0.0044883613 0.1761000000 985783305 0 402718720 -0.1672308445 -0.0402616262 -0.1552031338 3027 1311867819.6253750324 0.2222649306 0.2328436984 0.3266084492 0.0044888367 0.1731010000 985786209 0 402718720 -0.1682827175 -0.0410815179 -0.1549944431 3028 1311867819.6557610035 0.2247790694 0.2328410351 0.3266084492 0.0044881182 0.1840170000 985789057 0 402718720 -0.1708053797 -0.0419554822 -0.1547249556 3029 1311867819.6919729710 0.2254240662 0.2328385864 0.3266084492 0.0044879568 0.1732160000 985792073 0 402718720 -0.1714957505 -0.0430151485 -0.1546454877 3030 1311867819.7227339745 0.2262037396 0.2328363967 0.3266084492 0.0044875674 0.1734550000 985794977 0 402718720 -0.1720993519 -0.0437708460 -0.1542253345 3031 1311867819.7567169666 0.2279145420 0.2328347729 0.3266084492 0.0044884084 0.1747520000 985797937 0 402718720 -0.1740390658 -0.0438617580 -0.1535713971 3032 1311867819.7913908958 0.2311204523 0.2328342075 0.3266084492 0.0044884767 0.1739330000 985800897 0 402718720 -0.1771066785 -0.0453079604 -0.1529702842 3033 1311867819.8285260201 0.2281486243 0.2328326626 0.3266084492 0.0044879894 0.1901110000 985803913 0 402718720 -0.1745224744 -0.0444877855 -0.1530836672 3034 1311867819.8552229404 0.2310318649 0.2328320691 0.3266084492 0.0044917614 0.1748360000 985806649 0 402718720 -0.1776125282 -0.0449987650 -0.1527675390 3035 1311867819.8941109180 0.2339055985 0.2328324228 0.3266084492 0.0044921046 0.1888190000 985809833 0 402718720 -0.1813969165 -0.0436452478 -0.1520144939 3036 1311867819.9237871170 0.2280938774 0.2328308620 0.3266084492 0.0044943732 0.1781170000 985812625 0 402718720 -0.1743009537 -0.0456321239 -0.1522689164 3037 1311867819.9576539993 0.2291641533 0.2328296547 0.3266084492 0.0044940588 0.1880320000 985815585 0 402718720 -0.1753301471 -0.0462894589 -0.1524193883 3038 1311867819.9939079285 0.2293723375 0.2328285166 0.3266084492 0.0044933989 0.1863080000 985818657 0 402718720 -0.1751579493 -0.0471887924 -0.1523465663 3039 1311867820.0229809284 0.2304528505 0.2328277349 0.3266084492 0.0044931653 0.1952810000 985821449 0 402718720 -0.1758565158 -0.0483313538 -0.1521083117 3040 1311867820.0577530861 0.2365029156 0.2328289438 0.3266084492 0.0044983728 0.1871860000 985824409 0 402718720 -0.1832432896 -0.0459320769 -0.1508314908 3041 1311867820.0944790840 0.2279492766 0.2328273392 0.3266084492 0.0045029381 0.1799900000 985827425 0 402718720 -0.1741136461 -0.0453894511 -0.1513032615 3042 1311867820.1251690388 0.2297718078 0.2328263348 0.3266084492 0.0045030889 0.1769420000 985830273 0 402718720 -0.1750846505 -0.0478675514 -0.1511270106 3043 1311867820.1551020145 0.2348261774 0.2328269920 0.3266084492 0.0045055581 0.2014220000 985833177 0 402718720 -0.1809183508 -0.0472153053 -0.1502661258 3044 1311867820.1938860416 0.2287331969 0.2328256471 0.3266084492 0.0045064061 0.1800960000 985836249 0 402718720 -0.1747079045 -0.0462900810 -0.1503071040 3045 1311867820.2262499332 0.2324159294 0.2328255125 0.3266084492 0.0045075875 0.2011390000 985839153 0 402718720 -0.1782819480 -0.0472458266 -0.1497938335 3046 1311867820.2557370663 0.2308849543 0.2328248755 0.3266084492 0.0045071154 0.1812300000 985841945 0 402718720 -0.1761241555 -0.0486817807 -0.1493814439 3047 1311867820.2941820621 0.2367516458 0.2328261642 0.3266084492 0.0045085792 0.1894350000 985845129 0 402718720 -0.1829055697 -0.0480984300 -0.1489534676 3048 1311867820.3227488995 0.2286947072 0.2328248087 0.3266084492 0.0045126243 0.1909020000 985847921 0 402718720 -0.1738763154 -0.0489817150 -0.1492651701 3049 1311867820.3565030098 0.2295794189 0.2328237443 0.3266084492 0.0045119575 0.1909730000 985850825 0 402718720 -0.1743745804 -0.0503883399 -0.1490615457 3050 1311867820.3936169147 0.2291180044 0.2328225293 0.3266084492 0.0045112998 0.1807750000 985853897 0 402718720 -0.1737296432 -0.0512939282 -0.1490975916 3051 1311867820.4230690002 0.2302259654 0.2328216783 0.3266084492 0.0045107155 0.1789980000 985856689 0 402718720 -0.1746730506 -0.0523258224 -0.1487814784 3052 1311867820.4605870247 0.2272688299 0.2328198588 0.3266084492 0.0045102084 0.1813870000 985859705 0 402718720 -0.1722707599 -0.0514016636 -0.1483432502 3053 1311867820.4940779209 0.2275464833 0.2328181316 0.3266084492 0.0045096439 0.1933470000 985862665 0 402718720 -0.1723768115 -0.0524738654 -0.1483237743 3054 1311867820.5266289711 0.2279712260 0.2328165445 0.3266084492 0.0045090137 0.1789430000 985865625 0 402718720 -0.1727156341 -0.0536665730 -0.1479247063 3055 1311867820.5596110821 0.2305888087 0.2328158153 0.3266084492 0.0045083489 0.1791790000 985868529 0 402718720 -0.1755672693 -0.0540918335 -0.1471907496 3056 1311867820.5906820297 0.2318921536 0.2328155130 0.3266084492 0.0045078514 0.1897870000 985871377 0 402718720 -0.1772394776 -0.0543772578 -0.1468583792 3057 1311867820.6261150837 0.2325988114 0.2328154422 0.3266084492 0.0045079842 0.1906030000 985874393 0 402718720 -0.1789107919 -0.0546268038 -0.1465190500 3058 1311867820.6602840424 0.2321509123 0.2328152249 0.3266084492 0.0045073109 0.1796300000 985877297 0 402718720 -0.1785597205 -0.0554526560 -0.1461186409 3059 1311867820.6933140755 0.2333325446 0.2328153940 0.3266084492 0.0045068341 0.1795580000 985880313 0 402718720 -0.1800984442 -0.0559523590 -0.1457118392 3060 1311867820.7232019901 0.2385933846 0.2328172822 0.3266084492 0.0045083779 0.2007260000 985883161 0 402718720 -0.1870106310 -0.0538841374 -0.1448949128 3061 1311867820.7605569363 0.2354774475 0.2328181512 0.3266084492 0.0045089864 0.1813960000 985886177 0 402718720 -0.1838875562 -0.0545877032 -0.1447834522 3062 1311867820.7916440964 0.2363610566 0.2328193083 0.3266084492 0.0045084032 0.1785520000 985889025 0 402718720 -0.1849854887 -0.0553650893 -0.1447106451 3063 1311867820.8228490353 0.2376211137 0.2328208760 0.3266084492 0.0045079029 0.1792940000 985891985 0 402718720 -0.1862045825 -0.0567765310 -0.1443690956 3064 1311867820.8588171005 0.2366739959 0.2328221335 0.3266084492 0.0045079323 0.1787580000 985895001 0 402718720 -0.1855168194 -0.0575086549 -0.1442282051 3065 1311867820.8911399841 0.2365030795 0.2328233345 0.3266084492 0.0045076972 0.1786010000 985897849 0 402718720 -0.1858194321 -0.0576024875 -0.1440583467 3066 1311867820.9231750965 0.2350652516 0.2328240657 0.3266084492 0.0045074842 0.2037490000 985900753 0 402718720 -0.1846336275 -0.0576875731 -0.1437506676 3067 1311867820.9593999386 0.2354556024 0.2328249237 0.3266084492 0.0045069410 0.1888060000 985903825 0 402718720 -0.1852291822 -0.0588780455 -0.1437516958 3068 1311867820.9930229187 0.2360005528 0.2328259588 0.3266084492 0.0045063531 0.1914550000 985906785 0 402718720 -0.1860747933 -0.0590574071 -0.1434467435 3069 1311867821.0258319378 0.2366633713 0.2328272092 0.3266084492 0.0045076482 0.1911180000 985909577 0 402718720 -0.1871173829 -0.0588019453 -0.1428605914 3070 1311867821.0608170033 0.2368078977 0.2328285058 0.3266084492 0.0045075356 0.1786060000 985912593 0 402718720 -0.1875680238 -0.0593744591 -0.1427620351 3071 1311867821.0909409523 0.2378359437 0.2328301364 0.3266084492 0.0045073540 0.1795070000 985915441 0 402718720 -0.1892471910 -0.0590168238 -0.1423247010 3072 1311867821.1260650158 0.2373200357 0.2328315979 0.3266084492 0.0045077818 0.1793770000 985918401 0 402718720 -0.1893375814 -0.0584465712 -0.1417608559 3073 1311867821.1620008945 0.2360980660 0.2328326609 0.3266084492 0.0045091508 0.1801720000 985921361 0 402718720 -0.1884532124 -0.0590870418 -0.1418728679 3074 1311867821.1925799847 0.2369758785 0.2328340087 0.3266084492 0.0045088820 0.1787520000 985924265 0 402718720 -0.1896772832 -0.0597809032 -0.1414310783 3075 1311867821.2257659435 0.2377221584 0.2328355984 0.3266084492 0.0045081811 0.1796060000 985927169 0 402718720 -0.1911450922 -0.0598575696 -0.1410321891 3076 1311867821.2620539665 0.2391281128 0.2328376440 0.3266084492 0.0045078366 0.1789260000 985930185 0 402718720 -0.1930671781 -0.0604385585 -0.1405225843 3077 1311867821.2933909893 0.2390594184 0.2328396661 0.3266084492 0.0045072365 0.1781000000 985933089 0 402718720 -0.1931572258 -0.0613457076 -0.1401208192 3078 1311867821.3235690594 0.2392690778 0.2328417549 0.3266084492 0.0045069354 0.2067850000 985935993 0 402718720 -0.1937863082 -0.0615222715 -0.1394176483 3079 1311867821.3590209484 0.2406308055 0.2328442846 0.3266084492 0.0045067889 0.1789800000 985939009 0 402718720 -0.1954555660 -0.0628450513 -0.1391432881 3080 1311867821.3907248974 0.2407203615 0.2328468418 0.3266084492 0.0045064179 0.1785510000 985941801 0 402718720 -0.1954647005 -0.0643253848 -0.1390388757 3081 1311867821.4246149063 0.2401612699 0.2328492158 0.3266084492 0.0045061253 0.1901490000 985944761 0 402718720 -0.1954430491 -0.0643311664 -0.1388540566 3082 1311867821.4626159668 0.2394776940 0.2328513666 0.3266084492 0.0045055795 0.1775860000 985947889 0 402718720 -0.1951558888 -0.0647500083 -0.1387888789 3083 1311867821.4939169884 0.2399107367 0.2328536563 0.3266084492 0.0045049639 0.1914910000 985950737 0 402718720 -0.1957770288 -0.0656480342 -0.1389272511 3084 1311867821.5273780823 0.2394595593 0.2328557983 0.3266084492 0.0045048606 0.1763700000 985953697 0 402718720 -0.1959628910 -0.0654496104 -0.1384062618 3085 1311867821.5590820312 0.2398449332 0.2328580638 0.3266084492 0.0045042130 0.1760370000 985956601 0 402718720 -0.1971527636 -0.0654442608 -0.1383705735 3086 1311867821.5928409100 0.2403773516 0.2328605004 0.3266084492 0.0045040753 0.1758990000 985959449 0 402718720 -0.1980832517 -0.0663530901 -0.1379306465 3087 1311867821.6260631084 0.2396037281 0.2328626848 0.3266084492 0.0045034730 0.1752200000 985962353 0 402718720 -0.1980357319 -0.0660711527 -0.1375537217 3088 1311867821.6634659767 0.2407022417 0.2328652235 0.3266084492 0.0045029093 0.1876350000 985965593 0 402718720 -0.1998372078 -0.0662770420 -0.1369523108 3089 1311867821.6953229904 0.2409522682 0.2328678415 0.3266084492 0.0045026906 0.1751590000 985968441 0 402718720 -0.2005697638 -0.0671497732 -0.1364683956 3090 1311867821.7313649654 0.2401632518 0.2328702025 0.3266084492 0.0045025964 0.1739380000 985971457 0 402718720 -0.2005088627 -0.0675792396 -0.1362025887 3091 1311867821.7634460926 0.2407460213 0.2328727505 0.3266084492 0.0045020113 0.1859920000 985974417 0 402718720 -0.2019805014 -0.0672240555 -0.1354495138 3092 1311867821.7956120968 0.2400594205 0.2328750748 0.3266084492 0.0045019545 0.1742210000 985977209 0 402718720 -0.2018679082 -0.0681557059 -0.1355382204 3093 1311867821.8313920498 0.2402929664 0.2328774731 0.3266084492 0.0045014161 0.1856070000 985980225 0 402718720 -0.2026692927 -0.0690714642 -0.1352156401 3094 1311867821.8633379936 0.2414046228 0.2328802291 0.3266084492 0.0045021798 0.1868940000 985983073 0 402718720 -0.2039518803 -0.0687527657 -0.1348717511 3095 1311867821.8956110477 0.2417105734 0.2328830822 0.3266084492 0.0045018990 0.1746240000 985986033 0 402718720 -0.2045991570 -0.0697247535 -0.1349374503 3096 1311867821.9314410686 0.2415564805 0.2328858837 0.3266084492 0.0045014713 0.1734400000 985989049 0 402718720 -0.2046703100 -0.0711360201 -0.1349268854 3097 1311867821.9633870125 0.2424188405 0.2328889618 0.3266084492 0.0045008024 0.1730140000 985992009 0 402718720 -0.2060476542 -0.0715452433 -0.1350735724 3098 1311867821.9954171181 0.2417597920 0.2328918252 0.3266084492 0.0045007171 0.1875720000 985994913 0 402718720 -0.2057138383 -0.0725059435 -0.1352070123 3099 1311867822.0314009190 0.2420002818 0.2328947644 0.3266084492 0.0045005354 0.1718020000 985997873 0 402718720 -0.2063605338 -0.0739360377 -0.1350560337 3100 1311867822.0633769035 0.2423408478 0.2328978115 0.3266084492 0.0045002631 0.1707560000 986000833 0 402718720 -0.2071611285 -0.0742300749 -0.1348422766 3101 1311867822.0962209702 0.2438542396 0.2329013447 0.3266084492 0.0044996830 0.1694370000 986003681 0 402718720 -0.2090878040 -0.0746232644 -0.1344398260 3102 1311867822.1315379143 0.2437328100 0.2329048365 0.3266084492 0.0045000965 0.1693030000 986006697 0 402718720 -0.2093121260 -0.0746052787 -0.1344026178 3103 1311867822.1634409428 0.2438308299 0.2329083576 0.3266084492 0.0044995159 0.1823550000 986009657 0 402718720 -0.2097485065 -0.0741748959 -0.1337683499 3104 1311867822.1960899830 0.2432650328 0.2329116941 0.3266084492 0.0044998028 0.1713610000 986012505 0 402718720 -0.2097005248 -0.0737392306 -0.1335048229 3105 1311867822.2317450047 0.2439741939 0.2329152569 0.3266084492 0.0044991764 0.1709890000 986015521 0 402718720 -0.2103876919 -0.0751082897 -0.1332914084 3106 1311867822.2634150982 0.2437308431 0.2329187391 0.3266084492 0.0045015875 0.1704870000 986018481 0 402718720 -0.2092783153 -0.0759560689 -0.1331765205 3107 1311867822.2954349518 0.2431304604 0.2329220258 0.3266084492 0.0045020242 0.1706970000 986021329 0 402718720 -0.2096619755 -0.0756641701 -0.1332587153 3108 1311867822.3315870762 0.2429227233 0.2329252435 0.3266084492 0.0045015709 0.1796940000 986024345 0 402718720 -0.2097575814 -0.0760547891 -0.1330945194 3109 1311867822.3635189533 0.2433536798 0.2329285978 0.3266084492 0.0045009301 0.1819760000 986027305 0 402718720 -0.2103977948 -0.0766852498 -0.1332144290 3110 1311867822.3960089684 0.2434564531 0.2329319829 0.3266084492 0.0045005655 0.1702410000 986030153 0 402718720 -0.2110136002 -0.0767241493 -0.1330047399 3111 1311867822.4314260483 0.2433783561 0.2329353408 0.3266084492 0.0044999962 0.1701190000 986033169 0 402718720 -0.2115898877 -0.0772530362 -0.1327763498 3112 1311867822.4634740353 0.2442007810 0.2329389608 0.3266084492 0.0044995537 0.1702730000 986036073 0 402718720 -0.2127496749 -0.0774385557 -0.1325324327 3113 1311867822.4957718849 0.2450626940 0.2329428554 0.3266084492 0.0044990896 0.1806150000 986038921 0 402718720 -0.2140446007 -0.0781143531 -0.1319650412 3114 1311867822.5315260887 0.2463050485 0.2329471464 0.3266084492 0.0044992096 0.1691870000 986041993 0 402718720 -0.2152402103 -0.0796725601 -0.1319396496 3115 1311867822.5634500980 0.2460878342 0.2329513649 0.3266084492 0.0044988680 0.1687550000 986044897 0 402718720 -0.2149730772 -0.0808223635 -0.1319321394 3116 1311867822.5955328941 0.2460061461 0.2329555545 0.3266084492 0.0044993729 0.1681440000 986047801 0 402718720 -0.2150790840 -0.0827975124 -0.1318844557 3117 1311867822.6315131187 0.2473163754 0.2329601617 0.3266084492 0.0044996837 0.1677600000 986050817 0 402718720 -0.2166853100 -0.0837746114 -0.1317506135 3118 1311867822.6634640694 0.2471521050 0.2329647134 0.3266084492 0.0044994063 0.1756970000 986053721 0 402718720 -0.2167229503 -0.0849067047 -0.1318310946 3119 1311867822.6954870224 0.2486603409 0.2329697456 0.3266084492 0.0044988472 0.1654420000 986056625 0 402718720 -0.2188084275 -0.0856333748 -0.1316894442 3120 1311867822.7317390442 0.2504816055 0.2329753584 0.3266084492 0.0044993292 0.1647030000 986059585 0 402718720 -0.2214449942 -0.0856478512 -0.1314541399 3121 1311867822.7634871006 0.2500053048 0.2329808150 0.3266084492 0.0044989149 0.1653530000 986062489 0 402718720 -0.2217118293 -0.0852780715 -0.1313833147 3122 1311867822.7954308987 0.2505723238 0.2329864497 0.3266084492 0.0044985459 0.1651620000 986065393 0 402718720 -0.2223902494 -0.0859751180 -0.1310560703 3123 1311867822.8314750195 0.2491800338 0.2329916349 0.3266084492 0.0044988826 0.1960510000 986068409 0 402718720 -0.2219361514 -0.0857559070 -0.1310210228 3124 1311867822.8634629250 0.2498881817 0.2329970435 0.3266084492 0.0045010852 0.1660110000 986071313 0 402718720 -0.2228388339 -0.0854517743 -0.1308836937 3125 1311867822.8955349922 0.2482721359 0.2330019316 0.3266084492 0.0045005661 0.1663750000 986074105 0 402718720 -0.2217508405 -0.0850633234 -0.1307221800 3126 1311867822.9318330288 0.2476796061 0.2330066269 0.3266084492 0.0045000333 0.1784010000 986077177 0 402718720 -0.2218908221 -0.0842607468 -0.1304226667 3127 1311867822.9635109901 0.2474147379 0.2330112346 0.3266084492 0.0044999302 0.1664390000 986080081 0 402718720 -0.2224661112 -0.0838476121 -0.1302598864 3128 1311867822.9979970455 0.2474794686 0.2330158600 0.3266084492 0.0045004630 0.1757710000 986083097 0 402718720 -0.2231743932 -0.0835240856 -0.1298234463 3129 1311867823.0344979763 0.2479206175 0.2330206234 0.3266084492 0.0044998574 0.1659090000 986086001 0 402718720 -0.2243669033 -0.0832716972 -0.1295123994 3130 1311867823.0634639263 0.2475624532 0.2330252693 0.3266084492 0.0045000307 0.1675600000 986088793 0 402718720 -0.2246156037 -0.0835498571 -0.1293694973 3131 1311867823.0971090794 0.2475226223 0.2330298996 0.3266084492 0.0044994428 0.1678880000 986091753 0 402718720 -0.2253461778 -0.0832825974 -0.1290531456 3132 1311867823.1313869953 0.2478383034 0.2330346277 0.3266084492 0.0045001157 0.1668370000 986094713 0 402718720 -0.2264272571 -0.0839443505 -0.1288839430 3133 1311867823.1635200977 0.2465080023 0.2330389282 0.3266084492 0.0045012649 0.1897460000 986097617 0 402718720 -0.2259585261 -0.0835723281 -0.1288772970 3134 1311867823.1954131126 0.2474921644 0.2330435399 0.3266084492 0.0045046818 0.1668610000 986100521 0 402718720 -0.2277538180 -0.0832915008 -0.1283317655 3135 1311867823.2316908836 0.2475116104 0.2330481549 0.3266084492 0.0045044180 0.1673270000 986103593 0 402718720 -0.2285982668 -0.0834802836 -0.1282365918 3136 1311867823.2635869980 0.2484703809 0.2330530727 0.3266084492 0.0045092248 0.1778300000 986106497 0 402718720 -0.2299873084 -0.0834553912 -0.1281292140 3137 1311867823.2955200672 0.2484200746 0.2330579714 0.3266084492 0.0045085360 0.1662710000 986109345 0 402718720 -0.2308406085 -0.0826599225 -0.1275918484 3138 1311867823.3330919743 0.2489004284 0.2330630200 0.3266084492 0.0045079554 0.1659720000 986112417 0 402718720 -0.2319465131 -0.0826129094 -0.1275062412 3139 1311867823.3635790348 0.2499393821 0.2330683963 0.3266084492 0.0045075404 0.1656130000 986115321 0 402718720 -0.2335551679 -0.0828308985 -0.1272361726 3140 1311867823.3954129219 0.2516900897 0.2330743268 0.3266084492 0.0045074258 0.1654990000 986118169 0 402718720 -0.2362097055 -0.0821743160 -0.1269621998 3141 1311867823.4318161011 0.2514212430 0.2330801679 0.3266084492 0.0045074859 0.1646870000 986121241 0 402718720 -0.2365766466 -0.0818863958 -0.1268958747 3142 1311867823.4634220600 0.2514209449 0.2330860052 0.3266084492 0.0045101170 0.1658960000 986124145 0 402718720 -0.2365270853 -0.0820400715 -0.1268647909 3143 1311867823.4969789982 0.2525350451 0.2330921932 0.3266084492 0.0045105604 0.1757550000 986127105 0 402718720 -0.2384332567 -0.0817475319 -0.1266714483 3144 1311867823.5356218815 0.2512965798 0.2330979834 0.3266084492 0.0045104701 0.1666970000 986130121 0 402718720 -0.2377366573 -0.0812439397 -0.1268008649 3145 1311867823.5636498928 0.2511959970 0.2331037380 0.3266084492 0.0045117831 0.1660280000 986132969 0 402718720 -0.2377205342 -0.0816094801 -0.1264257133 3146 1311867823.5974569321 0.2521007955 0.2331097765 0.3266084492 0.0045114036 0.1667330000 986135929 0 402718720 -0.2393049449 -0.0813164562 -0.1261823177 3147 1311867823.6316640377 0.2510631979 0.2331154814 0.3266084492 0.0045298820 0.1661830000 986138889 0 402718720 -0.2391559035 -0.0801461935 -0.1259997636 3148 1311867823.6636750698 0.2497193515 0.2331207558 0.3266084492 0.0045334684 0.1758810000 986141793 0 402718720 -0.2385476381 -0.0791038200 -0.1258336157 3149 1311867823.6956110001 0.2500254512 0.2331261241 0.3266084492 0.0045335204 0.1675500000 986144641 0 402718720 -0.2390549183 -0.0793710127 -0.1254102886 3150 1311867823.7316160202 0.2495036870 0.2331313233 0.3266084492 0.0045328545 0.1678080000 986147713 0 402718720 -0.2390200794 -0.0789727271 -0.1253791600 3151 1311867823.7635159492 0.2487980276 0.2331362953 0.3266084492 0.0045323146 0.1668140000 986150617 0 402718720 -0.2389508039 -0.0784384608 -0.1254246384 3152 1311867823.7964189053 0.2490939349 0.2331413580 0.3266084492 0.0045317996 0.1679810000 986153521 0 402718720 -0.2395662367 -0.0788083076 -0.1250675619 3153 1311867823.8316709995 0.2492121756 0.2331464550 0.3266084492 0.0045311356 0.1724750000 986156537 0 402718720 -0.2401699722 -0.0787125826 -0.1245152205 3154 1311867823.8635869026 0.2477926314 0.2331510987 0.3266084492 0.0045309846 0.1683450000 986159441 0 402718720 -0.2393573076 -0.0777407736 -0.1242452711 3155 1311867823.8993299007 0.2484860420 0.2331559592 0.3266084492 0.0045309314 0.1688750000 986162401 0 402718720 -0.2404085547 -0.0774792805 -0.1238479242 3156 1311867823.9316000938 0.2477768362 0.2331605919 0.3266084492 0.0045443292 0.1683250000 986165361 0 402718720 -0.2397939265 -0.0775057152 -0.1234136522 3157 1311867823.9639530182 0.2483822703 0.2331654135 0.3266084492 0.0045548275 0.1683660000 986168321 0 402718720 -0.2407737672 -0.0770425871 -0.1229159757 3158 1311867823.9956440926 0.2485900372 0.2331702978 0.3266084492 0.0045560992 0.1838750000 986171113 0 402718720 -0.2415285558 -0.0764730647 -0.1225589961 3159 1311867824.0315599442 0.2479068041 0.2331749627 0.3266084492 0.0045556355 0.1743410000 986174185 0 402718720 -0.2413640916 -0.0761314034 -0.1222303584 3160 1311867824.0634789467 0.2488519102 0.2331799238 0.3266084492 0.0045563416 0.1681430000 986177089 0 402718720 -0.2424800992 -0.0759534389 -0.1217448562 3161 1311867824.0966339111 0.2487098724 0.2331848367 0.3266084492 0.0045556940 0.1806070000 986179993 0 402718720 -0.2428693622 -0.0752389282 -0.1215301007 3162 1311867824.1315801144 0.2482899576 0.2331896138 0.3266084492 0.0045561103 0.1670730000 986183009 0 402718720 -0.2430027127 -0.0757145584 -0.1213666126 3163 1311867824.1636250019 0.2499525845 0.2331949135 0.3266084492 0.0045554944 0.1801030000 986185913 0 402718720 -0.2449227870 -0.0758745149 -0.1208882108 3164 1311867824.1974411011 0.2492789477 0.2331999970 0.3266084492 0.0045548908 0.1693780000 986188873 0 402718720 -0.2447550297 -0.0747347176 -0.1205178797 3165 1311867824.2314341068 0.2513896823 0.2332057441 0.3266084492 0.0045570922 0.1692480000 986191777 0 402718720 -0.2472950965 -0.0748364404 -0.1199125126 3166 1311867824.2667160034 0.2495911717 0.2332109195 0.3266084492 0.0045570151 0.1694310000 986194793 0 402718720 -0.2455614954 -0.0745955184 -0.1197711304 3167 1311867824.3015260696 0.2490364015 0.2332159165 0.3266084492 0.0045579257 0.1691270000 986197753 0 402718720 -0.2455294728 -0.0730008408 -0.1195202619 3168 1311867824.3329520226 0.2491521835 0.2332209469 0.3266084492 0.0045575483 0.1923270000 986200713 0 402718720 -0.2459675819 -0.0723753273 -0.1193287969 3169 1311867824.3655378819 0.2486459017 0.2332258144 0.3266084492 0.0045581038 0.1698470000 986203617 0 402718720 -0.2457900047 -0.0716682971 -0.1188699305 3170 1311867824.3960471153 0.2472627461 0.2332302424 0.3266084492 0.0045575806 0.1706960000 986206409 0 402718720 -0.2448035032 -0.0697591528 -0.1185654476 3171 1311867824.4315910339 0.2479021549 0.2332348693 0.3266084492 0.0045569096 0.1713320000 986209425 0 402718720 -0.2454651445 -0.0685789809 -0.1182374656 3172 1311867824.4656479359 0.2471904010 0.2332392689 0.3266084492 0.0045562947 0.1714510000 986212441 0 402718720 -0.2449948937 -0.0670676306 -0.1174365133 3173 1311867824.4978680611 0.2458907962 0.2332432562 0.3266084492 0.0045602900 0.1842910000 986215345 0 402718720 -0.2439460158 -0.0660305694 -0.1170924082 3174 1311867824.5316801071 0.2442645729 0.2332467286 0.3266084492 0.0045597824 0.1727380000 986218249 0 402718720 -0.2424088269 -0.0645128042 -0.1166190729 3175 1311867824.5658340454 0.2434409708 0.2332499393 0.3266084492 0.0045591271 0.1743680000 986221265 0 402718720 -0.2419211864 -0.0626302510 -0.1159719378 3176 1311867824.5956490040 0.2434041500 0.2332531365 0.3266084492 0.0045586721 0.1726890000 986224057 0 402718720 -0.2419142276 -0.0620614626 -0.1155183986 3177 1311867824.6318910122 0.2430872172 0.2332562319 0.3266084492 0.0045579741 0.1742370000 986227129 0 402718720 -0.2412890196 -0.0618126728 -0.1146545559 3178 1311867824.6661880016 0.2437856048 0.2332595451 0.3266084492 0.0045576253 0.2024470000 986230033 0 402718720 -0.2420593202 -0.0609722398 -0.1140922159 3179 1311867824.6979959011 0.2439779192 0.2332629167 0.3266084492 0.0045652564 0.1755490000 986232937 0 402718720 -0.2424704731 -0.0605051778 -0.1133442745 3180 1311867824.7314980030 0.2429487556 0.2332659626 0.3266084492 0.0045739791 0.1746430000 986235785 0 402718720 -0.2417409420 -0.0601656958 -0.1129924953 3181 1311867824.7639760971 0.2414237559 0.2332685271 0.3266084492 0.0045738382 0.1757220000 986238801 0 402718720 -0.2402647734 -0.0596572645 -0.1125134826 3182 1311867824.7997510433 0.2415364683 0.2332711255 0.3266084492 0.0045757772 0.1930170000 986241705 0 402718720 -0.2404671311 -0.0588326491 -0.1121136621 3183 1311867824.8315179348 0.2412022650 0.2332736172 0.3266084492 0.0045801486 0.1875150000 986244665 0 402718720 -0.2402961105 -0.0588173196 -0.1114566997 3184 1311867824.8635060787 0.2412469983 0.2332761214 0.3266084492 0.0045798049 0.1766440000 986247569 0 402718720 -0.2404426038 -0.0587247573 -0.1109301671 3185 1311867824.8995370865 0.2410397679 0.2332785590 0.3266084492 0.0045842696 0.1913330000 986250529 0 402718720 -0.2403503656 -0.0585892573 -0.1101137102 3186 1311867824.9316530228 0.2400150895 0.2332806734 0.3266084492 0.0045836558 0.1911340000 986253489 0 402718720 -0.2396902293 -0.0585743412 -0.1094973236 3187 1311867824.9636321068 0.2403549254 0.2332828931 0.3266084492 0.0045854707 0.1819120000 986256393 0 402718720 -0.2403231263 -0.0589129589 -0.1087398902 3188 1311867824.9996089935 0.2397739440 0.2332849292 0.3266084492 0.0045861367 0.1892190000 986259465 0 402718720 -0.2403774112 -0.0588449426 -0.1082728058 3189 1311867825.0316529274 0.2405263186 0.2332871999 0.3266084492 0.0045857278 0.1818260000 986262313 0 402718720 -0.2415964603 -0.0593047552 -0.1078229323 3190 1311867825.0644180775 0.2402814180 0.2332893925 0.3266084492 0.0045851215 0.1812070000 986265161 0 402718720 -0.2420168370 -0.0590820126 -0.1075252891 3191 1311867825.0997018814 0.2398058027 0.2332914346 0.3266084492 0.0045845106 0.1810850000 986268177 0 402718720 -0.2421761900 -0.0589682683 -0.1072679237 3192 1311867825.1316909790 0.2394932061 0.2332933775 0.3266084492 0.0045840050 0.1822590000 986271137 0 402718720 -0.2423110455 -0.0596277192 -0.1075631082 3193 1311867825.1636679173 0.2388410121 0.2332951149 0.3266084492 0.0045834201 0.2041970000 986274041 0 402718720 -0.2419568300 -0.0606696941 -0.1074458808 3194 1311867825.1996359825 0.2391043156 0.2332969337 0.3266084492 0.0045831794 0.1808200000 986277001 0 402718720 -0.2432681620 -0.0603659712 -0.1070378497 3195 1311867825.2316811085 0.2379274815 0.2332983830 0.3266084492 0.0045843169 0.1818980000 986279961 0 402718720 -0.2440038174 -0.0599851459 -0.1070900336 3196 1311867825.2670049667 0.2373461872 0.2332996496 0.3266084492 0.0045849287 0.1823420000 986282977 0 402718720 -0.2444079220 -0.0604302995 -0.1071587652 3197 1311867825.2996079922 0.2374088764 0.2333009349 0.3266084492 0.0045842461 0.1822820000 986285937 0 402718720 -0.2454506457 -0.0602252521 -0.1066174433 3198 1311867825.3316459656 0.2371242344 0.2333021304 0.3266084492 0.0045852234 0.1956040000 986288785 0 402718720 -0.2464414984 -0.0596005134 -0.1064360738 3199 1311867825.3635549545 0.2375800908 0.2333034677 0.3266084492 0.0045848707 0.1833640000 986291689 0 402718720 -0.2476952672 -0.0602284148 -0.1060857922 3200 1311867825.3995220661 0.2372067273 0.2333046875 0.3266084492 0.0045844134 0.1836950000 986294761 0 402718720 -0.2480240762 -0.0604814589 -0.1056145802 3201 1311867825.4329199791 0.2367865145 0.2333057752 0.3266084492 0.0045843085 0.1844430000 986297665 0 402718720 -0.2484254837 -0.0602059141 -0.1053323224 3202 1311867825.4655759335 0.2382728159 0.2333073264 0.3266084492 0.0045837013 0.1930810000 986300513 0 402718720 -0.2503713667 -0.0608161800 -0.1053126380 3203 1311867825.4996039867 0.2378471643 0.2333087438 0.3266084492 0.0045830326 0.1846140000 986303417 0 402718720 -0.2503340542 -0.0611360297 -0.1052363738 3204 1311867825.5338120461 0.2379176766 0.2333101823 0.3266084492 0.0045824198 0.1846050000 986306433 0 402718720 -0.2507316768 -0.0610314570 -0.1050933823 3205 1311867825.5637319088 0.2379463315 0.2333116288 0.3266084492 0.0045817562 0.1851260000 986309281 0 402718720 -0.2509828508 -0.0608418137 -0.1051416248 3206 1311867825.5995988846 0.2389597893 0.2333133906 0.3266084492 0.0045813325 0.1855090000 986312241 0 402718720 -0.2524658740 -0.0614544116 -0.1050517038 3207 1311867825.6372098923 0.2380498350 0.2333148675 0.3266084492 0.0045807977 0.1846690000 986315313 0 402718720 -0.2521666586 -0.0611524358 -0.1049383134 3208 1311867825.6636829376 0.2379448712 0.2333163108 0.3266084492 0.0045801713 0.1996170000 986318049 0 402718720 -0.2520586550 -0.0608941801 -0.1048279852 3209 1311867825.6997060776 0.2387993932 0.2333180194 0.3266084492 0.0045807731 0.1864960000 986321065 0 402718720 -0.2532519102 -0.0614575706 -0.1046904251 3210 1311867825.7345299721 0.2398692966 0.2333200603 0.3266084492 0.0045801384 0.1967850000 986324025 0 402718720 -0.2549752891 -0.0612017922 -0.1045958176 3211 1311867825.7654349804 0.2376791388 0.2333214179 0.3266084492 0.0045794523 0.1864550000 986326873 0 402718720 -0.2528031170 -0.0606375784 -0.1048232168 3212 1311867825.7998030186 0.2384903431 0.2333230271 0.3266084492 0.0045789878 0.1865360000 986329945 0 402718720 -0.2537485659 -0.0616736151 -0.1049621776 3213 1311867825.8355960846 0.2389381677 0.2333247748 0.3266084492 0.0045784057 0.1865470000 986332961 0 402718720 -0.2547817528 -0.0613645278 -0.1049455330 3214 1311867825.8656499386 0.2387042046 0.2333264485 0.3266084492 0.0045779116 0.1873640000 986335753 0 402718720 -0.2546834946 -0.0608790405 -0.1051006094 3215 1311867825.8996019363 0.2370702624 0.2333276130 0.3266084492 0.0045776828 0.1981730000 986338769 0 402718720 -0.2529237568 -0.0616184399 -0.1054199934 3216 1311867825.9338490963 0.2363650799 0.2333285575 0.3266084492 0.0045774256 0.1861650000 986341729 0 402718720 -0.2525650263 -0.0616427511 -0.1053556800 3217 1311867825.9640550613 0.2363090962 0.2333294840 0.3266084492 0.0045769406 0.1863510000 986344577 0 402718720 -0.2523435652 -0.0610394962 -0.1056795195 3218 1311867825.9996759892 0.2372990698 0.2333307175 0.3266084492 0.0045764215 0.1966550000 986347537 0 402718720 -0.2535138428 -0.0618103333 -0.1056746617 3219 1311867826.0327920914 0.2362990826 0.2333316397 0.3266084492 0.0045758858 0.1864790000 986350497 0 402718720 -0.2525760531 -0.0611633100 -0.1058805808 3220 1311867826.0636880398 0.2366767675 0.2333326785 0.3266084492 0.0045755768 0.1879940000 986353401 0 402718720 -0.2533659339 -0.0602404997 -0.1057028994 3221 1311867826.1009249687 0.2365106344 0.2333336652 0.3266084492 0.0045754257 0.1874720000 986356417 0 402718720 -0.2535016835 -0.0601224154 -0.1060679331 3222 1311867826.1333520412 0.2368469536 0.2333347556 0.3266084492 0.0045748011 0.1874400000 986359377 0 402718720 -0.2539083958 -0.0604027510 -0.1057556495 3223 1311867826.1658940315 0.2364543378 0.2333357235 0.3266084492 0.0045741315 0.2005810000 986362281 0 402718720 -0.2538347244 -0.0597340614 -0.1058568954 3224 1311867826.1998670101 0.2358391285 0.2333365000 0.3266084492 0.0045741617 0.2010920000 986365241 0 402718720 -0.2532203794 -0.0602831393 -0.1061748788 3225 1311867826.2345190048 0.2367726415 0.2333375654 0.3266084492 0.0045734584 0.1879790000 986368201 0 402718720 -0.2542969584 -0.0605864786 -0.1060744673 3226 1311867826.2638120651 0.2368032336 0.2333386397 0.3266084492 0.0045733832 0.1885880000 986371049 0 402718720 -0.2548879981 -0.0609740578 -0.1060449257 3227 1311867826.3011031151 0.2385065705 0.2333402412 0.3266084492 0.0045738392 0.1882020000 986374009 0 402718720 -0.2566176057 -0.0612927005 -0.1063745618 3228 1311867826.3321969509 0.2379931659 0.2333416826 0.3266084492 0.0045741460 0.1885050000 986376745 0 402718720 -0.2567202747 -0.0616715401 -0.1063168496 3229 1311867826.3637990952 0.2380110472 0.2333431287 0.3266084492 0.0045741844 0.1879230000 986379649 0 402718720 -0.2565221786 -0.0613634624 -0.1063346416 3230 1311867826.3997180462 0.2375932634 0.2333444445 0.3266084492 0.0045734930 0.1882470000 986382609 0 402718720 -0.2564243376 -0.0613260195 -0.1066247448 3231 1311867826.4321830273 0.2381587476 0.2333459346 0.3266084492 0.0045729303 0.1985270000 986385569 0 402718720 -0.2571197450 -0.0616294965 -0.1066291407 3232 1311867826.4641919136 0.2386295050 0.2333475693 0.3266084492 0.0045723854 0.1878380000 986388529 0 402718720 -0.2577433288 -0.0613954887 -0.1066383794 3233 1311867826.5007300377 0.2379113585 0.2333489810 0.3266084492 0.0045716957 0.2053140000 986391489 0 402718720 -0.2572561800 -0.0610837638 -0.1067900136 3234 1311867826.5320169926 0.2381404638 0.2333504626 0.3266084492 0.0045710184 0.1889580000 986394393 0 402718720 -0.2577754259 -0.0612112507 -0.1067909896 3235 1311867826.5638980865 0.2378716767 0.2333518601 0.3266084492 0.0045703751 0.1886790000 986397353 0 402718720 -0.2575121224 -0.0609359853 -0.1069535464 3236 1311867826.6006839275 0.2385461479 0.2333534653 0.3266084492 0.0045698419 0.2069280000 986400313 0 402718720 -0.2585247159 -0.0608700588 -0.1070201993 3237 1311867826.6315999031 0.2380677015 0.2333549217 0.3266084492 0.0045693812 0.1882320000 986403161 0 402718720 -0.2584922612 -0.0606575459 -0.1070636883 3238 1311867826.6638810635 0.2376926988 0.2333562613 0.3266084492 0.0045688755 0.1892480000 986406065 0 402718720 -0.2585011721 -0.0602885932 -0.1071553305 3239 1311867826.6997959614 0.2378938794 0.2333576622 0.3266084492 0.0045683509 0.1882160000 986409025 0 402718720 -0.2595309317 -0.0598648712 -0.1070928052 3240 1311867826.7349510193 0.2383349240 0.2333591984 0.3266084492 0.0045676644 0.2016480000 986412041 0 402718720 -0.2602739334 -0.0602172911 -0.1072564274 3241 1311867826.7678439617 0.2368779033 0.2333602841 0.3266084492 0.0045670891 0.1889280000 986414889 0 402718720 -0.2589620352 -0.0606131032 -0.1074810773 3242 1311867826.8019490242 0.2370071858 0.2333614090 0.3266084492 0.0045667005 0.1889660000 986417905 0 402718720 -0.2595344186 -0.0602112971 -0.1075653657 3243 1311867826.8324790001 0.2376985401 0.2333627464 0.3266084492 0.0045707355 0.2161100000 986420753 0 402718720 -0.2603138387 -0.0612040795 -0.1078504771 3244 1311867826.8646159172 0.2376660556 0.2333640729 0.3266084492 0.0045701433 0.1890130000 986423601 0 402718720 -0.2605540156 -0.0614032336 -0.1078434661 3245 1311867826.9008219242 0.2377486378 0.2333654241 0.3266084492 0.0045702111 0.1885090000 986426617 0 402718720 -0.2611030936 -0.0617293194 -0.1079595536 3246 1311867826.9319140911 0.2383540869 0.2333669610 0.3266084492 0.0045727881 0.1883650000 986429409 0 402718720 -0.2614316940 -0.0618273802 -0.1080706120 3247 1311867826.9639439583 0.2389029860 0.2333686659 0.3266084492 0.0045728462 0.1880930000 986432201 0 402718720 -0.2623631358 -0.0618431568 -0.1081550792 3248 1311867827.0083661079 0.2389419824 0.2333703819 0.3266084492 0.0045738185 0.1890070000 986435385 0 402718720 -0.2626104653 -0.0619182847 -0.1082885340 3249 1311867827.0334970951 0.2380981892 0.2333718370 0.3266084492 0.0045732770 0.1883930000 986438065 0 402718720 -0.2619034648 -0.0619082935 -0.1085261330 3250 1311867827.0653018951 0.2389667034 0.2333735585 0.3266084492 0.0045745854 0.1880680000 986440801 0 402718720 -0.2631149888 -0.0620477721 -0.1086902842 3251 1311867827.0995759964 0.2392632663 0.2333753702 0.3266084492 0.0045760646 0.1875480000 986443649 0 402718720 -0.2630809247 -0.0616966113 -0.1090803593 3252 1311867827.1319890022 0.2392081916 0.2333771638 0.3266084492 0.0045755310 0.1878690000 986446385 0 402718720 -0.2629519105 -0.0617851876 -0.1092617661 3253 1311867827.1636219025 0.2384808213 0.2333787327 0.3266084492 0.0045756854 0.1887460000 986449345 0 402718720 -0.2622236609 -0.0618019849 -0.1097107083 3254 1311867827.2006959915 0.2401316166 0.2333808080 0.3266084492 0.0045777279 0.1879640000 986452361 0 402718720 -0.2635541558 -0.0624452867 -0.1100322604 3255 1311867827.2315700054 0.2389669418 0.2333825241 0.3266084492 0.0045771786 0.1872370000 986455153 0 402718720 -0.2621356845 -0.0620914549 -0.1103128642 3256 1311867827.2656030655 0.2392497063 0.2333843261 0.3266084492 0.0045766565 0.1979240000 986457945 0 402718720 -0.2621130347 -0.0621562526 -0.1108135432 3257 1311867827.2999110222 0.2388622165 0.2333860080 0.3266084492 0.0045774025 0.1870300000 986460961 0 402718720 -0.2620406151 -0.0618446060 -0.1107572764 3258 1311867827.3331999779 0.2390427738 0.2333877442 0.3266084492 0.0045767776 0.1982170000 986463809 0 402718720 -0.2624335885 -0.0610240065 -0.1105817109 3259 1311867827.3665180206 0.2388488054 0.2333894199 0.3266084492 0.0045762401 0.1994830000 986466713 0 402718720 -0.2623330355 -0.0610103980 -0.1106160283 3260 1311867827.4023349285 0.2384509742 0.2333909725 0.3266084492 0.0045769833 0.1875080000 986469785 0 402718720 -0.2619295120 -0.0607668422 -0.1108625308 3261 1311867827.4316511154 0.2384773791 0.2333925323 0.3266084492 0.0045765326 0.1872570000 986472577 0 402718720 -0.2620121241 -0.0605435073 -0.1106645837 3262 1311867827.4660930634 0.2384153903 0.2333940721 0.3266084492 0.0045758682 0.1878540000 986475537 0 402718720 -0.2621293962 -0.0604125969 -0.1109806076 3263 1311867827.5022308826 0.2382358760 0.2333955560 0.3266084492 0.0045762756 0.2020100000 986478609 0 402718720 -0.2618685663 -0.0609795488 -0.1111601517 3264 1311867827.5346870422 0.2381869555 0.2333970239 0.3266084492 0.0045762287 0.1874520000 986481457 0 402718720 -0.2620928586 -0.0604453273 -0.1111034155 3265 1311867827.5639040470 0.2381424606 0.2333984774 0.3266084492 0.0045757101 0.1873580000 986484361 0 402718720 -0.2621012330 -0.0608355440 -0.1113204360 3266 1311867827.6014358997 0.2382896096 0.2333999749 0.3266084492 0.0045758359 0.1871700000 986487377 0 402718720 -0.2620252669 -0.0615491271 -0.1115884557 3267 1311867827.6328499317 0.2383681834 0.2334014957 0.3266084492 0.0045758677 0.1872870000 986490281 0 402718720 -0.2624196708 -0.0609416924 -0.1111738905 3268 1311867827.6636641026 0.2391771525 0.2334032630 0.3266084492 0.0045752160 0.1975400000 986493185 0 402718720 -0.2636500597 -0.0605508126 -0.1111333743 3269 1311867827.7023649216 0.2377353013 0.2334045882 0.3266084492 0.0045747172 0.1860030000 986496257 0 402718720 -0.2619191408 -0.0607355535 -0.1111924276 3270 1311867827.7343521118 0.2367048562 0.2334055975 0.3266084492 0.0045747853 0.1872050000 986499161 0 402718720 -0.2610453069 -0.0600912012 -0.1111529320 3271 1311867827.7669301033 0.2362366319 0.2334064629 0.3266084492 0.0045766150 0.1875470000 986502009 0 402718720 -0.2608522177 -0.0600217730 -0.1110666320 3272 1311867827.8077390194 0.2367230356 0.2334074766 0.3266084492 0.0045772837 0.1875500000 986505193 0 402718720 -0.2612628341 -0.0606201477 -0.1107615456 3273 1311867827.8316879272 0.2373704612 0.2334086874 0.3266084492 0.0045774504 0.1879120000 986507817 0 402718720 -0.2619708180 -0.0604186356 -0.1106474251 3274 1311867827.8644089699 0.2366834134 0.2334096876 0.3266084492 0.0045768900 0.1885100000 986510833 0 402718720 -0.2613086104 -0.0602736622 -0.1106349751 3275 1311867827.9007999897 0.2378555387 0.2334110451 0.3266084492 0.0045783227 0.1874160000 986513737 0 402718720 -0.2621381283 -0.0610851943 -0.1106193736 3276 1311867827.9316790104 0.2378779650 0.2334124086 0.3266084492 0.0045796016 0.1871040000 986516641 0 402718720 -0.2626973391 -0.0607551150 -0.1104298159 3277 1311867827.9717168808 0.2380394191 0.2334138206 0.3266084492 0.0045825849 0.1874980000 986519713 0 402718720 -0.2626647353 -0.0609450750 -0.1105209589 3278 1311867827.9999699593 0.2372785360 0.2334149996 0.3266084492 0.0045823679 0.1977940000 986522617 0 402718720 -0.2618178129 -0.0614976175 -0.1108527556 3279 1311867828.0320069790 0.2378673851 0.2334163574 0.3266084492 0.0045821737 0.1869460000 986525465 0 402718720 -0.2623004615 -0.0615289174 -0.1107484326 3280 1311867828.0711700916 0.2380195409 0.2334177609 0.3266084492 0.0045838193 0.1870860000 986528537 0 402718720 -0.2627920806 -0.0615933202 -0.1106109843 3281 1311867828.1003229618 0.2370298952 0.2334188618 0.3266084492 0.0045832638 0.1866410000 986531441 0 402718720 -0.2616527975 -0.0619054139 -0.1108552441 3282 1311867828.1317639351 0.2375648022 0.2334201250 0.3266084492 0.0045849035 0.1865220000 986534289 0 402718720 -0.2621686459 -0.0614739470 -0.1105964184 3283 1311867828.1714239120 0.2393287718 0.2334219248 0.3266084492 0.0045857947 0.2025090000 986537417 0 402718720 -0.2638585865 -0.0618814155 -0.1104425937 3284 1311867828.2080869675 0.2383127213 0.2334234141 0.3266084492 0.0045921071 0.1876490000 986540489 0 402718720 -0.2622618675 -0.0619763322 -0.1102349907 3285 1311867828.2316999435 0.2374697775 0.2334246458 0.3266084492 0.0045930164 0.1858520000 986543113 0 402718720 -0.2615761757 -0.0615274198 -0.1100422516 3286 1311867828.2725389004 0.2373165488 0.2334258302 0.3266084492 0.0045924801 0.1977640000 986546241 0 402718720 -0.2614578307 -0.0608531907 -0.1098765954 3287 1311867828.3008439541 0.2379573882 0.2334272089 0.3266084492 0.0045921572 0.1867760000 986549089 0 402718720 -0.2615736723 -0.0615937561 -0.1095737219 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:11:00 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 -nan 0.0919960000 960649900 0 402718720 -0.0000000000 0.0000000000 -0.0000000000 2 1311867170.4941389561 0.0573717020 0.0578118730 0.0582520440 0.0124384817 0.1051360000 976391721 0 402718720 -0.0004072262 -0.0012858674 -0.0024128594 3 1311867170.5264289379 0.0565326363 0.0573854608 0.0582520440 0.0101360069 0.1180740000 976081985 0 402718720 -0.0017253581 -0.0022905804 -0.0047754426 4 1311867170.5623490810 0.0561531186 0.0570773752 0.0582520440 0.0096939930 0.1069820000 976085401 0 402718720 0.0001815499 -0.0028489344 -0.0061352560 5 1311867170.5942170620 0.0564878471 0.0569594696 0.0582520440 0.0086570308 0.1083780000 976088249 0 402718720 0.0032386892 -0.0038525709 -0.0071731703 6 1311867170.6260869503 0.0565138943 0.0568852071 0.0582520440 0.0085082530 0.1092720000 976091953 0 402718720 0.0035822922 -0.0050064190 -0.0088233240 7 1311867170.6621398926 0.0566217005 0.0568475633 0.0582520440 0.0084011855 0.1109440000 976095025 0 402718720 0.0042666858 -0.0060294420 -0.0103985174 8 1311867170.6942050457 0.0565143824 0.0568059157 0.0582520440 0.0080624176 0.1111640000 976097873 0 402718720 0.0039346968 -0.0066705765 -0.0121178320 9 1311867170.7263879776 0.0572911352 0.0568598289 0.0582520440 0.0083638007 0.1121480000 976100777 0 402718720 0.0047216709 -0.0067814970 -0.0132080782 10 1311867170.7620189190 0.0571037121 0.0568842173 0.0582520440 0.0084267381 0.1114260000 976105449 0 402718720 0.0036999029 -0.0089522135 -0.0147678684 11 1311867170.7941920757 0.0576175041 0.0569508797 0.0582520440 0.0083849712 0.1115700000 976108241 0 402718720 0.0046730596 -0.0111104185 -0.0163442288 12 1311867170.8262820244 0.0582830422 0.0570618932 0.0582830422 0.0084182018 0.1137510000 976111201 0 402718720 0.0057509104 -0.0142152999 -0.0181489494 13 1311867170.8622210026 0.0583667755 0.0571622688 0.0583667755 0.0082326201 0.1132930000 976114217 0 402718720 0.0054110112 -0.0167625397 -0.0205292664 14 1311867170.8943779469 0.0588976108 0.0572862218 0.0588976108 0.0079371808 0.1132570000 976117065 0 402718720 0.0051991055 -0.0189172477 -0.0228590686 15 1311867170.9263520241 0.0592492297 0.0574170890 0.0592492297 0.0079867024 0.1120140000 976120025 0 402718720 0.0049795005 -0.0210557431 -0.0255748350 16 1311867170.9621469975 0.0584787801 0.0574834447 0.0592492297 0.0077860800 0.1130130000 976123041 0 402718720 0.0025149619 -0.0233250298 -0.0286700856 17 1311867170.9942629337 0.0581946447 0.0575252800 0.0592492297 0.0076115906 0.1128200000 976125889 0 402718720 0.0015675346 -0.0249397289 -0.0317836851 18 1311867171.0262739658 0.0583906658 0.0575733570 0.0592492297 0.0073987350 0.1227820000 976132049 0 402718720 0.0013857816 -0.0262926351 -0.0344625749 19 1311867171.0623519421 0.0577807315 0.0575842714 0.0592492297 0.0078912619 0.1127290000 976135065 0 402718720 0.0006828412 -0.0291226413 -0.0373767465 20 1311867171.0942349434 0.0569510125 0.0575526085 0.0592492297 0.0077962232 0.1119080000 976137913 0 402718720 0.0012539392 -0.0310282130 -0.0399192758 21 1311867171.1262509823 0.0568107404 0.0575172814 0.0592492297 0.0076727569 0.1106440000 976140873 0 402718720 0.0016471456 -0.0313888565 -0.0420592539 22 1311867171.1622469425 0.0565001555 0.0574710484 0.0592492297 0.0076320047 0.1275450000 976143889 0 402718720 0.0030269357 -0.0332086757 -0.0437395349 23 1311867171.1942689419 0.0555122197 0.0573858820 0.0592492297 0.0079612574 0.1110540000 976146737 0 402718720 0.0048672990 -0.0332908705 -0.0448285788 24 1311867171.2262530327 0.0571258999 0.0573750494 0.0592492297 0.0080020960 0.1106700000 976149697 0 402718720 0.0073566409 -0.0331376903 -0.0454756543 25 1311867171.2622439861 0.0565513112 0.0573420998 0.0592492297 0.0080365452 0.1108930000 976152713 0 402718720 0.0080675911 -0.0333134606 -0.0465236865 26 1311867171.2943410873 0.0566131808 0.0573140645 0.0592492297 0.0079475609 0.1127530000 976155505 0 402718720 0.0086030001 -0.0314863324 -0.0471895486 27 1311867171.3263869286 0.0564521998 0.0572821436 0.0592492297 0.0082482194 0.1262720000 976158465 0 402718720 0.0059560640 -0.0307081062 -0.0485000424 28 1311867171.3622460365 0.0552366190 0.0572090891 0.0592492297 0.0081268509 0.1274290000 976161481 0 402718720 0.0032985432 -0.0301743187 -0.0500387177 29 1311867171.3941431046 0.0556942075 0.0571568518 0.0592492297 0.0082774846 0.1263010000 976164329 0 402718720 0.0016327128 -0.0285019465 -0.0511358939 30 1311867171.4262878895 0.0563084893 0.0571285731 0.0592492297 0.0082832959 0.1160660000 976167289 0 402718720 0.0011757320 -0.0286029167 -0.0526739210 31 1311867171.4622440338 0.0560800321 0.0570947492 0.0592492297 0.0081859623 0.1170030000 976170305 0 402718720 0.0002749737 -0.0299116559 -0.0547510162 32 1311867171.4944040775 0.0560421087 0.0570618542 0.0592492297 0.0081323194 0.1169420000 976173153 0 402718720 0.0016349545 -0.0298265591 -0.0567201041 33 1311867171.5261778831 0.0557381026 0.0570217405 0.0592492297 0.0080121010 0.1270420000 976176113 0 402718720 0.0005321116 -0.0294397082 -0.0586504936 34 1311867171.5622971058 0.0550439171 0.0569635692 0.0592492297 0.0079018085 0.1151020000 976185529 0 402718720 0.0014305002 -0.0297154877 -0.0602305755 35 1311867171.5942931175 0.0556142144 0.0569250162 0.0592492297 0.0078366563 0.1166130000 976188377 0 402718720 0.0025925462 -0.0281834304 -0.0610744394 36 1311867171.6263399124 0.0556033030 0.0568883020 0.0592492297 0.0077397109 0.1168110000 976191337 0 402718720 0.0013984119 -0.0286685470 -0.0617083237 37 1311867171.6622560024 0.0552100167 0.0568429429 0.0592492297 0.0076391630 0.1168390000 976194353 0 402718720 -0.0010655982 -0.0294350330 -0.0626066625 38 1311867171.6943440437 0.0560208969 0.0568213101 0.0592492297 0.0078555864 0.1309620000 976197201 0 402718720 -0.0001966008 -0.0292492453 -0.0627679899 39 1311867171.7262439728 0.0563393459 0.0568089521 0.0592492297 0.0077899028 0.1179870000 976200161 0 402718720 0.0001748482 -0.0294915959 -0.0632380769 40 1311867171.7621190548 0.0570879541 0.0568159271 0.0592492297 0.0077099329 0.1177450000 976203177 0 402718720 0.0010024655 -0.0305460300 -0.0636968389 41 1311867171.7941710949 0.0574909821 0.0568323919 0.0592492297 0.0076986091 0.1173420000 976206025 0 402718720 0.0009890732 -0.0316518098 -0.0645686537 42 1311867171.8262550831 0.0579838790 0.0568598082 0.0592492297 0.0076324211 0.1276100000 976208985 0 402718720 -0.0001297734 -0.0320304856 -0.0655826405 43 1311867171.8623590469 0.0575281605 0.0568753513 0.0592492297 0.0075594044 0.1422410000 976212001 0 402718720 -0.0036291408 -0.0323144756 -0.0670155138 44 1311867171.8944430351 0.0572128519 0.0568830218 0.0592492297 0.0076907344 0.1164520000 976214905 0 402718720 -0.0061273281 -0.0326260664 -0.0679314435 45 1311867171.9262220860 0.0583500750 0.0569156229 0.0592492297 0.0076573722 0.1158850000 976217809 0 402718720 -0.0067630173 -0.0319095366 -0.0681905150 46 1311867171.9624669552 0.0588493384 0.0569576602 0.0592492297 0.0076022471 0.1163020000 976220825 0 402718720 -0.0080215465 -0.0316468477 -0.0685555115 47 1311867171.9946711063 0.0598669760 0.0570195606 0.0598669760 0.0076511396 0.1167290000 976223729 0 402718720 -0.0088181272 -0.0309289526 -0.0681130514 48 1311867172.0262680054 0.0607684180 0.0570976618 0.0607684180 0.0077688707 0.1167750000 976226633 0 402718720 -0.0100020552 -0.0300565343 -0.0675430968 49 1311867172.0622880459 0.0612903200 0.0571832262 0.0612903200 0.0077127469 0.1297410000 976229649 0 402718720 -0.0116153620 -0.0295300297 -0.0668326989 50 1311867172.0941960812 0.0615727752 0.0572710172 0.0615727752 0.0076923281 0.1169100000 976232553 0 402718720 -0.0134013910 -0.0292423852 -0.0661561713 51 1311867172.1263689995 0.0624003001 0.0573715914 0.0624003001 0.0076735371 0.1169740000 976235457 0 402718720 -0.0148056038 -0.0294340663 -0.0652802214 52 1311867172.1623349190 0.0618280135 0.0574572918 0.0624003001 0.0076701686 0.1171960000 976238473 0 402718720 -0.0177391488 -0.0296392199 -0.0650413409 53 1311867172.1944270134 0.0607901327 0.0575201756 0.0624003001 0.0076156099 0.1265230000 976241377 0 402718720 -0.0217750967 -0.0292378906 -0.0648028031 54 1311867172.2264409065 0.0604784898 0.0575749592 0.0624003001 0.0077680236 0.1288480000 976244281 0 402718720 -0.0255301632 -0.0290451273 -0.0646235719 55 1311867172.2622280121 0.0599651486 0.0576184172 0.0624003001 0.0077062328 0.1162520000 976247297 0 402718720 -0.0287055764 -0.0282772388 -0.0641242787 56 1311867172.2944829464 0.0602906495 0.0576661356 0.0624003001 0.0076500028 0.1173900000 976250201 0 402718720 -0.0310291126 -0.0276317690 -0.0636601448 57 1311867172.3263380527 0.0596651062 0.0577012053 0.0624003001 0.0076221490 0.1183270000 976253105 0 402718720 -0.0344843827 -0.0272155069 -0.0633451864 58 1311867172.3624010086 0.0599930957 0.0577407206 0.0624003001 0.0075757677 0.1303650000 976256121 0 402718720 -0.0369553864 -0.0270554665 -0.0632399619 59 1311867172.3942890167 0.0590376519 0.0577627025 0.0624003001 0.0075399757 0.1185680000 976259025 0 402718720 -0.0399551317 -0.0272814147 -0.0634874254 60 1311867172.4265220165 0.0593358018 0.0577889208 0.0624003001 0.0075673433 0.1180110000 976261929 0 402718720 -0.0423372872 -0.0278989412 -0.0638136491 61 1311867172.4623498917 0.0592659563 0.0578131345 0.0624003001 0.0075386291 0.1192420000 976264945 0 402718720 -0.0447976366 -0.0283379108 -0.0641527995 62 1311867172.4952669144 0.0598404258 0.0578458328 0.0624003001 0.0075797536 0.1190700000 976267793 0 402718720 -0.0459624827 -0.0280036014 -0.0641600117 63 1311867172.5263059139 0.0592677183 0.0578684024 0.0624003001 0.0075549112 0.1320320000 976270697 0 402718720 -0.0488425232 -0.0291027091 -0.0648227707 64 1311867172.5624930859 0.0591932647 0.0578891034 0.0624003001 0.0074949224 0.1314030000 976273713 0 402718720 -0.0510774180 -0.0300130621 -0.0654648915 65 1311867172.5945439339 0.0605049171 0.0579293467 0.0624003001 0.0074686497 0.1189480000 976276561 0 402718720 -0.0504406206 -0.0297366418 -0.0659903958 66 1311867172.6263699532 0.0605372749 0.0579688607 0.0624003001 0.0074394909 0.1193820000 976292321 0 402718720 -0.0523502566 -0.0297946651 -0.0666595995 67 1311867172.6624419689 0.0607907213 0.0580109780 0.0624003001 0.0073841642 0.1192220000 976295337 0 402718720 -0.0542058796 -0.0297031850 -0.0673438534 68 1311867172.6945450306 0.0605290346 0.0580480083 0.0624003001 0.0074717616 0.1211970000 976298241 0 402718720 -0.0564633161 -0.0296882540 -0.0676848888 69 1311867172.7263929844 0.0613684841 0.0580961311 0.0624003001 0.0074530336 0.1216130000 976301145 0 402718720 -0.0586331934 -0.0290635675 -0.0680714622 70 1311867172.7623739243 0.0616253838 0.0581465490 0.0624003001 0.0074198225 0.1219770000 976304161 0 402718720 -0.0613686964 -0.0282738414 -0.0685805827 71 1311867172.7944509983 0.0611533150 0.0581888978 0.0624003001 0.0073814579 0.1227950000 976307009 0 402718720 -0.0647521317 -0.0287007689 -0.0692241415 72 1311867172.8263089657 0.0619065650 0.0582405321 0.0624003001 0.0073574001 0.1224330000 976309969 0 402718720 -0.0673369095 -0.0287331957 -0.0699726269 73 1311867172.8632309437 0.0619436242 0.0582912594 0.0624003001 0.0073276315 0.1334230000 976313041 0 402718720 -0.0702262074 -0.0293993335 -0.0707680956 74 1311867172.8944649696 0.0612674654 0.0583314784 0.0624003001 0.0072805161 0.1228730000 976315833 0 402718720 -0.0727281496 -0.0297468025 -0.0714873672 75 1311867172.9263219833 0.0608027354 0.0583644285 0.0624003001 0.0072353364 0.1230370000 976318793 0 402718720 -0.0753169432 -0.0308243185 -0.0721638650 76 1311867172.9623310566 0.0607495010 0.0583958110 0.0624003001 0.0071895128 0.1347250000 976321809 0 402718720 -0.0765238628 -0.0314128920 -0.0727840140 77 1311867172.9945271015 0.0605420731 0.0584236845 0.0624003001 0.0071455040 0.1218530000 976324657 0 402718720 -0.0778170452 -0.0316172801 -0.0731934309 78 1311867173.0262629986 0.0599313937 0.0584430142 0.0624003001 0.0071008312 0.1346930000 976327561 0 402718720 -0.0792019889 -0.0322337784 -0.0736035109 79 1311867173.0624630451 0.0599318631 0.0584618603 0.0624003001 0.0070583232 0.1224210000 976330577 0 402718720 -0.0802900046 -0.0325851515 -0.0738083944 80 1311867173.0945179462 0.0603748187 0.0584857723 0.0624003001 0.0070467726 0.1231300000 976333481 0 402718720 -0.0806811750 -0.0327476002 -0.0739010200 81 1311867173.1267819405 0.0601213127 0.0585059642 0.0624003001 0.0070240222 0.1223900000 976336441 0 402718720 -0.0822229460 -0.0329038501 -0.0742386281 82 1311867173.1622309685 0.0604894236 0.0585301527 0.0624003001 0.0070188490 0.1232140000 976339457 0 402718720 -0.0830269381 -0.0321628936 -0.0740505084 83 1311867173.1943008900 0.0611513741 0.0585617337 0.0624003001 0.0069773353 0.1359200000 976342305 0 402718720 -0.0838483498 -0.0313886851 -0.0739964768 84 1311867173.2264449596 0.0609234944 0.0585898499 0.0624003001 0.0069436488 0.1454990000 976345209 0 402718720 -0.0859021097 -0.0316362418 -0.0739673078 85 1311867173.2622020245 0.0615775585 0.0586249994 0.0624003001 0.0069259859 0.1230870000 976348225 0 402718720 -0.0870130658 -0.0308776610 -0.0738645270 86 1311867173.2942678928 0.0621638745 0.0586661491 0.0624003001 0.0068881137 0.1235740000 976351073 0 402718720 -0.0885875225 -0.0306180604 -0.0738316104 87 1311867173.3262879848 0.0620661378 0.0587052294 0.0624003001 0.0068920016 0.1240780000 976353977 0 402718720 -0.0905538872 -0.0310555603 -0.0740900412 88 1311867173.3623280525 0.0625377521 0.0587487808 0.0625377521 0.0068546731 0.1355120000 976357049 0 402718720 -0.0920736343 -0.0308330040 -0.0742121488 89 1311867173.3942871094 0.0622891448 0.0587885602 0.0625377521 0.0068400891 0.1253240000 976359897 0 402718720 -0.0942156687 -0.0314036831 -0.0744345710 90 1311867173.4262790680 0.0619321503 0.0588234890 0.0625377521 0.0068315211 0.1249240000 976362801 0 402718720 -0.0964010283 -0.0322595760 -0.0748610869 91 1311867173.4622900486 0.0621041171 0.0588595398 0.0625377521 0.0068423046 0.1258770000 976365817 0 402718720 -0.0981139392 -0.0327651761 -0.0752825737 92 1311867173.4943389893 0.0627009049 0.0589012938 0.0627009049 0.0069118050 0.1260960000 976368721 0 402718720 -0.0998500884 -0.0332625136 -0.0755577087 93 1311867173.5263900757 0.0625437647 0.0589404602 0.0627009049 0.0068779712 0.1383780000 976371681 0 402718720 -0.1021069661 -0.0332847834 -0.0759437457 94 1311867173.5624370575 0.0625217855 0.0589785594 0.0627009049 0.0068584188 0.1260220000 976374697 0 402718720 -0.1041134447 -0.0327730253 -0.0760986730 95 1311867173.5943109989 0.0626235083 0.0590169273 0.0627009049 0.0068442742 0.1259370000 976377545 0 402718720 -0.1061658487 -0.0327677093 -0.0763819292 96 1311867173.6263959408 0.0617943890 0.0590458591 0.0627009049 0.0068354693 0.1258930000 976380449 0 402718720 -0.1087920070 -0.0333523080 -0.0769686699 97 1311867173.6623299122 0.0622252263 0.0590786361 0.0627009049 0.0068058133 0.1257700000 976383465 0 402718720 -0.1100879088 -0.0332797430 -0.0772877336 98 1311867173.6943540573 0.0627625436 0.0591162270 0.0627625436 0.0067751304 0.1329720000 976386369 0 402718720 -0.1110310778 -0.0336345024 -0.0778300539 99 1311867173.7267971039 0.0620149411 0.0591455070 0.0627625436 0.0067539695 0.1266880000 976389329 0 402718720 -0.1136603057 -0.0340474993 -0.0788532570 100 1311867173.7623970509 0.0624230057 0.0591782819 0.0627625436 0.0067307690 0.1266250000 976392345 0 402718720 -0.1146625504 -0.0334534869 -0.0794327185 101 1311867173.7943561077 0.0630205274 0.0592163240 0.0630205274 0.0067000769 0.1394720000 976395137 0 402718720 -0.1155292019 -0.0331781469 -0.0798635632 102 1311867173.8265669346 0.0618418492 0.0592420644 0.0630205274 0.0066688317 0.1270470000 976398097 0 402718720 -0.1186236367 -0.0343475901 -0.0809599683 103 1311867173.8635799885 0.0628676489 0.0592772643 0.0630205274 0.0066693769 0.1369320000 976401057 0 402718720 -0.1192512214 -0.0340323895 -0.0815442279 104 1311867173.8946080208 0.0626922250 0.0593101004 0.0630205274 0.0066402057 0.1275850000 976403961 0 402718720 -0.1207205951 -0.0344007872 -0.0823903307 105 1311867173.9266970158 0.0617062673 0.0593329211 0.0630205274 0.0066235794 0.1278770000 976406921 0 402718720 -0.1231204420 -0.0357738435 -0.0837274417 106 1311867173.9625461102 0.0624622405 0.0593624430 0.0630205274 0.0066271596 0.1281970000 976409937 0 402718720 -0.1240489483 -0.0351821445 -0.0841791853 107 1311867173.9944310188 0.0628851354 0.0593953653 0.0630205274 0.0066214939 0.1387840000 976412785 0 402718720 -0.1252307594 -0.0349309109 -0.0846056491 108 1311867174.0264260769 0.0628838986 0.0594276665 0.0630205274 0.0066468912 0.1382330000 976415689 0 402718720 -0.1265922934 -0.0355829671 -0.0857873634 109 1311867174.0624630451 0.0633864477 0.0594639856 0.0633864477 0.0066334388 0.1289920000 976418705 0 402718720 -0.1280388087 -0.0340102836 -0.0860928744 110 1311867174.0945188999 0.0645772517 0.0595104699 0.0645772517 0.0066240288 0.1289580000 976421609 0 402718720 -0.1283163577 -0.0327708721 -0.0860415250 111 1311867174.1264541149 0.0643704310 0.0595542533 0.0645772517 0.0066154034 0.1299540000 976424513 0 402718720 -0.1307152808 -0.0333948508 -0.0868034363 112 1311867174.1624329090 0.0644105524 0.0595976131 0.0645772517 0.0066051821 0.1302410000 976427529 0 402718720 -0.1327817589 -0.0329455659 -0.0871244073 113 1311867174.1943979263 0.0650814921 0.0596461430 0.0650814921 0.0065944306 0.1435110000 976430433 0 402718720 -0.1333822459 -0.0319275633 -0.0871452391 114 1311867174.2267580032 0.0649808124 0.0596929384 0.0650814921 0.0065738702 0.1416630000 976433393 0 402718720 -0.1354593039 -0.0327002443 -0.0877510533 115 1311867174.2626769543 0.0645911247 0.0597355313 0.0650814921 0.0065455512 0.1317560000 976436353 0 402718720 -0.1381848902 -0.0327608660 -0.0882308409 116 1311867174.2945280075 0.0658795238 0.0597884967 0.0658795238 0.0065345101 0.1328620000 976439257 0 402718720 -0.1382768601 -0.0319879986 -0.0884445384 117 1311867174.3265740871 0.0650665835 0.0598336086 0.0658795238 0.0065079326 0.1328310000 976442161 0 402718720 -0.1409630626 -0.0325786322 -0.0890879408 118 1311867174.3624329567 0.0648054183 0.0598757426 0.0658795238 0.0064951411 0.1447430000 976445233 0 402718720 -0.1430580616 -0.0323099531 -0.0891574323 119 1311867174.3946359158 0.0652648062 0.0599210288 0.0658795238 0.0064880211 0.1345990000 976448081 0 402718720 -0.1442109942 -0.0319426805 -0.0892268047 120 1311867174.4266788960 0.0656820312 0.0599690372 0.0658795238 0.0064614798 0.1348040000 976451041 0 402718720 -0.1452690065 -0.0322431736 -0.0894830897 121 1311867174.4630160332 0.0655665174 0.0600152973 0.0658795238 0.0064675873 0.1357710000 976454001 0 402718720 -0.1470038891 -0.0327039063 -0.0900100470 122 1311867174.4945669174 0.0661423802 0.0600655193 0.0661423802 0.0064443900 0.1591060000 976456905 0 402718720 -0.1481722593 -0.0321587585 -0.0898464099 123 1311867174.5267519951 0.0660568699 0.0601142295 0.0661423802 0.0064347721 0.1476970000 976459865 0 402718720 -0.1503337920 -0.0326523371 -0.0900936723 124 1311867174.5623500347 0.0657169074 0.0601594124 0.0661423802 0.0064310641 0.1357110000 976462881 0 402718720 -0.1524866819 -0.0321169831 -0.0901379734 125 1311867174.5944879055 0.0659101903 0.0602054186 0.0661423802 0.0064172611 0.1359030000 976465729 0 402718720 -0.1541458666 -0.0314416327 -0.0897601396 126 1311867174.6265459061 0.0663124993 0.0602538875 0.0663124993 0.0064102520 0.1354100000 976468633 0 402718720 -0.1558849812 -0.0312835127 -0.0895388648 127 1311867174.6624910831 0.0659339130 0.0602986121 0.0663124993 0.0063874558 0.1362100000 976471649 0 402718720 -0.1580023617 -0.0318784826 -0.0896739960 128 1311867174.6945910454 0.0663432702 0.0603458360 0.0663432702 0.0063761379 0.1515500000 976474553 0 402718720 -0.1593572646 -0.0311369747 -0.0891722664 129 1311867174.7265629768 0.0672239810 0.0603991550 0.0672239810 0.0063706519 0.1374300000 976477401 0 402718720 -0.1606481075 -0.0311325416 -0.0888065323 130 1311867174.7623760700 0.0670510605 0.0604503235 0.0672239810 0.0063665557 0.1370400000 976506073 0 402718720 -0.1627686024 -0.0321952887 -0.0891096517 131 1311867174.7944738865 0.0672266558 0.0605020512 0.0672266558 0.0063477350 0.1368140000 976508865 0 402718720 -0.1644290537 -0.0319458134 -0.0890841857 132 1311867174.8273398876 0.0677770600 0.0605571649 0.0677770600 0.0063289824 0.1377000000 976511825 0 402718720 -0.1654999107 -0.0322978497 -0.0892982781 133 1311867174.8624229431 0.0672450736 0.0606074499 0.0677770600 0.0063085910 0.1383240000 976514841 0 402718720 -0.1676005274 -0.0325823128 -0.0900450349 134 1311867174.8944199085 0.0677806884 0.0606609816 0.0677806884 0.0062926265 0.1383910000 976517689 0 402718720 -0.1681113094 -0.0317304246 -0.0909745097 135 1311867174.9270179272 0.0677134916 0.0607132224 0.0677806884 0.0062795726 0.1368180000 976520649 0 402718720 -0.1699564457 -0.0312793739 -0.0914167911 136 1311867174.9626429081 0.0679444075 0.0607663929 0.0679444075 0.0062574962 0.1387510000 976523665 0 402718720 -0.1719374210 -0.0315428153 -0.0920988843 137 1311867174.9943349361 0.0670973212 0.0608126040 0.0679444075 0.0062567936 0.1387810000 976526513 0 402718720 -0.1745223999 -0.0311352164 -0.0929828361 138 1311867175.0265510082 0.0677398592 0.0608628015 0.0679444075 0.0062651054 0.1389480000 976529473 0 402718720 -0.1759855151 -0.0294310115 -0.0929737315 139 1311867175.0633120537 0.0677246451 0.0609121673 0.0679444075 0.0062469423 0.1389520000 976532489 0 402718720 -0.1779364794 -0.0295755416 -0.0931616127 140 1311867175.0947189331 0.0608941168 0.0609120384 0.0679444075 0.0062454180 0.1416860000 976535393 0 402718720 -0.1883596033 -0.0271359775 -0.0940242410 141 1311867175.1265308857 0.0611853302 0.0609139766 0.0679444075 0.0062322681 0.1399070000 976538297 0 402718720 -0.1896046549 -0.0276404545 -0.0935051292 142 1311867175.1625180244 0.0615299083 0.0609183141 0.0679444075 0.0062336416 0.1407680000 976541313 0 402718720 -0.1904159188 -0.0275376216 -0.0934134945 143 1311867175.1946399212 0.0613409653 0.0609212697 0.0679444075 0.0062145029 0.1518270000 976544161 0 402718720 -0.1919880211 -0.0274216048 -0.0932170972 144 1311867175.2270050049 0.0620399788 0.0609290386 0.0679444075 0.0062940202 0.1412130000 976547121 0 402718720 -0.1926046759 -0.0265794117 -0.0927021727 145 1311867175.2624669075 0.0627654418 0.0609417034 0.0679444075 0.0063085608 0.1430710000 976550081 0 402718720 -0.1931158304 -0.0259687584 -0.0924117118 146 1311867175.2944509983 0.0627487078 0.0609540802 0.0679444075 0.0062888996 0.1430490000 976552985 0 402718720 -0.1943125874 -0.0258448999 -0.0922271162 147 1311867175.3267059326 0.0645226687 0.0609783563 0.0679444075 0.0062705962 0.1447380000 976555945 0 402718720 -0.1940687299 -0.0243748948 -0.0913412422 148 1311867175.3625650406 0.0655546188 0.0610092770 0.0679444075 0.0062622750 0.1571800000 976558905 0 402718720 -0.1956532151 -0.0240386836 -0.0907128975 149 1311867175.3945989609 0.0656142384 0.0610401827 0.0679444075 0.0062484360 0.1467870000 976561809 0 402718720 -0.1980031878 -0.0240332596 -0.0905135721 150 1311867175.4266059399 0.0661191270 0.0610740424 0.0679444075 0.0062317829 0.1587620000 976564713 0 402718720 -0.2001454830 -0.0228205044 -0.0902504101 151 1311867175.4625999928 0.0665628538 0.0611103921 0.0679444075 0.0062173318 0.1463060000 976567785 0 402718720 -0.2031547725 -0.0225996356 -0.0899100006 152 1311867175.4945731163 0.0667193010 0.0611472928 0.0679444075 0.0062005698 0.1472870000 976570689 0 402718720 -0.2062826157 -0.0225914605 -0.0897564590 153 1311867175.5264270306 0.0671656132 0.0611866283 0.0679444075 0.0061903670 0.1591180000 976573537 0 402718720 -0.2091697007 -0.0220905207 -0.0896771401 154 1311867175.5625700951 0.0674804524 0.0612274972 0.0679444075 0.0061993147 0.1478810000 976576609 0 402718720 -0.2115805894 -0.0206282567 -0.0894644335 155 1311867175.5946640968 0.0681081116 0.0612718883 0.0681081116 0.0062243746 0.1483080000 976579457 0 402718720 -0.2142094821 -0.0195332263 -0.0893302783 156 1311867175.6264801025 0.0669772401 0.0613084611 0.0681081116 0.0062384898 0.1486590000 976582361 0 402718720 -0.2180325836 -0.0194794256 -0.0892874524 157 1311867175.6624929905 0.0686475337 0.0613552068 0.0686475337 0.0062866695 0.1740740000 976585377 0 402718720 -0.2190328538 -0.0190384034 -0.0888373181 158 1311867175.6947000027 0.0695441514 0.0614070355 0.0695441514 0.0063052414 0.1507550000 976588281 0 402718720 -0.2207410634 -0.0196096487 -0.0888959840 159 1311867175.7273120880 0.0700197071 0.0614612033 0.0700197071 0.0062983081 0.1512350000 976591241 0 402718720 -0.2229018807 -0.0200653877 -0.0887356400 160 1311867175.7624969482 0.0707540214 0.0615192834 0.0707540214 0.0062851066 0.1514720000 976594257 0 402718720 -0.2246325314 -0.0190286152 -0.0887801796 161 1311867175.7948620319 0.0712084100 0.0615794643 0.0712084100 0.0062979988 0.1499860000 976597105 0 402718720 -0.2270110995 -0.0193034783 -0.0889241993 162 1311867175.8287971020 0.0707433596 0.0616360315 0.0712084100 0.0062833695 0.1520300000 976600121 0 402718720 -0.2303228378 -0.0196021423 -0.0893378481 163 1311867175.8625519276 0.0718811825 0.0616988852 0.0718811825 0.0062910716 0.1622740000 976603081 0 402718720 -0.2324458808 -0.0192981884 -0.0894367918 164 1311867175.8946080208 0.0726237223 0.0617655001 0.0726237223 0.0062784989 0.1523530000 976605929 0 402718720 -0.2347342670 -0.0195749644 -0.0899292901 165 1311867175.9282429218 0.0725314245 0.0618307481 0.0726237223 0.0062797281 0.1522960000 976608889 0 402718720 -0.2377828062 -0.0201096982 -0.0906292498 166 1311867175.9629371166 0.0729139969 0.0618975147 0.0729139969 0.0062611528 0.1522160000 976611849 0 402718720 -0.2401944250 -0.0194761585 -0.0908176005 167 1311867175.9983000755 0.0731495097 0.0619648919 0.0731495097 0.0062607151 0.1642140000 976614809 0 402718720 -0.2426767945 -0.0189579967 -0.0908442363 168 1311867176.0268509388 0.0732723996 0.0620321985 0.0732723996 0.0062434603 0.1620310000 976617601 0 402718720 -0.2448779941 -0.0203591604 -0.0913272128 169 1311867176.0627059937 0.0722070113 0.0620924045 0.0732723996 0.0062803303 0.1529390000 976620617 0 402718720 -0.2480146885 -0.0209282506 -0.0920545012 170 1311867176.0946600437 0.0726334751 0.0621544108 0.0732723996 0.0063185033 0.1546160000 976623465 0 402718720 -0.2494140565 -0.0205408949 -0.0924226791 171 1311867176.1268119812 0.0729550496 0.0622175724 0.0732723996 0.0063057159 0.1531600000 976626425 0 402718720 -0.2511346340 -0.0205851793 -0.0930490270 172 1311867176.1625900269 0.0726512671 0.0622782334 0.0732723996 0.0063902217 0.1528710000 976629441 0 402718720 -0.2529991865 -0.0202697013 -0.0937442333 173 1311867176.1946918964 0.0726383030 0.0623381182 0.0732723996 0.0064440963 0.1530290000 976632345 0 402718720 -0.2543495297 -0.0186499301 -0.0943974853 174 1311867176.2265360355 0.0719406679 0.0623933053 0.0732723996 0.0064288532 0.1535860000 976635249 0 402718720 -0.2567339540 -0.0176241081 -0.0949740484 175 1311867176.2625019550 0.0712765306 0.0624440666 0.0732723996 0.0064195412 0.1533140000 976638265 0 402718720 -0.2592940629 -0.0172633007 -0.0959409401 176 1311867176.2946109772 0.0705331266 0.0624900271 0.0732723996 0.0064147802 0.1532970000 976641113 0 402718720 -0.2620431185 -0.0160683692 -0.0964881629 177 1311867176.3266019821 0.0715375543 0.0625411431 0.0732723996 0.0064032075 0.1773180000 976644017 0 402718720 -0.2628752291 -0.0146466997 -0.0969658419 178 1311867176.3624560833 0.0715205446 0.0625915892 0.0732723996 0.0063860095 0.1863800000 976647089 0 402718720 -0.2647553086 -0.0150975669 -0.0978599787 179 1311867176.3952438831 0.0720505491 0.0626444325 0.0732723996 0.0063694229 0.1856120000 976649937 0 402718720 -0.2655390501 -0.0139391106 -0.0985299796 180 1311867176.4268360138 0.0730358139 0.0627021624 0.0732723996 0.0063541780 0.1856860000 976652841 0 402718720 -0.2656801045 -0.0126561737 -0.0991852731 181 1311867176.4629659653 0.0729493052 0.0627587765 0.0732723996 0.0064296655 0.1860500000 976655857 0 402718720 -0.2675202787 -0.0121694570 -0.1000696942 182 1311867176.4945809841 0.0724334419 0.0628119340 0.0732723996 0.0064297562 0.1860250000 976658705 0 402718720 -0.2698222101 -0.0118967928 -0.1011608914 183 1311867176.5266211033 0.0733871460 0.0628697220 0.0733871460 0.0064761471 0.1861860000 976661665 0 402718720 -0.2709841132 -0.0107582323 -0.1018986180 184 1311867176.5636389256 0.0733660012 0.0629267670 0.0733871460 0.0064739638 0.1875820000 976664737 0 402718720 -0.2729716301 -0.0110852690 -0.1028577164 185 1311867176.5946090221 0.0730298236 0.0629813781 0.0733871460 0.0064613972 0.1883830000 976667585 0 402718720 -0.2751568854 -0.0113589382 -0.1040909663 186 1311867176.6283841133 0.0732371584 0.0630365167 0.0733871460 0.0064542135 0.1544520000 976670545 0 402718720 -0.2770150900 -0.0105672516 -0.1049126908 187 1311867176.6625781059 0.0735069960 0.0630925086 0.0735069960 0.0064424700 0.1544500000 976673505 0 402718720 -0.2793905735 -0.0097606592 -0.1057213321 188 1311867176.6945180893 0.0735026374 0.0631478816 0.0735069960 0.0064272275 0.1570050000 976676353 0 402718720 -0.2815869153 -0.0092608808 -0.1065361947 189 1311867176.7265889645 0.0731703863 0.0632009108 0.0735069960 0.0064108406 0.1556540000 976679313 0 402718720 -0.2845946848 -0.0087893838 -0.1072807834 190 1311867176.7632329464 0.0738693997 0.0632570607 0.0738693997 0.0063978728 0.1561020000 976682329 0 402718720 -0.2866262496 -0.0088961739 -0.1077603027 191 1311867176.7947680950 0.0743001252 0.0633148778 0.0743001252 0.0063925634 0.1559430000 976685177 0 402718720 -0.2884441018 -0.0086489469 -0.1083077043 192 1311867176.8266770840 0.0743414387 0.0633723078 0.0743414387 0.0063782081 0.1557870000 976688137 0 402718720 -0.2908243835 -0.0087578623 -0.1089441106 193 1311867176.8627309799 0.0747095048 0.0634310498 0.0747095048 0.0063660350 0.1675170000 976691153 0 402718720 -0.2929264903 -0.0082459599 -0.1092618629 194 1311867176.8949549198 0.0746954829 0.0634891138 0.0747095048 0.0063528350 0.1552790000 976694057 0 402718720 -0.2954491973 -0.0079571372 -0.1097063795 195 1311867176.9268178940 0.0745062158 0.0635456118 0.0747095048 0.0063532553 0.1669500000 976696961 0 402718720 -0.2979824841 -0.0081862444 -0.1102106199 196 1311867176.9650609493 0.0752851740 0.0636055075 0.0752851740 0.0063640408 0.1552380000 976699977 0 402718720 -0.2997301221 -0.0071844142 -0.1104464903 197 1311867176.9947481155 0.0759153292 0.0636679939 0.0759153292 0.0063522685 0.1560950000 976702825 0 402718720 -0.3011579216 -0.0067999652 -0.1108625531 198 1311867177.0267279148 0.0760730952 0.0637306460 0.0760730952 0.0063406791 0.1653650000 976705729 0 402718720 -0.3034639060 -0.0075878962 -0.1112016067 199 1311867177.0626339912 0.0763418376 0.0637940188 0.0763418376 0.0063292022 0.1559370000 976708745 0 402718720 -0.3056857586 -0.0069253393 -0.1114268377 200 1311867177.0946850777 0.0766251534 0.0638581745 0.0766251534 0.0063175711 0.1562770000 976711649 0 402718720 -0.3070321083 -0.0066372487 -0.1119832322 201 1311867177.1266150475 0.0769168437 0.0639231430 0.0769168437 0.0063028082 0.1572000000 976714553 0 402718720 -0.3090840280 -0.0071163177 -0.1122869924 202 1311867177.1627299786 0.0778061301 0.0639918706 0.0778061301 0.0062876765 0.1570610000 976717569 0 402718720 -0.3106672764 -0.0065995432 -0.1125900820 203 1311867177.1946458817 0.0774087161 0.0640579635 0.0778061301 0.0062766869 0.1707150000 976720473 0 402718720 -0.3129924536 -0.0058459723 -0.1130038127 204 1311867177.2264730930 0.0783597454 0.0641280702 0.0783597454 0.0062613932 0.1559570000 976723377 0 402718720 -0.3145630956 -0.0059411437 -0.1134098098 205 1311867177.2638640404 0.0784318447 0.0641978447 0.0784318447 0.0062464114 0.1573090000 976726449 0 402718720 -0.3173466921 -0.0054114293 -0.1137891188 206 1311867177.2946178913 0.0783018470 0.0642663108 0.0784318447 0.0062519984 0.1569680000 976729297 0 402718720 -0.3193606436 -0.0056573297 -0.1144232303 207 1311867177.3276090622 0.0777834505 0.0643316110 0.0784318447 0.0062370021 0.1574430000 976732257 0 402718720 -0.3221544623 -0.0056029749 -0.1149765924 208 1311867177.3627710342 0.0788323358 0.0644013260 0.0788323358 0.0062261371 0.1575470000 976735217 0 402718720 -0.3233921826 -0.0045918399 -0.1152596101 209 1311867177.3946089745 0.0786423236 0.0644694647 0.0788323358 0.0062279864 0.1696930000 976738121 0 402718720 -0.3258500993 -0.0048833382 -0.1157151684 210 1311867177.4312860966 0.0791878477 0.0645395523 0.0791878477 0.0062190726 0.1578400000 976741193 0 402718720 -0.3278470635 -0.0042952215 -0.1159567162 211 1311867177.4626040459 0.0791715235 0.0646088981 0.0791878477 0.0062051188 0.1573680000 976744097 0 402718720 -0.3300093412 -0.0036486816 -0.1164269745 212 1311867177.4946429729 0.0791100115 0.0646772996 0.0791878477 0.0061922748 0.1573310000 976747001 0 402718720 -0.3319400251 -0.0032391658 -0.1169046164 213 1311867177.5276319981 0.0794254392 0.0647465397 0.0794254392 0.0061802807 0.1843230000 976749905 0 402718720 -0.3333579302 -0.0024295780 -0.1174737141 214 1311867177.5626399517 0.0805926770 0.0648205870 0.0805926770 0.0061733516 0.1588910000 976752865 0 402718720 -0.3348478377 -0.0021164597 -0.1176395044 215 1311867177.5947310925 0.0765595287 0.0648751868 0.0805926770 0.0061645462 0.1595470000 976755769 0 402718720 -0.3406353891 -0.0020766133 -0.1190961897 216 1311867177.6311450005 0.0761590526 0.0649274269 0.0805926770 0.0061511291 0.1595750000 976758841 0 402718720 -0.3432716429 -0.0017846350 -0.1197147369 217 1311867177.6624829769 0.0763730183 0.0649801716 0.0805926770 0.0061386629 0.1601060000 976761745 0 402718720 -0.3443160355 -0.0009308572 -0.1203607172 218 1311867177.6945610046 0.0761316717 0.0650313252 0.0805926770 0.0061492764 0.1599220000 976764649 0 402718720 -0.3462563753 -0.0009405179 -0.1209533438 219 1311867177.7305839062 0.0758283362 0.0650806266 0.0805926770 0.0061368816 0.1601040000 976767609 0 402718720 -0.3480429649 0.0004657888 -0.1215150729 220 1311867177.7625379562 0.0764745995 0.0651324174 0.0805926770 0.0061304471 0.1876240000 976770513 0 402718720 -0.3482847214 0.0006453144 -0.1220503747 221 1311867177.7945590019 0.0755860209 0.0651797188 0.0805926770 0.0061192092 0.1587300000 976773417 0 402718720 -0.3500201404 0.0009281460 -0.1229684576 222 1311867177.8309149742 0.0760156885 0.0652285295 0.0805926770 0.0061087162 0.1711220000 976776433 0 402718720 -0.3510508835 0.0011724316 -0.1237980798 223 1311867177.8625319004 0.0760382861 0.0652770037 0.0805926770 0.0060955971 0.1820930000 976779337 0 402718720 -0.3518837392 0.0012585940 -0.1245667785 224 1311867177.8946919441 0.0762395635 0.0653259437 0.0805926770 0.0060841545 0.1608500000 976782185 0 402718720 -0.3525305092 0.0018150355 -0.1250761896 225 1311867177.9317860603 0.0765505657 0.0653758309 0.0805926770 0.0060709372 0.1606630000 976785313 0 402718720 -0.3535086215 0.0024105213 -0.1259556562 226 1311867177.9627909660 0.0764967054 0.0654250383 0.0805926770 0.0060707020 0.1613620000 976788161 0 402718720 -0.3553512692 0.0025974042 -0.1268974692 227 1311867177.9947769642 0.0765541568 0.0654740653 0.0805926770 0.0060630592 0.1608520000 976790953 0 402718720 -0.3564016223 0.0037699309 -0.1276412606 228 1311867178.0306100845 0.0771226212 0.0655251554 0.0805926770 0.0060549268 0.1691110000 976793969 0 402718720 -0.3574011028 0.0037625595 -0.1286267936 229 1311867178.0634479523 0.0776797310 0.0655782322 0.0805926770 0.0060450607 0.1607620000 976796873 0 402718720 -0.3583681583 0.0034128812 -0.1293236613 230 1311867178.0951139927 0.0780300647 0.0656323706 0.0805926770 0.0060320868 0.1613360000 976799777 0 402718720 -0.3591955006 0.0046824194 -0.1298665404 231 1311867178.1307909489 0.0781202465 0.0656864307 0.0805926770 0.0060226125 0.1615360000 976802793 0 402718720 -0.3614930511 0.0043000816 -0.1305360049 232 1311867178.1627469063 0.0780600458 0.0657397652 0.0805926770 0.0060381582 0.1720150000 976805697 0 402718720 -0.3635468483 0.0041445876 -0.1313062608 233 1311867178.1950459480 0.0786140338 0.0657950196 0.0805926770 0.0060346780 0.1786430000 976808545 0 402718720 -0.3649929464 0.0054212152 -0.1315756440 234 1311867178.2307190895 0.0791762471 0.0658522043 0.0805926770 0.0060304032 0.1627210000 976811561 0 402718720 -0.3670724332 0.0042866846 -0.1323235780 235 1311867178.2628939152 0.0793171823 0.0659095021 0.0805926770 0.0060196471 0.1617110000 976814521 0 402718720 -0.3689422011 0.0039957180 -0.1328316182 236 1311867178.2954900265 0.0800085664 0.0659692439 0.0805926770 0.0060115449 0.1620520000 976817425 0 402718720 -0.3699555993 0.0048779421 -0.1330494732 237 1311867178.3306670189 0.0809041411 0.0660322603 0.0809041411 0.0060074123 0.1626770000 976820385 0 402718720 -0.3716149330 0.0037426644 -0.1334356964 238 1311867178.3627231121 0.0808719471 0.0660946120 0.0809041411 0.0060003344 0.1629940000 976823345 0 402718720 -0.3739669323 0.0041182148 -0.1336610764 239 1311867178.3949439526 0.0810454488 0.0661571678 0.0810454488 0.0059898303 0.1626700000 976826193 0 402718720 -0.3758832216 0.0045455149 -0.1339347064 240 1311867178.4306581020 0.0811385587 0.0662195902 0.0811385587 0.0059875230 0.1623210000 976829209 0 402718720 -0.3782058656 0.0050929994 -0.1339301318 241 1311867178.4628739357 0.0814742371 0.0662828875 0.0814742371 0.0059756120 0.1619120000 976832113 0 402718720 -0.3799729049 0.0058320551 -0.1338547170 242 1311867178.4946439266 0.0811253861 0.0663442202 0.0814742371 0.0059672757 0.1630070000 976835017 0 402718720 -0.3819686472 0.0053452360 -0.1340966523 243 1311867178.5306270123 0.0819137320 0.0664082922 0.0819137320 0.0059699109 0.1753050000 976838033 0 402718720 -0.3834661543 0.0056528533 -0.1339490265 244 1311867178.5626420975 0.0825490505 0.0664744429 0.0825490505 0.0059583046 0.1637040000 976840993 0 402718720 -0.3848410249 0.0058679949 -0.1340014338 245 1311867178.5947000980 0.0828848928 0.0665414243 0.0828848928 0.0059563265 0.1635150000 976843897 0 402718720 -0.3862015903 0.0053836023 -0.1341239065 246 1311867178.6306900978 0.0831369162 0.0666088857 0.0831369162 0.0059536113 0.1627170000 976846857 0 402718720 -0.3880349100 0.0057448954 -0.1341051012 247 1311867178.6626410484 0.0831313506 0.0666757782 0.0831369162 0.0059644932 0.1637360000 976849817 0 402718720 -0.3891912997 0.0069327764 -0.1343892515 248 1311867178.6946120262 0.0825607628 0.0667398306 0.0831369162 0.0059564792 0.1739220000 976852665 0 402718720 -0.3913953304 0.0064044092 -0.1348333210 249 1311867178.7307450771 0.0817552507 0.0668001335 0.0831369162 0.0059548868 0.1642440000 976855681 0 402718720 -0.3935106099 0.0073364591 -0.1351407319 250 1311867178.7632350922 0.0818301067 0.0668602534 0.0831369162 0.0059478677 0.1645540000 976858641 0 402718720 -0.3946007490 0.0073144878 -0.1352317929 251 1311867178.8006799221 0.0817814097 0.0669197002 0.0831369162 0.0059445867 0.1796120000 976861657 0 402718720 -0.3957355022 0.0056127007 -0.1357087046 252 1311867178.8309500217 0.0819546431 0.0669793627 0.0831369162 0.0059387295 0.1639290000 976864505 0 402718720 -0.3959842920 0.0072321128 -0.1359777600 253 1311867178.8627939224 0.0818038732 0.0670379576 0.0831369162 0.0059359579 0.1847820000 976867465 0 402718720 -0.3968743086 0.0077683437 -0.1361925602 254 1311867178.8952279091 0.0814073607 0.0670945300 0.0831369162 0.0059368943 0.1772350000 976870369 0 402718720 -0.3979683518 0.0057884641 -0.1369104087 255 1311867178.9306209087 0.0813104808 0.0671502789 0.0831369162 0.0059495781 0.1655870000 976873329 0 402718720 -0.3986038268 0.0073800609 -0.1375246197 256 1311867178.9627609253 0.0804844350 0.0672023654 0.0831369162 0.0059464142 0.1658740000 976876289 0 402718720 -0.4000316560 0.0085848225 -0.1381922364 257 1311867178.9946830273 0.0787455291 0.0672472804 0.0831369162 0.0059549123 0.1759720000 976879193 0 402718720 -0.4028308690 0.0082165366 -0.1392238438 258 1311867179.0309159756 0.0787240714 0.0672917641 0.0831369162 0.0059787253 0.1767080000 976933409 0 402718720 -0.4041081369 0.0082063070 -0.1400651485 259 1311867179.0628120899 0.0795521438 0.0673391015 0.0831369162 0.0059770276 0.1655210000 976936369 0 402718720 -0.4045375288 0.0069761081 -0.1408503056 260 1311867179.0968201160 0.0793315023 0.0673852261 0.0831369162 0.0060600337 0.1657520000 976939273 0 402718720 -0.4063432813 0.0049229297 -0.1417353004 261 1311867179.1310369968 0.0791989043 0.0674304893 0.0831369162 0.0060536526 0.1648190000 976942177 0 402718720 -0.4070261717 0.0068689454 -0.1427272558 262 1311867179.1627540588 0.0793284401 0.0674759013 0.0831369162 0.0060704326 0.1639090000 976945081 0 402718720 -0.4084804952 0.0067567336 -0.1440314949 263 1311867179.1957008839 0.0775750801 0.0675143012 0.0831369162 0.0060640316 0.1741750000 976947985 0 402718720 -0.4116529226 0.0062224288 -0.1456832439 264 1311867179.2307469845 0.0771868750 0.0675509397 0.0831369162 0.0061098557 0.1616740000 976950945 0 402718720 -0.4138514698 0.0083618928 -0.1467500925 265 1311867179.2634611130 0.0779942796 0.0675903486 0.0831369162 0.0061149284 0.1643320000 976953961 0 402718720 -0.4146349430 0.0067463084 -0.1477675438 266 1311867179.2959330082 0.0780315399 0.0676296012 0.0831369162 0.0061097026 0.1639770000 976956809 0 402718720 -0.4160176516 0.0060140337 -0.1486991495 267 1311867179.3307149410 0.0792509317 0.0676731267 0.0831369162 0.0061016062 0.1629560000 976959769 0 402718720 -0.4161381423 0.0069414391 -0.1491319686 268 1311867179.3629300594 0.0795212537 0.0677173362 0.0831369162 0.0060904403 0.1711530000 976962785 0 402718720 -0.4168575704 0.0075013200 -0.1495744586 269 1311867179.3948490620 0.0791882128 0.0677599788 0.0831369162 0.0060843447 0.1627110000 976965577 0 402718720 -0.4183563888 0.0069221575 -0.1500924826 270 1311867179.4308040142 0.0797228813 0.0678042859 0.0831369162 0.0060890399 0.1622190000 976968649 0 402718720 -0.4191602170 0.0074374308 -0.1503966153 271 1311867179.4637460709 0.0811098889 0.0678533840 0.0831369162 0.0060932558 0.1750050000 976971609 0 402718720 -0.4190559685 0.0079218457 -0.1501545906 272 1311867179.4949469566 0.0818969309 0.0679050147 0.0831369162 0.0061053620 0.1638510000 976974457 0 402718720 -0.4197545946 0.0071083535 -0.1502202004 273 1311867179.5307800770 0.0828232467 0.0679596603 0.0831369162 0.0061040572 0.1735660000 976977473 0 402718720 -0.4203038514 0.0097702015 -0.1502989382 274 1311867179.5627610683 0.0832792297 0.0680155711 0.0832792297 0.0061224425 0.1639360000 976980377 0 402718720 -0.4211508930 0.0102899084 -0.1503740698 275 1311867179.5946741104 0.0830075145 0.0680700873 0.0832792297 0.0061147738 0.1640600000 976983281 0 402718720 -0.4227790236 0.0108076157 -0.1502397060 276 1311867179.6306900978 0.0837807879 0.0681270101 0.0837807879 0.0061275131 0.1647630000 976986241 0 402718720 -0.4231222868 0.0116295405 -0.1502462476 277 1311867179.6625750065 0.0846568570 0.0681866846 0.0846568570 0.0061273015 0.1653770000 976989201 0 402718720 -0.4233476222 0.0107366135 -0.1501349062 278 1311867179.6946051121 0.0850473866 0.0682473346 0.0850473866 0.0061352399 0.1865510000 976992049 0 402718720 -0.4238635302 0.0118866190 -0.1501220316 279 1311867179.7309470177 0.0853839442 0.0683087562 0.0853839442 0.0061275559 0.1651620000 976995121 0 402718720 -0.4243474901 0.0126890428 -0.1498932540 280 1311867179.7627270222 0.0850680247 0.0683686107 0.0853839442 0.0061497322 0.1643200000 976998025 0 402718720 -0.4253299534 0.0118052987 -0.1500989497 281 1311867179.7948911190 0.0858074874 0.0684306708 0.0858074874 0.0061655753 0.1867430000 977000873 0 402718720 -0.4248019457 0.0130812731 -0.1501116604 282 1311867179.8307530880 0.0867817178 0.0684957454 0.0867817178 0.0061573131 0.1660450000 977003945 0 402718720 -0.4244379699 0.0134877767 -0.1499158293 283 1311867179.8627979755 0.0870899409 0.0685614493 0.0870899409 0.0061508095 0.1659660000 977006849 0 402718720 -0.4253485799 0.0119167790 -0.1497825980 284 1311867179.8948040009 0.0874948353 0.0686281161 0.0874948353 0.0061445123 0.1638880000 977009753 0 402718720 -0.4257246554 0.0117931226 -0.1495920867 285 1311867179.9309051037 0.0880135372 0.0686961352 0.0880135372 0.0061639378 0.1657110000 977012769 0 402718720 -0.4257901907 0.0144936275 -0.1492617428 286 1311867179.9635379314 0.0878697932 0.0687631759 0.0880135372 0.0061620440 0.1659490000 977015729 0 402718720 -0.4267681539 0.0138635682 -0.1490281820 287 1311867179.9958879948 0.0872441307 0.0688275695 0.0880135372 0.0061555842 0.1649630000 977018577 0 402718720 -0.4281404316 0.0139294760 -0.1487501264 288 1311867180.0309770107 0.0876963511 0.0688930861 0.0880135372 0.0061527141 0.1740930000 977021593 0 402718720 -0.4279339910 0.0158600025 -0.1483322978 289 1311867180.0626471043 0.0870987996 0.0689560816 0.0880135372 0.0061431257 0.1782800000 977024497 0 402718720 -0.4294620752 0.0150248008 -0.1478994936 290 1311867180.0947730541 0.0847961679 0.0690107026 0.0880135372 0.0061336593 0.1659590000 977027345 0 402718720 -0.4314433932 0.0162822232 -0.1487077922 291 1311867180.1307730675 0.0843031853 0.0690632541 0.0880135372 0.0061329850 0.1662050000 977030361 0 402718720 -0.4317263365 0.0155871008 -0.1485597938 292 1311867180.1636900902 0.0842201188 0.0691151612 0.0880135372 0.0061499804 0.1992760000 977033377 0 402718720 -0.4304676056 0.0159051605 -0.1489519626 293 1311867180.1949090958 0.0835735649 0.0691645073 0.0880135372 0.0061401454 0.2048140000 977036169 0 402718720 -0.4303147793 0.0160764847 -0.1492383629 294 1311867180.2308139801 0.0829905421 0.0692115346 0.0880135372 0.0061372436 0.2050370000 977039129 0 402718720 -0.4293783605 0.0164359063 -0.1502613872 295 1311867180.2637619972 0.0821048841 0.0692552409 0.0880135372 0.0061635148 0.2046730000 977042089 0 402718720 -0.4295181632 0.0165304299 -0.1509196907 296 1311867180.2947549820 0.0811828449 0.0692955368 0.0880135372 0.0061531757 0.2043220000 977044937 0 402718720 -0.4298768342 0.0164931621 -0.1515572667 297 1311867180.3308670521 0.0804132819 0.0693329703 0.0880135372 0.0061451111 0.2045600000 977047953 0 402718720 -0.4299716353 0.0165120866 -0.1519486159 298 1311867180.3658289909 0.0795656443 0.0693673081 0.0880135372 0.0061446686 0.2046710000 977050913 0 402718720 -0.4298225939 0.0171466786 -0.1523941457 299 1311867180.3964109421 0.0791304931 0.0693999609 0.0880135372 0.0061364894 0.2054410000 977053817 0 402718720 -0.4295235276 0.0180041380 -0.1525080949 300 1311867180.4309151173 0.0783546939 0.0694298100 0.0880135372 0.0061283697 0.1787030000 977056777 0 402718720 -0.4293651879 0.0174909309 -0.1531546563 301 1311867180.4670670033 0.0780924782 0.0694585897 0.0880135372 0.0061222000 0.1680410000 977059793 0 402718720 -0.4285498559 0.0178941116 -0.1534879208 302 1311867180.4947559834 0.0779774114 0.0694867977 0.0880135372 0.0061245688 0.1681700000 977062529 0 402718720 -0.4281470776 0.0176609643 -0.1536587179 303 1311867180.5308880806 0.0776790380 0.0695138348 0.0880135372 0.0061154030 0.1795640000 977065601 0 402718720 -0.4272068739 0.0179221034 -0.1536768526 304 1311867180.5629510880 0.0775637403 0.0695403147 0.0880135372 0.0061058181 0.1687140000 977068505 0 402718720 -0.4262376726 0.0180267170 -0.1535137445 305 1311867180.5946910381 0.0774304792 0.0695661841 0.0880135372 0.0060968454 0.1695490000 977071409 0 402718720 -0.4249697626 0.0184106007 -0.1534793079 306 1311867180.6308128834 0.0771973953 0.0695911227 0.0880135372 0.0060877830 0.1696460000 977074425 0 402718720 -0.4240536988 0.0181509666 -0.1533432901 307 1311867180.6640911102 0.0767982528 0.0696145987 0.0880135372 0.0060959966 0.1696860000 977077329 0 402718720 -0.4232427478 0.0184681248 -0.1530973464 308 1311867180.6957859993 0.0768673047 0.0696381465 0.0880135372 0.0060864314 0.1820750000 977080233 0 402718720 -0.4223355055 0.0176123939 -0.1527269334 309 1311867180.7309739590 0.0767657831 0.0696612133 0.0880135372 0.0060822475 0.1861690000 977083249 0 402718720 -0.4209042788 0.0183790419 -0.1526971161 310 1311867180.7650830746 0.0772474259 0.0696856849 0.0880135372 0.0060874210 0.1703180000 977086209 0 402718720 -0.4204030335 0.0181823261 -0.1523406953 311 1311867180.7949280739 0.0771150365 0.0697095735 0.0880135372 0.0060779838 0.1703870000 977089001 0 402718720 -0.4201406240 0.0182144213 -0.1520718634 312 1311867180.8309240341 0.0773719326 0.0697341323 0.0880135372 0.0060688954 0.1694490000 977092073 0 402718720 -0.4191209674 0.0189465936 -0.1516613364 313 1311867180.8652698994 0.0772739798 0.0697582213 0.0880135372 0.0060682236 0.1867950000 977095033 0 402718720 -0.4179604352 0.0179977100 -0.1516922712 314 1311867180.8966469765 0.0770287216 0.0697813758 0.0880135372 0.0060610096 0.1687440000 977097937 0 402718720 -0.4167732596 0.0183497705 -0.1516194195 315 1311867180.9306049347 0.0771666691 0.0698048212 0.0880135372 0.0060779960 0.1687770000 977100897 0 402718720 -0.4162099957 0.0184331480 -0.1514803767 316 1311867180.9631829262 0.0768296346 0.0698270516 0.0880135372 0.0060784533 0.1703300000 977103801 0 402718720 -0.4155341983 0.0181926433 -0.1514209062 317 1311867180.9948179722 0.0772972628 0.0698506169 0.0880135372 0.0060698361 0.1707920000 977106649 0 402718720 -0.4137036800 0.0187218506 -0.1509275883 318 1311867181.0308310986 0.0777600482 0.0698754893 0.0880135372 0.0060626360 0.1783290000 977109665 0 402718720 -0.4120624065 0.0174007323 -0.1506580263 319 1311867181.0627830029 0.0777600557 0.0699002058 0.0880135372 0.0060613766 0.1709440000 977112625 0 402718720 -0.4101603627 0.0171786323 -0.1504526287 320 1311867181.0948719978 0.0779214352 0.0699252722 0.0880135372 0.0060601349 0.1719280000 977115529 0 402718720 -0.4072998762 0.0173148960 -0.1503020227 321 1311867181.1311910152 0.0777465925 0.0699496377 0.0880135372 0.0060525228 0.1717960000 977118545 0 402718720 -0.4044643641 0.0177512877 -0.1503093392 322 1311867181.1629528999 0.0769449696 0.0699713623 0.0880135372 0.0060543594 0.1841250000 977121449 0 402718720 -0.4034133255 0.0170975477 -0.1505074352 323 1311867181.1972830296 0.0765156820 0.0699916234 0.0880135372 0.0060454768 0.1838120000 977124409 0 402718720 -0.4015905261 0.0166493412 -0.1504975110 324 1311867181.2342460155 0.0761779472 0.0700107169 0.0880135372 0.0060386467 0.1706890000 977127481 0 402718720 -0.3997582793 0.0162665211 -0.1506875008 325 1311867181.2629361153 0.0763414055 0.0700301960 0.0880135372 0.0060297136 0.1705950000 977130273 0 402718720 -0.3979012072 0.0163216237 -0.1504152715 326 1311867181.2948091030 0.0763941780 0.0700497174 0.0880135372 0.0060208584 0.1705850000 977133121 0 402718720 -0.3960472047 0.0167317912 -0.1503653079 327 1311867181.3317139149 0.0763243288 0.0700689058 0.0880135372 0.0060171315 0.1709190000 977136193 0 402718720 -0.3942027092 0.0166846458 -0.1504254490 328 1311867181.3626708984 0.0766715631 0.0700890359 0.0880135372 0.0060197971 0.1831610000 977139041 0 402718720 -0.3923349977 0.0183388945 -0.1499027014 329 1311867181.3948218822 0.0765969679 0.0701088168 0.0880135372 0.0060122392 0.1718630000 977141945 0 402718720 -0.3911187351 0.0171161368 -0.1498526335 330 1311867181.4308950901 0.0757989287 0.0701260596 0.0880135372 0.0060038222 0.1722290000 977144849 0 402718720 -0.3900893331 0.0167909972 -0.1497573555 331 1311867181.4628310204 0.0759042725 0.0701435164 0.0880135372 0.0059995754 0.1725320000 977147753 0 402718720 -0.3878114223 0.0160934050 -0.1492833346 332 1311867181.4963610172 0.0761388391 0.0701615746 0.0880135372 0.0060102185 0.1853480000 977150713 0 402718720 -0.3844894171 0.0160911661 -0.1492897868 333 1311867181.5359110832 0.0756616592 0.0701780914 0.0880135372 0.0060053385 0.1723340000 977153785 0 402718720 -0.3831543624 0.0156612843 -0.1490214318 334 1311867181.5671720505 0.0750634596 0.0701927182 0.0880135372 0.0060004562 0.1694150000 977156633 0 402718720 -0.3818522692 0.0150740203 -0.1493279636 335 1311867181.5948610306 0.0751682520 0.0702075706 0.0880135372 0.0059968337 0.1719530000 977159369 0 402718720 -0.3801421523 0.0160611235 -0.1493449509 336 1311867181.6313591003 0.0757150874 0.0702239620 0.0880135372 0.0059958933 0.1722450000 977162441 0 402718720 -0.3780645728 0.0153761879 -0.1494218260 337 1311867181.6628570557 0.0751512200 0.0702385829 0.0880135372 0.0059909706 0.1721440000 977165345 0 402718720 -0.3767601550 0.0139370691 -0.1498784870 338 1311867181.6949229240 0.0748666525 0.0702522755 0.0880135372 0.0059838709 0.1774850000 977168193 0 402718720 -0.3756312132 0.0142906616 -0.1501374543 339 1311867181.7310829163 0.0752365664 0.0702669784 0.0880135372 0.0059890799 0.1728330000 977171209 0 402718720 -0.3734745979 0.0134276329 -0.1504198909 340 1311867181.7634840012 0.0746416077 0.0702798449 0.0880135372 0.0059807887 0.1726270000 977174169 0 402718720 -0.3724344671 0.0122139137 -0.1509252340 341 1311867181.7948980331 0.0741980895 0.0702913354 0.0880135372 0.0059802232 0.1723010000 977176961 0 402718720 -0.3705860078 0.0124895666 -0.1510846019 342 1311867181.8308010101 0.0738653392 0.0703017857 0.0880135372 0.0059762029 0.1725330000 977179977 0 402718720 -0.3688919544 0.0111626247 -0.1512200832 343 1311867181.8627979755 0.0739919469 0.0703125442 0.0880135372 0.0059699811 0.1722990000 977182937 0 402718720 -0.3673050106 0.0104009826 -0.1513889432 344 1311867181.8949289322 0.0734867007 0.0703217714 0.0880135372 0.0059644066 0.1720750000 977185785 0 402718720 -0.3653681874 0.0106712924 -0.1511846185 345 1311867181.9307990074 0.0727705881 0.0703288694 0.0880135372 0.0059644261 0.1704930000 977188857 0 402718720 -0.3641879857 0.0101908343 -0.1512309462 346 1311867181.9629189968 0.0722877681 0.0703345310 0.0880135372 0.0059599753 0.1716180000 977191761 0 402718720 -0.3625175655 0.0097888913 -0.1510754973 347 1311867181.9955599308 0.0717929080 0.0703387338 0.0880135372 0.0059788552 0.1711850000 977194665 0 402718720 -0.3611818254 0.0089082886 -0.1503899544 348 1311867182.0320639610 0.0718662888 0.0703431233 0.0880135372 0.0059712041 0.1860590000 977197681 0 402718720 -0.3588408530 0.0081931138 -0.1500401199 349 1311867182.0629000664 0.0718357340 0.0703474001 0.0880135372 0.0059648439 0.1713580000 977200585 0 402718720 -0.3570707738 0.0081389314 -0.1496679038 350 1311867182.0948839188 0.0724021867 0.0703532709 0.0880135372 0.0059674784 0.1714090000 977203433 0 402718720 -0.3551039994 0.0076695541 -0.1494358480 351 1311867182.1314840317 0.0725210235 0.0703594469 0.0880135372 0.0059597493 0.1713190000 977206505 0 402718720 -0.3533980548 0.0074226870 -0.1488921940 352 1311867182.1629920006 0.0719205290 0.0703638818 0.0880135372 0.0059524020 0.1708700000 977209409 0 402718720 -0.3520153165 0.0076991832 -0.1486719847 353 1311867182.1994500160 0.0714395121 0.0703669289 0.0880135372 0.0059479925 0.1811330000 977212369 0 402718720 -0.3512918949 0.0072213253 -0.1482095867 354 1311867182.2307739258 0.0712726563 0.0703694874 0.0880135372 0.0059447980 0.1706550000 977215217 0 402718720 -0.3499933481 0.0067127566 -0.1477989852 355 1311867182.2629120350 0.0711595714 0.0703717130 0.0880135372 0.0059410541 0.1707420000 977218177 0 402718720 -0.3489395976 0.0066969884 -0.1472631991 356 1311867182.2973539829 0.0713393912 0.0703744312 0.0880135372 0.0059377438 0.2150610000 977221137 0 402718720 -0.3472340703 0.0053608827 -0.1471528411 357 1311867182.3308460712 0.0710383505 0.0703762909 0.0880135372 0.0059541182 0.2075590000 977224041 0 402718720 -0.3463455141 0.0051179510 -0.1465744972 358 1311867182.3629670143 0.0704574883 0.0703765177 0.0880135372 0.0059736910 0.2075170000 977227001 0 402718720 -0.3456708193 0.0047190222 -0.1461038589 359 1311867182.3990368843 0.0703364685 0.0703764062 0.0880135372 0.0059722691 0.2082370000 977229961 0 402718720 -0.3443926573 0.0037312666 -0.1456464082 360 1311867182.4308118820 0.0701519847 0.0703757828 0.0880135372 0.0059702644 0.2075220000 977232865 0 402718720 -0.3435476422 0.0020967834 -0.1456325650 361 1311867182.4629440308 0.0691075772 0.0703722698 0.0880135372 0.0059675880 0.2070490000 977235825 0 402718720 -0.3430172205 0.0018312987 -0.1456403583 362 1311867182.4969599247 0.0685539618 0.0703672468 0.0880135372 0.0059646891 0.2066480000 977238729 0 402718720 -0.3424157202 0.0005491076 -0.1455448270 363 1311867182.5309500694 0.0679025427 0.0703604570 0.0880135372 0.0059580862 0.2064720000 977241689 0 402718720 -0.3414614499 -0.0004962463 -0.1460492760 364 1311867182.5629699230 0.0670967624 0.0703514908 0.0880135372 0.0059550559 0.2046010000 977244593 0 402718720 -0.3403379023 -0.0005964012 -0.1463609189 365 1311867182.6036369801 0.0634408966 0.0703325577 0.0880135372 0.0059514405 0.1685220000 977247721 0 402718720 -0.3421335816 -0.0011612031 -0.1474237144 366 1311867182.6308450699 0.0624600463 0.0703110481 0.0880135372 0.0059676868 0.1808000000 977250457 0 402718720 -0.3420755565 -0.0021355827 -0.1478949338 367 1311867182.6635921001 0.0620299466 0.0702884838 0.0880135372 0.0059602784 0.1668500000 977253417 0 402718720 -0.3406659067 -0.0024593207 -0.1480706185 368 1311867182.6970019341 0.0612754039 0.0702639917 0.0880135372 0.0059594997 0.1891710000 977256321 0 402718720 -0.3392799795 -0.0030777480 -0.1483682990 369 1311867182.7330639362 0.0606929101 0.0702380538 0.0880135372 0.0059546051 0.1675690000 977259337 0 402718720 -0.3371020854 -0.0035551344 -0.1488563865 370 1311867182.7631130219 0.0606947728 0.0702122611 0.0880135372 0.0059489167 0.1658300000 977262073 0 402718720 -0.3352985382 -0.0037503252 -0.1487789601 371 1311867182.7970550060 0.0600019693 0.0701847401 0.0880135372 0.0059410442 0.1660650000 977265089 0 402718720 -0.3342423141 -0.0048597162 -0.1489540190 372 1311867182.8306989670 0.0594845116 0.0701559761 0.0880135372 0.0059344015 0.1654640000 977267993 0 402718720 -0.3326561153 -0.0054306658 -0.1492175162 373 1311867182.8641169071 0.0582514443 0.0701240605 0.0880135372 0.0059312494 0.1767190000 977270897 0 402718720 -0.3315493464 -0.0056390045 -0.1492611021 374 1311867182.8969969749 0.0585610531 0.0700931433 0.0880135372 0.0059235204 0.1793570000 977273857 0 402718720 -0.3291550577 -0.0062273373 -0.1490598321 375 1311867182.9318990707 0.0590073578 0.0700635812 0.0880135372 0.0059163519 0.1669440000 977276817 0 402718720 -0.3263218701 -0.0057033757 -0.1489181966 376 1311867182.9630720615 0.0592338033 0.0700347786 0.0880135372 0.0059086914 0.1671780000 977279721 0 402718720 -0.3239872456 -0.0056002815 -0.1486191303 377 1311867182.9983949661 0.0590042435 0.0700055199 0.0880135372 0.0059175649 0.1672920000 977282681 0 402718720 -0.3231107593 -0.0062631993 -0.1482184380 378 1311867183.0308830738 0.0587264858 0.0699756812 0.0880135372 0.0059100529 0.1834690000 977285585 0 402718720 -0.3215089440 -0.0069236076 -0.1478034556 379 1311867183.0628600121 0.0591271445 0.0699470571 0.0880135372 0.0059031236 0.1681760000 977288545 0 402718720 -0.3187092841 -0.0062229736 -0.1474403292 380 1311867183.1000499725 0.0584206954 0.0699167246 0.0880135372 0.0059268616 0.1673610000 977291505 0 402718720 -0.3172458410 -0.0072166487 -0.1471152902 381 1311867183.1344780922 0.0580936074 0.0698856928 0.0880135372 0.0059221267 0.1671320000 977294521 0 402718720 -0.3158302307 -0.0069448799 -0.1467187852 382 1311867183.1673240662 0.0581855774 0.0698550642 0.0880135372 0.0059165355 0.1686080000 977297481 0 402718720 -0.3140343130 -0.0062990058 -0.1461821049 383 1311867183.2004919052 0.0578448549 0.0698237059 0.0880135372 0.0059111123 0.1800490000 977300385 0 402718720 -0.3132796288 -0.0075433934 -0.1456306130 384 1311867183.2311279774 0.0581881590 0.0697934050 0.0880135372 0.0059037628 0.1688530000 977303233 0 402718720 -0.3116008341 -0.0080291815 -0.1451972276 385 1311867183.2633349895 0.0584437624 0.0697639254 0.0880135372 0.0058976448 0.1693660000 977306193 0 402718720 -0.3094722629 -0.0077857375 -0.1449197978 386 1311867183.2991099358 0.0581849739 0.0697339282 0.0880135372 0.0058922209 0.1687390000 977309153 0 402718720 -0.3085642457 -0.0092804432 -0.1449024826 387 1311867183.3320920467 0.0581829622 0.0697040807 0.0880135372 0.0058932286 0.1683840000 977312113 0 402718720 -0.3070362806 -0.0090497797 -0.1447658092 388 1311867183.3695240021 0.0578862801 0.0696736224 0.0880135372 0.0058857520 0.1677160000 977315185 0 402718720 -0.3057734668 -0.0094010672 -0.1444445401 389 1311867183.3986210823 0.0576463751 0.0696427041 0.0880135372 0.0058796114 0.1679860000 977317977 0 402718720 -0.3046149611 -0.0107079633 -0.1447758526 390 1311867183.4311549664 0.0573627129 0.0696112169 0.0880135372 0.0058880835 0.1675230000 977320881 0 402718720 -0.3032504618 -0.0104262866 -0.1445768774 391 1311867183.4667448997 0.0574023500 0.0695799922 0.0880135372 0.0058859199 0.1681250000 977323897 0 402718720 -0.3011536598 -0.0103650726 -0.1441524178 392 1311867183.4988338947 0.0566095114 0.0695469042 0.0880135372 0.0059101338 0.1676690000 977326857 0 402718720 -0.2999104261 -0.0116460491 -0.1442678124 393 1311867183.5321829319 0.0565489382 0.0695138305 0.0880135372 0.0059033415 0.1803760000 977329761 0 402718720 -0.2981010675 -0.0122156031 -0.1439382881 394 1311867183.5661609173 0.0562266074 0.0694801066 0.0880135372 0.0058971894 0.1686760000 977332721 0 402718720 -0.2965771258 -0.0116928769 -0.1435221434 395 1311867183.5985479355 0.0559863225 0.0694459451 0.0880135372 0.0058940337 0.1692620000 977335625 0 402718720 -0.2944832146 -0.0127028981 -0.1433521807 396 1311867183.6310880184 0.0559772030 0.0694119332 0.0880135372 0.0059090074 0.1814790000 977338529 0 402718720 -0.2927377820 -0.0131315337 -0.1428961009 397 1311867183.6649260521 0.0554209799 0.0693766915 0.0880135372 0.0059042825 0.1693310000 977341489 0 402718720 -0.2913706303 -0.0135043468 -0.1421834975 398 1311867183.6993949413 0.0559204370 0.0693428818 0.0880135372 0.0058974251 0.1915730000 977344505 0 402718720 -0.2886657119 -0.0145091079 -0.1417428702 399 1311867183.7308928967 0.0553365089 0.0693077781 0.0880135372 0.0058952081 0.1688320000 977347297 0 402718720 -0.2871811986 -0.0145915393 -0.1413307786 400 1311867183.7676479816 0.0551444702 0.0692723698 0.0880135372 0.0058993007 0.1686060000 977350369 0 402718720 -0.2844740152 -0.0150854075 -0.1407018751 401 1311867183.7971870899 0.0548183173 0.0692363248 0.0880135372 0.0058919433 0.1693560000 977353161 0 402718720 -0.2832554877 -0.0158872567 -0.1400518417 402 1311867183.8309071064 0.0549370311 0.0692007544 0.0880135372 0.0058848251 0.1681020000 977356065 0 402718720 -0.2812636197 -0.0166192260 -0.1393226534 403 1311867183.8655049801 0.0548590906 0.0691651672 0.0880135372 0.0058799829 0.1803800000 977359025 0 402718720 -0.2792955339 -0.0178559572 -0.1391632110 404 1311867183.8970971107 0.0546989851 0.0691293598 0.0880135372 0.0058731536 0.1685050000 977361873 0 402718720 -0.2779462636 -0.0181663707 -0.1387927085 405 1311867183.9314939976 0.0542014055 0.0690925006 0.0880135372 0.0058663815 0.1676170000 977364889 0 402718720 -0.2770530581 -0.0184500869 -0.1381161809 406 1311867183.9658319950 0.0539700128 0.0690552531 0.0880135372 0.0058659514 0.1687090000 977367793 0 402718720 -0.2751951516 -0.0193211585 -0.1379585564 407 1311867183.9966781139 0.0536168180 0.0690173209 0.0880135372 0.0058613247 0.1682140000 977370697 0 402718720 -0.2743238211 -0.0200280901 -0.1374614388 408 1311867184.0309689045 0.0537586212 0.0689799221 0.0880135372 0.0058841832 0.1772270000 977373657 0 402718720 -0.2733679414 -0.0202389341 -0.1369497329 409 1311867184.0647850037 0.0537686199 0.0689427306 0.0880135372 0.0058799158 0.1789840000 977376617 0 402718720 -0.2718361020 -0.0212788526 -0.1364712417 410 1311867184.0968890190 0.0534329861 0.0689049020 0.0880135372 0.0058729310 0.1671990000 977379465 0 402718720 -0.2705372572 -0.0216386765 -0.1359615028 411 1311867184.1312260628 0.0535890386 0.0688676371 0.0880135372 0.0058661404 0.1665400000 977382425 0 402718720 -0.2688295245 -0.0216177925 -0.1353092045 412 1311867184.1650640965 0.0531257838 0.0688294287 0.0880135372 0.0058597104 0.1676120000 977385329 0 402718720 -0.2676997483 -0.0226777922 -0.1350567788 413 1311867184.1969559193 0.0531467162 0.0687914561 0.0880135372 0.0058540370 0.1950500000 977388289 0 402718720 -0.2656212449 -0.0222475454 -0.1345906854 414 1311867184.2309360504 0.0535427816 0.0687546235 0.0880135372 0.0058472623 0.1688850000 977391249 0 402718720 -0.2631666958 -0.0220805947 -0.1339231580 415 1311867184.2681369781 0.0524482131 0.0687153310 0.0880135372 0.0058439864 0.1810520000 977394321 0 402718720 -0.2623436749 -0.0234705471 -0.1337964684 416 1311867184.2983899117 0.0524576306 0.0686762499 0.0880135372 0.0058387717 0.1677790000 977397169 0 402718720 -0.2606483102 -0.0230381768 -0.1332181990 417 1311867184.3314700127 0.0526569597 0.0686378344 0.0880135372 0.0058318820 0.1669130000 977400073 0 402718720 -0.2578550875 -0.0226491671 -0.1327028722 418 1311867184.3697841167 0.0518446639 0.0685976593 0.0880135372 0.0058336610 0.1790470000 977403145 0 402718720 -0.2564842999 -0.0238963384 -0.1325822473 419 1311867184.4000220299 0.0519516282 0.0685579313 0.0880135372 0.0058726407 0.1680630000 977405993 0 402718720 -0.2544922829 -0.0237023272 -0.1321430653 420 1311867184.4310610294 0.0532555357 0.0685214971 0.0880135372 0.0058692865 0.1693400000 977408897 0 402718720 -0.2508350313 -0.0231982283 -0.1316410303 421 1311867184.4655809402 0.0523194112 0.0684830123 0.0880135372 0.0058649423 0.1683240000 977411857 0 402718720 -0.2502671778 -0.0249547437 -0.1317768246 422 1311867184.5037670135 0.0516485460 0.0684431202 0.0880135372 0.0059048847 0.1678260000 977414929 0 402718720 -0.2484128177 -0.0260319747 -0.1320699900 423 1311867184.5310881138 0.0521338694 0.0684045640 0.0880135372 0.0059288169 0.1798920000 977417721 0 402718720 -0.2458027899 -0.0253974665 -0.1325742453 424 1311867184.5682930946 0.0515287891 0.0683647627 0.0880135372 0.0059233023 0.1688350000 977420793 0 402718720 -0.2435111701 -0.0256933756 -0.1330616027 425 1311867184.6018071175 0.0503598563 0.0683223982 0.0880135372 0.0059167275 0.1921440000 977423697 0 402718720 -0.2420627326 -0.0267952271 -0.1334952861 426 1311867184.6367399693 0.0496124700 0.0682784782 0.0880135372 0.0059108597 0.1786130000 977426713 0 402718720 -0.2405670434 -0.0269405972 -0.1328971833 427 1311867184.6662440300 0.0493405238 0.0682341270 0.0880135372 0.0059186158 0.1674720000 977429505 0 402718720 -0.2377828211 -0.0280390400 -0.1326207519 428 1311867184.6994929314 0.0487606972 0.0681886283 0.0880135372 0.0059147252 0.1898590000 977432521 0 402718720 -0.2356786132 -0.0294521134 -0.1324535161 429 1311867184.7359158993 0.0484113134 0.0681425274 0.0880135372 0.0059166585 0.1667710000 977435425 0 402718720 -0.2332599759 -0.0291918050 -0.1317180097 430 1311867184.7690689564 0.0484134816 0.0680966459 0.0880135372 0.0059156420 0.1658100000 977438441 0 402718720 -0.2313255072 -0.0307724457 -0.1308433861 431 1311867184.8001279831 0.0478974730 0.0680497800 0.0880135372 0.0059142269 0.1655540000 977441289 0 402718720 -0.2291068137 -0.0312537886 -0.1300916672 432 1311867184.8348441124 0.0477454439 0.0680027793 0.0880135372 0.0059078703 0.1649700000 977444193 0 402718720 -0.2262626439 -0.0312733054 -0.1290766746 433 1311867184.8690660000 0.0469510891 0.0679541610 0.0880135372 0.0059013956 0.1661290000 977447153 0 402718720 -0.2243709564 -0.0323677100 -0.1282235533 434 1311867184.9055209160 0.0464118049 0.0679045243 0.0880135372 0.0058962599 0.1657220000 977450057 0 402718720 -0.2216031849 -0.0329161622 -0.1271166503 435 1311867184.9332280159 0.0466984175 0.0678557746 0.0880135372 0.0058911967 0.1636620000 977452793 0 402718720 -0.2182751298 -0.0328156762 -0.1254838258 436 1311867184.9656410217 0.0464400351 0.0678066559 0.0880135372 0.0058903916 0.1653050000 977455697 0 402718720 -0.2161756903 -0.0342451744 -0.1240828782 437 1311867184.9983251095 0.0458113328 0.0677563234 0.0880135372 0.0058889437 0.1648110000 977458657 0 402718720 -0.2133870572 -0.0352681614 -0.1228047684 438 1311867185.0360550880 0.0456990786 0.0677059644 0.0880135372 0.0058826777 0.1823850000 977461673 0 402718720 -0.2099223435 -0.0355281606 -0.1210674867 439 1311867185.0652348995 0.0455354378 0.0676554620 0.0880135372 0.0058784192 0.1659650000 977464521 0 402718720 -0.2076392472 -0.0366510451 -0.1196362972 440 1311867185.0991280079 0.0443008617 0.0676023834 0.0880135372 0.0058737985 0.1655160000 977467481 0 402718720 -0.2061370164 -0.0366374888 -0.1182198375 441 1311867185.1360778809 0.0439699590 0.0675487951 0.0880135372 0.0058710601 0.1656490000 977470497 0 402718720 -0.2033338100 -0.0369717255 -0.1162773892 442 1311867185.1648709774 0.0439459831 0.0674953951 0.0880135372 0.0058669604 0.1637580000 977473345 0 402718720 -0.2004453838 -0.0381028764 -0.1145713478 443 1311867185.2000720501 0.0437208526 0.0674417280 0.0880135372 0.0058620157 0.1757080000 977476249 0 402718720 -0.1971258223 -0.0382169858 -0.1127869487 444 1311867185.2342920303 0.0442241579 0.0673894362 0.0880135372 0.0058637446 0.1652450000 977479265 0 402718720 -0.1936667711 -0.0382839255 -0.1107127070 445 1311867185.2663950920 0.0438875780 0.0673366230 0.0880135372 0.0058573975 0.1653160000 977482225 0 402718720 -0.1910800338 -0.0403265692 -0.1091832519 446 1311867185.2970550060 0.0435327590 0.0672832511 0.0880135372 0.0058746912 0.1645650000 977485073 0 402718720 -0.1880505234 -0.0405053720 -0.1076359972 447 1311867185.3360140324 0.0436067432 0.0672302835 0.0880135372 0.0058682507 0.1631460000 977488145 0 402718720 -0.1852170825 -0.0408799388 -0.1058861241 448 1311867185.3681778908 0.0435942672 0.0671775245 0.0880135372 0.0058622559 0.1775690000 977491105 0 402718720 -0.1819774061 -0.0421161316 -0.1046866104 449 1311867185.4036509991 0.0431931764 0.0671241073 0.0880135372 0.0058597533 0.1640110000 977494065 0 402718720 -0.1792492867 -0.0425665528 -0.1034632698 450 1311867185.4386389256 0.0435765646 0.0670717794 0.0880135372 0.0058538478 0.1644630000 977497025 0 402718720 -0.1757576168 -0.0423278734 -0.1019720733 451 1311867185.4655449390 0.0445073433 0.0670217474 0.0880135372 0.0058476659 0.1628810000 977499761 0 402718720 -0.1733415574 -0.0435604416 -0.1008949205 452 1311867185.5013909340 0.0442232005 0.0669713081 0.0880135372 0.0058577112 0.1641630000 977502777 0 402718720 -0.1703387499 -0.0447063670 -0.1001296490 453 1311867185.5336329937 0.0442666635 0.0669211875 0.0880135372 0.0058740576 0.1631080000 977505681 0 402718720 -0.1676972359 -0.0442466512 -0.0989833400 454 1311867185.5666799545 0.0441555306 0.0668710429 0.0880135372 0.0058680786 0.1616980000 977508641 0 402718720 -0.1661678255 -0.0453510284 -0.0981743336 455 1311867185.5970540047 0.0437692218 0.0668202697 0.0880135372 0.0058673767 0.1760950000 977511489 0 402718720 -0.1632540822 -0.0466192961 -0.0978246555 456 1311867185.6329469681 0.0436024107 0.0667693533 0.0880135372 0.0058896016 0.1618670000 977514505 0 402718720 -0.1610375941 -0.0461497530 -0.0968511328 457 1311867185.6664180756 0.0435423516 0.0667185284 0.0880135372 0.0058903353 0.1616500000 977517409 0 402718720 -0.1575848907 -0.0467287078 -0.0960379317 458 1311867185.6973390579 0.0430693030 0.0666668925 0.0880135372 0.0058839065 0.1903800000 977520313 0 402718720 -0.1545939744 -0.0475575551 -0.0953770503 459 1311867185.7351899147 0.0431245193 0.0666156019 0.0880135372 0.0058796500 0.1613740000 977523329 0 402718720 -0.1513513327 -0.0471831337 -0.0938031450 460 1311867185.7649769783 0.0434800424 0.0665653072 0.0880135372 0.0058744413 0.1614490000 977526233 0 402718720 -0.1487585902 -0.0486403368 -0.0925280377 461 1311867185.7989649773 0.0435704067 0.0665154268 0.0880135372 0.0058802162 0.1592470000 977529137 0 402718720 -0.1457691938 -0.0498540737 -0.0917061269 462 1311867185.8327999115 0.0435946770 0.0664658147 0.0880135372 0.0058755457 0.1730000000 977532153 0 402718720 -0.1424414217 -0.0496325232 -0.0905919001 463 1311867185.8649098873 0.0436514765 0.0664165397 0.0880135372 0.0058701483 0.1710310000 977535057 0 402718720 -0.1394680589 -0.0507670119 -0.0894417465 464 1311867185.9030420780 0.0427713618 0.0663655803 0.0880135372 0.0058651353 0.1739080000 977538073 0 402718720 -0.1370432526 -0.0516735725 -0.0885759741 465 1311867185.9396789074 0.0426407717 0.0663145592 0.0880135372 0.0058606041 0.1628540000 977541145 0 402718720 -0.1348685771 -0.0517536066 -0.0870083943 466 1311867185.9650609493 0.0431696624 0.0662648920 0.0880135372 0.0058728696 0.1633260000 977543769 0 402718720 -0.1319553256 -0.0535634905 -0.0859656408 467 1311867186.0039470196 0.0431038439 0.0662152966 0.0880135372 0.0058692932 0.1611810000 977546897 0 402718720 -0.1292132139 -0.0545493178 -0.0850189254 468 1311867186.0396919250 0.0434274003 0.0661666045 0.0880135372 0.0058724873 0.1835250000 977549913 0 402718720 -0.1270099729 -0.0543164760 -0.0836628303 469 1311867186.0653240681 0.0437368490 0.0661187799 0.0880135372 0.0058746795 0.1642850000 977552705 0 402718720 -0.1254225224 -0.0560051240 -0.0827378780 470 1311867186.1047339439 0.0430033058 0.0660695980 0.0880135372 0.0058691614 0.1642750000 977555777 0 402718720 -0.1240649521 -0.0574193746 -0.0822158009 471 1311867186.1361179352 0.0440767854 0.0660229042 0.0880135372 0.0058648989 0.1647440000 977558625 0 402718720 -0.1206832901 -0.0579627119 -0.0813643783 472 1311867186.1649448872 0.0440271795 0.0659763031 0.0880135372 0.0058602628 0.1640040000 977561473 0 402718720 -0.1192084625 -0.0593090802 -0.0808920115 473 1311867186.2044749260 0.0438537709 0.0659295324 0.0880135372 0.0058541352 0.1758860000 977564601 0 402718720 -0.1169128641 -0.0599857494 -0.0805299655 474 1311867186.2359659672 0.0439426266 0.0658831465 0.0880135372 0.0058499524 0.1648360000 977567449 0 402718720 -0.1150393859 -0.0603293143 -0.0797676221 475 1311867186.2674899101 0.0435846075 0.0658362022 0.0880135372 0.0058439888 0.1648150000 977570353 0 402718720 -0.1139882728 -0.0614477992 -0.0791257843 476 1311867186.3030838966 0.0431494191 0.0657885409 0.0880135372 0.0058396855 0.1647140000 977573369 0 402718720 -0.1119805947 -0.0617690980 -0.0784846172 477 1311867186.3349270821 0.0434743576 0.0657417606 0.0880135372 0.0058355762 0.1776040000 977576217 0 402718720 -0.1089337245 -0.0619501434 -0.0773029998 478 1311867186.3670160770 0.0430073477 0.0656941991 0.0880135372 0.0058361681 0.1900660000 977579065 0 402718720 -0.1076115966 -0.0637218282 -0.0765970126 479 1311867186.4019849300 0.0429143421 0.0656466420 0.0880135372 0.0058405017 0.1645260000 977582025 0 402718720 -0.1055173278 -0.0639599189 -0.0756463334 480 1311867186.4360210896 0.0434405990 0.0656003794 0.0880135372 0.0058389362 0.1651970000 977584985 0 402718720 -0.1025832370 -0.0636667758 -0.0739596114 481 1311867186.4659481049 0.0433688276 0.0655541600 0.0880135372 0.0058350094 0.1655780000 977587833 0 402718720 -0.1013302729 -0.0654791594 -0.0727949440 482 1311867186.5031139851 0.0427395143 0.0655068267 0.0880135372 0.0058301855 0.1650080000 977590905 0 402718720 -0.0997287408 -0.0665554255 -0.0719591603 483 1311867186.5363171101 0.0437428355 0.0654617667 0.0880135372 0.0058254006 0.1771580000 977593809 0 402718720 -0.0967175066 -0.0661740825 -0.0703678727 484 1311867186.5651130676 0.0439612269 0.0654173441 0.0880135372 0.0058252868 0.1660510000 977596657 0 402718720 -0.0951533839 -0.0676044151 -0.0696753785 485 1311867186.6014220715 0.0438787639 0.0653729346 0.0880135372 0.0058197068 0.1879480000 977599673 0 402718720 -0.0937077180 -0.0685367435 -0.0694399476 486 1311867186.6362628937 0.0442683883 0.0653295096 0.0880135372 0.0058137373 0.1660980000 977602633 0 402718720 -0.0916742086 -0.0689365119 -0.0692028627 487 1311867186.6650478840 0.0448446162 0.0652874462 0.0880135372 0.0058101172 0.1636350000 977605425 0 402718720 -0.0899617299 -0.0686561167 -0.0689354762 488 1311867186.7043809891 0.0447138399 0.0652452871 0.0880135372 0.0058241334 0.1818960000 977608609 0 402718720 -0.0882755965 -0.0690170228 -0.0692188814 489 1311867186.7337749004 0.0450457893 0.0652039794 0.0880135372 0.0058263901 0.1644790000 977611401 0 402718720 -0.0863177776 -0.0677866042 -0.0693642199 490 1311867186.7673180103 0.0455556959 0.0651638808 0.0880135372 0.0058215468 0.1660660000 977614361 0 402718720 -0.0843229443 -0.0671032816 -0.0692725182 491 1311867186.8047299385 0.0453810766 0.0651235900 0.0880135372 0.0058223551 0.1654300000 977617433 0 402718720 -0.0828634053 -0.0680418387 -0.0699666142 492 1311867186.8340749741 0.0452578552 0.0650832125 0.0880135372 0.0058207605 0.1645560000 977620225 0 402718720 -0.0815190077 -0.0667120814 -0.0702263415 493 1311867186.8775999546 0.0453901291 0.0650432671 0.0880135372 0.0058152937 0.1769590000 977623465 0 402718720 -0.0790119395 -0.0652407408 -0.0703094900 494 1311867186.9052100182 0.0454054773 0.0650035145 0.0880135372 0.0058108697 0.1644010000 977626201 0 402718720 -0.0776228979 -0.0648909956 -0.0704913586 495 1311867186.9334239960 0.0452667139 0.0649636422 0.0880135372 0.0058058609 0.1639440000 977629105 0 402718720 -0.0759083927 -0.0643909797 -0.0706992522 496 1311867186.9663379192 0.0458159447 0.0649250379 0.0880135372 0.0058075362 0.1770000000 977631953 0 402718720 -0.0733761489 -0.0624414198 -0.0704776272 497 1311867187.0017139912 0.0459715798 0.0648869022 0.0880135372 0.0058084544 0.1650560000 977634801 0 402718720 -0.0709419325 -0.0621800683 -0.0706425682 498 1311867187.0336461067 0.0455440059 0.0648480610 0.0880135372 0.0058117977 0.1637230000 977637705 0 402718720 -0.0691402107 -0.0612874255 -0.0710038766 499 1311867187.0749349594 0.0454299562 0.0648091470 0.0880135372 0.0058122542 0.1757470000 977640889 0 402718720 -0.0677482784 -0.0593272485 -0.0706423074 500 1311867187.1016030312 0.0457539037 0.0647710365 0.0880135372 0.0058079293 0.1625090000 977643681 0 402718720 -0.0648071021 -0.0585644171 -0.0704991817 501 1311867187.1342070103 0.0454124361 0.0647323966 0.0880135372 0.0058068324 0.2072600000 977646585 0 402718720 -0.0634379610 -0.0599752739 -0.0708079413 502 1311867187.1710209846 0.0453759469 0.0646938379 0.0880135372 0.0058137958 0.1958410000 977649601 0 402718720 -0.0615238436 -0.0589008853 -0.0707164407 503 1311867187.2041370869 0.0459878631 0.0646566491 0.0880135372 0.0058185252 0.1959870000 977652561 0 402718720 -0.0588028096 -0.0582123660 -0.0707596019 504 1311867187.2331659794 0.0461051427 0.0646198406 0.0880135372 0.0058209598 0.1957060000 977655409 0 402718720 -0.0556244142 -0.0590918846 -0.0714649409 505 1311867187.2707629204 0.0460334346 0.0645830358 0.0880135372 0.0058239982 0.1954410000 977658425 0 402718720 -0.0533767492 -0.0579583757 -0.0717973337 506 1311867187.3015060425 0.0460925512 0.0645464933 0.0880135372 0.0058253589 0.1662040000 977661329 0 402718720 -0.0513486750 -0.0579632893 -0.0721323565 507 1311867187.3336570263 0.0459940992 0.0645099008 0.0880135372 0.0058197622 0.1594200000 977664177 0 402718720 -0.0497623682 -0.0586439222 -0.0728322044 508 1311867187.3707590103 0.0461706221 0.0644737999 0.0880135372 0.0058152403 0.1618030000 977667249 0 402718720 -0.0483642966 -0.0585888773 -0.0732599348 509 1311867187.4033529758 0.0460787974 0.0644376604 0.0880135372 0.0058128537 0.1624790000 977670209 0 402718720 -0.0468823612 -0.0586272404 -0.0738696083 510 1311867187.4335899353 0.0457916856 0.0644010997 0.0880135372 0.0058111940 0.1628490000 977673057 0 402718720 -0.0451881886 -0.0591662973 -0.0744774714 511 1311867187.4763159752 0.0462075435 0.0643654958 0.0880135372 0.0058074502 0.1610740000 977676241 0 402718720 -0.0426992290 -0.0588334799 -0.0748939589 512 1311867187.5056400299 0.0465633012 0.0643307259 0.0880135372 0.0058040285 0.1621580000 977679033 0 402718720 -0.0400320217 -0.0593767092 -0.0755360052 513 1311867187.5342190266 0.0468339510 0.0642966192 0.0880135372 0.0058006402 0.1880070000 977681881 0 402718720 -0.0372040346 -0.0598107651 -0.0763985664 514 1311867187.5709679127 0.0469381474 0.0642628478 0.0880135372 0.0057953722 0.1633130000 977787297 0 402718720 -0.0344127044 -0.0600589924 -0.0772937089 515 1311867187.6045789719 0.0458024591 0.0642270024 0.0880135372 0.0058205904 0.1626750000 977790313 0 402718720 -0.0331826247 -0.0601297095 -0.0786258876 516 1311867187.6353919506 0.0458557718 0.0641913992 0.0880135372 0.0058166511 0.1630820000 977793161 0 402718720 -0.0304398537 -0.0605758838 -0.0798380971 517 1311867187.6707689762 0.0457051545 0.0641556425 0.0880135372 0.0058204438 0.1627820000 977796121 0 402718720 -0.0273115449 -0.0596807674 -0.0808529630 518 1311867187.7035770416 0.0461947247 0.0641209689 0.0880135372 0.0058217729 0.1887690000 977799081 0 402718720 -0.0247051772 -0.0593429431 -0.0815408006 519 1311867187.7345480919 0.0454217680 0.0640849396 0.0880135372 0.0058340898 0.1623270000 977801705 0 402718720 -0.0228403136 -0.0610738695 -0.0830293447 520 1311867187.7707819939 0.0453066267 0.0640488275 0.0880135372 0.0058334039 0.1625300000 977804721 0 402718720 -0.0202093720 -0.0596238039 -0.0837689191 521 1311867187.8017508984 0.0457953550 0.0640137920 0.0880135372 0.0058290686 0.1639630000 977807625 0 402718720 -0.0174020790 -0.0589734353 -0.0845209360 522 1311867187.8339610100 0.0454348214 0.0639782001 0.0880135372 0.0058247247 0.1765610000 977810529 0 402718720 -0.0153801590 -0.0589854904 -0.0853802934 523 1311867187.8708090782 0.0452000424 0.0639422954 0.0880135372 0.0058249281 0.1745790000 977813545 0 402718720 -0.0124674682 -0.0580824204 -0.0859471262 524 1311867187.9038810730 0.0456195176 0.0639073283 0.0880135372 0.0058225240 0.1639770000 977816561 0 402718720 -0.0092017874 -0.0574009269 -0.0864766613 525 1311867187.9363000393 0.0458115712 0.0638728602 0.0880135372 0.0058178224 0.1638600000 977819409 0 402718720 -0.0060131419 -0.0570928678 -0.0871994048 526 1311867187.9713420868 0.0455745272 0.0638380725 0.0880135372 0.0058177560 0.1626320000 977822425 0 402718720 -0.0030524081 -0.0578454100 -0.0883773193 527 1311867188.0047569275 0.0454549342 0.0638031899 0.0880135372 0.0058399807 0.1642090000 977825385 0 402718720 -0.0004803875 -0.0568996593 -0.0893836617 528 1311867188.0333108902 0.0455848798 0.0637686855 0.0880135372 0.0058460895 0.1864670000 977828177 0 402718720 0.0025763072 -0.0565090105 -0.0902413428 529 1311867188.0698699951 0.0453381874 0.0637338452 0.0880135372 0.0058405511 0.1648690000 977831137 0 402718720 0.0057233190 -0.0576915070 -0.0916595906 530 1311867188.1088800430 0.0451582596 0.0636987969 0.0880135372 0.0058413477 0.1655100000 977834321 0 402718720 0.0083682537 -0.0578632988 -0.0929647833 531 1311867188.1359970570 0.0439401232 0.0636615866 0.0880135372 0.0058484459 0.1652290000 977837057 0 402718720 0.0120105157 -0.0569713078 -0.0941001028 532 1311867188.1703350544 0.0450431742 0.0636265896 0.0880135372 0.0058456484 0.1651320000 977840017 0 402718720 0.0145106968 -0.0576051362 -0.0953805968 533 1311867188.2026720047 0.0447366536 0.0635911488 0.0880135372 0.0058475821 0.1861590000 977842977 0 402718720 0.0162006244 -0.0581327714 -0.0967580974 534 1311867188.2352449894 0.0436232723 0.0635537558 0.0880135372 0.0058513497 0.2004170000 977845825 0 402718720 0.0186818689 -0.0574550666 -0.0978981555 535 1311867188.2706460953 0.0443058871 0.0635177785 0.0880135372 0.0058486671 0.1996320000 977848841 0 402718720 0.0218890607 -0.0572066829 -0.0990778208 536 1311867188.3047339916 0.0442567207 0.0634818437 0.0880135372 0.0058439654 0.1989560000 977851857 0 402718720 0.0250912849 -0.0570772290 -0.1002011672 537 1311867188.3398799896 0.0441101380 0.0634457697 0.0880135372 0.0058394558 0.1983730000 977854873 0 402718720 0.0272908304 -0.0563118681 -0.1010358930 538 1311867188.3718800545 0.0443879999 0.0634103464 0.0880135372 0.0058387961 0.1974560000 977857721 0 402718720 0.0305916201 -0.0548864007 -0.1015049666 539 1311867188.4054470062 0.0442586914 0.0633748145 0.0880135372 0.0058398163 0.1975030000 977860625 0 402718720 0.0338198096 -0.0543590151 -0.1020712405 540 1311867188.4398789406 0.0441389084 0.0633391925 0.0880135372 0.0058377197 0.1968820000 977863641 0 402718720 0.0371246375 -0.0543389022 -0.1026957557 541 1311867188.4724500179 0.0445048958 0.0633043786 0.0880135372 0.0058404313 0.1971670000 977866545 0 402718720 0.0394828841 -0.0524560586 -0.1028720662 542 1311867188.5049159527 0.0442893282 0.0632692955 0.0880135372 0.0058401811 0.1882110000 977869449 0 402718720 0.0421084389 -0.0515223220 -0.1033066511 543 1311867188.5389990807 0.0441429578 0.0632340721 0.0880135372 0.0058421142 0.1726330000 977872465 0 402718720 0.0447953194 -0.0517832264 -0.1039764732 544 1311867188.5723888874 0.0441273488 0.0631989494 0.0880135372 0.0058604804 0.1613860000 977875369 0 402718720 0.0469339564 -0.0491753928 -0.1041257381 545 1311867188.6045958996 0.0447313152 0.0631650638 0.0880135372 0.0058552474 0.1623110000 977878273 0 402718720 0.0493390672 -0.0485016890 -0.1040599048 546 1311867188.6398339272 0.0449436605 0.0631316913 0.0880135372 0.0058517405 0.1606980000 977881177 0 402718720 0.0508977175 -0.0489047505 -0.1045989767 547 1311867188.6715080738 0.0454805642 0.0630994223 0.0880135372 0.0058517813 0.1597470000 977884137 0 402718720 0.0537059754 -0.0479115807 -0.1050463989 548 1311867188.7038300037 0.0455052182 0.0630673161 0.0880135372 0.0058511171 0.1732180000 977887041 0 402718720 0.0548495241 -0.0481769852 -0.1059144288 549 1311867188.7393829823 0.0453692451 0.0630350792 0.0880135372 0.0058561954 0.1587590000 977890001 0 402718720 0.0561322756 -0.0487563647 -0.1071174890 550 1311867188.7721049786 0.0455357172 0.0630032622 0.0880135372 0.0058522711 0.1565890000 977892961 0 402718720 0.0570463203 -0.0476018749 -0.1081696153 551 1311867188.8045220375 0.0463574789 0.0629730520 0.0880135372 0.0058525167 0.1525480000 977895921 0 402718720 0.0592097677 -0.0462383069 -0.1089596599 552 1311867188.8402431011 0.0471728221 0.0629444284 0.0880135372 0.0058509497 0.1525160000 977898881 0 402718720 0.0614253134 -0.0469492674 -0.1099054888 553 1311867188.8705990314 0.0476781167 0.0629168221 0.0880135372 0.0058481080 0.1497980000 977901729 0 402718720 0.0631208569 -0.0465279520 -0.1108795553 554 1311867188.9016311169 0.0477611572 0.0628894653 0.0880135372 0.0058446198 0.1487240000 977904633 0 402718720 0.0657915920 -0.0451859049 -0.1119529828 555 1311867188.9401769638 0.0483182222 0.0628632108 0.0880135372 0.0058430780 0.1480280000 977907761 0 402718720 0.0695255101 -0.0457584895 -0.1131183580 556 1311867188.9709990025 0.0483368523 0.0628370843 0.0880135372 0.0058423570 0.1462150000 977910553 0 402718720 0.0724124610 -0.0458052456 -0.1139364019 557 1311867189.0052258968 0.0485686064 0.0628114676 0.0880135372 0.0058381153 0.1453680000 977913569 0 402718720 0.0763098598 -0.0449042842 -0.1143394411 558 1311867189.0400099754 0.0489894859 0.0627866970 0.0880135372 0.0058391574 0.1580880000 977916473 0 402718720 0.0789999664 -0.0447543599 -0.1147538275 559 1311867189.0724329948 0.0488292947 0.0627617285 0.0880135372 0.0058378143 0.1441090000 977919489 0 402718720 0.0822022706 -0.0447325781 -0.1149160042 560 1311867189.1026360989 0.0491745919 0.0627374658 0.0880135372 0.0058369926 0.1448440000 977922337 0 402718720 0.0845673680 -0.0437330119 -0.1144092008 561 1311867189.1417639256 0.0494125858 0.0627137137 0.0880135372 0.0058325444 0.1429470000 977925465 0 402718720 0.0869913995 -0.0436836183 -0.1136153936 562 1311867189.1717920303 0.0492333323 0.0626897273 0.0880135372 0.0058293636 0.1433420000 977928313 0 402718720 0.0880164504 -0.0439741910 -0.1128573343 563 1311867189.2019069195 0.0494739898 0.0626662535 0.0880135372 0.0058247619 0.1664870000 977931161 0 402718720 0.0903462470 -0.0437355563 -0.1116978973 564 1311867189.2390630245 0.0495990030 0.0626430846 0.0880135372 0.0058222074 0.1426210000 977934177 0 402718720 0.0910003409 -0.0439311713 -0.1109009087 565 1311867189.2722640038 0.0495438538 0.0626199002 0.0880135372 0.0058175106 0.1437850000 977937081 0 402718720 0.0925597847 -0.0446754433 -0.1100558192 566 1311867189.3046789169 0.0496545248 0.0625969931 0.0880135372 0.0058132126 0.1431130000 977940041 0 402718720 0.0955944657 -0.0452490933 -0.1089539826 567 1311867189.3397970200 0.0491510853 0.0625732790 0.0880135372 0.0058165408 0.1421780000 977943001 0 402718720 0.0972902402 -0.0466597714 -0.1082516983 568 1311867189.3720359802 0.0497467667 0.0625506971 0.0880135372 0.0058537952 0.1702360000 977945905 0 402718720 0.0994267315 -0.0475859568 -0.1074392051 569 1311867189.4056949615 0.0497137196 0.0625281365 0.0880135372 0.0058576066 0.1416800000 977948865 0 402718720 0.1035169065 -0.0472547822 -0.1059664339 570 1311867189.4405019283 0.0495825782 0.0625054250 0.0880135372 0.0058592829 0.1412380000 977951825 0 402718720 0.1061342731 -0.0490228273 -0.1052610055 571 1311867189.4729130268 0.0503105707 0.0624840680 0.0880135372 0.0058555071 0.1405340000 977954785 0 402718720 0.1089265049 -0.0508100875 -0.1045238227 572 1311867189.5060400963 0.0501554459 0.0624625145 0.0880135372 0.0058526169 0.1387840000 977957689 0 402718720 0.1118723378 -0.0512366183 -0.1041618586 573 1311867189.5394289494 0.0502830558 0.0624412589 0.0880135372 0.0058483375 0.1529040000 977960593 0 402718720 0.1153951511 -0.0534665175 -0.1039189100 574 1311867189.5720269680 0.0501100011 0.0624197759 0.0880135372 0.0058463533 0.1395710000 977963553 0 402718720 0.1186187714 -0.0559537150 -0.1044410318 575 1311867189.6112909317 0.0506286845 0.0623992696 0.0880135372 0.0058438975 0.1669290000 977966625 0 402718720 0.1233167425 -0.0563199036 -0.1044403240 576 1311867189.6424219608 0.0508035384 0.0623791381 0.0880135372 0.0058400040 0.1398400000 977969529 0 402718720 0.1263371408 -0.0569601022 -0.1045556366 577 1311867189.6728401184 0.0508730859 0.0623591970 0.0880135372 0.0058352286 0.1403420000 977972433 0 402718720 0.1290629953 -0.0584614165 -0.1048040539 578 1311867189.7065870762 0.0514769256 0.0623403695 0.0880135372 0.0058334883 0.1576060000 977975337 0 402718720 0.1321680248 -0.0589750707 -0.1047185436 579 1311867189.7401719093 0.0513751470 0.0623214313 0.0880135372 0.0058289644 0.1407860000 977978297 0 402718720 0.1366613954 -0.0587978885 -0.1041553617 580 1311867189.7729759216 0.0514763594 0.0623027329 0.0880135372 0.0058239926 0.1420930000 977981201 0 402718720 0.1400298476 -0.0587366484 -0.1038612947 581 1311867189.8073968887 0.0510142148 0.0622833034 0.0880135372 0.0058223990 0.1531780000 977984161 0 402718720 0.1432774514 -0.0597909689 -0.1033477262 582 1311867189.8405311108 0.0511732772 0.0622642140 0.0880135372 0.0058189702 0.1543600000 977987065 0 402718720 0.1472163200 -0.0601881705 -0.1022708789 583 1311867189.8713529110 0.0508553609 0.0622446448 0.0880135372 0.0058150931 0.1644060000 977989969 0 402718720 0.1513283700 -0.0611596853 -0.1014358699 584 1311867189.9102680683 0.0507567637 0.0622249738 0.0880135372 0.0058153927 0.1434150000 977993041 0 402718720 0.1538237333 -0.0627362132 -0.1012495607 585 1311867189.9402260780 0.0504174270 0.0622047900 0.0880135372 0.0058118497 0.1435580000 977995945 0 402718720 0.1577842385 -0.0628468618 -0.1009016410 586 1311867189.9727621078 0.0501135699 0.0621841565 0.0880135372 0.0058069827 0.1438080000 977998849 0 402718720 0.1619312316 -0.0631202012 -0.1005799547 587 1311867190.0107009411 0.0503166616 0.0621639393 0.0880135372 0.0058050244 0.1547200000 978001865 0 402718720 0.1652832776 -0.0637619197 -0.1004947796 588 1311867190.0402929783 0.0504628196 0.0621440394 0.0880135372 0.0058017526 0.1590000000 978004713 0 402718720 0.1681055874 -0.0642201826 -0.1004242748 589 1311867190.0719039440 0.0506531782 0.0621245303 0.0880135372 0.0057973667 0.1435460000 978007617 0 402718720 0.1707300395 -0.0650351867 -0.1004624292 590 1311867190.1096539497 0.0539883599 0.0621107402 0.0880135372 0.0058071944 0.1432010000 978010689 0 402718720 0.1650556475 -0.0659157708 -0.1020780280 591 1311867190.1396369934 0.0549996011 0.0620987078 0.0880135372 0.0058055283 0.1410810000 978013593 0 402718720 0.1661146581 -0.0655509010 -0.1026328504 592 1311867190.1706380844 0.0555992499 0.0620877290 0.0880135372 0.0058065519 0.1419790000 978016385 0 402718720 0.1678422689 -0.0659609810 -0.1029853076 593 1311867190.2096021175 0.0563969463 0.0620781324 0.0880135372 0.0058024002 0.1509470000 978019513 0 402718720 0.1689454764 -0.0678855702 -0.1037289426 594 1311867190.2394330502 0.0564648919 0.0620686825 0.0880135372 0.0058078423 0.1392690000 978022305 0 402718720 0.1721949875 -0.0672949478 -0.1038657129 595 1311867190.2714810371 0.0568825454 0.0620599663 0.0880135372 0.0058095480 0.1400250000 978025265 0 402718720 0.1742603034 -0.0675994009 -0.1041337177 596 1311867190.3072700500 0.0579298288 0.0620530365 0.0880135372 0.0058078966 0.1394790000 978028281 0 402718720 0.1756687611 -0.0677772611 -0.1043330356 597 1311867190.3414731026 0.0575133599 0.0620454324 0.0880135372 0.0058047951 0.1375500000 978031241 0 402718720 0.1793888658 -0.0678648055 -0.1041413397 598 1311867190.3716828823 0.0570046045 0.0620370029 0.0880135372 0.0058073821 0.1595710000 978034089 0 402718720 0.1830925494 -0.0673613846 -0.1036982164 599 1311867190.4101090431 0.0578874014 0.0620300754 0.0880135372 0.0058054143 0.1399900000 978037105 0 402718720 0.1845780611 -0.0676248223 -0.1037879065 600 1311867190.4394960403 0.0577534102 0.0620229476 0.0880135372 0.0058028348 0.1397400000 978040065 0 402718720 0.1877509505 -0.0667541772 -0.1031815186 601 1311867190.4708199501 0.0578375421 0.0620159835 0.0880135372 0.0057987746 0.1385380000 978042857 0 402718720 0.1903766096 -0.0672039613 -0.1027424932 602 1311867190.5097529888 0.0576101467 0.0620086649 0.0880135372 0.0057945155 0.1389260000 978046041 0 402718720 0.1931094527 -0.0680783540 -0.1024014503 603 1311867190.5405189991 0.0582062453 0.0620023590 0.0880135372 0.0057964319 0.1398720000 978048833 0 402718720 0.1953592151 -0.0670370385 -0.1021553650 604 1311867190.5708439350 0.0581609868 0.0619959991 0.0880135372 0.0057937340 0.1412250000 978051681 0 402718720 0.1978679299 -0.0678223893 -0.1016069576 605 1311867190.6067750454 0.0583222993 0.0619899269 0.0880135372 0.0057894380 0.1407680000 978054697 0 402718720 0.1999110579 -0.0684169903 -0.1014916971 606 1311867190.6389939785 0.0578646101 0.0619831194 0.0880135372 0.0057857362 0.1408060000 978057657 0 402718720 0.2034632266 -0.0681739971 -0.1007351875 607 1311867190.6723659039 0.0577867441 0.0619762061 0.0880135372 0.0057818228 0.1397990000 978060561 0 402718720 0.2067693472 -0.0692796409 -0.0999224186 608 1311867190.7114980221 0.0583738610 0.0619702812 0.0880135372 0.0057789230 0.1633870000 978063633 0 402718720 0.2085906118 -0.0696666390 -0.0993058160 609 1311867190.7392649651 0.0578386709 0.0619634970 0.0880135372 0.0057745506 0.1625160000 978066369 0 402718720 0.2114181072 -0.0702043772 -0.0984933302 610 1311867190.7751801014 0.0574942790 0.0619561704 0.0880135372 0.0057700258 0.1417290000 978069385 0 402718720 0.2141018957 -0.0704770461 -0.0979141295 611 1311867190.8070900440 0.0575597063 0.0619489749 0.0880135372 0.0057662836 0.1425780000 978072345 0 402718720 0.2167156935 -0.0707719922 -0.0970399380 612 1311867190.8414280415 0.0571846217 0.0619411900 0.0880135372 0.0057681536 0.1430790000 978075305 0 402718720 0.2193244249 -0.0721120164 -0.0962778255 613 1311867190.8739249706 0.0576276965 0.0619341533 0.0880135372 0.0057641480 0.1424820000 978078209 0 402718720 0.2209425271 -0.0731169656 -0.0956440717 614 1311867190.9076139927 0.0577363558 0.0619273165 0.0880135372 0.0057596138 0.1424680000 978081169 0 402718720 0.2231698930 -0.0732319131 -0.0948291123 615 1311867190.9393599033 0.0571636297 0.0619195706 0.0880135372 0.0057564637 0.1424880000 978084017 0 402718720 0.2263898104 -0.0746700391 -0.0939739719 616 1311867190.9741609097 0.0571806729 0.0619118776 0.0880135372 0.0057521382 0.1421990000 978087033 0 402718720 0.2286080867 -0.0758737102 -0.0934144184 617 1311867191.0085949898 0.0573530942 0.0619044890 0.0880135372 0.0057549652 0.1422740000 978089993 0 402718720 0.2313807309 -0.0749526173 -0.0924739465 618 1311867191.0396919250 0.0574924238 0.0618973497 0.0880135372 0.0057517326 0.1633410000 978092897 0 402718720 0.2334083319 -0.0753600746 -0.0915028453 619 1311867191.0764329433 0.0578295104 0.0618907781 0.0880135372 0.0057496333 0.1423240000 978095913 0 402718720 0.2347674221 -0.0774669871 -0.0911622941 620 1311867191.1103041172 0.0586866103 0.0618856101 0.0880135372 0.0057553966 0.1427080000 978098873 0 402718720 0.2373093665 -0.0773147121 -0.0899040401 621 1311867191.1388139725 0.0577066876 0.0618788808 0.0880135372 0.0057673758 0.1428620000 978101721 0 402718720 0.2414408624 -0.0777286217 -0.0887787119 622 1311867191.1742820740 0.0583845712 0.0618732629 0.0880135372 0.0057643801 0.1549710000 978104681 0 402718720 0.2425975949 -0.0791677609 -0.0883210376 623 1311867191.2077920437 0.0587867945 0.0618683087 0.0880135372 0.0057598727 0.1564530000 978107641 0 402718720 0.2453074455 -0.0787852556 -0.0873272195 624 1311867191.2408421040 0.0595954619 0.0618646663 0.0880135372 0.0057565152 0.1560320000 978110601 0 402718720 0.2470549047 -0.0787929222 -0.0867147148 625 1311867191.2769579887 0.0602483563 0.0618620802 0.0880135372 0.0057543095 0.1432570000 978113561 0 402718720 0.2491520792 -0.0794748589 -0.0861414298 626 1311867191.3085029125 0.0607238561 0.0618602620 0.0880135372 0.0057554331 0.1431600000 978116297 0 402718720 0.2514683008 -0.0786561221 -0.0852518529 627 1311867191.3404779434 0.0606152751 0.0618582763 0.0880135372 0.0057523293 0.1434220000 978119201 0 402718720 0.2543293536 -0.0792429149 -0.0843228623 628 1311867191.3794629574 0.0607066862 0.0618564426 0.0880135372 0.0057480915 0.1535640000 978122329 0 402718720 0.2562214732 -0.0805967450 -0.0838586763 629 1311867191.4091579914 0.0602095202 0.0618538243 0.0880135372 0.0057450523 0.1435870000 978125121 0 402718720 0.2593627274 -0.0812757388 -0.0830148757 630 1311867191.4415969849 0.0595195517 0.0618501191 0.0880135372 0.0057413160 0.1441480000 978128025 0 402718720 0.2630429268 -0.0809564963 -0.0820729136 631 1311867191.4775309563 0.0599367395 0.0618470868 0.0880135372 0.0057418393 0.1438370000 978130985 0 402718720 0.2639845014 -0.0823409706 -0.0817193538 632 1311867191.5075590611 0.0600358732 0.0618442209 0.0880135372 0.0057378527 0.1435830000 978133777 0 402718720 0.2656486928 -0.0820136666 -0.0808834955 633 1311867191.5390620232 0.0595010296 0.0618405192 0.0880135372 0.0057335671 0.1596290000 978136681 0 402718720 0.2686147690 -0.0822791159 -0.0800531060 634 1311867191.5764698982 0.0597767234 0.0618372640 0.0880135372 0.0057300445 0.1443870000 978139697 0 402718720 0.2707353532 -0.0822439566 -0.0793163925 635 1311867191.6118669510 0.0597877279 0.0618340364 0.0880135372 0.0057550331 0.1435220000 978142713 0 402718720 0.2733850181 -0.0815550759 -0.0782214329 636 1311867191.6451880932 0.0597665943 0.0618307857 0.0880135372 0.0057520081 0.1449070000 978145617 0 402718720 0.2752690911 -0.0819773525 -0.0770561993 637 1311867191.6827919483 0.0586518385 0.0618257952 0.0880135372 0.0057561018 0.1560260000 978148745 0 402718720 0.2785751522 -0.0827493295 -0.0757860616 638 1311867191.7119400501 0.0586766377 0.0618208592 0.0880135372 0.0057541481 0.1573180000 978151537 0 402718720 0.2803821564 -0.0821988061 -0.0748381317 639 1311867191.7457199097 0.0588027276 0.0618161360 0.0880135372 0.0057694539 0.1455600000 978154385 0 402718720 0.2804501355 -0.0828008577 -0.0743820965 640 1311867191.7763800621 0.0593148880 0.0618122278 0.0880135372 0.0057725511 0.1460760000 978157233 0 402718720 0.2814049125 -0.0828628764 -0.0735304207 641 1311867191.8097250462 0.0582760833 0.0618067112 0.0880135372 0.0057709316 0.1462990000 978160193 0 402718720 0.2848820984 -0.0828401819 -0.0717098191 642 1311867191.8395779133 0.0576796010 0.0618002827 0.0880135372 0.0057749051 0.1467050000 978163041 0 402718720 0.2865353525 -0.0833804831 -0.0710958689 643 1311867191.8745219707 0.0579993129 0.0617943714 0.0880135372 0.0057767066 0.1777820000 978166001 0 402718720 0.2875193357 -0.0828775316 -0.0701756403 644 1311867191.9077119827 0.0568056516 0.0617866249 0.0880135372 0.0057732757 0.1468750000 978168961 0 402718720 0.2905158103 -0.0831687525 -0.0687392950 645 1311867191.9391601086 0.0574973337 0.0617799749 0.0880135372 0.0057699790 0.1470190000 978171865 0 402718720 0.2906865478 -0.0842927396 -0.0680174828 646 1311867191.9755239487 0.0570001751 0.0617725758 0.0880135372 0.0057689613 0.1475860000 978174825 0 402718720 0.2928240597 -0.0840674937 -0.0668391660 647 1311867192.0076289177 0.0573520921 0.0617657435 0.0880135372 0.0057655859 0.1484040000 978177729 0 402718720 0.2937487662 -0.0841011703 -0.0658924058 648 1311867192.0447950363 0.0569162704 0.0617582598 0.0880135372 0.0057745030 0.1554120000 978180801 0 402718720 0.2945689559 -0.0857907981 -0.0655426830 649 1311867192.0751929283 0.0573474281 0.0617514634 0.0880135372 0.0057730720 0.1479280000 978183593 0 402718720 0.2950839102 -0.0855154395 -0.0649359673 650 1311867192.1073920727 0.0573215820 0.0617446482 0.0880135372 0.0057715738 0.1482520000 978186553 0 402718720 0.2977654636 -0.0848411396 -0.0633245930 651 1311867192.1433029175 0.0580655932 0.0617389968 0.0880135372 0.0057761908 0.1588730000 978189569 0 402718720 0.2970713079 -0.0862914026 -0.0633161366 652 1311867192.1754670143 0.0590144396 0.0617348180 0.0880135372 0.0057811179 0.1478080000 978192473 0 402718720 0.2975371480 -0.0857665017 -0.0624926798 653 1311867192.2077538967 0.0589438044 0.0617305439 0.0880135372 0.0057778163 0.1699150000 978195433 0 402718720 0.2997376323 -0.0854910165 -0.0613067597 654 1311867192.2451250553 0.0584467687 0.0617255228 0.0880135372 0.0057855957 0.1468530000 978198505 0 402718720 0.3014627397 -0.0872474015 -0.0603229627 655 1311867192.2744629383 0.0590415820 0.0617214252 0.0880135372 0.0057835210 0.1467460000 978201297 0 402718720 0.3024362922 -0.0863587484 -0.0596521758 656 1311867192.3067719936 0.0591998734 0.0617175814 0.0880135372 0.0057813566 0.1468470000 978204201 0 402718720 0.3044856787 -0.0869525224 -0.0584702604 657 1311867192.3427391052 0.0596448705 0.0617144266 0.0880135372 0.0057781168 0.1595840000 978207217 0 402718720 0.3053011000 -0.0884658396 -0.0580149032 658 1311867192.3755910397 0.0609502345 0.0617132652 0.0880135372 0.0057808929 0.1479200000 978210177 0 402718720 0.3059809804 -0.0881565362 -0.0574669577 659 1311867192.4059340954 0.0606816821 0.0617116998 0.0880135372 0.0057769636 0.1474620000 978212969 0 402718720 0.3084876537 -0.0889090672 -0.0567184389 660 1311867192.4447100163 0.0619015470 0.0617119875 0.0880135372 0.0057743476 0.1475010000 978216097 0 402718720 0.3091289103 -0.0902568921 -0.0567700043 661 1311867192.4748210907 0.0634696931 0.0617146466 0.0880135372 0.0057739950 0.1471010000 978218945 0 402718720 0.3094991744 -0.0899507701 -0.0564059317 662 1311867192.5077190399 0.0643689260 0.0617186561 0.0880135372 0.0057701216 0.1596890000 978221849 0 402718720 0.3103671372 -0.0906808898 -0.0560415685 663 1311867192.5427820683 0.0643739849 0.0617226611 0.0880135372 0.0057686336 0.1633100000 978224865 0 402718720 0.3115534782 -0.0923087820 -0.0561478846 664 1311867192.5787169933 0.0655783415 0.0617284679 0.0880135372 0.0057688016 0.1469130000 978227825 0 402718720 0.3124020398 -0.0917680413 -0.0560346395 665 1311867192.6109929085 0.0681653917 0.0617381475 0.0880135372 0.0057657090 0.1477810000 978230729 0 402718720 0.3107493222 -0.0913858041 -0.0561642498 666 1311867192.6435210705 0.0695268586 0.0617498422 0.0880135372 0.0057657655 0.1459540000 978233689 0 402718720 0.3103831112 -0.0926707536 -0.0563973784 667 1311867192.6790139675 0.0699808076 0.0617621825 0.0880135372 0.0057629385 0.1476930000 978236705 0 402718720 0.3118757606 -0.0925039649 -0.0558646470 668 1311867192.7113289833 0.0696189329 0.0617739441 0.0880135372 0.0057597948 0.1589930000 978239553 0 402718720 0.3138114214 -0.0927300155 -0.0554823652 669 1311867192.7439620495 0.0704369992 0.0617868934 0.0880135372 0.0057591821 0.1480020000 978242513 0 402718720 0.3140119910 -0.0936541930 -0.0552855507 670 1311867192.7760629654 0.0700973123 0.0617992970 0.0880135372 0.0057575544 0.1474750000 978245417 0 402718720 0.3160525560 -0.0930147767 -0.0546988547 671 1311867192.8091869354 0.0702321455 0.0618118646 0.0880135372 0.0057533648 0.1477070000 978248377 0 402718720 0.3172800839 -0.0936298519 -0.0542648584 672 1311867192.8422288895 0.0701020360 0.0618242011 0.0880135372 0.0057497611 0.1472430000 978251281 0 402718720 0.3184928000 -0.0943731219 -0.0539256372 673 1311867192.8792889118 0.0707874075 0.0618375194 0.0880135372 0.0057504040 0.1567210000 978254353 0 402718720 0.3191868663 -0.0935639963 -0.0533472523 674 1311867192.9092190266 0.0700643435 0.0618497254 0.0880135372 0.0057465388 0.1487940000 978257145 0 402718720 0.3213363886 -0.0941067338 -0.0524340644 675 1311867192.9434111118 0.0698385835 0.0618615607 0.0880135372 0.0057437067 0.1493510000 978260161 0 402718720 0.3225609064 -0.0956056640 -0.0522145629 676 1311867192.9776289463 0.0697448775 0.0618732224 0.0880135372 0.0057439283 0.1669920000 978263065 0 402718720 0.3244746029 -0.0948833153 -0.0516286455 677 1311867193.0086810589 0.0697646439 0.0618848789 0.0880135372 0.0057417897 0.1503670000 978265969 0 402718720 0.3253966868 -0.0950654447 -0.0511754043 678 1311867193.0430600643 0.0694275349 0.0618960038 0.0880135372 0.0057396812 0.1593040000 978268929 0 402718720 0.3267812729 -0.0965670943 -0.0510737374 679 1311867193.0767369270 0.0700086281 0.0619079517 0.0880135372 0.0057450783 0.1501540000 978271833 0 402718720 0.3279530406 -0.0953400433 -0.0509120189 680 1311867193.1105849743 0.0696629584 0.0619193561 0.0880135372 0.0057419596 0.1511740000 978274793 0 402718720 0.3299597800 -0.0953236818 -0.0504024215 681 1311867193.1429219246 0.0685881898 0.0619291488 0.0880135372 0.0057429783 0.1508230000 978277753 0 402718720 0.3314896524 -0.0968880728 -0.0503592528 682 1311867193.1767370701 0.0700582787 0.0619410683 0.0880135372 0.0057573198 0.1494710000 978280657 0 402718720 0.3324101269 -0.0948476046 -0.0500413850 683 1311867193.2122681141 0.0701952428 0.0619531535 0.0880135372 0.0057575760 0.1661290000 978283673 0 402718720 0.3337670565 -0.0953730866 -0.0495912470 684 1311867193.2432429790 0.0696917996 0.0619644673 0.0880135372 0.0057563896 0.1517350000 978286577 0 402718720 0.3354783356 -0.0961107016 -0.0495605804 685 1311867193.2773900032 0.0704148635 0.0619768037 0.0880135372 0.0057544128 0.1522110000 978289537 0 402718720 0.3362613916 -0.0950364470 -0.0494446941 686 1311867193.3139379025 0.0717245042 0.0619910131 0.0880135372 0.0057545585 0.1522980000 978292553 0 402718720 0.3360029757 -0.0957815796 -0.0498196892 687 1311867193.3426671028 0.0714634657 0.0620048013 0.0880135372 0.0057542267 0.1505680000 978295345 0 402718720 0.3376080692 -0.0956064686 -0.0495324023 688 1311867193.3788230419 0.0709245875 0.0620177661 0.0880135372 0.0057507581 0.1629210000 978298361 0 402718720 0.3401042521 -0.0951126888 -0.0492234193 689 1311867193.4126739502 0.0714399442 0.0620314412 0.0880135372 0.0057570412 0.1525740000 978301265 0 402718720 0.3407092988 -0.0962826908 -0.0493696518 690 1311867193.4440810680 0.0717864558 0.0620455789 0.0880135372 0.0057573139 0.1525960000 978304225 0 402718720 0.3419566751 -0.0961200744 -0.0492849462 691 1311867193.4782969952 0.0719379783 0.0620598950 0.0880135372 0.0057540837 0.1529440000 978307185 0 402718720 0.3437088430 -0.0955593958 -0.0490263402 692 1311867193.5199069977 0.0731282607 0.0620758897 0.0880135372 0.0057521449 0.1529240000 978310257 0 402718720 0.3439973891 -0.0966907069 -0.0493077487 693 1311867193.5431120396 0.0723438859 0.0620907065 0.0880135372 0.0057515374 0.1668350000 978312993 0 402718720 0.3461018503 -0.0967354700 -0.0491075255 694 1311867193.5765709877 0.0729020834 0.0621062848 0.0880135372 0.0057477292 0.1509430000 978315897 0 402718720 0.3473629951 -0.0961135030 -0.0489644557 695 1311867193.6127800941 0.0732805580 0.0621223629 0.0880135372 0.0057437174 0.1526170000 978318969 0 402718720 0.3482329845 -0.0971203819 -0.0492120311 696 1311867193.6461451054 0.0740179569 0.0621394543 0.0880135372 0.0057409638 0.1521020000 978321873 0 402718720 0.3488732576 -0.0970199555 -0.0493503362 697 1311867193.6757860184 0.0742136389 0.0621567774 0.0880135372 0.0057375224 0.1547630000 978324721 0 402718720 0.3506291509 -0.0959626064 -0.0490543693 698 1311867193.7122890949 0.0749117509 0.0621750510 0.0880135372 0.0057338132 0.1884520000 978327737 0 402718720 0.3509109914 -0.0969258174 -0.0492800102 699 1311867193.7430191040 0.0757961571 0.0621945375 0.0880135372 0.0057315417 0.1762420000 978330585 0 402718720 0.3513780236 -0.0962601304 -0.0493929461 700 1311867193.7760169506 0.0765188485 0.0622150008 0.0880135372 0.0057288183 0.1529050000 978333489 0 402718720 0.3521643877 -0.0953637809 -0.0496721715 701 1311867193.8139710426 0.0771856233 0.0622363569 0.0880135372 0.0057262663 0.1512170000 978336617 0 402718720 0.3530247211 -0.0966398418 -0.0494778380 702 1311867193.8436760902 0.0774949268 0.0622580928 0.0880135372 0.0057240622 0.1516940000 978339409 0 402718720 0.3540284634 -0.0964875147 -0.0495687462 703 1311867193.8771181107 0.0775555223 0.0622798530 0.0880135372 0.0057210137 0.1546300000 978342369 0 402718720 0.3558461070 -0.0959663019 -0.0494650900 704 1311867193.9151229858 0.0788204297 0.0623033481 0.0880135372 0.0057178488 0.1547010000 978345385 0 402718720 0.3557690978 -0.0967752337 -0.0497191213 705 1311867193.9425311089 0.0789314657 0.0623269341 0.0880135372 0.0057157468 0.1531070000 978348233 0 402718720 0.3568862081 -0.0961471871 -0.0497283638 706 1311867193.9781770706 0.0797007978 0.0623515430 0.0880135372 0.0057126799 0.1547540000 978351249 0 402718720 0.3577208519 -0.0958599672 -0.0497570224 707 1311867194.0148570538 0.0818593577 0.0623791354 0.0880135372 0.0057110800 0.1522300000 978354209 0 402718720 0.3565182090 -0.0964100584 -0.0504813232 708 1311867194.0433440208 0.0829565600 0.0624081995 0.0880135372 0.0057088871 0.1804710000 978357057 0 402718720 0.3567541540 -0.0960103348 -0.0504348129 709 1311867194.0746119022 0.0820562467 0.0624359119 0.0880135372 0.0057053962 0.1554080000 978359905 0 402718720 0.3591390848 -0.0958792791 -0.0499316305 710 1311867194.1131060123 0.0830118582 0.0624648921 0.0880135372 0.0057015654 0.1558170000 978363033 0 402718720 0.3588115871 -0.0963946730 -0.0504364595 711 1311867194.1428558826 0.0840875059 0.0624953036 0.0880135372 0.0056998369 0.1561680000 978365881 0 402718720 0.3585634828 -0.0957282633 -0.0503569245 712 1311867194.1758549213 0.0835834518 0.0625249218 0.0880135372 0.0057017576 0.1567200000 978368785 0 402718720 0.3599723876 -0.0949690044 -0.0498556420 713 1311867194.2138450146 0.0843630135 0.0625555503 0.0880135372 0.0056988656 0.1691840000 978371857 0 402718720 0.3595934212 -0.0958161429 -0.0501807481 714 1311867194.2451140881 0.0843502060 0.0625860750 0.0880135372 0.0056966836 0.1561200000 978374649 0 402718720 0.3605143428 -0.0949621573 -0.0498578958 715 1311867194.2760241032 0.0837770700 0.0626157128 0.0880135372 0.0056931614 0.1566000000 978377497 0 402718720 0.3618188798 -0.0950724185 -0.0493047610 716 1311867194.3139200211 0.0849980786 0.0626469730 0.0880135372 0.0056904639 0.1568190000 978380569 0 402718720 0.3610455692 -0.0956701934 -0.0496130623 717 1311867194.3447821140 0.0847389847 0.0626777848 0.0880135372 0.0056909016 0.1568750000 978383473 0 402718720 0.3619654775 -0.0947249606 -0.0491469465 718 1311867194.3802230358 0.0832015499 0.0627063694 0.0880135372 0.0056881638 0.1689500000 978386433 0 402718720 0.3643179834 -0.0949266776 -0.0484823510 719 1311867194.4124519825 0.0835430399 0.0627353495 0.0880135372 0.0056865281 0.1562240000 978389281 0 402718720 0.3641436398 -0.0961633474 -0.0482537262 720 1311867194.4447510242 0.0839719772 0.0627648448 0.0880135372 0.0056828798 0.1685900000 978392241 0 402718720 0.3644147217 -0.0962440297 -0.0479992703 721 1311867194.4805839062 0.0839141682 0.0627941781 0.0880135372 0.0056794206 0.1543190000 978395145 0 402718720 0.3651470542 -0.0959450155 -0.0478754938 722 1311867194.5174930096 0.0846395120 0.0628244348 0.0880135372 0.0056767712 0.1675320000 978398273 0 402718720 0.3646765649 -0.0967021585 -0.0479007922 723 1311867194.5439500809 0.0847983137 0.0628548274 0.0880135372 0.0056748666 0.1679110000 978400953 0 402718720 0.3648017943 -0.0963447839 -0.0479400419 724 1311867194.5795979500 0.0841286480 0.0628842112 0.0880135372 0.0056710080 0.1699430000 978403913 0 402718720 0.3660679758 -0.0963568687 -0.0474134646 725 1311867194.6129479408 0.0834961236 0.0629126414 0.0880135372 0.0056675211 0.1557380000 978406873 0 402718720 0.3672100604 -0.0971673578 -0.0468137674 726 1311867194.6493880749 0.0822063461 0.0629392167 0.0880135372 0.0056758102 0.1696450000 978409945 0 402718720 0.3689377308 -0.0969753042 -0.0459616072 727 1311867194.6784319878 0.0814738050 0.0629647114 0.0880135372 0.0056747554 0.1574730000 978412737 0 402718720 0.3700340092 -0.0970831439 -0.0456733741 728 1311867194.7133309841 0.0822160766 0.0629911556 0.0880135372 0.0056726165 0.1678640000 978415697 0 402718720 0.3695806265 -0.0969061032 -0.0456203409 729 1311867194.7475099564 0.0824238807 0.0630178122 0.0880135372 0.0056690989 0.1576030000 978418657 0 402718720 0.3700420856 -0.0965101570 -0.0451873280 730 1311867194.7784450054 0.0827648938 0.0630448630 0.0880135372 0.0056654069 0.1573510000 978421561 0 402718720 0.3700877130 -0.0966164023 -0.0448605008 731 1311867194.8130390644 0.0826930255 0.0630717415 0.0880135372 0.0056615390 0.1764440000 978424521 0 402718720 0.3704071343 -0.0964774564 -0.0445828997 732 1311867194.8476719856 0.0836525187 0.0630998573 0.0880135372 0.0056579057 0.1939180000 978427481 0 402718720 0.3693161011 -0.0961406454 -0.0448189192 733 1311867194.8814148903 0.0839322805 0.0631282781 0.0880135372 0.0056545065 0.1820980000 978430441 0 402718720 0.3687647879 -0.0956992880 -0.0447185189 734 1311867194.9104089737 0.0835945159 0.0631561612 0.0880135372 0.0056612850 0.1563800000 978433233 0 402718720 0.3689311147 -0.0952459425 -0.0445795022 735 1311867194.9451448917 0.0834381655 0.0631837558 0.0880135372 0.0056582519 0.1566260000 978436249 0 402718720 0.3683926463 -0.0955846608 -0.0442208908 736 1311867194.9787399769 0.0811709985 0.0632081950 0.0880135372 0.0056566200 0.1579050000 978439209 0 402718720 0.3704719543 -0.0963964537 -0.0435020290 737 1311867195.0132799149 0.0803057626 0.0632313939 0.0880135372 0.0056547420 0.1585220000 978442169 0 402718720 0.3704185486 -0.0960354581 -0.0431524403 738 1311867195.0464940071 0.0792694241 0.0632531256 0.0880135372 0.0056520884 0.1567120000 978445073 0 402718720 0.3709784150 -0.0974613354 -0.0427011251 739 1311867195.0781710148 0.0788051486 0.0632741703 0.0880135372 0.0056488431 0.1587880000 978447977 0 402718720 0.3710322976 -0.0965746418 -0.0425529703 740 1311867195.1115310192 0.0788526833 0.0632952224 0.0880135372 0.0056453466 0.1589780000 978450881 0 402718720 0.3703132868 -0.0963286906 -0.0423958674 741 1311867195.1458311081 0.0789938197 0.0633164080 0.0880135372 0.0056416245 0.1585560000 978453897 0 402718720 0.3690767586 -0.0968462527 -0.0425839759 742 1311867195.1780319214 0.0783992335 0.0633367353 0.0880135372 0.0056394348 0.1692490000 978456801 0 402718720 0.3690474629 -0.0959169120 -0.0424080715 743 1311867195.2114748955 0.0769324452 0.0633550337 0.0880135372 0.0056361155 0.1579100000 978459705 0 402718720 0.3692097962 -0.0959551409 -0.0422052220 744 1311867195.2436800003 0.0764504895 0.0633726351 0.0880135372 0.0056343671 0.1789010000 978462665 0 402718720 0.3689818084 -0.0968788043 -0.0421823338 745 1311867195.2780399323 0.0758541897 0.0633893889 0.0880135372 0.0056312102 0.1586890000 978465625 0 402718720 0.3685813248 -0.0969622284 -0.0420073122 746 1311867195.3123180866 0.0753981173 0.0634054864 0.0880135372 0.0056277930 0.1588900000 978468585 0 402718720 0.3682126105 -0.0969152749 -0.0419769399 747 1311867195.3425979614 0.0760262758 0.0634223817 0.0880135372 0.0056283703 0.1590840000 978471433 0 402718720 0.3658367097 -0.0983282179 -0.0426309370 748 1311867195.3782711029 0.0756704658 0.0634387561 0.0880135372 0.0056260735 0.1587660000 978474449 0 402718720 0.3651481867 -0.0977308527 -0.0427618027 749 1311867195.4119830132 0.0751487687 0.0634543903 0.0880135372 0.0056251746 0.1690670000 978477353 0 402718720 0.3642542958 -0.0975022614 -0.0431929678 750 1311867195.4435520172 0.0754805729 0.0634704252 0.0880135372 0.0056228810 0.1576730000 978480313 0 402718720 0.3617304862 -0.0980112478 -0.0440328941 751 1311867195.4788239002 0.0742714033 0.0634848074 0.0880135372 0.0056200343 0.1588900000 978483273 0 402718720 0.3618773222 -0.0972127095 -0.0440022536 752 1311867195.5113179684 0.0738262385 0.0634985593 0.0880135372 0.0056165494 0.1578660000 978486177 0 402718720 0.3610444963 -0.0972316861 -0.0440547988 753 1311867195.5439620018 0.0733653009 0.0635116625 0.0880135372 0.0056130413 0.1590630000 978489137 0 402718720 0.3591780066 -0.0981589481 -0.0442428142 754 1311867195.5782160759 0.0721222833 0.0635230824 0.0880135372 0.0056106690 0.1713820000 978492097 0 402718720 0.3593972325 -0.0978148058 -0.0439082794 755 1311867195.6119859219 0.0722991824 0.0635347064 0.0880135372 0.0056086386 0.1588550000 978495057 0 402718720 0.3572872579 -0.0978311971 -0.0442158207 756 1311867195.6430909634 0.0725111514 0.0635465800 0.0880135372 0.0056051940 0.1563180000 978497905 0 402718720 0.3547205329 -0.0982322022 -0.0447989218 757 1311867195.6779129505 0.0724122673 0.0635582916 0.0880135372 0.0056018539 0.1591180000 978500921 0 402718720 0.3530350029 -0.0979992971 -0.0448212437 758 1311867195.7107300758 0.0724802315 0.0635700620 0.0880135372 0.0056019095 0.1589630000 978503769 0 402718720 0.3506743610 -0.0980434641 -0.0448601358 759 1311867195.7458300591 0.0712987706 0.0635802447 0.0880135372 0.0056000852 0.1689590000 978506785 0 402718720 0.3499339521 -0.0988612548 -0.0448202901 760 1311867195.7821879387 0.0709012076 0.0635898776 0.0880135372 0.0055965593 0.1590570000 978509745 0 402718720 0.3487620056 -0.0985585824 -0.0445578657 761 1311867195.8100500107 0.0716997385 0.0636005344 0.0880135372 0.0055934538 0.1586920000 978512537 0 402718720 0.3459210098 -0.0988776833 -0.0447714888 762 1311867195.8458549976 0.0704938844 0.0636095808 0.0880135372 0.0055902086 0.1708300000 978515553 0 402718720 0.3452413380 -0.0991050303 -0.0448281169 763 1311867195.8778660297 0.0699563250 0.0636178990 0.0880135372 0.0055890091 0.1564060000 978518513 0 402718720 0.3441229761 -0.0980135873 -0.0448006168 764 1311867195.9098269939 0.0700002685 0.0636262528 0.0880135372 0.0055863804 0.1596710000 978521417 0 402718720 0.3424385786 -0.0979230404 -0.0447912700 765 1311867195.9458460808 0.0698233023 0.0636343536 0.0880135372 0.0055832967 0.1589880000 978524377 0 402718720 0.3405221105 -0.0982936397 -0.0449031517 766 1311867195.9778430462 0.0700078011 0.0636426740 0.0880135372 0.0055812365 0.1566210000 978527337 0 402718720 0.3389907479 -0.0973109975 -0.0447782092 767 1311867196.0100569725 0.0694245994 0.0636502124 0.0880135372 0.0055783722 0.1582170000 978530241 0 402718720 0.3383036256 -0.0974704921 -0.0445490703 768 1311867196.0498790741 0.0685002878 0.0636565276 0.0880135372 0.0055759787 0.1581900000 978533369 0 402718720 0.3376086950 -0.0979412496 -0.0447663814 769 1311867196.0793108940 0.0688605383 0.0636632948 0.0880135372 0.0055769817 0.1709450000 978536273 0 402718720 0.3359609246 -0.0967809036 -0.0446468443 770 1311867196.1113979816 0.0687774494 0.0636699366 0.0880135372 0.0055741078 0.1739020000 978539065 0 402718720 0.3341956735 -0.0971954763 -0.0447870754 771 1311867196.1473290920 0.0680066347 0.0636755613 0.0880135372 0.0055707702 0.1591440000 978542137 0 402718720 0.3332907856 -0.0976764038 -0.0447644144 772 1311867196.1811769009 0.0677562952 0.0636808473 0.0880135372 0.0055709904 0.1576070000 978545097 0 402718720 0.3320015073 -0.0969730988 -0.0446841791 773 1311867196.2114949226 0.0684577376 0.0636870269 0.0880135372 0.0055687924 0.1588360000 978547889 0 402718720 0.3294571638 -0.0976305231 -0.0449526086 774 1311867196.2462599277 0.0683924556 0.0636931063 0.0880135372 0.0055658332 0.1740030000 978550905 0 402718720 0.3277535141 -0.0976123363 -0.0450935252 775 1311867196.2800569534 0.0682407543 0.0636989742 0.0880135372 0.0055623726 0.1591060000 978553865 0 402718720 0.3262739778 -0.0973511115 -0.0450044200 776 1311867196.3111600876 0.0675535575 0.0637039415 0.0880135372 0.0055590147 0.1591150000 978556713 0 402718720 0.3251710236 -0.0978349596 -0.0450979024 777 1311867196.3484730721 0.0676936060 0.0637090762 0.0880135372 0.0055560521 0.1588810000 978559785 0 402718720 0.3233179450 -0.0975177065 -0.0452784337 778 1311867196.3842670918 0.0673851445 0.0637138012 0.0880135372 0.0055529947 0.1583470000 978562745 0 402718720 0.3220116496 -0.0968448818 -0.0449644886 779 1311867196.4107549191 0.0674151033 0.0637185526 0.0880135372 0.0055510161 0.1697590000 978565481 0 402718720 0.3202996552 -0.0975236893 -0.0449646749 780 1311867196.4463150501 0.0671886653 0.0637230014 0.0880135372 0.0055502508 0.1582360000 978568497 0 402718720 0.3190186620 -0.0970151573 -0.0449217521 781 1311867196.4798319340 0.0665800869 0.0637266597 0.0880135372 0.0055467602 0.1581510000 978571457 0 402718720 0.3184438050 -0.0965081155 -0.0444734283 782 1311867196.5113470554 0.0668403134 0.0637306413 0.0880135372 0.0055435880 0.1595670000 978574305 0 402718720 0.3158705831 -0.0969011262 -0.0447360426 783 1311867196.5468420982 0.0661721155 0.0637337594 0.0880135372 0.0055412237 0.1597850000 978577321 0 402718720 0.3143032491 -0.0960784927 -0.0445078798 784 1311867196.5795550346 0.0658315346 0.0637364351 0.0880135372 0.0055397464 0.1712570000 978580281 0 402718720 0.3138158917 -0.0956602767 -0.0439965762 785 1311867196.6108930111 0.0651384518 0.0637382212 0.0880135372 0.0055394143 0.1598510000 978583129 0 402718720 0.3125691116 -0.0965282694 -0.0437228903 786 1311867196.6521809101 0.0649232268 0.0637397288 0.0880135372 0.0055431653 0.1705240000 978586313 0 402718720 0.3101785183 -0.0954762697 -0.0438398309 787 1311867196.6805100441 0.0642753094 0.0637404093 0.0880135372 0.0055515180 0.1598590000 978589105 0 402718720 0.3089155853 -0.0944956169 -0.0433399677 788 1311867196.7112100124 0.0637674630 0.0637404437 0.0880135372 0.0055484502 0.1704350000 978591953 0 402718720 0.3081074357 -0.0950704291 -0.0427414104 789 1311867196.7464900017 0.0639621690 0.0637407247 0.0880135372 0.0055449721 0.1700500000 978594969 0 402718720 0.3057202101 -0.0944842398 -0.0424337573 790 1311867196.7783749104 0.0634029880 0.0637402972 0.0880135372 0.0055416433 0.1571150000 978597929 0 402718720 0.3042797446 -0.0944312662 -0.0420300849 791 1311867196.8109180927 0.0631685704 0.0637395744 0.0880135372 0.0055397856 0.1578830000 978600721 0 402718720 0.3022128642 -0.0945690647 -0.0419354811 792 1311867196.8488750458 0.0629878938 0.0637386253 0.0880135372 0.0055376850 0.1584000000 978603849 0 402718720 0.2999414504 -0.0945013538 -0.0418385081 793 1311867196.8821749687 0.0624796897 0.0637370377 0.0880135372 0.0055345843 0.1581650000 978606753 0 402718720 0.2986078262 -0.0941227004 -0.0414822288 794 1311867196.9115700722 0.0626651347 0.0637356877 0.0880135372 0.0055320572 0.1582740000 978609545 0 402718720 0.2961475253 -0.0948936045 -0.0415045954 795 1311867196.9482440948 0.0622261204 0.0637337889 0.0880135372 0.0055286488 0.1578900000 978612617 0 402718720 0.2941763997 -0.0948659331 -0.0414493531 796 1311867196.9809880257 0.0617967993 0.0637313555 0.0880135372 0.0055262978 0.1578260000 978615577 0 402718720 0.2927017212 -0.0952167884 -0.0411898866 797 1311867197.0154891014 0.0615393408 0.0637286052 0.0880135372 0.0055235526 0.1579840000 978618481 0 402718720 0.2909820974 -0.0956052691 -0.0413770527 798 1311867197.0490679741 0.0611878075 0.0637254212 0.0880135372 0.0055212258 0.1559580000 978621441 0 402718720 0.2891801894 -0.0955891907 -0.0415357761 799 1311867197.0806479454 0.0607456490 0.0637216918 0.0880135372 0.0055184209 0.1806570000 978624233 0 402718720 0.2877822220 -0.0959705785 -0.0416071266 800 1311867197.1148109436 0.0606415309 0.0637178416 0.0880135372 0.0055152500 0.1566210000 978627249 0 402718720 0.2852168381 -0.0962942690 -0.0421281271 801 1311867197.1468429565 0.0606464446 0.0637140072 0.0880135372 0.0055127503 0.1582850000 978630153 0 402718720 0.2832307816 -0.0956727713 -0.0422348417 802 1311867197.1792430878 0.0606789812 0.0637102228 0.0880135372 0.0055101941 0.1558820000 978633113 0 402718720 0.2806788683 -0.0958722830 -0.0425477885 803 1311867197.2143619061 0.0605721995 0.0637063150 0.0880135372 0.0055092902 0.1573030000 978636073 0 402718720 0.2784487307 -0.0955659673 -0.0426237546 804 1311867197.2459290028 0.0604555383 0.0637022717 0.0880135372 0.0055060565 0.1768870000 978638977 0 402718720 0.2768968642 -0.0951673165 -0.0424712375 805 1311867197.2799959183 0.0596362464 0.0636972208 0.0880135372 0.0055043835 0.1571440000 978641993 0 402718720 0.2758023739 -0.0955223441 -0.0422401167 806 1311867197.3157260418 0.0594304763 0.0636919270 0.0880135372 0.0055014509 0.1582210000 978644897 0 402718720 0.2736259699 -0.0951773971 -0.0423758216 807 1311867197.3468708992 0.0588828847 0.0636859679 0.0880135372 0.0054991048 0.1583070000 978647801 0 402718720 0.2723618746 -0.0951943621 -0.0422006696 808 1311867197.3784019947 0.0589698963 0.0636801311 0.0880135372 0.0054974608 0.1581280000 978650649 0 402718720 0.2699007392 -0.0952345133 -0.0426660553 809 1311867197.4155099392 0.0590100922 0.0636743585 0.0880135372 0.0054945323 0.1679020000 978653665 0 402718720 0.2675387561 -0.0951929092 -0.0430643409 810 1311867197.4478878975 0.0587102696 0.0636682300 0.0880135372 0.0054913177 0.1690870000 978656569 0 402718720 0.2665435374 -0.0950981453 -0.0432331488 811 1311867197.4793179035 0.0584317334 0.0636617732 0.0880135372 0.0054886291 0.1583300000 978659361 0 402718720 0.2644614279 -0.0955323204 -0.0440730825 812 1311867197.5150759220 0.0586201809 0.0636555643 0.0880135372 0.0054869142 0.1577770000 978662377 0 402718720 0.2620476484 -0.0949187204 -0.0449277759 813 1311867197.5469260216 0.0584177300 0.0636491217 0.0880135372 0.0054836524 0.1568790000 978665225 0 402718720 0.2608783543 -0.0944410115 -0.0452728905 814 1311867197.5802750587 0.0584052205 0.0636426796 0.0880135372 0.0054822389 0.1701360000 978668185 0 402718720 0.2588002682 -0.0952992290 -0.0461265184 815 1311867197.6152749062 0.0599164702 0.0636381076 0.0880135372 0.0054836812 0.1569710000 978671145 0 402718720 0.2543686926 -0.0941739529 -0.0475181304 816 1311867197.6470439434 0.0594131798 0.0636329300 0.0880135372 0.0054819417 0.1575770000 978674049 0 402718720 0.2535225749 -0.0933708549 -0.0478301607 817 1311867197.6800849438 0.0596937351 0.0636281084 0.0880135372 0.0054810393 0.1572190000 978677009 0 402718720 0.2505257428 -0.0940388888 -0.0488741696 818 1311867197.7143290043 0.0596542321 0.0636232504 0.0880135372 0.0054812421 0.1582330000 978679969 0 402718720 0.2490338683 -0.0925437137 -0.0494782925 819 1311867197.7463419437 0.0596189387 0.0636183611 0.0880135372 0.0054795937 0.1843170000 978682873 0 402718720 0.2471874505 -0.0922009274 -0.0501621291 820 1311867197.7793009281 0.0600565970 0.0636140175 0.0880135372 0.0054771450 0.1689070000 978685833 0 402718720 0.2439776212 -0.0925287679 -0.0514034405 821 1311867197.8146750927 0.0597511679 0.0636093124 0.0880135372 0.0054782545 0.1583510000 978688849 0 402718720 0.2432443798 -0.0911415666 -0.0519844070 822 1311867197.8467919827 0.0593086928 0.0636040805 0.0880135372 0.0054764241 0.1588770000 978691697 0 402718720 0.2422180176 -0.0916016772 -0.0528334230 823 1311867197.8802978992 0.0594773144 0.0635990662 0.0880135372 0.0054741801 0.1589270000 978694601 0 402718720 0.2394277006 -0.0914748833 -0.0539927185 824 1311867197.9148609638 0.0590940602 0.0635935990 0.0880135372 0.0054753952 0.1690200000 978697617 0 402718720 0.2389093935 -0.0904138312 -0.0544024594 825 1311867197.9470140934 0.0586209074 0.0635875715 0.0880135372 0.0054792024 0.1580780000 978700521 0 402718720 0.2371640652 -0.0907904506 -0.0551040359 826 1311867197.9812700748 0.0589757860 0.0635819882 0.0880135372 0.0054762245 0.1579810000 978703481 0 402718720 0.2345996350 -0.0902467892 -0.0559894778 827 1311867198.0145471096 0.0583556928 0.0635756686 0.0880135372 0.0054739087 0.1580900000 978706497 0 402718720 0.2341037989 -0.0893156826 -0.0562487021 828 1311867198.0463368893 0.0580126047 0.0635689500 0.0880135372 0.0054711281 0.1567840000 978709345 0 402718720 0.2324944586 -0.0892716125 -0.0569790192 829 1311867198.0787069798 0.0580101721 0.0635622446 0.0880135372 0.0054699689 0.1820250000 978712305 0 402718720 0.2310086340 -0.0888648108 -0.0574674644 830 1311867198.1143770218 0.0570367984 0.0635543826 0.0880135372 0.0054669756 0.1591610000 978715265 0 402718720 0.2305444926 -0.0882429555 -0.0578281544 831 1311867198.1463611126 0.0572163835 0.0635467556 0.0880135372 0.0054637552 0.1588860000 978718169 0 402718720 0.2279508561 -0.0879727751 -0.0587760396 832 1311867198.1822519302 0.0565860458 0.0635383894 0.0880135372 0.0054606488 0.1799100000 978721185 0 402718720 0.2267240882 -0.0873693377 -0.0594872758 833 1311867198.2144989967 0.0569318496 0.0635304584 0.0880135372 0.0054636040 0.1588890000 978724089 0 402718720 0.2244977802 -0.0868365318 -0.0601457395 834 1311867198.2464120388 0.0562868118 0.0635217729 0.0880135372 0.0054612862 0.1810130000 978726993 0 402718720 0.2233877480 -0.0869306177 -0.0610771738 835 1311867198.2821578979 0.0557986349 0.0635125237 0.0880135372 0.0054585374 0.1587680000 978730009 0 402718720 0.2220651954 -0.0862856656 -0.0616030581 836 1311867198.3159120083 0.0552014373 0.0635025822 0.0880135372 0.0054576955 0.1581210000 978732913 0 402718720 0.2206394970 -0.0858071893 -0.0626024678 837 1311867198.3481218815 0.0546903536 0.0634920538 0.0880135372 0.0054548788 0.1585590000 978735817 0 402718720 0.2192059010 -0.0859585479 -0.0634624362 838 1311867198.3828320503 0.0544974171 0.0634813204 0.0880135372 0.0054574404 0.1577250000 978738833 0 402718720 0.2165798843 -0.0849501565 -0.0644644722 839 1311867198.4242680073 0.0536388904 0.0634695892 0.0880135372 0.0054632305 0.1741020000 978741793 0 402718720 0.2149532586 -0.0844047964 -0.0654861405 840 1311867198.4497859478 0.0539278015 0.0634582300 0.0880135372 0.0054608755 0.1548710000 978744417 0 402718720 0.2121668905 -0.0853130519 -0.0667539090 841 1311867198.4856219292 0.0544113405 0.0634474727 0.0880135372 0.0054664247 0.1562400000 978747321 0 402718720 0.2089227587 -0.0842146203 -0.0679712594 842 1311867198.5190339088 0.0542288683 0.0634365242 0.0880135372 0.0054638191 0.1554740000 978750281 0 402718720 0.2065630555 -0.0833072737 -0.0690164268 843 1311867198.5499279499 0.0535908341 0.0634248449 0.0880135372 0.0054638960 0.1537330000 978753185 0 402718720 0.2043806911 -0.0836726800 -0.0702742785 844 1311867198.5824239254 0.0531512760 0.0634126724 0.0880135372 0.0054611953 0.1797140000 978756089 0 402718720 0.2028194368 -0.0822918192 -0.0710421652 845 1311867198.6147489548 0.0526525639 0.0633999385 0.0880135372 0.0054612623 0.1546470000 978758993 0 402718720 0.2008446902 -0.0820224062 -0.0719724149 846 1311867198.6482009888 0.0522014052 0.0633867015 0.0880135372 0.0054609223 0.1546890000 978761897 0 402718720 0.1987042129 -0.0818272755 -0.0729065537 847 1311867198.6827540398 0.0524713211 0.0633738144 0.0880135372 0.0054591705 0.1556140000 978764857 0 402718720 0.1953206062 -0.0806924626 -0.0741048679 848 1311867198.7146520615 0.0527644306 0.0633613033 0.0880135372 0.0054560186 0.1553460000 978767705 0 402718720 0.1932558864 -0.0798676461 -0.0746290460 849 1311867198.7467699051 0.0529904887 0.0633490880 0.0880135372 0.0054541629 0.1686390000 978770553 0 402718720 0.1911026090 -0.0796211287 -0.0754435658 850 1311867198.7842700481 0.0526055358 0.0633364485 0.0880135372 0.0054514491 0.1562810000 978773569 0 402718720 0.1897459924 -0.0788244158 -0.0759469569 851 1311867198.8149418831 0.0532205515 0.0633245614 0.0880135372 0.0054484046 0.1554790000 978776417 0 402718720 0.1858316362 -0.0783458650 -0.0772688389 852 1311867198.8464009762 0.0533443503 0.0633128476 0.0880135372 0.0054462957 0.1559260000 978779321 0 402718720 0.1835855544 -0.0775301903 -0.0780900344 853 1311867198.8845369816 0.0533059798 0.0633011162 0.0880135372 0.0054441535 0.1557410000 978782281 0 402718720 0.1826172620 -0.0768439248 -0.0786410496 854 1311867198.9147930145 0.0538530424 0.0632900529 0.0880135372 0.0054409866 0.1572410000 978785129 0 402718720 0.1798744798 -0.0762297437 -0.0796732306 855 1311867198.9465179443 0.0539102070 0.0632790823 0.0880135372 0.0054378810 0.1572340000 978788033 0 402718720 0.1781585217 -0.0751164183 -0.0805735216 856 1311867198.9839329720 0.0539615378 0.0632681973 0.0880135372 0.0054351630 0.1577320000 978791161 0 402718720 0.1759991944 -0.0742039606 -0.0815501586 857 1311867199.0148730278 0.0544677377 0.0632579284 0.0880135372 0.0054368288 0.1578470000 978794009 0 402718720 0.1733175367 -0.0730767250 -0.0826377273 858 1311867199.0468010902 0.0554795414 0.0632488627 0.0880135372 0.0054367825 0.1584180000 978796913 0 402718720 0.1715117991 -0.0722640008 -0.0835990682 859 1311867199.0849320889 0.0556850322 0.0632400573 0.0880135372 0.0054366572 0.1759800000 978800041 0 402718720 0.1704410315 -0.0710777417 -0.0843534097 860 1311867199.1149818897 0.0560949296 0.0632317490 0.0880135372 0.0054346075 0.1582710000 978802833 0 402718720 0.1684270650 -0.0705071464 -0.0856577531 861 1311867199.1465420723 0.0570649318 0.0632245866 0.0880135372 0.0054322358 0.1589980000 978805737 0 402718720 0.1658499092 -0.0693049952 -0.0870576426 862 1311867199.1823658943 0.0577386208 0.0632182224 0.0880135372 0.0054308982 0.1582860000 978808753 0 402718720 0.1638265699 -0.0678976998 -0.0882567987 863 1311867199.2146680355 0.0585872158 0.0632128562 0.0880135372 0.0054280656 0.1787870000 978811713 0 402718720 0.1611878276 -0.0673393309 -0.0897182375 864 1311867199.2467749119 0.0588870756 0.0632078495 0.0880135372 0.0054251810 0.1698510000 978814561 0 402718720 0.1595879793 -0.0664098859 -0.0907542408 865 1311867199.2833590508 0.0591913648 0.0632032062 0.0880135372 0.0054220718 0.1591580000 978817633 0 402718720 0.1578116417 -0.0654976740 -0.0918230787 866 1311867199.3159129620 0.0595414527 0.0631989778 0.0880135372 0.0054223314 0.1591550000 978820425 0 402718720 0.1559838802 -0.0653109774 -0.0931861177 867 1311867199.3465209007 0.0595137700 0.0631947273 0.0880135372 0.0054192474 0.1711780000 978823273 0 402718720 0.1547538787 -0.0648297071 -0.0944243520 868 1311867199.3829050064 0.0593780242 0.0631903302 0.0880135372 0.0054165772 0.1590010000 978826345 0 402718720 0.1532070041 -0.0641241446 -0.0956146792 869 1311867199.4147589207 0.0593900308 0.0631859570 0.0880135372 0.0054135010 0.1808100000 978829193 0 402718720 0.1511726677 -0.0642268509 -0.0968927220 870 1311867199.4512910843 0.0591248050 0.0631812890 0.0880135372 0.0054107450 0.1571770000 978832265 0 402718720 0.1492343396 -0.0634470508 -0.0982726812 871 1311867199.4837360382 0.0587952919 0.0631762534 0.0880135372 0.0054091307 0.1581740000 978835169 0 402718720 0.1477922350 -0.0635604560 -0.0991313681 872 1311867199.5150198936 0.0587644167 0.0631711940 0.0880135372 0.0054061528 0.1575910000 978838073 0 402718720 0.1458320171 -0.0635063425 -0.1000639498 873 1311867199.5544059277 0.0583159104 0.0631656324 0.0880135372 0.0054047816 0.1560460000 978841201 0 402718720 0.1441084892 -0.0628237054 -0.1009296924 874 1311867199.5835030079 0.0581729859 0.0631599200 0.0880135372 0.0054018178 0.1684260000 978844049 0 402718720 0.1416845024 -0.0622697286 -0.1018282026 875 1311867199.6158308983 0.0577154644 0.0631536977 0.0880135372 0.0053990557 0.1557980000 978846841 0 402718720 0.1396366805 -0.0617679469 -0.1024114415 876 1311867199.6538460255 0.0567012057 0.0631463319 0.0880135372 0.0053982037 0.1572630000 978849969 0 402718720 0.1385267675 -0.0618398450 -0.1027963012 877 1311867199.6824479103 0.0567613468 0.0631390514 0.0880135372 0.0053954075 0.1568940000 978852761 0 402718720 0.1361279637 -0.0614060014 -0.1034637839 878 1311867199.7146759033 0.0558385514 0.0631307365 0.0880135372 0.0053931241 0.1562140000 978855721 0 402718720 0.1348714828 -0.0609698817 -0.1040367857 879 1311867199.7511539459 0.0556723401 0.0631222514 0.0880135372 0.0053916969 0.1810180000 978858681 0 402718720 0.1325638294 -0.0605463274 -0.1043540388 880 1311867199.7826020718 0.0554634072 0.0631135481 0.0880135372 0.0053894454 0.1560060000 978861585 0 402718720 0.1303378791 -0.0605826341 -0.1049768552 881 1311867199.8150150776 0.0549467020 0.0631042782 0.0880135372 0.0053936693 0.1560970000 978864489 0 402718720 0.1282892227 -0.0604899004 -0.1055115461 882 1311867199.8519051075 0.0544766560 0.0630944963 0.0880135372 0.0053907170 0.1564090000 978867505 0 402718720 0.1267407984 -0.0597289875 -0.1059189141 883 1311867199.8839609623 0.0542269424 0.0630844537 0.0880135372 0.0053908949 0.1574370000 978870465 0 402718720 0.1245229840 -0.0602389723 -0.1063481420 884 1311867199.9148159027 0.0539587624 0.0630741306 0.0880135372 0.0053890631 0.1584190000 978873369 0 402718720 0.1222926825 -0.0603805147 -0.1068799496 885 1311867199.9520709515 0.0536675118 0.0630635016 0.0880135372 0.0053864735 0.1896270000 978876385 0 402718720 0.1208752692 -0.0598432906 -0.1071520522 886 1311867199.9828410149 0.0529832095 0.0630521243 0.0880135372 0.0053844691 0.1936720000 978879233 0 402718720 0.1197539419 -0.0602932014 -0.1074356809 887 1311867200.0144031048 0.0527499393 0.0630405097 0.0880135372 0.0053817711 0.1932590000 978882137 0 402718720 0.1174595281 -0.0598390065 -0.1078774557 888 1311867200.0539638996 0.0523496158 0.0630284704 0.0880135372 0.0053799997 0.1932990000 978885265 0 402718720 0.1158164889 -0.0587167740 -0.1079975218 889 1311867200.0830330849 0.0518709272 0.0630159197 0.0880135372 0.0053772871 0.1929980000 978888057 0 402718720 0.1145790368 -0.0593077391 -0.1081173122 890 1311867200.1174468994 0.0514595099 0.0630029350 0.0880135372 0.0053770703 0.1717910000 978891017 0 402718720 0.1123421118 -0.0589333437 -0.1082047895 891 1311867200.1517000198 0.0510551333 0.0629895255 0.0880135372 0.0053758607 0.1552710000 978893977 0 402718720 0.1107059270 -0.0584376156 -0.1080798805 892 1311867200.1853220463 0.0512409136 0.0629763545 0.0880135372 0.0053752449 0.1566550000 978896993 0 402718720 0.1083547622 -0.0588579029 -0.1081235856 893 1311867200.2179059982 0.0505147092 0.0629623996 0.0880135372 0.0053740085 0.1845330000 978899897 0 402718720 0.1080310270 -0.0580043308 -0.1078414470 894 1311867200.2522649765 0.0499858782 0.0629478845 0.0880135372 0.0053712431 0.1708730000 978902857 0 402718720 0.1065042317 -0.0581012443 -0.1075444296 895 1311867200.2825429440 0.0497066230 0.0629330898 0.0880135372 0.0053689772 0.1577990000 978905705 0 402718720 0.1043161675 -0.0579743572 -0.1073344871 896 1311867200.3148880005 0.0494047962 0.0629179913 0.0880135372 0.0053660974 0.1563400000 978908665 0 402718720 0.1034397930 -0.0573011450 -0.1066910326 897 1311867200.3514990807 0.0490505062 0.0629025314 0.0880135372 0.0053652546 0.1566940000 978911625 0 402718720 0.1013756767 -0.0579785928 -0.1064525023 898 1311867200.3837759495 0.0489931405 0.0628870421 0.0880135372 0.0053736011 0.1564360000 978914585 0 402718720 0.0992350429 -0.0574976690 -0.1060295701 899 1311867200.4162800312 0.0487942658 0.0628713661 0.0880135372 0.0053712726 0.1705800000 978917433 0 402718720 0.0981717184 -0.0574633181 -0.1055378094 900 1311867200.4522490501 0.0484145768 0.0628553030 0.0880135372 0.0053695198 0.1557440000 978920449 0 402718720 0.0951590315 -0.0578808598 -0.1055905223 901 1311867200.4850699902 0.0481049567 0.0628389319 0.0880135372 0.0053704023 0.1564380000 978923353 0 402718720 0.0925814584 -0.0577333011 -0.1053178757 902 1311867200.5143918991 0.0479099043 0.0628223809 0.0880135372 0.0053699861 0.1579080000 978926257 0 402718720 0.0907958746 -0.0582249314 -0.1047510430 903 1311867200.5505030155 0.0474793650 0.0628053897 0.0880135372 0.0053747172 0.1575590000 978929273 0 402718720 0.0872361064 -0.0580313317 -0.1044498608 904 1311867200.5832219124 0.0477654152 0.0627887526 0.0880135372 0.0053762839 0.1826410000 978932177 0 402718720 0.0850661993 -0.0580074713 -0.1039125919 905 1311867200.6145610809 0.0475546904 0.0627719193 0.0880135372 0.0053751469 0.1575640000 978935025 0 402718720 0.0824045166 -0.0582462512 -0.1035452038 906 1311867200.6504778862 0.0472135283 0.0627547467 0.0880135372 0.0053735639 0.1572740000 978938041 0 402718720 0.0795033425 -0.0580711141 -0.1031270474 907 1311867200.6851279736 0.0469432734 0.0627373140 0.0880135372 0.0053708897 0.1572480000 978941057 0 402718720 0.0768919215 -0.0578776859 -0.1028123796 908 1311867200.7189719677 0.0467990525 0.0627197609 0.0880135372 0.0053698469 0.1678460000 978944017 0 402718720 0.0734881908 -0.0578656830 -0.1026387066 909 1311867200.7503669262 0.0465242453 0.0627019440 0.0880135372 0.0053687098 0.1714520000 978946865 0 402718720 0.0711669326 -0.0576914810 -0.1022292599 910 1311867200.7832930088 0.0463796593 0.0626840074 0.0880135372 0.0053736990 0.1571200000 978949825 0 402718720 0.0686751381 -0.0575285740 -0.1018819064 911 1311867200.8181068897 0.0458637811 0.0626655440 0.0880135372 0.0053727646 0.1560280000 978952785 0 402718720 0.0657299012 -0.0579039194 -0.1015246138 912 1311867200.8501501083 0.0458720662 0.0626471301 0.0880135372 0.0053698874 0.1575280000 978955633 0 402718720 0.0637913048 -0.0573790595 -0.1010066494 913 1311867200.8845369816 0.0462316461 0.0626291503 0.0880135372 0.0053705055 0.1572350000 978958705 0 402718720 0.0604808554 -0.0573546588 -0.1004270315 914 1311867200.9194929600 0.0467527322 0.0626117801 0.0880135372 0.0053717564 0.1692790000 978961665 0 402718720 0.0573854409 -0.0577181764 -0.0999412313 915 1311867200.9512679577 0.0463421792 0.0625939991 0.0880135372 0.0053716912 0.1578860000 978964513 0 402718720 0.0552312136 -0.0580015071 -0.0995923877 916 1311867200.9856009483 0.0470155701 0.0625769921 0.0880135372 0.0053765986 0.1581250000 978967529 0 402718720 0.0529379919 -0.0582600646 -0.0995675996 917 1311867201.0184400082 0.0472380221 0.0625602647 0.0880135372 0.0053739782 0.1559870000 978970433 0 402718720 0.0509961061 -0.0585506223 -0.0995651856 918 1311867201.0555179119 0.0472449400 0.0625435814 0.0880135372 0.0053718003 0.1604750000 978973505 0 402718720 0.0494539402 -0.0585142672 -0.0997300670 919 1311867201.0825428963 0.0475370139 0.0625272521 0.0880135372 0.0053707873 0.1911320000 978976241 0 402718720 0.0475950688 -0.0589012951 -0.0998084247 920 1311867201.1193449497 0.0479003079 0.0625113533 0.0880135372 0.0053687405 0.1904930000 978979313 0 402718720 0.0462365784 -0.0585956722 -0.0997076035 921 1311867201.1506710052 0.0482311696 0.0624958482 0.0880135372 0.0053660578 0.1904330000 978982105 0 402718720 0.0446816161 -0.0583588630 -0.0997800529 922 1311867201.1830160618 0.0481438674 0.0624802821 0.0880135372 0.0053641937 0.1906550000 978985009 0 402718720 0.0435448103 -0.0585939549 -0.0998962000 923 1311867201.2196528912 0.0480673984 0.0624646668 0.0880135372 0.0053645752 0.1899250000 978987969 0 402718720 0.0421296358 -0.0585153997 -0.0999950022 924 1311867201.2503149509 0.0480848104 0.0624491042 0.0880135372 0.0053616806 0.1898220000 978990873 0 402718720 0.0410716794 -0.0582421757 -0.0999099612 925 1311867201.2824099064 0.0479826257 0.0624334647 0.0880135372 0.0053594832 0.1892530000 978993777 0 402718720 0.0394066386 -0.0581354126 -0.1000993252 926 1311867201.3180539608 0.0478998870 0.0624177697 0.0880135372 0.0053581660 0.1893580000 978996793 0 402718720 0.0373785421 -0.0585887432 -0.1003438458 927 1311867201.3522200584 0.0477682240 0.0624019666 0.0880135372 0.0053568041 0.1894470000 978999753 0 402718720 0.0355439931 -0.0577126592 -0.1007340848 928 1311867201.3842790127 0.0477180593 0.0623861434 0.0880135372 0.0053567227 0.1677280000 979002657 0 402718720 0.0336396880 -0.0567077883 -0.1007008627 929 1311867201.4198760986 0.0467714183 0.0623693353 0.0880135372 0.0053762972 0.1566530000 979005561 0 402718720 0.0309143923 -0.0572516285 -0.1012577489 930 1311867201.4558579922 0.0466144048 0.0623523945 0.0880135372 0.0053780962 0.1550350000 979008465 0 402718720 0.0281014703 -0.0562671497 -0.1015078276 931 1311867201.4853110313 0.0467614830 0.0623356481 0.0880135372 0.0053768504 0.1550680000 979011313 0 402718720 0.0251262020 -0.0548550524 -0.1015356630 932 1311867201.5198690891 0.0463026203 0.0623184453 0.0880135372 0.0053755967 0.1684510000 979014329 0 402718720 0.0224660076 -0.0546959490 -0.1016955748 933 1311867201.5527739525 0.0458139405 0.0623007556 0.0880135372 0.0053761972 0.1541010000 979017177 0 402718720 0.0204735976 -0.0546005107 -0.1018466577 934 1311867201.5840220451 0.0458011776 0.0622830901 0.0880135372 0.0053733667 0.1669180000 979020081 0 402718720 0.0186236948 -0.0542148277 -0.1020319387 935 1311867201.6197049618 0.0458814315 0.0622655482 0.0880135372 0.0053712662 0.1563840000 979023097 0 402718720 0.0163919833 -0.0539327860 -0.1023587361 936 1311867201.6515579224 0.0454284921 0.0622475599 0.0880135372 0.0053710575 0.1570240000 979025945 0 402718720 0.0153247630 -0.0540544577 -0.1026355401 937 1311867201.6839449406 0.0453279801 0.0622295027 0.0880135372 0.0053683501 0.1564460000 979028905 0 402718720 0.0129421391 -0.0534619242 -0.1030969843 938 1311867201.7189009190 0.0452514812 0.0622114024 0.0880135372 0.0053660617 0.1566210000 979031921 0 402718720 0.0123765748 -0.0524000414 -0.1032762676 939 1311867201.7507290840 0.0450371727 0.0621931125 0.0880135372 0.0053638022 0.1711170000 979034825 0 402718720 0.0100445468 -0.0523133129 -0.1036402509 940 1311867201.7858049870 0.0443017147 0.0621740791 0.0880135372 0.0053708473 0.1565170000 979037729 0 402718720 0.0085508777 -0.0518515073 -0.1038770527 941 1311867201.8190178871 0.0446656048 0.0621554729 0.0880135372 0.0053758057 0.1566950000 979040745 0 402718720 0.0072965734 -0.0503224842 -0.1038721502 942 1311867201.8505740166 0.0444446988 0.0621366716 0.0880135372 0.0053763053 0.1566070000 979043593 0 402718720 0.0056283134 -0.0502937622 -0.1041731760 943 1311867201.8862850666 0.0442960411 0.0621177526 0.0880135372 0.0053736676 0.1579580000 979046553 0 402718720 0.0050269407 -0.0501177758 -0.1044421941 944 1311867201.9195730686 0.0445713215 0.0620991653 0.0880135372 0.0053748374 0.1821470000 979049569 0 402718720 0.0036151661 -0.0493473150 -0.1046690121 945 1311867201.9516520500 0.0443802029 0.0620804151 0.0880135372 0.0053728177 0.1578840000 979052361 0 402718720 0.0026605248 -0.0494108871 -0.1052214652 946 1311867201.9894599915 0.0440901145 0.0620613978 0.0880135372 0.0053701703 0.1577250000 979055489 0 402718720 0.0022790884 -0.0493931621 -0.1058401465 947 1311867202.0184879303 0.0440053008 0.0620423312 0.0880135372 0.0053674379 0.1576010000 979058281 0 402718720 0.0010779229 -0.0489186831 -0.1064138710 948 1311867202.0507359505 0.0438715927 0.0620231638 0.0880135372 0.0053650070 0.1587600000 979061185 0 402718720 0.0007413915 -0.0483675003 -0.1069751531 949 1311867202.0866351128 0.0439211540 0.0620040889 0.0880135372 0.0053624987 0.1703720000 979064201 0 402718720 -0.0010897260 -0.0481245108 -0.1074459180 950 1311867202.1185920238 0.0434838869 0.0619845940 0.0880135372 0.0053609220 0.1581280000 979067105 0 402718720 -0.0014857099 -0.0476070940 -0.1077458560 951 1311867202.1516621113 0.0436021425 0.0619652644 0.0880135372 0.0053589471 0.1586940000 979070065 0 402718720 -0.0024440687 -0.0468070619 -0.1077656746 952 1311867202.1866259575 0.0434253439 0.0619457897 0.0880135372 0.0053561637 0.1583150000 979073025 0 402718720 -0.0030124160 -0.0465721488 -0.1078362018 953 1311867202.2191269398 0.0431384891 0.0619260549 0.0880135372 0.0053534519 0.1595450000 979075929 0 402718720 -0.0039629764 -0.0465758257 -0.1080499142 954 1311867202.2513220310 0.0428966731 0.0619061079 0.0880135372 0.0053511776 0.1596030000 979078777 0 402718720 -0.0048276624 -0.0459146686 -0.1080063358 955 1311867202.2868280411 0.0429394729 0.0618862476 0.0880135372 0.0053505570 0.1603950000 979081793 0 402718720 -0.0061622551 -0.0449325703 -0.1078777760 956 1311867202.3199880123 0.0428673215 0.0618663533 0.0880135372 0.0053500709 0.1599660000 979084697 0 402718720 -0.0073508061 -0.0455948524 -0.1081164777 957 1311867202.3523900509 0.0426315367 0.0618462542 0.0880135372 0.0053476500 0.1710740000 979087601 0 402718720 -0.0090115387 -0.0452368557 -0.1083412170 958 1311867202.3883628845 0.0423131250 0.0618258647 0.0880135372 0.0053449553 0.1604180000 979090617 0 402718720 -0.0100615881 -0.0445314907 -0.1084138528 959 1311867202.4196391106 0.0425148010 0.0618057281 0.0880135372 0.0053439965 0.1725710000 979093521 0 402718720 -0.0110819601 -0.0445334017 -0.1084442437 960 1311867202.4529430866 0.0427650958 0.0617858941 0.0880135372 0.0053417192 0.1594650000 979096425 0 402718720 -0.0116579570 -0.0447004139 -0.1083889678 961 1311867202.4875710011 0.0432842374 0.0617666416 0.0880135372 0.0053419897 0.1583160000 979099385 0 402718720 -0.0131961284 -0.0441066548 -0.1082140282 962 1311867202.5206449032 0.0432759002 0.0617474204 0.0880135372 0.0053580922 0.1594280000 979102289 0 402718720 -0.0144151244 -0.0435271859 -0.1084473953 963 1311867202.5508940220 0.0435875356 0.0617285628 0.0880135372 0.0053554414 0.1698170000 979105137 0 402718720 -0.0153449420 -0.0437333174 -0.1083155274 964 1311867202.5864949226 0.0440731049 0.0617102480 0.0880135372 0.0053672784 0.1683860000 979108209 0 402718720 -0.0164016448 -0.0438839979 -0.1085781679 965 1311867202.6185030937 0.0441484042 0.0616920492 0.0880135372 0.0053710997 0.1591270000 979111113 0 402718720 -0.0183089115 -0.0436453298 -0.1091838107 966 1311867202.6514449120 0.0439362787 0.0616736685 0.0880135372 0.0053753082 0.1588950000 979114017 0 402718720 -0.0209607426 -0.0436177067 -0.1099415496 967 1311867202.6866559982 0.0437640399 0.0616551477 0.0880135372 0.0053730074 0.1578700000 979117033 0 402718720 -0.0219415743 -0.0431834646 -0.1106581017 968 1311867202.7185359001 0.0438021943 0.0616367045 0.0880135372 0.0053706642 0.1569820000 979119937 0 402718720 -0.0234917328 -0.0438794047 -0.1116453037 969 1311867202.7507350445 0.0437782370 0.0616182747 0.0880135372 0.0053686479 0.1838330000 979122841 0 402718720 -0.0250834897 -0.0445284955 -0.1127524897 970 1311867202.7897169590 0.0438758209 0.0615999836 0.0880135372 0.0053661987 0.1557420000 979125969 0 402718720 -0.0263288096 -0.0439869203 -0.1136624217 971 1311867202.8190000057 0.0435021259 0.0615813452 0.0880135372 0.0053645562 0.1557350000 979128817 0 402718720 -0.0278563127 -0.0443243682 -0.1145338789 972 1311867202.8527579308 0.0427505039 0.0615619719 0.0880135372 0.0053618294 0.1554590000 979131721 0 402718720 -0.0292139221 -0.0446919128 -0.1153189614 973 1311867202.8873219490 0.0421170369 0.0615419874 0.0880135372 0.0053608658 0.1546670000 979134681 0 402718720 -0.0297252294 -0.0433221087 -0.1158757359 974 1311867202.9199879169 0.0421484821 0.0615220762 0.0880135372 0.0053589342 0.1662690000 979137585 0 402718720 -0.0299409404 -0.0425085053 -0.1157774851 975 1311867202.9525690079 0.0422997512 0.0615023610 0.0880135372 0.0053607318 0.1549790000 979140545 0 402718720 -0.0300381873 -0.0428443626 -0.1157197952 976 1311867202.9868710041 0.0423734896 0.0614827617 0.0880135372 0.0053630772 0.1549680000 979143505 0 402718720 -0.0304591544 -0.0426463969 -0.1152504310 977 1311867203.0202019215 0.0423016958 0.0614631291 0.0880135372 0.0053603496 0.1547780000 979146409 0 402718720 -0.0301804021 -0.0423517898 -0.1149680093 978 1311867203.0560851097 0.0424739346 0.0614437128 0.0880135372 0.0053618827 0.1578450000 979149425 0 402718720 -0.0295613594 -0.0440609157 -0.1146079078 979 1311867203.0865778923 0.0431248881 0.0614250010 0.0880135372 0.0053605201 0.1890580000 979152273 0 402718720 -0.0297900774 -0.0446822457 -0.1141711846 980 1311867203.1189930439 0.0434430875 0.0614066521 0.0880135372 0.0053634416 0.1577690000 979155177 0 402718720 -0.0300462935 -0.0454052389 -0.1138420254 981 1311867203.1549820900 0.0436795466 0.0613885816 0.0880135372 0.0053698613 0.1591550000 979158193 0 402718720 -0.0304470640 -0.0474220663 -0.1138404608 982 1311867203.1877939701 0.0443368815 0.0613712174 0.0880135372 0.0054024163 0.1692710000 979161097 0 402718720 -0.0310899112 -0.0487914272 -0.1140404195 983 1311867203.2185909748 0.0445118137 0.0613540664 0.0880135372 0.0054011792 0.1576650000 979164001 0 402718720 -0.0305769872 -0.0487364233 -0.1142697260 984 1311867203.2552030087 0.0447544567 0.0613371969 0.0880135372 0.0053995179 0.1892890000 979167017 0 402718720 -0.0301609803 -0.0497784950 -0.1144781783 985 1311867203.2864799500 0.0448440537 0.0613204526 0.0880135372 0.0053993235 0.1585540000 979169865 0 402718720 -0.0307960566 -0.0511949249 -0.1148800850 986 1311867203.3194670677 0.0446131937 0.0613035081 0.0880135372 0.0053967534 0.1578800000 979172881 0 402718720 -0.0301300958 -0.0516995229 -0.1152629480 987 1311867203.3547461033 0.0441295877 0.0612861080 0.0880135372 0.0053946660 0.1702630000 979175785 0 402718720 -0.0290386975 -0.0519338958 -0.1156415939 988 1311867203.3865599632 0.0437412001 0.0612683500 0.0880135372 0.0053971481 0.1713240000 979178689 0 402718720 -0.0290028360 -0.0531103723 -0.1160036996 989 1311867203.4183609486 0.0433759429 0.0612502586 0.0880135372 0.0054025229 0.1592990000 979181649 0 402718720 -0.0283805691 -0.0564450659 -0.1164203286 990 1311867203.4545118809 0.0431668796 0.0612319925 0.0880135372 0.0054017808 0.1590520000 979184665 0 402718720 -0.0280527845 -0.0576723106 -0.1165881902 991 1311867203.4864439964 0.0431487635 0.0612137451 0.0880135372 0.0054017479 0.1587740000 979187513 0 402718720 -0.0276909173 -0.0591180362 -0.1165689901 992 1311867203.5185539722 0.0431363434 0.0611955219 0.0880135372 0.0054038663 0.1700230000 979190473 0 402718720 -0.0281634890 -0.0618578345 -0.1171044782 993 1311867203.5560259819 0.0433457941 0.0611775463 0.0880135372 0.0054014852 0.1583800000 979193489 0 402718720 -0.0281251613 -0.0638809875 -0.1175180972 994 1311867203.5876550674 0.0433152281 0.0611595762 0.0880135372 0.0053996707 0.1709330000 979196393 0 402718720 -0.0278053433 -0.0649737120 -0.1178530380 995 1311867203.6191980839 0.0432665832 0.0611415933 0.0880135372 0.0053980156 0.1583780000 979199297 0 402718720 -0.0279228352 -0.0672280192 -0.1182105616 996 1311867203.6557719707 0.0431090407 0.0611234883 0.0880135372 0.0053953783 0.1583330000 979202257 0 402718720 -0.0277221724 -0.0698311254 -0.1187408790 997 1311867203.6866750717 0.0429110192 0.0611052210 0.0880135372 0.0053927741 0.1581390000 979205161 0 402718720 -0.0280713085 -0.0714841187 -0.1191628948 998 1311867203.7195260525 0.0431108586 0.0610871906 0.0880135372 0.0053904548 0.1569860000 979208065 0 402718720 -0.0280632544 -0.0733813271 -0.1192450002 999 1311867203.7566421032 0.0435518995 0.0610696378 0.0880135372 0.0053881279 0.1731680000 979211137 0 402718720 -0.0282488652 -0.0746146739 -0.1193507910 1000 1311867203.7867228985 0.0437838584 0.0610523520 0.0880135372 0.0053854846 0.1578520000 979213985 0 402718720 -0.0287275370 -0.0764319375 -0.1196750551 1001 1311867203.8193860054 0.0438630953 0.0610351799 0.0880135372 0.0053828704 0.1575350000 979216889 0 402718720 -0.0281453617 -0.0776782632 -0.1201439351 1002 1311867203.8572859764 0.0440238714 0.0610182026 0.0880135372 0.0053812929 0.1583450000 979219961 0 402718720 -0.0283728000 -0.0788388103 -0.1207976341 1003 1311867203.8891890049 0.0440595746 0.0610012946 0.0880135372 0.0053793624 0.1580100000 979222865 0 402718720 -0.0287836809 -0.0807755589 -0.1216605008 1004 1311867203.9188020229 0.0442352369 0.0609845954 0.0880135372 0.0053773417 0.1705150000 979225713 0 402718720 -0.0295785200 -0.0819353610 -0.1224434227 1005 1311867203.9553489685 0.0441771261 0.0609678715 0.0880135372 0.0053750464 0.1571770000 979228729 0 402718720 -0.0292664357 -0.0823720545 -0.1233197004 1006 1311867203.9866371155 0.0442281067 0.0609512316 0.0880135372 0.0053739427 0.1671940000 979231633 0 402718720 -0.0295656193 -0.0839660987 -0.1242230237 1007 1311867204.0199849606 0.0443767421 0.0609347723 0.0880135372 0.0053724336 0.1556170000 979234537 0 402718720 -0.0298539773 -0.0847966895 -0.1253515631 1008 1311867204.0551509857 0.0443847068 0.0609183536 0.0880135372 0.0053701034 0.1562020000 979237553 0 402718720 -0.0304077752 -0.0859016031 -0.1265298426 1009 1311867204.0867509842 0.0441357940 0.0609017208 0.0880135372 0.0053689869 0.1771920000 979240457 0 402718720 -0.0309711378 -0.0876654834 -0.1275891811 1010 1311867204.1191530228 0.0444730558 0.0608854548 0.0880135372 0.0053663984 0.1544980000 979243361 0 402718720 -0.0313139558 -0.0889610127 -0.1285065860 1011 1311867204.1555769444 0.0445560813 0.0608693031 0.0880135372 0.0053640557 0.1536150000 979246321 0 402718720 -0.0314043351 -0.0904531106 -0.1291988939 1012 1311867204.1876530647 0.0444843844 0.0608531124 0.0880135372 0.0053620978 0.1518340000 979249225 0 402718720 -0.0321852788 -0.0920257047 -0.1298877895 1013 1311867204.2187769413 0.0447439589 0.0608372100 0.0880135372 0.0053602166 0.1626890000 979252129 0 402718720 -0.0329881497 -0.0930490196 -0.1303235441 1014 1311867204.2566440105 0.0451302268 0.0608217199 0.0880135372 0.0053577884 0.1498280000 979255201 0 402718720 -0.0331741311 -0.0942245945 -0.1307981014 1015 1311867204.2867140770 0.0452820174 0.0608064098 0.0880135372 0.0053552121 0.1498590000 979258049 0 402718720 -0.0337764136 -0.0962570980 -0.1312351823 1016 1311867204.3204538822 0.0458785854 0.0607917171 0.0880135372 0.0053531811 0.1632370000 979260953 0 402718720 -0.0348698981 -0.0971472114 -0.1316368729 1017 1311867204.3625741005 0.0465276428 0.0607776914 0.0880135372 0.0053506759 0.1502930000 979264193 0 402718720 -0.0359197110 -0.0987069905 -0.1317989975 1018 1311867204.3869600296 0.0466767177 0.0607638398 0.0880135372 0.0053482317 0.1494500000 979266873 0 402718720 -0.0367256999 -0.0999828354 -0.1321730465 1019 1311867204.4240970612 0.0474617518 0.0607507857 0.0880135372 0.0053460450 0.1636940000 979269945 0 402718720 -0.0377675705 -0.1009760574 -0.1324918717 1020 1311867204.4549949169 0.0479986817 0.0607382837 0.0880135372 0.0053447014 0.1484840000 979272793 0 402718720 -0.0385435000 -0.1017342657 -0.1326802522 1021 1311867204.4872748852 0.0484897867 0.0607262871 0.0880135372 0.0053425324 0.1487150000 979275697 0 402718720 -0.0395892784 -0.1034334749 -0.1329718083 1022 1311867204.5237219334 0.0488341935 0.0607146510 0.0880135372 0.0053400343 0.1581680000 979278769 0 402718720 -0.0401608422 -0.1045574546 -0.1333730072 1023 1311867204.5581860542 0.0491930544 0.0607033885 0.0880135372 0.0053384115 0.1588930000 979281729 0 402718720 -0.0408143476 -0.1052816212 -0.1335995346 1024 1311867204.5878469944 0.0491915718 0.0606921464 0.0880135372 0.0053361907 0.1585310000 979284577 0 402718720 -0.0414570011 -0.1069975793 -0.1337218583 1025 1311867204.6241528988 0.0490221269 0.0606807611 0.0880135372 0.0053337748 0.1444270000 979287593 0 402718720 -0.0421670042 -0.1080677658 -0.1336831748 1026 1311867204.6541819572 0.0492821559 0.0606696513 0.0880135372 0.0053315572 0.1458540000 979495241 0 402718720 -0.0426775217 -0.1101565138 -0.1335218400 1027 1311867204.6871540546 0.0496730246 0.0606589438 0.0880135372 0.0053293387 0.1560770000 979498145 0 402718720 -0.0435818098 -0.1111839786 -0.1334158629 1028 1311867204.7225689888 0.0498811938 0.0606484596 0.0880135372 0.0053279684 0.1447530000 979501161 0 402718720 -0.0437802225 -0.1117317453 -0.1331505775 1029 1311867204.7539510727 0.0498974286 0.0606380116 0.0880135372 0.0053255385 0.1578060000 979504065 0 402718720 -0.0451747179 -0.1129482761 -0.1328390986 1030 1311867204.7878720760 0.0500833951 0.0606277644 0.0880135372 0.0053246757 0.1435810000 979507025 0 402718720 -0.0467746034 -0.1145858392 -0.1320272386 1031 1311867204.8227200508 0.0499723032 0.0606174293 0.0880135372 0.0053222362 0.1438860000 979509985 0 402718720 -0.0467936210 -0.1153933331 -0.1307416558 1032 1311867204.8542668819 0.0498245321 0.0606069710 0.0880135372 0.0053209875 0.1440270000 979512889 0 402718720 -0.0470459536 -0.1168469340 -0.1294396371 1033 1311867204.8864960670 0.0501343533 0.0605968330 0.0880135372 0.0053195109 0.1426980000 979515793 0 402718720 -0.0481686629 -0.1190421954 -0.1284616739 1034 1311867204.9220221043 0.0504869148 0.0605870555 0.0880135372 0.0053171195 0.1452240000 979518809 0 402718720 -0.0495107807 -0.1210403591 -0.1272841245 1035 1311867204.9542920589 0.0504772104 0.0605772875 0.0880135372 0.0053150785 0.1569900000 979521713 0 402718720 -0.0498860851 -0.1225274354 -0.1262906790 1036 1311867204.9865999222 0.0507297777 0.0605677822 0.0880135372 0.0053126889 0.1442120000 979524617 0 402718720 -0.0504731052 -0.1252142042 -0.1254614443 1037 1311867205.0227239132 0.0509775169 0.0605585341 0.0880135372 0.0053143853 0.1435190000 979527633 0 402718720 -0.0509066023 -0.1268146038 -0.1247180179 1038 1311867205.0550808907 0.0504987203 0.0605488426 0.0880135372 0.0053274575 0.1430600000 979530593 0 402718720 -0.0512522347 -0.1277375966 -0.1238493845 1039 1311867205.0880999565 0.0507004634 0.0605393639 0.0880135372 0.0053251426 0.1576420000 979533385 0 402718720 -0.0518321209 -0.1299874187 -0.1229832396 1040 1311867205.1232450008 0.0513521731 0.0605305300 0.0880135372 0.0053240197 0.1436440000 979536401 0 402718720 -0.0518932752 -0.1314749569 -0.1221561879 1041 1311867205.1545319557 0.0520460568 0.0605223797 0.0880135372 0.0053350924 0.1432000000 979539249 0 402718720 -0.0517171249 -0.1326458454 -0.1214380115 1042 1311867205.1863510609 0.0520502105 0.0605142491 0.0880135372 0.0053426742 0.1438910000 979542153 0 402718720 -0.0518091172 -0.1350641102 -0.1206130385 1043 1311867205.2223129272 0.0516850427 0.0605057839 0.0880135372 0.0053415027 0.1423240000 979545169 0 402718720 -0.0516312122 -0.1369694471 -0.1200463474 1044 1311867205.2541849613 0.0517955050 0.0604974407 0.0880135372 0.0053406172 0.1526320000 979548073 0 402718720 -0.0518666767 -0.1384947598 -0.1193091124 1045 1311867205.2880499363 0.0522902459 0.0604895869 0.0880135372 0.0053385632 0.1421650000 979551033 0 402718720 -0.0524900034 -0.1401112527 -0.1184829250 1046 1311867205.3218879700 0.0526917167 0.0604821320 0.0880135372 0.0053380233 0.1419810000 979553937 0 402718720 -0.0529802367 -0.1417579353 -0.1177234501 1047 1311867205.3542900085 0.0530280694 0.0604750125 0.0880135372 0.0053421099 0.1416780000 979556897 0 402718720 -0.0537682213 -0.1434759647 -0.1167953014 1048 1311867205.3862779140 0.0532215238 0.0604680912 0.0880135372 0.0053486066 0.1416060000 979559801 0 402718720 -0.0544606671 -0.1447831839 -0.1159355715 1049 1311867205.4225649834 0.0533500612 0.0604613057 0.0880135372 0.0053507461 0.1805140000 979562817 0 402718720 -0.0556478836 -0.1464896351 -0.1152082682 1050 1311867205.4540419579 0.0536229685 0.0604547930 0.0880135372 0.0053538152 0.1406480000 979565721 0 402718720 -0.0560924038 -0.1476457417 -0.1142741442 1051 1311867205.4865119457 0.0528307296 0.0604475389 0.0880135372 0.0053565015 0.1512000000 979568625 0 402718720 -0.0565606020 -0.1491668671 -0.1132723615 1052 1311867205.5230340958 0.0528670959 0.0604403331 0.0880135372 0.0053649726 0.1402380000 979571641 0 402718720 -0.0577120781 -0.1510606408 -0.1123607755 1053 1311867205.5542900562 0.0533251576 0.0604335761 0.0880135372 0.0053839623 0.1406000000 979574545 0 402718720 -0.0590738244 -0.1517777443 -0.1111977845 1054 1311867205.5866839886 0.0531631187 0.0604266781 0.0880135372 0.0053814754 0.1525670000 979577449 0 402718720 -0.0601853505 -0.1531645656 -0.1101320907 1055 1311867205.6226179600 0.0524338968 0.0604191020 0.0880135372 0.0053853850 0.1413300000 979580465 0 402718720 -0.0606560260 -0.1553836614 -0.1091868505 1056 1311867205.6555979252 0.0524367765 0.0604115430 0.0880135372 0.0053838654 0.1395720000 979583369 0 402718720 -0.0622295402 -0.1578474194 -0.1083049774 1057 1311867205.6902959347 0.0525264181 0.0604040831 0.0880135372 0.0053814030 0.1408540000 979586385 0 402718720 -0.0627403781 -0.1593783796 -0.1075441390 1058 1311867205.7222061157 0.0528113469 0.0603969066 0.0880135372 0.0053789807 0.1405970000 979589289 0 402718720 -0.0643219352 -0.1617802680 -0.1070293561 1059 1311867205.7548348904 0.0530842245 0.0603900013 0.0880135372 0.0053768551 0.1502550000 979592249 0 402718720 -0.0655604750 -0.1634898186 -0.1066188514 1060 1311867205.7906379700 0.0531513095 0.0603831724 0.0880135372 0.0053746994 0.1409720000 979595209 0 402718720 -0.0664107352 -0.1651276052 -0.1060995385 1061 1311867205.8232109547 0.0536799878 0.0603768546 0.0880135372 0.0053814825 0.1405160000 979598169 0 402718720 -0.0679075643 -0.1672609895 -0.1055781618 1062 1311867205.8554759026 0.0536618270 0.0603705316 0.0880135372 0.0053831679 0.1521490000 979601129 0 402718720 -0.0689178705 -0.1688505411 -0.1051456928 1063 1311867205.8905880451 0.0539067462 0.0603644509 0.0880135372 0.0053824856 0.1385920000 979604033 0 402718720 -0.0700850561 -0.1703409553 -0.1048099399 1064 1311867205.9223020077 0.0539114662 0.0603583860 0.0880135372 0.0053895243 0.1525250000 979606937 0 402718720 -0.0708336905 -0.1717458516 -0.1044821888 1065 1311867205.9544939995 0.0538711250 0.0603522947 0.0880135372 0.0053871995 0.1403160000 979609841 0 402718720 -0.0715645850 -0.1739670336 -0.1040721685 1066 1311867205.9905850887 0.0546801798 0.0603469738 0.0880135372 0.0053955478 0.1384980000 979612913 0 402718720 -0.0730797574 -0.1745860428 -0.1035960466 1067 1311867206.0259850025 0.0545578599 0.0603415482 0.0880135372 0.0053966609 0.1405920000 979615873 0 402718720 -0.0733524561 -0.1755348444 -0.1033475474 1068 1311867206.0604250431 0.0540598631 0.0603356665 0.0880135372 0.0054038911 0.1413790000 979618777 0 402718720 -0.0736941099 -0.1782263666 -0.1032521054 1069 1311867206.0903289318 0.0537841804 0.0603295378 0.0880135372 0.0054015277 0.1406460000 979621625 0 402718720 -0.0738834515 -0.1802743077 -0.1033023745 1070 1311867206.1227540970 0.0539742224 0.0603235983 0.0880135372 0.0053990189 0.1405080000 979624529 0 402718720 -0.0739565641 -0.1822104454 -0.1028728932 1071 1311867206.1546130180 0.0544311255 0.0603180965 0.0880135372 0.0053967859 0.1407190000 979627433 0 402718720 -0.0745987445 -0.1844553947 -0.1029896215 1072 1311867206.1903800964 0.0547433831 0.0603128962 0.0880135372 0.0053981928 0.1515690000 979630505 0 402718720 -0.0760313347 -0.1870888770 -0.1030426770 1073 1311867206.2239561081 0.0547371618 0.0603076998 0.0880135372 0.0053961545 0.1395700000 979633465 0 402718720 -0.0762525871 -0.1884960383 -0.1031728834 1074 1311867206.2553579807 0.0542860106 0.0603020930 0.0880135372 0.0053949210 0.1408990000 979636313 0 402718720 -0.0760839731 -0.1901845932 -0.1034949496 1075 1311867206.2904770374 0.0541259684 0.0602963477 0.0880135372 0.0053925258 0.1411990000 979639273 0 402718720 -0.0766273811 -0.1924075782 -0.1038477570 1076 1311867206.3222041130 0.0540837236 0.0602905739 0.0880135372 0.0053904630 0.1673350000 979642121 0 402718720 -0.0771966130 -0.1935660094 -0.1042868793 1077 1311867206.3542530537 0.0540659167 0.0602847943 0.0880135372 0.0053889981 0.1716360000 979645081 0 402718720 -0.0780042186 -0.1952604502 -0.1045297086 1078 1311867206.3900070190 0.0539390370 0.0602789077 0.0880135372 0.0053877705 0.1517240000 979648041 0 402718720 -0.0781810656 -0.1971886158 -0.1046625599 1079 1311867206.4220259190 0.0537425652 0.0602728499 0.0880135372 0.0053862967 0.1597180000 979650945 0 402718720 -0.0780425519 -0.1988420635 -0.1046922058 1080 1311867206.4542310238 0.0536001027 0.0602666715 0.0880135372 0.0053845610 0.1417130000 979653905 0 402718720 -0.0783696920 -0.2006589770 -0.1046236306 1081 1311867206.4905378819 0.0531945601 0.0602601293 0.0880135372 0.0053926814 0.1547840000 979656865 0 402718720 -0.0790013522 -0.2032122016 -0.1047349647 1082 1311867206.5250329971 0.0535186008 0.0602538986 0.0880135372 0.0053944652 0.1402330000 979659881 0 402718720 -0.0797444806 -0.2055598944 -0.1048450321 1083 1311867206.5539300442 0.0535543077 0.0602477125 0.0880135372 0.0053983959 0.1423700000 979662729 0 402718720 -0.0798391104 -0.2078729272 -0.1048287079 1084 1311867206.5921130180 0.0536212213 0.0602415995 0.0880135372 0.0053969813 0.1574990000 979665745 0 402718720 -0.0798710883 -0.2098093331 -0.1050512344 1085 1311867206.6226360798 0.0547500588 0.0602365382 0.0880135372 0.0054093062 0.1409220000 979668593 0 402718720 -0.0808810219 -0.2116389275 -0.1051947922 1086 1311867206.6566751003 0.0541841798 0.0602309651 0.0880135372 0.0054077571 0.1406470000 979671553 0 402718720 -0.0811652020 -0.2136805803 -0.1053907126 1087 1311867206.6945209503 0.0539992973 0.0602252322 0.0880135372 0.0054062957 0.1406680000 979674625 0 402718720 -0.0807884112 -0.2147275656 -0.1057285443 1088 1311867206.7248480320 0.0534144938 0.0602189723 0.0880135372 0.0054122497 0.1401590000 979677473 0 402718720 -0.0810367614 -0.2169360071 -0.1060284749 1089 1311867206.7587969303 0.0545257591 0.0602137444 0.0880135372 0.0054528823 0.1612160000 979680489 0 402718720 -0.0810040087 -0.2180451453 -0.1064223200 1090 1311867206.7902839184 0.0537603721 0.0602078239 0.0880135372 0.0054676049 0.1402780000 979683393 0 402718720 -0.0815365613 -0.2197707742 -0.1068545878 1091 1311867206.8229770660 0.0545181520 0.0602026088 0.0880135372 0.0054659470 0.1403030000 979686297 0 402718720 -0.0834261104 -0.2216793001 -0.1073850021 1092 1311867206.8605449200 0.0545218028 0.0601974066 0.0880135372 0.0054636303 0.1523110000 979689313 0 402718720 -0.0837115198 -0.2235266268 -0.1080231071 1093 1311867206.8907771111 0.0541498065 0.0601918735 0.0880135372 0.0054622203 0.1398380000 979692161 0 402718720 -0.0833536685 -0.2245550305 -0.1086457372 1094 1311867206.9225020409 0.0542007834 0.0601863972 0.0880135372 0.0054597309 0.1517050000 979695065 0 402718720 -0.0836932734 -0.2264037728 -0.1092314497 1095 1311867206.9592480659 0.0553282835 0.0601819606 0.0880135372 0.0054588843 0.1397720000 979698137 0 402718720 -0.0853535458 -0.2290614396 -0.1097480282 1096 1311867206.9948680401 0.0556949638 0.0601778666 0.0880135372 0.0054669301 0.1403940000 979701097 0 402718720 -0.0859674513 -0.2311832160 -0.1099701226 1097 1311867207.0247550011 0.0563814826 0.0601744059 0.0880135372 0.0054699362 0.1398390000 979704001 0 402718720 -0.0860477462 -0.2329602540 -0.1100002378 1098 1311867207.0597259998 0.0556588247 0.0601702934 0.0880135372 0.0054678501 0.1506460000 979707017 0 402718720 -0.0857256874 -0.2352405936 -0.1104035005 1099 1311867207.0942800045 0.0558224507 0.0601663372 0.0880135372 0.0054712513 0.1592190000 979709921 0 402718720 -0.0862834007 -0.2379798144 -0.1105480045 1100 1311867207.1229140759 0.0558056012 0.0601623729 0.0880135372 0.0054742546 0.1379530000 979712713 0 402718720 -0.0857884511 -0.2390220910 -0.1107807159 1101 1311867207.1583549976 0.0563173220 0.0601588806 0.0880135372 0.0054783430 0.1393260000 979715729 0 402718720 -0.0858736187 -0.2408206761 -0.1108447835 1102 1311867207.1904919147 0.0560060702 0.0601551121 0.0880135372 0.0054770366 0.1374230000 979718577 0 402718720 -0.0861112848 -0.2426995635 -0.1109700352 1103 1311867207.2226181030 0.0557520278 0.0601511202 0.0880135372 0.0054767699 0.1383730000 979721537 0 402718720 -0.0858314186 -0.2438827455 -0.1108886972 1104 1311867207.2604830265 0.0558802895 0.0601472517 0.0880135372 0.0054770966 0.1505930000 979724609 0 402718720 -0.0862433240 -0.2452999204 -0.1106203198 1105 1311867207.2926900387 0.0556012690 0.0601431377 0.0880135372 0.0054766476 0.1392840000 979727513 0 402718720 -0.0863961056 -0.2470560372 -0.1104724705 1106 1311867207.3235239983 0.0563309714 0.0601396909 0.0880135372 0.0054808055 0.1391270000 979730361 0 402718720 -0.0873097032 -0.2485139966 -0.1098519787 1107 1311867207.3597478867 0.0558888838 0.0601358510 0.0880135372 0.0054794560 0.1524530000 979733433 0 402718720 -0.0877228081 -0.2501723766 -0.1093937531 1108 1311867207.3901309967 0.0557775348 0.0601319175 0.0880135372 0.0054798658 0.1504120000 979736281 0 402718720 -0.0883955657 -0.2524476349 -0.1088817343 1109 1311867207.4227840900 0.0555954501 0.0601278269 0.0880135372 0.0054775856 0.1565320000 979739185 0 402718720 -0.0899145827 -0.2544769943 -0.1086919531 1110 1311867207.4586789608 0.0556670204 0.0601238081 0.0880135372 0.0054770152 0.1385800000 979742201 0 402718720 -0.0904046670 -0.2553310096 -0.1082085595 1111 1311867207.4927639961 0.0557399541 0.0601198623 0.0880135372 0.0054763266 0.1386470000 979745161 0 402718720 -0.0913925171 -0.2572561204 -0.1078868136 1112 1311867207.5237300396 0.0559075736 0.0601160742 0.0880135372 0.0054799816 0.1520980000 979748065 0 402718720 -0.0922412947 -0.2588842511 -0.1075787544 1113 1311867207.5598409176 0.0561838858 0.0601125413 0.0880135372 0.0054783228 0.1380310000 979751025 0 402718720 -0.0935749635 -0.2604120672 -0.1073577255 1114 1311867207.5944800377 0.0564653985 0.0601092673 0.0880135372 0.0054784460 0.1598720000 979754041 0 402718720 -0.0948489606 -0.2621267736 -0.1071742252 1115 1311867207.6259219646 0.0552915484 0.0601049465 0.0880135372 0.0054762257 0.1693710000 979756889 0 402718720 -0.0943907201 -0.2650421858 -0.1066470519 1116 1311867207.6592938900 0.0549788810 0.0601003533 0.0880135372 0.0054745567 0.1691930000 979759905 0 402718720 -0.0946122631 -0.2666835487 -0.1065684333 1117 1311867207.6923089027 0.0557566546 0.0600964646 0.0880135372 0.0054740508 0.1687780000 979762809 0 402718720 -0.0960494950 -0.2683868706 -0.1063000858 1118 1311867207.7238640785 0.0551750101 0.0600920625 0.0880135372 0.0054744727 0.1683570000 979765713 0 402718720 -0.0961217657 -0.2711019814 -0.1061713099 1119 1311867207.7588050365 0.0552612543 0.0600877455 0.0880135372 0.0054728322 0.1681930000 979768561 0 402718720 -0.0970186144 -0.2734735012 -0.1059743017 1120 1311867207.7921919823 0.0554245152 0.0600835819 0.0880135372 0.0054705914 0.1681640000 979771521 0 402718720 -0.0979650021 -0.2747987807 -0.1059373096 1121 1311867207.8237760067 0.0554960892 0.0600794895 0.0880135372 0.0054681770 0.1674410000 979774425 0 402718720 -0.0988372043 -0.2771271765 -0.1059024632 1122 1311867207.8608479500 0.0552668758 0.0600752002 0.0880135372 0.0054665371 0.1667310000 979777441 0 402718720 -0.0983814672 -0.2789622545 -0.1056260467 1123 1311867207.8937089443 0.0555055253 0.0600711311 0.0880135372 0.0054643316 0.1668400000 979780401 0 402718720 -0.0983517393 -0.2799467444 -0.1053574905 1124 1311867207.9244139194 0.0553316399 0.0600669144 0.0880135372 0.0054632121 0.1669590000 979783249 0 402718720 -0.0988374799 -0.2821077704 -0.1050848067 1125 1311867207.9614970684 0.0552185215 0.0600626047 0.0880135372 0.0054622804 0.1408450000 979786153 0 402718720 -0.0992291272 -0.2834731340 -0.1046902090 1126 1311867207.9914131165 0.0551818311 0.0600582701 0.0880135372 0.0054772569 0.1374820000 979789001 0 402718720 -0.0987013206 -0.2848254144 -0.1045358405 1127 1311867208.0248498917 0.0545553081 0.0600533873 0.0880135372 0.0054926515 0.1371680000 979792017 0 402718720 -0.0988483652 -0.2874485254 -0.1042559892 1128 1311867208.0618500710 0.0550215058 0.0600489264 0.0880135372 0.0054910417 0.1363880000 979794865 0 402718720 -0.0992937237 -0.2891282439 -0.1039753556 1129 1311867208.0924620628 0.0550189205 0.0600444711 0.0880135372 0.0054886294 0.1522570000 979797713 0 402718720 -0.0991829559 -0.2905156612 -0.1038116217 1130 1311867208.1276559830 0.0552529357 0.0600402308 0.0880135372 0.0054870044 0.1356190000 979800673 0 402718720 -0.1000608504 -0.2926166058 -0.1037831455 1131 1311867208.1596069336 0.0552406423 0.0600359872 0.0880135372 0.0054846983 0.1365920000 979803577 0 402718720 -0.1004280895 -0.2940469682 -0.1039498895 1132 1311867208.1905009747 0.0553081855 0.0600318107 0.0880135372 0.0054831898 0.1364340000 979806369 0 402718720 -0.1008299664 -0.2952601314 -0.1043733507 1133 1311867208.2280850410 0.0553961992 0.0600277192 0.0880135372 0.0054812889 0.1349670000 979809497 0 402718720 -0.1009112000 -0.2968346477 -0.1045248583 1134 1311867208.2581789494 0.0548077226 0.0600231160 0.0880135372 0.0054793479 0.1436680000 979812345 0 402718720 -0.1006850153 -0.2985885739 -0.1048400551 1135 1311867208.2901990414 0.0547151044 0.0600184394 0.0880135372 0.0054772878 0.1351740000 979815193 0 402718720 -0.1003090367 -0.2990774810 -0.1051543951 1136 1311867208.3270208836 0.0556854457 0.0600146251 0.0880135372 0.0054794346 0.1355550000 979818265 0 402718720 -0.1012468562 -0.3000549376 -0.1054588854 1137 1311867208.3580970764 0.0559756532 0.0600110728 0.0880135372 0.0054798772 0.1338950000 979821169 0 402718720 -0.1019671112 -0.3011905551 -0.1053795666 1138 1311867208.3910560608 0.0561359078 0.0600076676 0.0880135372 0.0054780084 0.1348010000 979824017 0 402718720 -0.1023731530 -0.3023728728 -0.1054751128 1139 1311867208.4260230064 0.0559390113 0.0600040954 0.0880135372 0.0054760926 0.1413740000 979827033 0 402718720 -0.1027934179 -0.3047097921 -0.1056210920 1140 1311867208.4577419758 0.0564703010 0.0600009956 0.0880135372 0.0054760793 0.1347140000 979829937 0 402718720 -0.1030886322 -0.3065257072 -0.1054786295 1141 1311867208.4907650948 0.0564196408 0.0599978568 0.0880135372 0.0054738915 0.1349640000 979832897 0 402718720 -0.1030042991 -0.3075031638 -0.1053058282 1142 1311867208.5257411003 0.0563800186 0.0599946889 0.0880135372 0.0054721530 0.1348140000 979835913 0 402718720 -0.1037375033 -0.3087833524 -0.1050877497 1143 1311867208.5583798885 0.0565127134 0.0599916425 0.0880135372 0.0054698323 0.1340560000 979838817 0 402718720 -0.1040724814 -0.3095627725 -0.1046143696 1144 1311867208.5904500484 0.0563639142 0.0599884714 0.0880135372 0.0054682347 0.1494490000 979841777 0 402718720 -0.1040356904 -0.3110990524 -0.1040021628 1145 1311867208.6259779930 0.0560649373 0.0599850448 0.0880135372 0.0054660827 0.1356200000 979844681 0 402718720 -0.1045252681 -0.3122768402 -0.1035953313 1146 1311867208.6582078934 0.0553552173 0.0599810048 0.0880135372 0.0054638856 0.1351740000 979847641 0 402718720 -0.1040925682 -0.3136723638 -0.1030516773 1147 1311867208.6910300255 0.0542143397 0.0599759772 0.0880135372 0.0054667873 0.1352940000 979850545 0 402718720 -0.1041285023 -0.3145441413 -0.1023235917 1148 1311867208.7262260914 0.0545382127 0.0599712404 0.0880135372 0.0054662098 0.1345950000 979853561 0 402718720 -0.1043788269 -0.3159781694 -0.1019955650 1149 1311867208.7591009140 0.0547161549 0.0599666668 0.0880135372 0.0054639440 0.1521030000 979856465 0 402718720 -0.1050762758 -0.3164175749 -0.1014208719 1150 1311867208.7909750938 0.0542822666 0.0599617239 0.0880135372 0.0054619052 0.1354090000 979859313 0 402718720 -0.1049480885 -0.3170971870 -0.1009948254 1151 1311867208.8259930611 0.0544781312 0.0599569597 0.0880135372 0.0054606787 0.1510060000 979862329 0 402718720 -0.1056957841 -0.3189159632 -0.1005390882 1152 1311867208.8588190079 0.0555695333 0.0599531511 0.0880135372 0.0054649848 0.1471710000 979865289 0 402718720 -0.1071721390 -0.3199401200 -0.0999296680 1153 1311867208.8916258812 0.0545120314 0.0599484320 0.0880135372 0.0054752345 0.1358590000 979868137 0 402718720 -0.1080544144 -0.3206261992 -0.0994753242 1154 1311867208.9275119305 0.0551745482 0.0599442952 0.0880135372 0.0054745911 0.1483510000 979871097 0 402718720 -0.1086031869 -0.3227943182 -0.0994028375 1155 1311867208.9577760696 0.0557954125 0.0599407031 0.0880135372 0.0054724274 0.1350000000 979873945 0 402718720 -0.1100153327 -0.3243921995 -0.0996010005 1156 1311867208.9911639690 0.0559894256 0.0599372850 0.0880135372 0.0054703617 0.1455660000 979876905 0 402718720 -0.1101704612 -0.3250108063 -0.0998678803 1157 1311867209.0270779133 0.0562978573 0.0599341395 0.0880135372 0.0054696853 0.1338640000 979879921 0 402718720 -0.1106103286 -0.3267888427 -0.0999568030 1158 1311867209.0579569340 0.0569948815 0.0599316013 0.0880135372 0.0054676216 0.1325040000 979882769 0 402718720 -0.1118748561 -0.3278511465 -0.1006362215 1159 1311867209.0906980038 0.0568087921 0.0599289069 0.0880135372 0.0054656658 0.1473160000 979885729 0 402718720 -0.1118276566 -0.3282972574 -0.1010844111 1160 1311867209.1260778904 0.0570057929 0.0599263869 0.0880135372 0.0054640099 0.1344500000 979888633 0 402718720 -0.1126542091 -0.3295112550 -0.1016023457 1161 1311867209.1600620747 0.0575047843 0.0599243011 0.0880135372 0.0054623279 0.1335330000 979891649 0 402718720 -0.1133045182 -0.3306905627 -0.1019788384 1162 1311867209.1917839050 0.0576620400 0.0599223543 0.0880135372 0.0054604007 0.1335650000 979894553 0 402718720 -0.1134761423 -0.3309627175 -0.1024717838 1163 1311867209.2259531021 0.0579118580 0.0599206256 0.0880135372 0.0054581582 0.1445360000 979897457 0 402718720 -0.1143625304 -0.3325530887 -0.1028664187 1164 1311867209.2580060959 0.0581304245 0.0599190876 0.0880135372 0.0054564608 0.1446440000 979900417 0 402718720 -0.1150150001 -0.3334030509 -0.1032822877 1165 1311867209.2903130054 0.0577637143 0.0599172375 0.0880135372 0.0054542519 0.1319460000 979903321 0 402718720 -0.1150017828 -0.3339589536 -0.1039560810 1166 1311867209.3274219036 0.0576254763 0.0599152720 0.0880135372 0.0054539181 0.1309550000 979906337 0 402718720 -0.1155091226 -0.3355233073 -0.1045740023 1167 1311867209.3581039906 0.0576076023 0.0599132945 0.0880135372 0.0054516496 0.1321650000 979909185 0 402718720 -0.1158610433 -0.3367227018 -0.1050471812 1168 1311867209.3937969208 0.0575009212 0.0599112292 0.0880135372 0.0054502481 0.1318260000 979912201 0 402718720 -0.1160525903 -0.3373176157 -0.1054262444 1169 1311867209.4258151054 0.0570689216 0.0599087978 0.0880135372 0.0054487677 0.1327210000 979915161 0 402718720 -0.1162879393 -0.3387713134 -0.1059511676 1170 1311867209.4581329823 0.0576355867 0.0599068548 0.0880135372 0.0054465970 0.1450560000 979918009 0 402718720 -0.1176207066 -0.3402791917 -0.1060220003 1171 1311867209.4940650463 0.0577371009 0.0599050019 0.0880135372 0.0054451832 0.1445180000 979921081 0 402718720 -0.1183001772 -0.3409426510 -0.1062553078 1172 1311867209.5258729458 0.0570980795 0.0599026070 0.0880135372 0.0054433172 0.1303090000 979923929 0 402718720 -0.1183751896 -0.3421151340 -0.1065467671 1173 1311867209.5580699444 0.0568658300 0.0599000181 0.0880135372 0.0054414133 0.1317240000 979926833 0 402718720 -0.1191566885 -0.3438385129 -0.1066086292 1174 1311867209.5939540863 0.0571854450 0.0598977058 0.0880135372 0.0054393622 0.1325440000 979929849 0 402718720 -0.1209576800 -0.3457814455 -0.1067850739 1175 1311867209.6262791157 0.0567052923 0.0598949889 0.0880135372 0.0054372532 0.1297710000 979932697 0 402718720 -0.1213377565 -0.3474926353 -0.1069884822 1176 1311867209.6582019329 0.0566164888 0.0598922010 0.0880135372 0.0054351031 0.1323770000 979935545 0 402718720 -0.1217357144 -0.3487071693 -0.1072190925 1177 1311867209.6967020035 0.0564066209 0.0598892396 0.0880135372 0.0054411512 0.1322130000 979938561 0 402718720 -0.1219389886 -0.3508418500 -0.1072623730 1178 1311867209.7262639999 0.0573841967 0.0598871131 0.0880135372 0.0054498030 0.1322250000 979941409 0 402718720 -0.1241441369 -0.3527993560 -0.1076518074 1179 1311867209.7583460808 0.0573615730 0.0598849710 0.0880135372 0.0054515935 0.1459610000 979944369 0 402718720 -0.1245896146 -0.3541581929 -0.1082303897 1180 1311867209.7959320545 0.0578152388 0.0598832170 0.0880135372 0.0054495652 0.1309070000 979947441 0 402718720 -0.1255486906 -0.3557952344 -0.1088721901 1181 1311867209.8262419701 0.0578392185 0.0598814862 0.0880135372 0.0054476938 0.1310540000 979950289 0 402718720 -0.1260232627 -0.3569996059 -0.1095547751 1182 1311867209.8588960171 0.0583257750 0.0598801701 0.0880135372 0.0054455995 0.1305170000 979953193 0 402718720 -0.1270311326 -0.3577974737 -0.1101526394 1183 1311867209.8946969509 0.0587666743 0.0598792288 0.0880135372 0.0054440480 0.1299580000 979956209 0 402718720 -0.1275316179 -0.3586550653 -0.1105871126 1184 1311867209.9268450737 0.0593248308 0.0598787606 0.0880135372 0.0054421132 0.1300360000 979959057 0 402718720 -0.1284318715 -0.3595508933 -0.1108966544 1185 1311867209.9588210583 0.0593879968 0.0598783464 0.0880135372 0.0054399801 0.1300250000 979962017 0 402718720 -0.1287950426 -0.3605452478 -0.1112139300 1186 1311867209.9942541122 0.0593583137 0.0598779080 0.0880135372 0.0054397284 0.1410630000 979965033 0 402718720 -0.1286762059 -0.3617376089 -0.1115501225 1187 1311867210.0261061192 0.0604116023 0.0598783576 0.0880135372 0.0054378719 0.1569080000 979967881 0 402718720 -0.1303905696 -0.3628650904 -0.1117692664 1188 1311867210.0603590012 0.0603189319 0.0598787284 0.0880135372 0.0054383376 0.1297820000 979970953 0 402718720 -0.1299069375 -0.3624117970 -0.1122493073 1189 1311867210.0942480564 0.0614569373 0.0598800558 0.0880135372 0.0054394779 0.1527280000 979973857 0 402718720 -0.1311473101 -0.3632513583 -0.1123244837 1190 1311867210.1280341148 0.0593178086 0.0598795833 0.0880135372 0.0054386957 0.1307960000 979976817 0 402718720 -0.1275505275 -0.3652413189 -0.1119579971 1191 1311867210.1578240395 0.0589773320 0.0598788257 0.0880135372 0.0054370990 0.1292890000 979979665 0 402718720 -0.1265429556 -0.3656338751 -0.1117771789 1192 1311867210.1943209171 0.0593732782 0.0598784016 0.0880135372 0.0054350388 0.1311890000 979982737 0 402718720 -0.1271444559 -0.3666489124 -0.1120677963 1193 1311867210.2258129120 0.0595048517 0.0598780885 0.0880135372 0.0054331752 0.1318310000 979985585 0 402718720 -0.1277957112 -0.3680093288 -0.1128206924 1194 1311867210.2579770088 0.0597184375 0.0598779548 0.0880135372 0.0054310314 0.1308810000 979988489 0 402718720 -0.1280980706 -0.3683290482 -0.1132996604 1195 1311867210.2953989506 0.0601858832 0.0598782125 0.0880135372 0.0054288427 0.1316410000 979991561 0 402718720 -0.1288404912 -0.3684635460 -0.1137871668 1196 1311867210.3271369934 0.0603578091 0.0598786135 0.0880135372 0.0054320176 0.1311400000 979994409 0 402718720 -0.1295346320 -0.3688635528 -0.1140982658 1197 1311867210.3582420349 0.0601972826 0.0598788797 0.0880135372 0.0054364542 0.1316000000 979997313 0 402718720 -0.1291864216 -0.3693842888 -0.1143305823 1198 1311867210.3937919140 0.0605313592 0.0598794243 0.0880135372 0.0054342450 0.1317330000 980000329 0 402718720 -0.1296198815 -0.3699716926 -0.1144100353 1199 1311867210.4260039330 0.0605643205 0.0598799956 0.0880135372 0.0054363126 0.1606290000 980003177 0 402718720 -0.1305000931 -0.3707053661 -0.1148573086 1200 1311867210.4581708908 0.0604125410 0.0598804393 0.0880135372 0.0054342701 0.1315850000 980006137 0 402718720 -0.1304157525 -0.3709807694 -0.1151810139 1201 1311867210.4943509102 0.0598746985 0.0598804346 0.0880135372 0.0054499242 0.1308660000 980009097 0 402718720 -0.1294008493 -0.3697024584 -0.1157605574 1202 1311867210.5261299610 0.0596141182 0.0598802130 0.0880135372 0.0054498032 0.1449190000 980012001 0 402718720 -0.1297069788 -0.3704743683 -0.1163319126 1203 1311867210.5634729862 0.0592745692 0.0598797096 0.0880135372 0.0054487191 0.1324780000 980015073 0 402718720 -0.1293234825 -0.3703516126 -0.1167161763 1204 1311867210.5943870544 0.0586000159 0.0598786467 0.0880135372 0.0054468036 0.1448600000 980017977 0 402718720 -0.1287735105 -0.3695152402 -0.1175482795 1205 1311867210.6260209084 0.0582792759 0.0598773194 0.0880135372 0.0054511474 0.1320930000 980020769 0 402718720 -0.1289201826 -0.3707017303 -0.1182210892 1206 1311867210.6675710678 0.0588499717 0.0598764676 0.0880135372 0.0054545016 0.1327410000 980024009 0 402718720 -0.1299015582 -0.3718394339 -0.1186546087 1207 1311867210.6952280998 0.0595465228 0.0598761942 0.0880135372 0.0054560257 0.1451300000 980026857 0 402718720 -0.1305747628 -0.3716223538 -0.1193141863 1208 1311867210.7260899544 0.0589864440 0.0598754576 0.0880135372 0.0054542955 0.1448160000 980029593 0 402718720 -0.1298511773 -0.3714760244 -0.1198029816 1209 1311867210.7620921135 0.0589965396 0.0598747307 0.0880135372 0.0054534862 0.1482030000 980032665 0 402718720 -0.1302441955 -0.3729810119 -0.1200126335 1210 1311867210.7943489552 0.0588041991 0.0598738459 0.0880135372 0.0054565475 0.1324280000 980035345 0 402718720 -0.1295506507 -0.3713774383 -0.1202218533 1211 1311867210.8263258934 0.0584714748 0.0598726879 0.0880135372 0.0054552834 0.1454810000 980038249 0 402718720 -0.1290679276 -0.3709745705 -0.1204131767 1212 1311867210.8623979092 0.0587393939 0.0598717528 0.0880135372 0.0054531905 0.1326040000 980041265 0 402718720 -0.1295368969 -0.3712230027 -0.1203065366 1213 1311867210.8942279816 0.0580408648 0.0598702435 0.0880135372 0.0054511370 0.1326400000 980044225 0 402718720 -0.1282893419 -0.3709966540 -0.1203473359 1214 1311867210.9288311005 0.0579140261 0.0598686321 0.0880135372 0.0054489436 0.1574570000 980047185 0 402718720 -0.1279774010 -0.3707774282 -0.1201816425 1215 1311867210.9653480053 0.0576904714 0.0598668393 0.0880135372 0.0054561580 0.1344640000 980050201 0 402718720 -0.1273163557 -0.3688649535 -0.1199285686 1216 1311867210.9945580959 0.0569139235 0.0598644110 0.0880135372 0.0054628995 0.1347340000 980053049 0 402718720 -0.1268146932 -0.3696985543 -0.1200224161 1217 1311867211.0263500214 0.0570792444 0.0598621224 0.0880135372 0.0054608916 0.1348730000 980055953 0 402718720 -0.1275903583 -0.3702616096 -0.1201179922 1218 1311867211.0651569366 0.0569542050 0.0598597350 0.0880135372 0.0054653069 0.1350920000 980059025 0 402718720 -0.1269470453 -0.3684078157 -0.1201626435 1219 1311867211.0940821171 0.0566426516 0.0598570958 0.0880135372 0.0054667653 0.1506700000 980061817 0 402718720 -0.1270447075 -0.3691088855 -0.1205756739 1220 1311867211.1266880035 0.0563526452 0.0598542233 0.0880135372 0.0054655220 0.1465470000 980064721 0 402718720 -0.1271372736 -0.3706610799 -0.1207392439 1221 1311867211.1646990776 0.0566097647 0.0598515661 0.0880135372 0.0054638174 0.1343960000 980067849 0 402718720 -0.1271803230 -0.3696493804 -0.1210760027 1222 1311867211.1946630478 0.0567664281 0.0598490415 0.0880135372 0.0054617113 0.1341860000 980070697 0 402718720 -0.1272598505 -0.3693377078 -0.1212776527 1223 1311867211.2270209789 0.0569279753 0.0598466530 0.0880135372 0.0054672008 0.1530560000 980073601 0 402718720 -0.1282722950 -0.3703753054 -0.1214484274 1224 1311867211.2645599842 0.0565779358 0.0598439825 0.0880135372 0.0054656516 0.1484170000 980076673 0 402718720 -0.1279494762 -0.3698155284 -0.1217535138 1225 1311867211.2953100204 0.0568313152 0.0598415232 0.0880135372 0.0054635771 0.1343990000 980079577 0 402718720 -0.1279151738 -0.3689583838 -0.1216819063 1226 1311867211.3262948990 0.0565687679 0.0598388537 0.0880135372 0.0054616815 0.1338210000 980082425 0 402718720 -0.1274385750 -0.3683994710 -0.1219137833 1227 1311867211.3653290272 0.0569789298 0.0598365229 0.0880135372 0.0054594803 0.1339590000 980085553 0 402718720 -0.1281051487 -0.3684432209 -0.1217763722 1228 1311867211.3949019909 0.0569539368 0.0598341755 0.0880135372 0.0054578026 0.1345960000 980088401 0 402718720 -0.1279408336 -0.3676867783 -0.1216434985 1229 1311867211.4295680523 0.0569228046 0.0598318066 0.0880135372 0.0054627951 0.1509330000 980091305 0 402718720 -0.1275346130 -0.3664586842 -0.1214614436 1230 1311867211.4645059109 0.0569288693 0.0598294465 0.0880135372 0.0054613770 0.1479760000 980094265 0 402718720 -0.1279680431 -0.3663916290 -0.1215721816 1231 1311867211.4942829609 0.0576352887 0.0598276641 0.0880135372 0.0054594240 0.1353630000 980097113 0 402718720 -0.1286094040 -0.3651387990 -0.1213821322 1232 1311867211.5279569626 0.0566754267 0.0598251055 0.0880135372 0.0054592309 0.1355460000 980100017 0 402718720 -0.1279575527 -0.3644214571 -0.1212972626 1233 1311867211.5646700859 0.0578469373 0.0598235011 0.0880135372 0.0054609755 0.1357990000 980103089 0 402718720 -0.1280978173 -0.3642486036 -0.1210418940 1234 1311867211.5967590809 0.0583097674 0.0598222744 0.0880135372 0.0054630122 0.1446770000 980105993 0 402718720 -0.1291022897 -0.3644209206 -0.1208791062 1235 1311867211.6269431114 0.0592068695 0.0598217761 0.0880135372 0.0054687284 0.1347250000 980108841 0 402718720 -0.1297316849 -0.3635874391 -0.1205319762 1236 1311867211.6620280743 0.0578914732 0.0598202144 0.0880135372 0.0054797559 0.1353420000 980111857 0 402718720 -0.1285498887 -0.3629618287 -0.1205881760 1237 1311867211.6944348812 0.0583663359 0.0598190390 0.0880135372 0.0054814415 0.1345830000 980114761 0 402718720 -0.1291612536 -0.3630109727 -0.1208328605 1238 1311867211.7267570496 0.0578044616 0.0598174118 0.0880135372 0.0054800548 0.1337710000 980117609 0 402718720 -0.1284159720 -0.3627446592 -0.1210714430 1239 1311867211.7642099857 0.0576162636 0.0598156352 0.0880135372 0.0054781930 0.1418180000 980120737 0 402718720 -0.1275061816 -0.3628223836 -0.1213722900 1240 1311867211.7948160172 0.0576566830 0.0598138941 0.0880135372 0.0054767302 0.1345850000 980123473 0 402718720 -0.1271957159 -0.3623345792 -0.1218578666 1241 1311867211.8337268829 0.0583125576 0.0598126843 0.0880135372 0.0054747573 0.1468910000 980126545 0 402718720 -0.1276957244 -0.3620018065 -0.1222826764 1242 1311867211.8630928993 0.0589976870 0.0598120281 0.0880135372 0.0054734083 0.1342120000 980129393 0 402718720 -0.1280004531 -0.3607313335 -0.1224225834 1243 1311867211.8967690468 0.0586610138 0.0598111021 0.0880135372 0.0054712180 0.1339930000 980132297 0 402718720 -0.1274889559 -0.3596164584 -0.1228219122 1244 1311867211.9324300289 0.0590608977 0.0598104991 0.0880135372 0.0054711744 0.1494580000 980135313 0 402718720 -0.1280985475 -0.3592447042 -0.1234659702 1245 1311867211.9653239250 0.0591257885 0.0598099491 0.0880135372 0.0054690243 0.1341390000 980138273 0 402718720 -0.1277671158 -0.3585325480 -0.1238705814 1246 1311867211.9972860813 0.0590899922 0.0598093713 0.0880135372 0.0054671212 0.1467620000 980141121 0 402718720 -0.1271627545 -0.3563388586 -0.1244100928 1247 1311867212.0317659378 0.0593715422 0.0598090202 0.0880135372 0.0054651266 0.1342680000 980144137 0 402718720 -0.1272333860 -0.3556343615 -0.1247294396 1248 1311867212.0621519089 0.0598017909 0.0598090144 0.0880135372 0.0054630730 0.1341780000 980146985 0 402718720 -0.1278980970 -0.3550858200 -0.1251504272 1249 1311867212.0954549313 0.0592524186 0.0598085688 0.0880135372 0.0054633593 0.1445650000 980149889 0 402718720 -0.1262797713 -0.3529731333 -0.1252104044 1250 1311867212.1331028938 0.0586537346 0.0598076449 0.0880135372 0.0054632729 0.1339250000 980152961 0 402718720 -0.1253951341 -0.3514020741 -0.1256096065 1251 1311867212.1668488979 0.0590239279 0.0598070184 0.0880135372 0.0054619827 0.1465520000 980155865 0 402718720 -0.1259199381 -0.3507725298 -0.1260205507 1252 1311867212.1945068836 0.0591079555 0.0598064601 0.0880135372 0.0054601022 0.1344870000 980158657 0 402718720 -0.1255335361 -0.3499954939 -0.1262942553 1253 1311867212.2301759720 0.0591963083 0.0598059731 0.0880135372 0.0054606348 0.1351340000 980161617 0 402718720 -0.1251369864 -0.3485527337 -0.1270654052 1254 1311867212.2647190094 0.0592776649 0.0598055518 0.0880135372 0.0054605569 0.1449050000 980164633 0 402718720 -0.1247527376 -0.3479855657 -0.1278706491 1255 1311867212.2944819927 0.0593710281 0.0598052056 0.0880135372 0.0054585099 0.1331470000 980167481 0 402718720 -0.1246237680 -0.3469816148 -0.1288145036 1256 1311867212.3326430321 0.0590886027 0.0598046350 0.0880135372 0.0054572299 0.1512520000 980170553 0 402718720 -0.1238559484 -0.3451791704 -0.1296724677 1257 1311867212.3653640747 0.0589077361 0.0598039215 0.0880135372 0.0054551615 0.1631520000 980173457 0 402718720 -0.1233232543 -0.3433305621 -0.1304612607 1258 1311867212.3955509663 0.0596645772 0.0598038108 0.0880135372 0.0054715285 0.1635430000 980176305 0 402718720 -0.1233022809 -0.3417423368 -0.1310886294 1259 1311867212.4329519272 0.0588959269 0.0598030896 0.0880135372 0.0054896901 0.1628110000 980179377 0 402718720 -0.1226796433 -0.3402603269 -0.1316412538 1260 1311867212.4622640610 0.0593864918 0.0598027590 0.0880135372 0.0054980077 0.1633230000 980182225 0 402718720 -0.1226826981 -0.3385652602 -0.1319878548 1261 1311867212.4944300652 0.0593254827 0.0598023805 0.0880135372 0.0055019321 0.1536630000 980185129 0 402718720 -0.1221593842 -0.3377988338 -0.1325431615 1262 1311867212.5300269127 0.0594378151 0.0598020916 0.0880135372 0.0055006387 0.1347200000 980188145 0 402718720 -0.1217395961 -0.3371551335 -0.1332981586 1263 1311867212.5625970364 0.0597501770 0.0598020505 0.0880135372 0.0055094348 0.1342180000 980191049 0 402718720 -0.1209509298 -0.3364028335 -0.1341442019 1264 1311867212.5948359966 0.0591912307 0.0598015673 0.0880135372 0.0055087280 0.1447140000 980193953 0 402718720 -0.1195601821 -0.3358491957 -0.1351057291 1265 1311867212.6323919296 0.0579057336 0.0598000686 0.0880135372 0.0055085717 0.1343120000 980196913 0 402718720 -0.1166168675 -0.3358996809 -0.1358671784 1266 1311867212.6629829407 0.0574618466 0.0597982217 0.0880135372 0.0055114115 0.1338470000 980199761 0 402718720 -0.1150048077 -0.3343137503 -0.1366530955 1267 1311867212.6944150925 0.0575610921 0.0597964560 0.0880135372 0.0055095712 0.1336290000 980202721 0 402718720 -0.1142985895 -0.3330821693 -0.1374815702 1268 1311867212.7323219776 0.0574948974 0.0597946409 0.0880135372 0.0055084117 0.1325080000 980205737 0 402718720 -0.1136932746 -0.3323999047 -0.1383377463 1269 1311867212.7618949413 0.0577669367 0.0597930430 0.0880135372 0.0055065104 0.1446200000 980208529 0 402718720 -0.1139702275 -0.3308536112 -0.1391944736 1270 1311867212.7951610088 0.0579051152 0.0597915564 0.0880135372 0.0055043699 0.1332390000 980211489 0 402718720 -0.1138188541 -0.3297471404 -0.1397751719 1271 1311867212.8303771019 0.0580874793 0.0597902157 0.0880135372 0.0055023274 0.1328350000 980214561 0 402718720 -0.1135212407 -0.3287529945 -0.1406366974 1272 1311867212.8625240326 0.0583799109 0.0597891070 0.0880135372 0.0055024669 0.1333080000 980217409 0 402718720 -0.1133407950 -0.3283717930 -0.1415411532 1273 1311867212.8941800594 0.0582435317 0.0597878928 0.0880135372 0.0055120312 0.1331520000 980220313 0 402718720 -0.1129280701 -0.3268938959 -0.1425530016 1274 1311867212.9306590557 0.0574974231 0.0597860950 0.0880135372 0.0055207977 0.1587560000 980223329 0 402718720 -0.1121820733 -0.3252951503 -0.1433468312 1275 1311867212.9621579647 0.0574921072 0.0597842958 0.0880135372 0.0055386565 0.1323010000 980226233 0 402718720 -0.1110098958 -0.3238011003 -0.1442598253 1276 1311867212.9971981049 0.0575642064 0.0597825559 0.0880135372 0.0055413387 0.1306810000 980229193 0 402718720 -0.1101099104 -0.3222780526 -0.1450025588 1277 1311867213.0305559635 0.0575491115 0.0597808069 0.0880135372 0.0055439040 0.1321560000 980232209 0 402718720 -0.1099280566 -0.3213844299 -0.1454712152 1278 1311867213.0622329712 0.0577927046 0.0597792513 0.0880135372 0.0055423142 0.1306180000 980235057 0 402718720 -0.1095837280 -0.3205987513 -0.1458582878 1279 1311867213.0985310078 0.0573162287 0.0597773256 0.0880135372 0.0055405650 0.1329510000 980238073 0 402718720 -0.1083093733 -0.3193223178 -0.1465691626 1280 1311867213.1321671009 0.0573616326 0.0597754383 0.0880135372 0.0055384101 0.1310120000 980241033 0 402718720 -0.1070714593 -0.3182286322 -0.1472065300 1281 1311867213.1642329693 0.0579783618 0.0597740354 0.0880135372 0.0055364503 0.1324290000 980243937 0 402718720 -0.1070555523 -0.3172742128 -0.1478679031 1282 1311867213.1981649399 0.0583609566 0.0597729332 0.0880135372 0.0055371574 0.1324640000 980246897 0 402718720 -0.1074015647 -0.3168533146 -0.1488315463 1283 1311867213.2303979397 0.0596155524 0.0597728105 0.0880135372 0.0055355750 0.1447100000 980249801 0 402718720 -0.1079392433 -0.3156877756 -0.1492337883 1284 1311867213.2621340752 0.0594028607 0.0597725224 0.0880135372 0.0055335988 0.1473380000 980252705 0 402718720 -0.1067651585 -0.3140933812 -0.1502723098 1285 1311867213.2983639240 0.0597418174 0.0597724985 0.0880135372 0.0055317985 0.1316200000 980255721 0 402718720 -0.1066322625 -0.3133296072 -0.1510799825 1286 1311867213.3312969208 0.0595364496 0.0597723149 0.0880135372 0.0055314534 0.1322520000 980258681 0 402718720 -0.1058825180 -0.3112300634 -0.1516403556 1287 1311867213.3622069359 0.0590704307 0.0597717696 0.0880135372 0.0055294842 0.1449930000 980261529 0 402718720 -0.1051946729 -0.3091059923 -0.1524794549 1288 1311867213.3980619907 0.0595700853 0.0597716130 0.0880135372 0.0055275229 0.1324970000 980264545 0 402718720 -0.1048898548 -0.3077321351 -0.1526698470 1289 1311867213.4303960800 0.0590592399 0.0597710603 0.0880135372 0.0055262266 0.1429460000 980267505 0 402718720 -0.1031814143 -0.3058888018 -0.1529438645 1290 1311867213.4620630741 0.0594067425 0.0597707779 0.0880135372 0.0055245134 0.1318560000 980270353 0 402718720 -0.1032553911 -0.3045012057 -0.1533729136 1291 1311867213.4981389046 0.0591357835 0.0597702861 0.0880135372 0.0055274193 0.1603400000 980273369 0 402718720 -0.1028434113 -0.3024047017 -0.1537422985 1292 1311867213.5318338871 0.0584115721 0.0597692344 0.0880135372 0.0055281313 0.1601020000 980276329 0 402718720 -0.1017050222 -0.3003600240 -0.1539548039 1293 1311867213.5621318817 0.0577958636 0.0597677082 0.0880135372 0.0055260411 0.1317670000 980279177 0 402718720 -0.1003592014 -0.2987513542 -0.1540004313 1294 1311867213.5989580154 0.0576096028 0.0597660404 0.0880135372 0.0055282657 0.1454100000 980282249 0 402718720 -0.0996317789 -0.2965261936 -0.1541076899 1295 1311867213.6327760220 0.0573969930 0.0597642111 0.0880135372 0.0055264185 0.1334570000 980285153 0 402718720 -0.0986329615 -0.2935349047 -0.1541833133 1296 1311867213.6623249054 0.0579968281 0.0597628473 0.0880135372 0.0055262563 0.1332220000 980288001 0 402718720 -0.0984798372 -0.2914108336 -0.1540067792 1297 1311867213.6987268925 0.0583232529 0.0597617374 0.0880135372 0.0055252338 0.1332010000 980291017 0 402718720 -0.0978758633 -0.2890723646 -0.1537651867 1298 1311867213.7312800884 0.0582161769 0.0597605467 0.0880135372 0.0055295556 0.1317910000 980293977 0 402718720 -0.0964689627 -0.2871720493 -0.1536361128 1299 1311867213.7623159885 0.0576272309 0.0597589044 0.0880135372 0.0055374396 0.1459070000 980296825 0 402718720 -0.0952823609 -0.2853513956 -0.1531650722 1300 1311867213.7984969616 0.0577738732 0.0597573775 0.0880135372 0.0055355589 0.1345960000 980299729 0 402718720 -0.0944538787 -0.2830162644 -0.1528091431 1301 1311867213.8303530216 0.0572432056 0.0597554450 0.0880135372 0.0055336952 0.1352270000 980302633 0 402718720 -0.0923807770 -0.2813415527 -0.1523053795 1302 1311867213.8669381142 0.0579725020 0.0597540756 0.0880135372 0.0055349040 0.1343840000 980305649 0 402718720 -0.0929233357 -0.2813794613 -0.1520942450 1303 1311867213.8988749981 0.0586593524 0.0597532354 0.0880135372 0.0055332069 0.1341580000 980308553 0 402718720 -0.0928822681 -0.2798118591 -0.1520281434 1304 1311867213.9324591160 0.0588583313 0.0597525491 0.0880135372 0.0055326498 0.1489790000 980311457 0 402718720 -0.0922362432 -0.2773337364 -0.1519259214 1305 1311867213.9625511169 0.0588165931 0.0597518319 0.0880135372 0.0055311349 0.1470680000 980314305 0 402718720 -0.0915038362 -0.2763998210 -0.1523947716 1306 1311867214.0014989376 0.0595431589 0.0597516722 0.0880135372 0.0055301340 0.1345360000 980317489 0 402718720 -0.0914277211 -0.2751117051 -0.1529652923 1307 1311867214.0316550732 0.0591054223 0.0597511777 0.0880135372 0.0055313752 0.1337920000 980320281 0 402718720 -0.0908692777 -0.2731683254 -0.1533559263 1308 1311867214.0640029907 0.0588296279 0.0597504731 0.0880135372 0.0055298654 0.1348380000 980323241 0 402718720 -0.0894375667 -0.2708478868 -0.1536770165 1309 1311867214.0984749794 0.0588685945 0.0597497994 0.0880135372 0.0055282540 0.1463480000 980326201 0 402718720 -0.0887444243 -0.2695569992 -0.1540419906 1310 1311867214.1326990128 0.0592805222 0.0597494412 0.0880135372 0.0055280761 0.1349050000 980329105 0 402718720 -0.0884774104 -0.2679749131 -0.1540927291 1311 1311867214.1643800735 0.0595737025 0.0597493072 0.0880135372 0.0055285224 0.1345890000 980332065 0 402718720 -0.0881216377 -0.2662478387 -0.1539482921 1312 1311867214.2013020515 0.0594507009 0.0597490796 0.0880135372 0.0055267247 0.1349120000 980335025 0 402718720 -0.0877786055 -0.2651907206 -0.1542549580 1313 1311867214.2338430882 0.0600847602 0.0597493352 0.0880135372 0.0055248185 0.1349270000 980337985 0 402718720 -0.0881590992 -0.2639729083 -0.1540995389 1314 1311867214.2674899101 0.0599347726 0.0597494764 0.0880135372 0.0055229978 0.1365730000 980340945 0 402718720 -0.0876581445 -0.2625845075 -0.1542449743 1315 1311867214.3004720211 0.0596400537 0.0597493931 0.0880135372 0.0055210541 0.1355140000 980343849 0 402718720 -0.0871384218 -0.2606936991 -0.1543701738 1316 1311867214.3310549259 0.0594824627 0.0597491903 0.0880135372 0.0055190145 0.1348450000 980346697 0 402718720 -0.0869618356 -0.2597098947 -0.1547921598 1317 1311867214.3663671017 0.0599709973 0.0597493587 0.0880135372 0.0055188586 0.1342480000 980349713 0 402718720 -0.0870049968 -0.2583478987 -0.1549777538 1318 1311867214.3980031013 0.0603699125 0.0597498296 0.0880135372 0.0055169074 0.1346670000 980352617 0 402718720 -0.0868917480 -0.2575339675 -0.1554181725 1319 1311867214.4332211018 0.0602705590 0.0597502243 0.0880135372 0.0055163384 0.1454120000 980355577 0 402718720 -0.0863903463 -0.2565060258 -0.1560575068 1320 1311867214.4698181152 0.0603088066 0.0597506475 0.0880135372 0.0055186206 0.1350270000 980358761 0 402718720 -0.0860345513 -0.2550381422 -0.1566134244 1321 1311867214.5059390068 0.0601800308 0.0597509726 0.0880135372 0.0055188573 0.1335150000 980361777 0 402718720 -0.0846916437 -0.2535463572 -0.1569267064 1322 1311867214.5373690128 0.0599318892 0.0597511094 0.0880135372 0.0055178218 0.1346120000 980364681 0 402718720 -0.0835678503 -0.2515925169 -0.1572721899 1323 1311867214.5691421032 0.0597796552 0.0597511310 0.0880135372 0.0055162651 0.1471560000 980367585 0 402718720 -0.0830120444 -0.2496514320 -0.1575164795 1324 1311867214.6048638821 0.0597526170 0.0597511321 0.0880135372 0.0055146785 0.1349180000 980370601 0 402718720 -0.0824143440 -0.2475081533 -0.1578035504 1325 1311867214.6369891167 0.0595059954 0.0597509471 0.0880135372 0.0055143341 0.1460430000 980373449 0 402718720 -0.0815848187 -0.2468398958 -0.1578628570 1326 1311867214.6691009998 0.0595986471 0.0597508322 0.0880135372 0.0055126474 0.1347010000 980376409 0 402718720 -0.0809527561 -0.2451849282 -0.1579680145 1327 1311867214.7048900127 0.0603847280 0.0597513099 0.0880135372 0.0055115244 0.1453530000 980379369 0 402718720 -0.0805556029 -0.2445029765 -0.1580954045 1328 1311867214.7369639874 0.0605510995 0.0597519122 0.0880135372 0.0055156875 0.1350840000 980382273 0 402718720 -0.0801894739 -0.2428203374 -0.1582859308 1329 1311867214.7695059776 0.0601125285 0.0597521835 0.0880135372 0.0055163453 0.1350920000 980385233 0 402718720 -0.0790973976 -0.2418238223 -0.1584502012 1330 1311867214.8049929142 0.0602579229 0.0597525638 0.0880135372 0.0055154084 0.1350330000 980388249 0 402718720 -0.0790064707 -0.2401109785 -0.1593222171 1331 1311867214.8369181156 0.0598000698 0.0597525995 0.0880135372 0.0055158211 0.1546650000 980391097 0 402718720 -0.0782620236 -0.2397472709 -0.1596848369 1332 1311867214.8699979782 0.0603492148 0.0597530474 0.0880135372 0.0055146309 0.1622500000 980394057 0 402718720 -0.0782084763 -0.2378233969 -0.1598402411 1333 1311867214.9049839973 0.0596389808 0.0597529618 0.0880135372 0.0055128180 0.1645060000 980397073 0 402718720 -0.0768313333 -0.2357783914 -0.1603631675 1334 1311867214.9372529984 0.0594721138 0.0597527513 0.0880135372 0.0055129249 0.1649930000 980399977 0 402718720 -0.0761040226 -0.2344600111 -0.1609013081 1335 1311867214.9693040848 0.0593769327 0.0597524698 0.0880135372 0.0055118411 0.1640870000 980402881 0 402718720 -0.0754448324 -0.2322840095 -0.1611105800 1336 1311867215.0050640106 0.0589128099 0.0597518413 0.0880135372 0.0055099481 0.1647610000 980405953 0 402718720 -0.0741832256 -0.2295094877 -0.1610461324 1337 1311867215.0371069908 0.0587182306 0.0597510682 0.0880135372 0.0055091685 0.1653910000 980408745 0 402718720 -0.0743893236 -0.2286600918 -0.1614224017 1338 1311867215.0692911148 0.0587899536 0.0597503499 0.0880135372 0.0055076681 0.1659580000 980411705 0 402718720 -0.0740801096 -0.2262291610 -0.1612082869 1339 1311867215.1050040722 0.0582119711 0.0597492010 0.0880135372 0.0055072176 0.1669470000 980414721 0 402718720 -0.0728971958 -0.2233895510 -0.1609255821 1340 1311867215.1369140148 0.0573860593 0.0597474374 0.0880135372 0.0055053196 0.1678080000 980417569 0 402718720 -0.0712016821 -0.2219735831 -0.1603669077 1341 1311867215.1694459915 0.0575278550 0.0597457823 0.0880135372 0.0055046440 0.1678790000 980420585 0 402718720 -0.0708169043 -0.2211720049 -0.1600679159 1342 1311867215.2049460411 0.0567888133 0.0597435789 0.0880135372 0.0055037976 0.1418980000 980423545 0 402718720 -0.0698326975 -0.2186850607 -0.1598350853 1343 1311867215.2369511127 0.0568507686 0.0597414249 0.0880135372 0.0055018851 0.1366220000 980426393 0 402718720 -0.0693408400 -0.2172736079 -0.1596111953 1344 1311867215.2690820694 0.0569197014 0.0597393254 0.0880135372 0.0055000448 0.1381790000 980429353 0 402718720 -0.0695175305 -0.2165447772 -0.1593152583 1345 1311867215.3049569130 0.0571918413 0.0597374313 0.0880135372 0.0054995903 0.1498460000 980432369 0 402718720 -0.0688766316 -0.2143007815 -0.1594067067 1346 1311867215.3369619846 0.0573965944 0.0597356922 0.0880135372 0.0054985427 0.1508450000 980435273 0 402718720 -0.0687454492 -0.2130186558 -0.1594963819 1347 1311867215.3691840172 0.0568864346 0.0597335770 0.0880135372 0.0054992033 0.1394720000 980438177 0 402718720 -0.0684475973 -0.2123348713 -0.1595592350 1348 1311867215.4049520493 0.0568117760 0.0597314095 0.0880135372 0.0054982020 0.1396990000 980441193 0 402718720 -0.0671807677 -0.2099748552 -0.1597506851 1349 1311867215.4370350838 0.0567225069 0.0597291790 0.0880135372 0.0054965588 0.1516930000 980444041 0 402718720 -0.0660336986 -0.2083741426 -0.1600749046 1350 1311867215.4690899849 0.0570473336 0.0597271924 0.0880135372 0.0054965767 0.1398980000 980447001 0 402718720 -0.0653324276 -0.2070317566 -0.1603498012 1351 1311867215.5049800873 0.0569669455 0.0597251493 0.0880135372 0.0054968615 0.1396130000 980450017 0 402718720 -0.0644610673 -0.2052885443 -0.1605183333 1352 1311867215.5371229649 0.0566331483 0.0597228623 0.0880135372 0.0054950448 0.1502190000 980452865 0 402718720 -0.0637250841 -0.2030555904 -0.1610122174 1353 1311867215.5690340996 0.0567606501 0.0597206730 0.0880135372 0.0054937606 0.1394710000 980455825 0 402718720 -0.0631005615 -0.2021224350 -0.1613075584 1354 1311867215.6050848961 0.0569530316 0.0597186289 0.0880135372 0.0054926005 0.1404340000 980458841 0 402718720 -0.0622927770 -0.2001383901 -0.1612251252 1355 1311867215.6370549202 0.0561858639 0.0597160217 0.0880135372 0.0054913466 0.1386260000 980461745 0 402718720 -0.0604377016 -0.1974230409 -0.1609253585 1356 1311867215.6689219475 0.0559148900 0.0597132185 0.0880135372 0.0054898542 0.1399800000 980464649 0 402718720 -0.0601543263 -0.1966315955 -0.1610740572 1357 1311867215.7049510479 0.0559811369 0.0597104683 0.0880135372 0.0054895870 0.1402720000 980467665 0 402718720 -0.0598068386 -0.1950720996 -0.1612681150 1358 1311867215.7388830185 0.0556179211 0.0597074546 0.0880135372 0.0054880594 0.1401740000 980470625 0 402718720 -0.0586747341 -0.1922717243 -0.1611913741 1359 1311867215.7691988945 0.0556777678 0.0597044894 0.0880135372 0.0054861847 0.1408920000 980473361 0 402718720 -0.0585603192 -0.1908645928 -0.1611631513 1360 1311867215.8048830032 0.0552966595 0.0597012484 0.0880135372 0.0054877533 0.1408670000 980476377 0 402718720 -0.0578714982 -0.1900842786 -0.1612531543 1361 1311867215.8373351097 0.0554250218 0.0596981064 0.0880135372 0.0054863587 0.1413870000 980479281 0 402718720 -0.0575288497 -0.1887346655 -0.1613814086 1362 1311867215.8691670895 0.0559560992 0.0596953590 0.0880135372 0.0054847407 0.1418050000 980482241 0 402718720 -0.0574086346 -0.1876237094 -0.1616481394 1363 1311867215.9052760601 0.0564593151 0.0596929848 0.0880135372 0.0054829942 0.1414520000 980485257 0 402718720 -0.0582278147 -0.1876690239 -0.1620397419 1364 1311867215.9370880127 0.0559929311 0.0596902721 0.0880135372 0.0054810057 0.1407600000 980488105 0 402718720 -0.0571383201 -0.1870633811 -0.1625207216 1365 1311867215.9702870846 0.0561173037 0.0596876546 0.0880135372 0.0054790829 0.1677080000 980491065 0 402718720 -0.0568412989 -0.1855267584 -0.1626969725 1366 1311867216.0050790310 0.0562006198 0.0596851018 0.0880135372 0.0054783483 0.1528860000 980494081 0 402718720 -0.0568452515 -0.1845412999 -0.1632712632 1367 1311867216.0369679928 0.0561555400 0.0596825199 0.0880135372 0.0054764849 0.1418270000 980496929 0 402718720 -0.0562153868 -0.1834749430 -0.1635815054 1368 1311867216.0694830418 0.0557522923 0.0596796469 0.0880135372 0.0054755182 0.1410800000 980499889 0 402718720 -0.0553301945 -0.1824428141 -0.1638200283 1369 1311867216.1050429344 0.0558357723 0.0596768391 0.0880135372 0.0054739105 0.1402880000 980502905 0 402718720 -0.0545381531 -0.1808525473 -0.1634947211 1370 1311867216.1392951012 0.0554093048 0.0596737241 0.0880135372 0.0054721670 0.1528330000 980505865 0 402718720 -0.0537526943 -0.1796440929 -0.1635183692 1371 1311867216.1692190170 0.0552480966 0.0596704961 0.0880135372 0.0054710628 0.1526070000 980508713 0 402718720 -0.0531481318 -0.1777587831 -0.1632971019 1372 1311867216.2049610615 0.0547175631 0.0596668861 0.0880135372 0.0054691508 0.1442980000 980511729 0 402718720 -0.0518392846 -0.1752501577 -0.1631090641 1373 1311867216.2370231152 0.0545810349 0.0596631819 0.0880135372 0.0054681640 0.1445500000 980514577 0 402718720 -0.0516730398 -0.1745409518 -0.1623951793 1374 1311867216.2706630230 0.0546792559 0.0596595546 0.0880135372 0.0054678549 0.1448390000 980517593 0 402718720 -0.0517043062 -0.1731520295 -0.1617486179 1375 1311867216.3050479889 0.0544127375 0.0596557387 0.0880135372 0.0054660298 0.1456490000 980520553 0 402718720 -0.0507960506 -0.1708200872 -0.1611255258 1376 1311867216.3395419121 0.0536834635 0.0596513984 0.0880135372 0.0054657697 0.1572560000 980523569 0 402718720 -0.0499819070 -0.1691207886 -0.1607781202 1377 1311867216.3694689274 0.0533430465 0.0596468171 0.0880135372 0.0054639365 0.1454780000 980526361 0 402718720 -0.0490210690 -0.1678220630 -0.1602324247 1378 1311867216.4055120945 0.0534252562 0.0596423022 0.0880135372 0.0054620091 0.1463200000 980529433 0 402718720 -0.0487251617 -0.1664885581 -0.1597040296 1379 1311867216.4373409748 0.0530995019 0.0596375576 0.0880135372 0.0054600584 0.1468070000 980532225 0 402718720 -0.0482332706 -0.1651676744 -0.1595243812 1380 1311867216.4697530270 0.0529521815 0.0596327132 0.0880135372 0.0054583122 0.1472300000 980535241 0 402718720 -0.0481968634 -0.1632163972 -0.1592949182 1381 1311867216.5049800873 0.0526556373 0.0596276610 0.0880135372 0.0054571732 0.1547450000 980538201 0 402718720 -0.0467224345 -0.1617713869 -0.1588299423 1382 1311867216.5372259617 0.0529431552 0.0596228241 0.0880135372 0.0054553418 0.1464400000 980541105 0 402718720 -0.0464764759 -0.1613644809 -0.1583415568 1383 1311867216.5693330765 0.0531673282 0.0596181564 0.0880135372 0.0054535704 0.1468700000 980544009 0 402718720 -0.0468957201 -0.1602234095 -0.1581681520 1384 1311867216.6050319672 0.0534933358 0.0596137309 0.0880135372 0.0054539345 0.1455120000 980547025 0 402718720 -0.0462937616 -0.1591213793 -0.1576752067 1385 1311867216.6373488903 0.0533958785 0.0596092415 0.0880135372 0.0054529967 0.1466620000 980549929 0 402718720 -0.0451188087 -0.1581452936 -0.1574856788 1386 1311867216.6691188812 0.0541188568 0.0596052802 0.0880135372 0.0054516148 0.1585410000 980552833 0 402718720 -0.0458074510 -0.1577706784 -0.1574868709 1387 1311867216.7052359581 0.0535997637 0.0596009503 0.0880135372 0.0054503213 0.1474210000 980555849 0 402718720 -0.0447423607 -0.1564824879 -0.1573734730 1388 1311867216.7372078896 0.0538372695 0.0595967978 0.0880135372 0.0054489157 0.1485550000 980558697 0 402718720 -0.0445949584 -0.1552805454 -0.1573729962 1389 1311867216.7691950798 0.0536580756 0.0595925223 0.0880135372 0.0054471050 0.1482040000 980561657 0 402718720 -0.0440572277 -0.1546543539 -0.1576378495 1390 1311867216.8050019741 0.0540523827 0.0595885366 0.0880135372 0.0054455465 0.1481480000 980564673 0 402718720 -0.0433145091 -0.1537999958 -0.1576306373 1391 1311867216.8379631042 0.0539471321 0.0595844809 0.0880135372 0.0054437407 0.1567580000 980567577 0 402718720 -0.0426978283 -0.1528957486 -0.1576533914 1392 1311867216.8703401089 0.0535400286 0.0595801386 0.0880135372 0.0054431841 0.1482870000 980570481 0 402718720 -0.0424604714 -0.1525845975 -0.1578643769 1393 1311867216.9049589634 0.0535797738 0.0595758311 0.0880135372 0.0054414682 0.1483120000 980573497 0 402718720 -0.0420241393 -0.1516899019 -0.1580373496 1394 1311867216.9374070168 0.0539018326 0.0595717608 0.0880135372 0.0054395825 0.1479890000 980576345 0 402718720 -0.0409373157 -0.1509606391 -0.1581021398 1395 1311867216.9691729546 0.0537255444 0.0595675700 0.0880135372 0.0054385056 0.1471220000 980579249 0 402718720 -0.0407377854 -0.1495120972 -0.1580769122 1396 1311867217.0053269863 0.0534478799 0.0595631863 0.0880135372 0.0054384526 0.1604650000 980582321 0 402718720 -0.0398615748 -0.1489352286 -0.1579046696 1397 1311867217.0373110771 0.0533990338 0.0595587738 0.0880135372 0.0054369586 0.1474040000 980585169 0 402718720 -0.0391215160 -0.1479780525 -0.1578985453 1398 1311867217.0691289902 0.0540451221 0.0595548299 0.0880135372 0.0054367416 0.1471550000 980588073 0 402718720 -0.0389791727 -0.1469931304 -0.1578391194 1399 1311867217.1052579880 0.0543302558 0.0595510954 0.0880135372 0.0054354000 0.1681790000 980591145 0 402718720 -0.0390617065 -0.1459083855 -0.1577297449 1400 1311867217.1370849609 0.0540540256 0.0595471689 0.0880135372 0.0054349705 0.1483170000 980593993 0 402718720 -0.0380413420 -0.1456025243 -0.1578186005 1401 1311867217.1691889763 0.0544348322 0.0595435198 0.0880135372 0.0054336071 0.1631950000 980596953 0 402718720 -0.0382671580 -0.1449417174 -0.1579397321 1402 1311867217.2057919502 0.0545438118 0.0595399537 0.0880135372 0.0054320235 0.1483710000 980599969 0 402718720 -0.0377517603 -0.1436666548 -0.1579362154 1403 1311867217.2371680737 0.0538502075 0.0595358983 0.0880135372 0.0054310926 0.1490130000 980602873 0 402718720 -0.0374326408 -0.1433543712 -0.1584697515 1404 1311867217.2692279816 0.0541522950 0.0595320638 0.0880135372 0.0054300193 0.1487620000 980605777 0 402718720 -0.0378349572 -0.1419927627 -0.1588077098 1405 1311867217.3051640987 0.0538530648 0.0595280218 0.0880135372 0.0054281210 0.1487190000 980608793 0 402718720 -0.0367300324 -0.1404172033 -0.1588895023 1406 1311867217.3374049664 0.0531953387 0.0595235178 0.0880135372 0.0054264222 0.1601810000 980611697 0 402718720 -0.0360348821 -0.1392697096 -0.1589870155 1407 1311867217.3695969582 0.0531902313 0.0595190165 0.0880135372 0.0054248040 0.1489620000 980614601 0 402718720 -0.0368546434 -0.1381740421 -0.1588005126 1408 1311867217.4120450020 0.0529914200 0.0595143804 0.0880135372 0.0054237510 0.1494000000 980617673 0 402718720 -0.0360997319 -0.1368791610 -0.1587046981 1409 1311867217.4372820854 0.0525652021 0.0595094485 0.0880135372 0.0054225941 0.1491200000 980620353 0 402718720 -0.0350917615 -0.1360027194 -0.1588004678 1410 1311867217.4694299698 0.0528793037 0.0595047462 0.0880135372 0.0054215088 0.1494780000 980623313 0 402718720 -0.0351518579 -0.1352169812 -0.1586111188 1411 1311867217.5050430298 0.0527499840 0.0594999590 0.0880135372 0.0054200642 0.1632600000 980626329 0 402718720 -0.0351828784 -0.1339039952 -0.1588952392 1412 1311867217.5370678902 0.0526920334 0.0594951375 0.0880135372 0.0054182853 0.1507380000 980629177 0 402718720 -0.0350618996 -0.1327341050 -0.1591959894 1413 1311867217.5691540241 0.0529824048 0.0594905284 0.0880135372 0.0054164062 0.1504790000 980632081 0 402718720 -0.0348708369 -0.1317564696 -0.1589370370 1414 1311867217.6050539017 0.0524707213 0.0594855639 0.0880135372 0.0054148920 0.1513360000 980635153 0 402718720 -0.0345566496 -0.1305906326 -0.1591442525 1415 1311867217.6370990276 0.0516817495 0.0594800488 0.0880135372 0.0054134018 0.1639560000 980638001 0 402718720 -0.0338301212 -0.1288315505 -0.1592721194 1416 1311867217.6691000462 0.0510241799 0.0594740771 0.0880135372 0.0054125519 0.1619640000 980640961 0 402718720 -0.0329508074 -0.1276422441 -0.1592722833 1417 1311867217.7050631046 0.0506847240 0.0594678744 0.0880135372 0.0054112680 0.1525370000 980643977 0 402718720 -0.0311084352 -0.1266805232 -0.1591927856 1418 1311867217.7371540070 0.0508601516 0.0594618040 0.0880135372 0.0054095302 0.1529190000 980646825 0 402718720 -0.0312716924 -0.1262726784 -0.1591307372 1419 1311867217.7694880962 0.0509394221 0.0594557981 0.0880135372 0.0054077262 0.1633530000 980649785 0 402718720 -0.0307854805 -0.1255618930 -0.1591942459 1420 1311867217.8051838875 0.0510578081 0.0594498840 0.0880135372 0.0054058347 0.1528220000 980652801 0 402718720 -0.0303878840 -0.1249420643 -0.1592402309 1421 1311867217.8372271061 0.0509945974 0.0594439338 0.0880135372 0.0054042425 0.1679730000 980655649 0 402718720 -0.0297730938 -0.1247390881 -0.1594770700 1422 1311867217.8690850735 0.0507859327 0.0594378452 0.0880135372 0.0054028923 0.1522420000 980658609 0 402718720 -0.0289855208 -0.1233921573 -0.1595431268 1423 1311867217.9056351185 0.0508120246 0.0594317835 0.0880135372 0.0054012898 0.1503950000 980661681 0 402718720 -0.0288624335 -0.1217298135 -0.1595757157 1424 1311867217.9372580051 0.0505762286 0.0594255647 0.0880135372 0.0053998195 0.1516670000 980664473 0 402718720 -0.0284798034 -0.1207239032 -0.1596508324 1425 1311867217.9711000919 0.0502581522 0.0594191314 0.0880135372 0.0053981072 0.1534600000 980667489 0 402718720 -0.0279194172 -0.1189359128 -0.1595377177 1426 1311867218.0052239895 0.0501928590 0.0594126614 0.0880135372 0.0053964547 0.1535850000 980670449 0 402718720 -0.0275571961 -0.1176946461 -0.1592168957 1427 1311867218.0371439457 0.0504398569 0.0594063735 0.0880135372 0.0053945992 0.1529750000 980673297 0 402718720 -0.0279652625 -0.1167781577 -0.1588844359 1428 1311867218.0710949898 0.0505586118 0.0594001776 0.0880135372 0.0053927370 0.1523360000 980676145 0 402718720 -0.0278104469 -0.1149777919 -0.1587307900 1429 1311867218.1050980091 0.0502594486 0.0593937810 0.0880135372 0.0053908787 0.1537140000 980679161 0 402718720 -0.0273612365 -0.1133832783 -0.1586456746 1430 1311867218.1371181011 0.0500700809 0.0593872609 0.0880135372 0.0053890498 0.1541880000 980682065 0 402718720 -0.0269922819 -0.1121885031 -0.1584358960 1431 1311867218.1712090969 0.0497005843 0.0593804918 0.0880135372 0.0053883711 0.1772170000 980685025 0 402718720 -0.0264734179 -0.1102289483 -0.1580839306 1432 1311867218.2050349712 0.0499562696 0.0593739106 0.0880135372 0.0053867491 0.1543870000 980687985 0 402718720 -0.0265651066 -0.1086653396 -0.1577793062 1433 1311867218.2372438908 0.0499621890 0.0593673428 0.0880135372 0.0053851478 0.1538480000 980690833 0 402718720 -0.0264833085 -0.1079406366 -0.1574875265 1434 1311867218.2715640068 0.0505033098 0.0593611614 0.0880135372 0.0053841207 0.1531030000 980693849 0 402718720 -0.0276585016 -0.1062411591 -0.1573564708 1435 1311867218.3051331043 0.0505665764 0.0593550328 0.0880135372 0.0053826599 0.1552110000 980696809 0 402718720 -0.0269268099 -0.1055604443 -0.1574994773 1436 1311867218.3373649120 0.0505801216 0.0593489221 0.0880135372 0.0053809039 0.1749770000 980699657 0 402718720 -0.0275194589 -0.1049062684 -0.1580310464 1437 1311867218.3734769821 0.0506726801 0.0593428844 0.0880135372 0.0053803232 0.1552030000 980702729 0 402718720 -0.0278186668 -0.1029469073 -0.1584698260 1438 1311867218.4052689075 0.0506538935 0.0593368420 0.0880135372 0.0053790828 0.1554420000 980705633 0 402718720 -0.0276378710 -0.1016517431 -0.1590349078 1439 1311867218.4372320175 0.0504993461 0.0593307006 0.0880135372 0.0053793482 0.1547630000 980708537 0 402718720 -0.0276211165 -0.1017713249 -0.1598543823 1440 1311867218.4729750156 0.0502322242 0.0593243822 0.0880135372 0.0053782488 0.1554220000 980711497 0 402718720 -0.0273968820 -0.1009780914 -0.1604147702 1441 1311867218.5051169395 0.0503384694 0.0593181463 0.0880135372 0.0053803708 0.1636940000 980714457 0 402718720 -0.0275332462 -0.0987516195 -0.1604908854 1442 1311867218.5372729301 0.0497425459 0.0593115058 0.0880135372 0.0053787993 0.1551140000 980717305 0 402718720 -0.0274396688 -0.0972720236 -0.1607851684 1443 1311867218.5714759827 0.0495940745 0.0593047716 0.0880135372 0.0053769957 0.1548000000 980720321 0 402718720 -0.0268866103 -0.0962474123 -0.1606662422 1444 1311867218.6059319973 0.0495676771 0.0592980285 0.0880135372 0.0053758420 0.1527700000 980723337 0 402718720 -0.0270418115 -0.0943783224 -0.1601411998 1445 1311867218.6372020245 0.0495700426 0.0592912963 0.0880135372 0.0053751685 0.1549220000 980726129 0 402718720 -0.0273024235 -0.0938501880 -0.1597228050 1446 1311867218.6710820198 0.0494755581 0.0592845081 0.0880135372 0.0053745317 0.1673440000 980729145 0 402718720 -0.0272093080 -0.0931023061 -0.1593414843 1447 1311867218.7058999538 0.0500946492 0.0592781571 0.0880135372 0.0053744859 0.1553870000 980731993 0 402718720 -0.0265641417 -0.0922521800 -0.1587742567 1448 1311867218.7378489971 0.0494591556 0.0592713760 0.0880135372 0.0053747896 0.1667400000 980734897 0 402718720 -0.0265522599 -0.0920860171 -0.1581496447 1449 1311867218.7715899944 0.0500598215 0.0592650189 0.0880135372 0.0053748832 0.1556720000 980737857 0 402718720 -0.0274587665 -0.0919929966 -0.1579034179 1450 1311867218.8052420616 0.0499342605 0.0592585839 0.0880135372 0.0053747762 0.1559330000 980740873 0 402718720 -0.0270397905 -0.0902344286 -0.1572261453 1451 1311867218.8379960060 0.0500740819 0.0592522541 0.0880135372 0.0053731646 0.1664800000 980743721 0 402718720 -0.0273191184 -0.0894866511 -0.1567303836 1452 1311867218.8727340698 0.0509731956 0.0592465523 0.0880135372 0.0053761331 0.1571470000 980746681 0 402718720 -0.0282297470 -0.0899681374 -0.1564487070 1453 1311867218.9054861069 0.0500446074 0.0592402192 0.0880135372 0.0053772139 0.1573970000 980749529 0 402718720 -0.0280655511 -0.0884876847 -0.1558349580 1454 1311867218.9372200966 0.0495028570 0.0592335222 0.0880135372 0.0053774805 0.1575910000 980752489 0 402718720 -0.0278142914 -0.0877975523 -0.1557509303 1455 1311867218.9731678963 0.0497067012 0.0592269746 0.0880135372 0.0053758705 0.1582540000 980755505 0 402718720 -0.0280343499 -0.0875228420 -0.1552802175 1456 1311867219.0051829815 0.0496812128 0.0592204184 0.0880135372 0.0053740521 0.1700440000 980758465 0 402718720 -0.0277677905 -0.0862912983 -0.1549139619 1457 1311867219.0371239185 0.0493897200 0.0592136712 0.0880135372 0.0053724994 0.1579960000 980761369 0 402718720 -0.0278921351 -0.0854109302 -0.1547854394 1458 1311867219.0738430023 0.0490230620 0.0592066818 0.0880135372 0.0053739666 0.1574700000 980764385 0 402718720 -0.0269789174 -0.0846661329 -0.1544304341 1459 1311867219.1050798893 0.0489864685 0.0591996768 0.0880135372 0.0053771153 0.1593550000 980767233 0 402718720 -0.0271078255 -0.0842282847 -0.1541321576 1460 1311867219.1383259296 0.0489374176 0.0591926479 0.0880135372 0.0053752839 0.1592890000 980770137 0 402718720 -0.0264466163 -0.0831649527 -0.1536594033 1461 1311867219.1708459854 0.0491562970 0.0591857784 0.0880135372 0.0053734558 0.1773420000 980773097 0 402718720 -0.0267097875 -0.0820804909 -0.1531950533 1462 1311867219.2052450180 0.0490598753 0.0591788523 0.0880135372 0.0053727713 0.1734930000 980776113 0 402718720 -0.0257867146 -0.0809789374 -0.1527538002 1463 1311867219.2391340733 0.0488622785 0.0591718007 0.0880135372 0.0053748507 0.1601540000 980779017 0 402718720 -0.0259641223 -0.0799922645 -0.1524363756 1464 1311867219.2709059715 0.0484753512 0.0591644943 0.0880135372 0.0053737029 0.1601660000 980781921 0 402718720 -0.0250102393 -0.0790847912 -0.1523634940 1465 1311867219.3052430153 0.0482353605 0.0591570342 0.0880135372 0.0053788575 0.1598980000 980784881 0 402718720 -0.0243192762 -0.0784758553 -0.1522116810 1466 1311867219.3401598930 0.0484917648 0.0591497591 0.0880135372 0.0053774154 0.1790620000 980787841 0 402718720 -0.0236032512 -0.0773261338 -0.1516822726 1467 1311867219.3715050220 0.0486559272 0.0591426058 0.0880135372 0.0053758305 0.1599610000 980790689 0 402718720 -0.0231726132 -0.0762218833 -0.1514001191 1468 1311867219.4051969051 0.0484476797 0.0591353205 0.0880135372 0.0053740919 0.1595550000 980793705 0 402718720 -0.0229998752 -0.0758360475 -0.1513313204 1469 1311867219.4394860268 0.0484833047 0.0591280693 0.0880135372 0.0053724777 0.1604010000 980796665 0 402718720 -0.0226710364 -0.0746870115 -0.1511567831 1470 1311867219.4717299938 0.0485017709 0.0591208405 0.0880135372 0.0053706565 0.1602880000 980799569 0 402718720 -0.0220280979 -0.0733092651 -0.1508346051 1471 1311867219.5051560402 0.0485566743 0.0591136589 0.0880135372 0.0053694694 0.1696490000 980802529 0 402718720 -0.0214313287 -0.0727981031 -0.1506305933 1472 1311867219.5391950607 0.0485828146 0.0591065048 0.0880135372 0.0053686772 0.1603590000 980805433 0 402718720 -0.0213956963 -0.0714604184 -0.1504932344 1473 1311867219.5743470192 0.0480942838 0.0590990287 0.0880135372 0.0053672230 0.1604720000 980808449 0 402718720 -0.0206996724 -0.0697915331 -0.1502548605 1474 1311867219.6086258888 0.0481415391 0.0590915949 0.0880135372 0.0053656573 0.1607040000 980811353 0 402718720 -0.0204068944 -0.0694644451 -0.1500869244 1475 1311867219.6425020695 0.0488908067 0.0590846791 0.0880135372 0.0053760154 0.1610260000 980814313 0 402718720 -0.0197854284 -0.0683484823 -0.1498541385 1476 1311867219.6711170673 0.0490006879 0.0590778471 0.0880135372 0.0053906452 0.1616800000 980817105 0 402718720 -0.0195590481 -0.0677062944 -0.1498694569 1477 1311867219.7052869797 0.0493065044 0.0590712314 0.0880135372 0.0053892761 0.1598190000 980820065 0 402718720 -0.0196600985 -0.0679143369 -0.1500527859 1478 1311867219.7395179272 0.0492939688 0.0590646162 0.0880135372 0.0053882045 0.1596480000 980823025 0 402718720 -0.0192722809 -0.0671000704 -0.1499183476 1479 1311867219.7772109509 0.0497665480 0.0590583295 0.0880135372 0.0054002279 0.1597500000 980826041 0 402718720 -0.0181426611 -0.0659085736 -0.1500457525 1480 1311867219.8051769733 0.0497644693 0.0590520499 0.0880135372 0.0053994827 0.1598690000 980828889 0 402718720 -0.0175983049 -0.0655426830 -0.1502980143 1481 1311867219.8397340775 0.0494907908 0.0590455939 0.0880135372 0.0053988741 0.1601510000 980831905 0 402718720 -0.0170381721 -0.0641146228 -0.1505640000 1482 1311867219.8753221035 0.0498158634 0.0590393660 0.0880135372 0.0054088451 0.1606640000 980834865 0 402718720 -0.0156037863 -0.0628635660 -0.1502680182 1483 1311867219.9108390808 0.0493825674 0.0590328544 0.0880135372 0.0054278104 0.1606620000 980837769 0 402718720 -0.0153247584 -0.0621122345 -0.1502878666 1484 1311867219.9417819977 0.0488102697 0.0590259658 0.0880135372 0.0054283913 0.1603940000 980840673 0 402718720 -0.0147585878 -0.0609812737 -0.1502307057 1485 1311867219.9732298851 0.0487994626 0.0590190793 0.0880135372 0.0054281614 0.1623580000 980843465 0 402718720 -0.0143351024 -0.0602783747 -0.1501574218 1486 1311867220.0068678856 0.0491595119 0.0590124443 0.0880135372 0.0054291123 0.1735310000 980846481 0 402718720 -0.0134552773 -0.0594072938 -0.1499179453 1487 1311867220.0422430038 0.0487467013 0.0590055407 0.0880135372 0.0054283500 0.1638800000 980849441 0 402718720 -0.0126251234 -0.0580794811 -0.1498157382 1488 1311867220.0743820667 0.0494004898 0.0589990857 0.0880135372 0.0054269935 0.1768740000 980852345 0 402718720 -0.0131727820 -0.0572342612 -0.1498468965 1489 1311867220.1052761078 0.0493216068 0.0589925864 0.0880135372 0.0054324503 0.1652120000 980855249 0 402718720 -0.0126984008 -0.0560742319 -0.1498330384 1490 1311867220.1421229839 0.0494169034 0.0589861597 0.0880135372 0.0054310313 0.1665670000 980858209 0 402718720 -0.0134478919 -0.0546686575 -0.1498141289 1491 1311867220.1714730263 0.0485242903 0.0589791430 0.0880135372 0.0054364220 0.1762570000 980861113 0 402718720 -0.0135744214 -0.0534039736 -0.1498619765 1492 1311867220.2061989307 0.0493145362 0.0589726654 0.0880135372 0.0054409143 0.1775290000 980864129 0 402718720 -0.0137269245 -0.0526207425 -0.1497162879 1493 1311867220.2422249317 0.0492859744 0.0589661774 0.0880135372 0.0054441296 0.1680610000 980867145 0 402718720 -0.0132615566 -0.0520330258 -0.1498732418 1494 1311867220.2741279602 0.0493785739 0.0589597599 0.0880135372 0.0054427468 0.1868120000 980869993 0 402718720 -0.0131861186 -0.0509632714 -0.1498949230 1495 1311867220.3064579964 0.0498680398 0.0589536785 0.0880135372 0.0054529727 0.1686260000 980872897 0 402718720 -0.0129858842 -0.0501515046 -0.1499240696 1496 1311867220.3420999050 0.0498289242 0.0589475791 0.0880135372 0.0054562704 0.1909280000 980875801 0 402718720 -0.0130275795 -0.0493183695 -0.1501496434 1497 1311867220.3714869022 0.0486069508 0.0589406715 0.0880135372 0.0055053961 0.1690110000 980878649 0 402718720 -0.0129555566 -0.0483497456 -0.1502885967 1498 1311867220.4063799381 0.0488100760 0.0589339088 0.0880135372 0.0055051850 0.1699500000 980881721 0 402718720 -0.0128340069 -0.0467422865 -0.1502005309 1499 1311867220.4408841133 0.0484876409 0.0589269400 0.0880135372 0.0055046072 0.1703950000 980884681 0 402718720 -0.0123961987 -0.0451501682 -0.1500355452 1500 1311867220.4728751183 0.0484070815 0.0589199267 0.0880135372 0.0055060379 0.1707570000 980887529 0 402718720 -0.0119076138 -0.0441847444 -0.1499232799 1501 1311867220.5091059208 0.0493929498 0.0589135796 0.0880135372 0.0055044615 0.1823050000 980890601 0 402718720 -0.0115490407 -0.0433831029 -0.1497391760 1502 1311867220.5419850349 0.0492286012 0.0589071316 0.0880135372 0.0055026323 0.1701380000 980893449 0 402718720 -0.0111065945 -0.0425871909 -0.1494528949 1503 1311867220.5716400146 0.0492574945 0.0589007113 0.0880135372 0.0055017314 0.1708060000 980896241 0 402718720 -0.0110259699 -0.0424285159 -0.1497202218 1504 1311867220.6104249954 0.0493070111 0.0588943325 0.0880135372 0.0055019578 0.1713320000 980899313 0 402718720 -0.0109738773 -0.0417108014 -0.1502096653 1505 1311867220.6415500641 0.0492950194 0.0588879543 0.0880135372 0.0055010240 0.1712590000 980902105 0 402718720 -0.0101530291 -0.0412202217 -0.1504940540 1506 1311867220.6713089943 0.0493157282 0.0588815982 0.0880135372 0.0054993151 0.1859930000 980905009 0 402718720 -0.0096388431 -0.0406369641 -0.1509362608 1507 1311867220.7073359489 0.0496647060 0.0588754821 0.0880135372 0.0055007474 0.1718400000 980908025 0 402718720 -0.0092829205 -0.0399778858 -0.1514445841 1508 1311867220.7393438816 0.0494112000 0.0588692061 0.0880135372 0.0055000100 0.1716030000 980910929 0 402718720 -0.0091391727 -0.0394451842 -0.1520339251 1509 1311867220.7719850540 0.0494791418 0.0588629834 0.0880135372 0.0054987153 0.1838540000 980913777 0 402718720 -0.0076054991 -0.0384917967 -0.1523587853 1510 1311867220.8097529411 0.0495998934 0.0588568489 0.0880135372 0.0054989847 0.1715830000 980916905 0 402718720 -0.0071005803 -0.0375937223 -0.1526949853 1511 1311867220.8415019512 0.0496749692 0.0588507722 0.0880135372 0.0054982740 0.1814610000 980919753 0 402718720 -0.0067126960 -0.0363927893 -0.1527765393 1512 1311867220.8712480068 0.0496335477 0.0588446762 0.0880135372 0.0055007257 0.1840120000 980922657 0 402718720 -0.0066373199 -0.0351482816 -0.1527298540 1513 1311867220.9075961113 0.0496963561 0.0588386297 0.0880135372 0.0055033027 0.1707150000 980925673 0 402718720 -0.0059849895 -0.0346244648 -0.1527553350 1514 1311867220.9392969608 0.0496187769 0.0588325399 0.0880135372 0.0055015575 0.1708920000 980928577 0 402718720 -0.0054852730 -0.0341153815 -0.1527127475 1515 1311867220.9713189602 0.0493873358 0.0588263055 0.0880135372 0.0055141385 0.1714670000 980931481 0 402718720 -0.0039274553 -0.0334726162 -0.1524938196 1516 1311867221.0090179443 0.0491981953 0.0588199545 0.0880135372 0.0055124526 0.1847130000 980934553 0 402718720 -0.0033833224 -0.0327000841 -0.1523077786 1517 1311867221.0392940044 0.0490652509 0.0588135242 0.0880135372 0.0055107215 0.1716100000 980937401 0 402718720 -0.0031720917 -0.0324055292 -0.1522377729 1518 1311867221.0720989704 0.0489687137 0.0588070388 0.0880135372 0.0055089325 0.1714000000 980940305 0 402718720 -0.0021951331 -0.0316034220 -0.1519870311 1519 1311867221.1077580452 0.0489686802 0.0588005620 0.0880135372 0.0055079517 0.1715770000 980943321 0 402718720 -0.0016589910 -0.0302887633 -0.1517300308 1520 1311867221.1397790909 0.0491206311 0.0587941936 0.0880135372 0.0055067331 0.1833260000 980946281 0 402718720 -0.0007147801 -0.0301666353 -0.1517544687 1521 1311867221.1716909409 0.0492337905 0.0587879080 0.0880135372 0.0055073334 0.1700660000 980949073 0 402718720 0.0001031391 -0.0292283129 -0.1518358439 1522 1311867221.2083969116 0.0489243828 0.0587814274 0.0880135372 0.0055079949 0.1716330000 980952089 0 402718720 0.0016420904 -0.0273214094 -0.1517825723 1523 1311867221.2398130894 0.0487426147 0.0587748359 0.0880135372 0.0055076209 0.1856300000 980955049 0 402718720 0.0030221294 -0.0265149456 -0.1519165486 1524 1311867221.2721240520 0.0484891757 0.0587680868 0.0880135372 0.0055066555 0.1863080000 980957953 0 402718720 0.0038312140 -0.0262832958 -0.1523068994 1525 1311867221.3075931072 0.0485852510 0.0587614095 0.0880135372 0.0055068918 0.2098900000 980960913 0 402718720 0.0049581630 -0.0243591424 -0.1526830196 1526 1311867221.3393449783 0.0486387834 0.0587547761 0.0880135372 0.0055052102 0.2116050000 980963817 0 402718720 0.0060872943 -0.0233806036 -0.1531705409 1527 1311867221.3714220524 0.0486880764 0.0587481836 0.0880135372 0.0055045927 0.2113750000 980966777 0 402718720 0.0072731269 -0.0232614744 -0.1538827270 1528 1311867221.4073879719 0.0485351346 0.0587414997 0.0880135372 0.0055030725 0.2117000000 980969681 0 402718720 0.0082696406 -0.0211690180 -0.1545566618 1529 1311867221.4400680065 0.0487939455 0.0587349937 0.0880135372 0.0055019288 0.2118370000 980972641 0 402718720 0.0095738396 -0.0195949785 -0.1549568772 1530 1311867221.4712409973 0.0489528365 0.0587286002 0.0880135372 0.0055005851 0.2127320000 980975489 0 402718720 0.0092280023 -0.0181762669 -0.1554874182 1531 1311867221.5081720352 0.0491550863 0.0587223471 0.0880135372 0.0054992231 0.2126850000 980978505 0 402718720 0.0091484319 -0.0173595417 -0.1560305804 1532 1311867221.5396909714 0.0495327264 0.0587163486 0.0880135372 0.0054975583 0.1996110000 980981465 0 402718720 0.0087143537 -0.0157977082 -0.1565784067 1533 1311867221.5712790489 0.0500382856 0.0587106878 0.0880135372 0.0054978480 0.1744240000 980984369 0 402718720 0.0082974816 -0.0142222894 -0.1572344452 1534 1311867221.6073110104 0.0505539291 0.0587053705 0.0880135372 0.0054965682 0.1742030000 980987329 0 402718720 0.0075083771 -0.0136222895 -0.1582811326 1535 1311867221.6403770447 0.0505338050 0.0587000470 0.0880135372 0.0054956426 0.1722330000 980990345 0 402718720 0.0070795445 -0.0113264695 -0.1591745317 1536 1311867221.6771481037 0.0511951037 0.0586951609 0.0880135372 0.0054949677 0.1862350000 980993361 0 402718720 0.0068999054 -0.0094313407 -0.1601795405 1537 1311867221.7072019577 0.0510974377 0.0586902177 0.0880135372 0.0054972020 0.1742840000 980996153 0 402718720 0.0067447163 -0.0075998534 -0.1613563001 1538 1311867221.7423930168 0.0510025285 0.0586852192 0.0880135372 0.0054957744 0.1743420000 980999169 0 402718720 0.0065887673 -0.0052714683 -0.1625108868 1539 1311867221.7773499489 0.0515364110 0.0586805741 0.0880135372 0.0054953612 0.1745490000 981002073 0 402718720 0.0063752830 -0.0028484785 -0.1632364839 1540 1311867221.8074541092 0.0514716767 0.0586758930 0.0880135372 0.0054938241 0.1746960000 981004921 0 402718720 0.0065764892 -0.0009808268 -0.1643076837 1541 1311867221.8396520615 0.0517556444 0.0586714023 0.0880135372 0.0054986858 0.1866690000 981007881 0 402718720 0.0059829308 -0.0003621053 -0.1659254432 1542 1311867221.8777329922 0.0523593761 0.0586673089 0.0880135372 0.0055011621 0.1747790000 981010953 0 402718720 0.0061737793 0.0009655652 -0.1673283279 1543 1311867221.9077489376 0.0523450710 0.0586632115 0.0880135372 0.0055013783 0.1749770000 981013801 0 402718720 0.0065811966 0.0025649166 -0.1685503721 1544 1311867221.9424629211 0.0518800206 0.0586588182 0.0880135372 0.0055013886 0.1861110000 981016761 0 402718720 0.0062246658 0.0041233241 -0.1701017022 1545 1311867221.9775359631 0.0521286502 0.0586545916 0.0880135372 0.0055014070 0.1754200000 981019777 0 402718720 0.0053412463 0.0060824412 -0.1713372320 1546 1311867222.0090060234 0.0520480238 0.0586503183 0.0880135372 0.0054998710 0.1859190000 981022681 0 402718720 0.0049968637 0.0078159906 -0.1721906364 1547 1311867222.0428760052 0.0521993265 0.0586461483 0.0880135372 0.0055020140 0.1763790000 981025473 0 402718720 0.0046568452 0.0084856851 -0.1730980575 1548 1311867222.0782530308 0.0521184579 0.0586419314 0.0880135372 0.0055041578 0.1773310000 981028377 0 402718720 0.0048568840 0.0105264513 -0.1739513278 1549 1311867222.1110939980 0.0513972193 0.0586372544 0.0880135372 0.0055030774 0.1772240000 981031281 0 402718720 0.0049151299 0.0131620737 -0.1743381917 1550 1311867222.1406900883 0.0503073931 0.0586318803 0.0880135372 0.0055231262 0.1977340000 981034129 0 402718720 0.0053318464 0.0149493609 -0.1744587570 1551 1311867222.1797990799 0.0510341823 0.0586269817 0.0880135372 0.0055373672 0.1978560000 981037257 0 402718720 0.0048395293 0.0162729099 -0.1747043282 1552 1311867222.2081730366 0.0507145301 0.0586218835 0.0880135372 0.0055379231 0.1787700000 981040049 0 402718720 0.0050020991 0.0191511083 -0.1745436192 1553 1311867222.2400839329 0.0502622202 0.0586165006 0.0880135372 0.0055411509 0.1787950000 981042953 0 402718720 0.0057333661 0.0210719537 -0.1743479371 1554 1311867222.2760300636 0.0501179621 0.0586110317 0.0880135372 0.0055407624 0.1770890000 981045969 0 402718720 0.0053914655 0.0215694401 -0.1743487567 1555 1311867222.3077421188 0.0499526337 0.0586054636 0.0880135372 0.0055397472 0.1787050000 981048873 0 402718720 0.0055562472 0.0236457344 -0.1735375673 1556 1311867222.3396389484 0.0498002172 0.0585998047 0.0880135372 0.0055403353 0.1930540000 981051777 0 402718720 0.0063202698 0.0250841305 -0.1731538475 1557 1311867222.3792359829 0.0502435118 0.0585944378 0.0880135372 0.0055434762 0.1918920000 981054849 0 402718720 0.0063448688 0.0261370093 -0.1728642434 1558 1311867222.4102001190 0.0501968414 0.0585890478 0.0880135372 0.0055420825 0.1799240000 981057753 0 402718720 0.0071060513 0.0277925767 -0.1721925884 1559 1311867222.4436430931 0.0506651737 0.0585839652 0.0880135372 0.0055408869 0.1800830000 981060657 0 402718720 0.0075280489 0.0296508856 -0.1712640375 1560 1311867222.4781119823 0.0501058735 0.0585785305 0.0880135372 0.0055398381 0.1806020000 981063673 0 402718720 0.0081701744 0.0313430876 -0.1706129164 1561 1311867222.5087089539 0.0505941473 0.0585734156 0.0880135372 0.0055383626 0.1917850000 981066521 0 402718720 0.0084263850 0.0328506492 -0.1695086360 1562 1311867222.5401790142 0.0516446754 0.0585689798 0.0880135372 0.0055375353 0.1787350000 981069425 0 402718720 0.0095409099 0.0341802649 -0.1685688496 1563 1311867222.5774040222 0.0517500266 0.0585646170 0.0880135372 0.0055362937 0.1804070000 981072441 0 402718720 0.0100090038 0.0347466171 -0.1677868813 1564 1311867222.6084389687 0.0511920527 0.0585599031 0.0880135372 0.0055352305 0.1808500000 981075345 0 402718720 0.0108736856 0.0357371792 -0.1668801904 1565 1311867222.6433119774 0.0508520044 0.0585549780 0.0880135372 0.0055342193 0.1780360000 981078305 0 402718720 0.0087721515 0.0370972566 -0.1663817763 1566 1311867222.6796491146 0.0510557182 0.0585501892 0.0880135372 0.0055348008 0.1941580000 981081377 0 402718720 0.0089403698 0.0380192734 -0.1658401191 1567 1311867222.7080249786 0.0506136380 0.0585451243 0.0880135372 0.0055352969 0.1806370000 981084113 0 402718720 0.0091133844 0.0390509330 -0.1651932597 1568 1311867222.7400081158 0.0506380871 0.0585400816 0.0880135372 0.0055373155 0.1809930000 981087073 0 402718720 0.0095878374 0.0401551947 -0.1644111723 1569 1311867222.7793939114 0.0506880209 0.0585350771 0.0880135372 0.0055393216 0.1805280000 981090033 0 402718720 0.0098991236 0.0407422557 -0.1639080644 1570 1311867222.8093209267 0.0508928373 0.0585302094 0.0880135372 0.0055386717 0.1812870000 981092825 0 402718720 0.0107422741 0.0412677824 -0.1635187566 1571 1311867222.8402760029 0.0509710051 0.0585253977 0.0880135372 0.0055370752 0.2036000000 981095729 0 402718720 0.0115020331 0.0422894023 -0.1628914326 1572 1311867222.8812980652 0.0507550277 0.0585204547 0.0880135372 0.0055364996 0.1815720000 981098801 0 402718720 0.0113129299 0.0427525602 -0.1624772102 1573 1311867222.9082360268 0.0508908406 0.0585156044 0.0880135372 0.0055349330 0.1816060000 981101593 0 402718720 0.0112968767 0.0431767739 -0.1621123999 1574 1311867222.9470820427 0.0507915132 0.0585106971 0.0880135372 0.0055342269 0.1811650000 981104721 0 402718720 0.0114575252 0.0440362133 -0.1615377069 1575 1311867222.9831020832 0.0507301465 0.0585057570 0.0880135372 0.0055325968 0.1934980000 981107737 0 402718720 0.0117759081 0.0444897972 -0.1611536890 1576 1311867223.0078310966 0.0510510504 0.0585010269 0.0880135372 0.0055335690 0.1993400000 981110417 0 402718720 0.0116359405 0.0446677990 -0.1607322097 1577 1311867223.0454061031 0.0509505719 0.0584962390 0.0880135372 0.0055324135 0.2017820000 981113489 0 402718720 0.0116769262 0.0453464948 -0.1603278220 1578 1311867223.0808250904 0.0509517789 0.0584914580 0.0880135372 0.0055321842 0.1817350000 981116505 0 402718720 0.0113796769 0.0460082367 -0.1598605961 1579 1311867223.1094229221 0.0508563481 0.0584866226 0.0880135372 0.0055315237 0.1815250000 981119297 0 402718720 0.0112021388 0.0464696363 -0.1596378684 1580 1311867223.1473770142 0.0513400398 0.0584820994 0.0880135372 0.0055307991 0.1936280000 981122369 0 402718720 0.0105654541 0.0474273860 -0.1592328250 1581 1311867223.1758580208 0.0515409186 0.0584777091 0.0880135372 0.0055304081 0.1919890000 981125161 0 402718720 0.0105910311 0.0484670810 -0.1588262618 1582 1311867223.2080020905 0.0514154509 0.0584732449 0.0880135372 0.0055288466 0.1810860000 981128009 0 402718720 0.0101744011 0.0492423773 -0.1586061418 1583 1311867223.2450079918 0.0516290925 0.0584689214 0.0880135372 0.0055286644 0.1942770000 981131081 0 402718720 0.0101479357 0.0504628457 -0.1580792069 1584 1311867223.2779359818 0.0521281473 0.0584649184 0.0880135372 0.0055276212 0.1795410000 981134041 0 402718720 0.0105791707 0.0518536791 -0.1574884802 1585 1311867223.3085999489 0.0523287095 0.0584610470 0.0880135372 0.0055263096 0.1816050000 981136889 0 402718720 0.0099215563 0.0530088618 -0.1570356637 1586 1311867223.3452420235 0.0523874126 0.0584572174 0.0880135372 0.0055258015 0.2038000000 981139961 0 402718720 0.0095514208 0.0545989536 -0.1565751731 1587 1311867223.3794689178 0.0511735938 0.0584526279 0.0880135372 0.0055295380 0.1803100000 981142865 0 402718720 0.0095319469 0.0561625361 -0.1563035995 1588 1311867223.4074239731 0.0530445091 0.0584492223 0.0880135372 0.0055291116 0.1799580000 981145601 0 402718720 0.0093407230 0.0570542254 -0.1561732739 1589 1311867223.4458000660 0.0535140522 0.0584461164 0.0880135372 0.0055276444 0.1811020000 981148673 0 402718720 0.0090347631 0.0578184277 -0.1561354846 1590 1311867223.4758329391 0.0536291748 0.0584430869 0.0880135372 0.0055262986 0.1811160000 981151577 0 402718720 0.0084006051 0.0589738563 -0.1563619226 1591 1311867223.5077428818 0.0534903333 0.0584399739 0.0880135372 0.0055249364 0.1925650000 981154481 0 402718720 0.0076470822 0.0602551401 -0.1566711068 1592 1311867223.5466530323 0.0538992770 0.0584371217 0.0880135372 0.0055306761 0.1815250000 981157553 0 402718720 0.0072381045 0.0610104352 -0.1571514904 1593 1311867223.5759539604 0.0539517701 0.0584343061 0.0880135372 0.0055333802 0.1816070000 981160457 0 402718720 0.0067482712 0.0622472949 -0.1576504856 1594 1311867223.6078069210 0.0540035218 0.0584315264 0.0880135372 0.0055317156 0.1812950000 981163249 0 402718720 0.0063502020 0.0633902773 -0.1580443978 1595 1311867223.6502039433 0.0540382229 0.0584287720 0.0880135372 0.0055345009 0.1810610000 981166489 0 402718720 0.0058982926 0.0640695170 -0.1587734818 1596 1311867223.6753880978 0.0541171767 0.0584260705 0.0880135372 0.0055329890 0.1990630000 981169169 0 402718720 0.0061615603 0.0652604252 -0.1592225879 1597 1311867223.7088580132 0.0541965924 0.0584234221 0.0880135372 0.0055313897 0.1815880000 981172129 0 402718720 0.0055569764 0.0668573454 -0.1594303697 1598 1311867223.7452809811 0.0541561171 0.0584207517 0.0880135372 0.0055305436 0.1917300000 981175201 0 402718720 0.0048138653 0.0682125986 -0.1598775983 1599 1311867223.7760720253 0.0547273383 0.0584184419 0.0880135372 0.0055306414 0.1806830000 981178049 0 402718720 0.0053020371 0.0697309822 -0.1600302160 1600 1311867223.8077559471 0.0548874177 0.0584162350 0.0880135372 0.0055289641 0.1806200000 981180897 0 402718720 0.0050356025 0.0716471449 -0.1603145152 1601 1311867223.8438520432 0.0552584156 0.0584142626 0.0880135372 0.0055304925 0.1925280000 981183969 0 402718720 0.0048031900 0.0729650036 -0.1607051641 1602 1311867223.8760919571 0.0553737134 0.0584123646 0.0880135372 0.0055295360 0.1812630000 981186873 0 402718720 0.0049619772 0.0743468106 -0.1610189825 1603 1311867223.9078280926 0.0556594878 0.0584106473 0.0880135372 0.0055279674 0.1805540000 981189721 0 402718720 0.0052937749 0.0761706755 -0.1611782312 1604 1311867223.9491670132 0.0562670454 0.0584093109 0.0880135372 0.0055263702 0.2019200000 981192905 0 402718720 0.0059009106 0.0774861574 -0.1615735888 1605 1311867223.9760739803 0.0559327416 0.0584077678 0.0880135372 0.0055282308 0.1817640000 981195697 0 402718720 0.0063044783 0.0789278597 -0.1621233672 1606 1311867224.0093441010 0.0562831424 0.0584064449 0.0880135372 0.0055299519 0.1964090000 981198601 0 402718720 0.0062694917 0.0805288777 -0.1625555009 1607 1311867224.0470440388 0.0564569347 0.0584052318 0.0880135372 0.0055283494 0.1807290000 981201729 0 402718720 0.0067697298 0.0821823478 -0.1628488302 1608 1311867224.0761411190 0.0563351400 0.0584039444 0.0880135372 0.0055266761 0.1811350000 981204521 0 402718720 0.0068520424 0.0832619518 -0.1634327769 1609 1311867224.1081349850 0.0564913079 0.0584027557 0.0880135372 0.0055252182 0.1815510000 981207425 0 402718720 0.0072364826 0.0847994909 -0.1641166806 1610 1311867224.1458990574 0.0567724556 0.0584017431 0.0880135372 0.0055274927 0.1811200000 981210441 0 402718720 0.0072856601 0.0866167545 -0.1644828469 1611 1311867224.1768929958 0.0571889393 0.0584009902 0.0880135372 0.0055317517 0.1926850000 981213345 0 402718720 0.0080061946 0.0883986354 -0.1650185883 1612 1311867224.2143769264 0.0570903867 0.0584001772 0.0880135372 0.0055301837 0.1944570000 981216249 0 402718720 0.0088298460 0.0901499838 -0.1656946689 1613 1311867224.2470428944 0.0571863279 0.0583994247 0.0880135372 0.0055285066 0.1814670000 981219153 0 402718720 0.0086958865 0.0922009423 -0.1662828177 1614 1311867224.2768630981 0.0573830903 0.0583987950 0.0880135372 0.0055287304 0.1807060000 981221945 0 402718720 0.0082829902 0.0942003131 -0.1667981148 1615 1311867224.3146169186 0.0580177009 0.0583985590 0.0880135372 0.0055275585 0.1810730000 981225073 0 402718720 0.0077089840 0.0955774486 -0.1675146967 1616 1311867224.3456730843 0.0576969385 0.0583981248 0.0880135372 0.0055258695 0.2021910000 981227977 0 402718720 0.0079186941 0.0974558070 -0.1682835966 1617 1311867224.3769209385 0.0572704375 0.0583974274 0.0880135372 0.0055243952 0.1820290000 981230769 0 402718720 0.0078708800 0.0994132608 -0.1691260189 1618 1311867224.4141020775 0.0575723238 0.0583969175 0.0880135372 0.0055256609 0.1822580000 981233841 0 402718720 0.0076466943 0.1009472832 -0.1699550152 1619 1311867224.4464271069 0.0572250187 0.0583961936 0.0880135372 0.0055250208 0.1826970000 981236745 0 402718720 0.0076055587 0.1024561450 -0.1708532423 1620 1311867224.4776859283 0.0571038090 0.0583953959 0.0880135372 0.0055274279 0.1826810000 981239593 0 402718720 0.0066913716 0.1041302308 -0.1714904159 1621 1311867224.5181219578 0.0574202128 0.0583947943 0.0880135372 0.0055333632 0.1935610000 981242721 0 402718720 0.0062701320 0.1052317545 -0.1724810302 1622 1311867224.5470569134 0.0574718975 0.0583942253 0.0880135372 0.0055332773 0.1819400000 981245569 0 402718720 0.0058867321 0.1062638685 -0.1732279062 1623 1311867224.5859119892 0.0574314371 0.0583936321 0.0880135372 0.0055372877 0.1820420000 981248697 0 402718720 0.0050212056 0.1084034964 -0.1738950610 1624 1311867224.6181120872 0.0569347404 0.0583927337 0.0880135372 0.0055358101 0.1817930000 981251545 0 402718720 0.0045625386 0.1098470613 -0.1745239347 1625 1311867224.6502161026 0.0566318743 0.0583916501 0.0880135372 0.0055343048 0.1946600000 981254505 0 402718720 0.0049122609 0.1109668016 -0.1750931591 1626 1311867224.6785190105 0.0559487417 0.0583901477 0.0880135372 0.0055357285 0.2092950000 981257241 0 402718720 0.0046707839 0.1124986708 -0.1755370796 1627 1311867224.7173650265 0.0561790131 0.0583887887 0.0880135372 0.0055370342 0.1814650000 981260369 0 402718720 0.0045246682 0.1141386703 -0.1756799519 1628 1311867224.7520918846 0.0564690270 0.0583876095 0.0880135372 0.0055355548 0.2230950000 981263385 0 402718720 0.0043324977 0.1153904498 -0.1758050472 1629 1311867224.7866261005 0.0565925166 0.0583865075 0.0880135372 0.0055353463 0.2228160000 981266289 0 402718720 0.0047910418 0.1166493297 -0.1760472357 1630 1311867224.8123459816 0.0565052517 0.0583853534 0.0880135372 0.0055361096 0.2231440000 981269081 0 402718720 0.0048573087 0.1185759380 -0.1761256754 1631 1311867224.8458189964 0.0562512912 0.0583840449 0.0880135372 0.0055631050 0.2084190000 981271929 0 402718720 0.0047087562 0.1203217581 -0.1760322303 1632 1311867224.8779430389 0.0560060851 0.0583825879 0.0880135372 0.0055674854 0.1832180000 981274777 0 402718720 0.0046622767 0.1220413372 -0.1760580838 1633 1311867224.9142448902 0.0564508662 0.0583814049 0.0880135372 0.0055731968 0.1958680000 981277849 0 402718720 0.0050833547 0.1240174398 -0.1756666005 1634 1311867224.9471449852 0.0568898767 0.0583804921 0.0880135372 0.0055777719 0.1830600000 981280641 0 402718720 0.0050001363 0.1257813573 -0.1754593700 1635 1311867224.9800488949 0.0566397384 0.0583794274 0.0880135372 0.0055761258 0.1836860000 981283657 0 402718720 0.0049015223 0.1270986497 -0.1754264981 1636 1311867225.0142920017 0.0559542440 0.0583779451 0.0880135372 0.0055754819 0.1843890000 981286449 0 402718720 0.0045663635 0.1295859069 -0.1753083616 1637 1311867225.0493879318 0.0557871126 0.0583763624 0.0880135372 0.0055758258 0.1832500000 981289353 0 402718720 0.0047124624 0.1317570955 -0.1748284698 1638 1311867225.0798690319 0.0563263111 0.0583751108 0.0880135372 0.0055772084 0.1824250000 981292257 0 402718720 0.0045026676 0.1335025132 -0.1744563431 1639 1311867225.1138188839 0.0565543287 0.0583739999 0.0880135372 0.0055769513 0.1935820000 981295161 0 402718720 0.0041451771 0.1354636699 -0.1740327924 1640 1311867225.1472380161 0.0560304895 0.0583725710 0.0880135372 0.0055754110 0.1951250000 981298065 0 402718720 0.0031535681 0.1377164871 -0.1737389266 1641 1311867225.1810939312 0.0558497906 0.0583710336 0.0880135372 0.0055737267 0.1923060000 981301081 0 402718720 0.0029564027 0.1396087408 -0.1736103445 1642 1311867225.2153220177 0.0562767535 0.0583697582 0.0880135372 0.0055722245 0.1829620000 981304041 0 402718720 0.0030490523 0.1412878484 -0.1733296216 1643 1311867225.2483470440 0.0558545925 0.0583682273 0.0880135372 0.0055717699 0.1836100000 981306945 0 402718720 0.0029518337 0.1429440826 -0.1733727604 1644 1311867225.2792909145 0.0556083694 0.0583665486 0.0880135372 0.0055712011 0.1820800000 981309849 0 402718720 0.0036670789 0.1448499262 -0.1734152883 1645 1311867225.3207540512 0.0556111820 0.0583648736 0.0880135372 0.0055709339 0.1836220000 981313033 0 402718720 0.0040129246 0.1462454051 -0.1734248102 1646 1311867225.3462350368 0.0551916026 0.0583629457 0.0880135372 0.0055695171 0.1951140000 981315769 0 402718720 0.0034895842 0.1475360096 -0.1737753600 1647 1311867225.3852069378 0.0552666374 0.0583610657 0.0880135372 0.0055678892 0.1833830000 981318841 0 402718720 0.0030499757 0.1489392370 -0.1737399250 1648 1311867225.4130129814 0.0550108850 0.0583590329 0.0880135372 0.0055662630 0.1827860000 981321577 0 402718720 0.0027909554 0.1500444710 -0.1740763038 1649 1311867225.4504270554 0.0550078489 0.0583570006 0.0880135372 0.0055647513 0.1828250000 981324705 0 402718720 0.0021225223 0.1512974203 -0.1744107157 1650 1311867225.4842948914 0.0552815050 0.0583551367 0.0880135372 0.0055645539 0.1811720000 981327609 0 402718720 0.0017297162 0.1525262892 -0.1748348922 1651 1311867225.5163919926 0.0556990579 0.0583535279 0.0880135372 0.0055647059 0.1826220000 981330569 0 402718720 0.0007628312 0.1538076103 -0.1753096431 1652 1311867225.5493750572 0.0556367114 0.0583518834 0.0880135372 0.0055661461 0.1847920000 981333417 0 402718720 0.0002805841 0.1557602137 -0.1759565920 1653 1311867225.5882349014 0.0553870872 0.0583500898 0.0880135372 0.0055654997 0.1844430000 981336489 0 402718720 -0.0007193919 0.1573297977 -0.1768726856 1654 1311867225.6179010868 0.0558437072 0.0583485744 0.0880135372 0.0055644825 0.1848660000 981339337 0 402718720 -0.0012904318 0.1583339423 -0.1778931618 1655 1311867225.6461288929 0.0558251105 0.0583470497 0.0880135372 0.0055630607 0.1848800000 981342129 0 402718720 -0.0017820983 0.1597173363 -0.1788636744 1656 1311867225.6847119331 0.0556305237 0.0583454093 0.0880135372 0.0055614532 0.2105240000 981345257 0 402718720 -0.0034313302 0.1612108946 -0.1799678802 1657 1311867225.7160770893 0.0552374348 0.0583435336 0.0880135372 0.0055599960 0.1897750000 981348161 0 402718720 -0.0048198546 0.1624813527 -0.1813008487 1658 1311867225.7506299019 0.0553728417 0.0583417419 0.0880135372 0.0055624490 0.2256740000 981351121 0 402718720 -0.0062445053 0.1636819988 -0.1825755239 1659 1311867225.7872900963 0.0548909791 0.0583396618 0.0880135372 0.0055625097 0.2247270000 981354081 0 402718720 -0.0080971969 0.1650047749 -0.1839138567 1660 1311867225.8170781136 0.0543495566 0.0583372582 0.0880135372 0.0055655228 0.2252470000 981356873 0 402718720 -0.0081563797 0.1657383442 -0.1849719882 1661 1311867225.8520019054 0.0547509640 0.0583350990 0.0880135372 0.0055678056 0.2255400000 981359945 0 402718720 -0.0081134140 0.1666721851 -0.1857628673 1662 1311867225.8862910271 0.0549633577 0.0583330703 0.0880135372 0.0055707260 0.1963770000 981362905 0 402718720 -0.0087502012 0.1676802337 -0.1863644570 1663 1311867225.9177930355 0.0551547334 0.0583311591 0.0880135372 0.0055691614 0.1842340000 981365753 0 402718720 -0.0091108261 0.1685893238 -0.1867714226 1664 1311867225.9504909515 0.0548808947 0.0583290856 0.0880135372 0.0055693503 0.1846310000 981368713 0 402718720 -0.0086659836 0.1695700437 -0.1874852628 1665 1311867225.9852480888 0.0555190146 0.0583273979 0.0880135372 0.0055683427 0.1940390000 981371729 0 402718720 -0.0081454199 0.1707201749 -0.1879435480 1666 1311867226.0173718929 0.0557780191 0.0583258677 0.0880135372 0.0055667616 0.1976380000 981374633 0 402718720 -0.0073678740 0.1720313281 -0.1887515336 1667 1311867226.0511479378 0.0556512251 0.0583242632 0.0880135372 0.0055654816 0.1852880000 981377537 0 402718720 -0.0078423070 0.1735925227 -0.1895334423 1668 1311867226.0877819061 0.0557197630 0.0583227017 0.0880135372 0.0055671563 0.1849420000 981380553 0 402718720 -0.0084986594 0.1752542406 -0.1900300831 1669 1311867226.1182270050 0.0559967607 0.0583213081 0.0880135372 0.0055741498 0.1851690000 981383457 0 402718720 -0.0078254007 0.1765618324 -0.1903161854 1670 1311867226.1477489471 0.0557790510 0.0583197858 0.0880135372 0.0055725009 0.1959640000 981386249 0 402718720 -0.0078665307 0.1782410890 -0.1907141507 1671 1311867226.1833140850 0.0560988188 0.0583184567 0.0880135372 0.0055715582 0.1975670000 981389265 0 402718720 -0.0077470252 0.1799185276 -0.1908936799 1672 1311867226.2166810036 0.0563475601 0.0583172779 0.0880135372 0.0055698973 0.1862240000 981392169 0 402718720 -0.0079254219 0.1813509166 -0.1912118345 1673 1311867226.2487111092 0.0561990179 0.0583160118 0.0880135372 0.0055692489 0.1863510000 981395129 0 402718720 -0.0072449241 0.1830509454 -0.1917095333 1674 1311867226.2829930782 0.0568301082 0.0583151241 0.0880135372 0.0055688341 0.1865580000 981398089 0 402718720 -0.0066422643 0.1845938116 -0.1920855343 1675 1311867226.3211309910 0.0569032878 0.0583142813 0.0880135372 0.0055672126 0.1846950000 981401217 0 402718720 -0.0071105422 0.1864462644 -0.1926559359 1676 1311867226.3455820084 0.0563473292 0.0583131077 0.0880135372 0.0055672447 0.1971420000 981403841 0 402718720 -0.0079824012 0.1883818656 -0.1932858974 1677 1311867226.3873078823 0.0568257980 0.0583122208 0.0880135372 0.0055660369 0.1863500000 981407081 0 402718720 -0.0071694888 0.1897612363 -0.1934825927 1678 1311867226.4188749790 0.0564771183 0.0583111272 0.0880135372 0.0055645290 0.1866280000 981409929 0 402718720 -0.0069699329 0.1914156377 -0.1939600259 1679 1311867226.4472739697 0.0567339435 0.0583101878 0.0880135372 0.0055631979 0.1976560000 981412777 0 402718720 -0.0063225715 0.1929893047 -0.1940894723 1680 1311867226.4849569798 0.0571788065 0.0583095144 0.0880135372 0.0055618357 0.2000710000 981415793 0 402718720 -0.0061704651 0.1946371645 -0.1946655959 1681 1311867226.5167839527 0.0573081709 0.0583089187 0.0880135372 0.0055609841 0.1976640000 981418641 0 402718720 -0.0064574676 0.1960927844 -0.1952269971 1682 1311867226.5462191105 0.0571818575 0.0583082486 0.0880135372 0.0055597588 0.1870760000 981421489 0 402718720 -0.0061282278 0.1975700259 -0.1957033575 1683 1311867226.5842289925 0.0572238304 0.0583076043 0.0880135372 0.0055588746 0.1869440000 981424561 0 402718720 -0.0054531964 0.1990254968 -0.1961251646 1684 1311867226.6149599552 0.0571624897 0.0583069243 0.0880135372 0.0055574683 0.2227610000 981427409 0 402718720 -0.0051215868 0.2002185136 -0.1964976937 1685 1311867226.6545290947 0.0576451160 0.0583065315 0.0880135372 0.0055565089 0.1887190000 981430537 0 402718720 -0.0052502584 0.2015557885 -0.1966610700 1686 1311867226.6802148819 0.0573321246 0.0583059536 0.0880135372 0.0055557445 0.2248080000 981433273 0 402718720 -0.0050114719 0.2029768527 -0.1972122192 1687 1311867226.7142350674 0.0580265559 0.0583057879 0.0880135372 0.0055556522 0.2294940000 981436233 0 402718720 -0.0052437470 0.2039478570 -0.1976335943 1688 1311867226.7506589890 0.0581412017 0.0583056904 0.0880135372 0.0055573444 0.1964420000 981439249 0 402718720 -0.0058501293 0.2047077119 -0.1981015205 1689 1311867226.7818078995 0.0581554212 0.0583056015 0.0880135372 0.0055565379 0.1879740000 981442153 0 402718720 -0.0057526287 0.2058297098 -0.1985763907 1690 1311867226.8133080006 0.0578006841 0.0583053027 0.0880135372 0.0055574818 0.1885890000 981445001 0 402718720 -0.0056619472 0.2064648271 -0.1991108656 1691 1311867226.8513610363 0.0583627708 0.0583053367 0.0880135372 0.0055559917 0.1997880000 981448073 0 402718720 -0.0050806394 0.2071583867 -0.1994591206 1692 1311867226.8838679790 0.0586182848 0.0583055216 0.0880135372 0.0055584669 0.1881550000 981450977 0 402718720 -0.0045562452 0.2082211524 -0.1997696310 1693 1311867226.9181559086 0.0587669648 0.0583057942 0.0880135372 0.0055572603 0.1878400000 981453937 0 402718720 -0.0050668074 0.2090271562 -0.2003309578 1694 1311867226.9514899254 0.0591459312 0.0583062901 0.0880135372 0.0055556474 0.1862070000 981456897 0 402718720 -0.0057826703 0.2096762657 -0.2008589506 1695 1311867226.9810149670 0.0588876642 0.0583066331 0.0880135372 0.0055540699 0.1875130000 981459801 0 402718720 -0.0054465849 0.2108524442 -0.2014268637 1696 1311867227.0125620365 0.0588644147 0.0583069620 0.0880135372 0.0055528826 0.2037910000 981462593 0 402718720 -0.0053324266 0.2119761407 -0.2019093931 1697 1311867227.0480670929 0.0590072162 0.0583073747 0.0880135372 0.0055549761 0.1880870000 981465665 0 402718720 -0.0052707000 0.2131164819 -0.2022269517 1698 1311867227.0861930847 0.0589854047 0.0583077740 0.0880135372 0.0055556396 0.1885200000 981468569 0 402718720 -0.0054909340 0.2146951407 -0.2023392171 1699 1311867227.1158189774 0.0591008663 0.0583082408 0.0880135372 0.0055555045 0.1896230000 981471361 0 402718720 -0.0050934302 0.2161694169 -0.2023385614 1700 1311867227.1503999233 0.0596008375 0.0583090011 0.0880135372 0.0055572089 0.1894180000 981474377 0 402718720 -0.0050760331 0.2174963504 -0.2020764947 1701 1311867227.1841590405 0.0594481491 0.0583096708 0.0880135372 0.0055557758 0.1986490000 981477337 0 402718720 -0.0053794496 0.2194707245 -0.2017300576 1702 1311867227.2148449421 0.0596928187 0.0583104835 0.0880135372 0.0055544420 0.2001840000 981480129 0 402718720 -0.0060734777 0.2206323296 -0.2017370760 1703 1311867227.2480258942 0.0600641184 0.0583115132 0.0880135372 0.0055544566 0.1902480000 981483089 0 402718720 -0.0059224530 0.2218293548 -0.2015266418 1704 1311867227.2819800377 0.0600944720 0.0583125596 0.0880135372 0.0055574493 0.1899140000 981486049 0 402718720 -0.0058590537 0.2232631743 -0.2013649493 1705 1311867227.3152499199 0.0603079684 0.0583137299 0.0880135372 0.0055574483 0.1882010000 981489009 0 402718720 -0.0056321919 0.2243790179 -0.2012574077 1706 1311867227.3479840755 0.0598154888 0.0583146102 0.0880135372 0.0055558918 0.2019700000 981491913 0 402718720 -0.0065783896 0.2256466299 -0.2013227791 1707 1311867227.3841071129 0.0599173903 0.0583155491 0.0880135372 0.0055584815 0.1867130000 981494929 0 402718720 -0.0061477553 0.2265173644 -0.2012034357 1708 1311867227.4141440392 0.0596812181 0.0583163487 0.0880135372 0.0055609769 0.1900370000 981497777 0 402718720 -0.0072711715 0.2274517864 -0.2012637407 1709 1311867227.4479200840 0.0597802587 0.0583172053 0.0880135372 0.0055623793 0.2148820000 981500737 0 402718720 -0.0074186143 0.2286078036 -0.2012517899 1710 1311867227.4818758965 0.0601843782 0.0583182972 0.0880135372 0.0055610458 0.1903180000 981503753 0 402718720 -0.0071338955 0.2292056829 -0.2013241351 1711 1311867227.5169329643 0.0601010136 0.0583193391 0.0880135372 0.0055602495 0.2007840000 981506657 0 402718720 -0.0077290395 0.2300900817 -0.2014077902 1712 1311867227.5501220226 0.0598307364 0.0583202219 0.0880135372 0.0055589195 0.1901630000 981509617 0 402718720 -0.0088569131 0.2308439314 -0.2016245425 1713 1311867227.5819540024 0.0597681701 0.0583210672 0.0880135372 0.0055573695 0.1902500000 981512577 0 402718720 -0.0088989744 0.2315149605 -0.2017205060 1714 1311867227.6162750721 0.0598235503 0.0583219438 0.0880135372 0.0055591680 0.1900700000 981515481 0 402718720 -0.0084371669 0.2322720885 -0.2015835494 1715 1311867227.6503078938 0.0592564344 0.0583224887 0.0880135372 0.0055742697 0.1904310000 981518497 0 402718720 -0.0093200803 0.2327850163 -0.2015850544 1716 1311867227.6823980808 0.0592370890 0.0583230217 0.0880135372 0.0055726778 0.2110010000 981521401 0 402718720 -0.0098581733 0.2332945764 -0.2015598863 1717 1311867227.7135930061 0.0592200607 0.0583235441 0.0880135372 0.0055736479 0.1906210000 981524193 0 402718720 -0.0098484810 0.2340497673 -0.2014423758 1718 1311867227.7496368885 0.0594371073 0.0583241923 0.0880135372 0.0055720586 0.1905460000 981527265 0 402718720 -0.0098143034 0.2348112166 -0.2010952532 1719 1311867227.7827620506 0.0595685169 0.0583249161 0.0880135372 0.0055707239 0.1911740000 981530225 0 402718720 -0.0095412778 0.2355907410 -0.2008800060 1720 1311867227.8141551018 0.0596264713 0.0583256729 0.0880135372 0.0055711284 0.1912590000 981533073 0 402718720 -0.0093046455 0.2367657274 -0.2005165070 1721 1311867227.8497691154 0.0596106015 0.0583264195 0.0880135372 0.0055739516 0.2128030000 981536089 0 402718720 -0.0084455805 0.2379670590 -0.2002199888 1722 1311867227.8832869530 0.0599739812 0.0583273763 0.0880135372 0.0055723534 0.1912190000 981538993 0 402718720 -0.0077985730 0.2389989793 -0.1997762769 1723 1311867227.9196939468 0.0602795780 0.0583285093 0.0880135372 0.0055708924 0.1914600000 981542065 0 402718720 -0.0076472145 0.2401832640 -0.1994281113 1724 1311867227.9516780376 0.0604271404 0.0583297266 0.0880135372 0.0055701603 0.1914480000 981544969 0 402718720 -0.0066631511 0.2415945381 -0.1993485540 1725 1311867227.9828588963 0.0603799447 0.0583309151 0.0880135372 0.0055686270 0.1915640000 981547873 0 402718720 -0.0067384737 0.2427557707 -0.1991950423 1726 1311867228.0181910992 0.0600490347 0.0583319105 0.0880135372 0.0055674766 0.2094110000 981550833 0 402718720 -0.0065291328 0.2440630049 -0.1990531981 1727 1311867228.0516328812 0.0604651645 0.0583331458 0.0880135372 0.0055661088 0.1915120000 981553793 0 402718720 -0.0057817353 0.2453167289 -0.1986363530 1728 1311867228.0825328827 0.0606112294 0.0583344641 0.0880135372 0.0055648683 0.1899270000 981556641 0 402718720 -0.0053942087 0.2465376854 -0.1985025406 1729 1311867228.1179840565 0.0609698407 0.0583359883 0.0880135372 0.0055641602 0.1917790000 981559601 0 402718720 -0.0038901607 0.2476688772 -0.1984679848 1730 1311867228.1511390209 0.0618295670 0.0583380078 0.0880135372 0.0055639623 0.2041450000 981562617 0 402718720 -0.0030479082 0.2490127683 -0.1981520057 1731 1311867228.1828610897 0.0622813515 0.0583402858 0.0880135372 0.0055624886 0.2039580000 981565521 0 402718720 -0.0019753459 0.2501263022 -0.1982418597 1732 1311867228.2179419994 0.0624580570 0.0583426633 0.0880135372 0.0055676611 0.1919560000 981568425 0 402718720 -0.0019327934 0.2511819899 -0.1982598007 1733 1311867228.2541251183 0.0629430264 0.0583453179 0.0880135372 0.0055740719 0.1920740000 981571497 0 402718720 -0.0016756571 0.2525224984 -0.1984928399 1734 1311867228.2826519012 0.0626843199 0.0583478202 0.0880135372 0.0055725328 0.1923410000 981574289 0 402718720 -0.0019336212 0.2535396516 -0.1987177879 1735 1311867228.3181738853 0.0630621314 0.0583505373 0.0880135372 0.0055715314 0.2185900000 981577305 0 402718720 -0.0021691804 0.2544046342 -0.1985547543 1736 1311867228.3504519463 0.0627081543 0.0583530475 0.0880135372 0.0055700323 0.1921520000 981580209 0 402718720 -0.0026565399 0.2556994557 -0.1987742335 1737 1311867228.3824779987 0.0628367439 0.0583556288 0.0880135372 0.0055685861 0.1917550000 981583169 0 402718720 -0.0020589072 0.2567113340 -0.1987275034 1738 1311867228.4176759720 0.0627222136 0.0583581412 0.0880135372 0.0055670209 0.1928910000 981586073 0 402718720 -0.0022539534 0.2573326230 -0.1988026202 1739 1311867228.4483039379 0.0625105202 0.0583605290 0.0880135372 0.0055661687 0.1922990000 981588977 0 402718720 -0.0022328182 0.2580995560 -0.1987151951 1740 1311867228.4835319519 0.0627057552 0.0583630263 0.0880135372 0.0055648009 0.1923740000 981591937 0 402718720 -0.0020657266 0.2583004832 -0.1986897141 1741 1311867228.5177900791 0.0628363565 0.0583655957 0.0880135372 0.0055650834 0.2035740000 981594897 0 402718720 -0.0022630689 0.2584208846 -0.1988046765 1742 1311867228.5529639721 0.0626244396 0.0583680405 0.0880135372 0.0055635612 0.1916150000 981597913 0 402718720 -0.0025237340 0.2581375539 -0.1992559582 1743 1311867228.5834119320 0.0622913763 0.0583702914 0.0880135372 0.0055620032 0.1919100000 981600761 0 402718720 -0.0029443863 0.2577603459 -0.1998618543 1744 1311867228.6168839931 0.0621762685 0.0583724737 0.0880135372 0.0055606971 0.2036300000 981603777 0 402718720 -0.0037752271 0.2567748725 -0.2002769560 1745 1311867228.6513540745 0.0618668534 0.0583744762 0.0880135372 0.0055592304 0.2042030000 981606681 0 402718720 -0.0049234419 0.2557054758 -0.2008858770 1746 1311867228.6960909367 0.0619420074 0.0583765195 0.0880135372 0.0055577868 0.1945480000 981609977 0 402718720 -0.0056672748 0.2543906569 -0.2014687508 1747 1311867228.7251129150 0.0609594211 0.0583779979 0.0880135372 0.0055570680 0.1935390000 981612713 0 402718720 -0.0068788882 0.2534650564 -0.2021992356 1748 1311867228.7533209324 0.0607308373 0.0583793440 0.0880135372 0.0055557343 0.1937550000 981615393 0 402718720 -0.0076722931 0.2523889840 -0.2028166503 1749 1311867228.7872729301 0.0605783649 0.0583806013 0.0880135372 0.0055615841 0.1941930000 981618073 0 402718720 -0.0080462713 0.2510894835 -0.2032428533 1750 1311867228.8184990883 0.0612671450 0.0583822507 0.0880135372 0.0055655570 0.1942060000 981620921 0 402718720 -0.0086688092 0.2501603961 -0.2036827803 1751 1311867228.8512189388 0.0602439083 0.0583833139 0.0880135372 0.0055644910 0.2065200000 981623881 0 402718720 -0.0084697139 0.2495404333 -0.2042150795 1752 1311867228.8835051060 0.0604755059 0.0583845081 0.0880135372 0.0055630451 0.1948780000 981626729 0 402718720 -0.0091515826 0.2480018139 -0.2047193050 1753 1311867228.9181449413 0.0602456518 0.0583855698 0.0880135372 0.0055615560 0.1917890000 981629745 0 402718720 -0.0098449513 0.2467169911 -0.2052605748 1754 1311867228.9496490955 0.0594086573 0.0583861531 0.0880135372 0.0055604088 0.1923960000 981632649 0 402718720 -0.0101918150 0.2458131164 -0.2059839666 1755 1311867228.9844760895 0.0594709851 0.0583867712 0.0880135372 0.0055590635 0.1919100000 981635609 0 402718720 -0.0113689443 0.2438961118 -0.2064617276 1756 1311867229.0238449574 0.0594386645 0.0583873702 0.0880135372 0.0055584276 0.2143410000 981638737 0 402718720 -0.0117138587 0.2425463945 -0.2068026662 1757 1311867229.0509281158 0.0589584783 0.0583876953 0.0880135372 0.0055573638 0.1927840000 981641529 0 402718720 -0.0122079896 0.2412667125 -0.2073678225 1758 1311867229.0874319077 0.0587597750 0.0583879069 0.0880135372 0.0055568008 0.1926490000 981644489 0 402718720 -0.0121641262 0.2395661175 -0.2076665014 1759 1311867229.1218080521 0.0587368943 0.0583881053 0.0880135372 0.0055554677 0.1912790000 981647505 0 402718720 -0.0125134159 0.2378641367 -0.2078453302 1760 1311867229.1517140865 0.0590532087 0.0583884832 0.0880135372 0.0055557746 0.1894810000 981650409 0 402718720 -0.0129200844 0.2362568527 -0.2078622729 1761 1311867229.1890540123 0.0587352328 0.0583886801 0.0880135372 0.0055552588 0.2233030000 981653425 0 402718720 -0.0131923826 0.2345985174 -0.2079945654 1762 1311867229.2214341164 0.0588924736 0.0583889661 0.0880135372 0.0055543846 0.1917290000 981656329 0 402718720 -0.0137468278 0.2324544936 -0.2081355751 1763 1311867229.2532980442 0.0586937368 0.0583891389 0.0880135372 0.0055581102 0.1907730000 981659233 0 402718720 -0.0146616083 0.2308022082 -0.2085350603 1764 1311867229.2841351032 0.0585468598 0.0583892283 0.0880135372 0.0055567920 0.1897800000 981662081 0 402718720 -0.0148676028 0.2290171832 -0.2089836299 1765 1311867229.3193020821 0.0580315925 0.0583890257 0.0880135372 0.0055595492 0.1889280000 981665097 0 402718720 -0.0153994216 0.2269925177 -0.2095096111 1766 1311867229.3502240181 0.0582218654 0.0583889311 0.0880135372 0.0055611830 0.2030000000 981667945 0 402718720 -0.0158069972 0.2249617875 -0.2099225819 1767 1311867229.3850710392 0.0580164306 0.0583887202 0.0880135372 0.0055599850 0.1898140000 981670905 0 402718720 -0.0157566201 0.2229394466 -0.2104969770 1768 1311867229.4180469513 0.0581112504 0.0583885633 0.0880135372 0.0055597020 0.1898140000 981673809 0 402718720 -0.0156148449 0.2207578421 -0.2109708935 1769 1311867229.4483740330 0.0582399666 0.0583884793 0.0880135372 0.0055586193 0.1999720000 981676657 0 402718720 -0.0156246061 0.2184789181 -0.2112814635 1770 1311867229.4843358994 0.0581805296 0.0583883618 0.0880135372 0.0055628758 0.1977550000 981679673 0 402718720 -0.0152597986 0.2163560092 -0.2118832469 1771 1311867229.5189929008 0.0580172017 0.0583881522 0.0880135372 0.0055614318 0.1897440000 981682577 0 402718720 -0.0152894957 0.2143633217 -0.2127437145 1772 1311867229.5504579544 0.0579404607 0.0583878996 0.0880135372 0.0055599575 0.1894650000 981685481 0 402718720 -0.0167163759 0.2122535557 -0.2130308747 1773 1311867229.5853381157 0.0574805737 0.0583873878 0.0880135372 0.0055587780 0.1889560000 981688441 0 402718720 -0.0170208458 0.2104079425 -0.2137461156 1774 1311867229.6182799339 0.0576320663 0.0583869621 0.0880135372 0.0055575081 0.1885480000 981691345 0 402718720 -0.0168321151 0.2084010690 -0.2141385674 1775 1311867229.6503160000 0.0578087121 0.0583866363 0.0880135372 0.0055560979 0.1886080000 981694305 0 402718720 -0.0171690844 0.2065757066 -0.2144002467 1776 1311867229.6876978874 0.0575090870 0.0583861422 0.0880135372 0.0055552011 0.2035640000 981697321 0 402718720 -0.0177638736 0.2049665898 -0.2147920430 1777 1311867229.7184219360 0.0575892702 0.0583856937 0.0880135372 0.0055550455 0.1890730000 981700169 0 402718720 -0.0180486757 0.2033032626 -0.2152737230 1778 1311867229.7500000000 0.0577459596 0.0583853339 0.0880135372 0.0055536858 0.1882480000 981703073 0 402718720 -0.0175058544 0.2016049623 -0.2154829800 1779 1311867229.7854330540 0.0576247349 0.0583849064 0.0880135372 0.0055524438 0.1996070000 981706089 0 402718720 -0.0180905387 0.2005469650 -0.2158724219 1780 1311867229.8184831142 0.0577641055 0.0583845576 0.0880135372 0.0055510919 0.1873170000 981708993 0 402718720 -0.0174470264 0.1991876960 -0.2162166983 1781 1311867229.8494279385 0.0578289442 0.0583842457 0.0880135372 0.0055499373 0.1989610000 981711897 0 402718720 -0.0178851243 0.1975425333 -0.2165454030 1782 1311867229.8853340149 0.0574937426 0.0583837459 0.0880135372 0.0055486338 0.1858660000 981714913 0 402718720 -0.0191763602 0.1960847527 -0.2170316577 1783 1311867229.9183139801 0.0572679862 0.0583831202 0.0880135372 0.0055477588 0.1874120000 981717817 0 402718720 -0.0199773684 0.1945479363 -0.2177422494 1784 1311867229.9534161091 0.0573839471 0.0583825601 0.0880135372 0.0055488103 0.1866110000 981720833 0 402718720 -0.0199003033 0.1928211600 -0.2180424929 1785 1311867229.9877750874 0.0569278412 0.0583817451 0.0880135372 0.0055473639 0.1861850000 981723849 0 402718720 -0.0208260585 0.1914017648 -0.2184900492 1786 1311867230.0194880962 0.0565506928 0.0583807199 0.0880135372 0.0055459527 0.2007150000 981726697 0 402718720 -0.0211988240 0.1899669319 -0.2191859335 1787 1311867230.0512609482 0.0563687794 0.0583795940 0.0880135372 0.0055444041 0.1843630000 981729657 0 402718720 -0.0222304724 0.1880611032 -0.2198705524 1788 1311867230.0876040459 0.0561908670 0.0583783699 0.0880135372 0.0055430453 0.2154320000 981732561 0 402718720 -0.0237166155 0.1862288415 -0.2203866690 1789 1311867230.1212029457 0.0560999736 0.0583770963 0.0880135372 0.0055415168 0.1864420000 981735633 0 402718720 -0.0232122205 0.1844594777 -0.2210414857 1790 1311867230.1508131027 0.0561695248 0.0583758631 0.0880135372 0.0055402149 0.1854550000 981738425 0 402718720 -0.0226837732 0.1827805638 -0.2217393667 1791 1311867230.1872301102 0.0554317348 0.0583742192 0.0880135372 0.0055438229 0.2055630000 981741441 0 402718720 -0.0242465995 0.1811682880 -0.2223391086 1792 1311867230.2194790840 0.0561885424 0.0583729995 0.0880135372 0.0055511278 0.1865240000 981744345 0 402718720 -0.0250238590 0.1796302497 -0.2230383158 1793 1311867230.2494208813 0.0553055890 0.0583712888 0.0880135372 0.0055557289 0.1861940000 981747193 0 402718720 -0.0255398098 0.1780884862 -0.2238469869 1794 1311867230.2894790173 0.0559837446 0.0583699579 0.0880135372 0.0055600122 0.1855310000 981750321 0 402718720 -0.0268565360 0.1766086072 -0.2247127444 1795 1311867230.3189430237 0.0560335256 0.0583686563 0.0880135372 0.0055585057 0.1859330000 981753113 0 402718720 -0.0268736631 0.1751417816 -0.2253312320 1796 1311867230.3552010059 0.0559591949 0.0583673147 0.0880135372 0.0055571552 0.2024810000 981756185 0 402718720 -0.0266893860 0.1739261895 -0.2259356081 1797 1311867230.3913140297 0.0559462495 0.0583659674 0.0880135372 0.0055557402 0.1870160000 981759145 0 402718720 -0.0275923926 0.1723971963 -0.2265840173 1798 1311867230.4169929028 0.0560258441 0.0583646659 0.0880135372 0.0055543578 0.1860470000 981761881 0 402718720 -0.0280122086 0.1709698886 -0.2272270322 1799 1311867230.4538938999 0.0558219887 0.0583632525 0.0880135372 0.0055529289 0.1858840000 981764953 0 402718720 -0.0283853114 0.1698241234 -0.2278944552 1800 1311867230.4892110825 0.0548564158 0.0583613043 0.0880135372 0.0055641410 0.1864540000 981767913 0 402718720 -0.0280556120 0.1685901880 -0.2283667922 1801 1311867230.5216429234 0.0545679368 0.0583591980 0.0880135372 0.0055626632 0.1972860000 981770873 0 402718720 -0.0287706461 0.1673150361 -0.2289372236 1802 1311867230.5564150810 0.0555597395 0.0583576445 0.0880135372 0.0055721044 0.1959630000 981773889 0 402718720 -0.0289881043 0.1661242843 -0.2292643487 1803 1311867230.5930590630 0.0558562167 0.0583562571 0.0880135372 0.0055707061 0.1861660000 981776849 0 402718720 -0.0284719206 0.1650353223 -0.2294507772 1804 1311867230.6184151173 0.0559175946 0.0583549053 0.0880135372 0.0055691740 0.1844370000 981779529 0 402718720 -0.0291736051 0.1638847142 -0.2299038172 1805 1311867230.6534399986 0.0556056648 0.0583533822 0.0880135372 0.0055679501 0.1842400000 981782545 0 402718720 -0.0298410300 0.1627554297 -0.2302763015 1806 1311867230.6920781136 0.0555252209 0.0583518162 0.0880135372 0.0055669152 0.2108230000 981785673 0 402718720 -0.0297173969 0.1613894552 -0.2305658162 1807 1311867230.7185189724 0.0556910820 0.0583503438 0.0880135372 0.0055655818 0.1837740000 981788353 0 402718720 -0.0308538284 0.1600154787 -0.2308285236 1808 1311867230.7529120445 0.0555294678 0.0583487835 0.0880135372 0.0055642718 0.1848020000 981791369 0 402718720 -0.0311406590 0.1587598622 -0.2313032001 1809 1311867230.7871611118 0.0546951555 0.0583467638 0.0880135372 0.0055726066 0.1854180000 981794385 0 402718720 -0.0312018469 0.1577727199 -0.2314037830 1810 1311867230.8195741177 0.0557290800 0.0583453176 0.0880135372 0.0055795496 0.1853880000 981797233 0 402718720 -0.0312556960 0.1569182873 -0.2313981801 1811 1311867230.8534181118 0.0557196215 0.0583438678 0.0880135372 0.0055781272 0.1998590000 981800193 0 402718720 -0.0311698113 0.1562377661 -0.2314468622 1812 1311867230.8890159130 0.0555013977 0.0583422991 0.0880135372 0.0055767508 0.1857160000 981803209 0 402718720 -0.0311519727 0.1555788219 -0.2316145599 1813 1311867230.9176509380 0.0555120558 0.0583407380 0.0880135372 0.0055753760 0.1860350000 981806057 0 402718720 -0.0315543078 0.1550269723 -0.2316707224 1814 1311867230.9559168816 0.0557012446 0.0583392829 0.0880135372 0.0055739161 0.2160100000 981809073 0 402718720 -0.0317106582 0.1543982029 -0.2317190766 1815 1311867230.9881010056 0.0557954311 0.0583378813 0.0880135372 0.0055727427 0.2270060000 981811977 0 402718720 -0.0323338509 0.1540879011 -0.2318490446 1816 1311867231.0166280270 0.0557259731 0.0583364431 0.0880135372 0.0055716188 0.2287110000 981814825 0 402718720 -0.0322725475 0.1535993069 -0.2322514951 1817 1311867231.0603969097 0.0556336567 0.0583349556 0.0880135372 0.0055703440 0.2295980000 981817953 0 402718720 -0.0327193849 0.1530162096 -0.2326298654 1818 1311867231.0868620872 0.0553573146 0.0583333177 0.0880135372 0.0055689227 0.2287370000 981820633 0 402718720 -0.0333164409 0.1522986442 -0.2331448942 1819 1311867231.1221020222 0.0553195924 0.0583316609 0.0880135372 0.0055678214 0.2025580000 981823705 0 402718720 -0.0334648378 0.1512985826 -0.2335583270 1820 1311867231.1523799896 0.0553069524 0.0583299990 0.0880135372 0.0055706647 0.2028090000 981826497 0 402718720 -0.0345039777 0.1502304822 -0.2339845747 1821 1311867231.1860070229 0.0550427958 0.0583281938 0.0880135372 0.0055691481 0.1870680000 981829457 0 402718720 -0.0354911573 0.1490891427 -0.2347704023 1822 1311867231.2188270092 0.0552474000 0.0583265029 0.0880135372 0.0055686276 0.1867530000 981832361 0 402718720 -0.0362763479 0.1478469521 -0.2351102829 1823 1311867231.2522621155 0.0549070984 0.0583246272 0.0880135372 0.0055690424 0.1839780000 981835321 0 402718720 -0.0366367884 0.1466518044 -0.2358078957 1824 1311867231.2864110470 0.0547768101 0.0583226821 0.0880135372 0.0055689990 0.1845630000 981838281 0 402718720 -0.0379771739 0.1456098855 -0.2364942431 1825 1311867231.3215939999 0.0548290610 0.0583207678 0.0880135372 0.0055677438 0.1965510000 981841297 0 402718720 -0.0402373411 0.1441131532 -0.2369734645 1826 1311867231.3525509834 0.0546935946 0.0583187814 0.0880135372 0.0055663706 0.1859000000 981844145 0 402718720 -0.0404773913 0.1426726878 -0.2374464273 1827 1311867231.3874650002 0.0544884764 0.0583166849 0.0880135372 0.0055649510 0.1853030000 981847105 0 402718720 -0.0398212634 0.1414227337 -0.2377442718 1828 1311867231.4187040329 0.0541001633 0.0583143783 0.0880135372 0.0055635297 0.1852120000 981850009 0 402718720 -0.0399786010 0.1403975040 -0.2380805016 1829 1311867231.4542400837 0.0540695675 0.0583120575 0.0880135372 0.0055621716 0.1853060000 981853025 0 402718720 -0.0402141251 0.1392484009 -0.2379673570 1830 1311867231.4867990017 0.0537522547 0.0583095658 0.0880135372 0.0055607553 0.2012910000 981855929 0 402718720 -0.0412866808 0.1380729824 -0.2380508333 1831 1311867231.5193030834 0.0538559482 0.0583071334 0.0880135372 0.0055594967 0.1850600000 981858833 0 402718720 -0.0410602167 0.1370620877 -0.2378491014 1832 1311867231.5524148941 0.0538783185 0.0583047159 0.0880135372 0.0055585038 0.1860720000 981861737 0 402718720 -0.0409243591 0.1361635774 -0.2377703041 1833 1311867231.5855851173 0.0532473512 0.0583019569 0.0880135372 0.0055626279 0.1852260000 981864753 0 402718720 -0.0413509794 0.1353512555 -0.2376454324 1834 1311867231.6210820675 0.0540832616 0.0582996566 0.0880135372 0.0055723260 0.1964650000 981867713 0 402718720 -0.0412651002 0.1346520036 -0.2378504127 1835 1311867231.6522169113 0.0541100577 0.0582973734 0.0880135372 0.0055710055 0.1848770000 981870617 0 402718720 -0.0416746885 0.1338478476 -0.2380985469 1836 1311867231.6880500317 0.0539779104 0.0582950208 0.0880135372 0.0055695011 0.1960580000 981873633 0 402718720 -0.0413904190 0.1328991205 -0.2382944822 1837 1311867231.7208089828 0.0538257882 0.0582925879 0.0880135372 0.0055683430 0.1858350000 981876593 0 402718720 -0.0409668051 0.1319230944 -0.2386341393 1838 1311867231.7523078918 0.0539157577 0.0582902066 0.0880135372 0.0055695871 0.1859900000 981879385 0 402718720 -0.0406082869 0.1310572177 -0.2390093952 1839 1311867231.7860589027 0.0541282967 0.0582879435 0.0880135372 0.0055681359 0.1987440000 981882401 0 402718720 -0.0415112302 0.1300816536 -0.2393219024 1840 1311867231.8202130795 0.0543202534 0.0582857871 0.0880135372 0.0055676838 0.1858430000 981885361 0 402718720 -0.0423267148 0.1288788617 -0.2398849279 1841 1311867231.8521840572 0.0540801547 0.0582835027 0.0880135372 0.0055668129 0.2080500000 981888209 0 402718720 -0.0424468853 0.1276338696 -0.2403299361 1842 1311867231.8857500553 0.0536155514 0.0582809685 0.0880135372 0.0055657656 0.1979410000 981891225 0 402718720 -0.0425952263 0.1263005435 -0.2409333885 1843 1311867231.9208559990 0.0536668263 0.0582784649 0.0880135372 0.0055642918 0.1945220000 981894241 0 402718720 -0.0428134240 0.1250060052 -0.2415793091 1844 1311867231.9533181190 0.0538427308 0.0582760594 0.0880135372 0.0055634281 0.2260330000 981897089 0 402718720 -0.0435517058 0.1233817711 -0.2420368940 1845 1311867231.9870491028 0.0538918152 0.0582736831 0.0880135372 0.0055620813 0.2255270000 981900049 0 402718720 -0.0433088504 0.1221042350 -0.2424822301 1846 1311867232.0202860832 0.0541223921 0.0582714343 0.0880135372 0.0055606505 0.2266380000 981903009 0 402718720 -0.0443393439 0.1207847968 -0.2428463995 1847 1311867232.0522420406 0.0538433455 0.0582690369 0.0880135372 0.0055592006 0.2261370000 981905913 0 402718720 -0.0445190482 0.1195117012 -0.2433879524 1848 1311867232.0878489017 0.0538953617 0.0582666702 0.0880135372 0.0055577241 0.2270620000 981908929 0 402718720 -0.0447428375 0.1182223856 -0.2438188195 1849 1311867232.1203238964 0.0544687919 0.0582646161 0.0880135372 0.0055575824 0.2265240000 981911833 0 402718720 -0.0446197391 0.1169641837 -0.2443553060 1850 1311867232.1545510292 0.0538245402 0.0582622161 0.0880135372 0.0055567463 0.2277660000 981914793 0 402718720 -0.0435670465 0.1160463765 -0.2446146160 1851 1311867232.1846179962 0.0536375269 0.0582597176 0.0880135372 0.0055557992 0.2180880000 981917641 0 402718720 -0.0439130664 0.1147831082 -0.2452753335 1852 1311867232.2209780216 0.0536959283 0.0582572534 0.0880135372 0.0055547950 0.1845890000 981920657 0 402718720 -0.0451216549 0.1137255058 -0.2456641346 1853 1311867232.2531120777 0.0535441525 0.0582547099 0.0880135372 0.0055533974 0.1849850000 981923505 0 402718720 -0.0445101894 0.1127193272 -0.2460888624 1854 1311867232.2844479084 0.0535239168 0.0582521582 0.0880135372 0.0055526031 0.1935210000 981926465 0 402718720 -0.0447912775 0.1113436446 -0.2466046512 1855 1311867232.3209791183 0.0532720722 0.0582494735 0.0880135372 0.0055513061 0.1978960000 981929481 0 402718720 -0.0457321778 0.1102935374 -0.2471317947 1856 1311867232.3544659615 0.0530643687 0.0582466798 0.0880135372 0.0055502513 0.1851870000 981932385 0 402718720 -0.0454223454 0.1094333231 -0.2474800050 1857 1311867232.3858909607 0.0533887260 0.0582440638 0.0880135372 0.0055487688 0.1852390000 981935289 0 402718720 -0.0457600281 0.1083158627 -0.2478761226 1858 1311867232.4203910828 0.0532308109 0.0582413656 0.0880135372 0.0055480808 0.1841720000 981938249 0 402718720 -0.0453863256 0.1074958965 -0.2483538091 1859 1311867232.4544560909 0.0532349460 0.0582386725 0.0880135372 0.0055466562 0.2037170000 981941209 0 402718720 -0.0450527146 0.1066447943 -0.2485362440 1860 1311867232.4846010208 0.0526383147 0.0582356616 0.0880135372 0.0055504996 0.1841900000 981944057 0 402718720 -0.0453086607 0.1057204083 -0.2487331033 1861 1311867232.5203030109 0.0526830405 0.0582326779 0.0880135372 0.0055502330 0.1841020000 981947073 0 402718720 -0.0451607704 0.1047466174 -0.2489377707 1862 1311867232.5550050735 0.0511031449 0.0582288489 0.0880135372 0.0055512342 0.1837990000 981950033 0 402718720 -0.0453158990 0.1039012522 -0.2490663826 1863 1311867232.5844318867 0.0526602566 0.0582258599 0.0880135372 0.0055524993 0.1840280000 981952825 0 402718720 -0.0448180884 0.1029276326 -0.2492716908 1864 1311867232.6201601028 0.0525708683 0.0582228261 0.0880135372 0.0055511198 0.2094910000 981955841 0 402718720 -0.0445400253 0.1022851095 -0.2493716627 1865 1311867232.6554861069 0.0524984114 0.0582197567 0.0880135372 0.0055503988 0.1853090000 981958689 0 402718720 -0.0429204218 0.1010599509 -0.2493441850 1866 1311867232.6850490570 0.0525922813 0.0582167409 0.0880135372 0.0055490286 0.2110160000 981961537 0 402718720 -0.0429412536 0.0998771936 -0.2495525032 1867 1311867232.7210319042 0.0524602234 0.0582136576 0.0880135372 0.0055475624 0.1855600000 981964553 0 402718720 -0.0427581780 0.0986929089 -0.2497136593 1868 1311867232.7539520264 0.0523758717 0.0582105325 0.0880135372 0.0055467960 0.1852970000 981967401 0 402718720 -0.0427617393 0.0975981578 -0.2497545481 1869 1311867232.7885808945 0.0524007082 0.0582074239 0.0880135372 0.0055454390 0.1953280000 981970361 0 402718720 -0.0425526798 0.0960536078 -0.2497995943 1870 1311867232.8206169605 0.0526707545 0.0582044632 0.0880135372 0.0055441093 0.1856130000 981973321 0 402718720 -0.0432518981 0.0940208733 -0.2500350475 1871 1311867232.8539369106 0.0524996072 0.0582014141 0.0880135372 0.0055427189 0.1822070000 981976225 0 402718720 -0.0427254736 0.0929201990 -0.2501728535 1872 1311867232.8882710934 0.0525127947 0.0581983753 0.0880135372 0.0055412503 0.1827520000 981979185 0 402718720 -0.0422432758 0.0916008949 -0.2503158450 1873 1311867232.9203770161 0.0523968786 0.0581952778 0.0880135372 0.0055403656 0.1823950000 981982145 0 402718720 -0.0429873280 0.0901269242 -0.2507186234 1874 1311867232.9559900761 0.0522324368 0.0581920960 0.0880135372 0.0055389500 0.1834310000 981985161 0 402718720 -0.0431208611 0.0884631798 -0.2509566545 1875 1311867232.9890038967 0.0522864126 0.0581889463 0.0880135372 0.0055385725 0.1831270000 981988009 0 402718720 -0.0443491414 0.0873304978 -0.2511690557 1876 1311867233.0212259293 0.0522589907 0.0581857853 0.0880135372 0.0055374018 0.1831300000 981990969 0 402718720 -0.0438315235 0.0857153088 -0.2513273060 1877 1311867233.0569291115 0.0521005541 0.0581825433 0.0880135372 0.0055364707 0.1827120000 981993929 0 402718720 -0.0440820567 0.0845228434 -0.2513968349 1878 1311867233.0943200588 0.0520815030 0.0581792946 0.0880135372 0.0055354731 0.1950100000 981997001 0 402718720 -0.0433644056 0.0834118128 -0.2513264418 1879 1311867233.1241600513 0.0524453111 0.0581762430 0.0880135372 0.0055344088 0.1932940000 981999737 0 402718720 -0.0437558368 0.0819862559 -0.2512056828 1880 1311867233.1530799866 0.0519172177 0.0581729137 0.0880135372 0.0055348742 0.1832500000 982002529 0 402718720 -0.0430989973 0.0809100121 -0.2512600422 1881 1311867233.1887679100 0.0522378162 0.0581697584 0.0880135372 0.0055343253 0.1829850000 982005545 0 402718720 -0.0431513153 0.0798832551 -0.2510977387 1882 1311867233.2210481167 0.0519913733 0.0581664756 0.0880135372 0.0055329090 0.1831730000 982008449 0 402718720 -0.0427382141 0.0787515491 -0.2512485385 1883 1311867233.2590179443 0.0523096696 0.0581633652 0.0880135372 0.0055315823 0.1816440000 982011521 0 402718720 -0.0436410196 0.0771090090 -0.2511991262 1884 1311867233.2899589539 0.0519261286 0.0581600546 0.0880135372 0.0055302365 0.1900330000 982014425 0 402718720 -0.0432444476 0.0759225264 -0.2511852682 1885 1311867233.3212211132 0.0517990105 0.0581566800 0.0880135372 0.0055299480 0.1814440000 982017329 0 402718720 -0.0435078628 0.0746302903 -0.2510423362 1886 1311867233.3533849716 0.0523086600 0.0581535793 0.0880135372 0.0055291677 0.1926880000 982020177 0 402718720 -0.0436029583 0.0726531744 -0.2510819733 1887 1311867233.3884561062 0.0522151068 0.0581504322 0.0880135372 0.0055309227 0.1805800000 982023193 0 402718720 -0.0445354693 0.0714271441 -0.2511676252 1888 1311867233.4236669540 0.0520282164 0.0581471895 0.0880135372 0.0055356718 0.1938120000 982026153 0 402718720 -0.0444657728 0.0699298903 -0.2512562871 1889 1311867233.4522700310 0.0523335747 0.0581441119 0.0880135372 0.0055368779 0.1913600000 982029057 0 402718720 -0.0452403426 0.0678090155 -0.2516413629 1890 1311867233.4881610870 0.0523611978 0.0581410522 0.0880135372 0.0055404287 0.1929020000 982031961 0 402718720 -0.0457453281 0.0662219077 -0.2518515885 1891 1311867233.5201199055 0.0520454235 0.0581378287 0.0880135372 0.0055404214 0.1804950000 982034921 0 402718720 -0.0457640141 0.0654351711 -0.2520178258 1892 1311867233.5526270866 0.0521113351 0.0581346434 0.0880135372 0.0055404628 0.1795760000 982037825 0 402718720 -0.0460840426 0.0641087368 -0.2521823049 1893 1311867233.5890851021 0.0518081151 0.0581313013 0.0880135372 0.0055391722 0.1792580000 982040841 0 402718720 -0.0453568175 0.0632638410 -0.2521997094 1894 1311867233.6202619076 0.0519164242 0.0581280200 0.0880135372 0.0055377831 0.2152860000 982043745 0 402718720 -0.0456194021 0.0623345114 -0.2520808876 1895 1311867233.6539080143 0.0517648049 0.0581246621 0.0880135372 0.0055377795 0.1787540000 982046649 0 402718720 -0.0457755476 0.0613381788 -0.2522500157 1896 1311867233.6879289150 0.0518953912 0.0581213766 0.0880135372 0.0055365456 0.1789350000 982049609 0 402718720 -0.0464206450 0.0603358559 -0.2522263825 1897 1311867233.7197790146 0.0518876314 0.0581180905 0.0880135372 0.0055351818 0.1790400000 982052569 0 402718720 -0.0460774377 0.0597750917 -0.2521570027 1898 1311867233.7577540874 0.0518504120 0.0581147883 0.0880135372 0.0055340014 0.1785960000 982055641 0 402718720 -0.0462619476 0.0591120422 -0.2521407604 1899 1311867233.7896089554 0.0517368205 0.0581114297 0.0880135372 0.0055335748 0.1779530000 982058545 0 402718720 -0.0471982658 0.0583448596 -0.2521950901 1900 1311867233.8221189976 0.0517746322 0.0581080945 0.0880135372 0.0055338213 0.1783150000 982061505 0 402718720 -0.0478978902 0.0574538894 -0.2521674633 1901 1311867233.8562450409 0.0519085936 0.0581048333 0.0880135372 0.0055324488 0.1782560000 982064409 0 402718720 -0.0482180305 0.0562684573 -0.2520772815 1902 1311867233.8885691166 0.0520046502 0.0581016261 0.0880135372 0.0055311744 0.1778640000 982067313 0 402718720 -0.0486963838 0.0553806983 -0.2519178987 1903 1311867233.9203450680 0.0518067814 0.0580983182 0.0880135372 0.0055300480 0.1776110000 982070217 0 402718720 -0.0485531129 0.0546904802 -0.2518071532 1904 1311867233.9552910328 0.0515783168 0.0580948939 0.0880135372 0.0055286988 0.2038940000 982073233 0 402718720 -0.0484948605 0.0534703583 -0.2518823445 1905 1311867233.9885900021 0.0514861196 0.0580914247 0.0880135372 0.0055273178 0.1776440000 982076137 0 402718720 -0.0486524105 0.0524504445 -0.2518666089 1906 1311867234.0205829144 0.0512735583 0.0580878476 0.0880135372 0.0055258914 0.1777220000 982079041 0 402718720 -0.0487985946 0.0519662164 -0.2520202994 1907 1311867234.0566239357 0.0514205210 0.0580843514 0.0880135372 0.0055245555 0.1780210000 982082113 0 402718720 -0.0494935066 0.0506760366 -0.2520985305 1908 1311867234.0907170773 0.0512619168 0.0580807757 0.0880135372 0.0055231281 0.1890800000 982085017 0 402718720 -0.0496379249 0.0497226864 -0.2523048520 1909 1311867234.1214520931 0.0513568968 0.0580772535 0.0880135372 0.0055217811 0.1771790000 982087921 0 402718720 -0.0498947389 0.0487522967 -0.2522465289 1910 1311867234.1561689377 0.0514647886 0.0580737915 0.0880135372 0.0055204022 0.1762940000 982090881 0 402718720 -0.0504018366 0.0471901707 -0.2523021102 1911 1311867234.1892559528 0.0517842844 0.0580705003 0.0880135372 0.0055190941 0.1734490000 982093785 0 402718720 -0.0517893061 0.0457079671 -0.2522647679 1912 1311867234.2203600407 0.0516948886 0.0580671657 0.0880135372 0.0055188555 0.1745150000 982096689 0 402718720 -0.0522804745 0.0448585562 -0.2524196506 1913 1311867234.2588930130 0.0514455996 0.0580637044 0.0880135372 0.0055175821 0.1743770000 982099761 0 402718720 -0.0531172715 0.0436330475 -0.2524948418 1914 1311867234.2895319462 0.0512496307 0.0580601443 0.0880135372 0.0055163071 0.1893430000 982102665 0 402718720 -0.0531775206 0.0426612087 -0.2523553669 1915 1311867234.3213200569 0.0510207079 0.0580564683 0.0880135372 0.0055183278 0.1739120000 982105569 0 402718720 -0.0539358370 0.0418932214 -0.2520221174 1916 1311867234.3570129871 0.0507532395 0.0580526566 0.0880135372 0.0055169279 0.1741970000 982108529 0 402718720 -0.0541700870 0.0414900482 -0.2517465353 1917 1311867234.3885769844 0.0506338775 0.0580487866 0.0880135372 0.0055160145 0.1743590000 982111433 0 402718720 -0.0541660860 0.0403788909 -0.2514937818 1918 1311867234.4204909801 0.0507530943 0.0580449828 0.0880135372 0.0055146015 0.1742600000 982114393 0 402718720 -0.0543498248 0.0393628255 -0.2510411441 1919 1311867234.4579920769 0.0504250005 0.0580410120 0.0880135372 0.0055134377 0.1842630000 982117353 0 402718720 -0.0532999858 0.0392324105 -0.2506797910 1920 1311867234.4878959656 0.0508545078 0.0580372690 0.0880135372 0.0055172700 0.1722190000 982120257 0 402718720 -0.0545038469 0.0379644036 -0.2504740059 1921 1311867234.5201239586 0.0510887913 0.0580336519 0.0880135372 0.0055158971 0.1737090000 982123161 0 402718720 -0.0550943203 0.0364564247 -0.2501598299 1922 1311867234.5594279766 0.0507888049 0.0580298825 0.0880135372 0.0055153358 0.1963370000 982126289 0 402718720 -0.0551173985 0.0360803977 -0.2497174442 1923 1311867234.5882380009 0.0509981960 0.0580262259 0.0880135372 0.0055149661 0.1734940000 982129137 0 402718720 -0.0547806099 0.0348792449 -0.2492727339 1924 1311867234.6204199791 0.0512378998 0.0580226976 0.0880135372 0.0055136326 0.1880290000 982132041 0 402718720 -0.0548784100 0.0334977396 -0.2489336282 1925 1311867234.6590909958 0.0504388250 0.0580187580 0.0880135372 0.0055129807 0.1714810000 982135113 0 402718720 -0.0543201789 0.0337534957 -0.2484933883 1926 1311867234.6880459785 0.0502892956 0.0580147447 0.0880135372 0.0055116479 0.1856770000 982137905 0 402718720 -0.0536452010 0.0332403444 -0.2481003106 1927 1311867234.7198779583 0.0504082814 0.0580107974 0.0880135372 0.0055113104 0.1726190000 982140809 0 402718720 -0.0536604151 0.0323145874 -0.2474825978 1928 1311867234.7586181164 0.0499823913 0.0580066333 0.0880135372 0.0055099166 0.1728360000 982143825 0 402718720 -0.0524674430 0.0319361947 -0.2465821654 1929 1311867234.7882609367 0.0495298579 0.0580022389 0.0880135372 0.0055163203 0.1735190000 982146729 0 402718720 -0.0524064377 0.0318278372 -0.2456194758 1930 1311867234.8206560612 0.0496501215 0.0579979114 0.0880135372 0.0055150139 0.1843320000 982149633 0 402718720 -0.0528054200 0.0312642641 -0.2447249591 1931 1311867234.8590250015 0.0494681969 0.0579934941 0.0880135372 0.0055136486 0.1744360000 982152649 0 402718720 -0.0516650453 0.0316180363 -0.2437614202 1932 1311867234.8881230354 0.0499395840 0.0579893255 0.0880135372 0.0055124479 0.1737330000 982155497 0 402718720 -0.0512543768 0.0312710367 -0.2427295446 1933 1311867234.9204928875 0.0504421853 0.0579854211 0.0880135372 0.0055116898 0.1859010000 982158457 0 402718720 -0.0519519038 0.0304033644 -0.2420242578 1934 1311867234.9566090107 0.0506076589 0.0579816063 0.0880135372 0.0055104092 0.1862040000 982161473 0 402718720 -0.0519465059 0.0302070510 -0.2415122539 1935 1311867234.9904088974 0.0509748533 0.0579779853 0.0880135372 0.0055090215 0.1854650000 982164433 0 402718720 -0.0525361151 0.0295092817 -0.2410508096 1936 1311867235.0205988884 0.0510530435 0.0579744083 0.0880135372 0.0055079551 0.1724870000 982167281 0 402718720 -0.0526763648 0.0286845192 -0.2410680652 1937 1311867235.0563809872 0.0511034466 0.0579708611 0.0880135372 0.0055080009 0.1734490000 982170297 0 402718720 -0.0528026633 0.0276691262 -0.2411087155 1938 1311867235.0911149979 0.0511988141 0.0579673668 0.0880135372 0.0055066375 0.1713090000 982173257 0 402718720 -0.0543653928 0.0269494820 -0.2410378009 1939 1311867235.1208140850 0.0514217243 0.0579639910 0.0880135372 0.0055053263 0.1816770000 982176161 0 402718720 -0.0555436984 0.0258152205 -0.2409731895 1940 1311867235.1564071178 0.0508566834 0.0579603274 0.0880135372 0.0055048131 0.1832690000 982179121 0 402718720 -0.0543452613 0.0255854409 -0.2406304181 1941 1311867235.1885681152 0.0507663898 0.0579566211 0.0880135372 0.0055043139 0.1711520000 982182025 0 402718720 -0.0544251204 0.0247013904 -0.2402459085 1942 1311867235.2202088833 0.0506917909 0.0579528802 0.0880135372 0.0055030514 0.1705020000 982184929 0 402718720 -0.0554830618 0.0239432268 -0.2402196079 1943 1311867235.2576260567 0.0509658009 0.0579492842 0.0880135372 0.0055023919 0.1697270000 982187833 0 402718720 -0.0559225455 0.0240065455 -0.2399294972 1944 1311867235.2899661064 0.0508174524 0.0579456156 0.0880135372 0.0055025200 0.1850240000 982190793 0 402718720 -0.0576173179 0.0232456792 -0.2398347855 1945 1311867235.3247830868 0.0506408885 0.0579418599 0.0880135372 0.0055012249 0.1712510000 982193809 0 402718720 -0.0576704331 0.0228228886 -0.2398411781 1946 1311867235.3567800522 0.0497528873 0.0579376518 0.0880135372 0.0055126747 0.1699580000 982196713 0 402718720 -0.0588178225 0.0227841754 -0.2395162880 1947 1311867235.3886280060 0.0507293232 0.0579339495 0.0880135372 0.0055229361 0.1705180000 982199617 0 402718720 -0.0589884408 0.0225145537 -0.2392050028 1948 1311867235.4246189594 0.0504723080 0.0579301191 0.0880135372 0.0055222741 0.1706230000 982202633 0 402718720 -0.0601537749 0.0223692320 -0.2386816144 1949 1311867235.4564850330 0.0507130995 0.0579264162 0.0880135372 0.0055216436 0.1833020000 982205537 0 402718720 -0.0601511635 0.0228711013 -0.2378868908 1950 1311867235.4897930622 0.0505267680 0.0579226215 0.0880135372 0.0055216286 0.1720440000 982208441 0 402718720 -0.0603458881 0.0228276271 -0.2370288819 1951 1311867235.5240719318 0.0508819781 0.0579190128 0.0880135372 0.0055208721 0.1850650000 982211401 0 402718720 -0.0614171550 0.0227270219 -0.2363293916 1952 1311867235.5577290058 0.0507883430 0.0579153597 0.0880135372 0.0055198224 0.1709190000 982214305 0 402718720 -0.0608315952 0.0232737064 -0.2354612052 1953 1311867235.5880639553 0.0513205305 0.0579119830 0.0880135372 0.0055185061 0.1715420000 982217209 0 402718720 -0.0614929385 0.0227203593 -0.2347873747 1954 1311867235.6249940395 0.0517402291 0.0579088245 0.0880135372 0.0055174362 0.1720920000 982220281 0 402718720 -0.0619217940 0.0213599242 -0.2345439643 1955 1311867235.6563270092 0.0516264960 0.0579056110 0.0880135372 0.0055167891 0.1718060000 982223129 0 402718720 -0.0624520518 0.0218872372 -0.2341684997 1956 1311867235.6885619164 0.0517520942 0.0579024650 0.0880135372 0.0055155730 0.1718380000 982226033 0 402718720 -0.0631970316 0.0214552842 -0.2338770330 1957 1311867235.7241950035 0.0516298935 0.0578992598 0.0880135372 0.0055142317 0.1705230000 982229049 0 402718720 -0.0641379952 0.0209466349 -0.2336714119 1958 1311867235.7561719418 0.0513094142 0.0578958942 0.0880135372 0.0055131414 0.1703200000 982232009 0 402718720 -0.0640483126 0.0210345984 -0.2331249714 1959 1311867235.7903280258 0.0513814278 0.0578925688 0.0880135372 0.0055123817 0.1956530000 982234913 0 402718720 -0.0645565018 0.0206632130 -0.2324819565 1960 1311867235.8249480724 0.0514568947 0.0578892853 0.0880135372 0.0055111822 0.1708700000 982237873 0 402718720 -0.0649747923 0.0203722715 -0.2317444980 1961 1311867235.8562169075 0.0515635796 0.0578860596 0.0880135372 0.0055110674 0.1710230000 982240833 0 402718720 -0.0650338382 0.0210034791 -0.2306562960 1962 1311867235.8881049156 0.0519687273 0.0578830436 0.0880135372 0.0055097301 0.1714170000 982243625 0 402718720 -0.0661258474 0.0206982549 -0.2298168689 1963 1311867235.9239900112 0.0521897525 0.0578801433 0.0880135372 0.0055083353 0.1713260000 982246697 0 402718720 -0.0664281324 0.0201073773 -0.2288982570 1964 1311867235.9563760757 0.0523493253 0.0578773272 0.0880135372 0.0055076081 0.1862900000 982249657 0 402718720 -0.0658120885 0.0205065738 -0.2282082438 1965 1311867235.9890949726 0.0519874766 0.0578743298 0.0880135372 0.0055069786 0.1715560000 982252505 0 402718720 -0.0669003949 0.0200052578 -0.2278131247 1966 1311867236.0250449181 0.0519272648 0.0578713048 0.0880135372 0.0055056533 0.1706010000 982255521 0 402718720 -0.0673901513 0.0196859632 -0.2272875458 1967 1311867236.0599400997 0.0516353063 0.0578681345 0.0880135372 0.0055042661 0.1701030000 982258481 0 402718720 -0.0673410818 0.0197633896 -0.2265841365 1968 1311867236.0884859562 0.0518293194 0.0578650660 0.0880135372 0.0055029812 0.1699780000 982261273 0 402718720 -0.0677424967 0.0195489675 -0.2256796807 1969 1311867236.1247038841 0.0517765172 0.0578619738 0.0880135372 0.0055016550 0.1816620000 982264345 0 402718720 -0.0677982643 0.0195709616 -0.2246677727 1970 1311867236.1581289768 0.0522504523 0.0578591253 0.0880135372 0.0055008772 0.1720770000 982267249 0 402718720 -0.0683305189 0.0196741652 -0.2235013396 1971 1311867236.1901528835 0.0519263111 0.0578561153 0.0880135372 0.0054996868 0.1709450000 982270097 0 402718720 -0.0696047768 0.0198781900 -0.2223264724 1972 1311867236.2242329121 0.0514271408 0.0578528552 0.0880135372 0.0054983965 0.1716920000 982273057 0 402718720 -0.0694709569 0.0197876543 -0.2212257683 1973 1311867236.2599489689 0.0511007495 0.0578494329 0.0880135372 0.0054973389 0.1693510000 982276073 0 402718720 -0.0697889104 0.0199800357 -0.2199495882 1974 1311867236.2890419960 0.0514273793 0.0578461796 0.0880135372 0.0054960382 0.1893320000 982278865 0 402718720 -0.0705825984 0.0197282452 -0.2187672853 1975 1311867236.3262441158 0.0518676527 0.0578431525 0.0880135372 0.0054950149 0.1720370000 982281937 0 402718720 -0.0710204989 0.0195238162 -0.2173154205 1976 1311867236.3568809032 0.0519155040 0.0578401527 0.0880135372 0.0054939924 0.1715280000 982284841 0 402718720 -0.0708918646 0.0189020224 -0.2161178291 1977 1311867236.3897418976 0.0518294722 0.0578371124 0.0880135372 0.0054926544 0.1712870000 982287745 0 402718720 -0.0717037395 0.0187121835 -0.2149660736 1978 1311867236.4243390560 0.0510467924 0.0578336794 0.0880135372 0.0054938204 0.1713350000 982290705 0 402718720 -0.0715547949 0.0185617171 -0.2134895921 1979 1311867236.4566040039 0.0509267375 0.0578301893 0.0880135372 0.0054927727 0.1704640000 982293665 0 402718720 -0.0717181042 0.0186818633 -0.2120840698 1980 1311867236.4936130047 0.0515915602 0.0578270385 0.0880135372 0.0054968621 0.1909340000 982296681 0 402718720 -0.0723644346 0.0183003750 -0.2106433511 1981 1311867236.5246999264 0.0516024791 0.0578238964 0.0880135372 0.0054956014 0.1835710000 982299585 0 402718720 -0.0728642270 0.0185672771 -0.2090120763 1982 1311867236.5602099895 0.0511291139 0.0578205186 0.0880135372 0.0054960374 0.1726670000 982302601 0 402718720 -0.0727413371 0.0186145492 -0.2073904872 1983 1311867236.5972909927 0.0510663800 0.0578171126 0.0880135372 0.0054949374 0.1733430000 982305617 0 402718720 -0.0724282339 0.0180677380 -0.2057349831 1984 1311867236.6246581078 0.0513045527 0.0578138300 0.0880135372 0.0054935877 0.1953520000 982308353 0 402718720 -0.0729112104 0.0179871246 -0.2039049715 1985 1311867236.6600480080 0.0511258617 0.0578104608 0.0880135372 0.0054923431 0.1732670000 982311369 0 402718720 -0.0724857822 0.0182302073 -0.2016927302 1986 1311867236.6956660748 0.0509130731 0.0578069878 0.0880135372 0.0054917861 0.1725600000 982314385 0 402718720 -0.0723426566 0.0182548556 -0.1995660216 1987 1311867236.7276370525 0.0509164408 0.0578035199 0.0880135372 0.0054906583 0.1730380000 982317233 0 402718720 -0.0718157515 0.0181824137 -0.1973431259 1988 1311867236.7619268894 0.0508639477 0.0578000292 0.0880135372 0.0054902089 0.1738270000 982320193 0 402718720 -0.0715038627 0.0178015288 -0.1952511817 1989 1311867236.7923469543 0.0515708476 0.0577968974 0.0880135372 0.0054912549 0.1928910000 982323041 0 402718720 -0.0720320120 0.0176156461 -0.1931777745 1990 1311867236.8255391121 0.0512949787 0.0577936301 0.0880135372 0.0054905315 0.1742230000 982326057 0 402718720 -0.0724418908 0.0173577853 -0.1913565695 1991 1311867236.8583440781 0.0515835918 0.0577905110 0.0880135372 0.0054901238 0.1741800000 982328905 0 402718720 -0.0725209117 0.0170998462 -0.1893033683 1992 1311867236.8928480148 0.0514358468 0.0577873210 0.0880135372 0.0054900487 0.1722500000 982331865 0 402718720 -0.0723296329 0.0168968979 -0.1873104423 1993 1311867236.9255330563 0.0512850992 0.0577840584 0.0880135372 0.0054888229 0.1742780000 982334769 0 402718720 -0.0720333904 0.0165232029 -0.1853851825 1994 1311867236.9581959248 0.0514803939 0.0577808971 0.0880135372 0.0054876909 0.1836070000 982337673 0 402718720 -0.0723133907 0.0167521462 -0.1830950528 1995 1311867236.9937291145 0.0510334559 0.0577775149 0.0880135372 0.0054897018 0.1747540000 982340689 0 402718720 -0.0718188062 0.0172291063 -0.1808246225 1996 1311867237.0244200230 0.0511721037 0.0577742056 0.0880135372 0.0054891862 0.1755700000 982343537 0 402718720 -0.0724635199 0.0165905133 -0.1787972301 1997 1311867237.0603060722 0.0503811724 0.0577705035 0.0880135372 0.0054925560 0.1750450000 982346553 0 402718720 -0.0728657916 0.0169770028 -0.1767878830 1998 1311867237.0927588940 0.0509484075 0.0577670891 0.0880135372 0.0055057307 0.1767930000 982349513 0 402718720 -0.0718327761 0.0178237446 -0.1745894402 1999 1311867237.1276650429 0.0510233752 0.0577637155 0.0880135372 0.0055058542 0.1868460000 982352473 0 402718720 -0.0715523437 0.0168049149 -0.1728491336 2000 1311867237.1566579342 0.0509759523 0.0577603217 0.0880135372 0.0055052535 0.1761810000 982355265 0 402718720 -0.0725831687 0.0166412294 -0.1711615026 2001 1311867237.1925950050 0.0508635081 0.0577568750 0.0880135372 0.0055043449 0.1759750000 982358281 0 402718720 -0.0717983767 0.0170543697 -0.1692855209 2002 1311867237.2254281044 0.0519001447 0.0577539495 0.0880135372 0.0055032736 0.1746700000 982361241 0 402718720 -0.0734108388 0.0156686120 -0.1677989662 2003 1311867237.2569580078 0.0513709895 0.0577507628 0.0880135372 0.0055032040 0.1761140000 982364145 0 402718720 -0.0737120882 0.0152666671 -0.1663817614 2004 1311867237.2944281101 0.0510117598 0.0577474001 0.0880135372 0.0055018723 0.1875200000 982367161 0 402718720 -0.0740795434 0.0161135774 -0.1648562253 2005 1311867237.3250501156 0.0512731373 0.0577441710 0.0880135372 0.0055006443 0.1770540000 982370065 0 402718720 -0.0748847649 0.0158960093 -0.1632875353 2006 1311867237.3565309048 0.0518925227 0.0577412539 0.0880135372 0.0055009563 0.1765000000 982372969 0 402718720 -0.0753227770 0.0154482927 -0.1616649628 2007 1311867237.3934979439 0.0509273224 0.0577378588 0.0880135372 0.0055005701 0.1766950000 982375929 0 402718720 -0.0747078434 0.0160913076 -0.1598260850 2008 1311867237.4248709679 0.0511213839 0.0577345638 0.0880135372 0.0054993612 0.1772850000 982378889 0 402718720 -0.0751522705 0.0152847087 -0.1581307650 2009 1311867237.4579510689 0.0512185879 0.0577313204 0.0880135372 0.0054980407 0.2125850000 982381793 0 402718720 -0.0754783824 0.0147541324 -0.1563852429 2010 1311867237.4933559895 0.0509635620 0.0577279533 0.0880135372 0.0054975301 0.1773970000 982384809 0 402718720 -0.0759356022 0.0152054960 -0.1545178294 2011 1311867237.5253219604 0.0508831777 0.0577245497 0.0880135372 0.0054985886 0.1894750000 982387713 0 402718720 -0.0757618919 0.0139665660 -0.1525362432 2012 1311867237.5581231117 0.0513765998 0.0577213946 0.0880135372 0.0054975112 0.2169940000 982390673 0 402718720 -0.0758328289 0.0132109821 -0.1506180316 2013 1311867237.5925350189 0.0514546633 0.0577182815 0.0880135372 0.0054988931 0.2174030000 982393577 0 402718720 -0.0764397606 0.0138712572 -0.1484844983 2014 1311867237.6261129379 0.0514583141 0.0577151733 0.0880135372 0.0054978105 0.2177640000 982396593 0 402718720 -0.0766393021 0.0131424852 -0.1465971023 2015 1311867237.6569290161 0.0515228137 0.0577121001 0.0880135372 0.0054968846 0.2175770000 982399441 0 402718720 -0.0768728033 0.0125019467 -0.1446044743 2016 1311867237.6925010681 0.0513243675 0.0577089316 0.0880135372 0.0054955487 0.2176360000 982402401 0 402718720 -0.0768082812 0.0124643408 -0.1426281482 2017 1311867237.7243609428 0.0518031679 0.0577060036 0.0880135372 0.0054942043 0.2177200000 982405305 0 402718720 -0.0770335272 0.0122019928 -0.1404598355 2018 1311867237.7617940903 0.0518860258 0.0577031196 0.0880135372 0.0054929253 0.2172980000 982408433 0 402718720 -0.0777033269 0.0112763690 -0.1382577270 2019 1311867237.7926809788 0.0516680405 0.0577001305 0.0880135372 0.0054918360 0.2162230000 982411225 0 402718720 -0.0778287351 0.0116281742 -0.1358643919 2020 1311867237.8255820274 0.0516080186 0.0576971146 0.0880135372 0.0054908604 0.1795000000 982414185 0 402718720 -0.0776313543 0.0118142487 -0.1335774809 2021 1311867237.8612699509 0.0515114553 0.0576940539 0.0880135372 0.0054899425 0.1903880000 982417257 0 402718720 -0.0773375705 0.0115576023 -0.1313365996 2022 1311867237.8926060200 0.0511886515 0.0576908366 0.0880135372 0.0054892600 0.1799410000 982420105 0 402718720 -0.0770244524 0.0121908663 -0.1288314760 2023 1311867237.9253590107 0.0516762026 0.0576878634 0.0880135372 0.0054886517 0.1907920000 982422953 0 402718720 -0.0769913420 0.0119745769 -0.1265660971 2024 1311867237.9613509178 0.0517936647 0.0576849513 0.0880135372 0.0054879936 0.1912300000 982425969 0 402718720 -0.0773705468 0.0111417370 -0.1243606210 2025 1311867237.9928910732 0.0520560369 0.0576821716 0.0880135372 0.0054868751 0.1804390000 982428873 0 402718720 -0.0768508986 0.0110709900 -0.1221937463 2026 1311867238.0245919228 0.0521388575 0.0576794355 0.0880135372 0.0054860839 0.1804790000 982431721 0 402718720 -0.0762977749 0.0117731998 -0.1198515445 2027 1311867238.0607950687 0.0523082577 0.0576767857 0.0880135372 0.0054853158 0.1782710000 982434737 0 402718720 -0.0764637962 0.0110489111 -0.1177864447 2028 1311867238.0932629108 0.0521050170 0.0576740382 0.0880135372 0.0054843788 0.1794330000 982437641 0 402718720 -0.0763147175 0.0094335247 -0.1158948690 2029 1311867238.1251931190 0.0524712428 0.0576714740 0.0880135372 0.0054841127 0.1926790000 982440545 0 402718720 -0.0761391670 0.0102443816 -0.1135630533 2030 1311867238.1608469486 0.0524379462 0.0576688959 0.0880135372 0.0054903569 0.1793680000 982443561 0 402718720 -0.0754971355 0.0108218873 -0.1110903770 2031 1311867238.1928510666 0.0522818938 0.0576662435 0.0880135372 0.0054960268 0.1787520000 982446465 0 402718720 -0.0757784620 0.0098423492 -0.1088965461 2032 1311867238.2246770859 0.0521467067 0.0576635272 0.0880135372 0.0054949836 0.1797390000 982449369 0 402718720 -0.0747980624 0.0104720723 -0.1066038162 2033 1311867238.2605938911 0.0520600230 0.0576607710 0.0880135372 0.0054947472 0.1809650000 982452385 0 402718720 -0.0734929591 0.0104780551 -0.1042014286 2034 1311867238.2926790714 0.0521343239 0.0576580539 0.0880135372 0.0054984014 0.1801620000 982455233 0 402718720 -0.0735717416 0.0087909587 -0.1020040885 2035 1311867238.3257811069 0.0519709960 0.0576552593 0.0880135372 0.0055073577 0.1783100000 982458249 0 402718720 -0.0731326714 0.0089050531 -0.0996218920 2036 1311867238.3604390621 0.0522489920 0.0576526040 0.0880135372 0.0055071880 0.1790270000 982461209 0 402718720 -0.0725421906 0.0086021414 -0.0972851217 2037 1311867238.3936378956 0.0520075262 0.0576498327 0.0880135372 0.0055085589 0.1782190000 982464169 0 402718720 -0.0721307322 0.0073861554 -0.0950206593 2038 1311867238.4264049530 0.0520048030 0.0576470628 0.0880135372 0.0055119007 0.1754680000 982467073 0 402718720 -0.0716773570 0.0064153168 -0.0927770138 2039 1311867238.4616210461 0.0517936423 0.0576441921 0.0880135372 0.0055107605 0.1973420000 982470089 0 402718720 -0.0716192871 0.0065272017 -0.0903841183 2040 1311867238.4932549000 0.0517967418 0.0576413257 0.0880135372 0.0055152200 0.1774400000 982472881 0 402718720 -0.0715842992 0.0054063001 -0.0882271007 2041 1311867238.5248661041 0.0520839840 0.0576386028 0.0880135372 0.0055148809 0.1774880000 982475841 0 402718720 -0.0710811242 0.0043545519 -0.0859922618 2042 1311867238.5605928898 0.0515453517 0.0576356189 0.0880135372 0.0055204032 0.1764640000 982478857 0 402718720 -0.0698918402 0.0042624054 -0.0833546147 2043 1311867238.5929119587 0.0518017933 0.0576327633 0.0880135372 0.0055254875 0.1757090000 982481705 0 402718720 -0.0702531114 0.0030006173 -0.0808976442 2044 1311867238.6249868870 0.0518166982 0.0576299179 0.0880135372 0.0055242967 0.1879770000 982484665 0 402718720 -0.0696137622 0.0019225607 -0.0782942623 2045 1311867238.6608479023 0.0517809279 0.0576270578 0.0880135372 0.0055231033 0.1760370000 982487681 0 402718720 -0.0686502457 0.0018641941 -0.0753455833 2046 1311867238.6929359436 0.0512800179 0.0576239556 0.0880135372 0.0055223388 0.1769000000 982490585 0 402718720 -0.0676886514 0.0013201657 -0.0724713951 2047 1311867238.7246360779 0.0519675612 0.0576211923 0.0880135372 0.0055230897 0.1758450000 982493433 0 402718720 -0.0680783018 0.0007711459 -0.0695770606 2048 1311867238.7627971172 0.0508833379 0.0576179024 0.0880135372 0.0055217744 0.1738370000 982496505 0 402718720 -0.0676356703 0.0006569946 -0.0665288940 2049 1311867238.7949919701 0.0511866100 0.0576147636 0.0880135372 0.0055205253 0.1918690000 982499465 0 402718720 -0.0659648031 0.0008930247 -0.0634204224 2050 1311867238.8246819973 0.0515027270 0.0576117821 0.0880135372 0.0055233332 0.1770720000 982911857 0 402718720 -0.0656282082 0.0001621038 -0.0602901243 2051 1311867238.8630580902 0.0507983454 0.0576084601 0.0880135372 0.0055223323 0.1762440000 982914985 0 402718720 -0.0656770840 0.0002643552 -0.0571021140 2052 1311867238.8933889866 0.0507481694 0.0576051169 0.0880135372 0.0055211854 0.1761190000 982917833 0 402718720 -0.0645864159 0.0007257820 -0.0538381748 2053 1311867238.9278979301 0.0511484854 0.0576019719 0.0880135372 0.0055200143 0.1759170000 982920849 0 402718720 -0.0640964955 -0.0003394968 -0.0507404841 2054 1311867238.9628050327 0.0508046933 0.0575986627 0.0880135372 0.0055195963 0.1899890000 982923865 0 402718720 -0.0643320754 -0.0019021920 -0.0478632040 2055 1311867238.9937820435 0.0513043702 0.0575955997 0.0880135372 0.0055190094 0.1766670000 982926657 0 402718720 -0.0636089519 -0.0019234892 -0.0444410108 2056 1311867239.0287299156 0.0515389554 0.0575926539 0.0880135372 0.0055208347 0.1765790000 982929673 0 402718720 -0.0633035749 -0.0020859116 -0.0412091091 2057 1311867239.0619978905 0.0507450290 0.0575893250 0.0880135372 0.0055229110 0.1762240000 982932689 0 402718720 -0.0634738281 -0.0034314843 -0.0382025540 2058 1311867239.0939240456 0.0508723445 0.0575860611 0.0880135372 0.0055250874 0.1764290000 982935481 0 402718720 -0.0630791932 -0.0035220021 -0.0348078720 2059 1311867239.1358110905 0.0500709042 0.0575824112 0.0880135372 0.0055239486 0.1852430000 982938665 0 402718720 -0.0624485239 -0.0036034670 -0.0313800983 2060 1311867239.1620550156 0.0504022501 0.0575789257 0.0880135372 0.0055237320 0.1885280000 982941401 0 402718720 -0.0618641339 -0.0041855769 -0.0281399265 2061 1311867239.1936569214 0.0509455092 0.0575757072 0.0880135372 0.0055228677 0.1758490000 982944249 0 402718720 -0.0616990291 -0.0046154223 -0.0245672632 2062 1311867239.2294950485 0.0507483892 0.0575723961 0.0880135372 0.0055220152 0.1751580000 982947265 0 402718720 -0.0618309937 -0.0049831402 -0.0209727250 2063 1311867239.2609150410 0.0512528084 0.0575693328 0.0880135372 0.0055213304 0.1997750000 982950169 0 402718720 -0.0613648221 -0.0064619835 -0.0176320095 2064 1311867239.2928791046 0.0513724014 0.0575663305 0.0880135372 0.0055201059 0.2033810000 982953017 0 402718720 -0.0609782040 -0.0076514729 -0.0141570643 2065 1311867239.3295290470 0.0511005670 0.0575631993 0.0880135372 0.0055190358 0.1743920000 982956089 0 402718720 -0.0603853427 -0.0081737367 -0.0104963789 2066 1311867239.3615000248 0.0515936650 0.0575603099 0.0880135372 0.0055183369 0.1745320000 982958993 0 402718720 -0.0596317463 -0.0094474182 -0.0071411091 2067 1311867239.3928411007 0.0516707674 0.0575574606 0.0880135372 0.0055176642 0.1733740000 982961897 0 402718720 -0.0599554889 -0.0110739181 -0.0039878758 2068 1311867239.4293289185 0.0513429344 0.0575544555 0.0880135372 0.0055207602 0.1719090000 982964857 0 402718720 -0.0591595434 -0.0121963415 -0.0007882686 2069 1311867239.4619059563 0.0514897369 0.0575515243 0.0880135372 0.0055225611 0.1841190000 982967873 0 402718720 -0.0590494648 -0.0135071501 0.0022989134 2070 1311867239.4938249588 0.0517964102 0.0575487440 0.0880135372 0.0055218395 0.1724110000 982970721 0 402718720 -0.0587553456 -0.0154213933 0.0051734643 2071 1311867239.5295019150 0.0516310781 0.0575458866 0.0880135372 0.0055239716 0.1722870000 982973737 0 402718720 -0.0578446649 -0.0168740619 0.0080058463 2072 1311867239.5617070198 0.0514344350 0.0575429371 0.0880135372 0.0055293970 0.1838050000 982976641 0 402718720 -0.0575077832 -0.0171830356 0.0110812718 2073 1311867239.5944910049 0.0520271361 0.0575402763 0.0880135372 0.0055282149 0.1706500000 982979545 0 402718720 -0.0565587841 -0.0187933594 0.0140816150 2074 1311867239.6284430027 0.0519996770 0.0575376049 0.0880135372 0.0055356729 0.1887820000 982982505 0 402718720 -0.0560952388 -0.0206679255 0.0167645700 2075 1311867239.6623089314 0.0517710559 0.0575348258 0.0880135372 0.0055347210 0.1712810000 982985521 0 402718720 -0.0552541278 -0.0208327696 0.0197719056 2076 1311867239.6931240559 0.0520388633 0.0575321784 0.0880135372 0.0055475351 0.1709070000 982988313 0 402718720 -0.0544042662 -0.0206381809 0.0227968693 2077 1311867239.7284948826 0.0520143136 0.0575295218 0.0880135372 0.0055478898 0.1714580000 982991329 0 402718720 -0.0537911318 -0.0213130545 0.0256466921 2078 1311867239.7614610195 0.0520906113 0.0575269044 0.0880135372 0.0055472690 0.1707820000 982994345 0 402718720 -0.0527981296 -0.0219063647 0.0284267422 2079 1311867239.7926149368 0.0516282804 0.0575240671 0.0880135372 0.0055460306 0.1711210000 982997137 0 402718720 -0.0516211689 -0.0210731663 0.0314509720 2080 1311867239.8308320045 0.0515578873 0.0575211988 0.0880135372 0.0055465499 0.1713080000 983000265 0 402718720 -0.0505046509 -0.0212539993 0.0343785696 2081 1311867239.8608438969 0.0515928082 0.0575183500 0.0880135372 0.0055534778 0.1712330000 983003113 0 402718720 -0.0503416993 -0.0219728295 0.0374334604 2082 1311867239.8929069042 0.0518126823 0.0575156095 0.0880135372 0.0055544040 0.1712650000 983006017 0 402718720 -0.0493637174 -0.0220917780 0.0405709893 2083 1311867239.9306600094 0.0513585173 0.0575126536 0.0880135372 0.0055555464 0.1712890000 983009089 0 402718720 -0.0486493781 -0.0226588715 0.0433792435 2084 1311867239.9613699913 0.0518357158 0.0575099296 0.0880135372 0.0055570816 0.1718850000 983011993 0 402718720 -0.0490313843 -0.0230512861 0.0462410077 2085 1311867239.9948220253 0.0519649982 0.0575072701 0.0880135372 0.0055558833 0.1717070000 983014897 0 402718720 -0.0483270139 -0.0233825613 0.0491104573 2086 1311867240.0292289257 0.0517478809 0.0575045091 0.0880135372 0.0055560745 0.1716600000 983017857 0 402718720 -0.0478397869 -0.0243036412 0.0518639274 2087 1311867240.0618810654 0.0522386357 0.0575019860 0.0880135372 0.0055550044 0.1709080000 983020817 0 402718720 -0.0470595099 -0.0243396331 0.0546459146 2088 1311867240.0945510864 0.0517830439 0.0574992470 0.0880135372 0.0055538966 0.1705300000 983023665 0 402718720 -0.0466778129 -0.0245124716 0.0573645048 2089 1311867240.1297509670 0.0521588102 0.0574966906 0.0880135372 0.0055527399 0.1959650000 983026681 0 402718720 -0.0462015420 -0.0248359405 0.0604778454 2090 1311867240.1617240906 0.0522593781 0.0574941847 0.0880135372 0.0055520537 0.1716550000 983029585 0 402718720 -0.0458086431 -0.0244951416 0.0635804236 2091 1311867240.1963129044 0.0519794822 0.0574915473 0.0880135372 0.0055510330 0.1714200000 983032601 0 402718720 -0.0455134064 -0.0247941967 0.0662421957 2092 1311867240.2291030884 0.0524260029 0.0574891259 0.0880135372 0.0055498024 0.1715090000 983035505 0 402718720 -0.0448390022 -0.0250274371 0.0690178499 2093 1311867240.2612760067 0.0523166843 0.0574866546 0.0880135372 0.0055492674 0.1710820000 983038465 0 402718720 -0.0433482938 -0.0248483196 0.0718233958 2094 1311867240.2981250286 0.0523301661 0.0574841921 0.0880135372 0.0055480656 0.1972360000 983041313 0 402718720 -0.0434435681 -0.0252072681 0.0745195672 2095 1311867240.3289160728 0.0523659624 0.0574817490 0.0880135372 0.0055477816 0.1707910000 983044217 0 402718720 -0.0428065546 -0.0260797571 0.0770752728 2096 1311867240.3609399796 0.0525092371 0.0574793767 0.0880135372 0.0055468610 0.2033280000 983047177 0 402718720 -0.0422505550 -0.0269640684 0.0796760619 2097 1311867240.3967890739 0.0525553897 0.0574770285 0.0880135372 0.0055461414 0.1907970000 983050081 0 402718720 -0.0413774848 -0.0275361240 0.0821519047 2098 1311867240.4286890030 0.0525291897 0.0574746702 0.0880135372 0.0055451286 0.1807790000 983052873 0 402718720 -0.0407377742 -0.0289320052 0.0843622908 2099 1311867240.4650850296 0.0520114750 0.0574720674 0.0880135372 0.0055489207 0.1914500000 983055945 0 402718720 -0.0401604995 -0.0300765373 0.0865755081 2100 1311867240.4972898960 0.0523379780 0.0574696226 0.0880135372 0.0055520160 0.1705600000 983058849 0 402718720 -0.0402578637 -0.0309406109 0.0886206403 2101 1311867240.5309979916 0.0524794720 0.0574672475 0.0880135372 0.0055536781 0.1703700000 983061809 0 402718720 -0.0399199314 -0.0322090723 0.0904535800 2102 1311867240.5608210564 0.0521774814 0.0574647310 0.0880135372 0.0055524533 0.1695170000 983064657 0 402718720 -0.0393717624 -0.0327523649 0.0922757611 2103 1311867240.5965991020 0.0525440387 0.0574623911 0.0880135372 0.0055514315 0.1702330000 983067673 0 402718720 -0.0389138609 -0.0336816348 0.0939538702 2104 1311867240.6290791035 0.0529534966 0.0574602481 0.0880135372 0.0055518542 0.1699920000 983070577 0 402718720 -0.0386725590 -0.0351389833 0.0954320431 2105 1311867240.6622560024 0.0528637841 0.0574580645 0.0880135372 0.0055547110 0.1699120000 983073481 0 402718720 -0.0386321731 -0.0360646918 0.0967995971 2106 1311867240.6968801022 0.0528178848 0.0574558612 0.0880135372 0.0055538616 0.1710370000 983076441 0 402718720 -0.0384008996 -0.0367237851 0.0980813950 2107 1311867240.7291979790 0.0527364053 0.0574536213 0.0880135372 0.0055559408 0.1703460000 983079345 0 402718720 -0.0383262746 -0.0364639796 0.0992996022 2108 1311867240.7625629902 0.0531112179 0.0574515613 0.0880135372 0.0055555221 0.1699460000 983082249 0 402718720 -0.0381496362 -0.0363278501 0.1007828489 2109 1311867240.7965719700 0.0530954525 0.0574494958 0.0880135372 0.0055544224 0.1810770000 983085265 0 402718720 -0.0384479128 -0.0363501832 0.1021932587 2110 1311867240.8293309212 0.0527975149 0.0574472911 0.0880135372 0.0055531254 0.1721070000 983088169 0 402718720 -0.0384570546 -0.0356944911 0.1038683876 2111 1311867240.8621098995 0.0529953316 0.0574451822 0.0880135372 0.0055526365 0.1824250000 983091129 0 402718720 -0.0385930240 -0.0353185833 0.1057006717 2112 1311867240.8973500729 0.0530099720 0.0574430822 0.0880135372 0.0055517265 0.1719690000 983094145 0 402718720 -0.0393386930 -0.0348367058 0.1077505425 2113 1311867240.9290270805 0.0531474352 0.0574410492 0.0880135372 0.0055507328 0.1709590000 983096993 0 402718720 -0.0394060686 -0.0339416638 0.1099867225 2114 1311867240.9614369869 0.0533932969 0.0574391345 0.0880135372 0.0055494402 0.1903810000 983099897 0 402718720 -0.0396947004 -0.0331287719 0.1121926829 2115 1311867240.9968450069 0.0536735430 0.0574373541 0.0880135372 0.0055484559 0.1717450000 983102969 0 402718720 -0.0401067808 -0.0328970477 0.1145606413 2116 1311867241.0315620899 0.0532344580 0.0574353678 0.0880135372 0.0055510641 0.1845510000 983105929 0 402718720 -0.0407121442 -0.0320468545 0.1171263754 2117 1311867241.0633668900 0.0538171604 0.0574336587 0.0880135372 0.0055579420 0.1706410000 983108721 0 402718720 -0.0414901599 -0.0306110047 0.1199330986 2118 1311867241.0990099907 0.0534638837 0.0574317844 0.0880135372 0.0055594014 0.1705610000 983111793 0 402718720 -0.0420058742 -0.0306560099 0.1222569793 2119 1311867241.1285290718 0.0542209484 0.0574302691 0.0880135372 0.0055602905 0.1832020000 983114585 0 402718720 -0.0433648974 -0.0310918540 0.1245725453 2120 1311867241.1641499996 0.0541165546 0.0574287061 0.0880135372 0.0055627349 0.1892740000 983117657 0 402718720 -0.0436287411 -0.0306328386 0.1269896030 2121 1311867241.1980121136 0.0544125885 0.0574272840 0.0880135372 0.0055625352 0.1715560000 983120561 0 402718720 -0.0440085977 -0.0307912491 0.1293727010 2122 1311867241.2313330173 0.0549068488 0.0574260963 0.0880135372 0.0055629958 0.1698510000 983123577 0 402718720 -0.0454388969 -0.0302183125 0.1319077462 2123 1311867241.2640700340 0.0550331958 0.0574249691 0.0880135372 0.0055617088 0.1704810000 983126425 0 402718720 -0.0466881320 -0.0296794083 0.1340267807 2124 1311867241.3000609875 0.0545097925 0.0574235966 0.0880135372 0.0055656410 0.1911220000 983129497 0 402718720 -0.0477905720 -0.0299896523 0.1357057691 2125 1311867241.3294849396 0.0546546504 0.0574222936 0.0880135372 0.0055666504 0.1704100000 983132289 0 402718720 -0.0489426218 -0.0295944735 0.1375291049 2126 1311867241.3612549305 0.0548447296 0.0574210812 0.0880135372 0.0055660069 0.1700410000 983135249 0 402718720 -0.0498836190 -0.0296063237 0.1393519789 2127 1311867241.3981139660 0.0550260022 0.0574199552 0.0880135372 0.0055680232 0.1696760000 983138209 0 402718720 -0.0518494509 -0.0303641669 0.1410759836 2128 1311867241.4300589561 0.0552517287 0.0574189363 0.0880135372 0.0055803072 0.1690040000 983141169 0 402718720 -0.0524902642 -0.0302602407 0.1428250968 2129 1311867241.4652009010 0.0552975647 0.0574179399 0.0880135372 0.0055821016 0.1810500000 983144129 0 402718720 -0.0535988845 -0.0297762025 0.1447251588 2130 1311867241.4969789982 0.0547866747 0.0574167045 0.0880135372 0.0055864388 0.1698570000 983146977 0 402718720 -0.0544957817 -0.0300162453 0.1465464681 2131 1311867241.5331718922 0.0554949120 0.0574158027 0.0880135372 0.0055876559 0.1700980000 983150049 0 402718720 -0.0555898175 -0.0301444419 0.1481741667 2132 1311867241.5656960011 0.0549387671 0.0574146409 0.0880135372 0.0055878816 0.1703830000 983152953 0 402718720 -0.0562200956 -0.0300262012 0.1496544629 2133 1311867241.6002480984 0.0553661957 0.0574136805 0.0880135372 0.0055881711 0.1702200000 983155913 0 402718720 -0.0570479408 -0.0308706965 0.1507814527 2134 1311867241.6291201115 0.0559504032 0.0574129948 0.0880135372 0.0055870776 0.1816260000 983158761 0 402718720 -0.0573111884 -0.0309209749 0.1518853158 2135 1311867241.6646790504 0.0552299581 0.0574119723 0.0880135372 0.0055925057 0.1700040000 983161721 0 402718720 -0.0575196221 -0.0301055312 0.1529515535 2136 1311867241.6999258995 0.0551888347 0.0574109315 0.0880135372 0.0055928301 0.1699890000 983164737 0 402718720 -0.0579774305 -0.0301328730 0.1537887603 2137 1311867241.7297649384 0.0561530665 0.0574103429 0.0880135372 0.0056049003 0.1697360000 983167529 0 402718720 -0.0583966710 -0.0298820846 0.1545692086 2138 1311867241.7676639557 0.0557377078 0.0574095606 0.0880135372 0.0056037963 0.1693350000 983170657 0 402718720 -0.0589468703 -0.0295505300 0.1554578990 2139 1311867241.7974851131 0.0560073107 0.0574089050 0.0880135372 0.0056031043 0.1914950000 983173449 0 402718720 -0.0592330769 -0.0298513602 0.1562799364 2140 1311867241.8296549320 0.0556274503 0.0574080725 0.0880135372 0.0056032604 0.1684950000 983176353 0 402718720 -0.0602478646 -0.0300243776 0.1571837813 2141 1311867241.8668920994 0.0556636862 0.0574072578 0.0880135372 0.0056025062 0.1684760000 983179425 0 402718720 -0.0606455244 -0.0298177581 0.1583886743 2142 1311867241.8979690075 0.0559643731 0.0574065842 0.0880135372 0.0056016098 0.1813930000 983182273 0 402718720 -0.0615861043 -0.0297761168 0.1599136442 2143 1311867241.9292619228 0.0555559024 0.0574057206 0.0880135372 0.0056007732 0.1680140000 983185177 0 402718720 -0.0621322282 -0.0291814748 0.1617624611 2144 1311867241.9654040337 0.0550427251 0.0574046184 0.0880135372 0.0055996481 0.1800970000 983188193 0 402718720 -0.0623610839 -0.0283835102 0.1638790220 2145 1311867241.9974029064 0.0556812696 0.0574038150 0.0880135372 0.0055996462 0.1695820000 983191097 0 402718720 -0.0632091314 -0.0285778306 0.1658309698 2146 1311867242.0296339989 0.0559975430 0.0574031597 0.0880135372 0.0055999526 0.1686420000 983194001 0 402718720 -0.0634605139 -0.0285124928 0.1677950174 2147 1311867242.0670061111 0.0558116175 0.0574024184 0.0880135372 0.0055989549 0.1687240000 983197073 0 402718720 -0.0637805462 -0.0273204148 0.1697471887 2148 1311867242.0972509384 0.0561783426 0.0574018485 0.0880135372 0.0055991868 0.1810830000 983199921 0 402718720 -0.0644260496 -0.0275481474 0.1713082641 2149 1311867242.1308040619 0.0570093319 0.0574016659 0.0880135372 0.0056008655 0.1938200000 983202825 0 402718720 -0.0648515821 -0.0271585118 0.1728186905 2150 1311867242.1670179367 0.0569857098 0.0574014724 0.0880135372 0.0056012393 0.1668820000 983205785 0 402718720 -0.0652122721 -0.0269561969 0.1741981804 2151 1311867242.1982409954 0.0570604652 0.0574013139 0.0880135372 0.0056015393 0.1672100000 983208633 0 402718720 -0.0658799037 -0.0273151100 0.1754875481 2152 1311867242.2334370613 0.0567126609 0.0574009939 0.0880135372 0.0056028156 0.1675160000 983211649 0 402718720 -0.0666876584 -0.0266748276 0.1771122664 2153 1311867242.2696599960 0.0567622632 0.0574006972 0.0880135372 0.0056016414 0.1792910000 983214665 0 402718720 -0.0668882951 -0.0265218075 0.1788305342 2154 1311867242.2982430458 0.0570865385 0.0574005514 0.0880135372 0.0056003958 0.1780320000 983217457 0 402718720 -0.0673391968 -0.0268140119 0.1805589795 2155 1311867242.3293490410 0.0571161546 0.0574004194 0.0880135372 0.0055998547 0.1791700000 983220361 0 402718720 -0.0675128400 -0.0265196916 0.1824556291 2156 1311867242.3659460545 0.0572325103 0.0574003415 0.0880135372 0.0056010152 0.1657170000 983223377 0 402718720 -0.0679492950 -0.0268155448 0.1841864586 2157 1311867242.3974800110 0.0576807931 0.0574004715 0.0880135372 0.0056005925 0.1668810000 983226281 0 402718720 -0.0683671013 -0.0269627199 0.1858806908 2158 1311867242.4322769642 0.0577324182 0.0574006254 0.0880135372 0.0055994297 0.1671620000 983229297 0 402718720 -0.0685580373 -0.0269797072 0.1875520051 2159 1311867242.4648990631 0.0580276623 0.0574009158 0.0880135372 0.0055995309 0.1781090000 983232145 0 402718720 -0.0683985278 -0.0275853984 0.1888279021 2160 1311867242.4975609779 0.0578348674 0.0574011167 0.0880135372 0.0055983211 0.1665530000 983235049 0 402718720 -0.0694517791 -0.0279860776 0.1901731342 2161 1311867242.5292570591 0.0575860925 0.0574012023 0.0880135372 0.0055971264 0.1653060000 983237953 0 402718720 -0.0699362010 -0.0282400679 0.1915786415 2162 1311867242.5650939941 0.0571749471 0.0574010976 0.0880135372 0.0055959396 0.1651550000 983241025 0 402718720 -0.0705448687 -0.0289504509 0.1929343790 2163 1311867242.5985031128 0.0570768304 0.0574009477 0.0880135372 0.0055947419 0.1648130000 983243985 0 402718720 -0.0709480867 -0.0293946806 0.1943377107 2164 1311867242.6305589676 0.0574395359 0.0574009656 0.0880135372 0.0055935268 0.1779340000 983246833 0 402718720 -0.0708301961 -0.0296475366 0.1959306002 2165 1311867242.6692740917 0.0562216751 0.0574004209 0.0880135372 0.0055930562 0.1656840000 983249961 0 402718720 -0.0714182556 -0.0298947748 0.1974981427 2166 1311867242.6981039047 0.0560783073 0.0573998105 0.0880135372 0.0055919085 0.1649800000 983252753 0 402718720 -0.0719953328 -0.0296070501 0.1993788332 2167 1311867242.7372829914 0.0559269972 0.0573991308 0.0880135372 0.0055926219 0.1648060000 983255825 0 402718720 -0.0722334757 -0.0292165540 0.2014861703 2168 1311867242.7656900883 0.0561617762 0.0573985601 0.0880135372 0.0055920416 0.1645820000 983258673 0 402718720 -0.0721858591 -0.0299927760 0.2033312023 2169 1311867242.7994089127 0.0557944998 0.0573978205 0.0880135372 0.0055938185 0.1739860000 983261577 0 402718720 -0.0730225295 -0.0298108719 0.2052422613 2170 1311867242.8355538845 0.0554449484 0.0573969206 0.0880135372 0.0055946353 0.1640780000 983264649 0 402718720 -0.0733469427 -0.0294425730 0.2071758360 2171 1311867242.8666720390 0.0560774691 0.0573963128 0.0880135372 0.0055944010 0.1640550000 983267553 0 402718720 -0.0729900301 -0.0299208816 0.2091008425 2172 1311867242.8980929852 0.0571865924 0.0573962163 0.0880135372 0.0056172082 0.1633280000 983270401 0 402718720 -0.0736047179 -0.0296797063 0.2110387683 2173 1311867242.9335498810 0.0559877679 0.0573955681 0.0880135372 0.0056443950 0.1622830000 983273417 0 402718720 -0.0738556534 -0.0295404606 0.2130223662 2174 1311867242.9649999142 0.0564280711 0.0573951231 0.0880135372 0.0056469393 0.1744710000 983276321 0 402718720 -0.0742618516 -0.0297604054 0.2148694545 2175 1311867242.9970819950 0.0567180626 0.0573948118 0.0880135372 0.0056458552 0.1615940000 983279169 0 402718720 -0.0741736144 -0.0300207585 0.2167815864 2176 1311867243.0332529545 0.0578663312 0.0573950285 0.0880135372 0.0056447001 0.1603270000 983282185 0 402718720 -0.0744980574 -0.0301356111 0.2187003493 2177 1311867243.0648689270 0.0566655286 0.0573946934 0.0880135372 0.0056436181 0.1599450000 983285089 0 402718720 -0.0750765577 -0.0303307045 0.2204622775 2178 1311867243.0972158909 0.0568365902 0.0573944371 0.0880135372 0.0056425597 0.1614400000 983287993 0 402718720 -0.0755298883 -0.0305480380 0.2224068046 2179 1311867243.1357100010 0.0559608974 0.0573937792 0.0880135372 0.0056490360 0.1923700000 983291065 0 402718720 -0.0762395188 -0.0310763996 0.2243017703 2180 1311867243.1655960083 0.0570080206 0.0573936023 0.0880135372 0.0056562338 0.1619530000 983293913 0 402718720 -0.0769676566 -0.0313352831 0.2261635512 2181 1311867243.1977169514 0.0574977957 0.0573936501 0.0880135372 0.0056564382 0.1621510000 983296761 0 402718720 -0.0778862238 -0.0315127447 0.2280741781 2182 1311867243.2358860970 0.0570642129 0.0573934991 0.0880135372 0.0056571948 0.1623280000 983299889 0 402718720 -0.0785646662 -0.0322310030 0.2298584282 2183 1311867243.2649240494 0.0575429797 0.0573935676 0.0880135372 0.0056560938 0.1618490000 983302625 0 402718720 -0.0793054923 -0.0330457799 0.2316943407 2184 1311867243.2970221043 0.0574772730 0.0573936059 0.0880135372 0.0056550057 0.2058360000 983305585 0 402718720 -0.0798231512 -0.0335812494 0.2334964573 2185 1311867243.3327538967 0.0573959500 0.0573936070 0.0880135372 0.0056546250 0.1960520000 983308545 0 402718720 -0.0806482583 -0.0341820605 0.2353141755 2186 1311867243.3681559563 0.0576164760 0.0573937089 0.0880135372 0.0056534996 0.1956430000 983311561 0 402718720 -0.0813175961 -0.0344973169 0.2371719927 2187 1311867243.4021821022 0.0579360090 0.0573939569 0.0880135372 0.0056522645 0.1960210000 983314521 0 402718720 -0.0815725327 -0.0348512195 0.2388790399 2188 1311867243.4344329834 0.0583258197 0.0573943828 0.0880135372 0.0056521477 0.1953560000 983317425 0 402718720 -0.0819294080 -0.0350981057 0.2406687289 2189 1311867243.4665510654 0.0578941442 0.0573946111 0.0880135372 0.0056509107 0.1952810000 983320329 0 402718720 -0.0823963135 -0.0348197743 0.2426555753 2190 1311867243.4982140064 0.0582348146 0.0573949947 0.0880135372 0.0056502440 0.1951110000 983323177 0 402718720 -0.0824949294 -0.0349759310 0.2445085496 2191 1311867243.5339779854 0.0586428270 0.0573955643 0.0880135372 0.0056491206 0.1950140000 983326249 0 402718720 -0.0824446082 -0.0351281427 0.2463643551 2192 1311867243.5669720173 0.0584312044 0.0573960367 0.0880135372 0.0056480826 0.1947060000 983329209 0 402718720 -0.0825565085 -0.0350849852 0.2481019646 2193 1311867243.5978341103 0.0585298911 0.0573965538 0.0880135372 0.0056468743 0.1808630000 983332057 0 402718720 -0.0828565359 -0.0355470888 0.2496997267 2194 1311867243.6333720684 0.0589187406 0.0573972476 0.0880135372 0.0056487446 0.1713260000 983335017 0 402718720 -0.0832334682 -0.0356045105 0.2514255643 2195 1311867243.6661529541 0.0591245331 0.0573980345 0.0880135372 0.0056474880 0.1602920000 983337977 0 402718720 -0.0832075849 -0.0355655439 0.2530877292 2196 1311867243.6981849670 0.0591955893 0.0573988530 0.0880135372 0.0056466368 0.1609130000 983340825 0 402718720 -0.0831767246 -0.0361708216 0.2545201480 2197 1311867243.7344710827 0.0585147738 0.0573993610 0.0880135372 0.0056457884 0.1603340000 983343897 0 402718720 -0.0825698376 -0.0361288786 0.2561599314 2198 1311867243.7666299343 0.0587995760 0.0573999980 0.0880135372 0.0056456831 0.1725480000 983346857 0 402718720 -0.0820066854 -0.0360862464 0.2580248117 2199 1311867243.7979769707 0.0591100864 0.0574007757 0.0880135372 0.0056444078 0.1823220000 983349705 0 402718720 -0.0819786564 -0.0365215465 0.2598511875 2200 1311867243.8330240250 0.0587148741 0.0574013730 0.0880135372 0.0056432865 0.1592830000 983352665 0 402718720 -0.0816402510 -0.0362761170 0.2617374361 2201 1311867243.8647689819 0.0590830483 0.0574021370 0.0880135372 0.0056429710 0.1582670000 983355569 0 402718720 -0.0811016187 -0.0362690352 0.2636965215 2202 1311867243.8968739510 0.0592730567 0.0574029867 0.0880135372 0.0056417753 0.1576440000 983358529 0 402718720 -0.0808549672 -0.0366928540 0.2653960288 2203 1311867243.9329960346 0.0593999252 0.0574038931 0.0880135372 0.0056410815 0.1577790000 983361489 0 402718720 -0.0803335607 -0.0366191193 0.2670551240 2204 1311867243.9660589695 0.0593868531 0.0574047929 0.0880135372 0.0056400216 0.1703460000 983364449 0 402718720 -0.0802969784 -0.0369679928 0.2685145736 2205 1311867244.0016739368 0.0592339486 0.0574056224 0.0880135372 0.0056396487 0.1589660000 983367465 0 402718720 -0.0799643099 -0.0374391451 0.2700901628 2206 1311867244.0341379642 0.0591225848 0.0574064007 0.0880135372 0.0056387098 0.1579670000 983370369 0 402718720 -0.0794256926 -0.0376613960 0.2716520131 2207 1311867244.0655789375 0.0591382645 0.0574071854 0.0880135372 0.0056374907 0.1569450000 983373273 0 402718720 -0.0792352632 -0.0379959531 0.2732399702 2208 1311867244.1010930538 0.0589177236 0.0574078696 0.0880135372 0.0056363207 0.1828260000 983376289 0 402718720 -0.0789538547 -0.0383627489 0.2750054300 2209 1311867244.1353089809 0.0590077229 0.0574085938 0.0880135372 0.0056357100 0.1698100000 983379249 0 402718720 -0.0786067322 -0.0387123376 0.2769023776 2210 1311867244.1648418903 0.0591054671 0.0574093616 0.0880135372 0.0056345049 0.1586880000 983382041 0 402718720 -0.0783440992 -0.0392279774 0.2787173092 2211 1311867244.2024741173 0.0582683422 0.0574097501 0.0880135372 0.0056333123 0.1707790000 983385169 0 402718720 -0.0778630897 -0.0392675661 0.2807526886 2212 1311867244.2330279350 0.0590068810 0.0574104721 0.0880135372 0.0056320951 0.1581210000 983388017 0 402718720 -0.0774292797 -0.0392940156 0.2830077410 2213 1311867244.2649021149 0.0592550710 0.0574113057 0.0880135372 0.0056310770 0.1569600000 983390865 0 402718720 -0.0769515485 -0.0398784578 0.2850629687 2214 1311867244.3010311127 0.0589924119 0.0574120198 0.0880135372 0.0056302584 0.1582060000 983393937 0 402718720 -0.0764928237 -0.0397284999 0.2872349918 2215 1311867244.3355190754 0.0589312389 0.0574127057 0.0880135372 0.0056292288 0.1579530000 983396897 0 402718720 -0.0759231672 -0.0393558927 0.2894499600 2216 1311867244.3649079800 0.0597355701 0.0574137539 0.0880135372 0.0056287783 0.1561760000 983399689 0 402718720 -0.0755337998 -0.0397280455 0.2913916707 2217 1311867244.4008760452 0.0598521754 0.0574148538 0.0880135372 0.0056279870 0.1566870000 983402705 0 402718720 -0.0748853460 -0.0394423828 0.2935824990 2218 1311867244.4329938889 0.0598989576 0.0574159738 0.0880135372 0.0056286246 0.1566620000 983405609 0 402718720 -0.0738170743 -0.0394967422 0.2957355082 2219 1311867244.4654510021 0.0601026565 0.0574171845 0.0880135372 0.0056280875 0.1678460000 983408569 0 402718720 -0.0729876682 -0.0396576524 0.2978380620 2220 1311867244.5052490234 0.0597694479 0.0574182441 0.0880135372 0.0056270875 0.1577830000 983411697 0 402718720 -0.0715410560 -0.0389775373 0.3000251949 2221 1311867244.5330989361 0.0598930195 0.0574193584 0.0880135372 0.0056260370 0.1577500000 983414433 0 402718720 -0.0708199590 -0.0383751318 0.3023289144 2222 1311867244.5669400692 0.0598308146 0.0574204436 0.0880135372 0.0056249920 0.1575130000 983417337 0 402718720 -0.0699529573 -0.0379143320 0.3046069741 2223 1311867244.6027030945 0.0597944967 0.0574215116 0.0880135372 0.0056288657 0.1570950000 983420241 0 402718720 -0.0694550648 -0.0370888561 0.3071263731 2224 1311867244.6328020096 0.0598702133 0.0574226126 0.0880135372 0.0056286839 0.1571990000 983423033 0 402718720 -0.0686855838 -0.0364005230 0.3096115291 2225 1311867244.6672449112 0.0598906167 0.0574237218 0.0880135372 0.0056280966 0.1560860000 983426049 0 402718720 -0.0681104288 -0.0365133099 0.3119286895 2226 1311867244.7012600899 0.0601903461 0.0574249647 0.0880135372 0.0056271933 0.1569560000 983429009 0 402718720 -0.0674318448 -0.0365586430 0.3143886328 2227 1311867244.7346320152 0.0603662767 0.0574262855 0.0880135372 0.0056261928 0.1566530000 983431913 0 402718720 -0.0670051575 -0.0366601124 0.3165734112 2228 1311867244.7650001049 0.0605342984 0.0574276804 0.0880135372 0.0056251138 0.1561530000 983434761 0 402718720 -0.0662349612 -0.0362949856 0.3189367056 2229 1311867244.8015320301 0.0604945458 0.0574290563 0.0880135372 0.0056242026 0.1663280000 983437833 0 402718720 -0.0652803406 -0.0360413529 0.3211661577 2230 1311867244.8331909180 0.0605854243 0.0574304717 0.0880135372 0.0056231945 0.1554970000 983440681 0 402718720 -0.0651787296 -0.0364053212 0.3231403530 2231 1311867244.8651568890 0.0608238913 0.0574319928 0.0880135372 0.0056219373 0.1552630000 983443641 0 402718720 -0.0644168481 -0.0361627005 0.3253958523 2232 1311867244.9013550282 0.0607550032 0.0574334816 0.0880135372 0.0056207088 0.1564560000 983446657 0 402718720 -0.0639253110 -0.0359315611 0.3274870217 2233 1311867244.9328739643 0.0608391054 0.0574350067 0.0880135372 0.0056197339 0.1562270000 983449449 0 402718720 -0.0639327168 -0.0361323506 0.3295127749 2234 1311867244.9652509689 0.0606069826 0.0574364266 0.0880135372 0.0056191055 0.1733100000 983452409 0 402718720 -0.0636648014 -0.0353441872 0.3318270147 2235 1311867245.0022718906 0.0609246865 0.0574379873 0.0880135372 0.0056186260 0.1555860000 983455537 0 402718720 -0.0638078749 -0.0357342660 0.3339382112 2236 1311867245.0349979401 0.0613154098 0.0574397214 0.0880135372 0.0056185589 0.1559420000 983458385 0 402718720 -0.0637961030 -0.0357625037 0.3359811306 2237 1311867245.0664730072 0.0612037405 0.0574414040 0.0880135372 0.0056174703 0.1551970000 983461289 0 402718720 -0.0634481236 -0.0353233926 0.3381405473 2238 1311867245.1041638851 0.0610254072 0.0574430054 0.0880135372 0.0056167289 0.1664310000 983464305 0 402718720 -0.0636591464 -0.0353329666 0.3400001824 2239 1311867245.1338050365 0.0617119111 0.0574449121 0.0880135372 0.0056157828 0.1866270000 983467153 0 402718720 -0.0639168322 -0.0356054232 0.3419183791 2240 1311867245.1749250889 0.0612222068 0.0574465984 0.0880135372 0.0056149357 0.1671310000 983470393 0 402718720 -0.0640809163 -0.0352148972 0.3439617157 2241 1311867245.2108979225 0.0606893562 0.0574480454 0.0880135372 0.0056137630 0.1549540000 983473409 0 402718720 -0.0646095276 -0.0351983421 0.3459057808 2242 1311867245.2429010868 0.0610885508 0.0574496691 0.0880135372 0.0056138801 0.1546140000 983476369 0 402718720 -0.0653119683 -0.0353122614 0.3479934037 2243 1311867245.2755670547 0.0612091869 0.0574513453 0.0880135372 0.0056139878 0.1539900000 983479273 0 402718720 -0.0652537569 -0.0351770744 0.3503180742 2244 1311867245.3120090961 0.0609170124 0.0574528897 0.0880135372 0.0056128645 0.1532780000 983482289 0 402718720 -0.0658139810 -0.0352384038 0.3524643183 2245 1311867245.3430099487 0.0611371882 0.0574545308 0.0880135372 0.0056117611 0.1544170000 983485193 0 402718720 -0.0663582981 -0.0355890580 0.3546294272 2246 1311867245.3749370575 0.0616029911 0.0574563778 0.0880135372 0.0056117798 0.1546560000 983488041 0 402718720 -0.0664949566 -0.0357154422 0.3569861352 2247 1311867245.4122350216 0.0611154847 0.0574580063 0.0880135372 0.0056108996 0.1667920000 983491169 0 402718720 -0.0671410412 -0.0353872180 0.3593238890 2248 1311867245.4428830147 0.0616820529 0.0574598853 0.0880135372 0.0056131177 0.1744850000 983493905 0 402718720 -0.0674196556 -0.0354678407 0.3615633249 2249 1311867245.4751451015 0.0617263801 0.0574617824 0.0880135372 0.0056122109 0.1661200000 983496865 0 402718720 -0.0676618442 -0.0347926430 0.3639346361 2250 1311867245.5108819008 0.0613360517 0.0574635043 0.0880135372 0.0056112085 0.1539910000 983499881 0 402718720 -0.0681178272 -0.0343303271 0.3663888276 2251 1311867245.5429608822 0.0614466406 0.0574652737 0.0880135372 0.0056104166 0.1535020000 983502785 0 402718720 -0.0688366517 -0.0343932249 0.3687058687 2252 1311867245.5749409199 0.0616411529 0.0574671280 0.0880135372 0.0056092944 0.1533640000 983505689 0 402718720 -0.0687698573 -0.0334986784 0.3713111877 2253 1311867245.6109130383 0.0623945296 0.0574693151 0.0880135372 0.0056095948 0.1716310000 983508705 0 402718720 -0.0696272030 -0.0340867341 0.3735422790 2254 1311867245.6428189278 0.0615574419 0.0574711288 0.0880135372 0.0056166062 0.1523650000 983511553 0 402718720 -0.0701747015 -0.0347034000 0.3757421374 2255 1311867245.6751749516 0.0621701442 0.0574732126 0.0880135372 0.0056158988 0.1534300000 983514513 0 402718720 -0.0702408776 -0.0342635810 0.3781059682 2256 1311867245.7109169960 0.0622351244 0.0574753234 0.0880135372 0.0056149853 0.1534290000 983517529 0 402718720 -0.0710693449 -0.0348844677 0.3800666332 2257 1311867245.7429819107 0.0624021441 0.0574775063 0.0880135372 0.0056143000 0.1530600000 983520377 0 402718720 -0.0711758509 -0.0348991156 0.3822149634 2258 1311867245.7752521038 0.0622073561 0.0574796010 0.0880135372 0.0056159826 0.1619790000 983523337 0 402718720 -0.0717481300 -0.0348515213 0.3843524456 2259 1311867245.8110349178 0.0626938939 0.0574819093 0.0880135372 0.0056157240 0.1529630000 983526353 0 402718720 -0.0721435323 -0.0353827104 0.3861918151 2260 1311867245.8428230286 0.0629621670 0.0574843341 0.0880135372 0.0056149724 0.1531120000 983529313 0 402718720 -0.0724242106 -0.0359123386 0.3880592585 2261 1311867245.8757770061 0.0632835254 0.0574868990 0.0880135372 0.0056138429 0.1530370000 983532161 0 402718720 -0.0727190226 -0.0358715989 0.3899305463 2262 1311867245.9110751152 0.0632149428 0.0574894313 0.0880135372 0.0056134973 0.1528570000 983535177 0 402718720 -0.0732181966 -0.0363601893 0.3914499581 2263 1311867245.9428870678 0.0634189993 0.0574920515 0.0880135372 0.0056132690 0.1532870000 983538081 0 402718720 -0.0734618828 -0.0361877456 0.3931956887 2264 1311867245.9751350880 0.0635593906 0.0574947315 0.0880135372 0.0056123677 0.1528240000 983540985 0 402718720 -0.0742384419 -0.0360880382 0.3949531913 2265 1311867246.0112419128 0.0632945076 0.0574972921 0.0880135372 0.0056111474 0.1505670000 983544001 0 402718720 -0.0750572011 -0.0355971456 0.3969429731 2266 1311867246.0429229736 0.0633551180 0.0574998772 0.0880135372 0.0056099152 0.1626960000 983546849 0 402718720 -0.0757092386 -0.0351117253 0.3990851343 2267 1311867246.0752329826 0.0636748448 0.0575026010 0.0880135372 0.0056088459 0.1497830000 983549753 0 402718720 -0.0765348896 -0.0346390605 0.4013201296 2268 1311867246.1109249592 0.0639206395 0.0575054308 0.0880135372 0.0056084382 0.1616610000 983552769 0 402718720 -0.0768558830 -0.0336553939 0.4035729468 2269 1311867246.1430890560 0.0644865185 0.0575085076 0.0880135372 0.0056072448 0.1504020000 983555729 0 402718720 -0.0775624439 -0.0332244895 0.4056136012 2270 1311867246.1749811172 0.0645783246 0.0575116220 0.0880135372 0.0056064754 0.1506880000 983558577 0 402718720 -0.0780911520 -0.0325955786 0.4077945352 2271 1311867246.2109639645 0.0644790232 0.0575146900 0.0880135372 0.0056055272 0.1497740000 983561593 0 402718720 -0.0785475820 -0.0316306278 0.4099663198 2272 1311867246.2429399490 0.0648417398 0.0575179149 0.0880135372 0.0056045218 0.1495960000 983564497 0 402718720 -0.0787483454 -0.0307995584 0.4120351970 2273 1311867246.2750649452 0.0653376132 0.0575213552 0.0880135372 0.0056036733 0.1674120000 983567401 0 402718720 -0.0787900910 -0.0298604239 0.4141705632 2274 1311867246.3108720779 0.0653309003 0.0575247895 0.0880135372 0.0056033334 0.1491610000 983570417 0 402718720 -0.0790237263 -0.0288767498 0.4162186384 2275 1311867246.3429319859 0.0654517487 0.0575282738 0.0880135372 0.0056028172 0.1624130000 983573321 0 402718720 -0.0793052688 -0.0283266809 0.4181576073 2276 1311867246.3752970695 0.0657977611 0.0575319072 0.0880135372 0.0056017315 0.1488070000 983576225 0 402718720 -0.0795712993 -0.0277828090 0.4200950265 2277 1311867246.4109311104 0.0660062209 0.0575356289 0.0880135372 0.0056008689 0.1598750000 983579241 0 402718720 -0.0796751752 -0.0272803903 0.4220995903 2278 1311867246.4430770874 0.0662712157 0.0575394637 0.0880135372 0.0055998829 0.1576470000 983582145 0 402718720 -0.0797100142 -0.0266397819 0.4239774644 2279 1311867246.4751329422 0.0665928125 0.0575434362 0.0880135372 0.0055987370 0.1585680000 983585049 0 402718720 -0.0800264403 -0.0263132211 0.4256793857 2280 1311867246.5109679699 0.0669229850 0.0575475500 0.0880135372 0.0055984566 0.1480080000 983588065 0 402718720 -0.0800063163 -0.0255937148 0.4273828268 2281 1311867246.5431129932 0.0673978999 0.0575518684 0.0880135372 0.0055975653 0.1470990000 983590913 0 402718720 -0.0799314007 -0.0250752065 0.4288921654 2282 1311867246.5752038956 0.0677352846 0.0575563309 0.0880135372 0.0055966160 0.1472300000 983593873 0 402718720 -0.0801196322 -0.0251289885 0.4301324785 2283 1311867246.6111249924 0.0678759813 0.0575608511 0.0880135372 0.0055956992 0.1588390000 983596889 0 402718720 -0.0803540945 -0.0253620911 0.4313338697 2284 1311867246.6431870461 0.0676077157 0.0575652499 0.0880135372 0.0055955750 0.1469090000 983599793 0 402718720 -0.0802867785 -0.0252208896 0.4324155450 2285 1311867246.6751689911 0.0675850138 0.0575696350 0.0880135372 0.0055947068 0.1474120000 983602697 0 402718720 -0.0805867687 -0.0255072005 0.4331764579 2286 1311867246.7110559940 0.0675864667 0.0575740168 0.0880135372 0.0055936263 0.1601220000 983605713 0 402718720 -0.0810607821 -0.0258255880 0.4339920580 2287 1311867246.7433049679 0.0678043962 0.0575784901 0.0880135372 0.0055924164 0.1471470000 983608673 0 402718720 -0.0811788440 -0.0260982234 0.4347717166 2288 1311867246.7749860287 0.0681902170 0.0575831280 0.0880135372 0.0055915362 0.1473280000 983611521 0 402718720 -0.0815803483 -0.0264830384 0.4355389476 2289 1311867246.8111929893 0.0684142336 0.0575878599 0.0880135372 0.0055905324 0.1469710000 983614537 0 402718720 -0.0817178413 -0.0266183913 0.4361558259 2290 1311867246.8430919647 0.0684697330 0.0575926118 0.0880135372 0.0055893234 0.1465480000 983617497 0 402718720 -0.0817422792 -0.0268579256 0.4367026687 2291 1311867246.8750779629 0.0684993640 0.0575973725 0.0880135372 0.0055885022 0.1449530000 983620345 0 402718720 -0.0821003541 -0.0272600111 0.4371996820 2292 1311867246.9111549854 0.0684669316 0.0576021148 0.0880135372 0.0055874228 0.1468000000 983623361 0 402718720 -0.0821544677 -0.0273135696 0.4377389252 2293 1311867246.9430611134 0.0685322955 0.0576068816 0.0880135372 0.0055863339 0.1717000000 983626209 0 402718720 -0.0822918043 -0.0278838053 0.4381431937 2294 1311867246.9751238823 0.0680777580 0.0576114461 0.0880135372 0.0055851681 0.1477650000 983629169 0 402718720 -0.0828091577 -0.0281398818 0.4384700060 2295 1311867247.0109090805 0.0680196434 0.0576159812 0.0880135372 0.0055841754 0.1474160000 983632185 0 402718720 -0.0827335417 -0.0281246714 0.4389831126 2296 1311867247.0440731049 0.0680220798 0.0576205135 0.0880135372 0.0055829620 0.1477550000 983635145 0 402718720 -0.0827404559 -0.0283584129 0.4394980967 2297 1311867247.0751919746 0.0681564659 0.0576251003 0.0880135372 0.0055819520 0.1479640000 983637993 0 402718720 -0.0829137042 -0.0281335562 0.4401090741 2298 1311867247.1112151146 0.0682954639 0.0576297437 0.0880135372 0.0055811205 0.1724570000 983641009 0 402718720 -0.0830255747 -0.0279446244 0.4406616092 2299 1311867247.1430439949 0.0683716014 0.0576344161 0.0880135372 0.0055802311 0.1477480000 983643913 0 402718720 -0.0833719745 -0.0279595088 0.4411903322 2300 1311867247.1751630306 0.0685173497 0.0576391478 0.0880135372 0.0055793339 0.1476130000 983646817 0 402718720 -0.0830862075 -0.0277159084 0.4416551590 2301 1311867247.2113189697 0.0687979534 0.0576439973 0.0880135372 0.0055787110 0.1585360000 983649833 0 402718720 -0.0835298449 -0.0283357985 0.4418675303 2302 1311867247.2437279224 0.0692348629 0.0576490325 0.0880135372 0.0055787154 0.1477220000 983652737 0 402718720 -0.0843206793 -0.0295956712 0.4418585300 2303 1311867247.2777190208 0.0695958808 0.0576542200 0.0880135372 0.0055779311 0.1791270000 983655753 0 402718720 -0.0845500529 -0.0300437398 0.4416532815 2304 1311867247.3109691143 0.0695137307 0.0576593673 0.0880135372 0.0055770447 0.1470130000 983658601 0 402718720 -0.0851071998 -0.0304731354 0.4409617782 2305 1311867247.3432049751 0.0695716962 0.0576645354 0.0880135372 0.0055768050 0.1480560000 983661505 0 402718720 -0.0855756775 -0.0312559605 0.4401426613 2306 1311867247.3753070831 0.0693126023 0.0576695866 0.0880135372 0.0055759043 0.1481450000 983664409 0 402718720 -0.0861732736 -0.0314730443 0.4393269122 2307 1311867247.4116749763 0.0694088638 0.0576746751 0.0880135372 0.0055762033 0.1483670000 983667481 0 402718720 -0.0866900682 -0.0325027108 0.4382286966 2308 1311867247.4440929890 0.0696770921 0.0576798755 0.0880135372 0.0055752387 0.1487840000 983670329 0 402718720 -0.0869550481 -0.0336156711 0.4370824099 2309 1311867247.4751029015 0.0695655420 0.0576850230 0.0880135372 0.0055740989 0.1487750000 983673233 0 402718720 -0.0873329639 -0.0342925973 0.4357875288 2310 1311867247.5110449791 0.0696905553 0.0576902202 0.0880135372 0.0055764926 0.1492240000 983676249 0 402718720 -0.0874223337 -0.0357509926 0.4342734218 2311 1311867247.5430850983 0.0699217990 0.0576955130 0.0880135372 0.0055786910 0.1492970000 983679153 0 402718720 -0.0873009637 -0.0365805700 0.4326553345 2312 1311867247.5751209259 0.0693359300 0.0577005478 0.0880135372 0.0055824565 0.1491250000 983682001 0 402718720 -0.0871184841 -0.0371486135 0.4309642017 2313 1311867247.6114599705 0.0697719306 0.0577057667 0.0880135372 0.0055844622 0.1601460000 983685073 0 402718720 -0.0869472399 -0.0382723399 0.4290193319 2314 1311867247.6431109905 0.0697546080 0.0577109736 0.0880135372 0.0055833534 0.1490920000 983687921 0 402718720 -0.0866346285 -0.0391536579 0.4270375073 2315 1311867247.6750760078 0.0697277337 0.0577161644 0.0880135372 0.0055854874 0.1491510000 983690825 0 402718720 -0.0858200565 -0.0405361727 0.4247552752 2316 1311867247.7112369537 0.0705926716 0.0577217242 0.0880135372 0.0055846255 0.1499150000 983693897 0 402718720 -0.0854333416 -0.0425692759 0.4219704568 2317 1311867247.7431221008 0.0705852062 0.0577272760 0.0880135372 0.0055837623 0.1504750000 983696745 0 402718720 -0.0849773958 -0.0436951742 0.4191567004 2318 1311867247.7750411034 0.0697824433 0.0577324767 0.0880135372 0.0055832635 0.1592160000 983699649 0 402718720 -0.0844011232 -0.0440139435 0.4163743258 2319 1311867247.8111629486 0.0695525333 0.0577375737 0.0880135372 0.0055823715 0.1511530000 983702665 0 402718720 -0.0841553658 -0.0445174873 0.4136059582 2320 1311867247.8438889980 0.0690602362 0.0577424542 0.0880135372 0.0055826827 0.1510150000 983705625 0 402718720 -0.0841512010 -0.0447041765 0.4110665917 2321 1311867247.8752439022 0.0683421791 0.0577470211 0.0880135372 0.0055817106 0.1509330000 983708473 0 402718720 -0.0836232603 -0.0444032811 0.4089373946 2322 1311867247.9113290310 0.0683305338 0.0577515790 0.0880135372 0.0055810022 0.1509400000 983711489 0 402718720 -0.0832920596 -0.0448845997 0.4068461657 2323 1311867247.9430620670 0.0681884363 0.0577560719 0.0880135372 0.0055803691 0.1610300000 983714449 0 402718720 -0.0827649161 -0.0454035178 0.4048530459 2324 1311867247.9769830704 0.0680778250 0.0577605132 0.0880135372 0.0055792242 0.1628340000 983717409 0 402718720 -0.0820135549 -0.0451613441 0.4030456841 2325 1311867248.0109910965 0.0682746693 0.0577650354 0.0880135372 0.0055788483 0.1499730000 983720313 0 402718720 -0.0817288309 -0.0464176685 0.4008840919 2326 1311867248.0431969166 0.0683063418 0.0577695674 0.0880135372 0.0055778578 0.1501270000 983723273 0 402718720 -0.0812923834 -0.0472474732 0.3986125588 2327 1311867248.0751419067 0.0680887774 0.0577740019 0.0880135372 0.0055768142 0.1501280000 983726121 0 402718720 -0.0808944702 -0.0472192876 0.3962559700 2328 1311867248.1121830940 0.0683028325 0.0577785246 0.0880135372 0.0055756166 0.1628680000 983729193 0 402718720 -0.0808387324 -0.0480256043 0.3937817216 2329 1311867248.1431720257 0.0682342574 0.0577830140 0.0880135372 0.0055745351 0.1506650000 983732041 0 402718720 -0.0804730579 -0.0484323353 0.3912752271 2330 1311867248.1757500172 0.0681893826 0.0577874803 0.0880135372 0.0055733681 0.1510770000 983734889 0 402718720 -0.0804665908 -0.0485490002 0.3888384104 2331 1311867248.2111859322 0.0678680316 0.0577918048 0.0880135372 0.0055722374 0.1617960000 983737961 0 402718720 -0.0804303735 -0.0488084741 0.3864473999 2332 1311867248.2431430817 0.0679487884 0.0577961603 0.0880135372 0.0055710491 0.1486180000 983740865 0 402718720 -0.0799227208 -0.0487977527 0.3840799332 2333 1311867248.2755289078 0.0678428262 0.0578004666 0.0880135372 0.0055698679 0.1509230000 983743769 0 402718720 -0.0796296895 -0.0487269573 0.3816649020 2334 1311867248.3112230301 0.0673168600 0.0578045439 0.0880135372 0.0055701842 0.1494860000 983746729 0 402718720 -0.0795460492 -0.0488925651 0.3790415227 2335 1311867248.3434588909 0.0675248355 0.0578087068 0.0880135372 0.0055705507 0.1609160000 983749521 0 402718720 -0.0789593905 -0.0484931469 0.3766709864 2336 1311867248.3752219677 0.0674095824 0.0578128167 0.0880135372 0.0055719579 0.1741750000 983752425 0 402718720 -0.0785131902 -0.0474301539 0.3744166195 2337 1311867248.4115560055 0.0669063702 0.0578167079 0.0880135372 0.0055722192 0.1510480000 983755497 0 402718720 -0.0782058313 -0.0468745083 0.3721407056 2338 1311867248.4431369305 0.0671998337 0.0578207212 0.0880135372 0.0055710882 0.1717880000 983758345 0 402718720 -0.0778717026 -0.0468126610 0.3698201180 2339 1311867248.4759230614 0.0671030879 0.0578246897 0.0880135372 0.0055700178 0.1506770000 983761305 0 402718720 -0.0774426907 -0.0466568135 0.3675026000 2340 1311867248.5111510754 0.0665898621 0.0578284355 0.0880135372 0.0055692565 0.1605660000 983764265 0 402718720 -0.0770916268 -0.0464417003 0.3652125001 2341 1311867248.5431890488 0.0669163465 0.0578323176 0.0880135372 0.0055682610 0.1826880000 983767225 0 402718720 -0.0765313953 -0.0463929623 0.3628570437 2342 1311867248.5751869678 0.0667130277 0.0578361095 0.0880135372 0.0055674355 0.1825890000 983770073 0 402718720 -0.0760124028 -0.0466647707 0.3605325222 2343 1311867248.6114389896 0.0665742606 0.0578398390 0.0880135372 0.0055664978 0.1655190000 983773145 0 402718720 -0.0752789676 -0.0463861004 0.3582395613 2344 1311867248.6432449818 0.0670055002 0.0578437492 0.0880135372 0.0055653485 0.1506410000 983775993 0 402718720 -0.0750387311 -0.0465450250 0.3558274806 2345 1311867248.6753089428 0.0668789819 0.0578476022 0.0880135372 0.0055642425 0.1500400000 983778841 0 402718720 -0.0747401863 -0.0466844477 0.3533214033 2346 1311867248.7112829685 0.0673063621 0.0578516341 0.0880135372 0.0055639672 0.1504100000 983781913 0 402718720 -0.0742049590 -0.0460911617 0.3508707881 2347 1311867248.7433049679 0.0671669468 0.0578556031 0.0880135372 0.0055640949 0.1515630000 983784761 0 402718720 -0.0737937391 -0.0457366668 0.3481019437 2348 1311867248.7762219906 0.0669719726 0.0578594857 0.0880135372 0.0055629898 0.1592110000 983787721 0 402718720 -0.0731431395 -0.0456165783 0.3452867270 2349 1311867248.8111898899 0.0670903549 0.0578634154 0.0880135372 0.0055648436 0.1520500000 983790681 0 402718720 -0.0727459118 -0.0448654741 0.3427405655 2350 1311867248.8433189392 0.0667728335 0.0578672067 0.0880135372 0.0055701188 0.1516300000 983793585 0 402718720 -0.0727256164 -0.0450960286 0.3398953676 2351 1311867248.8755309582 0.0669650286 0.0578710764 0.0880135372 0.0055697129 0.1514740000 983796545 0 402718720 -0.0720749125 -0.0455889478 0.3369361162 2352 1311867248.9111700058 0.0671416000 0.0578750180 0.0880135372 0.0055689299 0.1494610000 983799561 0 402718720 -0.0709681436 -0.0450029857 0.3340386748 2353 1311867248.9430971146 0.0669225901 0.0578788631 0.0880135372 0.0055680626 0.1500720000 983802409 0 402718720 -0.0705331191 -0.0450167693 0.3310324550 2354 1311867248.9766070843 0.0670097247 0.0578827420 0.0880135372 0.0055675219 0.1498180000 983805425 0 402718720 -0.0702284276 -0.0456521735 0.3279077709 2355 1311867249.0112600327 0.0668660030 0.0578865565 0.0880135372 0.0055665820 0.1495160000 983808329 0 402718720 -0.0691234395 -0.0451719537 0.3249353170 2356 1311867249.0432310104 0.0670633689 0.0578904516 0.0880135372 0.0055654441 0.1616360000 983811233 0 402718720 -0.0677975342 -0.0448013768 0.3219624162 2357 1311867249.0799250603 0.0666639134 0.0578941739 0.0880135372 0.0055647596 0.1605570000 983814305 0 402718720 -0.0670908839 -0.0447431840 0.3188530505 2358 1311867249.1120550632 0.0665401146 0.0578978405 0.0880135372 0.0055645801 0.1597330000 983817209 0 402718720 -0.0659931451 -0.0439829454 0.3160840273 2359 1311867249.1435980797 0.0662622303 0.0579013863 0.0880135372 0.0055643750 0.1497760000 983820113 0 402718720 -0.0645515546 -0.0432531945 0.3132942021 2360 1311867249.1785130501 0.0662435666 0.0579049211 0.0880135372 0.0055636620 0.1497020000 983823017 0 402718720 -0.0636430532 -0.0438375399 0.3102232516 2361 1311867249.2113580704 0.0658143535 0.0579082711 0.0880135372 0.0055628763 0.1485810000 983825977 0 402718720 -0.0628689453 -0.0437534973 0.3072263002 2362 1311867249.2432780266 0.0657404438 0.0579115870 0.0880135372 0.0055625344 0.1498020000 983828937 0 402718720 -0.0616932660 -0.0427980199 0.3044642806 2363 1311867249.2773559093 0.0657408312 0.0579149003 0.0880135372 0.0055632089 0.1499150000 983831897 0 402718720 -0.0609251484 -0.0437291786 0.3014415801 2364 1311867249.3112919331 0.0655326769 0.0579181227 0.0880135372 0.0055640132 0.1500000000 983834801 0 402718720 -0.0598282330 -0.0435957871 0.2985925972 2365 1311867249.3437249660 0.0651307404 0.0579211725 0.0880135372 0.0055634186 0.1505530000 983837761 0 402718720 -0.0586364381 -0.0424681604 0.2959613502 2366 1311867249.3768579960 0.0648083687 0.0579240834 0.0880135372 0.0055649341 0.1500770000 983840721 0 402718720 -0.0578726977 -0.0430783331 0.2930754423 2367 1311867249.4112169743 0.0650280192 0.0579270846 0.0880135372 0.0055643092 0.1497030000 983843681 0 402718720 -0.0569109581 -0.0435025357 0.2902660072 2368 1311867249.4432210922 0.0647892132 0.0579299825 0.0880135372 0.0055637120 0.1818580000 983846529 0 402718720 -0.0558349788 -0.0429382361 0.2876658738 2369 1311867249.4764440060 0.0647040009 0.0579328419 0.0880135372 0.0055625439 0.1506020000 983849489 0 402718720 -0.0552125312 -0.0430870838 0.2849451005 2370 1311867249.5111339092 0.0647874251 0.0579357341 0.0880135372 0.0055618836 0.1505860000 983852449 0 402718720 -0.0548975244 -0.0440070517 0.2820467353 2371 1311867249.5432300568 0.0644432306 0.0579384787 0.0880135372 0.0055610772 0.1610800000 983855353 0 402718720 -0.0539433770 -0.0435391478 0.2793430686 2372 1311867249.5759820938 0.0644173622 0.0579412101 0.0880135372 0.0055599317 0.1504170000 983858313 0 402718720 -0.0532585829 -0.0433865152 0.2765981555 2373 1311867249.6112229824 0.0643455461 0.0579439090 0.0880135372 0.0055590499 0.1615870000 983861273 0 402718720 -0.0529252738 -0.0440729968 0.2737596929 2374 1311867249.6433780193 0.0640803054 0.0579464938 0.0880135372 0.0055598474 0.1505480000 983864177 0 402718720 -0.0524657406 -0.0434644483 0.2714010775 2375 1311867249.6751029491 0.0635925531 0.0579488711 0.0880135372 0.0055627298 0.1503850000 983867081 0 402718720 -0.0518192835 -0.0430915989 0.2689132988 2376 1311867249.7111389637 0.0642609820 0.0579515277 0.0880135372 0.0055626076 0.1500850000 983870041 0 402718720 -0.0517866053 -0.0440544859 0.2661287189 2377 1311867249.7432470322 0.0641043261 0.0579541162 0.0880135372 0.0055629946 0.1492380000 983873001 0 402718720 -0.0510371737 -0.0435249694 0.2635376155 2378 1311867249.7751579285 0.0632424951 0.0579563401 0.0880135372 0.0055648195 0.1586690000 983875849 0 402718720 -0.0502584726 -0.0422480181 0.2613212466 2379 1311867249.8111488819 0.0640224144 0.0579588899 0.0880135372 0.0055642216 0.1501520000 983878921 0 402718720 -0.0500255600 -0.0421035774 0.2589109838 2380 1311867249.8433248997 0.0638563260 0.0579613678 0.0880135372 0.0055631899 0.1498880000 983881769 0 402718720 -0.0492546372 -0.0412649512 0.2564569712 2381 1311867249.8784089088 0.0639718324 0.0579638922 0.0880135372 0.0055621777 0.1504860000 983884785 0 402718720 -0.0484882221 -0.0402647853 0.2541799247 2382 1311867249.9112401009 0.0642500445 0.0579665312 0.0880135372 0.0055611260 0.1501960000 983887689 0 402718720 -0.0481933467 -0.0398475900 0.2514279783 2383 1311867249.9432768822 0.0640832931 0.0579690980 0.0880135372 0.0055606701 0.1624970000 983890649 0 402718720 -0.0477056764 -0.0398645028 0.2486812472 2384 1311867249.9751698971 0.0642160550 0.0579717184 0.0880135372 0.0055601595 0.1509590000 983893497 0 402718720 -0.0471099839 -0.0396664999 0.2459400296 2385 1311867250.0117108822 0.0641502440 0.0579743090 0.0880135372 0.0055596978 0.1508960000 983896569 0 402718720 -0.0465583391 -0.0391442850 0.2430416644 2386 1311867250.0434269905 0.0642492399 0.0579769389 0.0880135372 0.0055592973 0.1512120000 983899473 0 402718720 -0.0462175980 -0.0388799198 0.2400530130 2387 1311867250.0767190456 0.0639636293 0.0579794469 0.0880135372 0.0055595197 0.1504430000 983902433 0 402718720 -0.0460095070 -0.0393003374 0.2369751632 2388 1311867250.1116099358 0.0639309660 0.0579819392 0.0880135372 0.0055585466 0.1588600000 983905393 0 402718720 -0.0455689020 -0.0391878635 0.2341354042 2389 1311867250.1432220936 0.0640480220 0.0579844783 0.0880135372 0.0055574736 0.1502570000 983908241 0 402718720 -0.0452217273 -0.0390746146 0.2311769426 2390 1311867250.1758980751 0.0638938919 0.0579869509 0.0880135372 0.0055563492 0.1526410000 983911201 0 402718720 -0.0448992662 -0.0395309441 0.2280343920 2391 1311867250.2133369446 0.0639995709 0.0579894656 0.0880135372 0.0055552596 0.1829970000 983914217 0 402718720 -0.0445459262 -0.0390193984 0.2250699699 2392 1311867250.2457129955 0.0633994266 0.0579917273 0.0880135372 0.0055547434 0.1541090000 983917177 0 402718720 -0.0439621545 -0.0383056439 0.2222046703 2393 1311867250.2751679420 0.0630418807 0.0579938377 0.0880135372 0.0055541838 0.1627510000 983919969 0 402718720 -0.0434382670 -0.0377909653 0.2194944322 2394 1311867250.3114409447 0.0633638650 0.0579960808 0.0880135372 0.0055531849 0.1506680000 983923041 0 402718720 -0.0430619493 -0.0374832302 0.2169182152 2395 1311867250.3431971073 0.0633367673 0.0579983107 0.0880135372 0.0055525626 0.1505030000 983925889 0 402718720 -0.0427345559 -0.0369468071 0.2145194560 2396 1311867250.3780639172 0.0629767627 0.0580003885 0.0880135372 0.0055516410 0.1510800000 983928905 0 402718720 -0.0420983844 -0.0364878438 0.2120852768 2397 1311867250.4116489887 0.0633354262 0.0580026142 0.0880135372 0.0055512533 0.1507830000 983931865 0 402718720 -0.0417418145 -0.0368890464 0.2094551772 2398 1311867250.4441781044 0.0629291385 0.0580046687 0.0880135372 0.0055501282 0.1781870000 983934713 0 402718720 -0.0408158563 -0.0369508564 0.2068788558 2399 1311867250.4793250561 0.0629167333 0.0580067162 0.0880135372 0.0055493605 0.1631080000 983937729 0 402718720 -0.0401717387 -0.0358394943 0.2045138925 2400 1311867250.5113220215 0.0627151355 0.0580086781 0.0880135372 0.0055485347 0.1755040000 983940633 0 402718720 -0.0400349572 -0.0356712453 0.2020657361 2401 1311867250.5443398952 0.0630298108 0.0580107693 0.0880135372 0.0055475334 0.1513900000 983943537 0 402718720 -0.0398336835 -0.0360524841 0.1997573078 2402 1311867250.5793490410 0.0629124492 0.0580128100 0.0880135372 0.0055465548 0.1700870000 983946553 0 402718720 -0.0389769487 -0.0348314792 0.1977563947 2403 1311867250.6114881039 0.0631097928 0.0580149311 0.0880135372 0.0055454349 0.1709880000 983949513 0 402718720 -0.0384569503 -0.0345680751 0.1954335272 2404 1311867250.6433761120 0.0630005524 0.0580170050 0.0880135372 0.0055450058 0.1521980000 983952417 0 402718720 -0.0383549072 -0.0352424681 0.1929144412 2405 1311867250.6795539856 0.0632753894 0.0580191914 0.0880135372 0.0055451173 0.1520090000 983955377 0 402718720 -0.0377856642 -0.0345248468 0.1906794310 2406 1311867250.7112920284 0.0628692582 0.0580212072 0.0880135372 0.0055442475 0.1519930000 983958281 0 402718720 -0.0375294872 -0.0339593068 0.1882373542 2407 1311867250.7445890903 0.0625490919 0.0580230884 0.0880135372 0.0055458745 0.1521430000 983961241 0 402718720 -0.0374270082 -0.0346707478 0.1857602745 2408 1311867250.7792830467 0.0628025830 0.0580250732 0.0880135372 0.0055457867 0.1754750000 983964145 0 402718720 -0.0376186408 -0.0349456221 0.1835367680 2409 1311867250.8145580292 0.0623804107 0.0580268811 0.0880135372 0.0055452053 0.1629310000 983967161 0 402718720 -0.0371584147 -0.0343214944 0.1815157533 2410 1311867250.8433599472 0.0622034259 0.0580286142 0.0880135372 0.0055442032 0.1510700000 983969953 0 402718720 -0.0371923856 -0.0350543410 0.1794729829 2411 1311867250.8792760372 0.0617416315 0.0580301542 0.0880135372 0.0055458945 0.1510860000 983972969 0 402718720 -0.0375533365 -0.0358702205 0.1773822755 2412 1311867250.9116361141 0.0618048571 0.0580317192 0.0880135372 0.0055453322 0.1507240000 983975929 0 402718720 -0.0372921079 -0.0359660238 0.1753338724 2413 1311867250.9433720112 0.0620718263 0.0580333935 0.0880135372 0.0055445567 0.1761750000 983978777 0 402718720 -0.0372044221 -0.0364529826 0.1733326614 2414 1311867250.9793050289 0.0620133765 0.0580350422 0.0880135372 0.0055437586 0.1516780000 983981793 0 402718720 -0.0374023989 -0.0365242474 0.1713925004 2415 1311867251.0112459660 0.0615554303 0.0580364999 0.0880135372 0.0055429544 0.1520870000 983984697 0 402718720 -0.0370072201 -0.0361586101 0.1695637405 2416 1311867251.0437910557 0.0620472170 0.0580381600 0.0880135372 0.0055422320 0.1526040000 983987601 0 402718720 -0.0374795832 -0.0368747525 0.1674989313 2417 1311867251.0793159008 0.0622908659 0.0580399194 0.0880135372 0.0055415378 0.1526710000 983990617 0 402718720 -0.0374378525 -0.0372301564 0.1655267477 2418 1311867251.1115839481 0.0616498888 0.0580414124 0.0880135372 0.0055406968 0.1769780000 983993577 0 402718720 -0.0372010507 -0.0364410654 0.1637649685 2419 1311867251.1432809830 0.0615707822 0.0580428714 0.0880135372 0.0055404886 0.1635440000 983996481 0 402718720 -0.0376501903 -0.0365395322 0.1616913378 2420 1311867251.1794250011 0.0617621504 0.0580444083 0.0880135372 0.0055412780 0.1517900000 983999497 0 402718720 -0.0380225964 -0.0373037905 0.1595621109 2421 1311867251.2113831043 0.0617672354 0.0580459460 0.0880135372 0.0055457239 0.1527840000 984002401 0 402718720 -0.0383081734 -0.0366054587 0.1576851159 2422 1311867251.2472319603 0.0613505691 0.0580473105 0.0880135372 0.0055463979 0.1527400000 984005417 0 402718720 -0.0381649807 -0.0365989059 0.1556840837 2423 1311867251.2793700695 0.0619044416 0.0580489023 0.0880135372 0.0055453783 0.1753360000 984008265 0 402718720 -0.0388574898 -0.0380731709 0.1534272432 2424 1311867251.3133869171 0.0620179586 0.0580505397 0.0880135372 0.0055450839 0.1525880000 984011281 0 402718720 -0.0385873616 -0.0381077752 0.1514698565 2425 1311867251.3432419300 0.0609013811 0.0580517153 0.0880135372 0.0055483373 0.1523990000 984014073 0 402718720 -0.0387447886 -0.0380660146 0.1493963152 2426 1311867251.3801820278 0.0613465644 0.0580530735 0.0880135372 0.0055474654 0.1519960000 984017145 0 402718720 -0.0389268436 -0.0388935655 0.1472958177 2427 1311867251.4113550186 0.0610310026 0.0580543005 0.0880135372 0.0055464298 0.1538270000 984020049 0 402718720 -0.0387714952 -0.0388670564 0.1453437656 2428 1311867251.4433960915 0.0612771735 0.0580556279 0.0880135372 0.0055456044 0.1828950000 984022897 0 402718720 -0.0385532156 -0.0388533846 0.1435517222 2429 1311867251.4793379307 0.0612445585 0.0580569407 0.0880135372 0.0055447493 0.1534680000 984025913 0 402718720 -0.0389463678 -0.0392170288 0.1416024417 2430 1311867251.5175099373 0.0607776083 0.0580580603 0.0880135372 0.0055440172 0.1653350000 984029041 0 402718720 -0.0388143808 -0.0393109880 0.1397683471 2431 1311867251.5431749821 0.0610886589 0.0580593070 0.0880135372 0.0055433781 0.1676320000 984031721 0 402718720 -0.0389156155 -0.0392031372 0.1380096227 2432 1311867251.5795340538 0.0613436513 0.0580606575 0.0880135372 0.0055425015 0.1657030000 984034793 0 402718720 -0.0391465314 -0.0392915420 0.1360969245 2433 1311867251.6119680405 0.0611144789 0.0580619126 0.0880135372 0.0055413621 0.1542060000 984037753 0 402718720 -0.0387995392 -0.0392441154 0.1342849284 2434 1311867251.6432960033 0.0609480627 0.0580630984 0.0880135372 0.0055406089 0.1535220000 984040601 0 402718720 -0.0385631472 -0.0396016128 0.1323139966 2435 1311867251.6797280312 0.0611627735 0.0580643714 0.0880135372 0.0055418568 0.1531160000 984043617 0 402718720 -0.0389620028 -0.0400629640 0.1302992851 2436 1311867251.7123379707 0.0607903153 0.0580654904 0.0880135372 0.0055414439 0.1638950000 984046577 0 402718720 -0.0386121571 -0.0396328717 0.1282765716 2437 1311867251.7434990406 0.0605393425 0.0580665055 0.0880135372 0.0055410317 0.1527580000 984049369 0 402718720 -0.0381421819 -0.0387212522 0.1264622808 2438 1311867251.7797439098 0.0610573627 0.0580677323 0.0880135372 0.0055400739 0.1958620000 984052441 0 402718720 -0.0386179797 -0.0397094823 0.1242859066 2439 1311867251.8112530708 0.0608969666 0.0580688923 0.0880135372 0.0055393039 0.1554980000 984055345 0 402718720 -0.0385992527 -0.0401382372 0.1221236065 2440 1311867251.8433279991 0.0603642352 0.0580698330 0.0880135372 0.0055382535 0.1528560000 984058249 0 402718720 -0.0384934135 -0.0394425243 0.1203746200 2441 1311867251.8805420399 0.0601550713 0.0580706872 0.0880135372 0.0055376892 0.1527410000 984061209 0 402718720 -0.0382724479 -0.0396012887 0.1184718534 2442 1311867251.9112489223 0.0601657517 0.0580715452 0.0880135372 0.0055366006 0.1511430000 984064113 0 402718720 -0.0378368497 -0.0396176949 0.1168177575 2443 1311867251.9432179928 0.0602200925 0.0580724246 0.0880135372 0.0055362172 0.1767660000 984066961 0 402718720 -0.0373013392 -0.0387481228 0.1152805313 2444 1311867251.9800109863 0.0601645261 0.0580732807 0.0880135372 0.0055357813 0.1530640000 984070033 0 402718720 -0.0371968932 -0.0389062203 0.1135861650 2445 1311867252.0119040012 0.0599005558 0.0580740280 0.0880135372 0.0055349539 0.1539210000 984072993 0 402718720 -0.0370091088 -0.0388756357 0.1118397936 2446 1311867252.0441029072 0.0603021458 0.0580749389 0.0880135372 0.0055341688 0.1540730000 984075897 0 402718720 -0.0371104963 -0.0393016823 0.1099193692 2447 1311867252.0794539452 0.0609597303 0.0580761178 0.0880135372 0.0055330859 0.1529950000 984078801 0 402718720 -0.0365811326 -0.0395817347 0.1077542827 2448 1311867252.1122460365 0.0608450286 0.0580772489 0.0880135372 0.0055326442 0.1683300000 984081817 0 402718720 -0.0370055586 -0.0398287624 0.1051810607 2449 1311867252.1432950497 0.0607646927 0.0580783463 0.0880135372 0.0055329927 0.1598830000 984084609 0 402718720 -0.0374365598 -0.0409532785 0.1023375392 2450 1311867252.1794359684 0.0609705597 0.0580795268 0.0880135372 0.0055318927 0.1865660000 984087625 0 402718720 -0.0373700298 -0.0417301767 0.0995042026 2451 1311867252.2113459110 0.0607283898 0.0580806075 0.0880135372 0.0055329148 0.1551000000 984090585 0 402718720 -0.0368985124 -0.0418548658 0.0967366844 2452 1311867252.2432808876 0.0604811497 0.0580815865 0.0880135372 0.0055325206 0.1542400000 984093489 0 402718720 -0.0374229215 -0.0429505184 0.0936731920 2453 1311867252.2794110775 0.0603378005 0.0580825063 0.0880135372 0.0055326933 0.1805070000 984096505 0 402718720 -0.0378252752 -0.0447152220 0.0907252878 2454 1311867252.3112668991 0.0599154308 0.0580832532 0.0880135372 0.0055324579 0.1552280000 984099409 0 402718720 -0.0376004092 -0.0453378744 0.0878689736 2455 1311867252.3450291157 0.0594167635 0.0580837964 0.0880135372 0.0055314896 0.1560730000 984102313 0 402718720 -0.0370204039 -0.0460556000 0.0849351585 2456 1311867252.3794589043 0.0594802983 0.0580843650 0.0880135372 0.0055307886 0.1570260000 984105329 0 402718720 -0.0371062122 -0.0485281385 0.0818247423 2457 1311867252.4111969471 0.0598572455 0.0580850866 0.0880135372 0.0055302289 0.1566420000 984108233 0 402718720 -0.0372153595 -0.0503598228 0.0787525326 2458 1311867252.4456050396 0.0598702319 0.0580858128 0.0880135372 0.0055366471 0.1860200000 984111193 0 402718720 -0.0361318514 -0.0505965315 0.0760067105 2459 1311867252.4792900085 0.0587683171 0.0580860904 0.0880135372 0.0055452474 0.1561920000 984114097 0 402718720 -0.0358551815 -0.0516695343 0.0729104355 2460 1311867252.5112249851 0.0591643713 0.0580865287 0.0880135372 0.0055442998 0.1576930000 984117057 0 402718720 -0.0361989699 -0.0534921959 0.0696729198 2461 1311867252.5432820320 0.0588344000 0.0580868326 0.0880135372 0.0055440260 0.1564160000 984119961 0 402718720 -0.0357874930 -0.0535648540 0.0666942224 2462 1311867252.5791800022 0.0586294718 0.0580870530 0.0880135372 0.0055429157 0.1796180000 984122977 0 402718720 -0.0365394726 -0.0541349687 0.0638141781 2463 1311867252.6112799644 0.0586675480 0.0580872887 0.0880135372 0.0055418968 0.1574700000 984125881 0 402718720 -0.0369830988 -0.0556546859 0.0607515760 2464 1311867252.6432769299 0.0589321405 0.0580876316 0.0880135372 0.0055409632 0.1584540000 984128841 0 402718720 -0.0361123756 -0.0564254187 0.0577109680 2465 1311867252.6792490482 0.0590005293 0.0580880019 0.0880135372 0.0055412481 0.1580520000 984131745 0 402718720 -0.0366471671 -0.0569210872 0.0549482703 2466 1311867252.7112491131 0.0586969033 0.0580882488 0.0880135372 0.0055408758 0.1576920000 984134705 0 402718720 -0.0373311453 -0.0581836961 0.0518768057 2467 1311867252.7432410717 0.0588912256 0.0580885743 0.0880135372 0.0055398641 0.1578970000 984137553 0 402718720 -0.0366004594 -0.0597267933 0.0485140309 2468 1311867252.7792730331 0.0591376573 0.0580889994 0.0880135372 0.0055387704 0.1771710000 984140569 0 402718720 -0.0361385383 -0.0603757612 0.0455117784 2469 1311867252.8112781048 0.0592922196 0.0580894867 0.0880135372 0.0055383580 0.1576400000 984143529 0 402718720 -0.0355692357 -0.0603735633 0.0425994620 2470 1311867252.8433189392 0.0591508970 0.0580899164 0.0880135372 0.0055379817 0.1580970000 984146433 0 402718720 -0.0352700315 -0.0616955124 0.0393083841 2471 1311867252.8792660236 0.0594932176 0.0580904844 0.0880135372 0.0055384789 0.1581850000 984149393 0 402718720 -0.0348694921 -0.0619092546 0.0363071188 2472 1311867252.9112188816 0.0587766059 0.0580907619 0.0880135372 0.0055374492 0.1578890000 984152353 0 402718720 -0.0342274755 -0.0614999421 0.0335581638 2473 1311867252.9446918964 0.0586979948 0.0580910075 0.0880135372 0.0055370587 0.1781870000 984155257 0 402718720 -0.0334658474 -0.0625794008 0.0305921379 2474 1311867252.9806020260 0.0594608672 0.0580915612 0.0880135372 0.0055369416 0.1593270000 984158273 0 402718720 -0.0333152488 -0.0636253804 0.0276736058 2475 1311867253.0113809109 0.0585196763 0.0580917341 0.0880135372 0.0055359986 0.1582620000 984161177 0 402718720 -0.0316996835 -0.0625739172 0.0251166169 2476 1311867253.0434310436 0.0590491630 0.0580921208 0.0880135372 0.0055357044 0.1585570000 984164081 0 402718720 -0.0314968750 -0.0639342293 0.0222467910 2477 1311867253.0799300671 0.0590412207 0.0580925040 0.0880135372 0.0055431515 0.1714960000 984167097 0 402718720 -0.0312775746 -0.0655747354 0.0190766454 2478 1311867253.1113030910 0.0589829944 0.0580928633 0.0880135372 0.0055451141 0.1688950000 984170001 0 402718720 -0.0305151474 -0.0649334788 0.0163095910 2479 1311867253.1440761089 0.0587788895 0.0580931401 0.0880135372 0.0055448711 0.1597830000 984172905 0 402718720 -0.0299173687 -0.0650580376 0.0133007132 2480 1311867253.1794049740 0.0587443672 0.0580934027 0.0880135372 0.0055439330 0.1591180000 984175865 0 402718720 -0.0297593977 -0.0661572143 0.0102198487 2481 1311867253.2112159729 0.0585347041 0.0580935805 0.0880135372 0.0055434185 0.1590950000 984178825 0 402718720 -0.0287614074 -0.0666660964 0.0075005130 2482 1311867253.2458410263 0.0578833222 0.0580934958 0.0880135372 0.0055423945 0.1598530000 984181785 0 402718720 -0.0286362432 -0.0667448267 0.0047905501 2483 1311867253.2793951035 0.0580918863 0.0580934952 0.0880135372 0.0055417482 0.1726240000 984184689 0 402718720 -0.0278398469 -0.0669120401 0.0021748494 2484 1311867253.3114080429 0.0576792769 0.0580933284 0.0880135372 0.0055407510 0.1707270000 984187649 0 402718720 -0.0266863406 -0.0672657937 -0.0003091182 2485 1311867253.3445611000 0.0576358177 0.0580931443 0.0880135372 0.0055464632 0.1597180000 984190609 0 402718720 -0.0259030070 -0.0677004755 -0.0027370420 2486 1311867253.3794078827 0.0575070530 0.0580929086 0.0880135372 0.0055491241 0.1603670000 984193513 0 402718720 -0.0245481394 -0.0681378171 -0.0051942179 2487 1311867253.4129528999 0.0575937405 0.0580927078 0.0880135372 0.0055498743 0.1606580000 984196529 0 402718720 -0.0237969849 -0.0687289611 -0.0075587388 2488 1311867253.4444990158 0.0574778095 0.0580924607 0.0880135372 0.0055498712 0.1823100000 984199377 0 402718720 -0.0232258476 -0.0687918290 -0.0098302243 2489 1311867253.4804859161 0.0575339831 0.0580922363 0.0880135372 0.0055499188 0.1620380000 984202393 0 402718720 -0.0217308886 -0.0685725436 -0.0119542386 2490 1311867253.5113739967 0.0572294183 0.0580918898 0.0880135372 0.0055491148 0.1620220000 984205297 0 402718720 -0.0201417115 -0.0694984868 -0.0143684298 2491 1311867253.5441629887 0.0572120473 0.0580915366 0.0880135372 0.0055488132 0.1610860000 984208145 0 402718720 -0.0200806633 -0.0705583915 -0.0166716799 2492 1311867253.5794069767 0.0570472702 0.0580911176 0.0880135372 0.0055480331 0.1615310000 984211161 0 402718720 -0.0189701114 -0.0711778477 -0.0188500900 2493 1311867253.6118021011 0.0568605885 0.0580906240 0.0880135372 0.0055470192 0.1909610000 984214121 0 402718720 -0.0191433225 -0.0722158030 -0.0214094426 2494 1311867253.6447649002 0.0570378266 0.0580902018 0.0880135372 0.0055461859 0.1621670000 984217025 0 402718720 -0.0187434237 -0.0732351318 -0.0238824654 2495 1311867253.6799790859 0.0569433607 0.0580897422 0.0880135372 0.0055452454 0.1619130000 984220041 0 402718720 -0.0185380951 -0.0741053671 -0.0264257658 2496 1311867253.7115769386 0.0572142974 0.0580893914 0.0880135372 0.0055449789 0.1946420000 984222945 0 402718720 -0.0185671430 -0.0756781697 -0.0293694716 2497 1311867253.7435369492 0.0573665164 0.0580891019 0.0880135372 0.0055463382 0.1974510000 984225793 0 402718720 -0.0187119003 -0.0783158019 -0.0328702480 2498 1311867253.7806150913 0.0576811433 0.0580889386 0.0880135372 0.0055463636 0.1969550000 984228809 0 402718720 -0.0193694755 -0.0796933919 -0.0363385268 2499 1311867253.8113009930 0.0574162565 0.0580886694 0.0880135372 0.0055453484 0.1688380000 984231713 0 402718720 -0.0196074340 -0.0810579658 -0.0398387797 2500 1311867253.8469560146 0.0572532900 0.0580883353 0.0880135372 0.0055452613 0.1626450000 984234729 0 402718720 -0.0200835206 -0.0823607221 -0.0436229296 2501 1311867253.8792059422 0.0570789762 0.0580879317 0.0880135372 0.0055443876 0.1640940000 984237577 0 402718720 -0.0210539699 -0.0842852890 -0.0475771129 2502 1311867253.9114460945 0.0567593127 0.0580874007 0.0880135372 0.0055433029 0.1635310000 984240481 0 402718720 -0.0225115065 -0.0857115388 -0.0515834317 2503 1311867253.9461600780 0.0565145202 0.0580867723 0.0880135372 0.0055422519 0.1759270000 984243497 0 402718720 -0.0232311115 -0.0859017968 -0.0555029996 2504 1311867253.9794149399 0.0562816076 0.0580860514 0.0880135372 0.0055412629 0.1645870000 984246345 0 402718720 -0.0245135669 -0.0865809396 -0.0591571070 2505 1311867254.0119979382 0.0563235655 0.0580853478 0.0880135372 0.0055414846 0.1652710000 984249305 0 402718720 -0.0262380838 -0.0883010775 -0.0628880560 2506 1311867254.0457749367 0.0558792539 0.0580844675 0.0880135372 0.0055404229 0.1651570000 984252265 0 402718720 -0.0269670188 -0.0886669308 -0.0662517026 2507 1311867254.0793740749 0.0565029569 0.0580838366 0.0880135372 0.0055443786 0.1650350000 984255169 0 402718720 -0.0276470259 -0.0892145857 -0.0695062354 2508 1311867254.1113519669 0.0562986434 0.0580831248 0.0880135372 0.0055435573 0.1748210000 984258073 0 402718720 -0.0285292361 -0.0902000740 -0.0728461668 2509 1311867254.1476950645 0.0563311055 0.0580824265 0.0880135372 0.0055427850 0.1644230000 984261145 0 402718720 -0.0306233540 -0.0898350850 -0.0758451372 2510 1311867254.1795129776 0.0563310795 0.0580817288 0.0880135372 0.0055417455 0.1648840000 984263993 0 402718720 -0.0308955833 -0.0898821577 -0.0788183361 2511 1311867254.2114939690 0.0548907518 0.0580804580 0.0880135372 0.0055460941 0.1652190000 984266953 0 402718720 -0.0320835449 -0.0900667384 -0.0819150507 2512 1311867254.2469160557 0.0558707342 0.0580795783 0.0880135372 0.0055459233 0.1645250000 984269969 0 402718720 -0.0338070840 -0.0900920480 -0.0850523040 2513 1311867254.2798569202 0.0558343306 0.0580786849 0.0880135372 0.0055465889 0.1746910000 984272817 0 402718720 -0.0351536013 -0.0880136266 -0.0879599229 2514 1311867254.3114631176 0.0550726168 0.0580774891 0.0880135372 0.0055532425 0.1648980000 984275721 0 402718720 -0.0368112959 -0.0862604305 -0.0911447555 2515 1311867254.3475589752 0.0563405156 0.0580767985 0.0880135372 0.0055537356 0.1654500000 984278793 0 402718720 -0.0389910042 -0.0872297809 -0.0947475135 2516 1311867254.3794488907 0.0568119548 0.0580762958 0.0880135372 0.0055529442 0.1654050000 984281641 0 402718720 -0.0405453220 -0.0885518566 -0.0986016840 2517 1311867254.4115350246 0.0568941161 0.0580758261 0.0880135372 0.0055571384 0.1644510000 984284601 0 402718720 -0.0417658687 -0.0881918296 -0.1024304554 2518 1311867254.4483439922 0.0574444570 0.0580755753 0.0880135372 0.0055563835 0.1883940000 984287617 0 402718720 -0.0427123271 -0.0877647400 -0.1065960005 2519 1311867254.4794480801 0.0569366813 0.0580751232 0.0880135372 0.0055558602 0.1657330000 984290465 0 402718720 -0.0427561775 -0.0881541893 -0.1108530015 2520 1311867254.5114428997 0.0564635172 0.0580744837 0.0880135372 0.0055547801 0.1648030000 984293369 0 402718720 -0.0428072847 -0.0880564973 -0.1149496660 2521 1311867254.5500459671 0.0569251440 0.0580740278 0.0880135372 0.0055554538 0.1650370000 984296441 0 402718720 -0.0425698832 -0.0875886008 -0.1193979904 2522 1311867254.5794870853 0.0565924495 0.0580734403 0.0880135372 0.0055594702 0.1645850000 984299289 0 402718720 -0.0425150767 -0.0876471996 -0.1236202419 2523 1311867254.6114809513 0.0557982549 0.0580725386 0.0880135372 0.0055585417 0.1770670000 984302193 0 402718720 -0.0433943383 -0.0867168903 -0.1275391281 2524 1311867254.6452929974 0.0556529723 0.0580715799 0.0880135372 0.0055598106 0.1655220000 984305153 0 402718720 -0.0434794724 -0.0851474404 -0.1315026879 2525 1311867254.6794900894 0.0558792613 0.0580707117 0.0880135372 0.0055606689 0.1649240000 984308169 0 402718720 -0.0437758304 -0.0846909881 -0.1357849538 2526 1311867254.7113230228 0.0550561585 0.0580695183 0.0880135372 0.0055596893 0.1649920000 984311073 0 402718720 -0.0442603417 -0.0848703906 -0.1398963630 2527 1311867254.7453329563 0.0553176589 0.0580684293 0.0880135372 0.0055608160 0.1645430000 984313977 0 402718720 -0.0444955640 -0.0836825222 -0.1433492005 2528 1311867254.7794649601 0.0552918501 0.0580673310 0.0880135372 0.0055642603 0.1786250000 984316937 0 402718720 -0.0447104909 -0.0825161636 -0.1468440294 2529 1311867254.8115739822 0.0551905595 0.0580661934 0.0880135372 0.0055638093 0.1648620000 984319841 0 402718720 -0.0452615507 -0.0825456306 -0.1502279788 2530 1311867254.8482780457 0.0549363270 0.0580649563 0.0880135372 0.0055649775 0.1958980000 984322969 0 402718720 -0.0444776528 -0.0819359273 -0.1533102542 2531 1311867254.8794910908 0.0553727858 0.0580638927 0.0880135372 0.0055639779 0.2007920000 984325761 0 402718720 -0.0442316942 -0.0816364735 -0.1563688368 2532 1311867254.9138929844 0.0549068227 0.0580626458 0.0880135372 0.0055638221 0.2007390000 984328721 0 402718720 -0.0451161750 -0.0815201998 -0.1597027183 2533 1311867254.9490759373 0.0550858863 0.0580614706 0.0880135372 0.0055634916 0.1676110000 984331737 0 402718720 -0.0460098200 -0.0814670101 -0.1626831740 2534 1311867254.9819579124 0.0546094365 0.0580601083 0.0880135372 0.0055629920 0.1648570000 984334697 0 402718720 -0.0460055172 -0.0801787898 -0.1654723883 2535 1311867255.0154359341 0.0550305545 0.0580589132 0.0880135372 0.0055640652 0.1654080000 984337601 0 402718720 -0.0460928939 -0.0800875947 -0.1681369990 2536 1311867255.0494379997 0.0554448478 0.0580578824 0.0880135372 0.0055631922 0.1649190000 984340561 0 402718720 -0.0462445505 -0.0800277516 -0.1708440483 2537 1311867255.0822079182 0.0546093546 0.0580565232 0.0880135372 0.0055621487 0.1648630000 984343465 0 402718720 -0.0459298082 -0.0786457360 -0.1732430756 2538 1311867255.1176838875 0.0556660779 0.0580555813 0.0880135372 0.0055610718 0.1757700000 984346369 0 402718720 -0.0457034521 -0.0786966980 -0.1755576730 2539 1311867255.1510150433 0.0554655902 0.0580545612 0.0880135372 0.0055609912 0.1649370000 984349273 0 402718720 -0.0456078015 -0.0788560361 -0.1782460064 2540 1311867255.1838800907 0.0552729741 0.0580534661 0.0880135372 0.0055612474 0.1649110000 984352065 0 402718720 -0.0472420640 -0.0777655840 -0.1809256226 2541 1311867255.2169129848 0.0546218865 0.0580521156 0.0880135372 0.0055614172 0.1658160000 984354969 0 402718720 -0.0475114211 -0.0760863647 -0.1833759844 2542 1311867255.2459371090 0.0545947887 0.0580507555 0.0880135372 0.0055608177 0.1658780000 984357817 0 402718720 -0.0480473414 -0.0757972598 -0.1859906167 2543 1311867255.2793660164 0.0549937561 0.0580495534 0.0880135372 0.0055701538 0.1766900000 984360721 0 402718720 -0.0481290892 -0.0760263875 -0.1884675175 2544 1311867255.3138630390 0.0552236661 0.0580484426 0.0880135372 0.0055702036 0.1652510000 984363681 0 402718720 -0.0484795384 -0.0759130567 -0.1911632568 2545 1311867255.3468410969 0.0554212928 0.0580474103 0.0880135372 0.0055696939 0.1658410000 984366641 0 402718720 -0.0482635722 -0.0760955065 -0.1939978451 2546 1311867255.3794751167 0.0554106310 0.0580463747 0.0880135372 0.0055686777 0.1652270000 984369545 0 402718720 -0.0483587049 -0.0763192847 -0.1970776170 2547 1311867255.4137639999 0.0554550923 0.0580453573 0.0880135372 0.0055717117 0.1639680000 984372505 0 402718720 -0.0490172841 -0.0758608133 -0.2000824362 2548 1311867255.4455530643 0.0550048500 0.0580441640 0.0880135372 0.0055710690 0.1825810000 984375409 0 402718720 -0.0495458432 -0.0754676834 -0.2030945420 2549 1311867255.4794819355 0.0560304634 0.0580433740 0.0880135372 0.0055716250 0.1645370000 984378369 0 402718720 -0.0498235822 -0.0755080879 -0.2058955878 2550 1311867255.5156099796 0.0563689880 0.0580427174 0.0880135372 0.0055728140 0.1640490000 984381385 0 402718720 -0.0492176563 -0.0747508258 -0.2086994052 2551 1311867255.5457780361 0.0552903824 0.0580416384 0.0880135372 0.0055745941 0.1637240000 984384233 0 402718720 -0.0486268550 -0.0743330941 -0.2117009014 2552 1311867255.5794420242 0.0563752428 0.0580409855 0.0880135372 0.0055735672 0.1895140000 984387137 0 402718720 -0.0487290882 -0.0746520832 -0.2146634310 2553 1311867255.6153330803 0.0560896844 0.0580402212 0.0880135372 0.0055744259 0.1764000000 984390153 0 402718720 -0.0491344929 -0.0745223537 -0.2177081257 2554 1311867255.6456480026 0.0554937497 0.0580392241 0.0880135372 0.0055737678 0.1637750000 984393057 0 402718720 -0.0486997291 -0.0732571036 -0.2202279717 2555 1311867255.6801021099 0.0559421517 0.0580384033 0.0880135372 0.0055732342 0.1641620000 984396017 0 402718720 -0.0481777675 -0.0731991753 -0.2229156196 2556 1311867255.7182919979 0.0566251166 0.0580378504 0.0880135372 0.0055746670 0.1634610000 984399089 0 402718720 -0.0489175655 -0.0744636655 -0.2259861380 2557 1311867255.7457749844 0.0558880791 0.0580370097 0.0880135372 0.0055744788 0.1631390000 984401881 0 402718720 -0.0489292890 -0.0736126006 -0.2287529260 2558 1311867255.7810928822 0.0556962453 0.0580360946 0.0880135372 0.0055788335 0.1933890000 984404841 0 402718720 -0.0475699641 -0.0720989108 -0.2315156013 2559 1311867255.8176100254 0.0561468937 0.0580353563 0.0880135372 0.0055834371 0.1679060000 984407857 0 402718720 -0.0481272116 -0.0731521696 -0.2344659120 2560 1311867255.8457250595 0.0558427572 0.0580344998 0.0880135372 0.0055831384 0.1679080000 984410649 0 402718720 -0.0482273512 -0.0738325715 -0.2373546809 2561 1311867255.8793790340 0.0549616963 0.0580333000 0.0880135372 0.0055820875 0.1679400000 984413609 0 402718720 -0.0478803366 -0.0730663091 -0.2402410656 2562 1311867255.9140310287 0.0547107980 0.0580320032 0.0880135372 0.0055811117 0.1750710000 984416625 0 402718720 -0.0470385440 -0.0731136426 -0.2432020009 2563 1311867255.9459080696 0.0546951592 0.0580307012 0.0880135372 0.0055803389 0.1945380000 984419529 0 402718720 -0.0472391397 -0.0744251460 -0.2464280874 2564 1311867255.9794859886 0.0551211834 0.0580295665 0.0880135372 0.0055792912 0.1696650000 984422433 0 402718720 -0.0471962243 -0.0749902502 -0.2493268251 2565 1311867256.0177969933 0.0546505004 0.0580282491 0.0880135372 0.0055782045 0.1707010000 984425561 0 402718720 -0.0472934954 -0.0748394430 -0.2522809207 2566 1311867256.0460140705 0.0542230420 0.0580267662 0.0880135372 0.0055774309 0.1704410000 984428353 0 402718720 -0.0469548851 -0.0754361749 -0.2552069128 2567 1311867256.0856881142 0.0542305782 0.0580252873 0.0880135372 0.0055815669 0.1707500000 984431425 0 402718720 -0.0469976366 -0.0758181363 -0.2581583261 2568 1311867256.1167299747 0.0544288680 0.0580238868 0.0880135372 0.0055822747 0.1974180000 984434329 0 402718720 -0.0473821834 -0.0753454790 -0.2608995438 2569 1311867256.1452269554 0.0535343550 0.0580221393 0.0880135372 0.0055823755 0.1712980000 984437121 0 402718720 -0.0473608822 -0.0748334080 -0.2636990249 2570 1311867256.1795060635 0.0541327372 0.0580206259 0.0880135372 0.0055830401 0.1722500000 984440137 0 402718720 -0.0479264148 -0.0756927952 -0.2667464912 2571 1311867256.2177491188 0.0541655608 0.0580191264 0.0880135372 0.0055837581 0.1834780000 984443209 0 402718720 -0.0472085103 -0.0766950846 -0.2695373297 2572 1311867256.2454690933 0.0537353493 0.0580174609 0.0880135372 0.0055836940 0.1722420000 984445945 0 402718720 -0.0471103117 -0.0771932453 -0.2723923326 2573 1311867256.2847039700 0.0537990145 0.0580158214 0.0880135372 0.0055833850 0.1969190000 984449073 0 402718720 -0.0472668149 -0.0773804337 -0.2757979929 2574 1311867256.3143420219 0.0543822646 0.0580144098 0.0880135372 0.0055851609 0.2113940000 984451865 0 402718720 -0.0491517633 -0.0794630125 -0.2793759704 2575 1311867256.3471789360 0.0534118637 0.0580126224 0.0880135372 0.0055852996 0.1723780000 984454825 0 402718720 -0.0484675728 -0.0792959854 -0.2828853428 2576 1311867256.3848650455 0.0539785735 0.0580110563 0.0880135372 0.0055845189 0.1845560000 984457841 0 402718720 -0.0491637290 -0.0802071393 -0.2864554822 2577 1311867256.4158649445 0.0539080948 0.0580094642 0.0880135372 0.0055835744 0.1722880000 984460689 0 402718720 -0.0503368936 -0.0816234797 -0.2901277542 2578 1311867256.4452838898 0.0535318516 0.0580077273 0.0880135372 0.0055838377 0.2016140000 984463537 0 402718720 -0.0495914705 -0.0820999593 -0.2937391996 2579 1311867256.4844601154 0.0526808240 0.0580056619 0.0880135372 0.0055850605 0.1735370000 984466609 0 402718720 -0.0498821102 -0.0818207264 -0.2976374030 2580 1311867256.5135829449 0.0524278134 0.0580034999 0.0880135372 0.0055848151 0.1748240000 984469513 0 402718720 -0.0498194918 -0.0833685994 -0.3013987243 2581 1311867256.5478789806 0.0509780943 0.0580007779 0.0880135372 0.0056038228 0.1748740000 984472473 0 402718720 -0.0491637662 -0.0840881914 -0.3050783575 2582 1311867256.5836489201 0.0520265847 0.0579984641 0.0880135372 0.0056134982 0.1733170000 984475545 0 402718720 -0.0488333888 -0.0844471082 -0.3084641695 2583 1311867256.6160368919 0.0520681962 0.0579961683 0.0880135372 0.0056124280 0.2012630000 984478393 0 402718720 -0.0490594245 -0.0850184113 -0.3117145896 2584 1311867256.6452310085 0.0517784655 0.0579937620 0.0880135372 0.0056120082 0.1739500000 984481241 0 402718720 -0.0496681295 -0.0858509690 -0.3151122332 2585 1311867256.6832759380 0.0521067083 0.0579914846 0.0880135372 0.0056113102 0.1743820000 984484369 0 402718720 -0.0499709919 -0.0860231221 -0.3184791505 2586 1311867256.7140300274 0.0516483448 0.0579890318 0.0880135372 0.0056121008 0.1746020000 984487161 0 402718720 -0.0499984212 -0.0848350823 -0.3213062584 2587 1311867256.7463369370 0.0512894094 0.0579864420 0.0880135372 0.0056112451 0.1742210000 984490065 0 402718720 -0.0494409949 -0.0851185843 -0.3241557777 2588 1311867256.7827401161 0.0510927141 0.0579837783 0.0880135372 0.0056107412 0.1865350000 984493137 0 402718720 -0.0476212315 -0.0849014670 -0.3271556199 2589 1311867256.8140430450 0.0512701795 0.0579811852 0.0880135372 0.0056110845 0.1748250000 984495985 0 402718720 -0.0473649353 -0.0848175585 -0.3298002481 2590 1311867256.8477399349 0.0527699664 0.0579791731 0.0880135372 0.0056108803 0.1744310000 984498945 0 402718720 -0.0483401865 -0.0874827430 -0.3328959048 2591 1311867256.8838980198 0.0523114465 0.0579769857 0.0880135372 0.0056111406 0.1746360000 984501905 0 402718720 -0.0473944284 -0.0887292400 -0.3363591731 2592 1311867256.9148108959 0.0520459041 0.0579746974 0.0880135372 0.0056104664 0.1729960000 984504809 0 402718720 -0.0466554128 -0.0888798833 -0.3396327198 2593 1311867256.9465379715 0.0519901328 0.0579723895 0.0880135372 0.0056095109 0.1950050000 984507713 0 402718720 -0.0465134047 -0.0890121013 -0.3432537615 2594 1311867256.9814610481 0.0520046465 0.0579700889 0.0880135372 0.0056085947 0.1755940000 984510673 0 402718720 -0.0467937104 -0.0898019001 -0.3469808102 2595 1311867257.0129959583 0.0526043065 0.0579680211 0.0880135372 0.0056083085 0.2105810000 984513633 0 402718720 -0.0473969467 -0.0914181024 -0.3505288363 2596 1311867257.0451910496 0.0527623296 0.0579660159 0.0880135372 0.0056097439 0.2100670000 984516481 0 402718720 -0.0478545614 -0.0915010124 -0.3537730873 2597 1311867257.0841369629 0.0524439439 0.0579638895 0.0880135372 0.0056091692 0.2052640000 984519553 0 402718720 -0.0475027747 -0.0898650736 -0.3568979502 2598 1311867257.1134428978 0.0527416356 0.0579618794 0.0880135372 0.0056081183 0.1745900000 984522457 0 402718720 -0.0473908857 -0.0906273499 -0.3597440124 2599 1311867257.1474308968 0.0528514907 0.0579599131 0.0880135372 0.0056073669 0.1742670000 984525417 0 402718720 -0.0473534949 -0.0903343409 -0.3627774417 2600 1311867257.1821229458 0.0520746857 0.0579576496 0.0880135372 0.0056064287 0.1741020000 984528377 0 402718720 -0.0466116071 -0.0894996449 -0.3662509024 2601 1311867257.2147839069 0.0517224818 0.0579552524 0.0880135372 0.0056096587 0.1748940000 984531281 0 402718720 -0.0466637909 -0.0898362026 -0.3695453703 2602 1311867257.2457039356 0.0530094802 0.0579533516 0.0880135372 0.0056111116 0.1747430000 984534129 0 402718720 -0.0480358340 -0.0905982330 -0.3728015423 2603 1311867257.2824490070 0.0530269444 0.0579514590 0.0880135372 0.0056100995 0.1973730000 984537201 0 402718720 -0.0483999066 -0.0894310176 -0.3759427369 2604 1311867257.3133430481 0.0529368967 0.0579495333 0.0880135372 0.0056092156 0.1765950000 984540049 0 402718720 -0.0480361134 -0.0879534110 -0.3790108263 2605 1311867257.3452849388 0.0531597100 0.0579476946 0.0880135372 0.0056082855 0.1760630000 984542897 0 402718720 -0.0489117317 -0.0881554261 -0.3821218014 2606 1311867257.3839631081 0.0539878048 0.0579461751 0.0880135372 0.0056076334 0.1767340000 984545969 0 402718720 -0.0504076779 -0.0870774537 -0.3849913776 2607 1311867257.4198129177 0.0554442294 0.0579452154 0.0880135372 0.0056104163 0.1762420000 984548985 0 402718720 -0.0514717363 -0.0858599395 -0.3875710070 2608 1311867257.4458611012 0.0554793105 0.0579442699 0.0880135372 0.0056095818 0.2102330000 984551721 0 402718720 -0.0528770983 -0.0850805491 -0.3900180161 2609 1311867257.4851269722 0.0567641594 0.0579438175 0.0880135372 0.0056091622 0.1771920000 984554849 0 402718720 -0.0544676259 -0.0854045302 -0.3927361369 2610 1311867257.5166249275 0.0568566583 0.0579434010 0.0880135372 0.0056091509 0.1775830000 984557753 0 402718720 -0.0545213707 -0.0835908204 -0.3950356245 2611 1311867257.5537879467 0.0573158637 0.0579431606 0.0880135372 0.0056086523 0.1783410000 984560769 0 402718720 -0.0536509305 -0.0831557363 -0.3975844979 2612 1311867257.5836200714 0.0577426143 0.0579430839 0.0880135372 0.0056184331 0.1785010000 984563617 0 402718720 -0.0542835630 -0.0832720399 -0.4002357721 2613 1311867257.6154460907 0.0580354594 0.0579431192 0.0880135372 0.0056242026 0.1785230000 984566465 0 402718720 -0.0546482131 -0.0826121345 -0.4027021527 2614 1311867257.6519720554 0.0582735799 0.0579432456 0.0880135372 0.0056232901 0.1806670000 984569537 0 402718720 -0.0543831959 -0.0817273334 -0.4050777555 2615 1311867257.6842958927 0.0588558055 0.0579435946 0.0880135372 0.0056229081 0.1812850000 984572441 0 402718720 -0.0566873513 -0.0802110210 -0.4076530933 2616 1311867257.7187778950 0.0592691414 0.0579441013 0.0880135372 0.0056219453 0.1810080000 984575457 0 402718720 -0.0560388230 -0.0800965279 -0.4098206460 2617 1311867257.7527809143 0.0598248169 0.0579448200 0.0880135372 0.0056228266 0.1814110000 984578417 0 402718720 -0.0555285923 -0.0804600790 -0.4115823507 2618 1311867257.7838430405 0.0603597164 0.0579457424 0.0880135372 0.0056222364 0.2071870000 984581321 0 402718720 -0.0549676567 -0.0802920610 -0.4131892323 2619 1311867257.8181409836 0.0600549579 0.0579465477 0.0880135372 0.0056217377 0.1818150000 984584281 0 402718720 -0.0538857803 -0.0801042542 -0.4150144458 2620 1311867257.8530700207 0.0609507449 0.0579476944 0.0880135372 0.0056302989 0.1813860000 984587241 0 402718720 -0.0539497063 -0.0794505924 -0.4168933928 2621 1311867257.8854579926 0.0606794097 0.0579487366 0.0880135372 0.0056320435 0.1825910000 984590089 0 402718720 -0.0532989390 -0.0795917138 -0.4187770486 2622 1311867257.9152529240 0.0602287501 0.0579496062 0.0880135372 0.0056326777 0.1825710000 984592937 0 402718720 -0.0513477735 -0.0798032954 -0.4200582206 2623 1311867257.9559030533 0.0608211197 0.0579507009 0.0880135372 0.0056321362 0.2025290000 984596121 0 402718720 -0.0510283858 -0.0802955702 -0.4210721254 2624 1311867257.9850780964 0.0609464757 0.0579518426 0.0880135372 0.0056314409 0.1827380000 984598913 0 402718720 -0.0508036204 -0.0812660232 -0.4226611853 2625 1311867258.0135710239 0.0606969818 0.0579528884 0.0880135372 0.0056305944 0.1825330000 984601761 0 402718720 -0.0497577712 -0.0821946189 -0.4243697524 2626 1311867258.0526609421 0.0607539266 0.0579539550 0.0880135372 0.0056299551 0.1834940000 984604833 0 402718720 -0.0483437479 -0.0834313184 -0.4258730114 2627 1311867258.0836610794 0.0609877966 0.0579551099 0.0880135372 0.0056306129 0.1832550000 984607681 0 402718720 -0.0489283763 -0.0838671401 -0.4272157848 2628 1311867258.1137859821 0.0606882796 0.0579561499 0.0880135372 0.0056299646 0.1911630000 984610585 0 402718720 -0.0482067987 -0.0847071335 -0.4288397729 2629 1311867258.1501069069 0.0609095283 0.0579572733 0.0880135372 0.0056311560 0.1818310000 984613545 0 402718720 -0.0481215008 -0.0845276341 -0.4304163456 2630 1311867258.1848480701 0.0615987591 0.0579586579 0.0880135372 0.0056302636 0.1817260000 984616505 0 402718720 -0.0480275750 -0.0851562172 -0.4314372838 2631 1311867258.2162730694 0.0624075681 0.0579603489 0.0880135372 0.0056292080 0.2035770000 984619465 0 402718720 -0.0489122309 -0.0865631402 -0.4329125881 2632 1311867258.2524979115 0.0617093369 0.0579617733 0.0880135372 0.0056305839 0.1835210000 984622481 0 402718720 -0.0478179641 -0.0867039636 -0.4343467355 2633 1311867258.2857830524 0.0612614900 0.0579630265 0.0880135372 0.0056298048 0.2107880000 984625385 0 402718720 -0.0471789390 -0.0872937068 -0.4353526533 2634 1311867258.3132910728 0.0613018423 0.0579642941 0.0880135372 0.0056289046 0.1825880000 984628233 0 402718720 -0.0463777594 -0.0883016735 -0.4359640181 2635 1311867258.3510708809 0.0614467524 0.0579656157 0.0880135372 0.0056300335 0.2287080000 984631249 0 402718720 -0.0449716784 -0.0889658928 -0.4365455806 2636 1311867258.3812119961 0.0612547733 0.0579668635 0.0880135372 0.0056291562 0.2063010000 984634041 0 402718720 -0.0454576500 -0.0894496217 -0.4375314415 2637 1311867258.4142711163 0.0613204613 0.0579681352 0.0880135372 0.0056282057 0.1823910000 984636945 0 402718720 -0.0457946546 -0.0899073109 -0.4384731948 2638 1311867258.4507009983 0.0608247146 0.0579692181 0.0880135372 0.0056284043 0.2032760000 984640017 0 402718720 -0.0456435122 -0.0896688178 -0.4394743145 2639 1311867258.4826059341 0.0615485795 0.0579705744 0.0880135372 0.0056278886 0.1839900000 984642977 0 402718720 -0.0468950309 -0.0909014121 -0.4403555095 2640 1311867258.5139899254 0.0630628467 0.0579725033 0.0880135372 0.0056280021 0.1833930000 984645825 0 402718720 -0.0474918596 -0.0924206749 -0.4412983656 2641 1311867258.5500509739 0.0619327463 0.0579740028 0.0880135372 0.0056391573 0.1840100000 984648841 0 402718720 -0.0469409041 -0.0931850374 -0.4426088631 2642 1311867258.5836040974 0.0620991737 0.0579755642 0.0880135372 0.0056452561 0.1960630000 984651745 0 402718720 -0.0453405716 -0.0935394019 -0.4438309669 2643 1311867258.6141679287 0.0620394647 0.0579771018 0.0880135372 0.0056456737 0.1929920000 984654593 0 402718720 -0.0456993356 -0.0939719751 -0.4454926252 2644 1311867258.6506860256 0.0625351071 0.0579788257 0.0880135372 0.0056457373 0.1830020000 984657609 0 402718720 -0.0461054705 -0.0940619633 -0.4475151896 2645 1311867258.6856470108 0.0625946298 0.0579805708 0.0880135372 0.0056457529 0.1833170000 984660625 0 402718720 -0.0451825820 -0.0954093188 -0.4494738877 2646 1311867258.7134239674 0.0629763603 0.0579824589 0.0880135372 0.0056448378 0.1810040000 984663361 0 402718720 -0.0448696390 -0.0976515189 -0.4516626894 2647 1311867258.7543559074 0.0638987944 0.0579846940 0.0880135372 0.0056460991 0.1811150000 984666489 0 402718720 -0.0454158410 -0.0975858867 -0.4536565542 2648 1311867258.7843589783 0.0623641051 0.0579863478 0.0880135372 0.0056465535 0.1984550000 984669337 0 402718720 -0.0436640307 -0.0978142545 -0.4551453888 2649 1311867258.8193690777 0.0622380376 0.0579879529 0.0880135372 0.0056457606 0.1812900000 984672353 0 402718720 -0.0431179106 -0.0992180482 -0.4570361376 2650 1311867258.8514409065 0.0621473007 0.0579895224 0.0880135372 0.0056447933 0.1823730000 984675313 0 402718720 -0.0428339280 -0.1001708210 -0.4589689076 2651 1311867258.8846011162 0.0627447665 0.0579913162 0.0880135372 0.0056443946 0.1829420000 984678161 0 402718720 -0.0426611230 -0.1003704444 -0.4604797661 2652 1311867258.9178969860 0.0635523871 0.0579934131 0.0880135372 0.0056433806 0.1825290000 984681121 0 402718720 -0.0430964753 -0.1011674628 -0.4622297585 2653 1311867258.9506199360 0.0634452477 0.0579954681 0.0880135372 0.0056435236 0.1924070000 984684025 0 402718720 -0.0423798524 -0.1022011042 -0.4641095698 2654 1311867258.9841670990 0.0628317073 0.0579972903 0.0880135372 0.0056438243 0.1824350000 984687041 0 402718720 -0.0400197692 -0.1025562510 -0.4661186039 2655 1311867259.0194389820 0.0630657896 0.0579991994 0.0880135372 0.0056429973 0.1874070000 984689945 0 402718720 -0.0388342589 -0.1037526429 -0.4683887064 2656 1311867259.0497961044 0.0640219375 0.0580014670 0.0880135372 0.0056455733 0.2237020000 984692849 0 402718720 -0.0382913053 -0.1053357944 -0.4706435502 2657 1311867259.0845470428 0.0641397238 0.0580037772 0.0880135372 0.0056458140 0.2231990000 984695753 0 402718720 -0.0371911675 -0.1047902182 -0.4729709327 2658 1311867259.1189930439 0.0643495247 0.0580061646 0.0880135372 0.0056452981 0.2125360000 984698769 0 402718720 -0.0365875289 -0.1044367850 -0.4753076434 2659 1311867259.1506030560 0.0645458624 0.0580086241 0.0880135372 0.0056473610 0.1819480000 984701673 0 402718720 -0.0349735059 -0.1055271551 -0.4773169160 2660 1311867259.1837821007 0.0659373105 0.0580116048 0.0880135372 0.0056476936 0.1820130000 984704577 0 402718720 -0.0343932584 -0.1062770933 -0.4792302251 2661 1311867259.2191979885 0.0661645159 0.0580146686 0.0880135372 0.0056466413 0.1942940000 984707649 0 402718720 -0.0323169641 -0.1068124101 -0.4813504219 2662 1311867259.2532899380 0.0667304471 0.0580179428 0.0880135372 0.0056460007 0.2098200000 984710609 0 402718720 -0.0292711034 -0.1078188047 -0.4840107858 2663 1311867259.2815980911 0.0668699741 0.0580212668 0.0880135372 0.0056452379 0.1931450000 984713401 0 402718720 -0.0285475254 -0.1081640348 -0.4863391221 2664 1311867259.3212718964 0.0676965341 0.0580248987 0.0880135372 0.0056456970 0.1802120000 984716529 0 402718720 -0.0269319061 -0.1077060625 -0.4887427092 2665 1311867259.3519039154 0.0667175651 0.0580281605 0.0880135372 0.0056450797 0.1797530000 984719433 0 402718720 -0.0244505405 -0.1076733023 -0.4919353724 2666 1311867259.3840188980 0.0673202276 0.0580316459 0.0880135372 0.0056441707 0.1795680000 984722281 0 402718720 -0.0236667935 -0.1087897494 -0.4951100647 2667 1311867259.4204289913 0.0677563995 0.0580352922 0.0880135372 0.0056451264 0.1774030000 984725297 0 402718720 -0.0235803258 -0.1086700335 -0.4982979596 2668 1311867259.4579179287 0.0677266344 0.0580389246 0.0880135372 0.0056441620 0.1866140000 984728369 0 402718720 -0.0221528988 -0.1077245697 -0.5011000633 2669 1311867259.4850549698 0.0672353059 0.0580423703 0.0880135372 0.0056452713 0.1770080000 984731049 0 402718720 -0.0206356421 -0.1089376882 -0.5036823153 2670 1311867259.5189819336 0.0671662912 0.0580457875 0.0880135372 0.0056444256 0.1732960000 984734009 0 402718720 -0.0184040498 -0.1105328873 -0.5065684915 2671 1311867259.5505928993 0.0673215166 0.0580492602 0.0880135372 0.0056436818 0.1742810000 984736913 0 402718720 -0.0172057413 -0.1115126610 -0.5096927881 2672 1311867259.5823240280 0.0669417381 0.0580525883 0.0880135372 0.0056431791 0.1738710000 984739873 0 402718720 -0.0148141878 -0.1124434993 -0.5125083923 2673 1311867259.6192719936 0.0660355687 0.0580555748 0.0880135372 0.0056436140 0.1899940000 984742833 0 402718720 -0.0066995746 -0.1138684973 -0.5142360926 2674 1311867259.6494839191 0.0649955347 0.0580581701 0.0880135372 0.0056429008 0.1732350000 984745625 0 402718720 -0.0061573717 -0.1130977273 -0.5177559853 2675 1311867259.6828589439 0.0645026416 0.0580605793 0.0880135372 0.0056437839 0.1729810000 984748585 0 402718720 -0.0054280129 -0.1119063199 -0.5211125016 2676 1311867259.7201991081 0.0627901480 0.0580623467 0.0880135372 0.0056428343 0.1766890000 984751657 0 402718720 -0.0032664877 -0.1093734801 -0.5242112279 2677 1311867259.7557690144 0.0641853660 0.0580646339 0.0880135372 0.0056422816 0.1754880000 984754673 0 402718720 -0.0045930170 -0.1118907407 -0.5267791748 2678 1311867259.7817859650 0.0646977797 0.0580671108 0.0880135372 0.0056413598 0.1885790000 984757409 0 402718720 -0.0059519270 -0.1120370179 -0.5292530060 2679 1311867259.8177011013 0.0624770857 0.0580687570 0.0880135372 0.0056406145 0.1798060000 984760425 0 402718720 -0.0011109037 -0.1100725606 -0.5314736962 2680 1311867259.8548939228 0.0646314621 0.0580712057 0.0880135372 0.0056404201 0.1772840000 984763441 0 402718720 -0.0029047481 -0.1115722582 -0.5337894559 2681 1311867259.8818409443 0.0631846637 0.0580731130 0.0880135372 0.0056397454 0.1810510000 984766233 0 402718720 0.0004594814 -0.1110208929 -0.5357450843 2682 1311867259.9219179153 0.0641575679 0.0580753817 0.0880135372 0.0056391152 0.1780880000 984769361 0 402718720 -0.0009722293 -0.1108882502 -0.5383924842 2683 1311867259.9520130157 0.0621744357 0.0580769095 0.0880135372 0.0056383074 0.1912520000 984772209 0 402718720 0.0034767024 -0.1087244526 -0.5406877995 2684 1311867259.9923639297 0.0641960204 0.0580791893 0.0880135372 0.0056382911 0.1804880000 984775337 0 402718720 0.0033737239 -0.1107366309 -0.5426239967 2685 1311867260.0219469070 0.0650869831 0.0580817993 0.0880135372 0.0056379039 0.1793530000 984778129 0 402718720 0.0028180652 -0.1106333733 -0.5446320772 2686 1311867260.0493209362 0.0631510466 0.0580836866 0.0880135372 0.0056378960 0.1823780000 984780865 0 402718720 0.0085674236 -0.1085970923 -0.5464307666 2687 1311867260.0888080597 0.0647805333 0.0580861789 0.0880135372 0.0056375536 0.1812330000 984783993 0 402718720 0.0086024860 -0.1097112149 -0.5488858223 2688 1311867260.1210498810 0.0647514164 0.0580886585 0.0880135372 0.0056386234 0.1940600000 984786897 0 402718720 0.0126919067 -0.1088386476 -0.5513039231 2689 1311867260.1513869762 0.0652281642 0.0580913136 0.0880135372 0.0056396754 0.1920510000 984789745 0 402718720 0.0124627929 -0.1092357412 -0.5540115833 2690 1311867260.1908860207 0.0665398911 0.0580944543 0.0880135372 0.0056389213 0.2031980000 984792817 0 402718720 0.0149833439 -0.1091942340 -0.5565760136 2691 1311867260.2204439640 0.0664390698 0.0580975553 0.0880135372 0.0056383081 0.1814150000 984795665 0 402718720 0.0140415505 -0.1085019633 -0.5599614382 2692 1311867260.2496669292 0.0671540797 0.0581009195 0.0880135372 0.0056376156 0.1822080000 984798569 0 402718720 0.0133905634 -0.1083248034 -0.5630373955 2693 1311867260.2869880199 0.0674874187 0.0581044050 0.0880135372 0.0056376359 0.1819460000 984801585 0 402718720 0.0141852722 -0.1069246307 -0.5661457181 2694 1311867260.3195590973 0.0672474429 0.0581077989 0.0880135372 0.0056369514 0.1828050000 984804489 0 402718720 0.0148366326 -0.1062970459 -0.5692494512 2695 1311867260.3505260944 0.0677086785 0.0581113613 0.0880135372 0.0056374523 0.1820840000 984807393 0 402718720 0.0148808537 -0.1063816920 -0.5723164082 2696 1311867260.3868899345 0.0684622377 0.0581152007 0.0880135372 0.0056407664 0.1822220000 984810409 0 402718720 0.0129531529 -0.1042860001 -0.5753331780 2697 1311867260.4211299419 0.0680045411 0.0581188675 0.0880135372 0.0056399031 0.2236600000 984813313 0 402718720 0.0140022272 -0.1030460745 -0.5783050060 2698 1311867260.4521770477 0.0664207637 0.0581219445 0.0880135372 0.0056389910 0.1876960000 984816161 0 402718720 0.0185454264 -0.1010179967 -0.5806885362 2699 1311867260.4867470264 0.0681786910 0.0581256706 0.0880135372 0.0056406725 0.1854480000 984819121 0 402718720 0.0151644116 -0.1024220288 -0.5838059187 2700 1311867260.5192930698 0.0678265616 0.0581292636 0.0880135372 0.0056424867 0.1859800000 984821913 0 402718720 0.0177167561 -0.1009222344 -0.5861315727 2701 1311867260.5527870655 0.0663945824 0.0581323237 0.0880135372 0.0056418850 0.1899070000 984824929 0 402718720 0.0191699956 -0.0970021337 -0.5889108181 2702 1311867260.5880448818 0.0686944276 0.0581362326 0.0880135372 0.0056414588 0.1868780000 984827945 0 402718720 0.0178929549 -0.0993505716 -0.5917149186 2703 1311867260.6196188927 0.0682042912 0.0581399574 0.0880135372 0.0056409969 0.1980080000 984830849 0 402718720 0.0200570635 -0.0997956172 -0.5946021080 2704 1311867260.6493411064 0.0680578947 0.0581436253 0.0880135372 0.0056401920 0.1886820000 984833641 0 402718720 0.0217211321 -0.1005140170 -0.5973123908 2705 1311867260.6865339279 0.0699451938 0.0581479882 0.0880135372 0.0056411650 0.1886970000 984836713 0 402718720 0.0219855197 -0.1017629802 -0.5997897983 2706 1311867260.7188229561 0.0695142150 0.0581521885 0.0880135372 0.0056414886 0.1996610000 984839617 0 402718720 0.0230972357 -0.1025653630 -0.6030427814 2707 1311867260.7493369579 0.0691469237 0.0581562501 0.0880135372 0.0056432817 0.1896890000 984842409 0 402718720 0.0235631727 -0.1022837535 -0.6055659652 2708 1311867260.7859649658 0.0691980049 0.0581603276 0.0880135372 0.0056451109 0.2104110000 984845481 0 402718720 0.0266020410 -0.1040568352 -0.6079012156 2709 1311867260.8179080486 0.0697494298 0.0581646056 0.0880135372 0.0056471466 0.1888100000 984848441 0 402718720 0.0251448303 -0.1045996100 -0.6117233634 2710 1311867260.8514599800 0.0690030083 0.0581686050 0.0880135372 0.0056517443 0.1993460000 984851345 0 402718720 0.0275136083 -0.1052970290 -0.6148214936 2711 1311867260.8867430687 0.0699342117 0.0581729450 0.0880135372 0.0056516043 0.1878200000 984854249 0 402718720 0.0260531176 -0.1063566208 -0.6185032725 2712 1311867260.9177849293 0.0699280202 0.0581772794 0.0880135372 0.0056510325 0.1873910000 984857153 0 402718720 0.0264683478 -0.1066503450 -0.6212493181 2713 1311867260.9494459629 0.0688690022 0.0581812204 0.0880135372 0.0056634562 0.1885940000 984860057 0 402718720 0.0255938563 -0.1071156189 -0.6245525479 2714 1311867260.9869680405 0.0708266124 0.0581858797 0.0880135372 0.0056737786 0.1883870000 984863129 0 402718720 0.0258949790 -0.1083298102 -0.6281319857 2715 1311867261.0202260017 0.0716652200 0.0581908444 0.0880135372 0.0056741658 0.1870470000 984866033 0 402718720 0.0242318548 -0.1092909276 -0.6313811541 2716 1311867261.0519640446 0.0717088208 0.0581958216 0.0880135372 0.0056745269 0.1866430000 984868937 0 402718720 0.0237613805 -0.1107218340 -0.6343711615 2717 1311867261.0871579647 0.0720154420 0.0582009080 0.0880135372 0.0056739833 0.2231530000 984871953 0 402718720 0.0273492970 -0.1134511754 -0.6369555593 2718 1311867261.1197659969 0.0732245594 0.0582064354 0.0880135372 0.0056741124 0.1849990000 984874857 0 402718720 0.0233891867 -0.1157469675 -0.6404432058 2719 1311867261.1530790329 0.0728474408 0.0582118201 0.0880135372 0.0056754953 0.1837170000 984877817 0 402718720 0.0228095427 -0.1160370559 -0.6434892416 2720 1311867261.1872630119 0.0730875582 0.0582172891 0.0880135372 0.0056775938 0.1813980000 984880777 0 402718720 0.0228004623 -0.1177570298 -0.6467579007 2721 1311867261.2191090584 0.0738479048 0.0582230336 0.0880135372 0.0056831779 0.1920740000 984883681 0 402718720 0.0218048654 -0.1204634309 -0.6495282054 2722 1311867261.2548229694 0.0750800893 0.0582292265 0.0880135372 0.0056829344 0.1884620000 984886641 0 402718720 0.0195473507 -0.1211880371 -0.6527241468 2723 1311867261.2879600525 0.0747819319 0.0582353053 0.0880135372 0.0056824213 0.1783060000 984889657 0 402718720 0.0206975490 -0.1217566952 -0.6552022099 2724 1311867261.3185029030 0.0756146684 0.0582416854 0.0880135372 0.0056869971 0.1899220000 984892561 0 402718720 0.0192167666 -0.1222804710 -0.6575375795 2725 1311867261.3546299934 0.0759385005 0.0582481797 0.0880135372 0.0056871818 0.1821610000 984895521 0 402718720 0.0159388445 -0.1214073226 -0.6602970362 2726 1311867261.3858330250 0.0754889771 0.0582545042 0.0880135372 0.0056861995 0.1816750000 984898369 0 402718720 0.0151485782 -0.1208340973 -0.6624068022 2727 1311867261.4186379910 0.0750932992 0.0582606791 0.0880135372 0.0056854451 0.1781630000 984901273 0 402718720 0.0161800627 -0.1216344237 -0.6640020013 2728 1311867261.4558680058 0.0749624819 0.0582668014 0.0880135372 0.0056861765 0.2049150000 984904345 0 402718720 0.0140587157 -0.1224652305 -0.6658881903 2729 1311867261.4862189293 0.0760040730 0.0582733010 0.0880135372 0.0056880520 0.1801570000 984907193 0 402718720 0.0139075583 -0.1231113374 -0.6675642133 2730 1311867261.5178630352 0.0759751126 0.0582797852 0.0880135372 0.0056876681 0.1807110000 984910153 0 402718720 0.0122151598 -0.1228313148 -0.6690503359 2731 1311867261.5556519032 0.0753428042 0.0582860331 0.0880135372 0.0056866980 0.1817480000 984913169 0 402718720 0.0136326607 -0.1222276464 -0.6702578664 2732 1311867261.5857899189 0.0771861970 0.0582929511 0.0880135372 0.0056889398 0.1820030000 984916017 0 402718720 0.0112683307 -0.1235975921 -0.6718536019 2733 1311867261.6174640656 0.0774467140 0.0582999595 0.0880135372 0.0056885421 0.1919020000 984918977 0 402718720 0.0105430987 -0.1224712878 -0.6735785604 2734 1311867261.6652009487 0.0784977823 0.0583073471 0.0880135372 0.0056886426 0.1825110000 984922273 0 402718720 0.0087142540 -0.1220069006 -0.6761825085 2735 1311867261.6889929771 0.0783878192 0.0583146891 0.0880135372 0.0056878217 0.1819730000 984924953 0 402718720 0.0085407486 -0.1222632304 -0.6790364385 2736 1311867261.7193109989 0.0803114325 0.0583227289 0.0880135372 0.0056886470 0.1809910000 984927745 0 402718720 0.0014149118 -0.1203091741 -0.6828165054 2737 1311867261.7601549625 0.0807915106 0.0583309382 0.0880135372 0.0056912282 0.1798180000 984930817 0 402718720 0.0021970039 -0.1192485839 -0.6857889295 2738 1311867261.7876880169 0.0804935843 0.0583390326 0.0880135372 0.0056927721 0.2032680000 984933609 0 402718720 0.0001424985 -0.1175261736 -0.6891623139 2739 1311867261.8213939667 0.0802305043 0.0583470251 0.0880135372 0.0056978901 0.1829810000 984936569 0 402718720 0.0004378447 -0.1161672398 -0.6925595999 2740 1311867261.8598148823 0.0817710385 0.0583555740 0.0880135372 0.0056977597 0.1832710000 984939585 0 402718720 -0.0013656992 -0.1154308841 -0.6954827905 2741 1311867261.8885459900 0.0802249759 0.0583635527 0.0880135372 0.0057021283 0.1826160000 984942433 0 402718720 0.0010910199 -0.1139795408 -0.6976518035 2742 1311867261.9212360382 0.0802947581 0.0583715509 0.0880135372 0.0057058197 0.1835150000 984945337 0 402718720 0.0017803727 -0.1132859886 -0.7009301782 2743 1311867261.9592299461 0.0807494968 0.0583797091 0.0880135372 0.0057048905 0.1944140000 984948465 0 402718720 0.0010177039 -0.1116997302 -0.7041308284 2744 1311867261.9886140823 0.0785145760 0.0583870469 0.0880135372 0.0057047768 0.2101170000 984951257 0 402718720 0.0057321750 -0.1089385077 -0.7064986229 2745 1311867262.0219531059 0.0793246999 0.0583946745 0.0880135372 0.0057045481 0.1862180000 984954217 0 402718720 0.0060719354 -0.1096433923 -0.7091876864 2746 1311867262.0576629639 0.0804786906 0.0584027167 0.0880135372 0.0057037190 0.1860770000 984957233 0 402718720 0.0046191392 -0.1086859554 -0.7124398947 2747 1311867262.0944681168 0.0812276006 0.0584110257 0.0880135372 0.0057027415 0.1989100000 984960193 0 402718720 0.0059806891 -0.1081854850 -0.7151325941 2748 1311867262.1180479527 0.0803149119 0.0584189966 0.0880135372 0.0057018609 0.2130720000 984962873 0 402718720 0.0061703050 -0.1067458391 -0.7181196213 2749 1311867262.1539878845 0.0811802298 0.0584272764 0.0880135372 0.0057023719 0.1883820000 984965889 0 402718720 0.0066990592 -0.1067812666 -0.7213034630 2750 1311867262.1906540394 0.0812853873 0.0584355884 0.0880135372 0.0057014437 0.1880000000 984968849 0 402718720 0.0080402698 -0.1057458371 -0.7250665426 2751 1311867262.2200620174 0.0823147073 0.0584442686 0.0880135372 0.0057009184 0.1878100000 984971753 0 402718720 0.0059263292 -0.1046576947 -0.7286602855 2752 1311867262.2557590008 0.0824310184 0.0584529847 0.0880135372 0.0057000657 0.1876160000 984974713 0 402718720 0.0090723671 -0.1039087176 -0.7314495444 2753 1311867262.2893559933 0.0842953995 0.0584623717 0.0880135372 0.0057017513 0.2128710000 984977673 0 402718720 0.0043136450 -0.1026617587 -0.7356146574 2754 1311867262.3192830086 0.0852164403 0.0584720863 0.0880135372 0.0057007704 0.1883240000 984980577 0 402718720 0.0020536969 -0.1018810645 -0.7401908636 2755 1311867262.3543510437 0.0862931162 0.0584821847 0.0880135372 0.0057045810 0.1873320000 984983537 0 402718720 0.0029828779 -0.1005027816 -0.7442218661 2756 1311867262.3862760067 0.0852701962 0.0584919046 0.0880135372 0.0057036531 0.1876990000 984986385 0 402718720 0.0040839673 -0.0987156257 -0.7486244440 2757 1311867262.4192481041 0.0870371908 0.0585022584 0.0880135372 0.0057029049 0.2279170000 984989345 0 402718720 -0.0002837296 -0.0972393602 -0.7539922595 2758 1311867262.4579370022 0.0886151269 0.0585131767 0.0886151269 0.0057027217 0.1886940000 984992417 0 402718720 -0.0012684880 -0.0950694084 -0.7584136724 2759 1311867262.4882910252 0.0886830166 0.0585241118 0.0886830166 0.0057055316 0.1862940000 984995321 0 402718720 -0.0043762866 -0.0931662396 -0.7638266087 2760 1311867262.5228719711 0.0901561081 0.0585355727 0.0901561081 0.0057048240 0.1873960000 984998281 0 402718720 -0.0068484233 -0.0923755392 -0.7690128684 2761 1311867262.5554070473 0.0919963941 0.0585476918 0.0919963941 0.0057049840 0.1864910000 985001185 0 402718720 -0.0111041358 -0.0898050368 -0.7738546133 2762 1311867262.5873200893 0.0922839195 0.0585599062 0.0922839195 0.0057156034 0.1859150000 985004145 0 402718720 -0.0111405561 -0.0885489732 -0.7782699466 2763 1311867262.6235508919 0.0938153192 0.0585726660 0.0938153192 0.0057177818 0.1856680000 985007161 0 402718720 -0.0130766667 -0.0875406414 -0.7820692658 2764 1311867262.6548008919 0.0927663818 0.0585850371 0.0938153192 0.0057174149 0.1859870000 985010009 0 402718720 -0.0116651170 -0.0870825797 -0.7858459949 2765 1311867262.6901140213 0.0942155048 0.0585979233 0.0942155048 0.0057192332 0.1979430000 985012969 0 402718720 -0.0140195414 -0.0855439529 -0.7896105051 2766 1311867262.7234799862 0.0912853330 0.0586097409 0.0942155048 0.0057188137 0.1866970000 985015929 0 402718720 -0.0081671644 -0.0859974474 -0.7930778861 2767 1311867262.7550880909 0.0903649479 0.0586212173 0.0942155048 0.0057249533 0.1865740000 985018833 0 402718720 -0.0065603987 -0.0863467529 -0.7963392138 2768 1311867262.7890789509 0.0921862945 0.0586333434 0.0942155048 0.0057265963 0.2006860000 985021737 0 402718720 -0.0083066700 -0.0861107633 -0.7997497916 2769 1311867262.8232269287 0.0951013342 0.0586465135 0.0951013342 0.0057278170 0.1860460000 985024809 0 402718720 -0.0092545329 -0.0862118304 -0.8020316362 2770 1311867262.8561139107 0.0955482125 0.0586598354 0.0955482125 0.0057289052 0.2178520000 985027657 0 402718720 -0.0107024685 -0.0858426839 -0.8052176237 2771 1311867262.8878281116 0.0964858234 0.0586734861 0.0964858234 0.0057288177 0.1865680000 985030561 0 402718720 -0.0099123260 -0.0870487392 -0.8077721596 2772 1311867262.9221930504 0.0958892182 0.0586869117 0.0964858234 0.0057295122 0.1868590000 985033577 0 402718720 -0.0076949722 -0.0865316987 -0.8100435138 2773 1311867262.9539968967 0.0980770886 0.0587011166 0.0980770886 0.0057309682 0.1969740000 985036481 0 402718720 -0.0081835240 -0.0869082510 -0.8120722175 2774 1311867262.9877319336 0.0978763923 0.0587152389 0.0980770886 0.0057326088 0.1848780000 985039441 0 402718720 -0.0080032954 -0.0865409896 -0.8144167662 2775 1311867263.0238440037 0.0992067382 0.0587298304 0.0992067382 0.0057317891 0.1839290000 985042457 0 402718720 -0.0082029328 -0.0869448707 -0.8169507384 2776 1311867263.0552799702 0.1004079357 0.0587448442 0.1004079357 0.0057308950 0.1842970000 985045305 0 402718720 -0.0089441398 -0.0875591263 -0.8192135096 2777 1311867263.0870039463 0.1003336683 0.0587598203 0.1004079357 0.0057299373 0.1827420000 985048209 0 402718720 -0.0076142484 -0.0869822949 -0.8213780522 2778 1311867263.1226899624 0.1005071402 0.0587748482 0.1005071402 0.0057291998 0.1957530000 985051225 0 402718720 -0.0077046701 -0.0864284635 -0.8239587545 2779 1311867263.1537079811 0.1004261300 0.0587898360 0.1005071402 0.0057324584 0.1815430000 985054073 0 402718720 -0.0079240249 -0.0858591646 -0.8265887499 2780 1311867263.1884229183 0.0996389613 0.0588045300 0.1005071402 0.0057317945 0.1811980000 985057033 0 402718720 -0.0075371685 -0.0844537020 -0.8288591504 2781 1311867263.2225809097 0.0984205902 0.0588187752 0.1005071402 0.0057310229 0.1807660000 985060049 0 402718720 -0.0059210374 -0.0842780471 -0.8312095404 2782 1311867263.2536139488 0.0985257179 0.0588330480 0.1005071402 0.0057310148 0.1811820000 985062897 0 402718720 -0.0067699673 -0.0850008577 -0.8339402080 2783 1311867263.2884469032 0.0981478542 0.0588471748 0.1005071402 0.0057302774 0.1918280000 985065857 0 402718720 -0.0061019370 -0.0851136968 -0.8362897038 2784 1311867263.3236269951 0.0985609144 0.0588614398 0.1005071402 0.0057511189 0.1826440000 985068873 0 402718720 -0.0067924084 -0.0847177058 -0.8385920525 2785 1311867263.3539469242 0.0969819725 0.0588751276 0.1005071402 0.0057524460 0.1822540000 985071721 0 402718720 -0.0034237423 -0.0857123211 -0.8404181600 2786 1311867263.3856530190 0.0988144204 0.0588894633 0.1005071402 0.0057515241 0.1809580000 985074625 0 402718720 -0.0071102781 -0.0854952410 -0.8431766629 2787 1311867263.4221460819 0.1004292145 0.0589043681 0.1005071402 0.0057510824 0.1805270000 985077641 0 402718720 -0.0103296340 -0.0837536529 -0.8458032608 2788 1311867263.4549560547 0.1010610759 0.0589194889 0.1010610759 0.0057503953 0.1943600000 985080489 0 402718720 -0.0093716290 -0.0841883048 -0.8481118083 2789 1311867263.4876389503 0.0999147296 0.0589341878 0.1010610759 0.0057505067 0.1807480000 985083505 0 402718720 -0.0059164916 -0.0848142877 -0.8503497243 2790 1311867263.5235950947 0.0997911990 0.0589488319 0.1010610759 0.0057539290 0.1798940000 985086577 0 402718720 -0.0062230490 -0.0841903687 -0.8532891870 2791 1311867263.5535099506 0.1005934849 0.0589637529 0.1010610759 0.0057539560 0.1814560000 985089369 0 402718720 -0.0049697249 -0.0852841586 -0.8561364412 2792 1311867263.5855040550 0.1004942358 0.0589786278 0.1010610759 0.0057534383 0.1811030000 985092217 0 402718720 -0.0032388242 -0.0856512114 -0.8585350513 2793 1311867263.6236140728 0.1002102122 0.0589933902 0.1010610759 0.0057556669 0.1902950000 985095345 0 402718720 -0.0000248985 -0.0851510614 -0.8615624309 2794 1311867263.6543920040 0.1009532660 0.0590084081 0.1010610759 0.0057554662 0.1812820000 985098137 0 402718720 0.0001950752 -0.0856143832 -0.8646126986 2795 1311867263.6903779507 0.1017010063 0.0590236827 0.1017010063 0.0057545839 0.1807270000 985101209 0 402718720 0.0015595156 -0.0856984034 -0.8675757647 2796 1311867263.7227630615 0.1011357754 0.0590387443 0.1017010063 0.0057560971 0.1801980000 985104113 0 402718720 0.0038841930 -0.0849327669 -0.8709228635 2797 1311867263.7559669018 0.1003307179 0.0590535072 0.1017010063 0.0057559409 0.1800220000 985107017 0 402718720 0.0057362067 -0.0844381303 -0.8746829033 2798 1311867263.7911560535 0.1011387035 0.0590685484 0.1017010063 0.0057568970 0.2137000000 985109977 0 402718720 0.0066474280 -0.0837896466 -0.8780819774 2799 1311867263.8235189915 0.1014309525 0.0590836832 0.1017010063 0.0057559999 0.1817650000 985112937 0 402718720 0.0078470148 -0.0838097259 -0.8814415932 2800 1311867263.8555519581 0.0994067937 0.0590980843 0.1017010063 0.0057556636 0.1820720000 985115785 0 402718720 0.0132235819 -0.0829807594 -0.8838309646 2801 1311867263.8925390244 0.1025245041 0.0591135882 0.1025245041 0.0057548371 0.1813290000 985118857 0 402718720 0.0097605372 -0.0831157640 -0.8874771595 2802 1311867263.9255890846 0.1015577465 0.0591287360 0.1025245041 0.0057541469 0.1804630000 985121761 0 402718720 0.0134523157 -0.0827485621 -0.8897835612 2803 1311867263.9557209015 0.1016984433 0.0591439232 0.1025245041 0.0057533662 0.1817490000 985124609 0 402718720 0.0143983075 -0.0826290175 -0.8925942779 2804 1311867263.9913449287 0.1016400158 0.0591590788 0.1025245041 0.0057528518 0.1824070000 985127625 0 402718720 0.0160969384 -0.0823236555 -0.8950715661 2805 1311867264.0265080929 0.1037433594 0.0591749733 0.1037433594 0.0057521897 0.1816020000 985130641 0 402718720 0.0150810154 -0.0833632797 -0.8977121711 2806 1311867264.0539839268 0.1034281999 0.0591907443 0.1037433594 0.0057516303 0.1813200000 985133433 0 402718720 0.0169029702 -0.0834538341 -0.8997265100 2807 1311867264.0935840607 0.1047885790 0.0592069886 0.1047885790 0.0057506772 0.1825850000 985136561 0 402718720 0.0176774412 -0.0836006477 -0.9014763832 2808 1311867264.1232929230 0.1054375470 0.0592234525 0.1054375470 0.0057499272 0.2012890000 985139409 0 402718720 0.0169989299 -0.0828312561 -0.9038621187 2809 1311867264.1547811031 0.1040490270 0.0592394103 0.1054375470 0.0057505030 0.1842240000 985142201 0 402718720 0.0200968310 -0.0826632679 -0.9056975245 2810 1311867264.1908740997 0.1032422408 0.0592550697 0.1054375470 0.0057508111 0.1850530000 985145217 0 402718720 0.0243133195 -0.0822061300 -0.9081599116 2811 1311867264.2230439186 0.1040554717 0.0592710072 0.1054375470 0.0057523253 0.1845020000 985148177 0 402718720 0.0219976995 -0.0821571201 -0.9115527272 2812 1311867264.2549281120 0.1032532677 0.0592866481 0.1054375470 0.0057542202 0.1845920000 985151025 0 402718720 0.0240641218 -0.0808594152 -0.9136986136 2813 1311867264.2910940647 0.1026235148 0.0593020540 0.1054375470 0.0057601897 0.1842020000 985154041 0 402718720 0.0267068334 -0.0795764327 -0.9165437222 2814 1311867264.3223540783 0.1031808928 0.0593176471 0.1054375470 0.0057634751 0.1831210000 985156945 0 402718720 0.0284857098 -0.0798043907 -0.9194281697 2815 1311867264.3539710045 0.1020041406 0.0593328110 0.1054375470 0.0057683326 0.1832660000 985159793 0 402718720 0.0284071192 -0.0793182477 -0.9220468402 2816 1311867264.3903570175 0.1015581787 0.0593478058 0.1054375470 0.0057704445 0.1959660000 985162809 0 402718720 0.0313861966 -0.0787844211 -0.9241929650 2817 1311867264.4247128963 0.1004153118 0.0593623843 0.1054375470 0.0057755748 0.1821310000 985165825 0 402718720 0.0331450589 -0.0797025040 -0.9272068143 2818 1311867264.4536709785 0.0993033722 0.0593765578 0.1054375470 0.0057763740 0.2299350000 985168617 0 402718720 0.0345039070 -0.0791722611 -0.9294797778 2819 1311867264.4911220074 0.0977159292 0.0593901582 0.1054375470 0.0057757647 0.2010590000 985171689 0 402718720 0.0381709673 -0.0785870478 -0.9314321280 2820 1311867264.5220930576 0.0966699123 0.0594033779 0.1054375470 0.0057756089 0.1831290000 985174537 0 402718720 0.0394481458 -0.0780917257 -0.9340968728 2821 1311867264.5544660091 0.0964113176 0.0594164967 0.1054375470 0.0057760629 0.1831860000 985177441 0 402718720 0.0422688350 -0.0782837570 -0.9355802536 2822 1311867264.5919189453 0.0945401192 0.0594289430 0.1054375470 0.0057775914 0.1828490000 985180513 0 402718720 0.0458117351 -0.0771597624 -0.9375904799 2823 1311867264.6239540577 0.0943559483 0.0594413153 0.1054375470 0.0057789695 0.1945300000 985183417 0 402718720 0.0483274199 -0.0783035755 -0.9393212795 2824 1311867264.6537890434 0.0944275260 0.0594537042 0.1054375470 0.0057790822 0.1825720000 985186321 0 402718720 0.0504876375 -0.0794512182 -0.9409161210 2825 1311867264.6908979416 0.0942401439 0.0594660180 0.1054375470 0.0057783355 0.2001810000 985189281 0 402718720 0.0521230400 -0.0796486586 -0.9427736998 2826 1311867264.7228040695 0.0942938328 0.0594783421 0.1054375470 0.0057789799 0.1823210000 985192241 0 402718720 0.0541612953 -0.0810270682 -0.9441244006 2827 1311867264.7547140121 0.0949095413 0.0594908752 0.1054375470 0.0057785320 0.1828710000 985195089 0 402718720 0.0557660237 -0.0820633620 -0.9452315569 2828 1311867264.7909140587 0.0942462459 0.0595031649 0.1054375470 0.0057780483 0.2010420000 985198105 0 402718720 0.0588276349 -0.0821101665 -0.9463992715 2829 1311867264.8233439922 0.0935110301 0.0595151861 0.1054375470 0.0057782635 0.1832460000 985201065 0 402718720 0.0618342943 -0.0828106999 -0.9480071664 2830 1311867264.8540790081 0.0927934498 0.0595269452 0.1054375470 0.0057776069 0.1824200000 985203913 0 402718720 0.0620648786 -0.0824426934 -0.9497218132 2831 1311867264.8904409409 0.0928822234 0.0595387274 0.1054375470 0.0057766503 0.1934660000 985206929 0 402718720 0.0616008863 -0.0820759684 -0.9511752129 2832 1311867264.9235579967 0.0930326954 0.0595505543 0.1054375470 0.0057758588 0.1822540000 985209889 0 402718720 0.0624241121 -0.0812961832 -0.9516478777 2833 1311867264.9598839283 0.0945545658 0.0595629101 0.1054375470 0.0057749561 0.2047750000 985212905 0 402718720 0.0586246327 -0.0816566572 -0.9533489943 2834 1311867264.9916839600 0.0932686031 0.0595748035 0.1054375470 0.0057741355 0.1845450000 985215809 0 402718720 0.0596280694 -0.0801036805 -0.9542747736 2835 1311867265.0220029354 0.0936192274 0.0595868121 0.1054375470 0.0057732389 0.1836320000 985218657 0 402718720 0.0595229156 -0.0802290738 -0.9552845955 2836 1311867265.0581490993 0.0954921916 0.0595994726 0.1054375470 0.0057726643 0.1832800000 985221673 0 402718720 0.0560791828 -0.0808505863 -0.9563036561 2837 1311867265.0911719799 0.0953550264 0.0596120759 0.1054375470 0.0057720551 0.1835970000 985224521 0 402718720 0.0593552813 -0.0812676027 -0.9570648670 2838 1311867265.1217110157 0.0958048776 0.0596248289 0.1054375470 0.0057721666 0.1894020000 985227369 0 402718720 0.0588303283 -0.0807205290 -0.9581453800 2839 1311867265.1582090855 0.0965398401 0.0596378317 0.1054375470 0.0057713355 0.1838710000 985230385 0 402718720 0.0569643229 -0.0799308196 -0.9599380493 2840 1311867265.1899518967 0.0971533731 0.0596510414 0.1054375470 0.0057711797 0.1947600000 985233233 0 402718720 0.0553245842 -0.0803586692 -0.9614965916 2841 1311867265.2225220203 0.0982935131 0.0596646431 0.1054375470 0.0057715693 0.1838890000 985236193 0 402718720 0.0518240854 -0.0798587948 -0.9629988074 2842 1311867265.2581849098 0.1009595916 0.0596791733 0.1054375470 0.0057755323 0.1929350000 985239097 0 402718720 0.0465098917 -0.0793526694 -0.9653451443 2843 1311867265.2915129662 0.1022280678 0.0596941395 0.1054375470 0.0057765235 0.1811730000 985242057 0 402718720 0.0443839915 -0.0782901272 -0.9666362405 2844 1311867265.3220860958 0.1031996310 0.0597094368 0.1054375470 0.0057761588 0.1815360000 985244961 0 402718720 0.0401912816 -0.0780850872 -0.9689614177 2845 1311867265.3585588932 0.1033558398 0.0597247783 0.1054375470 0.0057753214 0.1811720000 985247977 0 402718720 0.0417238772 -0.0782031715 -0.9703444839 2846 1311867265.3912470341 0.1041633636 0.0597403927 0.1054375470 0.0057748506 0.1794050000 985250881 0 402718720 0.0394775383 -0.0773982629 -0.9720011353 2847 1311867265.4244530201 0.1050425470 0.0597563049 0.1054375470 0.0057744043 0.1789870000 985253897 0 402718720 0.0391040109 -0.0789677501 -0.9740946293 2848 1311867265.4604411125 0.1064038500 0.0597726840 0.1064038500 0.0057743404 0.1789810000 985256801 0 402718720 0.0363024101 -0.0780886263 -0.9759764671 2849 1311867265.4902420044 0.1045167074 0.0597883891 0.1064038500 0.0057734885 0.2018670000 985259705 0 402718720 0.0389422216 -0.0775167495 -0.9779526591 2850 1311867265.5230569839 0.1048705652 0.0598042074 0.1064038500 0.0057727653 0.1774620000 985262665 0 402718720 0.0385728888 -0.0778265819 -0.9800018668 2851 1311867265.5594520569 0.1077025235 0.0598210080 0.1077025235 0.0057721043 0.1878230000 985265625 0 402718720 0.0344488397 -0.0785318166 -0.9820529819 2852 1311867265.5932300091 0.1069976166 0.0598375496 0.1077025235 0.0057714407 0.1959260000 985268641 0 402718720 0.0358795486 -0.0782090053 -0.9837950468 2853 1311867265.6250700951 0.1070043519 0.0598540819 0.1077025235 0.0057705809 0.1965970000 985271433 0 402718720 0.0343146734 -0.0767294690 -0.9859379530 2854 1311867265.6610729694 0.1084311828 0.0598711026 0.1084311828 0.0057700919 0.1764050000 985274449 0 402718720 0.0330602303 -0.0767691582 -0.9877482653 2855 1311867265.6956009865 0.1085938141 0.0598881684 0.1085938141 0.0057693301 0.1768200000 985277409 0 402718720 0.0327484533 -0.0756500810 -0.9892166853 2856 1311867265.7221889496 0.1083189249 0.0599051259 0.1085938141 0.0057684147 0.1887990000 985280201 0 402718720 0.0317484885 -0.0740493536 -0.9907652736 2857 1311867265.7626268864 0.1072292924 0.0599216902 0.1085938141 0.0057687845 0.1762380000 985283329 0 402718720 0.0351934433 -0.0746710151 -0.9918964505 2858 1311867265.7925920486 0.1082883924 0.0599386135 0.1085938141 0.0057682624 0.2060460000 985286177 0 402718720 0.0347372144 -0.0756801963 -0.9928231239 2859 1311867265.8224210739 0.1095564514 0.0599559684 0.1095564514 0.0057674318 0.2216940000 985289025 0 402718720 0.0311083701 -0.0737827644 -0.9939758182 2860 1311867265.8593389988 0.1090446115 0.0599731323 0.1095564514 0.0057665885 0.1846760000 985292041 0 402718720 0.0334030651 -0.0737131089 -0.9940854311 2861 1311867265.8943600655 0.1095001549 0.0599904434 0.1095564514 0.0057656109 0.1783750000 985295001 0 402718720 0.0322857983 -0.0731396452 -0.9954506755 2862 1311867265.9256451130 0.1082033515 0.0600072893 0.1095564514 0.0057649143 0.1913010000 985297905 0 402718720 0.0356230438 -0.0728342161 -0.9957545400 2863 1311867265.9620978832 0.1079149172 0.0600240226 0.1095564514 0.0057645115 0.1938290000 985300921 0 402718720 0.0360504203 -0.0726640970 -0.9972325563 2864 1311867265.9908990860 0.1093790382 0.0600412555 0.1095564514 0.0057658803 0.1793890000 985303713 0 402718720 0.0337183848 -0.0723958611 -0.9988070726 2865 1311867266.0233469009 0.1102740169 0.0600587888 0.1102740169 0.0057649408 0.1788760000 985306673 0 402718720 0.0327929743 -0.0725983381 -1.0000194311 2866 1311867266.0634260178 0.1107261926 0.0600764676 0.1107261926 0.0057641770 0.1782720000 985309801 0 402718720 0.0319942646 -0.0721341297 -1.0016587973 2867 1311867266.0954639912 0.1118324324 0.0600945199 0.1118324324 0.0057633833 0.1785170000 985312649 0 402718720 0.0304527879 -0.0723433793 -1.0031560659 2868 1311867266.1241600513 0.1100710034 0.0601119454 0.1118324324 0.0057626707 0.1892520000 985315497 0 402718720 0.0340010636 -0.0719316304 -1.0043241978 2869 1311867266.1634809971 0.1107250303 0.0601295868 0.1118324324 0.0057627650 0.1973520000 985318625 0 402718720 0.0335922763 -0.0725788996 -1.0054693222 2870 1311867266.1922690868 0.1111206263 0.0601473537 0.1118324324 0.0057619513 0.1761700000 985321417 0 402718720 0.0327955149 -0.0726480559 -1.0063724518 2871 1311867266.2255198956 0.1114606336 0.0601652267 0.1118324324 0.0057612974 0.1779290000 985324377 0 402718720 0.0321440063 -0.0726185888 -1.0076158047 2872 1311867266.2597849369 0.1105950922 0.0601827858 0.1118324324 0.0057603174 0.1775750000 985327281 0 402718720 0.0336721465 -0.0721301064 -1.0089440346 2873 1311867266.2915120125 0.1116564125 0.0602007022 0.1118324324 0.0057593320 0.1879520000 985330185 0 402718720 0.0329360552 -0.0726180449 -1.0096321106 2874 1311867266.3258039951 0.1122933626 0.0602188276 0.1122933626 0.0057585244 0.1759470000 985333089 0 402718720 0.0300247986 -0.0717124566 -1.0118190050 2875 1311867266.3601551056 0.1120257750 0.0602368475 0.1122933626 0.0057576937 0.1763750000 985336049 0 402718720 0.0298059601 -0.0710272789 -1.0134329796 2876 1311867266.3913159370 0.1124401018 0.0602549988 0.1124401018 0.0057567827 0.1760620000 985338953 0 402718720 0.0288758148 -0.0713253766 -1.0149354935 2877 1311867266.4254870415 0.1129377037 0.0602733105 0.1129377037 0.0057570231 0.1741620000 985341913 0 402718720 0.0272568651 -0.0709964037 -1.0159945488 2878 1311867266.4612910748 0.1130125523 0.0602916354 0.1130125523 0.0057562458 0.1721150000 985344929 0 402718720 0.0271678213 -0.0715464130 -1.0171724558 2879 1311867266.4912600517 0.1118870527 0.0603095567 0.1130125523 0.0057553365 0.2161320000 985347721 0 402718720 0.0289120525 -0.0718599409 -1.0184229612 2880 1311867266.5284929276 0.1124754846 0.0603276699 0.1130125523 0.0057544460 0.2073200000 985350849 0 402718720 0.0280769859 -0.0727148205 -1.0199944973 2881 1311867266.5587360859 0.1134495139 0.0603461086 0.1134495139 0.0057540619 0.1699110000 985353641 0 402718720 0.0249218550 -0.0719480887 -1.0213861465 2882 1311867266.5906820297 0.1158160865 0.0603653556 0.1158160865 0.0057532982 0.1691890000 985356545 0 402718720 0.0223193206 -0.0743149519 -1.0227217674 2883 1311867266.6256470680 0.1153688058 0.0603844342 0.1158160865 0.0057530987 0.1796140000 985359505 0 402718720 0.0228954945 -0.0750045255 -1.0245441198 2884 1311867266.6596419811 0.1154548675 0.0604035293 0.1158160865 0.0057523124 0.1660170000 985362465 0 402718720 0.0237322636 -0.0757448003 -1.0246117115 2885 1311867266.6914939880 0.1154495925 0.0604226094 0.1158160865 0.0057513926 0.1687470000 985365369 0 402718720 0.0231264252 -0.0759398043 -1.0251976252 2886 1311867266.7260789871 0.1179843694 0.0604425546 0.1179843694 0.0057504515 0.1668010000 985368329 0 402718720 0.0193247814 -0.0773557872 -1.0259754658 2887 1311867266.7576239109 0.1174296215 0.0604622938 0.1179843694 0.0057496846 0.1776810000 985371289 0 402718720 0.0179903712 -0.0755344927 -1.0267125368 2888 1311867266.7898240089 0.1154884696 0.0604813472 0.1179843694 0.0057498362 0.1649620000 985374193 0 402718720 0.0211601183 -0.0766200498 -1.0270435810 2889 1311867266.8257129192 0.1167989895 0.0605008410 0.1179843694 0.0057499161 0.1651950000 985377209 0 402718720 0.0191138014 -0.0771338716 -1.0271047354 2890 1311867266.8575000763 0.1175609455 0.0605205850 0.1179843694 0.0057489968 0.1748950000 985380113 0 402718720 0.0176309869 -0.0770265311 -1.0265042782 2891 1311867266.8898739815 0.1173973009 0.0605402587 0.1179843694 0.0057482473 0.1672830000 985383017 0 402718720 0.0194662139 -0.0788046792 -1.0253303051 2892 1311867266.9266190529 0.1170464084 0.0605597975 0.1179843694 0.0057475566 0.1665320000 985386033 0 402718720 0.0191202331 -0.0789245144 -1.0246999264 2893 1311867266.9576549530 0.1167636216 0.0605792250 0.1179843694 0.0057467893 0.1674350000 985388937 0 402718720 0.0210267212 -0.0800854191 -1.0225530863 2894 1311867266.9920771122 0.1110986844 0.0605966816 0.1179843694 0.0057485961 0.1743810000 985391897 0 402718720 0.0220457744 -0.0708790794 -1.0219532251 2895 1311867267.0259480476 0.1138997972 0.0606150937 0.1179843694 0.0057497279 0.1721480000 985394801 0 402718720 0.0213607326 -0.0773418099 -1.0211508274 2896 1311867267.0603609085 0.1078316942 0.0606313978 0.1179843694 0.0057489317 0.1893670000 985397705 0 402718720 0.0258041359 -0.0712770075 -1.0201793909 2897 1311867267.0929799080 0.1110784262 0.0606488114 0.1179843694 0.0057483583 0.1745040000 985400497 0 402718720 0.0240097139 -0.0767007098 -1.0195428133 2898 1311867267.1266899109 0.1126500741 0.0606667552 0.1179843694 0.0057521923 0.1741380000 985403401 0 402718720 0.0214239024 -0.0770445317 -1.0189205408 2899 1311867267.1586909294 0.1120175198 0.0606844685 0.1179843694 0.0057520356 0.1744380000 985406361 0 402718720 0.0213480927 -0.0773359463 -1.0179655552 2900 1311867267.1916129589 0.1123970449 0.0607023004 0.1179843694 0.0057517314 0.1835210000 985409265 0 402718720 0.0214708801 -0.0792774111 -1.0173586607 2901 1311867267.2262039185 0.1132677421 0.0607204202 0.1179843694 0.0057512129 0.1744170000 985412169 0 402718720 0.0190444719 -0.0788984299 -1.0166555643 2902 1311867267.2587449551 0.1127488911 0.0607383487 0.1179843694 0.0057504917 0.1748590000 985415073 0 402718720 0.0191978402 -0.0788573101 -1.0160845518 2903 1311867267.2920761108 0.1135361716 0.0607565360 0.1179843694 0.0057501883 0.1860720000 985418033 0 402718720 0.0178048387 -0.0797828063 -1.0154697895 2904 1311867267.3265810013 0.1120435521 0.0607741968 0.1179843694 0.0057495773 0.1761730000 985421049 0 402718720 0.0199458729 -0.0798849165 -1.0143386126 2905 1311867267.3609950542 0.1119117364 0.0607918001 0.1179843694 0.0057489196 0.1930370000 985423953 0 402718720 0.0200334117 -0.0801317766 -1.0131328106 2906 1311867267.3945980072 0.1110784113 0.0608091045 0.1179843694 0.0057481033 0.1773480000 985426857 0 402718720 0.0225895606 -0.0814565644 -1.0118821859 2907 1311867267.4286189079 0.1144046187 0.0608275412 0.1179843694 0.0057480182 0.1782210000 985429873 0 402718720 0.0166017972 -0.0821520537 -1.0114490986 2908 1311867267.4595789909 0.1143832803 0.0608459579 0.1179843694 0.0057472431 0.1790390000 985432721 0 402718720 0.0163218733 -0.0818754137 -1.0104402304 2909 1311867267.4935429096 0.1122631803 0.0608636331 0.1179843694 0.0057464438 0.1790990000 985435681 0 402718720 0.0183394141 -0.0813705921 -1.0098549128 2910 1311867267.5264101028 0.1114915982 0.0608810310 0.1179843694 0.0057458238 0.1888340000 985438585 0 402718720 0.0200151131 -0.0815291628 -1.0084885359 2911 1311867267.5577969551 0.1131241396 0.0608989778 0.1179843694 0.0057483216 0.1791040000 985441545 0 402718720 0.0178365000 -0.0814183503 -1.0073890686 2912 1311867267.5954480171 0.1121601313 0.0609165813 0.1179843694 0.0057507459 0.1793270000 985444561 0 402718720 0.0197431948 -0.0827931464 -1.0054529905 2913 1311867267.6272020340 0.1109023094 0.0609337408 0.1179843694 0.0057506369 0.1805690000 985447465 0 402718720 0.0232002344 -0.0840780735 -1.0036454201 2914 1311867267.6608970165 0.1111732498 0.0609509815 0.1179843694 0.0057498525 0.1807750000 985450369 0 402718720 0.0218099076 -0.0844610035 -1.0028086901 2915 1311867267.6955730915 0.1108631119 0.0609681040 0.1179843694 0.0057491003 0.1969240000 985453385 0 402718720 0.0215278007 -0.0839334577 -1.0012856722 2916 1311867267.7264549732 0.1100895628 0.0609849495 0.1179843694 0.0057575189 0.1816670000 985456233 0 402718720 0.0229796842 -0.0838854462 -0.9998150468 2917 1311867267.7624979019 0.1110482663 0.0610021121 0.1179843694 0.0057627825 0.1813580000 985459305 0 402718720 0.0196032692 -0.0841195285 -0.9987918735 2918 1311867267.7957980633 0.1099568084 0.0610188889 0.1179843694 0.0057619281 0.1813820000 985462209 0 402718720 0.0209081918 -0.0839846283 -0.9968553185 2919 1311867267.8323969841 0.1094695330 0.0610354873 0.1179843694 0.0057613188 0.1817300000 985465281 0 402718720 0.0219008029 -0.0850366801 -0.9952999353 2920 1311867267.8601078987 0.1087558120 0.0610518299 0.1179843694 0.0057604586 0.1928380000 985468017 0 402718720 0.0211792588 -0.0847141445 -0.9943078160 2921 1311867267.8989579678 0.1066278741 0.0610674328 0.1179843694 0.0057637630 0.1822460000 985471145 0 402718720 0.0219605062 -0.0848975554 -0.9931871295 2922 1311867267.9282948971 0.1074167192 0.0610832950 0.1179843694 0.0057629207 0.1826180000 985473937 0 402718720 0.0204743482 -0.0844557285 -0.9910897613 2923 1311867267.9643011093 0.1072634235 0.0610990938 0.1179843694 0.0057633038 0.1839900000 985476953 0 402718720 0.0202269685 -0.0848112181 -0.9892838597 2924 1311867267.9947459698 0.1064685285 0.0611146101 0.1179843694 0.0057624015 0.1830490000 985479857 0 402718720 0.0217745397 -0.0856706128 -0.9879453182 2925 1311867268.0287120342 0.1077824384 0.0611305649 0.1179843694 0.0057618047 0.1972540000 985482761 0 402718720 0.0173610281 -0.0852711871 -0.9866641164 2926 1311867268.0588328838 0.1070751697 0.0611462671 0.1179843694 0.0057612900 0.1837420000 985485665 0 402718720 0.0189521369 -0.0857340023 -0.9842562079 2927 1311867268.0946080685 0.1065361202 0.0611617744 0.1179843694 0.0057614274 0.1837830000 985488681 0 402718720 0.0203712676 -0.0882426649 -0.9823136330 2928 1311867268.1253910065 0.1063874364 0.0611772203 0.1179843694 0.0057612292 0.1836470000 985491529 0 402718720 0.0210805349 -0.0893347114 -0.9798457623 2929 1311867268.1606659889 0.1077757701 0.0611931296 0.1179843694 0.0057637828 0.1964430000 985494489 0 402718720 0.0183946155 -0.0897240788 -0.9773005843 2930 1311867268.1981959343 0.1071400866 0.0612088112 0.1179843694 0.0057629550 0.1946880000 985497561 0 402718720 0.0188566856 -0.0908389613 -0.9750435948 2931 1311867268.2290298939 0.1080773175 0.0612248018 0.1179843694 0.0057620580 0.1823860000 985500465 0 402718720 0.0172779188 -0.0920237377 -0.9727846980 2932 1311867268.2579200268 0.1071585193 0.0612404682 0.1179843694 0.0057619751 0.1853910000 985503257 0 402718720 0.0171033684 -0.0916957036 -0.9704313278 2933 1311867268.2951550484 0.1086118892 0.0612566193 0.1179843694 0.0057628222 0.1850770000 985506273 0 402718720 0.0165775530 -0.0941494927 -0.9669470787 2934 1311867268.3274168968 0.1083878800 0.0612726832 0.1179843694 0.0057631752 0.1851950000 985509177 0 402718720 0.0156823006 -0.0947122425 -0.9646544456 2935 1311867268.3586890697 0.1088170335 0.0612888823 0.1179843694 0.0057634325 0.2176980000 985512137 0 402718720 0.0135686081 -0.0940964893 -0.9624439478 2936 1311867268.3934800625 0.1082882434 0.0613048902 0.1179843694 0.0057630186 0.1869670000 985515097 0 402718720 0.0134918448 -0.0955853909 -0.9600262642 2937 1311867268.4261479378 0.1082281992 0.0613208668 0.1179843694 0.0057620971 0.1872420000 985518001 0 402718720 0.0120586716 -0.0959953964 -0.9580902457 2938 1311867268.4581170082 0.1076298654 0.0613366289 0.1179843694 0.0057623457 0.1859980000 985520905 0 402718720 0.0121662095 -0.0960649177 -0.9554515481 2939 1311867268.4943540096 0.1079790890 0.0613524991 0.1179843694 0.0057615123 0.1873660000 985523921 0 402718720 0.0120094437 -0.0978951603 -0.9525016546 2940 1311867268.5280330181 0.1090962067 0.0613687385 0.1179843694 0.0057607633 0.1872930000 985526881 0 402718720 0.0093591698 -0.0992764384 -0.9501451254 2941 1311867268.5616149902 0.1076234505 0.0613844660 0.1179843694 0.0057611150 0.1865950000 985529841 0 402718720 0.0082250992 -0.0980774313 -0.9479464889 2942 1311867268.5949339867 0.1069227830 0.0613999447 0.1179843694 0.0057617946 0.2094490000 985532745 0 402718720 0.0077853529 -0.0977025032 -0.9458212852 2943 1311867268.6294579506 0.1061539501 0.0614151516 0.1179843694 0.0057660329 0.2304720000 985535761 0 402718720 0.0076167663 -0.0987706184 -0.9439349174 2944 1311867268.6639370918 0.1063058600 0.0614303998 0.1179843694 0.0057674682 0.1874850000 985538777 0 402718720 0.0053440048 -0.0984994918 -0.9413892627 2945 1311867268.6937808990 0.1057997122 0.0614454658 0.1179843694 0.0057673915 0.2102900000 985541569 0 402718720 0.0045827068 -0.0988963917 -0.9394068718 2946 1311867268.7282569408 0.1057165414 0.0614604933 0.1179843694 0.0057664644 0.1877430000 985544529 0 402718720 0.0021288937 -0.0987113714 -0.9375818372 2947 1311867268.7629311085 0.1060719043 0.0614756312 0.1179843694 0.0057668154 0.1875010000 985547545 0 402718720 0.0004229816 -0.0984815508 -0.9348945618 2948 1311867268.7951219082 0.1051003635 0.0614904293 0.1179843694 0.0057660383 0.1985340000 985550393 0 402718720 0.0028779651 -0.0996936187 -0.9324914813 2949 1311867268.8264629841 0.1040890887 0.0615048744 0.1179843694 0.0057657700 0.1881490000 985553297 0 402718720 0.0034842058 -0.1002219841 -0.9295790195 2950 1311867268.8615820408 0.1051290780 0.0615196623 0.1179843694 0.0057658400 0.1985070000 985556257 0 402718720 0.0006327087 -0.1009080186 -0.9269331098 2951 1311867268.8947710991 0.1042425111 0.0615341397 0.1179843694 0.0057721255 0.1877510000 985559161 0 402718720 -0.0007028328 -0.1012132689 -0.9238227010 2952 1311867268.9271900654 0.1053837761 0.0615489939 0.1179843694 0.0057796960 0.1888730000 985562121 0 402718720 -0.0028175549 -0.1016553640 -0.9204891920 2953 1311867268.9633738995 0.1044473499 0.0615635210 0.1179843694 0.0057790893 0.1891460000 985565193 0 402718720 -0.0029583029 -0.1022702381 -0.9171844721 2954 1311867268.9942259789 0.1050038636 0.0615782266 0.1179843694 0.0057791834 0.2009960000 985567985 0 402718720 -0.0048197675 -0.1027634665 -0.9141215682 2955 1311867269.0293419361 0.1054526716 0.0615930741 0.1179843694 0.0057792054 0.2102960000 985571057 0 402718720 -0.0053403089 -0.1043655798 -0.9102157354 2956 1311867269.0628340244 0.1047286466 0.0616076667 0.1179843694 0.0057784351 0.1912720000 985574017 0 402718720 -0.0063894973 -0.1038348228 -0.9071403742 2957 1311867269.0942130089 0.1049658284 0.0616223295 0.1179843694 0.0057775071 0.1915290000 985576753 0 402718720 -0.0086379880 -0.1045843139 -0.9042246342 2958 1311867269.1263980865 0.1054221839 0.0616371368 0.1179843694 0.0057766065 0.1900080000 985579657 0 402718720 -0.0102783348 -0.1052899584 -0.9011250138 2959 1311867269.1618270874 0.1039607301 0.0616514401 0.1179843694 0.0057756655 0.1910680000 985582617 0 402718720 -0.0104907360 -0.1050790697 -0.8982997537 2960 1311867269.1941618919 0.1033418104 0.0616655247 0.1179843694 0.0057758990 0.2142810000 985585521 0 402718720 -0.0104569457 -0.1067103744 -0.8952549100 2961 1311867269.2266249657 0.1039785147 0.0616798148 0.1179843694 0.0057791054 0.2190770000 985588425 0 402718720 -0.0134758446 -0.1058420911 -0.8924747109 2962 1311867269.2623720169 0.1019331962 0.0616934048 0.1179843694 0.0057793747 0.2406940000 985591441 0 402718720 -0.0130662965 -0.1053646356 -0.8897372484 2963 1311867269.2948200703 0.1018450707 0.0617069558 0.1179843694 0.0058105073 0.2403140000 985594401 0 402718720 -0.0147821549 -0.1067765579 -0.8866804838 2964 1311867269.3261830807 0.1017791405 0.0617204754 0.1179843694 0.0058172491 0.2325770000 985597249 0 402718720 -0.0166878868 -0.1065538600 -0.8838012218 2965 1311867269.3641560078 0.0975168869 0.0617325484 0.1179843694 0.0058200327 0.2207470000 985600321 0 402718720 -0.0174536556 -0.0994014665 -0.8810986280 2966 1311867269.3967740536 0.1005691513 0.0617456423 0.1179843694 0.0058220868 0.1953600000 985603225 0 402718720 -0.0201541670 -0.1047068387 -0.8773551583 2967 1311867269.4275820255 0.1014777198 0.0617590337 0.1179843694 0.0058235707 0.1949340000 985606129 0 402718720 -0.0205256734 -0.1062563136 -0.8743341565 2968 1311867269.4626441002 0.1027240008 0.0617728359 0.1179843694 0.0058228786 0.1968590000 985609089 0 402718720 -0.0214243438 -0.1072616652 -0.8714362979 2969 1311867269.4938280582 0.0968301147 0.0617846436 0.1179843694 0.0058421008 0.2015660000 985611937 0 402718720 -0.0197930224 -0.0982678533 -0.8682104349 2970 1311867269.5278589725 0.0994213596 0.0617973159 0.1179843694 0.0058645949 0.2201470000 985614953 0 402718720 -0.0206634384 -0.1033505946 -0.8646202087 2971 1311867269.5634589195 0.1003935263 0.0618103069 0.1179843694 0.0058640651 0.1973530000 985617969 0 402718720 -0.0220248364 -0.1054402366 -0.8615403771 2972 1311867269.5962390900 0.0958226472 0.0618217512 0.1179843694 0.0058642043 0.2053970000 985620873 0 402718720 -0.0202712398 -0.0987601727 -0.8587905765 2973 1311867269.6306080818 0.0978791118 0.0618338795 0.1179843694 0.0058635700 0.2014910000 985623833 0 402718720 -0.0222796407 -0.1026114449 -0.8563581705 2974 1311867269.6631560326 0.0974514782 0.0618458558 0.1179843694 0.0058626662 0.2020370000 985626793 0 402718720 -0.0213254336 -0.1032857522 -0.8532587290 2975 1311867269.6964600086 0.0920548066 0.0618560100 0.1179843694 0.0058685475 0.2157810000 985629641 0 402718720 -0.0182305295 -0.0964893848 -0.8504635692 2976 1311867269.7280869484 0.0955309719 0.0618673256 0.1179843694 0.0058689041 0.2038910000 985632601 0 402718720 -0.0221639909 -0.1017402261 -0.8489279151 2977 1311867269.7622261047 0.0970636383 0.0618791483 0.1179843694 0.0058684389 0.2032250000 985635561 0 402718720 -0.0247492604 -0.1030608043 -0.8462866545 2978 1311867269.7974090576 0.0955100134 0.0618904414 0.1179843694 0.0058676857 0.2039400000 985638521 0 402718720 -0.0227979999 -0.1038504988 -0.8443618417 2979 1311867269.8295869827 0.0952008292 0.0619016231 0.1179843694 0.0058810730 0.2040230000 985641425 0 402718720 -0.0231190324 -0.1044919938 -0.8420094848 2980 1311867269.8676230907 0.0958738774 0.0619130232 0.1179843694 0.0058808380 0.2154030000 985644441 0 402718720 -0.0267776735 -0.1052227244 -0.8403349519 2981 1311867269.8953619003 0.0957506672 0.0619243743 0.1179843694 0.0058800606 0.2042910000 985647233 0 402718720 -0.0266638845 -0.1056051180 -0.8386305571 2982 1311867269.9344720840 0.0948527977 0.0619354167 0.1179843694 0.0058791965 0.2054890000 985650305 0 402718720 -0.0254513174 -0.1059263572 -0.8360507488 2983 1311867269.9627900124 0.0954129994 0.0619466395 0.1179843694 0.0058842219 0.2056600000 985653153 0 402718720 -0.0264104623 -0.1066920981 -0.8345615268 2984 1311867269.9987258911 0.0952640548 0.0619578049 0.1179843694 0.0058834999 0.2046770000 985656169 0 402718720 -0.0261772387 -0.1076020673 -0.8325477242 2985 1311867270.0306990147 0.0953022987 0.0619689756 0.1179843694 0.0058837158 0.2343190000 985659017 0 402718720 -0.0268817563 -0.1083652079 -0.8303387165 2986 1311867270.0660951138 0.0957967564 0.0619803044 0.1179843694 0.0058828693 0.2060100000 985662033 0 402718720 -0.0277602319 -0.1090625674 -0.8277924657 2987 1311867270.0948200226 0.0961933881 0.0619917583 0.1179843694 0.0058821466 0.2058050000 985664769 0 402718720 -0.0297051650 -0.1089540198 -0.8256494403 2988 1311867270.1336340904 0.0959983021 0.0620031394 0.1179843694 0.0058811624 0.2059690000 985667953 0 402718720 -0.0301143471 -0.1096808985 -0.8228353858 2989 1311867270.1624090672 0.0964927897 0.0620146782 0.1179843694 0.0058803033 0.2186000000 985670745 0 402718720 -0.0310553145 -0.1099025756 -0.8202558160 2990 1311867270.1943540573 0.0917644650 0.0620246280 0.1179843694 0.0058798522 0.2290870000 985673649 0 402718720 -0.0245263986 -0.1066534817 -0.8168942332 2991 1311867270.2323369980 0.0925404206 0.0620348305 0.1179843694 0.0058820760 0.2197410000 985676721 0 402718720 -0.0258693062 -0.1099128649 -0.8149352074 2992 1311867270.2655749321 0.0931001231 0.0620452133 0.1179843694 0.0058832318 0.2093630000 985679625 0 402718720 -0.0253492519 -0.1118887588 -0.8119907975 2993 1311867270.2960460186 0.0937522277 0.0620558071 0.1179843694 0.0058823690 0.2081010000 985682473 0 402718720 -0.0269307233 -0.1123628318 -0.8093761206 2994 1311867270.3346099854 0.0941742137 0.0620665346 0.1179843694 0.0058820610 0.2092070000 985685601 0 402718720 -0.0285494849 -0.1135684028 -0.8065420985 2995 1311867270.3624660969 0.0936682671 0.0620770861 0.1179843694 0.0058815685 0.2397880000 985688393 0 402718720 -0.0282653645 -0.1138588488 -0.8041644096 2996 1311867270.3957469463 0.0930571109 0.0620874266 0.1179843694 0.0058823215 0.2073790000 985691297 0 402718720 -0.0283617694 -0.1138776615 -0.8013466001 2997 1311867270.4334359169 0.0920246616 0.0620974157 0.1179843694 0.0058884338 0.2101780000 985694425 0 402718720 -0.0267290156 -0.1142930463 -0.7977552414 2998 1311867270.4641909599 0.0933076516 0.0621078260 0.1179843694 0.0058878905 0.2099060000 985697329 0 402718720 -0.0290128868 -0.1158362702 -0.7951593399 2999 1311867270.4954609871 0.0930426195 0.0621181411 0.1179843694 0.0058878157 0.2108150000 985700121 0 402718720 -0.0278685372 -0.1173406914 -0.7920081019 3000 1311867270.5331869125 0.0918617770 0.0621280556 0.1179843694 0.0058871188 0.2306820000 985703249 0 402718720 -0.0276078992 -0.1175219491 -0.7892849445 3001 1311867270.5629880428 0.0925500467 0.0621381929 0.1179843694 0.0058863997 0.2126830000 985706097 0 402718720 -0.0272135921 -0.1194297597 -0.7863997817 3002 1311867270.5944859982 0.0920327827 0.0621481511 0.1179843694 0.0058854382 0.2111180000 985708889 0 402718720 -0.0271765627 -0.1206984967 -0.7843164802 3003 1311867270.6312110424 0.0924678892 0.0621582476 0.1179843694 0.0058854542 0.2111620000 985711905 0 402718720 -0.0269499794 -0.1213622242 -0.7814099193 3004 1311867270.6644439697 0.0925621316 0.0621683687 0.1179843694 0.0058866084 0.2222480000 985714809 0 402718720 -0.0256673656 -0.1223100871 -0.7790718079 3005 1311867270.6950180531 0.0921740159 0.0621783540 0.1179843694 0.0058860900 0.2280720000 985717657 0 402718720 -0.0279969256 -0.1226545200 -0.7775893807 3006 1311867270.7318449020 0.0923207253 0.0621883814 0.1179843694 0.0058856029 0.2119770000 985720729 0 402718720 -0.0273420941 -0.1234857142 -0.7750852704 3007 1311867270.7623898983 0.0918245688 0.0621982371 0.1179843694 0.0058849312 0.2117100000 985723577 0 402718720 -0.0253872816 -0.1242379844 -0.7727221847 3008 1311867270.7960500717 0.0931749046 0.0622085352 0.1179843694 0.0058844243 0.2128520000 985726537 0 402718720 -0.0277881343 -0.1251226813 -0.7709968686 3009 1311867270.8322730064 0.0926392674 0.0622186484 0.1179843694 0.0058868350 0.2120830000 985729553 0 402718720 -0.0276682749 -0.1252317131 -0.7687004209 3010 1311867270.8635489941 0.0925122648 0.0622287128 0.1179843694 0.0058877962 0.2139330000 985732457 0 402718720 -0.0256581660 -0.1265182942 -0.7662189007 3011 1311867270.8945889473 0.0926757678 0.0622388247 0.1179843694 0.0058873056 0.2133100000 985735305 0 402718720 -0.0261416808 -0.1274877936 -0.7644765377 3012 1311867270.9326179028 0.0920488909 0.0622487218 0.1179843694 0.0058906168 0.2126560000 985738377 0 402718720 -0.0249179695 -0.1277626157 -0.7621796727 3013 1311867270.9624550343 0.0862523839 0.0622566885 0.1179843694 0.0058952168 0.2304720000 985741225 0 402718720 -0.0187743995 -0.1211618856 -0.7592468858 3014 1311867270.9944560528 0.0901474729 0.0622659422 0.1179843694 0.0058958593 0.2138430000 985744129 0 402718720 -0.0231190566 -0.1268619001 -0.7582821250 3015 1311867271.0306649208 0.0905521661 0.0622753241 0.1179843694 0.0058951363 0.2285210000 985747089 0 402718720 -0.0205732528 -0.1295948774 -0.7556295395 3016 1311867271.0623910427 0.0906878561 0.0622847447 0.1179843694 0.0058947150 0.2148690000 985749993 0 402718720 -0.0182762984 -0.1314821392 -0.7533569336 3017 1311867271.0983459949 0.0911995098 0.0622943286 0.1179843694 0.0058969024 0.2147320000 985753009 0 402718720 -0.0197085850 -0.1323543936 -0.7522626519 3018 1311867271.1322019100 0.0916777700 0.0623040647 0.1179843694 0.0058961997 0.2144220000 985755913 0 402718720 -0.0219466463 -0.1327496469 -0.7510239482 3019 1311867271.1643741131 0.0905866474 0.0623134329 0.1179843694 0.0058955549 0.2151470000 985758817 0 402718720 -0.0189403724 -0.1335221380 -0.7491935492 3020 1311867271.1988029480 0.0919042975 0.0623232312 0.1179843694 0.0058953872 0.2261010000 985761833 0 402718720 -0.0202215090 -0.1350478828 -0.7472011447 3021 1311867271.2320818901 0.0917914659 0.0623329856 0.1179843694 0.0058959733 0.2149690000 985764681 0 402718720 -0.0199863482 -0.1359645426 -0.7453196645 3022 1311867271.2645740509 0.0922397152 0.0623428820 0.1179843694 0.0058978126 0.2143220000 985767585 0 402718720 -0.0204473566 -0.1362687498 -0.7429738045 3023 1311867271.2998549938 0.0918812603 0.0623526532 0.1179843694 0.0058993490 0.2148750000 985770601 0 402718720 -0.0186743159 -0.1379701346 -0.7402423024 3024 1311867271.3354289532 0.0920263752 0.0623624659 0.1179843694 0.0059021413 0.2158330000 985773561 0 402718720 -0.0179325175 -0.1397095323 -0.7373067737 3025 1311867271.3673670292 0.0915143788 0.0623721029 0.1179843694 0.0059014497 0.2165950000 985776521 0 402718720 -0.0168346651 -0.1411659122 -0.7341971397 3026 1311867271.3988809586 0.0921652541 0.0623819487 0.1179843694 0.0059011331 0.2157570000 985779425 0 402718720 -0.0161376651 -0.1427886933 -0.7317771912 3027 1311867271.4355340004 0.0913321823 0.0623915127 0.1179843694 0.0059004115 0.2275320000 985782441 0 402718720 -0.0155117586 -0.1446703523 -0.7290804386 3028 1311867271.4657170773 0.0913792700 0.0624010859 0.1179843694 0.0059033608 0.2153480000 985785233 0 402718720 -0.0148144197 -0.1462985277 -0.7263529897 3029 1311867271.4997088909 0.0913146064 0.0624106315 0.1179843694 0.0059070402 0.2152180000 985788249 0 402718720 -0.0151866777 -0.1472727656 -0.7232099771 3030 1311867271.5323960781 0.0917275324 0.0624203070 0.1179843694 0.0059063964 0.2266060000 985791153 0 402718720 -0.0163644664 -0.1484954357 -0.7200662494 3031 1311867271.5676190853 0.0914849788 0.0624298961 0.1179843694 0.0059058300 0.2278510000 985794113 0 402718720 -0.0173375942 -0.1498011500 -0.7169012427 3032 1311867271.5991230011 0.0911687687 0.0624393747 0.1179843694 0.0059049242 0.2150970000 985797017 0 402718720 -0.0158348568 -0.1511231363 -0.7134066224 3033 1311867271.6349890232 0.0907772109 0.0624487178 0.1179843694 0.0059047880 0.2152280000 985799977 0 402718720 -0.0153855160 -0.1533560604 -0.7095521092 3034 1311867271.6658320427 0.0906603336 0.0624580163 0.1179843694 0.0059042750 0.2153880000 985802881 0 402718720 -0.0150334919 -0.1548248380 -0.7058588862 3035 1311867271.7005228996 0.0873624906 0.0624662221 0.1179843694 0.0059062274 0.2477430000 985805841 0 402718720 -0.0122023718 -0.1531173885 -0.7011924982 3036 1311867271.7349541187 0.0888737142 0.0624749202 0.1179843694 0.0059056762 0.2165340000 985808857 0 402718720 -0.0155775640 -0.1567022204 -0.6969156861 3037 1311867271.7661850452 0.0896392539 0.0624838647 0.1179843694 0.0059061743 0.2165670000 985811705 0 402718720 -0.0174439084 -0.1585771590 -0.6921747327 3038 1311867271.7994530201 0.0855059251 0.0624914427 0.1179843694 0.0059085904 0.2198800000 985814721 0 402718720 -0.0128332591 -0.1568057984 -0.6877685785 3039 1311867271.8341000080 0.0859919488 0.0624991757 0.1179843694 0.0059084162 0.2173230000 985817625 0 402718720 -0.0120389182 -0.1610944718 -0.6830277443 3040 1311867271.8629150391 0.0871674865 0.0625072902 0.1179843694 0.0059081864 0.2263350000 985820473 0 402718720 -0.0129948230 -0.1637824029 -0.6781967878 3041 1311867271.9009630680 0.0853812769 0.0625148121 0.1179843694 0.0059072986 0.2144940000 985823545 0 402718720 -0.0119892545 -0.1647186875 -0.6731935740 3042 1311867271.9304800034 0.0826554075 0.0625214329 0.1179843694 0.0059068667 0.2194940000 985826393 0 402718720 -0.0105722081 -0.1623239815 -0.6678854227 3043 1311867271.9669768810 0.0824271664 0.0625279744 0.1179843694 0.0059063776 0.2202490000 985829353 0 402718720 -0.0087877437 -0.1637693048 -0.6619927883 3044 1311867271.9994390011 0.0852679312 0.0625354448 0.1179843694 0.0059056918 0.2181870000 985832257 0 402718720 -0.0121104876 -0.1674942523 -0.6571147442 3045 1311867272.0337600708 0.0820354223 0.0625418488 0.1179843694 0.0059055829 0.2392100000 985835217 0 402718720 -0.0077704801 -0.1654772609 -0.6511911750 3046 1311867272.0626399517 0.0845783651 0.0625490834 0.1179843694 0.0059057937 0.2199720000 985838065 0 402718720 -0.0077802101 -0.1696267277 -0.6464042068 3047 1311867272.0988030434 0.0835633725 0.0625559801 0.1179843694 0.0059054418 0.2212210000 985841081 0 402718720 -0.0062481449 -0.1699166447 -0.6412636042 3048 1311867272.1336209774 0.0850432739 0.0625633578 0.1179843694 0.0059047689 0.2187330000 985844097 0 402718720 -0.0082889227 -0.1725909412 -0.6366703510 3049 1311867272.1659350395 0.0862870365 0.0625711386 0.1179843694 0.0059065300 0.2165100000 985847001 0 402718720 -0.0085458318 -0.1753436625 -0.6326754689 3050 1311867272.1987910271 0.0865081027 0.0625789868 0.1179843694 0.0059062757 0.2292310000 985849961 0 402718720 -0.0072299140 -0.1771369576 -0.6284598112 3051 1311867272.2319760323 0.0862796828 0.0625867550 0.1179843694 0.0059069204 0.2205950000 985852865 0 402718720 -0.0036634097 -0.1784688532 -0.6241459250 3052 1311867272.2655110359 0.0864520743 0.0625945745 0.1179843694 0.0059097948 0.2188480000 985855825 0 402718720 -0.0042422037 -0.1797190756 -0.6208159924 3053 1311867272.2982270718 0.0869534165 0.0626025532 0.1179843694 0.0059089475 0.2178650000 985858785 0 402718720 -0.0048138220 -0.1808304191 -0.6175507903 3054 1311867272.3315019608 0.0861371085 0.0626102593 0.1179843694 0.0059139282 0.2176650000 985861689 0 402718720 -0.0028323780 -0.1822374314 -0.6143305898 3055 1311867272.3696749210 0.0865581855 0.0626180982 0.1179843694 0.0059160068 0.2192720000 985864761 0 402718720 -0.0049804500 -0.1832713783 -0.6112458706 3056 1311867272.3987050056 0.0866919607 0.0626259758 0.1179843694 0.0059152579 0.2403890000 985867553 0 402718720 -0.0033252710 -0.1850709617 -0.6076628566 3057 1311867272.4335730076 0.0857382417 0.0626335363 0.1179843694 0.0059144924 0.2187870000 985870569 0 402718720 0.0001699807 -0.1864612699 -0.6048384309 3058 1311867272.4686141014 0.0862467363 0.0626412580 0.1179843694 0.0059138982 0.2177370000 985873529 0 402718720 0.0009443139 -0.1878746748 -0.6014720201 3059 1311867272.5011420250 0.0860072300 0.0626488965 0.1179843694 0.0059132074 0.2186100000 985876433 0 402718720 0.0038194554 -0.1893668771 -0.5980582237 3060 1311867272.5325479507 0.0864287466 0.0626566677 0.1179843694 0.0059123682 0.2372300000 985879337 0 402718720 0.0058327243 -0.1904883534 -0.5945847034 3061 1311867272.5676600933 0.0863914639 0.0626644216 0.1179843694 0.0059118939 0.2164510000 985882297 0 402718720 0.0070347185 -0.1911183447 -0.5916053653 3062 1311867272.5996229649 0.0864345953 0.0626721846 0.1179843694 0.0059111410 0.2184760000 985885257 0 402718720 0.0077998680 -0.1916882098 -0.5888877511 3063 1311867272.6315360069 0.0864825025 0.0626799581 0.1179843694 0.0059104268 0.2334770000 985888105 0 402718720 0.0085221762 -0.1924082190 -0.5861768126 3064 1311867272.6661291122 0.0855319574 0.0626874163 0.1179843694 0.0059095410 0.2191150000 985891065 0 402718720 0.0089492183 -0.1917585731 -0.5839106441 3065 1311867272.6987280846 0.0862147585 0.0626950924 0.1179843694 0.0059086802 0.2321530000 985894025 0 402718720 0.0108407727 -0.1926441193 -0.5810383558 3066 1311867272.7307109833 0.0870037377 0.0627030209 0.1179843694 0.0059082032 0.2183850000 985896929 0 402718720 0.0121045308 -0.1935032010 -0.5783500671 3067 1311867272.7686150074 0.0858571678 0.0627105703 0.1179843694 0.0059110035 0.2174060000 985899945 0 402718720 0.0131958490 -0.1928550005 -0.5755720139 3068 1311867272.7996079922 0.0864160508 0.0627182970 0.1179843694 0.0059101821 0.2179950000 985902793 0 402718720 0.0117670475 -0.1931926161 -0.5728491545 3069 1311867272.8310160637 0.0858904719 0.0627258474 0.1179843694 0.0059099768 0.2300700000 985905697 0 402718720 0.0137897488 -0.1930174381 -0.5701868534 3070 1311867272.8674850464 0.0857592970 0.0627333502 0.1179843694 0.0059091377 0.2261430000 985908769 0 402718720 0.0167474356 -0.1933877915 -0.5675773025 3071 1311867272.8996291161 0.0857304931 0.0627408387 0.1179843694 0.0059086998 0.2175430000 985911617 0 402718720 0.0200182293 -0.1933766305 -0.5650383830 3072 1311867272.9314110279 0.0866026506 0.0627486062 0.1179843694 0.0059085304 0.2165080000 985914521 0 402718720 0.0220280532 -0.1943339258 -0.5627422333 3073 1311867272.9664669037 0.0862414092 0.0627562511 0.1179843694 0.0059076391 0.2169090000 985917537 0 402718720 0.0229760222 -0.1938311905 -0.5607749224 3074 1311867272.9987599850 0.0859522671 0.0627637970 0.1179843694 0.0059068974 0.2157210000 985920441 0 402718720 0.0250064619 -0.1936462522 -0.5592414141 3075 1311867273.0328490734 0.0864797905 0.0627715095 0.1179843694 0.0059059571 0.2275300000 985923457 0 402718720 0.0270560384 -0.1942515820 -0.5575051904 3076 1311867273.0662739277 0.0864016265 0.0627791916 0.1179843694 0.0059050819 0.2145150000 985926361 0 402718720 0.0292189755 -0.1942515522 -0.5561258197 3077 1311867273.0999150276 0.0852180049 0.0627864840 0.1179843694 0.0059043148 0.2153850000 985929265 0 402718720 0.0284713507 -0.1926280558 -0.5552194715 3078 1311867273.1310710907 0.0848992020 0.0627936681 0.1179843694 0.0059035018 0.2151780000 985932169 0 402718720 0.0318102054 -0.1926965863 -0.5538063645 3079 1311867273.1665740013 0.0844584033 0.0628007044 0.1179843694 0.0059028505 0.2425030000 985935185 0 402718720 0.0341259427 -0.1928018779 -0.5525414944 3080 1311867273.1997520924 0.0837748125 0.0628075142 0.1179843694 0.0059019305 0.2241090000 985938089 0 402718720 0.0358208977 -0.1925230473 -0.5510306954 3081 1311867273.2331819534 0.0836938992 0.0628142933 0.1179843694 0.0059017437 0.2271440000 985941105 0 402718720 0.0370755568 -0.1935321540 -0.5497301817 3082 1311867273.2668380737 0.0828856453 0.0628208057 0.1179843694 0.0059016683 0.2152890000 985944009 0 402718720 0.0376981907 -0.1936371177 -0.5480870008 3083 1311867273.2985589504 0.0828998908 0.0628273186 0.1179843694 0.0059010149 0.2147230000 985946969 0 402718720 0.0406887382 -0.1932445318 -0.5457238555 3084 1311867273.3308010101 0.0830606148 0.0628338793 0.1179843694 0.0059010064 0.2137090000 985949817 0 402718720 0.0423711799 -0.1938424408 -0.5435844064 3085 1311867273.3663508892 0.0830438212 0.0628404303 0.1179843694 0.0059000773 0.2248500000 985952833 0 402718720 0.0422784127 -0.1935513467 -0.5415650010 3086 1311867273.3992459774 0.0833197460 0.0628470665 0.1179843694 0.0058999518 0.2150690000 985955737 0 402718720 0.0415261351 -0.1933793575 -0.5388044715 3087 1311867273.4308409691 0.0806668028 0.0628528391 0.1179843694 0.0059000584 0.2174870000 985958697 0 402718720 0.0452257693 -0.1895785928 -0.5358022451 3088 1311867273.4663250446 0.0827201083 0.0628592728 0.1179843694 0.0059013589 0.2159780000 985961657 0 402718720 0.0443622954 -0.1920117736 -0.5327973962 3089 1311867273.4997849464 0.0830714330 0.0628658160 0.1179843694 0.0059012968 0.2159860000 985964561 0 402718720 0.0430448689 -0.1922234893 -0.5297554135 3090 1311867273.5318419933 0.0813153088 0.0628717867 0.1179843694 0.0059026028 0.2358350000 985967521 0 402718720 0.0469295979 -0.1896542758 -0.5264878869 3091 1311867273.5687909126 0.0827243328 0.0628782094 0.1179843694 0.0059027071 0.2190890000 985970593 0 402718720 0.0455728918 -0.1918810606 -0.5229262710 3092 1311867273.6000390053 0.0837263614 0.0628849520 0.1179843694 0.0059019764 0.2192610000 985973385 0 402718720 0.0445234403 -0.1935346425 -0.5194588900 3093 1311867273.6349599361 0.0833197758 0.0628915588 0.1179843694 0.0059016358 0.2334360000 985976401 0 402718720 0.0468646921 -0.1930297613 -0.5153298378 3094 1311867273.6673769951 0.0842823386 0.0628984725 0.1179843694 0.0059007877 0.2180410000 985979361 0 402718720 0.0452748388 -0.1942250431 -0.5112225413 3095 1311867273.6987860203 0.0852991864 0.0629057102 0.1179843694 0.0059008380 0.2189200000 985982209 0 402718720 0.0435603559 -0.1954721510 -0.5072973371 3096 1311867273.7346739769 0.0820588022 0.0629118966 0.1179843694 0.0059027737 0.2217330000 985985225 0 402718720 0.0480115376 -0.1923187822 -0.5032618046 3097 1311867273.7665960789 0.0849007219 0.0629189966 0.1179843694 0.0059047006 0.2197410000 985988129 0 402718720 0.0484809987 -0.1943457276 -0.4996441901 3098 1311867273.7990698814 0.0851362795 0.0629261681 0.1179843694 0.0059041614 0.2195440000 985991089 0 402718720 0.0487131551 -0.1954717785 -0.4966927469 3099 1311867273.8358130455 0.0863096640 0.0629337136 0.1179843694 0.0059040030 0.2327950000 985994105 0 402718720 0.0478173979 -0.1968016624 -0.4935818017 3100 1311867273.8668060303 0.0853227451 0.0629409359 0.1179843694 0.0059055981 0.2313740000 985997009 0 402718720 0.0479918830 -0.1963432878 -0.4910140634 3101 1311867273.8990719318 0.0857731923 0.0629482987 0.1179843694 0.0059083314 0.2195940000 985999969 0 402718720 0.0454960577 -0.1968621761 -0.4885842502 3102 1311867273.9384820461 0.0855582207 0.0629555876 0.1179843694 0.0059074288 0.2312700000 986003041 0 402718720 0.0454858504 -0.1968406737 -0.4855053425 3103 1311867273.9669051170 0.0849818587 0.0629626859 0.1179843694 0.0059069600 0.2195630000 986005833 0 402718720 0.0448175259 -0.1967321038 -0.4827304184 3104 1311867273.9996581078 0.0847406536 0.0629697020 0.1179843694 0.0059060138 0.2188310000 986008793 0 402718720 0.0439029261 -0.1973376870 -0.4796668589 3105 1311867274.0348489285 0.0833087116 0.0629762524 0.1179843694 0.0059051997 0.2343420000 986011697 0 402718720 0.0446771942 -0.1964680403 -0.4763137102 3106 1311867274.0670020580 0.0832991153 0.0629827955 0.1179843694 0.0059072610 0.2211560000 986014657 0 402718720 0.0455315523 -0.1974535584 -0.4725704789 3107 1311867274.1025679111 0.0829258487 0.0629892143 0.1179843694 0.0059071826 0.2217130000 986017673 0 402718720 0.0454626717 -0.1981549561 -0.4685483575 3108 1311867274.1350569725 0.0814488307 0.0629951537 0.1179843694 0.0059063204 0.2257490000 986020633 0 402718720 0.0475310460 -0.1955961138 -0.4639617205 3109 1311867274.1667969227 0.0821185559 0.0630013047 0.1179843694 0.0059063412 0.2333710000 986023481 0 402718720 0.0466713235 -0.1978676766 -0.4600193501 3110 1311867274.2008550167 0.0818642378 0.0630073699 0.1179843694 0.0059115075 0.2230580000 986026385 0 402718720 0.0470631272 -0.1996785849 -0.4555755556 3111 1311867274.2389180660 0.0820374042 0.0630134869 0.1179843694 0.0059122062 0.2222080000 986029513 0 402718720 0.0445888937 -0.2007405758 -0.4512147009 3112 1311867274.2668540478 0.0827775300 0.0630198378 0.1179843694 0.0059114149 0.2184430000 986032305 0 402718720 0.0419040211 -0.2006538808 -0.4466621280 3113 1311867274.3018939495 0.0819826648 0.0630259293 0.1179843694 0.0059124623 0.2217560000 986035265 0 402718720 0.0408109538 -0.2009665370 -0.4425763488 3114 1311867274.3358139992 0.0824739113 0.0630321747 0.1179843694 0.0059132603 0.2211490000 986038225 0 402718720 0.0397744775 -0.2022634745 -0.4382525384 3115 1311867274.3679759502 0.0819158629 0.0630382369 0.1179843694 0.0059124826 0.2438110000 986041185 0 402718720 0.0383645594 -0.2023644894 -0.4339874685 3116 1311867274.4007549286 0.0818371549 0.0630442699 0.1179843694 0.0059118072 0.2206780000 986044033 0 402718720 0.0360567123 -0.2030770481 -0.4299592972 3117 1311867274.4357678890 0.0820691362 0.0630503735 0.1179843694 0.0059141477 0.2195490000 986047049 0 402718720 0.0350649171 -0.2041513026 -0.4256894588 3118 1311867274.4689209461 0.0817805603 0.0630563806 0.1179843694 0.0059162312 0.2186960000 986050009 0 402718720 0.0318451636 -0.2045249045 -0.4217720330 3119 1311867274.4997699261 0.0821312666 0.0630624963 0.1179843694 0.0059157313 0.2150680000 986052801 0 402718720 0.0321365856 -0.2058237791 -0.4176869988 3120 1311867274.5345981121 0.0825557262 0.0630687441 0.1179843694 0.0059160634 0.2290340000 986055761 0 402718720 0.0301805958 -0.2077723294 -0.4142903090 3121 1311867274.5686841011 0.0826385170 0.0630750145 0.1179843694 0.0059153710 0.2143670000 986058665 0 402718720 0.0281962901 -0.2091299891 -0.4107002318 3122 1311867274.6001191139 0.0830667168 0.0630814180 0.1179843694 0.0059151873 0.2143550000 986061569 0 402718720 0.0270361863 -0.2096296251 -0.4074777663 3123 1311867274.6349270344 0.0832778215 0.0630878850 0.1179843694 0.0059151840 0.2134740000 986064585 0 402718720 0.0247868933 -0.2113562077 -0.4043252766 3124 1311867274.6665649414 0.0842957720 0.0630946736 0.1179843694 0.0059164755 0.2115450000 986067433 0 402718720 0.0240153112 -0.2120370269 -0.4007267356 3125 1311867274.6988699436 0.0844874904 0.0631015193 0.1179843694 0.0059156790 0.2344380000 986070393 0 402718720 0.0222349260 -0.2127821147 -0.3973959088 3126 1311867274.7355759144 0.0844996795 0.0631083646 0.1179843694 0.0059187204 0.2101020000 986073353 0 402718720 0.0207790770 -0.2141119540 -0.3942456245 3127 1311867274.7669000626 0.0848880038 0.0631153296 0.1179843694 0.0059179147 0.2087280000 986076257 0 402718720 0.0191383027 -0.2149125040 -0.3909502327 3128 1311867274.8040020466 0.0837736279 0.0631219339 0.1179843694 0.0059176902 0.2071970000 986079329 0 402718720 0.0180342756 -0.2146229744 -0.3876598775 3129 1311867274.8350889683 0.0834235996 0.0631284221 0.1179843694 0.0059179410 0.2067500000 986082233 0 402718720 0.0163262598 -0.2146852612 -0.3843513727 3130 1311867274.8671360016 0.0826215148 0.0631346500 0.1179843694 0.0059173853 0.2155090000 986085137 0 402718720 0.0152611211 -0.2141169310 -0.3808264136 3131 1311867274.9044289589 0.0834331736 0.0631411330 0.1179843694 0.0059165072 0.2057830000 986088153 0 402718720 0.0126720071 -0.2148256302 -0.3767876923 3132 1311867274.9350550175 0.0832698345 0.0631475598 0.1179843694 0.0059158861 0.2185470000 986091057 0 402718720 0.0131084155 -0.2145100534 -0.3727005720 3133 1311867274.9666490555 0.0831388384 0.0631539407 0.1179843694 0.0059150075 0.2536750000 986093905 0 402718720 0.0123804556 -0.2146768570 -0.3690632582 3134 1311867275.0030829906 0.0840504616 0.0631606084 0.1179843694 0.0059162907 0.2076460000 986096977 0 402718720 0.0098884180 -0.2159879357 -0.3647525907 3135 1311867275.0368080139 0.0834470093 0.0631670793 0.1179843694 0.0059207427 0.2057790000 986099881 0 402718720 0.0072257305 -0.2151718587 -0.3609219193 3136 1311867275.0664451122 0.0831153169 0.0631734404 0.1179843694 0.0059220067 0.2057710000 986102729 0 402718720 0.0074039279 -0.2153193951 -0.3570728302 3137 1311867275.1023271084 0.0827035904 0.0631796661 0.1179843694 0.0059217739 0.2045950000 986105745 0 402718720 0.0070222309 -0.2165142149 -0.3531442285 3138 1311867275.1351230145 0.0834441036 0.0631861239 0.1179843694 0.0059210121 0.2042250000 986108649 0 402718720 0.0042750104 -0.2175775915 -0.3491758108 3139 1311867275.1667180061 0.0839810967 0.0631927486 0.1179843694 0.0059201041 0.2164720000 986111553 0 402718720 0.0036316577 -0.2182134539 -0.3448330760 3140 1311867275.2041749954 0.0835322440 0.0631992261 0.1179843694 0.0059201230 0.2045850000 986114625 0 402718720 0.0020296702 -0.2186436355 -0.3412470520 3141 1311867275.2371780872 0.0841132179 0.0632058845 0.1179843694 0.0059195452 0.2045550000 986117585 0 402718720 0.0004807451 -0.2188804001 -0.3377623260 3142 1311867275.2668180466 0.0838883221 0.0632124671 0.1179843694 0.0059227365 0.2037160000 986120377 0 402718720 0.0011043781 -0.2184556574 -0.3342159092 3143 1311867275.3026800156 0.0833547041 0.0632188757 0.1179843694 0.0059254500 0.2031210000 986123393 0 402718720 -0.0010406781 -0.2177519053 -0.3306459486 3144 1311867275.3351879120 0.0832628235 0.0632252510 0.1179843694 0.0059251276 0.2038380000 986126297 0 402718720 -0.0015953315 -0.2177119553 -0.3262905478 3145 1311867275.3669109344 0.0831104964 0.0632315738 0.1179843694 0.0059263030 0.2234230000 986129201 0 402718720 -0.0022061728 -0.2180454135 -0.3220279515 3146 1311867275.4038369656 0.0821881220 0.0632375994 0.1179843694 0.0059260222 0.2165760000 986132161 0 402718720 -0.0024316676 -0.2176182270 -0.3180278242 3147 1311867275.4349598885 0.0833224505 0.0632439816 0.1179843694 0.0059267822 0.2157720000 986135065 0 402718720 -0.0027796470 -0.2190384120 -0.3140578270 3148 1311867275.4669399261 0.0831874833 0.0632503169 0.1179843694 0.0059259846 0.2045950000 986137913 0 402718720 -0.0054477109 -0.2192279100 -0.3102663159 3149 1311867275.5037291050 0.0825914815 0.0632564589 0.1179843694 0.0059256171 0.2056940000 986140985 0 402718720 -0.0060019982 -0.2193151265 -0.3062287867 3150 1311867275.5353329182 0.0827913433 0.0632626605 0.1179843694 0.0059264474 0.2037480000 986143889 0 402718720 -0.0060372422 -0.2194911242 -0.3024488091 3151 1311867275.5668909550 0.0826740786 0.0632688209 0.1179843694 0.0059285326 0.2058290000 986146737 0 402718720 -0.0082922708 -0.2196153551 -0.2992152274 3152 1311867275.6028299332 0.0826394781 0.0632749664 0.1179843694 0.0059288236 0.2058700000 986149809 0 402718720 -0.0083887763 -0.2205381989 -0.2952668965 3153 1311867275.6383280754 0.0826274827 0.0632811042 0.1179843694 0.0059291634 0.2053900000 986152825 0 402718720 -0.0101170987 -0.2208536118 -0.2919152379 3154 1311867275.6682209969 0.0831625387 0.0632874078 0.1179843694 0.0059287769 0.2031660000 986155617 0 402718720 -0.0117639573 -0.2220803648 -0.2884992063 3155 1311867275.7045888901 0.0830243677 0.0632936635 0.1179843694 0.0059282499 0.2260180000 986158633 0 402718720 -0.0137269907 -0.2225722671 -0.2854168713 3156 1311867275.7349820137 0.0828725174 0.0632998672 0.1179843694 0.0059275179 0.2050390000 986161425 0 402718720 -0.0145690981 -0.2230924815 -0.2823120356 3157 1311867275.7792279720 0.0817618743 0.0633057152 0.1179843694 0.0059279459 0.2021780000 986164777 0 402718720 -0.0163813569 -0.2235730290 -0.2794475257 3158 1311867275.8028490543 0.0826721862 0.0633118477 0.1179843694 0.0059280126 0.2044020000 986167401 0 402718720 -0.0183934029 -0.2238789052 -0.2760300934 3159 1311867275.8355960846 0.0823434442 0.0633178723 0.1179843694 0.0059284365 0.2046770000 986170249 0 402718720 -0.0199279692 -0.2233016640 -0.2726011574 3160 1311867275.8701560497 0.0817707032 0.0633237118 0.1179843694 0.0059278484 0.2185960000 986173265 0 402718720 -0.0203861296 -0.2231983393 -0.2695927322 3161 1311867275.9032120705 0.0819793046 0.0633296136 0.1179843694 0.0059270704 0.2049910000 986176225 0 402718720 -0.0227118768 -0.2237514108 -0.2664973438 3162 1311867275.9371318817 0.0819831789 0.0633355129 0.1179843694 0.0059261733 0.2042410000 986179185 0 402718720 -0.0242893919 -0.2239380628 -0.2633766532 3163 1311867275.9683859348 0.0814827830 0.0633412502 0.1179843694 0.0059257758 0.2040350000 986182089 0 402718720 -0.0244499203 -0.2232152373 -0.2599139810 3164 1311867276.0048470497 0.0812310055 0.0633469044 0.1179843694 0.0059277484 0.2047870000 986185105 0 402718720 -0.0266721044 -0.2232172191 -0.2568181753 3165 1311867276.0387539864 0.0809701681 0.0633524725 0.1179843694 0.0059282953 0.2137340000 986188065 0 402718720 -0.0279355757 -0.2241782993 -0.2534992695 3166 1311867276.0739030838 0.0813318565 0.0633581514 0.1179843694 0.0059291216 0.2056810000 986191081 0 402718720 -0.0282345377 -0.2236539274 -0.2503152788 3167 1311867276.1051371098 0.0814829618 0.0633638745 0.1179843694 0.0059301823 0.2061520000 986193985 0 402718720 -0.0297873747 -0.2239596844 -0.2472043931 3168 1311867276.1382379532 0.0827130079 0.0633699821 0.1179843694 0.0059314439 0.2056720000 986196833 0 402718720 -0.0316673554 -0.2251138985 -0.2438898534 3169 1311867276.1709389687 0.0822856352 0.0633759511 0.1179843694 0.0059336272 0.2055430000 986199737 0 402718720 -0.0321642868 -0.2252063602 -0.2406580150 3170 1311867276.2042279243 0.0823952556 0.0633819509 0.1179843694 0.0059328460 0.2058390000 986202753 0 402718720 -0.0330511704 -0.2249253690 -0.2373082191 3171 1311867276.2357859612 0.0823438391 0.0633879307 0.1179843694 0.0059320492 0.2054080000 986205601 0 402718720 -0.0339361541 -0.2242677957 -0.2339900732 3172 1311867276.2747719288 0.0817271695 0.0633937123 0.1179843694 0.0059312547 0.2060910000 986208729 0 402718720 -0.0343366154 -0.2241746932 -0.2311595082 3173 1311867276.3027520180 0.0827420726 0.0633998101 0.1179843694 0.0059319214 0.2048660000 986211465 0 402718720 -0.0349048413 -0.2242693305 -0.2282443643 3174 1311867276.3387188911 0.0825324506 0.0634058380 0.1179843694 0.0059316273 0.2052050000 986214481 0 402718720 -0.0357469171 -0.2249125391 -0.2256936282 3175 1311867276.3729600906 0.0828659758 0.0634119672 0.1179843694 0.0059308156 0.2165290000 986217441 0 402718720 -0.0379167050 -0.2255946696 -0.2232647985 3176 1311867276.4031929970 0.0830538645 0.0634181517 0.1179843694 0.0059312135 0.2047890000 986220289 0 402718720 -0.0387306102 -0.2260995060 -0.2209946513 3177 1311867276.4360129833 0.0827923045 0.0634242499 0.1179843694 0.0059311161 0.2049750000 986223193 0 402718720 -0.0410445780 -0.2266401201 -0.2183737606 3178 1311867276.4737091064 0.0829842761 0.0634304047 0.1179843694 0.0059324121 0.2044370000 986226321 0 402718720 -0.0416211113 -0.2272466719 -0.2158593833 3179 1311867276.5048420429 0.0826793090 0.0634364598 0.1179843694 0.0059321315 0.2029000000 986229169 0 402718720 -0.0423019119 -0.2267570645 -0.2136896551 3180 1311867276.5387470722 0.0825759992 0.0634424785 0.1179843694 0.0059317373 0.2194200000 986232129 0 402718720 -0.0429574624 -0.2266243994 -0.2115897089 3181 1311867276.5746779442 0.0822770000 0.0634483994 0.1179843694 0.0059308758 0.2031160000 986235145 0 402718720 -0.0446175188 -0.2262386680 -0.2089840025 3182 1311867276.6041920185 0.0819729343 0.0634542211 0.1179843694 0.0059299822 0.2032940000 986237881 0 402718720 -0.0444470309 -0.2257565707 -0.2064353824 3183 1311867276.6361470222 0.0823404789 0.0634601546 0.1179843694 0.0059290660 0.2075780000 986240729 0 402718720 -0.0450360663 -0.2265537232 -0.2039465010 3184 1311867276.6710920334 0.0821500123 0.0634660245 0.1179843694 0.0059289581 0.2051480000 986243745 0 402718720 -0.0461788699 -0.2265169322 -0.2013553381 3185 1311867276.7029719353 0.0825403482 0.0634720133 0.1179843694 0.0059304419 0.2142010000 986246649 0 402718720 -0.0462178066 -0.2264747769 -0.1986167431 3186 1311867276.7360780239 0.0826013014 0.0634780175 0.1179843694 0.0059298887 0.2148640000 986249553 0 402718720 -0.0473963767 -0.2274723351 -0.1962791085 3187 1311867276.7721960545 0.0811483860 0.0634835620 0.1179843694 0.0059346407 0.2043010000 986252625 0 402718720 -0.0475984067 -0.2281176001 -0.1941232681 3188 1311867276.8029088974 0.0822606906 0.0634894519 0.1179843694 0.0059419569 0.2151500000 986255473 0 402718720 -0.0488071889 -0.2280732542 -0.1922229975 3189 1311867276.8375699520 0.0824498609 0.0634953975 0.1179843694 0.0059431643 0.2044290000 986258433 0 402718720 -0.0502703302 -0.2284801155 -0.1905396134 3190 1311867276.8740971088 0.0827223882 0.0635014248 0.1179843694 0.0059430850 0.2330220000 986261505 0 402718720 -0.0511111207 -0.2290318012 -0.1885359138 3191 1311867276.9029750824 0.0825632811 0.0635073984 0.1179843694 0.0059440668 0.2038740000 986264297 0 402718720 -0.0518496893 -0.2285266221 -0.1865716875 3192 1311867276.9374980927 0.0816192180 0.0635130725 0.1179843694 0.0059461743 0.2046430000 986267257 0 402718720 -0.0531127155 -0.2287235707 -0.1846307665 3193 1311867276.9726910591 0.0817432031 0.0635187819 0.1179843694 0.0059458877 0.2039890000 986270273 0 402718720 -0.0530910045 -0.2291558981 -0.1820569634 3194 1311867277.0050029755 0.0813582838 0.0635243672 0.1179843694 0.0059460150 0.2036810000 986273233 0 402718720 -0.0534354076 -0.2286128104 -0.1792948246 3195 1311867277.0356070995 0.0807883665 0.0635297707 0.1179843694 0.0059452634 0.2137180000 986276081 0 402718720 -0.0527650528 -0.2277393490 -0.1764015704 3196 1311867277.0711610317 0.0803328305 0.0635350282 0.1179843694 0.0059444465 0.2041740000 986279041 0 402718720 -0.0522209480 -0.2280604541 -0.1736444384 3197 1311867277.1039769650 0.0809607282 0.0635404789 0.1179843694 0.0059442710 0.2038090000 986282001 0 402718720 -0.0532183833 -0.2290032357 -0.1704505682 3198 1311867277.1350269318 0.0806530863 0.0635458299 0.1179843694 0.0059448669 0.2050090000 986284793 0 402718720 -0.0527077615 -0.2278424501 -0.1672331840 3199 1311867277.1708490849 0.0807948783 0.0635512219 0.1179843694 0.0059446509 0.2191160000 986287809 0 402718720 -0.0532113351 -0.2269451469 -0.1641002744 3200 1311867277.2029759884 0.0810306668 0.0635566842 0.1179843694 0.0059440827 0.2268130000 986290769 0 402718720 -0.0528363213 -0.2269159704 -0.1609719545 3201 1311867277.2351000309 0.0815746337 0.0635623131 0.1179843694 0.0059433510 0.2057790000 986293673 0 402718720 -0.0532040745 -0.2275364548 -0.1580997556 3202 1311867277.2733149529 0.0807804018 0.0635676904 0.1179843694 0.0059431631 0.2053270000 986296801 0 402718720 -0.0530340709 -0.2272072136 -0.1551028043 3203 1311867277.3063778877 0.0809156299 0.0635731065 0.1179843694 0.0059422526 0.2052920000 986299705 0 402718720 -0.0535792261 -0.2266954780 -0.1519900411 3204 1311867277.3396029472 0.0804387927 0.0635783705 0.1179843694 0.0059414755 0.2048830000 986302665 0 402718720 -0.0541970804 -0.2258837521 -0.1491392404 3205 1311867277.3773889542 0.0799114779 0.0635834666 0.1179843694 0.0059415820 0.2291220000 986305681 0 402718720 -0.0539602526 -0.2262717187 -0.1463911235 3206 1311867277.4055531025 0.0811760798 0.0635889540 0.1179843694 0.0059409203 0.2049340000 986308417 0 402718720 -0.0566160306 -0.2268961370 -0.1433900595 3207 1311867277.4425079823 0.0806905478 0.0635942866 0.1179843694 0.0059406700 0.2049820000 986311433 0 402718720 -0.0578463562 -0.2266602218 -0.1404549479 3208 1311867277.4723749161 0.0809036642 0.0635996823 0.1179843694 0.0059474781 0.2041350000 986314281 0 402718720 -0.0572022758 -0.2251001149 -0.1376441419 3209 1311867277.5057780743 0.0802541003 0.0636048722 0.1179843694 0.0059503592 0.2039330000 986317129 0 402718720 -0.0577236190 -0.2258107066 -0.1348344237 3210 1311867277.5401940346 0.0795342103 0.0636098346 0.1179843694 0.0059569649 0.2222140000 986320145 0 402718720 -0.0582449622 -0.2270770222 -0.1322027594 3211 1311867277.5715351105 0.0796722397 0.0636148369 0.1179843694 0.0059607326 0.2041170000 986323049 0 402718720 -0.0581358187 -0.2264737785 -0.1299683303 3212 1311867277.6027710438 0.0800344497 0.0636199489 0.1179843694 0.0059601429 0.2026680000 986325897 0 402718720 -0.0579050630 -0.2265326977 -0.1275179237 3213 1311867277.6416130066 0.0803496838 0.0636251558 0.1179843694 0.0059615362 0.2034050000 986328969 0 402718720 -0.0592348427 -0.2282586843 -0.1253175139 3214 1311867277.6713008881 0.0806485787 0.0636304524 0.1179843694 0.0059609900 0.2024390000 986331873 0 402718720 -0.0593954921 -0.2287736982 -0.1230542436 3215 1311867277.7063589096 0.0796141475 0.0636354240 0.1179843694 0.0059620041 0.2230890000 986334777 0 402718720 -0.0629736409 -0.2271290570 -0.1211756989 3216 1311867277.7401409149 0.0784033984 0.0636400160 0.1179843694 0.0059613996 0.2034810000 986337737 0 402718720 -0.0627461821 -0.2260829806 -0.1187119484 3217 1311867277.7720079422 0.0786011517 0.0636446667 0.1179843694 0.0059605629 0.2032770000 986340641 0 402718720 -0.0629884079 -0.2259779125 -0.1157272458 3218 1311867277.8036880493 0.0786139295 0.0636493184 0.1179843694 0.0059601228 0.2029510000 986343545 0 402718720 -0.0623857565 -0.2254410684 -0.1124662831 3219 1311867277.8400499821 0.0785281360 0.0636539406 0.1179843694 0.0059592303 0.2030860000 986346561 0 402718720 -0.0619348809 -0.2250349522 -0.1090329066 3220 1311867277.8711171150 0.0789135620 0.0636586796 0.1179843694 0.0059596474 0.2187040000 986349465 0 402718720 -0.0614030585 -0.2263880521 -0.1055013314 3221 1311867277.9031610489 0.0798062757 0.0636636928 0.1179843694 0.0059587631 0.2035900000 986352369 0 402718720 -0.0625782758 -0.2269867808 -0.1020767689 3222 1311867277.9393019676 0.0796284601 0.0636686478 0.1179843694 0.0059585695 0.2030200000 986355385 0 402718720 -0.0612595417 -0.2261137664 -0.0982509106 3223 1311867277.9714229107 0.0798760727 0.0636736764 0.1179843694 0.0059591020 0.2156400000 986358289 0 402718720 -0.0616459548 -0.2264348269 -0.0948365927 3224 1311867278.0041360855 0.0806828737 0.0636789522 0.1179843694 0.0059581943 0.2023880000 986361193 0 402718720 -0.0607572012 -0.2273570150 -0.0914218128 3225 1311867278.0394210815 0.0810714960 0.0636843453 0.1179843694 0.0059584458 0.2014590000 986364153 0 402718720 -0.0604192875 -0.2279364765 -0.0881912485 3226 1311867278.0712630749 0.0808835626 0.0636896767 0.1179843694 0.0059580474 0.1987340000 986367057 0 402718720 -0.0596351735 -0.2274228185 -0.0846012458 3227 1311867278.1056289673 0.0806204826 0.0636949233 0.1179843694 0.0059571583 0.2106210000 986370073 0 402718720 -0.0593043715 -0.2272104323 -0.0811090395 3228 1311867278.1391980648 0.0810712352 0.0637003063 0.1179843694 0.0059564019 0.1990520000 986372977 0 402718720 -0.0593636930 -0.2276258916 -0.0772471577 3229 1311867278.1710369587 0.0806837529 0.0637055660 0.1179843694 0.0059556399 0.2091080000 986375881 0 402718720 -0.0582567975 -0.2271252573 -0.0732429996 3230 1311867278.2038609982 0.0806551799 0.0637108135 0.1179843694 0.0059573674 0.2244180000 986378841 0 402718720 -0.0575383790 -0.2262250781 -0.0696959347 3231 1311867278.2388060093 0.0800310075 0.0637158647 0.1179843694 0.0059626063 0.1971990000 986381857 0 402718720 -0.0572595224 -0.2264729589 -0.0662784129 3232 1311867278.2707629204 0.0805636421 0.0637210775 0.1179843694 0.0059639214 0.1961250000 986384705 0 402718720 -0.0573001280 -0.2265161574 -0.0628735498 3233 1311867278.3027629852 0.0801360533 0.0637261548 0.1179843694 0.0059633778 0.1955310000 986387609 0 402718720 -0.0555516295 -0.2254099399 -0.0595612600 3234 1311867278.3421599865 0.0797755644 0.0637311175 0.1179843694 0.0059630287 0.1946930000 986390737 0 402718720 -0.0554595031 -0.2256350815 -0.0565739013 3235 1311867278.3714361191 0.0802818686 0.0637362337 0.1179843694 0.0059621089 0.2022500000 986393529 0 402718720 -0.0555957593 -0.2263835371 -0.0535370708 3236 1311867278.4035348892 0.0802650377 0.0637413414 0.1179843694 0.0059612593 0.1929490000 986396489 0 402718720 -0.0544749722 -0.2257871777 -0.0502708554 3237 1311867278.4391169548 0.0793169290 0.0637461532 0.1179843694 0.0059606540 0.1922160000 986399449 0 402718720 -0.0539061576 -0.2250547260 -0.0472689420 3238 1311867278.4713339806 0.0793253258 0.0637509645 0.1179843694 0.0059602270 0.1914790000 986402409 0 402718720 -0.0536150299 -0.2259965390 -0.0445836298 3239 1311867278.5041239262 0.0796490535 0.0637558729 0.1179843694 0.0059597550 0.1945700000 986405313 0 402718720 -0.0538207665 -0.2274264395 -0.0416954570 3240 1311867278.5423910618 0.0791390687 0.0637606208 0.1179843694 0.0059591669 0.2065600000 986408385 0 402718720 -0.0529877767 -0.2274817675 -0.0383734293 3241 1311867278.5710260868 0.0782359764 0.0637650871 0.1179843694 0.0059586712 0.1876270000 986411177 0 402718720 -0.0514543243 -0.2263249308 -0.0351150967 3242 1311867278.6069030762 0.0780138597 0.0637694822 0.1179843694 0.0059581087 0.1865360000 986414193 0 402718720 -0.0513191186 -0.2261262536 -0.0320092924 3243 1311867278.6393239498 0.0779831707 0.0637738650 0.1179843694 0.0059576340 0.1859550000 986417097 0 402718720 -0.0519599020 -0.2264808714 -0.0286745634 3244 1311867278.6709709167 0.0771368891 0.0637779843 0.1179843694 0.0059600067 0.1855510000 986420057 0 402718720 -0.0516494289 -0.2252607942 -0.0255233534 3245 1311867278.7069129944 0.0768123567 0.0637820011 0.1179843694 0.0059591073 0.1977350000 986423017 0 402718720 -0.0501919910 -0.2243860364 -0.0221479796 3246 1311867278.7390680313 0.0769220591 0.0637860492 0.1179843694 0.0059590888 0.1862110000 986425921 0 402718720 -0.0504692271 -0.2254250050 -0.0190353617 3247 1311867278.7718300819 0.0776341781 0.0637903141 0.1179843694 0.0059590502 0.1851480000 986428825 0 402718720 -0.0506899320 -0.2263229042 -0.0159201473 3248 1311867278.8068239689 0.0766730681 0.0637942804 0.1179843694 0.0059584423 0.1846710000 986431841 0 402718720 -0.0491830371 -0.2247624397 -0.0127295693 3249 1311867278.8386530876 0.0768496692 0.0637982987 0.1179843694 0.0059580578 0.1850540000 986434801 0 402718720 -0.0485308878 -0.2248716801 -0.0097520063 3250 1311867278.8741700649 0.0774632916 0.0638025033 0.1179843694 0.0059575203 0.2042850000 986437761 0 402718720 -0.0489824526 -0.2265602797 -0.0067111007 3251 1311867278.9090650082 0.0767378286 0.0638064822 0.1179843694 0.0059569760 0.1964400000 986440721 0 402718720 -0.0483600534 -0.2253941000 -0.0036549382 3252 1311867278.9392769337 0.0758376792 0.0638101818 0.1179843694 0.0059572463 0.1839460000 986443625 0 402718720 -0.0474123359 -0.2231667638 -0.0008232918 3253 1311867278.9711430073 0.0762109384 0.0638139939 0.1179843694 0.0059564747 0.1848220000 986446529 0 402718720 -0.0476709381 -0.2241163552 0.0019582650 3254 1311867279.0073111057 0.0763596520 0.0638178494 0.1179843694 0.0059575469 0.1849760000 986449545 0 402718720 -0.0480974652 -0.2252796292 0.0048664212 3255 1311867279.0397729874 0.0756578147 0.0638214869 0.1179843694 0.0059576767 0.1850670000 986452449 0 402718720 -0.0468250476 -0.2240130156 0.0080333464 3256 1311867279.0738539696 0.0750224516 0.0638249270 0.1179843694 0.0059571362 0.1856860000 986455409 0 402718720 -0.0466185361 -0.2234793752 0.0111631071 3257 1311867279.1068439484 0.0756729096 0.0638285647 0.1179843694 0.0059563821 0.1859590000 986458313 0 402718720 -0.0471011437 -0.2239402831 0.0139596704 3258 1311867279.1392490864 0.0750183314 0.0638319992 0.1179843694 0.0059556309 0.1844260000 986461273 0 402718720 -0.0465036258 -0.2238717824 0.0168708786 3259 1311867279.1712040901 0.0755301267 0.0638355887 0.1179843694 0.0059613720 0.1848360000 986464121 0 402718720 -0.0453144982 -0.2223719656 0.0198998246 3260 1311867279.2070438862 0.0751715973 0.0638390660 0.1179843694 0.0059619687 0.2044670000 986467137 0 402718720 -0.0460240357 -0.2220266610 0.0227560923 3261 1311867279.2411210537 0.0756119266 0.0638426762 0.1179843694 0.0059619504 0.1861940000 986470097 0 402718720 -0.0463315956 -0.2227285206 0.0255993009 3262 1311867279.2717759609 0.0755109042 0.0638462532 0.1179843694 0.0059614555 0.1861510000 986472945 0 402718720 -0.0454867445 -0.2218361795 0.0286474712 3263 1311867279.3067219257 0.0754820704 0.0638498192 0.1179843694 0.0059612011 0.1867790000 986475961 0 402718720 -0.0452449247 -0.2205971330 0.0314313844 3264 1311867279.3388090134 0.0757369623 0.0638534611 0.1179843694 0.0059621476 0.1867520000 986478865 0 402718720 -0.0455544181 -0.2206959277 0.0343557484 3265 1311867279.3804929256 0.0746103749 0.0638567557 0.1179843694 0.0059638087 0.1875620000 986482049 0 402718720 -0.0451864414 -0.2201031595 0.0372565687 3266 1311867279.4089910984 0.0749232918 0.0638601441 0.1179843694 0.0059637675 0.1871990000 986484729 0 402718720 -0.0444485173 -0.2188801020 0.0401492119 3267 1311867279.4410970211 0.0741993561 0.0638633089 0.1179843694 0.0059636867 0.1871360000 986487633 0 402718720 -0.0446820818 -0.2183311731 0.0430287309 3268 1311867279.4725570679 0.0756170750 0.0638669055 0.1179843694 0.0059628378 0.1870830000 986490537 0 402718720 -0.0445094034 -0.2192665935 0.0461538173 3269 1311867279.5095710754 0.0750217363 0.0638703178 0.1179843694 0.0059621624 0.1874540000 986493609 0 402718720 -0.0442351028 -0.2183219492 0.0491255708 3270 1311867279.5407390594 0.0745662823 0.0638735887 0.1179843694 0.0059624101 0.1884500000 986496345 0 402718720 -0.0445481949 -0.2178281099 0.0518470109 3271 1311867279.5734229088 0.0758126006 0.0638772387 0.1179843694 0.0059619548 0.1876720000 986499361 0 402718720 -0.0451440997 -0.2191061229 0.0545017123 3272 1311867279.6121640205 0.0751523972 0.0638806846 0.1179843694 0.0059618966 0.1878460000 986502433 0 402718720 -0.0450848117 -0.2190518230 0.0571620278 3273 1311867279.6389439106 0.0752326399 0.0638841530 0.1179843694 0.0059628737 0.1879250000 986505169 0 402718720 -0.0443113633 -0.2181846648 0.0596041419 3274 1311867279.6749770641 0.0750894845 0.0638875755 0.1179843694 0.0059643981 0.2010640000 986508241 0 402718720 -0.0446897708 -0.2189337313 0.0620136149 3275 1311867279.7107980251 0.0748375505 0.0638909190 0.1179843694 0.0059638550 0.1896260000 986511145 0 402718720 -0.0445279032 -0.2187078297 0.0647156537 3276 1311867279.7410199642 0.0746343732 0.0638941985 0.1179843694 0.0059632012 0.2073040000 986513993 0 402718720 -0.0439293645 -0.2174301147 0.0673657805 3277 1311867279.7777059078 0.0740353912 0.0638972931 0.1179843694 0.0059626248 0.2028010000 986517065 0 402718720 -0.0432669036 -0.2174664736 0.0701214969 3278 1311867279.8118851185 0.0749419704 0.0639006625 0.1179843694 0.0059622667 0.1900700000 986520025 0 402718720 -0.0431773923 -0.2179592103 0.0730386376 3279 1311867279.8438251019 0.0740222260 0.0639037492 0.1179843694 0.0059616016 0.1896160000 986522929 0 402718720 -0.0418855138 -0.2172592878 0.0761936009 3280 1311867279.8808829784 0.0737588555 0.0639067538 0.1179843694 0.0059641667 0.2017810000 986525945 0 402718720 -0.0407253988 -0.2169834524 0.0790707916 3281 1311867279.9088180065 0.0747813657 0.0639100683 0.1179843694 0.0059642626 0.1905580000 986528793 0 402718720 -0.0404527858 -0.2181024253 0.0818737000 3282 1311867279.9440410137 0.0748905912 0.0639134139 0.1179843694 0.0059637932 0.1903400000 986531809 0 402718720 -0.0400702134 -0.2179835290 0.0851052403 3283 1311867279.9795188904 0.0744417086 0.0639166209 0.1179843694 0.0059669983 0.2020610000 986534769 0 402718720 -0.0389050618 -0.2163397521 0.0882186741 3284 1311867280.0113790035 0.0743546709 0.0639197993 0.1179843694 0.0059681801 0.2005090000 986537617 0 402718720 -0.0386296660 -0.2164217979 0.0911765620 3285 1311867280.0401859283 0.0746017620 0.0639230511 0.1179843694 0.0059681750 0.1904480000 986540409 0 402718720 -0.0382714309 -0.2157906294 0.0944214910 3286 1311867280.0785079002 0.0744641051 0.0639262589 0.1179843694 0.0059687949 0.1903340000 986543481 0 402718720 -0.0370238349 -0.2142068744 0.0978254676 3287 1311867280.1111929417 0.0754992887 0.0639297798 0.1179843694 0.0059683595 0.1903530000 986546385 0 402718720 -0.0363315754 -0.2152057439 0.1007703468 3288 1311867280.1450068951 0.0758911893 0.0639334177 0.1179843694 0.0059674742 0.2025440000 986549401 0 402718720 -0.0366441719 -0.2155489326 0.1037533656 3289 1311867280.1753098965 0.0756731555 0.0639369871 0.1179843694 0.0059688387 0.1901570000 986552193 0 402718720 -0.0359667316 -0.2139261365 0.1067597941 3290 1311867280.2123339176 0.0757475495 0.0639405769 0.1179843694 0.0059695150 0.1909540000 986555265 0 402718720 -0.0350837298 -0.2142265737 0.1095982492 3291 1311867280.2422859669 0.0765010193 0.0639443935 0.1179843694 0.0059686950 0.1898420000 986558113 0 402718720 -0.0352333449 -0.2151121795 0.1124279276 3292 1311867280.2794580460 0.0760213882 0.0639480621 0.1179843694 0.0059722343 0.1902820000 986561185 0 402718720 -0.0342364013 -0.2132157832 0.1152993366 3293 1311867280.3114728928 0.0763393268 0.0639518250 0.1179843694 0.0059725116 0.1908170000 986564089 0 402718720 -0.0347570069 -0.2140192837 0.1178907901 3294 1311867280.3445079327 0.0771636888 0.0639558359 0.1179843694 0.0059729770 0.1908020000 986566937 0 402718720 -0.0348005481 -0.2144413441 0.1208447292 3295 1311867280.3755340576 0.0769387856 0.0639597761 0.1179843694 0.0059727203 0.2029990000 986569841 0 402718720 -0.0337955765 -0.2130288482 0.1236280277 3296 1311867280.4071900845 0.0773746520 0.0639638461 0.1179843694 0.0059722467 0.1908300000 986572689 0 402718720 -0.0341796130 -0.2138485909 0.1261019707 3297 1311867280.4424109459 0.0777338222 0.0639680227 0.1179843694 0.0059729401 0.1910840000 986575705 0 402718720 -0.0334907807 -0.2134225965 0.1287270784 3298 1311867280.4782869816 0.0768678188 0.0639719341 0.1179843694 0.0059730122 0.1914490000 986578721 0 402718720 -0.0325638726 -0.2126759589 0.1313138753 3299 1311867280.5091259480 0.0773337632 0.0639759843 0.1179843694 0.0059722867 0.1905650000 986581625 0 402718720 -0.0322466865 -0.2127941251 0.1339548826 3300 1311867280.5455989838 0.0775946081 0.0639801112 0.1179843694 0.0059714775 0.2008350000 986584585 0 402718720 -0.0320751891 -0.2126149386 0.1367013007 3301 1311867280.5782079697 0.0776842684 0.0639842627 0.1179843694 0.0059718383 0.1902650000 986587489 0 402718720 -0.0318324082 -0.2115809768 0.1393766701 3302 1311867280.6130499840 0.0775882080 0.0639883826 0.1179843694 0.0059717581 0.2062470000 986590449 0 402718720 -0.0318429954 -0.2116653025 0.1418347657 3303 1311867280.6422739029 0.0784304067 0.0639927550 0.1179843694 0.0059720510 0.1908940000 986593297 0 402718720 -0.0318216383 -0.2124989927 0.1443538070 3304 1311867280.6755290031 0.0787148625 0.0639972108 0.1179843694 0.0059715537 0.1900660000 986596257 0 402718720 -0.0313378349 -0.2122816741 0.1470269412 3305 1311867280.7094879150 0.0788749829 0.0640017124 0.1179843694 0.0059706591 0.2186690000 986599217 0 402718720 -0.0308790039 -0.2124921083 0.1493055522 3306 1311867280.7411808968 0.0779884756 0.0640059432 0.1179843694 0.0059714586 0.1908820000 986602065 0 402718720 -0.0308814608 -0.2126226872 0.1516459435 3307 1311867280.7752668858 0.0788833722 0.0640104419 0.1179843694 0.0059721535 0.1906840000 986605025 0 402718720 -0.0311269406 -0.2122232169 0.1539199948 3308 1311867280.8076250553 0.0787598044 0.0640149006 0.1179843694 0.0059712768 0.2015910000 986607929 0 402718720 -0.0309946500 -0.2117981911 0.1562175900 3309 1311867280.8401010036 0.0788924396 0.0640193967 0.1179843694 0.0059704544 0.2008920000 986610889 0 402718720 -0.0308827274 -0.2114341855 0.1585526168 3310 1311867280.8754839897 0.0785943866 0.0640238000 0.1179843694 0.0059695987 0.2293430000 986613849 0 402718720 -0.0303842351 -0.2114278078 0.1609847546 3311 1311867280.9079110622 0.0785045996 0.0640281736 0.1179843694 0.0059687006 0.2110520000 986616753 0 402718720 -0.0304796752 -0.2110081017 0.1633855402 3312 1311867280.9394528866 0.0785567388 0.0640325602 0.1179843694 0.0059678200 0.1898980000 986619713 0 402718720 -0.0305594523 -0.2106619626 0.1659286022 3313 1311867280.9766991138 0.0783902407 0.0640368940 0.1179843694 0.0059669717 0.1904370000 986622617 0 402718720 -0.0301216170 -0.2104413509 0.1686116904 3314 1311867281.0075190067 0.0785273537 0.0640412664 0.1179843694 0.0059661457 0.1903940000 986625521 0 402718720 -0.0297692921 -0.2103769779 0.1711196899 3315 1311867281.0433430672 0.0784832314 0.0640456230 0.1179843694 0.0059653544 0.1909280000 986628537 0 402718720 -0.0299781561 -0.2105564922 0.1736894995 3316 1311867281.0752780437 0.0786643997 0.0640500316 0.1179843694 0.0059645917 0.1902450000 986631385 0 402718720 -0.0290192049 -0.2105149180 0.1763833910 3317 1311867281.1074900627 0.0787610635 0.0640544666 0.1179843694 0.0059641593 0.1907860000 986634345 0 402718720 -0.0290967561 -0.2100835592 0.1790533662 3318 1311867281.1451520920 0.0785907730 0.0640588476 0.1179843694 0.0059638957 0.1892560000 986637361 0 402718720 -0.0286562759 -0.2103645653 0.1814487427 3319 1311867281.1786689758 0.0790678039 0.0640633698 0.1179843694 0.0059639400 0.1891730000 986640377 0 402718720 -0.0277797375 -0.2103538513 0.1839077771 3320 1311867281.2083299160 0.0793333501 0.0640679692 0.1179843694 0.0059630953 0.1999500000 986643225 0 402718720 -0.0266670994 -0.2098387480 0.1863692105 3321 1311867281.2457950115 0.0791389272 0.0640725072 0.1179843694 0.0059636889 0.1874790000 986646241 0 402718720 -0.0264560729 -0.2103981078 0.1885271370 3322 1311867281.2754399776 0.0801365748 0.0640773429 0.1179843694 0.0059629519 0.1893500000 986649033 0 402718720 -0.0258448143 -0.2105961591 0.1909516901 3323 1311867281.3072988987 0.0800037682 0.0640821357 0.1179843694 0.0059651106 0.1894010000 986651993 0 402718720 -0.0250174999 -0.2098166198 0.1934292465 3324 1311867281.3465099335 0.0797589421 0.0640868519 0.1179843694 0.0059669069 0.1882700000 986655065 0 402718720 -0.0243095458 -0.2101970613 0.1957508326 3325 1311867281.3751530647 0.0805769190 0.0640918114 0.1179843694 0.0059660285 0.2183030000 986657857 0 402718720 -0.0237756502 -0.2112325579 0.1981566697 3326 1311867281.4080700874 0.0804311708 0.0640967240 0.1179843694 0.0059652516 0.1891740000 986660817 0 402718720 -0.0226984490 -0.2106293142 0.2005304545 3327 1311867281.4434111118 0.0804916844 0.0641016518 0.1179843694 0.0059647756 0.1885420000 986663833 0 402718720 -0.0222759619 -0.2109438777 0.2028333098 3328 1311867281.4753720760 0.0810080916 0.0641067319 0.1179843694 0.0059639450 0.2129080000 986666681 0 402718720 -0.0221860204 -0.2117827535 0.2050630599 3329 1311867281.5101969242 0.0808230937 0.0641117533 0.1179843694 0.0059637260 0.1884820000 986669697 0 402718720 -0.0215156637 -0.2112271339 0.2074107379 3330 1311867281.5435659885 0.0804775506 0.0641166680 0.1179843694 0.0059636067 0.2019930000 986672657 0 402718720 -0.0208844133 -0.2111823261 0.2096334696 3331 1311867281.5754749775 0.0812945738 0.0641218250 0.1179843694 0.0059628390 0.1881230000 986675561 0 402718720 -0.0204616059 -0.2122665495 0.2118800879 3332 1311867281.6111190319 0.0811568126 0.0641269375 0.1179843694 0.0059626514 0.1878480000 986678521 0 402718720 -0.0196658503 -0.2118986994 0.2140738219 3333 1311867281.6435608864 0.0811408609 0.0641320422 0.1179843694 0.0059618359 0.1879640000 986681481 0 402718720 -0.0190551300 -0.2117467672 0.2160853893 3334 1311867281.6755120754 0.0814961940 0.0641372504 0.1179843694 0.0059614429 0.1879730000 986684385 0 402718720 -0.0185939278 -0.2127871811 0.2179728299 3335 1311867281.7089190483 0.0819310397 0.0641425859 0.1179843694 0.0059605713 0.2072410000 986687289 0 402718720 -0.0178448502 -0.2132611424 0.2199863046 3336 1311867281.7452239990 0.0816798136 0.0641478428 0.1179843694 0.0059599690 0.1879310000 986690361 0 402718720 -0.0167885274 -0.2129125148 0.2217908651 3337 1311867281.7755289078 0.0822224766 0.0641532593 0.1179843694 0.0059596911 0.1874960000 986693153 0 402718720 -0.0163105018 -0.2140188068 0.2233962566 3338 1311867281.8075580597 0.0822572038 0.0641586828 0.1179843694 0.0059591772 0.2011540000 986696057 0 402718720 -0.0150955459 -0.2144072056 0.2250469029 3339 1311867281.8447821140 0.0820561647 0.0641640430 0.1179843694 0.0059582981 0.1999360000 986699129 0 402718720 -0.0139417937 -0.2144228965 0.2265364826 3340 1311867281.8756659031 0.0824642554 0.0641695221 0.1179843694 0.0059574064 0.2005890000 986702033 0 402718720 -0.0130977184 -0.2150209546 0.2280127108 3341 1311867281.9077229500 0.0825573206 0.0641750258 0.1179843694 0.0059570223 0.1884080000 986704937 0 402718720 -0.0122579066 -0.2148358226 0.2296005785 3342 1311867281.9444870949 0.0822966471 0.0641804482 0.1179843694 0.0059574032 0.1887460000 986707897 0 402718720 -0.0107622640 -0.2142957151 0.2310515642 3343 1311867281.9785399437 0.0827576295 0.0641860052 0.1179843694 0.0059585929 0.1883980000 986710857 0 402718720 -0.0100056343 -0.2152572572 0.2323077321 3344 1311867282.0098121166 0.0830362737 0.0641916422 0.1179843694 0.0059577454 0.1979480000 986713761 0 402718720 -0.0090467883 -0.2156097144 0.2337572128 3345 1311867282.0436799526 0.0826254934 0.0641971531 0.1179843694 0.0059570834 0.2022560000 986716665 0 402718720 -0.0078588882 -0.2147722244 0.2353155017 3346 1311867282.0755469799 0.0826486275 0.0642026676 0.1179843694 0.0059562287 0.1883510000 986719569 0 402718720 -0.0069261761 -0.2149914503 0.2367467582 3347 1311867282.1077909470 0.0832165107 0.0642083484 0.1179843694 0.0059553635 0.1877500000 986722473 0 402718720 -0.0059353588 -0.2153756022 0.2384901196 3348 1311867282.1464140415 0.0825657398 0.0642138315 0.1179843694 0.0059545234 0.1988080000 986725545 0 402718720 -0.0046682283 -0.2144658417 0.2403429449 3349 1311867282.1797480583 0.0822672173 0.0642192222 0.1179843694 0.0059536574 0.1869210000 986728505 0 402718720 -0.0038859802 -0.2141397893 0.2421169281 3350 1311867282.2136330605 0.0827298388 0.0642247478 0.1179843694 0.0059528333 0.1864630000 986731465 0 402718720 -0.0032474729 -0.2146480232 0.2439712435 3351 1311867282.2453169823 0.0829540193 0.0642303369 0.1179843694 0.0059521298 0.1871980000 986734369 0 402718720 -0.0022529566 -0.2145112753 0.2459034175 3352 1311867282.2844099998 0.0827147141 0.0642358514 0.1179843694 0.0059516945 0.1870880000 986737385 0 402718720 -0.0009103384 -0.2145323604 0.2476766557 3353 1311867282.3187301159 0.0827611983 0.0642413764 0.1179843694 0.0059515887 0.1869900000 986740345 0 402718720 -0.0000500283 -0.2151802778 0.2494588941 3354 1311867282.3445549011 0.0828878209 0.0642469358 0.1179843694 0.0059508138 0.1860650000 986743081 0 402718720 0.0005558455 -0.2150324434 0.2510537803 3355 1311867282.3837130070 0.0830463096 0.0642525392 0.1179843694 0.0059510625 0.2043280000 986745929 0 402718720 0.0014765997 -0.2148517370 0.2528465390 3356 1311867282.4114849567 0.0832435042 0.0642581980 0.1179843694 0.0059507537 0.1866890000 986748665 0 402718720 0.0019629304 -0.2151869982 0.2545498312 3357 1311867282.4437038898 0.0833877847 0.0642638965 0.1179843694 0.0059500376 0.1862150000 986751625 0 402718720 0.0026910356 -0.2154145837 0.2563479543 3358 1311867282.4754569530 0.0830634758 0.0642694949 0.1179843694 0.0059494783 0.1853590000 986754473 0 402718720 0.0033405751 -0.2151902169 0.2580456138 3359 1311867282.5128560066 0.0835517794 0.0642752354 0.1179843694 0.0059489000 0.1856800000 986757545 0 402718720 0.0037785263 -0.2160091698 0.2596901059 3360 1311867282.5435400009 0.0840538815 0.0642811219 0.1179843694 0.0059480317 0.2066450000 986760449 0 402718720 0.0045841499 -0.2166691720 0.2613132894 3361 1311867282.5755639076 0.0835883915 0.0642868664 0.1179843694 0.0059473689 0.1856680000 986763353 0 402718720 0.0050913719 -0.2162927538 0.2628295422 3362 1311867282.6112899780 0.0835666060 0.0642926010 0.1179843694 0.0059467581 0.1861190000 986766313 0 402718720 0.0051196027 -0.2169254571 0.2640456557 3363 1311867282.6437261105 0.0838879719 0.0642984277 0.1179843694 0.0059460741 0.1968340000 986769217 0 402718720 0.0053489720 -0.2172501683 0.2652874589 3364 1311867282.6766591072 0.0839715302 0.0643042759 0.1179843694 0.0059456125 0.2239680000 986772121 0 402718720 0.0058432720 -0.2168576121 0.2663863599 3365 1311867282.7147250175 0.0837749392 0.0643100621 0.1179843694 0.0059449393 0.1848520000 986775193 0 402718720 0.0049298271 -0.2175874412 0.2670802474 3366 1311867282.7462520599 0.0845542252 0.0643160764 0.1179843694 0.0059440689 0.1848740000 986778097 0 402718720 0.0047634523 -0.2182285786 0.2678706050 3367 1311867282.7754290104 0.0841880813 0.0643219784 0.1179843694 0.0059435202 0.1852950000 986780777 0 402718720 0.0045619151 -0.2181947529 0.2685503066 3368 1311867282.8116350174 0.0840742365 0.0643278431 0.1179843694 0.0059427129 0.1863850000 986783737 0 402718720 0.0043281089 -0.2186051756 0.2693588138 3369 1311867282.8475370407 0.0831575021 0.0643334322 0.1179843694 0.0059425947 0.1853490000 986786753 0 402718720 0.0037310207 -0.2178577483 0.2703888118 3370 1311867282.8757910728 0.0825105831 0.0643388260 0.1179843694 0.0059417595 0.1990140000 986789601 0 402718720 0.0035117215 -0.2166924328 0.2715979218 3371 1311867282.9114630222 0.0827455074 0.0643442863 0.1179843694 0.0059408932 0.1856540000 986792561 0 402718720 0.0034443291 -0.2165964842 0.2730760574 3372 1311867282.9456479549 0.0833024234 0.0643499085 0.1179843694 0.0059403395 0.1855740000 986795521 0 402718720 0.0031052607 -0.2164849192 0.2747050524 3373 1311867282.9811890125 0.0828816816 0.0643554027 0.1179843694 0.0059395458 0.1857100000 986798481 0 402718720 0.0028110035 -0.2156719714 0.2761150301 3374 1311867283.0114879608 0.0832892284 0.0643610144 0.1179843694 0.0059389002 0.1843170000 986801385 0 402718720 0.0024776950 -0.2156702578 0.2774371803 3375 1311867283.0462460518 0.0842298940 0.0643669014 0.1179843694 0.0059387359 0.1945810000 986804345 0 402718720 0.0018976413 -0.2164914161 0.2786734402 3376 1311867283.0752930641 0.0841602311 0.0643727644 0.1179843694 0.0059387322 0.1844540000 986807193 0 402718720 0.0015797908 -0.2160972953 0.2798303366 3377 1311867283.1116878986 0.0826397315 0.0643781736 0.1179843694 0.0059398114 0.1844760000 986810265 0 402718720 0.0014289459 -0.2157203108 0.2807700038 3378 1311867283.1435511112 0.0835522488 0.0643838498 0.1179843694 0.0059393483 0.1842440000 986813169 0 402718720 0.0012055074 -0.2169468254 0.2815724015 3379 1311867283.1788220406 0.0832385197 0.0643894297 0.1179843694 0.0059405537 0.1848310000 986816073 0 402718720 0.0011253093 -0.2167033851 0.2823480666 3380 1311867283.2158269882 0.0836856738 0.0643951387 0.1179843694 0.0059403337 0.1977700000 986819145 0 402718720 0.0015406351 -0.2162228227 0.2831003666 3381 1311867283.2441749573 0.0843778178 0.0644010490 0.1179843694 0.0059399872 0.1842590000 986821937 0 402718720 0.0014796237 -0.2176116407 0.2838017344 3382 1311867283.2776839733 0.0845216513 0.0644069983 0.1179843694 0.0059393661 0.1861260000 986824897 0 402718720 0.0015347240 -0.2179901600 0.2847926617 3383 1311867283.3134660721 0.0839924440 0.0644127877 0.1179843694 0.0059387488 0.1855690000 986827913 0 402718720 0.0017611175 -0.2175002545 0.2856677175 3384 1311867283.3498029709 0.0842232034 0.0644186418 0.1179843694 0.0059383144 0.1847810000 986831041 0 402718720 0.0018926255 -0.2179131508 0.2866914868 3385 1311867283.3852219582 0.0841755494 0.0644244784 0.1179843694 0.0059376252 0.2101830000 986834057 0 402718720 0.0018491277 -0.2182310075 0.2877484262 3386 1311867283.4173080921 0.0842446610 0.0644303320 0.1179843694 0.0059373206 0.1952670000 986836905 0 402718720 0.0020479185 -0.2177602649 0.2887738645 3387 1311867283.4492650032 0.0840969607 0.0644361385 0.1179843694 0.0059364858 0.1852120000 986839809 0 402718720 0.0022844106 -0.2174041271 0.2894609272 3388 1311867283.4853370190 0.0843889713 0.0644420277 0.1179843694 0.0059359034 0.1837920000 986842825 0 402718720 0.0018959926 -0.2183641791 0.2900295854 3389 1311867283.5172159672 0.0845368952 0.0644479572 0.1179843694 0.0059350762 0.2065180000 986845729 0 402718720 0.0022216395 -0.2186423391 0.2907445729 3390 1311867283.5495610237 0.0840948075 0.0644537527 0.1179843694 0.0059344641 0.1965440000 986848633 0 402718720 0.0027056294 -0.2180816531 0.2913706601 3391 1311867283.5853879452 0.0841728076 0.0644595678 0.1179843694 0.0059338257 0.1849010000 986851593 0 402718720 0.0027793758 -0.2185137272 0.2918886542 3392 1311867283.6173179150 0.0841112509 0.0644653614 0.1179843694 0.0059332909 0.1852160000 986854497 0 402718720 0.0029293925 -0.2181358784 0.2926348448 3393 1311867283.6493821144 0.0837553591 0.0644710466 0.1179843694 0.0059324631 0.1849010000 986857457 0 402718720 0.0032923468 -0.2173045427 0.2931967974 3394 1311867283.6852879524 0.0836001709 0.0644766828 0.1179843694 0.0059321252 0.1845470000 986860473 0 402718720 0.0031938439 -0.2171290070 0.2937696576 3395 1311867283.7179150581 0.0836207420 0.0644823217 0.1179843694 0.0059313905 0.1916510000 986863321 0 402718720 0.0031089117 -0.2164593637 0.2944948077 3396 1311867283.7492079735 0.0836500600 0.0644879659 0.1179843694 0.0059308425 0.1840850000 986866225 0 402718720 0.0027003889 -0.2155295908 0.2951797247 3397 1311867283.7853169441 0.0840285122 0.0644937182 0.1179843694 0.0059301572 0.1981420000 986869241 0 402718720 0.0026108755 -0.2154875547 0.2957783043 3398 1311867283.8174130917 0.0845388174 0.0644996173 0.1179843694 0.0059294210 0.1848330000 986872089 0 402718720 0.0021518194 -0.2156164199 0.2963946164 3399 1311867283.8494520187 0.0844510943 0.0645054871 0.1179843694 0.0059288382 0.1845530000 986875049 0 402718720 0.0023056425 -0.2148233652 0.2969442010 3400 1311867283.8853459358 0.0843670964 0.0645113287 0.1179843694 0.0059280768 0.1941380000 986878009 0 402718720 0.0016372827 -0.2145276517 0.2972973883 3401 1311867283.9175400734 0.0846868306 0.0645172609 0.1179843694 0.0059272274 0.1846440000 986880913 0 402718720 0.0009489268 -0.2149118334 0.2976642847 3402 1311867283.9498898983 0.0844929069 0.0645231327 0.1179843694 0.0059263606 0.1846440000 986883817 0 402718720 0.0009297153 -0.2144303322 0.2980425358 3403 1311867283.9856629372 0.0842994824 0.0645289441 0.1179843694 0.0059256974 0.1854850000 986886889 0 402718720 0.0004911965 -0.2144434899 0.2983225286 3404 1311867284.0172998905 0.0846682861 0.0645348605 0.1179843694 0.0059249324 0.1848610000 986889737 0 402718720 -0.0004023133 -0.2151477933 0.2986012399 3405 1311867284.0497789383 0.0846843272 0.0645407781 0.1179843694 0.0059247830 0.1937490000 986892697 0 402718720 -0.0011171440 -0.2148470879 0.2989465594 3406 1311867284.0853729248 0.0840923712 0.0645465184 0.1179843694 0.0059240567 0.1973370000 986895657 0 402718720 -0.0014931633 -0.2136968374 0.2992461622 3407 1311867284.1175038815 0.0840203539 0.0645522343 0.1179843694 0.0059238711 0.1852520000 986898561 0 402718720 -0.0021493800 -0.2137095630 0.2995109558 3408 1311867284.1494109631 0.0839028582 0.0645579123 0.1179843694 0.0059231196 0.1855710000 986901465 0 402718720 -0.0023543243 -0.2131782174 0.3000434339 3409 1311867284.1874890327 0.0834432393 0.0645634521 0.1179843694 0.0059223015 0.2065150000 986904537 0 402718720 -0.0026627185 -0.2118375152 0.3006363809 3410 1311867284.2173368931 0.0838424936 0.0645691058 0.1179843694 0.0059216072 0.1986230000 986907385 0 402718720 -0.0037762618 -0.2123074234 0.3009471297 3411 1311867284.2494308949 0.0840693414 0.0645748227 0.1179843694 0.0059208769 0.1849670000 986910289 0 402718720 -0.0042016306 -0.2117904127 0.3013632596 3412 1311867284.2853159904 0.0840876848 0.0645805416 0.1179843694 0.0059200733 0.1841700000 986913249 0 402718720 -0.0038484787 -0.2110881060 0.3016638458 3413 1311867284.3178350925 0.0843326673 0.0645863289 0.1179843694 0.0059192698 0.1840170000 986916209 0 402718720 -0.0042696996 -0.2110534608 0.3017926812 3414 1311867284.3494238853 0.0841086730 0.0645920472 0.1179843694 0.0059186038 0.1837300000 986919113 0 402718720 -0.0038291940 -0.2098299265 0.3021698892 3415 1311867284.3854329586 0.0840661004 0.0645977497 0.1179843694 0.0059178016 0.1929520000 986922129 0 402718720 -0.0034365759 -0.2091296762 0.3025261462 3416 1311867284.4175798893 0.0843487382 0.0646035316 0.1179843694 0.0059171926 0.1837750000 986925033 0 402718720 -0.0031548145 -0.2091429979 0.3028065264 3417 1311867284.4495139122 0.0842173919 0.0646092717 0.1179843694 0.0059164907 0.1839050000 986927937 0 402718720 -0.0025298425 -0.2084586322 0.3032385409 3418 1311867284.4854190350 0.0842895806 0.0646150295 0.1179843694 0.0059157956 0.1838450000 986930897 0 402718720 -0.0023584065 -0.2084674090 0.3035556376 3419 1311867284.5177299976 0.0845120698 0.0646208491 0.1179843694 0.0059150386 0.1836870000 986933857 0 402718720 -0.0019356762 -0.2088122070 0.3039602637 3420 1311867284.5494539738 0.0844177306 0.0646266376 0.1179843694 0.0059147218 0.1960040000 986936761 0 402718720 -0.0010435765 -0.2082563192 0.3043724000 3421 1311867284.5854179859 0.0843222067 0.0646323949 0.1179843694 0.0059141454 0.1835120000 986939721 0 402718720 -0.0004408052 -0.2078182995 0.3047268689 3422 1311867284.6174941063 0.0845809728 0.0646382244 0.1179843694 0.0059134376 0.1838080000 986942625 0 402718720 0.0000444045 -0.2083068341 0.3050695360 3423 1311867284.6495230198 0.0846039653 0.0646440572 0.1179843694 0.0059131065 0.1836410000 986945585 0 402718720 0.0007527233 -0.2079003900 0.3054866493 3424 1311867284.6853780746 0.0843051150 0.0646497994 0.1179843694 0.0059129080 0.1842370000 986948545 0 402718720 0.0012488724 -0.2071640939 0.3058879972 3425 1311867284.7174859047 0.0847996026 0.0646556825 0.1179843694 0.0059127715 0.1915920000 986951449 0 402718720 0.0016506825 -0.2079352289 0.3061755896 3426 1311867284.7498660088 0.0849317387 0.0646616008 0.1179843694 0.0059130926 0.1843270000 986954409 0 402718720 0.0019383876 -0.2076524049 0.3067333400 3427 1311867284.7854089737 0.0845432281 0.0646674023 0.1179843694 0.0059123573 0.1831190000 986957369 0 402718720 0.0024360076 -0.2065484077 0.3072370291 3428 1311867284.8186919689 0.0850637034 0.0646733522 0.1179843694 0.0059122546 0.1942060000 986960329 0 402718720 0.0024749648 -0.2070843130 0.3076037765 3429 1311867284.8492770195 0.0850907713 0.0646793065 0.1179843694 0.0059119216 0.1841500000 986963177 0 402718720 0.0030233408 -0.2065981627 0.3079495728 3430 1311867284.8853850365 0.0848984793 0.0646852013 0.1179843694 0.0059110900 0.1951840000 986966137 0 402718720 0.0033742341 -0.2057485133 0.3082986176 3431 1311867284.9174609184 0.0853090882 0.0646912124 0.1179843694 0.0059104704 0.1830550000 986969097 0 402718720 0.0030422667 -0.2066273540 0.3083033860 3432 1311867284.9492468834 0.0852654874 0.0646972072 0.1179843694 0.0059097458 0.1830560000 986972001 0 402718720 0.0033568216 -0.2063073963 0.3083582222 3433 1311867284.9852581024 0.0852334425 0.0647031892 0.1179843694 0.0059091192 0.1827710000 986975073 0 402718720 0.0035063901 -0.2064071745 0.3081692159 3434 1311867285.0175390244 0.0854998901 0.0647092453 0.1179843694 0.0059090943 0.1830190000 986977921 0 402718720 0.0030300096 -0.2076574266 0.3078102171 3435 1311867285.0493679047 0.0855197012 0.0647153037 0.1179843694 0.0059084114 0.1963310000 986980825 0 402718720 0.0030089195 -0.2081404626 0.3074218631 3436 1311867285.0853259563 0.0852884129 0.0647212912 0.1179843694 0.0059075832 0.2049220000 986983841 0 402718720 0.0028638961 -0.2081196159 0.3068749309 3437 1311867285.1177120209 0.0858421847 0.0647274364 0.1179843694 0.0059070499 0.1841540000 986986745 0 402718720 0.0022704597 -0.2094728351 0.3061186671 3438 1311867285.1502749920 0.0861059427 0.0647336546 0.1179843694 0.0059065141 0.1843790000 986989705 0 402718720 0.0017613540 -0.2103373855 0.3053970337 3439 1311867285.1855800152 0.0858175009 0.0647397855 0.1179843694 0.0059057827 0.1837010000 986992609 0 402718720 0.0017649315 -0.2102178335 0.3044991493 3440 1311867285.2187609673 0.0860007927 0.0647459660 0.1179843694 0.0059051093 0.1973230000 986995625 0 402718720 0.0012738899 -0.2112627625 0.3035953641 3441 1311867285.2493660450 0.0863073692 0.0647522320 0.1179843694 0.0059042652 0.1838970000 986998473 0 402718720 0.0011128425 -0.2122813314 0.3028514981 3442 1311867285.2853620052 0.0859804079 0.0647583994 0.1179843694 0.0059037596 0.1841170000 987001489 0 402718720 0.0011104301 -0.2120501250 0.3020930588 3443 1311867285.3175029755 0.0857884735 0.0647645075 0.1179843694 0.0059030799 0.1839950000 987004393 0 402718720 0.0009071836 -0.2123134732 0.3013827503 3444 1311867285.3493449688 0.0860495195 0.0647706878 0.1179843694 0.0059023204 0.1849040000 987007297 0 402718720 0.0007879158 -0.2130483687 0.3009366393 3445 1311867285.3855409622 0.0855473578 0.0647767188 0.1179843694 0.0059022252 0.1850360000 987010369 0 402718720 0.0006216391 -0.2122976631 0.3005654514 3446 1311867285.4175810814 0.0852332264 0.0647826551 0.1179843694 0.0059017564 0.1849130000 987013217 0 402718720 0.0004733078 -0.2121592462 0.3003547788 3447 1311867285.4492840767 0.0852334648 0.0647885880 0.1179843694 0.0059009087 0.1843280000 987016121 0 402718720 0.0000529470 -0.2122204453 0.3005160689 3448 1311867285.4853799343 0.0848510414 0.0647944066 0.1179843694 0.0059006034 0.1958140000 987019081 0 402718720 0.0001352720 -0.2112191916 0.3008942008 3449 1311867285.5176479816 0.0846279785 0.0648001571 0.1179843694 0.0058999577 0.1839980000 987022041 0 402718720 -0.0000450222 -0.2108505964 0.3012687564 3450 1311867285.5494589806 0.0849528387 0.0648059984 0.1179843694 0.0058996448 0.1856530000 987024945 0 402718720 -0.0004612204 -0.2114442140 0.3017377257 3451 1311867285.5855739117 0.0847320482 0.0648117724 0.1179843694 0.0058993753 0.1847410000 987027961 0 402718720 -0.0002384465 -0.2104072869 0.3024265170 3452 1311867285.6175510883 0.0845232829 0.0648174826 0.1179843694 0.0058989701 0.1844910000 987030865 0 402718720 -0.0003574698 -0.2101211250 0.3028768599 3453 1311867285.6494030952 0.0847733393 0.0648232619 0.1179843694 0.0058981234 0.1845800000 987033769 0 402718720 -0.0011688455 -0.2104318440 0.3034769595 3454 1311867285.6856529713 0.0844766647 0.0648289519 0.1179843694 0.0058972951 0.1835140000 987036785 0 402718720 -0.0009272547 -0.2092539519 0.3041945994 3455 1311867285.7177190781 0.0847780779 0.0648347259 0.1179843694 0.0058972170 0.1918110000 987039689 0 402718720 -0.0016030578 -0.2096732557 0.3045826256 3456 1311867285.7497379780 0.0850219131 0.0648405671 0.1179843694 0.0058967943 0.1834560000 987042593 0 402718720 -0.0019396598 -0.2098929733 0.3049121797 3457 1311867285.7854781151 0.0849760771 0.0648463917 0.1179843694 0.0058960213 0.1839070000 987045665 0 402718720 -0.0021705204 -0.2095571309 0.3051528335 3458 1311867285.8179709911 0.0850937888 0.0648522469 0.1179843694 0.0058952899 0.1835490000 987048513 0 402718720 -0.0028966106 -0.2101383954 0.3052606583 3459 1311867285.8496279716 0.0853241608 0.0648581654 0.1179843694 0.0058947001 0.1842860000 987051417 0 402718720 -0.0034163992 -0.2104934752 0.3053746223 3460 1311867285.8852860928 0.0850662664 0.0648640059 0.1179843694 0.0058938587 0.1844510000 987054489 0 402718720 -0.0034273798 -0.2103550136 0.3054019511 3461 1311867285.9187369347 0.0852151215 0.0648698860 0.1179843694 0.0058937766 0.1840170000 987057393 0 402718720 -0.0042173206 -0.2114294767 0.3053410649 3462 1311867285.9496929646 0.0855080485 0.0648758473 0.1179843694 0.0058932299 0.1928900000 987060297 0 402718720 -0.0051275566 -0.2123800814 0.3054111600 3463 1311867285.9858360291 0.0848032385 0.0648816017 0.1179843694 0.0058933575 0.1850690000 987063257 0 402718720 -0.0051182141 -0.2114186585 0.3055517972 3464 1311867286.0184700489 0.0845083967 0.0648872676 0.1179843694 0.0058928821 0.1845520000 987066161 0 402718720 -0.0060168742 -0.2116890103 0.3056225777 3465 1311867286.0494220257 0.0848406106 0.0648930262 0.1179843694 0.0058921303 0.1848700000 987069065 0 402718720 -0.0060978853 -0.2119075209 0.3060731292 3466 1311867286.0854020119 0.0847800598 0.0648987639 0.1179843694 0.0058932272 0.1852470000 987072025 0 402718720 -0.0057738270 -0.2110633552 0.3065447211 3467 1311867286.1240980625 0.0847856477 0.0649045000 0.1179843694 0.0058940346 0.2043650000 987075041 0 402718720 -0.0062597697 -0.2113933414 0.3068532944 3468 1311867286.1506319046 0.0850620717 0.0649103124 0.1179843694 0.0058942427 0.1970060000 987077777 0 402718720 -0.0062108529 -0.2112118155 0.3071580529 3469 1311867286.1857590675 0.0848407522 0.0649160577 0.1179843694 0.0058934560 0.1854900000 987080737 0 402718720 -0.0060849693 -0.2104992121 0.3075349331 3470 1311867286.2179830074 0.0847713873 0.0649217797 0.1179843694 0.0058935867 0.1842960000 987083641 0 402718720 -0.0062760785 -0.2106018811 0.3077687621 3471 1311867286.2525210381 0.0851304010 0.0649276018 0.1179843694 0.0058927702 0.1846460000 987086545 0 402718720 -0.0062778662 -0.2106545419 0.3081646264 3472 1311867286.2861630917 0.0848742351 0.0649333468 0.1179843694 0.0058919963 0.2099700000 987089449 0 402718720 -0.0060654380 -0.2097578645 0.3082655668 3473 1311867286.3203520775 0.0848326012 0.0649390765 0.1179843694 0.0058913259 0.1847740000 987092353 0 402718720 -0.0060566016 -0.2094877362 0.3082244694 3474 1311867286.3524320126 0.0848310515 0.0649448025 0.1179843694 0.0058910098 0.1846240000 987095257 0 402718720 -0.0062378310 -0.2098135054 0.3080177605 3475 1311867286.3855628967 0.0841873810 0.0649503399 0.1179843694 0.0058904370 0.1847520000 987098161 0 402718720 -0.0060298294 -0.2090653926 0.3075729609 3476 1311867286.4177770615 0.0831833556 0.0649555853 0.1179843694 0.0058901332 0.1849320000 987101121 0 402718720 -0.0053697987 -0.2079005688 0.3069887459 3477 1311867286.4494199753 0.0830144361 0.0649607791 0.1179843694 0.0058893647 0.1944990000 987104025 0 402718720 -0.0047872365 -0.2079433352 0.3065686822 3478 1311867286.4855709076 0.0827599466 0.0649658968 0.1179843694 0.0058899496 0.1847300000 987106985 0 402718720 -0.0040040449 -0.2076674551 0.3063724041 3479 1311867286.5190370083 0.0823965892 0.0649709070 0.1179843694 0.0058893221 0.1842800000 987110001 0 402718720 -0.0029138720 -0.2069938928 0.3062479794 3480 1311867286.5512158871 0.0821956322 0.0649758567 0.1179843694 0.0058885993 0.1835190000 987112849 0 402718720 -0.0027508345 -0.2071387321 0.3060550988 3481 1311867286.5855200291 0.0820452198 0.0649807603 0.1179843694 0.0058880119 0.1827150000 987115921 0 402718720 -0.0025405826 -0.2072472274 0.3061307073 3482 1311867286.6190819740 0.0812424496 0.0649854305 0.1179843694 0.0058875398 0.1950730000 987118825 0 402718720 -0.0016217688 -0.2061413229 0.3062733114 3483 1311867286.6500060558 0.0813887417 0.0649901400 0.1179843694 0.0058872733 0.1824680000 987121673 0 402718720 -0.0015907421 -0.2064636201 0.3061570525 3484 1311867286.6856429577 0.0819884688 0.0649950190 0.1179843694 0.0058871125 0.1838750000 987124633 0 402718720 -0.0015736488 -0.2079678029 0.3061483502 3485 1311867286.7176160812 0.0818858221 0.0649998657 0.1179843694 0.0058865674 0.1843510000 987127537 0 402718720 -0.0009486624 -0.2079330832 0.3062341213 3486 1311867286.7495489120 0.0812122747 0.0650045164 0.1179843694 0.0058866165 0.1842790000 987130497 0 402718720 -0.0006294147 -0.2075688094 0.3062369227 3487 1311867286.7856459618 0.0810686797 0.0650091233 0.1179843694 0.0058872549 0.1955520000 987133457 0 402718720 -0.0007472039 -0.2075980157 0.3063881397 3488 1311867286.8176259995 0.0810112506 0.0650137110 0.1179843694 0.0058865957 0.1842820000 987136417 0 402718720 -0.0002940160 -0.2074003667 0.3066601157 3489 1311867286.8535819054 0.0808693767 0.0650182555 0.1179843694 0.0058859631 0.1841510000 987139433 0 402718720 0.0000758609 -0.2071832567 0.3067879975 3490 1311867286.8868150711 0.0809779912 0.0650228285 0.1179843694 0.0058852334 0.2069850000 987142337 0 402718720 0.0002915220 -0.2076681554 0.3068132997 3491 1311867286.9174380302 0.0812126249 0.0650274661 0.1179843694 0.0058844495 0.1848970000 987145185 0 402718720 0.0007218536 -0.2077214271 0.3070219457 3492 1311867286.9543609619 0.0810663775 0.0650320591 0.1179843694 0.0058838259 0.1844270000 987148257 0 402718720 0.0018766877 -0.2065502107 0.3073090613 3493 1311867286.9854118824 0.0812701583 0.0650367079 0.1179843694 0.0058834583 0.1839300000 987151105 0 402718720 0.0018318502 -0.2067801207 0.3073795438 3494 1311867287.0174310207 0.0819956362 0.0650415616 0.1179843694 0.0058828629 0.1956610000 987154009 0 402718720 0.0018643406 -0.2076676041 0.3073949814 3495 1311867287.0547020435 0.0825267658 0.0650465645 0.1179843694 0.0058847739 0.1847460000 987157081 0 402718720 0.0025706715 -0.2071119994 0.3074931502 3496 1311867287.0856859684 0.0819450542 0.0650513982 0.1179843694 0.0058840917 0.1835140000 987159985 0 402718720 0.0029703269 -0.2061341852 0.3074007630 3497 1311867287.1178219318 0.0820707604 0.0650562651 0.1179843694 0.0058842866 0.1832840000 987162833 0 402718720 0.0029591150 -0.2063400000 0.3072064221 3498 1311867287.1537048817 0.0825354159 0.0650612619 0.1179843694 0.0058834571 0.1833750000 987165849 0 402718720 0.0033438418 -0.2065462917 0.3072393835 3499 1311867287.1874449253 0.0822634101 0.0650661783 0.1179843694 0.0058829813 0.1832730000 987168809 0 402718720 0.0036142548 -0.2059535831 0.3072314262 3500 1311867287.2175579071 0.0823704004 0.0650711223 0.1179843694 0.0058831432 0.1940490000 987171657 0 402718720 0.0036087865 -0.2063456178 0.3071282506 3501 1311867287.2536680698 0.0827549100 0.0650761734 0.1179843694 0.0058826466 0.1948080000 987174673 0 402718720 0.0035963717 -0.2067675292 0.3070655167 3502 1311867287.2870221138 0.0824551806 0.0650811360 0.1179843694 0.0058821293 0.1852770000 987177633 0 402718720 0.0036481204 -0.2063062936 0.3069575727 3503 1311867287.3175630569 0.0824388266 0.0650860911 0.1179843694 0.0058817263 0.1830260000 987180481 0 402718720 0.0033049979 -0.2066864669 0.3067340851 3504 1311867287.3540940285 0.0830441266 0.0650912161 0.1179843694 0.0058809261 0.1837660000 987183553 0 402718720 0.0032453956 -0.2073612064 0.3066332936 3505 1311867287.3855540752 0.0828387737 0.0650962796 0.1179843694 0.0058802186 0.1836340000 987186457 0 402718720 0.0035848774 -0.2070650011 0.3064835668 3506 1311867287.4175760746 0.0829577222 0.0651013741 0.1179843694 0.0058793805 0.1842060000 987189305 0 402718720 0.0034474181 -0.2073642164 0.3063732088 3507 1311867287.4535288811 0.0835943893 0.0651066473 0.1179843694 0.0058786731 0.1850880000 987192321 0 402718720 0.0036688403 -0.2083018571 0.3062710464 3508 1311867287.4867310524 0.0822993219 0.0651115483 0.1179843694 0.0058802779 0.1847410000 987195225 0 402718720 0.0041189208 -0.2077361047 0.3061158061 3509 1311867287.5174999237 0.0827742592 0.0651165818 0.1179843694 0.0058840807 0.1821090000 987198129 0 402718720 0.0039751190 -0.2074860632 0.3060267270 3510 1311867287.5534870625 0.0827274546 0.0651215992 0.1179843694 0.0058833261 0.1837930000 987201145 0 402718720 0.0042039873 -0.2073811591 0.3061164021 3511 1311867287.5869519711 0.0827718079 0.0651266263 0.1179843694 0.0058825499 0.1839360000 987204105 0 402718720 0.0045064134 -0.2071477324 0.3063032031 3512 1311867287.6176569462 0.0831155106 0.0651317484 0.1179843694 0.0058828464 0.2076600000 987206953 0 402718720 0.0043852655 -0.2077431083 0.3062651157 3513 1311867287.6539158821 0.0836057663 0.0651370072 0.1179843694 0.0058821797 0.1849210000 987210025 0 402718720 0.0043439642 -0.2081483752 0.3061804771 3514 1311867287.6875660419 0.0831812844 0.0651421421 0.1179843694 0.0058829501 0.1842930000 987212929 0 402718720 0.0043084687 -0.2072354406 0.3061550856 3515 1311867287.7176280022 0.0829153359 0.0651471985 0.1179843694 0.0058823331 0.1839810000 987215777 0 402718720 0.0042588203 -0.2068098783 0.3062303364 3516 1311867287.7553908825 0.0832522139 0.0651523478 0.1179843694 0.0058818798 0.1837540000 987218849 0 402718720 0.0040543051 -0.2071432769 0.3062948287 3517 1311867287.7872428894 0.0833241269 0.0651575147 0.1179843694 0.0058811823 0.2136160000 987221697 0 402718720 0.0043737227 -0.2067290246 0.3065067530 3518 1311867287.8260099888 0.0829914808 0.0651625840 0.1179843694 0.0058803942 0.1840800000 987224769 0 402718720 0.0044789929 -0.2061118484 0.3068011999 3519 1311867287.8536510468 0.0831682608 0.0651677007 0.1179843694 0.0058798695 0.1838740000 987227561 0 402718720 0.0045456155 -0.2064213306 0.3070193529 3520 1311867287.8931109905 0.0836878642 0.0651729621 0.1179843694 0.0058791324 0.1840180000 987230577 0 402718720 0.0048928689 -0.2068511546 0.3075401783 3521 1311867287.9175710678 0.0832686275 0.0651781015 0.1179843694 0.0058793934 0.1937700000 987233257 0 402718720 0.0058966875 -0.2056125551 0.3080121279 3522 1311867287.9535610676 0.0828800872 0.0651831276 0.1179843694 0.0058837666 0.1918150000 987236217 0 402718720 0.0061740601 -0.2061415017 0.3081381023 3523 1311867287.9868519306 0.0843976662 0.0651885816 0.1179843694 0.0058837247 0.1837870000 987239121 0 402718720 0.0061954702 -0.2081399113 0.3080888391 3524 1311867288.0178821087 0.0843947902 0.0651940318 0.1179843694 0.0058841508 0.1836330000 987242025 0 402718720 0.0074419598 -0.2078817934 0.3081530333 3525 1311867288.0536389351 0.0834384710 0.0651992075 0.1179843694 0.0058844650 0.1834330000 987245041 0 402718720 0.0075517320 -0.2076469362 0.3080444336 3526 1311867288.0854179859 0.0838473812 0.0652044962 0.1179843694 0.0058837905 0.1959300000 987247889 0 402718720 0.0071395328 -0.2091034651 0.3078984618 3527 1311867288.1175940037 0.0837722793 0.0652097607 0.1179843694 0.0058834315 0.1960560000 987250849 0 402718720 0.0077180457 -0.2090913057 0.3080322742 3528 1311867288.1540820599 0.0834639445 0.0652149348 0.1179843694 0.0058835288 0.1846480000 987253865 0 402718720 0.0080909012 -0.2092674226 0.3080179393 3529 1311867288.1854550838 0.0843807459 0.0652203657 0.1179843694 0.0058827941 0.1848640000 987256769 0 402718720 0.0072996854 -0.2112260759 0.3077784777 3530 1311867288.2175340652 0.0841236562 0.0652257208 0.1179843694 0.0058833868 0.1956250000 987259561 0 402718720 0.0076275836 -0.2107922137 0.3075330853 3531 1311867288.2535810471 0.0835858211 0.0652309205 0.1179843694 0.0058830188 0.1840030000 987262633 0 402718720 0.0077237310 -0.2098507285 0.3071427941 3532 1311867288.2854719162 0.0839227885 0.0652362126 0.1179843694 0.0058831304 0.1952230000 987265481 0 402718720 0.0067391503 -0.2110838443 0.3066527247 3533 1311867288.3175830841 0.0840913951 0.0652415495 0.1179843694 0.0058827659 0.1855050000 987268441 0 402718720 0.0065314150 -0.2116329968 0.3064978719 3534 1311867288.3535211086 0.0835538656 0.0652467313 0.1179843694 0.0058820440 0.1852350000 987271457 0 402718720 0.0063005779 -0.2108067572 0.3064855933 3535 1311867288.3858890533 0.0836554393 0.0652519388 0.1179843694 0.0058817414 0.1853030000 987274361 0 402718720 0.0055126273 -0.2113560736 0.3064319789 3536 1311867288.4177610874 0.0837189928 0.0652571614 0.1179843694 0.0058810520 0.1860760000 987277265 0 402718720 0.0049134009 -0.2114464194 0.3064508736 3537 1311867288.4560298920 0.0834341645 0.0652623005 0.1179843694 0.0058804387 0.1964220000 987280337 0 402718720 0.0046439562 -0.2105792463 0.3066478074 3538 1311867288.4854650497 0.0833280087 0.0652674067 0.1179843694 0.0058797785 0.1845020000 987283241 0 402718720 0.0037646359 -0.2106418759 0.3066346347 3539 1311867288.5176889896 0.0838247314 0.0652726503 0.1179843694 0.0058790924 0.1841020000 987286089 0 402718720 0.0030596599 -0.2110435516 0.3068416119 3540 1311867288.5544929504 0.0836426690 0.0652778396 0.1179843694 0.0058786174 0.1852600000 987289105 0 402718720 0.0026380494 -0.2105277479 0.3068678677 3541 1311867288.5874340534 0.0835354552 0.0652829957 0.1179843694 0.0058778937 0.1843830000 987292009 0 402718720 0.0017114668 -0.2104965895 0.3066835999 3542 1311867288.6175410748 0.0839056969 0.0652882534 0.1179843694 0.0058771587 0.1936380000 987294857 0 402718720 0.0009865415 -0.2107936591 0.3066315651 3543 1311867288.6551198959 0.0839632824 0.0652935243 0.1179843694 0.0058764593 0.1852770000 987297929 0 402718720 0.0005825827 -0.2102875561 0.3064829111 3544 1311867288.6874110699 0.0838957131 0.0652987733 0.1179843694 0.0058757087 0.2104880000 987300833 0 402718720 -0.0003328731 -0.2099140137 0.3062573373 3545 1311867288.7177178860 0.0841515958 0.0653040914 0.1179843694 0.0058749227 0.1853840000 987303681 0 402718720 -0.0011253170 -0.2099822909 0.3060099781 3546 1311867288.7560660839 0.0839635804 0.0653093535 0.1179843694 0.0058741108 0.1839830000 987306753 0 402718720 -0.0009994331 -0.2094610333 0.3057267964 3547 1311867288.7855091095 0.0841173977 0.0653146560 0.1179843694 0.0058732885 0.1952670000 987309601 0 402718720 -0.0016670919 -0.2097227722 0.3054329753 3548 1311867288.8192400932 0.0842300951 0.0653199873 0.1179843694 0.0058725447 0.1842130000 987312617 0 402718720 -0.0021876842 -0.2099680901 0.3051781356 3549 1311867288.8543450832 0.0839452818 0.0653252354 0.1179843694 0.0058720833 0.1855670000 987315577 0 402718720 -0.0019871602 -0.2091876417 0.3049209118 3550 1311867288.8855559826 0.0837072432 0.0653304134 0.1179843694 0.0058713497 0.1837950000 987318481 0 402718720 -0.0019792165 -0.2090488374 0.3046048880 3551 1311867288.9176120758 0.0837777480 0.0653356084 0.1179843694 0.0058706103 0.1858040000 987321329 0 402718720 -0.0023452803 -0.2091574669 0.3044282198 3552 1311867288.9599480629 0.0835807472 0.0653407450 0.1179843694 0.0058701378 0.1935500000 987324569 0 402718720 -0.0023111708 -0.2086872458 0.3042725027 3553 1311867288.9855918884 0.0833783895 0.0653458217 0.1179843694 0.0058693708 0.1846270000 987327305 0 402718720 -0.0023013065 -0.2083036304 0.3042017519 3554 1311867289.0176560879 0.0834449083 0.0653509143 0.1179843694 0.0058687605 0.1855780000 987330153 0 402718720 -0.0019479848 -0.2083226442 0.3041688204 3555 1311867289.0535120964 0.0835868046 0.0653560439 0.1179843694 0.0058691035 0.1844710000 987333225 0 402718720 -0.0015750235 -0.2086070925 0.3042757511 3556 1311867289.0855109692 0.0835777521 0.0653611682 0.1179843694 0.0058684584 0.1845530000 987336073 0 402718720 -0.0018369401 -0.2087460458 0.3043316901 3557 1311867289.1175429821 0.0834137797 0.0653662434 0.1179843694 0.0058678142 0.1950670000 987338977 0 402718720 -0.0018990650 -0.2083542496 0.3043164611 3558 1311867289.1545929909 0.0834705159 0.0653713317 0.1179843694 0.0058670184 0.1856240000 987342105 0 402718720 -0.0018390823 -0.2085569650 0.3042683005 3559 1311867289.1856400967 0.0835273862 0.0653764332 0.1179843694 0.0058662294 0.1855360000 987344897 0 402718720 -0.0016828439 -0.2088523954 0.3042520881 3560 1311867289.2185060978 0.0834579468 0.0653815122 0.1179843694 0.0058656339 0.1854570000 987347857 0 402718720 -0.0016828802 -0.2089811116 0.3043134511 3561 1311867289.2550480366 0.0833604634 0.0653865611 0.1179843694 0.0058656624 0.1853490000 987350929 0 402718720 -0.0017650368 -0.2092059553 0.3043403924 3562 1311867289.2853870392 0.0835871920 0.0653916708 0.1179843694 0.0058650335 0.1953200000 987353833 0 402718720 -0.0020512401 -0.2098871171 0.3043017387 3563 1311867289.3176290989 0.0835924223 0.0653967790 0.1179843694 0.0058643543 0.1838500000 987356681 0 402718720 -0.0021293317 -0.2098939121 0.3041487634 3564 1311867289.3539168835 0.0834083185 0.0654018328 0.1179843694 0.0058636425 0.1850390000 987359697 0 402718720 -0.0022909692 -0.2096147388 0.3040632904 3565 1311867289.3861899376 0.0837264135 0.0654069729 0.1179843694 0.0058629029 0.1859760000 987362657 0 402718720 -0.0025453425 -0.2101443559 0.3041089475 3566 1311867289.4177041054 0.0837620348 0.0654121201 0.1179843694 0.0058629923 0.1858600000 987365505 0 402718720 -0.0024386169 -0.2095111459 0.3042500317 3567 1311867289.4536058903 0.0836560801 0.0654172348 0.1179843694 0.0058623756 0.1962700000 987368521 0 402718720 -0.0027622941 -0.2089520246 0.3045314848 3568 1311867289.4859669209 0.0839474499 0.0654224282 0.1179843694 0.0058619702 0.1844440000 987371481 0 402718720 -0.0036275322 -0.2095234692 0.3046873212 3569 1311867289.5183238983 0.0839994326 0.0654276333 0.1179843694 0.0058615860 0.1846930000 987374329 0 402718720 -0.0036793859 -0.2091553658 0.3050296307 3570 1311867289.5548820496 0.0834487379 0.0654326813 0.1179843694 0.0058608096 0.1844880000 987377401 0 402718720 -0.0034738667 -0.2080721408 0.3053452373 3571 1311867289.5856130123 0.0839575455 0.0654378688 0.1179843694 0.0058614660 0.1977750000 987380305 0 402718720 -0.0041226149 -0.2092536241 0.3053942323 3572 1311867289.6176490784 0.0842525512 0.0654431361 0.1179843694 0.0058606720 0.2090730000 987383153 0 402718720 -0.0041102814 -0.2095544487 0.3056709766 3573 1311867289.6536390781 0.0834977105 0.0654481892 0.1179843694 0.0058600209 0.1856310000 987386169 0 402718720 -0.0037963255 -0.2080979794 0.3060940206 3574 1311867289.6856849194 0.0830088779 0.0654531026 0.1179843694 0.0058595347 0.1847750000 987389073 0 402718720 -0.0043058139 -0.2077863514 0.3065623641 3575 1311867289.7204349041 0.0830335915 0.0654580203 0.1179843694 0.0058588298 0.1850430000 987392089 0 402718720 -0.0048579099 -0.2075733542 0.3073205948 3576 1311867289.7564179897 0.0828765482 0.0654628912 0.1179843694 0.0058587384 0.1845660000 987395049 0 402718720 -0.0050650244 -0.2066726983 0.3079592884 3577 1311867289.7855679989 0.0833023861 0.0654678785 0.1179843694 0.0058582979 0.1943460000 987397897 0 402718720 -0.0058146394 -0.2070317268 0.3085246384 3578 1311867289.8240370750 0.0840590298 0.0654730744 0.1179843694 0.0058577789 0.1843490000 987400969 0 402718720 -0.0064735087 -0.2082436532 0.3089719117 3579 1311867289.8541870117 0.0840319395 0.0654782599 0.1179843694 0.0058575081 0.1847790000 987403873 0 402718720 -0.0063893893 -0.2075080574 0.3095639944 3580 1311867289.8855679035 0.0841193348 0.0654834669 0.1179843694 0.0058573787 0.1845560000 987406721 0 402718720 -0.0065102410 -0.2075279802 0.3099761307 3581 1311867289.9200530052 0.0851244479 0.0654889517 0.1179843694 0.0058582176 0.1846200000 987409681 0 402718720 -0.0072340346 -0.2085193545 0.3103853464 3582 1311867289.9536409378 0.0845272392 0.0654942667 0.1179843694 0.0058583497 0.1931330000 987412641 0 402718720 -0.0075346045 -0.2084864527 0.3107922971 3583 1311867289.9855279922 0.0843629241 0.0654995329 0.1179843694 0.0058575322 0.1968340000 987415489 0 402718720 -0.0078919195 -0.2085843533 0.3110864758 3584 1311867290.0232169628 0.0849272087 0.0655049535 0.1179843694 0.0058584649 0.1853350000 987418617 0 402718720 -0.0085081710 -0.2102605850 0.3113909960 3585 1311867290.0535910130 0.0850508213 0.0655104057 0.1179843694 0.0058580573 0.1851990000 987421465 0 402718720 -0.0081897108 -0.2104862034 0.3118428886 3586 1311867290.0854740143 0.0845343694 0.0655157107 0.1179843694 0.0058576276 0.1843290000 987424425 0 402718720 -0.0082953256 -0.2101741731 0.3121950924 3587 1311867290.1248800755 0.0846993923 0.0655210588 0.1179843694 0.0058572759 0.1964430000 987427441 0 402718720 -0.0087984055 -0.2109184861 0.3125066459 3588 1311867290.1536118984 0.0844855756 0.0655263444 0.1179843694 0.0058566309 0.1851810000 987430289 0 402718720 -0.0081026014 -0.2101225853 0.3129916787 3589 1311867290.1856379509 0.0841448903 0.0655315320 0.1179843694 0.0058564431 0.1846820000 987433249 0 402718720 -0.0078073782 -0.2092641741 0.3133057654 3590 1311867290.2225489616 0.0844298229 0.0655367962 0.1179843694 0.0058558967 0.1970960000 987436209 0 402718720 -0.0079309633 -0.2095762193 0.3136107624 3591 1311867290.2540318966 0.0843921900 0.0655420469 0.1179843694 0.0058562922 0.1952820000 987439113 0 402718720 -0.0074913637 -0.2088093013 0.3140836060 3592 1311867290.2892379761 0.0842855722 0.0655472651 0.1179843694 0.0058558905 0.1931470000 987442129 0 402718720 -0.0076359524 -0.2087776810 0.3144362569 3593 1311867290.3220748901 0.0851267800 0.0655527144 0.1179843694 0.0058554080 0.1842300000 987445033 0 402718720 -0.0080329506 -0.2096275687 0.3145714104 3594 1311867290.3587789536 0.0852244273 0.0655581879 0.1179843694 0.0058549611 0.1847000000 987448049 0 402718720 -0.0078086178 -0.2094739377 0.3146317005 3595 1311867290.3864240646 0.0849132538 0.0655635718 0.1179843694 0.0058542026 0.1844830000 987450785 0 402718720 -0.0079874592 -0.2093074471 0.3144979775 3596 1311867290.4216320515 0.0850745365 0.0655689975 0.1179843694 0.0058535225 0.1855120000 987453857 0 402718720 -0.0087111965 -0.2100659162 0.3143313825 3597 1311867290.4578390121 0.0847792104 0.0655743381 0.1179843694 0.0058530744 0.1934610000 987456649 0 402718720 -0.0089105275 -0.2097418308 0.3143377006 3598 1311867290.4859950542 0.0848276317 0.0655796893 0.1179843694 0.0058524704 0.2049260000 987459441 0 402718720 -0.0092713479 -0.2097043991 0.3141834736 3599 1311867290.5223400593 0.0853942335 0.0655851948 0.1179843694 0.0058522736 0.1854700000 987462457 0 402718720 -0.0102502163 -0.2107103318 0.3140134513 3600 1311867290.5537059307 0.0853284374 0.0655906791 0.1179843694 0.0058522199 0.1862180000 987465361 0 402718720 -0.0103096254 -0.2102340609 0.3138898611 3601 1311867290.5855538845 0.0845929906 0.0655959560 0.1179843694 0.0058524607 0.1862690000 987468321 0 402718720 -0.0103037367 -0.2097528726 0.3136092424 3602 1311867290.6221020222 0.0850500464 0.0656013569 0.1179843694 0.0058520550 0.1855440000 987471281 0 402718720 -0.0104355412 -0.2100236565 0.3132739663 3603 1311867290.6536018848 0.0851007923 0.0656067689 0.1179843694 0.0058523865 0.1955800000 987474185 0 402718720 -0.0101961661 -0.2093419135 0.3130466342 3604 1311867290.6857531071 0.0848533064 0.0656121092 0.1179843694 0.0058516947 0.1857940000 987477033 0 402718720 -0.0104763946 -0.2088110745 0.3128507733 3605 1311867290.7256150246 0.0854532123 0.0656176130 0.1179843694 0.0058518101 0.1978120000 987480217 0 402718720 -0.0107813785 -0.2098624408 0.3125935197 3606 1311867290.7539739609 0.0857724324 0.0656232023 0.1179843694 0.0058512431 0.1857640000 987483009 0 402718720 -0.0105171595 -0.2099383324 0.3124101460 3607 1311867290.7866060734 0.0853368267 0.0656286676 0.1179843694 0.0058504950 0.1856320000 987485857 0 402718720 -0.0101771345 -0.2095491290 0.3120440245 3608 1311867290.8231720924 0.0857658759 0.0656342489 0.1179843694 0.0058501900 0.1963660000 987488929 0 402718720 -0.0099787563 -0.2103729248 0.3115628660 3609 1311867290.8556039333 0.0857559144 0.0656398243 0.1179843694 0.0058495532 0.1867740000 987491833 0 402718720 -0.0097604636 -0.2106926888 0.3112001419 3610 1311867290.8876988888 0.0861427486 0.0656455038 0.1179843694 0.0058522482 0.1867640000 987494737 0 402718720 -0.0092207026 -0.2105486095 0.3108237088 3611 1311867290.9227120876 0.0860757902 0.0656511616 0.1179843694 0.0058514786 0.1857670000 987497697 0 402718720 -0.0088058431 -0.2109338045 0.3103646040 3612 1311867290.9537110329 0.0856884569 0.0656567090 0.1179843694 0.0058531527 0.1867020000 987500601 0 402718720 -0.0084937103 -0.2115695328 0.3101035655 3613 1311867290.9906909466 0.0855336487 0.0656622105 0.1179843694 0.0058524971 0.1939840000 987503673 0 402718720 -0.0081111807 -0.2116307318 0.3097861707 3614 1311867291.0239291191 0.0854463503 0.0656676848 0.1179843694 0.0058519595 0.1968750000 987506633 0 402718720 -0.0076483097 -0.2118922025 0.3095175028 3615 1311867291.0558199883 0.0857335702 0.0656732356 0.1179843694 0.0058512992 0.1858470000 987509537 0 402718720 -0.0070693814 -0.2125839293 0.3092598915 3616 1311867291.0934820175 0.0854138359 0.0656786948 0.1179843694 0.0058510253 0.1862540000 987512553 0 402718720 -0.0061225104 -0.2118595988 0.3089788556 3617 1311867291.1203110218 0.0850959197 0.0656840631 0.1179843694 0.0058505618 0.1871450000 987515345 0 402718720 -0.0056750793 -0.2119179219 0.3085362017 3618 1311867291.1541891098 0.0859421566 0.0656896624 0.1179843694 0.0058513786 0.1978690000 987518193 0 402718720 -0.0054327124 -0.2124720365 0.3081043959 3619 1311867291.1891989708 0.0851154327 0.0656950301 0.1179843694 0.0058519924 0.1871410000 987521209 0 402718720 -0.0046809828 -0.2118825763 0.3077925444 3620 1311867291.2211010456 0.0852137506 0.0657004220 0.1179843694 0.0058514743 0.1868190000 987524113 0 402718720 -0.0043056803 -0.2122737169 0.3073779345 3621 1311867291.2543909550 0.0852862597 0.0657058310 0.1179843694 0.0058507766 0.1870620000 987527073 0 402718720 -0.0039896322 -0.2123576701 0.3070932925 3622 1311867291.2877960205 0.0851847157 0.0657112089 0.1179843694 0.0058500012 0.1868580000 987529977 0 402718720 -0.0032735174 -0.2120892704 0.3067315519 3623 1311867291.3210899830 0.0856271833 0.0657167060 0.1179843694 0.0058495580 0.2015970000 987532881 0 402718720 -0.0029934577 -0.2127155960 0.3063089252 3624 1311867291.3547959328 0.0858399644 0.0657222588 0.1179843694 0.0058488174 0.1859200000 987535897 0 402718720 -0.0027416607 -0.2130202949 0.3059301972 3625 1311867291.3878760338 0.0855611190 0.0657277316 0.1179843694 0.0058483416 0.2126840000 987538801 0 402718720 -0.0024321484 -0.2126676887 0.3055174351 3626 1311867291.4223349094 0.0855975747 0.0657332114 0.1179843694 0.0058477130 0.1861990000 987541761 0 402718720 -0.0025313571 -0.2129923105 0.3051508069 3627 1311867291.4536559582 0.0858250335 0.0657387509 0.1179843694 0.0058470250 0.1865160000 987544665 0 402718720 -0.0021160475 -0.2134877145 0.3047557771 3628 1311867291.4883999825 0.0855164155 0.0657442023 0.1179843694 0.0058466198 0.2003980000 987547625 0 402718720 -0.0017498552 -0.2130569816 0.3044475317 3629 1311867291.5201730728 0.0852361917 0.0657495735 0.1179843694 0.0058459260 0.1871900000 987550585 0 402718720 -0.0013952360 -0.2128904164 0.3042363822 3630 1311867291.5536448956 0.0852568746 0.0657549474 0.1179843694 0.0058452808 0.1871790000 987553489 0 402718720 -0.0016292107 -0.2132229358 0.3039372861 3631 1311867291.5895080566 0.0854287595 0.0657603657 0.1179843694 0.0058450145 0.1860970000 987556505 0 402718720 -0.0011539041 -0.2127638310 0.3037365675 3632 1311867291.6206870079 0.0850045532 0.0657656642 0.1179843694 0.0058450790 0.1870800000 987559353 0 402718720 -0.0013353645 -0.2131326050 0.3033354580 3633 1311867291.6539781094 0.0851417929 0.0657709975 0.1179843694 0.0058444267 0.2018380000 987562313 0 402718720 -0.0014038782 -0.2135657966 0.3031750917 3634 1311867291.6896810532 0.0851917490 0.0657763417 0.1179843694 0.0058436744 0.2045450000 987565329 0 402718720 -0.0010349520 -0.2132776231 0.3029816151 3635 1311867291.7202739716 0.0851678699 0.0657816764 0.1179843694 0.0058430252 0.1870320000 987568177 0 402718720 -0.0010903828 -0.2137425542 0.3026511967 3636 1311867291.7537178993 0.0850641280 0.0657869796 0.1179843694 0.0058427592 0.1865840000 987571137 0 402718720 -0.0012598212 -0.2141379863 0.3024047613 3637 1311867291.7890019417 0.0848069191 0.0657922092 0.1179843694 0.0058427103 0.1867240000 987574153 0 402718720 -0.0007559927 -0.2135485411 0.3022528887 3638 1311867291.8217189312 0.0849635601 0.0657974789 0.1179843694 0.0058426220 0.1966030000 987577001 0 402718720 -0.0008897381 -0.2142445594 0.3022280037 3639 1311867291.8538639545 0.0850973129 0.0658027825 0.1179843694 0.0058420739 0.1874270000 987579961 0 402718720 -0.0007255718 -0.2143620700 0.3023563325 3640 1311867291.8879489899 0.0850567222 0.0658080721 0.1179843694 0.0058421424 0.1875760000 987582865 0 402718720 -0.0008319894 -0.2140343040 0.3024435639 3641 1311867291.9206929207 0.0850239769 0.0658133497 0.1179843694 0.0058416199 0.1866620000 987585881 0 402718720 -0.0009566565 -0.2141977847 0.3024297655 3642 1311867291.9537200928 0.0852357149 0.0658186826 0.1179843694 0.0058416137 0.1871050000 987588729 0 402718720 -0.0004376007 -0.2140016705 0.3026475310 3643 1311867291.9902889729 0.0851167738 0.0658239799 0.1179843694 0.0058422260 0.2119280000 987591801 0 402718720 -0.0000992349 -0.2141759098 0.3028557301 3644 1311867292.0225260258 0.0855731145 0.0658293995 0.1179843694 0.0058447856 0.2226410000 987594705 0 402718720 0.0001133953 -0.2140162140 0.3030432463 3645 1311867292.0536830425 0.0856992826 0.0658348508 0.1179843694 0.0058442784 0.1867640000 987597553 0 402718720 0.0000622058 -0.2138942331 0.3032165170 3646 1311867292.0922849178 0.0850305781 0.0658401157 0.1179843694 0.0058461509 0.1859150000 987600625 0 402718720 0.0002555867 -0.2138564885 0.3034433126 3647 1311867292.1243879795 0.0848666281 0.0658453327 0.1179843694 0.0058454967 0.1867290000 987603473 0 402718720 0.0002056754 -0.2134572268 0.3036324978 3648 1311867292.1602649689 0.0848601982 0.0658505451 0.1179843694 0.0058447626 0.1883100000 987606489 0 402718720 0.0003954259 -0.2131195664 0.3039384484 3649 1311867292.1899850368 0.0848934799 0.0658557638 0.1179843694 0.0058440535 0.1878580000 987609337 0 402718720 0.0003488497 -0.2131972611 0.3041322827 3650 1311867292.2207419872 0.0851139873 0.0658610400 0.1179843694 0.0058432567 0.1880750000 987612129 0 402718720 0.0002640264 -0.2133066207 0.3044167161 3651 1311867292.2576909065 0.0851304755 0.0658663179 0.1179843694 0.0058425154 0.1877240000 987615201 0 402718720 0.0001896084 -0.2132630497 0.3046628535 3652 1311867292.2878270149 0.0852594003 0.0658716281 0.1179843694 0.0058417308 0.2087180000 987618049 0 402718720 -0.0001197247 -0.2135051340 0.3048666716 3653 1311867292.3217270374 0.0845756158 0.0658767483 0.1179843694 0.0058432855 0.1874790000 987620953 0 402718720 -0.0004316351 -0.2137343138 0.3050192595 3654 1311867292.3621709347 0.0851434842 0.0658820211 0.1179843694 0.0058449367 0.1879360000 987624137 0 402718720 -0.0007911799 -0.2138861716 0.3051483333 3655 1311867292.3953619003 0.0851043761 0.0658872803 0.1179843694 0.0058441692 0.1871110000 987627097 0 402718720 -0.0010933463 -0.2140718251 0.3052016497 3656 1311867292.4259300232 0.0852590427 0.0658925789 0.1179843694 0.0058434798 0.1870250000 987629945 0 402718720 -0.0014218043 -0.2144452482 0.3052524924 3657 1311867292.4565210342 0.0852789432 0.0658978801 0.1179843694 0.0058427555 0.1871780000 987632737 0 402718720 -0.0013467993 -0.2147500068 0.3053030372 3658 1311867292.4883699417 0.0853345618 0.0659031935 0.1179843694 0.0058419837 0.2075970000 987635697 0 402718720 -0.0015775473 -0.2150088400 0.3053107560 3659 1311867292.5229649544 0.0852073655 0.0659084694 0.1179843694 0.0058411946 0.1880930000 987638657 0 402718720 -0.0017904259 -0.2151869088 0.3052921295 3660 1311867292.5581150055 0.0848475546 0.0659136440 0.1179843694 0.0058404508 0.1880660000 987641617 0 402718720 -0.0016149454 -0.2146518528 0.3054079115 3661 1311867292.5882439613 0.0847292244 0.0659187834 0.1179843694 0.0058398653 0.1872120000 987644521 0 402718720 -0.0015729835 -0.2144241184 0.3056191504 3662 1311867292.6230869293 0.0848213658 0.0659239452 0.1179843694 0.0058390977 0.1870740000 987647481 0 402718720 -0.0015912212 -0.2143651098 0.3058483005 3663 1311867292.6595211029 0.0847439915 0.0659290831 0.1179843694 0.0058383060 0.2148350000 987650553 0 402718720 -0.0014008381 -0.2140378058 0.3060948253 3664 1311867292.6880218983 0.0850682184 0.0659343067 0.1179843694 0.0058377639 0.1948340000 987653289 0 402718720 -0.0016875982 -0.2148104459 0.3062138259 3665 1311867292.7206969261 0.0851555541 0.0659395512 0.1179843694 0.0058370050 0.1882550000 987656249 0 402718720 -0.0016235964 -0.2149076462 0.3064084351 3666 1311867292.7561879158 0.0848484933 0.0659447092 0.1179843694 0.0058362803 0.1873830000 987659265 0 402718720 -0.0013191262 -0.2145792842 0.3065608740 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:32:02 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0090940000 14313029 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0030799352 0.0015399676 0.0030799352 0.0051973686 0.0071590000 14706533 955859216 1373700096 -0.0004419940 -0.0040353294 0.0006710326 3 0.0800000000 0.0063506346 0.0031435233 0.0063506346 0.0043331486 0.0020030000 14708901 955859216 1373700096 -0.0005553669 -0.0098776221 0.0005279740 4 0.1200000000 0.0034860414 0.0032291528 0.0063506346 0.0069005444 0.0019740000 14711277 955859216 1373700096 0.0011180840 -0.0099722650 0.0018546147 5 0.1600000000 0.0069079553 0.0039649133 0.0069079553 0.0064677721 0.0021490000 14713637 955859216 1373700096 0.0026524500 -0.0108917719 0.0027139671 6 0.2000000000 0.0036774664 0.0039170055 0.0069079553 0.0058268102 0.0020170000 14716413 955859216 1373700096 0.0021576034 -0.0133283697 0.0027248424 7 0.2400000000 0.0054127197 0.0041306789 0.0069079553 0.0054986230 0.0020250000 14718389 955859216 1373700096 0.0024037305 -0.0152379032 0.0031261255 8 0.2800000000 0.0093587721 0.0047841906 0.0093587721 0.0053474131 0.0021630000 14720365 955859216 1373700096 0.0038559146 -0.0160899945 0.0041179261 9 0.3200000000 0.0107050790 0.0054420671 0.0107050790 0.0050521249 0.0021980000 14723109 955859216 1373700096 0.0039246851 -0.0174428560 0.0041639586 10 0.3600000000 0.0106631275 0.0059641731 0.0107050790 0.0047717426 0.0021230000 14726685 955859216 1373700096 0.0053004110 -0.0187896825 0.0043762154 11 0.4000000000 0.0117108244 0.0064865960 0.0117108244 0.0045913880 0.0021390000 14728661 955859216 1373700096 0.0058671809 -0.0202514809 0.0047775512 12 0.4400000000 0.0133319562 0.0070570427 0.0133319562 0.0044351456 0.0021440000 14730637 955859216 1373700096 0.0062363390 -0.0213814992 0.0047147102 13 0.4800000000 0.0158313010 0.0077319856 0.0158313010 0.0044932495 0.0022080000 14732613 955859216 1373700096 0.0069373362 -0.0220987499 0.0048589795 14 0.5200000000 0.0175072122 0.0084302161 0.0175072122 0.0044931601 0.0021220000 14734589 955859216 1373700096 0.0076552299 -0.0226538833 0.0050814510 15 0.5600000000 0.0184305180 0.0090969029 0.0184305180 0.0043487082 0.0022110000 14736565 955859216 1373700096 0.0079526352 -0.0228590965 0.0048376746 16 0.6000000000 0.0184298307 0.0096802109 0.0184305180 0.0042064400 0.0021870000 14738541 955859216 1373700096 0.0079712113 -0.0230398793 0.0045835935 17 0.6400000000 0.0192232020 0.0102415633 0.0192232020 0.0040872937 0.0021900000 14742053 955859216 1373700096 0.0074229813 -0.0231230184 0.0042380006 18 0.6800000000 0.0200507026 0.0107865155 0.0200507026 0.0039853236 0.0022710000 14747229 955859216 1373700096 0.0079087941 -0.0227893107 0.0042429226 19 0.7200000000 0.0203078836 0.0112876401 0.0203078836 0.0040374770 0.0021230000 14749205 955859216 1373700096 0.0092612756 -0.0225702841 0.0042404328 20 0.7600000000 0.0203503110 0.0117407736 0.0203503110 0.0039340845 0.0022320000 14751181 955859216 1373700096 0.0095356535 -0.0226423759 0.0038045223 21 0.8000000000 0.0209115930 0.0121774793 0.0209115930 0.0038364903 0.0021590000 14753157 955859216 1373700096 0.0091881286 -0.0222864617 0.0040957672 22 0.8400000000 0.0206508543 0.0125626327 0.0209115930 0.0037445529 0.0021500000 14755133 955859216 1373700096 0.0084718298 -0.0223275609 0.0038407771 23 0.8800000000 0.0202247165 0.0128957668 0.0209115930 0.0036585350 0.0021240000 14757109 955859216 1373700096 0.0088621052 -0.0227614287 0.0038709601 24 0.9200000000 0.0203173812 0.0132050008 0.0209115930 0.0035861440 0.0021210000 14759085 955859216 1373700096 0.0098904893 -0.0231690519 0.0042031948 25 0.9600000000 0.0205075797 0.0134971039 0.0209115930 0.0035198535 0.0021200000 14761061 955859216 1373700096 0.0110950265 -0.0235088971 0.0045966874 26 1.0000000000 0.0210367441 0.0137870901 0.0210367441 0.0034536249 0.0021280000 14763037 955859216 1373700096 0.0107075600 -0.0244990773 0.0044742217 27 1.0400000000 0.0221214630 0.0140957705 0.0221214630 0.0034043364 0.0021340000 14765013 955859216 1373700096 0.0112369880 -0.0248522479 0.0048264451 28 1.0800000000 0.0215105452 0.0143605839 0.0221214630 0.0033598122 0.0021340000 14766989 955859216 1373700096 0.0127700241 -0.0254729465 0.0048259939 29 1.1200000000 0.0226657353 0.0146469685 0.0226657353 0.0035479445 0.0022840000 14768965 955859216 1373700096 0.0143609522 -0.0259730108 0.0051806374 30 1.1600000000 0.0220899899 0.0148950692 0.0226657353 0.0037907440 0.0021860000 14770941 955859216 1373700096 0.0138037121 -0.0269066691 0.0051755216 31 1.2000000000 0.0226851087 0.0151463608 0.0226851087 0.0039678284 0.0023050000 14772917 955859216 1373700096 0.0158684142 -0.0272344649 0.0055949073 32 1.2400000000 0.0237944089 0.0154166123 0.0237944089 0.0044102713 0.0023110000 14774893 955859216 1373700096 0.0180737115 -0.0270671360 0.0062140762 33 1.2800000000 0.0234563574 0.0156602409 0.0237944089 0.0047337669 0.0023260000 14779941 955859216 1373700096 0.0180813279 -0.0272678733 0.0068590543 34 1.3200000000 0.0235868115 0.0158933753 0.0237944089 0.0049339079 0.0022780000 14788317 955859216 1373700096 0.0178322233 -0.0276076477 0.0076470771 35 1.3600000000 0.0242811702 0.0161330266 0.0242811702 0.0053849580 0.0023070000 14790293 955859216 1373700096 0.0182844512 -0.0276395790 0.0084909359 36 1.4000000000 0.0231198557 0.0163271052 0.0242811702 0.0057320561 0.0022400000 14792269 955859216 1373700096 0.0191836972 -0.0282242522 0.0091560846 37 1.4400000000 0.0237602722 0.0165280016 0.0242811702 0.0061957126 0.0022330000 14794245 955859216 1373700096 0.0203502197 -0.0287794527 0.0098505095 38 1.4800000000 0.0233878251 0.0167085233 0.0242811702 0.0081842492 0.0023360000 14796221 955859216 1373700096 0.0220740829 -0.0292809792 0.0114143752 39 1.5200000000 0.0242413580 0.0169016729 0.0242811702 0.0085112495 0.0023160000 14798197 955859216 1373700096 0.0238172729 -0.0298626907 0.0126694618 40 1.5600000000 0.0249115285 0.0171019193 0.0249115285 0.0086534317 0.0023540000 14800173 955859216 1373700096 0.0251108631 -0.0306869913 0.0132725826 41 1.6000000000 0.0227688327 0.0172401367 0.0249115285 0.0087852431 0.0023920000 14802149 955859216 1373700096 0.0263059381 -0.0321806632 0.0141853299 42 1.6400000000 0.0241626035 0.0174049573 0.0249115285 0.0089383534 0.0023100000 14804125 955859216 1373700096 0.0284108911 -0.0333329588 0.0149245644 43 1.6800000000 0.0271862764 0.0176324299 0.0271862764 0.0092465104 0.0023810000 14806101 955859216 1373700096 0.0309985094 -0.0338695124 0.0162277892 44 1.7200000000 0.0295327604 0.0179028919 0.0295327604 0.0095292060 0.0023590000 14808077 955859216 1373700096 0.0330749564 -0.0345182531 0.0177205820 45 1.7600000000 0.0287108626 0.0181430690 0.0295327604 0.0098384820 0.0024340000 14810053 955859216 1373700096 0.0348768905 -0.0358344167 0.0186484717 46 1.8000000000 0.0199755318 0.0181829052 0.0295327604 0.0109503792 0.0026070000 14812029 955859216 1373700096 0.0617258549 -0.0278987940 0.0122932261 47 1.8400000000 0.0199961085 0.0182214840 0.0295327604 0.0108601887 0.0025560000 14814005 955859216 1373700096 0.1221373379 -0.0311990771 0.0012534299 48 1.8800000000 0.0230765305 0.0183226308 0.0295327604 0.0110190510 0.0024110000 14815981 955859216 1373700096 0.1248205006 -0.0344830826 0.0026400478 49 1.9200000000 0.0250668656 0.0184602682 0.0295327604 0.0111828718 0.0024600000 14817957 955859216 1373700096 0.1275688112 -0.0374044403 0.0034640215 50 1.9600000000 0.0273497682 0.0186380582 0.0295327604 0.0112860095 0.0024170000 14819933 955859216 1373700096 0.1305192113 -0.0398035087 0.0043723951 51 2.0000000000 0.0287256557 0.0188358543 0.0295327604 0.0113607454 0.0024230000 14821909 955859216 1373700096 0.1335559934 -0.0421212278 0.0046120435 52 2.0400000000 0.0299694072 0.0190499611 0.0299694072 0.0114279078 0.0023980000 14823885 955859216 1373700096 0.1370539814 -0.0441765189 0.0049694330 53 2.0800000000 0.0310971960 0.0192772674 0.0310971960 0.0114656407 0.0023190000 14825861 955859216 1373700096 0.1388612241 -0.0460855588 0.0052948026 54 2.1200000000 0.0331750363 0.0195346335 0.0331750363 0.0115027890 0.0023610000 14827837 955859216 1373700096 0.1425224394 -0.0476902574 0.0054298830 55 2.1600000000 0.0236509759 0.0196094761 0.0331750363 0.0115173714 0.0029610000 14829813 955859216 1373700096 0.1445973814 -0.0364068784 0.0016929170 56 2.2000000000 0.0255800523 0.0197160935 0.0331750363 0.0115952234 0.0023600000 14831789 955859216 1373700096 0.1458854526 -0.0398185626 0.0022106159 57 2.2400000000 0.0263877306 0.0198331398 0.0331750363 0.0117547984 0.0024160000 14833765 955859216 1373700096 0.1458458900 -0.0431387573 0.0030002850 58 2.2800000000 0.0282553695 0.0199783506 0.0331750363 0.0119247368 0.0022960000 14835741 955859216 1373700096 0.1478979141 -0.0460688733 0.0032204343 59 2.3200000000 0.0305143539 0.0201569269 0.0331750363 0.0121802259 0.0023950000 14837717 955859216 1373700096 0.1503132731 -0.0486396998 0.0033224849 60 2.3600000000 0.0321003608 0.0203559842 0.0331750363 0.0123586164 0.0023550000 14839693 955859216 1373700096 0.1535605639 -0.0509299450 0.0027072199 61 2.4000000000 0.0339621492 0.0205790361 0.0339621492 0.0126410326 0.0023060000 14841669 955859216 1373700096 0.1563147604 -0.0528781973 0.0028307629 62 2.4400000000 0.0309252981 0.0207459112 0.0339621492 0.0128605805 0.0024240000 14843645 955859216 1373700096 0.1592197865 -0.0501478054 0.0008142891 63 2.4800000000 0.0299801528 0.0208924865 0.0339621492 0.0130697555 0.0025350000 14845621 955859216 1373700096 0.1624097824 -0.0487229116 -0.0004840976 64 2.5200000000 0.0307087563 0.0210458657 0.0339621492 0.0132107492 0.0024660000 14847597 955859216 1373700096 0.1658682823 -0.0514560305 -0.0018368032 65 2.5600000000 0.0297822356 0.0211802714 0.0339621492 0.0133118029 0.0024840000 14855717 955859216 1373700096 0.1698497087 -0.0502790585 -0.0039647236 66 2.6000000000 0.0291323848 0.0213007580 0.0339621492 0.0133965358 0.0025100000 14870493 955859216 1373700096 0.1740733385 -0.0506195910 -0.0063659837 67 2.6400000000 0.0289666504 0.0214151743 0.0339621492 0.0135039886 0.0024730000 14872469 955859216 1373700096 0.1773052216 -0.0509564020 -0.0084121227 68 2.6800000000 0.0290203784 0.0215270155 0.0339621492 0.0136199006 0.0024720000 14874445 955859216 1373700096 0.1819286495 -0.0507347025 -0.0112057887 69 2.7200000000 0.0297370423 0.0216460014 0.0339621492 0.0137323554 0.0024550000 14876421 955859216 1373700096 0.1850849986 -0.0535063669 -0.0128266858 70 2.7600000000 0.0308222473 0.0217770906 0.0339621492 0.0139152545 0.0024310000 14878397 955859216 1373700096 0.1879300922 -0.0558554865 -0.0135693159 71 2.8000000000 0.0298294239 0.0218905038 0.0339621492 0.0140273189 0.0025110000 14880373 955859216 1373700096 0.1918106228 -0.0543461666 -0.0160672329 72 2.8400000000 0.0294620451 0.0219956641 0.0339621492 0.0141870423 0.0025200000 14882349 955859216 1373700096 0.1943513751 -0.0540946610 -0.0176114496 73 2.8800000000 0.0310215857 0.0221193068 0.0339621492 0.0143168942 0.0024360000 14884325 955859216 1373700096 0.1970517337 -0.0561329685 -0.0185330659 74 2.9200000000 0.0297945458 0.0222230263 0.0339621492 0.0143981152 0.0025150000 14886301 955859216 1373700096 0.2011608034 -0.0553060211 -0.0215369668 75 2.9600000000 0.0317239873 0.0223497058 0.0339621492 0.0145427263 0.0025470000 14888277 955859216 1373700096 0.2033305019 -0.0570279509 -0.0220572297 76 3.0000000000 0.0296780989 0.0224461320 0.0339621492 0.0145749987 0.0026610000 14890253 955859216 1373700096 0.2075212598 -0.0576377213 -0.0254653282 77 3.0400000000 0.0306028929 0.0225520640 0.0339621492 0.0146433319 0.0025390000 14892229 955859216 1373700096 0.2104395926 -0.0598426089 -0.0272939038 78 3.0800000000 0.0299045574 0.0226463267 0.0339621492 0.0146616791 0.0025980000 14894205 955859216 1373700096 0.2151813805 -0.0600262657 -0.0308750365 79 3.1200000000 0.0298698619 0.0227377638 0.0339621492 0.0147127641 0.0025750000 14896181 955859216 1373700096 0.2192419469 -0.0603512749 -0.0334484987 80 3.1600000000 0.0299252328 0.0228276072 0.0339621492 0.0151446660 0.0026460000 14898157 955859216 1373700096 0.2278837711 -0.0615287498 -0.0396114066 81 3.2000000000 0.0299655050 0.0229157294 0.0339621492 0.0151708531 0.0026190000 14900133 955859216 1373700096 0.2319512069 -0.0618919432 -0.0421114005 82 3.2400000000 0.0295952689 0.0229971872 0.0339621492 0.0151715809 0.0026180000 14902109 955859216 1373700096 0.2343942672 -0.0645884350 -0.0443199761 83 3.2800000000 0.0299839117 0.0230813646 0.0339621492 0.0152240470 0.0026600000 14904085 955859216 1373700096 0.2383831143 -0.0651557818 -0.0465027466 84 3.3200000000 0.0296040531 0.0231590157 0.0339621492 0.0152123990 0.0025900000 14906061 955859216 1373700096 0.2399370968 -0.0678161979 -0.0478036329 85 3.3600000000 0.0298148580 0.0232373197 0.0339621492 0.0152281233 0.0028390000 14908037 955859216 1373700096 0.2439947128 -0.0692527816 -0.0501468666 86 3.4000000000 0.0307025462 0.0233241246 0.0339621492 0.0152664515 0.0026330000 14910013 955859216 1373700096 0.2459586561 -0.0713518113 -0.0511538759 87 3.4400000000 0.0302982330 0.0234042868 0.0339621492 0.0152945782 0.0027160000 14911989 955859216 1373700096 0.2500190437 -0.0713392496 -0.0536458977 88 3.4800000000 0.0304663498 0.0234845375 0.0339621492 0.0153168959 0.0027360000 14913965 955859216 1373700096 0.2538678646 -0.0706594214 -0.0562362447 89 3.5200000000 0.0313278064 0.0235726641 0.0339621492 0.0153155574 0.0026670000 14915941 955859216 1373700096 0.2561680377 -0.0721587092 -0.0579950847 90 3.5600000000 0.0311019793 0.0236563232 0.0339621492 0.0153232336 0.0026350000 14917917 955859216 1373700096 0.2582561672 -0.0740237311 -0.0595273301 91 3.6000000000 0.0318462849 0.0237463228 0.0339621492 0.0153404986 0.0026360000 14919893 955859216 1373700096 0.2609996498 -0.0754959509 -0.0609829351 92 3.6400000000 0.0311477203 0.0238267728 0.0339621492 0.0153412380 0.0027770000 14921869 955859216 1373700096 0.2646494806 -0.0738155320 -0.0633286908 93 3.6800000000 0.0312313810 0.0239063922 0.0339621492 0.0153009795 0.0026140000 14923845 955859216 1373700096 0.2658331692 -0.0754236057 -0.0649328232 94 3.7200000000 0.0318741128 0.0239911552 0.0339621492 0.0152624702 0.0026700000 14925821 955859216 1373700096 0.2685468793 -0.0765949190 -0.0661811009 95 3.7600000000 0.0327436142 0.0240832863 0.0339621492 0.0152196843 0.0026890000 14927797 955859216 1373700096 0.2717464268 -0.0771507621 -0.0681268126 96 3.8000000000 0.0329363383 0.0241755056 0.0339621492 0.0151748372 0.0026540000 14929773 955859216 1373700096 0.2742795348 -0.0776777118 -0.0703876838 97 3.8400000000 0.0332398266 0.0242689522 0.0339621492 0.0151378633 0.0026380000 14931749 955859216 1373700096 0.2766776085 -0.0782452300 -0.0723297149 98 3.8800000000 0.0330408290 0.0243584612 0.0339621492 0.0150960513 0.0026850000 14933725 955859216 1373700096 0.2777489424 -0.0791184977 -0.0730313510 99 3.9200000000 0.0330660380 0.0244464165 0.0339621492 0.0150405784 0.0026730000 14935701 955859216 1373700096 0.2799366117 -0.0798473433 -0.0750766918 100 3.9600000000 0.0327924900 0.0245298772 0.0339621492 0.0149883574 0.0026670000 14937677 955859216 1373700096 0.2814149857 -0.0809685513 -0.0763565302 101 4.0000000000 0.0344374105 0.0246279716 0.0344374105 0.0149378530 0.0026730000 14939653 955859216 1373700096 0.2842964232 -0.0807750151 -0.0776418000 102 4.0400000000 0.0348356217 0.0247280466 0.0348356217 0.0148922146 0.0026500000 14941629 955859216 1373700096 0.2864395380 -0.0805418268 -0.0791647732 103 4.0800000000 0.0350431986 0.0248281937 0.0350431986 0.0148461930 0.0027120000 14943605 955859216 1373700096 0.2887326479 -0.0802549571 -0.0803927109 104 4.1200000000 0.0354719982 0.0249305380 0.0354719982 0.0147927470 0.0026960000 14945581 955859216 1373700096 0.2905743420 -0.0796876028 -0.0816366225 105 4.1600000000 0.0359299853 0.0250352946 0.0359299853 0.0147446853 0.0027080000 14947557 955859216 1373700096 0.2930410802 -0.0789240152 -0.0833956376 106 4.2000000000 0.0357665420 0.0251365328 0.0359299853 0.0146882533 0.0026650000 14949533 955859216 1373700096 0.2946684659 -0.0782607496 -0.0846147388 107 4.2400000000 0.0353727825 0.0252321987 0.0359299853 0.0146253493 0.0027120000 14951509 955859216 1373700096 0.2954604328 -0.0778706893 -0.0853666961 108 4.2800000000 0.0361672044 0.0253334488 0.0361672044 0.0145613166 0.0027140000 14953485 955859216 1373700096 0.2985905111 -0.0764169917 -0.0879982039 109 4.3200000000 0.0360126868 0.0254314234 0.0361672044 0.0144942501 0.0027260000 14955461 955859216 1373700096 0.3001516461 -0.0756069273 -0.0892635733 110 4.3600000000 0.0363335274 0.0255305335 0.0363335274 0.0144300600 0.0027090000 14957437 955859216 1373700096 0.3010878861 -0.0748340860 -0.0903186426 111 4.4000000000 0.0371535048 0.0256352449 0.0371535048 0.0143662524 0.0027520000 14959413 955859216 1373700096 0.3023242652 -0.0735300407 -0.0915332958 112 4.4400000000 0.0380202234 0.0257458251 0.0380202234 0.0143083020 0.0027280000 14961389 955859216 1373700096 0.3045304418 -0.0717701092 -0.0935539529 113 4.4800000000 0.0385613739 0.0258592370 0.0385613739 0.0142452827 0.0027670000 14963365 955859216 1373700096 0.3060919344 -0.0698606968 -0.0945934281 114 4.5200000000 0.0383165851 0.0259685120 0.0385613739 0.0141822011 0.0027340000 14965341 955859216 1373700096 0.3069285154 -0.0680896118 -0.0956579596 115 4.5600000000 0.0387063958 0.0260792762 0.0387063958 0.0141221606 0.0027180000 14967317 955859216 1373700096 0.3080731034 -0.0660082400 -0.0970745459 116 4.6000000000 0.0384564959 0.0261859764 0.0387063958 0.0140650837 0.0027570000 14969293 955859216 1373700096 0.3084926009 -0.0642978400 -0.0981370211 117 4.6400000000 0.0388227403 0.0262939829 0.0388227403 0.0140228581 0.0027280000 14971269 955859216 1373700096 0.3092859685 -0.0621217042 -0.0994422361 118 4.6800000000 0.0378557965 0.0263919644 0.0388227403 0.0139877697 0.0027760000 14973245 955859216 1373700096 0.3096054792 -0.0606423207 -0.1001163125 119 4.7200000000 0.0387212448 0.0264955718 0.0388227403 0.0139487240 0.0027350000 14975221 955859216 1373700096 0.3100509346 -0.0587988533 -0.1004485190 120 4.7600000000 0.0384237543 0.0265949733 0.0388227403 0.0139023615 0.0027150000 14977197 955859216 1373700096 0.3097803891 -0.0575230904 -0.1014087275 121 4.8000000000 0.0385839865 0.0266940560 0.0388227403 0.0138583686 0.0027760000 14979173 955859216 1373700096 0.3091816604 -0.0563515052 -0.1010248438 122 4.8400000000 0.0405897386 0.0268079551 0.0405897386 0.0138322986 0.0028200000 14981149 955859216 1373700096 0.3085106015 -0.0536147952 -0.1013801023 123 4.8800000000 0.0407727696 0.0269214902 0.0407727696 0.0137862076 0.0027790000 14983125 955859216 1373700096 0.3078309894 -0.0515400246 -0.1011576951 124 4.9200000000 0.0400923416 0.0270277067 0.0407727696 0.0137456299 0.0027530000 14985101 955859216 1373700096 0.3068499863 -0.0498774946 -0.1012928858 125 4.9600000000 0.0408382677 0.0271381912 0.0408382677 0.0137044448 0.0028040000 14987077 955859216 1373700096 0.3065809011 -0.0476873145 -0.1008074507 126 5.0000000000 0.0406019650 0.0272450465 0.0408382677 0.0136654974 0.0027700000 14989053 955859216 1373700096 0.3061932027 -0.0455979817 -0.1009172872 127 5.0400000000 0.0397784747 0.0273437350 0.0408382677 0.0136369030 0.0028450000 14991029 955859216 1373700096 0.3047944903 -0.0432576090 -0.1004170850 128 5.0800000000 0.0377287008 0.0274248675 0.0408382677 0.0136099781 0.0028370000 14993005 955859216 1373700096 0.3032293320 -0.0397147834 -0.1002089828 129 5.1200000000 0.0368854702 0.0274982055 0.0408382677 0.0135830337 0.0029180000 15007269 955859216 1373700096 0.3028410971 -0.0361984484 -0.1004659534 130 5.1600000000 0.0360955074 0.0275643386 0.0408382677 0.0135621585 0.0028400000 15034845 955859216 1373700096 0.3011680543 -0.0346023440 -0.0993186310 131 5.2000000000 0.0354821943 0.0276247802 0.0408382677 0.0135434140 0.0028160000 15036821 955859216 1373700096 0.2989737988 -0.0338903032 -0.0981518477 132 5.2400000000 0.0352451503 0.0276825103 0.0408382677 0.0135242545 0.0028710000 15038797 955859216 1373700096 0.2969461381 -0.0333812982 -0.0970253497 133 5.2800000000 0.0354056470 0.0277405790 0.0408382677 0.0134931157 0.0028670000 15040773 955859216 1373700096 0.2958025932 -0.0327148624 -0.0953827426 134 5.3200000000 0.0361898579 0.0278036333 0.0408382677 0.0134560780 0.0028340000 15042749 955859216 1373700096 0.2942948341 -0.0317833424 -0.0938623026 135 5.3600000000 0.0358843356 0.0278634904 0.0408382677 0.0134203550 0.0029610000 15044725 955859216 1373700096 0.2918093801 -0.0311926361 -0.0917713642 136 5.4000000000 0.0362368412 0.0279250591 0.0408382677 0.0133875765 0.0029840000 15046701 955859216 1373700096 0.2903981507 -0.0299496911 -0.0904103294 137 5.4400000000 0.0368125662 0.0279899315 0.0408382677 0.0133557858 0.0030520000 15048677 955859216 1373700096 0.2896094322 -0.0279117785 -0.0891546831 138 5.4800000000 0.0353915170 0.0280435661 0.0408382677 0.0134164983 0.0031020000 15050653 955859216 1373700096 0.2858409882 -0.0265869740 -0.0862405151 139 5.5200000000 0.0355156437 0.0280973221 0.0408382677 0.0133854019 0.0031700000 15052629 955859216 1373700096 0.2838382423 -0.0259165857 -0.0844850689 140 5.5600000000 0.0358090214 0.0281524057 0.0408382677 0.0133662312 0.0030320000 15054605 955859216 1373700096 0.2828231156 -0.0243474245 -0.0831664950 141 5.6000000000 0.0360213965 0.0282082141 0.0408382677 0.0133431230 0.0030140000 15056581 955859216 1373700096 0.2812658548 -0.0227978230 -0.0816008523 142 5.6400000000 0.0364679731 0.0282663814 0.0408382677 0.0133171288 0.0030750000 15058557 955859216 1373700096 0.2800994813 -0.0207112413 -0.0802111849 143 5.6800000000 0.0356272645 0.0283178561 0.0408382677 0.0132991555 0.0030670000 15060533 955859216 1373700096 0.2776388228 -0.0194317773 -0.0787346512 144 5.7200000000 0.0351936631 0.0283656048 0.0408382677 0.0132698869 0.0030900000 15062509 955859216 1373700096 0.2749064565 -0.0187705252 -0.0774061084 145 5.7600000000 0.0365860686 0.0284222976 0.0408382677 0.0132391412 0.0030820000 15064485 955859216 1373700096 0.2736579180 -0.0166076794 -0.0755953118 146 5.8000000000 0.0358030125 0.0284728505 0.0408382677 0.0132113254 0.0031200000 15066461 955859216 1373700096 0.2712720335 -0.0151729556 -0.0743082389 147 5.8400000000 0.0355592370 0.0285210572 0.0408382677 0.0131887809 0.0018920000 15068437 955859216 1373700096 0.2684262395 -0.0139446957 -0.0721147060 148 5.8800000000 0.0353904255 0.0285674718 0.0408382677 0.0131691534 0.0031590000 15070413 955859216 1373700096 0.2666194141 -0.0125930430 -0.0713685602 149 5.9200000000 0.0348133259 0.0286093903 0.0408382677 0.0131483697 0.0031940000 15072389 955859216 1373700096 0.2634049952 -0.0120062307 -0.0694177374 150 5.9600000000 0.0339470617 0.0286449748 0.0408382677 0.0131297927 0.0031270000 15074365 955859216 1373700096 0.2594804466 -0.0124204177 -0.0672301799 151 6.0000000000 0.0342750065 0.0286822598 0.0408382677 0.0131068919 0.0031270000 15076341 955859216 1373700096 0.2559566498 -0.0124503067 -0.0650654957 152 6.0400000000 0.0335621499 0.0287143643 0.0408382677 0.0130902635 0.0031890000 15078317 955859216 1373700096 0.2524171174 -0.0130646639 -0.0627969950 153 6.0800000000 0.0349353105 0.0287550241 0.0408382677 0.0130727111 0.0031820000 15080293 955859216 1373700096 0.2489509583 -0.0121847410 -0.0601744317 154 6.1200000000 0.0352119692 0.0287969523 0.0408382677 0.0130654825 0.0031880000 15082269 955859216 1373700096 0.2461609393 -0.0107772220 -0.0584429316 155 6.1600000000 0.0343678221 0.0288328934 0.0408382677 0.0130602754 0.0031960000 15084245 955859216 1373700096 0.2418056428 -0.0106530059 -0.0560854636 156 6.2000000000 0.0347341895 0.0288707222 0.0408382677 0.0130570541 0.0031360000 15086221 955859216 1373700096 0.2375624776 -0.0101260133 -0.0534000881 157 6.2400000000 0.0354021601 0.0289123237 0.0408382677 0.0130586132 0.0031860000 15088197 955859216 1373700096 0.2336116731 -0.0087771956 -0.0516079850 158 6.2800000000 0.0352771915 0.0289526077 0.0408382677 0.0130736204 0.0031460000 15090173 955859216 1373700096 0.2307392657 -0.0074880468 -0.0500635169 159 6.3200000000 0.0349726602 0.0289904697 0.0408382677 0.0130807095 0.0032070000 15092149 955859216 1373700096 0.2269161642 -0.0070307953 -0.0483457185 160 6.3600000000 0.0353089646 0.0290299603 0.0408382677 0.0130803386 0.0032860000 15094125 955859216 1373700096 0.2240236402 -0.0061305268 -0.0467542149 161 6.4000000000 0.0354749598 0.0290699913 0.0408382677 0.0130813707 0.0032410000 15096101 955859216 1373700096 0.2212513238 -0.0051121558 -0.0454340763 162 6.4400000000 0.0348124057 0.0291054383 0.0408382677 0.0130942955 0.0032660000 15098077 955859216 1373700096 0.2167540044 -0.0050868704 -0.0438742191 163 6.4800000000 0.0345833749 0.0291390453 0.0408382677 0.0130929473 0.0032320000 15100053 955859216 1373700096 0.2126176953 -0.0055073295 -0.0419754125 164 6.5200000000 0.0342128053 0.0291699829 0.0408382677 0.0130868202 0.0032540000 15102029 955859216 1373700096 0.2093535066 -0.0063536912 -0.0403347239 165 6.5600000000 0.0362594873 0.0292129496 0.0408382677 0.0130722156 0.0032960000 15104005 955859216 1373700096 0.2063981742 -0.0049393270 -0.0383640900 166 6.6000000000 0.0350423642 0.0292480665 0.0408382677 0.0130842864 0.0033150000 15105981 955859216 1373700096 0.2005269378 -0.0050856271 -0.0358628221 167 6.6400000000 0.0349149331 0.0292819999 0.0408382677 0.0131015606 0.0034180000 15107957 955859216 1373700096 0.1964202821 -0.0051893494 -0.0337700099 168 6.6800000000 0.0361867845 0.0293230998 0.0408382677 0.0130996548 0.0033480000 15109933 955859216 1373700096 0.1934482604 -0.0039279801 -0.0318838134 169 6.7200000000 0.0349829644 0.0293565901 0.0408382677 0.0131437894 0.0033080000 15111909 955859216 1373700096 0.1890963018 -0.0040035527 -0.0302582365 170 6.7600000000 0.0346724391 0.0293878598 0.0408382677 0.0131622280 0.0032990000 15113885 955859216 1373700096 0.1851526499 -0.0047746655 -0.0288568940 171 6.8000000000 0.0363163650 0.0294283774 0.0408382677 0.0131705393 0.0033190000 15115861 955859216 1373700096 0.1836565286 -0.0035921433 -0.0278934669 172 6.8400000000 0.0363022871 0.0294683419 0.0408382677 0.0131898524 0.0033820000 15117837 955859216 1373700096 0.1815108210 -0.0026053695 -0.0269159637 173 6.8800000000 0.0356175117 0.0295038863 0.0408382677 0.0132162839 0.0033320000 15119813 955859216 1373700096 0.1803543121 -0.0024548422 -0.0265992582 174 6.9200000000 0.0346235819 0.0295333098 0.0408382677 0.0132483187 0.0033680000 15121789 955859216 1373700096 0.1785579920 -0.0034031512 -0.0252437834 175 6.9600000000 0.0354230702 0.0295669656 0.0408382677 0.0132881615 0.0033490000 15123765 955859216 1373700096 0.1787010580 -0.0032260078 -0.0248454493 176 7.0000000000 0.0360634476 0.0296038774 0.0408382677 0.0132971120 0.0033550000 15125741 955859216 1373700096 0.1788511574 -0.0024668477 -0.0249034483 177 7.0400000000 0.0367265344 0.0296441184 0.0408382677 0.0133374974 0.0034340000 15127717 955859216 1373700096 0.1769164503 -0.0010662378 -0.0240195431 178 7.0800000000 0.0362708978 0.0296813475 0.0408382677 0.0133807547 0.0034280000 15129693 955859216 1373700096 0.1744420230 -0.0003187929 -0.0235708077 179 7.1200000000 0.0350599326 0.0297113955 0.0408382677 0.0134439969 0.0034800000 15131669 955859216 1373700096 0.1721857488 -0.0008694337 -0.0229748394 180 7.1600000000 0.0361675508 0.0297472630 0.0408382677 0.0134729939 0.0034700000 15133645 955859216 1373700096 0.1716447920 -0.0002993022 -0.0226671435 181 7.2000000000 0.0362682343 0.0297832905 0.0408382677 0.0134629456 0.0034830000 15135621 955859216 1373700096 0.1690150499 -0.0001361740 -0.0219921861 182 7.2400000000 0.0367314629 0.0298214672 0.0408382677 0.0134566198 0.0035330000 15137597 955859216 1373700096 0.1687783301 0.0006308980 -0.0220026951 183 7.2800000000 0.0368928351 0.0298601086 0.0408382677 0.0134423865 0.0035230000 15139573 955859216 1373700096 0.1644897014 0.0012318774 -0.0208195392 184 7.3200000000 0.0358204022 0.0298925015 0.0408382677 0.0134467472 0.0035890000 15141549 955859216 1373700096 0.1620906293 0.0009073836 -0.0205806307 185 7.3600000000 0.0363875479 0.0299276099 0.0408382677 0.0134338944 0.0035610000 15143525 955859216 1373700096 0.1574489623 0.0008705707 -0.0201555695 186 7.4000000000 0.0359955020 0.0299602329 0.0408382677 0.0134489099 0.0036060000 15145501 955859216 1373700096 0.1569633335 0.0008532681 -0.0196951162 187 7.4400000000 0.0353097022 0.0299888397 0.0408382677 0.0134679656 0.0035880000 15147477 955859216 1373700096 0.1542391926 -0.0001746276 -0.0195063539 188 7.4800000000 0.0354392193 0.0300178311 0.0408382677 0.0134836557 0.0036150000 15149453 955859216 1373700096 0.1513720453 -0.0011258291 -0.0185511541 189 7.5200000000 0.0365175121 0.0300522210 0.0408382677 0.0135161099 0.0036500000 15151429 955859216 1373700096 0.1495344490 -0.0007254200 -0.0177178662 190 7.5600000000 0.0356347971 0.0300816029 0.0408382677 0.0135717596 0.0036420000 15153405 955859216 1373700096 0.1464442611 -0.0015211271 -0.0170277394 191 7.6000000000 0.0369791500 0.0301177157 0.0408382677 0.0136082088 0.0036440000 15155381 955859216 1373700096 0.1455802619 -0.0006614645 -0.0167491324 192 7.6400000000 0.0366202146 0.0301515829 0.0408382677 0.0136311053 0.0035810000 15157357 955859216 1373700096 0.1428093165 -0.0006568235 -0.0164772533 193 7.6800000000 0.0368234180 0.0301861520 0.0408382677 0.0136649267 0.0036110000 15159333 955859216 1373700096 0.1415141821 -0.0001582533 -0.0159724951 194 7.7200000000 0.0361651145 0.0302169714 0.0408382677 0.0136706348 0.0036630000 15161309 955859216 1373700096 0.1389098912 -0.0010842904 -0.0162794814 195 7.7600000000 0.0373267159 0.0302534316 0.0408382677 0.0136654824 0.0036860000 15163285 955859216 1373700096 0.1400509924 -0.0000513803 -0.0161559321 196 7.8000000000 0.0369602777 0.0302876502 0.0408382677 0.0136523342 0.0036920000 15165261 955859216 1373700096 0.1364441365 -0.0002662618 -0.0162651222 197 7.8400000000 0.0343274623 0.0303081569 0.0408382677 0.0136711947 0.0037470000 15167237 955859216 1373700096 0.1388724148 0.0026559921 -0.0162212830 198 7.8800000000 0.0360076912 0.0303369424 0.0408382677 0.0136733945 0.0036730000 15169213 955859216 1373700096 0.1375416964 0.0016850632 -0.0160470903 199 7.9200000000 0.0343062766 0.0303568888 0.0408382677 0.0137022979 0.0037890000 15171189 955859216 1373700096 0.1415577382 0.0044569578 -0.0158420336 200 7.9600000000 0.0360907577 0.0303855582 0.0408382677 0.0137128138 0.0037100000 15173165 955859216 1373700096 0.1410378814 0.0040797503 -0.0157619659 201 8.0000000000 0.0362487212 0.0304147281 0.0408382677 0.0137285643 0.0037400000 15175141 955859216 1373700096 0.1430069357 0.0043099006 -0.0154554360 202 8.0400000000 0.0353925303 0.0304393707 0.0408382677 0.0137327007 0.0037340000 15177117 955859216 1373700096 0.1395865232 0.0042935382 -0.0154544106 203 8.0800000000 0.0353594273 0.0304636075 0.0408382677 0.0137161156 0.0037510000 15179093 955859216 1373700096 0.1357782185 0.0054101381 -0.0151391625 204 8.1200000000 0.0351382196 0.0304865222 0.0408382677 0.0136879324 0.0037520000 15181069 955859216 1373700096 0.1335661858 0.0075659081 -0.0145531455 205 8.1600000000 0.0337587558 0.0305024843 0.0408382677 0.0136648724 0.0037830000 15183045 955859216 1373700096 0.1307999492 0.0071822382 -0.0140116001 206 8.1999999990 0.0329654887 0.0305144407 0.0408382677 0.0136497584 0.0037690000 15185021 955859216 1373700096 0.1278346181 0.0054710340 -0.0125746252 207 8.2400000000 0.0337244123 0.0305299478 0.0408382677 0.0136434880 0.0038040000 15186997 955859216 1373700096 0.1259001642 0.0062246947 -0.0116733480 208 8.2799999990 0.0320230685 0.0305371262 0.0408382677 0.0136660591 0.0038200000 15188973 955859216 1373700096 0.1249589622 0.0049915388 -0.0099559249 209 8.3200000000 0.0331433900 0.0305495964 0.0408382677 0.0136764644 0.0038240000 15190949 955859216 1373700096 0.1236580163 0.0058836532 -0.0092969984 210 8.3599999990 0.0342933685 0.0305674239 0.0408382677 0.0136880393 0.0038150000 15192925 955859216 1373700096 0.1215659305 0.0084134825 -0.0086047510 211 8.4000000000 0.0336857177 0.0305822025 0.0408382677 0.0137235606 0.0038760000 15194901 955859216 1373700096 0.1193162575 0.0095072929 -0.0077744699 212 8.4399999990 0.0319013521 0.0305884249 0.0408382677 0.0137545286 0.0038340000 15196877 955859216 1373700096 0.1185565516 0.0082221907 -0.0058974461 213 8.4800000000 0.0333399214 0.0306013428 0.0408382677 0.0137629726 0.0038250000 15198853 955859216 1373700096 0.1157802716 0.0083049424 -0.0050106538 214 8.5200000000 0.0329148360 0.0306121535 0.0408382677 0.0137807839 0.0038810000 15200829 955859216 1373700096 0.1140562892 0.0085842041 -0.0035670639 215 8.5600000000 0.0322623104 0.0306198286 0.0408382677 0.0138153840 0.0039000000 15202805 955859216 1373700096 0.1123396754 0.0074977605 -0.0023405710 216 8.6000000000 0.0327965058 0.0306299058 0.0408382677 0.0138336020 0.0038910000 15204781 955859216 1373700096 0.1136492714 0.0108124651 -0.0000312782 217 8.6400000000 0.0325769670 0.0306388785 0.0408382677 0.0138363848 0.0038710000 15206757 955859216 1373700096 0.1137265563 0.0125985378 0.0013583676 218 8.6800000000 0.0314378440 0.0306425435 0.0408382677 0.0138485972 0.0039090000 15208733 955859216 1373700096 0.1151070744 0.0128785996 0.0035471388 219 8.7200000000 0.0309559479 0.0306439745 0.0408382677 0.0138766064 0.0038950000 15210709 955859216 1373700096 0.1167612821 0.0125791375 0.0070000407 220 8.7600000000 0.0306834672 0.0306441540 0.0408382677 0.0138904468 0.0040640000 15212685 955859216 1373700096 0.1173935533 0.0108993175 0.0103735998 221 8.8000000000 0.0310970936 0.0306462035 0.0408382677 0.0139163276 0.0040310000 15214661 955859216 1373700096 0.1186601520 0.0109056570 0.0126849394 222 8.8400000000 0.0319012031 0.0306518567 0.0408382677 0.0139434591 0.0040310000 15216637 955859216 1373700096 0.1182512939 0.0122415926 0.0144156180 223 8.8800000000 0.0314806737 0.0306555734 0.0408382677 0.0139830929 0.0040110000 15218613 955859216 1373700096 0.1172368228 0.0115404017 0.0164197478 224 8.9200000000 0.0319063179 0.0306611570 0.0408382677 0.0140009997 0.0040740000 15220589 955859216 1373700096 0.1143208668 0.0109302588 0.0175103880 225 8.9600000000 0.0311151315 0.0306631747 0.0408382677 0.0141440140 0.0043050000 15222565 955859216 1373700096 0.0727222934 0.0061426209 0.0028978563 226 9.0000000000 0.0330197737 0.0306736021 0.0408382677 0.0141471129 0.0043910000 15224541 955859216 1373700096 0.0681917667 0.0074871541 0.0020535300 227 9.0400000000 0.0324745886 0.0306815360 0.0408382677 0.0141548197 0.0041670000 15226517 955859216 1373700096 0.0646428689 0.0067973156 0.0026003707 228 9.0800000000 0.0327396318 0.0306905627 0.0408382677 0.0141625104 0.0041290000 15228493 955859216 1373700096 0.0610484257 0.0066221841 0.0027486533 229 9.1200000000 0.0327681825 0.0306996353 0.0408382677 0.0141687626 0.0041510000 15230469 955859216 1373700096 0.0568856075 0.0061592571 0.0025003026 230 9.1600000000 0.0330390409 0.0307098066 0.0408382677 0.0141782131 0.0041900000 15232445 955859216 1373700096 0.0524004996 0.0062704100 0.0025446180 231 9.2000000000 0.0329290330 0.0307194137 0.0408382677 0.0141835216 0.0041340000 15234421 955859216 1373700096 0.0484702922 0.0059580659 0.0020081007 232 9.2400000000 0.0328964069 0.0307287973 0.0408382677 0.0141897041 0.0041250000 15236397 955859216 1373700096 0.0447831638 0.0053359871 0.0023637181 233 9.2800000000 0.0331641920 0.0307392496 0.0408382677 0.0142018897 0.0041080000 15238373 955859216 1373700096 0.0418908484 0.0059759524 0.0015486354 234 9.3200000000 0.0331724882 0.0307496481 0.0408382677 0.0142054957 0.0041090000 15240349 955859216 1373700096 0.0380448289 0.0060840957 0.0008275969 235 9.3600000000 0.0329790711 0.0307591350 0.0408382677 0.0142257602 0.0041450000 15242325 955859216 1373700096 0.0351852812 0.0055350172 0.0007519504 236 9.4000000000 0.0328853875 0.0307681445 0.0408382677 0.0142636030 0.0042730000 15244301 955859216 1373700096 0.0325123444 0.0045249439 0.0004677887 237 9.4400000000 0.0325880423 0.0307758234 0.0408382677 0.0142947957 0.0042680000 15246277 955859216 1373700096 0.0297033805 0.0020519253 0.0000755558 238 9.4800000000 0.0323481113 0.0307824297 0.0408382677 0.0143204591 0.0042320000 15248253 955859216 1373700096 0.0263215266 -0.0016541131 -0.0001638839 239 9.5200000000 0.0330518447 0.0307919251 0.0408382677 0.0143327597 0.0042360000 15250229 955859216 1373700096 0.0238198880 -0.0020633386 -0.0006111120 240 9.5600000000 0.0320556872 0.0307971908 0.0408382677 0.0144869497 0.0042350000 15252205 955859216 1373700096 0.0211040918 -0.0071995175 0.0005478811 241 9.6000000000 0.0330003165 0.0308063324 0.0408382677 0.0144844236 0.0042020000 15254181 955859216 1373700096 0.0185227674 -0.0081461361 -0.0003468264 242 9.6400000000 0.0326767974 0.0308140616 0.0408382677 0.0144985252 0.0042150000 15256157 955859216 1373700096 0.0171379354 -0.0102190245 0.0001687126 243 9.6800000000 0.0325910039 0.0308213741 0.0408382677 0.0145141841 0.0042440000 15258133 955859216 1373700096 0.0153458277 -0.0127559239 -0.0000981218 244 9.7200000000 0.0328986757 0.0308298876 0.0408382677 0.0145236758 0.0041950000 15260109 955859216 1373700096 0.0137505159 -0.0137529755 0.0002728311 245 9.7600000000 0.0332309492 0.0308396879 0.0408382677 0.0145220210 0.0042060000 15262085 955859216 1373700096 0.0119228745 -0.0132884467 0.0000283775 246 9.8000000000 0.0329120420 0.0308481121 0.0408382677 0.0145266275 0.0041750000 15264061 955859216 1373700096 0.0100544253 -0.0143039022 0.0000320419 247 9.8400000000 0.0330361687 0.0308569706 0.0408382677 0.0145331445 0.0041410000 15266037 955859216 1373700096 0.0071252445 -0.0148946028 -0.0008208188 248 9.8800000000 0.0326181501 0.0308640721 0.0408382677 0.0145310875 0.0041750000 15268013 955859216 1373700096 0.0039431467 -0.0177949481 -0.0012193342 249 9.9200000000 0.0325856805 0.0308709862 0.0408382677 0.0145330934 0.0041840000 15269989 955859216 1373700096 0.0001401051 -0.0208204687 -0.0029884861 250 9.9600000000 0.0330688842 0.0308797778 0.0408382677 0.0145261583 0.0041580000 15271965 955859216 1373700096 -0.0028165868 -0.0212837234 -0.0037631602 251 10.0000000000 0.0327925570 0.0308873985 0.0408382677 0.0145273699 0.0041590000 15273941 955859216 1373700096 -0.0060104351 -0.0233607031 -0.0047828946 252 10.0400000000 0.0328504480 0.0308951883 0.0408382677 0.0145335490 0.0041770000 15275917 955859216 1373700096 -0.0094772931 -0.0254890043 -0.0061009498 253 10.0800000000 0.0329384953 0.0309032647 0.0408382677 0.0145307948 0.0041840000 15277893 955859216 1373700096 -0.0123756565 -0.0262086485 -0.0070050228 254 10.1200000000 0.0324194245 0.0309092338 0.0408382677 0.0145289827 0.0041860000 15279869 955859216 1373700096 -0.0150269279 -0.0275310874 -0.0074597369 255 10.1600000000 0.0322372206 0.0309144416 0.0408382677 0.0145231781 0.0043000000 15281845 955859216 1373700096 -0.0177445710 -0.0283819102 -0.0086307246 256 10.2000000000 0.0324325375 0.0309203716 0.0408382677 0.0145220868 0.0043370000 15283821 955859216 1373700096 -0.0201818235 -0.0297458731 -0.0090679275 257 10.2400000000 0.0323311724 0.0309258611 0.0408382677 0.0146311329 0.0041920000 15310373 955859216 1373700096 -0.0243086945 -0.0331699699 -0.0101064947 258 10.2800000000 0.0325481333 0.0309321490 0.0408382677 0.0146339886 0.0042380000 15363549 955859216 1373700096 -0.0271309353 -0.0343210548 -0.0115937516 259 10.3200000000 0.0325968862 0.0309385766 0.0408382677 0.0146255099 0.0043530000 15365525 955859216 1373700096 -0.0292111374 -0.0355039984 -0.0125303594 260 10.3600000000 0.0324728787 0.0309444777 0.0408382677 0.0146147718 0.0043020000 15367501 955859216 1373700096 -0.0311561655 -0.0371664353 -0.0132810166 261 10.4000000000 0.0324764661 0.0309503474 0.0408382677 0.0145967041 0.0042950000 15369477 955859216 1373700096 -0.0330102853 -0.0384335890 -0.0142689934 262 10.4400000000 0.0323329046 0.0309556244 0.0408382677 0.0145788058 0.0042990000 15371453 955859216 1373700096 -0.0351442248 -0.0400054120 -0.0151886391 263 10.4800000000 0.0323193669 0.0309608097 0.0408382677 0.0145613480 0.0042510000 15373429 955859216 1373700096 -0.0372625142 -0.0411665626 -0.0163039751 264 10.5200000000 0.0322982296 0.0309658757 0.0408382677 0.0145453626 0.0042610000 15375405 955859216 1373700096 -0.0389892198 -0.0424452387 -0.0167696569 265 10.5600000000 0.0322111733 0.0309705749 0.0408382677 0.0145306403 0.0042410000 15377381 955859216 1373700096 -0.0417917185 -0.0443353839 -0.0189998206 266 10.6000000000 0.0322098844 0.0309752340 0.0408382677 0.0145219608 0.0042130000 15379357 955859216 1373700096 -0.0445730053 -0.0464275666 -0.0206074957 267 10.6400000000 0.0324785039 0.0309808642 0.0408382677 0.0145242446 0.0042830000 15381333 955859216 1373700096 -0.0469560847 -0.0474894680 -0.0220906734 268 10.6800000000 0.0323673859 0.0309860378 0.0408382677 0.0145304906 0.0033960000 15383309 955859216 1373700096 -0.0494529568 -0.0491275489 -0.0237670522 269 10.7200000000 0.0323491879 0.0309911053 0.0408382677 0.0145422269 0.0024430000 15385285 955859216 1373700096 -0.0518207029 -0.0510083809 -0.0253619067 270 10.7600000000 0.0323642343 0.0309961909 0.0408382677 0.0145483898 0.0043130000 15387261 955859216 1373700096 -0.0544510894 -0.0527917035 -0.0278176796 271 10.8000000000 0.0323845409 0.0310013140 0.0408382677 0.0145536039 0.0042190000 15389237 955859216 1373700096 -0.0568297505 -0.0546502434 -0.0295822155 272 10.8400000000 0.0324563123 0.0310066632 0.0408382677 0.0145706805 0.0042580000 15391213 955859216 1373700096 -0.0592069626 -0.0564158410 -0.0316012315 273 10.8800000000 0.0324892811 0.0310120941 0.0408382677 0.0145868586 0.0042250000 15393189 955859216 1373700096 -0.0617735162 -0.0582812764 -0.0338539891 274 10.9200000000 0.0325860009 0.0310178383 0.0408382677 0.0145975078 0.0043110000 15395165 955859216 1373700096 -0.0637453422 -0.0599248372 -0.0353241973 275 10.9600000000 0.0325051211 0.0310232466 0.0408382677 0.0146061139 0.0042780000 15397141 955859216 1373700096 -0.0658461303 -0.0618927218 -0.0369931906 276 11.0000000000 0.0328411758 0.0310298333 0.0408382677 0.0146057814 0.0042750000 15399117 955859216 1373700096 -0.0677708536 -0.0627791286 -0.0388075225 277 11.0400000000 0.0317311920 0.0310323652 0.0408382677 0.0149347482 0.0043950000 15401093 955859216 1373700096 -0.0758286715 -0.0690264925 -0.0456503890 278 11.0800000000 0.0324711539 0.0310375407 0.0408382677 0.0149271512 0.0042360000 15403069 955859216 1373700096 -0.0776235461 -0.0719117820 -0.0473891310 279 11.1200000000 0.0326741524 0.0310434067 0.0408382677 0.0149140127 0.0042580000 15405045 955859216 1373700096 -0.0791180208 -0.0745424554 -0.0482767224 280 11.1600000000 0.0331231505 0.0310508344 0.0408382677 0.0149052073 0.0042670000 15407021 955859216 1373700096 -0.0802121386 -0.0759718940 -0.0489426032 281 11.2000000000 0.0330534652 0.0310579612 0.0408382677 0.0149039633 0.0043120000 15408997 955859216 1373700096 -0.0814421326 -0.0781434104 -0.0498940535 282 11.2400000000 0.0334888995 0.0310665815 0.0408382677 0.0149022367 0.0043220000 15410973 955859216 1373700096 -0.0827149823 -0.0794288889 -0.0512624793 283 11.2800000000 0.0333212763 0.0310745487 0.0408382677 0.0148949738 0.0042760000 15412949 955859216 1373700096 -0.0836950317 -0.0815345645 -0.0520783737 284 11.3200000000 0.0336335786 0.0310835593 0.0408382677 0.0149011441 0.0042920000 15414925 955859216 1373700096 -0.0848451778 -0.0832082406 -0.0531527810 285 11.3600000000 0.0336429104 0.0310925395 0.0408382677 0.0148976683 0.0042650000 15416901 955859216 1373700096 -0.0859272182 -0.0851193294 -0.0543311350 286 11.4000000000 0.0336316675 0.0311014176 0.0408382677 0.0148860054 0.0042820000 15418877 955859216 1373700096 -0.0867818370 -0.0874590278 -0.0552371256 287 11.4400000000 0.0339526683 0.0311113522 0.0408382677 0.0148698206 0.0043030000 15420853 955859216 1373700096 -0.0874876231 -0.0892717317 -0.0559852049 288 11.4800000000 0.0338925608 0.0311210092 0.0408382677 0.0148491104 0.0042890000 15422829 955859216 1373700096 -0.0885312930 -0.0914359987 -0.0572348125 289 11.5200000000 0.0339924470 0.0311309450 0.0408382677 0.0148343319 0.0042620000 15424805 955859216 1373700096 -0.0889517814 -0.0939066932 -0.0578146242 290 11.5600000000 0.0345875882 0.0311428644 0.0408382677 0.0148197404 0.0042870000 15426781 955859216 1373700096 -0.0895451456 -0.0954973251 -0.0584636033 291 11.6000000000 0.0345975868 0.0311547363 0.0408382677 0.0147976071 0.0042960000 15428757 955859216 1373700096 -0.0899109617 -0.0972519889 -0.0587880984 292 11.6400000000 0.0344640687 0.0311660697 0.0408382677 0.0147729774 0.0042520000 15430733 955859216 1373700096 -0.0906554237 -0.0992434099 -0.0600064695 293 11.6800000000 0.0345877334 0.0311777477 0.0408382677 0.0147477133 0.0042520000 15432709 955859216 1373700096 -0.0909528434 -0.1012381539 -0.0603683516 294 11.7200000000 0.0350072272 0.0311907731 0.0408382677 0.0147238705 0.0043430000 15434685 955859216 1373700096 -0.0911345482 -0.1026836112 -0.0610969737 295 11.7600000000 0.0340167060 0.0312003526 0.0408382677 0.0147066775 0.0043360000 15436661 955859216 1373700096 -0.0912310481 -0.1065269038 -0.0611958504 296 11.8000000000 0.0345385373 0.0312116302 0.0408382677 0.0146870124 0.0043380000 15438637 955859216 1373700096 -0.0912281647 -0.1092201322 -0.0614693128 297 11.8400000000 0.0352455154 0.0312252123 0.0408382677 0.0146729607 0.0042680000 15440613 955859216 1373700096 -0.0915793702 -0.1109163910 -0.0623344667 298 11.8800000000 0.0348679274 0.0312374362 0.0408382677 0.0147064749 0.0042760000 15442589 955859216 1373700096 -0.0925719887 -0.1142352223 -0.0641881898 299 11.9200000000 0.0353879035 0.0312513174 0.0408382677 0.0147093914 0.0043310000 15444565 955859216 1373700096 -0.0933612734 -0.1163733006 -0.0655176044 300 11.9600000000 0.0355747789 0.0312657289 0.0408382677 0.0147221674 0.0043100000 15446541 955859216 1373700096 -0.0937209576 -0.1184235960 -0.0661199689 301 12.0000000000 0.0356700495 0.0312803612 0.0408382677 0.0147280597 0.0043200000 15448517 955859216 1373700096 -0.0944013745 -0.1204310209 -0.0672425479 302 12.0400000000 0.0355860218 0.0312946184 0.0408382677 0.0147641076 0.0043480000 15450493 955859216 1373700096 -0.0962634310 -0.1234989166 -0.0703469142 303 12.0800000000 0.0359149165 0.0313098669 0.0408382677 0.0147496363 0.0042900000 15452469 955859216 1373700096 -0.0976962075 -0.1255218238 -0.0724372417 304 12.1200000000 0.0360553414 0.0313254770 0.0408382677 0.0147373628 0.0042830000 15454445 955859216 1373700096 -0.0991654247 -0.1275065541 -0.0748902112 305 12.1600000000 0.0364632346 0.0313423221 0.0408382677 0.0147304267 0.0043400000 15456421 955859216 1373700096 -0.1004335359 -0.1290381551 -0.0768696368 306 12.2000000000 0.0362998396 0.0313585231 0.0408382677 0.0147308939 0.0042730000 15458397 955859216 1373700096 -0.1012414619 -0.1310350746 -0.0784707367 307 12.2400000000 0.0365637504 0.0313754783 0.0408382677 0.0147436948 0.0042820000 15460373 955859216 1373700096 -0.1025451869 -0.1329817027 -0.0805092603 308 12.2800000000 0.0368029959 0.0313931001 0.0408382677 0.0147598977 0.0043140000 15462349 955859216 1373700096 -0.1040768623 -0.1348038614 -0.0830690488 309 12.3200000000 0.0368114598 0.0314106352 0.0408382677 0.0147587424 0.0043000000 15464325 955859216 1373700096 -0.1057212651 -0.1365539730 -0.0860637501 310 12.3600000000 0.0369453393 0.0314284891 0.0408382677 0.0147587414 0.0043340000 15466301 955859216 1373700096 -0.1073633283 -0.1382849813 -0.0891583413 311 12.4000000000 0.0372000858 0.0314470473 0.0408382677 0.0147583710 0.0042590000 15468277 955859216 1373700096 -0.1086468026 -0.1396545172 -0.0919932351 312 12.4400000000 0.0372894928 0.0314657731 0.0408382677 0.0147514370 0.0043110000 15470253 955859216 1373700096 -0.1099278033 -0.1408598125 -0.0946807712 313 12.4800000000 0.0373035595 0.0314844242 0.0408382677 0.0147433290 0.0044520000 15472229 955859216 1373700096 -0.1112060472 -0.1422508955 -0.0971601680 314 12.5200000000 0.0373732224 0.0315031783 0.0408382677 0.0147419344 0.0043200000 15474205 955859216 1373700096 -0.1122447178 -0.1436212659 -0.0993534625 315 12.5600000000 0.0375767015 0.0315224593 0.0408382677 0.0147441155 0.0042550000 15476181 955859216 1373700096 -0.1135932505 -0.1447473019 -0.1018734649 316 12.6000000000 0.0375774167 0.0315416206 0.0408382677 0.0147420741 0.0042420000 15478157 955859216 1373700096 -0.1148584411 -0.1458905190 -0.1043954194 317 12.6400000000 0.0377326943 0.0315611508 0.0408382677 0.0147315848 0.0042630000 15480133 955859216 1373700096 -0.1160983145 -0.1468258649 -0.1069997177 318 12.6800000000 0.0377827883 0.0315807157 0.0408382677 0.0147171630 0.0042150000 15482109 955859216 1373700096 -0.1173855141 -0.1476624012 -0.1094420254 319 12.7200000000 0.0378814302 0.0316004671 0.0408382677 0.0147331162 0.0043130000 15484085 955859216 1373700096 -0.1194221526 -0.1490863562 -0.1140609458 320 12.7600000000 0.0378471613 0.0316199881 0.0408382677 0.0147222005 0.0042890000 15486061 955859216 1373700096 -0.1205137670 -0.1499457210 -0.1162423939 321 12.8000000000 0.0381103940 0.0316402074 0.0408382677 0.0147102176 0.0042070000 15488037 955859216 1373700096 -0.1217922121 -0.1504159570 -0.1186120436 322 12.8400000000 0.0380546264 0.0316601279 0.0408382677 0.0146962319 0.0043310000 15490013 955859216 1373700096 -0.1231537536 -0.1510281265 -0.1207262278 323 12.8800000000 0.0382359810 0.0316804866 0.0408382677 0.0146824847 0.0042320000 15491989 955859216 1373700096 -0.1241940632 -0.1514846087 -0.1223820671 324 12.9200000000 0.0385393798 0.0317016560 0.0408382677 0.0146691569 0.0043180000 15493965 955859216 1373700096 -0.1254855096 -0.1516891569 -0.1245267019 325 12.9600000000 0.0386732556 0.0317231071 0.0408382677 0.0146494802 0.0042800000 15495941 955859216 1373700096 -0.1266938299 -0.1515482962 -0.1264621019 326 13.0000000000 0.0386689492 0.0317444134 0.0408382677 0.0146299242 0.0042640000 15497917 955859216 1373700096 -0.1280956864 -0.1514109969 -0.1285660863 327 13.0400000000 0.0391207784 0.0317669711 0.0408382677 0.0146102744 0.0042660000 15499893 955859216 1373700096 -0.1293800026 -0.1506900191 -0.1302718520 328 13.0800000000 0.0393449664 0.0317900747 0.0408382677 0.0145901538 0.0042620000 15501869 955859216 1373700096 -0.1307584643 -0.1497712582 -0.1322575510 329 13.1200000000 0.0397496186 0.0318142679 0.0408382677 0.0145725609 0.0042590000 15503845 955859216 1373700096 -0.1319895685 -0.1484226882 -0.1338966340 330 13.1600000000 0.0399475843 0.0318389143 0.0408382677 0.0145553204 0.0042610000 15505821 955859216 1373700096 -0.1332999319 -0.1468181908 -0.1354031414 331 13.2000000000 0.0401407816 0.0318639954 0.0408382677 0.0145397621 0.0041860000 15507797 955859216 1373700096 -0.1344814152 -0.1449523866 -0.1370088309 332 13.2400000000 0.0403837860 0.0318896575 0.0408382677 0.0145227452 0.0042370000 15509773 955859216 1373700096 -0.1357241124 -0.1427912116 -0.1381493360 333 13.2800000000 0.0405350402 0.0319156196 0.0408382677 0.0145103458 0.0042770000 15511749 955859216 1373700096 -0.1370203644 -0.1403506547 -0.1396442503 334 13.3200000000 0.0419192091 0.0319455704 0.0419192091 0.0145351770 0.0043280000 15513725 955859216 1373700096 -0.1392247677 -0.1361818612 -0.1418380141 335 13.3600000000 0.0411454812 0.0319730329 0.0419192091 0.0145231767 0.0026720000 15515701 955859216 1373700096 -0.1401995569 -0.1324832588 -0.1426399946 336 13.4000000000 0.0406676903 0.0319989098 0.0419192091 0.0145116111 0.0044060000 15517677 955859216 1373700096 -0.1412378103 -0.1291086078 -0.1433403939 337 13.4400000000 0.0396836065 0.0320217131 0.0419192091 0.0145007839 0.0042180000 15519653 955859216 1373700096 -0.1421695799 -0.1256402433 -0.1439119130 338 13.4800000000 0.0388418622 0.0320418910 0.0419192091 0.0145021706 0.0041850000 15521629 955859216 1373700096 -0.1429854780 -0.1226204932 -0.1444094926 339 13.5200000000 0.0383968875 0.0320606373 0.0419192091 0.0145130767 0.0042100000 15523605 955859216 1373700096 -0.1440514475 -0.1195477396 -0.1448765099 340 13.5600000000 0.0379274897 0.0320778928 0.0419192091 0.0145147920 0.0042880000 15525581 955859216 1373700096 -0.1448651999 -0.1167885140 -0.1447841525 341 13.6000000000 0.0376575217 0.0320942553 0.0419192091 0.0145106104 0.0043560000 15527557 955859216 1373700096 -0.1456756741 -0.1138965413 -0.1448623836 342 13.6400000000 0.0375484079 0.0321102031 0.0419192091 0.0145048349 0.0042670000 15529533 955859216 1373700096 -0.1468852907 -0.1107752398 -0.1454470903 343 13.6800000000 0.0371381529 0.0321248619 0.0419192091 0.0145131700 0.0042190000 15531509 955859216 1373700096 -0.1478026956 -0.1080268100 -0.1455845684 344 13.7200000000 0.0369592346 0.0321389153 0.0419192091 0.0145261308 0.0041300000 15533485 955859216 1373700096 -0.1485425234 -0.1050611809 -0.1457664669 345 13.7600000000 0.0370330811 0.0321531013 0.0419192091 0.0146774741 0.0041610000 15535461 955859216 1373700096 -0.1501672715 -0.0995412916 -0.1458224207 346 13.8000000000 0.0380211249 0.0321700609 0.0419192091 0.0146785362 0.0042890000 15537437 955859216 1373700096 -0.1508215219 -0.0981210843 -0.1457284242 347 13.8400000000 0.0360566527 0.0321812614 0.0419192091 0.0146884707 0.0043290000 15539413 955859216 1373700096 -0.1516966373 -0.0935122967 -0.1462410390 348 13.8800000000 0.0369912088 0.0321950831 0.0419192091 0.0146724785 0.0042190000 15541389 955859216 1373700096 -0.1525413841 -0.0914946645 -0.1463845670 349 13.9200000000 0.0361606441 0.0322064458 0.0419192091 0.0146528335 0.0045200000 15543365 955859216 1373700096 -0.1533385962 -0.0870482922 -0.1466087699 350 13.9600000000 0.0366963893 0.0322192742 0.0419192091 0.0146364378 0.0047340000 15545341 955859216 1373700096 -0.1541445702 -0.0850607753 -0.1467998028 351 14.0000000000 0.0359379649 0.0322298687 0.0419192091 0.0146362725 0.0046190000 15547317 955859216 1373700096 -0.1548370421 -0.0809871405 -0.1467479467 352 14.0400000000 0.0365596898 0.0322421694 0.0419192091 0.0146312441 0.0043740000 15549293 955859216 1373700096 -0.1555884033 -0.0786486343 -0.1466853619 353 14.0800000000 0.0357711874 0.0322521666 0.0419192091 0.0146438906 0.0045810000 15551269 955859216 1373700096 -0.1562311053 -0.0743754804 -0.1463519037 354 14.1200000000 0.0364205278 0.0322639416 0.0419192091 0.0146676677 0.0044420000 15553245 955859216 1373700096 -0.1567616016 -0.0719775185 -0.1460589319 355 14.1600000000 0.0363613293 0.0322754836 0.0419192091 0.0146902538 0.0045550000 15555221 955859216 1373700096 -0.1572748870 -0.0690081567 -0.1456361711 356 14.2000000000 0.0357354917 0.0322852027 0.0419192091 0.0147015552 0.0046180000 15557197 955859216 1373700096 -0.1577595621 -0.0649690852 -0.1454405338 357 14.2400000000 0.0363990106 0.0322967259 0.0419192091 0.0147027394 0.0044620000 15559173 955859216 1373700096 -0.1582502723 -0.0627093315 -0.1449922770 358 14.2800000000 0.0362323932 0.0323077194 0.0419192091 0.0147074317 0.0044670000 15561149 955859216 1373700096 -0.1586832851 -0.0600039773 -0.1443152428 359 14.3200000000 0.0355880670 0.0323168569 0.0419192091 0.0147160379 0.0047300000 15563125 955859216 1373700096 -0.1589233428 -0.0563194789 -0.1435740143 360 14.3600000000 0.0360420346 0.0323272046 0.0419192091 0.0147158038 0.0045370000 15565101 955859216 1373700096 -0.1591767669 -0.0538539514 -0.1431842744 361 14.4000000000 0.0354276933 0.0323357932 0.0419192091 0.0147134678 0.0047800000 15567077 955859216 1373700096 -0.1592436582 -0.0503595211 -0.1421658844 362 14.4400000000 0.0356969088 0.0323450781 0.0419192091 0.0147168733 0.0024150000 15569053 955859216 1373700096 -0.1593784392 -0.0481234379 -0.1415327191 363 14.4800000000 0.0356072411 0.0323540647 0.0419192091 0.0147190998 0.0045730000 15571029 955859216 1373700096 -0.1593576223 -0.0460802913 -0.1407424361 364 14.5200000000 0.0356804766 0.0323632032 0.0419192091 0.0147220202 0.0046290000 15573005 955859216 1373700096 -0.1594490409 -0.0433125049 -0.1401293576 365 14.5600000000 0.0355539359 0.0323719450 0.0419192091 0.0147281221 0.0046840000 15574981 955859216 1373700096 -0.1593813747 -0.0413316451 -0.1393294632 366 14.6000000000 0.0352492221 0.0323798064 0.0419192091 0.0148219336 0.0048230000 15576957 955859216 1373700096 -0.1585046947 -0.0347829722 -0.1372605860 367 14.6400000000 0.0354371294 0.0323881370 0.0419192091 0.0148349412 0.0045950000 15578933 955859216 1373700096 -0.1581911594 -0.0321611352 -0.1365456581 368 14.6800000000 0.0354671925 0.0323965040 0.0419192091 0.0148459369 0.0046870000 15580909 955859216 1373700096 -0.1573714465 -0.0293747000 -0.1348766536 369 14.7200000000 0.0350536071 0.0324037048 0.0419192091 0.0148689043 0.0048290000 15582885 955859216 1373700096 -0.1555939317 -0.0216841958 -0.1317789257 370 14.7600000000 0.0355570689 0.0324122274 0.0419192091 0.0148744969 0.0045810000 15584861 955859216 1373700096 -0.1544094086 -0.0190940034 -0.1297286600 371 14.8000000000 0.0357454605 0.0324212118 0.0419192091 0.0148761714 0.0045790000 15586837 955859216 1373700096 -0.1531744003 -0.0168199074 -0.1275315136 372 14.8400000000 0.0358138457 0.0324303318 0.0419192091 0.0148750811 0.0045860000 15588813 955859216 1373700096 -0.1520586163 -0.0147741893 -0.1250837892 373 14.8800000000 0.0360105187 0.0324399302 0.0419192091 0.0148705317 0.0045520000 15590789 955859216 1373700096 -0.1505972892 -0.0120260632 -0.1224056929 374 14.9200000000 0.0346828699 0.0324459274 0.0419192091 0.0148638324 0.0048530000 15592765 955859216 1373700096 -0.1487655491 -0.0072831339 -0.1194904223 375 14.9600000000 0.0357385427 0.0324547077 0.0419192091 0.0148585176 0.0047190000 15594741 955859216 1373700096 -0.1475177258 -0.0057076733 -0.1171420664 376 15.0000000000 0.0357961729 0.0324635945 0.0419192091 0.0148671666 0.0048060000 15596717 955859216 1373700096 -0.1459331512 -0.0034646597 -0.1145774350 377 15.0400000000 0.0358015411 0.0324724485 0.0419192091 0.0148885225 0.0047470000 15598693 955859216 1373700096 -0.1440410465 -0.0011886790 -0.1119491309 378 15.0800000000 0.0359310769 0.0324815983 0.0419192091 0.0149009091 0.0037230000 15600669 955859216 1373700096 -0.1421291828 0.0015410711 -0.1097863689 379 15.1200000000 0.0358528979 0.0324904936 0.0419192091 0.0148982888 0.0032430000 15602645 955859216 1373700096 -0.1399755478 0.0041023917 -0.1073482260 380 15.1600000000 0.0354972184 0.0324984060 0.0419192091 0.0149057321 0.0032660000 15604621 955859216 1373700096 -0.1378356069 0.0064267274 -0.1048609838 381 15.2000000000 0.0351403989 0.0325053404 0.0419192091 0.0149120417 0.0032770000 15606597 955859216 1373700096 -0.1358102709 0.0084724296 -0.1028952673 382 15.2400000000 0.0349743329 0.0325118037 0.0419192091 0.0149089873 0.0032820000 15608573 955859216 1373700096 -0.1336473227 0.0102419658 -0.1007439792 383 15.2800000000 0.0349351093 0.0325181309 0.0419192091 0.0149061374 0.0032850000 15610549 955859216 1373700096 -0.1316297352 0.0118904933 -0.0987470224 384 15.3200000000 0.0347663164 0.0325239855 0.0419192091 0.0149254308 0.0033160000 15612525 955859216 1373700096 -0.1295348704 0.0133297360 -0.0966986343 385 15.3600000000 0.0345801935 0.0325293263 0.0419192091 0.0149298366 0.0033260000 15614501 955859216 1373700096 -0.1270966232 0.0140630621 -0.0945596918 386 15.4000000000 0.0348534808 0.0325353474 0.0419192091 0.0149307295 0.0033310000 15616477 955859216 1373700096 -0.1248399764 0.0158867035 -0.0926570743 387 15.4400000000 0.0346446596 0.0325407979 0.0419192091 0.0149325499 0.0048800000 15618453 955859216 1373700096 -0.1221437305 0.0168981217 -0.0900236964 388 15.4800000000 0.0345475972 0.0325459700 0.0419192091 0.0149430531 0.0049320000 15620429 955859216 1373700096 -0.1192518771 0.0177243948 -0.0875308141 389 15.5200000000 0.0347043127 0.0325515185 0.0419192091 0.0149479317 0.0049740000 15622405 955859216 1373700096 -0.1169715226 0.0191872623 -0.0857137218 390 15.5600000000 0.0345166661 0.0325565573 0.0419192091 0.0149417032 0.0049080000 15624381 955859216 1373700096 -0.1139829159 0.0196196083 -0.0826107785 391 15.6000000000 0.0345337242 0.0325616140 0.0419192091 0.0149406852 0.0049300000 15626357 955859216 1373700096 -0.1115686148 0.0203190390 -0.0803717002 392 15.6400000000 0.0343392342 0.0325661487 0.0419192091 0.0149411866 0.0049700000 15628333 955859216 1373700096 -0.1085365489 0.0202725921 -0.0776391327 393 15.6800000000 0.0343728401 0.0325707459 0.0419192091 0.0149408017 0.0049190000 15630309 955859216 1373700096 -0.1059826463 0.0206858274 -0.0755352080 394 15.7200000000 0.0345510468 0.0325757721 0.0419192091 0.0149457113 0.0049810000 15632285 955859216 1373700096 -0.1031842753 0.0219132584 -0.0736382082 395 15.7600000000 0.0343080945 0.0325801577 0.0419192091 0.0149513812 0.0048930000 15634261 955859216 1373700096 -0.1004381180 0.0221584886 -0.0717111304 396 15.8000000000 0.0344296582 0.0325848281 0.0419192091 0.0149462348 0.0049800000 15636237 955859216 1373700096 -0.0974567309 0.0228440017 -0.0699724406 397 15.8400000000 0.0345871337 0.0325898717 0.0419192091 0.0149378084 0.0039730000 15638213 955859216 1373700096 -0.0941587761 0.0241645612 -0.0676460490 398 15.8800000000 0.0345228314 0.0325947284 0.0419192091 0.0149328334 0.0050010000 15640189 955859216 1373700096 -0.0925594643 0.0249730535 -0.0676900223 399 15.9200000000 0.0345729701 0.0325996864 0.0419192091 0.0149287157 0.0050760000 15642165 955859216 1373700096 -0.0893655717 0.0257884394 -0.0656916499 400 15.9600000000 0.0343195274 0.0326039860 0.0419192091 0.0149241549 0.0051040000 15644141 955859216 1373700096 -0.0874838457 0.0253193192 -0.0649074987 401 16.0000000000 0.0343617238 0.0326083694 0.0419192091 0.0149125535 0.0051390000 15646117 955859216 1373700096 -0.0855499953 0.0246364493 -0.0635424331 402 16.0400000000 0.0345225558 0.0326131311 0.0419192091 0.0149052956 0.0050320000 15648093 955859216 1373700096 -0.0834955052 0.0246988032 -0.0623727180 403 16.0800000000 0.0340915583 0.0326167996 0.0419192091 0.0149052133 0.0050120000 15650069 955859216 1373700096 -0.0819003135 0.0234232731 -0.0615272895 404 16.1200000000 0.0343776681 0.0326211582 0.0419192091 0.0149128578 0.0039960000 15652045 955859216 1373700096 -0.0801033154 0.0231694449 -0.0608697906 405 16.1600000000 0.0347050950 0.0326263037 0.0419192091 0.0149158938 0.0051340000 15654021 955859216 1373700096 -0.0777326226 0.0242178291 -0.0599744841 406 16.2000000000 0.0345119983 0.0326309483 0.0419192091 0.0149131882 0.0051300000 15655997 955859216 1373700096 -0.0754085183 0.0246509165 -0.0585963801 407 16.2400000000 0.0343873277 0.0326352637 0.0419192091 0.0149198793 0.0051200000 15657973 955859216 1373700096 -0.0725622624 0.0248429701 -0.0571761765 408 16.2800000000 0.0344234221 0.0326396465 0.0419192091 0.0149248989 0.0051240000 15659949 955859216 1373700096 -0.0698941723 0.0251667388 -0.0561261289 409 16.3200000000 0.0344099700 0.0326439749 0.0419192091 0.0149167353 0.0051800000 15661925 955859216 1373700096 -0.0667885691 0.0253758561 -0.0543325394 410 16.3600000000 0.0341916718 0.0326477498 0.0419192091 0.0149195676 0.0051870000 15663901 955859216 1373700096 -0.0636818856 0.0250021834 -0.0524845719 411 16.3999999990 0.0338961147 0.0326507871 0.0419192091 0.0149294870 0.0051720000 15665877 955859216 1373700096 -0.0605458990 0.0236776024 -0.0506524779 412 16.4400000000 0.0341950729 0.0326545354 0.0419192091 0.0149334705 0.0052500000 15667853 955859216 1373700096 -0.0584539324 0.0232982207 -0.0495115072 413 16.4800000000 0.0338987634 0.0326575481 0.0419192091 0.0149387699 0.0051810000 15669829 955859216 1373700096 -0.0556600131 0.0220356192 -0.0474967957 414 16.5200000000 0.0341987647 0.0326612708 0.0419192091 0.0149328600 0.0052770000 15671805 955859216 1373700096 -0.0535029471 0.0218772832 -0.0465486087 415 16.5599999990 0.0344057456 0.0326654744 0.0419192091 0.0149237207 0.0052640000 15673781 955859216 1373700096 -0.0513781384 0.0222416669 -0.0457005017 416 16.6000000000 0.0343786031 0.0326695925 0.0419192091 0.0149116695 0.0042200000 15675757 955859216 1373700096 -0.0499166586 0.0224904269 -0.0450985581 417 16.6400000000 0.0344163328 0.0326737813 0.0419192091 0.0149032183 0.0053120000 15677733 955859216 1373700096 -0.0477348156 0.0229905006 -0.0440817811 418 16.6800000000 0.0341134742 0.0326772255 0.0419192091 0.0148939503 0.0053410000 15679709 955859216 1373700096 -0.0468519665 0.0222567841 -0.0438120551 419 16.7199999990 0.0341236703 0.0326806777 0.0419192091 0.0148878114 0.0053070000 15681685 955859216 1373700096 -0.0447059013 0.0215123910 -0.0427300856 420 16.7600000000 0.0338989347 0.0326835783 0.0419192091 0.0148856099 0.0053140000 15683661 955859216 1373700096 -0.0429146551 0.0201924425 -0.0412051156 421 16.8000000000 0.0337585472 0.0326861316 0.0419192091 0.0148853563 0.0041810000 15685637 955859216 1373700096 -0.0408449210 0.0186281595 -0.0395478383 422 16.8400000000 0.0342927650 0.0326899388 0.0419192091 0.0148805668 0.0053410000 15687613 955859216 1373700096 -0.0391940214 0.0186855551 -0.0387918353 423 16.8799999990 0.0340004712 0.0326930370 0.0419192091 0.0148764107 0.0052610000 15689589 955859216 1373700096 -0.0371912271 0.0179545749 -0.0376894325 424 16.9200000000 0.0338847637 0.0326958477 0.0419192091 0.0148673230 0.0053630000 15691565 955859216 1373700096 -0.0346473157 0.0168477818 -0.0364753827 425 16.9600000000 0.0340424627 0.0326990162 0.0419192091 0.0148736323 0.0053780000 15693541 955859216 1373700096 -0.0322285928 0.0165714808 -0.0343094133 426 17.0000000000 0.0332305208 0.0327002639 0.0419192091 0.0148683312 0.0053130000 15695517 955859216 1373700096 -0.0298663732 0.0134706292 -0.0326787308 427 17.0400000000 0.0336715244 0.0327025385 0.0419192091 0.0148641155 0.0042450000 15697493 955859216 1373700096 -0.0270230342 0.0120202089 -0.0317382887 428 17.0800000000 0.0339062512 0.0327053509 0.0419192091 0.0148588124 0.0054210000 15699469 955859216 1373700096 -0.0242104977 0.0116024744 -0.0303506870 429 17.1200000000 0.0338420905 0.0327080006 0.0419192091 0.0148525595 0.0053750000 15701445 955859216 1373700096 -0.0217627157 0.0110699115 -0.0292320829 430 17.1600000000 0.0344331376 0.0327120126 0.0419192091 0.0148445435 0.0055090000 15703421 955859216 1373700096 -0.0193881448 0.0128628518 -0.0286900774 431 17.2000000000 0.0340136029 0.0327150325 0.0419192091 0.0148382327 0.0045000000 15705397 955859216 1373700096 -0.0169481020 0.0130913341 -0.0283215679 432 17.2400000000 0.0329289474 0.0327155277 0.0419192091 0.0148381584 0.0053510000 15707373 955859216 1373700096 -0.0143995639 0.0094508212 -0.0269115455 433 17.2800000000 0.0327965580 0.0327157148 0.0419192091 0.0148501784 0.0053570000 15709349 955859216 1373700096 -0.0129264211 0.0055333925 -0.0250854529 434 17.3200000000 0.0331200846 0.0327166465 0.0419192091 0.0148546879 0.0053970000 15711325 955859216 1373700096 -0.0105450405 0.0029932715 -0.0233904719 435 17.3600000000 0.0328958072 0.0327170584 0.0419192091 0.0148590890 0.0042810000 15713301 955859216 1373700096 -0.0082938410 -0.0002002689 -0.0223345775 436 17.4000000000 0.0331254378 0.0327179951 0.0419192091 0.0148579653 0.0042690000 15715277 955859216 1373700096 -0.0068766973 -0.0021573063 -0.0211768374 437 17.4400000000 0.0333225280 0.0327193784 0.0419192091 0.0148537804 0.0053970000 15717253 955859216 1373700096 -0.0061695511 -0.0030754306 -0.0207885969 438 17.4800000000 0.0333472230 0.0327208119 0.0419192091 0.0148687399 0.0054200000 15719229 955859216 1373700096 -0.0058990764 -0.0034809785 -0.0195601042 439 17.5200000000 0.0331306346 0.0327217454 0.0419192091 0.0148777179 0.0053690000 15721205 955859216 1373700096 -0.0062218509 -0.0043212534 -0.0187961832 440 17.5600000000 0.0331465229 0.0327227108 0.0419192091 0.0148814189 0.0054570000 15723181 955859216 1373700096 -0.0075469348 -0.0048126532 -0.0184704233 441 17.6000000000 0.0330363922 0.0327234221 0.0419192091 0.0148937991 0.0054080000 15725157 955859216 1373700096 -0.0088759465 -0.0053644492 -0.0173647180 442 17.6400000000 0.0326063894 0.0327231573 0.0419192091 0.0149865039 0.0043320000 15727133 955859216 1373700096 -0.0162759237 -0.0079251854 -0.0174404494 443 17.6800000000 0.0330974050 0.0327240021 0.0419192091 0.0149954848 0.0054340000 15729109 955859216 1373700096 -0.0210773554 -0.0080477195 -0.0174947232 444 17.7200000000 0.0329860672 0.0327245924 0.0419192091 0.0150004484 0.0030360000 15731085 955859216 1373700096 -0.0241119619 -0.0081610493 -0.0166982766 445 17.7600000000 0.0320513360 0.0327230794 0.0419192091 0.0150053712 0.0028580000 15733061 955859216 1373700096 -0.0262888167 -0.0113769677 -0.0158694424 446 17.8000000000 0.0322499909 0.0327220187 0.0419192091 0.0150139697 0.0028420000 15735037 955859216 1373700096 -0.0281900354 -0.0136307441 -0.0149594257 447 17.8400000000 0.0316779055 0.0327196829 0.0419192091 0.0150123463 0.0028530000 15737013 955859216 1373700096 -0.0279162042 -0.0174805038 -0.0131865935 448 17.8800000000 0.0317792520 0.0327175837 0.0419192091 0.0150037796 0.0055360000 15738989 955859216 1373700096 -0.0272567645 -0.0204126555 -0.0118941236 449 17.9200000000 0.0318127014 0.0327155684 0.0419192091 0.0149949113 0.0054870000 15740965 955859216 1373700096 -0.0284668300 -0.0232812688 -0.0097917840 450 17.9600000000 0.0316103287 0.0327131123 0.0419192091 0.0149820776 0.0054900000 15742941 955859216 1373700096 -0.0281881057 -0.0263661053 -0.0080467146 451 18.0000000000 0.0319050997 0.0327113207 0.0419192091 0.0149744399 0.0055660000 15744917 955859216 1373700096 -0.0278638899 -0.0273888353 -0.0050344425 452 18.0400000000 0.0315729082 0.0327088021 0.0419192091 0.0149685464 0.0055460000 15746893 955859216 1373700096 -0.0275848880 -0.0293447319 -0.0019329430 453 18.0800000000 0.0315517113 0.0327062478 0.0419192091 0.0149582100 0.0055600000 15748869 955859216 1373700096 -0.0267849024 -0.0308062211 0.0013308724 454 18.1200000000 0.0315772407 0.0327037610 0.0419192091 0.0149461342 0.0055960000 15750845 955859216 1373700096 -0.0262277797 -0.0314125307 0.0053105545 455 18.1600000000 0.0311644431 0.0327003779 0.0419192091 0.0149310430 0.0055120000 15752821 955859216 1373700096 -0.0249291211 -0.0326108411 0.0092249485 456 18.2000000000 0.0311029721 0.0326968748 0.0419192091 0.0149219744 0.0055220000 15754797 955859216 1373700096 -0.0237666257 -0.0336661004 0.0142439781 457 18.2400000000 0.0308369417 0.0326928049 0.0419192091 0.0149155995 0.0056310000 15756773 955859216 1373700096 -0.0220968537 -0.0302710123 0.0186599549 458 18.2800000000 0.0307630524 0.0326885915 0.0419192091 0.0149044638 0.0044930000 15758749 955859216 1373700096 -0.0209273361 -0.0294491965 0.0248788763 459 18.3200000000 0.0306377038 0.0326841233 0.0419192091 0.0148894912 0.0056290000 15760725 955859216 1373700096 -0.0186268929 -0.0291598532 0.0309987105 460 18.3600000000 0.0306239314 0.0326796446 0.0419192091 0.0148751073 0.0056550000 15762701 955859216 1373700096 -0.0171438027 -0.0254611187 0.0374645665 461 18.4000000000 0.0304958466 0.0326749075 0.0419192091 0.0148601132 0.0056980000 15764677 955859216 1373700096 -0.0163486972 -0.0255370848 0.0447044447 462 18.4400000000 0.0304548386 0.0326701022 0.0419192091 0.0148445902 0.0056750000 15766653 955859216 1373700096 -0.0128529882 -0.0249061882 0.0523674004 463 18.4800000000 0.0304877516 0.0326653887 0.0419192091 0.0148317168 0.0056180000 15768629 955859216 1373700096 -0.0120865237 -0.0226460006 0.0604082905 464 18.5200000000 0.0305812582 0.0326608970 0.0419192091 0.0148185765 0.0043020000 15770605 955859216 1373700096 -0.0109953508 -0.0206349622 0.0695060566 465 18.5600000000 0.0303657334 0.0326559612 0.0419192091 0.0148068083 0.0044770000 15772581 955859216 1373700096 -0.0068682241 -0.0138649838 0.0889692679 466 18.6000000000 0.0303618927 0.0326510383 0.0419192091 0.0147920415 0.0043380000 15774557 955859216 1373700096 -0.0041513303 -0.0099518029 0.0992882624 467 18.6400000000 0.0302362256 0.0326458674 0.0419192091 0.0147769555 0.0055150000 15776533 955859216 1373700096 -0.0013376647 -0.0088369399 0.1102312356 468 18.6800000000 0.0301501490 0.0326405347 0.0419192091 0.0147634630 0.0055230000 15778509 955859216 1373700096 0.0006176051 -0.0039618728 0.1212950945 469 18.7200000000 0.0300202370 0.0326349477 0.0419192091 0.0147524755 0.0054450000 15780485 955859216 1373700096 0.0022024529 -0.0005177530 0.1327962577 470 18.7600000000 0.0298370384 0.0326289947 0.0419192091 0.0147457594 0.0055460000 15782461 955859216 1373700096 0.0042252680 0.0048029828 0.1445339769 471 18.8000000000 0.0296488740 0.0326226675 0.0419192091 0.0147386146 0.0028380000 15784437 955859216 1373700096 0.0056550456 0.0107977958 0.1568488926 472 18.8400000000 0.0294937100 0.0326160383 0.0419192091 0.0147236950 0.0056300000 15786413 955859216 1373700096 0.0087897209 0.0171570703 0.1685871929 473 18.8800000000 0.0290643051 0.0326085294 0.0419192091 0.0147083460 0.0056340000 15788389 955859216 1373700096 0.0113499556 0.0250945333 0.1804039031 474 18.9200000000 0.0292513780 0.0326014468 0.0419192091 0.0146965779 0.0055270000 15790365 955859216 1373700096 0.0147811053 0.0311652906 0.1915800571 475 18.9600000000 0.0290594008 0.0325939898 0.0419192091 0.0146884991 0.0056930000 15792341 955859216 1373700096 0.0183967985 0.0362045802 0.2041885704 476 19.0000000000 0.0288617127 0.0325861489 0.0419192091 0.0146788045 0.0056800000 15794317 955859216 1373700096 0.0216458626 0.0391592272 0.2161785662 477 19.0400000000 0.0285271425 0.0325776395 0.0419192091 0.0146658228 0.0044570000 15796293 955859216 1373700096 0.0233023446 0.0462409481 0.2278898954 478 19.0800000000 0.0283296052 0.0325687524 0.0419192091 0.0146530089 0.0057690000 15798269 955859216 1373700096 0.0268682465 0.0537859946 0.2389784753 479 19.1200000000 0.0284609906 0.0325601767 0.0419192091 0.0146424001 0.0056310000 15800245 955859216 1373700096 0.0304472744 0.0569452420 0.2507585287 480 19.1600000000 0.0283190161 0.0325513409 0.0419192091 0.0146336734 0.0056100000 15802221 955859216 1373700096 0.0340857506 0.0618769787 0.2618918121 481 19.2000000000 0.0278199315 0.0325415043 0.0419192091 0.0146201548 0.0045850000 15804197 955859216 1373700096 0.0350640565 0.0724466890 0.2720302641 482 19.2400000000 0.0279173963 0.0325319107 0.0419192091 0.0146182133 0.0057200000 15806173 955859216 1373700096 0.0388669148 0.0766658112 0.2835552096 483 19.2800000000 0.0276697334 0.0325218441 0.0419192091 0.0146198517 0.0057340000 15808149 955859216 1373700096 0.0413219370 0.0775806084 0.2950706482 484 19.3200000000 0.0275259353 0.0325115220 0.0419192091 0.0146180898 0.0057430000 15810125 955859216 1373700096 0.0447499938 0.0790081844 0.3062285483 485 19.3600000000 0.0275026690 0.0325011944 0.0419192091 0.0146055230 0.0057150000 15812101 955859216 1373700096 0.0468629897 0.0826389492 0.3173488975 486 19.4000000000 0.0271767396 0.0324902388 0.0419192091 0.0145904752 0.0045780000 15814077 955859216 1373700096 0.0500283092 0.0898718834 0.3273700178 487 19.4400000000 0.0272956584 0.0324795723 0.0419192091 0.0145756565 0.0057260000 15816053 955859216 1373700096 0.0503879450 0.0937927291 0.3390410841 488 19.4800000000 0.0271249209 0.0324685996 0.0419192091 0.0145609589 0.0057390000 15818029 955859216 1373700096 0.0523664430 0.0966618583 0.3500559330 489 19.5200000000 0.0268124342 0.0324570328 0.0419192091 0.0145466233 0.0059010000 15820005 955859216 1373700096 0.0531733073 0.1046711206 0.3605315387 490 19.5600000000 0.0269513354 0.0324457967 0.0419192091 0.0145324547 0.0046890000 15821981 955859216 1373700096 0.0534892716 0.1098550707 0.3712354600 491 19.6000000000 0.0265886784 0.0324338678 0.0419192091 0.0145178719 0.0060710000 15823957 955859216 1373700096 0.0564028956 0.1164040565 0.3814324737 492 19.6400000000 0.0266190730 0.0324220491 0.0419192091 0.0145031116 0.0059860000 15825933 955859216 1373700096 0.0567412004 0.1207485870 0.3916333318 493 19.6800000000 0.0264928639 0.0324100223 0.0419192091 0.0144886632 0.0059790000 15827909 955859216 1373700096 0.0572747998 0.1234459728 0.4025114775 494 19.7200000000 0.0263208821 0.0323976961 0.0419192091 0.0144739960 0.0060170000 15829885 955859216 1373700096 0.0576282777 0.1247785613 0.4137189686 495 19.7600000000 0.0262057446 0.0323851871 0.0419192091 0.0144604288 0.0060080000 15831861 955859216 1373700096 0.0583122000 0.1297100931 0.4248078465 496 19.8000000000 0.0261141658 0.0323725439 0.0419192091 0.0144475937 0.0059000000 15833837 955859216 1373700096 0.0583943911 0.1365232021 0.4352115691 497 19.8400000000 0.0259950738 0.0323597120 0.0419192091 0.0144353300 0.0058040000 15835813 955859216 1373700096 0.0583007708 0.1428199410 0.4461512268 498 19.8800000000 0.0258750934 0.0323466907 0.0419192091 0.0144261696 0.0033950000 15837789 955859216 1373700096 0.0569993742 0.1497893631 0.4568037391 499 19.9200000000 0.0257186163 0.0323334080 0.0419192091 0.0144180971 0.0059700000 15839765 955859216 1373700096 0.0562777482 0.1562424153 0.4683922231 500 19.9600000000 0.0255133659 0.0323197679 0.0419192091 0.0144079734 0.0058200000 15841741 955859216 1373700096 0.0552090108 0.1583339870 0.4795452654 501 20.0000000000 0.0254128408 0.0323059816 0.0419192091 0.0143989179 0.0059090000 15843717 955859216 1373700096 0.0537655391 0.1614031643 0.4903222322 502 20.0400000000 0.0253200028 0.0322920653 0.0419192091 0.0143892371 0.0046340000 15845693 955859216 1373700096 0.0523477718 0.1662298143 0.5013278723 503 20.0800000000 0.0252113268 0.0322779883 0.0419192091 0.0143771604 0.0058570000 15847669 955859216 1373700096 0.0501868352 0.1728414297 0.5120398998 504 20.1200000000 0.0250273105 0.0322636020 0.0419192091 0.0143629219 0.0058660000 15849645 955859216 1373700096 0.0475097410 0.1780566573 0.5228541493 505 20.1600000000 0.0249192696 0.0322490588 0.0419192091 0.0143489517 0.0058570000 15851621 955859216 1373700096 0.0459020436 0.1845236868 0.5334019065 506 20.2000000000 0.0246759336 0.0322340922 0.0419192091 0.0143382387 0.0059630000 15853597 955859216 1373700096 0.0440976359 0.1939492524 0.5432601571 507 20.2400000000 0.0246087871 0.0322190521 0.0419192091 0.0143344738 0.0059350000 15855573 955859216 1373700096 0.0412341319 0.1990955323 0.5536821485 508 20.2800000000 0.0244862661 0.0322038301 0.0419192091 0.0143328303 0.0046260000 15857549 955859216 1373700096 0.0390249416 0.2038457245 0.5637086630 509 20.3200000000 0.0243602358 0.0321884203 0.0419192091 0.0143438362 0.0059630000 15859525 955859216 1373700096 0.0364057980 0.2105883807 0.5731560588 510 20.3600000000 0.0242274236 0.0321728105 0.0419192091 0.0143450608 0.0059560000 15861501 955859216 1373700096 0.0325287394 0.2153152525 0.5825455189 511 20.4000000000 0.0241128001 0.0321570375 0.0419192091 0.0143431961 0.0059150000 15863477 955859216 1373700096 0.0304632951 0.2202466875 0.5912121534 512 20.4400000000 0.0240092408 0.0321411238 0.0419192091 0.0143484730 0.0044490000 15865453 955859216 1373700096 0.0301059391 0.2268873155 0.5991079211 513 20.4800000000 0.0238633417 0.0321249878 0.0419192091 0.0143491662 0.0038180000 15916581 955859216 1373700096 0.0285200905 0.2312749624 0.6073369980 514 20.5200000000 0.0237311143 0.0321086573 0.0419192091 0.0143523225 0.0061220000 16020957 955859216 1373700096 0.0271536615 0.2335859239 0.6157953739 515 20.5600000000 0.0236693826 0.0320922703 0.0419192091 0.0143584174 0.0060830000 16022933 955859216 1373700096 0.0268906131 0.2355502844 0.6228340268 516 20.6000000000 0.0236264598 0.0320758637 0.0419192091 0.0143729286 0.0060380000 16024909 955859216 1373700096 0.0268743169 0.2411627322 0.6299549341 517 20.6400000000 0.0235056896 0.0320592870 0.0419192091 0.0143870580 0.0055880000 16026885 955859216 1373700096 0.0271363463 0.2448930442 0.6364746094 518 20.6800000000 0.0234189574 0.0320426068 0.0419192091 0.0144052614 0.0060330000 16028861 955859216 1373700096 0.0272643249 0.2480581254 0.6429074407 519 20.7200000000 0.0233819429 0.0320259196 0.0419192091 0.0144241793 0.0051060000 16030837 955859216 1373700096 0.0292185750 0.2518348396 0.6485471725 520 20.7600000000 0.0232996568 0.0320091383 0.0419192091 0.0144522383 0.0042110000 16032813 955859216 1373700096 0.0304362942 0.2548835874 0.6540456414 521 20.8000000000 0.0232223012 0.0319922730 0.0419192091 0.0144772690 0.0061080000 16034789 955859216 1373700096 0.0323915817 0.2556516528 0.6593731642 522 20.8400000000 0.0232079942 0.0319754449 0.0419192091 0.0145052837 0.0061570000 16036765 955859216 1373700096 0.0339490697 0.2559366226 0.6645515561 523 20.8800000000 0.0238577649 0.0319599235 0.0419192091 0.0145344015 0.0047540000 16038741 955859216 1373700096 0.0362141579 0.2550573349 0.6690098047 524 20.9200000000 0.0232336018 0.0319432702 0.0419192091 0.0145683181 0.0048350000 16040717 955859216 1373700096 0.0385065787 0.2591662407 0.6731811166 525 20.9600000000 0.0240231846 0.0319281843 0.0419192091 0.0145852231 0.0047490000 16042693 955859216 1373700096 0.0413826331 0.2599390745 0.6770084500 526 21.0000000000 0.0238799490 0.0319128835 0.0419192091 0.0145970991 0.0047340000 16044669 955859216 1373700096 0.0444094390 0.2595407963 0.6807254553 527 21.0400000000 0.0245158505 0.0318988474 0.0419192091 0.0146143295 0.0047260000 16046645 955859216 1373700096 0.0473871343 0.2604483366 0.6841776967 528 21.0800000000 0.0245491005 0.0318849274 0.0419192091 0.0146248152 0.0047170000 16048621 955859216 1373700096 0.0510104038 0.2620383501 0.6871426702 529 21.1200000000 0.0242391489 0.0318704741 0.0419192091 0.0146275828 0.0046850000 16050597 955859216 1373700096 0.0538168028 0.2624921799 0.6901137233 530 21.1600000000 0.0244917441 0.0318565520 0.0419192091 0.0146327301 0.0047290000 16052573 955859216 1373700096 0.0571704321 0.2633885145 0.6928440928 531 21.2000000000 0.0242439006 0.0318422156 0.0419192091 0.0146426501 0.0059980000 16054549 955859216 1373700096 0.0608481392 0.2638401389 0.6954628229 532 21.2400000000 0.0241608974 0.0318277770 0.0419192091 0.0146575968 0.0059850000 16056525 955859216 1373700096 0.0644795746 0.2632884979 0.6978168488 533 21.2800000000 0.0243472978 0.0318137423 0.0419192091 0.0146754306 0.0059330000 16058501 955859216 1373700096 0.0683840737 0.2633152604 0.7000467181 534 21.3200000000 0.0243917815 0.0317998435 0.0419192091 0.0146921261 0.0059240000 16060477 955859216 1373700096 0.0723929182 0.2632381916 0.7022916675 535 21.3600000000 0.0245939568 0.0317863746 0.0419192091 0.0147089677 0.0046230000 16062453 955859216 1373700096 0.0760928690 0.2634608150 0.7046391964 536 21.4000000000 0.0247292481 0.0317732083 0.0419192091 0.0147258107 0.0059840000 16064429 955859216 1373700096 0.0797965825 0.2638156116 0.7067971230 537 21.4400000000 0.0248761959 0.0317603647 0.0419192091 0.0147447995 0.0046180000 16066405 955859216 1373700096 0.0842980146 0.2642472386 0.7090659142 538 21.4800000000 0.0250442848 0.0317478813 0.0419192091 0.0147538351 0.0060310000 16068381 955859216 1373700096 0.0889604613 0.2649888694 0.7109858394 539 21.5200000000 0.0251418538 0.0317356252 0.0419192091 0.0147640426 0.0059590000 16070357 955859216 1373700096 0.0940008759 0.2660844028 0.7126265764 540 21.5600000000 0.0247182995 0.0317226302 0.0419192091 0.0147660682 0.0059740000 16072333 955859216 1373700096 0.0977400243 0.2668574452 0.7148362994 541 21.6000000000 0.0247309152 0.0317097065 0.0419192091 0.0147697239 0.0059510000 16074309 955859216 1373700096 0.1022977158 0.2669520974 0.7166973948 542 21.6400000000 0.0253780019 0.0316980244 0.0419192091 0.0147773924 0.0045750000 16076285 955859216 1373700096 0.1062101126 0.2676832676 0.7185893059 543 21.6800000000 0.0253320709 0.0316863007 0.0419192091 0.0147940239 0.0059330000 16078261 955859216 1373700096 0.1100994349 0.2684715092 0.7206655741 544 21.7200000000 0.0253393799 0.0316746335 0.0419192091 0.0148087821 0.0059030000 16080237 955859216 1373700096 0.1132044569 0.2690368295 0.7228357792 545 21.7600000000 0.0257283840 0.0316637230 0.0419192091 0.0148233309 0.0045790000 16082213 955859216 1373700096 0.1175110042 0.2704452574 0.7249649763 546 21.8000000000 0.0235891026 0.0316489343 0.0419192091 0.0148993394 0.0060400000 16084189 955859216 1373700096 0.1227250546 0.2738227248 0.7295444608 547 21.8400000000 0.0248557404 0.0316365153 0.0419192091 0.0149079654 0.0059030000 16086165 955859216 1373700096 0.1268105656 0.2734086812 0.7316938043 548 21.8800000000 0.0258700885 0.0316259926 0.0419192091 0.0149212695 0.0045430000 16088141 955859216 1373700096 0.1311535537 0.2742384076 0.7334473729 549 21.9200000000 0.0260755122 0.0316158825 0.0419192091 0.0149424506 0.0058700000 16090117 955859216 1373700096 0.1347951442 0.2757714093 0.7355908155 550 21.9600000000 0.0258289333 0.0316053607 0.0419192091 0.0149593754 0.0058610000 16092093 955859216 1373700096 0.1399649382 0.2770105898 0.7371714711 551 22.0000000000 0.0264715124 0.0315960434 0.0419192091 0.0149867654 0.0058940000 16094069 955859216 1373700096 0.1433642805 0.2788232565 0.7387554646 552 22.0400000000 0.0260735806 0.0315860390 0.0419192091 0.0149978164 0.0045160000 16096045 955859216 1373700096 0.1478366554 0.2816433907 0.7401289344 553 22.0800000000 0.0249139145 0.0315739736 0.0419192091 0.0149944099 0.0058680000 16098021 955859216 1373700096 0.1521383375 0.2827099860 0.7417132258 554 22.1200000000 0.0250082947 0.0315621222 0.0419192091 0.0149879196 0.0058650000 16099997 955859216 1373700096 0.1554762125 0.2818056345 0.7438009381 555 22.1600000000 0.0267682876 0.0315534847 0.0419192091 0.0149801541 0.0058590000 16101973 955859216 1373700096 0.1614396721 0.2818101943 0.7449225187 556 22.2000000000 0.0278025232 0.0315467384 0.0419192091 0.0149793140 0.0058370000 16103949 955859216 1373700096 0.1669425517 0.2837586701 0.7461425662 557 22.2400000000 0.0273144338 0.0315391400 0.0419192091 0.0149755856 0.0058620000 16105925 955859216 1373700096 0.1714849621 0.2859936655 0.7476570010 558 22.2800000000 0.0275035743 0.0315319078 0.0419192091 0.0149750183 0.0045200000 16107901 955859216 1373700096 0.1767136455 0.2886740565 0.7491693497 559 22.3200000000 0.0273579191 0.0315244409 0.0419192091 0.0149720578 0.0058650000 16109877 955859216 1373700096 0.1822200716 0.2914456725 0.7505777478 560 22.3600000000 0.0266037770 0.0315156540 0.0419192091 0.0149683458 0.0058960000 16111853 955859216 1373700096 0.1863955408 0.2931306064 0.7530370355 561 22.4000000000 0.0272308178 0.0315080161 0.0419192091 0.0149647357 0.0044890000 16113829 955859216 1373700096 0.1905028969 0.2947755158 0.7548192739 562 22.4400000000 0.0278805736 0.0315015616 0.0419192091 0.0149624243 0.0038310000 16115805 955859216 1373700096 0.1956629306 0.2973637879 0.7560113072 563 22.4800000000 0.0276278555 0.0314946811 0.0419192091 0.0149553831 0.0038110000 16117781 955859216 1373700096 0.2015529871 0.3011253774 0.7566574812 564 22.5200000000 0.0263696872 0.0314855943 0.0419192091 0.0149460556 0.0058960000 16119757 955859216 1373700096 0.2060006559 0.3041796088 0.7582490444 565 22.5600000000 0.0256866310 0.0314753306 0.0419192091 0.0149362240 0.0059090000 16121733 955859216 1373700096 0.2094794810 0.3058714271 0.7599108219 566 22.6000000000 0.0265857447 0.0314666918 0.0419192091 0.0149270929 0.0058720000 16123709 955859216 1373700096 0.2144996822 0.3080964088 0.7612450719 567 22.6400000000 0.0262256190 0.0314574483 0.0419192091 0.0149159335 0.0058830000 16125685 955859216 1373700096 0.2191898227 0.3105901778 0.7622875571 568 22.6800000000 0.0259982441 0.0314478370 0.0419192091 0.0149063529 0.0044730000 16127661 955859216 1373700096 0.2235735059 0.3126586676 0.7636961937 569 22.7200000000 0.0258868691 0.0314380637 0.0419192091 0.0148950091 0.0058730000 16129637 955859216 1373700096 0.2285047621 0.3141736090 0.7641899586 570 22.7600000000 0.0266748406 0.0314297072 0.0419192091 0.0148843808 0.0059500000 16131613 955859216 1373700096 0.2329019010 0.3161857128 0.7650186419 571 22.8000000000 0.0268638860 0.0314217110 0.0419192091 0.0148723174 0.0059500000 16133589 955859216 1373700096 0.2379450798 0.3186682463 0.7657746077 572 22.8400000000 0.0269114375 0.0314138259 0.0419192091 0.0148597867 0.0044940000 16135565 955859216 1373700096 0.2434009612 0.3215014338 0.7655501366 573 22.8800000000 0.0262451898 0.0314048056 0.0419192091 0.0148484599 0.0057880000 16137541 955859216 1373700096 0.2480086386 0.3244480193 0.7660902739 574 22.9200000000 0.0261225477 0.0313956031 0.0419192091 0.0148372218 0.0058480000 16139517 955859216 1373700096 0.2521698773 0.3276643753 0.7663497925 575 22.9600000000 0.0256782454 0.0313856599 0.0419192091 0.0148244813 0.0057960000 16141493 955859216 1373700096 0.2561183274 0.3309315443 0.7669675946 576 23.0000000000 0.0262054596 0.0313766665 0.0419192091 0.0148116787 0.0044130000 16143469 955859216 1373700096 0.2596705258 0.3337416649 0.7675700188 577 23.0400000000 0.0262889974 0.0313678490 0.0419192091 0.0147988376 0.0058150000 16145445 955859216 1373700096 0.2634263039 0.3371904194 0.7679555416 578 23.0800000000 0.0256287903 0.0313579198 0.0419192091 0.0147861917 0.0059150000 16147421 955859216 1373700096 0.2662663460 0.3396461308 0.7683519125 579 23.1200000000 0.0269142855 0.0313502452 0.0419192091 0.0147739349 0.0058990000 16149397 955859216 1373700096 0.2698073983 0.3418638706 0.7681629658 580 23.1600000000 0.0276263654 0.0313438247 0.0419192091 0.0147618283 0.0045100000 16151373 955859216 1373700096 0.2744058669 0.3469103873 0.7679374814 581 23.2000000000 0.0266184118 0.0313356914 0.0419192091 0.0147492414 0.0058870000 16153349 955859216 1373700096 0.2780496776 0.3525472283 0.7676292658 582 23.2400000000 0.0255600493 0.0313257677 0.0419192091 0.0147366839 0.0058880000 16155325 955859216 1373700096 0.2806731462 0.3570991755 0.7675249577 583 23.2800000000 0.0258361716 0.0313163515 0.0419192091 0.0147241502 0.0044520000 16157301 955859216 1373700096 0.2838075757 0.3618400693 0.7675991058 584 23.3200000000 0.0247191377 0.0313050549 0.0419192091 0.0147127058 0.0058710000 16159277 955859216 1373700096 0.2861574888 0.3658755422 0.7669119835 585 23.3600000000 0.0241479427 0.0312928206 0.0419192091 0.0147007396 0.0058560000 16161253 955859216 1373700096 0.2886467576 0.3685297370 0.7664839029 586 23.4000000000 0.0245546661 0.0312813220 0.0419192091 0.0146886238 0.0058700000 16163229 955859216 1373700096 0.2909794152 0.3710393608 0.7664773464 587 23.4400000000 0.0247918740 0.0312702667 0.0419192091 0.0146761339 0.0045280000 16165205 955859216 1373700096 0.2931503057 0.3740229011 0.7662399411 588 23.4800000000 0.0243871808 0.0312585608 0.0419192091 0.0146637411 0.0045540000 16167181 955859216 1373700096 0.2953227460 0.3771962821 0.7661150694 589 23.5200000000 0.0241069105 0.0312464188 0.0419192091 0.0146513975 0.0045530000 16169157 955859216 1373700096 0.2979528606 0.3802452385 0.7659408450 590 23.5600000000 0.0235570464 0.0312333859 0.0419192091 0.0146390208 0.0059580000 16171133 955859216 1373700096 0.2999216318 0.3826175630 0.7661656141 591 23.6000000000 0.0239716675 0.0312210988 0.0419192091 0.0146267283 0.0059340000 16173109 955859216 1373700096 0.3018310368 0.3849234581 0.7666937113 592 23.6400000000 0.0239391755 0.0312087982 0.0419192091 0.0146153028 0.0026290000 16175085 955859216 1373700096 0.3040395379 0.3875973523 0.7663752437 593 23.6800000000 0.0221341997 0.0311934954 0.0419192091 0.0146062332 0.0059400000 16177061 955859216 1373700096 0.3092177212 0.3930417299 0.7659626007 594 23.7200000000 0.0223425999 0.0311785949 0.0419192091 0.0145939324 0.0060630000 16179037 955859216 1373700096 0.3103033602 0.3934237063 0.7667702436 595 23.7600000000 0.0233295038 0.0311654031 0.0419192091 0.0145819568 0.0059910000 16181013 955859216 1373700096 0.3114816546 0.3942886889 0.7673004270 596 23.8000000000 0.0239522718 0.0311533005 0.0419192091 0.0145697770 0.0042020000 16182989 955859216 1373700096 0.3128912151 0.3960367441 0.7680387497 597 23.8400000000 0.0237979982 0.0311409801 0.0419192091 0.0145578268 0.0037990000 16184965 955859216 1373700096 0.3141023815 0.3982872069 0.7684923410 598 23.8800000000 0.0230342653 0.0311274237 0.0419192091 0.0145465709 0.0038400000 16186941 955859216 1373700096 0.3147474229 0.4001263678 0.7692523003 599 23.9200000000 0.0231953114 0.0311141815 0.0419192091 0.0145364838 0.0038260000 16188917 955859216 1373700096 0.3154763281 0.4017989933 0.7701527476 600 23.9600000000 0.0229773354 0.0311006201 0.0419192091 0.0145266410 0.0040920000 16190893 955859216 1373700096 0.3156802654 0.4037731290 0.7709211111 601 24.0000000000 0.0222790688 0.0310859419 0.0419192091 0.0145176437 0.0039040000 16192869 955859216 1373700096 0.3174282312 0.4082585275 0.7718586922 602 24.0400000000 0.0224947669 0.0310716709 0.0419192091 0.0145071812 0.0037870000 16194845 955859216 1373700096 0.3172477782 0.4082839489 0.7729919553 603 24.0800000000 0.0230072513 0.0310582971 0.0419192091 0.0144967438 0.0038330000 16196821 955859216 1373700096 0.3177362978 0.4089176059 0.7738932967 604 24.1200000000 0.0235055164 0.0310457924 0.0419192091 0.0144849406 0.0060170000 16198797 955859216 1373700096 0.3184115589 0.4096701443 0.7747810483 605 24.1600000000 0.0240333360 0.0310342016 0.0419192091 0.0144730687 0.0037540000 16200773 955859216 1373700096 0.3202717900 0.4136130214 0.7755568624 606 24.2000000000 0.0236109756 0.0310219521 0.0419192091 0.0144611056 0.0025470000 16202749 955859216 1373700096 0.3203151524 0.4156037271 0.7768030167 607 24.2400000000 0.0234774947 0.0310095230 0.0419192091 0.0144494501 0.0060070000 16204725 955859216 1373700096 0.3209113181 0.4173671901 0.7773404121 608 24.2800000000 0.0234017856 0.0309970102 0.0419192091 0.0144377272 0.0059860000 16206701 955859216 1373700096 0.3213744760 0.4184477031 0.7782877088 609 24.3200000000 0.0233981218 0.0309845326 0.0419192091 0.0144260734 0.0059890000 16208677 955859216 1373700096 0.3218810856 0.4197412729 0.7787225246 610 24.3600000000 0.0241424441 0.0309733161 0.0419192091 0.0144143212 0.0059470000 16210653 955859216 1373700096 0.3224716187 0.4217458069 0.7791486979 611 24.4000000000 0.0243730601 0.0309625137 0.0419192091 0.0144025300 0.0045460000 16212629 955859216 1373700096 0.3231566250 0.4239093661 0.7795730829 612 24.4400000000 0.0239568334 0.0309510665 0.0419192091 0.0143907661 0.0045340000 16214605 955859216 1373700096 0.3229166269 0.4261277318 0.7804719210 613 24.4800000000 0.0242272429 0.0309400978 0.0419192091 0.0143792628 0.0060680000 16216581 955859216 1373700096 0.3233312964 0.4283546507 0.7810938954 614 24.5200000000 0.0238823071 0.0309286030 0.0419192091 0.0143681366 0.0060080000 16218557 955859216 1373700096 0.3231431246 0.4304992855 0.7819014192 615 24.5600000000 0.0238213502 0.0309170465 0.0419192091 0.0143573433 0.0060250000 16220533 955859216 1373700096 0.3223790526 0.4332833290 0.7828993201 616 24.6000000000 0.0235065538 0.0309050165 0.0419192091 0.0143463448 0.0045510000 16222509 955859216 1373700096 0.3214840591 0.4354996383 0.7842132449 617 24.6400000000 0.0237623528 0.0308934400 0.0419192091 0.0143349567 0.0060510000 16224485 955859216 1373700096 0.3202754259 0.4371954203 0.7856087685 618 24.6800000000 0.0240363646 0.0308823444 0.0419192091 0.0143255158 0.0061410000 16226461 955859216 1373700096 0.3192813993 0.4387929738 0.7871356606 619 24.7200000000 0.0241159834 0.0308714133 0.0419192091 0.0143162661 0.0054070000 16228437 955859216 1373700096 0.3178498447 0.4415349960 0.7884770036 620 24.7600000000 0.0238200855 0.0308600402 0.0419192091 0.0143077740 0.0061310000 16230413 955859216 1373700096 0.3160975873 0.4433914125 0.7899006009 621 24.8000000000 0.0244113822 0.0308496559 0.0419192091 0.0142998518 0.0059320000 16232389 955859216 1373700096 0.3139467835 0.4445889592 0.7919291258 622 24.8400000000 0.0247730315 0.0308398864 0.0419192091 0.0142927074 0.0045830000 16234365 955859216 1373700096 0.3118218184 0.4461745620 0.7942745090 623 24.8800000000 0.0257220939 0.0308316717 0.0419192091 0.0142883134 0.0045810000 16236341 955859216 1373700096 0.3097756803 0.4485263228 0.7964780927 624 24.9200000000 0.0250681750 0.0308224353 0.0419192091 0.0142821534 0.0060860000 16238317 955859216 1373700096 0.3083001971 0.4502012730 0.7983176708 625 24.9600000000 0.0256908573 0.0308142248 0.0419192091 0.0142752292 0.0060640000 16240293 955859216 1373700096 0.3062106967 0.4520388246 0.8004233837 626 25.0000000000 0.0257409755 0.0308061205 0.0419192091 0.0142685966 0.0045690000 16242269 955859216 1373700096 0.3040549159 0.4554453492 0.8023358583 627 25.0400000000 0.0224310290 0.0307927631 0.0419192091 0.0142664381 0.0063100000 16244245 955859216 1373700096 0.3051266968 0.4624546468 0.8018365502 628 25.0800000000 0.0230548233 0.0307804416 0.0419192091 0.0142658561 0.0061290000 16246221 955859216 1373700096 0.3015739918 0.4640945196 0.8043721318 629 25.1200000000 0.0239719748 0.0307696173 0.0419192091 0.0142682181 0.0046100000 16248197 955859216 1373700096 0.2993933558 0.4652793109 0.8059667349 630 25.1600000000 0.0241006818 0.0307590317 0.0419192091 0.0142626213 0.0060940000 16250173 955859216 1373700096 0.2963653207 0.4667118490 0.8081218004 631 25.2000000000 0.0246988442 0.0307494276 0.0419192091 0.0142570612 0.0060990000 16252149 955859216 1373700096 0.2935524285 0.4683995247 0.8099334240 632 25.2400000000 0.0240488537 0.0307388254 0.0419192091 0.0142506674 0.0046690000 16254125 955859216 1373700096 0.2906000316 0.4691937864 0.8124144673 633 25.2800000000 0.0245394912 0.0307290318 0.0419192091 0.0142421761 0.0061930000 16256101 955859216 1373700096 0.2868418694 0.4702573121 0.8146023750 634 25.3200000000 0.0250936113 0.0307201431 0.0419192091 0.0142336822 0.0053690000 16258077 955859216 1373700096 0.2833403647 0.4724449813 0.8170906901 635 25.3600000000 0.0248007160 0.0307108212 0.0419192091 0.0142262951 0.0038780000 16260053 955859216 1373700096 0.2795190215 0.4749660492 0.8198082447 636 25.4000000000 0.0242263749 0.0307006255 0.0419192091 0.0142201360 0.0061830000 16262029 955859216 1373700096 0.2756698728 0.4767087102 0.8221814632 637 25.4400000000 0.0241605453 0.0306903585 0.0419192091 0.0142136006 0.0061870000 16264005 955859216 1373700096 0.2715539634 0.4779073000 0.8250179291 638 25.4800000000 0.0238777846 0.0306796805 0.0419192091 0.0142062727 0.0046400000 16265981 955859216 1373700096 0.2669613957 0.4793436825 0.8282379508 639 25.5200000000 0.0232269187 0.0306680174 0.0419192091 0.0141991836 0.0061900000 16267957 955859216 1373700096 0.2626179755 0.4803573191 0.8313456774 640 25.5600000000 0.0225459002 0.0306553266 0.0419192091 0.0141908458 0.0062150000 16269933 955859216 1373700096 0.2581802905 0.4803986549 0.8347485065 641 25.6000000000 0.0226890985 0.0306428987 0.0419192091 0.0141827351 0.0046540000 16271909 955859216 1373700096 0.2533594966 0.4804068506 0.8379323483 642 25.6400000000 0.0234781615 0.0306317387 0.0419192091 0.0141786555 0.0039100000 16273885 955859216 1373700096 0.2489883155 0.4820317924 0.8409064412 643 25.6800000000 0.0234667994 0.0306205957 0.0419192091 0.0141761466 0.0039450000 16275861 955859216 1373700096 0.2442756295 0.4831887186 0.8439947963 644 25.7200000000 0.0230582748 0.0306088530 0.0419192091 0.0141727044 0.0061450000 16277837 955859216 1373700096 0.2399898916 0.4835680425 0.8468038440 645 25.7600000000 0.0236388799 0.0305980468 0.0419192091 0.0141667898 0.0029020000 16279813 955859216 1373700096 0.2356910110 0.4848066568 0.8493866920 646 25.8000000000 0.0237378236 0.0305874273 0.0419192091 0.0141611936 0.0061820000 16281789 955859216 1373700096 0.2313452363 0.4862783253 0.8522571325 647 25.8400000000 0.0234547816 0.0305764031 0.0419192091 0.0141551525 0.0061870000 16283765 955859216 1373700096 0.2266083211 0.4868142009 0.8553209901 648 25.8800000000 0.0244837981 0.0305670009 0.0419192091 0.0141475327 0.0061790000 16285741 955859216 1373700096 0.2220411450 0.4877135754 0.8580953479 649 25.9200000000 0.0248443447 0.0305581833 0.0419192091 0.0141397170 0.0046840000 16287717 955859216 1373700096 0.2176132798 0.4891597927 0.8608119488 650 25.9600000000 0.0216407925 0.0305444642 0.0419192091 0.0141336869 0.0064290000 16289693 955859216 1373700096 0.2150667757 0.4962352812 0.8625177145 651 26.0000000000 0.0218112748 0.0305310492 0.0419192091 0.0141326920 0.0063440000 16291669 955859216 1373700096 0.2116662562 0.4979377985 0.8647624850 652 26.0400000000 0.0218023863 0.0305176617 0.0419192091 0.0141295820 0.0048320000 16293645 955859216 1373700096 0.2078923285 0.5001096129 0.8666284680 653 26.0800000000 0.0223936737 0.0305052206 0.0419192091 0.0141284831 0.0062410000 16295621 955859216 1373700096 0.2024003267 0.5009015799 0.8691832423 654 26.1200000000 0.0218623914 0.0304920053 0.0419192091 0.0141283543 0.0055530000 16297597 955859216 1373700096 0.1988416910 0.5028246641 0.8712652326 655 26.1600000000 0.0213933047 0.0304781142 0.0419192091 0.0141242449 0.0042180000 16299573 955859216 1373700096 0.1962475181 0.5067526698 0.8727943897 656 26.2000000000 0.0227779001 0.0304663760 0.0419192091 0.0141199677 0.0062580000 16301549 955859216 1373700096 0.1861973405 0.5085326433 0.8767068386 657 26.2400000000 0.0215882901 0.0304528630 0.0419192091 0.0141179736 0.0064440000 16303525 955859216 1373700096 0.1837199032 0.5101839900 0.8783254623 658 26.2800000000 0.0215977561 0.0304394054 0.0419192091 0.0141110067 0.0049320000 16305501 955859216 1373700096 0.1800259948 0.5120959282 0.8798893094 659 26.3200000000 0.0211875662 0.0304253662 0.0419192091 0.0141068147 0.0067890000 16307477 955859216 1373700096 0.1768511683 0.5162960887 0.8811717033 660 26.3600000000 0.0213590674 0.0304116293 0.0419192091 0.0141043421 0.0061650000 16309453 955859216 1373700096 0.1729300618 0.5170506239 0.8827063441 661 26.4000000000 0.0215010010 0.0303981488 0.0419192091 0.0141027503 0.0050350000 16311429 955859216 1373700096 0.1701533049 0.5207079053 0.8834203482 662 26.4400000000 0.0213839691 0.0303845322 0.0419192091 0.0140971702 0.0065030000 16313405 955859216 1373700096 0.1676097661 0.5237069130 0.8842016459 663 26.4800000000 0.0216021948 0.0303712859 0.0419192091 0.0140939335 0.0063720000 16315381 955859216 1373700096 0.1630717218 0.5230871439 0.8858539462 664 26.5200000000 0.0213275142 0.0303576657 0.0419192091 0.0140926471 0.0044230000 16317357 955859216 1373700096 0.1614146084 0.5250667930 0.8866665363 665 26.5600000000 0.0229371302 0.0303465070 0.0419192091 0.0140904709 0.0036670000 16319333 955859216 1373700096 0.1574608684 0.5254938006 0.8879797459 666 26.6000000000 0.0232433490 0.0303358416 0.0419192091 0.0140856795 0.0064840000 16321309 955859216 1373700096 0.1544847041 0.5263351798 0.8890061378 667 26.6400000000 0.0235810112 0.0303257144 0.0419192091 0.0140803085 0.0064960000 16323285 955859216 1373700096 0.1505483985 0.5279209614 0.8899649978 668 26.6800000000 0.0234488733 0.0303154198 0.0419192091 0.0140750304 0.0057200000 16325261 955859216 1373700096 0.1466456801 0.5300433636 0.8909936547 669 26.7200000000 0.0209608246 0.0303014368 0.0419192091 0.0140720528 0.0051070000 16327237 955859216 1373700096 0.1436538398 0.5346431136 0.8916831613 670 26.7600000000 0.0216157809 0.0302884731 0.0419192091 0.0140654581 0.0064370000 16329213 955859216 1373700096 0.1387198865 0.5329561234 0.8930180073 671 26.8000000000 0.0211078469 0.0302747911 0.0419192091 0.0140607278 0.0051450000 16331189 955859216 1373700096 0.1357583106 0.5328171849 0.8944759965 672 26.8400000000 0.0221147910 0.0302626483 0.0419192091 0.0140528714 0.0042560000 16333165 955859216 1373700096 0.1312115639 0.5316647291 0.8960366249 673 26.8800000000 0.0211510397 0.0302491095 0.0419192091 0.0140439138 0.0043260000 16335141 955859216 1373700096 0.1280450821 0.5327895880 0.8972328901 674 26.9200000000 0.0208528675 0.0302351685 0.0419192091 0.0140401121 0.0067520000 16337117 955859216 1373700096 0.1240938380 0.5325394273 0.8987478018 675 26.9600000000 0.0214169789 0.0302221045 0.0419192091 0.0140362293 0.0065950000 16339093 955859216 1373700096 0.1195971668 0.5318319201 0.8998968601 676 27.0000000000 0.0217940304 0.0302096369 0.0419192091 0.0140283616 0.0066080000 16341069 955859216 1373700096 0.1151814610 0.5316956043 0.9007592201 677 27.0400000000 0.0215205438 0.0301968022 0.0419192091 0.0140215341 0.0048720000 16343045 955859216 1373700096 0.1105167642 0.5321134925 0.9014984965 678 27.0800000000 0.0214513969 0.0301839034 0.0419192091 0.0140141808 0.0066080000 16345021 955859216 1373700096 0.1058181152 0.5318323374 0.9024984241 679 27.1200000000 0.0213766489 0.0301709325 0.0419192091 0.0140054191 0.0066150000 16346997 955859216 1373700096 0.1006464064 0.5308068395 0.9035242200 680 27.1600000000 0.0208679996 0.0301572517 0.0419192091 0.0139999075 0.0051120000 16348973 955859216 1373700096 0.0961691514 0.5308141708 0.9047992826 681 27.2000000000 0.0208656993 0.0301436077 0.0419192091 0.0139949883 0.0067520000 16350949 955859216 1373700096 0.0936746448 0.5305726528 0.9055294394 682 27.2400000000 0.0208019912 0.0301299103 0.0419192091 0.0139899657 0.0046790000 16352925 955859216 1373700096 0.0900385678 0.5300341845 0.9063000083 683 27.2800000000 0.0207999535 0.0301162501 0.0419192091 0.0139848389 0.0051080000 16354901 955859216 1373700096 0.0874081403 0.5289047360 0.9072521329 684 27.3200000000 0.0221545063 0.0301046101 0.0419192091 0.0139754880 0.0066410000 16356877 955859216 1373700096 0.0813444555 0.5279823542 0.9084420800 685 27.3600000000 0.0211625397 0.0300915560 0.0419192091 0.0139695663 0.0057680000 16358853 955859216 1373700096 0.0788235664 0.5300753117 0.9092285037 686 27.4000000000 0.0217537805 0.0300794018 0.0419192091 0.0139645693 0.0042420000 16360829 955859216 1373700096 0.0745066479 0.5285438895 0.9104188681 687 27.4400000000 0.0210314337 0.0300662315 0.0419192091 0.0139610113 0.0067840000 16362805 955859216 1373700096 0.0711537898 0.5301071405 0.9117349386 688 27.4800000000 0.0209322982 0.0300529555 0.0419192091 0.0139582911 0.0059130000 16364781 955859216 1373700096 0.0691102222 0.5306786895 0.9127783775 689 27.5200000000 0.0226327032 0.0300421859 0.0419192091 0.0139538827 0.0041640000 16366757 955859216 1373700096 0.0647714213 0.5295621157 0.9136105180 690 27.5600000000 0.0233182628 0.0300324410 0.0419192091 0.0139474912 0.0045070000 16368733 955859216 1373700096 0.0612827763 0.5297782421 0.9146766663 691 27.6000000000 0.0211519711 0.0300195894 0.0419192091 0.0139427605 0.0067520000 16370709 955859216 1373700096 0.0585462265 0.5322998762 0.9155942798 692 27.6400000000 0.0223358218 0.0300084857 0.0419192091 0.0139370091 0.0063340000 16372685 955859216 1373700096 0.0545220189 0.5319152474 0.9168471694 693 27.6800000000 0.0222830102 0.0299973378 0.0419192091 0.0139310645 0.0049710000 16374661 955859216 1373700096 0.0502736159 0.5313727856 0.9178842902 694 27.7200000000 0.0211239550 0.0299845520 0.0419192091 0.0139238909 0.0067230000 16376637 955859216 1373700096 0.0482732318 0.5329738855 0.9190964103 695 27.7600000000 0.0209969711 0.0299716202 0.0419192091 0.0139182150 0.0050890000 16378613 955859216 1373700096 0.0455901064 0.5333654881 0.9201659560 696 27.8000000000 0.0210511647 0.0299588035 0.0419192091 0.0139129061 0.0041890000 16380589 955859216 1373700096 0.0413637273 0.5317118168 0.9214616418 697 27.8400000000 0.0219289828 0.0299472829 0.0419192091 0.0139091434 0.0065940000 16382565 955859216 1373700096 0.0376240611 0.5314043760 0.9224807620 698 27.8800000000 0.0208972543 0.0299343173 0.0419192091 0.0139057039 0.0067500000 16384541 955859216 1373700096 0.0353978015 0.5326836705 0.9235256314 699 27.9200000000 0.0214379933 0.0299221623 0.0419192091 0.0139005148 0.0050030000 16386517 955859216 1373700096 0.0313025489 0.5328026414 0.9245684147 700 27.9600000000 0.0215684790 0.0299102285 0.0419192091 0.0138978943 0.0042420000 16388493 955859216 1373700096 0.0274345465 0.5327600837 0.9256444573 701 28.0000000000 0.0221971311 0.0298992255 0.0419192091 0.0138943725 0.0066390000 16390469 955859216 1373700096 0.0241742004 0.5328545570 0.9265767932 702 28.0400000000 0.0235831272 0.0298902282 0.0419192091 0.0138897927 0.0066580000 16392445 955859216 1373700096 0.0195045099 0.5335457325 0.9271691442 703 28.0800000000 0.0232265200 0.0298807492 0.0419192091 0.0138855671 0.0050200000 16394421 955859216 1373700096 0.0166711155 0.5343453288 0.9283818007 704 28.1200000000 0.0227698367 0.0298706485 0.0419192091 0.0138808803 0.0042530000 16396397 955859216 1373700096 0.0136205759 0.5346868634 0.9294399619 705 28.1600000000 0.0226266421 0.0298603733 0.0419192091 0.0138763634 0.0066390000 16398373 955859216 1373700096 0.0104656238 0.5345768332 0.9309054017 706 28.2000000000 0.0220713932 0.0298493408 0.0419192091 0.0138718779 0.0064930000 16400349 955859216 1373700096 0.0076828361 0.5340099335 0.9320594668 707 28.2400000000 0.0218843017 0.0298380748 0.0419192091 0.0138673086 0.0066740000 16402325 955859216 1373700096 0.0035425797 0.5337917209 0.9332353473 708 28.2800000000 0.0218517650 0.0298267947 0.0419192091 0.0138615514 0.0049190000 16404301 955859216 1373700096 0.0008576961 0.5332786441 0.9344298244 709 28.3200000000 0.0229411609 0.0298170829 0.0419192091 0.0138543054 0.0066890000 16406277 955859216 1373700096 -0.0027129040 0.5334876776 0.9354596734 710 28.3600000000 0.0227487944 0.0298071276 0.0419192091 0.0138481095 0.0067250000 16408253 955859216 1373700096 -0.0068167145 0.5337885022 0.9364334345 711 28.4000000000 0.0228072312 0.0297972825 0.0419192091 0.0138431503 0.0061020000 16410229 955859216 1373700096 -0.0108306799 0.5334233046 0.9377185106 712 28.4400000000 0.0231725667 0.0297879781 0.0419192091 0.0138366392 0.0051050000 16412205 955859216 1373700096 -0.0156828146 0.5330674648 0.9386076331 713 28.4800000000 0.0235378277 0.0297792121 0.0419192091 0.0138301146 0.0042940000 16414181 955859216 1373700096 -0.0201022495 0.5334500670 0.9395951629 714 28.5200000000 0.0229792874 0.0297696884 0.0419192091 0.0138241723 0.0043150000 16416157 955859216 1373700096 -0.0240780562 0.5332636833 0.9410255551 715 28.5600000000 0.0231431033 0.0297604204 0.0419192091 0.0138163833 0.0067520000 16418133 955859216 1373700096 -0.0285472888 0.5334833264 0.9422818422 716 28.6000000000 0.0226241034 0.0297504535 0.0419192091 0.0138110865 0.0067450000 16420109 955859216 1373700096 -0.0330976993 0.5329306722 0.9434602261 717 28.6400000000 0.0232051555 0.0297413248 0.0419192091 0.0138040262 0.0067580000 16422085 955859216 1373700096 -0.0376168527 0.5326564908 0.9442870021 718 28.6800000000 0.0234451201 0.0297325557 0.0419192091 0.0137978495 0.0049770000 16424061 955859216 1373700096 -0.0427023172 0.5330978632 0.9451026917 719 28.7200000000 0.0227721035 0.0297228750 0.0419192091 0.0137949459 0.0043510000 16426037 955859216 1373700096 -0.0471381210 0.5323773026 0.9460154176 720 28.7600000000 0.0235440917 0.0297142933 0.0419192091 0.0137958636 0.0043980000 16428013 955859216 1373700096 -0.0511622839 0.5318586230 0.9468879104 721 28.8000000000 0.0229274500 0.0297048802 0.0419192091 0.0137927839 0.0068980000 16429989 955859216 1373700096 -0.0548443310 0.5313861966 0.9481132627 722 28.8400000000 0.0225923713 0.0296950291 0.0419192091 0.0137882618 0.0069100000 16431965 955859216 1373700096 -0.0598033220 0.5306369662 0.9489923120 723 28.8800000000 0.0231959242 0.0296860400 0.0419192091 0.0137819376 0.0052040000 16433941 955859216 1373700096 -0.0639061481 0.5302716494 0.9498753548 724 28.9200000000 0.0230798963 0.0296769155 0.0419192091 0.0137749502 0.0068840000 16435917 955859216 1373700096 -0.0691064596 0.5298201442 0.9505857825 725 28.9600000000 0.0227481276 0.0296673586 0.0419192091 0.0137679147 0.0059710000 16437893 955859216 1373700096 -0.0732546300 0.5293111205 0.9518325329 726 29.0000000000 0.0231799316 0.0296584227 0.0419192091 0.0137613254 0.0044140000 16439869 955859216 1373700096 -0.0769752264 0.5289230943 0.9525518417 727 29.0400000000 0.0233464334 0.0296497405 0.0419192091 0.0137570817 0.0069590000 16441845 955859216 1373700096 -0.0805891454 0.5287106037 0.9533885121 728 29.0800000000 0.0230740085 0.0296407079 0.0419192091 0.0137539781 0.0057640000 16443821 955859216 1373700096 -0.0835251436 0.5279586315 0.9541358352 729 29.1200000000 0.0231691282 0.0296318305 0.0419192091 0.0137535948 0.0069070000 16445797 955859216 1373700096 -0.0865932107 0.5278027058 0.9547939897 730 29.1600000000 0.0230015907 0.0296227480 0.0419192091 0.0137515541 0.0052310000 16447773 955859216 1373700096 -0.0891870037 0.5268637538 0.9557039738 731 29.2000000000 0.0230011307 0.0296136897 0.0419192091 0.0137491054 0.0044350000 16449749 955859216 1373700096 -0.0932320580 0.5257671475 0.9559746981 732 29.2400000000 0.0232011639 0.0296049294 0.0419192091 0.0137456788 0.0069720000 16451725 955859216 1373700096 -0.0969317481 0.5257359147 0.9563618898 733 29.2800000000 0.0227032304 0.0295955137 0.0419192091 0.0137417343 0.0069800000 16453701 955859216 1373700096 -0.0998502076 0.5246011019 0.9570482373 734 29.3200000000 0.0230158847 0.0295865497 0.0419192091 0.0137348948 0.0045130000 16455677 955859216 1373700096 -0.1023642644 0.5237042904 0.9574395418 735 29.3600000000 0.0230755676 0.0295776912 0.0419192091 0.0137276732 0.0039330000 16457653 955859216 1373700096 -0.1056715250 0.5234360695 0.9575356841 736 29.4000000000 0.0225821659 0.0295681864 0.0419192091 0.0137224605 0.0069910000 16459629 955859216 1373700096 -0.1088073701 0.5224269032 0.9576835036 737 29.4400000000 0.0225445665 0.0295586564 0.0419192091 0.0137171814 0.0064740000 16461605 955859216 1373700096 -0.1116421521 0.5206488371 0.9578885436 738 29.4800000000 0.0222701579 0.0295487804 0.0419192091 0.0137102645 0.0066720000 16463581 955859216 1373700096 -0.1132906601 0.5193659067 0.9584814310 739 29.5200000000 0.0219678711 0.0295385220 0.0419192091 0.0137045917 0.0053260000 16465557 955859216 1373700096 -0.1147774532 0.5176251531 0.9589062333 740 29.5600000000 0.0226031728 0.0295291499 0.0419192091 0.0137012783 0.0070970000 16467533 955859216 1373700096 -0.1162246540 0.5153027177 0.9591000676 741 29.6000000000 0.0224887263 0.0295196487 0.0419192091 0.0136993374 0.0053110000 16469509 955859216 1373700096 -0.1181550398 0.5141118765 0.9595482945 742 29.6400000000 0.0220437758 0.0295095734 0.0419192091 0.0136958302 0.0070620000 16471485 955859216 1373700096 -0.1197992191 0.5132721066 0.9600279927 743 29.6800000000 0.0219389200 0.0294993841 0.0419192091 0.0136932345 0.0047330000 16473461 955859216 1373700096 -0.1210844666 0.5118919015 0.9601439238 744 29.7200000000 0.0219163857 0.0294891919 0.0419192091 0.0136943097 0.0069970000 16475437 955859216 1373700096 -0.1241856813 0.5081447959 0.9609372020 745 29.7600000000 0.0221455488 0.0294793347 0.0419192091 0.0136872221 0.0053320000 16477413 955859216 1373700096 -0.1250892580 0.5055983067 0.9615338445 746 29.8000000000 0.0226200279 0.0294701399 0.0419192091 0.0136794067 0.0070350000 16479389 955859216 1373700096 -0.1264431328 0.5044972301 0.9618319869 747 29.8400000000 0.0222035516 0.0294604122 0.0419192091 0.0136717617 0.0071420000 16481365 955859216 1373700096 -0.1276526898 0.5032567382 0.9623939991 748 29.8800000000 0.0223380234 0.0294508903 0.0419192091 0.0136626386 0.0045210000 16483341 955859216 1373700096 -0.1283973455 0.5016839504 0.9627784491 749 29.9200000000 0.0221432913 0.0294411338 0.0419192091 0.0136536563 0.0043170000 16485317 955859216 1373700096 -0.1295086741 0.5006396770 0.9631607533 750 29.9600000000 0.0220015552 0.0294312144 0.0419192091 0.0136446118 0.0040960000 16487293 955859216 1373700096 -0.1306893080 0.5003131032 0.9635069966 751 30.0000000000 0.0214884095 0.0294206381 0.0419192091 0.0136357075 0.0040010000 16489269 955859216 1373700096 -0.1311249882 0.4974468052 0.9642930627 752 30.0400000000 0.0220209155 0.0294107980 0.0419192091 0.0136269212 0.0040130000 16491245 955859216 1373700096 -0.1315519512 0.4951756299 0.9651269317 753 30.0800000000 0.0218902342 0.0294008105 0.0419192091 0.0136203080 0.0040390000 16493221 955859216 1373700096 -0.1323687285 0.4941814542 0.9659298658 754 30.1200000000 0.0215815734 0.0293904402 0.0419192091 0.0136139598 0.0040460000 16495197 955859216 1373700096 -0.1320664585 0.4926911592 0.9669284821 755 30.1600000000 0.0214330517 0.0293799006 0.0419192091 0.0136076041 0.0040250000 16497173 955859216 1373700096 -0.1322067827 0.4914753139 0.9681270719 756 30.2000000000 0.0206431840 0.0293683441 0.0419192091 0.0135996347 0.0040060000 16499149 955859216 1373700096 -0.1324946582 0.4912740588 0.9689838886 757 30.2400000000 0.0203078389 0.0293563751 0.0419192091 0.0135929026 0.0071780000 16501125 955859216 1373700096 -0.1328182220 0.4898867309 0.9701070786 758 30.2800000000 0.0202614237 0.0293443765 0.0419192091 0.0135878748 0.0070580000 16503101 955859216 1373700096 -0.1335888356 0.4912042022 0.9711860418 759 30.3200000000 0.0200686473 0.0293321555 0.0419192091 0.0135839439 0.0071380000 16505077 955859216 1373700096 -0.1340240538 0.4903666079 0.9723331928 760 30.3600000000 0.0202140883 0.0293201581 0.0419192091 0.0135831963 0.0045830000 16507053 955859216 1373700096 -0.1336195022 0.4880481660 0.9735344648 761 30.4000000000 0.0201434866 0.0293080994 0.0419192091 0.0135779073 0.0040260000 16509029 955859216 1373700096 -0.1331112683 0.4878181517 0.9750763774 762 30.4400000000 0.0199806169 0.0292958586 0.0419192091 0.0135692248 0.0072160000 16511005 955859216 1373700096 -0.1323469430 0.4873585105 0.9764882326 763 30.4800000000 0.0200545285 0.0292837467 0.0419192091 0.0135605091 0.0071690000 16512981 955859216 1373700096 -0.1312652528 0.4848822057 0.9781515598 764 30.5200000000 0.0198519491 0.0292714015 0.0419192091 0.0135553345 0.0048650000 16514957 955859216 1373700096 -0.1222856864 0.4830562472 0.9800636768 765 30.5600000000 0.0197146460 0.0292589090 0.0419192091 0.0135496462 0.0071640000 16516933 955859216 1373700096 -0.1240567490 0.4816409945 0.9816893339 766 30.6000000000 0.0198738202 0.0292466569 0.0419192091 0.0135474780 0.0061000000 16518909 955859216 1373700096 -0.1239275262 0.4800702035 0.9831686616 767 30.6400000000 0.0199777074 0.0292345722 0.0419192091 0.0135524410 0.0045660000 16520885 955859216 1373700096 -0.1221181378 0.4771468341 0.9848955870 768 30.6800000000 0.0196457822 0.0292220868 0.0419192091 0.0135606113 0.0075600000 16522861 955859216 1373700096 -0.1119226143 0.4762232900 0.9872146249 769 30.7200000000 0.0195772648 0.0292095448 0.0419192091 0.0136148438 0.0051250000 16524837 955859216 1373700096 -0.1052274927 0.4740548432 0.9909742475 770 30.7600000000 0.0194530748 0.0291968740 0.0419192091 0.0136498077 0.0040510000 16526813 955859216 1373700096 -0.1065584794 0.4695541859 0.9920524955 771 30.8000000000 0.0194939282 0.0291842892 0.0419192091 0.0136695594 0.0042830000 16528789 955859216 1373700096 -0.0975288600 0.4670817554 0.9939222932 772 30.8400000000 0.0193400662 0.0291715376 0.0419192091 0.0136950792 0.0040450000 16530765 955859216 1373700096 -0.0997240916 0.4660645127 0.9944196343 773 30.8800000000 0.0195261873 0.0291590598 0.0419192091 0.0137216589 0.0040830000 16532741 955859216 1373700096 -0.0989449173 0.4632006884 0.9957466125 774 30.9200000000 0.0193768311 0.0291464212 0.0419192091 0.0137417042 0.0042890000 16534717 955859216 1373700096 -0.0878562331 0.4589730799 0.9978261590 775 30.9600000000 0.0190975480 0.0291334549 0.0419192091 0.0137656276 0.0074010000 16536693 955859216 1373700096 -0.0894092172 0.4572598338 0.9982612729 776 31.0000000000 0.0192432255 0.0291207098 0.0419192091 0.0137865072 0.0075620000 16538669 955859216 1373700096 -0.0806285217 0.4543224871 1.0005620718 777 31.0400000000 0.0188795999 0.0291075295 0.0419192091 0.0138023476 0.0072490000 16540645 955859216 1373700096 -0.0819867402 0.4526578486 1.0014740229 778 31.0800000000 0.0191356111 0.0290947121 0.0419192091 0.0138077928 0.0056270000 16542621 955859216 1373700096 -0.0743306428 0.4487749934 1.0037808418 779 31.1200000000 0.0187068507 0.0290813772 0.0419192091 0.0138103954 0.0044250000 16544597 955859216 1373700096 -0.0758346692 0.4458466172 1.0051145554 780 31.1600000000 0.0191309955 0.0290686203 0.0419192091 0.0138078532 0.0040840000 16546573 955859216 1373700096 -0.0755686015 0.4430507421 1.0065983534 781 31.2000000000 0.0190564916 0.0290558007 0.0419192091 0.0138069987 0.0074900000 16548549 955859216 1373700096 -0.0663252175 0.4388456345 1.0095590353 782 31.2400000000 0.0186112747 0.0290424445 0.0419192091 0.0138067732 0.0071750000 16550525 955859216 1373700096 -0.0681372210 0.4353067279 1.0109752417 783 31.2800000000 0.0189489704 0.0290295538 0.0419192091 0.0138035188 0.0048460000 16552501 955859216 1373700096 -0.0607713871 0.4308340549 1.0139987469 784 31.3200000000 0.0184433144 0.0290160509 0.0419192091 0.0138012552 0.0071920000 16554477 955859216 1373700096 -0.0626449585 0.4263181686 1.0151124001 785 31.3600000000 0.0186913237 0.0290028984 0.0419192091 0.0137964533 0.0064090000 16556453 955859216 1373700096 -0.0625417233 0.4218813479 1.0165172815 786 31.4000000000 0.0188815761 0.0289900214 0.0419192091 0.0137896785 0.0045670000 16558429 955859216 1373700096 -0.0615621023 0.4183047712 1.0178395510 787 31.4400000000 0.0188193247 0.0289770980 0.0419192091 0.0137862975 0.0074600000 16560405 955859216 1373700096 -0.0535809472 0.4116215408 1.0208404064 788 31.4800000000 0.0182997584 0.0289635481 0.0419192091 0.0137855378 0.0062150000 16562381 955859216 1373700096 -0.0551445894 0.4072344601 1.0219897032 789 31.5200000000 0.0185385346 0.0289503351 0.0419192091 0.0137850375 0.0045540000 16564357 955859216 1373700096 -0.0553159267 0.4025860727 1.0232872963 790 31.5600000000 0.0187108964 0.0289373738 0.0419192091 0.0137847741 0.0042340000 16566333 955859216 1373700096 -0.0487237871 0.3955418766 1.0263659954 791 31.6000000000 0.0183530599 0.0289239929 0.0419192091 0.0138171073 0.0072580000 16568309 955859216 1373700096 -0.0523212142 0.3872529566 1.0280052423 792 31.6400000000 0.0182371810 0.0289104994 0.0419192091 0.0138146287 0.0072190000 16570285 955859216 1373700096 -0.0522048175 0.3832523227 1.0298808813 793 31.6800000000 0.0185477454 0.0288974317 0.0419192091 0.0138119922 0.0054960000 16572261 955859216 1373700096 -0.0462260321 0.3761931062 1.0332689285 794 31.7200000000 0.0181189552 0.0288838567 0.0419192091 0.0138079668 0.0037850000 16574237 955859216 1373700096 -0.0481373705 0.3751128316 1.0342700481 795 31.7600000000 0.0184306856 0.0288707081 0.0419192091 0.0138033245 0.0032660000 16576213 955859216 1373700096 -0.0462225117 0.3735013008 1.0364595652 796 31.8000000000 0.0185478348 0.0288577397 0.0419192091 0.0138001790 0.0074700000 16578189 955859216 1373700096 -0.0458289795 0.3681233823 1.0387282372 797 31.8400000000 0.0185289886 0.0288447801 0.0419192091 0.0138008286 0.0075650000 16580165 955859216 1373700096 -0.0457728133 0.3623896241 1.0413594246 798 31.8800000000 0.0185928382 0.0288319331 0.0419192091 0.0138678708 0.0056930000 16582141 955859216 1373700096 -0.0444644988 0.3442653716 1.0478435755 799 31.9200000000 0.0180759151 0.0288184712 0.0419192091 0.0138849735 0.0045330000 16584117 955859216 1373700096 -0.0456110202 0.3363582492 1.0502066612 800 31.9600000000 0.0181706082 0.0288051614 0.0419192091 0.0138913224 0.0072480000 16586093 955859216 1373700096 -0.0465076081 0.3319444358 1.0524172783 801 32.0000000000 0.0177956130 0.0287914167 0.0419192091 0.0138861575 0.0068780000 16588069 955859216 1373700096 -0.0470877476 0.3284008503 1.0553771257 802 32.0400000000 0.0177675020 0.0287776711 0.0419192091 0.0138775905 0.0054790000 16590045 955859216 1373700096 -0.0479625389 0.3204800785 1.0580923557 803 32.0800000000 0.0177222509 0.0287639035 0.0419192091 0.0138691186 0.0045840000 16592021 955859216 1373700096 -0.0487032309 0.3112109601 1.0613088608 804 32.1199999990 0.0181532726 0.0287507062 0.0419192091 0.0138622944 0.0074180000 16593997 955859216 1373700096 -0.0490498543 0.2957943380 1.0687438250 805 32.1600000000 0.0178666227 0.0287371856 0.0419192091 0.0138546258 0.0069750000 16595973 955859216 1373700096 -0.0503656454 0.2919400632 1.0717619658 806 32.2000000000 0.0176432785 0.0287234214 0.0419192091 0.0138460299 0.0049070000 16597949 955859216 1373700096 -0.0523681641 0.2869144082 1.0750193596 807 32.2400000000 0.0178594328 0.0287099592 0.0419192091 0.0138382190 0.0073960000 16599925 955859216 1373700096 -0.0528056920 0.2784044743 1.0789760351 808 32.2800000000 0.0174174253 0.0286959833 0.0419192091 0.0138300519 0.0062850000 16601901 955859216 1373700096 -0.0555156171 0.2727193534 1.0823501348 809 32.3200000000 0.0178475063 0.0286825736 0.0419192091 0.0138225548 0.0042910000 16603877 955859216 1373700096 -0.0552714020 0.2587035298 1.0877428055 810 32.3600000000 0.0177943539 0.0286691313 0.0419192091 0.0138140418 0.0056900000 16605853 955859216 1373700096 -0.0564217530 0.2470153421 1.0920956135 811 32.4000000000 0.0176629759 0.0286555603 0.0419192091 0.0138063485 0.0055360000 16607829 955859216 1373700096 -0.0589973927 0.2436205894 1.0957466364 812 32.4399999990 0.0177001562 0.0286420684 0.0419192091 0.0138002505 0.0074530000 16609805 955859216 1373700096 -0.0605775826 0.2372273058 1.1002516747 813 32.4800000000 0.0176204685 0.0286285117 0.0419192091 0.0137929132 0.0049450000 16611781 955859216 1373700096 -0.0620286837 0.2277944237 1.1051908731 814 32.5200000000 0.0175979007 0.0286149606 0.0419192091 0.0137849319 0.0054640000 16613757 955859216 1373700096 -0.0630717948 0.2167275846 1.1103572845 815 32.5600000000 0.0175697282 0.0286014081 0.0419192091 0.0137775172 0.0073180000 16615733 955859216 1373700096 -0.0641522408 0.2069836110 1.1153864861 816 32.6000000000 0.0176179223 0.0285879480 0.0419192091 0.0137693943 0.0050510000 16617709 955859216 1373700096 -0.0652599707 0.1999424100 1.1206340790 817 32.6400000000 0.0175995547 0.0285744983 0.0419192091 0.0137631227 0.0055650000 16619685 955859216 1373700096 -0.0661671758 0.1871066689 1.1276476383 818 32.6800000000 0.0175515860 0.0285610228 0.0419192091 0.0137547446 0.0056140000 16621661 955859216 1373700096 -0.0669953898 0.1708393544 1.1345583200 819 32.7200000000 0.0172814056 0.0285472504 0.0419192091 0.0137471727 0.0073530000 16623637 955859216 1373700096 -0.0681219697 0.1609440297 1.1397389174 820 32.7599999990 0.0172768179 0.0285335060 0.0419192091 0.0137389506 0.0054350000 16625613 955859216 1373700096 -0.0702180862 0.1547435522 1.1439130306 821 32.7999999990 0.0173939168 0.0285199377 0.0419192091 0.0137307521 0.0046350000 16627589 955859216 1373700096 -0.0714458972 0.1460164040 1.1487317085 822 32.8400000000 0.0173444916 0.0285063422 0.0419192091 0.0137235456 0.0046540000 16629565 955859216 1373700096 -0.0715649053 0.1344096363 1.1542961597 823 32.8800000000 0.0172993354 0.0284927250 0.0419192091 0.0137171635 0.0046530000 16631541 955859216 1373700096 -0.0714634135 0.1225581914 1.1600483656 824 32.9200000000 0.0172380935 0.0284790664 0.0419192091 0.0137097545 0.0046350000 16633517 955859216 1373700096 -0.0711533949 0.1118265912 1.1657932997 825 32.9600000000 0.0172683764 0.0284654777 0.0419192091 0.0137017685 0.0046420000 16635493 955859216 1373700096 -0.0713813081 0.1022328809 1.1706273556 826 33.0000000000 0.0168645736 0.0284514330 0.0419192091 0.0136945343 0.0045230000 16637469 955859216 1373700096 -0.0728693753 0.0937387124 1.1750861406 827 33.0400000000 0.0170765594 0.0284376787 0.0419192091 0.0136878236 0.0046580000 16639445 955859216 1373700096 -0.0720601678 0.0836293548 1.1800402403 828 33.0800000000 0.0171487555 0.0284240447 0.0419192091 0.0136813545 0.0046320000 16641421 955859216 1373700096 -0.0718839541 0.0759584978 1.1838372946 829 33.1199999990 0.0170995817 0.0284103843 0.0419192091 0.0136781989 0.0046340000 16643397 955859216 1373700096 -0.0717128590 0.0651508793 1.1881775856 830 33.1600000000 0.0171617307 0.0283968317 0.0419192091 0.0136742262 0.0046340000 16645373 955859216 1373700096 -0.0711786449 0.0519882068 1.1933805943 831 33.2000000000 0.0172088742 0.0283833685 0.0419192091 0.0136676706 0.0046560000 16647349 955859216 1373700096 -0.0705638751 0.0404611863 1.1978223324 832 33.2400000000 0.0168007910 0.0283694471 0.0419192091 0.0136636184 0.0045820000 16649325 955859216 1373700096 -0.0711512491 0.0323697664 1.2006430626 833 33.2800000000 0.0170563962 0.0283558660 0.0419192091 0.0136588864 0.0046250000 16651301 955859216 1373700096 -0.0706080794 0.0222872477 1.2043648958 834 33.3200000000 0.0170568768 0.0283423181 0.0419192091 0.0136512986 0.0075030000 16653277 955859216 1373700096 -0.0702596754 0.0132938679 1.2073632479 835 33.3600000000 0.0170846488 0.0283288358 0.0419192091 0.0136435341 0.0033470000 16655253 955859216 1373700096 -0.0693692341 0.0060831010 1.2098228931 836 33.4000000000 0.0170690361 0.0283153672 0.0419192091 0.0136396194 0.0075750000 16657229 955859216 1373700096 -0.0678697899 -0.0021978763 1.2129620314 837 33.4399999990 0.0171789378 0.0283020620 0.0419192091 0.0136386760 0.0069180000 16659205 955859216 1373700096 -0.0667193159 -0.0129970126 1.2165100574 838 33.4800000000 0.0171614625 0.0282887677 0.0419192091 0.0136339278 0.0050940000 16661181 955859216 1373700096 -0.0656284466 -0.0229548458 1.2194470167 839 33.5200000000 0.0170195308 0.0282753360 0.0419192091 0.0136260044 0.0040180000 16663157 955859216 1373700096 -0.0652794093 -0.0313679986 1.2213724852 840 33.5600000000 0.0169937182 0.0282619055 0.0419192091 0.0136181368 0.0072920000 16665133 955859216 1373700096 -0.0650354475 -0.0377993397 1.2225573063 841 33.6000000000 0.0174482409 0.0282490474 0.0419192091 0.0136173120 0.0058960000 16667109 955859216 1373700096 -0.0620609336 -0.0503771603 1.2267189026 842 33.6400000000 0.0173925292 0.0282361536 0.0419192091 0.0136097873 0.0066510000 16669085 955859216 1373700096 -0.0606038235 -0.0634077489 1.2308182716 843 33.6800000000 0.0181754902 0.0282242193 0.0419192091 0.0136020677 0.0044980000 16671061 955859216 1373700096 -0.0583558790 -0.0696434379 1.2318705320 844 33.7200000000 0.0179995038 0.0282121047 0.0419192091 0.0135996307 0.0039920000 16673037 955859216 1373700096 -0.0576630607 -0.0765098855 1.2326745987 845 33.7599999990 0.0178691670 0.0281998645 0.0419192091 0.0136019337 0.0076380000 16675013 955859216 1373700096 -0.0578475632 -0.0872676894 1.2342901230 846 33.7999999990 0.0179465637 0.0281877448 0.0419192091 0.0135990709 0.0071000000 16676989 955859216 1373700096 -0.0571970381 -0.0926901475 1.2346932888 847 33.8400000000 0.0178279746 0.0281755136 0.0419192091 0.0135987506 0.0043700000 16678965 955859216 1373700096 -0.0570579581 -0.0977757350 1.2347093821 848 33.8800000000 0.0179401096 0.0281634436 0.0419192091 0.0135961295 0.0041110000 16680941 955859216 1373700096 -0.0555201732 -0.1093170270 1.2379871607 849 33.9200000000 0.0187623184 0.0281523704 0.0419192091 0.0135892723 0.0075360000 16682917 955859216 1373700096 -0.0539943241 -0.1168587357 1.2395353317 850 33.9600000000 0.0195841603 0.0281422902 0.0419192091 0.0135838142 0.0062860000 16684893 955859216 1373700096 -0.0538085327 -0.1210292354 1.2390085459 851 34.0000000000 0.0192907881 0.0281318889 0.0419192091 0.0135771580 0.0045690000 16686869 955859216 1373700096 -0.0550208949 -0.1278423369 1.2394237518 852 34.0400000000 0.0195846595 0.0281218569 0.0419192091 0.0135700228 0.0075020000 16688845 955859216 1373700096 -0.0554644577 -0.1326518804 1.2390892506 853 34.0800000000 0.0194807854 0.0281117267 0.0419192091 0.0135671751 0.0074990000 16690821 955859216 1373700096 -0.0559512042 -0.1369599551 1.2385907173 854 34.1199999990 0.0191367939 0.0281012174 0.0419192091 0.0135660449 0.0046700000 16692797 955859216 1373700096 -0.0566883199 -0.1441930830 1.2388697863 855 34.1600000000 0.0195198823 0.0280911808 0.0419192091 0.0135598791 0.0040370000 16694773 955859216 1373700096 -0.0564571321 -0.1498716176 1.2392822504 856 34.2000000000 0.0188143440 0.0280803433 0.0419192091 0.0135532538 0.0076600000 16696749 955859216 1373700096 -0.0573413335 -0.1512085348 1.2377249002 857 34.2400000000 0.0192316752 0.0280700182 0.0419192091 0.0135509035 0.0069690000 16698725 955859216 1373700096 -0.0567899160 -0.1540888399 1.2365249395 858 34.2800000000 0.0190380570 0.0280594914 0.0419192091 0.0135511466 0.0047780000 16700701 955859216 1373700096 -0.0559473783 -0.1571074277 1.2357832193 859 34.3200000000 0.0193454698 0.0280493470 0.0419192091 0.0135555299 0.0040420000 16702677 955859216 1373700096 -0.0549763814 -0.1592407972 1.2342683077 860 34.3600000000 0.0192141887 0.0280390736 0.0419192091 0.0135542011 0.0075080000 16704653 955859216 1373700096 -0.0537091047 -0.1613363624 1.2331130505 861 34.4000000000 0.0193677004 0.0280290023 0.0419192091 0.0135515483 0.0075490000 16706629 955859216 1373700096 -0.0512827188 -0.1625719815 1.2325760126 862 34.4400000000 0.0192392487 0.0280188054 0.0419192091 0.0135615081 0.0046300000 16708605 955859216 1373700096 -0.0493984856 -0.1654335260 1.2321381569 863 34.4800000000 0.0195186976 0.0280089559 0.0419192091 0.0135716605 0.0074760000 16710581 955859216 1373700096 -0.0479115844 -0.1695298404 1.2318624258 864 34.5200000000 0.0203920603 0.0280001400 0.0419192091 0.0135791768 0.0079570000 16712557 955859216 1373700096 -0.0469452292 -0.1699407846 1.2296936512 865 34.5600000000 0.0196585543 0.0279904966 0.0419192091 0.0135823978 0.0076580000 16714533 955859216 1373700096 -0.0463637933 -0.1705356240 1.2281007767 866 34.6000000000 0.0192749221 0.0279804324 0.0419192091 0.0135816618 0.0076710000 16716509 955859216 1373700096 -0.0454899445 -0.1742961705 1.2275632620 867 34.6400000000 0.0200983658 0.0279713412 0.0419192091 0.0135773492 0.0047430000 16718485 955859216 1373700096 -0.0438754670 -0.1767378151 1.2268084288 868 34.6800000000 0.0202764608 0.0279624762 0.0419192091 0.0135715396 0.0040610000 16720461 955859216 1373700096 -0.0425403863 -0.1777592450 1.2253092527 869 34.7200000000 0.0199138541 0.0279532142 0.0419192091 0.0135653661 0.0076620000 16722437 955859216 1373700096 -0.0421028174 -0.1799910814 1.2245023251 870 34.7600000000 0.0197990481 0.0279438416 0.0419192091 0.0135587156 0.0058850000 16724413 955859216 1373700096 -0.0415440388 -0.1826394498 1.2237488031 871 34.8000000000 0.0197221730 0.0279344023 0.0419192091 0.0135537444 0.0076260000 16726389 955859216 1373700096 -0.0414390154 -0.1861157268 1.2228832245 872 34.8400000000 0.0198387783 0.0279251183 0.0419192091 0.0135483464 0.0047910000 16728365 955859216 1373700096 -0.0417834260 -0.1903492957 1.2227759361 873 34.8800000000 0.0203203391 0.0279164072 0.0419192091 0.0135412075 0.0076350000 16730341 955859216 1373700096 -0.0413761549 -0.1934992373 1.2222976685 874 34.9200000000 0.0204817243 0.0279079007 0.0419192091 0.0135343860 0.0065360000 16732317 955859216 1373700096 -0.0409277231 -0.1954464912 1.2212244272 875 34.9600000000 0.0201456882 0.0278990296 0.0419192091 0.0135277491 0.0041720000 16734293 955859216 1373700096 -0.0413031615 -0.1982708722 1.2206108570 876 35.0000000000 0.0202848632 0.0278903376 0.0419192091 0.0135202562 0.0037160000 16736269 955859216 1373700096 -0.0408603884 -0.2011877745 1.2204518318 877 35.0400000000 0.0203901809 0.0278817856 0.0419192091 0.0135126471 0.0077330000 16738245 955859216 1373700096 -0.0407287143 -0.2034654617 1.2193433046 878 35.0800000000 0.0201192722 0.0278729444 0.0419192091 0.0135052294 0.0072220000 16740221 955859216 1373700096 -0.0408399515 -0.2067907900 1.2184964418 879 35.1200000000 0.0203607678 0.0278643982 0.0419192091 0.0134976673 0.0051480000 16742197 955859216 1373700096 -0.0406941473 -0.2102143168 1.2179530859 880 35.1600000000 0.0211229082 0.0278567374 0.0419192091 0.0134904679 0.0041140000 16744173 955859216 1373700096 -0.0401691087 -0.2155745625 1.2157472372 881 35.2000000000 0.0208845437 0.0278488234 0.0419192091 0.0134835493 0.0076960000 16746149 955859216 1373700096 -0.0404920056 -0.2166511118 1.2140353918 882 35.2400000000 0.0201370679 0.0278400799 0.0419192091 0.0134785902 0.0063420000 16748125 955859216 1373700096 -0.0411332957 -0.2185954452 1.2127447128 883 35.2800000000 0.0201718342 0.0278313956 0.0419192091 0.0134746081 0.0047320000 16750101 955859216 1373700096 -0.0416376553 -0.2213276476 1.2113466263 884 35.3200000000 0.0203546621 0.0278229378 0.0419192091 0.0134741844 0.0041260000 16752077 955859216 1373700096 -0.0424237922 -0.2236608416 1.2093950510 885 35.3600000000 0.0202580635 0.0278143899 0.0419192091 0.0134774077 0.0077440000 16754053 955859216 1373700096 -0.0438525081 -0.2257392853 1.2077015638 886 35.4000000000 0.0204173569 0.0278060411 0.0419192091 0.0134810608 0.0070320000 16756029 955859216 1373700096 -0.0456808582 -0.2277188450 1.2059277296 887 35.4400000000 0.0206512660 0.0277979749 0.0419192091 0.0134862553 0.0042550000 16758005 955859216 1373700096 -0.0474164635 -0.2288975418 1.2040292025 888 35.4800000000 0.0201914422 0.0277894089 0.0419192091 0.0134897126 0.0037790000 16759981 955859216 1373700096 -0.0493967421 -0.2305695862 1.2021410465 889 35.5200000000 0.0204939116 0.0277812025 0.0419192091 0.0134992662 0.0077950000 16761957 955859216 1373700096 -0.0505253039 -0.2323275059 1.2004613876 890 35.5600000000 0.0207228623 0.0277732718 0.0419192091 0.0135064432 0.0075470000 16763933 955859216 1373700096 -0.0520231724 -0.2328861952 1.1986492872 891 35.6000000000 0.0199629776 0.0277645060 0.0419192091 0.0135127223 0.0047460000 16765909 955859216 1373700096 -0.0540087409 -0.2351321429 1.1972833872 892 35.6400000000 0.0207260959 0.0277566155 0.0419192091 0.0135232745 0.0072020000 16767885 955859216 1373700096 -0.0554459691 -0.2370881736 1.1953700781 893 35.6800000000 0.0208289381 0.0277488577 0.0419192091 0.0135351821 0.0051560000 16769861 955859216 1373700096 -0.0574330017 -0.2377143204 1.1934731007 894 35.7200000000 0.0203108974 0.0277405378 0.0419192091 0.0135490756 0.0078110000 16771837 955859216 1373700096 -0.0595658123 -0.2393863499 1.1921443939 895 35.7600000000 0.0206111111 0.0277325720 0.0419192091 0.0135661632 0.0048850000 16773813 955859216 1373700096 -0.0615663864 -0.2419212461 1.1909071207 896 35.8000000000 0.0215692706 0.0277256933 0.0419192091 0.0135906004 0.0041180000 16775789 955859216 1373700096 -0.0633036867 -0.2429774404 1.1891466379 897 35.8400000000 0.0217800196 0.0277190649 0.0419192091 0.0136091909 0.0037500000 16777765 955859216 1373700096 -0.0649143681 -0.2427324653 1.1880344152 898 35.8800000000 0.0212921631 0.0277119080 0.0419192091 0.0136198711 0.0037710000 16779741 955859216 1373700096 -0.0664337277 -0.2428830415 1.1866842508 899 35.9200000000 0.0214965753 0.0277049944 0.0419192091 0.0136305208 0.0037880000 16781717 955859216 1373700096 -0.0674300268 -0.2432269007 1.1864219904 900 35.9600000000 0.0216432866 0.0276982592 0.0419192091 0.0136351334 0.0037480000 16783693 955859216 1373700096 -0.0684967116 -0.2438192666 1.1855416298 901 36.0000000000 0.0199084710 0.0276896134 0.0419192091 0.0136451025 0.0041090000 16785669 955859216 1373700096 -0.0597569756 -0.2431548536 1.1876406670 902 36.0400000000 0.0201275833 0.0276812298 0.0419192091 0.0136634320 0.0038050000 16787645 955859216 1373700096 -0.0643977150 -0.2442336977 1.1857525110 903 36.0800000000 0.0202765781 0.0276730298 0.0419192091 0.0136789332 0.0037730000 16789621 955859216 1373700096 -0.0682134852 -0.2446516603 1.1834806204 904 36.1200000000 0.0201896038 0.0276647516 0.0419192091 0.0137014452 0.0037740000 16791597 955859216 1373700096 -0.0708563924 -0.2453655899 1.1823170185 905 36.1600000000 0.0204675719 0.0276567990 0.0419192091 0.0137250623 0.0078740000 16793573 955859216 1373700096 -0.0725028962 -0.2460181117 1.1809880733 906 36.2000000000 0.0204890780 0.0276488876 0.0419192091 0.0137510629 0.0078700000 16795549 955859216 1373700096 -0.0742187873 -0.2458627522 1.1799069643 907 36.2400000000 0.0200035647 0.0276404583 0.0419192091 0.0137740236 0.0067280000 16797525 955859216 1373700096 -0.0755513683 -0.2466741353 1.1793340445 908 36.2800000000 0.0204140991 0.0276324998 0.0419192091 0.0137893274 0.0041900000 16799501 955859216 1373700096 -0.0766101256 -0.2470103949 1.1787202358 909 36.3200000000 0.0201985538 0.0276243216 0.0419192091 0.0137989205 0.0037430000 16801477 955859216 1373700096 -0.0780187920 -0.2470756322 1.1780298948 910 36.3600000000 0.0199536644 0.0276158923 0.0419192091 0.0138063014 0.0079390000 16803453 955859216 1373700096 -0.0794194043 -0.2474150062 1.1775006056 911 36.4000000000 0.0197394174 0.0276072464 0.0419192091 0.0138138507 0.0067560000 16805429 955859216 1373700096 -0.0806104168 -0.2482781112 1.1771513224 912 36.4400000000 0.0198630262 0.0275987549 0.0419192091 0.0138193300 0.0047240000 16807405 955859216 1373700096 -0.0819865391 -0.2498654127 1.1770315170 913 36.4800000000 0.0198729523 0.0275902929 0.0419192091 0.0138701652 0.0061530000 16809381 955859216 1373700096 -0.0784700885 -0.2497567534 1.1787685156 914 36.5200000000 0.0193708595 0.0275813001 0.0419192091 0.0138998617 0.0057980000 16811357 955859216 1373700096 -0.0821753666 -0.2502127290 1.1773972511 915 36.5600000000 0.0194099136 0.0275723696 0.0419192091 0.0139209196 0.0058060000 16813333 955859216 1373700096 -0.0849683210 -0.2505976558 1.1767400503 916 36.6000000000 0.0194424000 0.0275634941 0.0419192091 0.0139404527 0.0057940000 16815309 955859216 1373700096 -0.0875256285 -0.2507590353 1.1759206057 917 36.6400000000 0.0194183439 0.0275546117 0.0419192091 0.0139543230 0.0057870000 16817285 955859216 1373700096 -0.0899585932 -0.2511006594 1.1752856970 918 36.6800000000 0.0193822645 0.0275457094 0.0419192091 0.0139690124 0.0078900000 16819261 955859216 1373700096 -0.0920606405 -0.2515579760 1.1748168468 919 36.7200000000 0.0193807650 0.0275368248 0.0419192091 0.0139869637 0.0057580000 16821237 955859216 1373700096 -0.0938033462 -0.2520876229 1.1746121645 920 36.7600000000 0.0194910709 0.0275280794 0.0419192091 0.0140045387 0.0047520000 16823213 955859216 1373700096 -0.0953502133 -0.2520130873 1.1741430759 921 36.8000000000 0.0190598760 0.0275188848 0.0419192091 0.0140163350 0.0047670000 16825189 955859216 1373700096 -0.0973834768 -0.2521202564 1.1740791798 922 36.8400000000 0.0191513281 0.0275098094 0.0419192091 0.0140250955 0.0047510000 16827165 955859216 1373700096 -0.0994699448 -0.2529597878 1.1742416620 923 36.8800000000 0.0195476394 0.0275011830 0.0419192091 0.0140310960 0.0084080000 16829141 955859216 1373700096 -0.1014553830 -0.2538535297 1.1746921539 924 36.9200000000 0.0198775418 0.0274929323 0.0419192091 0.0140339197 0.0075530000 16831117 955859216 1373700096 -0.1033046246 -0.2548087537 1.1746842861 925 36.9600000000 0.0200915951 0.0274849308 0.0419192091 0.0140372831 0.0052010000 16833093 955859216 1373700096 -0.1049563512 -0.2551674843 1.1747471094 926 37.0000000000 0.0198096372 0.0274766422 0.0419192091 0.0140418067 0.0040940000 16835069 955859216 1373700096 -0.1063240319 -0.2550265193 1.1747721434 927 37.0400000000 0.0194067713 0.0274679368 0.0419192091 0.0140489879 0.0077790000 16837045 955859216 1373700096 -0.1075648367 -0.2553004324 1.1751995087 928 37.0800000000 0.0197077002 0.0274595745 0.0419192091 0.0140595594 0.0061110000 16839021 955859216 1373700096 -0.1089045629 -0.2552848458 1.1753553152 929 37.1200000000 0.0194755085 0.0274509802 0.0419192091 0.0140722298 0.0052410000 16840997 955859216 1373700096 -0.1106525958 -0.2542459369 1.1746793985 930 37.1600000000 0.0189508330 0.0274418403 0.0419192091 0.0140827290 0.0078280000 16842973 955859216 1373700096 -0.1126288548 -0.2531783581 1.1739753485 931 37.2000000000 0.0202387590 0.0274341033 0.0419192091 0.0140914480 0.0050990000 16844949 955859216 1373700096 -0.1076898426 -0.2540442944 1.1782248020 932 37.2400000000 0.0194105320 0.0274254944 0.0419192091 0.0141215960 0.0077390000 16846925 955859216 1373700096 -0.1121271253 -0.2542110682 1.1756204367 933 37.2800000000 0.0191979893 0.0274166760 0.0419192091 0.0141573370 0.0067740000 16848901 955859216 1373700096 -0.1154780164 -0.2536535859 1.1730974913 934 37.3200000000 0.0190357249 0.0274077029 0.0419192091 0.0141892420 0.0046310000 16850877 955859216 1373700096 -0.1185505614 -0.2522212267 1.1715078354 935 37.3600000000 0.0204815306 0.0274002952 0.0419192091 0.0141995176 0.0077910000 16852853 955859216 1373700096 -0.1150517091 -0.2520909011 1.1739497185 936 37.4000000000 0.0189663731 0.0273912846 0.0419192091 0.0142255949 0.0053370000 16854829 955859216 1373700096 -0.1199165955 -0.2512307167 1.1708000898 937 37.4400000000 0.0205837972 0.0273840194 0.0419192091 0.0142305478 0.0080230000 16856805 955859216 1373700096 -0.1180308238 -0.2503780723 1.1727547646 938 37.4800000000 0.0185111929 0.0273745601 0.0419192091 0.0142439513 0.0047330000 16858781 955859216 1373700096 -0.1229761913 -0.2490834296 1.1695740223 939 37.5200000000 0.0206527468 0.0273674016 0.0419192091 0.0142480542 0.0078150000 16860757 955859216 1373700096 -0.1206047982 -0.2502028346 1.1719774008 940 37.5600000000 0.0190633815 0.0273585675 0.0419192091 0.0142581768 0.0052920000 16862733 955859216 1373700096 -0.1250344217 -0.2494308501 1.1689002514 941 37.6000000000 0.0207330864 0.0273515266 0.0419192091 0.0142614715 0.0060020000 16864709 955859216 1373700096 -0.1232732758 -0.2494973242 1.1703350544 942 37.6400000000 0.0186732952 0.0273423141 0.0419192091 0.0142699131 0.0074280000 16866685 955859216 1373700096 -0.1279479861 -0.2482475787 1.1662449837 943 37.6800000000 0.0208101124 0.0273353870 0.0419192091 0.0142750671 0.0045830000 16868661 955859216 1373700096 -0.1256261915 -0.2496976703 1.1684659719 944 37.7200000000 0.0187212061 0.0273262618 0.0419192091 0.0142850169 0.0077680000 16870637 955859216 1373700096 -0.1297421306 -0.2489057183 1.1657925844 945 37.7600000000 0.0182309467 0.0273166372 0.0419192091 0.0142906007 0.0056320000 16872613 955859216 1373700096 -0.1323261708 -0.2484511584 1.1658945084 946 37.8000000000 0.0208713207 0.0273098239 0.0419192091 0.0142940407 0.0047650000 16874589 955859216 1373700096 -0.1294052154 -0.2501433492 1.1693646908 947 37.8400000000 0.0195105337 0.0273015882 0.0419192091 0.0143016649 0.0045230000 16876565 955859216 1373700096 -0.1330569386 -0.2493787557 1.1668694019 948 37.8800000000 0.0185758248 0.0272923838 0.0419192091 0.0143033293 0.0077270000 16878541 955859216 1373700096 -0.1357298344 -0.2488185465 1.1672458649 949 37.9200000000 0.0207953975 0.0272855376 0.0419192091 0.0143063264 0.0074040000 16880517 955859216 1373700096 -0.1334923953 -0.2438919842 1.1795363426 950 37.9600000000 0.0194894578 0.0272773312 0.0419192091 0.0143112853 0.0049680000 16882493 955859216 1373700096 -0.1375341564 -0.2399708629 1.1853957176 951 38.0000000000 0.0206134301 0.0272703240 0.0419192091 0.0143162819 0.0057870000 16884469 955859216 1373700096 -0.1365695149 -0.2375295013 1.1923532486 952 38.0400000000 0.0193277765 0.0272619810 0.0419192091 0.0143224939 0.0055740000 16886445 955859216 1373700096 -0.1398809701 -0.2364713252 1.1902984381 953 38.0800000000 0.0187132470 0.0272530106 0.0419192091 0.0143203417 0.0080220000 16888421 955859216 1373700096 -0.1421430856 -0.2359139770 1.1896587610 954 38.1200000000 0.0206326824 0.0272460711 0.0419192091 0.0143226480 0.0050290000 16890397 955859216 1373700096 -0.1397715360 -0.2360256910 1.1942704916 955 38.1600000000 0.0197359025 0.0272382070 0.0419192091 0.0143296078 0.0077490000 16892373 955859216 1373700096 -0.1425345093 -0.2362791002 1.1911711693 956 38.2000000000 0.0194512084 0.0272300616 0.0419192091 0.0143324405 0.0045950000 16894349 955859216 1373700096 -0.1444253474 -0.2355757058 1.1907043457 957 38.2400000000 0.0208906364 0.0272234374 0.0419192091 0.0143330963 0.0078880000 16896325 955859216 1373700096 -0.1431041211 -0.2350328863 1.1922729015 958 38.2800000000 0.0207999609 0.0272167323 0.0419192091 0.0143338261 0.0062100000 16898301 955859216 1373700096 -0.1458446234 -0.2358057499 1.1896302700 959 38.3200000000 0.0212398954 0.0272104999 0.0419192091 0.0143338728 0.0045340000 16900277 955859216 1373700096 -0.1476809978 -0.2360330671 1.1896250248 960 38.3600000000 0.0226775091 0.0272057780 0.0419192091 0.0143325419 0.0079980000 16902253 955859216 1373700096 -0.1465199292 -0.2350126058 1.1926752329 961 38.4000000000 0.0243566018 0.0272028132 0.0419192091 0.0143319916 0.0048860000 16904229 955859216 1373700096 -0.1492748410 -0.2353063822 1.1934756041 962 38.4400000000 0.0302588120 0.0272059899 0.0419192091 0.0143371443 0.0080200000 16906205 955859216 1373700096 -0.1488973051 -0.2353548855 1.2001056671 963 38.4800000000 0.0359764099 0.0272150973 0.0419192091 0.0143374269 0.0046600000 16908181 955859216 1373700096 -0.1517849565 -0.2360794544 1.2040441036 964 38.5200000000 0.0448296815 0.0272333697 0.0448296815 0.0143470529 0.0082160000 16910157 955859216 1373700096 -0.1515291929 -0.2353408933 1.2146230936 965 38.5600000000 0.0512825660 0.0272582912 0.0512825660 0.0143505588 0.0047890000 16912133 955859216 1373700096 -0.1546634436 -0.2344654799 1.2200329304 966 38.6000000000 0.0645454153 0.0272968907 0.0645454153 0.0143729655 0.0041730000 16914109 955859216 1373700096 -0.1539995521 -0.2345063835 1.2331066132 967 38.6400000000 0.0729956329 0.0273441489 0.0729956329 0.0143802992 0.0081380000 16916085 955859216 1373700096 -0.1554663926 -0.2329330891 1.2441260815 968 38.6800000000 0.0859106705 0.0274046516 0.0859106705 0.0143931642 0.0059710000 16918061 955859216 1373700096 -0.1568165272 -0.2340334207 1.2549278736 969 38.7200000000 0.0923626274 0.0274716876 0.0923626274 0.0144058673 0.0078720000 16920037 955859216 1373700096 -0.1599888802 -0.2323793769 1.2620197535 970 38.7600000000 0.1106516868 0.0275574402 0.1106516868 0.0144325981 0.0048090000 16922013 955859216 1373700096 -0.1595710218 -0.2329509258 1.2789459229 971 38.8000000000 0.1250201315 0.0276578137 0.1250201315 0.0144449274 0.0037760000 16923989 955859216 1373700096 -0.1610715389 -0.2334484309 1.2912815809 972 38.8400000000 0.1386450827 0.0277719982 0.1386450827 0.0144559173 0.0082010000 16925965 955859216 1373700096 -0.1626017094 -0.2324658036 1.3045384884 973 38.8800000000 0.1548381895 0.0279025904 0.1548381895 0.0144704229 0.0064680000 16927941 955859216 1373700096 -0.1637987942 -0.2322465330 1.3196268082 974 38.9200000000 0.1698188782 0.0280482950 0.1698188782 0.0144810748 0.0070250000 16929917 955859216 1373700096 -0.1651188135 -0.2311265022 1.3348547220 975 38.9600000000 0.1875550598 0.0282118917 0.1875550598 0.0144975318 0.0042290000 16931893 955859216 1373700096 -0.1665002704 -0.2298718393 1.3521136045 976 39.0000000000 0.2051721960 0.0283932034 0.2051721960 0.0145124919 0.0037510000 16933869 955859216 1373700096 -0.1678952575 -0.2302585691 1.3681447506 977 39.0400000000 0.2189836055 0.0285882806 0.2189836055 0.0145190334 0.0082560000 16935845 955859216 1373700096 -0.1690674722 -0.2290833145 1.3814729452 978 39.0800000000 0.2390889972 0.0288035165 0.2390889972 0.0145399685 0.0070650000 16937821 955859216 1373700096 -0.1702804863 -0.2285557389 1.3996725082 979 39.1200000000 0.2577875555 0.0290374124 0.2577875555 0.0145575828 0.0042170000 16939797 955859216 1373700096 -0.1713460386 -0.2292343974 1.4155972004 980 39.1600000000 0.2780814767 0.0292915390 0.2780814767 0.0145721732 0.0038370000 16941773 955859216 1373700096 -0.1728252918 -0.2281879485 1.4341901541 981 39.2000000000 0.3012970686 0.0295688127 0.3012970686 0.0146052721 0.0083770000 16943749 955859216 1373700096 -0.1738937497 -0.2278784662 1.4568264484 982 39.2400000000 0.3234134614 0.0298680435 0.3234134614 0.0146213575 0.0071900000 16945725 955859216 1373700096 -0.1751990765 -0.2271146923 1.4772216082 983 39.2800000000 0.3488087058 0.0301924999 0.3488087058 0.0146503141 0.0050560000 16947701 955859216 1373700096 -0.1763296574 -0.2260206640 1.5011197329 984 39.3200000000 0.3741250038 0.0305420248 0.3741250038 0.0146781770 0.0041390000 16949677 955859216 1373700096 -0.1774302274 -0.2251797915 1.5255275965 985 39.3600000000 0.4118575156 0.0309291472 0.4118575156 0.0147440940 0.0082820000 16951653 955859216 1373700096 -0.1786048561 -0.2244129926 1.5606383085 986 39.4000000000 0.4530043304 0.0313572153 0.4530043304 0.0148254804 0.0072410000 16953629 955859216 1373700096 -0.1796078086 -0.2234119326 1.6001939774 987 39.4400000000 0.4931578338 0.0318250984 0.4931578338 0.0148829703 0.0043350000 16955605 955859216 1373700096 -0.1810859591 -0.2226448953 1.6386761665 988 39.4800000000 0.5601698756 0.0323598603 0.5601698756 0.0151005146 0.0039740000 16957581 955859216 1373700096 -0.1818056256 -0.2226746231 1.7042185068 989 39.5200000000 0.6218746305 0.0329559319 0.6218746305 0.0152156600 0.0083500000 16959557 955859216 1373700096 -0.1840940416 -0.2207307965 1.7633287907 990 39.5600000000 0.7023246288 0.0336320619 0.7023246288 0.0154242290 0.0076500000 16961533 955859216 1373700096 -0.1864132732 -0.2181213945 1.8425458670 991 39.6000000000 0.7740619183 0.0343792161 0.7740619183 0.0156008547 0.0046090000 16963509 955859216 1373700096 -0.1886890084 -0.2161695361 1.9115891457 992 39.6400000000 0.8282829523 0.0351795223 0.8282829523 0.0157014708 0.0060570000 16965485 955859216 1373700096 -0.1904236376 -0.2143927366 1.9637684822 993 39.6800000000 0.8687388897 0.0360189577 0.8687388897 0.0157576475 0.0060020000 16967461 955859216 1373700096 -0.1916414499 -0.2136765420 2.0023365021 994 39.7200000000 0.9032973647 0.0368914712 0.9032973647 0.0158430260 0.0082490000 16969437 955859216 1373700096 -0.1914688796 -0.2155014575 2.0333673954 995 39.7600000000 0.9254978895 0.0377845430 0.9254978895 0.0158461389 0.0051010000 16971413 955859216 1373700096 -0.1925507337 -0.2138665020 2.0524325371 996 39.8000000000 0.9505952001 0.0387010195 0.9505952001 0.0158646759 0.0042940000 16973389 955859216 1373700096 -0.1945447773 -0.2103736699 2.0750653744 997 39.8400000000 0.9714197516 0.0396365448 0.9714197516 0.0158792724 0.0083790000 16975365 955859216 1373700096 -0.1958496571 -0.2078979313 2.0943024158 998 39.8800000000 0.9956592917 0.0405944835 0.9956592917 0.0158997594 0.0059570000 16977341 955859216 1373700096 -0.1968891472 -0.2056599855 2.1164484024 999 39.9200000000 1.0208520889 0.0415757223 1.0208520889 0.0160276441 0.0049060000 16979317 955859216 1373700096 -0.1963247359 -0.2070013136 2.1370148659 1000 39.9600000000 1.0279316902 0.0425620783 1.0279316902 0.0160215717 0.0079020000 16981293 955859216 1373700096 -0.1985096484 -0.2024951279 2.1422011852 1001 40.0000000000 1.0337917805 0.0435523177 1.0337917805 0.0160144178 0.0047350000 16983269 955859216 1373700096 -0.2001949549 -0.1989765167 2.1456205845 1002 40.0400000000 1.0443663597 0.0445511342 1.0443663597 0.0161016583 0.0042140000 16985245 955859216 1373700096 -0.1978733540 -0.2035456598 2.1541028023 1003 40.0800000000 1.0482802391 0.0455518611 1.0482802391 0.0160939493 0.0079310000 16987221 955859216 1373700096 -0.1996452510 -0.1989841759 2.1562943459 1004 40.1200000000 1.0560507774 0.0465583341 1.0560507774 0.0160875773 0.0048390000 16989197 955859216 1373700096 -0.2009182423 -0.1959490478 2.1606032848 1005 40.1600000000 1.0696835518 0.0475763691 1.0696835518 0.0161854918 0.0083320000 16991173 955859216 1373700096 -0.1988399923 -0.2008139342 2.1735215187 1006 40.2000000000 1.0734812021 0.0485961553 1.0734812021 0.0161776325 0.0046070000 16993149 955859216 1373700096 -0.2006699443 -0.1961410344 2.1746344566 1007 40.2400000000 1.0789568424 0.0496193536 1.0789568424 0.0161704615 0.0038780000 16995125 955859216 1373700096 -0.2017297447 -0.1927323788 2.1765887737 1008 40.2800000000 1.0822112560 0.0506437503 1.0822112560 0.0161632056 0.0080220000 16997101 955859216 1373700096 -0.2025801241 -0.1894478500 2.1775174141 1009 40.3200000000 1.0874390602 0.0516712977 1.0874390602 0.0162675154 0.0074950000 16999077 955859216 1373700096 -0.1995649487 -0.1977277249 2.1799237728 1010 40.3600000000 1.0889118910 0.0526982686 1.0889118910 0.0162634383 0.0042940000 17001053 955859216 1373700096 -0.2012784779 -0.1916536689 2.1777832508 1011 40.4000000000 1.0930866003 0.0537273371 1.0930866003 0.0162562754 0.0034460000 17003029 955859216 1373700096 -0.2022663057 -0.1872100085 2.1780755520 1012 40.4400000000 1.0994794369 0.0547606890 1.0994794369 0.0162509033 0.0082510000 17005005 955859216 1373700096 -0.2030563802 -0.1828308403 2.1814930439 1013 40.4800000000 1.1131069660 0.0558054534 1.1131069660 0.0164185935 0.0078740000 17006981 955859216 1373700096 -0.2006250918 -0.1919177622 2.1927161217 1014 40.5200000000 1.1154321432 0.0568504501 1.1154321432 0.0164108919 0.0044970000 17008957 955859216 1373700096 -0.2022475153 -0.1854080260 2.1927304268 1015 40.5600000000 1.1183096170 0.0578962227 1.1183096170 0.0164033931 0.0034110000 17010933 955859216 1373700096 -0.2032867968 -0.1794677973 2.1933071613 1016 40.6000000000 1.1211020947 0.0589426851 1.1211020947 0.0163965050 0.0079080000 17012909 955859216 1373700096 -0.2042423189 -0.1744077057 2.1943271160 1017 40.6400000000 1.1238913536 0.0599898323 1.1238913536 0.0163899126 0.0069330000 17014885 955859216 1373700096 -0.2048660964 -0.1700480580 2.1943681240 1018 40.6800000000 1.1262270212 0.0610372166 1.1262270212 0.0163844041 0.0040810000 17016861 955859216 1373700096 -0.2056166977 -0.1653378457 2.1945524216 1019 40.7200000000 1.1274193525 0.0620837152 1.1274193525 0.0165569486 0.0037560000 17018837 955859216 1373700096 -0.2039088905 -0.1766581237 2.1939795017 1020 40.7600000000 1.1262724400 0.0631270375 1.1274193525 0.0165488774 0.0078550000 17020813 955859216 1373700096 -0.2052804828 -0.1707154959 2.1913175583 1021 40.8000000000 1.1265218258 0.0641685603 1.1274193525 0.0165415859 0.0076410000 17022789 955859216 1373700096 -0.2062264532 -0.1660421640 2.1893980503 1022 40.8400000000 1.1264719963 0.0652079962 1.1274193525 0.0165346026 0.0044760000 17024765 955859216 1373700096 -0.2070581913 -0.1618680507 2.1881639957 1023 40.8800000000 1.1264972687 0.0662454246 1.1274193525 0.0165277875 0.0073640000 17026741 955859216 1373700096 -0.2079021037 -0.1572637260 2.1870267391 1024 40.9200000000 1.1278176308 0.0672821162 1.1278176308 0.0165248204 0.0051010000 17028717 955859216 1373700096 -0.2087265402 -0.1531959921 2.1866824627 1025 40.9600000000 1.1287050247 0.0683176507 1.1287050247 0.0165239296 0.0040090000 17128997 955859216 1373700096 -0.2093852013 -0.1486352384 2.1862304211 1026 41.0000000000 1.1311147213 0.0693535153 1.1311147213 0.0165194132 0.0082070000 17335773 955859216 1373700096 -0.2103822827 -0.1417636573 2.1859440804 1027 41.0400000000 1.1324518919 0.0703886647 1.1324518919 0.0165166701 0.0049890000 17337749 955859216 1373700096 -0.2113054544 -0.1369889826 2.1851196289 1028 41.0800000000 1.1328740120 0.0714222107 1.1328740120 0.0165144208 0.0069920000 17339725 955859216 1373700096 -0.2120337039 -0.1318371743 2.1841487885 1029 41.1200000000 1.1342142820 0.0724550505 1.1342142820 0.0165106274 0.0041270000 17341701 955859216 1373700096 -0.2126970887 -0.1277239025 2.1834061146 1030 41.1600000000 1.1346629858 0.0734863203 1.1346629858 0.0165083807 0.0080890000 17343677 955859216 1373700096 -0.2132589966 -0.1257006228 2.1819188595 1031 41.2000000000 1.1359180212 0.0745168069 1.1359180212 0.0165061035 0.0067780000 17345653 955859216 1373700096 -0.2139248997 -0.1210625097 2.1809146404 1032 41.2400000000 1.1367032528 0.0755460573 1.1367032528 0.0165010292 0.0042110000 17347629 955859216 1373700096 -0.2142934203 -0.1177368984 2.1798672676 1033 41.2800000000 1.1368309259 0.0765734386 1.1368309259 0.0164956309 0.0056880000 17349605 955859216 1373700096 -0.2146434486 -0.1160298437 2.1786634922 1034 41.3200000000 1.1394244432 0.0776013410 1.1394244432 0.0164995284 0.0058680000 17351581 955859216 1373700096 -0.2155079246 -0.1087537482 2.1779289246 1035 41.3600000000 1.1381068230 0.0786259839 1.1394244432 0.0164952369 0.0045650000 17353557 955859216 1373700096 -0.2156936377 -0.1084328890 2.1756300926 1036 41.4000000000 1.1379815340 0.0796485279 1.1394244432 0.0164935855 0.0079960000 17355533 955859216 1373700096 -0.2164035589 -0.1050759330 2.1736884117 1037 41.4400000000 1.1376944780 0.0806688229 1.1394244432 0.0164924543 0.0071350000 17357509 955859216 1373700096 -0.2168707401 -0.1013585329 2.1722309589 1038 41.4800000000 1.1375979185 0.0816870591 1.1394244432 0.0164889980 0.0041850000 17359485 955859216 1373700096 -0.2174135149 -0.0985434204 2.1702589989 1039 41.5200000000 1.1377897263 0.0827035198 1.1394244432 0.0164880901 0.0058310000 17361461 955859216 1373700096 -0.2180060595 -0.0944939554 2.1689038277 1040 41.5600000000 1.1369590759 0.0837172270 1.1394244432 0.0164868746 0.0058810000 17363437 955859216 1373700096 -0.2183329612 -0.0912574083 2.1667275429 1041 41.6000000000 1.1367474794 0.0847287835 1.1394244432 0.0164840165 0.0047110000 17365413 955859216 1373700096 -0.2187677771 -0.0873431563 2.1654598713 1042 41.6400000000 1.1360710859 0.0857377492 1.1394244432 0.0164828932 0.0089180000 17367389 955859216 1373700096 -0.2190544158 -0.0833953470 2.1634604931 1043 41.6800000000 1.1359487772 0.0867446629 1.1394244432 0.0164834539 0.0047980000 17369365 955859216 1373700096 -0.2192577869 -0.0794665143 2.1618969440 1044 41.7200000000 1.1350272894 0.0877487651 1.1394244432 0.0164819239 0.0080500000 17371341 955859216 1373700096 -0.2193756849 -0.0771604180 2.1601893902 1045 41.7600000000 1.1349155903 0.0887508386 1.1394244432 0.0164809755 0.0047100000 17373317 955859216 1373700096 -0.2196168005 -0.0747109428 2.1599576473 1046 41.8000000000 1.1347404718 0.0897508287 1.1394244432 0.0164808002 0.0040230000 17375293 955859216 1373700096 -0.2198326141 -0.0737608150 2.1588757038 1047 41.8400000000 1.1346294880 0.0907488026 1.1394244432 0.0164789000 0.0041150000 17377269 955859216 1373700096 -0.2199284434 -0.0737521574 2.1584484577 1048 41.8800000000 1.1345306635 0.0917447776 1.1394244432 0.0164734188 0.0040670000 17379245 955859216 1373700096 -0.2202097923 -0.0722173154 2.1573457718 1049 41.9200000000 1.1343170404 0.0927386501 1.1394244432 0.0164695302 0.0040570000 17381221 955859216 1373700096 -0.2203902900 -0.0700797662 2.1558792591 1050 41.9600000000 1.1335861683 0.0937299335 1.1394244432 0.0164637265 0.0040570000 17383197 955859216 1373700096 -0.2204889953 -0.0674583688 2.1541082859 1051 42.0000000000 1.1325621605 0.0947183562 1.1394244432 0.0164581190 0.0040590000 17385173 955859216 1373700096 -0.2203764617 -0.0659968033 2.1522111893 1052 42.0400000000 1.1319643259 0.0957043314 1.1394244432 0.0164533304 0.0040480000 17387149 955859216 1373700096 -0.2205052227 -0.0651793405 2.1512269974 1053 42.0800000000 1.1312083006 0.0966877160 1.1394244432 0.0164479312 0.0040680000 17389125 955859216 1373700096 -0.2205862850 -0.0626833886 2.1493761539 1054 42.1200000000 1.1310560703 0.0976690901 1.1394244432 0.0164433543 0.0041000000 17391101 955859216 1373700096 -0.2206993252 -0.0611874014 2.1486473083 1055 42.1600000000 1.1309435368 0.0986484972 1.1394244432 0.0164390287 0.0040490000 17393077 955859216 1373700096 -0.2210427523 -0.0596305095 2.1483495235 1056 42.2000000000 1.1306312084 0.0996257536 1.1394244432 0.0164373257 0.0040830000 17395053 955859216 1373700096 -0.2212930322 -0.0573175177 2.1479613781 1057 42.2400000000 1.1305762529 0.1006011088 1.1394244432 0.0164363856 0.0040670000 17397029 955859216 1373700096 -0.2214191407 -0.0570174120 2.1475105286 1058 42.2800000000 1.1306303740 0.1015746714 1.1394244432 0.0164308648 0.0040770000 17399005 955859216 1373700096 -0.2216828912 -0.0553991087 2.1479079723 1059 42.3200000000 1.1310936213 0.1025468329 1.1394244432 0.0164262759 0.0083890000 17400981 955859216 1373700096 -0.2220136672 -0.0553658977 2.1486763954 1060 42.3600000000 1.1310218573 0.1035170923 1.1394244432 0.0164224143 0.0083060000 17402957 955859216 1373700096 -0.2223226726 -0.0548407510 2.1488440037 1061 42.4000000000 1.1315417290 0.1044860128 1.1394244432 0.0164178883 0.0049000000 17404933 955859216 1373700096 -0.2227679789 -0.0540392287 2.1498703957 1062 42.4400000000 1.1210205555 0.1054432017 1.1394244432 0.0164152665 0.0043520000 17406909 955859216 1373700096 -0.2225619853 -0.0516880490 2.1418523788 1063 42.4800000000 1.1227383614 0.1064002056 1.1394244432 0.0164147946 0.0035870000 17408885 955859216 1373700096 -0.2225964069 -0.0525592417 2.1445720196 1064 42.5200000000 1.1244914532 0.1073570582 1.1394244432 0.0164109553 0.0083200000 17410861 955859216 1373700096 -0.2226748168 -0.0523101129 2.1473045349 1065 42.5600000000 1.1255866289 0.1083131423 1.1394244432 0.0164062890 0.0070280000 17412837 955859216 1373700096 -0.2225880772 -0.0518850386 2.1497459412 1066 42.6000000000 1.1251351833 0.1092670092 1.1394244432 0.0164003930 0.0041630000 17414813 955859216 1373700096 -0.2223895639 -0.0507820472 2.1501038074 1067 42.6400000000 1.1251051426 0.1102190599 1.1394244432 0.0163962455 0.0036410000 17416789 955859216 1373700096 -0.2222474813 -0.0499805063 2.1510674953 1068 42.6800000000 1.1250569820 0.1111692827 1.1394244432 0.0163931718 0.0083100000 17418765 955859216 1373700096 -0.2218579352 -0.0496990606 2.1521441936 1069 42.7200000000 1.1240048409 0.1121167434 1.1394244432 0.0163904639 0.0078660000 17420741 955859216 1373700096 -0.2214167416 -0.0494672917 2.1517624855 1070 42.7600000000 1.1233921051 0.1130618606 1.1394244432 0.0163863571 0.0047240000 17422717 955859216 1373700096 -0.2211116850 -0.0484923422 2.1515655518 1071 42.8000000000 1.1106954813 0.1139933579 1.1394244432 0.0163887000 0.0060870000 17424693 955859216 1373700096 -0.2205149382 -0.0480926856 2.1406824589 1072 42.8400000000 1.1096963882 0.1149221854 1.1394244432 0.0163849587 0.0051340000 17426669 955859216 1373700096 -0.2205078006 -0.0484208465 2.1412856579 1073 42.8800000000 1.1086983681 0.1158483514 1.1394244432 0.0163788131 0.0050990000 17428645 955859216 1373700096 -0.2203984112 -0.0470021926 2.1407845020 1074 42.9200000000 1.1074723005 0.1167716512 1.1394244432 0.0163728281 0.0087200000 17430621 955859216 1373700096 -0.2204018682 -0.0472011715 2.1401069164 1075 42.9600000000 1.1065359116 0.1176923621 1.1394244432 0.0163658828 0.0052630000 17432597 955859216 1373700096 -0.2202748060 -0.0461140722 2.1395995617 1076 43.0000000000 1.1066749096 0.1186114909 1.1394244432 0.0163597692 0.0043950000 17434573 955859216 1373700096 -0.2200586945 -0.0460883118 2.1416623592 1077 43.0400000000 1.1065489054 0.1195287958 1.1394244432 0.0163537236 0.0087640000 17436549 955859216 1373700096 -0.2198722661 -0.0460208543 2.1443307400 1078 43.0800000000 1.1053477526 0.1204432847 1.1394244432 0.0163485200 0.0052430000 17438525 955859216 1373700096 -0.2195381075 -0.0461373664 2.1453945637 1079 43.1200000000 1.1047388315 0.1213555141 1.1394244432 0.0163419891 0.0074520000 17440501 955859216 1373700096 -0.2193623185 -0.0451493971 2.1479389668 1080 43.1600000000 1.1040337086 0.1222654013 1.1394244432 0.0163353865 0.0045400000 17442477 955859216 1373700096 -0.2191880494 -0.0447796620 2.1493813992 1081 43.2000000000 1.1018589735 0.1231715933 1.1394244432 0.0163299177 0.0087760000 17444453 955859216 1373700096 -0.2190130055 -0.0457770377 2.1498947144 1082 43.2400000000 1.1043865681 0.1240784463 1.1394244432 0.0163298268 0.0048470000 17446429 955859216 1373700096 -0.2189132124 -0.0451149493 2.1545627117 1083 43.2800000000 1.1060322523 0.1249851442 1.1394244432 0.0163327858 0.0081570000 17448405 955859216 1373700096 -0.2186044902 -0.0460475013 2.1584424973 1084 43.3200000000 1.0990250111 0.1258837050 1.1394244432 0.0163276864 0.0048080000 17450381 955859216 1373700096 -0.2183598280 -0.0460846946 2.1529190540 1085 43.3600000000 1.1012282372 0.1267826400 1.1394244432 0.0163231764 0.0058970000 17452357 955859216 1373700096 -0.2179604322 -0.0461391658 2.1564612389 1086 43.4000000000 1.1024595499 0.1276810534 1.1394244432 0.0163188714 0.0046930000 17454333 955859216 1373700096 -0.2175005078 -0.0458590984 2.1591763496 1087 43.4400000000 1.0973813534 0.1285731420 1.1394244432 0.0163145255 0.0086050000 17456309 955859216 1373700096 -0.2174078077 -0.0444920957 2.1560447216 1088 43.4800000000 1.1001200676 0.1294661079 1.1394244432 0.0163108176 0.0071180000 17458285 955859216 1373700096 -0.2168845832 -0.0447951108 2.1602702141 1089 43.5200000000 1.0964655876 0.1303540781 1.1394244432 0.0163054466 0.0044280000 17460261 955859216 1373700096 -0.2166513205 -0.0434449427 2.1586992741 1090 43.5600000000 1.0975191593 0.1312413855 1.1394244432 0.0163003436 0.0086390000 17462237 955859216 1373700096 -0.2160081863 -0.0434640236 2.1612877846 1091 43.6000000000 1.0963032246 0.1321259518 1.1394244432 0.0162940255 0.0050740000 17464213 955859216 1373700096 -0.2154657841 -0.0426074490 2.1619865894 1092 43.6400000000 1.0972357988 0.1330097520 1.1394244432 0.0162909048 0.0078270000 17466189 955859216 1373700096 -0.2147254348 -0.0435897410 2.1654543877 1093 43.6800000000 1.0970643759 0.1338917782 1.1394244432 0.0162849346 0.0046760000 17468165 955859216 1373700096 -0.2141118646 -0.0421819985 2.1681602001 1094 43.7200000000 1.0969046354 0.1347720459 1.1394244432 0.0162788810 0.0063000000 17470141 955859216 1373700096 -0.2133652121 -0.0418500714 2.1702942848 1095 43.7600000000 1.0972347260 0.1356510072 1.1394244432 0.0162735678 0.0063120000 17472117 955859216 1373700096 -0.2128021717 -0.0417580381 2.1734015942 1096 43.8000000000 1.0974568129 0.1365285673 1.1394244432 0.0162675326 0.0078920000 17474093 955859216 1373700096 -0.2121678740 -0.0415810794 2.1762619019 1097 43.8400000000 1.0978449583 0.1374048812 1.1394244432 0.0162611885 0.0046860000 17476069 955859216 1373700096 -0.2115308046 -0.0422315970 2.1789836884 1098 43.8800000000 1.1017290354 0.1382831364 1.1394244432 0.0162582473 0.0083210000 17478045 955859216 1373700096 -0.2104453593 -0.0426772758 2.1851434708 1099 43.9200000000 1.1049306393 0.1391627064 1.1394244432 0.0162542253 0.0058460000 17480021 955859216 1373700096 -0.2093545049 -0.0427804962 2.1900799274 1100 43.9600000000 1.0985119343 0.1400348421 1.1394244432 0.0162564754 0.0063210000 17481997 955859216 1373700096 -0.2094888687 -0.0393266790 2.1859953403 1101 44.0000000000 1.0995947123 0.1409063769 1.1394244432 0.0162526611 0.0085560000 17483973 955859216 1373700096 -0.2087887228 -0.0390796848 2.1889081001 1102 44.0400000000 1.1007210016 0.1417773521 1.1394244432 0.0162484982 0.0056720000 17485949 955859216 1373700096 -0.2081540674 -0.0390048213 2.1926848888 1103 44.0800000000 1.1011779308 0.1426471622 1.1394244432 0.0162430539 0.0062420000 17487925 955859216 1373700096 -0.2075184882 -0.0378868654 2.1955902576 1104 44.1200000000 1.1011824608 0.1435154007 1.1394244432 0.0162365299 0.0052190000 17489901 955859216 1373700096 -0.2069084197 -0.0377677232 2.1977188587 1105 44.1600000000 1.1015914679 0.1443824379 1.1394244432 0.0162304849 0.0089440000 17491877 955859216 1373700096 -0.2063864917 -0.0370572321 2.2007181644 1106 44.2000000000 1.1014834642 0.1452478095 1.1394244432 0.0162241750 0.0061160000 17493853 955859216 1373700096 -0.2056845278 -0.0364115499 2.2029402256 1107 44.2400000000 1.1016641855 0.1461117810 1.1394244432 0.0162177867 0.0064430000 17495829 955859216 1373700096 -0.2050698698 -0.0367097259 2.2051699162 1108 44.2800000000 1.1021311283 0.1469746143 1.1394244432 0.0162116608 0.0084540000 17497805 955859216 1373700096 -0.2045467645 -0.0365821570 2.2077095509 1109 44.3200000000 1.1064429283 0.1478397796 1.1394244432 0.0162090474 0.0047980000 17499781 955859216 1373700096 -0.2030313462 -0.0387836881 2.2143118382 1110 44.3600000000 1.1028549671 0.1487001537 1.1394244432 0.0162112610 0.0064770000 17501757 955859216 1373700096 -0.2032712549 -0.0353288278 2.2121002674 1111 44.4000000000 1.1028002501 0.1495589296 1.1394244432 0.0162044023 0.0051980000 17503733 955859216 1373700096 -0.2026381642 -0.0357681885 2.2142219543 1112 44.4400000000 1.1058610678 0.1504189136 1.1394244432 0.0162005953 0.0041290000 17505709 955859216 1373700096 -0.2012516111 -0.0370780528 2.2193620205 1113 44.4800000000 1.1097044945 0.1512808054 1.1394244432 0.0161986520 0.0086560000 17507685 955859216 1373700096 -0.1996480972 -0.0404313095 2.2252414227 1114 44.5200000000 1.1030708551 0.1521351950 1.1394244432 0.0162107674 0.0075870000 17509661 955859216 1373700096 -0.2003389895 -0.0333751105 2.2211110592 1115 44.5600000000 1.1073266268 0.1529918689 1.1394244432 0.0162099937 0.0043680000 17511637 955859216 1373700096 -0.1984816045 -0.0372033417 2.2272315025 1116 44.6000000000 1.1032414436 0.1538433470 1.1394244432 0.0162103556 0.0040570000 17513613 955859216 1373700096 -0.1986759752 -0.0334197432 2.2252180576 1117 44.6400000000 1.1045237780 0.1546944486 1.1394244432 0.0162040254 0.0091040000 17515589 955859216 1373700096 -0.1978191137 -0.0319656692 2.2287838459 1118 44.6800000000 1.1062932014 0.1555456103 1.1394244432 0.0161983694 0.0075340000 17517565 955859216 1373700096 -0.1968204975 -0.0317566730 2.2335367203 1119 44.7200000000 1.1090950966 0.1563977546 1.1394244432 0.0162008407 0.0046090000 17519541 955859216 1373700096 -0.1961173117 -0.0297154337 2.2393860817 1120 44.7600000000 1.1130124331 0.1572518748 1.1394244432 0.0162001724 0.0086440000 17521517 955859216 1373700096 -0.1934942901 -0.0376903601 2.2465476990 1121 44.8000000000 1.1153711081 0.1581065753 1.1394244432 0.0161972601 0.0049730000 17523493 955859216 1373700096 -0.1911844313 -0.0455023386 2.2512519360 1122 44.8400000000 1.1150978804 0.1589595087 1.1394244432 0.0161950963 0.0079830000 17525469 955859216 1373700096 -0.1890315115 -0.0576595515 2.2541513443 1123 44.8800000000 1.0966590643 0.1597945039 1.1394244432 0.0162747568 0.0049810000 17527445 955859216 1373700096 -0.1922294348 -0.0446382836 2.2389576435 1124 44.9200000000 1.0967525244 0.1606280964 1.1394244432 0.0162682039 0.0037130000 17529421 955859216 1373700096 -0.1896687001 -0.0409332849 2.2414176464 1125 44.9600000000 1.0938459635 0.1614576234 1.1394244432 0.0162659033 0.0087710000 17531397 955859216 1373700096 -0.1871960759 -0.0490157120 2.2409758568 1126 45.0000000000 1.0694538355 0.1622640144 1.1394244432 0.0164102605 0.0065140000 17533373 955859216 1373700096 -0.1889057606 -0.0452308282 2.2196416855 1127 45.0400000000 1.0655691624 0.1630655274 1.1394244432 0.0164102004 0.0070770000 17535349 955859216 1373700096 -0.1854864508 -0.0562021509 2.2183489799 1128 45.0800000000 1.0571904182 0.1638581913 1.1394244432 0.0164126733 0.0052180000 17537325 955859216 1373700096 -0.1818313152 -0.0757374913 2.2123453617 1129 45.1200000000 0.9773622751 0.1645787441 1.1394244432 0.0164358373 0.0094600000 17539301 955859216 1373700096 -0.1842688620 -0.1012688279 2.1342759132 1130 45.1600000000 0.9494209290 0.1652732947 1.1394244432 0.0164648907 0.0055160000 17541277 955859216 1373700096 -0.1804544479 -0.0982542634 2.1084189415 1131 45.2000000000 0.8915528655 0.1659154517 1.1394244432 0.0165941260 0.0075920000 17543253 955859216 1373700096 -0.1790687740 -0.0775918588 2.0544850826 1132 45.2400000000 0.8439643979 0.1665144348 1.1394244432 0.0168184989 0.0050440000 17545229 955859216 1373700096 -0.1773643494 -0.0338962227 2.0097501278 1133 45.2800000000 0.8025664091 0.1670758223 1.1394244432 0.0169979799 0.0093860000 17547205 955859216 1373700096 -0.1753458828 -0.0196458828 1.9701908827 1134 45.3200000000 0.7723651528 0.1676095871 1.1394244432 0.0171176770 0.0054590000 17549181 955859216 1373700096 -0.1731857508 -0.0040182066 1.9416242838 1135 45.3600000000 0.7278349400 0.1681031777 1.1394244432 0.0173960694 0.0078110000 17551157 955859216 1373700096 -0.1710233539 0.0242486671 1.8992550373 1136 45.4000000000 0.7108741999 0.1685809691 1.1394244432 0.0176865582 0.0049620000 17553133 955859216 1373700096 -0.1680673361 0.1210597008 1.8704125881 1137 45.4400000000 0.6952176094 0.1690441500 1.1394244432 0.0182292893 0.0088410000 17555109 955859216 1373700096 -0.1645869464 0.2483758032 1.8177996874 1138 45.4800000000 0.7510811090 0.1695556060 1.1394244432 0.0195209086 0.0052140000 17557085 955859216 1373700096 -0.1603708565 0.4599018991 1.7496972084 1139 45.5200000000 0.7271817923 0.1700451812 1.1394244432 0.0195615262 0.0094100000 17559061 955859216 1373700096 -0.1607880294 0.4648551345 1.7168880701 1140 45.5600000000 0.7334106565 0.1705393615 1.1394244432 0.0196337321 0.0056270000 17561037 955859216 1373700096 -0.1573106050 0.4983594716 1.6964809895 1141 45.6000000000 0.7327483296 0.1710320950 1.1394244432 0.0196400072 0.0069780000 17563013 955859216 1373700096 -0.1548313797 0.5134629607 1.6853497028 1142 45.6400000000 0.7350015044 0.1715259386 1.1394244432 0.0196730551 0.0089670000 17564989 955859216 1373700096 -0.1523262262 0.5312250853 1.6740934849 1143 45.6800000000 0.7415738106 0.1720246682 1.1394244432 0.0196735918 0.0062860000 17566965 955859216 1373700096 -0.1500367671 0.5550399423 1.6667492390 1144 45.7200000000 0.7402682900 0.1725213846 1.1394244432 0.0196685727 0.0044870000 17568941 955859216 1373700096 -0.1476723701 0.5667511821 1.6599566936 1145 45.7600000000 0.7506724596 0.1730263201 1.1394244432 0.0197195624 0.0088140000 17570917 955859216 1373700096 -0.1451385021 0.5900011063 1.6488978863 1146 45.8000000000 0.7651028633 0.1735429663 1.1394244432 0.0197391994 0.0053880000 17572893 955859216 1373700096 -0.1421208680 0.6304098964 1.6309287548 1147 45.8400000000 0.7802237272 0.1740718946 1.1394244432 0.0197606586 0.0070580000 17574869 955859216 1373700096 -0.1381683946 0.6727107763 1.6042572260 1148 45.8800000000 0.7805339098 0.1746001716 1.1394244432 0.0197618733 0.0058150000 17576845 955859216 1373700096 -0.1344307810 0.6945836544 1.5762094259 1149 45.9200000000 0.7633419633 0.1751125665 1.1394244432 0.0198108270 0.0049380000 17578821 955859216 1373700096 -0.1289137155 0.7101336122 1.5237139463 1150 45.9600000000 0.7520979047 0.1756142929 1.1394244432 0.0198417316 0.0094640000 17580797 955859216 1373700096 -0.1247149557 0.7179061770 1.4826382399 1151 46.0000000000 0.7341673374 0.1760995692 1.1394244432 0.0198887484 0.0066050000 17582773 955859216 1373700096 -0.1196693033 0.7234865427 1.4221717119 1152 46.0400000000 0.7373792529 0.1765867912 1.1394244432 0.0198891533 0.0042700000 17584749 955859216 1373700096 -0.1165279895 0.7299337387 1.4106796980 1153 46.0800000000 0.7268832922 0.1770640648 1.1394244432 0.0199353196 0.0041340000 17586725 955859216 1373700096 -0.1143092066 0.7319738865 1.3816343546 1154 46.1200000000 0.7182158232 0.1775330005 1.1394244432 0.0199799419 0.0097050000 17588701 955859216 1373700096 -0.1107123345 0.7322462797 1.3489587307 1155 46.1600000000 0.7134166956 0.1779969691 1.1394244432 0.0200030171 0.0079830000 17590677 955859216 1373700096 -0.1073566303 0.7332792282 1.3199142218 1156 46.2000000000 0.7023652792 0.1784505749 1.1394244432 0.0200424097 0.0051440000 17592653 955859216 1373700096 -0.1045606285 0.7270597816 1.2888556719 1157 46.2400000000 0.6905030608 0.1788931440 1.1394244432 0.0200611166 0.0044920000 17594629 955859216 1373700096 -0.1015127450 0.7177439332 1.2687374353 1158 46.2800000000 0.6669455171 0.1793146055 1.1394244432 0.0201058999 0.0099310000 17596605 955859216 1373700096 -0.0989930108 0.6966428161 1.2449679375 1159 46.3200000000 0.6371880770 0.1797096645 1.1394244432 0.0201559477 0.0059740000 17598581 955859216 1373700096 -0.0965457037 0.6698467731 1.2250697613 1160 46.3600000000 0.5782184005 0.1800532065 1.1394244432 0.0202532709 0.0063970000 17600557 955859216 1373700096 -0.0942958668 0.6126400828 1.2098810673 1161 46.4000000000 0.5388473868 0.1803622455 1.1394244432 0.0202945342 0.0080620000 17602533 955859216 1373700096 -0.0924789533 0.5705599785 1.2003417015 1162 46.4400000000 0.5078231096 0.1806440534 1.1394244432 0.0203539444 0.0052580000 17604509 955859216 1373700096 -0.0910366625 0.5384443998 1.1902741194 1163 46.4800000000 0.4714680314 0.1808941170 1.1394244432 0.0204078603 0.0086830000 17606485 955859216 1373700096 -0.0893090591 0.5012822151 1.1830507517 1164 46.5200000000 0.4365968406 0.1811137929 1.1394244432 0.0204453248 0.0053420000 17608461 955859216 1373700096 -0.0870935842 0.4655587673 1.1785125732 1165 46.5600000000 0.4100313783 0.1813102887 1.1394244432 0.0204681791 0.0046690000 17610437 955859216 1373700096 -0.0853979439 0.4396592677 1.1763625145 1166 46.6000000000 0.4049749970 0.1815021109 1.1394244432 0.0204615983 0.0098700000 17612413 955859216 1373700096 -0.0824931487 0.4358195364 1.1768717766 1167 46.6400000000 0.3834786415 0.1816751842 1.1394244432 0.0204725425 0.0068210000 17614389 955859216 1373700096 -0.0818023533 0.4101721644 1.1765774488 1168 46.6800000000 0.3632102013 0.1818306080 1.1394244432 0.0204819154 0.0063640000 17616365 955859216 1373700096 -0.0803034157 0.3883210719 1.1786428690 1169 46.7200000000 0.3448089063 0.1819700249 1.1394244432 0.0204870066 0.0052540000 17618341 955859216 1373700096 -0.0785900280 0.3696100414 1.1825606823 1170 46.7600000000 0.3247680366 0.1820920745 1.1394244432 0.0204936352 0.0047560000 17620317 955859216 1373700096 -0.0772800148 0.3494132161 1.1900969744 1171 46.8000000000 0.3122370839 0.1822032145 1.1394244432 0.0204903665 0.0047800000 17622293 955859216 1373700096 -0.0753371343 0.3348963559 1.1987401247 1172 46.8400000000 0.2858223915 0.1822916268 1.1394244432 0.0204977452 0.0101180000 17624269 955859216 1373700096 -0.0736247152 0.3072863519 1.2124743462 1173 46.8800000000 0.2678238153 0.1823645443 1.1394244432 0.0205009199 0.0078490000 17626245 955859216 1373700096 -0.0724133030 0.2901208103 1.2224683762 1174 46.9200000000 0.2517437935 0.1824236407 1.1394244432 0.0205014382 0.0053680000 17628221 955859216 1373700096 -0.0711132586 0.2727368176 1.2306458950 1175 46.9600000000 0.2494040281 0.1824806453 1.1394244432 0.0204970398 0.0044850000 17630197 955859216 1373700096 -0.0674141869 0.2695482075 1.2349622250 1176 47.0000000000 0.2395441979 0.1825291687 1.1394244432 0.0204971981 0.0098650000 17632173 955859216 1373700096 -0.0681653470 0.2578967512 1.2370889187 1177 47.0400000000 0.2372260392 0.1825756402 1.1394244432 0.0204924631 0.0064270000 17634149 955859216 1373700096 -0.0648566708 0.2550623715 1.2404487133 1178 47.0800000000 0.2346281260 0.1826198273 1.1394244432 0.0204867060 0.0045650000 17636125 955859216 1373700096 -0.0627081990 0.2536039650 1.2429771423 1179 47.1200000000 0.2330754697 0.1826626226 1.1394244432 0.0204791208 0.0097450000 17638101 955859216 1373700096 -0.0608189590 0.2522824407 1.2449325323 1180 47.1600000000 0.2316776961 0.1827041608 1.1394244432 0.0204716384 0.0059330000 17640077 955859216 1373700096 -0.0588860102 0.2505190969 1.2467880249 1181 47.2000000000 0.2297553122 0.1827440009 1.1394244432 0.0204642405 0.0045660000 17642053 955859216 1373700096 -0.0570223704 0.2490964979 1.2487635612 1182 47.2400000000 0.2283202559 0.1827825595 1.1394244432 0.0204578727 0.0089150000 17644029 955859216 1373700096 -0.0555446669 0.2478080988 1.2505595684 1183 47.2800000000 0.2275557071 0.1828204066 1.1394244432 0.0204494762 0.0052090000 17646005 955859216 1373700096 -0.0538286678 0.2462416440 1.2521560192 1184 47.3200000000 0.2239230275 0.1828551217 1.1394244432 0.0204445789 0.0095460000 17647981 955859216 1373700096 -0.0565260313 0.2422511578 1.2511701584 1185 47.3600000000 0.2234174311 0.1828893515 1.1394244432 0.0204371493 0.0055570000 17649957 955859216 1373700096 -0.0535055809 0.2407511622 1.2536029816 1186 47.4000000000 0.2212193161 0.1829216702 1.1394244432 0.0204313381 0.0043990000 17651933 955859216 1373700096 -0.0517269559 0.2399618030 1.2549592257 1187 47.4400000000 0.2205022871 0.1829533303 1.1394244432 0.0204237344 0.0095840000 17653909 955859216 1373700096 -0.0503512062 0.2396538109 1.2557634115 1188 47.4800000000 0.2209104002 0.1829852807 1.1394244432 0.0204154160 0.0065310000 17655885 955859216 1373700096 -0.0489801280 0.2384568453 1.2568583488 1189 47.5200000000 0.2210117280 0.1830172626 1.1394244432 0.0204068369 0.0046690000 17657861 955859216 1373700096 -0.0473556295 0.2352787256 1.2582319975 1190 47.5600000000 0.2188986540 0.1830474150 1.1394244432 0.0203998082 0.0102900000 17659837 955859216 1373700096 -0.0459899642 0.2336758375 1.2596524954 1191 47.6000000000 0.2180416435 0.1830767973 1.1394244432 0.0203921822 0.0057340000 17661813 955859216 1373700096 -0.0450177044 0.2327505201 1.2607034445 1192 47.6400000000 0.2172390223 0.1831054568 1.1394244432 0.0203866040 0.0064470000 17663789 955859216 1373700096 -0.0493587814 0.2312501967 1.2584588528 1193 47.6800000000 0.2158657908 0.1831329173 1.1394244432 0.0203801947 0.0046320000 17665765 955859216 1373700096 -0.0464170277 0.2309336215 1.2607214451 1194 47.7200000000 0.2159080654 0.1831603672 1.1394244432 0.0203736658 0.0100410000 17667741 955859216 1373700096 -0.0443601832 0.2309678495 1.2624647617 1195 47.7600000000 0.2154265046 0.1831873681 1.1394244432 0.0203682602 0.0063340000 17669717 955859216 1373700096 -0.0488026552 0.2309046239 1.2605793476 1196 47.8000000000 0.2157258540 0.1832145742 1.1394244432 0.0203632640 0.0047030000 17671693 955859216 1373700096 -0.0454977863 0.2318213582 1.2628978491 1197 47.8400000000 0.2145606577 0.1832407614 1.1394244432 0.0203572259 0.0044900000 17673669 955859216 1373700096 -0.0480914935 0.2290225923 1.2623852491 1198 47.8800000000 0.2145377547 0.1832668858 1.1394244432 0.0203493896 0.0096970000 17675645 955859216 1373700096 -0.0440440290 0.2266034335 1.2653577328 1199 47.9200000000 0.2137479633 0.1832923079 1.1394244432 0.0203454808 0.0058320000 17677621 955859216 1373700096 -0.0480972230 0.2272425294 1.2637549639 1200 47.9600000000 0.2132361680 0.1833172611 1.1394244432 0.0203430549 0.0043640000 17679597 955859216 1373700096 -0.0446703844 0.2261069864 1.2660160065 1201 48.0000000000 0.2120400965 0.1833411769 1.1394244432 0.0203386264 0.0040610000 17681573 955859216 1373700096 -0.0423803963 0.2252962440 1.2677993774 1202 48.0400000000 0.2118643522 0.1833649066 1.1394244432 0.0203315373 0.0040630000 17683549 955859216 1373700096 -0.0407475233 0.2241609693 1.2688649893 1203 48.0800000000 0.2125430107 0.1833891611 1.1394244432 0.0203257138 0.0043960000 17685525 955859216 1373700096 -0.0454052836 0.2257487476 1.2667050362 1204 48.1200000000 0.2124674916 0.1834133125 1.1394244432 0.0203185575 0.0040980000 17687501 955859216 1373700096 -0.0428967997 0.2256826460 1.2683494091 1205 48.1600000000 0.2126688659 0.1834375910 1.1394244432 0.0203113415 0.0040810000 17689477 955859216 1373700096 -0.0407567024 0.2254871279 1.2694524527 1206 48.2000000000 0.2125044763 0.1834616929 1.1394244432 0.0203060114 0.0040840000 17691453 955859216 1373700096 -0.0393033214 0.2242470682 1.2699404955 1207 48.2400000000 0.2122528106 0.1834855463 1.1394244432 0.0203000858 0.0040910000 17693429 955859216 1373700096 -0.0379845612 0.2232045382 1.2706580162 1208 48.2800000000 0.2121413648 0.1835092680 1.1394244432 0.0202937994 0.0102500000 17695405 955859216 1373700096 -0.0365254022 0.2224303484 1.2712789774 1209 48.3200000000 0.2118462920 0.1835327064 1.1394244432 0.0202897541 0.0101420000 17697381 955859216 1373700096 -0.0350833498 0.2223840654 1.2715877295 1210 48.3600000000 0.2121748179 0.1835563776 1.1394244432 0.0202842546 0.0058430000 17699357 955859216 1373700096 -0.0334930718 0.2225735188 1.2720304728 1211 48.4000000000 0.2127298266 0.1835804680 1.1394244432 0.0202784896 0.0047410000 17701333 955859216 1373700096 -0.0311455913 0.2217698693 1.2728500366 1212 48.4400000000 0.2127038985 0.1836044972 1.1394244432 0.0202772862 0.0065930000 17703309 955859216 1373700096 -0.0324515477 0.2210172862 1.2719196081 1213 48.4800000000 0.2125453502 0.1836283561 1.1394244432 0.0202697963 0.0052730000 17705285 955859216 1373700096 -0.0277736057 0.2206870914 1.2729359865 1214 48.5200000000 0.2126611322 0.1836522711 1.1394244432 0.0202629926 0.0093030000 17707261 955859216 1373700096 -0.0233595800 0.2207623869 1.2739286423 1215 48.5600000000 0.2134416550 0.1836767891 1.1394244432 0.0202585296 0.0054800000 17709237 955859216 1373700096 -0.0196766332 0.2204333395 1.2746390104 1216 48.6000000000 0.2129721045 0.1837008806 1.1394244432 0.0202557279 0.0050540000 17711213 955859216 1373700096 -0.0230652820 0.2186688483 1.2736659050 1217 48.6400000000 0.2118296474 0.1837239938 1.1394244432 0.0202522927 0.0044060000 17713189 955859216 1373700096 -0.0181809720 0.2185835540 1.2746449709 1218 48.6800000000 0.2121804059 0.1837473571 1.1394244432 0.0202495783 0.0044120000 17715165 955859216 1373700096 -0.0144427530 0.2189304084 1.2755829096 1219 48.7200000000 0.2129293233 0.1837712963 1.1394244432 0.0202442148 0.0101580000 17717141 955859216 1373700096 -0.0107027553 0.2190724164 1.2766343355 1220 48.7600000000 0.2127855420 0.1837950785 1.1394244432 0.0202387787 0.0089340000 17719117 955859216 1373700096 -0.0130385263 0.2186318338 1.2762840986 1221 48.8000000000 0.2128406912 0.1838188669 1.1394244432 0.0202374780 0.0054960000 17721093 955859216 1373700096 -0.0076805018 0.2164091021 1.2781554461 1222 48.8400000000 0.2110599726 0.1838411591 1.1394244432 0.0202351968 0.0044540000 17723069 955859216 1373700096 -0.0033052347 0.2158819884 1.2795753479 1223 48.8800000000 0.2109786123 0.1838633484 1.1394244432 0.0202343647 0.0041550000 17725045 955859216 1373700096 0.0001263743 0.2158698738 1.2804081440 1224 48.9200000000 0.2110549212 0.1838855637 1.1394244432 0.0202309040 0.0102790000 17727021 955859216 1373700096 0.0032153900 0.2169220895 1.2812550068 1225 48.9600000000 0.2116677165 0.1839082430 1.1394244432 0.0202279215 0.0067840000 17728997 955859216 1373700096 0.0062041744 0.2171863914 1.2822105885 1226 49.0000000000 0.2112617493 0.1839305542 1.1394244432 0.0202244902 0.0049810000 17730973 955859216 1373700096 0.0091484375 0.2173854560 1.2831163406 1227 49.0400000000 0.2111682892 0.1839527528 1.1394244432 0.0202203150 0.0070600000 17732949 955859216 1373700096 0.0120568071 0.2176534981 1.2842590809 1228 49.0800000000 0.2113383859 0.1839750538 1.1394244432 0.0202155780 0.0073070000 17734925 955859216 1373700096 0.0151597839 0.2179065794 1.2852704525 1229 49.1200000000 0.2112871557 0.1839972769 1.1394244432 0.0202101941 0.0066210000 17736901 955859216 1373700096 0.0183431879 0.2181861252 1.2862012386 1230 49.1600000000 0.2108702511 0.1840191248 1.1394244432 0.0202060550 0.0053160000 17738877 955859216 1373700096 0.0208439827 0.2177633643 1.2871104479 1231 49.2000000000 0.2101921588 0.1840403864 1.1394244432 0.0201998130 0.0092300000 17740853 955859216 1373700096 0.0233258735 0.2187275141 1.2875016928 1232 49.2400000000 0.2106808424 0.1840620102 1.1394244432 0.0201935521 0.0055230000 17742829 955859216 1373700096 0.0260160994 0.2199773490 1.2879681587 1233 49.2800000000 0.2099586129 0.1840830131 1.1394244432 0.0201867979 0.0050620000 17744805 955859216 1373700096 0.0231827777 0.2200084627 1.2879920006 1234 49.3200000000 0.2106846124 0.1841045703 1.1394244432 0.0201801898 0.0093650000 17746781 955859216 1373700096 0.0275823753 0.2203330845 1.2889734507 1235 49.3600000000 0.2102539986 0.1841257439 1.1394244432 0.0201765160 0.0056180000 17748757 955859216 1373700096 0.0312929861 0.2202718258 1.2900407314 1236 49.4000000000 0.2091732472 0.1841460089 1.1394244432 0.0201784369 0.0048560000 17750733 955859216 1373700096 0.0339274593 0.2189610600 1.2911207676 1237 49.4400000000 0.2079634666 0.1841652631 1.1394244432 0.0201776020 0.0103940000 17752709 955859216 1373700096 0.0363109000 0.2194072455 1.2915028334 1238 49.4800000000 0.2078727931 0.1841844130 1.1394244432 0.0201793497 0.0103870000 17754685 955859216 1373700096 0.0380603336 0.2211575210 1.2913967371 1239 49.5200000000 0.2080870420 0.1842037048 1.1394244432 0.0201830350 0.0086600000 17756661 955859216 1373700096 0.0406441353 0.2216333151 1.2912557125 1240 49.5600000000 0.2083408535 0.1842231703 1.1394244432 0.0201847959 0.0055030000 17758637 955859216 1373700096 0.0433298349 0.2202467769 1.2918735743 1241 49.6000000000 0.2074620575 0.1842418962 1.1394244432 0.0201807807 0.0044950000 17760613 955859216 1373700096 0.0469341278 0.2201041132 1.2920536995 1242 49.6400000000 0.2075473964 0.1842606607 1.1394244432 0.0201747724 0.0104780000 17762589 955859216 1373700096 0.0497868508 0.2214939147 1.2920589447 1243 49.6800000000 0.2088254839 0.1842804232 1.1394244432 0.0201670956 0.0104830000 17764565 955859216 1373700096 0.0527345873 0.2227058411 1.2923702002 1244 49.7200000000 0.2086824477 0.1843000390 1.1394244432 0.0201590052 0.0062480000 17766541 955859216 1373700096 0.0558736660 0.2239558101 1.2921669483 1245 49.7600000000 0.2081540823 0.1843191989 1.1394244432 0.0201509370 0.0048500000 17768517 955859216 1373700096 0.0583850034 0.2250758260 1.2915630341 1246 49.8000000000 0.2089731693 0.1843389854 1.1394244432 0.0201437956 0.0042250000 17770493 955859216 1373700096 0.0606121309 0.2261932641 1.2915495634 1247 49.8400000000 0.2088728249 0.1843586597 1.1394244432 0.0201362953 0.0039580000 17772469 955859216 1373700096 0.0622457080 0.2274501771 1.2911546230 1248 49.8800000000 0.2088699788 0.1843783001 1.1394244432 0.0201289280 0.0103560000 17774445 955859216 1373700096 0.0639599860 0.2280854136 1.2908736467 1249 49.9200000000 0.2088306397 0.1843978777 1.1394244432 0.0201208796 0.0062850000 17776421 955859216 1373700096 0.0654359981 0.2275795490 1.2910089493 1250 49.9600000000 0.2076976895 0.1844165175 1.1394244432 0.0201128936 0.0048430000 17778397 955859216 1373700096 0.0671805888 0.2283052504 1.2907981873 1251 50.0000000000 0.2077441663 0.1844351647 1.1394244432 0.0201049698 0.0082110000 17780373 955859216 1373700096 0.0686216205 0.2305443585 1.2897390127 1252 50.0400000000 0.2083766460 0.1844542873 1.1394244432 0.0200975371 0.0054180000 17782349 955859216 1373700096 0.0698863417 0.2322473228 1.2888959646 1253 50.0800000000 0.2084641755 0.1844734492 1.1394244432 0.0200896205 0.0080300000 17784325 955859216 1373700096 0.0708702058 0.2332421392 1.2883331776 1254 50.1200000000 0.2086360902 0.1844927177 1.1394244432 0.0200818576 0.0052190000 17786301 955859216 1373700096 0.0725239739 0.2339612842 1.2879240513 1255 50.1600000000 0.2084995508 0.1845118466 1.1394244432 0.0200743713 0.0091020000 17788277 955859216 1373700096 0.0742311254 0.2341376841 1.2875821590 1256 50.2000000000 0.2079681307 0.1845305220 1.1394244432 0.0200672119 0.0054710000 17790253 955859216 1373700096 0.0764729083 0.2339905649 1.2873315811 1257 50.2400000000 0.2080773115 0.1845492546 1.1394244432 0.0200594889 0.0048240000 17792229 955859216 1373700096 0.0787667930 0.2338271290 1.2875196934 1258 50.2800000000 0.2073466182 0.1845673765 1.1394244432 0.0200515252 0.0094170000 17794205 955859216 1373700096 0.0802145526 0.2349959761 1.2865947485 1259 50.3200000000 0.2079017013 0.1845859105 1.1394244432 0.0200435946 0.0056050000 17796181 955859216 1373700096 0.0833145007 0.2362280637 1.2860921621 1260 50.3600000000 0.2080772519 0.1846045544 1.1394244432 0.0200367778 0.0050140000 17798157 955859216 1373700096 0.0840321183 0.2386403382 1.2844697237 1261 50.4000000000 0.2085420638 0.1846235374 1.1394244432 0.0200293364 0.0104840000 17800133 955859216 1373700096 0.0885414556 0.2396805882 1.2841135263 1262 50.4400000000 0.2082686573 0.1846422736 1.1394244432 0.0200214134 0.0063260000 17802109 955859216 1373700096 0.0896640196 0.2411501706 1.2828799486 1263 50.4800000000 0.2074453980 0.1846603283 1.1394244432 0.0200134902 0.0048810000 17804085 955859216 1373700096 0.0933278725 0.2425098568 1.2820428610 1264 50.5200000000 0.2082013190 0.1846789525 1.1394244432 0.0200056265 0.0075870000 17806061 955859216 1373700096 0.0931134969 0.2442688942 1.2807432413 1265 50.5600000000 0.2087270468 0.1846979629 1.1394244432 0.0199982136 0.0052910000 17808037 955859216 1373700096 0.0968050510 0.2440148592 1.2806764841 1266 50.6000000000 0.2074925154 0.1847159681 1.1394244432 0.0199909969 0.0044990000 17810013 955859216 1373700096 0.0995549709 0.2438436896 1.2802075148 1267 50.6400000000 0.2062162012 0.1847329375 1.1394244432 0.0199835271 0.0044670000 17811989 955859216 1373700096 0.1016270965 0.2450842261 1.2793008089 1268 50.6800000000 0.2066950649 0.1847502577 1.1394244432 0.0199767297 0.0046370000 17813965 955859216 1373700096 0.1057666615 0.2465068996 1.2777110338 1269 50.7200000000 0.2054290175 0.1847665531 1.1394244432 0.0199695845 0.0105190000 17815941 955859216 1373700096 0.1080729514 0.2454782724 1.2773501873 1270 50.7600000000 0.2045552582 0.1847821347 1.1394244432 0.0199622171 0.0083700000 17817917 955859216 1373700096 0.1098507047 0.2453915328 1.2767714262 1271 50.8000000000 0.2038494051 0.1847971365 1.1394244432 0.0199548242 0.0060740000 17819893 955859216 1373700096 0.1086798534 0.2468467504 1.2748368979 1272 50.8400000000 0.2050456554 0.1848130552 1.1394244432 0.0199475869 0.0045910000 17821869 955859216 1373700096 0.1087001860 0.2488729656 1.2733560801 1273 50.8800000000 0.2050566226 0.1848289574 1.1394244432 0.0199402228 0.0041920000 17823845 955859216 1373700096 0.1091199592 0.2503423393 1.2721590996 1274 50.9200000000 0.2051127553 0.1848448788 1.1394244432 0.0199328402 0.0103380000 17825821 955859216 1373700096 0.1112198904 0.2526682615 1.2709050179 1275 50.9600000000 0.2057885081 0.1848613051 1.1394244432 0.0199251570 0.0065500000 17827797 955859216 1373700096 0.1142542660 0.2536261976 1.2706646919 1276 51.0000000000 0.2048990428 0.1848770087 1.1394244432 0.0199174678 0.0048840000 17829773 955859216 1373700096 0.1147351339 0.2530549169 1.2703591585 1277 51.0400000000 0.2051510215 0.1848928850 1.1394244432 0.0199099965 0.0044670000 17831749 955859216 1373700096 0.1163675711 0.2527896762 1.2701948881 1278 51.0800000000 0.2049873173 0.1849086083 1.1394244432 0.0199022109 0.0104620000 17833725 955859216 1373700096 0.1184104010 0.2523239851 1.2702029943 1279 51.1200000000 0.2046290636 0.1849240270 1.1394244432 0.0198945868 0.0061390000 17835701 955859216 1373700096 0.1202221438 0.2512676418 1.2701120377 1280 51.1600000000 0.2043863982 0.1849392319 1.1394244432 0.0198876093 0.0047180000 17837677 955859216 1373700096 0.1193642393 0.2505722344 1.2696868181 1281 51.2000000000 0.2046251744 0.1849545996 1.1394244432 0.0198802592 0.0101570000 17839653 955859216 1373700096 0.1195229292 0.2539258301 1.2677221298 1282 51.2400000000 0.2039118558 0.1849693868 1.1394244432 0.0198725683 0.0058500000 17841629 955859216 1373700096 0.1197274029 0.2542803288 1.2672835588 1283 51.2800000000 0.2037550956 0.1849840289 1.1394244432 0.0198648373 0.0064990000 17843605 955859216 1373700096 0.1207983121 0.2535696328 1.2672685385 1284 51.3200000000 0.2045815140 0.1849992917 1.1394244432 0.0198570944 0.0052200000 17845581 955859216 1373700096 0.1213362440 0.2550257146 1.2667720318 1285 51.3600000000 0.2035514861 0.1850137292 1.1394244432 0.0198494240 0.0104930000 17847557 955859216 1373700096 0.1228790134 0.2548476458 1.2668074369 1286 51.4000000000 0.2034907639 0.1850280970 1.1394244432 0.0198417162 0.0060230000 17849533 955859216 1373700096 0.1239703447 0.2548369467 1.2668033838 1287 51.4400000000 0.2032462358 0.1850422525 1.1394244432 0.0198344705 0.0065350000 17851509 955859216 1373700096 0.1248369589 0.2540971041 1.2668939829 1288 51.4800000000 0.2035828382 0.1850566474 1.1394244432 0.0198279005 0.0051950000 17853485 955859216 1373700096 0.1255614907 0.2529505789 1.2672461271 1289 51.5200000000 0.2042328417 0.1850715242 1.1394244432 0.0198203555 0.0049220000 17855461 955859216 1373700096 0.1258045286 0.2555982769 1.2661261559 1290 51.5600000000 0.2043080479 0.1850864362 1.1394244432 0.0198153608 0.0106450000 17857437 955859216 1373700096 0.1282936484 0.2562783957 1.2659525871 1291 51.6000000000 0.2033979595 0.1851006202 1.1394244432 0.0198123445 0.0062710000 17859413 955859216 1373700096 0.1287457645 0.2555541396 1.2661234140 1292 51.6400000000 0.2031603903 0.1851145984 1.1394244432 0.0198083142 0.0048400000 17861389 955859216 1373700096 0.1298063546 0.2556958795 1.2655576468 1293 51.6800000000 0.2041710615 0.1851293365 1.1394244432 0.0198036702 0.0106040000 17863365 955859216 1373700096 0.1302687526 0.2576467097 1.2646394968 1294 51.7200000000 0.2036355883 0.1851436381 1.1394244432 0.0197966431 0.0059600000 17865341 955859216 1373700096 0.1316001266 0.2565731108 1.2647575140 1295 51.7600000000 0.2041224837 0.1851582936 1.1394244432 0.0197923864 0.0046810000 17867317 955859216 1373700096 0.1314893067 0.2563901544 1.2640779018 1296 51.8000000000 0.2044213414 0.1851731571 1.1394244432 0.0197950053 0.0077350000 17869293 955859216 1373700096 0.1325649172 0.2586744428 1.2628381252 1297 51.8400000000 0.2051859051 0.1851885871 1.1394244432 0.0197905334 0.0055250000 17871269 955859216 1373700096 0.1334420145 0.2587980628 1.2626590729 1298 51.8800000000 0.2055598795 0.1852042815 1.1394244432 0.0197854651 0.0048980000 17873245 955859216 1373700096 0.1345987320 0.2619603276 1.2615627050 1299 51.9200000000 0.2058851719 0.1852202021 1.1394244432 0.0197824878 0.0102310000 17875221 955859216 1373700096 0.1359712929 0.2638609409 1.2608801126 1300 51.9600000000 0.2059784085 0.1852361699 1.1394244432 0.0197811711 0.0071770000 17877197 955859216 1373700096 0.1368863583 0.2651876509 1.2604137659 1301 52.0000000000 0.2063353509 0.1852523876 1.1394244432 0.0197786475 0.0052290000 17879173 955859216 1373700096 0.1382403821 0.2672993839 1.2594814301 1302 52.0400000000 0.2025223076 0.1852656518 1.1394244432 0.0197805750 0.0095840000 17881149 955859216 1373700096 0.1406624168 0.2668528855 1.2592266798 1303 52.0800000000 0.2013106048 0.1852779656 1.1394244432 0.0197795944 0.0055380000 17883125 955859216 1373700096 0.1423754841 0.2700481713 1.2578864098 1304 52.1200000000 0.2007922232 0.1852898631 1.1394244432 0.0197768240 0.0047280000 17885101 955859216 1373700096 0.1432077736 0.2710813284 1.2567757368 1305 52.1600000000 0.1990604103 0.1853004152 1.1394244432 0.0197738160 0.0103650000 17887077 955859216 1373700096 0.1444653124 0.2718484998 1.2557387352 1306 52.2000000000 0.2062226087 0.1853164353 1.1394244432 0.0197681733 0.0063270000 17889053 955859216 1373700096 0.1453263909 0.2833344638 1.2518417835 1307 52.2400000000 0.2034860551 0.1853303370 1.1394244432 0.0197608509 0.0047230000 17891029 955859216 1373700096 0.1471821666 0.2837155461 1.2513809204 1308 52.2800000000 0.2015092969 0.1853427063 1.1394244432 0.0197535811 0.0091610000 17893005 955859216 1373700096 0.1486612111 0.2838614881 1.2503620386 1309 52.3200000000 0.2062214017 0.1853586564 1.1394244432 0.0197466982 0.0055970000 17894981 955859216 1373700096 0.1490570456 0.2910277545 1.2473477125 1310 52.3600000000 0.2009476572 0.1853705564 1.1394244432 0.0197430243 0.0083090000 17896957 955859216 1373700096 0.1501385868 0.2880203128 1.2477010489 1311 52.4000000000 0.2067060769 0.1853868306 1.1394244432 0.0197388538 0.0087690000 17898933 955859216 1373700096 0.1498190165 0.2988724113 1.2444778681 1312 52.4400000000 0.2010747045 0.1853987878 1.1394244432 0.0197342638 0.0053830000 17900909 955859216 1373700096 0.1510922611 0.2990490198 1.2435991764 1313 52.4800000000 0.2069295645 0.1854151860 1.1394244432 0.0197280104 0.0045280000 17902885 955859216 1373700096 0.1519380063 0.3103874624 1.2400087118 1314 52.5200000000 0.2072313279 0.1854317888 1.1394244432 0.0197219425 0.0043440000 17904861 955859216 1373700096 0.1534941643 0.3171548843 1.2367494106 1315 52.5600000000 0.2073755264 0.1854484761 1.1394244432 0.0197145910 0.0109660000 17906837 955859216 1373700096 0.1549060345 0.3238961995 1.2338513136 1316 52.6000000000 0.2075192630 0.1854652472 1.1394244432 0.0197071017 0.0070360000 17908813 955859216 1373700096 0.1558598876 0.3300043941 1.2313425541 1317 52.6400000000 0.2076489031 0.1854820913 1.1394244432 0.0197006320 0.0051160000 17910789 955859216 1373700096 0.1571949869 0.3374908566 1.2283095121 1318 52.6800000000 0.2078905553 0.1854990931 1.1394244432 0.0196941730 0.0087090000 17912765 955859216 1373700096 0.1580815017 0.3460297883 1.2253662348 1319 52.7200000000 0.2079971135 0.1855161500 1.1394244432 0.0196872376 0.0056310000 17914741 955859216 1373700096 0.1590820551 0.3541220129 1.2224670649 1320 52.7600000000 0.2081161439 0.1855332712 1.1394244432 0.0196807308 0.0044470000 17916717 955859216 1373700096 0.1596483588 0.3634366095 1.2197275162 1321 52.8000000000 0.2083037496 0.1855505085 1.1394244432 0.0196755679 0.0108490000 17918693 955859216 1373700096 0.1611057818 0.3744712472 1.2160154581 1322 52.8400000000 0.2084777206 0.1855678514 1.1394244432 0.0196683008 0.0066000000 17920669 955859216 1373700096 0.1621562243 0.3836090863 1.2128963470 1323 52.8800000000 0.2085886300 0.1855852518 1.1394244432 0.0196617309 0.0051080000 17922645 955859216 1373700096 0.1632483900 0.3923840821 1.2097636461 1324 52.9200000000 0.2087262571 0.1856027299 1.1394244432 0.0196571800 0.0046630000 17924621 955859216 1373700096 0.1644978970 0.4040964544 1.2058875561 1325 52.9600000000 0.2089303434 0.1856203356 1.1394244432 0.0196516255 0.0108320000 17926597 955859216 1373700096 0.1652577668 0.4152457118 1.2024391890 1326 53.0000000000 0.2089960277 0.1856379644 1.1394244432 0.0196465381 0.0068920000 17928573 955859216 1373700096 0.1663710624 0.4256448448 1.1988565922 1327 53.0400000000 0.2091829032 0.1856557074 1.1394244432 0.0196403014 0.0051110000 17930549 955859216 1373700096 0.1673114449 0.4361055791 1.1953476667 1328 53.0800000000 0.2092606723 0.1856734822 1.1394244432 0.0196360238 0.0047130000 17932525 955859216 1373700096 0.1683589071 0.4483068585 1.1916460991 1329 53.1200000000 0.2094153762 0.1856913467 1.1394244432 0.0196291056 0.0106570000 17934501 955859216 1373700096 0.1684810817 0.4575646222 1.1890292168 1330 53.1600000000 0.2095239162 0.1857092659 1.1394244432 0.0196218001 0.0061190000 17936477 955859216 1373700096 0.1687169671 0.4658551812 1.1861693859 1331 53.2000000000 0.2097316831 0.1857273143 1.1394244432 0.0196189994 0.0047400000 17938453 955859216 1373700096 0.1695054471 0.4784567654 1.1822446585 1332 53.2400000000 0.2100571692 0.1857455799 1.1394244432 0.0196141778 0.0100240000 17940429 955859216 1373700096 0.1705840081 0.4922751486 1.1781870127 1333 53.2800000000 0.2101987600 0.1857639244 1.1394244432 0.0196068665 0.0058480000 17942405 955859216 1373700096 0.1707130820 0.5030289888 1.1746677160 1334 53.3200000000 0.2102515996 0.1857822810 1.1394244432 0.0196003857 0.0052220000 17944381 955859216 1373700096 0.1702983975 0.5136235356 1.1712886095 1335 53.3600000000 0.2103411257 0.1858006771 1.1394244432 0.0195936311 0.0099560000 17946357 955859216 1373700096 0.1701977849 0.5244047642 1.1681028605 1336 53.4000000000 0.2103404552 0.1858190452 1.1394244432 0.0195863803 0.0058340000 17948333 955859216 1373700096 0.1697363704 0.5340955257 1.1654975414 1337 53.4400000000 0.2104821950 0.1858374919 1.1394244432 0.0195790866 0.0051810000 17950309 955859216 1373700096 0.1691084951 0.5420879722 1.1628417969 1338 53.4800000000 0.2106048167 0.1858560026 1.1394244432 0.0195721742 0.0097700000 17952285 955859216 1373700096 0.1693007201 0.5524314046 1.1599717140 1339 53.5200000000 0.2109014243 0.1858747071 1.1394244432 0.0195707386 0.0058440000 17954261 955859216 1373700096 0.1700310707 0.5654791594 1.1566268206 1340 53.5600000000 0.2110729516 0.1858935118 1.1394244432 0.0195725443 0.0051440000 17956237 955859216 1373700096 0.1685102731 0.5853618383 1.1518821716 1341 53.6000000000 0.2111834139 0.1859123708 1.1394244432 0.0195681947 0.0109090000 17958213 955859216 1373700096 0.1682721674 0.5971624851 1.1493269205 1342 53.6400000000 0.2108740509 0.1859309711 1.1394244432 0.0195612120 0.0061230000 17960189 955859216 1373700096 0.1679671407 0.6068434119 1.1475472450 1343 53.6800000000 0.2090866119 0.1859482129 1.1394244432 0.0195545487 0.0047640000 17962165 955859216 1373700096 0.1655572653 0.6110864282 1.1474685669 1344 53.7200000000 0.2107750177 0.1859666852 1.1394244432 0.0195473488 0.0045030000 17964141 955859216 1373700096 0.1650074720 0.6189947128 1.1462984085 1345 53.7600000000 0.2111098468 0.1859853790 1.1394244432 0.0195417427 0.0045160000 17966117 955859216 1373700096 0.1646643132 0.6268392205 1.1457060575 1346 53.8000000000 0.2114182413 0.1860042741 1.1394244432 0.0195363764 0.0045450000 17968093 955859216 1373700096 0.1631296724 0.6322072148 1.1460388899 1347 53.8400000000 0.2115011215 0.1860232028 1.1394244432 0.0195559525 0.0046110000 17970069 955859216 1373700096 0.1624914557 0.6488698125 1.1452757120 1348 53.8800000000 0.2126042992 0.1860429217 1.1394244432 0.0195509835 0.0045020000 17972045 955859216 1373700096 0.1629815400 0.6592219472 1.1448571682 1349 53.9200000000 0.2127356976 0.1860627088 1.1394244432 0.0195439317 0.0045120000 17974021 955859216 1373700096 0.1614816636 0.6648629904 1.1453948021 1350 53.9600000000 0.2129673809 0.1860826381 1.1394244432 0.0195368147 0.0045130000 17975997 955859216 1373700096 0.1612806022 0.6700142026 1.1453416348 1351 54.0000000000 0.2106407732 0.1861008159 1.1394244432 0.0195296529 0.0043070000 17977973 955859216 1373700096 0.1603898555 0.6705282331 1.1461544037 1352 54.0400000000 0.2132476419 0.1861208949 1.1394244432 0.0195227086 0.0113480000 17979949 955859216 1373700096 0.1591180414 0.6758237481 1.1464674473 1353 54.0800000000 0.2137898803 0.1861413450 1.1394244432 0.0195199823 0.0103080000 17981925 955859216 1373700096 0.1586609483 0.6819753051 1.1465704441 1354 54.1200000000 0.2141122371 0.1861620030 1.1394244432 0.0195162819 0.0059970000 17983901 955859216 1373700096 0.1574598998 0.6863468885 1.1469808817 1355 54.1600000000 0.2143319845 0.1861827926 1.1394244432 0.0195132122 0.0048360000 17985877 955859216 1373700096 0.1561568528 0.6901066303 1.1472800970 1356 54.2000000000 0.2145554721 0.1862037164 1.1394244432 0.0195111099 0.0044850000 17987853 955859216 1373700096 0.1549942344 0.6947596669 1.1476938725 1357 54.2400000000 0.2143938839 0.1862244903 1.1394244432 0.0195076157 0.0081320000 17989829 955859216 1373700096 0.1533320695 0.6980477571 1.1480225325 1358 54.2800000000 0.2143677622 0.1862452144 1.1394244432 0.0195015433 0.0086340000 17991805 955859216 1373700096 0.1507619172 0.6994117498 1.1488310099 1359 54.3200000000 0.2151168436 0.1862664591 1.1394244432 0.0194949667 0.0062400000 17993781 955859216 1373700096 0.1474826634 0.7022005320 1.1493748426 1360 54.3600000000 0.2151239067 0.1862876778 1.1394244432 0.0194904686 0.0077670000 17995757 955859216 1373700096 0.1463842690 0.7085968256 1.1496692896 1361 54.4000000000 0.2150857747 0.1863088374 1.1394244432 0.0194834661 0.0052710000 17997733 955859216 1373700096 0.1428970695 0.7103486061 1.1507123709 1362 54.4400000000 0.2148308307 0.1863297786 1.1394244432 0.0194770335 0.0102760000 17999709 955859216 1373700096 0.1398464292 0.7131034136 1.1517579556 1363 54.4800000000 0.2150830179 0.1863508742 1.1394244432 0.0194704097 0.0060010000 18001685 955859216 1373700096 0.1369172782 0.7174252272 1.1526961327 1364 54.5200000000 0.2151441574 0.1863719836 1.1394244432 0.0194636759 0.0047550000 18003661 955859216 1373700096 0.1330475360 0.7193561196 1.1545624733 1365 54.5600000000 0.2149346173 0.1863929086 1.1394244432 0.0194572500 0.0044040000 18005637 955859216 1373700096 0.1283877045 0.7193468213 1.1568968296 1366 54.6000000000 0.2152797282 0.1864140556 1.1394244432 0.0194534946 0.0112740000 18007613 955859216 1373700096 0.1243350208 0.7218717933 1.1590067148 1367 54.6400000000 0.2157313973 0.1864355021 1.1394244432 0.0194550237 0.0068110000 18009589 955859216 1373700096 0.1215093583 0.7281125188 1.1610056162 1368 54.6800000000 0.2158832401 0.1864570282 1.1394244432 0.0194511874 0.0052900000 18011565 955859216 1373700096 0.1167978421 0.7301841378 1.1635658741 1369 54.7200000000 0.2159042656 0.1864785383 1.1394244432 0.0194489268 0.0102380000 18013541 955859216 1373700096 0.1117476374 0.7342376709 1.1661013365 1370 54.7600000000 0.2160807401 0.1865001457 1.1394244432 0.0194466072 0.0060150000 18015517 955859216 1373700096 0.1074937508 0.7406533957 1.1680680513 1371 54.8000000000 0.2162727416 0.1865218617 1.1394244432 0.0194409482 0.0089420000 18017493 955859216 1373700096 0.1020911410 0.7451899052 1.1704694033 1372 54.8400000000 0.2162269950 0.1865435127 1.1394244432 0.0194371121 0.0058440000 18019469 955859216 1373700096 0.0973826498 0.7520952821 1.1725144386 1373 54.8800000000 0.2162132859 0.1865651221 1.1394244432 0.0194327726 0.0046790000 18021445 955859216 1373700096 0.0912916288 0.7571302056 1.1751382351 1374 54.9200000000 0.2159961462 0.1865865421 1.1394244432 0.0194285010 0.0108250000 18023421 955859216 1373700096 0.0839757249 0.7602139115 1.1784222126 1375 54.9600000000 0.2159055769 0.1866078650 1.1394244432 0.0194263604 0.0061840000 18025397 955859216 1373700096 0.0764070973 0.7647882104 1.1814898252 1376 55.0000000000 0.2159737796 0.1866292065 1.1394244432 0.0194255408 0.0049860000 18027373 955859216 1373700096 0.0688272491 0.7698845863 1.1843420267 1377 55.0400000000 0.2160577774 0.1866505780 1.1394244432 0.0194256917 0.0075180000 18029349 955859216 1373700096 0.0608758181 0.7745221853 1.1874091625 1378 55.0800000000 0.2160407603 0.1866719062 1.1394244432 0.0194257627 0.0053450000 18031325 955859216 1373700096 0.0522094294 0.7782806754 1.1911156178 1379 55.1200000000 0.2160371691 0.1866932008 1.1394244432 0.0194251199 0.0103870000 18033301 955859216 1373700096 0.0437830724 0.7824865580 1.1941543818 1380 55.1600000000 0.2160634547 0.1867144836 1.1394244432 0.0194294197 0.0060790000 18035277 955859216 1373700096 0.0362826101 0.7879031301 1.1964617968 1381 55.2000000000 0.2161571383 0.1867358034 1.1394244432 0.0194331340 0.0049260000 18037253 955859216 1373700096 0.0281261541 0.7921637893 1.1995649338 1382 55.2400000000 0.2161200643 0.1867570655 1.1394244432 0.0194368047 0.0105680000 18039229 955859216 1373700096 0.0190257747 0.7955473065 1.2031697035 1383 55.2800000000 0.2160642445 0.1867782565 1.1394244432 0.0194439611 0.0060680000 18041205 955859216 1373700096 0.0121752778 0.8009706736 1.2053020000 1384 55.3200000000 0.2161940038 0.1867995107 1.1394244432 0.0194486215 0.0048510000 18043181 955859216 1373700096 0.0040123253 0.8051917553 1.2080413103 1385 55.3600000000 0.2160039246 0.1868205969 1.1394244432 0.0194548008 0.0045430000 18045157 955859216 1373700096 -0.0032497370 0.8093595505 1.2107156515 1386 55.4000000000 0.2157613486 0.1868414777 1.1394244432 0.0194594455 0.0114180000 18047133 955859216 1373700096 -0.0099820280 0.8132652640 1.2128272057 1387 55.4400000000 0.2155282497 0.1868621603 1.1394244432 0.0194648866 0.0065000000 18049109 955859216 1373700096 -0.0177114587 0.8154495358 1.2159324884 1388 55.4800000000 0.2152298540 0.1868825981 1.1394244432 0.0194686231 0.0051350000 18051085 955859216 1373700096 -0.0252823066 0.8167905807 1.2193365097 1389 55.5200000000 0.2150418609 0.1869028711 1.1394244432 0.0194715637 0.0083120000 18053061 955859216 1373700096 -0.0313425325 0.8191412091 1.2222080231 1390 55.5600000000 0.2152221948 0.1869232448 1.1394244432 0.0194771974 0.0056010000 18055037 955859216 1373700096 -0.0373314582 0.8223461509 1.2251117229 1391 55.6000000000 0.2152532041 0.1869436114 1.1394244432 0.0194783931 0.0049940000 18057013 955859216 1373700096 -0.0419427380 0.8263682127 1.2276754379 1392 55.6400000000 0.2152894139 0.1869639747 1.1394244432 0.0194757495 0.0046190000 18058989 955859216 1373700096 -0.0473184809 0.8290370703 1.2311164141 1393 55.6800000000 0.2152202725 0.1869842592 1.1394244432 0.0194718832 0.0045440000 18060965 955859216 1373700096 -0.0517577417 0.8317573071 1.2343928814 1394 55.7200000000 0.2153459638 0.1870046048 1.1394244432 0.0194681170 0.0114550000 18062941 955859216 1373700096 -0.0560062155 0.8336676955 1.2375084162 1395 55.7600000000 0.2153700143 0.1870249384 1.1394244432 0.0194655624 0.0071910000 18064917 955859216 1373700096 -0.0589157343 0.8353423476 1.2408437729 1396 55.8000000000 0.2154597193 0.1870453072 1.1394244432 0.0194694204 0.0052840000 18066893 955859216 1373700096 -0.0603367537 0.8395562172 1.2436212301 1397 55.8400000000 0.2155708820 0.1870657263 1.1394244432 0.0194737660 0.0049420000 18068869 955859216 1373700096 -0.0639775842 0.8416959047 1.2485903502 1398 55.8800000000 0.2154169530 0.1870860062 1.1394244432 0.0194760800 0.0103260000 18070845 955859216 1373700096 -0.0672523901 0.8435783982 1.2541908026 1399 55.9200000000 0.2154618502 0.1871062891 1.1394244432 0.0194782896 0.0059640000 18072821 955859216 1373700096 -0.0692186803 0.8470235467 1.2591855526 1400 55.9600000000 0.2149956822 0.1871262101 1.1394244432 0.0194774976 0.0048670000 18074797 955859216 1373700096 -0.0699959621 0.8511161804 1.2628294230 1401 56.0000000000 0.2154162228 0.1871464028 1.1394244432 0.0194732029 0.0048000000 18076773 955859216 1373700096 -0.0722223520 0.8547856212 1.2680773735 1402 56.0400000000 0.2152255774 0.1871664308 1.1394244432 0.0194700148 0.0116450000 18078749 955859216 1373700096 -0.0749998689 0.8568267822 1.2739185095 1403 56.0800000000 0.2152219415 0.1871864276 1.1394244432 0.0194692240 0.0069350000 18080725 955859216 1373700096 -0.0767999440 0.8591487408 1.2790713310 1404 56.1200000000 0.2153319567 0.1872064743 1.1394244432 0.0194712402 0.0053050000 18082701 955859216 1373700096 -0.0774863809 0.8638880849 1.2840644121 1405 56.1600000000 0.2154213786 0.1872265560 1.1394244432 0.0194715662 0.0045740000 18084677 955859216 1373700096 -0.0785449594 0.8675442934 1.2895005941 1406 56.2000000000 0.2157409340 0.1872468365 1.1394244432 0.0195060897 0.0101790000 18086653 955859216 1373700096 -0.0801339149 0.8778491616 1.3025907278 1407 56.2400000000 0.2157344818 0.1872670836 1.1394244432 0.0195058260 0.0059930000 18088629 955859216 1373700096 -0.0801687762 0.8841143847 1.3092753887 1408 56.2800000000 0.2156001627 0.1872872066 1.1394244432 0.0195034231 0.0049460000 18090605 955859216 1373700096 -0.0822979510 0.8874665499 1.3176479340 1409 56.3200000000 0.2156397700 0.1873073290 1.1394244432 0.0195044648 0.0102700000 18092581 955859216 1373700096 -0.0835879222 0.8903611302 1.3254519701 1410 56.3600000000 0.2157014310 0.1873274667 1.1394244432 0.0195166864 0.0061150000 18094557 955859216 1373700096 -0.0836952329 0.8973707557 1.3324064016 1411 56.4000000000 0.2157119513 0.1873475833 1.1394244432 0.0195217279 0.0048790000 18096533 955859216 1373700096 -0.0848076493 0.9024437070 1.3404173851 1412 56.4400000000 0.2156820893 0.1873676502 1.1394244432 0.0195244355 0.0045280000 18098509 955859216 1373700096 -0.0873851553 0.9048534036 1.3491088152 1413 56.4800000000 0.2156466842 0.1873876637 1.1394244432 0.0195289173 0.0116530000 18100485 955859216 1373700096 -0.0882622749 0.9111019969 1.3571598530 1414 56.5200000000 0.2158581167 0.1874077983 1.1394244432 0.0195296065 0.0068830000 18102461 955859216 1373700096 -0.0883228704 0.9186514020 1.3642994165 1415 56.5600000000 0.2158463895 0.1874278963 1.1394244432 0.0195267062 0.0052460000 18104437 955859216 1373700096 -0.0893209875 0.9240499139 1.3717015982 1416 56.6000000000 0.2159163952 0.1874480153 1.1394244432 0.0195260869 0.0075100000 18106413 955859216 1373700096 -0.0895562023 0.9309342504 1.3776519299 1417 56.6400000000 0.2159495950 0.1874681293 1.1394244432 0.0195253841 0.0053600000 18108389 955859216 1373700096 -0.0901527554 0.9368023872 1.3832565546 1418 56.6800000000 0.2158257663 0.1874881277 1.1394244432 0.0195251520 0.0049050000 18110365 955859216 1373700096 -0.0909390524 0.9417747259 1.3892744780 1419 56.7200000000 0.2157633454 0.1875080538 1.1394244432 0.0195276805 0.0048880000 18112341 955859216 1373700096 -0.0920621902 0.9462139010 1.3952969313 1420 56.7600000000 0.2156863809 0.1875278977 1.1394244432 0.0195301490 0.0049770000 18114317 955859216 1373700096 -0.0927455798 0.9514964819 1.4008412361 1421 56.8000000000 0.2156466544 0.1875476857 1.1394244432 0.0195307063 0.0048890000 18116293 955859216 1373700096 -0.0942075104 0.9553727508 1.4065219164 1422 56.8400000000 0.2155623138 0.1875673866 1.1394244432 0.0195326143 0.0049330000 18118269 955859216 1373700096 -0.0951769948 0.9597502351 1.4116135836 1423 56.8800000000 0.2156209499 0.1875871010 1.1394244432 0.0195334206 0.0049130000 18120245 955859216 1373700096 -0.0950399637 0.9652715921 1.4159231186 1424 56.9200000000 0.2156564891 0.1876068126 1.1394244432 0.0195304673 0.0049390000 18122221 955859216 1373700096 -0.0955378637 0.9707229733 1.4211566448 1425 56.9600000000 0.2154889703 0.1876263790 1.1394244432 0.0195255151 0.0049300000 18124197 955859216 1373700096 -0.0982482061 0.9721443653 1.4279400110 1426 57.0000000000 0.2154190540 0.1876458690 1.1394244432 0.0195234661 0.0049490000 18126173 955859216 1373700096 -0.0988546312 0.9760280252 1.4331170321 1427 57.0400000000 0.2156196684 0.1876654722 1.1394244432 0.0195219698 0.0049260000 18128149 955859216 1373700096 -0.0996984169 0.9814999700 1.4387758970 1428 57.0800000000 0.2156905830 0.1876850976 1.1394244432 0.0195196200 0.0119210000 18130125 955859216 1373700096 -0.1010623351 0.9856518507 1.4458742142 1429 57.1200000000 0.2158308774 0.1877047938 1.1394244432 0.0195169979 0.0081800000 18132101 955859216 1373700096 -0.1021149457 0.9903661609 1.4516835213 1430 57.1600000000 0.2157362550 0.1877243962 1.1394244432 0.0195143778 0.0057100000 18134077 955859216 1373700096 -0.1030260250 0.9950332642 1.4582513571 1431 57.2000000000 0.2158239037 0.1877440325 1.1394244432 0.0195130594 0.0048820000 18136053 955859216 1373700096 -0.1054655388 0.9983151555 1.4658614397 1432 57.2400000000 0.2159172595 0.1877637065 1.1394244432 0.0195123569 0.0042830000 18138029 955859216 1373700096 -0.1073736772 1.0020833015 1.4722672701 1433 57.2800000000 0.2160275578 0.1877834301 1.1394244432 0.0195110161 0.0109350000 18140005 955859216 1373700096 -0.1088024154 1.0068873167 1.4788848162 1434 57.3200000000 0.2161233276 0.1878031929 1.1394244432 0.0195127146 0.0062520000 18141981 955859216 1373700096 -0.1110166907 1.0108753443 1.4864168167 1435 57.3600000000 0.2161249667 0.1878229293 1.1394244432 0.0195170733 0.0050260000 18143957 955859216 1373700096 -0.1132600605 1.0148508549 1.4933990240 1436 57.4000000000 0.2163651884 0.1878428055 1.1394244432 0.0195220205 0.0046800000 18145933 955859216 1373700096 -0.1149944067 1.0194712877 1.5001957417 1437 57.4400000000 0.2164167911 0.1878626900 1.1394244432 0.0195298468 0.0118710000 18147909 955859216 1373700096 -0.1174178347 1.0241184235 1.5092005730 1438 57.4800000000 0.2164266258 0.1878825537 1.1394244432 0.0195371649 0.0066340000 18149885 955859216 1373700096 -0.1178683713 1.0309027433 1.5158830881 1439 57.5200000000 0.2166965306 0.1879025773 1.1394244432 0.0195423402 0.0052650000 18151861 955859216 1373700096 -0.1185029522 1.0391079187 1.5223408937 1440 57.5600000000 0.2168829888 0.1879227026 1.1394244432 0.0195432615 0.0072310000 18153837 955859216 1373700096 -0.1198206469 1.0444142818 1.5294723511 1441 57.6000000000 0.2169666886 0.1879428580 1.1394244432 0.0195456011 0.0074160000 18155813 955859216 1373700096 -0.1212613583 1.0487674475 1.5365393162 1442 57.6400000000 0.2169512063 0.1879629747 1.1394244432 0.0195442017 0.0055560000 18157789 955859216 1373700096 -0.1210108846 1.0549008846 1.5416463614 1443 57.6800000000 0.2171002477 0.1879831669 1.1394244432 0.0195402110 0.0050800000 18159765 955859216 1373700096 -0.1218242124 1.0599415302 1.5482985973 1444 57.7200000000 0.2171907276 0.1880033937 1.1394244432 0.0195354537 0.0050900000 18161741 955859216 1373700096 -0.1230176091 1.0621154308 1.5541901588 1445 57.7600000000 0.2172400504 0.1880236267 1.1394244432 0.0195333584 0.0117870000 18163717 955859216 1373700096 -0.1235627010 1.0663806200 1.5606966019 1446 57.8000000000 0.2172627300 0.1880438474 1.1394244432 0.0195290695 0.0076570000 18165693 955859216 1373700096 -0.1231271327 1.0724247694 1.5655026436 1447 57.8400000000 0.2174706608 0.1880641838 1.1394244432 0.0195229673 0.0056210000 18167669 955859216 1373700096 -0.1240300983 1.0745767355 1.5710278749 1448 57.8800000000 0.2175229937 0.1880845283 1.1394244432 0.0195187750 0.0047940000 18169645 955859216 1373700096 -0.1247933581 1.0764555931 1.5766470432 1449 57.9200000000 0.2175842971 0.1881048870 1.1394244432 0.0195154327 0.0109350000 18171621 955859216 1373700096 -0.1246910468 1.0800774097 1.5813901424 1450 57.9600000000 0.2176740468 0.1881252795 1.1394244432 0.0195112993 0.0066620000 18173597 955859216 1373700096 -0.1247444153 1.0837081671 1.5861312151 1451 58.0000000000 0.2177980393 0.1881457294 1.1394244432 0.0195060228 0.0052050000 18175573 955859216 1373700096 -0.1250654161 1.0865558386 1.5909790993 1452 58.0400000000 0.2179218233 0.1881662364 1.1394244432 0.0195013249 0.0043860000 18177549 955859216 1373700096 -0.1243991479 1.0900574923 1.5964686871 1453 58.0800000000 0.2180438936 0.1881867991 1.1394244432 0.0194962825 0.0042660000 18179525 955859216 1373700096 -0.1236534268 1.0934089422 1.6020804644 1454 58.1200000000 0.2178840637 0.1882072236 1.1394244432 0.0194902174 0.0118430000 18181501 955859216 1373700096 -0.1224497408 1.0945401192 1.6068531275 1455 58.1600000000 0.2174148262 0.1882272976 1.1394244432 0.0194845789 0.0072610000 18183477 955859216 1373700096 -0.1214515343 1.0954811573 1.6114041805 1456 58.2000000000 0.2171487063 0.1882471612 1.1394244432 0.0194794607 0.0120320000 18185453 955859216 1373700096 -0.1193315312 1.0963258743 1.6148447990 1457 58.2400000000 0.2182509303 0.1882677540 1.1394244432 0.0194751225 0.0120500000 18187429 955859216 1373700096 -0.1166950986 1.1002190113 1.6181831360 1458 58.2800000000 0.2183151841 0.1882883627 1.1394244432 0.0194696127 0.0070540000 18189405 955859216 1373700096 -0.1136733219 1.1035411358 1.6222779751 1459 58.3200000000 0.2178493142 0.1883086238 1.1394244432 0.0194633430 0.0052920000 18191381 955859216 1373700096 -0.1107297391 1.1045885086 1.6258707047 1460 58.3600000000 0.2177713215 0.1883288037 1.1394244432 0.0194566791 0.0079540000 18193357 955859216 1373700096 -0.1072692722 1.1053475142 1.6288685799 1461 58.4000000000 0.2175017893 0.1883487715 1.1394244432 0.0194500290 0.0054760000 18195333 955859216 1373700096 -0.1032653004 1.1069815159 1.6327041388 1462 58.4400000000 0.2173053473 0.1883685777 1.1394244432 0.0194434494 0.0047520000 18197309 955859216 1373700096 -0.0987490937 1.1081074476 1.6370741129 1463 58.4800000000 0.2134183347 0.1883856999 1.1394244432 0.0194370711 0.0116340000 18199285 955859216 1373700096 -0.0947181880 1.1059769392 1.6421912909 1464 58.5200000000 0.2116110325 0.1884015642 1.1394244432 0.0194304827 0.0063590000 18201261 955859216 1373700096 -0.0897830129 1.1057971716 1.6463460922 1465 58.5600000000 0.2101612389 0.1884164172 1.1394244432 0.0194238932 0.0048970000 18203237 955859216 1373700096 -0.0846728310 1.1056913137 1.6507015228 1466 58.6000000000 0.2179931551 0.1884365923 1.1394244432 0.0194176285 0.0081240000 18205213 955859216 1373700096 -0.0781575367 1.1141318083 1.6501456499 1467 58.6400000000 0.2170504630 0.1884560973 1.1394244432 0.0194110395 0.0055500000 18207189 955859216 1373700096 -0.0726406053 1.1152225733 1.6542080641 1468 58.6800000000 0.2139372826 0.1884734551 1.1394244432 0.0194046284 0.0075860000 18209165 955859216 1373700096 -0.0677577108 1.1133279800 1.6590341330 1469 58.7200000000 0.2182121724 0.1884936993 1.1394244432 0.0193981260 0.0053220000 18211141 955859216 1373700096 -0.0615049340 1.1187419891 1.6592739820 1470 58.7600000000 0.2183216065 0.1885139904 1.1394244432 0.0193925186 0.0047740000 18213117 955859216 1373700096 -0.0550975166 1.1222977638 1.6609585285 1471 58.8000000000 0.2168308198 0.1885332404 1.1394244432 0.0193859919 0.0114340000 18215093 955859216 1373700096 -0.0496746674 1.1236922741 1.6641068459 1472 58.8400000000 0.2184429616 0.1885535595 1.1394244432 0.0193797518 0.0074520000 18217069 955859216 1373700096 -0.0438669920 1.1278008223 1.6665985584 1473 58.8800000000 0.2185412794 0.1885739178 1.1394244432 0.0193736164 0.0052630000 18219045 955859216 1373700096 -0.0380599275 1.1306028366 1.6683712006 1474 58.9200000000 0.2185813785 0.1885942756 1.1394244432 0.0193679436 0.0049180000 18221021 955859216 1373700096 -0.0323244520 1.1330214739 1.6690455675 1475 58.9600000000 0.2185897529 0.1886146116 1.1394244432 0.0193616922 0.0106320000 18222997 955859216 1373700096 -0.0264383312 1.1355713606 1.6695661545 1476 59.0000000000 0.2186509371 0.1886349614 1.1394244432 0.0193551656 0.0059700000 18224973 955859216 1373700096 -0.0210042801 1.1389554739 1.6699901819 1477 59.0400000000 0.2174383253 0.1886544626 1.1394244432 0.0193486463 0.0045880000 18226949 955859216 1373700096 -0.0161559526 1.1403243542 1.6719578505 1478 59.0800000000 0.2144980580 0.1886719482 1.1394244432 0.0193421234 0.0041590000 18228925 955859216 1373700096 -0.0113472547 1.1401832104 1.6755135059 1479 59.1200000000 0.2099761665 0.1886863526 1.1394244432 0.0193362321 0.0114450000 18230901 955859216 1373700096 -0.0025482692 1.1409620047 1.6790295839 1480 59.1600000000 0.2058427036 0.1886979448 1.1394244432 0.0193302065 0.0067690000 18232877 955859216 1373700096 0.0014386172 1.1399142742 1.6826232672 1481 59.2000000000 0.2034524381 0.1887079073 1.1394244432 0.0193238315 0.0050510000 18234853 955859216 1373700096 0.0048565543 1.1390696764 1.6849111319 1482 59.2400000000 0.2005690038 0.1887159107 1.1394244432 0.0193175049 0.0041730000 18236829 955859216 1373700096 0.0082091102 1.1388853788 1.6873859167 1483 59.2800000000 0.1997623593 0.1887233594 1.1394244432 0.0193111685 0.0103180000 18238805 955859216 1373700096 0.0114902463 1.1408447027 1.6881599426 1484 59.3200000000 0.1998341680 0.1887308465 1.1394244432 0.0193051144 0.0057690000 18240781 955859216 1373700096 0.0147483870 1.1431065798 1.6883920431 1485 59.3600000000 0.2002725750 0.1887386187 1.1394244432 0.0192993774 0.0050100000 18242757 955859216 1373700096 0.0180237591 1.1451086998 1.6881160736 1486 59.4000000000 0.2006576806 0.1887466396 1.1394244432 0.0192930412 0.0049590000 18244733 955859216 1373700096 0.0206172764 1.1469684839 1.6875636578 1487 59.4400000000 0.1990071684 0.1887535398 1.1394244432 0.0192866366 0.0115080000 18246709 955859216 1373700096 0.0230339617 1.1470453739 1.6880087852 1488 59.4800000000 0.2141874880 0.1887706325 1.1394244432 0.0192813194 0.0067740000 18248685 955859216 1373700096 0.0252533183 1.1647570133 1.6783270836 1489 59.5200000000 0.2119740248 0.1887862157 1.1394244432 0.0192749102 0.0049460000 18250661 955859216 1373700096 0.0276889484 1.1641607285 1.6789163351 1490 59.5600000000 0.2117584646 0.1888016333 1.1394244432 0.0192688366 0.0039950000 18252637 955859216 1373700096 0.0302153546 1.1665542126 1.6775597334 1491 59.6000000000 0.2086096406 0.1888149184 1.1394244432 0.0192632299 0.0038030000 18254613 955859216 1373700096 0.0323915705 1.1657168865 1.6758965254 1492 59.6400000000 0.2057612985 0.1888262765 1.1394244432 0.0192570588 0.0038470000 18256589 955859216 1373700096 0.0343863443 1.1646814346 1.6769070625 1493 59.6800000000 0.2044666260 0.1888367523 1.1394244432 0.0192506287 0.0038630000 18258565 955859216 1373700096 0.0370899960 1.1670417786 1.6772804260 1494 59.7200000000 0.2037829012 0.1888467564 1.1394244432 0.0192441827 0.0038330000 18260541 955859216 1373700096 0.0393473990 1.1682155132 1.6776025295 1495 59.7600000000 0.2039779127 0.1888568776 1.1394244432 0.0192385299 0.0038110000 18262517 955859216 1373700096 0.0413397402 1.1700674295 1.6758277416 1496 59.8000000000 0.2124687284 0.1888726609 1.1394244432 0.0192329788 0.0040020000 18264493 955859216 1373700096 0.0429793783 1.1803816557 1.6808891296 1497 59.8400000000 0.2107815892 0.1888872961 1.1394244432 0.0192283612 0.0038250000 18266469 955859216 1373700096 0.0448819213 1.1809743643 1.6787650585 1498 59.8800000000 0.2097879946 0.1889012485 1.1394244432 0.0192221485 0.0115970000 18268445 955859216 1373700096 0.0467832685 1.1832424402 1.6783297062 1499 59.9200000000 0.2086017281 0.1889143910 1.1394244432 0.0192157907 0.0108710000 18270421 955859216 1373700096 0.0482843108 1.1838743687 1.6796098948 1500 59.9600000000 0.2091703266 0.1889278949 1.1394244432 0.0192095602 0.0058590000 18272397 955859216 1373700096 0.0498100966 1.1852260828 1.6787184477 1501 60.0000000000 0.2090789527 0.1889413200 1.1394244432 0.0192033995 0.0045660000 18274373 955859216 1373700096 0.0511643812 1.1860510111 1.6774950027 1502 60.0400000000 0.2073433995 0.1889535717 1.1394244432 0.0191971748 0.0038550000 18276349 955859216 1373700096 0.0521901362 1.1851955652 1.6771600246 1503 60.0800000000 0.2121361941 0.1889689959 1.1394244432 0.0191909722 0.0110140000 18278325 955859216 1373700096 0.0533816442 1.1906573772 1.6825765371 1504 60.1200000000 0.2101313919 0.1889830667 1.1394244432 0.0191849063 0.0059170000 18280301 955859216 1373700096 0.0545507893 1.1897659302 1.6815037727 1505 60.1600000000 0.2120565772 0.1889983979 1.1394244432 0.0191787428 0.0045970000 18282277 955859216 1373700096 0.0561533459 1.1921968460 1.6820269823 1506 60.2000000000 0.2119830400 0.1890136600 1.1394244432 0.0191727585 0.0041640000 18284253 955859216 1373700096 0.0577885732 1.1928489208 1.6830837727 1507 60.2400000000 0.2120478451 0.1890289448 1.1394244432 0.0191666870 0.0119120000 18286229 955859216 1373700096 0.0592547767 1.1921072006 1.6832495928 1508 60.2800000000 0.2120462060 0.1890442082 1.1394244432 0.0191609362 0.0066450000 18288205 955859216 1373700096 0.0605925284 1.1922577620 1.6851490736 1509 60.3200000000 0.2120988965 0.1890594863 1.1394244432 0.0191548388 0.0049350000 18290181 955859216 1373700096 0.0623562820 1.1925277710 1.6867672205 1510 60.3600000000 0.2082904130 0.1890722220 1.1394244432 0.0191486580 0.0042660000 18292157 955859216 1373700096 0.0635598302 1.1879384518 1.6875212193 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:32:23 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0090690000 14162629 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0003050633 0.0001525316 0.0003050633 0.0020315323 0.0074700000 14359525 955859216 1373700096 0.0002619608 0.0005516480 0.0001832035 3 0.0800000000 0.0004748883 0.0002599839 0.0004748883 0.0017163088 0.0028700000 14361893 955859216 1373700096 0.0003212068 -0.0019857222 -0.0006929564 4 0.1200000000 0.0004439864 0.0003059845 0.0004748883 0.0014698945 0.0023460000 14364269 955859216 1373700096 0.0004856430 -0.0013268768 -0.0006143571 5 0.1600000000 0.0006838936 0.0003815663 0.0006838936 0.0014612923 0.0023400000 14366629 955859216 1373700096 0.0005465168 -0.0009052575 -0.0004290863 6 0.2000000000 0.0006669702 0.0004291336 0.0006838936 0.0016053354 0.0023610000 14369405 955859216 1373700096 0.0006299071 -0.0019287933 -0.0007420345 7 0.2400000000 0.0007888088 0.0004805158 0.0007888088 0.0015968328 0.0023840000 14371381 955859216 1373700096 0.0006585903 -0.0021325373 -0.0008136611 8 0.2800000000 0.0007740030 0.0005172017 0.0007888088 0.0016056769 0.0023050000 14373357 955859216 1373700096 0.0005141209 -0.0008804891 -0.0003782676 9 0.3200000000 0.0007878093 0.0005472692 0.0007888088 0.0015105485 0.0023210000 14376101 955859216 1373700096 0.0007080120 -0.0008119796 -0.0003083680 10 0.3600000000 0.0007743652 0.0005699788 0.0007888088 0.0014510303 0.0023670000 14379677 955859216 1373700096 0.0007113052 -0.0014935723 -0.0004733496 11 0.4000000000 0.0007976918 0.0005906800 0.0007976918 0.0013867927 0.0023060000 14381653 955859216 1373700096 0.0006064696 -0.0008676047 -0.0003008844 12 0.4400000000 0.0008266582 0.0006103448 0.0008266582 0.0013384476 0.0023750000 14383629 955859216 1373700096 0.0006546609 -0.0000610024 -0.0000063398 13 0.4800000000 0.0007925353 0.0006243595 0.0008266582 0.0013112498 0.0023510000 14385605 955859216 1373700096 0.0005720424 0.0004239220 0.0003150212 14 0.5200000000 0.0007897267 0.0006361714 0.0008266582 0.0014137914 0.0023410000 14387581 955859216 1373700096 0.0007216735 0.0005150037 0.0004010027 15 0.5600000000 0.0008403139 0.0006497809 0.0008403139 0.0015024944 0.0023370000 14389557 955859216 1373700096 0.0007697612 0.0005963069 0.0004762298 16 0.6000000000 0.0008241984 0.0006606820 0.0008403139 0.0014872140 0.0023600000 14391533 955859216 1373700096 0.0010692535 0.0005464273 0.0004203228 17 0.6400000000 0.0008886156 0.0006740899 0.0008886156 0.0014522469 0.0023760000 14395045 955859216 1373700096 0.0010333804 0.0003855833 0.0004585747 18 0.6800000000 0.0009091636 0.0006871495 0.0009091636 0.0014270214 0.0023600000 14400221 955859216 1373700096 0.0010235490 -0.0002611794 0.0002172627 19 0.7200000000 0.0008481625 0.0006956239 0.0009091636 0.0015637537 0.0023850000 14402197 955859216 1373700096 0.0008863842 -0.0001904893 0.0001458354 20 0.7600000000 0.0008298197 0.0007023337 0.0009091636 0.0017808264 0.0023640000 14404173 955859216 1373700096 0.0006770461 -0.0004253383 0.0000469853 21 0.8000000000 0.0009684882 0.0007150077 0.0009684882 0.0019814379 0.0023830000 14406149 955859216 1373700096 0.0007440408 -0.0005242454 -0.0000897974 22 0.8400000000 0.0008496051 0.0007211258 0.0009684882 0.0020028212 0.0024210000 14408125 955859216 1373700096 0.0007172120 -0.0003753503 0.0000067878 23 0.8800000000 0.0009351260 0.0007304301 0.0009684882 0.0020128143 0.0024000000 14410101 955859216 1373700096 0.0004900744 -0.0005070937 -0.0000563234 24 0.9200000000 0.0010024005 0.0007417622 0.0010024005 0.0019781665 0.0025040000 14412077 955859216 1373700096 0.0005681364 -0.0003332816 -0.0000480407 25 0.9600000000 0.0009950039 0.0007518919 0.0010024005 0.0019389358 0.0023870000 14414053 955859216 1373700096 0.0002752288 -0.0003099053 -0.0000487368 26 1.0000000000 0.0009934631 0.0007611831 0.0010024005 0.0019018184 0.0017830000 14416029 955859216 1373700096 0.0004295848 -0.0000548638 -0.0000013168 27 1.0400000000 0.0009614353 0.0007685998 0.0010024005 0.0018723066 0.0024440000 14418005 955859216 1373700096 0.0001242272 -0.0000719673 -0.0000267680 28 1.0800000000 0.0009514033 0.0007751285 0.0010024005 0.0018665677 0.0024640000 14419981 955859216 1373700096 0.0000055341 -0.0001904728 0.0000085748 29 1.1200000000 0.0009481850 0.0007810960 0.0010024005 0.0018439242 0.0024230000 14421957 955859216 1373700096 -0.0003452076 0.0000587767 0.0001155622 30 1.1600000000 0.0009206907 0.0007857492 0.0010024005 0.0018336587 0.0024320000 14423933 955859216 1373700096 -0.0001613152 0.0004643321 0.0000890353 31 1.2000000000 0.0009738304 0.0007918163 0.0010024005 0.0018274029 0.0024170000 14425909 955859216 1373700096 -0.0003270073 0.0002658024 0.0000664109 32 1.2400000000 0.0009914871 0.0007980560 0.0010024005 0.0018046301 0.0024620000 14427885 955859216 1373700096 -0.0005381849 -0.0001556159 0.0000326088 33 1.2800000000 0.0009953233 0.0008040338 0.0010024005 0.0018211431 0.0025280000 14432933 955859216 1373700096 -0.0007755029 -0.0000135388 0.0001892069 34 1.3200000000 0.0009915895 0.0008095501 0.0010024005 0.0018251511 0.0025990000 14441309 955859216 1373700096 -0.0012345016 -0.0003276272 0.0002600429 35 1.3600000000 0.0010050664 0.0008151363 0.0010050664 0.0018164806 0.0025670000 14443285 955859216 1373700096 -0.0015791828 -0.0011234981 0.0000282154 36 1.4000000000 0.0010810238 0.0008225221 0.0010810238 0.0018000871 0.0025820000 14445261 955859216 1373700096 -0.0018411112 -0.0013059032 0.0000055182 37 1.4400000000 0.0009869747 0.0008269668 0.0010810238 0.0017763439 0.0025090000 14447237 955859216 1373700096 -0.0020513211 -0.0008782480 0.0002442605 38 1.4800000000 0.0010664460 0.0008332688 0.0010810238 0.0017523769 0.0025470000 14449213 955859216 1373700096 -0.0022138709 -0.0013156314 0.0002747284 39 1.5200000000 0.0010845358 0.0008397116 0.0010845358 0.0017435814 0.0025280000 14451189 955859216 1373700096 -0.0027727233 -0.0028593554 -0.0000492933 40 1.5600000000 0.0010333704 0.0008445531 0.0010845358 0.0018678932 0.0025600000 14453165 955859216 1373700096 -0.0030626461 -0.0024868893 0.0003497851 41 1.6000000000 0.0010492762 0.0008495463 0.0010845358 0.0020486270 0.0025190000 14455141 955859216 1373700096 -0.0034090660 -0.0012668831 0.0010600419 42 1.6400000000 0.0010956706 0.0008554064 0.0010956706 0.0021351913 0.0025720000 14457117 955859216 1373700096 -0.0039401720 -0.0015385543 0.0014201589 43 1.6800000000 0.0010741890 0.0008604944 0.0010956706 0.0021582674 0.0024480000 14459093 955859216 1373700096 -0.0041752504 -0.0016676775 0.0019552673 44 1.7200000000 0.0010856455 0.0008656114 0.0010956706 0.0021455741 0.0025020000 14461069 955859216 1373700096 -0.0046047946 -0.0013047138 0.0026023665 45 1.7600000000 0.0011126522 0.0008711012 0.0011126522 0.0021511430 0.0025560000 14463045 955859216 1373700096 -0.0048951535 -0.0017606318 0.0031577260 46 1.8000000000 0.0010759536 0.0008755545 0.0011126522 0.0022882886 0.0024960000 14465021 955859216 1373700096 -0.0052150134 -0.0028832681 0.0037045530 47 1.8400000000 0.0010864261 0.0008800412 0.0011126522 0.0024662577 0.0025070000 14466997 955859216 1373700096 -0.0052514174 -0.0032804199 0.0045963433 48 1.8800000000 0.0010855355 0.0008843223 0.0011126522 0.0026823369 0.0025250000 14468973 955859216 1373700096 -0.0055692992 -0.0033756148 0.0060326122 49 1.9200000000 0.0011125295 0.0008889796 0.0011126522 0.0030011357 0.0025490000 14470949 955859216 1373700096 -0.0055176644 -0.0047511472 0.0070748557 50 1.9600000000 0.0010804888 0.0008928098 0.0011126522 0.0032997619 0.0025870000 14472925 955859216 1373700096 -0.0055077579 -0.0053151031 0.0085827047 51 2.0000000000 0.0010813159 0.0008965060 0.0011126522 0.0034948857 0.0025950000 14474901 955859216 1373700096 -0.0054239985 -0.0051646996 0.0104807513 52 2.0400000000 0.0010942479 0.0009003087 0.0011126522 0.0036493678 0.0025800000 14476877 955859216 1373700096 -0.0048506162 -0.0052830703 0.0124025345 53 2.0800000000 0.0011044944 0.0009041613 0.0011126522 0.0037191130 0.0025850000 14478853 955859216 1373700096 -0.0044636284 -0.0064963750 0.0140536567 54 2.1200000000 0.0010739167 0.0009073049 0.0011126522 0.0037950955 0.0027120000 14480829 955859216 1373700096 -0.0035279894 -0.0072173728 0.0158400480 55 2.1600000000 0.0010645383 0.0009101637 0.0011126522 0.0037997105 0.0028060000 14482805 955859216 1373700096 -0.0031655589 -0.0069879778 0.0183330197 56 2.2000000000 0.0010777945 0.0009131571 0.0011126522 0.0037839650 0.0026370000 14484781 955859216 1373700096 -0.0026601995 -0.0067121163 0.0208453070 57 2.2400000000 0.0010531154 0.0009156125 0.0011126522 0.0038055826 0.0025910000 14486757 955859216 1373700096 -0.0015388620 -0.0068537062 0.0232614204 58 2.2800000000 0.0010791795 0.0009184326 0.0011126522 0.0038656019 0.0025950000 14488733 955859216 1373700096 -0.0008425803 -0.0058215959 0.0261068754 59 2.3200000000 0.0010768606 0.0009211178 0.0011126522 0.0039768810 0.0026920000 14490709 955859216 1373700096 0.0004174538 -0.0060572783 0.0287535749 60 2.3600000000 0.0010991087 0.0009240843 0.0011126522 0.0042840697 0.0026770000 14492685 955859216 1373700096 0.0013451625 -0.0073355669 0.0311652347 61 2.4000000000 0.0010772465 0.0009265952 0.0011126522 0.0045525601 0.0026130000 14494661 955859216 1373700096 0.0026151016 -0.0073753549 0.0340861939 62 2.4400000000 0.0010555730 0.0009286755 0.0011126522 0.0048139985 0.0026540000 14496637 955859216 1373700096 0.0038687258 -0.0074422490 0.0369995348 63 2.4800000000 0.0010769672 0.0009310293 0.0011126522 0.0050058372 0.0027310000 14498613 955859216 1373700096 0.0053083175 -0.0080903517 0.0397015549 64 2.5200000000 0.0010281345 0.0009325466 0.0011126522 0.0051427877 0.0027060000 14500589 955859216 1373700096 0.0068522175 -0.0077772150 0.0428445041 65 2.5600000000 0.0010688815 0.0009346441 0.0011126522 0.0054009694 0.0027040000 14508709 955859216 1373700096 0.0080798799 -0.0081130592 0.0456997380 66 2.6000000000 0.0010488272 0.0009363741 0.0011126522 0.0057550245 0.0027430000 14523485 955859216 1373700096 0.0098281717 -0.0090823071 0.0482508130 67 2.6400000000 0.0012204463 0.0009406140 0.0012204463 0.0060399453 0.0028450000 14525461 955859216 1373700096 0.0120466556 -0.0074872840 0.0516160429 68 2.6800000000 0.0010520739 0.0009422531 0.0012204463 0.0064604740 0.0026920000 14527437 955859216 1373700096 0.0122812921 -0.0074124574 0.0544138961 69 2.7200000000 0.0010370561 0.0009436271 0.0012204463 0.0066811647 0.0027280000 14529413 955859216 1373700096 0.0140629662 -0.0082415324 0.0570890643 70 2.7600000000 0.0010501688 0.0009451491 0.0012204463 0.0068092759 0.0027310000 14531389 955859216 1373700096 0.0155712822 -0.0089621162 0.0595709756 71 2.8000000000 0.0010350047 0.0009464147 0.0012204463 0.0068353915 0.0027990000 14533365 955859216 1373700096 0.0168194026 -0.0082590627 0.0625933781 72 2.8400000000 0.0010025749 0.0009471947 0.0012204463 0.0068265366 0.0028060000 14535341 955859216 1373700096 0.0182616692 -0.0085383141 0.0652752370 73 2.8800000000 0.0010349721 0.0009483971 0.0012204463 0.0068159791 0.0027380000 14537317 955859216 1373700096 0.0196043607 -0.0090278396 0.0677434728 74 2.9200000000 0.0010310173 0.0009495136 0.0012204463 0.0068313217 0.0027730000 14539293 955859216 1373700096 0.0211055595 -0.0082013486 0.0706292316 75 2.9600000000 0.0010282153 0.0009505629 0.0012204463 0.0069011341 0.0027290000 14541269 955859216 1373700096 0.0224440917 -0.0078465296 0.0733382404 76 3.0000000000 0.0010666783 0.0009520908 0.0012204463 0.0070769675 0.0027370000 14543245 955859216 1373700096 0.0239509828 -0.0090400614 0.0755393729 77 3.0400000000 0.0010932118 0.0009539235 0.0012204463 0.0072407794 0.0027140000 14545221 955859216 1373700096 0.0250712074 -0.0101669282 0.0776420385 78 3.0800000000 0.0010440644 0.0009550792 0.0012204463 0.0074733265 0.0027140000 14547197 955859216 1373700096 0.0265570786 -0.0095194327 0.0804636031 79 3.1200000000 0.0010424664 0.0009561853 0.0012204463 0.0076773973 0.0027700000 14549173 955859216 1373700096 0.0273560937 -0.0092827352 0.0831952691 80 3.1600000000 0.0010793807 0.0009577253 0.0012204463 0.0078213908 0.0027950000 14551149 955859216 1373700096 0.0284419619 -0.0103076240 0.0854344219 81 3.2000000000 0.0010373747 0.0009587086 0.0012204463 0.0079751622 0.0027870000 14553125 955859216 1373700096 0.0297323130 -0.0105722323 0.0879573673 82 3.2400000000 0.0010444158 0.0009597538 0.0012204463 0.0081525806 0.0028100000 14555101 955859216 1373700096 0.0302733034 -0.0108156661 0.0904754996 83 3.2800000000 0.0010503961 0.0009608459 0.0012204463 0.0083406943 0.0028480000 14557077 955859216 1373700096 0.0313578360 -0.0117142135 0.0928762183 84 3.3200000000 0.0010429478 0.0009618233 0.0012204463 0.0084484627 0.0028330000 14559053 955859216 1373700096 0.0321076661 -0.0119183287 0.0954192653 85 3.3600000000 0.0009936055 0.0009621972 0.0012204463 0.0085186287 0.0028620000 14561029 955859216 1373700096 0.0326536223 -0.0115525294 0.0981882289 86 3.4000000000 0.0009859328 0.0009624732 0.0012204463 0.0085819698 0.0027810000 14563005 955859216 1373700096 0.0334386565 -0.0116915228 0.1007672548 87 3.4400000000 0.0009672393 0.0009625280 0.0012204463 0.0086553282 0.0028230000 14564981 955859216 1373700096 0.0342721418 -0.0116350278 0.1036150604 88 3.4800000000 0.0009901159 0.0009628415 0.0012204463 0.0087431826 0.0029000000 14566957 955859216 1373700096 0.0350739099 -0.0119609833 0.1063813493 89 3.5200000000 0.0009628569 0.0009628416 0.0012204463 0.0088273807 0.0028280000 14568933 955859216 1373700096 0.0358537138 -0.0119339032 0.1092837602 90 3.5600000000 0.0009737998 0.0009629634 0.0012204463 0.0089455051 0.0028450000 14570909 955859216 1373700096 0.0363121554 -0.0118936161 0.1122478470 91 3.6000000000 0.0009625209 0.0009629585 0.0012204463 0.0090855038 0.0028420000 14572885 955859216 1373700096 0.0375207588 -0.0124606481 0.1152551845 92 3.6400000000 0.0009821411 0.0009631670 0.0012204463 0.0091757999 0.0030110000 14574861 955859216 1373700096 0.0380651131 -0.0126771703 0.1184285283 93 3.6800000000 0.0009703005 0.0009632438 0.0012204463 0.0091789446 0.0028550000 14576837 955859216 1373700096 0.0385119617 -0.0131952642 0.1213704497 94 3.7200000000 0.0009068680 0.0009626440 0.0012204463 0.0091577635 0.0028630000 14578813 955859216 1373700096 0.0392430648 -0.0130208107 0.1245468408 95 3.7600000000 0.0009323414 0.0009623250 0.0012204463 0.0091467410 0.0028350000 14580789 955859216 1373700096 0.0400874838 -0.0131988004 0.1276182085 96 3.8000000000 0.0008806193 0.0009614739 0.0012204463 0.0091673209 0.0028390000 14582765 955859216 1373700096 0.0409719199 -0.0130839031 0.1308626682 97 3.8400000000 0.0008369504 0.0009601902 0.0012204463 0.0092847170 0.0028550000 14584741 955859216 1373700096 0.0414901115 -0.0116607584 0.1344795227 98 3.8800000000 0.0009108062 0.0009596863 0.0012204463 0.0094096670 0.0028750000 14586717 955859216 1373700096 0.0421140492 -0.0117018959 0.1376441121 99 3.9200000000 0.0008860491 0.0009589425 0.0012204463 0.0095395034 0.0029110000 14588693 955859216 1373700096 0.0431258418 -0.0116984835 0.1408693492 100 3.9600000000 0.0008245265 0.0009575983 0.0012204463 0.0096523159 0.0028900000 14590669 955859216 1373700096 0.0433129705 -0.0101418886 0.1444676071 101 4.0000000000 0.0008746249 0.0009567768 0.0012204463 0.0097022439 0.0028890000 14592645 955859216 1373700096 0.0438427292 -0.0095131155 0.1478535235 102 4.0400000000 0.0009130444 0.0009563480 0.0012204463 0.0097156392 0.0029560000 14594621 955859216 1373700096 0.0445478708 -0.0097881909 0.1508183926 103 4.0800000000 0.0008352872 0.0009551727 0.0012204463 0.0097286277 0.0029770000 14596597 955859216 1373700096 0.0448324569 -0.0086457375 0.1541999876 104 4.1200000000 0.0008919290 0.0009545646 0.0012204463 0.0097355399 0.0029990000 14598573 955859216 1373700096 0.0456611104 -0.0085321944 0.1573376507 105 4.1600000000 0.0008791076 0.0009538459 0.0012204463 0.0097413382 0.0030340000 14600549 955859216 1373700096 0.0461295880 -0.0084221531 0.1600835621 106 4.2000000000 0.0008326879 0.0009527029 0.0012204463 0.0097311351 0.0030140000 14602525 955859216 1373700096 0.0462065525 -0.0077250404 0.1629079431 107 4.2400000000 0.0009070557 0.0009522763 0.0012204463 0.0097073666 0.0029830000 14604501 955859216 1373700096 0.0468372405 -0.0083026215 0.1653671712 108 4.2800000000 0.0008208792 0.0009510597 0.0012204463 0.0096957778 0.0030290000 14606477 955859216 1373700096 0.0469276980 -0.0074628107 0.1681142598 109 4.3200000000 0.0008179217 0.0009498382 0.0012204463 0.0096790474 0.0030790000 14608453 955859216 1373700096 0.0470960960 -0.0065752505 0.1707962304 110 4.3600000000 0.0008325045 0.0009487716 0.0012204463 0.0096427673 0.0031290000 14610429 955859216 1373700096 0.0474632718 -0.0062156213 0.1733503342 111 4.4000000000 0.0008278284 0.0009476820 0.0012204463 0.0096107496 0.0031480000 14612405 955859216 1373700096 0.0479394719 -0.0059930664 0.1758713424 112 4.4400000000 0.0008072122 0.0009464278 0.0012204463 0.0095794928 0.0031620000 14614381 955859216 1373700096 0.0483821146 -0.0057883663 0.1782715917 113 4.4800000000 0.0008043990 0.0009451709 0.0012204463 0.0095464904 0.0031260000 14616357 955859216 1373700096 0.0480289832 -0.0050687473 0.1806867570 114 4.5200000000 0.0008819264 0.0009446161 0.0012204463 0.0095150166 0.0031580000 14618333 955859216 1373700096 0.0483167954 -0.0051539689 0.1830922812 115 4.5600000000 0.0008822883 0.0009440741 0.0012204463 0.0094858990 0.0031360000 14620309 955859216 1373700096 0.0486359186 -0.0052141016 0.1854231656 116 4.6000000000 0.0008829913 0.0009435476 0.0012204463 0.0094653222 0.0031640000 14622285 955859216 1373700096 0.0484312586 -0.0045399768 0.1879848093 117 4.6400000000 0.0009642747 0.0009437247 0.0012204463 0.0094347639 0.0031780000 14624261 955859216 1373700096 0.0485998429 -0.0047465246 0.1904001832 118 4.6800000000 0.0009876958 0.0009440974 0.0012204463 0.0094076807 0.0031360000 14626237 955859216 1373700096 0.0485461578 -0.0045713577 0.1930423230 119 4.7200000000 0.0010983070 0.0009453932 0.0012204463 0.0093822180 0.0032280000 14628213 955859216 1373700096 0.0489100106 -0.0043853140 0.1959359944 120 4.7600000000 0.0011753819 0.0009473098 0.0012204463 0.0093576421 0.0031810000 14630189 955859216 1373700096 0.0489872508 -0.0045937332 0.1986739486 121 4.8000000000 0.0012742738 0.0009500120 0.0012742738 0.0093445229 0.0032160000 14632165 955859216 1373700096 0.0490811691 -0.0044043986 0.2016457468 122 4.8400000000 0.0013871009 0.0009535947 0.0013871009 0.0093509894 0.0031460000 14634141 955859216 1373700096 0.0490089096 -0.0042991512 0.2046704441 123 4.8800000000 0.0014948962 0.0009579955 0.0014948962 0.0093367609 0.0031050000 14636117 955859216 1373700096 0.0489791706 -0.0041182335 0.2077514827 124 4.9200000000 0.0015795400 0.0009630080 0.0015795400 0.0093143250 0.0031180000 14638093 955859216 1373700096 0.0489425883 -0.0037767654 0.2107780874 125 4.9600000000 0.0017651923 0.0009694254 0.0017651923 0.0092937043 0.0031410000 14640069 955859216 1373700096 0.0490811877 -0.0033724064 0.2139909863 126 5.0000000000 0.0019070235 0.0009768667 0.0019070235 0.0092812571 0.0031270000 14642045 955859216 1373700096 0.0492455773 -0.0033524588 0.2170801759 127 5.0400000000 0.0020405729 0.0009852423 0.0020405729 0.0092831595 0.0031860000 14644021 955859216 1373700096 0.0496122129 -0.0032285282 0.2202662081 128 5.0800000000 0.0021450305 0.0009943032 0.0021450305 0.0093004580 0.0031470000 14645997 955859216 1373700096 0.0499873720 -0.0026915350 0.2233980447 129 5.1200000000 0.0022879248 0.0010043313 0.0022879248 0.0092854973 0.0031660000 14660261 955859216 1373700096 0.0504243039 -0.0025921746 0.2264433056 130 5.1600000000 0.0023580659 0.0010147446 0.0023580659 0.0092738799 0.0032110000 14687837 955859216 1373700096 0.0510007106 -0.0032648053 0.2290736586 131 5.2000000000 0.0024092391 0.0010253896 0.0024092391 0.0092641207 0.0032260000 14689813 955859216 1373700096 0.0515088998 -0.0031012692 0.2317945510 132 5.2400000000 0.0024945869 0.0010365199 0.0024945869 0.0092434277 0.0021200000 14691789 955859216 1373700096 0.0517268963 -0.0026116241 0.2346589714 133 5.2800000000 0.0027168277 0.0010491538 0.0027168277 0.0092382463 0.0032750000 14693765 955859216 1373700096 0.0522819944 -0.0030211420 0.2371218652 134 5.3200000000 0.0028454531 0.0010625590 0.0028454531 0.0092652477 0.0032840000 14695741 955859216 1373700096 0.0527368598 -0.0024165134 0.2400354892 135 5.3600000000 0.0029594698 0.0010766102 0.0029594698 0.0092674624 0.0032870000 14697717 955859216 1373700096 0.0532050058 -0.0026119605 0.2423021197 136 5.4000000000 0.0031522161 0.0010918720 0.0031522161 0.0092748555 0.0032620000 14699693 955859216 1373700096 0.0537870750 -0.0032841277 0.2444493175 137 5.4400000000 0.0033187759 0.0011081268 0.0033187759 0.0092736339 0.0032700000 14701669 955859216 1373700096 0.0543922447 -0.0035799178 0.2467865497 138 5.4800000000 0.0033364461 0.0011242740 0.0033364461 0.0092548134 0.0032650000 14703645 955859216 1373700096 0.0548175611 -0.0035394214 0.2490539253 139 5.5200000000 0.0035099504 0.0011414371 0.0035099504 0.0092439687 0.0032770000 14705621 955859216 1373700096 0.0550672263 -0.0036846125 0.2511993945 140 5.5600000000 0.0037839310 0.0011603121 0.0037839310 0.0092363258 0.0032820000 14707597 955859216 1373700096 0.0551664270 -0.0040357206 0.2532845438 141 5.6000000000 0.0021173707 0.0011670997 0.0037839310 0.0092997844 0.0035400000 14709573 955859216 1373700096 0.0566004179 -0.0046696267 0.2588240504 142 5.6400000000 0.0033032142 0.0011821428 0.0037839310 0.0092962814 0.0033010000 14711549 955859216 1373700096 0.0554785393 -0.0051758373 0.2596768141 143 5.6800000000 0.0037953153 0.0012004167 0.0037953153 0.0092963164 0.0032900000 14713525 955859216 1373700096 0.0549679250 -0.0055738557 0.2611630857 144 5.7200000000 0.0039863074 0.0012197632 0.0039863074 0.0092920835 0.0032720000 14715501 955859216 1373700096 0.0543548055 -0.0055802688 0.2629389763 145 5.7600000000 0.0041309455 0.0012398403 0.0041309455 0.0092817247 0.0033320000 14717477 955859216 1373700096 0.0536445826 -0.0055621942 0.2646012008 146 5.8000000000 0.0043949378 0.0012614506 0.0043949378 0.0092817423 0.0033170000 14719453 955859216 1373700096 0.0528707467 -0.0053336476 0.2662895620 147 5.8400000000 0.0046385606 0.0012844241 0.0046385606 0.0092733636 0.0033410000 14721429 955859216 1373700096 0.0520663522 -0.0060433424 0.2676741481 148 5.8800000000 0.0046869596 0.0013074142 0.0046869596 0.0092554768 0.0033140000 14723405 955859216 1373700096 0.0511654355 -0.0068254294 0.2690014541 149 5.9200000000 0.0048563979 0.0013312329 0.0048563979 0.0092383365 0.0033280000 14725381 955859216 1373700096 0.0501199998 -0.0070336303 0.2705677748 150 5.9600000000 0.0051112361 0.0013564329 0.0051112361 0.0092217231 0.0033700000 14727357 955859216 1373700096 0.0490591154 -0.0072957315 0.2723292410 151 6.0000000000 0.0051873131 0.0013818030 0.0051873131 0.0092033495 0.0034690000 14729333 955859216 1373700096 0.0478900410 -0.0075197150 0.2740010917 152 6.0400000000 0.0053825793 0.0014081239 0.0053825793 0.0091881418 0.0034560000 14731309 955859216 1373700096 0.0466919206 -0.0077380729 0.2757160664 153 6.0800000000 0.0057282159 0.0014363598 0.0057282159 0.0091748372 0.0034360000 14733285 955859216 1373700096 0.0454285368 -0.0079449452 0.2776728868 154 6.1200000000 0.0058578467 0.0014650707 0.0058578467 0.0091593879 0.0034070000 14735261 955859216 1373700096 0.0441268422 -0.0083343778 0.2795417011 155 6.1600000000 0.0058753751 0.0014935243 0.0058753751 0.0091407169 0.0034390000 14737237 955859216 1373700096 0.0426977053 -0.0085633202 0.2815216780 156 6.2000000000 0.0066720289 0.0015267199 0.0066720289 0.0091467576 0.0034280000 14739213 955859216 1373700096 0.0394834317 -0.0093888408 0.2849600911 157 6.2400000000 0.0064837155 0.0015582931 0.0066720289 0.0091304815 0.0034410000 14741189 955859216 1373700096 0.0381790996 -0.0096251285 0.2873997688 158 6.2800000000 0.0065379478 0.0015898099 0.0066720289 0.0091138461 0.0035170000 14743165 955859216 1373700096 0.0367004387 -0.0100307101 0.2893720567 159 6.3200000000 0.0066197743 0.0016214449 0.0066720289 0.0091009146 0.0034760000 14745141 955859216 1373700096 0.0350345671 -0.0102786934 0.2912734449 160 6.3600000000 0.0067800907 0.0016536864 0.0067800907 0.0090853169 0.0034660000 14747117 955859216 1373700096 0.0334225483 -0.0102448687 0.2932429910 161 6.4000000000 0.0069095609 0.0016863316 0.0069095609 0.0090768850 0.0034870000 14749093 955859216 1373700096 0.0317094214 -0.0102656223 0.2950603664 162 6.4400000000 0.0069212266 0.0017186458 0.0069212266 0.0090849526 0.0034950000 14751069 955859216 1373700096 0.0299379006 -0.0105308546 0.2968581319 163 6.4800000000 0.0069876076 0.0017509707 0.0069876076 0.0090773458 0.0035100000 14753045 955859216 1373700096 0.0283717159 -0.0106683969 0.2984834015 164 6.5200000000 0.0072342241 0.0017844052 0.0072342241 0.0090629846 0.0034920000 14755021 955859216 1373700096 0.0267579295 -0.0106673334 0.3001585305 165 6.5600000000 0.0074261269 0.0018185974 0.0074261269 0.0090552917 0.0034820000 14756997 955859216 1373700096 0.0251125097 -0.0108570447 0.3019337058 166 6.6000000000 0.0074801552 0.0018527032 0.0074801552 0.0090406391 0.0035250000 14758973 955859216 1373700096 0.0236522164 -0.0110440217 0.3036487699 167 6.6400000000 0.0076383450 0.0018873477 0.0076383450 0.0090293315 0.0035430000 14760949 955859216 1373700096 0.0221006796 -0.0108262338 0.3056398332 168 6.6800000000 0.0076650754 0.0019217390 0.0076650754 0.0090142649 0.0035520000 14762925 955859216 1373700096 0.0206280723 -0.0112663126 0.3071243167 169 6.7200000000 0.0076443614 0.0019556006 0.0076650754 0.0090000878 0.0035370000 14764901 955859216 1373700096 0.0191798937 -0.0115479967 0.3085962236 170 6.7600000000 0.0078312159 0.0019901631 0.0078312159 0.0089850966 0.0035750000 14766877 955859216 1373700096 0.0180009212 -0.0117200380 0.3101304471 171 6.8000000000 0.0079875765 0.0020252357 0.0079875765 0.0089721935 0.0035340000 14768853 955859216 1373700096 0.0169256590 -0.0123528838 0.3114581406 172 6.8400000000 0.0079152901 0.0020594802 0.0079875765 0.0089560256 0.0035390000 14770829 955859216 1373700096 0.0157794952 -0.0130090332 0.3125796616 173 6.8800000000 0.0078856247 0.0020931573 0.0079875765 0.0089416374 0.0035630000 14772805 955859216 1373700096 0.0148338759 -0.0136227161 0.3135326803 174 6.9200000000 0.0080111744 0.0021271689 0.0080111744 0.0089504787 0.0035700000 14774781 955859216 1373700096 0.0139710233 -0.0141530493 0.3144354224 175 6.9600000000 0.0081549175 0.0021616132 0.0081549175 0.0089665626 0.0035640000 14776757 955859216 1373700096 0.0130711924 -0.0147106815 0.3153949082 176 7.0000000000 0.0080955857 0.0021953289 0.0081549175 0.0089760122 0.0035620000 14778733 955859216 1373700096 0.0122436741 -0.0152332680 0.3160563111 177 7.0400000000 0.0082514128 0.0022295441 0.0082514128 0.0090007246 0.0036010000 14780709 955859216 1373700096 0.0115971556 -0.0157748200 0.3167638481 178 7.0800000000 0.0083293673 0.0022638128 0.0083293673 0.0090066630 0.0036420000 14782685 955859216 1373700096 0.0109926173 -0.0162872430 0.3173923790 179 7.1200000000 0.0083959037 0.0022980703 0.0083959037 0.0090135339 0.0035850000 14784661 955859216 1373700096 0.0104904557 -0.0166503284 0.3180876672 180 7.1600000000 0.0084672030 0.0023323432 0.0084672030 0.0090400857 0.0036830000 14786637 955859216 1373700096 0.0100399638 -0.0171116497 0.3188541532 181 7.2000000000 0.0084042400 0.0023658896 0.0084672030 0.0090595935 0.0035980000 14788613 955859216 1373700096 0.0095170541 -0.0175144970 0.3193450868 182 7.2400000000 0.0084199142 0.0023991535 0.0084672030 0.0090778183 0.0035620000 14790589 955859216 1373700096 0.0090300608 -0.0177563708 0.3197862506 183 7.2800000000 0.0084457928 0.0024321952 0.0084672030 0.0091024414 0.0036830000 14792565 955859216 1373700096 0.0086151464 -0.0180032514 0.3199328184 184 7.3200000000 0.0080453698 0.0024627016 0.0084672030 0.0092518356 0.0038050000 14794541 955859216 1373700096 0.0079371827 -0.0181621611 0.3210171759 185 7.3600000000 0.0080143446 0.0024927105 0.0084672030 0.0092735320 0.0038120000 14796517 955859216 1373700096 0.0076460689 -0.0183704123 0.3212672770 186 7.4000000000 0.0083365273 0.0025241289 0.0084672030 0.0092698982 0.0036630000 14798493 955859216 1373700096 0.0070646382 -0.0188436415 0.3218067586 187 7.4400000000 0.0080280229 0.0025535615 0.0084672030 0.0092591204 0.0037780000 14800469 955859216 1373700096 0.0067682345 -0.0188187491 0.3234928846 188 7.4800000000 0.0082528656 0.0025838769 0.0084672030 0.0092451033 0.0036520000 14802445 955859216 1373700096 0.0065048230 -0.0192154571 0.3245078623 189 7.5200000000 0.0082232459 0.0026137148 0.0084672030 0.0092407023 0.0036500000 14804421 955859216 1373700096 0.0063257641 -0.0195007920 0.3258900046 190 7.5600000000 0.0082283663 0.0026432656 0.0084672030 0.0092523218 0.0036820000 14806397 955859216 1373700096 0.0063167079 -0.0193621460 0.3274078071 191 7.6000000000 0.0080913082 0.0026717894 0.0084672030 0.0092437681 0.0037750000 14808373 955859216 1373700096 0.0066195671 -0.0192525089 0.3290177286 192 7.6400000000 0.0080446014 0.0026997728 0.0084672030 0.0092323211 0.0037890000 14810349 955859216 1373700096 0.0067066411 -0.0194860473 0.3308449388 193 7.6800000000 0.0079529872 0.0027269915 0.0084672030 0.0092219268 0.0036490000 14812325 955859216 1373700096 0.0067047784 -0.0197704751 0.3324487209 194 7.7200000000 0.0079086693 0.0027537012 0.0084672030 0.0092098541 0.0037260000 14814301 955859216 1373700096 0.0068627079 -0.0198715758 0.3338485360 195 7.7600000000 0.0078859497 0.0027800204 0.0084672030 0.0091962215 0.0036750000 14816277 955859216 1373700096 0.0070828646 -0.0200386029 0.3350349665 196 7.8000000000 0.0078409389 0.0028058415 0.0084672030 0.0091827540 0.0037340000 14818253 955859216 1373700096 0.0072495383 -0.0203029644 0.3360691071 197 7.8400000000 0.0079055475 0.0028317283 0.0084672030 0.0091696258 0.0037320000 14820229 955859216 1373700096 0.0074703079 -0.0206596106 0.3369010687 198 7.8800000000 0.0078514172 0.0028570803 0.0084672030 0.0091557558 0.0037160000 14822205 955859216 1373700096 0.0076952106 -0.0207867492 0.3379789889 199 7.9200000000 0.0077022845 0.0028814280 0.0084672030 0.0091455158 0.0037430000 14824181 955859216 1373700096 0.0079673044 -0.0210024398 0.3386049867 200 7.9600000000 0.0078015742 0.0029060287 0.0084672030 0.0091398505 0.0037290000 14826157 955859216 1373700096 0.0082003828 -0.0213787016 0.3392795026 201 8.0000000000 0.0078418329 0.0029305850 0.0084672030 0.0091278032 0.0037000000 14828133 955859216 1373700096 0.0083402665 -0.0215973724 0.3400175869 202 8.0400000000 0.0077934465 0.0029546586 0.0084672030 0.0091187697 0.0037480000 14830109 955859216 1373700096 0.0086095240 -0.0217150468 0.3404797912 203 8.0800000000 0.0076504773 0.0029777907 0.0084672030 0.0091129962 0.0037770000 14832085 955859216 1373700096 0.0087172957 -0.0217448212 0.3410116732 204 8.1200000000 0.0077653057 0.0030012589 0.0084672030 0.0091113896 0.0037990000 14834061 955859216 1373700096 0.0088391593 -0.0217297953 0.3414367437 205 8.1600000000 0.0077933623 0.0030246350 0.0084672030 0.0091126458 0.0038180000 14836037 955859216 1373700096 0.0089149885 -0.0216994677 0.3419638872 206 8.1999999990 0.0078660082 0.0030481368 0.0084672030 0.0091138359 0.0037700000 14838013 955859216 1373700096 0.0089277849 -0.0215308219 0.3420023620 207 8.2400000000 0.0078363679 0.0030712684 0.0084672030 0.0091434406 0.0038320000 14839989 955859216 1373700096 0.0090097496 -0.0214334857 0.3423936367 208 8.2799999990 0.0076872506 0.0030934606 0.0084672030 0.0091790128 0.0038460000 14841965 955859216 1373700096 0.0090012830 -0.0214061923 0.3427057266 209 8.3200000000 0.0077312589 0.0031156510 0.0084672030 0.0092062401 0.0038580000 14843941 955859216 1373700096 0.0089760413 -0.0215804074 0.3426073492 210 8.3599999990 0.0077702408 0.0031378157 0.0084672030 0.0092042535 0.0039300000 14845917 955859216 1373700096 0.0088678487 -0.0215466600 0.3427221477 211 8.4000000000 0.0077644773 0.0031597430 0.0084672030 0.0091957091 0.0038310000 14847893 955859216 1373700096 0.0088560609 -0.0214053094 0.3426049650 212 8.4399999990 0.0077144555 0.0031812275 0.0084672030 0.0091935557 0.0039110000 14849869 955859216 1373700096 0.0088477088 -0.0212603007 0.3421347737 213 8.4800000000 0.0077588679 0.0032027188 0.0084672030 0.0092038336 0.0038190000 14851845 955859216 1373700096 0.0088683031 -0.0212859064 0.3417827189 214 8.5200000000 0.0077265082 0.0032238580 0.0084672030 0.0092007853 0.0038100000 14853821 955859216 1373700096 0.0088882409 -0.0212469660 0.3413021564 215 8.5600000000 0.0077704350 0.0032450049 0.0084672030 0.0091918211 0.0038940000 14855797 955859216 1373700096 0.0088085262 -0.0209555570 0.3408080041 216 8.6000000000 0.0077721667 0.0032659639 0.0084672030 0.0091968980 0.0038740000 14857773 955859216 1373700096 0.0087263817 -0.0207120106 0.3402815759 217 8.6400000000 0.0077536181 0.0032866444 0.0084672030 0.0092067297 0.0038300000 14859749 955859216 1373700096 0.0085740751 -0.0204532873 0.3398466706 218 8.6800000000 0.0077456250 0.0033070984 0.0084672030 0.0092218288 0.0038360000 14861725 955859216 1373700096 0.0084638027 -0.0201719031 0.3393346369 219 8.7200000000 0.0077142068 0.0033272222 0.0084672030 0.0092353587 0.0038660000 14863701 955859216 1373700096 0.0083469748 -0.0198245440 0.3389627635 220 8.7600000000 0.0077072307 0.0033471313 0.0084672030 0.0092455963 0.0038660000 14865677 955859216 1373700096 0.0082321186 -0.0194518492 0.3383980691 221 8.8000000000 0.0077363024 0.0033669918 0.0084672030 0.0092602629 0.0038480000 14867653 955859216 1373700096 0.0081459889 -0.0192419384 0.3379736543 222 8.8400000000 0.0076728989 0.0033863878 0.0084672030 0.0092649986 0.0038810000 14869629 955859216 1373700096 0.0079733636 -0.0188987423 0.3374886513 223 8.8800000000 0.0077622621 0.0034060106 0.0084672030 0.0092760220 0.0038800000 14871605 955859216 1373700096 0.0076847686 -0.0185462143 0.3366469741 224 8.9200000000 0.0077513601 0.0034254094 0.0084672030 0.0093033664 0.0038810000 14873581 955859216 1373700096 0.0074055442 -0.0185080953 0.3360051811 225 8.9600000000 0.0076888083 0.0034443579 0.0084672030 0.0093238615 0.0039040000 14875557 955859216 1373700096 0.0070639588 -0.0181691330 0.3352507651 226 9.0000000000 0.0076328628 0.0034628911 0.0084672030 0.0093537248 0.0038790000 14877533 955859216 1373700096 0.0067468905 -0.0178960972 0.3345253468 227 9.0400000000 0.0076256366 0.0034812292 0.0084672030 0.0093722723 0.0039190000 14879509 955859216 1373700096 0.0063460474 -0.0175707173 0.3337388635 228 9.0800000000 0.0076574553 0.0034995460 0.0084672030 0.0094011920 0.0039400000 14881485 955859216 1373700096 0.0059910179 -0.0173219368 0.3329026997 229 9.1200000000 0.0076113245 0.0035175013 0.0084672030 0.0094319705 0.0039220000 14883461 955859216 1373700096 0.0055979844 -0.0173176676 0.3319928646 230 9.1600000000 0.0076689045 0.0035355509 0.0084672030 0.0094418928 0.0039030000 14885437 955859216 1373700096 0.0051629120 -0.0170980953 0.3308991194 231 9.2000000000 0.0076576406 0.0035533954 0.0084672030 0.0094586980 0.0039100000 14887413 955859216 1373700096 0.0046201707 -0.0167741068 0.3298883438 232 9.2400000000 0.0077054906 0.0035712924 0.0084672030 0.0094794174 0.0040090000 14889389 955859216 1373700096 0.0040936191 -0.0165014025 0.3288857043 233 9.2800000000 0.0076631578 0.0035888541 0.0084672030 0.0095077581 0.0040230000 14891365 955859216 1373700096 0.0034857343 -0.0161115229 0.3282162547 234 9.3200000000 0.0075821280 0.0036059193 0.0084672030 0.0095372672 0.0039740000 14893341 955859216 1373700096 0.0028955631 -0.0157741606 0.3270598948 235 9.3600000000 0.0076621515 0.0036231799 0.0084672030 0.0095492209 0.0039360000 14895317 955859216 1373700096 0.0022750958 -0.0155406650 0.3260039091 236 9.4000000000 0.0076468401 0.0036402293 0.0084672030 0.0095529782 0.0039620000 14897293 955859216 1373700096 0.0015684639 -0.0150893945 0.3249224126 237 9.4400000000 0.0077298996 0.0036574853 0.0084672030 0.0095627793 0.0039830000 14899269 955859216 1373700096 0.0008045776 -0.0148766572 0.3238261938 238 9.4800000000 0.0081228092 0.0036762472 0.0084672030 0.0096419681 0.0041180000 14901245 955859216 1373700096 -0.0009826674 -0.0141559253 0.3213680983 239 9.5200000000 0.0080761695 0.0036946569 0.0084672030 0.0096707877 0.0040560000 14903221 955859216 1373700096 -0.0019438937 -0.0133520998 0.3202601969 240 9.5600000000 0.0082391184 0.0037135921 0.0084672030 0.0096991666 0.0040550000 14905197 955859216 1373700096 -0.0030118029 -0.0124330539 0.3189308643 241 9.6000000000 0.0084688114 0.0037333233 0.0084688114 0.0097678804 0.0040380000 14907173 955859216 1373700096 -0.0040710061 -0.0120634874 0.3178702593 242 9.6400000000 0.0086226948 0.0037535273 0.0086226948 0.0098401927 0.0040640000 14909149 955859216 1373700096 -0.0051309299 -0.0116331009 0.3167639375 243 9.6800000000 0.0088338749 0.0037744341 0.0088338749 0.0098977004 0.0040010000 14911125 955859216 1373700096 -0.0061474773 -0.0111665204 0.3151661158 244 9.7200000000 0.0091160731 0.0037963261 0.0091160731 0.0099517245 0.0040290000 14913101 955859216 1373700096 -0.0072765527 -0.0106252776 0.3137882650 245 9.7600000000 0.0090862131 0.0038179175 0.0091160731 0.0099967985 0.0040430000 14915077 955859216 1373700096 -0.0082854386 -0.0101078600 0.3124751151 246 9.8000000000 0.0093391724 0.0038403616 0.0093391724 0.0100244737 0.0040480000 14917053 955859216 1373700096 -0.0094103152 -0.0095914798 0.3109112382 247 9.8400000000 0.0095142210 0.0038633327 0.0095142210 0.0100639470 0.0041150000 14919029 955859216 1373700096 -0.0105250934 -0.0088077104 0.3095231652 248 9.8800000000 0.0095145972 0.0038861200 0.0095145972 0.0101145021 0.0040970000 14921005 955859216 1373700096 -0.0116214259 -0.0078327116 0.3078389764 249 9.9200000000 0.0094319023 0.0039083923 0.0095145972 0.0101673365 0.0041160000 14922981 955859216 1373700096 -0.0125985146 -0.0069938633 0.3062615991 250 9.9600000000 0.0090609407 0.0039290024 0.0095145972 0.0102110102 0.0040820000 14924957 955859216 1373700096 -0.0136252204 -0.0056258151 0.3049704731 251 10.0000000000 0.0085176108 0.0039472838 0.0095145972 0.0102546229 0.0040500000 14926933 955859216 1373700096 -0.0147441700 -0.0034665354 0.3036075234 252 10.0400000000 0.0080960151 0.0039637470 0.0095145972 0.0103141461 0.0041300000 14928909 955859216 1373700096 -0.0158089865 -0.0017020733 0.3021439314 253 10.0800000000 0.0080806930 0.0039800195 0.0095145972 0.0103506063 0.0041020000 14930885 955859216 1373700096 -0.0166844018 -0.0007790887 0.3004756570 254 10.1200000000 0.0081148446 0.0039962983 0.0095145972 0.0103862315 0.0040510000 14932861 955859216 1373700096 -0.0176855940 0.0002847708 0.2988788188 255 10.1600000000 0.0081885736 0.0040127386 0.0095145972 0.0104368387 0.0041180000 14934837 955859216 1373700096 -0.0187145229 0.0010718049 0.2973513901 256 10.2000000000 0.0082312347 0.0040292171 0.0095145972 0.0104803896 0.0040770000 14936813 955859216 1373700096 -0.0196098629 0.0018533377 0.2958179712 257 10.2400000000 0.0083486671 0.0040460243 0.0095145972 0.0105235202 0.0040980000 14963365 955859216 1373700096 -0.0205984302 0.0026475312 0.2943191528 258 10.2800000000 0.0083512189 0.0040627111 0.0095145972 0.0105363738 0.0041660000 15016541 955859216 1373700096 -0.0214248300 0.0034950892 0.2927218676 259 10.3200000000 0.0083376151 0.0040792165 0.0095145972 0.0105384852 0.0041250000 15018517 955859216 1373700096 -0.0223273914 0.0042967768 0.2911904156 260 10.3600000000 0.0085694678 0.0040964867 0.0095145972 0.0105574599 0.0040500000 15020493 955859216 1373700096 -0.0233377460 0.0051647360 0.2895963490 261 10.4000000000 0.0085509224 0.0041135535 0.0095145972 0.0105906508 0.0041190000 15022469 955859216 1373700096 -0.0242029689 0.0058223568 0.2881008089 262 10.4400000000 0.0085862204 0.0041306248 0.0095145972 0.0106024937 0.0041210000 15024445 955859216 1373700096 -0.0250370037 0.0065044020 0.2864255905 263 10.4800000000 0.0086337421 0.0041477469 0.0095145972 0.0106022178 0.0041270000 15026421 955859216 1373700096 -0.0259596966 0.0073164292 0.2848754823 264 10.5200000000 0.0086846240 0.0041649321 0.0095145972 0.0106063259 0.0040720000 15028397 955859216 1373700096 -0.0269376561 0.0080338120 0.2832946777 265 10.5600000000 0.0087225540 0.0041821306 0.0095145972 0.0106311953 0.0040830000 15030373 955859216 1373700096 -0.0278504416 0.0082333256 0.2819355726 266 10.6000000000 0.0086641852 0.0041989805 0.0095145972 0.0106302030 0.0040750000 15032349 955859216 1373700096 -0.0285842847 0.0086649368 0.2803921700 267 10.6400000000 0.0087031908 0.0042158502 0.0095145972 0.0106137990 0.0041520000 15034325 955859216 1373700096 -0.0294647664 0.0093498817 0.2786768079 268 10.6800000000 0.0087005543 0.0042325841 0.0095145972 0.0106045725 0.0041810000 15036301 955859216 1373700096 -0.0303455368 0.0097457040 0.2769807577 269 10.7200000000 0.0087021738 0.0042491997 0.0095145972 0.0106029996 0.0041840000 15038277 955859216 1373700096 -0.0312320590 0.0099844029 0.2756062746 270 10.7600000000 0.0087918974 0.0042660245 0.0095145972 0.0106079012 0.0041740000 15040253 955859216 1373700096 -0.0320405215 0.0101873828 0.2738786340 271 10.8000000000 0.0088893091 0.0042830846 0.0095145972 0.0106022187 0.0041810000 15042229 955859216 1373700096 -0.0327271149 0.0106599992 0.2717384398 272 10.8400000000 0.0089314356 0.0043001741 0.0095145972 0.0105886098 0.0042040000 15044205 955859216 1373700096 -0.0336611941 0.0111836409 0.2700890899 273 10.8800000000 0.0090669217 0.0043176347 0.0095145972 0.0105938152 0.0041030000 15046181 955859216 1373700096 -0.0345946439 0.0114551829 0.2682296038 274 10.9200000000 0.0090292236 0.0043348303 0.0095145972 0.0105929988 0.0041090000 15048157 955859216 1373700096 -0.0354499742 0.0116729168 0.2666526735 275 10.9600000000 0.0089988671 0.0043517905 0.0095145972 0.0105795386 0.0041420000 15050133 955859216 1373700096 -0.0359830409 0.0117688961 0.2646974623 276 11.0000000000 0.0090002222 0.0043686326 0.0095145972 0.0105645527 0.0041280000 15052109 955859216 1373700096 -0.0367456041 0.0118584000 0.2629725933 277 11.0400000000 0.0090559348 0.0043855543 0.0095145972 0.0105555197 0.0040740000 15054085 955859216 1373700096 -0.0376157165 0.0119252149 0.2614054382 278 11.0800000000 0.0091306670 0.0044026230 0.0095145972 0.0105483490 0.0041610000 15056061 955859216 1373700096 -0.0383593589 0.0119542843 0.2596778870 279 11.1200000000 0.0090168063 0.0044191613 0.0095145972 0.0105336645 0.0041170000 15058037 955859216 1373700096 -0.0390020423 0.0119656734 0.2581257522 280 11.1600000000 0.0091149732 0.0044359321 0.0095145972 0.0105157334 0.0041090000 15060013 955859216 1373700096 -0.0397623964 0.0122659411 0.2564116716 281 11.2000000000 0.0092190867 0.0044529540 0.0095145972 0.0104995448 0.0041500000 15061989 955859216 1373700096 -0.0405495912 0.0124721909 0.2547231019 282 11.2400000000 0.0092656929 0.0044700204 0.0095145972 0.0104832979 0.0040880000 15063965 955859216 1373700096 -0.0414506458 0.0127247274 0.2531042099 283 11.2800000000 0.0093267858 0.0044871821 0.0095145972 0.0104658502 0.0040760000 15065941 955859216 1373700096 -0.0423921868 0.0129946284 0.2515263259 284 11.3200000000 0.0093206130 0.0045042013 0.0095145972 0.0104477681 0.0040400000 15067917 955859216 1373700096 -0.0432217903 0.0131001668 0.2501168549 285 11.3600000000 0.0093333004 0.0045211455 0.0095145972 0.0104297082 0.0040480000 15069893 955859216 1373700096 -0.0442032665 0.0132713206 0.2483874559 286 11.4000000000 0.0092676729 0.0045377417 0.0095145972 0.0104117557 0.0042480000 15071869 955859216 1373700096 -0.0451687165 0.0133974301 0.2465618104 287 11.4400000000 0.0093087247 0.0045543653 0.0095145972 0.0103938787 0.0041520000 15073845 955859216 1373700096 -0.0461804979 0.0132653862 0.2448673397 288 11.4800000000 0.0093784854 0.0045711158 0.0095145972 0.0103762077 0.0042590000 15075821 955859216 1373700096 -0.0472227596 0.0130656511 0.2428786010 289 11.5200000000 0.0093702879 0.0045877219 0.0095145972 0.0103590704 0.0041800000 15077797 955859216 1373700096 -0.0488756485 0.0127907461 0.2415165454 290 11.5600000000 0.0094930790 0.0046046369 0.0095145972 0.0103415435 0.0041110000 15079773 955859216 1373700096 -0.0502043329 0.0123963421 0.2395300120 291 11.6000000000 0.0095799109 0.0046217341 0.0095799109 0.0103280635 0.0042080000 15081749 955859216 1373700096 -0.0517406352 0.0120638981 0.2377710044 292 11.6400000000 0.0094662523 0.0046383249 0.0095799109 0.0103106812 0.0040990000 15083725 955859216 1373700096 -0.0532488786 0.0114906933 0.2362358719 293 11.6800000000 0.0093147522 0.0046542854 0.0095799109 0.0102997291 0.0042520000 15085701 955859216 1373700096 -0.0548557863 0.0111759370 0.2346263081 294 11.7200000000 0.0094184522 0.0046704900 0.0095799109 0.0102826602 0.0041750000 15087677 955859216 1373700096 -0.0567114428 0.0108493436 0.2327332944 295 11.7600000000 0.0094767585 0.0046867825 0.0095799109 0.0102672375 0.0042170000 15089653 955859216 1373700096 -0.0587668791 0.0106437150 0.2311748117 296 11.8000000000 0.0094764652 0.0047029638 0.0095799109 0.0102505194 0.0041940000 15091629 955859216 1373700096 -0.0608491376 0.0104758171 0.2295831144 297 11.8400000000 0.0094478847 0.0047189400 0.0095799109 0.0102334828 0.0041860000 15093605 955859216 1373700096 -0.0629538596 0.0103646405 0.2280685604 298 11.8800000000 0.0093386052 0.0047344422 0.0095799109 0.0102209893 0.0041910000 15095581 955859216 1373700096 -0.0650099367 0.0103121568 0.2264993191 299 11.9200000000 0.0094309915 0.0047501498 0.0095799109 0.0102114337 0.0041570000 15097557 955859216 1373700096 -0.0673629493 0.0103174988 0.2250371128 300 11.9600000000 0.0094536562 0.0047658281 0.0095799109 0.0101970962 0.0043580000 15099533 955859216 1373700096 -0.0697275624 0.0100365961 0.2234987170 301 12.0000000000 0.0095543470 0.0047817368 0.0095799109 0.0101863832 0.0042290000 15101509 955859216 1373700096 -0.0720917061 0.0100316852 0.2219279855 302 12.0400000000 0.0096808439 0.0047979590 0.0096808439 0.0101737880 0.0041810000 15103485 955859216 1373700096 -0.0745789260 0.0101476703 0.2204380631 303 12.0800000000 0.0096675782 0.0048140304 0.0096808439 0.0101600420 0.0041780000 15105461 955859216 1373700096 -0.0769724324 0.0101792337 0.2187715173 304 12.1200000000 0.0095483568 0.0048296038 0.0096808439 0.0101493094 0.0041960000 15107437 955859216 1373700096 -0.0793643668 0.0101439022 0.2173451036 305 12.1600000000 0.0096289683 0.0048453394 0.0096808439 0.0101411927 0.0042000000 15109413 955859216 1373700096 -0.0818599761 0.0103910202 0.2156981081 306 12.2000000000 0.0096881650 0.0048611657 0.0096881650 0.0101270996 0.0042200000 15111389 955859216 1373700096 -0.0844344199 0.0106014451 0.2143101692 307 12.2400000000 0.0096974140 0.0048769189 0.0096974140 0.0101108065 0.0042270000 15113365 955859216 1373700096 -0.0868923888 0.0106512364 0.2127510905 308 12.2800000000 0.0095328307 0.0048920355 0.0096974140 0.0100950506 0.0042440000 15115341 955859216 1373700096 -0.0892542377 0.0103500001 0.2114616036 309 12.3200000000 0.0094922734 0.0049069230 0.0096974140 0.0100853270 0.0042290000 15117317 955859216 1373700096 -0.0916288942 0.0100575397 0.2101161331 310 12.3600000000 0.0096428255 0.0049222001 0.0096974140 0.0100763101 0.0042600000 15119293 955859216 1373700096 -0.0941061378 0.0099879336 0.2086582333 311 12.4000000000 0.0098245423 0.0049379633 0.0098245423 0.0100604665 0.0041760000 15121269 955859216 1373700096 -0.0966004282 0.0095633967 0.2076883912 312 12.4400000000 0.0097275833 0.0049533146 0.0098245423 0.0100445569 0.0042790000 15123245 955859216 1373700096 -0.0991308689 0.0093034441 0.2065702528 313 12.4800000000 0.0097867111 0.0049687568 0.0098245423 0.0100298213 0.0042660000 15125221 955859216 1373700096 -0.1015035212 0.0089469515 0.2054174095 314 12.5200000000 0.0098509137 0.0049843051 0.0098509137 0.0100142384 0.0043220000 15127197 955859216 1373700096 -0.1041397899 0.0084835319 0.2045328021 315 12.5600000000 0.0097867977 0.0049995511 0.0098509137 0.0099999273 0.0042580000 15129173 955859216 1373700096 -0.1062107086 0.0074468791 0.2036604434 316 12.6000000000 0.0096438862 0.0050142483 0.0098509137 0.0099889197 0.0043120000 15131149 955859216 1373700096 -0.1087276116 0.0069353068 0.2029214948 317 12.6400000000 0.0095093753 0.0050284285 0.0098509137 0.0099786884 0.0043460000 15133125 955859216 1373700096 -0.1107377708 0.0061631775 0.2019593269 318 12.6800000000 0.0094831390 0.0050424371 0.0098509137 0.0099807299 0.0043380000 15135101 955859216 1373700096 -0.1126898453 0.0054078717 0.2011743039 319 12.7200000000 0.0096688643 0.0050569400 0.0098509137 0.0099767052 0.0043610000 15137077 955859216 1373700096 -0.1145696044 0.0048578875 0.1999175400 320 12.7600000000 0.0099878665 0.0050723491 0.0099878665 0.0099624106 0.0043010000 15139053 955859216 1373700096 -0.1161833405 0.0040929494 0.1987352818 321 12.8000000000 0.0100439936 0.0050878371 0.0100439936 0.0099472050 0.0043310000 15141029 955859216 1373700096 -0.1176632494 0.0032697525 0.1974319369 322 12.8400000000 0.0099497633 0.0051029363 0.0100439936 0.0099346647 0.0043390000 15143005 955859216 1373700096 -0.1190628558 0.0021318127 0.1963304728 323 12.8800000000 0.0101637207 0.0051186043 0.0101637207 0.0099283515 0.0043200000 15144981 955859216 1373700096 -0.1206147075 0.0015510496 0.1949974000 324 12.9200000000 0.0102175949 0.0051343419 0.0102175949 0.0099168464 0.0043350000 15146957 955859216 1373700096 -0.1222713664 0.0010286801 0.1934535056 325 12.9600000000 0.0101332841 0.0051497233 0.0102175949 0.0099042846 0.0043320000 15148933 955859216 1373700096 -0.1238125563 0.0003064482 0.1920360327 326 13.0000000000 0.0100693777 0.0051648143 0.0102175949 0.0098947049 0.0043390000 15150909 955859216 1373700096 -0.1251113713 -0.0004747470 0.1905045956 327 13.0400000000 0.0101595456 0.0051800887 0.0102175949 0.0098857930 0.0043760000 15152885 955859216 1373700096 -0.1265198439 -0.0011430066 0.1888524145 328 13.0800000000 0.0102324309 0.0051954922 0.0102324309 0.0098737985 0.0043500000 15154861 955859216 1373700096 -0.1277423948 -0.0018599331 0.1874118596 329 13.1200000000 0.0102096256 0.0052107327 0.0102324309 0.0098638578 0.0043780000 15156837 955859216 1373700096 -0.1289587021 -0.0025219626 0.1856450438 330 13.1600000000 0.0102510573 0.0052260064 0.0102510573 0.0098535199 0.0045120000 15158813 955859216 1373700096 -0.1302530020 -0.0033098571 0.1838833690 331 13.2000000000 0.0103485938 0.0052414825 0.0103485938 0.0098436677 0.0044800000 15160789 955859216 1373700096 -0.1316253245 -0.0038909530 0.1818782389 332 13.2400000000 0.0103052808 0.0052567349 0.0103485938 0.0098348633 0.0045060000 15162765 955859216 1373700096 -0.1329416782 -0.0045747096 0.1799516678 333 13.2800000000 0.0104539245 0.0052723421 0.0104539245 0.0098298379 0.0044460000 15164741 955859216 1373700096 -0.1340988278 -0.0049127643 0.1774972975 334 13.3200000000 0.0104351938 0.0052877997 0.0104539245 0.0098198844 0.0044740000 15166717 955859216 1373700096 -0.1354451925 -0.0051558912 0.1751826108 335 13.3600000000 0.0100605236 0.0053020467 0.0104539245 0.0098114914 0.0044620000 15168693 955859216 1373700096 -0.1365817934 -0.0062439749 0.1732354760 336 13.4000000000 0.0102803456 0.0053168630 0.0104539245 0.0098367906 0.0045090000 15170669 955859216 1373700096 -0.1375974268 -0.0065405685 0.1706344038 337 13.4400000000 0.0105413152 0.0053323658 0.0105413152 0.0098458236 0.0045310000 15172645 955859216 1373700096 -0.1388408095 -0.0063678627 0.1672640890 338 13.4800000000 0.0104859034 0.0053476130 0.0105413152 0.0098433435 0.0045040000 15174621 955859216 1373700096 -0.1401549727 -0.0065421178 0.1648578793 339 13.5200000000 0.0106602246 0.0053632844 0.0106602246 0.0098418343 0.0045320000 15176597 955859216 1373700096 -0.1413935125 -0.0063429652 0.1621521860 340 13.5600000000 0.0108380206 0.0053793866 0.0108380206 0.0098295554 0.0044890000 15178573 955859216 1373700096 -0.1426149607 -0.0060421596 0.1593827903 341 13.6000000000 0.0108334245 0.0053953808 0.0108380206 0.0098151029 0.0045480000 15180549 955859216 1373700096 -0.1438576877 -0.0058556832 0.1568712145 342 13.6400000000 0.0106810331 0.0054108360 0.0108380206 0.0098007237 0.0045580000 15182525 955859216 1373700096 -0.1450587958 -0.0059023248 0.1542195380 343 13.6800000000 0.0105135655 0.0054257127 0.0108380206 0.0097869249 0.0045740000 15184501 955859216 1373700096 -0.1459857374 -0.0062980535 0.1516478211 344 13.7200000000 0.0105773360 0.0054406884 0.0108380206 0.0097806785 0.0045450000 15186477 955859216 1373700096 -0.1469837576 -0.0062969364 0.1483705193 345 13.7600000000 0.0107254963 0.0054560066 0.0108380206 0.0097721179 0.0045120000 15188453 955859216 1373700096 -0.1479896605 -0.0061393734 0.1452576816 346 13.8000000000 0.0106812334 0.0054711085 0.0108380206 0.0097584412 0.0045840000 15190429 955859216 1373700096 -0.1489886642 -0.0059947819 0.1424607188 347 13.8400000000 0.0106360056 0.0054859929 0.0108380206 0.0097443720 0.0045880000 15192405 955859216 1373700096 -0.1498885304 -0.0061509404 0.1395477206 348 13.8800000000 0.0105218003 0.0055004636 0.0108380206 0.0097308258 0.0045630000 15194381 955859216 1373700096 -0.1508978009 -0.0063763335 0.1370130777 349 13.9200000000 0.0105553912 0.0055149476 0.0108380206 0.0097186490 0.0045570000 15196357 955859216 1373700096 -0.1517485082 -0.0068025091 0.1341709346 350 13.9600000000 0.0105704283 0.0055293919 0.0108380206 0.0097084645 0.0045600000 15198333 955859216 1373700096 -0.1524078399 -0.0071559870 0.1309622228 351 14.0000000000 0.0105211670 0.0055436134 0.0108380206 0.0096978682 0.0045870000 15200309 955859216 1373700096 -0.1531423777 -0.0076316250 0.1281686872 352 14.0400000000 0.0105253439 0.0055577661 0.0108380206 0.0096910875 0.0045680000 15202285 955859216 1373700096 -0.1538346261 -0.0079615889 0.1250903904 353 14.0800000000 0.0105208401 0.0055718258 0.0108380206 0.0096829772 0.0045640000 15204261 955859216 1373700096 -0.1545873880 -0.0082175843 0.1222740412 354 14.1200000000 0.0106513342 0.0055861747 0.0108380206 0.0096716470 0.0045940000 15206237 955859216 1373700096 -0.1554655582 -0.0081263585 0.1194029823 355 14.1600000000 0.0105659757 0.0056002023 0.0108380206 0.0096581270 0.0045920000 15208213 955859216 1373700096 -0.1562185585 -0.0081384741 0.1169856116 356 14.2000000000 0.0105664963 0.0056141526 0.0108380206 0.0096446269 0.0046430000 15210189 955859216 1373700096 -0.1569596976 -0.0082679978 0.1143004447 357 14.2400000000 0.0107178092 0.0056284485 0.0108380206 0.0096313139 0.0046120000 15212165 955859216 1373700096 -0.1576802284 -0.0082178498 0.1116316617 358 14.2800000000 0.0106805591 0.0056425606 0.0108380206 0.0096218614 0.0047430000 15214141 955859216 1373700096 -0.1585354954 -0.0080355778 0.1095009521 359 14.3200000000 0.0103911329 0.0056557878 0.0108380206 0.0096146943 0.0047890000 15216117 955859216 1373700096 -0.1591447741 -0.0086135175 0.1069614068 360 14.3600000000 0.0103196679 0.0056687430 0.0108380206 0.0096024517 0.0046040000 15218093 955859216 1373700096 -0.1593908370 -0.0094720731 0.1046421826 361 14.4000000000 0.0104213413 0.0056819081 0.0108380206 0.0095990701 0.0045740000 15220069 955859216 1373700096 -0.1598729938 -0.0097309779 0.1023959443 362 14.4400000000 0.0104720537 0.0056951405 0.0108380206 0.0095881024 0.0046070000 15222045 955859216 1373700096 -0.1603341848 -0.0098128784 0.0995933041 363 14.4800000000 0.0102407141 0.0057076628 0.0108380206 0.0095754518 0.0046160000 15224021 955859216 1373700096 -0.1607739925 -0.0102145383 0.0975308493 364 14.5200000000 0.0101593630 0.0057198927 0.0108380206 0.0095672615 0.0045880000 15225997 955859216 1373700096 -0.1609593332 -0.0104900319 0.0951267630 365 14.5600000000 0.0100383358 0.0057317241 0.0108380206 0.0095567282 0.0046180000 15227973 955859216 1373700096 -0.1614280194 -0.0097897118 0.0926699936 366 14.6000000000 0.0098028854 0.0057428475 0.0108380206 0.0095469882 0.0046090000 15229949 955859216 1373700096 -0.1618868858 -0.0093337130 0.0902078152 367 14.6400000000 0.0097020650 0.0057536355 0.0108380206 0.0095381430 0.0046270000 15231925 955859216 1373700096 -0.1619932204 -0.0104419962 0.0878714696 368 14.6800000000 0.0098923407 0.0057648820 0.0108380206 0.0095287291 0.0046820000 15233901 955859216 1373700096 -0.1621962488 -0.0112649119 0.0854455084 369 14.7200000000 0.0098189944 0.0057758688 0.0108380206 0.0095193770 0.0046480000 15235877 955859216 1373700096 -0.1625411808 -0.0111801913 0.0832321718 370 14.7600000000 0.0096267397 0.0057862765 0.0108380206 0.0095074527 0.0047470000 15237853 955859216 1373700096 -0.1630434394 -0.0105587775 0.0810088217 371 14.8000000000 0.0095513845 0.0057964251 0.0108380206 0.0094948800 0.0047460000 15239829 955859216 1373700096 -0.1635771841 -0.0098482817 0.0782803744 372 14.8400000000 0.0094739255 0.0058063108 0.0108380206 0.0094883185 0.0047130000 15241805 955859216 1373700096 -0.1639491618 -0.0097634289 0.0753517076 373 14.8800000000 0.0096284123 0.0058165577 0.0108380206 0.0094816650 0.0047880000 15243781 955859216 1373700096 -0.1644148827 -0.0096008293 0.0725768656 374 14.9200000000 0.0098149916 0.0058272487 0.0108380206 0.0094866277 0.0047420000 15245757 955859216 1373700096 -0.1651742458 -0.0095047262 0.0702505335 375 14.9600000000 0.0097737405 0.0058377727 0.0108380206 0.0095005287 0.0048070000 15247733 955859216 1373700096 -0.1656934172 -0.0106130755 0.0683561638 376 15.0000000000 0.0098979268 0.0058485710 0.0108380206 0.0094910577 0.0048790000 15249709 955859216 1373700096 -0.1662234068 -0.0113435099 0.0659908950 377 15.0400000000 0.0102012269 0.0058601165 0.0108380206 0.0094791643 0.0048220000 15251685 955859216 1373700096 -0.1670336127 -0.0107448185 0.0636259168 378 15.0800000000 0.0100434842 0.0058711836 0.0108380206 0.0094890181 0.0048260000 15253661 955859216 1373700096 -0.1674548984 -0.0109889526 0.0608570501 379 15.1200000000 0.0098766861 0.0058817522 0.0108380206 0.0094847332 0.0047940000 15255637 955859216 1373700096 -0.1679971963 -0.0117549775 0.0584576204 380 15.1600000000 0.0100581823 0.0058927428 0.0108380206 0.0094722697 0.0047720000 15257613 955859216 1373700096 -0.1686015129 -0.0118469801 0.0556102805 381 15.2000000000 0.0100150350 0.0059035625 0.0108380206 0.0094611370 0.0047650000 15259589 955859216 1373700096 -0.1695404351 -0.0117818769 0.0534978248 382 15.2400000000 0.0100098699 0.0059143120 0.0108380206 0.0094499719 0.0047440000 15261565 955859216 1373700096 -0.1699548066 -0.0121905059 0.0505628027 383 15.2800000000 0.0101330625 0.0059253270 0.0108380206 0.0094377125 0.0047270000 15263541 955859216 1373700096 -0.1707180440 -0.0122207180 0.0483879559 384 15.3200000000 0.0101787159 0.0059364035 0.0108380206 0.0094262927 0.0048140000 15265517 955859216 1373700096 -0.1718255877 -0.0120399762 0.0458140448 385 15.3600000000 0.0101924334 0.0059474582 0.0108380206 0.0094164995 0.0047410000 15267493 955859216 1373700096 -0.1730448753 -0.0117228664 0.0435389280 386 15.4000000000 0.0101665659 0.0059583885 0.0108380206 0.0094058802 0.0047930000 15269469 955859216 1373700096 -0.1738247275 -0.0115897311 0.0406492203 387 15.4400000000 0.0102367802 0.0059694438 0.0108380206 0.0093941663 0.0047710000 15271445 955859216 1373700096 -0.1747971773 -0.0111761568 0.0380185954 388 15.4800000000 0.0102615105 0.0059805058 0.0108380206 0.0093860858 0.0049970000 15273421 955859216 1373700096 -0.1764125973 -0.0104956739 0.0359396972 389 15.5200000000 0.0102184163 0.0059914002 0.0108380206 0.0093827259 0.0047700000 15275397 955859216 1373700096 -0.1772458255 -0.0100496355 0.0331804715 390 15.5600000000 0.0101873586 0.0060021590 0.0108380206 0.0093765042 0.0047860000 15277373 955859216 1373700096 -0.1787163764 -0.0097007584 0.0309429560 391 15.6000000000 0.0103671877 0.0060133228 0.0108380206 0.0093675373 0.0047140000 15279349 955859216 1373700096 -0.1802663803 -0.0089274440 0.0286112502 392 15.6400000000 0.0103499284 0.0060243856 0.0108380206 0.0093680829 0.0047330000 15281325 955859216 1373700096 -0.1815605313 -0.0083080996 0.0261068922 393 15.6800000000 0.0103861606 0.0060354842 0.0108380206 0.0093662490 0.0047680000 15283301 955859216 1373700096 -0.1825366467 -0.0080734808 0.0237127636 394 15.7200000000 0.0104638441 0.0060467237 0.0108380206 0.0093618585 0.0047400000 15285277 955859216 1373700096 -0.1837996244 -0.0076748538 0.0214206912 395 15.7600000000 0.0105919242 0.0060582305 0.0108380206 0.0093555299 0.0047320000 15287253 955859216 1373700096 -0.1855464429 -0.0069802613 0.0188289508 396 15.8000000000 0.0106605580 0.0060698526 0.0108380206 0.0093514283 0.0047820000 15289229 955859216 1373700096 -0.1864955127 -0.0061883978 0.0159725342 397 15.8400000000 0.0106129535 0.0060812962 0.0108380206 0.0093556919 0.0048200000 15291205 955859216 1373700096 -0.1878720671 -0.0054534394 0.0138878478 398 15.8800000000 0.0103723835 0.0060920778 0.0108380206 0.0093649915 0.0048180000 15293181 955859216 1373700096 -0.1890476197 -0.0056081000 0.0114025790 399 15.9200000000 0.0103735048 0.0061028082 0.0108380206 0.0093574432 0.0048190000 15295157 955859216 1373700096 -0.1901743859 -0.0057207607 0.0091938935 400 15.9600000000 0.0106966570 0.0061142928 0.0108380206 0.0093470014 0.0048480000 15297133 955859216 1373700096 -0.1913669258 -0.0049418896 0.0067107459 401 16.0000000000 0.0105845584 0.0061254406 0.0108380206 0.0093513970 0.0048240000 15299109 955859216 1373700096 -0.1923465282 -0.0046388344 0.0044128159 402 16.0400000000 0.0106192548 0.0061366192 0.0108380206 0.0093478779 0.0048680000 15301085 955859216 1373700096 -0.1935389489 -0.0043228846 0.0022352629 403 16.0800000000 0.0107693290 0.0061481148 0.0108380206 0.0093502037 0.0049190000 15303061 955859216 1373700096 -0.1945684999 -0.0038030928 0.0000126343 404 16.1200000000 0.0108900415 0.0061598522 0.0108900415 0.0093668742 0.0048480000 15305037 955859216 1373700096 -0.1949148476 -0.0034651232 -0.0025846225 405 16.1600000000 0.0106308963 0.0061708919 0.0108900415 0.0093871999 0.0050100000 15307013 955859216 1373700096 -0.1959574372 -0.0034207890 -0.0043332586 406 16.2000000000 0.0109775336 0.0061827309 0.0109775336 0.0093829695 0.0047280000 15308989 955859216 1373700096 -0.1965718418 -0.0024098989 -0.0067250412 407 16.2400000000 0.0108188866 0.0061941219 0.0109775336 0.0093985376 0.0050710000 15310965 955859216 1373700096 -0.1975100189 -0.0020718894 -0.0084878979 408 16.2800000000 0.0108898645 0.0062056311 0.0109775336 0.0094038254 0.0049650000 15312941 955859216 1373700096 -0.1979287267 -0.0020164219 -0.0105855009 409 16.3200000000 0.0109533379 0.0062172392 0.0109775336 0.0093971499 0.0050140000 15314917 955859216 1373700096 -0.1985696405 -0.0020252457 -0.0126657980 410 16.3600000000 0.0113742938 0.0062298174 0.0113742938 0.0093880494 0.0050050000 15316893 955859216 1373700096 -0.1989940405 -0.0013620264 -0.0148243131 411 16.3999999990 0.0113723865 0.0062423297 0.0113742938 0.0093949027 0.0050110000 15318869 955859216 1373700096 -0.1995041668 -0.0008617616 -0.0169130843 412 16.4400000000 0.0113852825 0.0062548126 0.0113852825 0.0094004784 0.0050640000 15320845 955859216 1373700096 -0.2000524700 -0.0002305061 -0.0191069543 413 16.4800000000 0.0113525484 0.0062671558 0.0113852825 0.0093989201 0.0050680000 15322821 955859216 1373700096 -0.2007437944 -0.0000572768 -0.0211150367 414 16.5200000000 0.0114178909 0.0062795972 0.0114178909 0.0093913428 0.0050270000 15324797 955859216 1373700096 -0.2010961175 0.0000578533 -0.0232922621 415 16.5599999990 0.0117803160 0.0062928519 0.0117803160 0.0093807676 0.0039770000 15326773 955859216 1373700096 -0.2014172226 0.0005367203 -0.0258119516 416 16.6000000000 0.0117371548 0.0063059392 0.0117803160 0.0093740708 0.0050560000 15328749 955859216 1373700096 -0.2018925846 0.0007327485 -0.0279885940 417 16.6400000000 0.0119362874 0.0063194412 0.0119362874 0.0093688812 0.0051080000 15330725 955859216 1373700096 -0.2026148438 0.0011281648 -0.0303734206 418 16.6800000000 0.0120387068 0.0063331237 0.0120387068 0.0093686247 0.0050190000 15332701 955859216 1373700096 -0.2036972940 0.0020043848 -0.0328311995 419 16.7199999990 0.0121320365 0.0063469636 0.0121320365 0.0093810441 0.0050170000 15334677 955859216 1373700096 -0.2041565627 0.0031590296 -0.0355740674 420 16.7600000000 0.0115617244 0.0063593796 0.0121320365 0.0094022826 0.0050780000 15336653 955859216 1373700096 -0.2043258846 0.0037304906 -0.0380979776 421 16.8000000000 0.0116395429 0.0063719216 0.0121320365 0.0093991062 0.0050180000 15338629 955859216 1373700096 -0.2047032118 0.0042877663 -0.0408676937 422 16.8400000000 0.0117497677 0.0063846653 0.0121320365 0.0093943381 0.0040110000 15340605 955859216 1373700096 -0.2043948770 0.0049261856 -0.0437200442 423 16.8799999990 0.0116953347 0.0063972201 0.0121320365 0.0093894121 0.0039770000 15342581 955859216 1373700096 -0.2051126659 0.0055943020 -0.0462536924 424 16.9200000000 0.0118450494 0.0064100687 0.0121320365 0.0093844301 0.0050800000 15344557 955859216 1373700096 -0.2054484487 0.0064596385 -0.0492733754 425 16.9600000000 0.0115912724 0.0064222598 0.0121320365 0.0094005106 0.0050720000 15346533 955859216 1373700096 -0.2052024305 0.0070506535 -0.0523536466 426 17.0000000000 0.0113042668 0.0064337199 0.0121320365 0.0093990867 0.0050700000 15348509 955859216 1373700096 -0.2050409764 0.0074742748 -0.0552584194 427 17.0400000000 0.0110920509 0.0064446294 0.0121320365 0.0093888247 0.0050470000 15350485 955859216 1373700096 -0.2050398588 0.0073963590 -0.0580580346 428 17.0800000000 0.0113496697 0.0064560897 0.0121320365 0.0093780120 0.0050450000 15352461 955859216 1373700096 -0.2036522031 0.0077596279 -0.0615068637 429 17.1200000000 0.0112545332 0.0064672749 0.0121320365 0.0093681137 0.0051200000 15354437 955859216 1373700096 -0.2031150013 0.0080267359 -0.0646691322 430 17.1600000000 0.0113049718 0.0064785254 0.0121320365 0.0093574841 0.0050220000 15356413 955859216 1373700096 -0.2034422606 0.0082442313 -0.0676138029 431 17.2000000000 0.0116147613 0.0064904424 0.0121320365 0.0093467641 0.0050120000 15358389 955859216 1373700096 -0.2030617744 0.0087300213 -0.0711458996 432 17.2400000000 0.0116193034 0.0065023148 0.0121320365 0.0093411647 0.0050530000 15360365 955859216 1373700096 -0.2030028850 0.0091644190 -0.0741001591 433 17.2800000000 0.0114896400 0.0065138328 0.0121320365 0.0093387651 0.0050800000 15362341 955859216 1373700096 -0.2030846924 0.0096203098 -0.0773623437 434 17.3200000000 0.0115583474 0.0065254561 0.0121320365 0.0093318633 0.0039760000 15364317 955859216 1373700096 -0.2028574795 0.0099234004 -0.0804700926 435 17.3600000000 0.0119852265 0.0065380073 0.0121320365 0.0093227244 0.0050850000 15366293 955859216 1373700096 -0.2029817700 0.0108246021 -0.0839131549 436 17.4000000000 0.0116693350 0.0065497764 0.0121320365 0.0093305187 0.0050710000 15368269 955859216 1373700096 -0.2023028433 0.0116119040 -0.0871114060 437 17.4400000000 0.0113550154 0.0065607724 0.0121320365 0.0093457274 0.0050410000 15370245 955859216 1373700096 -0.2016477734 0.0122380154 -0.0899488106 438 17.4800000000 0.0112263039 0.0065714243 0.0121320365 0.0093428656 0.0051270000 15372221 955859216 1373700096 -0.2005860060 0.0127095748 -0.0931751505 439 17.5200000000 0.0111752683 0.0065819114 0.0121320365 0.0093413732 0.0051010000 15374197 955859216 1373700096 -0.1985338330 0.0132401669 -0.0963193849 440 17.5600000000 0.0110830450 0.0065921413 0.0121320365 0.0093458079 0.0050570000 15376173 955859216 1373700096 -0.1977426112 0.0135939820 -0.0989641175 441 17.6000000000 0.0111088250 0.0066023832 0.0121320365 0.0093502190 0.0050710000 15378149 955859216 1373700096 -0.1969905645 0.0141092818 -0.1015810817 442 17.6400000000 0.0109201986 0.0066121520 0.0121320365 0.0093608854 0.0051070000 15380125 955859216 1373700096 -0.1967482120 0.0140161105 -0.1042966917 443 17.6800000000 0.0107670547 0.0066215310 0.0121320365 0.0093633517 0.0050730000 15382101 955859216 1373700096 -0.1965307891 0.0136180529 -0.1066285223 444 17.7200000000 0.0109699368 0.0066313247 0.0121320365 0.0093564993 0.0050920000 15384077 955859216 1373700096 -0.1963973790 0.0133475037 -0.1092895120 445 17.7600000000 0.0114031266 0.0066420479 0.0121320365 0.0093460075 0.0040320000 15386053 955859216 1373700096 -0.1964366436 0.0136465747 -0.1121282876 446 17.8000000000 0.0113184545 0.0066525331 0.0121320365 0.0093362585 0.0040250000 15388029 955859216 1373700096 -0.1963812560 0.0138802985 -0.1148106679 447 17.8400000000 0.0115165208 0.0066634145 0.0121320365 0.0093295010 0.0053730000 15390005 955859216 1373700096 -0.1965704709 0.0142289912 -0.1173794568 448 17.8800000000 0.0112874461 0.0066737360 0.0121320365 0.0093204448 0.0052500000 15391981 955859216 1373700096 -0.1961821616 0.0145148151 -0.1198237687 449 17.9200000000 0.0108032087 0.0066829330 0.0121320365 0.0093128873 0.0052080000 15393957 955859216 1373700096 -0.1956534237 0.0140522122 -0.1220038384 450 17.9600000000 0.0115492865 0.0066937471 0.0121320365 0.0093026539 0.0052130000 15395933 955859216 1373700096 -0.1957367063 0.0141686127 -0.1270783395 451 18.0000000000 0.0112249199 0.0067037941 0.0121320365 0.0093086596 0.0040920000 15397909 955859216 1373700096 -0.1958701313 0.0143012423 -0.1296628416 452 18.0400000000 0.0107362736 0.0067127155 0.0121320365 0.0093148758 0.0052860000 15399885 955859216 1373700096 -0.1961953938 0.0136505943 -0.1317418218 453 18.0800000000 0.0107908919 0.0067217181 0.0121320365 0.0093199935 0.0052420000 15401861 955859216 1373700096 -0.1963465363 0.0129671991 -0.1340925992 454 18.1200000000 0.0112036094 0.0067315901 0.0121320365 0.0093154787 0.0052300000 15403837 955859216 1373700096 -0.1967778504 0.0130371731 -0.1369623542 455 18.1600000000 0.0117342202 0.0067425849 0.0121320365 0.0093053530 0.0052240000 15405813 955859216 1373700096 -0.1973780841 0.0136434706 -0.1400095224 456 18.2000000000 0.0117483297 0.0067535624 0.0121320365 0.0092958980 0.0051910000 15407789 955859216 1373700096 -0.1977976263 0.0145970713 -0.1427088827 457 18.2400000000 0.0111094713 0.0067630939 0.0121320365 0.0092976512 0.0026030000 15409765 955859216 1373700096 -0.1982451528 0.0150378020 -0.1450895220 458 18.2800000000 0.0113140009 0.0067730304 0.0121320365 0.0092948169 0.0053010000 15411741 955859216 1373700096 -0.1989990771 0.0155621413 -0.1479025334 459 18.3200000000 0.0110448916 0.0067823373 0.0121320365 0.0093106513 0.0053730000 15413717 955859216 1373700096 -0.1999714524 0.0160181522 -0.1504890621 460 18.3600000000 0.0108342478 0.0067911458 0.0121320365 0.0093160725 0.0052030000 15415693 955859216 1373700096 -0.2002893537 0.0163984112 -0.1533734053 461 18.4000000000 0.0109004332 0.0068000597 0.0121320365 0.0093131244 0.0052450000 15417669 955859216 1373700096 -0.2010866255 0.0166215934 -0.1562213302 462 18.4400000000 0.0104706539 0.0068080047 0.0121320365 0.0093340283 0.0052450000 15419645 955859216 1373700096 -0.2014965564 0.0163090769 -0.1586721092 463 18.4800000000 0.0106025543 0.0068162002 0.0121320365 0.0093402622 0.0040710000 15421621 955859216 1373700096 -0.2020058334 0.0163202584 -0.1616258174 464 18.5200000000 0.0103409756 0.0068237967 0.0121320365 0.0093407552 0.0040810000 15423597 955859216 1373700096 -0.2028180957 0.0159648210 -0.1641100496 465 18.5600000000 0.0105843209 0.0068318839 0.0121320365 0.0093385751 0.0052550000 15425573 955859216 1373700096 -0.2035689652 0.0161299016 -0.1672278196 466 18.6000000000 0.0110803731 0.0068410008 0.0121320365 0.0093297448 0.0052360000 15427549 955859216 1373700096 -0.2049229592 0.0168643724 -0.1705960482 467 18.6400000000 0.0113207409 0.0068505934 0.0121320365 0.0093197917 0.0052800000 15429525 955859216 1373700096 -0.2062351257 0.0177818220 -0.1737588048 468 18.6800000000 0.0114068156 0.0068603289 0.0121320365 0.0093105276 0.0052620000 15431501 955859216 1373700096 -0.2074023187 0.0188489836 -0.1768948436 469 18.7200000000 0.0110543156 0.0068692713 0.0121320365 0.0093099672 0.0052630000 15433477 955859216 1373700096 -0.2082732618 0.0196353048 -0.1797247529 470 18.7600000000 0.0117533607 0.0068796630 0.0121320365 0.0093008209 0.0055110000 15435453 955859216 1373700096 -0.2097297311 0.0215682480 -0.1831949651 471 18.8000000000 0.0106147928 0.0068875932 0.0121320365 0.0093290207 0.0041730000 15437429 955859216 1373700096 -0.2104624510 0.0225534923 -0.1857601553 472 18.8400000000 0.0102924621 0.0068948069 0.0121320365 0.0094176505 0.0052400000 15439405 955859216 1373700096 -0.2113280743 0.0240762141 -0.1887346357 473 18.8800000000 0.0096950708 0.0069007272 0.0121320365 0.0094816802 0.0053260000 15441381 955859216 1373700096 -0.2123114765 0.0244050063 -0.1916470379 474 18.9200000000 0.0100912992 0.0069074583 0.0121320365 0.0094825728 0.0053500000 15443357 955859216 1373700096 -0.2140502632 0.0244442113 -0.1944799423 475 18.9600000000 0.0105688414 0.0069151665 0.0121320365 0.0094790355 0.0041940000 15445333 955859216 1373700096 -0.2154406607 0.0252520218 -0.1973819435 476 19.0000000000 0.0105896024 0.0069228859 0.0121320365 0.0094954187 0.0053790000 15447309 955859216 1373700096 -0.2165690064 0.0268679764 -0.2002357841 477 19.0400000000 0.0107578551 0.0069309257 0.0121320365 0.0094944690 0.0053750000 15449285 955859216 1373700096 -0.2173581570 0.0286450014 -0.2032987028 478 19.0800000000 0.0111471545 0.0069397462 0.0121320365 0.0094861057 0.0053080000 15451261 955859216 1373700096 -0.2184295207 0.0303830504 -0.2060012668 479 19.1200000000 0.0108211264 0.0069478493 0.0121320365 0.0094842127 0.0053150000 15453237 955859216 1373700096 -0.2196748257 0.0316906348 -0.2084367424 480 19.1600000000 0.0106070098 0.0069554726 0.0121320365 0.0094860419 0.0053370000 15455213 955859216 1373700096 -0.2206755728 0.0328686275 -0.2110392600 481 19.2000000000 0.0105116600 0.0069628659 0.0121320365 0.0094828415 0.0053630000 15457189 955859216 1373700096 -0.2216188610 0.0337197892 -0.2134189457 482 19.2400000000 0.0105425250 0.0069702926 0.0121320365 0.0094805205 0.0053580000 15459165 955859216 1373700096 -0.2227226496 0.0347198136 -0.2159889489 483 19.2800000000 0.0098978747 0.0069763538 0.0121320365 0.0094996333 0.0053740000 15461141 955859216 1373700096 -0.2235235423 0.0347558036 -0.2179949433 484 19.3200000000 0.0101253400 0.0069828600 0.0121320365 0.0094977784 0.0041480000 15463117 955859216 1373700096 -0.2241289467 0.0349115841 -0.2200645953 485 19.3600000000 0.0102325883 0.0069895605 0.0121320365 0.0094896619 0.0053480000 15465093 955859216 1373700096 -0.2244598567 0.0350303501 -0.2218864411 486 19.4000000000 0.0104708122 0.0069967235 0.0121320365 0.0094811998 0.0053150000 15467069 955859216 1373700096 -0.2247699946 0.0354302116 -0.2239568979 487 19.4400000000 0.0106425937 0.0070042099 0.0121320365 0.0094750736 0.0053410000 15469045 955859216 1373700096 -0.2252965719 0.0362928808 -0.2260292917 488 19.4800000000 0.0105778305 0.0070115329 0.0121320365 0.0094713626 0.0053220000 15471021 955859216 1373700096 -0.2256285846 0.0370937251 -0.2281766087 489 19.5200000000 0.0101123275 0.0070178740 0.0121320365 0.0094748502 0.0053580000 15472997 955859216 1373700096 -0.2258693278 0.0372174196 -0.2299306691 490 19.5600000000 0.0103079416 0.0070245884 0.0121320365 0.0094700556 0.0054090000 15474973 955859216 1373700096 -0.2260476500 0.0377314314 -0.2319783270 491 19.6000000000 0.0104504991 0.0070315658 0.0121320365 0.0094623049 0.0041670000 15476949 955859216 1373700096 -0.2268707007 0.0378497876 -0.2339612544 492 19.6400000000 0.0107024591 0.0070390270 0.0121320365 0.0094539064 0.0053970000 15478925 955859216 1373700096 -0.2267063260 0.0385197885 -0.2360343933 493 19.6800000000 0.0104021654 0.0070458488 0.0121320365 0.0094489166 0.0053370000 15480901 955859216 1373700096 -0.2268712372 0.0389652587 -0.2378727645 494 19.7200000000 0.0106474115 0.0070531394 0.0121320365 0.0094414832 0.0053680000 15482877 955859216 1373700096 -0.2265494019 0.0397034548 -0.2399051934 495 19.7600000000 0.0101514272 0.0070593986 0.0121320365 0.0094432451 0.0054350000 15484853 955859216 1373700096 -0.2274309248 0.0397607647 -0.2418621778 496 19.8000000000 0.0101971906 0.0070657248 0.0121320365 0.0094439793 0.0053850000 15486829 955859216 1373700096 -0.2287868410 0.0398062356 -0.2442650497 497 19.8400000000 0.0100891357 0.0070718081 0.0121320365 0.0094407318 0.0053820000 15488805 955859216 1373700096 -0.2292912453 0.0393878557 -0.2462171912 498 19.8800000000 0.0097694816 0.0070772251 0.0121320365 0.0094354415 0.0041750000 15490781 955859216 1373700096 -0.2284027338 0.0379950367 -0.2475492805 499 19.9200000000 0.0103005022 0.0070836846 0.0121320365 0.0094266973 0.0041680000 15492757 955859216 1373700096 -0.2277813107 0.0375831686 -0.2498352975 500 19.9600000000 0.0105966236 0.0070907104 0.0121320365 0.0094175770 0.0053660000 15494733 955859216 1373700096 -0.2270352542 0.0378455892 -0.2522451282 501 20.0000000000 0.0096328789 0.0070957846 0.0121320365 0.0094300500 0.0053930000 15496709 955859216 1373700096 -0.2274710089 0.0367919877 -0.2543631792 502 20.0400000000 0.0096086860 0.0071007904 0.0121320365 0.0094477055 0.0053560000 15498685 955859216 1373700096 -0.2283585668 0.0360082164 -0.2571506202 503 20.0800000000 0.0103109460 0.0071071724 0.0121320365 0.0094402462 0.0053270000 15500661 955859216 1373700096 -0.2280842513 0.0364121720 -0.2601816058 504 20.1200000000 0.0105823670 0.0071140677 0.0121320365 0.0094315200 0.0053390000 15502637 955859216 1373700096 -0.2276544124 0.0367602371 -0.2625881135 505 20.1600000000 0.0109576834 0.0071216788 0.0121320365 0.0094231903 0.0053010000 15504613 955859216 1373700096 -0.2274073362 0.0375453532 -0.2654000819 506 20.2000000000 0.0110669741 0.0071294758 0.0121320365 0.0094148991 0.0053060000 15506589 955859216 1373700096 -0.2276065052 0.0384235121 -0.2678296566 507 20.2400000000 0.0103431661 0.0071358144 0.0121320365 0.0094098224 0.0041180000 15508565 955859216 1373700096 -0.2280806005 0.0380171984 -0.2701687515 508 20.2800000000 0.0104527902 0.0071423439 0.0121320365 0.0094033844 0.0054500000 15510541 955859216 1373700096 -0.2279217690 0.0378674939 -0.2729665935 509 20.3200000000 0.0103084464 0.0071485642 0.0121320365 0.0094003284 0.0053900000 15512517 955859216 1373700096 -0.2271099538 0.0375309475 -0.2750763595 510 20.3600000000 0.0106942300 0.0071555164 0.0121320365 0.0094029498 0.0053850000 15514493 955859216 1373700096 -0.2267128974 0.0381272323 -0.2774853706 511 20.4000000000 0.0108021041 0.0071626526 0.0121320365 0.0093960799 0.0054220000 15516469 955859216 1373700096 -0.2266445607 0.0385419093 -0.2801253796 512 20.4400000000 0.0108867101 0.0071699262 0.0121320365 0.0093878381 0.0054020000 15518445 955859216 1373700096 -0.2263825834 0.0390786342 -0.2829768360 513 20.4800000000 0.0113001997 0.0071779774 0.0121320365 0.0093805129 0.0054660000 15569573 955859216 1373700096 -0.2240273505 0.0401541144 -0.2860269547 514 20.5200000000 0.0108074723 0.0071850387 0.0121320365 0.0093749759 0.0054570000 15673949 955859216 1373700096 -0.2230740637 0.0405820571 -0.2889289260 515 20.5600000000 0.0106116273 0.0071916922 0.0121320365 0.0093684652 0.0041690000 15675925 955859216 1373700096 -0.2216841280 0.0402317606 -0.2916703820 516 20.6000000000 0.0106250951 0.0071983461 0.0121320365 0.0093652364 0.0054990000 15677901 955859216 1373700096 -0.2193717808 0.0397374630 -0.2943694890 517 20.6400000000 0.0108845206 0.0072054760 0.0121320365 0.0093580347 0.0054830000 15679877 955859216 1373700096 -0.2172639221 0.0397928655 -0.2968874276 518 20.6800000000 0.0110328104 0.0072128647 0.0121320365 0.0093528418 0.0054740000 15681853 955859216 1373700096 -0.2153986394 0.0404129662 -0.2994470894 519 20.7200000000 0.0110193267 0.0072201989 0.0121320365 0.0093482064 0.0054530000 15683829 955859216 1373700096 -0.2139761597 0.0410297140 -0.3020639420 520 20.7600000000 0.0105879111 0.0072266753 0.0121320365 0.0093432678 0.0054700000 15685805 955859216 1373700096 -0.2130869925 0.0411133282 -0.3043393493 521 20.8000000000 0.0110759148 0.0072340635 0.0121320365 0.0093352513 0.0054850000 15687781 955859216 1373700096 -0.2121676803 0.0417625271 -0.3066942692 522 20.8400000000 0.0115205245 0.0072422751 0.0121320365 0.0093273180 0.0054470000 15689757 955859216 1373700096 -0.2115745097 0.0433418043 -0.3091784418 523 20.8800000000 0.0111691877 0.0072497835 0.0121320365 0.0093189105 0.0055170000 15691733 955859216 1373700096 -0.2108783722 0.0441989042 -0.3113770485 524 20.9200000000 0.0110213710 0.0072569812 0.0121320365 0.0093113618 0.0054920000 15693709 955859216 1373700096 -0.2104911655 0.0443615653 -0.3137605786 525 20.9600000000 0.0111962752 0.0072644846 0.0121320365 0.0093054624 0.0055150000 15695685 955859216 1373700096 -0.2099718451 0.0443960130 -0.3161252141 526 21.0000000000 0.0114374710 0.0072724181 0.0121320365 0.0093011469 0.0055450000 15697661 955859216 1373700096 -0.2094677538 0.0447341204 -0.3183927834 527 21.0400000000 0.0115328990 0.0072805025 0.0121320365 0.0092961832 0.0055150000 15699637 955859216 1373700096 -0.2090011537 0.0448610745 -0.3203139007 528 21.0800000000 0.0118412925 0.0072891403 0.0121320365 0.0092974122 0.0042530000 15701613 955859216 1373700096 -0.2081358582 0.0448283441 -0.3222423494 529 21.1200000000 0.0116846673 0.0072974495 0.0121320365 0.0092964131 0.0045420000 15703589 955859216 1373700096 -0.2074196935 0.0440890975 -0.3240636885 530 21.1600000000 0.0117786657 0.0073059046 0.0121320365 0.0092975423 0.0055850000 15705565 955859216 1373700096 -0.2075058520 0.0438677669 -0.3258956373 531 21.2000000000 0.0119686257 0.0073146856 0.0121320365 0.0093039866 0.0055290000 15707541 955859216 1373700096 -0.2070009112 0.0439409912 -0.3278031647 532 21.2400000000 0.0117152426 0.0073229573 0.0121320365 0.0093146786 0.0055290000 15709517 955859216 1373700096 -0.2062510252 0.0428095870 -0.3293731809 533 21.2800000000 0.0118448017 0.0073314411 0.0121320365 0.0093227821 0.0042700000 15711493 955859216 1373700096 -0.2057453841 0.0422990657 -0.3309796154 534 21.3200000000 0.0116297351 0.0073394903 0.0121320365 0.0093169570 0.0055360000 15713469 955859216 1373700096 -0.2051744610 0.0416460335 -0.3323285878 535 21.3600000000 0.0115476009 0.0073473560 0.0121320365 0.0093141553 0.0055760000 15715445 955859216 1373700096 -0.2049595267 0.0407196507 -0.3336650431 536 21.4000000000 0.0119629502 0.0073559671 0.0121320365 0.0093127015 0.0055800000 15717421 955859216 1373700096 -0.2047148496 0.0404410101 -0.3353194892 537 21.4400000000 0.0116186589 0.0073639051 0.0121320365 0.0093112321 0.0055380000 15719397 955859216 1373700096 -0.2047781050 0.0398059301 -0.3364879489 538 21.4800000000 0.0120709203 0.0073726542 0.0121320365 0.0093216977 0.0056050000 15721373 955859216 1373700096 -0.2042867690 0.0392079093 -0.3377898633 539 21.5200000000 0.0119704828 0.0073811845 0.0121320365 0.0093386690 0.0056110000 15723349 955859216 1373700096 -0.2039589286 0.0382824205 -0.3390187621 540 21.5600000000 0.0120876022 0.0073899001 0.0121320365 0.0093463379 0.0056230000 15725325 955859216 1373700096 -0.2037514746 0.0378597677 -0.3402630389 541 21.6000000000 0.0120711159 0.0073985530 0.0121320365 0.0093507236 0.0043530000 15727301 955859216 1373700096 -0.2039659470 0.0375759043 -0.3415236771 542 21.6400000000 0.0117650628 0.0074066093 0.0121320365 0.0093514741 0.0043670000 15729277 955859216 1373700096 -0.2040175050 0.0365093052 -0.3426306844 543 21.6800000000 0.0116931824 0.0074145035 0.0121320365 0.0093541591 0.0056800000 15731253 955859216 1373700096 -0.2045750171 0.0355937146 -0.3437142372 544 21.7200000000 0.0115533676 0.0074221117 0.0121320365 0.0093511645 0.0056440000 15733229 955859216 1373700096 -0.2050569206 0.0346476547 -0.3449031413 545 21.7600000000 0.0114912307 0.0074295780 0.0121320365 0.0093463360 0.0057010000 15735205 955859216 1373700096 -0.2052850723 0.0333654247 -0.3459057808 546 21.8000000000 0.0116573265 0.0074373211 0.0121320365 0.0093522382 0.0057100000 15737181 955859216 1373700096 -0.2055909932 0.0322567075 -0.3469017148 547 21.8400000000 0.0118288938 0.0074453496 0.0121320365 0.0093758276 0.0057410000 15739157 955859216 1373700096 -0.2054464370 0.0306127016 -0.3479429781 548 21.8800000000 0.0117966849 0.0074532900 0.0121320365 0.0093895781 0.0044320000 15741133 955859216 1373700096 -0.2057434767 0.0295719635 -0.3490422070 549 21.9200000000 0.0115563842 0.0074607638 0.0121320365 0.0094006494 0.0045420000 15743109 955859216 1373700096 -0.2062387168 0.0263415519 -0.3499938250 550 21.9600000000 0.0117837433 0.0074686237 0.0121320365 0.0094092827 0.0058940000 15745085 955859216 1373700096 -0.2069081813 0.0252547152 -0.3510498106 551 22.0000000000 0.0120996106 0.0074770284 0.0121320365 0.0094063681 0.0058400000 15747061 955859216 1373700096 -0.2074636519 0.0250922497 -0.3522053659 552 22.0400000000 0.0117501952 0.0074847697 0.0121320365 0.0094035785 0.0045280000 15749037 955859216 1373700096 -0.2081061304 0.0245390981 -0.3530206084 553 22.0800000000 0.0116460742 0.0074922946 0.0121320365 0.0094038773 0.0059020000 15751013 955859216 1373700096 -0.2088736296 0.0226533692 -0.3538696170 554 22.1200000000 0.0119787911 0.0075003930 0.0121320365 0.0094116000 0.0059200000 15752989 955859216 1373700096 -0.2093672007 0.0220869109 -0.3547627926 555 22.1600000000 0.0123691410 0.0075091655 0.0123691410 0.0094143935 0.0046570000 15754965 955859216 1373700096 -0.2096568644 0.0229858551 -0.3558679819 556 22.2000000000 0.0121469665 0.0075175069 0.0123691410 0.0094081358 0.0056680000 15756941 955859216 1373700096 -0.2097837478 0.0229390115 -0.3567540050 557 22.2400000000 0.0114967879 0.0075246510 0.0123691410 0.0094011265 0.0028260000 15758917 955859216 1373700096 -0.2099146098 0.0220064856 -0.3573864698 558 22.2800000000 0.0115551297 0.0075318741 0.0123691410 0.0093996851 0.0034470000 15760893 955859216 1373700096 -0.2097069472 0.0215043947 -0.3580186367 559 22.3200000000 0.0116713038 0.0075392792 0.0123691410 0.0094029055 0.0034900000 15762869 955859216 1373700096 -0.2099196762 0.0209943075 -0.3588629365 560 22.3600000000 0.0117494864 0.0075467974 0.0123691410 0.0094004338 0.0038750000 15764845 955859216 1373700096 -0.2102368325 0.0210445467 -0.3596099913 561 22.4000000000 0.0116342064 0.0075540833 0.0123691410 0.0093982363 0.0038980000 15766821 955859216 1373700096 -0.2100388855 0.0205293372 -0.3603124619 562 22.4400000000 0.0115130581 0.0075611278 0.0123691410 0.0093951509 0.0038710000 15768797 955859216 1373700096 -0.2104728371 0.0199977774 -0.3609222472 563 22.4800000000 0.0115853241 0.0075682755 0.0123691410 0.0093924715 0.0039010000 15770773 955859216 1373700096 -0.2105366141 0.0194579940 -0.3616053462 564 22.5200000000 0.0115827909 0.0075753935 0.0123691410 0.0093927460 0.0060950000 15772749 955859216 1373700096 -0.2106294781 0.0193485804 -0.3621273041 565 22.5600000000 0.0115504898 0.0075824290 0.0123691410 0.0093955782 0.0060310000 15774725 955859216 1373700096 -0.2111369073 0.0184934996 -0.3627734780 566 22.6000000000 0.0115737440 0.0075894808 0.0123691410 0.0093953010 0.0060790000 15776701 955859216 1373700096 -0.2110452801 0.0182122439 -0.3633033633 567 22.6400000000 0.0116121406 0.0075965755 0.0123691410 0.0093937507 0.0060830000 15778677 955859216 1373700096 -0.2111415416 0.0177712534 -0.3640844524 568 22.6800000000 0.0115654496 0.0076035629 0.0123691410 0.0093932336 0.0060790000 15780653 955859216 1373700096 -0.2115302533 0.0171695501 -0.3644106686 569 22.7200000000 0.0119398925 0.0076111839 0.0123691410 0.0093991161 0.0047470000 15782629 955859216 1373700096 -0.2116827369 0.0164480135 -0.3650284111 570 22.7600000000 0.0119385468 0.0076187757 0.0123691410 0.0094021088 0.0061210000 15784605 955859216 1373700096 -0.2120117247 0.0160794519 -0.3655464947 571 22.8000000000 0.0121273147 0.0076266716 0.0123691410 0.0094071708 0.0061140000 15786581 955859216 1373700096 -0.2121162415 0.0148531143 -0.3662672341 572 22.8400000000 0.0123017272 0.0076348448 0.0123691410 0.0094173999 0.0061540000 15788557 955859216 1373700096 -0.2120886594 0.0149565218 -0.3669534624 573 22.8800000000 0.0121577019 0.0076427381 0.0123691410 0.0094171577 0.0047860000 15790533 955859216 1373700096 -0.2122191191 0.0146325706 -0.3676841557 574 22.9200000000 0.0120106768 0.0076503477 0.0123691410 0.0094193845 0.0061760000 15792509 955859216 1373700096 -0.2119141072 0.0139539735 -0.3686698973 575 22.9600000000 0.0119037544 0.0076577450 0.0123691410 0.0094242476 0.0047840000 15794485 955859216 1373700096 -0.2118255049 0.0134177897 -0.3694715202 576 23.0000000000 0.0119179655 0.0076651412 0.0123691410 0.0094319174 0.0063040000 15796461 955859216 1373700096 -0.2119551003 0.0125405621 -0.3704277575 577 23.0400000000 0.0118005872 0.0076723083 0.0123691410 0.0094399906 0.0062130000 15798437 955859216 1373700096 -0.2116445303 0.0116268257 -0.3712731302 578 23.0800000000 0.0116626052 0.0076792120 0.0123691410 0.0094490669 0.0062010000 15800413 955859216 1373700096 -0.2115469426 0.0107058790 -0.3720336258 579 23.1200000000 0.0114578409 0.0076857381 0.0123691410 0.0094556008 0.0048280000 15802389 955859216 1373700096 -0.2114880234 0.0100489864 -0.3728402555 580 23.1600000000 0.0113104312 0.0076919876 0.0123691410 0.0094625990 0.0062230000 15804365 955859216 1373700096 -0.2116007656 0.0095685460 -0.3735355139 581 23.2000000000 0.0109605920 0.0076976134 0.0123691410 0.0094662813 0.0062270000 15806341 955859216 1373700096 -0.2116775066 0.0090009263 -0.3740007281 582 23.2400000000 0.0108506829 0.0077030310 0.0123691410 0.0094682480 0.0048460000 15808317 955859216 1373700096 -0.2110602558 0.0086735319 -0.3745804727 583 23.2800000000 0.0112304064 0.0077090814 0.0123691410 0.0094746958 0.0041690000 15810293 955859216 1373700096 -0.2102606446 0.0083373841 -0.3752507567 584 23.3200000000 0.0108480873 0.0077144564 0.0123691410 0.0094762290 0.0062270000 15812269 955859216 1373700096 -0.2104792148 0.0074002482 -0.3756556809 585 23.3600000000 0.0109717697 0.0077200245 0.0123691410 0.0094867529 0.0062430000 15814245 955859216 1373700096 -0.2100233734 0.0067812898 -0.3759329617 586 23.4000000000 0.0113478759 0.0077262154 0.0123691410 0.0095022491 0.0062790000 15816221 955859216 1373700096 -0.2096330523 0.0065877414 -0.3763495088 587 23.4400000000 0.0112069212 0.0077321450 0.0123691410 0.0095073592 0.0048370000 15818197 955859216 1373700096 -0.2094529122 0.0062687728 -0.3766817451 588 23.4800000000 0.0111301010 0.0077379238 0.0123691410 0.0095132803 0.0062570000 15820173 955859216 1373700096 -0.2089433521 0.0057622246 -0.3766098320 589 23.5200000000 0.0112105990 0.0077438197 0.0123691410 0.0095203049 0.0048550000 15822149 955859216 1373700096 -0.2087459713 0.0055216514 -0.3768881261 590 23.5600000000 0.0111937802 0.0077496671 0.0123691410 0.0095250146 0.0048140000 15824125 955859216 1373700096 -0.2086311430 0.0052846987 -0.3771507144 591 23.6000000000 0.0108343773 0.0077548866 0.0123691410 0.0095251929 0.0047980000 15826101 955859216 1373700096 -0.2086991668 0.0042394898 -0.3771021068 592 23.6400000000 0.0110204881 0.0077604028 0.0123691410 0.0095357217 0.0062080000 15828077 955859216 1373700096 -0.2087096721 0.0034076907 -0.3773254156 593 23.6800000000 0.0110499635 0.0077659501 0.0123691410 0.0095409105 0.0061980000 15830053 955859216 1373700096 -0.2087219357 0.0030140106 -0.3774116933 594 23.7200000000 0.0109951161 0.0077713864 0.0123691410 0.0095396810 0.0062240000 15832029 955859216 1373700096 -0.2086404860 0.0026953004 -0.3778056204 595 23.7600000000 0.0109195458 0.0077766775 0.0123691410 0.0095411726 0.0047900000 15834005 955859216 1373700096 -0.2086263597 0.0018959135 -0.3778887987 596 23.8000000000 0.0110322526 0.0077821398 0.0123691410 0.0095453758 0.0062580000 15835981 955859216 1373700096 -0.2090860456 0.0013271541 -0.3779679835 597 23.8400000000 0.0111122020 0.0077877178 0.0123691410 0.0095451037 0.0062080000 15837957 955859216 1373700096 -0.2090455443 0.0010447826 -0.3778967559 598 23.8800000000 0.0110249259 0.0077931312 0.0123691410 0.0095423944 0.0048290000 15839933 955859216 1373700096 -0.2090911865 0.0006193850 -0.3779528141 599 23.9200000000 0.0106847361 0.0077979586 0.0123691410 0.0095369022 0.0062430000 15841909 955859216 1373700096 -0.2090229988 -0.0001924753 -0.3778265715 600 23.9600000000 0.0106422780 0.0078026991 0.0123691410 0.0095318349 0.0062380000 15843885 955859216 1373700096 -0.2088032663 -0.0010914881 -0.3778760731 601 24.0000000000 0.0108206719 0.0078077207 0.0123691410 0.0095287342 0.0048300000 15845861 955859216 1373700096 -0.2087725848 -0.0020467462 -0.3777627647 602 24.0400000000 0.0108628497 0.0078127957 0.0123691410 0.0095288170 0.0062540000 15847837 955859216 1373700096 -0.2085841149 -0.0031561740 -0.3776141405 603 24.0800000000 0.0110924896 0.0078182346 0.0123691410 0.0095363482 0.0062690000 15849813 955859216 1373700096 -0.2083652914 -0.0041489718 -0.3772893846 604 24.1200000000 0.0111095002 0.0078236838 0.0123691410 0.0095399400 0.0048940000 15851789 955859216 1373700096 -0.2081538886 -0.0046521365 -0.3769257665 605 24.1600000000 0.0112210354 0.0078292992 0.0123691410 0.0095374852 0.0041600000 15853765 955859216 1373700096 -0.2081910968 -0.0048349504 -0.3767064810 606 24.2000000000 0.0110097453 0.0078345475 0.0123691410 0.0095313000 0.0041740000 15855741 955859216 1373700096 -0.2079827935 -0.0052020638 -0.3766120374 607 24.2400000000 0.0110195102 0.0078397945 0.0123691410 0.0095246760 0.0041520000 15857717 955859216 1373700096 -0.2076162249 -0.0055963174 -0.3765205145 608 24.2800000000 0.0109751942 0.0078449514 0.0123691410 0.0095178318 0.0041930000 15859693 955859216 1373700096 -0.2071951032 -0.0059814882 -0.3764159679 609 24.3200000000 0.0107666347 0.0078497490 0.0123691410 0.0095111326 0.0064070000 15861669 955859216 1373700096 -0.2077867687 -0.0070188623 -0.3763071299 610 24.3600000000 0.0112681286 0.0078553529 0.0123691410 0.0095102497 0.0063120000 15863645 955859216 1373700096 -0.2074198276 -0.0076721329 -0.3763684630 611 24.4000000000 0.0112360017 0.0078608858 0.0123691410 0.0095050272 0.0063580000 15865621 955859216 1373700096 -0.2071159780 -0.0085951127 -0.3760943711 612 24.4400000000 0.0113907885 0.0078666536 0.0123691410 0.0095022249 0.0047860000 15867597 955859216 1373700096 -0.2069279402 -0.0089429868 -0.3763449490 613 24.4800000000 0.0116915731 0.0078728933 0.0123691410 0.0094970734 0.0063420000 15869573 955859216 1373700096 -0.2060293704 -0.0083264047 -0.3761739135 614 24.5200000000 0.0117626935 0.0078792285 0.0123691410 0.0094894923 0.0063600000 15871549 955859216 1373700096 -0.2056634575 -0.0084404666 -0.3758505881 615 24.5600000000 0.0118208351 0.0078856376 0.0123691410 0.0094823661 0.0048570000 15873525 955859216 1373700096 -0.2058310509 -0.0098213386 -0.3756263852 616 24.6000000000 0.0118310228 0.0078920425 0.0123691410 0.0094804850 0.0063630000 15875501 955859216 1373700096 -0.2059469521 -0.0114896987 -0.3757720590 617 24.6400000000 0.0118933553 0.0078985276 0.0123691410 0.0094822266 0.0063600000 15877477 955859216 1373700096 -0.2055892646 -0.0119669419 -0.3757762015 618 24.6800000000 0.0117491260 0.0079047583 0.0123691410 0.0094827662 0.0049680000 15879453 955859216 1373700096 -0.2051583529 -0.0125465728 -0.3760438561 619 24.7200000000 0.0119911768 0.0079113600 0.0123691410 0.0094953818 0.0065320000 15881429 955859216 1373700096 -0.2044213414 -0.0128244199 -0.3760451078 620 24.7600000000 0.0122880908 0.0079184192 0.0123691410 0.0095003704 0.0063140000 15883405 955859216 1373700096 -0.2039046139 -0.0123526640 -0.3765272498 621 24.8000000000 0.0119200768 0.0079248631 0.0123691410 0.0094936158 0.0049470000 15885381 955859216 1373700096 -0.2033416927 -0.0120916162 -0.3769207299 622 24.8400000000 0.0118252169 0.0079311338 0.0123691410 0.0094860042 0.0041470000 15887357 955859216 1373700096 -0.2022032589 -0.0125602214 -0.3768896759 623 24.8800000000 0.0118755680 0.0079374651 0.0123691410 0.0094786114 0.0063100000 15889333 955859216 1373700096 -0.2013131231 -0.0129991667 -0.3767820597 624 24.9200000000 0.0119318478 0.0079438664 0.0123691410 0.0094714413 0.0063360000 15891309 955859216 1373700096 -0.2006322592 -0.0137813818 -0.3768929541 625 24.9600000000 0.0118403742 0.0079501008 0.0123691410 0.0094659028 0.0063900000 15893285 955859216 1373700096 -0.1995128393 -0.0136559578 -0.3770577610 626 25.0000000000 0.0120621594 0.0079566696 0.0123691410 0.0094585259 0.0048570000 15895261 955859216 1373700096 -0.1981194466 -0.0134916799 -0.3767860830 627 25.0400000000 0.0121052340 0.0079632861 0.0123691410 0.0094510512 0.0064220000 15897237 955859216 1373700096 -0.1968481690 -0.0142647503 -0.3766205013 628 25.0800000000 0.0122890621 0.0079701743 0.0123691410 0.0094465455 0.0064370000 15899213 955859216 1373700096 -0.1953981519 -0.0141390385 -0.3766059577 629 25.1200000000 0.0124992896 0.0079773748 0.0124992896 0.0094400729 0.0049890000 15901189 955859216 1373700096 -0.1936259568 -0.0129353860 -0.3769263625 630 25.1600000000 0.0122173391 0.0079841049 0.0124992896 0.0094367032 0.0064380000 15903165 955859216 1373700096 -0.1925084889 -0.0129066622 -0.3767187893 631 25.2000000000 0.0120344199 0.0079905238 0.0124992896 0.0094304230 0.0054200000 15905141 955859216 1373700096 -0.1908236742 -0.0133996615 -0.3764865398 632 25.2400000000 0.0121841673 0.0079971593 0.0124992896 0.0094229859 0.0042360000 15907117 955859216 1373700096 -0.1891450137 -0.0135409143 -0.3763217628 633 25.2800000000 0.0124733010 0.0080042306 0.0124992896 0.0094155886 0.0041970000 15909093 955859216 1373700096 -0.1875074059 -0.0127151255 -0.3761719465 634 25.3200000000 0.0123384409 0.0080110669 0.0124992896 0.0094099389 0.0043520000 15911069 955859216 1373700096 -0.1856237799 -0.0127216289 -0.3756249547 635 25.3600000000 0.0123092039 0.0080178356 0.0124992896 0.0094046602 0.0064870000 15913045 955859216 1373700096 -0.1835839003 -0.0130474018 -0.3749105632 636 25.4000000000 0.0125115113 0.0080249011 0.0125115113 0.0093984582 0.0064870000 15915021 955859216 1373700096 -0.1816810071 -0.0130195636 -0.3748516142 637 25.4400000000 0.0124714198 0.0080318815 0.0125115113 0.0093926780 0.0064650000 15916997 955859216 1373700096 -0.1795049310 -0.0127990879 -0.3745464385 638 25.4800000000 0.0123437038 0.0080386399 0.0125115113 0.0093887767 0.0060960000 15918973 955859216 1373700096 -0.1777659655 -0.0136598535 -0.3739399016 639 25.5200000000 0.0125031387 0.0080456266 0.0125115113 0.0093814938 0.0064840000 15920949 955859216 1373700096 -0.1754813194 -0.0137966014 -0.3738635778 640 25.5600000000 0.0125788487 0.0080527097 0.0125788487 0.0093745554 0.0064940000 15922925 955859216 1373700096 -0.1731044203 -0.0135294627 -0.3733429611 641 25.6000000000 0.0125647979 0.0080597489 0.0125788487 0.0093677933 0.0049960000 15924901 955859216 1373700096 -0.1703649163 -0.0130945016 -0.3728440106 642 25.6400000000 0.0125096226 0.0080666801 0.0125788487 0.0093624863 0.0065100000 15926877 955859216 1373700096 -0.1681934595 -0.0134707838 -0.3724958599 643 25.6800000000 0.0126612093 0.0080738256 0.0126612093 0.0093552166 0.0057000000 15928853 955859216 1373700096 -0.1656972021 -0.0130359055 -0.3723907173 644 25.7200000000 0.0125773400 0.0080808186 0.0126612093 0.0093487193 0.0042370000 15930829 955859216 1373700096 -0.1632487476 -0.0131942648 -0.3717243671 645 25.7600000000 0.0125272954 0.0080877124 0.0126612093 0.0093415585 0.0042560000 15932805 955859216 1373700096 -0.1607065052 -0.0138103319 -0.3710855842 646 25.8000000000 0.0127385026 0.0080949118 0.0127385026 0.0093361328 0.0065210000 15934781 955859216 1373700096 -0.1581843793 -0.0135803083 -0.3706315458 647 25.8400000000 0.0127392169 0.0081020900 0.0127392169 0.0093289128 0.0065230000 15936757 955859216 1373700096 -0.1555279642 -0.0131457467 -0.3699161708 648 25.8800000000 0.0126296189 0.0081090769 0.0127392169 0.0093226625 0.0065890000 15938733 955859216 1373700096 -0.1533257365 -0.0135872932 -0.3690363765 649 25.9200000000 0.0126393773 0.0081160573 0.0127392169 0.0093154803 0.0053770000 15940709 955859216 1373700096 -0.1507453918 -0.0140059292 -0.3686110377 650 25.9600000000 0.0127527239 0.0081231907 0.0127527239 0.0093088097 0.0063940000 15942685 955859216 1373700096 -0.1481413990 -0.0136870565 -0.3680824339 651 26.0000000000 0.0127930287 0.0081303640 0.0127930287 0.0093016650 0.0064990000 15944661 955859216 1373700096 -0.1456335783 -0.0131898867 -0.3675429523 652 26.0400000000 0.0127302837 0.0081374191 0.0127930287 0.0092946997 0.0049840000 15946637 955859216 1373700096 -0.1432253718 -0.0129586980 -0.3675629199 653 26.0800000000 0.0127208987 0.0081444382 0.0127930287 0.0092876861 0.0042310000 15948613 955859216 1373700096 -0.1409754008 -0.0131543390 -0.3674024343 654 26.1200000000 0.0126444530 0.0081513190 0.0127930287 0.0092813742 0.0065120000 15950589 955859216 1373700096 -0.1358246952 -0.0124902502 -0.3666016459 655 26.1600000000 0.0126258265 0.0081581503 0.0127930287 0.0092744443 0.0063900000 15952565 955859216 1373700096 -0.1332841218 -0.0129674831 -0.3655560017 656 26.2000000000 0.0127670765 0.0081651761 0.0127930287 0.0092677007 0.0064780000 15954541 955859216 1373700096 -0.1304247379 -0.0126965800 -0.3646386862 657 26.2400000000 0.0127636073 0.0081721752 0.0127930287 0.0092606807 0.0049720000 15956517 955859216 1373700096 -0.1277301610 -0.0127684036 -0.3635472953 658 26.2800000000 0.0128087215 0.0081792216 0.0128087215 0.0092537465 0.0064910000 15958493 955859216 1373700096 -0.1250760555 -0.0129757877 -0.3627472520 659 26.3200000000 0.0129822958 0.0081865101 0.0129822958 0.0092476215 0.0064430000 15960469 955859216 1373700096 -0.1224488392 -0.0126829613 -0.3624714613 660 26.3600000000 0.0128298374 0.0081935454 0.0129822958 0.0092406043 0.0043370000 15962445 955859216 1373700096 -0.1199222580 -0.0129638743 -0.3617679775 661 26.4000000000 0.0128144547 0.0082005362 0.0129822958 0.0092341038 0.0042900000 15964421 955859216 1373700096 -0.1170880049 -0.0132815801 -0.3607010841 662 26.4400000000 0.0128928823 0.0082076243 0.0129822958 0.0092285543 0.0066250000 15966397 955859216 1373700096 -0.1143319979 -0.0131923361 -0.3599781692 663 26.4800000000 0.0127301281 0.0082144456 0.0129822958 0.0092215952 0.0066070000 15968373 955859216 1373700096 -0.1118350327 -0.0135895144 -0.3594273329 664 26.5200000000 0.0126136793 0.0082210709 0.0129822958 0.0092150121 0.0055070000 15970349 955859216 1373700096 -0.1094923764 -0.0146148531 -0.3587409854 665 26.5600000000 0.0125903003 0.0082276412 0.0129822958 0.0092103663 0.0066100000 15972325 955859216 1373700096 -0.1073203981 -0.0161859691 -0.3584038019 666 26.6000000000 0.0127335433 0.0082344068 0.0129822958 0.0092103201 0.0050220000 15974301 955859216 1373700096 -0.1047995090 -0.0169561934 -0.3580117822 667 26.6400000000 0.0127556827 0.0082411854 0.0129822958 0.0092087447 0.0043230000 15976277 955859216 1373700096 -0.1023693606 -0.0176554713 -0.3577747345 668 26.6800000000 0.0127081722 0.0082478725 0.0129822958 0.0092047841 0.0043190000 15978253 955859216 1373700096 -0.0999707729 -0.0182487033 -0.3573580682 669 26.7200000000 0.0126237851 0.0082544134 0.0129822958 0.0091999851 0.0043000000 15980229 955859216 1373700096 -0.0976848751 -0.0192439929 -0.3573058546 670 26.7600000000 0.0126736844 0.0082610094 0.0129822958 0.0091995110 0.0066780000 15982205 955859216 1373700096 -0.0953410491 -0.0197027512 -0.3575260639 671 26.8000000000 0.0127316676 0.0082676720 0.0129822958 0.0091961761 0.0066850000 15984181 955859216 1373700096 -0.0928011164 -0.0194849167 -0.3579950333 672 26.8400000000 0.0125897657 0.0082741037 0.0129822958 0.0091896913 0.0067250000 15986157 955859216 1373700096 -0.0905215293 -0.0206334703 -0.3581777513 673 26.8800000000 0.0126760704 0.0082806445 0.0129822958 0.0091917178 0.0050960000 15988133 955859216 1373700096 -0.0880405232 -0.0215336233 -0.3584037721 674 26.9200000000 0.0129053555 0.0082875061 0.0129822958 0.0091988813 0.0043850000 15990109 955859216 1373700096 -0.0852959231 -0.0210945364 -0.3587401807 675 26.9600000000 0.0128608029 0.0082942814 0.0129822958 0.0091944830 0.0043460000 15992085 955859216 1373700096 -0.0826713517 -0.0210178439 -0.3595938683 676 27.0000000000 0.0126829362 0.0083007735 0.0129822958 0.0091882790 0.0067280000 15994061 955859216 1373700096 -0.0802319199 -0.0221643392 -0.3597881794 677 27.0400000000 0.0127741620 0.0083073811 0.0129822958 0.0091850688 0.0067340000 15996037 955859216 1373700096 -0.0775155053 -0.0223316494 -0.3608330190 678 27.0800000000 0.0127621824 0.0083139516 0.0129822958 0.0091805129 0.0067610000 15998013 955859216 1373700096 -0.0748423189 -0.0226355642 -0.3615024090 679 27.1200000000 0.0127860475 0.0083205379 0.0129822958 0.0091775682 0.0051600000 15999989 955859216 1373700096 -0.0723774508 -0.0231000911 -0.3623685837 680 27.1600000000 0.0129088340 0.0083272854 0.0129822958 0.0091762085 0.0067290000 16001965 955859216 1373700096 -0.0695771798 -0.0228495020 -0.3636137247 681 27.2000000000 0.0128603457 0.0083339419 0.0129822958 0.0091698907 0.0051390000 16003941 955859216 1373700096 -0.0668929890 -0.0228838194 -0.3646719754 682 27.2400000000 0.0128537137 0.0083405691 0.0129822958 0.0091637759 0.0067420000 16005917 955859216 1373700096 -0.0642589182 -0.0231518131 -0.3660722673 683 27.2800000000 0.0128708370 0.0083472020 0.0129822958 0.0091586986 0.0067540000 16007893 955859216 1373700096 -0.0614603087 -0.0232166089 -0.3674321771 684 27.3200000000 0.0128454668 0.0083537785 0.0129822958 0.0091521524 0.0061130000 16009869 955859216 1373700096 -0.0587038323 -0.0233529154 -0.3692025244 685 27.3600000000 0.0126077561 0.0083599886 0.0129822958 0.0091455149 0.0051210000 16011845 955859216 1373700096 -0.0561753474 -0.0249876119 -0.3705492020 686 27.4000000000 0.0126604503 0.0083662575 0.0129822958 0.0091447128 0.0067910000 16013821 955859216 1373700096 -0.0535946377 -0.0259584095 -0.3723480999 687 27.4400000000 0.0127224633 0.0083725984 0.0129822958 0.0091466763 0.0068980000 16015797 955859216 1373700096 -0.0506490804 -0.0259624831 -0.3744646311 688 27.4800000000 0.0127208931 0.0083789186 0.0129822958 0.0091473896 0.0067960000 16017773 955859216 1373700096 -0.0476355962 -0.0260265544 -0.3765395880 689 27.5200000000 0.0126627320 0.0083851361 0.0129822958 0.0091482127 0.0068130000 16019749 955859216 1373700096 -0.0448767170 -0.0263415501 -0.3786476851 690 27.5600000000 0.0121894814 0.0083906496 0.0129822958 0.0091543244 0.0059990000 16021725 955859216 1373700096 -0.0418053828 -0.0249454454 -0.3816140890 691 27.6000000000 0.0124897631 0.0083965818 0.0129822958 0.0091477482 0.0043780000 16023701 955859216 1373700096 -0.0383703373 -0.0244081747 -0.3834664822 692 27.6400000000 0.0123557560 0.0084023031 0.0129822958 0.0091445553 0.0067810000 16025677 955859216 1373700096 -0.0352643393 -0.0241424330 -0.3858179748 693 27.6800000000 0.0123186437 0.0084079544 0.0129822958 0.0091408729 0.0060800000 16027653 955859216 1373700096 -0.0323501267 -0.0248802267 -0.3878582120 694 27.7200000000 0.0123363519 0.0084136149 0.0129822958 0.0091342761 0.0051850000 16029629 955859216 1373700096 -0.0293735825 -0.0252190586 -0.3901547790 695 27.7600000000 0.0123067014 0.0084192165 0.0129822958 0.0091279292 0.0043690000 16031605 955859216 1373700096 -0.0263813827 -0.0257101525 -0.3920743167 696 27.8000000000 0.0122929197 0.0084247821 0.0129822958 0.0091234530 0.0068130000 16033581 955859216 1373700096 -0.0235165898 -0.0260829553 -0.3936944902 697 27.8400000000 0.0119565083 0.0084298492 0.0129822958 0.0091217252 0.0067050000 16035557 955859216 1373700096 -0.0180175249 -0.0247298237 -0.3992117643 698 27.8800000000 0.0121840201 0.0084352277 0.0129822958 0.0091152688 0.0047570000 16037533 955859216 1373700096 -0.0154022546 -0.0261551011 -0.4003994763 699 27.9200000000 0.0118826414 0.0084401596 0.0129822958 0.0091349374 0.0052980000 16039509 955859216 1373700096 -0.0110210972 -0.0260141436 -0.4050068855 700 27.9600000000 0.0121612204 0.0084454754 0.0129822958 0.0091291734 0.0043820000 16041485 955859216 1373700096 -0.0086856419 -0.0270593967 -0.4063586593 701 28.0000000000 0.0121851116 0.0084508101 0.0129822958 0.0091258755 0.0030210000 16043461 955859216 1373700096 -0.0065154778 -0.0281094760 -0.4076024294 702 28.0400000000 0.0122557385 0.0084562302 0.0129822958 0.0091309462 0.0071300000 16045437 955859216 1373700096 -0.0044923187 -0.0291048568 -0.4089586735 703 28.0800000000 0.0124538662 0.0084619168 0.0129822958 0.0091492580 0.0074160000 16047413 955859216 1373700096 -0.0023302373 -0.0291228443 -0.4109182358 704 28.1200000000 0.0124635668 0.0084676009 0.0129822958 0.0091557695 0.0053320000 16049389 955859216 1373700096 -0.0000195652 -0.0290744789 -0.4126234353 705 28.1600000000 0.0123371482 0.0084730896 0.0129822958 0.0091560764 0.0044250000 16051365 955859216 1373700096 0.0018959339 -0.0297988150 -0.4140259624 706 28.2000000000 0.0124026900 0.0084786556 0.0129822958 0.0091620495 0.0068690000 16053341 955859216 1373700096 0.0039801602 -0.0303136446 -0.4154591858 707 28.2400000000 0.0125133293 0.0084843624 0.0129822958 0.0091667732 0.0068600000 16055317 955859216 1373700096 0.0063991277 -0.0296663120 -0.4170183539 708 28.2800000000 0.0123851886 0.0084898720 0.0129822958 0.0091604824 0.0048760000 16057293 955859216 1373700096 0.0089113601 -0.0292796064 -0.4185850322 709 28.3200000000 0.0121872891 0.0084950870 0.0129822958 0.0091540869 0.0068760000 16059269 955859216 1373700096 0.0110626612 -0.0300572887 -0.4194723666 710 28.3600000000 0.0123606268 0.0085005314 0.0129822958 0.0091517428 0.0052130000 16061245 955859216 1373700096 0.0133656245 -0.0306903459 -0.4203788936 711 28.4000000000 0.0125507107 0.0085062279 0.0129822958 0.0091495580 0.0068800000 16063221 955859216 1373700096 0.0159255117 -0.0303161815 -0.4216669798 712 28.4400000000 0.0123388441 0.0085116108 0.0129822958 0.0091431281 0.0058570000 16065197 955859216 1373700096 0.0182094332 -0.0308914986 -0.4222879708 713 28.4800000000 0.0122946873 0.0085169166 0.0129822958 0.0091377538 0.0043930000 16067173 955859216 1373700096 0.0204770695 -0.0316575579 -0.4227821231 714 28.5200000000 0.0125141982 0.0085225151 0.0129822958 0.0091358860 0.0043800000 16069149 955859216 1373700096 0.0230739973 -0.0314920656 -0.4236096144 715 28.5600000000 0.0126370192 0.0085282696 0.0129822958 0.0091304213 0.0068030000 16071125 955859216 1373700096 0.0259778276 -0.0306576788 -0.4244063795 716 28.6000000000 0.0125504872 0.0085338872 0.0129822958 0.0091253414 0.0068230000 16073101 955859216 1373700096 0.0287719835 -0.0300977211 -0.4248303175 717 28.6400000000 0.0124165909 0.0085393025 0.0129822958 0.0091219263 0.0051670000 16075077 955859216 1373700096 0.0315156505 -0.0301989187 -0.4251684546 718 28.6800000000 0.0124803344 0.0085447914 0.0129822958 0.0091159070 0.0068410000 16077053 955859216 1373700096 0.0342016704 -0.0304055791 -0.4252361953 719 28.7200000000 0.0125159994 0.0085503146 0.0129822958 0.0091095716 0.0057830000 16079029 955859216 1373700096 0.0370270722 -0.0307922661 -0.4249886274 720 28.7600000000 0.0126633691 0.0085560272 0.0129822958 0.0091060593 0.0069000000 16081005 955859216 1373700096 0.0401035026 -0.0312104672 -0.4245467186 721 28.8000000000 0.0116637293 0.0085603374 0.0129822958 0.0091095524 0.0053330000 16082981 955859216 1373700096 0.0438365154 -0.0285734199 -0.4240202606 722 28.8400000000 0.0125498446 0.0085658631 0.0129822958 0.0091033693 0.0044020000 16084957 955859216 1373700096 0.0469907746 -0.0294170342 -0.4238917828 723 28.8800000000 0.0127385221 0.0085716344 0.0129822958 0.0090973547 0.0069060000 16086933 955859216 1373700096 0.0502783619 -0.0294569321 -0.4233821332 724 28.9200000000 0.0127403559 0.0085773923 0.0129822958 0.0090911528 0.0063050000 16088909 955859216 1373700096 0.0536550134 -0.0292487908 -0.4225984514 725 28.9600000000 0.0127522051 0.0085831506 0.0129822958 0.0090849870 0.0052360000 16090885 955859216 1373700096 0.0572316684 -0.0292191561 -0.4216451049 726 29.0000000000 0.0127270818 0.0085888585 0.0129822958 0.0090800384 0.0049950000 16092861 955859216 1373700096 0.0605551973 -0.0292805899 -0.4207551479 727 29.0400000000 0.0117179649 0.0085931627 0.0129822958 0.0090824816 0.0070290000 16094837 955859216 1373700096 0.0649989992 -0.0268861968 -0.4190730453 728 29.0800000000 0.0126684336 0.0085987606 0.0129822958 0.0090766155 0.0063530000 16096813 955859216 1373700096 0.0683811679 -0.0274489075 -0.4185580313 729 29.1200000000 0.0127527919 0.0086044588 0.0129822958 0.0090703956 0.0052220000 16098789 955859216 1373700096 0.0716567189 -0.0281031094 -0.4174619019 730 29.1600000000 0.0117452517 0.0086087613 0.0129822958 0.0090756504 0.0045520000 16100765 955859216 1373700096 0.0756238922 -0.0267963577 -0.4155567884 731 29.2000000000 0.0117374621 0.0086130413 0.0129822958 0.0090801778 0.0070130000 16102741 955859216 1373700096 0.0795537531 -0.0261930004 -0.4140675664 732 29.2400000000 0.0128047364 0.0086187677 0.0129822958 0.0090771448 0.0068080000 16104717 955859216 1373700096 0.0824452043 -0.0274009518 -0.4135306180 733 29.2800000000 0.0117857708 0.0086230883 0.0129822958 0.0090757166 0.0042750000 16106693 955859216 1373700096 0.0864643008 -0.0255709793 -0.4121319950 734 29.3200000000 0.0117544578 0.0086273545 0.0129822958 0.0090709947 0.0071310000 16108669 955859216 1373700096 0.0900063664 -0.0252610017 -0.4109423459 735 29.3600000000 0.0125248181 0.0086326571 0.0129822958 0.0090649263 0.0062260000 16110645 955859216 1373700096 0.0925920606 -0.0264915526 -0.4104239643 736 29.4000000000 0.0127059100 0.0086381914 0.0129822958 0.0090588200 0.0052690000 16112621 955859216 1373700096 0.0954202265 -0.0270766988 -0.4094021022 737 29.4400000000 0.0129044661 0.0086439801 0.0129822958 0.0090543512 0.0069310000 16114597 955859216 1373700096 0.0982583016 -0.0273589473 -0.4084652364 738 29.4800000000 0.0118497964 0.0086483241 0.0129822958 0.0090512884 0.0061090000 16116573 955859216 1373700096 0.1019632518 -0.0254917834 -0.4068468809 739 29.5200000000 0.0124852005 0.0086535160 0.0129822958 0.0090452358 0.0045370000 16118549 955859216 1373700096 0.1041391045 -0.0269751120 -0.4061054587 740 29.5600000000 0.0127420891 0.0086590411 0.0129822958 0.0090425117 0.0045410000 16120525 955859216 1373700096 0.1064899862 -0.0281554926 -0.4049655795 741 29.6000000000 0.0130551700 0.0086649738 0.0130551700 0.0090495435 0.0070820000 16122501 955859216 1373700096 0.1087435931 -0.0287267864 -0.4039617181 742 29.6400000000 0.0132143879 0.0086711051 0.0132143879 0.0090518841 0.0070880000 16124477 955859216 1373700096 0.1113601401 -0.0286067910 -0.4031265378 743 29.6800000000 0.0131520154 0.0086771360 0.0132143879 0.0090489988 0.0063480000 16126453 955859216 1373700096 0.1138047278 -0.0283598285 -0.4022330046 744 29.7200000000 0.0130148614 0.0086829662 0.0132143879 0.0090440735 0.0045290000 16128429 955859216 1373700096 0.1161172315 -0.0283617172 -0.4012753367 745 29.7600000000 0.0132058924 0.0086890373 0.0132143879 0.0090401727 0.0040390000 16130405 955859216 1373700096 0.1186154932 -0.0278480724 -0.4004510045 746 29.8000000000 0.0129647236 0.0086947688 0.0132143879 0.0090361787 0.0071710000 16132381 955859216 1373700096 0.1210651919 -0.0268678516 -0.3997572362 747 29.8400000000 0.0125361513 0.0086999112 0.0132143879 0.0090360170 0.0068100000 16134357 955859216 1373700096 0.1229161248 -0.0272298492 -0.3986822963 748 29.8800000000 0.0132506099 0.0087059950 0.0132506099 0.0090434547 0.0053840000 16136333 955859216 1373700096 0.1257983744 -0.0280274265 -0.3978309333 749 29.9200000000 0.0131718284 0.0087119574 0.0132506099 0.0090375534 0.0045770000 16138309 955859216 1373700096 0.1283474714 -0.0274776239 -0.3967434466 750 29.9600000000 0.0130232265 0.0087177058 0.0132506099 0.0090319760 0.0071300000 16140285 955859216 1373700096 0.1303886175 -0.0272216927 -0.3958040774 751 30.0000000000 0.0131471129 0.0087236038 0.0132506099 0.0090260086 0.0068340000 16142261 955859216 1373700096 0.1324356645 -0.0268030968 -0.3951962292 752 30.0400000000 0.0130520184 0.0087293596 0.0132506099 0.0090224149 0.0042840000 16144237 955859216 1373700096 0.1343903095 -0.0261466354 -0.3947641551 753 30.0800000000 0.0128594609 0.0087348445 0.0132506099 0.0090193391 0.0071840000 16146213 955859216 1373700096 0.1360001564 -0.0262514446 -0.3943490088 754 30.1200000000 0.0130960308 0.0087406286 0.0132506099 0.0090133808 0.0066300000 16148189 955859216 1373700096 0.1378178447 -0.0262998734 -0.3940803409 755 30.1600000000 0.0130245676 0.0087463027 0.0132506099 0.0090080422 0.0054210000 16150165 955859216 1373700096 0.1394388527 -0.0262209158 -0.3937447965 756 30.2000000000 0.0129189696 0.0087518221 0.0132506099 0.0090021554 0.0071510000 16152141 955859216 1373700096 0.1408251822 -0.0269668885 -0.3931478262 757 30.2400000000 0.0131735718 0.0087576632 0.0132506099 0.0090024348 0.0072480000 16154117 955859216 1373700096 0.1423443705 -0.0281178392 -0.3925697505 758 30.2800000000 0.0136760361 0.0087641518 0.0136760361 0.0090191202 0.0046500000 16156093 955859216 1373700096 0.1440764070 -0.0286350064 -0.3924728334 759 30.3200000000 0.0124015380 0.0087689442 0.0136760361 0.0090366967 0.0075460000 16158069 955859216 1373700096 0.1467406899 -0.0263045058 -0.3921019435 760 30.3600000000 0.0132471472 0.0087748365 0.0136760361 0.0090387523 0.0054550000 16160045 955859216 1373700096 0.1484188139 -0.0278799459 -0.3917062581 761 30.4000000000 0.0136215873 0.0087812055 0.0136760361 0.0090469653 0.0045760000 16162021 955859216 1373700096 0.1504159719 -0.0287399497 -0.3914461732 762 30.4400000000 0.0139735406 0.0087880195 0.0139735406 0.0090620120 0.0072040000 16163997 955859216 1373700096 0.1525175720 -0.0290985536 -0.3910049200 763 30.4800000000 0.0125669111 0.0087929722 0.0139735406 0.0090775433 0.0072840000 16165973 955859216 1373700096 0.1555581093 -0.0267158840 -0.3906940520 764 30.5200000000 0.0134726716 0.0087990975 0.0139735406 0.0090832844 0.0049060000 16167949 955859216 1373700096 0.1574773341 -0.0284254868 -0.3905057609 765 30.5600000000 0.0139917778 0.0088058853 0.0139917778 0.0090992897 0.0071840000 16169925 955859216 1373700096 0.1595347971 -0.0292853806 -0.3903219104 766 30.6000000000 0.0126924254 0.0088109591 0.0139917778 0.0091198795 0.0055550000 16171901 955859216 1373700096 0.1625963748 -0.0266166963 -0.3901904821 767 30.6400000000 0.0136105875 0.0088172168 0.0139917778 0.0091186243 0.0046160000 16173877 955859216 1373700096 0.1648495793 -0.0275652204 -0.3903271258 768 30.6800000000 0.0137659796 0.0088236605 0.0139917778 0.0091164375 0.0071640000 16175853 955859216 1373700096 0.1671150327 -0.0280628130 -0.3901592791 769 30.7200000000 0.0141486945 0.0088305851 0.0141486945 0.0091176650 0.0065570000 16177829 955859216 1373700096 0.1694819182 -0.0280733127 -0.3903284967 770 30.7600000000 0.0141218528 0.0088374569 0.0141486945 0.0091137316 0.0054550000 16179805 955859216 1373700096 0.1717957407 -0.0274752751 -0.3905709982 771 30.8000000000 0.0136956479 0.0088437580 0.0141486945 0.0091081218 0.0072330000 16181781 955859216 1373700096 0.1739785969 -0.0275457613 -0.3905551434 772 30.8400000000 0.0140643343 0.0088505204 0.0141486945 0.0091107422 0.0053770000 16183757 955859216 1373700096 0.1759844422 -0.0281444341 -0.3905745149 773 30.8800000000 0.0143346498 0.0088576150 0.0143346498 0.0091101881 0.0047160000 16185733 955859216 1373700096 0.1784865111 -0.0279378239 -0.3905892670 774 30.9200000000 0.0141888298 0.0088645029 0.0143346498 0.0091047800 0.0073890000 16187709 955859216 1373700096 0.1806496084 -0.0276407152 -0.3906309009 775 30.9600000000 0.0142811239 0.0088714921 0.0143346498 0.0090990402 0.0062310000 16189685 955859216 1373700096 0.1825567633 -0.0273655709 -0.3908183873 776 31.0000000000 0.0140613224 0.0088781800 0.0143346498 0.0090960328 0.0046880000 16191661 955859216 1373700096 0.1844541132 -0.0269044712 -0.3909416199 777 31.0400000000 0.0139944423 0.0088847647 0.0143346498 0.0090919514 0.0073640000 16193637 955859216 1373700096 0.1860525012 -0.0269188490 -0.3910159767 778 31.0800000000 0.0143865747 0.0088918364 0.0143865747 0.0090867944 0.0073400000 16195613 955859216 1373700096 0.1877393872 -0.0263501424 -0.3916061521 779 31.1200000000 0.0140782865 0.0088984942 0.0143865747 0.0090969545 0.0045950000 16197589 955859216 1373700096 0.1892144829 -0.0250154212 -0.3922288716 780 31.1600000000 0.0135893170 0.0089045081 0.0143865747 0.0091297647 0.0038140000 16199565 955859216 1373700096 0.1904816329 -0.0239367113 -0.3924736679 781 31.2000000000 0.0134852575 0.0089103733 0.0143865747 0.0091644579 0.0038210000 16201541 955859216 1373700096 0.1917167753 -0.0235572197 -0.3926762342 782 31.2400000000 0.0135394968 0.0089162929 0.0143865747 0.0091970472 0.0038120000 16203517 955859216 1373700096 0.1928453445 -0.0232624840 -0.3928168714 783 31.2800000000 0.0134086711 0.0089220303 0.0143865747 0.0092276500 0.0038110000 16205493 955859216 1373700096 0.1935649365 -0.0231299233 -0.3931453526 784 31.3200000000 0.0133895716 0.0089277287 0.0143865747 0.0092432865 0.0038280000 16207469 955859216 1373700096 0.1941560209 -0.0233924575 -0.3933379948 785 31.3600000000 0.0135960644 0.0089336757 0.0143865747 0.0092417176 0.0038190000 16209445 955859216 1373700096 0.1947961897 -0.0239973962 -0.3934294581 786 31.4000000000 0.0139677823 0.0089400804 0.0143865747 0.0092361754 0.0038550000 16211421 955859216 1373700096 0.1957074404 -0.0238175634 -0.3938170075 787 31.4400000000 0.0138265472 0.0089462893 0.0143865747 0.0092363421 0.0038210000 16213397 955859216 1373700096 0.1966176480 -0.0229467489 -0.3940791488 788 31.4800000000 0.0136448061 0.0089522519 0.0143865747 0.0092390008 0.0038260000 16215373 955859216 1373700096 0.1973018348 -0.0222411100 -0.3943260014 789 31.5200000000 0.0136573389 0.0089582153 0.0143865747 0.0092432079 0.0074680000 16217349 955859216 1373700096 0.1981921643 -0.0212365370 -0.3947027028 790 31.5600000000 0.0132804988 0.0089636865 0.0143865747 0.0092719364 0.0074550000 16219325 955859216 1373700096 0.1989336461 -0.0198938083 -0.3949159980 791 31.6000000000 0.0130238561 0.0089688195 0.0143865747 0.0093060245 0.0069700000 16221301 955859216 1373700096 0.1997423321 -0.0193024855 -0.3950704336 792 31.6400000000 0.0131538901 0.0089741037 0.0143865747 0.0093182124 0.0056700000 16223277 955859216 1373700096 0.2007408589 -0.0190235339 -0.3949703574 793 31.6800000000 0.0132925585 0.0089795494 0.0143865747 0.0093284395 0.0047470000 16225253 955859216 1373700096 0.2018136382 -0.0183421634 -0.3948259354 794 31.7200000000 0.0132564595 0.0089849359 0.0143865747 0.0093504880 0.0047650000 16227229 955859216 1373700096 0.2028833926 -0.0172242820 -0.3947018981 795 31.7600000000 0.0130997915 0.0089901118 0.0143865747 0.0093793032 0.0074570000 16229205 955859216 1373700096 0.2035757005 -0.0164302755 -0.3943680525 796 31.8000000000 0.0130849136 0.0089952561 0.0143865747 0.0094127755 0.0069880000 16231181 955859216 1373700096 0.2043000758 -0.0155210327 -0.3941127062 797 31.8400000000 0.0129358275 0.0090002003 0.0143865747 0.0094929001 0.0043600000 16233157 955859216 1373700096 0.2052481920 -0.0142915957 -0.3936970532 798 31.8800000000 0.0129052298 0.0090050938 0.0143865747 0.0095941954 0.0073560000 16235133 955859216 1373700096 0.2057350725 -0.0137941213 -0.3933638334 799 31.9200000000 0.0129703758 0.0090100566 0.0143865747 0.0096496800 0.0053210000 16237109 955859216 1373700096 0.2061460912 -0.0136965374 -0.3930995166 800 31.9600000000 0.0130942501 0.0090151619 0.0143865747 0.0096697675 0.0072330000 16239085 955859216 1373700096 0.2068069875 -0.0136244539 -0.3927772641 801 32.0000000000 0.0131915938 0.0090203759 0.0143865747 0.0096730729 0.0055490000 16241061 955859216 1373700096 0.2076339424 -0.0135032190 -0.3921707273 802 32.0400000000 0.0132531030 0.0090256536 0.0143865747 0.0096756432 0.0046140000 16243037 955859216 1373700096 0.2086309642 -0.0132819964 -0.3915491104 803 32.0800000000 0.0134072080 0.0090311101 0.0143865747 0.0096742493 0.0074120000 16245013 955859216 1373700096 0.2096566707 -0.0130118812 -0.3909468651 804 32.1199999990 0.0134710865 0.0090366325 0.0143865747 0.0096733351 0.0060110000 16246989 955859216 1373700096 0.2104974389 -0.0128100552 -0.3901277483 805 32.1600000000 0.0135228680 0.0090422054 0.0143865747 0.0096743130 0.0046210000 16248965 955859216 1373700096 0.2112650573 -0.0125834793 -0.3895208538 806 32.2000000000 0.0135471486 0.0090477947 0.0143865747 0.0096735989 0.0041300000 16250941 955859216 1373700096 0.2120069861 -0.0126245283 -0.3887386918 807 32.2400000000 0.0136382040 0.0090534829 0.0143865747 0.0096686754 0.0075190000 16252917 955859216 1373700096 0.2128189951 -0.0126475776 -0.3881437182 808 32.2800000000 0.0136859696 0.0090592162 0.0143865747 0.0096635308 0.0069420000 16254893 955859216 1373700096 0.2134831697 -0.0124744773 -0.3874539733 809 32.3200000000 0.0136576062 0.0090649002 0.0143865747 0.0096596831 0.0047120000 16256869 955859216 1373700096 0.2142181844 -0.0123061100 -0.3868001699 810 32.3600000000 0.0136878341 0.0090706076 0.0143865747 0.0096563026 0.0041670000 16258845 955859216 1373700096 0.2149643600 -0.0124302357 -0.3858342171 811 32.4000000000 0.0137858000 0.0090764216 0.0143865747 0.0096506372 0.0075450000 16260821 955859216 1373700096 0.2158371806 -0.0126307951 -0.3848924339 812 32.4399999990 0.0139501924 0.0090824238 0.0143865747 0.0096449186 0.0074890000 16262797 955859216 1373700096 0.2168235332 -0.0129259247 -0.3837540746 813 32.4800000000 0.0140313571 0.0090885111 0.0143865747 0.0096397500 0.0081250000 16264773 955859216 1373700096 0.2178578228 -0.0129042985 -0.3828471303 814 32.5200000000 0.0140729640 0.0090946345 0.0143865747 0.0096368231 0.0076150000 16266749 955859216 1373700096 0.2186615616 -0.0131446626 -0.3817403018 815 32.5600000000 0.0141820051 0.0091008766 0.0143865747 0.0096386176 0.0075430000 16268725 955859216 1373700096 0.2195176780 -0.0133771235 -0.3806048632 816 32.6000000000 0.0142491683 0.0091071858 0.0143865747 0.0096412348 0.0065310000 16270701 955859216 1373700096 0.2204012126 -0.0132389544 -0.3796637058 817 32.6400000000 0.0142236436 0.0091134483 0.0143865747 0.0096434657 0.0047550000 16272677 955859216 1373700096 0.2211650461 -0.0132930567 -0.3785427809 818 32.6800000000 0.0141705601 0.0091196306 0.0143865747 0.0096470643 0.0041780000 16274653 955859216 1373700096 0.2218087614 -0.0132203046 -0.3775271475 819 32.7200000000 0.0140176006 0.0091256110 0.0143865747 0.0096489942 0.0075160000 16276629 955859216 1373700096 0.2223874032 -0.0130730895 -0.3763465285 820 32.7599999990 0.0141666848 0.0091317587 0.0143865747 0.0096518087 0.0072970000 16278605 955859216 1373700096 0.2227508277 -0.0134415673 -0.3751829863 821 32.7999999990 0.0142694181 0.0091380165 0.0143865747 0.0096551158 0.0046660000 16280581 955859216 1373700096 0.2229728699 -0.0136710620 -0.3743159175 822 32.8400000000 0.0142803323 0.0091442723 0.0143865747 0.0096583977 0.0075150000 16282557 955859216 1373700096 0.2229164839 -0.0142276855 -0.3732827902 823 32.8800000000 0.0143238939 0.0091505659 0.0143865747 0.0096697372 0.0048440000 16284533 955859216 1373700096 0.2230474055 -0.0147553002 -0.3721596301 824 32.9200000000 0.0143907340 0.0091569254 0.0143907340 0.0096785113 0.0041810000 16286509 955859216 1373700096 0.2230129242 -0.0153365247 -0.3710777164 825 32.9600000000 0.0144134974 0.0091632970 0.0144134974 0.0096900792 0.0075540000 16288485 955859216 1373700096 0.2228581011 -0.0157948527 -0.3702068031 826 33.0000000000 0.0144797303 0.0091697333 0.0144797303 0.0097010876 0.0059360000 16290461 955859216 1373700096 0.2227268964 -0.0159004852 -0.3694234788 827 33.0400000000 0.0143912463 0.0091760471 0.0144797303 0.0097062902 0.0075860000 16292437 955859216 1373700096 0.2224353701 -0.0162079483 -0.3686470091 828 33.0800000000 0.0143438531 0.0091822884 0.0144797303 0.0097147333 0.0049040000 16294413 955859216 1373700096 0.2218662649 -0.0167273972 -0.3681088984 829 33.1199999990 0.0144275390 0.0091886156 0.0144797303 0.0097236837 0.0042220000 16296389 955859216 1373700096 0.2213617563 -0.0167981964 -0.3675598204 830 33.1600000000 0.0142587340 0.0091947242 0.0144797303 0.0097241048 0.0075880000 16298365 955859216 1373700096 0.2208274454 -0.0167928077 -0.3666854203 831 33.2000000000 0.0146361738 0.0092012723 0.0146361738 0.0097269943 0.0071920000 16300341 955859216 1373700096 0.2201773226 -0.0167833772 -0.3645153642 832 33.2400000000 0.0142081715 0.0092072902 0.0146361738 0.0097219721 0.0043680000 16302317 955859216 1373700096 0.2193347812 -0.0167692937 -0.3640402555 833 33.2800000000 0.0142722642 0.0092133706 0.0146361738 0.0097175270 0.0056700000 16304293 955859216 1373700096 0.2186383307 -0.0170147810 -0.3630407751 834 33.3200000000 0.0143759549 0.0092195607 0.0146361738 0.0097133952 0.0056750000 16306269 955859216 1373700096 0.2179699093 -0.0169494245 -0.3620186448 835 33.3600000000 0.0142694227 0.0092256085 0.0146361738 0.0097077275 0.0047550000 16308245 955859216 1373700096 0.2174223661 -0.0167757496 -0.3609245420 836 33.4000000000 0.0142578185 0.0092316279 0.0146361738 0.0097020339 0.0047780000 16310221 955859216 1373700096 0.2165976763 -0.0170540623 -0.3597161472 837 33.4399999990 0.0143058421 0.0092376902 0.0146361738 0.0096971720 0.0048600000 16312197 955859216 1373700096 0.2155628502 -0.0174685754 -0.3588193655 838 33.4800000000 0.0143058244 0.0092437381 0.0146361738 0.0096923896 0.0048610000 16314173 955859216 1373700096 0.2144461423 -0.0176133998 -0.3582479060 839 33.5200000000 0.0142337205 0.0092496857 0.0146361738 0.0096868657 0.0077140000 16316149 955859216 1373700096 0.2131961584 -0.0177324098 -0.3578774929 840 33.5600000000 0.0140962470 0.0092554554 0.0146361738 0.0096816260 0.0075370000 16318125 955859216 1373700096 0.2118670046 -0.0184039474 -0.3572761416 841 33.6000000000 0.0141191650 0.0092612386 0.0146361738 0.0096792092 0.0047750000 16320101 955859216 1373700096 0.2104303241 -0.0194854382 -0.3561792672 842 33.6400000000 0.0143829910 0.0092673215 0.0146361738 0.0096844179 0.0073160000 16322077 955859216 1373700096 0.2092260271 -0.0203138813 -0.3553222716 843 33.6800000000 0.0145407785 0.0092735771 0.0146361738 0.0096855839 0.0058680000 16324053 955859216 1373700096 0.2081162632 -0.0205522943 -0.3544256091 844 33.7200000000 0.0144486530 0.0092797087 0.0146361738 0.0096829898 0.0048500000 16326029 955859216 1373700096 0.2068716586 -0.0209213886 -0.3533004522 845 33.7599999990 0.0146506717 0.0092860648 0.0146506717 0.0096836752 0.0043040000 16328005 955859216 1373700096 0.2056027651 -0.0213130321 -0.3527596593 846 33.7999999990 0.0147529533 0.0092925269 0.0147529533 0.0096835986 0.0043140000 16329981 955859216 1373700096 0.2043423057 -0.0212797336 -0.3521447480 847 33.8400000000 0.0146447215 0.0092988459 0.0147529533 0.0096798073 0.0043420000 16331957 955859216 1373700096 0.2031597197 -0.0210900027 -0.3512492776 848 33.8800000000 0.0145679824 0.0093050595 0.0147529533 0.0096742303 0.0042980000 16333933 955859216 1373700096 0.2019539773 -0.0208484363 -0.3504102528 849 33.9200000000 0.0135906711 0.0093101073 0.0147529533 0.0096715351 0.0045210000 16335909 955859216 1373700096 0.1988760680 -0.0195372272 -0.3536059260 850 33.9600000000 0.0139181362 0.0093155285 0.0147529533 0.0096675754 0.0043340000 16337885 955859216 1373700096 0.1989185661 -0.0200966578 -0.3498593569 851 34.0000000000 0.0135527849 0.0093205077 0.0147529533 0.0096645066 0.0045330000 16339861 955859216 1373700096 0.1962734163 -0.0197338406 -0.3522822559 852 34.0400000000 0.0134965312 0.0093254091 0.0147529533 0.0096609689 0.0045250000 16341837 955859216 1373700096 0.1944900900 -0.0198183693 -0.3526392877 853 34.0800000000 0.0135752019 0.0093303913 0.0147529533 0.0096581559 0.0043310000 16343813 955859216 1373700096 0.1942579448 -0.0204602461 -0.3497029245 854 34.1199999990 0.0135269817 0.0093353053 0.0147529533 0.0096544183 0.0081170000 16345789 955859216 1373700096 0.1918594390 -0.0208281595 -0.3512929082 855 34.1600000000 0.0134496205 0.0093401174 0.0147529533 0.0096498739 0.0078240000 16347765 955859216 1373700096 0.1914279908 -0.0222250614 -0.3479683995 856 34.2000000000 0.0137759475 0.0093452994 0.0147529533 0.0096473952 0.0058010000 16349741 955859216 1373700096 0.1903225332 -0.0235672258 -0.3460718691 857 34.2400000000 0.0141039481 0.0093508521 0.0147529533 0.0096480020 0.0043620000 16351717 955859216 1373700096 0.1892742664 -0.0239501782 -0.3450316191 858 34.2800000000 0.0140412748 0.0093563188 0.0147529533 0.0096437026 0.0043570000 16353693 955859216 1373700096 0.1880391091 -0.0244342946 -0.3437041044 859 34.3200000000 0.0141095780 0.0093618523 0.0147529533 0.0096410309 0.0043640000 16355669 955859216 1373700096 0.1866638958 -0.0249951500 -0.3420760930 860 34.3600000000 0.0142233521 0.0093675052 0.0147529533 0.0096370851 0.0078760000 16357645 955859216 1373700096 0.1853012294 -0.0249747951 -0.3407324851 861 34.4000000000 0.0141100613 0.0093730134 0.0147529533 0.0096316158 0.0066910000 16359621 955859216 1373700096 0.1838714927 -0.0249885414 -0.3393411040 862 34.4400000000 0.0141443098 0.0093785485 0.0147529533 0.0096261303 0.0049150000 16361597 955859216 1373700096 0.1823713183 -0.0251680296 -0.3377352357 863 34.4800000000 0.0142669389 0.0093842130 0.0147529533 0.0096206115 0.0043920000 16363573 955859216 1373700096 0.1808510274 -0.0250555538 -0.3362370729 864 34.5200000000 0.0142510748 0.0093898459 0.0147529533 0.0096155607 0.0043570000 16365549 955859216 1373700096 0.1789968461 -0.0247454438 -0.3342399895 865 34.5600000000 0.0141327679 0.0093953290 0.0147529533 0.0096117531 0.0079150000 16367525 955859216 1373700096 0.1771456897 -0.0248973686 -0.3321116567 866 34.6000000000 0.0141906478 0.0094008664 0.0147529533 0.0096062493 0.0079190000 16369501 955859216 1373700096 0.1751072556 -0.0252489150 -0.3297089338 867 34.6400000000 0.0143961590 0.0094066279 0.0147529533 0.0096010324 0.0049960000 16371477 955859216 1373700096 0.1729618609 -0.0249728169 -0.3279719055 868 34.6800000000 0.0143474098 0.0094123201 0.0147529533 0.0095971019 0.0074250000 16373453 955859216 1373700096 0.1707029641 -0.0243722014 -0.3259555399 869 34.7200000000 0.0143511761 0.0094180035 0.0147529533 0.0095946784 0.0047330000 16375429 955859216 1373700096 0.1684166044 -0.0236213040 -0.3238918185 870 34.7600000000 0.0142493676 0.0094235568 0.0147529533 0.0095973283 0.0076240000 16377405 955859216 1373700096 0.1658789068 -0.0230111480 -0.3214527965 871 34.8000000000 0.0140925236 0.0094289172 0.0147529533 0.0096003443 0.0050500000 16379381 955859216 1373700096 0.1631979048 -0.0233244281 -0.3189555407 872 34.8400000000 0.0142737255 0.0094344732 0.0147529533 0.0095948635 0.0043760000 16381357 955859216 1373700096 0.1602878869 -0.0240700096 -0.3161497414 873 34.8800000000 0.0147533119 0.0094405658 0.0147533119 0.0095933907 0.0078850000 16383333 955859216 1373700096 0.1575193256 -0.0234660227 -0.3139857948 874 34.9200000000 0.0147227608 0.0094466095 0.0147533119 0.0095886777 0.0074850000 16385309 955859216 1373700096 0.1547485739 -0.0221371092 -0.3118881583 875 34.9600000000 0.0144833671 0.0094523658 0.0147533119 0.0095918516 0.0048370000 16387285 955859216 1373700096 0.1518365890 -0.0214160811 -0.3096284270 876 35.0000000000 0.0144199394 0.0094580365 0.0147533119 0.0095951862 0.0040340000 16389261 955859216 1373700096 0.1488623768 -0.0210264977 -0.3073693812 877 35.0400000000 0.0144786509 0.0094637613 0.0147533119 0.0095963833 0.0040230000 16391237 955859216 1373700096 0.1458749175 -0.0204654075 -0.3050473630 878 35.0800000000 0.0143519165 0.0094693287 0.0147533119 0.0096011411 0.0079690000 16393213 955859216 1373700096 0.1427839696 -0.0204412267 -0.3026393652 879 35.1200000000 0.0144642955 0.0094750112 0.0147533119 0.0095994513 0.0073820000 16395189 955859216 1373700096 0.1397801042 -0.0200163033 -0.3006197214 880 35.1600000000 0.0144844707 0.0094807038 0.0147533119 0.0096060244 0.0047230000 16397165 955859216 1373700096 0.1368437558 -0.0190725029 -0.2981390655 881 35.2000000000 0.0144059397 0.0094862943 0.0147533119 0.0096225426 0.0060580000 16399141 955859216 1373700096 0.1334787309 -0.0191624090 -0.2966075242 882 35.2400000000 0.0144746946 0.0094919501 0.0147533119 0.0096240479 0.0059970000 16401117 955859216 1373700096 0.1307474822 -0.0191880222 -0.2937113643 883 35.2800000000 0.0144656245 0.0094975828 0.0147533119 0.0096201615 0.0081570000 16403093 955859216 1373700096 0.1273305118 -0.0191081483 -0.2919148803 884 35.3200000000 0.0144934710 0.0095032343 0.0147533119 0.0096156995 0.0058090000 16405069 955859216 1373700096 0.1245460957 -0.0182258207 -0.2900124192 885 35.3600000000 0.0144643420 0.0095088400 0.0147533119 0.0096123281 0.0060490000 16407045 955859216 1373700096 0.1216477379 -0.0177420359 -0.2880432010 886 35.4000000000 0.0144582279 0.0095144262 0.0147533119 0.0096079008 0.0081820000 16409021 955859216 1373700096 0.1186378747 -0.0178064816 -0.2858515680 887 35.4400000000 0.0144768907 0.0095200209 0.0147533119 0.0096026369 0.0051060000 16410997 955859216 1373700096 0.1157371774 -0.0177686233 -0.2839724422 888 35.4800000000 0.0144909443 0.0095256188 0.0147533119 0.0095973268 0.0079650000 16412973 955859216 1373700096 0.1129128784 -0.0177396573 -0.2821092606 889 35.5200000000 0.0145131666 0.0095312291 0.0147533119 0.0095936438 0.0048460000 16414949 955859216 1373700096 0.1102907732 -0.0172275975 -0.2803625166 890 35.5600000000 0.0145270592 0.0095368424 0.0147533119 0.0095888634 0.0060950000 16416925 955859216 1373700096 0.1077264696 -0.0166307669 -0.2785591781 891 35.6000000000 0.0145445038 0.0095424626 0.0147533119 0.0095836029 0.0051120000 16418901 955859216 1373700096 0.1051598489 -0.0158402491 -0.2769072354 892 35.6400000000 0.0145378029 0.0095480628 0.0147533119 0.0095783095 0.0081330000 16420877 955859216 1373700096 0.1026335284 -0.0153771648 -0.2752874196 893 35.6800000000 0.0145223243 0.0095536331 0.0147533119 0.0095730039 0.0069940000 16422853 955859216 1373700096 0.1000899002 -0.0148885651 -0.2737257183 894 35.7200000000 0.0145321535 0.0095592019 0.0147533119 0.0095678334 0.0050970000 16424829 955859216 1373700096 0.0976023152 -0.0143910674 -0.2723136246 895 35.7600000000 0.0145675912 0.0095647979 0.0147533119 0.0095629971 0.0044820000 16426805 955859216 1373700096 0.0951188132 -0.0140455887 -0.2710545063 896 35.8000000000 0.0145706264 0.0095703847 0.0147533119 0.0095579199 0.0081190000 16428781 955859216 1373700096 0.0926656201 -0.0139220739 -0.2696279585 897 35.8400000000 0.0145272091 0.0095759107 0.0147533119 0.0095527002 0.0069690000 16430757 955859216 1373700096 0.0902903974 -0.0134009123 -0.2684592307 898 35.8800000000 0.0145446481 0.0095814438 0.0147533119 0.0095476586 0.0050750000 16432733 955859216 1373700096 0.0878514126 -0.0127163203 -0.2673999965 899 35.9200000000 0.0145524265 0.0095869733 0.0147533119 0.0095430207 0.0044700000 16434709 955859216 1373700096 0.0852549151 -0.0125446543 -0.2665933371 900 35.9600000000 0.0146006923 0.0095925441 0.0147533119 0.0095377989 0.0087590000 16436685 955859216 1373700096 0.0827186853 -0.0128698209 -0.2661829889 901 36.0000000000 0.0145633193 0.0095980610 0.0147533119 0.0095342794 0.0060290000 16438661 955859216 1373700096 0.0803520232 -0.0126741007 -0.2659947574 902 36.0400000000 0.0145497071 0.0096035507 0.0147533119 0.0095290478 0.0079170000 16440637 955859216 1373700096 0.0779947117 -0.0123288361 -0.2657454908 903 36.0800000000 0.0145827541 0.0096090647 0.0147533119 0.0095238476 0.0046490000 16442613 955859216 1373700096 0.0754503831 -0.0123956306 -0.2654748261 904 36.1200000000 0.0144542390 0.0096144245 0.0147533119 0.0095186537 0.0059180000 16444589 955859216 1373700096 0.0730594099 -0.0121990144 -0.2649850845 905 36.1600000000 0.0145102991 0.0096198343 0.0147533119 0.0095137788 0.0079210000 16446565 955859216 1373700096 0.0706176758 -0.0117559088 -0.2645636201 906 36.2000000000 0.0144307762 0.0096251444 0.0147533119 0.0095103068 0.0049920000 16448541 955859216 1373700096 0.0680027530 -0.0116754360 -0.2643486559 907 36.2400000000 0.0144127496 0.0096304229 0.0147533119 0.0095067891 0.0079210000 16450517 955859216 1373700096 0.0653759614 -0.0118887285 -0.2647613585 908 36.2800000000 0.0144029493 0.0096356789 0.0147533119 0.0095016326 0.0069310000 16452493 955859216 1373700096 0.0627150238 -0.0120517109 -0.2651857734 909 36.3200000000 0.0144108627 0.0096409322 0.0147533119 0.0094964095 0.0043630000 16454469 955859216 1373700096 0.0600811020 -0.0120701250 -0.2651000321 910 36.3600000000 0.0144342789 0.0096461996 0.0147533119 0.0094912415 0.0039260000 16456445 955859216 1373700096 0.0574625023 -0.0118954210 -0.2650469840 911 36.4000000000 0.0143987192 0.0096514164 0.0147533119 0.0094864452 0.0079590000 16458421 955859216 1373700096 0.0548033975 -0.0121497996 -0.2653787136 912 36.4400000000 0.0144172031 0.0096566420 0.0147533119 0.0094812611 0.0069920000 16460397 955859216 1373700096 0.0522879511 -0.0119881900 -0.2652305663 913 36.4800000000 0.0144003136 0.0096618377 0.0147533119 0.0094763266 0.0049530000 16462373 955859216 1373700096 0.0498352572 -0.0116478195 -0.2650821507 914 36.5200000000 0.0143810948 0.0096670010 0.0147533119 0.0094727851 0.0044060000 16464349 955859216 1373700096 0.0471917912 -0.0117935138 -0.2650567293 915 36.5600000000 0.0143646579 0.0096721351 0.0147533119 0.0094689691 0.0082010000 16466325 955859216 1373700096 0.0447431616 -0.0119970599 -0.2654178441 916 36.6000000000 0.0143898791 0.0096772855 0.0147533119 0.0094640250 0.0073050000 16468301 955859216 1373700096 0.0423572175 -0.0121802613 -0.2653644085 917 36.6400000000 0.0143529391 0.0096823843 0.0147533119 0.0094588652 0.0045040000 16470277 955859216 1373700096 0.0399369970 -0.0127725154 -0.2656148076 918 36.6800000000 0.0143647669 0.0096874850 0.0147533119 0.0094540263 0.0040110000 16472253 955859216 1373700096 0.0376813263 -0.0128608318 -0.2653593123 919 36.7200000000 0.0144014843 0.0096926145 0.0147533119 0.0094488846 0.0082140000 16474229 955859216 1373700096 0.0356177054 -0.0126716793 -0.2650803924 920 36.7600000000 0.0144029902 0.0096977344 0.0147533119 0.0094440163 0.0074090000 16476205 955859216 1373700096 0.0335699953 -0.0128703360 -0.2650711536 921 36.8000000000 0.0143689010 0.0097028063 0.0147533119 0.0094389231 0.0045540000 16478181 955859216 1373700096 0.0317584388 -0.0126482239 -0.2649038732 922 36.8400000000 0.0144481808 0.0097079531 0.0147533119 0.0094342348 0.0040270000 16480157 955859216 1373700096 0.0301312637 -0.0122344466 -0.2644442618 923 36.8800000000 0.0144380676 0.0097130778 0.0147533119 0.0094304741 0.0082180000 16482133 955859216 1373700096 0.0285510700 -0.0121168401 -0.2641874254 924 36.9200000000 0.0144028403 0.0097181533 0.0147533119 0.0094280165 0.0076150000 16484109 955859216 1373700096 0.0270846132 -0.0123101585 -0.2643918991 925 36.9600000000 0.0144192465 0.0097232356 0.0147533119 0.0094237322 0.0054370000 16486085 955859216 1373700096 0.0255398266 -0.0125671513 -0.2641665041 926 37.0000000000 0.0144425621 0.0097283320 0.0147533119 0.0094187230 0.0081530000 16488061 955859216 1373700096 0.0242510475 -0.0123260971 -0.2641471028 927 37.0400000000 0.0144549655 0.0097334309 0.0147533119 0.0094141881 0.0050890000 16490037 955859216 1373700096 0.0231001843 -0.0121987201 -0.2641394734 928 37.0800000000 0.0144281778 0.0097384899 0.0147533119 0.0094111190 0.0076760000 16492013 955859216 1373700096 0.0220569111 -0.0113786561 -0.2634833157 929 37.1200000000 0.0144442422 0.0097435553 0.0147533119 0.0094102248 0.0055430000 16493989 955859216 1373700096 0.0210664291 -0.0112175774 -0.2631458342 930 37.1600000000 0.0144569175 0.0097486234 0.0147533119 0.0094095055 0.0044860000 16495965 955859216 1373700096 0.0202212706 -0.0110219643 -0.2628876865 931 37.2000000000 0.0144577539 0.0097536816 0.0147533119 0.0094077851 0.0082570000 16497941 955859216 1373700096 0.0194026697 -0.0107057998 -0.2625832856 932 37.2400000000 0.0144914594 0.0097587650 0.0147533119 0.0094048898 0.0052180000 16499917 955859216 1373700096 0.0187371820 -0.0105826063 -0.2624798715 933 37.2800000000 0.0144615471 0.0097638055 0.0147533119 0.0094019404 0.0083060000 16501893 955859216 1373700096 0.0180285014 -0.0101343282 -0.2620120645 934 37.3200000000 0.0144547746 0.0097688280 0.0147533119 0.0093996202 0.0051890000 16503869 955859216 1373700096 0.0175088588 -0.0094060656 -0.2615399659 935 37.3600000000 0.0144536775 0.0097738385 0.0147533119 0.0093995341 0.0083010000 16505845 955859216 1373700096 0.0171103552 -0.0090335375 -0.2613946795 936 37.4000000000 0.0144015793 0.0097787827 0.0147533119 0.0093977912 0.0052320000 16507821 955859216 1373700096 0.0166880172 -0.0088433716 -0.2612899542 937 37.4400000000 0.0144818630 0.0097838019 0.0147533119 0.0093943773 0.0044950000 16509797 955859216 1373700096 0.0164075792 -0.0089569977 -0.2612907887 938 37.4800000000 0.0144976638 0.0097888274 0.0147533119 0.0093910277 0.0084250000 16511773 955859216 1373700096 0.0161269326 -0.0090285698 -0.2613003254 939 37.5200000000 0.0145312548 0.0097938779 0.0147533119 0.0093867429 0.0062310000 16513749 955859216 1373700096 0.0161210056 -0.0088727055 -0.2615518868 940 37.5600000000 0.0145449573 0.0097989322 0.0147533119 0.0093825181 0.0065430000 16515725 955859216 1373700096 0.0161098428 -0.0085946880 -0.2616588771 941 37.6000000000 0.0145601304 0.0098039920 0.0147533119 0.0093789241 0.0071130000 16517701 955859216 1373700096 0.0160446782 -0.0081024840 -0.2614972293 942 37.6400000000 0.0146045890 0.0098090881 0.0147533119 0.0093758183 0.0051520000 16519677 955859216 1373700096 0.0161689520 -0.0076772170 -0.2615765035 943 37.6800000000 0.0145862540 0.0098141541 0.0147533119 0.0093742327 0.0080010000 16521653 955859216 1373700096 0.0162666254 -0.0074312687 -0.2618085146 944 37.7200000000 0.0145906424 0.0098192139 0.0147533119 0.0093719860 0.0049700000 16523629 955859216 1373700096 0.0163933635 -0.0069560474 -0.2619537711 945 37.7600000000 0.0145789012 0.0098242506 0.0147533119 0.0093695878 0.0083670000 16525605 955859216 1373700096 0.0165442731 -0.0066630859 -0.2621262372 946 37.8000000000 0.0145730386 0.0098292705 0.0147533119 0.0093672308 0.0052370000 16527581 955859216 1373700096 0.0165555589 -0.0065030027 -0.2622161508 947 37.8400000000 0.0145878382 0.0098342953 0.0147533119 0.0093638645 0.0045340000 16529557 955859216 1373700096 0.0166979283 -0.0062515112 -0.2621326745 948 37.8800000000 0.0145950494 0.0098393172 0.0147533119 0.0093612541 0.0045240000 16531533 955859216 1373700096 0.0167998224 -0.0060700290 -0.2621873021 949 37.9200000000 0.0146105774 0.0098443449 0.0147533119 0.0093583426 0.0083720000 16533509 955859216 1373700096 0.0170084741 -0.0058141733 -0.2623547316 950 37.9600000000 0.0146286990 0.0098493811 0.0147533119 0.0093544269 0.0075090000 16535485 955859216 1373700096 0.0172668025 -0.0054054139 -0.2626495063 951 38.0000000000 0.0146209849 0.0098543985 0.0147533119 0.0093502135 0.0045880000 16537461 955859216 1373700096 0.0174726620 -0.0051393951 -0.2627042830 952 38.0400000000 0.0146203004 0.0098594047 0.0147533119 0.0093478737 0.0040950000 16539437 955859216 1373700096 0.0176091883 -0.0048942799 -0.2625924051 953 38.0800000000 0.0146410093 0.0098644222 0.0147533119 0.0093437690 0.0083860000 16541413 955859216 1373700096 0.0179655757 -0.0046630581 -0.2629550099 954 38.1200000000 0.0146389315 0.0098694269 0.0147533119 0.0093389915 0.0078570000 16543389 955859216 1373700096 0.0182074104 -0.0043097646 -0.2629794180 955 38.1600000000 0.0146484328 0.0098744311 0.0147533119 0.0093344725 0.0056100000 16545365 955859216 1373700096 0.0183738656 -0.0043013808 -0.2630186081 956 38.2000000000 0.0146601228 0.0098794370 0.0147533119 0.0093296313 0.0045450000 16547341 955859216 1373700096 0.0186793525 -0.0039614378 -0.2632340789 957 38.2400000000 0.0146362698 0.0098844076 0.0147533119 0.0093248796 0.0045460000 16549317 955859216 1373700096 0.0188087765 -0.0040623052 -0.2634552717 958 38.2800000000 0.0146761378 0.0098894094 0.0147533119 0.0093201830 0.0084010000 16551293 955859216 1373700096 0.0189678743 -0.0039012921 -0.2634405196 959 38.3200000000 0.0146857873 0.0098944108 0.0147533119 0.0093154709 0.0068770000 16553269 955859216 1373700096 0.0192482993 -0.0038917989 -0.2637579143 960 38.3600000000 0.0146730971 0.0098993886 0.0147533119 0.0093108831 0.0046090000 16555245 955859216 1373700096 0.0194082335 -0.0037755296 -0.2635705769 961 38.4000000000 0.0146829933 0.0099043664 0.0147533119 0.0093063625 0.0083700000 16557221 955859216 1373700096 0.0197144002 -0.0036495633 -0.2637816668 962 38.4400000000 0.0146888811 0.0099093399 0.0147533119 0.0093017203 0.0052810000 16559197 955859216 1373700096 0.0199757088 -0.0035397429 -0.2640454769 963 38.4800000000 0.0146660395 0.0099142793 0.0147533119 0.0092969873 0.0045010000 16561173 955859216 1373700096 0.0202477463 -0.0036556781 -0.2641555369 964 38.5200000000 0.0146965599 0.0099192402 0.0147533119 0.0092922342 0.0045050000 16563149 955859216 1373700096 0.0205774419 -0.0034808952 -0.2642779350 965 38.5600000000 0.0146741550 0.0099241676 0.0147533119 0.0092875004 0.0083480000 16565125 955859216 1373700096 0.0208513066 -0.0033929001 -0.2642328143 966 38.6000000000 0.0146555537 0.0099290655 0.0147533119 0.0092829025 0.0080120000 16567101 955859216 1373700096 0.0211105179 -0.0033937611 -0.2643910944 967 38.6400000000 0.0146629298 0.0099339609 0.0147533119 0.0092781338 0.0050030000 16569077 955859216 1373700096 0.0214047078 -0.0033756590 -0.2645454407 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:32:37 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0034140000 14154421 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025714899 0.0012857449 0.0025714899 0.0016432907 0.0026440000 14351317 955859216 1373700096 0.0001492798 -0.0015223033 0.0011158339 3 0.0800000000 0.0054865531 0.0026860143 0.0054865531 0.0017288008 0.0014640000 14353685 955859216 1373700096 -0.0038239695 -0.0031566895 0.0017731137 4 0.1200000000 0.0071276301 0.0037964183 0.0071276301 0.0015559976 0.0014500000 14356061 955859216 1373700096 -0.0022661428 -0.0055823806 0.0010928739 5 0.1600000000 0.0089090429 0.0048189432 0.0089090429 0.0013813257 0.0014460000 14358421 955859216 1373700096 -0.0045922636 -0.0064012622 0.0030444816 6 0.2000000000 0.0103094121 0.0057340213 0.0103094121 0.0012690832 0.0014560000 14361197 955859216 1373700096 -0.0038758849 -0.0083406530 0.0026003199 7 0.2400000000 0.0119307498 0.0066192683 0.0119307498 0.0012535126 0.0014370000 14363173 955859216 1373700096 -0.0037794772 -0.0100496644 0.0033220870 8 0.2800000000 0.0135899493 0.0074906034 0.0135899493 0.0012198315 0.0014480000 14365149 955859216 1373700096 -0.0048457128 -0.0114490706 0.0035914571 9 0.3200000000 0.0145517997 0.0082751808 0.0145517997 0.0012453706 0.0014530000 14367893 955859216 1373700096 -0.0065782429 -0.0129554095 0.0038957214 10 0.3600000000 0.0165167265 0.0090993353 0.0165167265 0.0012884565 0.0014540000 14371469 955859216 1373700096 -0.0065372740 -0.0137011874 0.0049862019 11 0.4000000000 0.0168790948 0.0098065862 0.0168790948 0.0015240100 0.0014810000 14373445 955859216 1373700096 -0.0073842062 -0.0149063021 0.0057881647 12 0.4400000000 0.0184423029 0.0105262293 0.0184423029 0.0018490029 0.0014690000 14375421 955859216 1373700096 -0.0073227854 -0.0166475959 0.0053976900 13 0.4800000000 0.0195128378 0.0112175068 0.0195128378 0.0019803508 0.0014640000 14377397 955859216 1373700096 -0.0092979828 -0.0178076830 0.0062139048 14 0.5200000000 0.0216195527 0.0119605101 0.0216195527 0.0019410659 0.0014630000 14379373 955859216 1373700096 -0.0092627676 -0.0187848732 0.0061659715 15 0.5600000000 0.0229770951 0.0126949491 0.0229770951 0.0018743843 0.0014640000 14381349 955859216 1373700096 -0.0117968675 -0.0189196728 0.0072214934 16 0.6000000000 0.0226544160 0.0133174158 0.0229770951 0.0018616014 0.0014620000 14383325 955859216 1373700096 -0.0113988873 -0.0204566959 0.0061501749 17 0.6400000000 0.0235626716 0.0139200779 0.0235626716 0.0018289043 0.0014830000 14386837 955859216 1373700096 -0.0131508559 -0.0226259008 0.0049336371 18 0.6800000000 0.0242600460 0.0144945206 0.0242600460 0.0017749741 0.0014750000 14392013 955859216 1373700096 -0.0144332219 -0.0231392365 0.0060616792 19 0.7200000000 0.0251539722 0.0150555443 0.0251539722 0.0017848209 0.0014730000 14393989 955859216 1373700096 -0.0158722661 -0.0237338487 0.0058700708 20 0.7600000000 0.0248820707 0.0155468707 0.0251539722 0.0018968664 0.0014570000 14395965 955859216 1373700096 -0.0188213158 -0.0247086678 0.0054082205 21 0.8000000000 0.0256400034 0.0160274960 0.0256400034 0.0018580091 0.0014730000 14397941 955859216 1373700096 -0.0215970408 -0.0245158114 0.0059202635 22 0.8400000000 0.0260289814 0.0164821090 0.0260289814 0.0018336065 0.0014740000 14399917 955859216 1373700096 -0.0269964878 -0.0256771985 0.0055130380 23 0.8800000000 0.0264441110 0.0169152395 0.0264441110 0.0017931248 0.0014880000 14401893 955859216 1373700096 -0.0269332919 -0.0270425621 0.0040367190 24 0.9200000000 0.0290556718 0.0174210909 0.0290556718 0.0017815465 0.0014850000 14403869 955859216 1373700096 -0.0341930501 -0.0279741753 0.0039182645 25 0.9600000000 0.0310614351 0.0179667046 0.0310614351 0.0017828309 0.0015000000 14405845 955859216 1373700096 -0.0355899297 -0.0287477206 0.0036814229 26 1.0000000000 0.0305674486 0.0184513486 0.0310614351 0.0017519344 0.0015210000 14407821 955859216 1373700096 -0.0414748490 -0.0297502615 0.0043693134 27 1.0400000000 0.0317295119 0.0189431325 0.0317295119 0.0018674197 0.0015070000 14409797 955859216 1373700096 -0.0470246449 -0.0315761790 0.0024925619 28 1.0800000000 0.0337575115 0.0194722174 0.0337575115 0.0020564237 0.0015080000 14411773 955859216 1373700096 -0.0515033975 -0.0317413583 0.0026671030 29 1.1200000000 0.0356585383 0.0200303664 0.0356585383 0.0022448384 0.0015060000 14413749 955859216 1373700096 -0.0572019108 -0.0333457328 0.0003464560 30 1.1600000000 0.0347998030 0.0205226810 0.0356585383 0.0022606539 0.0015360000 14415725 955859216 1373700096 -0.0664406046 -0.0332451984 0.0020102677 31 1.2000000000 0.0365353301 0.0210392180 0.0365353301 0.0022736935 0.0015120000 14417701 955859216 1373700096 -0.0729270652 -0.0342112519 0.0006623828 32 1.2400000000 0.0382359922 0.0215766172 0.0382359922 0.0023182790 0.0015340000 14419677 955859216 1373700096 -0.0794136450 -0.0354816876 -0.0012557873 33 1.2800000000 0.0381635055 0.0220792502 0.0382359922 0.0023846032 0.0015350000 14424725 955859216 1373700096 -0.0849446952 -0.0357925259 -0.0015545167 34 1.3200000000 0.0219272338 0.0220747791 0.0382359922 0.0027751795 0.0016910000 14433101 955859216 1373700096 -0.1155797988 -0.0208642464 -0.0059185522 35 1.3600000000 0.0269344803 0.0222136278 0.0382359922 0.0031654645 0.0015170000 14435077 955859216 1373700096 -0.1185257062 -0.0249655452 -0.0073487419 36 1.4000000000 0.0309110973 0.0224552241 0.0382359922 0.0037748075 0.0015460000 14437053 955859216 1373700096 -0.1235096678 -0.0279111750 -0.0082321987 37 1.4400000000 0.0267255809 0.0225706392 0.0382359922 0.0037799400 0.0015760000 14439029 955859216 1373700096 -0.1348732263 -0.0259267520 -0.0080188420 38 1.4800000000 0.0257898234 0.0226553545 0.0382359922 0.0037348291 0.0015780000 14441005 955859216 1373700096 -0.1467354596 -0.0255481862 -0.0075336513 39 1.5200000000 0.0296816528 0.0228355160 0.0382359922 0.0036944879 0.0015300000 14442981 955859216 1373700096 -0.1497272700 -0.0299902130 -0.0098957764 40 1.5600000000 0.0271244757 0.0229427400 0.0382359922 0.0036927154 0.0015540000 14444957 955859216 1373700096 -0.1597565711 -0.0291470457 -0.0098983068 41 1.6000000000 0.0262917206 0.0230244225 0.0382359922 0.0037106982 0.0015720000 14446933 955859216 1373700096 -0.1702382714 -0.0294596720 -0.0083986018 42 1.6400000000 0.0271689426 0.0231231015 0.0382359922 0.0036673273 0.0015700000 14448909 955859216 1373700096 -0.1833939105 -0.0288302954 -0.0060180849 43 1.6800000000 0.0303568617 0.0232913285 0.0382359922 0.0036339935 0.0015190000 14450885 955859216 1373700096 -0.1894207299 -0.0314002708 -0.0020218994 44 1.7200000000 0.0335753746 0.0235250568 0.0382359922 0.0036431220 0.0015270000 14452861 955859216 1373700096 -0.1955402046 -0.0352436863 -0.0032748091 45 1.7600000000 0.0372968726 0.0238310972 0.0382359922 0.0036346454 0.0015270000 14454837 955859216 1373700096 -0.2029261738 -0.0367140546 0.0011326667 46 1.8000000000 0.0400000215 0.0241825955 0.0400000215 0.0036274474 0.0015540000 14456813 955859216 1373700096 -0.2087720186 -0.0388193429 0.0019324797 47 1.8400000000 0.0405627936 0.0245311104 0.0405627936 0.0037262304 0.0015240000 14458789 955859216 1373700096 -0.2119505554 -0.0412524976 0.0018202595 48 1.8800000000 0.0420300178 0.0248956710 0.0420300178 0.0037498840 0.0015550000 14460765 955859216 1373700096 -0.2160180658 -0.0428882390 0.0032224830 49 1.9200000000 0.0443949960 0.0252936164 0.0443949960 0.0037138966 0.0015600000 14462741 955859216 1373700096 -0.2228525132 -0.0440631062 0.0045265714 50 1.9600000000 0.0251944512 0.0252916331 0.0443949960 0.0038257566 0.0017520000 14464717 955859216 1373700096 -0.2402607799 -0.0259377416 0.0049335468 51 2.0000000000 0.0294330213 0.0253728368 0.0443949960 0.0038202869 0.0015490000 14466693 955859216 1373700096 -0.2385556549 -0.0302593987 0.0030527732 52 2.0400000000 0.0335006192 0.0255291403 0.0443949960 0.0037909098 0.0015580000 14468669 955859216 1373700096 -0.2414292842 -0.0337276459 0.0031725832 53 2.0800000000 0.0354744643 0.0257167879 0.0443949960 0.0038135487 0.0015820000 14470645 955859216 1373700096 -0.2432913184 -0.0380131043 0.0004926785 54 2.1200000000 0.0258946158 0.0257200810 0.0443949960 0.0040130068 0.0016750000 14472621 955859216 1373700096 -0.2575094998 -0.0303258616 0.0039322362 55 2.1600000000 0.0309320167 0.0258148435 0.0443949960 0.0040584628 0.0020360000 14474597 955859216 1373700096 -0.2591513097 -0.0344475284 0.0048146565 56 2.2000000000 0.0258607138 0.0258156626 0.0443949960 0.0041004331 0.0017360000 14476573 955859216 1373700096 -0.2797043622 -0.0291080922 0.0127271097 57 2.2400000000 0.0278055463 0.0258505728 0.0443949960 0.0040717508 0.0016010000 14478549 955859216 1373700096 -0.2843022048 -0.0336680375 0.0137756579 58 2.2800000000 0.0279515926 0.0258867973 0.0443949960 0.0040754733 0.0016320000 14480525 955859216 1373700096 -0.2935896218 -0.0344513543 0.0165775903 59 2.3200000000 0.0289261620 0.0259383120 0.0443949960 0.0042115891 0.0016460000 14482501 955859216 1373700096 -0.3075535893 -0.0330572687 0.0224320795 60 2.3600000000 0.0308914296 0.0260208639 0.0443949960 0.0043336082 0.0017460000 14484477 955859216 1373700096 -0.3106769323 -0.0366975665 0.0210322924 61 2.4000000000 0.0326207168 0.0261290582 0.0443949960 0.0044632376 0.0014670000 14486453 955859216 1373700096 -0.3167918921 -0.0397795215 0.0211328790 62 2.4400000000 0.0260501225 0.0261277851 0.0443949960 0.0045534233 0.0016150000 14488429 955859216 1373700096 -0.3417731524 -0.0328898877 0.0299048200 63 2.4800000000 0.0272089802 0.0261449469 0.0443949960 0.0047031279 0.0015310000 14490405 955859216 1373700096 -0.3502490520 -0.0351472534 0.0313210264 64 2.5200000000 0.0282193851 0.0261773600 0.0443949960 0.0050603319 0.0015440000 14492381 955859216 1373700096 -0.3625922501 -0.0349138901 0.0360459425 65 2.5600000000 0.0282841586 0.0262097723 0.0443949960 0.0053563773 0.0015540000 14500501 955859216 1373700096 -0.3763523400 -0.0351319872 0.0397613458 66 2.6000000000 0.0293450095 0.0262572759 0.0443949960 0.0054463696 0.0015350000 14515277 955859216 1373700096 -0.3868530989 -0.0348540023 0.0419133641 67 2.6400000000 0.0304976087 0.0263205644 0.0443949960 0.0055015753 0.0015290000 14517253 955859216 1373700096 -0.3969092965 -0.0334788300 0.0443840772 68 2.6800000000 0.0304218773 0.0263808778 0.0443949960 0.0054817464 0.0015520000 14519229 955859216 1373700096 -0.4080599248 -0.0336158462 0.0436481871 69 2.7200000000 0.0301492531 0.0264354920 0.0443949960 0.0054432035 0.0015420000 14521205 955859216 1373700096 -0.4176486433 -0.0330810770 0.0480478033 70 2.7600000000 0.0359803960 0.0265718478 0.0443949960 0.0054101316 0.0014760000 14523181 955859216 1373700096 -0.4255196154 -0.0368855782 0.0489431508 71 2.8000000000 0.0408588275 0.0267730728 0.0443949960 0.0054322191 0.0014930000 14525157 955859216 1373700096 -0.4319700003 -0.0410033800 0.0469319820 72 2.8400000000 0.0275359321 0.0267836681 0.0443949960 0.0063411896 0.0016790000 14527133 955859216 1373700096 -0.4500044286 -0.0230121091 0.0466995239 73 2.8800000000 0.0308627598 0.0268395461 0.0443949960 0.0063843899 0.0015880000 14529109 955859216 1373700096 -0.4595427811 -0.0248584840 0.0490922146 74 2.9200000000 0.0377883315 0.0269875026 0.0443949960 0.0064302647 0.0015210000 14531085 955859216 1373700096 -0.4606513381 -0.0298728887 0.0474839844 75 2.9600000000 0.0447943099 0.0272249267 0.0447943099 0.0064502786 0.0015270000 14533061 955859216 1373700096 -0.4608715177 -0.0329545736 0.0461760908 76 3.0000000000 0.0293146856 0.0272524235 0.0447943099 0.0065968117 0.0017050000 14535037 955859216 1373700096 -0.4613772333 -0.0149184624 0.0346042477 77 3.0400000000 0.0325446576 0.0273211539 0.0447943099 0.0065946484 0.0016070000 14537013 955859216 1373700096 -0.4612655342 -0.0177209936 0.0284727290 78 3.0800000000 0.0292439666 0.0273458053 0.0447943099 0.0065639759 0.0016510000 14538989 955859216 1373700096 -0.4601743519 -0.0132921916 0.0205591246 79 3.1200000000 0.0370917693 0.0274691719 0.0447943099 0.0065426302 0.0015410000 14540965 955859216 1373700096 -0.4658125341 -0.0177927483 0.0200931523 80 3.1600000000 0.0434547216 0.0276689913 0.0447943099 0.0065229158 0.0015350000 14542941 955859216 1373700096 -0.4683789015 -0.0211033747 0.0177516714 81 3.2000000000 0.0289655346 0.0276849980 0.0447943099 0.0065041695 0.0017380000 14544917 955859216 1373700096 -0.4826492667 -0.0081041465 0.0175690167 82 3.2400000000 0.0303283129 0.0277172336 0.0447943099 0.0065123321 0.0016060000 14546893 955859216 1373700096 -0.4906934798 -0.0093093803 0.0173305571 83 3.2800000000 0.0311586186 0.0277586960 0.0447943099 0.0065519698 0.0016210000 14548869 955859216 1373700096 -0.4981974065 -0.0080305738 0.0143043250 84 3.3200000000 0.0306598451 0.0277932335 0.0447943099 0.0065405971 0.0016210000 14550845 955859216 1373700096 -0.5108920932 -0.0086882683 0.0144766858 85 3.3600000000 0.0290300250 0.0278077840 0.0447943099 0.0065211369 0.0016940000 14552821 955859216 1373700096 -0.5249058604 -0.0061678719 0.0145546878 86 3.4000000000 0.0297959279 0.0278309020 0.0447943099 0.0065631037 0.0016460000 14554797 955859216 1373700096 -0.5395060182 -0.0061868136 0.0186766814 87 3.4400000000 0.0293618236 0.0278484988 0.0447943099 0.0066820008 0.0016450000 14556773 955859216 1373700096 -0.5493931770 -0.0069017755 0.0182783492 88 3.4800000000 0.0293238629 0.0278652643 0.0447943099 0.0068281899 0.0016470000 14558749 955859216 1373700096 -0.5624411106 -0.0065286784 0.0185398068 89 3.5200000000 0.0291540977 0.0278797455 0.0447943099 0.0069588689 0.0016560000 14560725 955859216 1373700096 -0.5718178153 -0.0061626765 0.0186297074 90 3.5600000000 0.0287574567 0.0278894979 0.0447943099 0.0070495134 0.0016630000 14562701 955859216 1373700096 -0.5793994069 -0.0075736656 0.0173391812 91 3.6000000000 0.0286593363 0.0278979576 0.0447943099 0.0070885190 0.0016570000 14564677 955859216 1373700096 -0.5939180851 -0.0087321196 0.0203053467 92 3.6400000000 0.0288939700 0.0279087839 0.0447943099 0.0070968223 0.0016630000 14566653 955859216 1373700096 -0.6090276241 -0.0068299025 0.0254752114 93 3.6800000000 0.0288085211 0.0279184585 0.0447943099 0.0070753057 0.0016700000 14568629 955859216 1373700096 -0.6138167381 -0.0076772119 0.0220598057 94 3.7200000000 0.0306564271 0.0279475858 0.0447943099 0.0070491786 0.0016030000 14570605 955859216 1373700096 -0.6200946569 -0.0117188785 0.0218612459 95 3.7600000000 0.0290213041 0.0279588881 0.0447943099 0.0070269558 0.0016870000 14572581 955859216 1373700096 -0.6339704990 -0.0089089023 0.0281606372 96 3.8000000000 0.0289370194 0.0279690770 0.0447943099 0.0069977837 0.0017140000 14574557 955859216 1373700096 -0.6441228986 -0.0093749342 0.0276899654 97 3.8400000000 0.0300434809 0.0279904626 0.0447943099 0.0069623794 0.0016300000 14576533 955859216 1373700096 -0.6491622329 -0.0131208859 0.0297252741 98 3.8800000000 0.0289232954 0.0279999813 0.0447943099 0.0069336616 0.0016940000 14578509 955859216 1373700096 -0.6642042398 -0.0126983738 0.0336534642 99 3.9200000000 0.0318200439 0.0280385678 0.0447943099 0.0069083282 0.0016450000 14580485 955859216 1373700096 -0.6685948372 -0.0140081402 0.0370323062 100 3.9600000000 0.0330082141 0.0280882642 0.0447943099 0.0068738991 0.0016500000 14582461 955859216 1373700096 -0.6763651371 -0.0155826835 0.0411850251 101 4.0000000000 0.0329398848 0.0281363001 0.0447943099 0.0068409219 0.0016610000 14584437 955859216 1373700096 -0.6850008965 -0.0172143858 0.0471855961 102 4.0400000000 0.0336411595 0.0281902693 0.0447943099 0.0068166081 0.0016570000 14586413 955859216 1373700096 -0.6883185506 -0.0193208940 0.0489131473 103 4.0800000000 0.0302274339 0.0282100476 0.0447943099 0.0067861311 0.0017250000 14588389 955859216 1373700096 -0.7005733252 -0.0166068207 0.0552215688 104 4.1200000000 0.0292141587 0.0282197025 0.0447943099 0.0067573783 0.0017340000 14590365 955859216 1373700096 -0.7136418223 -0.0174010675 0.0679324940 105 4.1600000000 0.0312640183 0.0282486960 0.0447943099 0.0067600953 0.0016790000 14592341 955859216 1373700096 -0.7153787017 -0.0195123777 0.0698750168 106 4.2000000000 0.0325105004 0.0282889017 0.0447943099 0.0067687771 0.0016890000 14594317 955859216 1373700096 -0.7212441564 -0.0200424232 0.0749821812 107 4.2400000000 0.0298218597 0.0283032284 0.0447943099 0.0067453365 0.0017500000 14596293 955859216 1373700096 -0.7229423523 -0.0208598375 0.0711651966 108 4.2800000000 0.0293696709 0.0283131028 0.0447943099 0.0067142734 0.0017780000 14598269 955859216 1373700096 -0.7326708436 -0.0213969424 0.0795584470 109 4.3200000000 0.0318742879 0.0283457743 0.0447943099 0.0066974474 0.0017030000 14600245 955859216 1373700096 -0.7332683206 -0.0236722510 0.0808054581 110 4.3600000000 0.0319238529 0.0283783023 0.0447943099 0.0067017725 0.0016940000 14602221 955859216 1373700096 -0.7411213517 -0.0242845677 0.0891619250 111 4.4000000000 0.0317563489 0.0284087351 0.0447943099 0.0067004430 0.0017010000 14604197 955859216 1373700096 -0.7474526167 -0.0254204050 0.0958481729 112 4.4400000000 0.0327160433 0.0284471932 0.0447943099 0.0067022425 0.0017140000 14606173 955859216 1373700096 -0.7548266649 -0.0257380083 0.1037262231 113 4.4800000000 0.0332070477 0.0284893158 0.0447943099 0.0067080043 0.0017240000 14608149 955859216 1373700096 -0.7586809397 -0.0262936447 0.1079517826 114 4.5200000000 0.0300542712 0.0285030435 0.0447943099 0.0067395081 0.0017760000 14610125 955859216 1373700096 -0.7710521221 -0.0235718302 0.1201070175 115 4.5600000000 0.0315504372 0.0285295426 0.0447943099 0.0067634772 0.0017210000 14612101 955859216 1373700096 -0.7710251212 -0.0249494892 0.1220051423 116 4.6000000000 0.0301425382 0.0285434477 0.0447943099 0.0067959340 0.0017950000 14614077 955859216 1373700096 -0.7820337415 -0.0210795924 0.1339288652 117 4.6400000000 0.0327947438 0.0285797836 0.0447943099 0.0068080533 0.0017510000 14616053 955859216 1373700096 -0.7884699702 -0.0206025150 0.1443472356 118 4.6800000000 0.0333543308 0.0286202458 0.0447943099 0.0067799380 0.0017430000 14618029 955859216 1373700096 -0.7933710217 -0.0226220042 0.1485218108 119 4.7200000000 0.0343649313 0.0286685205 0.0447943099 0.0067545623 0.0017490000 14620005 955859216 1373700096 -0.7992887497 -0.0240047518 0.1555575728 120 4.7600000000 0.0357111953 0.0287272095 0.0447943099 0.0067274359 0.0017450000 14621981 955859216 1373700096 -0.8054261208 -0.0239894651 0.1637751907 121 4.8000000000 0.0309178885 0.0287453143 0.0447943099 0.0067147674 0.0018240000 14623957 955859216 1373700096 -0.8171558976 -0.0199406203 0.1815920919 122 4.8400000000 0.0342518389 0.0287904497 0.0447943099 0.0066891757 0.0017480000 14625933 955859216 1373700096 -0.8170607090 -0.0216131136 0.1822906882 123 4.8800000000 0.0368906036 0.0288563046 0.0447943099 0.0066682875 0.0017460000 14627909 955859216 1373700096 -0.8214290142 -0.0199222062 0.1885120869 124 4.9200000000 0.0301741902 0.0288669327 0.0447943099 0.0066433314 0.0019260000 14629885 955859216 1373700096 -0.8339124322 -0.0128913997 0.2046210468 125 4.9600000000 0.0321962759 0.0288935675 0.0447943099 0.0066357271 0.0017860000 14631861 955859216 1373700096 -0.8371036649 -0.0149280839 0.2095123380 126 5.0000000000 0.0338736624 0.0289330920 0.0447943099 0.0066176215 0.0017650000 14633837 955859216 1373700096 -0.8411856294 -0.0153233157 0.2167563885 127 5.0400000000 0.0308356117 0.0289480725 0.0447943099 0.0065929323 0.0018560000 14635813 955859216 1373700096 -0.8520768285 -0.0115288571 0.2338014245 128 5.0800000000 0.0331275016 0.0289807243 0.0447943099 0.0065679124 0.0017780000 14637789 955859216 1373700096 -0.8563026786 -0.0138208615 0.2394528985 129 5.1200000000 0.0339741521 0.0290194330 0.0447943099 0.0065441261 0.0017950000 14652053 955859216 1373700096 -0.8599274158 -0.0142526478 0.2460993230 130 5.1600000000 0.0305177495 0.0290309585 0.0447943099 0.0065333232 0.0018600000 14679629 955859216 1373700096 -0.8701889515 -0.0110786567 0.2643515766 131 5.2000000000 0.0317960531 0.0290520661 0.0447943099 0.0065640621 0.0018020000 14681605 955859216 1373700096 -0.8730851412 -0.0116832219 0.2683060467 132 5.2400000000 0.0302205477 0.0290609183 0.0447943099 0.0065721854 0.0018800000 14683581 955859216 1373700096 -0.8742450476 -0.0105275167 0.2661339343 133 5.2800000000 0.0299370140 0.0290675055 0.0447943099 0.0065707394 0.0018540000 14685557 955859216 1373700096 -0.8845760822 -0.0100308573 0.2851802111 134 5.3200000000 0.0298957136 0.0290736861 0.0447943099 0.0065977152 0.0018380000 14687533 955859216 1373700096 -0.8932936788 -0.0075314776 0.3015007973 135 5.3600000000 0.0294871442 0.0290767488 0.0447943099 0.0066158705 0.0018400000 14689509 955859216 1373700096 -0.8967153430 -0.0067664920 0.3054508269 136 5.4000000000 0.0292143207 0.0290777603 0.0447943099 0.0066495758 0.0018310000 14691485 955859216 1373700096 -0.9037179947 -0.0064303624 0.3175447881 137 5.4400000000 0.0299107805 0.0290838408 0.0447943099 0.0067025960 0.0017500000 14693461 955859216 1373700096 -0.9085681438 -0.0067256754 0.3266086578 138 5.4800000000 0.0288544577 0.0290821786 0.0447943099 0.0067410402 0.0018450000 14695437 955859216 1373700096 -0.9146711230 -0.0065430291 0.3314471245 139 5.5200000000 0.0285212062 0.0290781428 0.0447943099 0.0067819937 0.0017940000 14697413 955859216 1373700096 -0.9208091497 -0.0082576079 0.3367038369 140 5.5600000000 0.0285289399 0.0290742199 0.0447943099 0.0068510171 0.0018120000 14699389 955859216 1373700096 -0.9300550222 -0.0075226603 0.3509246409 141 5.6000000000 0.0285273138 0.0290703411 0.0447943099 0.0068832281 0.0018030000 14701365 955859216 1373700096 -0.9354478717 -0.0062806080 0.3563877046 142 5.6400000000 0.0282977372 0.0290649003 0.0447943099 0.0069162606 0.0018050000 14703341 955859216 1373700096 -0.9446286559 -0.0060038562 0.3710049093 143 5.6800000000 0.0298120975 0.0290701254 0.0447943099 0.0069932081 0.0017250000 14705317 955859216 1373700096 -0.9491626024 -0.0051935734 0.3807330132 144 5.7200000000 0.0284115653 0.0290655521 0.0447943099 0.0070330037 0.0017950000 14707293 955859216 1373700096 -0.9560295939 -0.0021400077 0.3887215257 145 5.7600000000 0.0279463362 0.0290578334 0.0447943099 0.0070315493 0.0018130000 14709269 955859216 1373700096 -0.9617113471 -0.0025833654 0.3954487741 146 5.8000000000 0.0279514790 0.0290502556 0.0447943099 0.0070221437 0.0018020000 14711245 955859216 1373700096 -0.9674838185 -0.0024828343 0.4048368335 147 5.8400000000 0.0278412141 0.0290420308 0.0447943099 0.0070049510 0.0018040000 14713221 955859216 1373700096 -0.9776253700 -0.0031359587 0.4256500900 148 5.8800000000 0.0276119485 0.0290323681 0.0447943099 0.0069835732 0.0018490000 14715197 955859216 1373700096 -0.9790595174 -0.0030589213 0.4289847016 149 5.9200000000 0.0299540050 0.0290385536 0.0447943099 0.0069674293 0.0017740000 14717173 955859216 1373700096 -0.9823917747 -0.0045442265 0.4396912456 150 5.9600000000 0.0304449555 0.0290479296 0.0447943099 0.0069484367 0.0017740000 14719149 955859216 1373700096 -0.9858478904 -0.0052725552 0.4483871460 151 6.0000000000 0.0311190933 0.0290616459 0.0447943099 0.0069292062 0.0017740000 14721125 955859216 1373700096 -0.9888808131 -0.0054888576 0.4580084383 152 6.0400000000 0.0318581574 0.0290800440 0.0447943099 0.0069154453 0.0017770000 14723101 955859216 1373700096 -0.9916459322 -0.0048418855 0.4686272442 153 6.0800000000 0.0308097620 0.0290913494 0.0447943099 0.0069034422 0.0017730000 14725077 955859216 1373700096 -0.9955360293 -0.0048463680 0.4772051871 154 6.1200000000 0.0279182959 0.0290837321 0.0447943099 0.0069172842 0.0018400000 14727053 955859216 1373700096 -1.0010269880 -0.0026524810 0.4897755682 155 6.1600000000 0.0270519610 0.0290706239 0.0447943099 0.0069754023 0.0017720000 14729029 955859216 1373700096 -1.0030219555 -0.0026800910 0.4975181818 156 6.2000000000 0.0271626525 0.0290583933 0.0447943099 0.0070836222 0.0018520000 14731005 955859216 1373700096 -1.0075266361 -0.0016334844 0.5121869445 157 6.2400000000 0.0271615256 0.0290463114 0.0447943099 0.0071709251 0.0017730000 14732981 955859216 1373700096 -1.0096410513 -0.0009594677 0.5228964090 158 6.2800000000 0.0268510524 0.0290324173 0.0447943099 0.0072442341 0.0018440000 14734957 955859216 1373700096 -1.0127190351 -0.0003110963 0.5392320156 159 6.3200000000 0.0267227124 0.0290178909 0.0447943099 0.0072723240 0.0017760000 14736933 955859216 1373700096 -1.0134997368 -0.0008288153 0.5471556187 160 6.3600000000 0.0279840771 0.0290114296 0.0447943099 0.0073115070 0.0017740000 14738909 955859216 1373700096 -1.0138704777 -0.0005792122 0.5619925261 161 6.4000000000 0.0294643473 0.0290142427 0.0447943099 0.0072966461 0.0017630000 14740885 955859216 1373700096 -1.0135483742 -0.0015808312 0.5728251338 162 6.4400000000 0.0296005234 0.0290178617 0.0447943099 0.0072763529 0.0017720000 14742861 955859216 1373700096 -1.0135593414 -0.0034745045 0.5839284062 163 6.4800000000 0.0314664431 0.0290328837 0.0447943099 0.0072593651 0.0017980000 14744837 955859216 1373700096 -1.0138558149 -0.0039821602 0.5966786742 164 6.5200000000 0.0333599262 0.0290592681 0.0447943099 0.0072409758 0.0017780000 14746813 955859216 1373700096 -1.0135084391 -0.0045055524 0.6085210443 165 6.5600000000 0.0264751315 0.0290436067 0.0447943099 0.0072372754 0.0019080000 14748789 955859216 1373700096 -1.0164145231 0.0034661924 0.6266226172 166 6.6000000000 0.0315826014 0.0290589018 0.0447943099 0.0072469730 0.0017690000 14750765 955859216 1373700096 -1.0143903494 -0.0008908884 0.6379964948 167 6.6400000000 0.0347955413 0.0290932530 0.0447943099 0.0072491981 0.0017590000 14752741 955859216 1373700096 -1.0124511719 -0.0021138997 0.6481722593 168 6.6800000000 0.0353658572 0.0291305899 0.0447943099 0.0072483697 0.0017960000 14754717 955859216 1373700096 -1.0114970207 -0.0024618129 0.6601957679 169 6.7200000000 0.0335564353 0.0291567783 0.0447943099 0.0072348550 0.0017710000 14756693 955859216 1373700096 -1.0116801262 -0.0028384943 0.6743090153 170 6.7600000000 0.0265223458 0.0291412817 0.0447943099 0.0072251354 0.0019250000 14758669 955859216 1373700096 -1.0158874989 0.0060967640 0.6922467947 171 6.8000000000 0.0298962258 0.0291456965 0.0447943099 0.0072199999 0.0017870000 14760645 955859216 1373700096 -1.0141664743 0.0055656806 0.7016931176 172 6.8400000000 0.0312908962 0.0291581686 0.0447943099 0.0072013891 0.0017650000 14762621 955859216 1373700096 -1.0129141808 0.0054998002 0.7138378024 173 6.8800000000 0.0326116122 0.0291781307 0.0447943099 0.0071816599 0.0017770000 14764597 955859216 1373700096 -1.0126900673 0.0058073658 0.7273181677 174 6.9200000000 0.0334774107 0.0292028392 0.0447943099 0.0071615651 0.0017820000 14766573 955859216 1373700096 -1.0134774446 0.0067421347 0.7397398949 175 6.9600000000 0.0262651332 0.0291860523 0.0447943099 0.0071438789 0.0019110000 14768549 955859216 1373700096 -1.0152378082 0.0146778049 0.7525625825 176 7.0000000000 0.0268139206 0.0291725743 0.0447943099 0.0071272986 0.0018480000 14770525 955859216 1373700096 -1.0164543390 0.0145136779 0.7671051621 177 7.0400000000 0.0265249871 0.0291576162 0.0447943099 0.0071370918 0.0018550000 14772501 955859216 1373700096 -1.0155175924 0.0124116773 0.7742377520 178 7.0800000000 0.0293710120 0.0291588151 0.0447943099 0.0071213908 0.0017870000 14774477 955859216 1373700096 -1.0136663914 0.0090971170 0.7817053199 179 7.1200000000 0.0271877404 0.0291478035 0.0447943099 0.0071060961 0.0018500000 14776453 955859216 1373700096 -1.0138022900 0.0138593614 0.7948941588 180 7.1600000000 0.0308524538 0.0291572737 0.0447943099 0.0070878890 0.0017710000 14778429 955859216 1373700096 -1.0118548870 0.0126789343 0.8072865009 181 7.2000000000 0.0326143019 0.0291763733 0.0447943099 0.0070718784 0.0017860000 14780405 955859216 1373700096 -1.0094672441 0.0116319703 0.8184033036 182 7.2400000000 0.0334338509 0.0291997661 0.0447943099 0.0070539585 0.0017900000 14782381 955859216 1373700096 -1.0091892481 0.0111408299 0.8315464854 183 7.2800000000 0.0255847853 0.0291800121 0.0447943099 0.0070451452 0.0019350000 14784357 955859216 1373700096 -1.0133332014 0.0193607118 0.8488366604 184 7.3200000000 0.0282000247 0.0291746861 0.0447943099 0.0070265573 0.0017890000 14786333 955859216 1373700096 -1.0105147362 0.0163969938 0.8593485951 185 7.3600000000 0.0300634075 0.0291794900 0.0447943099 0.0070106493 0.0017840000 14788309 955859216 1373700096 -1.0081372261 0.0149445785 0.8736816645 186 7.4000000000 0.0251665432 0.0291579150 0.0447943099 0.0069974554 0.0019240000 14790285 955859216 1373700096 -1.0099103451 0.0194747634 0.8928840756 187 7.4400000000 0.0256976131 0.0291394107 0.0447943099 0.0069906811 0.0018720000 14792261 955859216 1373700096 -1.0066634417 0.0190249383 0.9013062119 188 7.4800000000 0.0299776271 0.0291438693 0.0447943099 0.0070027944 0.0017910000 14794237 955859216 1373700096 -1.0030072927 0.0184103195 0.9159916043 189 7.5200000000 0.0248519797 0.0291211609 0.0447943099 0.0069872800 0.0019280000 14796213 955859216 1373700096 -1.0023608208 0.0261620451 0.9341145754 190 7.5600000000 0.0283430386 0.0291170655 0.0447943099 0.0069745924 0.0017800000 14798189 955859216 1373700096 -0.9989912510 0.0216416866 0.9481774569 191 7.6000000000 0.0244781319 0.0290927779 0.0447943099 0.0069619550 0.0019090000 14800165 955859216 1373700096 -0.9988832474 0.0277123507 0.9650264978 192 7.6400000000 0.0312624946 0.0291040785 0.0447943099 0.0069606644 0.0017960000 14802141 955859216 1373700096 -0.9934388995 0.0271544587 0.9794679284 193 7.6800000000 0.0242698956 0.0290790309 0.0447943099 0.0069676861 0.0019330000 14804117 955859216 1373700096 -0.9952751994 0.0344395414 0.9980999827 194 7.7200000000 0.0246365108 0.0290561313 0.0447943099 0.0069627788 0.0018630000 14806093 955859216 1373700096 -0.9954413772 0.0300132893 1.0141174793 195 7.7600000000 0.0246665943 0.0290336209 0.0447943099 0.0069651203 0.0018680000 14808069 955859216 1373700096 -0.9942292571 0.0297259353 1.0269993544 196 7.8000000000 0.0251562558 0.0290138384 0.0447943099 0.0070008746 0.0018550000 14810045 955859216 1373700096 -0.9922158122 0.0328530632 1.0435743332 197 7.8400000000 0.0250983313 0.0289939627 0.0447943099 0.0070251730 0.0018500000 14812021 955859216 1373700096 -0.9904584885 0.0364140309 1.0555175543 198 7.8800000000 0.0250465162 0.0289740261 0.0447943099 0.0070427747 0.0018190000 14813997 955859216 1373700096 -0.9893080592 0.0401581936 1.0719933510 199 7.9200000000 0.0243898500 0.0289509901 0.0447943099 0.0070351915 0.0018300000 14815973 955859216 1373700096 -0.9874470234 0.0418044664 1.0876920223 200 7.9600000000 0.0237468146 0.0289249692 0.0447943099 0.0070249605 0.0018390000 14817949 955859216 1373700096 -0.9874979258 0.0409208424 1.1016061306 201 8.0000000000 0.0237510912 0.0288992285 0.0447943099 0.0070395736 0.0018490000 14819925 955859216 1373700096 -0.9868276119 0.0413928218 1.1200910807 202 8.0400000000 0.0235082805 0.0288725407 0.0447943099 0.0070557461 0.0018310000 14821901 955859216 1373700096 -0.9840999246 0.0424912609 1.1306469440 203 8.0800000000 0.0238156933 0.0288476301 0.0447943099 0.0070646726 0.0018290000 14823877 955859216 1373700096 -0.9817445278 0.0440019704 1.1475822926 204 8.1200000000 0.0233100615 0.0288204851 0.0447943099 0.0070561370 0.0018250000 14825853 955859216 1373700096 -0.9799903035 0.0439730063 1.1601762772 205 8.1600000000 0.0243036151 0.0287984516 0.0447943099 0.0070479160 0.0017670000 14827829 955859216 1373700096 -0.9767674208 0.0419769064 1.1713646650 206 8.1999999990 0.0265119281 0.0287873520 0.0447943099 0.0070391068 0.0017660000 14829805 955859216 1373700096 -0.9728416800 0.0399500169 1.1841496229 207 8.2400000000 0.0301037300 0.0287937113 0.0447943099 0.0070333142 0.0017640000 14831781 955859216 1373700096 -0.9674569964 0.0394059867 1.1974512339 208 8.2799999990 0.0337109566 0.0288173519 0.0447943099 0.0070192805 0.0017530000 14833757 955859216 1373700096 -0.9623584747 0.0380204134 1.2099536657 209 8.3200000000 0.0375228748 0.0288590051 0.0447943099 0.0070137586 0.0017540000 14835733 955859216 1373700096 -0.9568599463 0.0361793824 1.2227102518 210 8.3599999990 0.0407960080 0.0289158480 0.0447943099 0.0070321688 0.0017800000 14837709 955859216 1373700096 -0.9504308105 0.0337409228 1.2343775034 211 8.4000000000 0.0417137593 0.0289765016 0.0447943099 0.0070485561 0.0017650000 14839685 955859216 1373700096 -0.9451134205 0.0310349017 1.2473428249 212 8.4399999990 0.0436036773 0.0290454977 0.0447943099 0.0070337656 0.0017710000 14841661 955859216 1373700096 -0.9374908805 0.0321232378 1.2594810724 213 8.4800000000 0.0478487685 0.0291337760 0.0478487685 0.0070314259 0.0017480000 14843637 955859216 1373700096 -0.9299706221 0.0318061598 1.2732244730 214 8.5200000000 0.0235155132 0.0291075224 0.0478487685 0.0071654592 0.0019760000 14845613 955859216 1373700096 -0.9291830659 0.0555576719 1.2874933481 215 8.5600000000 0.0281729475 0.0291031756 0.0478487685 0.0071697476 0.0017680000 14847589 955859216 1373700096 -0.9202021360 0.0504735783 1.2983696461 216 8.6000000000 0.0232333783 0.0290760006 0.0478487685 0.0071563657 0.0018960000 14849565 955859216 1373700096 -0.9121855497 0.0596622191 1.3096066713 217 8.6400000000 0.0261213481 0.0290623847 0.0478487685 0.0071747037 0.0018530000 14851541 955859216 1373700096 -0.9025502205 0.0598218367 1.3261212111 218 8.6800000000 0.0261987913 0.0290492489 0.0478487685 0.0072212241 0.0018450000 14853517 955859216 1373700096 -0.8940110803 0.0595005006 1.3357067108 219 8.7200000000 0.0325575955 0.0290652688 0.0478487685 0.0072173786 0.0017740000 14855493 955859216 1373700096 -0.8823983073 0.0560497344 1.3470059633 220 8.7600000000 0.0402502753 0.0291161097 0.0478487685 0.0072160274 0.0017730000 14857469 955859216 1373700096 -0.8699622154 0.0533698909 1.3588243723 221 8.8000000000 0.0449137390 0.0291875922 0.0478487685 0.0072448595 0.0017940000 14859445 955859216 1373700096 -0.8591095209 0.0499227643 1.3705636263 222 8.8400000000 0.0473915972 0.0292695922 0.0478487685 0.0072483723 0.0017780000 14861421 955859216 1373700096 -0.8492698073 0.0491062105 1.3842805624 223 8.8800000000 0.0500508733 0.0293627818 0.0500508733 0.0072467802 0.0017790000 14863397 955859216 1373700096 -0.8380494118 0.0495945141 1.3950123787 224 8.9200000000 0.0533298180 0.0294697775 0.0533298180 0.0072486989 0.0017810000 14865373 955859216 1373700096 -0.8265391588 0.0493199788 1.4058102369 225 8.9600000000 0.0544459708 0.0295807828 0.0544459708 0.0072442109 0.0017700000 14867349 955859216 1373700096 -0.8158861399 0.0508741587 1.4142744541 226 9.0000000000 0.0542891063 0.0296901117 0.0544459708 0.0072295556 0.0017680000 14869325 955859216 1373700096 -0.8056553602 0.0549204610 1.4249978065 227 9.0400000000 0.0308458079 0.0296952029 0.0544459708 0.0072564807 0.0019570000 14871301 955859216 1373700096 -0.7992795706 0.0836856067 1.4338737726 228 9.0800000000 0.0325672142 0.0297077994 0.0544459708 0.0072640297 0.0018200000 14873277 955859216 1373700096 -0.7874333262 0.0877791345 1.4475545883 229 9.1200000000 0.0307878070 0.0297125156 0.0544459708 0.0073230895 0.0018860000 14875253 955859216 1373700096 -0.7772592902 0.0935553908 1.4551230669 230 9.1600000000 0.0299267080 0.0297134469 0.0544459708 0.0074216883 0.0018910000 14877229 955859216 1373700096 -0.7666236758 0.0985161439 1.4619919062 231 9.2000000000 0.0293287225 0.0297117814 0.0544459708 0.0076277116 0.0018680000 14879205 955859216 1373700096 -0.7574974895 0.1001525745 1.4694594145 232 9.2400000000 0.0287497379 0.0297076346 0.0544459708 0.0077873479 0.0018650000 14881181 955859216 1373700096 -0.7481773496 0.1036837548 1.4778261185 233 9.2800000000 0.0279398207 0.0297000475 0.0544459708 0.0079278036 0.0018380000 14883157 955859216 1373700096 -0.7387688756 0.1073527709 1.4851801395 234 9.3200000000 0.0267632920 0.0296874972 0.0544459708 0.0080302660 0.0018180000 14885133 955859216 1373700096 -0.7290986776 0.1122596562 1.4921233654 235 9.3600000000 0.0253384802 0.0296689908 0.0544459708 0.0081070973 0.0017880000 14887109 955859216 1373700096 -0.7193886042 0.1170316488 1.4993890524 236 9.4000000000 0.0243288912 0.0296463632 0.0544459708 0.0081661186 0.0018020000 14889085 955859216 1373700096 -0.7102267742 0.1207476035 1.5079262257 237 9.4400000000 0.0241011214 0.0296229656 0.0544459708 0.0081933197 0.0018000000 14891061 955859216 1373700096 -0.7003504634 0.1251777560 1.5142424107 238 9.4800000000 0.0239304211 0.0295990473 0.0544459708 0.0082134189 0.0017980000 14893037 955859216 1373700096 -0.6895774007 0.1313257366 1.5219984055 239 9.5200000000 0.0237454716 0.0295745554 0.0544459708 0.0082552992 0.0017830000 14895013 955859216 1373700096 -0.6789227128 0.1367627084 1.5294355154 240 9.5600000000 0.0234868992 0.0295491901 0.0544459708 0.0083074211 0.0017920000 14896989 955859216 1373700096 -0.6688480973 0.1418054253 1.5380994081 241 9.6000000000 0.0235111136 0.0295241359 0.0544459708 0.0083590610 0.0017430000 14898965 955859216 1373700096 -0.6595567465 0.1426644623 1.5467942953 242 9.6400000000 0.0233848095 0.0294987668 0.0544459708 0.0083785540 0.0017470000 14900941 955859216 1373700096 -0.6498289704 0.1454175413 1.5553219318 243 9.6800000000 0.0228405464 0.0294713667 0.0544459708 0.0083921096 0.0018050000 14902917 955859216 1373700096 -0.6390459538 0.1519440711 1.5630460978 244 9.7200000000 0.0226696674 0.0294434909 0.0544459708 0.0084360024 0.0018090000 14904893 955859216 1373700096 -0.6277973652 0.1585426033 1.5711091757 245 9.7600000000 0.0258454327 0.0294288049 0.0544459708 0.0084910050 0.0017020000 14906869 955859216 1373700096 -0.6165928841 0.1580088139 1.5793178082 246 9.8000000000 0.0261973515 0.0294156689 0.0544459708 0.0085081768 0.0016910000 14908845 955859216 1373700096 -0.6061648726 0.1605099887 1.5880364180 247 9.8400000000 0.0252559446 0.0293988279 0.0544459708 0.0085127053 0.0016940000 14910821 955859216 1373700096 -0.5969780087 0.1616284102 1.5975461006 248 9.8800000000 0.0248895809 0.0293806455 0.0544459708 0.0084973228 0.0016930000 14912797 955859216 1373700096 -0.5877645016 0.1637301296 1.6058909893 249 9.9200000000 0.0242514107 0.0293600462 0.0544459708 0.0084812127 0.0016970000 14914773 955859216 1373700096 -0.5779495239 0.1666316688 1.6131800413 250 9.9600000000 0.0227163620 0.0293334714 0.0544459708 0.0084648488 0.0017420000 14916749 955859216 1373700096 -0.5687360168 0.1703511328 1.6228201389 251 10.0000000000 0.0225565713 0.0293064718 0.0544459708 0.0084483305 0.0017250000 14918725 955859216 1373700096 -0.5587157011 0.1735652834 1.6314603090 252 10.0400000000 0.0223775506 0.0292789761 0.0544459708 0.0084342760 0.0017190000 14920701 955859216 1373700096 -0.5502271056 0.1728299707 1.6417968273 253 10.0800000000 0.0221089739 0.0292506362 0.0544459708 0.0084185144 0.0017130000 14922677 955859216 1373700096 -0.5427138209 0.1699742228 1.6515942812 254 10.1200000000 0.0231782105 0.0292267290 0.0544459708 0.0084374863 0.0016640000 14924653 955859216 1373700096 -0.5327040553 0.1726726592 1.6595960855 255 10.1600000000 0.0233594291 0.0292037200 0.0544459708 0.0084529307 0.0016460000 14926629 955859216 1373700096 -0.5217989087 0.1794003695 1.6687388420 256 10.2000000000 0.0228434131 0.0291788750 0.0544459708 0.0084399795 0.0016650000 14928605 955859216 1373700096 -0.5107569098 0.1848072261 1.6775752306 257 10.2400000000 0.0225163717 0.0291529509 0.0544459708 0.0084253559 0.0016730000 14955157 955859216 1373700096 -0.5014815927 0.1848290563 1.6861424446 258 10.2800000000 0.0239014011 0.0291325960 0.0544459708 0.0084091300 0.0016570000 15008333 955859216 1373700096 -0.4907990396 0.1885953248 1.6949946880 259 10.3200000000 0.0246022083 0.0291151042 0.0544459708 0.0084015902 0.0016880000 15010309 955859216 1373700096 -0.4801716208 0.1917687058 1.7013305426 260 10.3600000000 0.0214434620 0.0290855979 0.0544459708 0.0084095763 0.0018050000 15012285 955859216 1373700096 -0.4710583389 0.1964602470 1.7099614143 261 10.4000000000 0.0233056117 0.0290634523 0.0544459708 0.0084073645 0.0016880000 15014261 955859216 1373700096 -0.4609833658 0.1941528320 1.7163088322 262 10.4400000000 0.0237165149 0.0290430442 0.0544459708 0.0083942044 0.0016730000 15016237 955859216 1373700096 -0.4513724148 0.1940179914 1.7234874964 263 10.4800000000 0.0235140547 0.0290220214 0.0544459708 0.0083800544 0.0016600000 15018213 955859216 1373700096 -0.4405881166 0.1957293153 1.7297180891 264 10.5200000000 0.0232638400 0.0290002101 0.0544459708 0.0083691387 0.0016540000 15020189 955859216 1373700096 -0.4303219020 0.1956476271 1.7358025312 265 10.5600000000 0.0227793530 0.0289767352 0.0544459708 0.0083535536 0.0016700000 15022165 955859216 1373700096 -0.4191865623 0.1980280131 1.7425439358 266 10.6000000000 0.0212874785 0.0289478282 0.0544459708 0.0083431305 0.0017210000 15024141 955859216 1373700096 -0.4076481462 0.2017843276 1.7466081381 267 10.6400000000 0.0211138353 0.0289184874 0.0544459708 0.0083391586 0.0017250000 15026117 955859216 1373700096 -0.3964501619 0.2010333389 1.7506977320 268 10.6800000000 0.0220458601 0.0288928433 0.0544459708 0.0083312961 0.0016650000 15028093 955859216 1373700096 -0.3847799599 0.1996587217 1.7573555708 269 10.7200000000 0.0219024867 0.0288668568 0.0544459708 0.0083196406 0.0016660000 15030069 955859216 1373700096 -0.3728708923 0.1997531950 1.7601546049 270 10.7600000000 0.0207273848 0.0288367106 0.0544459708 0.0083113356 0.0018000000 15032045 955859216 1373700096 -0.3479435444 0.2055123895 1.7698302269 271 10.8000000000 0.0206556581 0.0288065222 0.0544459708 0.0083272558 0.0018070000 15034021 955859216 1373700096 -0.3336335421 0.2093273252 1.7731609344 272 10.8400000000 0.0205342788 0.0287761096 0.0544459708 0.0083875638 0.0017460000 15035997 955859216 1373700096 -0.3216879964 0.2076115608 1.7769807577 273 10.8800000000 0.0204660129 0.0287456697 0.0544459708 0.0083953293 0.0017030000 15037973 955859216 1373700096 -0.3090978265 0.2084091008 1.7815279961 274 10.9200000000 0.0203858018 0.0287151592 0.0544459708 0.0084032624 0.0017180000 15039949 955859216 1373700096 -0.2958464026 0.2097049206 1.7852518559 275 10.9600000000 0.0203285329 0.0286846624 0.0544459708 0.0084081555 0.0017450000 15041925 955859216 1373700096 -0.2829527855 0.2097645402 1.7880814075 276 11.0000000000 0.0202087071 0.0286539524 0.0544459708 0.0084049358 0.0017230000 15043901 955859216 1373700096 -0.2695199251 0.2117584944 1.7919532061 277 11.0400000000 0.0200339146 0.0286228331 0.0544459708 0.0084103577 0.0017860000 15045877 955859216 1373700096 -0.2560199201 0.2133885920 1.7952543497 278 11.0800000000 0.0199409723 0.0285916034 0.0544459708 0.0084154026 0.0017340000 15047853 955859216 1373700096 -0.2424468696 0.2152628601 1.7988958359 279 11.1200000000 0.0198340826 0.0285602144 0.0544459708 0.0084246422 0.0018310000 15049829 955859216 1373700096 -0.2285344601 0.2171317190 1.8027055264 280 11.1600000000 0.0197307412 0.0285286806 0.0544459708 0.0084324604 0.0018230000 15051805 955859216 1373700096 -0.2145535499 0.2197438926 1.8059496880 281 11.2000000000 0.0196796153 0.0284971893 0.0544459708 0.0084380758 0.0017660000 15053781 955859216 1373700096 -0.2013987452 0.2206690460 1.8088226318 282 11.2400000000 0.0196248330 0.0284657270 0.0544459708 0.0084330312 0.0017850000 15055757 955859216 1373700096 -0.1895550936 0.2197540998 1.8134011030 283 11.2800000000 0.0204305314 0.0284373341 0.0544459708 0.0084182607 0.0017260000 15057733 955859216 1373700096 -0.1768596023 0.2204686105 1.8166379929 284 11.3200000000 0.0195264891 0.0284059579 0.0544459708 0.0084072862 0.0017900000 15059709 955859216 1373700096 -0.1646739691 0.2233435214 1.8214708567 285 11.3600000000 0.0192487258 0.0283738272 0.0544459708 0.0084044292 0.0018020000 15061685 955859216 1373700096 -0.1531703174 0.2247025818 1.8256958723 286 11.4000000000 0.0190295503 0.0283411549 0.0544459708 0.0083958308 0.0018030000 15063661 955859216 1373700096 -0.1426928639 0.2249305695 1.8297227621 287 11.4400000000 0.0189104993 0.0283082955 0.0544459708 0.0083812853 0.0018070000 15065637 955859216 1373700096 -0.1332098246 0.2246642262 1.8338521719 288 11.4800000000 0.0187969897 0.0282752701 0.0544459708 0.0083674529 0.0017990000 15067613 955859216 1373700096 -0.1243603751 0.2247020900 1.8378880024 289 11.5200000000 0.0186913647 0.0282421078 0.0544459708 0.0083540709 0.0018090000 15069589 955859216 1373700096 -0.1158682629 0.2246775627 1.8443616629 290 11.5600000000 0.0186010264 0.0282088627 0.0544459708 0.0083449573 0.0018140000 15071565 955859216 1373700096 -0.1075721458 0.2252072245 1.8501963615 291 11.6000000000 0.0184537675 0.0281753401 0.0544459708 0.0083336739 0.0017910000 15073541 955859216 1373700096 -0.1000762060 0.2244278491 1.8572325706 292 11.6400000000 0.0183090381 0.0281415514 0.0544459708 0.0083210017 0.0018030000 15075517 955859216 1373700096 -0.0920736268 0.2256025672 1.8630511761 293 11.6800000000 0.0182330981 0.0281077341 0.0544459708 0.0083068002 0.0018070000 15077493 955859216 1373700096 -0.0851253420 0.2259337157 1.8698364496 294 11.7200000000 0.0181741510 0.0280739464 0.0544459708 0.0082939302 0.0018360000 15079469 955859216 1373700096 -0.0790331140 0.2252423316 1.8770130873 295 11.7600000000 0.0184844173 0.0280414395 0.0544459708 0.0082852330 0.0017520000 15081445 955859216 1373700096 -0.0733525455 0.2248734534 1.8837052584 296 11.8000000000 0.0190571472 0.0280110872 0.0544459708 0.0082760690 0.0017560000 15083421 955859216 1373700096 -0.0674567297 0.2244318426 1.8897938728 297 11.8400000000 0.0194542650 0.0279822764 0.0544459708 0.0082672559 0.0017810000 15085397 955859216 1373700096 -0.0625737384 0.2235158235 1.8968061209 298 11.8800000000 0.0200314149 0.0279555956 0.0544459708 0.0082618871 0.0017940000 15087373 955859216 1373700096 -0.0576745830 0.2222479880 1.9040633440 299 11.9200000000 0.0178175904 0.0279216892 0.0544459708 0.0082520093 0.0019190000 15089349 955859216 1373700096 -0.0528506078 0.2246901691 1.9140249491 300 11.9600000000 0.0194977615 0.0278936095 0.0544459708 0.0082397047 0.0017950000 15091325 955859216 1373700096 -0.0477396287 0.2236857265 1.9210786819 301 12.0000000000 0.0179294366 0.0278605059 0.0544459708 0.0082262387 0.0018760000 15093301 955859216 1373700096 -0.0432791337 0.2256701142 1.9312660694 302 12.0400000000 0.0176896006 0.0278268274 0.0544459708 0.0082149657 0.0018960000 15095277 955859216 1373700096 -0.0393591598 0.2257481962 1.9411921501 303 12.0800000000 0.0175331831 0.0277928550 0.0544459708 0.0082084067 0.0019170000 15097253 955859216 1373700096 -0.0352152437 0.2262357920 1.9511008263 304 12.1200000000 0.0173239540 0.0277584178 0.0544459708 0.0082061911 0.0019130000 15099229 955859216 1373700096 -0.0313764885 0.2266836911 1.9613296986 305 12.1600000000 0.0171074551 0.0277234966 0.0544459708 0.0082024652 0.0019300000 15101205 955859216 1373700096 -0.0277646873 0.2268386632 1.9726812840 306 12.2000000000 0.0168866236 0.0276880820 0.0544459708 0.0081950476 0.0019260000 15103181 955859216 1373700096 -0.0242237467 0.2270395458 1.9842163324 307 12.2400000000 0.0167338718 0.0276524005 0.0544459708 0.0081960595 0.0019220000 15105157 955859216 1373700096 -0.0210228898 0.2279027253 1.9957109690 308 12.2800000000 0.0166269671 0.0276166037 0.0544459708 0.0081989422 0.0019310000 15107133 955859216 1373700096 -0.0184440315 0.2281375825 2.0073232651 309 12.3200000000 0.0162683576 0.0275798780 0.0544459708 0.0082093457 0.0020100000 15109109 955859216 1373700096 -0.0165971611 0.2281697094 2.0184061527 310 12.3600000000 0.0160862114 0.0275428016 0.0544459708 0.0082270257 0.0020110000 15111085 955859216 1373700096 -0.0149957165 0.2278295755 2.0303194523 311 12.4000000000 0.0159221645 0.0275054362 0.0544459708 0.0082397675 0.0020240000 15113061 955859216 1373700096 -0.0128445039 0.2288184017 2.0410776138 312 12.4400000000 0.0155611280 0.0274671532 0.0544459708 0.0082743024 0.0020220000 15115037 955859216 1373700096 -0.0106297852 0.2289418727 2.0650272369 313 12.4800000000 0.0153259858 0.0274283635 0.0544459708 0.0082674608 0.0019790000 15117013 955859216 1373700096 -0.0100956652 0.2289835364 2.0756638050 314 12.5200000000 0.0151081989 0.0273891273 0.0544459708 0.0082589944 0.0019730000 15118989 955859216 1373700096 -0.0101014525 0.2280892432 2.0882582664 315 12.5600000000 0.0147521636 0.0273490100 0.0544459708 0.0082577694 0.0019700000 15120965 955859216 1373700096 -0.0097441198 0.2287161946 2.0997407436 316 12.6000000000 0.0144372834 0.0273081501 0.0544459708 0.0082467935 0.0019740000 15122941 955859216 1373700096 -0.0096326498 0.2293458134 2.1120297909 317 12.6400000000 0.0139890751 0.0272661341 0.0544459708 0.0082338102 0.0019890000 15124917 955859216 1373700096 -0.0100118909 0.2292078137 2.1237380505 318 12.6800000000 0.0138972653 0.0272240936 0.0544459708 0.0082208256 0.0020870000 15126893 955859216 1373700096 -0.0106779495 0.2288288325 2.1350042820 319 12.7200000000 0.0136011345 0.0271813884 0.0544459708 0.0082079186 0.0020860000 15128869 955859216 1373700096 -0.0114617245 0.2293395251 2.1450672150 320 12.7600000000 0.0133189084 0.0271380682 0.0544459708 0.0081950822 0.0021030000 15130845 955859216 1373700096 -0.0127081042 0.2298495024 2.1553373337 321 12.8000000000 0.0130417673 0.0270941545 0.0544459708 0.0081851791 0.0021010000 15132821 955859216 1373700096 -0.0148886191 0.2290728241 2.1659057140 322 12.8400000000 0.0127522219 0.0270496143 0.0544459708 0.0081750188 0.0021220000 15134797 955859216 1373700096 -0.0165593084 0.2297739685 2.1751685143 323 12.8800000000 0.0124567635 0.0270044352 0.0544459708 0.0081666168 0.0021310000 15136773 955859216 1373700096 -0.0185579285 0.2290429473 2.1837782860 324 12.9200000000 0.0121665960 0.0269586394 0.0544459708 0.0081553558 0.0021360000 15138749 955859216 1373700096 -0.0205843765 0.2287927270 2.1928832531 325 12.9600000000 0.0118971122 0.0269122962 0.0544459708 0.0081430844 0.0021410000 15140725 955859216 1373700096 -0.0220034737 0.2300109565 2.2018103600 326 13.0000000000 0.0116679575 0.0268655344 0.0544459708 0.0081315485 0.0022370000 15142701 955859216 1373700096 -0.0239918996 0.2299989015 2.2089304924 327 13.0400000000 0.0114069479 0.0268182605 0.0544459708 0.0081210530 0.0022430000 15144677 955859216 1373700096 -0.0260249544 0.2307656109 2.2185292244 328 13.0800000000 0.0111917397 0.0267706187 0.0544459708 0.0081094198 0.0022620000 15146653 955859216 1373700096 -0.0266072415 0.2337911576 2.2248003483 329 13.1200000000 0.0109784342 0.0267226181 0.0544459708 0.0080980738 0.0023090000 15148629 955859216 1373700096 -0.0282622818 0.2349350899 2.2338395119 330 13.1600000000 0.0107970852 0.0266743589 0.0544459708 0.0080874837 0.0023020000 15150605 955859216 1373700096 -0.0301996116 0.2355455607 2.2420382500 331 13.2000000000 0.0106701339 0.0266260078 0.0544459708 0.0080758092 0.0023260000 15152581 955859216 1373700096 -0.0319784246 0.2364948094 2.2522778511 332 13.2400000000 0.0106222760 0.0265778038 0.0544459708 0.0080650297 0.0022720000 15154557 955859216 1373700096 -0.0338482708 0.2372698635 2.2612023354 333 13.2800000000 0.0105089927 0.0265295491 0.0544459708 0.0080533628 0.0023050000 15156533 955859216 1373700096 -0.0360087119 0.2378653735 2.2710793018 334 13.3200000000 0.0104327016 0.0264813549 0.0544459708 0.0080424498 0.0023300000 15158509 955859216 1373700096 -0.0383249521 0.2381016016 2.2795758247 335 13.3600000000 0.0103147179 0.0264330963 0.0544459708 0.0080304624 0.0023280000 15160485 955859216 1373700096 -0.0404318981 0.2393340170 2.2884726524 336 13.4000000000 0.0101837926 0.0263847353 0.0544459708 0.0080185386 0.0023450000 15162461 955859216 1373700096 -0.0419505239 0.2414732873 2.2964317799 337 13.4400000000 0.0100552654 0.0263362799 0.0544459708 0.0080180529 0.0023880000 15164437 955859216 1373700096 -0.0436808057 0.2440850437 2.3039872646 338 13.4800000000 0.0099082617 0.0262876763 0.0544459708 0.0080255098 0.0024270000 15166413 955859216 1373700096 -0.0455245823 0.2459385544 2.3103053570 339 13.5200000000 0.0098041696 0.0262390524 0.0544459708 0.0080430932 0.0024750000 15168389 955859216 1373700096 -0.0479616523 0.2461297512 2.3159196377 340 13.5600000000 0.0097285053 0.0261904919 0.0544459708 0.0080399245 0.0024770000 15170365 955859216 1373700096 -0.0503474548 0.2466829568 2.3210291862 341 13.6000000000 0.0096840532 0.0261420859 0.0544459708 0.0080334851 0.0025020000 15172341 955859216 1373700096 -0.0525134057 0.2472596914 2.3258652687 342 13.6400000000 0.0095966198 0.0260937074 0.0544459708 0.0080256763 0.0024380000 15174317 955859216 1373700096 -0.0546492040 0.2477629930 2.3315660954 343 13.6800000000 0.0095331240 0.0260454258 0.0544459708 0.0080141272 0.0024290000 15176293 955859216 1373700096 -0.0566279925 0.2481735796 2.3364365101 344 13.7200000000 0.0094968174 0.0259973194 0.0544459708 0.0080025146 0.0024170000 15178269 955859216 1373700096 -0.0577257164 0.2499147356 2.3419797421 345 13.7600000000 0.0094293989 0.0259492964 0.0544459708 0.0079949422 0.0024400000 15180245 955859216 1373700096 -0.0596523546 0.2499091029 2.3474991322 346 13.8000000000 0.0093779322 0.0259014023 0.0544459708 0.0079897128 0.0023970000 15182221 955859216 1373700096 -0.0613267943 0.2498841137 2.3525667191 347 13.8400000000 0.0093157822 0.0258536051 0.0544459708 0.0079788048 0.0024300000 15184197 955859216 1373700096 -0.0636622161 0.2486428767 2.3571221828 348 13.8800000000 0.0092574973 0.0258059152 0.0544459708 0.0079681289 0.0024220000 15186173 955859216 1373700096 -0.0642488822 0.2509340346 2.3628880978 349 13.9200000000 0.0091624158 0.0257582261 0.0544459708 0.0079659145 0.0023860000 15188149 955859216 1373700096 -0.0659205094 0.2507551908 2.3686630726 350 13.9600000000 0.0090893367 0.0257106007 0.0544459708 0.0079569522 0.0023790000 15190125 955859216 1373700096 -0.0679368600 0.2494646460 2.3774914742 351 14.0000000000 0.0090853311 0.0256632352 0.0544459708 0.0079463827 0.0024100000 15192101 955859216 1373700096 -0.0680180937 0.2501882017 2.3817834854 352 14.0400000000 0.0092891390 0.0256167179 0.0544459708 0.0079375559 0.0023010000 15194077 955859216 1373700096 -0.0686923563 0.2496195585 2.3867089748 353 14.0800000000 0.0092431027 0.0255703337 0.0544459708 0.0079262842 0.0023100000 15196053 955859216 1373700096 -0.0690632164 0.2487106025 2.3909866810 354 14.1200000000 0.0090247197 0.0255235947 0.0544459708 0.0079151537 0.0024030000 15198029 955859216 1373700096 -0.0686958954 0.2494887263 2.3956184387 355 14.1600000000 0.0091995439 0.0254776115 0.0544459708 0.0079042665 0.0022850000 15200005 955859216 1373700096 -0.0693411306 0.2479302436 2.4006226063 356 14.2000000000 0.0089858249 0.0254312862 0.0544459708 0.0078949534 0.0024000000 15201981 955859216 1373700096 -0.0689901635 0.2480168641 2.4050855637 357 14.2400000000 0.0089612305 0.0253851516 0.0544459708 0.0078843195 0.0023770000 15203957 955859216 1373700096 -0.0686661229 0.2485470027 2.4107060432 358 14.2800000000 0.0090726726 0.0253395860 0.0544459708 0.0078741652 0.0022930000 15205933 955859216 1373700096 -0.0690675303 0.2470909357 2.4162981510 359 14.3200000000 0.0089845397 0.0252940288 0.0544459708 0.0078644654 0.0023050000 15207909 955859216 1373700096 -0.0696891695 0.2454358339 2.4217524529 360 14.3600000000 0.0090126228 0.0252488027 0.0544459708 0.0078559266 0.0023190000 15209885 955859216 1373700096 -0.0698718280 0.2441229075 2.4279150963 361 14.4000000000 0.0089970334 0.0252037839 0.0544459708 0.0078514957 0.0023150000 15211861 955859216 1373700096 -0.0700118393 0.2440183610 2.4343941212 362 14.4400000000 0.0089473370 0.0251588766 0.0544459708 0.0078446868 0.0023110000 15213837 955859216 1373700096 -0.0700459629 0.2443080544 2.4409487247 363 14.4800000000 0.0089323753 0.0251141755 0.0544459708 0.0078342034 0.0023060000 15215813 955859216 1373700096 -0.0699477121 0.2452028692 2.4481360912 364 14.5200000000 0.0085389307 0.0250686391 0.0544459708 0.0078245993 0.0022100000 15217789 955859216 1373700096 -0.0702262297 0.2448885888 2.4550013542 365 14.5600000000 0.0086308923 0.0250236042 0.0544459708 0.0078139586 0.0023110000 15219765 955859216 1373700096 -0.0708558410 0.2440851480 2.4623160362 366 14.6000000000 0.0087116007 0.0249790359 0.0544459708 0.0078035595 0.0023040000 15221741 955859216 1373700096 -0.0710366592 0.2448103726 2.4702274799 367 14.6400000000 0.0082071638 0.0249333359 0.0544459708 0.0077933218 0.0022140000 15223717 955859216 1373700096 -0.0708648115 0.2460250407 2.4768128395 368 14.6800000000 0.0082248347 0.0248879324 0.0544459708 0.0077838160 0.0022960000 15225693 955859216 1373700096 -0.0711321756 0.2468524128 2.4848709106 369 14.7200000000 0.0083038872 0.0248429892 0.0544459708 0.0077827729 0.0023830000 15227669 955859216 1373700096 -0.0719897822 0.2465886772 2.4924919605 370 14.7600000000 0.0082546016 0.0247981557 0.0544459708 0.0077803045 0.0023960000 15229645 955859216 1373700096 -0.0722260922 0.2470434159 2.5003931522 371 14.8000000000 0.0082110185 0.0247534465 0.0544459708 0.0077738514 0.0024100000 15231621 955859216 1373700096 -0.0723125339 0.2468235642 2.5076406002 372 14.8400000000 0.0081718825 0.0247088724 0.0544459708 0.0077696316 0.0024080000 15233597 955859216 1373700096 -0.0725451708 0.2463922799 2.5146877766 373 14.8800000000 0.0081389816 0.0246644491 0.0544459708 0.0077693128 0.0024120000 15235573 955859216 1373700096 -0.0727030113 0.2462572008 2.5220365524 374 14.9200000000 0.0081014587 0.0246201630 0.0544459708 0.0077652946 0.0024120000 15237549 955859216 1373700096 -0.0729048401 0.2456267029 2.5293841362 375 14.9600000000 0.0080684191 0.0245760250 0.0544459708 0.0077682265 0.0024160000 15239525 955859216 1373700096 -0.0726747364 0.2452508658 2.5363655090 376 15.0000000000 0.0080313804 0.0245320233 0.0544459708 0.0077677645 0.0024290000 15241501 955859216 1373700096 -0.0717094317 0.2465933561 2.5437698364 377 15.0400000000 0.0079801725 0.0244881192 0.0544459708 0.0077602659 0.0025440000 15243477 955859216 1373700096 -0.0694615021 0.2477779388 2.5569729805 378 15.0800000000 0.0079007940 0.0244442374 0.0544459708 0.0077500294 0.0025740000 15245453 955859216 1373700096 -0.0675271302 0.2490277737 2.5634286404 379 15.1200000000 0.0078273527 0.0244003933 0.0544459708 0.0077398168 0.0024520000 15247429 955859216 1373700096 -0.0656424165 0.2495935261 2.5690841675 380 15.1600000000 0.0077776485 0.0243566493 0.0544459708 0.0077307459 0.0024840000 15249405 955859216 1373700096 -0.0628884360 0.2507453561 2.5744359493 381 15.2000000000 0.0077582523 0.0243130839 0.0544459708 0.0077208132 0.0025720000 15251381 955859216 1373700096 -0.0605355650 0.2517778575 2.5795304775 382 15.2400000000 0.0077251378 0.0242696600 0.0544459708 0.0077121632 0.0025660000 15253357 955859216 1373700096 -0.0583132505 0.2522625327 2.5843350887 383 15.2800000000 0.0076793842 0.0242263433 0.0544459708 0.0077028020 0.0025960000 15255333 955859216 1373700096 -0.0556403063 0.2533147931 2.5888476372 384 15.3200000000 0.0076300432 0.0241831238 0.0544459708 0.0076927753 0.0025980000 15257309 955859216 1373700096 -0.0528261662 0.2540357113 2.5926539898 385 15.3600000000 0.0076066717 0.0241400681 0.0544459708 0.0076834815 0.0026200000 15259285 955859216 1373700096 -0.0503160879 0.2536473870 2.5952260494 386 15.4000000000 0.0075637815 0.0240971243 0.0544459708 0.0076799030 0.0026230000 15261261 955859216 1373700096 -0.0472634472 0.2543387711 2.5973589420 387 15.4400000000 0.0075128046 0.0240542708 0.0544459708 0.0076797913 0.0026390000 15263237 955859216 1373700096 -0.0435690619 0.2564966381 2.5994899273 388 15.4800000000 0.0074533666 0.0240114850 0.0544459708 0.0076702222 0.0026190000 15265213 955859216 1373700096 -0.0405404344 0.2577853203 2.6003880501 389 15.5200000000 0.0074112643 0.0239688109 0.0544459708 0.0076608170 0.0026550000 15267189 955859216 1373700096 -0.0379153863 0.2579540610 2.6013698578 390 15.5600000000 0.0073274430 0.0239261407 0.0544459708 0.0076510424 0.0026610000 15269165 955859216 1373700096 -0.0340462513 0.2610650361 2.6025280952 391 15.6000000000 0.0073003834 0.0238836196 0.0544459708 0.0076560804 0.0026330000 15271141 955859216 1373700096 -0.0308614802 0.2614193857 2.6038663387 392 15.6400000000 0.0071945828 0.0238410455 0.0544459708 0.0076469046 0.0026120000 15273117 955859216 1373700096 -0.0280259345 0.2612198889 2.6041991711 393 15.6800000000 0.0069751218 0.0237981297 0.0544459708 0.0076378580 0.0025800000 15275093 955859216 1373700096 -0.0258652866 0.2596911788 2.6045329571 394 15.7200000000 0.0066072489 0.0237544980 0.0544459708 0.0076303150 0.0025820000 15277069 955859216 1373700096 -0.0238955971 0.2577962875 2.6049582958 395 15.7600000000 0.0072144871 0.0237126245 0.0544459708 0.0076340140 0.0030300000 15279045 955859216 1373700096 -0.0206108540 0.2580632567 2.6064107418 396 15.8000000000 0.0082870461 0.0236736711 0.0544459708 0.0076281151 0.0028240000 15281021 955859216 1373700096 -0.0170521103 0.2581791878 2.6081740856 397 15.8400000000 0.0376479849 0.0237088708 0.0544459708 0.0077483797 0.0028200000 15282997 955859216 1373700096 -0.0150316404 0.2577654719 2.6392772198 398 15.8800000000 0.0664660558 0.0238163010 0.0664660558 0.0078499730 0.0028550000 15284973 955859216 1373700096 -0.0126691908 0.2559273541 2.6677052975 399 15.9200000000 0.1071869805 0.0240252500 0.1071869805 0.0080887773 0.0029020000 15286949 955859216 1373700096 -0.0090738991 0.2580890656 2.7070615292 400 15.9600000000 0.1063806564 0.0242311386 0.1071869805 0.0080822698 0.0028910000 15288925 955859216 1373700096 -0.0047647064 0.2589064240 2.7067663670 401 16.0000000000 0.1042403132 0.0244306627 0.1071869805 0.0080779062 0.0027760000 15290901 955859216 1373700096 -0.0001859286 0.2594993114 2.7052814960 402 16.0400000000 0.1032833531 0.0246268136 0.1071869805 0.0080703836 0.0027630000 15292877 955859216 1373700096 0.0053866180 0.2600248456 2.7046148777 403 16.0800000000 0.1026548222 0.0248204315 0.1071869805 0.0080656402 0.0027290000 15294853 955859216 1373700096 0.0100392485 0.2595299184 2.7056269646 404 16.1200000000 0.1021041349 0.0250117278 0.1071869805 0.0080574700 0.0027240000 15296829 955859216 1373700096 0.0149948439 0.2599419355 2.7042131424 405 16.1600000000 0.1016726047 0.0252010139 0.1071869805 0.0080494748 0.0026710000 15298805 955859216 1373700096 0.0204027612 0.2603702247 2.7053387165 406 16.2000000000 0.1014008224 0.0253886982 0.1071869805 0.0080412182 0.0026210000 15300781 955859216 1373700096 0.0262722671 0.2620108426 2.7077047825 407 16.2400000000 0.1010165811 0.0255745161 0.1071869805 0.0080338602 0.0025890000 15302757 955859216 1373700096 0.0313690454 0.2627603412 2.7093327045 408 16.2800000000 0.1007469818 0.0257587623 0.1071869805 0.0080357320 0.0025830000 15304733 955859216 1373700096 0.0366242491 0.2632664442 2.7119386196 409 16.3200000000 0.1005041078 0.0259415138 0.1071869805 0.0080382831 0.0025720000 15306709 955859216 1373700096 0.0432409830 0.2667503953 2.7143208981 410 16.3600000000 0.1003042907 0.0261228864 0.1071869805 0.0080301766 0.0025740000 15308685 955859216 1373700096 0.0493428595 0.2697819769 2.7185266018 411 16.3999999990 0.1001900733 0.0263030986 0.1071869805 0.0080250262 0.0025420000 15310661 955859216 1373700096 0.0527589694 0.2683727443 2.7200863361 412 16.4400000000 0.1000553444 0.0264821089 0.1071869805 0.0080405364 0.0025320000 15312637 955859216 1373700096 0.0578514040 0.2681852877 2.7262067795 413 16.4800000000 0.0998909399 0.0266598542 0.1071869805 0.0080545042 0.0025380000 15314613 955859216 1373700096 0.0640015900 0.2695398033 2.7328314781 414 16.5200000000 0.0997946858 0.0268365084 0.1071869805 0.0080510946 0.0025200000 15316589 955859216 1373700096 0.0687475130 0.2673686445 2.7362895012 415 16.5599999990 0.0997282341 0.0270121511 0.1071869805 0.0080647207 0.0025020000 15318565 955859216 1373700096 0.0718156248 0.2615054548 2.7418029308 416 16.6000000000 0.0994245633 0.0271862194 0.1071869805 0.0081409588 0.0024850000 15320541 955859216 1373700096 0.0780426636 0.2613877952 2.7471861839 417 16.6400000000 0.0990725681 0.0273586087 0.1071869805 0.0081707077 0.0024550000 15322517 955859216 1373700096 0.0842528045 0.2627327442 2.7484371662 418 16.6800000000 0.0987944305 0.0275295078 0.1071869805 0.0081737459 0.0024870000 15324493 955859216 1373700096 0.0864075273 0.2590855360 2.7475667000 419 16.7199999990 0.0984212086 0.0276987004 0.1071869805 0.0082016554 0.0024990000 15326469 955859216 1373700096 0.0940256640 0.2616849840 2.7528405190 420 16.7600000000 0.0975861326 0.0278650991 0.1071869805 0.0081923591 0.0024170000 15328445 955859216 1373700096 0.1013116613 0.2622283697 2.7518882751 421 16.8000000000 0.0972338244 0.0280298704 0.1071869805 0.0082034724 0.0024010000 15330421 955859216 1373700096 0.1052395776 0.2561492622 2.7523970604 422 16.8400000000 0.2316849530 0.0285124654 0.2316849530 0.0089085114 0.0025250000 15332397 955859216 1373700096 0.1120648757 0.4360025227 2.8041658401 423 16.8799999990 0.3356365263 0.0292385270 0.3356365263 0.0091204202 0.0025520000 15334373 955859216 1373700096 0.1197853684 0.5450152755 2.8273413181 424 16.9200000000 0.4531920254 0.0302384173 0.4531920254 0.0093634381 0.0026550000 15336349 955859216 1373700096 0.1259694397 0.6642128229 2.8449127674 425 16.9600000000 0.6201475859 0.0316264389 0.6201475859 0.0099773756 0.0027410000 15338325 955859216 1373700096 0.1401423365 0.8393613696 2.8550512791 426 17.0000000000 0.6676298976 0.0331194048 0.6676298976 0.0099779650 0.0027870000 15340301 955859216 1373700096 0.1416923404 0.8885547519 2.8568520546 427 17.0400000000 0.8027364016 0.0349217865 0.8027364016 0.0102913429 0.0029720000 15342277 955859216 1373700096 0.1525648385 1.0252017975 2.8535380363 428 17.0800000000 0.8115189672 0.0367362659 0.8115189672 0.0102821827 0.0029140000 15344253 955859216 1373700096 0.1570363790 1.0326894522 2.8494544029 429 17.1200000000 0.8073184490 0.0385324947 0.8115189672 0.0102705158 0.0028390000 15346229 955859216 1373700096 0.1695124656 1.0273832083 2.8471207619 430 17.1600000000 0.8034776449 0.0403114369 0.8115189672 0.0102611597 0.0027950000 15348205 955859216 1373700096 0.1800084859 1.0190123320 2.8425519466 431 17.2000000000 0.8010224104 0.0420764276 0.8115189672 0.0102520405 0.0027920000 15350181 955859216 1373700096 0.1916851401 1.0114607811 2.8415153027 432 17.2400000000 0.7963193655 0.0438223603 0.8115189672 0.0102539820 0.0027450000 15352157 955859216 1373700096 0.2067366838 1.0046706200 2.8384821415 433 17.2800000000 0.7923850417 0.0455511425 0.8115189672 0.0102483695 0.0027310000 15354133 955859216 1373700096 0.2196022272 0.9987989068 2.8341360092 434 17.3200000000 0.7903473377 0.0472672628 0.8115189672 0.0102418710 0.0026960000 15356109 955859216 1373700096 0.2305724025 0.9911990762 2.8284127712 435 17.3600000000 0.7875909209 0.0489691562 0.8115189672 0.0102547466 0.0026260000 15358085 955859216 1373700096 0.2435349971 0.9871438146 2.8239293098 436 17.4000000000 0.7846756577 0.0506565565 0.8115189672 0.0102654004 0.0026040000 15360061 955859216 1373700096 0.2589765489 0.9883068204 2.8158028126 437 17.4400000000 0.7808138728 0.0523273970 0.8115189672 0.0102540399 0.0026130000 15362037 955859216 1373700096 0.2742574215 0.9904068708 2.8052597046 438 17.4800000000 0.7788971663 0.0539862321 0.8115189672 0.0102916388 0.0026160000 15364013 955859216 1373700096 0.2842192054 0.9898806810 2.7964041233 439 17.5200000000 0.7753902078 0.0556295213 0.8115189672 0.0103550091 0.0026030000 15365989 955859216 1373700096 0.2900209427 0.9801561236 2.7877690792 440 17.5600000000 0.7737205029 0.0572615463 0.8115189672 0.0103649786 0.0025770000 15367965 955859216 1373700096 0.2957991660 0.9686689973 2.7832641602 441 17.6000000000 0.7715224028 0.0588811854 0.8115189672 0.0103625832 0.0025670000 15369941 955859216 1373700096 0.3036494255 0.9585369229 2.7788131237 442 17.6400000000 0.7670072913 0.0604832807 0.8115189672 0.0104152143 0.0025560000 15371917 955859216 1373700096 0.3179489672 0.9546112418 2.7702093124 443 17.6800000000 0.7609255314 0.0620644144 0.8115189672 0.0104591014 0.0024910000 15373893 955859216 1373700096 0.3396821916 0.9527963996 2.7514741421 444 17.7200000000 0.7556634545 0.0636265744 0.8115189672 0.0104494828 0.0024720000 15375869 955859216 1373700096 0.3490625322 0.9462911487 2.7414200306 445 17.7600000000 0.7533046603 0.0651764128 0.8115189672 0.0104400701 0.0024470000 15377845 955859216 1373700096 0.3585552275 0.9406942129 2.7347426414 446 17.8000000000 0.7486525774 0.0667088706 0.8115189672 0.0104310958 0.0024200000 15379821 955859216 1373700096 0.3665704131 0.9359931350 2.7255580425 447 17.8400000000 0.7461841106 0.0682289494 0.8115189672 0.0104215078 0.0024090000 15381797 955859216 1373700096 0.3731222451 0.9300497174 2.7189729214 448 17.8800000000 0.7443867922 0.0697382303 0.8115189672 0.0104121121 0.0024200000 15383773 955859216 1373700096 0.3808719814 0.9258229136 2.7129480839 449 17.9200000000 0.7418523431 0.0712351437 0.8115189672 0.0104041076 0.0023930000 15385749 955859216 1373700096 0.3879530132 0.9209541678 2.7057363987 450 17.9600000000 0.7402927279 0.0727219384 0.8115189672 0.0103965971 0.0023450000 15387725 955859216 1373700096 0.3949872255 0.9143263698 2.7021634579 451 18.0000000000 0.7379770875 0.0741970052 0.8115189672 0.0103987191 0.0024070000 15389701 955859216 1373700096 0.4044813514 0.9113716483 2.6969208717 452 18.0400000000 0.7349760532 0.0756589058 0.8115189672 0.0103928762 0.0023000000 15391677 955859216 1373700096 0.4150385857 0.9081754088 2.6909031868 453 18.0800000000 0.7333412766 0.0771107432 0.8115189672 0.0103830223 0.0022840000 15393653 955859216 1373700096 0.4234860539 0.9023607969 2.6865284443 454 18.1200000000 0.7311733961 0.0785514099 0.8115189672 0.0103809638 0.0022560000 15395629 955859216 1373700096 0.4337029755 0.8992330432 2.6815783978 455 18.1600000000 0.7282384038 0.0799792934 0.8115189672 0.0103728635 0.0022400000 15397605 955859216 1373700096 0.4434552193 0.8950369358 2.6765153408 456 18.2000000000 0.7269243598 0.0813980325 0.8115189672 0.0103651522 0.0022450000 15399581 955859216 1373700096 0.4551142156 0.8897465467 2.6722693443 457 18.2400000000 0.7252519131 0.0828069032 0.8115189672 0.0103634582 0.0022210000 15401557 955859216 1373700096 0.4647740424 0.8848450780 2.6684365273 458 18.2800000000 0.7242760062 0.0842074907 0.8115189672 0.0103723723 0.0022380000 15403533 955859216 1373700096 0.4769111574 0.8852930069 2.6650228500 459 18.3200000000 0.7208443880 0.0855944992 0.8115189672 0.0103659835 0.0021740000 15405509 955859216 1373700096 0.4882917106 0.8844347000 2.6576991081 460 18.3600000000 0.7194070220 0.0869723525 0.8115189672 0.0103586978 0.0022420000 15407485 955859216 1373700096 0.4968628585 0.8784686923 2.6552145481 461 18.4000000000 0.7188940048 0.0883431153 0.8115189672 0.0103505059 0.0023230000 15409461 955859216 1373700096 0.5106306076 0.8756955266 2.6533269882 462 18.4400000000 0.7166053653 0.0897029903 0.8115189672 0.0103428422 0.0023440000 15411437 955859216 1373700096 0.5221548676 0.8742635250 2.6475138664 463 18.4800000000 0.7146033049 0.0910526671 0.8115189672 0.0103332502 0.0024050000 15413413 955859216 1373700096 0.5309846401 0.8696924448 2.6425075531 464 18.5200000000 0.7166551948 0.0924009484 0.8115189672 0.0103269430 0.0023580000 15415389 955859216 1373700096 0.5389212370 0.8668867946 2.6436383724 465 18.5600000000 0.7169210911 0.0937440024 0.8115189672 0.0103191224 0.0022430000 15417365 955859216 1373700096 0.5493540168 0.8620826006 2.6438598633 466 18.6000000000 0.7193011045 0.0950863996 0.8115189672 0.0103182229 0.0022630000 15419341 955859216 1373700096 0.5642712116 0.8624525070 2.6495370865 467 18.6400000000 0.7466325760 0.0964815735 0.8115189672 0.0103779556 0.0023350000 15421317 955859216 1373700096 0.5660323501 0.8804256320 2.6719565392 468 18.6800000000 0.7442942262 0.0978657885 0.8115189672 0.0103760764 0.0022790000 15423293 955859216 1373700096 0.5792236328 0.8729330897 2.6750686169 469 18.7200000000 0.7430405617 0.0992414277 0.8115189672 0.0103728662 0.0024460000 15425269 955859216 1373700096 0.6026948690 0.8660174608 2.6832144260 470 18.7600000000 0.6863260865 0.1004905440 0.8115189672 0.0105797906 0.0026150000 15427245 955859216 1373700096 0.6203113794 0.7902801633 2.7038252354 471 18.8000000000 0.7026388645 0.1017689906 0.8115189672 0.0106050104 0.0026560000 15429221 955859216 1373700096 0.5856106281 0.7968389988 2.7209744453 472 18.8400000000 0.6964532733 0.1030289149 0.8115189672 0.0106653728 0.0025880000 15431197 955859216 1373700096 0.5974082947 0.7935191989 2.7115459442 473 18.8800000000 0.7599668503 0.1044177900 0.8115189672 0.0110779364 0.0027190000 15433173 955859216 1373700096 0.5852509141 0.8299049735 2.7704863548 474 18.9200000000 0.8965250254 0.1060889023 0.8965250254 0.0126482464 0.0026190000 15435149 955859216 1373700096 0.5993528366 0.9086270928 2.8915846348 475 18.9600000000 1.0949954987 0.1081708109 1.0949954987 0.0193964362 0.0029250000 15437125 955859216 1373700096 0.0850738510 0.8967344165 2.9758260250 476 19.0000000000 1.2193460464 0.1105052127 1.2193460464 0.0200757804 0.0027920000 15439101 955859216 1373700096 -0.0969830379 0.9031029344 2.9943959713 477 19.0400000000 1.2891013622 0.1129760642 1.2891013622 0.0202892679 0.0027160000 15441077 955859216 1373700096 -0.2019867152 0.8911344409 2.9936516285 478 19.0800000000 1.3724313974 0.1156109080 1.3724313974 0.0205516937 0.0027890000 15443053 955859216 1373700096 -0.3260005414 0.8812375665 2.9802646637 479 19.1200000000 1.4497292042 0.1183961236 1.4497292042 0.0207742965 0.0028100000 15445029 955859216 1373700096 -0.4400159121 0.8618353009 2.9655499458 480 19.1600000000 1.4606621265 0.1211925111 1.4606621265 0.0208237647 0.0029850000 15447005 955859216 1373700096 -0.4691534340 0.8431903124 2.9369933605 481 19.2000000000 1.4574927092 0.1239706820 1.4606621265 0.0208439108 0.0029520000 15448981 955859216 1373700096 -0.4655409455 0.8392391205 2.9213790894 482 19.2400000000 1.6078729630 0.1270493174 1.6078729630 0.0216102890 0.0030580000 15450957 955859216 1373700096 -0.6612789631 0.8187991977 2.8906574249 483 19.2800000000 1.6131983995 0.1301262307 1.6131983995 0.0216095663 0.0030610000 15452933 955859216 1373700096 -0.6715777516 0.8063563704 2.8678910732 484 19.3200000000 1.6151971817 0.1331945591 1.6151971817 0.0216006060 0.0032060000 15454909 955859216 1373700096 -0.6732026339 0.8015385270 2.8566606045 485 19.3600000000 1.6449613571 0.1363116040 1.6449613571 0.0215928734 0.0031170000 15456885 955859216 1373700096 -0.7039316893 0.7993539572 2.8423919678 486 19.4000000000 1.8089770079 0.1397533024 1.8089770079 0.0224287156 0.0033220000 15458861 955859216 1373700096 -0.9087355137 0.7727258801 2.7762689590 487 19.4400000000 1.8300919533 0.1432242236 1.8300919533 0.0224290704 0.0031870000 15460837 955859216 1373700096 -0.9376914501 0.7557262182 2.7448332310 488 19.4800000000 1.9268597364 0.1468792144 1.9268597364 0.0227036549 0.0032380000 15462813 955859216 1373700096 -1.0583688021 0.7306408286 2.6958377361 489 19.5200000000 1.9510595798 0.1505687448 1.9510595798 0.0226826551 0.0032710000 15464789 955859216 1373700096 -1.0942879915 0.7108993530 2.6391112804 490 19.5600000000 1.9615771770 0.1542646804 1.9615771770 0.0226642749 0.0032120000 15466765 955859216 1373700096 -1.1125874519 0.6916897893 2.5898597240 491 19.6000000000 1.9999142885 0.1580236409 1.9999142885 0.0226596588 0.0032470000 15468741 955859216 1373700096 -1.1563395262 0.6746852994 2.5465829372 492 19.6400000000 1.9941915274 0.1617556895 1.9999142885 0.0226453580 0.0032950000 15470717 955859216 1373700096 -1.1531057358 0.6676141620 2.5236666203 493 19.6800000000 1.9879833460 0.1654600052 1.9999142885 0.0226291932 0.0032190000 15472693 955859216 1373700096 -1.1495422125 0.6553673148 2.4933147430 494 19.7200000000 2.0112504959 0.1691964232 2.0112504959 0.0226137517 0.0033070000 15474669 955859216 1373700096 -1.1807223558 0.6327877045 2.4395406246 495 19.7600000000 2.0148196220 0.1729249549 2.0148196220 0.0226030587 0.0033460000 15476645 955859216 1373700096 -1.1904721260 0.6137426496 2.3940389156 496 19.8000000000 2.0287761688 0.1766665904 2.0287761688 0.0225884433 0.0031680000 15478621 955859216 1373700096 -1.2096372843 0.6029395461 2.3614728451 497 19.8400000000 2.0460033417 0.1804278314 2.0460033417 0.0225725541 0.0034560000 15480597 955859216 1373700096 -1.2282299995 0.5867144465 2.3196005821 498 19.8800000000 2.0571928024 0.1841964357 2.0571928024 0.0225549000 0.0031960000 15482573 955859216 1373700096 -1.2440605164 0.5741889477 2.2875685692 499 19.9200000000 2.0590233803 0.1879536040 2.0590233803 0.0225538161 0.0032370000 15484549 955859216 1373700096 -1.2475337982 0.5601524115 2.2501266003 500 19.9600000000 2.0662415028 0.1917101797 2.0662415028 0.0225440530 0.0032660000 15486525 955859216 1373700096 -1.2580900192 0.5416849256 2.2122015953 501 20.0000000000 2.0456120968 0.1954105828 2.0662415028 0.0225600860 0.0033140000 15488501 955859216 1373700096 -1.2360646725 0.5402063727 2.2082486153 502 20.0400000000 2.0417776108 0.1990886047 2.0662415028 0.0225531146 0.0032830000 15490477 955859216 1373700096 -1.2292964458 0.5348963141 2.2027428150 503 20.0800000000 2.0295147896 0.2027276230 2.0662415028 0.0225539188 0.0032890000 15492453 955859216 1373700096 -1.2147555351 0.5357871056 2.1972324848 504 20.1200000000 2.0182311535 0.2063298126 2.0662415028 0.0225409570 0.0032750000 15494429 955859216 1373700096 -1.2050526142 0.5287039876 2.1897046566 505 20.1600000000 2.0082995892 0.2098980695 2.0662415028 0.0225364343 0.0032280000 15496405 955859216 1373700096 -1.1996805668 0.5218428373 2.1771979332 506 20.2000000000 2.0043401718 0.2134443978 2.0662415028 0.0225372741 0.0032580000 15498381 955859216 1373700096 -1.1956458092 0.5247256756 2.1686098576 507 20.2400000000 1.9919232130 0.2169522456 2.0662415028 0.0225285316 0.0034160000 15500357 955859216 1373700096 -1.1830923557 0.5247632265 2.1630964279 508 20.2800000000 1.9755976200 0.2204141459 2.0662415028 0.0225209895 0.0033930000 15502333 955859216 1373700096 -1.1748710871 0.5166162848 2.1525120735 509 20.3200000000 1.9671968222 0.2238459390 2.0662415028 0.0225067178 0.0032560000 15504309 955859216 1373700096 -1.1628232002 0.5150483847 2.1500682831 510 20.3600000000 1.9545555115 0.2272394872 2.0662415028 0.0225057795 0.0032030000 15506285 955859216 1373700096 -1.1455613375 0.5151264071 2.1456031799 511 20.4000000000 1.9430406094 0.2305972193 2.0662415028 0.0225000391 0.0032130000 15508261 955859216 1373700096 -1.1314781904 0.5164893866 2.1398975849 512 20.4400000000 1.9288177490 0.2339140563 2.0662415028 0.0224907050 0.0033470000 15510237 955859216 1373700096 -1.1208900213 0.5134096742 2.1296513081 513 20.4800000000 1.9195220470 0.2371998418 2.0662415028 0.0224781958 0.0032530000 15561365 955859216 1373700096 -1.1064922810 0.5104437470 2.1277329922 514 20.5200000000 1.9083770514 0.2404511594 2.0662415028 0.0224710084 0.0032860000 15665741 955859216 1373700096 -1.0937817097 0.5110874772 2.1223211288 515 20.5600000000 1.9002226591 0.2436740166 2.0662415028 0.0224556275 0.0032860000 15667717 955859216 1373700096 -1.0801825523 0.5118998289 2.1193280220 516 20.6000000000 1.8911278248 0.2468667566 2.0662415028 0.0224384173 0.0032100000 15669693 955859216 1373700096 -1.0676277876 0.5107423067 2.1154069901 517 20.6400000000 1.8949652910 0.2500545681 2.0662415028 0.0224220151 0.0032570000 15671669 955859216 1373700096 -1.0758032799 0.5088691711 2.1128377914 518 20.6800000000 1.8945562840 0.2532292818 2.0662415028 0.0224031003 0.0032840000 15673645 955859216 1373700096 -1.0593780279 0.5138375163 2.1145558357 519 20.7200000000 1.9034841061 0.2564089635 2.0662415028 0.0223953263 0.0039120000 15675621 955859216 1373700096 -1.0779857635 0.5159010887 2.1083562374 520 20.7600000000 1.9012644291 0.2595721471 2.0662415028 0.0223781377 0.0033900000 15677597 955859216 1373700096 -1.0833661556 0.5159927011 2.1020829678 521 20.8000000000 1.8959896564 0.2627130636 2.0662415028 0.0223575922 0.0032600000 15679573 955859216 1373700096 -1.0807352066 0.5118555427 2.0972011089 522 20.8400000000 1.8901640177 0.2658307858 2.0662415028 0.0223376334 0.0031490000 15681549 955859216 1373700096 -1.0729259253 0.5067559481 2.0952918530 523 20.8800000000 1.8872395754 0.2689309938 2.0662415028 0.0223317345 0.0031330000 15683525 955859216 1373700096 -1.0813056231 0.5028653741 2.0884795189 524 20.9200000000 1.8932331800 0.2720308071 2.0662415028 0.0223177086 0.0029710000 15685501 955859216 1373700096 -1.0691767931 0.5054360628 2.0932705402 525 20.9600000000 1.8866851330 0.2751063392 2.0662415028 0.0223074250 0.0029750000 15687477 955859216 1373700096 -1.0627766848 0.5047640800 2.0899589062 526 21.0000000000 1.8828843832 0.2781629514 2.0662415028 0.0222915744 0.0029380000 15689453 955859216 1373700096 -1.0502128601 0.5020276904 2.0918624401 527 21.0400000000 1.8744304180 0.2811919219 2.0662415028 0.0222968179 0.0029610000 15691429 955859216 1373700096 -1.0403063297 0.5020380616 2.0873515606 528 21.0800000000 1.8673011065 0.2841959166 2.0662415028 0.0222912945 0.0029200000 15693405 955859216 1373700096 -1.0299156904 0.5021630526 2.0863299370 529 21.1200000000 1.8523482084 0.2871602877 2.0662415028 0.0222948215 0.0028950000 15695381 955859216 1373700096 -0.9998231530 0.5021141768 2.0860249996 530 21.1600000000 1.8447520733 0.2900991401 2.0662415028 0.0222972535 0.0029350000 15697357 955859216 1373700096 -0.9960701466 0.5009158850 2.0798330307 531 21.2000000000 1.8314766884 0.2930019227 2.0662415028 0.0222970265 0.0028700000 15699333 955859216 1373700096 -0.9732889533 0.5003957152 2.0775957108 532 21.2400000000 1.8240246773 0.2958797850 2.0662415028 0.0222912540 0.0029490000 15701309 955859216 1373700096 -0.9646395445 0.4997802377 2.0750317574 533 21.2800000000 1.8184182644 0.2987363300 2.0662415028 0.0222793572 0.0028460000 15703285 955859216 1373700096 -0.9603835344 0.4980829656 2.0718696117 534 21.3200000000 1.8101700544 0.3015667302 2.0662415028 0.0222726148 0.0028680000 15705261 955859216 1373700096 -0.9431608915 0.4967816472 2.0714652538 535 21.3600000000 1.8014520407 0.3043702542 2.0662415028 0.0222660408 0.0028910000 15707237 955859216 1373700096 -0.9278696179 0.4979273379 2.0688543320 536 21.4000000000 1.7968330383 0.3071546997 2.0662415028 0.0222519369 0.0029200000 15709213 955859216 1373700096 -0.9258649945 0.4956014752 2.0654766560 537 21.4400000000 1.7879955769 0.3099123177 2.0662415028 0.0222410717 0.0029520000 15711189 955859216 1373700096 -0.9071979523 0.4943825006 2.0642623901 538 21.4800000000 1.7814068794 0.3126474377 2.0662415028 0.0222302258 0.0028950000 15713165 955859216 1373700096 -0.9001207948 0.4931977093 2.0602729321 539 21.5200000000 1.7744417191 0.3153594864 2.0662415028 0.0222185461 0.0029350000 15715141 955859216 1373700096 -0.8949345350 0.4903901517 2.0558702946 540 21.5600000000 1.7645882368 0.3180432434 2.0662415028 0.0222095336 0.0029120000 15717117 955859216 1373700096 -0.8810353279 0.4903857410 2.0509512424 541 21.6000000000 1.7574460506 0.3207038770 2.0662415028 0.0221948252 0.0029290000 15719093 955859216 1373700096 -0.8723759055 0.4914796352 2.0464954376 542 21.6400000000 1.7486512661 0.3233384663 2.0662415028 0.0221782588 0.0029280000 15721069 955859216 1373700096 -0.8598004580 0.4893867671 2.0422272682 543 21.6800000000 1.7446871996 0.3259560515 2.0662415028 0.0221626697 0.0029420000 15723045 955859216 1373700096 -0.8543141484 0.4857114851 2.0418293476 544 21.7200000000 1.7372705936 0.3285503797 2.0662415028 0.0221522590 0.0027750000 15725021 955859216 1373700096 -0.8455386162 0.4861617982 2.0367379189 545 21.7600000000 1.7296211720 0.3311211518 2.0662415028 0.0221396846 0.0027680000 15726997 955859216 1373700096 -0.8339244723 0.4844499826 2.0334610939 546 21.8000000000 1.7253684998 0.3336747183 2.0662415028 0.0221286505 0.0028130000 15728973 955859216 1373700096 -0.8276681304 0.4850888252 2.0310134888 547 21.8400000000 1.7172900438 0.3362041796 2.0662415028 0.0221171449 0.0027920000 15730949 955859216 1373700096 -0.8163934946 0.4856717587 2.0264520645 548 21.8800000000 1.7124788761 0.3387156298 2.0662415028 0.0221009293 0.0028240000 15732925 955859216 1373700096 -0.8149357438 0.4845488966 2.0220901966 549 21.9200000000 1.7080883980 0.3412099336 2.0662415028 0.0220851888 0.0028400000 15734901 955859216 1373700096 -0.8087096214 0.4835841060 2.0199851990 550 21.9600000000 1.7025038004 0.3436850133 2.0662415028 0.0220720702 0.0027250000 15736877 955859216 1373700096 -0.8033478260 0.4849449098 2.0154907703 551 22.0000000000 1.6966031790 0.3461404002 2.0662415028 0.0220552588 0.0026640000 15738853 955859216 1373700096 -0.7963057756 0.4843569994 2.0119066238 552 22.0400000000 1.6923245192 0.3485791395 2.0662415028 0.0220391656 0.0027380000 15740829 955859216 1373700096 -0.7878772616 0.4854246974 2.0100686550 553 22.0800000000 1.6894567013 0.3510038729 2.0662415028 0.0220228847 0.0027570000 15742805 955859216 1373700096 -0.7864155173 0.4844450057 2.0078232288 554 22.1200000000 1.6844174862 0.3534107567 2.0662415028 0.0220082884 0.0027650000 15744781 955859216 1373700096 -0.7799519300 0.4822447002 2.0054247379 555 22.1600000000 1.6785609722 0.3557984148 2.0662415028 0.0219999119 0.0027810000 15746757 955859216 1373700096 -0.7731047869 0.4838585854 2.0011477470 556 22.2000000000 1.6717230082 0.3581651856 2.0662415028 0.0219847012 0.0027180000 15748733 955859216 1373700096 -0.7657868266 0.4851618707 1.9960649014 557 22.2400000000 1.6681560278 0.3605170543 2.0662415028 0.0219661496 0.0026900000 15750709 955859216 1373700096 -0.7625288963 0.4817884266 1.9944863319 558 22.2800000000 1.6623333693 0.3628500584 2.0662415028 0.0219519843 0.0026350000 15752685 955859216 1373700096 -0.7582427263 0.4777425826 1.9910091162 559 22.3200000000 1.6578774452 0.3651667443 2.0662415028 0.0219472013 0.0027260000 15754661 955859216 1373700096 -0.7542544007 0.4791602492 1.9871671200 560 22.3600000000 1.6545857191 0.3674692781 2.0662415028 0.0219349335 0.0026450000 15756637 955859216 1373700096 -0.7521699071 0.4783757627 1.9845578671 561 22.4000000000 1.6504538059 0.3697562381 2.0662415028 0.0219214847 0.0026780000 15758613 955859216 1373700096 -0.7435469031 0.4773385823 1.9834582806 562 22.4400000000 1.6471953392 0.3720292614 2.0662415028 0.0219101402 0.0025960000 15760589 955859216 1373700096 -0.7417889833 0.4776457250 1.9804455042 563 22.4800000000 1.6415916681 0.3742842568 2.0662415028 0.0218947338 0.0026680000 15762565 955859216 1373700096 -0.7330859900 0.4771034420 1.9775063992 564 22.5200000000 1.6376565695 0.3765242786 2.0662415028 0.0218783131 0.0026310000 15764541 955859216 1373700096 -0.7280128598 0.4744242728 1.9757608175 565 22.5600000000 1.6315191984 0.3787455086 2.0662415028 0.0218675327 0.0026180000 15766517 955859216 1373700096 -0.7165271044 0.4717251956 1.9738092422 566 22.6000000000 1.6270836592 0.3809510530 2.0662415028 0.0218638835 0.0025820000 15768493 955859216 1373700096 -0.7104785442 0.4702228308 1.9714658260 567 22.6400000000 1.6233673096 0.3831422633 2.0662415028 0.0218567392 0.0026130000 15770469 955859216 1373700096 -0.7043481469 0.4694415629 1.9697132111 568 22.6800000000 1.6185040474 0.3853171960 2.0662415028 0.0218459321 0.0026230000 15772445 955859216 1373700096 -0.6955592036 0.4670739174 1.9679833651 569 22.7200000000 1.6121740341 0.3874733592 2.0662415028 0.0218384678 0.0026080000 15774421 955859216 1373700096 -0.6854679585 0.4649346471 1.9650481939 570 22.7600000000 1.6039453745 0.3896075206 2.0662415028 0.0218354474 0.0026700000 15776397 955859216 1373700096 -0.6776943207 0.4655605555 1.9586210251 571 22.8000000000 1.5966939926 0.3917215075 2.0662415028 0.0218205314 0.0026020000 15778373 955859216 1373700096 -0.6710590720 0.4653274715 1.9530079365 572 22.8400000000 1.5905517340 0.3938173645 2.0662415028 0.0218036083 0.0026330000 15780349 955859216 1373700096 -0.6635352373 0.4604092836 1.9501760006 573 22.8800000000 1.5834052563 0.3958934341 2.0662415028 0.0217942573 0.0026120000 15782325 955859216 1373700096 -0.6558359861 0.4585310221 1.9453663826 574 22.9200000000 1.5764617920 0.3979501734 2.0662415028 0.0217809086 0.0026160000 15784301 955859216 1373700096 -0.6513956189 0.4582484961 1.9393635988 575 22.9600000000 1.5687855482 0.3999864088 2.0662415028 0.0217651992 0.0025940000 15786277 955859216 1373700096 -0.6437057257 0.4536845684 1.9347738028 576 23.0000000000 1.5631935596 0.4020058657 2.0662415028 0.0217510177 0.0025100000 15788253 955859216 1373700096 -0.6378917098 0.4488828182 1.9318858385 577 23.0400000000 1.5550441742 0.4040041990 2.0662415028 0.0217452950 0.0026160000 15790229 955859216 1373700096 -0.6304200292 0.4490236342 1.9254430532 578 23.0800000000 1.5475201607 0.4059826003 2.0662415028 0.0217314611 0.0026160000 15792205 955859216 1373700096 -0.6226302981 0.4468032718 1.9203487635 579 23.1200000000 1.5408401489 0.4079426306 2.0662415028 0.0217171964 0.0025060000 15794181 955859216 1373700096 -0.6150667667 0.4430195093 1.9163528681 580 23.1600000000 1.5332101583 0.4098827471 2.0662415028 0.0217045548 0.0025310000 15796157 955859216 1373700096 -0.6065230966 0.4404446185 1.9113826752 581 23.2000000000 1.5254161358 0.4118027701 2.0662415028 0.0216905854 0.0025090000 15798133 955859216 1373700096 -0.5992268324 0.4390721917 1.9055184126 582 23.2400000000 1.5166727304 0.4137011721 2.0662415028 0.0216762869 0.0025070000 15800109 955859216 1373700096 -0.5903031826 0.4351914227 1.8997855186 583 23.2800000000 1.5100367069 0.4155816790 2.0662415028 0.0216620917 0.0025340000 15802085 955859216 1373700096 -0.5821602941 0.4309989512 1.8960657120 584 23.3200000000 1.5003434420 0.4174391478 2.0662415028 0.0216578943 0.0025980000 15804061 955859216 1373700096 -0.5731883645 0.4291940331 1.8888461590 585 23.3600000000 1.4914319515 0.4192750329 2.0662415028 0.0216485788 0.0025990000 15806037 955859216 1373700096 -0.5640158057 0.4267069995 1.8824889660 586 23.4000000000 1.4837815762 0.4210915970 2.0662415028 0.0216386651 0.0025430000 15808013 955859216 1373700096 -0.5547154546 0.4219980240 1.8779526949 587 23.4400000000 1.4759210348 0.4228885807 2.0662415028 0.0216405852 0.0025950000 15809989 955859216 1373700096 -0.5468662381 0.4198359847 1.8722958565 588 23.4800000000 1.4548935890 0.4246436913 2.0662415028 0.0217015883 0.0026140000 15811965 955859216 1373700096 -0.5246888995 0.4175923467 1.8561340570 589 23.5200000000 1.4466050863 0.4263787700 2.0662415028 0.0216934204 0.0026370000 15813941 955859216 1373700096 -0.5171600580 0.4172149599 1.8493105173 590 23.5600000000 1.4368672371 0.4280914623 2.0662415028 0.0216817521 0.0026650000 15815917 955859216 1373700096 -0.5084574819 0.4164828062 1.8413285017 591 23.6000000000 1.4284827709 0.4297841718 2.0662415028 0.0216677329 0.0026830000 15817893 955859216 1373700096 -0.4991769195 0.4124853313 1.8356411457 592 23.6400000000 1.4184632301 0.4314542378 2.0662415028 0.0216567611 0.0026870000 15819869 955859216 1373700096 -0.4876762927 0.4081552327 1.8287477493 593 23.6800000000 1.4087922573 0.4331023626 2.0662415028 0.0216501653 0.0027010000 15821845 955859216 1373700096 -0.4778459966 0.4060392380 1.8212374449 594 23.7200000000 1.3997501135 0.4347297157 2.0662415028 0.0216419776 0.0027120000 15823821 955859216 1373700096 -0.4683053493 0.4039380848 1.8142911196 595 23.7600000000 1.3918473721 0.4363383168 2.0662415028 0.0216319399 0.0026880000 15825797 955859216 1373700096 -0.4617364109 0.4010154009 1.8081144094 596 23.8000000000 1.3818125725 0.4379246830 2.0662415028 0.0216262389 0.0027190000 15827773 955859216 1373700096 -0.4514561892 0.4003022611 1.7998305559 597 23.8400000000 1.3726749420 0.4394904289 2.0662415028 0.0216157598 0.0027820000 15829749 955859216 1373700096 -0.4438679516 0.3996779621 1.7919677496 598 23.8800000000 1.3625472784 0.4410340022 2.0662415028 0.0216047112 0.0027600000 15831725 955859216 1373700096 -0.4329281151 0.3973296881 1.7840090990 599 23.9200000000 1.3533957005 0.4425571436 2.0662415028 0.0215927255 0.0028170000 15833701 955859216 1373700096 -0.4257625639 0.3970564902 1.7759031057 600 23.9600000000 1.3445842266 0.4440605221 2.0662415028 0.0215793254 0.0028590000 15835677 955859216 1373700096 -0.4170735180 0.3952453136 1.7686693668 601 24.0000000000 1.3355991840 0.4455439475 2.0662415028 0.0215662300 0.0028640000 15837653 955859216 1373700096 -0.4096580148 0.3929864168 1.7612338066 602 24.0400000000 1.3261182308 0.4470066954 2.0662415028 0.0215548068 0.0028380000 15839629 955859216 1373700096 -0.3998120725 0.3909799159 1.7534394264 603 24.0800000000 1.3178554773 0.4484508891 2.0662415028 0.0215414941 0.0027440000 15841605 955859216 1373700096 -0.3939355612 0.3889535964 1.7463467121 604 24.1200000000 1.3100149632 0.4498773197 2.0662415028 0.0215275747 0.0027980000 15843581 955859216 1373700096 -0.3885345757 0.3875443041 1.7394491434 605 24.1600000000 1.3024107218 0.4512864658 2.0662415028 0.0215134935 0.0027850000 15845557 955859216 1373700096 -0.3824241459 0.3847582340 1.7331871986 606 24.2000000000 1.2959325314 0.4526802712 2.0662415028 0.0214984697 0.0027290000 15847533 955859216 1373700096 -0.3769102097 0.3807284534 1.7282735109 607 24.2400000000 1.2864800692 0.4540539117 2.0662415028 0.0214872675 0.0027450000 15849509 955859216 1373700096 -0.3670032024 0.3778047562 1.7205740213 608 24.2800000000 1.2785189152 0.4554099397 2.0662415028 0.0214742332 0.0027990000 15851485 955859216 1373700096 -0.3610951900 0.3772338033 1.7133355141 609 24.3200000000 1.2719798088 0.4567507769 2.0662415028 0.0214599169 0.0028630000 15853461 955859216 1373700096 -0.3539498448 0.3729413748 1.7085099220 610 24.3600000000 1.2657270432 0.4580769675 2.0662415028 0.0214457869 0.0028170000 15855437 955859216 1373700096 -0.3476361632 0.3675423265 1.7041386366 611 24.4000000000 1.2566947937 0.4593840343 2.0662415028 0.0214377665 0.0027990000 15857413 955859216 1373700096 -0.3366022706 0.3646985590 1.6966936588 612 24.4400000000 1.2488762140 0.4606740542 2.0662415028 0.0214286164 0.0028870000 15859389 955859216 1373700096 -0.3302078545 0.3632762134 1.6896672249 613 24.4800000000 1.2428910732 0.4619501016 2.0662415028 0.0214142817 0.0028950000 15861365 955859216 1373700096 -0.3247039020 0.3596293330 1.6849920750 614 24.5200000000 1.2341889143 0.4632078195 2.0662415028 0.0214033731 0.0029370000 15863341 955859216 1373700096 -0.3143900335 0.3552124798 1.6779950857 615 24.5600000000 1.2283601761 0.4644519697 2.0662415028 0.0213910364 0.0029050000 15865317 955859216 1373700096 -0.3077301085 0.3524356782 1.6732318401 616 24.6000000000 1.2211554050 0.4656803844 2.0662415028 0.0213790399 0.0028900000 15867293 955859216 1373700096 -0.2988042831 0.3478941321 1.6675969362 617 24.6400000000 1.2136423588 0.4668926404 2.0662415028 0.0213705695 0.0029050000 15869269 955859216 1373700096 -0.2903426886 0.3445319831 1.6612591743 618 24.6800000000 1.2057921886 0.4680882707 2.0662415028 0.0213629722 0.0029860000 15871245 955859216 1373700096 -0.2797024548 0.3408301473 1.6546926498 619 24.7200000000 1.1966571808 0.4692652803 2.0662415028 0.0213583658 0.0029820000 15873221 955859216 1373700096 -0.2671263218 0.3377338648 1.6466568708 620 24.7600000000 1.1892325878 0.4704265179 2.0662415028 0.0213545062 0.0029770000 15875197 955859216 1373700096 -0.2608906925 0.3364503682 1.6396970749 621 24.8000000000 1.1823270321 0.4715728955 2.0662415028 0.0213438894 0.0030510000 15877173 955859216 1373700096 -0.2527709603 0.3339522779 1.6335421801 622 24.8400000000 1.1752339602 0.4727041834 2.0662415028 0.0213329039 0.0030520000 15879149 955859216 1373700096 -0.2443468869 0.3302425444 1.6273444891 623 24.8800000000 1.1676003933 0.4738195866 2.0662415028 0.0213256930 0.0030110000 15881125 955859216 1373700096 -0.2363090217 0.3287689388 1.6200690269 624 24.9200000000 1.1592354774 0.4749180095 2.0662415028 0.0213157922 0.0030940000 15883101 955859216 1373700096 -0.2282786518 0.3270583153 1.6120909452 625 24.9600000000 1.1519570351 0.4760012720 2.0662415028 0.0213038105 0.0030570000 15885077 955859216 1373700096 -0.2210228294 0.3233285844 1.6055642366 626 25.0000000000 1.1458312273 0.4770712879 2.0662415028 0.0212919986 0.0030500000 15887053 955859216 1373700096 -0.2137849778 0.3196568191 1.6000781059 627 25.0400000000 1.1383634806 0.4781259804 2.0662415028 0.0212868235 0.0031140000 15889029 955859216 1373700096 -0.2064613998 0.3172692358 1.5929797888 628 25.0800000000 1.1300339699 0.4791640504 2.0662415028 0.0212827948 0.0030850000 15891005 955859216 1373700096 -0.2001302242 0.3164661527 1.5846788883 629 25.1200000000 1.1247383356 0.4801904006 2.0662415028 0.0212707796 0.0032380000 15892981 955859216 1373700096 -0.1959439367 0.3143853545 1.5796405077 630 25.1600000000 1.1167067289 0.4812007440 2.0662415028 0.0212631950 0.0032180000 15894957 955859216 1373700096 -0.1896655113 0.3118619919 1.5719081163 631 25.2000000000 1.1089367867 0.4821955713 2.0662415028 0.0212554456 0.0032520000 15896933 955859216 1373700096 -0.1843578070 0.3104637861 1.5642304420 632 25.2400000000 1.1029466391 0.4831777724 2.0662415028 0.0212434916 0.0032650000 15898909 955859216 1373700096 -0.1811463535 0.3074163496 1.5587561131 633 25.2800000000 1.0940920115 0.4841428818 2.0662415028 0.0212363022 0.0032330000 15900885 955859216 1373700096 -0.1739663184 0.3056739271 1.5500158072 634 25.3200000000 1.0855376720 0.4850914540 2.0662415028 0.0212263148 0.0031950000 15902861 955859216 1373700096 -0.1698571891 0.3044208288 1.5415259600 635 25.3600000000 1.0794610977 0.4860274692 2.0662415028 0.0212126328 0.0032320000 15904837 955859216 1373700096 -0.1672036499 0.3024802506 1.5356200933 636 25.4000000000 1.0723494291 0.4869493591 2.0662415028 0.0212008774 0.0032060000 15906813 955859216 1373700096 -0.1608850658 0.2987142503 1.5288913250 637 25.4400000000 1.0650736094 0.4878569324 2.0662415028 0.0211898355 0.0031430000 15908789 955859216 1373700096 -0.1570691764 0.2966781855 1.5217622519 638 25.4800000000 1.0588468313 0.4887519009 2.0662415028 0.0211778686 0.0032100000 15910765 955859216 1373700096 -0.1518904418 0.2933356464 1.5156966448 639 25.5200000000 1.0519417524 0.4896332622 2.0662415028 0.0211669250 0.0031210000 15912741 955859216 1373700096 -0.1494096369 0.2891834676 1.5093860626 640 25.5600000000 1.0455353260 0.4905018592 2.0662415028 0.0211552289 0.0029860000 15914717 955859216 1373700096 -0.1460955739 0.2854768336 1.5036658049 641 25.6000000000 1.0384851694 0.4913567473 2.0662415028 0.0211439227 0.0029700000 15916693 955859216 1373700096 -0.1431546509 0.2821553648 1.4968461990 642 25.6400000000 1.0315914154 0.4921982344 2.0662415028 0.0211322990 0.0029590000 15918669 955859216 1373700096 -0.1415269971 0.2787335813 1.4904776812 643 25.6800000000 1.0248420238 0.4930266073 2.0662415028 0.0211206434 0.0029530000 15920645 955859216 1373700096 -0.1381645054 0.2749956250 1.4840341806 644 25.7200000000 1.0176994801 0.4938413167 2.0662415028 0.0211087630 0.0029410000 15922621 955859216 1373700096 -0.1367270201 0.2716232240 1.4773920774 645 25.7600000000 1.0107668638 0.4946427517 2.0662415028 0.0210957979 0.0029830000 15924597 955859216 1373700096 -0.1336574554 0.2668663859 1.4711647034 646 25.8000000000 1.0036464930 0.4954306832 2.0662415028 0.0210842518 0.0029370000 15926573 955859216 1373700096 -0.1336444914 0.2634896636 1.4644824266 647 25.8400000000 0.9944077134 0.4962018996 2.0662415028 0.0210749333 0.0030450000 15928549 955859216 1373700096 -0.1323870867 0.2613113523 1.4554622173 648 25.8800000000 0.9867966175 0.4969589902 2.0662415028 0.0210621322 0.0029180000 15930525 955859216 1373700096 -0.1321958154 0.2578766346 1.4483369589 649 25.9200000000 0.9787579775 0.4977013615 2.0662415028 0.0210494683 0.0029120000 15932501 955859216 1373700096 -0.1316202879 0.2525812089 1.4411398172 650 25.9600000000 0.9631761312 0.4984174766 2.0662415028 0.0210600661 0.0029890000 15934477 955859216 1373700096 -0.1305556893 0.2408101857 1.4275966883 651 26.0000000000 0.9429659843 0.4991003468 2.0662415028 0.0211012596 0.0030090000 15936453 955859216 1373700096 -0.1305701286 0.2342265397 1.4085508585 652 26.0400000000 0.9321001768 0.4997644569 2.0662415028 0.0210976196 0.0029810000 15938429 955859216 1373700096 -0.1306180507 0.2314575315 1.3980278969 653 26.0800000000 0.9201134443 0.5004081767 2.0662415028 0.0210909795 0.0030780000 15940405 955859216 1373700096 -0.1319738775 0.2306867391 1.3864697218 654 26.1200000000 0.9091861844 0.5010332195 2.0662415028 0.0210815147 0.0030560000 15942381 955859216 1373700096 -0.1340708584 0.2267714888 1.3765246868 655 26.1600000000 0.8982906342 0.5016397194 2.0662415028 0.0210731287 0.0029430000 15944357 955859216 1373700096 -0.1335716993 0.2209787965 1.3667038679 656 26.2000000000 0.8866155744 0.5022265728 2.0662415028 0.0210685031 0.0029360000 15946333 955859216 1373700096 -0.1354687959 0.2176843435 1.3557851315 657 26.2400000000 0.8755704761 0.5027948284 2.0662415028 0.0210631442 0.0029390000 15948309 955859216 1373700096 -0.1378770471 0.2143030167 1.3454686403 658 26.2800000000 0.8633361459 0.5033427635 2.0662415028 0.0210601056 0.0029310000 15950285 955859216 1373700096 -0.1397914886 0.2116085589 1.3337900639 659 26.3200000000 0.8505068421 0.5038695679 2.0662415028 0.0210561078 0.0029230000 15952261 955859216 1373700096 -0.1428611577 0.2100884020 1.3217267990 660 26.3600000000 0.8387793899 0.5043770070 2.0662415028 0.0210488558 0.0030320000 15954237 955859216 1373700096 -0.1451292783 0.2073943764 1.3107864857 661 26.4000000000 0.8255792260 0.5048629408 2.0662415028 0.0210425426 0.0030510000 15956213 955859216 1373700096 -0.1478105187 0.2054626644 1.2982761860 662 26.4400000000 0.8135564923 0.5053292452 2.0662415028 0.0210347288 0.0030260000 15958189 955859216 1373700096 -0.1526245326 0.2047483176 1.2868877649 663 26.4800000000 0.8024797440 0.5057774360 2.0662415028 0.0210325256 0.0029980000 15960165 955859216 1373700096 -0.1550373882 0.2006469071 1.2767255306 664 26.5200000000 0.7914556265 0.5062076743 2.0662415028 0.0210291184 0.0028960000 15962141 955859216 1373700096 -0.1552340686 0.1939346790 1.2668087482 665 26.5600000000 0.7805005908 0.5066201448 2.0662415028 0.0210212870 0.0028910000 15964117 955859216 1373700096 -0.1580582708 0.1908531636 1.2566708326 666 26.6000000000 0.7683117986 0.5070130752 2.0662415028 0.0210137285 0.0030010000 15966093 955859216 1373700096 -0.1604761630 0.1890433282 1.2451316118 667 26.6400000000 0.7574653029 0.5073885658 2.0662415028 0.0210039550 0.0030150000 15968069 955859216 1373700096 -0.1646555960 0.1882788241 1.2348498106 668 26.6800000000 0.7452903986 0.5077447063 2.0662415028 0.0209970080 0.0030110000 15970045 955859216 1373700096 -0.1675544679 0.1884115785 1.2229487896 669 26.7200000000 0.7339545488 0.5080828376 2.0662415028 0.0209966317 0.0029920000 15972021 955859216 1373700096 -0.1707071811 0.1860174686 1.2122559547 670 26.7600000000 0.7238560319 0.5084048871 2.0662415028 0.0209938675 0.0030380000 15973997 955859216 1373700096 -0.1728276312 0.1823101193 1.2030752897 671 26.8000000000 0.7136735916 0.5087108017 2.0662415028 0.0209861825 0.0030280000 15975973 955859216 1373700096 -0.1744427383 0.1791751832 1.1934888363 672 26.8400000000 0.7028129697 0.5089996442 2.0662415028 0.0209770731 0.0030010000 15977949 955859216 1373700096 -0.1758371443 0.1781189442 1.1828926802 673 26.8800000000 0.6929924488 0.5092730362 2.0662415028 0.0209680303 0.0030040000 15979925 955859216 1373700096 -0.1771005243 0.1754012555 1.1736602783 674 26.9200000000 0.6833867431 0.5095313652 2.0662415028 0.0209590125 0.0028800000 15981901 955859216 1373700096 -0.1784129739 0.1731973290 1.1644309759 675 26.9600000000 0.6739285588 0.5097749166 2.0662415028 0.0209499870 0.0029830000 15983877 955859216 1373700096 -0.1803699881 0.1720041037 1.1553634405 676 27.0000000000 0.6634782553 0.5100022884 2.0662415028 0.0209418660 0.0029940000 15985853 955859216 1373700096 -0.1820934415 0.1728191078 1.1448487043 677 27.0400000000 0.6543234587 0.5102154659 2.0662415028 0.0209341277 0.0030110000 15987829 955859216 1373700096 -0.1850407273 0.1728526205 1.1358988285 678 27.0800000000 0.6453515887 0.5104147817 2.0662415028 0.0209287692 0.0028710000 15989805 955859216 1373700096 -0.1865330487 0.1716842651 1.1271344423 679 27.1200000000 0.6354642510 0.5105989488 2.0662415028 0.0209240853 0.0028830000 15991781 955859216 1373700096 -0.1877999604 0.1703340113 1.1174582243 680 27.1600000000 0.6262953877 0.5107690906 2.0662415028 0.0209187251 0.0029450000 15993757 955859216 1373700096 -0.1874173284 0.1670802236 1.1088149548 681 27.2000000000 0.6174780726 0.5109257852 2.0662415028 0.0209087377 0.0029520000 15995733 955859216 1373700096 -0.1885796785 0.1653818190 1.1002537012 682 27.2400000000 0.6077551246 0.5110677637 2.0662415028 0.0208997311 0.0029510000 15997709 955859216 1373700096 -0.1892755628 0.1657152325 1.0904206038 683 27.2800000000 0.5983501077 0.5111955563 2.0662415028 0.0208920749 0.0029810000 15999685 955859216 1373700096 -0.1895995587 0.1653158516 1.0809792280 684 27.3200000000 0.5889346004 0.5113092098 2.0662415028 0.0208865051 0.0029720000 16001661 955859216 1373700096 -0.1901465952 0.1633059680 1.0718270540 685 27.3600000000 0.5796207190 0.5114089347 2.0662415028 0.0208796315 0.0029540000 16003637 955859216 1373700096 -0.1893369108 0.1609824002 1.0626802444 686 27.4000000000 0.5690677762 0.5114929855 2.0662415028 0.0208714819 0.0029590000 16005613 955859216 1373700096 -0.1890237629 0.1610094160 1.0519320965 687 27.4400000000 0.5589117408 0.5115620084 2.0662415028 0.0208672852 0.0029590000 16007589 955859216 1373700096 -0.1884248257 0.1610983610 1.0414874554 688 27.4800000000 0.5488736629 0.5116162405 2.0662415028 0.0208701342 0.0029670000 16009565 955859216 1373700096 -0.1879167408 0.1594302505 1.0315326452 689 27.5200000000 0.5388119221 0.5116557117 2.0662415028 0.0208708061 0.0029530000 16011541 955859216 1373700096 -0.1872672588 0.1577479094 1.0215033293 690 27.5600000000 0.5289931893 0.5116808385 2.0662415028 0.0208691085 0.0029570000 16013517 955859216 1373700096 -0.1855829060 0.1558503956 1.0115009546 691 27.6000000000 0.5178865194 0.5116898192 2.0662415028 0.0208660916 0.0029630000 16015493 955859216 1373700096 -0.1848483980 0.1564319730 0.9999251962 692 27.6400000000 0.5068042278 0.5116827591 2.0662415028 0.0208696585 0.0029790000 16017469 955859216 1373700096 -0.1836659014 0.1564202160 0.9885044098 693 27.6800000000 0.4969979525 0.5116615689 2.0662415028 0.0208793437 0.0029720000 16019445 955859216 1373700096 -0.1814301312 0.1535533220 0.9785559773 694 27.7200000000 0.4874312878 0.5116266549 2.0662415028 0.0208805092 0.0029560000 16021421 955859216 1373700096 -0.1781257391 0.1495566964 0.9688717723 695 27.7600000000 0.4784039855 0.5115788525 2.0662415028 0.0208732058 0.0029750000 16023397 955859216 1373700096 -0.1751458347 0.1457090378 0.9598265290 696 27.8000000000 0.4685547948 0.5115170364 2.0662415028 0.0208659151 0.0029770000 16025373 955859216 1373700096 -0.1727847010 0.1446280032 0.9493100047 697 27.8400000000 0.4583284855 0.5114407257 2.0662415028 0.0208593674 0.0029940000 16027349 955859216 1373700096 -0.1708986610 0.1443761438 0.9383459091 698 27.8800000000 0.4472415149 0.5113487497 2.0662415028 0.0208536107 0.0030000000 16029325 955859216 1373700096 -0.1698917747 0.1449750364 0.9265257716 699 27.9200000000 0.4370178282 0.5112424108 2.0662415028 0.0208491885 0.0030040000 16031301 955859216 1373700096 -0.1689300090 0.1454265565 0.9155443907 700 27.9600000000 0.4264301062 0.5111212504 2.0662415028 0.0208496744 0.0030020000 16033277 955859216 1373700096 -0.1675024927 0.1448359340 0.9042472243 701 28.0000000000 0.4167662859 0.5109866498 2.0662415028 0.0208510404 0.0030050000 16035253 955859216 1373700096 -0.1664154530 0.1437260658 0.8939690590 702 28.0400000000 0.4074541032 0.5108391676 2.0662415028 0.0208514397 0.0030370000 16037229 955859216 1373700096 -0.1650787145 0.1416397840 0.8841245174 703 28.0800000000 0.3994630575 0.5106807378 2.0662415028 0.0208450534 0.0030280000 16039205 955859216 1373700096 -0.1646342129 0.1398349255 0.8757417798 704 28.1200000000 0.3892544210 0.5105082573 2.0662415028 0.0208386240 0.0030300000 16041181 955859216 1373700096 -0.1656497270 0.1424351335 0.8645357490 705 28.1600000000 0.3798086643 0.5103228678 2.0662415028 0.0208434584 0.0030650000 16043157 955859216 1373700096 -0.1663897187 0.1432875395 0.8543420434 706 28.2000000000 0.3722086549 0.5101272386 2.0662415028 0.0208489653 0.0030410000 16045133 955859216 1373700096 -0.1665134132 0.1405227333 0.8465540409 707 28.2400000000 0.3635786474 0.5099199563 2.0662415028 0.0208430275 0.0030620000 16047109 955859216 1373700096 -0.1671897471 0.1408905834 0.8372620344 708 28.2800000000 0.3546434343 0.5097006391 2.0662415028 0.0208362759 0.0030650000 16049085 955859216 1373700096 -0.1689134687 0.1421224624 0.8277183175 709 28.3200000000 0.3490841985 0.5094740997 2.0662415028 0.0208288401 0.0029700000 16051061 955859216 1373700096 -0.1694371700 0.1370838732 0.8223009109 710 28.3600000000 0.3421694636 0.5092384594 2.0662415028 0.0208198965 0.0029730000 16053037 955859216 1373700096 -0.1700370014 0.1355538219 0.8149222732 711 28.4000000000 0.3324612677 0.5089898276 2.0662415028 0.0208126487 0.0030850000 16055013 955859216 1373700096 -0.1729164869 0.1404489428 0.8042660356 712 28.4400000000 0.3248070180 0.5087311439 2.0662415028 0.0208067492 0.0030100000 16056989 955859216 1373700096 -0.1749829650 0.1396939009 0.7961969972 713 28.4800000000 0.3206537366 0.5084673607 2.0662415028 0.0207931804 0.0029860000 16058965 955859216 1373700096 -0.1765197217 0.1351159364 0.7926819324 714 28.5200000000 0.3118719459 0.5081920170 2.0662415028 0.0208004341 0.0030900000 16060941 955859216 1373700096 -0.1804408580 0.1395767331 0.7831119895 715 28.5600000000 0.3031088412 0.5079051874 2.0662415028 0.0207906242 0.0030950000 16062917 955859216 1373700096 -0.1847894788 0.1432847232 0.7735949755 716 28.6000000000 0.2979471982 0.5076119500 2.0662415028 0.0207868345 0.0030090000 16064893 955859216 1373700096 -0.1900940239 0.1429255456 0.7687552571 717 28.6400000000 0.2931520343 0.5073128427 2.0662415028 0.0207768158 0.0029840000 16066869 955859216 1373700096 -0.1957469881 0.1428236365 0.7643277645 718 28.6800000000 0.2873752713 0.5070065230 2.0662415028 0.0207660093 0.0029800000 16068845 955859216 1373700096 -0.2021308392 0.1452728957 0.7582985759 719 28.7200000000 0.2813220024 0.5066926363 2.0662415028 0.0207604231 0.0030100000 16070821 955859216 1373700096 -0.2078926861 0.1461880654 0.7519826889 720 28.7600000000 0.2763426900 0.5063727058 2.0662415028 0.0207535419 0.0029800000 16072797 955859216 1373700096 -0.2149256617 0.1466304958 0.7469476461 721 28.8000000000 0.2725262642 0.5060483696 2.0662415028 0.0207426892 0.0029820000 16074773 955859216 1373700096 -0.2223912328 0.1460453719 0.7432750463 722 28.8400000000 0.2679830492 0.5057186392 2.0662415028 0.0207316847 0.0029810000 16076749 955859216 1373700096 -0.2301237285 0.1464251578 0.7382602096 723 28.8800000000 0.2644250095 0.5053848997 2.0662415028 0.0207203690 0.0029970000 16078725 955859216 1373700096 -0.2387055606 0.1459945440 0.7342692018 724 28.9200000000 0.2606026530 0.5050468027 2.0662415028 0.0207099789 0.0029880000 16080701 955859216 1373700096 -0.2475127280 0.1463478655 0.7293978930 725 28.9600000000 0.2570852041 0.5047047867 2.0662415028 0.0206999585 0.0029750000 16082677 955859216 1373700096 -0.2568800747 0.1469035298 0.7243425846 726 29.0000000000 0.2545150220 0.5043601727 2.0662415028 0.0206956841 0.0029700000 16084653 955859216 1373700096 -0.2661710680 0.1465182751 0.7202103734 727 29.0400000000 0.2516202331 0.5040125249 2.0662415028 0.0206917702 0.0029620000 16086629 955859216 1373700096 -0.2759895623 0.1464505792 0.7149825096 728 29.0800000000 0.2498037219 0.5036633370 2.0662415028 0.0206860934 0.0029640000 16088605 955859216 1373700096 -0.2861759961 0.1468312591 0.7102690339 729 29.1200000000 0.2488185018 0.5033137556 2.0662415028 0.0206769243 0.0029610000 16090581 955859216 1373700096 -0.2967509627 0.1475161463 0.7057402730 730 29.1600000000 0.2482947111 0.5029644145 2.0662415028 0.0206668038 0.0029670000 16092557 955859216 1373700096 -0.3070127368 0.1469073296 0.7016257644 731 29.2000000000 0.2474634051 0.5026148919 2.0662415028 0.0206583145 0.0030630000 16094533 955859216 1373700096 -0.3171890080 0.1475980729 0.6960839033 732 29.2400000000 0.2472326308 0.5022660090 2.0662415028 0.0206508732 0.0030680000 16096509 955859216 1373700096 -0.3280803859 0.1493792385 0.6897196174 733 29.2800000000 0.2489843667 0.5019204679 2.0662415028 0.0206435582 0.0030630000 16098485 955859216 1373700096 -0.3400557041 0.1505819559 0.6847574115 734 29.3200000000 0.2525524199 0.5015807294 2.0662415028 0.0206357865 0.0029660000 16100461 955859216 1373700096 -0.3527357578 0.1521781534 0.6808184385 735 29.3600000000 0.2562915981 0.5012470027 2.0662415028 0.0206277232 0.0029770000 16102437 955859216 1373700096 -0.3647174537 0.1538652033 0.6766262650 736 29.4000000000 0.2611374855 0.5009207669 2.0662415028 0.0206200598 0.0029680000 16104413 955859216 1373700096 -0.3769602776 0.1563924998 0.6725912094 737 29.4400000000 0.2662057281 0.5006022933 2.0662415028 0.0206119040 0.0029790000 16106389 955859216 1373700096 -0.3886336684 0.1580960900 0.6689396501 738 29.4800000000 0.2718575895 0.5002923412 2.0662415028 0.0206105288 0.0029830000 16108365 955859216 1373700096 -0.4004973769 0.1599342674 0.6650810838 739 29.5200000000 0.2781902850 0.4999917971 2.0662415028 0.0206215685 0.0029790000 16110341 955859216 1373700096 -0.4121034741 0.1614645571 0.6620054841 740 29.5600000000 0.2847992480 0.4997009964 2.0662415028 0.0206310820 0.0029750000 16112317 955859216 1373700096 -0.4231297374 0.1628604531 0.6595161557 741 29.6000000000 0.2920086682 0.4994207098 2.0662415028 0.0206497098 0.0029560000 16114293 955859216 1373700096 -0.4343236089 0.1658182442 0.6564255953 742 29.6400000000 0.2998673320 0.4991517700 2.0662415028 0.0206688086 0.0029530000 16116269 955859216 1373700096 -0.4453369975 0.1685797125 0.6544799209 743 29.6800000000 0.3069441617 0.4988930787 2.0662415028 0.0206670219 0.0029440000 16118245 955859216 1373700096 -0.4548898637 0.1693349183 0.6540951729 744 29.7200000000 0.3132709563 0.4986435866 2.0662415028 0.0206557519 0.0029420000 16120221 955859216 1373700096 -0.4635309577 0.1705737710 0.6528463960 745 29.7600000000 0.3193077743 0.4984028674 2.0662415028 0.0206440891 0.0029310000 16122197 955859216 1373700096 -0.4718084037 0.1723752022 0.6508807540 746 29.8000000000 0.3252295852 0.4981707316 2.0662415028 0.0206327410 0.0029310000 16124173 955859216 1373700096 -0.4797404110 0.1735161245 0.6494040489 747 29.8400000000 0.3310055435 0.4979469496 2.0662415028 0.0206264249 0.0029170000 16126149 955859216 1373700096 -0.4874918461 0.1755222976 0.6469482183 748 29.8800000000 0.3371175826 0.4977319370 2.0662415028 0.0206282363 0.0029280000 16128125 955859216 1373700096 -0.4952752292 0.1780819446 0.6445762515 749 29.9200000000 0.3429915011 0.4975253410 2.0662415028 0.0206278397 0.0029290000 16130101 955859216 1373700096 -0.5024445057 0.1802817732 0.6429060698 750 29.9600000000 0.3485020995 0.4973266433 2.0662415028 0.0206287617 0.0029050000 16132077 955859216 1373700096 -0.5091391802 0.1823493987 0.6412127018 751 30.0000000000 0.3534196019 0.4971350228 2.0662415028 0.0206294001 0.0029170000 16134053 955859216 1373700096 -0.5151720643 0.1838481575 0.6396889687 752 30.0400000000 0.3582081199 0.4969502796 2.0662415028 0.0206272628 0.0029130000 16136029 955859216 1373700096 -0.5208323598 0.1857276112 0.6380311847 753 30.0800000000 0.3622649014 0.4967714145 2.0662415028 0.0206283232 0.0029300000 16138005 955859216 1373700096 -0.5259738564 0.1869079173 0.6361714602 754 30.1200000000 0.3662570715 0.4965983186 2.0662415028 0.0206340991 0.0034840000 16139981 955859216 1373700096 -0.5309731960 0.1879861504 0.6345157027 755 30.1600000000 0.3699761331 0.4964306071 2.0662415028 0.0206434067 0.0028290000 16141957 955859216 1373700096 -0.5359613299 0.1884724796 0.6324232221 756 30.2000000000 0.3745632172 0.4962694068 2.0662415028 0.0206516906 0.0028090000 16143933 955859216 1373700096 -0.5414457917 0.1895450503 0.6299084425 757 30.2400000000 0.3785556257 0.4961139065 2.0662415028 0.0206506610 0.0028240000 16145909 955859216 1373700096 -0.5467268229 0.1912224740 0.6267000437 758 30.2800000000 0.3826965690 0.4959642794 2.0662415028 0.0206499055 0.0027830000 16147885 955859216 1373700096 -0.5522205830 0.1921990812 0.6237604022 759 30.3200000000 0.3874381781 0.4958212937 2.0662415028 0.0206654954 0.0027860000 16149861 955859216 1373700096 -0.5582629442 0.1935801953 0.6201555133 760 30.3600000000 0.3922968805 0.4956850774 2.0662415028 0.0206840373 0.0027740000 16151837 955859216 1373700096 -0.5644441247 0.1965468228 0.6151345372 761 30.4000000000 0.3965371549 0.4955547910 2.0662415028 0.0206965960 0.0027790000 16153813 955859216 1373700096 -0.5701031685 0.1986470819 0.6101437211 762 30.4400000000 0.4005562067 0.4954301210 2.0662415028 0.0206994292 0.0027740000 16155789 955859216 1373700096 -0.5756425261 0.2005787641 0.6046880484 763 30.4800000000 0.4052820504 0.4953119715 2.0662415028 0.0206999288 0.0028570000 16157765 955859216 1373700096 -0.5811138153 0.2022474706 0.5978008509 764 30.5200000000 0.4098892808 0.4952001617 2.0662415028 0.0206994454 0.0028450000 16159741 955859216 1373700096 -0.5870188475 0.2037705332 0.5913101435 765 30.5600000000 0.4147264659 0.4950949673 2.0662415028 0.0206963796 0.0028380000 16161717 955859216 1373700096 -0.5929794908 0.2054829746 0.5848085880 766 30.6000000000 0.4196768701 0.4949965102 2.0662415028 0.0206936787 0.0028060000 16163693 955859216 1373700096 -0.5990051031 0.2067447454 0.5784758329 767 30.6400000000 0.4246870279 0.4949048421 2.0662415028 0.0206910014 0.0028080000 16165669 955859216 1373700096 -0.6050540805 0.2082070261 0.5712336898 768 30.6800000000 0.4298924506 0.4948201905 2.0662415028 0.0206896848 0.0027870000 16167645 955859216 1373700096 -0.6111482382 0.2093521357 0.5643068552 769 30.7200000000 0.4355099201 0.4947430640 2.0662415028 0.0206882242 0.0027880000 16169621 955859216 1373700096 -0.6173713207 0.2110458165 0.5571753383 770 30.7600000000 0.4412573576 0.4946736021 2.0662415028 0.0206848212 0.0027840000 16171597 955859216 1373700096 -0.6235849261 0.2128615230 0.5499776006 771 30.8000000000 0.4466484785 0.4946113127 2.0662415028 0.0206797565 0.0027770000 16173573 955859216 1373700096 -0.6294395328 0.2141127139 0.5427147746 772 30.8400000000 0.4518150687 0.4945558771 2.0662415028 0.0206744460 0.0027790000 16175549 955859216 1373700096 -0.6351858974 0.2142183483 0.5359673500 773 30.8800000000 0.4574005306 0.4945078107 2.0662415028 0.0206701336 0.0027700000 16177525 955859216 1373700096 -0.6411147714 0.2147327214 0.5289605856 774 30.9200000000 0.4630083740 0.4944671138 2.0662415028 0.0206677127 0.0027710000 16179501 955859216 1373700096 -0.6470186114 0.2147694081 0.5226127505 775 30.9600000000 0.4680768847 0.4944330618 2.0662415028 0.0206648749 0.0027650000 16181477 955859216 1373700096 -0.6525427103 0.2138483822 0.5160405040 776 31.0000000000 0.4734800756 0.4944060606 2.0662415028 0.0206655374 0.0027610000 16183453 955859216 1373700096 -0.6582004428 0.2132908106 0.5091624856 777 31.0400000000 0.4791727066 0.4943864552 2.0662415028 0.0206716076 0.0027600000 16185429 955859216 1373700096 -0.6637024879 0.2138806731 0.5018916726 778 31.0800000000 0.4847811162 0.4943741090 2.0662415028 0.0206715351 0.0027350000 16187405 955859216 1373700096 -0.6689673066 0.2146684825 0.4946184754 779 31.1200000000 0.4902951717 0.4943688729 2.0662415028 0.0206671036 0.0027400000 16189381 955859216 1373700096 -0.6743167639 0.2146344036 0.4882303774 780 31.1600000000 0.4958732426 0.4943708016 2.0662415028 0.0206626026 0.0027350000 16191357 955859216 1373700096 -0.6795271635 0.2148939818 0.4818697572 781 31.2000000000 0.5010325313 0.4943793313 2.0662415028 0.0206569887 0.0027370000 16193333 955859216 1373700096 -0.6843194366 0.2149020582 0.4752812982 782 31.2400000000 0.5059292912 0.4943941011 2.0662415028 0.0206479627 0.0027410000 16195309 955859216 1373700096 -0.6889896393 0.2141324282 0.4695496559 783 31.2800000000 0.5111417770 0.4944154902 2.0662415028 0.0206384527 0.0027490000 16197285 955859216 1373700096 -0.6938438416 0.2137001306 0.4638405442 784 31.3200000000 0.5159053206 0.4944429007 2.0662415028 0.0206300331 0.0027340000 16199261 955859216 1373700096 -0.6983044744 0.2131309062 0.4586606324 785 31.3600000000 0.5202732086 0.4944758056 2.0662415028 0.0206200608 0.0027100000 16201237 955859216 1373700096 -0.7024998069 0.2119470239 0.4538722038 786 31.4000000000 0.5248720646 0.4945144777 2.0662415028 0.0206097170 0.0027030000 16203213 955859216 1373700096 -0.7068003416 0.2110455036 0.4490490258 787 31.4400000000 0.5294874310 0.4945589160 2.0662415028 0.0205993733 0.0027270000 16205189 955859216 1373700096 -0.7107630372 0.2111955881 0.4442445636 788 31.4800000000 0.5337935686 0.4946087061 2.0662415028 0.0205885799 0.0027250000 16207165 955859216 1373700096 -0.7147591710 0.2107535452 0.4405611753 789 31.5200000000 0.5379136205 0.4946635920 2.0662415028 0.0205786441 0.0028350000 16209141 955859216 1373700096 -0.7183092237 0.2089354992 0.4364577532 790 31.5600000000 0.5415654182 0.4947229614 2.0662415028 0.0205673135 0.0027380000 16211117 955859216 1373700096 -0.7221730351 0.2080312073 0.4332830608 791 31.6000000000 0.5452054739 0.4947867825 2.0662415028 0.0205570973 0.0027370000 16213093 955859216 1373700096 -0.7255848646 0.2069699317 0.4298836589 792 31.6400000000 0.5485234261 0.4948546318 2.0662415028 0.0205466251 0.0027340000 16215069 955859216 1373700096 -0.7288370132 0.2055715621 0.4272396266 793 31.6800000000 0.5513854027 0.4949259190 2.0662415028 0.0205350890 0.0027230000 16217045 955859216 1373700096 -0.7317804098 0.2038040459 0.4249825478 794 31.7200000000 0.5539762378 0.4950002897 2.0662415028 0.0205254438 0.0027470000 16219021 955859216 1373700096 -0.7345351577 0.2019007802 0.4232881665 795 31.7600000000 0.5565011501 0.4950776493 2.0662415028 0.0205197192 0.0027490000 16220997 955859216 1373700096 -0.7372266650 0.2000543624 0.4216277599 796 31.8000000000 0.5591977835 0.4951582022 2.0662415028 0.0205178233 0.0027340000 16222973 955859216 1373700096 -0.7401363850 0.1982808262 0.4202413559 797 31.8400000000 0.5615206361 0.4952414675 2.0662415028 0.0205215453 0.0027660000 16224949 955859216 1373700096 -0.7427121401 0.1965421438 0.4194473624 798 31.8800000000 0.5635973811 0.4953271265 2.0662415028 0.0205274167 0.0027660000 16226925 955859216 1373700096 -0.7451381683 0.1943715066 0.4182694256 799 31.9200000000 0.5655882955 0.4954150629 2.0662415028 0.0205302628 0.0027730000 16228901 955859216 1373700096 -0.7475404739 0.1919749975 0.4173900783 800 31.9600000000 0.5674900413 0.4955051566 2.0662415028 0.0205317767 0.0027610000 16230877 955859216 1373700096 -0.7498981953 0.1894978732 0.4168415666 801 32.0000000000 0.5692007542 0.4955971611 2.0662415028 0.0205344107 0.0026960000 16232853 955859216 1373700096 -0.7528870106 0.1872016490 0.4175429344 802 32.0400000000 0.5708992481 0.4956910540 2.0662415028 0.0205303022 0.0026870000 16234829 955859216 1373700096 -0.7553579807 0.1850628704 0.4175787270 803 32.0800000000 0.5734607577 0.4957879029 2.0662415028 0.0205261930 0.0026930000 16236805 955859216 1373700096 -0.7578573823 0.1848200262 0.4179096818 804 32.1199999990 0.5750332475 0.4958864668 2.0662415028 0.0205233960 0.0026770000 16238781 955859216 1373700096 -0.7599976063 0.1844989508 0.4184450209 805 32.1600000000 0.5763600469 0.4959864340 2.0662415028 0.0205215362 0.0026900000 16240757 955859216 1373700096 -0.7622179985 0.1833164245 0.4194722474 806 32.2000000000 0.5787225962 0.4960890843 2.0662415028 0.0205217063 0.0027850000 16242733 955859216 1373700096 -0.7641922832 0.1811732501 0.4189881682 807 32.2400000000 0.5790392160 0.4961918726 2.0662415028 0.0205232765 0.0026970000 16244709 955859216 1373700096 -0.7661451697 0.1785534322 0.4211085141 808 32.2800000000 0.5803980231 0.4962960881 2.0662415028 0.0205210528 0.0026980000 16246685 955859216 1373700096 -0.7687031031 0.1760747135 0.4224999547 809 32.3200000000 0.5814646482 0.4964013645 2.0662415028 0.0205182840 0.0027030000 16248661 955859216 1373700096 -0.7706836462 0.1727477163 0.4243748784 810 32.3600000000 0.5829082727 0.4965081631 2.0662415028 0.0205170834 0.0027370000 16250637 955859216 1373700096 -0.7730337977 0.1699354947 0.4257788956 811 32.4000000000 0.5840985775 0.4966161661 2.0662415028 0.0205105726 0.0027130000 16252613 955859216 1373700096 -0.7752026320 0.1660725027 0.4270106256 812 32.4399999990 0.5855914354 0.4967257415 2.0662415028 0.0205042345 0.0027200000 16254589 955859216 1373700096 -0.7773057818 0.1625754833 0.4281488955 813 32.4800000000 0.5877506137 0.4968377032 2.0662415028 0.0204992253 0.0027420000 16256565 955859216 1373700096 -0.7798892260 0.1601360142 0.4297960103 814 32.5200000000 0.5894768834 0.4969515106 2.0662415028 0.0204938848 0.0027260000 16258541 955859216 1373700096 -0.7825770378 0.1573819220 0.4316417873 815 32.5600000000 0.5909790993 0.4970668819 2.0662415028 0.0204878761 0.0027640000 16260517 955859216 1373700096 -0.7853152156 0.1543947160 0.4336007535 816 32.6000000000 0.5925217271 0.4971838608 2.0662415028 0.0204845504 0.0027710000 16262493 955859216 1373700096 -0.7881129384 0.1505432427 0.4362795055 817 32.6400000000 0.5942060351 0.4973026150 2.0662415028 0.0204788343 0.0027740000 16264469 955859216 1373700096 -0.7910624146 0.1467594653 0.4384420216 818 32.6800000000 0.5966250896 0.4974240362 2.0662415028 0.0204718806 0.0028010000 16266445 955859216 1373700096 -0.7943677306 0.1433731318 0.4405883253 819 32.7200000000 0.5999379158 0.4975492057 2.0662415028 0.0204662952 0.0027910000 16268421 955859216 1373700096 -0.7981552482 0.1414882094 0.4428007603 820 32.7599999990 0.6028050780 0.4976775665 2.0662415028 0.0204615224 0.0027880000 16270397 955859216 1373700096 -0.8019534349 0.1397168487 0.4451340437 821 32.7999999990 0.6065465808 0.4978101719 2.0662415028 0.0204632685 0.0027890000 16272373 955859216 1373700096 -0.8062666059 0.1388388574 0.4484658539 822 32.8400000000 0.6090238094 0.4979454683 2.0662415028 0.0204770160 0.0027940000 16274349 955859216 1373700096 -0.8102194071 0.1380286068 0.4518119991 823 32.8800000000 0.6116070151 0.4980835747 2.0662415028 0.0204898414 0.0029090000 16276325 955859216 1373700096 -0.8144686818 0.1380236447 0.4550698102 824 32.9200000000 0.6160616279 0.4982267519 2.0662415028 0.0204941204 0.0029040000 16278301 955859216 1373700096 -0.8196126223 0.1379500926 0.4579430819 825 32.9600000000 0.6201629639 0.4983745534 2.0662415028 0.0204981132 0.0029160000 16280277 955859216 1373700096 -0.8246998191 0.1368237287 0.4612337053 826 33.0000000000 0.6248977184 0.4985277292 2.0662415028 0.0204975977 0.0029190000 16282253 955859216 1373700096 -0.8301600218 0.1362415254 0.4642368853 827 33.0400000000 0.6288742423 0.4986853428 2.0662415028 0.0205014181 0.0029250000 16284229 955859216 1373700096 -0.8352800012 0.1340839714 0.4675470889 828 33.0800000000 0.6323790550 0.4988468087 2.0662415028 0.0205196745 0.0029130000 16286205 955859216 1373700096 -0.8401330113 0.1309506297 0.4713420868 829 33.1199999990 0.6367722154 0.4990131843 2.0662415028 0.0205427089 0.0029040000 16288181 955859216 1373700096 -0.8457649350 0.1282104403 0.4749413431 830 33.1600000000 0.6407966018 0.4991840077 2.0662415028 0.0205663984 0.0029290000 16290157 955859216 1373700096 -0.8509976864 0.1254604459 0.4784588516 831 33.2000000000 0.6447650194 0.4993591955 2.0662415028 0.0205948441 0.0029460000 16292133 955859216 1373700096 -0.8565008640 0.1218174025 0.4833694398 832 33.2400000000 0.6491046548 0.4995391780 2.0662415028 0.0206166289 0.0029570000 16294109 955859216 1373700096 -0.8622081280 0.1185077205 0.4873134494 833 33.2800000000 0.6541745663 0.4997248147 2.0662415028 0.0206273820 0.0029730000 16296085 955859216 1373700096 -0.8683618307 0.1160245463 0.4908512533 834 33.3200000000 0.6583822966 0.4999150515 2.0662415028 0.0206346018 0.0029610000 16298061 955859216 1373700096 -0.8740447164 0.1121944860 0.4948659539 835 33.3600000000 0.6633126736 0.5001107373 2.0662415028 0.0206480555 0.0029670000 16300037 955859216 1373700096 -0.8799616098 0.1097801849 0.4977856874 836 33.4000000000 0.6681047082 0.5003116870 2.0662415028 0.0206657985 0.0029850000 16302013 955859216 1373700096 -0.8858966827 0.1070993766 0.5015283227 837 33.4399999990 0.6731237173 0.5005181530 2.0662415028 0.0206864029 0.0029930000 16303989 955859216 1373700096 -0.8918247819 0.1051701307 0.5045602918 838 33.4800000000 0.6767873168 0.5007284980 2.0662415028 0.0207172425 0.0029890000 16305965 955859216 1373700096 -0.8969164491 0.1015202850 0.5087157488 839 33.5200000000 0.6815209985 0.5009439837 2.0662415028 0.0207508598 0.0029870000 16307941 955859216 1373700096 -0.9025990963 0.0996923298 0.5124865174 840 33.5600000000 0.6858512163 0.5011641114 2.0662415028 0.0207736013 0.0031020000 16309917 955859216 1373700096 -0.9074191451 0.0979226083 0.5131713152 841 33.6000000000 0.6901396513 0.5013888148 2.0662415028 0.0207747257 0.0030120000 16311893 955859216 1373700096 -0.9126866460 0.0959467515 0.5157421231 842 33.6400000000 0.6944532394 0.5016181074 2.0662415028 0.0207710945 0.0030440000 16313869 955859216 1373700096 -0.9176396728 0.0942143500 0.5176334381 843 33.6800000000 0.6984208226 0.5018515626 2.0662415028 0.0207710282 0.0030320000 16315845 955859216 1373700096 -0.9225142598 0.0914254710 0.5203036070 844 33.7200000000 0.7013629675 0.5020879505 2.0662415028 0.0207763220 0.0030190000 16317821 955859216 1373700096 -0.9268125892 0.0873513520 0.5235995054 845 33.7599999990 0.7047831416 0.5023278265 2.0662415028 0.0207890798 0.0030440000 16319797 955859216 1373700096 -0.9311919808 0.0848151743 0.5271734595 846 33.7999999990 0.7082574368 0.5025712421 2.0662415028 0.0207981371 0.0030300000 16321773 955859216 1373700096 -0.9355236292 0.0828832760 0.5293521285 847 33.8400000000 0.7091448307 0.5028151306 2.0662415028 0.0207920574 0.0029290000 16323749 955859216 1373700096 -0.9386397004 0.0782382339 0.5332557559 848 33.8800000000 0.7134274244 0.5030634942 2.0662415028 0.0207905959 0.0031440000 16325725 955859216 1373700096 -0.9426175356 0.0761933401 0.5336487889 849 33.9200000000 0.7143082619 0.5033123102 2.0662415028 0.0207800225 0.0029790000 16327701 955859216 1373700096 -0.9456551671 0.0708926022 0.5375232697 850 33.9600000000 0.7163935900 0.5035629940 2.0662415028 0.0207691349 0.0029520000 16329677 955859216 1373700096 -0.9490904808 0.0665719584 0.5404807329 851 34.0000000000 0.7194256186 0.5038166516 2.0662415028 0.0207590786 0.0029550000 16331653 955859216 1373700096 -0.9529017806 0.0635290742 0.5425482988 852 34.0400000000 0.7216790915 0.5040723587 2.0662415028 0.0207504329 0.0029640000 16333629 955859216 1373700096 -0.9559775591 0.0595540628 0.5455771089 853 34.0800000000 0.7227056623 0.5043286698 2.0662415028 0.0207448801 0.0029800000 16335605 955859216 1373700096 -0.9587031007 0.0555447713 0.5485106111 854 34.1199999990 0.7245624065 0.5045865547 2.0662415028 0.0207405177 0.0029820000 16337581 955859216 1373700096 -0.9617031217 0.0529148690 0.5514869690 855 34.1600000000 0.7260341048 0.5048455577 2.0662415028 0.0207360777 0.0029880000 16339557 955859216 1373700096 -0.9642603397 0.0509819649 0.5546684265 856 34.2000000000 0.7269839048 0.5051050651 2.0662415028 0.0207288895 0.0030040000 16341533 955859216 1373700096 -0.9665694237 0.0489111766 0.5573220849 857 34.2400000000 0.7295230031 0.5053669297 2.0662415028 0.0207182357 0.0029920000 16343509 955859216 1373700096 -0.9694931507 0.0479398407 0.5582157969 858 34.2800000000 0.7321344018 0.5056312274 2.0662415028 0.0207068781 0.0030130000 16345485 955859216 1373700096 -0.9721474648 0.0465047397 0.5581283569 859 34.3200000000 0.7331290841 0.5058960678 2.0662415028 0.0206961739 0.0029960000 16347461 955859216 1373700096 -0.9736576080 0.0421037748 0.5596696734 860 34.3600000000 0.7331058979 0.5061602652 2.0662415028 0.0206856341 0.0030020000 16349437 955859216 1373700096 -0.9750395417 0.0369841494 0.5617319942 861 34.4000000000 0.7347274423 0.5064257323 2.0662415028 0.0206765597 0.0030170000 16351413 955859216 1373700096 -0.9773375392 0.0331324525 0.5637090206 862 34.4400000000 0.7356658578 0.5066916722 2.0662415028 0.0206661497 0.0030320000 16353389 955859216 1373700096 -0.9790199399 0.0292983428 0.5655102730 863 34.4800000000 0.7348882556 0.5069560946 2.0662415028 0.0206571344 0.0030280000 16355365 955859216 1373700096 -0.9797568321 0.0240763295 0.5678512454 864 34.5200000000 0.7351312041 0.5072201862 2.0662415028 0.0206485938 0.0030050000 16357341 955859216 1373700096 -0.9810523391 0.0202022139 0.5704897642 865 34.5600000000 0.7358158827 0.5074844587 2.0662415028 0.0206379800 0.0030080000 16359317 955859216 1373700096 -0.9827489257 0.0182518307 0.5720714331 866 34.6000000000 0.7366355062 0.5077490673 2.0662415028 0.0206264352 0.0030200000 16361293 955859216 1373700096 -0.9841951728 0.0165590979 0.5723378658 867 34.6400000000 0.7384316325 0.5080151371 2.0662415028 0.0206148944 0.0030060000 16363269 955859216 1373700096 -0.9857376814 0.0146628674 0.5727234483 868 34.6800000000 0.7385058403 0.5082806794 2.0662415028 0.0206054073 0.0030010000 16365245 955859216 1373700096 -0.9865695834 0.0116596250 0.5733153820 869 34.7200000000 0.7384798527 0.5085455806 2.0662415028 0.0205959343 0.0030170000 16367221 955859216 1373700096 -0.9871261716 0.0087009640 0.5751544833 870 34.7600000000 0.7375670671 0.5088088237 2.0662415028 0.0205857052 0.0030100000 16369197 955859216 1373700096 -0.9876373410 0.0057688090 0.5765168667 871 34.8000000000 0.7377327681 0.5090716526 2.0662415028 0.0205749048 0.0030270000 16371173 955859216 1373700096 -0.9885775447 0.0035094749 0.5771118402 872 34.8400000000 0.7378916144 0.5093340608 2.0662415028 0.0205653111 0.0037620000 16373149 955859216 1373700096 -0.9895560145 0.0006322903 0.5773363709 873 34.8800000000 0.7390570045 0.5095972028 2.0662415028 0.0205559175 0.0030720000 16375125 955859216 1373700096 -0.9909991026 -0.0016428208 0.5780614614 874 34.9200000000 0.7400851250 0.5098609190 2.0662415028 0.0205472597 0.0030380000 16377101 955859216 1373700096 -0.9923577905 -0.0032810569 0.5784927607 875 34.9600000000 0.7419028282 0.5101261097 2.0662415028 0.0205385227 0.0030530000 16379077 955859216 1373700096 -0.9943509698 -0.0036567498 0.5781883597 876 35.0000000000 0.7436861396 0.5103927307 2.0662415028 0.0205289965 0.0030070000 16381053 955859216 1373700096 -0.9959936738 -0.0040280079 0.5777613521 877 35.0400000000 0.7454834580 0.5106607931 2.0662415028 0.0205179677 0.0030250000 16383029 955859216 1373700096 -0.9977055788 -0.0042179553 0.5774977207 878 35.0800000000 0.7470305562 0.5109300070 2.0662415028 0.0205063207 0.0030160000 16385005 955859216 1373700096 -0.9992318749 -0.0039630565 0.5769919753 879 35.1200000000 0.7481192350 0.5111998468 2.0662415028 0.0204946670 0.0030380000 16386981 955859216 1373700096 -1.0005630255 -0.0044919993 0.5769450665 880 35.1600000000 0.7499426603 0.5114711455 2.0662415028 0.0204831869 0.0030200000 16388957 955859216 1373700096 -1.0021252632 -0.0041123098 0.5767872930 881 35.2000000000 0.7516515851 0.5117437680 2.0662415028 0.0204719375 0.0030240000 16390933 955859216 1373700096 -1.0037856102 -0.0037853401 0.5762532949 882 35.2400000000 0.7515255809 0.5120156295 2.0662415028 0.0204604315 0.0030420000 16392909 955859216 1373700096 -1.0040969849 -0.0065113297 0.5773392320 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:32:39 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0093800000 14287333 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0004094284 0.0002047142 0.0004094284 0.0010303429 0.0076310000 14680837 955859216 1373700096 -0.0001883990 0.0036794858 0.0017925142 3 0.0800000000 0.0007736458 0.0003943581 0.0007736458 0.0018677595 0.0025490000 14683205 955859216 1373700096 -0.0019190218 -0.0019782742 0.0017745177 4 0.1200000000 0.0009048689 0.0005219858 0.0009048689 0.0023429534 0.0025550000 14685581 955859216 1373700096 -0.0022994194 -0.0007408440 0.0006243517 5 0.1600000000 0.0010996070 0.0006375100 0.0010996070 0.0042287254 0.0027850000 14687941 955859216 1373700096 -0.0001009388 0.0057270927 0.0036499682 6 0.2000000000 0.0012643087 0.0007419765 0.0012643087 0.0040530294 0.0026020000 14690717 955859216 1373700096 0.0030182770 -0.0043588500 0.0027662795 7 0.2400000000 0.0013147279 0.0008237981 0.0013147279 0.0039123365 0.0026830000 14692693 955859216 1373700096 0.0032340335 -0.0143805062 -0.0003496237 8 0.2800000000 0.0012483426 0.0008768662 0.0013147279 0.0036324239 0.0026080000 14694669 955859216 1373700096 0.0010289684 -0.0127349431 -0.0012624591 9 0.3200000000 0.0011119688 0.0009029887 0.0013147279 0.0045070057 0.0025960000 14697413 955859216 1373700096 -0.0001046339 -0.0090118377 0.0016741320 10 0.3600000000 0.0015377488 0.0009664647 0.0015377488 0.0042738382 0.0025220000 14700989 955859216 1373700096 -0.0020094230 -0.0159390066 -0.0001044746 11 0.4000000000 0.0013893836 0.0010049119 0.0015377488 0.0041149680 0.0026330000 14702965 955859216 1373700096 -0.0019318160 -0.0125451731 -0.0013850294 12 0.4400000000 0.0015643545 0.0010515321 0.0015643545 0.0041785242 0.0028180000 14704941 955859216 1373700096 -0.0009363076 -0.0024040469 0.0015460169 13 0.4800000000 0.0015554482 0.0010902949 0.0015643545 0.0040044699 0.0025830000 14706917 955859216 1373700096 0.0010242085 -0.0045432812 0.0015848510 14 0.5200000000 0.0017365448 0.0011364556 0.0017365448 0.0039622837 0.0027110000 14708893 955859216 1373700096 0.0039538071 -0.0120516000 -0.0011668218 15 0.5600000000 0.0013733063 0.0011522456 0.0017365448 0.0039249707 0.0026040000 14710869 955859216 1373700096 0.0065184906 -0.0107199606 -0.0013660063 16 0.6000000000 0.0015204150 0.0011752562 0.0017365448 0.0038004599 0.0025670000 14712845 955859216 1373700096 0.0077480217 -0.0094032669 -0.0010699943 17 0.6400000000 0.0017244305 0.0012075606 0.0017365448 0.0037018043 0.0025980000 14716357 955859216 1373700096 0.0074980655 -0.0128850136 -0.0028926409 18 0.6800000000 0.0015568256 0.0012269642 0.0017365448 0.0035935938 0.0025440000 14721533 955859216 1373700096 0.0066834879 -0.0120405033 -0.0042887172 19 0.7200000000 0.0018272134 0.0012585562 0.0018272134 0.0036640515 0.0026580000 14723509 955859216 1373700096 0.0073555154 -0.0077363923 -0.0040852432 20 0.7600000000 0.0017196776 0.0012816123 0.0018272134 0.0039422345 0.0025480000 14725485 955859216 1373700096 0.0067750034 -0.0090646604 -0.0066798073 21 0.8000000000 0.0019162913 0.0013118351 0.0019162913 0.0041299779 0.0027870000 14727461 955859216 1373700096 0.0094403932 -0.0058389995 -0.0064818170 22 0.8400000000 0.0017574644 0.0013320910 0.0019162913 0.0040657309 0.0026410000 14729437 955859216 1373700096 0.0095453719 -0.0033037816 -0.0061235386 23 0.8800000000 0.0019603055 0.0013594047 0.0019603055 0.0040401645 0.0027370000 14731413 955859216 1373700096 0.0122422772 -0.0094001908 -0.0100540314 24 0.9200000000 0.0017895983 0.0013773294 0.0019603055 0.0040306062 0.0027810000 14733389 955859216 1373700096 0.0142446356 -0.0083841961 -0.0099053178 25 0.9600000000 0.0019312195 0.0013994850 0.0019603055 0.0039477887 0.0026350000 14735365 955859216 1373700096 0.0143175339 -0.0110584553 -0.0129436748 26 1.0000000000 0.0019362512 0.0014201299 0.0019603055 0.0038687701 0.0026470000 14737341 955859216 1373700096 0.0126600200 -0.0114794588 -0.0139608830 27 1.0400000000 0.0020509919 0.0014434951 0.0020509919 0.0038081804 0.0026270000 14739317 955859216 1373700096 0.0137265250 -0.0154127507 -0.0164061673 28 1.0800000000 0.0020240154 0.0014642280 0.0020509919 0.0037406942 0.0027330000 14741293 955859216 1373700096 0.0125953583 -0.0176324919 -0.0178359747 29 1.1200000000 0.0020394044 0.0014840617 0.0020509919 0.0037617626 0.0026390000 14743269 955859216 1373700096 0.0137711894 -0.0196780581 -0.0190287940 30 1.1600000000 0.0018927174 0.0014976835 0.0020509919 0.0037310842 0.0026200000 14745245 955859216 1373700096 0.0169947147 -0.0189688969 -0.0194256734 31 1.2000000000 0.0021806685 0.0015197153 0.0021806685 0.0037383772 0.0029750000 14747221 955859216 1373700096 0.0219054073 -0.0174344219 -0.0208225753 32 1.2400000000 0.0019102187 0.0015319185 0.0021806685 0.0037833560 0.0029320000 14749197 955859216 1373700096 0.0221926682 -0.0146334339 -0.0219393987 33 1.2800000000 0.0021920181 0.0015519215 0.0021920181 0.0040312886 0.0028640000 14754245 955859216 1373700096 0.0235215258 -0.0102567039 -0.0220226683 34 1.3200000000 0.0022348077 0.0015720064 0.0022348077 0.0042439997 0.0029540000 14762621 955859216 1373700096 0.0317971148 -0.0078233508 -0.0243346449 35 1.3600000000 0.0021293845 0.0015879315 0.0022348077 0.0041844540 0.0031490000 14764597 955859216 1373700096 0.0309663564 -0.0092326552 -0.0259228889 36 1.4000000000 0.0021667217 0.0016040090 0.0022348077 0.0041350088 0.0026900000 14766573 955859216 1373700096 0.0313613266 -0.0115087871 -0.0293233842 37 1.4400000000 0.0021539435 0.0016188721 0.0022348077 0.0040781576 0.0026810000 14768549 955859216 1373700096 0.0339642353 -0.0126045356 -0.0315986164 38 1.4800000000 0.0021889312 0.0016338737 0.0022348077 0.0040233706 0.0026690000 14770525 955859216 1373700096 0.0338653326 -0.0126117459 -0.0318669714 39 1.5200000000 0.0021710244 0.0016476468 0.0022348077 0.0039959497 0.0026420000 14772501 955859216 1373700096 0.0346578136 -0.0118964724 -0.0328014567 40 1.5600000000 0.0021545172 0.0016603185 0.0022348077 0.0041949308 0.0027240000 14774477 955859216 1373700096 0.0376336724 -0.0115998322 -0.0336409248 41 1.6000000000 0.0023893269 0.0016780992 0.0023893269 0.0044608243 0.0028250000 14776453 955859216 1373700096 0.0432956368 -0.0096278554 -0.0342748575 42 1.6400000000 0.0022617050 0.0016919946 0.0023893269 0.0044230490 0.0026800000 14778429 955859216 1373700096 0.0436375737 -0.0098934323 -0.0355395749 43 1.6800000000 0.0022632249 0.0017052790 0.0023893269 0.0044095741 0.0027260000 14780405 955859216 1373700096 0.0454422310 -0.0100793233 -0.0370605215 44 1.7200000000 0.0022147568 0.0017168581 0.0023893269 0.0043797238 0.0026770000 14782381 955859216 1373700096 0.0473990254 -0.0092238234 -0.0372697897 45 1.7600000000 0.0021670079 0.0017268614 0.0023893269 0.0045671319 0.0027490000 14784357 955859216 1373700096 0.0492220819 -0.0076859598 -0.0384158380 46 1.8000000000 0.0022492951 0.0017382186 0.0023893269 0.0046608076 0.0027030000 14786333 955859216 1373700096 0.0507198088 -0.0068452251 -0.0390998386 47 1.8400000000 0.0024542015 0.0017534523 0.0024542015 0.0046709750 0.0029170000 14788309 955859216 1373700096 0.0524993092 -0.0040020947 -0.0395005643 48 1.8800000000 0.0022113810 0.0017629925 0.0024542015 0.0046547508 0.0027610000 14790285 955859216 1373700096 0.0543768220 -0.0032337988 -0.0392938852 49 1.9200000000 0.0023174258 0.0017743075 0.0024542015 0.0046863837 0.0027590000 14792261 955859216 1373700096 0.0555094630 -0.0054616798 -0.0411496498 50 1.9600000000 0.0023603479 0.0017860283 0.0024542015 0.0046602706 0.0028710000 14794237 955859216 1373700096 0.0509379022 -0.0034681237 -0.0431748070 51 2.0000000000 0.0022991656 0.0017960898 0.0024542015 0.0046575816 0.0028610000 14796213 955859216 1373700096 0.0501486510 0.0007077348 -0.0423096269 52 2.0400000000 0.0024003119 0.0018077094 0.0024542015 0.0046322113 0.0028090000 14798189 955859216 1373700096 0.0501841865 -0.0009694730 -0.0425336584 53 2.0800000000 0.0024811951 0.0018204167 0.0024811951 0.0045983651 0.0028270000 14800165 955859216 1373700096 0.0504571162 -0.0051449058 -0.0448277444 54 2.1200000000 0.0022687535 0.0018287193 0.0024811951 0.0046199583 0.0027520000 14802141 955859216 1373700096 0.0507848561 -0.0043399562 -0.0444268063 55 2.1600000000 0.0022257967 0.0018359388 0.0024811951 0.0046124616 0.0028150000 14804117 955859216 1373700096 0.0516817570 -0.0022456152 -0.0443565324 56 2.2000000000 0.0023027021 0.0018442739 0.0024811951 0.0046205730 0.0027640000 14806093 955859216 1373700096 0.0530725420 -0.0027541791 -0.0452396274 57 2.2400000000 0.0023856966 0.0018537726 0.0024811951 0.0046371727 0.0027430000 14808069 955859216 1373700096 0.0533584580 -0.0052442509 -0.0475287028 58 2.2800000000 0.0026033449 0.0018666962 0.0026033449 0.0048084976 0.0028880000 14810045 955859216 1373700096 0.0571545474 -0.0035539863 -0.0470007807 59 2.3200000000 0.0026363600 0.0018797414 0.0026363600 0.0049690844 0.0028620000 14812021 955859216 1373700096 0.0609371066 -0.0007635233 -0.0477153808 60 2.3600000000 0.0026573592 0.0018927017 0.0026573592 0.0050190962 0.0028480000 14813997 955859216 1373700096 0.0642668903 -0.0050987718 -0.0503167734 61 2.4000000000 0.0026077225 0.0019044233 0.0026573592 0.0050084523 0.0027110000 14815973 955859216 1373700096 0.0640450194 -0.0078311702 -0.0517003313 62 2.4400000000 0.0024397459 0.0019130575 0.0026573592 0.0050527221 0.0027590000 14817949 955859216 1373700096 0.0661094263 -0.0071492558 -0.0511754975 63 2.4800000000 0.0027056439 0.0019256383 0.0027056439 0.0050890671 0.0028810000 14819925 955859216 1373700096 0.0724388435 -0.0050210776 -0.0512392111 64 2.5200000000 0.0027034367 0.0019377914 0.0027056439 0.0050649285 0.0029370000 14821901 955859216 1373700096 0.0748050734 -0.0091521274 -0.0551469401 65 2.5600000000 0.0025107290 0.0019466058 0.0027056439 0.0050548903 0.0028290000 14830021 955859216 1373700096 0.0759724900 -0.0087753246 -0.0549718775 66 2.6000000000 0.0026122583 0.0019566915 0.0027056439 0.0050172097 0.0027800000 14844797 955859216 1373700096 0.0728200749 -0.0125838043 -0.0567746237 67 2.6400000000 0.0024772980 0.0019644617 0.0027056439 0.0050485620 0.0027370000 14846773 955859216 1373700096 0.0730941668 -0.0143820653 -0.0585720874 68 2.6800000000 0.0027923172 0.0019766360 0.0027923172 0.0051305396 0.0027930000 14848749 955859216 1373700096 0.0783980265 -0.0166312233 -0.0589932092 69 2.7200000000 0.0023979407 0.0019827419 0.0027923172 0.0051483288 0.0026890000 14850725 955859216 1373700096 0.0798005983 -0.0166552588 -0.0601037331 70 2.7600000000 0.0027978285 0.0019943860 0.0027978285 0.0052021160 0.0028250000 14852701 955859216 1373700096 0.0824733153 -0.0145695610 -0.0608476400 71 2.8000000000 0.0027887628 0.0020055744 0.0027978285 0.0052455073 0.0028660000 14854677 955859216 1373700096 0.0850033388 -0.0138812307 -0.0625868291 72 2.8400000000 0.0024028185 0.0020110917 0.0027978285 0.0052618890 0.0026920000 14856653 955859216 1373700096 0.0865660608 -0.0147012249 -0.0634027421 73 2.8800000000 0.0027874280 0.0020217264 0.0027978285 0.0053144009 0.0029020000 14858629 955859216 1373700096 0.0893140435 -0.0116394963 -0.0657199621 74 2.9200000000 0.0028712424 0.0020332064 0.0028712424 0.0054327060 0.0028490000 14860605 955859216 1373700096 0.0912376940 -0.0117584374 -0.0687552616 75 2.9600000000 0.0028950435 0.0020446975 0.0028950435 0.0054744798 0.0028710000 14862581 955859216 1373700096 0.0968225375 -0.0118075050 -0.0702042133 76 3.0000000000 0.0028644432 0.0020554837 0.0028950435 0.0054946650 0.0019570000 14864557 955859216 1373700096 0.1002319753 -0.0103203179 -0.0719242916 77 3.0400000000 0.0023114881 0.0020588084 0.0028950435 0.0055151656 0.0027480000 14866533 955859216 1373700096 0.1028904393 -0.0105192689 -0.0728469342 78 3.0800000000 0.0029266693 0.0020699348 0.0029266693 0.0054897302 0.0029300000 14868509 955859216 1373700096 0.1061407998 -0.0120485621 -0.0764892399 79 3.1200000000 0.0029016102 0.0020804624 0.0029266693 0.0055126927 0.0028610000 14870485 955859216 1373700096 0.1098680198 -0.0106764436 -0.0769786164 80 3.1600000000 0.0028742924 0.0020903852 0.0029266693 0.0054963674 0.0029050000 14872461 955859216 1373700096 0.1136394069 -0.0110050002 -0.0798439607 81 3.2000000000 0.0029814460 0.0021013860 0.0029814460 0.0054759600 0.0028540000 14874437 955859216 1373700096 0.1193037853 -0.0123778069 -0.0814463869 82 3.2400000000 0.0029774387 0.0021120696 0.0029814460 0.0054494816 0.0028320000 14876413 955859216 1373700096 0.1233621836 -0.0138357738 -0.0837647989 83 3.2800000000 0.0021591925 0.0021126373 0.0029814460 0.0054324628 0.0027430000 14878389 955859216 1373700096 0.1247604266 -0.0148055889 -0.0856971815 84 3.3200000000 0.0029597003 0.0021227214 0.0029814460 0.0054127522 0.0028270000 14880365 955859216 1373700096 0.1314608753 -0.0143713346 -0.0886843726 85 3.3600000000 0.0029330978 0.0021322552 0.0029814460 0.0053833396 0.0029010000 14882341 955859216 1373700096 0.1420080811 -0.0111122327 -0.0887619033 86 3.4000000000 0.0018834723 0.0021293624 0.0029814460 0.0054097140 0.0027420000 14884317 955859216 1373700096 0.1440659463 -0.0101841167 -0.0908266678 87 3.4400000000 0.0018028324 0.0021256092 0.0029814460 0.0054065445 0.0027700000 14886293 955859216 1373700096 0.1460017711 -0.0104778297 -0.0936211497 88 3.4800000000 0.0029309085 0.0021347603 0.0029814460 0.0053784450 0.0028750000 14888269 955859216 1373700096 0.1522705257 -0.0068258783 -0.0946329981 89 3.5200000000 0.0019669186 0.0021328744 0.0029814460 0.0053582399 0.0027330000 14890245 955859216 1373700096 0.1546829641 -0.0074656191 -0.0956079215 90 3.5600000000 0.0018128391 0.0021293185 0.0029814460 0.0053309690 0.0027920000 14892221 955859216 1373700096 0.1575471759 -0.0075453799 -0.0970806032 91 3.6000000000 0.0028915664 0.0021376948 0.0029814460 0.0053769709 0.0028350000 14894197 955859216 1373700096 0.1644580364 -0.0059934063 -0.0983021036 92 3.6400000000 0.0029329120 0.0021463385 0.0029814460 0.0054534170 0.0029540000 14896173 955859216 1373700096 0.1738549322 -0.0031874350 -0.0982806832 93 3.6800000000 0.0029144441 0.0021545977 0.0029814460 0.0054685404 0.0028540000 14898149 955859216 1373700096 0.1819858998 0.0007950146 -0.0997383818 94 3.7200000000 0.0030348059 0.0021639616 0.0030348059 0.0054448871 0.0028810000 14900125 955859216 1373700096 0.1903245747 0.0002498456 -0.1023021564 95 3.7600000000 0.0030527902 0.0021733177 0.0030527902 0.0054175001 0.0029220000 14902101 955859216 1373700096 0.1964565367 0.0002422934 -0.1047778279 96 3.8000000000 0.0031197991 0.0021831769 0.0031197991 0.0054023761 0.0029220000 14904077 955859216 1373700096 0.2039459199 -0.0009613868 -0.1067591161 97 3.8400000000 0.0030906729 0.0021925325 0.0031197991 0.0053765952 0.0029300000 14906053 955859216 1373700096 0.2118622214 0.0004916660 -0.1098599285 98 3.8800000000 0.0031632050 0.0022024373 0.0031632050 0.0053498623 0.0029470000 14908029 955859216 1373700096 0.2204021513 0.0006439016 -0.1106841639 99 3.9200000000 0.0031810708 0.0022123225 0.0031810708 0.0053599140 0.0029170000 14910005 955859216 1373700096 0.2286272794 0.0000267484 -0.1125846580 100 3.9600000000 0.0032161816 0.0022223611 0.0032161816 0.0053348492 0.0029240000 14911981 955859216 1373700096 0.2362845242 0.0004458611 -0.1130052507 101 4.0000000000 0.0031866920 0.0022319090 0.0032161816 0.0053242962 0.0029130000 14913957 955859216 1373700096 0.2449152768 0.0025198043 -0.1143246666 102 4.0400000000 0.0019915879 0.0022295529 0.0032161816 0.0053449449 0.0028940000 14915933 955859216 1373700096 0.2483614087 0.0013008966 -0.1158718988 103 4.0800000000 0.0031432083 0.0022384233 0.0032161816 0.0053190905 0.0028810000 14917909 955859216 1373700096 0.2576259375 0.0051930021 -0.1156172529 104 4.1200000000 0.0031855821 0.0022475306 0.0032161816 0.0052944349 0.0028740000 14919885 955859216 1373700096 0.2680574954 0.0078614531 -0.1163190827 105 4.1600000000 0.0032265312 0.0022568544 0.0032265312 0.0052864929 0.0028850000 14921861 955859216 1373700096 0.2746633291 0.0092287231 -0.1165691614 106 4.2000000000 0.0032836033 0.0022665407 0.0032836033 0.0052988238 0.0028670000 14923837 955859216 1373700096 0.2815839648 0.0075408407 -0.1190932542 107 4.2400000000 0.0033022708 0.0022762205 0.0033022708 0.0052760433 0.0029400000 14925813 955859216 1373700096 0.2895064652 0.0066218995 -0.1203047112 108 4.2800000000 0.0032872444 0.0022855818 0.0033022708 0.0052597118 0.0029400000 14927789 955859216 1373700096 0.2981612980 0.0067757084 -0.1220696643 109 4.3200000000 0.0034659954 0.0022964113 0.0034659954 0.0052398134 0.0030620000 14929765 955859216 1373700096 0.3153337538 0.0065846276 -0.1246479601 110 4.3600000000 0.0033178781 0.0023056973 0.0034659954 0.0052362262 0.0029730000 14931741 955859216 1373700096 0.3273510933 0.0074896226 -0.1253632456 111 4.4000000000 0.0033759971 0.0023153397 0.0034659954 0.0052127165 0.0029310000 14933717 955859216 1373700096 0.3371313512 0.0067883395 -0.1270566136 112 4.4400000000 0.0026284065 0.0023181349 0.0034659954 0.0051925515 0.0028600000 14935693 955859216 1373700096 0.3409692645 0.0029050931 -0.1290668845 113 4.4800000000 0.0033247722 0.0023270432 0.0034659954 0.0051701950 0.0029080000 14937669 955859216 1373700096 0.3518463671 0.0019664117 -0.1303994209 114 4.5200000000 0.0033394326 0.0023359238 0.0034659954 0.0051540587 0.0028990000 14939645 955859216 1373700096 0.3628134429 0.0018652887 -0.1312916279 115 4.5600000000 0.0033712890 0.0023449270 0.0034659954 0.0051412494 0.0029000000 14941621 955859216 1373700096 0.3728018105 0.0000123997 -0.1325874031 116 4.6000000000 0.0034211713 0.0023542050 0.0034659954 0.0051211331 0.0029060000 14943597 955859216 1373700096 0.3806957901 -0.0029151798 -0.1341880709 117 4.6400000000 0.0034370357 0.0023634599 0.0034659954 0.0051256775 0.0029370000 14945573 955859216 1373700096 0.3881727755 -0.0054329336 -0.1353384107 118 4.6800000000 0.0034079216 0.0023723113 0.0034659954 0.0051389473 0.0029040000 14947549 955859216 1373700096 0.3974432647 -0.0055504343 -0.1357059330 119 4.7200000000 0.0034212917 0.0023811263 0.0034659954 0.0051773944 0.0029000000 14949525 955859216 1373700096 0.4115660489 -0.0048687570 -0.1338240355 120 4.7600000000 0.0034290932 0.0023898593 0.0034659954 0.0051559640 0.0028970000 14951501 955859216 1373700096 0.4228167832 -0.0029815056 -0.1324140877 121 4.8000000000 0.0035299042 0.0023992812 0.0035299042 0.0051514863 0.0028930000 14953477 955859216 1373700096 0.4312586188 -0.0040739314 -0.1339072287 122 4.8400000000 0.0035332083 0.0024085757 0.0035332083 0.0051504412 0.0029820000 14955453 955859216 1373700096 0.4402956665 -0.0036049853 -0.1344281286 123 4.8800000000 0.0035443190 0.0024178093 0.0035443190 0.0051302886 0.0030420000 14957429 955859216 1373700096 0.4517633915 -0.0013495070 -0.1324567646 124 4.9200000000 0.0036691751 0.0024279010 0.0036691751 0.0051109253 0.0030200000 14959405 955859216 1373700096 0.4582513869 0.0001761877 -0.1292404979 125 4.9600000000 0.0037209836 0.0024382457 0.0037209836 0.0051026602 0.0029190000 14961381 955859216 1373700096 0.4616816342 -0.0000371868 -0.1277899295 126 5.0000000000 0.0036758753 0.0024480681 0.0037209836 0.0050885581 0.0028890000 14963357 955859216 1373700096 0.4709885120 -0.0000131949 -0.1260587722 127 5.0400000000 0.0037139861 0.0024580360 0.0037209836 0.0050712760 0.0028900000 14965333 955859216 1373700096 0.4811953902 -0.0001490349 -0.1238864884 128 5.0800000000 0.0037108157 0.0024678233 0.0037209836 0.0050653918 0.0029780000 14967309 955859216 1373700096 0.4930784702 0.0011090070 -0.1205487549 129 5.1200000000 0.0037384895 0.0024776734 0.0037384895 0.0050580916 0.0030860000 14981573 955859216 1373700096 0.5042192340 0.0024421909 -0.1170022562 130 5.1600000000 0.0038043880 0.0024878789 0.0038043880 0.0050401215 0.0030620000 15009149 955859216 1373700096 0.5108944774 0.0033690108 -0.1145401523 131 5.2000000000 0.0039445101 0.0024989983 0.0039445101 0.0050746132 0.0030580000 15011125 955859216 1373700096 0.5175938606 0.0026846698 -0.1114172190 132 5.2400000000 0.0038541851 0.0025092648 0.0039445101 0.0050606815 0.0029890000 15013101 955859216 1373700096 0.5283306837 0.0030820239 -0.1076070741 133 5.2800000000 0.0038619218 0.0025194352 0.0039445101 0.0050416145 0.0030330000 15015077 955859216 1373700096 0.5389447808 0.0039647180 -0.1031871140 134 5.3200000000 0.0039508208 0.0025301172 0.0039508208 0.0050888792 0.0030100000 15017053 955859216 1373700096 0.5475323796 0.0037581779 -0.1004980728 135 5.3600000000 0.0039220764 0.0025404280 0.0039508208 0.0051028368 0.0029770000 15019029 955859216 1373700096 0.5573251843 0.0047080293 -0.0970766246 136 5.4000000000 0.0040839808 0.0025517776 0.0040839808 0.0051298382 0.0031920000 15021005 955859216 1373700096 0.5714485049 0.0125787351 -0.0908309668 137 5.4400000000 0.0039124903 0.0025617098 0.0040839808 0.0051263747 0.0030720000 15022981 955859216 1373700096 0.5766602755 0.0161082055 -0.0870459005 138 5.4800000000 0.0040497170 0.0025724925 0.0040839808 0.0051719698 0.0030150000 15024957 955859216 1373700096 0.5802410841 0.0153019438 -0.0841815695 139 5.5200000000 0.0039277240 0.0025822424 0.0040839808 0.0051535279 0.0030400000 15026933 955859216 1373700096 0.5891025662 0.0157899857 -0.0792089105 140 5.5600000000 0.0039367639 0.0025919175 0.0040839808 0.0051370248 0.0030130000 15028909 955859216 1373700096 0.5975324512 0.0170118380 -0.0740857571 141 5.6000000000 0.0039465628 0.0026015249 0.0040839808 0.0051189718 0.0029940000 15030885 955859216 1373700096 0.6061668992 0.0179796424 -0.0692301840 142 5.6400000000 0.0039623096 0.0026111079 0.0040839808 0.0051040742 0.0030500000 15032861 955859216 1373700096 0.6170938611 0.0184422862 -0.0640259534 143 5.6800000000 0.0039906134 0.0026207548 0.0040839808 0.0050941477 0.0030650000 15034837 955859216 1373700096 0.6261628866 0.0204169266 -0.0587775856 144 5.7200000000 0.0040726666 0.0026308375 0.0040839808 0.0051126889 0.0030300000 15036813 955859216 1373700096 0.6321614981 0.0205578990 -0.0543375611 145 5.7600000000 0.0040207719 0.0026404233 0.0040839808 0.0050998277 0.0030710000 15038789 955859216 1373700096 0.6401224732 0.0209401324 -0.0490455441 146 5.8000000000 0.0040057846 0.0026497751 0.0040839808 0.0050846695 0.0030430000 15040765 955859216 1373700096 0.6499195695 0.0224031657 -0.0428787880 147 5.8400000000 0.0039446093 0.0026585835 0.0040839808 0.0050674153 0.0030250000 15042741 955859216 1373700096 0.6592737436 0.0262713972 -0.0367609113 148 5.8800000000 0.0041095824 0.0026683875 0.0041095824 0.0050906799 0.0030530000 15044717 955859216 1373700096 0.6635575891 0.0261837672 -0.0320579186 149 5.9200000000 0.0040432406 0.0026776147 0.0041095824 0.0050759844 0.0030790000 15046693 955859216 1373700096 0.6693006754 0.0255433097 -0.0276678465 150 5.9600000000 0.0039242818 0.0026859258 0.0041095824 0.0050813273 0.0030610000 15048669 955859216 1373700096 0.6772413254 0.0285121817 -0.0216673166 151 6.0000000000 0.0038838093 0.0026938588 0.0041095824 0.0050782222 0.0030410000 15050645 955859216 1373700096 0.6850020289 0.0307038166 -0.0169114769 152 6.0400000000 0.0040725223 0.0027029290 0.0041095824 0.0050864693 0.0030520000 15052621 955859216 1373700096 0.6983800530 0.0303672552 -0.0078990301 153 6.0800000000 0.0039828694 0.0027112946 0.0041095824 0.0051049858 0.0031630000 15054597 955859216 1373700096 0.7061048746 0.0313508511 -0.0024932201 154 6.1200000000 0.0040517049 0.0027199986 0.0041095824 0.0050885830 0.0030320000 15056573 955859216 1373700096 0.7123311758 0.0330657698 0.0025356896 155 6.1600000000 0.0040933848 0.0027288591 0.0041095824 0.0050883214 0.0030630000 15058549 955859216 1373700096 0.7165754437 0.0331270024 0.0067811217 156 6.2000000000 0.0040074303 0.0027370551 0.0041095824 0.0051016371 0.0031680000 15060525 955859216 1373700096 0.7251909971 0.0345692672 0.0124291806 157 6.2400000000 0.0041340403 0.0027459531 0.0041340403 0.0051116114 0.0030960000 15062501 955859216 1373700096 0.7319886684 0.0357747190 0.0183940567 158 6.2800000000 0.0041358620 0.0027547500 0.0041358620 0.0051210588 0.0030720000 15064477 955859216 1373700096 0.7365939021 0.0366810709 0.0241621062 159 6.3200000000 0.0040777586 0.0027630708 0.0041358620 0.0051507979 0.0031120000 15066453 955859216 1373700096 0.7438878417 0.0387841575 0.0310199615 160 6.3600000000 0.0042961123 0.0027726523 0.0042961123 0.0052049481 0.0031220000 15068429 955859216 1373700096 0.7575334907 0.0425086319 0.0452541336 161 6.4000000000 0.0041467263 0.0027811869 0.0042961123 0.0052298355 0.0031060000 15070405 955859216 1373700096 0.7614417672 0.0448334217 0.0521245413 162 6.4400000000 0.0040451507 0.0027889892 0.0042961123 0.0052198420 0.0031220000 15072381 955859216 1373700096 0.7664914727 0.0471981578 0.0598613732 163 6.4800000000 0.0039928146 0.0027963746 0.0042961123 0.0052288469 0.0031490000 15074357 955859216 1373700096 0.7729312181 0.0480398200 0.0679529533 164 6.5200000000 0.0039698710 0.0028035301 0.0042961123 0.0052393350 0.0031030000 15076333 955859216 1373700096 0.7806674242 0.0479504280 0.0760391951 165 6.5600000000 0.0039742785 0.0028106255 0.0042961123 0.0052459002 0.0031450000 15078309 955859216 1373700096 0.7893566489 0.0507276207 0.0848603547 166 6.6000000000 0.0039985059 0.0028177814 0.0042961123 0.0052682326 0.0031640000 15080285 955859216 1373700096 0.7973578572 0.0546891391 0.0939160064 167 6.6400000000 0.0040711113 0.0028252864 0.0042961123 0.0053192155 0.0031470000 15082261 955859216 1373700096 0.8017463684 0.0566187166 0.1020798534 168 6.6800000000 0.0039250660 0.0028318327 0.0042961123 0.0053236863 0.0031700000 15084237 955859216 1373700096 0.8087078929 0.0589940287 0.1108942106 169 6.7200000000 0.0039531910 0.0028384680 0.0042961123 0.0053176514 0.0031930000 15086213 955859216 1373700096 0.8175089955 0.0635627955 0.1215005592 170 6.7600000000 0.0039500017 0.0028450064 0.0042961123 0.0053311484 0.0032050000 15088189 955859216 1373700096 0.8231755495 0.0649758205 0.1297739595 171 6.8000000000 0.0039716302 0.0028515948 0.0042961123 0.0053156481 0.0031240000 15090165 955859216 1373700096 0.8325871825 0.0677985027 0.1400171071 172 6.8400000000 0.0040656347 0.0028586532 0.0042961123 0.0053001782 0.0032120000 15092141 955859216 1373700096 0.8407639861 0.0704972893 0.1502744406 173 6.8800000000 0.0040080496 0.0028652971 0.0042961123 0.0052853611 0.0032170000 15094117 955859216 1373700096 0.8445538878 0.0704771951 0.1574992239 174 6.9200000000 0.0039413106 0.0028714811 0.0042961123 0.0052776920 0.0031900000 15096093 955859216 1373700096 0.8528871536 0.0727004930 0.1672924310 175 6.9600000000 0.0039197123 0.0028774710 0.0042961123 0.0052655570 0.0032480000 15098069 955859216 1373700096 0.8625962138 0.0764655843 0.1777802110 176 7.0000000000 0.0040854695 0.0028843346 0.0042961123 0.0052506803 0.0032220000 15100045 955859216 1373700096 0.8695737123 0.0790184736 0.1877065748 177 7.0400000000 0.0040420475 0.0028908754 0.0042961123 0.0052902377 0.0032380000 15102021 955859216 1373700096 0.8742343187 0.0789010301 0.1958943158 178 7.0800000000 0.0039993539 0.0028971028 0.0042961123 0.0053184682 0.0032540000 15103997 955859216 1373700096 0.8785082102 0.0789021403 0.2037355751 179 7.1200000000 0.0039624642 0.0029030545 0.0042961123 0.0053041666 0.0032070000 15105973 955859216 1373700096 0.8845026493 0.0814276859 0.2129429281 180 7.1600000000 0.0038392111 0.0029082554 0.0042961123 0.0052948132 0.0033180000 15107949 955859216 1373700096 0.8906667233 0.0827621892 0.2220928073 181 7.2000000000 0.0039442829 0.0029139793 0.0042961123 0.0052803212 0.0032920000 15109925 955859216 1373700096 0.8945742249 0.0835436508 0.2309144884 182 7.2400000000 0.0037297322 0.0029184615 0.0042961123 0.0052669984 0.0032250000 15111901 955859216 1373700096 0.9001540542 0.0853772387 0.2395899743 183 7.2800000000 0.0037765668 0.0029231506 0.0042961123 0.0052527304 0.0033470000 15113877 955859216 1373700096 0.9054542780 0.0876027718 0.2489565313 184 7.3200000000 0.0036596959 0.0029271535 0.0042961123 0.0052451686 0.0033290000 15115853 955859216 1373700096 0.9108276963 0.0882421136 0.2565405071 185 7.3600000000 0.0021725981 0.0029230748 0.0042961123 0.0052411935 0.0032650000 15117829 955859216 1373700096 0.9126446247 0.0875174180 0.2631430030 186 7.4000000000 0.0036399385 0.0029269289 0.0042961123 0.0052271143 0.0033330000 15119805 955859216 1373700096 0.9199888110 0.0894141346 0.2720287442 187 7.4400000000 0.0037302293 0.0029312247 0.0042961123 0.0052263344 0.0033930000 15121781 955859216 1373700096 0.9250401258 0.0904786512 0.2793105245 188 7.4800000000 0.0038152335 0.0029359268 0.0042961123 0.0052130122 0.0033960000 15123757 955859216 1373700096 0.9292677045 0.0913981795 0.2859755754 189 7.5200000000 0.0027954122 0.0029351834 0.0042961123 0.0052013664 0.0032260000 15125733 955859216 1373700096 0.9313617349 0.0908947811 0.2925847471 190 7.5600000000 0.0037403088 0.0029394209 0.0042961123 0.0051955707 0.0033970000 15127709 955859216 1373700096 0.9374768138 0.0919899046 0.3004312515 191 7.6000000000 0.0039690770 0.0029448118 0.0042961123 0.0051856375 0.0033810000 15129685 955859216 1373700096 0.9414950609 0.0939373225 0.3085944951 192 7.6400000000 0.0041309460 0.0029509895 0.0042961123 0.0051724987 0.0034190000 15131661 955859216 1373700096 0.9444570541 0.0955121070 0.3170032799 193 7.6800000000 0.0043770042 0.0029583782 0.0043770042 0.0051599856 0.0034450000 15133637 955859216 1373700096 0.9501691461 0.0974125415 0.3323348165 194 7.7200000000 0.0041376455 0.0029644569 0.0043770042 0.0051466076 0.0034500000 15135613 955859216 1373700096 0.9535802603 0.0998515263 0.3411544263 195 7.7600000000 0.0040798164 0.0029701767 0.0043770042 0.0051334697 0.0035500000 15137589 955859216 1373700096 0.9582448602 0.1014451459 0.3597784340 196 7.8000000000 0.0043934258 0.0029774382 0.0043934258 0.0051262855 0.0033750000 15139565 955859216 1373700096 0.9589124322 0.1004572734 0.3683713078 197 7.8400000000 0.0043789502 0.0029845525 0.0043934258 0.0051143912 0.0034450000 15141541 955859216 1373700096 0.9614896178 0.1012536511 0.3785665631 198 7.8800000000 0.0044606719 0.0029920076 0.0044606719 0.0051015178 0.0019560000 15143517 955859216 1373700096 0.9636344910 0.1019272655 0.3895081580 199 7.9200000000 0.0045275493 0.0029997239 0.0045275493 0.0050962336 0.0034650000 15145493 955859216 1373700096 0.9638304114 0.1010717899 0.3995310664 200 7.9600000000 0.0045432043 0.0030074413 0.0045432043 0.0050853879 0.0035070000 15147469 955859216 1373700096 0.9659834504 0.1019134521 0.4104941785 201 8.0000000000 0.0041751964 0.0030132510 0.0045432043 0.0050738737 0.0035920000 15149445 955859216 1373700096 0.9679723978 0.1017087549 0.4221357107 202 8.0400000000 0.0041680289 0.0030189677 0.0045432043 0.0050620150 0.0035120000 15151421 955859216 1373700096 0.9677104950 0.1020552590 0.4324498177 203 8.0800000000 0.0041798120 0.0030246862 0.0045432043 0.0050497950 0.0035660000 15153397 955859216 1373700096 0.9675599933 0.1023613811 0.4431173503 204 8.1200000000 0.0041678050 0.0030302897 0.0045432043 0.0050405350 0.0036030000 15155373 955859216 1373700096 0.9676922560 0.1037681922 0.4538117945 205 8.1600000000 0.0041970713 0.0030359813 0.0045432043 0.0050519462 0.0036330000 15157349 955859216 1373700096 0.9688394070 0.1055854633 0.4655438066 206 8.1999999990 0.0042050895 0.0030416566 0.0045432043 0.0050589821 0.0036320000 15159325 955859216 1373700096 0.9694947600 0.1077167690 0.4777216017 207 8.2400000000 0.0042200694 0.0030473494 0.0045432043 0.0050547167 0.0036360000 15161301 955859216 1373700096 0.9703765512 0.1101007387 0.4905225337 208 8.2799999990 0.0042111101 0.0030529444 0.0045432043 0.0050553708 0.0036550000 15163277 955859216 1373700096 0.9700441360 0.1131578982 0.5022637844 209 8.3200000000 0.0046618260 0.0030606424 0.0046618260 0.0050506413 0.0035030000 15165253 955859216 1373700096 0.9706506133 0.1147719696 0.5137540698 210 8.3599999990 0.0042568231 0.0030663385 0.0046618260 0.0050391471 0.0036710000 15167229 955859216 1373700096 0.9709014893 0.1162333935 0.5259973407 211 8.4000000000 0.0042373161 0.0030718882 0.0046618260 0.0050352582 0.0036510000 15169205 955859216 1373700096 0.9713281989 0.1183467060 0.5383750796 212 8.4399999990 0.0042465618 0.0030774291 0.0046618260 0.0050283458 0.0038350000 15171181 955859216 1373700096 0.9703918099 0.1200970113 0.5507365465 213 8.4800000000 0.0042370139 0.0030828732 0.0046618260 0.0050204298 0.0036960000 15173157 955859216 1373700096 0.9691133499 0.1220737472 0.5622587800 214 8.5200000000 0.0042271265 0.0030882201 0.0046618260 0.0050161109 0.0037220000 15175133 955859216 1373700096 0.9683818817 0.1242493764 0.5735818148 215 8.5600000000 0.0042382060 0.0030935689 0.0046618260 0.0050070481 0.0036580000 15177109 955859216 1373700096 0.9685341716 0.1274905205 0.5857299566 216 8.6000000000 0.0042169890 0.0030987699 0.0046618260 0.0049985207 0.0036630000 15179085 955859216 1373700096 0.9691792727 0.1297159046 0.5980830193 217 8.6400000000 0.0042139958 0.0031039092 0.0046618260 0.0049918724 0.0037570000 15181061 955859216 1373700096 0.9680481553 0.1313058734 0.6089751720 218 8.6800000000 0.0042040944 0.0031089559 0.0046618260 0.0049865576 0.0037260000 15183037 955859216 1373700096 0.9663563967 0.1328136176 0.6196578741 219 8.7200000000 0.0042001279 0.0031139385 0.0046618260 0.0049798027 0.0037540000 15185013 955859216 1373700096 0.9635782242 0.1338605136 0.6299901605 220 8.7600000000 0.0042044776 0.0031188955 0.0046618260 0.0049702029 0.0037550000 15186989 955859216 1373700096 0.9602552652 0.1341734231 0.6395637393 221 8.8000000000 0.0042024856 0.0031237986 0.0046618260 0.0049593683 0.0037950000 15188965 955859216 1373700096 0.9606028795 0.1365011036 0.6516454220 222 8.8400000000 0.0041979705 0.0031286372 0.0046618260 0.0049502969 0.0038090000 15190941 955859216 1373700096 0.9590035677 0.1371927261 0.6623870730 223 8.8800000000 0.0046078023 0.0031352702 0.0046618260 0.0049392931 0.0036820000 15192917 955859216 1373700096 0.9566818476 0.1372302473 0.6717602015 224 8.9200000000 0.0042000739 0.0031400238 0.0046618260 0.0049289230 0.0038280000 15194893 955859216 1373700096 0.9545917511 0.1377553940 0.6823695302 225 8.9600000000 0.0044153272 0.0031456918 0.0046618260 0.0049217236 0.0037110000 15196869 955859216 1373700096 0.9545940161 0.1394009143 0.6935749650 226 9.0000000000 0.0041879988 0.0031503038 0.0046618260 0.0049112143 0.0038260000 15198845 955859216 1373700096 0.9553800821 0.1416848302 0.7155848145 227 9.0400000000 0.0044419309 0.0031559938 0.0046618260 0.0049003448 0.0036770000 15200821 955859216 1373700096 0.9558749795 0.1438736469 0.7261660099 228 9.0800000000 0.0044842288 0.0031618194 0.0046618260 0.0048911986 0.0036690000 15202797 955859216 1373700096 0.9534795284 0.1454435736 0.7352024317 229 9.1200000000 0.0044474048 0.0031674333 0.0046618260 0.0049027495 0.0037640000 15204773 955859216 1373700096 0.9536886811 0.1471925676 0.7463663220 230 9.1600000000 0.0043836869 0.0031727213 0.0046618260 0.0048997612 0.0036640000 15206749 955859216 1373700096 0.9543188214 0.1485605091 0.7566072941 231 9.2000000000 0.0041989814 0.0031771640 0.0046618260 0.0048952458 0.0038490000 15208725 955859216 1373700096 0.9534538388 0.1498531699 0.7753717899 232 9.2400000000 0.0043781484 0.0031823407 0.0046618260 0.0048880444 0.0037480000 15210701 955859216 1373700096 0.9543061852 0.1523669958 0.7872423530 233 9.2800000000 0.0043354337 0.0031872896 0.0046618260 0.0048890685 0.0036960000 15212677 955859216 1373700096 0.9550212622 0.1549234539 0.7993100882 234 9.3200000000 0.0043176496 0.0031921202 0.0046618260 0.0048881206 0.0037460000 15214653 955859216 1373700096 0.9540681243 0.1575965881 0.8100970984 235 9.3600000000 0.0042677643 0.0031966974 0.0046618260 0.0048862842 0.0037740000 15216629 955859216 1373700096 0.9539072514 0.1588313431 0.8209329247 236 9.4000000000 0.0042342371 0.0032010937 0.0046618260 0.0048811238 0.0037780000 15218605 955859216 1373700096 0.9553351998 0.1595763266 0.8304858804 237 9.4400000000 0.0043128938 0.0032057849 0.0046618260 0.0048886792 0.0038200000 15220581 955859216 1373700096 0.9561997652 0.1621404886 0.8414770961 238 9.4800000000 0.0043274979 0.0032104980 0.0046618260 0.0048868526 0.0037950000 15222557 955859216 1373700096 0.9569765329 0.1637906134 0.8522639275 239 9.5200000000 0.0042854901 0.0032149958 0.0046618260 0.0048931627 0.0037700000 15224533 955859216 1373700096 0.9587777257 0.1659759581 0.8630329967 240 9.5600000000 0.0043465467 0.0032197106 0.0046618260 0.0048908173 0.0039190000 15226509 955859216 1373700096 0.9585555792 0.1668709964 0.8725409508 241 9.6000000000 0.0043198066 0.0032242753 0.0046618260 0.0048806848 0.0038230000 15228485 955859216 1373700096 0.9568125606 0.1683219820 0.8822745681 242 9.6400000000 0.0041552596 0.0032281224 0.0046618260 0.0048831699 0.0038930000 15230461 955859216 1373700096 0.9578154683 0.1708487123 0.8945570588 243 9.6800000000 0.0042374139 0.0032322759 0.0046618260 0.0048739770 0.0037390000 15232437 955859216 1373700096 0.9609361291 0.1731749773 0.9081110954 244 9.7200000000 0.0042317193 0.0032363719 0.0046618260 0.0048639418 0.0037260000 15234413 955859216 1373700096 0.9622867703 0.1769256592 0.9201576114 245 9.7600000000 0.0042106356 0.0032403485 0.0046618260 0.0048561149 0.0037820000 15236389 955859216 1373700096 0.9621855617 0.1777542531 0.9298173189 246 9.8000000000 0.0041842512 0.0032441855 0.0046618260 0.0048462045 0.0037370000 15238365 955859216 1373700096 0.9638456106 0.1804563701 0.9415075779 247 9.8400000000 0.0042227018 0.0032481471 0.0046618260 0.0048365548 0.0037620000 15240341 955859216 1373700096 0.9640698433 0.1831547916 0.9531754851 248 9.8800000000 0.0041417493 0.0032517504 0.0046618260 0.0048309781 0.0037770000 15242317 955859216 1373700096 0.9639049172 0.1862800121 0.9632902145 249 9.9200000000 0.0041633765 0.0032554115 0.0046618260 0.0048212735 0.0037570000 15244293 955859216 1373700096 0.9653387666 0.1874431819 0.9740383029 250 9.9600000000 0.0041705188 0.0032590719 0.0046618260 0.0048120385 0.0038280000 15246269 955859216 1373700096 0.9658888578 0.1893204898 0.9848721027 251 10.0000000000 0.0041316766 0.0032625485 0.0046618260 0.0048040943 0.0038210000 15248245 955859216 1373700096 0.9653742909 0.1901278794 0.9940530062 252 10.0400000000 0.0040382501 0.0032656266 0.0046618260 0.0047945447 0.0038750000 15250221 955859216 1373700096 0.9657982588 0.1917238235 1.0036591291 253 10.0800000000 0.0040198048 0.0032686076 0.0046618260 0.0047857057 0.0038290000 15252197 955859216 1373700096 0.9659854174 0.1935121715 1.0130714178 254 10.1200000000 0.0039757672 0.0032713917 0.0046618260 0.0047802916 0.0039360000 15254173 955859216 1373700096 0.9662688971 0.1954892129 1.0223947763 255 10.1600000000 0.0039614798 0.0032740979 0.0046618260 0.0047712248 0.0037500000 15256149 955859216 1373700096 0.9655780792 0.1972502917 1.0315634012 256 10.2000000000 0.0040360368 0.0032770742 0.0046618260 0.0047709587 0.0036560000 15258125 955859216 1373700096 0.9646804333 0.1978755742 1.0389465094 257 10.2400000000 0.0038605556 0.0032793446 0.0046618260 0.0047840437 0.0039280000 15284677 955859216 1373700096 0.9635508657 0.1997120380 1.0480244160 258 10.2800000000 0.0038308878 0.0032814823 0.0046618260 0.0047854124 0.0038760000 15337853 955859216 1373700096 0.9637630582 0.2015271336 1.0576406717 259 10.3200000000 0.0041180956 0.0032847125 0.0046618260 0.0047930662 0.0037260000 15339829 955859216 1373700096 0.9634038806 0.2025087029 1.0652735233 260 10.3600000000 0.0042317621 0.0032883550 0.0046618260 0.0047998017 0.0037370000 15341805 955859216 1373700096 0.9613468051 0.2032883167 1.0727226734 261 10.4000000000 0.0038126777 0.0032903639 0.0046618260 0.0047921655 0.0039820000 15343781 955859216 1373700096 0.9594054818 0.2059837729 1.0828608274 262 10.4400000000 0.0038189113 0.0032923813 0.0046618260 0.0047830170 0.0037700000 15345757 955859216 1373700096 0.9602935910 0.2073254585 1.0920022726 263 10.4800000000 0.0038608194 0.0032945426 0.0046618260 0.0047739100 0.0037730000 15347733 955859216 1373700096 0.9598176479 0.2089958489 1.1015913486 264 10.5200000000 0.0039951908 0.0032971966 0.0046618260 0.0047673851 0.0036760000 15349709 955859216 1373700096 0.9582288265 0.2096355855 1.1093379259 265 10.5600000000 0.0038799220 0.0032993956 0.0046618260 0.0047599731 0.0036640000 15351685 955859216 1373700096 0.9567782879 0.2098312825 1.1168739796 266 10.6000000000 0.0037973516 0.0033012676 0.0046618260 0.0047514808 0.0037700000 15353661 955859216 1373700096 0.9573988914 0.2108978778 1.1256489754 267 10.6400000000 0.0038366362 0.0033032727 0.0046618260 0.0047444784 0.0037620000 15355637 955859216 1373700096 0.9566211104 0.2122505158 1.1342726946 268 10.6800000000 0.0038455587 0.0033052962 0.0046618260 0.0047382741 0.0037590000 15357613 955859216 1373700096 0.9554844499 0.2143599987 1.1436570883 269 10.7200000000 0.0038451378 0.0033073030 0.0046618260 0.0047343337 0.0037410000 15359589 955859216 1373700096 0.9537615180 0.2151438445 1.1528594494 270 10.7600000000 0.0038409424 0.0033092794 0.0046618260 0.0047282607 0.0037060000 15361565 955859216 1373700096 0.9517254829 0.2175366282 1.1619731188 271 10.8000000000 0.0038732381 0.0033113605 0.0046618260 0.0047211453 0.0037560000 15363541 955859216 1373700096 0.9496396184 0.2194887251 1.1719139814 272 10.8400000000 0.0038804689 0.0033134528 0.0046618260 0.0047124271 0.0037520000 15365517 955859216 1373700096 0.9468334913 0.2213562131 1.1811529398 273 10.8800000000 0.0051459256 0.0033201651 0.0051459256 0.0047062164 0.0036440000 15367493 955859216 1373700096 0.9439647198 0.2226425409 1.1893266439 274 10.9200000000 0.0036900698 0.0033215152 0.0051459256 0.0046982782 0.0038800000 15369469 955859216 1373700096 0.9413458705 0.2238241434 1.2006156445 275 10.9600000000 0.0038874401 0.0033235731 0.0051459256 0.0046924144 0.0038200000 15371445 955859216 1373700096 0.9389412999 0.2275515944 1.2101093531 276 11.0000000000 0.0053613265 0.0033309562 0.0053613265 0.0046894552 0.0036520000 15373421 955859216 1373700096 0.9363387227 0.2278041095 1.2171204090 277 11.0400000000 0.0037071253 0.0033323142 0.0053613265 0.0046828927 0.0039080000 15375397 955859216 1373700096 0.9347801805 0.2289176583 1.2293058634 278 11.0800000000 0.0037248568 0.0033337263 0.0053613265 0.0046744327 0.0039180000 15377373 955859216 1373700096 0.9297103286 0.2300214171 1.2382456064 279 11.1200000000 0.0056575397 0.0033420553 0.0056575397 0.0046671866 0.0036610000 15379349 955859216 1373700096 0.9264097810 0.2313165218 1.2464089394 280 11.1600000000 0.0037198188 0.0033434045 0.0056575397 0.0046614720 0.0039240000 15381325 955859216 1373700096 0.9224774837 0.2325994968 1.2582838535 281 11.2000000000 0.0037375924 0.0033448073 0.0056575397 0.0046533917 0.0038960000 15383301 955859216 1373700096 0.9203997850 0.2363737971 1.2677288055 282 11.2400000000 0.0037401842 0.0033462093 0.0056575397 0.0046457826 0.0039630000 15385277 955859216 1373700096 0.9169620872 0.2374358624 1.2764232159 283 11.2800000000 0.0037231748 0.0033475414 0.0056575397 0.0046384369 0.0038780000 15387253 955859216 1373700096 0.9137881994 0.2405846864 1.2859896421 284 11.3200000000 0.0037386429 0.0033489185 0.0056575397 0.0046311937 0.0039020000 15389229 955859216 1373700096 0.9088159800 0.2432459146 1.2969818115 285 11.3600000000 0.0055773822 0.0033567377 0.0056575397 0.0046271424 0.0037160000 15391205 955859216 1373700096 0.9054298997 0.2450728565 1.3048440218 286 11.4000000000 0.0037045460 0.0033579538 0.0056575397 0.0046270072 0.0038820000 15393181 955859216 1373700096 0.9052879214 0.2473011613 1.3163769245 287 11.4400000000 0.0037321651 0.0033592577 0.0056575397 0.0046197669 0.0039040000 15395157 955859216 1373700096 0.9028007388 0.2507134974 1.3253663778 288 11.4800000000 0.0037390708 0.0033605764 0.0056575397 0.0046118556 0.0039230000 15397133 955859216 1373700096 0.8957404494 0.2516784668 1.3321036100 289 11.5200000000 0.0056369831 0.0033684533 0.0056575397 0.0046095850 0.0036790000 15399109 955859216 1373700096 0.8914681673 0.2516764402 1.3384306431 290 11.5600000000 0.0037368457 0.0033697236 0.0056575397 0.0046074128 0.0039210000 15401085 955859216 1373700096 0.8872696161 0.2512073517 1.3482226133 291 11.6000000000 0.0038726206 0.0033714518 0.0056575397 0.0045997015 0.0037810000 15403061 955859216 1373700096 0.8849740624 0.2537877560 1.3565242290 292 11.6400000000 0.0052445857 0.0033778666 0.0056575397 0.0045928286 0.0036900000 15405037 955859216 1373700096 0.8829110861 0.2552917898 1.3635170460 293 11.6800000000 0.0050069033 0.0033834265 0.0056575397 0.0045853105 0.0037300000 15407013 955859216 1373700096 0.8811865449 0.2570241988 1.3700989485 294 11.7200000000 0.0055357111 0.0033907472 0.0056575397 0.0045820088 0.0036810000 15408989 955859216 1373700096 0.8773989081 0.2568529546 1.3764550686 295 11.7600000000 0.0039018476 0.0033924797 0.0056575397 0.0045887785 0.0038180000 15410965 955859216 1373700096 0.8749071956 0.2564648986 1.3850365877 296 11.8000000000 0.0045886785 0.0033965209 0.0056575397 0.0046021426 0.0037270000 15412941 955859216 1373700096 0.8729909062 0.2573004961 1.3923354149 297 11.8400000000 0.0048921839 0.0034015568 0.0056575397 0.0046287837 0.0037140000 15414917 955859216 1373700096 0.8689270020 0.2573762834 1.3994659185 298 11.8800000000 0.0037329393 0.0034026688 0.0056575397 0.0046465918 0.0043670000 15416893 955859216 1373700096 0.8651292920 0.2563785911 1.4089020491 299 11.9200000000 0.0035789856 0.0034032585 0.0056575397 0.0046454843 0.0038320000 15418869 955859216 1373700096 0.8631778955 0.2559348941 1.4170833826 300 11.9600000000 0.0035129078 0.0034036240 0.0056575397 0.0046442584 0.0038020000 15420845 955859216 1373700096 0.8613982201 0.2552844882 1.4247363806 301 12.0000000000 0.0035195334 0.0034040091 0.0056575397 0.0046398703 0.0037990000 15422821 955859216 1373700096 0.8605134487 0.2559696138 1.4343149662 302 12.0400000000 0.0034793075 0.0034042584 0.0056575397 0.0046332702 0.0037890000 15424797 955859216 1373700096 0.8598345518 0.2562980354 1.4429672956 303 12.0800000000 0.0034430702 0.0034043865 0.0056575397 0.0046273339 0.0037780000 15426773 955859216 1373700096 0.8577843904 0.2555815876 1.4505280256 304 12.1200000000 0.0034050895 0.0034043888 0.0056575397 0.0046215077 0.0037740000 15428749 955859216 1373700096 0.8566776514 0.2564100325 1.4601287842 305 12.1600000000 0.0034424656 0.0034045137 0.0056575397 0.0046140521 0.0037950000 15430725 955859216 1373700096 0.8557156324 0.2574439645 1.4697704315 306 12.2000000000 0.0033694515 0.0034043991 0.0056575397 0.0046065974 0.0038170000 15432701 955859216 1373700096 0.8530008197 0.2584113479 1.4786485434 307 12.2400000000 0.0032748932 0.0034039773 0.0056575397 0.0046006710 0.0038510000 15434677 955859216 1373700096 0.8509285450 0.2601754069 1.4882551432 308 12.2800000000 0.0032510464 0.0034034807 0.0056575397 0.0045993769 0.0038240000 15436653 955859216 1373700096 0.8498713374 0.2609407604 1.4980002642 309 12.3200000000 0.0032032379 0.0034028327 0.0056575397 0.0045976862 0.0039250000 15438629 955859216 1373700096 0.8484380245 0.2615699768 1.5071312189 310 12.3600000000 0.0031968518 0.0034021682 0.0056575397 0.0046061447 0.0038950000 15440605 955859216 1373700096 0.8474000692 0.2641940117 1.5171314478 311 12.4000000000 0.0032620018 0.0034017175 0.0056575397 0.0046246663 0.0038540000 15442581 955859216 1373700096 0.8461878896 0.2664951086 1.5273451805 312 12.4400000000 0.0029891010 0.0034003951 0.0056575397 0.0046348148 0.0039730000 15444557 955859216 1373700096 0.8451108336 0.2650535703 1.5351039171 313 12.4800000000 0.0030246258 0.0033991945 0.0056575397 0.0046350546 0.0038610000 15446533 955859216 1373700096 0.8440608978 0.2662315965 1.5447069407 314 12.5200000000 0.0030070050 0.0033979455 0.0056575397 0.0046331279 0.0038950000 15448509 955859216 1373700096 0.8424658775 0.2673962116 1.5539258718 315 12.5600000000 0.0028408556 0.0033961770 0.0056575397 0.0046293383 0.0038360000 15450485 955859216 1373700096 0.8411421180 0.2682238817 1.5621170998 316 12.6000000000 0.0027589516 0.0033941604 0.0056575397 0.0046220739 0.0038180000 15452461 955859216 1373700096 0.8420085311 0.2676697671 1.5701241493 317 12.6400000000 0.0027637004 0.0033921716 0.0056575397 0.0046152272 0.0038430000 15454437 955859216 1373700096 0.8413897753 0.2688847482 1.5790885687 318 12.6800000000 0.0028018123 0.0033903151 0.0056575397 0.0046104387 0.0038820000 15456413 955859216 1373700096 0.8411115408 0.2705342472 1.5880634785 319 12.7200000000 0.0026049453 0.0033878532 0.0056575397 0.0046051232 0.0039520000 15458389 955859216 1373700096 0.8384503722 0.2731434405 1.5985716581 320 12.7600000000 0.0027773739 0.0033859454 0.0056575397 0.0046033237 0.0039050000 15460365 955859216 1373700096 0.8361908197 0.2744635344 1.6075208187 321 12.8000000000 0.0027325819 0.0033839100 0.0056575397 0.0046141876 0.0039010000 15462341 955859216 1373700096 0.8342891335 0.2765052617 1.6168457270 322 12.8400000000 0.0026495776 0.0033816295 0.0056575397 0.0046202229 0.0038770000 15464317 955859216 1373700096 0.8330917358 0.2787311375 1.6258537769 323 12.8800000000 0.0026061349 0.0033792286 0.0056575397 0.0046337009 0.0038280000 15466293 955859216 1373700096 0.8319075704 0.2801654041 1.6338018179 324 12.9200000000 0.0025488483 0.0033766657 0.0056575397 0.0046472445 0.0039930000 15468269 955859216 1373700096 0.8307531476 0.2802551091 1.6407630444 325 12.9600000000 0.0025106901 0.0033740011 0.0056575397 0.0046588989 0.0039150000 15470245 955859216 1373700096 0.8304517865 0.2806917727 1.6479589939 326 13.0000000000 0.0025231661 0.0033713912 0.0056575397 0.0046698263 0.0038760000 15472221 955859216 1373700096 0.8294125199 0.2813876271 1.6561144590 327 13.0400000000 0.0025190432 0.0033687846 0.0056575397 0.0047737586 0.0041390000 15474197 955859216 1373700096 0.8258096576 0.2859463692 1.6756542921 328 13.0800000000 0.0025113623 0.0033661705 0.0056575397 0.0047939127 0.0040300000 15476173 955859216 1373700096 0.8239790797 0.2865805924 1.6835197210 329 13.1200000000 0.0025038489 0.0033635495 0.0056575397 0.0047985710 0.0039740000 15478149 955859216 1373700096 0.8217747211 0.2875453532 1.6914577484 330 13.1600000000 0.0025101160 0.0033609633 0.0056575397 0.0047981877 0.0041010000 15480125 955859216 1373700096 0.8205163479 0.2878395021 1.6987141371 331 13.2000000000 0.0025112589 0.0033583962 0.0056575397 0.0047986725 0.0040270000 15482101 955859216 1373700096 0.8197338581 0.2877735794 1.7054549456 332 13.2400000000 0.0024911033 0.0033557839 0.0056575397 0.0047946770 0.0040590000 15484077 955859216 1373700096 0.8186213374 0.2892008722 1.7131378651 333 13.2800000000 0.0024349533 0.0033530187 0.0056575397 0.0047911670 0.0040410000 15486053 955859216 1373700096 0.8175802231 0.2906500697 1.7206442356 334 13.3200000000 0.0024155772 0.0033502119 0.0056575397 0.0047911580 0.0040400000 15488029 955859216 1373700096 0.8169925213 0.2907818854 1.7266978025 335 13.3600000000 0.0024100689 0.0033474056 0.0056575397 0.0047989509 0.0041120000 15490005 955859216 1373700096 0.8148130774 0.2936095893 1.7354167700 336 13.4000000000 0.0024208694 0.0033446480 0.0056575397 0.0048082208 0.0041340000 15491981 955859216 1373700096 0.8125219941 0.2944783568 1.7415773869 337 13.4400000000 0.0024264283 0.0033419233 0.0056575397 0.0048258328 0.0041030000 15493957 955859216 1373700096 0.8109740019 0.2937357426 1.7466907501 338 13.4800000000 0.0024356903 0.0033392422 0.0056575397 0.0048525853 0.0040560000 15495933 955859216 1373700096 0.8075325489 0.2937926650 1.7521319389 339 13.5200000000 0.0024519854 0.0033366249 0.0056575397 0.0048739980 0.0040440000 15497909 955859216 1373700096 0.8056460619 0.2954342067 1.7597235441 340 13.5600000000 0.0024459974 0.0033340054 0.0056575397 0.0048940159 0.0041080000 15499885 955859216 1373700096 0.8011501431 0.2956185341 1.7654243708 341 13.6000000000 0.0024450847 0.0033313986 0.0056575397 0.0049070592 0.0040630000 15501861 955859216 1373700096 0.7974557877 0.2966541052 1.7726939917 342 13.6400000000 0.0024528918 0.0033288298 0.0056575397 0.0049151356 0.0041790000 15503837 955859216 1373700096 0.7938176990 0.2988542914 1.7808090448 343 13.6800000000 0.0024511879 0.0033262711 0.0056575397 0.0049277949 0.0041170000 15505813 955859216 1373700096 0.7895017862 0.3022540808 1.7892395258 344 13.7200000000 0.0024591996 0.0033237506 0.0056575397 0.0049311775 0.0041680000 15507789 955859216 1373700096 0.7855339646 0.3041921556 1.7950887680 345 13.7600000000 0.0024416898 0.0033211939 0.0056575397 0.0049321722 0.0042000000 15509765 955859216 1373700096 0.7838935256 0.3032144606 1.7997553349 346 13.8000000000 0.0012147208 0.0033151058 0.0056575397 0.0049316669 0.0039170000 15511741 955859216 1373700096 0.7796062827 0.3034736812 1.8037047386 347 13.8400000000 0.0024217574 0.0033125313 0.0056575397 0.0049413773 0.0042240000 15513717 955859216 1373700096 0.7774214745 0.3029017448 1.8094696999 348 13.8800000000 0.0024108468 0.0033099403 0.0056575397 0.0049538378 0.0041670000 15515693 955859216 1373700096 0.7728144526 0.3033631742 1.8161374331 349 13.9200000000 0.0024163225 0.0033073797 0.0056575397 0.0049631920 0.0042270000 15517669 955859216 1373700096 0.7666391134 0.3038042486 1.8235031366 350 13.9600000000 0.0023836212 0.0033047404 0.0056575397 0.0049725073 0.0041740000 15519645 955859216 1373700096 0.7607046366 0.3050262034 1.8311327696 351 14.0000000000 0.0023801289 0.0033021062 0.0056575397 0.0049754331 0.0042000000 15521621 955859216 1373700096 0.7552691102 0.3066248298 1.8376070261 352 14.0400000000 0.0015308842 0.0032970743 0.0056575397 0.0049706299 0.0040780000 15523597 955859216 1373700096 0.7481704950 0.3064692020 1.8412910700 353 14.0800000000 0.0023194954 0.0032943050 0.0056575397 0.0049740978 0.0042230000 15525573 955859216 1373700096 0.7453199029 0.3051978946 1.8467596769 354 14.1200000000 0.0023053533 0.0032915113 0.0056575397 0.0049753770 0.0043420000 15527549 955859216 1373700096 0.7392874956 0.3074637353 1.8558493853 355 14.1600000000 0.0011430182 0.0032854592 0.0056575397 0.0049730696 0.0040110000 15529525 955859216 1373700096 0.7319069505 0.3081917167 1.8607583046 356 14.2000000000 0.0023121738 0.0032827253 0.0056575397 0.0049970276 0.0042540000 15531501 955859216 1373700096 0.7271590829 0.3083356023 1.8653836250 357 14.2400000000 0.0023308168 0.0032800589 0.0056575397 0.0049939067 0.0043110000 15533477 955859216 1373700096 0.7196379900 0.3095995784 1.8717701435 358 14.2800000000 0.0023413915 0.0032774369 0.0056575397 0.0049875739 0.0042890000 15535453 955859216 1373700096 0.7141900659 0.3098069727 1.8773183823 359 14.3200000000 0.0023298499 0.0032747974 0.0056575397 0.0049811821 0.0042360000 15537429 955859216 1373700096 0.7052029967 0.3133822381 1.8848892450 360 14.3600000000 0.0023166344 0.0032721358 0.0056575397 0.0049818237 0.0044930000 15539405 955859216 1373700096 0.6892498732 0.3165500164 1.8968070745 361 14.4000000000 0.0023254447 0.0032695134 0.0056575397 0.0049761641 0.0043820000 15541381 955859216 1373700096 0.6793313622 0.3214745522 1.9054640532 362 14.4400000000 0.0023187294 0.0032668869 0.0056575397 0.0049713494 0.0032100000 15543357 955859216 1373700096 0.6624124646 0.3207996190 1.9117275476 363 14.4800000000 0.0020826382 0.0032636246 0.0056575397 0.0049658086 0.0039950000 15545333 955859216 1373700096 0.6564365625 0.3195237815 1.9156541824 364 14.5200000000 0.0028617147 0.0032625204 0.0056575397 0.0049669940 0.0041360000 15547309 955859216 1373700096 0.6498538256 0.3190869093 1.9218246937 365 14.5600000000 0.0031929442 0.0032623298 0.0056575397 0.0049604606 0.0040880000 15549285 955859216 1373700096 0.6418653727 0.3191460967 1.9270331860 366 14.6000000000 0.0023496186 0.0032598360 0.0056575397 0.0049769898 0.0044820000 15551261 955859216 1373700096 0.6241449118 0.3265477121 1.9414778948 367 14.6400000000 0.0026619118 0.0032582068 0.0056575397 0.0049721178 0.0041120000 15553237 955859216 1373700096 0.6148379445 0.3303442895 1.9466239214 368 14.6800000000 0.0021306970 0.0032551429 0.0056575397 0.0049793791 0.0039890000 15555213 955859216 1373700096 0.6051689386 0.3311396241 1.9505850077 369 14.7200000000 0.0025514271 0.0032532358 0.0056575397 0.0049878531 0.0040180000 15557189 955859216 1373700096 0.5958464146 0.3304784000 1.9520047903 370 14.7600000000 0.0023904867 0.0032509041 0.0056575397 0.0049811059 0.0039920000 15559165 955859216 1373700096 0.5879065394 0.3288690448 1.9535138607 371 14.8000000000 0.0023825429 0.0032485635 0.0056575397 0.0049980640 0.0040670000 15561141 955859216 1373700096 0.5795949101 0.3289550543 1.9601691961 372 14.8400000000 0.0027737741 0.0032472872 0.0056575397 0.0050133620 0.0040160000 15563117 955859216 1373700096 0.5711749196 0.3308471441 1.9653935432 373 14.8800000000 0.0030767974 0.0032468301 0.0056575397 0.0050171634 0.0040560000 15565093 955859216 1373700096 0.5615625978 0.3323310316 1.9700739384 374 14.9200000000 0.0031265644 0.0032465085 0.0056575397 0.0050130402 0.0039940000 15567069 955859216 1373700096 0.5503418446 0.3333152831 1.9734174013 375 14.9600000000 0.0027264305 0.0032451217 0.0056575397 0.0050226652 0.0039610000 15569045 955859216 1373700096 0.5394231081 0.3334162533 1.9746208191 376 15.0000000000 0.0026387353 0.0032435089 0.0056575397 0.0050161094 0.0040470000 15571021 955859216 1373700096 0.5302352309 0.3327955902 1.9797931910 377 15.0400000000 0.0031926688 0.0032433741 0.0056575397 0.0050106073 0.0040370000 15572997 955859216 1373700096 0.5098701715 0.3332604468 1.9868074656 378 15.0800000000 0.0028193903 0.0032422524 0.0056575397 0.0050051638 0.0040480000 15574973 955859216 1373700096 0.5004107356 0.3340924382 1.9905639887 379 15.1200000000 0.0025289997 0.0032403705 0.0056575397 0.0049990553 0.0039540000 15576949 955859216 1373700096 0.4925275147 0.3339020908 1.9934563637 380 15.1600000000 0.0024164126 0.0032382022 0.0056575397 0.0049958931 0.0041390000 15578925 955859216 1373700096 0.4848933518 0.3327654004 1.9971427917 381 15.2000000000 0.0023839637 0.0032359601 0.0056575397 0.0050082934 0.0041610000 15580901 955859216 1373700096 0.4766820967 0.3341649473 2.0033423901 382 15.2400000000 0.0023071135 0.0032335285 0.0056575397 0.0050182843 0.0039430000 15582877 955859216 1373700096 0.4660640657 0.3342390358 2.0043528080 383 15.2800000000 0.0022750509 0.0032310260 0.0056575397 0.0050308078 0.0039400000 15584853 955859216 1373700096 0.4574896395 0.3340113461 2.0065672398 384 15.3200000000 0.0023432449 0.0032287141 0.0056575397 0.0050407271 0.0042500000 15586829 955859216 1373700096 0.4492045939 0.3348091245 2.0122487545 385 15.3600000000 0.0023260908 0.0032263696 0.0056575397 0.0050438398 0.0039380000 15588805 955859216 1373700096 0.4408504963 0.3353979290 2.0145869255 386 15.4000000000 0.0023218847 0.0032240264 0.0056575397 0.0050404674 0.0041520000 15590781 955859216 1373700096 0.4338940680 0.3350138962 2.0181181431 387 15.4400000000 0.0023241935 0.0032217012 0.0056575397 0.0050440863 0.0041770000 15592757 955859216 1373700096 0.4274950624 0.3357631266 2.0220072269 388 15.4800000000 0.0023894135 0.0032195561 0.0056575397 0.0050484932 0.0039700000 15594733 955859216 1373700096 0.4210430384 0.3366498649 2.0250182152 389 15.5200000000 0.0023252855 0.0032172572 0.0056575397 0.0050531983 0.0041990000 15596709 955859216 1373700096 0.4131292403 0.3377664685 2.0297152996 390 15.5600000000 0.0024304725 0.0032152398 0.0056575397 0.0050657451 0.0039860000 15598685 955859216 1373700096 0.4049297571 0.3384615183 2.0322229862 391 15.6000000000 0.0023311351 0.0032129787 0.0056575397 0.0050636722 0.0019020000 15600661 955859216 1373700096 0.3983802497 0.3383725584 2.0362353325 392 15.6400000000 0.0023320715 0.0032107315 0.0056575397 0.0050700448 0.0018990000 15602637 955859216 1373700096 0.3916313648 0.3390806615 2.0411243439 393 15.6800000000 0.0024511064 0.0032087986 0.0056575397 0.0050660536 0.0017920000 15604613 955859216 1373700096 0.3846144676 0.3392243087 2.0434043407 394 15.7200000000 0.0023723075 0.0032066755 0.0056575397 0.0050635987 0.0020950000 15606589 955859216 1373700096 0.3783061802 0.3390134871 2.0473475456 395 15.7600000000 0.0023871087 0.0032046007 0.0056575397 0.0050636764 0.0043130000 15608565 955859216 1373700096 0.3717760742 0.3397095799 2.0535166264 396 15.8000000000 0.0024195341 0.0032026182 0.0056575397 0.0050610217 0.0043750000 15610541 955859216 1373700096 0.3646300733 0.3413845301 2.0586421490 397 15.8400000000 0.0026143785 0.0032011365 0.0056575397 0.0050603687 0.0040780000 15612517 955859216 1373700096 0.3581655622 0.3413213193 2.0606439114 398 15.8800000000 0.0024699860 0.0031992994 0.0056575397 0.0050557980 0.0042610000 15614493 955859216 1373700096 0.3533359468 0.3411871791 2.0684051514 399 15.9200000000 0.0025687604 0.0031977191 0.0056575397 0.0050592672 0.0041750000 15616469 955859216 1373700096 0.3451678157 0.3431831002 2.0715475082 400 15.9600000000 0.0025401060 0.0031960751 0.0056575397 0.0050564562 0.0043860000 15618445 955859216 1373700096 0.3401267529 0.3416477442 2.0753891468 401 16.0000000000 0.0025628412 0.0031944960 0.0056575397 0.0050532043 0.0041390000 15620421 955859216 1373700096 0.3341434598 0.3409949839 2.0790469646 402 16.0400000000 0.0026348685 0.0031931038 0.0056575397 0.0050557659 0.0044360000 15622397 955859216 1373700096 0.3285625577 0.3413215280 2.0865287781 403 16.0800000000 0.0026915486 0.0031918593 0.0056575397 0.0050520789 0.0042740000 15624373 955859216 1373700096 0.3224473894 0.3419588506 2.0925948620 404 16.1200000000 0.0027476298 0.0031907597 0.0056575397 0.0050476587 0.0041670000 15626349 955859216 1373700096 0.3153225780 0.3419797719 2.0965762138 405 16.1600000000 0.0027981161 0.0031897902 0.0056575397 0.0050437148 0.0044100000 15628325 955859216 1373700096 0.3101932108 0.3408159912 2.1011762619 406 16.2000000000 0.0028639464 0.0031889877 0.0056575397 0.0050531944 0.0044270000 15630301 955859216 1373700096 0.3040079772 0.3418307006 2.1096804142 407 16.2400000000 0.0029374030 0.0031883695 0.0056575397 0.0050559139 0.0043730000 15632277 955859216 1373700096 0.2965185046 0.3439194560 2.1151108742 408 16.2800000000 0.0029901147 0.0031878836 0.0056575397 0.0050601550 0.0045790000 15634253 955859216 1373700096 0.2911570668 0.3444127738 2.1197257042 409 16.3200000000 0.0029054724 0.0031871931 0.0056575397 0.0050661410 0.0048160000 15636229 955859216 1373700096 0.2840703130 0.3454304636 2.1265685558 410 16.3600000000 0.0028098479 0.0031862727 0.0056575397 0.0050644947 0.0046430000 15638205 955859216 1373700096 0.2786705196 0.3459703922 2.1305077076 411 16.3999999990 0.0024389245 0.0031844544 0.0056575397 0.0050615797 0.0044630000 15640181 955859216 1373700096 0.2722305655 0.3462516665 2.1337745190 412 16.4400000000 0.0020675533 0.0031817435 0.0056575397 0.0050596689 0.0045480000 15642157 955859216 1373700096 0.2660304308 0.3462020457 2.1391050816 413 16.4800000000 0.0018439735 0.0031785043 0.0056575397 0.0050703073 0.0046200000 15644133 955859216 1373700096 0.2595536411 0.3475626707 2.1462728977 414 16.5200000000 0.0017894561 0.0031751491 0.0056575397 0.0050772593 0.0046780000 15646109 955859216 1373700096 0.2529048920 0.3491767943 2.1516051292 415 16.5599999990 0.0019633509 0.0031722291 0.0056575397 0.0050915961 0.0046690000 15648085 955859216 1373700096 0.2466259003 0.3514911234 2.1582875252 416 16.6000000000 0.0022858335 0.0031700984 0.0056575397 0.0050937545 0.0047130000 15650061 955859216 1373700096 0.2412657142 0.3527740240 2.1622667313 417 16.6400000000 0.0021983769 0.0031677681 0.0056575397 0.0050972119 0.0047810000 15652037 955859216 1373700096 0.2361484766 0.3533643484 2.1660487652 418 16.6800000000 0.0024967552 0.0031661628 0.0056575397 0.0051119364 0.0047920000 15654013 955859216 1373700096 0.2252230048 0.3551306129 2.1751115322 419 16.7199999990 0.0024833393 0.0031645331 0.0056575397 0.0051187951 0.0048070000 15655989 955859216 1373700096 0.2190459520 0.3567985296 2.1815071106 420 16.7600000000 0.0020576406 0.0031618977 0.0056575397 0.0051272098 0.0046780000 15657965 955859216 1373700096 0.2126148343 0.3587339818 2.1873774529 421 16.8000000000 0.0014803809 0.0031579036 0.0056575397 0.0051337079 0.0046160000 15659941 955859216 1373700096 0.2064449638 0.3595244884 2.1924812794 422 16.8400000000 0.0013939897 0.0031537237 0.0056575397 0.0051424356 0.0046740000 15661917 955859216 1373700096 0.2006628215 0.3596879840 2.1972200871 423 16.8799999990 0.0015130002 0.0031498449 0.0056575397 0.0051571875 0.0046620000 15663893 955859216 1373700096 0.1955831051 0.3595340550 2.2024497986 424 16.9200000000 0.0015975117 0.0031461838 0.0056575397 0.0052393843 0.0046770000 15665869 955859216 1373700096 0.1836064905 0.3612916172 2.2121014595 425 16.9600000000 0.0018052589 0.0031430286 0.0056575397 0.0052472179 0.0046690000 15667845 955859216 1373700096 0.1787542254 0.3620081842 2.2156317234 426 17.0000000000 0.0018104815 0.0031399006 0.0056575397 0.0052675604 0.0046850000 15669821 955859216 1373700096 0.1731668264 0.3635324538 2.2206561565 427 17.0400000000 0.0018303648 0.0031368338 0.0056575397 0.0052783309 0.0046690000 15671797 955859216 1373700096 0.1676813662 0.3652541637 2.2250857353 428 17.0800000000 0.0018536715 0.0031338357 0.0056575397 0.0052874827 0.0046300000 15673773 955859216 1373700096 0.1627232879 0.3672504127 2.2289941311 429 17.1200000000 0.0018503404 0.0031308439 0.0056575397 0.0052924472 0.0046040000 15675749 955859216 1373700096 0.1576939225 0.3675536811 2.2312049866 430 17.1600000000 0.0019031626 0.0031279888 0.0056575397 0.0052966070 0.0045780000 15677725 955859216 1373700096 0.1528337598 0.3678866029 2.2346212864 431 17.2000000000 0.0019307673 0.0031252110 0.0056575397 0.0053007442 0.0046640000 15679701 955859216 1373700096 0.1481961161 0.3674907982 2.2382919788 432 17.2400000000 0.0019471979 0.0031224842 0.0056575397 0.0053014933 0.0046270000 15681677 955859216 1373700096 0.1429186463 0.3680622280 2.2427792549 433 17.2800000000 0.0019539518 0.0031197855 0.0056575397 0.0053018223 0.0046030000 15683653 955859216 1373700096 0.1391020417 0.3694958985 2.2465121746 434 17.3200000000 0.0019463617 0.0031170817 0.0056575397 0.0053014932 0.0046180000 15685629 955859216 1373700096 0.1335908175 0.3706539869 2.2488801479 435 17.3600000000 0.0019298440 0.0031143524 0.0056575397 0.0053002280 0.0045540000 15687605 955859216 1373700096 0.1283651292 0.3692106307 2.2503225803 436 17.4000000000 0.0019305862 0.0031116374 0.0056575397 0.0053038813 0.0046000000 15689581 955859216 1373700096 0.1233932003 0.3689263463 2.2530910969 437 17.4400000000 0.0019191208 0.0031089085 0.0056575397 0.0053029305 0.0046620000 15691557 955859216 1373700096 0.1171718687 0.3702214360 2.2561151981 438 17.4800000000 0.0019492846 0.0031062610 0.0056575397 0.0053026116 0.0045740000 15693533 955859216 1373700096 0.1121053621 0.3688161671 2.2583892345 439 17.5200000000 0.0019337769 0.0031035902 0.0056575397 0.0053016029 0.0046180000 15695509 955859216 1373700096 0.1072541103 0.3687123656 2.2607216835 440 17.5600000000 0.0019248530 0.0031009112 0.0056575397 0.0053007386 0.0046380000 15697485 955859216 1373700096 0.1021169126 0.3684079945 2.2627458572 441 17.6000000000 0.0018943535 0.0030981753 0.0056575397 0.0052992339 0.0046150000 15699461 955859216 1373700096 0.0964338556 0.3680550754 2.2641563416 442 17.6400000000 0.0043972745 0.0031011144 0.0056575397 0.0053122109 0.0044320000 15701437 955859216 1373700096 0.0899147913 0.3682358265 2.2636859417 443 17.6800000000 0.0019236677 0.0030984565 0.0056575397 0.0053118023 0.0046380000 15703413 955859216 1373700096 0.0857413188 0.3677804768 2.2671153545 444 17.7200000000 0.0044494597 0.0031014993 0.0056575397 0.0053192850 0.0018710000 15705389 955859216 1373700096 0.0790019780 0.3688446283 2.2678027153 445 17.7600000000 0.0019853765 0.0030989912 0.0056575397 0.0053236656 0.0047260000 15707365 955859216 1373700096 0.0755124986 0.3670872748 2.2710502148 446 17.8000000000 0.0039748931 0.0031009551 0.0056575397 0.0053379894 0.0044390000 15709341 955859216 1373700096 0.0689075217 0.3673733771 2.2712230682 447 17.8400000000 0.0020414400 0.0030985848 0.0056575397 0.0053395171 0.0046990000 15711317 955859216 1373700096 0.0643440038 0.3657835126 2.2760114670 448 17.8800000000 0.0042022052 0.0031010482 0.0056575397 0.0053499148 0.0044960000 15713293 955859216 1373700096 0.0566765256 0.3670883477 2.2764399052 449 17.9200000000 0.0057214056 0.0031068842 0.0057214056 0.0053498740 0.0044590000 15715269 955859216 1373700096 0.0506699607 0.3672337234 2.2765831947 450 17.9600000000 0.0065873694 0.0031146186 0.0065873694 0.0053470370 0.0044480000 15717245 955859216 1373700096 0.0451573916 0.3665065169 2.2775781155 451 18.0000000000 0.0021327592 0.0031124415 0.0065873694 0.0053666179 0.0048440000 15719221 955859216 1373700096 0.0338610113 0.3620645404 2.2842833996 452 18.0400000000 0.0045183515 0.0031155520 0.0065873694 0.0053715600 0.0044950000 15721197 955859216 1373700096 0.0270758308 0.3633816540 2.2849082947 453 18.0800000000 0.0056201261 0.0031210808 0.0065873694 0.0053765684 0.0044730000 15723173 955859216 1373700096 0.0203503296 0.3626255989 2.2865610123 454 18.1200000000 0.0022034158 0.0031190595 0.0065873694 0.0053795088 0.0048830000 15725149 955859216 1373700096 0.0144423386 0.3603125513 2.2923758030 455 18.1600000000 0.0043425011 0.0031217484 0.0065873694 0.0053819958 0.0045200000 15727125 955859216 1373700096 0.0067958068 0.3618975282 2.2942607403 456 18.2000000000 0.0056898589 0.0031273802 0.0065873694 0.0053816543 0.0045400000 15729101 955859216 1373700096 0.0008105628 0.3615253568 2.2951078415 457 18.2400000000 0.0065364717 0.0031348400 0.0065873694 0.0053763506 0.0045710000 15731077 955859216 1373700096 -0.0062843375 0.3618533313 2.2971277237 458 18.2800000000 0.0022884337 0.0031329919 0.0065873694 0.0054303041 0.0048440000 15733053 955859216 1373700096 -0.0118540358 0.3590939641 2.3017671108 459 18.3200000000 0.0043242965 0.0031355874 0.0065873694 0.0054251893 0.0045730000 15735029 955859216 1373700096 -0.0188999604 0.3594289124 2.3015964031 460 18.3600000000 0.0053983186 0.0031405063 0.0065873694 0.0054198379 0.0045520000 15737005 955859216 1373700096 -0.0250461362 0.3590975702 2.3024888039 461 18.4000000000 0.0057736142 0.0031462181 0.0065873694 0.0054146759 0.0045490000 15738981 955859216 1373700096 -0.0321971066 0.3580704629 2.3048682213 462 18.4400000000 0.0024193216 0.0031446447 0.0065873694 0.0054366672 0.0048800000 15740957 955859216 1373700096 -0.0381201170 0.3552281260 2.3105149269 463 18.4800000000 0.0035593009 0.0031455403 0.0065873694 0.0054322267 0.0045670000 15742933 955859216 1373700096 -0.0440633781 0.3560830951 2.3100159168 464 18.5200000000 0.0044173887 0.0031482813 0.0065873694 0.0054311293 0.0045460000 15744909 955859216 1373700096 -0.0510523580 0.3552865386 2.3101105690 465 18.5600000000 0.0024576376 0.0031467961 0.0065873694 0.0054367530 0.0049910000 15746885 955859216 1373700096 -0.0570666716 0.3528816104 2.3146550655 466 18.6000000000 0.0048025558 0.0031503492 0.0065873694 0.0054405647 0.0046050000 15748861 955859216 1373700096 -0.0638588294 0.3532548845 2.3156745434 467 18.6400000000 0.0061360262 0.0031567425 0.0065873694 0.0054425215 0.0045870000 15750837 955859216 1373700096 -0.0701832995 0.3545891941 2.3158533573 468 18.6800000000 0.0067232111 0.0031643632 0.0067232111 0.0054435687 0.0045930000 15752813 955859216 1373700096 -0.0754101202 0.3541495204 2.3152556419 469 18.7200000000 0.0026165480 0.0031631951 0.0067232111 0.0054616198 0.0051980000 15754789 955859216 1373700096 -0.0807297677 0.3513278067 2.3204109669 470 18.7600000000 0.0038734328 0.0031647063 0.0067232111 0.0054583324 0.0047010000 15756765 955859216 1373700096 -0.0869430378 0.3511374593 2.3200249672 471 18.8000000000 0.0026788423 0.0031636747 0.0067232111 0.0054658165 0.0050240000 15758741 955859216 1373700096 -0.1003496423 0.3461468220 2.3221814632 472 18.8400000000 0.0048315264 0.0031672083 0.0067232111 0.0054735584 0.0046300000 15760717 955859216 1373700096 -0.1056757346 0.3464319408 2.3219130039 473 18.8800000000 0.0066967490 0.0031746703 0.0067232111 0.0054827122 0.0046550000 15762693 955859216 1373700096 -0.1080163270 0.3457644284 2.3194971085 474 18.9200000000 0.0078430753 0.0031845193 0.0078430753 0.0054902759 0.0046600000 15764669 955859216 1373700096 -0.1104369387 0.3446629643 2.3188154697 475 18.9600000000 0.0028107166 0.0031837323 0.0078430753 0.0055071226 0.0049730000 15766645 955859216 1373700096 -0.1128232330 0.3404110670 2.3240504265 476 19.0000000000 0.0027708544 0.0031828649 0.0078430753 0.0055234722 0.0050420000 15768621 955859216 1373700096 -0.1178866923 0.3376980722 2.3243408203 477 19.0400000000 0.0046773334 0.0031859980 0.0078430753 0.0055575982 0.0047260000 15770597 955859216 1373700096 -0.1205386370 0.3366408646 2.3221631050 478 19.0800000000 0.0028346598 0.0031852630 0.0078430753 0.0055701387 0.0038430000 15772573 955859216 1373700096 -0.1262263209 0.3332415223 2.3297612667 479 19.1200000000 0.0066700247 0.0031925381 0.0078430753 0.0056072099 0.0035270000 15774549 955859216 1373700096 -0.1274687797 0.3358434737 2.3272488117 480 19.1600000000 0.0028912839 0.0031919104 0.0078430753 0.0056112607 0.0038440000 15776525 955859216 1373700096 -0.1266768426 0.3327037692 2.3294322491 481 19.2000000000 0.0068437369 0.0031995026 0.0078430753 0.0056821411 0.0035470000 15778501 955859216 1373700096 -0.1289833188 0.3346502781 2.3276724815 482 19.2400000000 0.0030219965 0.0031991343 0.0078430753 0.0056860154 0.0038520000 15780477 955859216 1373700096 -0.1287877262 0.3323781788 2.3311426640 483 19.2800000000 0.0070334906 0.0032070730 0.0078430753 0.0057581527 0.0035350000 15782453 955859216 1373700096 -0.1304462254 0.3339133263 2.3294906616 484 19.3200000000 0.0032395443 0.0032071400 0.0078430753 0.0057676546 0.0038690000 15784429 955859216 1373700096 -0.1291327924 0.3309418857 2.3335289955 485 19.3600000000 0.0032568676 0.0032072426 0.0078430753 0.0057909934 0.0038800000 15786405 955859216 1373700096 -0.1287439615 0.3309068382 2.3337101936 486 19.4000000000 0.0032548273 0.0032073405 0.0078430753 0.0058032601 0.0051070000 15788381 955859216 1373700096 -0.1297700554 0.3309685886 2.3368005753 487 19.4400000000 0.0033468700 0.0032076270 0.0078430753 0.0058150408 0.0051390000 15790357 955859216 1373700096 -0.1291483641 0.3312020600 2.3390398026 488 19.4800000000 0.0033145328 0.0032078461 0.0078430753 0.0058298866 0.0051290000 15792333 955859216 1373700096 -0.1292022020 0.3301156461 2.3417603970 489 19.5200000000 0.0033225142 0.0032080806 0.0078430753 0.0058391857 0.0051840000 15794309 955859216 1373700096 -0.1314696819 0.3306081295 2.3473365307 490 19.5600000000 0.0094996607 0.0032209205 0.0094996607 0.0059382618 0.0047640000 15796285 955859216 1373700096 -0.1312193573 0.3355575502 2.3436927795 491 19.6000000000 0.0034209022 0.0032213278 0.0094996607 0.0059663240 0.0051500000 15798261 955859216 1373700096 -0.1301221251 0.3318412900 2.3519220352 492 19.6400000000 0.0032988833 0.0032214855 0.0094996607 0.0059699489 0.0051540000 15800237 955859216 1373700096 -0.1292949170 0.3319585919 2.3550703526 493 19.6800000000 0.0032037932 0.0032214496 0.0094996607 0.0059785519 0.0051620000 15802213 955859216 1373700096 -0.1271364689 0.3334520161 2.3553888798 494 19.7200000000 0.0030888903 0.0032211812 0.0094996607 0.0060022150 0.0051910000 15804189 955859216 1373700096 -0.1281580180 0.3332120180 2.3604857922 495 19.7600000000 0.0103061320 0.0032354943 0.0103061320 0.0061680782 0.0036300000 15806165 955859216 1373700096 -0.1295793205 0.3378053308 2.3604502678 496 19.8000000000 0.0167804509 0.0032628026 0.0167804509 0.0062749425 0.0048560000 15808141 955859216 1373700096 -0.1302526295 0.3430217206 2.3602452278 497 19.8400000000 0.0034083996 0.0032630956 0.0167804509 0.0064795651 0.0029640000 15810117 955859216 1373700096 -0.1278557032 0.3353468478 2.3721303940 498 19.8800000000 0.0099374717 0.0032764980 0.0167804509 0.0065883836 0.0048490000 15812093 955859216 1373700096 -0.1275143176 0.3402910531 2.3695569038 499 19.9200000000 0.0032345997 0.0032764140 0.0167804509 0.0066478470 0.0054000000 15814069 955859216 1373700096 -0.1268865466 0.3353815675 2.3794867992 500 19.9600000000 0.0029725078 0.0032758062 0.0167804509 0.0066490447 0.0052410000 15816045 955859216 1373700096 -0.1263677031 0.3362983763 2.3825073242 501 20.0000000000 0.0029510073 0.0032751579 0.0167804509 0.0066529742 0.0052400000 15818021 955859216 1373700096 -0.1257169694 0.3368356228 2.3851571083 502 20.0400000000 0.0029533913 0.0032745169 0.0167804509 0.0066595305 0.0052030000 15819997 955859216 1373700096 -0.1254870743 0.3372937143 2.3885931969 503 20.0800000000 0.0029814106 0.0032739342 0.0167804509 0.0066661750 0.0052460000 15821973 955859216 1373700096 -0.1265461594 0.3382610381 2.3920860291 504 20.1200000000 0.0037428495 0.0032748646 0.0167804509 0.0066761328 0.0052450000 15823949 955859216 1373700096 -0.1267252862 0.3392783999 2.3953938484 505 20.1600000000 0.0038305768 0.0032759650 0.0167804509 0.0066841601 0.0052320000 15825925 955859216 1373700096 -0.1272517890 0.3402085304 2.3979065418 506 20.2000000000 0.0037839960 0.0032769690 0.0167804509 0.0066915130 0.0052660000 15827901 955859216 1373700096 -0.1268733144 0.3403551579 2.4002490044 507 20.2400000000 0.0040729735 0.0032785390 0.0167804509 0.0066989387 0.0052620000 15829877 955859216 1373700096 -0.1274333000 0.3402697742 2.4030821323 508 20.2800000000 0.0045723626 0.0032810859 0.0167804509 0.0067084431 0.0052910000 15831853 955859216 1373700096 -0.1293129921 0.3402605653 2.4066722393 509 20.3200000000 0.0047625084 0.0032839964 0.0167804509 0.0067180631 0.0052900000 15833829 955859216 1373700096 -0.1292079985 0.3399224579 2.4096281528 510 20.3600000000 0.0051456238 0.0032876466 0.0167804509 0.0067221792 0.0052910000 15835805 955859216 1373700096 -0.1287443489 0.3409149051 2.4093971252 511 20.4000000000 0.0134594738 0.0033075524 0.0167804509 0.0068690406 0.0036980000 15837781 955859216 1373700096 -0.1297158897 0.3465946913 2.4044485092 512 20.4400000000 0.0060469676 0.0033129028 0.0167804509 0.0069237764 0.0053450000 15839757 955859216 1373700096 -0.1321620196 0.3417794406 2.4131414890 513 20.4800000000 0.0087779453 0.0033235559 0.0167804509 0.0069309363 0.0054340000 15890885 955859216 1373700096 -0.1322077960 0.3447622061 2.4128665924 514 20.5200000000 0.0136281382 0.0033436037 0.0167804509 0.0070276682 0.0050210000 15995261 955859216 1373700096 -0.1336041838 0.3477892578 2.4086861610 515 20.5600000000 0.0074130283 0.0033515055 0.0167804509 0.0070769139 0.0053720000 15997237 955859216 1373700096 -0.1350757927 0.3432908952 2.4150216579 516 20.6000000000 0.0084066084 0.0033613022 0.0167804509 0.0070786176 0.0053570000 15999213 955859216 1373700096 -0.1365924031 0.3442142010 2.4148800373 517 20.6400000000 0.0100006973 0.0033741444 0.0167804509 0.0070813659 0.0053760000 16001189 955859216 1373700096 -0.1376807094 0.3453777134 2.4138886929 518 20.6800000000 0.0179041587 0.0034021946 0.0179041587 0.0071036545 0.0040870000 16003165 955859216 1373700096 -0.1391897202 0.3525983691 2.4139227867 519 20.7200000000 0.0180261508 0.0034303718 0.0180261508 0.0071046673 0.0054130000 16005141 955859216 1373700096 -0.1422820836 0.3526152074 2.4149549007 520 20.7600000000 0.0186560359 0.0034596519 0.0186560359 0.0071070680 0.0054080000 16007117 955859216 1373700096 -0.1440833956 0.3516206741 2.4154505730 521 20.8000000000 0.0220616125 0.0034953562 0.0220616125 0.0071135703 0.0054580000 16009093 955859216 1373700096 -0.1462700367 0.3544007242 2.4144971371 522 20.8400000000 0.0281159617 0.0035425222 0.0281159617 0.0071322323 0.0054040000 16011069 955859216 1373700096 -0.1491394341 0.3592158854 2.4146771431 523 20.8800000000 0.0497812629 0.0036309328 0.0497812629 0.0072113972 0.0054510000 16013045 955859216 1373700096 -0.1496340930 0.3814596534 2.4093761444 524 20.9200000000 0.0623973049 0.0037430823 0.0623973049 0.0073116221 0.0051190000 16015021 955859216 1373700096 -0.1508096159 0.3921273947 2.4033505917 525 20.9600000000 0.0639433265 0.0038577494 0.0639433265 0.0073251364 0.0051860000 16016997 955859216 1373700096 -0.1538163871 0.3909390867 2.4004991055 526 21.0000000000 0.0552187935 0.0039553940 0.0639433265 0.0074058578 0.0054270000 16018973 955859216 1373700096 -0.1573447734 0.3832693696 2.4048659801 527 21.0400000000 0.0585724488 0.0040590317 0.0639433265 0.0074073332 0.0041400000 16020949 955859216 1373700096 -0.1599909216 0.3865272105 2.4008982182 528 21.0800000000 0.0645575747 0.0041736123 0.0645575747 0.0074606642 0.0051350000 16022925 955859216 1373700096 -0.1638632566 0.3899869025 2.3955719471 529 21.1200000000 0.0560508035 0.0042716788 0.0645575747 0.0075098078 0.0054970000 16024901 955859216 1373700096 -0.1685452908 0.3808162212 2.3990206718 530 21.1600000000 0.0599862821 0.0043768007 0.0645575747 0.0075251570 0.0050970000 16026877 955859216 1373700096 -0.1708788127 0.3851941228 2.3913493156 531 21.2000000000 0.0615082607 0.0044843929 0.0645575747 0.0075326467 0.0050760000 16028853 955859216 1373700096 -0.1740611941 0.3854188025 2.3859903812 532 21.2400000000 0.0772516578 0.0046211735 0.0772516578 0.0075857505 0.0051690000 16030829 955859216 1373700096 -0.1784251034 0.4002217650 2.3799619675 533 21.2800000000 0.0733969063 0.0047502086 0.0772516578 0.0075885740 0.0051460000 16032805 955859216 1373700096 -0.1820631623 0.3956789672 2.3775432110 534 21.3200000000 0.0591046736 0.0048519960 0.0772516578 0.0075935708 0.0051530000 16034781 955859216 1373700096 -0.1859474331 0.3790981770 2.3785569668 535 21.3600000000 0.0550245903 0.0049457765 0.0772516578 0.0077053716 0.0054550000 16036757 955859216 1373700096 -0.1921061724 0.3743475378 2.3842995167 536 21.4000000000 0.0591662303 0.0050469341 0.0772516578 0.0077136683 0.0051320000 16038733 955859216 1373700096 -0.1958149523 0.3779082894 2.3784782887 537 21.4400000000 0.0743414536 0.0051759742 0.0772516578 0.0077352527 0.0022060000 16040709 955859216 1373700096 -0.2000653595 0.3933055699 2.3709306717 538 21.4800000000 0.0774274021 0.0053102705 0.0774274021 0.0077340737 0.0050840000 16042685 955859216 1373700096 -0.2048984021 0.3967973888 2.3663761616 539 21.5200000000 0.0698033646 0.0054299238 0.0774274021 0.0077300114 0.0050820000 16044661 955859216 1373700096 -0.2091664523 0.3879560232 2.3645019531 540 21.5600000000 0.0646779016 0.0055396422 0.0774274021 0.0077297156 0.0050970000 16046637 955859216 1373700096 -0.2141271681 0.3824175894 2.3620529175 541 21.6000000000 0.0553759858 0.0056317612 0.0774274021 0.0078202188 0.0054620000 16048613 955859216 1373700096 -0.2196084857 0.3728109300 2.3661088943 542 21.6400000000 0.0605840720 0.0057331492 0.0774274021 0.0078494151 0.0051200000 16050589 955859216 1373700096 -0.2233637273 0.3746873736 2.3611958027 543 21.6800000000 0.0444246083 0.0058044042 0.0774274021 0.0079431112 0.0055420000 16052565 955859216 1373700096 -0.2280525416 0.3568080068 2.3622112274 544 21.7200000000 0.0244672708 0.0058387109 0.0774274021 0.0080769082 0.0055910000 16054541 955859216 1373700096 -0.2356653363 0.3336991668 2.3563113213 545 21.7600000000 0.0334819816 0.0058894325 0.0774274021 0.0080749562 0.0038870000 16056517 955859216 1373700096 -0.2404485196 0.3448020816 2.3476631641 546 21.8000000000 0.0408688150 0.0059534973 0.0774274021 0.0080727819 0.0052130000 16058493 955859216 1373700096 -0.2449148744 0.3512187302 2.3413720131 547 21.8400000000 0.0493594818 0.0060328501 0.0774274021 0.0080798310 0.0051960000 16060469 955859216 1373700096 -0.2494938821 0.3571983576 2.3359005451 548 21.8800000000 0.0486901663 0.0061106919 0.0774274021 0.0080725290 0.0051470000 16062445 955859216 1373700096 -0.2552587688 0.3610569239 2.3295545578 549 21.9200000000 0.0436102971 0.0061789972 0.0774274021 0.0080705114 0.0051690000 16064421 955859216 1373700096 -0.2603193223 0.3586728871 2.3241653442 550 21.9600000000 0.0561483949 0.0062698507 0.0774274021 0.0080920792 0.0052520000 16066397 955859216 1373700096 -0.2636836469 0.3635643423 2.3193471432 551 22.0000000000 0.0612155683 0.0063695707 0.0774274021 0.0081016344 0.0052840000 16068373 955859216 1373700096 -0.2680115402 0.3672079742 2.3131022453 552 22.0400000000 0.0588948764 0.0064647252 0.0774274021 0.0080950178 0.0038680000 16070349 955859216 1373700096 -0.2735815942 0.3711670041 2.3053975105 553 22.0800000000 0.0566121712 0.0065554078 0.0774274021 0.0080887972 0.0038520000 16072325 955859216 1373700096 -0.2776576281 0.3699091673 2.2997500896 554 22.1200000000 0.0645533726 0.0066600972 0.0774274021 0.0080937759 0.0039860000 16074301 955859216 1373700096 -0.2818073034 0.3754850626 2.2937681675 555 22.1600000000 0.0580422878 0.0067526778 0.0774274021 0.0080889734 0.0038610000 16076277 955859216 1373700096 -0.2856451571 0.3697673976 2.2881674767 556 22.2000000000 0.0628964156 0.0068536557 0.0774274021 0.0080885787 0.0039890000 16078253 955859216 1373700096 -0.2890862226 0.3727984130 2.2820308208 557 22.2400000000 0.0538170673 0.0069379706 0.0774274021 0.0081095316 0.0048590000 16080229 955859216 1373700096 -0.2941095531 0.3662650883 2.2792024612 558 22.2800000000 0.0553653501 0.0070247580 0.0774274021 0.0081099982 0.0039430000 16082205 955859216 1373700096 -0.2971830666 0.3664291501 2.2717704773 559 22.3200000000 0.0492442213 0.0071002848 0.0774274021 0.0081135784 0.0056570000 16084181 955859216 1373700096 -0.3008071184 0.3587946594 2.2671668530 560 22.3600000000 0.0481826104 0.0071736461 0.0774274021 0.0081100825 0.0053500000 16086157 955859216 1373700096 -0.3035811782 0.3565592468 2.2585923672 561 22.4000000000 0.0382582732 0.0072290554 0.0774274021 0.0081105777 0.0056110000 16088133 955859216 1373700096 -0.3068724871 0.3462330103 2.2522330284 562 22.4400000000 0.0462516584 0.0072984907 0.0774274021 0.0081304287 0.0055460000 16090109 955859216 1373700096 -0.3103668094 0.3499218225 2.2489407063 563 22.4800000000 0.0402878858 0.0073570864 0.0774274021 0.0081286203 0.0054490000 16092085 955859216 1373700096 -0.3132361472 0.3419901431 2.2433385849 564 22.5200000000 0.0303747859 0.0073978979 0.0774274021 0.0081261391 0.0056370000 16094061 955859216 1373700096 -0.3163035810 0.3329213262 2.2364101410 565 22.5600000000 0.0118651818 0.0074058046 0.0774274021 0.0081427425 0.0056790000 16096037 955859216 1373700096 -0.3235502541 0.3160549104 2.2219491005 566 22.6000000000 0.0163533911 0.0074216131 0.0774274021 0.0081462253 0.0041300000 16098013 955859216 1373700096 -0.3270983696 0.3175633252 2.2155847549 567 22.6400000000 0.0069784480 0.0074208315 0.0774274021 0.0081462108 0.0056750000 16099989 955859216 1373700096 -0.3303593099 0.3053059876 2.2086575031 568 22.6800000000 0.0067461235 0.0074196436 0.0774274021 0.0081436365 0.0054910000 16101965 955859216 1373700096 -0.3336930573 0.3067749739 2.2009930611 569 22.7200000000 0.0070636664 0.0074190180 0.0774274021 0.0081396912 0.0057980000 16103941 955859216 1373700096 -0.3372468054 0.3068168461 2.1932084560 570 22.7600000000 0.0053130887 0.0074153234 0.0774274021 0.0081484489 0.0041290000 16105917 955859216 1373700096 -0.3404099047 0.3014266789 2.1892800331 571 22.8000000000 0.0061893291 0.0074131763 0.0774274021 0.0081426193 0.0055740000 16107893 955859216 1373700096 -0.3427793682 0.2983579934 2.1818013191 572 22.8400000000 0.0070050443 0.0074124628 0.0774274021 0.0081479769 0.0055890000 16109869 955859216 1373700096 -0.3458894491 0.3045844436 2.1730585098 573 22.8800000000 0.0062145661 0.0074103722 0.0774274021 0.0081486320 0.0041870000 16111845 955859216 1373700096 -0.3500252068 0.3029778600 2.1676425934 574 22.9200000000 0.0052021374 0.0074065251 0.0774274021 0.0081489145 0.0056800000 16113821 955859216 1373700096 -0.3546633124 0.3012696803 2.1614413261 575 22.9600000000 0.0777452216 0.0075288533 0.0777452216 0.0085488907 0.0057010000 16115797 955859216 1373700096 -0.3573564887 0.3744310439 2.1447334290 576 23.0000000000 0.0922837257 0.0076759971 0.0922837257 0.0086324961 0.0057450000 16117773 955859216 1373700096 -0.3608266711 0.3848026991 2.1420459747 577 23.0400000000 0.0721620098 0.0077877580 0.0922837257 0.0087521351 0.0043130000 16119749 955859216 1373700096 -0.3649707139 0.3624368906 2.1427903175 578 23.0800000000 0.0546545275 0.0078688424 0.0922837257 0.0088418956 0.0056700000 16121725 955859216 1373700096 -0.3672194481 0.3456408978 2.1383128166 579 23.1200000000 0.0379413553 0.0079207811 0.0922837257 0.0088864362 0.0056820000 16123701 955859216 1373700096 -0.3687869608 0.3276648521 2.1326868534 580 23.1600000000 0.0234410409 0.0079475401 0.0922837257 0.0089397166 0.0059810000 16125677 955859216 1373700096 -0.3700399697 0.3118618429 2.1290504932 581 23.2000000000 0.0921515003 0.0080924695 0.0922837257 0.0093003300 0.0054050000 16127653 955859216 1373700096 -0.3751355708 0.3818841875 2.1133551598 582 23.2400000000 0.0744480863 0.0082064826 0.0922837257 0.0094161352 0.0058190000 16129629 955859216 1373700096 -0.3822970688 0.3588321507 2.1147220135 583 23.2800000000 0.0586976223 0.0082930883 0.0922837257 0.0094869592 0.0057550000 16131605 955859216 1373700096 -0.3844353259 0.3429407775 2.1064004898 584 23.3200000000 0.0513897948 0.0083668840 0.0922837257 0.0094929330 0.0056170000 16133581 955859216 1373700096 -0.3877594769 0.3352702558 2.0925586224 585 23.3600000000 0.0484294072 0.0084353670 0.0922837257 0.0094962120 0.0042330000 16135557 955859216 1373700096 -0.3941770196 0.3300282955 2.0842156410 586 23.4000000000 0.0876068696 0.0085704719 0.0922837257 0.0096491522 0.0037750000 16137533 955859216 1373700096 -0.3974350393 0.3678873777 2.0827405453 587 23.4400000000 0.0846498832 0.0087000791 0.0922837257 0.0096463834 0.0059530000 16139509 955859216 1373700096 -0.4019818306 0.3647817373 2.0773878098 588 23.4800000000 0.0856797323 0.0088309969 0.0922837257 0.0096434364 0.0056680000 16141485 955859216 1373700096 -0.4088780880 0.3639172614 2.0702188015 589 23.5200000000 0.0861879811 0.0089623330 0.0922837257 0.0096379637 0.0055980000 16143461 955859216 1373700096 -0.4152573049 0.3614955246 2.0627653599 590 23.5600000000 0.0870840997 0.0090947428 0.0922837257 0.0096321270 0.0056690000 16145437 955859216 1373700096 -0.4213410616 0.3602810502 2.0552077293 591 23.6000000000 0.0879438296 0.0092281592 0.0922837257 0.0096259247 0.0043170000 16147413 955859216 1373700096 -0.4277784228 0.3591896892 2.0480482578 592 23.6400000000 0.0889670625 0.0093628533 0.0922837257 0.0096202031 0.0034940000 16149389 955859216 1373700096 -0.4341288805 0.3599205613 2.0402283669 593 23.6800000000 0.1096325368 0.0095319421 0.1096325368 0.0096686259 0.0057190000 16151365 955859216 1373700096 -0.4388643503 0.3808113933 2.0301735401 594 23.7200000000 0.1018890291 0.0096874254 0.1096325368 0.0096781786 0.0059870000 16153341 955859216 1373700096 -0.4474495649 0.3703646660 2.0256209373 595 23.7600000000 0.1019841507 0.0098425460 0.1096325368 0.0096765114 0.0060310000 16155317 955859216 1373700096 -0.4560514390 0.3667575717 2.0175004005 596 23.8000000000 0.1033356041 0.0099994135 0.1096325368 0.0096766219 0.0059310000 16157293 955859216 1373700096 -0.4635732472 0.3653863072 2.0097093582 597 23.8400000000 0.1136357635 0.0101730088 0.1136357635 0.0096781475 0.0053690000 16159269 955859216 1373700096 -0.4669265449 0.3761017919 2.0005881786 598 23.8800000000 0.1095615700 0.0103392104 0.1136357635 0.0096732647 0.0059920000 16161245 955859216 1373700096 -0.4761346281 0.3713693023 1.9938416481 599 23.9200000000 0.1111608744 0.0105075270 0.1136357635 0.0096693427 0.0057910000 16163221 955859216 1373700096 -0.4846639037 0.3726058602 1.9852591753 600 23.9600000000 0.1090003625 0.0106716817 0.1136357635 0.0096651236 0.0045540000 16165197 955859216 1373700096 -0.4907087386 0.3692313731 1.9774754047 601 24.0000000000 0.1123257652 0.0108408233 0.1136357635 0.0096620831 0.0058540000 16167173 955859216 1373700096 -0.4982886910 0.3714752495 1.9694068432 602 24.0400000000 0.1142404228 0.0110125834 0.1142404228 0.0096686528 0.0045730000 16169149 955859216 1373700096 -0.5147628784 0.3717034161 1.9528770447 603 24.0800000000 0.1136395931 0.0111827775 0.1142404228 0.0096644804 0.0043670000 16171125 955859216 1373700096 -0.5240121484 0.3701297045 1.9451160431 604 24.1200000000 0.1145175546 0.0113538615 0.1145175546 0.0096633213 0.0058940000 16173101 955859216 1373700096 -0.5358981490 0.3686452806 1.9364457130 605 24.1600000000 0.1160122007 0.0115268505 0.1160122007 0.0096641412 0.0060370000 16175077 955859216 1373700096 -0.5422397256 0.3699475229 1.9284068346 606 24.2000000000 0.1170225665 0.0117009359 0.1170225665 0.0096602301 0.0044340000 16177053 955859216 1373700096 -0.5476249456 0.3706856072 1.9198533297 607 24.2400000000 0.1169353575 0.0118743040 0.1170225665 0.0096547040 0.0060130000 16179029 955859216 1373700096 -0.5545600653 0.3692254424 1.9112524986 608 24.2800000000 0.1181700528 0.0120491325 0.1181700528 0.0096495420 0.0059320000 16181005 955859216 1373700096 -0.5627256632 0.3690674603 1.9021453857 609 24.3200000000 0.1187913194 0.0122244070 0.1187913194 0.0096449747 0.0060510000 16182981 955859216 1373700096 -0.5709306002 0.3693654537 1.8940486908 610 24.3600000000 0.1200801507 0.0124012197 0.1200801507 0.0096410348 0.0044480000 16184957 955859216 1373700096 -0.5759881735 0.3699620664 1.8858283758 611 24.4000000000 0.1208558753 0.0125787232 0.1208558753 0.0096361384 0.0059220000 16186933 955859216 1373700096 -0.5808329582 0.3699646592 1.8772968054 612 24.4400000000 0.1218315065 0.0127572409 0.1218315065 0.0096320667 0.0060060000 16188909 955859216 1373700096 -0.5874972939 0.3694675565 1.8686524630 613 24.4800000000 0.1230429560 0.0129371523 0.1230429560 0.0096283223 0.0045290000 16190885 955859216 1373700096 -0.5946487188 0.3700558245 1.8596551418 614 24.5200000000 0.1232122406 0.0131167534 0.1232122406 0.0096243480 0.0060280000 16192861 955859216 1373700096 -0.6013643742 0.3693719506 1.8519594669 615 24.5600000000 0.1242132112 0.0132973981 0.1242132112 0.0096202177 0.0060610000 16194837 955859216 1373700096 -0.6070361733 0.3697795272 1.8433150053 616 24.6000000000 0.1254554540 0.0134794728 0.1254554540 0.0096160675 0.0044050000 16196813 955859216 1373700096 -0.6144929528 0.3702201843 1.8338774443 617 24.6400000000 0.1264139861 0.0136625109 0.1264139861 0.0096120959 0.0060560000 16198789 955859216 1373700096 -0.6216675639 0.3708045483 1.8248637915 618 24.6800000000 0.1277126372 0.0138470581 0.1277126372 0.0096079073 0.0053970000 16200765 955859216 1373700096 -0.6260557771 0.3720096648 1.8160490990 619 24.7200000000 0.1286858320 0.0140325811 0.1286858320 0.0096023551 0.0044940000 16202741 955859216 1373700096 -0.6294237375 0.3731798828 1.8085706234 620 24.7600000000 0.1308304369 0.0142209648 0.1308304369 0.0096081575 0.0062910000 16204717 955859216 1373700096 -0.6418585777 0.3741937876 1.7896260023 621 24.8000000000 0.1318894029 0.0144104470 0.1318894029 0.0096037968 0.0060800000 16206693 955859216 1373700096 -0.6463451982 0.3740324974 1.7811295986 622 24.8400000000 0.1329854280 0.0146010820 0.1329854280 0.0095990901 0.0045930000 16208669 955859216 1373700096 -0.6532933712 0.3729648292 1.7711317539 623 24.8800000000 0.1339574456 0.0147926652 0.1339574456 0.0095935463 0.0061500000 16210645 955859216 1373700096 -0.6586734056 0.3727428019 1.7619436979 624 24.9200000000 0.1350733042 0.0149854227 0.1350733042 0.0095874329 0.0046700000 16212621 955859216 1373700096 -0.6643100977 0.3725240231 1.7525550127 625 24.9600000000 0.1363445371 0.0151795972 0.1363445371 0.0095811718 0.0045980000 16214597 955859216 1373700096 -0.6699699163 0.3727104068 1.7419461012 626 25.0000000000 0.1375622302 0.0153750967 0.1375622302 0.0095751829 0.0061850000 16216573 955859216 1373700096 -0.6770181656 0.3731426597 1.7313479185 627 25.0400000000 0.1386155635 0.0155716524 0.1386155635 0.0095702106 0.0062250000 16218549 955859216 1373700096 -0.6821571589 0.3730008900 1.7213666439 628 25.0800000000 0.1397819072 0.0157694395 0.1397819072 0.0095648019 0.0046880000 16220525 955859216 1373700096 -0.6875585914 0.3723829985 1.7113044262 629 25.1200000000 0.1411969066 0.0159688472 0.1411969066 0.0095587361 0.0061860000 16222501 955859216 1373700096 -0.6945605278 0.3733406365 1.6988546848 630 25.1600000000 0.1423777789 0.0161694963 0.1423777789 0.0095551456 0.0052260000 16224477 955859216 1373700096 -0.6989015341 0.3736764789 1.6887891293 631 25.2000000000 0.1434920728 0.0163712753 0.1434920728 0.0095478964 0.0061900000 16226453 955859216 1373700096 -0.7021445036 0.3737357557 1.6786971092 632 25.2400000000 0.1449247748 0.0165746828 0.1449247748 0.0095406826 0.0047370000 16228429 955859216 1373700096 -0.7091609836 0.3737803698 1.6658250093 633 25.2800000000 0.1463790536 0.0167797450 0.1463790536 0.0095353442 0.0040020000 16230405 955859216 1373700096 -0.7155145407 0.3736083508 1.6537394524 634 25.3200000000 0.1476627886 0.0169861851 0.1476627886 0.0095291141 0.0039770000 16232381 955859216 1373700096 -0.7185463905 0.3735177219 1.6435167789 635 25.3600000000 0.1486376375 0.0171935102 0.1486376375 0.0095234035 0.0039890000 16234357 955859216 1373700096 -0.7194007039 0.3736174703 1.6349756718 636 25.4000000000 0.1501223594 0.0174025178 0.1501223594 0.0095294298 0.0041240000 16236333 955859216 1373700096 -0.7287039757 0.3737349510 1.6207773685 637 25.4400000000 0.1517439485 0.0176134149 0.1517439485 0.0095228128 0.0040650000 16238309 955859216 1373700096 -0.7378067374 0.3754661679 1.6067016125 638 25.4800000000 0.1528235823 0.0178253431 0.1528235823 0.0095195119 0.0063400000 16240285 955859216 1373700096 -0.7379371524 0.3766998649 1.5972341299 639 25.5200000000 0.1541245133 0.0180386438 0.1541245133 0.0095127208 0.0062670000 16242261 955859216 1373700096 -0.7424380183 0.3773230612 1.5856144428 640 25.5600000000 0.1555657983 0.0182535300 0.1555657983 0.0095069879 0.0062440000 16244237 955859216 1373700096 -0.7466689944 0.3776667714 1.5731370449 641 25.6000000000 0.1569312066 0.0184698758 0.1569312066 0.0095004144 0.0046750000 16246213 955859216 1373700096 -0.7491140962 0.3781863153 1.5620266199 642 25.6400000000 0.1582849622 0.0186876563 0.1582849622 0.0094935621 0.0062660000 16248189 955859216 1373700096 -0.7524051070 0.3779230714 1.5500565767 643 25.6800000000 0.1595493555 0.0189067258 0.1595493555 0.0094868943 0.0046500000 16250165 955859216 1373700096 -0.7551163435 0.3775606453 1.5383070707 644 25.7200000000 0.1608363539 0.0191271135 0.1608363539 0.0094808243 0.0061300000 16252141 955859216 1373700096 -0.7587333918 0.3767513633 1.5269672871 645 25.7600000000 0.1622823477 0.0193490596 0.1622823477 0.0094747648 0.0061550000 16254117 955859216 1373700096 -0.7640990615 0.3770495653 1.5145795345 646 25.8000000000 0.1636341810 0.0195724111 0.1636341810 0.0094688025 0.0065680000 16256093 955859216 1373700096 -0.7669838071 0.3773237467 1.5024925470 647 25.8400000000 0.1650117636 0.0197972015 0.1650117636 0.0094628737 0.0046560000 16258069 955859216 1373700096 -0.7695268393 0.3784831762 1.4909842014 648 25.8800000000 0.1660602391 0.0200229160 0.1660602391 0.0094567001 0.0062310000 16260045 955859216 1373700096 -0.7700035572 0.3778967559 1.4817987680 649 25.9200000000 0.1674050689 0.0202500072 0.1674050689 0.0094524314 0.0052260000 16262021 955859216 1373700096 -0.7743458748 0.3775142729 1.4698444605 650 25.9600000000 0.1687878668 0.0204785270 0.1687878668 0.0094476183 0.0038540000 16263997 955859216 1373700096 -0.7784829736 0.3767798543 1.4576977491 651 26.0000000000 0.1700764596 0.0207083241 0.1700764596 0.0094426752 0.0061660000 16265973 955859216 1373700096 -0.7808666229 0.3757226169 1.4474484921 652 26.0400000000 0.1713161170 0.0209393177 0.1713161170 0.0094385547 0.0061970000 16267949 955859216 1373700096 -0.7830554843 0.3750850856 1.4361690283 653 26.0800000000 0.1727367193 0.0211717792 0.1727367193 0.0094348297 0.0061720000 16269925 955859216 1373700096 -0.7876696587 0.3733875751 1.4238675833 654 26.1200000000 0.1740076095 0.0214054732 0.1740076095 0.0094305691 0.0045810000 16271901 955859216 1373700096 -0.7908673882 0.3717013597 1.4128736258 655 26.1600000000 0.1752518415 0.0216403531 0.1752518415 0.0094261350 0.0038360000 16273877 955859216 1373700096 -0.7942324281 0.3694572151 1.4017368555 656 26.2000000000 0.1764933467 0.0218764095 0.1764933467 0.0094227246 0.0061870000 16275853 955859216 1373700096 -0.7985569239 0.3681901991 1.3903756142 657 26.2400000000 0.1777884811 0.0221137186 0.1777884811 0.0094176370 0.0061840000 16277829 955859216 1373700096 -0.8039366603 0.3662860692 1.3785752058 658 26.2800000000 0.1789425313 0.0223520602 0.1789425313 0.0094121018 0.0046340000 16279805 955859216 1373700096 -0.8062337041 0.3646820784 1.3687537909 659 26.3200000000 0.1802465469 0.0225916573 0.1802465469 0.0094075968 0.0046790000 16281781 955859216 1373700096 -0.8104788065 0.3640469909 1.3571864367 660 26.3600000000 0.1815132052 0.0228324476 0.1815132052 0.0094020981 0.0062270000 16283757 955859216 1373700096 -0.8136691451 0.3627440631 1.3459587097 661 26.4000000000 0.1828044355 0.0230744627 0.1828044355 0.0093982038 0.0025650000 16285733 955859216 1373700096 -0.8176754713 0.3620655239 1.3342922926 662 26.4400000000 0.1841554791 0.0233177875 0.1841554791 0.0093941058 0.0025330000 16287709 955859216 1373700096 -0.8230819702 0.3616163731 1.3219918013 663 26.4800000000 0.1856776476 0.0235626741 0.1856776476 0.0093890789 0.0062730000 16289685 955859216 1373700096 -0.8282908797 0.3620787263 1.3087812662 664 26.5200000000 0.1870499998 0.0238088900 0.1870499998 0.0093847267 0.0063160000 16291661 955859216 1373700096 -0.8325260282 0.3611407876 1.2967036963 665 26.5600000000 0.1899197698 0.0240586808 0.1899197698 0.0093932640 0.0062810000 16293637 955859216 1373700096 -0.8410190344 0.3621017337 1.2721825838 666 26.6000000000 0.1914250255 0.0243099816 0.1914250255 0.0093886408 0.0046740000 16295613 955859216 1373700096 -0.8460857868 0.3635663986 1.2584822178 667 26.6400000000 0.1926995814 0.0245624398 0.1926995814 0.0093833894 0.0062950000 16297589 955859216 1373700096 -0.8494975567 0.3643211126 1.2465758324 668 26.6800000000 0.1941751689 0.0248163511 0.1941751689 0.0093783621 0.0063370000 16299565 955859216 1373700096 -0.8550690413 0.3650657535 1.2329913378 669 26.7200000000 0.1954843849 0.0250714602 0.1954843849 0.0093748631 0.0047080000 16301541 955859216 1373700096 -0.8583478332 0.3663653433 1.2208133936 670 26.7600000000 0.1968767345 0.0253278860 0.1968767345 0.0093691508 0.0063950000 16303517 955859216 1373700096 -0.8614052534 0.3686976433 1.2084169388 671 26.8000000000 0.1984024495 0.0255858213 0.1984024495 0.0093645086 0.0047120000 16305493 955859216 1373700096 -0.8670608401 0.3686120212 1.1952325106 672 26.8400000000 0.1999524981 0.0258452955 0.1999524981 0.0093610046 0.0047370000 16307469 955859216 1373700096 -0.8720939159 0.3680014610 1.1825343370 673 26.8800000000 0.2015473843 0.0261063684 0.2015473843 0.0093573568 0.0063160000 16309445 955859216 1373700096 -0.8759326935 0.3673450053 1.1696417332 674 26.9200000000 0.2028467804 0.0263685946 0.2028467804 0.0093523696 0.0063590000 16311421 955859216 1373700096 -0.8769013286 0.3669132590 1.1580214500 675 26.9600000000 0.2043503076 0.0266322712 0.2043503076 0.0093508408 0.0063450000 16313397 955859216 1373700096 -0.8784913421 0.3660854697 1.1457754374 676 27.0000000000 0.2057500631 0.0268972383 0.2057500631 0.0093517362 0.0049790000 16315373 955859216 1373700096 -0.8822067380 0.3661534786 1.1326357126 677 27.0400000000 0.2071335763 0.0271634663 0.2071335763 0.0093504249 0.0063460000 16317349 955859216 1373700096 -0.8859001398 0.3663960695 1.1202868223 678 27.0800000000 0.2082737684 0.0274305906 0.2082737684 0.0093479049 0.0062840000 16319325 955859216 1373700096 -0.8889418244 0.3670268953 1.1097351313 679 27.1200000000 0.2095927745 0.0276988707 0.2095927745 0.0093459397 0.0054640000 16321301 955859216 1373700096 -0.8918238878 0.3668256700 1.0987436771 680 27.1600000000 0.2105661184 0.0279677931 0.2105661184 0.0093429721 0.0039430000 16323277 955859216 1373700096 -0.8946751356 0.3670401275 1.0893721581 681 27.2000000000 0.2118912488 0.0282378716 0.2118912488 0.0093402913 0.0062210000 16325253 955859216 1373700096 -0.8976120353 0.3676573336 1.0790281296 682 27.2400000000 0.2129129320 0.0285086562 0.2129129320 0.0093382798 0.0063190000 16327229 955859216 1373700096 -0.9015038610 0.3685479164 1.0675771236 683 27.2800000000 0.2142771333 0.0287806452 0.2142771333 0.0093334966 0.0063380000 16329205 955859216 1373700096 -0.9067838788 0.3695816696 1.0557401180 684 27.3200000000 0.2160555422 0.0290544389 0.2160555422 0.0093298685 0.0046500000 16331181 955859216 1373700096 -0.9076759815 0.3691385984 1.0463925600 685 27.3600000000 0.2169506848 0.0293287400 0.2169506848 0.0093278227 0.0038730000 16333157 955859216 1373700096 -0.9081172347 0.3693633080 1.0367205143 686 27.4000000000 0.2177501172 0.0296034067 0.2177501172 0.0093297487 0.0062870000 16335133 955859216 1373700096 -0.9139816761 0.3692972064 1.0237219334 687 27.4400000000 0.2194377929 0.0298797304 0.2194377929 0.0093258243 0.0063370000 16337109 955859216 1373700096 -0.9178999066 0.3688640296 1.0123919249 688 27.4800000000 0.2201412171 0.0301562733 0.2201412171 0.0093208062 0.0061270000 16339085 955859216 1373700096 -0.9202539325 0.3693592548 1.0029855967 689 27.5200000000 0.2217942476 0.0304344126 0.2217942476 0.0093172048 0.0063410000 16341061 955859216 1373700096 -0.9255349636 0.3701250851 0.9897867441 690 27.5600000000 0.2229570001 0.0307134308 0.2229570001 0.0093128596 0.0048130000 16343037 955859216 1373700096 -0.9263232350 0.3707377911 0.9793444276 691 27.6000000000 0.2241588235 0.0309933807 0.2241588235 0.0093074638 0.0065210000 16345013 955859216 1373700096 -0.9283233881 0.3706983924 0.9685987830 692 27.6400000000 0.2255171090 0.0312744844 0.2255171090 0.0093016585 0.0062530000 16346989 955859216 1373700096 -0.9309524298 0.3696134388 0.9560906887 693 27.6800000000 0.2267953753 0.0315566213 0.2267953753 0.0092954596 0.0063670000 16348965 955859216 1373700096 -0.9332314730 0.3699988425 0.9440037608 694 27.7200000000 0.2282719314 0.0318400728 0.2282719314 0.0092899152 0.0048340000 16350941 955859216 1373700096 -0.9352323413 0.3692819774 0.9318419695 695 27.7600000000 0.2296348810 0.0321246696 0.2296348810 0.0092846509 0.0065360000 16352917 955859216 1373700096 -0.9377413392 0.3673712313 0.9192728400 696 27.8000000000 0.2309761792 0.0324103758 0.2309761792 0.0092785890 0.0049570000 16354893 955859216 1373700096 -0.9402029514 0.3667686880 0.9065446258 697 27.8400000000 0.2341086566 0.0326997564 0.2341086566 0.0092758534 0.0066910000 16356869 955859216 1373700096 -0.9447182417 0.3622041345 0.8798615336 698 27.8800000000 0.2354570776 0.0329902397 0.2354570776 0.0092709560 0.0065340000 16358845 955859216 1373700096 -0.9449827671 0.3600869477 0.8689390421 699 27.9200000000 0.2367845625 0.0332817909 0.2367845625 0.0092769169 0.0048530000 16360821 955859216 1373700096 -0.9479981065 0.3629640341 0.8546563983 700 27.9600000000 0.2382715642 0.0335746335 0.2382715642 0.0092703703 0.0066050000 16362797 955859216 1373700096 -0.9490368962 0.3650996089 0.8399042487 701 28.0000000000 0.2398142368 0.0338688412 0.2398142368 0.0092674986 0.0032210000 16364773 955859216 1373700096 -0.9474257231 0.3654298186 0.8277814388 702 28.0400000000 0.2411677688 0.0341641388 0.2411677688 0.0092610691 0.0066000000 16366749 955859216 1373700096 -0.9476553798 0.3673193455 0.8149249554 703 28.0800000000 0.2428954393 0.0344610539 0.2428954393 0.0092552339 0.0067060000 16368725 955859216 1373700096 -0.9510270953 0.3669205308 0.7998530865 704 28.1200000000 0.2445331961 0.0347594518 0.2445331961 0.0092541679 0.0042660000 16370701 955859216 1373700096 -0.9505173564 0.3649207354 0.7867712379 705 28.1600000000 0.2463252693 0.0350595451 0.2463252693 0.0092483169 0.0067340000 16372677 955859216 1373700096 -0.9509695768 0.3623327613 0.7725425959 706 28.2000000000 0.2479452491 0.0353610830 0.2479452491 0.0092435693 0.0056670000 16374653 955859216 1373700096 -0.9516179562 0.3598933220 0.7588466406 707 28.2400000000 0.2494839728 0.0356639442 0.2494839728 0.0092435581 0.0041190000 16376629 955859216 1373700096 -0.9518831372 0.3612763584 0.7442790866 708 28.2800000000 0.2511511445 0.0359683047 0.2511511445 0.0092413369 0.0065920000 16378605 955859216 1373700096 -0.9551007152 0.3641704321 0.7289361358 709 28.3200000000 0.2529053092 0.0362742807 0.2529053092 0.0092400047 0.0067170000 16380581 955859216 1373700096 -0.9556023479 0.3628472090 0.7149227262 710 28.3600000000 0.2539910674 0.0365809240 0.2539910674 0.0092346371 0.0047070000 16382557 955859216 1373700096 -0.9527929425 0.3628392518 0.7048747540 711 28.4000000000 0.2554483116 0.0368887544 0.2554483116 0.0092306133 0.0066780000 16384533 955859216 1373700096 -0.9542083144 0.3631019592 0.6920214891 712 28.4400000000 0.2567642033 0.0371975682 0.2567642033 0.0092249276 0.0049890000 16386509 955859216 1373700096 -0.9545655251 0.3619926572 0.6802755594 713 28.4800000000 0.2580033839 0.0375072538 0.2580033839 0.0092197436 0.0041440000 16388485 955859216 1373700096 -0.9529560804 0.3600257933 0.6698059440 714 28.5200000000 0.2591787875 0.0378177181 0.2591787875 0.0092210457 0.0067100000 16390461 955859216 1373700096 -0.9537965655 0.3606080413 0.6583976746 715 28.5600000000 0.2606868446 0.0381294232 0.2606868446 0.0092206712 0.0063440000 16392437 955859216 1373700096 -0.9557988048 0.3640755117 0.6437866092 716 28.6000000000 0.2622305453 0.0384424136 0.2622305453 0.0092161242 0.0065230000 16394413 955859216 1373700096 -0.9561157227 0.3649349809 0.6309762597 717 28.6400000000 0.2651643455 0.0387586227 0.2651643455 0.0092140922 0.0048600000 16396389 955859216 1373700096 -0.9548365474 0.3636611104 0.6219685674 718 28.6800000000 0.2645805180 0.0390731379 0.2651643455 0.0092093051 0.0065590000 16398365 955859216 1373700096 -0.9555005431 0.3622103631 0.6134370565 719 28.7200000000 0.2657242715 0.0393883690 0.2657242715 0.0092072052 0.0050040000 16400341 955859216 1373700096 -0.9584579468 0.3624478877 0.6006223559 720 28.7600000000 0.2657021284 0.0397026936 0.2657242715 0.0092015701 0.0066350000 16402317 955859216 1373700096 -0.9604154229 0.3612917960 0.5897768140 721 28.8000000000 0.2679744959 0.0400192981 0.2679744959 0.0091994674 0.0067400000 16404293 955859216 1373700096 -0.9595771432 0.3648390174 0.5787037015 722 28.8400000000 0.2698233426 0.0403375862 0.2698233426 0.0091985820 0.0050510000 16406269 955859216 1373700096 -0.9654654860 0.3687655926 0.5662242770 723 28.8800000000 0.2707366645 0.0406562571 0.2707366645 0.0091959148 0.0067920000 16408245 955859216 1373700096 -0.9713960290 0.3692311347 0.5549079180 724 28.9200000000 0.2690225542 0.0409716802 0.2707366645 0.0091969707 0.0066460000 16410221 955859216 1373700096 -0.9744598866 0.3677305877 0.5465683341 725 28.9600000000 0.2734189332 0.0412922971 0.2734189332 0.0091942891 0.0068320000 16412197 955859216 1373700096 -0.9791914225 0.3726384640 0.5340874791 726 29.0000000000 0.2745169103 0.0416135431 0.2745169103 0.0091946120 0.0049340000 16414173 955859216 1373700096 -0.9819431901 0.3715047836 0.5206570625 727 29.0400000000 0.2770241499 0.0419373541 0.2770241499 0.0091935219 0.0067240000 16416149 955859216 1373700096 -0.9926481843 0.3728131652 0.5005042553 728 29.0800000000 0.2786017060 0.0422624425 0.2786017060 0.0091923013 0.0052280000 16418125 955859216 1373700096 -1.0036516190 0.3735392988 0.4861683547 729 29.1200000000 0.2799283564 0.0425884589 0.2799283564 0.0092114713 0.0067570000 16420101 955859216 1373700096 -1.0067312717 0.3690586090 0.4779335856 730 29.1600000000 0.2806413174 0.0429145587 0.2806413174 0.0092068052 0.0050810000 16422077 955859216 1373700096 -1.0096012354 0.3695329726 0.4689819217 731 29.2000000000 0.2822107971 0.0432419133 0.2822107971 0.0092020692 0.0051880000 16424053 955859216 1373700096 -1.0183664560 0.3736334741 0.4550689757 732 29.2400000000 0.2829508781 0.0435693846 0.2829508781 0.0092036769 0.0067900000 16426029 955859216 1373700096 -1.0239632130 0.3755071461 0.4442853332 733 29.2800000000 0.2840197086 0.0438974205 0.2840197086 0.0092017498 0.0072800000 16428005 955859216 1373700096 -1.0275242329 0.3792309761 0.4343541563 734 29.3200000000 0.2859491408 0.0442271912 0.2859491408 0.0091977247 0.0070370000 16429981 955859216 1373700096 -1.0358519554 0.3852209151 0.4221400619 735 29.3600000000 0.2868238688 0.0445572547 0.2868238688 0.0092182913 0.0068380000 16431957 955859216 1373700096 -1.0408580303 0.3841795921 0.4125105143 736 29.4000000000 0.2877219319 0.0448876415 0.2877219319 0.0092199535 0.0058290000 16433933 955859216 1373700096 -1.0435746908 0.3859009445 0.4044630527 737 29.4400000000 0.2894305885 0.0452194501 0.2894305885 0.0092146642 0.0041030000 16435909 955859216 1373700096 -1.0489993095 0.3922583163 0.3923904300 738 29.4800000000 0.2900940180 0.0455512585 0.2900940180 0.0092297474 0.0069700000 16437885 955859216 1373700096 -1.0538794994 0.3939523399 0.3820964694 739 29.5200000000 0.2904103100 0.0458825969 0.2904103100 0.0092449351 0.0067630000 16439861 955859216 1373700096 -1.0543622971 0.3923786283 0.3764797151 740 29.5600000000 0.2920030355 0.0462151921 0.2920030355 0.0092403633 0.0029360000 16441837 955859216 1373700096 -1.0569638014 0.3934586942 0.3674370348 741 29.6000000000 0.2931024134 0.0465483732 0.2931024134 0.0092351417 0.0070120000 16443813 955859216 1373700096 -1.0592221022 0.3948667049 0.3567481041 742 29.6400000000 0.2941358685 0.0468820491 0.2941358685 0.0092309534 0.0070560000 16445789 955859216 1373700096 -1.0617232323 0.3969196677 0.3467246294 743 29.6800000000 0.2914323509 0.0472111881 0.2941358685 0.0092298939 0.0059360000 16447765 955859216 1373700096 -1.0649017096 0.3963104784 0.3389231563 744 29.7200000000 0.2965190411 0.0475462793 0.2965190411 0.0092274969 0.0045360000 16449741 955859216 1373700096 -1.0713942051 0.4031442404 0.3294221163 745 29.7600000000 0.2967011929 0.0478807154 0.2967011929 0.0092366456 0.0070260000 16451717 955859216 1373700096 -1.0745062828 0.4038818181 0.3239822984 746 29.8000000000 0.2974912524 0.0482153140 0.2974912524 0.0092421069 0.0070750000 16453693 955859216 1373700096 -1.0794210434 0.4055337012 0.3158625960 747 29.8400000000 0.2986683249 0.0485505925 0.2986683249 0.0092618879 0.0059130000 16455669 955859216 1373700096 -1.0746448040 0.4052903354 0.3104661107 748 29.8800000000 0.2991220653 0.0488855811 0.2991220653 0.0092594720 0.0042400000 16457645 955859216 1373700096 -1.0725436211 0.4026386738 0.3072371781 749 29.9200000000 0.2967814505 0.0492165502 0.2991220653 0.0092544778 0.0068340000 16459621 955859216 1373700096 -1.0765373707 0.4003734887 0.2995324135 750 29.9600000000 0.3010933995 0.0495523860 0.3010933995 0.0092504979 0.0071240000 16461597 955859216 1373700096 -1.0800433159 0.4072316587 0.2892884016 751 30.0000000000 0.2998691797 0.0498856973 0.3010933995 0.0092558222 0.0058270000 16463573 955859216 1373700096 -1.0813119411 0.4046756327 0.2844912708 752 30.0400000000 0.2997789383 0.0502180021 0.3010933995 0.0092519527 0.0043710000 16465549 955859216 1373700096 -1.0837723017 0.4034087062 0.2806108296 753 30.0800000000 0.3030486107 0.0505537665 0.3030486107 0.0092471372 0.0072490000 16467525 955859216 1373700096 -1.0884183645 0.4101696908 0.2713834643 754 30.1200000000 0.3039142489 0.0508897884 0.3039142489 0.0092571214 0.0055640000 16469501 955859216 1373700096 -1.0873506069 0.4079483747 0.2662360668 755 30.1600000000 0.3048861325 0.0512262074 0.3048861325 0.0092556877 0.0067330000 16471477 955859216 1373700096 -1.0832513571 0.4060425162 0.2638126314 756 30.2000000000 0.3028501272 0.0515590433 0.3048861325 0.0092497654 0.0050920000 16473453 955859216 1373700096 -1.0853214264 0.4037440419 0.2566245496 757 30.2400000000 0.3030114174 0.0518912129 0.3048861325 0.0092453624 0.0067740000 16475429 955859216 1373700096 -1.0873748064 0.4030191004 0.2498566657 758 30.2800000000 0.3029566109 0.0522224337 0.3048861325 0.0092409332 0.0055720000 16477405 955859216 1373700096 -1.0898386240 0.4033269584 0.2434051484 759 30.3200000000 0.3067702353 0.0525578063 0.3067702353 0.0092361008 0.0044120000 16479381 955859216 1373700096 -1.0913418531 0.4097349048 0.2333760709 760 30.3600000000 0.3083215952 0.0528943376 0.3083215952 0.0092428432 0.0068580000 16481357 955859216 1373700096 -1.0879029036 0.4085798562 0.2277979106 761 30.4000000000 0.3078961670 0.0532294254 0.3083215952 0.0092398417 0.0068010000 16483333 955859216 1373700096 -1.0874209404 0.4067755342 0.2229255587 762 30.4400000000 0.3070200980 0.0535624840 0.3083215952 0.0092352854 0.0068100000 16485309 955859216 1373700096 -1.0905451775 0.4058287740 0.2154380828 763 30.4800000000 0.3094202280 0.0538978153 0.3094202280 0.0092357989 0.0061520000 16487285 955859216 1373700096 -1.0910360813 0.4055723846 0.2074736804 764 30.5200000000 0.3093958199 0.0542322368 0.3094202280 0.0092321520 0.0067880000 16489261 955859216 1373700096 -1.0900298357 0.4068092704 0.2007896751 765 30.5600000000 0.3118476570 0.0545689889 0.3118476570 0.0092275796 0.0051820000 16491237 955859216 1373700096 -1.0894614458 0.4081235528 0.1917317212 766 30.6000000000 0.3146341741 0.0549084996 0.3146341741 0.0092248415 0.0042720000 16493213 955859216 1373700096 -1.0847419500 0.4054357409 0.1875191480 767 30.6400000000 0.3137471974 0.0552459686 0.3146341741 0.0092190446 0.0044160000 16495189 955859216 1373700096 -1.0846424103 0.4046696723 0.1774252057 768 30.6800000000 0.3144873977 0.0555835225 0.3146341741 0.0092150056 0.0042750000 16497165 955859216 1373700096 -1.0843241215 0.4041351974 0.1682685614 769 30.7200000000 0.3158593774 0.0559219827 0.3158593774 0.0092136996 0.0043820000 16499141 955859216 1373700096 -1.0781546831 0.3993689120 0.1652260870 770 30.7600000000 0.3153957129 0.0562589616 0.3158593774 0.0092094014 0.0042690000 16501117 955859216 1373700096 -1.0771685839 0.3984553814 0.1576110125 771 30.8000000000 0.3164636791 0.0565964515 0.3164636791 0.0092050346 0.0043370000 16503093 955859216 1373700096 -1.0771887302 0.3975256979 0.1476000547 772 30.8400000000 0.3184160292 0.0569355960 0.3184160292 0.0092003748 0.0043940000 16505069 955859216 1373700096 -1.0709078312 0.3951648176 0.1413057745 773 30.8800000000 0.3190502226 0.0572746835 0.3190502226 0.0092005860 0.0043800000 16507045 955859216 1373700096 -1.0653538704 0.3938574195 0.1345068365 774 30.9200000000 0.3173792362 0.0576107359 0.3190502226 0.0092002423 0.0042810000 16509021 955859216 1373700096 -1.0668605566 0.3931324184 0.1254602224 775 30.9600000000 0.3181667030 0.0579469371 0.3190502226 0.0091974319 0.0042940000 16510997 955859216 1373700096 -1.0687904358 0.3933321834 0.1172920465 776 31.0000000000 0.3188275397 0.0582831235 0.3190502226 0.0091931526 0.0043050000 16512973 955859216 1373700096 -1.0700445175 0.3938847780 0.1106543243 777 31.0400000000 0.3210340142 0.0586212842 0.3210340142 0.0091891196 0.0069960000 16514949 955859216 1373700096 -1.0663728714 0.3949725032 0.1040754467 778 31.0800000000 0.3208405375 0.0589583269 0.3210340142 0.0091855874 0.0069990000 16516925 955859216 1373700096 -1.0669457912 0.3946875930 0.0965438485 779 31.1200000000 0.3204939365 0.0592940594 0.3210340142 0.0091830736 0.0069640000 16518901 955859216 1373700096 -1.0666623116 0.3973363340 0.0888196155 780 31.1600000000 0.3248182833 0.0596344751 0.3248182833 0.0091904019 0.0053120000 16520877 955859216 1373700096 -1.0665196180 0.4072519243 0.0800626129 781 31.2000000000 0.3256471157 0.0599750803 0.3256471157 0.0091855937 0.0070870000 16522853 955859216 1373700096 -1.0615254641 0.4084935486 0.0723470598 782 31.2400000000 0.3258150518 0.0603150291 0.3258150518 0.0091812323 0.0051810000 16524829 955859216 1373700096 -1.0574681759 0.4069021046 0.0656347424 783 31.2800000000 0.3268508613 0.0606554325 0.3268508613 0.0091768805 0.0043920000 16526805 955859216 1373700096 -1.0527794361 0.4079002440 0.0612395108 784 31.3200000000 0.3257961571 0.0609936222 0.3268508613 0.0091711959 0.0071210000 16528781 955859216 1373700096 -1.0520384312 0.4066591263 0.0523921140 785 31.3600000000 0.3263235092 0.0613316220 0.3268508613 0.0091669488 0.0057520000 16530757 955859216 1373700096 -1.0530230999 0.4054197967 0.0465130620 786 31.4000000000 0.3292063475 0.0616724296 0.3292063475 0.0091636680 0.0070740000 16532733 955859216 1373700096 -1.0493109226 0.4036003053 0.0420001782 787 31.4400000000 0.3294493854 0.0620126798 0.3294493854 0.0091583919 0.0044410000 16534709 955859216 1373700096 -1.0462023020 0.4009611905 0.0379522555 788 31.4800000000 0.3288709819 0.0623513325 0.3294493854 0.0091527824 0.0038160000 16536685 955859216 1373700096 -1.0436998606 0.4000450075 0.0327952877 789 31.5200000000 0.3287612200 0.0626889876 0.3294493854 0.0091472660 0.0038160000 16538661 955859216 1373700096 -1.0421117544 0.3997730315 0.0264598951 790 31.5600000000 0.3284066916 0.0630253391 0.3294493854 0.0091415886 0.0070950000 16540637 955859216 1373700096 -1.0402712822 0.3991466165 0.0232265778 791 31.6000000000 0.3276700079 0.0633599089 0.3294493854 0.0091359464 0.0070840000 16542613 955859216 1373700096 -1.0411541462 0.4002765715 0.0163402669 792 31.6400000000 0.3298200667 0.0636963485 0.3298200667 0.0091321347 0.0070760000 16544589 955859216 1373700096 -1.0415242910 0.3995067775 0.0107943565 793 31.6800000000 0.3308083415 0.0640331858 0.3308083415 0.0091267387 0.0071050000 16546565 955859216 1373700096 -1.0388709307 0.3973789811 0.0094503984 794 31.7200000000 0.3304958344 0.0643687811 0.3308083415 0.0091218810 0.0065980000 16548541 955859216 1373700096 -1.0406084061 0.3981239200 0.0016304911 795 31.7600000000 0.3315738440 0.0647048881 0.3315738440 0.0091173643 0.0043290000 16550517 955859216 1373700096 -1.0419826508 0.3983129859 -0.0036885657 796 31.8000000000 0.3328576088 0.0650417633 0.3328576088 0.0091124201 0.0043170000 16552493 955859216 1373700096 -1.0394099951 0.3973797858 -0.0066400967 797 31.8400000000 0.3328422308 0.0653777740 0.3328576088 0.0091067588 0.0043060000 16554469 955859216 1373700096 -1.0375663042 0.3970369399 -0.0111187659 798 31.8800000000 0.3330756724 0.0657132350 0.3330756724 0.0091011439 0.0043120000 16556445 955859216 1373700096 -1.0380777121 0.3947837055 -0.0145382248 799 31.9200000000 0.3361475468 0.0660517010 0.3361475468 0.0091040983 0.0045570000 16558421 955859216 1373700096 -1.0412975550 0.4031089246 -0.0232466310 800 31.9600000000 0.3369373083 0.0663903080 0.3369373083 0.0091038298 0.0043140000 16560397 955859216 1373700096 -1.0428671837 0.3987632394 -0.0287285969 801 32.0000000000 0.3368633389 0.0667279772 0.3369373083 0.0091061002 0.0044380000 16562373 955859216 1373700096 -1.0375540257 0.3878283799 -0.0263892431 802 32.0400000000 0.3360916376 0.0670638421 0.3369373083 0.0091094256 0.0043390000 16564349 955859216 1373700096 -1.0375148058 0.3862893581 -0.0309178047 803 32.0800000000 0.3358948529 0.0673986254 0.3369373083 0.0091097168 0.0043670000 16566325 955859216 1373700096 -1.0389634371 0.3872653842 -0.0384739526 804 32.1199999990 0.3372702301 0.0677342866 0.3372702301 0.0091055362 0.0070730000 16568301 955859216 1373700096 -1.0389388800 0.3854334950 -0.0417507812 805 32.1600000000 0.3388791978 0.0680711126 0.3388791978 0.0091042513 0.0071480000 16570277 955859216 1373700096 -1.0393880606 0.3830249310 -0.0468157344 806 32.2000000000 0.3386959136 0.0684068754 0.3388791978 0.0091153176 0.0061230000 16572253 955859216 1373700096 -1.0362020731 0.3859375119 -0.0638232604 807 32.2400000000 0.3385435641 0.0687416172 0.3388791978 0.0091136548 0.0071440000 16574229 955859216 1373700096 -1.0349726677 0.3873424530 -0.0691793188 808 32.2800000000 0.3371087611 0.0690737548 0.3388791978 0.0091123684 0.0044020000 16576205 955859216 1373700096 -1.0357521772 0.3920485377 -0.0775500312 809 32.3200000000 0.3388612866 0.0694072375 0.3388791978 0.0091082259 0.0037620000 16578181 955859216 1373700096 -1.0388239622 0.3930563927 -0.0851382315 810 32.3600000000 0.3434920311 0.0697456138 0.3434920311 0.0091138139 0.0039560000 16580157 955859216 1373700096 -1.0425361395 0.3934770823 -0.0899757594 811 32.4000000000 0.3447360396 0.0700846895 0.3447360396 0.0091091658 0.0070660000 16582133 955859216 1373700096 -1.0431802273 0.3884415925 -0.0962076411 812 32.4399999990 0.3446266651 0.0704227954 0.3447360396 0.0091105047 0.0071670000 16584109 955859216 1373700096 -1.0426785946 0.3804992735 -0.0977136791 813 32.4800000000 0.3459506333 0.0707616981 0.3459506333 0.0091390080 0.0057280000 16586085 955859216 1373700096 -1.0438950062 0.3921910822 -0.1094599962 814 32.5200000000 0.3479151130 0.0711021814 0.3479151130 0.0091448658 0.0073330000 16588061 955859216 1373700096 -1.0506265163 0.4046809971 -0.1257813424 815 32.5600000000 0.3483428359 0.0714423539 0.3483428359 0.0091668259 0.0053030000 16590037 955859216 1373700096 -1.0524390936 0.3959949613 -0.1282592416 816 32.6000000000 0.3477004766 0.0717809056 0.3483428359 0.0091618288 0.0043990000 16592013 955859216 1373700096 -1.0519762039 0.3918903470 -0.1327019334 817 32.6400000000 0.3468757272 0.0721176189 0.3483428359 0.0091565026 0.0071890000 16593989 955859216 1373700096 -1.0542935133 0.3912978172 -0.1402237564 818 32.6800000000 0.3479492366 0.0724548214 0.3483428359 0.0091521073 0.0072040000 16595965 955859216 1373700096 -1.0586608648 0.3894881904 -0.1484951079 819 32.7200000000 0.3504168391 0.0727942134 0.3504168391 0.0091491823 0.0052770000 16597941 955859216 1373700096 -1.0610173941 0.3852187395 -0.1540421098 820 32.7599999990 0.3498330414 0.0731320656 0.3504168391 0.0091443394 0.0070980000 16599917 955859216 1373700096 -1.0613554716 0.3852995038 -0.1605301946 821 32.7999999990 0.3501962125 0.0734695372 0.3504168391 0.0091401335 0.0072450000 16601893 955859216 1373700096 -1.0640786886 0.3865723312 -0.1689586490 822 32.8400000000 0.3515002429 0.0738077740 0.3515002429 0.0091356244 0.0062480000 16603869 955859216 1373700096 -1.0669609308 0.3859445751 -0.1759203821 823 32.8800000000 0.3517594337 0.0741455039 0.3517594337 0.0091310798 0.0064920000 16605845 955859216 1373700096 -1.0684012175 0.3870247006 -0.1822564602 824 32.9200000000 0.3520726860 0.0744827941 0.3520726860 0.0091262764 0.0044710000 16607821 955859216 1373700096 -1.0721808672 0.3888005316 -0.1914385706 825 32.9600000000 0.3551015556 0.0748229381 0.3551015556 0.0091257580 0.0072760000 16609797 955859216 1373700096 -1.0729904175 0.3857848346 -0.1961341798 826 33.0000000000 0.3542612493 0.0751612411 0.3551015556 0.0091208158 0.0062740000 16611773 955859216 1373700096 -1.0719475746 0.3861425221 -0.2017235160 827 33.0400000000 0.3559291065 0.0755007428 0.3559291065 0.0091164841 0.0073000000 16613749 955859216 1373700096 -1.0755407810 0.3857348561 -0.2112945914 828 33.0800000000 0.3575198650 0.0758413456 0.3575198650 0.0091207538 0.0047120000 16615725 955859216 1373700096 -1.0770064592 0.3775839508 -0.2143534720 829 33.1199999990 0.3560260832 0.0761793248 0.3575198650 0.0091215487 0.0041160000 16617701 955859216 1373700096 -1.0751911402 0.3777699172 -0.2199411541 830 33.1600000000 0.3594986200 0.0765206733 0.3594986200 0.0091371876 0.0042500000 16619677 955859216 1373700096 -1.0842868090 0.3860763013 -0.2327879667 831 33.2000000000 0.3599964678 0.0768617994 0.3599964678 0.0091329935 0.0074840000 16621653 955859216 1373700096 -1.0845192671 0.3829618394 -0.2376751602 832 33.2400000000 0.3608674705 0.0772031524 0.3608674705 0.0091293557 0.0071600000 16623629 955859216 1373700096 -1.0815302134 0.3794016540 -0.2398760766 833 33.2800000000 0.3602783978 0.0775429786 0.3608674705 0.0091270866 0.0061390000 16625605 955859216 1373700096 -1.0805543661 0.3783406615 -0.2470977455 834 33.3200000000 0.3602562249 0.0778819633 0.3608674705 0.0091246341 0.0076420000 16627581 955859216 1373700096 -1.0833345652 0.3768183887 -0.2543599606 835 33.3600000000 0.3606244922 0.0782205771 0.3608674705 0.0091216959 0.0051230000 16629557 955859216 1373700096 -1.0852873325 0.3769816160 -0.2629181147 836 33.4000000000 0.3610850573 0.0785589318 0.3610850573 0.0091186573 0.0042350000 16631533 955859216 1373700096 -1.0859832764 0.3783047497 -0.2707853913 837 33.4399999990 0.3624966741 0.0788981644 0.3624966741 0.0091150603 0.0041700000 16633509 955859216 1373700096 -1.0859141350 0.3780391514 -0.2776615024 838 33.4800000000 0.3638239503 0.0792381713 0.3638239503 0.0091108591 0.0041210000 16635485 955859216 1373700096 -1.0851612091 0.3761143088 -0.2842996120 839 33.5200000000 0.3643798232 0.0795780303 0.3643798232 0.0091082196 0.0041290000 16637461 955859216 1373700096 -1.0830415487 0.3777299523 -0.2950539291 840 33.5600000000 0.3670701087 0.0799202828 0.3670701087 0.0091049527 0.0041180000 16639437 955859216 1373700096 -1.0769463778 0.3742222190 -0.3007860184 841 33.6000000000 0.3674963117 0.0802622281 0.3674963117 0.0091007948 0.0041260000 16641413 955859216 1373700096 -1.0732222795 0.3715659082 -0.3074387908 842 33.6400000000 0.3678248823 0.0806037514 0.3678248823 0.0091017949 0.0041450000 16643389 955859216 1373700096 -1.0718650818 0.3705772758 -0.3161339462 843 33.6800000000 0.3702595532 0.0809473526 0.3702595532 0.0091136587 0.0076790000 16645365 955859216 1373700096 -1.0649319887 0.3693465292 -0.3327375054 844 33.7200000000 0.3703863323 0.0812902898 0.3703863323 0.0091108863 0.0075720000 16647341 955859216 1373700096 -1.0628874302 0.3683725893 -0.3423597217 845 33.7599999990 0.3702158928 0.0816322136 0.3703863323 0.0091105570 0.0053230000 16649317 955859216 1373700096 -1.0627601147 0.3703486919 -0.3527720571 846 33.7999999990 0.3745966554 0.0819785073 0.3745966554 0.0091189864 0.0058400000 16651293 955859216 1373700096 -1.0630215406 0.3801698387 -0.3642514050 847 33.8400000000 0.3755974472 0.0823251648 0.3755974472 0.0091159724 0.0073740000 16653269 955859216 1373700096 -1.0585181713 0.3825303018 -0.3747731149 848 33.8800000000 0.3767912984 0.0826724126 0.3767912984 0.0091152112 0.0076090000 16655245 955859216 1373700096 -1.0499325991 0.3818474710 -0.3828270137 849 33.9200000000 0.3771974742 0.0830193208 0.3771974742 0.0091112779 0.0052780000 16657221 955859216 1373700096 -1.0481176376 0.3781258464 -0.3912627697 850 33.9600000000 0.3789569438 0.0833674827 0.3789569438 0.0091063704 0.0058020000 16659197 955859216 1373700096 -1.0408325195 0.3772242069 -0.4008368850 851 34.0000000000 0.3799324036 0.0837159726 0.3799324036 0.0091011378 0.0073520000 16661173 955859216 1373700096 -1.0336968899 0.3751759231 -0.4086049199 852 34.0400000000 0.3810489178 0.0840649550 0.3810489178 0.0090967749 0.0062840000 16663149 955859216 1373700096 -1.0303878784 0.3761139810 -0.4183370471 853 34.0800000000 0.3821427822 0.0844144014 0.3821427822 0.0090920996 0.0047610000 16665125 955859216 1373700096 -1.0249830484 0.3791119754 -0.4281151891 854 34.1199999990 0.3822816610 0.0847631921 0.3822816610 0.0090878188 0.0075610000 16667101 955859216 1373700096 -1.0219492912 0.3789843321 -0.4361738563 855 34.1600000000 0.3841743469 0.0851133806 0.3841743469 0.0090831309 0.0057430000 16669077 955859216 1373700096 -1.0177696943 0.3779618144 -0.4446463287 856 34.2000000000 0.3850845993 0.0854638143 0.3850845993 0.0090800674 0.0047850000 16671053 955859216 1373700096 -1.0110238791 0.3783297539 -0.4522634745 857 34.2400000000 0.3849211931 0.0858132394 0.3850845993 0.0090749349 0.0046590000 16673029 955859216 1373700096 -1.0071806908 0.3764433265 -0.4598119259 858 34.2800000000 0.3857772648 0.0861628479 0.3857772648 0.0090702647 0.0075880000 16675005 955859216 1373700096 -1.0023550987 0.3747360408 -0.4660734832 859 34.3200000000 0.3856069446 0.0865114440 0.3857772648 0.0090685988 0.0072410000 16676981 955859216 1373700096 -0.9981951118 0.3765949011 -0.4752077758 860 34.3600000000 0.3866151273 0.0868604018 0.3866151273 0.0090643043 0.0044160000 16678957 955859216 1373700096 -0.9942708611 0.3775170743 -0.4842841029 861 34.4000000000 0.3883122504 0.0872105201 0.3883122504 0.0090600279 0.0040720000 16680933 955859216 1373700096 -0.9892977476 0.3761501610 -0.4917605519 862 34.4400000000 0.3892773390 0.0875609456 0.3892773390 0.0090554255 0.0076580000 16682909 955859216 1373700096 -0.9848027229 0.3755573630 -0.4991464019 863 34.4800000000 0.3893421292 0.0879106341 0.3893421292 0.0090505661 0.0075550000 16684885 955859216 1373700096 -0.9792016745 0.3767302334 -0.5063561797 864 34.5200000000 0.3899582028 0.0882602262 0.3899582028 0.0090463142 0.0050360000 16686861 955859216 1373700096 -0.9753029943 0.3794776797 -0.5152159929 865 34.5600000000 0.3928444088 0.0886123467 0.3928444088 0.0090460390 0.0053360000 16688837 955859216 1373700096 -0.9703691602 0.3765074313 -0.5219181776 866 34.6000000000 0.3950926065 0.0889662500 0.3950926065 0.0090432208 0.0075720000 16690813 955859216 1373700096 -0.9672816992 0.3675038517 -0.5255085826 867 34.6400000000 0.3940297067 0.0893181109 0.3950926065 0.0090510549 0.0048700000 16692789 955859216 1373700096 -0.9625062943 0.3634812832 -0.5413871408 868 34.6800000000 0.3945401311 0.0896697492 0.3950926065 0.0090489488 0.0075450000 16694765 955859216 1373700096 -0.9566096067 0.3619180918 -0.5481595993 869 34.7200000000 0.3944676220 0.0900204948 0.3950926065 0.0090475423 0.0054890000 16696741 955859216 1373700096 -0.9543654919 0.3619385660 -0.5559909940 870 34.7600000000 0.3960156143 0.0903722133 0.3960156143 0.0090462861 0.0073420000 16698717 955859216 1373700096 -0.9499376416 0.3620531857 -0.5651393533 871 34.8000000000 0.3978805840 0.0907252654 0.3978805840 0.0090430433 0.0075610000 16700693 955859216 1373700096 -0.9439961910 0.3602975309 -0.5708934069 872 34.8400000000 0.3978447914 0.0910774667 0.3978805840 0.0090429464 0.0052960000 16702669 955859216 1373700096 -0.9418376684 0.3584790528 -0.5775696635 873 34.8800000000 0.3971323371 0.0914280450 0.3978805840 0.0090438161 0.0075980000 16704645 955859216 1373700096 -0.9342332482 0.3622154891 -0.5856164694 874 34.9200000000 0.3982440233 0.0917790930 0.3982440233 0.0090416006 0.0055700000 16706621 955859216 1373700096 -0.9328785539 0.3640418649 -0.5940018296 875 34.9600000000 0.3983924985 0.0921295083 0.3983924985 0.0090384882 0.0075840000 16708597 955859216 1373700096 -0.9281551242 0.3679480851 -0.6016623974 876 35.0000000000 0.4003702700 0.0924813813 0.4003702700 0.0090345635 0.0051140000 16710573 955859216 1373700096 -0.9236274958 0.3685177565 -0.6091292500 877 35.0400000000 0.4035466313 0.0928360738 0.4035466313 0.0090307198 0.0056660000 16712549 955859216 1373700096 -0.9153874516 0.3678062856 -0.6140933037 878 35.0800000000 0.4036975503 0.0931901301 0.4036975503 0.0090262880 0.0076270000 16714525 955859216 1373700096 -0.9113414884 0.3644781113 -0.6196168661 879 35.1200000000 0.4016066492 0.0935410021 0.4036975503 0.0090252135 0.0050550000 16716501 955859216 1373700096 -0.9077819586 0.3663476408 -0.6285777688 880 35.1600000000 0.4036845565 0.0938934380 0.4036975503 0.0090212777 0.0055760000 16718477 955859216 1373700096 -0.9002485871 0.3659762442 -0.6358369589 881 35.2000000000 0.4044790566 0.0942459756 0.4044790566 0.0090166194 0.0076320000 16720453 955859216 1373700096 -0.8951982260 0.3641028106 -0.6405288577 882 35.2400000000 0.4040569067 0.0945972352 0.4044790566 0.0090121415 0.0050670000 16722429 955859216 1373700096 -0.8882493377 0.3636752665 -0.6481897235 883 35.2800000000 0.4043742716 0.0949480585 0.4044790566 0.0090077538 0.0040260000 16724405 955859216 1373700096 -0.8858000636 0.3635134697 -0.6569744945 884 35.3200000000 0.4053876102 0.0952992345 0.4053876102 0.0090037100 0.0075830000 16726381 955859216 1373700096 -0.8781185150 0.3643067777 -0.6635225415 885 35.3600000000 0.4090776443 0.0956537864 0.4090776443 0.0090011830 0.0075850000 16728357 955859216 1373700096 -0.8712003231 0.3602326512 -0.6693369150 886 35.4000000000 0.4113363028 0.0960100872 0.4113363028 0.0089977766 0.0045860000 16730333 955859216 1373700096 -0.8699362278 0.3546420634 -0.6760362387 887 35.4400000000 0.4099832177 0.0963640591 0.4113363028 0.0089934735 0.0073470000 16732309 955859216 1373700096 -0.8668677807 0.3525102735 -0.6856094599 888 35.4800000000 0.4111492932 0.0967185470 0.4113363028 0.0089892265 0.0076090000 16734285 955859216 1373700096 -0.8622761369 0.3491929173 -0.6932426095 889 35.5200000000 0.4114270210 0.0970725498 0.4114270210 0.0089864519 0.0053780000 16736261 955859216 1373700096 -0.8580596447 0.3464013636 -0.7004726529 890 35.5600000000 0.4105703831 0.0974247946 0.4114270210 0.0089878850 0.0055570000 16738237 955859216 1373700096 -0.8533393145 0.3462872803 -0.7088515162 891 35.6000000000 0.4102699459 0.0977759114 0.4114270210 0.0089885008 0.0045630000 16740213 955859216 1373700096 -0.8473004103 0.3474212587 -0.7199484706 892 35.6400000000 0.4115473330 0.0981276731 0.4115473330 0.0089860394 0.0076470000 16742189 955859216 1373700096 -0.8432921171 0.3487178385 -0.7289751768 893 35.6800000000 0.4144279957 0.0984818728 0.4144279957 0.0089841800 0.0055810000 16744165 955859216 1373700096 -0.8370226622 0.3487271667 -0.7364004850 894 35.7200000000 0.4148815572 0.0988357875 0.4148815572 0.0089825085 0.0049180000 16746141 955859216 1373700096 -0.8290947676 0.3505884409 -0.7428326607 895 35.7600000000 0.4151864052 0.0991892518 0.4151864052 0.0089805201 0.0076510000 16748117 955859216 1373700096 -0.8234139681 0.3517978489 -0.7526924610 896 35.8000000000 0.4149972796 0.0995417161 0.4151864052 0.0089771847 0.0035260000 16750093 955859216 1373700096 -0.8181166649 0.3533603847 -0.7605717182 897 35.8400000000 0.4140694737 0.0998923602 0.4151864052 0.0089746682 0.0028770000 16752069 955859216 1373700096 -0.8103184700 0.3594648838 -0.7705000043 898 35.8800000000 0.4170405269 0.1002455319 0.4170405269 0.0089773859 0.0075580000 16754045 955859216 1373700096 -0.8031190634 0.3631045520 -0.7779444456 899 35.9200000000 0.4196594357 0.1006008310 0.4196594357 0.0089802009 0.0075660000 16756021 955859216 1373700096 -0.7964854240 0.3634647131 -0.7861334085 900 35.9600000000 0.4231986701 0.1009592731 0.4231986701 0.0089829542 0.0046640000 16757997 955859216 1373700096 -0.7884437442 0.3592221141 -0.7921304703 901 36.0000000000 0.4240333736 0.1013178459 0.4240333736 0.0089811164 0.0040220000 16759973 955859216 1373700096 -0.7853257656 0.3534966707 -0.7977648377 902 36.0400000000 0.4229735732 0.1016744487 0.4240333736 0.0089791537 0.0040680000 16761949 955859216 1373700096 -0.7782740593 0.3528186679 -0.8089416623 903 36.0800000000 0.4258747399 0.1020334745 0.4258747399 0.0089809258 0.0077890000 16763925 955859216 1373700096 -0.7733241916 0.3518919945 -0.8180787563 904 36.1200000000 0.4261124134 0.1023919689 0.4261124134 0.0089782582 0.0077660000 16765901 955859216 1373700096 -0.7608523369 0.3510211110 -0.8154720664 905 36.1600000000 0.4286200404 0.1027524419 0.4286200404 0.0090022244 0.0068110000 16767877 955859216 1373700096 -0.7370680571 0.3525609076 -0.8417273164 906 36.2000000000 0.4272575974 0.1031106154 0.4286200404 0.0089982584 0.0040650000 16769853 955859216 1373700096 -0.7289542556 0.3490714729 -0.8485581875 907 36.2400000000 0.4278961122 0.1034687030 0.4286200404 0.0089946926 0.0077400000 16771829 955859216 1373700096 -0.7226931453 0.3445397913 -0.8541685939 908 36.2800000000 0.4314252436 0.1038298886 0.4314252436 0.0090013460 0.0067850000 16773805 955859216 1373700096 -0.7197951078 0.3486706614 -0.8625109196 909 36.3200000000 0.4293833077 0.1041880332 0.4314252436 0.0089978377 0.0041320000 16775781 955859216 1373700096 -0.7094894648 0.3500380814 -0.8654324412 910 36.3600000000 0.4303641915 0.1045464685 0.4314252436 0.0089959342 0.0076410000 16777757 955859216 1373700096 -0.7007934451 0.3500780463 -0.8671855927 911 36.4000000000 0.4314473569 0.1049053060 0.4314473569 0.0089931660 0.0066510000 16779733 955859216 1373700096 -0.6952057481 0.3488214612 -0.8693621755 912 36.4400000000 0.4311067462 0.1052629830 0.4314473569 0.0089898327 0.0041240000 16781709 955859216 1373700096 -0.6874252558 0.3489537835 -0.8748759627 913 36.4800000000 0.4318920672 0.1056207366 0.4318920672 0.0089870195 0.0036390000 16783685 955859216 1373700096 -0.6801387668 0.3486526608 -0.8798539042 914 36.5200000000 0.4326784015 0.1059785678 0.4326784015 0.0089835728 0.0036360000 16785661 955859216 1373700096 -0.6745063663 0.3462994397 -0.8843058944 915 36.5600000000 0.4324109256 0.1063353244 0.4326784015 0.0089800287 0.0036430000 16787637 955859216 1373700096 -0.6662834287 0.3459775150 -0.8871121407 916 36.6000000000 0.4312457144 0.1066900301 0.4326784015 0.0089766260 0.0036880000 16789613 955859216 1373700096 -0.6571499705 0.3469059467 -0.8912273645 917 36.6400000000 0.4331725836 0.1070460634 0.4331725836 0.0089727304 0.0036360000 16791589 955859216 1373700096 -0.6505962610 0.3442246318 -0.8951711655 918 36.6800000000 0.4336940944 0.1074018892 0.4336940944 0.0089698279 0.0036760000 16793565 955859216 1373700096 -0.6446157694 0.3401727676 -0.8999323845 919 36.7200000000 0.4319269359 0.1077550176 0.4336940944 0.0089658468 0.0036870000 16795541 955859216 1373700096 -0.6370407939 0.3404676318 -0.9029290080 920 36.7600000000 0.4313928485 0.1081067979 0.4336940944 0.0089614821 0.0036710000 16797517 955859216 1373700096 -0.6304621696 0.3411589563 -0.9080834389 921 36.8000000000 0.4369857907 0.1084638869 0.4369857907 0.0089608052 0.0038290000 16799493 955859216 1373700096 -0.6208094358 0.3493731320 -0.9126374722 922 36.8400000000 0.4381867647 0.1088215039 0.4381867647 0.0089617705 0.0078450000 16801469 955859216 1373700096 -0.6114355922 0.3458999693 -0.9157882929 923 36.8800000000 0.4375922680 0.1091777019 0.4381867647 0.0089571006 0.0034650000 16803445 955859216 1373700096 -0.6038989425 0.3430419266 -0.9173511863 924 36.9200000000 0.4379908442 0.1095335603 0.4381867647 0.0089547741 0.0088500000 16805421 955859216 1373700096 -0.5923733711 0.3469706178 -0.9236843586 925 36.9600000000 0.4379253089 0.1098885784 0.4381867647 0.0089547158 0.0073210000 16807397 955859216 1373700096 -0.5815670490 0.3466456234 -0.9286561012 926 37.0000000000 0.4383305609 0.1102432674 0.4383305609 0.0089566743 0.0045640000 16809373 955859216 1373700096 -0.5651717782 0.3483968377 -0.9358139038 927 37.0400000000 0.4382136464 0.1105970650 0.4383305609 0.0089560566 0.0037040000 16811349 955859216 1373700096 -0.5533337593 0.3490965664 -0.9396374226 928 37.0800000000 0.4391785264 0.1109511398 0.4391785264 0.0089524090 0.0079070000 16813325 955859216 1373700096 -0.5451292992 0.3456244171 -0.9427623749 929 37.1200000000 0.4392768443 0.1113045582 0.4392768443 0.0089482995 0.0064320000 16815301 955859216 1373700096 -0.5358059406 0.3426634669 -0.9463931322 930 37.1600000000 0.4390149117 0.1116569350 0.4392768443 0.0089443930 0.0047270000 16817277 955859216 1373700096 -0.5254435539 0.3421197236 -0.9497126937 931 37.2000000000 0.4396511018 0.1120092380 0.4396511018 0.0089402363 0.0076510000 16819253 955859216 1373700096 -0.5175178051 0.3401654959 -0.9538998604 932 37.2400000000 0.4394310713 0.1123605490 0.4396511018 0.0089373714 0.0057700000 16821229 955859216 1373700096 -0.5074445009 0.3415157199 -0.9555327296 933 37.2800000000 0.4397104084 0.1127114063 0.4397104084 0.0089346184 0.0047360000 16823205 955859216 1373700096 -0.4962098598 0.3433902860 -0.9594552517 934 37.3200000000 0.4403678477 0.1130622162 0.4403678477 0.0089325455 0.0078820000 16825181 955859216 1373700096 -0.4852554500 0.3451748788 -0.9634702206 935 37.3600000000 0.4407465458 0.1134126807 0.4407465458 0.0089317980 0.0051010000 16827157 955859216 1373700096 -0.4743109345 0.3459043503 -0.9656196833 936 37.4000000000 0.4414296746 0.1137631262 0.4414296746 0.0089290887 0.0041210000 16829133 955859216 1373700096 -0.4640866220 0.3446097672 -0.9661822319 937 37.4400000000 0.4419520199 0.1141133812 0.4419520199 0.0089258577 0.0078580000 16831109 955859216 1373700096 -0.4527112842 0.3433270156 -0.9673821926 938 37.4800000000 0.4418208003 0.1144627494 0.4419520199 0.0089215303 0.0061270000 16833085 955859216 1373700096 -0.4437448382 0.3402634561 -0.9695895314 939 37.5200000000 0.4391493201 0.1148085285 0.4419520199 0.0089174439 0.0047170000 16835061 955859216 1373700096 -0.4319842160 0.3406228423 -0.9723952413 940 37.5600000000 0.4382142425 0.1151525772 0.4419520199 0.0089140756 0.0080780000 16837037 955859216 1373700096 -0.4211556613 0.3417743742 -0.9729864001 941 37.6000000000 0.4390185773 0.1154967493 0.4419520199 0.0089098565 0.0049680000 16839013 955859216 1373700096 -0.4119224846 0.3402382731 -0.9748048186 942 37.6400000000 0.4402320683 0.1158414790 0.4419520199 0.0089059686 0.0079050000 16840989 955859216 1373700096 -0.4028780460 0.3383165598 -0.9774066806 943 37.6800000000 0.4408699870 0.1161861539 0.4419520199 0.0089033165 0.0047940000 16842965 955859216 1373700096 -0.3923030794 0.3383032382 -0.9789371490 944 37.7200000000 0.4410759211 0.1165303168 0.4419520199 0.0088993819 0.0040870000 16844941 955859216 1373700096 -0.3843557239 0.3370703757 -0.9787754416 945 37.7600000000 0.4417673945 0.1168744831 0.4419520199 0.0088958917 0.0079620000 16846917 955859216 1373700096 -0.3735432327 0.3361518979 -0.9787518978 946 37.8000000000 0.4418562651 0.1172180156 0.4419520199 0.0088924332 0.0071790000 16848893 955859216 1373700096 -0.3633504510 0.3344514370 -0.9795518517 947 37.8400000000 0.4418493807 0.1175608153 0.4419520199 0.0088932507 0.0042620000 16850869 955859216 1373700096 -0.3529185951 0.3324359655 -0.9819511771 948 37.8800000000 0.4421101809 0.1179031670 0.4421101809 0.0088923199 0.0058250000 16852845 955859216 1373700096 -0.3430790007 0.3303273022 -0.9835396409 949 37.9200000000 0.4410551488 0.1182436854 0.4421101809 0.0088914955 0.0058420000 16854821 955859216 1373700096 -0.3326130211 0.3292212486 -0.9861052632 950 37.9600000000 0.4408637881 0.1185832855 0.4421101809 0.0088884912 0.0077730000 16856797 955859216 1373700096 -0.3225125968 0.3287256360 -0.9880945086 951 38.0000000000 0.4416160882 0.1189229625 0.4421101809 0.0088851787 0.0046930000 16858773 955859216 1373700096 -0.3133808672 0.3275200129 -0.9893971682 952 38.0400000000 0.4418901205 0.1192622137 0.4421101809 0.0088832255 0.0079700000 16860749 955859216 1373700096 -0.3033243716 0.3253339231 -0.9917916656 953 38.0800000000 0.4417945743 0.1196006527 0.4421101809 0.0088810731 0.0048570000 16862725 955859216 1373700096 -0.2935405076 0.3246755004 -0.9929471612 954 38.1200000000 0.4417126179 0.1199382963 0.4421101809 0.0088783010 0.0041100000 16864701 955859216 1373700096 -0.2829089165 0.3237309158 -0.9947407246 955 38.1600000000 0.4400764406 0.1202735195 0.4421101809 0.0088764751 0.0079810000 16866677 955859216 1373700096 -0.2728403807 0.3230729103 -0.9959918857 956 38.2000000000 0.4398345351 0.1206077883 0.4421101809 0.0088730206 0.0058310000 16868653 955859216 1373700096 -0.2612077892 0.3223133087 -0.9980322123 957 38.2400000000 0.4395035207 0.1209410127 0.4421101809 0.0088689078 0.0079460000 16870629 955859216 1373700096 -0.2497642636 0.3215298951 -1.0005389452 958 38.2800000000 0.4398335218 0.1212738859 0.4421101809 0.0088648591 0.0048270000 16872605 955859216 1373700096 -0.2405158281 0.3200327754 -1.0030242205 959 38.3200000000 0.4380038083 0.1216041569 0.4421101809 0.0088610990 0.0074090000 16874581 955859216 1373700096 -0.2296513021 0.3208715618 -1.0049055815 960 38.3600000000 0.4364418387 0.1219321128 0.4421101809 0.0088594343 0.0044800000 16876557 955859216 1373700096 -0.2166437507 0.3232055902 -1.0059623718 961 38.4000000000 0.4409481585 0.1222640754 0.4421101809 0.0088651068 0.0079170000 16878533 955859216 1373700096 -0.2074292302 0.3214064240 -1.0072323084 962 38.4400000000 0.4426211715 0.1225970870 0.4426211715 0.0088633603 0.0047750000 16880509 955859216 1373700096 -0.1975188702 0.3205035925 -1.0084652901 963 38.4800000000 0.4461323023 0.1229330529 0.4461323023 0.0088678190 0.0081630000 16882485 955859216 1373700096 -0.1880567372 0.3215480745 -1.0146464109 964 38.5200000000 0.4462810457 0.1232684761 0.4462810457 0.0088667766 0.0066120000 16884461 955859216 1373700096 -0.1776906103 0.3196600080 -1.0149576664 965 38.5600000000 0.4463422298 0.1236032676 0.4463422298 0.0088637370 0.0047910000 16886437 955859216 1373700096 -0.1669475883 0.3172934353 -1.0183100700 966 38.6000000000 0.4438460469 0.1239347819 0.4463422298 0.0088596009 0.0077860000 16888413 955859216 1373700096 -0.1569475383 0.3127675653 -1.0184363127 967 38.6400000000 0.4411005378 0.1242627713 0.4463422298 0.0088567175 0.0063180000 16890389 955859216 1373700096 -0.1461283118 0.3089025319 -1.0185604095 968 38.6800000000 0.4393572807 0.1245882821 0.4463422298 0.0088532372 0.0046550000 16892365 955859216 1373700096 -0.1364810616 0.3052613139 -1.0197311640 969 38.7200000000 0.4382613599 0.1249119901 0.4463422298 0.0088493650 0.0079740000 16894341 955859216 1373700096 -0.1267838478 0.3039573431 -1.0197786093 970 38.7600000000 0.4381598830 0.1252349261 0.4463422298 0.0088454517 0.0048480000 16896317 955859216 1373700096 -0.1203710064 0.3016719520 -1.0209077597 971 38.8000000000 0.4379823208 0.1255570141 0.4463422298 0.0088418991 0.0078750000 16898293 955859216 1373700096 -0.1110899970 0.3014392555 -1.0216863155 972 38.8400000000 0.4392244220 0.1258797172 0.4463422298 0.0088421727 0.0070200000 16900269 955859216 1373700096 -0.1024702638 0.3024523854 -1.0219278336 973 38.8800000000 0.4412693977 0.1262038587 0.4463422298 0.0088496979 0.0046520000 16902245 955859216 1373700096 -0.0936441943 0.3042659461 -1.0215411186 974 38.9200000000 0.4432245195 0.1265293419 0.4463422298 0.0088559156 0.0077260000 16904221 955859216 1373700096 -0.0865145251 0.3040402532 -1.0206177235 975 38.9600000000 0.4435814321 0.1268545235 0.4463422298 0.0088541745 0.0066720000 16906197 955859216 1373700096 -0.0786935315 0.3025173843 -1.0191910267 976 39.0000000000 0.4432660043 0.1271787156 0.4463422298 0.0088498618 0.0069730000 16908173 955859216 1373700096 -0.0732195675 0.3001061082 -1.0159331560 977 39.0400000000 0.4418550432 0.1275007999 0.4463422298 0.0088464759 0.0048570000 16910149 955859216 1373700096 -0.0629872307 0.2985100150 -1.0181876421 978 39.0800000000 0.4406977892 0.1278210422 0.4463422298 0.0088427844 0.0079790000 16912125 955859216 1373700096 -0.0538779274 0.2956511676 -1.0178318024 979 39.1200000000 0.4386391342 0.1281385275 0.4463422298 0.0088434466 0.0053220000 16914101 955859216 1373700096 -0.0457111001 0.2915145457 -1.0174868107 980 39.1600000000 0.4372996390 0.1284539980 0.4463422298 0.0088415430 0.0041790000 16916077 955859216 1373700096 -0.0344228856 0.2899869978 -1.0171858072 981 39.2000000000 0.4353603721 0.1287668485 0.4463422298 0.0088375747 0.0041650000 16918053 955859216 1373700096 -0.0226733368 0.2893795371 -1.0161007643 982 39.2400000000 0.4351279438 0.1290788252 0.4463422298 0.0088340290 0.0080460000 16920029 955859216 1373700096 -0.0173158180 0.2877798676 -1.0157474279 983 39.2800000000 0.4353553653 0.1293903985 0.4463422298 0.0088321960 0.0083780000 16922005 955859216 1373700096 -0.0084139127 0.2867093980 -1.0174181461 984 39.3200000000 0.4462916851 0.1297124526 0.4463422298 0.0088458366 0.0051880000 16923981 955859216 1373700096 0.0030237685 0.2970996201 -1.0358740091 985 39.3600000000 0.4444614351 0.1300319948 0.4463422298 0.0088433064 0.0075190000 16925957 955859216 1373700096 0.0099311946 0.2927419543 -1.0364105701 986 39.4000000000 0.4425860643 0.1303489867 0.4463422298 0.0088396816 0.0044700000 16927933 955859216 1373700096 0.0179892536 0.2896262109 -1.0348746777 987 39.4400000000 0.4412688017 0.1306640017 0.4463422298 0.0088363489 0.0041400000 16929909 955859216 1373700096 0.0275472514 0.2871471941 -1.0337334871 988 39.4800000000 0.4401708543 0.1309772678 0.4463422298 0.0088325555 0.0041670000 16931885 955859216 1373700096 0.0379463956 0.2852134407 -1.0332912207 989 39.5200000000 0.4386529624 0.1312883655 0.4463422298 0.0088287807 0.0037060000 16933861 955859216 1373700096 0.0467631556 0.2828480005 -1.0340403318 990 39.5600000000 0.4373207986 0.1315974892 0.4463422298 0.0088249503 0.0029240000 16935837 955859216 1373700096 0.0563979670 0.2817119658 -1.0342833996 991 39.6000000000 0.4363624156 0.1319050219 0.4463422298 0.0088218993 0.0082280000 16937813 955859216 1373700096 0.0662232712 0.2826273441 -1.0321316719 992 39.6400000000 0.4350886047 0.1322106505 0.4463422298 0.0088195030 0.0080780000 16939789 955859216 1373700096 0.0758514255 0.2837285697 -1.0307446718 993 39.6800000000 0.4345698953 0.1325151412 0.4463422298 0.0088212411 0.0049050000 16941765 955859216 1373700096 0.0851479769 0.2852877676 -1.0277885199 994 39.7200000000 0.4347428679 0.1328191933 0.4463422298 0.0088230943 0.0041080000 16943741 955859216 1373700096 0.0947796851 0.2861615121 -1.0262711048 995 39.7600000000 0.4362562299 0.1331241551 0.4463422298 0.0088243833 0.0081360000 16945717 955859216 1373700096 0.1032511294 0.2862685919 -1.0261645317 996 39.8000000000 0.4375854135 0.1334298391 0.4463422298 0.0088222193 0.0072850000 16947693 955859216 1373700096 0.1127298698 0.2864002883 -1.0260096788 997 39.8400000000 0.4379889667 0.1337353147 0.4463422298 0.0088200011 0.0042880000 16949669 955859216 1373700096 0.1233596355 0.2867741287 -1.0254995823 998 39.8800000000 0.4392004311 0.1340413919 0.4463422298 0.0088176747 0.0036310000 16951645 955859216 1373700096 0.1324084699 0.2868812382 -1.0255804062 999 39.9200000000 0.4410223663 0.1343486802 0.4463422298 0.0088146806 0.0082090000 16953621 955859216 1373700096 0.1448605061 0.2927954495 -1.0241088867 1000 39.9600000000 0.4424991608 0.1346568307 0.4463422298 0.0088142698 0.0074320000 16955597 955859216 1373700096 0.1534816772 0.2934191823 -1.0255523920 1001 40.0000000000 0.4407818019 0.1349626498 0.4463422298 0.0088107921 0.0042940000 16957573 955859216 1373700096 0.1629849821 0.2904334664 -1.0251706839 1002 40.0400000000 0.4388663471 0.1352659469 0.4463422298 0.0088071184 0.0081690000 16959549 955859216 1373700096 0.1738565266 0.2896753550 -1.0226033926 1003 40.0800000000 0.4371840358 0.1355669620 0.4463422298 0.0088044199 0.0070430000 16961525 955859216 1373700096 0.1854092032 0.2903685272 -1.0204069614 1004 40.1200000000 0.4380967021 0.1358682864 0.4463422298 0.0088053839 0.0041350000 16963501 955859216 1373700096 0.1940143108 0.2902569771 -1.0186837912 1005 40.1600000000 0.4372140169 0.1361681329 0.4463422298 0.0088022847 0.0081750000 16965477 955859216 1373700096 0.2036058605 0.2895916104 -1.0172201395 1006 40.2000000000 0.4356947839 0.1364658731 0.4463422298 0.0087993627 0.0053020000 16967453 955859216 1373700096 0.2139338553 0.2903299332 -1.0141744614 1007 40.2400000000 0.4348650873 0.1367621981 0.4463422298 0.0087975233 0.0041030000 16969429 955859216 1373700096 0.2237855047 0.2908325791 -1.0108561516 1008 40.2800000000 0.4350748360 0.1370581431 0.4463422298 0.0087958827 0.0082060000 16971405 955859216 1373700096 0.2318526953 0.2905912697 -1.0075635910 1009 40.3200000000 0.4343009889 0.1373527347 0.4463422298 0.0087931695 0.0063340000 16973381 955859216 1373700096 0.2405640930 0.2903438509 -1.0039390326 1010 40.3600000000 0.4333565533 0.1376458077 0.4463422298 0.0087909474 0.0068290000 16975357 955859216 1373700096 0.2506706119 0.2900453806 -1.0006566048 1011 40.4000000000 0.4332049489 0.1379381511 0.4463422298 0.0087888592 0.0048690000 16977333 955859216 1373700096 0.2587516308 0.2892401516 -0.9979590178 1012 40.4400000000 0.4320669472 0.1382287922 0.4463422298 0.0087846915 0.0083370000 16979309 955859216 1373700096 0.2670756876 0.2866123319 -0.9967346787 1013 40.4800000000 0.4301657379 0.1385169827 0.4463422298 0.0087808542 0.0054220000 16981285 955859216 1373700096 0.2764319777 0.2854403853 -0.9928222895 1014 40.5200000000 0.4281851649 0.1388026515 0.4463422298 0.0087766751 0.0041770000 16983261 955859216 1373700096 0.2840074301 0.2834385335 -0.9893423915 1015 40.5600000000 0.4267749488 0.1390863681 0.4463422298 0.0087730392 0.0081570000 16985237 955859216 1373700096 0.2923385203 0.2806270123 -0.9882273078 1016 40.6000000000 0.4261512458 0.1393689122 0.4463422298 0.0087690564 0.0059130000 16987213 955859216 1373700096 0.3000053167 0.2778251469 -0.9869168997 1017 40.6400000000 0.4250721633 0.1396498397 0.4463422298 0.0087660794 0.0081550000 16989189 955859216 1373700096 0.3071756959 0.2772505879 -0.9837502241 1018 40.6800000000 0.4255627096 0.1399306971 0.4463422298 0.0087621695 0.0048240000 16991165 955859216 1373700096 0.3156722784 0.2775588632 -0.9813494682 1019 40.7200000000 0.4257802069 0.1402112168 0.4463422298 0.0087581593 0.0081680000 16993141 955859216 1373700096 0.3225795627 0.2781631052 -0.9774794579 1020 40.7600000000 0.4258175492 0.1404912230 0.4463422298 0.0087542866 0.0049750000 16995117 955859216 1373700096 0.3313255310 0.2782316804 -0.9738772511 1021 40.8000000000 0.4254506528 0.1407703214 0.4463422298 0.0087505443 0.0081700000 16997093 955859216 1373700096 0.3394547105 0.2782927155 -0.9702160358 1022 40.8400000000 0.4244777560 0.1410479216 0.4463422298 0.0087463539 0.0049160000 16999069 955859216 1373700096 0.3469026387 0.2781719863 -0.9643682241 1023 40.8800000000 0.4235204160 0.1413240433 0.4463422298 0.0087422016 0.0077470000 17001045 955859216 1373700096 0.3542534411 0.2775216997 -0.9590123892 1024 40.9200000000 0.4225484729 0.1415986765 0.4463422298 0.0087385848 0.0059730000 17003021 955859216 1373700096 0.3635474741 0.2773201466 -0.9548170567 1025 40.9600000000 0.4225851893 0.1418728097 0.4463422298 0.0087357044 0.0069850000 17115493 955859216 1373700096 0.3731797636 0.2779277563 -0.9500084519 1026 41.0000000000 0.4230571985 0.1421468686 0.4463422298 0.0087333456 0.0071830000 17310077 955859216 1373700096 0.3794297576 0.2781987786 -0.9445600510 1027 41.0400000000 0.4225049317 0.1424198560 0.4463422298 0.0087293639 0.0042580000 17312053 955859216 1373700096 0.3877944052 0.2762958109 -0.9423016906 1028 41.0800000000 0.4209361970 0.1426907862 0.4463422298 0.0087257904 0.0084100000 17314029 955859216 1373700096 0.3988392949 0.2765303552 -0.9359130859 1029 41.1200000000 0.4195297658 0.1429598232 0.4463422298 0.0087231540 0.0054190000 17316005 955859216 1373700096 0.4074882567 0.2751365304 -0.9321060777 1030 41.1600000000 0.4195059240 0.1432283145 0.4463422298 0.0087217637 0.0042220000 17317981 955859216 1373700096 0.4156823456 0.2746890187 -0.9288815856 1031 41.2000000000 0.4208987653 0.1434976360 0.4463422298 0.0087216784 0.0083890000 17319957 955859216 1373700096 0.4247685075 0.2752537727 -0.9252604246 1032 41.2400000000 0.4218991101 0.1437674049 0.4463422298 0.0087211480 0.0052730000 17321933 955859216 1373700096 0.4335353673 0.2760851085 -0.9217414260 1033 41.2800000000 0.4222860932 0.1440370261 0.4463422298 0.0087209379 0.0084370000 17323909 955859216 1373700096 0.4436157048 0.2774997056 -0.9175434113 1034 41.3200000000 0.4231131077 0.1443069256 0.4463422298 0.0087227113 0.0052080000 17325885 955859216 1373700096 0.4538755119 0.2788116634 -0.9120473862 1035 41.3600000000 0.4234459102 0.1445766251 0.4463422298 0.0087282754 0.0044060000 17327861 955859216 1373700096 0.4601306915 0.2789445519 -0.9098961353 1036 41.4000000000 0.4238942862 0.1448462367 0.4463422298 0.0087262104 0.0085760000 17329837 955859216 1373700096 0.4667529762 0.2769810557 -0.9071412086 1037 41.4400000000 0.4222904742 0.1451137818 0.4463422298 0.0087225748 0.0070040000 17331813 955859216 1373700096 0.4762254357 0.2745291293 -0.9031068087 1038 41.4800000000 0.4196592867 0.1453782765 0.4463422298 0.0087188400 0.0051800000 17333789 955859216 1373700096 0.4854524136 0.2737901211 -0.8969854712 1039 41.5200000000 0.4175526202 0.1456402345 0.4463422298 0.0087148994 0.0082590000 17335765 955859216 1373700096 0.4945135117 0.2734475136 -0.8914386034 1040 41.5600000000 0.4148749113 0.1458991140 0.4463422298 0.0087113336 0.0047350000 17337741 955859216 1373700096 0.5016514063 0.2736842036 -0.8848734498 1041 41.6000000000 0.4135993421 0.1461562708 0.4463422298 0.0087080680 0.0039000000 17339717 955859216 1373700096 0.5087167621 0.2725477517 -0.8811150789 1042 41.6400000000 0.4131077528 0.1464124622 0.4463422298 0.0087072771 0.0087640000 17341693 955859216 1373700096 0.5190028548 0.2739009559 -0.8757925034 1043 41.6800000000 0.4129694104 0.1466680297 0.4463422298 0.0087146399 0.0078540000 17343669 955859216 1373700096 0.5252494812 0.2751300335 -0.8706001639 1044 41.7200000000 0.4158261418 0.1469258440 0.4463422298 0.0087494944 0.0047750000 17345645 955859216 1373700096 0.5393348336 0.2784412205 -0.8658078909 1045 41.7600000000 0.4167059660 0.1471840068 0.4463422298 0.0087575314 0.0059640000 17347621 955859216 1373700096 0.5470656157 0.2793614566 -0.8641806841 1046 41.8000000000 0.4153420031 0.1474403720 0.4463422298 0.0087602720 0.0079890000 17349597 955859216 1373700096 0.5525273085 0.2790432572 -0.8586460948 1047 41.8400000000 0.4130846560 0.1476940915 0.4463422298 0.0087574951 0.0052960000 17351573 955859216 1373700096 0.5587946177 0.2768494785 -0.8537401557 1048 41.8800000000 0.4113392234 0.1479456613 0.4463422298 0.0087547582 0.0043930000 17353549 955859216 1373700096 0.5667384863 0.2758394182 -0.8469958901 1049 41.9200000000 0.4093609452 0.1481948655 0.4463422298 0.0087531676 0.0086510000 17355525 955859216 1373700096 0.5734274387 0.2743495405 -0.8407315016 1050 41.9600000000 0.4061945975 0.1484405796 0.4463422298 0.0087501532 0.0076010000 17357501 955859216 1373700096 0.5784631968 0.2720243931 -0.8336323500 1051 42.0000000000 0.4047236741 0.1486844265 0.4463422298 0.0087473049 0.0045620000 17359477 955859216 1373700096 0.5857019424 0.2699763477 -0.8264278769 1052 42.0400000000 0.4023566544 0.1489255598 0.4463422298 0.0087445088 0.0086510000 17361453 955859216 1373700096 0.5921791196 0.2692343891 -0.8180806041 1053 42.0800000000 0.3991163671 0.1491631579 0.4463422298 0.0087414251 0.0073650000 17363429 955859216 1373700096 0.5970225334 0.2679297924 -0.8092988729 1054 42.1200000000 0.3974064589 0.1493986828 0.4463422298 0.0087383882 0.0044570000 17365405 955859216 1373700096 0.6024603248 0.2666541636 -0.8013079166 1055 42.1600000000 0.3938018084 0.1496303446 0.4463422298 0.0087355642 0.0039480000 17367381 955859216 1373700096 0.6119376421 0.2634751797 -0.7874130607 1056 42.2000000000 0.3919173479 0.1498597830 0.4463422298 0.0087318956 0.0039980000 17369357 955859216 1373700096 0.6173191071 0.2618504465 -0.7782396674 1057 42.2400000000 0.3900362551 0.1500870077 0.4463422298 0.0087279812 0.0087020000 17371333 955859216 1373700096 0.6223160028 0.2606554031 -0.7692368627 1058 42.2800000000 0.3882651627 0.1503121288 0.4463422298 0.0087251509 0.0087190000 17373309 955859216 1373700096 0.6275343895 0.2602032125 -0.7595680356 1059 42.3200000000 0.3857909441 0.1505344884 0.4463422298 0.0087228525 0.0052660000 17375285 955859216 1373700096 0.6301307082 0.2599775791 -0.7518949509 1060 42.3600000000 0.3846890032 0.1507553889 0.4463422298 0.0087207011 0.0084840000 17377261 955859216 1373700096 0.6338198781 0.2598305941 -0.7443159223 1061 42.4000000000 0.3830781281 0.1509743547 0.4463422298 0.0087174970 0.0050320000 17379237 955859216 1373700096 0.6376373172 0.2592616677 -0.7372348905 1062 42.4400000000 0.3817482889 0.1511916560 0.4463422298 0.0087151836 0.0040410000 17381213 955859216 1373700096 0.6416507959 0.2592051327 -0.7291072607 1063 42.4800000000 0.3810353875 0.1514078777 0.4463422298 0.0087149959 0.0040280000 17383189 955859216 1373700096 0.6460703611 0.2593562901 -0.7213914990 1064 42.5200000000 0.3805124760 0.1516232016 0.4463422298 0.0087153825 0.0087670000 17385165 955859216 1373700096 0.6501453519 0.2592728138 -0.7145288587 1065 42.5600000000 0.3791606128 0.1518368518 0.4463422298 0.0087136594 0.0077000000 17387141 955859216 1373700096 0.6532405019 0.2588001192 -0.7079494596 1066 42.6000000000 0.3772705793 0.1520483281 0.4463422298 0.0087108955 0.0047690000 17389117 955859216 1373700096 0.6565271616 0.2584026456 -0.7003130317 1067 42.6400000000 0.3761292100 0.1522583383 0.4463422298 0.0087093146 0.0039900000 17391093 955859216 1373700096 0.6598850489 0.2580981553 -0.6935157180 1068 42.6800000000 0.3740231097 0.1524659832 0.4463422298 0.0087064709 0.0088520000 17393069 955859216 1373700096 0.6617084146 0.2576700151 -0.6864726543 1069 42.7200000000 0.3722627461 0.1526715929 0.4463422298 0.0087063915 0.0064410000 17395045 955859216 1373700096 0.6675832868 0.2587013245 -0.6782460809 1070 42.7600000000 0.3758063316 0.1528801300 0.4463422298 0.0087109105 0.0073780000 17397021 955859216 1373700096 0.6741089821 0.2672369778 -0.6712557077 1071 42.8000000000 0.3728884757 0.1530855533 0.4463422298 0.0087177712 0.0048400000 17398997 955859216 1373700096 0.6782810092 0.2665303946 -0.6617437005 1072 42.8400000000 0.3709767461 0.1532888100 0.4463422298 0.0087138901 0.0043700000 17400973 955859216 1373700096 0.6824023724 0.2671983540 -0.6540361643 1073 42.8800000000 0.3701329529 0.1534909015 0.4463422298 0.0087119290 0.0040330000 17402949 955859216 1373700096 0.6850551367 0.2675180137 -0.6462675333 1074 42.9200000000 0.3687101305 0.1536912918 0.4463422298 0.0087095101 0.0088250000 17404925 955859216 1373700096 0.6900674701 0.2685307562 -0.6381964684 1075 42.9600000000 0.3669392169 0.1538896620 0.4463422298 0.0087068049 0.0080890000 17406901 955859216 1373700096 0.6937697530 0.2694114745 -0.6290784478 1076 43.0000000000 0.3653864264 0.1540862203 0.4463422298 0.0087062384 0.0049530000 17408877 955859216 1373700096 0.6974860430 0.2708796859 -0.6230640411 1077 43.0400000000 0.3642778695 0.1542813843 0.4463422298 0.0087057461 0.0064320000 17410853 955859216 1373700096 0.7028957009 0.2717255354 -0.6166976094 1078 43.0800000000 0.3630833328 0.1544750782 0.4463422298 0.0087052489 0.0082990000 17412829 955859216 1373700096 0.7057521343 0.2722900212 -0.6109610796 1079 43.1200000000 0.3617790341 0.1546672042 0.4463422298 0.0087030087 0.0058610000 17414805 955859216 1373700096 0.7093548775 0.2728718221 -0.6049772501 1080 43.1600000000 0.3603153229 0.1548576191 0.4463422298 0.0086995172 0.0045540000 17416781 955859216 1373700096 0.7149367929 0.2735652328 -0.5955242515 1081 43.2000000000 0.3592545092 0.1550467004 0.4463422298 0.0086972533 0.0088810000 17418757 955859216 1373700096 0.7186231017 0.2732832134 -0.5877910256 1082 43.2400000000 0.3571941853 0.1552335280 0.4463422298 0.0086935087 0.0055210000 17420733 955859216 1373700096 0.7208407521 0.2735222876 -0.5801576376 1083 43.2800000000 0.3556136489 0.1554185512 0.4463422298 0.0086895938 0.0045650000 17422709 955859216 1373700096 0.7257114649 0.2732242942 -0.5699378252 1084 43.3200000000 0.3541070521 0.1556018432 0.4463422298 0.0086862070 0.0083480000 17424685 955859216 1373700096 0.7308726907 0.2730359435 -0.5595294833 1085 43.3600000000 0.3480476439 0.1557792126 0.4463422298 0.0086828957 0.0069440000 17426661 955859216 1373700096 0.7331100702 0.2699202001 -0.5529858470 1086 43.4000000000 0.3456804156 0.1559540756 0.4463422298 0.0086790680 0.0052100000 17428637 955859216 1373700096 0.7363502979 0.2690398693 -0.5454283357 1087 43.4400000000 0.3475254774 0.1561303142 0.4463422298 0.0086753721 0.0079860000 17430613 955859216 1373700096 0.7403122783 0.2725784779 -0.5365986824 1088 43.4800000000 0.3443190753 0.1563032818 0.4463422298 0.0086715904 0.0048600000 17432589 955859216 1373700096 0.7417126298 0.2700686455 -0.5295794606 1089 43.5200000000 0.3422269225 0.1564740106 0.4463422298 0.0086677464 0.0040430000 17434565 955859216 1373700096 0.7444798350 0.2685606778 -0.5217438340 1090 43.5600000000 0.3393790722 0.1566418134 0.4463422298 0.0086640288 0.0088400000 17436541 955859216 1373700096 0.7484996319 0.2674409449 -0.5122445226 1091 43.6000000000 0.3378534019 0.1568079102 0.4463422298 0.0086625673 0.0066330000 17438517 955859216 1373700096 0.7518525720 0.2671794295 -0.5029514432 1092 43.6400000000 0.3352372646 0.1569713070 0.4463422298 0.0086605504 0.0073360000 17440493 955859216 1373700096 0.7538648248 0.2669732273 -0.4950078726 1093 43.6800000000 0.3332979679 0.1571326306 0.4463422298 0.0086594274 0.0045590000 17442469 955859216 1373700096 0.7574299574 0.2666306198 -0.4859653711 1094 43.7200000000 0.3303517997 0.1572909662 0.4463422298 0.0086577157 0.0087720000 17444445 955859216 1373700096 0.7588405609 0.2662236691 -0.4789026678 1095 43.7600000000 0.3281725347 0.1574470224 0.4463422298 0.0086547711 0.0090140000 17446421 955859216 1373700096 0.7590487599 0.2653508186 -0.4726451635 1096 43.8000000000 0.3255098164 0.1576003644 0.4463422298 0.0086512145 0.0097310000 17448397 955859216 1373700096 0.7612110972 0.2645947337 -0.4651546478 1097 43.8400000000 0.3226886094 0.1577508551 0.4463422298 0.0086479428 0.0090450000 17450373 955859216 1373700096 0.7649682760 0.2641208470 -0.4552123249 1098 43.8800000000 0.3220157623 0.1579004588 0.4463422298 0.0086510555 0.0079520000 17452349 955859216 1373700096 0.7687103152 0.2646038234 -0.4444718659 1099 43.9200000000 0.3199874461 0.1580479447 0.4463422298 0.0086533501 0.0048620000 17454325 955859216 1373700096 0.7698216438 0.2646003664 -0.4369102716 1100 43.9600000000 0.3160901964 0.1581916195 0.4463422298 0.0086510027 0.0039230000 17456301 955859216 1373700096 0.7712082863 0.2632662058 -0.4299383163 1101 44.0000000000 0.3121160865 0.1583314237 0.4463422298 0.0086474896 0.0037850000 17458277 955859216 1373700096 0.7750709057 0.2611020207 -0.4222607017 1102 44.0400000000 0.3086613715 0.1584678393 0.4463422298 0.0086438259 0.0090310000 17460253 955859216 1373700096 0.7778285742 0.2582968473 -0.4149087965 1103 44.0800000000 0.3040980101 0.1585998702 0.4463422298 0.0086407993 0.0078090000 17462229 955859216 1373700096 0.7817299962 0.2548029721 -0.4065282047 1104 44.1200000000 0.3006016314 0.1587284950 0.4463422298 0.0086371619 0.0048250000 17464205 955859216 1373700096 0.7848846912 0.2514587343 -0.3971718252 1105 44.1600000000 0.2967338562 0.1588533868 0.4463422298 0.0086336594 0.0040820000 17466181 955859216 1373700096 0.7889248729 0.2482275665 -0.3867184222 1106 44.2000000000 0.2932995260 0.1589749475 0.4463422298 0.0086305826 0.0090150000 17468157 955859216 1373700096 0.7933429480 0.2452133447 -0.3764505088 1107 44.2400000000 0.2898760140 0.1590931959 0.4463422298 0.0086281876 0.0055870000 17470133 955859216 1373700096 0.7977553010 0.2427047640 -0.3662607670 1108 44.2800000000 0.2868481576 0.1592084983 0.4463422298 0.0086260012 0.0046080000 17472109 955859216 1373700096 0.8018301725 0.2398482561 -0.3562895656 1109 44.3200000000 0.2823984325 0.1593195802 0.4463422298 0.0086227034 0.0086080000 17474085 955859216 1373700096 0.8051714301 0.2365588397 -0.3469101489 1110 44.3600000000 0.2771726549 0.1594257542 0.4463422298 0.0086194543 0.0049720000 17476061 955859216 1373700096 0.8088175654 0.2339496464 -0.3373317719 1111 44.4000000000 0.2750702798 0.1595298447 0.4463422298 0.0086166292 0.0063260000 17478037 955859216 1373700096 0.8124882579 0.2320881784 -0.3272111714 1112 44.4400000000 0.2712104917 0.1596302769 0.4463422298 0.0086136656 0.0053460000 17480013 955859216 1373700096 0.8177482486 0.2294622362 -0.3160430193 1113 44.4800000000 0.2663952708 0.1597262023 0.4463422298 0.0086139808 0.0053550000 17481989 955859216 1373700096 0.8231862783 0.2266621143 -0.3051022887 1114 44.5200000000 0.2624571025 0.1598184204 0.4463422298 0.0086140182 0.0053000000 17483965 955859216 1373700096 0.8253293633 0.2235274911 -0.2976550460 1115 44.5600000000 0.2563250363 0.1599049734 0.4463422298 0.0086130236 0.0055860000 17485941 955859216 1373700096 0.8278049231 0.2187785059 -0.2898393273 1116 44.6000000000 0.2503117621 0.1599859831 0.4463422298 0.0086161020 0.0033170000 17487917 955859216 1373700096 0.8287342191 0.2138647586 -0.2798875272 1117 44.6400000000 0.2443234473 0.1600614866 0.4463422298 0.0086234363 0.0090900000 17489893 955859216 1373700096 0.8236969113 0.2085432708 -0.2716360688 1118 44.6800000000 0.2417930216 0.1601345917 0.4463422298 0.0086382737 0.0077420000 17491869 955859216 1373700096 0.8090449572 0.2010384202 -0.2645655274 1119 44.7200000000 0.2368719280 0.1602031684 0.4463422298 0.0086357221 0.0047640000 17493845 955859216 1373700096 0.8121568561 0.1964382380 -0.2552298605 1120 44.7600000000 0.2337832749 0.1602688650 0.4463422298 0.0086324732 0.0042890000 17495821 955859216 1373700096 0.8166058064 0.1944774985 -0.2440893501 1121 44.8000000000 0.2327143997 0.1603334908 0.4463422298 0.0086287493 0.0091770000 17497797 955859216 1373700096 0.8194572926 0.1948941648 -0.2334364653 1122 44.8400000000 0.2296587229 0.1603952780 0.4463422298 0.0086254377 0.0055090000 17499773 955859216 1373700096 0.8214827776 0.1933684200 -0.2242413610 1123 44.8800000000 0.2256038636 0.1604533444 0.4463422298 0.0086221579 0.0046890000 17501749 955859216 1373700096 0.8262107372 0.1921126842 -0.2136186808 1124 44.9200000000 0.2225194424 0.1605085633 0.4463422298 0.0086192960 0.0042960000 17503725 955859216 1373700096 0.8304200172 0.1909064800 -0.2036207914 1125 44.9600000000 0.2184801549 0.1605600936 0.4463422298 0.0086162062 0.0092850000 17505701 955859216 1373700096 0.8342828155 0.1900213212 -0.1937994957 1126 45.0000000000 0.2153731883 0.1606087731 0.4463422298 0.0086129366 0.0069890000 17507677 955859216 1373700096 0.8378934264 0.1887381822 -0.1845875382 1127 45.0400000000 0.2125228047 0.1606548370 0.4463422298 0.0086093925 0.0047570000 17509653 955859216 1373700096 0.8400253057 0.1867159307 -0.1768922359 1128 45.0800000000 0.2098416835 0.1606984424 0.4463422298 0.0086059369 0.0042400000 17511629 955859216 1373700096 0.8432203531 0.1847611815 -0.1677329093 1129 45.1200000000 0.2072878033 0.1607397084 0.4463422298 0.0086023743 0.0092450000 17513605 955859216 1373700096 0.8470630646 0.1836253703 -0.1578172892 1130 45.1600000000 0.2055481374 0.1607793619 0.4463422298 0.0085987765 0.0074090000 17515581 955859216 1373700096 0.8497959971 0.1824988574 -0.1490238607 1131 45.2000000000 0.2040075213 0.1608175831 0.4463422298 0.0085951227 0.0049090000 17517557 955859216 1373700096 0.8514215946 0.1810421795 -0.1418765783 1132 45.2400000000 0.2029747069 0.1608548244 0.4463422298 0.0085916575 0.0042740000 17519533 955859216 1373700096 0.8537409306 0.1790484190 -0.1346493065 1133 45.2800000000 0.2010197639 0.1608902745 0.4463422298 0.0085882526 0.0093680000 17521509 955859216 1373700096 0.8568885326 0.1768161505 -0.1262426674 1134 45.3200000000 0.2007891834 0.1609254587 0.4463422298 0.0085846448 0.0057930000 17523485 955859216 1373700096 0.8596170545 0.1777099669 -0.1168518960 1135 45.3600000000 0.1996092349 0.1609595413 0.4463422298 0.0085820406 0.0046760000 17525461 955859216 1373700096 0.8620362282 0.1762640625 -0.1092787087 1136 45.4000000000 0.1965200603 0.1609908446 0.4463422298 0.0085788494 0.0043520000 17527437 955859216 1373700096 0.8653635383 0.1762492061 -0.1007737145 1137 45.4400000000 0.1942959130 0.1610201366 0.4463422298 0.0085755373 0.0043600000 17529413 955859216 1373700096 0.8666722178 0.1762671471 -0.0930872262 1138 45.4800000000 0.1929075420 0.1610481572 0.4463422298 0.0085721286 0.0043960000 17531389 955859216 1373700096 0.8675252795 0.1762710512 -0.0861668438 1139 45.5200000000 0.1912305951 0.1610746563 0.4463422298 0.0085688083 0.0044010000 17533365 955859216 1373700096 0.8704739809 0.1768726557 -0.0783594176 1140 45.5600000000 0.1903589368 0.1611003442 0.4463422298 0.0085661968 0.0096060000 17535341 955859216 1373700096 0.8699192405 0.1775411218 -0.0731187314 1141 45.6000000000 0.1892693341 0.1611250322 0.4463422298 0.0085626012 0.0083840000 17537317 955859216 1373700096 0.8702163100 0.1766088605 -0.0669501349 1142 45.6400000000 0.1870415211 0.1611477262 0.4463422298 0.0085592109 0.0050750000 17539293 955859216 1373700096 0.8737431765 0.1767930388 -0.0586509630 1143 45.6800000000 0.1873946935 0.1611706894 0.4463422298 0.0085560629 0.0040730000 17541269 955859216 1373700096 0.8756641746 0.1766269505 -0.0512187928 1144 45.7200000000 0.1862237900 0.1611925890 0.4463422298 0.0085524400 0.0070180000 17543245 955859216 1373700096 0.8774833679 0.1758274585 -0.0442272983 1145 45.7600000000 0.1863332093 0.1612145458 0.4463422298 0.0085488023 0.0065230000 17545221 955859216 1373700096 0.8801875114 0.1781183332 -0.0363841578 1146 45.8000000000 0.1853836328 0.1612356358 0.4463422298 0.0085451468 0.0070520000 17547197 955859216 1373700096 0.8839941025 0.1776017100 -0.0285067093 1147 45.8400000000 0.1832605600 0.1612548380 0.4463422298 0.0085415312 0.0056600000 17549173 955859216 1373700096 0.8872905374 0.1762309819 -0.0221732631 1148 45.8800000000 0.1820745170 0.1612729736 0.4463422298 0.0085379266 0.0049620000 17551149 955859216 1373700096 0.8921690583 0.1762080491 -0.0151892677 1149 45.9200000000 0.1802892834 0.1612895239 0.4463422298 0.0085347836 0.0096570000 17553125 955859216 1373700096 0.8977649808 0.1755656898 -0.0067736544 1150 45.9600000000 0.1783204824 0.1613043334 0.4463422298 0.0085311539 0.0067880000 17555101 955859216 1373700096 0.9023001790 0.1746374518 0.0004166764 1151 46.0000000000 0.1763722450 0.1613174246 0.4463422298 0.0085279097 0.0046830000 17557077 955859216 1373700096 0.9071965218 0.1734877229 0.0093590626 1152 46.0400000000 0.1750295311 0.1613293275 0.4463422298 0.0085244962 0.0070930000 17559053 955859216 1373700096 0.9109036922 0.1728253365 0.0189254060 1153 46.0800000000 0.1735241264 0.1613399040 0.4463422298 0.0085215715 0.0058590000 17561029 955859216 1373700096 0.9134315252 0.1714082956 0.0271169767 1154 46.1200000000 0.1722618043 0.1613493684 0.4463422298 0.0085179121 0.0091810000 17563005 955859216 1373700096 0.9153763652 0.1709980220 0.0353849381 1155 46.1600000000 0.1707307696 0.1613574908 0.4463422298 0.0085155563 0.0053430000 17564981 955859216 1373700096 0.9184430838 0.1740607172 0.0463854186 1156 46.2000000000 0.1689637601 0.1613640707 0.4463422298 0.0085126839 0.0097060000 17566957 955859216 1373700096 0.9223470688 0.1747534573 0.0564761013 1157 46.2400000000 0.1674793661 0.1613693561 0.4463422298 0.0085098184 0.0056610000 17568933 955859216 1373700096 0.9261851311 0.1756714731 0.0672161654 1158 46.2800000000 0.1662632227 0.1613735823 0.4463422298 0.0085064908 0.0060650000 17570909 955859216 1373700096 0.9286448359 0.1789557487 0.0887676105 1159 46.3200000000 0.1625332385 0.1613745828 0.4463422298 0.0085033954 0.0077070000 17572885 955859216 1373700096 0.9364489913 0.1795048863 0.0973428041 1160 46.3600000000 0.1590760201 0.1613726013 0.4463422298 0.0085004059 0.0079260000 17574861 955859216 1373700096 0.9403842092 0.1810094565 0.1075501740 1161 46.4000000000 0.1562702358 0.1613682065 0.4463422298 0.0084996595 0.0050620000 17576837 955859216 1373700096 0.9447470903 0.1836047769 0.1170445234 1162 46.4400000000 0.1544481218 0.1613622512 0.4463422298 0.0084968558 0.0091370000 17578813 955859216 1373700096 0.9478782415 0.1853656471 0.1278330237 1163 46.4800000000 0.1527177393 0.1613548183 0.4463422298 0.0084938359 0.0054360000 17580789 955859216 1373700096 0.9509180188 0.1855031699 0.1379712224 1164 46.5200000000 0.1513767391 0.1613462460 0.4463422298 0.0084917857 0.0068180000 17582765 955859216 1373700096 0.9542787671 0.1873721182 0.1475506425 1165 46.5600000000 0.1504436731 0.1613368876 0.4463422298 0.0084892932 0.0070220000 17584741 955859216 1373700096 0.9585903883 0.1917718649 0.1595909595 1166 46.6000000000 0.1490677446 0.1613263652 0.4463422298 0.0084857085 0.0075530000 17586717 955859216 1373700096 0.9609897137 0.1931130141 0.1705454290 1167 46.6400000000 0.1483703703 0.1613152632 0.4463422298 0.0084829652 0.0077860000 17588693 955859216 1373700096 0.9624152780 0.1960949749 0.1803416163 1168 46.6800000000 0.1471068710 0.1613030985 0.4463422298 0.0084793661 0.0051900000 17590669 955859216 1373700096 0.9645984173 0.1960211694 0.1902918518 1169 46.7200000000 0.1460209340 0.1612900256 0.4463422298 0.0084759699 0.0046630000 17592645 955859216 1373700096 0.9651268125 0.1971314996 0.1993746608 1170 46.7600000000 0.1440238208 0.1612752682 0.4463422298 0.0084741017 0.0100200000 17594621 955859216 1373700096 0.9661845565 0.1977723837 0.2083178610 1171 46.8000000000 0.1430056095 0.1612596664 0.4463422298 0.0084735747 0.0079470000 17596597 955859216 1373700096 0.9683742523 0.2021068186 0.2200892717 1172 46.8400000000 0.1412294954 0.1612425758 0.4463422298 0.0084707133 0.0053040000 17598573 955859216 1373700096 0.9692656398 0.2054294199 0.2309996933 1173 46.8800000000 0.1396990567 0.1612242097 0.4463422298 0.0084677324 0.0092040000 17600549 955859216 1373700096 0.9706475735 0.2051365972 0.2409325689 1174 46.9200000000 0.1380163729 0.1612044415 0.4463422298 0.0084652281 0.0055540000 17602525 955859216 1373700096 0.9727701545 0.2063397914 0.2509394288 1175 46.9600000000 0.1369154900 0.1611837700 0.4463422298 0.0084616318 0.0047350000 17604501 955859216 1373700096 0.9734666944 0.2055051178 0.2591740191 1176 47.0000000000 0.1332374662 0.1611600062 0.4463422298 0.0084587143 0.0100940000 17606477 955859216 1373700096 0.9742691517 0.2060983628 0.2787082791 1177 47.0400000000 0.1314920485 0.1611347998 0.4463422298 0.0084557025 0.0060880000 17608453 955859216 1373700096 0.9763343334 0.2069656402 0.2887813747 1178 47.0800000000 0.1304475516 0.1611087495 0.4463422298 0.0084522677 0.0047340000 17610429 955859216 1373700096 0.9782172441 0.2054152638 0.2987217605 1179 47.1200000000 0.1254775673 0.1610785279 0.4463422298 0.0084528673 0.0088070000 17612405 955859216 1373700096 0.9786873460 0.2008402199 0.3069857359 1180 47.1600000000 0.1203699335 0.1610440291 0.4463422298 0.0084594673 0.0053590000 17614381 955859216 1373700096 0.9807295799 0.1989126503 0.3166373968 1181 47.2000000000 0.1158464625 0.1610057585 0.4463422298 0.0084616019 0.0096540000 17616357 955859216 1373700096 0.9801772833 0.1954380870 0.3253673911 1182 47.2400000000 0.1157138720 0.1609674405 0.4463422298 0.0084581823 0.0057770000 17618333 955859216 1373700096 0.9775114655 0.1929998249 0.3303232789 1183 47.2800000000 0.1159283519 0.1609293686 0.4463422298 0.0084547604 0.0073470000 17620309 955859216 1373700096 0.9767478704 0.1936845481 0.3409884274 1184 47.3200000000 0.1144133955 0.1608900815 0.4463422298 0.0084514010 0.0073910000 17622285 955859216 1373700096 0.9776617289 0.1940135211 0.3554372787 1185 47.3600000000 0.1139972433 0.1608505095 0.4463422298 0.0084485259 0.0050870000 17624261 955859216 1373700096 0.9814612865 0.1913027763 0.3656813502 1186 47.4000000000 0.1130564809 0.1608102109 0.4463422298 0.0084461613 0.0074080000 17626237 955859216 1373700096 0.9819184542 0.1899445653 0.3750896156 1187 47.4400000000 0.1116400957 0.1607687871 0.4463422298 0.0084429020 0.0061380000 17628213 955859216 1373700096 0.9821646214 0.1902090162 0.3856509030 1188 47.4800000000 0.1105844006 0.1607265443 0.4463422298 0.0084395863 0.0094070000 17630189 955859216 1373700096 0.9819087386 0.1892313212 0.3948135972 1189 47.5200000000 0.1100442335 0.1606839183 0.4463422298 0.0084396296 0.0056350000 17632165 955859216 1373700096 0.9831781387 0.1880933195 0.4030677378 1190 47.5600000000 0.1081765220 0.1606397945 0.4463422298 0.0084369391 0.0048910000 17634141 955859216 1373700096 0.9837884307 0.1868989021 0.4139028490 1191 47.6000000000 0.1061882377 0.1605940753 0.4463422298 0.0084338505 0.0102250000 17636117 955859216 1373700096 0.9876096249 0.1836969554 0.4254071712 1192 47.6400000000 0.1054399759 0.1605478051 0.4463422298 0.0084304312 0.0062140000 17638093 955859216 1373700096 0.9915861487 0.1828769445 0.4365394413 1193 47.6800000000 0.1044324338 0.1605007679 0.4463422298 0.0084269611 0.0049600000 17640069 955859216 1373700096 0.9951844215 0.1812994033 0.4465808868 1194 47.7200000000 0.1055416539 0.1604547385 0.4463422298 0.0084235848 0.0102060000 17642045 955859216 1373700096 0.9951268435 0.1807859093 0.4542186856 1195 47.7600000000 0.1025485322 0.1604062814 0.4463422298 0.0084205037 0.0061330000 17644021 955859216 1373700096 0.9961995482 0.1782703102 0.4662846327 1196 47.8000000000 0.1006726176 0.1603563369 0.4463422298 0.0084172331 0.0047280000 17645997 955859216 1373700096 1.0004485846 0.1777201742 0.4783801138 1197 47.8400000000 0.0990488827 0.1603051193 0.4463422298 0.0084138425 0.0075680000 17647973 955859216 1373700096 1.0054057837 0.1764786392 0.4893279970 1198 47.8800000000 0.0967471376 0.1602520659 0.4463422298 0.0084105794 0.0061330000 17649949 955859216 1373700096 1.0089638233 0.1759242564 0.5005396008 1199 47.9200000000 0.0954870135 0.1601980500 0.4463422298 0.0084077289 0.0092820000 17651925 955859216 1373700096 1.0121643543 0.1749473512 0.5112543702 1200 47.9600000000 0.0931557491 0.1601421814 0.4463422298 0.0084043842 0.0056680000 17653901 955859216 1373700096 1.0153697729 0.1708425432 0.5191411972 1201 48.0000000000 0.0902378708 0.1600839763 0.4463422298 0.0084025352 0.0049640000 17655877 955859216 1373700096 1.0179586411 0.1691325754 0.5312199593 1202 48.0400000000 0.0884349793 0.1600243681 0.4463422298 0.0084013191 0.0102780000 17657853 955859216 1373700096 1.0212094784 0.1692926735 0.5443611145 1203 48.0800000000 0.0867557451 0.1599634632 0.4463422298 0.0083987818 0.0063050000 17659829 955859216 1373700096 1.0241721869 0.1681960523 0.5548719764 1204 48.1200000000 0.0839651227 0.1599003417 0.4463422298 0.0084013771 0.0067340000 17661805 955859216 1373700096 1.0278489590 0.1659530252 0.5656796694 1205 48.1600000000 0.0816938877 0.1598354401 0.4463422298 0.0083987344 0.0053900000 17663781 955859216 1373700096 1.0304312706 0.1656643748 0.5773946643 1206 48.2000000000 0.0799504966 0.1597692005 0.4463422298 0.0083955618 0.0050250000 17665757 955859216 1373700096 1.0337014198 0.1649600714 0.5879045725 1207 48.2400000000 0.0783393905 0.1597017358 0.4463422298 0.0083923595 0.0050280000 17667733 955859216 1373700096 1.0377427340 0.1628337651 0.5969399214 1208 48.2800000000 0.0755651221 0.1596320863 0.4463422298 0.0083897109 0.0050370000 17669709 955859216 1373700096 1.0434306860 0.1607990265 0.6071912050 1209 48.3200000000 0.0732253939 0.1595606168 0.4463422298 0.0083877015 0.0050030000 17671685 955859216 1373700096 1.0485334396 0.1604462862 0.6179587841 1210 48.3600000000 0.0711705610 0.1594875671 0.4463422298 0.0083845645 0.0050260000 17673661 955859216 1373700096 1.0511955023 0.1588613540 0.6271839142 1211 48.4000000000 0.0692686588 0.1594130676 0.4463422298 0.0083816065 0.0049380000 17675637 955859216 1373700096 1.0531817675 0.1570118219 0.6360051036 1212 48.4400000000 0.0666762143 0.1593365521 0.4463422298 0.0083795367 0.0052590000 17677613 955859216 1373700096 1.0568877459 0.1577398330 0.6574206352 1213 48.4800000000 0.0657871291 0.1592594297 0.4463422298 0.0083771327 0.0049310000 17679589 955859216 1373700096 1.0578556061 0.1582095474 0.6651445627 1214 48.5200000000 0.0640484914 0.1591810022 0.4463422298 0.0083744240 0.0049170000 17681565 955859216 1373700096 1.0578360558 0.1564363837 0.6725571752 1215 48.5600000000 0.0615120307 0.1591006163 0.4463422298 0.0083718307 0.0048990000 17683541 955859216 1373700096 1.0576499701 0.1540686488 0.6803538203 1216 48.6000000000 0.0572873391 0.1590168882 0.4463422298 0.0083716940 0.0105170000 17685517 955859216 1373700096 1.0578409433 0.1524036676 0.6965263486 1217 48.6400000000 0.0540137030 0.1589306079 0.4463422298 0.0083688859 0.0092980000 17687493 955859216 1373700096 1.0586357117 0.1502441466 0.7045692205 1218 48.6800000000 0.0511425138 0.1588421119 0.4463422298 0.0083658599 0.0056030000 17689469 955859216 1373700096 1.0597250462 0.1486045271 0.7125384808 1219 48.7200000000 0.0489723273 0.1587519808 0.4463422298 0.0083626380 0.0046020000 17691445 955859216 1373700096 1.0615589619 0.1456423998 0.7190244198 1220 48.7600000000 0.0466530621 0.1586600965 0.4463422298 0.0083596638 0.0068880000 17693421 955859216 1373700096 1.0618413687 0.1447600722 0.7262063026 1221 48.8000000000 0.0462410524 0.1585680252 0.4463422298 0.0083574473 0.0053630000 17695397 955859216 1373700096 1.0615589619 0.1454129368 0.7335774302 1222 48.8400000000 0.0458117388 0.1584757533 0.4463422298 0.0083559706 0.0092540000 17697373 955859216 1373700096 1.0598934889 0.1474018246 0.7410179377 1223 48.8800000000 0.0446002632 0.1583826417 0.4463422298 0.0083527708 0.0054790000 17699349 955859216 1373700096 1.0589840412 0.1465414166 0.7494074702 1224 48.9200000000 0.0425074883 0.1582879724 0.4463422298 0.0083496771 0.0084130000 17701325 955859216 1373700096 1.0591320992 0.1445138901 0.7571255565 1225 48.9600000000 0.0417132042 0.1581928093 0.4463422298 0.0083473809 0.0060440000 17703301 955859216 1373700096 1.0582615137 0.1438899934 0.7653075457 1226 49.0000000000 0.0401245505 0.1580965057 0.4463422298 0.0083446032 0.0074700000 17705277 955859216 1373700096 1.0570832491 0.1427825838 0.7734988332 1227 49.0400000000 0.0391070321 0.1579995298 0.4463422298 0.0083417631 0.0082070000 17707253 955859216 1373700096 1.0555783510 0.1425003558 0.7816760540 1228 49.0800000000 0.0373728126 0.1579012996 0.4463422298 0.0083387165 0.0052350000 17709229 955859216 1373700096 1.0533707142 0.1426248550 0.7903555036 1229 49.1200000000 0.0361127444 0.1578022039 0.4463422298 0.0083360537 0.0089800000 17711205 955859216 1373700096 1.0508378744 0.1423351318 0.7991452217 1230 49.1600000000 0.0386612788 0.1577053414 0.4463422298 0.0083383913 0.0053710000 17713181 955859216 1373700096 1.0491410494 0.1453047246 0.8085972071 1231 49.2000000000 0.0373926051 0.1576076056 0.4463422298 0.0083354710 0.0081010000 17715157 955859216 1373700096 1.0481514931 0.1446658224 0.8170402646 1232 49.2400000000 0.0370448753 0.1575097462 0.4463422298 0.0083331557 0.0083250000 17717133 955859216 1373700096 1.0462718010 0.1446934193 0.8251757026 1233 49.2800000000 0.0362097435 0.1574113683 0.4463422298 0.0083299377 0.0053410000 17719109 955859216 1373700096 1.0428885221 0.1442538798 0.8325682282 1234 49.3200000000 0.0367258787 0.1573135680 0.4463422298 0.0083270873 0.0047990000 17721085 955859216 1373700096 1.0396646261 0.1448339671 0.8413378596 1235 49.3600000000 0.0358301140 0.1572152009 0.4463422298 0.0083242180 0.0097560000 17723061 955859216 1373700096 1.0378555059 0.1443903744 0.8501759768 1236 49.4000000000 0.0353691764 0.1571166200 0.4463422298 0.0083209666 0.0065590000 17725037 955859216 1373700096 1.0354281664 0.1441360712 0.8581506014 1237 49.4400000000 0.0341361389 0.1570172016 0.4463422298 0.0083178199 0.0048550000 17727013 955859216 1373700096 1.0339026451 0.1437975168 0.8685715199 1238 49.4800000000 0.0339227319 0.1569177715 0.4463422298 0.0083144600 0.0096710000 17728989 955859216 1373700096 1.0329385996 0.1439281404 0.8766491413 1239 49.5200000000 0.0341972001 0.1568187234 0.4463422298 0.0083111581 0.0054520000 17730965 955859216 1373700096 1.0316439867 0.1463989913 0.8852568269 1240 49.5600000000 0.0336205401 0.1567193701 0.4463422298 0.0083078955 0.0100300000 17732941 955859216 1373700096 1.0303946733 0.1481610537 0.8948768973 1241 49.6000000000 0.0340241157 0.1566205020 0.4463422298 0.0083045713 0.0070800000 17734917 955859216 1373700096 1.0286856890 0.1499921232 0.9018477798 1242 49.6400000000 0.0341168158 0.1565218678 0.4463422298 0.0083017533 0.0100480000 17736893 955859216 1373700096 1.0274391174 0.1509056389 0.9085974097 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:32:57 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 -nan 0.0093320000 14733949 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 1305031229.5644419193 0.0542627871 0.0574408155 0.0606188439 0.0575073138 0.0075290000 15521565 955859216 1373700096 0.0013755441 0.0021835307 0.0096326284 3 1305031229.5966169834 0.0526413769 0.0558410026 0.0606188439 0.0579490364 0.0024580000 15524829 955859216 1373700096 0.0134399962 -0.0028340230 0.0144416252 4 1305031229.6287899017 0.0486520492 0.0540437642 0.0606188439 0.0479624321 0.0024180000 15528045 955859216 1373700096 0.0181480199 0.0010524673 0.0210015606 5 1305031229.6646571159 0.0491557308 0.0530661575 0.0606188439 0.0428185384 0.0022850000 15531357 955859216 1373700096 0.0175530538 -0.0027123608 0.0255282465 6 1305031229.6968429089 0.0501502529 0.0525801734 0.0606188439 0.0383525771 0.0023280000 15535085 955859216 1373700096 0.0196280386 -0.0042131776 0.0289523080 7 1305031229.7290771008 0.0478200801 0.0519001601 0.0606188439 0.0365870775 0.0022720000 15537901 955859216 1373700096 0.0188891739 -0.0035767350 0.0343250707 8 1305031229.7648689747 0.0481220856 0.0514279008 0.0606188439 0.0339840122 0.0022800000 15540885 955859216 1373700096 0.0210147314 -0.0044871112 0.0390293151 9 1305031229.7969229221 0.0484815277 0.0511005260 0.0606188439 0.0320839593 0.0024080000 15544525 955859216 1373700096 0.0224724207 -0.0050563551 0.0428514332 10 1305031229.8256299496 0.0477991849 0.0507703919 0.0606188439 0.0303529729 0.0023280000 15548885 955859216 1373700096 0.0243196208 -0.0046594148 0.0481991991 11 1305031229.8630619049 0.0489536598 0.0506052344 0.0606188439 0.0293501133 0.0023010000 15551981 955859216 1373700096 0.0272357371 -0.0042557400 0.0527172983 12 1305031229.8969380856 0.0514156222 0.0506727668 0.0606188439 0.0295498675 0.0023410000 15554853 955859216 1373700096 0.0292805601 -0.0042388686 0.0566489212 13 1305031229.9262549877 0.0545422249 0.0509704174 0.0606188439 0.0285019357 0.0024770000 15557669 955859216 1373700096 0.0354560763 -0.0009259381 0.0631215647 14 1305031229.9662408829 0.0574452579 0.0514329060 0.0606188439 0.0275719441 0.0022830000 15560765 955859216 1373700096 0.0361899212 -0.0010128332 0.0666608885 15 1305031229.9979310036 0.0596384294 0.0519799409 0.0606188439 0.0274217348 0.0022670000 15563581 955859216 1373700096 0.0372663476 -0.0007309067 0.0704792589 16 1305031230.0300021172 0.0623441562 0.0526277043 0.0623441562 0.0266401638 0.0022350000 15566453 955859216 1373700096 0.0380823314 -0.0008158885 0.0737314671 17 1305031230.0656960011 0.0661407858 0.0534225915 0.0661407858 0.0260475342 0.0022140000 15570973 955859216 1373700096 0.0387657695 -0.0020297286 0.0765988752 18 1305031230.0982739925 0.0684064180 0.0542550263 0.0684064180 0.0254751321 0.0022810000 15577045 955859216 1373700096 0.0387827381 -0.0019408803 0.0788877010 19 1305031230.1299350262 0.0698349774 0.0550750237 0.0698349774 0.0247936692 0.0022710000 15579917 955859216 1373700096 0.0380027741 -0.0011633855 0.0807379782 20 1305031230.1657800674 0.0730449930 0.0559735222 0.0730449930 0.0243026797 0.0022430000 15582901 955859216 1373700096 0.0374424942 -0.0016783335 0.0830842406 21 1305031230.1977820396 0.0753093660 0.0568942766 0.0753093660 0.0238587118 0.0023420000 15585773 955859216 1373700096 0.0367633253 -0.0025439383 0.0849721730 22 1305031230.2298529148 0.0773865432 0.0578257433 0.0773865432 0.0234029467 0.0023080000 15588645 955859216 1373700096 0.0355879143 -0.0029639916 0.0866222531 23 1305031230.2655899525 0.0798358396 0.0587827040 0.0798358396 0.0230244119 0.0023470000 15591629 955859216 1373700096 0.0342307314 -0.0036363243 0.0885601044 24 1305031230.2979929447 0.0817571953 0.0597399745 0.0817571953 0.0225681139 0.0023720000 15594501 955859216 1373700096 0.0328270532 -0.0035086318 0.0908239037 25 1305031230.3351120949 0.0851004273 0.0607543926 0.0851004273 0.0222167026 0.0023880000 15597541 955859216 1373700096 0.0320601352 -0.0049805921 0.0930152535 26 1305031230.3656799793 0.0853847861 0.0617017154 0.0853847861 0.0218158210 0.0024040000 15600357 955859216 1373700096 0.0297937766 -0.0044176672 0.0947409198 27 1305031230.3973290920 0.0856923610 0.0625902579 0.0856923610 0.0213988590 0.0024340000 15603285 955859216 1373700096 0.0266701709 -0.0054842844 0.0963923633 28 1305031230.4368140697 0.0882192999 0.0635055808 0.0882192999 0.0220859921 0.0017350000 15606325 955859216 1373700096 0.0243123211 -0.0067811110 0.0982476622 29 1305031230.4653120041 0.0900053531 0.0644193660 0.0900053531 0.0219297237 0.0018270000 15609085 955859216 1373700096 0.0205482412 -0.0107291546 0.0994208604 30 1305031230.4972999096 0.0909555033 0.0653039039 0.0909555033 0.0216517257 0.0026920000 15612013 955859216 1373700096 0.0159174539 -0.0137637658 0.1003082693 31 1305031230.5301918983 0.0910607800 0.0661347709 0.0910607800 0.0213722031 0.0027620000 15614829 955859216 1373700096 0.0102903573 -0.0174788944 0.0995061770 32 1305031230.5661149025 0.0911991447 0.0669180326 0.0911991447 0.0222911229 0.0027720000 15617869 955859216 1373700096 0.0037917292 -0.0196627360 0.0974997059 33 1305031230.5988430977 0.0807894245 0.0673383778 0.0911991447 0.0220648261 0.0031050000 15623813 955859216 1373700096 -0.0123745706 -0.0205825418 0.0843389407 34 1305031230.6319139004 0.0794779360 0.0676954236 0.0911991447 0.0218462033 0.0028110000 15633141 955859216 1373700096 -0.0179526806 -0.0201539714 0.0785537735 35 1305031230.6660470963 0.0722688809 0.0678260938 0.0911991447 0.0219964687 0.0030680000 15636069 955859216 1373700096 -0.0296685565 -0.0133087998 0.0651325881 36 1305031230.6979451180 0.0730373412 0.0679708507 0.0911991447 0.0219107352 0.0028510000 15638885 955859216 1373700096 -0.0314721018 -0.0107506430 0.0604780950 37 1305031230.7336409092 0.0756569356 0.0681785827 0.0911991447 0.0229609819 0.0031150000 15641813 955859216 1373700096 -0.0328130610 0.0025192508 0.0440687202 38 1305031230.7659239769 0.0800019726 0.0684897246 0.0911991447 0.0232790498 0.0029250000 15644741 955859216 1373700096 -0.0326946378 0.0056683999 0.0373803154 39 1305031230.7973229885 0.0831844136 0.0688665115 0.0911991447 0.0233088604 0.0029990000 15647613 955859216 1373700096 -0.0348905437 0.0074780798 0.0294446833 40 1305031230.8317570686 0.0856193975 0.0692853336 0.0911991447 0.0231031257 0.0032560000 15650541 955859216 1373700096 -0.0492453352 0.0095366333 0.0111102741 41 1305031230.8655419350 0.0874726325 0.0697289263 0.0911991447 0.0237661810 0.0030690000 15653413 955859216 1373700096 -0.0544022843 0.0073067076 0.0050958619 42 1305031230.8973939419 0.0901619643 0.0702154272 0.0911991447 0.0235085479 0.0030890000 15656341 955859216 1373700096 -0.0593761429 0.0063682399 -0.0016487220 43 1305031230.9373099804 0.0943894163 0.0707776130 0.0943894163 0.0233690493 0.0032360000 15659381 955859216 1373700096 -0.0700737312 0.0109014632 -0.0137683693 44 1305031230.9650349617 0.0941183567 0.0713080844 0.0943894163 0.0232935374 0.0030200000 15662141 955859216 1373700096 -0.0703402683 0.0129721547 -0.0142557919 45 1305031230.9971239567 0.0929632187 0.0717893096 0.0943894163 0.0231634975 0.0031210000 15665069 955859216 1373700096 -0.0718682930 0.0149752488 -0.0136583624 46 1305031231.0367500782 0.0915050507 0.0722179127 0.0943894163 0.0230284852 0.0030740000 15668109 955859216 1373700096 -0.0738931000 0.0155978343 -0.0125670368 47 1305031231.0644741058 0.0907521322 0.0726122578 0.0943894163 0.0228279812 0.0031300000 15670813 955859216 1373700096 -0.0760886818 0.0155585455 -0.0120828580 48 1305031231.0967879295 0.0893750191 0.0729614820 0.0943894163 0.0226884430 0.0030980000 15673741 955859216 1373700096 -0.0769152269 0.0134765478 -0.0097307069 49 1305031231.1347110271 0.0886289030 0.0732812253 0.0943894163 0.0224609467 0.0030650000 15676725 955859216 1373700096 -0.0776326284 0.0103991237 -0.0075473059 50 1305031231.1652760506 0.0883976519 0.0735835538 0.0943894163 0.0223293212 0.0031020000 15679597 955859216 1373700096 -0.0775835887 0.0078274291 -0.0055895024 51 1305031231.1977710724 0.0862732306 0.0738323710 0.0943894163 0.0225183705 0.0031730000 15682525 955859216 1373700096 -0.0751930922 0.0085667670 -0.0009655590 52 1305031231.2344679832 0.0852878913 0.0740526695 0.0943894163 0.0243585322 0.0032120000 15685509 955859216 1373700096 -0.0700520650 0.0088981604 0.0044492451 53 1305031231.2656350136 0.0836704895 0.0742341378 0.0943894163 0.0249605266 0.0032910000 15688325 955859216 1373700096 -0.0648863837 0.0115088234 0.0098094214 54 1305031231.2978610992 0.0811566412 0.0743623323 0.0943894163 0.0254575651 0.0034040000 15691253 955859216 1373700096 -0.0639925748 0.0100209815 0.0149102844 55 1305031231.3351519108 0.0649587214 0.0741913575 0.0943894163 0.0299602217 0.0036900000 15694237 955859216 1373700096 -0.0658646002 -0.0112204682 0.0460273139 56 1305031231.3650770187 0.0611147881 0.0739578474 0.0943894163 0.0312663867 0.0037460000 15697053 955859216 1373700096 -0.0639018789 -0.0224552751 0.0707582235 57 1305031231.3973300457 0.0707450584 0.0739014826 0.0943894163 0.0317072850 0.0028940000 15699981 955859216 1373700096 -0.0467812158 -0.0299661756 0.0993789360 58 1305031231.4368579388 0.0942482799 0.0742522895 0.0943894163 0.0321472769 0.0037640000 15703021 955859216 1373700096 -0.0223828536 -0.0354387872 0.1304565668 59 1305031231.4649889469 0.0977623165 0.0746507645 0.0977623165 0.0318879064 0.0035670000 15705781 955859216 1373700096 -0.0123889875 -0.0320775174 0.1337616146 60 1305031231.4992439747 0.1081551388 0.0752091708 0.1081551388 0.0316413796 0.0038000000 15708653 955859216 1373700096 0.0036086862 -0.0258902777 0.1463002264 61 1305031231.5331959724 0.1119863689 0.0758120757 0.1119863689 0.0314148341 0.0035970000 15711693 955859216 1373700096 0.0099994699 -0.0243651494 0.1501393616 62 1305031231.5650680065 0.1119160578 0.0763943979 0.1119863689 0.0312819471 0.0034830000 15714509 955859216 1373700096 0.0137851695 -0.0214634798 0.1519138962 63 1305031231.6013169289 0.1137627214 0.0769875459 0.1137627214 0.0310405537 0.0035670000 15717493 955859216 1373700096 0.0192006547 -0.0167623311 0.1557169110 64 1305031231.6331589222 0.1150630414 0.0775824756 0.1150630414 0.0309330798 0.0034140000 15720421 955859216 1373700096 0.0233448781 -0.0156269278 0.1577321142 65 1305031231.6650550365 0.1079876274 0.0780502471 0.1150630414 0.0307068732 0.0036950000 15729381 955859216 1373700096 0.0225311182 -0.0096673071 0.1523972750 66 1305031231.7035079002 0.1004734635 0.0783899928 0.1150630414 0.0306335055 0.0035980000 15745277 955859216 1373700096 0.0234701950 -0.0012575897 0.1466054022 67 1305031231.7339379787 0.0979315415 0.0786816577 0.1150630414 0.0304729352 0.0038190000 15748037 955859216 1373700096 0.0247284938 0.0005639417 0.1439895034 68 1305031231.7655088902 0.0825854689 0.0787390667 0.1150630414 0.0302706839 0.0035790000 15750909 955859216 1373700096 0.0168718528 0.0070718550 0.1311250776 69 1305031231.8011910915 0.0835716501 0.0788091042 0.1150630414 0.0300985260 0.0032290000 15753893 955859216 1373700096 0.0201875661 0.0063962643 0.1299748123 70 1305031231.8332920074 0.0682352483 0.0786580491 0.1150630414 0.0300392750 0.0033480000 15756765 955859216 1373700096 0.0087532867 0.0075383605 0.1145949587 71 1305031231.8649590015 0.0684257597 0.0785139323 0.1150630414 0.0299037895 0.0029300000 15759637 955859216 1373700096 0.0114588300 0.0067520426 0.1120039374 72 1305031231.9012699127 0.0697062463 0.0783916033 0.1150630414 0.0299990050 0.0029370000 15762621 955859216 1373700096 0.0128773330 0.0034764360 0.1085312590 73 1305031231.9330461025 0.0696083233 0.0782712844 0.1150630414 0.0298811887 0.0027210000 15765493 955859216 1373700096 0.0124241179 -0.0000594857 0.1045738757 74 1305031231.9650299549 0.0682962984 0.0781364873 0.1150630414 0.0296885222 0.0027570000 15768365 955859216 1373700096 0.0109506315 -0.0022416776 0.0993817747 75 1305031232.0007200241 0.0663707480 0.0779796108 0.1150630414 0.0295662468 0.0025260000 15771349 955859216 1373700096 0.0076723918 -0.0032615138 0.0937403813 76 1305031232.0332028866 0.0649006367 0.0778075190 0.1150630414 0.0295202904 0.0025820000 15774277 955859216 1373700096 0.0053025042 -0.0046782866 0.0886037499 77 1305031232.0651450157 0.0635762960 0.0776226980 0.1150630414 0.0293843562 0.0027620000 15777093 955859216 1373700096 -0.0079772621 -0.0066139945 0.0755771697 78 1305031232.1007990837 0.0634905994 0.0774415172 0.1150630414 0.0292936834 0.0025880000 15780077 955859216 1373700096 -0.0095414165 -0.0066033467 0.0720277503 79 1305031232.1328380108 0.0645866543 0.0772787974 0.1150630414 0.0291744507 0.0025570000 15783005 955859216 1373700096 -0.0120824082 -0.0074233734 0.0676193088 80 1305031232.1650519371 0.0657052174 0.0771341277 0.1150630414 0.0290146778 0.0024900000 15785821 955859216 1373700096 -0.0152972080 -0.0082147550 0.0629733354 81 1305031232.1992239952 0.0673279241 0.0770130634 0.1150630414 0.0288823633 0.0025250000 15788749 955859216 1373700096 -0.0183018688 -0.0086770318 0.0586221553 82 1305031232.2364680767 0.0690208152 0.0769155970 0.1150630414 0.0287348502 0.0025980000 15791789 955859216 1373700096 -0.0213255584 -0.0094280997 0.0545269623 83 1305031232.2626979351 0.0722797364 0.0768597433 0.1150630414 0.0287507965 0.0025790000 15794493 955859216 1373700096 -0.0243571717 -0.0108604841 0.0502247065 84 1305031232.2980248928 0.0730167627 0.0768139935 0.1150630414 0.0288289376 0.0025860000 15797477 955859216 1373700096 -0.0246811751 -0.0096076922 0.0455776006 85 1305031232.3321430683 0.0751064345 0.0767939046 0.1150630414 0.0287009398 0.0026760000 15800405 955859216 1373700096 -0.0247500315 -0.0091929911 0.0405043475 86 1305031232.3647489548 0.0764225349 0.0767895863 0.1150630414 0.0285733588 0.0027980000 15803221 955859216 1373700096 -0.0260037016 -0.0080960067 0.0362864807 87 1305031232.4008779526 0.0776531845 0.0767995127 0.1150630414 0.0284431731 0.0028140000 15806261 955859216 1373700096 -0.0277108513 -0.0075123976 0.0333089009 88 1305031232.4331440926 0.0778944492 0.0768119552 0.1150630414 0.0282851279 0.0027890000 15809189 955859216 1373700096 -0.0292158499 -0.0061017498 0.0306703616 89 1305031232.4647209644 0.0791286901 0.0768379859 0.1150630414 0.0281277237 0.0027640000 15811949 955859216 1373700096 -0.0314669125 -0.0056574182 0.0282676909 90 1305031232.5015261173 0.0804042295 0.0768776108 0.1150630414 0.0279751551 0.0027860000 15814989 955859216 1373700096 -0.0322405510 -0.0060865213 0.0255561061 91 1305031232.5324640274 0.0828717723 0.0769434807 0.1150630414 0.0278278198 0.0027840000 15817861 955859216 1373700096 -0.0334819071 -0.0073796571 0.0223441496 92 1305031232.5647449493 0.0852974877 0.0770342852 0.1150630414 0.0277045883 0.0027890000 15820733 955859216 1373700096 -0.0355493613 -0.0085100504 0.0189416166 93 1305031232.6003499031 0.0879704282 0.0771518781 0.1150630414 0.0275674696 0.0029010000 15823661 955859216 1373700096 -0.0377047621 -0.0096994694 0.0154720126 94 1305031232.6294269562 0.0910291150 0.0772995083 0.1150630414 0.0274617965 0.0028590000 15826421 955859216 1373700096 -0.0406711996 -0.0108977677 0.0116987107 95 1305031232.6647078991 0.0941715837 0.0774771091 0.1150630414 0.0273221307 0.0029870000 15829461 955859216 1373700096 -0.0458424501 -0.0120052546 0.0079665957 96 1305031232.7005090714 0.0983563811 0.0776946015 0.1150630414 0.0271987180 0.0029340000 15832389 955859216 1373700096 -0.0514719374 -0.0125857480 0.0039045378 97 1305031232.7327980995 0.1014098302 0.0779390884 0.1150630414 0.0271204512 0.0030430000 15835261 955859216 1373700096 -0.0549732447 -0.0126903066 0.0000599295 98 1305031232.7684600353 0.1041329950 0.0782063732 0.1150630414 0.0270602033 0.0029720000 15838245 955859216 1373700096 -0.0590057150 -0.0134426272 -0.0031859085 99 1305031232.8045380116 0.1091626287 0.0785190626 0.1150630414 0.0269566054 0.0019580000 15841229 955859216 1373700096 -0.0659568235 -0.0165251568 -0.0068877302 100 1305031232.8346450329 0.1119590029 0.0788534620 0.1150630414 0.0268696571 0.0029620000 15844045 955859216 1373700096 -0.0698627159 -0.0164000522 -0.0105475336 101 1305031232.8685569763 0.1143743470 0.0792051539 0.1150630414 0.0267838691 0.0029330000 15847029 955859216 1373700096 -0.0736308768 -0.0165127460 -0.0137243811 102 1305031232.9041829109 0.1162490174 0.0795683291 0.1162490174 0.0266887634 0.0029650000 15849957 955859216 1373700096 -0.0777139962 -0.0162429567 -0.0163894929 103 1305031232.9330000877 0.1177039519 0.0799385778 0.1177039519 0.0266057226 0.0029090000 15852717 955859216 1373700096 -0.0800217465 -0.0148834512 -0.0185010396 104 1305031232.9683640003 0.1170127541 0.0802950603 0.1177039519 0.0264767285 0.0029400000 15855757 955859216 1373700096 -0.0802661926 -0.0141557017 -0.0201670099 105 1305031233.0011510849 0.1151308045 0.0806268293 0.1177039519 0.0264073559 0.0029240000 15858629 955859216 1373700096 -0.0791062266 -0.0115979537 -0.0206685886 106 1305031233.0330219269 0.1102298349 0.0809061029 0.1177039519 0.0265931081 0.0032280000 15861501 955859216 1373700096 -0.0802585632 -0.0007497667 -0.0189282373 107 1305031233.0688428879 0.1049970910 0.0811312523 0.1177039519 0.0267698936 0.0032410000 15864373 955859216 1373700096 -0.0767700374 0.0031776316 -0.0171317067 108 1305031233.1004469395 0.0968949348 0.0812772124 0.1177039519 0.0266985456 0.0032440000 15867189 955859216 1373700096 -0.0711116493 0.0134745352 -0.0130050965 109 1305031233.1328918934 0.0912045613 0.0813682890 0.1177039519 0.0271308972 0.0033570000 15870061 955859216 1373700096 -0.0613524541 0.0092776874 -0.0101894699 110 1305031233.1684799194 0.0857515186 0.0814081365 0.1177039519 0.0271783725 0.0032000000 15873045 955859216 1373700096 -0.0475191697 0.0086232470 -0.0077157295 111 1305031233.2006340027 0.0856504738 0.0814463558 0.1177039519 0.0271095869 0.0030580000 15875917 955859216 1373700096 -0.0476188883 0.0067409738 -0.0046389964 112 1305031233.2330091000 0.0845259205 0.0814738519 0.1177039519 0.0271129978 0.0030410000 15878789 955859216 1373700096 -0.0485148653 0.0060752709 -0.0009381872 113 1305031233.2684679031 0.0818809271 0.0814774543 0.1177039519 0.0277922733 0.0032440000 15881773 955859216 1373700096 -0.0504281931 0.0099982722 0.0037541741 114 1305031233.3003950119 0.0733557269 0.0814062111 0.1177039519 0.0280108421 0.0033590000 15884645 955859216 1373700096 -0.0469356664 0.0193512384 0.0110196555 115 1305031233.3325300217 0.0712856129 0.0813182059 0.1177039519 0.0279533575 0.0032680000 15887517 955859216 1373700096 -0.0485969558 0.0072553637 0.0229750331 116 1305031233.3686299324 0.0648257434 0.0811760295 0.1177039519 0.0279032415 0.0034970000 15890389 955859216 1373700096 -0.0268532094 0.0148926619 0.0312967375 117 1305031233.4008929729 0.0651356876 0.0810389325 0.1177039519 0.0278403144 0.0032600000 15893317 955859216 1373700096 -0.0172835514 0.0162680354 0.0396776050 118 1305031233.4330079556 0.0688668787 0.0809357795 0.1177039519 0.0279297701 0.0031310000 15896245 955859216 1373700096 -0.0209763870 0.0063552056 0.0445081145 119 1305031233.4687869549 0.0719452575 0.0808602289 0.1177039519 0.0279326033 0.0029750000 15899117 955859216 1373700096 -0.0227025449 0.0008878895 0.0485152379 120 1305031233.5007359982 0.0736870617 0.0808004525 0.1177039519 0.0278606117 0.0028670000 15902045 955859216 1373700096 -0.0244911797 -0.0022944757 0.0511583462 121 1305031233.5341610909 0.0759584382 0.0807604359 0.1177039519 0.0278599371 0.0029290000 15904973 955859216 1373700096 -0.0255947281 -0.0047719427 0.0533605479 122 1305031233.5697269440 0.0768115371 0.0807280679 0.1177039519 0.0277684237 0.0028930000 15907901 955859216 1373700096 -0.0262605436 -0.0059839226 0.0561469495 123 1305031233.6012749672 0.0785869062 0.0807106601 0.1177039519 0.0277195380 0.0028960000 15910773 955859216 1373700096 -0.0266118776 -0.0082008680 0.0585929565 124 1305031233.6330409050 0.0785757452 0.0806934430 0.1177039519 0.0276825983 0.0029080000 15913645 955859216 1373700096 -0.0272792075 -0.0087905619 0.0610486828 125 1305031233.6717829704 0.0776516199 0.0806691084 0.1177039519 0.0276171183 0.0032170000 15916741 955859216 1373700096 -0.0161933564 -0.0044047385 0.0736183673 126 1305031233.7022960186 0.0766448155 0.0806371696 0.1177039519 0.0276686289 0.0029080000 15919613 955859216 1373700096 -0.0176343434 -0.0040991092 0.0749270543 127 1305031233.7312009335 0.0739311650 0.0805843664 0.1177039519 0.0277648105 0.0029750000 15922373 955859216 1373700096 -0.0181485377 -0.0014332582 0.0762793496 128 1305031233.7691600323 0.0716348588 0.0805144484 0.1177039519 0.0278364741 0.0029450000 15925357 955859216 1373700096 -0.0168796293 0.0013512420 0.0777345300 129 1305031233.7997679710 0.0714904889 0.0804444952 0.1177039519 0.0277475828 0.0030410000 15940461 955859216 1373700096 -0.0146539854 0.0020878068 0.0789944530 130 1305031233.8338310719 0.0727923587 0.0803856326 0.1177039519 0.0276851723 0.0029810000 15968989 955859216 1373700096 -0.0126060331 -0.0002896810 0.0795776919 131 1305031233.8655700684 0.0741003528 0.0803376534 0.1177039519 0.0276237747 0.0029770000 15971861 955859216 1373700096 -0.0115928482 -0.0018630218 0.0794190988 132 1305031233.8986968994 0.0734656826 0.0802855930 0.1177039519 0.0275200850 0.0029900000 15974845 955859216 1373700096 -0.0111711742 -0.0016915285 0.0795694664 133 1305031233.9320030212 0.0730559528 0.0802312348 0.1177039519 0.0274542128 0.0029170000 15977717 955859216 1373700096 -0.0099025667 -0.0016564069 0.0801690668 134 1305031233.9681589603 0.0718170181 0.0801684421 0.1177039519 0.0273697655 0.0029460000 15980701 955859216 1373700096 -0.0085706199 -0.0007702675 0.0802389756 135 1305031233.9989380836 0.0718273520 0.0801066563 0.1177039519 0.0273028712 0.0029370000 15983573 955859216 1373700096 -0.0063851229 -0.0007116299 0.0800950006 136 1305031234.0370678902 0.0701588541 0.0800335107 0.1177039519 0.0272133664 0.0029470000 15986613 955859216 1373700096 -0.0047499957 0.0015501197 0.0794463009 137 1305031234.0687561035 0.0684724376 0.0799491233 0.1177039519 0.0271207578 0.0029160000 15989429 955859216 1373700096 -0.0028988130 0.0040659355 0.0792045072 138 1305031234.0997409821 0.0676140860 0.0798597390 0.1177039519 0.0270334722 0.0029100000 15992301 955859216 1373700096 -0.0015511609 0.0061756968 0.0780449361 139 1305031234.1350688934 0.0665221661 0.0797637852 0.1177039519 0.0269530974 0.0029160000 15995229 955859216 1373700096 -0.0009102485 0.0080451937 0.0765906647 140 1305031234.1659009457 0.0619315803 0.0796364123 0.1177039519 0.0269544723 0.0026720000 15998101 955859216 1373700096 0.0001947623 0.0158171151 0.0775013119 141 1305031234.2010040283 0.0619872548 0.0795112410 0.1177039519 0.0269274709 0.0030150000 16001029 955859216 1373700096 0.0003770193 0.0152666746 0.0768025443 142 1305031234.2385749817 0.0606019013 0.0793780766 0.1177039519 0.0268325450 0.0030150000 16004125 955859216 1373700096 -0.0001991191 0.0165622104 0.0761225224 143 1305031234.2655100822 0.0558402166 0.0792134762 0.1177039519 0.0267751123 0.0032130000 16006773 955859216 1373700096 -0.0000098131 0.0251619592 0.0778639540 144 1305031234.3024549484 0.0556122400 0.0790495787 0.1177039519 0.0266822548 0.0030100000 16009869 955859216 1373700096 0.0000055534 0.0247901492 0.0777578354 145 1305031234.3384580612 0.0554191619 0.0788866103 0.1177039519 0.0266226753 0.0030100000 16012853 955859216 1373700096 -0.0003313275 0.0252002086 0.0771174580 146 1305031234.3661808968 0.0524552055 0.0787055733 0.1177039519 0.0265625206 0.0030680000 16015557 955859216 1373700096 -0.0017321644 0.0287913959 0.0775906071 147 1305031234.4000349045 0.0517518595 0.0785222147 0.1177039519 0.0264730715 0.0031960000 16018485 955859216 1373700096 -0.0021216278 0.0300811771 0.0773216113 148 1305031234.4367709160 0.0520285629 0.0783432035 0.1177039519 0.0264561965 0.0032210000 16021525 955859216 1373700096 -0.0010569002 0.0301266722 0.0764063746 149 1305031234.4676060677 0.0521244556 0.0781672388 0.1177039519 0.0263710748 0.0032620000 16024341 955859216 1373700096 -0.0000301521 0.0312950797 0.0755332112 150 1305031234.4977810383 0.0514715053 0.0779892672 0.1177039519 0.0262857439 0.0033200000 16027157 955859216 1373700096 0.0003131304 0.0337689221 0.0748846531 151 1305031234.5376710892 0.0529874749 0.0778236925 0.1177039519 0.0263694389 0.0033320000 16030253 955859216 1373700096 0.0020663375 0.0324649103 0.0721167624 152 1305031234.5690369606 0.0528864600 0.0776596317 0.1177039519 0.0263540051 0.0033500000 16033069 955859216 1373700096 0.0024389506 0.0349965282 0.0705400109 153 1305031234.5982480049 0.0526661314 0.0774962755 0.1177039519 0.0262713519 0.0033440000 16035941 955859216 1373700096 0.0032646211 0.0370868072 0.0699264780 154 1305031234.6336491108 0.0545935780 0.0773475567 0.1177039519 0.0261990827 0.0033720000 16038813 955859216 1373700096 0.0064348611 0.0375754945 0.0691954643 155 1305031234.6658589840 0.0552347116 0.0772048932 0.1177039519 0.0261417907 0.0034380000 16041741 955859216 1373700096 0.0073851198 0.0391729027 0.0682770088 156 1305031234.6987318993 0.0601531491 0.0770955871 0.1177039519 0.0260894297 0.0036160000 16044669 955859216 1373700096 0.0154054714 0.0482381955 0.0762802437 157 1305031234.7344369888 0.0636237189 0.0770097790 0.1177039519 0.0260250058 0.0033020000 16047541 955859216 1373700096 0.0185482316 0.0479718111 0.0759599507 158 1305031234.7689719200 0.0690538287 0.0769594249 0.1177039519 0.0259683906 0.0032630000 16050525 955859216 1373700096 0.0242500808 0.0474112593 0.0763730109 159 1305031234.8015530109 0.0720786303 0.0769287281 0.1177039519 0.0260038479 0.0032650000 16053453 955859216 1373700096 0.0266861115 0.0485554934 0.0767038986 160 1305031234.8378078938 0.0752905980 0.0769184898 0.1177039519 0.0259368408 0.0032170000 16056493 955859216 1373700096 0.0293866396 0.0488920026 0.0775252953 161 1305031234.8693211079 0.0768731311 0.0769182081 0.1177039519 0.0258799062 0.0033470000 16059253 955859216 1373700096 0.0302141011 0.0490586385 0.0768966600 162 1305031234.9019980431 0.0766540244 0.0769165773 0.1177039519 0.0258031156 0.0032900000 16062181 955859216 1373700096 0.0290041454 0.0511919223 0.0779959708 163 1305031234.9381608963 0.0683568344 0.0768640635 0.1177039519 0.0259037563 0.0034800000 16065165 955859216 1373700096 0.0150774727 0.0655575022 0.0820494220 164 1305031234.9730799198 0.0662844554 0.0767995537 0.1177039519 0.0258298415 0.0036190000 16068149 955859216 1373700096 0.0135191940 0.0632652640 0.0834262297 165 1305031235.0050830841 0.0612123981 0.0767050861 0.1177039519 0.0258550921 0.0035250000 16070965 955859216 1373700096 0.0076055429 0.0652166605 0.0873648226 166 1305031235.0399720669 0.0574369244 0.0765890129 0.1177039519 0.0257842096 0.0034880000 16073949 955859216 1373700096 0.0046704742 0.0623534881 0.0880789459 167 1305031235.0729401112 0.0507667288 0.0764343884 0.1177039519 0.0257310674 0.0036510000 16076821 955859216 1373700096 -0.0032082947 0.0612958297 0.0880104676 168 1305031235.0995910168 0.0462689474 0.0762548322 0.1177039519 0.0256792878 0.0038650000 16079581 955859216 1373700096 -0.0068619079 0.0589458682 0.0883434415 169 1305031235.1362709999 0.0435532182 0.0760613315 0.1177039519 0.0256381497 0.0021490000 16082565 955859216 1373700096 -0.0095389225 0.0548299365 0.0875545815 170 1305031235.1663711071 0.0403424688 0.0758512206 0.1177039519 0.0256120406 0.0021170000 16085381 955859216 1373700096 -0.0155027909 0.0532327481 0.0867083147 171 1305031235.1998469830 0.0378330871 0.0756288923 0.1177039519 0.0255932374 0.0022620000 16088197 955859216 1373700096 -0.0242681168 0.0546089150 0.0857918486 172 1305031235.2375700474 0.0367451496 0.0754028240 0.1177039519 0.0255852207 0.0036100000 16091237 955859216 1373700096 -0.0274651125 0.0535214506 0.0865394473 173 1305031235.2690389156 0.0359791853 0.0751749417 0.1177039519 0.0255373666 0.0038110000 16094109 955859216 1373700096 -0.0321431048 0.0524480082 0.0873723030 174 1305031235.3064870834 0.0366539694 0.0749535568 0.1177039519 0.0255459202 0.0035930000 16097149 955859216 1373700096 -0.0354641378 0.0522957221 0.0887168646 175 1305031235.3380000591 0.0385226086 0.0747453800 0.1177039519 0.0254889119 0.0037130000 16099965 955859216 1373700096 -0.0418475494 0.0517322272 0.0894856974 176 1305031235.3698880672 0.0418642499 0.0745585554 0.1177039519 0.0254527898 0.0037120000 16102837 955859216 1373700096 -0.0455200486 0.0486559831 0.0893942639 177 1305031235.4060161114 0.0441422723 0.0743867120 0.1177039519 0.0255372790 0.0036290000 16105821 955859216 1373700096 -0.0470437147 0.0488652512 0.0916181207 178 1305031235.4381530285 0.0436690301 0.0742141407 0.1177039519 0.0255069750 0.0036320000 16108693 955859216 1373700096 -0.0514377244 0.0508223847 0.0957947299 179 1305031235.4700589180 0.0359788090 0.0740005355 0.1177039519 0.0254539715 0.0037430000 16111565 955859216 1373700096 -0.0415146053 0.0496471152 0.1044167727 180 1305031235.5059850216 0.0364689678 0.0737920268 0.1177039519 0.0254124026 0.0038260000 16114549 955859216 1373700096 -0.0395167656 0.0502550602 0.1082653776 181 1305031235.5385539532 0.0354845747 0.0735803834 0.1177039519 0.0253513644 0.0036500000 16117421 955859216 1373700096 -0.0374500938 0.0505292714 0.1121819988 182 1305031235.5703649521 0.0340083018 0.0733629544 0.1177039519 0.0252876673 0.0039060000 16120293 955859216 1373700096 -0.0283878613 0.0482452512 0.1202961579 183 1305031235.6060059071 0.0322141573 0.0731380976 0.1177039519 0.0252979803 0.0035190000 16123333 955859216 1373700096 -0.0248852689 0.0512797646 0.1278045624 184 1305031235.6389510632 0.0376408286 0.0729451777 0.1177039519 0.0252519013 0.0034660000 16126205 955859216 1373700096 -0.0257756952 0.0472916253 0.1307031065 185 1305031235.6705160141 0.0424963161 0.0727805892 0.1177039519 0.0251934111 0.0035590000 16129021 955859216 1373700096 -0.0282070301 0.0445736945 0.1335759908 186 1305031235.7057778835 0.0537667498 0.0726783643 0.1177039519 0.0251320598 0.0035990000 16132005 955859216 1373700096 -0.0305994488 0.0371355899 0.1364105493 187 1305031235.7387969494 0.0589671135 0.0726050421 0.1177039519 0.0250951662 0.0032820000 16134933 955859216 1373700096 -0.0335324518 0.0355586633 0.1385803819 188 1305031235.7696299553 0.0639677942 0.0725590993 0.1177039519 0.0250488189 0.0032440000 16137749 955859216 1373700096 -0.0368263870 0.0344985873 0.1404019743 189 1305031235.8072249889 0.0707154348 0.0725493444 0.1177039519 0.0249911211 0.0031790000 16140901 955859216 1373700096 -0.0401575975 0.0334581025 0.1410896778 190 1305031235.8388121128 0.0767441615 0.0725714224 0.1177039519 0.0249653927 0.0032110000 16143773 955859216 1373700096 -0.0434322730 0.0314447880 0.1433582455 191 1305031235.8700668812 0.0822628886 0.0726221631 0.1177039519 0.0249402030 0.0031620000 16146701 955859216 1373700096 -0.0463005453 0.0298775006 0.1458458304 192 1305031235.9061110020 0.0879280120 0.0727018810 0.1177039519 0.0248783029 0.0031750000 16149741 955859216 1373700096 -0.0480367281 0.0290345885 0.1483187526 193 1305031235.9382328987 0.0931847245 0.0728080098 0.1177039519 0.0248257960 0.0032360000 16152725 955859216 1373700096 -0.0493596420 0.0272868052 0.1510844976 194 1305031235.9700109959 0.0968082920 0.0729317226 0.1177039519 0.0247741905 0.0031970000 16155597 955859216 1373700096 -0.0508099496 0.0271167494 0.1540298760 195 1305031236.0068531036 0.1023339555 0.0730825032 0.1177039519 0.0247186813 0.0032080000 16158693 955859216 1373700096 -0.0522682369 0.0259966571 0.1573832929 196 1305031236.0380480289 0.1064010486 0.0732524958 0.1177039519 0.0246614242 0.0031550000 16161565 955859216 1373700096 -0.0538591705 0.0256929807 0.1601718068 197 1305031236.0698781013 0.1101010814 0.0734395445 0.1177039519 0.0246527537 0.0033330000 16164493 955859216 1373700096 -0.0554982312 0.0254004207 0.1633540094 198 1305031236.1058719158 0.1147850305 0.0736483601 0.1177039519 0.0245994992 0.0033370000 16167533 955859216 1373700096 -0.0567024536 0.0243052132 0.1665970534 199 1305031236.1383249760 0.1180258468 0.0738713625 0.1180258468 0.0245408802 0.0032070000 16170517 955859216 1373700096 -0.0578986406 0.0236122068 0.1692388207 200 1305031236.1709330082 0.1205825135 0.0741049183 0.1205825135 0.0244800487 0.0033000000 16173445 955859216 1373700096 -0.0588823631 0.0235353447 0.1709123403 201 1305031236.2071900368 0.1220321283 0.0743433621 0.1220321283 0.0244297574 0.0032460000 16176541 955859216 1373700096 -0.0592115074 0.0243521556 0.1725690663 202 1305031236.2383749485 0.1239182279 0.0745887822 0.1239182279 0.0243976391 0.0033460000 16179469 955859216 1373700096 -0.0601739585 0.0231169499 0.1747531146 203 1305031236.2699589729 0.1265276372 0.0748446386 0.1265276372 0.0243386806 0.0032650000 16182341 955859216 1373700096 -0.0610041022 0.0203759372 0.1761143059 204 1305031236.3069939613 0.1273658276 0.0751020955 0.1273658276 0.0243418653 0.0032280000 16185437 955859216 1373700096 -0.0607492998 0.0174827017 0.1767088175 205 1305031236.3392169476 0.1290936768 0.0753654690 0.1290936768 0.0242990382 0.0032360000 16188365 955859216 1373700096 -0.0600112379 0.0135108754 0.1767363250 206 1305031236.3700959682 0.1293819398 0.0756276849 0.1293819398 0.0242574217 0.0032910000 16191237 955859216 1373700096 -0.0587456115 0.0101834992 0.1748930067 207 1305031236.4058690071 0.1275916696 0.0758787186 0.1293819398 0.0242532698 0.0032700000 16194277 955859216 1373700096 -0.0570629649 0.0073155160 0.1724871993 208 1305031236.4387879372 0.1253223717 0.0761164285 0.1293819398 0.0241947407 0.0033220000 16197205 955859216 1373700096 -0.0544090606 0.0049160658 0.1697740257 209 1305031236.4751410484 0.1214253157 0.0763332174 0.1293819398 0.0241384814 0.0033880000 16200301 955859216 1373700096 -0.0504453368 0.0032799738 0.1665818840 210 1305031236.5077209473 0.1166856661 0.0765253720 0.1293819398 0.0240865221 0.0033540000 16203285 955859216 1373700096 -0.0460994057 0.0028512075 0.1628962755 211 1305031236.5386450291 0.1136959717 0.0767015359 0.1293819398 0.0240498422 0.0033220000 16206157 955859216 1373700096 -0.0423955880 0.0008713552 0.1592175066 212 1305031236.5740950108 0.1085335016 0.0768516867 0.1293819398 0.0239939602 0.0033300000 16209197 955859216 1373700096 -0.0392499566 -0.0002991861 0.1546646804 213 1305031236.6057569981 0.1066029444 0.0769913640 0.1293819398 0.0239413401 0.0033300000 16212069 955859216 1373700096 -0.0362126194 -0.0033067071 0.1503724158 214 1305031236.6384010315 0.1033025086 0.0771143133 0.1293819398 0.0239167244 0.0033410000 16214997 955859216 1373700096 -0.0327609107 -0.0045093168 0.1447276920 215 1305031236.6751470566 0.0975403190 0.0772093179 0.1293819398 0.0238779237 0.0033790000 16217981 955859216 1373700096 -0.0298910532 -0.0045070108 0.1388629824 216 1305031236.7033619881 0.0938628092 0.0772864174 0.1293819398 0.0238276953 0.0033920000 16220741 955859216 1373700096 -0.0253677480 -0.0047145602 0.1340842247 217 1305031236.7339220047 0.0836536065 0.0773157593 0.1293819398 0.0238110899 0.0036190000 16223557 955859216 1373700096 -0.0240915138 0.0022722969 0.1230739430 218 1305031236.7740409374 0.0799264461 0.0773277350 0.1293819398 0.0237980825 0.0033890000 16226653 955859216 1373700096 -0.0215589646 0.0013983239 0.1169725060 219 1305031236.8025879860 0.0771414414 0.0773268843 0.1293819398 0.0238772131 0.0035660000 16229525 955859216 1373700096 -0.0194865949 0.0030616638 0.1087024212 220 1305031236.8364150524 0.0706394166 0.0772964867 0.1293819398 0.0238246398 0.0036080000 16232397 955859216 1373700096 -0.0167832077 0.0065751509 0.1017707288 221 1305031236.8743979931 0.0663740039 0.0772470637 0.1293819398 0.0237842751 0.0034800000 16235437 955859216 1373700096 -0.0144423535 0.0079495814 0.0945944637 222 1305031236.9060690403 0.0646687150 0.0771904045 0.1293819398 0.0237838200 0.0035200000 16238309 955859216 1373700096 -0.0124654584 0.0087633217 0.0869767815 223 1305031236.9344370365 0.0639175922 0.0771308852 0.1293819398 0.0237471459 0.0036960000 16241069 955859216 1373700096 -0.0093102064 0.0098401252 0.0807957128 224 1305031236.9744000435 0.0623459779 0.0770648811 0.1293819398 0.0237018084 0.0035910000 16244109 955859216 1373700096 -0.0081324503 0.0096913371 0.0737816393 225 1305031237.0074260235 0.0622801743 0.0769991713 0.1293819398 0.0236498347 0.0037330000 16247093 955859216 1373700096 -0.0099124825 0.0079330280 0.0646047369 226 1305031237.0370240211 0.0608993545 0.0769279332 0.1293819398 0.0236298526 0.0039240000 16249909 955859216 1373700096 -0.0092246346 0.0098671662 0.0586897656 227 1305031237.0734269619 0.0613763444 0.0768594240 0.1293819398 0.0235835239 0.0037200000 16252837 955859216 1373700096 -0.0068014879 0.0086183269 0.0532100238 228 1305031237.1059679985 0.0636456013 0.0768014686 0.1293819398 0.0235395934 0.0037160000 16255765 955859216 1373700096 -0.0043450091 0.0075765699 0.0470598601 229 1305031237.1378319263 0.0657502785 0.0767532101 0.1293819398 0.0234929587 0.0039480000 16258637 955859216 1373700096 -0.0009268312 0.0083167991 0.0407098494 230 1305031237.1712269783 0.0652377903 0.0767031431 0.1293819398 0.0235092688 0.0038110000 16261565 955859216 1373700096 0.0004986281 0.0113045843 0.0360460691 231 1305031237.2042291164 0.0662112236 0.0766577235 0.1293819398 0.0235163429 0.0037640000 16264381 955859216 1373700096 0.0030202158 0.0109738437 0.0304247718 232 1305031237.2375690937 0.0675603300 0.0766185106 0.1293819398 0.0235227580 0.0039550000 16267365 955859216 1373700096 0.0058834236 0.0166050829 0.0267745312 233 1305031237.2746589184 0.0702480823 0.0765911697 0.1293819398 0.0234881777 0.0038120000 16270349 955859216 1373700096 0.0103641655 0.0170947649 0.0236265585 234 1305031237.3058099747 0.0739552230 0.0765799050 0.1293819398 0.0234531236 0.0039360000 16273221 955859216 1373700096 0.0154403104 0.0214062463 0.0221824832 235 1305031237.3371419907 0.0783539340 0.0765874541 0.1293819398 0.0234493733 0.0039000000 16276093 955859216 1373700096 0.0194413941 0.0219100527 0.0191945359 236 1305031237.3741660118 0.0828806385 0.0766141201 0.1293819398 0.0234122081 0.0039100000 16279021 955859216 1373700096 0.0243778117 0.0234823991 0.0168121681 237 1305031237.4057340622 0.0846158192 0.0766478825 0.1293819398 0.0234218822 0.0038720000 16281949 955859216 1373700096 0.0261330903 0.0257154033 0.0143192587 238 1305031237.4377219677 0.0888056979 0.0766989658 0.1293819398 0.0234198836 0.0038820000 16284821 955859216 1373700096 0.0299736988 0.0273824316 0.0126230018 239 1305031237.4741280079 0.0917911157 0.0767621129 0.1293819398 0.0233958629 0.0038020000 16287749 955859216 1373700096 0.0332795121 0.0291353278 0.0111892074 240 1305031237.5060451031 0.0935133919 0.0768319099 0.1293819398 0.0233791853 0.0037350000 16290677 955859216 1373700096 0.0351567380 0.0310774185 0.0105323372 241 1305031237.5376501083 0.0962828696 0.0769126192 0.1293819398 0.0233333003 0.0037550000 16293549 955859216 1373700096 0.0382430442 0.0326881409 0.0094936443 242 1305031237.5739479065 0.0985924080 0.0770022051 0.1293819398 0.0233000925 0.0043960000 16296477 955859216 1373700096 0.0403174423 0.0335273854 0.0086898422 243 1305031237.6068129539 0.0993047878 0.0770939853 0.1293819398 0.0232624440 0.0038500000 16299461 955859216 1373700096 0.0413433984 0.0356355198 0.0089348685 244 1305031237.6378550529 0.0999357924 0.0771875993 0.1293819398 0.0232247352 0.0038580000 16302277 955859216 1373700096 0.0416128710 0.0379906185 0.0089664180 245 1305031237.6752760410 0.1003907323 0.0772823059 0.1293819398 0.0231908798 0.0038520000 16305261 955859216 1373700096 0.0413942151 0.0397023447 0.0089492351 246 1305031237.7071180344 0.0999117941 0.0773742957 0.1293819398 0.0231466703 0.0039940000 16308189 955859216 1373700096 0.0402722321 0.0416004360 0.0088296309 247 1305031237.7416670322 0.0970252380 0.0774538542 0.1293819398 0.0231221935 0.0039020000 16311117 955859216 1373700096 0.0364361145 0.0436865203 0.0089879399 248 1305031237.7743060589 0.0986428559 0.0775392937 0.1293819398 0.0231625124 0.0039060000 16313933 955859216 1373700096 0.0384599455 0.0432362147 0.0097377347 249 1305031237.8064959049 0.0986251757 0.0776239760 0.1293819398 0.0231279571 0.0038070000 16316861 955859216 1373700096 0.0395809039 0.0410120487 0.0091694025 250 1305031237.8430309296 0.0939860344 0.0776894242 0.1293819398 0.0231581671 0.0039400000 16319901 955859216 1373700096 0.0328043476 0.0441059731 0.0088357227 251 1305031237.8754220009 0.0963337198 0.0777637043 0.1293819398 0.0233721976 0.0040230000 16322717 955859216 1373700096 0.0365647636 0.0426738374 0.0090782121 252 1305031237.9077839851 0.0956835374 0.0778348147 0.1293819398 0.0233609928 0.0039340000 16325645 955859216 1373700096 0.0371977799 0.0394808128 0.0085992711 253 1305031237.9441869259 0.0927685201 0.0778938412 0.1293819398 0.0234578454 0.0039990000 16328629 955859216 1373700096 0.0329982266 0.0422241427 0.0098004350 254 1305031237.9738099575 0.0928854644 0.0779528634 0.1293819398 0.0234156050 0.0040160000 16331333 955859216 1373700096 0.0320093706 0.0445174538 0.0126373079 255 1305031238.0069320202 0.0903643072 0.0780015357 0.1293819398 0.0233806015 0.0040910000 16334317 955859216 1373700096 0.0295133181 0.0439014770 0.0159652755 256 1305031238.0431399345 0.0879662931 0.0780404605 0.1293819398 0.0235632155 0.0040680000 16337301 955859216 1373700096 0.0273651909 0.0426442809 0.0184429754 257 1305031238.0740320683 0.0831349716 0.0780602835 0.1293819398 0.0235902595 0.0043020000 16364693 955859216 1373700096 0.0212342571 0.0434957631 0.0208485145 258 1305031238.1065878868 0.0739346445 0.0780442927 0.1293819398 0.0235770483 0.0043300000 16418765 955859216 1373700096 0.0099968342 0.0400418751 0.0162620507 259 1305031238.1433279514 0.0702660531 0.0780142609 0.1293819398 0.0236079523 0.0042680000 16421749 955859216 1373700096 0.0031908087 0.0369652733 0.0145801259 260 1305031238.1723001003 0.0607392639 0.0779478186 0.1293819398 0.0235835536 0.0043870000 16424621 955859216 1373700096 -0.0123609994 0.0425250046 0.0162339602 261 1305031238.2054259777 0.0575106181 0.0778695151 0.1293819398 0.0235421761 0.0043550000 16427437 955859216 1373700096 -0.0164379030 0.0339175537 0.0161591489 262 1305031238.2401471138 0.0548475385 0.0777816450 0.1293819398 0.0235209162 0.0042370000 16430421 955859216 1373700096 -0.0199683253 0.0285854395 0.0181590132 263 1305031238.2725269794 0.0521168299 0.0776840601 0.1293819398 0.0234798610 0.0043340000 16433349 955859216 1373700096 -0.0242840815 0.0271419343 0.0214722920 264 1305031238.3060529232 0.0491204374 0.0775758646 0.1293819398 0.0236664119 0.0044400000 16436221 955859216 1373700096 -0.0308076907 0.0286806449 0.0255290829 265 1305031238.3425960541 0.0484528169 0.0774659663 0.1293819398 0.0236591682 0.0043210000 16439205 955859216 1373700096 -0.0287171472 0.0263488330 0.0315173455 266 1305031238.3741040230 0.0511545055 0.0773670510 0.1293819398 0.0237087263 0.0043510000 16442077 955859216 1373700096 -0.0185081828 0.0263486821 0.0426840484 267 1305031238.4060359001 0.0587066002 0.0772971617 0.1293819398 0.0236656462 0.0043810000 16444949 955859216 1373700096 -0.0044276002 0.0272218361 0.0547322966 268 1305031238.4434239864 0.0614914484 0.0772381852 0.1293819398 0.0236277451 0.0040310000 16447933 955859216 1373700096 -0.0030600268 0.0255919136 0.0578880571 269 1305031238.4740819931 0.0620667301 0.0771817857 0.1293819398 0.0235895486 0.0039490000 16450805 955859216 1373700096 -0.0041477438 0.0235918295 0.0609793849 270 1305031238.5058109760 0.0628744587 0.0771287956 0.1293819398 0.0236100558 0.0039370000 16453677 955859216 1373700096 -0.0061630611 0.0196527932 0.0632091910 271 1305031238.5432639122 0.0662233308 0.0770885540 0.1293819398 0.0235695898 0.0042310000 16456717 955859216 1373700096 -0.0083757732 0.0141923884 0.0641228557 272 1305031238.5741839409 0.0668667555 0.0770509739 0.1293819398 0.0235293020 0.0041440000 16459477 955859216 1373700096 -0.0110774096 0.0120399836 0.0665269569 273 1305031238.6058249474 0.0687560961 0.0770205897 0.1293819398 0.0234906889 0.0039430000 16462405 955859216 1373700096 -0.0132218571 0.0094858408 0.0686016232 274 1305031238.6427590847 0.0702593699 0.0769959137 0.1293819398 0.0234554477 0.0039170000 16465445 955859216 1373700096 -0.0156269819 0.0075958013 0.0711685792 275 1305031238.6738131046 0.0729445741 0.0769811816 0.1293819398 0.0234191660 0.0039630000 16468205 955859216 1373700096 -0.0182276089 0.0063572079 0.0729374588 276 1305031238.7051889896 0.0738083795 0.0769696859 0.1293819398 0.0233776495 0.0038830000 16471077 955859216 1373700096 -0.0212240163 0.0062532169 0.0747258440 277 1305031238.7413070202 0.0757662579 0.0769653414 0.1293819398 0.0233646435 0.0038600000 16474117 955859216 1373700096 -0.0232208502 0.0053834324 0.0760364830 278 1305031238.7717959881 0.0783632249 0.0769703698 0.1293819398 0.0233427279 0.0038520000 16476989 955859216 1373700096 -0.0255318824 0.0036305028 0.0772750378 279 1305031238.8070189953 0.0809199065 0.0769845258 0.1293819398 0.0233219206 0.0038000000 16479973 955859216 1373700096 -0.0277766678 0.0035976029 0.0783869475 280 1305031238.8429400921 0.0820507258 0.0770026194 0.1293819398 0.0232840926 0.0038370000 16483013 955859216 1373700096 -0.0297873858 0.0034595265 0.0801495984 281 1305031238.8737230301 0.0864961743 0.0770364043 0.1293819398 0.0232872644 0.0037980000 16485941 955859216 1373700096 -0.0303279571 0.0006338620 0.0815638900 282 1305031238.9061720371 0.0900246426 0.0770824619 0.1293819398 0.0232631932 0.0038560000 16488813 955859216 1373700096 -0.0309101101 -0.0021086712 0.0832682997 283 1305031238.9427859783 0.0923601761 0.0771364467 0.1293819398 0.0232222351 0.0038420000 16491909 955859216 1373700096 -0.0315830298 -0.0032143630 0.0849637166 284 1305031238.9723079205 0.0947248116 0.0771983776 0.1293819398 0.0231929662 0.0037940000 16494781 955859216 1373700096 -0.0320237093 -0.0047784243 0.0863167793 285 1305031239.0104830265 0.0974063575 0.0772692828 0.1293819398 0.0231892196 0.0038740000 16497877 955859216 1373700096 -0.0324700698 -0.0056854882 0.0876727626 286 1305031239.0408790112 0.0989406779 0.0773450569 0.1293819398 0.0231523568 0.0038630000 16500749 955859216 1373700096 -0.0329134800 -0.0062079388 0.0889886692 287 1305031239.0746610165 0.1016761288 0.0774298342 0.1293819398 0.0231613675 0.0038660000 16503733 955859216 1373700096 -0.0332464576 -0.0082607493 0.0900316983 288 1305031239.1109058857 0.1042143032 0.0775228358 0.1293819398 0.0231211039 0.0038590000 16506829 955859216 1373700096 -0.0336121991 -0.0106992694 0.0910257772 289 1305031239.1417789459 0.1057536080 0.0776205201 0.1293819398 0.0230926737 0.0038640000 16509701 955859216 1373700096 -0.0341956951 -0.0129565233 0.0915136933 290 1305031239.1757500172 0.1081253663 0.0777257092 0.1293819398 0.0230740313 0.0039200000 16512685 955859216 1373700096 -0.0339833610 -0.0160604324 0.0914131850 291 1305031239.2096450329 0.1084647700 0.0778313418 0.1293819398 0.0230402144 0.0038600000 16515669 955859216 1373700096 -0.0333185159 -0.0167816188 0.0905778855 292 1305031239.2417099476 0.1087382957 0.0779371875 0.1293819398 0.0230141655 0.0038850000 16518597 955859216 1373700096 -0.0325305387 -0.0178136453 0.0897828713 293 1305031239.2738199234 0.1081425399 0.0780402774 0.1293819398 0.0230012187 0.0037860000 16521525 955859216 1373700096 -0.0314960815 -0.0184719414 0.0887462571 294 1305031239.3101770878 0.1077411920 0.0781413009 0.1293819398 0.0229631136 0.0038380000 16524621 955859216 1373700096 -0.0305581316 -0.0190046988 0.0873268917 295 1305031239.3419699669 0.1064716503 0.0782373360 0.1293819398 0.0229273845 0.0038480000 16527549 955859216 1373700096 -0.0295745973 -0.0188102741 0.0857145339 296 1305031239.3750240803 0.1045625731 0.0783262726 0.1293819398 0.0229099300 0.0039480000 16530421 955859216 1373700096 -0.0283227544 -0.0182579514 0.0835749730 297 1305031239.4106309414 0.1021409035 0.0784064566 0.1293819398 0.0228747058 0.0039970000 16533405 955859216 1373700096 -0.0272685811 -0.0168108549 0.0812683478 298 1305031239.4415419102 0.1011026055 0.0784826182 0.1293819398 0.0228409040 0.0039030000 16536277 955859216 1373700096 -0.0257892776 -0.0167703554 0.0789190754 299 1305031239.4733181000 0.0975235403 0.0785463002 0.1293819398 0.0228034916 0.0039690000 16539149 955859216 1373700096 -0.0248485692 -0.0142273344 0.0764239803 300 1305031239.5097389221 0.0937891901 0.0785971098 0.1293819398 0.0227677668 0.0039320000 16542133 955859216 1373700096 -0.0232452229 -0.0109536545 0.0733893886 301 1305031239.5438020229 0.0905394852 0.0786367855 0.1293819398 0.0227395858 0.0039780000 16545117 955859216 1373700096 -0.0220225826 -0.0087331738 0.0705205873 302 1305031239.5761160851 0.0873840451 0.0786657499 0.1293819398 0.0227124626 0.0039810000 16547989 955859216 1373700096 -0.0208297241 -0.0058099916 0.0674899295 303 1305031239.6111609936 0.0851487443 0.0786871459 0.1293819398 0.0226802888 0.0040690000 16550973 955859216 1373700096 -0.0198002625 -0.0038434151 0.0644313395 304 1305031239.6414220333 0.0840988457 0.0787049476 0.1293819398 0.0226459365 0.0040650000 16553789 955859216 1373700096 -0.0186249185 -0.0030144455 0.0610357672 305 1305031239.6710560322 0.0813686997 0.0787136812 0.1293819398 0.0226220312 0.0040570000 16556549 955859216 1373700096 -0.0177133847 -0.0001970913 0.0579034127 306 1305031239.7075550556 0.0798802748 0.0787174936 0.1293819398 0.0226357663 0.0040310000 16559533 955859216 1373700096 -0.0162336882 0.0005733338 0.0545385778 307 1305031239.7417550087 0.0797691345 0.0787209191 0.1293819398 0.0226002484 0.0040130000 16562517 955859216 1373700096 -0.0143370796 0.0005239276 0.0510042012 308 1305031239.7712600231 0.0796726421 0.0787240091 0.1293819398 0.0225691967 0.0040500000 16565277 955859216 1373700096 -0.0119088432 0.0006997909 0.0477361903 309 1305031239.8060870171 0.0800077990 0.0787281638 0.1293819398 0.0226522842 0.0041590000 16568205 955859216 1373700096 -0.0085493969 -0.0009695742 0.0446668342 310 1305031239.8392889500 0.0772462934 0.0787233836 0.1293819398 0.0226364332 0.0042740000 16571133 955859216 1373700096 -0.0087364251 0.0017784405 0.0407989845 311 1305031239.8744299412 0.0738556534 0.0787077317 0.1293819398 0.0226103514 0.0042410000 16574005 955859216 1373700096 -0.0103796562 0.0031632548 0.0381559245 312 1305031239.9090619087 0.0726454258 0.0786883012 0.1293819398 0.0226219815 0.0042930000 16576989 955859216 1373700096 -0.0093715200 0.0042151357 0.0357014947 313 1305031239.9403729439 0.0714972094 0.0786653265 0.1293819398 0.0226001382 0.0043100000 16579805 955859216 1373700096 -0.0096564209 0.0049211038 0.0321686529 314 1305031239.9710669518 0.0703164265 0.0786387376 0.1293819398 0.0225996859 0.0043770000 16582677 955859216 1373700096 -0.0096261315 0.0068324888 0.0289912429 315 1305031240.0088651180 0.0710592419 0.0786146758 0.1293819398 0.0226426094 0.0044340000 16585773 955859216 1373700096 -0.0085325185 0.0051985742 0.0246548094 316 1305031240.0396599770 0.0716279447 0.0785925658 0.1293819398 0.0226147906 0.0044620000 16588533 955859216 1373700096 -0.0075018411 0.0056852335 0.0208913647 317 1305031240.0711870193 0.0733380541 0.0785759901 0.1293819398 0.0225805240 0.0045000000 16591405 955859216 1373700096 -0.0054887813 0.0053694951 0.0174562708 318 1305031240.1093459129 0.0759742260 0.0785678084 0.1293819398 0.0225894317 0.0023650000 16594445 955859216 1373700096 -0.0011348637 0.0040787775 0.0141578205 319 1305031240.1435019970 0.0808385909 0.0785749269 0.1293819398 0.0225906288 0.0046990000 16597429 955859216 1373700096 0.0071544717 0.0046025580 0.0129885925 320 1305031240.1775770187 0.0820559710 0.0785858052 0.1293819398 0.0225796257 0.0045830000 16600301 955859216 1373700096 0.0093820710 0.0072606485 0.0105753252 321 1305031240.2093310356 0.0886179730 0.0786170580 0.1293819398 0.0225931788 0.0047260000 16603229 955859216 1373700096 0.0205774549 0.0082064066 0.0137800118 322 1305031240.2410049438 0.0942756683 0.0786656872 0.1293819398 0.0226276489 0.0045670000 16606045 955859216 1373700096 0.0272461176 0.0095909247 0.0107539641 323 1305031240.2774341106 0.0951758251 0.0787168022 0.1293819398 0.0226123252 0.0043830000 16609029 955859216 1373700096 0.0295029171 0.0114371898 0.0092438282 324 1305031240.3089289665 0.1019064113 0.0787883751 0.1293819398 0.0225804228 0.0046410000 16611845 955859216 1373700096 0.0384545438 0.0167512354 0.0124493493 325 1305031240.3422729969 0.1051696390 0.0788695482 0.1293819398 0.0225615115 0.0045110000 16614773 955859216 1373700096 0.0423598215 0.0175842382 0.0109759672 326 1305031240.3774259090 0.1024279892 0.0789418134 0.1293819398 0.0225844764 0.0045750000 16617757 955859216 1373700096 0.0380392708 0.0368457884 0.0167408269 327 1305031240.4091110229 0.1024276316 0.0790136354 0.1293819398 0.0225523601 0.0044680000 16620573 955859216 1373700096 0.0374387652 0.0398636423 0.0134967025 328 1305031240.4417860508 0.1018170342 0.0790831580 0.1293819398 0.0225179424 0.0043780000 16623501 955859216 1373700096 0.0356613211 0.0427857041 0.0123837441 329 1305031240.4776389599 0.0979026407 0.0791403601 0.1293819398 0.0224951646 0.0046910000 16626485 955859216 1373700096 0.0240153540 0.0579091907 0.0132841170 330 1305031240.5084490776 0.0988524407 0.0792000936 0.1293819398 0.0224801310 0.0045920000 16629245 955859216 1373700096 0.0232849345 0.0611598976 0.0136786876 331 1305031240.5412700176 0.0976829156 0.0792559330 0.1293819398 0.0224791411 0.0044350000 16632173 955859216 1373700096 0.0181751046 0.0660723746 0.0140453605 332 1305031240.5759088993 0.1004936621 0.0793199020 0.1293819398 0.0224599738 0.0045510000 16635157 955859216 1373700096 0.0113481367 0.0773333311 0.0177994557 333 1305031240.6101338863 0.0985952839 0.0793777861 0.1293819398 0.0224367077 0.0044920000 16638085 955859216 1373700096 0.0095900502 0.0763127357 0.0175895821 334 1305031240.6398229599 0.0968880355 0.0794302120 0.1293819398 0.0224248617 0.0044260000 16640845 955859216 1373700096 0.0080514112 0.0752221942 0.0189327989 335 1305031240.6747570038 0.0939170495 0.0794734563 0.1293819398 0.0223957463 0.0044810000 16643829 955859216 1373700096 0.0116128158 0.0682687163 0.0196817219 336 1305031240.7079319954 0.0906252638 0.0795066462 0.1293819398 0.0223964270 0.0045080000 16646757 955859216 1373700096 0.0118399439 0.0630886406 0.0206707567 337 1305031240.7439579964 0.0884484947 0.0795331798 0.1293819398 0.0223746917 0.0046680000 16649629 955859216 1373700096 0.0126167769 0.0597010367 0.0220586564 338 1305031240.7768330574 0.0859069750 0.0795520372 0.1293819398 0.0223444589 0.0046990000 16652613 955859216 1373700096 0.0141354557 0.0529533289 0.0214349944 339 1305031240.8096249104 0.0831495076 0.0795626492 0.1293819398 0.0223310880 0.0048350000 16655485 955859216 1373700096 0.0138320737 0.0467557497 0.0210178904 340 1305031240.8425960541 0.0785892978 0.0795597864 0.1293819398 0.0223101918 0.0046840000 16658357 955859216 1373700096 0.0090573700 0.0450307280 0.0204496477 341 1305031240.8794100285 0.0757326037 0.0795485630 0.1293819398 0.0222914086 0.0046160000 16661397 955859216 1373700096 0.0060232868 0.0418390669 0.0188229922 342 1305031240.9084498882 0.0713148341 0.0795244878 0.1293819398 0.0222706352 0.0046800000 16664213 955859216 1373700096 0.0004868609 0.0386553966 0.0172266942 343 1305031240.9423189163 0.0638845712 0.0794788904 0.1293819398 0.0222670328 0.0049130000 16667085 955859216 1373700096 -0.0225952584 0.0353239551 0.0041778591 344 1305031240.9779360294 0.0637048855 0.0794330357 0.1293819398 0.0222355155 0.0048310000 16670069 955859216 1373700096 -0.0259916317 0.0315811485 0.0039918376 345 1305031241.0083029270 0.0611807704 0.0793801306 0.1293819398 0.0223161438 0.0048580000 16672885 955859216 1373700096 -0.0336975195 0.0334771685 0.0058551719 346 1305031241.0401480198 0.0594597049 0.0793225571 0.1293819398 0.0223675394 0.0048910000 16675645 955859216 1373700096 -0.0433075018 0.0326376930 0.0068435045 347 1305031241.0759329796 0.0611368977 0.0792701489 0.1293819398 0.0223587979 0.0048980000 16678685 955859216 1373700096 -0.0488557294 0.0300418306 0.0072111716 348 1305031241.1065559387 0.0645581782 0.0792278731 0.1293819398 0.0223344526 0.0048550000 16681501 955859216 1373700096 -0.0592546761 0.0267779976 0.0070519778 349 1305031241.1400520802 0.0708326846 0.0792038181 0.1293819398 0.0223340813 0.0048710000 16684373 955859216 1373700096 -0.0696238056 0.0245172344 0.0058230390 350 1305031241.1781818867 0.0760022774 0.0791946708 0.1293819398 0.0223922276 0.0048400000 16687413 955859216 1373700096 -0.0779143199 0.0255588740 0.0068799523 351 1305031241.2106790543 0.0776215345 0.0791901890 0.1293819398 0.0223652863 0.0047920000 16690341 955859216 1373700096 -0.0815805420 0.0258175414 0.0095359301 352 1305031241.2393150330 0.0763606951 0.0791821506 0.1293819398 0.0223849191 0.0048220000 16693045 955859216 1373700096 -0.0765675157 0.0227028448 0.0130872121 353 1305031241.2768468857 0.0721292347 0.0791621707 0.1293819398 0.0223865008 0.0046350000 16696141 955859216 1373700096 -0.0678284690 0.0223374609 0.0186873339 354 1305031241.3063299656 0.0491013192 0.0790772530 0.1293819398 0.0224119773 0.0048730000 16698957 955859216 1373700096 -0.0225286670 0.0321114436 0.0529580191 355 1305031241.3424758911 0.0517745167 0.0790003439 0.1293819398 0.0223943630 0.0048150000 16701941 955859216 1373700096 -0.0111169685 0.0332728997 0.0661295801 356 1305031241.3795149326 0.0558900833 0.0789354275 0.1293819398 0.0224381011 0.0045140000 16704925 955859216 1373700096 -0.0126255201 0.0293409880 0.0667413920 357 1305031241.4096820354 0.0599738955 0.0788823139 0.1293819398 0.0224364371 0.0045070000 16707741 955859216 1373700096 -0.0147497607 0.0260046702 0.0675682276 358 1305031241.4455459118 0.0641320497 0.0788411121 0.1293819398 0.0224245595 0.0044940000 16710725 955859216 1373700096 -0.0168651175 0.0241405703 0.0703400224 359 1305031241.4775071144 0.0677056909 0.0788100942 0.1293819398 0.0226546917 0.0044720000 16713597 955859216 1373700096 -0.0175436419 0.0213478841 0.0718658492 360 1305031241.5098490715 0.0707900599 0.0787878163 0.1293819398 0.0226543911 0.0046570000 16716469 955859216 1373700096 -0.0184247009 0.0186483227 0.0723617524 361 1305031241.5477299690 0.0730455518 0.0787719098 0.1293819398 0.0226265251 0.0044700000 16719565 955859216 1373700096 -0.0191417094 0.0160404239 0.0720604509 362 1305031241.5783948898 0.0736180991 0.0787576727 0.1293819398 0.0226103688 0.0044230000 16722325 955859216 1373700096 -0.0194541663 0.0153433355 0.0714565516 363 1305031241.6092638969 0.0744990706 0.0787459410 0.1293819398 0.0226058127 0.0045000000 16725141 955859216 1373700096 -0.0190242454 0.0137994029 0.0703397393 364 1305031241.6475839615 0.0764923245 0.0787397498 0.1293819398 0.0225785127 0.0043750000 16728237 955859216 1373700096 -0.0180032756 0.0108724134 0.0684228167 365 1305031241.6783659458 0.0733190477 0.0787248985 0.1293819398 0.0225985719 0.0044960000 16731109 955859216 1373700096 -0.0174652934 0.0139334863 0.0670367256 366 1305031241.7098269463 0.0718196481 0.0787060317 0.1293819398 0.0225791077 0.0044420000 16733869 955859216 1373700096 -0.0165303163 0.0155174211 0.0655625239 367 1305031241.7471020222 0.0703010485 0.0786831299 0.1293819398 0.0225538631 0.0045550000 16736965 955859216 1373700096 -0.0158861317 0.0166299809 0.0643447414 368 1305031241.7782680988 0.0703513026 0.0786604890 0.1293819398 0.0225432212 0.0044850000 16739837 955859216 1373700096 -0.0150659382 0.0165146478 0.0632939562 369 1305031241.8098289967 0.0686716363 0.0786334190 0.1293819398 0.0225434635 0.0044860000 16742597 955859216 1373700096 -0.0149444956 0.0186148323 0.0625777617 370 1305031241.8464360237 0.0701636672 0.0786105278 0.1293819398 0.0225480952 0.0045200000 16745637 955859216 1373700096 -0.0147995036 0.0163790230 0.0611398518 371 1305031241.8787989616 0.0702394992 0.0785879643 0.1293819398 0.0226310406 0.0044420000 16748565 955859216 1373700096 -0.0153571283 0.0165247861 0.0600692034 372 1305031241.9114871025 0.0678054094 0.0785589790 0.1293819398 0.0226612586 0.0044880000 16751437 955859216 1373700096 -0.0161979757 0.0193422493 0.0601753145 373 1305031241.9477050304 0.0686355457 0.0785323746 0.1293819398 0.0226655006 0.0045650000 16754421 955859216 1373700096 -0.0164064001 0.0184683427 0.0597058199 374 1305031241.9783430099 0.0685030371 0.0785055582 0.1293819398 0.0228068675 0.0045460000 16757293 955859216 1373700096 -0.0174925923 0.0185504332 0.0589754246 375 1305031242.0105700493 0.0680280551 0.0784776182 0.1293819398 0.0229214886 0.0046590000 16760109 955859216 1373700096 -0.0192090981 0.0190746579 0.0581122190 376 1305031242.0463600159 0.0690036267 0.0784524214 0.1293819398 0.0230206875 0.0046020000 16763093 955859216 1373700096 -0.0207541659 0.0181818940 0.0566934645 377 1305031242.0795490742 0.0706422701 0.0784317048 0.1293819398 0.0231572456 0.0045460000 16765965 955859216 1373700096 -0.0225527771 0.0163900238 0.0548390783 378 1305031242.1105840206 0.0724679157 0.0784159276 0.1293819398 0.0232664485 0.0046240000 16768837 955859216 1373700096 -0.0251903366 0.0135148847 0.0523816310 379 1305031242.1466050148 0.0747135058 0.0784061587 0.1293819398 0.0234266554 0.0046080000 16771821 955859216 1373700096 -0.0277009103 0.0105137443 0.0499099307 380 1305031242.1797080040 0.0771528482 0.0784028605 0.1293819398 0.0235321348 0.0045730000 16774749 955859216 1373700096 -0.0303149857 0.0068648071 0.0474743210 381 1305031242.2087249756 0.0792200193 0.0784050053 0.1293819398 0.0235840687 0.0046300000 16777509 955859216 1373700096 -0.0332985446 0.0028773148 0.0451939292 382 1305031242.2478089333 0.0814961344 0.0784130972 0.1293819398 0.0236611772 0.0045990000 16780605 955859216 1373700096 -0.0356163867 -0.0013128872 0.0430766232 383 1305031242.2794981003 0.0828472674 0.0784246747 0.1293819398 0.0237188562 0.0046720000 16783477 955859216 1373700096 -0.0381090231 -0.0039262548 0.0406904109 384 1305031242.3097639084 0.0844771564 0.0784404364 0.1293819398 0.0237620057 0.0045900000 16786237 955859216 1373700096 -0.0399668328 -0.0070788055 0.0382580832 385 1305031242.3471269608 0.0859550238 0.0784599548 0.1293819398 0.0238872527 0.0046520000 16789333 955859216 1373700096 -0.0416677445 -0.0102763465 0.0355849937 386 1305031242.3784790039 0.0863576382 0.0784804151 0.1293819398 0.0240105208 0.0045840000 16792205 955859216 1373700096 -0.0431457572 -0.0119093964 0.0337582715 387 1305031242.4109969139 0.0875283405 0.0785037947 0.1293819398 0.0240846234 0.0046370000 16795077 955859216 1373700096 -0.0441853069 -0.0142219281 0.0315071642 388 1305031242.4470989704 0.0886470005 0.0785299370 0.1293819398 0.0242469800 0.0045190000 16798117 955859216 1373700096 -0.0455405451 -0.0166977216 0.0285820197 389 1305031242.4776470661 0.0901352018 0.0785597706 0.1293819398 0.0243641069 0.0045470000 16800989 955859216 1373700096 -0.0469568670 -0.0184696857 0.0250412542 390 1305031242.5097260475 0.0920707136 0.0785944140 0.1293819398 0.0246397218 0.0046440000 16803861 955859216 1373700096 -0.0487446263 -0.0207331274 0.0208212305 391 1305031242.5485460758 0.0929999352 0.0786312568 0.1293819398 0.0251173491 0.0045120000 16806957 955859216 1373700096 -0.0517788380 -0.0210620631 0.0168742016 392 1305031242.5748429298 0.0942571536 0.0786711188 0.1293819398 0.0252878039 0.0046300000 16809605 955859216 1373700096 -0.0546873957 -0.0208298769 0.0127582159 393 1305031242.6061151028 0.0962469503 0.0787158410 0.1293819398 0.0254004562 0.0046210000 16812533 955859216 1373700096 -0.0574473217 -0.0219903179 0.0087839141 394 1305031242.6438109875 0.0989293233 0.0787671443 0.1293819398 0.0256602321 0.0046000000 16815573 955859216 1373700096 -0.0609521158 -0.0233227331 0.0049132118 395 1305031242.6752018929 0.1002335101 0.0788214895 0.1293819398 0.0259891487 0.0035340000 16818501 955859216 1373700096 -0.0646557733 -0.0234786570 0.0021252157 396 1305031242.7139821053 0.1023007035 0.0788807804 0.1293819398 0.0263958243 0.0035720000 16821653 955859216 1373700096 -0.0686381906 -0.0230042692 -0.0010348900 397 1305031242.7452580929 0.1050668210 0.0789467402 0.1293819398 0.0264936076 0.0036130000 16824525 955859216 1373700096 -0.0727026612 -0.0230018627 -0.0048951074 398 1305031242.7775399685 0.1075353026 0.0790185708 0.1293819398 0.0266690544 0.0035880000 16827453 955859216 1373700096 -0.0769090131 -0.0235144366 -0.0078702783 399 1305031242.8140709400 0.1096800119 0.0790954165 0.1293819398 0.0269047265 0.0037610000 16830493 955859216 1373700096 -0.0806404203 -0.0224733222 -0.0095069129 400 1305031242.8443179131 0.1119863912 0.0791776440 0.1293819398 0.0269584418 0.0036130000 16833365 955859216 1373700096 -0.0842401609 -0.0217860192 -0.0114291422 401 1305031242.8740880489 0.1150807142 0.0792671778 0.1293819398 0.0270129551 0.0037780000 16836293 955859216 1373700096 -0.0878838450 -0.0218182355 -0.0132244360 402 1305031242.9137070179 0.1195119470 0.0793672892 0.1293819398 0.0271190448 0.0036430000 16839501 955859216 1373700096 -0.0931328014 -0.0215086378 -0.0160499737 403 1305031242.9444379807 0.1208881214 0.0794703185 0.1293819398 0.0273014756 0.0048180000 16842373 955859216 1373700096 -0.0978264287 -0.0189124774 -0.0174156316 404 1305031242.9760620594 0.1219195649 0.0795753909 0.1293819398 0.0273665732 0.0047340000 16845245 955859216 1373700096 -0.1034396961 -0.0157130025 -0.0193827525 405 1305031243.0141661167 0.1242126971 0.0796856065 0.1293819398 0.0274310427 0.0046990000 16848341 955859216 1373700096 -0.1085607633 -0.0138465185 -0.0206788648 406 1305031243.0469100475 0.1254248321 0.0797982647 0.1293819398 0.0274355152 0.0046870000 16851437 955859216 1373700096 -0.1130432412 -0.0121387905 -0.0216094516 407 1305031243.0780448914 0.1263814420 0.0799127197 0.1293819398 0.0274284440 0.0048100000 16854365 955859216 1373700096 -0.1166596860 -0.0096658347 -0.0235284120 408 1305031243.1136150360 0.1260641366 0.0800258359 0.1293819398 0.0274372048 0.0047820000 16857349 955859216 1373700096 -0.1195957214 -0.0064653317 -0.0248406008 409 1305031243.1458160877 0.1258545071 0.0801378864 0.1293819398 0.0274056875 0.0047520000 16860333 955859216 1373700096 -0.1224192157 -0.0036738999 -0.0267896932 410 1305031243.1780760288 0.1247348413 0.0802466595 0.1293819398 0.0273993717 0.0047540000 16863261 955859216 1373700096 -0.1241329759 -0.0026847555 -0.0274517741 411 1305031243.2136580944 0.1238465607 0.0803527420 0.1293819398 0.0274371483 0.0022710000 16866301 955859216 1373700096 -0.1234090328 -0.0048224977 -0.0266249757 412 1305031243.2455608845 0.1256480813 0.0804626821 0.1293819398 0.0277478925 0.0048080000 16869229 955859216 1373700096 -0.1223591715 -0.0086728297 -0.0270138942 413 1305031243.2781798840 0.1267875880 0.0805748489 0.1293819398 0.0278576241 0.0048610000 16872213 955859216 1373700096 -0.1206629276 -0.0132236751 -0.0263784453 414 1305031243.3142709732 0.1274529696 0.0806880811 0.1293819398 0.0279390448 0.0048060000 16875197 955859216 1373700096 -0.1178661957 -0.0161210727 -0.0246375687 415 1305031243.3460359573 0.1278941333 0.0808018306 0.1293819398 0.0282997865 0.0047660000 16878181 955859216 1373700096 -0.1143063530 -0.0177317392 -0.0234430544 416 1305031243.3789350986 0.1276667118 0.0809144866 0.1293819398 0.0283572285 0.0048580000 16881165 955859216 1373700096 -0.1114778742 -0.0185407288 -0.0207680203 417 1305031243.4139740467 0.1182966754 0.0810041321 0.1293819398 0.0284406769 0.0052160000 16884149 955859216 1373700096 -0.0994588360 -0.0103473542 -0.0117569910 418 1305031243.4470911026 0.1205026880 0.0810986263 0.1293819398 0.0286906061 0.0048600000 16887133 955859216 1373700096 -0.0996017829 -0.0113488352 -0.0112604396 419 1305031243.4780371189 0.1189137101 0.0811888771 0.1293819398 0.0287311919 0.0050860000 16890005 955859216 1373700096 -0.0966639966 -0.0073192725 -0.0084085586 420 1305031243.5154008865 0.1174046174 0.0812751051 0.1293819398 0.0288680554 0.0052970000 16893101 955859216 1373700096 -0.0980642214 -0.0017304341 -0.0071792668 421 1305031243.5459430218 0.1186494231 0.0813638802 0.1293819398 0.0289519357 0.0048180000 16896029 955859216 1373700096 -0.1000990048 -0.0011045290 -0.0068761618 422 1305031243.5779840946 0.1148247868 0.0814431714 0.1293819398 0.0289619119 0.0039470000 16898845 955859216 1373700096 -0.0996934548 0.0050743851 -0.0047924351 423 1305031243.6140549183 0.1137035787 0.0815194371 0.1293819398 0.0292515673 0.0049010000 16901829 955859216 1373700096 -0.0998291820 0.0083683617 -0.0038626129 424 1305031243.6461870670 0.1163056642 0.0816014801 0.1293819398 0.0295926077 0.0048880000 16904813 955859216 1373700096 -0.1019494534 0.0051944912 -0.0055993646 425 1305031243.6782801151 0.1185645759 0.0816884521 0.1293819398 0.0296554163 0.0049010000 16907685 955859216 1373700096 -0.1031245887 0.0022975197 -0.0065867240 426 1305031243.7142961025 0.1095081642 0.0817537566 0.1293819398 0.0299971751 0.0051920000 16910613 955859216 1373700096 -0.0952885896 0.0110409223 -0.0012837088 427 1305031243.7473781109 0.1113224700 0.0818230042 0.1293819398 0.0303358749 0.0048250000 16913541 955859216 1373700096 -0.0954106003 0.0064855097 -0.0021193461 428 1305031243.7790360451 0.1125451550 0.0818947849 0.1293819398 0.0305631292 0.0050200000 16916357 955859216 1373700096 -0.0947574005 0.0022418497 -0.0019460100 429 1305031243.8141930103 0.1024519801 0.0819427038 0.1293819398 0.0310523244 0.0052330000 16919285 955859216 1373700096 -0.0811361969 0.0078342510 0.0061075129 430 1305031243.8462920189 0.1045238301 0.0819952180 0.1293819398 0.0314439883 0.0049450000 16922157 955859216 1373700096 -0.0755213723 0.0031417771 0.0061505251 431 1305031243.8788089752 0.0984427184 0.0820333793 0.1293819398 0.0315959885 0.0053420000 16925085 955859216 1373700096 -0.0638855696 0.0062689395 0.0136035215 432 1305031243.9140000343 0.0951286480 0.0820636924 0.1293819398 0.0319089572 0.0049430000 16927957 955859216 1373700096 -0.0609056093 0.0067060003 0.0151218735 433 1305031243.9470779896 0.0846787468 0.0820697318 0.1293819398 0.0320314098 0.0054280000 16930941 955859216 1373700096 -0.0489659645 0.0173983239 0.0250299126 434 1305031243.9816520214 0.0822526664 0.0820701533 0.1293819398 0.0321787894 0.0050470000 16933869 955859216 1373700096 -0.0488150269 0.0186647139 0.0251516569 435 1305031244.0112700462 0.0794924423 0.0820642275 0.1293819398 0.0322533901 0.0050700000 16936685 955859216 1373700096 -0.0481624752 0.0209257472 0.0259497240 436 1305031244.0438230038 0.0710725412 0.0820390172 0.1293819398 0.0322575748 0.0053080000 16939557 955859216 1373700096 -0.0493319854 0.0327570587 0.0289856158 437 1305031244.0818090439 0.0671050400 0.0820048434 0.1293819398 0.0322857490 0.0052230000 16942597 955859216 1373700096 -0.0482615493 0.0379419290 0.0322436057 438 1305031244.1127901077 0.0678542331 0.0819725360 0.1293819398 0.0323581454 0.0025440000 16945469 955859216 1373700096 -0.0474199615 0.0376635343 0.0330783054 439 1305031244.1484949589 0.0645105168 0.0819327592 0.1293819398 0.0323563371 0.0053370000 16948453 955859216 1373700096 -0.0515054092 0.0435428768 0.0338299610 440 1305031244.1824309826 0.0620122440 0.0818874853 0.1293819398 0.0324298930 0.0053660000 16951325 955859216 1373700096 -0.0525534227 0.0461529084 0.0360058770 441 1305031244.2124009132 0.0613068081 0.0818408171 0.1293819398 0.0325424728 0.0052880000 16954197 955859216 1373700096 -0.0523844212 0.0491540171 0.0372130126 442 1305031244.2473471165 0.0574832074 0.0817857094 0.1293819398 0.0327007728 0.0054620000 16957125 955859216 1373700096 -0.0524993613 0.0557876006 0.0392314643 443 1305031244.2831470966 0.0562385544 0.0817280409 0.1293819398 0.0328425681 0.0053400000 16960109 955859216 1373700096 -0.0507747009 0.0591198616 0.0402199477 444 1305031244.3137950897 0.0482712612 0.0816526878 0.1293819398 0.0329612358 0.0056030000 16962869 955859216 1373700096 -0.0445809960 0.0696263239 0.0460769124 445 1305031244.3459599018 0.0428605042 0.0815655143 0.1293819398 0.0331274677 0.0044370000 16965797 955859216 1373700096 -0.0343922563 0.0791548938 0.0532801934 446 1305031244.3808560371 0.0428037085 0.0814786045 0.1293819398 0.0332984877 0.0056300000 16968725 955859216 1373700096 -0.0264737550 0.0840721354 0.0566787571 447 1305031244.4130189419 0.0436511189 0.0813939792 0.1293819398 0.0335198107 0.0056580000 16971597 955859216 1373700096 -0.0178728383 0.0908472836 0.0611258447 448 1305031244.4451670647 0.0416769199 0.0813053251 0.1293819398 0.0335912497 0.0056160000 16974469 955859216 1373700096 -0.0163240023 0.1000313461 0.0622227862 449 1305031244.4806590080 0.0407119505 0.0812149167 0.1293819398 0.0336672714 0.0044440000 16977453 955859216 1373700096 -0.0189135373 0.1044398844 0.0592396818 450 1305031244.5142281055 0.0411539227 0.0811258922 0.1293819398 0.0337680301 0.0054490000 16980381 955859216 1373700096 -0.0204860400 0.1089438424 0.0581603982 451 1305031244.5462141037 0.0376391821 0.0810294694 0.1293819398 0.0337477541 0.0055850000 16983253 955859216 1373700096 -0.0229083560 0.1179677323 0.0605393685 452 1305031244.5808050632 0.0365773253 0.0809311239 0.1293819398 0.0337979492 0.0053630000 16986181 955859216 1373700096 -0.0259610843 0.1191701964 0.0605534092 453 1305031244.6132769585 0.0364477038 0.0808329265 0.1293819398 0.0338831414 0.0053410000 16989109 955859216 1373700096 -0.0277323071 0.1204317659 0.0610409603 454 1305031244.6428399086 0.0347860642 0.0807315017 0.1293819398 0.0338752461 0.0053070000 16991869 955859216 1373700096 -0.0295796543 0.1228310838 0.0622738190 455 1305031244.6806099415 0.0332654491 0.0806271807 0.1293819398 0.0339331588 0.0054150000 16994853 955859216 1373700096 -0.0295599084 0.1268014163 0.0656869859 456 1305031244.7152500153 0.0320612788 0.0805206765 0.1293819398 0.0339566802 0.0052510000 16997837 955859216 1373700096 -0.0331417881 0.1283251643 0.0657906458 457 1305031244.7458879948 0.0323807113 0.0804153375 0.1293819398 0.0341426919 0.0052830000 17000653 955859216 1373700096 -0.0352539308 0.1286970079 0.0654794350 458 1305031244.7818510532 0.0328945220 0.0803115802 0.1293819398 0.0342323105 0.0053000000 17003693 955859216 1373700096 -0.0353470854 0.1291394234 0.0651284829 459 1305031244.8140940666 0.0285949763 0.0801989079 0.1293819398 0.0350958489 0.0055690000 17006565 955859216 1373700096 -0.0297909789 0.1332858056 0.0697579980 460 1305031244.8418219090 0.0283876359 0.0800862747 0.1293819398 0.0350825771 0.0053030000 17009269 955859216 1373700096 -0.0290251896 0.1349943876 0.0691875964 461 1305031244.8818008900 0.0250228737 0.0799668313 0.1293819398 0.0350540176 0.0044110000 17012365 955859216 1373700096 -0.0281146057 0.1417799741 0.0703592971 462 1305031244.9149079323 0.0252351109 0.0798483644 0.1293819398 0.0350363881 0.0042650000 17015237 955859216 1373700096 -0.0284506623 0.1433092654 0.0693782941 463 1305031244.9458680153 0.0246875491 0.0797292265 0.1293819398 0.0350000895 0.0042300000 17018053 955859216 1373700096 -0.0277033579 0.1462171078 0.0696968436 464 1305031244.9818000793 0.0250158627 0.0796113098 0.1293819398 0.0350219716 0.0054830000 17021037 955859216 1373700096 -0.0269048102 0.1494823694 0.0710468367 465 1305031245.0140550137 0.0241128057 0.0794919582 0.1293819398 0.0349866295 0.0053980000 17023909 955859216 1373700096 -0.0245240219 0.1506364495 0.0732926875 466 1305031245.0464398861 0.0245090965 0.0793739692 0.1293819398 0.0349524458 0.0026090000 17026781 955859216 1373700096 -0.0251158178 0.1525206119 0.0736650825 467 1305031245.0817689896 0.0239621270 0.0792553143 0.1293819398 0.0349328097 0.0053720000 17029765 955859216 1373700096 -0.0235230625 0.1532302052 0.0768062100 468 1305031245.1143150330 0.0257385727 0.0791409623 0.1293819398 0.0349328776 0.0055760000 17032581 955859216 1373700096 -0.0224318951 0.1523866355 0.0780370682 469 1305031245.1457099915 0.0275473502 0.0790309546 0.1293819398 0.0349178325 0.0056190000 17035509 955859216 1373700096 -0.0231015366 0.1518174857 0.0789327696 470 1305031245.1818709373 0.0299342591 0.0789264935 0.1293819398 0.0349303416 0.0043360000 17038437 955859216 1373700096 -0.0213182531 0.1487300992 0.0807754397 471 1305031245.2140939236 0.0344138257 0.0788319868 0.1293819398 0.0350091525 0.0055880000 17041309 955859216 1373700096 -0.0200097784 0.1430693269 0.0804224238 472 1305031245.2487950325 0.0323979110 0.0787336095 0.1293819398 0.0353558380 0.0060110000 17044293 955859216 1373700096 -0.0326501541 0.1416986883 0.0718261823 473 1305031245.2807950974 0.0349434875 0.0786410300 0.1293819398 0.0354389723 0.0044290000 17047109 955859216 1373700096 -0.0317541473 0.1360500604 0.0710689202 474 1305031245.3143179417 0.0374572724 0.0785541444 0.1293819398 0.0355850815 0.0044320000 17049981 955859216 1373700096 -0.0298133083 0.1296735257 0.0707453862 475 1305031245.3491809368 0.0367730670 0.0784661843 0.1293819398 0.0358357831 0.0060700000 17053021 955859216 1373700096 -0.0361782163 0.1238866895 0.0633030757 476 1305031245.3806860447 0.0391976871 0.0783836874 0.1293819398 0.0360495109 0.0060050000 17055781 955859216 1373700096 -0.0375537090 0.1158379689 0.0570339561 477 1305031245.4133110046 0.0415315479 0.0783064293 0.1293819398 0.0362115822 0.0057710000 17058653 955859216 1373700096 -0.0416289270 0.1092645004 0.0494373441 478 1305031245.4489970207 0.0473089255 0.0782415809 0.1293819398 0.0362034435 0.0060570000 17061581 955859216 1373700096 -0.0404030643 0.0982708856 0.0420125797 479 1305031245.4846711159 0.0487112142 0.0781799309 0.1293819398 0.0364467160 0.0058490000 17064565 955859216 1373700096 -0.0383377038 0.0951819792 0.0401086695 480 1305031245.5124320984 0.0510084592 0.0781233237 0.1293819398 0.0365318541 0.0047520000 17067325 955859216 1373700096 -0.0447408967 0.0897491425 0.0317737833 481 1305031245.5481460094 0.0522876382 0.0780696112 0.1293819398 0.0366943937 0.0045500000 17070253 955859216 1373700096 -0.0462932810 0.0861082152 0.0283497013 482 1305031245.5786890984 0.0552075654 0.0780221796 0.1293819398 0.0367099703 0.0047640000 17073125 955859216 1373700096 -0.0513430014 0.0802939385 0.0214068629 483 1305031245.6104750633 0.0587647744 0.0779823092 0.1293819398 0.0367891487 0.0060490000 17075941 955859216 1373700096 -0.0536762998 0.0749888569 0.0160003509 484 1305031245.6494629383 0.0591904372 0.0779434830 0.1293819398 0.0369779410 0.0059630000 17078981 955859216 1373700096 -0.0583400168 0.0725286081 0.0125335781 485 1305031245.6802349091 0.0601531714 0.0779068019 0.1293819398 0.0370037108 0.0057290000 17081853 955859216 1373700096 -0.0601965226 0.0700827762 0.0112435082 486 1305031245.7110319138 0.0628250018 0.0778757694 0.1293819398 0.0370109419 0.0046750000 17084725 955859216 1373700096 -0.0633225888 0.0656185374 0.0077102692 487 1305031245.7497749329 0.0628601983 0.0778449366 0.1293819398 0.0370939253 0.0057570000 17087765 955859216 1373700096 -0.0624145903 0.0653742030 0.0081112692 488 1305031245.7818500996 0.0640864894 0.0778167431 0.1293819398 0.0371457384 0.0056540000 17090693 955859216 1373700096 -0.0607058853 0.0649796948 0.0076885079 489 1305031245.8135690689 0.0653941706 0.0777913391 0.1293819398 0.0372587888 0.0055960000 17093509 955859216 1373700096 -0.0598818175 0.0647085533 0.0073914817 490 1305031245.8491089344 0.0676530302 0.0777706486 0.1293819398 0.0372923978 0.0043560000 17096493 955859216 1373700096 -0.0585306510 0.0622566082 0.0064726067 491 1305031245.8820281029 0.0696339831 0.0777540770 0.1293819398 0.0373200315 0.0055690000 17099421 955859216 1373700096 -0.0575257614 0.0592928082 0.0057591074 492 1305031245.9126079082 0.0724504590 0.0777432973 0.1293819398 0.0373322845 0.0055630000 17102237 955859216 1373700096 -0.0560484640 0.0559441000 0.0047621834 493 1305031245.9458959103 0.0746227577 0.0777369676 0.1293819398 0.0373870806 0.0055300000 17105109 955859216 1373700096 -0.0560132302 0.0521101542 0.0035542909 494 1305031245.9808180332 0.0763265491 0.0777341125 0.1293819398 0.0374220861 0.0042360000 17108093 955859216 1373700096 -0.0572092347 0.0493328609 0.0014851099 495 1305031246.0110030174 0.0792834312 0.0777372425 0.1293819398 0.0374387294 0.0042040000 17110909 955859216 1373700096 -0.0581560545 0.0453815497 -0.0016226702 496 1305031246.0483930111 0.0837383866 0.0777493415 0.1293819398 0.0375117398 0.0056740000 17114005 955859216 1373700096 -0.0638571084 0.0386138037 -0.0076547675 497 1305031246.0805249214 0.0860053897 0.0777659533 0.1293819398 0.0375867125 0.0054580000 17116765 955859216 1373700096 -0.0641360283 0.0360878520 -0.0095225889 498 1305031246.1123559475 0.0883939564 0.0777872947 0.1293819398 0.0376918544 0.0054390000 17119693 955859216 1373700096 -0.0650617853 0.0332110412 -0.0116015123 499 1305031246.1484489441 0.0909305513 0.0778136339 0.1293819398 0.0378083406 0.0055000000 17122621 955859216 1373700096 -0.0661118701 0.0304594617 -0.0140131610 500 1305031246.1805961132 0.0929642394 0.0778439351 0.1293819398 0.0378677392 0.0054220000 17125437 955859216 1373700096 -0.0687257275 0.0283991434 -0.0169838034 501 1305031246.2111370564 0.0991094634 0.0778863812 0.1293819398 0.0379508891 0.0059110000 17128309 955859216 1373700096 -0.0786295533 0.0202454533 -0.0249084048 502 1305031246.2469689846 0.1006311402 0.0779316895 0.1293819398 0.0380906739 0.0054620000 17131293 955859216 1373700096 -0.0801240951 0.0190169010 -0.0266712811 503 1305031246.2796959877 0.1064385474 0.0779883632 0.1293819398 0.0381545835 0.0044300000 17134165 955859216 1373700096 -0.0868220106 0.0128694195 -0.0329639167 504 1305031246.3124730587 0.1073696837 0.0780466595 0.1293819398 0.0382915643 0.0042290000 17137093 955859216 1373700096 -0.0880996734 0.0139638130 -0.0343890563 505 1305031246.3482720852 0.1132243574 0.0781163183 0.1293819398 0.0384066856 0.0057600000 17140077 955859216 1373700096 -0.0951298550 0.0087674912 -0.0398167856 506 1305031246.3782060146 0.1135714278 0.0781863877 0.1293819398 0.0385685452 0.0055220000 17142893 955859216 1373700096 -0.0976308063 0.0109681459 -0.0408783332 507 1305031246.4156370163 0.1146810949 0.0782583693 0.1293819398 0.0387370236 0.0047970000 17145989 955859216 1373700096 -0.1010062397 0.0129377972 -0.0415624082 508 1305031246.4452888966 0.1174660549 0.0783355498 0.1293819398 0.0388286542 0.0058920000 17148805 955859216 1373700096 -0.1054778695 0.0120311026 -0.0435032286 509 1305031246.4774649143 0.1194157600 0.0784162575 0.1293819398 0.0389281083 0.0057870000 17151789 955859216 1373700096 -0.1102348715 0.0128870131 -0.0454357117 510 1305031246.5163950920 0.1205455065 0.0784988639 0.1293819398 0.0390659672 0.0056470000 17154885 955859216 1373700096 -0.1133601665 0.0158956405 -0.0460630991 511 1305031246.5491750240 0.1204435155 0.0785809473 0.1293819398 0.0392000352 0.0042900000 17157869 955859216 1373700096 -0.1162941083 0.0191238355 -0.0461022332 512 1305031246.5795109272 0.1196551919 0.0786611705 0.1293819398 0.0393002912 0.0042700000 17160741 955859216 1373700096 -0.1183162928 0.0229934603 -0.0455824286 513 1305031246.6164529324 0.1253907382 0.0787522612 0.1293819398 0.0393630770 0.0047390000 17212989 955859216 1373700096 -0.1268643886 0.0213107988 -0.0502868854 514 1305031246.6477630138 0.1249227151 0.0788420870 0.1293819398 0.0394262932 0.0056850000 17318317 955859216 1373700096 -0.1277498901 0.0260836799 -0.0503040142 515 1305031246.6807579994 0.1236530617 0.0789290986 0.1293819398 0.0395218815 0.0056870000 17321301 955859216 1373700096 -0.1288469881 0.0297412630 -0.0495097935 516 1305031246.7169740200 0.1240009815 0.0790164472 0.1293819398 0.0396662244 0.0058250000 17324397 955859216 1373700096 -0.1298492998 0.0328324661 -0.0500550680 517 1305031246.7491660118 0.1234314367 0.0791023563 0.1293819398 0.0397570846 0.0057120000 17327325 955859216 1373700096 -0.1310886294 0.0368555859 -0.0508491881 518 1305031246.7808170319 0.1234664619 0.0791880013 0.1293819398 0.0398248941 0.0044240000 17330309 955859216 1373700096 -0.1332858354 0.0394103490 -0.0517387241 519 1305031246.8168079853 0.1258091331 0.0792778301 0.1293819398 0.0398923853 0.0056780000 17333405 955859216 1373700096 -0.1357891560 0.0424770042 -0.0551889576 520 1305031246.8488121033 0.1257905662 0.0793672776 0.1293819398 0.0399203552 0.0058020000 17336389 955859216 1373700096 -0.1383057982 0.0450317301 -0.0567201488 521 1305031246.8806428909 0.1250713170 0.0794550013 0.1293819398 0.0399961489 0.0044100000 17339373 955859216 1373700096 -0.1403560191 0.0479762703 -0.0579711236 522 1305031246.9166710377 0.1312147081 0.0795541579 0.1312147081 0.0400508268 0.0059490000 17342469 955859216 1373700096 -0.1503681540 0.0453525856 -0.0655962229 523 1305031246.9495339394 0.1319553852 0.0796543514 0.1319553852 0.0400548900 0.0043370000 17345453 955859216 1373700096 -0.1498797089 0.0489020757 -0.0682783648 524 1305031246.9775969982 0.1364237964 0.0797626900 0.1364237964 0.0400352727 0.0038360000 17348269 955859216 1373700096 -0.1550624669 0.0475741215 -0.0732090920 525 1305031247.0167899132 0.1332731545 0.0798646147 0.1364237964 0.0401274576 0.0057680000 17351421 955859216 1373700096 -0.1544697136 0.0516446456 -0.0733557492 526 1305031247.0479340553 0.1397212744 0.0799784107 0.1397212744 0.0400990971 0.0059900000 17354405 955859216 1373700096 -0.1638371795 0.0487839729 -0.0808848292 527 1305031247.0778899193 0.1339676231 0.0800808570 0.1397212744 0.0400917846 0.0055800000 17357333 955859216 1373700096 -0.1612025648 0.0542486161 -0.0801462159 528 1305031247.1162130833 0.1297433972 0.0801749148 0.1397212744 0.0400652813 0.0056300000 17360485 955859216 1373700096 -0.1597391665 0.0589573123 -0.0809785575 529 1305031247.1473660469 0.1362759769 0.0802809660 0.1397212744 0.0400485533 0.0059410000 17363469 955859216 1373700096 -0.1676596403 0.0562319010 -0.0879843161 530 1305031247.1796920300 0.1344570220 0.0803831850 0.1397212744 0.0400130461 0.0042100000 17366453 955859216 1373700096 -0.1654165983 0.0562825985 -0.0877336711 531 1305031247.2169430256 0.1324544549 0.0804812476 0.1397212744 0.0399858832 0.0056120000 17369605 955859216 1373700096 -0.1638190001 0.0559379682 -0.0872421488 532 1305031247.2487928867 0.1302845180 0.0805748628 0.1397212744 0.0399625401 0.0055970000 17372533 955859216 1373700096 -0.1624015272 0.0554467887 -0.0859662443 533 1305031247.2794220448 0.1322022527 0.0806717247 0.1397212744 0.0399431211 0.0041990000 17375461 955859216 1373700096 -0.1623463184 0.0530756339 -0.0873571411 534 1305031247.3166429996 0.1353949606 0.0807742026 0.1397212744 0.0399551710 0.0042440000 17378613 955859216 1373700096 -0.1623909473 0.0475825779 -0.0878768861 535 1305031247.3477900028 0.1384918690 0.0808820861 0.1397212744 0.0400264721 0.0056090000 17381597 955859216 1373700096 -0.1628037393 0.0443814658 -0.0878509805 536 1305031247.3786110878 0.1399672329 0.0809923196 0.1399672329 0.0400448946 0.0056800000 17384525 955859216 1373700096 -0.1630685776 0.0413347222 -0.0875709876 537 1305031247.4168620110 0.1371136904 0.0810968287 0.1399672329 0.0400807349 0.0062840000 17387733 955859216 1373700096 -0.1569042206 0.0427163988 -0.0831727162 538 1305031247.4487700462 0.1372397244 0.0812011835 0.1399672329 0.0402152535 0.0049660000 17390717 955859216 1373700096 -0.1551670283 0.0430820920 -0.0812500790 539 1305031247.4802629948 0.1351886541 0.0813013458 0.1399672329 0.0402805289 0.0037700000 17393589 955859216 1373700096 -0.1532903016 0.0447741225 -0.0775986761 540 1305031247.5178461075 0.1359842718 0.0814026105 0.1399672329 0.0403689684 0.0058870000 17396797 955859216 1373700096 -0.1505033523 0.0446912609 -0.0748688132 541 1305031247.5459010601 0.1349946707 0.0815016716 0.1399672329 0.0404615713 0.0058460000 17399613 955859216 1373700096 -0.1477285624 0.0448728167 -0.0719918534 542 1305031247.5779209137 0.1340170801 0.0815985635 0.1399672329 0.0405334514 0.0056880000 17402541 955859216 1373700096 -0.1448328346 0.0454667024 -0.0696870238 543 1305031247.6152799129 0.1336230785 0.0816943729 0.1399672329 0.0406822804 0.0046060000 17405581 955859216 1373700096 -0.1413189471 0.0457512103 -0.0675389096 544 1305031247.6484000683 0.1359615922 0.0817941288 0.1399672329 0.0408220579 0.0036450000 17408565 955859216 1373700096 -0.1426796615 0.0422413051 -0.0681930780 545 1305031247.6835579872 0.1306148022 0.0818837080 0.1399672329 0.0409661164 0.0039850000 17411549 955859216 1373700096 -0.1340795010 0.0446683168 -0.0625886247 546 1305031247.7159609795 0.1271620691 0.0819666354 0.1399672329 0.0411530426 0.0061810000 17414477 955859216 1373700096 -0.1271078289 0.0463623852 -0.0581458472 547 1305031247.7469019890 0.1253187209 0.0820458897 0.1399672329 0.0414011139 0.0060920000 17417405 955859216 1373700096 -0.1234379038 0.0453740023 -0.0560092591 548 1305031247.7822608948 0.1282284558 0.0821301645 0.1399672329 0.0415953264 0.0043980000 17420389 955859216 1373700096 -0.1247768253 0.0367981680 -0.0571776293 549 1305031247.8139829636 0.1305987835 0.0822184497 0.1399672329 0.0418877695 0.0044200000 17423149 955859216 1373700096 -0.1229726896 0.0310540721 -0.0592906512 550 1305031247.8484420776 0.1241210252 0.0822946362 0.1399672329 0.0420478572 0.0047890000 17426245 955859216 1373700096 -0.1072679535 0.0364435092 -0.0519529767 551 1305031247.8820719719 0.1271684170 0.0823760769 0.1399672329 0.0421240685 0.0045760000 17429117 955859216 1373700096 -0.1091370434 0.0308993999 -0.0571932122 552 1305031247.9173319340 0.1226156726 0.0824489747 0.1399672329 0.0421052508 0.0047500000 17432101 955859216 1373700096 -0.1049615368 0.0378845967 -0.0589585975 553 1305031247.9496860504 0.1210375056 0.0825187550 0.1399672329 0.0421775367 0.0046050000 17434917 955859216 1373700096 -0.1018104851 0.0393824503 -0.0605874509 554 1305031247.9861450195 0.1226891652 0.0825912648 0.1399672329 0.0423494241 0.0046180000 17437957 955859216 1373700096 -0.0974522978 0.0342646651 -0.0638709962 555 1305031248.0181560516 0.1210212037 0.0826605079 0.1399672329 0.0423288989 0.0046220000 17440773 955859216 1373700096 -0.0945858061 0.0348663107 -0.0658475384 556 1305031248.0499138832 0.1161370277 0.0827207175 0.1399672329 0.0423516392 0.0063950000 17443645 955859216 1373700096 -0.0841794536 0.0407921933 -0.0620724224 557 1305031248.0857460499 0.1152715161 0.0827791570 0.1399672329 0.0425585220 0.0060870000 17446573 955859216 1373700096 -0.0801737905 0.0373741053 -0.0652539656 558 1305031248.1175789833 0.1137432158 0.0828346481 0.1399672329 0.0425846992 0.0048810000 17449445 955859216 1373700096 -0.0656732321 0.0407645255 -0.0602323487 559 1305031248.1493461132 0.1104425788 0.0828840362 0.1399672329 0.0425952157 0.0061090000 17452317 955859216 1373700096 -0.0647801235 0.0419850573 -0.0626709014 560 1305031248.1848630905 0.1067122072 0.0829265865 0.1399672329 0.0427751645 0.0048030000 17455245 955859216 1373700096 -0.0680258572 0.0400920846 -0.0665600374 561 1305031248.2167689800 0.1047400907 0.0829654698 0.1399672329 0.0428031428 0.0047640000 17458117 955859216 1373700096 -0.0652140826 0.0420752056 -0.0679976046 562 1305031248.2488510609 0.1030142009 0.0830011437 0.1399672329 0.0428323030 0.0062520000 17460933 955859216 1373700096 -0.0656396747 0.0408496484 -0.0694628134 563 1305031248.2847399712 0.0968546793 0.0830257503 0.1399672329 0.0428941778 0.0063930000 17463973 955859216 1373700096 -0.0579864271 0.0504327007 -0.0642188117 564 1305031248.3161809444 0.0934477672 0.0830442290 0.1399672329 0.0429453204 0.0049510000 17466845 955859216 1373700096 -0.0520783998 0.0584670864 -0.0605033562 565 1305031248.3488430977 0.0960987434 0.0830673344 0.1399672329 0.0430098805 0.0061780000 17469661 955859216 1373700096 -0.0484361537 0.0549452491 -0.0618339442 566 1305031248.3881969452 0.0956747979 0.0830896091 0.1399672329 0.0430161716 0.0052660000 17472757 955859216 1373700096 -0.0454663336 0.0567690842 -0.0614153557 567 1305031248.4155070782 0.0952685103 0.0831110886 0.1399672329 0.0430465638 0.0042060000 17475517 955859216 1373700096 -0.0429536216 0.0595579632 -0.0610907041 568 1305031248.4482519627 0.0958404317 0.0831334994 0.1399672329 0.0430607162 0.0062590000 17478389 955859216 1373700096 -0.0407018661 0.0610179007 -0.0620251372 569 1305031248.4852969646 0.0969018713 0.0831576969 0.1399672329 0.0431006365 0.0063000000 17481373 955859216 1373700096 -0.0378628112 0.0629186854 -0.0631413087 570 1305031248.5154309273 0.0922794342 0.0831737000 0.1399672329 0.0430705796 0.0065720000 17484245 955859216 1373700096 -0.0388507023 0.0741799101 -0.0613305382 571 1305031248.5470030308 0.0922902003 0.0831896658 0.1399672329 0.0431108915 0.0063820000 17487117 955859216 1373700096 -0.0373287573 0.0773959085 -0.0621690564 572 1305031248.5860579014 0.0929834768 0.0832067878 0.1399672329 0.0431492058 0.0065790000 17490157 955859216 1373700096 -0.0304820202 0.0839031041 -0.0595294498 573 1305031248.6180379391 0.0937230438 0.0832251408 0.1399672329 0.0432063550 0.0063270000 17492973 955859216 1373700096 -0.0310725849 0.0849519223 -0.0622837357 574 1305031248.6494390965 0.0946603045 0.0832450627 0.1399672329 0.0431988029 0.0042000000 17495845 955859216 1373700096 -0.0289862268 0.0882927626 -0.0630373061 575 1305031248.6860280037 0.0938000977 0.0832634193 0.1399672329 0.0432282013 0.0065880000 17498885 955859216 1373700096 -0.0234939475 0.1002893895 -0.0566611812 576 1305031248.7199230194 0.0944846496 0.0832829006 0.1399672329 0.0432250343 0.0065710000 17501757 955859216 1373700096 -0.0188093334 0.1092213765 -0.0524866134 577 1305031248.7498369217 0.0979011953 0.0833082356 0.1399672329 0.0432761525 0.0060140000 17504573 955859216 1373700096 -0.0109334802 0.1164212301 -0.0464090630 578 1305031248.7856750488 0.1038710922 0.0833438115 0.1399672329 0.0433078221 0.0043400000 17507557 955859216 1373700096 0.0006411816 0.1235742792 -0.0383414328 579 1305031248.8181409836 0.0998496786 0.0833723190 0.1399672329 0.0432882728 0.0066030000 17510429 955859216 1373700096 -0.0011022601 0.1305652112 -0.0383606739 580 1305031248.8496789932 0.1012529358 0.0834031477 0.1399672329 0.0433192195 0.0031500000 17513301 955859216 1373700096 0.0051125246 0.1348936707 -0.0344786979 581 1305031248.8855929375 0.0960600823 0.0834249324 0.1399672329 0.0433529806 0.0064430000 17516285 955859216 1373700096 0.0050916565 0.1340110153 -0.0382328257 582 1305031248.9178819656 0.0910361484 0.0834380101 0.1399672329 0.0433390907 0.0063790000 17519157 955859216 1373700096 0.0038719720 0.1344653964 -0.0398248471 583 1305031248.9526810646 0.0861193314 0.0834426093 0.1399672329 0.0433589136 0.0046270000 17522141 955859216 1373700096 0.0028208902 0.1370305270 -0.0413258187 584 1305031248.9845540524 0.0782699659 0.0834337520 0.1399672329 0.0433426925 0.0066580000 17525013 955859216 1373700096 -0.0022404764 0.1482065320 -0.0389736369 585 1305031249.0169510841 0.0744094104 0.0834183258 0.1399672329 0.0433456419 0.0048560000 17527885 955859216 1373700096 -0.0036740680 0.1479290277 -0.0389142707 586 1305031249.0523660183 0.0707253218 0.0833966654 0.1399672329 0.0433250311 0.0041420000 17530869 955859216 1373700096 -0.0048868936 0.1489616185 -0.0367934294 587 1305031249.0845029354 0.0694216490 0.0833728578 0.1399672329 0.0432996709 0.0065240000 17533741 955859216 1373700096 -0.0045993510 0.1547304839 -0.0308806561 588 1305031249.1168839931 0.0667323917 0.0833445577 0.1399672329 0.0432661068 0.0070540000 17536613 955859216 1373700096 -0.0064691491 0.1531523317 -0.0291576851 589 1305031249.1534469128 0.0640640259 0.0833118234 0.1399672329 0.0432441723 0.0048580000 17539597 955859216 1373700096 -0.0123672187 0.1594462693 -0.0246345364 590 1305031249.1847391129 0.0627067462 0.0832768995 0.1399672329 0.0432203440 0.0064260000 17542469 955859216 1373700096 -0.0124392323 0.1578391790 -0.0210407674 591 1305031249.2168650627 0.0624228790 0.0832416135 0.1399672329 0.0431894224 0.0049290000 17545341 955859216 1373700096 -0.0117896209 0.1562151611 -0.0183646679 592 1305031249.2532238960 0.0627265498 0.0832069597 0.1399672329 0.0431646630 0.0064180000 17548325 955859216 1373700096 -0.0109615615 0.1564816982 -0.0139990347 593 1305031249.2848041058 0.0665979832 0.0831789513 0.1399672329 0.0431413741 0.0050620000 17551141 955859216 1373700096 -0.0048630778 0.1573250741 -0.0087346295 594 1305031249.3174340725 0.0659757853 0.0831499898 0.1399672329 0.0431158193 0.0042500000 17554069 955859216 1373700096 -0.0055247378 0.1572602540 -0.0062806541 595 1305031249.3527359962 0.0652010143 0.0831198234 0.1399672329 0.0430830182 0.0064440000 17556997 955859216 1373700096 -0.0062800325 0.1575447470 -0.0034386995 596 1305031249.3847539425 0.0669625700 0.0830927139 0.1399672329 0.0430602492 0.0065160000 17559869 955859216 1373700096 -0.0051084883 0.1547287256 -0.0038542107 597 1305031249.4178340435 0.0689959824 0.0830691013 0.1399672329 0.0430889593 0.0066180000 17562741 955859216 1373700096 -0.0036225868 0.1527508348 -0.0037990110 598 1305031249.4537220001 0.0707662329 0.0830485280 0.1399672329 0.0431172164 0.0066220000 17565725 955859216 1373700096 -0.0042046527 0.1494898200 -0.0045973798 599 1305031249.4859149456 0.0715250671 0.0830292901 0.1399672329 0.0431495257 0.0065070000 17568597 955859216 1373700096 -0.0045560142 0.1447179168 -0.0065737572 600 1305031249.5177340508 0.0709333271 0.0830091302 0.1399672329 0.0431551637 0.0068540000 17571469 955859216 1373700096 -0.0078372676 0.1368153244 -0.0138052097 601 1305031249.5543251038 0.0739463344 0.0829940507 0.1399672329 0.0432471670 0.0047980000 17574453 955859216 1373700096 -0.0063338093 0.1275978684 -0.0186973419 602 1305031249.5859050751 0.0752721876 0.0829812236 0.1399672329 0.0433518456 0.0066040000 17577269 955859216 1373700096 -0.0068795481 0.1236227304 -0.0206742659 603 1305031249.6180789471 0.0731211454 0.0829648719 0.1399672329 0.0433781210 0.0066150000 17580141 955859216 1373700096 -0.0137818269 0.1132386178 -0.0286712553 604 1305031249.6542129517 0.0753892064 0.0829523294 0.1399672329 0.0436008990 0.0046050000 17583069 955859216 1373700096 -0.0124209300 0.1105777994 -0.0289725177 605 1305031249.6856739521 0.0703049004 0.0829314246 0.1399672329 0.0437150969 0.0069350000 17585941 955859216 1373700096 -0.0250811819 0.1088056788 -0.0355590507 606 1305031249.7177898884 0.0673655197 0.0829057383 0.1399672329 0.0437873490 0.0053870000 17588813 955859216 1373700096 -0.0315509327 0.1017693207 -0.0386704467 607 1305031249.7539620399 0.0699768662 0.0828844387 0.1399672329 0.0438619582 0.0043740000 17591741 955859216 1373700096 -0.0321533196 0.0999266058 -0.0401436910 608 1305031249.7854170799 0.0682450309 0.0828603607 0.1399672329 0.0439193201 0.0069050000 17594557 955859216 1373700096 -0.0463331752 0.0968810618 -0.0476987697 609 1305031249.8186020851 0.0707789734 0.0828405226 0.1399672329 0.0439304863 0.0068440000 17597541 955859216 1373700096 -0.0502369180 0.0910357311 -0.0510783829 610 1305031249.8537468910 0.0725019053 0.0828235741 0.1399672329 0.0440545736 0.0050520000 17600413 955859216 1373700096 -0.0503452606 0.0908790678 -0.0517832674 611 1305031249.8855249882 0.0737423375 0.0828087112 0.1399672329 0.0440730270 0.0067000000 17603285 955859216 1373700096 -0.0578489453 0.0874767974 -0.0554825664 612 1305031249.9170649052 0.0762547851 0.0827980021 0.1399672329 0.0440778826 0.0048640000 17606213 955859216 1373700096 -0.0630292818 0.0808203742 -0.0590909123 613 1305031249.9533979893 0.0797866881 0.0827930897 0.1399672329 0.0440754802 0.0052370000 17609141 955859216 1373700096 -0.0670390576 0.0729773492 -0.0626255199 614 1305031249.9851789474 0.0815799981 0.0827911140 0.1399672329 0.0440721538 0.0064540000 17612013 955859216 1373700096 -0.0684824586 0.0706157163 -0.0634789467 615 1305031250.0164399147 0.0847739354 0.0827943381 0.1399672329 0.0440563027 0.0065080000 17614885 955859216 1373700096 -0.0729629174 0.0653467998 -0.0663188249 616 1305031250.0531940460 0.0879504085 0.0828027083 0.1399672329 0.0441240092 0.0065160000 17617869 955859216 1373700096 -0.0752582029 0.0598665625 -0.0677319914 617 1305031250.0845069885 0.0901670307 0.0828146440 0.1399672329 0.0441919756 0.0049000000 17620685 955859216 1373700096 -0.0800896361 0.0575825125 -0.0687850490 618 1305031250.1208500862 0.0918727443 0.0828293011 0.1399672329 0.0442755714 0.0040840000 17623725 955859216 1373700096 -0.0831177235 0.0573139191 -0.0682023764 619 1305031250.1532480717 0.0939459279 0.0828472602 0.1399672329 0.0445289330 0.0041510000 17626541 955859216 1373700096 -0.0890206471 0.0569844283 -0.0668190718 620 1305031250.1853280067 0.0959227160 0.0828683496 0.1399672329 0.0445373290 0.0042950000 17629357 955859216 1373700096 -0.0911610499 0.0525087714 -0.0657209903 621 1305031250.2214460373 0.0991991758 0.0828946472 0.1399672329 0.0445397517 0.0065680000 17632397 955859216 1373700096 -0.0942948386 0.0465040579 -0.0658569932 622 1305031250.2537350655 0.1009279042 0.0829236396 0.1399672329 0.0446347790 0.0065650000 17635269 955859216 1373700096 -0.0959533751 0.0422344394 -0.0634640679 623 1305031250.2852239609 0.1043335199 0.0829580054 0.1399672329 0.0446453795 0.0066370000 17638085 955859216 1373700096 -0.1001929194 0.0345383994 -0.0632862076 624 1305031250.3208620548 0.1060284525 0.0829949773 0.1399672329 0.0446779952 0.0047750000 17641013 955859216 1373700096 -0.1024070829 0.0335608795 -0.0624652952 625 1305031250.3517000675 0.1078245565 0.0830347046 0.1399672329 0.0446937390 0.0067360000 17643829 955859216 1373700096 -0.1051285192 0.0318278000 -0.0621302053 626 1305031250.3851490021 0.1125051156 0.0830817819 0.1399672329 0.0447066743 0.0051300000 17646701 955859216 1373700096 -0.1096749529 0.0293495208 -0.0633873716 627 1305031250.4215359688 0.1182231382 0.0831378287 0.1399672329 0.0447130962 0.0067500000 17649741 955859216 1373700096 -0.1175101697 0.0247557107 -0.0661274418 628 1305031250.4540181160 0.1181132942 0.0831935221 0.1399672329 0.0448000095 0.0064780000 17652725 955859216 1373700096 -0.1200664192 0.0281105842 -0.0637142137 629 1305031250.4856131077 0.1177670881 0.0832484881 0.1399672329 0.0448022373 0.0048610000 17655541 955859216 1373700096 -0.1227954328 0.0300715193 -0.0611715987 630 1305031250.5215380192 0.1234559268 0.0833123094 0.1399672329 0.0447794609 0.0067250000 17658581 955859216 1373700096 -0.1312647611 0.0257959031 -0.0631345361 631 1305031250.5536580086 0.1251788437 0.0833786589 0.1399672329 0.0447675326 0.0051590000 17661565 955859216 1373700096 -0.1343928725 0.0272361320 -0.0615202859 632 1305031250.5853788853 0.1250289828 0.0834445613 0.1399672329 0.0447567719 0.0065180000 17664437 955859216 1373700096 -0.1372919381 0.0284859277 -0.0593632758 633 1305031250.6213030815 0.1261570752 0.0835120376 0.1399672329 0.0447386749 0.0049310000 17667477 955859216 1373700096 -0.1406747550 0.0298476703 -0.0582624115 634 1305031250.6535439491 0.1292708516 0.0835842124 0.1399672329 0.0447588227 0.0042590000 17670517 955859216 1373700096 -0.1446722597 0.0305214077 -0.0580162592 635 1305031250.6852970123 0.1288779527 0.0836555411 0.1399672329 0.0447825650 0.0042330000 17673389 955859216 1373700096 -0.1471289843 0.0328832306 -0.0553598925 636 1305031250.7216401100 0.1285008937 0.0837260527 0.1399672329 0.0447607524 0.0066170000 17676429 955859216 1373700096 -0.1497978121 0.0355463848 -0.0532850362 637 1305031250.7534279823 0.1361407191 0.0838083363 0.1399672329 0.0447309851 0.0066330000 17679357 955859216 1373700096 -0.1592706293 0.0320854709 -0.0558123887 638 1305031250.7853651047 0.1349822432 0.0838885462 0.1399672329 0.0447060508 0.0050310000 17682285 955859216 1373700096 -0.1595320553 0.0344871879 -0.0535570309 639 1305031250.8217930794 0.1332230568 0.0839657520 0.1399672329 0.0446744033 0.0049470000 17685437 955859216 1373700096 -0.1597152352 0.0360852070 -0.0512002930 640 1305031250.8538279533 0.1322586834 0.0840412097 0.1399672329 0.0446427294 0.0065810000 17688421 955859216 1373700096 -0.1596055180 0.0368118845 -0.0502018109 641 1305031250.8820140362 0.1314734071 0.0841152069 0.1399672329 0.0446092815 0.0046410000 17691237 955859216 1373700096 -0.1583067030 0.0371230319 -0.0493487082 642 1305031250.9217998981 0.1311173290 0.0841884189 0.1399672329 0.0445775358 0.0065530000 17694389 955859216 1373700096 -0.1575486809 0.0378057063 -0.0497282557 643 1305031250.9535419941 0.1312648803 0.0842616327 0.1399672329 0.0445562920 0.0049600000 17697373 955859216 1373700096 -0.1582992375 0.0379461758 -0.0513588190 644 1305031250.9853079319 0.1312665343 0.0843346217 0.1399672329 0.0445256810 0.0049730000 17700245 955859216 1373700096 -0.1583284736 0.0363229662 -0.0515507832 645 1305031251.0214879513 0.1314262450 0.0844076320 0.1399672329 0.0445040132 0.0065860000 17703285 955859216 1373700096 -0.1573920399 0.0355267785 -0.0526464805 646 1305031251.0534679890 0.1305133104 0.0844790030 0.1399672329 0.0445086230 0.0050500000 17706213 955859216 1373700096 -0.1564121991 0.0336344428 -0.0535441488 647 1305031251.0851860046 0.1301163137 0.0845495398 0.1399672329 0.0445080472 0.0050160000 17709141 955859216 1373700096 -0.1552571952 0.0304530170 -0.0547724329 648 1305031251.1214449406 0.1307964772 0.0846209085 0.1399672329 0.0445080014 0.0051250000 17712181 955859216 1373700096 -0.1532655209 0.0271055028 -0.0570921525 649 1305031251.1537809372 0.1312355995 0.0846927339 0.1399672329 0.0446081905 0.0066330000 17715165 955859216 1373700096 -0.1519781947 0.0229645800 -0.0605409518 650 1305031251.1851599216 0.1320778728 0.0847656341 0.1399672329 0.0446352085 0.0067320000 17718037 955859216 1373700096 -0.1501093805 0.0179214198 -0.0630519986 651 1305031251.2204658985 0.1319298595 0.0848380830 0.1399672329 0.0446535624 0.0050010000 17721021 955859216 1373700096 -0.1465985477 0.0139425378 -0.0653646290 652 1305031251.2524240017 0.1240511686 0.0848982258 0.1399672329 0.0446968895 0.0069860000 17723893 955859216 1373700096 -0.1326100826 0.0170029439 -0.0624247007 653 1305031251.2844820023 0.1261818707 0.0849614473 0.1399672329 0.0449059768 0.0044670000 17726821 955859216 1373700096 -0.1299513578 0.0111160204 -0.0664642602 654 1305031251.3190040588 0.1192263216 0.0850138401 0.1399672329 0.0449805569 0.0053880000 17729805 955859216 1373700096 -0.1148634553 0.0133972010 -0.0622129552 655 1305031251.3532440662 0.1205425709 0.0850680824 0.1399672329 0.0450814220 0.0066960000 17732677 955859216 1373700096 -0.1128078848 0.0081767049 -0.0650486499 656 1305031251.3870069981 0.1120747328 0.0851092511 0.1399672329 0.0451189206 0.0056250000 17735605 955859216 1373700096 -0.0994639844 0.0154435635 -0.0589789115 657 1305031251.4210500717 0.1153509691 0.0851552811 0.1399672329 0.0452129870 0.0042760000 17738533 955859216 1373700096 -0.0972658321 0.0090995412 -0.0621298477 658 1305031251.4496629238 0.1100550070 0.0851931226 0.1399672329 0.0452685947 0.0070600000 17741293 955859216 1373700096 -0.0851285309 0.0124544911 -0.0565095507 659 1305031251.4890139103 0.1091395244 0.0852294601 0.1399672329 0.0453699615 0.0067100000 17744333 955859216 1373700096 -0.0838389099 0.0102218194 -0.0573761389 660 1305031251.5207729340 0.1041749716 0.0852581654 0.1399672329 0.0454600775 0.0048590000 17747261 955859216 1373700096 -0.0745435283 0.0136450836 -0.0525548495 661 1305031251.5530450344 0.1038360149 0.0852862711 0.1399672329 0.0455767424 0.0043300000 17750133 955859216 1373700096 -0.0719798356 0.0111071188 -0.0531475469 662 1305031251.5887598991 0.0979328081 0.0853053746 0.1399672329 0.0455976818 0.0069620000 17753061 955859216 1373700096 -0.0648866892 0.0183324330 -0.0479022451 663 1305031251.6208739281 0.0977480635 0.0853241419 0.1399672329 0.0456512776 0.0057540000 17755989 955859216 1373700096 -0.0629639104 0.0165212471 -0.0479951501 664 1305031251.6528749466 0.0970574245 0.0853418125 0.1399672329 0.0457305974 0.0068310000 17758861 955859216 1373700096 -0.0585727841 0.0164470002 -0.0471532345 665 1305031251.6897680759 0.0919141024 0.0853516956 0.1399672329 0.0457541740 0.0046550000 17761845 955859216 1373700096 -0.0533721559 0.0237835106 -0.0419764705 666 1305031251.7204608917 0.0911003202 0.0853603272 0.1399672329 0.0458155619 0.0039240000 17764717 955859216 1373700096 -0.0496846437 0.0234055445 -0.0394858941 667 1305031251.7531440258 0.0918641463 0.0853700781 0.1399672329 0.0459027321 0.0069030000 17767589 955859216 1373700096 -0.0442163385 0.0219963398 -0.0381304212 668 1305031251.7892498970 0.0883761123 0.0853745781 0.1399672329 0.0459325461 0.0070710000 17770573 955859216 1373700096 -0.0405922569 0.0288173109 -0.0335529484 669 1305031251.8209791183 0.0880786702 0.0853786201 0.1399672329 0.0459697329 0.0046040000 17773445 955859216 1373700096 -0.0399504937 0.0275208876 -0.0326766670 670 1305031251.8537969589 0.0883859321 0.0853831086 0.1399672329 0.0460664643 0.0073620000 17776317 955859216 1373700096 -0.0303239413 0.0296448991 -0.0256039388 671 1305031251.8896539211 0.0882196873 0.0853873360 0.1399672329 0.0460546142 0.0050200000 17779245 955859216 1373700096 -0.0223341379 0.0364927948 -0.0184679851 672 1305031251.9219300747 0.0845368430 0.0853860704 0.1399672329 0.0460418370 0.0078000000 17782173 955859216 1373700096 -0.0195068233 0.0471213721 -0.0111643448 673 1305031251.9538369179 0.0825156271 0.0853818053 0.1399672329 0.0460516190 0.0055470000 17784989 955859216 1373700096 -0.0178201739 0.0540112406 -0.0060363808 674 1305031251.9898068905 0.0815627426 0.0853761390 0.1399672329 0.0460502781 0.0043150000 17787973 955859216 1373700096 -0.0175468531 0.0549265929 -0.0049297730 675 1305031252.0221600533 0.0805520713 0.0853689922 0.1399672329 0.0460818565 0.0044420000 17790901 955859216 1373700096 -0.0138689578 0.0610001720 0.0010371031 676 1305031252.0537619591 0.0760301277 0.0853551773 0.1399672329 0.0460957391 0.0045490000 17793773 955859216 1373700096 -0.0128366742 0.0702091977 0.0054228031 677 1305031252.0895619392 0.0727736279 0.0853365931 0.1399672329 0.0461485542 0.0045180000 17796701 955859216 1373700096 -0.0113543132 0.0802016854 0.0096320873 678 1305031252.1221520901 0.0690213814 0.0853125293 0.1399672329 0.0462010091 0.0072860000 17799629 955859216 1373700096 -0.0121600190 0.0848559961 0.0081799896 679 1305031252.1539709568 0.0635699630 0.0852805079 0.1399672329 0.0463101637 0.0075310000 17802389 955859216 1373700096 -0.0122118071 0.0988602191 0.0122900531 680 1305031252.1897890568 0.0546588153 0.0852354760 0.1399672329 0.0462955297 0.0058130000 17805373 955859216 1373700096 -0.0222081933 0.1134679690 0.0095503656 681 1305031252.2220859528 0.0502392240 0.0851840865 0.1399672329 0.0462797769 0.0059730000 17808301 955859216 1373700096 -0.0303067174 0.1249361113 0.0091040647 682 1305031252.2530639172 0.0483312830 0.0851300501 0.1399672329 0.0463771340 0.0049580000 17811173 955859216 1373700096 -0.0267621819 0.1268405914 0.0132893361 683 1305031252.2888779640 0.0464806333 0.0850734624 0.1399672329 0.0464336560 0.0046780000 17814045 955859216 1373700096 -0.0260255747 0.1257814914 0.0123166293 684 1305031252.3206090927 0.0457626544 0.0850159905 0.1399672329 0.0464102076 0.0046160000 17816917 955859216 1373700096 -0.0259782802 0.1280598044 0.0125624575 685 1305031252.3528549671 0.0468608364 0.0849602895 0.1399672329 0.0464072702 0.0048010000 17819733 955859216 1373700096 -0.0213663541 0.1336091608 0.0185392909 686 1305031252.3893189430 0.0464116968 0.0849040962 0.1399672329 0.0463927309 0.0046290000 17822717 955859216 1373700096 -0.0221655145 0.1326823235 0.0164845157 687 1305031252.4217019081 0.0464173071 0.0848480747 0.1399672329 0.0463797268 0.0045660000 17825645 955859216 1373700096 -0.0235825758 0.1333155185 0.0150421513 688 1305031252.4538249969 0.0470676199 0.0847931612 0.1399672329 0.0463560304 0.0046320000 17828517 955859216 1373700096 -0.0230731964 0.1344729811 0.0164760593 689 1305031252.4895589352 0.0475657173 0.0847391301 0.1399672329 0.0463259567 0.0045730000 17831389 955859216 1373700096 -0.0238358509 0.1353255361 0.0170921981 690 1305031252.5221700668 0.0482456721 0.0846862410 0.1399672329 0.0462987655 0.0047000000 17834317 955859216 1373700096 -0.0241093915 0.1352879256 0.0175592601 691 1305031252.5537741184 0.0489213206 0.0846344828 0.1399672329 0.0462729537 0.0045910000 17837189 955859216 1373700096 -0.0253937766 0.1351407319 0.0170696564 692 1305031252.5897459984 0.0483563393 0.0845820578 0.1399672329 0.0462438168 0.0046140000 17840117 955859216 1373700096 -0.0275129247 0.1361405849 0.0169956312 693 1305031252.6221249104 0.0498107150 0.0845318827 0.1399672329 0.0462173969 0.0045720000 17843045 955859216 1373700096 -0.0256922059 0.1373014599 0.0204644930 694 1305031252.6578559875 0.0526207127 0.0844859012 0.1399672329 0.0461994203 0.0072230000 17845973 955859216 1373700096 -0.0240110923 0.1376930028 0.0229620785 695 1305031252.6889979839 0.0546500944 0.0844429719 0.1399672329 0.0462137205 0.0072690000 17848789 955859216 1373700096 -0.0230314583 0.1360138059 0.0250718836 696 1305031252.7216539383 0.0568848066 0.0844033769 0.1399672329 0.0462819612 0.0057860000 17851661 955859216 1373700096 -0.0235612486 0.1335861534 0.0243752468 697 1305031252.7578220367 0.0565885603 0.0843634704 0.1399672329 0.0463971199 0.0076350000 17854701 955859216 1373700096 -0.0273217838 0.1274867505 0.0186351482 698 1305031252.7896919250 0.0606588498 0.0843295096 0.1399672329 0.0465163190 0.0049970000 17857517 955859216 1373700096 -0.0245165508 0.1226770580 0.0162522700 699 1305031252.8224050999 0.0580876656 0.0842919676 0.1399672329 0.0466177578 0.0044040000 17860445 955859216 1373700096 -0.0356688574 0.1200814694 0.0056221718 700 1305031252.8539779186 0.0613180920 0.0842591478 0.1399672329 0.0466116201 0.0072290000 17863205 955859216 1373700096 -0.0331507176 0.1149572656 0.0045523918 701 1305031252.8897290230 0.0633163601 0.0842292722 0.1399672329 0.0466393244 0.0038060000 17866189 955859216 1373700096 -0.0338288583 0.1113745719 0.0020675866 702 1305031252.9206719398 0.0643061996 0.0842008918 0.1399672329 0.0466476341 0.0079570000 17869061 955859216 1373700096 -0.0388174132 0.1063174680 -0.0026772944 703 1305031252.9578649998 0.0662252232 0.0841753218 0.1399672329 0.0467240790 0.0050680000 17872157 955859216 1373700096 -0.0430539139 0.0996969566 -0.0061143087 704 1305031252.9894239902 0.0677473024 0.0841519866 0.1399672329 0.0467817478 0.0043840000 17874917 955859216 1373700096 -0.0472612455 0.0955490395 -0.0081314491 705 1305031253.0196959972 0.0688890219 0.0841303370 0.1399672329 0.0468521938 0.0074970000 17877789 955859216 1373700096 -0.0570931807 0.0907903761 -0.0137250498 706 1305031253.0574259758 0.0719144866 0.0841130341 0.1399672329 0.0468999269 0.0072950000 17880829 955859216 1373700096 -0.0611219965 0.0846370235 -0.0157634057 707 1305031253.0895500183 0.0760696307 0.0841016573 0.1399672329 0.0469267584 0.0047020000 17883645 955859216 1373700096 -0.0671276227 0.0764773190 -0.0219676923 708 1305031253.1197240353 0.0797640979 0.0840955308 0.1399672329 0.0469430771 0.0043320000 17886517 955859216 1373700096 -0.0676885471 0.0714708269 -0.0232109167 709 1305031253.1573839188 0.0863304511 0.0840986830 0.1399672329 0.0470121684 0.0073840000 17889501 955859216 1373700096 -0.0784473196 0.0626509935 -0.0318340473 710 1305031253.1892180443 0.0858639851 0.0841011693 0.1399672329 0.0470407798 0.0061170000 17892317 955859216 1373700096 -0.0816768482 0.0618842207 -0.0308880731 711 1305031253.2180271149 0.0836883113 0.0841005887 0.1399672329 0.0470309639 0.0047090000 17895189 955859216 1373700096 -0.0811895877 0.0625712201 -0.0276481248 712 1305031253.2578470707 0.0850213841 0.0841018819 0.1399672329 0.0470097375 0.0041780000 17898285 955859216 1373700096 -0.0843744352 0.0593723208 -0.0282179192 713 1305031253.2897419930 0.0854322687 0.0841037478 0.1399672329 0.0469798227 0.0071040000 17901101 955859216 1373700096 -0.0828884318 0.0564232282 -0.0263658129 714 1305031253.3220069408 0.0855087936 0.0841057157 0.1399672329 0.0469551754 0.0072090000 17904029 955859216 1373700096 -0.0777035505 0.0530897677 -0.0234162863 715 1305031253.3578300476 0.0867157057 0.0841093660 0.1399672329 0.0469273966 0.0047110000 17906957 955859216 1373700096 -0.0716873482 0.0504768379 -0.0209046602 716 1305031253.3880970478 0.0857272819 0.0841116257 0.1399672329 0.0468952133 0.0071970000 17909773 955859216 1373700096 -0.0707328618 0.0508792736 -0.0188848544 717 1305031253.4213519096 0.0861220881 0.0841144297 0.1399672329 0.0468638936 0.0053960000 17912701 955859216 1373700096 -0.0694546551 0.0505541712 -0.0177873280 718 1305031253.4579629898 0.0862607807 0.0841174190 0.1399672329 0.0468333404 0.0046930000 17915685 955859216 1373700096 -0.0691978037 0.0517423488 -0.0167823602 719 1305031253.4896900654 0.0853813961 0.0841191770 0.1399672329 0.0468011904 0.0072040000 17918557 955859216 1373700096 -0.0719116628 0.0533194989 -0.0166745577 720 1305031253.5207340717 0.0863596350 0.0841222887 0.1399672329 0.0467707067 0.0061920000 17921429 955859216 1373700096 -0.0718897358 0.0524058081 -0.0168963075 721 1305031253.5578539371 0.0874691755 0.0841269307 0.1399672329 0.0467403085 0.0072380000 17924413 955859216 1373700096 -0.0741186664 0.0522285812 -0.0176831894 722 1305031253.5898048878 0.0858974829 0.0841293830 0.1399672329 0.0467135189 0.0049760000 17927285 955859216 1373700096 -0.0824180543 0.0558689833 -0.0193323456 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:33:07 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 -nan 0.0093910000 14758853 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 1305031102.2112140656 0.0217163358 0.0235575829 0.0253988300 0.0240789838 0.0073810000 15546581 955859216 1373700096 -0.0023057149 0.0007948892 0.0125143202 3 1305031102.2432110310 0.0218860060 0.0230003906 0.0253988300 0.0192113140 0.0022950000 15549845 955859216 1373700096 -0.0037581150 0.0053050509 0.0258700028 4 1305031102.2753260136 0.0166617353 0.0214157267 0.0253988300 0.0157442527 0.0023860000 15553117 955859216 1373700096 -0.0044980450 0.0041071358 0.0388879888 5 1305031102.3112668991 0.0125742769 0.0196474368 0.0253988300 0.0141415665 0.0023230000 15556485 955859216 1373700096 -0.0033568183 0.0037984839 0.0516050272 6 1305031102.3432331085 0.0089264447 0.0178606048 0.0253988300 0.0148750974 0.0023240000 15560157 955859216 1373700096 -0.0042320332 0.0023710621 0.0636269748 7 1305031102.3753290176 0.0086956630 0.0165513274 0.0253988300 0.0137497420 0.0023030000 15562973 955859216 1373700096 -0.0045832600 0.0031377845 0.0755121559 8 1305031102.4112579823 0.0069271545 0.0153483058 0.0253988300 0.0147506067 0.0023590000 15566013 955859216 1373700096 -0.0065013543 0.0048748152 0.0872660130 9 1305031102.4432709217 0.0075859386 0.0144858205 0.0253988300 0.0167612079 0.0023620000 15569653 955859216 1373700096 -0.0082751131 0.0075846277 0.0996263996 10 1305031102.4753179550 0.0111059658 0.0141478350 0.0253988300 0.0160580584 0.0023530000 15574069 955859216 1373700096 -0.0071273595 0.0112016583 0.1126668677 11 1305031102.5112190247 0.0133451419 0.0140748629 0.0253988300 0.0161431803 0.0024110000 15577053 955859216 1373700096 -0.0073598521 0.0107499277 0.1251652092 12 1305031102.5432200432 0.0163727365 0.0142663524 0.0253988300 0.0153952126 0.0023440000 15579981 955859216 1373700096 -0.0085221631 0.0107870512 0.1370542645 13 1305031102.5752859116 0.0188182127 0.0146164955 0.0253988300 0.0158699950 0.0024200000 15582797 955859216 1373700096 -0.0114270085 0.0102471560 0.1486886144 14 1305031102.6112329960 0.0235384349 0.0152537769 0.0253988300 0.0167556746 0.0023950000 15585781 955859216 1373700096 -0.0129792737 0.0076831831 0.1597722024 15 1305031102.6432650089 0.0261419155 0.0159796528 0.0261419155 0.0169566027 0.0023900000 15588653 955859216 1373700096 -0.0159760453 0.0083227372 0.1706594378 16 1305031102.6752851009 0.0239344519 0.0164768277 0.0261419155 0.0170185796 0.0025200000 15591525 955859216 1373700096 -0.0178937055 0.0152768446 0.1823419333 17 1305031102.7112629414 0.0265338160 0.0170684153 0.0265338160 0.0168165272 0.0023930000 15596045 955859216 1373700096 -0.0183633696 0.0179083869 0.1947547793 18 1305031102.7432339191 0.0301243849 0.0177937469 0.0301243849 0.0164373622 0.0023230000 15602173 955859216 1373700096 -0.0191865619 0.0194330644 0.2075127959 19 1305031102.7754719257 0.0298159830 0.0184264962 0.0301243849 0.0165084732 0.0024500000 15604989 955859216 1373700096 -0.0187065974 0.0254325513 0.2203737944 20 1305031102.8112320900 0.0337635688 0.0191933498 0.0337635688 0.0161384486 0.0023850000 15607973 955859216 1373700096 -0.0199339502 0.0273376796 0.2330060452 21 1305031102.8432900906 0.0353394412 0.0199622113 0.0353394412 0.0157397266 0.0024250000 15610901 955859216 1373700096 -0.0219756309 0.0307089612 0.2455430478 22 1305031102.8753631115 0.0382936560 0.0207954588 0.0382936560 0.0154348373 0.0023730000 15613717 955859216 1373700096 -0.0247269124 0.0325101987 0.2572783828 23 1305031102.9111850262 0.0410960689 0.0216780940 0.0410960689 0.0151319288 0.0023810000 15616701 955859216 1373700096 -0.0272378195 0.0351311527 0.2687973380 24 1305031102.9432289600 0.0426346064 0.0225512820 0.0426346064 0.0152268078 0.0024820000 15619629 955859216 1373700096 -0.0292183235 0.0386338048 0.2801085114 25 1305031102.9752030373 0.0453491658 0.0234631974 0.0453491658 0.0161995855 0.0024250000 15622389 955859216 1373700096 -0.0328847319 0.0411693826 0.2913660109 26 1305031103.0112149715 0.0483099595 0.0244188421 0.0483099595 0.0158870754 0.0023870000 15625429 955859216 1373700096 -0.0335683301 0.0441947356 0.3029507995 27 1305031103.0432269573 0.0512406528 0.0254122425 0.0512406528 0.0155916420 0.0023790000 15628357 955859216 1373700096 -0.0334121957 0.0471130461 0.3143712878 28 1305031103.0753190517 0.0541885570 0.0264399680 0.0541885570 0.0159690708 0.0024110000 15631173 955859216 1373700096 -0.0323094688 0.0496956445 0.3251523376 29 1305031103.1112399101 0.0580497347 0.0275299600 0.0580497347 0.0159033852 0.0023980000 15634157 955859216 1373700096 -0.0319516622 0.0512650385 0.3349383175 30 1305031103.1433179379 0.0572017953 0.0285190211 0.0580497347 0.0156629175 0.0024570000 15637029 955859216 1373700096 -0.0317779481 0.0575121343 0.3443093300 31 1305031103.1754519939 0.0596248955 0.0295224364 0.0596248955 0.0154217484 0.0023930000 15639901 955859216 1373700096 -0.0325599983 0.0595789701 0.3532655835 32 1305031103.2112200260 0.0603725538 0.0304865026 0.0603725538 0.0161077857 0.0023570000 15642885 955859216 1373700096 -0.0330657884 0.0643650442 0.3620295227 33 1305031103.2432160378 0.0616953932 0.0314322266 0.0616953932 0.0158944379 0.0023740000 15648885 955859216 1373700096 -0.0329643525 0.0682099983 0.3710346222 34 1305031103.2753698826 0.0645252392 0.0324055505 0.0645252392 0.0160658549 0.0023110000 15658101 955859216 1373700096 -0.0328811929 0.0698088035 0.3792894781 35 1305031103.3112099171 0.0699843019 0.0334792291 0.0699843019 0.0166320206 0.0024180000 15661085 955859216 1373700096 -0.0339861810 0.0672946051 0.3866496980 36 1305031103.3432230949 0.0762693807 0.0346678444 0.0762693807 0.0173777138 0.0024990000 15664013 955859216 1373700096 -0.0338219404 0.0623902641 0.3917627335 37 1305031103.3753271103 0.0769567564 0.0358107880 0.0769567564 0.0173518480 0.0021990000 15666829 955859216 1373700096 -0.0325147808 0.0623989254 0.3943517804 38 1305031103.4112598896 0.0775254220 0.0369085415 0.0775254220 0.0172773091 0.0021950000 15669813 955859216 1373700096 -0.0310763605 0.0614246354 0.3950719833 39 1305031103.4432799816 0.0794955716 0.0380005166 0.0794955716 0.0171865758 0.0021610000 15672741 955859216 1373700096 -0.0316800959 0.0579501204 0.3937098682 40 1305031103.4752740860 0.0805284604 0.0390637152 0.0805284604 0.0169912478 0.0022560000 15675557 955859216 1373700096 -0.0316971913 0.0544016324 0.3908649385 41 1305031103.5113329887 0.0843531266 0.0401683350 0.0843531266 0.0169735348 0.0023700000 15678541 955859216 1373700096 -0.0295072552 0.0473212488 0.3869667649 42 1305031103.5434439182 0.0841133595 0.0412146451 0.0843531266 0.0168992486 0.0023790000 15681469 955859216 1373700096 -0.0293492284 0.0425398238 0.3802966475 43 1305031103.5754740238 0.0832282901 0.0421917066 0.0843531266 0.0167475745 0.0024320000 15684285 955859216 1373700096 -0.0287665613 0.0377223194 0.3721612990 44 1305031103.6112229824 0.0809787959 0.0430732314 0.0843531266 0.0166616528 0.0023370000 15687269 955859216 1373700096 -0.0275103599 0.0347030796 0.3630007505 45 1305031103.6434450150 0.0791865140 0.0438757488 0.0843531266 0.0164802469 0.0024210000 15690197 955859216 1373700096 -0.0264294874 0.0302174333 0.3532463908 46 1305031103.6755230427 0.0770641491 0.0445972357 0.0843531266 0.0163555562 0.0024490000 15693013 955859216 1373700096 -0.0242134891 0.0260976832 0.3428224921 47 1305031103.7116100788 0.0747864395 0.0452395592 0.0843531266 0.0161964590 0.0024160000 15695997 955859216 1373700096 -0.0218125433 0.0223302208 0.3316772282 48 1305031103.7433259487 0.0722351670 0.0458019677 0.0843531266 0.0160752017 0.0024770000 15698925 955859216 1373700096 -0.0195261016 0.0181696471 0.3199549317 49 1305031103.7753419876 0.0699851885 0.0462955028 0.0843531266 0.0159080434 0.0024010000 15701741 955859216 1373700096 -0.0184519347 0.0126655614 0.3074004054 50 1305031103.8112421036 0.0666769594 0.0467031320 0.0843531266 0.0161656077 0.0023510000 15704725 955859216 1373700096 -0.0173826423 0.0103862062 0.2941663265 51 1305031103.8432509899 0.0629335642 0.0470213757 0.0843531266 0.0161902520 0.0024290000 15707653 955859216 1373700096 -0.0156577174 0.0082297511 0.2813543975 52 1305031103.8753609657 0.0604509898 0.0472796375 0.0843531266 0.0161750767 0.0024560000 15710469 955859216 1373700096 -0.0159245767 0.0048990841 0.2690971792 53 1305031103.9112210274 0.0644312128 0.0476032522 0.0843531266 0.0172094415 0.0026730000 15713453 955859216 1373700096 -0.0159166660 -0.0060965735 0.2567055821 54 1305031103.9432110786 0.0646100268 0.0479181924 0.0843531266 0.0171134010 0.0026730000 15716381 955859216 1373700096 -0.0139553053 -0.0137234107 0.2432556152 55 1305031103.9753730297 0.0611846857 0.0481594014 0.0843531266 0.0170811924 0.0024940000 15719253 955859216 1373700096 -0.0130578140 -0.0169789996 0.2288479507 56 1305031104.0112318993 0.0606495440 0.0483824397 0.0843531266 0.0172870622 0.0026150000 15722181 955859216 1373700096 -0.0109693632 -0.0223626904 0.2144769430 57 1305031104.0432488918 0.0579562448 0.0485504012 0.0843531266 0.0172422690 0.0026580000 15725109 955859216 1373700096 -0.0080641555 -0.0279701408 0.1995860934 58 1305031104.0754249096 0.0522284769 0.0486138163 0.0843531266 0.0172683140 0.0027660000 15727925 955859216 1373700096 -0.0054950365 -0.0289929453 0.1839401722 59 1305031104.1112349033 0.0476964042 0.0485982669 0.0843531266 0.0171843293 0.0026430000 15730909 955859216 1373700096 -0.0059828744 -0.0298094284 0.1689559966 60 1305031104.1432299614 0.0440507419 0.0485224748 0.0843531266 0.0171338573 0.0027530000 15733837 955859216 1373700096 -0.0059710913 -0.0349176452 0.1544948220 61 1305031104.1754240990 0.0401688740 0.0483855305 0.0843531266 0.0170867420 0.0026540000 15736653 955859216 1373700096 -0.0061909580 -0.0383310840 0.1403282136 62 1305031104.2112829685 0.0389928706 0.0482340360 0.0843531266 0.0169936603 0.0026210000 15739637 955859216 1373700096 -0.0059430567 -0.0407953672 0.1267000437 63 1305031104.2431960106 0.0354386680 0.0480309349 0.0843531266 0.0168762524 0.0027080000 15742565 955859216 1373700096 -0.0054262253 -0.0439898521 0.1132597402 64 1305031104.2755460739 0.0320816524 0.0477817274 0.0843531266 0.0167519968 0.0027210000 15745381 955859216 1373700096 -0.0036061434 -0.0459821038 0.1003678069 65 1305031104.3112189770 0.0310942624 0.0475249972 0.0843531266 0.0166660821 0.0027220000 15754509 955859216 1373700096 -0.0023172491 -0.0472119525 0.0876685083 66 1305031104.3433420658 0.0276584923 0.0472239895 0.0843531266 0.0165921271 0.0027800000 15770237 955859216 1373700096 -0.0005447454 -0.0477763787 0.0755113289 67 1305031104.3758370876 0.0267668627 0.0469186593 0.0843531266 0.0165410834 0.0028430000 15773053 955859216 1373700096 0.0010002822 -0.0479266346 0.0637391657 68 1305031104.4115090370 0.0244644936 0.0465884510 0.0843531266 0.0164965956 0.0027850000 15776037 955859216 1373700096 0.0004295981 -0.0480493456 0.0525527969 69 1305031104.4432880878 0.0223856401 0.0462376856 0.0843531266 0.0164330367 0.0027670000 15778909 955859216 1373700096 -0.0007944410 -0.0485264249 0.0420317650 70 1305031104.4754559994 0.0211613793 0.0458794526 0.0843531266 0.0163710490 0.0028280000 15781781 955859216 1373700096 -0.0029768676 -0.0492004193 0.0323433019 71 1305031104.5113289356 0.0234467071 0.0455634985 0.0843531266 0.0164813217 0.0028290000 15784765 955859216 1373700096 -0.0048246421 -0.0510512032 0.0231717601 72 1305031104.5433681011 0.0227869060 0.0452471569 0.0843531266 0.0164679807 0.0028960000 15787693 955859216 1373700096 -0.0042765415 -0.0544349030 0.0135228736 73 1305031104.5753428936 0.0218504760 0.0449266544 0.0843531266 0.0165849689 0.0028110000 15790453 955859216 1373700096 -0.0030540635 -0.0561324321 0.0035216422 74 1305031104.6113359928 0.0239873622 0.0446436910 0.0843531266 0.0173369881 0.0028890000 15793493 955859216 1373700096 0.0006208413 -0.0595639646 -0.0078641912 75 1305031104.6432430744 0.0215414539 0.0443356612 0.0843531266 0.0173410145 0.0029520000 15796365 955859216 1373700096 0.0049469620 -0.0626113415 -0.0213291515 76 1305031104.6755249500 0.0220689252 0.0440426778 0.0843531266 0.0172340370 0.0029820000 15799237 955859216 1373700096 0.0072572478 -0.0575497448 -0.0354516804 77 1305031104.7112770081 0.0246902965 0.0437913482 0.0843531266 0.0174488572 0.0029520000 15802221 955859216 1373700096 0.0099075688 -0.0554469042 -0.0497459508 78 1305031104.7432799339 0.0290177986 0.0436019437 0.0843531266 0.0173648726 0.0029690000 15805093 955859216 1373700096 0.0122436825 -0.0504632033 -0.0638737902 79 1305031104.7753269672 0.0369319692 0.0435175137 0.0843531266 0.0172843787 0.0029690000 15807909 955859216 1373700096 0.0165442508 -0.0438066237 -0.0759425014 80 1305031104.8114650249 0.0439923666 0.0435234493 0.0843531266 0.0172185493 0.0029150000 15810949 955859216 1373700096 0.0193775278 -0.0379138254 -0.0862281248 81 1305031104.8432579041 0.0519522168 0.0436275082 0.0843531266 0.0171502299 0.0029260000 15813821 955859216 1373700096 0.0240062382 -0.0313571505 -0.0943600237 82 1305031104.8753499985 0.0548952967 0.0437649202 0.0843531266 0.0171972043 0.0028360000 15816693 955859216 1373700096 0.0243303198 -0.0282246359 -0.0995390266 83 1305031104.9115340710 0.0584607534 0.0439419785 0.0843531266 0.0171457815 0.0028460000 15819677 955859216 1373700096 0.0247200448 -0.0239541046 -0.1021816283 84 1305031104.9432621002 0.0616050065 0.0441522526 0.0843531266 0.0170532584 0.0028510000 15822549 955859216 1373700096 0.0258147568 -0.0204013195 -0.1023034230 85 1305031104.9752020836 0.0635073781 0.0443799600 0.0843531266 0.0170681163 0.0028790000 15825421 955859216 1373700096 0.0259871539 -0.0172551330 -0.0995969996 86 1305031105.0112900734 0.0711973980 0.0446917906 0.0843531266 0.0171927171 0.0030800000 15828405 955859216 1373700096 0.0252027810 -0.0069607701 -0.0932228789 87 1305031105.0433731079 0.0719977096 0.0450056518 0.0843531266 0.0171554859 0.0030360000 15831277 955859216 1373700096 0.0234246757 -0.0035976323 -0.0854426697 88 1305031105.0753200054 0.0687478408 0.0452754494 0.0843531266 0.0170937017 0.0031260000 15834149 955859216 1373700096 0.0197698567 -0.0039074803 -0.0761958659 89 1305031105.1112990379 0.0655866787 0.0455036654 0.0843531266 0.0170092786 0.0031810000 15837133 955859216 1373700096 0.0165879633 -0.0041356971 -0.0657334626 90 1305031105.1431059837 0.0598109253 0.0456626350 0.0843531266 0.0170011472 0.0031320000 15840005 955859216 1373700096 0.0114815775 -0.0064060367 -0.0541249737 91 1305031105.1751589775 0.0609957352 0.0458311306 0.0843531266 0.0174780689 0.0032560000 15842877 955859216 1373700096 0.0064292401 -0.0005508476 -0.0390958674 92 1305031105.2112679482 0.0564261302 0.0459462936 0.0843531266 0.0175139183 0.0031590000 15845861 955859216 1373700096 -0.0004408458 -0.0006961093 -0.0231477637 93 1305031105.2432699203 0.0450168177 0.0459362993 0.0843531266 0.0175354743 0.0031900000 15848733 955859216 1373700096 -0.0041938624 -0.0081866467 -0.0088820457 94 1305031105.2752881050 0.0396813825 0.0458697576 0.0843531266 0.0176880739 0.0032110000 15851605 955859216 1373700096 -0.0092581343 -0.0089261672 0.0063796719 95 1305031105.3112900257 0.0328636318 0.0457328510 0.0843531266 0.0176849849 0.0032090000 15854589 955859216 1373700096 -0.0140488585 -0.0108490931 0.0219247248 96 1305031105.3433020115 0.0242261384 0.0455088228 0.0843531266 0.0176265823 0.0032400000 15857461 955859216 1373700096 -0.0158379246 -0.0148982685 0.0369942449 97 1305031105.3753380775 0.0154612353 0.0451990538 0.0843531266 0.0178127088 0.0032350000 15860333 955859216 1373700096 -0.0152488733 -0.0195570830 0.0510015786 98 1305031105.4112861156 0.0111518577 0.0448516335 0.0843531266 0.0178454491 0.0032020000 15863317 955859216 1373700096 -0.0153536331 -0.0197671168 0.0650351569 99 1305031105.4433159828 0.0103876637 0.0445035125 0.0843531266 0.0177586836 0.0031330000 15866189 955859216 1373700096 -0.0175785292 -0.0156992469 0.0792866051 100 1305031105.4752800465 0.0060268380 0.0441187458 0.0843531266 0.0177033298 0.0032250000 15869061 955859216 1373700096 -0.0177820046 -0.0178745668 0.0931547582 101 1305031105.5113320351 0.0056528174 0.0437378950 0.0843531266 0.0176868102 0.0031400000 15872045 955859216 1373700096 -0.0189574491 -0.0166126546 0.1070465669 102 1305031105.5432820320 0.0074498784 0.0433821302 0.0843531266 0.0176287145 0.0031250000 15874917 955859216 1373700096 -0.0190190505 -0.0154003156 0.1209987625 103 1305031105.5754489899 0.0093296161 0.0430515232 0.0843531266 0.0175500995 0.0031470000 15877789 955859216 1373700096 -0.0207485519 -0.0154540092 0.1345146894 104 1305031105.6113779545 0.0114813978 0.0427479643 0.0843531266 0.0174714172 0.0030880000 15880773 955859216 1373700096 -0.0222386755 -0.0138580296 0.1482158005 105 1305031105.6432731152 0.0156687126 0.0424900667 0.0843531266 0.0174438829 0.0030570000 15883645 955859216 1373700096 -0.0232718643 -0.0142933410 0.1620724648 106 1305031105.6751658916 0.0176736210 0.0422559493 0.0843531266 0.0174120016 0.0030830000 15886517 955859216 1373700096 -0.0243517049 -0.0117736151 0.1762146205 107 1305031105.7113089561 0.0204468761 0.0420521262 0.0843531266 0.0175095317 0.0030480000 15889501 955859216 1373700096 -0.0237506516 -0.0092081940 0.1898093671 108 1305031105.7433118820 0.0240157656 0.0418851228 0.0843531266 0.0174397938 0.0031200000 15892373 955859216 1373700096 -0.0244637262 -0.0083928350 0.2035847157 109 1305031105.7753388882 0.0228487086 0.0417104768 0.0843531266 0.0173684947 0.0031680000 15895245 955859216 1373700096 -0.0250844024 -0.0026137587 0.2174186110 110 1305031105.8112831116 0.0271823388 0.0415784028 0.0843531266 0.0173050021 0.0031250000 15898229 955859216 1373700096 -0.0253344793 -0.0012953571 0.2311398238 111 1305031105.8432710171 0.0292931143 0.0414677246 0.0843531266 0.0172293002 0.0030710000 15901101 955859216 1373700096 -0.0261133984 0.0016481460 0.2449382544 112 1305031105.8753368855 0.0303156413 0.0413681524 0.0843531266 0.0171781377 0.0021150000 15903973 955859216 1373700096 -0.0253907964 0.0061619962 0.2584505975 113 1305031105.9112620354 0.0318171941 0.0412836306 0.0843531266 0.0172107312 0.0020600000 15906957 955859216 1373700096 -0.0252083875 0.0121802976 0.2724454999 114 1305031105.9432721138 0.0344930254 0.0412240639 0.0843531266 0.0171498621 0.0018980000 15909829 955859216 1373700096 -0.0244139228 0.0155715039 0.2857080102 115 1305031105.9753289223 0.0363479778 0.0411816632 0.0843531266 0.0171251788 0.0030490000 15912701 955859216 1373700096 -0.0249773841 0.0204302445 0.2985687852 116 1305031106.0112850666 0.0404181145 0.0411750809 0.0843531266 0.0170728388 0.0029610000 15915685 955859216 1373700096 -0.0244801529 0.0242242590 0.3113243580 117 1305031106.0433549881 0.0425694697 0.0411869987 0.0843531266 0.0170020802 0.0030010000 15918613 955859216 1373700096 -0.0252143741 0.0284000393 0.3236012757 118 1305031106.0753300190 0.0460231192 0.0412279828 0.0843531266 0.0169412336 0.0028860000 15921429 955859216 1373700096 -0.0253829807 0.0316002779 0.3356219530 119 1305031106.1113269329 0.0488954782 0.0412924155 0.0843531266 0.0169394376 0.0030270000 15924413 955859216 1373700096 -0.0289878696 0.0360642448 0.3470160961 120 1305031106.1433548927 0.0507234447 0.0413710074 0.0843531266 0.0168757251 0.0028820000 15927341 955859216 1373700096 -0.0295958687 0.0403468013 0.3585234582 121 1305031106.1755340099 0.0559816100 0.0414917562 0.0843531266 0.0168097692 0.0029250000 15930157 955859216 1373700096 -0.0310377162 0.0410830937 0.3694918752 122 1305031106.2112751007 0.0601173453 0.0416444250 0.0843531266 0.0167445833 0.0028270000 15933141 955859216 1373700096 -0.0325398333 0.0429769382 0.3793525398 123 1305031106.2432670593 0.0651999637 0.0418359334 0.0843531266 0.0166805315 0.0027900000 15936069 955859216 1373700096 -0.0339209810 0.0430652611 0.3884094656 124 1305031106.2763850689 0.0673693195 0.0420418478 0.0843531266 0.0166199668 0.0028230000 15938941 955859216 1373700096 -0.0344853923 0.0458957963 0.3960975707 125 1305031106.3112380505 0.0675229877 0.0422456969 0.0843531266 0.0165670197 0.0028390000 15941869 955859216 1373700096 -0.0342973955 0.0499762371 0.4029949009 126 1305031106.3432579041 0.0690446720 0.0424583872 0.0843531266 0.0165899325 0.0028340000 15944797 955859216 1373700096 -0.0341658629 0.0524632782 0.4091715813 127 1305031106.3753879070 0.0688090697 0.0426658729 0.0843531266 0.0166190067 0.0026760000 15947613 955859216 1373700096 -0.0350472704 0.0556965843 0.4137848020 128 1305031106.4113199711 0.0698804855 0.0428784871 0.0843531266 0.0166642383 0.0027640000 15950597 955859216 1373700096 -0.0356348157 0.0565457307 0.4166493714 129 1305031106.4432780743 0.0806409344 0.0431712192 0.0843531266 0.0168429986 0.0030000000 15965757 955859216 1373700096 -0.0368138626 0.0455812253 0.4185364246 130 1305031106.4753448963 0.0812844262 0.0434643977 0.0843531266 0.0169038375 0.0027290000 15994229 955859216 1373700096 -0.0386265069 0.0434146859 0.4162033796 131 1305031106.5111289024 0.0820838511 0.0437592027 0.0843531266 0.0169186898 0.0027220000 15997045 955859216 1373700096 -0.0403306745 0.0400488563 0.4119932950 132 1305031106.5433020592 0.0857073665 0.0440769918 0.0857073665 0.0168826117 0.0029790000 15999973 955859216 1373700096 -0.0394524783 0.0323143043 0.4062027931 133 1305031106.5752820969 0.0840096399 0.0443772373 0.0857073665 0.0168340597 0.0029180000 16002789 955859216 1373700096 -0.0379107669 0.0291634444 0.3976014555 134 1305031106.6111509800 0.0816089362 0.0446550858 0.0857073665 0.0168530004 0.0027650000 16005773 955859216 1373700096 -0.0380649790 0.0266278405 0.3877218664 135 1305031106.6432070732 0.0797595978 0.0449151192 0.0857073665 0.0168282064 0.0030090000 16008701 955859216 1373700096 -0.0379212089 0.0232621152 0.3773932457 136 1305031106.6752789021 0.0812095255 0.0451819899 0.0857073665 0.0167887832 0.0029540000 16011517 955859216 1373700096 -0.0375088304 0.0159697942 0.3662342727 137 1305031106.7115080357 0.0789149255 0.0454282157 0.0857073665 0.0168091832 0.0029150000 16014501 955859216 1373700096 -0.0369059481 0.0136026582 0.3534565866 138 1305031106.7433409691 0.0789789855 0.0456713372 0.0857073665 0.0168036999 0.0030320000 16017429 955859216 1373700096 -0.0361838564 0.0075077172 0.3408168554 139 1305031106.7753899097 0.0776065886 0.0459010872 0.0857073665 0.0167481209 0.0030380000 16020245 955859216 1373700096 -0.0346146971 0.0030132721 0.3272826076 140 1305031106.8112890720 0.0760494620 0.0461164327 0.0857073665 0.0167149356 0.0030180000 16023229 955859216 1373700096 -0.0323517211 -0.0000295230 0.3128819466 141 1305031106.8434159756 0.0731805786 0.0463083770 0.0857073665 0.0166925771 0.0030980000 16026101 955859216 1373700096 -0.0303473212 -0.0029932654 0.2983019650 142 1305031106.8759050369 0.0740311667 0.0465036080 0.0857073665 0.0168380041 0.0032800000 16028973 955859216 1373700096 -0.0298049040 -0.0117363315 0.2829802036 143 1305031106.9112429619 0.0718533099 0.0466808786 0.0857073665 0.0168492345 0.0031860000 16031957 955859216 1373700096 -0.0286968425 -0.0151131162 0.2656082809 144 1305031106.9434390068 0.0650725737 0.0468085987 0.0857073665 0.0168068482 0.0031640000 16034829 955859216 1373700096 -0.0279060919 -0.0154369343 0.2478888482 145 1305031106.9755470753 0.0638582930 0.0469261828 0.0857073665 0.0168106601 0.0031220000 16037701 955859216 1373700096 -0.0291042794 -0.0228555556 0.2305207849 146 1305031107.0115759373 0.0619474314 0.0470290681 0.0857073665 0.0167768165 0.0032670000 16040741 955859216 1373700096 -0.0303529948 -0.0279648416 0.2122167945 147 1305031107.0432810783 0.0525562763 0.0470666681 0.0857073665 0.0168026177 0.0031620000 16043613 955859216 1373700096 -0.0291832518 -0.0245163627 0.1940859258 148 1305031107.0754320621 0.0503715500 0.0470889984 0.0857073665 0.0168446796 0.0032400000 16046429 955859216 1373700096 -0.0304469019 -0.0309141632 0.1777958572 149 1305031107.1112289429 0.0499240607 0.0471080257 0.0857073665 0.0167949247 0.0032600000 16049413 955859216 1373700096 -0.0312011112 -0.0362865962 0.1613497883 150 1305031107.1432600021 0.0437828675 0.0470858579 0.0857073665 0.0167872674 0.0031980000 16052341 955859216 1373700096 -0.0289364439 -0.0358287469 0.1453325152 151 1305031107.1753990650 0.0392485447 0.0470339552 0.0857073665 0.0167413404 0.0031640000 16055157 955859216 1373700096 -0.0281009488 -0.0372235179 0.1305009425 152 1305031107.2113580704 0.0406674966 0.0469920706 0.0857073665 0.0168247453 0.0031930000 16058141 955859216 1373700096 -0.0287064407 -0.0437504575 0.1161209866 153 1305031107.2433779240 0.0365171470 0.0469236071 0.0857073665 0.0167793449 0.0032640000 16061013 955859216 1373700096 -0.0271937158 -0.0467601195 0.1016035303 154 1305031107.2753980160 0.0321484543 0.0468276645 0.0857073665 0.0167376549 0.0031710000 16063885 955859216 1373700096 -0.0248749834 -0.0472945385 0.0877709240 155 1305031107.3112258911 0.0314176045 0.0467282448 0.0857073665 0.0167237219 0.0033180000 16066869 955859216 1373700096 -0.0254020896 -0.0501479544 0.0740592852 156 1305031107.3435089588 0.0280744173 0.0466086690 0.0857073665 0.0167833936 0.0032880000 16069797 955859216 1373700096 -0.0258022808 -0.0538908280 0.0605058782 157 1305031107.3754129410 0.0234192070 0.0464609654 0.0857073665 0.0168357287 0.0033340000 16072613 955859216 1373700096 -0.0241157152 -0.0538247339 0.0478092059 158 1305031107.4112710953 0.0201120451 0.0462942001 0.0857073665 0.0168149286 0.0034040000 16075597 955859216 1373700096 -0.0200284254 -0.0501937717 0.0375778899 159 1305031107.4434189796 0.0171775669 0.0461110766 0.0857073665 0.0167655035 0.0034190000 16078525 955859216 1373700096 -0.0177818853 -0.0486304872 0.0294507165 160 1305031107.4753770828 0.0178175494 0.0459342420 0.0857073665 0.0167238643 0.0032840000 16081397 955859216 1373700096 -0.0158740953 -0.0465966612 0.0237331372 161 1305031107.5113520622 0.0207288619 0.0457776869 0.0857073665 0.0167020812 0.0032940000 16084325 955859216 1373700096 -0.0140565019 -0.0448798351 0.0198289566 162 1305031107.5436050892 0.0243283659 0.0456452837 0.0857073665 0.0167206838 0.0033120000 16087253 955859216 1373700096 -0.0125143863 -0.0409960635 0.0183170661 163 1305031107.5754539967 0.0245908219 0.0455161152 0.0857073665 0.0166963884 0.0032980000 16090069 955859216 1373700096 -0.0098512871 -0.0408060141 0.0177727565 164 1305031107.6112709045 0.0230154991 0.0453789163 0.0857073665 0.0166575755 0.0033770000 16093053 955859216 1373700096 -0.0073545058 -0.0419056676 0.0176727977 165 1305031107.6433229446 0.0228647701 0.0452424669 0.0857073665 0.0166462215 0.0034090000 16095981 955859216 1373700096 -0.0046678237 -0.0379914902 0.0192424040 166 1305031107.6755681038 0.0219967309 0.0451024324 0.0857073665 0.0166167044 0.0033420000 16098797 955859216 1373700096 -0.0037771801 -0.0369804762 0.0209276117 167 1305031107.7113070488 0.0208308920 0.0449570938 0.0857073665 0.0165752542 0.0033430000 16101781 955859216 1373700096 -0.0040085614 -0.0360619240 0.0229408070 168 1305031107.7435379028 0.0207877085 0.0448132284 0.0857073665 0.0165554970 0.0033720000 16104653 955859216 1373700096 -0.0040526865 -0.0332922041 0.0253985394 169 1305031107.7758018970 0.0208360273 0.0446713515 0.0857073665 0.0165136514 0.0033770000 16107525 955859216 1373700096 -0.0052053914 -0.0310180299 0.0278504770 170 1305031107.8115959167 0.0198074728 0.0445250934 0.0857073665 0.0164665267 0.0033720000 16110509 955859216 1373700096 -0.0051365644 -0.0311495364 0.0303628910 171 1305031107.8433320522 0.0192631669 0.0443773628 0.0857073665 0.0164262454 0.0034630000 16113381 955859216 1373700096 -0.0046070213 -0.0304211639 0.0328699425 172 1305031107.8753581047 0.0189669803 0.0442296280 0.0857073665 0.0164050676 0.0034810000 16116253 955859216 1373700096 -0.0041558924 -0.0306894463 0.0348950811 173 1305031107.9115409851 0.0192548428 0.0440852651 0.0857073665 0.0163907601 0.0034210000 16119237 955859216 1373700096 -0.0024236336 -0.0320576914 0.0364482589 174 1305031107.9431219101 0.0213002712 0.0439543169 0.0857073665 0.0163945800 0.0034530000 16122109 955859216 1373700096 -0.0012590154 -0.0322514921 0.0377533697 175 1305031107.9758069515 0.0246896110 0.0438442328 0.0857073665 0.0163895138 0.0034970000 16124981 955859216 1373700096 0.0022398075 -0.0315844864 0.0387507044 176 1305031108.0113201141 0.0276760254 0.0437523680 0.0857073665 0.0163587162 0.0035500000 16127965 955859216 1373700096 0.0065059187 -0.0312996395 0.0401744805 177 1305031108.0434179306 0.0295073818 0.0436718879 0.0857073665 0.0163255904 0.0035430000 16130837 955859216 1373700096 0.0140815740 -0.0273196120 0.0417654030 178 1305031108.0753519535 0.0316938572 0.0436045956 0.0857073665 0.0162925544 0.0035330000 16133653 955859216 1373700096 0.0225727167 -0.0234962963 0.0437364094 179 1305031108.1113779545 0.0406911336 0.0435883192 0.0857073665 0.0162549607 0.0034720000 16136637 955859216 1373700096 0.0270521455 -0.0240218565 0.0457873493 180 1305031108.1433339119 0.0439681560 0.0435904295 0.0857073665 0.0162289276 0.0035550000 16139509 955859216 1373700096 0.0351015292 -0.0223244093 0.0484866723 181 1305031108.1760580540 0.0491901785 0.0436213673 0.0857073665 0.0162762782 0.0036280000 16142381 955859216 1373700096 0.0454637744 -0.0179663096 0.0516946539 182 1305031108.2114748955 0.0522376783 0.0436687097 0.0857073665 0.0162764820 0.0035240000 16145365 955859216 1373700096 0.0541442446 -0.0140134208 0.0559715033 183 1305031108.2433469296 0.0526254065 0.0437176534 0.0857073665 0.0162837146 0.0035880000 16148237 955859216 1373700096 0.0642325655 -0.0173904132 0.0592032075 184 1305031108.2753579617 0.0524033569 0.0437648583 0.0857073665 0.0162423331 0.0035500000 16151109 955859216 1373700096 0.0753307045 -0.0205651913 0.0618759468 185 1305031108.3113319874 0.0576803721 0.0438400773 0.0857073665 0.0163881312 0.0035720000 16154093 955859216 1373700096 0.0844455510 -0.0149996253 0.0656005070 186 1305031108.3432779312 0.0586963147 0.0439199495 0.0857073665 0.0163721649 0.0035470000 16157021 955859216 1373700096 0.0938174054 -0.0122351851 0.0696019828 187 1305031108.3754100800 0.0576253124 0.0439932402 0.0857073665 0.0163444553 0.0035360000 16159837 955859216 1373700096 0.1052244008 -0.0119639840 0.0733226687 188 1305031108.4113609791 0.0599242076 0.0440779794 0.0857073665 0.0163077768 0.0035500000 16162821 955859216 1373700096 0.1171166003 -0.0127631128 0.0769034401 189 1305031108.4436099529 0.0574238934 0.0441485927 0.0857073665 0.0163183145 0.0035560000 16165749 955859216 1373700096 0.1308203638 -0.0141217075 0.0798654929 190 1305031108.4754710197 0.0568571910 0.0442154801 0.0857073665 0.0163235930 0.0035860000 16168565 955859216 1373700096 0.1428918689 -0.0151018938 0.0824432001 191 1305031108.5113780499 0.0607661195 0.0443021326 0.0857073665 0.0165876884 0.0035850000 16171549 955859216 1373700096 0.1550348997 -0.0179176033 0.0836094692 192 1305031108.5437369347 0.0626247227 0.0443975628 0.0857073665 0.0166206784 0.0035960000 16174477 955859216 1373700096 0.1656092554 -0.0203756820 0.0835182741 193 1305031108.5754139423 0.0648375526 0.0445034695 0.0857073665 0.0166545387 0.0035970000 16177293 955859216 1373700096 0.1750285327 -0.0192115176 0.0840850621 194 1305031108.6114070415 0.0708230436 0.0446391374 0.0857073665 0.0166478285 0.0036570000 16180277 955859216 1373700096 0.1828936636 -0.0118836900 0.0853768885 195 1305031108.6433029175 0.0732753128 0.0447859896 0.0857073665 0.0166185553 0.0035980000 16183205 955859216 1373700096 0.1919226050 -0.0115188640 0.0865843669 196 1305031108.6753749847 0.0753505081 0.0449419310 0.0857073665 0.0166180030 0.0036260000 16186021 955859216 1373700096 0.2004828304 -0.0074077738 0.0883404016 197 1305031108.7114109993 0.0796161368 0.0451179422 0.0857073665 0.0166287851 0.0036080000 16188949 955859216 1373700096 0.2096218765 -0.0047554416 0.0897860378 198 1305031108.7435019016 0.0818078965 0.0453032450 0.0857073665 0.0166032308 0.0038540000 16191877 955859216 1373700096 0.2174537033 -0.0059796944 0.0906080231 199 1305031108.7754929066 0.0824696943 0.0454900111 0.0857073665 0.0165636510 0.0036610000 16194693 955859216 1373700096 0.2254173160 -0.0061489474 0.0910337642 200 1305031108.8112440109 0.0835286379 0.0456802042 0.0857073665 0.0165247992 0.0036310000 16197677 955859216 1373700096 0.2334897965 -0.0047524930 0.0910826847 201 1305031108.8432641029 0.0840281546 0.0458709900 0.0857073665 0.0179492128 0.0036570000 16200605 955859216 1373700096 0.2408004850 -0.0054795044 0.0900196806 202 1305031108.8765149117 0.0771170631 0.0460256735 0.0857073665 0.0179806539 0.0036240000 16203477 955859216 1373700096 0.2479342073 -0.0059491037 0.0880797878 203 1305031108.9113640785 0.0719679296 0.0461534679 0.0857073665 0.0180666447 0.0035770000 16206405 955859216 1373700096 0.2532701492 -0.0060134120 0.0856497735 204 1305031108.9432430267 0.0706651360 0.0462736231 0.0857073665 0.0181309970 0.0036030000 16209333 955859216 1373700096 0.2557668090 -0.0095855808 0.0825111046 205 1305031108.9752678871 0.0692205280 0.0463855593 0.0857073665 0.0181106363 0.0034610000 16212205 955859216 1373700096 0.2544827461 -0.0103421789 0.0800264254 206 1305031109.0112690926 0.0618862733 0.0464608054 0.0857073665 0.0180856183 0.0037380000 16215133 955859216 1373700096 0.2545354366 -0.0052890545 0.0780592859 207 1305031109.0432770252 0.0595268235 0.0465239263 0.0857073665 0.0180631229 0.0034910000 16218061 955859216 1373700096 0.2511059344 -0.0074864281 0.0761575326 208 1305031109.0754098892 0.0583756790 0.0465809059 0.0857073665 0.0180569517 0.0035090000 16220877 955859216 1373700096 0.2451946288 -0.0080107665 0.0749072209 209 1305031109.1112821102 0.0530918874 0.0466120589 0.0857073665 0.0180314810 0.0037320000 16223861 955859216 1373700096 0.2381628156 -0.0042661498 0.0746958777 210 1305031109.1433339119 0.0505033210 0.0466305887 0.0857073665 0.0180094782 0.0035560000 16226789 955859216 1373700096 0.2316445559 -0.0073709865 0.0737238377 211 1305031109.1754639149 0.0489094779 0.0466413892 0.0857073665 0.0180193201 0.0036900000 16229605 955859216 1373700096 0.2233882099 -0.0091151800 0.0729556754 212 1305031109.2113790512 0.0418524854 0.0466188000 0.0857073665 0.0180257846 0.0036860000 16232589 955859216 1373700096 0.2152932435 -0.0052924096 0.0735357329 213 1305031109.2432899475 0.0376263671 0.0465765820 0.0857073665 0.0179911165 0.0036130000 16235517 955859216 1373700096 0.2075323313 -0.0028756780 0.0752206147 214 1305031109.2753078938 0.0371400006 0.0465324858 0.0857073665 0.0181063618 0.0037160000 16238333 955859216 1373700096 0.1973576844 -0.0069670868 0.0754757226 215 1305031109.3113288879 0.0341405310 0.0464748488 0.0857073665 0.0181733319 0.0036920000 16241317 955859216 1373700096 0.1865824014 -0.0130814062 0.0746860355 216 1305031109.3432478905 0.0300550666 0.0463988313 0.0857073665 0.0182057874 0.0037480000 16244245 955859216 1373700096 0.1759494543 -0.0093376273 0.0751471445 217 1305031109.3753969669 0.0282013100 0.0463149718 0.0857073665 0.0181729340 0.0037750000 16247061 955859216 1373700096 0.1642241329 -0.0083259707 0.0761962160 218 1305031109.4113290310 0.0251161195 0.0462177293 0.0857073665 0.0181334476 0.0037530000 16250045 955859216 1373700096 0.1526266932 -0.0112888226 0.0762576908 219 1305031109.4433019161 0.0232763216 0.0461129740 0.0857073665 0.0181156611 0.0037050000 16252917 955859216 1373700096 0.1410246938 -0.0094718589 0.0766879097 220 1305031109.4753630161 0.0236388482 0.0460108189 0.0857073665 0.0181048619 0.0038230000 16255733 955859216 1373700096 0.1281546801 -0.0098219644 0.0766014904 221 1305031109.5112729073 0.0240493082 0.0459114456 0.0857073665 0.0180871179 0.0037630000 16258717 955859216 1373700096 0.1145010367 -0.0131510552 0.0755321309 222 1305031109.5432939529 0.0260405578 0.0458219371 0.0857073665 0.0180667718 0.0037730000 16261645 955859216 1373700096 0.1008078828 -0.0157583859 0.0736537054 223 1305031109.5753619671 0.0245426912 0.0457265144 0.0857073665 0.0180289140 0.0037700000 16264517 955859216 1373700096 0.0890595838 -0.0142613100 0.0718059018 224 1305031109.6113100052 0.0217594840 0.0456195188 0.0857073665 0.0180137607 0.0037890000 16267445 955859216 1373700096 0.0766794160 -0.0124291759 0.0700457618 225 1305031109.6432290077 0.0218140762 0.0455137168 0.0857073665 0.0179745421 0.0039700000 16270373 955859216 1373700096 0.0649008751 -0.0117359534 0.0686322525 226 1305031109.6752629280 0.0202700105 0.0454020190 0.0857073665 0.0179372296 0.0038220000 16273189 955859216 1373700096 0.0545881242 -0.0097470209 0.0679290220 227 1305031109.7113120556 0.0190550536 0.0452859531 0.0857073665 0.0179582938 0.0037870000 16276173 955859216 1373700096 0.0429501384 -0.0083543593 0.0677984059 228 1305031109.7432739735 0.0188525673 0.0451700171 0.0857073665 0.0179194265 0.0039300000 16279101 955859216 1373700096 0.0305910110 -0.0052318792 0.0685314015 229 1305031109.7752768993 0.0199565049 0.0450599145 0.0857073665 0.0179035674 0.0037980000 16281917 955859216 1373700096 0.0195412841 -0.0064426409 0.0695784464 230 1305031109.8113710880 0.0200700816 0.0449512630 0.0857073665 0.0178748630 0.0037890000 16284901 955859216 1373700096 0.0066712815 -0.0066647800 0.0705735907 231 1305031109.8432960510 0.0202438980 0.0448443047 0.0857073665 0.0178426994 0.0039280000 16287829 955859216 1373700096 -0.0055315169 -0.0046233586 0.0721106082 232 1305031109.8753058910 0.0210101679 0.0447415714 0.0857073665 0.0178131463 0.0038980000 16290645 955859216 1373700096 -0.0184891652 -0.0037970520 0.0745694786 233 1305031109.9112648964 0.0234070625 0.0446500070 0.0857073665 0.0177941143 0.0038880000 16293629 955859216 1373700096 -0.0297601148 -0.0049923128 0.0770873502 234 1305031109.9432990551 0.0251565129 0.0445667014 0.0857073665 0.0177885138 0.0039390000 16296557 955859216 1373700096 -0.0436331481 -0.0046935794 0.0803149194 235 1305031109.9752581120 0.0257096849 0.0444864588 0.0857073665 0.0177550482 0.0039470000 16299373 955859216 1373700096 -0.0542334467 -0.0002987453 0.0837698504 236 1305031110.0112559795 0.0288214944 0.0444200819 0.0857073665 0.0177211926 0.0039330000 16302357 955859216 1373700096 -0.0680017471 -0.0020523597 0.0872060955 237 1305031110.0432989597 0.0296713877 0.0443578511 0.0857073665 0.0176851324 0.0039450000 16305285 955859216 1373700096 -0.0820782706 -0.0014363810 0.0906679034 238 1305031110.0753190517 0.0312153380 0.0443026304 0.0857073665 0.0176603965 0.0038850000 16308101 955859216 1373700096 -0.0952071995 -0.0017298508 0.0942049772 239 1305031110.1113250256 0.0329642519 0.0442551895 0.0857073665 0.0176766122 0.0038920000 16311085 955859216 1373700096 -0.1083385870 -0.0004329510 0.0977663845 240 1305031110.1434319019 0.0358473659 0.0442201569 0.0857073665 0.0177047541 0.0038970000 16314013 955859216 1373700096 -0.1214237288 -0.0038558922 0.1013546437 241 1305031110.1756410599 0.0381853692 0.0441951163 0.0857073665 0.0176684120 0.0038240000 16316829 955859216 1373700096 -0.1311796457 -0.0047851088 0.1042583287 242 1305031110.2116370201 0.0408402011 0.0441812530 0.0857073665 0.0176408777 0.0037980000 16319869 955859216 1373700096 -0.1404007822 -0.0025985800 0.1069642082 243 1305031110.2433230877 0.0443111882 0.0441817877 0.0857073665 0.0176422246 0.0038390000 16322741 955859216 1373700096 -0.1507659405 -0.0063846637 0.1095585674 244 1305031110.2793209553 0.0480991229 0.0441978424 0.0857073665 0.0176274553 0.0037460000 16325725 955859216 1373700096 -0.1585047692 -0.0079701450 0.1107219309 245 1305031110.3114039898 0.0485002398 0.0442154032 0.0857073665 0.0175929871 0.0038670000 16328541 955859216 1373700096 -0.1684763134 -0.0075827274 0.1112367958 246 1305031110.3433549404 0.0502907522 0.0442400997 0.0857073665 0.0175629827 0.0037360000 16331413 955859216 1373700096 -0.1762430966 -0.0069699031 0.1117631122 247 1305031110.3792810440 0.0517056361 0.0442703246 0.0857073665 0.0175560692 0.0039050000 16334397 955859216 1373700096 -0.1875482351 -0.0047095791 0.1119803265 248 1305031110.4114689827 0.0531259254 0.0443060326 0.0857073665 0.0175388096 0.0039600000 16337269 955859216 1373700096 -0.1981745809 -0.0039344658 0.1126919389 249 1305031110.4432599545 0.0542669073 0.0443460362 0.0857073665 0.0175081851 0.0039950000 16340141 955859216 1373700096 -0.2080834955 0.0005497865 0.1137409285 250 1305031110.4793310165 0.0583158173 0.0444019153 0.0857073665 0.0175397938 0.0040300000 16343181 955859216 1373700096 -0.2195636630 0.0001395809 0.1152025089 251 1305031110.5114290714 0.0615398921 0.0444701941 0.0857073665 0.0175221841 0.0039910000 16345997 955859216 1373700096 -0.2299609929 -0.0026612910 0.1172280759 252 1305031110.5434079170 0.0629984513 0.0445437189 0.0857073665 0.0174984098 0.0040100000 16348925 955859216 1373700096 -0.2402565479 -0.0010277138 0.1184534952 253 1305031110.5794260502 0.0656432584 0.0446271163 0.0857073665 0.0174962775 0.0040490000 16351909 955859216 1373700096 -0.2508191168 0.0021992850 0.1201410070 254 1305031110.6113069057 0.0674872771 0.0447171169 0.0857073665 0.0175153465 0.0040520000 16354725 955859216 1373700096 -0.2615933120 0.0020223090 0.1223288104 255 1305031110.6434180737 0.0708598420 0.0448196374 0.0857073665 0.0175414469 0.0040330000 16357653 955859216 1373700096 -0.2703225911 -0.0034759562 0.1244668663 256 1305031110.6796059608 0.0725273862 0.0449278708 0.0857073665 0.0175510708 0.0039050000 16360581 955859216 1373700096 -0.2774080336 -0.0029896614 0.1246505231 257 1305031110.7114119530 0.0726873055 0.0450358842 0.0857073665 0.0175210612 0.0039300000 16388029 955859216 1373700096 -0.2839328945 -0.0000814054 0.1252506971 258 1305031110.7432489395 0.0730775371 0.0451445728 0.0857073665 0.0175284364 0.0039080000 16442101 955859216 1373700096 -0.2909064293 -0.0019878517 0.1260474473 259 1305031110.7791929245 0.0738399401 0.0452553657 0.0857073665 0.0174958151 0.0038650000 16445085 955859216 1373700096 -0.2973671854 -0.0039080884 0.1265568137 260 1305031110.8113861084 0.0738354623 0.0453652891 0.0857073665 0.0174633450 0.0038790000 16447957 955859216 1373700096 -0.3002919555 -0.0029838597 0.1268709898 261 1305031110.8432180882 0.0729314387 0.0454709066 0.0857073665 0.0174413446 0.0038200000 16450829 955859216 1373700096 -0.3045014143 -0.0023756332 0.1271551549 262 1305031110.8793129921 0.0729766637 0.0455758904 0.0857073665 0.0174093129 0.0038450000 16453813 955859216 1373700096 -0.3073400557 -0.0044804132 0.1275049150 263 1305031110.9113330841 0.0731055066 0.0456805657 0.0857073665 0.0173904263 0.0038900000 16456685 955859216 1373700096 -0.3079063892 -0.0043333909 0.1283510625 264 1305031110.9438619614 0.0726020485 0.0457825410 0.0857073665 0.0173793020 0.0038770000 16459613 955859216 1373700096 -0.3081548512 -0.0048231254 0.1288920194 265 1305031110.9793450832 0.0715156719 0.0458796472 0.0857073665 0.0174074116 0.0038870000 16462485 955859216 1373700096 -0.3058114350 -0.0039189928 0.1293859482 266 1305031111.0114309788 0.0695327595 0.0459685687 0.0857073665 0.0174014397 0.0039040000 16465413 955859216 1373700096 -0.3007145822 -0.0009589731 0.1291788220 267 1305031111.0433270931 0.0697845444 0.0460577671 0.0857073665 0.0173702700 0.0039500000 16468285 955859216 1373700096 -0.2934105992 -0.0018773940 0.1293407530 268 1305031111.0792829990 0.0684042573 0.0461411495 0.0857073665 0.0173593193 0.0039160000 16471213 955859216 1373700096 -0.2847408652 -0.0009091200 0.1292795390 269 1305031111.1115078926 0.0680749342 0.0462226877 0.0857073665 0.0173381185 0.0039640000 16474141 955859216 1373700096 -0.2784453630 -0.0014348449 0.1295707673 270 1305031111.1432569027 0.0681392029 0.0463038600 0.0857073665 0.0173197106 0.0040190000 16477013 955859216 1373700096 -0.2705025375 -0.0031557865 0.1293276995 271 1305031111.1793260574 0.0670691878 0.0463804848 0.0857073665 0.0173769616 0.0042060000 16479997 955859216 1373700096 -0.2559451461 -0.0029683365 0.1286505759 272 1305031111.2114329338 0.0646590367 0.0464476854 0.0857073665 0.0173617662 0.0041010000 16482813 955859216 1373700096 -0.2445420772 -0.0012211724 0.1268450916 273 1305031111.2432360649 0.0631955564 0.0465090329 0.0857073665 0.0173964456 0.0026110000 16485685 955859216 1373700096 -0.2363828719 -0.0013373046 0.1262958050 274 1305031111.2793080807 0.0614285879 0.0465634838 0.0857073665 0.0174374391 0.0039590000 16488669 955859216 1373700096 -0.2308548540 -0.0046647675 0.1252919436 275 1305031111.3115470409 0.0590093844 0.0466087416 0.0857073665 0.0174443731 0.0042550000 16491541 955859216 1373700096 -0.2151736319 -0.0031821539 0.1238885894 276 1305031111.3433969021 0.0565413721 0.0466447294 0.0857073665 0.0175847155 0.0040620000 16494413 955859216 1373700096 -0.2095813453 -0.0004004399 0.1239843816 277 1305031111.3791339397 0.0563778318 0.0466798670 0.0857073665 0.0176946069 0.0039480000 16497397 955859216 1373700096 -0.2029553801 -0.0027343605 0.1238615960 278 1305031111.4112958908 0.0577427670 0.0467196616 0.0857073665 0.0176680794 0.0043300000 16500213 955859216 1373700096 -0.1823765785 -0.0064408309 0.1247299612 279 1305031111.4433860779 0.0538624264 0.0467452629 0.0857073665 0.0176597340 0.0041630000 16503141 955859216 1373700096 -0.1730465889 -0.0021554385 0.1239071861 280 1305031111.4792590141 0.0534974001 0.0467693777 0.0857073665 0.0181051605 0.0041990000 16506125 955859216 1373700096 -0.1568338573 -0.0041620117 0.1240627766 281 1305031111.5112640858 0.0509527624 0.0467842652 0.0857073665 0.0181047387 0.0041020000 16508941 955859216 1373700096 -0.1429828703 -0.0043814727 0.1219807565 282 1305031111.5432500839 0.0496451296 0.0467944101 0.0857073665 0.0180842574 0.0040150000 16511869 955859216 1373700096 -0.1352693886 -0.0058431928 0.1202293262 283 1305031111.5792369843 0.0473389551 0.0467963343 0.0857073665 0.0181057923 0.0044510000 16514853 955859216 1373700096 -0.1187008917 -0.0063801678 0.1182838455 284 1305031111.6112709045 0.0443365909 0.0467876732 0.0857073665 0.0181879568 0.0043030000 16517613 955859216 1373700096 -0.1077271476 -0.0035431022 0.1170736551 285 1305031111.6433949471 0.0474977195 0.0467901646 0.0857073665 0.0182043574 0.0039910000 16520541 955859216 1373700096 -0.1005033702 -0.0078326324 0.1168356165 286 1305031111.6793200970 0.0453188531 0.0467850201 0.0857073665 0.0184227229 0.0041760000 16523469 955859216 1373700096 -0.0787053630 -0.0093209706 0.1157294959 287 1305031111.7117600441 0.0388095081 0.0467572309 0.0857073665 0.0184425154 0.0042580000 16526397 955859216 1373700096 -0.0637150630 -0.0025304442 0.1140273586 288 1305031111.7433860302 0.0391490720 0.0467308137 0.0857073665 0.0185241298 0.0042200000 16529269 955859216 1373700096 -0.0502132624 -0.0053106379 0.1130896658 289 1305031111.7794229984 0.0372685790 0.0466980724 0.0857073665 0.0186170236 0.0041730000 16532253 955859216 1373700096 -0.0348526761 -0.0038220852 0.1118563116 290 1305031111.8114058971 0.0383018628 0.0466691199 0.0857073665 0.0186435286 0.0039520000 16535069 955859216 1373700096 -0.0280400384 -0.0028253540 0.1106023714 291 1305031111.8432989120 0.0417196713 0.0466521115 0.0857073665 0.0186249634 0.0038750000 16537941 955859216 1373700096 -0.0216465257 -0.0030976264 0.1091476306 292 1305031111.8794419765 0.0404938795 0.0466310217 0.0857073665 0.0186155672 0.0041080000 16540869 955859216 1373700096 -0.0076038674 0.0015596375 0.1087140292 293 1305031111.9113540649 0.0438180901 0.0466214212 0.0857073665 0.0186379322 0.0039490000 16543797 955859216 1373700096 0.0013907527 -0.0002659227 0.1093370989 294 1305031111.9433000088 0.0456093363 0.0466179788 0.0857073665 0.0186066893 0.0040520000 16546669 955859216 1373700096 0.0134190321 -0.0033030300 0.1098043993 295 1305031111.9794490337 0.0450991802 0.0466128303 0.0857073665 0.0187575280 0.0040660000 16549597 955859216 1373700096 0.0293336324 -0.0017186143 0.1100983992 296 1305031112.0114328861 0.0419014283 0.0465969134 0.0857073665 0.0187802748 0.0041390000 16552525 955859216 1373700096 0.0431234688 0.0007518933 0.1089732498 297 1305031112.0432701111 0.0468357690 0.0465977176 0.0857073665 0.0187497940 0.0039430000 16555397 955859216 1373700096 0.0493404642 -0.0005118059 0.1078174263 298 1305031112.0793390274 0.0505105294 0.0466108479 0.0857073665 0.0187923889 0.0040150000 16558381 955859216 1373700096 0.0601362437 0.0012714979 0.1065423414 299 1305031112.1114230156 0.0543104969 0.0466365992 0.0857073665 0.0188484636 0.0039470000 16561197 955859216 1373700096 0.0675916672 0.0006279954 0.1054161042 300 1305031112.1443419456 0.0568521172 0.0466706509 0.0857073665 0.0188282410 0.0041070000 16564069 955859216 1373700096 0.0768143833 0.0014339905 0.1051057801 301 1305031112.1793899536 0.0621959530 0.0467222300 0.0857073665 0.0189057151 0.0040420000 16566941 955859216 1373700096 0.0875300840 0.0028976412 0.1047801450 302 1305031112.2112538815 0.0674422532 0.0467908394 0.0857073665 0.0189006764 0.0041340000 16569813 955859216 1373700096 0.0961097255 -0.0003447791 0.1047205180 303 1305031112.2433691025 0.0723171532 0.0468750846 0.0857073665 0.0189147104 0.0041160000 16572741 955859216 1373700096 0.1056591272 -0.0066060056 0.1035538688 304 1305031112.2793529034 0.0782298222 0.0469782252 0.0857073665 0.0188982570 0.0041240000 16575669 955859216 1373700096 0.1161141545 -0.0064312862 0.1025361866 305 1305031112.3113119602 0.0792782754 0.0470841270 0.0857073665 0.0188886011 0.0041050000 16578597 955859216 1373700096 0.1272587925 -0.0070652566 0.1014764532 306 1305031112.3433229923 0.0789257213 0.0471881845 0.0857073665 0.0188675948 0.0041290000 16581469 955859216 1373700096 0.1394533515 -0.0073842718 0.1001233831 307 1305031112.3793599606 0.0810723528 0.0472985564 0.0857073665 0.0188431794 0.0042110000 16584509 955859216 1373700096 0.1517843306 -0.0043218140 0.0992487669 308 1305031112.4114420414 0.0794815943 0.0474030468 0.0857073665 0.0188243776 0.0041890000 16587325 955859216 1373700096 0.1642951518 -0.0031426735 0.0988829881 309 1305031112.4433910847 0.0772619769 0.0474996776 0.0857073665 0.0188106951 0.0042880000 16590253 955859216 1373700096 0.1772527546 -0.0031893426 0.0981929675 310 1305031112.4794180393 0.0786133856 0.0476000444 0.0857073665 0.0187938683 0.0043110000 16593237 955859216 1373700096 0.1894856542 -0.0040900498 0.0972242504 311 1305031112.5115039349 0.0756171793 0.0476901317 0.0857073665 0.0187777948 0.0042470000 16596053 955859216 1373700096 0.2013778239 -0.0026851399 0.0963531435 312 1305031112.5432119370 0.0737610757 0.0477736924 0.0857073665 0.0187602239 0.0042200000 16598925 955859216 1373700096 0.2122804224 -0.0034487250 0.0955739543 313 1305031112.5792520046 0.0746334717 0.0478595064 0.0857073665 0.0187323713 0.0044610000 16601853 955859216 1373700096 0.2226216793 -0.0026619546 0.0951768085 314 1305031112.6112608910 0.0724852383 0.0479379323 0.0857073665 0.0187798415 0.0043310000 16604725 955859216 1373700096 0.2328776419 -0.0008931600 0.0949392319 315 1305031112.6432459354 0.0713842362 0.0480123650 0.0857073665 0.0188103287 0.0043270000 16607653 955859216 1373700096 0.2409496009 0.0022692110 0.0952666402 316 1305031112.6799519062 0.0744992420 0.0480961842 0.0857073665 0.0188054394 0.0043050000 16610637 955859216 1373700096 0.2454251796 0.0028437241 0.0955896825 317 1305031112.7112510204 0.0756289139 0.0481830383 0.0857073665 0.0188001021 0.0042630000 16613453 955859216 1373700096 0.2487130165 0.0031804922 0.0963073224 318 1305031112.7432448864 0.0759973302 0.0482705046 0.0857073665 0.0187937151 0.0042040000 16616381 955859216 1373700096 0.2507637143 0.0062023140 0.0978339538 319 1305031112.7793099880 0.0747375712 0.0483534734 0.0857073665 0.0187931301 0.0042300000 16619365 955859216 1373700096 0.2519823909 0.0104460586 0.0999890119 320 1305031112.8113100529 0.0727654919 0.0484297610 0.0857073665 0.0188026163 0.0042140000 16622181 955859216 1373700096 0.2528728545 0.0084300730 0.1008569449 321 1305031112.8432860374 0.0715394840 0.0485017539 0.0857073665 0.0188129035 0.0041470000 16625053 955859216 1373700096 0.2515326440 0.0080089746 0.1024866402 322 1305031112.8794209957 0.0676298812 0.0485611580 0.0857073665 0.0188296291 0.0041720000 16628037 955859216 1373700096 0.2506654561 0.0094603179 0.1041952446 323 1305031112.9114110470 0.0637692362 0.0486082419 0.0857073665 0.0188038705 0.0041240000 16630965 955859216 1373700096 0.2500610948 0.0100265415 0.1051163524 324 1305031112.9433209896 0.0606496781 0.0486454068 0.0857073665 0.0187780210 0.0041580000 16633837 955859216 1373700096 0.2474802136 0.0093733361 0.1055696905 325 1305031112.9792780876 0.0563068911 0.0486689806 0.0857073665 0.0187935362 0.0041900000 16636821 955859216 1373700096 0.2435566187 0.0072303964 0.1056052893 326 1305031113.0113530159 0.0541881286 0.0486859105 0.0857073665 0.0187700062 0.0042440000 16639637 955859216 1373700096 0.2386686802 0.0055947974 0.1054384485 327 1305031113.0432310104 0.0518085659 0.0486954599 0.0857073665 0.0187508549 0.0042800000 16642565 955859216 1373700096 0.2319309562 0.0056990092 0.1053773314 328 1305031113.0792510509 0.0494775288 0.0486978442 0.0857073665 0.0187605224 0.0043290000 16645549 955859216 1373700096 0.2226047814 0.0012858029 0.1043199152 329 1305031113.1113159657 0.0491241962 0.0486991402 0.0857073665 0.0187538554 0.0043360000 16648365 955859216 1373700096 0.2140396833 -0.0033241913 0.1023776680 330 1305031113.1433060169 0.0468652658 0.0486935830 0.0857073665 0.0187379006 0.0044400000 16651293 955859216 1373700096 0.2035664320 -0.0006027999 0.1016008928 331 1305031113.1793429852 0.0417188257 0.0486725112 0.0857073665 0.0187545879 0.0044000000 16654277 955859216 1373700096 0.1936061680 -0.0013802414 0.1006860062 332 1305031113.2112588882 0.0426124856 0.0486542581 0.0857073665 0.0187423210 0.0043600000 16657093 955859216 1373700096 0.1833182275 -0.0070550730 0.0987748727 333 1305031113.2432270050 0.0386791490 0.0486243028 0.0857073665 0.0187389811 0.0044280000 16660021 955859216 1373700096 0.1732327938 -0.0058310032 0.0980761126 334 1305031113.2793118954 0.0329251103 0.0485772992 0.0857073665 0.0187577556 0.0044780000 16662949 955859216 1373700096 0.1619957238 -0.0069551384 0.0978320166 335 1305031113.3114519119 0.0352536663 0.0485375272 0.0857073665 0.0188240834 0.0045380000 16665821 955859216 1373700096 0.1496720165 -0.0146173500 0.0966098160 336 1305031113.3432519436 0.0318132676 0.0484877526 0.0857073665 0.0188359606 0.0044740000 16668693 955859216 1373700096 0.1368922442 -0.0145208538 0.0953777954 337 1305031113.3793120384 0.0204388630 0.0484045215 0.0857073665 0.0188820026 0.0045860000 16671621 955859216 1373700096 0.1239288747 -0.0077983579 0.0971037000 338 1305031113.4116249084 0.0220148470 0.0483264455 0.0857073665 0.0189048111 0.0045350000 16674549 955859216 1373700096 0.1082841158 -0.0121712387 0.0985276848 339 1305031113.4432659149 0.0217607412 0.0482480806 0.0857073665 0.0188878156 0.0044790000 16677421 955859216 1373700096 0.0930199549 -0.0146453660 0.0991553664 340 1305031113.4793109894 0.0167871658 0.0481555485 0.0857073665 0.0189137181 0.0046540000 16680349 955859216 1373700096 0.0758273229 -0.0113763977 0.1013761163 341 1305031113.5115230083 0.0177788176 0.0480664672 0.0857073665 0.0188935844 0.0045850000 16683277 955859216 1373700096 0.0602845959 -0.0128841167 0.1033958867 342 1305031113.5432419777 0.0202348270 0.0479850881 0.0857073665 0.0188866623 0.0046160000 16686149 955859216 1373700096 0.0433822349 -0.0162024405 0.1043246835 343 1305031113.5793011189 0.0204333737 0.0479047624 0.0857073665 0.0188618448 0.0046610000 16689077 955859216 1373700096 0.0258156061 -0.0181678571 0.1047513857 344 1305031113.6112680435 0.0203994419 0.0478248051 0.0857073665 0.0188372862 0.0046990000 16692005 955859216 1373700096 0.0112279272 -0.0161319170 0.1059816554 345 1305031113.6432220936 0.0217303298 0.0477491689 0.0857073665 0.0188147426 0.0045140000 16694877 955859216 1373700096 -0.0014371475 -0.0166601334 0.1066557392 346 1305031113.6792879105 0.0227453038 0.0476769034 0.0857073665 0.0187959338 0.0046100000 16697917 955859216 1373700096 -0.0149778845 -0.0181537047 0.1071052849 347 1305031113.7119309902 0.0240270160 0.0476087481 0.0857073665 0.0187716254 0.0047480000 16700733 955859216 1373700096 -0.0295577217 -0.0184705537 0.1071334481 348 1305031113.7435901165 0.0238855444 0.0475405780 0.0857073665 0.0187461875 0.0047020000 16703661 955859216 1373700096 -0.0432521664 -0.0185151231 0.1073449701 349 1305031113.7793200016 0.0237385426 0.0474723773 0.0857073665 0.0187352443 0.0046810000 16706589 955859216 1373700096 -0.0564932972 -0.0178896952 0.1077345908 350 1305031113.8112370968 0.0249433946 0.0474080088 0.0857073665 0.0187101623 0.0036530000 16709405 955859216 1373700096 -0.0716231987 -0.0184225850 0.1087337062 351 1305031113.8432950974 0.0241694022 0.0473418020 0.0857073665 0.0186947539 0.0046640000 16712333 955859216 1373700096 -0.0846578777 -0.0149541646 0.1095881760 352 1305031113.8792810440 0.0252500307 0.0472790413 0.0857073665 0.0187351751 0.0046790000 16715317 955859216 1373700096 -0.0982956961 -0.0159602817 0.1106369793 353 1305031113.9112899303 0.0273066238 0.0472224622 0.0857073665 0.0187087977 0.0046830000 16718189 955859216 1373700096 -0.1124157757 -0.0182680972 0.1117421314 354 1305031113.9432909489 0.0264951214 0.0471639104 0.0857073665 0.0186934746 0.0047730000 16721061 955859216 1373700096 -0.1237849519 -0.0143942274 0.1122393161 355 1305031113.9792931080 0.0270689819 0.0471073049 0.0857073665 0.0186707227 0.0047330000 16724045 955859216 1373700096 -0.1390660852 -0.0131113036 0.1129454821 356 1305031114.0112569332 0.0270858426 0.0470510649 0.0857073665 0.0186604108 0.0037630000 16726917 955859216 1373700096 -0.1551997066 -0.0113061825 0.1138509884 357 1305031114.0433011055 0.0285963323 0.0469993709 0.0857073665 0.0186653027 0.0037150000 16729789 955859216 1373700096 -0.1712854356 -0.0097992616 0.1154994667 358 1305031114.0792849064 0.0294996016 0.0469504889 0.0857073665 0.0186631385 0.0046740000 16732773 955859216 1373700096 -0.1833657473 -0.0105485506 0.1167336255 359 1305031114.1112630367 0.0308173914 0.0469055499 0.0857073665 0.0186430855 0.0046700000 16735645 955859216 1373700096 -0.1992554963 -0.0085889697 0.1186837777 360 1305031114.1432840824 0.0317043960 0.0468633245 0.0857073665 0.0186218693 0.0047780000 16738573 955859216 1373700096 -0.2100283206 -0.0061658728 0.1204046458 361 1305031114.1793370247 0.0333069079 0.0468257721 0.0857073665 0.0186326840 0.0024000000 16741557 955859216 1373700096 -0.2222710252 -0.0062327641 0.1222714856 362 1305031114.2113029957 0.0341176204 0.0467906667 0.0857073665 0.0186293435 0.0048690000 16744373 955859216 1373700096 -0.2338573039 -0.0043295603 0.1239777580 363 1305031114.2433369160 0.0362562500 0.0467616463 0.0857073665 0.0186414119 0.0047890000 16747245 955859216 1373700096 -0.2516227365 0.0018439715 0.1270697117 364 1305031114.2793900967 0.0370209999 0.0467348862 0.0857073665 0.0186942842 0.0046640000 16750229 955859216 1373700096 -0.2633108795 -0.0007324792 0.1296946853 365 1305031114.3114290237 0.0396412835 0.0467154517 0.0857073665 0.0186744386 0.0047310000 16753101 955859216 1373700096 -0.2735159993 0.0003084018 0.1328872442 366 1305031114.3433310986 0.0421087034 0.0467028650 0.0857073665 0.0186610488 0.0048300000 16756029 955859216 1373700096 -0.2806153893 0.0023771899 0.1352640837 367 1305031114.3793199062 0.0446130186 0.0466971706 0.0857073665 0.0186442406 0.0048920000 16759013 955859216 1373700096 -0.2892388701 0.0030158316 0.1373131871 368 1305031114.4113969803 0.0458331034 0.0466948226 0.0857073665 0.0186278055 0.0047700000 16761885 955859216 1373700096 -0.2991338372 0.0021250348 0.1391199380 369 1305031114.4433450699 0.0468457490 0.0466952316 0.0857073665 0.0186187909 0.0048120000 16764757 955859216 1373700096 -0.3109146059 0.0017477706 0.1413783431 370 1305031114.4793319702 0.0488266759 0.0467009922 0.0857073665 0.0186274597 0.0048520000 16767741 955859216 1373700096 -0.3201074898 0.0002781540 0.1436161846 371 1305031114.5112659931 0.0501299053 0.0467102346 0.0857073665 0.0186055687 0.0050350000 16770557 955859216 1373700096 -0.3287302852 -0.0007761428 0.1465613246 372 1305031114.5432360172 0.0521827340 0.0467249456 0.0857073665 0.0185912340 0.0048860000 16773485 955859216 1373700096 -0.3340949416 0.0002313418 0.1492615938 373 1305031114.5792369843 0.0532363653 0.0467424025 0.0857073665 0.0185724965 0.0049990000 16776469 955859216 1373700096 -0.3393448889 -0.0032622616 0.1511705220 374 1305031114.6113910675 0.0541963391 0.0467623328 0.0857073665 0.0185539727 0.0048030000 16779285 955859216 1373700096 -0.3435502648 -0.0042218878 0.1530413032 375 1305031114.6441500187 0.0554671884 0.0467855458 0.0857073665 0.0185384593 0.0048710000 16782213 955859216 1373700096 -0.3487324119 -0.0036680142 0.1551735252 376 1305031114.6792509556 0.0564548559 0.0468112620 0.0857073665 0.0185318879 0.0049040000 16785085 955859216 1373700096 -0.3554026186 -0.0070782341 0.1570086777 377 1305031114.7113060951 0.0574875697 0.0468395811 0.0857073665 0.0185286579 0.0048760000 16787901 955859216 1373700096 -0.3590588570 -0.0110532772 0.1579124182 378 1305031114.7432758808 0.0588075779 0.0468712425 0.0857073665 0.0185078873 0.0048350000 16790829 955859216 1373700096 -0.3606571853 -0.0130055789 0.1584646702 379 1305031114.7792890072 0.0593355559 0.0469041299 0.0857073665 0.0184904731 0.0048740000 16793813 955859216 1373700096 -0.3617758155 -0.0140323378 0.1583378911 380 1305031114.8113029003 0.0595337749 0.0469373658 0.0857073665 0.0184753675 0.0048500000 16796629 955859216 1373700096 -0.3607466817 -0.0128247356 0.1580336541 381 1305031114.8432080746 0.0597253181 0.0469709299 0.0857073665 0.0184520686 0.0048450000 16799557 955859216 1373700096 -0.3605075479 -0.0125263678 0.1579410583 382 1305031114.8792810440 0.0587782227 0.0470018391 0.0857073665 0.0184278550 0.0048120000 16802485 955859216 1373700096 -0.3592523634 -0.0115645723 0.1573320478 383 1305031114.9128789902 0.0588822775 0.0470328585 0.0857073665 0.0184080149 0.0049390000 16805469 955859216 1373700096 -0.3556379676 -0.0101771681 0.1572982073 384 1305031114.9432640076 0.0582496189 0.0470620688 0.0857073665 0.0183850302 0.0049480000 16808229 955859216 1373700096 -0.3518029153 -0.0072548217 0.1577241272 385 1305031114.9792799950 0.0567187518 0.0470871511 0.0857073665 0.0183660436 0.0049260000 16811213 955859216 1373700096 -0.3458612561 -0.0046500885 0.1575703323 386 1305031115.0113000870 0.0559098981 0.0471100080 0.0857073665 0.0183504116 0.0049870000 16814085 955859216 1373700096 -0.3397484720 -0.0014612288 0.1582717597 387 1305031115.0435299873 0.0550364219 0.0471304897 0.0857073665 0.0183436451 0.0049360000 16817013 955859216 1373700096 -0.3322806656 0.0001933443 0.1590597779 388 1305031115.0792379379 0.0539906062 0.0471481704 0.0857073665 0.0183223888 0.0040910000 16819997 955859216 1373700096 -0.3169664741 0.0001062813 0.1604016423 389 1305031115.1112298965 0.0527004376 0.0471624436 0.0857073665 0.0183157925 0.0038960000 16822813 955859216 1373700096 -0.3090937436 0.0011144491 0.1613934189 390 1305031115.1432940960 0.0510927960 0.0471725214 0.0857073665 0.0183074233 0.0050990000 16825741 955859216 1373700096 -0.2907791436 0.0022978440 0.1620113999 391 1305031115.1794400215 0.0489366241 0.0471770332 0.0857073665 0.0183127419 0.0049400000 16828725 955859216 1373700096 -0.2829154432 0.0014976901 0.1638491750 392 1305031115.2113740444 0.0485915840 0.0471806417 0.0857073665 0.0183113067 0.0049200000 16831541 955859216 1373700096 -0.2746353447 -0.0002352395 0.1657942683 393 1305031115.2432971001 0.0478488170 0.0471823419 0.0857073665 0.0183179880 0.0052660000 16834469 955859216 1373700096 -0.2524346411 -0.0035459769 0.1678659469 394 1305031115.2799661160 0.0447941534 0.0471762805 0.0857073665 0.0183406240 0.0051460000 16837397 955859216 1373700096 -0.2398463041 -0.0008194049 0.1702958643 395 1305031115.3117039204 0.0433973670 0.0471667136 0.0857073665 0.0183621785 0.0051790000 16840325 955859216 1373700096 -0.2245471478 0.0002422823 0.1725740135 396 1305031115.3434259892 0.0426317938 0.0471552618 0.0857073665 0.0183469253 0.0051720000 16843197 955859216 1373700096 -0.2069600224 -0.0020454207 0.1741799414 397 1305031115.3791658878 0.0393405408 0.0471355774 0.0857073665 0.0185803504 0.0040190000 16846069 955859216 1373700096 -0.1960193068 0.0057861563 0.1763410270 398 1305031115.4112370014 0.0446136333 0.0471292408 0.0857073665 0.0185664034 0.0048640000 16848941 955859216 1373700096 -0.1899137795 0.0041006356 0.1804844886 399 1305031115.4431591034 0.0437254310 0.0471207100 0.0857073665 0.0186212351 0.0051940000 16851813 955859216 1373700096 -0.1642068326 0.0021396973 0.1845055372 400 1305031115.4792408943 0.0456060953 0.0471169234 0.0857073665 0.0186038907 0.0051710000 16854797 955859216 1373700096 -0.1468035877 0.0021878993 0.1876131296 401 1305031115.5112531185 0.0474624373 0.0471177851 0.0857073665 0.0186828305 0.0050650000 16857613 955859216 1373700096 -0.1281569600 0.0002077438 0.1898533553 402 1305031115.5436201096 0.0476434939 0.0471190928 0.0857073665 0.0187146457 0.0059000000 16860541 955859216 1373700096 -0.1073514521 -0.0015159304 0.1903468817 403 1305031115.5793149471 0.0484651476 0.0471224329 0.0857073665 0.0186931964 0.0050940000 16863525 955859216 1373700096 -0.0916655362 -0.0016257265 0.1894822121 404 1305031115.6114239693 0.0494299009 0.0471281445 0.0857073665 0.0186731510 0.0051670000 16866341 955859216 1373700096 -0.0769716129 -0.0026359758 0.1886879802 405 1305031115.6432540417 0.0483131818 0.0471310705 0.0857073665 0.0186521633 0.0050830000 16869213 955859216 1373700096 -0.0594269186 -0.0031559647 0.1873196661 406 1305031115.6792409420 0.0511427447 0.0471409514 0.0857073665 0.0186356127 0.0049140000 16872197 955859216 1373700096 -0.0443074591 -0.0041772816 0.1860340983 407 1305031115.7113199234 0.0497108996 0.0471472658 0.0857073665 0.0186545950 0.0049870000 16875069 955859216 1373700096 -0.0266156588 -0.0037467694 0.1845253259 408 1305031115.7432498932 0.0458263494 0.0471440283 0.0857073665 0.0186945389 0.0049310000 16877997 955859216 1373700096 -0.0077674547 -0.0013915085 0.1826166362 409 1305031115.7794249058 0.0484186932 0.0471471448 0.0857073665 0.0186929589 0.0049690000 16880981 955859216 1373700096 0.0078765098 -0.0024769169 0.1806049645 410 1305031115.8112769127 0.0481909141 0.0471496906 0.0857073665 0.0186908256 0.0049640000 16883797 955859216 1373700096 0.0196969341 -0.0006317620 0.1788723916 411 1305031115.8432240486 0.0459128097 0.0471466811 0.0857073665 0.0186815410 0.0049550000 16886725 955859216 1373700096 0.0345641635 0.0025559873 0.1775902212 412 1305031115.8791980743 0.0522158779 0.0471589850 0.0857073665 0.0186732549 0.0047960000 16889597 955859216 1373700096 0.0463361107 -0.0001181489 0.1768338531 413 1305031115.9111180305 0.0542795509 0.0471762261 0.0857073665 0.0186626399 0.0047610000 16892469 955859216 1373700096 0.0568369888 0.0002547289 0.1761574298 414 1305031115.9433109760 0.0514552779 0.0471865620 0.0857073665 0.0186588340 0.0048980000 16895285 955859216 1373700096 0.0702244639 0.0053553451 0.1761436164 415 1305031115.9807400703 0.0564727224 0.0472089383 0.0857073665 0.0186513879 0.0047670000 16898269 955859216 1373700096 0.0806986839 0.0069633322 0.1770191789 416 1305031116.0113790035 0.0564253069 0.0472310930 0.0857073665 0.0186968195 0.0047790000 16901085 955859216 1373700096 0.0924851969 0.0097128414 0.1776482314 417 1305031116.0431640148 0.0577166006 0.0472562381 0.0857073665 0.0186790014 0.0048600000 16904013 955859216 1373700096 0.1020424441 0.0124821365 0.1788382828 418 1305031116.0800299644 0.0638770014 0.0472960007 0.0857073665 0.0186762821 0.0047950000 16906997 955859216 1373700096 0.1108107045 0.0146168973 0.1807401776 419 1305031116.1112999916 0.0649116114 0.0473380427 0.0857073665 0.0186573496 0.0047630000 16909813 955859216 1373700096 0.1209385693 0.0170511473 0.1829596758 420 1305031116.1434469223 0.0682076067 0.0473877322 0.0857073665 0.0186380999 0.0047290000 16912685 955859216 1373700096 0.1301165968 0.0165559445 0.1851593405 421 1305031116.1795721054 0.0733091012 0.0474493031 0.0857073665 0.0186201937 0.0047450000 16915669 955859216 1373700096 0.1397682577 0.0165750962 0.1870025545 422 1305031116.2113199234 0.0742900223 0.0475129067 0.0857073665 0.0186003845 0.0047590000 16918541 955859216 1373700096 0.1491922438 0.0184843130 0.1889059097 423 1305031116.2433199883 0.0753987730 0.0475788307 0.0857073665 0.0185844498 0.0047070000 16921413 955859216 1373700096 0.1592583954 0.0184330810 0.1899426728 424 1305031116.2793850899 0.0798391774 0.0476549165 0.0857073665 0.0185999341 0.0047250000 16924453 955859216 1373700096 0.1677181870 0.0185199324 0.1896459311 425 1305031116.3113360405 0.0811165422 0.0477336497 0.0857073665 0.0185961498 0.0048810000 16927269 955859216 1373700096 0.1750311553 0.0192982070 0.1898106188 426 1305031116.3432919979 0.0811436623 0.0478120770 0.0857073665 0.0185790922 0.0047550000 16930141 955859216 1373700096 0.1823418438 0.0192255359 0.1886320114 427 1305031116.3793840408 0.0831888989 0.0478949267 0.0857073665 0.0185627510 0.0046290000 16933069 955859216 1373700096 0.1875903308 0.0177367385 0.1860370487 428 1305031116.4113330841 0.0826852545 0.0479762125 0.0857073665 0.0185441997 0.0045760000 16935997 955859216 1373700096 0.1928079128 0.0169751998 0.1841133088 429 1305031116.4433689117 0.0788653642 0.0480482152 0.0857073665 0.0185314037 0.0046070000 16938925 955859216 1373700096 0.1979236752 0.0189647842 0.1826211512 430 1305031116.4798500538 0.0750424266 0.0481109924 0.0857073665 0.0185148166 0.0046230000 16941909 955859216 1373700096 0.1997835785 0.0202380829 0.1802404672 431 1305031116.5112049580 0.0738143101 0.0481706289 0.0857073665 0.0184962411 0.0048150000 16944725 955859216 1373700096 0.1979102790 0.0189634152 0.1778693795 432 1305031116.5432620049 0.0727640837 0.0482275582 0.0857073665 0.0184753287 0.0047300000 16947597 955859216 1373700096 0.1940897554 0.0170898363 0.1760856509 433 1305031116.5793130398 0.0668529943 0.0482705730 0.0857073665 0.0184812851 0.0048760000 16950581 955859216 1373700096 0.1886075139 0.0184859205 0.1744442880 434 1305031116.6112608910 0.0637452230 0.0483062289 0.0857073665 0.0184761427 0.0036690000 16953397 955859216 1373700096 0.1813697517 0.0179601442 0.1728243381 435 1305031116.6433548927 0.0612058230 0.0483358831 0.0857073665 0.0184698532 0.0050380000 16956269 955859216 1373700096 0.1721154302 0.0175340530 0.1713846773 436 1305031116.6792809963 0.0558566004 0.0483531325 0.0857073665 0.0184566921 0.0048070000 16959365 955859216 1373700096 0.1621773392 0.0162778161 0.1705684662 437 1305031116.7116339207 0.0550542921 0.0483684669 0.0857073665 0.0184373148 0.0049350000 16962181 955859216 1373700096 0.1497736871 0.0148217827 0.1696383953 438 1305031116.7432909012 0.0551432110 0.0483839344 0.0857073665 0.0184311616 0.0049110000 16965053 955859216 1373700096 0.1356346756 0.0137298396 0.1692102253 439 1305031116.7792980671 0.0526801459 0.0483937208 0.0857073665 0.0184302706 0.0049090000 16968037 955859216 1373700096 0.1212397739 0.0119412830 0.1687263101 440 1305031116.8113429546 0.0541220941 0.0484067398 0.0857073665 0.0184696642 0.0049490000 16970909 955859216 1373700096 0.1063348353 0.0092186918 0.1677146107 441 1305031116.8460888863 0.0516142547 0.0484140131 0.0857073665 0.0185650554 0.0048870000 16973837 955859216 1373700096 0.0918279216 0.0072286404 0.1662193090 442 1305031116.8801651001 0.0498272739 0.0484172105 0.0857073665 0.0185444349 0.0050190000 16976765 955859216 1373700096 0.0784180760 0.0084482590 0.1654082090 443 1305031116.9120440483 0.0506144501 0.0484221704 0.0857073665 0.0185350277 0.0049980000 16979637 955859216 1373700096 0.0644258559 0.0072796242 0.1650870442 444 1305031116.9432959557 0.0482123010 0.0484216977 0.0857073665 0.0185278235 0.0049430000 16982509 955859216 1373700096 0.0504702702 0.0091392053 0.1646541208 445 1305031116.9793510437 0.0473638624 0.0484193206 0.0857073665 0.0185273720 0.0028290000 16985437 955859216 1373700096 0.0347252414 0.0102355061 0.1641742140 446 1305031117.0113821030 0.0477698594 0.0484178644 0.0857073665 0.0185228061 0.0022170000 16988365 955859216 1373700096 0.0197181292 0.0112616075 0.1636855006 447 1305031117.0432610512 0.0466217250 0.0484138462 0.0857073665 0.0185029154 0.0050950000 16991237 955859216 1373700096 0.0043328744 0.0150466356 0.1635476947 448 1305031117.0795199871 0.0473247394 0.0484114151 0.0857073665 0.0185064283 0.0050450000 16994221 955859216 1373700096 -0.0105596483 0.0177464597 0.1641599387 449 1305031117.1112380028 0.0499333702 0.0484148048 0.0857073665 0.0185064265 0.0048480000 16997037 955859216 1373700096 -0.0203046426 0.0178769529 0.1653501689 450 1305031117.1432180405 0.0519376658 0.0484226334 0.0857073665 0.0184888700 0.0048610000 16999965 955859216 1373700096 -0.0300903916 0.0190927349 0.1667815149 451 1305031117.1792640686 0.0516271070 0.0484297386 0.0857073665 0.0184751502 0.0049920000 17002949 955859216 1373700096 -0.0409364998 0.0229331311 0.1678792238 452 1305031117.2113609314 0.0530343316 0.0484399258 0.0857073665 0.0184777416 0.0049140000 17005821 955859216 1373700096 -0.0481381640 0.0231276043 0.1695453823 453 1305031117.2432770729 0.0538673177 0.0484519068 0.0857073665 0.0184744368 0.0048490000 17008693 955859216 1373700096 -0.0529909246 0.0241185166 0.1715912968 454 1305031117.2792990208 0.0539395884 0.0484639942 0.0857073665 0.0184597304 0.0048770000 17011677 955859216 1373700096 -0.0570653863 0.0248553511 0.1733810753 455 1305031117.3111999035 0.0554311387 0.0484793066 0.0857073665 0.0184479111 0.0048160000 17014493 955859216 1373700096 -0.0618406720 0.0231495518 0.1747745574 456 1305031117.3432428837 0.0575642139 0.0484992296 0.0857073665 0.0184376945 0.0049290000 17017421 955859216 1373700096 -0.0658870861 0.0197043940 0.1754976511 457 1305031117.3794538975 0.0583170056 0.0485207127 0.0857073665 0.0184281328 0.0048940000 17020405 955859216 1373700096 -0.0681592077 0.0157930832 0.1755815744 458 1305031117.4112210274 0.0588737428 0.0485433176 0.0857073665 0.0184091235 0.0048750000 17023277 955859216 1373700096 -0.0699444637 0.0116077131 0.1751595140 459 1305031117.4432740211 0.0583832748 0.0485647554 0.0857073665 0.0183902658 0.0049590000 17026149 955859216 1373700096 -0.0710638016 0.0073686363 0.1744203120 460 1305031117.4794030190 0.0550381280 0.0485788280 0.0857073665 0.0183752833 0.0050100000 17029133 955859216 1373700096 -0.0707641244 0.0037887704 0.1735480130 461 1305031117.5113248825 0.0535056628 0.0485895152 0.0857073665 0.0183569759 0.0052840000 17032005 955859216 1373700096 -0.0714406967 -0.0013627268 0.1726151705 462 1305031117.5442850590 0.0512700267 0.0485953172 0.0857073665 0.0183395104 0.0037720000 17034821 955859216 1373700096 -0.0714079365 -0.0063314200 0.1717967987 463 1305031117.5791549683 0.0456716754 0.0485890026 0.0857073665 0.0183214613 0.0049050000 17037861 955859216 1373700096 -0.0719983801 -0.0100200539 0.1715909243 464 1305031117.6111590862 0.0426672213 0.0485762402 0.0857073665 0.0183028492 0.0048610000 17040677 955859216 1373700096 -0.0722149611 -0.0143007813 0.1727916896 465 1305031117.6432840824 0.0410545096 0.0485600644 0.0857073665 0.0182853688 0.0049740000 17043605 955859216 1373700096 -0.0727483407 -0.0203795824 0.1746756881 466 1305031117.6792619228 0.0365251862 0.0485342385 0.0857073665 0.0182705758 0.0050430000 17046589 955859216 1373700096 -0.0728269666 -0.0260426328 0.1773894280 467 1305031117.7112150192 0.0354982279 0.0485063241 0.0857073665 0.0182520532 0.0050670000 17049405 955859216 1373700096 -0.0725951791 -0.0327789150 0.1808497608 468 1305031117.7431840897 0.0373568051 0.0484825004 0.0857073665 0.0182392423 0.0040010000 17052277 955859216 1373700096 -0.0690237954 -0.0440833457 0.1856157482 469 1305031117.7794671059 0.0319015011 0.0484471464 0.0857073665 0.0182198679 0.0038150000 17055261 955859216 1373700096 -0.0702326670 -0.0498110466 0.1887711734 470 1305031117.8113200665 0.0296800509 0.0484072164 0.0857073665 0.0182030261 0.0038460000 17058133 955859216 1373700096 -0.0698389560 -0.0566370077 0.1925743520 471 1305031117.8433070183 0.0328631215 0.0483742141 0.0857073665 0.0181991499 0.0040310000 17060893 955859216 1373700096 -0.0665977821 -0.0695655197 0.1975090206 472 1305031117.8794670105 0.0258397851 0.0483264717 0.0857073665 0.0181823964 0.0038770000 17063877 955859216 1373700096 -0.0680497289 -0.0747484639 0.2005657852 473 1305031117.9114069939 0.0243587364 0.0482757999 0.0857073665 0.0181645388 0.0038850000 17066693 955859216 1373700096 -0.0698436350 -0.0818234086 0.2042950988 474 1305031117.9432721138 0.0266310554 0.0482301359 0.0857073665 0.0181468766 0.0041030000 17069565 955859216 1373700096 -0.0685215890 -0.0930668190 0.2098684758 475 1305031117.9792630672 0.0209577605 0.0481727204 0.0857073665 0.0181413073 0.0038800000 17072549 955859216 1373700096 -0.0709119961 -0.0979173407 0.2141073346 476 1305031118.0112280846 0.0242924429 0.0481225517 0.0857073665 0.0181290564 0.0040400000 17075365 955859216 1373700096 -0.0712063611 -0.1094190106 0.2202260196 477 1305031118.0435490608 0.0266765580 0.0480775916 0.0857073665 0.0181119446 0.0053210000 17078293 955859216 1373700096 -0.0720715225 -0.1200068817 0.2256977409 478 1305031118.0793690681 0.0230279211 0.0480251864 0.0857073665 0.0180955305 0.0051140000 17081277 955859216 1373700096 -0.0736880451 -0.1259961426 0.2300371975 479 1305031118.1112170219 0.0250046309 0.0479771268 0.0857073665 0.0180855925 0.0053560000 17084093 955859216 1373700096 -0.0719782934 -0.1365247965 0.2355458438 480 1305031118.1432559490 0.0262744091 0.0479319128 0.0857073665 0.0180689678 0.0052850000 17087021 955859216 1373700096 -0.0738607720 -0.1449876428 0.2399385720 481 1305031118.1793229580 0.0256725773 0.0478856356 0.0857073665 0.0180520512 0.0039510000 17090005 955859216 1373700096 -0.0753611028 -0.1533142030 0.2440869063 482 1305031118.2112019062 0.0298224110 0.0478481600 0.0857073665 0.0180433948 0.0054020000 17092821 955859216 1373700096 -0.0767555609 -0.1652630270 0.2486553043 483 1305031118.2431728840 0.0305774901 0.0478124029 0.0857073665 0.0180345982 0.0050820000 17095693 955859216 1373700096 -0.0789441839 -0.1722673029 0.2517267764 484 1305031118.2791941166 0.0300588273 0.0477757220 0.0857073665 0.0180368619 0.0051070000 17098677 955859216 1373700096 -0.0798861831 -0.1796810031 0.2548872530 485 1305031118.3112990856 0.0330675431 0.0477453959 0.0857073665 0.0180196624 0.0046790000 17101549 955859216 1373700096 -0.0798707008 -0.1901364028 0.2588172853 486 1305031118.3433239460 0.0323590115 0.0477137366 0.0857073665 0.0180119599 0.0052330000 17104421 955859216 1373700096 -0.0793704763 -0.1948318332 0.2616332173 487 1305031118.3792080879 0.0324613824 0.0476824176 0.0857073665 0.0179954613 0.0053660000 17107405 955859216 1373700096 -0.0816201866 -0.1988172531 0.2649385333 488 1305031118.4112958908 0.0349898040 0.0476564082 0.0857073665 0.0179922713 0.0053500000 17110277 955859216 1373700096 -0.0847892910 -0.2029052377 0.2686113119 489 1305031118.4457030296 0.0338559821 0.0476281865 0.0857073665 0.0179754864 0.0052590000 17113205 955859216 1373700096 -0.0816777050 -0.2050652355 0.2717202008 490 1305031118.4792850018 0.0342962407 0.0476009784 0.0857073665 0.0179576766 0.0053260000 17116077 955859216 1373700096 -0.0812310725 -0.2075245678 0.2750849426 491 1305031118.5112550259 0.0356105492 0.0475765580 0.0857073665 0.0179420412 0.0055440000 17118949 955859216 1373700096 -0.0807725936 -0.2094629407 0.2774151862 492 1305031118.5451989174 0.0351589397 0.0475513189 0.0857073665 0.0179358954 0.0053660000 17121877 955859216 1373700096 -0.0798731968 -0.2078257650 0.2794737220 493 1305031118.5792849064 0.0324588083 0.0475207053 0.0857073665 0.0179179588 0.0042220000 17124861 955859216 1373700096 -0.0749741346 -0.2035475373 0.2799832821 494 1305031118.6161420345 0.0355874524 0.0474965489 0.0857073665 0.0179025515 0.0041150000 17127845 955859216 1373700096 -0.0757456347 -0.2018996179 0.2802215517 495 1305031118.6453309059 0.0321238972 0.0474654931 0.0857073665 0.0178870910 0.0055070000 17130661 955859216 1373700096 -0.0726447552 -0.1958032548 0.2789877653 496 1305031118.6792950630 0.0353584066 0.0474410836 0.0857073665 0.0178740789 0.0053360000 17133645 955859216 1373700096 -0.0733780786 -0.1919397265 0.2783468366 497 1305031118.7114210129 0.0377358794 0.0474215560 0.0857073665 0.0178667397 0.0054840000 17136461 955859216 1373700096 -0.0743905827 -0.1877436936 0.2763647139 498 1305031118.7468008995 0.0433359593 0.0474133520 0.0857073665 0.0178633202 0.0054530000 17139445 955859216 1373700096 -0.0748557672 -0.1839932054 0.2737576067 499 1305031118.7792770863 0.0363625325 0.0473912061 0.0857073665 0.0178946313 0.0043290000 17142373 955859216 1373700096 -0.0730355009 -0.1686903685 0.2701353133 500 1305031118.8112208843 0.0346841365 0.0473657920 0.0857073665 0.0179023952 0.0056430000 17145189 955859216 1373700096 -0.0683199912 -0.1597613990 0.2665473819 501 1305031118.8467741013 0.0437956192 0.0473586659 0.0857073665 0.0179179599 0.0055260000 17148173 955859216 1373700096 -0.0680579320 -0.1573688984 0.2615073919 502 1305031118.8792080879 0.0379428864 0.0473399093 0.0857073665 0.0179692278 0.0056290000 17151101 955859216 1373700096 -0.0667134449 -0.1416165829 0.2548266053 503 1305031118.9111769199 0.0360439979 0.0473174522 0.0857073665 0.0179740807 0.0056820000 17153917 955859216 1373700096 -0.0657717958 -0.1300960034 0.2485995144 504 1305031118.9470090866 0.0416263081 0.0473061603 0.0857073665 0.0179584148 0.0043440000 17156901 955859216 1373700096 -0.0669279173 -0.1219885126 0.2418091744 505 1305031118.9793939590 0.0390392542 0.0472897902 0.0857073665 0.0179535527 0.0036970000 17159829 955859216 1373700096 -0.0677378103 -0.1090981960 0.2350125164 506 1305031119.0113630295 0.0384851359 0.0472723897 0.0857073665 0.0179421736 0.0056480000 17162645 955859216 1373700096 -0.0689087212 -0.0978111625 0.2288005203 507 1305031119.0471799374 0.0442178585 0.0472663650 0.0857073665 0.0179286852 0.0056410000 17165629 955859216 1373700096 -0.0710239634 -0.0896743834 0.2222644836 508 1305031119.0792229176 0.0458635576 0.0472636035 0.0857073665 0.0179161170 0.0056590000 17168445 955859216 1373700096 -0.0729871839 -0.0813216791 0.2156257331 509 1305031119.1113278866 0.0460169204 0.0472611543 0.0857073665 0.0179016946 0.0057210000 17171373 955859216 1373700096 -0.0740987286 -0.0719213858 0.2088835090 510 1305031119.1476290226 0.0486954115 0.0472639665 0.0857073665 0.0178897622 0.0044070000 17174357 955859216 1373700096 -0.0736970529 -0.0617387444 0.2023009062 511 1305031119.1792619228 0.0486299917 0.0472666398 0.0857073665 0.0178837557 0.0057670000 17177229 955859216 1373700096 -0.0743112713 -0.0523999035 0.1958954930 512 1305031119.2113640308 0.0490510948 0.0472701250 0.0857073665 0.0178717102 0.0057750000 17180101 955859216 1373700096 -0.0733783990 -0.0441908948 0.1896500885 513 1305031119.2476599216 0.0501724333 0.0472757825 0.0857073665 0.0178609651 0.0053490000 17232237 955859216 1373700096 -0.0731806904 -0.0326249525 0.1834765971 514 1305031119.2792439461 0.0498420298 0.0472807752 0.0857073665 0.0178459400 0.0053480000 17337509 955859216 1373700096 -0.0739447623 -0.0229285304 0.1781712919 515 1305031119.3112120628 0.0532760397 0.0472924165 0.0857073665 0.0178298431 0.0055570000 17340381 955859216 1373700096 -0.0739332959 -0.0176788792 0.1742236465 516 1305031119.3477499485 0.0545541160 0.0473064896 0.0857073665 0.0178150783 0.0057890000 17343365 955859216 1373700096 -0.0742168128 -0.0065809172 0.1689989865 517 1305031119.3792390823 0.0538434461 0.0473191336 0.0857073665 0.0178036845 0.0044240000 17346237 955859216 1373700096 -0.0735657439 0.0037211007 0.1646677107 518 1305031119.4114921093 0.0538301505 0.0473317031 0.0857073665 0.0177935655 0.0058020000 17349109 955859216 1373700096 -0.0723888800 0.0138915498 0.1607248038 519 1305031119.4477260113 0.0608583018 0.0473577660 0.0857073665 0.0177777163 0.0053140000 17352149 955859216 1373700096 -0.0718907341 0.0195642840 0.1577244252 520 1305031119.4792668819 0.0593937784 0.0473809121 0.0857073665 0.0177649409 0.0044300000 17354909 955859216 1373700096 -0.0742952749 0.0311765019 0.1525908262 521 1305031119.5112578869 0.0591729134 0.0474035455 0.0857073665 0.0177526257 0.0058100000 17357781 955859216 1373700096 -0.0747004971 0.0427284464 0.1488944888 522 1305031119.5474140644 0.0662198365 0.0474395921 0.0857073665 0.0177356600 0.0055460000 17360821 955859216 1373700096 -0.0749320239 0.0485549234 0.1462616622 523 1305031119.5795691013 0.0637021735 0.0474706869 0.0857073665 0.0177345463 0.0044350000 17363693 955859216 1373700096 -0.0754771605 0.0631540120 0.1423876882 524 1305031119.6150240898 0.0678319708 0.0475095443 0.0857073665 0.0177242390 0.0055770000 17366677 955859216 1373700096 -0.0761254728 0.0694838241 0.1406224221 525 1305031119.6488890648 0.0704496354 0.0475532397 0.0857073665 0.0177239058 0.0031680000 17369605 955859216 1373700096 -0.0787160844 0.0816669017 0.1375771761 526 1305031119.6792080402 0.0706128925 0.0475970793 0.0857073665 0.0177158262 0.0025920000 17372365 955859216 1373700096 -0.0795453191 0.0934101343 0.1355401278 527 1305031119.7152490616 0.0753009170 0.0476496483 0.0857073665 0.0177016312 0.0055590000 17375349 955859216 1373700096 -0.0799823105 0.0991588309 0.1350388825 528 1305031119.7471930981 0.0821970925 0.0477150791 0.0857073665 0.0176947542 0.0055860000 17378277 955859216 1373700096 -0.0822661221 0.1040551662 0.1340234727 529 1305031119.7791690826 0.0814928934 0.0477789313 0.0857073665 0.0176802903 0.0057660000 17381149 955859216 1373700096 -0.0843455121 0.1163356155 0.1319885105 530 1305031119.8145709038 0.0865523219 0.0478520886 0.0865523219 0.0176703839 0.0055290000 17384021 955859216 1373700096 -0.0843979120 0.1202332675 0.1315681189 531 1305031119.8474450111 0.0876107216 0.0479269636 0.0876107216 0.0176606722 0.0043630000 17387005 955859216 1373700096 -0.0833459571 0.1330238581 0.1296199113 532 1305031119.8792319298 0.0914669260 0.0480088056 0.0914669260 0.0176545015 0.0055400000 17389821 955859216 1373700096 -0.0848022923 0.1364344358 0.1280645281 533 1305031119.9114239216 0.0890185684 0.0480857470 0.0914669260 0.0176627401 0.0057570000 17392693 955859216 1373700096 -0.0859652981 0.1490076780 0.1251300424 534 1305031119.9474620819 0.0938834324 0.0481715105 0.0938834324 0.0176501376 0.0054880000 17395733 955859216 1373700096 -0.0867829323 0.1534772664 0.1239571348 535 1305031119.9795460701 0.0958706588 0.0482606678 0.0958706588 0.0176366881 0.0055460000 17398605 955859216 1373700096 -0.0878455564 0.1577882916 0.1224506944 536 1305031120.0152831078 0.0969520435 0.0483515099 0.0969520435 0.0176402066 0.0041900000 17401533 955859216 1373700096 -0.0881795660 0.1632899344 0.1214515939 537 1305031120.0473101139 0.0989139229 0.0484456671 0.0989139229 0.0176361989 0.0055770000 17404461 955859216 1373700096 -0.0903301015 0.1676786393 0.1204660609 538 1305031120.0794179440 0.1001919359 0.0485418497 0.1001919359 0.0176343505 0.0041900000 17407333 955859216 1373700096 -0.0926470086 0.1683083922 0.1195188537 539 1305031120.1152489185 0.1000763774 0.0486374611 0.1001919359 0.0176251548 0.0041510000 17410261 955859216 1373700096 -0.0931997970 0.1697182655 0.1190503761 540 1305031120.1481750011 0.0980710313 0.0487290048 0.1001919359 0.0176238491 0.0055420000 17413189 955859216 1373700096 -0.0929928198 0.1708721966 0.1187472492 541 1305031120.1792609692 0.0965753123 0.0488174453 0.1001919359 0.0176143793 0.0055590000 17416005 955859216 1373700096 -0.0925585553 0.1691037118 0.1182618216 542 1305031120.2152600288 0.0946374238 0.0489019840 0.1001919359 0.0175995926 0.0055550000 17418989 955859216 1373700096 -0.0921134949 0.1655996889 0.1176349372 543 1305031120.2480180264 0.0896722004 0.0489770672 0.1001919359 0.0175846445 0.0056080000 17421917 955859216 1373700096 -0.0918583721 0.1630790234 0.1172491163 544 1305031120.2794411182 0.0855000690 0.0490442051 0.1001919359 0.0175691678 0.0042430000 17424789 955859216 1373700096 -0.0931432024 0.1596425176 0.1170878634 545 1305031120.3152129650 0.0814006850 0.0491035748 0.1001919359 0.0175532628 0.0035450000 17427717 955859216 1373700096 -0.0940726250 0.1552360505 0.1175832227 546 1305031120.3477969170 0.0752292871 0.0491514241 0.1001919359 0.0175373994 0.0034960000 17430645 955859216 1373700096 -0.0951128751 0.1493982077 0.1188412309 547 1305031120.3794460297 0.0720847622 0.0491933497 0.1001919359 0.0175219475 0.0035220000 17433517 955859216 1373700096 -0.0951981097 0.1428969353 0.1213727295 548 1305031120.4154899120 0.0759273842 0.0492421345 0.1001919359 0.0175534623 0.0037040000 17436445 955859216 1373700096 -0.0933950841 0.1252901852 0.1262956262 549 1305031120.4474329948 0.0675818175 0.0492755401 0.1001919359 0.0175433885 0.0034790000 17439373 955859216 1373700096 -0.0934255645 0.1204010919 0.1288322061 550 1305031120.4794321060 0.0639765635 0.0493022692 0.1001919359 0.0175276662 0.0039220000 17442245 955859216 1373700096 -0.0920796767 0.1154869571 0.1326810718 551 1305031120.5148770809 0.0618533194 0.0493250479 0.1001919359 0.0175166864 0.0036150000 17445173 955859216 1373700096 -0.0906738415 0.1067074463 0.1365336180 552 1305031120.5478069782 0.0570231117 0.0493389937 0.1001919359 0.0175034140 0.0056760000 17448101 955859216 1373700096 -0.0893415064 0.0984562039 0.1407846957 553 1305031120.5795590878 0.0550391562 0.0493493014 0.1001919359 0.0174924766 0.0055480000 17450973 955859216 1373700096 -0.0870792791 0.0920107141 0.1455998123 554 1305031120.6152710915 0.0550798215 0.0493596453 0.1001919359 0.0174856652 0.0058590000 17453845 955859216 1373700096 -0.0814098939 0.0821637139 0.1510449797 555 1305031120.6473538876 0.0492688306 0.0493594817 0.1001919359 0.0174725942 0.0054980000 17456773 955859216 1373700096 -0.0821959153 0.0758778602 0.1546443701 556 1305031120.6793179512 0.0471036658 0.0493554244 0.1001919359 0.0174808666 0.0055020000 17459589 955859216 1373700096 -0.0803265050 0.0704761371 0.1591184884 557 1305031120.7145531178 0.0451504961 0.0493478752 0.1001919359 0.0174656052 0.0056240000 17462573 955859216 1373700096 -0.0793381780 0.0636093393 0.1635481417 558 1305031120.7473959923 0.0426006839 0.0493357834 0.1001919359 0.0174546643 0.0055500000 17465501 955859216 1373700096 -0.0761982948 0.0535278358 0.1686208546 559 1305031120.7799079418 0.0408599898 0.0493206210 0.1001919359 0.0174422713 0.0042720000 17468429 955859216 1373700096 -0.0762374625 0.0461859107 0.1722436547 560 1305031120.8149440289 0.0399049558 0.0493038073 0.1001919359 0.0174357441 0.0042610000 17471357 955859216 1373700096 -0.0763203278 0.0386321023 0.1760598421 561 1305031120.8479421139 0.0353550948 0.0492789433 0.1001919359 0.0174205533 0.0057300000 17474285 955859216 1373700096 -0.0770901367 0.0325370952 0.1796374172 562 1305031120.8834540844 0.0372797735 0.0492575925 0.1001919359 0.0174131265 0.0060190000 17477213 955859216 1373700096 -0.0762370899 0.0195070393 0.1834444106 563 1305031120.9154539108 0.0348347649 0.0492319747 0.1001919359 0.0174090451 0.0058180000 17480085 955859216 1373700096 -0.0779163688 0.0143362284 0.1862304062 564 1305031120.9475090504 0.0322401077 0.0492018473 0.1001919359 0.0173940676 0.0059160000 17482957 955859216 1373700096 -0.0795069635 0.0056613944 0.1893378049 565 1305031120.9833900928 0.0320860147 0.0491715537 0.1001919359 0.0173816055 0.0044690000 17485941 955859216 1373700096 -0.0805429518 -0.0029397879 0.1924240142 566 1305031121.0150289536 0.0329455957 0.0491428860 0.1001919359 0.0173730539 0.0044890000 17488757 955859216 1373700096 -0.0819070488 -0.0125306221 0.1952031553 567 1305031121.0477550030 0.0285147093 0.0491065047 0.1001919359 0.0173583519 0.0058620000 17491741 955859216 1373700096 -0.0828501433 -0.0180192757 0.1974114925 568 1305031121.0831170082 0.0305687804 0.0490738679 0.1001919359 0.0173481037 0.0060250000 17494669 955859216 1373700096 -0.0843738541 -0.0295465998 0.2002264559 569 1305031121.1148779392 0.0288706236 0.0490383613 0.1001919359 0.0173337722 0.0058660000 17497485 955859216 1373700096 -0.0848324150 -0.0362527035 0.2018769532 570 1305031121.1473550797 0.0254172124 0.0489969207 0.1001919359 0.0173196338 0.0059260000 17500413 955859216 1373700096 -0.0855393708 -0.0431538671 0.2039540708 571 1305031121.1832809448 0.0274291933 0.0489591488 0.1001919359 0.0173045743 0.0047070000 17503397 955859216 1373700096 -0.0875473917 -0.0538844541 0.2066315860 572 1305031121.2114310265 0.0255947262 0.0489183019 0.1001919359 0.0172916564 0.0059770000 17506101 955859216 1373700096 -0.0876651853 -0.0605837628 0.2086448073 573 1305031121.2472009659 0.0225258451 0.0488722418 0.1001919359 0.0172781034 0.0059470000 17509085 955859216 1373700096 -0.0878985897 -0.0671732426 0.2114053071 574 1305031121.2828760147 0.0246487316 0.0488300406 0.1001919359 0.0172632744 0.0062230000 17512069 955859216 1373700096 -0.0901935399 -0.0759983510 0.2148281485 575 1305031121.3135879040 0.0254413746 0.0487893646 0.1001919359 0.0172575826 0.0061700000 17514885 955859216 1373700096 -0.0889901370 -0.0883771107 0.2182342559 576 1305031121.3475399017 0.0244262051 0.0487470675 0.1001919359 0.0172471487 0.0056630000 17517813 955859216 1373700096 -0.0901052058 -0.0956127271 0.2216816843 577 1305031121.3832480907 0.0242886320 0.0487046785 0.1001919359 0.0172403801 0.0044900000 17520797 955859216 1373700096 -0.0908692703 -0.1023111492 0.2246478945 578 1305031121.4143280983 0.0242307503 0.0486623361 0.1001919359 0.0172269750 0.0038200000 17523613 955859216 1373700096 -0.0904311165 -0.1121914163 0.2275132835 579 1305031121.4473190308 0.0248541385 0.0486212166 0.1001919359 0.0172183898 0.0060000000 17526541 955859216 1373700096 -0.0922317430 -0.1177358180 0.2306397408 580 1305031121.4830150604 0.0250461139 0.0485805698 0.1001919359 0.0172177637 0.0060470000 17529469 955859216 1373700096 -0.0921781659 -0.1249498576 0.2332525402 581 1305031121.5141639709 0.0270198118 0.0485434601 0.1001919359 0.0172077018 0.0061520000 17532285 955859216 1373700096 -0.0936828479 -0.1354116797 0.2361649275 582 1305031121.5472700596 0.0285752062 0.0485091504 0.1001919359 0.0172017160 0.0045680000 17535269 955859216 1373700096 -0.0956061780 -0.1406778693 0.2388875037 583 1305031121.5832130909 0.0292804204 0.0484761680 0.1001919359 0.0171898398 0.0061130000 17538253 955859216 1373700096 -0.0965876728 -0.1492960155 0.2418104261 584 1305031121.6147189140 0.0309279207 0.0484461196 0.1001919359 0.0171762977 0.0061400000 17541069 955859216 1373700096 -0.0982368961 -0.1588971466 0.2443380654 585 1305031121.6471829414 0.0312089212 0.0484166543 0.1001919359 0.0171683832 0.0045710000 17543941 955859216 1373700096 -0.0979238600 -0.1643219739 0.2461032867 586 1305031121.6832110882 0.0334155783 0.0483910552 0.1001919359 0.0171599721 0.0061140000 17546981 955859216 1373700096 -0.0998937041 -0.1697039008 0.2490341067 587 1305031121.7145280838 0.0361494981 0.0483702008 0.1001919359 0.0171459478 0.0048080000 17549797 955859216 1373700096 -0.1023696586 -0.1790843010 0.2517215908 588 1305031121.7471449375 0.0360684954 0.0483492795 0.1001919359 0.0171332042 0.0047080000 17552669 955859216 1373700096 -0.1007002145 -0.1874705106 0.2554521263 589 1305031121.7828710079 0.0365363769 0.0483292236 0.1001919359 0.0171192255 0.0060930000 17555653 955859216 1373700096 -0.1000092626 -0.1937702000 0.2589330375 590 1305031121.8115448952 0.0371781588 0.0483103235 0.1001919359 0.0171088059 0.0061250000 17558413 955859216 1373700096 -0.0990829170 -0.1996915787 0.2619746923 591 1305031121.8473351002 0.0373538770 0.0482917847 0.1001919359 0.0170958549 0.0061310000 17561397 955859216 1373700096 -0.0968511254 -0.2042398602 0.2652535439 592 1305031121.8821229935 0.0369082838 0.0482725558 0.1001919359 0.0170814614 0.0047050000 17564325 955859216 1373700096 -0.0953481644 -0.2081795633 0.2679027915 593 1305031121.9149429798 0.0375948846 0.0482545496 0.1001919359 0.0170680270 0.0061840000 17567253 955859216 1373700096 -0.0955550596 -0.2107014656 0.2697176039 594 1305031121.9473180771 0.0392181277 0.0482393368 0.1001919359 0.0170554189 0.0061630000 17570125 955859216 1373700096 -0.0964615867 -0.2125847042 0.2707783282 595 1305031121.9829349518 0.0381434448 0.0482223689 0.1001919359 0.0170418013 0.0046480000 17573109 955859216 1373700096 -0.0950722694 -0.2116065174 0.2713179588 596 1305031122.0144240856 0.0386906937 0.0482063762 0.1001919359 0.0170283733 0.0062080000 17575981 955859216 1373700096 -0.0959347561 -0.2092862576 0.2709598243 597 1305031122.0473060608 0.0406354740 0.0481936946 0.1001919359 0.0170145549 0.0061200000 17578853 955859216 1373700096 -0.0968230739 -0.2068204135 0.2698437572 598 1305031122.0829689503 0.0413728543 0.0481822885 0.1001919359 0.0170004146 0.0061900000 17581837 955859216 1373700096 -0.0972701386 -0.2019827068 0.2678681910 599 1305031122.1146879196 0.0418005511 0.0481716345 0.1001919359 0.0169869891 0.0057390000 17584653 955859216 1373700096 -0.0975682735 -0.1957748830 0.2651032805 600 1305031122.1507480145 0.0387257822 0.0481558914 0.1001919359 0.0169820010 0.0049190000 17587637 955859216 1373700096 -0.0980417803 -0.1797294468 0.2610951662 601 1305031122.1830520630 0.0401961729 0.0481426473 0.1001919359 0.0169805285 0.0062480000 17590565 955859216 1373700096 -0.0969528630 -0.1752357334 0.2578154504 602 1305031122.2149689198 0.0372137129 0.0481244929 0.1001919359 0.0170132026 0.0056850000 17593381 955859216 1373700096 -0.0990915895 -0.1575619131 0.2538661957 603 1305031122.2513549328 0.0409171805 0.0481125405 0.1001919359 0.0170004871 0.0062880000 17596421 955859216 1373700096 -0.0984935164 -0.1511512399 0.2505528927 604 1305031122.2838659286 0.0395381711 0.0480983445 0.1001919359 0.0169923808 0.0049410000 17599349 955859216 1373700096 -0.0985806361 -0.1396995485 0.2453870028 605 1305031122.3143088818 0.0374797173 0.0480807931 0.1001919359 0.0170116623 0.0064560000 17602109 955859216 1373700096 -0.1003338248 -0.1237166598 0.2415827960 606 1305031122.3513510227 0.0425260104 0.0480716268 0.1001919359 0.0170050888 0.0062670000 17605093 955859216 1373700096 -0.0995623246 -0.1185247302 0.2375018746 607 1305031122.3826780319 0.0398978554 0.0480581609 0.1001919359 0.0169949232 0.0048760000 17608021 955859216 1373700096 -0.0962893665 -0.1081474423 0.2320211679 608 1305031122.4150080681 0.0429834165 0.0480498143 0.1001919359 0.0169934206 0.0040210000 17610781 955859216 1373700096 -0.0950743333 -0.1033595353 0.2269472033 609 1305031122.4512720108 0.0440468229 0.0480432412 0.1001919359 0.0169823532 0.0041660000 17613821 955859216 1373700096 -0.0930532441 -0.0924515948 0.2208050042 610 1305031122.4833879471 0.0425372608 0.0480342150 0.1001919359 0.0169713167 0.0041770000 17616693 955859216 1373700096 -0.0904271007 -0.0825474635 0.2152677923 611 1305031122.5151350498 0.0425459780 0.0480252327 0.1001919359 0.0169641451 0.0064640000 17619565 955859216 1373700096 -0.0879769698 -0.0739837140 0.2099635303 612 1305031122.5515100956 0.0452291295 0.0480206639 0.1001919359 0.0169566316 0.0064940000 17622549 955859216 1373700096 -0.0865316465 -0.0636093542 0.2044765949 613 1305031122.5832169056 0.0461375117 0.0480175918 0.1001919359 0.0169437853 0.0065040000 17625421 955859216 1373700096 -0.0872986466 -0.0545868501 0.1991368830 614 1305031122.6150169373 0.0505313948 0.0480216860 0.1001919359 0.0169362674 0.0054680000 17628237 955859216 1373700096 -0.0884246901 -0.0499853380 0.1945798099 615 1305031122.6488099098 0.0524847209 0.0480289429 0.1001919359 0.0169229653 0.0041770000 17631221 955859216 1373700096 -0.0886547714 -0.0386845879 0.1884474456 616 1305031122.6834199429 0.0519309305 0.0480352773 0.1001919359 0.0169094572 0.0064710000 17634149 955859216 1373700096 -0.0884654894 -0.0276615322 0.1833612919 617 1305031122.7152190208 0.0527778231 0.0480429638 0.1001919359 0.0168977729 0.0064970000 17636965 955859216 1373700096 -0.0879644006 -0.0183379687 0.1791160405 618 1305031122.7513089180 0.0554867610 0.0480550088 0.1001919359 0.0168932008 0.0049300000 17640005 955859216 1373700096 -0.0872018114 -0.0066610230 0.1751017272 619 1305031122.7834379673 0.0538411736 0.0480643564 0.1001919359 0.0168844137 0.0041660000 17642877 955859216 1373700096 -0.0862271637 0.0065546869 0.1718102396 620 1305031122.8125650883 0.0579556413 0.0480803101 0.1001919359 0.0168726116 0.0062740000 17645693 955859216 1373700096 -0.0873955712 0.0124702249 0.1698870063 621 1305031122.8514859676 0.0630922318 0.0481044839 0.1001919359 0.0168724790 0.0062620000 17648733 955859216 1373700096 -0.0873159245 0.0191194657 0.1674585640 622 1305031122.8837749958 0.0611667037 0.0481254842 0.1001919359 0.0168655432 0.0059240000 17651661 955859216 1373700096 -0.0889297426 0.0315513611 0.1640004963 623 1305031122.9145851135 0.0654294342 0.0481532594 0.1001919359 0.0168583092 0.0046670000 17654421 955859216 1373700096 -0.0908328146 0.0352701060 0.1620360315 624 1305031122.9514129162 0.0709205568 0.0481897455 0.1001919359 0.0168463900 0.0061880000 17657461 955859216 1373700096 -0.0923451781 0.0400764421 0.1596898735 625 1305031122.9830000401 0.0692744553 0.0482234810 0.1001919359 0.0168379430 0.0055660000 17660333 955859216 1373700096 -0.0934186354 0.0508691072 0.1565091610 626 1305031123.0154619217 0.0727814063 0.0482627109 0.1001919359 0.0168251364 0.0062560000 17663149 955859216 1373700096 -0.0933654010 0.0549142696 0.1546044350 627 1305031123.0518379211 0.0773265511 0.0483090647 0.1001919359 0.0168168540 0.0046840000 17666189 955859216 1373700096 -0.0921833441 0.0601284765 0.1519256085 628 1305031123.0829920769 0.0747363940 0.0483511465 0.1001919359 0.0168079394 0.0070130000 17669061 955859216 1373700096 -0.0925344303 0.0720388368 0.1480525881 629 1305031123.1139390469 0.0738587379 0.0483916991 0.1001919359 0.0168022458 0.0057630000 17671821 955859216 1373700096 -0.0925211385 0.0827326030 0.1455870271 630 1305031123.1508400440 0.0802883580 0.0484423287 0.1001919359 0.0167894143 0.0039500000 17674861 955859216 1373700096 -0.0930898041 0.0869470462 0.1445841938 631 1305031123.1821761131 0.0799536258 0.0484922673 0.1001919359 0.0167872960 0.0065060000 17677733 955859216 1373700096 -0.0932435766 0.0982796773 0.1424754560 632 1305031123.2147240639 0.0800541192 0.0485422070 0.1001919359 0.0167775457 0.0028640000 17680605 955859216 1373700096 -0.0924819708 0.1095201746 0.1411934197 633 1305031123.2506411076 0.0873838514 0.0486035682 0.1001919359 0.0167817662 0.0025620000 17683589 955859216 1373700096 -0.0932990834 0.1150581688 0.1414406151 634 1305031123.2823629379 0.0882640108 0.0486661241 0.1001919359 0.0167710623 0.0027340000 17686461 955859216 1373700096 -0.0945791602 0.1263318211 0.1409271508 635 1305031123.3209919930 0.0958899856 0.0487404924 0.1001919359 0.0167620413 0.0062630000 17689501 955859216 1373700096 -0.0957123339 0.1306312531 0.1411182880 636 1305031123.3504929543 0.0996286348 0.0488205052 0.1001919359 0.0167517625 0.0062430000 17692317 955859216 1373700096 -0.0954839066 0.1365891248 0.1411941797 637 1305031123.3822629452 0.0978609994 0.0488974918 0.1001919359 0.0167406471 0.0064770000 17695189 955859216 1373700096 -0.0944585502 0.1493702382 0.1392624527 638 1305031123.4213430882 0.1053221077 0.0489859317 0.1053221077 0.0167291222 0.0059870000 17698229 955859216 1373700096 -0.0953097865 0.1524438709 0.1389295906 639 1305031123.4512660503 0.1095976606 0.0490807857 0.1095976606 0.0167215819 0.0062830000 17700989 955859216 1373700096 -0.0954910517 0.1564711928 0.1385538280 640 1305031123.4836049080 0.1130970493 0.0491808111 0.1130970493 0.0167108839 0.0042270000 17703917 955859216 1373700096 -0.0957980901 0.1616083980 0.1379824579 641 1305031123.5197250843 0.1186918020 0.0492892526 0.1186918020 0.0166998031 0.0038310000 17706845 955859216 1373700096 -0.0960724801 0.1663038135 0.1374273598 642 1305031123.5515730381 0.1215117797 0.0494017488 0.1215117797 0.0166872123 0.0062090000 17709773 955859216 1373700096 -0.0959029868 0.1710086912 0.1365620643 643 1305031123.5796160698 0.1133735701 0.0495012384 0.1215117797 0.0166819091 0.0065090000 17712477 955859216 1373700096 -0.0916281566 0.1892388165 0.1326562166 644 1305031123.6203870773 0.1200279072 0.0496107518 0.1215117797 0.0166734639 0.0061750000 17715573 955859216 1373700096 -0.0926054418 0.1912060678 0.1327104867 645 1305031123.6524300575 0.1228357852 0.0497242790 0.1228357852 0.0166621406 0.0045480000 17718445 955859216 1373700096 -0.0920434818 0.1954694688 0.1325352788 646 1305031123.6837849617 0.1250741631 0.0498409197 0.1250741631 0.0166493987 0.0061210000 17721317 955859216 1373700096 -0.0908295289 0.1998935491 0.1323657185 647 1305031123.7199749947 0.1284877360 0.0499624758 0.1284877360 0.0166369168 0.0061470000 17724301 955859216 1373700096 -0.0901717544 0.2042687982 0.1319906861 648 1305031123.7519800663 0.1293056011 0.0500849189 0.1293056011 0.0166302448 0.0061080000 17727173 955859216 1373700096 -0.0896417573 0.2076148987 0.1312724650 649 1305031123.7841379642 0.1294490248 0.0502072057 0.1294490248 0.0166218084 0.0060630000 17729989 955859216 1373700096 -0.0889784619 0.2099602818 0.1304185688 650 1305031123.8196959496 0.1291503757 0.0503286567 0.1294490248 0.0166103276 0.0044800000 17733029 955859216 1373700096 -0.0875550285 0.2121911943 0.1294471025 651 1305031123.8515510559 0.1276719868 0.0504474637 0.1294490248 0.0165978068 0.0037220000 17735901 955859216 1373700096 -0.0864168108 0.2135050148 0.1284201294 652 1305031123.8838191032 0.1265920103 0.0505642498 0.1294490248 0.0165873748 0.0060910000 17738773 955859216 1373700096 -0.0860627741 0.2133366168 0.1277946085 653 1305031123.9157938957 0.1240408272 0.0506767713 0.1294490248 0.0165767744 0.0060910000 17741589 955859216 1373700096 -0.0852206945 0.2122289687 0.1269783378 654 1305031123.9515299797 0.1209101155 0.0507841618 0.1294490248 0.0165766188 0.0044830000 17744629 955859216 1373700096 -0.0855821073 0.2117915750 0.1265242398 655 1305031123.9834210873 0.1190682277 0.0508884123 0.1294490248 0.0165718822 0.0061900000 17747501 955859216 1373700096 -0.0871590450 0.2096911073 0.1271217465 656 1305031124.0197370052 0.1157392785 0.0509872703 0.1294490248 0.0165790751 0.0061170000 17750485 955859216 1373700096 -0.0886577144 0.2053030580 0.1281113476 657 1305031124.0515310764 0.1129198447 0.0510815360 0.1294490248 0.0165789856 0.0044820000 17753301 955859216 1373700096 -0.0884184539 0.2019159198 0.1290856749 658 1305031124.0839018822 0.1099676937 0.0511710286 0.1294490248 0.0165692857 0.0041570000 17756173 955859216 1373700096 -0.0890588760 0.1986469030 0.1305581182 659 1305031124.1196689606 0.1055371910 0.0512535266 0.1294490248 0.0165734531 0.0038260000 17759157 955859216 1373700096 -0.0896739513 0.1928064972 0.1325434148 660 1305031124.1474580765 0.1027009562 0.0513314773 0.1294490248 0.0165762061 0.0061300000 17761973 955859216 1373700096 -0.0878064036 0.1886420548 0.1346482784 661 1305031124.1827070713 0.0993994921 0.0514041974 0.1294490248 0.0165667213 0.0061910000 17764901 955859216 1373700096 -0.0875471681 0.1842158884 0.1366183907 662 1305031124.2171790600 0.0951865241 0.0514703339 0.1294490248 0.0165734462 0.0058560000 17767829 955859216 1373700096 -0.0875637606 0.1771733612 0.1387160271 663 1305031124.2493400574 0.0927825347 0.0515326449 0.1294490248 0.0165830696 0.0061390000 17770645 955859216 1373700096 -0.0863424391 0.1709614694 0.1407410949 664 1305031124.2825551033 0.0895497054 0.0515898995 0.1294490248 0.0165712362 0.0061720000 17773573 955859216 1373700096 -0.0866402760 0.1657625884 0.1425052881 665 1305031124.3167819977 0.0855708793 0.0516409987 0.1294490248 0.0165764461 0.0045750000 17776501 955859216 1373700096 -0.0874509960 0.1577450633 0.1443170458 666 1305031124.3503708839 0.0842883885 0.0516900188 0.1294490248 0.0165686080 0.0037370000 17779373 955859216 1373700096 -0.0863571540 0.1495610476 0.1464414746 667 1305031124.3824319839 0.0823150650 0.0517359334 0.1294490248 0.0165598398 0.0061730000 17782301 955859216 1373700096 -0.0844306946 0.1417382509 0.1484587044 668 1305031124.4185550213 0.0827942789 0.0517824279 0.1294490248 0.0165668458 0.0064030000 17785341 955859216 1373700096 -0.0785762742 0.1264800131 0.1522030085 669 1305031124.4502561092 0.0780761689 0.0518217310 0.1294490248 0.0165547190 0.0062100000 17788101 955859216 1373700096 -0.0801601261 0.1196802109 0.1520521045 670 1305031124.4801259041 0.0743841901 0.0518554063 0.1294490248 0.0165424384 0.0053130000 17790973 955859216 1373700096 -0.0808181018 0.1119407043 0.1525584161 671 1305031124.5167369843 0.0679436401 0.0518793828 0.1294490248 0.0165306201 0.0062270000 17793957 955859216 1373700096 -0.0813086331 0.1037876084 0.1533935815 672 1305031124.5505030155 0.0642978922 0.0518978627 0.1294490248 0.0165184013 0.0046450000 17796885 955859216 1373700096 -0.0810679272 0.0959755778 0.1550158858 673 1305031124.5846059322 0.0646117851 0.0519167541 0.1294490248 0.0165070264 0.0064650000 17799813 955859216 1373700096 -0.0787901878 0.0831433907 0.1583780646 674 1305031124.6176528931 0.0568830147 0.0519241225 0.1294490248 0.0165073953 0.0045980000 17802741 955859216 1373700096 -0.0801289156 0.0750373751 0.1599702388 675 1305031124.6513130665 0.0539572537 0.0519271345 0.1294490248 0.0165011899 0.0046240000 17805613 955859216 1373700096 -0.0802668706 0.0666484311 0.1629503369 676 1305031124.6854729652 0.0542369150 0.0519305514 0.1294490248 0.0164969890 0.0064460000 17808541 955859216 1373700096 -0.0769624934 0.0528120771 0.1669973582 677 1305031124.7157909870 0.0464217588 0.0519224143 0.1294490248 0.0164853668 0.0057570000 17811413 955859216 1373700096 -0.0778549314 0.0457773209 0.1695967317 678 1305031124.7499411106 0.0450256616 0.0519122421 0.1294490248 0.0164737270 0.0041140000 17814341 955859216 1373700096 -0.0767831951 0.0347002521 0.1738499105 679 1305031124.7851779461 0.0439398624 0.0519005007 0.1294490248 0.0164623054 0.0066430000 17817269 955859216 1373700096 -0.0767611191 0.0231295191 0.1780521274 680 1305031124.8166410923 0.0360544585 0.0518771977 0.1294490248 0.0164514758 0.0057910000 17820141 955859216 1373700096 -0.0779873729 0.0162191689 0.1822590381 681 1305031124.8505589962 0.0357781053 0.0518535574 0.1294490248 0.0164396962 0.0041710000 17823069 955859216 1373700096 -0.0778001547 0.0044083716 0.1881875098 682 1305031124.8835940361 0.0354601964 0.0518295202 0.1294490248 0.0164354128 0.0067040000 17825941 955859216 1373700096 -0.0773585215 -0.0072885072 0.1940839142 683 1305031124.9187700748 0.0305032507 0.0517982958 0.1294490248 0.0164366438 0.0066930000 17828925 955859216 1373700096 -0.0793565065 -0.0151530132 0.1999431849 684 1305031124.9507479668 0.0299954377 0.0517664203 0.1294490248 0.0164263785 0.0042030000 17831741 955859216 1373700096 -0.0807202384 -0.0233098958 0.2061874121 685 1305031124.9864599705 0.0312022530 0.0517363996 0.1294490248 0.0164566546 0.0068290000 17834725 955859216 1373700096 -0.0808306336 -0.0394595265 0.2125082314 686 1305031125.0194671154 0.0331746675 0.0517093417 0.1294490248 0.0164495979 0.0055270000 17837653 955859216 1373700096 -0.0836248845 -0.0498228222 0.2178424299 687 1305031125.0507979393 0.0297662336 0.0516774012 0.1294490248 0.0164484372 0.0041010000 17840469 955859216 1373700096 -0.0823489502 -0.0545818806 0.2230578959 688 1305031125.0834798813 0.0295844786 0.0516452894 0.1294490248 0.0164388058 0.0067470000 17843397 955859216 1373700096 -0.0827960521 -0.0622905083 0.2284304947 689 1305031125.1190290451 0.0291813854 0.0516126857 0.1294490248 0.0164333097 0.0057360000 17846381 955859216 1373700096 -0.0844608620 -0.0734383166 0.2331708819 690 1305031125.1510369778 0.0288314782 0.0515796695 0.1294490248 0.0164245612 0.0067230000 17849197 955859216 1373700096 -0.0852827355 -0.0817583725 0.2369546443 691 1305031125.1870639324 0.0245760903 0.0515405905 0.1294490248 0.0164245145 0.0041600000 17852237 955859216 1373700096 -0.0862287059 -0.0856629312 0.2410326302 692 1305031125.2190179825 0.0264139008 0.0515042803 0.1294490248 0.0164163596 0.0067340000 17855109 955859216 1373700096 -0.0890302733 -0.0944335237 0.2447092533 693 1305031125.2506420612 0.0302152634 0.0514735602 0.1294490248 0.0164082253 0.0049410000 17857925 955859216 1373700096 -0.0914429948 -0.1069936007 0.2479552031 694 1305031125.2863960266 0.0279699732 0.0514396933 0.1294490248 0.0163978329 0.0065880000 17860909 955859216 1373700096 -0.0930459723 -0.1123858988 0.2505890727 695 1305031125.3191399574 0.0266865343 0.0514040773 0.1294490248 0.0163891386 0.0066110000 17863837 955859216 1373700096 -0.0933095962 -0.1179575399 0.2534530163 696 1305031125.3488988876 0.0292058736 0.0513721833 0.1294490248 0.0163788384 0.0049400000 17866597 955859216 1373700096 -0.0961598158 -0.1266277581 0.2564592361 697 1305031125.3867919445 0.0280190706 0.0513386781 0.1294490248 0.0163785048 0.0066290000 17869693 955859216 1373700096 -0.0976438969 -0.1298452467 0.2595329583 698 1305031125.4195740223 0.0272290651 0.0513041371 0.1294490248 0.0163678603 0.0066940000 17872565 955859216 1373700096 -0.0969507098 -0.1346878707 0.2625421286 699 1305031125.4512319565 0.0300146379 0.0512736801 0.1294490248 0.0163632286 0.0049930000 17875437 955859216 1373700096 -0.0993470624 -0.1406750381 0.2660000026 700 1305031125.4869990349 0.0329544507 0.0512475097 0.1294490248 0.0163623876 0.0068910000 17878421 955859216 1373700096 -0.0996587276 -0.1506622881 0.2683858573 701 1305031125.5193541050 0.0331451818 0.0512216861 0.1294490248 0.0163568551 0.0043510000 17881349 955859216 1373700096 -0.0998003334 -0.1535051465 0.2706303895 702 1305031125.5510499477 0.0338669233 0.0511969643 0.1294490248 0.0163477039 0.0036440000 17884165 955859216 1373700096 -0.1002474129 -0.1560070217 0.2720003128 703 1305031125.5853030682 0.0347835012 0.0511736165 0.1294490248 0.0163361239 0.0066150000 17887093 955859216 1373700096 -0.1003450528 -0.1582470685 0.2728752196 704 1305031125.6178700924 0.0378253870 0.0511546560 0.1294490248 0.0163437490 0.0066690000 17890021 955859216 1373700096 -0.1010085121 -0.1626140922 0.2727361619 705 1305031125.6505749226 0.0423659049 0.0511421897 0.1294490248 0.0163355591 0.0066190000 17892893 955859216 1373700096 -0.1023350582 -0.1674707830 0.2714022100 706 1305031125.6846020222 0.0435574092 0.0511314463 0.1294490248 0.0163320147 0.0049740000 17895765 955859216 1373700096 -0.1027632728 -0.1670134366 0.2693967819 707 1305031125.7156689167 0.0437709577 0.0511210355 0.1294490248 0.0163495742 0.0067720000 17898637 955859216 1373700096 -0.1019020453 -0.1645566672 0.2669344842 708 1305031125.7512919903 0.0376388319 0.0511019928 0.1294490248 0.0163487451 0.0047680000 17901621 955859216 1373700096 -0.0979438871 -0.1554898024 0.2633795440 709 1305031125.7868049145 0.0398354754 0.0510861021 0.1294490248 0.0163411310 0.0041910000 17904605 955859216 1373700096 -0.0987637341 -0.1506726295 0.2605398893 710 1305031125.8194499016 0.0398307294 0.0510702494 0.1294490248 0.0163332375 0.0042310000 17907533 955859216 1373700096 -0.0976874977 -0.1449575126 0.2570929229 711 1305031125.8547739983 0.0356376320 0.0510485439 0.1294490248 0.0163289301 0.0044910000 17910405 955859216 1373700096 -0.0977454707 -0.1312283128 0.2531094849 712 1305031125.8866450787 0.0413007997 0.0510348533 0.1294490248 0.0163255046 0.0068280000 17913333 955859216 1373700096 -0.0985186398 -0.1277539581 0.2494683713 713 1305031125.9193339348 0.0396118239 0.0510188322 0.1294490248 0.0163290631 0.0070860000 17916261 955859216 1373700096 -0.0994830802 -0.1148770899 0.2465470135 714 1305031125.9552519321 0.0445610471 0.0510097877 0.1294490248 0.0163271273 0.0043410000 17919189 955859216 1373700096 -0.1000248715 -0.1122030839 0.2435959429 715 1305031125.9870939255 0.0446172021 0.0510008470 0.1294490248 0.0163212395 0.0071100000 17922061 955859216 1373700096 -0.0971670896 -0.1010535136 0.2401961684 716 1305031126.0195720196 0.0427096300 0.0509892671 0.1294490248 0.0163133299 0.0052420000 17924989 955859216 1373700096 -0.0951711237 -0.0888690352 0.2375460863 717 1305031126.0550379753 0.0410366729 0.0509753862 0.1294490248 0.0163083617 0.0046580000 17927917 955859216 1373700096 -0.0915987045 -0.0771055967 0.2351797670 718 1305031126.0870759487 0.0467319079 0.0509694761 0.1294490248 0.0162994693 0.0045670000 17930789 955859216 1373700096 -0.0883739144 -0.0699332952 0.2329981029 719 1305031126.1194519997 0.0456457436 0.0509620717 0.1294490248 0.0162902990 0.0072900000 17933717 955859216 1373700096 -0.0877127051 -0.0561768189 0.2301933020 720 1305031126.1549999714 0.0492653958 0.0509597152 0.1294490248 0.0162810916 0.0064720000 17936589 955859216 1373700096 -0.0852154121 -0.0491291769 0.2287884057 721 1305031126.1871740818 0.0502465367 0.0509587261 0.1294490248 0.0162795159 0.0042280000 17939517 955859216 1373700096 -0.0845895410 -0.0321745314 0.2267900407 722 1305031126.2194728851 0.0554126501 0.0509648949 0.1294490248 0.0162886768 0.0069360000 17942445 955859216 1373700096 -0.0813805982 -0.0263992697 0.2247708291 723 1305031126.2552359104 0.0537646413 0.0509687673 0.1294490248 0.0162874085 0.0053380000 17945429 955859216 1373700096 -0.0774082914 -0.0120414402 0.2218297571 724 1305031126.2871050835 0.0614253618 0.0509832102 0.1294490248 0.0162801720 0.0069320000 17948245 955859216 1373700096 -0.0759320706 -0.0042961799 0.2199406475 725 1305031126.3197870255 0.0597995594 0.0509953706 0.1294490248 0.0162739462 0.0060460000 17951173 955859216 1373700096 -0.0757943317 0.0108134896 0.2168693542 726 1305031126.3554151058 0.0645859390 0.0510140904 0.1294490248 0.0162652853 0.0042380000 17954101 955859216 1373700096 -0.0756534711 0.0171217006 0.2150272727 727 1305031126.3874828815 0.0673755929 0.0510365959 0.1294490248 0.0162625531 0.0071100000 17957029 955859216 1373700096 -0.0793911517 0.0293582566 0.2115799338 728 1305031126.4197928905 0.0715093315 0.0510647178 0.1294490248 0.0162525049 0.0058530000 17959845 955859216 1373700096 -0.0795890316 0.0357943848 0.2098049074 729 1305031126.4553799629 0.0754604489 0.0510981825 0.1294490248 0.0162521684 0.0041150000 17962773 955859216 1373700096 -0.0803074166 0.0421635434 0.2075154483 730 1305031126.4903860092 0.0821311325 0.0511406934 0.1294490248 0.0162498704 0.0035960000 17965757 955859216 1373700096 -0.0809184164 0.0488413274 0.2047548890 731 1305031126.5223209858 0.0786882564 0.0511783781 0.1294490248 0.0162533201 0.0069530000 17968629 955859216 1373700096 -0.0819681212 0.0634962842 0.2009370327 732 1305031126.5582089424 0.0851484835 0.0512247854 0.1294490248 0.0162521933 0.0068470000 17971613 955859216 1373700096 -0.0811021328 0.0693021193 0.1997492462 733 1305031126.5901761055 0.0872440115 0.0512739248 0.1294490248 0.0162414362 0.0043200000 17974485 955859216 1373700096 -0.0794493556 0.0753766820 0.1979574114 734 1305031126.6186869144 0.0891908333 0.0513255828 0.1294490248 0.0162304679 0.0067820000 17977245 955859216 1373700096 -0.0789614394 0.0817804784 0.1965362579 735 1305031126.6544740200 0.0911354125 0.0513797458 0.1294490248 0.0162331286 0.0050230000 17980285 955859216 1373700096 -0.0785715505 0.0865782574 0.1947522461 736 1305031126.6900219917 0.0954590589 0.0514396362 0.1294490248 0.0162229775 0.0068420000 17983269 955859216 1373700096 -0.0777677149 0.0905316845 0.1928739697 737 1305031126.7157700062 0.0960797966 0.0515002063 0.1294490248 0.0162132012 0.0068480000 17985917 955859216 1373700096 -0.0765972957 0.0956246182 0.1907284856 738 1305031126.7553739548 0.0971517414 0.0515620647 0.1294490248 0.0162037968 0.0048730000 17989013 955859216 1373700096 -0.0758914649 0.0989240706 0.1882629395 739 1305031126.7875649929 0.0988406315 0.0516260411 0.1294490248 0.0161946674 0.0041300000 17991885 955859216 1373700096 -0.0747780874 0.1024587527 0.1857264042 740 1305031126.8199288845 0.0985460058 0.0516894465 0.1294490248 0.0161865950 0.0041210000 17994757 955859216 1373700096 -0.0736535192 0.1064751521 0.1831626445 741 1305031126.8583779335 0.0986466408 0.0517528165 0.1294490248 0.0161759387 0.0041160000 17997853 955859216 1373700096 -0.0725326613 0.1102207676 0.1806374192 742 1305031126.8881540298 0.0980486050 0.0518152098 0.1294490248 0.0161656985 0.0068130000 18000669 955859216 1373700096 -0.0725317448 0.1128533036 0.1782537401 743 1305031126.9194090366 0.0971120074 0.0518761745 0.1294490248 0.0161550576 0.0068170000 18003485 955859216 1373700096 -0.0725112855 0.1148945615 0.1762888283 744 1305031126.9555010796 0.0964584500 0.0519360969 0.1294490248 0.0161469174 0.0050760000 18006469 955859216 1373700096 -0.0724074021 0.1164274663 0.1746655852 745 1305031126.9873158932 0.0962325931 0.0519955553 0.1294490248 0.0161368436 0.0049950000 18009397 955859216 1373700096 -0.0727157295 0.1169388667 0.1732893735 746 1305031127.0195240974 0.0957831219 0.0520542518 0.1294490248 0.0161266241 0.0068140000 18012213 955859216 1373700096 -0.0724124089 0.1168680042 0.1722745150 747 1305031127.0533180237 0.0947271809 0.0521113775 0.1294490248 0.0161194450 0.0057740000 18015141 955859216 1373700096 -0.0716665164 0.1174065918 0.1716898829 748 1305031127.0886490345 0.0926522687 0.0521655765 0.1294490248 0.0161120151 0.0067980000 18018125 955859216 1373700096 -0.0714055300 0.1180003360 0.1715291440 749 1305031127.1209630966 0.0920615047 0.0522188421 0.1294490248 0.0161074360 0.0050620000 18020941 955859216 1373700096 -0.0719617382 0.1169979051 0.1715851873 750 1305031127.1576919556 0.0908763185 0.0522703854 0.1294490248 0.0160971569 0.0068630000 18023981 955859216 1373700096 -0.0721711591 0.1156020761 0.1716625392 751 1305031127.1875000000 0.0897601321 0.0523203052 0.1294490248 0.0160894492 0.0050450000 18026797 955859216 1373700096 -0.0715675130 0.1146843955 0.1721512079 752 1305031127.2218310833 0.0883201137 0.0523681773 0.1294490248 0.0160822183 0.0068620000 18029725 955859216 1373700096 -0.0711658821 0.1143039912 0.1727954745 753 1305031127.2597610950 0.0861963928 0.0524131019 0.1294490248 0.0160763584 0.0046670000 18032765 955859216 1373700096 -0.0714466721 0.1123609617 0.1735257506 754 1305031127.2870380878 0.0851247460 0.0524564860 0.1294490248 0.0160732940 0.0041600000 18035469 955859216 1373700096 -0.0713568628 0.1109652668 0.1745780110 755 1305031127.3204679489 0.0839027986 0.0524981368 0.1294490248 0.0160640105 0.0041730000 18038397 955859216 1373700096 -0.0721889436 0.1098736823 0.1759230644 756 1305031127.3534069061 0.0839570835 0.0525397491 0.1294490248 0.0160567693 0.0069220000 18041269 955859216 1373700096 -0.0728613734 0.1065063700 0.1772746891 757 1305031127.3837130070 0.0833914578 0.0525805044 0.1294490248 0.0160480172 0.0069350000 18044141 955859216 1373700096 -0.0727926642 0.1045105234 0.1788391769 758 1305031127.4196500778 0.0818110853 0.0526190671 0.1294490248 0.0160390662 0.0050870000 18047069 955859216 1373700096 -0.0727454796 0.1034410596 0.1807016432 759 1305031127.4542460442 0.0816122964 0.0526572664 0.1294490248 0.0160378442 0.0042000000 18050053 955859216 1373700096 -0.0733721927 0.1010510698 0.1823012978 760 1305031127.4872000217 0.0808773115 0.0526943980 0.1294490248 0.0160400383 0.0041950000 18052925 955859216 1373700096 -0.0736575648 0.0996909067 0.1840447187 761 1305031127.5218999386 0.0805997625 0.0527310674 0.1294490248 0.0160302070 0.0041940000 18055909 955859216 1373700096 -0.0734106824 0.0993833095 0.1859196573 762 1305031127.5537250042 0.0813045427 0.0527685654 0.1294490248 0.0160286537 0.0042070000 18058725 955859216 1373700096 -0.0740552694 0.0967973247 0.1875852495 763 1305031127.5866320133 0.0813262761 0.0528059936 0.1294490248 0.0160194313 0.0041930000 18061653 955859216 1373700096 -0.0737878978 0.0952562690 0.1888727546 764 1305031127.6206569672 0.0810997784 0.0528430273 0.1294490248 0.0160096931 0.0041760000 18064581 955859216 1373700096 -0.0734298900 0.0950999483 0.1903377920 765 1305031127.6546559334 0.0817652941 0.0528808342 0.1294490248 0.0160002588 0.0069630000 18067453 955859216 1373700096 -0.0736236796 0.0936804414 0.1914648414 766 1305031127.6871099472 0.0820497572 0.0529189137 0.1294490248 0.0159900544 0.0070550000 18070381 955859216 1373700096 -0.0732582286 0.0917936116 0.1922638565 767 1305031127.7232100964 0.0815426707 0.0529562328 0.1294490248 0.0159811246 0.0069000000 18073365 955859216 1373700096 -0.0728050917 0.0918806195 0.1929904222 768 1305031127.7546939850 0.0813312307 0.0529931794 0.1294490248 0.0159716542 0.0041010000 18076181 955859216 1373700096 -0.0727960244 0.0912443027 0.1935121268 769 1305031127.7876410484 0.0816213116 0.0530304072 0.1294490248 0.0159665820 0.0036640000 18079165 955859216 1373700096 -0.0731365904 0.0892692804 0.1937752217 770 1305031127.8201279640 0.0810050368 0.0530667379 0.1294490248 0.0159575465 0.0036770000 18081981 955859216 1373700096 -0.0729753599 0.0888573527 0.1937110573 771 1305031127.8551321030 0.0806506649 0.0531025147 0.1294490248 0.0159471874 0.0070450000 18084909 955859216 1373700096 -0.0736428723 0.0886706710 0.1937941164 772 1305031127.8871219158 0.0806037635 0.0531381381 0.1294490248 0.0159380820 0.0070530000 18087837 955859216 1373700096 -0.0745678023 0.0876504257 0.1938931942 773 1305031127.9225599766 0.0807884857 0.0531739082 0.1294490248 0.0159290321 0.0060650000 18090821 955859216 1373700096 -0.0751522705 0.0871931091 0.1944517344 774 1305031127.9550879002 0.0802736953 0.0532089209 0.1294490248 0.0159205220 0.0042380000 18093693 955859216 1373700096 -0.0752417147 0.0875194669 0.1953581274 775 1305031127.9870929718 0.0793205276 0.0532426133 0.1294490248 0.0159103721 0.0070410000 18096565 955859216 1373700096 -0.0754804015 0.0874618590 0.1966473013 776 1305031128.0217759609 0.0789683014 0.0532757649 0.1294490248 0.0159028992 0.0058550000 18099549 955859216 1373700096 -0.0752963722 0.0873372704 0.1983665526 777 1305031128.0557179451 0.0787732601 0.0533085803 0.1294490248 0.0158960111 0.0042640000 18102421 955859216 1373700096 -0.0751186460 0.0864593461 0.2005898207 778 1305031128.0872058868 0.0798897967 0.0533427463 0.1294490248 0.0158872565 0.0037350000 18105293 955859216 1373700096 -0.0754272118 0.0841273889 0.2023206651 779 1305031128.1247460842 0.0804714337 0.0533775714 0.1294490248 0.0158780050 0.0070620000 18108333 955859216 1373700096 -0.0747595876 0.0826180130 0.2040007710 780 1305031128.1577820778 0.0805129558 0.0534123603 0.1294490248 0.0158692608 0.0070670000 18111261 955859216 1373700096 -0.0736187994 0.0815874338 0.2056702077 781 1305031128.1872210503 0.0813116357 0.0534480828 0.1294490248 0.0158614725 0.0051810000 18114021 955859216 1373700096 -0.0734175891 0.0795839056 0.2066573054 782 1305031128.2254419327 0.0814731568 0.0534839205 0.1294490248 0.0158543389 0.0042290000 18117061 955859216 1373700096 -0.0721071586 0.0786380917 0.2074436098 783 1305031128.2560069561 0.0808650553 0.0535188900 0.1294490248 0.0158448115 0.0070600000 18119877 955859216 1373700096 -0.0713483840 0.0786773264 0.2080683857 784 1305031128.2912750244 0.0813772380 0.0535544236 0.1294490248 0.0158375782 0.0061820000 18122861 955859216 1373700096 -0.0715130344 0.0775786564 0.2085008770 785 1305031128.3241701126 0.0812517479 0.0535897069 0.1294490248 0.0158286520 0.0042210000 18125733 955859216 1373700096 -0.0714565143 0.0772222057 0.2085665613 786 1305031128.3552060127 0.0807940587 0.0536243180 0.1294490248 0.0158190294 0.0036690000 18128605 955859216 1373700096 -0.0715964809 0.0772856995 0.2085393816 787 1305031128.3913969994 0.0807356089 0.0536587669 0.1294490248 0.0158090951 0.0070730000 18131589 955859216 1373700096 -0.0728506073 0.0765905306 0.2084665596 788 1305031128.4236090183 0.0807961822 0.0536932052 0.1294490248 0.0157991443 0.0071590000 18134461 955859216 1373700096 -0.0733370706 0.0757452697 0.2083162516 789 1305031128.4554989338 0.0804699212 0.0537271428 0.1294490248 0.0157908173 0.0063430000 18137333 955859216 1373700096 -0.0738890171 0.0754402280 0.2081786692 790 1305031128.4895229340 0.0803513527 0.0537608443 0.1294490248 0.0157813041 0.0042510000 18140317 955859216 1373700096 -0.0742806047 0.0748212412 0.2081532031 791 1305031128.5236039162 0.0802182034 0.0537942923 0.1294490248 0.0157715044 0.0037910000 18143189 955859216 1373700096 -0.0747017041 0.0739641190 0.2081322521 792 1305031128.5556390285 0.0799654350 0.0538273367 0.1294490248 0.0157622033 0.0071590000 18146061 955859216 1373700096 -0.0750133470 0.0734232068 0.2079939842 793 1305031128.5914599895 0.0803211853 0.0538607463 0.1294490248 0.0157534531 0.0067000000 18149045 955859216 1373700096 -0.0754523277 0.0720167533 0.2077843100 794 1305031128.6233680248 0.0803904831 0.0538941591 0.1294490248 0.0157444150 0.0051720000 18151917 955859216 1373700096 -0.0755716041 0.0708960518 0.2074829936 795 1305031128.6555540562 0.0801042765 0.0539271278 0.1294490248 0.0157364252 0.0070900000 18154789 955859216 1373700096 -0.0753073469 0.0706307441 0.2073153853 796 1305031128.6904489994 0.0799537376 0.0539598245 0.1294490248 0.0157279632 0.0060350000 18157773 955859216 1373700096 -0.0751441047 0.0701696277 0.2069543898 797 1305031128.7229759693 0.0796716809 0.0539920853 0.1294490248 0.0157192199 0.0042320000 18160645 955859216 1373700096 -0.0747678354 0.0697390661 0.2065771967 798 1305031128.7546460629 0.0791261047 0.0540235816 0.1294490248 0.0157105718 0.0070390000 18163517 955859216 1373700096 -0.0747653544 0.0697675645 0.2060406506 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:33:18 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 -nan 0.0231460000 23446397 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 1311867718.6768438816 0.0027237353 0.0023131936 0.0027237353 0.0021631627 0.0039780000 36030549 955859216 1373700096 0.0005165687 -0.0010969677 0.0001808407 3 1311867718.7114279270 0.0032015231 0.0026093035 0.0032015231 0.0034764563 0.0035850000 36033869 955859216 1373700096 0.0005427790 -0.0010956122 0.0002245010 4 1311867718.7410299778 0.0041534118 0.0029953305 0.0041534118 0.0042836118 0.0035640000 36037029 955859216 1373700096 0.0010230482 -0.0015515424 0.0003019936 5 1311867718.7767970562 0.0055195354 0.0035001715 0.0055195354 0.0043315304 0.0035590000 36040397 955859216 1373700096 0.0021228199 -0.0026199964 0.0001477610 6 1311867718.8094089031 0.0056029493 0.0038506345 0.0056029493 0.0041675478 0.0027940000 36044069 955859216 1373700096 0.0020333331 -0.0026798677 0.0002588151 7 1311867718.8408079147 0.0062577589 0.0041945094 0.0062577589 0.0038573067 0.0024240000 36046885 955859216 1373700096 0.0026878614 -0.0024248944 0.0003464787 8 1311867718.8767778873 0.0070267227 0.0045485361 0.0070267227 0.0036745977 0.0036210000 36049869 955859216 1373700096 0.0029782981 -0.0028183113 0.0004539220 9 1311867718.9088680744 0.0079898117 0.0049309000 0.0079898117 0.0035500021 0.0037030000 36053453 955859216 1373700096 0.0037092457 -0.0027837222 0.0006467429 10 1311867718.9438331127 0.0086698057 0.0053047906 0.0086698057 0.0033961494 0.0029590000 36058037 955859216 1373700096 0.0044340785 -0.0028026388 0.0010421835 11 1311867718.9784109592 0.0095560178 0.0056912658 0.0095560178 0.0033684351 0.0025350000 36061021 955859216 1373700096 0.0048617758 -0.0037261229 0.0012528754 12 1311867719.0091300011 0.0099234497 0.0060439478 0.0099234497 0.0032156027 0.0025310000 36063781 955859216 1373700096 0.0048085144 -0.0041651218 0.0013782058 13 1311867719.0441620350 0.0108152879 0.0064109740 0.0108152879 0.0031145882 0.0036710000 36066765 955859216 1373700096 0.0055956277 -0.0042344751 0.0016281628 14 1311867719.0776190758 0.0118946210 0.0068026630 0.0118946210 0.0031016325 0.0037050000 36069693 955859216 1373700096 0.0065762182 -0.0046565877 0.0017765030 15 1311867719.1086950302 0.0124980453 0.0071823552 0.0124980453 0.0029918885 0.0037120000 36072565 955859216 1373700096 0.0069167614 -0.0050507430 0.0020173236 16 1311867719.1437010765 0.0134292524 0.0075727863 0.0134292524 0.0029027332 0.0037590000 36075493 955859216 1373700096 0.0076477472 -0.0050778706 0.0022310587 17 1311867719.1810290813 0.0144238928 0.0079757925 0.0144238928 0.0028869795 0.0031240000 36080013 955859216 1373700096 0.0082663372 -0.0055756662 0.0025800329 18 1311867719.2127099037 0.0148656759 0.0083585638 0.0148656759 0.0028211300 0.0038470000 36086085 955859216 1373700096 0.0084172012 -0.0059015416 0.0028517907 19 1311867719.2412090302 0.0156941656 0.0087446481 0.0156941656 0.0027989776 0.0038180000 36088845 955859216 1373700096 0.0087053925 -0.0063784411 0.0030916058 20 1311867719.2779469490 0.0170029998 0.0091575657 0.0170029998 0.0031191422 0.0030080000 36091773 955859216 1373700096 0.0094133904 -0.0066762329 0.0032736238 21 1311867719.3104898930 0.0180220250 0.0095796828 0.0180220250 0.0030981671 0.0026210000 36094701 955859216 1373700096 0.0101769157 -0.0067518721 0.0034051207 22 1311867719.3413150311 0.0193861760 0.0100254325 0.0193861760 0.0032176732 0.0026300000 36097573 955859216 1373700096 0.0111316433 -0.0071418476 0.0034846759 23 1311867719.3772718906 0.0210309550 0.0105039335 0.0210309550 0.0032547761 0.0026270000 36100501 955859216 1373700096 0.0122021660 -0.0079104258 0.0034753359 24 1311867719.4105761051 0.0215934068 0.0109659949 0.0215934068 0.0032102265 0.0026580000 36103429 955859216 1373700096 0.0124854166 -0.0081581054 0.0034877392 25 1311867719.4427709579 0.0226466097 0.0114332195 0.0226466097 0.0032955607 0.0024250000 36106357 955859216 1373700096 0.0133510819 -0.0086136088 0.0035936132 26 1311867719.4787840843 0.0232513230 0.0118877619 0.0232513230 0.0033752339 0.0023990000 36109285 955859216 1373700096 0.0132283363 -0.0100220423 0.0035407848 27 1311867719.5104370117 0.0230137911 0.0122998371 0.0232513230 0.0035823890 0.0038630000 36112157 955859216 1373700096 0.0125852674 -0.0103879664 0.0036519775 28 1311867719.5449650288 0.0236991514 0.0127069554 0.0236991514 0.0036172016 0.0039470000 36115085 955859216 1373700096 0.0126762409 -0.0101475734 0.0039986526 29 1311867719.5771939754 0.0249622762 0.0131295527 0.0249622762 0.0036259418 0.0039540000 36118013 955859216 1373700096 0.0133514991 -0.0108827315 0.0040466841 30 1311867719.6112511158 0.0255258065 0.0135427612 0.0255258065 0.0035854062 0.0030580000 36120941 955859216 1373700096 0.0132163679 -0.0112194046 0.0043078773 31 1311867719.6421909332 0.0261473767 0.0139493617 0.0261473767 0.0035413405 0.0039110000 36123757 955859216 1373700096 0.0135908565 -0.0106682731 0.0046822852 32 1311867719.6770479679 0.0270536561 0.0143588709 0.0270536561 0.0034900767 0.0037740000 36126741 955859216 1373700096 0.0138303619 -0.0110401129 0.0051478301 33 1311867719.7107939720 0.0278889351 0.0147688728 0.0278889351 0.0034405633 0.0027100000 36132685 955859216 1373700096 0.0142760333 -0.0107057504 0.0056497785 34 1311867719.7442650795 0.0289763063 0.0151867385 0.0289763063 0.0033957438 0.0026750000 36141957 955859216 1373700096 0.0150811756 -0.0100084031 0.0061886781 35 1311867719.7861878872 0.0304657966 0.0156232830 0.0304657966 0.0033719840 0.0026830000 36145165 955859216 1373700096 0.0157590974 -0.0103698708 0.0066406922 36 1311867719.8099169731 0.0313633010 0.0160605057 0.0313633010 0.0033386776 0.0038900000 36147757 955859216 1373700096 0.0160681847 -0.0108224731 0.0070284549 37 1311867719.8454990387 0.0328110382 0.0165132228 0.0328110382 0.0034008613 0.0039090000 36150741 955859216 1373700096 0.0168576278 -0.0118152155 0.0070691654 38 1311867719.8771090508 0.0327986516 0.0169417867 0.0328110382 0.0033580270 0.0039420000 36153613 955859216 1373700096 0.0166676175 -0.0120168673 0.0073749176 39 1311867719.9114089012 0.0345015228 0.0173920364 0.0345015228 0.0033497619 0.0031220000 36156597 955859216 1373700096 0.0177267678 -0.0124624185 0.0076786280 40 1311867719.9461970329 0.0354840606 0.0178443370 0.0354840606 0.0033129384 0.0039460000 36159525 955859216 1373700096 0.0183954667 -0.0133100236 0.0080101816 41 1311867719.9807810783 0.0374720134 0.0183230608 0.0374720134 0.0032932746 0.0031100000 36162453 955859216 1373700096 0.0196984652 -0.0139890471 0.0080927163 42 1311867720.0117020607 0.0390320383 0.0188161317 0.0390320383 0.0032624055 0.0031290000 36165325 955859216 1373700096 0.0209066831 -0.0141539769 0.0083343983 43 1311867720.0452380180 0.0417489521 0.0193494531 0.0417489521 0.0032383394 0.0040030000 36168197 955859216 1373700096 0.0233508237 -0.0141236121 0.0086775813 44 1311867720.0772819519 0.0447948575 0.0199277578 0.0447948575 0.0032671517 0.0035150000 36171125 955859216 1373700096 0.0261806976 -0.0145188058 0.0091110487 45 1311867720.1172130108 0.0467398167 0.0205235813 0.0467398167 0.0032564162 0.0028500000 36174221 955859216 1373700096 0.0279991366 -0.0147206662 0.0095892139 46 1311867720.1451559067 0.0470516011 0.0211002774 0.0470516011 0.0032215137 0.0028700000 36176925 955859216 1373700096 0.0281358585 -0.0150291715 0.0100268750 47 1311867720.1781630516 0.0480778180 0.0216742676 0.0480778180 0.0031933158 0.0035670000 36179797 955859216 1373700096 0.0292445067 -0.0148196118 0.0103720510 48 1311867720.2094950676 0.0490367524 0.0222443194 0.0490367524 0.0031658885 0.0035630000 36182669 955859216 1373700096 0.0301618390 -0.0146456864 0.0108574247 49 1311867720.2421469688 0.0500070527 0.0228109058 0.0500070527 0.0031353868 0.0036500000 36185597 955859216 1373700096 0.0310839396 -0.0142851491 0.0113331936 50 1311867720.2770779133 0.0517390668 0.0233894690 0.0517390668 0.0031759867 0.0036010000 36188525 955859216 1373700096 0.0324776210 -0.0142990891 0.0120476708 51 1311867720.3094570637 0.0525971986 0.0239621696 0.0525971986 0.0031521640 0.0029070000 36191397 955859216 1373700096 0.0334127769 -0.0135939792 0.0129414368 52 1311867720.3430728912 0.0541558936 0.0245428181 0.0541558936 0.0031601478 0.0029690000 36194325 955859216 1373700096 0.0347886309 -0.0134404087 0.0138158603 53 1311867720.3779859543 0.0560525097 0.0251373406 0.0560525097 0.0032267529 0.0037150000 36197197 955859216 1373700096 0.0360090286 -0.0146856848 0.0142033109 54 1311867720.4096798897 0.0581826158 0.0257492901 0.0581826158 0.0034558826 0.0036240000 36200069 955859216 1373700096 0.0371560492 -0.0155678140 0.0146377562 55 1311867720.4461109638 0.0593099296 0.0263594836 0.0593099296 0.0034488048 0.0036480000 36203109 955859216 1373700096 0.0382042527 -0.0155537464 0.0152026815 56 1311867720.4799289703 0.0608963035 0.0269762125 0.0608963035 0.0035111420 0.0037100000 36206037 955859216 1373700096 0.0394581258 -0.0158328284 0.0152612785 57 1311867720.5104389191 0.0614038631 0.0275802064 0.0614038631 0.0035447968 0.0029950000 36208853 955859216 1373700096 0.0399307013 -0.0161789376 0.0151840448 58 1311867720.5467319489 0.0630762130 0.0281922065 0.0630762130 0.0036292605 0.0036270000 36211893 955859216 1373700096 0.0406881757 -0.0163212791 0.0155880051 59 1311867720.5793280602 0.0634532943 0.0287898520 0.0634532943 0.0036709919 0.0036740000 36214765 955859216 1373700096 0.0410216972 -0.0168012585 0.0158124287 60 1311867720.6121249199 0.0653098524 0.0293985187 0.0653098524 0.0036575285 0.0029550000 36217637 955859216 1373700096 0.0421829857 -0.0172542240 0.0158895832 61 1311867720.6463210583 0.0660602152 0.0299995301 0.0660602152 0.0036488158 0.0037190000 36220621 955859216 1373700096 0.0422509685 -0.0175783206 0.0162851810 62 1311867720.6798269749 0.0669336393 0.0305952416 0.0669336393 0.0036321583 0.0036940000 36223437 955859216 1373700096 0.0424630828 -0.0180427115 0.0162918624 63 1311867720.7102439404 0.0682197884 0.0311924566 0.0682197884 0.0036247554 0.0036910000 36226309 955859216 1373700096 0.0429999828 -0.0190108828 0.0162204709 64 1311867720.7451629639 0.0691298246 0.0317852280 0.0691298246 0.0036199248 0.0037050000 36229237 955859216 1373700096 0.0430319943 -0.0192395598 0.0163044706 65 1311867720.7790179253 0.1112767011 0.0330081737 0.1112767011 0.0049866343 0.0033730000 36238365 955859216 1373700096 0.0857973620 -0.0169385076 0.0258410834 66 1311867720.8115909100 0.1123256236 0.0342099533 0.1123256236 0.0049617343 0.0038050000 36254037 955859216 1373700096 0.0860311091 -0.0182861537 0.0259797778 67 1311867720.8467299938 0.1132578850 0.0353897731 0.1132578850 0.0049543943 0.0037430000 36257021 955859216 1373700096 0.0864261240 -0.0187977813 0.0265692100 68 1311867720.8813319206 0.1133894473 0.0365368272 0.1133894473 0.0049435447 0.0030200000 36259949 955859216 1373700096 0.0862058401 -0.0191015359 0.0269482713 69 1311867720.9149661064 0.1144858748 0.0376665235 0.1144858748 0.0049174985 0.0038420000 36262821 955859216 1373700096 0.0867390782 -0.0198996272 0.0272546522 70 1311867720.9500010014 0.1150927767 0.0387726128 0.1150927767 0.0048854354 0.0038090000 36265749 955859216 1373700096 0.0870002955 -0.0204006415 0.0276053250 71 1311867720.9797990322 0.1155605540 0.0398541331 0.1155605540 0.0048571332 0.0037730000 36268509 955859216 1373700096 0.0872230977 -0.0206182953 0.0277692918 72 1311867721.0093889236 0.1157153174 0.0409077607 0.1157153174 0.0048235290 0.0038020000 36271325 955859216 1373700096 0.0871642679 -0.0210772958 0.0277927965 73 1311867721.0478379726 0.1162900552 0.0419403949 0.1162900552 0.0047921888 0.0030950000 36274421 955859216 1373700096 0.0873558372 -0.0214134455 0.0278144497 74 1311867721.0794439316 0.1171292141 0.0429564600 0.1171292141 0.0047654901 0.0038330000 36277237 955859216 1373700096 0.0878956169 -0.0218961034 0.0279939938 75 1311867721.1103579998 0.1176245436 0.0439520344 0.1176245436 0.0047429033 0.0038720000 36280109 955859216 1373700096 0.0880170465 -0.0221878868 0.0281539597 76 1311867721.1467890739 0.1189808995 0.0449392563 0.1189808995 0.0047331125 0.0033050000 36283093 955859216 1373700096 0.0885730535 -0.0227176249 0.0280970279 77 1311867721.1774179935 0.1198335439 0.0459119094 0.1198335439 0.0047660455 0.0039430000 36285965 955859216 1373700096 0.0895221531 -0.0231060050 0.0282163844 78 1311867721.2112360001 0.1200206727 0.0468620218 0.1200206727 0.0047371440 0.0038620000 36288837 955859216 1373700096 0.0892719924 -0.0236680415 0.0283511262 79 1311867721.2469010353 0.1209860593 0.0478003007 0.1209860593 0.0047267619 0.0031390000 36291821 955859216 1373700096 0.0899549723 -0.0242737141 0.0284090377 80 1311867721.2800450325 0.1217652336 0.0487248624 0.1217652336 0.0047126577 0.0039460000 36294693 955859216 1373700096 0.0901247710 -0.0249126069 0.0284873322 81 1311867721.3099579811 0.1227669492 0.0496389622 0.1227669492 0.0046988694 0.0039230000 36297509 955859216 1373700096 0.0907636434 -0.0255405586 0.0286457147 82 1311867721.3483059406 0.1241308898 0.0505474004 0.1241308898 0.0046770736 0.0038940000 36300549 955859216 1373700096 0.0917102247 -0.0258295648 0.0287335608 83 1311867721.3790040016 0.1249252185 0.0514435187 0.1249252185 0.0046511158 0.0038950000 36303309 955859216 1373700096 0.0920550823 -0.0257923026 0.0288369823 84 1311867721.4092550278 0.1252547055 0.0523222233 0.1252547055 0.0046254857 0.0031150000 36306125 955859216 1373700096 0.0917972848 -0.0262440890 0.0291207116 85 1311867721.4478130341 0.1258986145 0.0531878279 0.1258986145 0.0045986761 0.0034950000 36309277 955859216 1373700096 0.0918420404 -0.0265714061 0.0294889417 86 1311867721.4768960476 0.1263264716 0.0540382772 0.1263264716 0.0045758484 0.0044280000 36312037 955859216 1373700096 0.0918006003 -0.0268837754 0.0296850260 87 1311867721.5093359947 0.1270142794 0.0548770818 0.1270142794 0.0045686945 0.0034550000 36314853 955859216 1373700096 0.0920084715 -0.0273737293 0.0299532432 88 1311867721.5451331139 0.1287297457 0.0557163167 0.1287297457 0.0045469482 0.0043560000 36317781 955859216 1373700096 0.0931834206 -0.0281921513 0.0300867148 89 1311867721.5769670010 0.1295579821 0.0565459983 0.1295579821 0.0045248594 0.0034180000 36320541 955859216 1373700096 0.0937359780 -0.0282306019 0.0304159187 90 1311867721.6129651070 0.1305809468 0.0573686088 0.1305809468 0.0045450487 0.0030290000 36323469 955859216 1373700096 0.0941871852 -0.0288009420 0.0303684864 91 1311867721.6496050358 0.1310938746 0.0581787766 0.1310938746 0.0045678906 0.0043560000 36326509 955859216 1373700096 0.0943309069 -0.0292284992 0.0301063918 92 1311867721.6800351143 0.1315754056 0.0589765660 0.1315754056 0.0045669710 0.0026970000 36329325 955859216 1373700096 0.0945025086 -0.0288775563 0.0302872434 93 1311867721.7162289619 0.1316667348 0.0597581808 0.1316667348 0.0045581746 0.0044540000 36332365 955859216 1373700096 0.0945356190 -0.0289822593 0.0305214208 94 1311867721.7467949390 0.1325501800 0.0605325637 0.1325501800 0.0045910999 0.0039560000 36335181 955859216 1373700096 0.0945096985 -0.0299548935 0.0304814111 95 1311867721.7787001133 0.1327863932 0.0612931304 0.1327863932 0.0045678082 0.0044840000 36338053 955859216 1373700096 0.0944512114 -0.0299936775 0.0306364968 96 1311867721.8154830933 0.1335319132 0.0620456177 0.1335319132 0.0045472152 0.0031690000 36341037 955859216 1373700096 0.0947019532 -0.0303689521 0.0306804068 97 1311867721.8485159874 0.1340906918 0.0627883504 0.1340906918 0.0045267030 0.0043990000 36343965 955859216 1373700096 0.0946810544 -0.0311684497 0.0305013508 98 1311867721.8778810501 0.1340169758 0.0635151731 0.1340906918 0.0045061730 0.0043100000 36346781 955859216 1373700096 0.0943251774 -0.0311171450 0.0303883106 99 1311867721.9146931171 0.1341983080 0.0642291442 0.1341983080 0.0044840600 0.0030570000 36349541 955859216 1373700096 0.0942277014 -0.0311745014 0.0302346647 100 1311867721.9467151165 0.1346044540 0.0649328973 0.1346044540 0.0044625063 0.0044910000 36352413 955859216 1373700096 0.0942452401 -0.0316154286 0.0301054902 101 1311867721.9773728848 0.1350724399 0.0656273482 0.1350724399 0.0044647387 0.0043510000 36355285 955859216 1373700096 0.0946716443 -0.0316477790 0.0299381614 102 1311867722.0166850090 0.1356602162 0.0663139449 0.1356602162 0.0044942432 0.0030510000 36358213 955859216 1373700096 0.0946379900 -0.0321931206 0.0298475418 103 1311867722.0475180149 0.1360756457 0.0669912430 0.1360756457 0.0045004525 0.0027820000 36360917 955859216 1373700096 0.0950802490 -0.0326173864 0.0295618773 104 1311867722.0800709724 0.1365942210 0.0676605024 0.1365942210 0.0044881043 0.0044810000 36363845 955859216 1373700096 0.0951647088 -0.0329820514 0.0295248870 105 1311867722.1161251068 0.1372532248 0.0683232902 0.1372532248 0.0044724521 0.0044860000 36366829 955859216 1373700096 0.0951912403 -0.0339105353 0.0295334551 106 1311867722.1479530334 0.1376381367 0.0689772039 0.1376381367 0.0044677145 0.0033450000 36369645 955859216 1373700096 0.0950751528 -0.0343966335 0.0293865614 107 1311867722.1798410416 0.1381968558 0.0696241165 0.1381968558 0.0044491135 0.0045520000 36372517 955859216 1373700096 0.0953433886 -0.0342561677 0.0297664553 108 1311867722.2146399021 0.1388272643 0.0702648864 0.1388272643 0.0044528683 0.0035850000 36375501 955859216 1373700096 0.0957151204 -0.0349319130 0.0297571365 109 1311867722.2469589710 0.1397286057 0.0709021682 0.1397286057 0.0044352582 0.0031150000 36378373 955859216 1373700096 0.0962893367 -0.0354707874 0.0297828168 110 1311867722.2780389786 0.1402767152 0.0715328459 0.1402767152 0.0044163613 0.0031500000 36381245 955859216 1373700096 0.0966857895 -0.0352834240 0.0301666390 111 1311867722.3154170513 0.1404579580 0.0721537929 0.1404579580 0.0043972645 0.0045590000 36384229 955859216 1373700096 0.0967101753 -0.0356361344 0.0302282404 112 1311867722.3488469124 0.1413055807 0.0727712196 0.1413055807 0.0043885775 0.0045160000 36387101 955859216 1373700096 0.0971718729 -0.0363951921 0.0302158613 113 1311867722.3777940273 0.1412459314 0.0733771905 0.1413055807 0.0043726528 0.0034780000 36389917 955859216 1373700096 0.0970201120 -0.0363042019 0.0304365922 114 1311867722.4150679111 0.1417597830 0.0739770378 0.1417597830 0.0043552764 0.0045370000 36392733 955859216 1373700096 0.0971067697 -0.0368798375 0.0305816047 115 1311867722.4467909336 0.1421578377 0.0745699143 0.1421578377 0.0043799064 0.0036090000 36395605 955859216 1373700096 0.0971569046 -0.0377650931 0.0309860744 116 1311867722.4777851105 0.1432640702 0.0751621053 0.1432640702 0.0044110520 0.0046270000 36398421 955859216 1373700096 0.0977487788 -0.0376586914 0.0313676633 117 1311867722.5147399902 0.1438494921 0.0757491770 0.1438494921 0.0043953183 0.0036080000 36401349 955859216 1373700096 0.0979795903 -0.0380409323 0.0319695361 118 1311867722.5469911098 0.1436948478 0.0763249877 0.1438494921 0.0043812137 0.0046580000 36404221 955859216 1373700096 0.0976065546 -0.0382445864 0.0321500525 119 1311867722.5802359581 0.1437803805 0.0768918398 0.1438494921 0.0043701059 0.0046500000 36407093 955859216 1373700096 0.0974758938 -0.0387694016 0.0325290374 120 1311867722.6146309376 0.1450246274 0.0774596130 0.1450246274 0.0043541169 0.0046370000 36410021 955859216 1373700096 0.0985384956 -0.0395100079 0.0327198021 121 1311867722.6560258865 0.1459592581 0.0780257258 0.1459592581 0.0043406620 0.0036420000 36413173 955859216 1373700096 0.0992247537 -0.0402105153 0.0327873342 122 1311867722.6778230667 0.1470079571 0.0785911539 0.1470079571 0.0043317685 0.0028750000 36415821 955859216 1373700096 0.1000817344 -0.0406745262 0.0329786390 123 1311867722.7252709866 0.1476558149 0.0791526552 0.1476558149 0.0043978795 0.0046630000 36419085 955859216 1373700096 0.1003108397 -0.0409898497 0.0331395566 124 1311867722.7449109554 0.1479170918 0.0797072071 0.1479170918 0.0044126072 0.0045860000 36421565 955859216 1373700096 0.1005493030 -0.0413385667 0.0327495895 125 1311867722.7770080566 0.1474432200 0.0802490952 0.1479170918 0.0044571035 0.0036430000 36424493 955859216 1373700096 0.0997139961 -0.0412696525 0.0325464793 126 1311867722.8162860870 0.1469826549 0.0807787266 0.1479170918 0.0044395400 0.0046400000 36427477 955859216 1373700096 0.0988075212 -0.0412792712 0.0328179076 127 1311867722.8466939926 0.1481417567 0.0813091442 0.1481417567 0.0044637777 0.0034460000 36430293 955859216 1373700096 0.0991889387 -0.0426912718 0.0335642509 128 1311867722.8819770813 0.1494020820 0.0818411203 0.1494020820 0.0044505549 0.0042290000 36433277 955859216 1373700096 0.0995596945 -0.0436212607 0.0344695300 129 1311867722.9150629044 0.1519496292 0.0823845971 0.1519496292 0.0044496153 0.0033500000 36448269 955859216 1373700096 0.1015726551 -0.0431370363 0.0356579460 130 1311867722.9485991001 0.1527936012 0.0829262048 0.1527936012 0.0044669791 0.0042130000 36476853 955859216 1373700096 0.1019383892 -0.0439760312 0.0360377356 131 1311867722.9821140766 0.1532284617 0.0834628633 0.1532284617 0.0044511507 0.0042260000 36479725 955859216 1373700096 0.1015504822 -0.0448496267 0.0367364772 132 1311867723.0147259235 0.1542970836 0.0839994861 0.1542970836 0.0044351442 0.0028270000 36482597 955859216 1373700096 0.1023536250 -0.0442847945 0.0376459993 133 1311867723.0460629463 0.1554544866 0.0845367418 0.1554544866 0.0044509467 0.0042490000 36485413 955859216 1373700096 0.1027098224 -0.0450549312 0.0385177135 134 1311867723.0845439434 0.1579570919 0.0850846549 0.1579570919 0.0044503865 0.0042490000 36488453 955859216 1373700096 0.1043397412 -0.0463934690 0.0394498594 135 1311867723.1140980721 0.1589579433 0.0856318644 0.1589579433 0.0044366656 0.0042830000 36491269 955859216 1373700096 0.1046144664 -0.0469073802 0.0402154401 136 1311867723.1505160332 0.1604515761 0.0861820093 0.1604515761 0.0044280051 0.0034170000 36494253 955859216 1373700096 0.1052880287 -0.0478048474 0.0406128168 137 1311867723.1811029911 0.1609100699 0.0867274696 0.1609100699 0.0044145406 0.0042850000 36497069 955859216 1373700096 0.1048359573 -0.0490324944 0.0408946536 138 1311867723.2201359272 0.1619091928 0.0872722647 0.1619091928 0.0043987287 0.0034320000 36500109 955859216 1373700096 0.1050076187 -0.0498973206 0.0418590903 139 1311867723.2486810684 0.1642918587 0.0878263625 0.1642918587 0.0043964909 0.0043170000 36502869 955859216 1373700096 0.1068701446 -0.0506853871 0.0422556773 140 1311867723.2846419811 0.1593193263 0.0883370266 0.1642918587 0.0044321642 0.0042920000 36505853 955859216 1373700096 0.1015919521 -0.0506660007 0.0395819210 141 1311867723.3132460117 0.1581587940 0.0888322164 0.1642918587 0.0044190343 0.0042880000 36508613 955859216 1373700096 0.1001417711 -0.0509339161 0.0389015190 142 1311867723.3499810696 0.1576186568 0.0893166279 0.1642918587 0.0044070620 0.0043210000 36511653 955859216 1373700096 0.0990521163 -0.0507467687 0.0390269570 143 1311867723.3822429180 0.1582603604 0.0897987519 0.1642918587 0.0043966296 0.0034400000 36514581 955859216 1373700096 0.0992426649 -0.0511782691 0.0396708213 144 1311867723.4193739891 0.1588853896 0.0902785203 0.1642918587 0.0044144656 0.0043030000 36517565 955859216 1373700096 0.0996967852 -0.0516174473 0.0405254997 145 1311867723.4455900192 0.1587295234 0.0907505961 0.1642918587 0.0044037627 0.0034910000 36520269 955859216 1373700096 0.0992579758 -0.0514697097 0.0403405651 146 1311867723.4825348854 0.1592900753 0.0912200446 0.1642918587 0.0044030748 0.0043580000 36523309 955859216 1373700096 0.0989197418 -0.0516051836 0.0408203304 147 1311867723.5147960186 0.1595329046 0.0916847580 0.1642918587 0.0043896227 0.0043700000 36526125 955859216 1373700096 0.0987015814 -0.0516494066 0.0409488156 148 1311867723.5451340675 0.1600321382 0.0921465646 0.1642918587 0.0043769133 0.0034670000 36528997 955859216 1373700096 0.0985350162 -0.0519596674 0.0414532535 149 1311867723.5809938908 0.1603987664 0.0926046331 0.1642918587 0.0043654470 0.0043600000 36531981 955859216 1373700096 0.0982553810 -0.0523213409 0.0417950228 150 1311867723.6132669449 0.1621729732 0.0930684220 0.1642918587 0.0043574128 0.0034690000 36534909 955859216 1373700096 0.0996010900 -0.0525895804 0.0425411910 151 1311867723.6453940868 0.1618808210 0.0935241332 0.1642918587 0.0043439574 0.0043970000 36537725 955859216 1373700096 0.0990147442 -0.0525421090 0.0426981673 152 1311867723.6809489727 0.1623303741 0.0939768059 0.1642918587 0.0043309315 0.0048690000 36540709 955859216 1373700096 0.0990736336 -0.0531028435 0.0427977964 153 1311867723.7130429745 0.1630384922 0.0944281895 0.1642918587 0.0043195185 0.0033090000 36543581 955859216 1373700096 0.0992539227 -0.0535940416 0.0433721915 154 1311867723.7471990585 0.1641049534 0.0948806360 0.1642918587 0.0043081703 0.0048950000 36546509 955859216 1373700096 0.0999460071 -0.0538436100 0.0432432815 155 1311867723.7809250355 0.1646815091 0.0953309642 0.1646815091 0.0042979633 0.0037990000 36549437 955859216 1373700096 0.0998465642 -0.0546847098 0.0432023704 156 1311867723.8157649040 0.1663382947 0.0957861394 0.1663382947 0.0042915125 0.0048670000 36552365 955859216 1373700096 0.1008869782 -0.0554004386 0.0431076810 157 1311867723.8468959332 0.1678738594 0.0962452968 0.1678738594 0.0042799529 0.0037440000 36555237 955859216 1373700096 0.1021478102 -0.0553814694 0.0434782170 158 1311867723.8826351166 0.1666533798 0.0966909176 0.1678738594 0.0042792809 0.0050250000 36558165 955859216 1373700096 0.1004174501 -0.0558958799 0.0426944681 159 1311867723.9172909260 0.1670668870 0.0971335338 0.1678738594 0.0042733277 0.0049600000 36560981 955859216 1373700096 0.1005000547 -0.0559998490 0.0426515378 160 1311867723.9490020275 0.1672914922 0.0975720210 0.1678738594 0.0042623959 0.0049930000 36563797 955859216 1373700096 0.1007015854 -0.0551915169 0.0425014980 161 1311867723.9839010239 0.1688400656 0.0980146797 0.1688400656 0.0042623840 0.0041060000 36566781 955859216 1373700096 0.1017608494 -0.0560887456 0.0428662933 162 1311867724.0132899284 0.1685339212 0.0984499836 0.1688400656 0.0042613034 0.0033390000 36569541 955859216 1373700096 0.1013725623 -0.0560004376 0.0426021740 163 1311867724.0475380421 0.1700337082 0.0988891476 0.1700337082 0.0042511629 0.0049160000 36572525 955859216 1373700096 0.1026838347 -0.0559279956 0.0429494381 164 1311867724.0824530125 0.1703000367 0.0993245798 0.1703000367 0.0042439582 0.0043750000 36575453 955859216 1373700096 0.1026118919 -0.0562941432 0.0429951251 165 1311867724.1132431030 0.1695420891 0.0997501405 0.1703000367 0.0042323282 0.0033530000 36578325 955859216 1373700096 0.1016415879 -0.0562467836 0.0425963663 166 1311867724.1547191143 0.1698532552 0.1001724484 0.1703000367 0.0042282339 0.0049750000 36581477 955859216 1373700096 0.1018468961 -0.0557598621 0.0422676913 167 1311867724.1810541153 0.1701778173 0.1005916422 0.1703000367 0.0042202205 0.0042800000 36584181 955859216 1373700096 0.1018815562 -0.0559568480 0.0425981171 168 1311867724.2139430046 0.1701681912 0.1010057884 0.1703000367 0.0042119239 0.0038970000 36587109 955859216 1373700096 0.1014728919 -0.0563605390 0.0428474061 169 1311867724.2507870197 0.1696901619 0.1014122048 0.1703000367 0.0042079524 0.0049640000 36590093 955859216 1373700096 0.1006956547 -0.0559116192 0.0426429138 170 1311867724.2855930328 0.1708948016 0.1018209259 0.1708948016 0.0042013234 0.0033700000 36593021 955859216 1373700096 0.1017069519 -0.0558918342 0.0428986922 171 1311867724.3144888878 0.1712696105 0.1022270586 0.1712696105 0.0041901206 0.0049740000 36595781 955859216 1373700096 0.1018016264 -0.0563890748 0.0423830152 172 1311867724.3517999649 0.1713440567 0.1026289016 0.1713440567 0.0041927512 0.0039790000 36598877 955859216 1373700096 0.1014524847 -0.0567050464 0.0427068509 173 1311867724.3888330460 0.1710229516 0.1030242429 0.1713440567 0.0041865542 0.0039710000 36601805 955859216 1373700096 0.1009192765 -0.0567005575 0.0425630026 174 1311867724.4160330296 0.1713948101 0.1034171772 0.1713948101 0.0041827733 0.0039610000 36604565 955859216 1373700096 0.1012867466 -0.0569683686 0.0423856787 175 1311867724.4509639740 0.1714978665 0.1038062097 0.1714978665 0.0041726766 0.0031660000 36607493 955859216 1373700096 0.1010366678 -0.0576773696 0.0419380553 176 1311867724.4830689430 0.1719343364 0.1041933014 0.1719343364 0.0041615419 0.0045920000 36610365 955859216 1373700096 0.1011527330 -0.0581909567 0.0415069498 177 1311867724.5208630562 0.1708983332 0.1045701660 0.1719343364 0.0041528163 0.0045780000 36613293 955859216 1373700096 0.0995208323 -0.0586721487 0.0413132757 178 1311867724.5523910522 0.1705414355 0.1049407911 0.1719343364 0.0041443101 0.0046060000 36616221 955859216 1373700096 0.0990910456 -0.0590954311 0.0402035043 179 1311867724.5861799717 0.1689146608 0.1052981870 0.1719343364 0.0041421489 0.0047400000 36619093 955859216 1373700096 0.0970788524 -0.0595401488 0.0391225740 180 1311867724.6193559170 0.1683560163 0.1056485083 0.1719343364 0.0041743966 0.0037230000 36621965 955859216 1373700096 0.0963851288 -0.0595396608 0.0381367542 181 1311867724.6529819965 0.1668788642 0.1059867975 0.1719343364 0.0041786754 0.0032180000 36624893 955859216 1373700096 0.0943282917 -0.0594964325 0.0378772691 182 1311867724.6818330288 0.1640109718 0.1063056117 0.1719343364 0.0041694162 0.0051370000 36627653 955859216 1373700096 0.0909444466 -0.0598988459 0.0363205709 183 1311867724.7153129578 0.1608641893 0.1066037460 0.1719343364 0.0041851178 0.0047140000 36630581 955859216 1373700096 0.0873782858 -0.0590885207 0.0353121385 184 1311867724.7518899441 0.1581686586 0.1068839901 0.1719343364 0.0041955940 0.0034300000 36633565 955859216 1373700096 0.0842348635 -0.0579565167 0.0349889547 185 1311867724.7853860855 0.1555999815 0.1071473197 0.1719343364 0.0041981268 0.0051590000 36636493 955859216 1373700096 0.0812175646 -0.0577481873 0.0343125090 186 1311867724.8179960251 0.1527673304 0.1073925886 0.1719343364 0.0041876310 0.0037150000 36639365 955859216 1373700096 0.0779426470 -0.0576675795 0.0330622084 187 1311867724.8547580242 0.1505331695 0.1076232869 0.1719343364 0.0042267465 0.0051360000 36642293 955859216 1373700096 0.0752258301 -0.0574293509 0.0326286219 188 1311867724.8830249310 0.1481564045 0.1078388886 0.1719343364 0.0042253968 0.0040200000 36645053 955859216 1373700096 0.0724865794 -0.0570897162 0.0320947617 189 1311867724.9137279987 0.1466168314 0.1080440629 0.1719343364 0.0042213941 0.0051390000 36647925 955859216 1373700096 0.0703892559 -0.0573826581 0.0310911331 190 1311867724.9535229206 0.1446163654 0.1082365487 0.1719343364 0.0042236232 0.0034360000 36650965 955859216 1373700096 0.0682108179 -0.0570205897 0.0300891977 191 1311867724.9843940735 0.1430243552 0.1084186838 0.1719343364 0.0042138743 0.0051880000 36653837 955859216 1373700096 0.0665337443 -0.0568447784 0.0290864818 192 1311867725.0159099102 0.1416179985 0.1085915969 0.1719343364 0.0042281527 0.0040740000 36656653 955859216 1373700096 0.0650502890 -0.0570312031 0.0286197867 193 1311867725.0518310070 0.1399613917 0.1087541347 0.1719343364 0.0042227146 0.0051900000 36659637 955859216 1373700096 0.0628146008 -0.0574267097 0.0284345727 194 1311867725.0813930035 0.1388394386 0.1089092136 0.1719343364 0.0042152913 0.0038180000 36662453 955859216 1373700096 0.0613504536 -0.0572792701 0.0282887612 195 1311867725.1151220798 0.1379087418 0.1090579291 0.1719343364 0.0042047644 0.0038130000 36665381 955859216 1373700096 0.0600825213 -0.0577809997 0.0275115333 196 1311867725.1557130814 0.1363535821 0.1091971927 0.1719343364 0.0042050396 0.0048610000 36668477 955859216 1373700096 0.0579863824 -0.0578251220 0.0272678807 197 1311867725.1843969822 0.1350372732 0.1093283606 0.1719343364 0.0042040630 0.0047750000 36671237 955859216 1373700096 0.0561821871 -0.0580025911 0.0270622056 198 1311867725.2150099277 0.1333474368 0.1094496691 0.1719343364 0.0041968132 0.0038160000 36674109 955859216 1373700096 0.0537925884 -0.0587628521 0.0260192789 199 1311867725.2516539097 0.1313160807 0.1095595505 0.1719343364 0.0041951096 0.0047900000 36677149 955859216 1373700096 0.0511431098 -0.0586794429 0.0257467944 200 1311867725.2816410065 0.1292598248 0.1096580519 0.1719343364 0.0041895342 0.0047830000 36679965 955859216 1373700096 0.0487350821 -0.0587222241 0.0249219090 201 1311867725.3196239471 0.1284456104 0.1097515223 0.1719343364 0.0041852820 0.0047700000 36682949 955859216 1373700096 0.0473463610 -0.0589618571 0.0244426876 202 1311867725.3517010212 0.1266384125 0.1098351208 0.1719343364 0.0041902959 0.0045430000 36685765 955859216 1373700096 0.0448616333 -0.0591890328 0.0247744322 203 1311867725.3837459087 0.1256237477 0.1099128973 0.1719343364 0.0042242141 0.0048040000 36688525 955859216 1373700096 0.0438160636 -0.0588222668 0.0245483220 204 1311867725.4178969860 0.1247282550 0.1099855216 0.1719343364 0.0042278655 0.0038070000 36691509 955859216 1373700096 0.0424050093 -0.0589626767 0.0243043229 205 1311867725.4492449760 0.1231715158 0.1100498435 0.1719343364 0.0042429103 0.0048040000 36694325 955859216 1373700096 0.0401066132 -0.0587494150 0.0243200622 206 1311867725.4836509228 0.1223361343 0.1101094857 0.1719343364 0.0042723869 0.0048130000 36697253 955859216 1373700096 0.0385413915 -0.0585609004 0.0241262745 207 1311867725.5178139210 0.1213224679 0.1101636547 0.1719343364 0.0042698056 0.0038350000 36700293 955859216 1373700096 0.0369999856 -0.0582986251 0.0232692156 208 1311867725.5497610569 0.1205554903 0.1102136154 0.1719343364 0.0042599140 0.0048460000 36703109 955859216 1373700096 0.0352045819 -0.0587506257 0.0233069602 209 1311867725.5815479755 0.1196106300 0.1102585772 0.1719343364 0.0042508057 0.0043450000 36705981 955859216 1373700096 0.0335144997 -0.0585566945 0.0229328480 210 1311867725.6194949150 0.1193623021 0.1103019283 0.1719343364 0.0042427948 0.0048600000 36709021 955859216 1373700096 0.0324870944 -0.0588555485 0.0226601493 211 1311867725.6515610218 0.1188580543 0.1103424787 0.1719343364 0.0043085243 0.0038950000 36711893 955859216 1373700096 0.0310051590 -0.0594043992 0.0225877929 212 1311867725.6834650040 0.1185141653 0.1103810244 0.1719343364 0.0043050628 0.0048560000 36714765 955859216 1373700096 0.0296588112 -0.0597540960 0.0233251024 213 1311867725.7201809883 0.1179036796 0.1104163420 0.1719343364 0.0042970386 0.0043110000 36717749 955859216 1373700096 0.0280103367 -0.0601970702 0.0238005724 214 1311867725.7515070438 0.1182332337 0.1104528695 0.1719343364 0.0042870092 0.0034140000 36720621 955859216 1373700096 0.0274018105 -0.0610710010 0.0238253139 215 1311867725.7835409641 0.1060092524 0.1104322015 0.1719343364 0.0043229950 0.0050000000 36723437 955859216 1373700096 0.0130259190 -0.0594654530 0.0222506169 216 1311867725.8211829662 0.1027845293 0.1103967956 0.1719343364 0.0043468806 0.0048930000 36726533 955859216 1373700096 0.0078043658 -0.0604401603 0.0213196464 217 1311867725.8517971039 0.1013654694 0.1103551766 0.1719343364 0.0043373120 0.0048750000 36729405 955859216 1373700096 0.0051395539 -0.0609195009 0.0205913559 218 1311867725.8837900162 0.1004786640 0.1103098715 0.1719343364 0.0043558677 0.0048560000 36732165 955859216 1373700096 0.0033883390 -0.0605277009 0.0208408665 219 1311867725.9192690849 0.1004851311 0.1102650097 0.1719343364 0.0043471587 0.0033590000 36735149 955859216 1373700096 0.0019782153 -0.0612574145 0.0212018229 220 1311867725.9511859417 0.1007948741 0.1102219636 0.1719343364 0.0043392346 0.0049170000 36738021 955859216 1373700096 0.0008777760 -0.0622301772 0.0221035331 221 1311867725.9829630852 0.1013082266 0.1101816300 0.1719343364 0.0043388326 0.0053850000 36740837 955859216 1373700096 0.0006513541 -0.0623056702 0.0230838880 222 1311867726.0219368935 0.1034886762 0.1101514815 0.1719343364 0.0043326619 0.0036330000 36743933 955859216 1373700096 0.0008410507 -0.0638349727 0.0257980879 223 1311867726.0504179001 0.1051616371 0.1101291055 0.1719343364 0.0043247030 0.0053890000 36746637 955859216 1373700096 0.0005520158 -0.0656898096 0.0278256126 224 1311867726.0845088959 0.1068222746 0.1101143429 0.1719343364 0.0043278699 0.0036300000 36749621 955859216 1373700096 0.0003644079 -0.0671926886 0.0308581274 225 1311867726.1199669838 0.1091320813 0.1101099773 0.1719343364 0.0043196150 0.0054180000 36752549 955859216 1373700096 0.0005689571 -0.0691662803 0.0334562398 226 1311867726.1506989002 0.1102975830 0.1101108074 0.1719343364 0.0043172398 0.0051670000 36755421 955859216 1373700096 0.0004323941 -0.0702122375 0.0348546132 227 1311867726.1824700832 0.1117629185 0.1101180854 0.1719343364 0.0043243419 0.0033450000 36758293 955859216 1373700096 -0.0001419325 -0.0715813711 0.0374618433 228 1311867726.2198660374 0.1132399216 0.1101317777 0.1719343364 0.0043480609 0.0054600000 36761277 955859216 1373700096 -0.0004486433 -0.0727909878 0.0395500585 229 1311867726.2506690025 0.1156752333 0.1101559849 0.1719343364 0.0043438250 0.0039900000 36764149 955859216 1373700096 -0.0003289646 -0.0749180093 0.0420603566 230 1311867726.2845950127 0.1183837876 0.1101917580 0.1719343364 0.0043479563 0.0033040000 36767021 955859216 1373700096 -0.0003235720 -0.0770193636 0.0454369970 231 1311867726.3187239170 0.1210539490 0.1102387805 0.1719343364 0.0043499875 0.0054140000 36770005 955859216 1373700096 0.0000858065 -0.0787232146 0.0480651297 232 1311867726.3524029255 0.1236436740 0.1102965602 0.1719343364 0.0043492288 0.0045130000 36772933 955859216 1373700096 0.0005877883 -0.0799779296 0.0511144921 233 1311867726.3835608959 0.1263259202 0.1103653557 0.1719343364 0.0043440833 0.0049180000 36775749 955859216 1373700096 0.0005489176 -0.0817596465 0.0539440177 234 1311867726.4218099117 0.1284302026 0.1104425559 0.1719343364 0.0043426610 0.0036520000 36778845 955859216 1373700096 0.0006800721 -0.0826065540 0.0564654320 235 1311867726.4504199028 0.1311727613 0.1105307695 0.1719343364 0.0043375004 0.0054350000 36781605 955859216 1373700096 0.0006164761 -0.0842185616 0.0597856529 236 1311867726.4843189716 0.1333858967 0.1106276133 0.1719343364 0.0043336962 0.0038550000 36784533 955859216 1373700096 0.0003760809 -0.0856899396 0.0622777380 237 1311867726.5207901001 0.1366329193 0.1107373403 0.1719343364 0.0043338876 0.0055140000 36787517 955859216 1373700096 0.0005567632 -0.0876259953 0.0658352152 238 1311867726.5524380207 0.1398953944 0.1108598532 0.1719343364 0.0043375668 0.0037490000 36790389 955859216 1373700096 0.0017634438 -0.0891586691 0.0688660517 239 1311867726.5874860287 0.1428253055 0.1109935998 0.1719343364 0.0043358409 0.0057140000 36793373 955859216 1373700096 0.0019052197 -0.0907368287 0.0722607821 240 1311867726.6204600334 0.1447140425 0.1111341017 0.1719343364 0.0043509096 0.0040480000 36796245 955859216 1373700096 0.0027216061 -0.0915530920 0.0741131306 241 1311867726.6509370804 0.1466981769 0.1112816705 0.1719343364 0.0043565562 0.0053200000 36799061 955859216 1373700096 0.0034847686 -0.0928099751 0.0756078511 242 1311867726.6916151047 0.1471134722 0.1114297357 0.1719343364 0.0043476246 0.0037120000 36802213 955859216 1373700096 0.0037769505 -0.0931837261 0.0756043270 243 1311867726.7201170921 0.1475136578 0.1115782293 0.1719343364 0.0043408054 0.0055180000 36804917 955859216 1373700096 0.0046168379 -0.0933449790 0.0754324794 244 1311867726.7513859272 0.1465696543 0.1117216367 0.1719343364 0.0043367999 0.0043440000 36807789 955859216 1373700096 0.0044066953 -0.0932176560 0.0742190406 245 1311867726.7880010605 0.1448352337 0.1118567943 0.1719343364 0.0043374350 0.0049900000 36810829 955859216 1373700096 0.0041029966 -0.0927434117 0.0721208453 246 1311867726.8198299408 0.1428650320 0.1119828440 0.1719343364 0.0043287988 0.0035320000 36813645 955859216 1373700096 0.0037907590 -0.0916544646 0.0701079294 247 1311867726.8500390053 0.1419213116 0.1121040524 0.1719343364 0.0043226852 0.0051000000 36816461 955859216 1373700096 0.0040206206 -0.0911003724 0.0687691048 248 1311867726.8927390575 0.1413287669 0.1122218940 0.1719343364 0.0043140305 0.0047660000 36819669 955859216 1373700096 0.0040873997 -0.0909817442 0.0679481626 249 1311867726.9216780663 0.1402812451 0.1123345821 0.1719343364 0.0043071825 0.0051480000 36822429 955859216 1373700096 0.0039143562 -0.0901528299 0.0672381371 250 1311867726.9543499947 0.1388563067 0.1124406690 0.1719343364 0.0043160611 0.0040390000 36825301 955859216 1373700096 0.0041150339 -0.0891099572 0.0660736337 251 1311867726.9902989864 0.1373558342 0.1125399326 0.1719343364 0.0043102729 0.0052350000 36828229 955859216 1373700096 0.0032729863 -0.0887680650 0.0645913854 252 1311867727.0208179951 0.1358610690 0.1126324768 0.1719343364 0.0043063687 0.0047660000 36831101 955859216 1373700096 0.0035246639 -0.0877103657 0.0627094582 253 1311867727.0536949635 0.1341849267 0.1127176644 0.1719343364 0.0043051752 0.0051970000 36833973 955859216 1373700096 0.0033437270 -0.0870379731 0.0609372072 254 1311867727.0911629200 0.1332678795 0.1127985707 0.1719343364 0.0043016447 0.0036630000 36837013 955859216 1373700096 0.0034814631 -0.0864076018 0.0601552390 255 1311867727.1196689606 0.1311747581 0.1128706342 0.1719343364 0.0042986099 0.0051860000 36839661 955859216 1373700096 0.0029388715 -0.0856021047 0.0577723496 256 1311867727.1514298916 0.1292767823 0.1129347207 0.1719343364 0.0042943261 0.0052240000 36842589 955859216 1373700096 0.0020723625 -0.0849601552 0.0562988073 257 1311867727.1904149055 0.1283531636 0.1129947147 0.1719343364 0.0043028089 0.0036550000 36870149 955859216 1373700096 0.0022605499 -0.0840938166 0.0560633168 258 1311867727.2208960056 0.1268246472 0.1130483191 0.1719343364 0.0042955982 0.0052350000 36924221 955859216 1373700096 0.0016704253 -0.0833130553 0.0551517233 259 1311867727.2544560432 0.1243623272 0.1130920025 0.1719343364 0.0042968093 0.0045430000 36927093 955859216 1373700096 0.0005815605 -0.0824257061 0.0525505245 260 1311867727.2870850563 0.1222896948 0.1131273782 0.1719343364 0.0042911054 0.0052390000 36930021 955859216 1373700096 -0.0000153736 -0.0813791081 0.0507379882 261 1311867727.3192501068 0.1201375946 0.1131542373 0.1719343364 0.0042891613 0.0039290000 36932893 955859216 1373700096 -0.0003054186 -0.0804820210 0.0483066328 262 1311867727.3502039909 0.1177496091 0.1131717769 0.1719343364 0.0042994713 0.0056940000 36935709 955859216 1373700096 -0.0008278334 -0.0796402022 0.0454004705 263 1311867727.3894629478 0.1147031039 0.1131775994 0.1719343364 0.0043049829 0.0036830000 36938693 955859216 1373700096 -0.0010062115 -0.0774614438 0.0424695313 264 1311867727.4182970524 0.1102355942 0.1131664555 0.1719343364 0.0043025806 0.0057680000 36941509 955859216 1373700096 -0.0024466671 -0.0751341879 0.0386375003 265 1311867727.4495580196 0.1066665128 0.1131419274 0.1719343364 0.0043067349 0.0039070000 36944269 955859216 1373700096 -0.0033299371 -0.0729029998 0.0352354608 266 1311867727.4858360291 0.1040005088 0.1131075611 0.1719343364 0.0043006284 0.0057130000 36947309 955859216 1373700096 -0.0038749247 -0.0707638860 0.0332816355 267 1311867727.5198891163 0.1014543250 0.1130639161 0.1719343364 0.0043015524 0.0037090000 36950181 955859216 1373700096 -0.0046302918 -0.0690978914 0.0309368074 268 1311867727.5494980812 0.0988893658 0.1130110260 0.1719343364 0.0043036296 0.0049120000 36952997 955859216 1373700096 -0.0060064862 -0.0683448017 0.0283066500 269 1311867727.5905909538 0.0959013999 0.1129474214 0.1719343364 0.0043039199 0.0037510000 36956149 955859216 1373700096 -0.0073222816 -0.0672910959 0.0260796063 270 1311867727.6176431179 0.0937887877 0.1128764635 0.1719343364 0.0042967096 0.0039260000 36958853 955859216 1373700096 -0.0082529159 -0.0663092136 0.0240576640 271 1311867727.6497650146 0.0912053213 0.1127964962 0.1719343364 0.0042977381 0.0038830000 36961725 955859216 1373700096 -0.0095645757 -0.0652558357 0.0216091927 272 1311867727.6884338856 0.0884084105 0.1127068341 0.1719343364 0.0042977036 0.0057940000 36964597 955859216 1373700096 -0.0114227952 -0.0643834695 0.0191799235 273 1311867727.7184689045 0.0851563960 0.1126059167 0.1719343364 0.0042916935 0.0055400000 36967469 955859216 1373700096 -0.0142777376 -0.0633069128 0.0165050104 274 1311867727.7523269653 0.0823617801 0.1124955367 0.1719343364 0.0042869876 0.0038800000 36970397 955859216 1373700096 -0.0180627406 -0.0634038150 0.0144605618 275 1311867727.7856590748 0.0801455602 0.1123779004 0.1719343364 0.0042895463 0.0058250000 36973269 955859216 1373700096 -0.0213573016 -0.0631649122 0.0144191142 276 1311867727.8181309700 0.0776734501 0.1122521596 0.1719343364 0.0043007421 0.0038610000 36976197 955859216 1373700096 -0.0245954841 -0.0623842701 0.0133870617 277 1311867727.8548729420 0.0753190368 0.1121188271 0.1719343364 0.0042985833 0.0045080000 36979181 955859216 1373700096 -0.0276824348 -0.0618070289 0.0121225649 278 1311867727.8882629871 0.0730404481 0.1119782574 0.1719343364 0.0042960735 0.0058580000 36982109 955859216 1373700096 -0.0310432371 -0.0614264607 0.0113267926 279 1311867727.9193139076 0.0715347007 0.1118332984 0.1719343364 0.0042931881 0.0038400000 36984925 955859216 1373700096 -0.0331770256 -0.0609548427 0.0109195942 280 1311867727.9556980133 0.0695564672 0.1116823097 0.1719343364 0.0042886847 0.0032240000 36987909 955859216 1373700096 -0.0359070003 -0.0604209192 0.0098431073 281 1311867727.9869389534 0.0677141473 0.1115258394 0.1719343364 0.0042841196 0.0058000000 36990837 955859216 1373700096 -0.0383314155 -0.0598290674 0.0086484347 282 1311867728.0179219246 0.0664417818 0.1113659668 0.1719343364 0.0042807555 0.0047800000 36993597 955859216 1373700096 -0.0400492661 -0.0594950430 0.0081589557 283 1311867728.0555219650 0.0653317273 0.1112033017 0.1719343364 0.0042748727 0.0035940000 36996637 955859216 1373700096 -0.0405121371 -0.0586562306 0.0077797943 284 1311867728.0892169476 0.0641841739 0.1110377414 0.1719343364 0.0042699399 0.0059230000 36999565 955859216 1373700096 -0.0416783765 -0.0581086241 0.0074107740 285 1311867728.1177880764 0.0625261739 0.1108675253 0.1719343364 0.0042789234 0.0038760000 37002381 955859216 1373700096 -0.0444532484 -0.0574885830 0.0063384669 286 1311867728.1556169987 0.0613670275 0.1106944467 0.1719343364 0.0042795064 0.0034930000 37005365 955859216 1373700096 -0.0463922471 -0.0570191555 0.0055926587 287 1311867728.1882989407 0.0603108183 0.1105188940 0.1719343364 0.0042734593 0.0034680000 37008349 955859216 1373700096 -0.0483255200 -0.0565701872 0.0045295185 288 1311867728.2182519436 0.0593893155 0.1103413607 0.1719343364 0.0042698338 0.0058460000 37011165 955859216 1373700096 -0.0500208065 -0.0561393797 0.0035001819 289 1311867728.2558999062 0.0585746765 0.1101622372 0.1719343364 0.0042641985 0.0055300000 37014149 955859216 1373700096 -0.0520258695 -0.0557542779 0.0027378276 290 1311867728.2875900269 0.0578386076 0.1099818109 0.1719343364 0.0042742303 0.0035480000 37017021 955859216 1373700096 -0.0587158464 -0.0559893139 0.0026579902 291 1311867728.3226509094 0.0568067729 0.1097990788 0.1719343364 0.0042725027 0.0059170000 37020005 955859216 1373700096 -0.0625446439 -0.0553157479 0.0020350302 292 1311867728.3597300053 0.0567933992 0.1096175525 0.1719343364 0.0042730141 0.0038910000 37022933 955859216 1373700096 -0.0654295683 -0.0553285219 0.0011525583 293 1311867728.3861401081 0.0557319559 0.1094336426 0.1719343364 0.0042725777 0.0045380000 37025693 955859216 1373700096 -0.0686539188 -0.0540478192 -0.0007577265 294 1311867728.4175701141 0.0566410571 0.1092540760 0.1719343364 0.0043299608 0.0058940000 37028565 955859216 1373700096 -0.0709467679 -0.0542122945 -0.0016981791 295 1311867728.4568250179 0.0566594936 0.1090757893 0.1719343364 0.0043248285 0.0038960000 37031605 955859216 1373700096 -0.0739901215 -0.0536523648 -0.0030939612 296 1311867728.4875330925 0.0562658906 0.1088973775 0.1719343364 0.0043200158 0.0045940000 37034421 955859216 1373700096 -0.0762162730 -0.0527248345 -0.0041787908 297 1311867728.5187420845 0.0568703376 0.1087222023 0.1719343364 0.0043142531 0.0039670000 37037237 955859216 1373700096 -0.0792295784 -0.0524629839 -0.0046282937 298 1311867728.5550920963 0.0568547472 0.1085481504 0.1719343364 0.0043094429 0.0035900000 37040277 955859216 1373700096 -0.0805137455 -0.0519639589 -0.0049151410 299 1311867728.5878560543 0.0581391193 0.1083795583 0.1719343364 0.0043089589 0.0055360000 37043205 955859216 1373700096 -0.0845262408 -0.0516114496 -0.0061309105 300 1311867728.6187679768 0.0602109246 0.1082189962 0.1719343364 0.0043150181 0.0047050000 37045965 955859216 1373700096 -0.0898104608 -0.0511981323 -0.0069772839 301 1311867728.6580820084 0.0632040426 0.1080694449 0.1719343364 0.0043298575 0.0054810000 37049061 955859216 1373700096 -0.0956687704 -0.0508375280 -0.0081164008 302 1311867728.6893489361 0.0672792718 0.1079343781 0.1719343364 0.0043338775 0.0038210000 37051933 955859216 1373700096 -0.1024507061 -0.0506773926 -0.0092686070 303 1311867728.7210168839 0.0712406784 0.1078132768 0.1719343364 0.0043344593 0.0059880000 37054805 955859216 1373700096 -0.1087488383 -0.0505170748 -0.0101201423 304 1311867728.7584259510 0.0750874430 0.1077056260 0.1719343364 0.0043410442 0.0038740000 37057789 955859216 1373700096 -0.1138583645 -0.0504435450 -0.0111395754 305 1311867728.7858450413 0.0782232955 0.1076089626 0.1719343364 0.0043424016 0.0032710000 37060605 955859216 1373700096 -0.1177887619 -0.0506309494 -0.0114446366 306 1311867728.8203740120 0.0796297863 0.1075175274 0.1719343364 0.0043404095 0.0032680000 37063477 955859216 1373700096 -0.1196899116 -0.0500698686 -0.0128892427 307 1311867728.8545160294 0.0798764378 0.1074274913 0.1719343364 0.0043338235 0.0033260000 37066405 955859216 1373700096 -0.1202040240 -0.0495273732 -0.0130612860 308 1311867728.8860759735 0.0812723786 0.1073425721 0.1719343364 0.0043288016 0.0032670000 37069333 955859216 1373700096 -0.1218858585 -0.0492674820 -0.0150012933 309 1311867728.9193949699 0.0827905312 0.1072631156 0.1719343364 0.0043237566 0.0032680000 37072149 955859216 1373700096 -0.1239393279 -0.0487116389 -0.0156240966 310 1311867728.9585559368 0.0840466544 0.1071882238 0.1719343364 0.0043467121 0.0032510000 37075357 955859216 1373700096 -0.1253548563 -0.0479778498 -0.0168631561 311 1311867728.9886839390 0.0865392461 0.1071218284 0.1719343364 0.0043437392 0.0060800000 37078061 955859216 1373700096 -0.1278480589 -0.0481583253 -0.0175647046 312 1311867729.0231020451 0.0878188238 0.1070599598 0.1719343364 0.0043404852 0.0059920000 37081045 955859216 1373700096 -0.1290197819 -0.0478864424 -0.0174475461 313 1311867729.0583839417 0.0893545076 0.1070033928 0.1719343364 0.0043392663 0.0039810000 37084029 955859216 1373700096 -0.1309584975 -0.0472574458 -0.0175445545 314 1311867729.0882170200 0.0915930867 0.1069543154 0.1719343364 0.0043349939 0.0033210000 37086845 955859216 1373700096 -0.1334867328 -0.0474253744 -0.0171796996 315 1311867729.1263229847 0.0916868001 0.1069058471 0.1719343364 0.0043496327 0.0055180000 37089885 955859216 1373700096 -0.1344996095 -0.0464589298 -0.0169308726 316 1311867729.1556320190 0.0924758464 0.1068601826 0.1719343364 0.0043440708 0.0055470000 37092645 955859216 1373700096 -0.1363371313 -0.0456864908 -0.0167554393 317 1311867729.1888830662 0.0925859883 0.1068151536 0.1719343364 0.0043780154 0.0038110000 37095573 955859216 1373700096 -0.1371770799 -0.0454763621 -0.0162444673 318 1311867729.2240469456 0.0955229551 0.1067796435 0.1719343364 0.0043873100 0.0060280000 37098501 955859216 1373700096 -0.1405181736 -0.0452916436 -0.0166132860 319 1311867729.2579979897 0.0987043977 0.1067543293 0.1719343364 0.0043820245 0.0037990000 37101485 955859216 1373700096 -0.1438644081 -0.0456725433 -0.0162232723 320 1311867729.2880148888 0.1020867601 0.1067397431 0.1719343364 0.0043785781 0.0032760000 37104301 955859216 1373700096 -0.1472782195 -0.0461804904 -0.0161233265 321 1311867729.3236539364 0.1064023152 0.1067386919 0.1719343364 0.0043799918 0.0056560000 37107229 955859216 1373700096 -0.1517097652 -0.0459211506 -0.0160930976 322 1311867729.3580930233 0.1106168851 0.1067507360 0.1719343364 0.0043944185 0.0047590000 37110213 955859216 1373700096 -0.1554749459 -0.0458933562 -0.0164563227 323 1311867729.3882780075 0.1137157232 0.1067722994 0.1719343364 0.0043931330 0.0055660000 37112973 955859216 1373700096 -0.1581996083 -0.0457157679 -0.0162661504 324 1311867729.4253289700 0.1170918792 0.1068041500 0.1719343364 0.0043921124 0.0037990000 37116013 955859216 1373700096 -0.1614790112 -0.0449071936 -0.0167786200 325 1311867729.4572670460 0.1192558557 0.1068424629 0.1719343364 0.0043905690 0.0043860000 37118885 955859216 1373700096 -0.1631059945 -0.0443245098 -0.0179798771 326 1311867729.4887750149 0.1212932989 0.1068867906 0.1719343364 0.0044019960 0.0037310000 37121813 955859216 1373700096 -0.1648703068 -0.0440144390 -0.0189835113 327 1311867729.5223650932 0.1238815263 0.1069387623 0.1719343364 0.0043987717 0.0056370000 37124685 955859216 1373700096 -0.1670818776 -0.0441391207 -0.0192261990 328 1311867729.5603790283 0.1268547028 0.1069994816 0.1719343364 0.0043966980 0.0048410000 37127725 955859216 1373700096 -0.1697210670 -0.0442577861 -0.0199276023 329 1311867729.5890150070 0.1281986982 0.1070639170 0.1719343364 0.0043907510 0.0037960000 37130485 955859216 1373700096 -0.1708040684 -0.0442575365 -0.0205784906 330 1311867729.6254830360 0.1304654330 0.1071348306 0.1719343364 0.0043879706 0.0055790000 37133469 955859216 1373700096 -0.1729639620 -0.0439786129 -0.0204882585 331 1311867729.6614611149 0.1325663477 0.1072116630 0.1719343364 0.0043831149 0.0039290000 37136453 955859216 1373700096 -0.1748973727 -0.0440095998 -0.0206200201 332 1311867729.6888220310 0.1335475147 0.1072909879 0.1719343364 0.0043780871 0.0033630000 37139101 955859216 1373700096 -0.1757941693 -0.0439284630 -0.0210135970 333 1311867729.7230739594 0.1360139400 0.1073772430 0.1719343364 0.0043742571 0.0056490000 37142085 955859216 1373700096 -0.1781253964 -0.0439833403 -0.0213188734 334 1311867729.7570610046 0.1379863173 0.1074688869 0.1719343364 0.0043712551 0.0056160000 37144845 955859216 1373700096 -0.1796909571 -0.0439623892 -0.0212925356 335 1311867729.7899730206 0.1410887837 0.1075692448 0.1719343364 0.0043662482 0.0036790000 37147773 955859216 1373700096 -0.1825027168 -0.0443497933 -0.0213648975 336 1311867729.8264250755 0.1443067193 0.1076785825 0.1719343364 0.0043693637 0.0057810000 37150701 955859216 1373700096 -0.1855247319 -0.0441010892 -0.0211453326 337 1311867729.8550031185 0.1481270939 0.1077986078 0.1719343364 0.0043689677 0.0038610000 37153461 955859216 1373700096 -0.1893014610 -0.0436356328 -0.0208509881 338 1311867729.8881840706 0.1501745135 0.1079239803 0.1719343364 0.0043662067 0.0056580000 37156445 955859216 1373700096 -0.1911718845 -0.0437552407 -0.0211526901 339 1311867729.9233629704 0.1537819207 0.1080592545 0.1719343364 0.0043627640 0.0043370000 37159373 955859216 1373700096 -0.1947429031 -0.0433023982 -0.0212854687 340 1311867729.9569330215 0.1570566595 0.1082033645 0.1719343364 0.0043635402 0.0056570000 37162301 955859216 1373700096 -0.1980601102 -0.0432005413 -0.0203658212 341 1311867729.9865698814 0.1607582718 0.1083574844 0.1719343364 0.0043615289 0.0041490000 37165061 955859216 1373700096 -0.2016227692 -0.0434990078 -0.0206513274 342 1311867730.0230469704 0.1632241607 0.1085179133 0.1719343364 0.0043568602 0.0044860000 37168045 955859216 1373700096 -0.2039951831 -0.0433275998 -0.0204897765 343 1311867730.0557899475 0.1664538831 0.1086868229 0.1719343364 0.0043555494 0.0057140000 37170973 955859216 1373700096 -0.2072855383 -0.0429682694 -0.0199388415 344 1311867730.0871100426 0.1691283584 0.1088625250 0.1719343364 0.0043514372 0.0040810000 37173845 955859216 1373700096 -0.2097774744 -0.0429255329 -0.0202309303 345 1311867730.1231229305 0.1708437651 0.1090421808 0.1719343364 0.0043466226 0.0043700000 37176829 955859216 1373700096 -0.2113718837 -0.0428214259 -0.0200100075 346 1311867730.1568520069 0.1725236773 0.1092256533 0.1725236773 0.0043409887 0.0043730000 37179757 955859216 1373700096 -0.2130522728 -0.0426949896 -0.0193542037 347 1311867730.1882419586 0.1749149710 0.1094149597 0.1749149710 0.0043384241 0.0037380000 37182573 955859216 1373700096 -0.2153770328 -0.0420764685 -0.0196816139 348 1311867730.2224810123 0.1775982082 0.1096108886 0.1775982082 0.0043340183 0.0057120000 37185557 955859216 1373700096 -0.2181345075 -0.0416717865 -0.0191436429 349 1311867730.2575879097 0.1794708073 0.1098110602 0.1794708073 0.0043287224 0.0043880000 37188485 955859216 1373700096 -0.2201456279 -0.0410185941 -0.0190107059 350 1311867730.2914879322 0.1798949540 0.1100112999 0.1798949540 0.0043243907 0.0037660000 37191413 955859216 1373700096 -0.2205195874 -0.0404067934 -0.0192564894 351 1311867730.3230810165 0.1800456345 0.1102108280 0.1800456345 0.0043222580 0.0037770000 37194285 955859216 1373700096 -0.2206547409 -0.0400851928 -0.0194509830 352 1311867730.3554260731 0.1824346781 0.1104160094 0.1824346781 0.0043245489 0.0057010000 37197157 955859216 1373700096 -0.2226973623 -0.0403537191 -0.0192727987 353 1311867730.3982920647 0.1825911105 0.1106204714 0.1825911105 0.0043224090 0.0057210000 37200309 955859216 1373700096 -0.2226805240 -0.0399229154 -0.0190572981 354 1311867730.4225230217 0.1835688800 0.1108265403 0.1835688800 0.0043233168 0.0037850000 37203013 955859216 1373700096 -0.2239360660 -0.0390942506 -0.0186161026 355 1311867730.4600110054 0.1835785359 0.1110314755 0.1835785359 0.0043176117 0.0057270000 37205997 955859216 1373700096 -0.2239392698 -0.0391959175 -0.0186042376 356 1311867730.4948410988 0.1853266358 0.1112401698 0.1853266358 0.0043189868 0.0038880000 37208925 955859216 1373700096 -0.2254082859 -0.0394638292 -0.0183927771 357 1311867730.5300729275 0.1865641326 0.1114511613 0.1865641326 0.0043134421 0.0057450000 37211853 955859216 1373700096 -0.2264636904 -0.0392857306 -0.0182324164 358 1311867730.5597670078 0.1861594915 0.1116598438 0.1865641326 0.0043079863 0.0046830000 37214669 955859216 1373700096 -0.2259026021 -0.0390621610 -0.0184968822 359 1311867730.5940020084 0.1888150126 0.1118747607 0.1888150126 0.0043065557 0.0045130000 37217653 955859216 1373700096 -0.2283744365 -0.0391034037 -0.0182644054 360 1311867730.6230149269 0.1887325943 0.1120882547 0.1888150126 0.0043061687 0.0038120000 37220357 955859216 1373700096 -0.2281262130 -0.0382284299 -0.0185032189 361 1311867730.6614060402 0.1920401752 0.1123097281 0.1920401752 0.0043039871 0.0057460000 37223397 955859216 1373700096 -0.2310581356 -0.0383214466 -0.0178607907 362 1311867730.6922950745 0.1929081678 0.1125323758 0.1929081678 0.0042983061 0.0038680000 37226269 955859216 1373700096 -0.2315548360 -0.0382119603 -0.0177785922 363 1311867730.7275629044 0.1945759207 0.1127583910 0.1945759207 0.0042978591 0.0034030000 37229197 955859216 1373700096 -0.2328482121 -0.0381158702 -0.0181575511 364 1311867730.7572948933 0.1953235269 0.1129852183 0.1953235269 0.0042929481 0.0057360000 37232013 955859216 1373700096 -0.2332130522 -0.0373603962 -0.0182517413 365 1311867730.7932779789 0.1968817860 0.1132150719 0.1968817860 0.0042879350 0.0057730000 37235053 955859216 1373700096 -0.2341690212 -0.0369618796 -0.0186241381 366 1311867730.8240480423 0.1963434219 0.1134421986 0.1968817860 0.0042828849 0.0036290000 37237813 955859216 1373700096 -0.2325617075 -0.0378024876 -0.0194738228 367 1311867730.8591129780 0.1960925758 0.1136674040 0.1968817860 0.0042780372 0.0057890000 37240797 955859216 1373700096 -0.2316771448 -0.0371944346 -0.0196409002 368 1311867730.8922739029 0.1971670389 0.1138943052 0.1971670389 0.0042749467 0.0054790000 37243557 955859216 1373700096 -0.2321617901 -0.0363675468 -0.0191214960 369 1311867730.9270720482 0.1982868016 0.1141230111 0.1982868016 0.0042746023 0.0034700000 37246541 955859216 1373700096 -0.2325678319 -0.0357347988 -0.0184440780 370 1311867730.9611239433 0.1997799426 0.1143545163 0.1997799426 0.0042745923 0.0063330000 37249413 955859216 1373700096 -0.2334554493 -0.0351383165 -0.0179209281 371 1311867730.9928169250 0.2004931569 0.1145866960 0.2004931569 0.0042750681 0.0042740000 37252285 955859216 1373700096 -0.2334526181 -0.0352869816 -0.0174762830 372 1311867731.0221049786 0.2022858858 0.1148224465 0.2022858858 0.0042723628 0.0036340000 37255101 955859216 1373700096 -0.2346475422 -0.0354010016 -0.0174121074 373 1311867731.0609729290 0.2046641707 0.1150633090 0.2046641707 0.0042699751 0.0033320000 37258141 955859216 1373700096 -0.2363361418 -0.0349790454 -0.0169522353 374 1311867731.0900061131 0.2043646723 0.1153020827 0.2046641707 0.0042691748 0.0058520000 37260901 955859216 1373700096 -0.2354014218 -0.0348859988 -0.0173967350 375 1311867731.1276559830 0.2044440806 0.1155397947 0.2046641707 0.0042652868 0.0052350000 37263941 955859216 1373700096 -0.2345977724 -0.0353585668 -0.0173985846 376 1311867731.1551880836 0.2056565285 0.1157794669 0.2056565285 0.0042602905 0.0038370000 37266701 955859216 1373700096 -0.2354763746 -0.0346766822 -0.0165866949 377 1311867731.1935870647 0.2061167359 0.1160190883 0.2061167359 0.0042573860 0.0036630000 37269685 955859216 1373700096 -0.2353764176 -0.0344239809 -0.0160194077 378 1311867731.2235820293 0.2067466229 0.1162591082 0.2067466229 0.0042521487 0.0036350000 37272557 955859216 1373700096 -0.2354600132 -0.0344164483 -0.0150981685 379 1311867731.2602028847 0.2082989514 0.1165019574 0.2082989514 0.0042504086 0.0063770000 37275485 955859216 1373700096 -0.2361260653 -0.0345859528 -0.0144653423 380 1311867731.2900059223 0.2092989087 0.1167461599 0.2092989087 0.0042849218 0.0055770000 37278301 955859216 1373700096 -0.2358785570 -0.0349144079 -0.0134591730 381 1311867731.3230779171 0.2075333595 0.1169844465 0.2092989087 0.0043693877 0.0039570000 37281229 955859216 1373700096 -0.2337340117 -0.0350576639 -0.0137752853 382 1311867731.3570859432 0.2051488906 0.1172152435 0.2092989087 0.0044094592 0.0034620000 37284213 955859216 1373700096 -0.2306015342 -0.0349847190 -0.0149747599 383 1311867731.3915760517 0.2046185434 0.1174434505 0.2092989087 0.0044053094 0.0059040000 37287085 955859216 1373700096 -0.2293038815 -0.0363828316 -0.0137859536 384 1311867731.4279849529 0.2060127556 0.1176740998 0.2092989087 0.0044247933 0.0057620000 37290125 955859216 1373700096 -0.2300942689 -0.0367983729 -0.0148884123 385 1311867731.4602010250 0.2072527558 0.1179067716 0.2092989087 0.0044400250 0.0036630000 37292997 955859216 1373700096 -0.2307538688 -0.0372717157 -0.0162015203 386 1311867731.4926180840 0.2085927725 0.1181417094 0.2092989087 0.0044512990 0.0054460000 37295869 955859216 1373700096 -0.2315378636 -0.0375624672 -0.0163803454 387 1311867731.5259540081 0.2116656750 0.1183833734 0.2116656750 0.0044529256 0.0043530000 37298741 955859216 1373700096 -0.2338476926 -0.0384189896 -0.0148318941 388 1311867731.5589148998 0.2142487317 0.1186304491 0.2142487317 0.0044522144 0.0059950000 37301613 955859216 1373700096 -0.2355507016 -0.0389280058 -0.0142855905 389 1311867731.5967359543 0.2174567282 0.1188845012 0.2174567282 0.0044584263 0.0040520000 37304709 955859216 1373700096 -0.2386127859 -0.0398298949 -0.0129856002 390 1311867731.6247410774 0.2213965952 0.1191473527 0.2213965952 0.0044783073 0.0037610000 37307413 955859216 1373700096 -0.2420251817 -0.0405107290 -0.0123652034 391 1311867731.6616659164 0.2242751867 0.1194162219 0.2242751867 0.0044874485 0.0037230000 37310453 955859216 1373700096 -0.2442963570 -0.0408558734 -0.0114347795 392 1311867731.6925039291 0.2274687588 0.1196918661 0.2274687588 0.0044830718 0.0037030000 37313269 955859216 1373700096 -0.2472520620 -0.0410558432 -0.0102872616 393 1311867731.7299311161 0.2294608355 0.1199711764 0.2294608355 0.0044827230 0.0060250000 37316309 955859216 1373700096 -0.2486288697 -0.0413783155 -0.0098647447 394 1311867731.7615330219 0.2309946120 0.1202529618 0.2309946120 0.0044773679 0.0053130000 37319181 955859216 1373700096 -0.2496103048 -0.0420441478 -0.0094241882 395 1311867731.7939310074 0.2318037152 0.1205353688 0.2318037152 0.0044721871 0.0045790000 37322053 955859216 1373700096 -0.2498637587 -0.0422758684 -0.0087294150 396 1311867731.8252151012 0.2320621759 0.1208170021 0.2320621759 0.0044686326 0.0039380000 37324869 955859216 1373700096 -0.2496023923 -0.0435242206 -0.0079220543 397 1311867731.8593230247 0.2316768765 0.1210962462 0.2320621759 0.0044693900 0.0041670000 37327797 955859216 1373700096 -0.2484239489 -0.0441810042 -0.0072678137 398 1311867731.8910930157 0.2303713709 0.1213708068 0.2320621759 0.0044788851 0.0041830000 37330725 955859216 1373700096 -0.2467569709 -0.0449220873 -0.0065020248 399 1311867731.9224479198 0.2275045365 0.1216368061 0.2320621759 0.0044775191 0.0053430000 37333597 955859216 1373700096 -0.2433409095 -0.0459870994 -0.0059755221 400 1311867731.9598410130 0.2248314619 0.1218947927 0.2320621759 0.0044791409 0.0042210000 37336525 955859216 1373700096 -0.2399839312 -0.0468247570 -0.0050202031 401 1311867731.9915709496 0.2226104736 0.1221459540 0.2320621759 0.0044776472 0.0042540000 37339397 955859216 1373700096 -0.2371749729 -0.0475187302 -0.0033063577 402 1311867732.0239229202 0.2202912569 0.1223900966 0.2320621759 0.0044907122 0.0042300000 37342269 955859216 1373700096 -0.2340150923 -0.0486836992 -0.0024543137 403 1311867732.0619950294 0.2167973965 0.1226243579 0.2320621759 0.0045000116 0.0040960000 37345309 955859216 1373700096 -0.2298028171 -0.0498302057 -0.0018792903 404 1311867732.0918290615 0.2138509005 0.1228501661 0.2320621759 0.0044992485 0.0061750000 37348125 955859216 1373700096 -0.2259057462 -0.0506698266 -0.0009747685 405 1311867732.1221950054 0.2101608813 0.1230657482 0.2320621759 0.0045140028 0.0050210000 37350997 955859216 1373700096 -0.2216070890 -0.0519965924 -0.0006158447 406 1311867732.1605980396 0.2073476315 0.1232733390 0.2320621759 0.0045280892 0.0054760000 37353981 955859216 1373700096 -0.2182464749 -0.0526255183 -0.0003826169 407 1311867732.1931400299 0.2061653137 0.1234770048 0.2320621759 0.0045405208 0.0039770000 37356909 955859216 1373700096 -0.2160182297 -0.0533009656 0.0001883779 408 1311867732.2232089043 0.2037534565 0.1236737608 0.2320621759 0.0046152013 0.0035510000 37359669 955859216 1373700096 -0.2135319412 -0.0538409166 -0.0001742120 409 1311867732.2590498924 0.2031669915 0.1238681208 0.2320621759 0.0046654686 0.0062110000 37362653 955859216 1373700096 -0.2119636387 -0.0542481057 0.0002844626 410 1311867732.2903969288 0.2014153153 0.1240572603 0.2320621759 0.0047257963 0.0055260000 37365525 955859216 1373700096 -0.2100443691 -0.0543118119 0.0004568965 411 1311867732.3218240738 0.2008606642 0.1242441299 0.2320621759 0.0047549714 0.0039780000 37368397 955859216 1373700096 -0.2087758929 -0.0548016727 0.0000311741 412 1311867732.3607840538 0.2004900724 0.1244291928 0.2320621759 0.0047502762 0.0061550000 37371437 955859216 1373700096 -0.2074178457 -0.0552250668 0.0005241156 413 1311867732.3899528980 0.2019055337 0.1246167869 0.2320621759 0.0047543603 0.0052550000 37374197 955859216 1373700096 -0.2082234025 -0.0557072535 0.0007064643 414 1311867732.4218940735 0.2031238824 0.1248064175 0.2320621759 0.0047559554 0.0047400000 37377125 955859216 1373700096 -0.2083240896 -0.0569009557 0.0007727004 415 1311867732.4593050480 0.2038213760 0.1249968150 0.2320621759 0.0047561103 0.0035860000 37380109 955859216 1373700096 -0.2083427906 -0.0574224442 0.0010255668 416 1311867732.4918489456 0.2050314397 0.1251892060 0.2320621759 0.0047531894 0.0040380000 37383037 955859216 1373700096 -0.2085734159 -0.0583802238 0.0010829762 417 1311867732.5229809284 0.2066187710 0.1253844807 0.2320621759 0.0047546818 0.0037680000 37385853 955859216 1373700096 -0.2092119306 -0.0591094121 0.0011803157 418 1311867732.5698928833 0.2078037113 0.1255816559 0.2320621759 0.0047515210 0.0036340000 37389117 955859216 1373700096 -0.2095354795 -0.0591326356 0.0016361469 419 1311867732.5926280022 0.2088966519 0.1257804984 0.2320621759 0.0047462344 0.0036530000 37391765 955859216 1373700096 -0.2102195770 -0.0595524497 0.0020579519 420 1311867732.6242370605 0.2092714608 0.1259792864 0.2320621759 0.0047518101 0.0062450000 37394637 955859216 1373700096 -0.2099972069 -0.0600131489 0.0016817494 421 1311867732.6630299091 0.2098443210 0.1261784907 0.2320621759 0.0047663091 0.0062170000 37397677 955859216 1373700096 -0.2099514157 -0.0603080578 0.0019292940 422 1311867732.6922440529 0.2088656723 0.1263744319 0.2320621759 0.0047685441 0.0047680000 37400493 955859216 1373700096 -0.2086991221 -0.0598605461 0.0022721922 423 1311867732.7260940075 0.2099428624 0.1265719932 0.2320621759 0.0047632784 0.0036510000 37403421 955859216 1373700096 -0.2092607617 -0.0605823994 0.0025234588 424 1311867732.7601239681 0.2103906125 0.1267696786 0.2320621759 0.0047586252 0.0037310000 37406293 955859216 1373700096 -0.2093728185 -0.0609941743 0.0023739729 425 1311867732.7919039726 0.2115726471 0.1269692150 0.2320621759 0.0047545200 0.0062760000 37409221 955859216 1373700096 -0.2104177326 -0.0607164353 0.0026192185 426 1311867732.8280360699 0.2112162262 0.1271669780 0.2320621759 0.0047560309 0.0059350000 37412149 955859216 1373700096 -0.2098541111 -0.0604786240 0.0021665124 427 1311867732.8589270115 0.2107218802 0.1273626569 0.2320621759 0.0047506352 0.0037370000 37415021 955859216 1373700096 -0.2093229443 -0.0604544878 0.0020456042 428 1311867732.8912909031 0.2108940035 0.1275578236 0.2320621759 0.0047457062 0.0034090000 37417893 955859216 1373700096 -0.2094162554 -0.0600857586 0.0022396964 429 1311867732.9262781143 0.2101738155 0.1277504017 0.2320621759 0.0047464687 0.0062960000 37420877 955859216 1373700096 -0.2086152136 -0.0593372472 0.0024713858 430 1311867732.9602870941 0.2103608549 0.1279425190 0.2320621759 0.0047475982 0.0059560000 37423749 955859216 1373700096 -0.2084484249 -0.0598869622 0.0027130696 431 1311867732.9987640381 0.2104027867 0.1281338421 0.2320621759 0.0047485126 0.0037570000 37426845 955859216 1373700096 -0.2083491683 -0.0600248314 0.0028772191 432 1311867733.0276939869 0.2112685591 0.1283262836 0.2320621759 0.0047434315 0.0063710000 37429661 955859216 1373700096 -0.2091619819 -0.0597244576 0.0036085313 433 1311867733.0607628822 0.2119802684 0.1285194799 0.2320621759 0.0047609493 0.0046970000 37432533 955859216 1373700096 -0.2095723748 -0.0604434125 0.0036130568 434 1311867733.0977020264 0.2128377855 0.1287137617 0.2320621759 0.0047569976 0.0037090000 37435517 955859216 1373700096 -0.2102709711 -0.0604448058 0.0036239242 435 1311867733.1263020039 0.2141264379 0.1289101127 0.2320621759 0.0047533187 0.0037510000 37438277 955859216 1373700096 -0.2116446644 -0.0598513931 0.0040277452 436 1311867733.1625030041 0.2160040140 0.1291098693 0.2320621759 0.0047588059 0.0063900000 37441261 955859216 1373700096 -0.2131701559 -0.0608667210 0.0037384403 437 1311867733.1926651001 0.2179584801 0.1293131842 0.2320621759 0.0047536948 0.0056680000 37444077 955859216 1373700096 -0.2150955647 -0.0609133653 0.0038225567 438 1311867733.2259631157 0.2203672379 0.1295210702 0.2320621759 0.0047492037 0.0041900000 37447005 955859216 1373700096 -0.2172731757 -0.0606926866 0.0042627966 439 1311867733.2618060112 0.2230933160 0.1297342188 0.2320621759 0.0047507908 0.0063910000 37449989 955859216 1373700096 -0.2197252959 -0.0608529449 0.0043259584 440 1311867733.2919199467 0.2249349803 0.1299505842 0.2320621759 0.0047511122 0.0040210000 37452749 955859216 1373700096 -0.2214303017 -0.0609551556 0.0039857901 441 1311867733.3300418854 0.2270826697 0.1301708383 0.2320621759 0.0047650303 0.0038070000 37455789 955859216 1373700096 -0.2232674211 -0.0609592497 0.0040857736 442 1311867733.3602790833 0.2292418629 0.1303949809 0.2320621759 0.0047674611 0.0037610000 37458661 955859216 1373700096 -0.2250323892 -0.0614319853 0.0036808334 443 1311867733.3923840523 0.2315867841 0.1306234049 0.2320621759 0.0047626624 0.0064750000 37461533 955859216 1373700096 -0.2269266248 -0.0616112389 0.0033668960 444 1311867733.4289550781 0.2344459444 0.1308572394 0.2344459444 0.0047648912 0.0054660000 37464517 955859216 1373700096 -0.2294944674 -0.0610358790 0.0034145743 445 1311867733.4588150978 0.2377705276 0.1310974940 0.2377705276 0.0047609243 0.0042330000 37467221 955859216 1373700096 -0.2326771617 -0.0609566532 0.0033412254 446 1311867733.4956119061 0.2408483922 0.1313435722 0.2408483922 0.0047578137 0.0040270000 37470093 955859216 1373700096 -0.2355686575 -0.0608655997 0.0033659651 447 1311867733.5290400982 0.2426427305 0.1315925636 0.2426427305 0.0047580016 0.0038870000 37473021 955859216 1373700096 -0.2372815609 -0.0602816455 0.0034998406 448 1311867733.5630290508 0.2457285523 0.1318473315 0.2457285523 0.0047561063 0.0040190000 37475949 955859216 1373700096 -0.2400682420 -0.0603646971 0.0033737752 449 1311867733.5922229290 0.2486318797 0.1321074307 0.2486318797 0.0047538262 0.0039690000 37478709 955859216 1373700096 -0.2426020503 -0.0611454509 0.0033879313 450 1311867733.6283020973 0.2508564889 0.1323713175 0.2508564889 0.0047515645 0.0069800000 37481693 955859216 1373700096 -0.2445247471 -0.0613688603 0.0034978837 451 1311867733.6601879597 0.2531604767 0.1326391427 0.2531604767 0.0047477430 0.0066470000 37484565 955859216 1373700096 -0.2465880960 -0.0615369119 0.0039071948 452 1311867733.6917510033 0.2557816207 0.1329115818 0.2557816207 0.0047448791 0.0040930000 37487437 955859216 1373700096 -0.2489345521 -0.0615383983 0.0037721286 453 1311867733.7288239002 0.2578726113 0.1331874339 0.2578726113 0.0047416288 0.0034920000 37490421 955859216 1373700096 -0.2505252659 -0.0616207831 0.0038007421 454 1311867733.7597820759 0.2602586746 0.1334673265 0.2602586746 0.0047376340 0.0032000000 37493181 955859216 1373700096 -0.2525115907 -0.0618291236 0.0039619738 455 1311867733.7924160957 0.2621115446 0.1337500611 0.2621115446 0.0047474227 0.0033760000 37496053 955859216 1373700096 -0.2539720833 -0.0619750693 0.0043309503 456 1311867733.8282589912 0.2641746402 0.1340360799 0.2641746402 0.0047429852 0.0033090000 37499037 955859216 1373700096 -0.2552626431 -0.0623042509 0.0035917852 457 1311867733.8608579636 0.2672607005 0.1343275999 0.2672607005 0.0047409343 0.0033450000 37501797 955859216 1373700096 -0.2579494119 -0.0623739585 0.0035222806 458 1311867733.8918149471 0.2690124214 0.1346216715 0.2690124214 0.0047358326 0.0033240000 37504557 955859216 1373700096 -0.2593205273 -0.0621212125 0.0033374070 459 1311867733.9289460182 0.2721436918 0.1349212838 0.2721436918 0.0047316599 0.0033410000 37507541 955859216 1373700096 -0.2618174553 -0.0625512898 0.0033246586 460 1311867733.9595899582 0.2746021748 0.1352249379 0.2746021748 0.0047333178 0.0070670000 37510413 955859216 1373700096 -0.2640570104 -0.0623595752 0.0030880431 461 1311867733.9941790104 0.2771781385 0.1355328624 0.2771781385 0.0047438930 0.0065650000 37513341 955859216 1373700096 -0.2657516301 -0.0625793710 0.0034246156 462 1311867734.0275731087 0.2793393731 0.1358441319 0.2793393731 0.0047458610 0.0049550000 37516325 955859216 1373700096 -0.2677718997 -0.0629899129 0.0034334713 463 1311867734.0599920750 0.2804315388 0.1361564157 0.2804315388 0.0047416161 0.0048220000 37519141 955859216 1373700096 -0.2686357498 -0.0625090599 0.0034621863 464 1311867734.0956780910 0.2830368876 0.1364729685 0.2830368876 0.0047374692 0.0038380000 37522125 955859216 1373700096 -0.2709944248 -0.0622457042 0.0035096328 465 1311867734.1274170876 0.2855022550 0.1367934615 0.2855022550 0.0047335403 0.0035630000 37525053 955859216 1373700096 -0.2730065584 -0.0630791187 0.0030779829 466 1311867734.1618878841 0.2872929573 0.1371164218 0.2872929573 0.0047299060 0.0072160000 37527925 955859216 1373700096 -0.2744664550 -0.0629169792 0.0028775639 467 1311867734.1942350864 0.2897138298 0.1374431829 0.2897138298 0.0047266492 0.0046940000 37530853 955859216 1373700096 -0.2765373290 -0.0624825172 0.0030057763 468 1311867734.2291829586 0.2917960584 0.1377729967 0.2917960584 0.0047294271 0.0037310000 37533725 955859216 1373700096 -0.2781885564 -0.0633778721 0.0027294003 469 1311867734.2607750893 0.2932876050 0.1381045844 0.2932876050 0.0047247043 0.0065840000 37536597 955859216 1373700096 -0.2793639898 -0.0633634925 0.0026425666 470 1311867734.2941219807 0.2951695323 0.1384387651 0.2951695323 0.0047199841 0.0043440000 37539469 955859216 1373700096 -0.2810836732 -0.0628833398 0.0028258008 471 1311867734.3263280392 0.2975720465 0.1387766277 0.2975720465 0.0047193776 0.0050630000 37542341 955859216 1373700096 -0.2832012773 -0.0630773380 0.0031176251 472 1311867734.3610401154 0.2988180816 0.1391156986 0.2988180816 0.0047165858 0.0043550000 37545269 955859216 1373700096 -0.2842433453 -0.0628250837 0.0031693229 473 1311867734.3941841125 0.2990432978 0.1394538119 0.2990432978 0.0047156505 0.0066840000 37548197 955859216 1373700096 -0.2844185233 -0.0619706213 0.0034593339 474 1311867734.4276480675 0.3011082411 0.1397948550 0.3011082411 0.0047113816 0.0052720000 37551125 955859216 1373700096 -0.2862165272 -0.0625588968 0.0038353025 475 1311867734.4586091042 0.3020241261 0.1401363903 0.3020241261 0.0047088109 0.0039460000 37553941 955859216 1373700096 -0.2868968248 -0.0632125661 0.0039238613 476 1311867734.4938759804 0.3029951751 0.1404785306 0.3029951751 0.0047043271 0.0033470000 37556925 955859216 1373700096 -0.2876178026 -0.0627950430 0.0044685206 477 1311867734.5300569534 0.3032754064 0.1408198238 0.3032754064 0.0047017519 0.0034160000 37559909 955859216 1373700096 -0.2876191139 -0.0628386438 0.0048059411 478 1311867734.5595300198 0.3050661087 0.1411634353 0.3050661087 0.0047055249 0.0066750000 37562669 955859216 1373700096 -0.2889177799 -0.0631906167 0.0050883796 479 1311867734.5953910351 0.3046382964 0.1415047190 0.3050661087 0.0047025163 0.0066880000 37565597 955859216 1373700096 -0.2887159586 -0.0629386678 0.0054235961 480 1311867734.6285231113 0.3052625060 0.1418458810 0.3052625060 0.0046994220 0.0067190000 37568525 955859216 1373700096 -0.2887592614 -0.0633793250 0.0055497983 481 1311867734.6593229771 0.3056477904 0.1421864255 0.3056477904 0.0046946979 0.0072170000 37571341 955859216 1373700096 -0.2890623212 -0.0639694035 0.0055276547 482 1311867734.6947479248 0.3065007329 0.1425273266 0.3065007329 0.0046899250 0.0070960000 37574269 955859216 1373700096 -0.2899382114 -0.0646543056 0.0055807224 483 1311867734.7310240269 0.3077833951 0.1428694716 0.3077833951 0.0046888261 0.0046540000 37577309 955859216 1373700096 -0.2909040451 -0.0642618313 0.0057408134 484 1311867734.7607629299 0.3074922264 0.1432096013 0.3077833951 0.0046848921 0.0037280000 37580069 955859216 1373700096 -0.2901501954 -0.0641137213 0.0055752457 485 1311867734.7976419926 0.3078801930 0.1435491283 0.3078801930 0.0046818741 0.0034170000 37583109 955859216 1373700096 -0.2903801501 -0.0638716295 0.0058207233 486 1311867734.8298120499 0.3088446558 0.1438892425 0.3088446558 0.0046781490 0.0067380000 37585981 955859216 1373700096 -0.2910868824 -0.0636128783 0.0060232836 487 1311867734.8645250797 0.3090475202 0.1442283766 0.3090475202 0.0046742247 0.0044300000 37588909 955859216 1373700096 -0.2910142243 -0.0635301992 0.0064519187 488 1311867734.8943901062 0.3097592592 0.1445675792 0.3097592592 0.0046716672 0.0061010000 37591781 955859216 1373700096 -0.2913869321 -0.0639362931 0.0064649242 489 1311867734.9263660908 0.3105100691 0.1449069299 0.3105100691 0.0046669432 0.0039560000 37594597 955859216 1373700096 -0.2918356061 -0.0640323311 0.0066663101 490 1311867734.9631719589 0.3114655018 0.1452468454 0.3114655018 0.0046646069 0.0067320000 37597357 955859216 1373700096 -0.2922506928 -0.0639595538 0.0065115578 491 1311867734.9948470592 0.3113849461 0.1455852122 0.3114655018 0.0046673668 0.0043960000 37600229 955859216 1373700096 -0.2924213409 -0.0645235851 0.0061726482 492 1311867735.0292239189 0.3124457896 0.1459243597 0.3124457896 0.0046688824 0.0035550000 37603269 955859216 1373700096 -0.2931115627 -0.0645300224 0.0061329487 493 1311867735.0596508980 0.3124496043 0.1462621391 0.3124496043 0.0046651141 0.0067800000 37605973 955859216 1373700096 -0.2932664752 -0.0642623007 0.0061927564 494 1311867735.0952830315 0.3134299815 0.1466005355 0.3134299815 0.0046618531 0.0056570000 37608957 955859216 1373700096 -0.2941856086 -0.0647185892 0.0062626377 495 1311867735.1313030720 0.3154290020 0.1469416031 0.3154290020 0.0046623112 0.0039950000 37611941 955859216 1373700096 -0.2960813940 -0.0649582818 0.0067740553 496 1311867735.1603751183 0.3156024516 0.1472816452 0.3156024516 0.0046579851 0.0068990000 37614701 955859216 1373700096 -0.2961473763 -0.0649650246 0.0069795083 497 1311867735.1994349957 0.3155209124 0.1476201548 0.3156024516 0.0046571077 0.0049720000 37617741 955859216 1373700096 -0.2958501577 -0.0653864071 0.0068760621 498 1311867735.2263538837 0.3151496351 0.1479565593 0.3156024516 0.0046544308 0.0039010000 37620557 955859216 1373700096 -0.2954472005 -0.0648548380 0.0072738859 499 1311867735.2655019760 0.3149491549 0.1482912138 0.3156024516 0.0046507858 0.0068780000 37623541 955859216 1373700096 -0.2950787842 -0.0646362379 0.0077612139 500 1311867735.2961549759 0.3157877922 0.1486262070 0.3157877922 0.0046512220 0.0044370000 37626413 955859216 1373700096 -0.2958345115 -0.0650516823 0.0081005357 501 1311867735.3321089745 0.3159595132 0.1489602056 0.3159595132 0.0046516208 0.0055760000 37629397 955859216 1373700096 -0.2959185541 -0.0647492930 0.0085622473 502 1311867735.3666970730 0.3161719739 0.1492932968 0.3161719739 0.0046569626 0.0056340000 37632213 955859216 1373700096 -0.2959323227 -0.0648766607 0.0088261254 503 1311867735.3943350315 0.3167835176 0.1496262793 0.3167835176 0.0046649474 0.0059350000 37634917 955859216 1373700096 -0.2963851094 -0.0646779910 0.0091558825 504 1311867735.4322299957 0.3177860081 0.1499599296 0.3177860081 0.0046630625 0.0044990000 37638013 955859216 1373700096 -0.2972821593 -0.0646099299 0.0095756073 505 1311867735.4628560543 0.3206896782 0.1502980083 0.3206896782 0.0046768030 0.0068850000 37640829 955859216 1373700096 -0.2993105650 -0.0655675456 0.0101407589 506 1311867735.4973869324 0.3209184408 0.1506352028 0.3209184408 0.0046814630 0.0042860000 37643813 955859216 1373700096 -0.2998100817 -0.0659653619 0.0106285643 507 1311867735.5293200016 0.3217783272 0.1509727632 0.3217783272 0.0046778113 0.0036130000 37646629 955859216 1373700096 -0.3004000187 -0.0662976056 0.0111232577 508 1311867735.5632629395 0.3219130635 0.1513092599 0.3219130635 0.0046737040 0.0068850000 37649613 955859216 1373700096 -0.3003124595 -0.0664248019 0.0113711040 509 1311867735.5976569653 0.3229081929 0.1516463894 0.3229081929 0.0046704080 0.0045440000 37652541 955859216 1373700096 -0.3010239899 -0.0669636205 0.0117896320 510 1311867735.6363260746 0.3226016760 0.1519815959 0.3229081929 0.0046699651 0.0039260000 37655525 955859216 1373700096 -0.3005211949 -0.0670642406 0.0117913205 511 1311867735.6626520157 0.3236291111 0.1523175010 0.3236291111 0.0046666731 0.0036500000 37658285 955859216 1373700096 -0.3012546301 -0.0678977743 0.0116864620 512 1311867735.6952130795 0.3248447776 0.1526544683 0.3248447776 0.0046631874 0.0068520000 37661157 955859216 1373700096 -0.3022330999 -0.0691562667 0.0115252873 513 1311867735.7291250229 0.3257765174 0.1529919382 0.3257765174 0.0046615512 0.0060610000 37713237 955859216 1373700096 -0.3029710054 -0.0691897273 0.0114265978 514 1311867735.7631659508 0.3254455626 0.1533274511 0.3257765174 0.0046584046 0.0040170000 37818621 955859216 1373700096 -0.3026172817 -0.0687235966 0.0113902371 515 1311867735.7963778973 0.3262550533 0.1536632328 0.3262550533 0.0046563440 0.0069540000 37821493 955859216 1373700096 -0.3031632304 -0.0690041855 0.0113513628 516 1311867735.8277759552 0.3272990584 0.1539997364 0.3272990584 0.0046607675 0.0050360000 37824309 955859216 1373700096 -0.3040955067 -0.0682640299 0.0115296561 517 1311867735.8638889790 0.3275337815 0.1543353922 0.3275337815 0.0046570783 0.0037670000 37827125 955859216 1373700096 -0.3042701185 -0.0675482228 0.0120484037 518 1311867735.8951849937 0.3278912604 0.1546704421 0.3278912604 0.0046526283 0.0069540000 37829997 955859216 1373700096 -0.3046345413 -0.0671233758 0.0124873072 519 1311867735.9322230816 0.3284680545 0.1550053123 0.3284680545 0.0046490102 0.0046000000 37833037 955859216 1373700096 -0.3052051663 -0.0667799935 0.0131579898 520 1311867735.9623689651 0.3280071318 0.1553380081 0.3284680545 0.0046485117 0.0037520000 37835853 955859216 1373700096 -0.3049271405 -0.0665733665 0.0135568324 521 1311867735.9945859909 0.3279283345 0.1556692755 0.3284680545 0.0046458215 0.0074110000 37838669 955859216 1373700096 -0.3049982488 -0.0661554113 0.0140095269 522 1311867736.0290079117 0.3280262947 0.1559994614 0.3284680545 0.0046438984 0.0044400000 37841653 955859216 1373700096 -0.3051885068 -0.0660390407 0.0144892726 523 1311867736.0642199516 0.3285976350 0.1563294770 0.3285976350 0.0046414973 0.0037760000 37844637 955859216 1373700096 -0.3057666123 -0.0660481825 0.0148340333 524 1311867736.0946779251 0.3293257058 0.1566596225 0.3293257058 0.0046373156 0.0069130000 37847397 955859216 1373700096 -0.3066023290 -0.0660202056 0.0153104598 525 1311867736.1299190521 0.3303539455 0.1569904688 0.3303539455 0.0046435787 0.0050150000 37850381 955859216 1373700096 -0.3077715337 -0.0658033192 0.0156244161 526 1311867736.1631360054 0.3301061988 0.1573195861 0.3303539455 0.0046399662 0.0041630000 37853365 955859216 1373700096 -0.3079507351 -0.0657270104 0.0156792887 527 1311867736.1942429543 0.3306201994 0.1576484298 0.3306201994 0.0046401225 0.0037710000 37856125 955859216 1373700096 -0.3085619211 -0.0657437220 0.0156545881 528 1311867736.2298679352 0.3322181404 0.1579790543 0.3322181404 0.0046379985 0.0037980000 37859109 955859216 1373700096 -0.3107601702 -0.0659695864 0.0161339045 529 1311867736.2633900642 0.3329569995 0.1583098254 0.3329569995 0.0046401481 0.0037490000 37862037 955859216 1373700096 -0.3116596639 -0.0662177503 0.0163307004 530 1311867736.2995250225 0.3324798644 0.1586384481 0.3329569995 0.0046407722 0.0075730000 37865021 955859216 1373700096 -0.3113395870 -0.0666336194 0.0161875971 531 1311867736.3304500580 0.3340192735 0.1589687322 0.3340192735 0.0046374122 0.0066310000 37867781 955859216 1373700096 -0.3130586147 -0.0666927099 0.0169112124 532 1311867736.3637149334 0.3358270526 0.1593011726 0.3358270526 0.0046348602 0.0041410000 37870709 955859216 1373700096 -0.3148972094 -0.0671650022 0.0172367264 533 1311867736.3943159580 0.3379661739 0.1596363790 0.3379661739 0.0046322968 0.0034230000 37873469 955859216 1373700096 -0.3169376552 -0.0681291223 0.0171638783 534 1311867736.4313519001 0.3394085765 0.1599730311 0.3394085765 0.0046411584 0.0052400000 37876565 955859216 1373700096 -0.3182368577 -0.0683101267 0.0173757933 535 1311867736.4625089169 0.3416710794 0.1603126536 0.3416710794 0.0046398801 0.0053100000 37879437 955859216 1373700096 -0.3206335306 -0.0690014362 0.0176549014 536 1311867736.4987530708 0.3436336219 0.1606546703 0.3436336219 0.0046393707 0.0044220000 37882365 955859216 1373700096 -0.3224361539 -0.0698806792 0.0174568351 537 1311867736.5321619511 0.3461476266 0.1610000948 0.3461476266 0.0046425271 0.0069730000 37885293 955859216 1373700096 -0.3248140514 -0.0701587722 0.0178870074 538 1311867736.5634689331 0.3462907672 0.1613445013 0.3462907672 0.0046396058 0.0050470000 37888165 955859216 1373700096 -0.3250632882 -0.0702593997 0.0180392619 539 1311867736.5958600044 0.3483636379 0.1616914756 0.3483636379 0.0046356503 0.0037210000 37891037 955859216 1373700096 -0.3271407485 -0.0716974959 0.0182460286 540 1311867736.6320459843 0.3500328064 0.1620402558 0.3500328064 0.0046448702 0.0070240000 37894021 955859216 1373700096 -0.3284909725 -0.0717911124 0.0186505392 541 1311867736.6635379791 0.3500340581 0.1623877490 0.3500340581 0.0046554512 0.0050600000 37896893 955859216 1373700096 -0.3289182484 -0.0722408518 0.0185660515 542 1311867736.6945500374 0.3532581329 0.1627399083 0.3532581329 0.0046598103 0.0039730000 37899653 955859216 1373700096 -0.3319965303 -0.0738688931 0.0184116233 543 1311867736.7332150936 0.3546825051 0.1630933938 0.3546825051 0.0046557673 0.0070140000 37902693 955859216 1373700096 -0.3333436251 -0.0747077689 0.0185791776 544 1311867736.7636179924 0.3557453454 0.1634475334 0.3557453454 0.0046547487 0.0050840000 37905565 955859216 1373700096 -0.3337837160 -0.0748934746 0.0186332185 545 1311867736.7952749729 0.3594064713 0.1638070911 0.3594064713 0.0046588549 0.0054060000 37908381 955859216 1373700096 -0.3376804888 -0.0747632682 0.0186509416 546 1311867736.8325269222 0.3662184775 0.1641778079 0.3662184775 0.0046754198 0.0060670000 37911365 955859216 1373700096 -0.3443102539 -0.0742653981 0.0192898437 547 1311867736.8640279770 0.3673317134 0.1645492045 0.3673317134 0.0046733435 0.0061880000 37914293 955859216 1373700096 -0.3451260328 -0.0747271106 0.0194036812 548 1311867736.8945000172 0.3689765632 0.1649222471 0.3689765632 0.0046723315 0.0045500000 37917053 955859216 1373700096 -0.3464043736 -0.0758139864 0.0197861437 549 1311867736.9362800121 0.3729859293 0.1653012338 0.3729859293 0.0046786210 0.0049010000 37920205 955859216 1373700096 -0.3499753475 -0.0762663782 0.0198540166 550 1311867736.9632000923 0.3754757345 0.1656833692 0.3754757345 0.0046745946 0.0039590000 37922965 955859216 1373700096 -0.3524772823 -0.0758294240 0.0207482670 551 1311867736.9954400063 0.3785520196 0.1660697007 0.3785520196 0.0046724766 0.0071710000 37925837 955859216 1373700096 -0.3553705812 -0.0758214816 0.0213983990 552 1311867737.0307478905 0.3788453043 0.1664551637 0.3788453043 0.0046697576 0.0054030000 37928765 955859216 1373700096 -0.3554215729 -0.0774365216 0.0212992802 553 1311867737.0629029274 0.3768819571 0.1668356824 0.3788453043 0.0046668432 0.0050800000 37931693 955859216 1373700096 -0.3533113897 -0.0772365034 0.0217703842 554 1311867737.0977239609 0.3772525787 0.1672154963 0.3788453043 0.0046640821 0.0060000000 37934621 955859216 1373700096 -0.3536159992 -0.0777034983 0.0217019580 555 1311867737.1300530434 0.3772329688 0.1675939061 0.3788453043 0.0046599845 0.0040500000 37937437 955859216 1373700096 -0.3535442352 -0.0780624822 0.0215941835 556 1311867737.1655049324 0.3759160340 0.1679685862 0.3788453043 0.0046561072 0.0071120000 37940421 955859216 1373700096 -0.3521829247 -0.0775422677 0.0216529556 557 1311867737.1952710152 0.3759526312 0.1683419866 0.3788453043 0.0046520400 0.0046520000 37943237 955859216 1373700096 -0.3520366848 -0.0775527433 0.0215252843 558 1311867737.2333149910 0.3771953285 0.1687162758 0.3788453043 0.0046485909 0.0064110000 37946333 955859216 1373700096 -0.3531199396 -0.0780007765 0.0215460025 559 1311867737.2693018913 0.3763772249 0.1690877623 0.3788453043 0.0046501492 0.0042650000 37949261 955859216 1373700096 -0.3516825736 -0.0775072202 0.0216767713 560 1311867737.2957379818 0.3768586218 0.1694587817 0.3788453043 0.0046464178 0.0039110000 37951965 955859216 1373700096 -0.3519355655 -0.0775575787 0.0220160577 561 1311867737.3316531181 0.3772549927 0.1698291849 0.3788453043 0.0046425069 0.0071520000 37955005 955859216 1373700096 -0.3521276116 -0.0775801167 0.0222380031 562 1311867737.3659460545 0.3771469295 0.1701980777 0.3788453043 0.0046383976 0.0047900000 37957877 955859216 1373700096 -0.3521532118 -0.0773176849 0.0225039814 563 1311867737.3967239857 0.3781046271 0.1705673611 0.3788453043 0.0046365747 0.0042470000 37960749 955859216 1373700096 -0.3528723717 -0.0774596781 0.0229431223 564 1311867737.4355359077 0.3792059720 0.1709372877 0.3792059720 0.0046336325 0.0039110000 37963789 955859216 1373700096 -0.3538661003 -0.0774413645 0.0234933086 565 1311867737.4691100121 0.3801656067 0.1713076033 0.3801656067 0.0046295284 0.0038730000 37966717 955859216 1373700096 -0.3546822667 -0.0775628760 0.0239288993 566 1311867737.4959459305 0.3803317845 0.1716769040 0.3803317845 0.0046255833 0.0076290000 37969421 955859216 1373700096 -0.3549085259 -0.0777200758 0.0244754106 567 1311867737.5353999138 0.3809085190 0.1720459192 0.3809085190 0.0046220412 0.0060900000 37972517 955859216 1373700096 -0.3552203178 -0.0780198574 0.0248522200 568 1311867737.5654399395 0.3802945614 0.1724125541 0.3809085190 0.0046185328 0.0041190000 37975277 955859216 1373700096 -0.3540699184 -0.0779785514 0.0251178760 569 1311867737.5958089828 0.3808797002 0.1727789287 0.3809085190 0.0046158587 0.0051250000 37978149 955859216 1373700096 -0.3543300629 -0.0780931562 0.0257259533 570 1311867737.6330978870 0.3822764158 0.1731464681 0.3822764158 0.0046129362 0.0040330000 37981189 955859216 1373700096 -0.3554289341 -0.0782109573 0.0261562578 571 1311867737.6624519825 0.3836736381 0.1735151672 0.3836736381 0.0046096555 0.0072770000 37984005 955859216 1373700096 -0.3565506339 -0.0788792446 0.0266790800 572 1311867737.7032339573 0.3840380609 0.1738832142 0.3840380609 0.0046072390 0.0046390000 37987045 955859216 1373700096 -0.3565513790 -0.0797684416 0.0268246271 573 1311867737.7314720154 0.3849342465 0.1742515406 0.3849342465 0.0046036706 0.0040330000 37989805 955859216 1373700096 -0.3571021855 -0.0801911727 0.0272825733 574 1311867737.7658560276 0.3853141069 0.1746192455 0.3853141069 0.0045998772 0.0074470000 37992733 955859216 1373700096 -0.3572128713 -0.0802716985 0.0275045857 575 1311867737.8011269569 0.3855773211 0.1749861291 0.3855773211 0.0045969471 0.0047470000 37995717 955859216 1373700096 -0.3572035432 -0.0801591575 0.0279508084 576 1311867737.8323190212 0.3853960931 0.1753514241 0.3855773211 0.0045932770 0.0049690000 37998589 955859216 1373700096 -0.3568183780 -0.0802396461 0.0283301044 577 1311867737.8633110523 0.3864210248 0.1757172293 0.3864210248 0.0045945376 0.0040730000 38001405 955859216 1373700096 -0.3572854400 -0.0800147355 0.0288329571 578 1311867737.9004418850 0.3863651454 0.1760816721 0.3864210248 0.0045912406 0.0072750000 38004333 955859216 1373700096 -0.3567150533 -0.0807583332 0.0294667203 579 1311867737.9305500984 0.3867052197 0.1764454433 0.3867052197 0.0045929753 0.0046910000 38007149 955859216 1373700096 -0.3567150235 -0.0809373856 0.0300971549 580 1311867737.9630560875 0.3877444565 0.1768097520 0.3877444565 0.0045898190 0.0041000000 38010077 955859216 1373700096 -0.3573985696 -0.0809604824 0.0307066608 581 1311867737.9996941090 0.3890136182 0.1771749910 0.3890136182 0.0045876709 0.0072500000 38013061 955859216 1373700096 -0.3582125604 -0.0814861730 0.0313365534 582 1311867738.0315399170 0.3898909390 0.1775404823 0.3898909390 0.0045846110 0.0046380000 38015933 955859216 1373700096 -0.3586923182 -0.0813353583 0.0322066545 583 1311867738.0629770756 0.3887040913 0.1779026841 0.3898909390 0.0045808211 0.0055140000 38018805 955859216 1373700096 -0.3569330573 -0.0812431648 0.0331280753 584 1311867738.0998299122 0.3891964555 0.1782644885 0.3898909390 0.0045781838 0.0072790000 38021733 955859216 1373700096 -0.3568399549 -0.0814207941 0.0337534472 585 1311867738.1308510303 0.3882762492 0.1786234829 0.3898909390 0.0045764867 0.0045130000 38024549 955859216 1373700096 -0.3552874625 -0.0820703357 0.0346339643 586 1311867738.1635079384 0.3886741698 0.1789819312 0.3898909390 0.0045737446 0.0038290000 38027477 955859216 1373700096 -0.3551774621 -0.0828257129 0.0352400653 587 1311867738.1992070675 0.3901290894 0.1793416367 0.3901290894 0.0045712206 0.0073290000 38030405 955859216 1373700096 -0.3559810817 -0.0833407491 0.0360215493 588 1311867738.2306089401 0.3907493949 0.1797011737 0.3907493949 0.0045720130 0.0047170000 38033277 955859216 1373700096 -0.3562222719 -0.0843726248 0.0363883860 589 1311867738.2632689476 0.3914570212 0.1800606913 0.3914570212 0.0045743289 0.0066820000 38036205 955859216 1373700096 -0.3564272523 -0.0852248520 0.0364004411 590 1311867738.3008689880 0.3924427927 0.1804206610 0.3924427927 0.0045716419 0.0043210000 38039189 955859216 1373700096 -0.3567845523 -0.0862278193 0.0367121808 591 1311867738.3339769840 0.3942945898 0.1807825458 0.3942945898 0.0045708389 0.0072720000 38042061 955859216 1373700096 -0.3581433892 -0.0868689939 0.0368703231 592 1311867738.3651630878 0.3962622583 0.1811465318 0.3962622583 0.0045672436 0.0044590000 38044933 955859216 1373700096 -0.3598960340 -0.0873159766 0.0370223820 593 1311867738.3995900154 0.3972302377 0.1815109225 0.3972302377 0.0045639450 0.0053390000 38047917 955859216 1373700096 -0.3603990972 -0.0871833414 0.0371099003 594 1311867738.4334011078 0.3972716331 0.1818741561 0.3972716331 0.0045604134 0.0046430000 38050845 955859216 1373700096 -0.3602786362 -0.0870786160 0.0371457972 595 1311867738.4643430710 0.3991704881 0.1822393600 0.3991704881 0.0045570547 0.0043600000 38053661 955859216 1373700096 -0.3613423705 -0.0875526741 0.0372744687 596 1311867738.5000250340 0.3994501233 0.1826038076 0.3994501233 0.0045537424 0.0078520000 38056645 955859216 1373700096 -0.3610276878 -0.0873201340 0.0373976193 597 1311867738.5332009792 0.3994103372 0.1829669676 0.3994501233 0.0045503309 0.0052630000 38059517 955859216 1373700096 -0.3602481186 -0.0867462456 0.0377173908 598 1311867738.5634350777 0.3993990421 0.1833288941 0.3994501233 0.0045482559 0.0038640000 38062389 955859216 1373700096 -0.3595708907 -0.0871548802 0.0378611423 599 1311867738.6022439003 0.3993507624 0.1836895316 0.3994501233 0.0045461362 0.0074240000 38065429 955859216 1373700096 -0.3585445881 -0.0875543803 0.0378976986 600 1311867738.6328980923 0.3999129534 0.1840499040 0.3999129534 0.0045429222 0.0045290000 38068245 955859216 1373700096 -0.3581676185 -0.0876519829 0.0380019583 601 1311867738.6628730297 0.4006395936 0.1844102862 0.4006395936 0.0045408837 0.0059290000 38071117 955859216 1373700096 -0.3580286205 -0.0879940018 0.0381431542 602 1311867738.6996099949 0.4012721479 0.1847705218 0.4012721479 0.0045412002 0.0043850000 38074101 955859216 1373700096 -0.3576996028 -0.0885671005 0.0380908437 603 1311867738.7314729691 0.4016831517 0.1851302443 0.4016831517 0.0045438673 0.0040480000 38076973 955859216 1373700096 -0.3572808802 -0.0888338983 0.0382589996 604 1311867738.7626600266 0.4026653469 0.1854904017 0.4026653469 0.0045440539 0.0040180000 38079789 955859216 1373700096 -0.3573738337 -0.0884729251 0.0384466313 605 1311867738.8032259941 0.4035813510 0.1858508826 0.4035813510 0.0045485629 0.0040760000 38082885 955859216 1373700096 -0.3572869301 -0.0885422677 0.0387019701 606 1311867738.8306779861 0.4034205973 0.1862099086 0.4035813510 0.0045475472 0.0040050000 38085645 955859216 1373700096 -0.3564814031 -0.0888065547 0.0386887603 607 1311867738.8639259338 0.4021940827 0.1865657309 0.4035813510 0.0045438129 0.0040290000 38088573 955859216 1373700096 -0.3545106053 -0.0887622461 0.0386145227 608 1311867738.9000120163 0.4036026001 0.1869226995 0.4036026001 0.0045464268 0.0040130000 38091557 955859216 1373700096 -0.3551792204 -0.0887010619 0.0387109034 609 1311867738.9307610989 0.4046339393 0.1872801892 0.4046339393 0.0045522329 0.0040250000 38094373 955859216 1373700096 -0.3556616604 -0.0887850299 0.0390581489 610 1311867738.9664750099 0.4047240913 0.1876366546 0.4047240913 0.0045486667 0.0040040000 38097357 955859216 1373700096 -0.3552714288 -0.0885427669 0.0392942093 611 1311867738.9989941120 0.4057040215 0.1879935570 0.4057040215 0.0045454695 0.0040750000 38100285 955859216 1373700096 -0.3557789028 -0.0884014517 0.0393301286 612 1311867739.0329539776 0.4049785435 0.1883481076 0.4057040215 0.0045445565 0.0038680000 38103213 955859216 1373700096 -0.3545483351 -0.0892805606 0.0392865650 613 1311867739.0664470196 0.4037421942 0.1886994846 0.4057040215 0.0045463323 0.0075800000 38106085 955859216 1373700096 -0.3528062701 -0.0895517096 0.0392497145 614 1311867739.0997900963 0.4027144611 0.1890480432 0.4057040215 0.0045427495 0.0069920000 38108845 955859216 1373700096 -0.3514176607 -0.0892422274 0.0392876044 615 1311867739.1321549416 0.4025593996 0.1893952161 0.4057040215 0.0045414234 0.0043980000 38111661 955859216 1373700096 -0.3509633243 -0.0892899409 0.0394352823 616 1311867739.1687150002 0.4025826156 0.1897412996 0.4057040215 0.0045381164 0.0040380000 38114645 955859216 1373700096 -0.3509304523 -0.0889436454 0.0396649912 617 1311867739.1999289989 0.4031772017 0.1900872249 0.4057040215 0.0045355004 0.0080980000 38117461 955859216 1373700096 -0.3515288830 -0.0887988731 0.0401240438 618 1311867739.2313010693 0.4023691118 0.1904307231 0.4057040215 0.0045327656 0.0049570000 38120277 955859216 1373700096 -0.3506611288 -0.0890837386 0.0402557403 619 1311867739.2672259808 0.4019805491 0.1907724837 0.4057040215 0.0045303035 0.0040650000 38123317 955859216 1373700096 -0.3504072130 -0.0895973518 0.0404488035 620 1311867739.2996931076 0.4023800194 0.1911137862 0.4057040215 0.0045310659 0.0076760000 38126189 955859216 1373700096 -0.3509374857 -0.0900696740 0.0406681001 621 1311867739.3319859505 0.4013346732 0.1914523061 0.4057040215 0.0045281332 0.0048400000 38129061 955859216 1373700096 -0.3498713672 -0.0901011825 0.0409508646 622 1311867739.3670029640 0.4015177190 0.1917900319 0.4057040215 0.0045271161 0.0041490000 38131989 955859216 1373700096 -0.3503449261 -0.0897614658 0.0411089994 623 1311867739.3990058899 0.4003117681 0.1921247377 0.4057040215 0.0045240398 0.0060590000 38134917 955859216 1373700096 -0.3493493795 -0.0897809267 0.0413741358 624 1311867739.4311320782 0.3987464905 0.1924558623 0.4057040215 0.0045216579 0.0059290000 38137733 955859216 1373700096 -0.3477707803 -0.0896972939 0.0416073799 625 1311867739.4668490887 0.4002293050 0.1927882998 0.4057040215 0.0045183886 0.0044700000 38140717 955859216 1373700096 -0.3492817283 -0.0898344442 0.0421054251 626 1311867739.4988598824 0.4011614323 0.1931211642 0.4057040215 0.0045255206 0.0080920000 38143589 955859216 1373700096 -0.3501830697 -0.0902208090 0.0426275097 627 1311867739.5316400528 0.4007213712 0.1934522650 0.4057040215 0.0045221225 0.0044280000 38146405 955859216 1373700096 -0.3495559096 -0.0899836868 0.0430153087 628 1311867739.5670249462 0.4018177688 0.1937840572 0.4057040215 0.0045195911 0.0038860000 38149389 955859216 1373700096 -0.3506291211 -0.0897610560 0.0439480580 629 1311867739.5990490913 0.4029017389 0.1941165178 0.4057040215 0.0045161534 0.0075450000 38152261 955859216 1373700096 -0.3517552912 -0.0901353583 0.0446241349 630 1311867739.6325490475 0.4038611054 0.1944494457 0.4057040215 0.0045126300 0.0045100000 38155189 955859216 1373700096 -0.3529663384 -0.0897043198 0.0452925488 631 1311867739.6706740856 0.4052776396 0.1947835633 0.4057040215 0.0045110472 0.0076730000 38158229 955859216 1373700096 -0.3546967804 -0.0899088532 0.0458821021 632 1311867739.7001221180 0.4060120583 0.1951177856 0.4060120583 0.0045084198 0.0048220000 38161045 955859216 1373700096 -0.3555546105 -0.0896619037 0.0465030484 633 1311867739.7323939800 0.4053232074 0.1954498637 0.4060120583 0.0045061627 0.0049340000 38163917 955859216 1373700096 -0.3550515175 -0.0893449336 0.0473215207 634 1311867739.7662999630 0.4058905840 0.1957817891 0.4060120583 0.0045032245 0.0076420000 38166845 955859216 1373700096 -0.3557991982 -0.0893638358 0.0480514839 635 1311867739.8016180992 0.4060414135 0.1961129066 0.4060414135 0.0045007378 0.0046120000 38169829 955859216 1373700096 -0.3562483788 -0.0898191035 0.0485518053 636 1311867739.8325679302 0.4063127935 0.1964434096 0.4063127935 0.0045000462 0.0039170000 38172645 955859216 1373700096 -0.3568308949 -0.0893802419 0.0490647927 637 1311867739.8701560497 0.4062860310 0.1967728328 0.4063127935 0.0044969646 0.0036500000 38175629 955859216 1373700096 -0.3573989570 -0.0893194824 0.0495498925 638 1311867739.9036860466 0.4068876803 0.1971021665 0.4068876803 0.0044941262 0.0077060000 38178613 955859216 1373700096 -0.3587246537 -0.0900297314 0.0497511700 639 1311867739.9317240715 0.4076007903 0.1974315853 0.4076007903 0.0044909410 0.0062490000 38181373 955859216 1373700096 -0.3599397540 -0.0900069177 0.0499917492 640 1311867739.9668979645 0.4076130688 0.1977599938 0.4076130688 0.0044886996 0.0043120000 38184301 955859216 1373700096 -0.3604157865 -0.0896957368 0.0501537435 641 1311867739.9987080097 0.4091802537 0.1980898226 0.4091802537 0.0044860884 0.0075260000 38187229 955859216 1373700096 -0.3626728356 -0.0898535028 0.0507625453 642 1311867740.0328791142 0.4095599949 0.1984192154 0.4095599949 0.0044827086 0.0045340000 38190157 955859216 1373700096 -0.3636514544 -0.0900250524 0.0509808734 643 1311867740.0671849251 0.4085277617 0.1987459783 0.4095599949 0.0044797853 0.0038710000 38193029 955859216 1373700096 -0.3630478084 -0.0896044970 0.0509950519 644 1311867740.0992529392 0.4089995921 0.1990724591 0.4095599949 0.0044796058 0.0077270000 38195957 955859216 1373700096 -0.3638357222 -0.0901881158 0.0513052791 645 1311867740.1347720623 0.4098716080 0.1993992795 0.4098716080 0.0044776475 0.0055000000 38198829 955859216 1373700096 -0.3654553294 -0.0907491967 0.0514098853 646 1311867740.1666491032 0.4097540379 0.1997249060 0.4098716080 0.0044743932 0.0040810000 38201757 955859216 1373700096 -0.3654938638 -0.0904439837 0.0513065122 647 1311867740.1993310452 0.4093298018 0.2000488703 0.4098716080 0.0044713234 0.0078910000 38204685 955859216 1373700096 -0.3655054867 -0.0902326331 0.0514703430 648 1311867740.2383539677 0.4101442695 0.2003730916 0.4101442695 0.0044695398 0.0048250000 38207781 955859216 1373700096 -0.3668297231 -0.0906616300 0.0514493957 649 1311867740.2664349079 0.4098195136 0.2006958134 0.4101442695 0.0044683031 0.0051790000 38210485 955859216 1373700096 -0.3668898046 -0.0903420895 0.0513166375 650 1311867740.2981588840 0.4110652804 0.2010194587 0.4110652804 0.0044659261 0.0056100000 38213357 955859216 1373700096 -0.3684607744 -0.0898247808 0.0515384153 651 1311867740.3347120285 0.4100694954 0.2013405801 0.4110652804 0.0044627096 0.0042590000 38216397 955859216 1373700096 -0.3678973615 -0.0902741626 0.0512867346 652 1311867740.3665161133 0.4094907641 0.2016598289 0.4110652804 0.0044615793 0.0078650000 38219213 955859216 1373700096 -0.3675353527 -0.0900857225 0.0508669876 653 1311867740.3993780613 0.4089092314 0.2019772093 0.4110652804 0.0044593167 0.0046420000 38222085 955859216 1373700096 -0.3670669794 -0.0902540237 0.0505686440 654 1311867740.4346680641 0.4093531668 0.2022942979 0.4110652804 0.0044581825 0.0039310000 38225069 955859216 1373700096 -0.3673929870 -0.0902139768 0.0502656586 655 1311867740.4664289951 0.4099249840 0.2026112913 0.4110652804 0.0044558359 0.0077770000 38227941 955859216 1373700096 -0.3680911958 -0.0900573656 0.0499826148 656 1311867740.4993040562 0.4109992683 0.2029289559 0.4110652804 0.0044559712 0.0049570000 38230813 955859216 1373700096 -0.3687842190 -0.0900166556 0.0498731360 657 1311867740.5354259014 0.4122923613 0.2032476217 0.4122923613 0.0044582859 0.0039270000 38233797 955859216 1373700096 -0.3696695566 -0.0901888758 0.0497940890 658 1311867740.5666589737 0.4123807549 0.2035654532 0.4123807549 0.0044558337 0.0074600000 38236669 955859216 1373700096 -0.3695927560 -0.0899990350 0.0495481119 659 1311867740.6008880138 0.4141093493 0.2038849432 0.4141093493 0.0044555327 0.0045330000 38239597 955859216 1373700096 -0.3711698055 -0.0899681151 0.0497134663 660 1311867740.6346809864 0.4147937298 0.2042045019 0.4147937298 0.0044536701 0.0068200000 38242525 955859216 1373700096 -0.3719272316 -0.0901367664 0.0497395024 661 1311867740.6665890217 0.4146065712 0.2045228107 0.4147937298 0.0044506517 0.0043540000 38245397 955859216 1373700096 -0.3719168305 -0.0902159363 0.0494575724 662 1311867740.6994900703 0.4154743552 0.2048414686 0.4154743552 0.0044484297 0.0066310000 38248269 955859216 1373700096 -0.3729617298 -0.0904314816 0.0490571223 663 1311867740.7368240356 0.4155490994 0.2051592780 0.4155490994 0.0044475997 0.0069330000 38251141 955859216 1373700096 -0.3732074797 -0.0904025286 0.0487363227 664 1311867740.7668819427 0.4162666798 0.2054772108 0.4162666798 0.0044449677 0.0044670000 38253957 955859216 1373700096 -0.3741629422 -0.0905664191 0.0486992151 665 1311867740.7996399403 0.4177946150 0.2057964851 0.4177946150 0.0044424322 0.0051560000 38256885 955859216 1373700096 -0.3759857416 -0.0909082890 0.0490838625 666 1311867740.8349099159 0.4182301760 0.2061154546 0.4182301760 0.0044395030 0.0056200000 38259757 955859216 1373700096 -0.3767457902 -0.0904920027 0.0487611815 667 1311867740.8668210506 0.4187526107 0.2064342510 0.4187526107 0.0044370395 0.0042930000 38262685 955859216 1373700096 -0.3776314259 -0.0905105844 0.0488515496 668 1311867740.8993830681 0.4192994237 0.2067529114 0.4192994237 0.0044338346 0.0077970000 38265557 955859216 1373700096 -0.3788504899 -0.0908159465 0.0486640744 669 1311867740.9399120808 0.4189444780 0.2070700886 0.4192994237 0.0044327882 0.0046240000 38268709 955859216 1373700096 -0.3791067600 -0.0905083418 0.0482237153 670 1311867740.9665501118 0.4183812737 0.2073854784 0.4192994237 0.0044295723 0.0041640000 38271413 955859216 1373700096 -0.3789961934 -0.0901979432 0.0478561781 671 1311867741.0021579266 0.4192015827 0.2077011507 0.4192994237 0.0044269995 0.0079680000 38274397 955859216 1373700096 -0.3803200126 -0.0906822532 0.0476948321 672 1311867741.0367169380 0.4190128446 0.2080156027 0.4192994237 0.0044239469 0.0046850000 38277325 955859216 1373700096 -0.3804450035 -0.0907158926 0.0472733155 673 1311867741.0666699409 0.4186613560 0.2083285978 0.4192994237 0.0044217549 0.0039620000 38280141 955859216 1373700096 -0.3804354668 -0.0901732817 0.0469489619 674 1311867741.1009640694 0.4193677604 0.2086417123 0.4193677604 0.0044232027 0.0079390000 38283069 955859216 1373700096 -0.3816052079 -0.0908799171 0.0466611944 675 1311867741.1357901096 0.4190334380 0.2089534038 0.4193677604 0.0044205931 0.0046990000 38285997 955859216 1373700096 -0.3818045855 -0.0909976736 0.0459530577 676 1311867741.1675300598 0.4185781777 0.2092634996 0.4193677604 0.0044177185 0.0039980000 38288925 955859216 1373700096 -0.3813750744 -0.0914801508 0.0454851612 677 1311867741.2014830112 0.4191147983 0.2095734720 0.4193677604 0.0044191623 0.0080720000 38291797 955859216 1373700096 -0.3818362355 -0.0918750614 0.0451382808 678 1311867741.2411060333 0.4198885262 0.2098836712 0.4198885262 0.0044213536 0.0049630000 38294893 955859216 1373700096 -0.3827944696 -0.0925770178 0.0449122936 679 1311867741.2668209076 0.4207549393 0.2101942327 0.4207549393 0.0044212187 0.0039880000 38297597 955859216 1373700096 -0.3835132420 -0.0926055387 0.0447689183 680 1311867741.2997009754 0.4214845598 0.2105049537 0.4214845598 0.0044180108 0.0039000000 38300469 955859216 1373700096 -0.3840567470 -0.0925735235 0.0445802175 681 1311867741.3348419666 0.4221483767 0.2108157370 0.4221483767 0.0044150466 0.0038540000 38303453 955859216 1373700096 -0.3846782744 -0.0920640901 0.0441282727 682 1311867741.3701419830 0.4220500588 0.2111254648 0.4221483767 0.0044118258 0.0038700000 38306381 955859216 1373700096 -0.3842425346 -0.0914798602 0.0437352322 683 1311867741.4066278934 0.4225143492 0.2114349653 0.4225143492 0.0044103066 0.0038320000 38309421 955859216 1373700096 -0.3842660487 -0.0914971083 0.0435361043 684 1311867741.4393060207 0.4225505888 0.2117436139 0.4225505888 0.0044085331 0.0084800000 38312349 955859216 1373700096 -0.3840657473 -0.0907526910 0.0435121879 685 1311867741.4667329788 0.4218927920 0.2120504010 0.4225505888 0.0044055585 0.0078490000 38315053 955859216 1373700096 -0.3830360770 -0.0901365206 0.0432178266 686 1311867741.5025069714 0.4227813184 0.2123575890 0.4227813184 0.0044032182 0.0046980000 38318037 955859216 1373700096 -0.3834179640 -0.0894836709 0.0435124002 687 1311867741.5368049145 0.4230813980 0.2126643194 0.4230813980 0.0044016087 0.0039590000 38320965 955859216 1373700096 -0.3833425045 -0.0891857892 0.0433196425 688 1311867741.5688209534 0.4226148725 0.2129694801 0.4230813980 0.0043984656 0.0036880000 38323837 955859216 1373700096 -0.3824172616 -0.0886662379 0.0430877209 689 1311867741.6046030521 0.4232294559 0.2132746470 0.4232294559 0.0044038110 0.0034870000 38326765 955859216 1373700096 -0.3826691508 -0.0883847624 0.0432908982 690 1311867741.6355440617 0.4237376750 0.2135796658 0.4237376750 0.0044013309 0.0085110000 38329637 955859216 1373700096 -0.3826909959 -0.0882077590 0.0431915112 691 1311867741.6679561138 0.4233438969 0.2138832320 0.4237376750 0.0043984238 0.0061990000 38332565 955859216 1373700096 -0.3817203939 -0.0879651681 0.0429841131 692 1311867741.7048020363 0.4247631133 0.2141879717 0.4247631133 0.0044008412 0.0043670000 38335549 955859216 1373700096 -0.3822969198 -0.0876528844 0.0429151095 693 1311867741.7345991135 0.4240999520 0.2144908750 0.4247631133 0.0043990876 0.0036430000 38338309 955859216 1373700096 -0.3811070323 -0.0874469131 0.0424399972 694 1311867741.7702169418 0.4245865643 0.2147936066 0.4247631133 0.0043960140 0.0033420000 38341293 955859216 1373700096 -0.3807737827 -0.0875415057 0.0423433073 695 1311867741.8058650494 0.4245196879 0.2150953707 0.4247631133 0.0043928857 0.0080430000 38344277 955859216 1373700096 -0.3798677921 -0.0872065127 0.0419133119 696 1311867741.8388509750 0.4248060882 0.2153966792 0.4248060882 0.0043907100 0.0069720000 38347261 955859216 1373700096 -0.3795643747 -0.0872199610 0.0416076966 697 1311867741.8683021069 0.4253672361 0.2156979282 0.4253672361 0.0043882218 0.0044000000 38350021 955859216 1373700096 -0.3794742227 -0.0873089135 0.0414784551 698 1311867741.9065721035 0.4254655540 0.2159984549 0.4254655540 0.0043851813 0.0050330000 38353061 955859216 1373700096 -0.3789308369 -0.0869353563 0.0409989655 699 1311867741.9387769699 0.4261373281 0.2162990828 0.4261373281 0.0043828433 0.0053580000 38355989 955859216 1373700096 -0.3787354529 -0.0867145434 0.0407484546 700 1311867741.9665379524 0.4259535968 0.2165985892 0.4261373281 0.0043809727 0.0043340000 38358693 955859216 1373700096 -0.3778614700 -0.0867855772 0.0402835235 701 1311867742.0029959679 0.4261721969 0.2168975530 0.4261721969 0.0043784356 0.0039840000 38361677 955859216 1373700096 -0.3770851493 -0.0870849192 0.0402359776 702 1311867742.0344839096 0.4268513918 0.2171966325 0.4268513918 0.0043754050 0.0080260000 38364493 955859216 1373700096 -0.3769727051 -0.0867272988 0.0400539972 703 1311867742.0674400330 0.4266109169 0.2174945191 0.4268513918 0.0043728817 0.0059480000 38367365 955859216 1373700096 -0.3759339750 -0.0865005329 0.0398701280 704 1311867742.1030650139 0.4281328917 0.2177937214 0.4281328917 0.0043710102 0.0043320000 38370293 955859216 1373700096 -0.3761760890 -0.0861469805 0.0397445112 705 1311867742.1348879337 0.4284943640 0.2180925875 0.4284943640 0.0043692249 0.0059940000 38373109 955859216 1373700096 -0.3754985332 -0.0861505494 0.0394791961 706 1311867742.1672229767 0.4280020595 0.2183899097 0.4284943640 0.0043670552 0.0048630000 38376037 955859216 1373700096 -0.3745130002 -0.0857077315 0.0394082665 707 1311867742.2028279305 0.4281980395 0.2186866680 0.4284943640 0.0043647756 0.0039840000 38379077 955859216 1373700096 -0.3737792969 -0.0854102299 0.0393025689 708 1311867742.2362670898 0.4284015000 0.2189828754 0.4284943640 0.0043633970 0.0085680000 38381949 955859216 1373700096 -0.3731631637 -0.0851485878 0.0392337553 709 1311867742.2674059868 0.4288385808 0.2192788637 0.4288385808 0.0043609808 0.0050860000 38384821 955859216 1373700096 -0.3729667366 -0.0855743438 0.0393780731 710 1311867742.3028159142 0.4291570187 0.2195744668 0.4291570187 0.0043584285 0.0040030000 38387805 955859216 1373700096 -0.3728891015 -0.0855960324 0.0391122811 711 1311867742.3350739479 0.4298066199 0.2198701519 0.4298066199 0.0043556721 0.0078120000 38390621 955859216 1373700096 -0.3731706440 -0.0854469761 0.0388214812 712 1311867742.3694241047 0.4299070537 0.2201651476 0.4299070537 0.0043526655 0.0046730000 38393605 955859216 1373700096 -0.3730562925 -0.0857527256 0.0384989530 713 1311867742.4062991142 0.4311266840 0.2204610263 0.4311266840 0.0043496652 0.0039910000 38396589 955859216 1373700096 -0.3738873005 -0.0858298764 0.0380215906 714 1311867742.4346439838 0.4309976101 0.2207558955 0.4311266840 0.0043467387 0.0078780000 38399349 955859216 1373700096 -0.3734686375 -0.0859160572 0.0376736522 715 1311867742.4666969776 0.4317348897 0.2210509710 0.4317348897 0.0043444447 0.0046270000 38402221 955859216 1373700096 -0.3738570213 -0.0857432932 0.0373992175 716 1311867742.5047059059 0.4316878021 0.2213451565 0.4317348897 0.0043415017 0.0040040000 38405205 955859216 1373700096 -0.3733829856 -0.0855720341 0.0372952893 717 1311867742.5359389782 0.4319650531 0.2216389081 0.4319650531 0.0043388194 0.0081660000 38408077 955859216 1373700096 -0.3732727766 -0.0853668377 0.0372842103 718 1311867742.5678529739 0.4317341745 0.2219315199 0.4319650531 0.0043365979 0.0050580000 38411005 955859216 1373700096 -0.3726150393 -0.0851028487 0.0371896401 719 1311867742.6054639816 0.4320945442 0.2222238190 0.4320945442 0.0043338390 0.0039660000 38413989 955859216 1373700096 -0.3726417422 -0.0853214338 0.0371718556 720 1311867742.6347279549 0.4310151339 0.2225138069 0.4320945442 0.0043313826 0.0075400000 38416749 955859216 1373700096 -0.3713711500 -0.0849478096 0.0370754637 721 1311867742.6724960804 0.4316844940 0.2228039188 0.4320945442 0.0043287449 0.0045270000 38419845 955859216 1373700096 -0.3717235625 -0.0851590410 0.0372973345 722 1311867742.7046229839 0.4320050180 0.2230936710 0.4320945442 0.0043257448 0.0069800000 38422661 955859216 1373700096 -0.3717896044 -0.0853870064 0.0373167768 723 1311867742.7356119156 0.4317746460 0.2233823031 0.4320945442 0.0043228586 0.0044900000 38425533 955859216 1373700096 -0.3712534308 -0.0853410661 0.0370586365 724 1311867742.7726070881 0.4325896502 0.2236712635 0.4325896502 0.0043206900 0.0078970000 38428573 955859216 1373700096 -0.3715659976 -0.0858222470 0.0371307097 725 1311867742.8034689426 0.4331011772 0.2239601324 0.4331011772 0.0043214955 0.0046770000 38431445 955859216 1373700096 -0.3721174598 -0.0858136937 0.0371959209 726 1311867742.8352251053 0.4335725904 0.2242488547 0.4335725904 0.0043209491 0.0037550000 38434261 955859216 1373700096 -0.3719379902 -0.0859048441 0.0370893255 727 1311867742.8705639839 0.4341505468 0.2245375778 0.4341505468 0.0043182789 0.0079200000 38437189 955859216 1373700096 -0.3723069727 -0.0857950971 0.0371176936 728 1311867742.9046700001 0.4338213801 0.2248250556 0.4341505468 0.0043154382 0.0046400000 38440117 955859216 1373700096 -0.3715950549 -0.0858848915 0.0369862616 729 1311867742.9382069111 0.4334191084 0.2251111928 0.4341505468 0.0043357041 0.0040010000 38443101 955859216 1373700096 -0.3711483479 -0.0857237577 0.0369475447 730 1311867742.9707310200 0.4330025017 0.2253959755 0.4341505468 0.0043361060 0.0082100000 38445973 955859216 1373700096 -0.3704131842 -0.0854937509 0.0366745330 731 1311867743.0024189949 0.4336612821 0.2256808801 0.4341505468 0.0043375211 0.0051250000 38448789 955859216 1373700096 -0.3707937002 -0.0855526850 0.0368872583 732 1311867743.0345149040 0.4337553978 0.2259651349 0.4341505468 0.0043379383 0.0040910000 38451661 955859216 1373700096 -0.3705249429 -0.0852556154 0.0368695632 733 1311867743.0722420216 0.4339895546 0.2262489336 0.4341505468 0.0043365202 0.0080120000 38454701 955859216 1373700096 -0.3702753484 -0.0855996385 0.0367311724 734 1311867743.1045989990 0.4336273372 0.2265314655 0.4341505468 0.0043339302 0.0046730000 38457573 955859216 1373700096 -0.3695708811 -0.0857093781 0.0367567018 735 1311867743.1350400448 0.4342180490 0.2268140323 0.4342180490 0.0043327142 0.0040130000 38460389 955859216 1373700096 -0.3695453703 -0.0857307538 0.0365992561 736 1311867743.1704380512 0.4338245392 0.2270952965 0.4342180490 0.0043361528 0.0037480000 38463317 955859216 1373700096 -0.3690294027 -0.0860254318 0.0362716652 737 1311867743.2037980556 0.4337191284 0.2273756545 0.4342180490 0.0043339054 0.0083010000 38466245 955859216 1373700096 -0.3685154915 -0.0858230367 0.0360288136 738 1311867743.2358140945 0.4342961907 0.2276560346 0.4342961907 0.0043321204 0.0061100000 38469061 955859216 1373700096 -0.3685885966 -0.0857304260 0.0360891670 739 1311867743.2708129883 0.4339699745 0.2279352145 0.4342961907 0.0043344836 0.0044940000 38472045 955859216 1373700096 -0.3681146204 -0.0851710215 0.0361719877 740 1311867743.3032529354 0.4342549443 0.2282140250 0.4342961907 0.0043417955 0.0061790000 38474917 955859216 1373700096 -0.3683379292 -0.0851714835 0.0362732112 741 1311867743.3363931179 0.4345326424 0.2284924577 0.4345326424 0.0043391603 0.0044670000 38477789 955859216 1373700096 -0.3685078621 -0.0846695378 0.0364330374 742 1311867743.3707330227 0.4340463579 0.2287694845 0.4345326424 0.0043366292 0.0083560000 38480717 955859216 1373700096 -0.3678830862 -0.0842393488 0.0365237296 743 1311867743.4043838978 0.4345954657 0.2290465046 0.4345954657 0.0043338776 0.0048920000 38483645 955859216 1373700096 -0.3683921695 -0.0841813609 0.0366798900 744 1311867743.4352641106 0.4347124398 0.2293229374 0.4347124398 0.0043394486 0.0040460000 38486517 955859216 1373700096 -0.3685133457 -0.0843691230 0.0365482680 745 1311867743.4768960476 0.4348298609 0.2295987856 0.4348298609 0.0043389588 0.0037790000 38489613 955859216 1373700096 -0.3685619235 -0.0841201544 0.0365433954 746 1311867743.5035250187 0.4355194271 0.2298748186 0.4355194271 0.0043367066 0.0039380000 38492373 955859216 1373700096 -0.3690266311 -0.0840076357 0.0366388150 747 1311867743.5389750004 0.4356651008 0.2301503076 0.4356651008 0.0043378356 0.0039010000 38495301 955859216 1373700096 -0.3693715334 -0.0841217786 0.0364900641 748 1311867743.5749680996 0.4348323345 0.2304239467 0.4356651008 0.0043378621 0.0087620000 38498285 955859216 1373700096 -0.3679514527 -0.0833941400 0.0360284448 749 1311867743.6036109924 0.4355234504 0.2306977778 0.4356651008 0.0043416100 0.0071270000 38501045 955859216 1373700096 -0.3691699803 -0.0833568797 0.0361617357 750 1311867743.6354589462 0.4355178475 0.2309708712 0.4356651008 0.0043417264 0.0046550000 38503917 955859216 1373700096 -0.3693443239 -0.0831813514 0.0358549133 751 1311867743.6759150028 0.4351130426 0.2312426983 0.4356651008 0.0043389558 0.0039190000 38507013 955859216 1373700096 -0.3690469861 -0.0837221369 0.0355514735 752 1311867743.7034959793 0.4357975423 0.2315147128 0.4357975423 0.0043361396 0.0085000000 38509773 955859216 1373700096 -0.3699207306 -0.0837797597 0.0355838053 753 1311867743.7388861179 0.4350355268 0.2317849927 0.4357975423 0.0043341154 0.0051370000 38512757 955859216 1373700096 -0.3693937957 -0.0837584734 0.0350292325 754 1311867743.7733619213 0.4353316128 0.2320549485 0.4357975423 0.0043314593 0.0034760000 38515741 955859216 1373700096 -0.3699202240 -0.0842770264 0.0348155871 755 1311867743.8064749241 0.4358051717 0.2323248163 0.4358051717 0.0043289259 0.0035750000 38518557 955859216 1373700096 -0.3705732524 -0.0844527483 0.0346009284 756 1311867743.8391659260 0.4370835721 0.2325956612 0.4370835721 0.0043271066 0.0036980000 38521429 955859216 1373700096 -0.3721362352 -0.0849104300 0.0344722606 757 1311867743.8726658821 0.4356435537 0.2328638883 0.4370835721 0.0043250361 0.0037090000 38524413 955859216 1373700096 -0.3709544539 -0.0852319747 0.0339090675 758 1311867743.9031310081 0.4358649254 0.2331316997 0.4370835721 0.0043224505 0.0088530000 38527229 955859216 1373700096 -0.3710882664 -0.0853133351 0.0335162207 759 1311867743.9453630447 0.4372166395 0.2334005863 0.4372166395 0.0043201130 0.0081820000 38530381 955859216 1373700096 -0.3726038337 -0.0857107490 0.0334465094 760 1311867743.9741249084 0.4370980263 0.2336686092 0.4372166395 0.0043183720 0.0047940000 38533141 955859216 1373700096 -0.3725935519 -0.0852894783 0.0329053216 761 1311867744.0042529106 0.4366938174 0.2339353966 0.4372166395 0.0043171144 0.0039530000 38535901 955859216 1373700096 -0.3722015917 -0.0843085945 0.0327131264 762 1311867744.0407259464 0.4365169704 0.2342012517 0.4372166395 0.0043151875 0.0037230000 38538941 955859216 1373700096 -0.3720528483 -0.0840545818 0.0326097719 763 1311867744.0716118813 0.4359340370 0.2344656459 0.4372166395 0.0043127550 0.0035610000 38541757 955859216 1373700096 -0.3716103137 -0.0836926401 0.0324636437 764 1311867744.1111290455 0.4358932972 0.2347292947 0.4372166395 0.0043099696 0.0035410000 38544685 955859216 1373700096 -0.3716034889 -0.0835652500 0.0322425142 765 1311867744.1412119865 0.4362201095 0.2349926814 0.4372166395 0.0043076702 0.0035720000 38547501 955859216 1373700096 -0.3719605207 -0.0826230273 0.0319807045 766 1311867744.1734991074 0.4354179800 0.2352543332 0.4372166395 0.0043050441 0.0037870000 38550429 955859216 1373700096 -0.3709397316 -0.0817426667 0.0318044536 767 1311867744.2046771049 0.4367959499 0.2355170993 0.4372166395 0.0043076483 0.0048070000 38553245 955859216 1373700096 -0.3722942173 -0.0822108984 0.0317732356 768 1311867744.2400228977 0.4369636774 0.2357793996 0.4372166395 0.0043061472 0.0045390000 38556285 955859216 1373700096 -0.3725299537 -0.0822896063 0.0317079499 769 1311867744.2773048878 0.4366284311 0.2360405817 0.4372166395 0.0043036134 0.0046120000 38559269 955859216 1373700096 -0.3721586764 -0.0812133253 0.0315566547 770 1311867744.3032519817 0.4360432923 0.2363003254 0.4372166395 0.0043018200 0.0045790000 38561973 955859216 1373700096 -0.3717428744 -0.0815204382 0.0313315503 771 1311867744.3391230106 0.4363886118 0.2365598433 0.4372166395 0.0043016452 0.0089240000 38564957 955859216 1373700096 -0.3719296753 -0.0819061548 0.0314271376 772 1311867744.3707659245 0.4360303283 0.2368182248 0.4372166395 0.0042990853 0.0071660000 38567773 955859216 1373700096 -0.3713951409 -0.0814278275 0.0312661417 773 1311867744.4027431011 0.4370780289 0.2370772931 0.4372166395 0.0042972496 0.0046160000 38570701 955859216 1373700096 -0.3722925484 -0.0813748613 0.0315184928 774 1311867744.4383800030 0.4378461242 0.2373366843 0.4378461242 0.0042950604 0.0038710000 38573629 955859216 1373700096 -0.3730580509 -0.0816329643 0.0312447604 775 1311867744.4717690945 0.4385685027 0.2375963383 0.4385685027 0.0042935905 0.0078600000 38576557 955859216 1373700096 -0.3736086190 -0.0817903131 0.0315396786 776 1311867744.5026860237 0.4375573695 0.2378540200 0.4385685027 0.0042909177 0.0046550000 38579429 955859216 1373700096 -0.3725319803 -0.0810195059 0.0309657268 777 1311867744.5383169651 0.4378103316 0.2381113641 0.4385685027 0.0042908985 0.0041110000 38582413 955859216 1373700096 -0.3726679087 -0.0813578293 0.0306490343 778 1311867744.5726189613 0.4375925064 0.2383677666 0.4385685027 0.0042882590 0.0038660000 38585341 955859216 1373700096 -0.3723610342 -0.0821210146 0.0304887444 779 1311867744.6028740406 0.4382680655 0.2386243780 0.4385685027 0.0042885699 0.0086770000 38588157 955859216 1373700096 -0.3725463152 -0.0819401518 0.0304262713 780 1311867744.6386809349 0.4378581941 0.2388798060 0.4385685027 0.0042890809 0.0053380000 38591141 955859216 1373700096 -0.3725093603 -0.0818386823 0.0301403590 781 1311867744.6707758904 0.4366310239 0.2391330085 0.4385685027 0.0042865877 0.0041700000 38594013 955859216 1373700096 -0.3713495433 -0.0815905705 0.0296526160 782 1311867744.7029349804 0.4385150075 0.2393879727 0.4385685027 0.0042898838 0.0038880000 38596885 955859216 1373700096 -0.3725688457 -0.0815089643 0.0299980305 783 1311867744.7396171093 0.4364818633 0.2396396891 0.4385685027 0.0042936710 0.0085190000 38599869 955859216 1373700096 -0.3710710406 -0.0807375014 0.0296122395 784 1311867744.7705199718 0.4373010397 0.2398918081 0.4385685027 0.0042912041 0.0053410000 38602685 955859216 1373700096 -0.3718991578 -0.0813646317 0.0297995117 785 1311867744.8035891056 0.4377417862 0.2401438463 0.4385685027 0.0042920971 0.0041300000 38605613 955859216 1373700096 -0.3719663024 -0.0818618611 0.0297130048 786 1311867744.8424170017 0.4371766150 0.2403945242 0.4385685027 0.0042899173 0.0038990000 38608653 955859216 1373700096 -0.3712058663 -0.0820638537 0.0297595114 787 1311867744.8727390766 0.4371618629 0.2406445462 0.4385685027 0.0042908561 0.0085570000 38611525 955859216 1373700096 -0.3718022704 -0.0825452358 0.0294960029 788 1311867744.9029939175 0.4374684393 0.2408943227 0.4385685027 0.0042882308 0.0060940000 38614341 955859216 1373700096 -0.3721471429 -0.0832418278 0.0293163732 789 1311867744.9392940998 0.4373575449 0.2411433255 0.4385685027 0.0042898793 0.0044050000 38617381 955859216 1373700096 -0.3713866770 -0.0833487362 0.0290943123 790 1311867744.9708900452 0.4370506108 0.2413913094 0.4385685027 0.0042906157 0.0060820000 38620141 955859216 1373700096 -0.3715310395 -0.0833289921 0.0286023356 791 1311867745.0027489662 0.4371474683 0.2416387888 0.4385685027 0.0042942396 0.0045940000 38623013 955859216 1373700096 -0.3711542785 -0.0832453296 0.0280226171 792 1311867745.0384869576 0.4374373555 0.2418860092 0.4385685027 0.0042941176 0.0042330000 38625997 955859216 1373700096 -0.3717291057 -0.0835270733 0.0282684378 793 1311867745.0729780197 0.4368056953 0.2421318095 0.4385685027 0.0042942407 0.0087070000 38628925 955859216 1373700096 -0.3709927797 -0.0837539360 0.0280866884 794 1311867745.1118760109 0.4365226030 0.2423766342 0.4385685027 0.0042944567 0.0053890000 38631965 955859216 1373700096 -0.3709564507 -0.0834310800 0.0276178028 795 1311867745.1405589581 0.4355330765 0.2426195983 0.4385685027 0.0042933823 0.0042290000 38634725 955859216 1373700096 -0.3698807061 -0.0833627507 0.0272563715 796 1311867745.1729030609 0.4364853799 0.2428631483 0.4385685027 0.0042909998 0.0086070000 38637597 955859216 1373700096 -0.3706877232 -0.0840154290 0.0274490453 797 1311867745.2068369389 0.4374775887 0.2431073320 0.4385685027 0.0042885427 0.0047640000 38640525 955859216 1373700096 -0.3716995418 -0.0842624828 0.0275726523 798 1311867745.2430789471 0.4362357855 0.2433493476 0.4385685027 0.0042865153 0.0074270000 38643509 955859216 1373700096 -0.3702326715 -0.0838080794 0.0274741873 799 1311867745.2729060650 0.4383202791 0.2435933663 0.4385685027 0.0042845219 0.0047500000 38646325 955859216 1373700096 -0.3721366823 -0.0839909464 0.0278736055 800 1311867745.3112850189 0.4373186827 0.2438355229 0.4385685027 0.0042832778 0.0064060000 38649309 955859216 1373700096 -0.3711551726 -0.0838720202 0.0274186581 801 1311867745.3395059109 0.4368309379 0.2440764660 0.4385685027 0.0042806693 0.0058670000 38652125 955859216 1373700096 -0.3705820441 -0.0837449208 0.0270736367 802 1311867745.3733940125 0.4366741478 0.2443166128 0.4385685027 0.0042795859 0.0046500000 38655053 955859216 1373700096 -0.3703391552 -0.0837070569 0.0267023351 803 1311867745.4102098942 0.4364317358 0.2445558595 0.4385685027 0.0042772945 0.0080070000 38658037 955859216 1373700096 -0.3697961271 -0.0841322467 0.0265345033 804 1311867745.4433169365 0.4376981854 0.2447960863 0.4385685027 0.0042752052 0.0047330000 38660965 955859216 1373700096 -0.3709758818 -0.0839383453 0.0265718792 805 1311867745.4708619118 0.4362525940 0.2450339204 0.4385685027 0.0042728414 0.0071850000 38663669 955859216 1373700096 -0.3695855141 -0.0835805833 0.0260235928 806 1311867745.5099780560 0.4372805655 0.2452724399 0.4385685027 0.0042719576 0.0047810000 38666765 955859216 1373700096 -0.3703968227 -0.0836627632 0.0256845821 807 1311867745.5417380333 0.4372511208 0.2455103317 0.4385685027 0.0042710344 0.0054940000 38669637 955859216 1373700096 -0.3701316714 -0.0840498507 0.0255728830 808 1311867745.5704059601 0.4368286729 0.2457471118 0.4385685027 0.0042688273 0.0042590000 38672397 955859216 1373700096 -0.3697906435 -0.0847883821 0.0251737647 809 1311867745.6133821011 0.4365503788 0.2459829625 0.4385685027 0.0042672256 0.0087730000 38675605 955859216 1373700096 -0.3695457876 -0.0848498791 0.0247985572 810 1311867745.6438291073 0.4359281063 0.2462174627 0.4385685027 0.0042684345 0.0050660000 38678477 955859216 1373700096 -0.3689073622 -0.0846533254 0.0243046694 811 1311867745.6709001064 0.4367394447 0.2464523850 0.4385685027 0.0042726810 0.0042680000 38681125 955859216 1373700096 -0.3696151376 -0.0844428390 0.0243217032 812 1311867745.7088780403 0.4374352694 0.2466875856 0.4385685027 0.0042711495 0.0086100000 38684221 955859216 1373700096 -0.3699797988 -0.0842694268 0.0239878986 813 1311867745.7423269749 0.4364691377 0.2469210193 0.4385685027 0.0042713075 0.0049550000 38687093 955859216 1373700096 -0.3692615926 -0.0843397826 0.0236979015 814 1311867745.7760419846 0.4375321269 0.2471551852 0.4385685027 0.0042753725 0.0042380000 38690021 955859216 1373700096 -0.3698112965 -0.0848647207 0.0241837185 815 1311867745.8116889000 0.4368215203 0.2473879047 0.4385685027 0.0042784915 0.0083510000 38693005 955859216 1373700096 -0.3690199852 -0.0845515355 0.0243524350 816 1311867745.8389890194 0.4365921915 0.2476197727 0.4385685027 0.0042777594 0.0048760000 38695765 955859216 1373700096 -0.3689076900 -0.0847336426 0.0246597677 817 1311867745.8709759712 0.4381775856 0.2478530136 0.4385685027 0.0042759649 0.0042650000 38698581 955859216 1373700096 -0.3705040812 -0.0847139582 0.0250643417 818 1311867745.9108459949 0.4376024604 0.2480849811 0.4385685027 0.0042767839 0.0094690000 38701677 955859216 1373700096 -0.3696872294 -0.0842781514 0.0247663576 819 1311867745.9435789585 0.4383054078 0.2483172405 0.4385685027 0.0042770418 0.0054370000 38704605 955859216 1373700096 -0.3703521490 -0.0847138315 0.0245809015 820 1311867745.9732220173 0.4386503994 0.2485493541 0.4386503994 0.0042747648 0.0041470000 38707365 955859216 1373700096 -0.3703606129 -0.0861781836 0.0255052783 821 1311867746.0083909035 0.4385247529 0.2487807492 0.4386503994 0.0042736769 0.0075840000 38710293 955859216 1373700096 -0.3699704111 -0.0864600465 0.0257500093 822 1311867746.0391409397 0.4381154776 0.2490110834 0.4386503994 0.0042715445 0.0047760000 38713221 955859216 1373700096 -0.3693130016 -0.0867161155 0.0259813331 823 1311867746.0728518963 0.4377343059 0.2492403948 0.4386503994 0.0042692763 0.0083750000 38716093 955859216 1373700096 -0.3686773181 -0.0863949284 0.0256018043 824 1311867746.1113359928 0.4384751618 0.2494700486 0.4386503994 0.0042680468 0.0048910000 38719077 955859216 1373700096 -0.3689585626 -0.0867372453 0.0258695707 825 1311867746.1412689686 0.4399410486 0.2497009225 0.4399410486 0.0042661190 0.0076090000 38721949 955859216 1373700096 -0.3700487912 -0.0877473801 0.0265832637 826 1311867746.1721889973 0.4402379990 0.2499315970 0.4402379990 0.0042642613 0.0047750000 38724765 955859216 1373700096 -0.3701869249 -0.0877368525 0.0266229045 827 1311867746.2066209316 0.4398820996 0.2501612832 0.4402379990 0.0042619028 0.0041280000 38727693 955859216 1373700096 -0.3695720136 -0.0875168592 0.0264972001 828 1311867746.2386920452 0.4402942955 0.2503909124 0.4402942955 0.0042599472 0.0038740000 38730621 955859216 1373700096 -0.3702455759 -0.0884768069 0.0266289487 829 1311867746.2704648972 0.4404943883 0.2506202290 0.4404943883 0.0042574414 0.0038770000 38733493 955859216 1373700096 -0.3705536723 -0.0890956819 0.0268229917 830 1311867746.3068819046 0.4383759201 0.2508464407 0.4404943883 0.0042563161 0.0038680000 38736421 955859216 1373700096 -0.3687539399 -0.0884749591 0.0257663354 831 1311867746.3393440247 0.4381843805 0.2510718775 0.4404943883 0.0042577347 0.0093720000 38739349 955859216 1373700096 -0.3681684434 -0.0887610763 0.0259040184 832 1311867746.3797800541 0.4391132295 0.2512978887 0.4404943883 0.0042555242 0.0075350000 38742445 955859216 1373700096 -0.3693489134 -0.0890417546 0.0265220907 833 1311867746.4078478813 0.4390163124 0.2515232410 0.4404943883 0.0042538291 0.0047370000 38745205 955859216 1373700096 -0.3695340157 -0.0884586498 0.0258880109 834 1311867746.4389901161 0.4379834533 0.2517468144 0.4404943883 0.0042516988 0.0039980000 38748021 955859216 1373700096 -0.3686569035 -0.0878091455 0.0255152732 835 1311867746.4774639606 0.4370443523 0.2519687276 0.4404943883 0.0042512439 0.0058330000 38751117 955859216 1373700096 -0.3678686917 -0.0880432129 0.0254823994 836 1311867746.5066781044 0.4373160303 0.2521904349 0.4404943883 0.0042492613 0.0043360000 38753877 955859216 1373700096 -0.3680534959 -0.0878161043 0.0251039304 837 1311867746.5406761169 0.4368576109 0.2524110647 0.4404943883 0.0042485505 0.0090180000 38756805 955859216 1373700096 -0.3678160906 -0.0873990506 0.0252119321 838 1311867746.5748629570 0.4369153976 0.2526312369 0.4404943883 0.0042463619 0.0053440000 38759789 955859216 1373700096 -0.3680039048 -0.0874213427 0.0251649879 839 1311867746.6067559719 0.4365833700 0.2528504886 0.4404943883 0.0042438701 0.0059750000 38762605 955859216 1373700096 -0.3676241934 -0.0874674320 0.0254239310 840 1311867746.6396849155 0.4371567369 0.2530699008 0.4404943883 0.0042445317 0.0043370000 38765589 955859216 1373700096 -0.3682470620 -0.0875628367 0.0254922025 841 1311867746.6749529839 0.4362835288 0.2532877529 0.4404943883 0.0042454346 0.0072050000 38768517 955859216 1373700096 -0.3672505319 -0.0873854309 0.0251127835 842 1311867746.7095060349 0.4367575049 0.2535056505 0.4404943883 0.0042433232 0.0060400000 38771445 955859216 1373700096 -0.3675972223 -0.0879938677 0.0253186394 843 1311867746.7391049862 0.4372704923 0.2537236396 0.4404943883 0.0042418501 0.0043000000 38774205 955859216 1373700096 -0.3679891527 -0.0884370655 0.0257037524 844 1311867746.7751340866 0.4368799031 0.2539406494 0.4404943883 0.0042394479 0.0087610000 38777245 955859216 1373700096 -0.3676899672 -0.0883248895 0.0251714718 845 1311867746.8070099354 0.4367458224 0.2541569869 0.4404943883 0.0042370206 0.0050260000 38780117 955859216 1373700096 -0.3674152195 -0.0884443596 0.0252709016 846 1311867746.8401610851 0.4358841479 0.2543717944 0.4404943883 0.0042350274 0.0040670000 38782989 955859216 1373700096 -0.3664473891 -0.0892182365 0.0252799466 847 1311867746.8748359680 0.4361060262 0.2545863567 0.4404943883 0.0042338537 0.0084100000 38785973 955859216 1373700096 -0.3665913343 -0.0892997980 0.0247442443 848 1311867746.9086029530 0.4358398020 0.2548000989 0.4404943883 0.0042317581 0.0049090000 38788845 955859216 1373700096 -0.3660483062 -0.0889141038 0.0247217193 849 1311867746.9389610291 0.4361451864 0.2550136974 0.4404943883 0.0042296755 0.0100160000 38791717 955859216 1373700096 -0.3661090732 -0.0896036625 0.0250291564 850 1311867746.9748229980 0.4363669753 0.2552270542 0.4404943883 0.0042328777 0.0096020000 38794701 955859216 1373700096 -0.3655712903 -0.0895997807 0.0250196122 851 1311867747.0066559315 0.4353372157 0.2554386995 0.4404943883 0.0042374046 0.0059160000 38797517 955859216 1373700096 -0.3651931286 -0.0893861055 0.0244965628 852 1311867747.0389339924 0.4358442724 0.2556504431 0.4404943883 0.0042354134 0.0045200000 38800389 955859216 1373700096 -0.3656036556 -0.0895662084 0.0249207001 853 1311867747.0749640465 0.4356449246 0.2558614566 0.4404943883 0.0042355685 0.0039100000 38803429 955859216 1373700096 -0.3647996783 -0.0898596048 0.0249916613 854 1311867747.1066820621 0.4347753227 0.2560709576 0.4404943883 0.0042401293 0.0096100000 38806245 955859216 1373700096 -0.3643576503 -0.0898265168 0.0254990421 855 1311867747.1389479637 0.4344158769 0.2562795482 0.4404943883 0.0042376742 0.0078830000 38809117 955859216 1373700096 -0.3637694716 -0.0894072801 0.0256301593 856 1311867747.1744880676 0.4349516630 0.2564882773 0.4404943883 0.0042359114 0.0049650000 38812101 955859216 1373700096 -0.3640642762 -0.0898400992 0.0258263554 857 1311867747.2066030502 0.4356856346 0.2566973757 0.4404943883 0.0042336104 0.0040950000 38814973 955859216 1373700096 -0.3646450937 -0.0902033076 0.0263244119 858 1311867747.2385439873 0.4357705116 0.2569060856 0.4404943883 0.0042332569 0.0036650000 38817901 955859216 1373700096 -0.3643829226 -0.0903669447 0.0260396060 859 1311867747.2745490074 0.4343430698 0.2571126479 0.4404943883 0.0042581852 0.0090120000 38820885 955859216 1373700096 -0.3628088236 -0.0904199034 0.0253719166 860 1311867747.3064720631 0.4350307584 0.2573195294 0.4404943883 0.0042654215 0.0049470000 38823645 955859216 1373700096 -0.3635359108 -0.0906871557 0.0257224068 861 1311867747.3388469219 0.4355650246 0.2575265509 0.4404943883 0.0042731386 0.0040470000 38826629 955859216 1373700096 -0.3639006615 -0.0917430669 0.0264948811 862 1311867747.3758800030 0.4359268546 0.2577335118 0.4404943883 0.0042741790 0.0081890000 38829557 955859216 1373700096 -0.3639324903 -0.0916786343 0.0266691819 863 1311867747.4068729877 0.4351166189 0.2579390542 0.4404943883 0.0042724537 0.0056090000 38832429 955859216 1373700096 -0.3631388843 -0.0914001912 0.0267422535 864 1311867747.4396450520 0.4353140593 0.2581443494 0.4404943883 0.0042764638 0.0043170000 38835245 955859216 1373700096 -0.3631672859 -0.0916420072 0.0271369629 865 1311867747.4756069183 0.4360736609 0.2583500480 0.4404943883 0.0042764307 0.0082530000 38838229 955859216 1373700096 -0.3640092611 -0.0917372629 0.0271730665 866 1311867747.5095520020 0.4350136518 0.2585540475 0.4404943883 0.0042756173 0.0055670000 38841213 955859216 1373700096 -0.3630063236 -0.0910400599 0.0268262401 867 1311867747.5405330658 0.4350283146 0.2587575934 0.4404943883 0.0042771462 0.0043390000 38844029 955859216 1373700096 -0.3629622161 -0.0910076424 0.0263536181 868 1311867747.5766739845 0.4338934422 0.2589593628 0.4404943883 0.0042751232 0.0066780000 38847013 955859216 1373700096 -0.3617226481 -0.0913664848 0.0263859406 869 1311867747.6086390018 0.4356625080 0.2591627036 0.4404943883 0.0042734587 0.0048140000 38849885 955859216 1373700096 -0.3632381558 -0.0919889733 0.0275063850 870 1311867747.6432039738 0.4349552691 0.2593647640 0.4404943883 0.0042711749 0.0043320000 38852869 955859216 1373700096 -0.3625350296 -0.0917537287 0.0274236016 871 1311867747.6760280132 0.4345364571 0.2595658796 0.4404943883 0.0042759075 0.0091690000 38855741 955859216 1373700096 -0.3622558415 -0.0916861892 0.0272276718 872 1311867747.7068400383 0.4362786412 0.2597685319 0.4404943883 0.0042743805 0.0054960000 38858557 955859216 1373700096 -0.3640511930 -0.0920837075 0.0279063974 873 1311867747.7480750084 0.4360913336 0.2599705053 0.4404943883 0.0042793111 0.0081410000 38861821 955859216 1373700096 -0.3644140363 -0.0918363035 0.0273137018 874 1311867747.7826869488 0.4351665974 0.2601709585 0.4404943883 0.0042773508 0.0048960000 38864749 955859216 1373700096 -0.3636732101 -0.0917840973 0.0270792302 875 1311867747.8149020672 0.4352927208 0.2603710977 0.4404943883 0.0042758445 0.0046760000 38867621 955859216 1373700096 -0.3642805815 -0.0919859409 0.0268749781 876 1311867747.8466539383 0.4357900321 0.2605713476 0.4404943883 0.0042737373 0.0080770000 38870437 955859216 1373700096 -0.3646985888 -0.0920388550 0.0272710882 877 1311867747.8827810287 0.4360262454 0.2607714102 0.4404943883 0.0042750714 0.0049170000 38873477 955859216 1373700096 -0.3650070429 -0.0920274705 0.0276863389 878 1311867747.9150440693 0.4363785684 0.2609714183 0.4404943883 0.0042735612 0.0073480000 38876405 955859216 1373700096 -0.3660932779 -0.0912016928 0.0270256847 879 1311867747.9477820396 0.4363200665 0.2611709049 0.4404943883 0.0042712325 0.0061840000 38879277 955859216 1373700096 -0.3663462996 -0.0910087451 0.0269535556 880 1311867747.9826579094 0.4358856380 0.2613694443 0.4404943883 0.0042690231 0.0043930000 38882205 955859216 1373700096 -0.3662887216 -0.0910812244 0.0267202444 881 1311867748.0146598816 0.4362652600 0.2615679640 0.4404943883 0.0042671887 0.0089880000 38885077 955859216 1373700096 -0.3672101498 -0.0906679928 0.0267162602 882 1311867748.0469269753 0.4360131025 0.2617657476 0.4404943883 0.0042655025 0.0051170000 38887949 955859216 1373700096 -0.3674783111 -0.0897351801 0.0268792957 883 1311867748.0828750134 0.4360564947 0.2619631324 0.4404943883 0.0042631009 0.0040820000 38890989 955859216 1373700096 -0.3680750132 -0.0895753652 0.0266113896 884 1311867748.1150569916 0.4353270531 0.2621592454 0.4404943883 0.0042616534 0.0086730000 38893805 955859216 1373700096 -0.3676415980 -0.0891898423 0.0269776266 885 1311867748.1486010551 0.4374456108 0.2623573091 0.4404943883 0.0042605560 0.0050960000 38896733 955859216 1373700096 -0.3700875342 -0.0889220685 0.0269838180 886 1311867748.1831040382 0.4350125194 0.2625521795 0.4404943883 0.0042595580 0.0041030000 38899605 955859216 1373700096 -0.3681786954 -0.0879304335 0.0257465355 887 1311867748.2148320675 0.4366039634 0.2627484048 0.4404943883 0.0042584067 0.0039960000 38902533 955859216 1373700096 -0.3698731065 -0.0879998431 0.0264993627 888 1311867748.2466599941 0.4357427359 0.2629432182 0.4404943883 0.0042593089 0.0097230000 38905349 955859216 1373700096 -0.3691384494 -0.0879242495 0.0263642222 889 1311867748.2827599049 0.4354197681 0.2631372301 0.4404943883 0.0042577926 0.0052190000 38908333 955859216 1373700096 -0.3690571487 -0.0875147358 0.0260179024 890 1311867748.3148829937 0.4353788793 0.2633307600 0.4404943883 0.0042633927 0.0042240000 38911205 955859216 1373700096 -0.3690374196 -0.0874973983 0.0264312308 891 1311867748.3470869064 0.4357385337 0.2635242592 0.4404943883 0.0042679501 0.0093160000 38914077 955859216 1373700096 -0.3696267009 -0.0881819800 0.0259916112 892 1311867748.3826999664 0.4362503290 0.2637178983 0.4404943883 0.0042701982 0.0050890000 38917061 955859216 1373700096 -0.3700428605 -0.0882391557 0.0265782960 893 1311867748.4148259163 0.4364521503 0.2639113297 0.4404943883 0.0042690084 0.0041300000 38919877 955859216 1373700096 -0.3703654408 -0.0878768489 0.0262066387 894 1311867748.4520189762 0.4362794459 0.2641041352 0.4404943883 0.0042805170 0.0039800000 38922917 955859216 1373700096 -0.3707439005 -0.0879594088 0.0260111354 895 1311867748.4831318855 0.4360873997 0.2642962953 0.4404943883 0.0042781905 0.0038060000 38925789 955859216 1373700096 -0.3706423938 -0.0876983926 0.0258215722 896 1311867748.5149960518 0.4359419644 0.2644878641 0.4404943883 0.0042775539 0.0037700000 38928661 955859216 1373700096 -0.3703420460 -0.0873688832 0.0258442871 897 1311867748.5467929840 0.4363745749 0.2646794881 0.4404943883 0.0042758646 0.0037980000 38931477 955859216 1373700096 -0.3711012006 -0.0876318291 0.0261790026 898 1311867748.5827159882 0.4369665682 0.2648713445 0.4404943883 0.0042738357 0.0037830000 38934461 955859216 1373700096 -0.3718209267 -0.0876820832 0.0263045225 899 1311867748.6147999763 0.4365995228 0.2650623658 0.4404943883 0.0042731101 0.0037690000 38937389 955859216 1373700096 -0.3717180490 -0.0870554447 0.0264516454 900 1311867748.6470849514 0.4371099174 0.2652535298 0.4404943883 0.0042836806 0.0037800000 38940205 955859216 1373700096 -0.3721813858 -0.0870808437 0.0272676647 901 1311867748.6827559471 0.4369173348 0.2654440556 0.4404943883 0.0042816905 0.0038790000 38943189 955859216 1373700096 -0.3720271587 -0.0875330716 0.0274515934 902 1311867748.7147359848 0.4364831746 0.2656336777 0.4404943883 0.0043043031 0.0038150000 38946061 955859216 1373700096 -0.3717300594 -0.0880777165 0.0279682819 903 1311867748.7499361038 0.4366750121 0.2658230923 0.4404943883 0.0043022022 0.0038400000 38948989 955859216 1373700096 -0.3721747994 -0.0884558558 0.0280884057 904 1311867748.7828259468 0.4370048940 0.2660124527 0.4404943883 0.0043012643 0.0099760000 38951973 955859216 1373700096 -0.3726391196 -0.0887167081 0.0284913052 905 1311867748.8151619434 0.4362043440 0.2662005100 0.4404943883 0.0042989127 0.0081150000 38954845 955859216 1373700096 -0.3721294403 -0.0889872164 0.0283506420 906 1311867748.8466329575 0.4373619258 0.2663894299 0.4404943883 0.0042972691 0.0050100000 38957605 955859216 1373700096 -0.3736040592 -0.0892562643 0.0288551021 907 1311867748.8829579353 0.4371330142 0.2665776808 0.4404943883 0.0042973642 0.0041370000 38960589 955859216 1373700096 -0.3736775517 -0.0892706215 0.0289778374 908 1311867748.9149119854 0.4366815090 0.2667650198 0.4404943883 0.0042961079 0.0037330000 38963517 955859216 1373700096 -0.3740303218 -0.0884122178 0.0284387004 909 1311867748.9472498894 0.4373264313 0.2669526562 0.4404943883 0.0042938291 0.0036690000 38966389 955859216 1373700096 -0.3752893806 -0.0880381763 0.0280525181 910 1311867748.9829359055 0.4359841049 0.2671384050 0.4404943883 0.0042921233 0.0094530000 38969373 955859216 1373700096 -0.3748435974 -0.0868298337 0.0266252663 911 1311867749.0159859657 0.4346157908 0.2673222441 0.4404943883 0.0042898754 0.0057870000 38972245 955859216 1373700096 -0.3739234507 -0.0862224400 0.0257900525 912 1311867749.0467190742 0.4343414307 0.2675053791 0.4404943883 0.0042879026 0.0046120000 38975061 955859216 1373700096 -0.3741306365 -0.0856744274 0.0252935626 913 1311867749.0828969479 0.4343742132 0.2676881489 0.4404943883 0.0042859785 0.0064970000 38978045 955859216 1373700096 -0.3744676709 -0.0856824815 0.0255913176 914 1311867749.1158421040 0.4328444898 0.2678688452 0.4404943883 0.0042844231 0.0045100000 38980973 955859216 1373700096 -0.3731247783 -0.0852188244 0.0252344850 915 1311867749.1485249996 0.4326570630 0.2680489416 0.4404943883 0.0042821918 0.0088940000 38983901 955859216 1373700096 -0.3730943203 -0.0851134285 0.0252836999 916 1311867749.1829619408 0.4327386320 0.2682287338 0.4404943883 0.0042805367 0.0050930000 38986829 955859216 1373700096 -0.3737749457 -0.0849687457 0.0250943732 917 1311867749.2156000137 0.4323352575 0.2684076940 0.4404943883 0.0042783356 0.0058020000 38989645 955859216 1373700096 -0.3735841215 -0.0845895931 0.0247117896 918 1311867749.2468719482 0.4321617782 0.2685860754 0.4404943883 0.0042791106 0.0069330000 38992461 955859216 1373700096 -0.3733605146 -0.0851876438 0.0244375523 919 1311867749.2828478813 0.4325392246 0.2687644792 0.4404943883 0.0042806544 0.0048170000 38995445 955859216 1373700096 -0.3739839196 -0.0851905346 0.0248847976 920 1311867749.3148140907 0.4332767129 0.2689432969 0.4404943883 0.0042817157 0.0041460000 38998373 955859216 1373700096 -0.3749012053 -0.0846805796 0.0245071184 921 1311867749.3468968868 0.4331664443 0.2691216065 0.4404943883 0.0042803541 0.0038990000 39001189 955859216 1373700096 -0.3752450347 -0.0843560398 0.0245413743 922 1311867749.3828470707 0.4335458577 0.2692999408 0.4404943883 0.0042787593 0.0039300000 39004173 955859216 1373700096 -0.3759679198 -0.0843132585 0.0244941749 923 1311867749.4147930145 0.4327414334 0.2694770172 0.4404943883 0.0042769136 0.0095760000 39007101 955859216 1373700096 -0.3755188286 -0.0836659372 0.0241978671 924 1311867749.4467489719 0.4336496890 0.2696546933 0.4404943883 0.0042752188 0.0082460000 39009917 955859216 1373700096 -0.3767283559 -0.0830287859 0.0242930800 925 1311867749.4829080105 0.4316814840 0.2698298574 0.4404943883 0.0042740045 0.0051860000 39012901 955859216 1373700096 -0.3756048381 -0.0827661380 0.0238361638 926 1311867749.5159850121 0.4320415854 0.2700050320 0.4404943883 0.0042718025 0.0042100000 39015773 955859216 1373700096 -0.3764421046 -0.0832585916 0.0243062563 927 1311867749.5468530655 0.4323399365 0.2701801506 0.4404943883 0.0042707753 0.0079800000 39018645 955859216 1373700096 -0.3772956133 -0.0834749565 0.0245481823 928 1311867749.5830268860 0.4316111505 0.2703541064 0.4404943883 0.0042685922 0.0050750000 39021629 955859216 1373700096 -0.3772765100 -0.0836086869 0.0245273411 929 1311867749.6148250103 0.4304972589 0.2705264887 0.4404943883 0.0042670029 0.0058910000 39024445 955859216 1373700096 -0.3769213557 -0.0837792084 0.0241833255 930 1311867749.6469049454 0.4305919409 0.2706986021 0.4404943883 0.0042661544 0.0090050000 39027373 955859216 1373700096 -0.3772549629 -0.0842656717 0.0245130640 931 1311867749.6829149723 0.4304893017 0.2708702355 0.4404943883 0.0042647049 0.0050870000 39030357 955859216 1373700096 -0.3781030178 -0.0848263875 0.0244115349 932 1311867749.7160799503 0.4305232465 0.2710415370 0.4404943883 0.0042632071 0.0041850000 39033229 955859216 1373700096 -0.3785640299 -0.0851515010 0.0239599999 933 1311867749.7468609810 0.4303725958 0.2712123098 0.4404943883 0.0042652943 0.0087980000 39036101 955859216 1373700096 -0.3785533011 -0.0857703015 0.0239526406 934 1311867749.7828791142 0.4292072058 0.2713814692 0.4404943883 0.0042639722 0.0057510000 39039085 955859216 1373700096 -0.3780150115 -0.0860139132 0.0236475244 935 1311867749.8148949146 0.4289124906 0.2715499516 0.4404943883 0.0042633750 0.0065340000 39041901 955859216 1373700096 -0.3781904876 -0.0859744251 0.0237876046 936 1311867749.8469030857 0.4280636907 0.2717171672 0.4404943883 0.0042611787 0.0058880000 39044829 955859216 1373700096 -0.3776904047 -0.0856912732 0.0235003438 937 1311867749.8829030991 0.4293836653 0.2718854345 0.4404943883 0.0042827143 0.0059580000 39047813 955859216 1373700096 -0.3791762292 -0.0859344974 0.0236328300 938 1311867749.9149639606 0.4282986224 0.2720521863 0.4404943883 0.0042936217 0.0062880000 39050629 955859216 1373700096 -0.3788168430 -0.0856270716 0.0233968925 939 1311867749.9508709908 0.4271124303 0.2722173197 0.4404943883 0.0042919983 0.0079020000 39053613 955859216 1373700096 -0.3780963719 -0.0854173228 0.0230319556 940 1311867749.9827940464 0.4267896116 0.2723817583 0.4404943883 0.0042926561 0.0050550000 39056541 955859216 1373700096 -0.3781740367 -0.0855762139 0.0228776634 941 1311867750.0147750378 0.4259278178 0.2725449316 0.4404943883 0.0042906848 0.0069480000 39059413 955859216 1373700096 -0.3777388930 -0.0858506784 0.0224941820 942 1311867750.0470709801 0.4253285229 0.2727071222 0.4404943883 0.0042884841 0.0048200000 39062285 955859216 1373700096 -0.3774687052 -0.0860886201 0.0221652109 943 1311867750.0829339027 0.4257614613 0.2728694280 0.4404943883 0.0042877006 0.0066160000 39065269 955859216 1373700096 -0.3780791163 -0.0863791704 0.0224128682 944 1311867750.1156458855 0.4250732660 0.2730306609 0.4404943883 0.0042861973 0.0049770000 39068141 955859216 1373700096 -0.3777507842 -0.0863089561 0.0221249722 945 1311867750.1474790573 0.4260517359 0.2731925879 0.4404943883 0.0042858840 0.0090600000 39071013 955859216 1373700096 -0.3789748847 -0.0860653818 0.0223811846 946 1311867750.1828711033 0.4254118204 0.2733534962 0.4404943883 0.0042843102 0.0050960000 39073997 955859216 1373700096 -0.3785553575 -0.0862010345 0.0221225023 947 1311867750.2156589031 0.4245009124 0.2735131028 0.4404943883 0.0042822684 0.0041660000 39076869 955859216 1373700096 -0.3779872656 -0.0857317895 0.0218427964 948 1311867750.2469079494 0.4256931543 0.2736736302 0.4404943883 0.0042813275 0.0096800000 39079685 955859216 1373700096 -0.3793629706 -0.0855818838 0.0223764069 949 1311867750.2829968929 0.4257378280 0.2738338665 0.4404943883 0.0042811303 0.0055410000 39082669 955859216 1373700096 -0.3797585368 -0.0850017071 0.0226831846 950 1311867750.3150129318 0.4256768823 0.2739937012 0.4404943883 0.0042789168 0.0043820000 39085597 955859216 1373700096 -0.3799926341 -0.0846973956 0.0227942485 951 1311867750.3469090462 0.4241825640 0.2741516285 0.4404943883 0.0042779448 0.0039740000 39088413 955859216 1373700096 -0.3786984682 -0.0849282965 0.0224564523 952 1311867750.3828659058 0.4244075716 0.2743094604 0.4404943883 0.0042757961 0.0096990000 39091397 955859216 1373700096 -0.3789854348 -0.0842313170 0.0226232708 953 1311867750.4148640633 0.4237573147 0.2744662787 0.4404943883 0.0042738555 0.0056020000 39094325 955859216 1373700096 -0.3785572052 -0.0842452571 0.0226746351 954 1311867750.4469859600 0.4231340885 0.2746221150 0.4404943883 0.0042717254 0.0044270000 39097141 955859216 1373700096 -0.3782818913 -0.0845623463 0.0224685390 955 1311867750.4829618931 0.4229429662 0.2747774248 0.4404943883 0.0042701371 0.0066320000 39100069 955859216 1373700096 -0.3781929910 -0.0850347355 0.0219920557 956 1311867750.5148859024 0.4227610528 0.2749322194 0.4404943883 0.0042680567 0.0050150000 39102885 955859216 1373700096 -0.3782555163 -0.0849360749 0.0214840099 957 1311867750.5476069450 0.4220498800 0.2750859474 0.4404943883 0.0042660440 0.0090070000 39105813 955859216 1373700096 -0.3777090907 -0.0852220803 0.0212205462 958 1311867750.5827779770 0.4215430915 0.2752388254 0.4404943883 0.0042662189 0.0050860000 39108797 955859216 1373700096 -0.3774635792 -0.0848555192 0.0210677870 959 1311867750.6148829460 0.4215324521 0.2753913735 0.4404943883 0.0042654655 0.0042310000 39111613 955859216 1373700096 -0.3776911497 -0.0846466944 0.0209227782 960 1311867750.6469810009 0.4211404920 0.2755431955 0.4404943883 0.0042634289 0.0087370000 39114541 955859216 1373700096 -0.3777049780 -0.0846502632 0.0210003834 961 1311867750.6829319000 0.4206080437 0.2756941475 0.4404943883 0.0042643771 0.0051160000 39117525 955859216 1373700096 -0.3776005507 -0.0838547572 0.0210443679 962 1311867750.7149219513 0.4189851880 0.2758430986 0.4404943883 0.0042632573 0.0084070000 39120453 955859216 1373700096 -0.3761818111 -0.0834105015 0.0208819062 963 1311867750.7469151020 0.4189391732 0.2759916927 0.4404943883 0.0042617511 0.0053960000 39123269 955859216 1373700096 -0.3763082027 -0.0835280344 0.0212349650 964 1311867750.7832129002 0.4179877937 0.2761389916 0.4404943883 0.0042626246 0.0065390000 39126197 955859216 1373700096 -0.3756602407 -0.0834346935 0.0213901531 965 1311867750.8149549961 0.4169957638 0.2762849571 0.4404943883 0.0042606025 0.0046810000 39128957 955859216 1373700096 -0.3747588992 -0.0828792602 0.0218964517 966 1311867750.8468461037 0.4167906940 0.2764304082 0.4404943883 0.0042611762 0.0069650000 39131829 955859216 1373700096 -0.3747177422 -0.0828637332 0.0219427589 967 1311867750.8828840256 0.4165948629 0.2765753559 0.4404943883 0.0042591081 0.0047390000 39134869 955859216 1373700096 -0.3747065663 -0.0825916976 0.0218814984 968 1311867750.9147970676 0.4151308537 0.2767184918 0.4404943883 0.0042581598 0.0094390000 39137685 955859216 1373700096 -0.3733174205 -0.0824393183 0.0218925849 969 1311867750.9468770027 0.4153277874 0.2768615354 0.4404943883 0.0042572265 0.0053930000 39140557 955859216 1373700096 -0.3736194968 -0.0821668133 0.0219693184 970 1311867750.9830369949 0.4146274924 0.2770035622 0.4404943883 0.0042555788 0.0043420000 39143597 955859216 1373700096 -0.3731150627 -0.0822529867 0.0217916071 971 1311867751.0168409348 0.4143212736 0.2771449810 0.4404943883 0.0042546521 0.0068360000 39146525 955859216 1373700096 -0.3731106520 -0.0825547948 0.0214303229 972 1311867751.0470340252 0.4136558771 0.2772854243 0.4404943883 0.0042540997 0.0050120000 39149341 955859216 1373700096 -0.3728162348 -0.0826160237 0.0211744178 973 1311867751.0828599930 0.4123318195 0.2774242182 0.4404943883 0.0042519440 0.0043890000 39152269 955859216 1373700096 -0.3717504740 -0.0826280639 0.0206812844 974 1311867751.1174809933 0.4116804004 0.2775620582 0.4404943883 0.0042498459 0.0044050000 39155253 955859216 1373700096 -0.3714457750 -0.0828445628 0.0203081388 975 1311867751.1468789577 0.4120189250 0.2776999627 0.4404943883 0.0042510867 0.0043840000 39158013 955859216 1373700096 -0.3718960583 -0.0826116279 0.0198957212 976 1311867751.1835930347 0.4109222591 0.2778364609 0.4404943883 0.0042503681 0.0044070000 39161053 955859216 1373700096 -0.3713120818 -0.0824561268 0.0196672436 977 1311867751.2161049843 0.4112800360 0.2779730460 0.4404943883 0.0042486927 0.0044590000 39163925 955859216 1373700096 -0.3719377816 -0.0823374167 0.0195194297 978 1311867751.2468481064 0.4122730196 0.2781103670 0.4404943883 0.0042486737 0.0044000000 39166741 955859216 1373700096 -0.3728779852 -0.0824169964 0.0193864610 979 1311867751.2831909657 0.4119353890 0.2782470626 0.4404943883 0.0042498091 0.0043800000 39169781 955859216 1373700096 -0.3728075027 -0.0816426650 0.0192291941 980 1311867751.3149859905 0.4112705588 0.2783828009 0.4404943883 0.0042477082 0.0103890000 39172597 955859216 1373700096 -0.3722678423 -0.0814739466 0.0192207266 981 1311867751.3498640060 0.4117361307 0.2785187370 0.4404943883 0.0042457949 0.0063710000 39175581 955859216 1373700096 -0.3730403185 -0.0819396749 0.0190083925 982 1311867751.3834669590 0.4115975201 0.2786542551 0.4404943883 0.0042439838 0.0047760000 39178509 955859216 1373700096 -0.3732156456 -0.0817739666 0.0184441842 983 1311867751.4151160717 0.4112228751 0.2787891164 0.4404943883 0.0042440226 0.0040760000 39181381 955859216 1373700096 -0.3725989461 -0.0817802623 0.0180068463 984 1311867751.4513890743 0.4104149044 0.2789228824 0.4404943883 0.0042446331 0.0038750000 39184309 955859216 1373700096 -0.3722116947 -0.0822501853 0.0176741760 985 1311867751.4838130474 0.4100170135 0.2790559729 0.4404943883 0.0042425353 0.0100340000 39187237 955859216 1373700096 -0.3716585338 -0.0823204741 0.0170672871 986 1311867751.5149779320 0.4093639255 0.2791881311 0.4404943883 0.0042419561 0.0053640000 39190109 955859216 1373700096 -0.3714306355 -0.0820675269 0.0170106385 987 1311867751.5495769978 0.4085250497 0.2793191715 0.4404943883 0.0042402473 0.0043890000 39193037 955859216 1373700096 -0.3707822859 -0.0822419003 0.0169635955 988 1311867751.5829720497 0.4066850841 0.2794480844 0.4404943883 0.0042389628 0.0081880000 39195909 955859216 1373700096 -0.3686709106 -0.0820564628 0.0168665666 989 1311867751.6149520874 0.4056315720 0.2795756713 0.4404943883 0.0042376184 0.0050820000 39198781 955859216 1373700096 -0.3677210212 -0.0821146443 0.0166980773 990 1311867751.6501350403 0.4041668475 0.2797015210 0.4404943883 0.0042362340 0.0043890000 39201709 955859216 1373700096 -0.3667471409 -0.0823486969 0.0163365044 991 1311867751.6839730740 0.4041737020 0.2798271236 0.4404943883 0.0042341036 0.0096360000 39204693 955859216 1373700096 -0.3668594062 -0.0825218037 0.0161892213 992 1311867751.7150709629 0.4029918313 0.2799512816 0.4404943883 0.0042330515 0.0053900000 39207453 955859216 1373700096 -0.3657899201 -0.0826235190 0.0158410147 993 1311867751.7507519722 0.4020004869 0.2800741911 0.4404943883 0.0042310331 0.0044440000 39210437 955859216 1373700096 -0.3650561869 -0.0830603838 0.0157380644 994 1311867751.7830109596 0.4017783701 0.2801966300 0.4404943883 0.0042299864 0.0071930000 39213309 955859216 1373700096 -0.3650752008 -0.0830648988 0.0155233378 995 1311867751.8149600029 0.4008361995 0.2803178758 0.4404943883 0.0042293077 0.0048940000 39216181 955859216 1373700096 -0.3642266989 -0.0831844062 0.0154790031 996 1311867751.8509531021 0.3997347653 0.2804377722 0.4404943883 0.0042282887 0.0097760000 39219165 955859216 1373700096 -0.3633205891 -0.0831386074 0.0152132688 997 1311867751.8832330704 0.3996629417 0.2805573562 0.4404943883 0.0042271429 0.0054050000 39222037 955859216 1373700096 -0.3635861576 -0.0833581090 0.0152422581 998 1311867751.9149179459 0.3995300829 0.2806765673 0.4404943883 0.0042281198 0.0043890000 39224853 955859216 1373700096 -0.3639077544 -0.0829320475 0.0152105335 999 1311867751.9530611038 0.3982515931 0.2807942600 0.4404943883 0.0042262881 0.0064650000 39227949 955859216 1373700096 -0.3628435731 -0.0831138566 0.0149525683 1000 1311867751.9829521179 0.3992912173 0.2809127570 0.4404943883 0.0042257946 0.0068820000 39230765 955859216 1373700096 -0.3641510010 -0.0833484679 0.0151837226 1001 1311867752.0153670311 0.3989651203 0.2810306914 0.4404943883 0.0042267619 0.0048200000 39233581 955859216 1373700096 -0.3641889989 -0.0830153450 0.0151348785 1002 1311867752.0510330200 0.3978196979 0.2811472473 0.4404943883 0.0042257766 0.0041380000 39236565 955859216 1373700096 -0.3630101681 -0.0829804540 0.0150225842 1003 1311867752.0828928947 0.3959606588 0.2812617173 0.4404943883 0.0042245588 0.0105710000 39239493 955859216 1373700096 -0.3614182174 -0.0834160745 0.0148086334 1004 1311867752.1150529385 0.3942483366 0.2813742538 0.4404943883 0.0042224988 0.0058820000 39242309 955859216 1373700096 -0.3596348464 -0.0839206204 0.0143431760 1005 1311867752.1509859562 0.3933368325 0.2814856593 0.4404943883 0.0042214498 0.0045450000 39245293 955859216 1373700096 -0.3594150543 -0.0839166865 0.0140440278 1006 1311867752.1829679012 0.3935685158 0.2815970737 0.4404943883 0.0042221084 0.0039810000 39248221 955859216 1373700096 -0.3600313067 -0.0841114521 0.0138907246 1007 1311867752.2150039673 0.3941938877 0.2817088878 0.4404943883 0.0042209237 0.0099610000 39251093 955859216 1373700096 -0.3611407876 -0.0840589702 0.0137014808 1008 1311867752.2512340546 0.3938274980 0.2818201166 0.4404943883 0.0042201901 0.0054390000 39254021 955859216 1373700096 -0.3608190417 -0.0839158371 0.0136034964 1009 1311867752.2833271027 0.3941571116 0.2819314516 0.4404943883 0.0042192927 0.0044840000 39256893 955859216 1373700096 -0.3613224626 -0.0837511793 0.0137177026 1010 1311867752.3150799274 0.3923364580 0.2820407635 0.4404943883 0.0042197164 0.0074670000 39259709 955859216 1373700096 -0.3599470556 -0.0836311355 0.0134012224 1011 1311867752.3509979248 0.3928051591 0.2821503227 0.4404943883 0.0042199924 0.0050440000 39262693 955859216 1373700096 -0.3602075279 -0.0836856291 0.0136071043 1012 1311867752.3829851151 0.3929116726 0.2822597707 0.4404943883 0.0042180037 0.0068400000 39265621 955859216 1373700096 -0.3603801429 -0.0840207711 0.0135559691 1013 1311867752.4160280228 0.3910063207 0.2823671217 0.4404943883 0.0042164445 0.0049000000 39268493 955859216 1373700096 -0.3584970236 -0.0844021291 0.0131202126 1014 1311867752.4510710239 0.3908868432 0.2824741431 0.4404943883 0.0042218608 0.0080450000 39271477 955859216 1373700096 -0.3586962223 -0.0845738500 0.0130419089 1015 1311867752.4829080105 0.3907569647 0.2825808257 0.4404943883 0.0042217524 0.0064050000 39274349 955859216 1373700096 -0.3584117591 -0.0848901793 0.0127977869 1016 1311867752.5181159973 0.3898555934 0.2826864111 0.4404943883 0.0042218031 0.0069120000 39277277 955859216 1373700096 -0.3577547371 -0.0852119997 0.0124032330 1017 1311867752.5511059761 0.3894821405 0.2827914216 0.4404943883 0.0042215102 0.0049630000 39280149 955859216 1373700096 -0.3571695685 -0.0853395686 0.0121597396 1018 1311867752.5830090046 0.3889734149 0.2828957261 0.4404943883 0.0042196484 0.0064480000 39283077 955859216 1373700096 -0.3569593132 -0.0850176886 0.0119007081 1019 1311867752.6167891026 0.3882003129 0.2829990672 0.4404943883 0.0042179723 0.0066540000 39285949 955859216 1373700096 -0.3560342193 -0.0852237791 0.0114434408 1020 1311867752.6514921188 0.3879609704 0.2831019711 0.4404943883 0.0042182729 0.0048950000 39288877 955859216 1373700096 -0.3556635380 -0.0853438750 0.0113262348 1021 1311867752.6830079556 0.3883690536 0.2832050730 0.4404943883 0.0042203748 0.0076280000 39291749 955859216 1373700096 -0.3560773432 -0.0854821950 0.0110445274 1022 1311867752.7152869701 0.3865173161 0.2833061613 0.4404943883 0.0042227766 0.0054550000 39294677 955859216 1373700096 -0.3541140854 -0.0858063996 0.0104189329 1023 1311867752.7510609627 0.3869248927 0.2834074504 0.4404943883 0.0042208748 0.0045010000 39297549 955859216 1373700096 -0.3545786142 -0.0863235816 0.0101100337 1024 1311867752.7830440998 0.3859357238 0.2835075757 0.4404943883 0.0042276716 0.0102770000 39300477 955859216 1373700096 -0.3536067605 -0.0865069181 0.0094548929 1025 1311867752.8162839413 0.3848855495 0.2836064810 0.4404943883 0.0042256335 0.0058340000 39401653 955859216 1373700096 -0.3524885178 -0.0863779858 0.0088955285 1026 1311867752.8511059284 0.3843687773 0.2837046899 0.4404943883 0.0042236252 0.0045320000 39609381 955859216 1373700096 -0.3518290818 -0.0860587358 0.0084487684 1027 1311867752.8833000660 0.3845643401 0.2838028979 0.4404943883 0.0042221202 0.0039550000 39612309 955859216 1373700096 -0.3520845473 -0.0857173726 0.0083699711 1028 1311867752.9183809757 0.3833959699 0.2838997783 0.4404943883 0.0042201689 0.0097820000 39615293 955859216 1373700096 -0.3504268825 -0.0853710547 0.0080418214 1029 1311867752.9511129856 0.3832543492 0.2839963328 0.4404943883 0.0042229593 0.0054260000 39618109 955859216 1373700096 -0.3503024280 -0.0853690132 0.0078474442 1030 1311867752.9828579426 0.3827398419 0.2840922003 0.4404943883 0.0042215346 0.0044650000 39621037 955859216 1373700096 -0.3497976959 -0.0853822306 0.0075784256 1031 1311867753.0168170929 0.3821738660 0.2841873329 0.4404943883 0.0042196236 0.0080490000 39623909 955859216 1373700096 -0.3489851356 -0.0854723528 0.0072764959 1032 1311867753.0510199070 0.3824616969 0.2842825599 0.4404943883 0.0042175926 0.0051680000 39626837 955859216 1373700096 -0.3492974639 -0.0856202319 0.0067752479 1033 1311867753.0829060078 0.3819535673 0.2843771108 0.4404943883 0.0042182132 0.0072300000 39629653 955859216 1373700096 -0.3489167690 -0.0855643898 0.0063334303 1034 1311867753.1184310913 0.3811306357 0.2844706829 0.4404943883 0.0042162830 0.0049360000 39632693 955859216 1373700096 -0.3480518162 -0.0852697343 0.0058275806 1035 1311867753.1510760784 0.3809973001 0.2845639453 0.4404943883 0.0042143123 0.0044530000 39635509 955859216 1373700096 -0.3480337560 -0.0853447244 0.0054934933 1036 1311867753.1830070019 0.3803210557 0.2846563749 0.4404943883 0.0042134674 0.0103420000 39638325 955859216 1373700096 -0.3476496637 -0.0855706111 0.0052860291 1037 1311867753.2186999321 0.3792265654 0.2847475709 0.4404943883 0.0042128440 0.0059520000 39641365 955859216 1373700096 -0.3466011882 -0.0850704014 0.0049940152 1038 1311867753.2520470619 0.3777355850 0.2848371547 0.4404943883 0.0042108960 0.0046230000 39644181 955859216 1373700096 -0.3452677727 -0.0846181363 0.0048113759 1039 1311867753.2829909325 0.3771299124 0.2849259831 0.4404943883 0.0042089352 0.0062280000 39647053 955859216 1373700096 -0.3451000750 -0.0845576227 0.0046262173 1040 1311867753.3196740150 0.3753806353 0.2850129588 0.4404943883 0.0042119654 0.0046870000 39650093 955859216 1373700096 -0.3439297676 -0.0836111754 0.0040763984 1041 1311867753.3509368896 0.3736742139 0.2850981281 0.4404943883 0.0042101239 0.0087290000 39652853 955859216 1373700096 -0.3424142003 -0.0832199529 0.0039577004 1042 1311867753.3829340935 0.3741770983 0.2851836165 0.4404943883 0.0042087845 0.0052690000 39655781 955859216 1373700096 -0.3434115946 -0.0832023919 0.0037936792 1043 1311867753.4182109833 0.3747944236 0.2852695329 0.4404943883 0.0042079461 0.0043220000 39658765 955859216 1373700096 -0.3444206417 -0.0829413682 0.0036253722 1044 1311867753.4511721134 0.3740573227 0.2853545787 0.4404943883 0.0042068231 0.0097190000 39661581 955859216 1373700096 -0.3442872167 -0.0823677480 0.0031183497 1045 1311867753.4831509590 0.3732431829 0.2854386826 0.4404943883 0.0042054984 0.0054440000 39664509 955859216 1373700096 -0.3441115916 -0.0824390054 0.0024375839 1046 1311867753.5199849606 0.3725217581 0.2855219361 0.4404943883 0.0042041984 0.0044990000 39667549 955859216 1373700096 -0.3442001641 -0.0819501132 0.0018295121 1047 1311867753.5532789230 0.3718096912 0.2856043503 0.4404943883 0.0042024339 0.0081170000 39670421 955859216 1373700096 -0.3442236781 -0.0819054544 0.0013083784 1048 1311867753.5832290649 0.3714269102 0.2856862421 0.4404943883 0.0042011958 0.0051630000 39673237 955859216 1373700096 -0.3445056677 -0.0816266164 0.0010053334 1049 1311867753.6183180809 0.3699023724 0.2857665244 0.4404943883 0.0042002558 0.0075410000 39676221 955859216 1373700096 -0.3438582718 -0.0811148137 0.0005620797 1050 1311867753.6509299278 0.3693567216 0.2858461341 0.4404943883 0.0041982791 0.0050640000 39679093 955859216 1373700096 -0.3439213634 -0.0808437988 0.0005398911 1051 1311867753.6830120087 0.3678388596 0.2859241481 0.4404943883 0.0041963729 0.0043010000 39681909 955859216 1373700096 -0.3428506851 -0.0806212872 0.0002198862 1052 1311867753.7204821110 0.3674935699 0.2860016856 0.4404943883 0.0041945426 0.0045880000 39685005 955859216 1373700096 -0.3429443538 -0.0803511366 0.0000214672 1053 1311867753.7510209084 0.3669318855 0.2860785424 0.4404943883 0.0041929169 0.0041410000 39687765 955859216 1373700096 -0.3431759179 -0.0800508484 -0.0000312312 1054 1311867753.7865459919 0.3642555773 0.2861527141 0.4404943883 0.0041952546 0.0109720000 39690749 955859216 1373700096 -0.3413891196 -0.0800248161 -0.0002499521 1055 1311867753.8151860237 0.3644099534 0.2862268916 0.4404943883 0.0041968093 0.0060910000 39693509 955859216 1373700096 -0.3416336775 -0.0792416781 -0.0002606253 1056 1311867753.8510670662 0.3633405864 0.2862999160 0.4404943883 0.0041984860 0.0046530000 39696493 955859216 1373700096 -0.3415610492 -0.0786758065 -0.0002507586 1057 1311867753.8831698895 0.3625629842 0.2863720664 0.4404943883 0.0042021899 0.0041210000 39699421 955859216 1373700096 -0.3412914276 -0.0793773308 -0.0003457803 1058 1311867753.9155960083 0.3621637225 0.2864437032 0.4404943883 0.0042017719 0.0075440000 39702237 955859216 1373700096 -0.3415552080 -0.0790419579 -0.0004589373 1059 1311867753.9511620998 0.3626353145 0.2865156499 0.4404943883 0.0042031902 0.0050440000 39705221 955859216 1373700096 -0.3427746296 -0.0781581402 -0.0002317194 1060 1311867753.9859020710 0.3623486161 0.2865871905 0.4404943883 0.0042016661 0.0060750000 39708205 955859216 1373700096 -0.3433451653 -0.0778069347 -0.0001766584 1061 1311867754.0151760578 0.3606281281 0.2866569746 0.4404943883 0.0042007493 0.0049010000 39710965 955859216 1373700096 -0.3428756893 -0.0776326358 -0.0001646150 1062 1311867754.0510439873 0.3604053259 0.2867264175 0.4404943883 0.0042080342 0.0044900000 39714005 955859216 1373700096 -0.3433384001 -0.0773180053 0.0001556741 1063 1311867754.0839149952 0.3591754735 0.2867945727 0.4404943883 0.0042071217 0.0044760000 39716877 955859216 1373700096 -0.3428618312 -0.0765691698 0.0002691599 1064 1311867754.1166028976 0.3590554893 0.2868624871 0.4404943883 0.0042051703 0.0044880000 39719749 955859216 1373700096 -0.3436892629 -0.0764401928 0.0005808644 1065 1311867754.1511039734 0.3584667146 0.2869297211 0.4404943883 0.0042119599 0.0045320000 39722621 955859216 1373700096 -0.3438559175 -0.0759915337 0.0007492572 1066 1311867754.1832261086 0.3578122556 0.2869962151 0.4404943883 0.0042107349 0.0045050000 39725549 955859216 1373700096 -0.3440057337 -0.0750167742 0.0011229815 1067 1311867754.2166349888 0.3552756608 0.2870602071 0.4404943883 0.0042151760 0.0045730000 39728421 955859216 1373700096 -0.3428017497 -0.0747976527 0.0012026440 1068 1311867754.2522869110 0.3546711504 0.2871235132 0.4404943883 0.0042175041 0.0045210000 39731405 955859216 1373700096 -0.3432424366 -0.0751745775 0.0015279317 1069 1311867754.2873370647 0.3539296389 0.2871860072 0.4404943883 0.0042299703 0.0044660000 39734389 955859216 1373700096 -0.3438529968 -0.0745387897 0.0015409340 1070 1311867754.3188319206 0.3554641902 0.2872498186 0.4404943883 0.0042284262 0.0111040000 39737261 955859216 1373700096 -0.3465464711 -0.0744923279 0.0018100621 1071 1311867754.3511719704 0.3568235636 0.2873147801 0.4404943883 0.0042343234 0.0063460000 39740133 955859216 1373700096 -0.3489587009 -0.0748196095 0.0021051301 1072 1311867754.3868899345 0.3585807979 0.2873812596 0.4404943883 0.0042334995 0.0068320000 39743061 955859216 1373700096 -0.3517965376 -0.0743445903 0.0023248601 1073 1311867754.4159760475 0.3585276902 0.2874475657 0.4404943883 0.0042331881 0.0049300000 39745933 955859216 1373700096 -0.3522859216 -0.0739728659 0.0025375998 1074 1311867754.4545960426 0.3584422171 0.2875136687 0.4404943883 0.0042398999 0.0041780000 39748917 955859216 1373700096 -0.3532390893 -0.0739259943 0.0029835799 1075 1311867754.4863700867 0.3589297235 0.2875801022 0.4404943883 0.0042541280 0.0038820000 39751789 955859216 1373700096 -0.3542000055 -0.0743049160 0.0033992790 1076 1311867754.5164580345 0.3605828285 0.2876479486 0.4404943883 0.0042552545 0.0104760000 39754605 955859216 1373700096 -0.3562743366 -0.0746256039 0.0038437713 1077 1311867754.5513699055 0.3601241708 0.2877152432 0.4404943883 0.0042544654 0.0055950000 39757477 955859216 1373700096 -0.3562351763 -0.0742068514 0.0041232556 1078 1311867754.5835940838 0.3605729342 0.2877828292 0.4404943883 0.0042546785 0.0045850000 39760405 955859216 1373700096 -0.3571023643 -0.0749105588 0.0043459418 1079 1311867754.6154909134 0.3608286977 0.2878505269 0.4404943883 0.0042537696 0.0040330000 39763221 955859216 1373700096 -0.3577610850 -0.0751215890 0.0046165041 1080 1311867754.6510920525 0.3605753183 0.2879178647 0.4404943883 0.0042519699 0.0039020000 39766149 955859216 1373700096 -0.3579329848 -0.0746945590 0.0048105055 1081 1311867754.6872758865 0.3601604402 0.2879846941 0.4404943883 0.0042513677 0.0110520000 39769133 955859216 1373700096 -0.3580409884 -0.0749389976 0.0049046855 1082 1311867754.7162959576 0.3602677584 0.2880514991 0.4404943883 0.0042494590 0.0059300000 39771893 955859216 1373700096 -0.3583703935 -0.0755951107 0.0051472080 1083 1311867754.7516000271 0.3596433103 0.2881176042 0.4404943883 0.0042490375 0.0045440000 39774877 955859216 1373700096 -0.3581099808 -0.0750771239 0.0055246926 1084 1311867754.7865269184 0.3582564890 0.2881823080 0.4404943883 0.0042479462 0.0040620000 39777805 955859216 1373700096 -0.3572253883 -0.0747301877 0.0056802398 1085 1311867754.8154470921 0.3571787477 0.2882458992 0.4404943883 0.0042470442 0.0089350000 39780565 955859216 1373700096 -0.3565866351 -0.0753251985 0.0056587327 1086 1311867754.8510210514 0.3557707369 0.2883080767 0.4404943883 0.0042583005 0.0053360000 39783549 955859216 1373700096 -0.3559878767 -0.0753052533 0.0057875519 1087 1311867754.8877389431 0.3546307087 0.2883690911 0.4404943883 0.0042570217 0.0066920000 39786589 955859216 1373700096 -0.3555421829 -0.0754971206 0.0058177919 1088 1311867754.9201259613 0.3545861542 0.2884299524 0.4404943883 0.0042550913 0.0069280000 39789461 955859216 1373700096 -0.3561450839 -0.0766264647 0.0057924078 1089 1311867754.9510319233 0.3535994589 0.2884897958 0.4404943883 0.0042544250 0.0049490000 39792277 955859216 1373700096 -0.3557994962 -0.0768565834 0.0058252653 1090 1311867754.9837870598 0.3518985808 0.2885479690 0.4404943883 0.0042544769 0.0067230000 39795205 955859216 1373700096 -0.3552340567 -0.0764898434 0.0060906578 1091 1311867755.0183880329 0.3503507078 0.2886046168 0.4404943883 0.0042530668 0.0048610000 39798133 955859216 1373700096 -0.3543850183 -0.0759879500 0.0064831991 1092 1311867755.0540831089 0.3492704034 0.2886601716 0.4404943883 0.0042535052 0.0074510000 39801117 955859216 1373700096 -0.3538610041 -0.0760317594 0.0069325096 1093 1311867755.0850980282 0.3493143916 0.2887156649 0.4404943883 0.0042540249 0.0050120000 39803989 955859216 1373700096 -0.3542548716 -0.0762474388 0.0073027937 1094 1311867755.1156959534 0.3491784334 0.2887709325 0.4404943883 0.0042571477 0.0045120000 39806749 955859216 1373700096 -0.3546702564 -0.0763338432 0.0076191779 1095 1311867755.1556220055 0.3486122489 0.2888255821 0.4404943883 0.0042552774 0.0096840000 39809845 955859216 1373700096 -0.3547655344 -0.0764382184 0.0077949706 1096 1311867755.1847031116 0.3486761153 0.2888801903 0.4404943883 0.0042538659 0.0055350000 39812717 955859216 1373700096 -0.3553453982 -0.0768892467 0.0078540668 1097 1311867755.2151238918 0.3484611213 0.2889345029 0.4404943883 0.0042521036 0.0044620000 39815477 955859216 1373700096 -0.3555992842 -0.0763075352 0.0080571268 1098 1311867755.2512340546 0.3479003310 0.2889882058 0.4404943883 0.0042519478 0.0075470000 39818461 955859216 1373700096 -0.3557269275 -0.0765390024 0.0081910929 1099 1311867755.2832889557 0.3478787839 0.2890417914 0.4404943883 0.0042512599 0.0066010000 39821333 955859216 1373700096 -0.3560287058 -0.0778919458 0.0079642152 1100 1311867755.3192110062 0.3479978442 0.2890953878 0.4404943883 0.0042507092 0.0048070000 39824317 955859216 1373700096 -0.3564486206 -0.0781481639 0.0078382054 1101 1311867755.3553090096 0.3470380306 0.2891480151 0.4404943883 0.0042491466 0.0102960000 39827357 955859216 1373700096 -0.3560619950 -0.0781910196 0.0074750255 1102 1311867755.3900220394 0.3473923802 0.2892008685 0.4404943883 0.0042473674 0.0056010000 39830229 955859216 1373700096 -0.3567591906 -0.0796605349 0.0070908563 1103 1311867755.4156589508 0.3480181396 0.2892541933 0.4404943883 0.0042477777 0.0044530000 39832989 955859216 1373700096 -0.3576579690 -0.0795148313 0.0069838967 1104 1311867755.4549160004 0.3470333815 0.2893065295 0.4404943883 0.0042464894 0.0087180000 39836029 955859216 1373700096 -0.3573814034 -0.0789933726 0.0069597932 1105 1311867755.4860870838 0.3473130763 0.2893590241 0.4404943883 0.0042446335 0.0053260000 39838845 955859216 1373700096 -0.3579920828 -0.0799826905 0.0069797216 1106 1311867755.5161950588 0.3472068310 0.2894113277 0.4404943883 0.0042433602 0.0064300000 39841605 955859216 1373700096 -0.3580685556 -0.0798287839 0.0071110982 1107 1311867755.5550999641 0.3465594649 0.2894629521 0.4404943883 0.0042414716 0.0048300000 39844701 955859216 1373700096 -0.3577530384 -0.0793412402 0.0071153427 1108 1311867755.5854589939 0.3467741013 0.2895146769 0.4404943883 0.0042396090 0.0104370000 39847573 955859216 1373700096 -0.3581850529 -0.0790225416 0.0071147298 1109 1311867755.6171119213 0.3464829028 0.2895660459 0.4404943883 0.0042382616 0.0056320000 39850389 955859216 1373700096 -0.3581623733 -0.0786158890 0.0069912304 1110 1311867755.6542940140 0.3461451530 0.2896170181 0.4404943883 0.0042364770 0.0044890000 39853429 955859216 1373700096 -0.3580406904 -0.0783167556 0.0069727660 1111 1311867755.6831719875 0.3463581204 0.2896680902 0.4404943883 0.0042346300 0.0086800000 39856189 955859216 1373700096 -0.3585355580 -0.0786975399 0.0066276761 1112 1311867755.7182741165 0.3461886644 0.2897189180 0.4404943883 0.0042329978 0.0072890000 39859173 955859216 1373700096 -0.3587432802 -0.0792229846 0.0061974726 1113 1311867755.7511448860 0.3465848565 0.2897700105 0.4404943883 0.0042319462 0.0050810000 39862045 955859216 1373700096 -0.3594517112 -0.0795205012 0.0056888941 1114 1311867755.7863750458 0.3463468552 0.2898207976 0.4404943883 0.0042300911 0.0070370000 39864973 955859216 1373700096 -0.3595163226 -0.0792391151 0.0052683465 1115 1311867755.8156878948 0.3454433680 0.2898706834 0.4404943883 0.0042283282 0.0071270000 39867845 955859216 1373700096 -0.3586950004 -0.0799734145 0.0050620898 1116 1311867755.8554079533 0.3447364569 0.2899198462 0.4404943883 0.0042279635 0.0050130000 39870829 955859216 1373700096 -0.3582668900 -0.0792915225 0.0050785057 1117 1311867755.8848359585 0.3442436159 0.2899684799 0.4404943883 0.0042264468 0.0076570000 39873701 955859216 1373700096 -0.3581655920 -0.0787077621 0.0050600767 1118 1311867755.9156229496 0.3437337875 0.2900165705 0.4404943883 0.0042253162 0.0055630000 39876573 955859216 1373700096 -0.3578587472 -0.0793927312 0.0047964808 1119 1311867755.9550359249 0.3436592817 0.2900645086 0.4404943883 0.0042251231 0.0085920000 39879557 955859216 1373700096 -0.3581232727 -0.0788913965 0.0049104975 1120 1311867755.9855198860 0.3435474038 0.2901122612 0.4404943883 0.0042243675 0.0054840000 39882373 955859216 1373700096 -0.3581235409 -0.0785842687 0.0050204680 1121 1311867756.0173881054 0.3438296616 0.2901601803 0.4404943883 0.0042226581 0.0044540000 39885189 955859216 1373700096 -0.3585142791 -0.0791019127 0.0050139059 1122 1311867756.0554430485 0.3432187736 0.2902074696 0.4404943883 0.0042215476 0.0041300000 39888173 955859216 1373700096 -0.3580038249 -0.0788773745 0.0050920141 1123 1311867756.0835959911 0.3430386782 0.2902545143 0.4404943883 0.0042199102 0.0041620000 39890989 955859216 1373700096 -0.3580023646 -0.0783582404 0.0051692068 1124 1311867756.1196908951 0.3433214724 0.2903017269 0.4404943883 0.0042198196 0.0041100000 39893973 955859216 1373700096 -0.3581721783 -0.0791951194 0.0051077837 1125 1311867756.1519339085 0.3428643942 0.2903484493 0.4404943883 0.0042180104 0.0041070000 39896677 955859216 1373700096 -0.3577011526 -0.0792318359 0.0050620125 1126 1311867756.1836869717 0.3430552483 0.2903952582 0.4404943883 0.0042166122 0.0041190000 39899437 955859216 1373700096 -0.3580290079 -0.0785603672 0.0051758732 1127 1311867756.2230648994 0.3436871469 0.2904425447 0.4404943883 0.0042192617 0.0041330000 39902309 955859216 1373700096 -0.3584482372 -0.0792682171 0.0053929705 1128 1311867756.2552509308 0.3432651758 0.2904893733 0.4404943883 0.0042208660 0.0040930000 39905181 955859216 1373700096 -0.3579680026 -0.0794660002 0.0053697652 1129 1311867756.2851591110 0.3434082270 0.2905362456 0.4404943883 0.0042203399 0.0041020000 39908053 955859216 1373700096 -0.3580278754 -0.0785847455 0.0056229290 1130 1311867756.3200058937 0.3430761397 0.2905827411 0.4404943883 0.0042194293 0.0113910000 39910981 955859216 1373700096 -0.3576242924 -0.0784754604 0.0055789906 1131 1311867756.3546419144 0.3436465263 0.2906296587 0.4404943883 0.0042177408 0.0070270000 39913965 955859216 1373700096 -0.3580063581 -0.0790511221 0.0056047947 1132 1311867756.3843090534 0.3437951803 0.2906766247 0.4404943883 0.0042163248 0.0051560000 39916725 955859216 1373700096 -0.3581852615 -0.0788540542 0.0057577062 1133 1311867756.4231688976 0.3432609141 0.2907230362 0.4404943883 0.0042147248 0.0044020000 39919709 955859216 1373700096 -0.3575000465 -0.0787433311 0.0058887489 1134 1311867756.4510979652 0.3434622288 0.2907695434 0.4404943883 0.0042132890 0.0040260000 39922413 955859216 1373700096 -0.3575903475 -0.0794329047 0.0060082776 1135 1311867756.4865350723 0.3433040082 0.2908158293 0.4404943883 0.0042169532 0.0108390000 39925453 955859216 1373700096 -0.3574292064 -0.0792263970 0.0061880113 1136 1311867756.5264549255 0.3435630202 0.2908622617 0.4404943883 0.0042159024 0.0058010000 39928493 955859216 1373700096 -0.3574657142 -0.0794302225 0.0063683055 1137 1311867756.5525779724 0.3433621228 0.2909084357 0.4404943883 0.0042141732 0.0046400000 39931253 955859216 1373700096 -0.3570909500 -0.0797527134 0.0064775082 1138 1311867756.5897810459 0.3430284262 0.2909542354 0.4404943883 0.0042125239 0.0072000000 39934293 955859216 1373700096 -0.3566427827 -0.0796866789 0.0065892134 1139 1311867756.6202929020 0.3436958194 0.2910005405 0.4404943883 0.0042107986 0.0050900000 39937053 955859216 1373700096 -0.3571864963 -0.0800485015 0.0066479868 1140 1311867756.6518390179 0.3437988162 0.2910468548 0.4404943883 0.0042089504 0.0078700000 39939925 955859216 1373700096 -0.3571818769 -0.0806375742 0.0069584809 1141 1311867756.6839349270 0.3429092467 0.2910923083 0.4404943883 0.0042080255 0.0057180000 39942741 955859216 1373700096 -0.3563981652 -0.0804493129 0.0071275970 1142 1311867756.7217059135 0.3427678943 0.2911375583 0.4404943883 0.0042090848 0.0043830000 39945725 955859216 1373700096 -0.3564143777 -0.0803687274 0.0074181291 1143 1311867756.7516939640 0.3425915539 0.2911825750 0.4404943883 0.0042075361 0.0095990000 39948541 955859216 1373700096 -0.3562041223 -0.0807327777 0.0075356262 1144 1311867756.7872660160 0.3423239887 0.2912272790 0.4404943883 0.0042057736 0.0074020000 39951525 955859216 1373700096 -0.3558757007 -0.0809336603 0.0075827725 1145 1311867756.8227219582 0.3423053622 0.2912718887 0.4404943883 0.0042039477 0.0052050000 39954509 955859216 1373700096 -0.3560095131 -0.0806473121 0.0078177499 1146 1311867756.8542120457 0.3422212005 0.2913163471 0.4404943883 0.0042115806 0.0044230000 39957325 955859216 1373700096 -0.3558228016 -0.0812807828 0.0079984525 1147 1311867756.8841960430 0.3421725333 0.2913606855 0.4404943883 0.0042197952 0.0075990000 39960197 955859216 1373700096 -0.3559784591 -0.0812874064 0.0083120195 1148 1311867756.9223539829 0.3414453864 0.2914043133 0.4404943883 0.0042190235 0.0051050000 39963181 955859216 1373700096 -0.3553936481 -0.0816502497 0.0084460136 1149 1311867756.9552440643 0.3417433202 0.2914481244 0.4404943883 0.0042173975 0.0085760000 39966109 955859216 1373700096 -0.3557031155 -0.0822523683 0.0084693078 1150 1311867756.9841780663 0.3412821591 0.2914914584 0.4404943883 0.0042159491 0.0053410000 39968869 955859216 1373700096 -0.3553971648 -0.0818305537 0.0085622286 1151 1311867757.0282740593 0.3409259915 0.2915344076 0.4404943883 0.0042168781 0.0043540000 39972077 955859216 1373700096 -0.3553215861 -0.0823191553 0.0086431950 1152 1311867757.0552940369 0.3412020802 0.2915775219 0.4404943883 0.0042152621 0.0100970000 39974837 955859216 1373700096 -0.3554520607 -0.0831037909 0.0085671125 1153 1311867757.0858569145 0.3410117030 0.2916203963 0.4404943883 0.0042138000 0.0057640000 39977653 955859216 1373700096 -0.3553418517 -0.0827182382 0.0086480156 1154 1311867757.1283040047 0.3409630656 0.2916631542 0.4404943883 0.0042196545 0.0046280000 39980749 955859216 1373700096 -0.3552979827 -0.0836685747 0.0086105242 1155 1311867757.1522068977 0.3413580954 0.2917061801 0.4404943883 0.0042188997 0.0067880000 39983341 955859216 1373700096 -0.3554952145 -0.0849676877 0.0083878357 1156 1311867757.1851921082 0.3422581553 0.2917499102 0.4404943883 0.0042171902 0.0047930000 39986269 955859216 1373700096 -0.3562611938 -0.0849677324 0.0084900958 1157 1311867757.2192370892 0.3431554437 0.2917943402 0.4404943883 0.0042163474 0.0107060000 39989253 955859216 1373700096 -0.3569701016 -0.0856598616 0.0083153993 1158 1311867757.2523930073 0.3438040614 0.2918392536 0.4404943883 0.0042334879 0.0058800000 39992125 955859216 1373700096 -0.3572583497 -0.0868879929 0.0078320960 1159 1311867757.2835690975 0.3438907266 0.2918841643 0.4404943883 0.0042348521 0.0047080000 39994941 955859216 1373700096 -0.3573153317 -0.0862953365 0.0074946601 1160 1311867757.3233768940 0.3448891938 0.2919298583 0.4404943883 0.0042433724 0.0068740000 39998037 955859216 1373700096 -0.3579277694 -0.0857049972 0.0073110210 1161 1311867757.3555359840 0.3456479609 0.2919761271 0.4404943883 0.0042416413 0.0073130000 40000965 955859216 1373700096 -0.3585868478 -0.0862504318 0.0072679925 1162 1311867757.3833439350 0.3460372686 0.2920226513 0.4404943883 0.0042407862 0.0051480000 40003669 955859216 1373700096 -0.3589751720 -0.0857642516 0.0074980184 1163 1311867757.4264349937 0.3462963402 0.2920693183 0.4404943883 0.0042405674 0.0078850000 40006765 955859216 1373700096 -0.3590102494 -0.0862279832 0.0075133978 1164 1311867757.4546940327 0.3469054103 0.2921164284 0.4404943883 0.0042402935 0.0052150000 40009525 955859216 1373700096 -0.3595713973 -0.0865805149 0.0075802640 1165 1311867757.4884710312 0.3468742967 0.2921634308 0.4404943883 0.0042385208 0.0073290000 40012509 955859216 1373700096 -0.3594927192 -0.0859020352 0.0076120854 1166 1311867757.5210690498 0.3468550146 0.2922103361 0.4404943883 0.0042401677 0.0052030000 40015213 955859216 1373700096 -0.3592299223 -0.0869731531 0.0075790002 1167 1311867757.5554831028 0.3471748233 0.2922574351 0.4404943883 0.0042386682 0.0078880000 40018197 955859216 1373700096 -0.3595316708 -0.0873236582 0.0076766885 1168 1311867757.5887749195 0.3475732207 0.2923047945 0.4404943883 0.0042375095 0.0051930000 40021125 955859216 1373700096 -0.3599244058 -0.0869347826 0.0078726355 1169 1311867757.6231749058 0.3474955261 0.2923520064 0.4404943883 0.0042365343 0.0043570000 40024053 955859216 1373700096 -0.3599967062 -0.0873885229 0.0080396226 1170 1311867757.6566219330 0.3477257192 0.2923993344 0.4404943883 0.0042348838 0.0110050000 40026925 955859216 1373700096 -0.3601975739 -0.0871404111 0.0083035827 1171 1311867757.6914329529 0.3475119770 0.2924463990 0.4404943883 0.0042335538 0.0058990000 40029853 955859216 1373700096 -0.3600557148 -0.0867672414 0.0084151998 1172 1311867757.7207450867 0.3477884531 0.2924936192 0.4404943883 0.0042317576 0.0046190000 40032725 955859216 1373700096 -0.3603475392 -0.0873394981 0.0086771781 1173 1311867757.7614738941 0.3475883603 0.2925405882 0.4404943883 0.0042301226 0.0090660000 40035765 955859216 1373700096 -0.3601994216 -0.0877280831 0.0087735951 1174 1311867757.7876570225 0.3477615416 0.2925876248 0.4404943883 0.0042283241 0.0054420000 40038525 955859216 1373700096 -0.3603795171 -0.0878209621 0.0088212127 1175 1311867757.8206570148 0.3477991223 0.2926346133 0.4404943883 0.0042266544 0.0044010000 40041453 955859216 1373700096 -0.3603788316 -0.0884238183 0.0086058360 1176 1311867757.8555610180 0.3484380841 0.2926820653 0.4404943883 0.0042253260 0.0101160000 40044325 955859216 1373700096 -0.3611591756 -0.0885800794 0.0084840963 1177 1311867757.8887560368 0.3489399552 0.2927298630 0.4404943883 0.0042264506 0.0056860000 40047253 955859216 1373700096 -0.3616248667 -0.0885009691 0.0082738670 1178 1311867757.9201729298 0.3491562307 0.2927777631 0.4404943883 0.0042247303 0.0046070000 40050069 955859216 1373700096 -0.3618526459 -0.0887394994 0.0082217399 1179 1311867757.9554479122 0.3489749432 0.2928254282 0.4404943883 0.0042232541 0.0078700000 40053053 955859216 1373700096 -0.3615970314 -0.0887862593 0.0080115963 1180 1311867757.9904439449 0.3491778374 0.2928731845 0.4404943883 0.0042284766 0.0052930000 40056093 955859216 1373700096 -0.3616488278 -0.0885276198 0.0078811916 1181 1311867758.0221159458 0.3487449288 0.2929204934 0.4404943883 0.0042274812 0.0090990000 40058909 955859216 1373700096 -0.3611007929 -0.0888002440 0.0075790584 1182 1311867758.0557579994 0.3487666249 0.2929677405 0.4404943883 0.0042258671 0.0054460000 40061893 955859216 1373700096 -0.3610935509 -0.0890299156 0.0075417920 1183 1311867758.0871500969 0.3490000963 0.2930151051 0.4404943883 0.0042241822 0.0043280000 40064653 955859216 1373700096 -0.3613097668 -0.0893206149 0.0072426121 1184 1311867758.1223280430 0.3492633402 0.2930626121 0.4404943883 0.0042225131 0.0104640000 40067637 955859216 1373700096 -0.3614593148 -0.0896807387 0.0070421300 1185 1311867758.1526539326 0.3498190939 0.2931105079 0.4404943883 0.0042251212 0.0067630000 40070453 955859216 1373700096 -0.3620125651 -0.0900224447 0.0068301773 1186 1311867758.1877539158 0.3496429622 0.2931581743 0.4404943883 0.0042236420 0.0071850000 40073437 955859216 1373700096 -0.3618537486 -0.0901324898 0.0063976934 1187 1311867758.2221779823 0.3500958979 0.2932061421 0.4404943883 0.0042234776 0.0051050000 40076365 955859216 1373700096 -0.3622918427 -0.0905302837 0.0060042166 1188 1311867758.2562980652 0.3507383466 0.2932545699 0.4404943883 0.0042218209 0.0043900000 40079293 955859216 1373700096 -0.3630495369 -0.0908387378 0.0056694997 1189 1311867758.2902839184 0.3505300283 0.2933027410 0.4404943883 0.0042204854 0.0040730000 40082277 955859216 1373700096 -0.3629164398 -0.0913110599 0.0052117952 1190 1311867758.3220090866 0.3499101400 0.2933503102 0.4404943883 0.0042207754 0.0116130000 40085093 955859216 1373700096 -0.3623045981 -0.0916325822 0.0049129799 1191 1311867758.3539829254 0.3492150009 0.2933972159 0.4404943883 0.0042194765 0.0059410000 40088021 955859216 1373700096 -0.3618494868 -0.0915413871 0.0045738155 1192 1311867758.3902978897 0.3491886258 0.2934440208 0.4404943883 0.0042178700 0.0046880000 40090949 955859216 1373700096 -0.3620567322 -0.0915729031 0.0043625487 1193 1311867758.4210340977 0.3496757746 0.2934911556 0.4404943883 0.0042161160 0.0041170000 40093821 955859216 1373700096 -0.3626868427 -0.0922466442 0.0040194546 1194 1311867758.4536960125 0.3501165509 0.2935385805 0.4404943883 0.0042151101 0.0102570000 40096693 955859216 1373700096 -0.3633081019 -0.0918904468 0.0039725732 1195 1311867758.4900159836 0.3492082059 0.2935851660 0.4404943883 0.0042137879 0.0124450000 40099621 955859216 1373700096 -0.3627904058 -0.0902468935 0.0039662630 1196 1311867758.5217890739 0.3498159945 0.2936321817 0.4404943883 0.0042123844 0.0117660000 40102493 955859216 1373700096 -0.3634155989 -0.0908553824 0.0040447717 1197 1311867758.5528969765 0.3504606485 0.2936796575 0.4404943883 0.0042106987 0.0118270000 40105365 955859216 1373700096 -0.3641165793 -0.0916689485 0.0041138879 1198 1311867758.5893049240 0.3504217565 0.2937270215 0.4404943883 0.0042095123 0.0051670000 40108349 955859216 1373700096 -0.3643102348 -0.0909556001 0.0042905835 1199 1311867758.6221299171 0.3497303426 0.2937737298 0.4404943883 0.0042097581 0.0040770000 40111221 955859216 1373700096 -0.3637799919 -0.0913209990 0.0042091119 1200 1311867758.6535029411 0.3509823680 0.2938214037 0.4404943883 0.0042080604 0.0092090000 40114149 955859216 1373700096 -0.3649787903 -0.0923983827 0.0043880413 1201 1311867758.6911680698 0.3510607481 0.2938690634 0.4404943883 0.0042082349 0.0054140000 40117133 955859216 1373700096 -0.3651985228 -0.0916506797 0.0045592580 1202 1311867758.7212190628 0.3507300019 0.2939163687 0.4404943883 0.0042080536 0.0044450000 40119949 955859216 1373700096 -0.3647930324 -0.0921849534 0.0046307901 1203 1311867758.7601859570 0.3511140943 0.2939639146 0.4404943883 0.0042066265 0.0040300000 40122989 955859216 1373700096 -0.3652863503 -0.0922636390 0.0047528781 1204 1311867758.7879199982 0.3515719175 0.2940117618 0.4404943883 0.0042050753 0.0115890000 40125749 955859216 1373700096 -0.3658399582 -0.0923022404 0.0050163311 1205 1311867758.8218998909 0.3514380455 0.2940594185 0.4404943883 0.0042046246 0.0059540000 40128621 955859216 1373700096 -0.3657526970 -0.0927503258 0.0050642500 1206 1311867758.8574860096 0.3521510661 0.2941075873 0.4404943883 0.0042046051 0.0046910000 40131605 955859216 1373700096 -0.3664572239 -0.0935022980 0.0053050448 1207 1311867758.8875849247 0.3525881767 0.2941560385 0.4404943883 0.0042029433 0.0119320000 40134421 955859216 1373700096 -0.3668447137 -0.0932646990 0.0054960400 1208 1311867758.9205179214 0.3529831767 0.2942047365 0.4404943883 0.0042014367 0.0118810000 40137181 955859216 1373700096 -0.3671282530 -0.0935513824 0.0055103120 1209 1311867758.9576990604 0.3534514010 0.2942537412 0.4404943883 0.0042020400 0.0069810000 40140277 955859216 1373700096 -0.3674327135 -0.0948313251 0.0053909817 1210 1311867758.9880809784 0.3544837832 0.2943035181 0.4404943883 0.0042004076 0.0048520000 40143093 955859216 1373700096 -0.3682712018 -0.0956348330 0.0053611267 1211 1311867759.0196750164 0.3538260162 0.2943526696 0.4404943883 0.0041987210 0.0042400000 40145965 955859216 1373700096 -0.3677463233 -0.0950613394 0.0051620128 1212 1311867759.0579299927 0.3546307385 0.2944024040 0.4404943883 0.0041974801 0.0119340000 40149005 955859216 1373700096 -0.3687812090 -0.0945898518 0.0053064283 1213 1311867759.0873589516 0.3550102711 0.2944523692 0.4404943883 0.0041965176 0.0094940000 40151765 955859216 1373700096 -0.3694136739 -0.0938645527 0.0054940088 1214 1311867759.1199090481 0.3548105359 0.2945020877 0.4404943883 0.0041950096 0.0055070000 40154637 955859216 1373700096 -0.3694299459 -0.0932614729 0.0055344338 1215 1311867759.1563479900 0.3549861014 0.2945518687 0.4404943883 0.0041934288 0.0045330000 40157509 955859216 1373700096 -0.3695982397 -0.0934661627 0.0056578000 1216 1311867759.1888740063 0.3550412953 0.2946016133 0.4404943883 0.0041917408 0.0070590000 40160437 955859216 1373700096 -0.3697595298 -0.0936631933 0.0055819899 1217 1311867759.2214748859 0.3549802303 0.2946512260 0.4404943883 0.0041903064 0.0075500000 40163253 955859216 1373700096 -0.3697562218 -0.0941478461 0.0057237078 1218 1311867759.2585420609 0.3545164764 0.2947003765 0.4404943883 0.0041888692 0.0051960000 40166293 955859216 1373700096 -0.3693047464 -0.0944259539 0.0055299066 1219 1311867759.2957389355 0.3549121320 0.2947497708 0.4404943883 0.0041873623 0.0044360000 40169277 955859216 1373700096 -0.3696829081 -0.0949213505 0.0055891890 1220 1311867759.3223690987 0.3548853993 0.2947990623 0.4404943883 0.0041856851 0.0039550000 40171981 955859216 1373700096 -0.3696659803 -0.0951090157 0.0054609724 1221 1311867759.3619010448 0.3553844988 0.2948486819 0.4404943883 0.0041849850 0.0119610000 40175077 955859216 1373700096 -0.3699071705 -0.0952800214 0.0056671798 1222 1311867759.3886260986 0.3562650383 0.2948989407 0.4404943883 0.0041849222 0.0060430000 40177837 955859216 1373700096 -0.3707260489 -0.0962830707 0.0057498226 1223 1311867759.4206190109 0.3570151031 0.2949497307 0.4404943883 0.0041844599 0.0045980000 40180709 955859216 1373700096 -0.3713599741 -0.0965859145 0.0058751060 1224 1311867759.4585750103 0.3567799330 0.2950002456 0.4404943883 0.0041831329 0.0041630000 40183749 955859216 1373700096 -0.3710789979 -0.0963660628 0.0059307250 1225 1311867759.4905979633 0.3562822938 0.2950502718 0.4404943883 0.0041823060 0.0071940000 40186621 955859216 1373700096 -0.3707347214 -0.0957628116 0.0058715641 1226 1311867759.5243968964 0.3569747806 0.2951007812 0.4404943883 0.0041811870 0.0054440000 40189549 955859216 1373700096 -0.3710975945 -0.0965280235 0.0061680591 1227 1311867759.5617649555 0.3572295606 0.2951514159 0.4404943883 0.0041795812 0.0045690000 40192533 955859216 1373700096 -0.3712961972 -0.0966128409 0.0063666650 1228 1311867759.5870699883 0.3573360443 0.2952020548 0.4404943883 0.0041778905 0.0119840000 40195181 955859216 1373700096 -0.3712454736 -0.0970375463 0.0064396644 1229 1311867759.6198399067 0.3576819599 0.2952528928 0.4404943883 0.0041762515 0.0060320000 40198053 955859216 1373700096 -0.3713795841 -0.0978570953 0.0066116219 1230 1311867759.6576719284 0.3582406044 0.2953041023 0.4404943883 0.0041746929 0.0047080000 40201037 955859216 1373700096 -0.3716049492 -0.0981787741 0.0066632861 1231 1311867759.6904048920 0.3588172197 0.2953556971 0.4404943883 0.0041732002 0.0041110000 40203965 955859216 1373700096 -0.3719743490 -0.0984831825 0.0065977662 1232 1311867759.7190918922 0.3594775200 0.2954077440 0.4404943883 0.0041719255 0.0102280000 40206725 955859216 1373700096 -0.3723952174 -0.0990732685 0.0064455187 1233 1311867759.7576398849 0.3595138490 0.2954597360 0.4404943883 0.0041707343 0.0056510000 40209765 955859216 1373700096 -0.3723647594 -0.0991479605 0.0064060306 1234 1311867759.7871410847 0.3595722020 0.2955116910 0.4404943883 0.0041720855 0.0071810000 40212581 955859216 1373700096 -0.3724965751 -0.0988755897 0.0063588480 1235 1311867759.8209869862 0.3603639007 0.2955642029 0.4404943883 0.0041784960 0.0051230000 40215453 955859216 1373700096 -0.3732178211 -0.0998470262 0.0064201560 1236 1311867759.8573861122 0.3612952232 0.2956173833 0.4404943883 0.0041847451 0.0071570000 40218493 955859216 1373700096 -0.3738609552 -0.1002103686 0.0063104271 1237 1311867759.8883268833 0.3612960875 0.2956704785 0.4404943883 0.0041891617 0.0049370000 40221309 955859216 1373700096 -0.3737863898 -0.1004528701 0.0060333167 1238 1311867759.9261589050 0.3617887497 0.2957238858 0.4404943883 0.0041887524 0.0044290000 40224349 955859216 1373700096 -0.3741916418 -0.1014881358 0.0057004225 1239 1311867759.9576280117 0.3622416556 0.2957775725 0.4404943883 0.0041887322 0.0113520000 40227221 955859216 1373700096 -0.3746660054 -0.1016301438 0.0054430049 1240 1311867759.9870700836 0.3619056046 0.2958309015 0.4404943883 0.0041880076 0.0058910000 40229981 955859216 1373700096 -0.3744524419 -0.1012257114 0.0051142788 1241 1311867760.0261199474 0.3628155589 0.2958848779 0.4404943883 0.0041882253 0.0046010000 40233021 955859216 1373700096 -0.3754559457 -0.1017550081 0.0047454443 1242 1311867760.0566520691 0.3630636930 0.2959389671 0.4404943883 0.0041879188 0.0040260000 40235893 955859216 1373700096 -0.3758072555 -0.1018619686 0.0046141641 1243 1311867760.0870590210 0.3635970056 0.2959933983 0.4404943883 0.0041863945 0.0038940000 40238709 955859216 1373700096 -0.3765657246 -0.1010735333 0.0047888597 1244 1311867760.1246991158 0.3635472655 0.2960477021 0.4404943883 0.0041853896 0.0116170000 40241749 955859216 1373700096 -0.3767634630 -0.1009869874 0.0046466393 1245 1311867760.1576859951 0.3638550341 0.2961021658 0.4404943883 0.0041853335 0.0063790000 40244621 955859216 1373700096 -0.3769673705 -0.1016202867 0.0044177552 1246 1311867760.1870229244 0.3639559150 0.2961566231 0.4404943883 0.0041838421 0.0047410000 40247437 955859216 1373700096 -0.3772814870 -0.1009478867 0.0043506399 1247 1311867760.2261290550 0.3641139567 0.2962111197 0.4404943883 0.0041842742 0.0041640000 40250477 955859216 1373700096 -0.3775779605 -0.1015246138 0.0040124743 1248 1311867760.2573459148 0.3647411168 0.2962660316 0.4404943883 0.0041827230 0.0040220000 40253349 955859216 1373700096 -0.3782564998 -0.1021911055 0.0036459484 1249 1311867760.2895119190 0.3645964861 0.2963207397 0.4404943883 0.0041811170 0.0112640000 40256277 955859216 1373700096 -0.3782952726 -0.1020016670 0.0034872356 1250 1311867760.3248739243 0.3647198081 0.2963754590 0.4404943883 0.0041796346 0.0058870000 40259261 955859216 1373700096 -0.3785584271 -0.1020484269 0.0032519249 1251 1311867760.3574841022 0.3656144142 0.2964308059 0.4404943883 0.0041888488 0.0046610000 40262077 955859216 1373700096 -0.3794499040 -0.1031624973 0.0030624280 1252 1311867760.3897368908 0.3658496737 0.2964862522 0.4404943883 0.0041872176 0.0041690000 40265005 955859216 1373700096 -0.3797650635 -0.1037286595 0.0023211730 1253 1311867760.4247770309 0.3655144870 0.2965413426 0.4404943883 0.0041901485 0.0040770000 40267933 955859216 1373700096 -0.3798463047 -0.1031479761 0.0019697878 1254 1311867760.4572839737 0.3663338423 0.2965969985 0.4404943883 0.0041888440 0.0041340000 40270749 955859216 1373700096 -0.3803595901 -0.1032882854 0.0016378978 1255 1311867760.4886090755 0.3674040437 0.2966534185 0.4404943883 0.0041872494 0.0041070000 40273677 955859216 1373700096 -0.3814005852 -0.1038262919 0.0014029922 1256 1311867760.5243430138 0.3672919571 0.2967096594 0.4404943883 0.0041857202 0.0039770000 40276661 955859216 1373700096 -0.3811490834 -0.1035217941 0.0011470441 1257 1311867760.5571060181 0.3679766059 0.2967663554 0.4404943883 0.0041841111 0.0040050000 40279533 955859216 1373700096 -0.3816775978 -0.1040252522 0.0008767470 1258 1311867760.5894339085 0.3682761490 0.2968231994 0.4404943883 0.0041826757 0.0040890000 40282461 955859216 1373700096 -0.3819253445 -0.1044434831 0.0006442955 1259 1311867760.6240029335 0.3686646223 0.2968802617 0.4404943883 0.0041812861 0.0121710000 40285389 955859216 1373700096 -0.3821762204 -0.1042222679 0.0004406702 1260 1311867760.6560370922 0.3688693345 0.2969373959 0.4404943883 0.0041796642 0.0068680000 40288261 955859216 1373700096 -0.3821998239 -0.1043626964 0.0002008302 1261 1311867760.6867549419 0.3700473011 0.2969953736 0.4404943883 0.0041785741 0.0049780000 40291077 955859216 1373700096 -0.3833997846 -0.1054821983 -0.0000088560 1262 1311867760.7232599258 0.3697295785 0.2970530077 0.4404943883 0.0041770030 0.0042850000 40294061 955859216 1373700096 -0.3829596341 -0.1058549583 -0.0004123509 1263 1311867760.7558701038 0.3702093661 0.2971109304 0.4404943883 0.0041753770 0.0039830000 40296989 955859216 1373700096 -0.3834559917 -0.1059626043 -0.0007113877 1264 1311867760.7868170738 0.3710787594 0.2971694493 0.4404943883 0.0041738314 0.0040800000 40299805 955859216 1373700096 -0.3841382265 -0.1067134812 -0.0010271256 1265 1311867760.8233850002 0.3679805398 0.2972254264 0.4404943883 0.0041723955 0.0114810000 40302789 955859216 1373700096 -0.3808416724 -0.1071029902 -0.0016297275 1266 1311867760.8547210693 0.3674195409 0.2972808720 0.4404943883 0.0041710223 0.0065300000 40305661 955859216 1373700096 -0.3801063299 -0.1067246422 -0.0016021972 1267 1311867760.8877849579 0.3680127263 0.2973366982 0.4404943883 0.0041694481 0.0076880000 40308533 955859216 1373700096 -0.3806149364 -0.1072991043 -0.0018536936 1268 1311867760.9240860939 0.3687519431 0.2973930194 0.4404943883 0.0041715494 0.0052130000 40311573 955859216 1373700096 -0.3813103437 -0.1071118265 -0.0019897514 1269 1311867760.9559810162 0.3681814671 0.2974488023 0.4404943883 0.0041700076 0.0044170000 40314445 955859216 1373700096 -0.3808608949 -0.1063651964 -0.0021398291 1270 1311867760.9867389202 0.3684194386 0.2975046847 0.4404943883 0.0041685989 0.0040220000 40317205 955859216 1373700096 -0.3811194003 -0.1067921221 -0.0023332837 1271 1311867761.0245900154 0.3685403168 0.2975605742 0.4404943883 0.0041670298 0.0086300000 40320301 955859216 1373700096 -0.3812878132 -0.1072557047 -0.0026702837 1272 1311867761.0566051006 0.3675378561 0.2976155878 0.4404943883 0.0041654407 0.0059320000 40323173 955859216 1373700096 -0.3804073930 -0.1063857973 -0.0029384415 1273 1311867761.0866270065 0.3677116334 0.2976706515 0.4404943883 0.0041644038 0.0047010000 40325933 955859216 1373700096 -0.3806300461 -0.1065799743 -0.0030434290 1274 1311867761.1242640018 0.3687687516 0.2977264585 0.4404943883 0.0041645368 0.0040750000 40329029 955859216 1373700096 -0.3818285167 -0.1067390963 -0.0032106314 1275 1311867761.1547141075 0.3700636029 0.2977831935 0.4404943883 0.0041633716 0.0041190000 40331845 955859216 1373700096 -0.3832195401 -0.1062646806 -0.0032509146 1276 1311867761.1912519932 0.3696191013 0.2978394912 0.4404943883 0.0041629536 0.0122590000 40334773 955859216 1373700096 -0.3829368651 -0.1065377295 -0.0035607854 1277 1311867761.2244689465 0.3703606725 0.2978962815 0.4404943883 0.0041613884 0.0064640000 40337757 955859216 1373700096 -0.3837764859 -0.1071910858 -0.0035882932 1278 1311867761.2564349174 0.3711777925 0.2979536223 0.4404943883 0.0041618511 0.0047730000 40340629 955859216 1373700096 -0.3847513795 -0.1063299179 -0.0036670023 1279 1311867761.2914810181 0.3712939620 0.2980109642 0.4404943883 0.0041603302 0.0041300000 40343501 955859216 1373700096 -0.3849915862 -0.1063741744 -0.0039568730 1280 1311867761.3245120049 0.3715296090 0.2980684006 0.4404943883 0.0041589845 0.0095540000 40346485 955859216 1373700096 -0.3852645159 -0.1074531749 -0.0040580621 1281 1311867761.3563210964 0.3708447814 0.2981252128 0.4404943883 0.0041574465 0.0054940000 40349301 955859216 1373700096 -0.3847795129 -0.1069297865 -0.0043183411 1282 1311867761.3919639587 0.3706768453 0.2981818053 0.4404943883 0.0041559068 0.0044620000 40352285 955859216 1373700096 -0.3847778141 -0.1073031500 -0.0046619922 1283 1311867761.4230949879 0.3715856075 0.2982390180 0.4404943883 0.0041552933 0.0040940000 40355157 955859216 1373700096 -0.3858493865 -0.1078334376 -0.0050801062 1284 1311867761.4547801018 0.3713906109 0.2982959896 0.4404943883 0.0041539479 0.0040790000 40357973 955859216 1373700096 -0.3858000040 -0.1070468500 -0.0054288316 1285 1311867761.4908668995 0.3713143170 0.2983528132 0.4404943883 0.0041524813 0.0122740000 40361013 955859216 1373700096 -0.3858207166 -0.1066346690 -0.0058011245 1286 1311867761.5258040428 0.3721656203 0.2984102104 0.4404943883 0.0041508933 0.0065480000 40363885 955859216 1373700096 -0.3866227269 -0.1078619212 -0.0062740906 1287 1311867761.5562748909 0.3728517890 0.2984680516 0.4404943883 0.0041495757 0.0048080000 40366701 955859216 1373700096 -0.3871097863 -0.1085878536 -0.0064214254 1288 1311867761.5914149284 0.3719618917 0.2985251120 0.4404943883 0.0041484714 0.0070840000 40369629 955859216 1373700096 -0.3861869276 -0.1078210920 -0.0069028935 1289 1311867761.6232030392 0.3726652265 0.2985826296 0.4404943883 0.0041484991 0.0050360000 40372557 955859216 1373700096 -0.3867508173 -0.1089694947 -0.0074879681 1290 1311867761.6567790508 0.3733668029 0.2986406018 0.4404943883 0.0041483924 0.0042010000 40375429 955859216 1373700096 -0.3872196078 -0.1099566817 -0.0076714540 1291 1311867761.6917459965 0.3727286458 0.2986979899 0.4404943883 0.0041469544 0.0040080000 40378357 955859216 1373700096 -0.3865344822 -0.1092438176 -0.0079966858 1292 1311867761.7235610485 0.3730824292 0.2987555630 0.4404943883 0.0041474063 0.0115500000 40381229 955859216 1373700096 -0.3866594732 -0.1099411622 -0.0081717661 1293 1311867761.7545659542 0.3738554716 0.2988136449 0.4404943883 0.0041462845 0.0059590000 40384045 955859216 1373700096 -0.3872373998 -0.1107185557 -0.0083083091 1294 1311867761.7916970253 0.3737047315 0.2988715205 0.4404943883 0.0041457801 0.0046820000 40387029 955859216 1373700096 -0.3868367076 -0.1106360555 -0.0085211303 1295 1311867761.8235230446 0.3734996021 0.2989291484 0.4404943883 0.0041442511 0.0046210000 40389901 955859216 1373700096 -0.3865565658 -0.1104745865 -0.0086795324 1296 1311867761.8546519279 0.3731357157 0.2989864066 0.4404943883 0.0041426746 0.0045510000 40392773 955859216 1373700096 -0.3861072958 -0.1103699431 -0.0088683572 1297 1311867761.8910980225 0.3739379048 0.2990441949 0.4404943883 0.0041419931 0.0040680000 40395757 955859216 1373700096 -0.3867603242 -0.1099963039 -0.0087913377 1298 1311867761.9224560261 0.3734393418 0.2991015101 0.4404943883 0.0041414197 0.0118150000 40398629 955859216 1373700096 -0.3860192597 -0.1100868210 -0.0088128820 1299 1311867761.9546790123 0.3741171658 0.2991592589 0.4404943883 0.0041411025 0.0073930000 40401557 955859216 1373700096 -0.3863005042 -0.1113187522 -0.0090708127 1300 1311867761.9942779541 0.3752193153 0.2992177666 0.4404943883 0.0041399121 0.0050930000 40404653 955859216 1373700096 -0.3870755434 -0.1122616753 -0.0094456049 1301 1311867762.0235669613 0.3751904964 0.2992761623 0.4404943883 0.0041407900 0.0043170000 40407413 955859216 1373700096 -0.3867630661 -0.1123172268 -0.0098308083 1302 1311867762.0558550358 0.3753044307 0.2993345557 0.4404943883 0.0041392750 0.0074780000 40410285 955859216 1373700096 -0.3867203295 -0.1122940555 -0.0100953598 1303 1311867762.0913889408 0.3754765987 0.2993929917 0.4404943883 0.0041608441 0.0040840000 40413213 955859216 1373700096 -0.3868935108 -0.1125178337 -0.0102076745 1304 1311867762.1225299835 0.3759456575 0.2994516977 0.4404943883 0.0041595404 0.0040620000 40416085 955859216 1373700096 -0.3872208595 -0.1122513935 -0.0100103896 1305 1311867762.1545391083 0.3764692545 0.2995107150 0.4404943883 0.0041814169 0.0040870000 40419013 955859216 1373700096 -0.3872337639 -0.1125043258 -0.0100499019 1306 1311867762.1913030148 0.3766216040 0.2995697586 0.4404943883 0.0041805649 0.0040550000 40421941 955859216 1373700096 -0.3868514299 -0.1138611212 -0.0099946670 1307 1311867762.2234869003 0.3782448769 0.2996299537 0.4404943883 0.0041790636 0.0125600000 40424869 955859216 1373700096 -0.3881134987 -0.1143099964 -0.0098117795 1308 1311867762.2565600872 0.3790465593 0.2996906698 0.4404943883 0.0041775712 0.0093300000 40427797 955859216 1373700096 -0.3886662126 -0.1142647043 -0.0099920901 1309 1311867762.2907900810 0.3794287741 0.2997515851 0.4404943883 0.0041761637 0.0054730000 40430669 955859216 1373700096 -0.3888929486 -0.1146363094 -0.0098754931 1310 1311867762.3235380650 0.3794013262 0.2998123864 0.4404943883 0.0042006935 0.0046290000 40433597 955859216 1373700096 -0.3887929022 -0.1149515361 -0.0098512396 1311 1311867762.3545570374 0.3798192739 0.2998734138 0.4404943883 0.0041994696 0.0041350000 40436469 955859216 1373700096 -0.3890495896 -0.1148863435 -0.0098865889 1312 1311867762.3949799538 0.3798131347 0.2999343435 0.4404943883 0.0042168263 0.0041340000 40439565 955859216 1373700096 -0.3889038563 -0.1149890795 -0.0099040456 1313 1311867762.4242470264 0.3797838688 0.2999951580 0.4404943883 0.0042152921 0.0041290000 40442381 955859216 1373700096 -0.3886107206 -0.1160138324 -0.0101016723 1314 1311867762.4588010311 0.3798059523 0.3000558968 0.4404943883 0.0042138559 0.0040860000 40445253 955859216 1373700096 -0.3883725405 -0.1164240614 -0.0101623498 1315 1311867762.4918160439 0.3801140189 0.3001167775 0.4404943883 0.0042122774 0.0041830000 40448125 955859216 1373700096 -0.3888686001 -0.1160130650 -0.0102550043 1316 1311867762.5242910385 0.3803089261 0.3001777138 0.4404943883 0.0042110773 0.0041090000 40451053 955859216 1373700096 -0.3890777230 -0.1163268611 -0.0102629196 1317 1311867762.5594940186 0.3802193701 0.3002384896 0.4404943883 0.0042095801 0.0040500000 40454037 955859216 1373700096 -0.3890488446 -0.1166686043 -0.0102231549 1318 1311867762.5913679600 0.3794336021 0.3002985769 0.4404943883 0.0042083220 0.0124170000 40456853 955859216 1373700096 -0.3885222971 -0.1163683981 -0.0101253418 1319 1311867762.6233699322 0.3797305226 0.3003587982 0.4404943883 0.0042068283 0.0081610000 40459725 955859216 1373700096 -0.3887490928 -0.1172727048 -0.0099748457 1320 1311867762.6626110077 0.3803321421 0.3004193841 0.4404943883 0.0042053300 0.0053320000 40462821 955859216 1373700096 -0.3894946575 -0.1176956370 -0.0100014284 1321 1311867762.6927230358 0.3803207278 0.3004798696 0.4404943883 0.0042039563 0.0044120000 40465525 955859216 1373700096 -0.3894995749 -0.1181607246 -0.0100800628 1322 1311867762.7241640091 0.3790374100 0.3005392929 0.4404943883 0.0042035750 0.0042590000 40468397 955859216 1373700096 -0.3881963789 -0.1188156381 -0.0103458529 1323 1311867762.7605299950 0.3794509768 0.3005989389 0.4404943883 0.0042021157 0.0041780000 40471325 955859216 1373700096 -0.3888637722 -0.1193921641 -0.0104026906 1324 1311867762.7905199528 0.3791802526 0.3006582903 0.4404943883 0.0042008501 0.0127440000 40474141 955859216 1373700096 -0.3887153566 -0.1190970093 -0.0106214052 1325 1311867762.8258841038 0.3788975477 0.3007173388 0.4404943883 0.0041994283 0.0104460000 40477125 955859216 1373700096 -0.3886407018 -0.1178971231 -0.0102216387 1326 1311867762.8593358994 0.3793103397 0.3007766096 0.4404943883 0.0041992029 0.0056880000 40480053 955859216 1373700096 -0.3888595998 -0.1188624874 -0.0097409049 1327 1311867762.8911890984 0.3800414801 0.3008363419 0.4404943883 0.0041981817 0.0070860000 40482869 955859216 1373700096 -0.3895080090 -0.1193787605 -0.0095727555 1328 1311867762.9231870174 0.3791391253 0.3008953049 0.4404943883 0.0041969207 0.0052110000 40485797 955859216 1373700096 -0.3887453675 -0.1191384494 -0.0095205456 1329 1311867762.9586219788 0.3789663315 0.3009540491 0.4404943883 0.0041959055 0.0044210000 40488781 955859216 1373700096 -0.3886595070 -0.1191776320 -0.0094971899 1330 1311867762.9910819530 0.3791151643 0.3010128168 0.4404943883 0.0041943491 0.0041670000 40491653 955859216 1373700096 -0.3888263106 -0.1197211668 -0.0094529251 1331 1311867763.0241999626 0.3799960911 0.3010721581 0.4404943883 0.0041935146 0.0041390000 40494581 955859216 1373700096 -0.3895531595 -0.1195493788 -0.0092534469 1332 1311867763.0586409569 0.3807832599 0.3011320013 0.4404943883 0.0041924135 0.0041250000 40497453 955859216 1373700096 -0.3901644647 -0.1200912446 -0.0091380198 1333 1311867763.0910348892 0.3807014823 0.3011916933 0.4404943883 0.0041912408 0.0124670000 40500381 955859216 1373700096 -0.3898806870 -0.1207995340 -0.0094665429 1334 1311867763.1222279072 0.3795135915 0.3012504054 0.4404943883 0.0041897873 0.0061680000 40503197 955859216 1373700096 -0.3885600865 -0.1200824678 -0.0096638435 1335 1311867763.1606709957 0.3801163137 0.3013094810 0.4404943883 0.0041882478 0.0048970000 40506237 955859216 1373700096 -0.3889306188 -0.1203646287 -0.0096017206 1336 1311867763.1913530827 0.3798783720 0.3013682900 0.4404943883 0.0041876796 0.0041570000 40509109 955859216 1373700096 -0.3883306980 -0.1213788390 -0.0097626634 1337 1311867763.2239060402 0.3795484006 0.3014267643 0.4404943883 0.0041870257 0.0078910000 40511981 955859216 1373700096 -0.3879978359 -0.1197807267 -0.0095099295 1338 1311867763.2619409561 0.3799795508 0.3014854734 0.4404943883 0.0041857400 0.0053510000 40514909 955859216 1373700096 -0.3880706728 -0.1196338832 -0.0091414480 1339 1311867763.2997210026 0.3803341091 0.3015443596 0.4404943883 0.0041850232 0.0042860000 40518005 955859216 1373700096 -0.3881425858 -0.1196865439 -0.0088578165 1340 1311867763.3283360004 0.3775779307 0.3016011011 0.4404943883 0.0041838633 0.0111660000 40520765 955859216 1373700096 -0.3850030005 -0.1194665730 -0.0089487089 1341 1311867763.3595879078 0.3774113953 0.3016576338 0.4404943883 0.0041831584 0.0059880000 40523525 955859216 1373700096 -0.3846595883 -0.1189002991 -0.0086987531 1342 1311867763.3930239677 0.3775014579 0.3017141493 0.4404943883 0.0041816943 0.0047280000 40526453 955859216 1373700096 -0.3843474984 -0.1195379570 -0.0086033018 1343 1311867763.4231410027 0.3777367175 0.3017707558 0.4404943883 0.0041803298 0.0041730000 40529269 955859216 1373700096 -0.3842034042 -0.1195660010 -0.0084889783 1344 1311867763.4599080086 0.3774963915 0.3018270993 0.4404943883 0.0041787946 0.0081430000 40532309 955859216 1373700096 -0.3836246431 -0.1191789582 -0.0082314583 1345 1311867763.4920830727 0.3789956570 0.3018844737 0.4404943883 0.0041775125 0.0053930000 40535125 955859216 1373700096 -0.3845486641 -0.1204354241 -0.0081882467 1346 1311867763.5240089893 0.3784251809 0.3019413390 0.4404943883 0.0041767163 0.0076320000 40538053 955859216 1373700096 -0.3836396635 -0.1206191331 -0.0081878928 1347 1311867763.5586268902 0.3787283599 0.3019983449 0.4404943883 0.0041756921 0.0052280000 40540925 955859216 1373700096 -0.3837614954 -0.1200656295 -0.0081088683 1348 1311867763.5911428928 0.3786720634 0.3020552246 0.4404943883 0.0041746247 0.0045000000 40543853 955859216 1373700096 -0.3834142387 -0.1214038357 -0.0082879765 1349 1311867763.6315419674 0.3785984516 0.3021119653 0.4404943883 0.0041739888 0.0112180000 40546893 955859216 1373700096 -0.3831956685 -0.1217867881 -0.0083223190 1350 1311867763.6613171101 0.3783577085 0.3021684436 0.4404943883 0.0041726544 0.0059240000 40549597 955859216 1373700096 -0.3830686212 -0.1206956729 -0.0082472069 1351 1311867763.6906011105 0.3781941235 0.3022247172 0.4404943883 0.0041711496 0.0076490000 40552469 955859216 1373700096 -0.3828669190 -0.1208600998 -0.0081598116 1352 1311867763.7281720638 0.3781059086 0.3022808424 0.4404943883 0.0041699548 0.0051930000 40555509 955859216 1373700096 -0.3827775717 -0.1203906536 -0.0082597379 1353 1311867763.7617700100 0.3784639537 0.3023371492 0.4404943883 0.0041684827 0.0044170000 40558381 955859216 1373700096 -0.3829922080 -0.1208143532 -0.0083308211 1354 1311867763.7929420471 0.3790855110 0.3023938319 0.4404943883 0.0041670203 0.0041820000 40561253 955859216 1373700096 -0.3833951950 -0.1220430732 -0.0084238360 1355 1311867763.8308730125 0.3792634010 0.3024505622 0.4404943883 0.0041660099 0.0128180000 40564293 955859216 1373700096 -0.3835300803 -0.1223825663 -0.0087244092 1356 1311867763.8622579575 0.3801395297 0.3025078549 0.4404943883 0.0041650046 0.0073360000 40567109 955859216 1373700096 -0.3844919503 -0.1220574751 -0.0089704785 1357 1311867763.8950018883 0.3801122606 0.3025650431 0.4404943883 0.0041636416 0.0050760000 40570037 955859216 1373700096 -0.3843255639 -0.1229839325 -0.0092964247 1358 1311867763.9286549091 0.3798612058 0.3026219623 0.4404943883 0.0041629785 0.0043810000 40572909 955859216 1373700096 -0.3841587007 -0.1226501539 -0.0098972395 1359 1311867763.9622230530 0.3803260624 0.3026791397 0.4404943883 0.0041627234 0.0040400000 40575837 955859216 1373700096 -0.3847884834 -0.1212726608 -0.0100119198 1360 1311867763.9930698872 0.3810800910 0.3027367874 0.4404943883 0.0041616526 0.0080350000 40578653 955859216 1373700096 -0.3855201304 -0.1219953448 -0.0100417910 1361 1311867764.0303530693 0.3806709051 0.3027940498 0.4404943883 0.0041619286 0.0053060000 40581693 955859216 1373700096 -0.3849766254 -0.1227489337 -0.0103228223 1362 1311867764.0625600815 0.3802049458 0.3028508860 0.4404943883 0.0041613994 0.0079290000 40584509 955859216 1373700096 -0.3843740821 -0.1223480478 -0.0105251921 1363 1311867764.0939369202 0.3817914724 0.3029088028 0.4404943883 0.0041600740 0.0053000000 40587381 955859216 1373700096 -0.3858971298 -0.1221855655 -0.0103126150 1364 1311867764.1303229332 0.3824948967 0.3029671504 0.4404943883 0.0041588825 0.0074110000 40590365 955859216 1373700096 -0.3864201307 -0.1234322414 -0.0105487406 1365 1311867764.1600530148 0.3826459348 0.3030255231 0.4404943883 0.0041586688 0.0050570000 40593181 955859216 1373700096 -0.3865092397 -0.1231290102 -0.0104967002 1366 1311867764.1931879520 0.3822436929 0.3030835159 0.4404943883 0.0041573973 0.0044790000 40596109 955859216 1373700096 -0.3861572146 -0.1229371354 -0.0109111816 1367 1311867764.2289299965 0.3837566078 0.3031425306 0.4404943883 0.0041568844 0.0056200000 40599037 955859216 1373700096 -0.3875913024 -0.1235984787 -0.0109700840 1368 1311867764.2623479366 0.3830057085 0.3032009101 0.4404943883 0.0041564514 0.0112850000 40601965 955859216 1373700096 -0.3871049285 -0.1227151304 -0.0113316886 1369 1311867764.2925939560 0.3827556372 0.3032590217 0.4404943883 0.0041550502 0.0058980000 40604781 955859216 1373700096 -0.3870445192 -0.1227262095 -0.0115928920 1370 1311867764.3292350769 0.3845320344 0.3033183451 0.4404943883 0.0041575940 0.0046610000 40607821 955859216 1373700096 -0.3889476955 -0.1241204143 -0.0118641304 1371 1311867764.3632280827 0.3844250143 0.3033775038 0.4404943883 0.0041584601 0.0041340000 40610749 955859216 1373700096 -0.3890376985 -0.1242948696 -0.0122495852 1372 1311867764.3937499523 0.3850887120 0.3034370601 0.4404943883 0.0041572479 0.0116170000 40613565 955859216 1373700096 -0.3901140392 -0.1232784018 -0.0121106468 1373 1311867764.4299139977 0.3847209215 0.3034962618 0.4404943883 0.0041580317 0.0059640000 40616549 955859216 1373700096 -0.3899108768 -0.1252138466 -0.0126171596 1374 1311867764.4600350857 0.3853827715 0.3035558589 0.4404943883 0.0041597289 0.0047380000 40619309 955859216 1373700096 -0.3907866180 -0.1258438528 -0.0129468692 1375 1311867764.4931490421 0.3848575652 0.3036149874 0.4404943883 0.0041632288 0.0042390000 40622181 955859216 1373700096 -0.3909656405 -0.1245432496 -0.0129985847 1376 1311867764.5289220810 0.3850587904 0.3036741763 0.4404943883 0.0041704154 0.0084180000 40625165 955859216 1373700096 -0.3914787769 -0.1260252297 -0.0135632409 1377 1311867764.5604650974 0.3845256865 0.3037328919 0.4404943883 0.0041712441 0.0053450000 40627981 955859216 1373700096 -0.3910890222 -0.1269261688 -0.0141386176 1378 1311867764.5906419754 0.3843087256 0.3037913650 0.4404943883 0.0041698779 0.0044420000 40630797 955859216 1373700096 -0.3913152814 -0.1266898364 -0.0144315250 1379 1311867764.6277070045 0.3835339844 0.3038491914 0.4404943883 0.0041828570 0.0081820000 40633781 955859216 1373700096 -0.3904994130 -0.1270723492 -0.0149170421 1380 1311867764.6609039307 0.3840471804 0.3039073059 0.4404943883 0.0041900079 0.0053440000 40636765 955859216 1373700096 -0.3911595345 -0.1274987608 -0.0153446309 1381 1311867764.6907351017 0.3852133751 0.3039661806 0.4404943883 0.0041888768 0.0066110000 40639525 955859216 1373700096 -0.3925631344 -0.1271816939 -0.0152907493 1382 1311867764.7274560928 0.3853144050 0.3040250433 0.4404943883 0.0041876852 0.0052580000 40642509 955859216 1373700096 -0.3932335377 -0.1278550625 -0.0156209785 1383 1311867764.7591719627 0.3864469528 0.3040846398 0.4404943883 0.0041873438 0.0107380000 40645437 955859216 1373700096 -0.3947281241 -0.1277001649 -0.0158480797 1384 1311867764.7921779156 0.3872784674 0.3041447509 0.4404943883 0.0041869181 0.0058380000 40648253 955859216 1373700096 -0.3957001269 -0.1272715181 -0.0155721121 1385 1311867764.8278260231 0.3876405060 0.3042050367 0.4404943883 0.0041876725 0.0051560000 40651237 955859216 1373700096 -0.3962655663 -0.1284231097 -0.0158537347 1386 1311867764.8610520363 0.3877719939 0.3042653303 0.4404943883 0.0041862149 0.0041470000 40654109 955859216 1373700096 -0.3965935409 -0.1293585002 -0.0166174583 1387 1311867764.8946199417 0.3871081471 0.3043250584 0.4404943883 0.0041856309 0.0110270000 40657093 955859216 1373700096 -0.3964850307 -0.1276709884 -0.0164231732 1388 1311867764.9271790981 0.3872176111 0.3043847792 0.4404943883 0.0041868565 0.0059060000 40659965 955859216 1373700096 -0.3967767656 -0.1287391335 -0.0165733341 1389 1311867764.9599800110 0.3875755370 0.3044446718 0.4404943883 0.0041856212 0.0076090000 40662893 955859216 1373700096 -0.3975983858 -0.1284343004 -0.0167454202 1390 1311867764.9950439930 0.3872400820 0.3045042368 0.4404943883 0.0041848227 0.0052610000 40665821 955859216 1373700096 -0.3976907432 -0.1273462027 -0.0165182855 1391 1311867765.0330669880 0.3878601789 0.3045641620 0.4404943883 0.0041854173 0.0044110000 40668749 955859216 1373700096 -0.3987860680 -0.1274290830 -0.0166044869 1392 1311867765.0598719120 0.3883114159 0.3046243253 0.4404943883 0.0041845542 0.0082310000 40671509 955859216 1373700096 -0.3995263278 -0.1268411130 -0.0166958608 1393 1311867765.0951199532 0.3891652822 0.3046850151 0.4404943883 0.0041857462 0.0071180000 40674493 955859216 1373700096 -0.4003481269 -0.1269927472 -0.0166208129 1394 1311867765.1273620129 0.3882844150 0.3047449860 0.4404943883 0.0041855549 0.0051930000 40677309 955859216 1373700096 -0.3997765481 -0.1274485886 -0.0169203188 1395 1311867765.1595649719 0.3887697160 0.3048052188 0.4404943883 0.0041841721 0.0100950000 40680125 955859216 1373700096 -0.4005342722 -0.1275354475 -0.0169894006 1396 1311867765.1969060898 0.3886621296 0.3048652882 0.4404943883 0.0041827686 0.0056990000 40683053 955859216 1373700096 -0.4006179869 -0.1275328398 -0.0171121061 1397 1311867765.2290871143 0.3890550137 0.3049255528 0.4404943883 0.0041816726 0.0044410000 40685925 955859216 1373700096 -0.4010079801 -0.1286292374 -0.0173746329 1398 1311867765.2611060143 0.3891688585 0.3049858127 0.4404943883 0.0041807142 0.0041460000 40688797 955859216 1373700096 -0.4014979005 -0.1277378649 -0.0176323149 1399 1311867765.2958459854 0.3891985416 0.3050460077 0.4404943883 0.0041794469 0.0115770000 40691669 955859216 1373700096 -0.4015715718 -0.1282669753 -0.0178288426 1400 1311867765.3289039135 0.3900662363 0.3051067364 0.4404943883 0.0041783842 0.0060700000 40694653 955859216 1373700096 -0.4025275409 -0.1287683845 -0.0183408111 1401 1311867765.3593490124 0.3914068341 0.3051683353 0.4404943883 0.0041771346 0.0049540000 40697469 955859216 1373700096 -0.4039044678 -0.1290952861 -0.0186288822 1402 1311867765.3951449394 0.3910076320 0.3052295616 0.4404943883 0.0041758235 0.0042600000 40700453 955859216 1373700096 -0.4038147926 -0.1287726164 -0.0191417728 1403 1311867765.4278709888 0.3902299106 0.3052901464 0.4404943883 0.0041759292 0.0041080000 40703269 955859216 1373700096 -0.4030378163 -0.1293407828 -0.0197473485 1404 1311867765.4589679241 0.3911701143 0.3053513144 0.4404943883 0.0041753820 0.0041510000 40706141 955859216 1373700096 -0.4042088985 -0.1284176409 -0.0196708906 1405 1311867765.4974000454 0.3899163306 0.3054115030 0.4404943883 0.0041744308 0.0042290000 40709181 955859216 1373700096 -0.4031558931 -0.1285042912 -0.0200978704 1406 1311867765.5298929214 0.3904943466 0.3054720172 0.4404943883 0.0041729723 0.0041560000 40712109 955859216 1373700096 -0.4037582278 -0.1291211993 -0.0202446952 1407 1311867765.5625720024 0.3893552721 0.3055316357 0.4404943883 0.0041715358 0.0042080000 40714981 955859216 1373700096 -0.4029086530 -0.1278064102 -0.0204601213 1408 1311867765.5947990417 0.3898859024 0.3055915464 0.4404943883 0.0041720708 0.0043280000 40717853 955859216 1373700096 -0.4038332105 -0.1270556450 -0.0203915462 1409 1311867765.6310911179 0.3898811638 0.3056513687 0.4404943883 0.0041712340 0.0042390000 40720781 955859216 1373700096 -0.4040592909 -0.1266892850 -0.0206381641 1410 1311867765.6618249416 0.3899918199 0.3057111846 0.4404943883 0.0041697909 0.0131670000 40723653 955859216 1373700096 -0.4044396281 -0.1256076396 -0.0205772389 1411 1311867765.6966838837 0.3897112906 0.3057707169 0.4404943883 0.0041690171 0.0073090000 40726581 955859216 1373700096 -0.4041970372 -0.1262492687 -0.0209169611 1412 1311867765.7292089462 0.3908356726 0.3058309612 0.4404943883 0.0041678030 0.0051810000 40729565 955859216 1373700096 -0.4056023955 -0.1263201684 -0.0209880900 1413 1311867765.7602009773 0.3907685578 0.3058910728 0.4404943883 0.0041664834 0.0045540000 40732381 955859216 1373700096 -0.4058421254 -0.1255907118 -0.0209308546 1414 1311867765.7960450649 0.3912231028 0.3059514207 0.4404943883 0.0041650146 0.0078120000 40735365 955859216 1373700096 -0.4065837264 -0.1255742460 -0.0210542213 1415 1311867765.8298408985 0.3863703310 0.3060082539 0.4404943883 0.0041643996 0.0053960000 40738237 955859216 1373700096 -0.4018185735 -0.1249518096 -0.0219987947 1416 1311867765.8610999584 0.3852125108 0.3060641891 0.4404943883 0.0041630068 0.0043900000 40741109 955859216 1373700096 -0.4006652534 -0.1242274418 -0.0221068412 1417 1311867765.8960449696 0.3843633533 0.3061194461 0.4404943883 0.0041623380 0.0089940000 40744037 955859216 1373700096 -0.4000411630 -0.1235405207 -0.0218461193 1418 1311867765.9303019047 0.3844132125 0.3061746603 0.4404943883 0.0041609749 0.0056880000 40747021 955859216 1373700096 -0.3999957442 -0.1233008727 -0.0214519873 1419 1311867765.9612519741 0.3840003610 0.3062295058 0.4404943883 0.0041596072 0.0045670000 40749781 955859216 1373700096 -0.3994674683 -0.1229178607 -0.0211486872 1420 1311867765.9962689877 0.3832043707 0.3062837134 0.4404943883 0.0041582266 0.0112900000 40752709 955859216 1373700096 -0.3984064758 -0.1231447980 -0.0209632423 1421 1311867766.0289440155 0.3840309381 0.3063384265 0.4404943883 0.0041568653 0.0059910000 40755693 955859216 1373700096 -0.3990391791 -0.1232196093 -0.0207818914 1422 1311867766.0606811047 0.3844396174 0.3063933499 0.4404943883 0.0041556917 0.0048160000 40758565 955859216 1373700096 -0.3992007673 -0.1234433278 -0.0204297099 1423 1311867766.0968139172 0.3824832737 0.3064468214 0.4404943883 0.0041547467 0.0042360000 40761549 955859216 1373700096 -0.3969936967 -0.1224728003 -0.0203197915 1424 1311867766.1277561188 0.3815472424 0.3064995605 0.4404943883 0.0041533256 0.0112730000 40764309 955859216 1373700096 -0.3957308531 -0.1229302585 -0.0201729555 1425 1311867766.1625239849 0.3807963729 0.3065516986 0.4404943883 0.0041529416 0.0059680000 40767293 955859216 1373700096 -0.3948483169 -0.1222165376 -0.0198918153 1426 1311867766.1968889236 0.3792557716 0.3066026832 0.4404943883 0.0041515755 0.0048050000 40770221 955859216 1373700096 -0.3932295442 -0.1215019077 -0.0195102450 1427 1311867766.2298009396 0.3786291182 0.3066531572 0.4404943883 0.0041505216 0.0042360000 40773149 955859216 1373700096 -0.3925733268 -0.1211022660 -0.0190181285 1428 1311867766.2654640675 0.3770966530 0.3067024874 0.4404943883 0.0041493037 0.0116350000 40776077 955859216 1373700096 -0.3912509382 -0.1200006083 -0.0185707137 1429 1311867766.2981679440 0.3755573928 0.3067506714 0.4404943883 0.0041491800 0.0060610000 40778949 955859216 1373700096 -0.3896796107 -0.1191981733 -0.0178132970 1430 1311867766.3291699886 0.3745716512 0.3067980987 0.4404943883 0.0041700724 0.0048930000 40781821 955859216 1373700096 -0.3886691928 -0.1189810038 -0.0169158708 1431 1311867766.3653209209 0.3734586835 0.3068446819 0.4404943883 0.0041876160 0.0073350000 40784749 955859216 1373700096 -0.3872679472 -0.1187483072 -0.0162789393 1432 1311867766.3979220390 0.3739177287 0.3068915206 0.4404943883 0.0041928317 0.0053390000 40787677 955859216 1373700096 -0.3873421550 -0.1184473932 -0.0154722203 1433 1311867766.4302849770 0.3738178909 0.3069382243 0.4404943883 0.0041951741 0.0045790000 40790605 955859216 1373700096 -0.3869220018 -0.1189224049 -0.0151335374 1434 1311867766.4642350674 0.3733054399 0.3069845055 0.4404943883 0.0042001503 0.0107970000 40793477 955859216 1373700096 -0.3859846294 -0.1197316423 -0.0148472684 1435 1311867766.4967210293 0.3732711971 0.3070306983 0.4404943883 0.0041988637 0.0059450000 40796349 955859216 1373700096 -0.3855840564 -0.1195994169 -0.0144987376 1436 1311867766.5302040577 0.3734137118 0.3070769260 0.4404943883 0.0041974343 0.0074060000 40799165 955859216 1373700096 -0.3852518797 -0.1202210933 -0.0142834010 1437 1311867766.5639820099 0.3743757904 0.3071237589 0.4404943883 0.0041962187 0.0078610000 40802093 955859216 1373700096 -0.3855827451 -0.1219192296 -0.0143641531 1438 1311867766.5953519344 0.3737983704 0.3071701251 0.4404943883 0.0041950010 0.0081390000 40804965 955859216 1373700096 -0.3845114708 -0.1222764850 -0.0146264182 1439 1311867766.6287128925 0.3742930889 0.3072167707 0.4404943883 0.0041936007 0.0054080000 40807893 955859216 1373700096 -0.3845350742 -0.1221742854 -0.0149915675 1440 1311867766.6636400223 0.3743254244 0.3072633739 0.4404943883 0.0041929979 0.0045880000 40810821 955859216 1373700096 -0.3838524818 -0.1234403029 -0.0156368315 1441 1311867766.6964800358 0.3756371439 0.3073108227 0.4404943883 0.0042068331 0.0084580000 40813637 955859216 1373700096 -0.3843636513 -0.1238762811 -0.0161918439 1442 1311867766.7300829887 0.3761924505 0.3073585908 0.4404943883 0.0042164541 0.0055860000 40816621 955859216 1373700096 -0.3844465315 -0.1243696958 -0.0168834087 1443 1311867766.7628269196 0.3758841157 0.3074060791 0.4404943883 0.0042155586 0.0077200000 40819493 955859216 1373700096 -0.3838034570 -0.1241549626 -0.0177694000 1444 1311867766.7970418930 0.3782659769 0.3074551510 0.4404943883 0.0042147600 0.0059570000 40822365 955859216 1373700096 -0.3853863180 -0.1259130985 -0.0186421052 1445 1311867766.8299551010 0.3777395487 0.3075037908 0.4404943883 0.0042136007 0.0044170000 40825237 955859216 1373700096 -0.3845004439 -0.1255803257 -0.0198341347 1446 1311867766.8662180901 0.3791040480 0.3075533068 0.4404943883 0.0042122526 0.0108790000 40828277 955859216 1373700096 -0.3853682280 -0.1253632754 -0.0205558240 1447 1311867766.8958721161 0.3789231777 0.3076026295 0.4404943883 0.0042111116 0.0059540000 40830981 955859216 1373700096 -0.3844711483 -0.1269038171 -0.0218505859 1448 1311867766.9286260605 0.3790793717 0.3076519919 0.4404943883 0.0042196766 0.0049460000 40833909 955859216 1373700096 -0.3843405843 -0.1276357621 -0.0227600262 1449 1311867766.9661469460 0.3776836693 0.3077003229 0.4404943883 0.0042387330 0.0043540000 40836949 955859216 1373700096 -0.3824359477 -0.1260863990 -0.0235575717 1450 1311867766.9956479073 0.3771346509 0.3077482087 0.4404943883 0.0042390429 0.0125160000 40839709 955859216 1373700096 -0.3817666769 -0.1258278936 -0.0238792226 1451 1311867767.0294270515 0.3777779639 0.3077964718 0.4404943883 0.0042391725 0.0064380000 40842693 955859216 1373700096 -0.3821786046 -0.1265430599 -0.0240789093 1452 1311867767.0660951138 0.3788130283 0.3078453812 0.4404943883 0.0042383943 0.0051330000 40845621 955859216 1373700096 -0.3829665482 -0.1268987060 -0.0238782167 1453 1311867767.0968320370 0.3777275681 0.3078934763 0.4404943883 0.0042372232 0.0043500000 40848493 955859216 1373700096 -0.3820377886 -0.1256712824 -0.0239603836 1454 1311867767.1276900768 0.3786566556 0.3079421443 0.4404943883 0.0042387696 0.0085750000 40851309 955859216 1373700096 -0.3830627501 -0.1260422617 -0.0236330703 1455 1311867767.1632909775 0.3789366484 0.3079909378 0.4404943883 0.0042373987 0.0072920000 40854293 955859216 1373700096 -0.3833231032 -0.1268629432 -0.0236294493 1456 1311867767.1955349445 0.3783724010 0.3080392767 0.4404943883 0.0042361736 0.0053110000 40857165 955859216 1373700096 -0.3830510676 -0.1265061945 -0.0237180460 1457 1311867767.2308650017 0.3771433830 0.3080867057 0.4404943883 0.0042352176 0.0043500000 40860205 955859216 1373700096 -0.3816711605 -0.1269283146 -0.0239954460 1458 1311867767.2658200264 0.3770340681 0.3081339947 0.4404943883 0.0042339095 0.0125470000 40863133 955859216 1373700096 -0.3817582130 -0.1268656552 -0.0238514282 1459 1311867767.2981290817 0.3774588406 0.3081815100 0.4404943883 0.0042330430 0.0073400000 40866005 955859216 1373700096 -0.3824781775 -0.1267967373 -0.0237681661 1460 1311867767.3362140656 0.3764917552 0.3082282979 0.4404943883 0.0042352948 0.0053650000 40869045 955859216 1373700096 -0.3817692995 -0.1261299402 -0.0238368865 1461 1311867767.3633511066 0.3770101368 0.3082753765 0.4404943883 0.0042339937 0.0045580000 40871805 955859216 1373700096 -0.3823120594 -0.1265662611 -0.0237581730 1462 1311867767.3987689018 0.3753485978 0.3083212542 0.4404943883 0.0042336679 0.0043740000 40874789 955859216 1373700096 -0.3815437257 -0.1264675707 -0.0239999555 1463 1311867767.4331369400 0.3754100204 0.3083671112 0.4404943883 0.0042323131 0.0114200000 40877717 955859216 1373700096 -0.3816811144 -0.1257564574 -0.0238014366 1464 1311867767.4638109207 0.3757309616 0.3084131247 0.4404943883 0.0042313167 0.0062630000 40880533 955859216 1373700096 -0.3821974099 -0.1256577671 -0.0236944631 1465 1311867767.4974899292 0.3757410645 0.3084590824 0.4404943883 0.0042299094 0.0049840000 40883461 955859216 1373700096 -0.3824327588 -0.1259845197 -0.0237480830 1466 1311867767.5351889133 0.3748487830 0.3085043686 0.4404943883 0.0042337724 0.0043580000 40886501 955859216 1373700096 -0.3817036152 -0.1250234991 -0.0237254892 1467 1311867767.5664100647 0.3747062385 0.3085494960 0.4404943883 0.0042378955 0.0114170000 40889373 955859216 1373700096 -0.3818915188 -0.1246118546 -0.0235620048 1468 1311867767.5953979492 0.3745670319 0.3085944671 0.4404943883 0.0042365998 0.0063610000 40892133 955859216 1373700096 -0.3820492923 -0.1247067302 -0.0233891364 1469 1311867767.6338059902 0.3741168380 0.3086390705 0.4404943883 0.0042353972 0.0049320000 40895173 955859216 1373700096 -0.3820891678 -0.1243831143 -0.0233293474 1470 1311867767.6632149220 0.3740620613 0.3086835759 0.4404943883 0.0042341195 0.0044230000 40897989 955859216 1373700096 -0.3822477460 -0.1242092475 -0.0231632497 1471 1311867767.6991050243 0.3750640750 0.3087287020 0.4404943883 0.0042333725 0.0101800000 40900973 955859216 1373700096 -0.3834263682 -0.1245732158 -0.0232093558 1472 1311867767.7346129417 0.3752051890 0.3087738627 0.4404943883 0.0042320269 0.0058700000 40903901 955859216 1373700096 -0.3838537931 -0.1247782111 -0.0233487878 1473 1311867767.7651679516 0.3752978444 0.3088190249 0.4404943883 0.0042306245 0.0056170000 40906773 955859216 1373700096 -0.3841854334 -0.1248186752 -0.0237191152 1474 1311867767.7999849319 0.3754920959 0.3088642577 0.4404943883 0.0042292198 0.0079090000 40909701 955859216 1373700096 -0.3844266832 -0.1251353323 -0.0238307100 1475 1311867767.8344929218 0.3752540946 0.3089092677 0.4404943883 0.0042281266 0.0056000000 40912573 955859216 1373700096 -0.3842623532 -0.1258075237 -0.0241512302 1476 1311867767.8673300743 0.3748201430 0.3089539228 0.4404943883 0.0042267497 0.0048890000 40915445 955859216 1373700096 -0.3838738203 -0.1260370910 -0.0244587120 1477 1311867767.8966870308 0.3741969466 0.3089980955 0.4404943883 0.0042254331 0.0045750000 40918205 955859216 1373700096 -0.3833735883 -0.1252533942 -0.0245650597 1478 1311867767.9358460903 0.3741725981 0.3090421919 0.4404943883 0.0042242417 0.0119020000 40921301 955859216 1373700096 -0.3835658431 -0.1244187951 -0.0242876373 1479 1311867767.9646739960 0.3741820455 0.3090862351 0.4404943883 0.0042231579 0.0062220000 40924117 955859216 1373700096 -0.3836629391 -0.1242760792 -0.0242478326 1480 1311867767.9988079071 0.3745933771 0.3091304966 0.4404943883 0.0042218488 0.0049940000 40927045 955859216 1373700096 -0.3842472136 -0.1243430153 -0.0245626327 1481 1311867768.0346310139 0.3738936186 0.3091742260 0.4404943883 0.0042205450 0.0044500000 40930029 955859216 1373700096 -0.3836659789 -0.1238950565 -0.0247099064 1482 1311867768.0639820099 0.3731658161 0.3092174052 0.4404943883 0.0042200344 0.0119340000 40932789 955859216 1373700096 -0.3830615282 -0.1237279773 -0.0251274202 1483 1311867768.0985600948 0.3731341660 0.3092605048 0.4404943883 0.0042186577 0.0084210000 40935773 955859216 1373700096 -0.3833900094 -0.1236277744 -0.0257636290 1484 1311867768.1352849007 0.3731757998 0.3093035744 0.4404943883 0.0042174694 0.0056090000 40938757 955859216 1373700096 -0.3837777972 -0.1235150248 -0.0261013880 1485 1311867768.1651999950 0.3733208776 0.3093466837 0.4404943883 0.0042162445 0.0081730000 40941573 955859216 1373700096 -0.3842691481 -0.1228845119 -0.0263515823 1486 1311867768.1962070465 0.3729230762 0.3093894673 0.4404943883 0.0042150376 0.0084460000 40944389 955859216 1373700096 -0.3842411041 -0.1220786646 -0.0268627107 1487 1311867768.2323460579 0.3721068799 0.3094316444 0.4404943883 0.0042142272 0.0084540000 40947373 955859216 1373700096 -0.3836686909 -0.1218294650 -0.0272674579 1488 1311867768.2749121189 0.3718681633 0.3094736044 0.4404943883 0.0042133323 0.0057170000 40950581 955859216 1373700096 -0.3838444054 -0.1211345196 -0.0274674036 1489 1311867768.2962079048 0.3710109591 0.3095149324 0.4404943883 0.0042119836 0.0048540000 40953117 955859216 1373700096 -0.3831865788 -0.1197686791 -0.0275197569 1490 1311867768.3351829052 0.3691555262 0.3095549597 0.4404943883 0.0042154360 0.0044800000 40956213 955859216 1373700096 -0.3815048337 -0.1196531802 -0.0277947430 1491 1311867768.3693380356 0.3674893379 0.3095938157 0.4404943883 0.0042146681 0.0044430000 40959029 955859216 1373700096 -0.3800054491 -0.1197278202 -0.0283590816 1492 1311867768.4011199474 0.3670605719 0.3096323323 0.4404943883 0.0042149660 0.0044470000 40961845 955859216 1373700096 -0.3797077239 -0.1190707684 -0.0284247641 1493 1311867768.4324789047 0.3661405146 0.3096701811 0.4404943883 0.0042135771 0.0134970000 40964605 955859216 1373700096 -0.3790435493 -0.1179406717 -0.0284586661 1494 1311867768.4655070305 0.3662276864 0.3097080375 0.4404943883 0.0042128147 0.0078030000 40967477 955859216 1373700096 -0.3792314827 -0.1184495091 -0.0285067745 1495 1311867768.4980540276 0.3660965860 0.3097457556 0.4404943883 0.0042117790 0.0055590000 40970405 955859216 1373700096 -0.3792011142 -0.1183522642 -0.0285479762 1496 1311867768.5367710590 0.3646592498 0.3097824625 0.4404943883 0.0042116032 0.0077370000 40973389 955859216 1373700096 -0.3776994050 -0.1166481674 -0.0283921286 1497 1311867768.5648899078 0.3636625111 0.3098184545 0.4404943883 0.0042122149 0.0055390000 40976205 955859216 1373700096 -0.3767561615 -0.1163497716 -0.0282617044 1498 1311867768.5998411179 0.3634464145 0.3098542542 0.4404943883 0.0042108333 0.0077340000 40979133 955859216 1373700096 -0.3765414655 -0.1168614849 -0.0280842558 1499 1311867768.6319470406 0.3634363711 0.3098899994 0.4404943883 0.0042095451 0.0055320000 40982005 955859216 1373700096 -0.3764896393 -0.1169072837 -0.0278045386 1500 1311867768.6643230915 0.3621743619 0.3099248557 0.4404943883 0.0042087016 0.0047850000 40984933 955859216 1373700096 -0.3754210174 -0.1157612652 -0.0276208930 1501 1311867768.7014238834 0.3622209728 0.3099596965 0.4404943883 0.0042075365 0.0045340000 40987861 955859216 1373700096 -0.3755656481 -0.1149375737 -0.0271763764 1502 1311867768.7344141006 0.3625511229 0.3099947108 0.4404943883 0.0042062632 0.0099110000 40990845 955859216 1373700096 -0.3760462403 -0.1152736694 -0.0268849488 1503 1311867768.7646389008 0.3622206450 0.3100294586 0.4404943883 0.0042053684 0.0059740000 40993661 955859216 1373700096 -0.3756695688 -0.1153625473 -0.0265591778 1504 1311867768.8039369583 0.3616394401 0.3100637737 0.4404943883 0.0042041783 0.0049700000 40996701 955859216 1373700096 -0.3749921918 -0.1150128171 -0.0261929147 1505 1311867768.8365039825 0.3620698750 0.3100983293 0.4404943883 0.0042029257 0.0078340000 40999629 955859216 1373700096 -0.3752623200 -0.1151597723 -0.0257815700 1506 1311867768.8651020527 0.3621251285 0.3101328756 0.4404943883 0.0042021599 0.0056540000 41002389 955859216 1373700096 -0.3751733005 -0.1158699244 -0.0254485868 1507 1311867768.9001519680 0.3615059853 0.3101669653 0.4404943883 0.0042008911 0.0046530000 41005373 955859216 1373700096 -0.3744878173 -0.1155179068 -0.0252661109 1508 1311867768.9330470562 0.3618462980 0.3102012354 0.4404943883 0.0041999681 0.0117850000 41008189 955859216 1373700096 -0.3743910789 -0.1159219742 -0.0247342791 1509 1311867768.9639101028 0.3611542284 0.3102350015 0.4404943883 0.0041988620 0.0062100000 41011005 955859216 1373700096 -0.3736137152 -0.1162275150 -0.0245021991 1510 1311867768.9992640018 0.3614548445 0.3102689219 0.4404943883 0.0041988281 0.0050200000 41013989 955859216 1373700096 -0.3737964928 -0.1161953285 -0.0241998471 1511 1311867769.0331530571 0.3610979617 0.3103025612 0.4404943883 0.0041980358 0.0046450000 41016805 955859216 1373700096 -0.3733985126 -0.1153951436 -0.0238737576 1512 1311867769.0641028881 0.3606143594 0.3103358362 0.4404943883 0.0041969077 0.0086340000 41019677 955859216 1373700096 -0.3729680181 -0.1149519384 -0.0237358566 1513 1311867769.0999929905 0.3609632552 0.3103692978 0.4404943883 0.0041956191 0.0057850000 41022661 955859216 1373700096 -0.3733385801 -0.1154855788 -0.0235889349 1514 1311867769.1327989101 0.3607214987 0.3104025556 0.4404943883 0.0041942444 0.0047930000 41025477 955859216 1373700096 -0.3731856644 -0.1154502481 -0.0235361513 1515 1311867769.1643240452 0.3599065244 0.3104352314 0.4404943883 0.0041996846 0.0120220000 41028349 955859216 1373700096 -0.3725697994 -0.1152839065 -0.0233931616 1516 1311867769.2002429962 0.3598585725 0.3104678326 0.4404943883 0.0041995772 0.0063850000 41031277 955859216 1373700096 -0.3724039793 -0.1150466800 -0.0233257841 1517 1311867769.2324860096 0.3590910733 0.3104998848 0.4404943883 0.0042016493 0.0051330000 41034149 955859216 1373700096 -0.3717566133 -0.1140742525 -0.0232539196 1518 1311867769.2636189461 0.3590345979 0.3105318576 0.4404943883 0.0042016714 0.0078470000 41037021 955859216 1373700096 -0.3714283705 -0.1145789251 -0.0231192466 1519 1311867769.3002018929 0.3589641750 0.3105637420 0.4404943883 0.0042073980 0.0055760000 41039949 955859216 1373700096 -0.3713075817 -0.1145066023 -0.0230464507 1520 1311867769.3330841064 0.3578239083 0.3105948342 0.4404943883 0.0042067344 0.0047390000 41042821 955859216 1373700096 -0.3701429963 -0.1137277260 -0.0230974574 1521 1311867769.3653230667 0.3566027880 0.3106250827 0.4404943883 0.0042053661 0.0083250000 41045805 955859216 1373700096 -0.3690944910 -0.1123428121 -0.0229618922 1522 1311867769.3995320797 0.3561862707 0.3106550178 0.4404943883 0.0042041191 0.0057250000 41048733 955859216 1373700096 -0.3688468933 -0.1114431024 -0.0228021797 1523 1311867769.4340240955 0.3559418321 0.3106847530 0.4404943883 0.0042031535 0.0047820000 41051605 955859216 1373700096 -0.3686949015 -0.1111630872 -0.0228348840 1524 1311867769.4644269943 0.3552509248 0.3107139959 0.4404943883 0.0042118992 0.0101520000 41054477 955859216 1373700096 -0.3680212498 -0.1110665128 -0.0228105634 1525 1311867769.4999239445 0.3547538221 0.3107428745 0.4404943883 0.0042139815 0.0060670000 41057461 955859216 1373700096 -0.3674954772 -0.1106739193 -0.0230521765 1526 1311867769.5317490101 0.3559792042 0.3107725182 0.4404943883 0.0042126787 0.0051220000 41060277 955859216 1373700096 -0.3685518503 -0.1110994294 -0.0229132846 1527 1311867769.5660109520 0.3559764028 0.3108021213 0.4404943883 0.0042113600 0.0079980000 41063093 955859216 1373700096 -0.3686795831 -0.1115050986 -0.0228285789 1528 1311867769.6002509594 0.3554936945 0.3108313697 0.4404943883 0.0042100576 0.0056680000 41066021 955859216 1373700096 -0.3682800531 -0.1110773236 -0.0229488127 1529 1311867769.6330249310 0.3558906019 0.3108608394 0.4404943883 0.0042128478 0.0048610000 41068949 955859216 1373700096 -0.3684519827 -0.1115688235 -0.0227537714 1530 1311867769.6637229919 0.3555351198 0.3108900383 0.4404943883 0.0042118024 0.0119590000 41071765 955859216 1373700096 -0.3682233989 -0.1114774942 -0.0224643853 1531 1311867769.7014029026 0.3546619117 0.3109186287 0.4404943883 0.0042158329 0.0063390000 41074861 955859216 1373700096 -0.3674350083 -0.1106875315 -0.0221052263 1532 1311867769.7340829372 0.3548852205 0.3109473275 0.4404943883 0.0042146603 0.0056990000 41077677 955859216 1373700096 -0.3675871789 -0.1097407117 -0.0214800201 1533 1311867769.7641069889 0.3550394773 0.3109760895 0.4404943883 0.0042224480 0.0048560000 41080549 955859216 1373700096 -0.3676882684 -0.1091481745 -0.0207982473 1534 1311867769.8003458977 0.3544625640 0.3110044379 0.4404943883 0.0042474466 0.0086800000 41083477 955859216 1373700096 -0.3673892021 -0.1094289795 -0.0203913953 1535 1311867769.8341090679 0.3537268937 0.3110322702 0.4404943883 0.0042467187 0.0058790000 41086405 955859216 1373700096 -0.3665264249 -0.1097197384 -0.0202278793 1536 1311867769.8692820072 0.3534083366 0.3110598587 0.4404943883 0.0042457561 0.0049000000 41089389 955859216 1373700096 -0.3659841716 -0.1099001244 -0.0199301802 1537 1311867769.9001140594 0.3528066278 0.3110870200 0.4404943883 0.0042450486 0.0119740000 41092261 955859216 1373700096 -0.3653423786 -0.1089297310 -0.0195105281 1538 1311867769.9321451187 0.3522100747 0.3111137580 0.4404943883 0.0042440098 0.0064920000 41095077 955859216 1373700096 -0.3647967279 -0.1076622307 -0.0193679370 1539 1311867769.9684319496 0.3523500264 0.3111405522 0.4404943883 0.0042428721 0.0052250000 41098061 955859216 1373700096 -0.3649730384 -0.1076546013 -0.0192165356 1540 1311867770.0010259151 0.3519303501 0.3111670390 0.4404943883 0.0042417572 0.0047960000 41101045 955859216 1373700096 -0.3644056022 -0.1073387936 -0.0188693721 1541 1311867770.0330319405 0.3516995907 0.3111933418 0.4404943883 0.0042405345 0.0047020000 41103861 955859216 1373700096 -0.3641512692 -0.1069718078 -0.0186316743 1542 1311867770.0690810680 0.3507032096 0.3112189643 0.4404943883 0.0042413175 0.0130450000 41106845 955859216 1373700096 -0.3632450998 -0.1072403565 -0.0186058823 1543 1311867770.1002650261 0.3509093225 0.3112446871 0.4404943883 0.0042424214 0.0067140000 41109717 955859216 1373700096 -0.3633974493 -0.1076096222 -0.0181508269 1544 1311867770.1335709095 0.3502221107 0.3112699316 0.4404943883 0.0042413927 0.0055290000 41112589 955859216 1373700096 -0.3626889586 -0.1073241010 -0.0179765318 1545 1311867770.1684958935 0.3499242663 0.3112949506 0.4404943883 0.0042401584 0.0047790000 41115573 955859216 1373700096 -0.3625092506 -0.1071212515 -0.0179179776 1546 1311867770.2001299858 0.3500130177 0.3113199946 0.4404943883 0.0042388534 0.0048260000 41118445 955859216 1373700096 -0.3627785742 -0.1070508659 -0.0175978821 1547 1311867770.2336180210 0.3495807946 0.3113447268 0.4404943883 0.0042384424 0.0107030000 41121317 955859216 1373700096 -0.3627827764 -0.1073186845 -0.0173701290 1548 1311867770.2679719925 0.3499280512 0.3113696515 0.4404943883 0.0042393764 0.0080240000 41124245 955859216 1373700096 -0.3629564345 -0.1077897623 -0.0172486957 1549 1311867770.3009040356 0.3492296040 0.3113940930 0.4404943883 0.0042391240 0.0057280000 41127117 955859216 1373700096 -0.3623822331 -0.1078085825 -0.0171320159 1550 1311867770.3339090347 0.3497845232 0.3114188610 0.4404943883 0.0042401238 0.0049010000 41130045 955859216 1373700096 -0.3630919158 -0.1082815528 -0.0169866513 1551 1311867770.3681850433 0.3486613333 0.3114428729 0.4404943883 0.0042579909 0.0048020000 41132973 955859216 1373700096 -0.3623213470 -0.1079182178 -0.0172691252 1552 1311867770.4014930725 0.3481310010 0.3114665122 0.4404943883 0.0042633490 0.0048280000 41135845 955859216 1373700096 -0.3619293869 -0.1074071974 -0.0172665734 1553 1311867770.4333899021 0.3482114971 0.3114901729 0.4404943883 0.0042640551 0.0048550000 41138773 955859216 1373700096 -0.3622314036 -0.1072507575 -0.0169023313 1554 1311867770.4684588909 0.3481710851 0.3115137770 0.4404943883 0.0042627609 0.0136000000 41141701 955859216 1373700096 -0.3621691167 -0.1078088060 -0.0167945698 1555 1311867770.5046019554 0.3473213613 0.3115368044 0.4404943883 0.0042615363 0.0068190000 41144685 955859216 1373700096 -0.3615211844 -0.1077646241 -0.0169297475 1556 1311867770.5338129997 0.3475169539 0.3115599279 0.4404943883 0.0042602598 0.0084360000 41147445 955859216 1373700096 -0.3617579043 -0.1074706241 -0.0166141093 1557 1311867770.5683600903 0.3474620283 0.3115829864 0.4404943883 0.0042665003 0.0058910000 41150373 955859216 1373700096 -0.3617390096 -0.1074064597 -0.0163632352 1558 1311867770.6027359962 0.3474552333 0.3116060110 0.4404943883 0.0042682079 0.0080430000 41153301 955859216 1373700096 -0.3616656065 -0.1065252125 -0.0160180572 1559 1311867770.6331069469 0.3463695645 0.3116283096 0.4404943883 0.0042675392 0.0057480000 41156117 955859216 1373700096 -0.3605431318 -0.1066712216 -0.0158733092 1560 1311867770.6699299812 0.3466232121 0.3116507422 0.4404943883 0.0042662156 0.0049690000 41159157 955859216 1373700096 -0.3603667915 -0.1070478931 -0.0156488493 1561 1311867770.7014191151 0.3470896184 0.3116734449 0.4404943883 0.0042649332 0.0047690000 41162029 955859216 1373700096 -0.3605136573 -0.1074838936 -0.0152943200 1562 1311867770.7347331047 0.3468012214 0.3116959339 0.4404943883 0.0042638267 0.0090440000 41164957 955859216 1373700096 -0.3600989580 -0.1068642959 -0.0150283342 1563 1311867770.7684218884 0.3468430936 0.3117184209 0.4404943883 0.0042625518 0.0062800000 41167829 955859216 1373700096 -0.3600127697 -0.1069196984 -0.0147929620 1564 1311867770.8017508984 0.3472243845 0.3117411229 0.4404943883 0.0042612137 0.0050760000 41170701 955859216 1373700096 -0.3602670729 -0.1075984165 -0.0144862020 1565 1311867770.8396499157 0.3461236358 0.3117630925 0.4404943883 0.0042604739 0.0087370000 41173797 955859216 1373700096 -0.3590340018 -0.1068622842 -0.0142559921 1566 1311867770.8699400425 0.3456416726 0.3117847264 0.4404943883 0.0042598742 0.0059640000 41176613 955859216 1373700096 -0.3583646715 -0.1071190983 -0.0139627270 1567 1311867770.9027009010 0.3456324935 0.3118063267 0.4404943883 0.0042588490 0.0049280000 41179485 955859216 1373700096 -0.3582744002 -0.1073212773 -0.0138095524 1568 1311867770.9355690479 0.3450710773 0.3118275415 0.4404943883 0.0042585864 0.0105160000 41182413 955859216 1373700096 -0.3578266501 -0.1064001843 -0.0134803699 1569 1311867770.9692869186 0.3453041315 0.3118488778 0.4404943883 0.0042577565 0.0063570000 41185341 955859216 1373700096 -0.3579184115 -0.1063334420 -0.0132182892 1570 1311867771.0021619797 0.3454161584 0.3118702582 0.4404943883 0.0042591491 0.0052890000 41188213 955859216 1373700096 -0.3579642177 -0.1065205038 -0.0129936282 1571 1311867771.0365509987 0.3452883065 0.3118915300 0.4404943883 0.0042686080 0.0087990000 41191085 955859216 1373700096 -0.3581958115 -0.1054427698 -0.0126818568 1572 1311867771.0685739517 0.3451187909 0.3119126670 0.4404943883 0.0042675087 0.0060020000 41194013 955859216 1373700096 -0.3581424654 -0.1047201678 -0.0123786796 1573 1311867771.1014111042 0.3442860544 0.3119332476 0.4404943883 0.0042701491 0.0049530000 41196941 955859216 1373700096 -0.3571789861 -0.1049208716 -0.0121749779 1574 1311867771.1381099224 0.3436177969 0.3119533776 0.4404943883 0.0042689980 0.0049340000 41199925 955859216 1373700096 -0.3564178646 -0.1045541912 -0.0120105604 1575 1311867771.1686840057 0.3432031274 0.3119732187 0.4404943883 0.0042677465 0.0049260000 41202741 955859216 1373700096 -0.3559153080 -0.1043423191 -0.0117095644 1576 1311867771.2019159794 0.3432757556 0.3119930807 0.4404943883 0.0042665123 0.0149920000 41205613 955859216 1373700096 -0.3557461500 -0.1048963964 -0.0115424152 1577 1311867771.2363801003 0.3431043625 0.3120128089 0.4404943883 0.0042652329 0.0128810000 41208541 955859216 1373700096 -0.3553619385 -0.1046842858 -0.0113933366 1578 1311867771.2705540657 0.3430379331 0.3120324699 0.4404943883 0.0042640581 0.0068070000 41211525 955859216 1373700096 -0.3549488485 -0.1041996032 -0.0111561595 1579 1311867771.3016860485 0.3429597616 0.3120520565 0.4404943883 0.0042627718 0.0054270000 41214341 955859216 1373700096 -0.3546623886 -0.1040568128 -0.0108661857 1580 1311867771.3360719681 0.3432975411 0.3120718321 0.4404943883 0.0042614501 0.0050930000 41217269 955859216 1373700096 -0.3545755148 -0.1044192836 -0.0106932679 1581 1311867771.3679900169 0.3426380157 0.3120911656 0.4404943883 0.0042601147 0.0150790000 41220141 955859216 1373700096 -0.3537714481 -0.1038131416 -0.0106911734 1582 1311867771.4030399323 0.3411561549 0.3121095379 0.4404943883 0.0042588892 0.0113400000 41223069 955859216 1373700096 -0.3521045148 -0.1026986241 -0.0106900316 1583 1311867771.4361710548 0.3413520455 0.3121280107 0.4404943883 0.0042577667 0.0065000000 41225997 955859216 1373700096 -0.3519585729 -0.1031511426 -0.0105919186 1584 1311867771.4682569504 0.3414620161 0.3121465297 0.4404943883 0.0042564401 0.0054620000 41228869 955859216 1373700096 -0.3517573178 -0.1026521102 -0.0103111286 1585 1311867771.5008640289 0.3405949473 0.3121644782 0.4404943883 0.0042554876 0.0049990000 41231741 955859216 1373700096 -0.3505500853 -0.1017770767 -0.0100521026 1586 1311867771.5365910530 0.3392099142 0.3121815308 0.4404943883 0.0042543197 0.0091190000 41234725 955859216 1373700096 -0.3487277627 -0.1014701352 -0.0101162679 1587 1311867771.5686171055 0.3384252489 0.3121980675 0.4404943883 0.0042531554 0.0061100000 41237653 955859216 1373700096 -0.3476015329 -0.1017134190 -0.0101715513 1588 1311867771.6077210903 0.3383028209 0.3122145063 0.4404943883 0.0042531196 0.0051930000 41240693 955859216 1373700096 -0.3469973505 -0.1014158428 -0.0098125841 1589 1311867771.6366779804 0.3370535672 0.3122301382 0.4404943883 0.0042518822 0.0049940000 41243453 955859216 1373700096 -0.3455174863 -0.1012505218 -0.0097611276 1590 1311867771.6715440750 0.3365119994 0.3122454098 0.4404943883 0.0042510335 0.0050370000 41246437 955859216 1373700096 -0.3446595967 -0.1018084735 -0.0095095504 1591 1311867771.7024850845 0.3362146318 0.3122604753 0.4404943883 0.0042505614 0.0050120000 41249309 955859216 1373700096 -0.3440244496 -0.1012915671 -0.0089706033 1592 1311867771.7367300987 0.3354460001 0.3122750390 0.4404943883 0.0042498811 0.0094640000 41252181 955859216 1373700096 -0.3428547978 -0.1007873863 -0.0087605603 1593 1311867771.7697410583 0.3353545070 0.3122895271 0.4404943883 0.0042494045 0.0063720000 41255109 955859216 1373700096 -0.3422566056 -0.1013511196 -0.0085567506 1594 1311867771.8023030758 0.3351633549 0.3123038771 0.4404943883 0.0042481578 0.0052600000 41257981 955859216 1373700096 -0.3413956463 -0.1011449546 -0.0083249984 1595 1311867771.8386220932 0.3351472616 0.3123181989 0.4404943883 0.0042475675 0.0103860000 41261021 955859216 1373700096 -0.3409970701 -0.1009066403 -0.0081129279 1596 1311867771.8711829185 0.3352635503 0.3123325757 0.4404943883 0.0042463182 0.0081470000 41263837 955859216 1373700096 -0.3406390250 -0.1015145034 -0.0080241570 1597 1311867771.9016489983 0.3348098099 0.3123466504 0.4404943883 0.0042451143 0.0059300000 41266709 955859216 1373700096 -0.3396997452 -0.1021926180 -0.0082612792 1598 1311867771.9377520084 0.3350296915 0.3123608450 0.4404943883 0.0042443834 0.0053300000 41269693 955859216 1373700096 -0.3393699527 -0.1021995768 -0.0081945574 1599 1311867771.9696009159 0.3339641392 0.3123743555 0.4404943883 0.0042435508 0.0050110000 41272565 955859216 1373700096 -0.3378814459 -0.1021179557 -0.0085098157 1600 1311867772.0018649101 0.3339415491 0.3123878350 0.4404943883 0.0042425696 0.0091780000 41275493 955859216 1373700096 -0.3374860585 -0.1020451635 -0.0086994004 1601 1311867772.0375399590 0.3345807791 0.3124016969 0.4404943883 0.0042419870 0.0062790000 41278421 955859216 1373700096 -0.3378503025 -0.1016614810 -0.0084240232 1602 1311867772.0696671009 0.3347567022 0.3124156514 0.4404943883 0.0042406754 0.0052640000 41281349 955859216 1373700096 -0.3379027843 -0.1015657485 -0.0083866101 1603 1311867772.1012299061 0.3344273269 0.3124293829 0.4404943883 0.0042396817 0.0050750000 41284165 955859216 1373700096 -0.3374710977 -0.1014367044 -0.0085448073 1604 1311867772.1369819641 0.3345623612 0.3124431815 0.4404943883 0.0042384465 0.0050270000 41287037 955859216 1373700096 -0.3375246227 -0.1011617705 -0.0083387019 1605 1311867772.1690549850 0.3350934386 0.3124572938 0.4404943883 0.0042371666 0.0050390000 41289965 955859216 1373700096 -0.3379566967 -0.1009024978 -0.0079706209 1606 1311867772.2016880512 0.3347912431 0.3124712004 0.4404943883 0.0042359591 0.0050100000 41292893 955859216 1373700096 -0.3374538124 -0.1010448188 -0.0078359302 1607 1311867772.2370250225 0.3348981142 0.3124851562 0.4404943883 0.0042347984 0.0146110000 41295765 955859216 1373700096 -0.3374248147 -0.1014947295 -0.0078366855 1608 1311867772.2710011005 0.3347344697 0.3124989928 0.4404943883 0.0042337818 0.0078160000 41298749 955859216 1373700096 -0.3371861875 -0.1014349312 -0.0075410879 1609 1311867772.3046050072 0.3344607949 0.3125126422 0.4404943883 0.0042325249 0.0060990000 41301677 955859216 1373700096 -0.3369469941 -0.1011235267 -0.0075575239 1610 1311867772.3366808891 0.3344384432 0.3125262607 0.4404943883 0.0042313955 0.0051900000 41304493 955859216 1373700096 -0.3370156884 -0.1015914604 -0.0075927977 1611 1311867772.3689630032 0.3345688581 0.3125399432 0.4404943883 0.0042301420 0.0050320000 41307421 955859216 1373700096 -0.3373104036 -0.1017316803 -0.0075121890 1612 1311867772.4054839611 0.3348872066 0.3125538063 0.4404943883 0.0042291317 0.0080980000 41310461 955859216 1373700096 -0.3376901150 -0.1016921327 -0.0071435454 1613 1311867772.4385271072 0.3349233270 0.3125676746 0.4404943883 0.0042279252 0.0058850000 41313333 955859216 1373700096 -0.3380349874 -0.1017839387 -0.0070923832 1614 1311867772.4697830677 0.3352951705 0.3125817560 0.4404943883 0.0042266373 0.0053800000 41316149 955859216 1373700096 -0.3385151923 -0.1025559604 -0.0070424466 1615 1311867772.5049729347 0.3349745870 0.3125956216 0.4404943883 0.0042256564 0.0051600000 41319133 955859216 1373700096 -0.3385651708 -0.1024954766 -0.0069740280 1616 1311867772.5382430553 0.3340688944 0.3126089095 0.4404943883 0.0042247326 0.0051630000 41322005 955859216 1373700096 -0.3380514979 -0.1021839827 -0.0070789149 1617 1311867772.5713028908 0.3341454268 0.3126222283 0.4404943883 0.0042240660 0.0128120000 41324933 955859216 1373700096 -0.3383931816 -0.1019288599 -0.0070671979 1618 1311867772.6077790260 0.3340880573 0.3126354952 0.4404943883 0.0042237153 0.0068120000 41327861 955859216 1373700096 -0.3387691379 -0.1019261330 -0.0068516051 1619 1311867772.6382429600 0.3334312439 0.3126483400 0.4404943883 0.0042224556 0.0055850000 41330677 955859216 1373700096 -0.3383685052 -0.1018013582 -0.0067847064 1620 1311867772.6695280075 0.3327759206 0.3126607644 0.4404943883 0.0042221045 0.0051720000 41333549 955859216 1373700096 -0.3380182385 -0.1020950601 -0.0067748469 1621 1311867772.7066609859 0.3325134814 0.3126730116 0.4404943883 0.0042208739 0.0087310000 41336533 955859216 1373700096 -0.3378746808 -0.1021533832 -0.0066566365 1622 1311867772.7385280132 0.3323479891 0.3126851417 0.4404943883 0.0042196018 0.0061050000 41339405 955859216 1373700096 -0.3378106058 -0.1019117758 -0.0064050434 1623 1311867772.7712020874 0.3325890005 0.3126974053 0.4404943883 0.0042183917 0.0052290000 41342333 955859216 1373700096 -0.3380915821 -0.1025006026 -0.0061359885 1624 1311867772.8056819439 0.3327301145 0.3127097407 0.4404943883 0.0042175877 0.0051090000 41345317 955859216 1373700096 -0.3382624090 -0.1029383317 -0.0057383049 1625 1311867772.8384070396 0.3325129449 0.3127219273 0.4404943883 0.0042165048 0.0127550000 41348133 955859216 1373700096 -0.3380361497 -0.1025976837 -0.0052602133 1626 1311867772.8747529984 0.3318283558 0.3127336779 0.4404943883 0.0042153498 0.0068130000 41351173 955859216 1373700096 -0.3372612000 -0.1027551591 -0.0051478483 1627 1311867772.9054989815 0.3316022456 0.3127452751 0.4404943883 0.0042142713 0.0055790000 41353989 955859216 1373700096 -0.3368964195 -0.1032306999 -0.0050364030 1628 1311867772.9415910244 0.3315147758 0.3127568042 0.4404943883 0.0042140657 0.0051520000 41356917 955859216 1373700096 -0.3365214765 -0.1032217294 -0.0048363265 1629 1311867772.9716000557 0.3313525319 0.3127682197 0.4404943883 0.0042128056 0.0050340000 41359733 955859216 1373700096 -0.3360694349 -0.1032564119 -0.0045178984 1630 1311867773.0115981102 0.3312542439 0.3127795608 0.4404943883 0.0042117784 0.0111580000 41362773 955859216 1373700096 -0.3356672525 -0.1035891250 -0.0046208641 1631 1311867773.0406711102 0.3310684562 0.3127907741 0.4404943883 0.0042109070 0.0066280000 41365589 955859216 1373700096 -0.3353106081 -0.1032258198 -0.0043538995 1632 1311867773.0706710815 0.3309639096 0.3128019096 0.4404943883 0.0042096817 0.0054820000 41368349 955859216 1373700096 -0.3350674212 -0.1027846113 -0.0039924593 1633 1311867773.1044468880 0.3308862746 0.3128129839 0.4404943883 0.0042091916 0.0051770000 41371277 955859216 1373700096 -0.3346555531 -0.1036953703 -0.0038790624 1634 1311867773.1367809772 0.3309989870 0.3128241136 0.4404943883 0.0042082137 0.0051000000 41374149 955859216 1373700096 -0.3343222737 -0.1046266481 -0.0035900895 1635 1311867773.1702499390 0.3310097456 0.3128352364 0.4404943883 0.0042071853 0.0050830000 41377077 955859216 1373700096 -0.3340776563 -0.1046427488 -0.0032089232 1636 1311867773.2047750950 0.3306410611 0.3128461201 0.4404943883 0.0042059294 0.0141700000 41380005 955859216 1373700096 -0.3335971534 -0.1045144573 -0.0031271286 1637 1311867773.2366468906 0.3306939304 0.3128570229 0.4404943883 0.0042047988 0.0071240000 41382877 955859216 1373700096 -0.3333904147 -0.1044615135 -0.0026683651 1638 1311867773.2714850903 0.3296859264 0.3128672969 0.4404943883 0.0042042092 0.0063140000 41385861 955859216 1373700096 -0.3324003816 -0.1040720493 -0.0024123969 1639 1311867773.3104391098 0.3296747506 0.3128775516 0.4404943883 0.0042038655 0.0051310000 41388901 955859216 1373700096 -0.3320272863 -0.1041578948 -0.0019965023 1640 1311867773.3365778923 0.3318110108 0.3128890964 0.4404943883 0.0042028735 0.0051260000 41391549 955859216 1373700096 -0.3341152072 -0.1040819064 -0.0013847122 1641 1311867773.3720550537 0.3322902918 0.3129009192 0.4404943883 0.0042019129 0.0090410000 41394533 955859216 1373700096 -0.3343986273 -0.1046571359 -0.0011014619 1642 1311867773.4075679779 0.3322245479 0.3129126876 0.4404943883 0.0042014786 0.0062040000 41397461 955859216 1373700096 -0.3340550065 -0.1046111286 -0.0007143851 1643 1311867773.4431231022 0.3324006796 0.3129245488 0.4404943883 0.0042013749 0.0052420000 41400445 955859216 1373700096 -0.3340523541 -0.1045817360 -0.0002775739 1644 1311867773.4752271175 0.3325149715 0.3129364651 0.4404943883 0.0042007261 0.0087950000 41403317 955859216 1373700096 -0.3338340521 -0.1053328067 0.0000722450 1645 1311867773.5056390762 0.3321807384 0.3129481637 0.4404943883 0.0041997969 0.0061230000 41406133 955859216 1373700096 -0.3331443667 -0.1055536196 0.0003919140 1646 1311867773.5412580967 0.3318535686 0.3129596494 0.4404943883 0.0041987848 0.0054020000 41409117 955859216 1373700096 -0.3325813711 -0.1051673591 0.0008583884 1647 1311867773.5752460957 0.3316424191 0.3129709929 0.4404943883 0.0041979756 0.0051660000 41412045 955859216 1373700096 -0.3322027028 -0.1057094187 0.0011546212 1648 1311867773.6103789806 0.3315566182 0.3129822706 0.4404943883 0.0041969222 0.0128970000 41415029 955859216 1373700096 -0.3317388296 -0.1061229035 0.0013792947 1649 1311867773.6384060383 0.3309206367 0.3129931489 0.4404943883 0.0041974535 0.0064790000 41417733 955859216 1373700096 -0.3308711350 -0.1056330577 0.0017653096 1650 1311867773.6767098904 0.3305395544 0.3130037831 0.4404943883 0.0041986838 0.0052390000 41420773 955859216 1373700096 -0.3304263949 -0.1053968892 0.0018815090 1651 1311867773.7092239857 0.3311357200 0.3130147655 0.4404943883 0.0041975668 0.0051680000 41423645 955859216 1373700096 -0.3307830095 -0.1057857722 0.0020475760 1652 1311867773.7367770672 0.3309723139 0.3130256357 0.4404943883 0.0041966252 0.0052250000 41426349 955859216 1373700096 -0.3305636048 -0.1056935489 0.0024992432 1653 1311867773.7767388821 0.3300276101 0.3130359212 0.4404943883 0.0041961946 0.0051270000 41429445 955859216 1373700096 -0.3294729888 -0.1053915918 0.0027383387 1654 1311867773.8052179813 0.3294399381 0.3130458390 0.4404943883 0.0041961460 0.0153520000 41432205 955859216 1373700096 -0.3289742470 -0.1055880040 0.0027895933 1655 1311867773.8394160271 0.3293384612 0.3130556835 0.4404943883 0.0041952722 0.0084920000 41435133 955859216 1373700096 -0.3288736045 -0.1064041257 0.0030057142 1656 1311867773.8739800453 0.3290945590 0.3130653688 0.4404943883 0.0041942842 0.0085110000 41438061 955859216 1373700096 -0.3286573291 -0.1071457714 0.0032477994 1657 1311867773.9096889496 0.3282653987 0.3130745420 0.4404943883 0.0041935159 0.0085270000 41441045 955859216 1373700096 -0.3277481794 -0.1073649377 0.0034671926 1658 1311867773.9369859695 0.3280734420 0.3130835884 0.4404943883 0.0041926786 0.0085180000 41443749 955859216 1373700096 -0.3275376856 -0.1075099409 0.0035532515 1659 1311867773.9740200043 0.3279637992 0.3130925578 0.4404943883 0.0041915818 0.0061710000 41446789 955859216 1373700096 -0.3273202479 -0.1076815277 0.0039127860 1660 1311867774.0073120594 0.3280867040 0.3131015904 0.4404943883 0.0041917004 0.0053350000 41449661 955859216 1373700096 -0.3270539045 -0.1079972014 0.0040494814 1661 1311867774.0389740467 0.3282236159 0.3131106946 0.4404943883 0.0041934597 0.0051280000 41452589 955859216 1373700096 -0.3272413909 -0.1085589230 0.0043122005 1662 1311867774.0735630989 0.3285427690 0.3131199798 0.4404943883 0.0041944852 0.0092710000 41455517 955859216 1373700096 -0.3270025253 -0.1084429100 0.0044982135 1663 1311867774.1093399525 0.3286473453 0.3131293168 0.4404943883 0.0041978339 0.0062420000 41458501 955859216 1373700096 -0.3271174431 -0.1080713123 0.0047267121 1664 1311867774.1424911022 0.3293566406 0.3131390688 0.4404943883 0.0041990268 0.0052970000 41461429 955859216 1373700096 -0.3275554776 -0.1088307276 0.0049076038 1665 1311867774.1754300594 0.3291313350 0.3131486738 0.4404943883 0.0041995541 0.0051590000 41464301 955859216 1373700096 -0.3271857202 -0.1090922952 0.0053320779 1666 1311867774.2059481144 0.3288607001 0.3131581047 0.4404943883 0.0041983621 0.0083200000 41467173 955859216 1373700096 -0.3266165555 -0.1089732870 0.0057841679 1667 1311867774.2384989262 0.3285706341 0.3131673504 0.4404943883 0.0041972710 0.0083710000 41469989 955859216 1373700096 -0.3262015581 -0.1091675982 0.0061934083 1668 1311867774.2744109631 0.3285042048 0.3131765452 0.4404943883 0.0041961198 0.0063410000 41473029 955859216 1373700096 -0.3259413838 -0.1097864285 0.0064481776 1669 1311867774.3046739101 0.3285729587 0.3131857701 0.4404943883 0.0041952135 0.0060420000 41475845 955859216 1373700096 -0.3258650601 -0.1095927432 0.0069650058 1670 1311867774.3375370502 0.3277614117 0.3131944980 0.4404943883 0.0041940906 0.0154530000 41478717 955859216 1373700096 -0.3250060976 -0.1089984924 0.0071555944 1671 1311867774.3727159500 0.3273982108 0.3132029982 0.4404943883 0.0041929303 0.0095130000 41481645 955859216 1373700096 -0.3244590163 -0.1096248701 0.0073956419 1672 1311867774.4051818848 0.3270261288 0.3132112656 0.4404943883 0.0041924963 0.0064480000 41484573 955859216 1373700096 -0.3239142895 -0.1097924635 0.0078790849 1673 1311867774.4376831055 0.3263978660 0.3132191476 0.4404943883 0.0041915615 0.0053240000 41487445 955859216 1373700096 -0.3232382238 -0.1094106361 0.0082128411 1674 1311867774.4740140438 0.3260123134 0.3132267899 0.4404943883 0.0041914506 0.0084800000 41490429 955859216 1373700096 -0.3228993416 -0.1098879799 0.0082935682 1675 1311867774.5066258907 0.3262035251 0.3132345372 0.4404943883 0.0041902830 0.0060540000 41493357 955859216 1373700096 -0.3230265379 -0.1107549444 0.0086007779 1676 1311867774.5394051075 0.3257640302 0.3132420130 0.4404943883 0.0041892532 0.0052830000 41496229 955859216 1373700096 -0.3226381540 -0.1108955964 0.0088403765 1677 1311867774.5727870464 0.3253871202 0.3132492552 0.4404943883 0.0041886091 0.0051350000 41499101 955859216 1373700096 -0.3221303821 -0.1109615266 0.0094062537 1678 1311867774.6076970100 0.3249679804 0.3132562389 0.4404943883 0.0041875145 0.0051070000 41502085 955859216 1373700096 -0.3216989040 -0.1106658056 0.0096215634 1679 1311867774.6373310089 0.3250844777 0.3132632837 0.4404943883 0.0041865017 0.0050650000 41504901 955859216 1373700096 -0.3217180669 -0.1104329526 0.0099759670 1680 1311867774.6731650829 0.3250537813 0.3132703019 0.4404943883 0.0041855378 0.0096600000 41507829 955859216 1373700096 -0.3216087222 -0.1103490740 0.0103133889 1681 1311867774.7048470974 0.3250054121 0.3132772829 0.4404943883 0.0041844542 0.0063550000 41510757 955859216 1373700096 -0.3212729096 -0.1106888652 0.0105272178 1682 1311867774.7448370457 0.3253671527 0.3132844707 0.4404943883 0.0041861242 0.0053500000 41513853 955859216 1373700096 -0.3213421106 -0.1101959124 0.0109720109 1683 1311867774.7731618881 0.3253133893 0.3132916180 0.4404943883 0.0041849487 0.0051370000 41516557 955859216 1373700096 -0.3211610317 -0.1099369898 0.0113795390 1684 1311867774.8052101135 0.3253369927 0.3132987708 0.4404943883 0.0041846246 0.0099620000 41519485 955859216 1373700096 -0.3209971488 -0.1103326157 0.0117829451 1685 1311867774.8443410397 0.3251316845 0.3133057933 0.4404943883 0.0041834530 0.0066690000 41522525 955859216 1373700096 -0.3205676973 -0.1105330288 0.0121929031 1686 1311867774.8735189438 0.3253348470 0.3133129280 0.4404943883 0.0041827512 0.0054740000 41525341 955859216 1373700096 -0.3204956055 -0.1108344793 0.0126836989 1687 1311867774.9063620567 0.3254654706 0.3133201316 0.4404943883 0.0041819852 0.0051330000 41528213 955859216 1373700096 -0.3203666210 -0.1112455279 0.0130201085 1688 1311867774.9433379173 0.3256717324 0.3133274489 0.4404943883 0.0041807552 0.0129750000 41531253 955859216 1373700096 -0.3202219009 -0.1114488319 0.0133287143 1689 1311867774.9730870724 0.3255531788 0.3133346874 0.4404943883 0.0041795621 0.0094310000 41534013 955859216 1373700096 -0.3199085593 -0.1114392281 0.0136197610 1690 1311867775.0104990005 0.3260816932 0.3133422300 0.4404943883 0.0041783476 0.0063100000 41537109 955859216 1373700096 -0.3202502429 -0.1115774438 0.0139039792 1691 1311867775.0417571068 0.3257651031 0.3133495765 0.4404943883 0.0041771236 0.0053460000 41539925 955859216 1373700096 -0.3199371099 -0.1113959923 0.0140534844 1692 1311867775.0737869740 0.3254871368 0.3133567500 0.4404943883 0.0041762518 0.0051120000 41542797 955859216 1373700096 -0.3195134699 -0.1109189466 0.0142314443 1693 1311867775.1060369015 0.3255413473 0.3133639470 0.4404943883 0.0041753339 0.0051090000 41545669 955859216 1373700096 -0.3195687532 -0.1108318493 0.0143172266 1694 1311867775.1426749229 0.3261596859 0.3133715006 0.4404943883 0.0041741249 0.0092210000 41548653 955859216 1373700096 -0.3199120164 -0.1114028916 0.0145752439 1695 1311867775.1733469963 0.3262716234 0.3133791113 0.4404943883 0.0041730304 0.0062310000 41551469 955859216 1373700096 -0.3199726343 -0.1115193814 0.0148047600 1696 1311867775.2047309875 0.3261819184 0.3133866601 0.4404943883 0.0041718545 0.0053630000 41554397 955859216 1373700096 -0.3198750019 -0.1114531085 0.0148214716 1697 1311867775.2407341003 0.3256381154 0.3133938796 0.4404943883 0.0041712826 0.0055760000 41557381 955859216 1373700096 -0.3193212152 -0.1111676916 0.0148630245 1698 1311867775.2726259232 0.3257535398 0.3134011585 0.4404943883 0.0041706252 0.0055640000 41560197 955859216 1373700096 -0.3195321262 -0.1110215932 0.0149892624 1699 1311867775.3058989048 0.3256491125 0.3134083674 0.4404943883 0.0041695702 0.0053040000 41563125 955859216 1373700096 -0.3193207383 -0.1112335473 0.0150829637 1700 1311867775.3405869007 0.3257499039 0.3134156272 0.4404943883 0.0041703999 0.0128780000 41566109 955859216 1373700096 -0.3192074895 -0.1107259467 0.0152813457 1701 1311867775.3728890419 0.3252980411 0.3134226127 0.4404943883 0.0041710861 0.0068550000 41569037 955859216 1373700096 -0.3188575506 -0.1103536114 0.0152815562 1702 1311867775.4055740833 0.3263976872 0.3134302361 0.4404943883 0.0041706542 0.0056120000 41571909 955859216 1373700096 -0.3195891380 -0.1111136451 0.0158168375 1703 1311867775.4408710003 0.3263542056 0.3134378251 0.4404943883 0.0041712421 0.0051000000 41574893 955859216 1373700096 -0.3192106485 -0.1111189425 0.0160136204 1704 1311867775.4725620747 0.3258287311 0.3134450967 0.4404943883 0.0041712168 0.0094680000 41577709 955859216 1373700096 -0.3187934160 -0.1108150035 0.0161165837 1705 1311867775.5057229996 0.3259865046 0.3134524524 0.4404943883 0.0041702420 0.0063050000 41580693 955859216 1373700096 -0.3188384175 -0.1107306182 0.0164140984 1706 1311867775.5413000584 0.3260306120 0.3134598253 0.4404943883 0.0041698039 0.0052500000 41583677 955859216 1373700096 -0.3188014030 -0.1110094115 0.0165963657 1707 1311867775.5736858845 0.3258130252 0.3134670621 0.4404943883 0.0041687533 0.0050630000 41586493 955859216 1373700096 -0.3183831275 -0.1109877303 0.0168684646 1708 1311867775.6086819172 0.3259985745 0.3134743990 0.4404943883 0.0041679463 0.0050930000 41589421 955859216 1373700096 -0.3183648884 -0.1108643413 0.0169438105 1709 1311867775.6414420605 0.3262117803 0.3134818522 0.4404943883 0.0041667452 0.0129710000 41592405 955859216 1373700096 -0.3183449805 -0.1110392287 0.0171429217 1710 1311867775.6726739407 0.3263744414 0.3134893917 0.4404943883 0.0041657918 0.0068140000 41595165 955859216 1373700096 -0.3184780478 -0.1108461246 0.0172402058 1711 1311867775.7051100731 0.3260669708 0.3134967427 0.4404943883 0.0041646992 0.0055840000 41598093 955859216 1373700096 -0.3181090355 -0.1106822267 0.0172734018 1712 1311867775.7416241169 0.3259834349 0.3135040363 0.4404943883 0.0041635661 0.0052220000 41601077 955859216 1373700096 -0.3178790212 -0.1107933074 0.0176457223 1713 1311867775.7742578983 0.3262721300 0.3135114900 0.4404943883 0.0041632096 0.0092890000 41603949 955859216 1373700096 -0.3180345297 -0.1108225435 0.0181530975 1714 1311867775.8062939644 0.3255412579 0.3135185085 0.4404943883 0.0041624683 0.0062150000 41606821 955859216 1373700096 -0.3172530532 -0.1104341224 0.0181448162 1715 1311867775.8408269882 0.3258095384 0.3135256753 0.4404943883 0.0041613307 0.0052020000 41609805 955859216 1373700096 -0.3173444867 -0.1103090346 0.0183298662 1716 1311867775.8729701042 0.3258034289 0.3135328302 0.4404943883 0.0041602541 0.0051040000 41612621 955859216 1373700096 -0.3171756864 -0.1104083955 0.0186829958 1717 1311867775.9066479206 0.3259986043 0.3135400904 0.4404943883 0.0041590681 0.0095950000 41615605 955859216 1373700096 -0.3173298538 -0.1103617698 0.0189127941 1718 1311867775.9435749054 0.3260753751 0.3135473868 0.4404943883 0.0041581482 0.0063430000 41618533 955859216 1373700096 -0.3172787428 -0.1104071736 0.0191286616 1719 1311867775.9730579853 0.3259078264 0.3135545773 0.4404943883 0.0041573852 0.0052770000 41621349 955859216 1373700096 -0.3168774843 -0.1102361977 0.0192395356 1720 1311867776.0135231018 0.3266804516 0.3135622086 0.4404943883 0.0041564376 0.0051160000 41624445 955859216 1373700096 -0.3173202276 -0.1108946353 0.0195115898 1721 1311867776.0423479080 0.3263475001 0.3135696376 0.4404943883 0.0041555809 0.0101220000 41627149 955859216 1373700096 -0.3168339431 -0.1109056175 0.0195458606 1722 1311867776.0782909393 0.3262318075 0.3135769908 0.4404943883 0.0041543904 0.0065020000 41630189 955859216 1373700096 -0.3165026307 -0.1109851748 0.0196361747 1723 1311867776.1090068817 0.3262413740 0.3135843410 0.4404943883 0.0041535544 0.0054220000 41633061 955859216 1373700096 -0.3163560927 -0.1108201966 0.0198217295 1724 1311867776.1410119534 0.3265306652 0.3135918504 0.4404943883 0.0041524202 0.0051010000 41635933 955859216 1373700096 -0.3166240156 -0.1105854958 0.0200232714 1725 1311867776.1773319244 0.3265188038 0.3135993443 0.4404943883 0.0041513631 0.0129970000 41638917 955859216 1373700096 -0.3165785372 -0.1105186418 0.0200970024 1726 1311867776.2094259262 0.3265330493 0.3136068378 0.4404943883 0.0041501683 0.0068260000 41641789 955859216 1373700096 -0.3164898753 -0.1102603674 0.0200581886 1727 1311867776.2407069206 0.3265151083 0.3136143122 0.4404943883 0.0041491289 0.0062350000 41644661 955859216 1373700096 -0.3164686263 -0.1101920977 0.0200718418 1728 1311867776.2753469944 0.3271069229 0.3136221204 0.4404943883 0.0041480701 0.0052430000 41647645 955859216 1373700096 -0.3169845045 -0.1100621670 0.0201612506 1729 1311867776.3120670319 0.3275203407 0.3136301587 0.4404943883 0.0041469244 0.0092220000 41650573 955859216 1373700096 -0.3172518015 -0.1100223139 0.0203091223 1730 1311867776.3407590389 0.3275771141 0.3136382205 0.4404943883 0.0041458240 0.0062950000 41653445 955859216 1373700096 -0.3172712326 -0.1099727228 0.0204053931 1731 1311867776.3730750084 0.3273966610 0.3136461688 0.4404943883 0.0041446850 0.0053450000 41656317 955859216 1373700096 -0.3170253038 -0.1100246087 0.0205297172 1732 1311867776.4097070694 0.3273594081 0.3136540863 0.4404943883 0.0041436300 0.0051860000 41659357 955859216 1373700096 -0.3169142008 -0.1098499745 0.0206053890 1733 1311867776.4422268867 0.3269244432 0.3136617438 0.4404943883 0.0041426869 0.0098890000 41662229 955859216 1373700096 -0.3164319098 -0.1094226986 0.0205653217 1734 1311867776.4727520943 0.3273132145 0.3136696166 0.4404943883 0.0041415121 0.0064680000 41665045 955859216 1373700096 -0.3168195486 -0.1093844697 0.0207248274 1735 1311867776.5105879307 0.3268744051 0.3136772274 0.4404943883 0.0041404540 0.0055020000 41668085 955859216 1373700096 -0.3162834644 -0.1092048213 0.0207684375 1736 1311867776.5415630341 0.3268861771 0.3136848363 0.4404943883 0.0041393574 0.0051890000 41670901 955859216 1373700096 -0.3162420988 -0.1089713722 0.0210954789 1737 1311867776.5743160248 0.3262875974 0.3136920918 0.4404943883 0.0041382216 0.0124960000 41673829 955859216 1373700096 -0.3155476749 -0.1087265164 0.0212391149 1738 1311867776.6094930172 0.3265023828 0.3136994625 0.4404943883 0.0041370623 0.0070260000 41676813 955859216 1373700096 -0.3156370819 -0.1085974053 0.0215544086 1739 1311867776.6413109303 0.3266324103 0.3137068995 0.4404943883 0.0041358761 0.0057510000 41679685 955859216 1373700096 -0.3155409694 -0.1087559685 0.0220867302 1740 1311867776.6763460636 0.3265838921 0.3137143000 0.4404943883 0.0041347149 0.0052600000 41682725 955859216 1373700096 -0.3153308630 -0.1087991595 0.0225112271 1741 1311867776.7134280205 0.3260444105 0.3137213822 0.4404943883 0.0041336174 0.0093370000 41685709 955859216 1373700096 -0.3146145642 -0.1085608229 0.0227262210 1742 1311867776.7423970699 0.3258196414 0.3137283273 0.4404943883 0.0041328522 0.0063660000 41688469 955859216 1373700096 -0.3144538701 -0.1084137261 0.0229333732 1743 1311867776.7739920616 0.3256336153 0.3137351576 0.4404943883 0.0041319963 0.0053630000 41691453 955859216 1373700096 -0.3140732348 -0.1087653860 0.0232853200 1744 1311867776.8117430210 0.3252960145 0.3137417866 0.4404943883 0.0041317279 0.0089670000 41694549 955859216 1373700096 -0.3136261404 -0.1086573005 0.0235510152 1745 1311867776.8449618816 0.3253971338 0.3137484658 0.4404943883 0.0041308762 0.0063400000 41697533 955859216 1373700096 -0.3134371936 -0.1086402759 0.0238186307 1746 1311867776.8748989105 0.3254532218 0.3137551696 0.4404943883 0.0041297715 0.0053640000 41700349 955859216 1373700096 -0.3133856058 -0.1086963788 0.0242302269 1747 1311867776.9104089737 0.3249931037 0.3137616023 0.4404943883 0.0041289353 0.0089740000 41703333 955859216 1373700096 -0.3128305972 -0.1085736454 0.0245422795 1748 1311867776.9465129375 0.3246999979 0.3137678600 0.4404943883 0.0041278646 0.0063230000 41706373 955859216 1373700096 -0.3124203980 -0.1086088941 0.0248067062 1749 1311867776.9780058861 0.3245410025 0.3137740196 0.4404943883 0.0041277286 0.0084120000 41709245 955859216 1373700096 -0.3122097254 -0.1085787266 0.0250270981 1750 1311867777.0103049278 0.3248132467 0.3137803277 0.4404943883 0.0041270303 0.0061730000 41712229 955859216 1373700096 -0.3124166727 -0.1083995029 0.0254911147 1751 1311867777.0430829525 0.3250200450 0.3137867467 0.4404943883 0.0041258579 0.0054440000 41715157 955859216 1373700096 -0.3125544190 -0.1083570346 0.0256504770 1752 1311867777.0763421059 0.3246825039 0.3137929658 0.4404943883 0.0041249706 0.0052310000 41718085 955859216 1373700096 -0.3120883107 -0.1085499600 0.0259791799 1753 1311867777.1087210178 0.3248170018 0.3137992544 0.4404943883 0.0041238356 0.0130900000 41721013 955859216 1373700096 -0.3121069372 -0.1086464897 0.0263342727 1754 1311867777.1435770988 0.3250596225 0.3138056743 0.4404943883 0.0041226784 0.0069950000 41724053 955859216 1373700096 -0.3123172522 -0.1084927619 0.0265959129 1755 1311867777.1783010960 0.3253214061 0.3138122359 0.4404943883 0.0041215139 0.0056570000 41727037 955859216 1373700096 -0.3123643696 -0.1083272845 0.0269912947 1756 1311867777.2115299702 0.3254011869 0.3138188356 0.4404943883 0.0041203852 0.0052140000 41730077 955859216 1373700096 -0.3124552965 -0.1083062813 0.0272331703 1757 1311867777.2420690060 0.3249905705 0.3138251940 0.4404943883 0.0041192837 0.0053060000 41732837 955859216 1373700096 -0.3118329048 -0.1083737314 0.0275598988 1758 1311867777.2766950130 0.3244539797 0.3138312399 0.4404943883 0.0041184529 0.0099650000 41735821 955859216 1373700096 -0.3112842143 -0.1082764640 0.0276485253 1759 1311867777.3093490601 0.3245784044 0.3138373497 0.4404943883 0.0041183631 0.0067080000 41738749 955859216 1373700096 -0.3112907112 -0.1084274724 0.0281139743 1760 1311867777.3419890404 0.3244137168 0.3138433590 0.4404943883 0.0041172069 0.0054110000 41741677 955859216 1373700096 -0.3112164438 -0.1086836383 0.0284073055 1761 1311867777.3780329227 0.3242631257 0.3138492760 0.4404943883 0.0041167008 0.0099100000 41744773 955859216 1373700096 -0.3111500740 -0.1086433530 0.0285738576 1762 1311867777.4108960629 0.3239939511 0.3138550335 0.4404943883 0.0041156630 0.0064290000 41747701 955859216 1373700096 -0.3109801114 -0.1085911393 0.0287904460 1763 1311867777.4411139488 0.3243754506 0.3138610008 0.4404943883 0.0041145851 0.0054080000 41750573 955859216 1373700096 -0.3113940656 -0.1088446081 0.0290324632 1764 1311867777.4770240784 0.3239643574 0.3138667283 0.4404943883 0.0041134976 0.0093870000 41753669 955859216 1373700096 -0.3110903800 -0.1089641973 0.0291750059 1765 1311867777.5098700523 0.3239980340 0.3138724685 0.4404943883 0.0041123707 0.0063860000 41756597 955859216 1373700096 -0.3112763762 -0.1088489890 0.0295660980 1766 1311867777.5421240330 0.3233802915 0.3138778523 0.4404943883 0.0041112499 0.0055380000 41759469 955859216 1373700096 -0.3108170629 -0.1085054874 0.0297526233 1767 1311867777.5777161121 0.3231097162 0.3138830769 0.4404943883 0.0041101230 0.0093310000 41762565 955859216 1373700096 -0.3108505011 -0.1083603278 0.0300181601 1768 1311867777.6086440086 0.3226203024 0.3138880187 0.4404943883 0.0041092507 0.0062820000 41765437 955859216 1373700096 -0.3104863167 -0.1082502306 0.0305420868 1769 1311867777.6407959461 0.3221682310 0.3138926995 0.4404943883 0.0041081242 0.0053740000 41768421 955859216 1373700096 -0.3102845848 -0.1082492545 0.0309295729 1770 1311867777.6765840054 0.3217277825 0.3138971261 0.4404943883 0.0041069982 0.0102330000 41771461 955859216 1373700096 -0.3101372123 -0.1083342731 0.0313569419 1771 1311867777.7086570263 0.3215214908 0.3139014312 0.4404943883 0.0041058604 0.0065360000 41774333 955859216 1373700096 -0.3100717068 -0.1083915383 0.0318611376 1772 1311867777.7411170006 0.3209577501 0.3139054133 0.4404943883 0.0041049407 0.0054810000 41777261 955859216 1373700096 -0.3095483184 -0.1085705459 0.0320952423 1773 1311867777.7797420025 0.3206172287 0.3139091989 0.4404943883 0.0041039090 0.0052050000 41780413 955859216 1373700096 -0.3094255328 -0.1085929275 0.0323040150 1774 1311867777.8103909492 0.3209384084 0.3139131612 0.4404943883 0.0041028457 0.0104050000 41783341 955859216 1373700096 -0.3098799586 -0.1084911153 0.0325499810 1775 1311867777.8421120644 0.3207300603 0.3139170017 0.4404943883 0.0041017930 0.0066780000 41786213 955859216 1373700096 -0.3097691834 -0.1083191112 0.0330580287 1776 1311867777.8771729469 0.3206019104 0.3139207658 0.4404943883 0.0041006952 0.0055180000 41789253 955859216 1373700096 -0.3098198771 -0.1083115861 0.0334232412 1777 1311867777.9091188908 0.3204843998 0.3139244594 0.4404943883 0.0040996417 0.0051800000 41792181 955859216 1373700096 -0.3100480735 -0.1085472107 0.0337652192 1778 1311867777.9424149990 0.3200377226 0.3139278977 0.4404943883 0.0040986632 0.0102110000 41795109 955859216 1373700096 -0.3099457324 -0.1083906814 0.0338153914 1779 1311867777.9770610332 0.3197701573 0.3139311817 0.4404943883 0.0040976622 0.0066190000 41798205 955859216 1373700096 -0.3100973666 -0.1076334342 0.0339799039 1780 1311867778.0100560188 0.3196990192 0.3139344221 0.4404943883 0.0040994137 0.0055440000 41801133 955859216 1373700096 -0.3104409575 -0.1076346561 0.0340624452 1781 1311867778.0413420200 0.3202656507 0.3139379769 0.4404943883 0.0040984556 0.0052390000 41804005 955859216 1373700096 -0.3112069368 -0.1082629040 0.0344102457 1782 1311867778.0773630142 0.3193126321 0.3139409930 0.4404943883 0.0040985907 0.0127850000 41807045 955859216 1373700096 -0.3103833795 -0.1079639643 0.0342574641 1783 1311867778.1094930172 0.3193850815 0.3139440464 0.4404943883 0.0040983221 0.0070000000 41809973 955859216 1373700096 -0.3105148375 -0.1081189066 0.0341663510 1784 1311867778.1418550014 0.3199413419 0.3139474081 0.4404943883 0.0040972162 0.0057350000 41812957 955859216 1373700096 -0.3112782240 -0.1079452559 0.0341803171 1785 1311867778.1826310158 0.3201175034 0.3139508647 0.4404943883 0.0040970745 0.0052940000 41816053 955859216 1373700096 -0.3119023740 -0.1077437401 0.0341522433 1786 1311867778.2094058990 0.3205573559 0.3139545638 0.4404943883 0.0040967717 0.0092550000 41818869 955859216 1373700096 -0.3123442829 -0.1082979813 0.0341462679 1787 1311867778.2432699203 0.3206824660 0.3139583287 0.4404943883 0.0040959251 0.0089110000 41821853 955859216 1373700096 -0.3126285374 -0.1085131839 0.0341206305 1788 1311867778.2796919346 0.3204188645 0.3139619419 0.4404943883 0.0040956097 0.0062470000 41824893 955859216 1373700096 -0.3125214577 -0.1088479757 0.0341702513 1789 1311867778.3125588894 0.3203484714 0.3139655118 0.4404943883 0.0040945829 0.0054060000 41827821 955859216 1373700096 -0.3125914335 -0.1094651371 0.0342139341 1790 1311867778.3414309025 0.3189052641 0.3139682715 0.4404943883 0.0040944334 0.0091330000 41830693 955859216 1373700096 -0.3111103475 -0.1096069738 0.0339943953 1791 1311867778.3782539368 0.3185084760 0.3139708065 0.4404943883 0.0040941970 0.0064310000 41833789 955859216 1373700096 -0.3107555211 -0.1099018008 0.0339775123 1792 1311867778.4093298912 0.3183782697 0.3139732660 0.4404943883 0.0040931714 0.0053920000 41836661 955859216 1373700096 -0.3106588125 -0.1101804823 0.0340358168 1793 1311867778.4445381165 0.3185845315 0.3139758378 0.4404943883 0.0040920560 0.0100790000 41839701 955859216 1373700096 -0.3109573722 -0.1101737767 0.0338382311 1794 1311867778.4812810421 0.3185201585 0.3139783709 0.4404943883 0.0040912968 0.0066120000 41842797 955859216 1373700096 -0.3107759356 -0.1102941707 0.0337906592 1795 1311867778.5097670555 0.3187637329 0.3139810368 0.4404943883 0.0040903253 0.0055520000 41845613 955859216 1373700096 -0.3111106157 -0.1106423587 0.0338073224 1796 1311867778.5484840870 0.3188427091 0.3139837438 0.4404943883 0.0040896624 0.0052050000 41848709 955859216 1373700096 -0.3113001287 -0.1110150665 0.0339020975 1797 1311867778.5830690861 0.3184393942 0.3139862233 0.4404943883 0.0040886888 0.0129120000 41851749 955859216 1373700096 -0.3108661771 -0.1112705544 0.0337361693 1798 1311867778.6150701046 0.3187470436 0.3139888711 0.4404943883 0.0040877468 0.0069930000 41854677 955859216 1373700096 -0.3112272918 -0.1116808057 0.0336898081 1799 1311867778.6452109814 0.3191261590 0.3139917267 0.4404943883 0.0040872851 0.0057800000 41857549 955859216 1373700096 -0.3119265735 -0.1116921008 0.0335467979 1800 1311867778.6781129837 0.3189069331 0.3139944574 0.4404943883 0.0040864434 0.0052580000 41860477 955859216 1373700096 -0.3117686808 -0.1118437201 0.0334960297 1801 1311867778.7125270367 0.3193773031 0.3139974462 0.4404943883 0.0040859398 0.0089320000 41863461 955859216 1373700096 -0.3123434782 -0.1121439710 0.0334891044 1802 1311867778.7490179539 0.3199589849 0.3140007545 0.4404943883 0.0040848710 0.0063270000 41866557 955859216 1373700096 -0.3131598532 -0.1118281111 0.0333354771 1803 1311867778.7815420628 0.3199756742 0.3140040684 0.4404943883 0.0040842258 0.0097960000 41869541 955859216 1373700096 -0.3134880364 -0.1115872636 0.0331939384 1804 1311867778.8090119362 0.3205741942 0.3140077104 0.4404943883 0.0040832107 0.0065780000 41872301 955859216 1373700096 -0.3140532076 -0.1122497395 0.0332763605 1805 1311867778.8465809822 0.3205425441 0.3140113308 0.4404943883 0.0040833293 0.0054980000 41875397 955859216 1373700096 -0.3141412735 -0.1127023026 0.0332412943 1806 1311867778.8808300495 0.3216317296 0.3140155503 0.4404943883 0.0040822425 0.0095080000 41878381 955859216 1373700096 -0.3153176308 -0.1126628518 0.0331514664 1807 1311867778.9117860794 0.3217472732 0.3140198290 0.4404943883 0.0040816653 0.0065010000 41881253 955859216 1373700096 -0.3155958354 -0.1127636954 0.0330671035 1808 1311867778.9482150078 0.3221929073 0.3140243495 0.4404943883 0.0040814329 0.0054080000 41884349 955859216 1373700096 -0.3160989583 -0.1134815514 0.0329899415 1809 1311867778.9777760506 0.3230628371 0.3140293459 0.4404943883 0.0040804894 0.0103360000 41887221 955859216 1373700096 -0.3170786202 -0.1139361635 0.0329169147 1810 1311867779.0105700493 0.3237041831 0.3140346911 0.4404943883 0.0040799719 0.0067030000 41890149 955859216 1373700096 -0.3177233636 -0.1140419394 0.0327796154 1811 1311867779.0471200943 0.3241270185 0.3140402639 0.4404943883 0.0040789561 0.0093680000 41893245 955859216 1373700096 -0.3180730045 -0.1142106131 0.0324877612 1812 1311867779.0780360699 0.3251259923 0.3140463819 0.4404943883 0.0040778553 0.0064310000 41896061 955859216 1373700096 -0.3189116716 -0.1145979986 0.0321329795 1813 1311867779.1124050617 0.3256154656 0.3140527631 0.4404943883 0.0040777339 0.0054720000 41899045 955859216 1373700096 -0.3193336725 -0.1146548092 0.0319774598 1814 1311867779.1473538876 0.3263170421 0.3140595240 0.4404943883 0.0040766501 0.0053360000 41901917 955859216 1373700096 -0.3196877241 -0.1151218414 0.0319718570 1815 1311867779.1777000427 0.3265119493 0.3140663848 0.4404943883 0.0040755495 0.0105400000 41904733 955859216 1373700096 -0.3196360171 -0.1156359985 0.0319284126 1816 1311867779.2123599052 0.3268450201 0.3140734215 0.4404943883 0.0040748155 0.0071100000 41907661 955859216 1373700096 -0.3198245168 -0.1160518825 0.0318320766 1817 1311867779.2447109222 0.3263148963 0.3140801587 0.4404943883 0.0040738057 0.0056830000 41910589 955859216 1373700096 -0.3191574812 -0.1161633506 0.0314268917 1818 1311867779.2782809734 0.3263154030 0.3140868888 0.4404943883 0.0040733848 0.0096400000 41913461 955859216 1373700096 -0.3190006316 -0.1159767359 0.0314657241 1819 1311867779.3104579449 0.3264287114 0.3140936737 0.4404943883 0.0040723533 0.0065610000 41916389 955859216 1373700096 -0.3190705180 -0.1155485660 0.0310998838 1820 1311867779.3468949795 0.3264459372 0.3141004607 0.4404943883 0.0040718032 0.0055590000 41919429 955859216 1373700096 -0.3190047741 -0.1149982065 0.0307502449 1821 1311867779.3772010803 0.3263618052 0.3141071940 0.4404943883 0.0040713001 0.0092950000 41922245 955859216 1373700096 -0.3186165094 -0.1153599322 0.0304067601 1822 1311867779.4088799953 0.3264769912 0.3141139831 0.4404943883 0.0040702286 0.0066690000 41925117 955859216 1373700096 -0.3185481131 -0.1155288219 0.0302178226 1823 1311867779.4446020126 0.3263712525 0.3141207068 0.4404943883 0.0040694183 0.0055990000 41928101 955859216 1373700096 -0.3181664646 -0.1154766753 0.0298540816 1824 1311867779.4768970013 0.3269210160 0.3141277245 0.4404943883 0.0040691327 0.0090960000 41931029 955859216 1373700096 -0.3185877204 -0.1158314198 0.0297353901 1825 1311867779.5098230839 0.3273035288 0.3141349441 0.4404943883 0.0040681637 0.0090580000 41933901 955859216 1373700096 -0.3188018203 -0.1161516458 0.0297784302 1826 1311867779.5450038910 0.3273819387 0.3141421988 0.4404943883 0.0040674387 0.0064880000 41936885 955859216 1373700096 -0.3189001977 -0.1159767956 0.0293018017 1827 1311867779.5777029991 0.3276000619 0.3141495649 0.4404943883 0.0040666843 0.0099420000 41939757 955859216 1373700096 -0.3190615773 -0.1163041517 0.0291241314 1828 1311867779.6092689037 0.3279288411 0.3141571028 0.4404943883 0.0040659689 0.0066040000 41942629 955859216 1373700096 -0.3192102015 -0.1165251285 0.0288465135 1829 1311867779.6482150555 0.3281371295 0.3141647463 0.4404943883 0.0040653970 0.0056070000 41945669 955859216 1373700096 -0.3193479478 -0.1162169576 0.0285511408 1830 1311867779.6796278954 0.3279770911 0.3141722940 0.4404943883 0.0040647651 0.0053690000 41948541 955859216 1373700096 -0.3191765249 -0.1158244908 0.0279842373 1831 1311867779.7129859924 0.3282814920 0.3141799998 0.4404943883 0.0040637969 0.0089210000 41951413 955859216 1373700096 -0.3192605972 -0.1159015298 0.0278487466 1832 1311867779.7461729050 0.3287580609 0.3141879572 0.4404943883 0.0040631383 0.0063820000 41954397 955859216 1373700096 -0.3195361197 -0.1162487268 0.0279099010 1833 1311867779.7771708965 0.3284587860 0.3141957427 0.4404943883 0.0040621313 0.0055020000 41957213 955859216 1373700096 -0.3190827072 -0.1163765565 0.0275273323 1834 1311867779.8130059242 0.3286080360 0.3142036011 0.4404943883 0.0040614918 0.0055560000 41960141 955859216 1373700096 -0.3189743757 -0.1165510491 0.0272986405 1835 1311867779.8454499245 0.3285522163 0.3142114205 0.4404943883 0.0040605276 0.0054920000 41963069 955859216 1373700096 -0.3187505901 -0.1170165539 0.0270193331 1836 1311867779.8771400452 0.3284271061 0.3142191633 0.4404943883 0.0040597491 0.0137430000 41965885 955859216 1373700096 -0.3183929026 -0.1174707264 0.0268898066 1837 1311867779.9128279686 0.3281154037 0.3142267279 0.4404943883 0.0040591347 0.0071960000 41968925 955859216 1373700096 -0.3178691566 -0.1176764145 0.0265746769 1838 1311867779.9448599815 0.3278361261 0.3142341324 0.4404943883 0.0040581616 0.0060020000 41971797 955859216 1373700096 -0.3176262677 -0.1173348576 0.0262284316 1839 1311867779.9769320488 0.3281132579 0.3142416795 0.4404943883 0.0040575723 0.0054990000 41974669 955859216 1373700096 -0.3178116679 -0.1173259839 0.0260867085 1840 1311867780.0130739212 0.3281757534 0.3142492523 0.4404943883 0.0040569484 0.0054880000 41977653 955859216 1373700096 -0.3179357350 -0.1171240881 0.0257395916 1841 1311867780.0448310375 0.3278773427 0.3142566549 0.4404943883 0.0040568585 0.0055460000 41980525 955859216 1373700096 -0.3177736998 -0.1166342348 0.0251606852 1842 1311867780.0771219730 0.3276896775 0.3142639475 0.4404943883 0.0040560853 0.0054960000 41983397 955859216 1373700096 -0.3176213205 -0.1163790748 0.0250749867 1843 1311867780.1143870354 0.3274697065 0.3142711129 0.4404943883 0.0040551661 0.0055420000 41986437 955859216 1373700096 -0.3174310029 -0.1160738617 0.0246557146 1844 1311867780.1448268890 0.3274064958 0.3142782362 0.4404943883 0.0040569168 0.0055160000 41989253 955859216 1373700096 -0.3176421225 -0.1161960736 0.0243786573 1845 1311867780.1773400307 0.3276644945 0.3142854916 0.4404943883 0.0040600216 0.0055740000 41992125 955859216 1373700096 -0.3177507222 -0.1161742657 0.0240965541 1846 1311867780.2158250809 0.3270561099 0.3142924096 0.4404943883 0.0040626923 0.0054990000 41995221 955859216 1373700096 -0.3175272644 -0.1158389747 0.0237044841 1847 1311867780.2454960346 0.3277208507 0.3142996800 0.4404943883 0.0040649648 0.0055130000 41998037 955859216 1373700096 -0.3177907169 -0.1160535663 0.0235920306 1848 1311867780.2815570831 0.3277332485 0.3143069493 0.4404943883 0.0040639378 0.0055360000 42001021 955859216 1373700096 -0.3179211318 -0.1162056178 0.0233079344 1849 1311867780.3140099049 0.3277898431 0.3143142412 0.4404943883 0.0040630243 0.0055160000 42003893 955859216 1373700096 -0.3178924918 -0.1166791022 0.0229847729 1850 1311867780.3464050293 0.3281769156 0.3143217346 0.4404943883 0.0040619646 0.0148330000 42006765 955859216 1373700096 -0.3181890845 -0.1169195548 0.0226994380 1851 1311867780.3772649765 0.3283735514 0.3143293261 0.4404943883 0.0040611888 0.0074670000 42009581 955859216 1373700096 -0.3184014559 -0.1173575372 0.0221260674 1852 1311867780.4132668972 0.3283110559 0.3143368756 0.4404943883 0.0040607262 0.0059760000 42012621 955859216 1373700096 -0.3182297349 -0.1177756786 0.0216148421 1853 1311867780.4451050758 0.3286496997 0.3143445997 0.4404943883 0.0040602014 0.0099980000 42015493 955859216 1373700096 -0.3186248839 -0.1176980585 0.0211982541 1854 1311867780.4791510105 0.3283631802 0.3143521610 0.4404943883 0.0040624652 0.0066120000 42018421 955859216 1373700096 -0.3187323213 -0.1175766736 0.0207813885 1855 1311867780.5153009892 0.3287478983 0.3143599215 0.4404943883 0.0040624890 0.0056470000 42021461 955859216 1373700096 -0.3188742995 -0.1178043634 0.0206177663 1856 1311867780.5455119610 0.3280084133 0.3143672752 0.4404943883 0.0040662568 0.0054860000 42024277 955859216 1373700096 -0.3184783757 -0.1180760264 0.0204808284 1857 1311867780.5798339844 0.3285769820 0.3143749272 0.4404943883 0.0040659275 0.0096360000 42027205 955859216 1373700096 -0.3189912438 -0.1181356162 0.0203082357 1858 1311867780.6136929989 0.3296244740 0.3143831347 0.4404943883 0.0040684902 0.0065880000 42030077 955859216 1373700096 -0.3197157383 -0.1180691794 0.0200087689 1859 1311867780.6459660530 0.3302638829 0.3143916773 0.4404943883 0.0040674849 0.0056590000 42033005 955859216 1373700096 -0.3204657137 -0.1180581525 0.0197691061 1860 1311867780.6793959141 0.3308688402 0.3144005360 0.4404943883 0.0040670118 0.0096960000 42035933 955859216 1373700096 -0.3213550150 -0.1174544767 0.0195090789 1861 1311867780.7156999111 0.3312458396 0.3144095877 0.4404943883 0.0040660952 0.0066260000 42038917 955859216 1373700096 -0.3220016360 -0.1169434562 0.0191554092 1862 1311867780.7469029427 0.3314768970 0.3144187539 0.4404943883 0.0040650411 0.0056400000 42041733 955859216 1373700096 -0.3223662078 -0.1169248000 0.0189017877 1863 1311867780.7774689198 0.3317136467 0.3144280372 0.4404943883 0.0040639963 0.0098310000 42044605 955859216 1373700096 -0.3226603568 -0.1169653460 0.0184100084 1864 1311867780.8164570332 0.3319326937 0.3144374281 0.4404943883 0.0040630207 0.0066030000 42047701 955859216 1373700096 -0.3229105771 -0.1170504838 0.0180428512 1865 1311867780.8460350037 0.3322090805 0.3144469572 0.4404943883 0.0040629813 0.0057250000 42050461 955859216 1373700096 -0.3235474229 -0.1175578907 0.0177687909 1866 1311867780.8791809082 0.3330020905 0.3144569010 0.4404943883 0.0040621402 0.0097450000 42053389 955859216 1373700096 -0.3243666291 -0.1178750396 0.0173589345 1867 1311867780.9152340889 0.3328704238 0.3144667636 0.4404943883 0.0040612474 0.0066800000 42056373 955859216 1373700096 -0.3243521452 -0.1174744144 0.0168168638 1868 1311867780.9457290173 0.3332307637 0.3144768086 0.4404943883 0.0040608029 0.0056860000 42059189 955859216 1373700096 -0.3247804940 -0.1177048236 0.0164482556 1869 1311867780.9838399887 0.3336222470 0.3144870522 0.4404943883 0.0040599001 0.0098010000 42062229 955859216 1373700096 -0.3251089752 -0.1181011721 0.0161013249 1870 1311867781.0137300491 0.3337825537 0.3144973707 0.4404943883 0.0040588697 0.0066980000 42065045 955859216 1373700096 -0.3253896236 -0.1178998724 0.0158415958 1871 1311867781.0463659763 0.3340279758 0.3145078093 0.4404943883 0.0040581075 0.0057200000 42067917 955859216 1373700096 -0.3256495297 -0.1180566847 0.0153849963 1872 1311867781.0821859837 0.3341989815 0.3145183281 0.4404943883 0.0040570840 0.0093790000 42070901 955859216 1373700096 -0.3256960511 -0.1187227368 0.0148761580 1873 1311867781.1157560349 0.3347225487 0.3145291152 0.4404943883 0.0040560943 0.0089980000 42073829 955859216 1373700096 -0.3262494504 -0.1190934628 0.0145373419 1874 1311867781.1459479332 0.3348240554 0.3145399449 0.4404943883 0.0040559365 0.0096830000 42076645 955859216 1373700096 -0.3265740275 -0.1196360067 0.0141323237 1875 1311867781.1839950085 0.3351828754 0.3145509545 0.4404943883 0.0040556347 0.0066240000 42079685 955859216 1373700096 -0.3267101347 -0.1204008013 0.0136260819 1876 1311867781.2133030891 0.3349631429 0.3145618352 0.4404943883 0.0040549809 0.0099860000 42082445 955859216 1373700096 -0.3265793025 -0.1203528643 0.0131904380 1877 1311867781.2467529774 0.3352533281 0.3145728589 0.4404943883 0.0040541640 0.0067610000 42085317 955859216 1373700096 -0.3267142177 -0.1199552640 0.0124996910 1878 1311867781.2855589390 0.3354784548 0.3145839907 0.4404943883 0.0040531655 0.0057560000 42088413 955859216 1373700096 -0.3267231584 -0.1200808212 0.0117667317 1879 1311867781.3133049011 0.3362314701 0.3145955115 0.4404943883 0.0040525297 0.0056410000 42091117 955859216 1373700096 -0.3273204863 -0.1198149398 0.0112974867 1880 1311867781.3465669155 0.3363825083 0.3146071003 0.4404943883 0.0040518570 0.0055660000 42094101 955859216 1373700096 -0.3275394142 -0.1196000129 0.0107467882 1881 1311867781.3809239864 0.3372386396 0.3146191319 0.4404943883 0.0040508610 0.0093680000 42097029 955859216 1373700096 -0.3284339607 -0.1195716038 0.0102573838 1882 1311867781.4144830704 0.3374812305 0.3146312797 0.4404943883 0.0040499704 0.0066810000 42099901 955859216 1373700096 -0.3288386166 -0.1190802976 0.0098360274 1883 1311867781.4457330704 0.3371013999 0.3146432129 0.4404943883 0.0040526206 0.0057860000 42102773 955859216 1373700096 -0.3290742934 -0.1190314889 0.0092557985 1884 1311867781.4812419415 0.3385566473 0.3146559058 0.4404943883 0.0040534327 0.0090820000 42105757 955859216 1373700096 -0.3299193680 -0.1194372326 0.0090133809 1885 1311867781.5131030083 0.3393364549 0.3146689989 0.4404943883 0.0040534660 0.0065900000 42108573 955859216 1373700096 -0.3308977783 -0.1191537529 0.0088622505 1886 1311867781.5451910496 0.3402019441 0.3146825370 0.4404943883 0.0040532095 0.0056970000 42111501 955859216 1373700096 -0.3320187032 -0.1187066585 0.0086047240 1887 1311867781.5813419819 0.3403459787 0.3146961372 0.4404943883 0.0040540753 0.0090590000 42114485 955859216 1373700096 -0.3325214386 -0.1188519746 0.0079965396 1888 1311867781.6135890484 0.3413170576 0.3147102372 0.4404943883 0.0040534187 0.0065650000 42117301 955859216 1373700096 -0.3333018124 -0.1192202866 0.0075768535 1889 1311867781.6467020512 0.3411935270 0.3147242570 0.4404943883 0.0040524162 0.0058470000 42120229 955859216 1373700096 -0.3332401514 -0.1191227362 0.0071128774 1890 1311867781.6832339764 0.3420871794 0.3147387347 0.4404943883 0.0040519642 0.0056430000 42123213 955859216 1373700096 -0.3342001140 -0.1193843931 0.0068547567 1891 1311867781.7131800652 0.3424364626 0.3147533818 0.4404943883 0.0040509910 0.0056170000 42126029 955859216 1373700096 -0.3346211910 -0.1196421832 0.0064805555 1892 1311867781.7453010082 0.3423224390 0.3147679532 0.4404943883 0.0040501934 0.0055970000 42128957 955859216 1373700096 -0.3346646428 -0.1198606789 0.0061802724 1893 1311867781.7820630074 0.3428298831 0.3147827773 0.4404943883 0.0040502562 0.0058010000 42131941 955859216 1373700096 -0.3352363706 -0.1203000024 0.0060220263 1894 1311867781.8145859241 0.3431049287 0.3147977309 0.4404943883 0.0040521566 0.0056370000 42134813 955859216 1373700096 -0.3357762694 -0.1207789630 0.0056135431 1895 1311867781.8453550339 0.3429908156 0.3148126085 0.4404943883 0.0040512189 0.0144100000 42137685 955859216 1373700096 -0.3358014524 -0.1206015944 0.0052005849 1896 1311867781.8827259541 0.3428252637 0.3148273831 0.4404943883 0.0040517576 0.0075480000 42140669 955859216 1373700096 -0.3359443247 -0.1208952069 0.0046983385 1897 1311867781.9138391018 0.3432233632 0.3148423520 0.4404943883 0.0040514385 0.0061430000 42143541 955859216 1373700096 -0.3361118138 -0.1221932918 0.0041896459 1898 1311867781.9470670223 0.3435477018 0.3148574760 0.4404943883 0.0040504061 0.0055740000 42146469 955859216 1373700096 -0.3364392221 -0.1229471415 0.0036469665 1899 1311867781.9856810570 0.3438065350 0.3148727204 0.4404943883 0.0040522180 0.0056590000 42149453 955859216 1373700096 -0.3371188641 -0.1230553985 0.0031544776 1900 1311867782.0139210224 0.3446136117 0.3148883735 0.4404943883 0.0040517704 0.0057710000 42152213 955859216 1373700096 -0.3378947973 -0.1238855422 0.0025441253 1901 1311867782.0464830399 0.3451460004 0.3149042902 0.4404943883 0.0040514426 0.0103840000 42155141 955859216 1373700096 -0.3384379447 -0.1243156716 0.0019575362 1902 1311867782.0839829445 0.3451993763 0.3149202182 0.4404943883 0.0040520079 0.0067980000 42158069 955859216 1373700096 -0.3387670219 -0.1235451177 0.0015054197 1903 1311867782.1135599613 0.3453880250 0.3149362286 0.4404943883 0.0040518479 0.0059410000 42160885 955859216 1373700096 -0.3392722905 -0.1229872927 0.0013069951 1904 1311867782.1472380161 0.3452599943 0.3149521549 0.4404943883 0.0040508645 0.0057050000 42163813 955859216 1373700096 -0.3393152058 -0.1225914359 0.0011617417 1905 1311867782.1819090843 0.3450572789 0.3149679581 0.4404943883 0.0040500565 0.0061830000 42166797 955859216 1373700096 -0.3392699361 -0.1219395772 0.0010881529 1906 1311867782.2144429684 0.3450944424 0.3149837643 0.4404943883 0.0040497795 0.0095660000 42169669 955859216 1373700096 -0.3390912414 -0.1218288094 0.0008903965 1907 1311867782.2494089603 0.3452893794 0.3149996561 0.4404943883 0.0040504864 0.0092930000 42172597 955859216 1373700096 -0.3394232988 -0.1222160161 0.0007277202 1908 1311867782.2860810757 0.3458287120 0.3150158138 0.4404943883 0.0040494597 0.0066560000 42175637 955859216 1373700096 -0.3398976326 -0.1222682744 0.0006154487 1909 1311867782.3144040108 0.3455698788 0.3150318191 0.4404943883 0.0040486510 0.0059560000 42178341 955859216 1373700096 -0.3396462500 -0.1219492033 0.0002403432 1910 1311867782.3526129723 0.3459934294 0.3150480294 0.4404943883 0.0040484234 0.0056610000 42181437 955859216 1373700096 -0.3399414718 -0.1223053858 0.0000698537 1911 1311867782.3825540543 0.3464068174 0.3150644390 0.4404943883 0.0040473977 0.0124360000 42184197 955859216 1373700096 -0.3403641284 -0.1224670559 -0.0001415118 1912 1311867782.4147620201 0.3465296924 0.3150808957 0.4404943883 0.0040466588 0.0071160000 42186957 955859216 1373700096 -0.3403769433 -0.1221033782 -0.0002207291 1913 1311867782.4514210224 0.3465315402 0.3150973362 0.4404943883 0.0040456890 0.0059880000 42189941 955859216 1373700096 -0.3403578401 -0.1223345101 -0.0004832307 1914 1311867782.4812099934 0.3467302322 0.3151138633 0.4404943883 0.0040446771 0.0056560000 42192813 955859216 1373700096 -0.3403591216 -0.1223806813 -0.0005823622 1915 1311867782.5149359703 0.3468186259 0.3151304193 0.4404943883 0.0040440089 0.0056740000 42195685 955859216 1373700096 -0.3403961658 -0.1216975003 -0.0005844561 1916 1311867782.5516130924 0.3472693861 0.3151471933 0.4404943883 0.0040434405 0.0057500000 42198669 955859216 1373700096 -0.3406437039 -0.1221169531 -0.0004877128 1917 1311867782.5828690529 0.3472919166 0.3151639616 0.4404943883 0.0040425272 0.0090180000 42201485 955859216 1373700096 -0.3406024277 -0.1219786778 -0.0006810171 1918 1311867782.6142859459 0.3472760916 0.3151807041 0.4404943883 0.0040415290 0.0065560000 42204413 955859216 1373700096 -0.3404343426 -0.1217808276 -0.0008540300 1919 1311867782.6501080990 0.3476354182 0.3151976164 0.4404943883 0.0040408193 0.0057200000 42207397 955859216 1373700096 -0.3406600952 -0.1219530478 -0.0010450443 1920 1311867782.6862080097 0.3480562270 0.3152147302 0.4404943883 0.0040415769 0.0104840000 42210381 955859216 1373700096 -0.3403175473 -0.1218275055 -0.0012333522 1921 1311867782.7131700516 0.3481901288 0.3152318960 0.4404943883 0.0040407274 0.0068950000 42213085 955859216 1373700096 -0.3405434787 -0.1214597747 -0.0015162078 1922 1311867782.7489991188 0.3484782577 0.3152491938 0.4404943883 0.0040408315 0.0058160000 42216069 955859216 1373700096 -0.3407814503 -0.1218933165 -0.0018658399 1923 1311867782.7844688892 0.3486977816 0.3152665877 0.4404943883 0.0040398044 0.0056470000 42219053 955859216 1373700096 -0.3410632014 -0.1221376508 -0.0022717561 1924 1311867782.8159070015 0.3486658037 0.3152839470 0.4404943883 0.0040391266 0.0056460000 42221925 955859216 1373700096 -0.3418264091 -0.1217227280 -0.0026115619 1925 1311867782.8522670269 0.3488165438 0.3153013665 0.4404943883 0.0040381694 0.0097470000 42224853 955859216 1373700096 -0.3416674435 -0.1220524907 -0.0031747546 1926 1311867782.8824830055 0.3501614630 0.3153194663 0.4404943883 0.0040373063 0.0093910000 42227725 955859216 1373700096 -0.3429287374 -0.1231692955 -0.0034693591 1927 1311867782.9145979881 0.3497633040 0.3153373406 0.4404943883 0.0040373090 0.0067180000 42230597 955859216 1373700096 -0.3427263498 -0.1224283874 -0.0040405411 1928 1311867782.9517209530 0.3500177860 0.3153553284 0.4404943883 0.0040364147 0.0101560000 42233637 955859216 1373700096 -0.3431717455 -0.1223619506 -0.0045686993 1929 1311867782.9812240601 0.3509754539 0.3153737940 0.4404943883 0.0040353941 0.0069590000 42236397 955859216 1373700096 -0.3442104757 -0.1232589707 -0.0050781779 1930 1311867783.0143089294 0.3509578109 0.3153922313 0.4404943883 0.0040348845 0.0058570000 42239325 955859216 1373700096 -0.3444401026 -0.1228894889 -0.0056493948 1931 1311867783.0528459549 0.3511807024 0.3154107649 0.4404943883 0.0040342599 0.0102530000 42242309 955859216 1373700096 -0.3448776305 -0.1227015182 -0.0061028483 1932 1311867783.0829811096 0.3521107733 0.3154297608 0.4404943883 0.0040337052 0.0068130000 42245181 955859216 1373700096 -0.3457718492 -0.1231398582 -0.0063658040 1933 1311867783.1137030125 0.3525287807 0.3154489533 0.4404943883 0.0040330082 0.0058540000 42247997 955859216 1373700096 -0.3463113606 -0.1228330731 -0.0066785584 1934 1311867783.1539480686 0.3523992598 0.3154680589 0.4404943883 0.0040320960 0.0056660000 42251093 955859216 1373700096 -0.3463732004 -0.1226510480 -0.0070478227 1935 1311867783.1857850552 0.3530575931 0.3154874850 0.4404943883 0.0040312512 0.0056920000 42253965 955859216 1373700096 -0.3470957577 -0.1229203120 -0.0071601733 1936 1311867783.2169439793 0.3534830511 0.3155071108 0.4404943883 0.0040308714 0.0105060000 42256781 955859216 1373700096 -0.3478482068 -0.1227582470 -0.0073765605 1937 1311867783.2548489571 0.3535477817 0.3155267498 0.4404943883 0.0040299029 0.0069040000 42259877 955859216 1373700096 -0.3480164111 -0.1224409863 -0.0076021035 1938 1311867783.2816879749 0.3537380397 0.3155464667 0.4404943883 0.0040289808 0.0058290000 42262637 955859216 1373700096 -0.3482596576 -0.1227772459 -0.0077735917 1939 1311867783.3132228851 0.3539096713 0.3155662517 0.4404943883 0.0040281183 0.0056730000 42265397 955859216 1373700096 -0.3483945727 -0.1231109053 -0.0078812316 1940 1311867783.3503270149 0.3562933505 0.3155872451 0.4404943883 0.0040278166 0.0056220000 42268437 955859216 1373700096 -0.3510655165 -0.1222488731 -0.0078781322 1941 1311867783.3855919838 0.3573495150 0.3156087609 0.4404943883 0.0040273583 0.0117390000 42271421 955859216 1373700096 -0.3521153927 -0.1225303113 -0.0080375103 1942 1311867783.4198501110 0.3574924469 0.3156303282 0.4404943883 0.0040263739 0.0072100000 42274349 955859216 1373700096 -0.3522456884 -0.1231065243 -0.0081676804 1943 1311867783.4503099918 0.3572866917 0.3156517674 0.4404943883 0.0040254969 0.0179380000 42277165 955859216 1373700096 -0.3523166776 -0.1226015612 -0.0084191868 1944 1311867783.4863688946 0.3573906124 0.3156732380 0.4404943883 0.0040254501 0.0138560000 42280149 955859216 1373700096 -0.3524114788 -0.1231903434 -0.0086375168 1945 1311867783.5186200142 0.3582922816 0.3156951501 0.4404943883 0.0040245374 0.0074450000 42282965 955859216 1373700096 -0.3533105254 -0.1234431788 -0.0086010275 1946 1311867783.5488419533 0.3580948114 0.3157169382 0.4404943883 0.0040244060 0.0061070000 42285781 955859216 1373700096 -0.3533861041 -0.1230669841 -0.0088085504 1947 1311867783.5823969841 0.3577539325 0.3157385289 0.4404943883 0.0040234938 0.0057330000 42288765 955859216 1373700096 -0.3529374003 -0.1236947402 -0.0091380207 1948 1311867783.6168529987 0.3581782579 0.3157603152 0.4404943883 0.0040225024 0.0173230000 42291637 955859216 1373700096 -0.3533860147 -0.1237988919 -0.0091808764 1949 1311867783.6515829563 0.3582621813 0.3157821222 0.4404943883 0.0040215597 0.0082620000 42294565 955859216 1373700096 -0.3535192013 -0.1232625619 -0.0093312506 1950 1311867783.6816630363 0.3589083552 0.3158042382 0.4404943883 0.0040211608 0.0095810000 42297437 955859216 1373700096 -0.3542131782 -0.1231723651 -0.0091894567 1951 1311867783.7179610729 0.3591278195 0.3158264440 0.4404943883 0.0040210365 0.0073590000 42300421 955859216 1373700096 -0.3544255197 -0.1233302504 -0.0092814108 1952 1311867783.7488200665 0.3588317931 0.3158484755 0.4404943883 0.0040200658 0.0058440000 42303237 955859216 1373700096 -0.3541054726 -0.1222962737 -0.0092461342 1953 1311867783.7808690071 0.3591032028 0.3158706233 0.4404943883 0.0040196761 0.0057890000 42306109 955859216 1373700096 -0.3542117774 -0.1220812351 -0.0089414204 1954 1311867783.8168580532 0.3594930768 0.3158929480 0.4404943883 0.0040207881 0.0094640000 42309037 955859216 1373700096 -0.3543011546 -0.1229621172 -0.0087712621 1955 1311867783.8489229679 0.3597013354 0.3159153564 0.4404943883 0.0040222154 0.0067300000 42311909 955859216 1373700096 -0.3546336889 -0.1212080866 -0.0082260557 1956 1311867783.8808929920 0.3587024212 0.3159372312 0.4404943883 0.0040213944 0.0059700000 42314781 955859216 1373700096 -0.3536922634 -0.1207161099 -0.0082336133 1957 1311867783.9168200493 0.3592624962 0.3159593698 0.4404943883 0.0040278092 0.0058150000 42317765 955859216 1373700096 -0.3540922105 -0.1213613600 -0.0077804602 1958 1311867783.9508318901 0.3589513898 0.3159813269 0.4404943883 0.0040269217 0.0094600000 42320693 955859216 1373700096 -0.3538771272 -0.1211522296 -0.0074167564 1959 1311867783.9816930294 0.3588210344 0.3160031950 0.4404943883 0.0040284312 0.0067830000 42323509 955859216 1373700096 -0.3537884057 -0.1210505739 -0.0068917484 1960 1311867784.0175230503 0.3590119779 0.3160251383 0.4404943883 0.0040282798 0.0058380000 42326549 955859216 1373700096 -0.3539814651 -0.1222105548 -0.0068487353 1961 1311867784.0505928993 0.3594776690 0.3160472966 0.4404943883 0.0040281143 0.0098670000 42329477 955859216 1373700096 -0.3545266092 -0.1223077700 -0.0066940482 1962 1311867784.0830729008 0.3588073850 0.3160690908 0.4404943883 0.0040273630 0.0094240000 42332293 955859216 1373700096 -0.3542821109 -0.1214349791 -0.0066752592 1963 1311867784.1187570095 0.3593356311 0.3160911318 0.4404943883 0.0040268887 0.0067320000 42335277 955859216 1373700096 -0.3548452556 -0.1222476736 -0.0065047797 1964 1311867784.1503119469 0.3590484262 0.3161130041 0.4404943883 0.0040265075 0.0058600000 42338149 955859216 1373700096 -0.3548920453 -0.1224010140 -0.0064593004 1965 1311867784.1823339462 0.3582997322 0.3161344732 0.4404943883 0.0040255500 0.0058060000 42341077 955859216 1373700096 -0.3544711471 -0.1219318658 -0.0061286837 1966 1311867784.2173891068 0.3584958017 0.3161560202 0.4404943883 0.0040251872 0.0057280000 42343949 955859216 1373700096 -0.3548062444 -0.1229401007 -0.0058927368 1967 1311867784.2502059937 0.3587856591 0.3161776926 0.4404943883 0.0040253605 0.0093550000 42346877 955859216 1373700096 -0.3554775417 -0.1230297014 -0.0057782796 1968 1311867784.2819900513 0.3585085273 0.3161992022 0.4404943883 0.0040247483 0.0067990000 42349693 955859216 1373700096 -0.3553964496 -0.1226631775 -0.0055700471 1969 1311867784.3176920414 0.3589338958 0.3162209059 0.4404943883 0.0040245634 0.0060120000 42352733 955859216 1373700096 -0.3559510410 -0.1232745722 -0.0053453529 1970 1311867784.3490819931 0.3594650626 0.3162428573 0.4404943883 0.0040243128 0.0058230000 42355549 955859216 1373700096 -0.3562368751 -0.1238123178 -0.0050327759 1971 1311867784.3815689087 0.3586991131 0.3162643977 0.4404943883 0.0040240017 0.0110360000 42358477 955859216 1373700096 -0.3557086289 -0.1229765937 -0.0049495082 1972 1311867784.4190580845 0.3591024280 0.3162861209 0.4404943883 0.0040233619 0.0070630000 42361461 955859216 1373700096 -0.3560422659 -0.1239878163 -0.0047313566 1973 1311867784.4496140480 0.3590674102 0.3163078042 0.4404943883 0.0040224157 0.0061030000 42364333 955859216 1373700096 -0.3558341265 -0.1243306473 -0.0044958545 1974 1311867784.4828379154 0.3590701818 0.3163294671 0.4404943883 0.0040217813 0.0057730000 42367261 955859216 1373700096 -0.3559682071 -0.1238709539 -0.0043343161 1975 1311867784.5185639858 0.3594466150 0.3163512985 0.4404943883 0.0040209101 0.0098230000 42370133 955859216 1373700096 -0.3561696410 -0.1243445352 -0.0041038422 1976 1311867784.5499279499 0.3591954410 0.3163729808 0.4404943883 0.0040200079 0.0068570000 42373005 955859216 1373700096 -0.3562038541 -0.1251066327 -0.0040479843 1977 1311867784.5848410130 0.3587447107 0.3163944131 0.4404943883 0.0040190504 0.0059270000 42375989 955859216 1373700096 -0.3560431004 -0.1244793013 -0.0040688915 1978 1311867784.6179790497 0.3588604033 0.3164158823 0.4404943883 0.0040184603 0.0093870000 42378861 955859216 1373700096 -0.3562702239 -0.1251503974 -0.0039429236 1979 1311867784.6492750645 0.3592459857 0.3164375246 0.4404943883 0.0040176029 0.0068100000 42381733 955859216 1373700096 -0.3568302989 -0.1254941672 -0.0037087135 1980 1311867784.6878700256 0.3591080308 0.3164590753 0.4404943883 0.0040173033 0.0059370000 42384773 955859216 1373700096 -0.3569600284 -0.1245566830 -0.0036695190 1981 1311867784.7168869972 0.3590669036 0.3164805836 0.4404943883 0.0040166356 0.0068520000 42387533 955859216 1373700096 -0.3571873605 -0.1248188987 -0.0036427530 1982 1311867784.7578089237 0.3586984277 0.3165018842 0.4404943883 0.0040195399 0.0059810000 42390741 955859216 1373700096 -0.3573522568 -0.1249282137 -0.0035002981 1983 1311867784.7870030403 0.3587756455 0.3165232023 0.4404943883 0.0040185438 0.0061760000 42393501 955859216 1373700096 -0.3574147522 -0.1244725659 -0.0032144629 1984 1311867784.8199620247 0.3583768904 0.3165442979 0.4404943883 0.0040186949 0.0059560000 42396261 955859216 1373700096 -0.3574174047 -0.1255897880 -0.0032002165 1985 1311867784.8550779819 0.3589482307 0.3165656601 0.4404943883 0.0040182583 0.0059650000 42399189 955859216 1373700096 -0.3581384718 -0.1260010153 -0.0031764864 1986 1311867784.8873779774 0.3588216603 0.3165869370 0.4404943883 0.0040172552 0.0058750000 42402061 955859216 1373700096 -0.3582898974 -0.1256619245 -0.0029817417 1987 1311867784.9173130989 0.3595532477 0.3166085607 0.4404943883 0.0040166463 0.0059120000 42404933 955859216 1373700096 -0.3588418961 -0.1263274103 -0.0031199206 1988 1311867784.9491391182 0.3592946231 0.3166300326 0.4404943883 0.0040159582 0.0059090000 42407749 955859216 1373700096 -0.3590696454 -0.1265003383 -0.0031275256 1989 1311867784.9848570824 0.3594765663 0.3166515743 0.4404943883 0.0040152517 0.0152090000 42410733 955859216 1373700096 -0.3594874442 -0.1263925880 -0.0029870041 1990 1311867785.0184569359 0.3595445156 0.3166731286 0.4404943883 0.0040143021 0.0077220000 42413605 955859216 1373700096 -0.3596079946 -0.1268051863 -0.0032010768 1991 1311867785.0500280857 0.3597682714 0.3166947735 0.4404943883 0.0040133972 0.0061750000 42416533 955859216 1373700096 -0.3600735068 -0.1269150376 -0.0031627365 1992 1311867785.0871460438 0.3599179685 0.3167164719 0.4404943883 0.0040124222 0.0057990000 42419517 955859216 1373700096 -0.3603803813 -0.1262281835 -0.0030308287 1993 1311867785.1168398857 0.3598057628 0.3167380923 0.4404943883 0.0040116774 0.0058360000 42422389 955859216 1373700096 -0.3604130745 -0.1262465119 -0.0032681827 1994 1311867785.1499750614 0.3602676094 0.3167599225 0.4404943883 0.0040108504 0.0058040000 42425205 955859216 1373700096 -0.3608118594 -0.1266826540 -0.0032215053 1995 1311867785.1850368977 0.3603664637 0.3167817804 0.4404943883 0.0040099218 0.0058510000 42428189 955859216 1373700096 -0.3610206842 -0.1257711500 -0.0032749057 1996 1311867785.2169620991 0.3603558540 0.3168036111 0.4404943883 0.0040090133 0.0104870000 42431005 955859216 1373700096 -0.3611560166 -0.1257792860 -0.0034505010 1997 1311867785.2491741180 0.3606891930 0.3168255869 0.4404943883 0.0040080595 0.0070520000 42433877 955859216 1373700096 -0.3615732193 -0.1258462071 -0.0033247757 1998 1311867785.2858769894 0.3606159985 0.3168475040 0.4404943883 0.0040072317 0.0059480000 42436917 955859216 1373700096 -0.3616465330 -0.1255336553 -0.0033898642 1999 1311867785.3214280605 0.3598297536 0.3168690059 0.4404943883 0.0040066513 0.0058800000 42440013 955859216 1373700096 -0.3612127900 -0.1254404485 -0.0036455274 2000 1311867785.3573219776 0.3598318398 0.3168904873 0.4404943883 0.0040061567 0.0058020000 42442941 955859216 1373700096 -0.3613487482 -0.1257266849 -0.0036589087 2001 1311867785.3893299103 0.3603486419 0.3169122055 0.4404943883 0.0040053752 0.0158800000 42445813 955859216 1373700096 -0.3621326089 -0.1253539771 -0.0035850506 2002 1311867785.4211249352 0.3598292768 0.3169336426 0.4404943883 0.0040046747 0.0078570000 42448685 955859216 1373700096 -0.3618597984 -0.1251902580 -0.0036741740 2003 1311867785.4570529461 0.3600459397 0.3169551665 0.4404943883 0.0040057310 0.0062120000 42451669 955859216 1373700096 -0.3621439338 -0.1257572025 -0.0037404862 2004 1311867785.4900350571 0.3603254259 0.3169768083 0.4404943883 0.0040051284 0.0057530000 42454597 955859216 1373700096 -0.3626931310 -0.1246422306 -0.0034616012 2005 1311867785.5211930275 0.3601123691 0.3169983223 0.4404943883 0.0040042286 0.0058340000 42457413 955859216 1373700096 -0.3629167974 -0.1244120151 -0.0034630254 2006 1311867785.5571260452 0.3589564562 0.3170192386 0.4404943883 0.0040047209 0.0057990000 42460397 955859216 1373700096 -0.3626224101 -0.1247749552 -0.0035698502 2007 1311867785.5891211033 0.3594081998 0.3170403592 0.4404943883 0.0040043772 0.0058080000 42463269 955859216 1373700096 -0.3633316159 -0.1246754229 -0.0033373521 2008 1311867785.6211590767 0.3577802479 0.3170606480 0.4404943883 0.0040170348 0.0110880000 42466197 955859216 1373700096 -0.3623540401 -0.1238904446 -0.0036827321 2009 1311867785.6570439339 0.3579213321 0.3170809868 0.4404943883 0.0040209302 0.0071120000 42469181 955859216 1373700096 -0.3626641333 -0.1244857311 -0.0037349428 2010 1311867785.6892280579 0.3584518731 0.3171015693 0.4404943883 0.0040201452 0.0060690000 42471997 955859216 1373700096 -0.3633105755 -0.1248776168 -0.0038111564 2011 1311867785.7214241028 0.3577460349 0.3171217804 0.4404943883 0.0040220310 0.0058840000 42474869 955859216 1373700096 -0.3630686700 -0.1242279112 -0.0039877258 2012 1311867785.7573668957 0.3576293588 0.3171419134 0.4404943883 0.0040215284 0.0058550000 42477853 955859216 1373700096 -0.3633694351 -0.1245014518 -0.0042412025 2013 1311867785.7892301083 0.3580126762 0.3171622168 0.4404943883 0.0040210954 0.0058900000 42480725 955859216 1373700096 -0.3639128208 -0.1249027550 -0.0041814237 2014 1311867785.8210389614 0.3583030999 0.3171826442 0.4404943883 0.0040202220 0.0059510000 42483597 955859216 1373700096 -0.3642220497 -0.1249752864 -0.0041321935 2015 1311867785.8574340343 0.3594374657 0.3172036144 0.4404943883 0.0040201440 0.0058910000 42486581 955859216 1373700096 -0.3656830788 -0.1248730123 -0.0040326416 2016 1311867785.8893110752 0.3595379889 0.3172246136 0.4404943883 0.0040192907 0.0058160000 42489509 955859216 1373700096 -0.3658065200 -0.1253597885 -0.0038826123 2017 1311867785.9211509228 0.3595473170 0.3172455966 0.4404943883 0.0040193875 0.0159770000 42492381 955859216 1373700096 -0.3662686646 -0.1246693283 -0.0037620976 2018 1311867785.9588449001 0.3599441946 0.3172667554 0.4404943883 0.0040199619 0.0079730000 42495365 955859216 1373700096 -0.3668071330 -0.1247308329 -0.0037060499 2019 1311867785.9892621040 0.3603191972 0.3172880791 0.4404943883 0.0040190124 0.0064720000 42498237 955859216 1373700096 -0.3675727546 -0.1245317087 -0.0035398828 2020 1311867786.0210618973 0.3599698842 0.3173092087 0.4404943883 0.0040182299 0.0058690000 42501109 955859216 1373700096 -0.3675777614 -0.1241953671 -0.0033651539 2021 1311867786.0572268963 0.3598343432 0.3173302503 0.4404943883 0.0040183634 0.0058770000 42504037 955859216 1373700096 -0.3680242002 -0.1244368926 -0.0032604756 2022 1311867786.0892500877 0.3602551520 0.3173514793 0.4404943883 0.0040177527 0.0059890000 42506965 955859216 1373700096 -0.3688161969 -0.1251885295 -0.0030791196 2023 1311867786.1211619377 0.3600284755 0.3173725751 0.4404943883 0.0040169718 0.0094350000 42509893 955859216 1373700096 -0.3691022098 -0.1248559505 -0.0028754384 2024 1311867786.1570990086 0.3598651290 0.3173935695 0.4404943883 0.0040160638 0.0068120000 42512821 955859216 1373700096 -0.3695441484 -0.1243399531 -0.0028972107 2025 1311867786.1891019344 0.3605589569 0.3174148857 0.4404943883 0.0040153291 0.0059870000 42515637 955859216 1373700096 -0.3707059622 -0.1252145618 -0.0027053414 2026 1311867786.2216470242 0.3603225052 0.3174360642 0.4404943883 0.0040144433 0.0103240000 42518509 955859216 1373700096 -0.3709992468 -0.1252654940 -0.0027106153 2027 1311867786.2570950985 0.3600972295 0.3174571107 0.4404943883 0.0040136312 0.0071030000 42521549 955859216 1373700096 -0.3713021576 -0.1248575076 -0.0026714064 2028 1311867786.2895779610 0.3604143262 0.3174782927 0.4404943883 0.0040132221 0.0060710000 42524365 955859216 1373700096 -0.3720147312 -0.1255176812 -0.0025311415 2029 1311867786.3211650848 0.3608253598 0.3174996565 0.4404943883 0.0040128929 0.0059480000 42527181 955859216 1373700096 -0.3725917339 -0.1258653849 -0.0025596751 2030 1311867786.3572299480 0.3603833318 0.3175207815 0.4404943883 0.0040120303 0.0092430000 42530221 955859216 1373700096 -0.3725099564 -0.1252617836 -0.0024837505 2031 1311867786.3891439438 0.3602921069 0.3175418407 0.4404943883 0.0040113443 0.0067930000 42533037 955859216 1373700096 -0.3727403283 -0.1257571876 -0.0023800773 2032 1311867786.4213869572 0.3603744209 0.3175629197 0.4404943883 0.0040107964 0.0099260000 42535965 955859216 1373700096 -0.3728641570 -0.1269042045 -0.0021144014 2033 1311867786.4573409557 0.3606796861 0.3175841282 0.4404943883 0.0040112037 0.0096680000 42538949 955859216 1373700096 -0.3734646738 -0.1263147593 -0.0019300045 2034 1311867786.4891700745 0.3603502512 0.3176051538 0.4404943883 0.0040113019 0.0068770000 42541765 955859216 1373700096 -0.3735740483 -0.1264888793 -0.0017026134 2035 1311867786.5218079090 0.3600786924 0.3176260253 0.4404943883 0.0040112558 0.0061320000 42544693 955859216 1373700096 -0.3735540509 -0.1273032129 -0.0015063648 2036 1311867786.5572519302 0.3601211309 0.3176468972 0.4404943883 0.0040104446 0.0059650000 42547677 955859216 1373700096 -0.3738982379 -0.1270967722 -0.0013399130 2037 1311867786.5895760059 0.3605874181 0.3176679774 0.4404943883 0.0040098714 0.0059670000 42550549 955859216 1373700096 -0.3749436140 -0.1271510124 -0.0011558868 2038 1311867786.6211080551 0.3612599075 0.3176893670 0.4404943883 0.0040099465 0.0059300000 42553421 955859216 1373700096 -0.3757906258 -0.1278083026 -0.0008428176 2039 1311867786.6573529243 0.3603413105 0.3177102851 0.4404943883 0.0040099752 0.0065170000 42556405 955859216 1373700096 -0.3750804961 -0.1279118359 -0.0008398501 2040 1311867786.6891629696 0.3606773615 0.3177313474 0.4404943883 0.0040091468 0.0059980000 42559221 955859216 1373700096 -0.3756895661 -0.1281599849 -0.0005637995 2041 1311867786.7210969925 0.3612165153 0.3177526532 0.4404943883 0.0040084237 0.0142000000 42562093 955859216 1373700096 -0.3765252233 -0.1285674870 -0.0003586727 2042 1311867786.7570719719 0.3605987728 0.3177736356 0.4404943883 0.0040079298 0.0076520000 42565021 955859216 1373700096 -0.3763245344 -0.1281064153 -0.0003894437 2043 1311867786.7892940044 0.3602443039 0.3177944240 0.4404943883 0.0040071046 0.0063110000 42567949 955859216 1373700096 -0.3762403429 -0.1273939162 -0.0002326580 2044 1311867786.8211419582 0.3605335951 0.3178153336 0.4404943883 0.0040062231 0.0059340000 42570821 955859216 1373700096 -0.3767677546 -0.1280831248 0.0001960472 2045 1311867786.8575630188 0.3599078059 0.3178359167 0.4404943883 0.0040068772 0.0059490000 42573749 955859216 1373700096 -0.3766601086 -0.1280816346 0.0005662776 2046 1311867786.8893759251 0.3599054217 0.3178564785 0.4404943883 0.0040083525 0.0059270000 42576677 955859216 1373700096 -0.3765350580 -0.1272998899 0.0009164003 2047 1311867786.9211881161 0.3598243594 0.3178769807 0.4404943883 0.0040103122 0.0061820000 42579549 955859216 1373700096 -0.3769670427 -0.1277629137 0.0012112488 2048 1311867786.9576020241 0.3599238694 0.3178975114 0.4404943883 0.0040093478 0.0125440000 42582589 955859216 1373700096 -0.3771159947 -0.1277845353 0.0014503741 2049 1311867786.9892089367 0.3586423993 0.3179173966 0.4404943883 0.0040095975 0.0077370000 42781957 955859216 1373700096 -0.3764775693 -0.1269917190 0.0015083196 2050 1311867787.0211400986 0.3595481217 0.3179377043 0.4404943883 0.0040087558 0.0063930000 43194485 955859216 1373700096 -0.3771279156 -0.1276712716 0.0016476115 2051 1311867787.0571250916 0.3596719205 0.3179580525 0.4404943883 0.0040079494 0.0109100000 43197525 955859216 1373700096 -0.3772999942 -0.1284049600 0.0020543658 2052 1311867787.0895950794 0.3592653573 0.3179781828 0.4404943883 0.0040072321 0.0071910000 43200341 955859216 1373700096 -0.3771931827 -0.1276025772 0.0021483907 2053 1311867787.1239550114 0.3594768643 0.3179983965 0.4404943883 0.0040068473 0.0061820000 43203269 955859216 1373700096 -0.3776426911 -0.1287928373 0.0022500074 2054 1311867787.1573429108 0.3595384657 0.3180186205 0.4404943883 0.0040069101 0.0061100000 43206197 955859216 1373700096 -0.3780097067 -0.1289775819 0.0022861529 2055 1311867787.1892991066 0.3588328362 0.3180384814 0.4404943883 0.0040060855 0.0098190000 43209069 955859216 1373700096 -0.3776467741 -0.1277691126 0.0023115145 2056 1311867787.2230238914 0.3587523401 0.3180582838 0.4404943883 0.0040055809 0.0070370000 43211997 955859216 1373700096 -0.3778121769 -0.1287024170 0.0024987683 2057 1311867787.2571809292 0.3591921031 0.3180782808 0.4404943883 0.0040054363 0.0061470000 43214925 955859216 1373700096 -0.3785565794 -0.1287190020 0.0026892340 2058 1311867787.2893400192 0.3586745560 0.3180980069 0.4404943883 0.0040045319 0.0060320000 43217797 955859216 1373700096 -0.3784451783 -0.1281704605 0.0028816042 2059 1311867787.3217399120 0.3588159084 0.3181177825 0.4404943883 0.0040043723 0.0060260000 43220669 955859216 1373700096 -0.3788839579 -0.1291527003 0.0028922351 2060 1311867787.3572421074 0.3595694602 0.3181379047 0.4404943883 0.0040044461 0.0100820000 43223653 955859216 1373700096 -0.3796135187 -0.1296319962 0.0029141202 2061 1311867787.3892920017 0.3582572341 0.3181573706 0.4404943883 0.0040036152 0.0099550000 43226525 955859216 1373700096 -0.3787921071 -0.1287152320 0.0026119130 2062 1311867787.4245440960 0.3585267067 0.3181769484 0.4404943883 0.0040031973 0.0070070000 43229453 955859216 1373700096 -0.3796032667 -0.1292469203 0.0024480629 2063 1311867787.4572229385 0.3587557375 0.3181966182 0.4404943883 0.0040024045 0.0061820000 43232381 955859216 1373700096 -0.3799504936 -0.1298620403 0.0024004860 2064 1311867787.4892969131 0.3584300280 0.3182161111 0.4404943883 0.0040015420 0.0059890000 43235197 955859216 1373700096 -0.3798898160 -0.1292082071 0.0022006850 2065 1311867787.5220890045 0.3587433696 0.3182357369 0.4404943883 0.0040006733 0.0060610000 43238069 955859216 1373700096 -0.3805767894 -0.1297096163 0.0021373192 2066 1311867787.5581040382 0.3592559099 0.3182555918 0.4404943883 0.0040002082 0.0101180000 43241053 955859216 1373700096 -0.3813058138 -0.1304843724 0.0018750965 2067 1311867787.5897688866 0.3577706218 0.3182747089 0.4404943883 0.0039997261 0.0072140000 43243981 955859216 1373700096 -0.3803427815 -0.1294674873 0.0014405134 2068 1311867787.6235499382 0.3575191796 0.3182936859 0.4404943883 0.0039990152 0.0062400000 43246853 955859216 1373700096 -0.3807207346 -0.1291408986 0.0013002711 2069 1311867787.6574609280 0.3582684398 0.3183130067 0.4404943883 0.0039981883 0.0065910000 43249781 955859216 1373700096 -0.3817434609 -0.1299668998 0.0011862756 2070 1311867787.6898610592 0.3581003845 0.3183322276 0.4404943883 0.0039976854 0.0105790000 43252709 955859216 1373700096 -0.3817747533 -0.1300140321 0.0009119524 2071 1311867787.7212240696 0.3577273488 0.3183512499 0.4404943883 0.0039969136 0.0072530000 43255581 955859216 1373700096 -0.3816761672 -0.1293085665 0.0007998073 2072 1311867787.7579810619 0.3571722806 0.3183699859 0.4404943883 0.0039970250 0.0061560000 43258565 955859216 1373700096 -0.3817276359 -0.1289978027 0.0006390894 2073 1311867787.7901558876 0.3572206795 0.3183887272 0.4404943883 0.0039962766 0.0060720000 43261437 955859216 1373700096 -0.3820845485 -0.1291408241 0.0004116703 2074 1311867787.8218519688 0.3560831845 0.3184069020 0.4404943883 0.0039963800 0.0061470000 43264365 955859216 1373700096 -0.3813123107 -0.1289698184 -0.0000397727 2075 1311867787.8573749065 0.3565604985 0.3184252893 0.4404943883 0.0039960472 0.0061390000 43267237 955859216 1373700096 -0.3821236491 -0.1295030415 -0.0000560378 2076 1311867787.8894400597 0.3566867709 0.3184437197 0.4404943883 0.0039952662 0.0126870000 43270165 955859216 1373700096 -0.3825034499 -0.1300765425 -0.0001968602 2077 1311867787.9214320183 0.3555323482 0.3184615765 0.4404943883 0.0039947713 0.0075860000 43273093 955859216 1373700096 -0.3818639815 -0.1295379400 -0.0006881930 2078 1311867787.9577279091 0.3556278944 0.3184794621 0.4404943883 0.0039941271 0.0099550000 43276021 955859216 1373700096 -0.3825644851 -0.1298408359 -0.0009401881 2079 1311867787.9892189503 0.3558102548 0.3184974182 0.4404943883 0.0039932740 0.0071180000 43278837 955859216 1373700096 -0.3831615746 -0.1301236153 -0.0011114173 2080 1311867788.0211091042 0.3557021320 0.3185153051 0.4404943883 0.0039929007 0.0062490000 43281765 955859216 1373700096 -0.3835634589 -0.1293341517 -0.0017690726 2081 1311867788.0577259064 0.3552554846 0.3185329602 0.4404943883 0.0039923163 0.0061510000 43284805 955859216 1373700096 -0.3837968111 -0.1287231892 -0.0019786244 2082 1311867788.0892241001 0.3556755781 0.3185508000 0.4404943883 0.0039920891 0.0060860000 43287621 955859216 1373700096 -0.3846714199 -0.1286924034 -0.0019117452 2083 1311867788.1307280064 0.3555540144 0.3185685644 0.4404943883 0.0039932243 0.0061460000 43290773 955859216 1373700096 -0.3852366209 -0.1285286248 -0.0019448980 2084 1311867788.1572849751 0.3557418585 0.3185864019 0.4404943883 0.0039924666 0.0061020000 43293533 955859216 1373700096 -0.3862025738 -0.1280450374 -0.0017188200 2085 1311867788.1904621124 0.3553389311 0.3186040290 0.4404943883 0.0039916576 0.0103100000 43296405 955859216 1373700096 -0.3867367804 -0.1278276294 -0.0016113718 2086 1311867788.2247180939 0.3543912768 0.3186211849 0.4404943883 0.0039909955 0.0099800000 43299333 955859216 1373700096 -0.3865193725 -0.1269122958 -0.0016818425 2087 1311867788.2583730221 0.3538176715 0.3186380496 0.4404943883 0.0039913447 0.0071290000 43302205 955859216 1373700096 -0.3867519796 -0.1262499988 -0.0015388554 2088 1311867788.2893440723 0.3536011577 0.3186547943 0.4404943883 0.0039915628 0.0103840000 43305077 955859216 1373700096 -0.3872062862 -0.1262954772 -0.0013094707 2089 1311867788.3251628876 0.3540649712 0.3186717451 0.4404943883 0.0039911860 0.0098870000 43308061 955859216 1373700096 -0.3882677853 -0.1261304170 -0.0008729963 2090 1311867788.3571081161 0.3537294269 0.3186885191 0.4404943883 0.0039907724 0.0070640000 43310933 955859216 1373700096 -0.3883873224 -0.1257353723 -0.0006433082 2091 1311867788.3910779953 0.3534230888 0.3187051306 0.4404943883 0.0039903487 0.0062350000 43313861 955859216 1373700096 -0.3888755441 -0.1256079674 -0.0002032955 2092 1311867788.4251430035 0.3549558520 0.3187224589 0.4404943883 0.0039898687 0.0062290000 43316789 955859216 1373700096 -0.3908587992 -0.1263834238 0.0001445860 2093 1311867788.4573140144 0.3539034724 0.3187392678 0.4404943883 0.0039893553 0.0062610000 43319661 955859216 1373700096 -0.3902839124 -0.1264274567 0.0001214484 2094 1311867788.4924380779 0.3548313677 0.3187565037 0.4404943883 0.0039886720 0.0062040000 43322589 955859216 1373700096 -0.3916678131 -0.1270754635 0.0005364068 2095 1311867788.5262899399 0.3543197513 0.3187734790 0.4404943883 0.0039879575 0.0061940000 43325517 955859216 1373700096 -0.3917858005 -0.1272867620 0.0006282062 2096 1311867788.5573079586 0.3547206521 0.3187906294 0.4404943883 0.0039877180 0.0096020000 43328389 955859216 1373700096 -0.3926635087 -0.1277672946 0.0005377510 2097 1311867788.5915369987 0.3549129963 0.3188078551 0.4404943883 0.0039869572 0.0073450000 43331317 955859216 1373700096 -0.3936560452 -0.1272518933 0.0003347289 2098 1311867788.6251940727 0.3555002809 0.3188253444 0.4404943883 0.0039863022 0.0062870000 43334189 955859216 1373700096 -0.3950455785 -0.1276976317 0.0004639539 2099 1311867788.6593029499 0.3549025953 0.3188425322 0.4404943883 0.0039855418 0.0062200000 43337117 955859216 1373700096 -0.3948892057 -0.1279298216 0.0002071322 2100 1311867788.6898009777 0.3549426794 0.3188597227 0.4404943883 0.0039849099 0.0061560000 43339989 955859216 1373700096 -0.3956635296 -0.1274195164 -0.0000613938 2101 1311867788.7262809277 0.3553960025 0.3188771127 0.4404943883 0.0039842526 0.0104730000 43343029 955859216 1373700096 -0.3969158232 -0.1281948835 -0.0002030976 2102 1311867788.7571070194 0.3545585275 0.3188940877 0.4404943883 0.0039834544 0.0071430000 43345901 955859216 1373700096 -0.3966709375 -0.1288169771 -0.0005442388 2103 1311867788.7899940014 0.3553037047 0.3189114008 0.4404943883 0.0039830740 0.0063690000 43348717 955859216 1373700096 -0.3980774283 -0.1283295453 -0.0008725443 2104 1311867788.8253190517 0.3555155694 0.3189287983 0.4404943883 0.0039830008 0.0061550000 43351757 955859216 1373700096 -0.3991280198 -0.1289974451 -0.0011308116 2105 1311867788.8572509289 0.3551043570 0.3189459838 0.4404943883 0.0039821843 0.0064560000 43354629 955859216 1373700096 -0.3992042542 -0.1297825575 -0.0014222650 2106 1311867788.8892900944 0.3556200564 0.3189633979 0.4404943883 0.0039819565 0.0062270000 43357445 955859216 1373700096 -0.4003294408 -0.1295783669 -0.0018663862 2107 1311867788.9253408909 0.3548332453 0.3189804220 0.4404943883 0.0039819714 0.0106350000 43360485 955859216 1373700096 -0.4005430043 -0.1293895245 -0.0020413927 2108 1311867788.9572029114 0.3557893634 0.3189978836 0.4404943883 0.0039817660 0.0072570000 43363357 955859216 1373700096 -0.4017933905 -0.1295675784 -0.0022104743 2109 1311867788.9914720058 0.3559269011 0.3190153938 0.4404943883 0.0039813417 0.0063840000 43366285 955859216 1373700096 -0.4027116895 -0.1299542487 -0.0022710788 2110 1311867789.0253350735 0.3558470309 0.3190328495 0.4404943883 0.0039808204 0.0061950000 43369157 955859216 1373700096 -0.4033070207 -0.1292741746 -0.0023440882 2111 1311867789.0572888851 0.3553292453 0.3190500435 0.4404943883 0.0039800293 0.0062950000 43372029 955859216 1373700096 -0.4034233093 -0.1286421269 -0.0023492058 2112 1311867789.0921590328 0.3551919162 0.3190671561 0.4404943883 0.0039798824 0.0062750000 43375013 955859216 1373700096 -0.4040068388 -0.1287837178 -0.0022442804 2113 1311867789.1266920567 0.3545635641 0.3190839551 0.4404943883 0.0039793583 0.0061770000 43377997 955859216 1373700096 -0.4039792717 -0.1283221394 -0.0021433108 2114 1311867789.1574180126 0.3553019464 0.3191010876 0.4404943883 0.0039793595 0.0061600000 43380757 955859216 1373700096 -0.4049007893 -0.1286437362 -0.0021916421 2115 1311867789.1895699501 0.3569819331 0.3191189982 0.4404943883 0.0039784821 0.0062210000 43383685 955859216 1373700096 -0.4069111645 -0.1294183880 -0.0022089276 2116 1311867789.2251811028 0.3557486236 0.3191363089 0.4404943883 0.0039777973 0.0063730000 43386669 955859216 1373700096 -0.4062370360 -0.1295678467 -0.0022575394 2117 1311867789.2573940754 0.3560121357 0.3191537278 0.4404943883 0.0039779489 0.0062830000 43389485 955859216 1373700096 -0.4070676863 -0.1293692440 -0.0023621705 2118 1311867789.2926049232 0.3572783470 0.3191717281 0.4404943883 0.0039771688 0.0062500000 43392469 955859216 1373700096 -0.4090326726 -0.1297409981 -0.0026917816 2119 1311867789.3252000809 0.3574386835 0.3191897871 0.4404943883 0.0039763739 0.0145770000 43395397 955859216 1373700096 -0.4097443223 -0.1304793805 -0.0028431246 2120 1311867789.3589100838 0.3564557433 0.3192073654 0.4404943883 0.0039756039 0.0078300000 43398269 955859216 1373700096 -0.4094549716 -0.1305569112 -0.0032574229 2121 1311867789.3897531033 0.3575768173 0.3192254557 0.4404943883 0.0039753916 0.0065150000 43401141 955859216 1373700096 -0.4112856686 -0.1302258372 -0.0036445502 2122 1311867789.4252359867 0.3576507270 0.3192435637 0.4404943883 0.0039749381 0.0063130000 43404125 955859216 1373700096 -0.4121122658 -0.1305096596 -0.0039549195 2123 1311867789.4577910900 0.3572539389 0.3192614678 0.4404943883 0.0039742803 0.0063210000 43406941 955859216 1373700096 -0.4123960137 -0.1311402023 -0.0042075329 2124 1311867789.4892559052 0.3587627709 0.3192800654 0.4404943883 0.0039740142 0.0062840000 43409869 955859216 1373700096 -0.4145073891 -0.1308907270 -0.0045449813 2125 1311867789.5256059170 0.3594243228 0.3192989568 0.4404943883 0.0039738187 0.0062850000 43412797 955859216 1373700096 -0.4159015119 -0.1311194003 -0.0047299052 2126 1311867789.5572779179 0.3592332602 0.3193177406 0.4404943883 0.0039731591 0.0062690000 43415669 955859216 1373700096 -0.4165543318 -0.1312135011 -0.0048965751 2127 1311867789.5892720222 0.3593422472 0.3193365579 0.4404943883 0.0039723248 0.0099220000 43418485 955859216 1373700096 -0.4172922671 -0.1315319389 -0.0049590110 2128 1311867789.6253700256 0.3597624004 0.3193555550 0.4404943883 0.0039718180 0.0078100000 43421525 955859216 1373700096 -0.4185691774 -0.1309194714 -0.0052787433 2129 1311867789.6574499607 0.3595750332 0.3193744463 0.4404943883 0.0039711499 0.0064470000 43424397 955859216 1373700096 -0.4192113578 -0.1301635355 -0.0055386107 2130 1311867789.6894960403 0.3593074083 0.3193931942 0.4404943883 0.0039704011 0.0063830000 43427213 955859216 1373700096 -0.4197888076 -0.1297039390 -0.0055267122 2131 1311867789.7253561020 0.3585318923 0.3194115605 0.4404943883 0.0039722775 0.0064210000 43430197 955859216 1373700096 -0.4198881090 -0.1284436882 -0.0059797075 2132 1311867789.7572269440 0.3573350012 0.3194293482 0.4404943883 0.0039717104 0.0063670000 43433069 955859216 1373700096 -0.4195996523 -0.1271875501 -0.0062231715 2133 1311867789.7893610001 0.3564611673 0.3194467096 0.4404943883 0.0039715636 0.0065830000 43435941 955859216 1373700096 -0.4194817245 -0.1264931113 -0.0063043898 2134 1311867789.8253350258 0.3576461375 0.3194646100 0.4404943883 0.0039710772 0.0063830000 43438925 955859216 1373700096 -0.4211061597 -0.1265625656 -0.0064021922 2135 1311867789.8573670387 0.3571894467 0.3194822797 0.4404943883 0.0039704246 0.0064300000 43441853 955859216 1373700096 -0.4210898578 -0.1266438663 -0.0063578840 2136 1311867789.8893530369 0.3556404710 0.3194992077 0.4404943883 0.0039697749 0.0063770000 43444669 955859216 1373700096 -0.4203979969 -0.1263170391 -0.0063949013 2137 1311867789.9253480434 0.3564086556 0.3195164793 0.4404943883 0.0039688913 0.0063720000 43447653 955859216 1373700096 -0.4221059382 -0.1261399984 -0.0062251482 2138 1311867789.9573481083 0.3567160368 0.3195338786 0.4404943883 0.0039688112 0.0063500000 43450469 955859216 1373700096 -0.4232595265 -0.1259595156 -0.0061680027 2139 1311867789.9892580509 0.3566672206 0.3195512387 0.4404943883 0.0039690168 0.0065360000 43453341 955859216 1373700096 -0.4237598777 -0.1259295344 -0.0063092876 2140 1311867790.0253860950 0.3560268283 0.3195682834 0.4404943883 0.0039683254 0.0149920000 43456381 955859216 1373700096 -0.4240844846 -0.1254646927 -0.0062149279 2141 1311867790.0572309494 0.3559109271 0.3195852580 0.4404943883 0.0039675389 0.0079410000 43459197 955859216 1373700096 -0.4247184098 -0.1249392033 -0.0062626996 2142 1311867790.0896899700 0.3560975492 0.3196023039 0.4404943883 0.0039674908 0.0104340000 43462125 955859216 1373700096 -0.4254210889 -0.1248771250 -0.0061186440 2143 1311867790.1257700920 0.3560235798 0.3196192993 0.4404943883 0.0039671351 0.0073270000 43465109 955859216 1373700096 -0.4261417687 -0.1241878197 -0.0061318232 2144 1311867790.1572160721 0.3552555442 0.3196359207 0.4404943883 0.0039667221 0.0064130000 43467925 955859216 1373700096 -0.4260435700 -0.1239720657 -0.0059857136 2145 1311867790.1894400120 0.3559224010 0.3196528375 0.4404943883 0.0039660715 0.0064540000 43470853 955859216 1373700096 -0.4272544682 -0.1236092746 -0.0060105510 2146 1311867790.2254109383 0.3568248749 0.3196701590 0.4404943883 0.0039664266 0.0063340000 43473837 955859216 1373700096 -0.4286851883 -0.1236322597 -0.0055734385 2147 1311867790.2576739788 0.3562109768 0.3196871785 0.4404943883 0.0039658433 0.0063690000 43476765 955859216 1373700096 -0.4287782013 -0.1233642548 -0.0054444680 2148 1311867790.2894508839 0.3562840819 0.3197042162 0.4404943883 0.0039659232 0.0063170000 43479581 955859216 1373700096 -0.4292619824 -0.1232577413 -0.0055446140 2149 1311867790.3254859447 0.3581958711 0.3197221276 0.4404943883 0.0039668183 0.0063550000 43482565 955859216 1373700096 -0.4317540526 -0.1233450845 -0.0052654087 2150 1311867790.3573629856 0.3574011028 0.3197396527 0.4404943883 0.0039673242 0.0064390000 43485437 955859216 1373700096 -0.4314602911 -0.1230522692 -0.0053562797 2151 1311867790.3896288872 0.3573174775 0.3197571226 0.4404943883 0.0039667755 0.0064250000 43488309 955859216 1373700096 -0.4319537878 -0.1232468635 -0.0054501705 2152 1311867790.4259679317 0.3573798537 0.3197746053 0.4404943883 0.0039688730 0.0109760000 43491349 955859216 1373700096 -0.4323521554 -0.1229934990 -0.0057384511 2153 1311867790.4603750706 0.3587087989 0.3197926890 0.4404943883 0.0039700252 0.0074710000 43494277 955859216 1373700096 -0.4344497323 -0.1228129715 -0.0057541328 2154 1311867790.4893760681 0.3589971066 0.3198108898 0.4404943883 0.0039693393 0.0064040000 43497037 955859216 1373700096 -0.4351682663 -0.1229627654 -0.0055184113 2155 1311867790.5260839462 0.3591229916 0.3198291320 0.4404943883 0.0039699112 0.0103550000 43500021 955859216 1373700096 -0.4357752800 -0.1220889390 -0.0058360980 2156 1311867790.5578188896 0.3588705659 0.3198472403 0.4404943883 0.0039707430 0.0072200000 43502837 955859216 1373700096 -0.4359426498 -0.1214845106 -0.0057923798 2157 1311867790.5941619873 0.3596669436 0.3198657010 0.4404943883 0.0039733081 0.0064930000 43505821 955859216 1373700096 -0.4368906319 -0.1216357648 -0.0057699648 2158 1311867790.6255199909 0.3598715365 0.3198842394 0.4404943883 0.0039730649 0.0068450000 43508749 955859216 1373700096 -0.4377658367 -0.1218401566 -0.0059302119 2159 1311867790.6573970318 0.3607402444 0.3199031630 0.4404943883 0.0039742100 0.0106320000 43511509 955859216 1373700096 -0.4393233657 -0.1219434664 -0.0061111315 2160 1311867790.6901810169 0.3614127934 0.3199223804 0.4404943883 0.0039739642 0.0073780000 43514437 955859216 1373700096 -0.4406109154 -0.1220310926 -0.0060458821 2161 1311867790.7253530025 0.3611013889 0.3199414359 0.4404943883 0.0039734047 0.0065500000 43517365 955859216 1373700096 -0.4409352839 -0.1216830909 -0.0062209712 2162 1311867790.7575750351 0.3594987094 0.3199597325 0.4404943883 0.0039729998 0.0065600000 43520237 955859216 1373700096 -0.4399595261 -0.1211971119 -0.0064077000 2163 1311867790.7912769318 0.3601329625 0.3199783055 0.4404943883 0.0039746633 0.0105880000 43523165 955859216 1373700096 -0.4411161542 -0.1203598157 -0.0064180987 2164 1311867790.8261909485 0.3593090773 0.3199964805 0.4404943883 0.0039741094 0.0074510000 43526149 955859216 1373700096 -0.4409616292 -0.1191589683 -0.0064519737 2165 1311867790.8573698997 0.3584848940 0.3200142580 0.4404943883 0.0039734651 0.0065760000 43529021 955859216 1373700096 -0.4405175447 -0.1188663393 -0.0063897264 2166 1311867790.8950428963 0.3590506613 0.3200322804 0.4404943883 0.0039734162 0.0102600000 43532005 955859216 1373700096 -0.4413871765 -0.1182034612 -0.0060198684 2167 1311867790.9258179665 0.3584945202 0.3200500295 0.4404943883 0.0039731239 0.0075190000 43534877 955859216 1373700096 -0.4411710203 -0.1170946285 -0.0061574643 2168 1311867790.9607090950 0.3576347828 0.3200673656 0.4404943883 0.0039731903 0.0106930000 43537805 955859216 1373700096 -0.4410158694 -0.1162505448 -0.0062009422 2169 1311867790.9944651127 0.3576241136 0.3200846808 0.4404943883 0.0039731746 0.0074630000 43540733 955859216 1373700096 -0.4414057732 -0.1158530563 -0.0057674348 2170 1311867791.0299000740 0.3573192954 0.3201018396 0.4404943883 0.0039732882 0.0064960000 43543717 955859216 1373700096 -0.4413734972 -0.1157058403 -0.0056480770 2171 1311867791.0577330589 0.3567745686 0.3201187317 0.4404943883 0.0039728707 0.0064530000 43546365 955859216 1373700096 -0.4414583445 -0.1150076166 -0.0057776594 2172 1311867791.0913140774 0.3573906720 0.3201358919 0.4404943883 0.0039722365 0.0064120000 43549349 955859216 1373700096 -0.4423272908 -0.1151060462 -0.0057637757 2173 1311867791.1254060268 0.3565980792 0.3201526716 0.4404943883 0.0039735975 0.0065560000 43552277 955859216 1373700096 -0.4420752227 -0.1144240797 -0.0057846620 2174 1311867791.1664540768 0.3557028472 0.3201690240 0.4404943883 0.0039747864 0.0103320000 43555429 955859216 1373700096 -0.4418366253 -0.1133233905 -0.0059115114 2175 1311867791.1905651093 0.3558053672 0.3201854085 0.4404943883 0.0039753032 0.0075940000 43558077 955859216 1373700096 -0.4422339499 -0.1127536073 -0.0059063993 2176 1311867791.2257969379 0.3586985469 0.3202031076 0.4404943883 0.0039761849 0.0064650000 43561061 955859216 1373700096 -0.4454948902 -0.1137990877 -0.0057227821 2177 1311867791.2579009533 0.3586429358 0.3202207648 0.4404943883 0.0039765028 0.0064450000 43563877 955859216 1373700096 -0.4461607933 -0.1143905073 -0.0056545748 2178 1311867791.2920219898 0.3605096936 0.3202392630 0.4404943883 0.0039760046 0.0108340000 43566805 955859216 1373700096 -0.4485025108 -0.1147876158 -0.0053825327 2179 1311867791.3277790546 0.3593468368 0.3202572105 0.4404943883 0.0039771044 0.0075490000 43569789 955859216 1373700096 -0.4477018714 -0.1149032190 -0.0054995674 2180 1311867791.3597049713 0.3602911532 0.3202755747 0.4404943883 0.0039783119 0.0064820000 43572717 955859216 1373700096 -0.4493712783 -0.1150244996 -0.0056227604 2181 1311867791.3896780014 0.3600596488 0.3202938159 0.4404943883 0.0039776227 0.0064990000 43575533 955859216 1373700096 -0.4497610331 -0.1149225533 -0.0056595765 2182 1311867791.4270040989 0.3604910374 0.3203122380 0.4404943883 0.0039779522 0.0065180000 43578573 955859216 1373700096 -0.4510901868 -0.1144990176 -0.0054892153 2183 1311867791.4574470520 0.3617068827 0.3203312003 0.4404943883 0.0039773498 0.0065330000 43581389 955859216 1373700096 -0.4528744221 -0.1146550626 -0.0052009625 2184 1311867791.4916520119 0.3625210822 0.3203505180 0.4404943883 0.0039805299 0.0102440000 43584317 955859216 1373700096 -0.4542237222 -0.1143021882 -0.0050843256 2185 1311867791.5275359154 0.3612244129 0.3203692246 0.4404943883 0.0039799035 0.0074390000 43587301 955859216 1373700096 -0.4533971548 -0.1142529100 -0.0050934171 2186 1311867791.5593819618 0.3616428673 0.3203881055 0.4404943883 0.0039809960 0.0064300000 43590173 955859216 1373700096 -0.4542341232 -0.1146239117 -0.0049033039 2187 1311867791.5894811153 0.3603517413 0.3204063788 0.4404943883 0.0039804323 0.0065230000 43592989 955859216 1373700096 -0.4535225034 -0.1135985181 -0.0049662502 2188 1311867791.6275899410 0.3599514961 0.3204244524 0.4404943883 0.0039801004 0.0101660000 43596029 955859216 1373700096 -0.4536091387 -0.1132148802 -0.0051498953 2189 1311867791.6574349403 0.3605886996 0.3204428006 0.4404943883 0.0039798854 0.0073780000 43598901 955859216 1373700096 -0.4544724226 -0.1130146980 -0.0051417933 2190 1311867791.6894969940 0.3616951108 0.3204616373 0.4404943883 0.0039793861 0.0064270000 43601717 955859216 1373700096 -0.4557398856 -0.1136056632 -0.0051183156 2191 1311867791.7263259888 0.3636291921 0.3204813395 0.4404943883 0.0039790152 0.0114790000 43604757 955859216 1373700096 -0.4578061700 -0.1139269993 -0.0049528908 2192 1311867791.7602820396 0.3623110652 0.3205004224 0.4404943883 0.0039782972 0.0078150000 43607685 955859216 1373700096 -0.4566921294 -0.1140798628 -0.0050920635 2193 1311867791.7897930145 0.3604921699 0.3205186585 0.4404943883 0.0039779650 0.0066290000 43610501 955859216 1373700096 -0.4550018609 -0.1134510115 -0.0051016128 2194 1311867791.8265190125 0.3622139394 0.3205376628 0.4404943883 0.0039785370 0.0063940000 43613485 955859216 1373700096 -0.4568847418 -0.1135335788 -0.0051229261 2195 1311867791.8574469090 0.3618126512 0.3205564668 0.4404943883 0.0039783656 0.0113720000 43616357 955859216 1373700096 -0.4567347765 -0.1130106971 -0.0050307116 2196 1311867791.8895421028 0.3618245423 0.3205752592 0.4404943883 0.0039775263 0.0074380000 43619173 955859216 1373700096 -0.4569443166 -0.1129856408 -0.0053432812 2197 1311867791.9276258945 0.3633714914 0.3205947386 0.4404943883 0.0039774284 0.0065020000 43622213 955859216 1373700096 -0.4586339295 -0.1132681891 -0.0053427313 2198 1311867791.9574968815 0.3620726168 0.3206136094 0.4404943883 0.0039770579 0.0064860000 43625029 955859216 1373700096 -0.4577908516 -0.1125181392 -0.0054554148 2199 1311867791.9918000698 0.3619420826 0.3206324036 0.4404943883 0.0039762750 0.0064860000 43627845 955859216 1373700096 -0.4577712417 -0.1126546338 -0.0052869283 2200 1311867792.0277240276 0.3644190431 0.3206523066 0.4404943883 0.0039770892 0.0064360000 43630773 955859216 1373700096 -0.4603795111 -0.1130588427 -0.0052386173 2201 1311867792.0615789890 0.3643251061 0.3206721488 0.4404943883 0.0039764459 0.0107730000 43633813 955859216 1373700096 -0.4607094824 -0.1131896228 -0.0051658452 2202 1311867792.0946090221 0.3646646142 0.3206921273 0.4404943883 0.0039759541 0.0074890000 43636629 955859216 1373700096 -0.4612301290 -0.1131357625 -0.0053387382 2203 1311867792.1256630421 0.3660570681 0.3207127196 0.4404943883 0.0039758692 0.0066120000 43639501 955859216 1373700096 -0.4628577828 -0.1130447015 -0.0054869112 2204 1311867792.1595768929 0.3651132286 0.3207328650 0.4404943883 0.0039756906 0.0102350000 43642429 955859216 1373700096 -0.4625682235 -0.1118810251 -0.0054827239 2205 1311867792.1948819160 0.3640118539 0.3207524927 0.4404943883 0.0039799134 0.0076190000 43645413 955859216 1373700096 -0.4618504345 -0.1122695804 -0.0054012178 2206 1311867792.2253580093 0.3652250171 0.3207726525 0.4404943883 0.0039870411 0.0067510000 43648229 955859216 1373700096 -0.4637268186 -0.1118969396 -0.0056853462 2207 1311867792.2575860023 0.3657214046 0.3207930189 0.4404943883 0.0039861852 0.0065760000 43651101 955859216 1373700096 -0.4648002982 -0.1114143208 -0.0056658746 2208 1311867792.2995440960 0.3655216992 0.3208132765 0.4404943883 0.0039856329 0.0065620000 43654253 955859216 1373700096 -0.4652613699 -0.1113747209 -0.0057498394 2209 1311867792.3314530849 0.3655152619 0.3208335128 0.4404943883 0.0039854586 0.0068370000 43657125 955859216 1373700096 -0.4657522440 -0.1110981032 -0.0056401738 2210 1311867792.3589100838 0.3660196662 0.3208539590 0.4404943883 0.0039849050 0.0065910000 43659829 955859216 1373700096 -0.4665419757 -0.1112897098 -0.0057629566 2211 1311867792.3954761028 0.3658344150 0.3208743030 0.4404943883 0.0039841589 0.0065620000 43662869 955859216 1373700096 -0.4669102728 -0.1110859588 -0.0061631771 2212 1311867792.4281890392 0.3640290499 0.3208938123 0.4404943883 0.0039837822 0.0065810000 43665741 955859216 1373700096 -0.4656938016 -0.1109685004 -0.0066302121 2213 1311867792.4589219093 0.3648530543 0.3209136764 0.4404943883 0.0039835749 0.0066150000 43668557 955859216 1373700096 -0.4667842984 -0.1113336161 -0.0067675686 2214 1311867792.4948880672 0.3652626574 0.3209337076 0.4404943883 0.0039833514 0.0065530000 43671541 955859216 1373700096 -0.4676647186 -0.1113628596 -0.0067640212 2215 1311867792.5256149769 0.3648779094 0.3209535470 0.4404943883 0.0039827459 0.0065720000 43674413 955859216 1373700096 -0.4675959647 -0.1111289486 -0.0069061294 2216 1311867792.5579619408 0.3654268086 0.3209736161 0.4404943883 0.0039821513 0.0073400000 43677229 955859216 1373700096 -0.4685928822 -0.1108662188 -0.0069533410 2217 1311867792.5937440395 0.3655380011 0.3209937173 0.4404943883 0.0039815046 0.0066680000 43680157 955859216 1373700096 -0.4688054621 -0.1112675741 -0.0068888105 2218 1311867792.6254990101 0.3644681573 0.3210133181 0.4404943883 0.0039811408 0.0136640000 43682973 955859216 1373700096 -0.4683496058 -0.1108865216 -0.0071757995 2219 1311867792.6587610245 0.3630053699 0.3210322419 0.4404943883 0.0039807203 0.0079630000 43685901 955859216 1373700096 -0.4673305154 -0.1102932170 -0.0073275259 2220 1311867792.6947619915 0.3628731966 0.3210510892 0.4404943883 0.0039802133 0.0067330000 43688885 955859216 1373700096 -0.4676158726 -0.1105370447 -0.0073264316 2221 1311867792.7254660130 0.3627172709 0.3210698493 0.4404943883 0.0039800593 0.0065180000 43691757 955859216 1373700096 -0.4673893750 -0.1108998135 -0.0074402224 2222 1311867792.7574810982 0.3632435799 0.3210888294 0.4404943883 0.0039792201 0.0064690000 43694629 955859216 1373700096 -0.4684318304 -0.1111772358 -0.0073289867 2223 1311867792.7968890667 0.3622153997 0.3211073299 0.4404943883 0.0039802901 0.0064700000 43697725 955859216 1373700096 -0.4678575695 -0.1114150807 -0.0074728006 2224 1311867792.8254449368 0.3634446561 0.3211263664 0.4404943883 0.0039801963 0.0105580000 43700429 955859216 1373700096 -0.4693556726 -0.1116560623 -0.0072628874 2225 1311867792.8578031063 0.3632657826 0.3211453055 0.4404943883 0.0039800594 0.0074490000 43703301 955859216 1373700096 -0.4698999524 -0.1111093536 -0.0071526933 2226 1311867792.8974819183 0.3601206541 0.3211628146 0.4404943883 0.0039799163 0.0065900000 43706453 955859216 1373700096 -0.4675364196 -0.1108822301 -0.0075142724 2227 1311867792.9254279137 0.3601583838 0.3211803250 0.4404943883 0.0039793321 0.0113960000 43709157 955859216 1373700096 -0.4679357708 -0.1107789129 -0.0074835052 2228 1311867792.9580180645 0.3610245883 0.3211982084 0.4404943883 0.0039794839 0.0076210000 43712085 955859216 1373700096 -0.4690835476 -0.1105071828 -0.0077481214 2229 1311867792.9958879948 0.3613543808 0.3212162238 0.4404943883 0.0039791062 0.0112380000 43715125 955859216 1373700096 -0.4704640210 -0.1105331779 -0.0074519450 2230 1311867793.0254249573 0.3598747253 0.3212335594 0.4404943883 0.0039786390 0.0077000000 43717885 955859216 1373700096 -0.4696681798 -0.1103871465 -0.0074819005 2231 1311867793.0575890541 0.3584676087 0.3212502488 0.4404943883 0.0039784139 0.0065590000 43720757 955859216 1373700096 -0.4692610800 -0.1096717119 -0.0075570615 2232 1311867793.0956139565 0.3610808551 0.3212680941 0.4404943883 0.0039776276 0.0066290000 43723853 955859216 1373700096 -0.4727734327 -0.1093813032 -0.0070675500 2233 1311867793.1253910065 0.3603064418 0.3212855765 0.4404943883 0.0039771034 0.0065720000 43726613 955859216 1373700096 -0.4724777639 -0.1094616205 -0.0070628910 2234 1311867793.1573770046 0.3611860573 0.3213034371 0.4404943883 0.0039766890 0.0065370000 43729485 955859216 1373700096 -0.4739412367 -0.1092663780 -0.0068374421 2235 1311867793.1934790611 0.3601045310 0.3213207977 0.4404943883 0.0039763002 0.0065320000 43732469 955859216 1373700096 -0.4734898806 -0.1088661328 -0.0065846085 2236 1311867793.2255470753 0.3598342836 0.3213380220 0.4404943883 0.0039757203 0.0065140000 43735341 955859216 1373700096 -0.4736989439 -0.1086506695 -0.0064521376 2237 1311867793.2574770451 0.3607921898 0.3213556591 0.4404943883 0.0039749204 0.0102310000 43738157 955859216 1373700096 -0.4749598801 -0.1089951918 -0.0061043333 2238 1311867793.2951428890 0.3601726294 0.3213730036 0.4404943883 0.0039744178 0.0073440000 43741253 955859216 1373700096 -0.4751144648 -0.1088448092 -0.0060317661 2239 1311867793.3254458904 0.3613531590 0.3213908599 0.4404943883 0.0039737037 0.0065170000 43744069 955859216 1373700096 -0.4766117036 -0.1088353992 -0.0053584753 2240 1311867793.3620529175 0.3598346114 0.3214080222 0.4404943883 0.0039734948 0.0064830000 43747109 955859216 1373700096 -0.4757598341 -0.1079738811 -0.0054130848 2241 1311867793.3934969902 0.3569673598 0.3214238899 0.4404943883 0.0039737521 0.0064880000 43749925 955859216 1373700096 -0.4735563993 -0.1072840691 -0.0055741346 2242 1311867793.4254410267 0.3553157151 0.3214390067 0.4404943883 0.0039735459 0.0111560000 43752797 955859216 1373700096 -0.4724661112 -0.1067002863 -0.0054992232 2243 1311867793.4615969658 0.3532881141 0.3214532060 0.4404943883 0.0039736938 0.0103700000 43755781 955859216 1373700096 -0.4707762003 -0.1064039171 -0.0051573762 2244 1311867793.4961650372 0.3507663906 0.3214662689 0.4404943883 0.0039734710 0.0073760000 43758597 955859216 1373700096 -0.4686752856 -0.1059780940 -0.0052562524 2245 1311867793.5258960724 0.3494412601 0.3214787299 0.4404943883 0.0039729819 0.0074880000 43761413 955859216 1373700096 -0.4676469564 -0.1059652567 -0.0048837857 2246 1311867793.5653350353 0.3481400013 0.3214906005 0.4404943883 0.0039726197 0.0116400000 43764509 955859216 1373700096 -0.4667116702 -0.1056900173 -0.0048772697 2247 1311867793.5951368809 0.3462814987 0.3215016334 0.4404943883 0.0039728786 0.0076840000 43767213 955859216 1373700096 -0.4649882615 -0.1049829423 -0.0049534407 2248 1311867793.6255569458 0.3455672860 0.3215123387 0.4404943883 0.0039728895 0.0112770000 43770085 955859216 1373700096 -0.4645695984 -0.1049722657 -0.0047388440 2249 1311867793.6641399860 0.3446387053 0.3215226217 0.4404943883 0.0039729074 0.0104290000 43773069 955859216 1373700096 -0.4639820158 -0.1048222482 -0.0047332370 2250 1311867793.6930859089 0.3434778750 0.3215323796 0.4404943883 0.0039749267 0.0074450000 43775885 955859216 1373700096 -0.4633764625 -0.1039353758 -0.0050145518 2251 1311867793.7268340588 0.3419110775 0.3215414328 0.4404943883 0.0039752183 0.0066490000 43778869 955859216 1373700096 -0.4620575607 -0.1038343906 -0.0051494264 2252 1311867793.7666549683 0.3397862017 0.3215495343 0.4404943883 0.0039746929 0.0065230000 43781909 955859216 1373700096 -0.4606262147 -0.1037426963 -0.0056708544 2253 1311867793.7944359779 0.3385899961 0.3215570978 0.4404943883 0.0039752838 0.0065550000 43784613 955859216 1373700096 -0.4596648216 -0.1034196019 -0.0061273035 2254 1311867793.8265230656 0.3381853402 0.3215644750 0.4404943883 0.0039747792 0.0064960000 43787541 955859216 1373700096 -0.4598331451 -0.1028345004 -0.0064421715 2255 1311867793.8667359352 0.3382778466 0.3215718867 0.4404943883 0.0039746015 0.0064930000 43790693 955859216 1373700096 -0.4603229463 -0.1028341204 -0.0063821673 2256 1311867793.8930900097 0.3385903835 0.3215794304 0.4404943883 0.0039738692 0.0064460000 43793397 955859216 1373700096 -0.4608928859 -0.1033202484 -0.0062486515 2257 1311867793.9269030094 0.3378067911 0.3215866202 0.4404943883 0.0039731244 0.0064940000 43796325 955859216 1373700096 -0.4606882036 -0.1031017601 -0.0064886869 2258 1311867793.9623370171 0.3376457095 0.3215937322 0.4404943883 0.0039723219 0.0064670000 43799197 955859216 1373700096 -0.4610133767 -0.1032380089 -0.0066654403 2259 1311867793.9955279827 0.3379240036 0.3216009612 0.4404943883 0.0039720487 0.0066560000 43802181 955859216 1373700096 -0.4618251622 -0.1028834060 -0.0069786943 2260 1311867794.0277070999 0.3371720016 0.3216078511 0.4404943883 0.0039721451 0.0065140000 43805053 955859216 1373700096 -0.4617055058 -0.1021730825 -0.0070060422 2261 1311867794.0608921051 0.3363018334 0.3216143499 0.4404943883 0.0039714023 0.0112590000 43807925 955859216 1373700096 -0.4611743391 -0.1014603078 -0.0072196922 2262 1311867794.0951509476 0.3362287581 0.3216208108 0.4404943883 0.0039706795 0.0104890000 43810853 955859216 1373700096 -0.4613327682 -0.1007965058 -0.0072771902 2263 1311867794.1269369125 0.3363653123 0.3216273262 0.4404943883 0.0039715160 0.0074350000 43813781 955859216 1373700096 -0.4616067708 -0.1002745554 -0.0072724898 2264 1311867794.1632831097 0.3350760639 0.3216332665 0.4404943883 0.0039719779 0.0066270000 43816765 955859216 1373700096 -0.4607994556 -0.0988756642 -0.0075288303 2265 1311867794.1936271191 0.3358326852 0.3216395356 0.4404943883 0.0039723933 0.0065320000 43819525 955859216 1373700096 -0.4616167545 -0.0981686115 -0.0074269408 2266 1311867794.2258520126 0.3359047771 0.3216458309 0.4404943883 0.0039716286 0.0065720000 43822397 955859216 1373700096 -0.4619963467 -0.0975886509 -0.0071526128 2267 1311867794.2619779110 0.3364953995 0.3216523812 0.4404943883 0.0039710736 0.0106240000 43825381 955859216 1373700096 -0.4628093839 -0.0969180316 -0.0070757600 2268 1311867794.2955250740 0.3363714814 0.3216588711 0.4404943883 0.0039707121 0.0075390000 43828253 955859216 1373700096 -0.4628360271 -0.0960397571 -0.0071006939 2269 1311867794.3254759312 0.3367863595 0.3216655382 0.4404943883 0.0039702110 0.0066360000 43831069 955859216 1373700096 -0.4636043608 -0.0948663428 -0.0066045742 2270 1311867794.3628959656 0.3371388018 0.3216723546 0.4404943883 0.0039712302 0.0065540000 43834109 955859216 1373700096 -0.4643714428 -0.0935565308 -0.0065262071 2271 1311867794.3958311081 0.3373124003 0.3216792414 0.4404943883 0.0039706057 0.0065600000 43837037 955859216 1373700096 -0.4648746848 -0.0929534435 -0.0062415106 2272 1311867794.4267809391 0.3372820318 0.3216861088 0.4404943883 0.0039701592 0.0066590000 43839909 955859216 1373700096 -0.4651132524 -0.0924207494 -0.0063990387 2273 1311867794.4620559216 0.3373528123 0.3216930014 0.4404943883 0.0039693483 0.0201340000 43842893 955859216 1373700096 -0.4656273425 -0.0917110145 -0.0063436390 2274 1311867794.4987208843 0.3377163112 0.3217000477 0.4404943883 0.0039687709 0.0138500000 43845821 955859216 1373700096 -0.4663874209 -0.0913252309 -0.0064550145 2275 1311867794.5290880203 0.3379139900 0.3217071747 0.4404943883 0.0039680309 0.0201470000 43848637 955859216 1373700096 -0.4671329558 -0.0908775255 -0.0064292327 2276 1311867794.5637059212 0.3368722498 0.3217138377 0.4404943883 0.0039681735 0.0092560000 43851565 955859216 1373700096 -0.4667132497 -0.0906491950 -0.0065453108 2277 1311867794.5940639973 0.3372285962 0.3217206514 0.4404943883 0.0039675616 0.0071670000 43854437 955859216 1373700096 -0.4674824476 -0.0906775817 -0.0065833698 2278 1311867794.6319000721 0.3370333016 0.3217273734 0.4404943883 0.0039687026 0.0066080000 43857421 955859216 1373700096 -0.4675885737 -0.0902666226 -0.0069566690 2279 1311867794.6658101082 0.3365994692 0.3217338991 0.4404943883 0.0039689601 0.0066990000 43860349 955859216 1373700096 -0.4675396383 -0.0892581418 -0.0070308419 2280 1311867794.6949920654 0.3362613916 0.3217402708 0.4404943883 0.0039689348 0.0065760000 43863165 955859216 1373700096 -0.4676975310 -0.0884467885 -0.0071454765 2281 1311867794.7305591106 0.3363865316 0.3217466918 0.4404943883 0.0039687239 0.0065250000 43866149 955859216 1373700096 -0.4680240154 -0.0880170241 -0.0070953099 2282 1311867794.7625899315 0.3361775577 0.3217530156 0.4404943883 0.0039684002 0.0065500000 43868965 955859216 1373700096 -0.4678749740 -0.0878939331 -0.0072499979 2283 1311867794.7959010601 0.3352397084 0.3217589230 0.4404943883 0.0039679377 0.0064940000 43871893 955859216 1373700096 -0.4672876894 -0.0870474279 -0.0074581346 2284 1311867794.8306028843 0.3352351189 0.3217648233 0.4404943883 0.0039674714 0.0065550000 43874821 955859216 1373700096 -0.4675413370 -0.0867874250 -0.0075006234 2285 1311867794.8631660938 0.3359400332 0.3217710269 0.4404943883 0.0039666999 0.0065650000 43877581 955859216 1373700096 -0.4683684707 -0.0867259204 -0.0075815860 2286 1311867794.8947780132 0.3362285793 0.3217773512 0.4404943883 0.0039663635 0.0067030000 43880453 955859216 1373700096 -0.4689512253 -0.0861243382 -0.0074729384 2287 1311867794.9343950748 0.3351004720 0.3217831768 0.4404943883 0.0039657966 0.0065770000 43883549 955859216 1373700096 -0.4684228301 -0.0854059309 -0.0078513548 2288 1311867794.9646499157 0.3353730440 0.3217891165 0.4404943883 0.0039650103 0.0064940000 43886365 955859216 1373700096 -0.4688858092 -0.0849055052 -0.0078789312 2289 1311867794.9988350868 0.3346672654 0.3217947426 0.4404943883 0.0039647577 0.0121620000 43889349 955859216 1373700096 -0.4683772326 -0.0844111368 -0.0081990026 2290 1311867795.0307559967 0.3344946206 0.3218002884 0.4404943883 0.0039641931 0.0077900000 43892165 955859216 1373700096 -0.4682776332 -0.0842127129 -0.0082596280 2291 1311867795.0651550293 0.3339023590 0.3218055708 0.4404943883 0.0039634871 0.0066410000 43895093 955859216 1373700096 -0.4681374133 -0.0833540857 -0.0083149560 2292 1311867795.0993340015 0.3334763646 0.3218106628 0.4404943883 0.0039629230 0.0065950000 43898021 955859216 1373700096 -0.4680469334 -0.0826281831 -0.0084894076 2293 1311867795.1310648918 0.3327555954 0.3218154360 0.4404943883 0.0039622692 0.0065460000 43900949 955859216 1373700096 -0.4675215483 -0.0821251720 -0.0085514812 2294 1311867795.1630289555 0.3330665827 0.3218203406 0.4404943883 0.0039618503 0.0065610000 43903765 955859216 1373700096 -0.4682577252 -0.0816868693 -0.0084970538 2295 1311867795.1945760250 0.3329014778 0.3218251689 0.4404943883 0.0039611725 0.0065590000 43906693 955859216 1373700096 -0.4686307907 -0.0817049891 -0.0086760037 2296 1311867795.2313210964 0.3336211443 0.3218303066 0.4404943883 0.0039606823 0.0108780000 43909677 955859216 1373700096 -0.4696157873 -0.0817562863 -0.0088800816 2297 1311867795.2631359100 0.3333814740 0.3218353354 0.4404943883 0.0039599660 0.0079530000 43912549 955859216 1373700096 -0.4697842598 -0.0814657062 -0.0091546373 2298 1311867795.2958068848 0.3336295187 0.3218404677 0.4404943883 0.0039591895 0.0105550000 43915477 955859216 1373700096 -0.4702917337 -0.0816769600 -0.0091101900 2299 1311867795.3314220905 0.3330281079 0.3218453340 0.4404943883 0.0039594877 0.0076420000 43918405 955859216 1373700096 -0.4698811769 -0.0814750865 -0.0094811330 2300 1311867795.3670549393 0.3329869509 0.3218501782 0.4404943883 0.0039590315 0.0108440000 43921501 955859216 1373700096 -0.4698680937 -0.0812907219 -0.0094041936 2301 1311867795.3950240612 0.3323979378 0.3218547622 0.4404943883 0.0039591153 0.0208740000 43924205 955859216 1373700096 -0.4696744084 -0.0803521797 -0.0095864227 2302 1311867795.4294250011 0.3322525024 0.3218592790 0.4404943883 0.0039586167 0.0137740000 43927189 955859216 1373700096 -0.4695915878 -0.0801335871 -0.0096010976 2303 1311867795.4614660740 0.3322763145 0.3218638023 0.4404943883 0.0039594303 0.0081360000 43930173 955859216 1373700096 -0.4691563845 -0.0800679699 -0.0095188990 2304 1311867795.4961009026 0.3321271837 0.3218682569 0.4404943883 0.0039586824 0.0068640000 43933157 955859216 1373700096 -0.4689593017 -0.0792498738 -0.0095234476 2305 1311867795.5292580128 0.3320979476 0.3218726949 0.4404943883 0.0039578551 0.0065710000 43936085 955859216 1373700096 -0.4689328671 -0.0785785764 -0.0092983050 2306 1311867795.5632829666 0.3317699432 0.3218769869 0.4404943883 0.0039576957 0.0207340000 43939125 955859216 1373700096 -0.4683472514 -0.0778490007 -0.0093889693 2307 1311867795.5938069820 0.3316093981 0.3218812055 0.4404943883 0.0039571760 0.0102470000 43941997 955859216 1373700096 -0.4677878320 -0.0770451948 -0.0093500344 2308 1311867795.6295180321 0.3317545950 0.3218854834 0.4404943883 0.0039567046 0.0073020000 43945037 955859216 1373700096 -0.4677255750 -0.0758907050 -0.0093358746 2309 1311867795.6619150639 0.3315411806 0.3218896652 0.4404943883 0.0039560352 0.0066460000 43947965 955859216 1373700096 -0.4671913981 -0.0745799616 -0.0091950344 2310 1311867795.6935899258 0.3312466145 0.3218937158 0.4404943883 0.0039553183 0.0065870000 43950837 955859216 1373700096 -0.4665708542 -0.0732036382 -0.0092493352 2311 1311867795.7300128937 0.3312445283 0.3218977620 0.4404943883 0.0039548106 0.0108980000 43953933 955859216 1373700096 -0.4661232233 -0.0715165660 -0.0092104971 2312 1311867795.7627360821 0.3308717012 0.3219016435 0.4404943883 0.0039542285 0.0076830000 43956917 955859216 1373700096 -0.4654144347 -0.0703714266 -0.0092749782 2313 1311867795.7993569374 0.3310241103 0.3219055875 0.4404943883 0.0039536889 0.0067990000 43959957 955859216 1373700096 -0.4654848874 -0.0694311857 -0.0091319261 2314 1311867795.8297359943 0.3317323625 0.3219098342 0.4404943883 0.0039529751 0.0068170000 43962829 955859216 1373700096 -0.4661492705 -0.0688905120 -0.0091270786 2315 1311867795.8630819321 0.3320889771 0.3219142312 0.4404943883 0.0039524262 0.0067480000 43965813 955859216 1373700096 -0.4661210775 -0.0694540814 -0.0091581270 2316 1311867795.9011631012 0.3322953284 0.3219187135 0.4404943883 0.0039519032 0.0073090000 43968909 955859216 1373700096 -0.4663325250 -0.0687387735 -0.0093214959 2317 1311867795.9300799370 0.3326486647 0.3219233445 0.4404943883 0.0039510514 0.0067860000 43971725 955859216 1373700096 -0.4666842520 -0.0686015859 -0.0092230784 2318 1311867795.9624390602 0.3331985176 0.3219282087 0.4404943883 0.0039503387 0.0066260000 43974653 955859216 1373700096 -0.4671704471 -0.0684822202 -0.0093643842 2319 1311867796.0000178814 0.3333224952 0.3219331221 0.4404943883 0.0039497562 0.0066620000 43977749 955859216 1373700096 -0.4670566618 -0.0684797689 -0.0095919538 2320 1311867796.0296399593 0.3334980905 0.3219381070 0.4404943883 0.0039490216 0.0067840000 43980565 955859216 1373700096 -0.4670070410 -0.0689368024 -0.0096205901 2321 1311867796.0617599487 0.3333854079 0.3219430391 0.4404943883 0.0039485776 0.0107750000 43983549 955859216 1373700096 -0.4666749239 -0.0688487217 -0.0097170705 2322 1311867796.0984148979 0.3326768875 0.3219476618 0.4404943883 0.0039478090 0.0076160000 43986533 955859216 1373700096 -0.4658977091 -0.0679643080 -0.0099822609 2323 1311867796.1296660900 0.3331211209 0.3219524717 0.4404943883 0.0039473836 0.0067530000 43989293 955859216 1373700096 -0.4662141204 -0.0673991889 -0.0099236490 2324 1311867796.1618049145 0.3334607482 0.3219574236 0.4404943883 0.0039465647 0.0066850000 43992221 955859216 1373700096 -0.4663464725 -0.0675684661 -0.0098463353 2325 1311867796.1990590096 0.3327293694 0.3219620567 0.4404943883 0.0039459433 0.0068650000 43995317 955859216 1373700096 -0.4653263688 -0.0671664700 -0.0098681059 2326 1311867796.2292931080 0.3327660263 0.3219667016 0.4404943883 0.0039451003 0.0067760000 43998189 955859216 1373700096 -0.4652233720 -0.0671407580 -0.0098224496 2327 1311867796.2631280422 0.3329205215 0.3219714089 0.4404943883 0.0039443971 0.0067970000 44001117 955859216 1373700096 -0.4651137292 -0.0668640956 -0.0098360283 2328 1311867796.3010690212 0.3327997625 0.3219760602 0.4404943883 0.0039436443 0.0068170000 44004157 955859216 1373700096 -0.4645946622 -0.0665636733 -0.0098164883 2329 1311867796.3299860954 0.3325063288 0.3219805816 0.4404943883 0.0039428290 0.0068590000 44006973 955859216 1373700096 -0.4639410675 -0.0663670823 -0.0098617719 2330 1311867796.3619849682 0.3330816925 0.3219853460 0.4404943883 0.0039420988 0.0115290000 44009957 955859216 1373700096 -0.4642485976 -0.0662422031 -0.0097224461 2331 1311867796.3998959064 0.3329263330 0.3219900397 0.4404943883 0.0039413562 0.0078900000 44012885 955859216 1373700096 -0.4636046588 -0.0660809651 -0.0096635465 2332 1311867796.4297831059 0.3331084549 0.3219948075 0.4404943883 0.0039405395 0.0068830000 44015757 955859216 1373700096 -0.4634686708 -0.0660458356 -0.0093335733 2333 1311867796.4618980885 0.3333281875 0.3219996653 0.4404943883 0.0039397244 0.0067540000 44018741 955859216 1373700096 -0.4635161757 -0.0659170449 -0.0093834372 2334 1311867796.5018439293 0.3331113756 0.3220044261 0.4404943883 0.0039391023 0.0067190000 44021893 955859216 1373700096 -0.4630263746 -0.0658130199 -0.0094837220 2335 1311867796.5301249027 0.3331210017 0.3220091870 0.4404943883 0.0039383195 0.0066940000 44024709 955859216 1373700096 -0.4627583623 -0.0656961128 -0.0094360514 2336 1311867796.5621480942 0.3340114951 0.3220143249 0.4404943883 0.0039375758 0.0111830000 44027637 955859216 1373700096 -0.4633317888 -0.0657219663 -0.0090424987 2337 1311867796.6018888950 0.3342001140 0.3220195392 0.4404943883 0.0039370714 0.0076420000 44030789 955859216 1373700096 -0.4629828632 -0.0658285990 -0.0088510616 2338 1311867796.6323978901 0.3333666921 0.3220243926 0.4404943883 0.0039364921 0.0068100000 44033661 955859216 1373700096 -0.4616130888 -0.0659870356 -0.0089357477 2339 1311867796.6659901142 0.3335075676 0.3220293020 0.4404943883 0.0039357534 0.0070410000 44036645 955859216 1373700096 -0.4612070918 -0.0661422387 -0.0086057615 2340 1311867796.7025029659 0.3336663544 0.3220342751 0.4404943883 0.0039352515 0.0067500000 44039573 955859216 1373700096 -0.4607683420 -0.0661893189 -0.0084916465 2341 1311867796.7335898876 0.3348938823 0.3220397683 0.4404943883 0.0039353050 0.0067120000 44042445 955859216 1373700096 -0.4610498846 -0.0659691766 -0.0081328461 2342 1311867796.7634348869 0.3346501291 0.3220451528 0.4404943883 0.0039345329 0.0066190000 44045373 955859216 1373700096 -0.4601408243 -0.0657622293 -0.0078687398 2343 1311867796.7990939617 0.3342539668 0.3220503635 0.4404943883 0.0039343128 0.0115860000 44048357 955859216 1373700096 -0.4591666460 -0.0654044673 -0.0074219876 2344 1311867796.8303010464 0.3346087337 0.3220557212 0.4404943883 0.0039336851 0.0076820000 44051285 955859216 1373700096 -0.4589484334 -0.0651387200 -0.0066982936 2345 1311867796.8626410961 0.3345696926 0.3220610576 0.4404943883 0.0039331622 0.0067340000 44054157 955859216 1373700096 -0.4582963288 -0.0647184104 -0.0062562004 2346 1311867796.8988420963 0.3347347975 0.3220664599 0.4404943883 0.0039327374 0.0068370000 44057197 955859216 1373700096 -0.4575809240 -0.0644606054 -0.0055760075 2347 1311867796.9308090210 0.3356798291 0.3220722602 0.4404943883 0.0039324276 0.0117230000 44060125 955859216 1373700096 -0.4579253495 -0.0644424558 -0.0050171278 2348 1311867796.9623529911 0.3363256454 0.3220783307 0.4404943883 0.0039318268 0.0078070000 44063053 955859216 1373700096 -0.4581530988 -0.0646245107 -0.0043757441 2349 1311867796.9994709492 0.3369849920 0.3220846766 0.4404943883 0.0039314373 0.0068830000 44066093 955859216 1373700096 -0.4582179487 -0.0652740747 -0.0037087668 2350 1311867797.0328159332 0.3374053240 0.3220911961 0.4404943883 0.0039307955 0.0067540000 44068965 955859216 1373700096 -0.4583553374 -0.0654073656 -0.0033812018 2351 1311867797.0733079910 0.3378229439 0.3220978876 0.4404943883 0.0039306902 0.0067270000 44072229 955859216 1373700096 -0.4582095742 -0.0654259771 -0.0026649968 2352 1311867797.0992720127 0.3386097550 0.3221049079 0.4404943883 0.0039301922 0.0068760000 44074933 955859216 1373700096 -0.4586838782 -0.0654255003 -0.0018908252 2353 1311867797.1336839199 0.3392399848 0.3221121902 0.4404943883 0.0039300211 0.0120740000 44077973 955859216 1373700096 -0.4587337077 -0.0656453371 -0.0010808295 2354 1311867797.1708030701 0.3399817050 0.3221197813 0.4404943883 0.0039294366 0.0108720000 44081013 955859216 1373700096 -0.4589214027 -0.0653217435 -0.0003380540 2355 1311867797.1996591091 0.3403136730 0.3221275069 0.4404943883 0.0039295048 0.0077000000 44083829 955859216 1373700096 -0.4587771893 -0.0650680289 0.0001842508 2356 1311867797.2372090816 0.3405013084 0.3221353057 0.4404943883 0.0039288173 0.0109070000 44086981 955859216 1373700096 -0.4581393003 -0.0647594109 0.0008673060 2357 1311867797.2708179951 0.3410611749 0.3221433353 0.4404943883 0.0039283060 0.0076920000 44089909 955859216 1373700096 -0.4584612250 -0.0642453432 0.0015310230 2358 1311867797.3019850254 0.3417524397 0.3221516513 0.4404943883 0.0039279365 0.0108780000 44092837 955859216 1373700096 -0.4588786066 -0.0640489161 0.0021632116 2359 1311867797.3296120167 0.3412951529 0.3221597664 0.4404943883 0.0039272700 0.0077480000 44095597 955859216 1373700096 -0.4583433867 -0.0636026710 0.0027727662 2360 1311867797.3703179359 0.3421103656 0.3221682200 0.4404943883 0.0039269496 0.0069130000 44098749 955859216 1373700096 -0.4592315555 -0.0634506047 0.0033344657 2361 1311867797.3999080658 0.3428463042 0.3221769782 0.4404943883 0.0039262797 0.0068990000 44101621 955859216 1373700096 -0.4601560831 -0.0630717725 0.0038693226 2362 1311867797.4322440624 0.3421139121 0.3221854189 0.4404943883 0.0039255684 0.0068190000 44104605 955859216 1373700096 -0.4595765173 -0.0630471930 0.0045153182 2363 1311867797.4688720703 0.3421986997 0.3221938884 0.4404943883 0.0039253566 0.0068120000 44107589 955859216 1373700096 -0.4599683583 -0.0629255921 0.0050122435 2364 1311867797.5000469685 0.3411679864 0.3222019146 0.4404943883 0.0039245946 0.0067670000 44110517 955859216 1373700096 -0.4590624273 -0.0626907796 0.0052120183 2365 1311867797.5296459198 0.3413698077 0.3222100194 0.4404943883 0.0039240364 0.0068560000 44113389 955859216 1373700096 -0.4594267309 -0.0627863407 0.0056777955 2366 1311867797.5718441010 0.3415040672 0.3222181741 0.4404943883 0.0039232523 0.0069580000 44116541 955859216 1373700096 -0.4598889649 -0.0627229735 0.0061132316 2367 1311867797.5997619629 0.3423913419 0.3222266968 0.4404943883 0.0039227090 0.0069660000 44119357 955859216 1373700096 -0.4608761370 -0.0628152415 0.0065073613 2368 1311867797.6303300858 0.3429667354 0.3222354553 0.4404943883 0.0039219565 0.0068760000 44122229 955859216 1373700096 -0.4617021382 -0.0628290251 0.0067257187 2369 1311867797.6706480980 0.3432791233 0.3222443382 0.4404943883 0.0039211386 0.0118540000 44125381 955859216 1373700096 -0.4622310698 -0.0634049773 0.0070388387 2370 1311867797.7010281086 0.3433917761 0.3222532612 0.4404943883 0.0039203580 0.0079420000 44128253 955859216 1373700096 -0.4625812471 -0.0635496601 0.0071005574 2371 1311867797.7299659252 0.3437092900 0.3222623105 0.4404943883 0.0039196513 0.0113020000 44131069 955859216 1373700096 -0.4631478786 -0.0638674945 0.0075183115 2372 1311867797.7678339481 0.3427266181 0.3222709380 0.4404943883 0.0039189777 0.0078430000 44134165 955859216 1373700096 -0.4623697698 -0.0640905201 0.0074184514 2373 1311867797.8001670837 0.3434694111 0.3222798712 0.4404943883 0.0039182496 0.0069670000 44137149 955859216 1373700096 -0.4631232619 -0.0644669458 0.0077126771 2374 1311867797.8302230835 0.3440518081 0.3222890422 0.4404943883 0.0039174498 0.0070500000 44140021 955859216 1373700096 -0.4637442231 -0.0646655038 0.0075868336 2375 1311867797.8681600094 0.3429438174 0.3222977389 0.4404943883 0.0039173530 0.0068840000 44143117 955859216 1373700096 -0.4626734257 -0.0648174733 0.0075773336 2376 1311867797.8986220360 0.3447223604 0.3223071769 0.4404943883 0.0039167317 0.0078980000 44145933 955859216 1373700096 -0.4642557204 -0.0657342374 0.0077708960 2377 1311867797.9362978935 0.3451070189 0.3223167688 0.4404943883 0.0039160149 0.0070950000 44149029 955859216 1373700096 -0.4645148516 -0.0657411590 0.0077870586 2378 1311867797.9696850777 0.3445881605 0.3223261344 0.4404943883 0.0039152945 0.0068790000 44151901 955859216 1373700096 -0.4640075266 -0.0659038424 0.0078941938 2379 1311867798.0026450157 0.3451997936 0.3223357492 0.4404943883 0.0039145572 0.0070020000 44154829 955859216 1373700096 -0.4645406902 -0.0661799237 0.0079400912 2380 1311867798.0362720490 0.3456751704 0.3223455557 0.4404943883 0.0039138025 0.0069710000 44157757 955859216 1373700096 -0.4648386538 -0.0664830208 0.0080059115 2381 1311867798.0708239079 0.3457784355 0.3223553973 0.4404943883 0.0039133830 0.0068480000 44160685 955859216 1373700096 -0.4648692012 -0.0667944700 0.0080404477 2382 1311867798.1006710529 0.3440650105 0.3223645113 0.4404943883 0.0039137039 0.0069040000 44163501 955859216 1373700096 -0.4630133808 -0.0670439824 0.0080348002 2383 1311867798.1315639019 0.3453587294 0.3223741606 0.4404943883 0.0039131250 0.0069900000 44166317 955859216 1373700096 -0.4639735520 -0.0676686093 0.0080356868 2384 1311867798.1681389809 0.3472812474 0.3223846082 0.4404943883 0.0039125629 0.0069940000 44169301 955859216 1373700096 -0.4654372633 -0.0682513416 0.0081067123 2385 1311867798.2041590214 0.3465352058 0.3223947342 0.4404943883 0.0039122556 0.0069570000 44172341 955859216 1373700096 -0.4642056823 -0.0683537498 0.0078864852 2386 1311867798.2401928902 0.3484792113 0.3224056665 0.4404943883 0.0039123268 0.0069620000 44175325 955859216 1373700096 -0.4655379355 -0.0691780820 0.0080400929 2387 1311867798.2742829323 0.3491750062 0.3224168812 0.4404943883 0.0039117780 0.0069150000 44178253 955859216 1373700096 -0.4658019841 -0.0689881891 0.0080533419 2388 1311867798.3000180721 0.3484410644 0.3224277791 0.4404943883 0.0039111259 0.0069050000 44180957 955859216 1373700096 -0.4645487070 -0.0689422041 0.0083215516 2389 1311867798.3389759064 0.3490924537 0.3224389405 0.4404943883 0.0039105955 0.0119530000 44184053 955859216 1373700096 -0.4644957781 -0.0691504329 0.0083837323 2390 1311867798.3689808846 0.3490977883 0.3224500948 0.4404943883 0.0039098209 0.0079550000 44186813 955859216 1373700096 -0.4639310539 -0.0690440312 0.0084500555 2391 1311867798.4016571045 0.3492287099 0.3224612946 0.4404943883 0.0039091343 0.0070500000 44189741 955859216 1373700096 -0.4635098577 -0.0687809661 0.0087105716 2392 1311867798.4377439022 0.3483032286 0.3224720981 0.4404943883 0.0039087689 0.0069530000 44192725 955859216 1373700096 -0.4619046450 -0.0688990206 0.0087407995 2393 1311867798.4722189903 0.3475343585 0.3224825712 0.4404943883 0.0039086700 0.0070840000 44195653 955859216 1373700096 -0.4605986476 -0.0686308071 0.0087372642 2394 1311867798.4979979992 0.3484409451 0.3224934143 0.4404943883 0.0039081054 0.0110940000 44198357 955859216 1373700096 -0.4611229002 -0.0687281713 0.0088234032 2395 1311867798.5371229649 0.3491953015 0.3225045633 0.4404943883 0.0039075239 0.0119640000 44201397 955859216 1373700096 -0.4611177742 -0.0691390336 0.0088649001 2396 1311867798.5710020065 0.3487292230 0.3225155085 0.4404943883 0.0039068635 0.0080100000 44204325 955859216 1373700096 -0.4601932466 -0.0694160163 0.0087131206 2397 1311867798.6058080196 0.3487910926 0.3225264704 0.4404943883 0.0039062854 0.0070960000 44207253 955859216 1373700096 -0.4595369995 -0.0695642754 0.0085617006 2398 1311867798.6374750137 0.3500557542 0.3225379505 0.4404943883 0.0039067946 0.0070870000 44210069 955859216 1373700096 -0.4600818753 -0.0695555732 0.0088274302 2399 1311867798.6689419746 0.3499373794 0.3225493717 0.4404943883 0.0039062084 0.0071100000 44212941 955859216 1373700096 -0.4593663812 -0.0689094886 0.0088651758 2400 1311867798.7046790123 0.3496575356 0.3225606667 0.4404943883 0.0039060174 0.0069840000 44215925 955859216 1373700096 -0.4584771991 -0.0685582608 0.0090490924 2401 1311867798.7372579575 0.3506171107 0.3225723520 0.4404943883 0.0039057279 0.0070640000 44218853 955859216 1373700096 -0.4584592283 -0.0683409497 0.0089553008 2402 1311867798.7684650421 0.3507728577 0.3225840925 0.4404943883 0.0039050855 0.0111520000 44221669 955859216 1373700096 -0.4579579532 -0.0677368268 0.0091402913 2403 1311867798.8009719849 0.3487667441 0.3225949883 0.4404943883 0.0039057394 0.0079230000 44224541 955859216 1373700096 -0.4553232193 -0.0668588206 0.0090326089 2404 1311867798.8353779316 0.3511892557 0.3226068827 0.4404943883 0.0039064208 0.0070180000 44227469 955859216 1373700096 -0.4565150142 -0.0668019801 0.0090588881 2405 1311867798.8719079494 0.3514620662 0.3226188807 0.4404943883 0.0039058145 0.0070200000 44230453 955859216 1373700096 -0.4555689096 -0.0662316456 0.0090935407 2406 1311867798.9030900002 0.3508726954 0.3226306238 0.4404943883 0.0039051103 0.0077550000 44233269 955859216 1373700096 -0.4541950524 -0.0657563955 0.0087456722 2407 1311867798.9344220161 0.3521928191 0.3226429056 0.4404943883 0.0039046871 0.0118970000 44236141 955859216 1373700096 -0.4544434547 -0.0652250573 0.0087456312 2408 1311867798.9702930450 0.3512243330 0.3226547749 0.4404943883 0.0039041885 0.0080620000 44239125 955859216 1373700096 -0.4523538649 -0.0643171445 0.0085470388 2409 1311867798.9996600151 0.3512501121 0.3226666451 0.4404943883 0.0039062707 0.0070940000 44241941 955859216 1373700096 -0.4523051083 -0.0638689175 0.0084321247 2410 1311867799.0381140709 0.3524947166 0.3226790219 0.4404943883 0.0039074935 0.0069470000 44245037 955859216 1373700096 -0.4517565966 -0.0633101016 0.0084132021 2411 1311867799.0688700676 0.3521521091 0.3226912464 0.4404943883 0.0039070238 0.0070200000 44247853 955859216 1373700096 -0.4504907131 -0.0632885322 0.0082751252 2412 1311867799.1011309624 0.3515452445 0.3227032090 0.4404943883 0.0039073863 0.0121180000 44250725 955859216 1373700096 -0.4492639005 -0.0629865751 0.0082682054 2413 1311867799.1368980408 0.3520103395 0.3227153546 0.4404943883 0.0039069721 0.0082220000 44253709 955859216 1373700096 -0.4486732781 -0.0626275390 0.0083363075 2414 1311867799.1699140072 0.3517325819 0.3227273749 0.4404943883 0.0039062745 0.0071180000 44256581 955859216 1373700096 -0.4476705194 -0.0621298030 0.0080102971 2415 1311867799.2040729523 0.3504568636 0.3227388571 0.4404943883 0.0039098265 0.0070130000 44259509 955859216 1373700096 -0.4457747340 -0.0618228614 0.0074097593 2416 1311867799.2358450890 0.3511024714 0.3227505970 0.4404943883 0.0039093334 0.0121960000 44262381 955859216 1373700096 -0.4458275139 -0.0616822056 0.0069401334 2417 1311867799.2801609039 0.3525699973 0.3227629344 0.4404943883 0.0039087727 0.0083180000 44265589 955859216 1373700096 -0.4461898506 -0.0618764721 0.0065063108 2418 1311867799.2992970943 0.3515122831 0.3227748241 0.4404943883 0.0039080266 0.0071140000 44268069 955859216 1373700096 -0.4448946118 -0.0616147369 0.0057364614 2419 1311867799.3363530636 0.3516405225 0.3227867570 0.4404943883 0.0039080661 0.0069620000 44271109 955859216 1373700096 -0.4444346130 -0.0610840470 0.0052992837 2420 1311867799.3682019711 0.3524540961 0.3227990163 0.4404943883 0.0039080015 0.0069120000 44273925 955859216 1373700096 -0.4448035657 -0.0608478077 0.0048095388 2421 1311867799.4002521038 0.3525848389 0.3228113194 0.4404943883 0.0039072801 0.0070820000 44276853 955859216 1373700096 -0.4443861246 -0.0603968017 0.0044562356 2422 1311867799.4359819889 0.3522161841 0.3228234601 0.4404943883 0.0039065961 0.0114100000 44279837 955859216 1373700096 -0.4437340200 -0.0594303273 0.0039877002 2423 1311867799.4694008827 0.3523664176 0.3228356528 0.4404943883 0.0039058979 0.0083460000 44282709 955859216 1373700096 -0.4434818625 -0.0585574210 0.0038243225 2424 1311867799.5055029392 0.3515847921 0.3228475130 0.4404943883 0.0039051496 0.0072100000 44285693 955859216 1373700096 -0.4424234033 -0.0579110421 0.0034224989 2425 1311867799.5358369350 0.3488833308 0.3228582495 0.4404943883 0.0039049540 0.0071580000 44288509 955859216 1373700096 -0.4397285581 -0.0572683290 0.0030002065 2426 1311867799.5718040466 0.3504329026 0.3228696158 0.4404943883 0.0039045799 0.0071460000 44291493 955859216 1373700096 -0.4412112534 -0.0566581860 0.0027162766 2427 1311867799.6046330929 0.3501988649 0.3228808763 0.4404943883 0.0039041606 0.0073130000 44294309 955859216 1373700096 -0.4408833385 -0.0561054386 0.0024239242 2428 1311867799.6362400055 0.3495582044 0.3228918636 0.4404943883 0.0039035212 0.0126960000 44297237 955859216 1373700096 -0.4401709437 -0.0555410497 0.0017775748 2429 1311867799.6706030369 0.3507844508 0.3229033468 0.4404943883 0.0039035614 0.0082090000 44300165 955859216 1373700096 -0.4409552813 -0.0553856157 0.0012745738 2430 1311867799.7089800835 0.3513870835 0.3229150685 0.4404943883 0.0039030017 0.0071300000 44303205 955859216 1373700096 -0.4413378537 -0.0547548011 0.0006497027 2431 1311867799.7397329807 0.3502705693 0.3229263213 0.4404943883 0.0039026679 0.0071300000 44306021 955859216 1373700096 -0.4402953684 -0.0543164238 -0.0000117390 2432 1311867799.7721259594 0.3494834006 0.3229372411 0.4404943883 0.0039022131 0.0071420000 44308949 955859216 1373700096 -0.4392504692 -0.0537708327 -0.0006061729 2433 1311867799.8072490692 0.3506791890 0.3229486435 0.4404943883 0.0039020537 0.0070060000 44311877 955859216 1373700096 -0.4403283000 -0.0533329993 -0.0012154216 2434 1311867799.8393049240 0.3477241695 0.3229588224 0.4404943883 0.0039018587 0.0071290000 44314749 955859216 1373700096 -0.4373569191 -0.0524221547 -0.0018301017 2435 1311867799.8678040504 0.3483187854 0.3229692372 0.4404943883 0.0039015364 0.0072920000 44317565 955859216 1373700096 -0.4376640022 -0.0520960055 -0.0021379206 2436 1311867799.9071669579 0.3493146598 0.3229800522 0.4404943883 0.0039010541 0.0113110000 44320661 955859216 1373700096 -0.4384418130 -0.0512866192 -0.0021577559 2437 1311867799.9347701073 0.3479933739 0.3229903162 0.4404943883 0.0039004029 0.0121820000 44323309 955859216 1373700096 -0.4368994534 -0.0504400767 -0.0022023811 2438 1311867799.9675478935 0.3470769525 0.3230001959 0.4404943883 0.0038997771 0.0082450000 44326237 955859216 1373700096 -0.4359119534 -0.0496653542 -0.0020383357 2439 1311867800.0074419975 0.3483708799 0.3230105980 0.4404943883 0.0038992077 0.0073460000 44329333 955859216 1373700096 -0.4367077649 -0.0492184162 -0.0020773853 2440 1311867800.0354819298 0.3487025201 0.3230211274 0.4404943883 0.0038986498 0.0072160000 44332093 955859216 1373700096 -0.4367167056 -0.0485501662 -0.0022867916 2441 1311867800.0715930462 0.3484318852 0.3230315374 0.4404943883 0.0038988324 0.0072030000 44335077 955859216 1373700096 -0.4358117878 -0.0481538773 -0.0023027700 2442 1311867800.1054389477 0.3474011719 0.3230415168 0.4404943883 0.0038982136 0.0073550000 44338005 955859216 1373700096 -0.4342108965 -0.0475042537 -0.0026985810 2443 1311867800.1350870132 0.3475009501 0.3230515288 0.4404943883 0.0038975094 0.0072820000 44340765 955859216 1373700096 -0.4338851869 -0.0469454862 -0.0030485552 2444 1311867800.1694350243 0.3469687998 0.3230613150 0.4404943883 0.0038970942 0.0071940000 44343693 955859216 1373700096 -0.4327816963 -0.0464970246 -0.0032935883 2445 1311867800.2077379227 0.3466289341 0.3230709541 0.4404943883 0.0038963944 0.0072080000 44346789 955859216 1373700096 -0.4315939844 -0.0463026389 -0.0034981910 2446 1311867800.2413349152 0.3467396498 0.3230806305 0.4404943883 0.0038958600 0.0119810000 44349717 955859216 1373700096 -0.4309612513 -0.0456859507 -0.0034840642 2447 1311867800.2718439102 0.3472258747 0.3230904978 0.4404943883 0.0038952266 0.0081780000 44352533 955859216 1373700096 -0.4307437241 -0.0453887656 -0.0032316621 2448 1311867800.3038680553 0.3464313745 0.3231000325 0.4404943883 0.0038951514 0.0073220000 44355349 955859216 1373700096 -0.4293486178 -0.0448785089 -0.0030007602 2449 1311867800.3359420300 0.3459806144 0.3231093753 0.4404943883 0.0038944925 0.0072560000 44358277 955859216 1373700096 -0.4280965626 -0.0444405861 -0.0028743832 2450 1311867800.3712899685 0.3459127843 0.3231186828 0.4404943883 0.0038937758 0.0072070000 44361149 955859216 1373700096 -0.4268544614 -0.0439138487 -0.0026080750 2451 1311867800.4036390781 0.3457496166 0.3231279162 0.4404943883 0.0038934573 0.0072360000 44364077 955859216 1373700096 -0.4257932603 -0.0435486883 -0.0026315225 2452 1311867800.4360520840 0.3462381363 0.3231373412 0.4404943883 0.0038928636 0.0072370000 44366893 955859216 1373700096 -0.4253914952 -0.0432591029 -0.0025966840 2453 1311867800.4683868885 0.3462643921 0.3231467693 0.4404943883 0.0038921317 0.0117200000 44369765 955859216 1373700096 -0.4244132936 -0.0430292040 -0.0025010889 2454 1311867800.5043759346 0.3470959961 0.3231565286 0.4404943883 0.0038916793 0.0081640000 44372805 955859216 1373700096 -0.4241153300 -0.0423643477 -0.0022054622 2455 1311867800.5355989933 0.3472725451 0.3231663518 0.4404943883 0.0038912514 0.0074160000 44375677 955859216 1373700096 -0.4234339595 -0.0420684405 -0.0023095417 2456 1311867800.5714819431 0.3478427827 0.3231763992 0.4404943883 0.0038909085 0.0073270000 44378717 955859216 1373700096 -0.4227716327 -0.0418813787 -0.0021563361 2457 1311867800.6043050289 0.3469647467 0.3231860811 0.4404943883 0.0038903131 0.0073350000 44381589 955859216 1373700096 -0.4209874868 -0.0416362584 -0.0020962427 2458 1311867800.6356160641 0.3472188115 0.3231958584 0.4404943883 0.0038896498 0.0122570000 44384461 955859216 1373700096 -0.4201931953 -0.0417895727 -0.0020322925 2459 1311867800.6704459190 0.3460886180 0.3232051682 0.4404943883 0.0038899894 0.0083160000 44387389 955859216 1373700096 -0.4181736112 -0.0411037877 -0.0020850827 2460 1311867800.7034249306 0.3463409245 0.3232145730 0.4404943883 0.0038895292 0.0073190000 44390261 955859216 1373700096 -0.4176034629 -0.0407886468 -0.0019101008 2461 1311867800.7352058887 0.3478098512 0.3232245670 0.4404943883 0.0038890434 0.0072370000 44393133 955859216 1373700096 -0.4179026186 -0.0407718010 -0.0017390919 2462 1311867800.7744410038 0.3466026187 0.3232340626 0.4404943883 0.0038901782 0.0072620000 44396173 955859216 1373700096 -0.4159075320 -0.0406233296 -0.0017378642 2463 1311867800.8084959984 0.3470554948 0.3232437343 0.4404943883 0.0038897122 0.0073390000 44399101 955859216 1373700096 -0.4156914055 -0.0403117239 -0.0016002230 2464 1311867800.8347818851 0.3473062813 0.3232534999 0.4404943883 0.0038890854 0.0081840000 44401805 955859216 1373700096 -0.4153482318 -0.0401906669 -0.0013464112 2465 1311867800.8741569519 0.3462869823 0.3232628441 0.4404943883 0.0038891340 0.0075270000 44404901 955859216 1373700096 -0.4138312936 -0.0395319462 -0.0014777575 2466 1311867800.9060831070 0.3456798196 0.3232719345 0.4404943883 0.0038884342 0.0073490000 44407717 955859216 1373700096 -0.4128032625 -0.0390019752 -0.0015449637 2467 1311867800.9397630692 0.3468585312 0.3232814954 0.4404943883 0.0038879511 0.0072810000 44410645 955859216 1373700096 -0.4134677052 -0.0392484739 -0.0015308363 2468 1311867800.9754400253 0.3462079167 0.3232907849 0.4404943883 0.0038880431 0.0073440000 44413629 955859216 1373700096 -0.4122149348 -0.0392630808 -0.0016229800 2469 1311867801.0043320656 0.3466347754 0.3233002397 0.4404943883 0.0038877636 0.0075200000 44416389 955859216 1373700096 -0.4122419059 -0.0398869812 -0.0016624574 2470 1311867801.0391418934 0.3476215899 0.3233100864 0.4404943883 0.0038875873 0.0073900000 44419373 955859216 1373700096 -0.4127976894 -0.0405489951 -0.0015250850 2471 1311867801.0742049217 0.3463698030 0.3233194185 0.4404943883 0.0038869304 0.0074280000 44422245 955859216 1373700096 -0.4111834764 -0.0403427072 -0.0015416405 2472 1311867801.1095008850 0.3459874988 0.3233285885 0.4404943883 0.0038867332 0.0073800000 44425229 955859216 1373700096 -0.4106661081 -0.0401762612 -0.0012591006 2473 1311867801.1356039047 0.3455131650 0.3233375592 0.4404943883 0.0038860771 0.0073210000 44427933 955859216 1373700096 -0.4099992216 -0.0400988013 -0.0011402016 2474 1311867801.1731019020 0.3454916477 0.3233465140 0.4404943883 0.0038855069 0.0073520000 44430973 955859216 1373700096 -0.4099130034 -0.0400659554 -0.0008644231 2475 1311867801.2059779167 0.3438156843 0.3233547843 0.4404943883 0.0038863374 0.0073210000 44433845 955859216 1373700096 -0.4084621370 -0.0401770733 -0.0009352173 2476 1311867801.2351169586 0.3436921835 0.3233629981 0.4404943883 0.0038857174 0.0073210000 44436493 955859216 1373700096 -0.4083077610 -0.0410731472 -0.0008486243 2477 1311867801.2740859985 0.3446060419 0.3233715743 0.4404943883 0.0038849916 0.0121220000 44439645 955859216 1373700096 -0.4093050361 -0.0413767695 -0.0006526585 2478 1311867801.3080420494 0.3436799645 0.3233797697 0.4404943883 0.0038849934 0.0083660000 44442517 955859216 1373700096 -0.4086949825 -0.0413756184 -0.0005969623 2479 1311867801.3364291191 0.3428277373 0.3233876148 0.4404943883 0.0038844894 0.0115460000 44445277 955859216 1373700096 -0.4080470502 -0.0407721475 -0.0006580235 2480 1311867801.3723030090 0.3413747251 0.3233948677 0.4404943883 0.0038843200 0.0123790000 44448261 955859216 1373700096 -0.4068974853 -0.0401209928 -0.0007224723 2481 1311867801.4048879147 0.3410315216 0.3234019764 0.4404943883 0.0038836015 0.0086080000 44451133 955859216 1373700096 -0.4066680670 -0.0400068536 -0.0006714631 2482 1311867801.4369940758 0.3414672017 0.3234092549 0.4404943883 0.0038834534 0.0073690000 44454061 955859216 1373700096 -0.4072772861 -0.0399646983 -0.0004691685 2483 1311867801.4725570679 0.3405779600 0.3234161694 0.4404943883 0.0038872071 0.0075270000 44456989 955859216 1373700096 -0.4061033428 -0.0395768248 -0.0001493311 2484 1311867801.5049059391 0.3407115340 0.3234231321 0.4404943883 0.0038871243 0.0073600000 44459805 955859216 1373700096 -0.4061568677 -0.0391522013 0.0002797916 2485 1311867801.5366990566 0.3420288265 0.3234306193 0.4404943883 0.0038880879 0.0074320000 44462733 955859216 1373700096 -0.4066914022 -0.0391615890 0.0007277470 2486 1311867801.5724411011 0.3416802883 0.3234379603 0.4404943883 0.0038882908 0.0073380000 44465717 955859216 1373700096 -0.4062406719 -0.0387637764 0.0012083718 2487 1311867801.6040530205 0.3414959311 0.3234452212 0.4404943883 0.0038875627 0.0073310000 44468533 955859216 1373700096 -0.4055191576 -0.0386779904 0.0016889370 2488 1311867801.6371319294 0.3418487906 0.3234526181 0.4404943883 0.0038869100 0.0072000000 44471461 955859216 1373700096 -0.4051017761 -0.0384020247 0.0020990202 2489 1311867801.6713359356 0.3406706452 0.3234595358 0.4404943883 0.0038942517 0.0073660000 44474389 955859216 1373700096 -0.4037403166 -0.0379790813 0.0021873226 2490 1311867801.7047519684 0.3399688005 0.3234661660 0.4404943883 0.0038955665 0.0073190000 44477317 955859216 1373700096 -0.4020726085 -0.0383445062 0.0023752509 2491 1311867801.7362918854 0.3417466879 0.3234735046 0.4404943883 0.0039004180 0.0073880000 44480189 955859216 1373700096 -0.4023819864 -0.0394475907 0.0025951997 2492 1311867801.7739040852 0.3423606455 0.3234810837 0.4404943883 0.0039009128 0.0073730000 44483229 955859216 1373700096 -0.4018402398 -0.0400049910 0.0024596541 2493 1311867801.8057849407 0.3422263861 0.3234886029 0.4404943883 0.0039004347 0.0082880000 44486045 955859216 1373700096 -0.4006957412 -0.0403577872 0.0020233090 2494 1311867801.8389480114 0.3438889682 0.3234967827 0.4404943883 0.0039000346 0.0075560000 44488917 955859216 1373700096 -0.4010574520 -0.0417489409 0.0015365955 2495 1311867801.8715689182 0.3439232409 0.3235049697 0.4404943883 0.0039003547 0.0074670000 44491901 955859216 1373700096 -0.3998844624 -0.0427748375 0.0006136188 2496 1311867801.9050290585 0.3439868391 0.3235131755 0.4404943883 0.0039019530 0.0075430000 44494773 955859216 1373700096 -0.3987217247 -0.0433285497 -0.0004196595 2497 1311867801.9403839111 0.3449700475 0.3235217686 0.4404943883 0.0039020422 0.0075630000 44497757 955859216 1373700096 -0.3984333873 -0.0439519435 -0.0013307527 2498 1311867801.9724469185 0.3444066942 0.3235301292 0.4404943883 0.0039016536 0.0074660000 44500629 955859216 1373700096 -0.3967433274 -0.0436957479 -0.0027773252 2499 1311867802.0031659603 0.3456086516 0.3235389642 0.4404943883 0.0039074110 0.0074510000 44503445 955859216 1373700096 -0.3965978920 -0.0434831083 -0.0038597351 2500 1311867802.0413680077 0.3467515409 0.3235482492 0.4404943883 0.0039123248 0.0074340000 44506541 955859216 1373700096 -0.3958998322 -0.0429643206 -0.0052460749 2501 1311867802.0717110634 0.3465946913 0.3235574641 0.4404943883 0.0039126350 0.0075220000 44509357 955859216 1373700096 -0.3943237960 -0.0426818393 -0.0067966795 2502 1311867802.1040730476 0.3478867412 0.3235671880 0.4404943883 0.0039139746 0.0075690000 44512173 955859216 1373700096 -0.3937958479 -0.0426536202 -0.0084439153 2503 1311867802.1390628815 0.3478485346 0.3235768889 0.4404943883 0.0039158752 0.0075340000 44515101 955859216 1373700096 -0.3919053972 -0.0423234627 -0.0100351349 2504 1311867802.1724100113 0.3462632895 0.3235859490 0.4404943883 0.0039220298 0.0075640000 44518029 955859216 1373700096 -0.3889266849 -0.0418032780 -0.0121657914 2505 1311867802.2056589127 0.3464679420 0.3235950835 0.4404943883 0.0039248892 0.0116590000 44520901 955859216 1373700096 -0.3870839775 -0.0416241586 -0.0141594512 2506 1311867802.2409839630 0.3466977179 0.3236043025 0.4404943883 0.0039308599 0.0123440000 44523885 955859216 1373700096 -0.3856002092 -0.0415758826 -0.0162025653 2507 1311867802.2706429958 0.3470036983 0.3236136361 0.4404943883 0.0039303955 0.0085020000 44526701 955859216 1373700096 -0.3842054605 -0.0421609357 -0.0183702465 2508 1311867802.3064510822 0.3461109996 0.3236226063 0.4404943883 0.0039317806 0.0117340000 44529629 955859216 1373700096 -0.3818992972 -0.0428846031 -0.0205248129 2509 1311867802.3400380611 0.3462040126 0.3236316065 0.4404943883 0.0039363109 0.0084770000 44532557 955859216 1373700096 -0.3804893196 -0.0440614447 -0.0227093492 2510 1311867802.3742809296 0.3461585939 0.3236405814 0.4404943883 0.0039359783 0.0076720000 44535373 955859216 1373700096 -0.3787463605 -0.0449687243 -0.0249215905 2511 1311867802.4052720070 0.3461549580 0.3236495477 0.4404943883 0.0039379972 0.0076950000 44538245 955859216 1373700096 -0.3773981631 -0.0463989377 -0.0269700121 2512 1311867802.4389400482 0.3466974199 0.3236587228 0.4404943883 0.0039415597 0.0075790000 44541117 955859216 1373700096 -0.3767387867 -0.0473118350 -0.0288917217 2513 1311867802.4714379311 0.3466500044 0.3236678717 0.4404943883 0.0039418514 0.0118000000 44544045 955859216 1373700096 -0.3755392730 -0.0481242128 -0.0309962481 2514 1311867802.5060200691 0.3467811346 0.3236770655 0.4404943883 0.0039426600 0.0124370000 44546973 955859216 1373700096 -0.3744205832 -0.0483686253 -0.0331768617 2515 1311867802.5389459133 0.3476127088 0.3236865827 0.4404943883 0.0039433374 0.0085230000 44549789 955859216 1373700096 -0.3739056885 -0.0492747687 -0.0351581573 2516 1311867802.5715909004 0.3480730355 0.3236962753 0.4404943883 0.0039461205 0.0117120000 44552773 955859216 1373700096 -0.3729712963 -0.0491320491 -0.0376215838 2517 1311867802.6031410694 0.3480791748 0.3237059625 0.4404943883 0.0039465299 0.0124500000 44555589 955859216 1373700096 -0.3715461195 -0.0483522862 -0.0396524817 2518 1311867802.6396369934 0.3496686816 0.3237162734 0.4404943883 0.0039466926 0.0085060000 44558573 955859216 1373700096 -0.3716371357 -0.0489210561 -0.0415935107 2519 1311867802.6727440357 0.3504146039 0.3237268722 0.4404943883 0.0039462159 0.0117130000 44561445 955859216 1373700096 -0.3709533215 -0.0486057475 -0.0435625017 2520 1311867802.7073149681 0.3505600691 0.3237375203 0.4404943883 0.0039464724 0.0124240000 44564373 955859216 1373700096 -0.3698999882 -0.0475490429 -0.0453689396 2521 1311867802.7416400909 0.3503763080 0.3237480870 0.4404943883 0.0039458965 0.0085160000 44567301 955859216 1373700096 -0.3682682812 -0.0467412956 -0.0471711159 2522 1311867802.7708799839 0.3500465155 0.3237585146 0.4404943883 0.0039451392 0.0117640000 44570117 955859216 1373700096 -0.3664836586 -0.0463412963 -0.0491158217 2523 1311867802.8048460484 0.3488920927 0.3237684764 0.4404943883 0.0039445201 0.0126650000 44572933 955859216 1373700096 -0.3640578687 -0.0456306748 -0.0508249551 2524 1311867802.8393790722 0.3492591679 0.3237785757 0.4404943883 0.0039440751 0.0084920000 44575917 955859216 1373700096 -0.3630882502 -0.0452605560 -0.0520981550 2525 1311867802.8706729412 0.3495717049 0.3237887908 0.4404943883 0.0039437437 0.0117960000 44578789 955859216 1373700096 -0.3618757427 -0.0456119068 -0.0537215620 2526 1311867802.9066920280 0.3498970568 0.3237991266 0.4404943883 0.0039437172 0.0083850000 44581773 955859216 1373700096 -0.3610362709 -0.0456030592 -0.0552737303 2527 1311867802.9404280186 0.3497153223 0.3238093824 0.4404943883 0.0039431272 0.0077620000 44584645 955859216 1373700096 -0.3594357669 -0.0453856289 -0.0568562262 2528 1311867802.9723958969 0.3503012061 0.3238198617 0.4404943883 0.0039424758 0.0076320000 44587517 955859216 1373700096 -0.3587042689 -0.0458900221 -0.0581630655 2529 1311867803.0042099953 0.3497902155 0.3238301307 0.4404943883 0.0039429313 0.0075780000 44590389 955859216 1373700096 -0.3573613763 -0.0456888005 -0.0595048554 2530 1311867803.0404539108 0.3499992788 0.3238404743 0.4404943883 0.0039424958 0.0209380000 44593373 955859216 1373700096 -0.3560222089 -0.0458153859 -0.0610113032 2531 1311867803.0710830688 0.3499929905 0.3238508072 0.4404943883 0.0039420694 0.0101840000 44596189 955859216 1373700096 -0.3552439809 -0.0463207103 -0.0622932315 2532 1311867803.1049640179 0.3504492342 0.3238613121 0.4404943883 0.0039414874 0.0078370000 44599061 955859216 1373700096 -0.3547700047 -0.0469189845 -0.0637119785 2533 1311867803.1399960518 0.3505930901 0.3238718655 0.4404943883 0.0039408974 0.0075480000 44602045 955859216 1373700096 -0.3541440070 -0.0469920710 -0.0651243851 2534 1311867803.1724820137 0.3500530720 0.3238821974 0.4404943883 0.0039403234 0.0074330000 44604917 955859216 1373700096 -0.3532120287 -0.0470337942 -0.0664957315 2535 1311867803.2086870670 0.3501607180 0.3238925637 0.4404943883 0.0039400231 0.0074390000 44607957 955859216 1373700096 -0.3527430594 -0.0471556261 -0.0675361529 2536 1311867803.2400670052 0.3497737646 0.3239027692 0.4404943883 0.0039407297 0.0120980000 44610773 955859216 1373700096 -0.3524141014 -0.0474454686 -0.0687189400 2537 1311867803.2704820633 0.3508444130 0.3239133887 0.4404943883 0.0039418781 0.0124630000 44613589 955859216 1373700096 -0.3531090021 -0.0479420237 -0.0697332472 2538 1311867803.3084690571 0.3509115875 0.3239240263 0.4404943883 0.0039416822 0.0083750000 44616685 955859216 1373700096 -0.3533024490 -0.0487690344 -0.0707178414 2539 1311867803.3390929699 0.3507753313 0.3239346019 0.4404943883 0.0039416558 0.0075030000 44619389 955859216 1373700096 -0.3534095585 -0.0487946123 -0.0715966076 2540 1311867803.3732869625 0.3508974910 0.3239452172 0.4404943883 0.0039410160 0.0121080000 44622373 955859216 1373700096 -0.3535670936 -0.0490258150 -0.0722764730 2541 1311867803.4067549706 0.3507578969 0.3239557692 0.4404943883 0.0039404053 0.0083590000 44625301 955859216 1373700096 -0.3535833359 -0.0487937741 -0.0729531422 2542 1311867803.4397881031 0.3501490057 0.3239660734 0.4404943883 0.0039400007 0.0074470000 44628173 955859216 1373700096 -0.3528337479 -0.0489387214 -0.0738083869 2543 1311867803.4707190990 0.3505208194 0.3239765157 0.4404943883 0.0039394436 0.0075460000 44631045 955859216 1373700096 -0.3530512750 -0.0493490137 -0.0745160431 2544 1311867803.5065801144 0.3511915505 0.3239872134 0.4404943883 0.0039391519 0.0074880000 44634029 955859216 1373700096 -0.3534312248 -0.0497298129 -0.0753116235 2545 1311867803.5397379398 0.3511452079 0.3239978845 0.4404943883 0.0039388229 0.0123880000 44636901 955859216 1373700096 -0.3534490466 -0.0497109294 -0.0763321966 2546 1311867803.5702500343 0.3512927294 0.3240086052 0.4404943883 0.0039383480 0.0087680000 44639717 955859216 1373700096 -0.3536966741 -0.0498595051 -0.0772873461 2547 1311867803.6121668816 0.3517519832 0.3240194978 0.4404943883 0.0039382101 0.0077890000 44642925 955859216 1373700096 -0.3543771505 -0.0500156172 -0.0779941678 2548 1311867803.6394500732 0.3515809178 0.3240303147 0.4404943883 0.0039377234 0.0075670000 44645629 955859216 1373700096 -0.3544007242 -0.0493861325 -0.0788177773 2549 1311867803.6726729870 0.3515766263 0.3240411214 0.4404943883 0.0039375136 0.0076900000 44648501 955859216 1373700096 -0.3547434211 -0.0488954559 -0.0795276910 2550 1311867803.7105441093 0.3525228798 0.3240522907 0.4404943883 0.0039374197 0.0076230000 44651597 955859216 1373700096 -0.3560645878 -0.0487127341 -0.0800067410 2551 1311867803.7378931046 0.3523467481 0.3240633822 0.4404943883 0.0039372288 0.0080350000 44654301 955859216 1373700096 -0.3560817838 -0.0476953201 -0.0808310658 2552 1311867803.7722349167 0.3514426649 0.3240741108 0.4404943883 0.0039369256 0.0077150000 44657285 955859216 1373700096 -0.3553003073 -0.0469688289 -0.0818513334 2553 1311867803.8064799309 0.3524872661 0.3240852401 0.4404943883 0.0039364398 0.0077340000 44660213 955859216 1373700096 -0.3562742174 -0.0469266139 -0.0823749974 2554 1311867803.8385739326 0.3539723456 0.3240969422 0.4404943883 0.0039370817 0.0076350000 44663029 955859216 1373700096 -0.3574879169 -0.0466250181 -0.0825462788 2555 1311867803.8737049103 0.3531904519 0.3241083290 0.4404943883 0.0039395339 0.0127060000 44666069 955859216 1373700096 -0.3567023277 -0.0458978340 -0.0832237080 2556 1311867803.9077479839 0.3533405364 0.3241197657 0.4404943883 0.0039410396 0.0086750000 44668997 955859216 1373700096 -0.3569549620 -0.0454141274 -0.0839793608 2557 1311867803.9400169849 0.3545892239 0.3241316818 0.4404943883 0.0039425752 0.0078480000 44671813 955859216 1373700096 -0.3583300114 -0.0445677266 -0.0844061449 2558 1311867803.9723939896 0.3553797603 0.3241438977 0.4404943883 0.0039434191 0.0077560000 44674741 955859216 1373700096 -0.3595077097 -0.0438899957 -0.0848507136 2559 1311867804.0064320564 0.3552493453 0.3241560530 0.4404943883 0.0039431100 0.0076920000 44677613 955859216 1373700096 -0.3597232103 -0.0436625369 -0.0856671482 2560 1311867804.0387020111 0.3552189171 0.3241681869 0.4404943883 0.0039425343 0.0078320000 44680485 955859216 1373700096 -0.3601756394 -0.0432264358 -0.0862596557 2561 1311867804.0722310543 0.3548793197 0.3241801788 0.4404943883 0.0039418689 0.0078630000 44683413 955859216 1373700096 -0.3604535162 -0.0422332324 -0.0870289579 2562 1311867804.1084001064 0.3558784127 0.3241925512 0.4404943883 0.0039421207 0.0078970000 44686341 955859216 1373700096 -0.3620698154 -0.0424316339 -0.0874360651 2563 1311867804.1399340630 0.3563115299 0.3242050830 0.4404943883 0.0039416763 0.0078030000 44689213 955859216 1373700096 -0.3630720675 -0.0422543325 -0.0881786570 2564 1311867804.1736989021 0.3570480049 0.3242178923 0.4404943883 0.0039412564 0.0077750000 44692141 955859216 1373700096 -0.3642344475 -0.0418475606 -0.0886557177 2565 1311867804.2092669010 0.3573298156 0.3242308014 0.4404943883 0.0039409635 0.0076740000 44695069 955859216 1373700096 -0.3651967943 -0.0421706662 -0.0895738453 2566 1311867804.2408709526 0.3574272096 0.3242437384 0.4404943883 0.0039406192 0.0078610000 44697885 955859216 1373700096 -0.3658441305 -0.0418891273 -0.0902481750 2567 1311867804.2707660198 0.3574839532 0.3242566875 0.4404943883 0.0039399832 0.0077220000 44700701 955859216 1373700096 -0.3663209081 -0.0410683118 -0.0906496346 2568 1311867804.3078389168 0.3574431539 0.3242696106 0.4404943883 0.0039400516 0.0128200000 44703629 955859216 1373700096 -0.3668728173 -0.0408862308 -0.0913148895 2569 1311867804.3404970169 0.3584195077 0.3242829036 0.4404943883 0.0039393799 0.0087190000 44706557 955859216 1373700096 -0.3682664633 -0.0407050997 -0.0919597670 2570 1311867804.3725171089 0.3585005999 0.3242962179 0.4404943883 0.0039387798 0.0080400000 44709429 955859216 1373700096 -0.3688026667 -0.0398276299 -0.0926780924 2571 1311867804.4121570587 0.3583393693 0.3243094591 0.4404943883 0.0039384313 0.0079400000 44712525 955859216 1373700096 -0.3689610362 -0.0395605341 -0.0933171436 2572 1311867804.4434490204 0.3593316376 0.3243230758 0.4404943883 0.0039377335 0.0079670000 44715397 955859216 1373700096 -0.3700172901 -0.0398174524 -0.0940227658 2573 1311867804.4745810032 0.3594017029 0.3243367092 0.4404943883 0.0039370327 0.0120060000 44718213 955859216 1373700096 -0.3700907826 -0.0395465977 -0.0945752636 2574 1311867804.5092110634 0.3591317534 0.3243502271 0.4404943883 0.0039378298 0.0093360000 44721141 955859216 1373700096 -0.3698638082 -0.0396430567 -0.0953746885 2575 1311867804.5393021107 0.3602781594 0.3243641797 0.4404943883 0.0039372466 0.0128480000 44723957 955859216 1373700096 -0.3710098267 -0.0402389951 -0.0960589051 2576 1311867804.5744440556 0.3601467013 0.3243780704 0.4404943883 0.0039367012 0.0087730000 44726885 955859216 1373700096 -0.3708138168 -0.0395936891 -0.0967209265 2577 1311867804.6065940857 0.3605350256 0.3243921010 0.4404943883 0.0039360582 0.0079850000 44729813 955859216 1373700096 -0.3710199296 -0.0397907048 -0.0972890630 2578 1311867804.6414110661 0.3610802591 0.3244063323 0.4404943883 0.0039356623 0.0080420000 44732741 955859216 1373700096 -0.3712181449 -0.0396180600 -0.0977324471 2579 1311867804.6758968830 0.3605221510 0.3244203361 0.4404943883 0.0039350261 0.0079990000 44735725 955859216 1373700096 -0.3704400361 -0.0387141705 -0.0982790515 2580 1311867804.7094891071 0.3612084687 0.3244345951 0.4404943883 0.0039343079 0.0120690000 44738597 955859216 1373700096 -0.3709394932 -0.0382065363 -0.0986457318 2581 1311867804.7431960106 0.3627513945 0.3244494408 0.4404943883 0.0039354525 0.0085890000 44741525 955859216 1373700096 -0.3720348179 -0.0376125649 -0.0987893268 2582 1311867804.7739880085 0.3622857928 0.3244640947 0.4404943883 0.0039348916 0.0080170000 44744285 955859216 1373700096 -0.3714296818 -0.0367104299 -0.0992544517 2583 1311867804.8113589287 0.3624122739 0.3244787862 0.4404943883 0.0039378173 0.0078630000 44747325 955859216 1373700096 -0.3717728853 -0.0367562547 -0.0994974524 2584 1311867804.8407669067 0.3622504473 0.3244934037 0.4404943883 0.0039373896 0.0078970000 44750141 955859216 1373700096 -0.3713292181 -0.0361828916 -0.0997012109 2585 1311867804.8758749962 0.3622596562 0.3245080135 0.4404943883 0.0039377214 0.0079040000 44753069 955859216 1373700096 -0.3710870445 -0.0357819051 -0.0998242497 2586 1311867804.9093499184 0.3624266684 0.3245226765 0.4404943883 0.0039378148 0.0079310000 44755997 955859216 1373700096 -0.3707491755 -0.0366504043 -0.1000258550 2587 1311867804.9418170452 0.3625230491 0.3245373655 0.4404943883 0.0039383810 0.0078520000 44758869 955859216 1373700096 -0.3706012368 -0.0366594903 -0.0998384953 2588 1311867804.9785380363 0.3620177507 0.3245518479 0.4404943883 0.0039377431 0.0080230000 44761797 955859216 1373700096 -0.3698089123 -0.0359522104 -0.0997850299 2589 1311867805.0090980530 0.3618738055 0.3245662635 0.4404943883 0.0039372262 0.0081050000 44764613 955859216 1373700096 -0.3692606091 -0.0359370261 -0.0998289287 2590 1311867805.0401790142 0.3619820178 0.3245807097 0.4404943883 0.0039366091 0.0129080000 44767485 955859216 1373700096 -0.3689115345 -0.0360989906 -0.0993790403 2591 1311867805.0801899433 0.3616868854 0.3245950309 0.4404943883 0.0039363969 0.0087880000 44770581 955859216 1373700096 -0.3678815067 -0.0360859074 -0.0991316140 2592 1311867805.1079609394 0.3627751172 0.3246097608 0.4404943883 0.0039364749 0.0080670000 44773397 955859216 1373700096 -0.3679553568 -0.0360777117 -0.0987337828 2593 1311867805.1444120407 0.3630151749 0.3246245720 0.4404943883 0.0039378172 0.0080140000 44776381 955859216 1373700096 -0.3673847616 -0.0364649817 -0.0982972011 2594 1311867805.1750040054 0.3632223308 0.3246394517 0.4404943883 0.0039373773 0.0079470000 44779141 955859216 1373700096 -0.3669224381 -0.0364318527 -0.0979115441 2595 1311867805.2100739479 0.3627055287 0.3246541207 0.4404943883 0.0039380400 0.0080260000 44782125 955859216 1373700096 -0.3658361137 -0.0362643823 -0.0973978862 2596 1311867805.2393519878 0.3622477949 0.3246686021 0.4404943883 0.0039373735 0.0220670000 44784941 955859216 1373700096 -0.3648440242 -0.0361312293 -0.0970088765 2597 1311867805.2741580009 0.3629797399 0.3246833541 0.4404943883 0.0039367809 0.0106390000 44787869 955859216 1373700096 -0.3648174405 -0.0361457057 -0.0962560475 2598 1311867805.3108520508 0.3632040322 0.3246981812 0.4404943883 0.0039362683 0.0082740000 44790853 955859216 1373700096 -0.3642347157 -0.0364452302 -0.0958050564 2599 1311867805.3395309448 0.3631197214 0.3247129644 0.4404943883 0.0039355613 0.0132030000 44793669 955859216 1373700096 -0.3635991216 -0.0369337127 -0.0957018882 2600 1311867805.3745789528 0.3636852503 0.3247279537 0.4404943883 0.0039396133 0.0087760000 44796597 955859216 1373700096 -0.3633998334 -0.0372232608 -0.0952150524 2601 1311867805.4084360600 0.3634319603 0.3247428342 0.4404943883 0.0039389919 0.0082030000 44799581 955859216 1373700096 -0.3626806438 -0.0368471779 -0.0948953554 2602 1311867805.4401900768 0.3634318411 0.3247577031 0.4404943883 0.0039383433 0.0081100000 44802397 955859216 1373700096 -0.3624085486 -0.0361037143 -0.0945068672 2603 1311867805.4747269154 0.3633253872 0.3247725197 0.4404943883 0.0039395071 0.0129170000 44805325 955859216 1373700096 -0.3620931804 -0.0362408832 -0.0939816386 2604 1311867805.5079410076 0.3633786440 0.3247873454 0.4404943883 0.0039395104 0.0131560000 44808253 955859216 1373700096 -0.3616541028 -0.0360355936 -0.0932703018 2605 1311867805.5406329632 0.3632418513 0.3248021072 0.4404943883 0.0039389062 0.0087450000 44811181 955859216 1373700096 -0.3610748947 -0.0356450751 -0.0926857442 2606 1311867805.5750451088 0.3632568717 0.3248168635 0.4404943883 0.0039382438 0.0081090000 44814053 955859216 1373700096 -0.3606457114 -0.0362433530 -0.0920550749 2607 1311867805.6078290939 0.3637984395 0.3248318161 0.4404943883 0.0039383305 0.0121830000 44816981 955859216 1373700096 -0.3606811464 -0.0369089358 -0.0917465165 2608 1311867805.6431670189 0.3637256622 0.3248467294 0.4404943883 0.0039403600 0.0086300000 44819965 955859216 1373700096 -0.3603697121 -0.0368067585 -0.0914038718 2609 1311867805.6750800610 0.3642073572 0.3248618159 0.4404943883 0.0039398910 0.0130010000 44822837 955859216 1373700096 -0.3606460690 -0.0366545394 -0.0911406353 2610 1311867805.7071790695 0.3642896712 0.3248769224 0.4404943883 0.0039396251 0.0086700000 44825765 955859216 1373700096 -0.3604788780 -0.0369050913 -0.0910262913 2611 1311867805.7425789833 0.3645989001 0.3248921357 0.4404943883 0.0039417431 0.0079720000 44828749 955859216 1373700096 -0.3601159751 -0.0369330235 -0.0907782093 2612 1311867805.7748079300 0.3649172783 0.3249074592 0.4404943883 0.0039411464 0.0077970000 44831565 955859216 1373700096 -0.3600860238 -0.0366252512 -0.0904654786 2613 1311867805.8089549541 0.3646632731 0.3249226739 0.4404943883 0.0039409949 0.0130560000 44834493 955859216 1373700096 -0.3595233560 -0.0359383784 -0.0903730169 2614 1311867805.8436930180 0.3645540774 0.3249378351 0.4404943883 0.0039432997 0.0132470000 44837365 955859216 1373700096 -0.3591735065 -0.0356657803 -0.0899593309 2615 1311867805.8754489422 0.3646370173 0.3249530164 0.4404943883 0.0039427200 0.0088990000 44840237 955859216 1373700096 -0.3589674234 -0.0356239974 -0.0895657465 2616 1311867805.9129049778 0.3649635613 0.3249683110 0.4404943883 0.0039474306 0.0080470000 44843277 955859216 1373700096 -0.3587026298 -0.0357912295 -0.0890783221 2617 1311867805.9434199333 0.3651674986 0.3249836717 0.4404943883 0.0039485711 0.0079240000 44846149 955859216 1373700096 -0.3585078716 -0.0361012444 -0.0889984593 2618 1311867805.9747679234 0.3645524085 0.3249987859 0.4404943883 0.0039481519 0.0130510000 44848965 955859216 1373700096 -0.3576457500 -0.0354156569 -0.0889542177 2619 1311867806.0099248886 0.3655945063 0.3250142863 0.4404943883 0.0039483203 0.0209110000 44851893 955859216 1373700096 -0.3581705391 -0.0356106646 -0.0885366499 2620 1311867806.0427870750 0.3653140366 0.3250296679 0.4404943883 0.0039479518 0.0099080000 44854877 955859216 1373700096 -0.3573052287 -0.0359045155 -0.0882924199 2621 1311867806.0743720531 0.3653910160 0.3250450671 0.4404943883 0.0039529196 0.0081760000 44857637 955859216 1373700096 -0.3570718467 -0.0353446044 -0.0879459083 2622 1311867806.1078710556 0.3656529188 0.3250605545 0.4404943883 0.0039523417 0.0080560000 44860565 955859216 1373700096 -0.3566610515 -0.0351409651 -0.0876461715 2623 1311867806.1461410522 0.3659597039 0.3250761470 0.4404943883 0.0039521202 0.0088950000 44863605 955859216 1373700096 -0.3557634056 -0.0354224555 -0.0871496126 2624 1311867806.1751658916 0.3658975661 0.3250917039 0.4404943883 0.0039517039 0.0083860000 44866365 955859216 1373700096 -0.3549612463 -0.0348809175 -0.0867960900 2625 1311867806.2106690407 0.3658328652 0.3251072244 0.4404943883 0.0039525156 0.0082510000 44869349 955859216 1373700096 -0.3538228273 -0.0349404588 -0.0863816887 2626 1311867806.2435200214 0.3659147918 0.3251227642 0.4404943883 0.0039519074 0.0081030000 44872277 955859216 1373700096 -0.3530306518 -0.0348391570 -0.0859629437 2627 1311867806.2773389816 0.3659251928 0.3251382961 0.4404943883 0.0039517714 0.0079750000 44875205 955859216 1373700096 -0.3522385955 -0.0339710936 -0.0854996964 2628 1311867806.3098840714 0.3652197421 0.3251535478 0.4404943883 0.0039510348 0.0080880000 44878021 955859216 1373700096 -0.3508096039 -0.0336921066 -0.0852964222 2629 1311867806.3459429741 0.3656658828 0.3251689576 0.4404943883 0.0039511020 0.0123540000 44881061 955859216 1373700096 -0.3504537344 -0.0333896801 -0.0848613903 2630 1311867806.3760368824 0.3653672636 0.3251842422 0.4404943883 0.0039504826 0.0087050000 44883877 955859216 1373700096 -0.3495451808 -0.0326219723 -0.0844831243 2631 1311867806.4090569019 0.3648780882 0.3251993291 0.4404943883 0.0039595957 0.0082670000 44886749 955859216 1373700096 -0.3480790854 -0.0327871330 -0.0844779462 2632 1311867806.4434189796 0.3651187122 0.3252144961 0.4404943883 0.0039604032 0.0081750000 44889677 955859216 1373700096 -0.3476115763 -0.0331705883 -0.0841887146 2633 1311867806.4748079777 0.3648656309 0.3252295554 0.4404943883 0.0039621429 0.0082760000 44892549 955859216 1373700096 -0.3468236327 -0.0328398608 -0.0839576572 2634 1311867806.5103459358 0.3652666807 0.3252447555 0.4404943883 0.0039616591 0.0130390000 44895533 955859216 1373700096 -0.3463650644 -0.0331743062 -0.0836915821 2635 1311867806.5426719189 0.3652287722 0.3252599297 0.4404943883 0.0039616012 0.0088880000 44898405 955859216 1373700096 -0.3457693756 -0.0332886279 -0.0833465308 2636 1311867806.5787520409 0.3653545976 0.3252751401 0.4404943883 0.0039609427 0.0083000000 44901333 955859216 1373700096 -0.3454299569 -0.0322880447 -0.0831744075 2637 1311867806.6116139889 0.3652131855 0.3252902854 0.4404943883 0.0039615160 0.0081590000 44904317 955859216 1373700096 -0.3448562324 -0.0322555900 -0.0827713311 2638 1311867806.6448700428 0.3657694757 0.3253056300 0.4404943883 0.0039608436 0.0082790000 44907189 955859216 1373700096 -0.3450526595 -0.0317351483 -0.0821489170 2639 1311867806.6744968891 0.3654955328 0.3253208592 0.4404943883 0.0039609632 0.0081160000 44910005 955859216 1373700096 -0.3445729017 -0.0308121815 -0.0815227553 2640 1311867806.7064468861 0.3656974435 0.3253361534 0.4404943883 0.0039603422 0.0081530000 44912877 955859216 1373700096 -0.3445156217 -0.0306825675 -0.0809289962 2641 1311867806.7427020073 0.3657750785 0.3253514654 0.4404943883 0.0039598558 0.0083410000 44915861 955859216 1373700096 -0.3439435363 -0.0308181122 -0.0804338753 2642 1311867806.7790679932 0.3649840951 0.3253664664 0.4404943883 0.0039604503 0.0133460000 44918789 955859216 1373700096 -0.3431648016 -0.0303103048 -0.0796944425 2643 1311867806.8067629337 0.3649375737 0.3253814384 0.4404943883 0.0039599894 0.0089740000 44921605 955859216 1373700096 -0.3427605331 -0.0302897412 -0.0791281834 2644 1311867806.8439810276 0.3651524186 0.3253964804 0.4404943883 0.0039593195 0.0083100000 44924589 955859216 1373700096 -0.3425345719 -0.0307346731 -0.0784243643 2645 1311867806.8763918877 0.3650320470 0.3254114655 0.4404943883 0.0039588599 0.0124280000 44927461 955859216 1373700096 -0.3422439992 -0.0300741494 -0.0779642239 2646 1311867806.9124479294 0.3656843007 0.3254266857 0.4404943883 0.0039582879 0.0088080000 44930445 955859216 1373700096 -0.3424168527 -0.0307135526 -0.0776919127 2647 1311867806.9446148872 0.3652174771 0.3254417182 0.4404943883 0.0039577824 0.0132990000 44933261 955859216 1373700096 -0.3413646221 -0.0312681310 -0.0775386840 2648 1311867806.9770460129 0.3646588922 0.3254565283 0.4404943883 0.0039573792 0.0242080000 44936245 955859216 1373700096 -0.3406081498 -0.0308146570 -0.0773205087 2649 1311867807.0138700008 0.3647496104 0.3254713614 0.4404943883 0.0039578976 0.0121580000 44939173 955859216 1373700096 -0.3399810791 -0.0313260257 -0.0770083442 2650 1311867807.0428779125 0.3645438850 0.3254861058 0.4404943883 0.0039574255 0.0086640000 44942045 955859216 1373700096 -0.3390839696 -0.0321183391 -0.0765136406 2651 1311867807.0794920921 0.3644397259 0.3255007997 0.4404943883 0.0039609955 0.0083250000 44944973 955859216 1373700096 -0.3382222950 -0.0324518308 -0.0759840608 2652 1311867807.1121389866 0.3646816313 0.3255155738 0.4404943883 0.0039604006 0.0081760000 44947901 955859216 1373700096 -0.3379800320 -0.0325019695 -0.0754519925 2653 1311867807.1428070068 0.3641555905 0.3255301384 0.4404943883 0.0039597129 0.0205520000 44950773 955859216 1373700096 -0.3367932141 -0.0329594985 -0.0750824660 2654 1311867807.1802010536 0.3643008471 0.3255447469 0.4404943883 0.0039600759 0.0097840000 44953645 955859216 1373700096 -0.3363620639 -0.0328110196 -0.0745536536 2655 1311867807.2105820179 0.3637602925 0.3255591407 0.4404943883 0.0039606273 0.0083920000 44956461 955859216 1373700096 -0.3356133997 -0.0318286605 -0.0740875080 2656 1311867807.2429521084 0.3633068800 0.3255733529 0.4404943883 0.0039600698 0.0124330000 44959333 955859216 1373700096 -0.3347591460 -0.0322283916 -0.0736420602 2657 1311867807.2808670998 0.3638289869 0.3255877510 0.4404943883 0.0039594967 0.0087450000 44962373 955859216 1373700096 -0.3344834447 -0.0330398232 -0.0733188391 2658 1311867807.3107318878 0.3644072711 0.3256023557 0.4404943883 0.0039590070 0.0081870000 44965189 955859216 1373700096 -0.3343842328 -0.0329766124 -0.0727751106 2659 1311867807.3434429169 0.3644080460 0.3256169498 0.4404943883 0.0039585200 0.0080830000 44968061 955859216 1373700096 -0.3337933421 -0.0331570953 -0.0726676881 2660 1311867807.3776888847 0.3644171655 0.3256315364 0.4404943883 0.0039586736 0.0123010000 44970989 955859216 1373700096 -0.3330573738 -0.0339028053 -0.0726223141 2661 1311867807.4111731052 0.3654253185 0.3256464908 0.4404943883 0.0039600297 0.0087310000 44973917 955859216 1373700096 -0.3337285817 -0.0340140127 -0.0723712370 2662 1311867807.4426960945 0.3651477396 0.3256613298 0.4404943883 0.0039595294 0.0081500000 44976789 955859216 1373700096 -0.3329239488 -0.0342672579 -0.0725775212 2663 1311867807.4781239033 0.3649973273 0.3256761011 0.4404943883 0.0039627329 0.0082400000 44979717 955859216 1373700096 -0.3319012821 -0.0354453772 -0.0727939755 2664 1311867807.5104010105 0.3652836978 0.3256909688 0.4404943883 0.0039625200 0.0080340000 44982533 955859216 1373700096 -0.3315488696 -0.0364693366 -0.0726772770 2665 1311867807.5430259705 0.3652791977 0.3257058237 0.4404943883 0.0039626572 0.0079660000 44985405 955859216 1373700096 -0.3310969770 -0.0367911197 -0.0727221668 2666 1311867807.5746030807 0.3653706312 0.3257207017 0.4404943883 0.0039639095 0.0133280000 44988277 955859216 1373700096 -0.3306304216 -0.0390130952 -0.0728872418 2667 1311867807.6121149063 0.3651214540 0.3257354751 0.4404943883 0.0039653982 0.0088380000 44991317 955859216 1373700096 -0.3299366534 -0.0404188186 -0.0733611286 2668 1311867807.6434121132 0.3649666309 0.3257501795 0.4404943883 0.0039664140 0.0083040000 44994189 955859216 1373700096 -0.3297210634 -0.0404973067 -0.0737383142 2669 1311867807.6772611141 0.3643026948 0.3257646240 0.4404943883 0.0039660862 0.0082550000 44997117 955859216 1373700096 -0.3289318383 -0.0411936231 -0.0744662806 2670 1311867807.7112979889 0.3650038838 0.3257793204 0.4404943883 0.0039660901 0.0080320000 45000045 955859216 1373700096 -0.3295881450 -0.0422454104 -0.0747776553 2671 1311867807.7441759109 0.3645823896 0.3257938479 0.4404943883 0.0039681253 0.0081020000 45002973 955859216 1373700096 -0.3296190500 -0.0413557626 -0.0749412179 2672 1311867807.7760479450 0.3637138307 0.3258080395 0.4404943883 0.0039677416 0.0080160000 45005789 955859216 1373700096 -0.3289871514 -0.0411802195 -0.0753117278 2673 1311867807.8105859756 0.3632657528 0.3258220529 0.4404943883 0.0039678056 0.0123800000 45008717 955859216 1373700096 -0.3288212419 -0.0419004895 -0.0755412728 2674 1311867807.8429179192 0.3627842665 0.3258358757 0.4404943883 0.0039679593 0.0085250000 45011589 955859216 1373700096 -0.3286174238 -0.0416570902 -0.0755568072 2675 1311867807.8800721169 0.3616915345 0.3258492797 0.4404943883 0.0039682095 0.0081290000 45014517 955859216 1373700096 -0.3282160461 -0.0407181382 -0.0758138299 2676 1311867807.9118909836 0.3618848622 0.3258627459 0.4404943883 0.0039686882 0.0080670000 45017445 955859216 1373700096 -0.3286848366 -0.0411114432 -0.0759511739 2677 1311867807.9477560520 0.3618078828 0.3258761733 0.4404943883 0.0039689521 0.0081370000 45020373 955859216 1373700096 -0.3285742402 -0.0422931872 -0.0761249140 2678 1311867807.9757928848 0.3614701629 0.3258894645 0.4404943883 0.0039683692 0.0081190000 45023133 955859216 1373700096 -0.3284967840 -0.0420398153 -0.0761767477 2679 1311867808.0103120804 0.3617811501 0.3259028620 0.4404943883 0.0039701839 0.0132300000 45026061 955859216 1373700096 -0.3285517693 -0.0417589247 -0.0763947889 2680 1311867808.0437099934 0.3616814315 0.3259162122 0.4404943883 0.0039697850 0.0088490000 45028989 955859216 1373700096 -0.3283231556 -0.0419161953 -0.0771001950 2681 1311867808.0799739361 0.3627390862 0.3259299469 0.4404943883 0.0039950358 0.0083310000 45031973 955859216 1373700096 -0.3286942840 -0.0428868197 -0.0779776648 2682 1311867808.1118609905 0.3634040952 0.3259439194 0.4404943883 0.0039978040 0.0082510000 45034845 955859216 1373700096 -0.3289355040 -0.0434076488 -0.0788230971 2683 1311867808.1470420361 0.3629240096 0.3259577025 0.4404943883 0.0039974256 0.0083950000 45037773 955859216 1373700096 -0.3283076882 -0.0434577018 -0.0796006471 2684 1311867808.1792190075 0.3627304435 0.3259714032 0.4404943883 0.0039980758 0.0082510000 45040589 955859216 1373700096 -0.3281647563 -0.0429003239 -0.0806780756 2685 1311867808.2112250328 0.3626049161 0.3259850470 0.4404943883 0.0040189960 0.0082080000 45043517 955859216 1373700096 -0.3285032511 -0.0438740365 -0.0817441419 2686 1311867808.2432029247 0.3629081547 0.3259987935 0.4404943883 0.0040185506 0.0122990000 45046445 955859216 1373700096 -0.3283551633 -0.0444050580 -0.0826914832 2687 1311867808.2811930180 0.3632687926 0.3260126640 0.4404943883 0.0040192402 0.0088310000 45049429 955859216 1373700096 -0.3285732567 -0.0439481139 -0.0835156292 2688 1311867808.3112449646 0.3638265133 0.3260267316 0.4404943883 0.0040189515 0.0084500000 45052245 955859216 1373700096 -0.3288049996 -0.0440455563 -0.0839654654 2689 1311867808.3454720974 0.3645048738 0.3260410411 0.4404943883 0.0040186575 0.0082730000 45055173 955859216 1373700096 -0.3291150033 -0.0441818014 -0.0843688026 2690 1311867808.3792409897 0.3641181588 0.3260551962 0.4404943883 0.0040183947 0.0124500000 45058045 955859216 1373700096 -0.3287550807 -0.0437104627 -0.0847270340 2691 1311867808.4111659527 0.3642807007 0.3260694011 0.4404943883 0.0040185060 0.0089890000 45060973 955859216 1373700096 -0.3287460506 -0.0433140844 -0.0855064243 2692 1311867808.4447789192 0.3640826344 0.3260835219 0.4404943883 0.0040183837 0.0083880000 45063845 955859216 1373700096 -0.3285776079 -0.0422846824 -0.0858710632 2693 1311867808.4827229977 0.3645450473 0.3260978040 0.4404943883 0.0040193935 0.0229160000 45066941 955859216 1373700096 -0.3289318979 -0.0427964851 -0.0860967860 2694 1311867808.5103700161 0.3646056652 0.3261120979 0.4404943883 0.0040240662 0.0110330000 45069645 955859216 1373700096 -0.3287792206 -0.0429294482 -0.0865565166 2695 1311867808.5431969166 0.3645807207 0.3261263720 0.4404943883 0.0040239642 0.0088430000 45072629 955859216 1373700096 -0.3288011253 -0.0422310866 -0.0868869871 2696 1311867808.5788240433 0.3657475412 0.3261410682 0.4404943883 0.0040233534 0.0086750000 45075557 955859216 1373700096 -0.3296743929 -0.0432118811 -0.0873457789 2697 1311867808.6111960411 0.3653846383 0.3261556191 0.4404943883 0.0040226914 0.0084590000 45078429 955859216 1373700096 -0.3293981552 -0.0433761068 -0.0876523554 2698 1311867808.6424980164 0.3660241961 0.3261703962 0.4404943883 0.0040220700 0.0084210000 45081301 955859216 1373700096 -0.3300122321 -0.0437926389 -0.0879760087 2699 1311867808.6796329021 0.3660489917 0.3261851715 0.4404943883 0.0040217730 0.0083120000 45084229 955859216 1373700096 -0.3301317394 -0.0437361896 -0.0884110481 2700 1311867808.7121589184 0.3661731482 0.3261999818 0.4404943883 0.0040211416 0.0083670000 45087213 955859216 1373700096 -0.3302084208 -0.0437626764 -0.0890062749 2701 1311867808.7424249649 0.3655267656 0.3262145419 0.4404943883 0.0040210189 0.0084830000 45090029 955859216 1373700096 -0.3291010261 -0.0446338877 -0.0896999389 2702 1311867808.7797210217 0.3666077256 0.3262294913 0.4404943883 0.0040214347 0.0083740000 45093013 955859216 1373700096 -0.3298725784 -0.0450960286 -0.0900122970 2703 1311867808.8102169037 0.3652074635 0.3262439115 0.4404943883 0.0040216411 0.0128590000 45095829 955859216 1373700096 -0.3284116089 -0.0446207486 -0.0908441842 2704 1311867808.8426899910 0.3664729297 0.3262587891 0.4404943883 0.0040249292 0.0088740000 45098701 955859216 1373700096 -0.3291283548 -0.0459539928 -0.0917564258 2705 1311867808.8811960220 0.3669030666 0.3262738148 0.4404943883 0.0040243838 0.0084070000 45101797 955859216 1373700096 -0.3292832375 -0.0460426360 -0.0924400240 2706 1311867808.9101860523 0.3669888973 0.3262888610 0.4404943883 0.0040238248 0.0084680000 45104557 955859216 1373700096 -0.3292672932 -0.0459793508 -0.0928351656 2707 1311867808.9424829483 0.3678460121 0.3263042127 0.4404943883 0.0040234685 0.0084870000 45107485 955859216 1373700096 -0.3296474814 -0.0477941670 -0.0935002491 2708 1311867808.9811229706 0.3683354855 0.3263197339 0.4404943883 0.0040252566 0.0084330000 45110525 955859216 1373700096 -0.3299725354 -0.0481081568 -0.0942814425 2709 1311867809.0102269650 0.3681524992 0.3263351760 0.4404943883 0.0040251369 0.0085070000 45113285 955859216 1373700096 -0.3297583759 -0.0482371971 -0.0950469002 2710 1311867809.0425639153 0.3683743477 0.3263506886 0.4404943883 0.0040247974 0.0082450000 45116213 955859216 1373700096 -0.3292578459 -0.0501541980 -0.0959490836 2711 1311867809.0782320499 0.3684672713 0.3263662241 0.4404943883 0.0040261312 0.0123270000 45119141 955859216 1373700096 -0.3293354511 -0.0496572554 -0.0963679031 2712 1311867809.1110110283 0.3678310812 0.3263815135 0.4404943883 0.0040256521 0.0088940000 45122069 955859216 1373700096 -0.3286481202 -0.0490590781 -0.0971504822 2713 1311867809.1425359249 0.3676265180 0.3263967162 0.4404943883 0.0040254079 0.0134020000 45124941 955859216 1373700096 -0.3280331194 -0.0499106050 -0.0978431702 2714 1311867809.1801810265 0.3682745099 0.3264121465 0.4404943883 0.0040255799 0.0091030000 45127925 955859216 1373700096 -0.3284976482 -0.0495222658 -0.0984143168 2715 1311867809.2120649815 0.3685550094 0.3264276687 0.4404943883 0.0040261119 0.0086170000 45130797 955859216 1373700096 -0.3288142681 -0.0479253642 -0.0984291211 2716 1311867809.2422831059 0.3672308326 0.3264426920 0.4404943883 0.0040254795 0.0083560000 45133669 955859216 1373700096 -0.3271549940 -0.0479395390 -0.0989620537 2717 1311867809.2790520191 0.3686669469 0.3264582327 0.4404943883 0.0040248680 0.0083170000 45136541 955859216 1373700096 -0.3280258775 -0.0486735851 -0.0991528928 2718 1311867809.3103950024 0.3682080209 0.3264735932 0.4404943883 0.0040242495 0.0082230000 45139413 955859216 1373700096 -0.3270827532 -0.0485224798 -0.0993420258 2719 1311867809.3436670303 0.3684509695 0.3264890317 0.4404943883 0.0040236345 0.0082620000 45142341 955859216 1373700096 -0.3266848624 -0.0487152860 -0.0996092409 2720 1311867809.3787779808 0.3680730462 0.3265043200 0.4404943883 0.0040229826 0.0082220000 45145213 955859216 1373700096 -0.3255010545 -0.0495246612 -0.1000881791 2721 1311867809.4101309776 0.3681413531 0.3265196221 0.4404943883 0.0040226784 0.0092560000 45148085 955859216 1373700096 -0.3248665333 -0.0498566926 -0.1006419510 2722 1311867809.4475460052 0.3696533442 0.3265354684 0.4404943883 0.0040232364 0.0084220000 45151125 955859216 1373700096 -0.3252804577 -0.0504180901 -0.1007753760 2723 1311867809.4785499573 0.3692501187 0.3265511550 0.4404943883 0.0040228832 0.0083770000 45154053 955859216 1373700096 -0.3241056502 -0.0509854145 -0.1013260856 2724 1311867809.5100600719 0.3689576387 0.3265667228 0.4404943883 0.0040229285 0.0082300000 45156813 955859216 1373700096 -0.3230850697 -0.0508111194 -0.1019676700 2725 1311867809.5460391045 0.3694191873 0.3265824484 0.4404943883 0.0040224419 0.0082320000 45159853 955859216 1373700096 -0.3227089047 -0.0503504537 -0.1024071127 2726 1311867809.5791211128 0.3699802458 0.3265983684 0.4404943883 0.0040218527 0.0084100000 45162725 955859216 1373700096 -0.3222016394 -0.0503874496 -0.1027984396 2727 1311867809.6122300625 0.3697480857 0.3266141915 0.4404943883 0.0040215433 0.0082490000 45165653 955859216 1373700096 -0.3213963509 -0.0495771170 -0.1033601165 2728 1311867809.6463921070 0.3696366549 0.3266299622 0.4404943883 0.0040210695 0.0083140000 45168581 955859216 1373700096 -0.3204851151 -0.0489973314 -0.1037744507 2729 1311867809.6796839237 0.3696169853 0.3266457142 0.4404943883 0.0040206095 0.0081780000 45171453 955859216 1373700096 -0.3195998967 -0.0481496342 -0.1038056687 2730 1311867809.7111020088 0.3691926003 0.3266612991 0.4404943883 0.0040201342 0.0081530000 45174325 955859216 1373700096 -0.3180373907 -0.0485668294 -0.1044054180 2731 1311867809.7464809418 0.3694475889 0.3266769660 0.4404943883 0.0040195617 0.0082400000 45177309 955859216 1373700096 -0.3170614541 -0.0493051931 -0.1053124443 2732 1311867809.7800478935 0.3705929518 0.3266930407 0.4404943883 0.0040190752 0.0082350000 45180181 955859216 1373700096 -0.3170369565 -0.0495977849 -0.1060902104 2733 1311867809.8107759953 0.3697414994 0.3267087920 0.4404943883 0.0040193173 0.0082670000 45183053 955859216 1373700096 -0.3151722550 -0.0495949276 -0.1073522493 2734 1311867809.8470799923 0.3704413176 0.3267247878 0.4404943883 0.0040188068 0.0081650000 45186037 955859216 1373700096 -0.3148670793 -0.0506002530 -0.1085804254 2735 1311867809.8791100979 0.3709238768 0.3267409484 0.4404943883 0.0040184387 0.0081960000 45188909 955859216 1373700096 -0.3144620061 -0.0514462851 -0.1102730408 2736 1311867809.9124441147 0.3709412813 0.3267571035 0.4404943883 0.0040182349 0.0083070000 45191781 955859216 1373700096 -0.3135906458 -0.0521882251 -0.1116115823 2737 1311867809.9469900131 0.3710636795 0.3267732915 0.4404943883 0.0040181302 0.0082430000 45194709 955859216 1373700096 -0.3130823970 -0.0530486591 -0.1127457619 2738 1311867809.9805769920 0.3717686236 0.3267897251 0.4404943883 0.0040194380 0.0084210000 45197525 955859216 1373700096 -0.3136679232 -0.0530682392 -0.1137636602 2739 1311867810.0119459629 0.3713464439 0.3268059926 0.4404943883 0.0040189144 0.0083440000 45200341 955859216 1373700096 -0.3132092059 -0.0529600270 -0.1148054302 2740 1311867810.0470910072 0.3714241385 0.3268222766 0.4404943883 0.0040183371 0.0083230000 45203269 955859216 1373700096 -0.3131567538 -0.0534959398 -0.1150953099 2741 1311867810.0808799267 0.3707859516 0.3268383159 0.4404943883 0.0040185897 0.0084220000 45206141 955859216 1373700096 -0.3129222989 -0.0525478832 -0.1155435815 2742 1311867810.1118919849 0.3698539436 0.3268540036 0.4404943883 0.0040179097 0.0129810000 45209013 955859216 1373700096 -0.3120561242 -0.0523504093 -0.1158746108 2743 1311867810.1474719048 0.3700958192 0.3268697680 0.4404943883 0.0040173742 0.0091140000 45211997 955859216 1373700096 -0.3122300804 -0.0527890064 -0.1162742376 2744 1311867810.1817660332 0.3698360026 0.3268854263 0.4404943883 0.0040167767 0.0083990000 45214869 955859216 1373700096 -0.3120348752 -0.0527445190 -0.1166977882 2745 1311867810.2106039524 0.3692913353 0.3269008747 0.4404943883 0.0040161328 0.0085630000 45217685 955859216 1373700096 -0.3115713000 -0.0521732979 -0.1174347028 2746 1311867810.2471721172 0.3693684638 0.3269163399 0.4404943883 0.0040177417 0.0083360000 45220669 955859216 1373700096 -0.3112853169 -0.0517974831 -0.1180825606 2747 1311867810.2785871029 0.3698107600 0.3269319549 0.4404943883 0.0040171330 0.0083750000 45223485 955859216 1373700096 -0.3118206263 -0.0514895208 -0.1188160107 2748 1311867810.3111360073 0.3705150783 0.3269478149 0.4404943883 0.0040167374 0.0082680000 45226413 955859216 1373700096 -0.3125874996 -0.0513173714 -0.1193309203 2749 1311867810.3463029861 0.3710525036 0.3269638588 0.4404943883 0.0040164041 0.0084280000 45229397 955859216 1373700096 -0.3129194379 -0.0518459678 -0.1196854487 2750 1311867810.3784830570 0.3723269701 0.3269803545 0.4404943883 0.0040161306 0.0083570000 45232325 955859216 1373700096 -0.3141250014 -0.0526096411 -0.1201992482 2751 1311867810.4100239277 0.3724105060 0.3269968685 0.4404943883 0.0040158428 0.0231540000 45235085 955859216 1373700096 -0.3142528832 -0.0529308058 -0.1209144816 2752 1311867810.4462749958 0.3730457425 0.3270136014 0.4404943883 0.0040152571 0.0105000000 45238069 955859216 1373700096 -0.3148406148 -0.0531622507 -0.1214814633 2753 1311867810.4781119823 0.3734438121 0.3270304667 0.4404943883 0.0040146272 0.0086880000 45240885 955859216 1373700096 -0.3153530955 -0.0522956327 -0.1220506281 2754 1311867810.5101990700 0.3738864660 0.3270474805 0.4404943883 0.0040139606 0.0084610000 45243757 955859216 1373700096 -0.3158374727 -0.0514949672 -0.1223084927 2755 1311867810.5459640026 0.3741894364 0.3270645919 0.4404943883 0.0040133957 0.0084690000 45246741 955859216 1373700096 -0.3158668578 -0.0514498539 -0.1227310300 2756 1311867810.5791409016 0.3739742637 0.3270816129 0.4404943883 0.0040126975 0.0082550000 45249613 955859216 1373700096 -0.3157311976 -0.0507617556 -0.1232362688 2757 1311867810.6141140461 0.3747134209 0.3270988895 0.4404943883 0.0040121112 0.0081890000 45252597 955859216 1373700096 -0.3165511787 -0.0505800471 -0.1234724671 2758 1311867810.6471910477 0.3748102486 0.3271161888 0.4404943883 0.0040115742 0.0080280000 45255525 955859216 1373700096 -0.3166182935 -0.0508524328 -0.1237294301 2759 1311867810.6781129837 0.3749080002 0.3271335109 0.4404943883 0.0040110573 0.0082100000 45258341 955859216 1373700096 -0.3168983757 -0.0501481146 -0.1239543483 2760 1311867810.7146449089 0.3740791082 0.3271505202 0.4404943883 0.0040107021 0.0080760000 45261325 955859216 1373700096 -0.3159104288 -0.0497460626 -0.1242859364 2761 1311867810.7468900681 0.3740710616 0.3271675143 0.4404943883 0.0040101560 0.0083220000 45264253 955859216 1373700096 -0.3158270121 -0.0499728248 -0.1247782707 2762 1311867810.7789669037 0.3742853403 0.3271845736 0.4404943883 0.0040102153 0.0084440000 45267125 955859216 1373700096 -0.3159061968 -0.0499294847 -0.1252793968 2763 1311867810.8146491051 0.3744145036 0.3272016673 0.4404943883 0.0040096036 0.0084440000 45270053 955859216 1373700096 -0.3155552745 -0.0504750609 -0.1258376390 2764 1311867810.8460769653 0.3756405711 0.3272191922 0.4404943883 0.0040134417 0.0083260000 45272925 955859216 1373700096 -0.3168684542 -0.0501665138 -0.1260289550 2765 1311867810.8793289661 0.3750230372 0.3272364811 0.4404943883 0.0040133983 0.0084980000 45275853 955859216 1373700096 -0.3160938025 -0.0495408811 -0.1260749996 2766 1311867810.9141631126 0.3756568134 0.3272539867 0.4404943883 0.0040141866 0.0083740000 45278837 955859216 1373700096 -0.3162362874 -0.0500801131 -0.1258269399 2767 1311867810.9458940029 0.3760825992 0.3272716334 0.4404943883 0.0040183237 0.0085160000 45281653 955859216 1373700096 -0.3160506785 -0.0501357727 -0.1260143816 2768 1311867810.9796259403 0.3748643696 0.3272888273 0.4404943883 0.0040179290 0.0083240000 45284525 955859216 1373700096 -0.3145614862 -0.0495478921 -0.1266533732 2769 1311867811.0151500702 0.3753526807 0.3273061852 0.4404943883 0.0040224990 0.0085920000 45287509 955859216 1373700096 -0.3148660660 -0.0495015457 -0.1271909028 2770 1311867811.0469939709 0.3755381107 0.3273235974 0.4404943883 0.0040225783 0.0084150000 45290381 955859216 1373700096 -0.3146912158 -0.0490578040 -0.1275170892 2771 1311867811.0785760880 0.3759374917 0.3273411412 0.4404943883 0.0040225812 0.0084800000 45293253 955859216 1373700096 -0.3146530986 -0.0489625260 -0.1279872507 2772 1311867811.1144239902 0.3754147589 0.3273584838 0.4404943883 0.0040227483 0.0083710000 45296237 955859216 1373700096 -0.3139030933 -0.0484800413 -0.1284679323 2773 1311867811.1461989880 0.3762359619 0.3273761100 0.4404943883 0.0040231800 0.0084820000 45299109 955859216 1373700096 -0.3144043684 -0.0481316037 -0.1287005395 2774 1311867811.1786370277 0.3762941957 0.3273937445 0.4404943883 0.0040227509 0.0084060000 45302037 955859216 1373700096 -0.3140347898 -0.0477469116 -0.1290062815 2775 1311867811.2142488956 0.3750754595 0.3274109271 0.4404943883 0.0040223079 0.0085560000 45304909 955859216 1373700096 -0.3124122620 -0.0473198406 -0.1295529902 2776 1311867811.2464840412 0.3746061623 0.3274279283 0.4404943883 0.0040219286 0.0090010000 45307837 955859216 1373700096 -0.3119260073 -0.0463020951 -0.1297958493 2777 1311867811.2798390388 0.3746122718 0.3274449194 0.4404943883 0.0040215923 0.0139080000 45310765 955859216 1373700096 -0.3117206097 -0.0456819311 -0.1300583780 2778 1311867811.3147039413 0.3751885295 0.3274621057 0.4404943883 0.0040221712 0.0091770000 45313693 955859216 1373700096 -0.3119885921 -0.0456665270 -0.1304632276 2779 1311867811.3470849991 0.3746583760 0.3274790889 0.4404943883 0.0040228538 0.0087050000 45316565 955859216 1373700096 -0.3113460243 -0.0452202037 -0.1309237182 2780 1311867811.3799240589 0.3755193651 0.3274963696 0.4404943883 0.0040225801 0.0085070000 45319437 955859216 1373700096 -0.3119382262 -0.0445120186 -0.1311420649 2781 1311867811.4141869545 0.3752321899 0.3275135346 0.4404943883 0.0040228239 0.0085550000 45322365 955859216 1373700096 -0.3111276031 -0.0442912951 -0.1313492805 2782 1311867811.4464430809 0.3755090833 0.3275307867 0.4404943883 0.0040222784 0.0085160000 45325293 955859216 1373700096 -0.3109824955 -0.0439360887 -0.1319645494 2783 1311867811.4788289070 0.3751835525 0.3275479096 0.4404943883 0.0040223504 0.0085980000 45328221 955859216 1373700096 -0.3103881180 -0.0433561392 -0.1326705813 2784 1311867811.5141620636 0.3752832413 0.3275650559 0.4404943883 0.0040236226 0.0084520000 45331093 955859216 1373700096 -0.3098518848 -0.0433098301 -0.1327347308 2785 1311867811.5465340614 0.3748558760 0.3275820364 0.4404943883 0.0040237723 0.0085600000 45334021 955859216 1373700096 -0.3086013794 -0.0433481075 -0.1329755932 2786 1311867811.5787150860 0.3745483458 0.3275988944 0.4404943883 0.0040271437 0.0084260000 45336893 955859216 1373700096 -0.3078378141 -0.0423472263 -0.1339856237 2787 1311867811.6143789291 0.3732197285 0.3276152635 0.4404943883 0.0040406436 0.0086790000 45339821 955859216 1373700096 -0.3086968958 -0.0330984332 -0.1337531507 2788 1311867811.6465210915 0.3725801408 0.3276313915 0.4404943883 0.0040475470 0.0085010000 45342749 955859216 1373700096 -0.3064827919 -0.0376913995 -0.1340247244 2789 1311867811.6790111065 0.3735357523 0.3276478506 0.4404943883 0.0040486418 0.0127360000 45345565 955859216 1373700096 -0.3063398302 -0.0392581969 -0.1339106858 2790 1311867811.7141160965 0.3723900914 0.3276638873 0.4404943883 0.0040491158 0.0089900000 45348549 955859216 1373700096 -0.3048377037 -0.0382231511 -0.1342376024 2791 1311867811.7471590042 0.3724674582 0.3276799401 0.4404943883 0.0040491529 0.0085770000 45351477 955859216 1373700096 -0.3047581911 -0.0380524360 -0.1346938163 2792 1311867811.7787630558 0.3721832931 0.3276958797 0.4404943883 0.0040485391 0.0084530000 45354349 955859216 1373700096 -0.3042050600 -0.0384918116 -0.1352784038 2793 1311867811.8140239716 0.3720840812 0.3277117724 0.4404943883 0.0040479869 0.0085050000 45357333 955859216 1373700096 -0.3040571809 -0.0382307358 -0.1355039030 2794 1311867811.8467700481 0.3716921806 0.3277275134 0.4404943883 0.0040473982 0.0084950000 45360205 955859216 1373700096 -0.3034369051 -0.0381801017 -0.1356581002 2795 1311867811.8873019218 0.3710733652 0.3277430218 0.4404943883 0.0040472857 0.0085880000 45363301 955859216 1373700096 -0.3026663661 -0.0379338898 -0.1359345168 2796 1311867811.9162950516 0.3703986704 0.3277582777 0.4404943883 0.0040467392 0.0084770000 45366005 955859216 1373700096 -0.3020417392 -0.0376916938 -0.1364362985 2797 1311867811.9480459690 0.3708575070 0.3277736868 0.4404943883 0.0040463344 0.0085820000 45368821 955859216 1373700096 -0.3024022579 -0.0377722681 -0.1366233826 2798 1311867811.9825990200 0.3708429933 0.3277890797 0.4404943883 0.0040459817 0.0127040000 45371805 955859216 1373700096 -0.3021037281 -0.0380901918 -0.1370835751 2799 1311867812.0155920982 0.3703017831 0.3278042682 0.4404943883 0.0040454804 0.0091010000 45374677 955859216 1373700096 -0.3012467325 -0.0380498357 -0.1372462660 2800 1311867812.0471529961 0.3695597649 0.3278191809 0.4404943883 0.0040449123 0.0084440000 45377549 955859216 1373700096 -0.3004411161 -0.0377732143 -0.1376612484 2801 1311867812.0860528946 0.3708579540 0.3278345464 0.4404943883 0.0040444390 0.0087100000 45380645 955859216 1373700096 -0.3014767468 -0.0381398238 -0.1376534551 2802 1311867812.1176469326 0.3707042336 0.3278498461 0.4404943883 0.0040440215 0.0086810000 45383517 955859216 1373700096 -0.3010555506 -0.0383270122 -0.1375846863 2803 1311867812.1501319408 0.3696876168 0.3278647722 0.4404943883 0.0040433565 0.0090420000 45386333 955859216 1373700096 -0.2997522056 -0.0380750783 -0.1377624124 2804 1311867812.1841530800 0.3701356947 0.3278798474 0.4404943883 0.0040427355 0.0090110000 45389317 955859216 1373700096 -0.2997882962 -0.0382572673 -0.1376129240 2805 1311867812.2161788940 0.3706889451 0.3278951091 0.4404943883 0.0040485883 0.0087990000 45392189 955859216 1373700096 -0.2996194363 -0.0386342630 -0.1375045627 2806 1311867812.2469139099 0.3709404171 0.3279104495 0.4404943883 0.0040482725 0.0085560000 45395005 955859216 1373700096 -0.2996312082 -0.0384475477 -0.1375447214 2807 1311867812.2830879688 0.3706839383 0.3279256877 0.4404943883 0.0040588547 0.0085920000 45398045 955859216 1373700096 -0.2992517352 -0.0383152664 -0.1375799477 2808 1311867812.3143959045 0.3704691529 0.3279408385 0.4404943883 0.0040672993 0.0085400000 45400805 955859216 1373700096 -0.2983060777 -0.0382371023 -0.1374344826 2809 1311867812.3466560841 0.3698994219 0.3279557757 0.4404943883 0.0040666513 0.0086430000 45403733 955859216 1373700096 -0.2972829640 -0.0380703956 -0.1371945292 2810 1311867812.3833289146 0.3695058823 0.3279705622 0.4404943883 0.0040669141 0.0085200000 45406773 955859216 1373700096 -0.2965542376 -0.0377699025 -0.1371246278 2811 1311867812.4177269936 0.3701692522 0.3279855742 0.4404943883 0.0040663724 0.0139920000 45409701 955859216 1373700096 -0.2966384888 -0.0376134999 -0.1371731013 2812 1311867812.4586019516 0.3701318800 0.3280005622 0.4404943883 0.0040659117 0.0092650000 45412797 955859216 1373700096 -0.2959378958 -0.0379073583 -0.1369667351 2813 1311867812.4830911160 0.3703395724 0.3280156134 0.4404943883 0.0040655477 0.0086650000 45415333 955859216 1373700096 -0.2961131334 -0.0377137549 -0.1372710317 2814 1311867812.5157220364 0.3702278137 0.3280306142 0.4404943883 0.0040697346 0.0087130000 45418149 955859216 1373700096 -0.2960490882 -0.0374233611 -0.1373640746 2815 1311867812.5469310284 0.3699038923 0.3280454892 0.4404943883 0.0040691279 0.0088210000 45421021 955859216 1373700096 -0.2953576744 -0.0372400768 -0.1375907063 2816 1311867812.5857439041 0.3702242970 0.3280604675 0.4404943883 0.0040685720 0.0129430000 45424061 955859216 1373700096 -0.2952401638 -0.0375096947 -0.1375568211 2817 1311867812.6147639751 0.3694283962 0.3280751526 0.4404943883 0.0040679119 0.0090560000 45426821 955859216 1373700096 -0.2941973805 -0.0374362767 -0.1377635896 2818 1311867812.6462490559 0.3700459898 0.3280900465 0.4404943883 0.0040679975 0.0130510000 45429749 955859216 1373700096 -0.2946566045 -0.0373872928 -0.1378560513 2819 1311867812.6821310520 0.3695520759 0.3281047545 0.4404943883 0.0040675570 0.0090300000 45432733 955859216 1373700096 -0.2940743268 -0.0371882431 -0.1381543428 2820 1311867812.7141439915 0.3689517677 0.3281192393 0.4404943883 0.0040674300 0.0085360000 45435549 955859216 1373700096 -0.2936353981 -0.0367029496 -0.1382107288 2821 1311867812.7468860149 0.3687506616 0.3281336425 0.4404943883 0.0040669045 0.0084840000 45438477 955859216 1373700096 -0.2935622036 -0.0364343226 -0.1385736018 2822 1311867812.7839629650 0.3694493175 0.3281482830 0.4404943883 0.0040665918 0.0083750000 45441517 955859216 1373700096 -0.2943562865 -0.0362736396 -0.1384005845 2823 1311867812.8143351078 0.3685297072 0.3281625875 0.4404943883 0.0040679735 0.0224860000 45444277 955859216 1373700096 -0.2935683727 -0.0358002819 -0.1386179030 2824 1311867812.8463029861 0.3683092892 0.3281768037 0.4404943883 0.0040674940 0.0102840000 45447205 955859216 1373700096 -0.2936082780 -0.0354109369 -0.1388916522 2825 1311867812.8841478825 0.3683092892 0.3281910099 0.4404943883 0.0040713421 0.0087090000 45450245 955859216 1373700096 -0.2941414416 -0.0349997319 -0.1391279995 2826 1311867812.9142088890 0.3683865964 0.3282052334 0.4404943883 0.0040710662 0.0085500000 45453005 955859216 1373700096 -0.2944642603 -0.0351937078 -0.1391928792 2827 1311867812.9470400810 0.3688666821 0.3282196167 0.4404943883 0.0040705322 0.0087080000 45455933 955859216 1373700096 -0.2952696979 -0.0350582749 -0.1388755292 2828 1311867812.9833469391 0.3687172234 0.3282339369 0.4404943883 0.0040707576 0.0086990000 45458861 955859216 1373700096 -0.2957051694 -0.0340130329 -0.1387069225 2829 1311867813.0143780708 0.3686068952 0.3282482080 0.4404943883 0.0040774391 0.0087880000 45461733 955859216 1373700096 -0.2957414687 -0.0337359346 -0.1388076991 2830 1311867813.0462698936 0.3685721159 0.3282624567 0.4404943883 0.0040856343 0.0085590000 45464605 955859216 1373700096 -0.2963722944 -0.0333676226 -0.1386076212 2831 1311867813.0825068951 0.3668804765 0.3282760978 0.4404943883 0.0040910268 0.0086530000 45467645 955859216 1373700096 -0.2950935364 -0.0328944698 -0.1390377581 2832 1311867813.1142160892 0.3681102395 0.3282901636 0.4404943883 0.0040966792 0.0085460000 45470517 955859216 1373700096 -0.2969502509 -0.0328133814 -0.1387454271 2833 1311867813.1504809856 0.3681334853 0.3283042276 0.4404943883 0.0040970506 0.0086520000 45473445 955859216 1373700096 -0.2968879342 -0.0335631967 -0.1388117820 2834 1311867813.1829130650 0.3667928576 0.3283178086 0.4404943883 0.0040972773 0.0085830000 45476373 955859216 1373700096 -0.2962569594 -0.0324779265 -0.1390861124 2835 1311867813.2166841030 0.3678462803 0.3283317516 0.4404943883 0.0040975370 0.0085870000 45479245 955859216 1373700096 -0.2978335917 -0.0320140310 -0.1391279399 2836 1311867813.2536849976 0.3675004244 0.3283455629 0.4404943883 0.0040981841 0.0084670000 45482229 955859216 1373700096 -0.2978296876 -0.0323911980 -0.1392245889 2837 1311867813.2831010818 0.3673906028 0.3283593257 0.4404943883 0.0041058270 0.0084140000 45485045 955859216 1373700096 -0.2977447212 -0.0316184796 -0.1393287182 2838 1311867813.3142321110 0.3677498102 0.3283732053 0.4404943883 0.0041072290 0.0082270000 45487917 955859216 1373700096 -0.2986431718 -0.0309851784 -0.1394956708 2839 1311867813.3517169952 0.3674260378 0.3283869612 0.4404943883 0.0041270248 0.0083780000 45490901 955859216 1373700096 -0.2987297475 -0.0315096341 -0.1393201053 2840 1311867813.3851261139 0.3688715994 0.3284012163 0.4404943883 0.0041267015 0.0082270000 45493829 955859216 1373700096 -0.3001745045 -0.0315595493 -0.1388746351 2841 1311867813.4148280621 0.3679906428 0.3284151514 0.4404943883 0.0041447754 0.0128680000 45496589 955859216 1373700096 -0.2990593314 -0.0310344826 -0.1388587654 2842 1311867813.4501829147 0.3669984341 0.3284287275 0.4404943883 0.0041606352 0.0092160000 45499517 955859216 1373700096 -0.2982521057 -0.0305499509 -0.1390393823 2843 1311867813.4843769073 0.3675411344 0.3284424849 0.4404943883 0.0041615101 0.0087270000 45502501 955859216 1373700096 -0.2985925674 -0.0297738332 -0.1387913674 2844 1311867813.5152790546 0.3666888177 0.3284559330 0.4404943883 0.0041675116 0.0085490000 45505317 955859216 1373700096 -0.2978957295 -0.0295429807 -0.1386448741 2845 1311867813.5519089699 0.3672430515 0.3284695664 0.4404943883 0.0041710649 0.0085850000 45508301 955859216 1373700096 -0.2986278236 -0.0286697969 -0.1386573166 2846 1311867813.5863409042 0.3674015999 0.3284832460 0.4404943883 0.0041706846 0.0085190000 45511229 955859216 1373700096 -0.2991401553 -0.0275980886 -0.1388110816 2847 1311867813.6168019772 0.3671185374 0.3284968165 0.4404943883 0.0041873459 0.0086460000 45514045 955859216 1373700096 -0.2992892265 -0.0272297841 -0.1388106942 2848 1311867813.6515810490 0.3678102195 0.3285106204 0.4404943883 0.0041872311 0.0085010000 45516973 955859216 1373700096 -0.2998906374 -0.0267325006 -0.1387505829 2849 1311867813.6860060692 0.3675440848 0.3285243211 0.4404943883 0.0041868745 0.0086950000 45519901 955859216 1373700096 -0.2993671596 -0.0261612963 -0.1391064525 2850 1311867813.7184169292 0.3675347269 0.3285380090 0.4404943883 0.0041862538 0.0085290000 45522773 955859216 1373700096 -0.2994050384 -0.0253743269 -0.1393778771 2851 1311867813.7506020069 0.3674284220 0.3285516500 0.4404943883 0.0041858187 0.0086270000 45525645 955859216 1373700096 -0.2995020449 -0.0244677365 -0.1399511397 2852 1311867813.7827889919 0.3687347174 0.3285657394 0.4404943883 0.0041852836 0.0135990000 45528573 955859216 1373700096 -0.3007428944 -0.0236615147 -0.1404094547 2853 1311867813.8147668839 0.3695203364 0.3285800943 0.4404943883 0.0041846900 0.0093470000 45531333 955859216 1373700096 -0.3013657629 -0.0229124445 -0.1404059380 2854 1311867813.8517930508 0.3698160052 0.3285945428 0.4404943883 0.0041843979 0.0138630000 45534429 955859216 1373700096 -0.3014232218 -0.0223302823 -0.1408400387 2855 1311867813.8838069439 0.3698974252 0.3286090096 0.4404943883 0.0041847431 0.0102780000 45537245 955859216 1373700096 -0.3009507358 -0.0213153623 -0.1415076256 2856 1311867813.9144020081 0.3723450005 0.3286243234 0.4404943883 0.0041845050 0.0090710000 45540061 955859216 1373700096 -0.3033638299 -0.0207937472 -0.1416442096 2857 1311867813.9523379803 0.3724694252 0.3286396699 0.4404943883 0.0041842037 0.0088610000 45543157 955859216 1373700096 -0.3030507863 -0.0202919338 -0.1416887045 2858 1311867813.9825320244 0.3730714023 0.3286552164 0.4404943883 0.0041839644 0.0140070000 45545973 955859216 1373700096 -0.3033534586 -0.0185010247 -0.1420979351 2859 1311867814.0155770779 0.3747934699 0.3286713543 0.4404943883 0.0041883853 0.0094550000 45548845 955859216 1373700096 -0.3040222228 -0.0179227106 -0.1420670748 2860 1311867814.0528070927 0.3742754161 0.3286872997 0.4404943883 0.0041878575 0.0086090000 45551941 955859216 1373700096 -0.3035012782 -0.0173323900 -0.1423930824 2861 1311867814.0849530697 0.3738419414 0.3287030825 0.4404943883 0.0041877437 0.0087120000 45554757 955859216 1373700096 -0.3030611873 -0.0158278849 -0.1428924203 2862 1311867814.1153879166 0.3746465445 0.3287191355 0.4404943883 0.0041876712 0.0086700000 45557573 955859216 1373700096 -0.3034654558 -0.0155887110 -0.1429351270 2863 1311867814.1526429653 0.3751292825 0.3287353458 0.4404943883 0.0041874868 0.0231190000 45560669 955859216 1373700096 -0.3032233119 -0.0153797101 -0.1428704113 2864 1311867814.1845281124 0.3751121759 0.3287515388 0.4404943883 0.0041877713 0.0103860000 45563541 955859216 1373700096 -0.3029075861 -0.0144374222 -0.1432526112 2865 1311867814.2153480053 0.3738641441 0.3287672849 0.4404943883 0.0041877737 0.0087070000 45566301 955859216 1373700096 -0.3013383746 -0.0144936973 -0.1434188634 2866 1311867814.2520170212 0.3726738393 0.3287826047 0.4404943883 0.0041881530 0.0086630000 45569341 955859216 1373700096 -0.2999926209 -0.0136305653 -0.1437721401 2867 1311867814.2834239006 0.3713754117 0.3287974610 0.4404943883 0.0041876563 0.0098060000 45572269 955859216 1373700096 -0.2981803715 -0.0136194387 -0.1441307366 2868 1311867814.3181779385 0.3705308437 0.3288120123 0.4404943883 0.0041875681 0.0138540000 45575197 955859216 1373700096 -0.2971124053 -0.0128400614 -0.1446465701 2869 1311867814.3510050774 0.3690130711 0.3288260246 0.4404943883 0.0041902699 0.0091680000 45578013 955859216 1373700096 -0.2953317761 -0.0120893577 -0.1452963054 2870 1311867814.3861339092 0.3694052100 0.3288401637 0.4404943883 0.0041896163 0.0086350000 45580997 955859216 1373700096 -0.2955589592 -0.0118704149 -0.1455558389 2871 1311867814.4182898998 0.3693659604 0.3288542792 0.4404943883 0.0041892172 0.0084360000 45583869 955859216 1373700096 -0.2952623367 -0.0114963539 -0.1459407359 2872 1311867814.4512650967 0.3674957454 0.3288677338 0.4404943883 0.0041892255 0.0083550000 45586797 955859216 1373700096 -0.2933484912 -0.0105032623 -0.1467129141 2873 1311867814.4847788811 0.3692002594 0.3288817722 0.4404943883 0.0041886870 0.0140210000 45589669 955859216 1373700096 -0.2950333059 -0.0102385739 -0.1467731595 2874 1311867814.5201790333 0.3668589592 0.3288949863 0.4404943883 0.0041946728 0.0139000000 45592653 955859216 1373700096 -0.2930088043 -0.0092312172 -0.1471298635 2875 1311867814.5517210960 0.3676094711 0.3289084522 0.4404943883 0.0041941353 0.0091970000 45595525 955859216 1373700096 -0.2939795852 -0.0094884494 -0.1472101957 2876 1311867814.5848219395 0.3692061603 0.3289224639 0.4404943883 0.0041936911 0.0140030000 45598341 955859216 1373700096 -0.2961457968 -0.0090865726 -0.1472102404 2877 1311867814.6200098991 0.3684715927 0.3289362106 0.4404943883 0.0041933713 0.0092220000 45601269 955859216 1373700096 -0.2959337533 -0.0093529625 -0.1475044191 2878 1311867814.6503028870 0.3689473569 0.3289501130 0.4404943883 0.0041927498 0.0084800000 45604141 955859216 1373700096 -0.2971286178 -0.0089464625 -0.1475108564 2879 1311867814.6833140850 0.3698014021 0.3289643024 0.4404943883 0.0041922424 0.0093790000 45607013 955859216 1373700096 -0.2981896996 -0.0093120681 -0.1471080482 2880 1311867814.7211821079 0.3699000478 0.3289785162 0.4404943883 0.0041921065 0.0085190000 45610053 955859216 1373700096 -0.2988944650 -0.0087014372 -0.1470743865 2881 1311867814.7502319813 0.3719463646 0.3289934304 0.4404943883 0.0041918019 0.0084390000 45612869 955859216 1373700096 -0.3016533852 -0.0075834515 -0.1463928074 2882 1311867814.7828900814 0.3723618984 0.3290084785 0.4404943883 0.0041919682 0.0085440000 45615741 955859216 1373700096 -0.3023020327 -0.0072845044 -0.1462911665 2883 1311867814.8186480999 0.3731226623 0.3290237799 0.4404943883 0.0041917068 0.0084570000 45618725 955859216 1373700096 -0.3031553626 -0.0062923986 -0.1455412507 2884 1311867814.8526010513 0.3741263449 0.3290394188 0.4404943883 0.0041913419 0.0084040000 45621653 955859216 1373700096 -0.3039748669 -0.0064591062 -0.1451249868 2885 1311867814.8852329254 0.3730688095 0.3290546803 0.4404943883 0.0041909275 0.0083330000 45624525 955859216 1373700096 -0.3029847741 -0.0057907496 -0.1452191621 2886 1311867814.9202771187 0.3734346628 0.3290700580 0.4404943883 0.0041903595 0.0083570000 45627509 955859216 1373700096 -0.3034412265 -0.0052725179 -0.1449068636 2887 1311867814.9503459930 0.3734439015 0.3290854282 0.4404943883 0.0041901178 0.0082550000 45630325 955859216 1373700096 -0.3030543029 -0.0053114556 -0.1446956694 2888 1311867814.9839959145 0.3733215630 0.3291007454 0.4404943883 0.0041931570 0.0083640000 45633253 955859216 1373700096 -0.3028229475 -0.0043252921 -0.1444453299 2889 1311867815.0193099976 0.3736155927 0.3291161538 0.4404943883 0.0041955609 0.0083830000 45636125 955859216 1373700096 -0.3027870357 -0.0041073863 -0.1441596597 2890 1311867815.0509970188 0.3743734956 0.3291318138 0.4404943883 0.0041949758 0.0083670000 45638941 955859216 1373700096 -0.3032066226 -0.0033783736 -0.1439472139 2891 1311867815.0835149288 0.3757988513 0.3291479560 0.4404943883 0.0041956027 0.0083380000 45641813 955859216 1373700096 -0.3039339483 -0.0034140614 -0.1436077654 2892 1311867815.1192519665 0.3766707182 0.3291643885 0.4404943883 0.0041950017 0.0083320000 45644797 955859216 1373700096 -0.3041333556 -0.0025959348 -0.1436510980 2893 1311867815.1505639553 0.3778360784 0.3291812124 0.4404943883 0.0041955218 0.0226900000 45647613 955859216 1373700096 -0.3045412004 -0.0026224959 -0.1435638666 2894 1311867815.1827230453 0.3785257936 0.3291982631 0.4404943883 0.0041951877 0.0108250000 45650541 955859216 1373700096 -0.3042516708 -0.0021822904 -0.1436041594 2895 1311867815.2192549706 0.3788630068 0.3292154184 0.4404943883 0.0041964679 0.0088540000 45653525 955859216 1373700096 -0.3038071990 -0.0009924807 -0.1436999887 2896 1311867815.2503280640 0.3796223104 0.3292328241 0.4404943883 0.0041960995 0.0129920000 45656341 955859216 1373700096 -0.3037028611 -0.0008522491 -0.1434805840 2897 1311867815.2826719284 0.3805413246 0.3292505350 0.4404943883 0.0041956123 0.0092050000 45659269 955859216 1373700096 -0.3038311899 -0.0004169083 -0.1429932564 2898 1311867815.3188140392 0.3814153075 0.3292685353 0.4404943883 0.0041949872 0.0087930000 45662253 955859216 1373700096 -0.3042704761 0.0000690559 -0.1428629905 2899 1311867815.3506569862 0.3820214868 0.3292867323 0.4404943883 0.0041943629 0.0087210000 45665069 955859216 1373700096 -0.3042845130 0.0004059477 -0.1428101510 2900 1311867815.3841490746 0.3809719682 0.3293045548 0.4404943883 0.0041939792 0.0086700000 45667997 955859216 1373700096 -0.3025585413 0.0006118693 -0.1427039951 2901 1311867815.4187209606 0.3817080259 0.3293226187 0.4404943883 0.0041945283 0.0086390000 45670981 955859216 1373700096 -0.3031232953 0.0011520314 -0.1423637569 2902 1311867815.4505259991 0.3810691237 0.3293404500 0.4404943883 0.0041938973 0.0086780000 45673797 955859216 1373700096 -0.3022212386 0.0015116237 -0.1420299709 2903 1311867815.4827210903 0.3810778558 0.3293582721 0.4404943883 0.0041936630 0.0084670000 45676725 955859216 1373700096 -0.3019087613 0.0014389083 -0.1415873170 2904 1311867815.5188379288 0.3808982968 0.3293760200 0.4404943883 0.0041931239 0.0085660000 45679709 955859216 1373700096 -0.3016097844 0.0019753312 -0.1411924809 2905 1311867815.5508639812 0.3796106279 0.3293933125 0.4404943883 0.0041926877 0.0140900000 45682525 955859216 1373700096 -0.3004310727 0.0031498629 -0.1411887258 2906 1311867815.5879790783 0.3795851767 0.3294105843 0.4404943883 0.0041927402 0.0092220000 45685565 955859216 1373700096 -0.3000626564 0.0034657146 -0.1405695677 2907 1311867815.6201279163 0.3797626793 0.3294279053 0.4404943883 0.0041933301 0.0138900000 45688437 955859216 1373700096 -0.3003102243 0.0042777746 -0.1398442388 2908 1311867815.6522359848 0.3787006438 0.3294448491 0.4404943883 0.0041929405 0.0097270000 45691365 955859216 1373700096 -0.2989260554 0.0049388851 -0.1395908594 2909 1311867815.6869289875 0.3790538311 0.3294619027 0.4404943883 0.0041940668 0.0087480000 45694293 955859216 1373700096 -0.2987878323 0.0045796786 -0.1391724497 2910 1311867815.7186810970 0.3790272474 0.3294789355 0.4404943883 0.0041969407 0.0087190000 45697221 955859216 1373700096 -0.2988977134 0.0058730575 -0.1389249563 2911 1311867815.7527859211 0.3795314431 0.3294961298 0.4404943883 0.0042104104 0.0086100000 45700093 955859216 1373700096 -0.2987945378 0.0058344239 -0.1386634558 2912 1311867815.7881309986 0.3800251782 0.3295134818 0.4404943883 0.0042098050 0.0085590000 45703077 955859216 1373700096 -0.2989770472 0.0058175735 -0.1385495216 2913 1311867815.8185119629 0.3792940378 0.3295305709 0.4404943883 0.0042279488 0.0130070000 45705837 955859216 1373700096 -0.2981618047 0.0064948052 -0.1383038908 2914 1311867815.8516321182 0.3797715902 0.3295478121 0.4404943883 0.0042276867 0.0133550000 45708765 955859216 1373700096 -0.2980625629 0.0057696518 -0.1379530430 2915 1311867815.8881559372 0.3798759282 0.3295650773 0.4404943883 0.0042271127 0.0091340000 45711805 955859216 1373700096 -0.2977427244 0.0061849155 -0.1376891881 2916 1311867815.9183700085 0.3797407746 0.3295822844 0.4404943883 0.0042270289 0.0086040000 45714565 955859216 1373700096 -0.2974782884 0.0073915180 -0.1372628957 2917 1311867815.9544029236 0.3803324699 0.3295996825 0.4404943883 0.0042266806 0.0085810000 45717549 955859216 1373700096 -0.2974744141 0.0073669017 -0.1368697733 2918 1311867815.9880459309 0.3793259263 0.3296167237 0.4404943883 0.0042312875 0.0085370000 45720477 955859216 1373700096 -0.2961252630 0.0077298097 -0.1368025541 2919 1311867816.0232369900 0.3788073361 0.3296335755 0.4404943883 0.0042348254 0.0187210000 45723461 955859216 1373700096 -0.2949748933 0.0085549327 -0.1367229670 2920 1311867816.0513160229 0.3797651827 0.3296507439 0.4404943883 0.0042343660 0.0099140000 45726165 955859216 1373700096 -0.2952858806 0.0088742860 -0.1362300962 2921 1311867816.0872139931 0.3794603050 0.3296677961 0.4404943883 0.0042339863 0.0089240000 45729205 955859216 1373700096 -0.2943675518 0.0094680758 -0.1359717250 2922 1311867816.1192660332 0.3798774481 0.3296849794 0.4404943883 0.0042333300 0.0088450000 45732021 955859216 1373700096 -0.2939140201 0.0095539987 -0.1357240528 2923 1311867816.1530499458 0.3798848987 0.3297021535 0.4404943883 0.0042329152 0.0086890000 45734837 955859216 1373700096 -0.2933095098 0.0102538094 -0.1355068088 2924 1311867816.1877670288 0.3798443377 0.3297193020 0.4404943883 0.0042330763 0.0142700000 45737821 955859216 1373700096 -0.2926867902 0.0105531514 -0.1351103932 2925 1311867816.2185130119 0.3801283538 0.3297365359 0.4404943883 0.0042329879 0.0092770000 45740693 955859216 1373700096 -0.2924683690 0.0109115541 -0.1350168437 2926 1311867816.2509930134 0.3800414205 0.3297537283 0.4404943883 0.0042358839 0.0086700000 45743509 955859216 1373700096 -0.2921468616 0.0115417149 -0.1348391920 2927 1311867816.2875878811 0.3793611526 0.3297706765 0.4404943883 0.0042358688 0.0086130000 45746493 955859216 1373700096 -0.2910434902 0.0118381903 -0.1346924901 2928 1311867816.3221759796 0.3786165416 0.3297873588 0.4404943883 0.0042353591 0.0086150000 45749477 955859216 1373700096 -0.2900090218 0.0122703332 -0.1348205060 2929 1311867816.3515660763 0.3783022165 0.3298039224 0.4404943883 0.0042352263 0.0100830000 45752237 955859216 1373700096 -0.2892793417 0.0123747531 -0.1349727809 2930 1311867816.3902490139 0.3786120117 0.3298205805 0.4404943883 0.0042345777 0.0088430000 45755277 955859216 1373700096 -0.2893953919 0.0125419907 -0.1354396492 2931 1311867816.4188189507 0.3793479800 0.3298374783 0.4404943883 0.0042339067 0.0086120000 45758093 955859216 1373700096 -0.2901978493 0.0126395840 -0.1357529312 2932 1311867816.4527490139 0.3789265454 0.3298542208 0.4404943883 0.0042334147 0.0085500000 45761021 955859216 1373700096 -0.2897808552 0.0126639633 -0.1362825781 2933 1311867816.4875969887 0.3808724880 0.3298716154 0.4404943883 0.0042350741 0.0085080000 45763949 955859216 1373700096 -0.2920037508 0.0127606727 -0.1365960538 2934 1311867816.5199189186 0.3814098835 0.3298891812 0.4404943883 0.0042353480 0.0142120000 45766765 955859216 1373700096 -0.2926035225 0.0121746128 -0.1371205449 2935 1311867816.5529119968 0.3804718852 0.3299064155 0.4404943883 0.0042367997 0.0094560000 45769749 955859216 1373700096 -0.2919121683 0.0118058855 -0.1372520626 2936 1311867816.5888628960 0.3804731071 0.3299236385 0.4404943883 0.0042361980 0.0139520000 45772733 955859216 1373700096 -0.2921639085 0.0118461289 -0.1375203729 2937 1311867816.6194050312 0.3804538548 0.3299408432 0.4404943883 0.0042357353 0.0092700000 45775549 955859216 1373700096 -0.2926275134 0.0114991078 -0.1375461370 2938 1311867816.6509261131 0.3804785311 0.3299580446 0.4404943883 0.0042352810 0.0087500000 45778365 955859216 1373700096 -0.2931907773 0.0111604547 -0.1378334612 2939 1311867816.6893680096 0.3809402287 0.3299753914 0.4404943883 0.0042350847 0.0141820000 45781461 955859216 1373700096 -0.2945092916 0.0107751163 -0.1379901767 2940 1311867816.7204029560 0.3806548417 0.3299926293 0.4404943883 0.0042359560 0.0094200000 45784221 955859216 1373700096 -0.2951063812 0.0100006601 -0.1383466423 2941 1311867816.7523219585 0.3794820011 0.3300094567 0.4404943883 0.0042354438 0.0088020000 45787093 955859216 1373700096 -0.2946857214 0.0088712387 -0.1386765689 2942 1311867816.7867000103 0.3800632060 0.3300264702 0.4404943883 0.0042352102 0.0143700000 45790021 955859216 1373700096 -0.2957439423 0.0081834905 -0.1390410960 2943 1311867816.8192241192 0.3791148663 0.3300431499 0.4404943883 0.0042348295 0.0093650000 45792893 955859216 1373700096 -0.2954190075 0.0074348371 -0.1391672641 2944 1311867816.8584229946 0.3783534169 0.3300595597 0.4404943883 0.0042347364 0.0086540000 45795989 955859216 1373700096 -0.2953542173 0.0067877960 -0.1397912651 2945 1311867816.8891038895 0.3789657652 0.3300761662 0.4404943883 0.0042343230 0.0085820000 45798749 955859216 1373700096 -0.2962581813 0.0061114789 -0.1400660425 2946 1311867816.9194529057 0.3788124323 0.3300927094 0.4404943883 0.0042433246 0.0085980000 45801621 955859216 1373700096 -0.2962653935 0.0056551429 -0.1403490305 2947 1311867816.9566609859 0.3795890808 0.3301095049 0.4404943883 0.0042457300 0.0207960000 45804493 955859216 1373700096 -0.2978610992 0.0048146313 -0.1405294538 2948 1311867816.9880828857 0.3785758317 0.3301259453 0.4404943883 0.0042631348 0.0103260000 45807365 955859216 1373700096 -0.2974810302 0.0038152509 -0.1411177814 2949 1311867817.0196158886 0.3793205619 0.3301426271 0.4404943883 0.0042630491 0.0088920000 45810237 955859216 1373700096 -0.2983733416 0.0028264306 -0.1412990540 2950 1311867817.0547220707 0.3800671697 0.3301595507 0.4404943883 0.0042634107 0.0087140000 45813165 955859216 1373700096 -0.2999188900 0.0029274563 -0.1414532661 2951 1311867817.0868639946 0.3788751364 0.3301760588 0.4404943883 0.0042632782 0.0088510000 45816037 955859216 1373700096 -0.2987229228 0.0019639155 -0.1419954598 2952 1311867817.1189420223 0.3792997301 0.3301926997 0.4404943883 0.0042630855 0.0088830000 45818965 955859216 1373700096 -0.2993308604 0.0011576301 -0.1422382295 2953 1311867817.1549699306 0.3800323009 0.3302095773 0.4404943883 0.0042627030 0.0097410000 45821949 955859216 1373700096 -0.3006795049 0.0009032178 -0.1423012763 2954 1311867817.1863970757 0.3794336021 0.3302262408 0.4404943883 0.0042634191 0.0091850000 45824765 955859216 1373700096 -0.3001820445 0.0005254372 -0.1425561160 2955 1311867817.2202200890 0.3799068630 0.3302430532 0.4404943883 0.0042633267 0.0090330000 45827693 955859216 1373700096 -0.3006360531 -0.0004589948 -0.1426617056 2956 1311867817.2567460537 0.3806380033 0.3302601015 0.4404943883 0.0042641708 0.0090220000 45830677 955859216 1373700096 -0.3014829457 -0.0012300005 -0.1427247077 2957 1311867817.2865970135 0.3795568347 0.3302767727 0.4404943883 0.0042641067 0.0088430000 45833493 955859216 1373700096 -0.3007209599 -0.0019635465 -0.1432981491 2958 1311867817.3192870617 0.3793532252 0.3302933638 0.4404943883 0.0042638358 0.0088830000 45836421 955859216 1373700096 -0.3010045290 -0.0025760094 -0.1437951624 2959 1311867817.3578689098 0.3806024790 0.3303103659 0.4404943883 0.0042648995 0.0088310000 45839461 955859216 1373700096 -0.3029040098 -0.0032047229 -0.1435393393 2960 1311867817.3868360519 0.3819193244 0.3303278014 0.4404943883 0.0042659255 0.0089500000 45842221 955859216 1373700096 -0.3044660985 -0.0047108065 -0.1437329054 2961 1311867817.4206850529 0.3804580271 0.3303447315 0.4404943883 0.0042655511 0.0090140000 45845149 955859216 1373700096 -0.3034242094 -0.0055257306 -0.1442056000 2962 1311867817.4551830292 0.3810114861 0.3303618371 0.4404943883 0.0042658108 0.0090680000 45848077 955859216 1373700096 -0.3043256104 -0.0073847277 -0.1442058980 2963 1311867817.4888920784 0.3810394704 0.3303789406 0.4404943883 0.0042661344 0.0089830000 45851061 955859216 1373700096 -0.3047376275 -0.0084652714 -0.1445232630 2964 1311867817.5194959641 0.3806446791 0.3303958994 0.4404943883 0.0042662333 0.0089440000 45853821 955859216 1373700096 -0.3047956526 -0.0089499326 -0.1448910981 2965 1311867817.5576219559 0.3815881014 0.3304131648 0.4404943883 0.0042661840 0.0088740000 45856917 955859216 1373700096 -0.3061803281 -0.0106977290 -0.1451254785 2966 1311867817.5864789486 0.3816017210 0.3304304233 0.4404943883 0.0042657053 0.0088960000 45859677 955859216 1373700096 -0.3065192699 -0.0123810377 -0.1452664435 2967 1311867817.6205849648 0.3820216954 0.3304478117 0.4404943883 0.0042651156 0.0089620000 45862605 955859216 1373700096 -0.3076123297 -0.0131838759 -0.1453154981 2968 1311867817.6566040516 0.3800292015 0.3304645170 0.4404943883 0.0042648346 0.0090070000 45865589 955859216 1373700096 -0.3063203990 -0.0141546838 -0.1455023140 2969 1311867817.6880049706 0.3796528876 0.3304810843 0.4404943883 0.0042650188 0.0088010000 45868461 955859216 1373700096 -0.3065020740 -0.0152789820 -0.1457268447 2970 1311867817.7194509506 0.3800053000 0.3304977591 0.4404943883 0.0042648695 0.0093550000 45871389 955859216 1373700096 -0.3072022796 -0.0164575130 -0.1458845139 2971 1311867817.7552740574 0.3797455132 0.3305143353 0.4404943883 0.0042656588 0.0092430000 45874261 955859216 1373700096 -0.3072965741 -0.0175761506 -0.1460445374 2972 1311867817.7872710228 0.3801371157 0.3305310320 0.4404943883 0.0042665481 0.0094090000 45877189 955859216 1373700096 -0.3080337942 -0.0183514077 -0.1459742934 2973 1311867817.8201289177 0.3798546195 0.3305476225 0.4404943883 0.0042673031 0.0093580000 45880117 955859216 1373700096 -0.3082168698 -0.0189998690 -0.1461842060 2974 1311867817.8596370220 0.3820276856 0.3305649326 0.4404943883 0.0042700437 0.0094890000 45883213 955859216 1373700096 -0.3107047975 -0.0208212268 -0.1456484050 2975 1311867817.8866479397 0.3828787506 0.3305825171 0.4404943883 0.0042705529 0.0094430000 45885917 955859216 1373700096 -0.3117754459 -0.0213625915 -0.1449814141 2976 1311867817.9203889370 0.3823536336 0.3305999133 0.4404943883 0.0042710280 0.0093310000 45888845 955859216 1373700096 -0.3114167750 -0.0226036571 -0.1449072808 2977 1311867817.9569509029 0.3827356696 0.3306174261 0.4404943883 0.0042712715 0.0093920000 45891829 955859216 1373700096 -0.3122333884 -0.0232713111 -0.1449481845 2978 1311867817.9865961075 0.3821349144 0.3306347255 0.4404943883 0.0042714896 0.0093970000 45894645 955859216 1373700096 -0.3116309643 -0.0245096851 -0.1448967904 2979 1311867818.0255188942 0.3829284906 0.3306522796 0.4404943883 0.0042722348 0.0094280000 45897685 955859216 1373700096 -0.3125308156 -0.0254841447 -0.1449904889 2980 1311867818.0579230785 0.3828224838 0.3306697864 0.4404943883 0.0042728932 0.0093470000 45900613 955859216 1373700096 -0.3122085035 -0.0264558885 -0.1450106204 2981 1311867818.0892961025 0.3820418417 0.3306870196 0.4404943883 0.0042728265 0.0093890000 45903373 955859216 1373700096 -0.3115847409 -0.0271884874 -0.1453981549 2982 1311867818.1228859425 0.3836231530 0.3307047714 0.4404943883 0.0042756266 0.0094930000 45906357 955859216 1373700096 -0.3134629726 -0.0280062258 -0.1455174237 2983 1311867818.1594460011 0.3851239979 0.3307230146 0.4404943883 0.0042765144 0.0094220000 45909285 955859216 1373700096 -0.3149347305 -0.0289782938 -0.1455968618 2984 1311867818.1912620068 0.3834075332 0.3307406702 0.4404943883 0.0042912936 0.0092410000 45912213 955859216 1373700096 -0.3132315874 -0.0297133978 -0.1460353881 2985 1311867818.2233390808 0.3829127550 0.3307581483 0.4404943883 0.0042976878 0.0093750000 45915141 955859216 1373700096 -0.3130224645 -0.0297984295 -0.1464490592 2986 1311867818.2556240559 0.3812775612 0.3307750671 0.4404943883 0.0042989948 0.0094010000 45917957 955859216 1373700096 -0.3112206161 -0.0305997469 -0.1468965709 2987 1311867818.2891340256 0.3806374073 0.3307917602 0.4404943883 0.0043001983 0.0095400000 45920885 955859216 1373700096 -0.3107710779 -0.0310885236 -0.1472379565 2988 1311867818.3256890774 0.3803200126 0.3308083359 0.4404943883 0.0042997730 0.0094110000 45923869 955859216 1373700096 -0.3104749024 -0.0316087417 -0.1475645602 2989 1311867818.3582971096 0.3808188736 0.3308250674 0.4404943883 0.0042993667 0.0093830000 45926797 955859216 1373700096 -0.3108981550 -0.0331123993 -0.1479835361 2990 1311867818.3892099857 0.3805896044 0.3308417111 0.4404943883 0.0042996338 0.0094510000 45929669 955859216 1373700096 -0.3106059432 -0.0335839428 -0.1482350975 2991 1311867818.4233601093 0.3804205954 0.3308582871 0.4404943883 0.0042998163 0.0094370000 45932597 955859216 1373700096 -0.3108166158 -0.0337540917 -0.1483167261 2992 1311867818.4555370808 0.3792659640 0.3308744662 0.4404943883 0.0042995568 0.0093530000 45935413 955859216 1373700096 -0.3099918365 -0.0340691321 -0.1489680707 2993 1311867818.4896349907 0.3796422184 0.3308907601 0.4404943883 0.0043003598 0.0092650000 45938397 955859216 1373700096 -0.3106862903 -0.0351265147 -0.1490669399 2994 1311867818.5246019363 0.3786802590 0.3309067219 0.4404943883 0.0043016435 0.0095200000 45941325 955859216 1373700096 -0.3102744818 -0.0350982696 -0.1490489841 2995 1311867818.5566370487 0.3784416914 0.3309225933 0.4404943883 0.0043025061 0.0094360000 45944197 955859216 1373700096 -0.3108181059 -0.0355157889 -0.1492668390 2996 1311867818.5892300606 0.3781799078 0.3309383668 0.4404943883 0.0043052253 0.0094010000 45947069 955859216 1373700096 -0.3111262918 -0.0364415497 -0.1496526897 2997 1311867818.6233239174 0.3785299957 0.3309542465 0.4404943883 0.0043055577 0.0094520000 45949997 955859216 1373700096 -0.3124218285 -0.0368238240 -0.1496606618 2998 1311867818.6555750370 0.3792224228 0.3309703467 0.4404943883 0.0043066150 0.0093580000 45952813 955859216 1373700096 -0.3143330514 -0.0373759419 -0.1496008039 2999 1311867818.6877410412 0.3786648810 0.3309862501 0.4404943883 0.0043066421 0.0094020000 45955741 955859216 1373700096 -0.3143568039 -0.0384384096 -0.1497489065 3000 1311867818.7238090038 0.3790596724 0.3310022746 0.4404943883 0.0043062246 0.0094180000 45958669 955859216 1373700096 -0.3158904016 -0.0383569747 -0.1497455686 3001 1311867818.7561779022 0.3806413710 0.3310188155 0.4404943883 0.0043065807 0.0100780000 45961597 955859216 1373700096 -0.3179900944 -0.0387198515 -0.1497016251 3002 1311867818.7870090008 0.3809470832 0.3310354471 0.4404943883 0.0043070858 0.0095840000 45964413 955859216 1373700096 -0.3189776838 -0.0395371765 -0.1497867554 3003 1311867818.8250839710 0.3813357651 0.3310521971 0.4404943883 0.0043097612 0.0094780000 45967397 955859216 1373700096 -0.3203064203 -0.0395095386 -0.1495741010 3004 1311867818.8546340466 0.3813821077 0.3310689514 0.4404943883 0.0043098726 0.0094320000 45970213 955859216 1373700096 -0.3213860393 -0.0393640585 -0.1494881511 3005 1311867818.8872439861 0.3811923563 0.3310856314 0.4404943883 0.0043197417 0.0094660000 45973197 955859216 1373700096 -0.3221464157 -0.0396365151 -0.1494394541 3006 1311867818.9249579906 0.3799293041 0.3311018802 0.4404943883 0.0043206559 0.0095230000 45976237 955859216 1373700096 -0.3221502602 -0.0393644311 -0.1494822651 3007 1311867818.9544699192 0.3790326118 0.3311178199 0.4404943883 0.0043239352 0.0095000000 45978997 955859216 1373700096 -0.3219890296 -0.0393132828 -0.1494908780 3008 1311867818.9864790440 0.3801828921 0.3311341314 0.4404943883 0.0043252615 0.0095480000 45981869 955859216 1373700096 -0.3241506517 -0.0394752771 -0.1492625028 3009 1311867819.0252439976 0.3794296980 0.3311501818 0.4404943883 0.0043276717 0.0095680000 45984965 955859216 1373700096 -0.3240491450 -0.0408455655 -0.1492534429 3010 1311867819.0550930500 0.3792948723 0.3311661767 0.4404943883 0.0043431344 0.0094860000 45987781 955859216 1373700096 -0.3245444298 -0.0427336544 -0.1493601799 3011 1311867819.0875039101 0.3795595467 0.3311822489 0.4404943883 0.0043454545 0.0095170000 45990653 955859216 1373700096 -0.3254224360 -0.0431752652 -0.1489129663 3012 1311867819.1251850128 0.3783681989 0.3311979149 0.4404943883 0.0043572159 0.0095220000 45993637 955859216 1373700096 -0.3253984451 -0.0437094457 -0.1488793790 3013 1311867819.1578950882 0.3781743050 0.3312135061 0.4404943883 0.0043575098 0.0095220000 45996565 955859216 1373700096 -0.3262715638 -0.0445219725 -0.1487586945 3014 1311867819.1891999245 0.3789795041 0.3312293542 0.4404943883 0.0043580004 0.0090840000 45999437 955859216 1373700096 -0.3274104893 -0.0454869531 -0.1485044956 3015 1311867819.2251279354 0.3788182735 0.3312451382 0.4404943883 0.0043597496 0.0091550000 46002365 955859216 1373700096 -0.3280525506 -0.0459003672 -0.1482762843 3016 1311867819.2586779594 0.3755243123 0.3312598196 0.4404943883 0.0043631787 0.0092390000 46005293 955859216 1373700096 -0.3235614300 -0.0513201989 -0.1485028714 3017 1311867819.2937591076 0.3782940805 0.3312754094 0.4404943883 0.0043625422 0.0093310000 46008221 955859216 1373700096 -0.3271758258 -0.0515498705 -0.1486176103 3018 1311867819.3250200748 0.3787678480 0.3312911458 0.4404943883 0.0043621849 0.0092230000 46011093 955859216 1373700096 -0.3277992606 -0.0524790809 -0.1483646482 3019 1311867819.3568780422 0.3797489107 0.3313071967 0.4404943883 0.0043625187 0.0092560000 46013965 955859216 1373700096 -0.3289416432 -0.0526710004 -0.1483868062 3020 1311867819.3930859566 0.3811910748 0.3313237145 0.4404943883 0.0043662343 0.0092020000 46016949 955859216 1373700096 -0.3307134509 -0.0532920212 -0.1482679695 3021 1311867819.4237139225 0.3817767203 0.3313404153 0.4404943883 0.0043658655 0.0093320000 46019821 955859216 1373700096 -0.3319514692 -0.0527034402 -0.1483181864 3022 1311867819.4571580887 0.3832021952 0.3313575767 0.4404943883 0.0043655584 0.0092300000 46022693 955859216 1373700096 -0.3335671723 -0.0537257865 -0.1480053067 3023 1311867819.4921460152 0.3821389377 0.3313743751 0.4404943883 0.0043667328 0.0092960000 46025621 955859216 1373700096 -0.3320893347 -0.0550931990 -0.1478746980 3024 1311867819.5226500034 0.3819405437 0.3313910967 0.4404943883 0.0043670668 0.0092080000 46028493 955859216 1373700096 -0.3324199319 -0.0537569746 -0.1474922299 3025 1311867819.5550689697 0.3797741532 0.3314070911 0.4404943883 0.0043673461 0.0092190000 46031309 955859216 1373700096 -0.3303712606 -0.0541489311 -0.1476635337 3026 1311867819.5923891068 0.3784563541 0.3314226394 0.4404943883 0.0043686214 0.0093330000 46034405 955859216 1373700096 -0.3288065493 -0.0552704148 -0.1476716101 3027 1311867819.6253750324 0.3764083982 0.3314375009 0.4404943883 0.0043695551 0.0094920000 46037277 955859216 1373700096 -0.3270882666 -0.0540708080 -0.1471838355 3028 1311867819.6557610035 0.3759609163 0.3314522048 0.4404943883 0.0043693619 0.0105810000 46040093 955859216 1373700096 -0.3267155886 -0.0540986061 -0.1470655501 3029 1311867819.6919729710 0.3748572469 0.3314665346 0.4404943883 0.0043701578 0.0098850000 46043077 955859216 1373700096 -0.3255046308 -0.0556139797 -0.1478018463 3030 1311867819.7227339745 0.3648783863 0.3314775616 0.4404943883 0.0043734350 0.0137490000 46045949 955859216 1373700096 -0.3149407208 -0.0562126711 -0.1477272511 3031 1311867819.7567169666 0.3662802577 0.3314890439 0.4404943883 0.0043738897 0.0138530000 46048877 955859216 1373700096 -0.3167215884 -0.0554684326 -0.1476048231 3032 1311867819.7913908958 0.3616283238 0.3314989843 0.4404943883 0.0043755006 0.0137200000 46051805 955859216 1373700096 -0.3115018606 -0.0572300330 -0.1477362812 3033 1311867819.8285260201 0.3650858402 0.3315100581 0.4404943883 0.0043754636 0.0099970000 46054789 955859216 1373700096 -0.3149898648 -0.0583324097 -0.1477265507 3034 1311867819.8552229404 0.3677518368 0.3315220033 0.4404943883 0.0043799400 0.0138510000 46057493 955859216 1373700096 -0.3184533715 -0.0566436462 -0.1475156993 3035 1311867819.8941109180 0.3726312518 0.3315355484 0.4404943883 0.0043804731 0.0221550000 46060645 955859216 1373700096 -0.3233522773 -0.0575818084 -0.1472504437 3036 1311867819.9237871170 0.3728035986 0.3315491413 0.4404943883 0.0043802947 0.0111460000 46063405 955859216 1373700096 -0.3228730261 -0.0598403737 -0.1470661908 3037 1311867819.9576539993 0.3766207695 0.3315639821 0.4404943883 0.0043802512 0.0095790000 46066333 955859216 1373700096 -0.3274225593 -0.0578428842 -0.1466920376 3038 1311867819.9939079285 0.3791148961 0.3315796342 0.4404943883 0.0043799092 0.0143250000 46069373 955859216 1373700096 -0.3300006688 -0.0577338450 -0.1464951932 3039 1311867820.0229809284 0.3770632148 0.3315946008 0.4404943883 0.0043803337 0.0098370000 46072133 955859216 1373700096 -0.3274839222 -0.0590401478 -0.1465541273 3040 1311867820.0577530861 0.3782675862 0.3316099537 0.4404943883 0.0043801023 0.0094070000 46075061 955859216 1373700096 -0.3286336064 -0.0587015375 -0.1458402723 3041 1311867820.0944790840 0.3792805672 0.3316256297 0.4404943883 0.0043794024 0.0140200000 46078045 955859216 1373700096 -0.3297493756 -0.0581279024 -0.1456895471 3042 1311867820.1251690388 0.3744095564 0.3316396941 0.4404943883 0.0043809683 0.0096610000 46080861 955859216 1373700096 -0.3241640031 -0.0599395707 -0.1456776112 3043 1311867820.1551020145 0.3773680925 0.3316547215 0.4404943883 0.0043809564 0.0093760000 46083733 955859216 1373700096 -0.3272899687 -0.0599481836 -0.1452503204 3044 1311867820.1938860416 0.3775111437 0.3316697860 0.4404943883 0.0043804455 0.0094140000 46086773 955859216 1373700096 -0.3278655112 -0.0583473593 -0.1450361609 3045 1311867820.2262499332 0.3773234487 0.3316847790 0.4404943883 0.0043802154 0.0091220000 46089645 955859216 1373700096 -0.3269893527 -0.0607232973 -0.1448464096 3046 1311867820.2557370663 0.3766552508 0.3316995428 0.4404943883 0.0043796716 0.0091090000 46092405 955859216 1373700096 -0.3260290027 -0.0619882941 -0.1447315663 3047 1311867820.2941820621 0.3725312054 0.3317129434 0.4404943883 0.0043804111 0.0138900000 46095557 955859216 1373700096 -0.3220428228 -0.0610324554 -0.1445622593 3048 1311867820.3227488995 0.3780668676 0.3317281514 0.4404943883 0.0043805712 0.0097900000 46098317 955859216 1373700096 -0.3275382221 -0.0620195679 -0.1442411542 3049 1311867820.3565030098 0.3731520474 0.3317417375 0.4404943883 0.0043812069 0.0092810000 46101189 955859216 1373700096 -0.3222477436 -0.0627869368 -0.1440575868 3050 1311867820.3936169147 0.3783251345 0.3317570107 0.4404943883 0.0043828605 0.0094880000 46104229 955859216 1373700096 -0.3277853131 -0.0626551062 -0.1437874138 3051 1311867820.4230690002 0.3737773895 0.3317707834 0.4404943883 0.0043838191 0.0092770000 46106989 955859216 1373700096 -0.3228603303 -0.0637865141 -0.1438644528 3052 1311867820.4605870247 0.3751628101 0.3317850009 0.4404943883 0.0043833319 0.0090720000 46109973 955859216 1373700096 -0.3244494498 -0.0645162761 -0.1435781866 3053 1311867820.4940779209 0.3763540685 0.3317995994 0.4404943883 0.0043826361 0.0091550000 46112901 955859216 1373700096 -0.3258038163 -0.0648267046 -0.1434483975 3054 1311867820.5266289711 0.3779557943 0.3318147127 0.4404943883 0.0043820414 0.0223530000 46115829 955859216 1373700096 -0.3276406825 -0.0653724223 -0.1430810690 3055 1311867820.5596110821 0.3787147701 0.3318300646 0.4404943883 0.0043814149 0.0108900000 46118701 955859216 1373700096 -0.3284549117 -0.0658414513 -0.1426582634 3056 1311867820.5906820297 0.3778516054 0.3318451241 0.4404943883 0.0043807967 0.0094460000 46121517 955859216 1373700096 -0.3278366029 -0.0659729540 -0.1425309628 3057 1311867820.6261150837 0.3776825368 0.3318601183 0.4404943883 0.0043807038 0.0092750000 46124501 955859216 1373700096 -0.3285757601 -0.0660572276 -0.1423428953 3058 1311867820.6602840424 0.3770588934 0.3318748988 0.4404943883 0.0043800999 0.0091570000 46127373 955859216 1373700096 -0.3280109167 -0.0672132969 -0.1418340802 3059 1311867820.6933140755 0.3776160181 0.3318898518 0.4404943883 0.0043797603 0.0092320000 46130357 955859216 1373700096 -0.3289819956 -0.0672687888 -0.1415056586 3060 1311867820.7232019901 0.3775268793 0.3319047658 0.4404943883 0.0043792043 0.0091650000 46133173 955859216 1373700096 -0.3292246163 -0.0671935678 -0.1412595659 3061 1311867820.7605569363 0.3763138354 0.3319192739 0.4404943883 0.0043796600 0.0091290000 46136157 955859216 1373700096 -0.3281812966 -0.0680506527 -0.1411397457 3062 1311867820.7916440964 0.3763359487 0.3319337796 0.4404943883 0.0043792266 0.0147820000 46138973 955859216 1373700096 -0.3286416829 -0.0679340959 -0.1410440952 3063 1311867820.8228490353 0.3771982491 0.3319485574 0.4404943883 0.0043786711 0.0098330000 46141901 955859216 1373700096 -0.3296857476 -0.0688189939 -0.1408463866 3064 1311867820.8588171005 0.3756862283 0.3319628321 0.4404943883 0.0043787342 0.0092620000 46144885 955859216 1373700096 -0.3285022080 -0.0693936422 -0.1405790448 3065 1311867820.8911399841 0.3770136833 0.3319775306 0.4404943883 0.0043782287 0.0092380000 46147701 955859216 1373700096 -0.3302449286 -0.0697671175 -0.1401476562 3066 1311867820.9231750965 0.3790056705 0.3319928692 0.4404943883 0.0043778019 0.0091080000 46150573 955859216 1373700096 -0.3326328993 -0.0699686036 -0.1397995502 3067 1311867820.9593999386 0.3793049157 0.3320082954 0.4404943883 0.0043773028 0.0092520000 46153613 955859216 1373700096 -0.3331501484 -0.0713835657 -0.1397346556 3068 1311867820.9930229187 0.3784066141 0.3320234187 0.4404943883 0.0043768193 0.0091910000 46156541 955859216 1373700096 -0.3325828314 -0.0711919293 -0.1393994242 3069 1311867821.0258319378 0.3777872920 0.3320383304 0.4404943883 0.0043779541 0.0092390000 46159301 955859216 1373700096 -0.3323618472 -0.0705982819 -0.1390534341 3070 1311867821.0608170033 0.3770203292 0.3320529825 0.4404943883 0.0043779392 0.0092050000 46162285 955859216 1373700096 -0.3316779435 -0.0717506260 -0.1388460547 3071 1311867821.0909409523 0.3770334125 0.3320676293 0.4404943883 0.0043777557 0.0092080000 46165101 955859216 1373700096 -0.3322973549 -0.0710679293 -0.1385025084 3072 1311867821.1260650158 0.3768175840 0.3320821964 0.4404943883 0.0043783658 0.0092280000 46168029 955859216 1373700096 -0.3327111006 -0.0703925416 -0.1380582303 3073 1311867821.1620008945 0.3760400414 0.3320965009 0.4404943883 0.0043796939 0.0092890000 46170957 955859216 1373700096 -0.3322368264 -0.0714417771 -0.1380847543 3074 1311867821.1925799847 0.3761861026 0.3321108436 0.4404943883 0.0043796378 0.0103130000 46173829 955859216 1373700096 -0.3327251077 -0.0720544234 -0.1377611607 3075 1311867821.2257659435 0.3768129349 0.3321253809 0.4404943883 0.0043790064 0.0096500000 46176701 955859216 1373700096 -0.3339647055 -0.0721616223 -0.1372688413 3076 1311867821.2620539665 0.3771948516 0.3321400329 0.4404943883 0.0043787309 0.0095450000 46179685 955859216 1373700096 -0.3347973824 -0.0726216510 -0.1369132400 3077 1311867821.2933909893 0.3774494827 0.3321547581 0.4404943883 0.0043781630 0.0095210000 46182557 955859216 1373700096 -0.3352652788 -0.0736136734 -0.1364098191 3078 1311867821.3235690594 0.3782031536 0.3321697186 0.4404943883 0.0043778527 0.0094370000 46185429 955859216 1373700096 -0.3365651965 -0.0733867809 -0.1357721239 3079 1311867821.3590209484 0.3784876764 0.3321847618 0.4404943883 0.0043780880 0.0137860000 46188413 955859216 1373700096 -0.3371407986 -0.0747762844 -0.1357257217 3080 1311867821.3907248974 0.3788801134 0.3321999226 0.4404943883 0.0043778734 0.0137880000 46191173 955859216 1373700096 -0.3375554979 -0.0763425827 -0.1356409490 3081 1311867821.4246149063 0.3785947859 0.3322149810 0.4404943883 0.0043776251 0.0140460000 46194101 955859216 1373700096 -0.3377474844 -0.0763782561 -0.1350776702 3082 1311867821.4626159668 0.3775796890 0.3322297002 0.4404943883 0.0043772491 0.0138640000 46197197 955859216 1373700096 -0.3371518254 -0.0767663792 -0.1352711469 3083 1311867821.4939169884 0.3772391677 0.3322442994 0.4404943883 0.0043767105 0.0099040000 46200013 955859216 1373700096 -0.3371359408 -0.0771423802 -0.1353442073 3084 1311867821.5273780823 0.3770622909 0.3322588319 0.4404943883 0.0043768960 0.0225860000 46202941 955859216 1373700096 -0.3376645744 -0.0765627325 -0.1346557438 3085 1311867821.5590820312 0.3756466508 0.3322728960 0.4404943883 0.0043765456 0.0109390000 46205813 955859216 1373700096 -0.3369727135 -0.0763569623 -0.1348015666 3086 1311867821.5928409100 0.3772840500 0.3322874816 0.4404943883 0.0043767547 0.0097420000 46208629 955859216 1373700096 -0.3390408456 -0.0775165334 -0.1344778687 3087 1311867821.6260631084 0.3771674633 0.3323020200 0.4404943883 0.0043762551 0.0095830000 46211501 955859216 1373700096 -0.3396797478 -0.0770686418 -0.1338997632 3088 1311867821.6634659767 0.3778333664 0.3323167646 0.4404943883 0.0043756476 0.0094950000 46214709 955859216 1373700096 -0.3410631418 -0.0771380216 -0.1335543394 3089 1311867821.6953229904 0.3774359822 0.3323313710 0.4404943883 0.0043756349 0.0094560000 46217525 955859216 1373700096 -0.3411949575 -0.0779783353 -0.1331497580 3090 1311867821.7313649654 0.3773371577 0.3323459360 0.4404943883 0.0043754544 0.0094690000 46220509 955859216 1373700096 -0.3418910503 -0.0783444196 -0.1327394992 3091 1311867821.7634460926 0.3765970469 0.3323602521 0.4404943883 0.0043750048 0.0094720000 46223437 955859216 1373700096 -0.3419220746 -0.0778557956 -0.1320783049 3092 1311867821.7956120968 0.3756081164 0.3323742391 0.4404943883 0.0043748472 0.0094050000 46226197 955859216 1373700096 -0.3415747583 -0.0787510723 -0.1320364922 3093 1311867821.8313920498 0.3752543330 0.3323881027 0.4404943883 0.0043743308 0.0095480000 46229181 955859216 1373700096 -0.3419169486 -0.0792395547 -0.1317249835 3094 1311867821.8633379936 0.3760612607 0.3324022181 0.4404943883 0.0043752270 0.0095620000 46231997 955859216 1373700096 -0.3429084420 -0.0785804838 -0.1314126998 3095 1311867821.8956110477 0.3764949739 0.3324164646 0.4404943883 0.0043753101 0.0096960000 46234925 955859216 1373700096 -0.3435946405 -0.0800063089 -0.1313577145 3096 1311867821.9314410686 0.3707579374 0.3324288488 0.4404943883 0.0043760955 0.0094600000 46237909 955859216 1373700096 -0.3378388286 -0.0817973614 -0.1315972209 3097 1311867821.9633870125 0.3708308041 0.3324412485 0.4404943883 0.0043755727 0.0104040000 46240837 955859216 1373700096 -0.3384864032 -0.0815648958 -0.1316547692 3098 1311867821.9954171181 0.3709933162 0.3324536927 0.4404943883 0.0043751391 0.0096220000 46243709 955859216 1373700096 -0.3391612470 -0.0821987763 -0.1317491978 3099 1311867822.0314009190 0.3740952909 0.3324671298 0.4404943883 0.0043755434 0.0097470000 46246637 955859216 1373700096 -0.3424960673 -0.0848693177 -0.1313161850 3100 1311867822.0633769035 0.3678685129 0.3324785496 0.4404943883 0.0043782054 0.0096400000 46249565 955859216 1373700096 -0.3368442953 -0.0836989433 -0.1312121451 3101 1311867822.0962209702 0.3686317205 0.3324902081 0.4404943883 0.0043776048 0.0094240000 46252381 955859216 1373700096 -0.3379346728 -0.0842010379 -0.1309515685 3102 1311867822.1315379143 0.3682857454 0.3325017477 0.4404943883 0.0043781258 0.0093800000 46255365 955859216 1373700096 -0.3378124237 -0.0842949152 -0.1308816075 3103 1311867822.1634409428 0.3682935834 0.3325132822 0.4404943883 0.0043776047 0.0093950000 46258293 955859216 1373700096 -0.3382085860 -0.0835273415 -0.1302895099 3104 1311867822.1960899830 0.3675556779 0.3325245717 0.4404943883 0.0043780376 0.0094900000 46261109 955859216 1373700096 -0.3378849924 -0.0830763653 -0.1299361885 3105 1311867822.2317450047 0.3677361012 0.3325359119 0.4404943883 0.0043775943 0.0094380000 46264093 955859216 1373700096 -0.3379703164 -0.0849454999 -0.1298894435 3106 1311867822.2634150982 0.3642651439 0.3325461274 0.4404943883 0.0043787639 0.0097120000 46267021 955859216 1373700096 -0.3338729739 -0.0849789605 -0.1297969520 3107 1311867822.2954349518 0.3653069139 0.3325566716 0.4404943883 0.0043785322 0.0095390000 46269837 955859216 1373700096 -0.3356709480 -0.0854535252 -0.1298473775 3108 1311867822.3315870762 0.3663513958 0.3325675451 0.4404943883 0.0043779034 0.0093610000 46272821 955859216 1373700096 -0.3370984793 -0.0857675523 -0.1297226548 3109 1311867822.3635189533 0.3658937514 0.3325782643 0.4404943883 0.0043774057 0.0095040000 46275749 955859216 1373700096 -0.3368542194 -0.0863099247 -0.1298501939 3110 1311867822.3960089684 0.3668056428 0.3325892699 0.4404943883 0.0043773611 0.0094160000 46278565 955859216 1373700096 -0.3382382989 -0.0864913762 -0.1296755224 3111 1311867822.4314260483 0.3664822876 0.3326001645 0.4404943883 0.0043767720 0.0095180000 46281549 955859216 1373700096 -0.3386588991 -0.0866841152 -0.1293706149 3112 1311867822.4634740353 0.3660571873 0.3326109155 0.4404943883 0.0043763439 0.0093930000 46284421 955859216 1373700096 -0.3384569585 -0.0868351460 -0.1289883256 3113 1311867822.4957718849 0.3658619821 0.3326215968 0.4404943883 0.0043759545 0.0094180000 46287237 955859216 1373700096 -0.3387081027 -0.0873499438 -0.1285725236 3114 1311867822.5315260887 0.3668473065 0.3326325877 0.4404943883 0.0043762379 0.0093920000 46290277 955859216 1373700096 -0.3396264315 -0.0890848786 -0.1284982413 3115 1311867822.5634500980 0.3656963408 0.3326432021 0.4404943883 0.0043762425 0.0094920000 46293149 955859216 1373700096 -0.3384242952 -0.0902314857 -0.1284660250 3116 1311867822.5955328941 0.3631061912 0.3326529784 0.4404943883 0.0043783248 0.0094340000 46296021 955859216 1373700096 -0.3355574906 -0.0934529305 -0.1283781976 3117 1311867822.6315131187 0.3639622927 0.3326630231 0.4404943883 0.0043784432 0.0094830000 46299005 955859216 1373700096 -0.3367820978 -0.0936771184 -0.1283399016 3118 1311867822.6634640694 0.3654837310 0.3326735493 0.4404943883 0.0043779123 0.0094460000 46301877 955859216 1373700096 -0.3386566639 -0.0946117640 -0.1283201128 3119 1311867822.6954870224 0.3653914630 0.3326840392 0.4404943883 0.0043775550 0.0094130000 46304749 955859216 1373700096 -0.3390789628 -0.0950362161 -0.1281702220 3120 1311867822.7317390442 0.3659824431 0.3326947117 0.4404943883 0.0043780618 0.0094580000 46307677 955859216 1373700096 -0.3403154016 -0.0949577242 -0.1279834062 3121 1311867822.7634871006 0.3660258651 0.3327053914 0.4404943883 0.0043776807 0.0140610000 46310549 955859216 1373700096 -0.3410707712 -0.0945095494 -0.1280710995 3122 1311867822.7954308987 0.3663187325 0.3327161580 0.4404943883 0.0043776062 0.0229730000 46313421 955859216 1373700096 -0.3414961100 -0.0953940824 -0.1279152185 3123 1311867822.8314750195 0.3655097187 0.3327266587 0.4404943883 0.0043776865 0.0108960000 46316405 955859216 1373700096 -0.3416309655 -0.0952502340 -0.1278291792 3124 1311867822.8634629250 0.3669101894 0.3327376009 0.4404943883 0.0043806734 0.0095350000 46319277 955859216 1373700096 -0.3432371914 -0.0950627774 -0.1276099682 3125 1311867822.8955349922 0.3667491674 0.3327484846 0.4404943883 0.0043803376 0.0094380000 46322037 955859216 1373700096 -0.3436893821 -0.0947645977 -0.1274775565 3126 1311867822.9318330288 0.3657515347 0.3327590422 0.4404943883 0.0043798655 0.0093890000 46325077 955859216 1373700096 -0.3434917927 -0.0935598612 -0.1271823794 3127 1311867822.9635109901 0.3660477102 0.3327696877 0.4404943883 0.0043797130 0.0140870000 46327949 955859216 1373700096 -0.3445542753 -0.0932630002 -0.1270691901 3128 1311867822.9979970455 0.3656878769 0.3327802115 0.4404943883 0.0043803569 0.0139220000 46330933 955859216 1373700096 -0.3448978364 -0.0928297341 -0.1266343892 3129 1311867823.0344979763 0.3665670156 0.3327910094 0.4404943883 0.0043798633 0.0097780000 46333805 955859216 1373700096 -0.3465197086 -0.0926397070 -0.1264556199 3130 1311867823.0634639263 0.3673782051 0.3328020596 0.4404943883 0.0043798662 0.0093010000 46336565 955859216 1373700096 -0.3479855955 -0.0930205286 -0.1262795925 3131 1311867823.0971090794 0.3671494722 0.3328130297 0.4404943883 0.0043792838 0.0093710000 46339493 955859216 1373700096 -0.3484802544 -0.0928139463 -0.1259444058 3132 1311867823.1313869953 0.3669626117 0.3328239332 0.4404943883 0.0043802656 0.0092750000 46342421 955859216 1373700096 -0.3490357697 -0.0936129168 -0.1258713305 3133 1311867823.1635200977 0.3656733632 0.3328344182 0.4404943883 0.0043811363 0.0093920000 46345293 955859216 1373700096 -0.3486188650 -0.0929745659 -0.1257790774 3134 1311867823.1954131126 0.3654669821 0.3328448306 0.4404943883 0.0043854336 0.0093120000 46348165 955859216 1373700096 -0.3491238356 -0.0925897062 -0.1252456009 3135 1311867823.2316908836 0.3649235666 0.3328550631 0.4404943883 0.0043853389 0.0093200000 46351205 955859216 1373700096 -0.3492940366 -0.0931665301 -0.1251463592 3136 1311867823.2635869980 0.3660273850 0.3328656410 0.4404943883 0.0043908522 0.0092710000 46354077 955859216 1373700096 -0.3508982658 -0.0930512473 -0.1250011176 3137 1311867823.2955200672 0.3657519221 0.3328761243 0.4404943883 0.0043902481 0.0092870000 46356893 955859216 1373700096 -0.3514527678 -0.0920957178 -0.1245335415 3138 1311867823.3330919743 0.3661837280 0.3328867386 0.4404943883 0.0043898099 0.0092650000 46359933 955859216 1373700096 -0.3525058627 -0.0920327604 -0.1245256588 3139 1311867823.3635790348 0.3663669825 0.3328974045 0.4404943883 0.0043893818 0.0158190000 46362805 955859216 1373700096 -0.3531176746 -0.0926329866 -0.1243478209 3140 1311867823.3954129219 0.3676871359 0.3329084840 0.4404943883 0.0043893215 0.0101470000 46365621 955859216 1373700096 -0.3553066254 -0.0916748866 -0.1241293922 3141 1311867823.4318161011 0.3683997393 0.3329197834 0.4404943883 0.0043893569 0.0096590000 46368661 955859216 1373700096 -0.3567014933 -0.0913484469 -0.1240727007 3142 1311867823.4634220600 0.3676885366 0.3329308492 0.4404943883 0.0043915767 0.0096200000 46371533 955859216 1373700096 -0.3559086919 -0.0918655246 -0.1240140498 3143 1311867823.4969789982 0.3684311807 0.3329421442 0.4404943883 0.0043920625 0.0096150000 46374461 955859216 1373700096 -0.3572607934 -0.0918139294 -0.1238285452 3144 1311867823.5356218815 0.3686725795 0.3329535089 0.4404943883 0.0043923145 0.0096150000 46377445 955859216 1373700096 -0.3581268489 -0.0912372172 -0.1238939539 3145 1311867823.5636498928 0.3676916361 0.3329645544 0.4404943883 0.0043942289 0.0095800000 46380261 955859216 1373700096 -0.3573039174 -0.0914389640 -0.1235837191 3146 1311867823.5974569321 0.3677743673 0.3329756192 0.4404943883 0.0043939661 0.0096660000 46383189 955859216 1373700096 -0.3580203056 -0.0910559744 -0.1233081371 3147 1311867823.6316640377 0.3674314022 0.3329865679 0.4404943883 0.0044139004 0.0105250000 46386117 955859216 1373700096 -0.3585214615 -0.0901425704 -0.1231449619 3148 1311867823.6636750698 0.3668060303 0.3329973111 0.4404943883 0.0044172312 0.0146430000 46388989 955859216 1373700096 -0.3585966527 -0.0890737996 -0.1230252683 3149 1311867823.6956110001 0.3671081364 0.3330081434 0.4404943883 0.0044173035 0.0102840000 46391805 955859216 1373700096 -0.3591668010 -0.0892948732 -0.1226791292 3150 1311867823.7316160202 0.3670065999 0.3330189365 0.4404943883 0.0044167195 0.0101600000 46394845 955859216 1373700096 -0.3595048487 -0.0891476348 -0.1225867271 3151 1311867823.7635159492 0.3665786386 0.3330295870 0.4404943883 0.0044161666 0.0101130000 46397717 955859216 1373700096 -0.3596842885 -0.0886652097 -0.1226574183 3152 1311867823.7964189053 0.3660763800 0.3330400714 0.4404943883 0.0044156779 0.0099710000 46400589 955859216 1373700096 -0.3594928980 -0.0891262963 -0.1223749071 3153 1311867823.8316709995 0.3668886125 0.3330508067 0.4404943883 0.0044149839 0.0250780000 46403573 955859216 1373700096 -0.3607953787 -0.0890970826 -0.1217596978 3154 1311867823.8635869026 0.3655776083 0.3330611196 0.4404943883 0.0044149089 0.0115260000 46406445 955859216 1373700096 -0.3600614071 -0.0881152749 -0.1214779541 3155 1311867823.8993299007 0.3663499355 0.3330716707 0.4404943883 0.0044149247 0.0100650000 46409373 955859216 1373700096 -0.3611901104 -0.0877764523 -0.1210965365 3156 1311867823.9316000938 0.3655928075 0.3330819753 0.4404943883 0.0044278808 0.0098620000 46412301 955859216 1373700096 -0.3606207967 -0.0874825045 -0.1206938326 3157 1311867823.9639530182 0.3650358021 0.3330920969 0.4404943883 0.0044384898 0.0098910000 46415229 955859216 1373700096 -0.3604767025 -0.0868099779 -0.1201341972 3158 1311867823.9956440926 0.3650341928 0.3331022115 0.4404943883 0.0044400255 0.0141480000 46417989 955859216 1373700096 -0.3609559238 -0.0862091184 -0.1198664531 3159 1311867824.0315599442 0.3648549020 0.3331122630 0.4404943883 0.0044395927 0.0101410000 46421029 955859216 1373700096 -0.3612541258 -0.0860920995 -0.1195014343 3160 1311867824.0634789467 0.3654772043 0.3331225051 0.4404943883 0.0044405626 0.0097980000 46423901 955859216 1373700096 -0.3621354401 -0.0856462568 -0.1190226823 3161 1311867824.0966339111 0.3652543724 0.3331326702 0.4404943883 0.0044399840 0.0153550000 46426773 955859216 1373700096 -0.3623946607 -0.0849815905 -0.1187966689 3162 1311867824.1315801144 0.3650502563 0.3331427643 0.4404943883 0.0044405792 0.0100430000 46429757 955859216 1373700096 -0.3628062904 -0.0855438709 -0.1186927855 3163 1311867824.1636250019 0.3652031124 0.3331529004 0.4404943883 0.0044399595 0.0140540000 46432629 955859216 1373700096 -0.3631458580 -0.0857031420 -0.1182486340 3164 1311867824.1974411011 0.3648104668 0.3331629059 0.4404943883 0.0044394487 0.0101100000 46435557 955859216 1373700096 -0.3632310331 -0.0845451280 -0.1178680956 3165 1311867824.2314341068 0.3663594127 0.3331733945 0.4404943883 0.0044425697 0.0097400000 46438429 955859216 1373700096 -0.3651676178 -0.0846280456 -0.1174359769 3166 1311867824.2667160034 0.3653577268 0.3331835602 0.4404943883 0.0044422197 0.0097710000 46441413 955859216 1373700096 -0.3642778695 -0.0846201107 -0.1171907708 3167 1311867824.3015260696 0.3639072478 0.3331932614 0.4404943883 0.0044429476 0.0150950000 46444341 955859216 1373700096 -0.3632504046 -0.0830754712 -0.1169259399 3168 1311867824.3329520226 0.3645651340 0.3332031641 0.4404943883 0.0044425764 0.0107600000 46447269 955859216 1373700096 -0.3641870618 -0.0826324448 -0.1166407019 3169 1311867824.3655378819 0.3638731539 0.3332128422 0.4404943883 0.0044432064 0.0103790000 46450141 955859216 1373700096 -0.3637989461 -0.0819790587 -0.1161952391 3170 1311867824.3960471153 0.3626490533 0.3332221281 0.4404943883 0.0044426747 0.0100370000 46452901 955859216 1373700096 -0.3629414439 -0.0799966678 -0.1158924028 3171 1311867824.4315910339 0.3625933528 0.3332313905 0.4404943883 0.0044419940 0.0098970000 46455885 955859216 1373700096 -0.3628773987 -0.0787740797 -0.1155611351 3172 1311867824.4656479359 0.3622534871 0.3332405400 0.4404943883 0.0044413717 0.0252700000 46458869 955859216 1373700096 -0.3627635241 -0.0772772878 -0.1147859693 3173 1311867824.4978680611 0.3615926504 0.3332494754 0.4404943883 0.0044455155 0.0115960000 46461741 955859216 1373700096 -0.3623974621 -0.0763205588 -0.1145380288 3174 1311867824.5316801071 0.3604460061 0.3332580440 0.4404943883 0.0044449446 0.0102350000 46464613 955859216 1373700096 -0.3613753021 -0.0747239292 -0.1140308082 3175 1311867824.5658340454 0.3591322601 0.3332661933 0.4404943883 0.0044443853 0.0101290000 46467597 955859216 1373700096 -0.3603204489 -0.0728000924 -0.1134866327 3176 1311867824.5956490040 0.3591667414 0.3332743484 0.4404943883 0.0044439682 0.0099710000 46470357 955859216 1373700096 -0.3603338897 -0.0723760948 -0.1129624397 3177 1311867824.6318910122 0.3593782485 0.3332825649 0.4404943883 0.0044433202 0.0098230000 46473397 955859216 1373700096 -0.3602778316 -0.0722953752 -0.1121853068 3178 1311867824.6661880016 0.3599061370 0.3332909424 0.4404943883 0.0044430473 0.0098060000 46476269 955859216 1373700096 -0.3608518243 -0.0713285729 -0.1116720363 3179 1311867824.6979959011 0.3596649766 0.3332992387 0.4404943883 0.0044506666 0.0098700000 46479141 955859216 1373700096 -0.3608484566 -0.0709415525 -0.1109749377 3180 1311867824.7314980030 0.3585975170 0.3333071942 0.4404943883 0.0044599693 0.0097680000 46481957 955859216 1373700096 -0.3600583076 -0.0704965964 -0.1106803790 3181 1311867824.7639760971 0.3584287763 0.3333150915 0.4404943883 0.0044603204 0.0096800000 46484941 955859216 1373700096 -0.3599493504 -0.0702539459 -0.1101809219 3182 1311867824.7997510433 0.3579286337 0.3333228268 0.4404943883 0.0044620397 0.0150250000 46487813 955859216 1373700096 -0.3595554829 -0.0691966861 -0.1097882837 3183 1311867824.8315179348 0.3573639095 0.3333303797 0.4404943883 0.0044665621 0.0101900000 46490741 955859216 1373700096 -0.3591366708 -0.0690211728 -0.1091605946 3184 1311867824.8635060787 0.3563062549 0.3333375958 0.4404943883 0.0044663541 0.0099250000 46493613 955859216 1373700096 -0.3582397699 -0.0687724650 -0.1086746603 3185 1311867824.8995370865 0.3567807078 0.3333449563 0.4404943883 0.0044713663 0.0097560000 46496541 955859216 1373700096 -0.3588950336 -0.0686909184 -0.1078466251 3186 1311867824.9316530228 0.3569140434 0.3333523540 0.4404943883 0.0044707413 0.0099600000 46499469 955859216 1373700096 -0.3594690561 -0.0687226057 -0.1071810499 3187 1311867824.9636321068 0.3569711745 0.3333597650 0.4404943883 0.0044726691 0.0099610000 46502341 955859216 1373700096 -0.3598238230 -0.0690500438 -0.1063644439 3188 1311867824.9996089935 0.3556265831 0.3333667495 0.4404943883 0.0044731193 0.0098470000 46505381 955859216 1373700096 -0.3591249287 -0.0689528808 -0.1060163826 3189 1311867825.0316529274 0.3575811982 0.3333743426 0.4404943883 0.0044727490 0.0100280000 46508197 955859216 1373700096 -0.3615642190 -0.0694733188 -0.1054893509 3190 1311867825.0644180775 0.3566917181 0.3333816522 0.4404943883 0.0044722370 0.0101180000 46511013 955859216 1373700096 -0.3612609208 -0.0692880154 -0.1052176729 3191 1311867825.0997018814 0.3563703597 0.3333888564 0.4404943883 0.0044716433 0.0101380000 46513997 955859216 1373700096 -0.3615636230 -0.0692192167 -0.1049544141 3192 1311867825.1316909790 0.3566945195 0.3333961577 0.4404943883 0.0044711207 0.0143100000 46516925 955859216 1373700096 -0.3623729348 -0.0699903220 -0.1052274480 3193 1311867825.1636679173 0.3566303253 0.3334034343 0.4404943883 0.0044705734 0.0104540000 46519797 955859216 1373700096 -0.3627588153 -0.0709903389 -0.1050519049 3194 1311867825.1996359825 0.3570866585 0.3334108492 0.4404943883 0.0044703202 0.0102210000 46522725 955859216 1373700096 -0.3642134368 -0.0707563832 -0.1047148481 3195 1311867825.2316811085 0.3560990095 0.3334179503 0.4404943883 0.0044715543 0.0100870000 46525653 955859216 1373700096 -0.3650759161 -0.0704720914 -0.1048106924 3196 1311867825.2670049667 0.3557909727 0.3334249506 0.4404943883 0.0044719813 0.0101430000 46528637 955859216 1373700096 -0.3658307791 -0.0707921982 -0.1048061773 3197 1311867825.2996079922 0.3559926450 0.3334320097 0.4404943883 0.0044713259 0.0150320000 46531565 955859216 1373700096 -0.3670032024 -0.0705623254 -0.1043057665 3198 1311867825.3316459656 0.3546521664 0.3334386451 0.4404943883 0.0044722346 0.0104460000 46534381 955859216 1373700096 -0.3669305742 -0.0697897896 -0.1042204648 3199 1311867825.3635549545 0.3549994826 0.3334453850 0.4404943883 0.0044718736 0.0101580000 46537253 955859216 1373700096 -0.3680988848 -0.0703814626 -0.1039018035 3200 1311867825.3995220661 0.3554301262 0.3334522552 0.4404943883 0.0044716054 0.0102360000 46540293 955859216 1373700096 -0.3692670763 -0.0708233565 -0.1033696979 3201 1311867825.4329199791 0.3548057675 0.3334589261 0.4404943883 0.0044715504 0.0154700000 46543165 955859216 1373700096 -0.3694678545 -0.0705038533 -0.1030862927 3202 1311867825.4655759335 0.3551250398 0.3334656925 0.4404943883 0.0044711910 0.0107220000 46545981 955859216 1373700096 -0.3702761531 -0.0709360018 -0.1031907499 3203 1311867825.4996039867 0.3552474380 0.3334724930 0.4404943883 0.0044705202 0.0103940000 46548853 955859216 1373700096 -0.3707982600 -0.0715122521 -0.1030477136 3204 1311867825.5338120461 0.3552688658 0.3334792958 0.4404943883 0.0044699273 0.0102940000 46551837 955859216 1373700096 -0.3711667359 -0.0713959038 -0.1028860733 3205 1311867825.5637319088 0.3550992012 0.3334860415 0.4404943883 0.0044692721 0.0103550000 46554653 955859216 1373700096 -0.3712549508 -0.0711815953 -0.1030467302 3206 1311867825.5995988846 0.3557191491 0.3334929763 0.4404943883 0.0044689890 0.0102700000 46557581 955859216 1373700096 -0.3723409176 -0.0717965066 -0.1029419526 3207 1311867825.6372098923 0.3549258113 0.3334996595 0.4404943883 0.0044684701 0.0102550000 46560621 955859216 1373700096 -0.3721590340 -0.0715558827 -0.1028486639 3208 1311867825.6636829376 0.3551216722 0.3335063995 0.4404943883 0.0044678485 0.0144680000 46563325 955859216 1373700096 -0.3723844588 -0.0712290704 -0.1026826352 3209 1311867825.6997060776 0.3554255068 0.3335132300 0.4404943883 0.0044686567 0.0106600000 46566309 955859216 1373700096 -0.3731013834 -0.0715643466 -0.1025827155 3210 1311867825.7345299721 0.3563399315 0.3335203411 0.4404943883 0.0044680459 0.0102280000 46569237 955859216 1373700096 -0.3745437264 -0.0715106204 -0.1024634317 3211 1311867825.7654349804 0.3543695211 0.3335268342 0.4404943883 0.0044673801 0.0154250000 46572053 955859216 1373700096 -0.3726227880 -0.0709900633 -0.1027352959 3212 1311867825.7998030186 0.3548977077 0.3335334876 0.4404943883 0.0044669247 0.0105340000 46575093 955859216 1373700096 -0.3733648360 -0.0719282478 -0.1028939113 3213 1311867825.8355960846 0.3553858995 0.3335402889 0.4404943883 0.0044663699 0.0100530000 46578077 955859216 1373700096 -0.3743744195 -0.0716155618 -0.1027763560 3214 1311867825.8656499386 0.3547453284 0.3335468866 0.4404943883 0.0044658628 0.0111620000 46580837 955859216 1373700096 -0.3738396168 -0.0710800141 -0.1030013114 3215 1311867825.8996019363 0.3537416756 0.3335531680 0.4404943883 0.0044655475 0.0106010000 46583821 955859216 1373700096 -0.3727948964 -0.0720016360 -0.1032551602 3216 1311867825.9338490963 0.3528614640 0.3335591718 0.4404943883 0.0044653052 0.0102090000 46586749 955859216 1373700096 -0.3723036051 -0.0720483512 -0.1031791866 3217 1311867825.9640550613 0.3526086211 0.3335650933 0.4404943883 0.0044647865 0.0101670000 46589565 955859216 1373700096 -0.3718424141 -0.0714588240 -0.1035389677 3218 1311867825.9996759892 0.3536937833 0.3335713484 0.4404943883 0.0044643339 0.0102960000 46592493 955859216 1373700096 -0.3731752932 -0.0721734762 -0.1035492197 3219 1311867826.0327920914 0.3532351553 0.3335774570 0.4404943883 0.0044639154 0.0155370000 46595421 955859216 1373700096 -0.3727990091 -0.0715299845 -0.1037059277 3220 1311867826.0636880398 0.3530839384 0.3335835150 0.4404943883 0.0044634848 0.0249720000 46598293 955859216 1373700096 -0.3729307353 -0.0707686171 -0.1035468653 3221 1311867826.1009249687 0.3518705368 0.3335891924 0.4404943883 0.0044637234 0.0116450000 46601277 955859216 1373700096 -0.3720252514 -0.0705136284 -0.1040335000 3222 1311867826.1333520412 0.3524916470 0.3335950591 0.4404943883 0.0044630921 0.0103770000 46604205 955859216 1373700096 -0.3727319837 -0.0709743574 -0.1036341041 3223 1311867826.1658940315 0.3522595763 0.3336008501 0.4404943883 0.0044624447 0.0144060000 46607077 955859216 1373700096 -0.3727991283 -0.0702139884 -0.1037457064 3224 1311867826.1998670101 0.3521526754 0.3336066044 0.4404943883 0.0044624661 0.0104710000 46610005 955859216 1373700096 -0.3727625906 -0.0708059072 -0.1040033326 3225 1311867826.2345190048 0.3525676727 0.3336124838 0.4404943883 0.0044617888 0.0100420000 46612933 955859216 1373700096 -0.3733736575 -0.0708683133 -0.1039249524 3226 1311867826.2638120651 0.3523542583 0.3336182934 0.4404943883 0.0044618382 0.0100230000 46615749 955859216 1373700096 -0.3736933470 -0.0713510662 -0.1039134860 3227 1311867826.3011031151 0.3543969691 0.3336247324 0.4404943883 0.0044623757 0.0101550000 46618677 955859216 1373700096 -0.3757393658 -0.0716841742 -0.1042076498 3228 1311867826.3321969509 0.3534578681 0.3336308765 0.4404943883 0.0044627761 0.0101140000 46621381 955859216 1373700096 -0.3754942715 -0.0718611702 -0.1042460278 3229 1311867826.3637990952 0.3541604877 0.3336372344 0.4404943883 0.0044630825 0.0099850000 46624253 955859216 1373700096 -0.3760391772 -0.0714641362 -0.1041922420 3230 1311867826.3997180462 0.3531785607 0.3336432843 0.4404943883 0.0044624268 0.0101310000 46627181 955859216 1373700096 -0.3753490150 -0.0714545324 -0.1045176089 3231 1311867826.4321830273 0.3537911177 0.3336495201 0.4404943883 0.0044618531 0.0100680000 46630109 955859216 1373700096 -0.3761154115 -0.0717325136 -0.1045700237 3232 1311867826.4641919136 0.3535693288 0.3336556834 0.4404943883 0.0044612419 0.0100150000 46633037 955859216 1373700096 -0.3759899139 -0.0715326369 -0.1046338826 3233 1311867826.5007300377 0.3533762693 0.3336617832 0.4404943883 0.0044605746 0.0149780000 46635965 955859216 1373700096 -0.3760198355 -0.0713122934 -0.1046902984 3234 1311867826.5320169926 0.3533483446 0.3336678706 0.4404943883 0.0044599402 0.0143550000 46638837 955859216 1373700096 -0.3763062656 -0.0714414343 -0.1047716960 3235 1311867826.5638980865 0.3524354994 0.3336736720 0.4404943883 0.0044593965 0.0104130000 46641765 955859216 1373700096 -0.3754008412 -0.0709747821 -0.1049283594 3236 1311867826.6006839275 0.3531116843 0.3336796788 0.4404943883 0.0044588499 0.0110240000 46644693 955859216 1373700096 -0.3763707876 -0.0710128993 -0.1050433367 3237 1311867826.6315999031 0.3532680571 0.3336857302 0.4404943883 0.0044582486 0.0103290000 46647509 955859216 1373700096 -0.3769673705 -0.0709802434 -0.1050120443 3238 1311867826.6638810635 0.3531197906 0.3336917321 0.4404943883 0.0044577600 0.0103590000 46650381 955859216 1373700096 -0.3771549463 -0.0706447735 -0.1050748378 3239 1311867826.6997959614 0.3525518179 0.3336975549 0.4404943883 0.0044572497 0.0140060000 46653309 955859216 1373700096 -0.3773940206 -0.0700759143 -0.1050978601 3240 1311867826.7349510193 0.3536608517 0.3337037164 0.4404943883 0.0044566053 0.0152220000 46656293 955859216 1373700096 -0.3787871897 -0.0705644265 -0.1052589491 3241 1311867826.7678439617 0.3523741663 0.3337094771 0.4404943883 0.0044560210 0.0106470000 46659109 955859216 1373700096 -0.3778047562 -0.0708573088 -0.1054535583 3242 1311867826.8019490242 0.3526068628 0.3337153060 0.4404943883 0.0044556730 0.0102710000 46662093 955859216 1373700096 -0.3783880174 -0.0704525039 -0.1055371910 3243 1311867826.8324790001 0.3532939255 0.3337213432 0.4404943883 0.0044598213 0.0155830000 46664909 955859216 1373700096 -0.3791969419 -0.0714661330 -0.1057714075 3244 1311867826.8646159172 0.3525841534 0.3337271579 0.4404943883 0.0044592876 0.0146960000 46667725 955859216 1373700096 -0.3787695169 -0.0716015026 -0.1058939472 3245 1311867826.9008219242 0.3525142968 0.3337329475 0.4404943883 0.0044593846 0.0104730000 46670709 955859216 1373700096 -0.3791225851 -0.0719659105 -0.1060352102 3246 1311867826.9319140911 0.3527452648 0.3337388046 0.4404943883 0.0044618267 0.0102580000 46673469 955859216 1373700096 -0.3791387975 -0.0719671175 -0.1061408892 3247 1311867826.9639439583 0.3538799286 0.3337450076 0.4404943883 0.0044617899 0.0102140000 46676229 955859216 1373700096 -0.3806415498 -0.0719999671 -0.1061972901 3248 1311867827.0083661079 0.3540216386 0.3337512504 0.4404943883 0.0044629053 0.0103140000 46679381 955859216 1373700096 -0.3809859157 -0.0721953288 -0.1062815785 3249 1311867827.0334970951 0.3533307612 0.3337572768 0.4404943883 0.0044623902 0.0101870000 46682029 955859216 1373700096 -0.3805084825 -0.0720530599 -0.1065088063 3250 1311867827.0653018951 0.3537819684 0.3337634382 0.4404943883 0.0044637574 0.0101620000 46684733 955859216 1373700096 -0.3811904788 -0.0724185258 -0.1066547185 3251 1311867827.0995759964 0.3537788987 0.3337695949 0.4404943883 0.0044649894 0.0100650000 46687549 955859216 1373700096 -0.3808009624 -0.0721571222 -0.1070699468 3252 1311867827.1319890022 0.3538638949 0.3337757740 0.4404943883 0.0044644528 0.0100340000 46690253 955859216 1373700096 -0.3808262050 -0.0723189339 -0.1073040962 3253 1311867827.1636219025 0.3540396690 0.3337820033 0.4404943883 0.0044644859 0.0101750000 46693181 955859216 1373700096 -0.3809878528 -0.0724317804 -0.1076681688 3254 1311867827.2006959915 0.3545896113 0.3337883977 0.4404943883 0.0044661200 0.0102750000 46696165 955859216 1373700096 -0.3812853396 -0.0728035271 -0.1079668179 3255 1311867827.2315700054 0.3538622260 0.3337945648 0.4404943883 0.0044656182 0.0101440000 46698925 955859216 1373700096 -0.3803346455 -0.0724646002 -0.1083244383 3256 1311867827.2656030655 0.3537664711 0.3338006987 0.4404943883 0.0044650943 0.0101460000 46701685 955859216 1373700096 -0.3799754083 -0.0724265128 -0.1088469252 3257 1311867827.2999110222 0.3540650010 0.3338069205 0.4404943883 0.0044656130 0.0101440000 46704669 955859216 1373700096 -0.3805436194 -0.0722585097 -0.1086995676 3258 1311867827.3331999779 0.3537604511 0.3338130449 0.4404943883 0.0044649782 0.0100640000 46707485 955859216 1373700096 -0.3804061413 -0.0713426843 -0.1086376607 3259 1311867827.3665180206 0.3535434604 0.3338190991 0.4404943883 0.0044644767 0.0235600000 46710357 955859216 1373700096 -0.3802955449 -0.0712931678 -0.1086462140 3260 1311867827.4023349285 0.3532268405 0.3338250524 0.4404943883 0.0044652237 0.0117360000 46713397 955859216 1373700096 -0.3799709380 -0.0710064694 -0.1089129522 3261 1311867827.4316511154 0.3535286784 0.3338310946 0.4404943883 0.0044648527 0.0104510000 46716157 955859216 1373700096 -0.3803427219 -0.0708097517 -0.1086531430 3262 1311867827.4660930634 0.3534339070 0.3338371040 0.4404943883 0.0044642024 0.0102850000 46719085 955859216 1373700096 -0.3803622127 -0.0709124506 -0.1089119166 3263 1311867827.5022308826 0.3528098166 0.3338429185 0.4404943883 0.0044646352 0.0103230000 46722125 955859216 1373700096 -0.3797177076 -0.0712914616 -0.1091273203 3264 1311867827.5346870422 0.3533828557 0.3338489050 0.4404943883 0.0044646508 0.0104190000 46724941 955859216 1373700096 -0.3805098832 -0.0708778054 -0.1090457514 3265 1311867827.5639040470 0.3530770242 0.3338547942 0.4404943883 0.0044641719 0.0147490000 46727813 955859216 1373700096 -0.3802413046 -0.0713224560 -0.1092659757 3266 1311867827.6014358997 0.3530533314 0.3338606725 0.4404943883 0.0044644954 0.0106530000 46730797 955859216 1373700096 -0.3800795376 -0.0720172152 -0.1094960049 3267 1311867827.6328499317 0.3536637425 0.3338667340 0.4404943883 0.0044644270 0.0280180000 46733669 955859216 1373700096 -0.3809763193 -0.0714934915 -0.1091043726 3268 1311867827.6636641026 0.3538508713 0.3338728491 0.4404943883 0.0044637582 0.0124470000 46736541 955859216 1373700096 -0.3814823031 -0.0711346716 -0.1091597602 3269 1311867827.7023649216 0.3525600731 0.3338785656 0.4404943883 0.0044633314 0.0105550000 46739581 955859216 1373700096 -0.3800027370 -0.0712313727 -0.1091385186 3270 1311867827.7343521118 0.3518508673 0.3338840617 0.4404943883 0.0044634449 0.0155970000 46742453 955859216 1373700096 -0.3794360161 -0.0707013682 -0.1091177762 3271 1311867827.7669301033 0.3514262140 0.3338894247 0.4404943883 0.0044653885 0.0105110000 46745269 955859216 1373700096 -0.3792583644 -0.0705708414 -0.1090307906 3272 1311867827.8077390194 0.3517350852 0.3338948787 0.4404943883 0.0044660994 0.0244710000 46748421 955859216 1373700096 -0.3795746267 -0.0712066442 -0.1087350771 3273 1311867827.8316879272 0.3530555367 0.3339007329 0.4404943883 0.0044663506 0.0117000000 46751013 955859216 1373700096 -0.3808748126 -0.0710726976 -0.1085788980 3274 1311867827.8644089699 0.3520153165 0.3339062657 0.4404943883 0.0044658340 0.0109320000 46753997 955859216 1373700096 -0.3798571825 -0.0709095448 -0.1086080447 3275 1311867827.9007999897 0.3530741334 0.3339121185 0.4404943883 0.0044674355 0.0113420000 46756869 955859216 1373700096 -0.3807015717 -0.0715351254 -0.1085745096 3276 1311867827.9316790104 0.3528373539 0.3339178954 0.4404943883 0.0044689745 0.0153990000 46759741 955859216 1373700096 -0.3808974624 -0.0711933449 -0.1084363014 3277 1311867827.9717168808 0.3531283140 0.3339237576 0.4404943883 0.0044721016 0.0107110000 46762781 955859216 1373700096 -0.3809755743 -0.0716531873 -0.1084820703 3278 1311867827.9999699593 0.3523626626 0.3339293827 0.4404943883 0.0044718248 0.0105220000 46765653 955859216 1373700096 -0.3802079856 -0.0721182302 -0.1087834463 3279 1311867828.0320069790 0.3526107669 0.3339350800 0.4404943883 0.0044715749 0.0104440000 46768469 955859216 1373700096 -0.3803606927 -0.0720471367 -0.1087094098 3280 1311867828.0711700916 0.3530706465 0.3339409140 0.4404943883 0.0044732211 0.0101630000 46771509 955859216 1373700096 -0.3811325431 -0.0721056908 -0.1085913926 3281 1311867828.1003229618 0.3523094952 0.3339465125 0.4404943883 0.0044726401 0.0104750000 46774381 955859216 1373700096 -0.3802742958 -0.0724607706 -0.1088179350 3282 1311867828.1317639351 0.3524070084 0.3339521372 0.4404943883 0.0044740801 0.0103810000 46777197 955859216 1373700096 -0.3802781105 -0.0720313713 -0.1085897014 3283 1311867828.1714239120 0.3542929590 0.3339583330 0.4404943883 0.0044750280 0.0157850000 46780293 955859216 1373700096 -0.3820716143 -0.0723717660 -0.1084049791 3284 1311867828.2080869675 0.3535832167 0.3339643089 0.4404943883 0.0044816464 0.0106860000 46783333 955859216 1373700096 -0.3808649480 -0.0726566687 -0.1081578955 3285 1311867828.2316999435 0.3526631892 0.3339700011 0.4404943883 0.0044826125 0.0103060000 46785925 955859216 1373700096 -0.3800259829 -0.0722373798 -0.1079846844 3286 1311867828.2725389004 0.3523144722 0.3339755838 0.4404943883 0.0044820950 0.0103270000 46789021 955859216 1373700096 -0.3796711266 -0.0714500546 -0.1078010276 3287 1311867828.3008439541 0.3530341983 0.3339813819 0.4404943883 0.0044818062 0.0103490000 46791837 955859216 1373700096 -0.3799993098 -0.0721363053 -0.1075236276 ================================================ FILE: icra2018_results/1080/violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:34:07 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 -nan 0.0076110000 23816669 955859216 1375797248 -0.0000000000 0.0000000000 -0.0000000000 2 1311867170.4941389561 0.0573643968 0.0578082204 0.0582520440 0.0124427658 0.0032800000 36400709 955859216 1373700096 -0.0004107888 -0.0012853811 -0.0024214056 3 1311867170.5264289379 0.0565281659 0.0573815356 0.0582520440 0.0101379281 0.0019070000 36404029 955859216 1373700096 -0.0017274972 -0.0022942068 -0.0047791684 4 1311867170.5623490810 0.0561557040 0.0570750777 0.0582520440 0.0096907319 0.0018000000 36407413 955859216 1373700096 0.0001666794 -0.0028439625 -0.0061352286 5 1311867170.5942170620 0.0565002635 0.0569601148 0.0582520440 0.0086579290 0.0018090000 36410613 955859216 1373700096 0.0032586332 -0.0038356904 -0.0071666827 6 1311867170.6260869503 0.0565145761 0.0568858584 0.0582520440 0.0085193343 0.0018020000 36414285 955859216 1373700096 0.0035894865 -0.0050017708 -0.0088247461 7 1311867170.6621398926 0.0566341281 0.0568498969 0.0582520440 0.0083896253 0.0026810000 36417325 955859216 1373700096 0.0042680521 -0.0060192915 -0.0103889499 8 1311867170.6942050457 0.0565385632 0.0568109802 0.0582520440 0.0080447921 0.0033580000 36420141 955859216 1373700096 0.0039733560 -0.0066503519 -0.0121041704 9 1311867170.7263879776 0.0573048107 0.0568658503 0.0582520440 0.0083447402 0.0026760000 36423781 955859216 1373700096 0.0047303978 -0.0067653782 -0.0132004693 10 1311867170.7620189190 0.0571196526 0.0568912305 0.0582520440 0.0084103537 0.0026490000 36428421 955859216 1373700096 0.0037223531 -0.0089277960 -0.0147628011 11 1311867170.7941920757 0.0576276146 0.0569581745 0.0582520440 0.0083697979 0.0033060000 36431181 955859216 1373700096 0.0046895202 -0.0110970335 -0.0163411610 12 1311867170.8262820244 0.0582976639 0.0570697986 0.0582976639 0.0084025426 0.0033880000 36434109 955859216 1373700096 0.0057686996 -0.0142045021 -0.0181409754 13 1311867170.8622210026 0.0583833158 0.0571708384 0.0583833158 0.0082224769 0.0033760000 36437093 955859216 1373700096 0.0054557901 -0.0167554766 -0.0205254089 14 1311867170.8943779469 0.0589015223 0.0572944587 0.0589015223 0.0079283863 0.0033840000 36439909 955859216 1373700096 0.0052011162 -0.0189121775 -0.0228569396 15 1311867170.9263520241 0.0592489354 0.0574247571 0.0592489354 0.0079798603 0.0033860000 36442837 955859216 1373700096 0.0049796882 -0.0210459232 -0.0255782045 16 1311867170.9621469975 0.0584923401 0.0574914811 0.0592489354 0.0077811651 0.0033640000 36445821 955859216 1373700096 0.0025199968 -0.0233074185 -0.0286620855 17 1311867170.9942629337 0.0581994466 0.0575331261 0.0592489354 0.0076057664 0.0027010000 36450173 955859216 1373700096 0.0015490805 -0.0249245539 -0.0317789726 18 1311867171.0262739658 0.0584000424 0.0575812881 0.0592489354 0.0073929096 0.0033670000 36456301 955859216 1373700096 0.0013883736 -0.0262807086 -0.0344569013 19 1311867171.0623519421 0.0577873662 0.0575921343 0.0592489354 0.0078873197 0.0033770000 36459285 955859216 1373700096 0.0006972001 -0.0291270595 -0.0373714454 20 1311867171.0942349434 0.0569595098 0.0575605031 0.0592489354 0.0077921904 0.0033480000 36462101 955859216 1373700096 0.0012762174 -0.0310345031 -0.0399133191 21 1311867171.1262509823 0.0568150692 0.0575250063 0.0592489354 0.0076689374 0.0033740000 36465029 955859216 1373700096 0.0016514439 -0.0313870944 -0.0420561284 22 1311867171.1622469425 0.0565040112 0.0574785974 0.0592489354 0.0076285348 0.0039710000 36468013 955859216 1373700096 0.0030351996 -0.0331967324 -0.0437408686 23 1311867171.1942689419 0.0555193648 0.0573934134 0.0592489354 0.0079586562 0.0039150000 36470829 955859216 1373700096 0.0048778029 -0.0332864076 -0.0448248647 24 1311867171.2262530327 0.0571338311 0.0573825974 0.0592489354 0.0079997750 0.0039360000 36473757 955859216 1373700096 0.0073625711 -0.0331346616 -0.0454695672 25 1311867171.2622439861 0.0565472208 0.0573491824 0.0592489354 0.0080357771 0.0038100000 36476741 955859216 1373700096 0.0080455421 -0.0333054364 -0.0465254784 26 1311867171.2943410873 0.0566246100 0.0573213142 0.0592489354 0.0079460871 0.0026460000 36479501 955859216 1373700096 0.0086148735 -0.0314770043 -0.0471827500 27 1311867171.3263869286 0.0564643480 0.0572895747 0.0592489354 0.0082445405 0.0039440000 36482429 955859216 1373700096 0.0059655621 -0.0306835845 -0.0484963097 28 1311867171.3622460365 0.0552399196 0.0572163727 0.0592489354 0.0081227706 0.0039460000 36485413 955859216 1373700096 0.0032682631 -0.0301576611 -0.0500395149 29 1311867171.3941431046 0.0556969531 0.0571639790 0.0592489354 0.0082713027 0.0031070000 36488229 955859216 1373700096 0.0016476010 -0.0285116453 -0.0511297844 30 1311867171.4262878895 0.0563100055 0.0571355132 0.0592489354 0.0082767399 0.0026540000 36491157 955859216 1373700096 0.0012457182 -0.0286312439 -0.0526631214 31 1311867171.4622440338 0.0560833812 0.0571015734 0.0592489354 0.0081786182 0.0039730000 36494141 955859216 1373700096 0.0002764402 -0.0299044419 -0.0547497384 32 1311867171.4944040775 0.0560423285 0.0570684720 0.0592489354 0.0081226718 0.0039740000 36496957 955859216 1373700096 0.0016207356 -0.0298378542 -0.0567160398 33 1311867171.5261778831 0.0557431914 0.0570283120 0.0592489354 0.0080032451 0.0030740000 36502957 955859216 1373700096 0.0005223858 -0.0294314679 -0.0586474016 34 1311867171.5622971058 0.0550522953 0.0569701939 0.0592489354 0.0078938662 0.0039890000 36512341 955859216 1373700096 0.0014596751 -0.0297163595 -0.0602234267 35 1311867171.5942931175 0.0556190498 0.0569315898 0.0592489354 0.0078288301 0.0030970000 36515157 955859216 1373700096 0.0025773393 -0.0281724278 -0.0610714294 36 1311867171.6263399124 0.0556017309 0.0568946492 0.0592489354 0.0077317573 0.0039480000 36518085 955859216 1373700096 0.0013724428 -0.0286738537 -0.0617055781 37 1311867171.6622560024 0.0552114323 0.0568491569 0.0592489354 0.0076307518 0.0030950000 36521069 955859216 1373700096 -0.0010721460 -0.0294353738 -0.0626045093 38 1311867171.6943440437 0.0560284704 0.0568275599 0.0592489354 0.0078482063 0.0040100000 36523885 955859216 1373700096 -0.0001744902 -0.0292495750 -0.0627629161 39 1311867171.7262439728 0.0563391522 0.0568150366 0.0592489354 0.0077815257 0.0031230000 36526813 955859216 1373700096 0.0001489436 -0.0294913184 -0.0632338971 40 1311867171.7621190548 0.0570984222 0.0568221212 0.0592489354 0.0077027939 0.0040270000 36529797 955859216 1373700096 0.0010186225 -0.0305383466 -0.0636917725 41 1311867171.7941710949 0.0575007871 0.0568386741 0.0592489354 0.0076910207 0.0031500000 36532613 955859216 1373700096 0.0009916978 -0.0316385403 -0.0645628721 42 1311867171.8262550831 0.0579950400 0.0568662066 0.0592489354 0.0076249695 0.0027080000 36535541 955859216 1373700096 -0.0001166869 -0.0320221558 -0.0655769780 43 1311867171.8623590469 0.0575436093 0.0568819601 0.0592489354 0.0075527394 0.0036060000 36538525 955859216 1373700096 -0.0036014377 -0.0323108770 -0.0670081452 44 1311867171.8944430351 0.0572256669 0.0568897717 0.0592489354 0.0076857239 0.0035290000 36541397 955859216 1373700096 -0.0061103650 -0.0326210931 -0.0679241642 45 1311867171.9262220860 0.0583620220 0.0569224883 0.0592489354 0.0076521986 0.0035590000 36544269 955859216 1373700096 -0.0067454251 -0.0319115818 -0.0681827441 46 1311867171.9624669552 0.0588577837 0.0569645600 0.0592489354 0.0075971349 0.0030140000 36547253 955859216 1373700096 -0.0080130370 -0.0316465013 -0.0685496032 47 1311867171.9946711063 0.0598744825 0.0570264732 0.0598744825 0.0076453231 0.0036230000 36550125 955859216 1373700096 -0.0088139819 -0.0309248958 -0.0681076795 48 1311867172.0262680054 0.0607723407 0.0571045121 0.0607723407 0.0077630543 0.0035660000 36552997 955859216 1373700096 -0.0100077707 -0.0300552286 -0.0675363019 49 1311867172.0622880459 0.0613152608 0.0571904458 0.0613152608 0.0077074772 0.0028460000 36555981 955859216 1373700096 -0.0115916356 -0.0295254271 -0.0668171197 50 1311867172.0941960812 0.0615796484 0.0572782298 0.0615796484 0.0076868762 0.0035590000 36558853 955859216 1373700096 -0.0134140458 -0.0292217508 -0.0661482066 51 1311867172.1263689995 0.0623959638 0.0573785775 0.0623959638 0.0076673735 0.0035980000 36561725 955859216 1373700096 -0.0148234302 -0.0294212643 -0.0652794167 52 1311867172.1623349190 0.0618304349 0.0574641902 0.0623959638 0.0076640960 0.0036090000 36564709 955859216 1373700096 -0.0177440308 -0.0296264123 -0.0650395080 53 1311867172.1944270134 0.0608019605 0.0575271670 0.0623959638 0.0076097956 0.0035880000 36567581 955859216 1373700096 -0.0217591859 -0.0292327590 -0.0647991449 54 1311867172.2264409065 0.0604843162 0.0575819290 0.0623959638 0.0077616703 0.0036140000 36570453 955859216 1373700096 -0.0255313590 -0.0290392861 -0.0646177605 55 1311867172.2622280121 0.0599735901 0.0576254138 0.0623959638 0.0076997812 0.0028830000 36573437 955859216 1373700096 -0.0287051070 -0.0282654595 -0.0641180202 56 1311867172.2944829464 0.0603031665 0.0576732308 0.0623959638 0.0076439698 0.0036490000 36576309 955859216 1373700096 -0.0310184173 -0.0276256576 -0.0636529401 57 1311867172.3263380527 0.0596789345 0.0577084186 0.0623959638 0.0076163298 0.0036980000 36579181 955859216 1373700096 -0.0344727300 -0.0272127576 -0.0633358210 58 1311867172.3624010086 0.0600020699 0.0577479643 0.0623959638 0.0075698504 0.0032410000 36582165 955859216 1373700096 -0.0369471647 -0.0270582009 -0.0632330999 59 1311867172.3942890167 0.0590594187 0.0577701923 0.0623959638 0.0075346622 0.0027790000 36585037 955859216 1373700096 -0.0399243273 -0.0272818822 -0.0634784549 60 1311867172.4265220165 0.0593483038 0.0577964942 0.0623959638 0.0075632145 0.0041770000 36587909 955859216 1373700096 -0.0423277840 -0.0278974120 -0.0638046190 61 1311867172.4623498917 0.0592823029 0.0578208517 0.0623959638 0.0075344824 0.0041280000 36590893 955859216 1373700096 -0.0447822809 -0.0283342525 -0.0641430020 62 1311867172.4952669144 0.0598548390 0.0578536579 0.0623959638 0.0075761461 0.0028670000 36593709 955859216 1373700096 -0.0459441841 -0.0280010514 -0.0641537681 63 1311867172.5263059139 0.0592856146 0.0578763874 0.0623959638 0.0075514025 0.0025500000 36596581 955859216 1373700096 -0.0488195010 -0.0291024540 -0.0648143813 64 1311867172.5624930859 0.0592078380 0.0578971913 0.0623959638 0.0074914306 0.0041990000 36599565 955859216 1373700096 -0.0510668606 -0.0300126076 -0.0654537901 65 1311867172.5945439339 0.0605114140 0.0579374101 0.0623959638 0.0074647880 0.0042210000 36608525 955859216 1373700096 -0.0504447147 -0.0297312327 -0.0659817085 66 1311867172.6263699532 0.0605484210 0.0579769709 0.0623959638 0.0074354855 0.0027980000 36624253 955859216 1373700096 -0.0523444973 -0.0297914483 -0.0666505024 67 1311867172.6624419689 0.0607979298 0.0580190748 0.0623959638 0.0073801969 0.0041830000 36627237 955859216 1373700096 -0.0542066693 -0.0297007486 -0.0673354343 68 1311867172.6945450306 0.0605306998 0.0580560104 0.0623959638 0.0074680633 0.0032530000 36630109 955859216 1373700096 -0.0564697236 -0.0296872072 -0.0676793978 69 1311867172.7263929844 0.0613786466 0.0581041646 0.0623959638 0.0074493060 0.0028480000 36632981 955859216 1373700096 -0.0586345308 -0.0290561803 -0.0680601671 70 1311867172.7623739243 0.0616353899 0.0581546107 0.0623959638 0.0074160942 0.0042250000 36635965 955859216 1373700096 -0.0613653101 -0.0282675326 -0.0685721114 71 1311867172.7944509983 0.0611701421 0.0581970829 0.0623959638 0.0073780874 0.0042420000 36638781 955859216 1373700096 -0.0647342131 -0.0287003163 -0.0692153499 72 1311867172.8263089657 0.0619259104 0.0582488722 0.0623959638 0.0073540445 0.0027740000 36641709 955859216 1373700096 -0.0673164651 -0.0287292432 -0.0699632689 73 1311867172.8632309437 0.0619711727 0.0582998626 0.0623959638 0.0073244054 0.0026180000 36644749 955859216 1373700096 -0.0701904967 -0.0293916482 -0.0707595721 74 1311867172.8944649696 0.0612851717 0.0583402046 0.0623959638 0.0072772302 0.0043030000 36647509 955859216 1373700096 -0.0727139339 -0.0297379103 -0.0714770481 75 1311867172.9263219833 0.0607994013 0.0583729939 0.0623959638 0.0072319603 0.0042750000 36650437 955859216 1373700096 -0.0753362477 -0.0308228228 -0.0721556470 76 1311867172.9623310566 0.0607560389 0.0584043498 0.0623959638 0.0071861413 0.0040730000 36653421 955859216 1373700096 -0.0765243694 -0.0314130373 -0.0727757588 77 1311867172.9945271015 0.0605467632 0.0584321733 0.0623959638 0.0071421069 0.0029010000 36656237 955859216 1373700096 -0.0778298154 -0.0316108689 -0.0731807426 78 1311867173.0262629986 0.0599394217 0.0584514970 0.0623959638 0.0070975123 0.0026030000 36659109 955859216 1373700096 -0.0792083070 -0.0322198644 -0.0735924691 79 1311867173.0624630451 0.0599534661 0.0584705093 0.0623959638 0.0070550225 0.0026250000 36662093 955859216 1373700096 -0.0802628770 -0.0325983502 -0.0737972781 80 1311867173.0945179462 0.0603840500 0.0584944285 0.0623959638 0.0070440392 0.0026000000 36664965 955859216 1373700096 -0.0806793347 -0.0327480473 -0.0738910064 81 1311867173.1267819405 0.0601412021 0.0585147591 0.0623959638 0.0070214993 0.0026310000 36667893 955859216 1373700096 -0.0822019577 -0.0329018012 -0.0742284954 82 1311867173.1622309685 0.0605027936 0.0585390034 0.0623959638 0.0070163984 0.0036410000 36670877 955859216 1373700096 -0.0830204561 -0.0321661904 -0.0740380585 83 1311867173.1943008900 0.0611637309 0.0585706266 0.0623959638 0.0069748430 0.0043440000 36673693 955859216 1373700096 -0.0838398710 -0.0313801728 -0.0739886165 84 1311867173.2264449596 0.0609587729 0.0585990569 0.0623959638 0.0069412486 0.0043060000 36676565 955859216 1373700096 -0.0858600736 -0.0316319466 -0.0739533529 85 1311867173.2622020245 0.0616162233 0.0586345530 0.0623959638 0.0069232025 0.0039770000 36679549 955859216 1373700096 -0.0869617462 -0.0308770332 -0.0738525316 86 1311867173.2942678928 0.0622052848 0.0586760732 0.0623959638 0.0068853227 0.0028940000 36682365 955859216 1373700096 -0.0885366723 -0.0306129418 -0.0738170892 87 1311867173.3262879848 0.0621007383 0.0587154371 0.0623959638 0.0068897172 0.0026310000 36685237 955859216 1373700096 -0.0905150771 -0.0310658365 -0.0740731657 88 1311867173.3623280525 0.0625792891 0.0587593445 0.0625792891 0.0068525364 0.0043620000 36688277 955859216 1373700096 -0.0920253247 -0.0308333728 -0.0741953924 89 1311867173.3942871094 0.0622987822 0.0587991135 0.0625792891 0.0068374057 0.0043660000 36691093 955859216 1373700096 -0.0942146257 -0.0314071402 -0.0744227767 90 1311867173.4262790680 0.0619173758 0.0588337609 0.0625792891 0.0068284340 0.0030210000 36693965 955859216 1373700096 -0.0964311808 -0.0322666653 -0.0748561099 91 1311867173.4622900486 0.0621018298 0.0588696737 0.0625792891 0.0068392177 0.0039460000 36696949 955859216 1373700096 -0.0981279835 -0.0327655599 -0.0752745941 92 1311867173.4943389893 0.0626950338 0.0589112537 0.0626950338 0.0069090334 0.0038860000 36699821 955859216 1373700096 -0.0998766273 -0.0332449526 -0.0755473673 93 1311867173.5263900757 0.0625697896 0.0589505928 0.0626950338 0.0068749274 0.0030500000 36702749 955859216 1373700096 -0.1020834297 -0.0332621336 -0.0759317130 94 1311867173.5624370575 0.0625306889 0.0589886789 0.0626950338 0.0068554579 0.0030480000 36705733 955859216 1373700096 -0.1041029096 -0.0327580795 -0.0760977417 95 1311867173.5943109989 0.0626233071 0.0590269382 0.0626950338 0.0068415086 0.0038820000 36708549 955859216 1373700096 -0.1061777920 -0.0327533931 -0.0763750151 96 1311867173.6263959408 0.0618173778 0.0590560052 0.0626950338 0.0068329414 0.0039580000 36711421 955859216 1373700096 -0.1087772772 -0.0333295017 -0.0769538283 97 1311867173.6623299122 0.0622303784 0.0590887307 0.0626950338 0.0068032805 0.0039190000 36714405 955859216 1373700096 -0.1100943759 -0.0332700610 -0.0772775561 98 1311867173.6943540573 0.0627756715 0.0591263526 0.0627756715 0.0067726529 0.0038890000 36717277 955859216 1373700096 -0.1110275015 -0.0336259343 -0.0778172240 99 1311867173.7267971039 0.0620555356 0.0591559403 0.0627756715 0.0067512247 0.0030710000 36720205 955859216 1373700096 -0.1136158556 -0.0340314545 -0.0788379461 100 1311867173.7623970509 0.0624423511 0.0591888044 0.0627756715 0.0067278517 0.0027080000 36723189 955859216 1373700096 -0.1146482453 -0.0334424376 -0.0794207081 101 1311867173.7943561077 0.0630516037 0.0592270499 0.0630516037 0.0066970020 0.0039210000 36725949 955859216 1373700096 -0.1154962927 -0.0331627689 -0.0798518360 102 1311867173.8265669346 0.0618787706 0.0592530472 0.0630516037 0.0066657577 0.0039420000 36728877 955859216 1373700096 -0.1185844168 -0.0343398824 -0.0809440538 103 1311867173.8635799885 0.0628832355 0.0592882917 0.0630516037 0.0066659133 0.0039620000 36731805 955859216 1373700096 -0.1192452833 -0.0340164378 -0.0815311745 104 1311867173.8946080208 0.0627003089 0.0593210996 0.0630516037 0.0066368839 0.0039500000 36734677 955859216 1373700096 -0.1207163259 -0.0344067961 -0.0823825374 105 1311867173.9266970158 0.0617323071 0.0593440635 0.0630516037 0.0066204679 0.0031190000 36737605 955859216 1373700096 -0.1230896935 -0.0357697718 -0.0837187320 106 1311867173.9625461102 0.0624897443 0.0593737397 0.0630516037 0.0066243586 0.0039920000 36740589 955859216 1373700096 -0.1240187362 -0.0351723321 -0.0841691792 107 1311867173.9944310188 0.0629306659 0.0594069820 0.0630516037 0.0066187753 0.0039300000 36743405 955859216 1373700096 -0.1251786202 -0.0349208079 -0.0845904127 108 1311867174.0264260769 0.0629139245 0.0594394537 0.0630516037 0.0066444494 0.0039740000 36746277 955859216 1373700096 -0.1265595406 -0.0355836675 -0.0857752785 109 1311867174.0624630451 0.0634051710 0.0594758364 0.0634051710 0.0066309939 0.0031830000 36749261 955859216 1373700096 -0.1280233115 -0.0340064578 -0.0860817507 110 1311867174.0945188999 0.0646023378 0.0595224410 0.0646023378 0.0066214346 0.0039990000 36752133 955859216 1373700096 -0.1282935292 -0.0327620395 -0.0860291570 111 1311867174.1264541149 0.0644067675 0.0595664439 0.0646023378 0.0066129328 0.0040010000 36755005 955859216 1373700096 -0.1306741983 -0.0333944038 -0.0867904127 112 1311867174.1624329090 0.0644297376 0.0596098662 0.0646023378 0.0066027792 0.0031680000 36757989 955859216 1373700096 -0.1327649355 -0.0329497904 -0.0871127546 113 1311867174.1943979263 0.0650919974 0.0596583806 0.0650919974 0.0065919597 0.0040100000 36760861 955859216 1373700096 -0.1333776414 -0.0319342501 -0.0871342868 114 1311867174.2267580032 0.0649932772 0.0597051780 0.0650919974 0.0065714718 0.0040490000 36763789 955859216 1373700096 -0.1354505420 -0.0327035114 -0.0877416655 115 1311867174.2626769543 0.0646182969 0.0597479007 0.0650919974 0.0065431333 0.0032280000 36766717 955859216 1373700096 -0.1381608546 -0.0327509120 -0.0882166773 116 1311867174.2945280075 0.0658868626 0.0598008228 0.0658868626 0.0065321674 0.0028050000 36769589 955859216 1373700096 -0.1382757425 -0.0319922380 -0.0884352475 117 1311867174.3265740871 0.0650599450 0.0598457726 0.0658868626 0.0065056222 0.0041250000 36772461 955859216 1373700096 -0.1409851611 -0.0325854793 -0.0890767500 118 1311867174.3624329567 0.0648365468 0.0598880673 0.0658868626 0.0064932701 0.0040980000 36775501 955859216 1373700096 -0.1430240422 -0.0323067307 -0.0891459659 119 1311867174.3946359158 0.0652753487 0.0599333386 0.0658868626 0.0064861148 0.0041700000 36778317 955859216 1373700096 -0.1442092210 -0.0319470018 -0.0892138928 120 1311867174.4266788960 0.0657024533 0.0599814145 0.0658868626 0.0064595802 0.0041460000 36781245 955859216 1373700096 -0.1452575624 -0.0322382450 -0.0894662365 121 1311867174.4630160332 0.0655782595 0.0600276694 0.0658868626 0.0064658894 0.0033040000 36784173 955859216 1373700096 -0.1469990611 -0.0327009410 -0.0899987072 122 1311867174.4945669174 0.0661556348 0.0600778987 0.0661556348 0.0064426907 0.0041960000 36787045 955859216 1373700096 -0.1481672674 -0.0321563371 -0.0898331702 123 1311867174.5267519951 0.0660706535 0.0601266202 0.0661556348 0.0064331033 0.0041820000 36789973 955859216 1373700096 -0.1503269225 -0.0326461270 -0.0900815949 124 1311867174.5623500347 0.0657534227 0.0601719977 0.0661556348 0.0064290771 0.0032650000 36792957 955859216 1373700096 -0.1524495631 -0.0321079940 -0.0901231617 125 1311867174.5944879055 0.0659368262 0.0602181163 0.0661556348 0.0064151553 0.0041920000 36795773 955859216 1373700096 -0.1541206092 -0.0314426981 -0.0897471160 126 1311867174.6265459061 0.0663441643 0.0602667357 0.0663441643 0.0064082779 0.0041990000 36798645 955859216 1373700096 -0.1558559090 -0.0312932581 -0.0895221233 127 1311867174.6624910831 0.0659731776 0.0603116684 0.0663441643 0.0063855177 0.0041850000 36801629 955859216 1373700096 -0.1579602659 -0.0318832994 -0.0896594152 128 1311867174.6945910454 0.0663366318 0.0603587384 0.0663441643 0.0063737725 0.0032910000 36804501 955859216 1373700096 -0.1593790352 -0.0311391056 -0.0891604945 129 1311867174.7265629768 0.0672486797 0.0604121488 0.0672486797 0.0063679175 0.0042060000 36819605 955859216 1373700096 -0.1606266201 -0.0311312731 -0.0887929201 130 1311867174.7623760700 0.0670531392 0.0604632333 0.0672486797 0.0063638167 0.0042400000 36848245 955859216 1373700096 -0.1627765298 -0.0321973488 -0.0890988410 131 1311867174.7944738865 0.0672376603 0.0605149465 0.0672486797 0.0063449703 0.0032940000 36851005 955859216 1373700096 -0.1644275934 -0.0319419913 -0.0890703648 132 1311867174.8273398876 0.0677918792 0.0605700748 0.0677918792 0.0063262206 0.0042130000 36853933 955859216 1373700096 -0.1654907316 -0.0322881006 -0.0892868862 133 1311867174.8624229431 0.0672626495 0.0606203949 0.0677918792 0.0063059169 0.0042300000 36856917 955859216 1373700096 -0.1675908864 -0.0325732753 -0.0900300667 134 1311867174.8944199085 0.0678068101 0.0606740249 0.0678068101 0.0062899144 0.0032010000 36859733 955859216 1373700096 -0.1680893898 -0.0317292698 -0.0909596384 135 1311867174.9270179272 0.0677024722 0.0607260874 0.0678068101 0.0062770093 0.0052500000 36862661 955859216 1373700096 -0.1699839681 -0.0312768444 -0.0914042220 136 1311867174.9626429081 0.0679304674 0.0607790608 0.0679304674 0.0062550010 0.0049230000 36865645 955859216 1373700096 -0.1719683409 -0.0315475427 -0.0920863226 137 1311867174.9943349361 0.0670984238 0.0608251875 0.0679304674 0.0062544837 0.0036810000 36868461 955859216 1373700096 -0.1745346338 -0.0311277118 -0.0929688215 138 1311867175.0265510082 0.0677414984 0.0608753057 0.0679304674 0.0062628810 0.0037060000 36871389 955859216 1373700096 -0.1759977788 -0.0294189528 -0.0929592773 139 1311867175.0633120537 0.0677185059 0.0609245374 0.0679304674 0.0062447043 0.0032090000 36874373 955859216 1373700096 -0.1779565364 -0.0295711420 -0.0931494832 140 1311867175.0947189331 0.0608990677 0.0609243555 0.0679304674 0.0062432002 0.0049870000 36877245 955859216 1373700096 -0.1883691698 -0.0271241684 -0.0940100551 141 1311867175.1265308857 0.0612057149 0.0609263509 0.0679304674 0.0062301150 0.0037620000 36880117 955859216 1373700096 -0.1895911694 -0.0276335627 -0.0934902877 142 1311867175.1625180244 0.0615562983 0.0609307872 0.0679304674 0.0062314704 0.0032070000 36883101 955859216 1373700096 -0.1903905123 -0.0275404770 -0.0934006572 143 1311867175.1946399212 0.0613661632 0.0609338318 0.0679304674 0.0062122794 0.0048090000 36885917 955859216 1373700096 -0.1919628680 -0.0274270065 -0.0932054594 144 1311867175.2270050049 0.0620570295 0.0609416318 0.0679304674 0.0062916932 0.0044660000 36888845 955859216 1373700096 -0.1925957352 -0.0265808627 -0.0926870629 145 1311867175.2624669075 0.0627649650 0.0609542065 0.0679304674 0.0063064581 0.0048330000 36891773 955859216 1373700096 -0.1931317449 -0.0259649903 -0.0923971683 146 1311867175.2944509983 0.0627651662 0.0609666103 0.0679304674 0.0062868048 0.0032410000 36894645 955859216 1373700096 -0.1943051815 -0.0258416105 -0.0922114849 147 1311867175.3267059326 0.0645492226 0.0609909818 0.0679304674 0.0062684257 0.0027310000 36897573 955859216 1373700096 -0.1940466166 -0.0243774876 -0.0913258418 148 1311867175.3625650406 0.0655597672 0.0610218520 0.0679304674 0.0062604303 0.0044140000 36900501 955859216 1373700096 -0.1956573427 -0.0240386724 -0.0907011405 149 1311867175.3945989609 0.0656346381 0.0610528103 0.0679304674 0.0062466082 0.0044070000 36903373 955859216 1373700096 -0.1979877800 -0.0240332782 -0.0905000865 150 1311867175.4266059399 0.0661395639 0.0610867220 0.0679304674 0.0062299959 0.0038620000 36906245 955859216 1373700096 -0.2001349777 -0.0228196178 -0.0902317017 151 1311867175.4625999928 0.0665823221 0.0611231167 0.0679304674 0.0062155847 0.0032870000 36909285 955859216 1373700096 -0.2031418979 -0.0226052385 -0.0898951814 152 1311867175.4945731163 0.0667542815 0.0611601638 0.0679304674 0.0061988409 0.0044650000 36912157 955859216 1373700096 -0.2062456757 -0.0225922987 -0.0897447765 153 1311867175.5264270306 0.0671921596 0.0611995886 0.0679304674 0.0061888490 0.0044310000 36914973 955859216 1373700096 -0.2091486752 -0.0220877361 -0.0896608904 154 1311867175.5625700951 0.0675388649 0.0612407527 0.0679304674 0.0061975791 0.0034830000 36918013 955859216 1373700096 -0.2115152627 -0.0206239335 -0.0894494280 155 1311867175.5946640968 0.0681410879 0.0612852710 0.0681410879 0.0062226186 0.0044490000 36920829 955859216 1373700096 -0.2141825706 -0.0195330065 -0.0893107429 156 1311867175.6264801025 0.0670114085 0.0613219770 0.0681410879 0.0062366917 0.0050200000 36923701 955859216 1373700096 -0.2180065215 -0.0194750745 -0.0892654210 157 1311867175.6624929905 0.0686321780 0.0613685388 0.0686321780 0.0062847850 0.0034490000 36926685 955859216 1373700096 -0.2190665603 -0.0190342013 -0.0888234600 158 1311867175.6947000027 0.0695995316 0.0614206337 0.0695995316 0.0063044076 0.0050450000 36929557 955859216 1373700096 -0.2206847072 -0.0196174644 -0.0888760686 159 1311867175.7273120880 0.0700707883 0.0614750372 0.0700707883 0.0062974916 0.0033110000 36932485 955859216 1373700096 -0.2228512764 -0.0200742297 -0.0887159631 160 1311867175.7624969482 0.0707732141 0.0615331508 0.0707732141 0.0062843685 0.0049180000 36935469 955859216 1373700096 -0.2246175706 -0.0190470833 -0.0887684450 161 1311867175.7948620319 0.0712324679 0.0615933950 0.0712324679 0.0062972384 0.0038620000 36938285 955859216 1373700096 -0.2269920260 -0.0193210710 -0.0889099389 162 1311867175.8287971020 0.0707592592 0.0616499744 0.0712324679 0.0062826741 0.0033400000 36941269 955859216 1373700096 -0.2303133309 -0.0196049735 -0.0893246084 163 1311867175.8625519276 0.0719166398 0.0617129601 0.0719166398 0.0062905707 0.0050170000 36944197 955859216 1373700096 -0.2324113399 -0.0193079859 -0.0894230083 164 1311867175.8946080208 0.0726383254 0.0617795782 0.0726383254 0.0062782201 0.0041950000 36947013 955859216 1373700096 -0.2347306907 -0.0195721854 -0.0899107158 165 1311867175.9282429218 0.0725700408 0.0618449749 0.0726383254 0.0062799466 0.0045440000 36949941 955859216 1373700096 -0.2377464026 -0.0201205686 -0.0906132981 166 1311867175.9629371166 0.0729732811 0.0619120129 0.0729732811 0.0062613216 0.0035740000 36952869 955859216 1373700096 -0.2401299328 -0.0194732342 -0.0908021629 167 1311867175.9983000755 0.0731673688 0.0619794103 0.0731673688 0.0062604649 0.0044760000 36955797 955859216 1373700096 -0.2426703721 -0.0189597737 -0.0908241868 168 1311867176.0268509388 0.0732970238 0.0620467770 0.0732970238 0.0062432193 0.0035960000 36958557 955859216 1373700096 -0.2448574901 -0.0203606598 -0.0913133994 169 1311867176.0627059937 0.0722516328 0.0621071608 0.0732970238 0.0062805169 0.0045130000 36961541 955859216 1373700096 -0.2479698956 -0.0209375452 -0.0920389146 170 1311867176.0946600437 0.0726846680 0.0621693814 0.0732970238 0.0063187735 0.0045730000 36964357 955859216 1373700096 -0.2493611425 -0.0205520652 -0.0924066678 171 1311867176.1268119812 0.0729974955 0.0622327037 0.0732970238 0.0063060162 0.0036210000 36967285 955859216 1373700096 -0.2510923445 -0.0205851570 -0.0930327997 172 1311867176.1625900269 0.0726849735 0.0622934727 0.0732970238 0.0063900846 0.0045480000 36970269 955859216 1373700096 -0.2529695928 -0.0202636197 -0.0937262103 173 1311867176.1946918964 0.0726511404 0.0623533436 0.0732970238 0.0064441293 0.0045650000 36973141 955859216 1373700096 -0.2543476224 -0.0186575223 -0.0943807885 174 1311867176.2265360355 0.0719367489 0.0624084207 0.0732970238 0.0064288603 0.0042130000 36976013 955859216 1373700096 -0.2567545176 -0.0176277105 -0.0949570760 175 1311867176.2625019550 0.0713060796 0.0624592644 0.0732970238 0.0064198245 0.0031430000 36978997 955859216 1373700096 -0.2592671216 -0.0172562841 -0.0959260762 176 1311867176.2946109772 0.0705607608 0.0625052957 0.0732970238 0.0064151383 0.0046120000 36981813 955859216 1373700096 -0.2620231211 -0.0160622448 -0.0964685678 177 1311867176.3266019821 0.0715599209 0.0625564517 0.0732970238 0.0064034555 0.0046100000 36984685 955859216 1373700096 -0.2628609538 -0.0146498810 -0.0969485417 178 1311867176.3624560833 0.0715567619 0.0626070153 0.0732970238 0.0063862547 0.0045930000 36987725 955859216 1373700096 -0.2647190094 -0.0150933219 -0.0978454128 179 1311867176.3952438831 0.0720876679 0.0626599798 0.0732970238 0.0063697099 0.0044350000 36990541 955859216 1373700096 -0.2655009031 -0.0139323371 -0.0985162184 180 1311867176.4268360138 0.0730601773 0.0627177587 0.0732970238 0.0063544637 0.0036100000 36993413 955859216 1373700096 -0.2656649351 -0.0126548856 -0.0991654322 181 1311867176.4629659653 0.0730029941 0.0627745832 0.0732970238 0.0064305979 0.0045630000 36996397 955859216 1373700096 -0.2674664557 -0.0121683432 -0.1000496224 182 1311867176.4945809841 0.0724586099 0.0628277921 0.0732970238 0.0064307863 0.0036090000 36999213 955859216 1373700096 -0.2698048055 -0.0118965283 -0.1011425108 183 1311867176.5266211033 0.0734009296 0.0628855688 0.0734009296 0.0064774284 0.0046310000 37002141 955859216 1373700096 -0.2709829807 -0.0107493233 -0.1018784344 184 1311867176.5636389256 0.0733635947 0.0629425146 0.0734009296 0.0064753458 0.0036280000 37005181 955859216 1373700096 -0.2729910612 -0.0110840695 -0.1028392613 185 1311867176.5946090221 0.0730255023 0.0629970173 0.0734009296 0.0064628129 0.0046260000 37007997 955859216 1373700096 -0.2751804590 -0.0113543309 -0.1040701196 186 1311867176.6283841133 0.0732261911 0.0630520128 0.0734009296 0.0064556204 0.0046330000 37010925 955859216 1373700096 -0.2770451903 -0.0105547048 -0.1048937365 187 1311867176.6625781059 0.0734622627 0.0631076826 0.0734622627 0.0064435823 0.0036640000 37013853 955859216 1373700096 -0.2794649601 -0.0097568920 -0.1057029516 188 1311867176.6945180893 0.0735214353 0.0631630749 0.0735214353 0.0064282828 0.0046240000 37016669 955859216 1373700096 -0.2815774083 -0.0092669725 -0.1065187678 189 1311867176.7265889645 0.0731737614 0.0632160415 0.0735214353 0.0064118956 0.0036860000 37019597 955859216 1373700096 -0.2846079767 -0.0087929834 -0.1072603390 190 1311867176.7632329464 0.0738729537 0.0632721305 0.0738729537 0.0063988469 0.0046850000 37022581 955859216 1373700096 -0.2866390347 -0.0088974144 -0.1077397391 191 1311867176.7947680950 0.0743081421 0.0633299107 0.0743081421 0.0063934577 0.0036770000 37025397 955859216 1373700096 -0.2884491682 -0.0086521721 -0.1082892269 192 1311867176.8266770840 0.0743392110 0.0633872508 0.0743392110 0.0063790745 0.0046720000 37028325 955859216 1373700096 -0.2908448279 -0.0087553402 -0.1089227349 193 1311867176.8627309799 0.0747120082 0.0634459283 0.0747120082 0.0063669170 0.0046840000 37031309 955859216 1373700096 -0.2929396927 -0.0082330061 -0.1092410609 194 1311867176.8949549198 0.0746300966 0.0635035787 0.0747120082 0.0063535183 0.0045950000 37034181 955859216 1373700096 -0.2955501080 -0.0079574278 -0.1096867695 195 1311867176.9268178940 0.0745070726 0.0635600068 0.0747120082 0.0063544054 0.0032000000 37037053 955859216 1373700096 -0.2979951799 -0.0081787454 -0.1101929545 196 1311867176.9650609493 0.0752905756 0.0636198567 0.0752905756 0.0063651779 0.0047400000 37040037 955859216 1373700096 -0.2997386754 -0.0071744849 -0.1104264781 197 1311867176.9947481155 0.0758473873 0.0636819253 0.0758473873 0.0063531036 0.0043780000 37042853 955859216 1373700096 -0.3012621999 -0.0067990697 -0.1108402163 198 1311867177.0267279148 0.0760699213 0.0637444910 0.0760699213 0.0063417610 0.0032270000 37045725 955859216 1373700096 -0.3034835458 -0.0075842016 -0.1111817285 199 1311867177.0626339912 0.0763433129 0.0638078016 0.0763433129 0.0063302436 0.0047540000 37048709 955859216 1373700096 -0.3056973815 -0.0069292248 -0.1114099696 200 1311867177.0946850777 0.0766084045 0.0638718047 0.0766084045 0.0063185248 0.0047690000 37051581 955859216 1373700096 -0.3070688546 -0.0066385358 -0.1119635031 201 1311867177.1266150475 0.0769126862 0.0639366847 0.0769126862 0.0063037903 0.0036800000 37054453 955859216 1373700096 -0.3091010451 -0.0071255155 -0.1122726649 202 1311867177.1627299786 0.0778056830 0.0640053431 0.0778056830 0.0062886990 0.0048150000 37057437 955859216 1373700096 -0.3106860518 -0.0066027800 -0.1125664786 203 1311867177.1946458817 0.0774201900 0.0640714261 0.0778056830 0.0062777135 0.0048320000 37060309 955859216 1373700096 -0.3129961193 -0.0058533787 -0.1129805446 204 1311867177.2264730930 0.0783732757 0.0641415332 0.0783732757 0.0062624244 0.0035580000 37063181 955859216 1373700096 -0.3145605624 -0.0059473789 -0.1133911610 205 1311867177.2638640404 0.0784263909 0.0642112154 0.0784263909 0.0062474504 0.0048010000 37066221 955859216 1373700096 -0.3173665106 -0.0054181213 -0.1137728617 206 1311867177.2946178913 0.0782978833 0.0642795973 0.0784263909 0.0062530191 0.0037720000 37069037 955859216 1373700096 -0.3193815947 -0.0056612575 -0.1144021079 207 1311867177.3276090622 0.0777939186 0.0643448839 0.0784263909 0.0062380206 0.0047690000 37071965 955859216 1373700096 -0.3221574128 -0.0056055188 -0.1149553880 208 1311867177.3627710342 0.0788550079 0.0644146441 0.0788550079 0.0062271561 0.0044480000 37074893 955859216 1373700096 -0.3233802617 -0.0045987125 -0.1152382791 209 1311867177.3946089745 0.0786868259 0.0644829320 0.0788550079 0.0062288831 0.0053970000 37077765 955859216 1373700096 -0.3258081973 -0.0048857396 -0.1156968996 210 1311867177.4312860966 0.0791966468 0.0645529973 0.0791966468 0.0062201208 0.0035660000 37080805 955859216 1373700096 -0.3278534710 -0.0042977240 -0.1159335524 211 1311867177.4626040459 0.0791461170 0.0646221590 0.0791966468 0.0062061987 0.0041450000 37083677 955859216 1373700096 -0.3300608099 -0.0036548381 -0.1164015308 212 1311867177.4946429729 0.0790977404 0.0646904401 0.0791966468 0.0061933633 0.0051550000 37086549 955859216 1373700096 -0.3319709599 -0.0032314733 -0.1168827787 213 1311867177.5276319981 0.0794034228 0.0647595151 0.0794034228 0.0061813135 0.0046480000 37089421 955859216 1373700096 -0.3334030211 -0.0024389122 -0.1174508259 214 1311867177.5626399517 0.0805952996 0.0648335141 0.0805952996 0.0061743699 0.0037990000 37092349 955859216 1373700096 -0.3348590434 -0.0021200695 -0.1176201627 215 1311867177.5947310925 0.0765844360 0.0648881696 0.0805952996 0.0061656280 0.0036280000 37095221 955859216 1373700096 -0.3406181037 -0.0020850338 -0.1190789491 216 1311867177.6311450005 0.0761706606 0.0649404033 0.0805952996 0.0061521937 0.0036120000 37098261 955859216 1373700096 -0.3432743251 -0.0017950214 -0.1196938083 217 1311867177.6624829769 0.0763876662 0.0649931557 0.0805952996 0.0061397423 0.0035990000 37101133 955859216 1373700096 -0.3443123698 -0.0009332446 -0.1203416437 218 1311867177.6945610046 0.0761340037 0.0650442605 0.0805952996 0.0061503550 0.0036230000 37104005 955859216 1373700096 -0.3462693989 -0.0009468128 -0.1209335923 219 1311867177.7305839062 0.0758306459 0.0650935134 0.0805952996 0.0061379970 0.0036210000 37106933 955859216 1373700096 -0.3480593860 0.0004644586 -0.1214902997 220 1311867177.7625379562 0.0765010118 0.0651453657 0.0805952996 0.0061317080 0.0035970000 37109805 955859216 1373700096 -0.3482667804 0.0006400331 -0.1220310330 221 1311867177.7945590019 0.0755932853 0.0651926413 0.0805952996 0.0061204716 0.0036070000 37112677 955859216 1373700096 -0.3500263393 0.0009326531 -0.1229479015 222 1311867177.8309149742 0.0760213435 0.0652414192 0.0805952996 0.0061098928 0.0054420000 37115661 955859216 1373700096 -0.3510550559 0.0011703643 -0.1237838641 223 1311867177.8625319004 0.0760601312 0.0652899337 0.0805952996 0.0060967781 0.0050090000 37118533 955859216 1373700096 -0.3518699110 0.0012543593 -0.1245494261 224 1311867177.8946919441 0.0762395710 0.0653388160 0.0805952996 0.0060852550 0.0037540000 37121349 955859216 1373700096 -0.3525457680 0.0018076428 -0.1250576079 225 1311867177.9317860603 0.0765567720 0.0653886735 0.0805952996 0.0060720395 0.0054120000 37124445 955859216 1373700096 -0.3535176814 0.0024079459 -0.1259340644 226 1311867177.9627909660 0.0765054375 0.0654378628 0.0805952996 0.0060717880 0.0035830000 37127261 955859216 1373700096 -0.3553561568 0.0025971481 -0.1268769652 227 1311867177.9947769642 0.0765680969 0.0654868946 0.0805952996 0.0060641621 0.0054310000 37130021 955859216 1373700096 -0.3563979566 0.0037816288 -0.1276215017 228 1311867178.0306100845 0.0771502331 0.0655380496 0.0805952996 0.0060560585 0.0035920000 37133005 955859216 1373700096 -0.3573851883 0.0037528262 -0.1286035478 229 1311867178.0634479523 0.0777375996 0.0655913228 0.0805952996 0.0060460773 0.0030240000 37135877 955859216 1373700096 -0.3583092093 0.0034110264 -0.1293054521 230 1311867178.0951139927 0.0780545920 0.0656455109 0.0805952996 0.0060330958 0.0030160000 37138749 955859216 1373700096 -0.3591840267 0.0046819584 -0.1298408657 231 1311867178.1307909489 0.0781675056 0.0656997187 0.0805952996 0.0060236446 0.0030140000 37141733 955859216 1373700096 -0.3614515960 0.0043001720 -0.1305121332 232 1311867178.1627469063 0.0780651942 0.0657530181 0.0805952996 0.0060395067 0.0054890000 37144605 955859216 1373700096 -0.3635616302 0.0041376334 -0.1312792301 233 1311867178.1950459480 0.0786638781 0.0658084295 0.0805952996 0.0060359876 0.0054430000 37147421 955859216 1373700096 -0.3649501801 0.0054093259 -0.1315508783 234 1311867178.2307190895 0.0791613162 0.0658654932 0.0805952996 0.0060313803 0.0037380000 37150405 955859216 1373700096 -0.3671094775 0.0042685024 -0.1323017031 235 1311867178.2628939152 0.0793159157 0.0659227290 0.0805952996 0.0060205742 0.0032660000 37153333 955859216 1373700096 -0.3689622283 0.0039891317 -0.1328073889 236 1311867178.2954900265 0.0799977258 0.0659823688 0.0805952996 0.0060124776 0.0030600000 37156205 955859216 1373700096 -0.3699812293 0.0048805405 -0.1330320537 237 1311867178.3306670189 0.0808851048 0.0660452496 0.0808851048 0.0060081424 0.0030540000 37159133 955859216 1373700096 -0.3716598451 0.0037355984 -0.1334067285 238 1311867178.3627231121 0.0808881745 0.0661076148 0.0808881745 0.0060008175 0.0051230000 37162061 955859216 1373700096 -0.3739645779 0.0041265492 -0.1336347610 239 1311867178.3949439526 0.0810620487 0.0661701856 0.0810620487 0.0059903648 0.0050560000 37164877 955859216 1373700096 -0.3758809268 0.0045466768 -0.1339086294 240 1311867178.4306581020 0.0811376721 0.0662325502 0.0811376721 0.0059881417 0.0035490000 37167861 955859216 1373700096 -0.3782248497 0.0050906157 -0.1339049637 241 1311867178.4628739357 0.0814897418 0.0662958580 0.0814897418 0.0059762455 0.0050400000 37170733 955859216 1373700096 -0.3799657524 0.0058246772 -0.1338389814 242 1311867178.4946439266 0.0811326876 0.0663571672 0.0814897418 0.0059678259 0.0039960000 37173605 955859216 1373700096 -0.3819835782 0.0053349528 -0.1340644211 243 1311867178.5306270123 0.0819375291 0.0664212840 0.0819375291 0.0059703149 0.0050270000 37176589 955859216 1373700096 -0.3834551573 0.0056357463 -0.1339261085 244 1311867178.5626420975 0.0825758204 0.0664874911 0.0825758204 0.0059587228 0.0039530000 37179517 955859216 1373700096 -0.3848259449 0.0058499686 -0.1339791864 245 1311867178.5947000980 0.0828663185 0.0665543434 0.0828663185 0.0059565222 0.0034130000 37182389 955859216 1373700096 -0.3862455189 0.0053738728 -0.1340948641 246 1311867178.6306900978 0.0831341371 0.0666217410 0.0831341371 0.0059538668 0.0030810000 37185317 955859216 1373700096 -0.3880617321 0.0057209367 -0.1340760589 247 1311867178.6626410484 0.0831626132 0.0666887081 0.0831626132 0.0059650021 0.0030910000 37188245 955859216 1373700096 -0.3891727328 0.0069168205 -0.1343635023 248 1311867178.6946120262 0.0825374722 0.0667526144 0.0831626132 0.0059568523 0.0050630000 37191061 955859216 1373700096 -0.3914441764 0.0063923043 -0.1348062307 249 1311867178.7307450771 0.0817465186 0.0668128308 0.0831626132 0.0059549431 0.0050650000 37194045 955859216 1373700096 -0.3935346305 0.0073169908 -0.1351253241 250 1311867178.7632350922 0.0818249807 0.0668728794 0.0831626132 0.0059479094 0.0045390000 37196973 955859216 1373700096 -0.3946332335 0.0072993743 -0.1351974607 251 1311867178.8006799221 0.0818342641 0.0669324866 0.0831626132 0.0059446259 0.0034290000 37199957 955859216 1373700096 -0.3956899941 0.0056077000 -0.1356818825 252 1311867178.8309500217 0.0819957554 0.0669922614 0.0831626132 0.0059388517 0.0051420000 37202773 955859216 1373700096 -0.3959471583 0.0072543388 -0.1359544247 253 1311867178.8627939224 0.0818483457 0.0670509811 0.0831626132 0.0059360952 0.0053590000 37205701 955859216 1373700096 -0.3968359232 0.0077846553 -0.1361666024 254 1311867178.8952279091 0.0814353451 0.0671076125 0.0831626132 0.0059372272 0.0035420000 37208573 955859216 1373700096 -0.3979525864 0.0057818908 -0.1368854195 255 1311867178.9306209087 0.0813581645 0.0671634970 0.0831626132 0.0059497910 0.0051550000 37211501 955859216 1373700096 -0.3985640109 0.0073698852 -0.1374999732 256 1311867178.9627609253 0.0804662779 0.0672154610 0.0831626132 0.0059465094 0.0051470000 37214429 955859216 1373700096 -0.4000754356 0.0085832598 -0.1381627321 257 1311867178.9946830273 0.0787430033 0.0672603152 0.0831626132 0.0059550198 0.0034610000 37241877 955859216 1373700096 -0.4028516710 0.0082178283 -0.1391995847 258 1311867179.0309159756 0.0787105784 0.0673046961 0.0831626132 0.0059787558 0.0051600000 37296061 955859216 1373700096 -0.4041459560 0.0082043866 -0.1400365978 259 1311867179.0628120899 0.0795779005 0.0673520830 0.0831626132 0.0059770754 0.0036620000 37298989 955859216 1373700096 -0.4045234621 0.0069769495 -0.1408253461 260 1311867179.0968201160 0.0793226957 0.0673981238 0.0831626132 0.0060604947 0.0031870000 37301861 955859216 1373700096 -0.4063788950 0.0049111559 -0.1417040527 261 1311867179.1310369968 0.0791917369 0.0674433101 0.0831626132 0.0060540759 0.0031450000 37304733 955859216 1373700096 -0.4070529640 0.0068835826 -0.1427000165 262 1311867179.1627540588 0.0793545991 0.0674887730 0.0831626132 0.0060706281 0.0051960000 37307605 955859216 1373700096 -0.4084638357 0.0067568235 -0.1440097541 263 1311867179.1957008839 0.0775578320 0.0675270584 0.0831626132 0.0060642937 0.0052130000 37310477 955859216 1373700096 -0.4116940498 0.0062191901 -0.1456578225 264 1311867179.2307469845 0.0771931037 0.0675636722 0.0831626132 0.0061101833 0.0040340000 37313405 955859216 1373700096 -0.4138569832 0.0083679473 -0.1467316151 265 1311867179.2634611130 0.0780101866 0.0676030930 0.0831626132 0.0061152487 0.0035280000 37316389 955859216 1373700096 -0.4146295488 0.0067635742 -0.1477449238 266 1311867179.2959330082 0.0780144110 0.0676422333 0.0831626132 0.0061102103 0.0051850000 37319205 955859216 1373700096 -0.4160579443 0.0060111247 -0.1486738473 267 1311867179.3307149410 0.0792501345 0.0676857086 0.0831626132 0.0061021177 0.0051900000 37322133 955859216 1373700096 -0.4161592424 0.0069285613 -0.1491064727 268 1311867179.3629300594 0.0795264840 0.0677298906 0.0831626132 0.0060909336 0.0034940000 37325117 955859216 1373700096 -0.4168688059 0.0075017270 -0.1495494545 269 1311867179.3948490620 0.0791828185 0.0677724665 0.0831626132 0.0060847888 0.0031740000 37327877 955859216 1373700096 -0.4183829725 0.0069288849 -0.1500632167 270 1311867179.4308040142 0.0797148868 0.0678166977 0.0831626132 0.0060894106 0.0051900000 37330917 955859216 1373700096 -0.4191869795 0.0074318293 -0.1503734291 271 1311867179.4637460709 0.0810512453 0.0678655337 0.0831626132 0.0060936127 0.0052200000 37333845 955859216 1373700096 -0.4191578925 0.0078277048 -0.1501291245 272 1311867179.4949469566 0.0818998143 0.0679171303 0.0831626132 0.0061046610 0.0035110000 37336661 955859216 1373700096 -0.4197687209 0.0071001421 -0.1501961797 273 1311867179.5307800770 0.0828271210 0.0679717457 0.0831626132 0.0061033881 0.0052340000 37339645 955859216 1373700096 -0.4203154445 0.0097707668 -0.1502742916 274 1311867179.5627610683 0.0832727775 0.0680275888 0.0832727775 0.0061218121 0.0040540000 37342517 955859216 1373700096 -0.4211742282 0.0102808010 -0.1503523290 275 1311867179.5946741104 0.0830089077 0.0680820664 0.0832727775 0.0061141438 0.0052150000 37345389 955859216 1373700096 -0.4227948785 0.0107878959 -0.1502176821 276 1311867179.6306900978 0.0837857202 0.0681389637 0.0837857202 0.0061268683 0.0050350000 37348317 955859216 1373700096 -0.4231316447 0.0116217872 -0.1502248198 277 1311867179.6625750065 0.0847046450 0.0681987676 0.0847046450 0.0061266744 0.0035660000 37351245 955859216 1373700096 -0.4233043194 0.0107258828 -0.1501156688 278 1311867179.6946051121 0.0850846022 0.0682595080 0.0850846022 0.0061344679 0.0052600000 37354061 955859216 1373700096 -0.4238343239 0.0118863750 -0.1500982344 279 1311867179.7309470177 0.0853864849 0.0683208950 0.0853864849 0.0061267095 0.0049790000 37357101 955859216 1373700096 -0.4243605137 0.0126867304 -0.1498690397 280 1311867179.7627270222 0.0851006433 0.0683808227 0.0853864849 0.0061490279 0.0033040000 37359973 955859216 1373700096 -0.4253004491 0.0118184611 -0.1500806212 281 1311867179.7948911190 0.0858506262 0.0684429928 0.0858506262 0.0061648556 0.0030270000 37362789 955859216 1373700096 -0.4247648120 0.0130823273 -0.1500887126 282 1311867179.8307530880 0.0867853686 0.0685080367 0.0867853686 0.0061565182 0.0032320000 37365829 955859216 1373700096 -0.4244500697 0.0134863341 -0.1498899460 283 1311867179.8627979755 0.0870970860 0.0685737224 0.0870970860 0.0061499815 0.0032340000 37368701 955859216 1373700096 -0.4253523648 0.0119271129 -0.1497600675 284 1311867179.8948040009 0.0874696001 0.0686402571 0.0874696001 0.0061438094 0.0031760000 37371573 955859216 1373700096 -0.4257723093 0.0117869852 -0.1495655328 285 1311867179.9309051037 0.0879767612 0.0687081045 0.0879767612 0.0061632010 0.0058110000 37374557 955859216 1373700096 -0.4258458018 0.0144885164 -0.1492433995 286 1311867179.9635379314 0.0878877416 0.0687751662 0.0879767612 0.0061613438 0.0058560000 37377485 955859216 1373700096 -0.4267607331 0.0138736730 -0.1490033418 287 1311867179.9958879948 0.0872527137 0.0688395479 0.0879767612 0.0061549026 0.0044540000 37380301 955859216 1373700096 -0.4281461239 0.0139281098 -0.1487250030 288 1311867180.0309770107 0.0877030566 0.0689050462 0.0879767612 0.0061520001 0.0034470000 37383285 955859216 1373700096 -0.4279439449 0.0158542059 -0.1483046561 289 1311867180.0626471043 0.0871468410 0.0689681666 0.0879767612 0.0061423858 0.0053860000 37386157 955859216 1373700096 -0.4294180274 0.0150185404 -0.1478799582 290 1311867180.0947730541 0.0848410949 0.0690229008 0.0879767612 0.0061329419 0.0036050000 37388973 955859216 1373700096 -0.4314062297 0.0162820611 -0.1486819685 291 1311867180.1307730675 0.0843505859 0.0690755733 0.0879767612 0.0061323173 0.0061400000 37391957 955859216 1373700096 -0.4316860437 0.0155816702 -0.1485353410 292 1311867180.1636900902 0.0842628852 0.0691275846 0.0879767612 0.0061494697 0.0038740000 37394941 955859216 1373700096 -0.4304294884 0.0158990715 -0.1489328146 293 1311867180.1949090958 0.0835969597 0.0691769681 0.0879767612 0.0061396346 0.0032330000 37397701 955859216 1373700096 -0.4303031266 0.0160770975 -0.1492129862 294 1311867180.2308139801 0.0830089673 0.0692240158 0.0879767612 0.0061367290 0.0032760000 37400629 955859216 1373700096 -0.4293723404 0.0164455231 -0.1502344608 295 1311867180.2637619972 0.0821131095 0.0692677076 0.0879767612 0.0061629679 0.0032470000 37403557 955859216 1373700096 -0.4295280874 0.0165197495 -0.1508921534 296 1311867180.2947549820 0.0811809897 0.0693079552 0.0879767612 0.0061526260 0.0032460000 37406373 955859216 1373700096 -0.4298949242 0.0164832491 -0.1515356302 297 1311867180.3308670521 0.0804218724 0.0693453758 0.0879767612 0.0061445419 0.0032610000 37409357 955859216 1373700096 -0.4299748838 0.0165136140 -0.1519280523 298 1311867180.3658289909 0.0795881376 0.0693797475 0.0879767612 0.0061440469 0.0032160000 37412285 955859216 1373700096 -0.4298137128 0.0171413887 -0.1523680687 299 1311867180.3964109421 0.0790394023 0.0694120540 0.0879767612 0.0061355202 0.0058730000 37415157 955859216 1373700096 -0.4296733737 0.0178301483 -0.1524847597 300 1311867180.4309151173 0.0783363357 0.0694418016 0.0879767612 0.0061279425 0.0059310000 37418085 955859216 1373700096 -0.4294052720 0.0174609348 -0.1531352848 301 1311867180.4670670033 0.0780852586 0.0694705174 0.0879767612 0.0061218173 0.0038310000 37421069 955859216 1373700096 -0.4285778701 0.0178773962 -0.1534635276 302 1311867180.4947559834 0.0780093670 0.0694987917 0.0879767612 0.0061240169 0.0032220000 37423773 955859216 1373700096 -0.4281240106 0.0176520962 -0.1536371708 303 1311867180.5308880806 0.0777034536 0.0695258698 0.0879767612 0.0061148643 0.0030750000 37426813 955859216 1373700096 -0.4271930158 0.0179165974 -0.1536549330 304 1311867180.5629510880 0.0775754154 0.0695523486 0.0879767612 0.0061052728 0.0032470000 37429685 955859216 1373700096 -0.4262405634 0.0180205423 -0.1534904689 305 1311867180.5946910381 0.0774419829 0.0695782163 0.0879767612 0.0060963138 0.0059700000 37432557 955859216 1373700096 -0.4249719381 0.0184139982 -0.1534556746 306 1311867180.6308128834 0.0771953017 0.0696031087 0.0879767612 0.0060872476 0.0060150000 37435541 955859216 1373700096 -0.4240758121 0.0181507878 -0.1533154994 307 1311867180.6640911102 0.0767996088 0.0696265501 0.0879767612 0.0060954865 0.0038810000 37438413 955859216 1373700096 -0.4232585430 0.0184695274 -0.1530721486 308 1311867180.6957859993 0.0768656209 0.0696500535 0.0879767612 0.0060859259 0.0040910000 37441285 955859216 1373700096 -0.4223550856 0.0176095013 -0.1527025700 309 1311867180.7309739590 0.0767744854 0.0696731100 0.0879767612 0.0060817155 0.0055840000 37444269 955859216 1373700096 -0.4209100008 0.0183816366 -0.1526730806 310 1311867180.7650830746 0.0772590265 0.0696975807 0.0879767612 0.0060868727 0.0042970000 37447197 955859216 1373700096 -0.4204057753 0.0181806963 -0.1523168981 311 1311867180.7949280739 0.0771397576 0.0697215105 0.0879767612 0.0060774390 0.0036530000 37449957 955859216 1373700096 -0.4201304018 0.0182061139 -0.1520448774 312 1311867180.8309240341 0.0773868710 0.0697460789 0.0879767612 0.0060683415 0.0040540000 37452997 955859216 1373700096 -0.4191209078 0.0189349037 -0.1516376585 313 1311867180.8652698994 0.0772796273 0.0697701478 0.0879767612 0.0060676690 0.0056560000 37455925 955859216 1373700096 -0.4179693162 0.0179926883 -0.1516706944 314 1311867180.8966469765 0.0770139620 0.0697932173 0.0879767612 0.0060605146 0.0042840000 37458797 955859216 1373700096 -0.4168083072 0.0183434896 -0.1515969336 315 1311867180.9306049347 0.0771670863 0.0698166264 0.0879767612 0.0060776242 0.0060950000 37461725 955859216 1373700096 -0.4162303507 0.0184224136 -0.1514530182 316 1311867180.9631829262 0.0768188909 0.0698387854 0.0879767612 0.0060780746 0.0061020000 37464597 955859216 1373700096 -0.4155627489 0.0181952901 -0.1513991505 317 1311867180.9948179722 0.0773141980 0.0698623672 0.0879767612 0.0060694587 0.0061340000 37467413 955859216 1373700096 -0.4136998951 0.0187139586 -0.1509050429 318 1311867181.0308310986 0.0777972415 0.0698873196 0.0879767612 0.0060623166 0.0041830000 37470397 955859216 1373700096 -0.4120311439 0.0173988380 -0.1506377012 319 1311867181.0627830029 0.0777716562 0.0699120354 0.0879767612 0.0060611892 0.0033400000 37473325 955859216 1373700096 -0.4101659358 0.0171753410 -0.1504257917 320 1311867181.0948719978 0.0779172182 0.0699370516 0.0879767612 0.0060598886 0.0043550000 37476197 955859216 1373700096 -0.4073236287 0.0173085853 -0.1502773911 321 1311867181.1311910152 0.0777564198 0.0699614110 0.0879767612 0.0060522929 0.0034460000 37479181 955859216 1373700096 -0.4044686258 0.0177478567 -0.1502867490 322 1311867181.1629528999 0.0769327432 0.0699830611 0.0879767612 0.0060542107 0.0056230000 37482053 955859216 1373700096 -0.4034480155 0.0170894228 -0.1504818201 323 1311867181.1972830296 0.0765239745 0.0700033116 0.0879767612 0.0060453103 0.0056460000 37484981 955859216 1373700096 -0.4015972912 0.0166457556 -0.1504745781 324 1311867181.2342460155 0.0761884451 0.0700224015 0.0879767612 0.0060384789 0.0037300000 37488021 955859216 1373700096 -0.3997612000 0.0162626784 -0.1506663263 325 1311867181.2629361153 0.0763464272 0.0700418601 0.0879767612 0.0060295490 0.0056450000 37490781 955859216 1373700096 -0.3979130685 0.0163122136 -0.1503925622 326 1311867181.2948091030 0.0764030814 0.0700613730 0.0879767612 0.0060206849 0.0043500000 37493597 955859216 1373700096 -0.3960556984 0.0167283658 -0.1503389329 327 1311867181.3317139149 0.0763403550 0.0700805748 0.0879767612 0.0060169917 0.0056560000 37496637 955859216 1373700096 -0.3942036331 0.0166739579 -0.1503986865 328 1311867181.3626708984 0.0766782984 0.0701006898 0.0879767612 0.0060196753 0.0042120000 37499453 955859216 1373700096 -0.3923416436 0.0183385797 -0.1498819739 329 1311867181.3948218822 0.0766084567 0.0701204703 0.0879767612 0.0060121199 0.0033910000 37502325 955859216 1373700096 -0.3911212981 0.0171162821 -0.1498293132 330 1311867181.4308950901 0.0758048892 0.0701376958 0.0879767612 0.0060037224 0.0034240000 37505197 955859216 1373700096 -0.3900991976 0.0168008395 -0.1497320682 331 1311867181.4628310204 0.0759296790 0.0701551942 0.0879767612 0.0059995496 0.0056380000 37508069 955859216 1373700096 -0.3877927065 0.0160986129 -0.1492644548 332 1311867181.4963610172 0.0761572123 0.0701732726 0.0879767612 0.0060101284 0.0056930000 37510997 955859216 1373700096 -0.3844813406 0.0160911996 -0.1492693573 333 1311867181.5359110832 0.0756880492 0.0701898335 0.0879767612 0.0060052236 0.0038050000 37514037 955859216 1373700096 -0.3831378818 0.0156621039 -0.1489987522 334 1311867181.5671720505 0.0750839114 0.0702044864 0.0879767612 0.0060003744 0.0056790000 37516853 955859216 1373700096 -0.3818429708 0.0150707951 -0.1493066847 335 1311867181.5948610306 0.0751723647 0.0702193159 0.0879767612 0.0059967764 0.0040520000 37519557 955859216 1373700096 -0.3801547587 0.0160628837 -0.1493203342 336 1311867181.6313591003 0.0757149979 0.0702356721 0.0879767612 0.0059958071 0.0040530000 37522597 955859216 1373700096 -0.3780807257 0.0153776594 -0.1493996233 337 1311867181.6628570557 0.0751518831 0.0702502602 0.0879767612 0.0059908922 0.0032280000 37525469 955859216 1373700096 -0.3767764866 0.0139341615 -0.1498559862 338 1311867181.6949229240 0.0748477876 0.0702638624 0.0879767612 0.0059837545 0.0056230000 37528285 955859216 1373700096 -0.3756748140 0.0142832175 -0.1501122117 339 1311867181.7310829163 0.0752285644 0.0702785075 0.0879767612 0.0059888162 0.0056900000 37531269 955859216 1373700096 -0.3734987676 0.0134335468 -0.1504001766 340 1311867181.7634840012 0.0746443719 0.0702913483 0.0879767612 0.0059805207 0.0044110000 37534197 955859216 1373700096 -0.3724462688 0.0122111961 -0.1509055346 341 1311867181.7948980331 0.0742139891 0.0703028517 0.0879767612 0.0059799185 0.0033930000 37536957 955859216 1373700096 -0.3705837727 0.0124851782 -0.1510621309 342 1311867181.8308010101 0.0738899261 0.0703133402 0.0879767612 0.0059759093 0.0057520000 37539941 955859216 1373700096 -0.3688760102 0.0111577474 -0.1512012035 343 1311867181.8627979755 0.0739964023 0.0703240780 0.0879767612 0.0059696349 0.0049670000 37542869 955859216 1373700096 -0.3673171699 0.0104057742 -0.1513643116 344 1311867181.8949289322 0.0735303834 0.0703333986 0.0879767612 0.0059641171 0.0053580000 37545685 955859216 1373700096 -0.3653290272 0.0106787076 -0.1511616856 345 1311867181.9307990074 0.0727994889 0.0703405467 0.0879767612 0.0059642067 0.0037960000 37548725 955859216 1373700096 -0.3641675115 0.0101930676 -0.1512094289 346 1311867181.9629189968 0.0723094568 0.0703462372 0.0879767612 0.0059597627 0.0057570000 37551597 955859216 1373700096 -0.3625076115 0.0097920829 -0.1510521472 347 1311867181.9955599308 0.0717922002 0.0703504042 0.0879767612 0.0059785716 0.0042250000 37554469 955859216 1373700096 -0.3612003028 0.0089042112 -0.1503680199 348 1311867182.0320639610 0.0718664676 0.0703547607 0.0879767612 0.0059709222 0.0034560000 37557453 955859216 1373700096 -0.3588573635 0.0081910901 -0.1500185281 349 1311867182.0629000664 0.0718315914 0.0703589923 0.0879767612 0.0059645617 0.0057890000 37560325 955859216 1373700096 -0.3570922613 0.0081390319 -0.1496466994 350 1311867182.0948839188 0.0723763928 0.0703647564 0.0879767612 0.0059672650 0.0044510000 37563141 955859216 1373700096 -0.3551539481 0.0076655014 -0.1494144201 351 1311867182.1314840317 0.0725074559 0.0703708609 0.0879767612 0.0059595313 0.0058070000 37566181 955859216 1373700096 -0.3534317315 0.0074208695 -0.1488712877 352 1311867182.1629920006 0.0718977302 0.0703751986 0.0879767612 0.0059521848 0.0038720000 37569053 955859216 1373700096 -0.3520609438 0.0077013983 -0.1486501694 353 1311867182.1994500160 0.0714323297 0.0703781933 0.0879767612 0.0059478016 0.0057950000 37571981 955859216 1373700096 -0.3513188958 0.0072196475 -0.1481875181 354 1311867182.2307739258 0.0712795183 0.0703807394 0.0879767612 0.0059445630 0.0039400000 37574797 955859216 1373700096 -0.3500007391 0.0067207124 -0.1477769613 355 1311867182.2629120350 0.0711586326 0.0703829307 0.0879767612 0.0059408041 0.0047840000 37577725 955859216 1373700096 -0.3489556611 0.0066983439 -0.1472445577 356 1311867182.2973539829 0.0713419318 0.0703856245 0.0879767612 0.0059375155 0.0041070000 37580653 955859216 1373700096 -0.3472468853 0.0053515644 -0.1471346021 357 1311867182.3308460712 0.0710349306 0.0703874433 0.0879767612 0.0059539472 0.0036520000 37583525 955859216 1373700096 -0.3463668525 0.0051126075 -0.1465546787 358 1311867182.3629670143 0.0704619661 0.0703876514 0.0879767612 0.0059735958 0.0062840000 37586453 955859216 1373700096 -0.3456800580 0.0047135102 -0.1460866332 359 1311867182.3990368843 0.0703268200 0.0703874820 0.0879767612 0.0059722337 0.0043480000 37589381 955859216 1373700096 -0.3444221914 0.0037324631 -0.1456261426 360 1311867182.4308118820 0.0701712817 0.0703868814 0.0879767612 0.0059702809 0.0036420000 37592253 955859216 1373700096 -0.3435406089 0.0020937021 -0.1456114501 361 1311867182.4629440308 0.0691316947 0.0703834045 0.0879767612 0.0059676022 0.0034110000 37595181 955859216 1373700096 -0.3430037200 0.0018330502 -0.1456185281 362 1311867182.4969599247 0.0685597807 0.0703783668 0.0879767612 0.0059647558 0.0033960000 37598053 955859216 1373700096 -0.3424246013 0.0005504412 -0.1455260664 363 1311867182.5309500694 0.0679019690 0.0703715448 0.0879767612 0.0059581561 0.0063740000 37600981 955859216 1373700096 -0.3414809704 -0.0004951644 -0.1460288465 364 1311867182.5629699230 0.0670947880 0.0703625427 0.0879767612 0.0059551355 0.0056670000 37603853 955859216 1373700096 -0.3403585851 -0.0005937252 -0.1463414282 365 1311867182.6036369801 0.0634629056 0.0703436396 0.0879767612 0.0059515374 0.0037180000 37606949 955859216 1373700096 -0.3421206176 -0.0011472343 -0.1474034041 366 1311867182.6308450699 0.0624560080 0.0703220887 0.0879767612 0.0059677786 0.0033790000 37609653 955859216 1373700096 -0.3421060145 -0.0021426275 -0.1478729397 367 1311867182.6635921001 0.0620338134 0.0702995048 0.0879767612 0.0059604033 0.0058980000 37612581 955859216 1373700096 -0.3406828344 -0.0024519702 -0.1480484307 368 1311867182.6970019341 0.0612754337 0.0702749829 0.0879767612 0.0059596637 0.0049120000 37615453 955859216 1373700096 -0.3393025994 -0.0030750711 -0.1483474225 369 1311867182.7330639362 0.0607035682 0.0702490441 0.0879767612 0.0059548101 0.0036870000 37618437 955859216 1373700096 -0.3371057212 -0.0035541086 -0.1488386095 370 1311867182.7631130219 0.0606962442 0.0702232257 0.0879767612 0.0059491556 0.0034000000 37621141 955859216 1373700096 -0.3353238702 -0.0037517122 -0.1487548798 371 1311867182.7970550060 0.0599865615 0.0701956337 0.0879767612 0.0059412885 0.0064130000 37624125 955859216 1373700096 -0.3342890739 -0.0048541087 -0.1489337683 372 1311867182.8306989670 0.0595073290 0.0701669017 0.0879767612 0.0059346231 0.0056360000 37626997 955859216 1373700096 -0.3326445222 -0.0054304386 -0.1491973400 373 1311867182.8641169071 0.0582841448 0.0701350444 0.0879767612 0.0059314757 0.0037530000 37629869 955859216 1373700096 -0.3315242231 -0.0056412700 -0.1492394805 374 1311867182.8969969749 0.0585631914 0.0701041036 0.0879767612 0.0059237315 0.0047090000 37632797 955859216 1373700096 -0.3291789889 -0.0062304176 -0.1490376294 375 1311867182.9318990707 0.0590248033 0.0700745588 0.0879767612 0.0059166013 0.0037030000 37635725 955859216 1373700096 -0.3263184130 -0.0056936727 -0.1488970071 376 1311867182.9630720615 0.0592366159 0.0700457345 0.0879767612 0.0059089530 0.0064910000 37638597 955859216 1373700096 -0.3240101039 -0.0055992524 -0.1485958099 377 1311867182.9983949661 0.0590228327 0.0700164960 0.0879767612 0.0059176944 0.0042320000 37641525 955859216 1373700096 -0.3231047988 -0.0062589217 -0.1481985897 378 1311867183.0308830738 0.0587425008 0.0699866706 0.0879767612 0.0059101827 0.0055850000 37644397 955859216 1373700096 -0.3215073943 -0.0069293352 -0.1477847397 379 1311867183.0628600121 0.0591296405 0.0699580241 0.0879767612 0.0059032531 0.0037330000 37647325 955859216 1373700096 -0.3187294900 -0.0062275361 -0.1474209130 380 1311867183.1000499725 0.0584149137 0.0699276475 0.0879767612 0.0059269723 0.0059770000 37650253 955859216 1373700096 -0.3172780871 -0.0072188978 -0.1470967233 381 1311867183.1344780922 0.0581156425 0.0698966449 0.0879767612 0.0059221791 0.0037310000 37653237 955859216 1373700096 -0.3158197105 -0.0069517423 -0.1466996968 382 1311867183.1673240662 0.0582107976 0.0698660537 0.0879767612 0.0059165996 0.0059050000 37656165 955859216 1373700096 -0.3140159249 -0.0063028196 -0.1461648643 383 1311867183.2004919052 0.0578566417 0.0698346975 0.0879767612 0.0059111787 0.0045290000 37659037 955859216 1373700096 -0.3132857382 -0.0075460151 -0.1456110775 384 1311867183.2311279774 0.0581893325 0.0698043710 0.0879767612 0.0059038260 0.0059190000 37661853 955859216 1373700096 -0.3116261065 -0.0080308551 -0.1451759189 385 1311867183.2633349895 0.0584439635 0.0697748635 0.0879767612 0.0058976997 0.0041910000 37664781 955859216 1373700096 -0.3094965219 -0.0077894018 -0.1449006051 386 1311867183.2991099358 0.0581801124 0.0697448253 0.0879767612 0.0058922755 0.0059200000 37667709 955859216 1373700096 -0.3085959852 -0.0092771081 -0.1448829621 387 1311867183.3320920467 0.0581830628 0.0697149499 0.0879767612 0.0058932339 0.0045660000 37670637 955859216 1373700096 -0.3070577085 -0.0090432325 -0.1447476596 388 1311867183.3695240021 0.0578865409 0.0696844643 0.0879767612 0.0058857524 0.0044020000 37673677 955859216 1373700096 -0.3057928383 -0.0094003119 -0.1444289684 389 1311867183.3986210823 0.0576500632 0.0696535275 0.0879767612 0.0058796019 0.0060070000 37676437 955859216 1373700096 -0.3046308458 -0.0107022459 -0.1447578371 390 1311867183.4311549664 0.0573725291 0.0696220378 0.0879767612 0.0058880716 0.0045820000 37679309 955859216 1373700096 -0.3032564223 -0.0104215788 -0.1445591748 391 1311867183.4667448997 0.0574160628 0.0695908205 0.0879767612 0.0058858918 0.0046340000 37682293 955859216 1373700096 -0.3011567593 -0.0103725726 -0.1441334188 392 1311867183.4988338947 0.0566222221 0.0695577373 0.0879767612 0.0059101264 0.0060500000 37685221 955859216 1373700096 -0.2999157012 -0.0116512720 -0.1442484111 393 1311867183.5321829319 0.0565578192 0.0695246586 0.0879767612 0.0059033304 0.0054000000 37688093 955859216 1373700096 -0.2981144190 -0.0122250989 -0.1439178288 394 1311867183.5661609173 0.0562246442 0.0694909023 0.0879767612 0.0058972176 0.0063030000 37691021 955859216 1373700096 -0.2966086566 -0.0117025524 -0.1435018033 395 1311867183.5985479355 0.0560110174 0.0694567760 0.0879767612 0.0058941689 0.0041950000 37693893 955859216 1373700096 -0.2944710255 -0.0127054341 -0.1433306932 396 1311867183.6310880184 0.0559864715 0.0694227601 0.0879767612 0.0059092722 0.0046860000 37696765 955859216 1373700096 -0.2927516401 -0.0131297400 -0.1428738981 397 1311867183.6649260521 0.0554471910 0.0693875571 0.0879767612 0.0059044919 0.0060870000 37699693 955859216 1373700096 -0.2913532853 -0.0135076409 -0.1421638876 398 1311867183.6993949413 0.0559396707 0.0693537685 0.0879767612 0.0058976327 0.0039820000 37702677 955859216 1373700096 -0.2886599302 -0.0145146418 -0.1417237669 399 1311867183.7308928967 0.0553538650 0.0693186810 0.0879767612 0.0058954159 0.0060600000 37705437 955859216 1373700096 -0.2871770859 -0.0145947309 -0.1413125843 400 1311867183.7676479816 0.0551696569 0.0692833084 0.0879767612 0.0058995722 0.0038490000 37708477 955859216 1373700096 -0.2844535112 -0.0150933182 -0.1406863630 401 1311867183.7971870899 0.0548463315 0.0692473060 0.0879767612 0.0058922132 0.0062080000 37711237 955859216 1373700096 -0.2832338512 -0.0158904996 -0.1400330961 402 1311867183.8309071064 0.0549462885 0.0692117313 0.0879767612 0.0058850850 0.0046500000 37714109 955859216 1373700096 -0.2812736332 -0.0166234765 -0.1393045783 403 1311867183.8655049801 0.0548536777 0.0691761034 0.0879767612 0.0058802170 0.0043480000 37717037 955859216 1373700096 -0.2793326974 -0.0178593826 -0.1391438693 404 1311867183.8970971107 0.0547003672 0.0691402724 0.0879767612 0.0058734111 0.0060840000 37719853 955859216 1373700096 -0.2779662907 -0.0181705188 -0.1387773007 405 1311867183.9314939976 0.0542095155 0.0691034063 0.0879767612 0.0058666406 0.0040340000 37722837 955859216 1373700096 -0.2770614028 -0.0184500944 -0.1381006390 406 1311867183.9658319950 0.0539763793 0.0690661476 0.0879767612 0.0058662081 0.0060670000 37725709 955859216 1373700096 -0.2752061188 -0.0193199981 -0.1379429400 407 1311867183.9966781139 0.0536137670 0.0690281811 0.0879767612 0.0058616008 0.0045560000 37728581 955859216 1373700096 -0.2743529081 -0.0200281870 -0.1374453306 408 1311867184.0309689045 0.0537691005 0.0689907814 0.0879767612 0.0058843573 0.0046440000 37731509 955859216 1373700096 -0.2733737528 -0.0202457402 -0.1369338483 409 1311867184.0647850037 0.0537804253 0.0689535922 0.0879767612 0.0058800882 0.0060730000 37734437 955859216 1373700096 -0.2718396485 -0.0212827250 -0.1364550292 410 1311867184.0968890190 0.0534366034 0.0689157459 0.0879767612 0.0058730990 0.0045680000 37737253 955859216 1373700096 -0.2705577910 -0.0216446277 -0.1359440386 411 1311867184.1312260628 0.0535922423 0.0688784624 0.0879767612 0.0058663054 0.0046510000 37740181 955859216 1373700096 -0.2688514292 -0.0216196664 -0.1352909952 412 1311867184.1650640965 0.0531301871 0.0688402385 0.0879767612 0.0058598726 0.0060970000 37743053 955859216 1373700096 -0.2677171230 -0.0226814579 -0.1350405067 413 1311867184.1969559193 0.0531566776 0.0688022638 0.0879767612 0.0058541911 0.0043010000 37745981 955859216 1373700096 -0.2656293511 -0.0222511422 -0.1345737427 414 1311867184.2309360504 0.0535544977 0.0687654334 0.0879767612 0.0058474171 0.0047570000 37748909 955859216 1373700096 -0.2631710768 -0.0220818948 -0.1339062452 415 1311867184.2681369781 0.0524535701 0.0687261277 0.0879767612 0.0058441424 0.0061870000 37751949 955859216 1373700096 -0.2623626888 -0.0234725978 -0.1337783933 416 1311867184.2983899117 0.0524673611 0.0686870441 0.0879767612 0.0058389403 0.0043650000 37754765 955859216 1373700096 -0.2606573701 -0.0230411030 -0.1332012862 417 1311867184.3314700127 0.0526575074 0.0686486040 0.0879767612 0.0058320564 0.0046920000 37757637 955859216 1373700096 -0.2578813136 -0.0226459820 -0.1326852590 418 1311867184.3697841167 0.0518533289 0.0686084239 0.0879767612 0.0058338872 0.0061740000 37760677 955859216 1373700096 -0.2564949393 -0.0238960367 -0.1325654536 419 1311867184.4000220299 0.0519682355 0.0685687099 0.0879767612 0.0058727562 0.0038680000 37763493 955859216 1373700096 -0.2544837594 -0.0236992463 -0.1321284175 420 1311867184.4310610294 0.0532763936 0.0685322996 0.0879767612 0.0058694230 0.0062110000 37766365 955859216 1373700096 -0.2508214712 -0.0231911968 -0.1316241622 421 1311867184.4655809402 0.0523264892 0.0684938060 0.0879767612 0.0058651013 0.0041560000 37769293 955859216 1373700096 -0.2502780259 -0.0249500629 -0.1317616999 422 1311867184.5037670135 0.0516595878 0.0684539145 0.0879767612 0.0059051370 0.0035900000 37772333 955859216 1373700096 -0.2484161258 -0.0260301847 -0.1320551634 423 1311867184.5310881138 0.0521475635 0.0684153652 0.0879767612 0.0059290113 0.0061880000 37775093 955859216 1373700096 -0.2458041906 -0.0254003480 -0.1325578988 424 1311867184.5682930946 0.0515357181 0.0683755547 0.0879767612 0.0059235195 0.0059710000 37778133 955859216 1373700096 -0.2435276508 -0.0256939288 -0.1330444515 425 1311867184.6018071175 0.0503650345 0.0683331770 0.0879767612 0.0059169428 0.0038870000 37781005 955859216 1373700096 -0.2420834750 -0.0267986879 -0.1334784180 426 1311867184.6367399693 0.0496235825 0.0682892577 0.0879767612 0.0059110778 0.0062450000 37783989 955859216 1373700096 -0.2405709624 -0.0269382987 -0.1328824759 427 1311867184.6662440300 0.0493575186 0.0682449211 0.0879767612 0.0059188192 0.0041130000 37786749 955859216 1373700096 -0.2377810329 -0.0280395914 -0.1326025277 428 1311867184.6994929314 0.0487682484 0.0681994149 0.0879767612 0.0059149383 0.0062860000 37789733 955859216 1373700096 -0.2356946766 -0.0294490363 -0.1324364245 429 1311867184.7359158993 0.0484243669 0.0681533192 0.0879767612 0.0059168402 0.0042440000 37792605 955859216 1373700096 -0.2332612723 -0.0291899908 -0.1317026466 430 1311867184.7690689564 0.0484200642 0.0681074279 0.0879767612 0.0059158507 0.0035380000 37795589 955859216 1373700096 -0.2313415706 -0.0307699144 -0.1308282018 431 1311867184.8001279831 0.0479020886 0.0680605478 0.0879767612 0.0059144433 0.0067550000 37798405 955859216 1373700096 -0.2291237861 -0.0312507823 -0.1300784498 432 1311867184.8348441124 0.0477573127 0.0680135495 0.0879767612 0.0059080780 0.0043980000 37801277 955859216 1373700096 -0.2262651920 -0.0312764011 -0.1290624887 433 1311867184.8690660000 0.0469713248 0.0679649532 0.0879767612 0.0059015952 0.0035170000 37804205 955859216 1373700096 -0.2243552953 -0.0323718563 -0.1282085776 434 1311867184.9055209160 0.0464280099 0.0679153289 0.0879767612 0.0058964603 0.0067310000 37807077 955859216 1373700096 -0.2215986848 -0.0329187661 -0.1271009743 435 1311867184.9332280159 0.0467386544 0.0678666469 0.0879767612 0.0058914188 0.0041080000 37809781 955859216 1373700096 -0.2182162553 -0.0328137837 -0.1254658997 436 1311867184.9656410217 0.0464537330 0.0678175347 0.0879767612 0.0058906200 0.0035420000 37812653 955859216 1373700096 -0.2161834687 -0.0342421085 -0.1240644455 437 1311867184.9983251095 0.0458260439 0.0677672109 0.0879767612 0.0058891451 0.0068680000 37815581 955859216 1373700096 -0.2133849263 -0.0352668576 -0.1227895766 438 1311867185.0360550880 0.0457061194 0.0677168431 0.0879767612 0.0058828887 0.0044110000 37818565 955859216 1373700096 -0.2099360079 -0.0355257019 -0.1210539863 439 1311867185.0652348995 0.0455357283 0.0676663167 0.0879767612 0.0058785928 0.0035780000 37821381 955859216 1373700096 -0.2076748908 -0.0366443507 -0.1196211427 440 1311867185.0991280079 0.0443085656 0.0676132309 0.0879767612 0.0058739848 0.0068310000 37824309 955859216 1373700096 -0.2061485052 -0.0366353542 -0.1182072461 441 1311867185.1360778809 0.0439851284 0.0675596524 0.0879767612 0.0058712209 0.0040030000 37827293 955859216 1373700096 -0.2033299208 -0.0369771346 -0.1162627116 442 1311867185.1648709774 0.0439544842 0.0675062470 0.0879767612 0.0058671187 0.0048050000 37830109 955859216 1373700096 -0.2004593462 -0.0381065644 -0.1145574227 443 1311867185.2000720501 0.0437292680 0.0674525744 0.0879767612 0.0058621936 0.0062920000 37832981 955859216 1373700096 -0.1971428096 -0.0382226519 -0.1127722338 444 1311867185.2342920303 0.0442341901 0.0674002807 0.0879767612 0.0058639279 0.0039770000 37835965 955859216 1373700096 -0.1936777532 -0.0382852629 -0.1106982678 445 1311867185.2663950920 0.0438829735 0.0673474329 0.0879767612 0.0058575881 0.0063510000 37838893 955859216 1373700096 -0.1911292076 -0.0403313898 -0.1091719940 446 1311867185.2970550060 0.0435388349 0.0672940504 0.0879767612 0.0058749761 0.0044270000 37841709 955859216 1373700096 -0.1880710721 -0.0405093357 -0.1076228470 447 1311867185.3360140324 0.0436099246 0.0672410657 0.0879767612 0.0058685313 0.0035570000 37844749 955859216 1373700096 -0.1852426082 -0.0408827364 -0.1058746278 448 1311867185.3681778908 0.0435974970 0.0671882899 0.0879767612 0.0058625173 0.0069260000 37847677 955859216 1373700096 -0.1820054948 -0.0421147346 -0.1046739891 449 1311867185.4036509991 0.0432032011 0.0671348710 0.0879767612 0.0058600017 0.0043490000 37850605 955859216 1373700096 -0.1792598665 -0.0425699949 -0.1034494340 450 1311867185.4386389256 0.0435861126 0.0670825404 0.0879767612 0.0058540806 0.0045180000 37853533 955859216 1373700096 -0.1757621914 -0.0423267111 -0.1019604877 451 1311867185.4655449390 0.0445141569 0.0670324997 0.0879767612 0.0058479056 0.0038600000 37856237 955859216 1373700096 -0.1733613163 -0.0435582735 -0.1008810848 452 1311867185.5013909340 0.0442354865 0.0669820638 0.0879767612 0.0058579894 0.0068180000 37859221 955859216 1373700096 -0.1703403294 -0.0447058864 -0.1001161188 453 1311867185.5336329937 0.0442693904 0.0669319254 0.0879767612 0.0058744896 0.0040250000 37862093 955859216 1373700096 -0.1677269787 -0.0442389138 -0.0989708304 454 1311867185.5666799545 0.0441646837 0.0668817773 0.0879767612 0.0058684970 0.0036190000 37865021 955859216 1373700096 -0.1661782861 -0.0453490205 -0.0981617346 455 1311867185.5970540047 0.0437669381 0.0668309755 0.0879767612 0.0058677688 0.0069020000 37867837 955859216 1373700096 -0.1632957160 -0.0466112942 -0.0978144854 456 1311867185.6329469681 0.0436100140 0.0667800523 0.0879767612 0.0058897516 0.0051800000 37870821 955859216 1373700096 -0.1610565484 -0.0461512618 -0.0968382508 457 1311867185.6664180756 0.0435539745 0.0667292294 0.0879767612 0.0058904277 0.0038570000 37873693 955859216 1373700096 -0.1575883776 -0.0467274971 -0.0960250050 458 1311867185.6973390579 0.0430824347 0.0666775988 0.0879767612 0.0058839963 0.0051980000 37876565 955859216 1373700096 -0.1545946151 -0.0475602411 -0.0953631625 459 1311867185.7351899147 0.0431330167 0.0666263035 0.0879767612 0.0058797163 0.0043460000 37879549 955859216 1373700096 -0.1513586640 -0.0471852273 -0.0937922448 460 1311867185.7649769783 0.0434921198 0.0665760118 0.0879767612 0.0058744960 0.0038600000 37882421 955859216 1373700096 -0.1487606764 -0.0486390367 -0.0925150067 461 1311867185.7989649773 0.0435807668 0.0665261305 0.0879767612 0.0058802535 0.0068930000 37885293 955859216 1373700096 -0.1457731575 -0.0498570651 -0.0916943252 462 1311867185.8327999115 0.0436011143 0.0664765093 0.0879767612 0.0058755892 0.0051890000 37888277 955859216 1373700096 -0.1424568594 -0.0496319495 -0.0905810297 463 1311867185.8649098873 0.0436645970 0.0664272395 0.0879767612 0.0058702101 0.0038450000 37891149 955859216 1373700096 -0.1394606680 -0.0507711619 -0.0894299895 464 1311867185.9030420780 0.0427788347 0.0663762731 0.0879767612 0.0058651875 0.0052380000 37894133 955859216 1373700096 -0.1370562017 -0.0516727753 -0.0885647312 465 1311867185.9396789074 0.0426494256 0.0663252476 0.0879767612 0.0058606434 0.0038570000 37897173 955859216 1373700096 -0.1348705590 -0.0517537370 -0.0869988948 466 1311867185.9650609493 0.0431804359 0.0662755806 0.0879767612 0.0058729062 0.0035380000 37899765 955859216 1373700096 -0.1319519132 -0.0535609573 -0.0859554783 467 1311867186.0039470196 0.0431125090 0.0662259809 0.0879767612 0.0058693389 0.0069970000 37902861 955859216 1373700096 -0.1292167753 -0.0545499548 -0.0850087181 468 1311867186.0396919250 0.0434341244 0.0661772804 0.0879767612 0.0058725378 0.0052790000 37905845 955859216 1373700096 -0.1270188093 -0.0543169156 -0.0836528987 469 1311867186.0653240681 0.0437457003 0.0661294518 0.0879767612 0.0058747891 0.0037530000 37908605 955859216 1373700096 -0.1254231781 -0.0560087487 -0.0827282071 470 1311867186.1047339439 0.0430111960 0.0660802641 0.0879767612 0.0058692730 0.0049410000 37911645 955859216 1373700096 -0.1240740046 -0.0574288666 -0.0822042301 471 1311867186.1361179352 0.0440879725 0.0660335713 0.0879767612 0.0058650136 0.0048950000 37914461 955859216 1373700096 -0.1206772551 -0.0579656363 -0.0813545510 472 1311867186.1649448872 0.0440408438 0.0659869765 0.0879767612 0.0058603621 0.0041450000 37917277 955859216 1373700096 -0.1192028895 -0.0593111478 -0.0808794200 473 1311867186.2044749260 0.0438611805 0.0659401990 0.0879767612 0.0058542350 0.0064750000 37920373 955859216 1373700096 -0.1169180796 -0.0599854067 -0.0805201083 474 1311867186.2359659672 0.0439472608 0.0658938004 0.0879767612 0.0058500940 0.0049370000 37923189 955859216 1373700096 -0.1150522456 -0.0603254549 -0.0797578394 475 1311867186.2674899101 0.0435958728 0.0658468574 0.0879767612 0.0058441304 0.0044100000 37926061 955859216 1373700096 -0.1139823943 -0.0614492223 -0.0791158453 476 1311867186.3030838966 0.0431639142 0.0657992041 0.0879767612 0.0058398209 0.0059010000 37929045 955859216 1373700096 -0.1119620949 -0.0617654100 -0.0784758329 477 1311867186.3349270821 0.0434880480 0.0657524302 0.0879767612 0.0058357120 0.0041960000 37931861 955859216 1373700096 -0.1089218035 -0.0619437695 -0.0772931054 478 1311867186.3670160770 0.0430250317 0.0657048833 0.0879767612 0.0058363024 0.0064930000 37934677 955859216 1373700096 -0.1075857803 -0.0637170747 -0.0765874684 479 1311867186.4019849300 0.0429248549 0.0656573259 0.0879767612 0.0058406204 0.0047980000 37937605 955859216 1373700096 -0.1055220962 -0.0639628917 -0.0756332502 480 1311867186.4360210896 0.0434573069 0.0656110758 0.0879767612 0.0058390152 0.0037580000 37940533 955859216 1373700096 -0.1025624126 -0.0636690930 -0.0739493519 481 1311867186.4659481049 0.0433776379 0.0655648525 0.0879767612 0.0058351067 0.0034930000 37943349 955859216 1373700096 -0.1013297066 -0.0654803887 -0.0727857575 482 1311867186.5031139851 0.0427530520 0.0655175251 0.0879767612 0.0058302946 0.0065570000 37946389 955859216 1373700096 -0.0997182652 -0.0665560886 -0.0719484687 483 1311867186.5363171101 0.0437512547 0.0654724603 0.0879767612 0.0058255046 0.0057360000 37949261 955859216 1373700096 -0.0967157856 -0.0661765635 -0.0703594163 484 1311867186.5651130676 0.0439730845 0.0654280401 0.0879767612 0.0058254285 0.0047210000 37952077 955859216 1373700096 -0.0951422006 -0.0676092431 -0.0696667954 485 1311867186.6014220715 0.0438933782 0.0653836388 0.0879767612 0.0058198554 0.0038370000 37955061 955859216 1373700096 -0.0936930627 -0.0685376525 -0.0694296807 486 1311867186.6362628937 0.0442839675 0.0653402238 0.0879767612 0.0058138865 0.0035130000 37957989 955859216 1373700096 -0.0916585028 -0.0689417422 -0.0691919103 487 1311867186.6650478840 0.0448499136 0.0652981493 0.0879767612 0.0058102992 0.0034800000 37960749 955859216 1373700096 -0.0899744332 -0.0686577335 -0.0689252764 488 1311867186.7043809891 0.0447233655 0.0652559878 0.0879767612 0.0058243672 0.0066430000 37963901 955859216 1373700096 -0.0882726237 -0.0690218732 -0.0692099482 489 1311867186.7337749004 0.0450565927 0.0652146803 0.0879767612 0.0058266421 0.0065690000 37966661 955859216 1373700096 -0.0863124207 -0.0677839443 -0.0693546906 490 1311867186.7673180103 0.0455753095 0.0651745999 0.0879767612 0.0058217830 0.0048350000 37969589 955859216 1373700096 -0.0842968151 -0.0671041831 -0.0692612603 491 1311867186.8047299385 0.0453964844 0.0651343186 0.0879767612 0.0058225862 0.0035320000 37972629 955859216 1373700096 -0.0828475729 -0.0680499524 -0.0699562356 492 1311867186.8340749741 0.0452648252 0.0650939335 0.0879767612 0.0058210479 0.0066300000 37975389 955859216 1373700096 -0.0815243647 -0.0667119995 -0.0702170283 493 1311867186.8775999546 0.0453967936 0.0650539798 0.0879767612 0.0058155789 0.0045680000 37978597 955859216 1373700096 -0.0790128112 -0.0652433932 -0.0703020990 494 1311867186.9052100182 0.0454085618 0.0650142118 0.0879767612 0.0058111233 0.0038300000 37981301 955859216 1373700096 -0.0776359066 -0.0648870543 -0.0704836696 495 1311867186.9334239960 0.0452773161 0.0649743393 0.0879767612 0.0058060835 0.0034910000 37984173 955859216 1373700096 -0.0759031773 -0.0643932000 -0.0706898421 496 1311867186.9663379192 0.0458114147 0.0649357043 0.0879767612 0.0058078886 0.0034940000 37986989 955859216 1373700096 -0.0734048486 -0.0624357872 -0.0704730451 497 1311867187.0017139912 0.0459773839 0.0648975588 0.0879767612 0.0058087875 0.0067300000 37989805 955859216 1373700096 -0.0709432960 -0.0621715225 -0.0706359595 498 1311867187.0336461067 0.0455554873 0.0648587193 0.0879767612 0.0058120128 0.0058730000 37992677 955859216 1373700096 -0.0691275224 -0.0612802617 -0.0709956214 499 1311867187.0749349594 0.0454366244 0.0648197973 0.0879767612 0.0058125605 0.0038350000 37995829 955859216 1373700096 -0.0677549392 -0.0593282804 -0.0706337616 500 1311867187.1016030312 0.0457581207 0.0647816739 0.0879767612 0.0058082460 0.0034700000 37998589 955859216 1373700096 -0.0648196936 -0.0585675426 -0.0704913437 501 1311867187.1342070103 0.0454151556 0.0647430182 0.0879767612 0.0058070839 0.0034640000 38001461 955859216 1373700096 -0.0634604096 -0.0599692985 -0.0708001927 502 1311867187.1710209846 0.0453787968 0.0647044441 0.0879767612 0.0058139133 0.0035000000 38004445 955859216 1373700096 -0.0615332052 -0.0589033887 -0.0707115531 503 1311867187.2041370869 0.0459957346 0.0646672498 0.0879767612 0.0058185963 0.0066450000 38007373 955859216 1373700096 -0.0587900467 -0.0582167841 -0.0707537308 504 1311867187.2331659794 0.0461179093 0.0646304456 0.0879767612 0.0058209562 0.0067580000 38010189 955859216 1373700096 -0.0556174666 -0.0590936840 -0.0714533329 505 1311867187.2707629204 0.0460398160 0.0645936324 0.0879767612 0.0058240020 0.0043050000 38013173 955859216 1373700096 -0.0533828326 -0.0579509288 -0.0717897788 506 1311867187.3015060425 0.0461069234 0.0645570974 0.0879767612 0.0058254389 0.0036720000 38016045 955859216 1373700096 -0.0513297543 -0.0579578951 -0.0721223950 507 1311867187.3336570263 0.0460050702 0.0645205057 0.0879767612 0.0058198399 0.0072440000 38018861 955859216 1373700096 -0.0497537106 -0.0586386621 -0.0728232712 508 1311867187.3707590103 0.0461731926 0.0644843889 0.0879767612 0.0058153422 0.0044500000 38021901 955859216 1373700096 -0.0483794324 -0.0585808940 -0.0732535720 509 1311867187.4033529758 0.0460832044 0.0644482373 0.0879767612 0.0058129621 0.0076180000 38024829 955859216 1373700096 -0.0468864590 -0.0586270317 -0.0738639534 510 1311867187.4335899353 0.0458022580 0.0644116765 0.0879767612 0.0058113075 0.0073140000 38027645 955859216 1373700096 -0.0451765470 -0.0591648668 -0.0744697228 511 1311867187.4763159752 0.0462174155 0.0643760713 0.0879767612 0.0058075731 0.0057670000 38030797 955859216 1373700096 -0.0426925048 -0.0588323288 -0.0748855397 512 1311867187.5056400299 0.0465748236 0.0643413033 0.0879767612 0.0058041547 0.0040770000 38033557 955859216 1373700096 -0.0400183797 -0.0593827367 -0.0755274296 513 1311867187.5342190266 0.0468285084 0.0643071653 0.0879767612 0.0058008245 0.0035080000 38085525 955859216 1373700096 -0.0372335650 -0.0598082729 -0.0763966888 514 1311867187.5709679127 0.0469351783 0.0642733676 0.0879767612 0.0057955551 0.0034980000 38190909 955859216 1373700096 -0.0344419703 -0.0600621626 -0.0772897527 515 1311867187.6045789719 0.0458058156 0.0642375083 0.0879767612 0.0058209539 0.0073830000 38193893 955859216 1373700096 -0.0331954435 -0.0601427369 -0.0786200166 516 1311867187.6353919506 0.0458602495 0.0642018934 0.0879767612 0.0058170202 0.0072920000 38196709 955859216 1373700096 -0.0304480307 -0.0605781078 -0.0798319504 517 1311867187.6707689762 0.0457034111 0.0641661130 0.0879767612 0.0058208916 0.0051640000 38199637 955859216 1373700096 -0.0273345374 -0.0596741103 -0.0808502212 518 1311867187.7035770416 0.0461978130 0.0641314252 0.0879767612 0.0058221730 0.0038790000 38202565 955859216 1373700096 -0.0247094501 -0.0593383238 -0.0815369114 519 1311867187.7345480919 0.0454262495 0.0640953844 0.0879767612 0.0058344774 0.0034580000 38205157 955859216 1373700096 -0.0228426997 -0.0610667095 -0.0830242038 520 1311867187.7707819939 0.0453110822 0.0640592607 0.0879767612 0.0058337856 0.0073110000 38208141 955859216 1373700096 -0.0202151313 -0.0596251525 -0.0837630704 521 1311867187.8017508984 0.0457983278 0.0640242109 0.0879767612 0.0058294809 0.0043240000 38211013 955859216 1373700096 -0.0174025223 -0.0589742213 -0.0845177621 522 1311867187.8339610100 0.0454404056 0.0639886098 0.0879767612 0.0058251270 0.0037200000 38213885 955859216 1373700096 -0.0153821101 -0.0589857176 -0.0853741392 523 1311867187.8708090782 0.0452046879 0.0639526941 0.0879767612 0.0058253451 0.0034870000 38216869 955859216 1373700096 -0.0124708470 -0.0580816567 -0.0859415755 524 1311867187.9038810730 0.0456235632 0.0639177148 0.0879767612 0.0058229291 0.0074480000 38219853 955859216 1373700096 -0.0092034750 -0.0573900975 -0.0864722058 525 1311867187.9363000393 0.0458154529 0.0638832343 0.0879767612 0.0058182323 0.0055310000 38222669 955859216 1373700096 -0.0060156751 -0.0570868552 -0.0871947557 526 1311867187.9713420868 0.0455783680 0.0638484342 0.0879767612 0.0058181599 0.0040890000 38225653 955859216 1373700096 -0.0030641295 -0.0578359663 -0.0883703083 527 1311867188.0047569275 0.0454670638 0.0638135549 0.0879767612 0.0058405067 0.0035110000 38228581 955859216 1373700096 -0.0004581882 -0.0568966530 -0.0893765464 528 1311867188.0333108902 0.0455932729 0.0637790468 0.0879767612 0.0058466320 0.0034840000 38231341 955859216 1373700096 0.0025893932 -0.0565088205 -0.0902358368 529 1311867188.0698699951 0.0453358814 0.0637441826 0.0879767612 0.0058410929 0.0074160000 38234269 955859216 1373700096 0.0057114498 -0.0576872230 -0.0916591510 530 1311867188.1088800430 0.0451559946 0.0637091105 0.0879767612 0.0058418680 0.0048940000 38237421 955859216 1373700096 0.0083503816 -0.0578564182 -0.0929632559 531 1311867188.1359970570 0.0439469144 0.0636718936 0.0879767612 0.0058491053 0.0037820000 38240125 955859216 1373700096 0.0120147429 -0.0569541901 -0.0940947160 532 1311867188.1703350544 0.0450456105 0.0636368818 0.0879767612 0.0058463161 0.0055710000 38243053 955859216 1373700096 0.0145119391 -0.0575932302 -0.0953786597 533 1311867188.2026720047 0.0447356179 0.0636014198 0.0879767612 0.0058482627 0.0064160000 38245981 955859216 1373700096 0.0161867142 -0.0581237637 -0.0967563540 534 1311867188.2352449894 0.0436240137 0.0635640089 0.0879767612 0.0058520310 0.0043070000 38248797 955859216 1373700096 0.0186713729 -0.0574643984 -0.0978948176 535 1311867188.2706460953 0.0443147980 0.0635280291 0.0879767612 0.0058492791 0.0055660000 38251781 955859216 1373700096 0.0219074376 -0.0572123453 -0.0990719646 536 1311867188.3047339916 0.0442558601 0.0634920735 0.0879767612 0.0058446360 0.0048760000 38254765 955859216 1373700096 0.0250712764 -0.0570879392 -0.1001978889 537 1311867188.3398799896 0.0441214591 0.0634560016 0.0879767612 0.0058401226 0.0070190000 38257749 955859216 1373700096 0.0273148995 -0.0563204475 -0.1010274291 538 1311867188.3718800545 0.0443964973 0.0634205750 0.0879767612 0.0058395135 0.0044220000 38260565 955859216 1373700096 0.0305996425 -0.0549031496 -0.1014962569 539 1311867188.4054470062 0.0442628674 0.0633850320 0.0879767612 0.0058405076 0.0046520000 38263437 955859216 1373700096 0.0338232629 -0.0543675497 -0.1020668820 540 1311867188.4398789406 0.0441426784 0.0633493980 0.0879767612 0.0058384348 0.0069800000 38266421 955859216 1373700096 0.0371332616 -0.0543495007 -0.1026925966 541 1311867188.4724500179 0.0445085838 0.0633145721 0.0879767612 0.0058411974 0.0050170000 38269293 955859216 1373700096 0.0394919366 -0.0524641238 -0.1028689817 542 1311867188.5049159527 0.0442903265 0.0632794720 0.0879767612 0.0058409023 0.0039470000 38272165 955859216 1373700096 0.0420941636 -0.0515141077 -0.1033043191 543 1311867188.5389990807 0.0441468656 0.0632442370 0.0879767612 0.0058428601 0.0069680000 38275149 955859216 1373700096 0.0448004566 -0.0517754443 -0.1039739400 544 1311867188.5723888874 0.0441280864 0.0632090970 0.0879767612 0.0058612849 0.0041970000 38278021 955859216 1373700096 0.0469087996 -0.0491657406 -0.1041227430 545 1311867188.6045958996 0.0447385460 0.0631752061 0.0879767612 0.0058560392 0.0052940000 38280893 955859216 1373700096 0.0493535474 -0.0484964326 -0.1040550917 546 1311867188.6398339272 0.0449485630 0.0631418240 0.0879767612 0.0058525158 0.0044000000 38283765 955859216 1373700096 0.0509099066 -0.0488953888 -0.1045961827 547 1311867188.6715080738 0.0454748794 0.0631095261 0.0879767612 0.0058526135 0.0069560000 38286693 955859216 1373700096 0.0536782220 -0.0479114726 -0.1050489396 548 1311867188.7038300037 0.0455100574 0.0630774102 0.0879767612 0.0058519303 0.0044070000 38289565 955859216 1373700096 0.0548554845 -0.0481706038 -0.1059106737 549 1311867188.7393829823 0.0453684628 0.0630451535 0.0879767612 0.0058567663 0.0036220000 38292493 955859216 1373700096 0.0561141707 -0.0487277284 -0.1071201563 550 1311867188.7721049786 0.0455415249 0.0630133287 0.0879767612 0.0058528386 0.0036140000 38295421 955859216 1373700096 0.0570138283 -0.0475939214 -0.1081650630 551 1311867188.8045220375 0.0463581868 0.0629831016 0.0879767612 0.0058530814 0.0069740000 38298349 955859216 1373700096 0.0591957159 -0.0462447591 -0.1089583784 552 1311867188.8402431011 0.0471805595 0.0629544738 0.0879767612 0.0058514827 0.0070340000 38301277 955859216 1373700096 0.0614244677 -0.0469573624 -0.1098965108 553 1311867188.8705990314 0.0476836786 0.0629268594 0.0879767612 0.0058487305 0.0042030000 38304093 955859216 1373700096 0.0631072521 -0.0465242416 -0.1108760014 554 1311867188.9016311169 0.0477661602 0.0628994935 0.0879767612 0.0058451983 0.0035520000 38306965 955859216 1373700096 0.0657966658 -0.0451940000 -0.1119455919 555 1311867188.9401769638 0.0483235717 0.0628732306 0.0879767612 0.0058436048 0.0033520000 38310061 955859216 1373700096 0.0694706813 -0.0457589440 -0.1131204441 556 1311867188.9709990025 0.0483373404 0.0628470869 0.0879767612 0.0058427772 0.0033480000 38312821 955859216 1373700096 0.0723948032 -0.0458151624 -0.1139366925 557 1311867189.0052258968 0.0485707819 0.0628214562 0.0879767612 0.0058384957 0.0033220000 38315805 955859216 1373700096 0.0763296932 -0.0449124463 -0.1143325269 558 1311867189.0400099754 0.0489921421 0.0627966724 0.0879767612 0.0058395868 0.0076000000 38318677 955859216 1373700096 0.0789858550 -0.0447495915 -0.1147547513 559 1311867189.0724329948 0.0488310680 0.0627716893 0.0879767612 0.0058381986 0.0075080000 38321661 955859216 1373700096 0.0822183788 -0.0447346680 -0.1149110049 560 1311867189.1026360989 0.0491735861 0.0627474069 0.0879767612 0.0058374018 0.0052280000 38324477 955859216 1373700096 0.0845761821 -0.0437415950 -0.1144064739 561 1311867189.1417639256 0.0494153649 0.0627236421 0.0879767612 0.0058329772 0.0037380000 38327573 955859216 1373700096 0.0869698673 -0.0436764471 -0.1136181504 562 1311867189.1717920303 0.0492344573 0.0626996400 0.0879767612 0.0058298423 0.0033060000 38330389 955859216 1373700096 0.0880328193 -0.0439746752 -0.1128526181 563 1311867189.2019069195 0.0494772457 0.0626761544 0.0879767612 0.0058252288 0.0070460000 38333205 955859216 1373700096 0.0903589576 -0.0437336564 -0.1116925403 564 1311867189.2390630245 0.0495998524 0.0626529695 0.0879767612 0.0058226707 0.0061340000 38336189 955859216 1373700096 0.0910032690 -0.0439340360 -0.1108985022 565 1311867189.2722640038 0.0495459102 0.0626297712 0.0879767612 0.0058179869 0.0041900000 38339061 955859216 1373700096 0.0925630629 -0.0446746573 -0.1100530177 566 1311867189.3046789169 0.0496595129 0.0626068555 0.0879767612 0.0058136753 0.0036810000 38341989 955859216 1373700096 0.0955854282 -0.0452439860 -0.1089524031 567 1311867189.3397970200 0.0491510592 0.0625831240 0.0879767612 0.0058170444 0.0070620000 38344917 955859216 1373700096 0.0972798765 -0.0466630757 -0.1082534418 568 1311867189.3720359802 0.0497427694 0.0625605177 0.0879767612 0.0058540180 0.0057440000 38347789 955859216 1373700096 0.0994477570 -0.0475920737 -0.1074356809 569 1311867189.4056949615 0.0497088172 0.0625379312 0.0879767612 0.0058578424 0.0039470000 38350717 955859216 1373700096 0.1035400927 -0.0472626872 -0.1059634089 570 1311867189.4405019283 0.0495829396 0.0625152032 0.0879767612 0.0058594604 0.0070490000 38353645 955859216 1373700096 0.1061309278 -0.0490224436 -0.1052616760 571 1311867189.4729130268 0.0503125191 0.0624938324 0.0879767612 0.0058556832 0.0042890000 38356573 955859216 1373700096 0.1089233086 -0.0508011989 -0.1045251638 572 1311867189.5060400963 0.0501573719 0.0624722652 0.0879767612 0.0058527766 0.0035420000 38359445 955859216 1373700096 0.1118722260 -0.0512315519 -0.1041614786 573 1311867189.5394289494 0.0502874516 0.0624510003 0.0879767612 0.0058485145 0.0037270000 38362317 955859216 1373700096 0.1153802499 -0.0534649938 -0.1039193049 574 1311867189.5720269680 0.0501114093 0.0624295027 0.0879767612 0.0058465528 0.0037760000 38365245 955859216 1373700096 0.1186116040 -0.0559615716 -0.1044394895 575 1311867189.6112909317 0.0506252572 0.0624089736 0.0879767612 0.0058440600 0.0037340000 38368285 955859216 1373700096 0.1233254671 -0.0563258380 -0.1044392809 576 1311867189.6424219608 0.0508032478 0.0623888248 0.0879767612 0.0058401682 0.0037230000 38371157 955859216 1373700096 0.1263379902 -0.0569579154 -0.1045566127 577 1311867189.6728401184 0.0508730412 0.0623688667 0.0879767612 0.0058353996 0.0075600000 38374029 955859216 1373700096 0.1290638149 -0.0584550537 -0.1048059762 578 1311867189.7065870762 0.0514785536 0.0623500254 0.0879767612 0.0058336394 0.0065720000 38376901 955859216 1373700096 0.1321574301 -0.0589721426 -0.1047221795 579 1311867189.7401719093 0.0513789207 0.0623310770 0.0879767612 0.0058291088 0.0040560000 38379829 955859216 1373700096 0.1366399080 -0.0587965436 -0.1041602790 580 1311867189.7729759216 0.0514820106 0.0623123717 0.0879767612 0.0058241353 0.0037910000 38382701 955859216 1373700096 0.1400232762 -0.0587258898 -0.1038616821 581 1311867189.8073968887 0.0510102883 0.0622929189 0.0879767612 0.0058225494 0.0035330000 38385629 955859216 1373700096 0.1432929635 -0.0597948767 -0.1033441871 582 1311867189.8405311108 0.0511854999 0.0622738340 0.0879767612 0.0058192032 0.0035130000 38388501 955859216 1373700096 0.1471689343 -0.0601830147 -0.1022787243 583 1311867189.8713529110 0.0508488566 0.0622542371 0.0879767612 0.0058154219 0.0035460000 38391373 955859216 1373700096 0.1513424814 -0.0611620061 -0.1014368981 584 1311867189.9102680683 0.0507573709 0.0622345507 0.0879767612 0.0058156883 0.0035110000 38394413 955859216 1373700096 0.1538120955 -0.0627368689 -0.1012538299 585 1311867189.9402260780 0.0504220985 0.0622143585 0.0879767612 0.0058121597 0.0035530000 38397285 955859216 1373700096 0.1577741653 -0.0628329664 -0.1009049863 586 1311867189.9727621078 0.0501192324 0.0621937183 0.0879767612 0.0058072960 0.0035560000 38400157 955859216 1373700096 0.1619214714 -0.0631033331 -0.1005829871 587 1311867190.0107009411 0.0503159501 0.0621734836 0.0879767612 0.0058053610 0.0035040000 38403141 955859216 1373700096 0.1652848870 -0.0637604520 -0.1004953682 588 1311867190.0402929783 0.0504660457 0.0621535730 0.0879767612 0.0058021017 0.0035860000 38405957 955859216 1373700096 0.1680926383 -0.0642158985 -0.1004275456 589 1311867190.0719039440 0.0506538860 0.0621340489 0.0879767612 0.0057977095 0.0035360000 38408829 955859216 1373700096 0.1707332432 -0.0650281832 -0.1004624888 590 1311867190.1096539497 0.0539838411 0.0621202350 0.0879767612 0.0058075686 0.0078130000 38411869 955859216 1373700096 0.1650623679 -0.0659147277 -0.1020796373 591 1311867190.1396369934 0.0550047234 0.0621081952 0.0879767612 0.0058058917 0.0076910000 38414741 955859216 1373700096 0.1660998613 -0.0655532405 -0.1026362181 592 1311867190.1706380844 0.0555966794 0.0620971961 0.0879767612 0.0058069383 0.0044390000 38417501 955859216 1373700096 0.1678412408 -0.0659623295 -0.1029888391 593 1311867190.2096021175 0.0564098172 0.0620876052 0.0879767612 0.0058028873 0.0037180000 38420597 955859216 1373700096 0.1689225137 -0.0678638816 -0.1037383452 594 1311867190.2394330502 0.0564703234 0.0620781485 0.0879767612 0.0058079095 0.0057310000 38423357 955859216 1373700096 0.1721715331 -0.0673021525 -0.1038742959 595 1311867190.2714810371 0.0568790361 0.0620694105 0.0879767612 0.0058094523 0.0055460000 38426285 955859216 1373700096 0.1742618531 -0.0676079318 -0.1041336805 596 1311867190.3072700500 0.0579506233 0.0620624998 0.0879767612 0.0058078348 0.0047640000 38429269 955859216 1373700096 0.1756355315 -0.0677579790 -0.1043412909 597 1311867190.3414731026 0.0575334318 0.0620549134 0.0879767612 0.0058047079 0.0057380000 38432197 955859216 1373700096 0.1793499142 -0.0678487867 -0.1041538641 598 1311867190.3716828823 0.0570109971 0.0620464787 0.0879767612 0.0058073303 0.0049540000 38435013 955859216 1373700096 0.1830792278 -0.0673534870 -0.1037039682 599 1311867190.4101090431 0.0578817651 0.0620395260 0.0879767612 0.0058053523 0.0041560000 38437997 955859216 1373700096 0.1845826358 -0.0676309690 -0.1037890986 600 1311867190.4394960403 0.0577435233 0.0620323660 0.0879767612 0.0058027382 0.0074610000 38440925 955859216 1373700096 0.1877625883 -0.0667672157 -0.1031793281 601 1311867190.4708199501 0.0578392819 0.0620253891 0.0879767612 0.0057986530 0.0043650000 38443685 955859216 1373700096 0.1903668344 -0.0672033876 -0.1027487069 602 1311867190.5097529888 0.0576157495 0.0620180641 0.0879767612 0.0057944060 0.0067980000 38446837 955859216 1373700096 0.1930961460 -0.0680737868 -0.1024070978 603 1311867190.5405189991 0.0582116172 0.0620117516 0.0879767612 0.0057963758 0.0042770000 38449597 955859216 1373700096 0.1953508854 -0.0670229271 -0.1021613404 604 1311867190.5708439350 0.0581643023 0.0620053817 0.0879767612 0.0057936698 0.0050770000 38452413 955859216 1373700096 0.1978691518 -0.0677990466 -0.1016115919 605 1311867190.6067750454 0.0583112128 0.0619992756 0.0879767612 0.0057893534 0.0078880000 38455397 955859216 1373700096 0.1999328434 -0.0684050173 -0.1014928147 606 1311867190.6389939785 0.0578710027 0.0619924633 0.0879767612 0.0057856264 0.0045190000 38458325 955859216 1373700096 0.2034548968 -0.0681591406 -0.1007402912 607 1311867190.6723659039 0.0577922203 0.0619855436 0.0879767612 0.0057816998 0.0037010000 38461197 955859216 1373700096 0.2067569047 -0.0692720041 -0.0999290422 608 1311867190.7114980221 0.0583674200 0.0619795927 0.0879767612 0.0057787732 0.0057980000 38464237 955859216 1373700096 0.2085960954 -0.0696687624 -0.0993091017 609 1311867190.7392649651 0.0578457229 0.0619728048 0.0879767612 0.0057743922 0.0047810000 38466941 955859216 1373700096 0.2114026994 -0.0701960400 -0.0985006392 610 1311867190.7751801014 0.0574936941 0.0619654620 0.0879767612 0.0057698647 0.0071620000 38469925 955859216 1373700096 0.2140987664 -0.0704688951 -0.0979210436 611 1311867190.8070900440 0.0575556941 0.0619582447 0.0879767612 0.0057661076 0.0042980000 38472853 955859216 1373700096 0.2167179286 -0.0707740188 -0.0970426872 612 1311867190.8414280415 0.0571784340 0.0619504345 0.0879767612 0.0057679907 0.0036770000 38475781 955859216 1373700096 0.2193292230 -0.0721141919 -0.0962810442 613 1311867190.8739249706 0.0576246828 0.0619433778 0.0879767612 0.0057639950 0.0073290000 38478653 955859216 1373700096 0.2209461629 -0.0731105432 -0.0956476107 614 1311867190.9076139927 0.0577439405 0.0619365384 0.0879767612 0.0057594537 0.0047250000 38481581 955859216 1373700096 0.2231615186 -0.0732150599 -0.0948333517 615 1311867190.9393599033 0.0571810789 0.0619288059 0.0879767612 0.0057563220 0.0065220000 38484397 955859216 1373700096 0.2263612747 -0.0746489316 -0.0939838365 616 1311867190.9741609097 0.0571896620 0.0619211125 0.0879767612 0.0057519879 0.0041040000 38487381 955859216 1373700096 0.2285855561 -0.0758686438 -0.0934241861 617 1311867191.0085949898 0.0573753417 0.0619137450 0.0879767612 0.0057548974 0.0037010000 38490309 955859216 1373700096 0.2313363403 -0.0749419853 -0.0924871638 618 1311867191.0396919250 0.0574981123 0.0619065999 0.0879767612 0.0057516635 0.0074280000 38493181 955859216 1373700096 0.2333983481 -0.0753467381 -0.0915098116 619 1311867191.0764329433 0.0578303263 0.0619000147 0.0879767612 0.0057495430 0.0053550000 38496165 955859216 1373700096 0.2347634286 -0.0774587318 -0.0911685824 620 1311867191.1103041172 0.0586855896 0.0618948301 0.0879767612 0.0057553208 0.0038610000 38499093 955859216 1373700096 0.2373062074 -0.0773054510 -0.0899128467 621 1311867191.1388139725 0.0577136651 0.0618880972 0.0879767612 0.0057672101 0.0073620000 38501909 955859216 1373700096 0.2414283752 -0.0777061135 -0.0887900665 622 1311867191.1742820740 0.0584044978 0.0618824965 0.0879767612 0.0057642481 0.0046360000 38504837 955859216 1373700096 0.2425663024 -0.0791491419 -0.0883308128 623 1311867191.2077920437 0.0587909035 0.0618775341 0.0879767612 0.0057597431 0.0049050000 38507765 955859216 1373700096 0.2452963591 -0.0787789002 -0.0873351693 624 1311867191.2408421040 0.0596140847 0.0618739068 0.0879767612 0.0057564234 0.0066150000 38510693 955859216 1373700096 0.2470261753 -0.0787806660 -0.0867220312 625 1311867191.2769579887 0.0602558143 0.0618713178 0.0879767612 0.0057541512 0.0041420000 38513621 955859216 1373700096 0.2491354942 -0.0794707090 -0.0861495286 626 1311867191.3085029125 0.0607131831 0.0618694678 0.0879767612 0.0057553821 0.0074340000 38516325 955859216 1373700096 0.2514851391 -0.0786473826 -0.0852544382 627 1311867191.3404779434 0.0606119893 0.0618674622 0.0879767612 0.0057522076 0.0044480000 38519197 955859216 1373700096 0.2543281615 -0.0792398900 -0.0843305513 628 1311867191.3794629574 0.0607010461 0.0618656049 0.0879767612 0.0057479703 0.0037570000 38522293 955859216 1373700096 0.2562235296 -0.0805925205 -0.0838673487 629 1311867191.4091579914 0.0602166094 0.0618629832 0.0879767612 0.0057449560 0.0075040000 38525053 955859216 1373700096 0.2593467832 -0.0812699944 -0.0830236226 630 1311867191.4415969849 0.0595402047 0.0618592963 0.0879767612 0.0057412290 0.0044620000 38527925 955859216 1373700096 0.2630073130 -0.0809466243 -0.0820835158 631 1311867191.4775309563 0.0599211380 0.0618562247 0.0879767612 0.0057418063 0.0055830000 38530853 955859216 1373700096 0.2640021145 -0.0823403075 -0.0817247182 632 1311867191.5075590611 0.0600352436 0.0618533434 0.0879767612 0.0057378028 0.0059920000 38533613 955859216 1373700096 0.2656421363 -0.0820095539 -0.0808938593 633 1311867191.5390620232 0.0595156066 0.0618496503 0.0879767612 0.0057335160 0.0045010000 38536485 955859216 1373700096 0.2685846388 -0.0822776929 -0.0800643414 634 1311867191.5764698982 0.0597524531 0.0618463424 0.0879767612 0.0057299998 0.0055830000 38539469 955859216 1373700096 0.2707674503 -0.0822424889 -0.0793194026 635 1311867191.6118669510 0.0597971566 0.0618431154 0.0879767612 0.0057550574 0.0072800000 38542453 955859216 1373700096 0.2733595967 -0.0815483257 -0.0782381594 636 1311867191.6451880932 0.0597534552 0.0618398297 0.0879767612 0.0057520338 0.0043630000 38545325 955859216 1373700096 0.2752856314 -0.0819676593 -0.0770629272 637 1311867191.6827919483 0.0586503781 0.0618348228 0.0879767612 0.0057561298 0.0066500000 38548421 955859216 1373700096 0.2785728872 -0.0827428997 -0.0757936761 638 1311867191.7119400501 0.0586643852 0.0618298534 0.0879767612 0.0057541658 0.0047670000 38551181 955859216 1373700096 0.2803935409 -0.0821922794 -0.0748477727 639 1311867191.7457199097 0.0588121004 0.0618251308 0.0879767612 0.0057695923 0.0063980000 38553997 955859216 1373700096 0.2804291546 -0.0827937946 -0.0743943304 640 1311867191.7763800621 0.0593103468 0.0618212014 0.0879767612 0.0057727254 0.0054250000 38556813 955859216 1373700096 0.2814023495 -0.0828595683 -0.0735422373 641 1311867191.8097250462 0.0582748167 0.0618156689 0.0879767612 0.0057710998 0.0038560000 38559741 955859216 1373700096 0.2848758698 -0.0828392953 -0.0717185959 642 1311867191.8395779133 0.0576856136 0.0618092358 0.0879767612 0.0057750845 0.0075860000 38562557 955859216 1373700096 0.2865164280 -0.0833734423 -0.0711097866 643 1311867191.8745219707 0.0579876862 0.0618032924 0.0879767612 0.0057769144 0.0044680000 38565485 955859216 1373700096 0.2875322104 -0.0828682035 -0.0701841116 644 1311867191.9077119827 0.0567987971 0.0617955215 0.0879767612 0.0057734637 0.0037430000 38568413 955859216 1373700096 0.2905162275 -0.0831638202 -0.0687517896 645 1311867191.9391601086 0.0574952252 0.0617888544 0.0879767612 0.0057701692 0.0076500000 38571285 955859216 1373700096 0.2906839848 -0.0842838064 -0.0680272803 646 1311867191.9755239487 0.0569920763 0.0617814290 0.0879767612 0.0057691740 0.0047740000 38574213 955859216 1373700096 0.2928285003 -0.0840619132 -0.0668494329 647 1311867192.0076289177 0.0573392622 0.0617745632 0.0879767612 0.0057658062 0.0038200000 38577085 955859216 1373700096 0.2937584519 -0.0841044337 -0.0659002289 648 1311867192.0447950363 0.0569155216 0.0617670647 0.0879767612 0.0057747489 0.0075750000 38580125 955859216 1373700096 0.2945601344 -0.0857900828 -0.0655537471 649 1311867192.0751929283 0.0573383681 0.0617602408 0.0879767612 0.0057733127 0.0047250000 38582885 955859216 1373700096 0.2950904667 -0.0855180696 -0.0649418607 650 1311867192.1073920727 0.0573200211 0.0617534097 0.0879767612 0.0057718627 0.0039160000 38585813 955859216 1373700096 0.2977598310 -0.0848359615 -0.0633349270 651 1311867192.1433029175 0.0580477677 0.0617477175 0.0879767612 0.0057765117 0.0081140000 38588797 955859216 1373700096 0.2970850766 -0.0862895027 -0.0633296072 652 1311867192.1754670143 0.0590158664 0.0617435275 0.0879767612 0.0057814731 0.0045620000 38591669 955859216 1373700096 0.2975247502 -0.0857635289 -0.0625060573 653 1311867192.2077538967 0.0589376241 0.0617392306 0.0879767612 0.0057781983 0.0050830000 38594597 955859216 1373700096 0.2997426391 -0.0854731500 -0.0613194481 654 1311867192.2451250553 0.0584545843 0.0617342082 0.0879767612 0.0057860077 0.0051230000 38597637 955859216 1373700096 0.3014416397 -0.0872414783 -0.0603374913 655 1311867192.2744629383 0.0590276606 0.0617300761 0.0879767612 0.0057839175 0.0068030000 38600397 955859216 1373700096 0.3024468124 -0.0863627344 -0.0596605204 656 1311867192.3067719936 0.0591986254 0.0617262171 0.0879767612 0.0057817490 0.0044220000 38603269 955859216 1373700096 0.3044808805 -0.0869449675 -0.0584813207 657 1311867192.3427391052 0.0596414581 0.0617230440 0.0879767612 0.0057785096 0.0040560000 38606253 955859216 1373700096 0.3053011596 -0.0884595811 -0.0580229945 658 1311867192.3755910397 0.0609612204 0.0617218862 0.0879767612 0.0057813275 0.0039840000 38609181 955859216 1373700096 0.3059546649 -0.0881479904 -0.0574852601 659 1311867192.4059340954 0.0606599748 0.0617202748 0.0879767612 0.0057774037 0.0039640000 38611941 955859216 1373700096 0.3085039258 -0.0889094546 -0.0567339659 660 1311867192.4447100163 0.0619034693 0.0617205524 0.0879767612 0.0057748384 0.0081810000 38615037 955859216 1373700096 0.3091182709 -0.0902453959 -0.0567853712 661 1311867192.4748210907 0.0634772032 0.0617232099 0.0879767612 0.0057744750 0.0057380000 38617853 955859216 1373700096 0.3094777763 -0.0899436697 -0.0564241782 662 1311867192.5077190399 0.0643064156 0.0617271121 0.0879767612 0.0057706406 0.0041190000 38620725 955859216 1373700096 0.3104402721 -0.0906891972 -0.0560483485 663 1311867192.5427820683 0.0643187165 0.0617310210 0.0879767612 0.0057690193 0.0034920000 38623709 955859216 1373700096 0.3116213977 -0.0923091322 -0.0561518222 664 1311867192.5787169933 0.0655718744 0.0617368054 0.0879767612 0.0057692514 0.0081220000 38626637 955859216 1373700096 0.3124076426 -0.0917554945 -0.0560445897 665 1311867192.6109929085 0.0682071522 0.0617465352 0.0879767612 0.0057662091 0.0045160000 38629509 955859216 1373700096 0.3106949031 -0.0913506746 -0.0561859384 666 1311867192.6435210705 0.0695400313 0.0617582372 0.0879767612 0.0057663509 0.0050740000 38632437 955859216 1373700096 0.3103632927 -0.0926471353 -0.0564148799 667 1311867192.6790139675 0.0699802786 0.0617705641 0.0879767612 0.0057634747 0.0053200000 38635421 955859216 1373700096 0.3118716180 -0.0925019532 -0.0558730736 668 1311867192.7113289833 0.0696357712 0.0617823383 0.0879767612 0.0057603650 0.0041600000 38638237 955859216 1373700096 0.3137868345 -0.0927264094 -0.0554904118 669 1311867192.7439620495 0.0704568401 0.0617953047 0.0879767612 0.0057597795 0.0076650000 38641165 955859216 1373700096 0.3139829338 -0.0936398134 -0.0553006791 670 1311867192.7760629654 0.0700900108 0.0618076849 0.0879767612 0.0057581648 0.0047910000 38644037 955859216 1373700096 0.3160553277 -0.0930114910 -0.0547101647 671 1311867192.8091869354 0.0702396855 0.0618202512 0.0879767612 0.0057539676 0.0037860000 38646965 955859216 1373700096 0.3172634840 -0.0936240628 -0.0542797744 672 1311867192.8422288895 0.0701031387 0.0618325769 0.0879767612 0.0057503697 0.0076210000 38649837 955859216 1373700096 0.3184885383 -0.0943547115 -0.0539395176 673 1311867192.8792889118 0.0708098188 0.0618459161 0.0879767612 0.0057510053 0.0047860000 38652877 955859216 1373700096 0.3191541135 -0.0935528278 -0.0533622913 674 1311867192.9092190266 0.0700889379 0.0618581461 0.0879767612 0.0057471273 0.0050210000 38655637 955859216 1373700096 0.3212997019 -0.0940892026 -0.0524531305 675 1311867192.9434111118 0.0698464736 0.0618699806 0.0879767612 0.0057443011 0.0067010000 38658621 955859216 1373700096 0.3225447536 -0.0955971777 -0.0522286631 676 1311867192.9776289463 0.0697876960 0.0618816932 0.0879767612 0.0057445764 0.0047290000 38661493 955859216 1373700096 0.3244131207 -0.0948710740 -0.0516487248 677 1311867193.0086810589 0.0697835013 0.0618933650 0.0879767612 0.0057424820 0.0075590000 38664365 955859216 1373700096 0.3253669143 -0.0950489193 -0.0511940196 678 1311867193.0430600643 0.0694260001 0.0619044751 0.0879767612 0.0057403990 0.0081790000 38667293 955859216 1373700096 0.3267825246 -0.0965492949 -0.0510832109 679 1311867193.0767369270 0.0700351968 0.0619164496 0.0879767612 0.0057458150 0.0079940000 38670165 955859216 1373700096 0.3279123902 -0.0953266770 -0.0509317741 680 1311867193.1105849743 0.0696774721 0.0619278629 0.0879767612 0.0057426849 0.0072830000 38673093 955859216 1373700096 0.3299369216 -0.0953102782 -0.0504171848 681 1311867193.1429219246 0.0686201081 0.0619376900 0.0879767612 0.0057437863 0.0044920000 38676021 955859216 1373700096 0.3314422965 -0.0968803987 -0.0503761992 682 1311867193.1767370701 0.0700588599 0.0619495979 0.0879767612 0.0057581663 0.0037510000 38678893 955859216 1373700096 0.3324027658 -0.0948469341 -0.0500523932 683 1311867193.2122681141 0.0701991394 0.0619616763 0.0879767612 0.0057583922 0.0084090000 38681877 955859216 1373700096 0.3337546289 -0.0953679159 -0.0496062078 684 1311867193.2432429790 0.0696869493 0.0619729705 0.0879767612 0.0057571883 0.0078680000 38684749 955859216 1373700096 0.3354801536 -0.0960990712 -0.0495727696 685 1311867193.2773900032 0.0704202503 0.0619853023 0.0879767612 0.0057551834 0.0052330000 38687677 955859216 1373700096 0.3362523317 -0.0950251743 -0.0494545437 686 1311867193.3139379025 0.0717388391 0.0619995203 0.0879767612 0.0057552571 0.0040310000 38690661 955859216 1373700096 0.3359813392 -0.0957661346 -0.0498350859 687 1311867193.3426671028 0.0715027228 0.0620133532 0.0879767612 0.0057549353 0.0035120000 38693421 955859216 1373700096 0.3375521302 -0.0955937579 -0.0495539196 688 1311867193.3788230419 0.0709470063 0.0620263382 0.0879767612 0.0057514480 0.0083940000 38696405 955859216 1373700096 0.3400720656 -0.0950994194 -0.0492386259 689 1311867193.4126739502 0.0714091510 0.0620399562 0.0879767612 0.0057578006 0.0049990000 38699277 955859216 1373700096 0.3407445252 -0.0962784067 -0.0493740067 690 1311867193.4440810680 0.0717647970 0.0620540502 0.0879767612 0.0057581187 0.0040030000 38702205 955859216 1373700096 0.3419781327 -0.0961120054 -0.0492966883 691 1311867193.4782969952 0.0719123855 0.0620683169 0.0879767612 0.0057548784 0.0060430000 38705133 955859216 1373700096 0.3437364101 -0.0955527052 -0.0490349345 692 1311867193.5199069977 0.0731311217 0.0620843036 0.0879767612 0.0057529915 0.0044760000 38708173 955859216 1373700096 0.3439876139 -0.0966726989 -0.0493284091 693 1311867193.5431120396 0.0723529905 0.0620991214 0.0879767612 0.0057524134 0.0040240000 38710877 955859216 1373700096 0.3460828960 -0.0967312977 -0.0491237342 694 1311867193.5765709877 0.0728863999 0.0621146650 0.0879767612 0.0057485960 0.0084360000 38713749 955859216 1373700096 0.3473766148 -0.0961158350 -0.0489720292 695 1311867193.6127800941 0.0732794181 0.0621307294 0.0879767612 0.0057445787 0.0048520000 38716789 955859216 1373700096 0.3482301533 -0.0971114859 -0.0492238365 696 1311867193.6461451054 0.0740058646 0.0621477914 0.0879767612 0.0057418487 0.0038790000 38719661 955859216 1373700096 0.3488845229 -0.0970039666 -0.0493638888 697 1311867193.6757860184 0.0742174610 0.0621651080 0.0879767612 0.0057384251 0.0083200000 38722477 955859216 1373700096 0.3506207466 -0.0959418043 -0.0490721092 698 1311867193.7122890949 0.0749065951 0.0621833622 0.0879767612 0.0057347249 0.0046400000 38725461 955859216 1373700096 0.3509138227 -0.0969107449 -0.0492935032 699 1311867193.7430191040 0.0757921487 0.0622028312 0.0879767612 0.0057324441 0.0052060000 38728277 955859216 1373700096 0.3513762653 -0.0962543339 -0.0494081378 700 1311867193.7760169506 0.0765208751 0.0622232855 0.0879767612 0.0057297252 0.0052660000 38731149 955859216 1373700096 0.3521594703 -0.0953507572 -0.0496844649 701 1311867193.8139710426 0.0771733075 0.0622446122 0.0879767612 0.0057271999 0.0066240000 38734245 955859216 1373700096 0.3530349433 -0.0966375843 -0.0494868793 702 1311867193.8436760902 0.0774928182 0.0622663333 0.0879767612 0.0057249961 0.0043130000 38737005 955859216 1373700096 0.3540245891 -0.0964801013 -0.0495847389 703 1311867193.8771181107 0.0775683001 0.0622881000 0.0879767612 0.0057219459 0.0078750000 38739933 955859216 1373700096 0.3558255136 -0.0959614664 -0.0494788066 704 1311867193.9151229858 0.0788613856 0.0623116416 0.0879767612 0.0057187704 0.0046030000 38742917 955859216 1373700096 0.3557147682 -0.0967585593 -0.0497412011 705 1311867193.9425311089 0.0789144114 0.0623351916 0.0879767612 0.0057167007 0.0056880000 38745733 955859216 1373700096 0.3569036126 -0.0961354151 -0.0497392043 706 1311867193.9781770706 0.0796865523 0.0623597686 0.0879767612 0.0057136448 0.0058820000 38748717 955859216 1373700096 0.3577373326 -0.0958474576 -0.0497641675 707 1311867194.0148570538 0.0818819925 0.0623873814 0.0879767612 0.0057121001 0.0041130000 38751645 955859216 1373700096 0.3564856648 -0.0963978097 -0.0505024754 708 1311867194.0433440208 0.0829713345 0.0624164548 0.0879767612 0.0057098617 0.0080240000 38754461 955859216 1373700096 0.3567295671 -0.0960134640 -0.0504495464 709 1311867194.0746119022 0.0820358619 0.0624441267 0.0879767612 0.0057063778 0.0052770000 38757277 955859216 1373700096 0.3591574728 -0.0958795249 -0.0499416292 710 1311867194.1131060123 0.0830594227 0.0624731623 0.0879767612 0.0057025678 0.0041110000 38760373 955859216 1373700096 0.3587500453 -0.0963796452 -0.0504609942 711 1311867194.1428558826 0.0840891004 0.0625035645 0.0879767612 0.0057008461 0.0062970000 38763189 955859216 1373700096 0.3585561216 -0.0957223549 -0.0503723621 712 1311867194.1758549213 0.0835785791 0.0625331642 0.0879767612 0.0057027682 0.0042940000 38766061 955859216 1373700096 0.3599736989 -0.0949633047 -0.0498688556 713 1311867194.2138450146 0.0843463317 0.0625637577 0.0879767612 0.0056998620 0.0063070000 38769101 955859216 1373700096 0.3596100509 -0.0958086848 -0.0501904450 714 1311867194.2451140881 0.0843478814 0.0625942677 0.0879767612 0.0056976907 0.0051730000 38771861 955859216 1373700096 0.3605121970 -0.0949527621 -0.0498746149 715 1311867194.2760241032 0.0837947428 0.0626239187 0.0879767612 0.0056941661 0.0062640000 38774677 955859216 1373700096 0.3617983162 -0.0950550959 -0.0493172258 716 1311867194.3139200211 0.0849915370 0.0626551584 0.0879767612 0.0056914683 0.0043060000 38777717 955859216 1373700096 0.3610507548 -0.0956552848 -0.0496269576 717 1311867194.3447821140 0.0847514495 0.0626859761 0.0879767612 0.0056918761 0.0038020000 38780589 955859216 1373700096 0.3619493842 -0.0947105959 -0.0491605960 718 1311867194.3802230358 0.0832239315 0.0627145805 0.0879767612 0.0056890861 0.0038360000 38783517 955859216 1373700096 0.3642917275 -0.0948965773 -0.0485028885 719 1311867194.4124519825 0.0835564882 0.0627435679 0.0879767612 0.0056875122 0.0086090000 38786333 955859216 1373700096 0.3641254902 -0.0961479545 -0.0482698120 720 1311867194.4447510242 0.0839984640 0.0627730886 0.0879767612 0.0056838706 0.0060230000 38789261 955859216 1373700096 0.3643788695 -0.0962270573 -0.0480230525 721 1311867194.4805839062 0.0839333087 0.0628024370 0.0879767612 0.0056804088 0.0042780000 38792133 955859216 1373700096 0.3651224375 -0.0959207118 -0.0478962213 722 1311867194.5174930096 0.0846396908 0.0628326825 0.0879767612 0.0056777666 0.0057880000 38795229 955859216 1373700096 0.3646730185 -0.0966887102 -0.0479166433 723 1311867194.5439500809 0.0847898722 0.0628630520 0.0879767612 0.0056758839 0.0040400000 38797877 955859216 1373700096 0.3648068607 -0.0963319018 -0.0479586758 724 1311867194.5795979500 0.0841101557 0.0628923989 0.0879767612 0.0056720271 0.0087390000 38800805 955859216 1373700096 0.3660862744 -0.0963483974 -0.0474248491 725 1311867194.6129479408 0.0834933519 0.0629208140 0.0879767612 0.0056685474 0.0053190000 38803733 955859216 1373700096 0.3672118783 -0.0971534848 -0.0468249023 726 1311867194.6493880749 0.0822197795 0.0629473966 0.0879767612 0.0056769047 0.0041760000 38806773 955859216 1373700096 0.3689195216 -0.0969558060 -0.0459792428 727 1311867194.6784319878 0.0814856440 0.0629728962 0.0879767612 0.0056758737 0.0034990000 38809533 955859216 1373700096 0.3700169027 -0.0970686451 -0.0456891432 728 1311867194.7133309841 0.0822113007 0.0629993226 0.0879767612 0.0056737619 0.0034720000 38812461 955859216 1373700096 0.3695824146 -0.0969022065 -0.0456304513 729 1311867194.7475099564 0.0824171677 0.0630259589 0.0879767612 0.0056702379 0.0034680000 38815389 955859216 1373700096 0.3700455427 -0.0965057015 -0.0451992378 730 1311867194.7784450054 0.0827669278 0.0630530013 0.0879767612 0.0056665404 0.0035060000 38818261 955859216 1373700096 0.3700821400 -0.0966032594 -0.0448750444 731 1311867194.8130390644 0.0826987326 0.0630798765 0.0879767612 0.0056626710 0.0034790000 38821189 955859216 1373700096 0.3703984320 -0.0964669362 -0.0445936061 732 1311867194.8476719856 0.0836651474 0.0631079984 0.0879767612 0.0056590422 0.0090670000 38824117 955859216 1373700096 0.3692975044 -0.0961253718 -0.0448377132 733 1311867194.8814148903 0.0839124769 0.0631363811 0.0879767612 0.0056556331 0.0087800000 38827045 955859216 1373700096 0.3687863350 -0.0956884548 -0.0447265767 734 1311867194.9104089737 0.0835873187 0.0631642434 0.0879767612 0.0056624601 0.0054100000 38829805 955859216 1373700096 0.3689366281 -0.0952317938 -0.0445941761 735 1311867194.9451448917 0.0834298804 0.0631918157 0.0879767612 0.0056594328 0.0067700000 38832789 955859216 1373700096 0.3684001863 -0.0955663994 -0.0442359596 736 1311867194.9787399769 0.0811604336 0.0632162295 0.0879767612 0.0056578184 0.0068590000 38835717 955859216 1373700096 0.3704813421 -0.0963790342 -0.0435171314 737 1311867195.0132799149 0.0803122446 0.0632394263 0.0879767612 0.0056559275 0.0067520000 38838645 955859216 1373700096 0.3704075813 -0.0960300565 -0.0431633294 738 1311867195.0464940071 0.0792786852 0.0632611597 0.0879767612 0.0056532466 0.0045040000 38841517 955859216 1373700096 0.3709639013 -0.0974481553 -0.0427158140 739 1311867195.0781710148 0.0788284689 0.0632822251 0.0879767612 0.0056499977 0.0037890000 38844389 955859216 1373700096 0.3710004389 -0.0965575725 -0.0425717458 740 1311867195.1115310192 0.0788726062 0.0633032932 0.0879767612 0.0056464928 0.0086000000 38847261 955859216 1373700096 0.3702834845 -0.0963080898 -0.0424192175 741 1311867195.1458311081 0.0789958760 0.0633244708 0.0879767612 0.0056427780 0.0048180000 38850245 955859216 1373700096 0.3690711260 -0.0968348384 -0.0425964706 742 1311867195.1780319214 0.0783972889 0.0633447845 0.0879767612 0.0056405917 0.0038250000 38853117 955859216 1373700096 0.3690457642 -0.0959102735 -0.0424188934 743 1311867195.2114748955 0.0769170970 0.0633630514 0.0879767612 0.0056372699 0.0081590000 38855989 955859216 1373700096 0.3692013323 -0.0960200801 -0.0422205739 744 1311867195.2436800003 0.0764518976 0.0633806440 0.0879767612 0.0056355218 0.0053490000 38858917 955859216 1373700096 0.3689702749 -0.0968862548 -0.0421969928 745 1311867195.2780399323 0.0758495107 0.0633973807 0.0879767612 0.0056323652 0.0051250000 38861845 955859216 1373700096 0.3685795367 -0.0969567522 -0.0420227349 746 1311867195.3123180866 0.0754277706 0.0634135072 0.0879767612 0.0056289305 0.0053080000 38864773 955859216 1373700096 0.3681707084 -0.0969067067 -0.0419933200 747 1311867195.3425979614 0.0760367066 0.0634304058 0.0879767612 0.0056295143 0.0044390000 38867589 955859216 1373700096 0.3658179641 -0.0983189791 -0.0426471047 748 1311867195.3782711029 0.0756925195 0.0634467990 0.0879767612 0.0056272171 0.0082750000 38870573 955859216 1373700096 0.3651161790 -0.0977162272 -0.0427794755 749 1311867195.4119830132 0.0751504079 0.0634624246 0.0879767612 0.0056263426 0.0050190000 38873445 955859216 1373700096 0.3642477393 -0.0974878967 -0.0432079174 750 1311867195.4435520172 0.0754927024 0.0634784650 0.0879767612 0.0056240493 0.0054380000 38876373 955859216 1373700096 0.3617109358 -0.0979962721 -0.0440499298 751 1311867195.4788239002 0.0742733404 0.0634928390 0.0879767612 0.0056212009 0.0044360000 38879301 955859216 1373700096 0.3618695736 -0.0972004011 -0.0440178216 752 1311867195.5113179684 0.0738251656 0.0635065788 0.0879767612 0.0056177207 0.0075430000 38882173 955859216 1373700096 0.3610404432 -0.0972222537 -0.0440685898 753 1311867195.5439620018 0.0733568072 0.0635196601 0.0879767612 0.0056142115 0.0051750000 38885101 955859216 1373700096 0.3591815829 -0.0981563479 -0.0442551970 754 1311867195.5782160759 0.0721451119 0.0635310997 0.0879767612 0.0056118277 0.0040120000 38888029 955859216 1373700096 0.3593612611 -0.0978046060 -0.0439266972 755 1311867195.6119859219 0.0723100379 0.0635427274 0.0879767612 0.0056098051 0.0083130000 38890957 955859216 1373700096 0.3572680354 -0.0978227928 -0.0442299210 756 1311867195.6430909634 0.0725352019 0.0635546222 0.0879767612 0.0056063467 0.0050900000 38893773 955859216 1373700096 0.3546838164 -0.0982165039 -0.0448200926 757 1311867195.6779129505 0.0724518076 0.0635663754 0.0879767612 0.0056030048 0.0043610000 38896757 955859216 1373700096 0.3529774249 -0.0979895443 -0.0448427796 758 1311867195.7107300758 0.0725053996 0.0635781683 0.0879767612 0.0056030391 0.0060850000 38899573 955859216 1373700096 0.3506374061 -0.0980343372 -0.0448759161 759 1311867195.7458300591 0.0712967739 0.0635883378 0.0879767612 0.0056011948 0.0045170000 38902557 955859216 1373700096 0.3499303460 -0.0988470241 -0.0448368415 760 1311867195.7821879387 0.0709157288 0.0635979791 0.0879767612 0.0055976624 0.0083500000 38905485 955859216 1373700096 0.3487386703 -0.0985414907 -0.0445748195 761 1311867195.8100500107 0.0717071965 0.0636086351 0.0879767612 0.0055945610 0.0048060000 38908245 955859216 1373700096 0.3459057212 -0.0988648161 -0.0447877683 762 1311867195.8458549976 0.0704962611 0.0636176740 0.0879767612 0.0055913190 0.0049560000 38911229 955859216 1373700096 0.3452302516 -0.0990961790 -0.0448450148 763 1311867195.8778660297 0.0699542463 0.0636259788 0.0879767612 0.0055901023 0.0081040000 38914157 955859216 1373700096 0.3441202641 -0.0980075076 -0.0448118262 764 1311867195.9098269939 0.0700033233 0.0636343261 0.0879767612 0.0055874645 0.0053910000 38917029 955859216 1373700096 0.3424263895 -0.0979098752 -0.0448104031 765 1311867195.9458460808 0.0698297843 0.0636424247 0.0879767612 0.0055843850 0.0042310000 38919957 955859216 1373700096 0.3405074179 -0.0982855558 -0.0449174531 766 1311867195.9778430462 0.0700237229 0.0636507554 0.0879767612 0.0055823136 0.0079930000 38922885 955859216 1373700096 0.3389637470 -0.0973029211 -0.0447938442 767 1311867196.0100569725 0.0694212541 0.0636582789 0.0879767612 0.0055794339 0.0053300000 38925757 955859216 1373700096 0.3383040726 -0.0974574462 -0.0445602499 768 1311867196.0498790741 0.0685289726 0.0636646209 0.0879767612 0.0055770296 0.0043270000 38928853 955859216 1373700096 0.3375639617 -0.0979276970 -0.0447864756 769 1311867196.0793108940 0.0688747615 0.0636713961 0.0879767612 0.0055780216 0.0037300000 38931725 955859216 1373700096 0.3359364569 -0.0967712551 -0.0446618572 770 1311867196.1113979816 0.0687667429 0.0636780135 0.0879767612 0.0055751584 0.0038590000 38934485 955859216 1373700096 0.3342020214 -0.0971927941 -0.0447986126 771 1311867196.1473290920 0.0680138916 0.0636836372 0.0879767612 0.0055718113 0.0037100000 38937525 955859216 1373700096 0.3332742155 -0.0976682380 -0.0447788537 772 1311867196.1811769009 0.0677541867 0.0636889099 0.0879767612 0.0055720168 0.0038540000 38940453 955859216 1373700096 0.3319980800 -0.0969676897 -0.0446956493 773 1311867196.2114949226 0.0684593990 0.0636950813 0.0879767612 0.0055698180 0.0092090000 38943213 955859216 1373700096 0.3294482827 -0.0976201221 -0.0449671485 774 1311867196.2462599277 0.0684026629 0.0637011634 0.0879767612 0.0055668538 0.0071030000 38946197 955859216 1373700096 0.3277321160 -0.0976021066 -0.0451107994 775 1311867196.2800569534 0.0682600066 0.0637070458 0.0879767612 0.0055633892 0.0060880000 38949125 955859216 1373700096 0.3262426853 -0.0973377600 -0.0450209416 776 1311867196.3111600876 0.0675598159 0.0637120107 0.0879767612 0.0055600269 0.0044280000 38951941 955859216 1373700096 0.3251574039 -0.0978260115 -0.0451101810 777 1311867196.3484730721 0.0676987544 0.0637171417 0.0879767612 0.0055570590 0.0038350000 38954981 955859216 1373700096 0.3233044744 -0.0975093767 -0.0452923216 778 1311867196.3842670918 0.0673839003 0.0637218547 0.0879767612 0.0055540020 0.0075790000 38957909 955859216 1373700096 0.3220061064 -0.0968336090 -0.0449793376 779 1311867196.4107549191 0.0674291328 0.0637266138 0.0879767612 0.0055520309 0.0048080000 38960613 955859216 1373700096 0.3202738762 -0.0975138918 -0.0449806377 780 1311867196.4463150501 0.0671956390 0.0637310612 0.0879767612 0.0055512739 0.0066030000 38963597 955859216 1373700096 0.3190031648 -0.0970044732 -0.0449356437 781 1311867196.4798319340 0.0665800497 0.0637347091 0.0879767612 0.0055477849 0.0045590000 38966525 955859216 1373700096 0.3184366226 -0.0965010077 -0.0444860868 782 1311867196.5113470554 0.0668445304 0.0637386859 0.0879767612 0.0055446152 0.0090300000 38969341 955859216 1373700096 0.3158591688 -0.0968929604 -0.0447480343 783 1311867196.5468420982 0.0662038848 0.0637418343 0.0879767612 0.0055422226 0.0049430000 38972325 955859216 1373700096 0.3142571449 -0.0960620791 -0.0445234179 784 1311867196.5795550346 0.0658134446 0.0637444766 0.0879767612 0.0055406949 0.0041260000 38975253 955859216 1373700096 0.3138327003 -0.0956539586 -0.0440075584 785 1311867196.6108930111 0.0651315525 0.0637462436 0.0879767612 0.0055403474 0.0087400000 38978069 955859216 1373700096 0.3125709593 -0.0965202898 -0.0437352955 786 1311867196.6521809101 0.0649453476 0.0637477692 0.0879767612 0.0055440409 0.0056540000 38981221 955859216 1373700096 0.3101432025 -0.0954704285 -0.0438519120 787 1311867196.6805100441 0.0642733201 0.0637484370 0.0879767612 0.0055523472 0.0043720000 38983981 955859216 1373700096 0.3089118600 -0.0944877863 -0.0433517992 788 1311867196.7112100124 0.0637698397 0.0637484641 0.0879767612 0.0055492957 0.0037010000 38986797 955859216 1373700096 0.3080992401 -0.0950701013 -0.0427481458 789 1311867196.7464900017 0.0639578477 0.0637487295 0.0879767612 0.0055458125 0.0067640000 38989781 955859216 1373700096 0.3057189584 -0.0944717526 -0.0424475893 790 1311867196.7783749104 0.0633812845 0.0637482644 0.0879767612 0.0055424859 0.0059430000 38992709 955859216 1373700096 0.3043056130 -0.0944216996 -0.0420369469 791 1311867196.8109180927 0.0631460920 0.0637475031 0.0879767612 0.0055406280 0.0050620000 38995469 955859216 1373700096 0.3022391200 -0.0945591107 -0.0419431739 792 1311867196.8488750458 0.0629817396 0.0637465362 0.0879767612 0.0055385307 0.0040880000 38998565 955859216 1373700096 0.2999446392 -0.0944929644 -0.0418477841 793 1311867196.8821749687 0.0625025183 0.0637449675 0.0879767612 0.0055354155 0.0039850000 39001437 955859216 1373700096 0.2985689342 -0.0941101313 -0.0414971560 794 1311867196.9115700722 0.0626539290 0.0637435934 0.0879767612 0.0055328811 0.0038910000 39004197 955859216 1373700096 0.2961562574 -0.0948841646 -0.0415156633 795 1311867196.9482440948 0.0622103624 0.0637416648 0.0879767612 0.0055294677 0.0039410000 39007237 955859216 1373700096 0.2941922843 -0.0948645547 -0.0414560884 796 1311867196.9809880257 0.0617924109 0.0637392160 0.0879767612 0.0055271314 0.0038940000 39010165 955859216 1373700096 0.2927017808 -0.0952067599 -0.0412003882 797 1311867197.0154891014 0.0615424998 0.0637364597 0.0879767612 0.0055243729 0.0092900000 39013037 955859216 1373700096 0.2909698188 -0.0955934525 -0.0413902961 798 1311867197.0490679741 0.0611853078 0.0637332628 0.0879767612 0.0055220567 0.0063410000 39015965 955859216 1373700096 0.2891758680 -0.0955819190 -0.0415470675 799 1311867197.0806479454 0.0607438423 0.0637295214 0.0879767612 0.0055192547 0.0044450000 39018725 955859216 1373700096 0.2877782881 -0.0959596708 -0.0416175947 800 1311867197.1148109436 0.0606486723 0.0637256703 0.0879767612 0.0055160788 0.0038930000 39021709 955859216 1373700096 0.2851985395 -0.0962840393 -0.0421411134 801 1311867197.1468429565 0.0606374256 0.0637218148 0.0879767612 0.0055135661 0.0036870000 39024581 955859216 1373700096 0.2832379043 -0.0956678391 -0.0422423482 802 1311867197.1792430878 0.0606740043 0.0637180145 0.0879767612 0.0055109968 0.0093110000 39027509 955859216 1373700096 0.2806770802 -0.0958656594 -0.0425598510 803 1311867197.2143619061 0.0605656803 0.0637140888 0.0879767612 0.0055100565 0.0051350000 39030437 955859216 1373700096 0.2784505188 -0.0955652595 -0.0426320955 804 1311867197.2459290028 0.0604516789 0.0637100311 0.0879767612 0.0055068156 0.0057170000 39033309 955859216 1373700096 0.2768945694 -0.0951641202 -0.0424807258 805 1311867197.2799959183 0.0596358925 0.0637049701 0.0879767612 0.0055051540 0.0058680000 39036293 955859216 1373700096 0.2757958770 -0.0955205783 -0.0422481969 806 1311867197.3157260418 0.0594462678 0.0636996863 0.0879767612 0.0055022405 0.0043900000 39039165 955859216 1373700096 0.2735916078 -0.0951661319 -0.0423922725 807 1311867197.3468708992 0.0588746779 0.0636937074 0.0879767612 0.0054999324 0.0068360000 39042037 955859216 1373700096 0.2723664045 -0.0951909870 -0.0422092564 808 1311867197.3784019947 0.0589729361 0.0636878648 0.0879767612 0.0054982815 0.0050250000 39044853 955859216 1373700096 0.2698880434 -0.0952306241 -0.0426758230 809 1311867197.4155099392 0.0590142347 0.0636820878 0.0879767612 0.0054953435 0.0041180000 39047837 955859216 1373700096 0.2675243020 -0.0951863006 -0.0430749655 810 1311867197.4478878975 0.0587045401 0.0636759427 0.0879767612 0.0054921319 0.0039020000 39050709 955859216 1373700096 0.2665462196 -0.0950950682 -0.0432398282 811 1311867197.4793179035 0.0584341027 0.0636694793 0.0879767612 0.0054894288 0.0039160000 39053469 955859216 1373700096 0.2644520998 -0.0955233201 -0.0440816283 812 1311867197.5150759220 0.0586078353 0.0636632457 0.0879767612 0.0054877068 0.0093670000 39056453 955859216 1373700096 0.2620603740 -0.0949088112 -0.0449360721 813 1311867197.5469260216 0.0584131144 0.0636567880 0.0879767612 0.0054844487 0.0059280000 39059269 955859216 1373700096 0.2608775496 -0.0944300890 -0.0452835448 814 1311867197.5802750587 0.0583974272 0.0636503268 0.0879767612 0.0054830506 0.0044800000 39062197 955859216 1373700096 0.2588070929 -0.0952923149 -0.0461329892 815 1311867197.6152749062 0.0599074997 0.0636457344 0.0879767612 0.0054844910 0.0039030000 39065125 955859216 1373700096 0.2543777227 -0.0941667780 -0.0475239679 816 1311867197.6470439434 0.0593923703 0.0636405220 0.0879767612 0.0054827359 0.0086760000 39067997 955859216 1373700096 0.2535512745 -0.0933572575 -0.0478359014 817 1311867197.6800849438 0.0596833602 0.0636356784 0.0879767612 0.0054818623 0.0049770000 39070925 955859216 1373700096 0.2505382895 -0.0940336064 -0.0488779955 818 1311867197.7143290043 0.0596445799 0.0636307993 0.0879767612 0.0054820543 0.0041070000 39073853 955859216 1373700096 0.2490442395 -0.0925458446 -0.0494812243 819 1311867197.7463419437 0.0596184321 0.0636259002 0.0879767612 0.0054803736 0.0065680000 39076725 955859216 1373700096 0.2471816987 -0.0921933949 -0.0501708202 820 1311867197.7793009281 0.0600679368 0.0636215613 0.0879767612 0.0054779446 0.0045930000 39079653 955859216 1373700096 0.2439584732 -0.0925227031 -0.0514088087 821 1311867197.8146750927 0.0597523265 0.0636168484 0.0879767612 0.0054790977 0.0089180000 39082637 955859216 1373700096 0.2432384938 -0.0911280438 -0.0519928336 822 1311867197.8467919827 0.0593074784 0.0636116059 0.0879767612 0.0054772632 0.0050680000 39085453 955859216 1373700096 0.2422155440 -0.0915855765 -0.0528424047 823 1311867197.8802978992 0.0594794974 0.0636065851 0.0879767612 0.0054749820 0.0041780000 39088325 955859216 1373700096 0.2394206822 -0.0914693549 -0.0539983474 824 1311867197.9148609638 0.0590849146 0.0636010976 0.0879767612 0.0054762564 0.0037370000 39091309 955859216 1373700096 0.2389141470 -0.0904107615 -0.0544118918 825 1311867197.9470140934 0.0586100891 0.0635950479 0.0879767612 0.0054800862 0.0093920000 39094181 955859216 1373700096 0.2371763140 -0.0907864645 -0.0551088899 826 1311867197.9812700748 0.0589747205 0.0635894543 0.0879767612 0.0054771300 0.0055280000 39097109 955859216 1373700096 0.2345944196 -0.0902294070 -0.0560012311 827 1311867198.0145471096 0.0583602637 0.0635831312 0.0879767612 0.0054747930 0.0043270000 39100093 955859216 1373700096 0.2340895683 -0.0893082544 -0.0562579744 828 1311867198.0463368893 0.0580172017 0.0635764091 0.0879767612 0.0054720051 0.0058700000 39102909 955859216 1373700096 0.2324792445 -0.0892677903 -0.0569876768 829 1311867198.0787069798 0.0580193922 0.0635697058 0.0879767612 0.0054708423 0.0044030000 39105837 955859216 1373700096 0.2309876084 -0.0888579786 -0.0574756302 830 1311867198.1143770218 0.0570282042 0.0635618245 0.0879767612 0.0054678602 0.0089720000 39108765 955859216 1373700096 0.2305528820 -0.0882407427 -0.0578332357 831 1311867198.1463611126 0.0572019592 0.0635541712 0.0879767612 0.0054646390 0.0050470000 39111637 955859216 1373700096 0.2279660404 -0.0879727080 -0.0587822907 832 1311867198.1822519302 0.0565856844 0.0635457956 0.0879767612 0.0054615315 0.0040450000 39114621 955859216 1373700096 0.2267171144 -0.0873674527 -0.0594941862 833 1311867198.2144989967 0.0569310524 0.0635378548 0.0879767612 0.0054644827 0.0088010000 39117493 955859216 1373700096 0.2245000899 -0.0868329331 -0.0601460449 834 1311867198.2464120388 0.0562859289 0.0635291594 0.0879767612 0.0054621502 0.0049830000 39120365 955859216 1373700096 0.2233822197 -0.0869269297 -0.0610839948 835 1311867198.2821578979 0.0557932742 0.0635198949 0.0879767612 0.0054594091 0.0041120000 39123349 955859216 1373700096 0.2220732868 -0.0862755552 -0.0616059564 836 1311867198.3159120083 0.0551964827 0.0635099386 0.0879767612 0.0054585889 0.0085700000 39126221 955859216 1373700096 0.2206393778 -0.0857943445 -0.0626119673 837 1311867198.3481218815 0.0546895973 0.0634994006 0.0879767612 0.0054557828 0.0049010000 39129093 955859216 1373700096 0.2192063630 -0.0859499052 -0.0634649992 838 1311867198.3828320503 0.0544965118 0.0634886573 0.0879767612 0.0054583499 0.0062890000 39132077 955859216 1373700096 0.2165780067 -0.0849459246 -0.0644681081 839 1311867198.4242680073 0.0536304675 0.0634769074 0.0879767612 0.0054640855 0.0048200000 39135005 955859216 1373700096 0.2149608582 -0.0844019279 -0.0654919446 840 1311867198.4497859478 0.0539193191 0.0634655293 0.0879767612 0.0054617112 0.0084860000 39137597 955859216 1373700096 0.2121794969 -0.0853099972 -0.0667559654 841 1311867198.4856219292 0.0544129461 0.0634547652 0.0879767612 0.0054672353 0.0056020000 39140469 955859216 1373700096 0.2089125514 -0.0842087567 -0.0679779127 842 1311867198.5190339088 0.0542401224 0.0634438215 0.0879767612 0.0054646460 0.0062050000 39143397 955859216 1373700096 0.2065326869 -0.0832957998 -0.0690263733 843 1311867198.5499279499 0.0536007881 0.0634321453 0.0879767612 0.0054647369 0.0044070000 39146269 955859216 1373700096 0.2043576092 -0.0836660713 -0.0702794492 844 1311867198.5824239254 0.0531521738 0.0634199652 0.0879767612 0.0054620404 0.0083970000 39149141 955859216 1373700096 0.2028178126 -0.0822866261 -0.0710434392 845 1311867198.6147489548 0.0526627265 0.0634072347 0.0879767612 0.0054620865 0.0059270000 39152013 955859216 1373700096 0.2008091211 -0.0820138380 -0.0719853938 846 1311867198.6482009888 0.0522059910 0.0633939945 0.0879767612 0.0054617365 0.0043800000 39154885 955859216 1373700096 0.1986851841 -0.0818220079 -0.0729143992 847 1311867198.6827540398 0.0524730049 0.0633811008 0.0879767612 0.0054599667 0.0065790000 39157813 955859216 1373700096 0.1953100860 -0.0806854293 -0.0741114914 848 1311867198.7146520615 0.0527647920 0.0633685815 0.0879767612 0.0054568149 0.0048710000 39160629 955859216 1373700096 0.1932485849 -0.0798607767 -0.0746349692 849 1311867198.7467699051 0.0529939272 0.0633563617 0.0879767612 0.0054549645 0.0043660000 39163445 955859216 1373700096 0.1910932809 -0.0796131939 -0.0754473284 850 1311867198.7842700481 0.0526015162 0.0633437089 0.0879767612 0.0054522582 0.0090660000 39166429 955859216 1373700096 0.1897515059 -0.0788185820 -0.0759496242 851 1311867198.8149418831 0.0532303788 0.0633318249 0.0879767612 0.0054492213 0.0051420000 39169245 955859216 1373700096 0.1858063340 -0.0783307031 -0.0772769973 852 1311867198.8464009762 0.0533553623 0.0633201154 0.0879767612 0.0054471085 0.0040800000 39172117 955859216 1373700096 0.1835575849 -0.0775138140 -0.0780991390 853 1311867198.8845369816 0.0533161312 0.0633083874 0.0879767612 0.0054449720 0.0088310000 39175045 955859216 1373700096 0.1825862378 -0.0768339112 -0.0786508620 854 1311867198.9147930145 0.0538564287 0.0632973195 0.0879767612 0.0054418046 0.0050440000 39177861 955859216 1373700096 0.1798583418 -0.0762248412 -0.0796810538 855 1311867198.9465179443 0.0539081059 0.0632863380 0.0879767612 0.0054387014 0.0040900000 39180733 955859216 1373700096 0.1781575233 -0.0751148611 -0.0805772021 856 1311867198.9839329720 0.0539611317 0.0632754441 0.0879767612 0.0054359808 0.0085680000 39183829 955859216 1373700096 0.1759950370 -0.0741979927 -0.0815548450 857 1311867199.0148730278 0.0544646308 0.0632651631 0.0879767612 0.0054376379 0.0049710000 39186645 955859216 1373700096 0.1733229011 -0.0730709657 -0.0826389715 858 1311867199.0468010902 0.0554742478 0.0632560828 0.0879767612 0.0054375777 0.0054520000 39189517 955859216 1373700096 0.1715232283 -0.0722546056 -0.0835995153 859 1311867199.0849320889 0.0556951016 0.0632472807 0.0879767612 0.0054374210 0.0045990000 39192613 955859216 1373700096 0.1704185307 -0.0710659921 -0.0843594074 860 1311867199.1149818897 0.0561002381 0.0632389702 0.0879767612 0.0054353637 0.0088980000 39195373 955859216 1373700096 0.1684146076 -0.0704955235 -0.0856626779 861 1311867199.1465420723 0.0570679158 0.0632318029 0.0879767612 0.0054329789 0.0051510000 39198245 955859216 1373700096 0.1658421755 -0.0692986622 -0.0870612934 862 1311867199.1823658943 0.0577415600 0.0632254337 0.0879767612 0.0054316375 0.0065230000 39201229 955859216 1373700096 0.1638169587 -0.0678928792 -0.0882616639 863 1311867199.2146680355 0.0585865378 0.0632200583 0.0879767612 0.0054287996 0.0056850000 39204157 955859216 1373700096 0.1611894965 -0.0673278943 -0.0897202492 864 1311867199.2467749119 0.0588978119 0.0632150557 0.0879767612 0.0054259178 0.0056740000 39206973 955859216 1373700096 0.1595675647 -0.0663985461 -0.0907597095 865 1311867199.2833590508 0.0592061207 0.0632104211 0.0879767612 0.0054228068 0.0061000000 39210013 955859216 1373700096 0.1577825695 -0.0654892921 -0.0918298885 866 1311867199.3159129620 0.0595449060 0.0632061884 0.0879767612 0.0054230761 0.0056350000 39212773 955859216 1373700096 0.1559747756 -0.0653042495 -0.0931906998 867 1311867199.3465209007 0.0595199876 0.0632019368 0.0879767612 0.0054199929 0.0042960000 39215589 955859216 1373700096 0.1547408402 -0.0648264661 -0.0944279805 868 1311867199.3829050064 0.0593717508 0.0631975241 0.0879767612 0.0054173204 0.0040420000 39218629 955859216 1373700096 0.1532146633 -0.0641283393 -0.0956157222 869 1311867199.4147589207 0.0593904592 0.0631931431 0.0879767612 0.0054142453 0.0040060000 39221445 955859216 1373700096 0.1511618346 -0.0642376766 -0.0968990177 870 1311867199.4512910843 0.0591358840 0.0631884796 0.0879767612 0.0054114851 0.0096860000 39224485 955859216 1373700096 0.1492086053 -0.0634525642 -0.0982783586 871 1311867199.4837360382 0.0588044859 0.0631834463 0.0879767612 0.0054098665 0.0066700000 39227357 955859216 1373700096 0.1477714926 -0.0635607243 -0.0991362110 872 1311867199.5150198936 0.0587755106 0.0631783914 0.0879767612 0.0054068902 0.0046470000 39230229 955859216 1373700096 0.1458141059 -0.0635032281 -0.1000647694 873 1311867199.5544059277 0.0583139248 0.0631728192 0.0879767612 0.0054055357 0.0059260000 39233325 955859216 1373700096 0.1441109031 -0.0628205165 -0.1009311527 874 1311867199.5835030079 0.0581837073 0.0631671109 0.0879767612 0.0054025729 0.0045020000 39236141 955859216 1373700096 0.1416638047 -0.0622639768 -0.1018319130 875 1311867199.6158308983 0.0577232316 0.0631608893 0.0879767612 0.0053998102 0.0040970000 39238901 955859216 1373700096 0.1396212429 -0.0617608652 -0.1024150625 876 1311867199.6538460255 0.0567031018 0.0631535174 0.0879767612 0.0053989499 0.0098400000 39241997 955859216 1373700096 0.1385198534 -0.0618399084 -0.1027989835 877 1311867199.6824479103 0.0567661822 0.0631462342 0.0879767612 0.0053961553 0.0054980000 39244757 955859216 1373700096 0.1361192167 -0.0614044406 -0.1034645364 878 1311867199.7146759033 0.0558376946 0.0631379102 0.0879767612 0.0053938734 0.0043230000 39247685 955859216 1373700096 0.1348724812 -0.0609706268 -0.1040370539 879 1311867199.7511539459 0.0556648374 0.0631294084 0.0879767612 0.0053924423 0.0038750000 39250613 955859216 1373700096 0.1325760335 -0.0605416186 -0.1043557748 880 1311867199.7826020718 0.0554638691 0.0631206975 0.0879767612 0.0053901904 0.0089850000 39253485 955859216 1373700096 0.1303357780 -0.0605738573 -0.1049797162 881 1311867199.8150150776 0.0549573079 0.0631114315 0.0879767612 0.0053944471 0.0052070000 39256357 955859216 1373700096 0.1282659173 -0.0604822896 -0.1055159122 882 1311867199.8519051075 0.0544818826 0.0631016474 0.0879767612 0.0053914918 0.0043030000 39259341 955859216 1373700096 0.1267293394 -0.0597256050 -0.1059207618 883 1311867199.8839609623 0.0542294234 0.0630915996 0.0879767612 0.0053916545 0.0038930000 39262269 955859216 1373700096 0.1245170832 -0.0602356382 -0.1063498035 884 1311867199.9148159027 0.0539806187 0.0630812930 0.0879767612 0.0053898060 0.0095510000 39265141 955859216 1373700096 0.1222373843 -0.0603740439 -0.1068899259 885 1311867199.9520709515 0.0536826067 0.0630706731 0.0879767612 0.0053872057 0.0060270000 39268125 955859216 1373700096 0.1208390817 -0.0598355606 -0.1071578041 886 1311867199.9828410149 0.0529916845 0.0630592972 0.0879767612 0.0053852007 0.0045970000 39270941 955859216 1373700096 0.1197375581 -0.0602830239 -0.1074372455 887 1311867200.0144031048 0.0527595803 0.0630476854 0.0879767612 0.0053825007 0.0061070000 39273813 955859216 1373700096 0.1174370125 -0.0598266609 -0.1078818366 888 1311867200.0539638996 0.0523565598 0.0630356458 0.0879767612 0.0053807457 0.0046750000 39276909 955859216 1373700096 0.1158000305 -0.0587023757 -0.1080018133 889 1311867200.0830330849 0.0518695451 0.0630230855 0.0879767612 0.0053780402 0.0067590000 39279669 955859216 1373700096 0.1145817116 -0.0593058430 -0.1081178039 890 1311867200.1174468994 0.0514698774 0.0630101044 0.0879767612 0.0053777932 0.0060440000 39282597 955859216 1373700096 0.1123144031 -0.0589226186 -0.1082093790 891 1311867200.1517000198 0.0510631688 0.0629966959 0.0879767612 0.0053766038 0.0045960000 39285525 955859216 1373700096 0.1106780544 -0.0584399775 -0.1080842465 892 1311867200.1853220463 0.0512469634 0.0629835236 0.0879767612 0.0053759726 0.0040380000 39288509 955859216 1373700096 0.1083357632 -0.0588571988 -0.1081264541 893 1311867200.2179059982 0.0505143218 0.0629695603 0.0879767612 0.0053747329 0.0038430000 39291381 955859216 1373700096 0.1080290005 -0.0580086038 -0.1078419015 894 1311867200.2522649765 0.0499966592 0.0629550492 0.0879767612 0.0053719535 0.0098950000 39294309 955859216 1373700096 0.1064787209 -0.0580948070 -0.1075450629 895 1311867200.2825429440 0.0497128926 0.0629402535 0.0879767612 0.0053696918 0.0065540000 39297125 955859216 1373700096 0.1042962000 -0.0579693168 -0.1073372066 896 1311867200.3148880005 0.0494012460 0.0629251430 0.0879767612 0.0053668160 0.0046400000 39300053 955859216 1373700096 0.1034490764 -0.0573041439 -0.1066906005 897 1311867200.3514990807 0.0490530878 0.0629096781 0.0879767612 0.0053659591 0.0040300000 39302981 955859216 1373700096 0.1013689041 -0.0579799749 -0.1064521596 898 1311867200.3837759495 0.0489974059 0.0628941856 0.0879767612 0.0053743187 0.0065920000 39305909 955859216 1373700096 0.0992190167 -0.0574934185 -0.1060316265 899 1311867200.4162800312 0.0488001928 0.0628785082 0.0879767612 0.0053719864 0.0046450000 39308725 955859216 1373700096 0.0981463119 -0.0574592538 -0.1055404842 900 1311867200.4522490501 0.0484223925 0.0628624458 0.0879767612 0.0053702191 0.0040170000 39311709 955859216 1373700096 0.0951320082 -0.0578714758 -0.1055928469 901 1311867200.4850699902 0.0481122546 0.0628460749 0.0879767612 0.0053710789 0.0093510000 39314581 955859216 1373700096 0.0925564170 -0.0577257946 -0.1053196192 902 1311867200.5143918991 0.0479137525 0.0628295202 0.0879767612 0.0053706758 0.0052720000 39317453 955859216 1373700096 0.0907830149 -0.0582219698 -0.1047514006 903 1311867200.5505030155 0.0474832170 0.0628125254 0.0879767612 0.0053754363 0.0046600000 39320437 955859216 1373700096 0.0872213915 -0.0580292493 -0.1044508889 904 1311867200.5832219124 0.0477674790 0.0627958827 0.0879767612 0.0053770128 0.0061160000 39323309 955859216 1373700096 0.0850537568 -0.0580071509 -0.1039142907 905 1311867200.6145610809 0.0475548767 0.0627790418 0.0879767612 0.0053758787 0.0049570000 39326125 955859216 1373700096 0.0824069157 -0.0582457222 -0.1035443395 906 1311867200.6504778862 0.0472178608 0.0627618661 0.0879767612 0.0053742799 0.0042470000 39329109 955859216 1373700096 0.0794948414 -0.0580677092 -0.1031256393 907 1311867200.6851279736 0.0469510071 0.0627444341 0.0879767612 0.0053716046 0.0094390000 39332093 955859216 1373700096 0.0768705457 -0.0578705929 -0.1028118581 908 1311867200.7189719677 0.0468060263 0.0627268807 0.0879767612 0.0053705647 0.0056180000 39335021 955859216 1373700096 0.0734687075 -0.0578617007 -0.1026381552 909 1311867200.7503669262 0.0465305075 0.0627090629 0.0879767612 0.0053694121 0.0044520000 39337837 955859216 1373700096 0.0711532459 -0.0576809682 -0.1022288799 910 1311867200.7832930088 0.0463837460 0.0626911230 0.0879767612 0.0053743489 0.0058440000 39340765 955859216 1373700096 0.0686701164 -0.0575161986 -0.1018814445 911 1311867200.8181068897 0.0458666310 0.0626726549 0.0879767612 0.0053734058 0.0073800000 39343693 955859216 1373700096 0.0657252073 -0.0578965880 -0.1015243232 912 1311867200.8501501083 0.0458791144 0.0626542409 0.0879767612 0.0053705291 0.0049610000 39346509 955859216 1373700096 0.0637734309 -0.0573709793 -0.1010060459 913 1311867200.8845369816 0.0462375432 0.0626362599 0.0879767612 0.0053711538 0.0042240000 39349549 955859216 1373700096 0.0604727268 -0.0573477931 -0.1004244089 914 1311867200.9194929600 0.0467563868 0.0626188858 0.0879767612 0.0053724202 0.0089560000 39352477 955859216 1373700096 0.0573886707 -0.0577068999 -0.0999379158 915 1311867200.9512679577 0.0463464372 0.0626011017 0.0879767612 0.0053723550 0.0059560000 39355293 955859216 1373700096 0.0552302636 -0.0579939038 -0.0995891467 916 1311867200.9856009483 0.0470191054 0.0625840908 0.0879767612 0.0053773084 0.0045970000 39358277 955859216 1373700096 0.0529270694 -0.0582601354 -0.0995674133 917 1311867201.0184400082 0.0472434647 0.0625673617 0.0879767612 0.0053746881 0.0059440000 39361149 955859216 1373700096 0.0509825274 -0.0585479513 -0.0995643511 918 1311867201.0555179119 0.0472491346 0.0625506751 0.0879767612 0.0053725103 0.0074540000 39364189 955859216 1373700096 0.0494541489 -0.0585090183 -0.0997263044 919 1311867201.0825428963 0.0475419983 0.0625343436 0.0879767612 0.0053714966 0.0049780000 39366893 955859216 1373700096 0.0475773551 -0.0589073785 -0.0998083875 920 1311867201.1193449497 0.0479139499 0.0625184519 0.0879767612 0.0053694430 0.0041940000 39369933 955859216 1373700096 0.0462046564 -0.0585980825 -0.0997036099 921 1311867201.1506710052 0.0482325293 0.0625029406 0.0879767612 0.0053667568 0.0089870000 39372693 955859216 1373700096 0.0446715057 -0.0583606064 -0.0997818261 922 1311867201.1830160618 0.0481495932 0.0624873729 0.0879767612 0.0053648968 0.0051080000 39375565 955859216 1373700096 0.0435364693 -0.0585909523 -0.0998933762 923 1311867201.2196528912 0.0480724871 0.0624717555 0.0879767612 0.0053652831 0.0042700000 39378493 955859216 1373700096 0.0421319939 -0.0585058741 -0.0999900922 924 1311867201.2503149509 0.0480853170 0.0624561858 0.0879767612 0.0053623905 0.0089260000 39381365 955859216 1373700096 0.0410663784 -0.0582428649 -0.0999110490 925 1311867201.2824099064 0.0479907691 0.0624405475 0.0879767612 0.0053601878 0.0059150000 39384237 955859216 1373700096 0.0393880531 -0.0581354126 -0.1000966057 926 1311867201.3180539608 0.0479060449 0.0624248515 0.0879767612 0.0053588656 0.0045530000 39387221 955859216 1373700096 0.0373633578 -0.0585882664 -0.1003422290 927 1311867201.3522200584 0.0477745309 0.0624090475 0.0879767612 0.0053575071 0.0059870000 39390149 955859216 1373700096 0.0355268493 -0.0577084459 -0.1007334366 928 1311867201.3842790127 0.0477236174 0.0623932227 0.0879767612 0.0053574331 0.0050420000 39393021 955859216 1373700096 0.0336297713 -0.0567028075 -0.1006987318 929 1311867201.4198760986 0.0467835553 0.0623764200 0.0879767612 0.0053768701 0.0044080000 39395893 955859216 1373700096 0.0308932532 -0.0572364219 -0.1012534946 930 1311867201.4558579922 0.0466239229 0.0623594818 0.0879767612 0.0053786421 0.0041040000 39398765 955859216 1373700096 0.0280773863 -0.0562681742 -0.1015048027 931 1311867201.4853110313 0.0467722341 0.0623427393 0.0879767612 0.0053773889 0.0101840000 39401581 955859216 1373700096 0.0251077730 -0.0548503771 -0.1015307680 932 1311867201.5198690891 0.0463112369 0.0623255382 0.0879767612 0.0053761220 0.0066430000 39404565 955859216 1373700096 0.0224531982 -0.0546934456 -0.1016907766 933 1311867201.5527739525 0.0458216928 0.0623078492 0.0879767612 0.0053767399 0.0051190000 39407381 955859216 1373700096 0.0204728972 -0.0545945615 -0.1018394604 934 1311867201.5840220451 0.0458147973 0.0622901906 0.0879767612 0.0053739046 0.0042150000 39410253 955859216 1373700096 0.0185855888 -0.0542068258 -0.1020294949 935 1311867201.6197049618 0.0458839610 0.0622726439 0.0879767612 0.0053717855 0.0065320000 39413237 955859216 1373700096 0.0163995810 -0.0539238118 -0.1023552343 936 1311867201.6515579224 0.0454306267 0.0622546503 0.0879767612 0.0053715604 0.0048100000 39416053 955859216 1373700096 0.0153481504 -0.0540462993 -0.1026285961 937 1311867201.6839449406 0.0453343689 0.0622365923 0.0879767612 0.0053688473 0.0071170000 39418981 955859216 1373700096 0.0129269902 -0.0534552224 -0.1030949801 938 1311867201.7189009190 0.0452589504 0.0622184925 0.0879767612 0.0053665517 0.0048830000 39421965 955859216 1373700096 0.0123570776 -0.0523962080 -0.1032733321 939 1311867201.7507290840 0.0450406857 0.0622001988 0.0879767612 0.0053642982 0.0081840000 39424837 955859216 1373700096 0.0100392550 -0.0523075126 -0.1036385372 940 1311867201.7858049870 0.0443108492 0.0621811676 0.0879767612 0.0053712823 0.0050520000 39427709 955859216 1373700096 0.0085238647 -0.0518468991 -0.1038742587 941 1311867201.8190178871 0.0446696319 0.0621625581 0.0879767612 0.0053761948 0.0043420000 39430693 955859216 1373700096 0.0073131495 -0.0503224209 -0.1038645357 942 1311867201.8505740166 0.0444504581 0.0621437554 0.0879767612 0.0053766928 0.0039730000 39433509 955859216 1373700096 0.0056252452 -0.0502928905 -0.1041680053 943 1311867201.8862850666 0.0443018824 0.0621248351 0.0879767612 0.0053740527 0.0039870000 39436437 955859216 1373700096 0.0050193705 -0.0501113720 -0.1044385061 944 1311867201.9195730686 0.0445779637 0.0621062473 0.0879767612 0.0053752154 0.0039540000 39439421 955859216 1373700096 0.0036120983 -0.0493457131 -0.1046629101 945 1311867201.9516520500 0.0443849936 0.0620874946 0.0879767612 0.0053732073 0.0039900000 39442181 955859216 1373700096 0.0026670450 -0.0494075418 -0.1052155048 946 1311867201.9894599915 0.0440960974 0.0620684762 0.0879767612 0.0053705464 0.0039890000 39445277 955859216 1373700096 0.0022721086 -0.0493925437 -0.1058354229 947 1311867202.0184879303 0.0440093838 0.0620494065 0.0879767612 0.0053678085 0.0039740000 39448037 955859216 1373700096 0.0010873635 -0.0489144772 -0.1064082012 948 1311867202.0507359505 0.0438756794 0.0620302359 0.0879767612 0.0053653819 0.0039760000 39450909 955859216 1373700096 0.0007557350 -0.0483630821 -0.1069687009 949 1311867202.0866351128 0.0439292155 0.0620111621 0.0879767612 0.0053628805 0.0040330000 39453893 955859216 1373700096 -0.0011081424 -0.0481226072 -0.1074416786 950 1311867202.1185920238 0.0434906334 0.0619916668 0.0879767612 0.0053613163 0.0040010000 39456765 955859216 1373700096 -0.0015027835 -0.0476066358 -0.1077423543 951 1311867202.1516621113 0.0436063111 0.0619723341 0.0879767612 0.0053593288 0.0103090000 39459693 955859216 1373700096 -0.0024384542 -0.0468067937 -0.1077603772 952 1311867202.1866259575 0.0434309505 0.0619528579 0.0879767612 0.0053565419 0.0073270000 39462621 955859216 1373700096 -0.0030284745 -0.0465687439 -0.1078335270 953 1311867202.2191269398 0.0431418233 0.0619331191 0.0879767612 0.0053538261 0.0050220000 39465493 955859216 1373700096 -0.0039468501 -0.0465786681 -0.1080435887 954 1311867202.2513220310 0.0428988747 0.0619131671 0.0879767612 0.0053515401 0.0042560000 39468309 955859216 1373700096 -0.0048363968 -0.0459187999 -0.1080050766 955 1311867202.2868280411 0.0429454297 0.0618933056 0.0879767612 0.0053508952 0.0040410000 39471293 955859216 1373700096 -0.0061644837 -0.0449291989 -0.1078724712 956 1311867202.3199880123 0.0428757109 0.0618734127 0.0879767612 0.0053504415 0.0039220000 39474165 955859216 1373700096 -0.0073265955 -0.0455898680 -0.1081048474 957 1311867202.3523900509 0.0426408090 0.0618533159 0.0879767612 0.0053480300 0.0039320000 39477037 955859216 1373700096 -0.0090225134 -0.0452310219 -0.1083340198 958 1311867202.3883628845 0.0423167236 0.0618329228 0.0879767612 0.0053453414 0.0103660000 39480021 955859216 1373700096 -0.0100544551 -0.0445295088 -0.1084093377 959 1311867202.4196391106 0.0425200239 0.0618127843 0.0879767612 0.0053443949 0.0062460000 39482893 955859216 1373700096 -0.0110815614 -0.0445305705 -0.1084390804 960 1311867202.4529430866 0.0427724160 0.0617929505 0.0879767612 0.0053421130 0.0067960000 39485765 955859216 1373700096 -0.0116739133 -0.0447012782 -0.1083837152 961 1311867202.4875710011 0.0432909988 0.0617736977 0.0879767612 0.0053423697 0.0048540000 39488693 955859216 1373700096 -0.0132110482 -0.0441076197 -0.1082093269 962 1311867202.5206449032 0.0432809740 0.0617544745 0.0879767612 0.0053584228 0.0042220000 39491565 955859216 1373700096 -0.0144157195 -0.0435247421 -0.1084425971 963 1311867202.5508940220 0.0435950868 0.0617356174 0.0879767612 0.0053557669 0.0066920000 39494381 955859216 1373700096 -0.0153649701 -0.0437315553 -0.1083110049 964 1311867202.5864949226 0.0440808050 0.0617173033 0.0879767612 0.0053675950 0.0048240000 39497421 955859216 1373700096 -0.0164188463 -0.0438793749 -0.1085733399 965 1311867202.6185030937 0.0441565700 0.0616991056 0.0879767612 0.0053714312 0.0063520000 39500293 955859216 1373700096 -0.0183338076 -0.0436442122 -0.1091797203 966 1311867202.6514449120 0.0439455099 0.0616807272 0.0879767612 0.0053756367 0.0064950000 39503165 955859216 1373700096 -0.0209830552 -0.0436145663 -0.1099366248 967 1311867202.6866559982 0.0437730104 0.0616622083 0.0879767612 0.0053733253 0.0068990000 39506149 955859216 1373700096 -0.0219554380 -0.0431783423 -0.1106519401 968 1311867202.7185359001 0.0438103378 0.0616437663 0.0879767612 0.0053709855 0.0049240000 39509021 955859216 1373700096 -0.0235067233 -0.0438766479 -0.1116399169 969 1311867202.7507350445 0.0437818728 0.0616253330 0.0879767612 0.0053689795 0.0063250000 39511893 955859216 1373700096 -0.0250789672 -0.0445256606 -0.1127482578 970 1311867202.7897169590 0.0438835435 0.0616070425 0.0879767612 0.0053665340 0.0064340000 39514989 955859216 1373700096 -0.0263331328 -0.0439820848 -0.1136557683 971 1311867202.8190000057 0.0435113423 0.0615884063 0.0879767612 0.0053648740 0.0047870000 39517805 955859216 1373700096 -0.0278772600 -0.0443189107 -0.1145287305 972 1311867202.8527579308 0.0427573882 0.0615690329 0.0879767612 0.0053621494 0.0069990000 39520677 955859216 1373700096 -0.0292189717 -0.0446918085 -0.1153127402 973 1311867202.8873219490 0.0421206616 0.0615490448 0.0879767612 0.0053611657 0.0048670000 39523605 955859216 1373700096 -0.0297150556 -0.0433303006 -0.1158691421 974 1311867202.9199879169 0.0421554372 0.0615291335 0.0879767612 0.0053592592 0.0044000000 39526477 955859216 1373700096 -0.0299520250 -0.0425066724 -0.1157724038 975 1311867202.9525690079 0.0423097424 0.0615094213 0.0879767612 0.0053610471 0.0101100000 39529405 955859216 1373700096 -0.0300511047 -0.0428401418 -0.1157122403 976 1311867202.9868710041 0.0423797630 0.0614898213 0.0879767612 0.0053633897 0.0062900000 39532333 955859216 1373700096 -0.0304622538 -0.0426476784 -0.1152442247 977 1311867203.0202019215 0.0423128605 0.0614701929 0.0879767612 0.0053606625 0.0046990000 39535205 955859216 1373700096 -0.0301551390 -0.0423361398 -0.1149561405 978 1311867203.0560851097 0.0424828716 0.0614507784 0.0879767612 0.0053622316 0.0041180000 39538189 955859216 1373700096 -0.0295736548 -0.0440507084 -0.1146021113 979 1311867203.0865778923 0.0431335233 0.0614320682 0.0879767612 0.0053608361 0.0097210000 39541005 955859216 1373700096 -0.0297990683 -0.0446786210 -0.1141644716 980 1311867203.1189930439 0.0434487686 0.0614137179 0.0879767612 0.0053637234 0.0053830000 39543877 955859216 1373700096 -0.0300513711 -0.0454054587 -0.1138370261 981 1311867203.1549820900 0.0436848402 0.0613956457 0.0879767612 0.0053701536 0.0044820000 39546861 955859216 1373700096 -0.0304360501 -0.0474155918 -0.1138335317 982 1311867203.1877939701 0.0443420224 0.0613782795 0.0879767612 0.0054027364 0.0078440000 39549733 955859216 1373700096 -0.0310733877 -0.0487838238 -0.1140322760 983 1311867203.2185909748 0.0445185043 0.0613611281 0.0879767612 0.0054014922 0.0065890000 39552605 955859216 1373700096 -0.0305854548 -0.0487333164 -0.1142652705 984 1311867203.2552030087 0.0447648577 0.0613442620 0.0879767612 0.0053998297 0.0047690000 39555589 955859216 1373700096 -0.0301705915 -0.0497754142 -0.1144701093 985 1311867203.2864799500 0.0448581092 0.0613275248 0.0879767612 0.0053996147 0.0073570000 39558405 955859216 1373700096 -0.0308342781 -0.0511911735 -0.1148758531 986 1311867203.3194670677 0.0446213521 0.0613105814 0.0879767612 0.0053970433 0.0049040000 39561389 955859216 1373700096 -0.0301426239 -0.0516978167 -0.1152579039 987 1311867203.3547461033 0.0441377759 0.0612931824 0.0879767612 0.0053949551 0.0083520000 39564261 955859216 1373700096 -0.0290539488 -0.0519316345 -0.1156371236 988 1311867203.3865599632 0.0437496156 0.0612754258 0.0879767612 0.0053974163 0.0052350000 39567133 955859216 1373700096 -0.0290192701 -0.0531138927 -0.1159982830 989 1311867203.4183609486 0.0433819965 0.0612573333 0.0879767612 0.0054027330 0.0061860000 39570061 955859216 1373700096 -0.0283891559 -0.0564559884 -0.1164144427 990 1311867203.4545118809 0.0431706533 0.0612390639 0.0879767612 0.0054019718 0.0045570000 39573045 955859216 1373700096 -0.0280557889 -0.0576762185 -0.1165842712 991 1311867203.4864439964 0.0431533456 0.0612208140 0.0879767612 0.0054019169 0.0041900000 39575861 955859216 1373700096 -0.0276799258 -0.0591169633 -0.1165621728 992 1311867203.5185539722 0.0431436859 0.0612025911 0.0879767612 0.0054040124 0.0045790000 39578789 955859216 1373700096 -0.0281728506 -0.0618560798 -0.1170992181 993 1311867203.5560259819 0.0433545299 0.0611846172 0.0879767612 0.0054016401 0.0100670000 39581773 955859216 1373700096 -0.0281509776 -0.0638807341 -0.1175148785 994 1311867203.5876550674 0.0433207154 0.0611666455 0.0879767612 0.0053998268 0.0080560000 39584645 955859216 1373700096 -0.0278142188 -0.0649770051 -0.1178486347 995 1311867203.6191980839 0.0432726964 0.0611486616 0.0879767612 0.0053981781 0.0052390000 39587517 955859216 1373700096 -0.0279276725 -0.0672288388 -0.1182051226 996 1311867203.6557719707 0.0431175977 0.0611305581 0.0879767612 0.0053955400 0.0066680000 39590445 955859216 1373700096 -0.0277420189 -0.0698302090 -0.1187365875 997 1311867203.6866750717 0.0429186299 0.0611122914 0.0879767612 0.0053929353 0.0048420000 39593317 955859216 1373700096 -0.0280890949 -0.0714801177 -0.1191594824 998 1311867203.7195260525 0.0431189723 0.0610942620 0.0879767612 0.0053906193 0.0064770000 39596189 955859216 1373700096 -0.0280741472 -0.0733793750 -0.1192393526 999 1311867203.7566421032 0.0435574651 0.0610767077 0.0879767612 0.0053882907 0.0066230000 39599229 955859216 1373700096 -0.0282581765 -0.0746129230 -0.1193475127 1000 1311867203.7867228985 0.0437907316 0.0610594217 0.0879767612 0.0053856464 0.0047930000 39602045 955859216 1373700096 -0.0287354887 -0.0764240548 -0.1196710542 1001 1311867203.8193860054 0.0438703969 0.0610422498 0.0879767612 0.0053830328 0.0074370000 39604917 955859216 1373700096 -0.0281489845 -0.0776710063 -0.1201382354 1002 1311867203.8572859764 0.0440316945 0.0610252732 0.0879767612 0.0053814498 0.0050090000 39607957 955859216 1373700096 -0.0283787847 -0.0788316280 -0.1207919717 1003 1311867203.8891890049 0.0440662429 0.0610083649 0.0879767612 0.0053795224 0.0084590000 39610829 955859216 1373700096 -0.0287817065 -0.0807653964 -0.1216542721 1004 1311867203.9188020229 0.0442416109 0.0609916650 0.0879767612 0.0053774942 0.0054830000 39613645 955859216 1373700096 -0.0295764860 -0.0819333121 -0.1224364787 1005 1311867203.9553489685 0.0441869386 0.0609749438 0.0879767612 0.0053751857 0.0044060000 39616629 955859216 1373700096 -0.0292813797 -0.0823650360 -0.1233142763 1006 1311867203.9866371155 0.0442342311 0.0609583030 0.0879767612 0.0053740943 0.0097990000 39619501 955859216 1373700096 -0.0295611136 -0.0839646757 -0.1242155805 1007 1311867204.0199849606 0.0443849191 0.0609418448 0.0879767612 0.0053725847 0.0053730000 39622373 955859216 1373700096 -0.0298614576 -0.0847941339 -0.1253453344 1008 1311867204.0551509857 0.0443910100 0.0609254253 0.0879767612 0.0053702584 0.0044960000 39625357 955859216 1373700096 -0.0304158535 -0.0859033838 -0.1265252233 1009 1311867204.0867509842 0.0441451818 0.0609087948 0.0879767612 0.0053691234 0.0040080000 39628229 955859216 1373700096 -0.0309911277 -0.0876634866 -0.1275852770 1010 1311867204.1191530228 0.0444763191 0.0608925250 0.0879767612 0.0053665346 0.0097460000 39631101 955859216 1373700096 -0.0313083269 -0.0889547020 -0.1285024285 1011 1311867204.1555769444 0.0445651487 0.0608763752 0.0879767612 0.0053641844 0.0054610000 39634029 955859216 1373700096 -0.0314156786 -0.0904440582 -0.1291941553 1012 1311867204.1876530647 0.0444910526 0.0608601842 0.0879767612 0.0053622317 0.0046340000 39636901 955859216 1373700096 -0.0321819186 -0.0920217484 -0.1298803836 1013 1311867204.2187769413 0.0447529778 0.0608442837 0.0879767612 0.0053603524 0.0094330000 39639773 955859216 1373700096 -0.0329977423 -0.0930448994 -0.1303178966 1014 1311867204.2566440105 0.0451373607 0.0608287937 0.0879767612 0.0053579234 0.0054730000 39642813 955859216 1373700096 -0.0331758037 -0.0942221507 -0.1307914406 1015 1311867204.2867140770 0.0452898443 0.0608134843 0.0879767612 0.0053553461 0.0045060000 39645629 955859216 1373700096 -0.0337826535 -0.0962523669 -0.1312298179 1016 1311867204.3204538822 0.0458804294 0.0607987865 0.0879767612 0.0053533085 0.0040350000 39648501 955859216 1373700096 -0.0348649956 -0.0971526578 -0.1316318810 1017 1311867204.3625741005 0.0465379916 0.0607847640 0.0879767612 0.0053508099 0.0039690000 39651709 955859216 1373700096 -0.0359399207 -0.0987064838 -0.1317956895 1018 1311867204.3869600296 0.0466816761 0.0607709103 0.0879767612 0.0053483602 0.0039430000 39654357 955859216 1373700096 -0.0367278792 -0.0999892205 -0.1321671009 1019 1311867204.4240970612 0.0474673249 0.0607578548 0.0879767612 0.0053461731 0.0039940000 39657397 955859216 1373700096 -0.0377688743 -0.1009745598 -0.1324865967 1020 1311867204.4549949169 0.0480058081 0.0607453528 0.0879767612 0.0053448305 0.0039320000 39660213 955859216 1373700096 -0.0385505185 -0.1017372757 -0.1326745898 1021 1311867204.4872748852 0.0484995916 0.0607333589 0.0879767612 0.0053426596 0.0115040000 39663085 955859216 1373700096 -0.0395951420 -0.1034279466 -0.1329648197 1022 1311867204.5237219334 0.0488385037 0.0607217201 0.0879767612 0.0053401597 0.0064290000 39666125 955859216 1373700096 -0.0401586443 -0.1045591310 -0.1333666593 1023 1311867204.5581860542 0.0492019355 0.0607104593 0.0879767612 0.0053385215 0.0047420000 39669053 955859216 1373700096 -0.0408210792 -0.1052804291 -0.1335929036 1024 1311867204.5878469944 0.0492007472 0.0606992193 0.0879767612 0.0053363099 0.0041620000 39671869 955859216 1373700096 -0.0414612070 -0.1069901064 -0.1337152869 1025 1311867204.6241528988 0.0490383692 0.0606878429 0.0879767612 0.0053338872 0.0066090000 39773157 955859216 1373700096 -0.0421827845 -0.1080613062 -0.1336739957 1026 1311867204.6541819572 0.0492910966 0.0606767350 0.0879767612 0.0053316794 0.0048040000 39980773 955859216 1373700096 -0.0426826738 -0.1101540998 -0.1335147768 1027 1311867204.6871540546 0.0496885628 0.0606660357 0.0879767612 0.0053294636 0.0071190000 39983645 955859216 1373700096 -0.0436040685 -0.1111820936 -0.1334096044 1028 1311867204.7225689888 0.0498938821 0.0606555569 0.0879767612 0.0053281051 0.0049540000 39986629 955859216 1373700096 -0.0438019186 -0.1117274016 -0.1331480294 1029 1311867204.7539510727 0.0499104708 0.0606451147 0.0879767612 0.0053256769 0.0076080000 39989501 955859216 1373700096 -0.0451894291 -0.1129492596 -0.1328313500 1030 1311867204.7878720760 0.0501015931 0.0606348782 0.0879767612 0.0053248842 0.0050900000 39992429 955859216 1373700096 -0.0467900001 -0.1145535335 -0.1320243329 1031 1311867204.8227200508 0.0499804579 0.0606245442 0.0879767612 0.0053224285 0.0045120000 39995357 955859216 1373700096 -0.0467987433 -0.1153852865 -0.1307373792 1032 1311867204.8542668819 0.0498395786 0.0606140936 0.0879767612 0.0053211661 0.0042200000 39998229 955859216 1373700096 -0.0470672250 -0.1168399081 -0.1294352412 1033 1311867204.8864960670 0.0501316451 0.0606039461 0.0879767612 0.0053196615 0.0107770000 40001101 955859216 1373700096 -0.0481497087 -0.1190434694 -0.1284545511 1034 1311867204.9220221043 0.0504967459 0.0605941712 0.0879767612 0.0053172674 0.0057330000 40004085 955859216 1373700096 -0.0495235436 -0.1210412681 -0.1272790730 1035 1311867204.9542920589 0.0504942760 0.0605844128 0.0879767612 0.0053152307 0.0044900000 40006957 955859216 1373700096 -0.0499328040 -0.1225463375 -0.1262895763 1036 1311867204.9865999222 0.0507503152 0.0605749205 0.0879767612 0.0053128322 0.0109210000 40009829 955859216 1373700096 -0.0505001135 -0.1252069175 -0.1254542768 1037 1311867205.0227239132 0.0509787612 0.0605656667 0.0879767612 0.0053144539 0.0109190000 40012813 955859216 1373700096 -0.0508946292 -0.1268046498 -0.1247127429 1038 1311867205.0550808907 0.0505067222 0.0605559760 0.0879767612 0.0053274027 0.0062930000 40015741 955859216 1373700096 -0.0512539223 -0.1277257055 -0.1238447800 1039 1311867205.0880999565 0.0507127717 0.0605465023 0.0879767612 0.0053250880 0.0047820000 40018501 955859216 1373700096 -0.0518430658 -0.1299773455 -0.1229781732 1040 1311867205.1232450008 0.0513582639 0.0605376674 0.0879767612 0.0053239690 0.0039840000 40021485 955859216 1373700096 -0.0518891551 -0.1314614564 -0.1221508682 1041 1311867205.1545319557 0.0520617850 0.0605295254 0.0879767612 0.0053350730 0.0110930000 40024301 955859216 1373700096 -0.0517335236 -0.1326341778 -0.1214325130 1042 1311867205.1863510609 0.0520662405 0.0605214032 0.0879767612 0.0053426473 0.0073300000 40027173 955859216 1373700096 -0.0518300124 -0.1350602657 -0.1206072271 1043 1311867205.2223129272 0.0516957045 0.0605129414 0.0879767612 0.0053414578 0.0049800000 40030157 955859216 1373700096 -0.0516331829 -0.1369582862 -0.1200381815 1044 1311867205.2541849613 0.0518052727 0.0605046007 0.0879767612 0.0053405756 0.0042420000 40033029 955859216 1373700096 -0.0518600047 -0.1384743750 -0.1192998663 1045 1311867205.2880499363 0.0522940718 0.0604967437 0.0879767612 0.0053385183 0.0039460000 40035957 955859216 1373700096 -0.0524711311 -0.1400822848 -0.1184763163 1046 1311867205.3218879700 0.0527017191 0.0604892915 0.0879767612 0.0053379653 0.0097260000 40038829 955859216 1373700096 -0.0529841632 -0.1417498887 -0.1177163348 1047 1311867205.3542900085 0.0530362241 0.0604821730 0.0879767612 0.0053420095 0.0055580000 40041757 955859216 1373700096 -0.0537716374 -0.1434658766 -0.1167907193 1048 1311867205.3862779140 0.0532343611 0.0604752572 0.0879767612 0.0053485031 0.0070480000 40044629 955859216 1373700096 -0.0544746071 -0.1447767764 -0.1159305125 1049 1311867205.4225649834 0.0533634424 0.0604684775 0.0879767612 0.0053506294 0.0049500000 40047613 955859216 1373700096 -0.0556651130 -0.1464807242 -0.1152055711 1050 1311867205.4540419579 0.0536316261 0.0604619663 0.0879767612 0.0053536849 0.0064930000 40050485 955859216 1373700096 -0.0560914651 -0.1476330906 -0.1142676398 1051 1311867205.4865119457 0.0528359488 0.0604547103 0.0879767612 0.0053563793 0.0046660000 40053357 955859216 1373700096 -0.0565650724 -0.1491688341 -0.1132680774 1052 1311867205.5230340958 0.0528677367 0.0604474983 0.0879767612 0.0053649065 0.0042230000 40056341 955859216 1373700096 -0.0576952696 -0.1510490030 -0.1123536229 1053 1311867205.5542900562 0.0533129349 0.0604407229 0.0879767612 0.0053838938 0.0109140000 40059213 955859216 1373700096 -0.0590380989 -0.1517627388 -0.1111962423 1054 1311867205.5866839886 0.0531679019 0.0604338227 0.0879767612 0.0053814092 0.0058020000 40062085 955859216 1373700096 -0.0601783879 -0.1531534195 -0.1101259664 1055 1311867205.6226179600 0.0524464101 0.0604262517 0.0879767612 0.0053853016 0.0045980000 40065069 955859216 1373700096 -0.0606671944 -0.1553796828 -0.1091799811 1056 1311867205.6555979252 0.0524474494 0.0604186960 0.0879767612 0.0053837813 0.0070480000 40067941 955859216 1373700096 -0.0622414351 -0.1578525603 -0.1082973927 1057 1311867205.6902959347 0.0525340997 0.0604112366 0.0879767612 0.0053813164 0.0048750000 40070925 955859216 1373700096 -0.0627465174 -0.1593856812 -0.1075360999 1058 1311867205.7222061157 0.0528150983 0.0604040569 0.0879767612 0.0053788930 0.0073100000 40073797 955859216 1373700096 -0.0643205792 -0.1617826074 -0.1070231646 1059 1311867205.7548348904 0.0531040244 0.0603971635 0.0879767612 0.0053767737 0.0050650000 40076725 955859216 1373700096 -0.0655870661 -0.1634894311 -0.1066113040 1060 1311867205.7906379700 0.0531665422 0.0603903422 0.0879767612 0.0053746149 0.0070850000 40079653 955859216 1373700096 -0.0664291754 -0.1651241034 -0.1060935482 1061 1311867205.8232109547 0.0537089445 0.0603840449 0.0879767612 0.0053813330 0.0049770000 40082581 955859216 1373700096 -0.0679483488 -0.1672415733 -0.1055750847 1062 1311867205.8554759026 0.0536865108 0.0603777384 0.0879767612 0.0053829922 0.0042620000 40085509 955859216 1373700096 -0.0689517409 -0.1688402593 -0.1051402763 1063 1311867205.8905880451 0.0539224409 0.0603716657 0.0879767612 0.0053822905 0.0099310000 40088381 955859216 1373700096 -0.0701196343 -0.1703562587 -0.1048066020 1064 1311867205.9223020077 0.0539263450 0.0603656080 0.0879767612 0.0053893431 0.0056040000 40091253 955859216 1373700096 -0.0708573088 -0.1717558205 -0.1044749543 1065 1311867205.9544939995 0.0538894534 0.0603595271 0.0879767612 0.0053870197 0.0045860000 40094125 955859216 1373700096 -0.0715931356 -0.1739682257 -0.1040671319 1066 1311867205.9905850887 0.0546917357 0.0603542103 0.0879767612 0.0053952965 0.0066990000 40097165 955859216 1373700096 -0.0731004700 -0.1746049076 -0.1035877615 1067 1311867206.0259850025 0.0545688644 0.0603487882 0.0879767612 0.0053964492 0.0049520000 40100093 955859216 1373700096 -0.0733652785 -0.1755351275 -0.1033419967 1068 1311867206.0604250431 0.0540600643 0.0603428999 0.0879767612 0.0054037054 0.0073410000 40102965 955859216 1373700096 -0.0736829191 -0.1782328784 -0.1032419726 1069 1311867206.0903289318 0.0537892208 0.0603367692 0.0879767612 0.0054013532 0.0055470000 40105781 955859216 1373700096 -0.0738940462 -0.1802904010 -0.1032967567 1070 1311867206.1227540970 0.0539747700 0.0603308234 0.0879767612 0.0053988497 0.0070470000 40108653 955859216 1373700096 -0.0739502013 -0.1822148710 -0.1028663963 1071 1311867206.1546130180 0.0544341914 0.0603253177 0.0879767612 0.0053966125 0.0050220000 40111525 955859216 1373700096 -0.0745993033 -0.1844625771 -0.1029834747 1072 1311867206.1903800964 0.0547550656 0.0603201216 0.0879767612 0.0053980447 0.0043120000 40114565 955859216 1373700096 -0.0760413781 -0.1870873421 -0.1030353904 1073 1311867206.2239561081 0.0547453612 0.0603149261 0.0879767612 0.0053960151 0.0100190000 40117493 955859216 1373700096 -0.0762499794 -0.1884838045 -0.1031652167 1074 1311867206.2553579807 0.0542890914 0.0603093154 0.0879767612 0.0053947821 0.0056370000 40120309 955859216 1373700096 -0.0760757923 -0.1901774704 -0.1034881547 1075 1311867206.2904770374 0.0541354455 0.0603035723 0.0879767612 0.0053923829 0.0045500000 40123237 955859216 1373700096 -0.0766309574 -0.1923973709 -0.1038421243 1076 1311867206.3222041130 0.0540812723 0.0602977895 0.0879767612 0.0053903292 0.0067300000 40126053 955859216 1373700096 -0.0771885961 -0.1935752332 -0.1042810827 1077 1311867206.3542530537 0.0540855788 0.0602920214 0.0879767612 0.0053888822 0.0048500000 40128981 955859216 1373700096 -0.0780352056 -0.1952675879 -0.1045234501 1078 1311867206.3900070190 0.0539349280 0.0602861243 0.0879767612 0.0053876960 0.0043160000 40131909 955859216 1373700096 -0.0781668201 -0.1971931458 -0.1046563610 1079 1311867206.4220259190 0.0537619591 0.0602800778 0.0879767612 0.0053862471 0.0098510000 40134781 955859216 1373700096 -0.0780663341 -0.1988324076 -0.1046875045 1080 1311867206.4542310238 0.0535920672 0.0602738852 0.0879767612 0.0053844816 0.0056080000 40137709 955859216 1373700096 -0.0783386156 -0.2006516308 -0.1046153083 1081 1311867206.4905378819 0.0531955473 0.0602673373 0.0879767612 0.0053925630 0.0045420000 40140637 955859216 1373700096 -0.0789879337 -0.2032048255 -0.1047272906 1082 1311867206.5250329971 0.0535329804 0.0602611133 0.0879767612 0.0053943668 0.0042180000 40143621 955859216 1373700096 -0.0797578171 -0.2055625468 -0.1048348919 1083 1311867206.5539300442 0.0535653308 0.0602549306 0.0879767612 0.0053983161 0.0040470000 40146437 955859216 1373700096 -0.0798464268 -0.2078637332 -0.1048230976 1084 1311867206.5921130180 0.0536367744 0.0602488253 0.0879767612 0.0053968880 0.0111460000 40149421 955859216 1373700096 -0.0798882321 -0.2098063827 -0.1050444916 1085 1311867206.6226360798 0.0547627546 0.0602437690 0.0879767612 0.0054091590 0.0060360000 40152237 955859216 1373700096 -0.0808899626 -0.2116285861 -0.1051886007 1086 1311867206.6566751003 0.0541852005 0.0602381903 0.0879767612 0.0054076103 0.0046560000 40155165 955859216 1373700096 -0.0811538398 -0.2136707455 -0.1053843722 1087 1311867206.6945209503 0.0540148392 0.0602324650 0.0879767612 0.0054061196 0.0040900000 40158205 955859216 1373700096 -0.0808044896 -0.2147219181 -0.1057224199 1088 1311867206.7248480320 0.0534375571 0.0602262197 0.0879767612 0.0054120776 0.0040190000 40161021 955859216 1373700096 -0.0810684115 -0.2169268280 -0.1060253307 1089 1311867206.7587969303 0.0545350686 0.0602209936 0.0879767612 0.0054525954 0.0040250000 40164005 955859216 1373700096 -0.0810123086 -0.2180397809 -0.1064183414 1090 1311867206.7902839184 0.0537803099 0.0602150848 0.0879767612 0.0054672904 0.0112080000 40166877 955859216 1373700096 -0.0815552920 -0.2197601348 -0.1068465114 1091 1311867206.8229770660 0.0545228906 0.0602098674 0.0879767612 0.0054656267 0.0059780000 40169749 955859216 1373700096 -0.0834136605 -0.2216565609 -0.1073771045 1092 1311867206.8605449200 0.0545422994 0.0602046773 0.0879767612 0.0054633188 0.0046460000 40172733 955859216 1373700096 -0.0837330446 -0.2235174179 -0.1080163568 1093 1311867206.8907771111 0.0541697741 0.0601991559 0.0879767612 0.0054619123 0.0041010000 40175549 955859216 1373700096 -0.0833730474 -0.2245372832 -0.1086412221 1094 1311867206.9225020409 0.0542017557 0.0601936738 0.0879767612 0.0054594250 0.0087350000 40178421 955859216 1373700096 -0.0836822242 -0.2263913453 -0.1092264801 1095 1311867206.9592480659 0.0553397164 0.0601892409 0.0879767612 0.0054586032 0.0052750000 40181461 955859216 1373700096 -0.0853629112 -0.2290557623 -0.1097424403 1096 1311867206.9948680401 0.0557035021 0.0601851481 0.0879767612 0.0054667044 0.0043410000 40184389 955859216 1373700096 -0.0859735161 -0.2311847657 -0.1099631041 1097 1311867207.0247550011 0.0563984551 0.0601816962 0.0879767612 0.0054697387 0.0085440000 40187261 955859216 1373700096 -0.0860651061 -0.2329536974 -0.1099941656 1098 1311867207.0597259998 0.0556757897 0.0601775925 0.0879767612 0.0054676467 0.0052470000 40190245 955859216 1373700096 -0.0857446194 -0.2352375686 -0.1103971526 1099 1311867207.0942800045 0.0558175147 0.0601736252 0.0879767612 0.0054711208 0.0048160000 40193117 955859216 1373700096 -0.0862665400 -0.2379805148 -0.1105400398 1100 1311867207.1229140759 0.0558067895 0.0601696553 0.0879767612 0.0054741813 0.0084910000 40195877 955859216 1373700096 -0.0857831687 -0.2390249670 -0.1107733101 1101 1311867207.1583549976 0.0563449897 0.0601661815 0.0879767612 0.0054783625 0.0052670000 40198861 955859216 1373700096 -0.0859439149 -0.2408917099 -0.1108366624 1102 1311867207.1904919147 0.0560070425 0.0601624074 0.0879767612 0.0054770909 0.0064580000 40201677 955859216 1373700096 -0.0861168429 -0.2427317351 -0.1109601259 1103 1311867207.2226181030 0.0557664707 0.0601584219 0.0879767612 0.0054767731 0.0046710000 40204605 955859216 1373700096 -0.0858510137 -0.2438945621 -0.1108806580 1104 1311867207.2604830265 0.0558900647 0.0601545557 0.0879767612 0.0054770732 0.0086850000 40207645 955859216 1373700096 -0.0862558261 -0.2453127652 -0.1106118038 1105 1311867207.2926900387 0.0556178987 0.0601504501 0.0879767612 0.0054766116 0.0053360000 40210517 955859216 1373700096 -0.0864144117 -0.2470549047 -0.1104660258 1106 1311867207.3235239983 0.0563398860 0.0601470047 0.0879767612 0.0054807739 0.0043830000 40213333 955859216 1373700096 -0.0873192772 -0.2485190183 -0.1098455936 1107 1311867207.3597478867 0.0559061989 0.0601431738 0.0879767612 0.0054794245 0.0085840000 40216373 955859216 1373700096 -0.0877471119 -0.2501842976 -0.1093851849 1108 1311867207.3901309967 0.0557845794 0.0601392401 0.0879767612 0.0054798370 0.0053010000 40219189 955859216 1373700096 -0.0883969218 -0.2524482012 -0.1088728234 1109 1311867207.4227840900 0.0556356274 0.0601351791 0.0879767612 0.0054775483 0.0043480000 40222061 955859216 1373700096 -0.0899689868 -0.2544748187 -0.1086850166 1110 1311867207.4586789608 0.0557140149 0.0601311961 0.0879767612 0.0054770411 0.0101520000 40225045 955859216 1373700096 -0.0905117616 -0.2554066777 -0.1082045808 1111 1311867207.4927639961 0.0557527579 0.0601272551 0.0879767612 0.0054763068 0.0057540000 40227973 955859216 1373700096 -0.0914291963 -0.2573009133 -0.1078815460 1112 1311867207.5237300396 0.0559192263 0.0601234709 0.0879767612 0.0054799793 0.0046110000 40230845 955859216 1373700096 -0.0922541916 -0.2588918507 -0.1075704247 1113 1311867207.5598409176 0.0562021732 0.0601199477 0.0879767612 0.0054783316 0.0065280000 40233773 955859216 1373700096 -0.0936007574 -0.2604176402 -0.1073523015 1114 1311867207.5944800377 0.0564838275 0.0601166837 0.0879767612 0.0054784594 0.0048100000 40236757 955859216 1373700096 -0.0948736668 -0.2621257901 -0.1071707010 1115 1311867207.6259219646 0.0553120822 0.0601123746 0.0879767612 0.0054762413 0.0102640000 40239573 955859216 1373700096 -0.0944178626 -0.2650503516 -0.1066381559 1116 1311867207.6592938900 0.0550027676 0.0601077961 0.0879767612 0.0054745822 0.0056240000 40242557 955859216 1373700096 -0.0946431682 -0.2666758001 -0.1065645143 1117 1311867207.6923089027 0.0557674803 0.0601039104 0.0879767612 0.0054740713 0.0046780000 40245429 955859216 1373700096 -0.0960562825 -0.2683829367 -0.1062927470 1118 1311867207.7238640785 0.0551974103 0.0600995218 0.0879767612 0.0054744769 0.0070050000 40248301 955859216 1373700096 -0.0961563587 -0.2711097002 -0.1061657444 1119 1311867207.7588050365 0.0552715361 0.0600952073 0.0879767612 0.0054728565 0.0049930000 40251117 955859216 1373700096 -0.0970332697 -0.2734820247 -0.1059688181 1120 1311867207.7921919823 0.0554441735 0.0600910545 0.0879767612 0.0054706233 0.0076180000 40254045 955859216 1373700096 -0.0980023891 -0.2748199999 -0.1059318483 1121 1311867207.8237760067 0.0555058122 0.0600869642 0.0879767612 0.0054682086 0.0051730000 40256917 955859216 1373700096 -0.0988497734 -0.2771396935 -0.1058942378 1122 1311867207.8608479500 0.0552791879 0.0600826792 0.0879767612 0.0054665694 0.0046540000 40259901 955859216 1373700096 -0.0983965099 -0.2789754570 -0.1056159660 1123 1311867207.8937089443 0.0555237494 0.0600786196 0.0879767612 0.0054643597 0.0043530000 40262829 955859216 1373700096 -0.0983808339 -0.2799589336 -0.1053509489 1124 1311867207.9244139194 0.0553583056 0.0600744201 0.0879767612 0.0054632267 0.0108670000 40265645 955859216 1373700096 -0.0988712683 -0.2821097374 -0.1050756946 1125 1311867207.9614970684 0.0552207045 0.0600701056 0.0879767612 0.0054623092 0.0060930000 40268517 955859216 1373700096 -0.0992304608 -0.2834836543 -0.1046831831 1126 1311867207.9914131165 0.0551927090 0.0600657740 0.0879767612 0.0054772929 0.0047380000 40271333 955859216 1373700096 -0.0987177119 -0.2848379314 -0.1045286357 1127 1311867208.0248498917 0.0545548834 0.0600608842 0.0879767612 0.0054926921 0.0065110000 40274317 955859216 1373700096 -0.0988458693 -0.2874576747 -0.1042500660 1128 1311867208.0618500710 0.0550356284 0.0600564291 0.0879767612 0.0054911031 0.0050770000 40277133 955859216 1373700096 -0.0993120745 -0.2891380787 -0.1039667428 1129 1311867208.0924620628 0.0550099574 0.0600519593 0.0879767612 0.0054886872 0.0043920000 40279949 955859216 1373700096 -0.0991539881 -0.2905198038 -0.1037979722 1130 1311867208.1276559830 0.0552687123 0.0600477263 0.0879767612 0.0054870384 0.0109580000 40282877 955859216 1373700096 -0.1000809595 -0.2926187515 -0.1037772894 1131 1311867208.1596069336 0.0552490130 0.0600434834 0.0879767612 0.0054847324 0.0058930000 40285749 955859216 1373700096 -0.1004357338 -0.2940565050 -0.1039407477 1132 1311867208.1905009747 0.0553052723 0.0600392977 0.0879767612 0.0054832329 0.0065220000 40288509 955859216 1373700096 -0.1008244827 -0.2952785492 -0.1043644473 1133 1311867208.2280850410 0.0554243177 0.0600352245 0.0879767612 0.0054813137 0.0049080000 40291605 955859216 1373700096 -0.1009524614 -0.2968373895 -0.1045199409 1134 1311867208.2581789494 0.0548395962 0.0600306428 0.0879767612 0.0054793694 0.0066680000 40294421 955859216 1373700096 -0.1007301733 -0.2985791266 -0.1048386097 1135 1311867208.2901990414 0.0547428392 0.0600259839 0.0879767612 0.0054773127 0.0070610000 40297237 955859216 1373700096 -0.1003509164 -0.2990783751 -0.1051509678 1136 1311867208.3270208836 0.0556893423 0.0600221665 0.0879767612 0.0054793835 0.0050210000 40300277 955859216 1373700096 -0.1012472287 -0.3000557721 -0.1054532602 1137 1311867208.3580970764 0.0559930131 0.0600186228 0.0879767612 0.0054798060 0.0076850000 40303149 955859216 1373700096 -0.1019932330 -0.3011991978 -0.1053736806 1138 1311867208.3910560608 0.0561473146 0.0600152210 0.0879767612 0.0054779443 0.0052020000 40305965 955859216 1373700096 -0.1023845151 -0.3023763597 -0.1054673940 1139 1311867208.4260230064 0.0559657142 0.0600116656 0.0879767612 0.0054760310 0.0045810000 40308949 955859216 1373700096 -0.1028287038 -0.3047071993 -0.1056158170 1140 1311867208.4577419758 0.0565123633 0.0600085961 0.0879767612 0.0054760397 0.0097490000 40311821 955859216 1373700096 -0.1031509787 -0.3065288365 -0.1054732949 1141 1311867208.4907650948 0.0564392470 0.0600054678 0.0879767612 0.0054738718 0.0055140000 40314749 955859216 1373700096 -0.1030215174 -0.3074976802 -0.1052959338 1142 1311867208.5257411003 0.0563851967 0.0600022977 0.0879767612 0.0054721359 0.0070860000 40317733 955859216 1373700096 -0.1037336141 -0.3087790012 -0.1050790995 1143 1311867208.5583798885 0.0565339439 0.0599992633 0.0879767612 0.0054698086 0.0049740000 40320605 955859216 1373700096 -0.1040968224 -0.3095676899 -0.1046034545 1144 1311867208.5904500484 0.0563735515 0.0599960939 0.0879767612 0.0054682093 0.0065910000 40323533 955859216 1373700096 -0.1040536016 -0.3111217916 -0.1039935201 1145 1311867208.6259779930 0.0560882688 0.0599926810 0.0879767612 0.0054660579 0.0049280000 40326405 955859216 1373700096 -0.1045615375 -0.3122954369 -0.1035855040 1146 1311867208.6582078934 0.0553450808 0.0599886255 0.0879767612 0.0054638737 0.0107440000 40329333 955859216 1373700096 -0.1040741429 -0.3136932552 -0.1030395627 1147 1311867208.6910300255 0.0542356707 0.0599836098 0.0879767612 0.0054666766 0.0056990000 40332205 955859216 1373700096 -0.1041635945 -0.3145602345 -0.1023164019 1148 1311867208.7262260914 0.0545655154 0.0599788902 0.0879767612 0.0054660717 0.0046160000 40335189 955859216 1373700096 -0.1044141501 -0.3159770370 -0.1019888744 1149 1311867208.7591009140 0.0547404364 0.0599743311 0.0879767612 0.0054638040 0.0042600000 40338061 955859216 1373700096 -0.1051015705 -0.3164129853 -0.1014110148 1150 1311867208.7909750938 0.0543011352 0.0599693979 0.0879767612 0.0054617693 0.0041250000 40340877 955859216 1373700096 -0.1049733758 -0.3171003461 -0.1009886637 1151 1311867208.8259930611 0.0545035228 0.0599646491 0.0879767612 0.0054605376 0.0040760000 40343861 955859216 1373700096 -0.1057258397 -0.3189065754 -0.1005340368 1152 1311867208.8588190079 0.0555919185 0.0599608533 0.0879767612 0.0054648029 0.0111530000 40346789 955859216 1373700096 -0.1071925163 -0.3199139535 -0.0999277681 1153 1311867208.8916258812 0.0545304790 0.0599561435 0.0879767612 0.0054749859 0.0071020000 40349605 955859216 1373700096 -0.1080766618 -0.3206249177 -0.0994695202 1154 1311867208.9275119305 0.0551940575 0.0599520169 0.0879767612 0.0054743592 0.0050840000 40352533 955859216 1373700096 -0.1086303666 -0.3227974772 -0.0993978679 1155 1311867208.9577760696 0.0557980649 0.0599484204 0.0879767612 0.0054721787 0.0043420000 40355349 955859216 1373700096 -0.1100142747 -0.3244033754 -0.0995915458 1156 1311867208.9911639690 0.0559932068 0.0599449990 0.0879767612 0.0054701104 0.0083870000 40358277 955859216 1373700096 -0.1101625562 -0.3250136673 -0.0998541862 1157 1311867209.0270779133 0.0563239679 0.0599418693 0.0879767612 0.0054693790 0.0055210000 40361261 955859216 1373700096 -0.1106482819 -0.3267976940 -0.0999498367 1158 1311867209.0579569340 0.0570220836 0.0599393479 0.0879767612 0.0054673221 0.0048780000 40364077 955859216 1373700096 -0.1119073778 -0.3278470039 -0.1006291509 1159 1311867209.0906980038 0.0567995310 0.0599366388 0.0879767612 0.0054653609 0.0041630000 40367005 955859216 1373700096 -0.1117979288 -0.3282928765 -0.1010727957 1160 1311867209.1260778904 0.0570184626 0.0599341232 0.0879767612 0.0054637216 0.0115560000 40369877 955859216 1373700096 -0.1126679555 -0.3295187354 -0.1015933752 1161 1311867209.1600620747 0.0575262420 0.0599320492 0.0879767612 0.0054620435 0.0059770000 40372861 955859216 1373700096 -0.1133333892 -0.3306953311 -0.1019725576 1162 1311867209.1917839050 0.0576834567 0.0599301141 0.0879767612 0.0054601160 0.0047450000 40375733 955859216 1373700096 -0.1135043204 -0.3309600651 -0.1024683490 1163 1311867209.2259531021 0.0579283386 0.0599283929 0.0879767612 0.0054578672 0.0041220000 40378605 955859216 1373700096 -0.1143810824 -0.3325490654 -0.1028619111 1164 1311867209.2580060959 0.0581781976 0.0599268893 0.0879767612 0.0054561424 0.0080280000 40381533 955859216 1373700096 -0.1150876805 -0.3334139287 -0.1032769009 1165 1311867209.2903130054 0.0577943958 0.0599250588 0.0879767612 0.0054539232 0.0052520000 40384405 955859216 1373700096 -0.1150416285 -0.3339628577 -0.1039472520 1166 1311867209.3274219036 0.0576486588 0.0599231065 0.0879767612 0.0054535947 0.0066310000 40387389 955859216 1373700096 -0.1155371293 -0.3355236053 -0.1045664921 1167 1311867209.3581039906 0.0576181971 0.0599211314 0.0879767612 0.0054513260 0.0046870000 40390205 955859216 1373700096 -0.1158642769 -0.3367202878 -0.1050360054 1168 1311867209.3937969208 0.0575299151 0.0599190841 0.0879767612 0.0054499408 0.0087410000 40393189 955859216 1373700096 -0.1160867140 -0.3372981548 -0.1054249331 1169 1311867209.4258151054 0.0570814833 0.0599166568 0.0879767612 0.0054484727 0.0052780000 40396117 955859216 1373700096 -0.1162949726 -0.3387663066 -0.1059418842 1170 1311867209.4581329823 0.0576916039 0.0599147550 0.0879767612 0.0054463033 0.0065450000 40398933 955859216 1373700096 -0.1177043989 -0.3402886689 -0.1060141400 1171 1311867209.4940650463 0.0577326082 0.0599128915 0.0879767612 0.0054448237 0.0046750000 40401973 955859216 1373700096 -0.1182624474 -0.3409128785 -0.1062415764 1172 1311867209.5258729458 0.0571199544 0.0599105085 0.0879767612 0.0054429236 0.0105060000 40404789 955859216 1373700096 -0.1183910817 -0.3420990705 -0.1065375581 1173 1311867209.5580699444 0.0568829849 0.0599079275 0.0879767612 0.0054410327 0.0056680000 40407661 955859216 1373700096 -0.1191819087 -0.3438489735 -0.1066019610 1174 1311867209.5939540863 0.0572042540 0.0599056245 0.0879767612 0.0054389905 0.0045790000 40410645 955859216 1373700096 -0.1209813431 -0.3457909822 -0.1067754626 1175 1311867209.6262791157 0.0567236952 0.0599029165 0.0879767612 0.0054368799 0.0068610000 40413461 955859216 1373700096 -0.1213606894 -0.3474914432 -0.1069836468 1176 1311867209.6582019329 0.0566463247 0.0599001473 0.0879767612 0.0054347282 0.0049040000 40416277 955859216 1373700096 -0.1217716932 -0.3486966193 -0.1072141826 1177 1311867209.6967020035 0.0564345047 0.0598972028 0.0879767612 0.0054407921 0.0043910000 40419261 955859216 1373700096 -0.1219761446 -0.3508412838 -0.1072563678 1178 1311867209.7262639999 0.0574015826 0.0598950843 0.0879767612 0.0054494287 0.0111210000 40422077 955859216 1373700096 -0.1241753921 -0.3528204858 -0.1076464653 1179 1311867209.7583460808 0.0573707111 0.0598929431 0.0879767612 0.0054512347 0.0058100000 40425005 955859216 1373700096 -0.1246054471 -0.3541834950 -0.1082205921 1180 1311867209.7959320545 0.0578224435 0.0598911885 0.0879767612 0.0054491996 0.0046730000 40428045 955859216 1373700096 -0.1255596131 -0.3558194041 -0.1088615507 1181 1311867209.8262419701 0.0578633696 0.0598894715 0.0879767612 0.0054473150 0.0073880000 40430861 955859216 1373700096 -0.1260538697 -0.3570004702 -0.1095482633 1182 1311867209.8588960171 0.0583448708 0.0598881647 0.0879767612 0.0054452170 0.0051300000 40433733 955859216 1373700096 -0.1270490289 -0.3577986062 -0.1101415157 1183 1311867209.8946969509 0.0587719865 0.0598872212 0.0879767612 0.0054436525 0.0068390000 40436717 955859216 1373700096 -0.1275318116 -0.3586556613 -0.1105793417 1184 1311867209.9268450737 0.0593515746 0.0598867688 0.0879767612 0.0054417284 0.0049280000 40439533 955859216 1373700096 -0.1284671426 -0.3595501184 -0.1108920872 1185 1311867209.9588210583 0.0594054163 0.0598863626 0.0879767612 0.0054396120 0.0043420000 40442461 955859216 1373700096 -0.1288177669 -0.3605442941 -0.1112109646 1186 1311867209.9942541122 0.0593727864 0.0598859295 0.0879767612 0.0054393653 0.0113810000 40445445 955859216 1373700096 -0.1286924779 -0.3617398143 -0.1115437075 1187 1311867210.0261061192 0.0604346320 0.0598863918 0.0879767612 0.0054375007 0.0071960000 40448261 955859216 1373700096 -0.1304264367 -0.3628920615 -0.1117596924 1188 1311867210.0603590012 0.0603275411 0.0598867631 0.0879767612 0.0054379644 0.0049450000 40451301 955859216 1373700096 -0.1299233586 -0.3624378145 -0.1122409180 1189 1311867210.0942480564 0.0614935383 0.0598881145 0.0879767612 0.0054391506 0.0043100000 40454173 955859216 1373700096 -0.1311934739 -0.3632543981 -0.1123151556 1190 1311867210.1280341148 0.0593293048 0.0598876449 0.0879767612 0.0054383697 0.0040380000 40457101 955859216 1373700096 -0.1275668591 -0.3652535081 -0.1119516417 1191 1311867210.1578240395 0.0590068251 0.0598869053 0.0879767612 0.0054367644 0.0102900000 40459917 955859216 1373700096 -0.1265892237 -0.3656506240 -0.1117701977 1192 1311867210.1943209171 0.0594018809 0.0598864984 0.0879767612 0.0054346988 0.0056430000 40462957 955859216 1373700096 -0.1271888763 -0.3666754365 -0.1120574623 1193 1311867210.2258129120 0.0595386960 0.0598862069 0.0879767612 0.0054328236 0.0045680000 40465773 955859216 1373700096 -0.1278463602 -0.3680208027 -0.1128152609 1194 1311867210.2579770088 0.0597604662 0.0598861016 0.0879767612 0.0054306901 0.0041340000 40468645 955859216 1373700096 -0.1281520426 -0.3682997823 -0.1132999063 1195 1311867210.2953989506 0.0602225773 0.0598863832 0.0879767612 0.0054284996 0.0102270000 40471685 955859216 1373700096 -0.1288845241 -0.3684391975 -0.1137846634 1196 1311867210.3271369934 0.0603904538 0.0598868046 0.0879767612 0.0054316703 0.0056540000 40474501 955859216 1373700096 -0.1295700073 -0.3688481450 -0.1140907258 1197 1311867210.3582420349 0.0602207519 0.0598870836 0.0879767612 0.0054360395 0.0071840000 40477373 955859216 1373700096 -0.1292156577 -0.3693852723 -0.1143240184 1198 1311867210.3937919140 0.0605630279 0.0598876478 0.0879767612 0.0054338338 0.0051810000 40480357 955859216 1373700096 -0.1296634227 -0.3699754179 -0.1144042462 1199 1311867210.4260039330 0.0605907030 0.0598882342 0.0879767612 0.0054358801 0.0042110000 40483173 955859216 1373700096 -0.1305199116 -0.3706750870 -0.1148491427 1200 1311867210.4581708908 0.0604320243 0.0598886874 0.0879767612 0.0054338491 0.0108860000 40486101 955859216 1373700096 -0.1304278374 -0.3709479868 -0.1151761487 1201 1311867210.4943509102 0.0598762706 0.0598886770 0.0879767612 0.0054494045 0.0056980000 40489029 955859216 1373700096 -0.1293925494 -0.3696950674 -0.1157539263 1202 1311867210.5261299610 0.0596346892 0.0598884657 0.0879767612 0.0054492865 0.0046300000 40491901 955859216 1373700096 -0.1297335625 -0.3704741597 -0.1163271964 1203 1311867210.5634729862 0.0592985153 0.0598879753 0.0879767612 0.0054482122 0.0041460000 40494941 955859216 1373700096 -0.1293502897 -0.3703593612 -0.1167039946 1204 1311867210.5943870544 0.0586298071 0.0598869303 0.0879767612 0.0054463031 0.0103650000 40497813 955859216 1373700096 -0.1288108826 -0.3695065081 -0.1175429150 1205 1311867210.6260209084 0.0582941473 0.0598856085 0.0879767612 0.0054506845 0.0057200000 40500573 955859216 1373700096 -0.1289357245 -0.3707150519 -0.1182095259 1206 1311867210.6675710678 0.0588569790 0.0598847556 0.0879767612 0.0054540298 0.0046390000 40503781 955859216 1373700096 -0.1299063861 -0.3718509674 -0.1186451986 1207 1311867210.6952280998 0.0595645495 0.0598844903 0.0879767612 0.0054555642 0.0077280000 40506597 955859216 1373700096 -0.1305971444 -0.3716206849 -0.1193098277 1208 1311867210.7260899544 0.0590027161 0.0598837604 0.0879767612 0.0054538286 0.0052740000 40509301 955859216 1373700096 -0.1298740506 -0.3714930415 -0.1197947711 1209 1311867210.7620921135 0.0589967445 0.0598830267 0.0879767612 0.0054530116 0.0073600000 40512341 955859216 1373700096 -0.1302378029 -0.3729866445 -0.1200046390 1210 1311867210.7943489552 0.0588372387 0.0598821624 0.0879767612 0.0054561031 0.0052970000 40514989 955859216 1373700096 -0.1296001524 -0.3713932037 -0.1202145144 1211 1311867210.8263258934 0.0584899336 0.0598810127 0.0879767612 0.0054548457 0.0070520000 40517861 955859216 1373700096 -0.1290975213 -0.3710018992 -0.1204040125 1212 1311867210.8623979092 0.0587614141 0.0598800890 0.0879767612 0.0054527446 0.0049270000 40520845 955859216 1373700096 -0.1295681745 -0.3712406754 -0.1202979535 1213 1311867210.8942279816 0.0580717884 0.0598785982 0.0879767612 0.0054506922 0.0095640000 40523773 955859216 1373700096 -0.1283375919 -0.3710124493 -0.1203418076 1214 1311867210.9288311005 0.0579210632 0.0598769857 0.0879767612 0.0054484996 0.0055190000 40526701 955859216 1373700096 -0.1279834211 -0.3707870841 -0.1201738045 1215 1311867210.9653480053 0.0577114634 0.0598752034 0.0879767612 0.0054557364 0.0044710000 40529685 955859216 1373700096 -0.1273413748 -0.3688669801 -0.1199205890 1216 1311867210.9945580959 0.0569401123 0.0598727897 0.0879767612 0.0054624625 0.0101840000 40532501 955859216 1373700096 -0.1268452406 -0.3696981966 -0.1200133562 1217 1311867211.0263500214 0.0571059212 0.0598705162 0.0879767612 0.0054604494 0.0058610000 40535373 955859216 1373700096 -0.1276276559 -0.3702695072 -0.1201114208 1218 1311867211.0651569366 0.0569881871 0.0598681497 0.0879767612 0.0054648850 0.0046860000 40538413 955859216 1373700096 -0.1269887686 -0.3683952391 -0.1201568320 1219 1311867211.0940821171 0.0566600934 0.0598655180 0.0879767612 0.0054663361 0.0067810000 40541173 955859216 1373700096 -0.1270607710 -0.3690953255 -0.1205704808 1220 1311867211.1266880035 0.0563857593 0.0598626658 0.0879767612 0.0054650864 0.0048930000 40544045 955859216 1373700096 -0.1271780431 -0.3706453145 -0.1207343265 1221 1311867211.1646990776 0.0566415787 0.0598600277 0.0879767612 0.0054633715 0.0107480000 40547141 955859216 1373700096 -0.1272197813 -0.3696473539 -0.1210673079 1222 1311867211.1946630478 0.0568003319 0.0598575239 0.0879767612 0.0054612659 0.0057820000 40549957 955859216 1373700096 -0.1273050904 -0.3693350852 -0.1212714463 1223 1311867211.2270209789 0.0569361933 0.0598551352 0.0879767612 0.0054667868 0.0046880000 40552829 955859216 1373700096 -0.1282767355 -0.3703786433 -0.1214400455 1224 1311867211.2645599842 0.0566024855 0.0598524778 0.0879767612 0.0054652343 0.0042540000 40555869 955859216 1373700096 -0.1279808730 -0.3698242009 -0.1217446551 1225 1311867211.2953100204 0.0568600819 0.0598500350 0.0879767612 0.0054631651 0.0042030000 40558741 955859216 1373700096 -0.1279456615 -0.3689481616 -0.1216726601 1226 1311867211.3262948990 0.0565941036 0.0598473793 0.0879767612 0.0054612754 0.0116370000 40561557 955859216 1373700096 -0.1274646521 -0.3683947921 -0.1219036952 1227 1311867211.3653290272 0.0570118502 0.0598450683 0.0879767612 0.0054590745 0.0059890000 40564653 955859216 1373700096 -0.1281453073 -0.3684357703 -0.1217691153 1228 1311867211.3949019909 0.0569726378 0.0598427292 0.0879767612 0.0054573916 0.0077050000 40567469 955859216 1373700096 -0.1279592961 -0.3676814139 -0.1216357946 1229 1311867211.4295680523 0.0569480099 0.0598403739 0.0879767612 0.0054623849 0.0053210000 40570341 955859216 1373700096 -0.1275682449 -0.3664639592 -0.1214544326 1230 1311867211.4645059109 0.0569487549 0.0598380230 0.0879767612 0.0054609681 0.0046400000 40573269 955859216 1373700096 -0.1279964596 -0.3664111793 -0.1215636432 1231 1311867211.4942829609 0.0576596074 0.0598362533 0.0879767612 0.0054590149 0.0042230000 40576085 955859216 1373700096 -0.1286435276 -0.3651555777 -0.1213736013 1232 1311867211.5279569626 0.0566962957 0.0598337047 0.0879767612 0.0054588254 0.0042080000 40578957 955859216 1373700096 -0.1279931813 -0.3644545078 -0.1212887615 1233 1311867211.5646700859 0.0578645691 0.0598321077 0.0879767612 0.0054605726 0.0041950000 40581997 955859216 1373700096 -0.1281210780 -0.3642632067 -0.1210336387 1234 1311867211.5967590809 0.0583248883 0.0598308862 0.0879767612 0.0054626102 0.0042110000 40584869 955859216 1373700096 -0.1291073114 -0.3644060194 -0.1208672523 1235 1311867211.6269431114 0.0592106245 0.0598303840 0.0879767612 0.0054683342 0.0042140000 40587685 955859216 1373700096 -0.1297231317 -0.3635801673 -0.1205212325 1236 1311867211.6620280743 0.0579002202 0.0598288224 0.0879767612 0.0054793284 0.0042020000 40590669 955859216 1373700096 -0.1285424232 -0.3629249334 -0.1205807924 1237 1311867211.6944348812 0.0583823547 0.0598276531 0.0879767612 0.0054810194 0.0041880000 40593541 955859216 1373700096 -0.1291715205 -0.3630005717 -0.1208232045 1238 1311867211.7267570496 0.0578220561 0.0598260330 0.0879767612 0.0054796425 0.0041930000 40596357 955859216 1373700096 -0.1284297705 -0.3627407849 -0.1210608482 1239 1311867211.7642099857 0.0576283634 0.0598242593 0.0879767612 0.0054777899 0.0041910000 40599453 955859216 1373700096 -0.1275117695 -0.3628268242 -0.1213595942 1240 1311867211.7948160172 0.0576594584 0.0598225135 0.0879767612 0.0054763148 0.0041310000 40602157 955859216 1373700096 -0.1271907389 -0.3623374999 -0.1218487322 1241 1311867211.8337268829 0.0583384968 0.0598213176 0.0879767612 0.0054743550 0.0121850000 40605197 955859216 1373700096 -0.1277290732 -0.3620200157 -0.1222723797 1242 1311867211.8630928993 0.0590206608 0.0598206730 0.0879767612 0.0054730144 0.0080080000 40608013 955859216 1373700096 -0.1280264556 -0.3607384264 -0.1224125177 1243 1311867211.8967690468 0.0586751848 0.0598197514 0.0879767612 0.0054708249 0.0054370000 40610885 955859216 1373700096 -0.1275028884 -0.3596259356 -0.1228123978 1244 1311867211.9324300289 0.0590805970 0.0598191573 0.0879767612 0.0054707712 0.0045460000 40613869 955859216 1373700096 -0.1281204969 -0.3592529595 -0.1234562099 1245 1311867211.9653239250 0.0591448657 0.0598186157 0.0879767612 0.0054686211 0.0047270000 40616797 955859216 1373700096 -0.1277876943 -0.3585377634 -0.1238617077 1246 1311867211.9972860813 0.0590976253 0.0598180370 0.0879767612 0.0054667140 0.0042390000 40619613 955859216 1373700096 -0.1271651536 -0.3563537598 -0.1243973821 1247 1311867212.0317659378 0.0594416223 0.0598177352 0.0879767612 0.0054647528 0.0041560000 40622597 955859216 1373700096 -0.1273317486 -0.3555974960 -0.1247321293 1248 1311867212.0621519089 0.0598461963 0.0598177580 0.0879767612 0.0054626849 0.0042020000 40625413 955859216 1373700096 -0.1279509664 -0.3550581634 -0.1251453310 1249 1311867212.0954549313 0.0592854954 0.0598173318 0.0879767612 0.0054629620 0.0122680000 40628285 955859216 1373700096 -0.1263204217 -0.3529573381 -0.1252057552 1250 1311867212.1331028938 0.0586727671 0.0598164162 0.0879767612 0.0054628903 0.0064430000 40631325 955859216 1373700096 -0.1254174560 -0.3514007032 -0.1256037951 1251 1311867212.1668488979 0.0590503179 0.0598158038 0.0879767612 0.0054615984 0.0048970000 40634197 955859216 1373700096 -0.1259474456 -0.3507538438 -0.1260143369 1252 1311867212.1945068836 0.0591236167 0.0598152509 0.0879767612 0.0054597150 0.0042840000 40636957 955859216 1373700096 -0.1255467683 -0.3499824405 -0.1262882799 1253 1311867212.2301759720 0.0592093728 0.0598147674 0.0879767612 0.0054602509 0.0067680000 40639885 955859216 1373700096 -0.1251441389 -0.3485547006 -0.1270536631 1254 1311867212.2647190094 0.0593026876 0.0598143590 0.0879767612 0.0054601837 0.0049740000 40642869 955859216 1373700096 -0.1247849017 -0.3479973078 -0.1278623044 1255 1311867212.2944819927 0.0594064146 0.0598140340 0.0879767612 0.0054581314 0.0076870000 40645685 955859216 1373700096 -0.1246681437 -0.3469837308 -0.1288055629 1256 1311867212.3326430321 0.0590868331 0.0598134550 0.0879767612 0.0054568301 0.0053840000 40648725 955859216 1373700096 -0.1238445267 -0.3451814950 -0.1296640188 1257 1311867212.3653640747 0.0589206032 0.0598127447 0.0879767612 0.0054547601 0.0043310000 40651597 955859216 1373700096 -0.1233330145 -0.3433345556 -0.1304513663 1258 1311867212.3955509663 0.0596899167 0.0598126470 0.0879767612 0.0054711492 0.0108400000 40654413 955859216 1373700096 -0.1233355626 -0.3417488933 -0.1310819387 1259 1311867212.4329519272 0.0589138046 0.0598119331 0.0879767612 0.0054893664 0.0057880000 40657453 955859216 1373700096 -0.1227001771 -0.3402673602 -0.1316332370 1260 1311867212.4622640610 0.0594086982 0.0598116131 0.0879767612 0.0054977526 0.0047670000 40660269 955859216 1373700096 -0.1227110848 -0.3385718465 -0.1319811642 1261 1311867212.4944300652 0.0593619496 0.0598112565 0.0879767612 0.0055016679 0.0042270000 40663141 955859216 1373700096 -0.1222084239 -0.3377948999 -0.1325384378 1262 1311867212.5300269127 0.0594740361 0.0598109893 0.0879767612 0.0055003838 0.0041850000 40666125 955859216 1373700096 -0.1217888296 -0.3371622264 -0.1332914084 1263 1311867212.5625970364 0.0597737394 0.0598109598 0.0879767612 0.0055091463 0.0116160000 40668997 955859216 1373700096 -0.1209787875 -0.3364052474 -0.1341363490 1264 1311867212.5948359966 0.0591999702 0.0598104764 0.0879767612 0.0055084536 0.0061010000 40671869 955859216 1373700096 -0.1195647195 -0.3358615935 -0.1350950748 1265 1311867212.6323919296 0.0579201467 0.0598089821 0.0879767612 0.0055082905 0.0077000000 40674797 955859216 1373700096 -0.1166328117 -0.3359123468 -0.1358587444 1266 1311867212.6629829407 0.0574938320 0.0598071534 0.0879767612 0.0055111486 0.0054090000 40677613 955859216 1373700096 -0.1150507405 -0.3343213499 -0.1366465837 1267 1311867212.6944150925 0.0575961620 0.0598054083 0.0879767612 0.0055093065 0.0076550000 40680541 955859216 1373700096 -0.1143492460 -0.3330836594 -0.1374761164 1268 1311867212.7323219776 0.0575148426 0.0598036019 0.0879767612 0.0055081439 0.0052180000 40683525 955859216 1373700096 -0.1137192771 -0.3324189186 -0.1383286268 1269 1311867212.7618949413 0.0578004420 0.0598020233 0.0879767612 0.0055062416 0.0075710000 40686285 955859216 1373700096 -0.1140146330 -0.3308661282 -0.1391841173 1270 1311867212.7951610088 0.0579177551 0.0598005396 0.0879767612 0.0055041026 0.0053420000 40689213 955859216 1373700096 -0.1138311476 -0.3297475278 -0.1397685260 1271 1311867212.8303771019 0.0581174679 0.0597992154 0.0879767612 0.0055020700 0.0071270000 40692253 955859216 1373700096 -0.1135691628 -0.3287805915 -0.1406311691 1272 1311867212.8625240326 0.0584133640 0.0597981259 0.0879767612 0.0055022224 0.0050370000 40695069 955859216 1373700096 -0.1133870631 -0.3283807039 -0.1415336579 1273 1311867212.8941800594 0.0582650639 0.0597969216 0.0879767612 0.0055118428 0.0044820000 40697941 955859216 1373700096 -0.1129588336 -0.3269083202 -0.1425474733 1274 1311867212.9306590557 0.0575178191 0.0597951327 0.0879767612 0.0055205958 0.0104000000 40700925 955859216 1373700096 -0.1122080758 -0.3253039718 -0.1433395594 1275 1311867212.9621579647 0.0575131066 0.0597933429 0.0879767612 0.0055384275 0.0062050000 40703797 955859216 1373700096 -0.1110378876 -0.3238191903 -0.1442513764 1276 1311867212.9971981049 0.0575742796 0.0597916038 0.0879767612 0.0055411199 0.0047570000 40706725 955859216 1373700096 -0.1101174280 -0.3222851157 -0.1449940354 1277 1311867213.0305559635 0.0575522035 0.0597898502 0.0879767612 0.0055437445 0.0043130000 40709709 955859216 1373700096 -0.1099237129 -0.3214110136 -0.1454581022 1278 1311867213.0622329712 0.0578142144 0.0597883043 0.0879767612 0.0055421398 0.0041660000 40712525 955859216 1373700096 -0.1096160933 -0.3206305206 -0.1458506435 1279 1311867213.0985310078 0.0573518053 0.0597863993 0.0879767612 0.0055403940 0.0118230000 40715509 955859216 1373700096 -0.1083702371 -0.3193736076 -0.1465626508 1280 1311867213.1321671009 0.0573847704 0.0597845230 0.0879767612 0.0055382384 0.0063610000 40718437 955859216 1373700096 -0.1071046591 -0.3182495534 -0.1471992880 1281 1311867213.1642329693 0.0580039211 0.0597831330 0.0879767612 0.0055362808 0.0069120000 40721309 955859216 1373700096 -0.1071000770 -0.3172962368 -0.1478669494 1282 1311867213.1981649399 0.0583882816 0.0597820450 0.0879767612 0.0055369708 0.0051530000 40724237 955859216 1373700096 -0.1074344367 -0.3168594539 -0.1488222033 1283 1311867213.2303979397 0.0596432090 0.0597819368 0.0879767612 0.0055353934 0.0045120000 40727109 955859216 1373700096 -0.1079726219 -0.3156856894 -0.1492261440 1284 1311867213.2621340752 0.0594122186 0.0597816488 0.0879767612 0.0055334136 0.0041890000 40729981 955859216 1373700096 -0.1067662612 -0.3140839040 -0.1502623260 1285 1311867213.2983639240 0.0597594902 0.0597816316 0.0879767612 0.0055316138 0.0106280000 40732965 955859216 1373700096 -0.1066515744 -0.3133205473 -0.1510747671 1286 1311867213.3312969208 0.0595419258 0.0597814452 0.0879767612 0.0055312620 0.0059680000 40735893 955859216 1373700096 -0.1058768779 -0.3112097681 -0.1516318023 1287 1311867213.3622069359 0.0590900369 0.0597809080 0.0879767612 0.0055293000 0.0079470000 40738709 955859216 1373700096 -0.1052134484 -0.3091044128 -0.1524698287 1288 1311867213.3980619907 0.0596070811 0.0597807730 0.0879767612 0.0055273322 0.0053910000 40741693 955859216 1373700096 -0.1049396098 -0.3077270687 -0.1526646316 1289 1311867213.4303960800 0.0590772219 0.0597802272 0.0879767612 0.0055260358 0.0046090000 40744621 955859216 1373700096 -0.1032014564 -0.3058932722 -0.1529358923 1290 1311867213.4620630741 0.0594187826 0.0597799470 0.0879767612 0.0055243171 0.0044800000 40747437 955859216 1373700096 -0.1032650173 -0.3045101762 -0.1533632278 1291 1311867213.4981389046 0.0591494031 0.0597794586 0.0879767612 0.0055272062 0.0044670000 40750421 955859216 1373700096 -0.1028568968 -0.3024079502 -0.1537351906 1292 1311867213.5318338871 0.0584177896 0.0597784047 0.0879767612 0.0055279510 0.0044310000 40753349 955859216 1373700096 -0.1017054915 -0.3003718853 -0.1539444476 1293 1311867213.5621318817 0.0578028597 0.0597768768 0.0879767612 0.0055258597 0.0044700000 40756165 955859216 1373700096 -0.1003612652 -0.2987611890 -0.1539910883 1294 1311867213.5989580154 0.0576224923 0.0597752119 0.0879767612 0.0055281087 0.0044640000 40759205 955859216 1373700096 -0.0996405184 -0.2965151966 -0.1541000158 1295 1311867213.6327760220 0.0574183837 0.0597733919 0.0879767612 0.0055262601 0.0045170000 40762077 955859216 1373700096 -0.0986593664 -0.2935380638 -0.1541764587 1296 1311867213.6623249054 0.0580169037 0.0597720366 0.0879767612 0.0055261018 0.0045370000 40764893 955859216 1373700096 -0.0985006467 -0.2914043665 -0.1539991498 1297 1311867213.6987268925 0.0583384894 0.0597709313 0.0879767612 0.0055250804 0.0044360000 40767877 955859216 1373700096 -0.0978941917 -0.2890724540 -0.1537604183 1298 1311867213.7312800884 0.0582376532 0.0597697501 0.0879767612 0.0055294044 0.0045230000 40770805 955859216 1373700096 -0.0964957103 -0.2871780097 -0.1536285579 1299 1311867213.7623159885 0.0576400422 0.0597681106 0.0879767612 0.0055373204 0.0044680000 40773621 955859216 1373700096 -0.0952959582 -0.2853605747 -0.1531572938 1300 1311867213.7984969616 0.0577958934 0.0597665935 0.0879767612 0.0055354394 0.0045690000 40776493 955859216 1373700096 -0.0944876671 -0.2830316424 -0.1528042257 1301 1311867213.8303530216 0.0572622567 0.0597646686 0.0879767612 0.0055335727 0.0045390000 40779365 955859216 1373700096 -0.0924071223 -0.2813445330 -0.1523007900 1302 1311867213.8669381142 0.0579885244 0.0597633044 0.0879767612 0.0055347822 0.0044680000 40782349 955859216 1373700096 -0.0929417387 -0.2813865244 -0.1520869881 1303 1311867213.8988749981 0.0586809106 0.0597624737 0.0879767612 0.0055330875 0.0044860000 40785221 955859216 1373700096 -0.0929082856 -0.2798192203 -0.1520200372 1304 1311867213.9324591160 0.0588783883 0.0597617957 0.0879767612 0.0055325463 0.0044270000 40788093 955859216 1373700096 -0.0922592282 -0.2773307562 -0.1519193053 1305 1311867213.9625511169 0.0588432066 0.0597610918 0.0879767612 0.0055310267 0.0044550000 40790909 955859216 1373700096 -0.0915394947 -0.2764040232 -0.1523885280 1306 1311867214.0014989376 0.0595542528 0.0597609334 0.0879767612 0.0055300153 0.0046140000 40794061 955859216 1373700096 -0.0914354622 -0.2751159072 -0.1529564857 1307 1311867214.0316550732 0.0591205545 0.0597604435 0.0879767612 0.0055312529 0.0045420000 40796821 955859216 1373700096 -0.0908847675 -0.2731656730 -0.1533494592 1308 1311867214.0640029907 0.0588507280 0.0597597480 0.0879767612 0.0055297280 0.0045270000 40799749 955859216 1373700096 -0.0894608945 -0.2708485723 -0.1536684781 1309 1311867214.0984749794 0.0588892326 0.0597590830 0.0879767612 0.0055281235 0.0045300000 40802677 955859216 1373700096 -0.0887658820 -0.2695577443 -0.1540320814 1310 1311867214.1326990128 0.0592976026 0.0597587307 0.0879767612 0.0055279404 0.0045020000 40805549 955859216 1373700096 -0.0884980708 -0.2679863870 -0.1540848613 1311 1311867214.1643800735 0.0595790073 0.0597585936 0.0879767612 0.0055283634 0.0045030000 40808477 955859216 1373700096 -0.0881246701 -0.2662608624 -0.1539409459 1312 1311867214.2013020515 0.0594716743 0.0597583749 0.0879767612 0.0055265675 0.0045380000 40811405 955859216 1373700096 -0.0878045708 -0.2651972175 -0.1542471647 1313 1311867214.2338430882 0.0600969195 0.0597586327 0.0879767612 0.0055246585 0.0044760000 40814333 955859216 1373700096 -0.0881722271 -0.2639814317 -0.1540924907 1314 1311867214.2674899101 0.0599396415 0.0597587705 0.0879767612 0.0055228519 0.0045450000 40817261 955859216 1373700096 -0.0876546353 -0.2625825703 -0.1542361677 1315 1311867214.3004720211 0.0596638769 0.0597586983 0.0879767612 0.0055209063 0.0045120000 40820133 955859216 1373700096 -0.0871681497 -0.2606905699 -0.1543638408 1316 1311867214.3310549259 0.0595254749 0.0597585211 0.0879767612 0.0055188608 0.0045020000 40822949 955859216 1373700096 -0.0870267376 -0.2597040534 -0.1547896862 1317 1311867214.3663671017 0.0599915758 0.0597586981 0.0879767612 0.0055186670 0.0045130000 40825933 955859216 1373700096 -0.0870302990 -0.2583512068 -0.1549706161 1318 1311867214.3980031013 0.0603914745 0.0597591782 0.0879767612 0.0055167171 0.0044490000 40828805 955859216 1373700096 -0.0869218856 -0.2575477660 -0.1554119140 1319 1311867214.4332211018 0.0602877364 0.0597595789 0.0879767612 0.0055161541 0.0045280000 40831733 955859216 1373700096 -0.0864153653 -0.2565221786 -0.1560522020 1320 1311867214.4698181152 0.0603244752 0.0597600069 0.0879767612 0.0055184149 0.0045890000 40834885 955859216 1373700096 -0.0860534161 -0.2550475299 -0.1566064358 1321 1311867214.5059390068 0.0601978041 0.0597603383 0.0879767612 0.0055186781 0.0044780000 40837869 955859216 1373700096 -0.0847065896 -0.2535128891 -0.1569219083 1322 1311867214.5373690128 0.0599357374 0.0597604709 0.0879767612 0.0055176216 0.0044880000 40840741 955859216 1373700096 -0.0835638493 -0.2515805960 -0.1572665274 1323 1311867214.5691421032 0.0598034076 0.0597605034 0.0879767612 0.0055160626 0.0045010000 40843613 955859216 1373700096 -0.0830437690 -0.2496560812 -0.1575099081 1324 1311867214.6048638821 0.0597686321 0.0597605095 0.0879767612 0.0055144664 0.0046070000 40846597 955859216 1373700096 -0.0824281350 -0.2474975735 -0.1577960551 1325 1311867214.6369891167 0.0595242828 0.0597603313 0.0879767612 0.0055141168 0.0045670000 40849413 955859216 1373700096 -0.0816047564 -0.2468296140 -0.1578570902 1326 1311867214.6691009998 0.0596147999 0.0597602215 0.0879767612 0.0055124280 0.0045310000 40852341 955859216 1373700096 -0.0809696987 -0.2451813817 -0.1579612792 1327 1311867214.7048900127 0.0603987128 0.0597607027 0.0879767612 0.0055112963 0.0045440000 40855269 955859216 1373700096 -0.0805676877 -0.2445005476 -0.1580874175 1328 1311867214.7369639874 0.0605571941 0.0597613024 0.0879767612 0.0055154387 0.0045510000 40858141 955859216 1373700096 -0.0801913738 -0.2428352237 -0.1582767963 1329 1311867214.7695059776 0.0601319969 0.0597615813 0.0879767612 0.0055161282 0.0045720000 40861069 955859216 1373700096 -0.0791257620 -0.2418468148 -0.1584430635 1330 1311867214.8049929142 0.0602679402 0.0597619621 0.0879767612 0.0055151964 0.0045450000 40864053 955859216 1373700096 -0.0790125206 -0.2401225418 -0.1593119502 1331 1311867214.8369181156 0.0598136857 0.0597620009 0.0879767612 0.0055155978 0.0045340000 40866869 955859216 1373700096 -0.0782727003 -0.2397561371 -0.1596743315 1332 1311867214.8699979782 0.0603631772 0.0597624523 0.0879767612 0.0055144105 0.0045040000 40869797 955859216 1373700096 -0.0782221183 -0.2378341258 -0.1598311365 1333 1311867214.9049839973 0.0596582890 0.0597623741 0.0879767612 0.0055125997 0.0046840000 40872781 955859216 1373700096 -0.0768611208 -0.2357943803 -0.1603588313 1334 1311867214.9372529984 0.0594775937 0.0597621606 0.0879767612 0.0055127295 0.0049170000 40875653 955859216 1373700096 -0.0761020333 -0.2344627678 -0.1608923376 1335 1311867214.9693040848 0.0593793876 0.0597618739 0.0879767612 0.0055116580 0.0045970000 40878525 955859216 1373700096 -0.0754332989 -0.2322728783 -0.1611009836 1336 1311867215.0050640106 0.0589203723 0.0597612441 0.0879767612 0.0055097575 0.0045230000 40881565 955859216 1373700096 -0.0741868317 -0.2295105457 -0.1610391140 1337 1311867215.0371069908 0.0587288104 0.0597604719 0.0879767612 0.0055089833 0.0045200000 40884325 955859216 1373700096 -0.0744006038 -0.2286670804 -0.1614160389 1338 1311867215.0692911148 0.0588106439 0.0597597620 0.0879767612 0.0055074946 0.0046770000 40887253 955859216 1373700096 -0.0741035715 -0.2262191921 -0.1612013578 1339 1311867215.1050040722 0.0582317561 0.0597586208 0.0879767612 0.0055070622 0.0045990000 40890237 955859216 1373700096 -0.0729248300 -0.2233884931 -0.1609211117 1340 1311867215.1369140148 0.0573909432 0.0597568539 0.0879767612 0.0055051724 0.0045980000 40893053 955859216 1373700096 -0.0712012202 -0.2219820172 -0.1603588313 1341 1311867215.1694459915 0.0575459450 0.0597552052 0.0879767612 0.0055045065 0.0045790000 40896037 955859216 1373700096 -0.0708408877 -0.2211779803 -0.1600610316 1342 1311867215.2049460411 0.0568036474 0.0597530058 0.0879767612 0.0055036550 0.0045340000 40898965 955859216 1373700096 -0.0698522553 -0.2186868936 -0.1598299295 1343 1311867215.2369511127 0.0568721816 0.0597508607 0.0879767612 0.0055017403 0.0045470000 40901781 955859216 1373700096 -0.0693738386 -0.2172832936 -0.1596052796 1344 1311867215.2690820694 0.0569392331 0.0597487688 0.0879767612 0.0054998994 0.0045630000 40904709 955859216 1373700096 -0.0695471764 -0.2165586352 -0.1593089402 1345 1311867215.3049569130 0.0572032779 0.0597468762 0.0879767612 0.0054994322 0.0045450000 40907693 955859216 1373700096 -0.0688881874 -0.2143201381 -0.1593971550 1346 1311867215.3369619846 0.0574045703 0.0597451360 0.0879767612 0.0054983762 0.0046140000 40910565 955859216 1373700096 -0.0687475204 -0.2130146772 -0.1594887823 1347 1311867215.3691840172 0.0569088310 0.0597430304 0.0879767612 0.0054990250 0.0045400000 40913437 955859216 1373700096 -0.0684840009 -0.2123484761 -0.1595542729 1348 1311867215.4049520493 0.0568278842 0.0597408678 0.0879767612 0.0054980220 0.0078300000 40916421 955859216 1373700096 -0.0672037527 -0.2099838853 -0.1597445607 1349 1311867215.4370350838 0.0567412451 0.0597386442 0.0879767612 0.0054963845 0.0053960000 40919237 955859216 1373700096 -0.0660529360 -0.2083711624 -0.1600653082 1350 1311867215.4690899849 0.0570666082 0.0597366649 0.0879767612 0.0054964015 0.0071490000 40922165 955859216 1373700096 -0.0653546080 -0.2070219368 -0.1603425741 1351 1311867215.5049800873 0.0569840409 0.0597346274 0.0879767612 0.0054966883 0.0051710000 40925149 955859216 1373700096 -0.0644769147 -0.2052875608 -0.1605081856 1352 1311867215.5371229649 0.0566438064 0.0597323413 0.0879767612 0.0054948735 0.0094180000 40927965 955859216 1373700096 -0.0637377650 -0.2030712515 -0.1610047519 1353 1311867215.5690340996 0.0567669980 0.0597301497 0.0879767612 0.0054935840 0.0056860000 40930893 955859216 1373700096 -0.0631022677 -0.2021123320 -0.1613026112 1354 1311867215.6050848961 0.0569595657 0.0597281034 0.0879767612 0.0054924151 0.0047640000 40933877 955859216 1373700096 -0.0622934103 -0.2001445740 -0.1612168849 1355 1311867215.6370549202 0.0562092066 0.0597255065 0.0879767612 0.0054911536 0.0105470000 40936749 955859216 1373700096 -0.0604775809 -0.1974235177 -0.1609210074 1356 1311867215.6689219475 0.0559291542 0.0597227068 0.0879767612 0.0054896655 0.0059150000 40939621 955859216 1373700096 -0.0601744168 -0.1966395676 -0.1610677391 1357 1311867215.7049510479 0.0560005009 0.0597199638 0.0879767612 0.0054894019 0.0048600000 40942605 955859216 1373700096 -0.0598337837 -0.1950731575 -0.1612612158 1358 1311867215.7388830185 0.0556305684 0.0597169525 0.0879767612 0.0054878846 0.0044830000 40945533 955859216 1373700096 -0.0586914904 -0.1922745854 -0.1611858010 1359 1311867215.7691988945 0.0557022206 0.0597139983 0.0879767612 0.0054860173 0.0043980000 40948237 955859216 1373700096 -0.0586091392 -0.1908644140 -0.1611625105 1360 1311867215.8048830032 0.0553032495 0.0597107551 0.0879767612 0.0054876355 0.0124890000 40951221 955859216 1373700096 -0.0578709319 -0.1900909692 -0.1612440795 1361 1311867215.8373351097 0.0554406419 0.0597076176 0.0879767612 0.0054862401 0.0064610000 40954093 955859216 1373700096 -0.0575521030 -0.1887394339 -0.1613755524 1362 1311867215.8691670895 0.0559705794 0.0597048738 0.0879767612 0.0054846234 0.0136950000 40957021 955859216 1373700096 -0.0574301146 -0.1876318902 -0.1616422385 1363 1311867215.9052760601 0.0564658754 0.0597024975 0.0879767612 0.0054828725 0.0066380000 40960005 955859216 1373700096 -0.0582299791 -0.1876911074 -0.1620303094 1364 1311867215.9370880127 0.0559972078 0.0596997810 0.0879767612 0.0054808835 0.0052490000 40962821 955859216 1373700096 -0.0571359806 -0.1870808899 -0.1625123024 1365 1311867215.9702870846 0.0561295860 0.0596971654 0.0879767612 0.0054789634 0.0046010000 40965749 955859216 1373700096 -0.0568572357 -0.1855354160 -0.1626904309 1366 1311867216.0050790310 0.0562160201 0.0596946170 0.0879767612 0.0054782342 0.0045210000 40968733 955859216 1373700096 -0.0568680838 -0.1845469177 -0.1632654965 1367 1311867216.0369679928 0.0561637394 0.0596920341 0.0879767612 0.0054763754 0.0044360000 40971549 955859216 1373700096 -0.0562247187 -0.1834767610 -0.1635770053 1368 1311867216.0694830418 0.0557575189 0.0596891580 0.0879767612 0.0054753879 0.0127870000 40974477 955859216 1373700096 -0.0553286113 -0.1824392080 -0.1638135612 1369 1311867216.1050429344 0.0558484606 0.0596863525 0.0879767612 0.0054737771 0.0065900000 40977461 955859216 1373700096 -0.0545552969 -0.1808512211 -0.1634896547 1370 1311867216.1392951012 0.0554175489 0.0596832366 0.0879767612 0.0054720362 0.0050850000 40980389 955859216 1373700096 -0.0537577271 -0.1796509326 -0.1635106951 1371 1311867216.1692190170 0.0552617721 0.0596800116 0.0879767612 0.0054709378 0.0045010000 40983205 955859216 1373700096 -0.0531663932 -0.1777653545 -0.1632901728 1372 1311867216.2049610615 0.0547315478 0.0596764048 0.0879767612 0.0054690256 0.0046050000 40986189 955859216 1373700096 -0.0518626831 -0.1752434075 -0.1631063968 1373 1311867216.2370231152 0.0546016172 0.0596727087 0.0879767612 0.0054680176 0.0117530000 40989005 955859216 1373700096 -0.0517023951 -0.1745206267 -0.1623901278 1374 1311867216.2706630230 0.0546941161 0.0596690853 0.0879767612 0.0054676939 0.0062120000 40991989 955859216 1373700096 -0.0517279543 -0.1731419116 -0.1617453992 1375 1311867216.3050479889 0.0544243306 0.0596652709 0.0879767612 0.0054658678 0.0049850000 40994917 955859216 1373700096 -0.0508075990 -0.1708143950 -0.1611191481 1376 1311867216.3395419121 0.0536888465 0.0596609276 0.0879767612 0.0054656206 0.0045090000 40997901 955859216 1373700096 -0.0499769524 -0.1691184789 -0.1607697755 1377 1311867216.3694689274 0.0533563085 0.0596563491 0.0879767612 0.0054637782 0.0046050000 41000661 955859216 1373700096 -0.0490420051 -0.1678201407 -0.1602280736 1378 1311867216.4055120945 0.0534402058 0.0596518381 0.0879767612 0.0054618501 0.0118580000 41003701 955859216 1373700096 -0.0487515330 -0.1664886922 -0.1597003937 1379 1311867216.4373409748 0.0531151332 0.0596470979 0.0879767612 0.0054599011 0.0063010000 41006461 955859216 1373700096 -0.0482582450 -0.1651747972 -0.1595181823 1380 1311867216.4697530270 0.0529687591 0.0596422585 0.0879767612 0.0054581530 0.0049880000 41009445 955859216 1373700096 -0.0482268520 -0.1632191837 -0.1592909396 1381 1311867216.5049800873 0.0526772030 0.0596372150 0.0879767612 0.0054569965 0.0045620000 41012373 955859216 1373700096 -0.0467557721 -0.1617710888 -0.1588218957 1382 1311867216.5372259617 0.0529572666 0.0596323815 0.0879767612 0.0054551666 0.0085390000 41015245 955859216 1373700096 -0.0464988425 -0.1613571644 -0.1583372951 1383 1311867216.5693330765 0.0531812832 0.0596277169 0.0879767612 0.0054533957 0.0084650000 41018117 955859216 1373700096 -0.0469236635 -0.1602264941 -0.1581660360 1384 1311867216.6050319672 0.0535055138 0.0596232934 0.0879767612 0.0054537433 0.0057110000 41021101 955859216 1373700096 -0.0463108383 -0.1591284424 -0.1576690227 1385 1311867216.6373488903 0.0534069911 0.0596188051 0.0879767612 0.0054528069 0.0048230000 41023973 955859216 1373700096 -0.0451337770 -0.1581476927 -0.1574800462 1386 1311867216.6691188812 0.0541323051 0.0596148466 0.0879767612 0.0054514273 0.0103360000 41026845 955859216 1373700096 -0.0458252244 -0.1577700526 -0.1574804932 1387 1311867216.7052359581 0.0536164828 0.0596105218 0.0879767612 0.0054501332 0.0059010000 41029829 955859216 1373700096 -0.0447684415 -0.1564872414 -0.1573667675 1388 1311867216.7372078896 0.0538631864 0.0596063811 0.0879767612 0.0054487509 0.0049930000 41032645 955859216 1373700096 -0.0446274877 -0.1552724242 -0.1573605984 1389 1311867216.7691950798 0.0536684692 0.0596021062 0.0879767612 0.0054469517 0.0078680000 41035573 955859216 1373700096 -0.0440642722 -0.1546581537 -0.1576292366 1390 1311867216.8050019741 0.0540672094 0.0595981242 0.0879767612 0.0054453930 0.0055780000 41038557 955859216 1373700096 -0.0433376469 -0.1538043022 -0.1576245725 1391 1311867216.8379631042 0.0539577678 0.0595940693 0.0879767612 0.0054435919 0.0048060000 41041429 955859216 1373700096 -0.0427122712 -0.1528828293 -0.1576498896 1392 1311867216.8703401089 0.0535530448 0.0595897295 0.0879767612 0.0054430187 0.0112450000 41044301 955859216 1373700096 -0.0424846001 -0.1525861174 -0.1578610390 1393 1311867216.9049589634 0.0535940304 0.0595854254 0.0879767612 0.0054413053 0.0060830000 41047285 955859216 1373700096 -0.0420511030 -0.1516957879 -0.1580334157 1394 1311867216.9374070168 0.0539172180 0.0595813592 0.0879767612 0.0054394173 0.0049700000 41050101 955859216 1373700096 -0.0409672447 -0.1509653479 -0.1580983549 1395 1311867216.9691729546 0.0537430681 0.0595771740 0.0879767612 0.0054383401 0.0045630000 41052973 955859216 1373700096 -0.0407681167 -0.1495173573 -0.1580708176 1396 1311867217.0053269863 0.0534554496 0.0595727889 0.0879767612 0.0054382962 0.0111800000 41056013 955859216 1373700096 -0.0398658924 -0.1489398926 -0.1578977704 1397 1311867217.0373110771 0.0534082018 0.0595683761 0.0879767612 0.0054368063 0.0060680000 41058829 955859216 1373700096 -0.0391364917 -0.1479881853 -0.1578939259 1398 1311867217.0691289902 0.0540550649 0.0595644324 0.0879767612 0.0054365870 0.0049480000 41061701 955859216 1373700096 -0.0389961526 -0.1470095813 -0.1578338593 1399 1311867217.1052579880 0.0543411039 0.0595606988 0.0879767612 0.0054352527 0.0045690000 41064741 955859216 1373700096 -0.0390745699 -0.1459216326 -0.1577221006 1400 1311867217.1370849609 0.0540605821 0.0595567701 0.0879767612 0.0054348275 0.0045860000 41067557 955859216 1373700096 -0.0380490646 -0.1456193477 -0.1578128338 1401 1311867217.1691889763 0.0544462688 0.0595531224 0.0879767612 0.0054334576 0.0135870000 41070485 955859216 1373700096 -0.0382929258 -0.1449574530 -0.1579369158 1402 1311867217.2057919502 0.0545575619 0.0595495592 0.0879767612 0.0054318769 0.0134130000 41073469 955859216 1373700096 -0.0377760865 -0.1436786056 -0.1579305083 1403 1311867217.2371680737 0.0538525842 0.0595454987 0.0879767612 0.0054309761 0.0068060000 41076341 955859216 1373700096 -0.0374327898 -0.1433798820 -0.1584644467 1404 1311867217.2692279816 0.0541680492 0.0595416686 0.0879767612 0.0054299279 0.0052870000 41079213 955859216 1373700096 -0.0378682353 -0.1420045942 -0.1588039696 1405 1311867217.3051640987 0.0538611449 0.0595376255 0.0879767612 0.0054280290 0.0047190000 41082197 955859216 1373700096 -0.0367408916 -0.1404297650 -0.1588838547 1406 1311867217.3374049664 0.0532012694 0.0595331188 0.0879767612 0.0054263315 0.0047770000 41085069 955859216 1373700096 -0.0360422246 -0.1392813772 -0.1589823365 1407 1311867217.3695969582 0.0531998612 0.0595286176 0.0879767612 0.0054247162 0.0046930000 41087941 955859216 1373700096 -0.0368698798 -0.1381891519 -0.1587948799 1408 1311867217.4120450020 0.0530026406 0.0595239827 0.0879767612 0.0054236566 0.0138840000 41090981 955859216 1373700096 -0.0361166932 -0.1368909478 -0.1586983502 1409 1311867217.4372820854 0.0525814071 0.0595190554 0.0879767612 0.0054224857 0.0082110000 41093629 955859216 1373700096 -0.0351227485 -0.1360100657 -0.1587945074 1410 1311867217.4694299698 0.0528888404 0.0595143531 0.0879767612 0.0054214139 0.0061630000 41096557 955859216 1373700096 -0.0351618566 -0.1352109611 -0.1586053222 1411 1311867217.5050430298 0.0527580045 0.0595095647 0.0879767612 0.0054199623 0.0048560000 41099541 955859216 1373700096 -0.0351903364 -0.1339087188 -0.1588890553 1412 1311867217.5370678902 0.0526982062 0.0595047408 0.0879767612 0.0054181814 0.0045520000 41102357 955859216 1373700096 -0.0350631699 -0.1327358931 -0.1591896117 1413 1311867217.5691540241 0.0529893674 0.0595001298 0.0879767612 0.0054162998 0.0075730000 41105229 955859216 1373700096 -0.0348781087 -0.1317676008 -0.1589313298 1414 1311867217.6050539017 0.0524818823 0.0594951664 0.0879767612 0.0054147844 0.0054220000 41108269 955859216 1373700096 -0.0345758423 -0.1305994540 -0.1591392010 1415 1311867217.6370990276 0.0516915359 0.0594896515 0.0879767612 0.0054132991 0.0100530000 41111085 955859216 1373700096 -0.0338484757 -0.1288375556 -0.1592682004 1416 1311867217.6691000462 0.0510395803 0.0594836839 0.0879767612 0.0054124389 0.0060950000 41114013 955859216 1373700096 -0.0329911783 -0.1276343912 -0.1592723429 1417 1311867217.7050631046 0.0506996028 0.0594774848 0.0879767612 0.0054111565 0.0050260000 41116997 955859216 1373700096 -0.0311431363 -0.1266725957 -0.1591902226 1418 1311867217.7371540070 0.0508787371 0.0594714208 0.0879767612 0.0054094184 0.0080960000 41119813 955859216 1373700096 -0.0313196406 -0.1262716651 -0.1591288000 1419 1311867217.7694880962 0.0509542115 0.0594654186 0.0879767612 0.0054076107 0.0056100000 41122741 955859216 1373700096 -0.0308186598 -0.1255723238 -0.1591898203 1420 1311867217.8051838875 0.0510740727 0.0594595092 0.0879767612 0.0054057185 0.0073690000 41125725 955859216 1373700096 -0.0304322708 -0.1249485761 -0.1592387557 1421 1311867217.8372271061 0.0510054268 0.0594535598 0.0879767612 0.0054041303 0.0057170000 41128541 955859216 1373700096 -0.0297937952 -0.1247446686 -0.1594728380 1422 1311867217.8690850735 0.0507998317 0.0594474742 0.0879767612 0.0054027884 0.0088410000 41131469 955859216 1373700096 -0.0290090516 -0.1233769730 -0.1595379561 1423 1311867217.9056351185 0.0508233346 0.0594414136 0.0879767612 0.0054011867 0.0074950000 41134509 955859216 1373700096 -0.0288873333 -0.1217170283 -0.1595736593 1424 1311867217.9372580051 0.0505864806 0.0594351953 0.0879767612 0.0053997103 0.0079340000 41137269 955859216 1373700096 -0.0284898691 -0.1207049564 -0.1596448570 1425 1311867217.9711000919 0.0502714366 0.0594287646 0.0879767612 0.0053980022 0.0055850000 41140253 955859216 1373700096 -0.0279463604 -0.1189438328 -0.1595325172 1426 1311867218.0052239895 0.0502020903 0.0594222943 0.0879767612 0.0053963563 0.0047890000 41143181 955859216 1373700096 -0.0275741816 -0.1176962405 -0.1592129618 1427 1311867218.0371439457 0.0504521318 0.0594160082 0.0879767612 0.0053944981 0.0101330000 41145997 955859216 1373700096 -0.0279814824 -0.1167769060 -0.1588772684 1428 1311867218.0710949898 0.0505737998 0.0594098162 0.0879767612 0.0053926370 0.0060700000 41148813 955859216 1373700096 -0.0278415103 -0.1149726659 -0.1587262899 1429 1311867218.1050980091 0.0502690487 0.0594034196 0.0879767612 0.0053907778 0.0050310000 41151797 955859216 1373700096 -0.0273760818 -0.1133928299 -0.1586401612 1430 1311867218.1371181011 0.0500785373 0.0593968987 0.0879767612 0.0053889464 0.0046530000 41154669 955859216 1373700096 -0.0270035733 -0.1121832579 -0.1584311575 1431 1311867218.1712090969 0.0497075617 0.0593901277 0.0879767612 0.0053882659 0.0046210000 41157597 955859216 1373700096 -0.0264786966 -0.1102264747 -0.1580785215 1432 1311867218.2050349712 0.0499645583 0.0593835456 0.0879767612 0.0053866377 0.0126740000 41160525 955859216 1373700096 -0.0265779886 -0.1086878106 -0.1577731818 1433 1311867218.2372438908 0.0499689542 0.0593769757 0.0879767612 0.0053850373 0.0066150000 41163341 955859216 1373700096 -0.0264959093 -0.1079575792 -0.1574834287 1434 1311867218.2715640068 0.0505122170 0.0593707939 0.0879767612 0.0053840108 0.0053460000 41166325 955859216 1373700096 -0.0276682451 -0.1062448397 -0.1573501825 1435 1311867218.3051331043 0.0505776778 0.0593646663 0.0879767612 0.0053825514 0.0046620000 41169253 955859216 1373700096 -0.0269394200 -0.1055683568 -0.1574913263 1436 1311867218.3373649120 0.0505865440 0.0593585534 0.0879767612 0.0053807969 0.0045880000 41172069 955859216 1373700096 -0.0275249444 -0.1049125493 -0.1580257416 1437 1311867218.3734769821 0.0506789386 0.0593525133 0.0879767612 0.0053801987 0.0046300000 41175109 955859216 1373700096 -0.0278116837 -0.1029590070 -0.1584600508 1438 1311867218.4052689075 0.0506610721 0.0593464692 0.0879767612 0.0053789561 0.0047980000 41177981 955859216 1373700096 -0.0276417937 -0.1016517580 -0.1590286046 1439 1311867218.4372320175 0.0505102016 0.0593403286 0.0879767612 0.0053792098 0.0047340000 41180853 955859216 1373700096 -0.0276286118 -0.1017671302 -0.1598455906 1440 1311867218.4729750156 0.0502455048 0.0593340128 0.0879767612 0.0053781043 0.0140800000 41183781 955859216 1373700096 -0.0274243280 -0.1009777114 -0.1604095697 1441 1311867218.5051169395 0.0503499620 0.0593277782 0.0879767612 0.0053802265 0.0068030000 41186709 955859216 1373700096 -0.0275570434 -0.0987441391 -0.1604870260 1442 1311867218.5372729301 0.0497524403 0.0593211379 0.0879767612 0.0053786547 0.0052550000 41189525 955859216 1373700096 -0.0274577588 -0.0972683877 -0.1607808173 1443 1311867218.5714759827 0.0496018566 0.0593144024 0.0879767612 0.0053768526 0.0047070000 41192509 955859216 1373700096 -0.0268971752 -0.0962443575 -0.1606614739 1444 1311867218.6059319973 0.0495766066 0.0593076588 0.0879767612 0.0053757060 0.0046640000 41195493 955859216 1373700096 -0.0270606335 -0.0943803489 -0.1601374447 1445 1311867218.6372020245 0.0495819971 0.0593009282 0.0879767612 0.0053750316 0.0048070000 41198253 955859216 1373700096 -0.0273362119 -0.0938603207 -0.1597195417 1446 1311867218.6710820198 0.0494869947 0.0592941412 0.0879767612 0.0053743985 0.0047620000 41201237 955859216 1373700096 -0.0272487067 -0.0931121185 -0.1593406051 1447 1311867218.7058999538 0.0501025207 0.0592877891 0.0879767612 0.0053743677 0.0136130000 41204053 955859216 1373700096 -0.0265707187 -0.0922534317 -0.1587678045 1448 1311867218.7378489971 0.0494710356 0.0592810095 0.0879767612 0.0053746688 0.0077730000 41206925 955859216 1373700096 -0.0265846234 -0.0920878276 -0.1581464261 1449 1311867218.7715899944 0.0500696450 0.0592746525 0.0879767612 0.0053747508 0.0056290000 41209853 955859216 1373700096 -0.0274852253 -0.0919949114 -0.1579012573 1450 1311867218.8052420616 0.0499436334 0.0592682173 0.0879767612 0.0053746449 0.0048370000 41212837 955859216 1373700096 -0.0270699430 -0.0902432054 -0.1572247595 1451 1311867218.8379960060 0.0500798151 0.0592618848 0.0879767612 0.0053730325 0.0047010000 41215653 955859216 1373700096 -0.0273308791 -0.0894890577 -0.1567277759 1452 1311867218.8727340698 0.0509798303 0.0592561809 0.0879767612 0.0053759986 0.0046770000 41218581 955859216 1373700096 -0.0282337386 -0.0899620950 -0.1564432979 1453 1311867218.9054861069 0.0500529557 0.0592498470 0.0879767612 0.0053770646 0.0117770000 41221397 955859216 1373700096 -0.0280762892 -0.0884864777 -0.1558295190 1454 1311867218.9372200966 0.0495144390 0.0592431514 0.0879767612 0.0053773178 0.0063990000 41224325 955859216 1373700096 -0.0278401226 -0.0877937749 -0.1557464600 1455 1311867218.9731678963 0.0497190319 0.0592366056 0.0879767612 0.0053757103 0.0051300000 41227309 955859216 1373700096 -0.0280673224 -0.0875181183 -0.1552771181 1456 1311867219.0051829815 0.0496945605 0.0592300520 0.0879767612 0.0053738925 0.0046800000 41230237 955859216 1373700096 -0.0278123021 -0.0862848535 -0.1549127698 1457 1311867219.0371239185 0.0493994392 0.0592233048 0.0879767612 0.0053723489 0.0068950000 41233109 955859216 1373700096 -0.0279160794 -0.0854041427 -0.1547822356 1458 1311867219.0738430023 0.0490286984 0.0592163126 0.0879767612 0.0053738052 0.0055450000 41236093 955859216 1373700096 -0.0269781649 -0.0846586525 -0.1544247717 1459 1311867219.1050798893 0.0489961952 0.0592093078 0.0879767612 0.0053769525 0.0087030000 41238909 955859216 1373700096 -0.0271196235 -0.0842264965 -0.1541251987 1460 1311867219.1383259296 0.0489473604 0.0592022790 0.0879767612 0.0053751197 0.0060220000 41241781 955859216 1373700096 -0.0264712684 -0.0831648633 -0.1536551416 1461 1311867219.1708459854 0.0491641536 0.0591954083 0.0879767612 0.0053732914 0.0050950000 41244709 955859216 1373700096 -0.0267191306 -0.0820810199 -0.1531891823 1462 1311867219.2052450180 0.0490662642 0.0591884800 0.0879767612 0.0053726150 0.0086950000 41247693 955859216 1373700096 -0.0257793833 -0.0809742659 -0.1527457237 1463 1311867219.2391340733 0.0488708578 0.0591814277 0.0879767612 0.0053747101 0.0059090000 41250565 955859216 1373700096 -0.0259877052 -0.0799831450 -0.1524336338 1464 1311867219.2709059715 0.0484839939 0.0591741207 0.0879767612 0.0053735591 0.0082110000 41253437 955859216 1373700096 -0.0250252411 -0.0790763199 -0.1523584574 1465 1311867219.3052430153 0.0482468382 0.0591666618 0.0879767612 0.0053786963 0.0057270000 41256365 955859216 1373700096 -0.0243566427 -0.0784693137 -0.1522087455 1466 1311867219.3401598930 0.0485033691 0.0591593880 0.0879767612 0.0053772573 0.0048680000 41259293 955859216 1373700096 -0.0236475226 -0.0773157999 -0.1516807675 1467 1311867219.3715050220 0.0486617014 0.0591522322 0.0879767612 0.0053756561 0.0116900000 41262109 955859216 1373700096 -0.0231824387 -0.0762119889 -0.1513968259 1468 1311867219.4051969051 0.0484573171 0.0591449468 0.0879767612 0.0053739109 0.0064190000 41265093 955859216 1373700096 -0.0230333488 -0.0758341923 -0.1513292938 1469 1311867219.4394860268 0.0484909751 0.0591376943 0.0879767612 0.0053722954 0.0053120000 41268021 955859216 1373700096 -0.0226874091 -0.0746938065 -0.1511525661 1470 1311867219.4717299938 0.0485113747 0.0591304655 0.0879767612 0.0053704738 0.0048760000 41270893 955859216 1373700096 -0.0220502801 -0.0733103752 -0.1508298665 1471 1311867219.5051560402 0.0485640392 0.0591232823 0.0879767612 0.0053692867 0.0099200000 41273821 955859216 1373700096 -0.0214483514 -0.0728047863 -0.1506266892 1472 1311867219.5391950607 0.0485900193 0.0591161266 0.0879767612 0.0053684952 0.0061130000 41276693 955859216 1373700096 -0.0214137472 -0.0714601129 -0.1504899561 1473 1311867219.5743470192 0.0481010824 0.0591086486 0.0879767612 0.0053670390 0.0051050000 41279677 955859216 1373700096 -0.0207141973 -0.0697893947 -0.1502512693 1474 1311867219.6086258888 0.0481468216 0.0591012118 0.0879767612 0.0053654817 0.0083430000 41282549 955859216 1373700096 -0.0204009898 -0.0694629326 -0.1500801742 1475 1311867219.6425020695 0.0488948859 0.0590942923 0.0879767612 0.0053758271 0.0084260000 41285477 955859216 1373700096 -0.0197488721 -0.0683533326 -0.1498417705 1476 1311867219.6711170673 0.0490056835 0.0590874572 0.0879767612 0.0053904154 0.0058760000 41288237 955859216 1373700096 -0.0195530392 -0.0677135587 -0.1498628110 1477 1311867219.7052869797 0.0493144579 0.0590808404 0.0879767612 0.0053890551 0.0049720000 41291165 955859216 1373700096 -0.0196999107 -0.0679089576 -0.1500542909 1478 1311867219.7395179272 0.0493028797 0.0590742247 0.0879767612 0.0053879882 0.0101130000 41294093 955859216 1373700096 -0.0192944463 -0.0671040937 -0.1499144733 1479 1311867219.7772109509 0.0497698039 0.0590679337 0.0879767612 0.0053999859 0.0061220000 41297077 955859216 1373700096 -0.0181487929 -0.0659198985 -0.1500435024 1480 1311867219.8051769733 0.0497754626 0.0590616550 0.0879767612 0.0053992274 0.0051790000 41299893 955859216 1373700096 -0.0176490918 -0.0655458197 -0.1502984315 1481 1311867219.8397340775 0.0494972505 0.0590551969 0.0879767612 0.0053985939 0.0047390000 41302877 955859216 1373700096 -0.0170503799 -0.0641263723 -0.1505599767 1482 1311867219.8753221035 0.0498251393 0.0590489688 0.0879767612 0.0054086100 0.0089490000 41305805 955859216 1373700096 -0.0156171164 -0.0628669411 -0.1502612680 1483 1311867219.9108390808 0.0493910462 0.0590424564 0.0879767612 0.0054275598 0.0060430000 41308677 955859216 1373700096 -0.0153575558 -0.0621131435 -0.1502864361 1484 1311867219.9417819977 0.0488174483 0.0590355662 0.0879767612 0.0054281454 0.0083890000 41311549 955859216 1373700096 -0.0147806052 -0.0609852858 -0.1502279639 1485 1311867219.9732298851 0.0488059334 0.0590286776 0.0879767612 0.0054279254 0.0058460000 41314309 955859216 1373700096 -0.0143493460 -0.0602904111 -0.1501534730 1486 1311867220.0068678856 0.0491670333 0.0590220412 0.0879767612 0.0054288801 0.0049330000 41317293 955859216 1373700096 -0.0134810740 -0.0594274886 -0.1499151438 1487 1311867220.0422430038 0.0487538055 0.0590151359 0.0879767612 0.0054281327 0.0118080000 41320221 955859216 1373700096 -0.0126606906 -0.0580686219 -0.1498154700 1488 1311867220.0743820667 0.0494076237 0.0590086792 0.0879767612 0.0054267664 0.0065000000 41323093 955859216 1373700096 -0.0131881926 -0.0572326519 -0.1498428285 1489 1311867220.1052761078 0.0493281186 0.0590021778 0.0879767612 0.0054322158 0.0052920000 41325965 955859216 1373700096 -0.0127164489 -0.0560723357 -0.1498300135 1490 1311867220.1421229839 0.0494246669 0.0589957500 0.0879767612 0.0054307946 0.0078510000 41328893 955859216 1373700096 -0.0134788305 -0.0546650290 -0.1498129517 1491 1311867220.1714730263 0.0485346168 0.0589887338 0.0879767612 0.0054361713 0.0057600000 41331765 955859216 1373700096 -0.0136012742 -0.0533986092 -0.1498574317 1492 1311867220.2061989307 0.0493238978 0.0589822560 0.0879767612 0.0054406465 0.0086590000 41334749 955859216 1373700096 -0.0137514649 -0.0526180156 -0.1497122049 1493 1311867220.2422249317 0.0492932387 0.0589757664 0.0879767612 0.0054438787 0.0090690000 41337733 955859216 1373700096 -0.0132716196 -0.0520317294 -0.1498679817 1494 1311867220.2741279602 0.0493829846 0.0589693455 0.0879767612 0.0054424974 0.0088580000 41340549 955859216 1373700096 -0.0131810680 -0.0509611182 -0.1498892903 1495 1311867220.3064579964 0.0498798080 0.0589632655 0.0879767612 0.0054528247 0.0087800000 41343421 955859216 1373700096 -0.0130238319 -0.0501372479 -0.1499197632 1496 1311867220.3420999050 0.0498366877 0.0589571649 0.0879767612 0.0054560982 0.0059330000 41346293 955859216 1373700096 -0.0130469482 -0.0493071899 -0.1501455009 1497 1311867220.3714869022 0.0486159623 0.0589502569 0.0879767612 0.0055053329 0.0056960000 41349109 955859216 1373700096 -0.0129706906 -0.0483627468 -0.1502828151 1498 1311867220.4063799381 0.0488173552 0.0589434927 0.0879767612 0.0055051359 0.0050330000 41352149 955859216 1373700096 -0.0128457751 -0.0467356779 -0.1501954496 1499 1311867220.4408841133 0.0485028103 0.0589365276 0.0879767612 0.0055045233 0.0050390000 41355077 955859216 1373700096 -0.0125012686 -0.0451284312 -0.1500404328 1500 1311867220.4728751183 0.0484151058 0.0589295133 0.0879767612 0.0055058847 0.0055100000 41357893 955859216 1373700096 -0.0119407177 -0.0441787578 -0.1499212980 1501 1311867220.5091059208 0.0494008325 0.0589231651 0.0879767612 0.0055043156 0.0049600000 41360933 955859216 1373700096 -0.0115756737 -0.0433823913 -0.1497361213 1502 1311867220.5419850349 0.0492364317 0.0589167158 0.0879767612 0.0055024864 0.0123610000 41363749 955859216 1373700096 -0.0111298198 -0.0425838046 -0.1494490653 1503 1311867220.5716400146 0.0492640994 0.0589102936 0.0879767612 0.0055015859 0.0066800000 41366509 955859216 1373700096 -0.0110407360 -0.0424287654 -0.1497163326 1504 1311867220.6104249954 0.0493121967 0.0589039119 0.0879767612 0.0055018014 0.0054630000 41369549 955859216 1373700096 -0.0109852757 -0.0417053029 -0.1502064168 1505 1311867220.6415500641 0.0493028350 0.0588975324 0.0879767612 0.0055008548 0.0049100000 41372309 955859216 1373700096 -0.0101859532 -0.0412215032 -0.1504925489 1506 1311867220.6713089943 0.0493175834 0.0588911712 0.0879767612 0.0054991355 0.0049630000 41375181 955859216 1373700096 -0.0096233524 -0.0406424627 -0.1509316862 1507 1311867220.7073359489 0.0496734865 0.0588850547 0.0879767612 0.0055005450 0.0115820000 41378165 955859216 1373700096 -0.0093077421 -0.0399816483 -0.1514408886 1508 1311867220.7393438816 0.0494212583 0.0588787789 0.0879767612 0.0054998099 0.0065090000 41381037 955859216 1373700096 -0.0091570793 -0.0394529440 -0.1520277858 1509 1311867220.7719850540 0.0494865142 0.0588725548 0.0879767612 0.0054985106 0.0079200000 41383853 955859216 1373700096 -0.0076173944 -0.0385007374 -0.1523540169 1510 1311867220.8097529411 0.0496056266 0.0588664177 0.0879767612 0.0054987723 0.0058770000 41386949 955859216 1373700096 -0.0071008150 -0.0375966839 -0.1526893377 1511 1311867220.8415019512 0.0496829078 0.0588603400 0.0879767612 0.0054980766 0.0078940000 41389765 955859216 1373700096 -0.0067322557 -0.0363922939 -0.1527724564 1512 1311867220.8712480068 0.0496412367 0.0588542427 0.0879767612 0.0055005211 0.0058670000 41392637 955859216 1373700096 -0.0066606696 -0.0351426639 -0.1527269483 1513 1311867220.9075961113 0.0497001447 0.0588481924 0.0879767612 0.0055030762 0.0077310000 41395621 955859216 1373700096 -0.0059722238 -0.0346149318 -0.1527482867 1514 1311867220.9392969608 0.0496228933 0.0588420990 0.0879767612 0.0055013339 0.0059480000 41398493 955859216 1373700096 -0.0055006249 -0.0341134928 -0.1527117938 1515 1311867220.9713189602 0.0493909009 0.0588358606 0.0879767612 0.0055139306 0.0085100000 41401365 955859216 1373700096 -0.0039247163 -0.0334710889 -0.1524894983 1516 1311867221.0090179443 0.0492054746 0.0588295081 0.0879767612 0.0055122490 0.0059580000 41404405 955859216 1373700096 -0.0034032715 -0.0327041559 -0.1523045897 1517 1311867221.0392940044 0.0490712188 0.0588230755 0.0879767612 0.0055105238 0.0078690000 41407221 955859216 1373700096 -0.0031613493 -0.0324095450 -0.1522295773 1518 1311867221.0720989704 0.0489716679 0.0588165858 0.0879767612 0.0055087370 0.0058190000 41410093 955859216 1373700096 -0.0022114313 -0.0316007324 -0.1519871950 1519 1311867221.1077580452 0.0489751808 0.0588101069 0.0879767612 0.0055077553 0.0084120000 41413077 955859216 1373700096 -0.0016781489 -0.0302859135 -0.1517270803 1520 1311867221.1397790909 0.0491303839 0.0588037387 0.0879767612 0.0055065400 0.0060360000 41416005 955859216 1373700096 -0.0007415027 -0.0301660020 -0.1517498195 1521 1311867221.1716909409 0.0492432043 0.0587974530 0.0879767612 0.0055071240 0.0051680000 41418765 955859216 1373700096 0.0000899367 -0.0292240456 -0.1518286914 1522 1311867221.2083969116 0.0489321016 0.0587909711 0.0879767612 0.0055077731 0.0050770000 41421749 955859216 1373700096 0.0016183163 -0.0273127630 -0.1517785490 1523 1311867221.2398130894 0.0487477183 0.0587843768 0.0879767612 0.0055073988 0.0122510000 41424677 955859216 1373700096 0.0030000217 -0.0265105050 -0.1519147903 1524 1311867221.2721240520 0.0484948866 0.0587776251 0.0879767612 0.0055064418 0.0066060000 41427549 955859216 1373700096 0.0038069577 -0.0262846593 -0.1523051709 1525 1311867221.3075931072 0.0485904180 0.0587709450 0.0879767612 0.0055066861 0.0054190000 41430477 955859216 1373700096 0.0049313949 -0.0243558735 -0.1526816189 1526 1311867221.3393449783 0.0486463346 0.0587643103 0.0879767612 0.0055050051 0.0050020000 41433349 955859216 1373700096 0.0060745869 -0.0233760849 -0.1531644017 1527 1311867221.3714220524 0.0486920923 0.0587577142 0.0879767612 0.0055043949 0.0082770000 41436277 955859216 1373700096 0.0072677080 -0.0232602898 -0.1538792104 1528 1311867221.4073879719 0.0485394634 0.0587510268 0.0879767612 0.0055028769 0.0059740000 41439149 955859216 1373700096 0.0082458965 -0.0211704485 -0.1545553505 1529 1311867221.4400680065 0.0487984121 0.0587445176 0.0879767612 0.0055017326 0.0058760000 41442077 955859216 1373700096 0.0095544895 -0.0195953734 -0.1549545527 1530 1311867221.4712409973 0.0489591099 0.0587381219 0.0879767612 0.0055003991 0.0095100000 41444893 955859216 1373700096 0.0092245275 -0.0181758534 -0.1554815471 1531 1311867221.5081720352 0.0491598025 0.0587318657 0.0879767612 0.0054990377 0.0062860000 41447877 955859216 1373700096 0.0091362493 -0.0173578821 -0.1560273767 1532 1311867221.5396909714 0.0495376922 0.0587258642 0.0879767612 0.0054973725 0.0053260000 41450805 955859216 1373700096 0.0087095452 -0.0157987345 -0.1565741301 1533 1311867221.5712790489 0.0500418581 0.0587201995 0.0879767612 0.0054976556 0.0050180000 41453677 955859216 1373700096 0.0082861120 -0.0142228883 -0.1572327018 1534 1311867221.6073110104 0.0505577475 0.0587148785 0.0879767612 0.0054963747 0.0117340000 41456605 955859216 1373700096 0.0074714459 -0.0136238448 -0.1582836658 1535 1311867221.6403770447 0.0505416878 0.0587095539 0.0879767612 0.0054954346 0.0065350000 41459589 955859216 1373700096 0.0070671299 -0.0113308961 -0.1591690481 1536 1311867221.6771481037 0.0512020588 0.0587046663 0.0879767612 0.0054947443 0.0055630000 41462573 955859216 1373700096 0.0068687918 -0.0094331549 -0.1601777822 1537 1311867221.7072019577 0.0511024706 0.0586997201 0.0879767612 0.0054969556 0.0050720000 41465333 955859216 1373700096 0.0067352746 -0.0076068779 -0.1613533497 1538 1311867221.7423930168 0.0510084927 0.0586947193 0.0879767612 0.0054955217 0.0050970000 41468317 955859216 1373700096 0.0065457067 -0.0052702664 -0.1625113040 1539 1311867221.7773499489 0.0515432730 0.0586900725 0.0879767612 0.0054950947 0.0124730000 41471189 955859216 1373700096 0.0063623791 -0.0028490382 -0.1632314920 1540 1311867221.8074541092 0.0514749847 0.0586853874 0.0879767612 0.0054935705 0.0066510000 41474005 955859216 1373700096 0.0066161281 -0.0009874963 -0.1642992496 1541 1311867221.8396520615 0.0517620817 0.0586808947 0.0879767612 0.0054983833 0.0055030000 41476933 955859216 1373700096 0.0059645148 -0.0003636112 -0.1659217626 1542 1311867221.8777329922 0.0523648150 0.0586767986 0.0879767612 0.0055008630 0.0050550000 41479973 955859216 1373700096 0.0061510429 0.0009690420 -0.1673256457 1543 1311867221.9077489376 0.0523497686 0.0586726982 0.0879767612 0.0055010793 0.0050380000 41482789 955859216 1373700096 0.0065530352 0.0025713937 -0.1685486883 1544 1311867221.9424629211 0.0518829636 0.0586683007 0.0879767612 0.0055011415 0.0129120000 41485717 955859216 1373700096 0.0062322021 0.0040956945 -0.1701001525 1545 1311867221.9775359631 0.0521354005 0.0586640722 0.0879767612 0.0055012198 0.0089970000 41488701 955859216 1373700096 0.0052965856 0.0060739894 -0.1713370532 1546 1311867222.0090060234 0.0520542003 0.0586597968 0.0879767612 0.0054996928 0.0061360000 41491573 955859216 1373700096 0.0049839020 0.0078171520 -0.1721861362 1547 1311867222.0428760052 0.0522042550 0.0586556238 0.0879767612 0.0055018634 0.0052020000 41494333 955859216 1373700096 0.0046707061 0.0084848050 -0.1730911881 1548 1311867222.0782530308 0.0521217547 0.0586514030 0.0879767612 0.0055040358 0.0082910000 41497205 955859216 1373700096 0.0048261075 0.0105253635 -0.1739519984 1549 1311867222.1110939980 0.0514028706 0.0586467235 0.0879767612 0.0055029534 0.0060840000 41500077 955859216 1373700096 0.0049010036 0.0131689683 -0.1743336171 1550 1311867222.1406900883 0.0503120832 0.0586413463 0.0879767612 0.0055230533 0.0052780000 41502893 955859216 1373700096 0.0053152633 0.0149453273 -0.1744561195 1551 1311867222.1797990799 0.0510428622 0.0586364472 0.0879767612 0.0055372846 0.0084910000 41505989 955859216 1373700096 0.0048515140 0.0162748657 -0.1746940613 1552 1311867222.2081730366 0.0507210754 0.0586313471 0.0879767612 0.0055378638 0.0061010000 41508749 955859216 1373700096 0.0049651172 0.0191604104 -0.1745397151 1553 1311867222.2400839329 0.0502666980 0.0586259610 0.0879767612 0.0055410881 0.0051650000 41511621 955859216 1373700096 0.0056976229 0.0210677441 -0.1743465662 1554 1311867222.2760300636 0.0501239896 0.0586204900 0.0879767612 0.0055407009 0.0092650000 41514605 955859216 1373700096 0.0053700050 0.0215722490 -0.1743437946 1555 1311867222.3077421188 0.0499584042 0.0586149195 0.0879767612 0.0055396942 0.0063320000 41517477 955859216 1373700096 0.0055424459 0.0236466713 -0.1735324115 1556 1311867222.3396389484 0.0498042107 0.0586092571 0.0879767612 0.0055402917 0.0088840000 41520349 955859216 1373700096 0.0063298102 0.0250808671 -0.1731499135 1557 1311867222.3792359829 0.0502512269 0.0586038891 0.0879767612 0.0055434287 0.0062130000 41523389 955859216 1373700096 0.0063635083 0.0261286404 -0.1728572547 1558 1311867222.4102001190 0.0502017178 0.0585984961 0.0879767612 0.0055420363 0.0053020000 41526261 955859216 1373700096 0.0071050772 0.0277844295 -0.1721890718 1559 1311867222.4436430931 0.0506692976 0.0585934100 0.0879767612 0.0055408382 0.0083690000 41529133 955859216 1373700096 0.0075192493 0.0296477769 -0.1712603271 1560 1311867222.4781119823 0.0501098186 0.0585879719 0.0879767612 0.0055397868 0.0060860000 41532117 955859216 1373700096 0.0081514502 0.0313439034 -0.1706082672 1561 1311867222.5087089539 0.0506047010 0.0585828576 0.0879767612 0.0055382941 0.0054020000 41534933 955859216 1373700096 0.0084595578 0.0328503065 -0.1694987267 1562 1311867222.5401790142 0.0516450331 0.0585784160 0.0879767612 0.0055374402 0.0051620000 41537805 955859216 1373700096 0.0095285522 0.0341814086 -0.1685676128 1563 1311867222.5774040222 0.0517509431 0.0585740478 0.0879767612 0.0055361911 0.0099490000 41540789 955859216 1373700096 0.0099849775 0.0347452462 -0.1677849889 1564 1311867222.6084389687 0.0511968508 0.0585693310 0.0879767612 0.0055351357 0.0065430000 41543661 955859216 1373700096 0.0108742202 0.0357339829 -0.1668760329 1565 1311867222.6433119774 0.0508487672 0.0585643977 0.0879767612 0.0055341112 0.0055130000 41546589 955859216 1373700096 0.0087102056 0.0370944850 -0.1663847268 1566 1311867222.6796491146 0.0510588922 0.0585596049 0.0879767612 0.0055346661 0.0094940000 41549629 955859216 1373700096 0.0089133848 0.0380181521 -0.1658367813 1567 1311867222.7080249786 0.0506157354 0.0585545354 0.0879767612 0.0055351551 0.0063140000 41552333 955859216 1373700096 0.0090834089 0.0390517823 -0.1651905626 1568 1311867222.7400081158 0.0506405085 0.0585494882 0.0879767612 0.0055371744 0.0054100000 41555261 955859216 1373700096 0.0095627094 0.0401587076 -0.1644073129 1569 1311867222.7793939114 0.0506890081 0.0585444783 0.0879767612 0.0055391888 0.0092660000 41558189 955859216 1373700096 0.0098762792 0.0407406241 -0.1639070064 1570 1311867222.8093209267 0.0508907028 0.0585396033 0.0879767612 0.0055385401 0.0065220000 41560949 955859216 1373700096 0.0107112983 0.0412705578 -0.1635190398 1571 1311867222.8402760029 0.0509723797 0.0585347865 0.0879767612 0.0055369437 0.0054100000 41563821 955859216 1373700096 0.0114695206 0.0422880165 -0.1628885865 1572 1311867222.8812980652 0.0507575050 0.0585298391 0.0879767612 0.0055363631 0.0109920000 41566861 955859216 1373700096 0.0112890676 0.0427533425 -0.1624730229 1573 1311867222.9082360268 0.0508915335 0.0585249832 0.0879767612 0.0055347934 0.0065650000 41569621 955859216 1373700096 0.0112922890 0.0431709364 -0.1621129811 1574 1311867222.9470820427 0.0507940575 0.0585200716 0.0879767612 0.0055340740 0.0055940000 41572717 955859216 1373700096 0.0114393150 0.0440320447 -0.1615350544 1575 1311867222.9831020832 0.0507347137 0.0585151285 0.0879767612 0.0055324435 0.0085780000 41575701 955859216 1373700096 0.0117743379 0.0444817878 -0.1611510366 1576 1311867223.0078310966 0.0510527939 0.0585103935 0.0879767612 0.0055333995 0.0061930000 41578349 955859216 1373700096 0.0116207171 0.0446642786 -0.1607302576 1577 1311867223.0454061031 0.0509615354 0.0585056067 0.0879767612 0.0055322289 0.0053170000 41581389 955859216 1373700096 0.0116943270 0.0453406386 -0.1603194922 1578 1311867223.0808250904 0.0509579703 0.0585008236 0.0879767612 0.0055319968 0.0051420000 41584373 955859216 1373700096 0.0113805775 0.0460016169 -0.1598561108 1579 1311867223.1094229221 0.0508672483 0.0584959892 0.0879767612 0.0055313379 0.0097290000 41587133 955859216 1373700096 0.0112204654 0.0464623086 -0.1596301794 1580 1311867223.1473770142 0.0513474084 0.0584914648 0.0879767612 0.0055306156 0.0065520000 41590173 955859216 1373700096 0.0105692875 0.0474219620 -0.1592270583 1581 1311867223.1758580208 0.0515469424 0.0584870723 0.0879767612 0.0055302357 0.0055030000 41592933 955859216 1373700096 0.0105840554 0.0484653227 -0.1588197798 1582 1311867223.2080020905 0.0514200218 0.0584826051 0.0879767612 0.0055286762 0.0051390000 41595749 955859216 1373700096 0.0101667074 0.0492368601 -0.1586022526 1583 1311867223.2450079918 0.0516358465 0.0584782800 0.0879767612 0.0055284919 0.0100110000 41598789 955859216 1373700096 0.0101415534 0.0504596941 -0.1580723822 1584 1311867223.2779359818 0.0521322675 0.0584742736 0.0879767612 0.0055274521 0.0065770000 41601717 955859216 1373700096 0.0105619673 0.0518473461 -0.1574838907 1585 1311867223.3085999489 0.0523381084 0.0584704022 0.0879767612 0.0055261391 0.0056140000 41604533 955859216 1373700096 0.0099236211 0.0530074425 -0.1570264399 1586 1311867223.3452420235 0.0523902178 0.0584665686 0.0879767612 0.0055256313 0.0095520000 41607573 955859216 1373700096 0.0095526362 0.0546050034 -0.1565704197 1587 1311867223.3794689178 0.0511748157 0.0584619739 0.0879767612 0.0055293490 0.0068780000 41610445 955859216 1373700096 0.0095168529 0.0561644882 -0.1562992185 1588 1311867223.4074239731 0.0530455597 0.0584585631 0.0879767612 0.0055289154 0.0056460000 41613149 955859216 1373700096 0.0093266433 0.0570536330 -0.1561702192 1589 1311867223.4458000660 0.0535212904 0.0584554559 0.0879767612 0.0055274446 0.0052750000 41616189 955859216 1373700096 0.0090408996 0.0578210354 -0.1561278552 1590 1311867223.4758329391 0.0536276102 0.0584524195 0.0879767612 0.0055261099 0.0100830000 41619061 955859216 1373700096 0.0083760787 0.0589758605 -0.1563590020 1591 1311867223.5077428818 0.0534984358 0.0584493058 0.0879767612 0.0055247379 0.0065670000 41621933 955859216 1373700096 0.0076488666 0.0602510236 -0.1566641033 1592 1311867223.5466530323 0.0538984239 0.0584464472 0.0879767612 0.0055304350 0.0055180000 41624973 955859216 1373700096 0.0072169928 0.0610118471 -0.1571482867 1593 1311867223.5759539604 0.0539461561 0.0584436221 0.0879767612 0.0055331387 0.0081600000 41627845 955859216 1373700096 0.0067224754 0.0622480549 -0.1576519907 1594 1311867223.6078069210 0.0540087670 0.0584408399 0.0879767612 0.0055314753 0.0060800000 41630605 955859216 1373700096 0.0063475361 0.0633870065 -0.1580394655 1595 1311867223.6502039433 0.0540429614 0.0584380826 0.0879767612 0.0055342445 0.0053100000 41633813 955859216 1373700096 0.0058858497 0.0640681982 -0.1587667018 1596 1311867223.6753880978 0.0541231558 0.0584353790 0.0879767612 0.0055327343 0.0053230000 41636461 955859216 1373700096 0.0061501185 0.0652587637 -0.1592146307 1597 1311867223.7088580132 0.0541981608 0.0584327258 0.0879767612 0.0055311344 0.0053280000 41639389 955859216 1373700096 0.0055449046 0.0668566823 -0.1594266742 1598 1311867223.7452809811 0.0541520081 0.0584300470 0.0879767612 0.0055303036 0.0053210000 41642429 955859216 1373700096 0.0047773016 0.0682194680 -0.1598733068 1599 1311867223.7760720253 0.0547120459 0.0584277218 0.0879767612 0.0055304222 0.0053760000 41645245 955859216 1373700096 0.0052413484 0.0697384700 -0.1600329578 1600 1311867223.8077559471 0.0548834987 0.0584255067 0.0879767612 0.0055287485 0.0053400000 41648061 955859216 1373700096 0.0050152475 0.0716512874 -0.1603136212 1601 1311867223.8438520432 0.0552656800 0.0584235330 0.0879767612 0.0055302467 0.0053080000 41651101 955859216 1373700096 0.0048114392 0.0729659572 -0.1606983542 1602 1311867223.8760919571 0.0553727187 0.0584216286 0.0879767612 0.0055292862 0.0053900000 41653973 955859216 1373700096 0.0049361959 0.0743474141 -0.1610156000 1603 1311867223.9078280926 0.0556535050 0.0584199018 0.0879767612 0.0055277169 0.0053690000 41656789 955859216 1373700096 0.0052595590 0.0761773661 -0.1611766517 1604 1311867223.9491670132 0.0562684573 0.0584185605 0.0879767612 0.0055261191 0.0053840000 41659941 955859216 1373700096 0.0058873412 0.0774873793 -0.1615692675 1605 1311867223.9760739803 0.0559092537 0.0584169971 0.0879767612 0.0055279045 0.0053440000 41662701 955859216 1373700096 0.0062131924 0.0789296255 -0.1621325910 1606 1311867224.0093441010 0.0562754199 0.0584156636 0.0879767612 0.0055295468 0.0052920000 41665573 955859216 1373700096 0.0062369443 0.0805288851 -0.1625586599 1607 1311867224.0470440388 0.0564617105 0.0584144477 0.0879767612 0.0055279449 0.0053140000 41668669 955859216 1373700096 0.0067699393 0.0821842700 -0.1628429592 1608 1311867224.0761411190 0.0563305393 0.0584131517 0.0879767612 0.0055262688 0.0053100000 41671429 955859216 1373700096 0.0068260208 0.0832635909 -0.1634331197 1609 1311867224.1081349850 0.0564951338 0.0584119597 0.0879767612 0.0055248087 0.0135140000 41674301 955859216 1373700096 0.0072236452 0.0848006457 -0.1641101837 1610 1311867224.1458990574 0.0567751117 0.0584109430 0.0879767612 0.0055270990 0.0092910000 41677285 955859216 1373700096 0.0072820075 0.0866195932 -0.1644783616 1611 1311867224.1768929958 0.0571864694 0.0584101829 0.0879767612 0.0055313834 0.0063020000 41680157 955859216 1373700096 0.0079759900 0.0884000733 -0.1650165617 1612 1311867224.2143769264 0.0570925586 0.0584093655 0.0879767612 0.0055298197 0.0053960000 41683029 955859216 1373700096 0.0088153202 0.0901505798 -0.1656899750 1613 1311867224.2470428944 0.0571737327 0.0584085995 0.0879767612 0.0055281458 0.0052880000 41685901 955859216 1373700096 0.0086429492 0.0922069326 -0.1662869602 1614 1311867224.2768630981 0.0573807247 0.0584079626 0.0879767612 0.0055283570 0.0052850000 41688661 955859216 1373700096 0.0082520451 0.0942023322 -0.1667962223 1615 1311867224.3146169186 0.0580153130 0.0584077195 0.0879767612 0.0055271887 0.0053820000 41691757 955859216 1373700096 0.0076794527 0.0955827236 -0.1675121933 1616 1311867224.3456730843 0.0577049851 0.0584072846 0.0879767612 0.0055255009 0.0059230000 41694629 955859216 1373700096 0.0079387669 0.0974587202 -0.1682758778 1617 1311867224.3769209385 0.0572657958 0.0584065787 0.0879767612 0.0055240433 0.0054700000 41697389 955859216 1373700096 0.0078470139 0.0994224846 -0.1691250056 1618 1311867224.4141020775 0.0575725995 0.0584060633 0.0879767612 0.0055253256 0.0053220000 41700429 955859216 1373700096 0.0076325871 0.1009566560 -0.1699497849 1619 1311867224.4464271069 0.0572176017 0.0584053292 0.0879767612 0.0055246669 0.0135640000 41703301 955859216 1373700096 0.0075529236 0.1024630293 -0.1708538085 1620 1311867224.4776859283 0.0571013950 0.0584045243 0.0879767612 0.0055270570 0.0070930000 41706117 955859216 1373700096 0.0066573489 0.1041356698 -0.1714884490 1621 1311867224.5181219578 0.0574133806 0.0584039129 0.0879767612 0.0055329444 0.0057520000 41709213 955859216 1373700096 0.0062098228 0.1052308381 -0.1724850237 1622 1311867224.5470569134 0.0574700013 0.0584033371 0.0879767612 0.0055328317 0.0052900000 41712029 955859216 1373700096 0.0058505996 0.1062632129 -0.1732283384 1623 1311867224.5859119892 0.0574342832 0.0584027400 0.0879767612 0.0055368534 0.0052780000 41715125 955859216 1373700096 0.0050020716 0.1084059030 -0.1738904417 1624 1311867224.6181120872 0.0569502115 0.0584018456 0.0879767612 0.0055353800 0.0053180000 41717941 955859216 1373700096 0.0046100304 0.1098380014 -0.1745123714 1625 1311867224.6502161026 0.0566391610 0.0584007609 0.0879767612 0.0055338862 0.0112300000 41720869 955859216 1373700096 0.0049111526 0.1109626889 -0.1750868410 1626 1311867224.6785190105 0.0559557006 0.0583992571 0.0879767612 0.0055353039 0.0067240000 41723573 955859216 1373700096 0.0046627903 0.1124963239 -0.1755301803 1627 1311867224.7173650265 0.0561863296 0.0583978970 0.0879767612 0.0055365955 0.0056050000 41726669 955859216 1373700096 0.0045189257 0.1141332313 -0.1756738424 1628 1311867224.7520918846 0.0564503819 0.0583967008 0.0879767612 0.0055351424 0.0052880000 41729653 955859216 1373700096 0.0042062649 0.1154013649 -0.1758152097 1629 1311867224.7866261005 0.0565908030 0.0583955922 0.0879767612 0.0055349943 0.0115400000 41732525 955859216 1373700096 0.0047525764 0.1166577786 -0.1760437936 1630 1311867224.8123459816 0.0565045811 0.0583944320 0.0879767612 0.0055357426 0.0067870000 41735285 955859216 1373700096 0.0048314342 0.1185823604 -0.1761225313 1631 1311867224.8458189964 0.0562498793 0.0583931172 0.0879767612 0.0055627353 0.0056640000 41738101 955859216 1373700096 0.0046689105 0.1203241497 -0.1760307401 1632 1311867224.8779430389 0.0560060143 0.0583916545 0.0879767612 0.0055671517 0.0052990000 41740917 955859216 1373700096 0.0046226843 0.1220455244 -0.1760544926 1633 1311867224.9142448902 0.0564530715 0.0583904673 0.0879767612 0.0055728254 0.0053020000 41743957 955859216 1373700096 0.0050521898 0.1240176558 -0.1756621301 1634 1311867224.9471449852 0.0568909980 0.0583895497 0.0879767612 0.0055773988 0.0101350000 41746717 955859216 1373700096 0.0049733636 0.1257800460 -0.1754571050 1635 1311867224.9800488949 0.0566422604 0.0583884810 0.0879767612 0.0055757530 0.0066750000 41749701 955859216 1373700096 0.0048780488 0.1270982474 -0.1754224151 1636 1311867225.0142920017 0.0559590384 0.0583869960 0.0879767612 0.0055751001 0.0056290000 41752461 955859216 1373700096 0.0045579392 0.1295825690 -0.1753040403 1637 1311867225.0493879318 0.0557905920 0.0583854099 0.0879767612 0.0055754388 0.0053510000 41755333 955859216 1373700096 0.0046954192 0.1317552179 -0.1748243421 1638 1311867225.0798690319 0.0563302338 0.0583841552 0.0879767612 0.0055768203 0.0088930000 41758205 955859216 1373700096 0.0044829510 0.1334995329 -0.1744522154 1639 1311867225.1138188839 0.0565593988 0.0583830419 0.0879767612 0.0055765673 0.0063500000 41761077 955859216 1373700096 0.0041305539 0.1354594827 -0.1740282625 1640 1311867225.1472380161 0.0560326949 0.0583816088 0.0879767612 0.0055750252 0.0055250000 41763949 955859216 1373700096 0.0031209339 0.1377172470 -0.1737352908 1641 1311867225.1810939312 0.0558507964 0.0583800665 0.0879767612 0.0055733405 0.0053520000 41766933 955859216 1373700096 0.0029283897 0.1396074295 -0.1736089587 1642 1311867225.2153220177 0.0562807322 0.0583787880 0.0879767612 0.0055718387 0.0132100000 41769861 955859216 1373700096 0.0030231187 0.1412858963 -0.1733253151 1643 1311867225.2483470440 0.0558540262 0.0583772513 0.0879767612 0.0055713646 0.0072970000 41772733 955859216 1373700096 0.0028939687 0.1429410428 -0.1733728945 1644 1311867225.2792909145 0.0556132197 0.0583755701 0.0879767612 0.0055708158 0.0059330000 41775605 955859216 1373700096 0.0036384868 0.1448462605 -0.1734100878 1645 1311867225.3207540512 0.0556163453 0.0583738927 0.0879767612 0.0055705383 0.0053630000 41778757 955859216 1373700096 0.0040007550 0.1462408006 -0.1734203100 1646 1311867225.3462350368 0.0551948994 0.0583719614 0.0879767612 0.0055691194 0.0053550000 41781461 955859216 1373700096 0.0034598564 0.1475294381 -0.1737728119 1647 1311867225.3852069378 0.0552740693 0.0583700804 0.0879767612 0.0055674937 0.0053090000 41784501 955859216 1373700096 0.0030363272 0.1489326954 -0.1737338006 1648 1311867225.4130129814 0.0550153702 0.0583680448 0.0879767612 0.0055658695 0.0127050000 41787205 955859216 1373700096 0.0027647412 0.1500394195 -0.1740720272 1649 1311867225.4504270554 0.0550124459 0.0583660099 0.0879767612 0.0055643565 0.0070500000 41790301 955859216 1373700096 0.0020994705 0.1512921453 -0.1744067371 1650 1311867225.4842948914 0.0552857444 0.0583641431 0.0879767612 0.0055641617 0.0058150000 41793173 955859216 1373700096 0.0017069258 0.1525236368 -0.1748301983 1651 1311867225.5163919926 0.0557029136 0.0583625312 0.0879767612 0.0055643099 0.0053730000 41796101 955859216 1373700096 0.0007444536 0.1538060904 -0.1753052622 1652 1311867225.5493750572 0.0556429476 0.0583608849 0.0879767612 0.0055657500 0.0089690000 41798917 955859216 1373700096 0.0002733748 0.1557579488 -0.1759504080 1653 1311867225.5882349014 0.0553880930 0.0583590865 0.0879767612 0.0055650994 0.0063210000 41801957 955859216 1373700096 -0.0007472939 0.1573253274 -0.1768718213 1654 1311867225.6179010868 0.0558464378 0.0583575674 0.0879767612 0.0055640820 0.0084470000 41804773 955859216 1373700096 -0.0013049881 0.1583333164 -0.1778896004 1655 1311867225.6461288929 0.0558292791 0.0583560397 0.0879767612 0.0055626606 0.0062530000 41807533 955859216 1373700096 -0.0018022574 0.1597159356 -0.1788584143 1656 1311867225.6847119331 0.0556406416 0.0583544000 0.0879767612 0.0055610538 0.0055220000 41810629 955859216 1373700096 -0.0034262259 0.1612053961 -0.1799594313 1657 1311867225.7160770893 0.0552412048 0.0583525212 0.0879767612 0.0055595913 0.0097130000 41813501 955859216 1373700096 -0.0048509496 0.1624753922 -0.1812973171 1658 1311867225.7506299019 0.0553828292 0.0583507300 0.0879767612 0.0055620334 0.0065130000 41816429 955859216 1373700096 -0.0062378249 0.1636748761 -0.1825676560 1659 1311867225.7872900963 0.0548967645 0.0583486481 0.0879767612 0.0055621041 0.0056020000 41819357 955859216 1373700096 -0.0081114862 0.1650018990 -0.1839084625 1660 1311867225.8170781136 0.0543544553 0.0583462419 0.0879767612 0.0055651126 0.0054440000 41822117 955859216 1373700096 -0.0081835082 0.1657318771 -0.1849682778 1661 1311867225.8520019054 0.0547559820 0.0583440804 0.0879767612 0.0055673957 0.0098720000 41825157 955859216 1373700096 -0.0081368899 0.1666688323 -0.1857577562 1662 1311867225.8862910271 0.0549694821 0.0583420500 0.0879767612 0.0055703377 0.0066500000 41828085 955859216 1373700096 -0.0087550525 0.1676773429 -0.1863588542 1663 1311867225.9177930355 0.0551573709 0.0583401350 0.0879767612 0.0055687754 0.0057920000 41830901 955859216 1373700096 -0.0091328956 0.1685856581 -0.1867693067 1664 1311867225.9504909515 0.0548787862 0.0583380548 0.0879767612 0.0055689478 0.0054790000 41833829 955859216 1373700096 -0.0087161232 0.1695692837 -0.1874855161 1665 1311867225.9852480888 0.0555201359 0.0583363624 0.0879767612 0.0055679353 0.0090790000 41836813 955859216 1373700096 -0.0081866644 0.1707222164 -0.1879388094 1666 1311867226.0173718929 0.0557769872 0.0583348261 0.0879767612 0.0055663542 0.0064720000 41839685 955859216 1373700096 -0.0074037560 0.1720385551 -0.1887467057 1667 1311867226.0511479378 0.0556530841 0.0583332174 0.0879767612 0.0055650690 0.0055660000 41842557 955859216 1373700096 -0.0078604324 0.1735971272 -0.1895280629 1668 1311867226.0877819061 0.0557235442 0.0583316529 0.0879767612 0.0055667566 0.0101710000 41845541 955859216 1373700096 -0.0085258409 0.1752589196 -0.1900217831 1669 1311867226.1182270050 0.0559969060 0.0583302540 0.0879767612 0.0055737634 0.0066350000 41848413 955859216 1373700096 -0.0078478176 0.1765685380 -0.1903110296 1670 1311867226.1477489471 0.0557819009 0.0583287280 0.0879767612 0.0055721135 0.0056700000 41851173 955859216 1373700096 -0.0078814942 0.1782457083 -0.1907076538 1671 1311867226.1833140850 0.0561013296 0.0583273950 0.0879767612 0.0055711691 0.0055110000 41854157 955859216 1373700096 -0.0077644717 0.1799221188 -0.1908875853 1672 1311867226.2166810036 0.0563497879 0.0583262123 0.0879767612 0.0055695081 0.0055950000 41857029 955859216 1373700096 -0.0079480689 0.1813527048 -0.1912063658 1673 1311867226.2487111092 0.0561995320 0.0583249411 0.0879767612 0.0055688575 0.0055460000 41859957 955859216 1373700096 -0.0072628795 0.1830559522 -0.1917047203 1674 1311867226.2829930782 0.0568430983 0.0583240559 0.0879767612 0.0055684611 0.0055440000 41862885 955859216 1373700096 -0.0066089267 0.1845978945 -0.1920736283 1675 1311867226.3211309910 0.0569092222 0.0583232112 0.0879767612 0.0055668412 0.0055450000 41865981 955859216 1373700096 -0.0071144127 0.1864477992 -0.1926484406 1676 1311867226.3455820084 0.0563452654 0.0583220310 0.0879767612 0.0055668963 0.0061230000 41868573 955859216 1373700096 -0.0080290325 0.1883825958 -0.1932838410 1677 1311867226.3873078823 0.0568291955 0.0583211409 0.0879767612 0.0055656985 0.0056680000 41871781 955859216 1373700096 -0.0071902005 0.1897609979 -0.1934768856 1678 1311867226.4188749790 0.0564852655 0.0583200468 0.0879767612 0.0055641890 0.0056000000 41874597 955859216 1373700096 -0.0069842483 0.1914138496 -0.1939503253 1679 1311867226.4472739697 0.0567399785 0.0583191057 0.0879767612 0.0055628518 0.0055420000 41877413 955859216 1373700096 -0.0063171033 0.1929864883 -0.1940848231 1680 1311867226.4849569798 0.0571901686 0.0583184337 0.0879767612 0.0055614864 0.0137510000 41880397 955859216 1373700096 -0.0061491649 0.1946336478 -0.1946574003 1681 1311867226.5167839527 0.0573174469 0.0583178382 0.0879767612 0.0055606392 0.0071870000 41883213 955859216 1373700096 -0.0064519732 0.1960875392 -0.1952197850 1682 1311867226.5462191105 0.0571805313 0.0583171621 0.0879767612 0.0055593990 0.0059330000 41886029 955859216 1373700096 -0.0061622388 0.1975683421 -0.1957009435 1683 1311867226.5842289925 0.0572235063 0.0583165122 0.0879767612 0.0055585183 0.0055810000 41889069 955859216 1373700096 -0.0054866429 0.1990196705 -0.1961230338 1684 1311867226.6149599552 0.0571597219 0.0583158253 0.0879767612 0.0055571129 0.0093100000 41891885 955859216 1373700096 -0.0051564467 0.2002135515 -0.1964974105 1685 1311867226.6545290947 0.0576424971 0.0583154257 0.0879767612 0.0055561603 0.0065390000 41894981 955859216 1373700096 -0.0052938028 0.2015506774 -0.1966592222 1686 1311867226.6802148819 0.0573355220 0.0583148445 0.0879767612 0.0055554119 0.0056740000 41897685 955859216 1373700096 -0.0050275293 0.2029720843 -0.1972077936 1687 1311867226.7142350674 0.0580276437 0.0583146743 0.0879767612 0.0055553271 0.0055050000 41900613 955859216 1373700096 -0.0052687023 0.2039447427 -0.1976296902 1688 1311867226.7506589890 0.0581372418 0.0583145692 0.0879767612 0.0055569893 0.0054820000 41903597 955859216 1373700096 -0.0059102755 0.2047020644 -0.1980989873 1689 1311867226.7818078995 0.0581526943 0.0583144733 0.0879767612 0.0055561766 0.0112020000 41906469 955859216 1373700096 -0.0057777311 0.2058286369 -0.1985758394 1690 1311867226.8133080006 0.0578030683 0.0583141707 0.0879767612 0.0055571379 0.0069040000 41909285 955859216 1373700096 -0.0056802528 0.2064626962 -0.1991061121 1691 1311867226.8513610363 0.0583508611 0.0583141924 0.0879767612 0.0055556516 0.0056740000 41912325 955859216 1373700096 -0.0051392070 0.2071576118 -0.1994618326 1692 1311867226.8838679790 0.0586116873 0.0583143682 0.0879767612 0.0055581070 0.0087960000 41915197 955859216 1373700096 -0.0045948899 0.2082211822 -0.1997691095 1693 1311867226.9181559086 0.0587644838 0.0583146341 0.0879767612 0.0055568951 0.0064090000 41918125 955859216 1373700096 -0.0050986796 0.2090259194 -0.2003279179 1694 1311867226.9514899254 0.0591464788 0.0583151252 0.0879767612 0.0055552817 0.0098430000 41921053 955859216 1373700096 -0.0058014467 0.2096670568 -0.2008587867 1695 1311867226.9810149670 0.0588880293 0.0583154632 0.0879767612 0.0055537060 0.0066950000 41923925 955859216 1373700096 -0.0054625804 0.2108460516 -0.2014260888 1696 1311867227.0125620365 0.0588652417 0.0583157873 0.0879767612 0.0055525195 0.0057010000 41926685 955859216 1373700096 -0.0053493246 0.2119696736 -0.2019078881 1697 1311867227.0480670929 0.0590398200 0.0583162140 0.0879767612 0.0055547124 0.0055060000 41929725 955859216 1373700096 -0.0051690945 0.2131156772 -0.2022121549 1698 1311867227.0861930847 0.0590011925 0.0583166174 0.0879767612 0.0055554285 0.0055350000 41932597 955859216 1373700096 -0.0054574315 0.2146957815 -0.2023280859 1699 1311867227.1158189774 0.0591052920 0.0583170816 0.0879767612 0.0055552881 0.0099690000 41935357 955859216 1373700096 -0.0050927065 0.2161633819 -0.2023366392 1700 1311867227.1503999233 0.0596007220 0.0583178367 0.0879767612 0.0055570020 0.0068380000 41938341 955859216 1373700096 -0.0050903587 0.2174974382 -0.2020730227 1701 1311867227.1841590405 0.0594464391 0.0583185001 0.0879767612 0.0055555670 0.0057490000 41941269 955859216 1373700096 -0.0054074377 0.2194693387 -0.2017266601 1702 1311867227.2148449421 0.0596924238 0.0583193074 0.0879767612 0.0055542358 0.0055590000 41944029 955859216 1373700096 -0.0060946262 0.2206343114 -0.2017322630 1703 1311867227.2480258942 0.0600678511 0.0583203341 0.0879767612 0.0055542359 0.0055630000 41946957 955859216 1373700096 -0.0059336107 0.2218320519 -0.2015188485 1704 1311867227.2819800377 0.0600818209 0.0583213679 0.0879767612 0.0055571893 0.0130340000 41949885 955859216 1373700096 -0.0059115118 0.2232722640 -0.2013636529 1705 1311867227.3152499199 0.0602999739 0.0583225283 0.0879767612 0.0055571776 0.0075810000 41952813 955859216 1373700096 -0.0056727109 0.2243836373 -0.2012549043 1706 1311867227.3479840755 0.0598084554 0.0583233993 0.0879767612 0.0055556226 0.0060640000 41955685 955859216 1373700096 -0.0066147232 0.2256519943 -0.2013200969 1707 1311867227.3841071129 0.0599185191 0.0583243338 0.0879767612 0.0055582374 0.0095340000 41958669 955859216 1373700096 -0.0061611654 0.2265192866 -0.2011980265 1708 1311867227.4141440392 0.0596749149 0.0583251245 0.0879767612 0.0055606934 0.0066260000 41961485 955859216 1373700096 -0.0073110149 0.2274582684 -0.2012588382 1709 1311867227.4479200840 0.0597766265 0.0583259739 0.0879767612 0.0055620769 0.0087170000 41964413 955859216 1373700096 -0.0074517988 0.2286109328 -0.2012467086 1710 1311867227.4818758965 0.0601879507 0.0583270627 0.0879767612 0.0055607476 0.0064510000 41967397 955859216 1373700096 -0.0071433303 0.2292050570 -0.2013180256 1711 1311867227.5169329643 0.0601062067 0.0583281026 0.0879767612 0.0055599526 0.0056780000 41970269 955859216 1373700096 -0.0077374601 0.2300891429 -0.2014003396 1712 1311867227.5501220226 0.0598289445 0.0583289792 0.0879767612 0.0055586264 0.0093080000 41973197 955859216 1373700096 -0.0088815624 0.2308442891 -0.2016209066 1713 1311867227.5819540024 0.0597626567 0.0583298162 0.0879767612 0.0055570765 0.0065510000 41976125 955859216 1373700096 -0.0089341328 0.2315212637 -0.2017159462 1714 1311867227.6162750721 0.0598190427 0.0583306850 0.0879767612 0.0055588601 0.0056960000 41978997 955859216 1373700096 -0.0084658889 0.2322705984 -0.2015824467 1715 1311867227.6503078938 0.0592591837 0.0583312264 0.0879767612 0.0055739786 0.0101080000 41981981 955859216 1373700096 -0.0093325851 0.2327849567 -0.2015792876 1716 1311867227.6823980808 0.0592421480 0.0583317573 0.0879767612 0.0055723873 0.0068040000 41984853 955859216 1373700096 -0.0098654227 0.2332910597 -0.2015542835 1717 1311867227.7135930061 0.0592234321 0.0583322766 0.0879767612 0.0055733640 0.0058460000 41987613 955859216 1373700096 -0.0098669510 0.2340443879 -0.2014372349 1718 1311867227.7496368885 0.0594432838 0.0583329233 0.0879767612 0.0055717750 0.0055990000 41990653 955859216 1373700096 -0.0098210908 0.2348096222 -0.2010875940 1719 1311867227.7827620506 0.0595730990 0.0583336447 0.0879767612 0.0055704409 0.0089640000 41993581 955859216 1373700096 -0.0095489398 0.2355868965 -0.2008750290 1720 1311867227.8141551018 0.0596303754 0.0583343986 0.0879767612 0.0055708428 0.0065530000 41996397 955859216 1373700096 -0.0093127368 0.2367619276 -0.2005121857 1721 1311867227.8497691154 0.0596125051 0.0583351413 0.0879767612 0.0055736711 0.0056420000 41999381 955859216 1373700096 -0.0084514609 0.2379642278 -0.2002178729 1722 1311867227.8832869530 0.0599757396 0.0583360940 0.0879767612 0.0055720730 0.0099150000 42002253 955859216 1373700096 -0.0078204637 0.2389952540 -0.1997710466 1723 1311867227.9196939468 0.0602798536 0.0583372221 0.0879767612 0.0055706121 0.0067610000 42005293 955859216 1373700096 -0.0076641305 0.2401878089 -0.1994216889 1724 1311867227.9516780376 0.0604259558 0.0583384337 0.0879767612 0.0055698801 0.0058160000 42008165 955859216 1373700096 -0.0066890875 0.2415940315 -0.1993441284 1725 1311867227.9828588963 0.0603870638 0.0583396213 0.0879767612 0.0055683466 0.0096770000 42011037 955859216 1373700096 -0.0067443596 0.2427520156 -0.1991874427 1726 1311867228.0181910992 0.0601482131 0.0583406692 0.0879767612 0.0055672373 0.0067200000 42013965 955859216 1373700096 -0.0060847611 0.2442535311 -0.1989414841 1727 1311867228.0516328812 0.0604580231 0.0583418952 0.0879767612 0.0055659011 0.0057450000 42016893 955859216 1373700096 -0.0056902897 0.2454254478 -0.1986092627 1728 1311867228.0825328827 0.0606115796 0.0583432087 0.0879767612 0.0055646553 0.0056040000 42019709 955859216 1373700096 -0.0053436277 0.2465951592 -0.1984840333 1729 1311867228.1179840565 0.0609507598 0.0583447168 0.0879767612 0.0055639385 0.0136480000 42022637 955859216 1373700096 -0.0039193658 0.2477025390 -0.1984657943 1730 1311867228.1511390209 0.0618239269 0.0583467279 0.0879767612 0.0055637264 0.0073570000 42025621 955859216 1373700096 -0.0030549185 0.2490350902 -0.1981453896 1731 1311867228.1828610897 0.0622807965 0.0583490006 0.0879767612 0.0055622544 0.0060770000 42028493 955859216 1373700096 -0.0019803131 0.2501409054 -0.1982338578 1732 1311867228.2179419994 0.0624623038 0.0583513755 0.0879767612 0.0055674521 0.0056230000 42031365 955859216 1373700096 -0.0019215526 0.2511925697 -0.1982523650 1733 1311867228.2541251183 0.0629410148 0.0583540239 0.0879767612 0.0055738908 0.0094730000 42034405 955859216 1373700096 -0.0016861670 0.2525323331 -0.1984875798 1734 1311867228.2826519012 0.0626860559 0.0583565222 0.0879767612 0.0055723526 0.0068530000 42037165 955859216 1373700096 -0.0019387224 0.2535469532 -0.1987107694 1735 1311867228.3181738853 0.0630671158 0.0583592372 0.0879767612 0.0055713478 0.0058370000 42040149 955859216 1373700096 -0.0021713502 0.2544085085 -0.1985464990 1736 1311867228.3504519463 0.0627065152 0.0583617414 0.0879767612 0.0055698518 0.0092780000 42043021 955859216 1373700096 -0.0026715898 0.2557065189 -0.1987691522 1737 1311867228.3824779987 0.0628359169 0.0583643172 0.0879767612 0.0055684044 0.0065760000 42045949 955859216 1373700096 -0.0020728270 0.2567176223 -0.1987220049 1738 1311867228.4176759720 0.0627225339 0.0583668248 0.0879767612 0.0055668380 0.0057780000 42048821 955859216 1373700096 -0.0022688713 0.2573398352 -0.1987952143 1739 1311867228.4483039379 0.0625096112 0.0583692071 0.0879767612 0.0055659864 0.0094120000 42051693 955859216 1373700096 -0.0022527322 0.2581083179 -0.1987073570 1740 1311867228.4835319519 0.0627099797 0.0583717018 0.0879767612 0.0055646252 0.0067860000 42054621 955859216 1373700096 -0.0020709364 0.2583081424 -0.1986799836 1741 1311867228.5177900791 0.0628447533 0.0583742710 0.0879767612 0.0055649105 0.0099410000 42057549 955859216 1373700096 -0.0022615313 0.2584260106 -0.1987930983 1742 1311867228.5529639721 0.0626340434 0.0583767164 0.0879767612 0.0055633868 0.0067540000 42060533 955859216 1373700096 -0.0025132024 0.2581446767 -0.1992442161 1743 1311867228.5834119320 0.0623055920 0.0583789705 0.0879767612 0.0055618292 0.0057820000 42063349 955859216 1373700096 -0.0029267825 0.2577647269 -0.1998479068 1744 1311867228.6168839931 0.0621821880 0.0583811512 0.0879767612 0.0055605198 0.0056200000 42066333 955859216 1373700096 -0.0037810316 0.2567809224 -0.2002663314 1745 1311867228.6513540745 0.0618702844 0.0583831507 0.0879767612 0.0055590531 0.0118440000 42069205 955859216 1373700096 -0.0049270662 0.2557124496 -0.2008782029 1746 1311867228.6960909367 0.0619441830 0.0583851902 0.0879767612 0.0055576088 0.0071680000 42072469 955859216 1373700096 -0.0056750681 0.2543956637 -0.2014626265 1747 1311867228.7251129150 0.0609667562 0.0583866680 0.0879767612 0.0055568916 0.0059220000 42075173 955859216 1373700096 -0.0068653463 0.2534692585 -0.2021919936 1748 1311867228.7533209324 0.0607351474 0.0583880115 0.0879767612 0.0055555618 0.0057400000 42077821 955859216 1373700096 -0.0076729618 0.2523947358 -0.2028093487 1749 1311867228.7872729301 0.0605809651 0.0583892653 0.0879767612 0.0055614090 0.0098700000 42080469 955859216 1373700096 -0.0080517475 0.2510973215 -0.2032355964 1750 1311867228.8184990883 0.0612734035 0.0583909134 0.0879767612 0.0055653712 0.0093190000 42083285 955859216 1373700096 -0.0086667547 0.2501668632 -0.2036734819 1751 1311867228.8512189388 0.0602419637 0.0583919705 0.0879767612 0.0055642974 0.0067230000 42086213 955859216 1373700096 -0.0084873596 0.2495512813 -0.2042092681 1752 1311867228.8835051060 0.0604260266 0.0583931315 0.0879767612 0.0055628921 0.0058130000 42089029 955859216 1373700096 -0.0094747823 0.2478338331 -0.2047880292 1753 1311867228.9181449413 0.0602586381 0.0583941957 0.0879767612 0.0055614145 0.0056620000 42092013 955859216 1373700096 -0.0099329865 0.2466282248 -0.2052687109 1754 1311867228.9496490955 0.0594253503 0.0583947836 0.0879767612 0.0055602676 0.0057880000 42094885 955859216 1373700096 -0.0102172391 0.2457701415 -0.2059793621 1755 1311867228.9844760895 0.0594754703 0.0583953994 0.0879767612 0.0055589199 0.0092530000 42097813 955859216 1373700096 -0.0114017390 0.2438759953 -0.2064604461 1756 1311867229.0238449574 0.0594133958 0.0583959791 0.0879767612 0.0055582461 0.0091000000 42100909 955859216 1373700096 -0.0120140817 0.2423486561 -0.2068670243 1757 1311867229.0509281158 0.0589828193 0.0583963131 0.0879767612 0.0055571048 0.0066240000 42103669 955859216 1373700096 -0.0122719910 0.2411629856 -0.2073748261 1758 1311867229.0874319077 0.0587793887 0.0583965310 0.0879767612 0.0055565542 0.0057810000 42106597 955859216 1373700096 -0.0121840779 0.2395109236 -0.2076651454 1759 1311867229.1218080521 0.0587510131 0.0583967325 0.0879767612 0.0055552261 0.0057590000 42109581 955859216 1373700096 -0.0125190932 0.2378356606 -0.2078408152 1760 1311867229.1517140865 0.0590635575 0.0583971114 0.0879767612 0.0055555397 0.0094040000 42112453 955859216 1373700096 -0.0129330717 0.2362393886 -0.2078565508 1761 1311867229.1890540123 0.0587394536 0.0583973058 0.0879767612 0.0055550236 0.0067650000 42115437 955859216 1373700096 -0.0132087460 0.2345892936 -0.2079917789 1762 1311867229.2214341164 0.0589064285 0.0583975947 0.0879767612 0.0055542081 0.0058780000 42118309 955859216 1373700096 -0.0135572972 0.2326376587 -0.2080669105 1763 1311867229.2532980442 0.0586764254 0.0583977529 0.0879767612 0.0055580605 0.0063210000 42121181 955859216 1373700096 -0.0146603910 0.2308960259 -0.2085170597 1764 1311867229.2841351032 0.0585355014 0.0583978310 0.0879767612 0.0055567421 0.0058710000 42123997 955859216 1373700096 -0.0148924589 0.2290659994 -0.2089742571 1765 1311867229.3193020821 0.0580245070 0.0583976195 0.0879767612 0.0055594948 0.0119330000 42126981 955859216 1373700096 -0.0154364929 0.2270200998 -0.2095030844 1766 1311867229.3502240181 0.0582172945 0.0583975174 0.0879767612 0.0055611319 0.0071090000 42129797 955859216 1373700096 -0.0158463251 0.2249809653 -0.2099168003 1767 1311867229.3850710392 0.0580161773 0.0583973016 0.0879767612 0.0055599434 0.0168700000 42132725 955859216 1373700096 -0.0157745257 0.2229514569 -0.2104911059 1768 1311867229.4180469513 0.0581142865 0.0583971415 0.0879767612 0.0055596619 0.0142890000 42135597 955859216 1373700096 -0.0156274121 0.2207660079 -0.2109632939 1769 1311867229.4483740330 0.0582413226 0.0583970534 0.0879767612 0.0055585745 0.0075170000 42138413 955859216 1373700096 -0.0156489443 0.2184846103 -0.2112754285 1770 1311867229.4843358994 0.0581838749 0.0583969330 0.0879767612 0.0055628449 0.0061230000 42141397 955859216 1373700096 -0.0152691798 0.2163600922 -0.2118770778 1771 1311867229.5189929008 0.0580210201 0.0583967207 0.0879767612 0.0055614022 0.0056860000 42144269 955859216 1373700096 -0.0153047796 0.2143686414 -0.2127359062 1772 1311867229.5504579544 0.0579453409 0.0583964660 0.0879767612 0.0055599273 0.0167210000 42147141 955859216 1373700096 -0.0167160016 0.2122592628 -0.2130234241 1773 1311867229.5853381157 0.0574862324 0.0583959526 0.0879767612 0.0055587456 0.0118710000 42150069 955859216 1373700096 -0.0170308109 0.2104102671 -0.2137382925 1774 1311867229.6182799339 0.0576411188 0.0583955271 0.0879767612 0.0055574794 0.0071460000 42152941 955859216 1373700096 -0.0168280918 0.2084022164 -0.2141287029 1775 1311867229.6503160000 0.0578262284 0.0583952064 0.0879767612 0.0055560577 0.0058800000 42155869 955859216 1373700096 -0.0171046443 0.2065802515 -0.2143854350 1776 1311867229.6876978874 0.0575157143 0.0583947111 0.0879767612 0.0055551372 0.0088960000 42158853 955859216 1373700096 -0.0177746527 0.2049684525 -0.2147832364 1777 1311867229.7184219360 0.0575938262 0.0583942604 0.0879767612 0.0055549746 0.0088980000 42161669 955859216 1373700096 -0.0180585030 0.2033043355 -0.2152675390 1778 1311867229.7500000000 0.0577474274 0.0583938966 0.0879767612 0.0055536091 0.0066160000 42164541 955859216 1373700096 -0.0175415743 0.2016027719 -0.2154785246 1779 1311867229.7854330540 0.0576272234 0.0583934657 0.0879767612 0.0055523673 0.0064410000 42167525 955859216 1373700096 -0.0181181673 0.2005483061 -0.2158666402 1780 1311867229.8184831142 0.0577682070 0.0583931144 0.0879767612 0.0055510178 0.0058590000 42170397 955859216 1373700096 -0.0174592678 0.1991873085 -0.2162111402 1781 1311867229.8494279385 0.0578336157 0.0583928003 0.0879767612 0.0055498661 0.0057860000 42173269 955859216 1373700096 -0.0178978555 0.1975405216 -0.2165398747 1782 1311867229.8853340149 0.0574954972 0.0583922967 0.0879767612 0.0055485641 0.0057540000 42176253 955859216 1373700096 -0.0191919282 0.1960875839 -0.2170273662 1783 1311867229.9183139801 0.0572610237 0.0583916623 0.0879767612 0.0055476916 0.0056710000 42179125 955859216 1373700096 -0.0199991558 0.1945513338 -0.2177468985 1784 1311867229.9534161091 0.0573937036 0.0583911029 0.0879767612 0.0055487553 0.0057120000 42182109 955859216 1373700096 -0.0198918488 0.1928218305 -0.2180324197 1785 1311867229.9877750874 0.0569320731 0.0583902855 0.0879767612 0.0055473103 0.0092580000 42185093 955859216 1373700096 -0.0208371058 0.1914023757 -0.2184846550 1786 1311867230.0194880962 0.0565555133 0.0583892582 0.0879767612 0.0055459015 0.0066670000 42187909 955859216 1373700096 -0.0212229304 0.1899666786 -0.2191796005 1787 1311867230.0512609482 0.0563699827 0.0583881282 0.0879767612 0.0055443530 0.0058190000 42190837 955859216 1373700096 -0.0222586598 0.1880643517 -0.2198670059 1788 1311867230.0876040459 0.0561979115 0.0583869032 0.0879767612 0.0055429951 0.0090700000 42193709 955859216 1373700096 -0.0237366352 0.1862320155 -0.2203776985 1789 1311867230.1212029457 0.0561010391 0.0583856255 0.0879767612 0.0055414682 0.0089100000 42196749 955859216 1373700096 -0.0232707337 0.1844553351 -0.2210398912 1790 1311867230.1508131027 0.0561747439 0.0583843904 0.0879767612 0.0055401690 0.0066240000 42199509 955859216 1373700096 -0.0227086879 0.1827735603 -0.2217352092 1791 1311867230.1872301102 0.0554390810 0.0583827459 0.0879767612 0.0055437738 0.0057710000 42202493 955859216 1373700096 -0.0242602583 0.1811669320 -0.2223314047 1792 1311867230.2194790840 0.0561960638 0.0583815256 0.0879767612 0.0055510614 0.0087400000 42205365 955859216 1373700096 -0.0250282716 0.1796316057 -0.2230297923 1793 1311867230.2494208813 0.0553098693 0.0583798125 0.0879767612 0.0055556500 0.0066220000 42208181 955859216 1373700096 -0.0255550221 0.1780885011 -0.2238423377 1794 1311867230.2894790173 0.0559900999 0.0583784804 0.0879767612 0.0055599495 0.0095150000 42211277 955859216 1373700096 -0.0268927831 0.1766069829 -0.2247071117 1795 1311867230.3189430237 0.0560388714 0.0583771770 0.0879767612 0.0055584422 0.0067270000 42214037 955859216 1373700096 -0.0269018319 0.1751402915 -0.2253264487 1796 1311867230.3552010059 0.0559691265 0.0583758362 0.0879767612 0.0055571339 0.0058700000 42217077 955859216 1373700096 -0.0270203501 0.1737003773 -0.2260087579 1797 1311867230.3913140297 0.0559666045 0.0583744955 0.0879767612 0.0055557435 0.0093300000 42220005 955859216 1373700096 -0.0277361292 0.1722733825 -0.2266093194 1798 1311867230.4169929028 0.0560456850 0.0583732003 0.0879767612 0.0055543564 0.0066980000 42222709 955859216 1373700096 -0.0280553959 0.1709091365 -0.2272289693 1799 1311867230.4538938999 0.0558352694 0.0583717896 0.0879767612 0.0055529250 0.0058860000 42225749 955859216 1373700096 -0.0284041706 0.1697970629 -0.2278906107 1800 1311867230.4892110825 0.0548597202 0.0583698384 0.0879767612 0.0055639589 0.0093400000 42228677 955859216 1373700096 -0.0283418577 0.1683413237 -0.2284529060 1801 1311867230.5216429234 0.0545967817 0.0583677434 0.0879767612 0.0055625133 0.0069030000 42231605 955859216 1373700096 -0.0288122166 0.1671886891 -0.2289512306 1802 1311867230.5564150810 0.0555802509 0.0583661966 0.0879767612 0.0055719597 0.0058700000 42234589 955859216 1373700096 -0.0290134083 0.1660520136 -0.2292691320 1803 1311867230.5930590630 0.0558803827 0.0583648178 0.0879767612 0.0055705779 0.0057290000 42237517 955859216 1373700096 -0.0287717115 0.1647581756 -0.2295283228 1804 1311867230.6184151173 0.0559486486 0.0583634785 0.0879767612 0.0055690426 0.0114180000 42240165 955859216 1373700096 -0.0292759705 0.1637393832 -0.2299250662 1805 1311867230.6534399986 0.0556352846 0.0583619670 0.0879767612 0.0055678583 0.0069470000 42243149 955859216 1373700096 -0.0297821313 0.1626734436 -0.2302722633 1806 1311867230.6920781136 0.0555409826 0.0583604050 0.0879767612 0.0055667951 0.0059570000 42246245 955859216 1373700096 -0.0297391247 0.1613391787 -0.2305671871 1807 1311867230.7185189724 0.0557017587 0.0583589337 0.0879767612 0.0055654648 0.0093020000 42248893 955859216 1373700096 -0.0308895875 0.1599831581 -0.2308303416 1808 1311867230.7529120445 0.0555370934 0.0583573730 0.0879767612 0.0055641583 0.0067150000 42251877 955859216 1373700096 -0.0311743096 0.1587392092 -0.2313040495 1809 1311867230.7871611118 0.0547020882 0.0583553524 0.0879767612 0.0055725045 0.0058620000 42254861 955859216 1373700096 -0.0312216338 0.1577560902 -0.2314032763 1810 1311867230.8195741177 0.0557387248 0.0583539067 0.0879767612 0.0055794431 0.0059270000 42257677 955859216 1373700096 -0.0312783793 0.1568934917 -0.2313979566 1811 1311867230.8534181118 0.0557304211 0.0583524581 0.0879767612 0.0055780192 0.0058690000 42260605 955859216 1373700096 -0.0311815049 0.1562255323 -0.2314401716 1812 1311867230.8890159130 0.0555087663 0.0583508887 0.0879767612 0.0055766451 0.0057920000 42263589 955859216 1373700096 -0.0311727598 0.1555629671 -0.2316130102 1813 1311867230.9176509380 0.0555174947 0.0583493259 0.0879767612 0.0055752741 0.0057860000 42266405 955859216 1373700096 -0.0315859802 0.1550177038 -0.2316689938 1814 1311867230.9559168816 0.0557075217 0.0583478696 0.0879767612 0.0055738124 0.0169510000 42269389 955859216 1373700096 -0.0317388847 0.1543898433 -0.2317159325 1815 1311867230.9881010056 0.0558021329 0.0583464669 0.0879767612 0.0055726423 0.0126260000 42272261 955859216 1373700096 -0.0323580578 0.1540822983 -0.2318444550 1816 1311867231.0166280270 0.0557310879 0.0583450268 0.0879767612 0.0055715231 0.0074770000 42275077 955859216 1373700096 -0.0322950929 0.1535860300 -0.2322513759 1817 1311867231.0603969097 0.0556427501 0.0583435395 0.0879767612 0.0055702502 0.0074650000 42278173 955859216 1373700096 -0.0327290967 0.1530079246 -0.2326233089 1818 1311867231.0868620872 0.0553668067 0.0583419022 0.0879767612 0.0055688277 0.0072240000 42280821 955859216 1373700096 -0.0333091281 0.1522920132 -0.2331371307 1819 1311867231.1221020222 0.0553306825 0.0583402467 0.0879767612 0.0055677271 0.0059900000 42283861 955859216 1373700096 -0.0334650725 0.1512830853 -0.2335520685 1820 1311867231.1523799896 0.0553159527 0.0583385850 0.0879767612 0.0055705539 0.0140590000 42286621 955859216 1373700096 -0.0345275663 0.1502159387 -0.2339806855 1821 1311867231.1860070229 0.0550523698 0.0583367804 0.0879767612 0.0055690382 0.0074550000 42289549 955859216 1373700096 -0.0355274864 0.1490780562 -0.2347652614 1822 1311867231.2188270092 0.0552562252 0.0583350897 0.0879767612 0.0055685147 0.0061960000 42292421 955859216 1373700096 -0.0363118276 0.1478319466 -0.2351074070 1823 1311867231.2522621155 0.0549181812 0.0583332153 0.0879767612 0.0055689481 0.0057450000 42295349 955859216 1373700096 -0.0366459154 0.1466326416 -0.2358029634 1824 1311867231.2864110470 0.0547874458 0.0583312714 0.0879767612 0.0055689198 0.0057530000 42298277 955859216 1373700096 -0.0379979648 0.1455946118 -0.2364891022 1825 1311867231.3215939999 0.0548388772 0.0583293577 0.0879767612 0.0055676623 0.0057500000 42301261 955859216 1373700096 -0.0402461477 0.1440951228 -0.2369697392 1826 1311867231.3525509834 0.0547048450 0.0583273728 0.0879767612 0.0055662932 0.0103740000 42304077 955859216 1373700096 -0.0405158587 0.1426565945 -0.2374429852 1827 1311867231.3874650002 0.0544990599 0.0583252774 0.0879767612 0.0055648760 0.0098880000 42307005 955859216 1373700096 -0.0398645438 0.1414052695 -0.2377415299 1828 1311867231.4187040329 0.0541105419 0.0583229717 0.0879767612 0.0055634528 0.0069280000 42309877 955859216 1373700096 -0.0400227383 0.1403808594 -0.2380775660 1829 1311867231.4542400837 0.0540789850 0.0583206513 0.0879767612 0.0055621005 0.0059450000 42312861 955859216 1373700096 -0.0402411297 0.1392323524 -0.2379641384 1830 1311867231.4867990017 0.0537615269 0.0583181600 0.0879767612 0.0055606826 0.0058900000 42315733 955859216 1373700096 -0.0413025729 0.1380619556 -0.2380457819 1831 1311867231.5193030834 0.0538667925 0.0583157289 0.0879767612 0.0055594265 0.0096660000 42318605 955859216 1373700096 -0.0410886444 0.1370488554 -0.2378437966 1832 1311867231.5524148941 0.0538886599 0.0583133124 0.0879767612 0.0055584421 0.0174020000 42321477 955859216 1373700096 -0.0409366786 0.1361455172 -0.2377661467 1833 1311867231.5855851173 0.0532561615 0.0583105534 0.0879767612 0.0055625596 0.0130410000 42324461 955859216 1373700096 -0.0413660966 0.1353338659 -0.2376427650 1834 1311867231.6210820675 0.0540923066 0.0583082534 0.0879767612 0.0055722974 0.0075790000 42327389 955859216 1373700096 -0.0412823036 0.1346443594 -0.2378442883 1835 1311867231.6522169113 0.0541165359 0.0583059691 0.0879767612 0.0055709840 0.0075750000 42330261 955859216 1373700096 -0.0416729301 0.1338456124 -0.2380923778 1836 1311867231.6880500317 0.0539856814 0.0583036160 0.0879767612 0.0055694781 0.0073570000 42333245 955859216 1373700096 -0.0414109789 0.1328920424 -0.2382895797 1837 1311867231.7208089828 0.0538338162 0.0583011828 0.0879767612 0.0055683201 0.0067420000 42336173 955859216 1373700096 -0.0410055891 0.1319128275 -0.2386305630 1838 1311867231.7523078918 0.0539245233 0.0582988016 0.0879767612 0.0055695475 0.0137220000 42338933 955859216 1373700096 -0.0406632535 0.1310427338 -0.2390062064 1839 1311867231.7860589027 0.0541367531 0.0582965384 0.0879767612 0.0055680948 0.0077760000 42341917 955859216 1373700096 -0.0415219069 0.1300680637 -0.2393177748 1840 1311867231.8202130795 0.0543292835 0.0582943823 0.0879767612 0.0055676447 0.0062880000 42344845 955859216 1373700096 -0.0423533246 0.1288643479 -0.2398815602 1841 1311867231.8521840572 0.0540903248 0.0582920987 0.0879767612 0.0055667724 0.0059390000 42347661 955859216 1373700096 -0.0424649566 0.1276211590 -0.2403243631 1842 1311867231.8857500553 0.0536218397 0.0582895633 0.0879767612 0.0055657244 0.0059410000 42350645 955859216 1373700096 -0.0426199920 0.1262879670 -0.2409323156 1843 1311867231.9208559990 0.0536753647 0.0582870596 0.0879767612 0.0055642521 0.0103650000 42353629 955859216 1373700096 -0.0428477041 0.1249876842 -0.2415784597 1844 1311867231.9533181190 0.0538540855 0.0582846556 0.0879767612 0.0055633802 0.0070040000 42356445 955859216 1373700096 -0.0435688607 0.1233654842 -0.2420316041 1845 1311867231.9870491028 0.0539011769 0.0582822798 0.0879767612 0.0055620354 0.0059720000 42359373 955859216 1373700096 -0.0433188640 0.1220891252 -0.2424779385 1846 1311867232.0202860832 0.0541314855 0.0582800312 0.0879767612 0.0055606050 0.0101890000 42362301 955859216 1373700096 -0.0443617664 0.1207702309 -0.2428436428 1847 1311867232.0522420406 0.0538524985 0.0582776341 0.0879767612 0.0055591542 0.0070460000 42365173 955859216 1373700096 -0.0445218273 0.1194992661 -0.2433824837 1848 1311867232.0878489017 0.0539068803 0.0582752689 0.0879767612 0.0055576794 0.0060320000 42368157 955859216 1373700096 -0.0447862409 0.1182063073 -0.2438165694 1849 1311867232.1203238964 0.0544528030 0.0582732016 0.0879767612 0.0055575232 0.0058500000 42371029 955859216 1373700096 -0.0444293916 0.1171975210 -0.2442782968 1850 1311867232.1545510292 0.0538397059 0.0582708051 0.0879767612 0.0055566097 0.0057890000 42373957 955859216 1373700096 -0.0438687615 0.1158853844 -0.2446761429 1851 1311867232.1846179962 0.0536618829 0.0582683152 0.0879767612 0.0055556789 0.0101920000 42376773 955859216 1373700096 -0.0440154374 0.1146875471 -0.2452895343 1852 1311867232.2209780216 0.0537132993 0.0582658557 0.0879767612 0.0055546606 0.0071290000 42379757 955859216 1373700096 -0.0451570004 0.1136771366 -0.2456647903 1853 1311867232.2531120777 0.0535599887 0.0582633161 0.0879767612 0.0055532637 0.0101890000 42382573 955859216 1373700096 -0.0445176028 0.1126895249 -0.2460821271 1854 1311867232.2844479084 0.0535351038 0.0582607658 0.0879767612 0.0055524648 0.0069890000 42385501 955859216 1373700096 -0.0448044688 0.1113238037 -0.2466004044 1855 1311867232.3209791183 0.0532827601 0.0582580822 0.0879767612 0.0055511744 0.0059960000 42388485 955859216 1373700096 -0.0457667671 0.1102818847 -0.2471282482 1856 1311867232.3544659615 0.0530753843 0.0582552898 0.0879767612 0.0055501207 0.0100650000 42391357 955859216 1373700096 -0.0454586782 0.1094249934 -0.2474751920 1857 1311867232.3858909607 0.0533977039 0.0582526740 0.0879767612 0.0055486384 0.0070870000 42394229 955859216 1373700096 -0.0457837731 0.1082935929 -0.2478764653 1858 1311867232.4203910828 0.0532397069 0.0582499760 0.0879767612 0.0055479406 0.0061070000 42397157 955859216 1373700096 -0.0453829020 0.1074686274 -0.2483524680 1859 1311867232.4544560909 0.0532491505 0.0582472859 0.0879767612 0.0055465054 0.0061270000 42400085 955859216 1373700096 -0.0451232940 0.1066257954 -0.2485350221 1860 1311867232.4846010208 0.0526474230 0.0582442752 0.0879767612 0.0055504610 0.0093660000 42402901 955859216 1373700096 -0.0452929549 0.1056995913 -0.2487283349 1861 1311867232.5203030109 0.0526925661 0.0582412920 0.0879767612 0.0055502255 0.0067430000 42405885 955859216 1373700096 -0.0451920219 0.1047323346 -0.2489358485 1862 1311867232.5550050735 0.0511160381 0.0582374654 0.0879767612 0.0055512094 0.0059550000 42408813 955859216 1373700096 -0.0453928746 0.1038749740 -0.2490703464 1863 1311867232.5844318867 0.0526694804 0.0582344767 0.0879767612 0.0055524221 0.0092610000 42411573 955859216 1373700096 -0.0448210575 0.1029116288 -0.2492673695 1864 1311867232.6201601028 0.0525816530 0.0582314440 0.0879767612 0.0055510416 0.0068160000 42414557 955859216 1373700096 -0.0445407964 0.1022647992 -0.2493665516 1865 1311867232.6554861069 0.0525106862 0.0582283766 0.0879767612 0.0055503406 0.0060040000 42417373 955859216 1373700096 -0.0429681689 0.1010465771 -0.2493399829 1866 1311867232.6850490570 0.0525990874 0.0582253598 0.0879767612 0.0055489783 0.0102470000 42420189 955859216 1373700096 -0.0429523140 0.0998643339 -0.2495503426 1867 1311867232.7210319042 0.0524711944 0.0582222778 0.0879767612 0.0055475162 0.0070870000 42423173 955859216 1373700096 -0.0428214520 0.0986791030 -0.2497126609 1868 1311867232.7539520264 0.0523877703 0.0582191544 0.0879767612 0.0055467428 0.0061060000 42425989 955859216 1373700096 -0.0428118296 0.0975832865 -0.2497517914 1869 1311867232.7885808945 0.0524118207 0.0582160472 0.0879767612 0.0055453883 0.0061300000 42428917 955859216 1373700096 -0.0425826833 0.0960356519 -0.2497963756 1870 1311867232.8206169605 0.0526844673 0.0582130891 0.0879767612 0.0055440507 0.0060670000 42431845 955859216 1373700096 -0.0433206931 0.0940069109 -0.2500332594 1871 1311867232.8539369106 0.0525089093 0.0582100404 0.0879767612 0.0055426558 0.0060310000 42434717 955859216 1373700096 -0.0427568406 0.0929072350 -0.2501704395 1872 1311867232.8882710934 0.0525229760 0.0582070024 0.0879767612 0.0055411868 0.0059960000 42437645 955859216 1373700096 -0.0422432758 0.0915906057 -0.2503081262 1873 1311867232.9203770161 0.0524081364 0.0582039064 0.0879767612 0.0055402922 0.0059870000 42440573 955859216 1373700096 -0.0430185087 0.0901160389 -0.2507136166 1874 1311867232.9559900761 0.0522417873 0.0582007249 0.0879767612 0.0055388769 0.0059660000 42443557 955859216 1373700096 -0.0431476794 0.0884513333 -0.2509534657 1875 1311867232.9890038967 0.0522979647 0.0581975768 0.0879767612 0.0055385091 0.0059790000 42446373 955859216 1373700096 -0.0443972349 0.0873215348 -0.2511667311 1876 1311867233.0212259293 0.0522713363 0.0581944178 0.0879767612 0.0055373377 0.0059090000 42449301 955859216 1373700096 -0.0438831635 0.0857032612 -0.2513253093 1877 1311867233.0569291115 0.0521105044 0.0581911765 0.0879767612 0.0055364027 0.0059890000 42452229 955859216 1373700096 -0.0441156030 0.0845147297 -0.2513938546 1878 1311867233.0943200588 0.0520921685 0.0581879289 0.0879767612 0.0055354082 0.0135170000 42455269 955859216 1373700096 -0.0433971770 0.0833952427 -0.2513245940 1879 1311867233.1241600513 0.0524562187 0.0581848785 0.0879767612 0.0055343457 0.0075070000 42457973 955859216 1373700096 -0.0437710546 0.0819731951 -0.2512002587 1880 1311867233.1530799866 0.0519285351 0.0581815506 0.0879767612 0.0055348166 0.0061910000 42460733 955859216 1373700096 -0.0431103297 0.0808943585 -0.2512540817 1881 1311867233.1887679100 0.0522479489 0.0581783962 0.0879767612 0.0055342662 0.0059220000 42463717 955859216 1373700096 -0.0431460962 0.0798687860 -0.2510904074 1882 1311867233.2210481167 0.0520015918 0.0581751141 0.0879767612 0.0055328437 0.0060090000 42466589 955859216 1373700096 -0.0427856781 0.0787440911 -0.2512460947 1883 1311867233.2590179443 0.0523230098 0.0581720063 0.0879767612 0.0055315174 0.0059820000 42469629 955859216 1373700096 -0.0436934084 0.0770959631 -0.2511967123 1884 1311867233.2899589539 0.0519367792 0.0581686967 0.0879767612 0.0055301736 0.0059100000 42472501 955859216 1373700096 -0.0432701185 0.0759055316 -0.2511823773 1885 1311867233.3212211132 0.0518084653 0.0581653226 0.0879767612 0.0055298885 0.0096580000 42475373 955859216 1373700096 -0.0435293987 0.0746183470 -0.2510386705 1886 1311867233.3533849716 0.0523202978 0.0581622234 0.0879767612 0.0055291211 0.0068530000 42478189 955859216 1373700096 -0.0436479896 0.0726444423 -0.2510789335 1887 1311867233.3884561062 0.0522308089 0.0581590801 0.0879767612 0.0055308877 0.0059940000 42481173 955859216 1373700096 -0.0445904657 0.0714216456 -0.2511616647 1888 1311867233.4236669540 0.0520395190 0.0581558388 0.0879767612 0.0055356527 0.0058910000 42484101 955859216 1373700096 -0.0445099100 0.0699227005 -0.2512530982 1889 1311867233.4522700310 0.0523481369 0.0581527643 0.0879767612 0.0055368552 0.0059550000 42486973 955859216 1373700096 -0.0452906452 0.0677989125 -0.2516376674 1890 1311867233.4881610870 0.0523763560 0.0581497080 0.0879767612 0.0055403898 0.0059030000 42489845 955859216 1373700096 -0.0457788743 0.0662135035 -0.2518441081 1891 1311867233.5201199055 0.0520669632 0.0581464913 0.0879767612 0.0055403556 0.0059100000 42492773 955859216 1373700096 -0.0458589308 0.0654253513 -0.2520156205 1892 1311867233.5526270866 0.0521245226 0.0581433085 0.0879767612 0.0055403659 0.0137330000 42495645 955859216 1373700096 -0.0461303629 0.0640952885 -0.2521807551 1893 1311867233.5890851021 0.0518187396 0.0581399674 0.0879767612 0.0055390768 0.0075910000 42498629 955859216 1373700096 -0.0453786887 0.0632539988 -0.2521949112 1894 1311867233.6202619076 0.0519218259 0.0581366844 0.0879767612 0.0055376866 0.0062170000 42501501 955859216 1373700096 -0.0456198007 0.0623311363 -0.2520761490 1895 1311867233.6539080143 0.0517787449 0.0581333293 0.0879767612 0.0055376764 0.0096250000 42504373 955859216 1373700096 -0.0457982942 0.0613271855 -0.2522424459 1896 1311867233.6879289150 0.0519084595 0.0581300461 0.0879767612 0.0055364477 0.0068640000 42507301 955859216 1373700096 -0.0464512818 0.0603160039 -0.2522238493 1897 1311867233.7197790146 0.0519054495 0.0581267648 0.0879767612 0.0055350888 0.0059960000 42510229 955859216 1373700096 -0.0461322106 0.0597602427 -0.2521524131 1898 1311867233.7577540874 0.0518599600 0.0581234630 0.0879767612 0.0055338962 0.0094600000 42513269 955859216 1373700096 -0.0462292880 0.0590970181 -0.2521285713 1899 1311867233.7896089554 0.0517491028 0.0581201063 0.0879767612 0.0055334514 0.0068810000 42516141 955859216 1373700096 -0.0472088158 0.0583237223 -0.2521896064 1900 1311867233.8221189976 0.0517891496 0.0581167742 0.0879767612 0.0055337198 0.0059630000 42519069 955859216 1373700096 -0.0479616672 0.0574476048 -0.2521668673 1901 1311867233.8562450409 0.0519250929 0.0581135172 0.0879767612 0.0055323463 0.0059760000 42521941 955859216 1373700096 -0.0482913479 0.0562598668 -0.2520769835 1902 1311867233.8885691166 0.0520171784 0.0581103119 0.0879767612 0.0055310621 0.0059210000 42524813 955859216 1373700096 -0.0487412475 0.0553719178 -0.2519161701 1903 1311867233.9203450680 0.0518163443 0.0581070046 0.0879767612 0.0055299452 0.0103740000 42527685 955859216 1373700096 -0.0485639088 0.0546762012 -0.2518027723 1904 1311867233.9552910328 0.0515936539 0.0581035837 0.0879767612 0.0055285861 0.0070160000 42530669 955859216 1373700096 -0.0485631861 0.0534660183 -0.2518800795 1905 1311867233.9885900021 0.0514973216 0.0581001158 0.0879767612 0.0055272138 0.0060960000 42533541 955859216 1373700096 -0.0486740321 0.0524410978 -0.2518611848 1906 1311867234.0205829144 0.0512869768 0.0580965412 0.0879767612 0.0055257874 0.0059390000 42536413 955859216 1373700096 -0.0488447584 0.0519558117 -0.2520171702 1907 1311867234.0566239357 0.0514378548 0.0580930495 0.0879767612 0.0055244528 0.0106040000 42539453 955859216 1373700096 -0.0495533869 0.0506640188 -0.2520946562 1908 1311867234.0907170773 0.0512858629 0.0580894818 0.0879767612 0.0055230275 0.0071700000 42542325 955859216 1373700096 -0.0497128405 0.0497064255 -0.2522974610 1909 1311867234.1214520931 0.0513750352 0.0580859646 0.0879767612 0.0055216787 0.0061000000 42545197 955859216 1373700096 -0.0499689318 0.0487422086 -0.2522433400 1910 1311867234.1561689377 0.0514817871 0.0580825069 0.0879767612 0.0055203010 0.0059410000 42548125 955859216 1373700096 -0.0504620448 0.0471803620 -0.2522976696 1911 1311867234.1892559528 0.0517959967 0.0580792172 0.0879767612 0.0055189922 0.0065650000 42550997 955859216 1373700096 -0.0518212318 0.0456974953 -0.2522612214 1912 1311867234.2203600407 0.0517072454 0.0580758846 0.0879767612 0.0055187550 0.0060430000 42553869 955859216 1373700096 -0.0523194931 0.0448519252 -0.2524162531 1913 1311867234.2588930130 0.0514577664 0.0580724251 0.0879767612 0.0055174803 0.0104350000 42556909 955859216 1373700096 -0.0531537756 0.0436357930 -0.2524890602 1914 1311867234.2895319462 0.0512632541 0.0580688675 0.0879767612 0.0055162085 0.0096520000 42559781 955859216 1373700096 -0.0532046370 0.0426402427 -0.2523508668 1915 1311867234.3213200569 0.0510368347 0.0580651954 0.0879767612 0.0055181990 0.0069430000 42562653 955859216 1373700096 -0.0539867543 0.0418764427 -0.2520190477 1916 1311867234.3570129871 0.0507667810 0.0580613862 0.0879767612 0.0055168004 0.0060460000 42565581 955859216 1373700096 -0.0542049520 0.0414789915 -0.2517414093 1917 1311867234.3885769844 0.0506410487 0.0580575154 0.0879767612 0.0055158968 0.0059400000 42568453 955859216 1373700096 -0.0541811287 0.0403703190 -0.2514908016 1918 1311867234.4204909801 0.0507681519 0.0580537149 0.0879767612 0.0055144845 0.0059630000 42571381 955859216 1373700096 -0.0543646812 0.0393484198 -0.2510311902 1919 1311867234.4579920769 0.0504370816 0.0580497459 0.0879767612 0.0055133205 0.0097970000 42574309 955859216 1373700096 -0.0533233732 0.0392154977 -0.2506741285 1920 1311867234.4878959656 0.0508692041 0.0580460060 0.0879767612 0.0055172099 0.0069620000 42577181 955859216 1373700096 -0.0545613281 0.0379572399 -0.2504696548 1921 1311867234.5201239586 0.0511039495 0.0580423922 0.0879767612 0.0055158334 0.0062120000 42580053 955859216 1373700096 -0.0551310591 0.0364434384 -0.2501533031 1922 1311867234.5594279766 0.0508026443 0.0580386255 0.0879767612 0.0055152838 0.0060070000 42583149 955859216 1373700096 -0.0551659241 0.0360711627 -0.2497135848 1923 1311867234.5882380009 0.0510052703 0.0580349680 0.0879767612 0.0055149221 0.0100290000 42585965 955859216 1373700096 -0.0548022687 0.0348774865 -0.2492693365 1924 1311867234.6204199791 0.0512478016 0.0580314403 0.0879767612 0.0055135901 0.0069760000 42588837 955859216 1373700096 -0.0549129993 0.0334978327 -0.2489290833 1925 1311867234.6590909958 0.0504489988 0.0580275014 0.0879767612 0.0055129309 0.0101490000 42591877 955859216 1373700096 -0.0543827564 0.0337504707 -0.2484929860 1926 1311867234.6880459785 0.0502983965 0.0580234884 0.0879767612 0.0055115963 0.0070870000 42594637 955859216 1373700096 -0.0536875017 0.0332354568 -0.2480978072 1927 1311867234.7198779583 0.0504191108 0.0580195421 0.0879767612 0.0055112663 0.0061360000 42597509 955859216 1373700096 -0.0537159964 0.0323025063 -0.2474824339 1928 1311867234.7586181164 0.0499938950 0.0580153795 0.0879767612 0.0055098720 0.0059290000 42600493 955859216 1373700096 -0.0525249764 0.0319263823 -0.2465801388 1929 1311867234.7882609367 0.0495397635 0.0580109857 0.0879767612 0.0055162701 0.0059730000 42603365 955859216 1373700096 -0.0524553768 0.0318224430 -0.2456171662 1930 1311867234.8206560612 0.0496622585 0.0580066599 0.0879767612 0.0055149681 0.0112330000 42606237 955859216 1373700096 -0.0528603382 0.0312684216 -0.2447194010 1931 1311867234.8590250015 0.0494782478 0.0580022433 0.0879767612 0.0055135980 0.0073360000 42609221 955859216 1373700096 -0.0517025143 0.0316107832 -0.2437576205 1932 1311867234.8881230354 0.0499451570 0.0579980730 0.0879767612 0.0055123973 0.0061280000 42612037 955859216 1373700096 -0.0512774102 0.0312721208 -0.2427264005 1933 1311867234.9204928875 0.0504510142 0.0579941687 0.0879767612 0.0055116465 0.0059270000 42614965 955859216 1373700096 -0.0519972742 0.0303996634 -0.2420225143 1934 1311867234.9566090107 0.0506170355 0.0579903542 0.0879767612 0.0055103621 0.0098930000 42617949 955859216 1373700096 -0.0519791655 0.0301977582 -0.2415094674 1935 1311867234.9904088974 0.0509880148 0.0579867354 0.0879767612 0.0055089731 0.0073650000 42620877 955859216 1373700096 -0.0525740720 0.0294893533 -0.2410478443 1936 1311867235.0205988884 0.0510645844 0.0579831600 0.0879767612 0.0055079059 0.0105740000 42623693 955859216 1373700096 -0.0527084619 0.0286757294 -0.2410633117 1937 1311867235.0563809872 0.0511140749 0.0579796137 0.0879767612 0.0055079460 0.0098440000 42626677 955859216 1373700096 -0.0528391339 0.0276606567 -0.2411052287 1938 1311867235.0911149979 0.0512079522 0.0579761196 0.0879767612 0.0055065837 0.0070170000 42629605 955859216 1373700096 -0.0544047914 0.0269469228 -0.2410359234 1939 1311867235.1208140850 0.0514351800 0.0579727462 0.0879767612 0.0055052721 0.0061160000 42632477 955859216 1373700096 -0.0555925407 0.0258112606 -0.2409695834 1940 1311867235.1564071178 0.0508634709 0.0579690816 0.0879767612 0.0055047578 0.0066150000 42635405 955859216 1373700096 -0.0543577634 0.0255849827 -0.2406252772 1941 1311867235.1885681152 0.0507731177 0.0579653743 0.0879767612 0.0055042586 0.0061970000 42638277 955859216 1373700096 -0.0544325188 0.0246995371 -0.2402403504 1942 1311867235.2202088833 0.0507015176 0.0579616339 0.0879767612 0.0055029925 0.0060430000 42641149 955859216 1373700096 -0.0555156283 0.0239454657 -0.2402136177 1943 1311867235.2576260567 0.0509758331 0.0579580385 0.0879767612 0.0055023356 0.0060460000 42644021 955859216 1373700096 -0.0559749566 0.0240059774 -0.2399268299 1944 1311867235.2899661064 0.0508206002 0.0579543670 0.0879767612 0.0055025140 0.0059700000 42646949 955859216 1373700096 -0.0575749539 0.0232411269 -0.2398258895 1945 1311867235.3247830868 0.0506549627 0.0579506141 0.0879767612 0.0055012269 0.0060650000 42649933 955859216 1373700096 -0.0577107556 0.0228144992 -0.2398344576 1946 1311867235.3567800522 0.0497676097 0.0579464090 0.0879767612 0.0055126499 0.0141080000 42652805 955859216 1373700096 -0.0588622764 0.0227769781 -0.2395098656 1947 1311867235.3886280060 0.0507433005 0.0579427094 0.0879767612 0.0055229233 0.0076410000 42655677 955859216 1373700096 -0.0590482764 0.0225124955 -0.2392004430 1948 1311867235.4246189594 0.0504850410 0.0579388811 0.0879767612 0.0055222661 0.0063710000 42658661 955859216 1373700096 -0.0601977706 0.0223735832 -0.2386746109 1949 1311867235.4564850330 0.0507273376 0.0579351809 0.0879767612 0.0055216408 0.0060650000 42661533 955859216 1373700096 -0.0602089278 0.0228681453 -0.2378822863 1950 1311867235.4897930622 0.0505380817 0.0579313876 0.0879767612 0.0055216494 0.0107380000 42664405 955859216 1373700096 -0.0603863858 0.0228260104 -0.2370240241 1951 1311867235.5240719318 0.0508873016 0.0579277771 0.0879767612 0.0055208945 0.0072250000 42667333 955859216 1373700096 -0.0614340901 0.0227353107 -0.2363249362 1952 1311867235.5577290058 0.0507975370 0.0579241243 0.0879767612 0.0055198440 0.0061450000 42670205 955859216 1373700096 -0.0608339906 0.0232735034 -0.2354520857 1953 1311867235.5880639553 0.0513342842 0.0579207501 0.0879767612 0.0055185297 0.0060490000 42673077 955859216 1373700096 -0.0615335554 0.0227133371 -0.2347819507 1954 1311867235.6249940395 0.0517551303 0.0579175947 0.0879767612 0.0055174618 0.0060260000 42676117 955859216 1373700096 -0.0619776621 0.0213508103 -0.2345408201 1955 1311867235.6563270092 0.0516375341 0.0579143824 0.0879767612 0.0055167902 0.0060190000 42678933 955859216 1373700096 -0.0624667518 0.0218684003 -0.2341641933 1956 1311867235.6885619164 0.0517686754 0.0579112404 0.0879767612 0.0055155670 0.0060250000 42681805 955859216 1373700096 -0.0632410496 0.0214402154 -0.2338720262 1957 1311867235.7241950035 0.0516431108 0.0579080375 0.0879767612 0.0055142260 0.0113300000 42684789 955859216 1373700096 -0.0641703308 0.0209394414 -0.2336661369 1958 1311867235.7561719418 0.0513218530 0.0579046737 0.0879767612 0.0055131379 0.0073210000 42687717 955859216 1373700096 -0.0640858561 0.0210260227 -0.2331217080 1959 1311867235.7903280258 0.0513975732 0.0579013521 0.0879767612 0.0055123775 0.0062320000 42690589 955859216 1373700096 -0.0645983070 0.0206496175 -0.2324770987 1960 1311867235.8249480724 0.0514708385 0.0578980712 0.0879767612 0.0055111757 0.0060700000 42693517 955859216 1373700096 -0.0650014579 0.0203587972 -0.2317387462 1961 1311867235.8562169075 0.0515725315 0.0578948455 0.0879767612 0.0055110574 0.0061090000 42696445 955859216 1373700096 -0.0650499612 0.0210025441 -0.2306506485 1962 1311867235.8881049156 0.0519814417 0.0578918316 0.0879767612 0.0055097227 0.0098630000 42699205 955859216 1373700096 -0.0661529750 0.0206995774 -0.2298095524 1963 1311867235.9239900112 0.0522058606 0.0578889350 0.0879767612 0.0055083276 0.0095530000 42702245 955859216 1373700096 -0.0664712787 0.0201059338 -0.2288917154 1964 1311867235.9563760757 0.0523633659 0.0578861216 0.0879767612 0.0055075924 0.0070540000 42705173 955859216 1373700096 -0.0658579096 0.0204975754 -0.2282053977 1965 1311867235.9890949726 0.0520003475 0.0578831263 0.0879767612 0.0055069601 0.0062140000 42707989 955859216 1373700096 -0.0669337809 0.0200022850 -0.2278079391 1966 1311867236.0250449181 0.0519433618 0.0578801050 0.0879767612 0.0055056320 0.0060830000 42710973 955859216 1373700096 -0.0674413070 0.0196867026 -0.2272824198 1967 1311867236.0599400997 0.0516470037 0.0578769362 0.0879767612 0.0055042455 0.0105910000 42713901 955859216 1373700096 -0.0673774481 0.0197631083 -0.2265800387 1968 1311867236.0884859562 0.0518463776 0.0578738719 0.0879767612 0.0055029590 0.0072010000 42716661 955859216 1373700096 -0.0677937046 0.0195447002 -0.2256739289 1969 1311867236.1247038841 0.0517887734 0.0578707814 0.0879767612 0.0055016341 0.0062510000 42719701 955859216 1373700096 -0.0678252429 0.0195632018 -0.2246622592 1970 1311867236.1581289768 0.0522637554 0.0578679352 0.0879767612 0.0055008580 0.0060360000 42722573 955859216 1373700096 -0.0683637112 0.0196689386 -0.2234955281 1971 1311867236.1901528835 0.0519402698 0.0578649278 0.0879767612 0.0054996676 0.0091030000 42725389 955859216 1373700096 -0.0696414635 0.0198703408 -0.2223216891 1972 1311867236.2242329121 0.0514405929 0.0578616700 0.0879767612 0.0054983778 0.0104650000 42728317 955859216 1373700096 -0.0695025995 0.0197800398 -0.2212198675 1973 1311867236.2599489689 0.0511141270 0.0578582501 0.0879767612 0.0054973239 0.0073320000 42731301 955859216 1373700096 -0.0698111206 0.0199676380 -0.2199427485 1974 1311867236.2890419960 0.0514426306 0.0578550000 0.0879767612 0.0054960245 0.0062990000 42734061 955859216 1373700096 -0.0706190541 0.0197143517 -0.2187618762 1975 1311867236.3262441158 0.0518795177 0.0578519745 0.0879767612 0.0054950048 0.0061170000 42737101 955859216 1373700096 -0.0710480958 0.0195100065 -0.2173116654 1976 1311867236.3568809032 0.0519295521 0.0578489773 0.0879767612 0.0054939852 0.0061100000 42739973 955859216 1373700096 -0.0709254071 0.0188856740 -0.2161132395 1977 1311867236.3897418976 0.0518375300 0.0578459366 0.0879767612 0.0054926450 0.0097780000 42742845 955859216 1373700096 -0.0717045441 0.0187020339 -0.2149600387 1978 1311867236.4243390560 0.0510593876 0.0578425056 0.0879767612 0.0054937923 0.0070400000 42745773 955859216 1373700096 -0.0715826675 0.0185513888 -0.2134840190 1979 1311867236.4566040039 0.0509406403 0.0578390180 0.0879767612 0.0054927419 0.0104450000 42748701 955859216 1373700096 -0.0717534870 0.0186720304 -0.2120784670 1980 1311867236.4936130047 0.0516032502 0.0578358686 0.0879767612 0.0054968214 0.0099800000 42751685 955859216 1373700096 -0.0723951757 0.0182931609 -0.2106389701 1981 1311867236.5246999264 0.0516135320 0.0578327276 0.0879767612 0.0054955582 0.0096770000 42754557 955859216 1373700096 -0.0728826970 0.0185598843 -0.2090059966 1982 1311867236.5602099895 0.0511450134 0.0578293534 0.0879767612 0.0054959859 0.0070600000 42757541 955859216 1373700096 -0.0727754682 0.0186007898 -0.2073838562 1983 1311867236.5972909927 0.0510822684 0.0578259509 0.0879767612 0.0054948868 0.0062000000 42760525 955859216 1373700096 -0.0724634081 0.0180548225 -0.2057282925 1984 1311867236.6246581078 0.0513170063 0.0578226702 0.0879767612 0.0054935365 0.0061110000 42763229 955859216 1373700096 -0.0729348958 0.0179769546 -0.2038991898 1985 1311867236.6600480080 0.0511426069 0.0578193050 0.0879767612 0.0054922878 0.0060770000 42766213 955859216 1373700096 -0.0725236908 0.0182229057 -0.2016848028 1986 1311867236.6956660748 0.0509244464 0.0578158332 0.0879767612 0.0054917208 0.0062390000 42769197 955859216 1373700096 -0.0723633766 0.0182471666 -0.1995601356 1987 1311867236.7276370525 0.0509310998 0.0578123683 0.0879767612 0.0054905903 0.0125340000 42772013 955859216 1373700096 -0.0718573928 0.0181765351 -0.1973374784 1988 1311867236.7619268894 0.0508778580 0.0578088801 0.0879767612 0.0054901434 0.0075470000 42774941 955859216 1373700096 -0.0715425909 0.0177933704 -0.1952461153 1989 1311867236.7923469543 0.0515865348 0.0578057518 0.0879767612 0.0054911868 0.0064260000 42777757 955859216 1373700096 -0.0720682889 0.0176065266 -0.1931709349 1990 1311867236.8255391121 0.0513089970 0.0578024871 0.0879767612 0.0054904652 0.0061010000 42780741 955859216 1373700096 -0.0724706724 0.0173485223 -0.1913500875 1991 1311867236.8583440781 0.0515985861 0.0577993711 0.0879767612 0.0054900553 0.0104940000 42783557 955859216 1373700096 -0.0725526512 0.0170892626 -0.1892967671 1992 1311867236.8928480148 0.0514515974 0.0577961845 0.0879767612 0.0054899799 0.0073920000 42786485 955859216 1373700096 -0.0723629072 0.0168821923 -0.1873040944 1993 1311867236.9255330563 0.0512980111 0.0577929240 0.0879767612 0.0054887538 0.0107550000 42789357 955859216 1373700096 -0.0720576942 0.0165144224 -0.1853784472 1994 1311867236.9581959248 0.0514950491 0.0577897656 0.0879767612 0.0054876225 0.0073490000 42792229 955859216 1373700096 -0.0723477304 0.0167414155 -0.1830888093 1995 1311867236.9937291145 0.0510490090 0.0577863867 0.0879767612 0.0054896284 0.0062960000 42795213 955859216 1373700096 -0.0718752742 0.0172199085 -0.1808201671 1996 1311867237.0244200230 0.0511834249 0.0577830786 0.0879767612 0.0054891212 0.0105830000 42798029 955859216 1373700096 -0.0724849924 0.0165862925 -0.1787901074 1997 1311867237.0603060722 0.0503934808 0.0577793783 0.0879767612 0.0054924878 0.0073330000 42801013 955859216 1373700096 -0.0728919581 0.0169697218 -0.1767811328 1998 1311867237.0927588940 0.0509598330 0.0577759651 0.0879767612 0.0055056632 0.0070490000 42803941 955859216 1373700096 -0.0718605965 0.0178140346 -0.1745836139 1999 1311867237.1276650429 0.0510355085 0.0577725932 0.0879767612 0.0055057796 0.0063960000 42806869 955859216 1373700096 -0.0715862513 0.0167963691 -0.1728427261 2000 1311867237.1566579342 0.0509872884 0.0577692005 0.0879767612 0.0055051793 0.0062810000 42809629 955859216 1373700096 -0.0726274103 0.0166309811 -0.1711579412 2001 1311867237.1925950050 0.0508737713 0.0577657545 0.0879767612 0.0055042722 0.0061840000 42812613 955859216 1373700096 -0.0718398988 0.0170453358 -0.1692813188 2002 1311867237.2254281044 0.0519106686 0.0577628299 0.0879767612 0.0055031992 0.0115910000 42815541 955859216 1373700096 -0.0734440312 0.0156623106 -0.1677937508 2003 1311867237.2569580078 0.0513814241 0.0577596440 0.0879767612 0.0055031300 0.0076780000 42818413 955859216 1373700096 -0.0737358108 0.0152578494 -0.1663759798 2004 1311867237.2944281101 0.0510229431 0.0577562824 0.0879767612 0.0055017979 0.0097910000 42821397 955859216 1373700096 -0.0741083547 0.0160999708 -0.1648511887 2005 1311867237.3250501156 0.0512848198 0.0577530547 0.0879767612 0.0055005689 0.0071180000 42824269 955859216 1373700096 -0.0749066323 0.0158850309 -0.1632806808 2006 1311867237.3565309048 0.0519043505 0.0577501391 0.0879767612 0.0055008869 0.0062520000 42827141 955859216 1373700096 -0.0753429234 0.0154381543 -0.1616576016 2007 1311867237.3934979439 0.0509389490 0.0577467454 0.0879767612 0.0055005013 0.0097670000 42830069 955859216 1373700096 -0.0747391954 0.0160805080 -0.1598195583 2008 1311867237.4248709679 0.0511317402 0.0577434511 0.0879767612 0.0054992923 0.0070640000 42832997 955859216 1373700096 -0.0751694366 0.0152745852 -0.1581241041 2009 1311867237.4579510689 0.0512300394 0.0577402089 0.0879767612 0.0054979731 0.0064100000 42835869 955859216 1373700096 -0.0755167976 0.0147381797 -0.1563809365 2010 1311867237.4933559895 0.0509734787 0.0577368424 0.0879767612 0.0054974544 0.0062510000 42838853 955859216 1373700096 -0.0759724081 0.0151900938 -0.1545147002 2011 1311867237.5253219604 0.0508961715 0.0577334408 0.0879767612 0.0054984964 0.0062850000 42841725 955859216 1373700096 -0.0757938623 0.0139557384 -0.1525281668 2012 1311867237.5581231117 0.0513890721 0.0577302875 0.0879767612 0.0054974181 0.0097770000 42844653 955859216 1373700096 -0.0758614689 0.0131984847 -0.1506106853 2013 1311867237.5925350189 0.0514663495 0.0577271758 0.0879767612 0.0054987988 0.0070290000 42847525 955859216 1373700096 -0.0764734074 0.0138559965 -0.1484792382 2014 1311867237.6261129379 0.0514685400 0.0577240682 0.0879767612 0.0054977170 0.0062310000 42850509 955859216 1373700096 -0.0766679272 0.0131327091 -0.1465915889 2015 1311867237.6569290161 0.0515340716 0.0577209962 0.0879767612 0.0054967905 0.0110230000 42853325 955859216 1373700096 -0.0769083276 0.0124899773 -0.1445990354 2016 1311867237.6925010681 0.0513346456 0.0577178284 0.0879767612 0.0054954543 0.0074630000 42856253 955859216 1373700096 -0.0768385604 0.0124557801 -0.1426222175 2017 1311867237.7243609428 0.0518133864 0.0577149011 0.0879767612 0.0054941095 0.0064650000 42859125 955859216 1373700096 -0.0770620778 0.0121909929 -0.1404544264 2018 1311867237.7617940903 0.0518950596 0.0577120171 0.0879767612 0.0054928305 0.0063530000 42862221 955859216 1373700096 -0.0777187943 0.0112648085 -0.1382527947 2019 1311867237.7926809788 0.0516771078 0.0577090281 0.0879767612 0.0054917416 0.0110000000 42864981 955859216 1373700096 -0.0778541341 0.0116221188 -0.1358587742 2020 1311867237.8255820274 0.0516168587 0.0577060121 0.0879767612 0.0054907631 0.0073800000 42867909 955859216 1373700096 -0.0776337385 0.0118068019 -0.1335704178 2021 1311867237.8612699509 0.0515232161 0.0577029529 0.0879767612 0.0054898388 0.0108210000 42870949 955859216 1373700096 -0.0773701072 0.0115471194 -0.1313293427 2022 1311867237.8926060200 0.0511977561 0.0576997356 0.0879767612 0.0054891551 0.0073270000 42873765 955859216 1373700096 -0.0770608336 0.0121815139 -0.1288264841 2023 1311867237.9253590107 0.0516851321 0.0576967625 0.0879767612 0.0054885532 0.0107900000 42876581 955859216 1373700096 -0.0770074800 0.0119632427 -0.1265607178 2024 1311867237.9613509178 0.0518027954 0.0576938505 0.0879767612 0.0054878953 0.0100510000 42879565 955859216 1373700096 -0.0774009526 0.0111304736 -0.1243561730 2025 1311867237.9928910732 0.0520637520 0.0576910702 0.0879767612 0.0054867787 0.0071510000 42882437 955859216 1373700096 -0.0768719539 0.0110638589 -0.1221888438 2026 1311867238.0245919228 0.0521487333 0.0576883346 0.0879767612 0.0054859931 0.0062920000 42885253 955859216 1373700096 -0.0763346627 0.0117590800 -0.1198465973 2027 1311867238.0607950687 0.0523168594 0.0576856846 0.0879767612 0.0054852262 0.0069330000 42888237 955859216 1373700096 -0.0764881074 0.0110423472 -0.1177804172 2028 1311867238.0932629108 0.0521135628 0.0576829370 0.0879767612 0.0054842870 0.0107810000 42891109 955859216 1373700096 -0.0763479546 0.0094250478 -0.1158898324 2029 1311867238.1251931190 0.0524827912 0.0576803741 0.0879767612 0.0054840206 0.0099960000 42893981 955859216 1373700096 -0.0761838183 0.0102311820 -0.1135567650 2030 1311867238.1608469486 0.0524478815 0.0576777965 0.0879767612 0.0054902588 0.0072350000 42896965 955859216 1373700096 -0.0755202994 0.0108106807 -0.1110839397 2031 1311867238.1928510666 0.0522908419 0.0576751442 0.0879767612 0.0054959099 0.0063550000 42899837 955859216 1373700096 -0.0758123621 0.0098363012 -0.1088907346 2032 1311867238.2246770859 0.0521554016 0.0576724278 0.0879767612 0.0054948634 0.0062860000 42902709 955859216 1373700096 -0.0748255551 0.0104653928 -0.1065978184 2033 1311867238.2605938911 0.0520672090 0.0576696707 0.0879767612 0.0054946305 0.0109090000 42905693 955859216 1373700096 -0.0735248253 0.0104689077 -0.1041976064 2034 1311867238.2926790714 0.0521421209 0.0576669531 0.0879767612 0.0054982701 0.0100470000 42908509 955859216 1373700096 -0.0735964701 0.0087837474 -0.1019993648 2035 1311867238.3257811069 0.0519783795 0.0576641577 0.0879767612 0.0055072001 0.0071710000 42911493 955859216 1373700096 -0.0731485710 0.0089018531 -0.0996159539 2036 1311867238.3604390621 0.0522584803 0.0576615027 0.0879767612 0.0055070410 0.0064120000 42914421 955859216 1373700096 -0.0725692809 0.0085957525 -0.0972785726 2037 1311867238.3936378956 0.0520180166 0.0576587322 0.0879767612 0.0055084223 0.0062930000 42917349 955859216 1373700096 -0.0721553490 0.0073761558 -0.0950139761 2038 1311867238.4264049530 0.0520129018 0.0576559619 0.0879767612 0.0055117535 0.0062820000 42920221 955859216 1373700096 -0.0716984197 0.0064086015 -0.0927718952 2039 1311867238.4616210461 0.0518026724 0.0576530912 0.0879767612 0.0055106139 0.0062660000 42923205 955859216 1373700096 -0.0716477260 0.0065207379 -0.0903787836 2040 1311867238.4932549000 0.0518061444 0.0576502251 0.0879767612 0.0055150585 0.0062520000 42925965 955859216 1373700096 -0.0716081113 0.0053947768 -0.0882223397 2041 1311867238.5248661041 0.0520950407 0.0576475033 0.0879767612 0.0055147320 0.0062570000 42928893 955859216 1373700096 -0.0711115152 0.0043476406 -0.0859851018 2042 1311867238.5605928898 0.0515534617 0.0576445189 0.0879767612 0.0055202810 0.0063070000 42931877 955859216 1373700096 -0.0699142069 0.0042568035 -0.0833492354 2043 1311867238.5929119587 0.0518089719 0.0576416626 0.0879767612 0.0055253458 0.0100870000 42934693 955859216 1373700096 -0.0702663064 0.0029942477 -0.0808930248 2044 1311867238.6249868870 0.0518262424 0.0576388174 0.0879767612 0.0055241484 0.0071350000 42937621 955859216 1373700096 -0.0696440861 0.0019174926 -0.0782880783 2045 1311867238.6608479023 0.0517921261 0.0576359584 0.0879767612 0.0055229553 0.0062880000 42940605 955859216 1373700096 -0.0686812177 0.0018559947 -0.0753382966 2046 1311867238.6929359436 0.0512871221 0.0576328554 0.0879767612 0.0055221927 0.0062220000 42943477 955859216 1373700096 -0.0677010715 0.0013139767 -0.0724663362 2047 1311867238.7246360779 0.0519746915 0.0576300913 0.0879767612 0.0055229501 0.0063250000 42946293 955859216 1373700096 -0.0680910870 0.0007676414 -0.0695714727 2048 1311867238.7627971172 0.0508908294 0.0576268006 0.0879767612 0.0055216341 0.0098050000 42949333 955859216 1373700096 -0.0676582232 0.0006499818 -0.0665243715 2049 1311867238.7949919701 0.0511941724 0.0576236612 0.0879767612 0.0055203850 0.0073060000 43148869 955859216 1373700096 -0.0659842640 0.0008868617 -0.0634148419 2050 1311867238.8246819973 0.0515123121 0.0576206801 0.0879767612 0.0055232005 0.0063760000 43561229 955859216 1373700096 -0.0656374916 0.0001541068 -0.0602826923 2051 1311867238.8630580902 0.0508067980 0.0576173578 0.0879767612 0.0055221963 0.0110240000 43564325 955859216 1373700096 -0.0657051876 0.0002576160 -0.0570963621 2052 1311867238.8933889866 0.0507572368 0.0576140147 0.0879767612 0.0055210462 0.0074580000 43567141 955859216 1373700096 -0.0646004304 0.0007178963 -0.0538311489 2053 1311867238.9278979301 0.0511580408 0.0576108700 0.0879767612 0.0055198752 0.0064650000 43570125 955859216 1373700096 -0.0641097054 -0.0003527608 -0.0507345386 2054 1311867238.9628050327 0.0508130006 0.0576075605 0.0879767612 0.0055194580 0.0101270000 43573109 955859216 1373700096 -0.0643530563 -0.0019093798 -0.0478571653 2055 1311867238.9937820435 0.0513129681 0.0576044974 0.0879767612 0.0055188738 0.0071930000 43575869 955859216 1373700096 -0.0636391044 -0.0019316702 -0.0444347560 2056 1311867239.0287299156 0.0515447445 0.0576015501 0.0879767612 0.0055206907 0.0063480000 43578853 955859216 1373700096 -0.0633357391 -0.0020920127 -0.0412053280 2057 1311867239.0619978905 0.0507510304 0.0575982197 0.0879767612 0.0055227641 0.0064740000 43581837 955859216 1373700096 -0.0635111183 -0.0034389971 -0.0381990708 2058 1311867239.0939240456 0.0508811139 0.0575949558 0.0879767612 0.0055249373 0.0063560000 43584597 955859216 1373700096 -0.0631119236 -0.0035286800 -0.0348011255 2059 1311867239.1358110905 0.0500784703 0.0575913053 0.0879767612 0.0055238018 0.0063290000 43587749 955859216 1373700096 -0.0624717101 -0.0036137102 -0.0313754492 2060 1311867239.1620550156 0.0504092649 0.0575878188 0.0879767612 0.0055235869 0.0105820000 43590453 955859216 1373700096 -0.0618920289 -0.0041915923 -0.0281344280 2061 1311867239.1936569214 0.0509537049 0.0575845999 0.0879767612 0.0055227172 0.0073090000 43593269 955859216 1373700096 -0.0617099255 -0.0046240618 -0.0245613027 2062 1311867239.2294950485 0.0507564247 0.0575812885 0.0879767612 0.0055218674 0.0063640000 43596253 955859216 1373700096 -0.0618489683 -0.0049898466 -0.0209667031 2063 1311867239.2609150410 0.0512612946 0.0575782250 0.0879767612 0.0055211781 0.0101560000 43599125 955859216 1373700096 -0.0613912120 -0.0064711259 -0.0176266357 2064 1311867239.2928791046 0.0513818674 0.0575752229 0.0879767612 0.0055199511 0.0072190000 43601941 955859216 1373700096 -0.0610109121 -0.0076591326 -0.0141507396 2065 1311867239.3295290470 0.0511070192 0.0575720906 0.0879767612 0.0055188767 0.0063260000 43604981 955859216 1373700096 -0.0604256019 -0.0081815170 -0.0104934704 2066 1311867239.3615000248 0.0516029336 0.0575692014 0.0879767612 0.0055181788 0.0062540000 43607853 955859216 1373700096 -0.0596631654 -0.0094561474 -0.0071350276 2067 1311867239.3928411007 0.0516802743 0.0575663523 0.0879767612 0.0055175071 0.0106750000 43610725 955859216 1373700096 -0.0599848889 -0.0110833477 -0.0039823661 2068 1311867239.4293289185 0.0513503328 0.0575633465 0.0879767612 0.0055206088 0.0072640000 43613653 955859216 1373700096 -0.0591917261 -0.0122027323 -0.0007841642 2069 1311867239.4619059563 0.0514987260 0.0575604154 0.0879767612 0.0055224450 0.0064100000 43616637 955859216 1373700096 -0.0590519458 -0.0135168992 0.0023054734 2070 1311867239.4938249588 0.0518049337 0.0575576349 0.0879767612 0.0055217393 0.0101750000 43619453 955859216 1373700096 -0.0587659515 -0.0154316332 0.0051787258 2071 1311867239.5295019150 0.0516411252 0.0575547781 0.0879767612 0.0055238614 0.0072530000 43622437 955859216 1373700096 -0.0578774884 -0.0168793369 0.0080121504 2072 1311867239.5617070198 0.0514424220 0.0575518281 0.0879767612 0.0055292670 0.0063790000 43625309 955859216 1373700096 -0.0575467162 -0.0171913803 0.0110840891 2073 1311867239.5944910049 0.0520359576 0.0575491673 0.0879767612 0.0055280855 0.0062960000 43628181 955859216 1373700096 -0.0565879308 -0.0188043267 0.0140854353 2074 1311867239.6284430027 0.0520078316 0.0575464955 0.0879767612 0.0055355706 0.0063070000 43631109 955859216 1373700096 -0.0561138727 -0.0206720605 0.0167702734 2075 1311867239.6623089314 0.0517802797 0.0575437166 0.0879767612 0.0055346247 0.0096840000 43634093 955859216 1373700096 -0.0552853458 -0.0208402853 0.0197766200 2076 1311867239.6931240559 0.0520472899 0.0575410690 0.0879767612 0.0055473833 0.0109010000 43636853 955859216 1373700096 -0.0544273816 -0.0206477977 0.0228010863 2077 1311867239.7284948826 0.0520238914 0.0575384127 0.0879767612 0.0055477410 0.0074470000 43639837 955859216 1373700096 -0.0538081042 -0.0213227998 0.0256524812 2078 1311867239.7614610195 0.0521012470 0.0575357961 0.0879767612 0.0055471288 0.0064370000 43642821 955859216 1373700096 -0.0528208911 -0.0219131615 0.0284341462 2079 1311867239.7926149368 0.0516374260 0.0575329590 0.0879767612 0.0055458901 0.0063380000 43645581 955859216 1373700096 -0.0516424365 -0.0210819971 0.0314567573 2080 1311867239.8308320045 0.0515678301 0.0575300912 0.0879767612 0.0055464004 0.0063180000 43648677 955859216 1373700096 -0.0505154170 -0.0212673508 0.0343848392 2081 1311867239.8608438969 0.0516028292 0.0575272429 0.0879767612 0.0055533218 0.0108510000 43651493 955859216 1373700096 -0.0503622852 -0.0219859853 0.0374392010 2082 1311867239.8929069042 0.0518219918 0.0575245026 0.0879767612 0.0055542326 0.0074790000 43654365 955859216 1373700096 -0.0493775085 -0.0221025273 0.0405772738 2083 1311867239.9306600094 0.0513665341 0.0575215463 0.0879767612 0.0055553698 0.0108680000 43657405 955859216 1373700096 -0.0486478247 -0.0226620138 0.0433867387 2084 1311867239.9613699913 0.0518425740 0.0575188213 0.0879767612 0.0055569341 0.0077390000 43660277 955859216 1373700096 -0.0490659736 -0.0230560824 0.0462457202 2085 1311867239.9948220253 0.0519715957 0.0575161607 0.0879767612 0.0055557386 0.0110330000 43663149 955859216 1373700096 -0.0483432896 -0.0233891159 0.0491151735 2086 1311867240.0292289257 0.0517538153 0.0575133983 0.0879767612 0.0055559281 0.0079640000 43666077 955859216 1373700096 -0.0478510894 -0.0243091695 0.0518684089 2087 1311867240.0618810654 0.0522410795 0.0575108721 0.0879767612 0.0055548557 0.0065860000 43669005 955859216 1373700096 -0.0470919237 -0.0243386813 0.0546488985 2088 1311867240.0945510864 0.0517888702 0.0575081317 0.0879767612 0.0055537466 0.0063090000 43671821 955859216 1373700096 -0.0466994569 -0.0245180726 0.0573691428 2089 1311867240.1297509670 0.0521629117 0.0575055729 0.0879767612 0.0055525888 0.0063640000 43674805 955859216 1373700096 -0.0462348424 -0.0248417910 0.0604804866 2090 1311867240.1617240906 0.0522647463 0.0575030653 0.0879767612 0.0055518973 0.0063330000 43677677 955859216 1373700096 -0.0458209328 -0.0245014280 0.0635842234 2091 1311867240.1963129044 0.0519839637 0.0575004259 0.0879767612 0.0055508813 0.0065340000 43680661 955859216 1373700096 -0.0455418006 -0.0247983988 0.0662454888 2092 1311867240.2291030884 0.0524320602 0.0574980031 0.0879767612 0.0055496468 0.0065370000 43683533 955859216 1373700096 -0.0448626541 -0.0250302777 0.0690232217 2093 1311867240.2612760067 0.0523218475 0.0574955301 0.0879767612 0.0055491084 0.0064260000 43686461 955859216 1373700096 -0.0433650799 -0.0248539299 0.0718273073 2094 1311867240.2981250286 0.0523360148 0.0574930661 0.0879767612 0.0055479073 0.0065380000 43689277 955859216 1373700096 -0.0434692167 -0.0252137557 0.0745235831 2095 1311867240.3289160728 0.0523732416 0.0574906223 0.0879767612 0.0055476108 0.0064540000 43692149 955859216 1373700096 -0.0428108796 -0.0260875784 0.0770805255 2096 1311867240.3609399796 0.0525136739 0.0574882478 0.0879767612 0.0055466852 0.0063920000 43695077 955859216 1373700096 -0.0422732346 -0.0269696079 0.0796792880 2097 1311867240.3967890739 0.0525622442 0.0574858987 0.0879767612 0.0055459672 0.0121630000 43697949 955859216 1373700096 -0.0414002426 -0.0275478382 0.0821559653 2098 1311867240.4286890030 0.0525337122 0.0574835383 0.0879767612 0.0055449551 0.0077690000 43700709 955859216 1373700096 -0.0407590903 -0.0289360918 0.0843664259 2099 1311867240.4650850296 0.0520173088 0.0574809341 0.0879767612 0.0055487356 0.0065680000 43703749 955859216 1373700096 -0.0401733965 -0.0300816558 0.0865805522 2100 1311867240.4972898960 0.0523446389 0.0574784882 0.0879767612 0.0055518104 0.0063100000 43706621 955859216 1373700096 -0.0402645729 -0.0309479088 0.0886256769 2101 1311867240.5309979916 0.0524854809 0.0574761117 0.0879767612 0.0055534846 0.0063760000 43709549 955859216 1373700096 -0.0399205796 -0.0322158635 0.0904578343 2102 1311867240.5608210564 0.0521820821 0.0574735932 0.0879767612 0.0055522626 0.0063240000 43712365 955859216 1373700096 -0.0393844545 -0.0327600725 0.0922789648 2103 1311867240.5965991020 0.0525498390 0.0574712519 0.0879767612 0.0055512385 0.0063580000 43715349 955859216 1373700096 -0.0389229245 -0.0336917415 0.0939574763 2104 1311867240.6290791035 0.0529604815 0.0574691080 0.0879767612 0.0055516459 0.0105120000 43718221 955859216 1373700096 -0.0386784375 -0.0351460837 0.0954375416 2105 1311867240.6622560024 0.0528697483 0.0574669230 0.0879767612 0.0055544892 0.0073430000 43721093 955859216 1373700096 -0.0386401303 -0.0360717885 0.0968041942 2106 1311867240.6968801022 0.0528197624 0.0574647164 0.0879767612 0.0055536291 0.0063720000 43724021 955859216 1373700096 -0.0384261794 -0.0367302708 0.0980833471 2107 1311867240.7291979790 0.0527374446 0.0574624728 0.0879767612 0.0055557191 0.0063460000 43726893 955859216 1373700096 -0.0383575596 -0.0364696980 0.0993018299 2108 1311867240.7625629902 0.0531157665 0.0574604107 0.0879767612 0.0055553113 0.0108430000 43729765 955859216 1373700096 -0.0381610766 -0.0363363735 0.1007861346 2109 1311867240.7965719700 0.0530990958 0.0574583428 0.0879767612 0.0055542082 0.0076640000 43732749 955859216 1373700096 -0.0384706222 -0.0363599323 0.1021964848 2110 1311867240.8293309212 0.0527994186 0.0574561348 0.0879767612 0.0055529107 0.0110240000 43735621 955859216 1373700096 -0.0384792723 -0.0357001573 0.1038714424 2111 1311867240.8621098995 0.0529952161 0.0574540216 0.0879767612 0.0055524210 0.0075210000 43738549 955859216 1373700096 -0.0386131071 -0.0353183448 0.1057033762 2112 1311867240.8973500729 0.0530160069 0.0574519203 0.0879767612 0.0055515236 0.0108920000 43741533 955859216 1373700096 -0.0393420905 -0.0348446183 0.1077547446 2113 1311867240.9290270805 0.0531540476 0.0574498862 0.0879767612 0.0055505272 0.0075300000 43744349 955859216 1373700096 -0.0394107625 -0.0339499749 0.1099916399 2114 1311867240.9614369869 0.0533971339 0.0574479691 0.0879767612 0.0055492358 0.0202700000 43747221 955859216 1373700096 -0.0397033803 -0.0331330672 0.1121967435 2115 1311867240.9968450069 0.0536734946 0.0574461845 0.0879767612 0.0055482555 0.0123220000 43750261 955859216 1373700096 -0.0401311032 -0.0329039656 0.1145622879 2116 1311867241.0315620899 0.0532350726 0.0574441944 0.0879767612 0.0055508802 0.0080050000 43753189 955859216 1373700096 -0.0407294966 -0.0320507772 0.1171287373 2117 1311867241.0633668900 0.0538163483 0.0574424807 0.0879767612 0.0055577729 0.0066770000 43755949 955859216 1373700096 -0.0415164307 -0.0306138415 0.1199359596 2118 1311867241.0990099907 0.0534623377 0.0574406015 0.0879767612 0.0055592298 0.0109240000 43758989 955859216 1373700096 -0.0420302600 -0.0306571592 0.1222595647 2119 1311867241.1285290718 0.0542245172 0.0574390838 0.0879767612 0.0055601296 0.0180570000 43761749 955859216 1373700096 -0.0433829501 -0.0311014373 0.1245758161 2120 1311867241.1641499996 0.0541169271 0.0574375167 0.0879767612 0.0055625801 0.0085710000 43764789 955859216 1373700096 -0.0436465554 -0.0306335464 0.1269932687 2121 1311867241.1980121136 0.0544063672 0.0574360876 0.0879767612 0.0055623707 0.0068880000 43767661 955859216 1373700096 -0.0440431722 -0.0307865143 0.1293748170 2122 1311867241.2313330173 0.0549082607 0.0574348964 0.0879767612 0.0055628276 0.0065540000 43770645 955859216 1373700096 -0.0454539396 -0.0302165803 0.1319126636 2123 1311867241.2640700340 0.0550364591 0.0574337666 0.0879767612 0.0055615402 0.0064620000 43773461 955859216 1373700096 -0.0466930531 -0.0296754465 0.1340325475 2124 1311867241.3000609875 0.0545128547 0.0574323914 0.0879767612 0.0055654766 0.0111980000 43776501 955859216 1373700096 -0.0478050150 -0.0299921241 0.1357105523 2125 1311867241.3294849396 0.0546573922 0.0574310856 0.0879767612 0.0055664880 0.0074970000 43779261 955859216 1373700096 -0.0489678495 -0.0296057202 0.1375320554 2126 1311867241.3612549305 0.0548520610 0.0574298725 0.0879767612 0.0055658444 0.0065090000 43782189 955859216 1373700096 -0.0498997606 -0.0296216458 0.1393570304 2127 1311867241.3981139660 0.0550271310 0.0574287428 0.0879767612 0.0055678484 0.0064590000 43785117 955859216 1373700096 -0.0518785790 -0.0303706639 0.1410791576 2128 1311867241.4300589561 0.0552593246 0.0574277234 0.0879767612 0.0055800815 0.0064190000 43788045 955859216 1373700096 -0.0524934940 -0.0302696805 0.1428303868 2129 1311867241.4652009010 0.0553008877 0.0574267244 0.0879767612 0.0055818801 0.0109790000 43790973 955859216 1373700096 -0.0536114573 -0.0297818389 0.1447287202 2130 1311867241.4969789982 0.0547906198 0.0574254868 0.0879767612 0.0055862122 0.0075000000 43793789 955859216 1373700096 -0.0545103773 -0.0300201792 0.1465517133 2131 1311867241.5331718922 0.0554956831 0.0574245812 0.0879767612 0.0055874272 0.0066180000 43796829 955859216 1373700096 -0.0556061603 -0.0301467590 0.1481767595 2132 1311867241.5656960011 0.0549434386 0.0574234174 0.0879767612 0.0055876494 0.0064560000 43799701 955859216 1373700096 -0.0562323034 -0.0300362781 0.1496579945 2133 1311867241.6002480984 0.0553721040 0.0574224557 0.0879767612 0.0055879375 0.0064440000 43802629 955859216 1373700096 -0.0570611954 -0.0308817029 0.1507860720 2134 1311867241.6291201115 0.0559511259 0.0574217663 0.0879767612 0.0055868507 0.0108690000 43805445 955859216 1373700096 -0.0573358908 -0.0309271049 0.1518881172 2135 1311867241.6646790504 0.0552378558 0.0574207433 0.0879767612 0.0055923319 0.0074360000 43808373 955859216 1373700096 -0.0575257577 -0.0301165935 0.1529572755 2136 1311867241.6999258995 0.0551933870 0.0574197006 0.0879767612 0.0055926442 0.0107100000 43811357 955859216 1373700096 -0.0579846166 -0.0301372409 0.1537934244 2137 1311867241.7297649384 0.0561599322 0.0574191111 0.0879767612 0.0056047219 0.0075270000 43814117 955859216 1373700096 -0.0584074557 -0.0298894458 0.1545757502 2138 1311867241.7676639557 0.0557475463 0.0574183292 0.0879767612 0.0056036162 0.0065330000 43817213 955859216 1373700096 -0.0589461289 -0.0295644347 0.1554632783 2139 1311867241.7974851131 0.0560059845 0.0574176690 0.0879767612 0.0056029341 0.0064710000 43819973 955859216 1373700096 -0.0592698306 -0.0298591908 0.1562825292 2140 1311867241.8296549320 0.0556323566 0.0574168347 0.0879767612 0.0056030993 0.0064290000 43822845 955859216 1373700096 -0.0602659583 -0.0300376918 0.1571874470 2141 1311867241.8668920994 0.0556699038 0.0574160188 0.0879767612 0.0056023562 0.0064430000 43825885 955859216 1373700096 -0.0606575683 -0.0298258383 0.1583948731 2142 1311867241.8979690075 0.0559709743 0.0574153441 0.0879767612 0.0056014650 0.0109450000 43828701 955859216 1373700096 -0.0616026409 -0.0297898110 0.1599187255 2143 1311867241.9292619228 0.0555576719 0.0574144773 0.0879767612 0.0056006294 0.0076440000 43831573 955859216 1373700096 -0.0621557981 -0.0291894414 0.1617658585 2144 1311867241.9654040337 0.0550402328 0.0574133699 0.0879767612 0.0055995033 0.0110080000 43834557 955859216 1373700096 -0.0623950474 -0.0283873528 0.1638819426 2145 1311867241.9974029064 0.0556861125 0.0574125646 0.0879767612 0.0055995078 0.0102810000 43837429 955859216 1373700096 -0.0632175207 -0.0285819471 0.1658364087 2146 1311867242.0296339989 0.0559993163 0.0574119061 0.0879767612 0.0055998158 0.0073680000 43840301 955859216 1373700096 -0.0634820387 -0.0285164565 0.1677998900 2147 1311867242.0670061111 0.0558255948 0.0574111672 0.0879767612 0.0055988216 0.0105540000 43843341 955859216 1373700096 -0.0637627393 -0.0273247249 0.1697569191 2148 1311867242.0972509384 0.0561892316 0.0574105984 0.0879767612 0.0055990480 0.0075410000 43846157 955859216 1373700096 -0.0644205138 -0.0275537390 0.1713168323 2149 1311867242.1308040619 0.0570203476 0.0574104168 0.0879767612 0.0056007248 0.0066040000 43849029 955859216 1373700096 -0.0648514181 -0.0271726586 0.1728252769 2150 1311867242.1670179367 0.0569914468 0.0574102219 0.0879767612 0.0056010843 0.0064580000 43851957 955859216 1373700096 -0.0652258247 -0.0269655678 0.1742039174 2151 1311867242.1982409954 0.0570607446 0.0574100594 0.0879767612 0.0056013744 0.0064850000 43854773 955859216 1373700096 -0.0659052879 -0.0273160581 0.1754931808 2152 1311867242.2334370613 0.0567226596 0.0574097400 0.0879767612 0.0056026276 0.0064670000 43857757 955859216 1373700096 -0.0666908622 -0.0266872533 0.1771190017 2153 1311867242.2696599960 0.0567681044 0.0574094420 0.0879767612 0.0056014542 0.0102580000 43860741 955859216 1373700096 -0.0669011921 -0.0265327934 0.1788355559 2154 1311867242.2982430458 0.0570948683 0.0574092959 0.0879767612 0.0056002080 0.0074760000 43863501 955859216 1373700096 -0.0673501790 -0.0268275645 0.1805651784 2155 1311867242.3293490410 0.0571229793 0.0574091631 0.0879767612 0.0055996643 0.0066250000 43866373 955859216 1373700096 -0.0675261021 -0.0265345294 0.1824602783 2156 1311867242.3659460545 0.0572348237 0.0574090822 0.0879767612 0.0056008263 0.0065500000 43869357 955859216 1373700096 -0.0679704472 -0.0268239863 0.1841904521 2157 1311867242.3974800110 0.0576897077 0.0574092123 0.0879767612 0.0056003975 0.0065620000 43872229 955859216 1373700096 -0.0683746114 -0.0269748811 0.1858873814 2158 1311867242.4322769642 0.0577361695 0.0574093638 0.0879767612 0.0055992322 0.0066940000 43875213 955859216 1373700096 -0.0685737878 -0.0269869585 0.1875568628 2159 1311867242.4648990631 0.0580289662 0.0574096508 0.0879767612 0.0055993290 0.0065860000 43878029 955859216 1373700096 -0.0684198961 -0.0275904629 0.1888322234 2160 1311867242.4975609779 0.0578406826 0.0574098504 0.0879767612 0.0055981185 0.0065670000 43880901 955859216 1373700096 -0.0694671720 -0.0279957615 0.1901790202 2161 1311867242.5292570591 0.0575885363 0.0574099330 0.0879767612 0.0055969267 0.0065990000 43883773 955859216 1373700096 -0.0699575320 -0.0282454416 0.1915836781 2162 1311867242.5650939941 0.0571672246 0.0574098208 0.0879767612 0.0055957438 0.0065710000 43886813 955859216 1373700096 -0.0705918372 -0.0289545618 0.1929338425 2163 1311867242.5985031128 0.0570759922 0.0574096665 0.0879767612 0.0055945504 0.0072980000 43889741 955859216 1373700096 -0.0709868744 -0.0294061359 0.1943401098 2164 1311867242.6305589676 0.0574372523 0.0574096792 0.0879767612 0.0055933321 0.0066080000 43892557 955859216 1373700096 -0.0708648711 -0.0296536926 0.1959326863 2165 1311867242.6692740917 0.0562244542 0.0574091318 0.0879767612 0.0055928774 0.0106360000 43895653 955859216 1373700096 -0.0714324489 -0.0298998114 0.1975020468 2166 1311867242.6981039047 0.0560834557 0.0574085197 0.0879767612 0.0055917288 0.0074020000 43898413 955859216 1373700096 -0.0720017627 -0.0296103172 0.1993843764 2167 1311867242.7372829914 0.0559302345 0.0574078375 0.0879767612 0.0055924643 0.0066010000 43901453 955859216 1373700096 -0.0722561106 -0.0292244647 0.2014909834 2168 1311867242.7656900883 0.0561699681 0.0574072666 0.0879767612 0.0055919038 0.0065200000 43904269 955859216 1373700096 -0.0722029582 -0.0300019607 0.2033398598 2169 1311867242.7994089127 0.0558108650 0.0574065306 0.0879767612 0.0055936594 0.0107250000 43907141 955859216 1373700096 -0.0730080232 -0.0298321508 0.2052498758 2170 1311867242.8355538845 0.0554561839 0.0574056318 0.0879767612 0.0055944686 0.0075030000 43910181 955859216 1373700096 -0.0733421370 -0.0294551216 0.2071827203 2171 1311867242.8666720390 0.0560781583 0.0574050203 0.0879767612 0.0055942180 0.0066340000 43913053 955859216 1373700096 -0.0730181783 -0.0299289394 0.2091034800 2172 1311867242.8980929852 0.0571971536 0.0574049246 0.0879767612 0.0056170049 0.0064820000 43915869 955859216 1373700096 -0.0736099407 -0.0296931211 0.2110461146 2173 1311867242.9335498810 0.0559944436 0.0574042755 0.0879767612 0.0056441680 0.0105800000 43918853 955859216 1373700096 -0.0738605782 -0.0295445789 0.2130287886 2174 1311867242.9649999142 0.0564317144 0.0574038282 0.0879767612 0.0056467188 0.0074750000 43921725 955859216 1373700096 -0.0742731169 -0.0297595002 0.2148754150 2175 1311867242.9970819950 0.0567184538 0.0574035130 0.0879767612 0.0056456406 0.0066000000 43924541 955859216 1373700096 -0.0741995499 -0.0300235562 0.2167850584 2176 1311867243.0332529545 0.0578705743 0.0574037277 0.0879767612 0.0056444867 0.0065380000 43927525 955859216 1373700096 -0.0745170936 -0.0301410984 0.2187057585 2177 1311867243.0648689270 0.0566688627 0.0574033901 0.0879767612 0.0056434069 0.0105080000 43930397 955859216 1373700096 -0.0750821307 -0.0303301252 0.2204668969 2178 1311867243.0972158909 0.0568509735 0.0574031365 0.0879767612 0.0056423419 0.0074450000 43933269 955859216 1373700096 -0.0755050331 -0.0305529740 0.2224165499 2179 1311867243.1357100010 0.0559624322 0.0574024753 0.0879767612 0.0056487300 0.0066500000 43936309 955859216 1373700096 -0.0762619674 -0.0310751181 0.2243076563 2180 1311867243.1655960083 0.0570122637 0.0574022963 0.0879767612 0.0056558692 0.0065460000 43939125 955859216 1373700096 -0.0769877955 -0.0313478447 0.2261667252 2181 1311867243.1977169514 0.0575111769 0.0574023462 0.0879767612 0.0056560547 0.0105210000 43941941 955859216 1373700096 -0.0778790116 -0.0315307565 0.2280808687 2182 1311867243.2358860970 0.0570703223 0.0574021941 0.0879767612 0.0056567827 0.0074300000 43945037 955859216 1373700096 -0.0785787553 -0.0322400890 0.2298638672 2183 1311867243.2649240494 0.0575495549 0.0574022616 0.0879767612 0.0056556850 0.0065410000 43947741 955859216 1373700096 -0.0793263018 -0.0330593847 0.2316994667 2184 1311867243.2970221043 0.0574904270 0.0574023020 0.0879767612 0.0056545844 0.0065180000 43950669 955859216 1373700096 -0.0798091963 -0.0335949920 0.2335034013 2185 1311867243.3327538967 0.0574040711 0.0574023028 0.0879767612 0.0056541732 0.0108060000 43953597 955859216 1373700096 -0.0806659013 -0.0341956131 0.2353204042 2186 1311867243.3681559563 0.0576286688 0.0574024063 0.0879767612 0.0056530467 0.0074870000 43956581 955859216 1373700096 -0.0813129246 -0.0345127657 0.2371786684 2187 1311867243.4021821022 0.0579403080 0.0574026523 0.0879767612 0.0056518087 0.0066050000 43959509 955859216 1373700096 -0.0816041529 -0.0348644443 0.2388832867 2188 1311867243.4344329834 0.0583301075 0.0574030762 0.0879767612 0.0056516880 0.0065310000 43962381 955859216 1373700096 -0.0819573402 -0.0351084620 0.2406734675 2189 1311867243.4665510654 0.0579026490 0.0574033044 0.0879767612 0.0056504560 0.0107110000 43965253 955859216 1373700096 -0.0824000537 -0.0348287039 0.2426619381 2190 1311867243.4982140064 0.0582436509 0.0574036881 0.0879767612 0.0056497850 0.0075100000 43968069 955859216 1373700096 -0.0824955180 -0.0349805802 0.2445164472 2191 1311867243.5339779854 0.0586507469 0.0574042573 0.0879767612 0.0056486643 0.0065360000 43971109 955859216 1373700096 -0.0824372992 -0.0351286232 0.2463716120 2192 1311867243.5669720173 0.0584408380 0.0574047302 0.0879767612 0.0056476198 0.0073110000 43974037 955859216 1373700096 -0.0825573429 -0.0350935049 0.2481092811 2193 1311867243.5978341103 0.0585425794 0.0574052490 0.0879767612 0.0056464191 0.0066950000 43976853 955859216 1373700096 -0.0828430802 -0.0355607718 0.2497060895 2194 1311867243.6333720684 0.0589283332 0.0574059432 0.0879767612 0.0056483326 0.0113170000 43979781 955859216 1373700096 -0.0832509845 -0.0356249362 0.2514306307 2195 1311867243.6661529541 0.0591351986 0.0574067310 0.0879767612 0.0056470778 0.0104570000 43982709 955859216 1373700096 -0.0832165629 -0.0355812572 0.2530945539 2196 1311867243.6981849670 0.0592047907 0.0574075498 0.0879767612 0.0056462288 0.0074570000 43985525 955859216 1373700096 -0.0831822976 -0.0361804515 0.2545271218 2197 1311867243.7344710827 0.0585206859 0.0574080565 0.0879767612 0.0056453788 0.0066210000 43988565 955859216 1373700096 -0.0825898051 -0.0361398607 0.2561650276 2198 1311867243.7666299343 0.0588076822 0.0574086933 0.0879767612 0.0056452673 0.0065120000 43991493 955859216 1373700096 -0.0820118114 -0.0360979289 0.2580297589 2199 1311867243.7979769707 0.0591192469 0.0574094711 0.0879767612 0.0056439933 0.0065820000 43994309 955859216 1373700096 -0.0819768161 -0.0365287252 0.2598581016 2200 1311867243.8330240250 0.0587232560 0.0574100683 0.0879767612 0.0056428694 0.0065670000 43997237 955859216 1373700096 -0.0816528499 -0.0362878181 0.2617438138 2201 1311867243.8647689819 0.0590907186 0.0574108319 0.0879767612 0.0056425549 0.0105220000 44000109 955859216 1373700096 -0.0811108947 -0.0362794586 0.2637020648 2202 1311867243.8968739510 0.0592863075 0.0574116836 0.0879767612 0.0056413491 0.0074650000 44003037 955859216 1373700096 -0.0808322132 -0.0366980247 0.2654054761 2203 1311867243.9329960346 0.0594077073 0.0574125897 0.0879767612 0.0056406637 0.0065440000 44005965 955859216 1373700096 -0.0803369656 -0.0366257206 0.2670614123 2204 1311867243.9660589695 0.0593960918 0.0574134896 0.0879767612 0.0056396132 0.0065120000 44008893 955859216 1373700096 -0.0802944377 -0.0369767807 0.2685208917 2205 1311867244.0016739368 0.0592361130 0.0574143162 0.0879767612 0.0056392206 0.0066330000 44011877 955859216 1373700096 -0.0799954236 -0.0374487303 0.2700927258 2206 1311867244.0341379642 0.0591228381 0.0574150907 0.0879767612 0.0056382864 0.0106050000 44014749 955859216 1373700096 -0.0794503391 -0.0376591906 0.2716562748 2207 1311867244.0655789375 0.0591343194 0.0574158697 0.0879767612 0.0056370713 0.0074810000 44017621 955859216 1373700096 -0.0792756677 -0.0379973464 0.2732403278 2208 1311867244.1010930538 0.0589253455 0.0574165533 0.0879767612 0.0056359086 0.0067150000 44020605 955859216 1373700096 -0.0789626837 -0.0383718386 0.2750113606 2209 1311867244.1353089809 0.0590131953 0.0574172761 0.0879767612 0.0056352983 0.0066570000 44023533 955859216 1373700096 -0.0786237642 -0.0387229919 0.2769064009 2210 1311867244.1648418903 0.0591119193 0.0574180429 0.0879767612 0.0056340930 0.0110990000 44026293 955859216 1373700096 -0.0783621296 -0.0392392129 0.2787222862 2211 1311867244.2024741173 0.0582751259 0.0574184306 0.0879767612 0.0056329009 0.0075910000 44029389 955859216 1373700096 -0.0778799132 -0.0392783694 0.2807580829 2212 1311867244.2330279350 0.0590196438 0.0574191544 0.0879767612 0.0056316848 0.0066650000 44032205 955859216 1373700096 -0.0774138570 -0.0393078215 0.2830141783 2213 1311867244.2649021149 0.0592645630 0.0574199883 0.0879767612 0.0056306537 0.0105010000 44035021 955859216 1373700096 -0.0769634321 -0.0398910977 0.2850699127 2214 1311867244.3010311127 0.0590055063 0.0574207045 0.0879767612 0.0056298347 0.0074860000 44038061 955859216 1373700096 -0.0764619261 -0.0397373699 0.2872415185 2215 1311867244.3355190754 0.0589389950 0.0574213899 0.0879767612 0.0056288133 0.0065500000 44040989 955859216 1373700096 -0.0759316906 -0.0393661708 0.2894555330 2216 1311867244.3649079800 0.0597466566 0.0574224392 0.0879767612 0.0056283567 0.0065340000 44043749 955859216 1373700096 -0.0755292177 -0.0397414118 0.2913977504 2217 1311867244.4008760452 0.0598626249 0.0574235399 0.0879767612 0.0056275698 0.0111840000 44046733 955859216 1373700096 -0.0748836547 -0.0394530930 0.2935892940 2218 1311867244.4329938889 0.0599090718 0.0574246605 0.0879767612 0.0056282112 0.0104160000 44049605 955859216 1373700096 -0.0738156587 -0.0395085067 0.2957414687 2219 1311867244.4654510021 0.0601125509 0.0574258718 0.0879767612 0.0056276705 0.0076290000 44052533 955859216 1373700096 -0.0729912892 -0.0396684222 0.2978450060 2220 1311867244.5052490234 0.0597821884 0.0574269332 0.0879767612 0.0056266597 0.0067300000 44055629 955859216 1373700096 -0.0715293139 -0.0389896929 0.3000320494 2221 1311867244.5330989361 0.0599070303 0.0574280499 0.0879767612 0.0056256049 0.0070310000 44058333 955859216 1373700096 -0.0707917511 -0.0383777656 0.3023383915 2222 1311867244.5669400692 0.0598276034 0.0574291298 0.0879767612 0.0056245284 0.0108620000 44061205 955859216 1373700096 -0.0699915662 -0.0379144140 0.3046101034 2223 1311867244.6027030945 0.0597970262 0.0574301950 0.0879767612 0.0056283486 0.0077300000 44064077 955859216 1373700096 -0.0694707632 -0.0370913930 0.3071306944 2224 1311867244.6328020096 0.0598787479 0.0574312959 0.0879767612 0.0056281829 0.0107590000 44066837 955859216 1373700096 -0.0686862543 -0.0364125445 0.3096161187 2225 1311867244.6672449112 0.0599008463 0.0574324058 0.0879767612 0.0056275938 0.0074020000 44069821 955859216 1373700096 -0.0681055859 -0.0365244187 0.3119345605 2226 1311867244.7012600899 0.0601970516 0.0574336478 0.0879767612 0.0056266917 0.0065540000 44072749 955859216 1373700096 -0.0674341619 -0.0365668610 0.3143929243 2227 1311867244.7346320152 0.0603688024 0.0574349658 0.0879767612 0.0056256994 0.0064880000 44075621 955859216 1373700096 -0.0670229122 -0.0366639234 0.3165774047 2228 1311867244.7650001049 0.0605394021 0.0574363592 0.0879767612 0.0056246223 0.0110480000 44078437 955859216 1373700096 -0.0662487671 -0.0363005996 0.3189422190 2229 1311867244.8015320301 0.0605005138 0.0574377339 0.0879767612 0.0056237054 0.0077810000 44081477 955859216 1373700096 -0.0652851611 -0.0360484533 0.3211706877 2230 1311867244.8331909180 0.0605996326 0.0574391518 0.0879767612 0.0056226921 0.0066890000 44084293 955859216 1373700096 -0.0651559234 -0.0364142209 0.3231485486 2231 1311867244.8651568890 0.0608349964 0.0574406739 0.0879767612 0.0056214340 0.0066240000 44087221 955859216 1373700096 -0.0644171610 -0.0361749530 0.3254030943 2232 1311867244.9013550282 0.0607597753 0.0574421609 0.0879767612 0.0056202047 0.0066110000 44090205 955859216 1373700096 -0.0639412403 -0.0359427519 0.3274906576 2233 1311867244.9328739643 0.0608508326 0.0574436874 0.0879767612 0.0056192285 0.0066030000 44092965 955859216 1373700096 -0.0639273673 -0.0361461528 0.3295190632 2234 1311867244.9652509689 0.0606121346 0.0574451057 0.0879767612 0.0056185998 0.0066430000 44095893 955859216 1373700096 -0.0636727363 -0.0353546180 0.3318299055 2235 1311867245.0022718906 0.0609314367 0.0574466656 0.0879767612 0.0056181194 0.0066080000 44098989 955859216 1373700096 -0.0638190731 -0.0357476063 0.3339421153 2236 1311867245.0349979401 0.0613249987 0.0574484001 0.0879767612 0.0056180444 0.0065700000 44101805 955859216 1373700096 -0.0637984499 -0.0357767493 0.3359862268 2237 1311867245.0664730072 0.0612114109 0.0574500823 0.0879767612 0.0056169564 0.0065670000 44104677 955859216 1373700096 -0.0634526983 -0.0353356414 0.3381448686 2238 1311867245.1041638851 0.0610389225 0.0574516858 0.0879767612 0.0056162225 0.0066520000 44107661 955859216 1373700096 -0.0636445358 -0.0353467800 0.3400067389 2239 1311867245.1338050365 0.0617251806 0.0574535945 0.0879767612 0.0056152773 0.0067570000 44110477 955859216 1373700096 -0.0639032722 -0.0356170274 0.3419257104 2240 1311867245.1749250889 0.0612288341 0.0574552799 0.0879767612 0.0056144148 0.0067500000 44113685 955859216 1373700096 -0.0640884563 -0.0352228619 0.3439670801 2241 1311867245.2108979225 0.0607025512 0.0574567289 0.0879767612 0.0056132402 0.0065590000 44116669 955859216 1373700096 -0.0645980015 -0.0352104306 0.3459130824 2242 1311867245.2429010868 0.0610979646 0.0574583530 0.0879767612 0.0056133540 0.0146920000 44119597 955859216 1373700096 -0.0653137341 -0.0353274569 0.3479976952 2243 1311867245.2755670547 0.0612189285 0.0574600296 0.0879767612 0.0056134448 0.0080320000 44122469 955859216 1373700096 -0.0652539432 -0.0351895913 0.3503235877 2244 1311867245.3120090961 0.0609251261 0.0574615738 0.0879767612 0.0056123179 0.0069190000 44125453 955859216 1373700096 -0.0658135638 -0.0352469683 0.3524695933 2245 1311867245.3430099487 0.0611513145 0.0574632173 0.0879767612 0.0056112138 0.0067370000 44128325 955859216 1373700096 -0.0663393140 -0.0356007107 0.3546365798 2246 1311867245.3749370575 0.0616152696 0.0574650659 0.0879767612 0.0056112135 0.0067040000 44131141 955859216 1373700096 -0.0664923191 -0.0357298590 0.3569931388 2247 1311867245.4122350216 0.0611235574 0.0574666941 0.0879767612 0.0056103314 0.0066510000 44134237 955859216 1373700096 -0.0671444610 -0.0353977568 0.3593290746 2248 1311867245.4428830147 0.0616883002 0.0574685720 0.0879767612 0.0056125700 0.0110080000 44136941 955859216 1373700096 -0.0674248934 -0.0354743972 0.3615685701 2249 1311867245.4751451015 0.0617325082 0.0574704680 0.0879767612 0.0056116654 0.0076070000 44139869 955859216 1373700096 -0.0676694065 -0.0347992070 0.3639402688 2250 1311867245.5108819008 0.0613363795 0.0574721861 0.0879767612 0.0056106576 0.0078000000 44142853 955859216 1373700096 -0.0681390539 -0.0343369395 0.3663908839 2251 1311867245.5429608822 0.0614643395 0.0574739597 0.0879767612 0.0056098513 0.0068330000 44145725 955859216 1373700096 -0.0688197091 -0.0344105586 0.3687146604 2252 1311867245.5749409199 0.0616557002 0.0574758166 0.0879767612 0.0056087364 0.0066490000 44148597 955859216 1373700096 -0.0687467456 -0.0335097052 0.3713177741 2253 1311867245.6109130383 0.0624094009 0.0574780063 0.0879767612 0.0056090668 0.0065630000 44151581 955859216 1373700096 -0.0696102083 -0.0340993591 0.3735498786 2254 1311867245.6428189278 0.0615639053 0.0574798191 0.0879767612 0.0056160309 0.0066400000 44154397 955859216 1373700096 -0.0701815560 -0.0347122923 0.3757470846 2255 1311867245.6751749516 0.0621751286 0.0574819012 0.0879767612 0.0056153251 0.0065740000 44157325 955859216 1373700096 -0.0702478439 -0.0342695750 0.3781104982 2256 1311867245.7109169960 0.0622471161 0.0574840135 0.0879767612 0.0056144026 0.0066650000 44160309 955859216 1373700096 -0.0710512400 -0.0348917507 0.3800729811 2257 1311867245.7429819107 0.0624095723 0.0574861958 0.0879767612 0.0056137209 0.0112460000 44163125 955859216 1373700096 -0.0711735412 -0.0349049307 0.3822202682 2258 1311867245.7752521038 0.0621966422 0.0574882819 0.0879767612 0.0056153345 0.0077330000 44166053 955859216 1373700096 -0.0718068331 -0.0348517895 0.3843534291 2259 1311867245.8110349178 0.0626847893 0.0574905823 0.0879767612 0.0056150581 0.0068370000 44169037 955859216 1373700096 -0.0721902624 -0.0353822820 0.3861922324 2260 1311867245.8428230286 0.0629651099 0.0574930047 0.0879767612 0.0056142913 0.0067190000 44171965 955859216 1373700096 -0.0724293143 -0.0359150432 0.3880624771 2261 1311867245.8757770061 0.0632855892 0.0574955666 0.0879767612 0.0056131582 0.0066470000 44174781 955859216 1373700096 -0.0727368221 -0.0358779579 0.3899342418 2262 1311867245.9110751152 0.0632194579 0.0574980971 0.0879767612 0.0056128166 0.0066530000 44177765 955859216 1373700096 -0.0732289553 -0.0363671519 0.3914544880 2263 1311867245.9428870678 0.0634290501 0.0575007179 0.0879767612 0.0056125761 0.0066740000 44180637 955859216 1373700096 -0.0734535977 -0.0361988544 0.3932002485 2264 1311867245.9751350880 0.0635558516 0.0575033924 0.0879767612 0.0056116995 0.0113360000 44183509 955859216 1373700096 -0.0742718950 -0.0360906683 0.3949560523 2265 1311867246.0112419128 0.0632953271 0.0575059496 0.0879767612 0.0056104810 0.0076740000 44186493 955859216 1373700096 -0.0750722960 -0.0355998948 0.3969464600 2266 1311867246.0429229736 0.0633623227 0.0575085340 0.0879767612 0.0056092493 0.0111300000 44189309 955859216 1373700096 -0.0757063106 -0.0351143852 0.3990913332 2267 1311867246.0752329826 0.0636793077 0.0575112560 0.0879767612 0.0056081856 0.0075920000 44192181 955859216 1373700096 -0.0765445381 -0.0346450657 0.4013250470 2268 1311867246.1109249592 0.0639218092 0.0575140826 0.0879767612 0.0056077810 0.0067170000 44195165 955859216 1373700096 -0.0768797919 -0.0336604156 0.4035783112 2269 1311867246.1430890560 0.0644829050 0.0575171539 0.0879767612 0.0056065881 0.0065890000 44198093 955859216 1373700096 -0.0775939971 -0.0332246237 0.4056177139 2270 1311867246.1749811172 0.0645827875 0.0575202665 0.0879767612 0.0056058303 0.0066620000 44200909 955859216 1373700096 -0.0780961961 -0.0325992703 0.4077993929 2271 1311867246.2109639645 0.0644875541 0.0575233344 0.0879767612 0.0056048845 0.0067080000 44203893 955859216 1373700096 -0.0785403922 -0.0316344313 0.4099723399 2272 1311867246.2429399490 0.0648505464 0.0575265594 0.0879767612 0.0056038764 0.0067100000 44206765 955859216 1373700096 -0.0787434280 -0.0308076143 0.4120402336 2273 1311867246.2750649452 0.0653467104 0.0575299999 0.0879767612 0.0056030236 0.0066490000 44209637 955859216 1373700096 -0.0787907615 -0.0298714694 0.4141761363 2274 1311867246.3108720779 0.0653397366 0.0575334343 0.0879767612 0.0056026786 0.0112730000 44212621 955859216 1373700096 -0.0790261552 -0.0288864076 0.4162250161 2275 1311867246.3429319859 0.0654586703 0.0575369179 0.0879767612 0.0056021542 0.0076740000 44215493 955859216 1373700096 -0.0793117210 -0.0283360481 0.4181631804 2276 1311867246.3752970695 0.0658006817 0.0575405487 0.0879767612 0.0056010635 0.0110550000 44218365 955859216 1373700096 -0.0795750692 -0.0277850833 0.4200983644 2277 1311867246.4109311104 0.0660157278 0.0575442708 0.0879767612 0.0056002022 0.0076230000 44221349 955859216 1373700096 -0.0796686485 -0.0272876117 0.4221052229 2278 1311867246.4430770874 0.0662795156 0.0575481054 0.0879767612 0.0055992162 0.0068050000 44224221 955859216 1373700096 -0.0797002614 -0.0266398024 0.4239839613 2279 1311867246.4751329422 0.0665974170 0.0575520761 0.0879767612 0.0055980728 0.0066590000 44227093 955859216 1373700096 -0.0800284296 -0.0263180118 0.4256830513 2280 1311867246.5109679699 0.0669319853 0.0575561901 0.0879767612 0.0055977930 0.0072230000 44230077 955859216 1373700096 -0.0800015330 -0.0256014075 0.4273882210 2281 1311867246.5431129932 0.0674050450 0.0575605079 0.0879767612 0.0055968969 0.0067250000 44232893 955859216 1373700096 -0.0799298510 -0.0250811968 0.4288971722 2282 1311867246.5752038956 0.0677426830 0.0575649699 0.0879767612 0.0055959458 0.0066490000 44235821 955859216 1373700096 -0.0801148862 -0.0251349807 0.4301367998 2283 1311867246.6111249924 0.0678888932 0.0575694919 0.0879767612 0.0055950308 0.0066850000 44238805 955859216 1373700096 -0.0803395361 -0.0253704712 0.4313403964 2284 1311867246.6431870461 0.0676143616 0.0575738899 0.0879767612 0.0055948765 0.0068090000 44241677 955859216 1373700096 -0.0802925080 -0.0252292268 0.4324210882 2285 1311867246.6751689911 0.0675916970 0.0575782740 0.0879767612 0.0055940052 0.0116740000 44244549 955859216 1373700096 -0.0805869922 -0.0255118012 0.4331820309 2286 1311867246.7110559940 0.0675822273 0.0575826502 0.0879767612 0.0055929311 0.0106330000 44247533 955859216 1373700096 -0.0810916647 -0.0258280672 0.4339953959 2287 1311867246.7433049679 0.0678014532 0.0575871184 0.0879767612 0.0055917207 0.0075610000 44250461 955859216 1373700096 -0.0812096819 -0.0261017364 0.4347759783 2288 1311867246.7749860287 0.0681949407 0.0575917547 0.0879767612 0.0055908378 0.0106630000 44253277 955859216 1373700096 -0.0815825686 -0.0264863204 0.4355434179 2289 1311867246.8111929893 0.0684107020 0.0575964812 0.0879767612 0.0055898487 0.0075040000 44256261 955859216 1373700096 -0.0817519724 -0.0266217310 0.4361602664 2290 1311867246.8430919647 0.0684727132 0.0576012307 0.0879767612 0.0055886437 0.0106830000 44259189 955859216 1373700096 -0.0817531496 -0.0268651675 0.4367060065 2291 1311867246.8750779629 0.0685125589 0.0576059934 0.0879767612 0.0055878156 0.0075300000 44262005 955859216 1373700096 -0.0820898190 -0.0272710882 0.4372066259 2292 1311867246.9111549854 0.0684736222 0.0576107349 0.0879767612 0.0055867334 0.0068080000 44264989 955859216 1373700096 -0.0821625292 -0.0273224916 0.4377449155 2293 1311867246.9430611134 0.0685359538 0.0576154995 0.0879767612 0.0055856427 0.0066950000 44267805 955859216 1373700096 -0.0823096856 -0.0278912429 0.4381493032 2294 1311867246.9751238823 0.0680881143 0.0576200647 0.0879767612 0.0055844692 0.0067650000 44270733 955859216 1373700096 -0.0827971250 -0.0281464215 0.4384754002 2295 1311867247.0109090805 0.0680280477 0.0576245998 0.0879767612 0.0055834653 0.0067050000 44273717 955859216 1373700096 -0.0827346072 -0.0281321835 0.4389895499 2296 1311867247.0440731049 0.0680181161 0.0576291266 0.0879767612 0.0055822532 0.0067140000 44276645 955859216 1373700096 -0.0827767178 -0.0283647701 0.4395014942 2297 1311867247.0751919746 0.0681582168 0.0576337104 0.0879767612 0.0055812394 0.0068830000 44279461 955859216 1373700096 -0.0829318911 -0.0281402413 0.4401133657 2298 1311867247.1112151146 0.0682998449 0.0576383519 0.0879767612 0.0055804166 0.0067150000 44282445 955859216 1373700096 -0.0830367655 -0.0279493500 0.4406677485 2299 1311867247.1430439949 0.0683750287 0.0576430221 0.0879767612 0.0055795224 0.0067340000 44285317 955859216 1373700096 -0.0833856612 -0.0279644020 0.4411959350 2300 1311867247.1751630306 0.0685238689 0.0576477529 0.0879767612 0.0055786269 0.0067740000 44288189 955859216 1373700096 -0.0830899328 -0.0277220290 0.4416609108 2301 1311867247.2113189697 0.0688071102 0.0576526026 0.0879767612 0.0055779951 0.0067000000 44291173 955859216 1373700096 -0.0835231915 -0.0283417962 0.4418732524 2302 1311867247.2437279224 0.0692452490 0.0576576386 0.0879767612 0.0055780038 0.0112590000 44294045 955859216 1373700096 -0.0843121558 -0.0296017714 0.4418651462 2303 1311867247.2777190208 0.0696039647 0.0576628258 0.0879767612 0.0055772189 0.0076540000 44297029 955859216 1373700096 -0.0845458731 -0.0300494805 0.4416586757 2304 1311867247.3109691143 0.0695200413 0.0576679722 0.0879767612 0.0055763244 0.0069170000 44299845 955859216 1373700096 -0.0851119012 -0.0304786488 0.4409678578 2305 1311867247.3432049751 0.0695710704 0.0576731362 0.0879767612 0.0055760779 0.0068630000 44302717 955859216 1373700096 -0.0855989307 -0.0312590189 0.4401472807 2306 1311867247.3753070831 0.0693139136 0.0576781843 0.0879767612 0.0055751664 0.0111200000 44305589 955859216 1373700096 -0.0861867815 -0.0314738154 0.4393317699 2307 1311867247.4116749763 0.0694102272 0.0576832697 0.0879767612 0.0055754756 0.0076720000 44308629 955859216 1373700096 -0.0867107958 -0.0325077176 0.4382337630 2308 1311867247.4440929890 0.0696850792 0.0576884698 0.0879767612 0.0055745104 0.0068390000 44311445 955859216 1373700096 -0.0869554058 -0.0336216576 0.4370888472 2309 1311867247.4751029015 0.0695736855 0.0576936171 0.0879767612 0.0055733725 0.0067690000 44314317 955859216 1373700096 -0.0873375982 -0.0343015306 0.4357939661 2310 1311867247.5110449791 0.0696994960 0.0576988145 0.0879767612 0.0055757750 0.0110230000 44317301 955859216 1373700096 -0.0874260888 -0.0357607231 0.4342801273 2311 1311867247.5430850983 0.0699284226 0.0577041064 0.0879767612 0.0055779776 0.0078480000 44320173 955859216 1373700096 -0.0873082057 -0.0365876704 0.4326615334 2312 1311867247.5751209259 0.0693517923 0.0577091443 0.0879767612 0.0055817949 0.0069270000 44322989 955859216 1373700096 -0.0870993659 -0.0371603854 0.4309719205 2313 1311867247.6114599705 0.0697778463 0.0577143621 0.0879767612 0.0055838418 0.0068820000 44326029 955859216 1373700096 -0.0869550258 -0.0382790789 0.4290249050 2314 1311867247.6431109905 0.0697650686 0.0577195698 0.0879767612 0.0055827334 0.0067700000 44328845 955859216 1373700096 -0.0866279900 -0.0391620584 0.4270439744 2315 1311867247.6750760078 0.0697356686 0.0577247604 0.0879767612 0.0055848520 0.0068170000 44331717 955859216 1373700096 -0.0858314857 -0.0405489653 0.4247612953 2316 1311867247.7112369537 0.0706068426 0.0577303226 0.0879767612 0.0055839749 0.0067920000 44334757 955859216 1373700096 -0.0854222476 -0.0425821841 0.4219779968 2317 1311867247.7431221008 0.0705983043 0.0577358763 0.0879767612 0.0055831143 0.0067500000 44337573 955859216 1373700096 -0.0849703401 -0.0437075458 0.4191642702 2318 1311867247.7750411034 0.0697897896 0.0577410764 0.0879767612 0.0055826052 0.0067150000 44340445 955859216 1373700096 -0.0844104737 -0.0440240204 0.4163804054 2319 1311867247.8111629486 0.0695574954 0.0577461719 0.0879767612 0.0055817100 0.0137910000 44343429 955859216 1373700096 -0.0841735005 -0.0445292443 0.4136106074 2320 1311867247.8438889980 0.0690770447 0.0577510559 0.0879767612 0.0055819716 0.0081850000 44346357 955859216 1373700096 -0.0841189399 -0.0447128713 0.4110743999 2321 1311867247.8752439022 0.0683561116 0.0577556251 0.0879767612 0.0055810045 0.0069440000 44349173 955859216 1373700096 -0.0836043954 -0.0444107391 0.4089456201 2322 1311867247.9113290310 0.0683424473 0.0577601844 0.0879767612 0.0055803014 0.0068760000 44352157 955859216 1373700096 -0.0832851976 -0.0448969230 0.4068526924 2323 1311867247.9430620670 0.0681956708 0.0577646767 0.0879767612 0.0055796719 0.0067820000 44355085 955859216 1373700096 -0.0827812180 -0.0454194397 0.4048575461 2324 1311867247.9769830704 0.0680778697 0.0577691144 0.0879767612 0.0055785276 0.0068510000 44358013 955859216 1373700096 -0.0820481107 -0.0451737493 0.4030474722 2325 1311867248.0109910965 0.0682811067 0.0577736357 0.0879767612 0.0055781666 0.0067960000 44360885 955859216 1373700096 -0.0817301050 -0.0464215204 0.4008898139 2326 1311867248.0431969166 0.0683178455 0.0577781689 0.0879767612 0.0055771731 0.0112120000 44363813 955859216 1373700096 -0.0812870115 -0.0472574718 0.3986199796 2327 1311867248.0751419067 0.0681025982 0.0577826056 0.0879767612 0.0055761346 0.0077100000 44366629 955859216 1373700096 -0.0808797479 -0.0472297519 0.3962638676 2328 1311867248.1121830940 0.0683139712 0.0577871294 0.0879767612 0.0055749368 0.0109950000 44369669 955859216 1373700096 -0.0808334649 -0.0480384417 0.3937875926 2329 1311867248.1431720257 0.0682326257 0.0577916144 0.0879767612 0.0055738708 0.0077750000 44372485 955859216 1373700096 -0.0805336311 -0.0484492444 0.3912776411 2330 1311867248.1757500172 0.0682028010 0.0577960827 0.0879767612 0.0055726955 0.0070070000 44375301 955859216 1373700096 -0.0804597288 -0.0485617444 0.3888465762 2331 1311867248.2111859322 0.0678806305 0.0578004090 0.0879767612 0.0055715624 0.0067780000 44378341 955859216 1373700096 -0.0804252699 -0.0488213487 0.3864548802 2332 1311867248.2431430817 0.0679555386 0.0578047637 0.0879767612 0.0055703759 0.0068010000 44381213 955859216 1373700096 -0.0799331963 -0.0488056354 0.3840858638 2333 1311867248.2755289078 0.0678482428 0.0578090686 0.0879767612 0.0055691937 0.0067870000 44384085 955859216 1373700096 -0.0796329603 -0.0487290956 0.3816705048 2334 1311867248.3112230301 0.0673236102 0.0578131451 0.0879767612 0.0055695063 0.0112590000 44387013 955859216 1373700096 -0.0795524493 -0.0489002429 0.3790467381 2335 1311867248.3434588909 0.0675285086 0.0578173059 0.0879767612 0.0055698805 0.0077420000 44389773 955859216 1373700096 -0.0789783970 -0.0484998040 0.3766755760 2336 1311867248.3752219677 0.0674185157 0.0578214160 0.0879767612 0.0055712670 0.0069420000 44392645 955859216 1373700096 -0.0785103291 -0.0474378616 0.3744227588 2337 1311867248.4115560055 0.0669156462 0.0578253074 0.0879767612 0.0055715364 0.0069240000 44395685 955859216 1373700096 -0.0782004446 -0.0468846187 0.3721457720 2338 1311867248.4431369305 0.0672087669 0.0578293209 0.0879767612 0.0055704093 0.0072040000 44398501 955859216 1373700096 -0.0778827518 -0.0468276665 0.3698254526 2339 1311867248.4759230614 0.0671099350 0.0578332886 0.0879767612 0.0055693403 0.0120100000 44401429 955859216 1373700096 -0.0774560422 -0.0466669872 0.3675079644 2340 1311867248.5111510754 0.0666049123 0.0578370372 0.0879767612 0.0055685931 0.0078590000 44404357 955859216 1373700096 -0.0770759583 -0.0464554802 0.3652207553 2341 1311867248.5431890488 0.0669297278 0.0578409213 0.0879767612 0.0055675974 0.0110760000 44407285 955859216 1373700096 -0.0765205100 -0.0464073122 0.3628640473 2342 1311867248.5751869678 0.0667211488 0.0578447130 0.0879767612 0.0055667846 0.0119700000 44410101 955859216 1373700096 -0.0760272518 -0.0466786623 0.3605378568 2343 1311867248.6114389896 0.0665871128 0.0578484443 0.0879767612 0.0055658494 0.0108730000 44413141 955859216 1373700096 -0.0752625763 -0.0463968031 0.3582466841 2344 1311867248.6432449818 0.0670144856 0.0578523547 0.0879767612 0.0055647041 0.0078160000 44415957 955859216 1373700096 -0.0750434026 -0.0465542525 0.3558340669 2345 1311867248.6753089428 0.0668856129 0.0578562069 0.0879767612 0.0055635998 0.0070500000 44418773 955859216 1373700096 -0.0747499391 -0.0466931760 0.3533265293 2346 1311867248.7112829685 0.0673181266 0.0578602401 0.0879767612 0.0055633271 0.0070120000 44421813 955859216 1373700096 -0.0741974413 -0.0461011007 0.3508783281 2347 1311867248.7433049679 0.0671725273 0.0578642078 0.0879767612 0.0055634527 0.0110500000 44424629 955859216 1373700096 -0.0738102794 -0.0457447469 0.3481071293 2348 1311867248.7762219906 0.0669705421 0.0578680862 0.0879767612 0.0055623510 0.0077680000 44427557 955859216 1373700096 -0.0731854364 -0.0456212536 0.3452897668 2349 1311867248.8111898899 0.0670893490 0.0578720118 0.0879767612 0.0055641963 0.0108770000 44430485 955859216 1373700096 -0.0727856979 -0.0448734313 0.3427422345 2350 1311867248.8433189392 0.0667648911 0.0578757960 0.0879767612 0.0055694263 0.0077570000 44433357 955859216 1373700096 -0.0727957487 -0.0450988673 0.3398958445 2351 1311867248.8755309582 0.0669708699 0.0578796646 0.0879767612 0.0055689771 0.0070490000 44436285 955859216 1373700096 -0.0720833465 -0.0455932878 0.3369418681 2352 1311867248.9111700058 0.0671513230 0.0578836066 0.0879767612 0.0055681874 0.0069830000 44439269 955859216 1373700096 -0.0709528327 -0.0450106338 0.3340438306 2353 1311867248.9430971146 0.0669333190 0.0578874527 0.0879767612 0.0055673219 0.0109650000 44442085 955859216 1373700096 -0.0705324337 -0.0450300053 0.3310384750 2354 1311867248.9766070843 0.0670207664 0.0578913326 0.0879767612 0.0055667777 0.0077470000 44445069 955859216 1373700096 -0.0702248067 -0.0456625819 0.3279148638 2355 1311867249.0112600327 0.0668737590 0.0578951468 0.0879767612 0.0055658526 0.0069080000 44447941 955859216 1373700096 -0.0691448599 -0.0451813415 0.3249424696 2356 1311867249.0432310104 0.0670696273 0.0578990408 0.0879767612 0.0055647168 0.0069360000 44450813 955859216 1373700096 -0.0678045154 -0.0448072366 0.3219676614 2357 1311867249.0799250603 0.0666606128 0.0579027581 0.0879767612 0.0055640059 0.0068880000 44453853 955859216 1373700096 -0.0671473891 -0.0447478220 0.3188537061 2358 1311867249.1120550632 0.0665415749 0.0579064217 0.0879767612 0.0055638119 0.0068820000 44456725 955859216 1373700096 -0.0660321414 -0.0439889766 0.3160871863 2359 1311867249.1435980797 0.0662560388 0.0579099612 0.0879767612 0.0055635931 0.0068920000 44459597 955859216 1373700096 -0.0646160543 -0.0432531238 0.3132945001 2360 1311867249.1785130501 0.0662458166 0.0579134933 0.0879767612 0.0055629046 0.0069320000 44462469 955859216 1373700096 -0.0636659265 -0.0438420810 0.3102260828 2361 1311867249.2113580704 0.0658276752 0.0579168454 0.0879767612 0.0055621132 0.0116110000 44465397 955859216 1373700096 -0.0628687814 -0.0437712297 0.3072332442 2362 1311867249.2432780266 0.0657533333 0.0579201631 0.0879767612 0.0055617571 0.0078940000 44468325 955859216 1373700096 -0.0616836399 -0.0428128727 0.3044714034 2363 1311867249.2773559093 0.0657497644 0.0579234765 0.0879767612 0.0055624226 0.0069350000 44471253 955859216 1373700096 -0.0609310120 -0.0437426753 0.3014460206 2364 1311867249.3112919331 0.0655483752 0.0579267020 0.0879767612 0.0055632097 0.0069580000 44474125 955859216 1373700096 -0.0598187670 -0.0436182320 0.2985994816 2365 1311867249.3437249660 0.0651337877 0.0579297494 0.0879767612 0.0055626336 0.0115250000 44477053 955859216 1373700096 -0.0586862974 -0.0424839295 0.2959615588 2366 1311867249.3768579960 0.0648155436 0.0579326597 0.0879767612 0.0055641672 0.0079060000 44479981 955859216 1373700096 -0.0579001196 -0.0430938154 0.2930785120 2367 1311867249.4112169743 0.0650344267 0.0579356600 0.0879767612 0.0055635287 0.0076460000 44482909 955859216 1373700096 -0.0569180250 -0.0435127318 0.2902690768 2368 1311867249.4432210922 0.0647911355 0.0579385550 0.0879767612 0.0055629373 0.0071510000 44485725 955859216 1373700096 -0.0558725633 -0.0429427810 0.2876684666 2369 1311867249.4764440060 0.0647110045 0.0579414138 0.0879767612 0.0055617683 0.0109950000 44488653 955859216 1373700096 -0.0552388169 -0.0431018732 0.2849482596 2370 1311867249.5111339092 0.0647944212 0.0579443054 0.0879767612 0.0055611155 0.0078070000 44491581 955859216 1373700096 -0.0549047440 -0.0440151319 0.2820514143 2371 1311867249.5432300568 0.0644539744 0.0579470509 0.0879767612 0.0055603066 0.0071800000 44494453 955859216 1373700096 -0.0539338067 -0.0435498208 0.2793497145 2372 1311867249.5759820938 0.0644213110 0.0579497804 0.0879767612 0.0055591597 0.0071270000 44497381 955859216 1373700096 -0.0532713868 -0.0433910415 0.2766014636 2373 1311867249.6112229824 0.0643549338 0.0579524795 0.0879767612 0.0055582812 0.0069790000 44500309 955859216 1373700096 -0.0529275052 -0.0440836661 0.2737655938 2374 1311867249.6433780193 0.0640854016 0.0579550629 0.0879767612 0.0055590835 0.0119290000 44503181 955859216 1373700096 -0.0524792336 -0.0434684455 0.2714057863 2375 1311867249.6751029491 0.0635958239 0.0579574380 0.0879767612 0.0055619354 0.0079200000 44506053 955859216 1373700096 -0.0518517531 -0.0430980586 0.2689165473 2376 1311867249.7111389637 0.0642649308 0.0579600926 0.0879767612 0.0055618400 0.0071400000 44508981 955859216 1373700096 -0.0518375002 -0.0440662056 0.2661310732 2377 1311867249.7432470322 0.0641101599 0.0579626800 0.0879767612 0.0055621988 0.0071560000 44511909 955859216 1373700096 -0.0510559827 -0.0435355976 0.2635406554 2378 1311867249.7751579285 0.0632387251 0.0579648987 0.0879767612 0.0055639487 0.0070690000 44514725 955859216 1373700096 -0.0503277257 -0.0422532633 0.2613202333 2379 1311867249.8111488819 0.0640242174 0.0579674457 0.0879767612 0.0055633393 0.0070180000 44517765 955859216 1373700096 -0.0500753783 -0.0421127416 0.2589124441 2380 1311867249.8433248997 0.0638605729 0.0579699218 0.0879767612 0.0055623096 0.0115500000 44520581 955859216 1373700096 -0.0492960811 -0.0412786156 0.2564589381 2381 1311867249.8784089088 0.0639823005 0.0579724469 0.0879767612 0.0055612993 0.0079300000 44523565 955859216 1373700096 -0.0485079959 -0.0402806401 0.2541862130 2382 1311867249.9112401009 0.0642559975 0.0579750848 0.0879767612 0.0055602485 0.0071310000 44526437 955859216 1373700096 -0.0482262671 -0.0398621634 0.2514306307 2383 1311867249.9432768822 0.0640867054 0.0579776495 0.0879767612 0.0055597893 0.0070730000 44529365 955859216 1373700096 -0.0477419682 -0.0398760512 0.2486826479 2384 1311867249.9751698971 0.0642208233 0.0579802683 0.0879767612 0.0055592771 0.0069880000 44532181 955859216 1373700096 -0.0471435897 -0.0396799073 0.2459418923 2385 1311867250.0117108822 0.0641560853 0.0579828577 0.0879767612 0.0055588075 0.0070560000 44535221 955859216 1373700096 -0.0465955213 -0.0391564071 0.2430457175 2386 1311867250.0434269905 0.0642575994 0.0579854876 0.0879767612 0.0055583880 0.0070020000 44538093 955859216 1373700096 -0.0462269522 -0.0388911366 0.2400580645 2387 1311867250.0767190456 0.0639723986 0.0579879957 0.0879767612 0.0055586101 0.0070510000 44541021 955859216 1373700096 -0.0460133068 -0.0393095501 0.2369810045 2388 1311867250.1116099358 0.0639403909 0.0579904883 0.0879767612 0.0055576271 0.0070190000 44543949 955859216 1373700096 -0.0455579385 -0.0392002128 0.2341397107 2389 1311867250.1432220936 0.0640584901 0.0579930283 0.0879767612 0.0055565655 0.0070850000 44546765 955859216 1373700096 -0.0452445969 -0.0390981287 0.2311796993 2390 1311867250.1758980751 0.0638970882 0.0579954986 0.0879767612 0.0055554450 0.0070540000 44549693 955859216 1373700096 -0.0449476838 -0.0395395011 0.2280367315 2391 1311867250.2133369446 0.0640019625 0.0579980107 0.0879767612 0.0055543546 0.0071830000 44552677 955859216 1373700096 -0.0445848219 -0.0390242785 0.2250722796 2392 1311867250.2457129955 0.0633994490 0.0580002689 0.0879767612 0.0055538511 0.0107730000 44555605 955859216 1373700096 -0.0440167934 -0.0383116901 0.2222045660 2393 1311867250.2751679420 0.0630478635 0.0580023782 0.0879767612 0.0055532817 0.0117150000 44558365 955859216 1373700096 -0.0434736200 -0.0378046222 0.2194967419 2394 1311867250.3114409447 0.0633681789 0.0580046195 0.0879767612 0.0055522867 0.0080410000 44561405 955859216 1373700096 -0.0430906676 -0.0374925546 0.2169201076 2395 1311867250.3431971073 0.0633480698 0.0580068506 0.0879767612 0.0055516621 0.0110990000 44564221 955859216 1373700096 -0.0427305363 -0.0369602218 0.2145259827 2396 1311867250.3780639172 0.0629882365 0.0580089296 0.0879767612 0.0055507406 0.0079490000 44567205 955859216 1373700096 -0.0420966595 -0.0365020819 0.2120917290 2397 1311867250.4116489887 0.0633424446 0.0580111547 0.0879767612 0.0055503450 0.0071830000 44570133 955859216 1373700096 -0.0417739786 -0.0369054005 0.2094568461 2398 1311867250.4441781044 0.0629359707 0.0580132084 0.0879767612 0.0055492194 0.0070820000 44572949 955859216 1373700096 -0.0408500321 -0.0369677171 0.2068803459 2399 1311867250.4793250561 0.0629239231 0.0580152554 0.0879767612 0.0055484477 0.0070770000 44575933 955859216 1373700096 -0.0402024686 -0.0358552672 0.2045161873 2400 1311867250.5113220215 0.0627216548 0.0580172164 0.0879767612 0.0055476204 0.0118240000 44578805 955859216 1373700096 -0.0400642343 -0.0356834680 0.2020684928 2401 1311867250.5443398952 0.0630341247 0.0580193059 0.0879767612 0.0055466188 0.0081120000 44581677 955859216 1373700096 -0.0398555882 -0.0360588022 0.1997596771 2402 1311867250.5793490410 0.0629131347 0.0580213433 0.0879767612 0.0055456418 0.0113510000 44584661 955859216 1373700096 -0.0390182361 -0.0348345712 0.1977568269 2403 1311867250.6114881039 0.0631145164 0.0580234628 0.0879767612 0.0055445238 0.0080010000 44587589 955859216 1373700096 -0.0384862870 -0.0345763825 0.1954358667 2404 1311867250.6433761120 0.0630121231 0.0580255380 0.0879767612 0.0055441105 0.0073100000 44590461 955859216 1373700096 -0.0383558348 -0.0352581553 0.1929202974 2405 1311867250.6795539856 0.0632841587 0.0580277245 0.0879767612 0.0055442354 0.0118400000 44593389 955859216 1373700096 -0.0378013812 -0.0345377550 0.1906836629 2406 1311867250.7112920284 0.0628792420 0.0580297410 0.0879767612 0.0055433615 0.0082240000 44596261 955859216 1373700096 -0.0375249498 -0.0339726508 0.1882425845 2407 1311867250.7445890903 0.0625563636 0.0580316216 0.0879767612 0.0055449833 0.0072380000 44599189 955859216 1373700096 -0.0374402255 -0.0346813500 0.1857637465 2408 1311867250.7792830467 0.0628083125 0.0580336052 0.0879767612 0.0055449039 0.0070620000 44602061 955859216 1373700096 -0.0376375318 -0.0349527448 0.1835398525 2409 1311867250.8145580292 0.0623921007 0.0580354145 0.0879767612 0.0055443137 0.0070540000 44605045 955859216 1373700096 -0.0371381305 -0.0343338996 0.1815234274 2410 1311867250.8433599472 0.0622123256 0.0580371476 0.0879767612 0.0055433108 0.0120590000 44607805 955859216 1373700096 -0.0372034013 -0.0350649096 0.1794781536 2411 1311867250.8792760372 0.0617510676 0.0580386881 0.0879767612 0.0055450244 0.0080890000 44610789 955859216 1373700096 -0.0375531092 -0.0358856656 0.1773861051 2412 1311867250.9116361141 0.0618146956 0.0580402536 0.0879767612 0.0055444619 0.0072420000 44613717 955859216 1373700096 -0.0372851007 -0.0359802581 0.1753387600 2413 1311867250.9433720112 0.0620815046 0.0580419283 0.0879767612 0.0055436889 0.0072750000 44616533 955859216 1373700096 -0.0372049734 -0.0364674181 0.1733371466 2414 1311867250.9793050289 0.0620255768 0.0580435786 0.0879767612 0.0055428965 0.0070550000 44619517 955859216 1373700096 -0.0374093726 -0.0365419276 0.1713982522 2415 1311867251.0112459660 0.0615616068 0.0580450353 0.0879767612 0.0055420859 0.0069750000 44622389 955859216 1373700096 -0.0370362513 -0.0361677706 0.1695664227 2416 1311867251.0437910557 0.0620552227 0.0580466952 0.0879767612 0.0055413696 0.0114250000 44625261 955859216 1373700096 -0.0374824814 -0.0368869193 0.1675024927 2417 1311867251.0793159008 0.0622970834 0.0580484537 0.0879767612 0.0055406882 0.0080340000 44628245 955859216 1373700096 -0.0374720469 -0.0372387692 0.1655293107 2418 1311867251.1115839481 0.0616547018 0.0580499451 0.0879767612 0.0055398447 0.0072400000 44631173 955859216 1373700096 -0.0372451246 -0.0364500880 0.1637660712 2419 1311867251.1432809830 0.0615763329 0.0580514029 0.0879767612 0.0055396258 0.0071810000 44634045 955859216 1373700096 -0.0376695767 -0.0365454927 0.1616944373 2420 1311867251.1794250011 0.0617707707 0.0580529398 0.0879767612 0.0055403957 0.0071460000 44637029 955859216 1373700096 -0.0380587615 -0.0373213440 0.1595633328 2421 1311867251.2113831043 0.0617752336 0.0580544773 0.0879767612 0.0055448099 0.0116940000 44639901 955859216 1373700096 -0.0383108370 -0.0366140679 0.1576901823 2422 1311867251.2472319603 0.0613605641 0.0580558424 0.0879767612 0.0055454884 0.0080650000 44642885 955859216 1373700096 -0.0381565690 -0.0366095155 0.1556908190 2423 1311867251.2793700695 0.0619127601 0.0580574342 0.0879767612 0.0055444741 0.0112860000 44645701 955859216 1373700096 -0.0388778299 -0.0380851030 0.1534306854 2424 1311867251.3133869171 0.0620299578 0.0580590730 0.0879767612 0.0055441637 0.0088240000 44648685 955859216 1373700096 -0.0385810919 -0.0381238274 0.1514762938 2425 1311867251.3432419300 0.0609114803 0.0580602492 0.0879767612 0.0055473865 0.0075570000 44651445 955859216 1373700096 -0.0387581512 -0.0380820706 0.1494002938 2426 1311867251.3801820278 0.0613542311 0.0580616070 0.0879767612 0.0055465074 0.0073690000 44654485 955859216 1373700096 -0.0389335044 -0.0389018320 0.1473004669 2427 1311867251.4113550186 0.0610428527 0.0580628354 0.0879767612 0.0055454710 0.0122870000 44657357 955859216 1373700096 -0.0387546793 -0.0388792157 0.1453518271 2428 1311867251.4433960915 0.0612901598 0.0580641646 0.0879767612 0.0055446542 0.0082960000 44660173 955859216 1373700096 -0.0385563672 -0.0388681628 0.1435595900 2429 1311867251.4793379307 0.0612590201 0.0580654799 0.0879767612 0.0055438042 0.0074610000 44663157 955859216 1373700096 -0.0389491729 -0.0392366871 0.1416098475 2430 1311867251.5175099373 0.0607911423 0.0580666016 0.0879767612 0.0055430781 0.0073370000 44666253 955859216 1373700096 -0.0388220437 -0.0393352509 0.1397727430 2431 1311867251.5431749821 0.0610993505 0.0580678491 0.0879767612 0.0055424362 0.0073420000 44668901 955859216 1373700096 -0.0389265120 -0.0392268896 0.1380110681 2432 1311867251.5795340538 0.0613564849 0.0580692013 0.0879767612 0.0055415578 0.0072710000 44671941 955859216 1373700096 -0.0391417816 -0.0393106528 0.1361030638 2433 1311867251.6119680405 0.0611279160 0.0580704585 0.0879767612 0.0055404184 0.0071510000 44674869 955859216 1373700096 -0.0387725309 -0.0392600037 0.1342939585 2434 1311867251.6432960033 0.0609576926 0.0580716447 0.0879767612 0.0055396425 0.0071920000 44677685 955859216 1373700096 -0.0385770947 -0.0396122262 0.1323195547 2435 1311867251.6797280312 0.0611714795 0.0580729178 0.0879767612 0.0055408892 0.0072070000 44680669 955859216 1373700096 -0.0389873013 -0.0400757566 0.1303021759 2436 1311867251.7123379707 0.0607996061 0.0580740371 0.0879767612 0.0055404603 0.0070860000 44683597 955859216 1373700096 -0.0386133194 -0.0396446213 0.1282816976 2437 1311867251.7434990406 0.0605465733 0.0580750517 0.0879767612 0.0055400723 0.0071690000 44686357 955859216 1373700096 -0.0381892323 -0.0387321711 0.1264640540 2438 1311867251.7797439098 0.0610629953 0.0580762772 0.0879767612 0.0055391205 0.0071450000 44689397 955859216 1373700096 -0.0386384539 -0.0397148840 0.1242889166 2439 1311867251.8112530708 0.0609038323 0.0580774365 0.0879767612 0.0055383491 0.0071660000 44692269 955859216 1373700096 -0.0386199839 -0.0401488766 0.1221256480 2440 1311867251.8433279991 0.0603689924 0.0580783757 0.0879767612 0.0055372940 0.0072920000 44695141 955859216 1373700096 -0.0385446958 -0.0394506641 0.1203741580 2441 1311867251.8805420399 0.0601661280 0.0580792310 0.0879767612 0.0055367494 0.0072680000 44698069 955859216 1373700096 -0.0382864103 -0.0396163315 0.1184769794 2442 1311867251.9112489223 0.0601713210 0.0580800877 0.0879767612 0.0055356579 0.0072520000 44700941 955859216 1373700096 -0.0378702842 -0.0396259800 0.1168192402 2443 1311867251.9432179928 0.0602292009 0.0580809674 0.0879767612 0.0055352639 0.0072700000 44703757 955859216 1373700096 -0.0373129919 -0.0387608372 0.1152847558 2444 1311867251.9800109863 0.0601756386 0.0580818245 0.0879767612 0.0055348313 0.0125650000 44706797 955859216 1373700096 -0.0371937938 -0.0389182754 0.1135932058 2445 1311867252.0119040012 0.0599084981 0.0580825716 0.0879767612 0.0055339954 0.0082460000 44709725 955859216 1373700096 -0.0370439962 -0.0388872921 0.1118424162 2446 1311867252.0441029072 0.0603141226 0.0580834839 0.0879767612 0.0055332085 0.0075640000 44712597 955859216 1373700096 -0.0371299647 -0.0393163823 0.1099254265 2447 1311867252.0794539452 0.0609678105 0.0580846626 0.0879767612 0.0055321260 0.0072230000 44715469 955859216 1373700096 -0.0366030149 -0.0395948067 0.1077569649 2448 1311867252.1122460365 0.0608497448 0.0580857922 0.0879767612 0.0055316984 0.0072350000 44718453 955859216 1373700096 -0.0370581560 -0.0398382619 0.1051805392 2449 1311867252.1432950497 0.0607699826 0.0580868882 0.0879767612 0.0055320465 0.0071430000 44721213 955859216 1373700096 -0.0374844074 -0.0409586616 0.1023391187 2450 1311867252.1794359684 0.0609736033 0.0580880664 0.0879767612 0.0055309476 0.0071070000 44724197 955859216 1373700096 -0.0374291316 -0.0417359397 0.0995026678 2451 1311867252.2113459110 0.0607421026 0.0580891493 0.0879767612 0.0055319312 0.0070850000 44727125 955859216 1373700096 -0.0369227342 -0.0418780819 0.0967410579 2452 1311867252.2432808876 0.0604937151 0.0580901299 0.0879767612 0.0055315378 0.0071950000 44729997 955859216 1373700096 -0.0374327451 -0.0429700837 0.0936781615 2453 1311867252.2794110775 0.0603425466 0.0580910482 0.0879767612 0.0055316804 0.0121020000 44732981 955859216 1373700096 -0.0378695279 -0.0447191559 0.0907264054 2454 1311867252.3112668991 0.0599227138 0.0580917946 0.0879767612 0.0055314291 0.0088400000 44735853 955859216 1373700096 -0.0376185477 -0.0453453921 0.0878727734 2455 1311867252.3450291157 0.0594255589 0.0580923378 0.0879767612 0.0055304587 0.0077860000 44738725 955859216 1373700096 -0.0370437987 -0.0460672490 0.0849388391 2456 1311867252.3794589043 0.0594849400 0.0580929049 0.0879767612 0.0055297545 0.0074030000 44741709 955859216 1373700096 -0.0371371768 -0.0485363118 0.0818249583 2457 1311867252.4111969471 0.0598673560 0.0580936271 0.0879767612 0.0055291918 0.0074100000 44744581 955859216 1373700096 -0.0372229591 -0.0503756478 0.0787563026 2458 1311867252.4456050396 0.0598778687 0.0580943530 0.0879767612 0.0055356130 0.0073590000 44747509 955859216 1373700096 -0.0361493044 -0.0506016761 0.0760122165 2459 1311867252.4792900085 0.0587787814 0.0580946313 0.0879767612 0.0055442234 0.0072940000 44750381 955859216 1373700096 -0.0358801894 -0.0516789034 0.0729172528 2460 1311867252.5112249851 0.0591702200 0.0580950685 0.0879767612 0.0055432738 0.0073110000 44753309 955859216 1373700096 -0.0362349711 -0.0535028912 0.0696737245 2461 1311867252.5432820320 0.0588425994 0.0580953723 0.0879767612 0.0055429989 0.0072510000 44756181 955859216 1373700096 -0.0358287729 -0.0535806641 0.0666954964 2462 1311867252.5791800022 0.0586431846 0.0580955948 0.0879767612 0.0055418885 0.0072800000 44759165 955859216 1373700096 -0.0365595892 -0.0541553088 0.0638198107 2463 1311867252.6112799644 0.0586787835 0.0580958316 0.0879767612 0.0055408638 0.0119470000 44762037 955859216 1373700096 -0.0369800888 -0.0556676164 0.0607584193 2464 1311867252.6432769299 0.0589410216 0.0580961746 0.0879767612 0.0055399262 0.0082290000 44764965 955859216 1373700096 -0.0361251868 -0.0564325862 0.0577171855 2465 1311867252.6792490482 0.0590077825 0.0580965444 0.0879767612 0.0055401958 0.0073480000 44767837 955859216 1373700096 -0.0366912596 -0.0569322594 0.0549495146 2466 1311867252.7112491131 0.0587081499 0.0580967924 0.0879767612 0.0055398162 0.0073750000 44770765 955859216 1373700096 -0.0373617150 -0.0582012236 0.0518797599 2467 1311867252.7432410717 0.0588990115 0.0580971176 0.0879767612 0.0055388024 0.0073760000 44773581 955859216 1373700096 -0.0366306677 -0.0597393923 0.0485154688 2468 1311867252.7792730331 0.0591514930 0.0580975448 0.0879767612 0.0055377132 0.0119880000 44776565 955859216 1373700096 -0.0361241177 -0.0603978075 0.0455180109 2469 1311867252.8112781048 0.0593048744 0.0580980338 0.0879767612 0.0055373008 0.0082300000 44779493 955859216 1373700096 -0.0355649777 -0.0603954978 0.0426040255 2470 1311867252.8433189392 0.0591616705 0.0580984644 0.0879767612 0.0055369382 0.0077160000 44782365 955859216 1373700096 -0.0352957882 -0.0617197976 0.0393082574 2471 1311867252.8792660236 0.0595037416 0.0580990331 0.0879767612 0.0055374451 0.0073610000 44785293 955859216 1373700096 -0.0349234007 -0.0619342662 0.0363049619 2472 1311867252.9112188816 0.0587819554 0.0580993094 0.0879767612 0.0055364257 0.0072920000 44788221 955859216 1373700096 -0.0342515074 -0.0615055598 0.0335605294 2473 1311867252.9446918964 0.0587070100 0.0580995551 0.0879767612 0.0055360420 0.0120270000 44791093 955859216 1373700096 -0.0334817506 -0.0625929832 0.0305954255 2474 1311867252.9806020260 0.0594622344 0.0581001059 0.0879767612 0.0055359366 0.0082760000 44794077 955859216 1373700096 -0.0333610289 -0.0636313632 0.0276705008 2475 1311867253.0113809109 0.0585216805 0.0581002763 0.0879767612 0.0055349934 0.0074660000 44796949 955859216 1373700096 -0.0317554101 -0.0625825897 0.0251139365 2476 1311867253.0434310436 0.0590545237 0.0581006617 0.0879767612 0.0055347052 0.0076200000 44799821 955859216 1373700096 -0.0315448977 -0.0639503971 0.0222440846 2477 1311867253.0799300671 0.0590550043 0.0581010470 0.0879767612 0.0055421712 0.0227370000 44802805 955859216 1373700096 -0.0312977619 -0.0655919462 0.0190830454 2478 1311867253.1113030910 0.0589910522 0.0581014061 0.0879767612 0.0055441353 0.0128820000 44805677 955859216 1373700096 -0.0305476226 -0.0649488792 0.0163103361 2479 1311867253.1440761089 0.0587949753 0.0581016859 0.0879767612 0.0055438613 0.0084400000 44808549 955859216 1373700096 -0.0298783258 -0.0650849864 0.0133072929 2480 1311867253.1794049740 0.0587603487 0.0581019515 0.0879767612 0.0055429068 0.0075570000 44811477 955859216 1373700096 -0.0297687706 -0.0661792606 0.0102268718 2481 1311867253.2112159729 0.0585499890 0.0581021321 0.0879767612 0.0055423853 0.0073330000 44814405 955859216 1373700096 -0.0287697390 -0.0666866302 0.0075075338 2482 1311867253.2458410263 0.0578945205 0.0581020484 0.0879767612 0.0055413610 0.0192460000 44817333 955859216 1373700096 -0.0286349356 -0.0667605326 0.0047956649 2483 1311867253.2793951035 0.0581037998 0.0581020491 0.0879767612 0.0055407097 0.0092100000 44820205 955859216 1373700096 -0.0278644450 -0.0669339672 0.0021770257 2484 1311867253.3114080429 0.0576891489 0.0581018829 0.0879767612 0.0055397133 0.0075600000 44823133 955859216 1373700096 -0.0267366543 -0.0672875419 -0.0003097711 2485 1311867253.3445611000 0.0576425306 0.0581016981 0.0879767612 0.0055453969 0.0075560000 44826061 955859216 1373700096 -0.0259464681 -0.0677087903 -0.0027349722 2486 1311867253.3794078827 0.0575131029 0.0581014613 0.0879767612 0.0055480678 0.0075550000 44828933 955859216 1373700096 -0.0245852340 -0.0681541786 -0.0051961322 2487 1311867253.4129528999 0.0576133840 0.0581012650 0.0879767612 0.0055488704 0.0074690000 44831917 955859216 1373700096 -0.0237358920 -0.0687478855 -0.0075441827 2488 1311867253.4444990158 0.0574888624 0.0581010189 0.0879767612 0.0055488946 0.0074990000 44834733 955859216 1373700096 -0.0232498068 -0.0688106418 -0.0098277824 2489 1311867253.4804859161 0.0575488918 0.0581007971 0.0879767612 0.0055489513 0.0074450000 44837717 955859216 1373700096 -0.0218015350 -0.0686082467 -0.0119562829 2490 1311867253.5113739967 0.0572381653 0.0581004506 0.0879767612 0.0055481377 0.0126460000 44840589 955859216 1373700096 -0.0201990511 -0.0695195571 -0.0143696694 2491 1311867253.5441629887 0.0572175905 0.0581000962 0.0879767612 0.0055478355 0.0084740000 44843405 955859216 1373700096 -0.0201469325 -0.0705757514 -0.0166764967 2492 1311867253.5794069767 0.0570545755 0.0580996767 0.0879767612 0.0055470602 0.0117110000 44846389 955859216 1373700096 -0.0190136563 -0.0711939186 -0.0188509412 2493 1311867253.6118021011 0.0568771437 0.0580991863 0.0879767612 0.0055460426 0.0083420000 44849317 955859216 1373700096 -0.0191541072 -0.0722426772 -0.0214041304 2494 1311867253.6447649002 0.0570463724 0.0580987641 0.0879767612 0.0055452173 0.0076080000 44852189 955859216 1373700096 -0.0187910572 -0.0732534826 -0.0238841865 2495 1311867253.6799790859 0.0569503829 0.0580983039 0.0879767612 0.0055442747 0.0075930000 44855173 955859216 1373700096 -0.0186012872 -0.0741225854 -0.0264294762 2496 1311867253.7115769386 0.0572162084 0.0580979505 0.0879767612 0.0055440044 0.0124990000 44858045 955859216 1373700096 -0.0186118875 -0.0756867826 -0.0293737333 2497 1311867253.7435369492 0.0573764518 0.0580976615 0.0879767612 0.0055453616 0.0085460000 44860861 955859216 1373700096 -0.0187848136 -0.0783409029 -0.0328748636 2498 1311867253.7806150913 0.0576839633 0.0580974959 0.0879767612 0.0055453996 0.0077260000 44863845 955859216 1373700096 -0.0194488205 -0.0797036886 -0.0363441966 2499 1311867253.8113009930 0.0574117862 0.0580972215 0.0879767612 0.0055443830 0.0075780000 44866717 955859216 1373700096 -0.0196774695 -0.0810517967 -0.0398434736 2500 1311867253.8469560146 0.0572512746 0.0580968831 0.0879767612 0.0055442794 0.0075920000 44869701 955859216 1373700096 -0.0201920196 -0.0823757499 -0.0436346158 2501 1311867253.8792059422 0.0570838563 0.0580964781 0.0879767612 0.0055434040 0.0124810000 44872517 955859216 1373700096 -0.0211135950 -0.0843014643 -0.0475806929 2502 1311867253.9114460945 0.0567673482 0.0580959469 0.0879767612 0.0055423221 0.0087090000 44875389 955859216 1373700096 -0.0225365404 -0.0857230723 -0.0515807718 2503 1311867253.9461600780 0.0565230772 0.0580953185 0.0879767612 0.0055412717 0.0078040000 44878373 955859216 1373700096 -0.0232598782 -0.0859126449 -0.0554988794 2504 1311867253.9794149399 0.0562906303 0.0580945977 0.0879767612 0.0055402855 0.0077650000 44881189 955859216 1373700096 -0.0245612748 -0.0866043642 -0.0591585152 2505 1311867254.0119979382 0.0563405603 0.0580938975 0.0879767612 0.0055405019 0.0076720000 44884117 955859216 1373700096 -0.0262863841 -0.0883353800 -0.0628868863 2506 1311867254.0457749367 0.0558944680 0.0580930199 0.0879767612 0.0055394396 0.0075640000 44887045 955859216 1373700096 -0.0270083323 -0.0886927173 -0.0662477389 2507 1311867254.0793740749 0.0565139130 0.0580923900 0.0879767612 0.0055434046 0.0075180000 44889917 955859216 1373700096 -0.0276801698 -0.0892364755 -0.0695048347 2508 1311867254.1113519669 0.0563112162 0.0580916798 0.0879767612 0.0055425864 0.0075510000 44892789 955859216 1373700096 -0.0285625607 -0.0902209878 -0.0728428662 2509 1311867254.1476950645 0.0563393906 0.0580909814 0.0879767612 0.0055418121 0.0074840000 44895829 955859216 1373700096 -0.0306469537 -0.0898447856 -0.0758412778 2510 1311867254.1795129776 0.0563352741 0.0580902819 0.0879767612 0.0055407749 0.0077140000 44898645 955859216 1373700096 -0.0309471451 -0.0898870975 -0.0788168982 2511 1311867254.2114939690 0.0548975281 0.0580890104 0.0879767612 0.0055451555 0.0076990000 44901573 955859216 1373700096 -0.0321072005 -0.0900747627 -0.0819119960 2512 1311867254.2469160557 0.0558783747 0.0580881304 0.0879767612 0.0055449636 0.0076600000 44904557 955859216 1373700096 -0.0338701829 -0.0901071876 -0.0850539804 2513 1311867254.2798569202 0.0558407456 0.0580872361 0.0879767612 0.0055456701 0.0075080000 44907373 955859216 1373700096 -0.0352747627 -0.0880256966 -0.0879661813 2514 1311867254.3114631176 0.0550823174 0.0580860408 0.0879767612 0.0055522204 0.0075240000 44910245 955859216 1373700096 -0.0368544981 -0.0862793103 -0.0911458731 2515 1311867254.3475589752 0.0563544221 0.0580853523 0.0879767612 0.0055527035 0.0075950000 44913285 955859216 1373700096 -0.0390137956 -0.0872418955 -0.0947402120 2516 1311867254.3794488907 0.0568262339 0.0580848518 0.0879767612 0.0055519087 0.0075650000 44916101 955859216 1373700096 -0.0405920036 -0.0885630995 -0.0985974669 2517 1311867254.4115350246 0.0569076203 0.0580843841 0.0879767612 0.0055561189 0.0077280000 44919029 955859216 1373700096 -0.0418333896 -0.0881999806 -0.1024294272 2518 1311867254.4483439922 0.0574606508 0.0580841364 0.0879767612 0.0055553559 0.0074570000 44922013 955859216 1373700096 -0.0427551903 -0.0877821147 -0.1065926999 2519 1311867254.4794480801 0.0569531061 0.0580836874 0.0879767612 0.0055548321 0.0075730000 44924829 955859216 1373700096 -0.0428042598 -0.0881755799 -0.1108513996 2520 1311867254.5114428997 0.0564747155 0.0580830489 0.0879767612 0.0055537511 0.0075350000 44927701 955859216 1373700096 -0.0428798348 -0.0880674273 -0.1149519607 2521 1311867254.5500459671 0.0569370650 0.0580825943 0.0879767612 0.0055544152 0.0075290000 44930741 955859216 1373700096 -0.0426192060 -0.0876013488 -0.1193957105 2522 1311867254.5794870853 0.0566059053 0.0580820088 0.0879767612 0.0055584496 0.0076120000 44933557 955859216 1373700096 -0.0425517559 -0.0876701474 -0.1236192062 2523 1311867254.6114809513 0.0558131225 0.0580811095 0.0879767612 0.0055575199 0.0075580000 44936429 955859216 1373700096 -0.0434528105 -0.0867376253 -0.1275379807 2524 1311867254.6452929974 0.0556677207 0.0580801534 0.0879767612 0.0055587934 0.0076480000 44939357 955859216 1373700096 -0.0435290635 -0.0851662681 -0.1314993650 2525 1311867254.6794900894 0.0558928214 0.0580792871 0.0879767612 0.0055596655 0.0075880000 44942341 955859216 1373700096 -0.0438047126 -0.0847108364 -0.1357816607 2526 1311867254.7113230228 0.0550701879 0.0580780958 0.0879767612 0.0055586847 0.0076820000 44945213 955859216 1373700096 -0.0443152189 -0.0848858133 -0.1398935765 2527 1311867254.7453329563 0.0553291366 0.0580770080 0.0879767612 0.0055597995 0.0077360000 44948085 955859216 1373700096 -0.0445513204 -0.0836947635 -0.1433482468 2528 1311867254.7794649601 0.0553122051 0.0580759143 0.0879767612 0.0055632494 0.0076970000 44951013 955859216 1373700096 -0.0447961390 -0.0825399086 -0.1468422413 2529 1311867254.8115739822 0.0552030541 0.0580747784 0.0879767612 0.0055627726 0.0076820000 44953885 955859216 1373700096 -0.0453211553 -0.0825528651 -0.1502255052 2530 1311867254.8482780457 0.0549453385 0.0580735414 0.0879767612 0.0055639479 0.0126210000 44956981 955859216 1373700096 -0.0445252433 -0.0819430575 -0.1533091515 2531 1311867254.8794910908 0.0553879216 0.0580724803 0.0879767612 0.0055629498 0.0085500000 44959741 955859216 1373700096 -0.0442503467 -0.0816498101 -0.1563603878 2532 1311867254.9138929844 0.0549155623 0.0580712335 0.0879767612 0.0055627932 0.0083690000 44962669 955859216 1373700096 -0.0451293886 -0.0815227404 -0.1596960723 2533 1311867254.9490759373 0.0550964363 0.0580700591 0.0879767612 0.0055624685 0.0079930000 44965653 955859216 1373700096 -0.0460405834 -0.0814770386 -0.1626809686 2534 1311867254.9819579124 0.0546273999 0.0580687005 0.0879767612 0.0055619784 0.0126440000 44968581 955859216 1373700096 -0.0460605100 -0.0801956877 -0.1654690504 2535 1311867255.0154359341 0.0550437011 0.0580675072 0.0879767612 0.0055630520 0.0085850000 44971453 955859216 1373700096 -0.0461606607 -0.0800959766 -0.1681376547 2536 1311867255.0494379997 0.0554723181 0.0580664839 0.0879767612 0.0055621703 0.0078650000 44974381 955859216 1373700096 -0.0462720357 -0.0800666064 -0.1708360314 2537 1311867255.0822079182 0.0546256192 0.0580651276 0.0879767612 0.0055611283 0.0079120000 44977253 955859216 1373700096 -0.0459757186 -0.0786674842 -0.1732428223 2538 1311867255.1176838875 0.0556887090 0.0580641913 0.0879767612 0.0055600499 0.0077850000 44980125 955859216 1373700096 -0.0457621515 -0.0787241459 -0.1755552888 2539 1311867255.1510150433 0.0554759875 0.0580631719 0.0879767612 0.0055599679 0.0077760000 44982997 955859216 1373700096 -0.0456408523 -0.0788581520 -0.1782414019 2540 1311867255.1838800907 0.0552922636 0.0580620810 0.0879767612 0.0055602147 0.0077580000 44985757 955859216 1373700096 -0.0472817831 -0.0777877718 -0.1809226573 2541 1311867255.2169129848 0.0546364710 0.0580607329 0.0879767612 0.0055603773 0.0076400000 44988629 955859216 1373700096 -0.0475173406 -0.0761069208 -0.1833697259 2542 1311867255.2459371090 0.0546065234 0.0580593740 0.0879767612 0.0055597780 0.0120070000 44991445 955859216 1373700096 -0.0480693690 -0.0758068711 -0.1859868765 2543 1311867255.2793660164 0.0550110415 0.0580581753 0.0879767612 0.0055690931 0.0084900000 44994317 955859216 1373700096 -0.0481716767 -0.0760392696 -0.1884640455 2544 1311867255.3138630390 0.0552389957 0.0580570671 0.0879767612 0.0055691520 0.0079280000 44997245 955859216 1373700096 -0.0485016778 -0.0759304613 -0.1911591589 2545 1311867255.3468410969 0.0554333217 0.0580560362 0.0879767612 0.0055686346 0.0078060000 45000173 955859216 1373700096 -0.0482844897 -0.0761039779 -0.1939933747 2546 1311867255.3794751167 0.0554301143 0.0580550048 0.0879767612 0.0055676197 0.0077660000 45003045 955859216 1373700096 -0.0483965836 -0.0763331577 -0.1970717311 2547 1311867255.4137639999 0.0554705188 0.0580539901 0.0879767612 0.0055706703 0.0077960000 45005973 955859216 1373700096 -0.0490458086 -0.0758703947 -0.2000774294 2548 1311867255.4455530643 0.0550252758 0.0580528014 0.0879767612 0.0055700311 0.0077980000 45008845 955859216 1373700096 -0.0495750308 -0.0754912645 -0.2030905634 2549 1311867255.4794819355 0.0560560673 0.0580520181 0.0879767612 0.0055706044 0.0129680000 45011773 955859216 1373700096 -0.0498697497 -0.0755328014 -0.2058919370 2550 1311867255.5156099796 0.0563860275 0.0580513647 0.0879767612 0.0055717741 0.0087480000 45014757 955859216 1373700096 -0.0492458977 -0.0747673437 -0.2086959779 2551 1311867255.5457780361 0.0553096309 0.0580502900 0.0879767612 0.0055735410 0.0079140000 45017573 955859216 1373700096 -0.0486667193 -0.0743474364 -0.2116980702 2552 1311867255.5794420242 0.0563959815 0.0580496417 0.0879767612 0.0055725168 0.0124550000 45020445 955859216 1373700096 -0.0487837568 -0.0746640116 -0.2146633565 2553 1311867255.6153330803 0.0561003722 0.0580488782 0.0879767612 0.0055733362 0.0129210000 45023429 955859216 1373700096 -0.0491363779 -0.0745324939 -0.2177007347 2554 1311867255.6456480026 0.0555036478 0.0580478816 0.0879767612 0.0055726734 0.0086710000 45026301 955859216 1373700096 -0.0487015024 -0.0732649639 -0.2202204019 2555 1311867255.6801021099 0.0559669919 0.0580470672 0.0879767612 0.0055721412 0.0079110000 45029229 955859216 1373700096 -0.0482162051 -0.0732242242 -0.2229106873 2556 1311867255.7182919979 0.0566450916 0.0580465187 0.0879767612 0.0055735623 0.0079450000 45032269 955859216 1373700096 -0.0489474796 -0.0744888261 -0.2259843946 2557 1311867255.7457749844 0.0559168421 0.0580456858 0.0879767612 0.0055733898 0.0078940000 45035029 955859216 1373700096 -0.0489980467 -0.0736243948 -0.2287510931 2558 1311867255.7810928822 0.0557215177 0.0580447772 0.0879767612 0.0055777082 0.0120250000 45037957 955859216 1373700096 -0.0476082861 -0.0721325278 -0.2315126956 2559 1311867255.8176100254 0.0561661460 0.0580440431 0.0879767612 0.0055823535 0.0085720000 45040941 955859216 1373700096 -0.0481452309 -0.0731782764 -0.2344604433 2560 1311867255.8457250595 0.0558735020 0.0580431952 0.0879767612 0.0055820867 0.0078970000 45043701 955859216 1373700096 -0.0483085923 -0.0738473609 -0.2373570651 2561 1311867255.8793790340 0.0549932830 0.0580420043 0.0879767612 0.0055810349 0.0079210000 45046629 955859216 1373700096 -0.0479483083 -0.0730890557 -0.2402396798 2562 1311867255.9140310287 0.0547322147 0.0580407125 0.0879767612 0.0055800581 0.0079070000 45049613 955859216 1373700096 -0.0470836200 -0.0731271803 -0.2431992143 2563 1311867255.9459080696 0.0547247119 0.0580394187 0.0879767612 0.0055792790 0.0078870000 45052485 955859216 1373700096 -0.0473022610 -0.0744461641 -0.2464261502 2564 1311867255.9794859886 0.0551445261 0.0580382896 0.0879767612 0.0055782302 0.0078570000 45055357 955859216 1373700096 -0.0472484641 -0.0750065967 -0.2493257672 2565 1311867256.0177969933 0.0546690822 0.0580369761 0.0879767612 0.0055771435 0.0078820000 45058453 955859216 1373700096 -0.0473293364 -0.0748521537 -0.2522777021 2566 1311867256.0460140705 0.0542479791 0.0580354995 0.0879767612 0.0055763720 0.0078010000 45061213 955859216 1373700096 -0.0469956882 -0.0754593685 -0.2552022040 2567 1311867256.0856881142 0.0542535149 0.0580340262 0.0879767612 0.0055805017 0.0078530000 45064253 955859216 1373700096 -0.0470415018 -0.0758322626 -0.2581530213 2568 1311867256.1167299747 0.0544536151 0.0580326319 0.0879767612 0.0055812172 0.0078380000 45067125 955859216 1373700096 -0.0474310257 -0.0753628239 -0.2608952522 2569 1311867256.1452269554 0.0535538942 0.0580308885 0.0879767612 0.0055813353 0.0079320000 45069885 955859216 1373700096 -0.0473824143 -0.0748546720 -0.2636928558 2570 1311867256.1795060635 0.0541566759 0.0580293811 0.0879767612 0.0055820130 0.0125200000 45072869 955859216 1373700096 -0.0479855798 -0.0757084563 -0.2667459249 2571 1311867256.2177491188 0.0541853830 0.0580278859 0.0879767612 0.0055827282 0.0086420000 45075909 955859216 1373700096 -0.0472605936 -0.0767093524 -0.2695372105 2572 1311867256.2454690933 0.0537577458 0.0580262257 0.0879767612 0.0055826561 0.0080140000 45078613 955859216 1373700096 -0.0471669659 -0.0772072449 -0.2723903656 2573 1311867256.2847039700 0.0538195707 0.0580245908 0.0879767612 0.0055823477 0.0078960000 45081709 955859216 1373700096 -0.0473107919 -0.0773968250 -0.2757945359 2574 1311867256.3143420219 0.0544048473 0.0580231845 0.0879767612 0.0055841065 0.0080580000 45084469 955859216 1373700096 -0.0491897091 -0.0794716477 -0.2793660164 2575 1311867256.3471789360 0.0534285866 0.0580214002 0.0879767612 0.0055842491 0.0079370000 45087397 955859216 1373700096 -0.0485073514 -0.0793130845 -0.2828853130 2576 1311867256.3848650455 0.0539833605 0.0580198326 0.0879767612 0.0055834518 0.0078450000 45090381 955859216 1373700096 -0.0491180979 -0.0802108571 -0.2864390612 2577 1311867256.4158649445 0.0539286397 0.0580182450 0.0879767612 0.0055825091 0.0128070000 45093197 955859216 1373700096 -0.0503960662 -0.0816333741 -0.2901262343 2578 1311867256.4452838898 0.0535610989 0.0580165161 0.0879767612 0.0055827674 0.0087390000 45096013 955859216 1373700096 -0.0496486574 -0.0821289271 -0.2937343717 2579 1311867256.4844601154 0.0527040437 0.0580144562 0.0879767612 0.0055840313 0.0080450000 45099053 955859216 1373700096 -0.0498894714 -0.0818556175 -0.2976281047 2580 1311867256.5135829449 0.0524454713 0.0580122977 0.0879767612 0.0055837887 0.0081450000 45101925 955859216 1373700096 -0.0498239435 -0.0833947510 -0.3013916612 2581 1311867256.5478789806 0.0509995744 0.0580095806 0.0879767612 0.0056027465 0.0081380000 45104853 955859216 1373700096 -0.0492025018 -0.0841124058 -0.3050733209 2582 1311867256.5836489201 0.0520483479 0.0580072719 0.0879767612 0.0056124346 0.0079910000 45107893 955859216 1373700096 -0.0488883369 -0.0844703093 -0.3084611595 2583 1311867256.6160368919 0.0520875566 0.0580049801 0.0879767612 0.0056113651 0.0081480000 45110709 955859216 1373700096 -0.0491028167 -0.0850386545 -0.3117112219 2584 1311867256.6452310085 0.0518041588 0.0580025804 0.0879767612 0.0056109379 0.0079040000 45113525 955859216 1373700096 -0.0497291796 -0.0858761370 -0.3151087463 2585 1311867256.6832759380 0.0521286130 0.0580003081 0.0879767612 0.0056102350 0.0132490000 45116621 955859216 1373700096 -0.0500203259 -0.0860431045 -0.3184753060 2586 1311867256.7140300274 0.0516642928 0.0579978579 0.0879767612 0.0056110096 0.0088240000 45119381 955859216 1373700096 -0.0499885306 -0.0848544836 -0.3212948143 2587 1311867256.7463369370 0.0513019823 0.0579952697 0.0879767612 0.0056101496 0.0079460000 45122253 955859216 1373700096 -0.0494689383 -0.0851279497 -0.3241524994 2588 1311867256.7827401161 0.0511143617 0.0579926109 0.0879767612 0.0056096465 0.0086080000 45125293 955859216 1373700096 -0.0476599559 -0.0849326253 -0.3271537423 2589 1311867256.8140430450 0.0513019972 0.0579900266 0.0879767612 0.0056100172 0.0082340000 45128109 955859216 1373700096 -0.0474593341 -0.0848490745 -0.3297995329 2590 1311867256.8477399349 0.0527913384 0.0579880194 0.0879767612 0.0056098164 0.0080900000 45131037 955859216 1373700096 -0.0483871587 -0.0874983072 -0.3328908086 2591 1311867256.8838980198 0.0523365252 0.0579858382 0.0879767612 0.0056100663 0.0079380000 45133965 955859216 1373700096 -0.0474772416 -0.0887399539 -0.3363544345 2592 1311867256.9148108959 0.0520738438 0.0579835574 0.0879767612 0.0056093923 0.0079370000 45136837 955859216 1373700096 -0.0467319451 -0.0889052227 -0.3396302760 2593 1311867256.9465379715 0.0520166941 0.0579812562 0.0879767612 0.0056084398 0.0080330000 45139709 955859216 1373700096 -0.0465795621 -0.0890311673 -0.3432476819 2594 1311867256.9814610481 0.0520265475 0.0579789606 0.0879767612 0.0056075251 0.0080100000 45142637 955859216 1373700096 -0.0468533635 -0.0898212045 -0.3469794989 2595 1311867257.0129959583 0.0526380837 0.0579769025 0.0879767612 0.0056072427 0.0080760000 45145565 955859216 1373700096 -0.0474650301 -0.0914531946 -0.3505252898 2596 1311867257.0451910496 0.0527819060 0.0579749013 0.0879767612 0.0056086947 0.0080700000 45148381 955859216 1373700096 -0.0479056202 -0.0915016755 -0.3537651896 2597 1311867257.0841369629 0.0524815805 0.0579727861 0.0879767612 0.0056081409 0.0080930000 45151421 955859216 1373700096 -0.0476709045 -0.0898705274 -0.3569048047 2598 1311867257.1134428978 0.0527524799 0.0579707767 0.0879767612 0.0056070968 0.0080150000 45154293 955859216 1373700096 -0.0474371649 -0.0906192958 -0.3597407639 2599 1311867257.1474308968 0.0528717227 0.0579688148 0.0879767612 0.0056063480 0.0079440000 45157221 955859216 1373700096 -0.0473911986 -0.0903548077 -0.3627744615 2600 1311867257.1821229458 0.0520902053 0.0579665538 0.0879767612 0.0056054066 0.0079890000 45160149 955859216 1373700096 -0.0466480367 -0.0895108059 -0.3662481308 2601 1311867257.2147839069 0.0517357327 0.0579641583 0.0879767612 0.0056086476 0.0079860000 45163021 955859216 1373700096 -0.0466665812 -0.0898455828 -0.3695354760 2602 1311867257.2457039356 0.0530268028 0.0579622607 0.0879767612 0.0056101029 0.0079380000 45165837 955859216 1373700096 -0.0480602346 -0.0906142667 -0.3727967441 2603 1311867257.2824490070 0.0530337356 0.0579603673 0.0879767612 0.0056090944 0.0121320000 45168877 955859216 1373700096 -0.0483838692 -0.0894445032 -0.3759366572 2604 1311867257.3133430481 0.0529618375 0.0579584478 0.0879767612 0.0056082161 0.0086630000 45171693 955859216 1373700096 -0.0480859205 -0.0879721940 -0.3790059686 2605 1311867257.3452849388 0.0531882346 0.0579566166 0.0879767612 0.0056072901 0.0130060000 45174509 955859216 1373700096 -0.0489920191 -0.0881698355 -0.3821218014 2606 1311867257.3839631081 0.0540294647 0.0579551096 0.0879767612 0.0056066416 0.0088510000 45177549 955859216 1373700096 -0.0504932553 -0.0871118382 -0.3849898875 2607 1311867257.4198129177 0.0554763339 0.0579541588 0.0879767612 0.0056094321 0.0082600000 45180533 955859216 1373700096 -0.0515569374 -0.0858720541 -0.3875728250 2608 1311867257.4458611012 0.0554748923 0.0579532082 0.0879767612 0.0056086165 0.0081590000 45183237 955859216 1373700096 -0.0528518930 -0.0850915089 -0.3900170326 2609 1311867257.4851269722 0.0567918867 0.0579527631 0.0879767612 0.0056081902 0.0081620000 45186333 955859216 1373700096 -0.0544860885 -0.0854294300 -0.3927229941 2610 1311867257.5166249275 0.0569117256 0.0579523642 0.0879767612 0.0056081686 0.0080790000 45189205 955859216 1373700096 -0.0546201579 -0.0836399719 -0.3950397074 2611 1311867257.5537879467 0.0573524311 0.0579521344 0.0879767612 0.0056076273 0.0121930000 45192189 955859216 1373700096 -0.0536872558 -0.0831920505 -0.3975740373 2612 1311867257.5836200714 0.0577858165 0.0579520707 0.0879767612 0.0056172807 0.0128210000 45195005 955859216 1373700096 -0.0543655604 -0.0832938552 -0.4002357423 2613 1311867257.6154460907 0.0580805615 0.0579521199 0.0879767612 0.0056230737 0.0131380000 45197821 955859216 1373700096 -0.0547438636 -0.0826206729 -0.4027027488 2614 1311867257.6519720554 0.0583142750 0.0579522585 0.0879767612 0.0056221573 0.0090830000 45200861 955859216 1373700096 -0.0544413477 -0.0817574188 -0.4050730467 2615 1311867257.6842958927 0.0588451177 0.0579525999 0.0879767612 0.0056217407 0.0087380000 45203733 955859216 1373700096 -0.0566467308 -0.0802172124 -0.4076438248 2616 1311867257.7187778950 0.0592893772 0.0579531109 0.0879767612 0.0056207856 0.0084960000 45206717 955859216 1373700096 -0.0560552739 -0.0801108554 -0.4098114967 2617 1311867257.7527809143 0.0598120429 0.0579538212 0.0879767612 0.0056217043 0.0200430000 45209645 955859216 1373700096 -0.0554678254 -0.0804893374 -0.4115721583 2618 1311867257.7838430405 0.0603780299 0.0579547472 0.0879767612 0.0056211427 0.0098440000 45212517 955859216 1373700096 -0.0549950972 -0.0802774578 -0.4131775796 2619 1311867257.8181409836 0.0600992590 0.0579555660 0.0879767612 0.0056206303 0.0083870000 45215445 955859216 1373700096 -0.0539807007 -0.0800938159 -0.4150142670 2620 1311867257.8530700207 0.0609915257 0.0579567248 0.0879767612 0.0056291642 0.0082950000 45218373 955859216 1373700096 -0.0540302508 -0.0794588774 -0.4168973863 2621 1311867257.8854579926 0.0607111976 0.0579577757 0.0879767612 0.0056309141 0.0124910000 45221189 955859216 1373700096 -0.0533581898 -0.0795938894 -0.4187763035 2622 1311867257.9152529240 0.0602134429 0.0579586360 0.0879767612 0.0056315880 0.0088770000 45224005 955859216 1373700096 -0.0513112433 -0.0798035115 -0.4200545847 2623 1311867257.9559030533 0.0608084798 0.0579597225 0.0879767612 0.0056310433 0.0082370000 45227157 955859216 1373700096 -0.0509848446 -0.0803037435 -0.4210638106 2624 1311867257.9850780964 0.0609619021 0.0579608666 0.0879767612 0.0056303471 0.0080790000 45229917 955859216 1373700096 -0.0508011058 -0.0812883750 -0.4226493537 2625 1311867258.0135710239 0.0607494824 0.0579619289 0.0879767612 0.0056295037 0.0080980000 45232733 955859216 1373700096 -0.0498517491 -0.0822170898 -0.4243718386 2626 1311867258.0526609421 0.0608323365 0.0579630220 0.0879767612 0.0056288831 0.0131040000 45235773 955859216 1373700096 -0.0484935865 -0.0834532455 -0.4258749783 2627 1311867258.0836610794 0.0610173866 0.0579641847 0.0879767612 0.0056295812 0.0089860000 45238589 955859216 1373700096 -0.0489428751 -0.0839009061 -0.4272016883 2628 1311867258.1137859821 0.0606431961 0.0579652041 0.0879767612 0.0056289922 0.0082500000 45241461 955859216 1373700096 -0.0480560325 -0.0847441107 -0.4288198650 2629 1311867258.1501069069 0.0609232448 0.0579663293 0.0879767612 0.0056302426 0.0121980000 45244389 955859216 1373700096 -0.0480844676 -0.0845788419 -0.4303972423 2630 1311867258.1848480701 0.0616168752 0.0579677173 0.0879767612 0.0056293562 0.0087600000 45247317 955859216 1373700096 -0.0480098389 -0.0851980448 -0.4314203858 2631 1311867258.2162730694 0.0624114685 0.0579694063 0.0879767612 0.0056283023 0.0130960000 45250245 955859216 1373700096 -0.0488932319 -0.0866006762 -0.4329108894 2632 1311867258.2524979115 0.0617752075 0.0579708523 0.0879767612 0.0056295945 0.0090370000 45253229 955859216 1373700096 -0.0479278527 -0.0867537260 -0.4343526363 2633 1311867258.2857830524 0.0613376498 0.0579721310 0.0879767612 0.0056288170 0.0083000000 45256101 955859216 1373700096 -0.0472900905 -0.0873724148 -0.4353576005 2634 1311867258.3132910728 0.0613140054 0.0579733997 0.0879767612 0.0056279207 0.0124150000 45258917 955859216 1373700096 -0.0463716611 -0.0883399546 -0.4359606206 2635 1311867258.3510708809 0.0614481941 0.0579747184 0.0879767612 0.0056290734 0.0088750000 45261901 955859216 1373700096 -0.0449525416 -0.0889812782 -0.4365389049 2636 1311867258.3812119961 0.0612354428 0.0579759554 0.0879767612 0.0056281984 0.0131030000 45264661 955859216 1373700096 -0.0453677401 -0.0894818828 -0.4375146925 2637 1311867258.4142711163 0.0613932274 0.0579772513 0.0879767612 0.0056272942 0.0090390000 45267533 955859216 1373700096 -0.0459654592 -0.0899055079 -0.4384860396 2638 1311867258.4507009983 0.0608587936 0.0579783436 0.0879767612 0.0056274539 0.0083470000 45270573 955859216 1373700096 -0.0457063429 -0.0896799192 -0.4394748807 2639 1311867258.4826059341 0.0615611114 0.0579797013 0.0879767612 0.0056269330 0.0123320000 45273501 955859216 1373700096 -0.0469269939 -0.0908892676 -0.4403552711 2640 1311867258.5139899254 0.0630431026 0.0579816192 0.0879767612 0.0056270169 0.0088810000 45276317 955859216 1373700096 -0.0474065505 -0.0924447849 -0.4412781894 2641 1311867258.5500509739 0.0619459711 0.0579831203 0.0879767612 0.0056381348 0.0083300000 45279301 955859216 1373700096 -0.0469090790 -0.0932345316 -0.4425927103 2642 1311867258.5836040974 0.0621154308 0.0579846844 0.0879767612 0.0056442987 0.0082440000 45282173 955859216 1373700096 -0.0453444645 -0.0935591906 -0.4438215494 2643 1311867258.6141679287 0.0620443709 0.0579862204 0.0879767612 0.0056447477 0.0082080000 45284989 955859216 1373700096 -0.0456740111 -0.0940055102 -0.4454841018 2644 1311867258.6506860256 0.0625611767 0.0579879507 0.0879767612 0.0056448369 0.0221580000 45287973 955859216 1373700096 -0.0461366586 -0.0940879881 -0.4475138783 2645 1311867258.6856470108 0.0625945255 0.0579896923 0.0879767612 0.0056448564 0.0102490000 45290957 955859216 1373700096 -0.0451704375 -0.0954195932 -0.4494701028 2646 1311867258.7134239674 0.0630205199 0.0579915936 0.0879767612 0.0056439550 0.0083260000 45293661 955859216 1373700096 -0.0449367426 -0.0976804048 -0.4516648054 2647 1311867258.7543559074 0.0639052764 0.0579938277 0.0879767612 0.0056451814 0.0083670000 45296757 955859216 1373700096 -0.0454261303 -0.0975803137 -0.4536532164 2648 1311867258.7843589783 0.0623793900 0.0579954839 0.0879767612 0.0056456275 0.0083050000 45299573 955859216 1373700096 -0.0436786264 -0.0978212059 -0.4551387429 2649 1311867258.8193690777 0.0622398034 0.0579970861 0.0879767612 0.0056448595 0.0133580000 45302557 955859216 1373700096 -0.0430619195 -0.0992828980 -0.4570215344 2650 1311867258.8514409065 0.0621432215 0.0579986507 0.0879767612 0.0056438916 0.0089320000 45305485 955859216 1373700096 -0.0427981243 -0.1001908556 -0.4589573741 2651 1311867258.8846011162 0.0627765208 0.0580004530 0.0879767612 0.0056435010 0.0083920000 45308301 955859216 1373700096 -0.0426869690 -0.1004014984 -0.4604697526 2652 1311867258.9178969860 0.0635814667 0.0580025575 0.0879767612 0.0056424878 0.0082650000 45311229 955859216 1373700096 -0.0431214795 -0.1012019143 -0.4622241557 2653 1311867258.9506199360 0.0634533241 0.0580046120 0.0879767612 0.0056426336 0.0082730000 45314101 955859216 1373700096 -0.0423871316 -0.1021983922 -0.4641032517 2654 1311867258.9841670990 0.0628590956 0.0580064411 0.0879767612 0.0056429233 0.0082070000 45317085 955859216 1373700096 -0.0400716104 -0.1025636494 -0.4661224186 2655 1311867259.0194389820 0.0631136447 0.0580083648 0.0879767612 0.0056420909 0.0133540000 45319957 955859216 1373700096 -0.0389195010 -0.1037537456 -0.4683869779 2656 1311867259.0497961044 0.0640749782 0.0580106489 0.0879767612 0.0056446795 0.0132320000 45322829 955859216 1373700096 -0.0383865833 -0.1053553000 -0.4706507921 2657 1311867259.0845470428 0.0641952455 0.0580129765 0.0879767612 0.0056449282 0.0104740000 45325701 955859216 1373700096 -0.0373102017 -0.1047807261 -0.4729804993 2658 1311867259.1189930439 0.0643893331 0.0580153755 0.0879767612 0.0056444075 0.0084500000 45328685 955859216 1373700096 -0.0366384126 -0.1044599637 -0.4753024876 2659 1311867259.1506030560 0.0645328090 0.0580178266 0.0879767612 0.0056464945 0.0083330000 45331557 955859216 1373700096 -0.0349243097 -0.1055390313 -0.4773024619 2660 1311867259.1837821007 0.0659595355 0.0580208122 0.0879767612 0.0056468416 0.0085000000 45334429 955859216 1373700096 -0.0344153307 -0.1062860265 -0.4792212844 2661 1311867259.2191979885 0.0661974326 0.0580238849 0.0879767612 0.0056457887 0.0084140000 45337469 955859216 1373700096 -0.0323598757 -0.1068403497 -0.4813512266 2662 1311867259.2532899380 0.0667414665 0.0580271597 0.0879767612 0.0056451519 0.0083990000 45340397 955859216 1373700096 -0.0292753261 -0.1078313813 -0.4840050340 2663 1311867259.2815980911 0.0668643042 0.0580304782 0.0879767612 0.0056443934 0.0082990000 45343157 955859216 1373700096 -0.0285063200 -0.1081904918 -0.4863279760 2664 1311867259.3212718964 0.0677022859 0.0580341088 0.0879767612 0.0056448541 0.0083340000 45346253 955859216 1373700096 -0.0269004442 -0.1077484861 -0.4887311459 2665 1311867259.3519039154 0.0667270571 0.0580373707 0.0879767612 0.0056442483 0.0087500000 45349125 955859216 1373700096 -0.0244666114 -0.1076701134 -0.4919330478 2666 1311867259.3840188980 0.0673387274 0.0580408596 0.0879767612 0.0056433382 0.0084110000 45351941 955859216 1373700096 -0.0237051137 -0.1087748036 -0.4951063991 2667 1311867259.4204289913 0.0677687004 0.0580445071 0.0879767612 0.0056443126 0.0132490000 45354925 955859216 1373700096 -0.0235844515 -0.1086877435 -0.4982927442 2668 1311867259.4579179287 0.0677781403 0.0580481553 0.0879767612 0.0056433486 0.0090740000 45357965 955859216 1373700096 -0.0222396776 -0.1077497452 -0.5011073351 2669 1311867259.4850549698 0.0673156455 0.0580516276 0.0879767612 0.0056444433 0.0083790000 45360613 955859216 1373700096 -0.0207510777 -0.1089852452 -0.5036820173 2670 1311867259.5189819336 0.0671942681 0.0580550518 0.0879767612 0.0056436150 0.0084150000 45363541 955859216 1373700096 -0.0184192732 -0.1105838418 -0.5065655708 2671 1311867259.5505928993 0.0673214197 0.0580585211 0.0879767612 0.0056428765 0.0082010000 45366413 955859216 1373700096 -0.0171609931 -0.1115504205 -0.5096790195 2672 1311867259.5823240280 0.0669140965 0.0580618353 0.0879767612 0.0056423947 0.0132780000 45369341 955859216 1373700096 -0.0147155775 -0.1124844924 -0.5124976039 2673 1311867259.6192719936 0.0660493970 0.0580648235 0.0879767612 0.0056428132 0.0091250000 45372269 955859216 1373700096 -0.0068043596 -0.1138171330 -0.5142484903 2674 1311867259.6494839191 0.0650348812 0.0580674301 0.0879767612 0.0056420940 0.0086230000 45375029 955859216 1373700096 -0.0062587499 -0.1130917072 -0.5177574754 2675 1311867259.6828589439 0.0645721629 0.0580698618 0.0879767612 0.0056429860 0.0084380000 45377957 955859216 1373700096 -0.0055656554 -0.1119313911 -0.5211098790 2676 1311867259.7201991081 0.0627855286 0.0580716240 0.0879767612 0.0056420455 0.0084120000 45380997 955859216 1373700096 -0.0032342577 -0.1093888879 -0.5242069364 2677 1311867259.7557690144 0.0642070994 0.0580739159 0.0879767612 0.0056415055 0.0222460000 45383981 955859216 1373700096 -0.0046245544 -0.1119059175 -0.5267759562 2678 1311867259.7817859650 0.0647338107 0.0580764028 0.0879767612 0.0056405776 0.0102620000 45386685 955859216 1373700096 -0.0060085836 -0.1120705530 -0.5292552114 2679 1311867259.8177011013 0.0625210628 0.0580780619 0.0879767612 0.0056398307 0.0084530000 45389669 955859216 1373700096 -0.0012108710 -0.1101090387 -0.5314840078 2680 1311867259.8548939228 0.0646685660 0.0580805210 0.0879767612 0.0056396235 0.0083670000 45392653 955859216 1373700096 -0.0030028392 -0.1115621999 -0.5337908268 2681 1311867259.8818409443 0.0632010996 0.0580824310 0.0879767612 0.0056389831 0.0083320000 45395413 955859216 1373700096 0.0004697446 -0.1110596284 -0.5357375741 2682 1311867259.9219179153 0.0641549975 0.0580846952 0.0879767612 0.0056383485 0.0081810000 45398509 955859216 1373700096 -0.0009171928 -0.1109108403 -0.5383782387 2683 1311867259.9520130157 0.0622333586 0.0580862415 0.0879767612 0.0056374837 0.0082450000 45401325 955859216 1373700096 0.0031960024 -0.1086949483 -0.5407258272 2684 1311867259.9923639297 0.0642318279 0.0580885312 0.0879767612 0.0056375095 0.0081200000 45404421 955859216 1373700096 0.0032913852 -0.1107554287 -0.5426256657 2685 1311867260.0219469070 0.0650850162 0.0580911369 0.0879767612 0.0056370973 0.0081240000 45407181 955859216 1373700096 0.0028991890 -0.1106687039 -0.5446145535 2686 1311867260.0493209362 0.0631754175 0.0580930298 0.0879767612 0.0056370125 0.0081210000 45409885 955859216 1373700096 0.0084853321 -0.1086054072 -0.5464351773 2687 1311867260.0888080597 0.0647913739 0.0580955227 0.0879767612 0.0056366880 0.0083000000 45412981 955859216 1373700096 0.0086246626 -0.1097336411 -0.5488758087 2688 1311867260.1210498810 0.0647655800 0.0580980041 0.0879767612 0.0056377622 0.0084300000 45415853 955859216 1373700096 0.0127203977 -0.1088579670 -0.5512878895 2689 1311867260.1513869762 0.0652240962 0.0581006542 0.0879767612 0.0056388424 0.0082910000 45418669 955859216 1373700096 0.0125321262 -0.1092587635 -0.5540053248 2690 1311867260.1908860207 0.0665454492 0.0581037935 0.0879767612 0.0056380895 0.0141370000 45421709 955859216 1373700096 0.0149100237 -0.1091597229 -0.5565741658 2691 1311867260.2204439640 0.0664785802 0.0581069057 0.0879767612 0.0056374815 0.0133770000 45424525 955859216 1373700096 0.0139215980 -0.1085214987 -0.5599635839 2692 1311867260.2496669292 0.0671767369 0.0581102749 0.0879767612 0.0056367788 0.0092310000 45427397 955859216 1373700096 0.0133539820 -0.1083414182 -0.5630315542 2693 1311867260.2869880199 0.0675002933 0.0581137617 0.0879767612 0.0056367495 0.0086000000 45430381 955859216 1373700096 0.0141851706 -0.1069551259 -0.5661451817 2694 1311867260.3195590973 0.0672492832 0.0581171528 0.0879767612 0.0056360569 0.0084700000 45433253 955859216 1373700096 0.0149079347 -0.1063417122 -0.5692437291 2695 1311867260.3505260944 0.0677522495 0.0581207279 0.0879767612 0.0056365087 0.0085450000 45436125 955859216 1373700096 0.0147895031 -0.1064120904 -0.5723134279 2696 1311867260.3868899345 0.0685051158 0.0581245797 0.0879767612 0.0056397486 0.0131770000 45439109 955859216 1373700096 0.0129303243 -0.1043599173 -0.5753266215 2697 1311867260.4211299419 0.0680107772 0.0581282453 0.0879767612 0.0056388844 0.0134840000 45441981 955859216 1373700096 0.0140333781 -0.1030846015 -0.5783030391 2698 1311867260.4521770477 0.0664460286 0.0581313283 0.0879767612 0.0056379581 0.0092970000 45444797 955859216 1373700096 0.0184918027 -0.1010424569 -0.5806884170 2699 1311867260.4867470264 0.0682007074 0.0581350591 0.0879767612 0.0056396418 0.0085060000 45447725 955859216 1373700096 0.0151425591 -0.1024458930 -0.5838003159 2700 1311867260.5192930698 0.0678643212 0.0581386625 0.0879767612 0.0056414754 0.0086460000 45450485 955859216 1373700096 0.0176702142 -0.1009668633 -0.5861262679 2701 1311867260.5527870655 0.0664061084 0.0581417234 0.0879767612 0.0056408941 0.0086350000 45453469 955859216 1373700096 0.0191733278 -0.0970437080 -0.5889139771 2702 1311867260.5880448818 0.0687276796 0.0581456412 0.0879767612 0.0056404820 0.0084570000 45456453 955859216 1373700096 0.0178234335 -0.0993878990 -0.5917212367 2703 1311867260.6196188927 0.0682338104 0.0581493734 0.0879767612 0.0056399974 0.0084920000 45459325 955859216 1373700096 0.0199920814 -0.0997966155 -0.5945925117 2704 1311867260.6493411064 0.0680611581 0.0581530390 0.0879767612 0.0056392170 0.0084760000 45462085 955859216 1373700096 0.0217562988 -0.1005503237 -0.5973137021 2705 1311867260.6865339279 0.0699062422 0.0581573840 0.0879767612 0.0056400970 0.0085360000 45465125 955859216 1373700096 0.0221479833 -0.1017822400 -0.5997837782 2706 1311867260.7188229561 0.0694984794 0.0581615751 0.0879767612 0.0056403858 0.0083980000 45467997 955859216 1373700096 0.0231631789 -0.1025847197 -0.6030459404 2707 1311867260.7493369579 0.0691952482 0.0581656511 0.0879767612 0.0056422519 0.0135530000 45470757 955859216 1373700096 0.0235209074 -0.1023378596 -0.6055510640 2708 1311867260.7859649658 0.0692198724 0.0581697331 0.0879767612 0.0056441406 0.0092390000 45473797 955859216 1373700096 0.0266123619 -0.1041166037 -0.6079012156 2709 1311867260.8179080486 0.0697927400 0.0581740236 0.0879767612 0.0056462119 0.0086100000 45476725 955859216 1373700096 0.0250940900 -0.1046596915 -0.6117210984 2710 1311867260.8514599800 0.0690315366 0.0581780301 0.0879767612 0.0056508097 0.0085240000 45479597 955859216 1373700096 0.0274692718 -0.1053174734 -0.6148137450 2711 1311867260.8867430687 0.0699415803 0.0581823693 0.0879767612 0.0056506515 0.0083770000 45482469 955859216 1373700096 0.0260935389 -0.1063854024 -0.6184927821 2712 1311867260.9177849293 0.0699347705 0.0581867028 0.0879767612 0.0056500904 0.0084780000 45485341 955859216 1373700096 0.0265374612 -0.1067121550 -0.6212437153 2713 1311867260.9494459629 0.0688706934 0.0581906409 0.0879767612 0.0056624716 0.0134920000 45488213 955859216 1373700096 0.0256238170 -0.1071498469 -0.6245543361 2714 1311867260.9869680405 0.0708641484 0.0581953105 0.0879767612 0.0056729284 0.0093800000 45491253 955859216 1373700096 0.0258212052 -0.1083612517 -0.6281336546 2715 1311867261.0202260017 0.0717200413 0.0582002920 0.0879767612 0.0056733370 0.0087000000 45494125 955859216 1373700096 0.0241397191 -0.1093261316 -0.6313737631 2716 1311867261.0519640446 0.0717217624 0.0582052705 0.0879767612 0.0056737345 0.0086590000 45496997 955859216 1373700096 0.0237569753 -0.1107371524 -0.6343649626 2717 1311867261.0871579647 0.0720687807 0.0582103730 0.0879767612 0.0056731512 0.0084700000 45499981 955859216 1373700096 0.0271603689 -0.1134434789 -0.6369619966 2718 1311867261.1197659969 0.0731657520 0.0582158753 0.0879767612 0.0056732400 0.0126800000 45502853 955859216 1373700096 0.0235844944 -0.1157542765 -0.6404288411 2719 1311867261.1530790329 0.0729193389 0.0582212830 0.0879767612 0.0056744757 0.0212050000 45505781 955859216 1373700096 0.0226938669 -0.1161036640 -0.6434885263 2720 1311867261.1872630119 0.0731171593 0.0582267594 0.0879767612 0.0056765477 0.0100950000 45508709 955859216 1373700096 0.0227777939 -0.1177940667 -0.6467505097 2721 1311867261.2191090584 0.0739080235 0.0582325225 0.0879767612 0.0056820572 0.0089470000 45511581 955859216 1373700096 0.0216739364 -0.1204778627 -0.6495246291 2722 1311867261.2548229694 0.0751225427 0.0582387275 0.0879767612 0.0056817887 0.0086410000 45514509 955859216 1373700096 0.0195212550 -0.1212602258 -0.6527214050 2723 1311867261.2879600525 0.0747789815 0.0582448017 0.0879767612 0.0056812925 0.0085590000 45517493 955859216 1373700096 0.0207363237 -0.1218003258 -0.6552088857 2724 1311867261.3185029030 0.0756184086 0.0582511797 0.0879767612 0.0056859695 0.0084920000 45520365 955859216 1373700096 0.0192058552 -0.1222686395 -0.6575325131 2725 1311867261.3546299934 0.0759651735 0.0582576803 0.0879767612 0.0056861471 0.0084350000 45523293 955859216 1373700096 0.0158541892 -0.1213960722 -0.6603047252 2726 1311867261.3858330250 0.0755256787 0.0582640148 0.0879767612 0.0056851651 0.0083790000 45526109 955859216 1373700096 0.0150870811 -0.1208355650 -0.6623961329 2727 1311867261.4186379910 0.0751002282 0.0582701887 0.0879767612 0.0056844383 0.0084190000 45528981 955859216 1373700096 0.0162317082 -0.1216990948 -0.6639984250 2728 1311867261.4558680058 0.0749876127 0.0582763168 0.0879767612 0.0056851262 0.0084370000 45532021 955859216 1373700096 0.0140440119 -0.1225041747 -0.6658845544 2729 1311867261.4862189293 0.0760435686 0.0582828273 0.0879767612 0.0056870260 0.0082920000 45534837 955859216 1373700096 0.0138395578 -0.1231282353 -0.6675597429 2730 1311867261.5178630352 0.0759905651 0.0582893137 0.0879767612 0.0056866503 0.0083360000 45537765 955859216 1373700096 0.0121899461 -0.1228342950 -0.6690462828 2731 1311867261.5556519032 0.0753534809 0.0582955620 0.0879767612 0.0056856781 0.0127320000 45540749 955859216 1373700096 0.0136273960 -0.1222538799 -0.6702604890 2732 1311867261.5857899189 0.0772280246 0.0583024919 0.0879767612 0.0056879197 0.0089350000 45543565 955859216 1373700096 0.0112113347 -0.1236345097 -0.6718510985 2733 1311867261.6174640656 0.0774746910 0.0583095070 0.0879767612 0.0056875473 0.0084290000 45546493 955859216 1373700096 0.0105079720 -0.1224794537 -0.6735665202 2734 1311867261.6652009487 0.0784783363 0.0583168840 0.0879767612 0.0056876985 0.0136480000 45549757 955859216 1373700096 0.0087823700 -0.1220620349 -0.6761987805 2735 1311867261.6889929771 0.0784330219 0.0583242391 0.0879767612 0.0056868580 0.0136510000 45552405 955859216 1373700096 0.0084412517 -0.1222491190 -0.6790250540 2736 1311867261.7193109989 0.0803160965 0.0583322771 0.0879767612 0.0056876917 0.0136980000 45555165 955859216 1373700096 0.0014057045 -0.1203146875 -0.6828193069 2737 1311867261.7601549625 0.0808378682 0.0583404998 0.0879767612 0.0056902777 0.0091730000 45558205 955859216 1373700096 0.0021322344 -0.1192776114 -0.6857840419 2738 1311867261.7876880169 0.0806041881 0.0583486312 0.0879767612 0.0056917351 0.0136960000 45560965 955859216 1373700096 -0.0000656381 -0.1175304502 -0.6891576052 2739 1311867261.8213939667 0.0801961720 0.0583566076 0.0879767612 0.0056965741 0.0101290000 45563893 955859216 1373700096 0.0005401361 -0.1161874011 -0.6925480962 2740 1311867261.8598148823 0.0817641988 0.0583651505 0.0879767612 0.0056964742 0.0090070000 45566877 955859216 1373700096 -0.0013397816 -0.1154438406 -0.6954811215 2741 1311867261.8885459900 0.0802869052 0.0583731483 0.0879767612 0.0057007705 0.0136400000 45569693 955859216 1373700096 0.0010007719 -0.1140084714 -0.6976435781 2742 1311867261.9212360382 0.0802963302 0.0583811436 0.0879767612 0.0057043715 0.0093430000 45572565 955859216 1373700096 0.0017813133 -0.1132880375 -0.7009285092 2743 1311867261.9592299461 0.0807756707 0.0583893078 0.0879767612 0.0057034459 0.0088100000 45575661 955859216 1373700096 0.0009480547 -0.1116552949 -0.7041185498 2744 1311867261.9886140823 0.0785636753 0.0583966600 0.0879767612 0.0057033182 0.0088460000 45578421 955859216 1373700096 0.0056455568 -0.1089600921 -0.7064969540 2745 1311867262.0219531059 0.0793596283 0.0584042968 0.0879767612 0.0057031100 0.0231210000 45581349 955859216 1373700096 0.0060465974 -0.1096896231 -0.7091819644 2746 1311867262.0576629639 0.0805172026 0.0584123496 0.0879767612 0.0057022716 0.0105180000 45584333 955859216 1373700096 0.0046225032 -0.1087874472 -0.7124413848 2747 1311867262.0944681168 0.0812467486 0.0584206620 0.0879767612 0.0057013002 0.0087060000 45587261 955859216 1373700096 0.0059756138 -0.1081977487 -0.7151176929 2748 1311867262.1180479527 0.0803188682 0.0584286308 0.0879767612 0.0057004134 0.0128390000 45589909 955859216 1373700096 0.0062162746 -0.1068009287 -0.7181162834 2749 1311867262.1539878845 0.0811486691 0.0584368957 0.0879767612 0.0057009813 0.0089940000 45592893 955859216 1373700096 0.0068635358 -0.1068673581 -0.7212956548 2750 1311867262.1906540394 0.0814210847 0.0584452535 0.0879767612 0.0057000540 0.0086990000 45595821 955859216 1373700096 0.0077424739 -0.1057391614 -0.7250577807 2751 1311867262.2200620174 0.0823411793 0.0584539398 0.0879767612 0.0056994828 0.0084570000 45598693 955859216 1373700096 0.0058734473 -0.1046710759 -0.7286651134 2752 1311867262.2557590008 0.0824506581 0.0584626596 0.0879767612 0.0056986340 0.0139360000 45601621 955859216 1373700096 0.0090986695 -0.1039956138 -0.7314579487 2753 1311867262.2893559933 0.0843264014 0.0584720543 0.0879767612 0.0057002941 0.0092520000 45604549 955859216 1373700096 0.0042469124 -0.1026715040 -0.7356211543 2754 1311867262.3192830086 0.0852143392 0.0584817646 0.0879767612 0.0056993135 0.0137660000 45607421 955859216 1373700096 0.0020880378 -0.1018876210 -0.7401745915 2755 1311867262.3543510437 0.0863715559 0.0584918880 0.0879767612 0.0057031605 0.0093370000 45610349 955859216 1373700096 0.0028527568 -0.1005426049 -0.7442236543 2756 1311867262.3862760067 0.0852917731 0.0585016122 0.0879767612 0.0057022444 0.0135730000 45613165 955859216 1373700096 0.0040721167 -0.0987588167 -0.7486276031 2757 1311867262.4192481041 0.0870759264 0.0585119765 0.0879767612 0.0057015073 0.0092000000 45616093 955859216 1373700096 -0.0003408963 -0.0972602591 -0.7539915442 2758 1311867262.4579370022 0.0886625797 0.0585229085 0.0886625797 0.0057013188 0.0085380000 45619133 955859216 1373700096 -0.0012977562 -0.0951254368 -0.7584005594 2759 1311867262.4882910252 0.0887149274 0.0585338516 0.0887149274 0.0057041297 0.0084390000 45622005 955859216 1373700096 -0.0043648076 -0.0932490006 -0.7638183832 2760 1311867262.5228719711 0.0901738331 0.0585453154 0.0901738331 0.0057034212 0.0084140000 45624933 955859216 1373700096 -0.0067693582 -0.0924808457 -0.7689827085 2761 1311867262.5554070473 0.0920626521 0.0585574549 0.0920626521 0.0057035701 0.0083080000 45627805 955859216 1373700096 -0.0111834984 -0.0898537263 -0.7738536596 2762 1311867262.5873200893 0.0922925249 0.0585696689 0.0922925249 0.0057141165 0.0087000000 45630733 955859216 1373700096 -0.0111202663 -0.0885856450 -0.7782595158 2763 1311867262.6235508919 0.0938098356 0.0585824233 0.0938098356 0.0057163341 0.0091730000 45633717 955859216 1373700096 -0.0130203329 -0.0876003504 -0.7820594311 2764 1311867262.6548008919 0.0927820876 0.0585947965 0.0938098356 0.0057159758 0.0086840000 45636533 955859216 1373700096 -0.0116933379 -0.0871285871 -0.7858716249 2765 1311867262.6901140213 0.0942333415 0.0586076857 0.0942333415 0.0057178762 0.0088580000 45639461 955859216 1373700096 -0.0140219480 -0.0855721310 -0.7896016836 2766 1311867262.7234799862 0.0913426429 0.0586195204 0.0942333415 0.0057174391 0.0087760000 45642389 955859216 1373700096 -0.0082440646 -0.0860169306 -0.7930697799 2767 1311867262.7550880909 0.0904099867 0.0586310096 0.0942333415 0.0057236215 0.0087000000 45645261 955859216 1373700096 -0.0066173151 -0.0863744766 -0.7963363528 2768 1311867262.7890789509 0.0922305211 0.0586431481 0.0942333415 0.0057252805 0.0087270000 45648133 955859216 1373700096 -0.0083741527 -0.0861114636 -0.7997431159 2769 1311867262.8232269287 0.0951497406 0.0586563322 0.0951497406 0.0057264987 0.0085140000 45651173 955859216 1373700096 -0.0093438337 -0.0862053558 -0.8020340204 2770 1311867262.8561139107 0.0956666991 0.0586696933 0.0956666991 0.0057275273 0.0137100000 45653989 955859216 1373700096 -0.0108695766 -0.0858716369 -0.8052087426 2771 1311867262.8878281116 0.0965338126 0.0586833577 0.0965338126 0.0057274026 0.0138330000 45656861 955859216 1373700096 -0.0100471424 -0.0870017186 -0.8077939153 2772 1311867262.9221930504 0.0959752053 0.0586968108 0.0965338126 0.0057281057 0.0094780000 45659845 955859216 1373700096 -0.0078694215 -0.0865317136 -0.8100686073 2773 1311867262.9539968967 0.0981555507 0.0587110404 0.0981555507 0.0057295203 0.0090420000 45662717 955859216 1373700096 -0.0083033666 -0.0869655237 -0.8120943308 2774 1311867262.9877319336 0.0979373381 0.0587251811 0.0981555507 0.0057311764 0.0087400000 45665645 955859216 1373700096 -0.0080640595 -0.0866044089 -0.8144164085 2775 1311867263.0238440037 0.0992023349 0.0587397675 0.0992023349 0.0057303713 0.0086050000 45668629 955859216 1373700096 -0.0081394985 -0.0870023370 -0.8169337511 2776 1311867263.0552799702 0.1004756168 0.0587548020 0.1004756168 0.0057294873 0.0231360000 45671445 955859216 1373700096 -0.0090081245 -0.0876035392 -0.8191966414 2777 1311867263.0870039463 0.1004197001 0.0587698056 0.1004756168 0.0057285272 0.0105300000 45674317 955859216 1373700096 -0.0077259918 -0.0870406851 -0.8213831186 2778 1311867263.1226899624 0.1004646197 0.0587848145 0.1004756168 0.0057277985 0.0089000000 45677301 955859216 1373700096 -0.0075598261 -0.0865113735 -0.8239420056 2779 1311867263.1537079811 0.1004150212 0.0587997948 0.1004756168 0.0057310287 0.0087220000 45680117 955859216 1373700096 -0.0078514572 -0.0859244987 -0.8265785575 2780 1311867263.1884229183 0.0997218713 0.0588145149 0.1004756168 0.0057303566 0.0089090000 45683045 955859216 1373700096 -0.0076403259 -0.0845111385 -0.8288604617 2781 1311867263.2225809097 0.0984999612 0.0588287851 0.1004756168 0.0057295831 0.0088120000 45686029 955859216 1373700096 -0.0060241297 -0.0843287930 -0.8312112689 2782 1311867263.2536139488 0.0985426158 0.0588430604 0.1004756168 0.0057296106 0.0087350000 45688845 955859216 1373700096 -0.0067728469 -0.0850653425 -0.8339552879 2783 1311867263.2884469032 0.0982537717 0.0588572217 0.1004756168 0.0057289009 0.0086970000 45691773 955859216 1373700096 -0.0062769055 -0.0851380825 -0.8362997174 2784 1311867263.3236269951 0.0986759886 0.0588715244 0.1004756168 0.0057497488 0.0086120000 45694757 955859216 1373700096 -0.0069886954 -0.0847223327 -0.8385960460 2785 1311867263.3539469242 0.0970620066 0.0588852373 0.1004756168 0.0057511028 0.0087560000 45697573 955859216 1373700096 -0.0035846182 -0.0857139900 -0.8404342532 2786 1311867263.3856530190 0.0988835543 0.0588995942 0.1004756168 0.0057501794 0.0085290000 45700445 955859216 1373700096 -0.0072189225 -0.0855082944 -0.8431773782 2787 1311867263.4221460819 0.1004523784 0.0589145037 0.1004756168 0.0057497312 0.0085680000 45703429 955859216 1373700096 -0.0104124518 -0.0836880878 -0.8458076119 2788 1311867263.4549560547 0.1010870561 0.0589296302 0.1010870561 0.0057490342 0.0084660000 45706245 955859216 1373700096 -0.0094574578 -0.0841375515 -0.8481214643 2789 1311867263.4876389503 0.0999810696 0.0589443492 0.1010870561 0.0057491553 0.0084920000 45709229 955859216 1373700096 -0.0060104490 -0.0848499909 -0.8503546119 2790 1311867263.5235950947 0.0998396426 0.0589590070 0.1010870561 0.0057525385 0.0085540000 45712269 955859216 1373700096 -0.0063184421 -0.0841821507 -0.8532976508 2791 1311867263.5535099506 0.1006373242 0.0589739401 0.1010870561 0.0057525554 0.0086680000 45715029 955859216 1373700096 -0.0050511896 -0.0852697119 -0.8561352491 2792 1311867263.5855040550 0.1005450115 0.0589888295 0.1010870561 0.0057520244 0.0136780000 45717845 955859216 1373700096 -0.0033542418 -0.0856032819 -0.8585331440 2793 1311867263.6236140728 0.1003031880 0.0590036216 0.1010870561 0.0057542216 0.0092310000 45720941 955859216 1373700096 -0.0001359396 -0.0852128714 -0.8615581393 2794 1311867263.6543920040 0.1010486633 0.0590186699 0.1010870561 0.0057540058 0.0089500000 45723701 955859216 1373700096 0.0000343383 -0.0856142938 -0.8646128774 2795 1311867263.6903779507 0.1018495262 0.0590339940 0.1018495262 0.0057531216 0.0091090000 45726741 955859216 1373700096 0.0013134402 -0.0857263431 -0.8675888181 2796 1311867263.7227630615 0.1012175754 0.0590490811 0.1018495262 0.0057546072 0.0090860000 45729613 955859216 1373700096 0.0037356375 -0.0849290118 -0.8709286451 2797 1311867263.7559669018 0.1003905162 0.0590638618 0.1018495262 0.0057544657 0.0090520000 45732485 955859216 1373700096 0.0056625158 -0.0844725668 -0.8746797442 2798 1311867263.7911560535 0.1011999100 0.0590789211 0.1018495262 0.0057554577 0.0091190000 45735413 955859216 1373700096 0.0065332544 -0.0837559402 -0.8780707121 2799 1311867263.8235189915 0.1014873981 0.0590940724 0.1018495262 0.0057545626 0.0091570000 45738341 955859216 1373700096 0.0077458518 -0.0837944821 -0.8814372420 2800 1311867263.8555519581 0.0994521230 0.0591084860 0.1018495262 0.0057542441 0.0091050000 45741157 955859216 1373700096 0.0131543363 -0.0830031484 -0.8838356733 2801 1311867263.8925390244 0.1026022732 0.0591240140 0.1026022732 0.0057534216 0.0084700000 45744197 955859216 1373700096 0.0096276505 -0.0831388682 -0.8874931335 2802 1311867263.9255890846 0.1016549990 0.0591391928 0.1026022732 0.0057527304 0.0138920000 45747069 955859216 1373700096 0.0133447479 -0.0828398466 -0.8897885680 2803 1311867263.9557209015 0.1016995609 0.0591543766 0.1026022732 0.0057519274 0.0240800000 45749885 955859216 1373700096 0.0144019704 -0.0826747417 -0.8926175237 2804 1311867263.9913449287 0.1016844064 0.0591695442 0.1026022732 0.0057513878 0.0110860000 45752869 955859216 1373700096 0.0160494410 -0.0823510140 -0.8950638175 2805 1311867264.0265080929 0.1037786379 0.0591854477 0.1037786379 0.0057507167 0.0089510000 45755853 955859216 1373700096 0.0150602935 -0.0834242925 -0.8977165818 2806 1311867264.0539839268 0.1034657508 0.0592012282 0.1037786379 0.0057501619 0.0088330000 45758613 955859216 1373700096 0.0168667454 -0.0834890455 -0.8997246623 2807 1311867264.0935840607 0.1048888788 0.0592175046 0.1048888788 0.0057492052 0.0087060000 45761709 955859216 1373700096 0.0175375845 -0.0836352110 -0.9014695287 2808 1311867264.1232929230 0.1053558365 0.0592339356 0.1053558365 0.0057484966 0.0229530000 45764525 955859216 1373700096 0.0171869826 -0.0828821436 -0.9038518667 2809 1311867264.1547811031 0.1040396765 0.0592498864 0.1053558365 0.0057490459 0.0107870000 45767285 955859216 1373700096 0.0201478079 -0.0827133805 -0.9057006836 2810 1311867264.1908740997 0.1033251882 0.0592655715 0.1053558365 0.0057494056 0.0090000000 45770269 955859216 1373700096 0.0242189076 -0.0822621807 -0.9081519246 2811 1311867264.2230439186 0.1040851176 0.0592815159 0.1053558365 0.0057509212 0.0088940000 45773197 955859216 1373700096 0.0219189972 -0.0821360499 -0.9115617871 2812 1311867264.2549281120 0.1033367291 0.0592971827 0.1053558365 0.0057527818 0.0088130000 45776013 955859216 1373700096 0.0239026807 -0.0808715448 -0.9137189984 2813 1311867264.2910940647 0.1026755869 0.0593126034 0.1053558365 0.0057587671 0.0087300000 45778997 955859216 1373700096 0.0266018454 -0.0795750767 -0.9165520072 2814 1311867264.3223540783 0.1032057181 0.0593282016 0.1053558365 0.0057620094 0.0130410000 45781869 955859216 1373700096 0.0284208097 -0.0797856152 -0.9194307327 2815 1311867264.3539710045 0.1020068377 0.0593433627 0.1053558365 0.0057668734 0.0091460000 45784685 955859216 1373700096 0.0283468626 -0.0792507157 -0.9220464826 2816 1311867264.3903570175 0.1015562713 0.0593583531 0.1053558365 0.0057689565 0.0087320000 45787669 955859216 1373700096 0.0313732848 -0.0787614733 -0.9241904020 2817 1311867264.4247128963 0.1004710123 0.0593729476 0.1053558365 0.0057739995 0.0087750000 45790653 955859216 1373700096 0.0330361128 -0.0797105059 -0.9272149205 2818 1311867264.4536709785 0.0993867442 0.0593871469 0.1053558365 0.0057748041 0.0088120000 45793413 955859216 1373700096 0.0343057923 -0.0791705549 -0.9295068383 2819 1311867264.4911220074 0.0977319553 0.0594007492 0.1053558365 0.0057742262 0.0142430000 45796453 955859216 1373700096 0.0381433815 -0.0786115453 -0.9314458370 2820 1311867264.5220930576 0.0966939256 0.0594139737 0.1053558365 0.0057740422 0.0093970000 45799269 955859216 1373700096 0.0393977650 -0.0780779421 -0.9340876937 2821 1311867264.5544660091 0.0963922292 0.0594270819 0.1053558365 0.0057745147 0.0088410000 45802141 955859216 1373700096 0.0423162468 -0.0782693028 -0.9355662465 2822 1311867264.5919189453 0.0945905298 0.0594395424 0.1053558365 0.0057761090 0.0141760000 45805181 955859216 1373700096 0.0456462316 -0.0771345496 -0.9376024008 2823 1311867264.6239540577 0.0943404362 0.0594519055 0.1053558365 0.0057775593 0.0094540000 45808053 955859216 1373700096 0.0483988263 -0.0783164799 -0.9393120408 2824 1311867264.6537890434 0.0944332406 0.0594642926 0.1053558365 0.0057776745 0.0137680000 45810925 955859216 1373700096 0.0505578890 -0.0794872493 -0.9408982992 2825 1311867264.6908979416 0.0943070799 0.0594766263 0.1053558365 0.0057769023 0.0094170000 45813853 955859216 1373700096 0.0521066226 -0.0797471404 -0.9427651763 2826 1311867264.7228040695 0.0943143144 0.0594889539 0.1053558365 0.0057775536 0.0087740000 45816781 955859216 1373700096 0.0541524626 -0.0810569152 -0.9441237450 2827 1311867264.7547140121 0.0949282199 0.0595014899 0.1053558365 0.0057771278 0.0087780000 45819597 955859216 1373700096 0.0557083338 -0.0820517316 -0.9452235103 2828 1311867264.7909140587 0.0942666680 0.0595137831 0.1053558365 0.0057766400 0.0086860000 45822581 955859216 1373700096 0.0587777421 -0.0821014643 -0.9463860393 2829 1311867264.8233439922 0.0935282782 0.0595258066 0.1053558365 0.0057768656 0.0145300000 45825509 955859216 1373700096 0.0618454739 -0.0828427523 -0.9480050802 2830 1311867264.8540790081 0.0928170308 0.0595375703 0.1053558365 0.0057762366 0.0094480000 45828325 955859216 1373700096 0.0621816963 -0.0825204104 -0.9497070909 2831 1311867264.8904409409 0.0929473415 0.0595493717 0.1053558365 0.0057752862 0.0089220000 45831309 955859216 1373700096 0.0615230724 -0.0821445361 -0.9511729479 2832 1311867264.9235579967 0.0930517465 0.0595612016 0.1053558365 0.0057744951 0.0088770000 45834237 955859216 1373700096 0.0623576343 -0.0812888592 -0.9516427517 2833 1311867264.9598839283 0.0945222378 0.0595735423 0.1053558365 0.0057735888 0.0145870000 45837221 955859216 1373700096 0.0588591285 -0.0816997513 -0.9533215761 2834 1311867264.9916839600 0.0932506621 0.0595854255 0.1053558365 0.0057727670 0.0140920000 45840093 955859216 1373700096 0.0597912371 -0.0801444799 -0.9542574883 2835 1311867265.0220029354 0.0936604068 0.0595974449 0.1053558365 0.0057718517 0.0096220000 45842909 955859216 1373700096 0.0594438724 -0.0802641213 -0.9552921653 2836 1311867265.0581490993 0.0954972878 0.0596101035 0.1053558365 0.0057712474 0.0137870000 45845893 955859216 1373700096 0.0561496653 -0.0808924139 -0.9562937021 2837 1311867265.0911719799 0.0953971893 0.0596227179 0.1053558365 0.0057706115 0.0096260000 45848709 955859216 1373700096 0.0592669584 -0.0812890530 -0.9570652246 2838 1311867265.1217110157 0.0958409980 0.0596354799 0.1053558365 0.0057707357 0.0091430000 45851525 955859216 1373700096 0.0587209873 -0.0807313174 -0.9581565261 2839 1311867265.1582090855 0.0965835899 0.0596484943 0.1053558365 0.0057699029 0.0090740000 45854509 955859216 1373700096 0.0568818450 -0.0799502581 -0.9599351287 2840 1311867265.1899518967 0.0972715691 0.0596617419 0.1053558365 0.0057697046 0.0088950000 45857325 955859216 1373700096 0.0550466068 -0.0803970248 -0.9615111351 2841 1311867265.2225220203 0.0983575210 0.0596753624 0.1053558365 0.0057700622 0.0089060000 45860253 955859216 1373700096 0.0517344140 -0.0798903853 -0.9629866481 2842 1311867265.2581849098 0.1010138541 0.0596899079 0.1053558365 0.0057740164 0.0260710000 45863125 955859216 1373700096 0.0464218706 -0.0793872327 -0.9653526545 2843 1311867265.2915129662 0.1022566482 0.0597048804 0.1053558365 0.0057750009 0.0119930000 45866053 955859216 1373700096 0.0443093032 -0.0782743767 -0.9666355252 2844 1311867265.3220860958 0.1032002643 0.0597201741 0.1053558365 0.0057746475 0.0237270000 45868925 955859216 1373700096 0.0402060784 -0.0781075507 -0.9689660668 2845 1311867265.3585588932 0.1033917964 0.0597355245 0.1053558365 0.0057738127 0.0107420000 45871909 955859216 1373700096 0.0416787863 -0.0782223791 -0.9703397751 2846 1311867265.3912470341 0.1041689366 0.0597511370 0.1053558365 0.0057733520 0.0089990000 45874781 955859216 1373700096 0.0394141003 -0.0773279443 -0.9719905257 2847 1311867265.4244530201 0.1050615907 0.0597670522 0.1053558365 0.0057729292 0.0089240000 45877765 955859216 1373700096 0.0390814580 -0.0789853856 -0.9740973115 2848 1311867265.4604411125 0.1064291224 0.0597834363 0.1064291224 0.0057728391 0.0088710000 45880637 955859216 1373700096 0.0363814309 -0.0782068893 -0.9759619236 2849 1311867265.4902420044 0.1046332568 0.0597991786 0.1064291224 0.0057719921 0.0129970000 45883509 955859216 1373700096 0.0388117656 -0.0776049197 -0.9779477715 2850 1311867265.5230569839 0.1049221978 0.0598150113 0.1064291224 0.0057712614 0.0095250000 45886437 955859216 1373700096 0.0385438278 -0.0778976902 -0.9800013900 2851 1311867265.5594520569 0.1077981219 0.0598318416 0.1077981219 0.0057705995 0.0092540000 45889365 955859216 1373700096 0.0343061052 -0.0785731524 -0.9820600748 2852 1311867265.5932300091 0.1071050838 0.0598484170 0.1077981219 0.0057699273 0.0091690000 45892349 955859216 1373700096 0.0356906205 -0.0782258809 -0.9838024974 2853 1311867265.6250700951 0.1070926413 0.0598649765 0.1077981219 0.0057690723 0.0088140000 45895109 955859216 1373700096 0.0341823921 -0.0767267123 -0.9859157801 2854 1311867265.6610729694 0.1085020676 0.0598820182 0.1085020676 0.0057685728 0.0087280000 45898093 955859216 1373700096 0.0329396836 -0.0767598897 -0.9877388477 2855 1311867265.6956009865 0.1086786985 0.0598991099 0.1086786985 0.0057678180 0.0088000000 45901021 955859216 1373700096 0.0326000303 -0.0756819174 -0.9892413020 2856 1311867265.7221889496 0.1084077582 0.0599160947 0.1086786985 0.0057669145 0.0087290000 45903781 955859216 1373700096 0.0315716751 -0.0740060881 -0.9907580018 2857 1311867265.7626268864 0.1072148159 0.0599326501 0.1086786985 0.0057672737 0.0257200000 45906877 955859216 1373700096 0.0352140032 -0.0746512413 -0.9918860197 2858 1311867265.7925920486 0.1082633510 0.0599495608 0.1086786985 0.0057667608 0.0118310000 45909693 955859216 1373700096 0.0348436870 -0.0757145286 -0.9927959442 2859 1311867265.8224210739 0.1094973832 0.0599668913 0.1094973832 0.0057659284 0.0091650000 45912509 955859216 1373700096 0.0312276892 -0.0737916231 -0.9939645529 2860 1311867265.8593389988 0.1090391800 0.0599840494 0.1094973832 0.0057650699 0.0089290000 45915493 955859216 1373700096 0.0334048867 -0.0737045333 -0.9940857291 2861 1311867265.8943600655 0.1095359847 0.0600013692 0.1095359847 0.0057640946 0.0088540000 45918421 955859216 1373700096 0.0322267152 -0.0731418356 -0.9954504371 2862 1311867265.9256451130 0.1081986427 0.0600182096 0.1095359847 0.0057634239 0.0087750000 45921293 955859216 1373700096 0.0356785990 -0.0728995502 -0.9957635403 2863 1311867265.9620978832 0.1079113334 0.0600349379 0.1095359847 0.0057630110 0.0087380000 45924277 955859216 1373700096 0.0360982157 -0.0726961195 -0.9972216487 2864 1311867265.9908990860 0.1094445437 0.0600521899 0.1095359847 0.0057644000 0.0088450000 45927037 955859216 1373700096 0.0336371809 -0.0724391341 -0.9988110662 2865 1311867266.0233469009 0.1103390306 0.0600697420 0.1103390306 0.0057634601 0.0089150000 45929965 955859216 1373700096 0.0327094644 -0.0726345778 -1.0000214577 2866 1311867266.0634260178 0.1107713953 0.0600874327 0.1107713953 0.0057627037 0.0087500000 45933061 955859216 1373700096 0.0319155119 -0.0721358210 -1.0016615391 2867 1311867266.0954639912 0.1118762493 0.0601054965 0.1118762493 0.0057619119 0.0087660000 45935877 955859216 1373700096 0.0304241665 -0.0723977387 -1.0031554699 2868 1311867266.1241600513 0.1100476161 0.0601229101 0.1118762493 0.0057611948 0.0086870000 45938693 955859216 1373700096 0.0340645537 -0.0719442666 -1.0043141842 2869 1311867266.1634809971 0.1108020395 0.0601405745 0.1118762493 0.0057612720 0.0144220000 45941789 955859216 1373700096 0.0335113592 -0.0726503432 -1.0054769516 2870 1311867266.1922690868 0.1110779196 0.0601583227 0.1118762493 0.0057604575 0.0097700000 45944549 955859216 1373700096 0.0327981301 -0.0725786388 -1.0063823462 2871 1311867266.2255198956 0.1115410626 0.0601762198 0.1118762493 0.0057597700 0.0097260000 45947477 955859216 1373700096 0.0319961831 -0.0726411715 -1.0076398849 2872 1311867266.2597849369 0.1106301993 0.0601937874 0.1118762493 0.0057587897 0.0091840000 45950349 955859216 1373700096 0.0336224176 -0.0721375719 -1.0089389086 2873 1311867266.2915120125 0.1117419451 0.0602117296 0.1118762493 0.0057578045 0.0090280000 45953221 955859216 1373700096 0.0328297652 -0.0726695955 -1.0096323490 2874 1311867266.3258039951 0.1122856736 0.0602298486 0.1122856736 0.0057569980 0.0088600000 45956093 955859216 1373700096 0.0300260354 -0.0716954321 -1.0118166208 2875 1311867266.3601551056 0.1120667011 0.0602478788 0.1122856736 0.0057561589 0.0088020000 45959021 955859216 1373700096 0.0297191348 -0.0710144192 -1.0134377480 2876 1311867266.3913159370 0.1124579981 0.0602660325 0.1124579981 0.0057552414 0.0088630000 45961893 955859216 1373700096 0.0288413670 -0.0713202283 -1.0149350166 2877 1311867266.4254870415 0.1129193678 0.0602843340 0.1129193678 0.0057554793 0.0087710000 45964821 955859216 1373700096 0.0272960942 -0.0709975660 -1.0159877539 2878 1311867266.4612910748 0.1130104139 0.0603026544 0.1130104139 0.0057546933 0.0088320000 45967805 955859216 1373700096 0.0272044800 -0.0715764165 -1.0171650648 2879 1311867266.4912600517 0.1119525433 0.0603205946 0.1130104139 0.0057537943 0.0088790000 45970565 955859216 1373700096 0.0288410503 -0.0719166771 -1.0184285641 2880 1311867266.5284929276 0.1125408411 0.0603387267 0.1130104139 0.0057529118 0.0088530000 45973661 955859216 1373700096 0.0280093495 -0.0727493539 -1.0199806690 2881 1311867266.5587360859 0.1135077849 0.0603571817 0.1135077849 0.0057525322 0.0087920000 45976421 955859216 1373700096 0.0248500593 -0.0719817430 -1.0213875771 2882 1311867266.5906820297 0.1158300862 0.0603764298 0.1158300862 0.0057517614 0.0087840000 45979293 955859216 1373700096 0.0222818553 -0.0743058175 -1.0227285624 2883 1311867266.6256470680 0.1154262125 0.0603955244 0.1158300862 0.0057515688 0.0088450000 45982221 955859216 1373700096 0.0228699204 -0.0750774145 -1.0245351791 2884 1311867266.6596419811 0.1155461073 0.0604146474 0.1158300862 0.0057507853 0.0090710000 45985149 955859216 1373700096 0.0236322228 -0.0758162662 -1.0246180296 2885 1311867266.6914939880 0.1155713722 0.0604337658 0.1158300862 0.0057498638 0.0089440000 45988021 955859216 1373700096 0.0230015684 -0.0760171860 -1.0251835585 2886 1311867266.7260789871 0.1180711985 0.0604537372 0.1180711985 0.0057489239 0.0142190000 45990949 955859216 1373700096 0.0192252193 -0.0774110928 -1.0259782076 2887 1311867266.7576239109 0.1174698249 0.0604734864 0.1180711985 0.0057481482 0.0094350000 45993877 955859216 1373700096 0.0179909430 -0.0756044611 -1.0267013311 2888 1311867266.7898240089 0.1155933961 0.0604925723 0.1180711985 0.0057482451 0.0136350000 45996749 955859216 1373700096 0.0209997073 -0.0766495690 -1.0270543098 2889 1311867266.8257129192 0.1168340966 0.0605120744 0.1180711985 0.0057482921 0.0095900000 45999733 955859216 1373700096 0.0191089138 -0.0771897435 -1.0270971060 2890 1311867266.8575000763 0.1175811514 0.0605318215 0.1180711985 0.0057473770 0.0091070000 46002605 955859216 1373700096 0.0176433995 -0.0770824850 -1.0265030861 2891 1311867266.8898739815 0.1174783632 0.0605515193 0.1180711985 0.0057466281 0.0090440000 46005477 955859216 1373700096 0.0193375591 -0.0788155794 -1.0253336430 2892 1311867266.9266190529 0.1171695665 0.0605710968 0.1180711985 0.0057459306 0.0142270000 46008461 955859216 1373700096 0.0189260617 -0.0789296702 -1.0246955156 2893 1311867266.9576549530 0.1168937832 0.0605905654 0.1180711985 0.0057451656 0.0096630000 46011333 955859216 1373700096 0.0208275188 -0.0801050439 -1.0225487947 2894 1311867266.9920771122 0.1111337021 0.0606080302 0.1180711985 0.0057469464 0.0093060000 46014261 955859216 1373700096 0.0219888967 -0.0708768070 -1.0219510794 2895 1311867267.0259480476 0.1139752567 0.0606264645 0.1180711985 0.0057480554 0.0091190000 46017133 955859216 1373700096 0.0212052427 -0.0773243010 -1.0211638212 2896 1311867267.0603609085 0.1079059318 0.0606427903 0.1180711985 0.0057472520 0.0102970000 46020005 955859216 1373700096 0.0257288497 -0.0713437870 -1.0201812983 2897 1311867267.0929799080 0.1110816523 0.0606602010 0.1180711985 0.0057466514 0.0093450000 46022765 955859216 1373700096 0.0239178911 -0.0766122341 -1.0195515156 2898 1311867267.1266899109 0.1127012745 0.0606781586 0.1180711985 0.0057505010 0.0142210000 46025637 955859216 1373700096 0.0212567784 -0.0769669265 -1.0189341307 2899 1311867267.1586909294 0.1120306775 0.0606958724 0.1180711985 0.0057503794 0.0096470000 46028565 955859216 1373700096 0.0213414021 -0.0773484856 -1.0179609060 2900 1311867267.1916129589 0.1124780178 0.0607137284 0.1180711985 0.0057500660 0.0138910000 46031437 955859216 1373700096 0.0213966854 -0.0793512091 -1.0173588991 2901 1311867267.2262039185 0.1132397875 0.0607318345 0.1180711985 0.0057495132 0.0097330000 46034309 955859216 1373700096 0.0191667117 -0.0789489523 -1.0166239738 2902 1311867267.2587449551 0.1128653586 0.0607497992 0.1180711985 0.0057488268 0.0092300000 46037181 955859216 1373700096 0.0190476663 -0.0789248869 -1.0160959959 2903 1311867267.2920761108 0.1135989949 0.0607680043 0.1180711985 0.0057485066 0.0144050000 46040109 955859216 1373700096 0.0176538620 -0.0797500834 -1.0154882669 2904 1311867267.3265810013 0.1120999008 0.0607856805 0.1180711985 0.0057478854 0.0098490000 46043093 955859216 1373700096 0.0197862275 -0.0798228085 -1.0143475533 2905 1311867267.3609950542 0.1120091379 0.0608033134 0.1180711985 0.0057472173 0.0092040000 46045965 955859216 1373700096 0.0198970810 -0.0801742449 -1.0131385326 2906 1311867267.3945980072 0.1111231744 0.0608206292 0.1180711985 0.0057463955 0.0244020000 46048837 955859216 1373700096 0.0224790946 -0.0814366937 -1.0118927956 2907 1311867267.4286189079 0.1145040542 0.0608390962 0.1180711985 0.0057463257 0.0109930000 46051821 955859216 1373700096 0.0164554566 -0.0821915716 -1.0114618540 2908 1311867267.4595789909 0.1144326329 0.0608575259 0.1180711985 0.0057455538 0.0092280000 46054637 955859216 1373700096 0.0162499882 -0.0818881616 -1.0104403496 2909 1311867267.4935429096 0.1123106033 0.0608752134 0.1180711985 0.0057447508 0.0089690000 46057565 955859216 1373700096 0.0182551555 -0.0813756883 -1.0098625422 2910 1311867267.5264101028 0.1115473434 0.0608926265 0.1180711985 0.0057441289 0.0090130000 46060437 955859216 1373700096 0.0199790560 -0.0815937668 -1.0084854364 2911 1311867267.5577969551 0.1131801084 0.0609105886 0.1180711985 0.0057466377 0.0093080000 46063365 955859216 1373700096 0.0177771002 -0.0814496353 -1.0073809624 2912 1311867267.5954480171 0.1121995375 0.0609282015 0.1180711985 0.0057490348 0.0090910000 46066349 955859216 1373700096 0.0196542833 -0.0827318355 -1.0054224730 2913 1311867267.6272020340 0.1110206470 0.0609453977 0.1180711985 0.0057489235 0.0090000000 46069221 955859216 1373700096 0.0229641683 -0.0840559453 -1.0036453009 2914 1311867267.6608970165 0.1111809388 0.0609626371 0.1180711985 0.0057481889 0.0133820000 46072093 955859216 1373700096 0.0216063634 -0.0843545720 -1.0028866529 2915 1311867267.6955730915 0.1109929755 0.0609798001 0.1180711985 0.0057474297 0.0133830000 46075077 955859216 1373700096 0.0212029796 -0.0838982537 -1.0013381243 2916 1311867267.7264549732 0.1102334857 0.0609966910 0.1180711985 0.0057558991 0.0134670000 46077893 955859216 1373700096 0.0227220785 -0.0839198455 -0.9998387098 2917 1311867267.7624979019 0.1111423820 0.0610138818 0.1180711985 0.0057612179 0.0133970000 46080933 955859216 1373700096 0.0194473881 -0.0841313750 -0.9987933636 2918 1311867267.7957980633 0.1099786758 0.0610306621 0.1180711985 0.0057603790 0.0135500000 46083805 955859216 1373700096 0.0208909810 -0.0840174183 -0.9968627691 2919 1311867267.8323969841 0.1096820086 0.0610473292 0.1180711985 0.0057597911 0.0133950000 46086845 955859216 1373700096 0.0215700865 -0.0850987732 -0.9953041077 2920 1311867267.8601078987 0.1087848395 0.0610636777 0.1180711985 0.0057589595 0.0134570000 46089549 955859216 1373700096 0.0211302079 -0.0847281814 -0.9943166971 2921 1311867267.8989579678 0.1067100316 0.0610793046 0.1180711985 0.0057622485 0.0135250000 46092645 955859216 1373700096 0.0218792129 -0.0849711895 -0.9931900501 2922 1311867267.9282948971 0.1074911579 0.0610951882 0.1180711985 0.0057614106 0.0095730000 46095405 955859216 1373700096 0.0203407127 -0.0844691023 -0.9911007285 2923 1311867267.9643011093 0.1072774604 0.0611109878 0.1180711985 0.0057617701 0.0232540000 46098389 955859216 1373700096 0.0202535596 -0.0848668441 -0.9892841578 2924 1311867267.9947459698 0.1065231115 0.0611265187 0.1180711985 0.0057608585 0.0110830000 46101261 955859216 1373700096 0.0216940586 -0.0856974348 -0.9879507422 2925 1311867268.0287120342 0.1078445986 0.0611424907 0.1180711985 0.0057602697 0.0145460000 46104133 955859216 1373700096 0.0172151774 -0.0852599069 -0.9866890311 2926 1311867268.0588328838 0.1071227044 0.0611582050 0.1180711985 0.0057597461 0.0097930000 46107005 955859216 1373700096 0.0189254843 -0.0858060494 -0.9842632413 2927 1311867268.0946080685 0.1066016033 0.0611737306 0.1180711985 0.0057598302 0.0093340000 46109989 955859216 1373700096 0.0202728510 -0.0882540196 -0.9823042750 2928 1311867268.1253910065 0.1065463647 0.0611892267 0.1180711985 0.0057596061 0.0092000000 46112805 955859216 1373700096 0.0207175445 -0.0893137231 -0.9798812866 2929 1311867268.1606659889 0.1078426689 0.0612051548 0.1180711985 0.0057621183 0.0090390000 46115733 955859216 1373700096 0.0182340033 -0.0896806642 -0.9772970080 2930 1311867268.1981959343 0.1071953699 0.0612208512 0.1180711985 0.0057612920 0.0090980000 46118773 955859216 1373700096 0.0187342260 -0.0908210352 -0.9750449061 2931 1311867268.2290298939 0.1081199273 0.0612368522 0.1180711985 0.0057603934 0.0089820000 46121645 955859216 1373700096 0.0171944201 -0.0920291245 -0.9727933407 2932 1311867268.2579200268 0.1072153077 0.0612525338 0.1180711985 0.0057603100 0.0090560000 46124405 955859216 1373700096 0.0170074273 -0.0917192549 -0.9704433084 2933 1311867268.2951550484 0.1086279079 0.0612686863 0.1180711985 0.0057611615 0.0090610000 46127389 955859216 1373700096 0.0165329874 -0.0941327512 -0.9669447541 2934 1311867268.3274168968 0.1083731949 0.0612847410 0.1180711985 0.0057615254 0.0144810000 46130261 955859216 1373700096 0.0156379305 -0.0946570113 -0.9646673799 2935 1311867268.3586890697 0.1088240519 0.0613009384 0.1180711985 0.0057617829 0.0097130000 46133189 955859216 1373700096 0.0135891465 -0.0941139385 -0.9624301195 2936 1311867268.3934800625 0.1083539501 0.0613169647 0.1180711985 0.0057613493 0.0138200000 46136117 955859216 1373700096 0.0133602871 -0.0955764651 -0.9600265026 2937 1311867268.4261479378 0.1082810760 0.0613329552 0.1180711985 0.0057604351 0.0097610000 46138989 955859216 1373700096 0.0120317759 -0.0960657448 -0.9580895305 2938 1311867268.4581170082 0.1077414900 0.0613487511 0.1180711985 0.0057607073 0.0093820000 46141861 955859216 1373700096 0.0120324390 -0.0961286202 -0.9554423094 2939 1311867268.4943540096 0.1080875769 0.0613646541 0.1180711985 0.0057598785 0.0142160000 46144845 955859216 1373700096 0.0118696643 -0.0979569629 -0.9524995089 2940 1311867268.5280330181 0.1091900170 0.0613809212 0.1180711985 0.0057591237 0.0098570000 46147773 955859216 1373700096 0.0092492187 -0.0993399173 -0.9501443505 2941 1311867268.5616149902 0.1076216102 0.0613966440 0.1180711985 0.0057595000 0.0094300000 46150701 955859216 1373700096 0.0082308585 -0.0980762318 -0.9479435682 2942 1311867268.5949339867 0.1069093868 0.0614121140 0.1180711985 0.0057601718 0.0093550000 46153573 955859216 1373700096 0.0078482097 -0.0977324620 -0.9458147287 2943 1311867268.6294579506 0.1062282026 0.0614273420 0.1180711985 0.0057643383 0.0094500000 46156557 955859216 1373700096 0.0075182994 -0.0988089591 -0.9439330697 2944 1311867268.6639370918 0.1064234748 0.0614426260 0.1180711985 0.0057658162 0.0092810000 46159541 955859216 1373700096 0.0051793782 -0.0985419452 -0.9413798451 2945 1311867268.6937808990 0.1058588773 0.0614577080 0.1180711985 0.0057657717 0.0091580000 46162301 955859216 1373700096 0.0044961777 -0.0989191756 -0.9394061565 2946 1311867268.7282569408 0.1058164164 0.0614727652 0.1180711985 0.0057648484 0.0135990000 46165229 955859216 1373700096 0.0019542710 -0.0987362638 -0.9375964999 2947 1311867268.7629311085 0.1061047986 0.0614879101 0.1180711985 0.0057651794 0.0226020000 46168213 955859216 1373700096 0.0004137435 -0.0985314175 -0.9348914027 2948 1311867268.7951219082 0.1052704230 0.0615027617 0.1180711985 0.0057644030 0.0108690000 46171029 955859216 1373700096 0.0025358158 -0.0996884778 -0.9325063825 2949 1311867268.8264629841 0.1041908264 0.0615172372 0.1180711985 0.0057641623 0.0094530000 46173901 955859216 1373700096 0.0032928090 -0.1002326980 -0.9295836687 2950 1311867268.8615820408 0.1056536213 0.0615321987 0.1180711985 0.0057643054 0.0095540000 46176829 955859216 1373700096 0.0001431152 -0.1013919264 -0.9269250035 2951 1311867268.8947710991 0.1044147089 0.0615467302 0.1180711985 0.0057708387 0.0094930000 46179701 955859216 1373700096 -0.0008106210 -0.1013978422 -0.9237989187 2952 1311867268.9271900654 0.1054546982 0.0615616041 0.1180711985 0.0057784080 0.0093600000 46182629 955859216 1373700096 -0.0029003811 -0.1017087772 -0.9204923511 2953 1311867268.9633738995 0.1043644771 0.0615760988 0.1180711985 0.0057778276 0.0093060000 46185669 955859216 1373700096 -0.0027478568 -0.1023118496 -0.9171755910 2954 1311867268.9942259789 0.1050013751 0.0615907993 0.1180711985 0.0057779655 0.0092950000 46188429 955859216 1373700096 -0.0048173103 -0.1027575731 -0.9141185284 2955 1311867269.0293419361 0.1055060923 0.0616056607 0.1180711985 0.0057779735 0.0092340000 46191469 955859216 1373700096 -0.0054394859 -0.1043744385 -0.9102209210 2956 1311867269.0628340244 0.1047930047 0.0616202708 0.1180711985 0.0057772008 0.0091250000 46194397 955859216 1373700096 -0.0064269542 -0.1039144322 -0.9071370363 2957 1311867269.0942130089 0.1050273106 0.0616349502 0.1180711985 0.0057762730 0.0091800000 46197101 955859216 1373700096 -0.0087415231 -0.1046068296 -0.9042333961 2958 1311867269.1263980865 0.1055135280 0.0616497840 0.1180711985 0.0057753706 0.0091750000 46199973 955859216 1373700096 -0.0104349395 -0.1053199843 -0.9011381269 2959 1311867269.1618270874 0.1040147617 0.0616641014 0.1180711985 0.0057744316 0.0092220000 46202901 955859216 1373700096 -0.0105341710 -0.1051280424 -0.8982921839 2960 1311867269.1941618919 0.1033791974 0.0616781943 0.1180711985 0.0057746602 0.0091450000 46205773 955859216 1373700096 -0.0105066346 -0.1067271382 -0.8952510357 2961 1311867269.2266249657 0.1040872931 0.0616925169 0.1180711985 0.0057778966 0.0092510000 46208645 955859216 1373700096 -0.0136594139 -0.1058737785 -0.8924841881 2962 1311867269.2623720169 0.1019933149 0.0617061228 0.1180711985 0.0057781903 0.0136020000 46211629 955859216 1373700096 -0.0131419208 -0.1053962708 -0.8897317052 2963 1311867269.2948200703 0.1019149646 0.0617196931 0.1180711985 0.0058092406 0.0101260000 46214557 955859216 1373700096 -0.0149094090 -0.1067993417 -0.8866946101 2964 1311867269.3261830807 0.1018569469 0.0617332347 0.1180711985 0.0058159962 0.0096050000 46217373 955859216 1373700096 -0.0168550685 -0.1065488532 -0.8838142157 2965 1311867269.3641560078 0.0976241976 0.0617453396 0.1180711985 0.0058187035 0.0096430000 46220413 955859216 1373700096 -0.0175556988 -0.0994986594 -0.8810924888 2966 1311867269.3967740536 0.1006588712 0.0617584595 0.1180711985 0.0058207087 0.0094950000 46223285 955859216 1373700096 -0.0202407297 -0.1047771573 -0.8773458600 2967 1311867269.4275820255 0.1015749127 0.0617718792 0.1180711985 0.0058222097 0.0094230000 46226157 955859216 1373700096 -0.0207360983 -0.1062475145 -0.8743501902 2968 1311867269.4626441002 0.1028038040 0.0617857040 0.1180711985 0.0058215303 0.0095030000 46229085 955859216 1373700096 -0.0215354618 -0.1073008403 -0.8714364171 2969 1311867269.4938280582 0.0968552679 0.0617975159 0.1180711985 0.0058407791 0.0096410000 46231901 955859216 1373700096 -0.0199284889 -0.0981885940 -0.8682219386 2970 1311867269.5278589725 0.0994526446 0.0618101944 0.1180711985 0.0058633338 0.0095070000 46234885 955859216 1373700096 -0.0207406338 -0.1033360288 -0.8646212816 2971 1311867269.5634589195 0.1004612222 0.0618232038 0.1180711985 0.0058628081 0.0094880000 46237869 955859216 1373700096 -0.0221559852 -0.1054525003 -0.8615496159 2972 1311867269.5962390900 0.0958997905 0.0618346697 0.1180711985 0.0058629474 0.0095800000 46240741 955859216 1373700096 -0.0203043595 -0.0988664553 -0.8587819338 2973 1311867269.6306080818 0.0979536772 0.0618468187 0.1180711985 0.0058622989 0.0094280000 46243669 955859216 1373700096 -0.0224152617 -0.1026265025 -0.8563610315 2974 1311867269.6631560326 0.0975463837 0.0618588226 0.1180711985 0.0058613874 0.0094610000 46246597 955859216 1373700096 -0.0215551425 -0.1032685339 -0.8532692790 2975 1311867269.6964600086 0.0920801759 0.0618689811 0.1180711985 0.0058672057 0.0096320000 46249413 955859216 1373700096 -0.0182713419 -0.0964925811 -0.8504569530 2976 1311867269.7280869484 0.0955919400 0.0618803127 0.1180711985 0.0058675771 0.0094290000 46252341 955859216 1373700096 -0.0222566575 -0.1017742380 -0.8489304781 2977 1311867269.7622261047 0.0970913619 0.0618921404 0.1180711985 0.0058671012 0.0096270000 46255269 955859216 1373700096 -0.0247363634 -0.1031167209 -0.8462814093 2978 1311867269.7974090576 0.0955595076 0.0619034458 0.1180711985 0.0058663486 0.0096420000 46258197 955859216 1373700096 -0.0228523538 -0.1038766950 -0.8443475366 2979 1311867269.8295869827 0.0952550173 0.0619146413 0.1180711985 0.0058797034 0.0096120000 46261069 955859216 1373700096 -0.0231978912 -0.1045159176 -0.8420026302 2980 1311867269.8676230907 0.0959422588 0.0619260600 0.1180711985 0.0058794670 0.0095260000 46264053 955859216 1373700096 -0.0269297697 -0.1052221954 -0.8403414488 2981 1311867269.8953619003 0.0956884772 0.0619373858 0.1180711985 0.0058787170 0.0096270000 46266813 955859216 1373700096 -0.0266036689 -0.1055782139 -0.8386579752 2982 1311867269.9344720840 0.0948966965 0.0619484386 0.1180711985 0.0058778491 0.0094320000 46269853 955859216 1373700096 -0.0255281106 -0.1059468687 -0.8360544443 2983 1311867269.9627900124 0.0954779014 0.0619596788 0.1180711985 0.0058828579 0.0137630000 46272669 955859216 1373700096 -0.0265032798 -0.1067307442 -0.8345602155 2984 1311867269.9987258911 0.0953200907 0.0619708585 0.1180711985 0.0058821334 0.0229500000 46275653 955859216 1373700096 -0.0262689404 -0.1076251864 -0.8325455189 2985 1311867270.0306990147 0.0953629762 0.0619820452 0.1180711985 0.0058823739 0.0112090000 46278469 955859216 1373700096 -0.0269196443 -0.1084463596 -0.8303421140 2986 1311867270.0660951138 0.0958757326 0.0619933960 0.1180711985 0.0058815264 0.0096710000 46281453 955859216 1373700096 -0.0277940352 -0.1091736034 -0.8277908564 2987 1311867270.0948200226 0.0962483585 0.0620048641 0.1180711985 0.0058808162 0.0096050000 46284157 955859216 1373700096 -0.0297961403 -0.1089823842 -0.8256549835 2988 1311867270.1336340904 0.0960178748 0.0620162473 0.1180711985 0.0058798319 0.0094310000 46287309 955859216 1373700096 -0.0301278960 -0.1097027361 -0.8228338361 2989 1311867270.1624090672 0.0964903757 0.0620277809 0.1180711985 0.0058789870 0.0093970000 46290069 955859216 1373700096 -0.0308734979 -0.1100183800 -0.8202252984 2990 1311867270.1943540573 0.0918387398 0.0620377512 0.1180711985 0.0058785254 0.0095020000 46292941 955859216 1373700096 -0.0246011876 -0.1067364439 -0.8168970942 2991 1311867270.2323369980 0.0925992504 0.0620479690 0.1180711985 0.0058807218 0.0138440000 46295981 955859216 1373700096 -0.0259281099 -0.1099546179 -0.8149214983 2992 1311867270.2655749321 0.0931374133 0.0620583598 0.1180711985 0.0058818576 0.0098490000 46298853 955859216 1373700096 -0.0254249815 -0.1119117737 -0.8120020032 2993 1311867270.2960460186 0.0937999189 0.0620689651 0.1180711985 0.0058809990 0.0094900000 46301669 955859216 1373700096 -0.0270694755 -0.1123611629 -0.8093932867 2994 1311867270.3346099854 0.0942257568 0.0620797055 0.1180711985 0.0058806966 0.0095280000 46304765 955859216 1373700096 -0.0285671484 -0.1136513203 -0.8065463901 2995 1311867270.3624660969 0.0936832502 0.0620902576 0.1180711985 0.0058802167 0.0095150000 46307525 955859216 1373700096 -0.0282371286 -0.1139171273 -0.8041713834 2996 1311867270.3957469463 0.0930719972 0.0621005986 0.1180711985 0.0058809470 0.0094380000 46310397 955859216 1373700096 -0.0282894447 -0.1139574051 -0.8013414145 2997 1311867270.4334359169 0.0920692086 0.0621105982 0.1180711985 0.0058870823 0.0094440000 46313493 955859216 1373700096 -0.0266978685 -0.1143868789 -0.7977467179 2998 1311867270.4641909599 0.0934165418 0.0621210405 0.1180711985 0.0058865460 0.0094660000 46316365 955859216 1373700096 -0.0290800519 -0.1159663051 -0.7951504588 2999 1311867270.4954609871 0.0931129232 0.0621313745 0.1180711985 0.0058864574 0.0093580000 46319125 955859216 1373700096 -0.0279941149 -0.1173876897 -0.7920248508 3000 1311867270.5331869125 0.0918974355 0.0621412965 0.1180711985 0.0058857450 0.0094260000 46322221 955859216 1373700096 -0.0276458338 -0.1175448820 -0.7892765999 3001 1311867270.5629880428 0.0925970376 0.0621514451 0.1180711985 0.0058850310 0.0094160000 46325037 955859216 1373700096 -0.0272386912 -0.1194728836 -0.7863830924 3002 1311867270.5944859982 0.0920628682 0.0621614089 0.1180711985 0.0058840669 0.0093820000 46327797 955859216 1373700096 -0.0272590071 -0.1206824556 -0.7843132615 3003 1311867270.6312110424 0.0925168768 0.0621715173 0.1180711985 0.0058840432 0.0094420000 46330781 955859216 1373700096 -0.0270885341 -0.1213670671 -0.7814311981 3004 1311867270.6644439697 0.0925889686 0.0621816429 0.1180711985 0.0058851474 0.0095670000 46333653 955859216 1373700096 -0.0256927125 -0.1223451644 -0.7790772915 3005 1311867270.6950180531 0.0922153518 0.0621916375 0.1180711985 0.0058846263 0.0147390000 46336469 955859216 1373700096 -0.0280159116 -0.1226863861 -0.7775678039 3006 1311867270.7318449020 0.0923368335 0.0622016659 0.1180711985 0.0058841266 0.0103640000 46339509 955859216 1373700096 -0.0273588877 -0.1235020012 -0.7750862837 3007 1311867270.7623898983 0.0918745697 0.0622115338 0.1180711985 0.0058834372 0.0098140000 46342325 955859216 1373700096 -0.0254840292 -0.1242625415 -0.7727311850 3008 1311867270.7960500717 0.0931970626 0.0622218348 0.1180711985 0.0058829264 0.0097460000 46345253 955859216 1373700096 -0.0278243441 -0.1251398176 -0.7710030079 3009 1311867270.8322730064 0.0926965848 0.0622319627 0.1180711985 0.0058853556 0.0096870000 46348237 955859216 1373700096 -0.0277686436 -0.1252496243 -0.7686995268 3010 1311867270.8635489941 0.0925552398 0.0622420369 0.1180711985 0.0058863153 0.0096280000 46351109 955859216 1373700096 -0.0257504396 -0.1265110821 -0.7662107944 3011 1311867270.8945889473 0.0927162915 0.0622521579 0.1180711985 0.0058858201 0.0095590000 46353925 955859216 1373700096 -0.0262262560 -0.1274917722 -0.7644769549 3012 1311867270.9326179028 0.0921200365 0.0622620742 0.1180711985 0.0058891241 0.0100190000 46356965 955859216 1373700096 -0.0250326544 -0.1278064698 -0.7621880770 3013 1311867270.9624550343 0.0862811729 0.0622700460 0.1180711985 0.0058937293 0.0100830000 46359781 955859216 1373700096 -0.0188927036 -0.1211575568 -0.7592719793 3014 1311867270.9944560528 0.0902481079 0.0622793287 0.1180711985 0.0058944021 0.0093320000 46362653 955859216 1373700096 -0.0232840218 -0.1269340813 -0.7583025694 3015 1311867271.0306649208 0.0906381086 0.0622887346 0.1180711985 0.0058936849 0.0093690000 46365581 955859216 1373700096 -0.0206875969 -0.1296736151 -0.7556406856 3016 1311867271.0623910427 0.0907578990 0.0622981740 0.1180711985 0.0058932698 0.0093740000 46368453 955859216 1373700096 -0.0183538776 -0.1315393597 -0.7533496022 3017 1311867271.0983459949 0.0912274495 0.0623077627 0.1180711985 0.0058954986 0.0095270000 46371437 955859216 1373700096 -0.0197242685 -0.1323911846 -0.7522622943 3018 1311867271.1322019100 0.0917047411 0.0623175033 0.1180711985 0.0058947946 0.0095070000 46374309 955859216 1373700096 -0.0219616145 -0.1327947229 -0.7510313392 3019 1311867271.1643741131 0.0906492099 0.0623268877 0.1180711985 0.0058941521 0.0095240000 46377181 955859216 1373700096 -0.0190301128 -0.1335753500 -0.7492039204 3020 1311867271.1988029480 0.0919535831 0.0623366979 0.1180711985 0.0058939697 0.0095230000 46380165 955859216 1373700096 -0.0202712491 -0.1350994855 -0.7472048402 3021 1311867271.2320818901 0.0918998569 0.0623464838 0.1180711985 0.0058945089 0.0095350000 46382981 955859216 1373700096 -0.0202002861 -0.1360015422 -0.7453375459 3022 1311867271.2645740509 0.0923032090 0.0623563967 0.1180711985 0.0058963573 0.0139150000 46385853 955859216 1373700096 -0.0205381718 -0.1363071054 -0.7429749370 3023 1311867271.2998549938 0.0919865593 0.0623661982 0.1180711985 0.0058979047 0.0100240000 46388837 955859216 1373700096 -0.0188591778 -0.1380109936 -0.7402480245 3024 1311867271.3354289532 0.0920733958 0.0623760220 0.1180711985 0.0059007181 0.0096720000 46391765 955859216 1373700096 -0.0179721005 -0.1397523135 -0.7372999191 3025 1311867271.3673670292 0.0915441662 0.0623856644 0.1180711985 0.0059000293 0.0097200000 46394693 955859216 1373700096 -0.0168777164 -0.1411938667 -0.7342051864 3026 1311867271.3988809586 0.0922244191 0.0623955252 0.1180711985 0.0058997054 0.0096120000 46397565 955859216 1373700096 -0.0161945783 -0.1428403407 -0.7317711115 3027 1311867271.4355340004 0.0913687199 0.0624050968 0.1180711985 0.0058989875 0.0096610000 46400549 955859216 1373700096 -0.0155721745 -0.1446777284 -0.7290728688 3028 1311867271.4657170773 0.0914257243 0.0624146809 0.1180711985 0.0059019082 0.0096930000 46403309 955859216 1373700096 -0.0149449809 -0.1462877244 -0.7263603806 3029 1311867271.4997088909 0.0913624614 0.0624242378 0.1180711985 0.0059055417 0.0096570000 46406293 955859216 1373700096 -0.0152835762 -0.1472938657 -0.7232210636 3030 1311867271.5323960781 0.0917767510 0.0624339250 0.1180711985 0.0059048991 0.0098200000 46409165 955859216 1373700096 -0.0164985694 -0.1485109329 -0.7200974822 3031 1311867271.5676190853 0.0915536359 0.0624435323 0.1180711985 0.0059043343 0.0098600000 46412093 955859216 1373700096 -0.0174714755 -0.1498184204 -0.7169073224 3032 1311867271.5991230011 0.0912033319 0.0624530178 0.1180711985 0.0059034350 0.0098220000 46414965 955859216 1373700096 -0.0158928074 -0.1511393189 -0.7134081125 3033 1311867271.6349890232 0.0908174962 0.0624623697 0.1180711985 0.0059033240 0.0098250000 46417893 955859216 1373700096 -0.0153881507 -0.1534216702 -0.7095502615 3034 1311867271.6658320427 0.0907485932 0.0624716928 0.1180711985 0.0059028027 0.0097950000 46420765 955859216 1373700096 -0.0151472120 -0.1548991203 -0.7058671713 3035 1311867271.7005228996 0.0873946920 0.0624799047 0.1180711985 0.0059047750 0.0098790000 46423693 955859216 1373700096 -0.0122722704 -0.1531196386 -0.7011908889 3036 1311867271.7349541187 0.0889060795 0.0624886089 0.1180711985 0.0059042383 0.0097020000 46426677 955859216 1373700096 -0.0155934850 -0.1567545980 -0.6969231963 3037 1311867271.7661850452 0.0897086710 0.0624975717 0.1180711985 0.0059047216 0.0102890000 46429493 955859216 1373700096 -0.0175143220 -0.1586474925 -0.6921790242 3038 1311867271.7994530201 0.0856123120 0.0625051803 0.1180711985 0.0059071318 0.0099740000 46432477 955859216 1373700096 -0.0128806056 -0.1569408327 -0.6877552867 3039 1311867271.8341000080 0.0860709623 0.0625129347 0.1180711985 0.0059069244 0.0099670000 46435349 955859216 1373700096 -0.0121617364 -0.1611423641 -0.6830238700 3040 1311867271.8629150391 0.0872284994 0.0625210649 0.1180711985 0.0059067419 0.0139890000 46438165 955859216 1373700096 -0.0129714357 -0.1638841033 -0.6781850457 3041 1311867271.9009630680 0.0841058418 0.0625281628 0.1180711985 0.0059059486 0.0102770000 46441205 955859216 1373700096 -0.0104685510 -0.1631897539 -0.6728862524 3042 1311867271.9304800034 0.0842993483 0.0625353196 0.1180711985 0.0059058038 0.0098320000 46444021 955859216 1373700096 -0.0120054958 -0.1644070745 -0.6680728793 3043 1311867271.9669768810 0.0826979876 0.0625419456 0.1180711985 0.0059055696 0.0097490000 46446949 955859216 1373700096 -0.0089110695 -0.1641409695 -0.6619836092 3044 1311867271.9994390011 0.0853928551 0.0625494524 0.1180711985 0.0059048494 0.0143660000 46449821 955859216 1373700096 -0.0122308666 -0.1676201522 -0.6571097970 3045 1311867272.0337600708 0.0821212605 0.0625558800 0.1180711985 0.0059047454 0.0274010000 46452749 955859216 1373700096 -0.0078311116 -0.1655683368 -0.6511757374 3046 1311867272.0626399517 0.0846244395 0.0625631251 0.1180711985 0.0059049466 0.0121660000 46455565 955859216 1373700096 -0.0078797257 -0.1696614325 -0.6464152932 3047 1311867272.0988030434 0.0836069360 0.0625700315 0.1180711985 0.0059046016 0.0100290000 46458549 955859216 1373700096 -0.0063325800 -0.1699398458 -0.6412602067 3048 1311867272.1336209774 0.0850829706 0.0625774176 0.1180711985 0.0059039221 0.0097600000 46461533 955859216 1373700096 -0.0083085569 -0.1726412773 -0.6366673708 3049 1311867272.1659350395 0.0863798857 0.0625852242 0.1180711985 0.0059056295 0.0096640000 46464405 955859216 1373700096 -0.0086712195 -0.1754192412 -0.6326728463 3050 1311867272.1987910271 0.0865499675 0.0625930815 0.1180711985 0.0059053672 0.0096150000 46467333 955859216 1373700096 -0.0073168129 -0.1771620512 -0.6284650564 3051 1311867272.2319760323 0.0863293111 0.0626008613 0.1180711985 0.0059060204 0.0096890000 46470205 955859216 1373700096 -0.0037271858 -0.1785122007 -0.6241422892 3052 1311867272.2655110359 0.0864738449 0.0626086834 0.1180711985 0.0059089120 0.0150720000 46473133 955859216 1373700096 -0.0042734290 -0.1797391772 -0.6208171248 3053 1311867272.2982270718 0.0869831219 0.0626166672 0.1180711985 0.0059080691 0.0101340000 46476061 955859216 1373700096 -0.0048756846 -0.1808352768 -0.6175428033 3054 1311867272.3315019608 0.0861969367 0.0626243883 0.1180711985 0.0059131539 0.0140260000 46478933 955859216 1373700096 -0.0028777218 -0.1823079437 -0.6143283248 3055 1311867272.3696749210 0.0865922570 0.0626322338 0.1180711985 0.0059152370 0.0100720000 46481973 955859216 1373700096 -0.0049990551 -0.1833175570 -0.6112467647 3056 1311867272.3987050056 0.0867308974 0.0626401194 0.1180711985 0.0059144873 0.0097940000 46484733 955859216 1373700096 -0.0033569022 -0.1851155013 -0.6076615453 3057 1311867272.4335730076 0.0857714862 0.0626476861 0.1180711985 0.0059137009 0.0099050000 46487717 955859216 1373700096 -0.0000136679 -0.1864441484 -0.6048548818 3058 1311867272.4686141014 0.0862585306 0.0626554071 0.1180711985 0.0059131202 0.0097670000 46490645 955859216 1373700096 0.0008067095 -0.1878454387 -0.6014862657 3059 1311867272.5011420250 0.0860294178 0.0626630482 0.1180711985 0.0059124509 0.0096260000 46493517 955859216 1373700096 0.0038187099 -0.1893928051 -0.5980505347 3060 1311867272.5325479507 0.0864343494 0.0626708166 0.1180711985 0.0059116067 0.0095930000 46496389 955859216 1373700096 0.0057336455 -0.1904758662 -0.5945986509 3061 1311867272.5676600933 0.0864605382 0.0626785885 0.1180711985 0.0059111493 0.0096520000 46499317 955859216 1373700096 0.0068361866 -0.1911570877 -0.5916072726 3062 1311867272.5996229649 0.0864799991 0.0626863616 0.1180711985 0.0059103955 0.0096660000 46502245 955859216 1373700096 0.0076345857 -0.1917022914 -0.5888891816 3063 1311867272.6315360069 0.0865441263 0.0626941507 0.1180711985 0.0059097078 0.0095970000 46505061 955859216 1373700096 0.0085028298 -0.1924836636 -0.5861645937 3064 1311867272.6661291122 0.0855795890 0.0627016198 0.1180711985 0.0059088275 0.0241620000 46507989 955859216 1373700096 0.0089153042 -0.1918062270 -0.5838974714 3065 1311867272.6987280846 0.0862459689 0.0627093015 0.1180711985 0.0059079652 0.0113120000 46510917 955859216 1373700096 0.0108104832 -0.1926737577 -0.5810303092 3066 1311867272.7307109833 0.0870710909 0.0627172473 0.1180711985 0.0059074906 0.0098880000 46513789 955859216 1373700096 0.0120811304 -0.1935864985 -0.5783382654 3067 1311867272.7686150074 0.0859055221 0.0627248078 0.1180711985 0.0059102718 0.0097120000 46516773 955859216 1373700096 0.0131187858 -0.1929037720 -0.5755702257 3068 1311867272.7996079922 0.0864611864 0.0627325446 0.1180711985 0.0059094316 0.0098030000 46519589 955859216 1373700096 0.0118487952 -0.1932755113 -0.5728344917 3069 1311867272.8310160637 0.0859655961 0.0627401148 0.1180711985 0.0059091908 0.0097900000 46522461 955859216 1373700096 0.0137922252 -0.1931206137 -0.5701740384 3070 1311867272.8674850464 0.0858220086 0.0627476334 0.1180711985 0.0059083499 0.0099240000 46525501 955859216 1373700096 0.0167518612 -0.1934695989 -0.5675626397 3071 1311867272.8996291161 0.0857864544 0.0627551354 0.1180711985 0.0059079102 0.0098970000 46528317 955859216 1373700096 0.0199281815 -0.1934342384 -0.5650355220 3072 1311867272.9314110279 0.0866511911 0.0627629141 0.1180711985 0.0059077331 0.0099420000 46531189 955859216 1373700096 0.0220931303 -0.1944058388 -0.5627237558 3073 1311867272.9664669037 0.0862852857 0.0627705686 0.1180711985 0.0059068335 0.0101000000 46534173 955859216 1373700096 0.0227953307 -0.1938678175 -0.5607939363 3074 1311867272.9987599850 0.0859966204 0.0627781243 0.1180711985 0.0059060723 0.0098090000 46537045 955859216 1373700096 0.0249674618 -0.1937059462 -0.5592432022 3075 1311867273.0328490734 0.0865218118 0.0627858458 0.1180711985 0.0059051335 0.0097570000 46540029 955859216 1373700096 0.0269580502 -0.1942871064 -0.5575036407 3076 1311867273.0662739277 0.0864737779 0.0627935467 0.1180711985 0.0059042672 0.0097270000 46542901 955859216 1373700096 0.0291414745 -0.1943445951 -0.5561280251 3077 1311867273.0999150276 0.0852913707 0.0628008583 0.1180711985 0.0059035033 0.0148650000 46545773 955859216 1373700096 0.0283761509 -0.1927082390 -0.5552158356 3078 1311867273.1310710907 0.0849015415 0.0628080385 0.1180711985 0.0059026910 0.0103950000 46548645 955859216 1373700096 0.0317392573 -0.1926845163 -0.5538105965 3079 1311867273.1665740013 0.0844343156 0.0628150623 0.1180711985 0.0059020594 0.0101940000 46551629 955859216 1373700096 0.0339657851 -0.1927359551 -0.5525530577 3080 1311867273.1997520924 0.0837870017 0.0628218714 0.1180711985 0.0059011300 0.0108000000 46554501 955859216 1373700096 0.0358782001 -0.1925443709 -0.5510206819 3081 1311867273.2331819534 0.0837139413 0.0628286523 0.1180711985 0.0059009359 0.0151840000 46557485 955859216 1373700096 0.0370955467 -0.1935569197 -0.5497207642 3082 1311867273.2668380737 0.0828988701 0.0628351644 0.1180711985 0.0059008362 0.0105280000 46560357 955859216 1373700096 0.0376356319 -0.1936633289 -0.5481048822 3083 1311867273.2985589504 0.0829371810 0.0628416847 0.1180711985 0.0059001899 0.0100970000 46563285 955859216 1373700096 0.0406228490 -0.1932923049 -0.5457263589 3084 1311867273.3308010101 0.0831094086 0.0628482566 0.1180711985 0.0059001730 0.0102740000 46566101 955859216 1373700096 0.0423443392 -0.1939129382 -0.5435847044 3085 1311867273.3663508892 0.0830739066 0.0628548127 0.1180711985 0.0058992432 0.0100400000 46569085 955859216 1373700096 0.0422601812 -0.1935928017 -0.5415639281 3086 1311867273.3992459774 0.0833567008 0.0628614562 0.1180711985 0.0058991268 0.0224940000 46571957 955859216 1373700096 0.0415533483 -0.1934346706 -0.5387980342 3087 1311867273.4308409691 0.0806831196 0.0628672293 0.1180711985 0.0058992272 0.0284810000 46574885 955859216 1373700096 0.0451783277 -0.1895962358 -0.5358015299 3088 1311867273.4663250446 0.0827219114 0.0628736590 0.1180711985 0.0059005477 0.0126520000 46577813 955859216 1373700096 0.0442996770 -0.1920135468 -0.5328063965 3089 1311867273.4997849464 0.0830995888 0.0628802067 0.1180711985 0.0059004947 0.0101230000 46580685 955859216 1373700096 0.0429628715 -0.1922611743 -0.5297659636 3090 1311867273.5318419933 0.0813157856 0.0628861729 0.1180711985 0.0059018216 0.0101620000 46583613 955859216 1373700096 0.0468999110 -0.1896529198 -0.5264899731 3091 1311867273.5687909126 0.0827739388 0.0628926070 0.1180711985 0.0059019278 0.0099280000 46586653 955859216 1373700096 0.0454979017 -0.1919312030 -0.5229161978 3092 1311867273.6000390053 0.0837734565 0.0628993602 0.1180711985 0.0059012012 0.0224920000 46589413 955859216 1373700096 0.0444246605 -0.1935931891 -0.5194668770 3093 1311867273.6349599361 0.0833309889 0.0629059659 0.1180711985 0.0059008619 0.0111920000 46592397 955859216 1373700096 0.0467554927 -0.1930415034 -0.5153442621 3094 1311867273.6673769951 0.0843217298 0.0629128876 0.1180711985 0.0059000045 0.0141410000 46595325 955859216 1373700096 0.0450547189 -0.1942436695 -0.5112339854 3095 1311867273.6987860203 0.0853323117 0.0629201314 0.1180711985 0.0059000896 0.0111240000 46598141 955859216 1373700096 0.0435633771 -0.1955173314 -0.5072918534 3096 1311867273.7346739769 0.0820918158 0.0629263238 0.1180711985 0.0059019776 0.0153010000 46601125 955859216 1373700096 0.0478775352 -0.1923491955 -0.5032708645 3097 1311867273.7665960789 0.0849074349 0.0629334213 0.1180711985 0.0059038656 0.0107030000 46603997 955859216 1373700096 0.0484330282 -0.1943509132 -0.4996496737 3098 1311867273.7990698814 0.0851761028 0.0629406010 0.1180711985 0.0059033393 0.0102910000 46606925 955859216 1373700096 0.0486299656 -0.1955175698 -0.4966979623 3099 1311867273.8358130455 0.0863368735 0.0629481507 0.1180711985 0.0059031728 0.0101550000 46609909 955859216 1373700096 0.0477572754 -0.1968320757 -0.4935868979 3100 1311867273.8668060303 0.0853581354 0.0629553797 0.1180711985 0.0059047584 0.0100730000 46612781 955859216 1373700096 0.0479557365 -0.1963803470 -0.4910080433 3101 1311867273.8990719318 0.0857877433 0.0629627426 0.1180711985 0.0059075021 0.0100080000 46615709 955859216 1373700096 0.0454653576 -0.1968680620 -0.4885783195 3102 1311867273.9384820461 0.0855822340 0.0629700345 0.1180711985 0.0059066005 0.0100140000 46618749 955859216 1373700096 0.0454321466 -0.1968704313 -0.4855143130 3103 1311867273.9669051170 0.0850425139 0.0629771478 0.1180711985 0.0059061337 0.0100740000 46621509 955859216 1373700096 0.0447231978 -0.1967962682 -0.4827314615 3104 1311867273.9996581078 0.0847638026 0.0629841667 0.1180711985 0.0059051904 0.0100560000 46624437 955859216 1373700096 0.0439365879 -0.1973760575 -0.4796603024 3105 1311867274.0348489285 0.0833480731 0.0629907251 0.1180711985 0.0059043725 0.0100070000 46627309 955859216 1373700096 0.0445483476 -0.1964908242 -0.4763126075 3106 1311867274.0670020580 0.0833475739 0.0629972791 0.1180711985 0.0059064703 0.0141330000 46630237 955859216 1373700096 0.0454663076 -0.1975055337 -0.4725655913 3107 1311867274.1025679111 0.0829330236 0.0630036955 0.1180711985 0.0059063970 0.0102770000 46633221 955859216 1373700096 0.0454027392 -0.1981580853 -0.4685528576 3108 1311867274.1350569725 0.0814821571 0.0630096410 0.1180711985 0.0059055362 0.0102060000 46636149 955859216 1373700096 0.0474889018 -0.1956386715 -0.4639598131 3109 1311867274.1667969227 0.0821287930 0.0630157906 0.1180711985 0.0059055263 0.0100860000 46638965 955859216 1373700096 0.0465592854 -0.1978837848 -0.4600342512 3110 1311867274.2008550167 0.0818854943 0.0630218580 0.1180711985 0.0059107300 0.0100600000 46641837 955859216 1373700096 0.0469779558 -0.1997119337 -0.4555854499 3111 1311867274.2389180660 0.0820460394 0.0630279731 0.1180711985 0.0059114337 0.0229640000 46644933 955859216 1373700096 0.0445187949 -0.2007507533 -0.4512196779 3112 1311867274.2668540478 0.0827977806 0.0630343259 0.1180711985 0.0059106431 0.0114050000 46647693 955859216 1373700096 0.0418610089 -0.2006863356 -0.4466695189 3113 1311867274.3018939495 0.0819914415 0.0630404156 0.1180711985 0.0059117201 0.0146280000 46650621 955859216 1373700096 0.0407157503 -0.2009779662 -0.4425859749 3114 1311867274.3358139992 0.0825034976 0.0630466658 0.1180711985 0.0059125411 0.0105410000 46653549 955859216 1373700096 0.0397410579 -0.2023023367 -0.4382514954 3115 1311867274.3679759502 0.0819414556 0.0630527315 0.1180711985 0.0059117628 0.0103350000 46656477 955859216 1373700096 0.0382788889 -0.2024058849 -0.4339994192 3116 1311867274.4007549286 0.0818701014 0.0630587705 0.1180711985 0.0059110877 0.0103290000 46659293 955859216 1373700096 0.0359639190 -0.2031216919 -0.4299664795 3117 1311867274.4357678890 0.0821158811 0.0630648844 0.1180711985 0.0059133659 0.0154050000 46662277 955859216 1373700096 0.0350430124 -0.2042217106 -0.4256914556 3118 1311867274.4689209461 0.0818114653 0.0630708968 0.1180711985 0.0059154127 0.0106600000 46665205 955859216 1373700096 0.0317545496 -0.2045615464 -0.4217770398 3119 1311867274.4997699261 0.0821529850 0.0630770148 0.1180711985 0.0059149180 0.0103940000 46667965 955859216 1373700096 0.0320757516 -0.2058573961 -0.4176953435 3120 1311867274.5345981121 0.0825848505 0.0630832673 0.1180711985 0.0059152399 0.0103990000 46670893 955859216 1373700096 0.0300816949 -0.2078007609 -0.4142913520 3121 1311867274.5686841011 0.0826459974 0.0630895354 0.1180711985 0.0059145476 0.0153230000 46673765 955859216 1373700096 0.0281147845 -0.2091377676 -0.4107107818 3122 1311867274.6001191139 0.0831028149 0.0630959458 0.1180711985 0.0059143467 0.0104350000 46676637 955859216 1373700096 0.0269653667 -0.2096737176 -0.4074798226 3123 1311867274.6349270344 0.0833092183 0.0631024182 0.1180711985 0.0059143663 0.0102570000 46679621 955859216 1373700096 0.0247640293 -0.2114020288 -0.4043275416 3124 1311867274.6665649414 0.0843224153 0.0631092107 0.1180711985 0.0059157003 0.0101240000 46682437 955859216 1373700096 0.0239716098 -0.2120654136 -0.4007240534 3125 1311867274.6988699436 0.0845075473 0.0631160582 0.1180711985 0.0059148974 0.0100960000 46685365 955859216 1373700096 0.0221969597 -0.2128121853 -0.3974027932 3126 1311867274.7355759144 0.0845297873 0.0631229084 0.1180711985 0.0059179241 0.0098920000 46688293 955859216 1373700096 0.0207380112 -0.2141486853 -0.3942460716 3127 1311867274.7669000626 0.0849135369 0.0631298770 0.1180711985 0.0059171191 0.0099360000 46691165 955859216 1373700096 0.0191130899 -0.2149434686 -0.3909486234 3128 1311867274.8040020466 0.0838138014 0.0631364895 0.1180711985 0.0059169031 0.0100300000 46694205 955859216 1373700096 0.0179774053 -0.2146696746 -0.3876596689 3129 1311867274.8350889683 0.0834531412 0.0631429825 0.1180711985 0.0059171620 0.0100360000 46697077 955859216 1373700096 0.0162613485 -0.2147166878 -0.3843548894 3130 1311867274.8671360016 0.0826532394 0.0631492158 0.1180711985 0.0059166095 0.0244750000 46699949 955859216 1373700096 0.0152012780 -0.2141494900 -0.3808266819 3131 1311867274.9044289589 0.0834419951 0.0631556970 0.1180711985 0.0059157340 0.0114590000 46702933 955859216 1373700096 0.0124296742 -0.2147984207 -0.3768208325 3132 1311867274.9350550175 0.0832893178 0.0631621254 0.1180711985 0.0059151065 0.0102290000 46705805 955859216 1373700096 0.0130427741 -0.2145194858 -0.3726992309 3133 1311867274.9666490555 0.0831534490 0.0631685063 0.1180711985 0.0059142300 0.0141870000 46708621 955859216 1373700096 0.0123462174 -0.2146860957 -0.3690601587 3134 1311867275.0030829906 0.0840723068 0.0631751763 0.1180711985 0.0059155083 0.0102630000 46711661 955859216 1373700096 0.0098188957 -0.2159990668 -0.3647518754 3135 1311867275.0368080139 0.0834851488 0.0631816548 0.1180711985 0.0059199570 0.0099300000 46714533 955859216 1373700096 0.0071529062 -0.2152062058 -0.3609215021 3136 1311867275.0664451122 0.0831441060 0.0631880203 0.1180711985 0.0059212435 0.0099270000 46717349 955859216 1373700096 0.0073435656 -0.2153488547 -0.3570757806 3137 1311867275.1023271084 0.0827269331 0.0631942489 0.1180711985 0.0059210140 0.0102420000 46720333 955859216 1373700096 0.0069803610 -0.2165405750 -0.3531463146 3138 1311867275.1351230145 0.0834824368 0.0632007142 0.1180711985 0.0059202523 0.0100960000 46723205 955859216 1373700096 0.0041775880 -0.2176035643 -0.3491753936 3139 1311867275.1667180061 0.0840052962 0.0632073420 0.1180711985 0.0059193467 0.0099360000 46726077 955859216 1373700096 0.0035499632 -0.2182223201 -0.3448322415 3140 1311867275.2041749954 0.0835404694 0.0632138175 0.1180711985 0.0059193713 0.0104430000 46729117 955859216 1373700096 0.0019534039 -0.2186331451 -0.3412505090 3141 1311867275.2371780872 0.0841138884 0.0632204714 0.1180711985 0.0059187875 0.0101330000 46732045 955859216 1373700096 0.0004285874 -0.2188591808 -0.3377605677 3142 1311867275.2668180466 0.0838940293 0.0632270512 0.1180711985 0.0059219838 0.0152070000 46734805 955859216 1373700096 0.0010519976 -0.2184484750 -0.3342179656 3143 1311867275.3026800156 0.0833573267 0.0632334560 0.1180711985 0.0059246866 0.0104950000 46737789 955859216 1373700096 -0.0010705328 -0.2177464366 -0.3306474388 3144 1311867275.3351879120 0.0832782611 0.0632398315 0.1180711985 0.0059243560 0.0142080000 46740661 955859216 1373700096 -0.0016689546 -0.2177153975 -0.3262950480 3145 1311867275.3669109344 0.0831398368 0.0632461591 0.1180711985 0.0059255380 0.0104090000 46743533 955859216 1373700096 -0.0022616396 -0.2180756032 -0.3220291138 3146 1311867275.4038369656 0.0822150409 0.0632521886 0.1180711985 0.0059252509 0.0100710000 46746461 955859216 1373700096 -0.0025099956 -0.2176376730 -0.3180295825 3147 1311867275.4349598885 0.0833339617 0.0632585698 0.1180711985 0.0059260143 0.0100790000 46749333 955859216 1373700096 -0.0027868242 -0.2190540880 -0.3140568733 3148 1311867275.4669399261 0.0832037032 0.0632649056 0.1180711985 0.0059252174 0.0100560000 46752149 955859216 1373700096 -0.0054774019 -0.2192455083 -0.3102672994 3149 1311867275.5037291050 0.0826154202 0.0632710506 0.1180711985 0.0059248427 0.0152550000 46755189 955859216 1373700096 -0.0060458095 -0.2193359584 -0.3062256277 3150 1311867275.5353329182 0.0828308910 0.0632772601 0.1180711985 0.0059257023 0.0246680000 46758061 955859216 1373700096 -0.0061449958 -0.2195202857 -0.3024465740 3151 1311867275.5668909550 0.0827093869 0.0632834270 0.1180711985 0.0059278346 0.0114280000 46760877 955859216 1373700096 -0.0083457669 -0.2196541727 -0.2992132306 3152 1311867275.6028299332 0.0826697797 0.0632895775 0.1180711985 0.0059281253 0.0103330000 46763917 955859216 1373700096 -0.0084611988 -0.2205689549 -0.2952681184 3153 1311867275.6383280754 0.0826527104 0.0632957187 0.1180711985 0.0059284643 0.0102380000 46766901 955859216 1373700096 -0.0101863509 -0.2208753675 -0.2919153869 3154 1311867275.6682209969 0.0831842571 0.0633020245 0.1180711985 0.0059280829 0.0101050000 46769661 955859216 1373700096 -0.0118350526 -0.2220980525 -0.2885009944 3155 1311867275.7045888901 0.0830475613 0.0633082830 0.1180711985 0.0059275518 0.0152720000 46772645 955859216 1373700096 -0.0138144009 -0.2225904167 -0.2854213715 3156 1311867275.7349820137 0.0829034895 0.0633144919 0.1180711985 0.0059268179 0.0103740000 46775405 955859216 1373700096 -0.0146586914 -0.2231171876 -0.2823110521 3157 1311867275.7792279720 0.0817944705 0.0633203455 0.1180711985 0.0059272179 0.0100260000 46778725 955859216 1373700096 -0.0164547320 -0.2236119658 -0.2794520557 3158 1311867275.8028490543 0.0827030987 0.0633264832 0.1180711985 0.0059272733 0.0098070000 46781317 955859216 1373700096 -0.0184828993 -0.2239053100 -0.2760313153 3159 1311867275.8355960846 0.0823745579 0.0633325130 0.1180711985 0.0059276864 0.0099850000 46784133 955859216 1373700096 -0.0199338011 -0.2233408689 -0.2725923955 3160 1311867275.8701560497 0.0817875564 0.0633383532 0.1180711985 0.0059270866 0.0152580000 46787117 955859216 1373700096 -0.0204604249 -0.2232054472 -0.2695920467 3161 1311867275.9032120705 0.0819944665 0.0633442552 0.1180711985 0.0059263161 0.0114150000 46790045 955859216 1373700096 -0.0227293950 -0.2237709612 -0.2664966583 3162 1311867275.9371318817 0.0819986463 0.0633501547 0.1180711985 0.0059254206 0.0104310000 46792973 955859216 1373700096 -0.0243557245 -0.2239499092 -0.2633800209 3163 1311867275.9683859348 0.0815158710 0.0633558979 0.1180711985 0.0059250210 0.0154840000 46795845 955859216 1373700096 -0.0244991407 -0.2232477814 -0.2599058449 3164 1311867276.0048470497 0.0812735334 0.0633615609 0.1180711985 0.0059269783 0.0106350000 46798829 955859216 1373700096 -0.0267149378 -0.2232677191 -0.2568106353 3165 1311867276.0387539864 0.0810127333 0.0633671379 0.1180711985 0.0059275475 0.0104880000 46801757 955859216 1373700096 -0.0279560219 -0.2242379636 -0.2534945011 3166 1311867276.0739030838 0.0813511312 0.0633728182 0.1180711985 0.0059283915 0.0104130000 46804741 955859216 1373700096 -0.0282450691 -0.2236724794 -0.2503066957 3167 1311867276.1051371098 0.0815124288 0.0633785459 0.1180711985 0.0059294756 0.0104400000 46807613 955859216 1373700096 -0.0298119169 -0.2239990830 -0.2472011894 3168 1311867276.1382379532 0.0827429444 0.0633846584 0.1180711985 0.0059307744 0.0228630000 46810429 955859216 1373700096 -0.0317346118 -0.2251444608 -0.2438874096 3169 1311867276.1709389687 0.0823254213 0.0633906353 0.1180711985 0.0059329836 0.0112970000 46813301 955859216 1373700096 -0.0321907885 -0.2252569199 -0.2406506687 3170 1311867276.2042279243 0.0824116170 0.0633966356 0.1180711985 0.0059322060 0.0105890000 46816285 955859216 1373700096 -0.0330950134 -0.2249411047 -0.2373071462 3171 1311867276.2357859612 0.0823685974 0.0634026186 0.1180711985 0.0059314076 0.0103700000 46819101 955859216 1373700096 -0.0339827389 -0.2243001759 -0.2339911014 3172 1311867276.2747719288 0.0817522034 0.0634084034 0.1180711985 0.0059306109 0.0102640000 46822197 955859216 1373700096 -0.0343633071 -0.2242051810 -0.2311551720 3173 1311867276.3027520180 0.0827673152 0.0634145046 0.1180711985 0.0059312932 0.0102640000 46824901 955859216 1373700096 -0.0349725187 -0.2242948115 -0.2282433361 3174 1311867276.3387188911 0.0825640857 0.0634205378 0.1180711985 0.0059310073 0.0105310000 46827885 955859216 1373700096 -0.0358063467 -0.2249546796 -0.2256954461 3175 1311867276.3729600906 0.0828943700 0.0634266713 0.1180711985 0.0059301918 0.0101300000 46830813 955859216 1373700096 -0.0379699357 -0.2256286293 -0.2232643515 3176 1311867276.4031929970 0.0830932856 0.0634328636 0.1180711985 0.0059305935 0.0102800000 46833629 955859216 1373700096 -0.0387827381 -0.2261473536 -0.2209903598 3177 1311867276.4360129833 0.0828192830 0.0634389657 0.1180711985 0.0059304828 0.0103130000 46836501 955859216 1373700096 -0.0411173478 -0.2266554683 -0.2183662951 3178 1311867276.4737091064 0.0830181539 0.0634451266 0.1180711985 0.0059317325 0.0103090000 46839597 955859216 1373700096 -0.0416594446 -0.2272868454 -0.2158539593 3179 1311867276.5048420429 0.0827071443 0.0634511857 0.1180711985 0.0059314594 0.0102250000 46842413 955859216 1373700096 -0.0423326865 -0.2267942876 -0.2136880159 3180 1311867276.5387470722 0.0826125592 0.0634572113 0.1180711985 0.0059310798 0.0103250000 46845341 955859216 1373700096 -0.0430084877 -0.2266645879 -0.2115832418 3181 1311867276.5746779442 0.0823130682 0.0634631389 0.1180711985 0.0059302198 0.0102070000 46848325 955859216 1373700096 -0.0446825698 -0.2262764275 -0.2089799196 3182 1311867276.6041920185 0.0819909126 0.0634689616 0.1180711985 0.0059293270 0.0101210000 46851029 955859216 1373700096 -0.0445220359 -0.2257676572 -0.2064359486 3183 1311867276.6361470222 0.0823656619 0.0634748984 0.1180711985 0.0059284127 0.0103510000 46853845 955859216 1373700096 -0.0450817868 -0.2265812159 -0.2039441466 3184 1311867276.6710920334 0.0821707398 0.0634807702 0.1180711985 0.0059283011 0.0154530000 46856829 955859216 1373700096 -0.0462480038 -0.2265323251 -0.2013546973 3185 1311867276.7029719353 0.0825613886 0.0634867610 0.1180711985 0.0059297688 0.0106650000 46859701 955859216 1373700096 -0.0462542549 -0.2264912724 -0.1986097246 3186 1311867276.7360780239 0.0826206431 0.0634927666 0.1180711985 0.0059292012 0.0103410000 46862573 955859216 1373700096 -0.0474742837 -0.2274836898 -0.1962785125 3187 1311867276.7721960545 0.0811720639 0.0634983139 0.1180711985 0.0059339830 0.0104150000 46865613 955859216 1373700096 -0.0476588123 -0.2281372547 -0.1941193044 3188 1311867276.8029088974 0.0822649822 0.0635042006 0.1180711985 0.0059413560 0.0103500000 46868429 955859216 1373700096 -0.0488758981 -0.2280638218 -0.1922238618 3189 1311867276.8375699520 0.0824728012 0.0635101487 0.1180711985 0.0059425993 0.0103660000 46871357 955859216 1373700096 -0.0503415614 -0.2285035104 -0.1905419081 3190 1311867276.8740971088 0.0827495977 0.0635161799 0.1180711985 0.0059425258 0.0102510000 46874397 955859216 1373700096 -0.0511668883 -0.2290603518 -0.1885332614 3191 1311867276.9029750824 0.0825773403 0.0635221533 0.1180711985 0.0059434916 0.0257400000 46877157 955859216 1373700096 -0.0518791378 -0.2285430133 -0.1865714788 3192 1311867276.9374980927 0.0816467032 0.0635278314 0.1180711985 0.0059456092 0.0118900000 46880085 955859216 1373700096 -0.0531552099 -0.2287622243 -0.1846325397 3193 1311867276.9726910591 0.0817699581 0.0635335446 0.1180711985 0.0059453273 0.0149630000 46883069 955859216 1373700096 -0.0531488247 -0.2291871160 -0.1820563227 3194 1311867277.0050029755 0.0813775063 0.0635391313 0.1180711985 0.0059454620 0.0105880000 46885997 955859216 1373700096 -0.0534978583 -0.2286320925 -0.1792951077 3195 1311867277.0356070995 0.0807601959 0.0635445213 0.1180711985 0.0059447042 0.0103080000 46888813 955859216 1373700096 -0.0527719781 -0.2276935428 -0.1764048785 3196 1311867277.0711610317 0.0803029984 0.0635497649 0.1180711985 0.0059438826 0.0101390000 46891741 955859216 1373700096 -0.0522745848 -0.2280032635 -0.1736472845 3197 1311867277.1039769650 0.0809731334 0.0635552148 0.1180711985 0.0059437437 0.0149270000 46894669 955859216 1373700096 -0.0532514341 -0.2290191650 -0.1704511493 3198 1311867277.1350269318 0.0806642249 0.0635605647 0.1180711985 0.0059443526 0.0105010000 46897429 955859216 1373700096 -0.0527520366 -0.2278550863 -0.1672335714 3199 1311867277.1708490849 0.0808076710 0.0635659561 0.1180711985 0.0059441410 0.0101900000 46900413 955859216 1373700096 -0.0532388575 -0.2269663662 -0.1641028821 3200 1311867277.2029759884 0.0810584649 0.0635714225 0.1180711985 0.0059435704 0.0155070000 46903341 955859216 1373700096 -0.0528803580 -0.2269481421 -0.1609651595 3201 1311867277.2351000309 0.0816033930 0.0635770557 0.1180711985 0.0059428333 0.0105720000 46906213 955859216 1373700096 -0.0532313846 -0.2275788486 -0.1580978930 3202 1311867277.2733149529 0.0808161274 0.0635824396 0.1180711985 0.0059426439 0.0103290000 46909309 955859216 1373700096 -0.0530609153 -0.2272584885 -0.1550986618 3203 1311867277.3063778877 0.0809497982 0.0635878618 0.1180711985 0.0059417335 0.0158330000 46912181 955859216 1373700096 -0.0536168404 -0.2267440706 -0.1519868970 3204 1311867277.3396029472 0.0804574713 0.0635931269 0.1180711985 0.0059409665 0.0116420000 46915109 955859216 1373700096 -0.0542854890 -0.2259074301 -0.1491416693 3205 1311867277.3773889542 0.0799355060 0.0635982260 0.1180711985 0.0059410875 0.0107330000 46918093 955859216 1373700096 -0.0539954491 -0.2263019234 -0.1463868767 3206 1311867277.4055531025 0.0812188312 0.0636037221 0.1180711985 0.0059404302 0.0155500000 46920797 955859216 1373700096 -0.0566602610 -0.2269428968 -0.1433770359 3207 1311867277.4425079823 0.0807283670 0.0636090619 0.1180711985 0.0059401731 0.0237650000 46923781 955859216 1373700096 -0.0579154082 -0.2267022431 -0.1404485404 3208 1311867277.4723749161 0.0809309855 0.0636144615 0.1180711985 0.0059469761 0.0115920000 46926597 955859216 1373700096 -0.0572537929 -0.2251323611 -0.1376400441 3209 1311867277.5057780743 0.0802777335 0.0636196542 0.1180711985 0.0059498829 0.0106370000 46929413 955859216 1373700096 -0.0577686690 -0.2258403003 -0.1348322630 3210 1311867277.5401940346 0.0795687586 0.0636246227 0.1180711985 0.0059564923 0.0156090000 46932397 955859216 1373700096 -0.0582728721 -0.2271188647 -0.1321943253 3211 1311867277.5715351105 0.0796904340 0.0636296261 0.1180711985 0.0059602757 0.0108020000 46935269 955859216 1373700096 -0.0581841953 -0.2264962494 -0.1299676895 3212 1311867277.6027710438 0.0800413862 0.0636347356 0.1180711985 0.0059596911 0.0104750000 46938085 955859216 1373700096 -0.0579652898 -0.2265359610 -0.1275179386 3213 1311867277.6416130066 0.0803762972 0.0636399462 0.1180711985 0.0059610964 0.0156740000 46941125 955859216 1373700096 -0.0592829697 -0.2282841057 -0.1253089011 3214 1311867277.6713008881 0.0806725249 0.0636452457 0.1180711985 0.0059605544 0.0106680000 46943997 955859216 1373700096 -0.0594547242 -0.2288006544 -0.1230516285 3215 1311867277.7063589096 0.0796454921 0.0636502224 0.1180711985 0.0059615318 0.0104320000 46946869 955859216 1373700096 -0.0629798472 -0.2271749377 -0.1211711839 3216 1311867277.7401409149 0.0784308687 0.0636548184 0.1180711985 0.0059609218 0.0156410000 46949797 955859216 1373700096 -0.0627889112 -0.2261128724 -0.1187071428 3217 1311867277.7720079422 0.0786339715 0.0636594746 0.1180711985 0.0059600877 0.0107090000 46952669 955859216 1373700096 -0.0630408674 -0.2260088772 -0.1157185882 3218 1311867277.8036880493 0.0786411166 0.0636641302 0.1180711985 0.0059596386 0.0103790000 46955541 955859216 1373700096 -0.0624396652 -0.2254703045 -0.1124634743 3219 1311867277.8400499821 0.0785591379 0.0636687574 0.1180711985 0.0059587463 0.0104980000 46958525 955859216 1373700096 -0.0619755425 -0.2250749916 -0.1090305001 3220 1311867277.8711171150 0.0789209530 0.0636734941 0.1180711985 0.0059591626 0.0155540000 46961397 955859216 1373700096 -0.0614325665 -0.2263915539 -0.1054998934 3221 1311867277.9031610489 0.0798155591 0.0636785056 0.1180711985 0.0059582795 0.0108990000 46964269 955859216 1373700096 -0.0626161322 -0.2269885242 -0.1020738706 3222 1311867277.9393019676 0.0796366185 0.0636834585 0.1180711985 0.0059580820 0.0247270000 46967253 955859216 1373700096 -0.0612828545 -0.2261171490 -0.0982475579 3223 1311867277.9714229107 0.0798969120 0.0636884890 0.1180711985 0.0059586186 0.0123890000 46970125 955859216 1373700096 -0.0616836399 -0.2264548838 -0.0948328972 3224 1311867278.0041360855 0.0807006583 0.0636937658 0.1180711985 0.0059577112 0.0145770000 46972997 955859216 1373700096 -0.0607855916 -0.2273780853 -0.0914208964 3225 1311867278.0394210815 0.0810985193 0.0636991626 0.1180711985 0.0059579701 0.0107390000 46975925 955859216 1373700096 -0.0604600534 -0.2279616147 -0.0881848037 3226 1311867278.0712630749 0.0808864981 0.0637044904 0.1180711985 0.0059575725 0.0104860000 46978797 955859216 1373700096 -0.0596979111 -0.2274111807 -0.0846027359 3227 1311867278.1056289673 0.0806124359 0.0637097299 0.1180711985 0.0059566825 0.0107230000 46981781 955859216 1373700096 -0.0593312234 -0.2271931618 -0.0811126903 3228 1311867278.1391980648 0.0810815096 0.0637151115 0.1180711985 0.0059559263 0.0103140000 46984653 955859216 1373700096 -0.0594040193 -0.2276293486 -0.0772465318 3229 1311867278.1710369587 0.0806956440 0.0637203702 0.1180711985 0.0059551645 0.0104930000 46987525 955859216 1373700096 -0.0583019592 -0.2271312326 -0.0732429251 3230 1311867278.2038609982 0.0806731507 0.0637256188 0.1180711985 0.0059569059 0.0103580000 46990453 955859216 1373700096 -0.0575869083 -0.2262376100 -0.0696939453 3231 1311867278.2388060093 0.0800608322 0.0637306745 0.1180711985 0.0059621555 0.0102280000 46993437 955859216 1373700096 -0.0573109463 -0.2265045196 -0.0662757605 3232 1311867278.2707629204 0.0805895999 0.0637358908 0.1180711985 0.0059634635 0.0101830000 46996253 955859216 1373700096 -0.0573367998 -0.2265433520 -0.0628693625 3233 1311867278.3027629852 0.0801712647 0.0637409744 0.1180711985 0.0059629083 0.0102200000 46999125 955859216 1373700096 -0.0555968583 -0.2254486233 -0.0595545843 3234 1311867278.3421599865 0.0798007473 0.0637459403 0.1180711985 0.0059625767 0.0099790000 47002221 955859216 1373700096 -0.0554784946 -0.2256665230 -0.0565692224 3235 1311867278.3714361191 0.0803116262 0.0637510611 0.1180711985 0.0059616570 0.0146060000 47004981 955859216 1373700096 -0.0555989966 -0.2264257967 -0.0535309874 3236 1311867278.4035348892 0.0803069025 0.0637561773 0.1180711985 0.0059608017 0.0106520000 47007909 955859216 1373700096 -0.0545258000 -0.2258351445 -0.0502638482 3237 1311867278.4391169548 0.0793569535 0.0637609968 0.1180711985 0.0059601944 0.0104730000 47010837 955859216 1373700096 -0.0539472178 -0.2251032144 -0.0472621582 3238 1311867278.4713339806 0.0793573782 0.0637658134 0.1180711985 0.0059597662 0.0157470000 47013765 955859216 1373700096 -0.0536628440 -0.2260337770 -0.0445803627 3239 1311867278.5041239262 0.0796783268 0.0637707262 0.1180711985 0.0059592988 0.0107790000 47016637 955859216 1373700096 -0.0538460650 -0.2274640203 -0.0416914485 3240 1311867278.5423910618 0.0791761428 0.0637754810 0.1180711985 0.0059587149 0.0105530000 47019677 955859216 1373700096 -0.0530281253 -0.2275297195 -0.0383700840 3241 1311867278.5710260868 0.0782698840 0.0637799532 0.1180711985 0.0059582268 0.0151870000 47022437 955859216 1373700096 -0.0514975488 -0.2263642848 -0.0351087786 3242 1311867278.6069030762 0.0780326501 0.0637843495 0.1180711985 0.0059576750 0.0107530000 47025421 955859216 1373700096 -0.0513497144 -0.2261477411 -0.0320066474 3243 1311867278.6393239498 0.0779855102 0.0637887285 0.1180711985 0.0059571925 0.0105550000 47028293 955859216 1373700096 -0.0519505702 -0.2264821678 -0.0286707580 3244 1311867278.6709709167 0.0771519467 0.0637928478 0.1180711985 0.0059595849 0.0156310000 47031221 955859216 1373700096 -0.0516858324 -0.2252733111 -0.0255205072 3245 1311867278.7069129944 0.0768276453 0.0637968647 0.1180711985 0.0059586839 0.0109480000 47034149 955859216 1373700096 -0.0502534099 -0.2243974656 -0.0221480951 3246 1311867278.7390680313 0.0769399628 0.0638009137 0.1180711985 0.0059586775 0.0105200000 47037021 955859216 1373700096 -0.0505113080 -0.2254394740 -0.0190311484 3247 1311867278.7718300819 0.0776562542 0.0638051809 0.1180711985 0.0059586452 0.0103750000 47039893 955859216 1373700096 -0.0507298075 -0.2263448089 -0.0159156695 3248 1311867278.8068239689 0.0766867250 0.0638091468 0.1180711985 0.0059580472 0.0103630000 47042877 955859216 1373700096 -0.0492146537 -0.2247747481 -0.0127266943 3249 1311867278.8386530876 0.0768652782 0.0638131654 0.1180711985 0.0059576613 0.0104420000 47045805 955859216 1373700096 -0.0485540591 -0.2248860598 -0.0097466037 3250 1311867278.8741700649 0.0774792954 0.0638173703 0.1180711985 0.0059571343 0.0104670000 47048733 955859216 1373700096 -0.0489848703 -0.2265787274 -0.0067042960 3251 1311867278.9090650082 0.0767581165 0.0638213509 0.1180711985 0.0059565955 0.0104490000 47051661 955859216 1373700096 -0.0483876690 -0.2254171520 -0.0036504418 3252 1311867278.9392769337 0.0758367032 0.0638250456 0.1180711985 0.0059568856 0.0103560000 47054533 955859216 1373700096 -0.0474730060 -0.2231512368 -0.0008252239 3253 1311867278.9711430073 0.0762163997 0.0638288548 0.1180711985 0.0059561224 0.0155720000 47057405 955859216 1373700096 -0.0476919748 -0.2241162509 0.0019611861 3254 1311867279.0073111057 0.0763707608 0.0638327091 0.1180711985 0.0059571909 0.0107030000 47060389 955859216 1373700096 -0.0481181890 -0.2252876908 0.0048707514 3255 1311867279.0397729874 0.0756654218 0.0638363444 0.1180711985 0.0059573131 0.0106980000 47063261 955859216 1373700096 -0.0468205996 -0.2240176201 0.0080402261 3256 1311867279.0738539696 0.0750459656 0.0638397871 0.1180711985 0.0059567665 0.0104780000 47066189 955859216 1373700096 -0.0466306508 -0.2235100269 0.0111696748 3257 1311867279.1068439484 0.0756932795 0.0638434265 0.1180711985 0.0059560106 0.0104600000 47069061 955859216 1373700096 -0.0471527688 -0.2239615023 0.0139615638 3258 1311867279.1392490864 0.0750345662 0.0638468615 0.1180711985 0.0059552588 0.0103940000 47071989 955859216 1373700096 -0.0465395898 -0.2238884419 0.0168737415 3259 1311867279.1712040901 0.0755474195 0.0638504517 0.1180711985 0.0059610048 0.0103730000 47074805 955859216 1373700096 -0.0453445166 -0.2223910540 0.0199041069 3260 1311867279.2070438862 0.0751839206 0.0638539283 0.1180711985 0.0059616015 0.0104100000 47077789 955859216 1373700096 -0.0460324250 -0.2220373899 0.0227627195 3261 1311867279.2411210537 0.0756117851 0.0638575338 0.1180711985 0.0059615680 0.0234340000 47080717 955859216 1373700096 -0.0463915728 -0.2227230966 0.0255936999 3262 1311867279.2717759609 0.0755252540 0.0638611107 0.1180711985 0.0059610636 0.0115460000 47083533 955859216 1373700096 -0.0455190390 -0.2218523473 0.0286499951 3263 1311867279.3067219257 0.0754949749 0.0638646761 0.1180711985 0.0059607999 0.0107880000 47086517 955859216 1373700096 -0.0452622510 -0.2206128389 0.0314345658 3264 1311867279.3388090134 0.0757484138 0.0638683169 0.1180711985 0.0059617458 0.0105970000 47089389 955859216 1373700096 -0.0455634259 -0.2207065374 0.0343614444 3265 1311867279.3804929256 0.0746249333 0.0638716115 0.1180711985 0.0059634082 0.0105040000 47092541 955859216 1373700096 -0.0452023782 -0.2201190442 0.0372616798 3266 1311867279.4089910984 0.0749393553 0.0638750002 0.1180711985 0.0059633687 0.0104300000 47095189 955859216 1373700096 -0.0444977023 -0.2189014405 0.0401492454 3267 1311867279.4410970211 0.0742155090 0.0638781654 0.1180711985 0.0059632953 0.0102420000 47098061 955859216 1373700096 -0.0447126590 -0.2183527350 0.0430307277 3268 1311867279.4725570679 0.0756181255 0.0638817578 0.1180711985 0.0059624444 0.0116030000 47100933 955859216 1373700096 -0.0445469134 -0.2192620039 0.0461542159 3269 1311867279.5095710754 0.0750326663 0.0638851689 0.1180711985 0.0059617652 0.0107840000 47103973 955859216 1373700096 -0.0442731492 -0.2183354944 0.0491260402 3270 1311867279.5407390594 0.0745823011 0.0638884402 0.1180711985 0.0059620164 0.0104600000 47106677 955859216 1373700096 -0.0445861220 -0.2178492099 0.0518488474 3271 1311867279.5734229088 0.0758269057 0.0638920900 0.1180711985 0.0059615623 0.0104020000 47109661 955859216 1373700096 -0.0451691225 -0.2191216350 0.0545060523 3272 1311867279.6121640205 0.0751635060 0.0638955348 0.1180711985 0.0059615034 0.0103970000 47112701 955859216 1373700096 -0.0451264158 -0.2190618217 0.0571644679 3273 1311867279.6389439106 0.0752405524 0.0638990010 0.1180711985 0.0059624663 0.0104460000 47115405 955859216 1373700096 -0.0443348140 -0.2181923836 0.0596065111 3274 1311867279.6749770641 0.0751043707 0.0639024236 0.1180711985 0.0059640134 0.0104340000 47118445 955859216 1373700096 -0.0446790569 -0.2189530879 0.0620196834 3275 1311867279.7107980251 0.0748564973 0.0639057683 0.1180711985 0.0059634717 0.0103580000 47121317 955859216 1373700096 -0.0445242189 -0.2187310159 0.0647233799 3276 1311867279.7410199642 0.0746544972 0.0639090494 0.1180711985 0.0059628125 0.0104080000 47124133 955859216 1373700096 -0.0439559780 -0.2174573094 0.0673696771 3277 1311867279.7777059078 0.0740550458 0.0639121455 0.1180711985 0.0059622351 0.0103380000 47127173 955859216 1373700096 -0.0432848781 -0.2174925059 0.0701262876 3278 1311867279.8118851185 0.0749525055 0.0639155135 0.1180711985 0.0059618699 0.0146850000 47130101 955859216 1373700096 -0.0431973524 -0.2179736197 0.0730397850 3279 1311867279.8438251019 0.0740391016 0.0639186009 0.1180711985 0.0059612046 0.0107620000 47132973 955859216 1373700096 -0.0419130065 -0.2172822058 0.0761963278 3280 1311867279.8808829784 0.0737774894 0.0639216067 0.1180711985 0.0059637678 0.0105790000 47135957 955859216 1373700096 -0.0407519303 -0.2170082629 0.0790747553 3281 1311867279.9088180065 0.0747936070 0.0639249203 0.1180711985 0.0059638589 0.0103150000 47138773 955859216 1373700096 -0.0404738560 -0.2181168646 0.0818771198 3282 1311867279.9440410137 0.0749047697 0.0639282658 0.1180711985 0.0059633969 0.0104340000 47141757 955859216 1373700096 -0.0401056632 -0.2180005461 0.0851078555 3283 1311867279.9795188904 0.0744540915 0.0639314719 0.1180711985 0.0059665838 0.0146860000 47144685 955859216 1373700096 -0.0389219336 -0.2163565755 0.0882212445 3284 1311867280.0113790035 0.0743647516 0.0639346489 0.1180711985 0.0059677574 0.0112970000 47147501 955859216 1373700096 -0.0386545584 -0.2164328396 0.0911794305 3285 1311867280.0401859283 0.0745996907 0.0639378955 0.1180711985 0.0059677530 0.0106610000 47150261 955859216 1373700096 -0.0382820219 -0.2157802582 0.0944251269 3286 1311867280.0785079002 0.0744597614 0.0639410976 0.1180711985 0.0059683791 0.0104070000 47153301 955859216 1373700096 -0.0370735638 -0.2141992897 0.0978217795 3287 1311867280.1111929417 0.0754991695 0.0639446139 0.1180711985 0.0059679396 0.0103250000 47156173 955859216 1373700096 -0.0363666974 -0.2152068168 0.1007670164 3288 1311867280.1450068951 0.0758956894 0.0639482486 0.1180711985 0.0059670531 0.0105610000 47159157 955859216 1373700096 -0.0366925113 -0.2155524790 0.1037524939 3289 1311867280.1753098965 0.0756816566 0.0639518161 0.1180711985 0.0059684113 0.0104070000 47161917 955859216 1373700096 -0.0360066518 -0.2139363885 0.1067601442 3290 1311867280.2123339176 0.0757602826 0.0639554053 0.1180711985 0.0059691023 0.0107130000 47164957 955859216 1373700096 -0.0351187848 -0.2142462134 0.1095981449 3291 1311867280.2422859669 0.0765033811 0.0639592181 0.1180711985 0.0059682867 0.0109730000 47167773 955859216 1373700096 -0.0352235250 -0.2151102424 0.1124328002 3292 1311867280.2794580460 0.0760341510 0.0639628861 0.1180711985 0.0059718382 0.0104910000 47170813 955859216 1373700096 -0.0342652835 -0.2132354379 0.1152997687 3293 1311867280.3114728928 0.0763457268 0.0639666464 0.1180711985 0.0059721108 0.0105310000 47173685 955859216 1373700096 -0.0347796232 -0.2140245587 0.1178929880 3294 1311867280.3445079327 0.0771693736 0.0639706545 0.1180711985 0.0059725838 0.0105790000 47176501 955859216 1373700096 -0.0348286591 -0.2144472897 0.1208448634 3295 1311867280.3755340576 0.0769456401 0.0639745923 0.1180711985 0.0059723346 0.0104980000 47179373 955859216 1373700096 -0.0338139944 -0.2130373716 0.1236291453 3296 1311867280.4071900845 0.0773836449 0.0639786606 0.1180711985 0.0059718632 0.0104730000 47182189 955859216 1373700096 -0.0341885723 -0.2138603479 0.1261041462 3297 1311867280.4424109459 0.0777390674 0.0639828342 0.1180711985 0.0059725721 0.0104110000 47185173 955859216 1373700096 -0.0335355438 -0.2134265453 0.1287265271 3298 1311867280.4782869816 0.0768737942 0.0639867429 0.1180711985 0.0059726590 0.0110720000 47188157 955859216 1373700096 -0.0325804204 -0.2126844674 0.1313139498 3299 1311867280.5091259480 0.0773438662 0.0639907918 0.1180711985 0.0059719280 0.0109070000 47191029 955859216 1373700096 -0.0322675072 -0.2128075063 0.1339562982 3300 1311867280.5455989838 0.0776073411 0.0639949180 0.1180711985 0.0059711175 0.0107980000 47193957 955859216 1373700096 -0.0320971161 -0.2126319855 0.1367032528 3301 1311867280.5782079697 0.0777001381 0.0639990698 0.1180711985 0.0059714654 0.0109500000 47196829 955859216 1373700096 -0.0318318456 -0.2116061896 0.1393788904 3302 1311867280.6130499840 0.0776032060 0.0640031898 0.1180711985 0.0059713799 0.0108430000 47199757 955859216 1373700096 -0.0318466984 -0.2116862237 0.1418383569 3303 1311867280.6422739029 0.0784341544 0.0640075588 0.1180711985 0.0059716540 0.0108200000 47202573 955859216 1373700096 -0.0318542905 -0.2125023454 0.1443531364 3304 1311867280.6755290031 0.0787315518 0.0640120153 0.1180711985 0.0059711525 0.0107680000 47205501 955859216 1373700096 -0.0313800871 -0.2123049796 0.1470277160 3305 1311867280.7094879150 0.0788885355 0.0640165165 0.1180711985 0.0059702572 0.0109610000 47208429 955859216 1373700096 -0.0309043769 -0.2125088722 0.1493084282 3306 1311867280.7411808968 0.0780007765 0.0640207464 0.1180711985 0.0059710445 0.0108010000 47211245 955859216 1373700096 -0.0309162214 -0.2126391530 0.1516466439 3307 1311867280.7752668858 0.0788909867 0.0640252430 0.1180711985 0.0059717357 0.0109080000 47214173 955859216 1373700096 -0.0311624147 -0.2122338414 0.1539189368 3308 1311867280.8076250553 0.0787701905 0.0640297004 0.1180711985 0.0059708591 0.0108570000 47217045 955859216 1373700096 -0.0310332198 -0.2118142098 0.1562159806 3309 1311867280.8401010036 0.0789022893 0.0640341950 0.1180711985 0.0059700493 0.0108480000 47219973 955859216 1373700096 -0.0308362842 -0.2114482373 0.1585589349 3310 1311867280.8754839897 0.0786122605 0.0640385992 0.1180711985 0.0059691804 0.0260790000 47222901 955859216 1373700096 -0.0304860529 -0.2114520967 0.1609819978 3311 1311867280.9079110622 0.0785181373 0.0640429724 0.1180711985 0.0059682851 0.0121230000 47225773 955859216 1373700096 -0.0304710642 -0.2110272795 0.1633895338 3312 1311867280.9394528866 0.0785696581 0.0640473585 0.1180711985 0.0059674077 0.0110090000 47228701 955859216 1373700096 -0.0305713620 -0.2106799781 0.1659310162 3313 1311867280.9766991138 0.0784078836 0.0640516931 0.1180711985 0.0059665593 0.0109680000 47231573 955859216 1373700096 -0.0301314909 -0.2104659528 0.1686155200 3314 1311867281.0075190067 0.0785405189 0.0640560651 0.1180711985 0.0059657345 0.0108260000 47234445 955859216 1373700096 -0.0297998004 -0.2103973329 0.1711196005 3315 1311867281.0433430672 0.0784967840 0.0640604212 0.1180711985 0.0059649426 0.0107350000 47237429 955859216 1373700096 -0.0300336313 -0.2105737180 0.1736899912 3316 1311867281.0752780437 0.0786714777 0.0640648275 0.1180711985 0.0059641840 0.0106310000 47240245 955859216 1373700096 -0.0290564932 -0.2105248123 0.1763828695 3317 1311867281.1074900627 0.0787683204 0.0640692602 0.1180711985 0.0059637498 0.0106950000 47243173 955859216 1373700096 -0.0291288253 -0.2100926638 0.1790537387 3318 1311867281.1451520920 0.0786004961 0.0640736398 0.1180711985 0.0059634777 0.0107160000 47246157 955859216 1373700096 -0.0287101623 -0.2103760988 0.1814487875 3319 1311867281.1786689758 0.0790748522 0.0640781596 0.1180711985 0.0059635091 0.0106120000 47249141 955859216 1373700096 -0.0278085545 -0.2103632540 0.1839080155 3320 1311867281.2083299160 0.0793340057 0.0640827547 0.1180711985 0.0059626688 0.0106450000 47251957 955859216 1373700096 -0.0267180800 -0.2098389864 0.1863669455 3321 1311867281.2457950115 0.0791385695 0.0640872882 0.1180711985 0.0059632633 0.0149110000 47254941 955859216 1373700096 -0.0264931284 -0.2103963196 0.1885256469 3322 1311867281.2754399776 0.0801408887 0.0640921207 0.1180711985 0.0059625261 0.0108730000 47257701 955859216 1373700096 -0.0259085968 -0.2106009126 0.1909497976 3323 1311867281.3072988987 0.0800077990 0.0640969103 0.1180711985 0.0059646521 0.0106940000 47260629 955859216 1373700096 -0.0250675939 -0.2098226696 0.1934270114 3324 1311867281.3465099335 0.0797583982 0.0641016219 0.1180711985 0.0059664611 0.0107000000 47263669 955859216 1373700096 -0.0243186392 -0.2101968229 0.1957497597 3325 1311867281.3751530647 0.0805724636 0.0641065755 0.1180711985 0.0059655811 0.0108800000 47266429 955859216 1373700096 -0.0238297787 -0.2112266421 0.1981521845 3326 1311867281.4080700874 0.0804387331 0.0641114860 0.1180711985 0.0059647990 0.0106510000 47269357 955859216 1373700096 -0.0227636099 -0.2106415778 0.2005275488 3327 1311867281.4434111118 0.0805009082 0.0641164122 0.1180711985 0.0059643365 0.0148840000 47272341 955859216 1373700096 -0.0222984739 -0.2109563500 0.2028345168 3328 1311867281.4753720760 0.0810149387 0.0641214899 0.1180711985 0.0059635054 0.0110180000 47275157 955859216 1373700096 -0.0222101696 -0.2117916495 0.2050637007 3329 1311867281.5101969242 0.0808303878 0.0641265091 0.1180711985 0.0059632942 0.0253910000 47278141 955859216 1373700096 -0.0215476155 -0.2112375051 0.2074104398 3330 1311867281.5435659885 0.0804811344 0.0641314204 0.1180711985 0.0059631745 0.0120770000 47281069 955859216 1373700096 -0.0209170878 -0.2111873329 0.2096324861 3331 1311867281.5754749775 0.0813009366 0.0641365748 0.1180711985 0.0059624070 0.0112280000 47283941 955859216 1373700096 -0.0204767995 -0.2122745961 0.2118812501 3332 1311867281.6111190319 0.0811683685 0.0641416864 0.1180711985 0.0059622134 0.0160020000 47286869 955859216 1373700096 -0.0197012015 -0.2119147927 0.2140745819 3333 1311867281.6435608864 0.0811571479 0.0641467916 0.1180711985 0.0059613920 0.0114530000 47289797 955859216 1373700096 -0.0190397557 -0.2117677182 0.2160910070 3334 1311867281.6755120754 0.0815086439 0.0641519991 0.1180711985 0.0059610011 0.0112330000 47292669 955859216 1373700096 -0.0185977109 -0.2128048688 0.2179751098 3335 1311867281.7089190483 0.0819457322 0.0641573345 0.1180711985 0.0059601325 0.0111790000 47295541 955859216 1373700096 -0.0178080685 -0.2132797986 0.2199925482 3336 1311867281.7452239990 0.0816961378 0.0641625920 0.1180711985 0.0059595508 0.0108620000 47298581 955859216 1373700096 -0.0168167260 -0.2129382044 0.2217911035 3337 1311867281.7755289078 0.0822376311 0.0641680085 0.1180711985 0.0059592772 0.0156710000 47301341 955859216 1373700096 -0.0163159110 -0.2140390873 0.2233998328 3338 1311867281.8075580597 0.0822690874 0.0641734312 0.1180711985 0.0059587583 0.0109590000 47304213 955859216 1373700096 -0.0151288686 -0.2144241780 0.2250476331 3339 1311867281.8447821140 0.0820650011 0.0641787896 0.1180711985 0.0059578807 0.0109910000 47307253 955859216 1373700096 -0.0139802275 -0.2144371271 0.2265353501 3340 1311867281.8756659031 0.0824702829 0.0641842661 0.1180711985 0.0059569895 0.0108840000 47310125 955859216 1373700096 -0.0131264040 -0.2150313109 0.2280113697 3341 1311867281.9077229500 0.0825695246 0.0641897690 0.1180711985 0.0059565994 0.0109090000 47312997 955859216 1373700096 -0.0122612799 -0.2148527801 0.2296031266 3342 1311867281.9444870949 0.0823038518 0.0641951891 0.1180711985 0.0059569877 0.0107280000 47315925 955859216 1373700096 -0.0107971411 -0.2143072188 0.2310508341 3343 1311867281.9785399437 0.0827585310 0.0642007420 0.1180711985 0.0059581653 0.0108640000 47318853 955859216 1373700096 -0.0100467419 -0.2152598649 0.2323052585 3344 1311867282.0098121166 0.0830409527 0.0642063761 0.1180711985 0.0059573199 0.0108790000 47321725 955859216 1373700096 -0.0090890620 -0.2156173885 0.2337556332 3345 1311867282.0436799526 0.0826264992 0.0642118828 0.1180711985 0.0059566560 0.0255790000 47324597 955859216 1373700096 -0.0078809690 -0.2147747427 0.2353139818 3346 1311867282.0755469799 0.0826568082 0.0642173954 0.1180711985 0.0059558033 0.0121040000 47327469 955859216 1373700096 -0.0069372808 -0.2150032371 0.2367477119 3347 1311867282.1077909470 0.0832258388 0.0642230746 0.1180711985 0.0059549380 0.0112530000 47330341 955859216 1373700096 -0.0059457980 -0.2153889835 0.2384912372 3348 1311867282.1464140415 0.0825830400 0.0642285585 0.1180711985 0.0059541007 0.0110580000 47333381 955859216 1373700096 -0.0046480447 -0.2144884914 0.2403481454 3349 1311867282.1797480583 0.0822841823 0.0642339498 0.1180711985 0.0059532354 0.0110760000 47336309 955859216 1373700096 -0.0038792726 -0.2141616791 0.2421218604 3350 1311867282.2136330605 0.0827426687 0.0642394748 0.1180711985 0.0059524135 0.0109490000 47339237 955859216 1373700096 -0.0032446492 -0.2146655619 0.2439741641 3351 1311867282.2453169823 0.0829643831 0.0642450627 0.1180711985 0.0059517163 0.0108200000 47342109 955859216 1373700096 -0.0022808178 -0.2145272642 0.2459035665 3352 1311867282.2844099998 0.0827250257 0.0642505758 0.1180711985 0.0059512795 0.0109990000 47345093 955859216 1373700096 -0.0009412411 -0.2145482153 0.2476769835 3353 1311867282.3187301159 0.0827648640 0.0642560975 0.1180711985 0.0059511725 0.0109710000 47348021 955859216 1373700096 -0.0000711698 -0.2151862979 0.2494585365 3354 1311867282.3445549011 0.0828911588 0.0642616536 0.1180711985 0.0059503978 0.0108310000 47350725 955859216 1373700096 0.0005228346 -0.2150404751 0.2510511875 3355 1311867282.3837130070 0.0830501914 0.0642672537 0.1180711985 0.0059506515 0.0113810000 47353541 955859216 1373700096 0.0014475874 -0.2148581743 0.2528460026 3356 1311867282.4114849567 0.0832496062 0.0642729100 0.1180711985 0.0059503389 0.0109580000 47356245 955859216 1373700096 0.0019308003 -0.2151969373 0.2545493245 3357 1311867282.4437038898 0.0833951533 0.0642786062 0.1180711985 0.0059496366 0.0300950000 47359173 955859216 1373700096 0.0026970294 -0.2154221684 0.2563515306 3358 1311867282.4754569530 0.0830711797 0.0642842026 0.1180711985 0.0059490812 0.0130690000 47361989 955859216 1373700096 0.0033368184 -0.2152019441 0.2580463290 3359 1311867282.5128560066 0.0835673288 0.0642899433 0.1180711985 0.0059485036 0.0111330000 47365029 955859216 1373700096 0.0037894035 -0.2160302401 0.2596938908 3360 1311867282.5435400009 0.0840670243 0.0642958293 0.1180711985 0.0059476352 0.0109510000 47367901 955859216 1373700096 0.0045944727 -0.2166857123 0.2613174319 3361 1311867282.5755639076 0.0835940614 0.0643015711 0.1180711985 0.0059469688 0.0109450000 47370773 955859216 1373700096 0.0050748424 -0.2163021117 0.2628293931 3362 1311867282.6112899780 0.0835710689 0.0643073027 0.1180711985 0.0059463638 0.0241850000 47373701 955859216 1373700096 0.0050899624 -0.2169341892 0.2640440762 3363 1311867282.6437261105 0.0838891119 0.0643131254 0.1180711985 0.0059456695 0.0118140000 47376573 955859216 1373700096 0.0053385636 -0.2172527611 0.2652867734 3364 1311867282.6766591072 0.0839737803 0.0643189699 0.1180711985 0.0059451893 0.0111660000 47379445 955859216 1373700096 0.0058068861 -0.2168625295 0.2663851082 3365 1311867282.7147250175 0.0837850571 0.0643247547 0.1180711985 0.0059445115 0.0111280000 47382485 955859216 1373700096 0.0049055927 -0.2176032513 0.2670804858 3366 1311867282.7462520599 0.0845674053 0.0643307686 0.1180711985 0.0059436408 0.0110940000 47385357 955859216 1373700096 0.0047717551 -0.2182452679 0.2678747475 3367 1311867282.7754290104 0.0841984823 0.0643366693 0.1180711985 0.0059430860 0.0159980000 47388005 955859216 1373700096 0.0045586252 -0.2182088643 0.2685527205 3368 1311867282.8116350174 0.0840801150 0.0643425314 0.1180711985 0.0059422813 0.0111850000 47390933 955859216 1373700096 0.0042982227 -0.2186157554 0.2693577409 3369 1311867282.8475370407 0.0831644982 0.0643481182 0.1180711985 0.0059421655 0.0161750000 47393917 955859216 1373700096 0.0037202293 -0.2178672105 0.2703902423 3370 1311867282.8757910728 0.0825150385 0.0643535090 0.1180711985 0.0059413306 0.0111860000 47396733 955859216 1373700096 0.0035006597 -0.2166985273 0.2715989053 3371 1311867282.9114630222 0.0827476382 0.0643589655 0.1180711985 0.0059404631 0.0162680000 47399661 955859216 1373700096 0.0034120802 -0.2166021615 0.2730743587 3372 1311867282.9456479549 0.0833066776 0.0643645847 0.1180711985 0.0059398914 0.0111760000 47402589 955859216 1373700096 0.0031486084 -0.2164852172 0.2747102082 3373 1311867282.9811890125 0.0828913301 0.0643700773 0.1180711985 0.0059391024 0.0110470000 47405517 955859216 1373700096 0.0028191716 -0.2156829089 0.2761189342 3374 1311867283.0114879608 0.0832965747 0.0643756868 0.1180711985 0.0059384604 0.0109090000 47408389 955859216 1373700096 0.0024721925 -0.2156804502 0.2774388194 3375 1311867283.0462460518 0.0842300504 0.0643815696 0.1180711985 0.0059382811 0.0109610000 47411317 955859216 1373700096 0.0018579429 -0.2164955884 0.2786707282 3376 1311867283.0752930641 0.0841600969 0.0643874282 0.1180711985 0.0059382858 0.0242160000 47414133 955859216 1373700096 0.0015549024 -0.2161005139 0.2798278928 3377 1311867283.1116878986 0.0826361403 0.0643928320 0.1180711985 0.0059393527 0.0120000000 47417173 955859216 1373700096 0.0013876504 -0.2157215476 0.2807651758 3378 1311867283.1435511112 0.0835532397 0.0643985041 0.1180711985 0.0059388899 0.0111130000 47420045 955859216 1373700096 0.0011788876 -0.2169518769 0.2815702260 3379 1311867283.1788220406 0.0832319334 0.0644040778 0.1180711985 0.0059401279 0.0110080000 47422917 955859216 1373700096 0.0010652723 -0.2167006582 0.2823421061 3380 1311867283.2158269882 0.0836851522 0.0644097823 0.1180711985 0.0059399077 0.0109930000 47425957 955859216 1373700096 0.0015177635 -0.2162232846 0.2830995619 3381 1311867283.2441749573 0.0843747258 0.0644156873 0.1180711985 0.0059395664 0.0110330000 47428717 955859216 1373700096 0.0014420233 -0.2176121771 0.2837977111 3382 1311867283.2776839733 0.0845255703 0.0644216334 0.1180711985 0.0059389387 0.0110560000 47431645 955859216 1373700096 0.0015167166 -0.2179978192 0.2847917974 3383 1311867283.3134660721 0.0840000808 0.0644274208 0.1180711985 0.0059383267 0.0111870000 47434629 955859216 1373700096 0.0017504052 -0.2175116837 0.2856687903 3384 1311867283.3498029709 0.0842312127 0.0644332729 0.1180711985 0.0059378928 0.0110090000 47437725 955859216 1373700096 0.0018824302 -0.2179242224 0.2866932452 3385 1311867283.3852219582 0.0841859132 0.0644391083 0.1180711985 0.0059372087 0.0109540000 47440709 955859216 1373700096 0.0018252258 -0.2182463408 0.2877497077 3386 1311867283.4173080921 0.0842445865 0.0644449575 0.1180711985 0.0059369187 0.0109000000 47443525 955859216 1373700096 0.0019929435 -0.2177688628 0.2887672782 3387 1311867283.4492650032 0.0840983242 0.0644507601 0.1180711985 0.0059360809 0.0109100000 47446397 955859216 1373700096 0.0022523431 -0.2174081355 0.2894597054 3388 1311867283.4853370190 0.0843915492 0.0644566458 0.1180711985 0.0059355023 0.0112170000 47449381 955859216 1373700096 0.0018749794 -0.2183699608 0.2900284231 3389 1311867283.5172159672 0.0845394582 0.0644625717 0.1180711985 0.0059346745 0.0110070000 47452253 955859216 1373700096 0.0021953152 -0.2186484486 0.2907430232 3390 1311867283.5495610237 0.0840965658 0.0644683634 0.1180711985 0.0059340637 0.0109720000 47455125 955859216 1373700096 0.0026771459 -0.2180869430 0.2913688421 3391 1311867283.5853879452 0.0841710046 0.0644741737 0.1180711985 0.0059334176 0.0110040000 47458053 955859216 1373700096 0.0027070101 -0.2185193300 0.2918818891 3392 1311867283.6173179150 0.0841185302 0.0644799651 0.1180711985 0.0059328796 0.0119920000 47460925 955859216 1373700096 0.0029063048 -0.2181479335 0.2926349342 3393 1311867283.6493821144 0.0837609097 0.0644856476 0.1180711985 0.0059320515 0.0112730000 47463853 955859216 1373700096 0.0032946609 -0.2173116505 0.2931984663 3394 1311867283.6852879524 0.0836034417 0.0644912805 0.1180711985 0.0059317088 0.0111090000 47466837 955859216 1373700096 0.0031648765 -0.2171377242 0.2937672734 3395 1311867283.7179150581 0.0836278126 0.0644969171 0.1180711985 0.0059309713 0.0111540000 47469653 955859216 1373700096 0.0031002131 -0.2164703161 0.2944955826 3396 1311867283.7492079735 0.0836590603 0.0645025597 0.1180711985 0.0059304205 0.0112540000 47472525 955859216 1373700096 0.0026967460 -0.2155429721 0.2951810956 3397 1311867283.7853169441 0.0840359554 0.0645083099 0.1180711985 0.0059297275 0.0250920000 47475509 955859216 1373700096 0.0025835880 -0.2155019492 0.2957770824 3398 1311867283.8174130917 0.0845477208 0.0645142073 0.1180711985 0.0059289870 0.0120180000 47478325 955859216 1373700096 0.0021354922 -0.2156305015 0.2963953316 3399 1311867283.8494520187 0.0844540223 0.0645200737 0.1180711985 0.0059284060 0.0113060000 47481253 955859216 1373700096 0.0022829021 -0.2148303837 0.2969429195 3400 1311867283.8853459358 0.0843715146 0.0645259123 0.1180711985 0.0059276443 0.0110630000 47484181 955859216 1373700096 0.0016122024 -0.2145363688 0.2972966731 3401 1311867283.9175400734 0.0846954361 0.0645318428 0.1180711985 0.0059267955 0.0111240000 47487053 955859216 1373700096 0.0009386533 -0.2149250805 0.2976652682 3402 1311867283.9498898983 0.0844970271 0.0645377115 0.1180711985 0.0059259291 0.0109560000 47489925 955859216 1373700096 0.0008857130 -0.2144404352 0.2980408370 3403 1311867283.9856629372 0.0843037441 0.0645435199 0.1180711985 0.0059252684 0.0150890000 47492965 955859216 1373700096 0.0004616952 -0.2144532949 0.2983210981 3404 1311867284.0172998905 0.0846726522 0.0645494333 0.1180711985 0.0059245048 0.0110680000 47495781 955859216 1373700096 -0.0004184666 -0.2151553929 0.2986011803 3405 1311867284.0497789383 0.0846942216 0.0645553495 0.1180711985 0.0059243541 0.0111630000 47498709 955859216 1373700096 -0.0011250294 -0.2148614973 0.2989483774 3406 1311867284.0853729248 0.0840971246 0.0645610870 0.1180711985 0.0059236325 0.0110400000 47501637 955859216 1373700096 -0.0015211251 -0.2137072831 0.2992449999 3407 1311867284.1175038815 0.0840256959 0.0645668001 0.1180711985 0.0059234503 0.0109140000 47504509 955859216 1373700096 -0.0021736119 -0.2137202173 0.2995102406 3408 1311867284.1494109631 0.0839093849 0.0645724757 0.1180711985 0.0059226988 0.0150950000 47507381 955859216 1373700096 -0.0023788062 -0.2131900638 0.3000433743 3409 1311867284.1874890327 0.0834507272 0.0645780135 0.1180711985 0.0059218796 0.0112170000 47510421 955859216 1373700096 -0.0026806502 -0.2118496150 0.3006373048 3410 1311867284.2173368931 0.0838458315 0.0645836639 0.1180711985 0.0059211829 0.0109840000 47513237 955859216 1373700096 -0.0038037470 -0.2123149037 0.3009461164 3411 1311867284.2494308949 0.0840742514 0.0645893779 0.1180711985 0.0059204511 0.0111020000 47516109 955859216 1373700096 -0.0042215367 -0.2117988467 0.3013632894 3412 1311867284.2853159904 0.0840925202 0.0645950940 0.1180711985 0.0059196495 0.0109940000 47519037 955859216 1373700096 -0.0038627321 -0.2110961825 0.3016641736 3413 1311867284.3178350925 0.0843390971 0.0646008789 0.1180711985 0.0059188436 0.0156740000 47521965 955859216 1373700096 -0.0042870454 -0.2110633701 0.3017935157 3414 1311867284.3494238853 0.0841176361 0.0646065956 0.1180711985 0.0059181696 0.0112790000 47524837 955859216 1373700096 -0.0038358860 -0.2098418921 0.3021722734 3415 1311867284.3854329586 0.0840721875 0.0646122956 0.1180711985 0.0059173646 0.0152380000 47527821 955859216 1373700096 -0.0034548889 -0.2091403604 0.3025260270 3416 1311867284.4175798893 0.0843464062 0.0646180726 0.1180711985 0.0059167476 0.0112770000 47530693 955859216 1373700096 -0.0032119935 -0.2091474384 0.3028008342 3417 1311867284.4495139122 0.0842198208 0.0646238091 0.1180711985 0.0059160445 0.0111700000 47533565 955859216 1373700096 -0.0025590195 -0.2084660232 0.3032364845 3418 1311867284.4854190350 0.0842923224 0.0646295635 0.1180711985 0.0059153489 0.0109830000 47536493 955859216 1373700096 -0.0023894527 -0.2084745318 0.3035540581 3419 1311867284.5177299976 0.0845082700 0.0646353777 0.1180711985 0.0059145917 0.0161020000 47539421 955859216 1373700096 -0.0019676613 -0.2088104635 0.3039570451 3420 1311867284.5494539738 0.0844183713 0.0646411622 0.1180711985 0.0059142738 0.0113110000 47542293 955859216 1373700096 -0.0010698441 -0.2082597762 0.3043710589 3421 1311867284.5854179859 0.0843276754 0.0646469168 0.1180711985 0.0059136928 0.0159750000 47545221 955859216 1373700096 -0.0004531982 -0.2078267187 0.3047276437 3422 1311867284.6174941063 0.0845866129 0.0646527437 0.1180711985 0.0059129844 0.0114220000 47548093 955859216 1373700096 0.0000255500 -0.2083164603 0.3050695956 3423 1311867284.6495230198 0.0846083462 0.0646585736 0.1180711985 0.0059126546 0.0160530000 47551021 955859216 1373700096 0.0007324441 -0.2079091072 0.3054859638 3424 1311867284.6853780746 0.0843071043 0.0646643120 0.1180711985 0.0059124575 0.0112450000 47553949 955859216 1373700096 0.0012190498 -0.2071707547 0.3058859706 3425 1311867284.7174859047 0.0848017111 0.0646701916 0.1180711985 0.0059123238 0.0160620000 47556821 955859216 1373700096 0.0016249220 -0.2079418004 0.3061737418 3426 1311867284.7498660088 0.0849383026 0.0646761075 0.1180711985 0.0059126378 0.0113300000 47559749 955859216 1373700096 0.0019193010 -0.2076631039 0.3067337573 3427 1311867284.7854089737 0.0845487192 0.0646819064 0.1180711985 0.0059119032 0.0112580000 47562677 955859216 1373700096 0.0024259884 -0.2065571547 0.3072375059 3428 1311867284.8186919689 0.0850698501 0.0646878539 0.1180711985 0.0059118016 0.0272960000 47565605 955859216 1373700096 0.0024624805 -0.2070939690 0.3076044619 3429 1311867284.8492770195 0.0850978792 0.0646938060 0.1180711985 0.0059114696 0.0124770000 47568421 955859216 1373700096 0.0030043505 -0.2066100091 0.3079499304 3430 1311867284.8853850365 0.0849033669 0.0646996980 0.1180711985 0.0059106379 0.0114960000 47571349 955859216 1373700096 0.0033631807 -0.2057561874 0.3082993329 3431 1311867284.9174609184 0.0853157118 0.0647057068 0.1180711985 0.0059100178 0.0112830000 47574277 955859216 1373700096 0.0030258719 -0.2066375464 0.3083043098 3432 1311867284.9492468834 0.0852677077 0.0647116980 0.1180711985 0.0059092962 0.0111970000 47577149 955859216 1373700096 0.0033364675 -0.2063135356 0.3083569407 3433 1311867284.9852581024 0.0852368250 0.0647176768 0.1180711985 0.0059086696 0.0112280000 47580189 955859216 1373700096 0.0034808780 -0.2064158767 0.3081677556 3434 1311867285.0175390244 0.0855033100 0.0647237297 0.1180711985 0.0059086425 0.0152560000 47583005 955859216 1373700096 0.0030098581 -0.2076648921 0.3078092933 3435 1311867285.0493679047 0.0855209902 0.0647297842 0.1180711985 0.0059079583 0.0112530000 47585877 955859216 1373700096 0.0029826565 -0.2081461847 0.3074199259 3436 1311867285.0853259563 0.0852907002 0.0647357682 0.1180711985 0.0059071305 0.0111490000 47588861 955859216 1373700096 0.0028307347 -0.2081275582 0.3068729639 3437 1311867285.1177120209 0.0858475119 0.0647419107 0.1180711985 0.0059065983 0.0111030000 47591733 955859216 1373700096 0.0022527848 -0.2094827145 0.3061184287 3438 1311867285.1502749920 0.0861098841 0.0647481259 0.1180711985 0.0059060621 0.0111160000 47594661 955859216 1373700096 0.0017365264 -0.2103461474 0.3053959012 3439 1311867285.1855800152 0.0858260840 0.0647542550 0.1180711985 0.0059053275 0.0111810000 47597533 955859216 1373700096 0.0017543838 -0.2102294564 0.3045014739 3440 1311867285.2187609673 0.0860074162 0.0647604333 0.1180711985 0.0059046523 0.0110880000 47600517 955859216 1373700096 0.0012516115 -0.2112749815 0.3035950661 3441 1311867285.2493660450 0.0863109976 0.0647666961 0.1180711985 0.0059038081 0.0113730000 47603333 955859216 1373700096 0.0011077366 -0.2122871727 0.3028517067 3442 1311867285.2853620052 0.0859819427 0.0647728598 0.1180711985 0.0059033040 0.0110650000 47606317 955859216 1373700096 0.0010871631 -0.2120551169 0.3020918667 3443 1311867285.3175029755 0.0857940465 0.0647789653 0.1180711985 0.0059026265 0.0112900000 47609189 955859216 1373700096 0.0008926799 -0.2123231292 0.3013829291 3444 1311867285.3493449688 0.0860579237 0.0647851438 0.1180711985 0.0059018704 0.0105600000 47612061 955859216 1373700096 0.0007790477 -0.2130601853 0.3009384274 3445 1311867285.3855409622 0.0855538994 0.0647911725 0.1180711985 0.0059017805 0.0107430000 47615101 955859216 1373700096 0.0005999209 -0.2123089880 0.3005658090 3446 1311867285.4175810814 0.0852402225 0.0647971066 0.1180711985 0.0059013138 0.0109180000 47617917 955859216 1373700096 0.0004494114 -0.2121728957 0.3003540635 3447 1311867285.4492840767 0.0852390677 0.0648030370 0.1180711985 0.0059004667 0.0160750000 47620789 955859216 1373700096 0.0000302981 -0.2122319192 0.3005150855 3448 1311867285.4853799343 0.0848621354 0.0648088546 0.1180711985 0.0059001497 0.0112330000 47623717 955859216 1373700096 0.0001338788 -0.2112338990 0.3008970618 3449 1311867285.5176479816 0.0846374035 0.0648146037 0.1180711985 0.0058995014 0.0160170000 47626645 955859216 1373700096 -0.0000508481 -0.2108642161 0.3012705147 3450 1311867285.5494589806 0.0849582553 0.0648204424 0.1180711985 0.0058991845 0.0113560000 47629517 955859216 1373700096 -0.0004817983 -0.2114542127 0.3017375767 3451 1311867285.5855739117 0.0847358704 0.0648262133 0.1180711985 0.0058989184 0.0113180000 47632501 955859216 1373700096 -0.0002588411 -0.2104149014 0.3024263978 3452 1311867285.6175510883 0.0845238194 0.0648319195 0.1180711985 0.0058985103 0.0112790000 47635373 955859216 1373700096 -0.0003907528 -0.2101276517 0.3028739691 3453 1311867285.6494030952 0.0847749561 0.0648376950 0.1180711985 0.0058976636 0.0118320000 47638245 955859216 1373700096 -0.0011973954 -0.2104381323 0.3034750819 3454 1311867285.6856529713 0.0844809711 0.0648433821 0.1180711985 0.0058968343 0.0120110000 47641229 955859216 1373700096 -0.0009382192 -0.2092615664 0.3041947484 3455 1311867285.7177190781 0.0847837478 0.0648491536 0.1180711985 0.0058967564 0.0112880000 47644101 955859216 1373700096 -0.0016212107 -0.2096829414 0.3045829833 3456 1311867285.7497379780 0.0850314125 0.0648549934 0.1180711985 0.0058963354 0.0112670000 47646973 955859216 1373700096 -0.0019439260 -0.2099066675 0.3049139082 3457 1311867285.7854781151 0.0849824995 0.0648608156 0.1180711985 0.0058955643 0.0161340000 47650013 955859216 1373700096 -0.0021823985 -0.2095675617 0.3051535189 3458 1311867285.8179709911 0.0850994736 0.0648666683 0.1180711985 0.0058948334 0.0119210000 47652829 955859216 1373700096 -0.0029086710 -0.2101475298 0.3052613437 3459 1311867285.8496279716 0.0853295326 0.0648725842 0.1180711985 0.0058942415 0.0120910000 47655701 955859216 1373700096 -0.0034233162 -0.2105019838 0.3053751886 3460 1311867285.8852860928 0.0850708708 0.0648784218 0.1180711985 0.0058934006 0.0117350000 47658741 955859216 1373700096 -0.0034301416 -0.2103624493 0.3054022789 3461 1311867285.9187369347 0.0852210149 0.0648842995 0.1180711985 0.0058933199 0.0163750000 47661613 955859216 1373700096 -0.0042333910 -0.2114396691 0.3053413630 3462 1311867285.9496929646 0.0855160654 0.0648902590 0.1180711985 0.0058927740 0.0267950000 47664485 955859216 1373700096 -0.0051440569 -0.2123932540 0.3054116964 3463 1311867285.9858360291 0.0848085955 0.0648960107 0.1180711985 0.0058929030 0.0126230000 47667413 955859216 1373700096 -0.0051332158 -0.2114280313 0.3055520356 3464 1311867286.0184700489 0.0845105648 0.0649016731 0.1180711985 0.0058924298 0.0116330000 47670285 955859216 1373700096 -0.0060329242 -0.2116944194 0.3056216836 3465 1311867286.0494220257 0.0848436877 0.0649074284 0.1180711985 0.0058916788 0.0115630000 47673157 955859216 1373700096 -0.0061308546 -0.2119165957 0.3060711324 3466 1311867286.0854020119 0.0847864375 0.0649131638 0.1180711985 0.0058927662 0.0113260000 47676085 955859216 1373700096 -0.0057874615 -0.2110736370 0.3065456152 3467 1311867286.1240980625 0.0847904533 0.0649188971 0.1180711985 0.0058935643 0.0112190000 47679069 955859216 1373700096 -0.0062950496 -0.2114044130 0.3068519533 3468 1311867286.1506319046 0.0850630105 0.0649247057 0.1180711985 0.0058937738 0.0110430000 47681773 955859216 1373700096 -0.0062384675 -0.2112168372 0.3071562350 3469 1311867286.1857590675 0.0848460495 0.0649304484 0.1180711985 0.0058929859 0.0111850000 47684701 955859216 1373700096 -0.0061023906 -0.2105087340 0.3075350523 3470 1311867286.2179830074 0.0847818479 0.0649361692 0.1180711985 0.0058931207 0.0110290000 47687573 955859216 1373700096 -0.0062918048 -0.2106177658 0.3077704608 3471 1311867286.2525210381 0.0851369500 0.0649419891 0.1180711985 0.0058923050 0.0111520000 47690445 955859216 1373700096 -0.0062993756 -0.2106665373 0.3081644773 3472 1311867286.2861630917 0.0848805681 0.0649477318 0.1180711985 0.0058915331 0.0111220000 47693317 955859216 1373700096 -0.0061036157 -0.2097713798 0.3082647622 3473 1311867286.3203520775 0.0848298669 0.0649534565 0.1180711985 0.0058908625 0.0121590000 47696189 955859216 1373700096 -0.0060882103 -0.2094888091 0.3082214594 3474 1311867286.3524320126 0.0848316103 0.0649591785 0.1180711985 0.0058905523 0.0115600000 47699061 955859216 1373700096 -0.0062391805 -0.2098139822 0.3080182374 3475 1311867286.3855628967 0.0841888860 0.0649647123 0.1180711985 0.0058899757 0.0114370000 47701933 955859216 1373700096 -0.0060542938 -0.2090701014 0.3075722158 3476 1311867286.4177770615 0.0831898004 0.0649699554 0.1180711985 0.0058896712 0.0114670000 47704861 955859216 1373700096 -0.0053833709 -0.2079116255 0.3069891036 3477 1311867286.4494199753 0.0830148309 0.0649751452 0.1180711985 0.0058889033 0.0114400000 47707733 955859216 1373700096 -0.0048145102 -0.2079500407 0.3065657914 3478 1311867286.4855709076 0.0827590972 0.0649802584 0.1180711985 0.0058894981 0.0114680000 47710661 955859216 1373700096 -0.0040448690 -0.2076740265 0.3063692451 3479 1311867286.5190370083 0.0823974013 0.0649852648 0.1180711985 0.0058888727 0.0114680000 47713645 955859216 1373700096 -0.0029448534 -0.2070014477 0.3062457740 3480 1311867286.5512158871 0.0821975395 0.0649902108 0.1180711985 0.0058881502 0.0159660000 47716461 955859216 1373700096 -0.0027835835 -0.2071480006 0.3060531318 3481 1311867286.5855200291 0.0820468515 0.0649951108 0.1180711985 0.0058875628 0.0114770000 47719501 955859216 1373700096 -0.0025679667 -0.2072542906 0.3061296344 3482 1311867286.6190819740 0.0812371001 0.0649997753 0.1180711985 0.0058870911 0.0114230000 47722373 955859216 1373700096 -0.0016599289 -0.2061410546 0.3062703013 3483 1311867286.6500060558 0.0813857466 0.0650044799 0.1180711985 0.0058868245 0.0114180000 47725189 955859216 1373700096 -0.0016307937 -0.2064675540 0.3061538935 3484 1311867286.6856429577 0.0819868669 0.0650093543 0.1180711985 0.0058866665 0.0113360000 47728117 955859216 1373700096 -0.0016169810 -0.2079742998 0.3061450720 3485 1311867286.7176160812 0.0818908513 0.0650141983 0.1180711985 0.0058861185 0.0154640000 47730989 955859216 1373700096 -0.0009753975 -0.2079458684 0.3062331676 3486 1311867286.7495489120 0.0812164992 0.0650188461 0.1180711985 0.0058861614 0.0115730000 47733917 955859216 1373700096 -0.0006513158 -0.2075787336 0.3062368631 3487 1311867286.7856459618 0.0810745284 0.0650234506 0.1180711985 0.0058867932 0.0115710000 47736845 955859216 1373700096 -0.0007627147 -0.2076079398 0.3063893020 3488 1311867286.8176259995 0.0810149163 0.0650280353 0.1180711985 0.0058861361 0.0117170000 47739773 955859216 1373700096 -0.0003069344 -0.2074073106 0.3066605628 3489 1311867286.8535819054 0.0808760151 0.0650325776 0.1180711985 0.0058855050 0.0115270000 47742757 955859216 1373700096 0.0000657098 -0.2071932107 0.3067896664 3490 1311867286.8868150711 0.0809795633 0.0650371469 0.1180711985 0.0058847718 0.0112180000 47745629 955859216 1373700096 0.0002624235 -0.2076760381 0.3068117201 3491 1311867286.9174380302 0.0812142715 0.0650417809 0.1180711985 0.0058839882 0.0112860000 47748445 955859216 1373700096 0.0006990964 -0.2077284753 0.3070206046 3492 1311867286.9543609619 0.0810636356 0.0650463690 0.1180711985 0.0058833676 0.0111130000 47751485 955859216 1373700096 0.0018364131 -0.2065554708 0.3073056042 3493 1311867286.9854118824 0.0812743381 0.0650510149 0.1180711985 0.0058830077 0.0160630000 47754301 955859216 1373700096 0.0018141753 -0.2067887485 0.3073799014 3494 1311867287.0174310207 0.0819976330 0.0650558651 0.1180711985 0.0058824096 0.0117100000 47757173 955859216 1373700096 0.0018477667 -0.2076733112 0.3073947430 3495 1311867287.0547020435 0.0825250000 0.0650608634 0.1180711985 0.0058843211 0.0118280000 47760213 955859216 1373700096 0.0025392158 -0.2071174383 0.3074899912 3496 1311867287.0856859684 0.0819452927 0.0650656930 0.1180711985 0.0058836398 0.0116070000 47763085 955859216 1373700096 0.0029468185 -0.2061402798 0.3073988259 3497 1311867287.1178219318 0.0820695311 0.0650705554 0.1180711985 0.0058838332 0.0113810000 47765901 955859216 1373700096 0.0029301771 -0.2063448429 0.3072040975 3498 1311867287.1537048817 0.0825387686 0.0650755492 0.1180711985 0.0058830036 0.0114050000 47768885 955859216 1373700096 0.0033214071 -0.2065553963 0.3072389364 3499 1311867287.1874449253 0.0822625607 0.0650804612 0.1180711985 0.0058825406 0.0110160000 47771813 955859216 1373700096 0.0035845453 -0.2059587389 0.3072293997 3500 1311867287.2175579071 0.0823692903 0.0650854009 0.1180711985 0.0058827066 0.0112590000 47774629 955859216 1373700096 0.0035727432 -0.2063525021 0.3071251512 3501 1311867287.2536680698 0.0827601254 0.0650904493 0.1180711985 0.0058822164 0.0111430000 47777613 955859216 1373700096 0.0035873374 -0.2067756653 0.3070667386 3502 1311867287.2870221138 0.0824600905 0.0650954093 0.1180711985 0.0058816991 0.0113270000 47780541 955859216 1373700096 0.0036372216 -0.2063152492 0.3069579303 3503 1311867287.3175630569 0.0824414045 0.0651003610 0.1180711985 0.0058812927 0.0112680000 47783357 955859216 1373700096 0.0032864914 -0.2066932321 0.3067338467 3504 1311867287.3540940285 0.0830507055 0.0651054838 0.1180711985 0.0058804927 0.0113510000 47786397 955859216 1373700096 0.0032310269 -0.2073737383 0.3066333830 3505 1311867287.3855540752 0.0828476474 0.0651105458 0.1180711985 0.0058797834 0.0113940000 47789269 955859216 1373700096 0.0035811532 -0.2070770562 0.3064858913 3506 1311867287.4175760746 0.0829668269 0.0651156388 0.1180711985 0.0058789454 0.0114890000 47792085 955859216 1373700096 0.0034434884 -0.2073770911 0.3063752651 3507 1311867287.4535288811 0.0835959390 0.0651209084 0.1180711985 0.0058782331 0.0162270000 47795069 955859216 1373700096 0.0036411253 -0.2083096802 0.3062695265 3508 1311867287.4867310524 0.0823050588 0.0651258070 0.1180711985 0.0058798486 0.0115850000 47797941 955859216 1373700096 0.0040980200 -0.2077490985 0.3061151505 3509 1311867287.5174999237 0.0827805325 0.0651308382 0.1180711985 0.0058836476 0.0114760000 47800813 955859216 1373700096 0.0039536101 -0.2074990422 0.3060266972 3510 1311867287.5534870625 0.0827354938 0.0651358538 0.1180711985 0.0058828939 0.0114230000 47803797 955859216 1373700096 0.0041917837 -0.2073947936 0.3061172366 3511 1311867287.5869519711 0.0827752501 0.0651408778 0.1180711985 0.0058821195 0.0113300000 47806725 955859216 1373700096 0.0044828681 -0.2071581781 0.3063018918 3512 1311867287.6176569462 0.0831142887 0.0651459955 0.1180711985 0.0058824115 0.0113610000 47809541 955859216 1373700096 0.0043518702 -0.2077500969 0.3062615395 3513 1311867287.6539158821 0.0836102292 0.0651512515 0.1180711985 0.0058817482 0.0161010000 47812581 955859216 1373700096 0.0043294798 -0.2081567198 0.3061811030 3514 1311867287.6875660419 0.0831876993 0.0651563843 0.1180711985 0.0058825169 0.0116660000 47815453 955859216 1373700096 0.0043004286 -0.2072453201 0.3061564863 3515 1311867287.7176280022 0.0829172283 0.0651614371 0.1180711985 0.0058819006 0.0114360000 47818269 955859216 1373700096 0.0042372290 -0.2068171501 0.3062294126 3516 1311867287.7553908825 0.0832543448 0.0651665830 0.1180711985 0.0058814501 0.0119220000 47821309 955859216 1373700096 0.0040292637 -0.2071512192 0.3062942028 3517 1311867287.7872428894 0.0833315551 0.0651717479 0.1180711985 0.0058807505 0.0163200000 47824125 955859216 1373700096 0.0043620286 -0.2067411244 0.3065080643 3518 1311867287.8260099888 0.0829896182 0.0651768127 0.1180711985 0.0058799666 0.0264170000 47827165 955859216 1373700096 0.0044441284 -0.2061177343 0.3067978323 3519 1311867287.8536510468 0.0831650272 0.0651819244 0.1180711985 0.0058794448 0.0124610000 47829925 955859216 1373700096 0.0045145848 -0.2064240724 0.3070160747 3520 1311867287.8931109905 0.0836871937 0.0651871816 0.1180711985 0.0058787077 0.0118030000 47832909 955859216 1373700096 0.0048573832 -0.2068580687 0.3075371981 3521 1311867287.9175710678 0.0832733512 0.0651923183 0.1180711985 0.0058789559 0.0115250000 47835557 955859216 1373700096 0.0058794394 -0.2056227624 0.3080118299 3522 1311867287.9535610676 0.0828834102 0.0651973413 0.1180711985 0.0058833116 0.0115220000 47838485 955859216 1373700096 0.0061604208 -0.2061485946 0.3081381023 3523 1311867287.9868519306 0.0844033509 0.0652027929 0.1180711985 0.0058832609 0.0114030000 47841357 955859216 1373700096 0.0061756731 -0.2081511766 0.3080887496 3524 1311867288.0178821087 0.0843983144 0.0652082400 0.1180711985 0.0058836931 0.0164810000 47844229 955859216 1373700096 0.0074266032 -0.2078887373 0.3081533313 3525 1311867288.0536389351 0.0834485665 0.0652134145 0.1180711985 0.0058840250 0.0115830000 47847213 955859216 1373700096 0.0075565381 -0.2076596022 0.3080471456 3526 1311867288.0854179859 0.0838513896 0.0652187004 0.1180711985 0.0058833435 0.0114880000 47850029 955859216 1373700096 0.0071219797 -0.2091115862 0.3078984618 3527 1311867288.1175940037 0.0837784931 0.0652239626 0.1180711985 0.0058829786 0.0114790000 47852957 955859216 1373700096 0.0077085700 -0.2091021389 0.3080325425 3528 1311867288.1540820599 0.0834645629 0.0652291329 0.1180711985 0.0058830668 0.0114000000 47855941 955859216 1373700096 0.0080635482 -0.2092738748 0.3080158532 3529 1311867288.1854550838 0.0843816251 0.0652345600 0.1180711985 0.0058823329 0.0114130000 47858813 955859216 1373700096 0.0072661289 -0.2112340480 0.3077757061 3530 1311867288.2175340652 0.0841230527 0.0652399109 0.1180711985 0.0058829253 0.0116700000 47861573 955859216 1373700096 0.0075918916 -0.2107991874 0.3075295985 3531 1311867288.2535810471 0.0835853592 0.0652451064 0.1180711985 0.0058825564 0.0115040000 47864613 955859216 1373700096 0.0076849083 -0.2098581344 0.3071397245 3532 1311867288.2854719162 0.0839276761 0.0652503959 0.1180711985 0.0058826673 0.0116210000 47867429 955859216 1373700096 0.0067215627 -0.2110940069 0.3066523671 3533 1311867288.3175830841 0.0840972438 0.0652557304 0.1180711985 0.0058823013 0.0157870000 47870357 955859216 1373700096 0.0065136799 -0.2116441429 0.3064980805 3534 1311867288.3535211086 0.0835612640 0.0652609103 0.1180711985 0.0058815761 0.0276300000 47873341 955859216 1373700096 0.0062938430 -0.2108173817 0.3064874113 3535 1311867288.3858890533 0.0836617649 0.0652661156 0.1180711985 0.0058812724 0.0130680000 47876213 955859216 1373700096 0.0055059195 -0.2113657296 0.3064331114 3536 1311867288.4177610874 0.0837290213 0.0652713370 0.1180711985 0.0058805816 0.0120220000 47879085 955859216 1373700096 0.0049184710 -0.2114591151 0.3064534068 3537 1311867288.4560298920 0.0834410861 0.0652764741 0.1180711985 0.0058799734 0.0117430000 47882125 955859216 1373700096 0.0046265577 -0.2105925530 0.3066480160 3538 1311867288.4854650497 0.0833278820 0.0652815762 0.1180711985 0.0058793106 0.0116990000 47884997 955859216 1373700096 0.0037368166 -0.2106472105 0.3066327572 3539 1311867288.5176889896 0.0838159695 0.0652868134 0.1180711985 0.0058786188 0.0116810000 47887813 955859216 1373700096 0.0030164276 -0.2110410035 0.3068360686 3540 1311867288.5544929504 0.0836335942 0.0652919961 0.1180711985 0.0058781448 0.0118110000 47890797 955859216 1373700096 0.0026114197 -0.2105209231 0.3068639636 3541 1311867288.5874340534 0.0835314468 0.0652971470 0.1180711985 0.0058774244 0.0115490000 47893669 955859216 1373700096 0.0016837862 -0.2104972005 0.3066805601 3542 1311867288.6175410748 0.0839015394 0.0653023996 0.1180711985 0.0058766903 0.0160290000 47896485 955859216 1373700096 0.0009497705 -0.2107957453 0.3066276908 3543 1311867288.6551198959 0.0839678720 0.0653076678 0.1180711985 0.0058759874 0.0118410000 47899525 955859216 1373700096 0.0005705707 -0.2102957964 0.3064834774 3544 1311867288.6874110699 0.0838974044 0.0653129132 0.1180711985 0.0058752400 0.0118480000 47902397 955859216 1373700096 -0.0003623528 -0.2099206150 0.3062567115 3545 1311867288.7177178860 0.0841536149 0.0653182280 0.1180711985 0.0058744541 0.0118230000 47905213 955859216 1373700096 -0.0011460746 -0.2099882215 0.3060095608 3546 1311867288.7560660839 0.0839660764 0.0653234868 0.1180711985 0.0058736420 0.0119070000 47908253 955859216 1373700096 -0.0010234724 -0.2094687521 0.3057260215 3547 1311867288.7855091095 0.0841213986 0.0653287865 0.1180711985 0.0058728199 0.0116740000 47911069 955859216 1373700096 -0.0016815433 -0.2097302675 0.3054333627 3548 1311867288.8192400932 0.0842319354 0.0653341143 0.1180711985 0.0058720773 0.0116020000 47914053 955859216 1373700096 -0.0022134127 -0.2099756300 0.3051764071 3549 1311867288.8543450832 0.0839479938 0.0653393591 0.1180711985 0.0058716161 0.0114410000 47916981 955859216 1373700096 -0.0020063682 -0.2091945708 0.3049204051 3550 1311867288.8855559826 0.0837103128 0.0653445340 0.1180711985 0.0058708835 0.0112040000 47919853 955859216 1373700096 -0.0019992562 -0.2090559006 0.3046046495 3551 1311867288.9176120758 0.0837812498 0.0653497260 0.1180711985 0.0058701424 0.0113420000 47922669 955859216 1373700096 -0.0023587747 -0.2091635317 0.3044289351 3552 1311867288.9599480629 0.0835836232 0.0653548594 0.1180711985 0.0058696676 0.0113590000 47925877 955859216 1373700096 -0.0023357994 -0.2086945921 0.3042719066 3553 1311867288.9855918884 0.0833819509 0.0653599332 0.1180711985 0.0058689019 0.0114540000 47928581 955859216 1373700096 -0.0023205050 -0.2083119452 0.3042009175 3554 1311867289.0176560879 0.0834477320 0.0653650226 0.1180711985 0.0058682929 0.0117460000 47931397 955859216 1373700096 -0.0019717687 -0.2083302885 0.3041678071 3555 1311867289.0535120964 0.0835921541 0.0653701498 0.1180711985 0.0058686362 0.0114650000 47934437 955859216 1373700096 -0.0015834834 -0.2086158097 0.3042763472 3556 1311867289.0855109692 0.0835767537 0.0653752698 0.1180711985 0.0058679956 0.0117070000 47937253 955859216 1373700096 -0.0018763043 -0.2087517679 0.3043279350 3557 1311867289.1175429821 0.0834121332 0.0653803406 0.1180711985 0.0058673513 0.0116220000 47940125 955859216 1373700096 -0.0019431297 -0.2083600610 0.3043118417 3558 1311867289.1545929909 0.0834707841 0.0653854250 0.1180711985 0.0058665577 0.0116300000 47943221 955859216 1373700096 -0.0018664441 -0.2085610479 0.3042667508 3559 1311867289.1856400967 0.0835279152 0.0653905227 0.1180711985 0.0058657700 0.0115590000 47945981 955859216 1373700096 -0.0016992304 -0.2088560611 0.3042507172 3560 1311867289.2185060978 0.0834602341 0.0653955984 0.1180711985 0.0058651803 0.0114900000 47948909 955859216 1373700096 -0.0017131465 -0.2089892030 0.3043116927 3561 1311867289.2550480366 0.0833615959 0.0654006436 0.1180711985 0.0058652091 0.0113960000 47951949 955859216 1373700096 -0.0017985896 -0.2092131078 0.3043379784 3562 1311867289.2853870392 0.0835904554 0.0654057503 0.1180711985 0.0058645807 0.0114680000 47954821 955859216 1373700096 -0.0020808484 -0.2098961473 0.3043003082 3563 1311867289.3176290989 0.0835962892 0.0654108557 0.1180711985 0.0058639016 0.0114470000 47957637 955859216 1373700096 -0.0021534394 -0.2099030912 0.3041478097 3564 1311867289.3539168835 0.0834134445 0.0654159069 0.1180711985 0.0058631897 0.0114480000 47960621 955859216 1373700096 -0.0023124705 -0.2096247375 0.3040632606 3565 1311867289.3861899376 0.0837306604 0.0654210443 0.1180711985 0.0058624502 0.0114760000 47963549 955859216 1373700096 -0.0025709793 -0.2101544440 0.3041080832 3566 1311867289.4177041054 0.0837627500 0.0654261878 0.1180711985 0.0058625392 0.0113980000 47966365 955859216 1373700096 -0.0024597275 -0.2095157802 0.3042488396 3567 1311867289.4536058903 0.0836564153 0.0654312986 0.1180711985 0.0058619258 0.0115910000 47969349 955859216 1373700096 -0.0027864978 -0.2089566588 0.3045299053 3568 1311867289.4859669209 0.0839366168 0.0654364850 0.1180711985 0.0058615111 0.0116840000 47972277 955859216 1373700096 -0.0036695048 -0.2095155716 0.3046819270 3569 1311867289.5183238983 0.0839911848 0.0654416839 0.1180711985 0.0058611251 0.0265870000 47975093 955859216 1373700096 -0.0037146737 -0.2091499269 0.3050253093 3570 1311867289.5548820496 0.0834470317 0.0654467274 0.1180711985 0.0058603496 0.0125720000 47978133 955859216 1373700096 -0.0035061017 -0.2080757171 0.3053425252 3571 1311867289.5856130123 0.0839583203 0.0654519113 0.1180711985 0.0058610102 0.0118990000 47981005 955859216 1373700096 -0.0041448693 -0.2092580646 0.3053930402 3572 1311867289.6176490784 0.0842544958 0.0654571751 0.1180711985 0.0058602167 0.0157220000 47983821 955859216 1373700096 -0.0041405982 -0.2095621079 0.3056693375 3573 1311867289.6536390781 0.0835005492 0.0654622251 0.1180711985 0.0058595636 0.0117670000 47986805 955859216 1373700096 -0.0038228675 -0.2081068009 0.3060928881 3574 1311867289.6856849194 0.0830122083 0.0654671355 0.1180711985 0.0058590760 0.0115920000 47989677 955859216 1373700096 -0.0043214941 -0.2077933848 0.3065623343 3575 1311867289.7204349041 0.0830333158 0.0654720491 0.1180711985 0.0058583749 0.0114680000 47992661 955859216 1373700096 -0.0048919874 -0.2075795978 0.3073178530 3576 1311867289.7564179897 0.0828888789 0.0654769196 0.1180711985 0.0058582703 0.0125170000 47995589 955859216 1373700096 -0.0050806031 -0.2066924274 0.3079611361 3577 1311867289.7855679989 0.0833095685 0.0654819050 0.1180711985 0.0058578264 0.0119850000 47998405 955859216 1373700096 -0.0058328742 -0.2070443034 0.3085254431 3578 1311867289.8240370750 0.0840628669 0.0654870981 0.1180711985 0.0058573034 0.0118390000 48001445 955859216 1373700096 -0.0065013515 -0.2082535923 0.3089710474 3579 1311867289.8541870117 0.0840338394 0.0654922802 0.1180711985 0.0058570351 0.0117430000 48004317 955859216 1373700096 -0.0064174291 -0.2075157017 0.3095627427 3580 1311867289.8855679035 0.0841240287 0.0654974846 0.1180711985 0.0058569064 0.0118240000 48007133 955859216 1373700096 -0.0065142699 -0.2075348794 0.3099771440 3581 1311867289.9200530052 0.0851294547 0.0655029669 0.1180711985 0.0058577470 0.0118110000 48010061 955859216 1373700096 -0.0072455625 -0.2085280120 0.3103860319 3582 1311867289.9536409378 0.0845337659 0.0655082798 0.1180711985 0.0058578782 0.0117230000 48012989 955859216 1373700096 -0.0075557390 -0.2084986418 0.3107928336 3583 1311867289.9855279922 0.0843674093 0.0655135433 0.1180711985 0.0058570609 0.0266620000 48015805 955859216 1373700096 -0.0079066465 -0.2085928172 0.3110868037 3584 1311867290.0232169628 0.0849317610 0.0655189613 0.1180711985 0.0058579963 0.0129860000 48018901 955859216 1373700096 -0.0085263336 -0.2102701217 0.3113906682 3585 1311867290.0535910130 0.0850518495 0.0655244098 0.1180711985 0.0058575898 0.0119640000 48021717 955859216 1373700096 -0.0082129175 -0.2104918957 0.3118416369 3586 1311867290.0854740143 0.0845311582 0.0655297101 0.1180711985 0.0058571581 0.0117060000 48024645 955859216 1373700096 -0.0083254827 -0.2101760954 0.3121917844 3587 1311867290.1248800755 0.0846990421 0.0655350542 0.1180711985 0.0058568076 0.0167940000 48027629 955859216 1373700096 -0.0088283466 -0.2109231353 0.3125045896 3588 1311867290.1536118984 0.0844878927 0.0655403365 0.1180711985 0.0058561595 0.0119150000 48030445 955859216 1373700096 -0.0081200553 -0.2101294845 0.3129906058 3589 1311867290.1856379509 0.0841463059 0.0655455206 0.1180711985 0.0058559790 0.0116800000 48033373 955859216 1373700096 -0.0078287488 -0.2092701346 0.3133046031 3590 1311867290.2225489616 0.0844327584 0.0655507817 0.1180711985 0.0058554331 0.0116080000 48036301 955859216 1373700096 -0.0079607433 -0.2095851451 0.3136096895 3591 1311867290.2540318966 0.0843936950 0.0655560290 0.1180711985 0.0058558303 0.0159520000 48039173 955859216 1373700096 -0.0075193746 -0.2088160217 0.3140825331 3592 1311867290.2892379761 0.0842884108 0.0655612440 0.1180711985 0.0058554293 0.0118840000 48042157 955859216 1373700096 -0.0076630949 -0.2087859660 0.3144355416 3593 1311867290.3220748901 0.0851332098 0.0655666912 0.1180711985 0.0058549481 0.0118380000 48045029 955859216 1373700096 -0.0080551468 -0.2096396983 0.3145718277 3594 1311867290.3587789536 0.0852292255 0.0655721622 0.1180711985 0.0058545025 0.0116840000 48048013 955859216 1373700096 -0.0078372192 -0.2094851583 0.3146312833 3595 1311867290.3864240646 0.0849113315 0.0655775416 0.1180711985 0.0058537453 0.0118170000 48050717 955859216 1373700096 -0.0080263335 -0.2093118429 0.3144951463 3596 1311867290.4216320515 0.0850746259 0.0655829635 0.1180711985 0.0058530666 0.0117930000 48053757 955859216 1373700096 -0.0087405695 -0.2100712061 0.3143297434 3597 1311867290.4578390121 0.0847827643 0.0655883012 0.1180711985 0.0058526201 0.0120220000 48056517 955859216 1373700096 -0.0089295767 -0.2097494453 0.3143379688 3598 1311867290.4859950542 0.0848302022 0.0655936492 0.1180711985 0.0058520168 0.0116670000 48059277 955859216 1373700096 -0.0092923548 -0.2097118199 0.3141827881 3599 1311867290.5223400593 0.0853987783 0.0655991521 0.1180711985 0.0058518187 0.0117460000 48062261 955859216 1373700096 -0.0102554923 -0.2107157409 0.3140154481 3600 1311867290.5537059307 0.0853283405 0.0656046325 0.1180711985 0.0058517668 0.0208280000 48065133 955859216 1373700096 -0.0103333220 -0.2102375776 0.3138889074 3601 1311867290.5855538845 0.0845914632 0.0656099051 0.1180711985 0.0058520014 0.0123370000 48068061 955859216 1373700096 -0.0103278803 -0.2097548693 0.3136077523 3602 1311867290.6221020222 0.0850523561 0.0656153028 0.1180711985 0.0058515986 0.0178350000 48070989 955859216 1373700096 -0.0104478057 -0.2100280672 0.3132744730 3603 1311867290.6536018848 0.0851014480 0.0656207111 0.1180711985 0.0058519312 0.0121020000 48073861 955859216 1373700096 -0.0102192797 -0.2093468159 0.3130456507 3604 1311867290.6857531071 0.0848593637 0.0656260492 0.1180711985 0.0058512380 0.0120700000 48076677 955859216 1373700096 -0.0104971817 -0.2088225484 0.3128513396 3605 1311867290.7256150246 0.0854578242 0.0656315504 0.1180711985 0.0058513554 0.0119430000 48079829 955859216 1373700096 -0.0107992860 -0.2098714709 0.3125936985 3606 1311867290.7539739609 0.0857736617 0.0656371362 0.1180711985 0.0058507917 0.0119120000 48082589 955859216 1373700096 -0.0105438894 -0.2099449039 0.3124085367 3607 1311867290.7866060734 0.0853330866 0.0656425966 0.1180711985 0.0058500440 0.0118480000 48085405 955859216 1373700096 -0.0101979552 -0.2095468789 0.3120424449 3608 1311867290.8231720924 0.0857634693 0.0656481734 0.1180711985 0.0058497391 0.0118430000 48088445 955859216 1373700096 -0.0100004338 -0.2103726864 0.3115615547 3609 1311867290.8556039333 0.0857546255 0.0656537446 0.1180711985 0.0058491007 0.0117180000 48091317 955859216 1373700096 -0.0097842254 -0.2106952220 0.3111982644 3610 1311867290.8876988888 0.0861434340 0.0656594204 0.1180711985 0.0058517941 0.0116880000 48094189 955859216 1373700096 -0.0092435898 -0.2105537653 0.3108223677 3611 1311867290.9227120876 0.0860765427 0.0656650745 0.1180711985 0.0058510246 0.0116480000 48097117 955859216 1373700096 -0.0088366987 -0.2109406590 0.3103625178 3612 1311867290.9537110329 0.0856848136 0.0656706171 0.1180711985 0.0058526878 0.0214000000 48099989 955859216 1373700096 -0.0085195396 -0.2115694582 0.3101007640 3613 1311867290.9906909466 0.0855359584 0.0656761154 0.1180711985 0.0058520278 0.0122560000 48103029 955859216 1373700096 -0.0081341527 -0.2116384804 0.3097845614 3614 1311867291.0239291191 0.0854476392 0.0656815862 0.1180711985 0.0058514872 0.0120340000 48105957 955859216 1373700096 -0.0076763374 -0.2118986249 0.3095159233 3615 1311867291.0558199883 0.0857354254 0.0656871336 0.1180711985 0.0058508261 0.0117490000 48108829 955859216 1373700096 -0.0070970915 -0.2125908285 0.3092586398 3616 1311867291.0934820175 0.0854148939 0.0656925893 0.1180711985 0.0058505521 0.0117930000 48111813 955859216 1373700096 -0.0061459625 -0.2118655145 0.3089771271 3617 1311867291.1203110218 0.0850977078 0.0656979543 0.1180711985 0.0058500900 0.0284370000 48114573 955859216 1373700096 -0.0056980508 -0.2119246423 0.3085348308 3618 1311867291.1541891098 0.0859434158 0.0657035500 0.1180711985 0.0058509123 0.0128920000 48117389 955859216 1373700096 -0.0054593654 -0.2124780715 0.3081028461 3619 1311867291.1891989708 0.0851149708 0.0657089138 0.1180711985 0.0058515286 0.0120430000 48120373 955859216 1373700096 -0.0047072126 -0.2118857503 0.3077912033 3620 1311867291.2211010456 0.0852155015 0.0657143023 0.1180711985 0.0058510129 0.0119350000 48123245 955859216 1373700096 -0.0043290844 -0.2122803330 0.3073765039 3621 1311867291.2543909550 0.0852816924 0.0657197062 0.1180711985 0.0058503196 0.0116900000 48126173 955859216 1373700096 -0.0040281974 -0.2123578489 0.3070896268 3622 1311867291.2877960205 0.0851859674 0.0657250807 0.1180711985 0.0058495421 0.0161680000 48129045 955859216 1373700096 -0.0032940703 -0.2120939642 0.3067308068 3623 1311867291.3210899830 0.0856301561 0.0657305747 0.1180711985 0.0058491000 0.0118650000 48131917 955859216 1373700096 -0.0030152581 -0.2127229571 0.3063082695 3624 1311867291.3547959328 0.0858417451 0.0657361242 0.1180711985 0.0058483593 0.0118390000 48134901 955859216 1373700096 -0.0027638250 -0.2130269259 0.3059287369 3625 1311867291.3878760338 0.0855569616 0.0657415920 0.1180711985 0.0058478933 0.0117560000 48137773 955859216 1373700096 -0.0024682446 -0.2126691937 0.3055133522 3626 1311867291.4223349094 0.0855989680 0.0657470684 0.1180711985 0.0058472678 0.0161050000 48140701 955859216 1373700096 -0.0025612079 -0.2129993290 0.3051488996 3627 1311867291.4536559582 0.0858273432 0.0657526047 0.1180711985 0.0058465799 0.0122790000 48143573 955859216 1373700096 -0.0021495018 -0.2134972513 0.3047534525 3628 1311867291.4883999825 0.0855171904 0.0657580525 0.1180711985 0.0058461756 0.0120440000 48146501 955859216 1373700096 -0.0017797310 -0.2130631506 0.3044457138 3629 1311867291.5201730728 0.0852419436 0.0657634214 0.1180711985 0.0058454838 0.0120500000 48149429 955859216 1373700096 -0.0014113412 -0.2129006386 0.3042369187 3630 1311867291.5536448956 0.0852581635 0.0657687919 0.1180711985 0.0058448378 0.0119730000 48152301 955859216 1373700096 -0.0016462294 -0.2132274508 0.3039365411 3631 1311867291.5895080566 0.0854293928 0.0657742066 0.1180711985 0.0058445754 0.0119720000 48155285 955859216 1373700096 -0.0011845148 -0.2127689719 0.3037357032 3632 1311867291.6206870079 0.0850105658 0.0657795029 0.1180711985 0.0058446522 0.0159130000 48158101 955859216 1373700096 -0.0013445180 -0.2131423205 0.3033360839 3633 1311867291.6539781094 0.0851448327 0.0657848333 0.1180711985 0.0058439957 0.0125510000 48161029 955859216 1373700096 -0.0014288974 -0.2135749161 0.3031735420 3634 1311867291.6896810532 0.0851995721 0.0657901758 0.1180711985 0.0058432402 0.0122280000 48164013 955859216 1373700096 -0.0010351806 -0.2132878900 0.3029836118 3635 1311867291.7202739716 0.0851733461 0.0657955082 0.1180711985 0.0058425825 0.0119840000 48166829 955859216 1373700096 -0.0011165699 -0.2137553096 0.3026501536 3636 1311867291.7537178993 0.0850643739 0.0658008077 0.1180711985 0.0058423152 0.0119000000 48169757 955859216 1373700096 -0.0013006879 -0.2141471505 0.3024011552 3637 1311867291.7890019417 0.0848111361 0.0658060346 0.1180711985 0.0058422593 0.0119320000 48172741 955859216 1373700096 -0.0007744093 -0.2135583013 0.3022522032 3638 1311867291.8217189312 0.0849798992 0.0658113050 0.1180711985 0.0058421773 0.0119460000 48175557 955859216 1373700096 -0.0008478409 -0.2142566442 0.3022359312 3639 1311867291.8538639545 0.0850987881 0.0658166052 0.1180711985 0.0058416320 0.0161650000 48178485 955859216 1373700096 -0.0007175508 -0.2143591940 0.3023598492 3640 1311867291.8879489899 0.0850575343 0.0658218912 0.1180711985 0.0058416968 0.0122790000 48181357 955859216 1373700096 -0.0008516978 -0.2140387446 0.3024426997 3641 1311867291.9206929207 0.0850248635 0.0658271653 0.1180711985 0.0058411703 0.0123890000 48184341 955859216 1373700096 -0.0009848045 -0.2142040133 0.3024278581 3642 1311867291.9537200928 0.0852273703 0.0658324921 0.1180711985 0.0058411699 0.0122270000 48187157 955859216 1373700096 -0.0004817739 -0.2139996439 0.3026417792 3643 1311867291.9902889729 0.0851152167 0.0658377852 0.1180711985 0.0058417960 0.0119830000 48190197 955859216 1373700096 -0.0001303121 -0.2141798586 0.3028528392 3644 1311867292.0225260258 0.0855754912 0.0658432017 0.1180711985 0.0058443513 0.0119900000 48193069 955859216 1373700096 0.0000921668 -0.2140242010 0.3030415475 3645 1311867292.0536830425 0.0857013762 0.0658486498 0.1180711985 0.0058438446 0.0179400000 48195885 955859216 1373700096 0.0000329895 -0.2139024884 0.3032146394 3646 1311867292.0922849178 0.0850373060 0.0658539127 0.1180711985 0.0058457300 0.0123600000 48198925 955859216 1373700096 0.0002463730 -0.2138672918 0.3034440577 3647 1311867292.1243879795 0.0848735943 0.0658591278 0.1180711985 0.0058450770 0.0119740000 48201741 955859216 1373700096 0.0001968139 -0.2134677917 0.3036336899 3648 1311867292.1602649689 0.0848653466 0.0658643379 0.1180711985 0.0058443446 0.0118980000 48204725 955859216 1373700096 0.0003722971 -0.2131306380 0.3039378226 3649 1311867292.1899850368 0.0848998204 0.0658695545 0.1180711985 0.0058436354 0.0118160000 48207541 955859216 1373700096 0.0003339260 -0.2132077068 0.3041331470 3650 1311867292.2207419872 0.0851154476 0.0658748274 0.1180711985 0.0058428380 0.0117870000 48210301 955859216 1373700096 0.0002352386 -0.2133146226 0.3044142127 3651 1311867292.2576909065 0.0851401836 0.0658801041 0.1180711985 0.0058420966 0.0117300000 48213341 955859216 1373700096 0.0001844425 -0.2132775038 0.3046643436 3652 1311867292.2878270149 0.0852644071 0.0658854120 0.1180711985 0.0058413129 0.0171410000 48216157 955859216 1373700096 -0.0001445628 -0.2135163248 0.3048659265 3653 1311867292.3217270374 0.0845749751 0.0658905282 0.1180711985 0.0058428644 0.0122580000 48219029 955859216 1373700096 -0.0004594403 -0.2137391269 0.3050166070 3654 1311867292.3621709347 0.0851461664 0.0658957979 0.1180711985 0.0058445200 0.0125800000 48222181 955859216 1373700096 -0.0008175309 -0.2138949037 0.3051467836 3655 1311867292.3953619003 0.0851063505 0.0659010539 0.1180711985 0.0058437534 0.0121060000 48225109 955859216 1373700096 -0.0011200474 -0.2140790969 0.3052002490 3656 1311867292.4259300232 0.0852584466 0.0659063486 0.1180711985 0.0058430676 0.0120030000 48227925 955859216 1373700096 -0.0014695826 -0.2144541591 0.3052478433 3657 1311867292.4565210342 0.0852750689 0.0659116449 0.1180711985 0.0058423429 0.0120040000 48230685 955859216 1373700096 -0.0014004441 -0.2147559375 0.3052971065 3658 1311867292.4883699417 0.0853338316 0.0659169544 0.1180711985 0.0058415707 0.0120360000 48233613 955859216 1373700096 -0.0016202433 -0.2150153518 0.3053075671 3659 1311867292.5229649544 0.0852092728 0.0659222270 0.1180711985 0.0058407810 0.0120270000 48236541 955859216 1373700096 -0.0018188511 -0.2151940465 0.3052908182 3660 1311867292.5581150055 0.0848533884 0.0659273994 0.1180711985 0.0058400342 0.0120410000 48239469 955859216 1373700096 -0.0016265515 -0.2146631181 0.3054073751 3661 1311867292.5882439613 0.0847313628 0.0659325357 0.1180711985 0.0058394424 0.0119950000 48242341 955859216 1373700096 -0.0016038351 -0.2144336253 0.3056166470 3662 1311867292.6230869293 0.0848268792 0.0659376953 0.1180711985 0.0058386727 0.0270610000 48245269 955859216 1373700096 -0.0016136629 -0.2143764198 0.3058480024 3663 1311867292.6595211029 0.0847451761 0.0659428298 0.1180711985 0.0058378815 0.0131140000 48248309 955859216 1373700096 -0.0014356555 -0.2140463740 0.3060922027 3664 1311867292.6880218983 0.0850671902 0.0659480493 0.1180711985 0.0058373397 0.0122080000 48251013 955859216 1373700096 -0.0017230497 -0.2148155868 0.3062107563 3665 1311867292.7206969261 0.0851573274 0.0659532906 0.1180711985 0.0058365805 0.0174900000 48253941 955859216 1373700096 -0.0016579541 -0.2149169743 0.3064056337 3666 1311867292.7561879158 0.0848537013 0.0659584462 0.1180711985 0.0058358546 0.0123100000 48256925 955859216 1373700096 -0.0013364544 -0.2145900130 0.3065602481 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:37:09 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000001192 0.0000001192 0.0000001192 -nan 0.9999490000 0.1849090000 0.0279470000 0.0759390000 0.0000030000 0.7110390000 106164926 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0071111759 0.0035556476 0.0071111759 0.0073250057 0.3038350000 0.1973290000 0.0260170000 0.0759180000 0.0000000000 0.0045300000 113250179 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0160688832 0.0077267261 0.0160688832 0.0105653904 0.2913530000 0.1847370000 0.0261320000 0.0759110000 0.0000000000 0.0045340000 113253347 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0069097765 0.0075224887 0.0160688832 0.0105835547 0.9945640000 0.1925650000 0.0260100000 0.0759660000 0.6954540000 0.0045310000 113256523 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0087667275 0.0077713365 0.0160688832 0.0110948651 1.7852980000 0.1849780000 0.1253630000 0.0765620000 0.6877790000 0.7105740000 113259683 0 402718720 4.0003609657 4.0041584969 3.9997618198 6 0.2000000000 0.0088930950 0.0079582962 0.0160688832 0.0099833355 0.6269720000 0.1276860000 0.0483750000 0.0000000000 0.4489460000 0.0019210000 113263259 0 402718720 4.0005426407 3.9987919331 4.0005846024 7 0.2400000000 0.0089947172 0.0081063564 0.0160688832 0.0091706648 0.6370290000 0.1057380000 0.0458410000 0.0352620000 0.4482130000 0.0019310000 113266035 0 402718720 4.0003776550 3.9986178875 4.0004811287 8 0.2800000000 0.0089779021 0.0082152996 0.0160688832 0.0085523253 0.6150060000 0.1195940000 0.0453790000 0.0000010000 0.4480570000 0.0019260000 113268811 0 402718720 4.0010104179 4.0014657974 4.0004425049 9 0.3200000000 0.0089545501 0.0082974385 0.0160688832 0.0080187039 1.0993110000 0.1058420000 0.0554660000 0.0353060000 0.4481300000 0.4545140000 113272355 0 402718720 4.0009670258 4.0013694763 4.0000152588 10 0.3600000000 0.0091754040 0.0083852351 0.0160688832 0.0075716634 0.6189700000 0.1057350000 0.0578580000 0.0000010000 0.4526330000 0.0026920000 113276731 0 402718720 4.0024089813 4.0002012253 4.0001807213 11 0.4000000000 0.0092245769 0.0084615389 0.0160688832 0.0072053832 0.7126030000 0.1344200000 0.0745690000 0.0444490000 0.4571870000 0.0019300000 113279507 0 402718720 4.0023021698 3.9996802807 4.0003638268 12 0.4400000000 0.0093334951 0.0085342019 0.0160688832 0.0068918608 0.6129130000 0.1059680000 0.0555160000 0.0000010000 0.4494480000 0.0019310000 113282283 0 402718720 4.0025787354 4.0002465248 3.9998211861 13 0.4800000000 0.0092639755 0.0085903383 0.0160688832 0.0067038797 1.1068480000 0.1091610000 0.0589400000 0.0348210000 0.4487750000 0.4550960000 113285059 0 402718720 4.0026950836 4.0017895699 3.9992957115 14 0.5200000000 0.0092736362 0.0086391453 0.0160688832 0.0065179718 0.6145470000 0.1059140000 0.0579670000 0.0000010000 0.4486760000 0.0019360000 113287835 0 402718720 4.0027508736 4.0027585030 3.9991116524 15 0.5600000000 0.0092612300 0.0086806176 0.0160688832 0.0062904905 0.6565480000 0.1057700000 0.0650010000 0.0353280000 0.4484620000 0.0019330000 113290611 0 402718720 4.0029397011 4.0034251213 3.9985945225 16 0.6000000000 0.0093297996 0.0087211915 0.0160688832 0.0060789093 0.6114970000 0.1056890000 0.0553630000 0.0000000000 0.4484620000 0.0019290000 113293387 0 402718720 4.0029802322 4.0033140182 3.9983277321 17 0.6400000000 0.0093143089 0.0087560808 0.0160688832 0.0058993499 1.0996440000 0.1057860000 0.0553780000 0.0352640000 0.4485660000 0.4545900000 113297699 0 402718720 4.0021824837 4.0039443970 3.9977533817 18 0.6800000000 0.0094567277 0.0087950056 0.0160688832 0.0057494188 0.6025930000 0.1058470000 0.0458610000 0.0000000000 0.4488910000 0.0019350000 113303675 0 402718720 4.0026183128 4.0052161217 3.9974815845 19 0.7200000000 0.0094302874 0.0088284415 0.0160688832 0.0057144288 0.6567890000 0.1145800000 0.0581110000 0.0353580000 0.4467420000 0.0019370000 113306451 0 402718720 4.0038194656 4.0056333542 3.9974064827 20 0.7600000000 0.0095038619 0.0088622125 0.0160688832 0.0055638433 0.6041230000 0.1059120000 0.0480290000 0.0000000000 0.4481880000 0.0019320000 113309227 0 402718720 4.0043606758 4.0057182312 3.9969446659 21 0.8000000000 0.0095046833 0.0088928063 0.0160688832 0.0054229898 1.1009620000 0.1031280000 0.0549420000 0.0352620000 0.4504870000 0.4570800000 113312003 0 402718720 4.0034151077 4.0065183640 3.9971866608 22 0.8400000000 0.0097127324 0.0089300757 0.0160688832 0.0052924464 0.6087880000 0.1061120000 0.0482510000 0.0000010000 0.4524240000 0.0019370000 113314779 0 402718720 4.0030841827 4.0064840317 3.9969151020 23 0.8800000000 0.0096084243 0.0089595691 0.0160688832 0.0051708165 0.6474770000 0.1034260000 0.0549380000 0.0344820000 0.4526280000 0.0019380000 113317555 0 402718720 4.0035991669 4.0055513382 3.9970743656 24 0.9200000000 0.0097360928 0.0089919243 0.0160688832 0.0050608833 0.6071380000 0.1063530000 0.0459770000 0.0000000000 0.4528120000 0.0019310000 113320331 0 402718720 4.0043063164 4.0053038597 3.9973998070 25 0.9600000000 0.0098110326 0.0090246886 0.0160688832 0.0049609048 1.0989850000 0.1064610000 0.0459950000 0.0353660000 0.4525070000 0.4585850000 113323107 0 402718720 4.0055928230 4.0052309036 3.9976959229 26 1.0000000000 0.0097867167 0.0090539974 0.0160688832 0.0048627339 0.6140890000 0.1067110000 0.0484810000 0.0000000000 0.4561420000 0.0026760000 113325883 0 402718720 4.0052080154 4.0047221184 3.9974107742 27 1.0400000000 0.0098243309 0.0090825282 0.0160688832 0.0047731464 0.7203400000 0.1355230000 0.0778880000 0.0445480000 0.4603780000 0.0019320000 113328659 0 402718720 4.0053777695 4.0054135323 3.9974813461 28 1.0800000000 0.0098536927 0.0091100698 0.0160688832 0.0047021689 0.6210000000 0.1069440000 0.0580860000 0.0000010000 0.4539720000 0.0019260000 113331435 0 402718720 4.0071635246 4.0042719841 3.9975636005 29 1.1200000000 0.0098079508 0.0091341347 0.0160688832 0.0047713040 1.1340120000 0.1211170000 0.0651110000 0.0353160000 0.4530470000 0.4593450000 113334211 0 402718720 4.0084033012 4.0047941208 3.9976210594 30 1.1600000000 0.0098484280 0.0091579445 0.0160688832 0.0049240496 0.6195630000 0.1076960000 0.0556040000 0.0000010000 0.4542520000 0.0019340000 113336987 0 402718720 4.0077061653 4.0033121109 3.9978673458 31 1.2000000000 0.0098978737 0.0091818132 0.0160688832 0.0050149506 0.6568880000 0.1079330000 0.0579970000 0.0354200000 0.4535330000 0.0019300000 113339763 0 402718720 4.0099506378 4.0036349297 3.9980351925 32 1.2400000000 0.0099975374 0.0092073045 0.0160688832 0.0052970900 0.6200260000 0.1064250000 0.0556010000 0.0000010000 0.4559920000 0.0019270000 113342539 0 402718720 4.0117006302 4.0049104691 3.9983918667 33 1.2800000000 0.0100069633 0.0092315366 0.0160688832 0.0055427556 1.1205400000 0.1089740000 0.0577330000 0.0354340000 0.4560940000 0.4622230000 113348387 0 402718720 4.0115060806 4.0043516159 3.9992022514 34 1.3200000000 0.0100308405 0.0092550456 0.0160688832 0.0056836623 0.6170480000 0.1094240000 0.0468030000 0.0000010000 0.4588000000 0.0019370000 113357563 0 402718720 4.0110921860 4.0041384697 3.9999632835 35 1.3600000000 0.0100617008 0.0092780929 0.0160688832 0.0060317781 0.6578050000 0.1067710000 0.0548420000 0.0351850000 0.4589820000 0.0019380000 113360339 0 402718720 4.0113382339 4.0047774315 4.0006189346 36 1.4000000000 0.0101703657 0.0093028782 0.0160688832 0.0063434210 0.6303220000 0.1104410000 0.0550510000 0.0000010000 0.4628650000 0.0018780000 113363115 0 402718720 4.0127167702 4.0032405853 4.0015172958 37 1.4400000000 0.0101698842 0.0093263108 0.0160688832 0.0067312779 1.1399660000 0.1108680000 0.0434300000 0.0355440000 0.4692010000 0.4808330000 113365891 0 402718720 4.0137434006 4.0032958984 4.0020494461 38 1.4800000000 0.0101781487 0.0093487276 0.0160688832 0.0085630053 0.6385270000 0.1113080000 0.0579950000 0.0000000000 0.4671940000 0.0019380000 113368667 0 402718720 4.0152249336 4.0024065971 4.0038027763 39 1.5200000000 0.0102096563 0.0093708027 0.0160688832 0.0088484018 0.6886630000 0.1281100000 0.0576740000 0.0352430000 0.4655960000 0.0019430000 113371443 0 402718720 4.0167517662 4.0026597977 4.0048270226 40 1.5600000000 0.0102482494 0.0093927389 0.0160688832 0.0089642662 0.6495850000 0.1115320000 0.0672830000 0.0000010000 0.4687340000 0.0019420000 113374219 0 402718720 4.0180807114 4.0025238991 4.0051808357 41 1.6000000000 0.0102015967 0.0094124671 0.0160688832 0.0091032828 1.1619830000 0.1245140000 0.0576800000 0.0357070000 0.4684890000 0.4754980000 113376995 0 402718720 4.0196819305 3.9989571571 4.0066704750 42 1.6400000000 0.0103022177 0.0094336516 0.0160688832 0.0092233538 0.6421350000 0.1116360000 0.0554380000 0.0000000000 0.4730900000 0.0018760000 113379771 0 402718720 4.0214962959 3.9992222786 4.0070328712 43 1.6800000000 0.0102144005 0.0094518086 0.0160688832 0.0094675654 0.6738770000 0.1093300000 0.0551480000 0.0358180000 0.4716130000 0.0018760000 113382547 0 402718720 4.0233302116 4.0014257431 4.0075716972 44 1.7200000000 0.0103026470 0.0094711458 0.0160688832 0.0097001134 0.6574130000 0.1220900000 0.0606660000 0.0000010000 0.4726170000 0.0019390000 113385323 0 402718720 4.0246386528 4.0030379295 4.0085287094 45 1.7600000000 0.0103136469 0.0094898681 0.0160688832 0.0099992774 1.1846850000 0.1350470000 0.0572840000 0.0354170000 0.4747680000 0.4820690000 113388099 0 402718720 4.0266637802 4.0009579659 4.0096273422 46 1.8000000000 0.0103841182 0.0095093083 0.0160688832 0.0112156523 0.6464640000 0.1079660000 0.0604450000 0.0000000000 0.4760140000 0.0019370000 113390875 0 402718720 4.0545296669 4.0005726814 4.0058226585 47 1.8400000000 0.0104420763 0.0095291544 0.0160688832 0.0111216992 0.6718590000 0.1116460000 0.0460300000 0.0359620000 0.4761750000 0.0019450000 113393651 0 402718720 4.1148071289 3.9972991943 3.9947819710 48 1.8800000000 0.0104260491 0.0095478397 0.0160688832 0.0112452398 0.6523150000 0.1116930000 0.0586940000 0.0000010000 0.4798890000 0.0019360000 113396427 0 402718720 4.1174712181 3.9970273972 3.9951250553 49 1.9200000000 0.0104605220 0.0095664659 0.0160688832 0.0113768337 1.1797370000 0.1219300000 0.0578360000 0.0356560000 0.4768160000 0.4873890000 113399203 0 402718720 4.1196966171 3.9960007668 3.9954032898 50 1.9600000000 0.0104673868 0.0095844843 0.0160688832 0.0114532760 0.6543410000 0.1118090000 0.0578760000 0.0000010000 0.4826170000 0.0019330000 113401979 0 402718720 4.1222162247 3.9957606792 3.9956457615 51 2.0000000000 0.0104683200 0.0096018144 0.0160688832 0.0115121093 0.7029810000 0.1246720000 0.0575490000 0.0360030000 0.4827080000 0.0019350000 113404755 0 402718720 4.1250910759 3.9947535992 3.9954471588 52 2.0400000000 0.0104810745 0.0096187233 0.0160688832 0.0115605838 0.6684020000 0.1118820000 0.0554130000 0.0000000000 0.4982960000 0.0026890000 113407531 0 402718720 4.1281352043 3.9938495159 3.9954857826 53 2.0800000000 0.0105333524 0.0096359804 0.0160688832 0.0115827710 1.2432490000 0.1440020000 0.0771070000 0.0426070000 0.4854280000 0.4939930000 113410307 0 402718720 4.1294550896 3.9930112362 3.9955632687 54 2.1200000000 0.0105564846 0.0096530268 0.0160688832 0.0116035865 0.6599280000 0.1117980000 0.0577580000 0.0000000000 0.4883950000 0.0018640000 113413083 0 402718720 4.1326694489 3.9933810234 3.9951083660 55 2.1600000000 0.0106123807 0.0096704696 0.0160688832 0.0116330562 0.7273960000 0.1342490000 0.0698730000 0.0365460000 0.4847050000 0.0019020000 113415859 0 402718720 4.1358623505 3.9955952168 3.9941723347 56 2.2000000000 0.0106686242 0.0096882938 0.0160688832 0.0116961561 0.6561140000 0.1118550000 0.0543380000 0.0000010000 0.4879190000 0.0018880000 113418635 0 402718720 4.1371884346 3.9941446781 3.9940123558 57 2.2400000000 0.0107586738 0.0097070724 0.0160688832 0.0118339064 1.1805910000 0.1119370000 0.0445780000 0.0365260000 0.4875560000 0.4998810000 113421411 0 402718720 4.1364507675 3.9915580750 3.9946136475 58 2.2800000000 0.0107774092 0.0097255265 0.0160688832 0.0119855047 0.6547100000 0.1079870000 0.0557290000 0.0000010000 0.4890240000 0.0018510000 113424187 0 402718720 4.1382780075 3.9904229641 3.9942324162 59 2.3200000000 0.0111008249 0.0097488366 0.0160688832 0.0122076356 0.7182650000 0.1395590000 0.0529870000 0.0361090000 0.4876420000 0.0018410000 113426963 0 402718720 4.1396369934 3.9901521206 3.9937374592 60 2.3600000000 0.0110469693 0.0097704721 0.0160688832 0.0123709307 0.6583970000 0.1120870000 0.0578010000 0.0000010000 0.4865530000 0.0018320000 113429739 0 402718720 4.1425590515 3.9892640114 3.9925780296 61 2.4000000000 0.0108104786 0.0097875214 0.0160688832 0.0126405191 1.1973490000 0.1121100000 0.0546430000 0.0368030000 0.4872680000 0.5063900000 113432515 0 402718720 4.1448273659 3.9888403416 3.9923024178 62 2.4400000000 0.0106492359 0.0098014201 0.0160688832 0.0128730082 0.7186240000 0.1445860000 0.0735970000 0.0000010000 0.4985020000 0.0018140000 113435291 0 402718720 4.1487517357 3.9886188507 3.9910035133 63 2.4800000000 0.0105467886 0.0098132513 0.0160688832 0.0130843895 0.6902100000 0.1122110000 0.0524440000 0.0363520000 0.4872660000 0.0018130000 113438067 0 402718720 4.1524329185 3.9891073704 3.9898703098 64 2.5200000000 0.0104767922 0.0098236191 0.0160688832 0.0132256071 0.6658470000 0.1123250000 0.0627710000 0.0000010000 0.4888150000 0.0017960000 113440843 0 402718720 4.1564545631 3.9871284962 3.9881901741 65 2.5600000000 0.0103913285 0.0098323531 0.0160688832 0.0133255696 1.1980980000 0.1123700000 0.0557480000 0.0365060000 0.4870400000 0.5063020000 113449763 0 402718720 4.1605582237 3.9873204231 3.9863116741 66 2.6000000000 0.0104169110 0.0098412101 0.0160688832 0.0134083795 0.6544780000 0.1124050000 0.0513500000 0.0000010000 0.4887980000 0.0017930000 113465339 0 402718720 4.1650896072 3.9864213467 3.9840264320 67 2.6400000000 0.0104648126 0.0098505176 0.0160688832 0.0135120997 0.6890590000 0.1125410000 0.0508820000 0.0370810000 0.4866290000 0.0017960000 113468115 0 402718720 4.1683750153 3.9859824181 3.9820284843 68 2.6800000000 0.0104670096 0.0098595836 0.0160688832 0.0136249891 0.6520370000 0.1085310000 0.0528470000 0.0000010000 0.4887420000 0.0017850000 113470891 0 402718720 4.1730446815 3.9862711430 3.9792447090 69 2.7200000000 0.0104662422 0.0098683758 0.0160688832 0.0137342074 1.1953460000 0.1127030000 0.0506520000 0.0372230000 0.4863680000 0.5082680000 113473667 0 402718720 4.1764059067 3.9842488766 3.9773914814 70 2.7600000000 0.0104967989 0.0098773532 0.0160688832 0.0139063855 0.6497090000 0.1086490000 0.0504440000 0.0000010000 0.4886970000 0.0017830000 113476443 0 402718720 4.1786746979 3.9828863144 3.9764397144 71 2.8000000000 0.0105376504 0.0098866532 0.0160688832 0.0140153316 0.6870570000 0.1127620000 0.0505040000 0.0367630000 0.4851130000 0.0017790000 113479219 0 402718720 4.1827130318 3.9834725857 3.9741680622 72 2.8400000000 0.0105718682 0.0098961701 0.0160688832 0.0141736207 0.6436030000 0.1128340000 0.0420640000 0.0000010000 0.4867950000 0.0017710000 113481995 0 402718720 4.1854767799 3.9834394455 3.9726927280 73 2.8800000000 0.0105731152 0.0099054433 0.0160688832 0.0142968715 1.1871990000 0.1087880000 0.0498560000 0.0369690000 0.4839290000 0.5075180000 113484771 0 402718720 4.1877613068 3.9828777313 3.9714314938 74 2.9200000000 0.0105859833 0.0099146398 0.0160688832 0.0143758291 0.6506800000 0.1129390000 0.0505110000 0.0000010000 0.4853250000 0.0017620000 113487547 0 402718720 4.1921977997 3.9825434685 3.9686732292 75 2.9600000000 0.0106244143 0.0099241034 0.0160688832 0.0145126434 0.6987350000 0.1272240000 0.0501700000 0.0371450000 0.4822860000 0.0017640000 113490323 0 402718720 4.1937527657 3.9826734066 3.9677977562 76 3.0000000000 0.0106401620 0.0099335253 0.0160688832 0.0145452049 0.6453900000 0.1089570000 0.0498420000 0.0000010000 0.4846890000 0.0017600000 113493099 0 402718720 4.1987738609 3.9801769257 3.9646968842 77 3.0400000000 0.0106199253 0.0099424396 0.0160688832 0.0146117343 1.1899390000 0.1131290000 0.0499600000 0.0371170000 0.4822600000 0.5073280000 113495875 0 402718720 4.2017226219 3.9788901806 3.9626338482 78 3.0800000000 0.0106502697 0.0099515143 0.0160688832 0.0146263692 0.6401110000 0.1131440000 0.0416500000 0.0000010000 0.4834050000 0.0017630000 113498651 0 402718720 4.2062644958 3.9779863358 3.9592096806 79 3.1200000000 0.0106206974 0.0099599850 0.0160688832 0.0146746616 0.6794290000 0.1111240000 0.0498220000 0.0369670000 0.4796090000 0.0017600000 113501427 0 402718720 4.2103214264 3.9775955677 3.9566628933 80 3.1600000000 0.0106643122 0.0099687891 0.0160688832 0.0150949753 0.6350420000 0.1091040000 0.0410590000 0.0000000000 0.4829750000 0.0017550000 113504203 0 402718720 4.2188949585 3.9765052795 3.9505164623 81 3.2000000000 0.0106044142 0.0099766363 0.0160688832 0.0151187611 1.2169120000 0.1385030000 0.0519700000 0.0376590000 0.4749330000 0.5136700000 113506979 0 402718720 4.2228779793 3.9761021137 3.9480280876 82 3.2400000000 0.0105653852 0.0099838162 0.0160688832 0.0151217858 0.7016110000 0.1461120000 0.0678090000 0.0000000000 0.4857870000 0.0017510000 113509755 0 402718720 4.2262153625 3.9731538296 3.9456999302 83 3.2800000000 0.0105850538 0.0099910600 0.0160688832 0.0151677927 0.6808950000 0.1133960000 0.0496830000 0.0379780000 0.4779300000 0.0017540000 113512531 0 402718720 4.2293882370 3.9728453159 3.9436094761 84 3.3200000000 0.0105674518 0.0099979218 0.0160688832 0.0151575902 0.6487570000 0.1096070000 0.0498480000 0.0000010000 0.4867440000 0.0023840000 113515307 0 402718720 4.2316341400 3.9699101448 3.9422283173 85 3.3600000000 0.0105741862 0.0100047014 0.0160688832 0.0151676481 1.2425720000 0.1462310000 0.0645080000 0.0483570000 0.4779870000 0.5053300000 113518083 0 402718720 4.2349843979 3.9685502052 3.9399809837 86 3.4000000000 0.0105877230 0.0100114807 0.0160688832 0.0152070777 0.6449630000 0.1121720000 0.0519740000 0.0000010000 0.4789050000 0.0017490000 113520859 0 402718720 4.2370381355 3.9673917294 3.9387700558 87 3.4400000000 0.0105743222 0.0100179501 0.0160688832 0.0152298108 0.6793350000 0.1133940000 0.0495480000 0.0376940000 0.4767970000 0.0017450000 113523635 0 402718720 4.2407021523 3.9668848515 3.9364335537 88 3.4800000000 0.0105117382 0.0100235614 0.0160688832 0.0152495106 0.6427130000 0.1134710000 0.0497310000 0.0000000000 0.4776040000 0.0017460000 113526411 0 402718720 4.2443609238 3.9676401615 3.9338674545 89 3.5200000000 0.0105467429 0.0100294398 0.0160688832 0.0152525397 1.1794780000 0.1134930000 0.0494350000 0.0376290000 0.4747050000 0.5040510000 113529187 0 402718720 4.2471618652 3.9671533108 3.9318206310 90 3.5600000000 0.0106056351 0.0100358420 0.0160688832 0.0152590583 0.6409360000 0.1134130000 0.0496170000 0.0000010000 0.4759950000 0.0017430000 113531963 0 402718720 4.2493805885 3.9651312828 3.9302570820 91 3.6000000000 0.0105669638 0.0100416785 0.0160688832 0.0152745541 0.6754830000 0.1092170000 0.0509980000 0.0372790000 0.4760760000 0.0017440000 113534739 0 402718720 4.2518315315 3.9643185139 3.9286942482 92 3.6400000000 0.0105852969 0.0100475874 0.0160688832 0.0152691263 0.6341920000 0.1134730000 0.0433120000 0.0000000000 0.4754990000 0.0017390000 113537515 0 402718720 4.2548913956 3.9651730061 3.9266314507 93 3.6800000000 0.0105870599 0.0100533882 0.0160688832 0.0152321872 1.1766130000 0.1134990000 0.0493250000 0.0371510000 0.4731740000 0.5032950000 113540291 0 402718720 4.2570395470 3.9638454914 3.9247627258 94 3.7200000000 0.0106400410 0.0100596291 0.0160688832 0.0151942495 0.6648810000 0.1135040000 0.0748600000 0.0000010000 0.4746030000 0.0017420000 113543067 0 402718720 4.2595472336 3.9633386135 3.9234151840 95 3.7600000000 0.0106442487 0.0100657830 0.0160688832 0.0151521074 0.7284470000 0.1299120000 0.0670690000 0.0485320000 0.4810130000 0.0017460000 113545843 0 402718720 4.2627453804 3.9636592865 3.9212799072 96 3.8000000000 0.0105484109 0.0100708104 0.0160688832 0.0151069913 0.6325730000 0.1135090000 0.0452910000 0.0000000000 0.4718540000 0.0017420000 113548619 0 402718720 4.2653336525 3.9632313251 3.9189243317 97 3.8400000000 0.0105836643 0.0100760976 0.0160688832 0.0150700704 1.2032630000 0.1430600000 0.0471330000 0.0376870000 0.4722250000 0.5029790000 113551395 0 402718720 4.2676563263 3.9629859924 3.9169063568 98 3.8800000000 0.0105485236 0.0100809182 0.0160688832 0.0150265486 0.6373960000 0.1135500000 0.0518670000 0.0000010000 0.4700580000 0.0017410000 113554171 0 402718720 4.2686123848 3.9618430138 3.9162461758 99 3.9200000000 0.0106240446 0.0100864044 0.0160688832 0.0149725593 0.6777040000 0.1135440000 0.0538300000 0.0379060000 0.4705020000 0.0017430000 113556947 0 402718720 4.2713360786 3.9612932205 3.9140307903 100 3.9600000000 0.0107040433 0.0100925807 0.0160688832 0.0149198022 0.6402390000 0.1135670000 0.0511100000 0.0000010000 0.4736420000 0.0017410000 113559723 0 402718720 4.2728753090 3.9599680901 3.9127550125 101 4.0000000000 0.0107474830 0.0100990649 0.0160688832 0.0148706140 1.1847290000 0.1135300000 0.0514840000 0.0371540000 0.4705230000 0.5118340000 113562499 0 402718720 4.2753453255 3.9618122578 3.9112653732 102 4.0400000000 0.0106475716 0.0101044424 0.0160688832 0.0148249154 0.6910150000 0.1467380000 0.0672770000 0.0000000000 0.4750760000 0.0017450000 113565275 0 402718720 4.2774748802 3.9623346329 3.9096415043 103 4.0800000000 0.0107284253 0.0101105005 0.0160688832 0.0147792924 0.6724940000 0.1136000000 0.0493620000 0.0371390000 0.4704590000 0.0017470000 113568051 0 402718720 4.2797679901 3.9629082680 3.9083716869 104 4.1200000000 0.0107177375 0.0101163393 0.0160688832 0.0147257813 0.6496960000 0.1265560000 0.0494770000 0.0000010000 0.4717340000 0.0017400000 113570827 0 402718720 4.2814540863 3.9638659954 3.9070441723 105 4.1600000000 0.0108143073 0.0101229867 0.0160688832 0.0146789705 1.1751990000 0.1136000000 0.0517330000 0.0379240000 0.4702250000 0.5015300000 113573603 0 402718720 4.2841644287 3.9652259350 3.9051351547 106 4.2000000000 0.0107511412 0.0101289126 0.0160688832 0.0146221741 0.6283360000 0.1136030000 0.0409770000 0.0000000000 0.4718240000 0.0017430000 113576379 0 402718720 4.2857298851 3.9656393528 3.9039075375 107 4.2400000000 0.0107758585 0.0101349589 0.0160688832 0.0145591606 0.6699460000 0.1136060000 0.0469800000 0.0377420000 0.4696860000 0.0017410000 113579155 0 402718720 4.2865772247 3.9656538963 3.9031825066 108 4.2800000000 0.0107798297 0.0101409299 0.0160688832 0.0144952798 0.6447550000 0.1136380000 0.0514520000 0.0000010000 0.4777240000 0.0017440000 113581931 0 402718720 4.2902097702 3.9679791927 3.9002368450 109 4.3200000000 0.0108310180 0.0101472610 0.0160688832 0.0144284995 1.1720020000 0.1136090000 0.0490570000 0.0376890000 0.4698900000 0.5015550000 113584707 0 402718720 4.2918114662 3.9686822891 3.8989753723 110 4.3600000000 0.0109131737 0.0101542238 0.0160688832 0.0143644825 0.6363340000 0.1135850000 0.0494440000 0.0000010000 0.4713550000 0.0017470000 113587483 0 402718720 4.2926702499 3.9698560238 3.8979079723 111 4.4000000000 0.0109120160 0.0101610508 0.0160688832 0.0143012290 0.6736330000 0.1135980000 0.0493150000 0.0377610000 0.4710070000 0.0017480000 113590259 0 402718720 4.2938880920 3.9719862938 3.8965530396 112 4.4400000000 0.0109837325 0.0101683962 0.0160688832 0.0142442706 0.6321480000 0.1136530000 0.0431170000 0.0000010000 0.4734290000 0.0017420000 113593035 0 402718720 4.2963447571 3.9747135639 3.8942809105 113 4.4800000000 0.0110525964 0.0101762209 0.0160688832 0.0141815583 1.1843330000 0.1272230000 0.0450610000 0.0379130000 0.4701900000 0.5037430000 113595811 0 402718720 4.2976489067 3.9772145748 3.8932480812 114 4.5200000000 0.0110347075 0.0101837515 0.0160688832 0.0141187915 0.6427500000 0.1136290000 0.0539710000 0.0000000000 0.4732070000 0.0017400000 113598587 0 402718720 4.2985296249 3.9787328243 3.8922171593 115 4.5600000000 0.0110922977 0.0101916519 0.0160688832 0.0140587419 0.6672100000 0.1136600000 0.0407490000 0.0373030000 0.4735520000 0.0017400000 113601363 0 402718720 4.2998323441 3.9812760353 3.8906869888 116 4.6000000000 0.0110512441 0.0101990622 0.0160688832 0.0140022308 0.6414770000 0.1136170000 0.0539460000 0.0000010000 0.4719670000 0.0017400000 113604139 0 402718720 4.3002758026 3.9827001095 3.8896467686 117 4.6400000000 0.0112032387 0.0102076449 0.0160688832 0.0139592199 1.2004380000 0.1136270000 0.0677280000 0.0373970000 0.4752300000 0.5062500000 113606915 0 402718720 4.3011445999 3.9854133129 3.8882834911 118 4.6800000000 0.0111746360 0.0102158397 0.0160688832 0.0139256911 0.6412000000 0.1136270000 0.0494750000 0.0000010000 0.4761480000 0.0017400000 113609691 0 402718720 4.3016715050 3.9859075546 3.8877222538 119 4.7200000000 0.0111495331 0.0102236859 0.0160688832 0.0138858576 0.6775740000 0.1136250000 0.0493110000 0.0372860000 0.4753970000 0.0017460000 113612467 0 402718720 4.3019070625 3.9885857105 3.8873484135 120 4.7600000000 0.0112141566 0.0102319398 0.0160688832 0.0138397344 0.6377420000 0.1093190000 0.0490270000 0.0000010000 0.4774460000 0.0017390000 113615243 0 402718720 4.3018317223 3.9896481037 3.8863747120 121 4.8000000000 0.0112135401 0.0102400522 0.0160688832 0.0137961532 1.2197940000 0.1409380000 0.0494410000 0.0377920000 0.4756410000 0.5157330000 113618019 0 402718720 4.3010516167 3.9909698963 3.8868222237 122 4.8400000000 0.0112649323 0.0102484529 0.0160688832 0.0137675972 0.7037080000 0.1470980000 0.0698830000 0.0000000000 0.4847780000 0.0017360000 113620795 0 402718720 4.3001899719 3.9957606792 3.8861553669 123 4.8800000000 0.0113250781 0.0102572059 0.0160688832 0.0137215351 0.6770470000 0.1136700000 0.0465950000 0.0369240000 0.4779080000 0.0017340000 113623571 0 402718720 4.2992916107 3.9980773926 3.8864560127 124 4.9200000000 0.0114360861 0.0102667130 0.0160688832 0.0136810293 0.6683730000 0.1261740000 0.0515130000 0.0000000000 0.4880700000 0.0023660000 113626347 0 402718720 4.2985572815 3.9991974831 3.8863687515 125 4.9600000000 0.0114161568 0.0102759086 0.0160688832 0.0136395499 1.2537890000 0.1470920000 0.0670000000 0.0486170000 0.4806880000 0.5101710000 113629123 0 402718720 4.2978763580 4.0021071434 3.8869628906 126 5.0000000000 0.0115006650 0.0102856289 0.0160688832 0.0136002868 0.6457770000 0.1136190000 0.0494560000 0.0000010000 0.4807420000 0.0017410000 113631899 0 402718720 4.2977290154 4.0040736198 3.8868341446 127 5.0400000000 0.0115054231 0.0102952335 0.0160688832 0.0135718303 0.6823840000 0.1136330000 0.0517970000 0.0380510000 0.4769410000 0.0017400000 113634675 0 402718720 4.2964601517 4.0056214333 3.8875284195 128 5.0800000000 0.0115554808 0.0103050792 0.0160688832 0.0135431603 0.6768070000 0.1264100000 0.0665190000 0.0000000000 0.4819130000 0.0017380000 113637451 0 402718720 4.2954668999 4.0072183609 3.8879446983 129 5.1200000000 0.0115558356 0.0103147750 0.0160688832 0.0135146779 1.2122170000 0.1347540000 0.0473210000 0.0380800000 0.4802290000 0.5116040000 113652515 0 402718720 4.2954821587 4.0099387169 3.8877708912 130 5.1600000000 0.0115229003 0.0103240683 0.0160688832 0.0134953876 0.6541120000 0.1136160000 0.0560050000 0.0000000000 0.4825200000 0.0017430000 113680891 0 402718720 4.2936120033 4.0107030869 3.8891582489 131 5.2000000000 0.0115458472 0.0103333948 0.0160688832 0.0134754981 0.6951190000 0.1136130000 0.0511010000 0.0380670000 0.4897050000 0.0023710000 113683667 0 402718720 4.2916655540 4.0108485222 3.8903825283 132 5.2400000000 0.0116115352 0.0103430777 0.0160688832 0.0134557640 0.7093310000 0.1470780000 0.0703570000 0.0000010000 0.4899220000 0.0017430000 113686443 0 402718720 4.2897405624 4.0112051964 3.8915636539 133 5.2800000000 0.0116336057 0.0103527809 0.0160688832 0.0134244778 1.1924140000 0.1093220000 0.0517230000 0.0378660000 0.4813790000 0.5118960000 113689219 0 402718720 4.2884120941 4.0120472908 3.8932800293 134 5.3200000000 0.0116141448 0.0103621941 0.0160688832 0.0133879406 0.6660780000 0.1237670000 0.0608960000 0.0000010000 0.4794350000 0.0017400000 113691995 0 402718720 4.2865471840 4.0137176514 3.8947727680 135 5.3600000000 0.0115915472 0.0103713004 0.0160688832 0.0133520145 0.6851980000 0.1136090000 0.0495510000 0.0378520000 0.4822090000 0.0017440000 113694771 0 402718720 4.2839884758 4.0139765739 3.8969731331 136 5.4000000000 0.0116860103 0.0103809674 0.0160688832 0.0133185381 0.6561110000 0.1136050000 0.0517830000 0.0000000000 0.4880880000 0.0023730000 113697547 0 402718720 4.2825517654 4.0156803131 3.8983173370 137 5.4400000000 0.0116508426 0.0103902366 0.0160688832 0.0132864997 1.2817300000 0.1470360000 0.0814360000 0.0492220000 0.4907000000 0.5131000000 113700323 0 402718720 4.2815814018 4.0182490349 3.8995687962 138 5.4800000000 0.0116638001 0.0103994653 0.0160688832 0.0133442987 0.6485660000 0.1093480000 0.0511370000 0.0000000000 0.4860440000 0.0017680000 113703099 0 402718720 4.2780284882 4.0181903839 3.9027109146 139 5.5200000000 0.0116651468 0.0104085709 0.0160688832 0.0133132255 0.7044220000 0.1275280000 0.0542420000 0.0376110000 0.4830460000 0.0017520000 113705875 0 402718720 4.2757110596 4.0189704895 3.9046070576 140 5.5600000000 0.0117111625 0.0104178751 0.0160688832 0.0132936292 0.6533190000 0.1136010000 0.0519260000 0.0000010000 0.4858000000 0.0017480000 113708651 0 402718720 4.2746415138 4.0208864212 3.9059298038 141 5.6000000000 0.0118258847 0.0104278610 0.0160688832 0.0132703137 1.2224950000 0.1135820000 0.0498390000 0.0375950000 0.4904300000 0.5307990000 113711427 0 402718720 4.2728114128 4.0227408409 3.9075748920 142 5.6400000000 0.0118245753 0.0104376970 0.0160688832 0.0132440920 0.6538670000 0.1135720000 0.0545290000 0.0000000000 0.4837640000 0.0017550000 113714203 0 402718720 4.2714519501 4.0252604485 3.9089763165 143 5.6800000000 0.0117675029 0.0104469964 0.0160688832 0.0132262676 0.6969280000 0.1135600000 0.0582900000 0.0377450000 0.4853310000 0.0017530000 113716979 0 402718720 4.2690625191 4.0256495476 3.9105958939 144 5.7200000000 0.0118587930 0.0104568005 0.0160688832 0.0131965216 0.6643830000 0.1243490000 0.0520800000 0.0000000000 0.4859410000 0.0017530000 113719755 0 402718720 4.2664775848 4.0259928703 3.9120051861 145 5.7600000000 0.0118601527 0.0104664788 0.0160688832 0.0131661981 1.2088920000 0.1316720000 0.0414650000 0.0377420000 0.4853740000 0.5123830000 113722531 0 402718720 4.2645435333 4.0294809341 3.9137945175 146 5.8000000000 0.0118717905 0.0104761042 0.0160688832 0.0131379920 0.6649670000 0.1263730000 0.0499510000 0.0000010000 0.4866350000 0.0017520000 113725307 0 402718720 4.2624168396 4.0301742554 3.9151592255 147 5.8400000000 0.0118994415 0.0104857868 0.0160688832 0.0131155181 0.6889360000 0.1135330000 0.0499690000 0.0376760000 0.4857490000 0.0017550000 113728083 0 402718720 4.2594523430 4.0311732292 3.9174802303 148 5.8800000000 0.0119055146 0.0104953796 0.0160688832 0.0130951985 0.6524020000 0.1134780000 0.0524850000 0.0000010000 0.4844250000 0.0017530000 113730859 0 402718720 4.2578210831 4.0323958397 3.9182255268 149 5.9200000000 0.0119489683 0.0105051352 0.0160688832 0.0130743042 1.1991470000 0.1134730000 0.0500610000 0.0377400000 0.4859010000 0.5117120000 113733635 0 402718720 4.2545804977 4.0324401855 3.9203133583 150 5.9600000000 0.0118429055 0.0105140537 0.0160688832 0.0130553271 0.6652830000 0.1262970000 0.0501850000 0.0000010000 0.4867860000 0.0017510000 113736411 0 402718720 4.2508163452 4.0310664177 3.9225735664 151 6.0000000000 0.0119858636 0.0105238007 0.0160688832 0.0130324320 0.6891580000 0.1134420000 0.0501790000 0.0376270000 0.4858970000 0.0017540000 113739187 0 402718720 4.2471647263 4.0314946175 3.9247553349 152 6.0400000000 0.0118047763 0.0105322282 0.0160688832 0.0130153108 0.6527540000 0.1133880000 0.0502570000 0.0000000000 0.4870910000 0.0017550000 113741963 0 402718720 4.2437491417 4.0299930573 3.9270615578 153 6.0800000000 0.0120208673 0.0105419579 0.0160688832 0.0129988836 1.2250120000 0.1401090000 0.0527060000 0.0376990000 0.4836790000 0.5105480000 113744739 0 402718720 4.2395238876 4.0323667526 3.9296634197 154 6.1200000000 0.0119325472 0.0105509877 0.0160688832 0.0129917318 0.6772920000 0.1349270000 0.0528100000 0.0000010000 0.4875230000 0.0017560000 113747515 0 402718720 4.2365217209 4.0339412689 3.9313635826 155 6.1600000000 0.0120410258 0.0105606008 0.0160688832 0.0129857103 0.6914200000 0.1132590000 0.0529360000 0.0384620000 0.4847320000 0.0017630000 113750291 0 402718720 4.2322673798 4.0333323479 3.9338696003 156 6.2000000000 0.0120775076 0.0105703246 0.0160688832 0.0129829647 0.6652160000 0.1132530000 0.0612950000 0.0000010000 0.4886370000 0.0017640000 113753067 0 402718720 4.2276878357 4.0342078209 3.9365763664 157 6.2400000000 0.0118849250 0.0105786978 0.0160688832 0.0129848098 1.2039710000 0.1132560000 0.0527000000 0.0377990000 0.4888050000 0.5111430000 113755843 0 402718720 4.2233738899 4.0359811783 3.9382913113 158 6.2800000000 0.0119858235 0.0105876037 0.0160688832 0.0129996157 0.6578950000 0.1131980000 0.0528050000 0.0000010000 0.4898560000 0.0017660000 113758619 0 402718720 4.2205948830 4.0372681618 3.9398806095 159 6.3200000000 0.0118922181 0.0105958088 0.0160688832 0.0130063877 0.6925990000 0.1131520000 0.0507150000 0.0375150000 0.4891770000 0.0017680000 113761395 0 402718720 4.2166728973 4.0373044014 3.9416556358 160 6.3600000000 0.0119374301 0.0106041940 0.0160688832 0.0130063638 0.6582080000 0.1131300000 0.0529160000 0.0000000000 0.4901260000 0.0017640000 113764171 0 402718720 4.2135581970 4.0385565758 3.9432680607 161 6.4000000000 0.0118971262 0.0106122246 0.0160688832 0.0130075644 1.2259060000 0.1254210000 0.0625970000 0.0376320000 0.4896340000 0.5103460000 113766947 0 402718720 4.2106204033 4.0396685600 3.9446008205 162 6.4400000000 0.0118845254 0.0106200783 0.0160688832 0.0130200105 0.6567580000 0.1129750000 0.0510420000 0.0000010000 0.4906920000 0.0017710000 113769723 0 402718720 4.2061414719 4.0390100479 3.9462246895 163 6.4800000000 0.0118977269 0.0106279166 0.0160688832 0.0130181346 0.7061940000 0.1130590000 0.0530830000 0.0376010000 0.4997050000 0.0024320000 113772499 0 402718720 4.2020440102 4.0383801460 3.9481616020 164 6.5200000000 0.0118746459 0.0106355186 0.0160688832 0.0130112317 0.7034030000 0.1460890000 0.0603600000 0.0000010000 0.4948930000 0.0017770000 113775275 0 402718720 4.1989040375 4.0371594429 3.9498307705 165 6.5600000000 0.0117919743 0.0106425275 0.0160688832 0.0129997770 1.2019130000 0.1129260000 0.0535570000 0.0375370000 0.4876980000 0.5099160000 113778051 0 402718720 4.1946010590 4.0402889252 3.9516577721 166 6.6000000000 0.0117330002 0.0106490966 0.0160688832 0.0130100909 0.6561430000 0.1087540000 0.0529280000 0.0000020000 0.4923970000 0.0017830000 113780827 0 402718720 4.1890249252 4.0388989449 3.9542715549 167 6.6400000000 0.0117539586 0.0106557125 0.0160688832 0.0130275440 0.6966970000 0.1128750000 0.0534220000 0.0371850000 0.4911340000 0.0017910000 113783603 0 402718720 4.1848559380 4.0386762619 3.9564011097 168 6.6800000000 0.0117999474 0.0106625234 0.0160688832 0.0130278145 0.6696320000 0.1220310000 0.0537010000 0.0000010000 0.4918220000 0.0017840000 113786379 0 402718720 4.1810898781 4.0410928726 3.9582290649 169 6.7200000000 0.0118551562 0.0106695804 0.0160688832 0.0130712984 1.2014080000 0.1126370000 0.0543900000 0.0371930000 0.4893480000 0.5075610000 113789155 0 402718720 4.1769466400 4.0399036407 3.9599511623 170 6.7600000000 0.0118360138 0.0106764418 0.0160688832 0.0130876768 0.6732370000 0.1164730000 0.0518950000 0.0000010000 0.5020570000 0.0024760000 113791931 0 402718720 4.1732473373 4.0388460159 3.9613912106 171 6.8000000000 0.0119787483 0.0106840576 0.0160688832 0.0131017770 0.7605050000 0.1455560000 0.0701460000 0.0470500000 0.4956590000 0.0018020000 113794707 0 402718720 4.1701102257 4.0414876938 3.9623374939 172 6.8400000000 0.0120993694 0.0106922862 0.0160688832 0.0131224636 0.6600930000 0.1126110000 0.0544440000 0.0000010000 0.4909340000 0.0018110000 113797483 0 402718720 4.1675186157 4.0424747467 3.9633734226 173 6.8800000000 0.0123613244 0.0107019338 0.0160688832 0.0131490300 1.1860330000 0.1125250000 0.0433770000 0.0363810000 0.4900700000 0.5033870000 113800259 0 402718720 4.1662492752 4.0421500206 3.9637644291 174 6.9200000000 0.0123454574 0.0107113794 0.0160688832 0.0131782318 0.6705230000 0.1251680000 0.0528020000 0.0000000000 0.4904180000 0.0018320000 113803035 0 402718720 4.1648316383 4.0402460098 3.9651937485 175 6.9600000000 0.0123758838 0.0107208908 0.0160688832 0.0132179935 0.6933720000 0.1123050000 0.0530610000 0.0362800000 0.4895900000 0.0018410000 113805811 0 402718720 4.1648111343 4.0412549973 3.9655330181 176 7.0000000000 0.0121197123 0.0107288387 0.0160688832 0.0132246475 0.6603360000 0.1122420000 0.0556480000 0.0000000000 0.4902910000 0.0018540000 113808587 0 402718720 4.1652293205 4.0425014496 3.9654371738 177 7.0400000000 0.0120210862 0.0107361395 0.0160688832 0.0132648142 1.2044930000 0.1250240000 0.0539010000 0.0366140000 0.4896510000 0.4989950000 113811363 0 402718720 4.1630964279 4.0444345474 3.9662928581 178 7.0800000000 0.0118762134 0.0107425444 0.0160688832 0.0133036780 0.6583810000 0.1121180000 0.0542350000 0.0000010000 0.4898410000 0.0018790000 113814139 0 402718720 4.1612129211 4.0447044373 3.9667813778 179 7.1200000000 0.0118144648 0.0107485328 0.0160688832 0.0133597021 0.7091370000 0.1249670000 0.0569350000 0.0365110000 0.4885240000 0.0018930000 113816915 0 402718720 4.1599140167 4.0430712700 3.9674789906 180 7.1600000000 0.0118112471 0.0107544368 0.0160688832 0.0133897922 0.6832840000 0.1338330000 0.0589010000 0.0000000000 0.4883360000 0.0019060000 113819691 0 402718720 4.1589722633 4.0446648598 3.9677290916 181 7.2000000000 0.0117468303 0.0107599196 0.0160688832 0.0133791311 1.1959450000 0.1119600000 0.0668890000 0.0364540000 0.4867370000 0.4935970000 113822467 0 402718720 4.1563758850 4.0448565483 3.9683992863 182 7.2400000000 0.0117993159 0.0107656306 0.0160688832 0.0133725570 0.6594600000 0.1118570000 0.0605250000 0.0000000000 0.4848440000 0.0019250000 113825243 0 402718720 4.1560349464 4.0461325645 3.9683539867 183 7.2800000000 0.0118192481 0.0107713880 0.0160688832 0.0133581611 0.7108560000 0.1293850000 0.0606550000 0.0363080000 0.4822610000 0.0019340000 113828019 0 402718720 4.1516294479 4.0468778610 3.9695568085 184 7.3200000000 0.0117923729 0.0107769369 0.0160688832 0.0133599420 0.6561580000 0.1116240000 0.0580810000 0.0000000000 0.4842060000 0.0019330000 113830795 0 402718720 4.1498870850 4.0455856323 3.9698581696 185 7.3600000000 0.0118515668 0.0107827457 0.0160688832 0.0133475879 1.2010720000 0.1115090000 0.0607570000 0.0357430000 0.4865650000 0.5061470000 113833571 0 402718720 4.1449527740 4.0461015701 3.9702675343 186 7.4000000000 0.0118607022 0.0107885411 0.0160688832 0.0133602601 0.6455830000 0.1169840000 0.0460480000 0.0000010000 0.4802930000 0.0019410000 113836347 0 402718720 4.1448407173 4.0457916260 3.9707410336 187 7.4400000000 0.0118668713 0.0107943076 0.0160688832 0.0133775624 0.6826870000 0.1112230000 0.0556620000 0.0359810000 0.4775700000 0.0019360000 113839123 0 402718720 4.1424322128 4.0441260338 3.9709713459 188 7.4800000000 0.0119178025 0.0108002836 0.0160688832 0.0133927985 0.6381470000 0.1110090000 0.0484730000 0.0000010000 0.4764060000 0.0019380000 113841899 0 402718720 4.1395301819 4.0433435440 3.9719192982 189 7.5200000000 0.0118022170 0.0108055849 0.0160688832 0.0134264935 1.1561950000 0.1108920000 0.0556000000 0.0358430000 0.4736840000 0.4798610000 113844675 0 402718720 4.1371726990 4.0446009636 3.9726622105 190 7.5600000000 0.0118105616 0.0108108742 0.0160688832 0.0134789417 0.6764340000 0.1455420000 0.0557680000 0.0000010000 0.4728580000 0.0019410000 113847451 0 402718720 4.1344852448 4.0429935455 3.9734039307 191 7.6000000000 0.0119179348 0.0108166704 0.0160688832 0.0135179869 0.6740200000 0.1108530000 0.0557380000 0.0353490000 0.4698190000 0.0019410000 113850227 0 402718720 4.1329479218 4.0451865196 3.9736011028 192 7.6400000000 0.0118873920 0.0108222470 0.0160688832 0.0135394000 0.6417510000 0.1109320000 0.0611150000 0.0000000000 0.4674370000 0.0019400000 113853003 0 402718720 4.1302647591 4.0447993279 3.9738945961 193 7.6800000000 0.0117646847 0.0108271301 0.0160688832 0.0135734056 1.1453080000 0.1108830000 0.0610010000 0.0357560000 0.4652420000 0.4721060000 113855779 0 402718720 4.1288676262 4.0453486443 3.9743626118 194 7.7200000000 0.0118251825 0.0108322747 0.0160688832 0.0135776258 0.6342420000 0.1109490000 0.0555600000 0.0000000000 0.4654710000 0.0019360000 113858555 0 402718720 4.1264162064 4.0438361168 3.9741067886 195 7.7600000000 0.0119053498 0.0108377777 0.0160688832 0.0135742884 0.6916810000 0.1220110000 0.0579260000 0.0356270000 0.4730440000 0.0027020000 113861331 0 402718720 4.1269745827 4.0459895134 3.9741473198 196 7.8000000000 0.0118133388 0.0108427550 0.0160688832 0.0135610042 0.6929840000 0.1422550000 0.0745260000 0.0000000000 0.4731390000 0.0026930000 113864107 0 402718720 4.1232681274 4.0452485085 3.9740478992 197 7.8400000000 0.0118120648 0.0108476754 0.0160688832 0.0135722773 1.1329120000 0.1185880000 0.0556690000 0.0350440000 0.4584000000 0.4648830000 113866883 0 402718720 4.1271500587 4.0458431244 3.9743232727 198 7.8800000000 0.0118605252 0.0108527908 0.0160688832 0.0135779704 0.6228490000 0.1074020000 0.0550510000 0.0000010000 0.4581280000 0.0019310000 113869659 0 402718720 4.1249589920 4.0464076996 3.9743480682 199 7.9200000000 0.0118002836 0.0108575521 0.0160688832 0.0136015202 0.6717260000 0.1238290000 0.0557590000 0.0350000000 0.4548720000 0.0019310000 113872435 0 402718720 4.1297054291 4.0475769043 3.9747323990 200 7.9600000000 0.0117947152 0.0108622379 0.0160688832 0.0136160480 0.6297890000 0.1104880000 0.0583720000 0.0000010000 0.4578560000 0.0026950000 113875211 0 402718720 4.1284804344 4.0488376617 3.9745969772 201 8.0000000000 0.0117976638 0.0108668917 0.0160688832 0.0136301602 1.1839790000 0.1410070000 0.0777700000 0.0446520000 0.4623640000 0.4578480000 113877987 0 402718720 4.1307024956 4.0493083000 3.9749000072 202 8.0400000000 0.0117871752 0.0108714476 0.0160688832 0.0136273298 0.6384580000 0.1105070000 0.0748380000 0.0000010000 0.4508970000 0.0018710000 113880763 0 402718720 4.1293973923 4.0490179062 3.9749729633 203 8.0800000000 0.0117945950 0.0108759951 0.0160688832 0.0136100093 0.6949310000 0.1105310000 0.0714060000 0.0453160000 0.4646060000 0.0026890000 113883539 0 402718720 4.1264700890 4.0503239632 3.9752984047 204 8.1200000000 0.0118316934 0.0108806799 0.0160688832 0.0135812106 0.6324460000 0.1226250000 0.0578560000 0.0000010000 0.4496890000 0.0019310000 113886315 0 402718720 4.1253929138 4.0525560379 3.9759130478 205 8.1600000000 0.0118618533 0.0108854661 0.0160688832 0.0135565238 1.1283160000 0.1417400000 0.0578680000 0.0354720000 0.4424620000 0.4504220000 113889091 0 402718720 4.1231732368 4.0508856773 3.9765367508 206 8.1999999990 0.0118913222 0.0108903489 0.0160688832 0.0135400385 0.6183340000 0.1106560000 0.0580140000 0.0000000000 0.4473780000 0.0019340000 113891867 0 402718720 4.1206092834 4.0484580994 3.9780321121 207 8.2400000000 0.0117554171 0.0108945280 0.0160688832 0.0135347799 0.6722920000 0.1108140000 0.0837600000 0.0353290000 0.4400940000 0.0019420000 113894643 0 402718720 4.1188745499 4.0498995781 3.9788672924 208 8.2799999990 0.0119028026 0.0108993755 0.0160688832 0.0135526807 0.6235120000 0.1109340000 0.0650580000 0.0000010000 0.4452930000 0.0018770000 113897419 0 402718720 4.1191754341 4.0472736359 3.9807281494 209 8.3200000000 0.0119662099 0.0109044799 0.0160688832 0.0135645853 1.0840890000 0.1109000000 0.0576100000 0.0354240000 0.4365890000 0.4432160000 113900195 0 402718720 4.1173229218 4.0492949486 3.9812982082 210 8.3599999990 0.0119048199 0.0109092435 0.0160688832 0.0135792434 0.6172010000 0.1110540000 0.0554890000 0.0000000000 0.4475620000 0.0026920000 113902971 0 402718720 4.1144223213 4.0528144836 3.9819118977 211 8.4000000000 0.0120085934 0.0109144537 0.0160688832 0.0136123283 0.7079800000 0.1419410000 0.0741820000 0.0445840000 0.4449670000 0.0019490000 113905747 0 402718720 4.1122274399 4.0534000397 3.9828176498 212 8.4399999990 0.0119724367 0.0109194441 0.0160688832 0.0136374873 0.6056580000 0.1113650000 0.0555510000 0.0000000000 0.4364350000 0.0019460000 113908523 0 402718720 4.1127729416 4.0504512787 3.9847943783 213 8.4800000000 0.0120067131 0.0109245487 0.0160688832 0.0136492589 1.0671870000 0.1115730000 0.0575440000 0.0348530000 0.4279920000 0.4348670000 113911299 0 402718720 4.1087336540 4.0518450737 3.9855973721 214 8.5200000000 0.0119368518 0.0109292791 0.0160688832 0.0136649266 0.6030680000 0.1117600000 0.0554440000 0.0000010000 0.4335600000 0.0019420000 113914075 0 402718720 4.1076683998 4.0517277718 3.9870569706 215 8.5600000000 0.0120454365 0.0109344705 0.0160688832 0.0136984556 0.6289730000 0.1118810000 0.0579100000 0.0350350000 0.4218340000 0.0019490000 113916851 0 402718720 4.1060452461 4.0500984192 3.9883079529 216 8.6000000000 0.0120562119 0.0109396638 0.0160688832 0.0137149638 0.5995990000 0.1119850000 0.0555510000 0.0000010000 0.4298050000 0.0018930000 113919627 0 402718720 4.1088056564 4.0541830063 3.9906284809 217 8.6400000000 0.0121133225 0.0109450723 0.0160688832 0.0137172994 1.0491510000 0.1120080000 0.0552140000 0.0354220000 0.4196070000 0.4265330000 113922403 0 402718720 4.1085639000 4.0557694435 3.9920542240 218 8.6800000000 0.0121410144 0.0109505583 0.0160688832 0.0137258552 0.5914390000 0.1083810000 0.0548770000 0.0000010000 0.4258600000 0.0019520000 113925179 0 402718720 4.1110677719 4.0550374985 3.9943466187 219 8.7200000000 0.0121590942 0.0109560767 0.0160688832 0.0137516156 0.6183680000 0.1122680000 0.0551960000 0.0349900000 0.4135890000 0.0019560000 113927955 0 402718720 4.1131739616 4.0543022156 3.9978346825 220 8.7600000000 0.0122460919 0.0109619404 0.0160688832 0.0137651988 0.5899680000 0.1123840000 0.0554750000 0.0000000000 0.4197810000 0.0019500000 113930731 0 402718720 4.1133947372 4.0523843765 4.0012373924 221 8.8000000000 0.0120928492 0.0109670577 0.0160688832 0.0137904846 1.0359640000 0.1125330000 0.0551520000 0.0351110000 0.4083480000 0.4243990000 113933507 0 402718720 4.1149902344 4.0526871681 4.0035223961 222 8.8400000000 0.0121398000 0.0109723403 0.0160688832 0.0138186799 0.6450060000 0.1448340000 0.0743190000 0.0000010000 0.4235240000 0.0019500000 113936283 0 402718720 4.1137008667 4.0548167229 4.0051836967 223 8.8800000000 0.0121348677 0.0109775534 0.0160688832 0.0138574154 0.6096610000 0.1127610000 0.0552860000 0.0351030000 0.4041830000 0.0019530000 113939059 0 402718720 4.1124954224 4.0536522865 4.0071711540 224 8.9200000000 0.0121179046 0.0109826443 0.0160688832 0.0138766566 0.5811200000 0.1128550000 0.0554840000 0.0000010000 0.4104420000 0.0019550000 113941835 0 402718720 4.1086864471 4.0533552170 4.0082402229 225 8.9600000000 0.0121242832 0.0109877182 0.0160688832 0.0140208079 1.0372320000 0.1312860000 0.0610780000 0.0352810000 0.3963750000 0.4128300000 113944611 0 402718720 4.0668244362 4.0477042198 3.9935598373 226 9.0000000000 0.0121087125 0.0109926784 0.0160688832 0.0140276068 0.5895580000 0.1127490000 0.0673960000 0.0000010000 0.4070760000 0.0019520000 113947387 0 402718720 4.0616135597 4.0509233475 3.9926886559 227 9.0400000000 0.0121403346 0.0109977341 0.0160688832 0.0140346430 0.6426740000 0.1128560000 0.0956650000 0.0359940000 0.3958180000 0.0019600000 113950163 0 402718720 4.0582346916 4.0497188568 3.9932289124 228 9.0800000000 0.0120602623 0.0110023943 0.0160688832 0.0140424717 0.5691490000 0.1088940000 0.0548230000 0.0000010000 0.4030850000 0.0019560000 113952939 0 402718720 4.0544614792 4.0497088432 3.9933717251 229 9.1200000000 0.0121720089 0.0110075018 0.0160688832 0.0140485969 0.9955220000 0.1129170000 0.0574550000 0.0352710000 0.3915500000 0.3979430000 113955715 0 402718720 4.0500349998 4.0493421555 3.9930756092 230 9.1600000000 0.0120843034 0.0110121836 0.0160688832 0.0140581805 0.5716940000 0.1130050000 0.0578360000 0.0000010000 0.3985030000 0.0019570000 113958491 0 402718720 4.0452246666 4.0495977402 3.9931373596 231 9.2000000000 0.0121266292 0.0110170080 0.0160688832 0.0140628303 0.6170250000 0.1243990000 0.0669960000 0.0357590000 0.3875280000 0.0019570000 113961267 0 402718720 4.0413947105 4.0492277145 3.9926095009 232 9.2400000000 0.0122163882 0.0110221777 0.0160688832 0.0140691794 0.5770820000 0.1130460000 0.0673520000 0.0000010000 0.3943320000 0.0019560000 113964043 0 402718720 4.0376653671 4.0486507416 3.9929125309 233 9.2800000000 0.0121936863 0.0110272057 0.0160688832 0.0140811723 0.9881150000 0.1130930000 0.0670270000 0.0356720000 0.3825720000 0.3893580000 113966819 0 402718720 4.0349664688 4.0495791435 3.9920985699 234 9.3200000000 0.0121821277 0.0110321412 0.0160688832 0.0140844919 0.5753490000 0.1258570000 0.0577700000 0.0000010000 0.3893620000 0.0019580000 113969595 0 402718720 4.0306682587 4.0496129990 3.9913983345 235 9.3600000000 0.0122786826 0.0110374457 0.0160688832 0.0141043314 0.5869600000 0.1131080000 0.0575490000 0.0356680000 0.3782800000 0.0019610000 113972371 0 402718720 4.0281434059 4.0490126610 3.9913048744 236 9.4000000000 0.0121931890 0.0110423429 0.0160688832 0.0141414353 0.5598490000 0.1131160000 0.0579070000 0.0000010000 0.3864550000 0.0019630000 113975147 0 402718720 4.0253958702 4.0477962494 3.9910173416 237 9.4400000000 0.0121654328 0.0110470817 0.0160688832 0.0141704320 0.9770310000 0.1265020000 0.0604850000 0.0353250000 0.3734000000 0.3809180000 113977923 0 402718720 4.0225672722 4.0449714661 3.9905788898 238 9.4800000000 0.0121920854 0.0110518926 0.0160688832 0.0141955105 0.5564400000 0.1132380000 0.0582950000 0.0000010000 0.3817340000 0.0027170000 113980699 0 402718720 4.0189542770 4.0409903526 3.9902884960 239 9.5200000000 0.0121324584 0.0110564138 0.0160688832 0.0142083830 0.6698630000 0.1456750000 0.0896370000 0.0452850000 0.3860900000 0.0027200000 113983475 0 402718720 4.0166563988 4.0412921906 3.9898552895 240 9.5600000000 0.0122818304 0.0110615197 0.0160688832 0.0143554406 0.5574580000 0.1183790000 0.0555760000 0.0000000000 0.3811370000 0.0019580000 113986251 0 402718720 4.0138664246 4.0352349281 3.9909472466 241 9.6000000000 0.0122533515 0.0110664651 0.0160688832 0.0143540465 0.9361540000 0.1132660000 0.0547160000 0.0358440000 0.3627210000 0.3691970000 113989027 0 402718720 4.0113015175 4.0352544785 3.9900422096 242 9.6400000000 0.0123339901 0.0110717028 0.0160688832 0.0143669136 0.5443280000 0.1133130000 0.0577760000 0.0000010000 0.3708680000 0.0019550000 113991803 0 402718720 4.0101876259 4.0329594612 3.9905529022 243 9.6800000000 0.0123570962 0.0110769925 0.0160688832 0.0143817266 0.5647210000 0.1132660000 0.0550800000 0.0356670000 0.3583320000 0.0019630000 113994579 0 402718720 4.0082945824 4.0303306580 3.9902429581 244 9.7200000000 0.0123118116 0.0110820532 0.0160688832 0.0143910888 0.5321340000 0.1090980000 0.0547790000 0.0000000000 0.3658880000 0.0019560000 113997355 0 402718720 4.0066795349 4.0296049118 3.9906153679 245 9.7600000000 0.0122967632 0.0110870112 0.0160688832 0.0143893251 0.9197970000 0.1133440000 0.0573350000 0.0358080000 0.3531870000 0.3597130000 114000131 0 402718720 4.0048217773 4.0304036140 3.9903891087 246 9.8000000000 0.0123946406 0.0110923268 0.0160688832 0.0143927883 0.5349490000 0.1133230000 0.0577020000 0.0000010000 0.3615510000 0.0019560000 114002907 0 402718720 4.0028920174 4.0291380882 3.9903769493 247 9.8400000000 0.0124580516 0.0110978560 0.0160688832 0.0143999404 0.6015150000 0.1458870000 0.0699520000 0.0357950000 0.3475000000 0.0019540000 114005683 0 402718720 3.9997050762 4.0287046432 3.9895353317 248 9.8800000000 0.0125794634 0.0111038302 0.0160688832 0.0143969422 0.5690790000 0.1158310000 0.0774300000 0.0000010000 0.3726190000 0.0027160000 114008459 0 402718720 3.9964249134 4.0254626274 3.9891009331 249 9.9200000000 0.0125998612 0.0111098384 0.0160688832 0.0143983626 0.9470250000 0.1458510000 0.0699260000 0.0356630000 0.3443730000 0.3507960000 114011235 0 402718720 3.9924261570 4.0223774910 3.9872953892 250 9.9600000000 0.0125591811 0.0111156358 0.0160688832 0.0143917328 0.5197260000 0.1090450000 0.0570730000 0.0000010000 0.3512200000 0.0019590000 114014011 0 402718720 3.9895758629 4.0224061012 3.9865224361 251 10.0000000000 0.0125875240 0.0111214999 0.0160688832 0.0143923906 0.5490550000 0.1128540000 0.0574270000 0.0358360000 0.3405540000 0.0019570000 114016787 0 402718720 3.9862945080 4.0200452805 3.9854860306 252 10.0400000000 0.0127264988 0.0111278689 0.0160688832 0.0143985505 0.5220550000 0.1132650000 0.0580120000 0.0000010000 0.3483920000 0.0019530000 114019563 0 402718720 3.9826688766 4.0180873871 3.9841732979 253 10.0800000000 0.0126860403 0.0111340277 0.0160688832 0.0143953184 0.8959090000 0.1126730000 0.0667580000 0.0351480000 0.3372190000 0.3436880000 114022339 0 402718720 3.9798803329 4.0174436569 3.9833197594 254 10.1200000000 0.0125811379 0.0111397250 0.0160688832 0.0143922479 0.5271550000 0.1132650000 0.0672450000 0.0000010000 0.3442610000 0.0019500000 114025115 0 402718720 3.9772272110 4.0154595375 3.9828307629 255 10.1600000000 0.0125664985 0.0111453202 0.0160688832 0.0143859096 0.5536380000 0.1261310000 0.0549470000 0.0356710000 0.3344980000 0.0019550000 114027891 0 402718720 3.9745192528 4.0144028664 3.9816474915 256 10.2000000000 0.0123996595 0.0111502199 0.0160688832 0.0143846018 0.5486360000 0.1404370000 0.0677310000 0.0000000000 0.3379600000 0.0020490000 114030667 0 402718720 3.9720692635 4.0130724907 3.9812347889 257 10.2400000000 0.0123419836 0.0111548571 0.0160688832 0.0144930653 0.9128530000 0.1282640000 0.0575250000 0.0356060000 0.3387910000 0.3521690000 114058019 0 402718720 3.9674975872 4.0093770027 3.9800908566 258 10.2800000000 0.0123212328 0.0111593780 0.0160688832 0.0144956462 0.5444950000 0.1460070000 0.0604300000 0.0000010000 0.3356600000 0.0019550000 114111995 0 402718720 3.9649374485 4.0084943771 3.9786550999 259 10.3200000000 0.0121691842 0.0111632768 0.0160688832 0.0144868206 0.5351090000 0.1132680000 0.0600290000 0.0357040000 0.3236010000 0.0020480000 114114771 0 402718720 3.9630570412 4.0072512627 3.9777407646 260 10.3600000000 0.0121511277 0.0111670763 0.0160688832 0.0144756874 0.5150700000 0.1133250000 0.0670780000 0.0000010000 0.3323310000 0.0018920000 114117547 0 402718720 3.9611186981 4.0054335594 3.9769718647 261 10.4000000000 0.0121625066 0.0111708902 0.0160688832 0.0144575243 0.8577070000 0.1132830000 0.0599300000 0.0356890000 0.3197140000 0.3286540000 114120323 0 402718720 3.9592828751 4.0041837692 3.9759833813 262 10.4400000000 0.0121593950 0.0111746631 0.0160688832 0.0144397485 0.5089190000 0.1132190000 0.0676010000 0.0000000000 0.3255870000 0.0020440000 114123099 0 402718720 3.9570665359 4.0024318695 3.9750072956 263 10.4800000000 0.0122231357 0.0111786497 0.0160688832 0.0144222553 0.5496490000 0.1236280000 0.0643500000 0.0351640000 0.3232920000 0.0027080000 114125875 0 402718720 3.9549539089 4.0013217926 3.9738886356 264 10.5200000000 0.0122281462 0.0111826250 0.0160688832 0.0144061026 0.5650760000 0.1459450000 0.0772690000 0.0000010000 0.3386290000 0.0027020000 114128651 0 402718720 3.9533107281 4.0000429153 3.9734303951 265 10.5600000000 0.0122370766 0.0111866041 0.0160688832 0.0143914526 0.8828130000 0.1489100000 0.0667410000 0.0355580000 0.3123040000 0.3188450000 114131427 0 402718720 3.9502823353 3.9980084896 3.9711182117 266 10.6000000000 0.0123110367 0.0111908313 0.0160688832 0.0143826871 0.4889410000 0.1132470000 0.0551320000 0.0000010000 0.3181630000 0.0019480000 114134203 0 402718720 3.9474623203 3.9959771633 3.9694733620 267 10.6400000000 0.0121533228 0.0111944361 0.0160688832 0.0143847119 0.5129100000 0.1131820000 0.0574520000 0.0350490000 0.3047170000 0.0020370000 114136979 0 402718720 3.9451339245 3.9950532913 3.9680066109 268 10.6800000000 0.0121617932 0.0111980457 0.0160688832 0.0143906139 0.4839010000 0.1132030000 0.0551490000 0.0000010000 0.3131500000 0.0019420000 114139755 0 402718720 3.9425687790 3.9932851791 3.9663186073 269 10.7200000000 0.0121613117 0.0112016266 0.0160688832 0.0144017315 0.8279290000 0.1131860000 0.0674900000 0.0355820000 0.3000460000 0.3111110000 114142531 0 402718720 3.9402511120 3.9913933277 3.9647026062 270 10.7600000000 0.0121827526 0.0112052604 0.0160688832 0.0144081141 0.5487320000 0.1459340000 0.0741320000 0.0000010000 0.3254360000 0.0027030000 114145307 0 402718720 3.9374988079 3.9896147251 3.9622254372 271 10.8000000000 0.0122315586 0.0112090475 0.0160688832 0.0144130889 0.5328580000 0.1425640000 0.0548090000 0.0354320000 0.2976380000 0.0019500000 114148083 0 402718720 3.9351966381 3.9878454208 3.9604661465 272 10.8400000000 0.0120343016 0.0112120815 0.0160688832 0.0144306047 0.4737790000 0.1089400000 0.0595920000 0.0000010000 0.3027800000 0.0019810000 114150859 0 402718720 3.9327299595 3.9859220982 3.9584081173 273 10.8800000000 0.0120338872 0.0112150918 0.0160688832 0.0144465448 0.7980320000 0.1130310000 0.0550670000 0.0355990000 0.2935210000 0.3003520000 114153635 0 402718720 3.9301331043 3.9840786457 3.9561314583 274 10.9200000000 0.0119188270 0.0112176601 0.0160688832 0.0144568692 0.4949070000 0.1319290000 0.0579940000 0.0000000000 0.3017450000 0.0027020000 114156411 0 402718720 3.9282584190 3.9824485779 3.9547188282 275 10.9600000000 0.0119871804 0.0112204584 0.0160688832 0.0144656177 0.5147480000 0.1303160000 0.0572740000 0.0354090000 0.2893240000 0.0019520000 114159187 0 402718720 3.9261233807 3.9804496765 3.9530203342 276 11.0000000000 0.0119513711 0.0112231066 0.0160688832 0.0144653287 0.4769810000 0.1130370000 0.0676070000 0.0000020000 0.2939030000 0.0019510000 114161963 0 402718720 3.9241900444 3.9798867702 3.9512372017 277 11.0400000000 0.0120929489 0.0112262469 0.0160688832 0.0147808834 0.7792800000 0.1128680000 0.0661390000 0.0353670000 0.2787270000 0.2857110000 114164739 0 402718720 3.9162383080 3.9725964069 3.9443092346 278 11.0800000000 0.0119579760 0.0112288790 0.0160688832 0.0147743274 0.4571530000 0.1128900000 0.0575000000 0.0000010000 0.2843310000 0.0019500000 114167515 0 402718720 3.9143316746 3.9703416824 3.9425940514 279 11.1200000000 0.0119507462 0.0112314663 0.0160688832 0.0147611859 0.4949050000 0.1246150000 0.0572580000 0.0351750000 0.2754250000 0.0019470000 114170291 0 402718720 3.9129087925 3.9679400921 3.9417457581 280 11.1600000000 0.0117140114 0.0112331897 0.0160688832 0.0147524169 0.4821250000 0.1256250000 0.0740630000 0.0000010000 0.2800050000 0.0019460000 114173067 0 402718720 3.9118547440 3.9667632580 3.9411530495 281 11.2000000000 0.0116612054 0.0112347129 0.0160688832 0.0147510191 0.7638860000 0.1127300000 0.0667760000 0.0351380000 0.2709110000 0.2778550000 114175843 0 402718720 3.9106009007 3.9644503593 3.9401750565 282 11.2400000000 0.0114648361 0.0112355289 0.0160688832 0.0147495311 0.4438660000 0.1099590000 0.0550620000 0.0000010000 0.2764110000 0.0019420000 114178619 0 402718720 3.9092848301 3.9634206295 3.9388213158 283 11.2800000000 0.0112275518 0.0112355007 0.0160688832 0.0147413110 0.4813260000 0.1125850000 0.0644200000 0.0354530000 0.2664400000 0.0019470000 114181395 0 402718720 3.9083614349 3.9608957767 3.9379467964 284 11.3200000000 0.0108649321 0.0112341959 0.0160688832 0.0147473983 0.5067640000 0.1394570000 0.0774130000 0.0000000000 0.2866320000 0.0027010000 114184171 0 402718720 3.9071578979 3.9591608047 3.9368252754 285 11.3600000000 0.0107522765 0.0112325050 0.0160688832 0.0147440428 0.8051640000 0.1455700000 0.0771310000 0.0448450000 0.2663500000 0.2707860000 114186947 0 402718720 3.9060866833 3.9571380615 3.9356112480 286 11.4000000000 0.0105751622 0.0112302066 0.0160688832 0.0147319013 0.4430320000 0.1124520000 0.0601910000 0.0000000000 0.2679520000 0.0019410000 114189723 0 402718720 3.9052627087 3.9546027184 3.9346628189 287 11.4400000000 0.0104314480 0.0112274234 0.0160688832 0.0147158305 0.4848410000 0.1124410000 0.0738730000 0.0352520000 0.2608350000 0.0019460000 114192499 0 402718720 3.9045805931 3.9529895782 3.9339289665 288 11.4800000000 0.0103371534 0.0112243322 0.0160688832 0.0146953810 0.4534770000 0.1123550000 0.0741330000 0.0000000000 0.2645510000 0.0019410000 114195275 0 402718720 3.9034619331 3.9506287575 3.9325954914 289 11.5200000000 0.0100888964 0.0112204034 0.0160688832 0.0146800356 0.7549210000 0.1214900000 0.0738320000 0.0353900000 0.2583460000 0.2653740000 114198051 0 402718720 3.9031431675 3.9480297565 3.9320590496 290 11.5600000000 0.0098942285 0.0112158304 0.0160688832 0.0146658547 0.4315150000 0.1082920000 0.0594930000 0.0000010000 0.2613510000 0.0018730000 114200827 0 402718720 3.9025149345 3.9468731880 3.9314615726 291 11.6000000000 0.0100083593 0.0112116810 0.0160688832 0.0146438465 0.4718690000 0.1121940000 0.0666240000 0.0354470000 0.2551630000 0.0019410000 114203603 0 402718720 3.9022042751 3.9452629089 3.9311671257 292 11.6400000000 0.0097598964 0.0112067091 0.0160688832 0.0146194210 0.4316040000 0.1121260000 0.0600960000 0.0000010000 0.2568230000 0.0020340000 114206379 0 402718720 3.9014308453 3.9428400993 3.9298202991 293 11.6800000000 0.0096103074 0.0112012606 0.0160688832 0.0145944002 0.8315550000 0.1170320000 0.1523580000 0.0448060000 0.2565460000 0.2603140000 114209155 0 402718720 3.9011957645 3.9408252239 3.9294395447 294 11.7200000000 0.0095453225 0.0111956282 0.0160688832 0.0145707829 0.4843630000 0.1111590000 0.1141950000 0.0000010000 0.2566290000 0.0018720000 114211931 0 402718720 3.9010262489 3.9397649765 3.9287242889 295 11.7600000000 0.0091000712 0.0111885246 0.0160688832 0.0145530970 0.4851960000 0.1216540000 0.0772510000 0.0352250000 0.2485030000 0.0020360000 114214707 0 402718720 3.9009220600 3.9343223572 3.9282817841 296 11.8000000000 0.0088633820 0.0111806694 0.0160688832 0.0145333114 0.4818630000 0.1370780000 0.0865060000 0.0000010000 0.2558190000 0.0019360000 114217483 0 402718720 3.9009532928 3.9319465160 3.9280655384 297 11.8400000000 0.0086277686 0.0111720738 0.0160688832 0.0145200613 0.7181450000 0.1248290000 0.0573200000 0.0351690000 0.2461450000 0.2541750000 114220259 0 402718720 3.9005436897 3.9307258129 3.9271390438 298 11.8800000000 0.0084830979 0.0111630504 0.0160688832 0.0145549797 0.4290330000 0.1118290000 0.0582530000 0.0000010000 0.2565030000 0.0019290000 114223035 0 402718720 3.8993420601 3.9267430305 3.9250111580 299 11.9200000000 0.0083629144 0.0111536854 0.0160688832 0.0145581292 0.4638790000 0.1117420000 0.0698020000 0.0352080000 0.2445630000 0.0020290000 114225811 0 402718720 3.8986241817 3.9250354767 3.9236714840 300 11.9600000000 0.0080838557 0.0111434526 0.0160688832 0.0145705500 0.4304780000 0.1101580000 0.0672490000 0.0000010000 0.2506200000 0.0019350000 114228587 0 402718720 3.8983170986 3.9228680134 3.9230136871 301 12.0000000000 0.0079773022 0.0111329338 0.0160688832 0.0145771140 0.6991110000 0.1113170000 0.0573960000 0.0348840000 0.2438690000 0.2511290000 114231363 0 402718720 3.8975734711 3.9208045006 3.9217965603 302 12.0400000000 0.0076217870 0.0111213075 0.0160688832 0.0146156187 0.4836400000 0.1287610000 0.0814250000 0.0000000000 0.2701660000 0.0026900000 114234139 0 402718720 3.8954002857 3.9170665741 3.9182066917 303 12.0800000000 0.0076162047 0.0111097395 0.0160688832 0.0146008981 0.5859190000 0.1449510000 0.1513310000 0.0446880000 0.2424970000 0.0019240000 114236915 0 402718720 3.8940839767 3.9153945446 3.9161341190 304 12.1200000000 0.0073761251 0.0110974579 0.0160688832 0.0145885196 0.4161820000 0.1114890000 0.0573030000 0.0000010000 0.2449400000 0.0019250000 114239691 0 402718720 3.8926126957 3.9132597446 3.9135997295 305 12.1600000000 0.0073819957 0.0110852760 0.0160688832 0.0145818624 0.6815300000 0.1115560000 0.0572900000 0.0352200000 0.2328890000 0.2439940000 114242467 0 402718720 3.8913290501 3.9121477604 3.9116206169 306 12.2000000000 0.0070773107 0.0110721781 0.0160688832 0.0145813177 0.4937140000 0.1449710000 0.0900240000 0.0000010000 0.2554300000 0.0026850000 114245243 0 402718720 3.8905887604 3.9095761776 3.9098858833 307 12.2400000000 0.0070951357 0.0110592236 0.0160688832 0.0145953793 0.4851810000 0.1450050000 0.0726750000 0.0347270000 0.2303200000 0.0019260000 114248019 0 402718720 3.8891689777 3.9078586102 3.9077069759 308 12.2800000000 0.0069755334 0.0110459649 0.0160688832 0.0146124182 0.4181860000 0.1117150000 0.0669270000 0.0000010000 0.2370790000 0.0019240000 114250795 0 402718720 3.8875329494 3.9060266018 3.9049544334 309 12.3200000000 0.0069458052 0.0110326957 0.0160688832 0.0146112250 0.6720560000 0.1116620000 0.0670570000 0.0352660000 0.2250000000 0.2325410000 114253571 0 402718720 3.8858618736 3.9042048454 3.9018745422 310 12.3600000000 0.0068913242 0.0110193365 0.0160688832 0.0146111830 0.4121460000 0.1116280000 0.0668990000 0.0000000000 0.2311610000 0.0019250000 114256347 0 402718720 3.8842105865 3.9024384022 3.8985631466 311 12.4000000000 0.0068224431 0.0110058416 0.0160688832 0.0146107646 0.4362110000 0.1117380000 0.0664080000 0.0349270000 0.2206870000 0.0019200000 114259123 0 402718720 3.8829598427 3.9012324810 3.8957312107 312 12.4400000000 0.0067395959 0.0109921678 0.0160688832 0.0146036161 0.3981150000 0.1116700000 0.0600190000 0.0000010000 0.2238430000 0.0020220000 114261899 0 402718720 3.8816993237 3.8998084068 3.8927118778 313 12.4800000000 0.0067118974 0.0109784928 0.0160688832 0.0145954907 0.6496600000 0.1117280000 0.0570050000 0.0350220000 0.2174070000 0.2279620000 114264675 0 402718720 3.8804290295 3.8983526230 3.8901309967 314 12.5200000000 0.0067401775 0.0109649950 0.0160688832 0.0145940967 0.3923930000 0.1116330000 0.0574080000 0.0000010000 0.2208920000 0.0019200000 114267451 0 402718720 3.8794009686 3.8971097469 3.8879988194 315 12.5600000000 0.0068409760 0.0109519028 0.0160688832 0.0145970217 0.4268270000 0.1116330000 0.0665640000 0.0345370000 0.2116230000 0.0019270000 114270227 0 402718720 3.8780307770 3.8961913586 3.8852674961 316 12.6000000000 0.0067840884 0.0109387136 0.0160688832 0.0145946990 0.3971830000 0.1116080000 0.0668020000 0.0000000000 0.2163060000 0.0019160000 114273003 0 402718720 3.8767995834 3.8948130608 3.8825316429 317 12.6400000000 0.0067881313 0.0109256202 0.0160688832 0.0145844780 0.6306730000 0.1077770000 0.0656520000 0.0344690000 0.2078560000 0.2143730000 114275779 0 402718720 3.8755600452 3.8939936161 3.8798477650 318 12.6800000000 0.0067885872 0.0109126107 0.0160688832 0.0145701726 0.3919870000 0.1115660000 0.0666730000 0.0000000000 0.2112780000 0.0019180000 114278555 0 402718720 3.8742663860 3.8930878639 3.8772263527 319 12.7200000000 0.0070070773 0.0109003676 0.0160688832 0.0145874591 0.4415950000 0.1246660000 0.0794690000 0.0348630000 0.2001130000 0.0019290000 114281331 0 402718720 3.8719880581 3.8916597366 3.8720567226 320 12.7600000000 0.0070777228 0.0108884219 0.0160688832 0.0145754911 0.3851790000 0.1113820000 0.0667120000 0.0000010000 0.2046100000 0.0019220000 114284107 0 402718720 3.8711268902 3.8907604218 3.8698170185 321 12.8000000000 0.0071947495 0.0108769151 0.0160688832 0.0145639827 0.6150910000 0.1114480000 0.0664070000 0.0347340000 0.1977850000 0.2041640000 114286883 0 402718720 3.8698360920 3.8905882835 3.8672561646 322 12.8400000000 0.0074937432 0.0108664084 0.0160688832 0.0145498412 0.4093490000 0.1198480000 0.0856500000 0.0000010000 0.2013700000 0.0019210000 114289659 0 402718720 3.8684837818 3.8897750378 3.8645195961 323 12.8800000000 0.0074308417 0.0108557719 0.0160688832 0.0145362212 0.3992030000 0.1112600000 0.0570780000 0.0340790000 0.1943060000 0.0019260000 114292435 0 402718720 3.8674643040 3.8893980980 3.8627517223 324 12.9200000000 0.0076099406 0.0108457539 0.0160688832 0.0145233787 0.3924490000 0.1075320000 0.0855670000 0.0000000000 0.1968750000 0.0019180000 114295211 0 402718720 3.8661329746 3.8894913197 3.8602385521 325 12.9600000000 0.0075498181 0.0108356126 0.0160688832 0.0145040218 0.6123730000 0.1112630000 0.0758330000 0.0341000000 0.1920560000 0.1985620000 114297987 0 402718720 3.8649568558 3.8898570538 3.8583741188 326 13.0000000000 0.0077759996 0.0108262273 0.0160688832 0.0144842407 0.3847060000 0.1111970000 0.0759240000 0.0000010000 0.1951050000 0.0019160000 114300763 0 402718720 3.8635423183 3.8897962570 3.8557803631 327 13.0400000000 0.0083824266 0.0108187539 0.0160688832 0.0144642151 0.4218730000 0.1111100000 0.0849560000 0.0344870000 0.1888230000 0.0019330000 114303539 0 402718720 3.8623006344 3.8908345699 3.8530037403 328 13.0800000000 0.0081498586 0.0108106170 0.0160688832 0.0144446181 0.3708150000 0.1111450000 0.0665370000 0.0000010000 0.1906630000 0.0019120000 114306315 0 402718720 3.8609244823 3.8919107914 3.8511598110 329 13.1200000000 0.0085009532 0.0108035968 0.0160688832 0.0144270047 0.6380980000 0.1110860000 0.1133330000 0.0345170000 0.1862160000 0.1923850000 114309091 0 402718720 3.8597576618 3.8935163021 3.8488547802 330 13.1600000000 0.0090421317 0.0107982590 0.0160688832 0.0144090317 0.4039290000 0.1111230000 0.1019400000 0.0000010000 0.1883740000 0.0019200000 114311867 0 402718720 3.8584434986 3.8944635391 3.8462388515 331 13.2000000000 0.0088535342 0.0107923837 0.0160688832 0.0143942110 0.4187610000 0.1316970000 0.0663520000 0.0339800000 0.1842270000 0.0019270000 114314643 0 402718720 3.8573179245 3.8963983059 3.8447782993 332 13.2400000000 0.0090311123 0.0107870786 0.0160688832 0.0143772164 0.4355310000 0.1321250000 0.1165350000 0.0000010000 0.1843760000 0.0019190000 114317419 0 402718720 3.8561058044 3.8984198570 3.8432767391 333 13.2800000000 0.0084653860 0.0107801066 0.0160688832 0.0143658901 0.6073040000 0.1110340000 0.0893390000 0.0344860000 0.1822890000 0.1895810000 114320195 0 402718720 3.8548080921 3.9007315636 3.8423948288 334 13.3200000000 0.0087412633 0.0107740023 0.0160688832 0.0143899007 0.3945200000 0.1109230000 0.0946300000 0.0000010000 0.1864870000 0.0019110000 114322971 0 402718720 3.8525586128 3.9054713249 3.8397572041 335 13.3600000000 0.0084650880 0.0107671100 0.0160688832 0.0143788277 0.4178560000 0.1108490000 0.0890870000 0.0344280000 0.1809910000 0.0019230000 114325747 0 402718720 3.8516511917 3.9080643654 3.8392679691 336 13.4000000000 0.0090622101 0.0107620359 0.0160688832 0.0143670875 0.3822050000 0.1108090000 0.0853110000 0.0000000000 0.1835900000 0.0019190000 114328523 0 402718720 3.8506579399 3.9104275703 3.8379926682 337 13.4400000000 0.0089184809 0.0107565654 0.0160688832 0.0143571531 0.6080140000 0.1108750000 0.0854650000 0.0342740000 0.1908300000 0.1859910000 114331299 0 402718720 3.8497579098 3.9126636982 3.8376905918 338 13.4800000000 0.0090089049 0.0107513948 0.0160688832 0.0143592826 0.3765730000 0.1070820000 0.0847200000 0.0000000000 0.1823310000 0.0018540000 114334075 0 402718720 3.8489360809 3.9142971039 3.8372058868 339 13.5200000000 0.0090493830 0.0107463741 0.0160688832 0.0143709570 0.3825420000 0.1106960000 0.0572320000 0.0336750000 0.1784240000 0.0019300000 114336851 0 402718720 3.8478868008 3.9168868065 3.8367400169 340 13.5600000000 0.0091703311 0.0107417387 0.0160688832 0.0143734792 0.4083640000 0.1107750000 0.1143500000 0.0000000000 0.1807250000 0.0019240000 114339627 0 402718720 3.8470916748 3.9188258648 3.8367552757 341 13.6000000000 0.0092019793 0.0107372233 0.0160688832 0.0143698845 0.5674680000 0.1069830000 0.0661100000 0.0332470000 0.1773370000 0.1832130000 114342403 0 402718720 3.8462610245 3.9214756489 3.8367259502 342 13.6400000000 0.0094264224 0.0107333905 0.0160688832 0.0143643205 0.3854550000 0.1248620000 0.0776810000 0.0000010000 0.1803940000 0.0019150000 114345179 0 402718720 3.8450324535 3.9242699146 3.8359818459 343 13.6800000000 0.0094152549 0.0107295476 0.0160688832 0.0143735207 0.4097070000 0.1375210000 0.0599080000 0.0342460000 0.1755140000 0.0019240000 114347955 0 402718720 3.8441627026 3.9267823696 3.8358557224 344 13.7200000000 0.0092867799 0.0107253535 0.0160688832 0.0143872811 0.3721700000 0.1105490000 0.0797360000 0.0000010000 0.1793750000 0.0019130000 114350731 0 402718720 3.8434164524 3.9293091297 3.8358759880 345 13.7600000000 0.0095116254 0.0107218354 0.0160688832 0.0145373167 0.5613240000 0.1104840000 0.0569590000 0.0335530000 0.1767340000 0.1830090000 114353507 0 402718720 3.8418157101 3.9347438812 3.8356437683 346 13.8000000000 0.0099678105 0.0107196562 0.0160688832 0.0145463048 0.3702370000 0.1103530000 0.0763120000 0.0000000000 0.1810410000 0.0019220000 114356283 0 402718720 3.8411781788 3.9369776249 3.8351116180 347 13.8400000000 0.0101706404 0.0107180740 0.0160688832 0.0145447229 0.4302470000 0.1230920000 0.0948930000 0.0340950000 0.1756390000 0.0019300000 114359059 0 402718720 3.8402819633 3.9396026134 3.8347582817 348 13.8800000000 0.0098995576 0.0107157219 0.0160688832 0.0145314653 0.3592710000 0.1102850000 0.0666890000 0.0000000000 0.1797680000 0.0019230000 114361835 0 402718720 3.8394539356 3.9424972534 3.8349277973 349 13.9200000000 0.0094934823 0.0107122198 0.0160688832 0.0145112684 0.6668650000 0.1188910000 0.1149870000 0.0430340000 0.1913150000 0.1979570000 114364611 0 402718720 3.8385903835 3.9459414482 3.8352649212 350 13.9600000000 0.0100757694 0.0107104014 0.0160688832 0.0144956802 0.4136100000 0.1433490000 0.0851460000 0.0000010000 0.1825830000 0.0019180000 114367387 0 402718720 3.8378281593 3.9482629299 3.8346493244 351 14.0000000000 0.0100562396 0.0107085377 0.0160688832 0.0144932274 0.4385630000 0.1104290000 0.1149810000 0.0340780000 0.1765420000 0.0019250000 114370163 0 402718720 3.8371429443 3.9517891407 3.8347134590 352 14.0400000000 0.0099514006 0.0107063867 0.0160688832 0.0144913750 0.3834740000 0.1195520000 0.0798810000 0.0000010000 0.1815010000 0.0019220000 114372939 0 402718720 3.8363976479 3.9545924664 3.8350446224 353 14.0800000000 0.0098941475 0.0107040857 0.0160688832 0.0145011879 0.6058260000 0.1104050000 0.0989840000 0.0337920000 0.1779200000 0.1841230000 114375715 0 402718720 3.8357367516 3.9582729340 3.8354065418 354 14.1200000000 0.0104001490 0.0107032272 0.0160688832 0.0145247496 0.3830570000 0.1106030000 0.0857650000 0.0000000000 0.1841450000 0.0019220000 114378491 0 402718720 3.8352530003 3.9609951973 3.8353860378 355 14.1600000000 0.0101818433 0.0107017585 0.0160688832 0.0145478260 0.4288190000 0.1377100000 0.0761840000 0.0341320000 0.1782410000 0.0019340000 114381267 0 402718720 3.8347263336 3.9640002251 3.8360328674 356 14.2000000000 0.0099716205 0.0106997075 0.0160688832 0.0145576278 0.4149070000 0.1106310000 0.1197670000 0.0000010000 0.1819680000 0.0019210000 114384043 0 402718720 3.8341846466 3.9674768448 3.8364377022 357 14.2400000000 0.0100124581 0.0106977825 0.0160688832 0.0145598645 0.6248670000 0.1109100000 0.1139080000 0.0335600000 0.1795530000 0.1863220000 114386819 0 402718720 3.8337211609 3.9702422619 3.8370628357 358 14.2800000000 0.0100817150 0.0106960616 0.0160688832 0.0145643430 0.3770930000 0.1109960000 0.0797870000 0.0000010000 0.1836450000 0.0020210000 114389595 0 402718720 3.8333196640 3.9725842476 3.8377726078 359 14.3200000000 0.0095378179 0.0106928353 0.0160688832 0.0145700445 0.4923520000 0.1322480000 0.1271450000 0.0430210000 0.1873860000 0.0019260000 114392371 0 402718720 3.8329925537 3.9758489132 3.8389840126 360 14.3600000000 0.0101037342 0.0106911989 0.0160688832 0.0145678751 0.3683920000 0.1111660000 0.0698720000 0.0000010000 0.1846940000 0.0020170000 114395147 0 402718720 3.8328180313 3.9782249928 3.8391203880 361 14.4000000000 0.0101384064 0.0106896676 0.0160688832 0.0145638125 0.5897410000 0.1242050000 0.0571440000 0.0335770000 0.1835670000 0.1906230000 114397923 0 402718720 3.8326735497 3.9812707901 3.8399901390 362 14.4400000000 0.0097331293 0.0106870253 0.0160688832 0.0145682829 0.3847380000 0.1075040000 0.0846270000 0.0000010000 0.1901300000 0.0018560000 114400699 0 402718720 3.8326256275 3.9838905334 3.8412537575 363 14.4800000000 0.0098049790 0.0106845954 0.0160688832 0.0145699759 0.4094040000 0.1113520000 0.0758800000 0.0336160000 0.1859950000 0.0019310000 114403475 0 402718720 3.8326609135 3.9857153893 3.8420779705 364 14.5200000000 0.0101282606 0.0106830670 0.0160688832 0.0145718093 0.3734300000 0.1114870000 0.0666300000 0.0000010000 0.1927550000 0.0019250000 114406251 0 402718720 3.8325829506 3.9880614281 3.8425557613 365 14.5600000000 0.0098679299 0.0106808337 0.0160688832 0.0145774240 0.6162360000 0.1196250000 0.0794210000 0.0343510000 0.1871800000 0.1950270000 114409027 0 402718720 3.8326575756 3.9898006916 3.8437652588 366 14.6000000000 0.0091562783 0.0106766683 0.0160688832 0.0146696146 0.3907920000 0.1117850000 0.0756110000 0.0000010000 0.2008220000 0.0019300000 114411803 0 402718720 3.8333694935 3.9965922832 3.8463814259 367 14.6400000000 0.0085157519 0.0106707802 0.0160688832 0.0146854679 0.4097520000 0.1117220000 0.0693590000 0.0343670000 0.1917320000 0.0019330000 114414579 0 402718720 3.8338024616 3.9998204708 3.8479301929 368 14.6800000000 0.0084227007 0.0106646713 0.0160688832 0.0146964763 0.4168620000 0.1365400000 0.0797530000 0.0000000000 0.1979870000 0.0019320000 114417355 0 402718720 3.8346562386 4.0026674271 3.8498215675 369 14.7200000000 0.0080303820 0.0106575323 0.0160688832 0.0147179709 0.6202630000 0.1120510000 0.0693310000 0.0344970000 0.1974640000 0.2062910000 114420131 0 402718720 3.8362267017 4.0101652145 3.8531336784 370 14.7600000000 0.0073429146 0.0106485739 0.0160688832 0.0147249726 0.4562300000 0.1311110000 0.1019200000 0.0000010000 0.2197660000 0.0026990000 114422907 0 402718720 3.8376612663 4.0136857033 3.8562383652 371 14.8000000000 0.0061793695 0.0106365275 0.0160688832 0.0147288432 0.5052890000 0.1447180000 0.1018340000 0.0436570000 0.2124970000 0.0019390000 114425683 0 402718720 3.8388633728 4.0174598694 3.8596754074 372 14.8400000000 0.0055154273 0.0106227611 0.0160688832 0.0147292339 0.3908190000 0.1122560000 0.0667150000 0.0000010000 0.2092570000 0.0019400000 114428459 0 402718720 3.8399186134 4.0209369659 3.8631289005 373 14.8800000000 0.0053885016 0.0106087282 0.0160688832 0.0147263530 0.6576250000 0.1122790000 0.0795120000 0.0346250000 0.2107330000 0.2198380000 114431235 0 402718720 3.8413844109 4.0252962112 3.8667213917 374 14.9200000000 0.0056656399 0.0105955114 0.0160688832 0.0147190173 0.4152850000 0.1291090000 0.0666660000 0.0000010000 0.2169130000 0.0019420000 114434011 0 402718720 3.8428349495 4.0296664238 3.8697972298 375 14.9600000000 0.0064264210 0.0105843939 0.0160688832 0.0147141234 0.4386720000 0.1123760000 0.0697790000 0.0347290000 0.2191880000 0.0019480000 114436787 0 402718720 3.8443911076 4.0339527130 3.8733489513 376 15.0000000000 0.0070043039 0.0105748723 0.0160688832 0.0147234283 0.4105010000 0.1124820000 0.0697710000 0.0000010000 0.2256480000 0.0019470000 114439563 0 402718720 3.8459849358 4.0371227264 3.8764317036 377 15.0400000000 0.0074509764 0.0105665861 0.0160688832 0.0147445354 0.6863670000 0.1125260000 0.0794910000 0.0349810000 0.2251190000 0.2336020000 114442339 0 402718720 3.8479118347 4.0400347710 3.8794806004 378 15.0800000000 0.0080831116 0.0105600161 0.0160688832 0.0147561958 0.4248360000 0.1325100000 0.0573940000 0.0000010000 0.2323120000 0.0019500000 114445115 0 402718720 3.8498077393 4.0436625481 3.8820176125 379 15.1200000000 0.0084359841 0.0105544118 0.0160688832 0.0147528943 0.4714650000 0.1126230000 0.0896050000 0.0351070000 0.2315110000 0.0019600000 114447891 0 402718720 3.8520190716 4.0465693474 3.8846595287 380 15.1600000000 0.0089031737 0.0105500664 0.0160688832 0.0147581709 0.4114100000 0.1126910000 0.0573660000 0.0000000000 0.2387270000 0.0019590000 114450667 0 402718720 3.8541946411 4.0490365028 3.8872232437 381 15.2000000000 0.0093370751 0.0105468827 0.0160688832 0.0147633231 0.6999870000 0.1126820000 0.0600950000 0.0346680000 0.2390840000 0.2528000000 114453443 0 402718720 3.8562533855 4.0511870384 3.8893113136 382 15.2400000000 0.0093858717 0.0105438434 0.0160688832 0.0147596994 0.4178970000 0.1127480000 0.0574610000 0.0000010000 0.2450500000 0.0019650000 114456219 0 402718720 3.8585283756 4.0528578758 3.8913235664 383 15.2800000000 0.0094811367 0.0105410687 0.0160688832 0.0147561900 0.4538570000 0.1127460000 0.0575440000 0.0350040000 0.2459420000 0.0019650000 114458995 0 402718720 3.8605895042 4.0545749664 3.8933126926 384 15.3200000000 0.0094685396 0.0105382757 0.0160688832 0.0147744617 0.4375490000 0.1253170000 0.0574150000 0.0000010000 0.2521740000 0.0019670000 114461771 0 402718720 3.8627359867 4.0558261871 3.8952674866 385 15.3600000000 0.0095324991 0.0105356633 0.0160688832 0.0147782302 0.7221040000 0.1128770000 0.0600720000 0.0348420000 0.2522290000 0.2614300000 114464547 0 402718720 3.8652601242 4.0564489365 3.8974106312 386 15.4000000000 0.0096301911 0.0105333175 0.0160688832 0.0147781343 0.4369600000 0.1110140000 0.0644260000 0.0000010000 0.2588900000 0.0019580000 114467323 0 402718720 3.8675231934 4.0586624146 3.8992874622 387 15.4400000000 0.0098596374 0.0105315767 0.0160688832 0.0147789273 0.4639190000 0.1087840000 0.0566960000 0.0349340000 0.2608730000 0.0019630000 114470099 0 402718720 3.8702723980 4.0597019196 3.9019396305 388 15.4800000000 0.0097624734 0.0105295945 0.0160688832 0.0147883567 0.4327000000 0.1092520000 0.0549760000 0.0000010000 0.2658350000 0.0019550000 114472875 0 402718720 3.8732111454 4.0603175163 3.9043524265 389 15.5200000000 0.0097421817 0.0105275703 0.0160688832 0.0147928784 0.7547050000 0.1129820000 0.0574670000 0.0351350000 0.2674670000 0.2809010000 114475651 0 402718720 3.8754227161 4.0618958473 3.9060943127 390 15.5600000000 0.0100028003 0.0105262248 0.0160688832 0.0147858335 0.5090770000 0.1456030000 0.0741440000 0.0000000000 0.2858440000 0.0027120000 114478427 0 402718720 3.8785552979 4.0624361038 3.9092397690 391 15.6000000000 0.0100466823 0.0105249983 0.0160688832 0.0147842774 0.5320530000 0.1456010000 0.0646480000 0.0352320000 0.2830800000 0.0027160000 114481203 0 402718720 3.8809132576 4.0631799698 3.9114117622 392 15.6400000000 0.0100695230 0.0105238364 0.0160688832 0.0147845306 0.4515630000 0.1154800000 0.0574840000 0.0000010000 0.2759640000 0.0019520000 114483979 0 402718720 3.8840558529 4.0629658699 3.9141278267 393 15.6800000000 0.0100787133 0.0105227037 0.0160688832 0.0147838478 0.7697400000 0.1130340000 0.0580020000 0.0350970000 0.2782810000 0.2846500000 114486755 0 402718720 3.8865733147 4.0634045601 3.9161505699 394 15.7200000000 0.0101600830 0.0105217834 0.0160688832 0.0147879358 0.4805580000 0.1367010000 0.0603360000 0.0000010000 0.2808670000 0.0019540000 114489531 0 402718720 3.8894238472 4.0649051666 3.9180116653 395 15.7600000000 0.0103229005 0.0105212799 0.0160688832 0.0147929816 0.4929190000 0.1130640000 0.0575890000 0.0348370000 0.2847820000 0.0019610000 114492307 0 402718720 3.8921914101 4.0650668144 3.9199364185 396 15.8000000000 0.0103099598 0.0105207462 0.0160688832 0.0147873494 0.4645980000 0.1130580000 0.0603030000 0.0000010000 0.2885820000 0.0019520000 114495083 0 402718720 3.8952426910 4.0658698082 3.9216864109 397 15.8400000000 0.0103474706 0.0105203098 0.0160688832 0.0147784314 0.8075140000 0.1258070000 0.0551830000 0.0349660000 0.2919680000 0.2989040000 114497859 0 402718720 3.8986339569 4.0674004555 3.9239933491 398 15.8800000000 0.0104264412 0.0105200739 0.0160688832 0.0147729383 0.4696260000 0.1130360000 0.0575620000 0.0000010000 0.2963640000 0.0019600000 114500635 0 402718720 3.8999435902 4.0681648254 3.9238476753 399 15.9200000000 0.0103814201 0.0105197264 0.0160688832 0.0147685293 0.5213830000 0.1289630000 0.0551850000 0.0355690000 0.2989990000 0.0019630000 114503411 0 402718720 3.9034667015 4.0690369606 3.9259185791 400 15.9600000000 0.0104292231 0.0105195002 0.0160688832 0.0147640282 0.4733110000 0.1130940000 0.0552630000 0.0000010000 0.3022950000 0.0019570000 114506187 0 402718720 3.9051191807 4.0683050156 3.9266211987 401 16.0000000000 0.0104694255 0.0105193753 0.0160688832 0.0147524502 0.8248540000 0.1089180000 0.0571070000 0.0352600000 0.3048130000 0.3179650000 114508963 0 402718720 3.9070835114 4.0676984787 3.9279589653 402 16.0400000000 0.0105230287 0.0105193844 0.0160688832 0.0147443058 0.4870140000 0.1183770000 0.0576850000 0.0000000000 0.3082770000 0.0019610000 114511739 0 402718720 3.9091949463 4.0679836273 3.9291002750 403 16.0800000000 0.0106130242 0.0105196167 0.0160688832 0.0147442692 0.5192390000 0.1130070000 0.0576630000 0.0351650000 0.3107300000 0.0019670000 114514515 0 402718720 3.9107520580 4.0663380623 3.9298579693 404 16.1200000000 0.0106566390 0.0105199559 0.0160688832 0.0147511165 0.4994340000 0.1243910000 0.0604560000 0.0000000000 0.3117840000 0.0020620000 114517291 0 402718720 3.9126143456 4.0664277077 3.9304978848 405 16.1600000000 0.0107512837 0.0105205271 0.0160688832 0.0147532176 0.8459140000 0.1129490000 0.0580010000 0.0357820000 0.3156010000 0.3228800000 114520067 0 402718720 3.9151117802 4.0679235458 3.9313852787 406 16.2000000000 0.0108907074 0.0105214389 0.0160688832 0.0147501039 0.5053330000 0.1258540000 0.0579220000 0.0000000000 0.3188700000 0.0019620000 114522843 0 402718720 3.9174797535 4.0683078766 3.9327461720 407 16.2400000000 0.0109801078 0.0105225658 0.0160688832 0.0147566312 0.5234650000 0.1088230000 0.0547510000 0.0354230000 0.3217960000 0.0019660000 114525619 0 402718720 3.9204726219 4.0684709549 3.9340946674 408 16.2800000000 0.0111032035 0.0105239889 0.0160688832 0.0147610766 0.4939740000 0.1088400000 0.0571710000 0.0000010000 0.3252810000 0.0019660000 114528395 0 402718720 3.9231791496 4.0689659119 3.9350829124 409 16.3200000000 0.0110744797 0.0105253349 0.0160688832 0.0147530981 0.9028910000 0.1374690000 0.0673840000 0.0357720000 0.3274570000 0.3340960000 114531171 0 402718720 3.9264063835 4.0691246986 3.9368281364 410 16.3600000000 0.0110965902 0.0105267282 0.0160688832 0.0147557245 0.5134220000 0.1129230000 0.0673850000 0.0000000000 0.3304290000 0.0019630000 114533947 0 402718720 3.9295442104 4.0685429573 3.9386172295 411 16.3999999990 0.0111528710 0.0105282517 0.0160688832 0.0147658423 0.5415260000 0.1128840000 0.0581500000 0.0357590000 0.3320470000 0.0019660000 114536723 0 402718720 3.9327125549 4.0669612885 3.9404006004 412 16.4400000000 0.0111376150 0.0105297307 0.0160688832 0.0147694384 0.4992030000 0.1129460000 0.0481330000 0.0000010000 0.3354350000 0.0019610000 114539499 0 402718720 3.9345877171 4.0668377876 3.9414691925 413 16.4800000000 0.0112359766 0.0105314407 0.0160688832 0.0147747886 0.9031740000 0.1236160000 0.0607460000 0.0352970000 0.3378030000 0.3449990000 114542275 0 402718720 3.9375727177 4.0653824806 3.9434678555 414 16.5200000000 0.0112447925 0.0105331638 0.0160688832 0.0147685949 0.5286820000 0.1257640000 0.0606460000 0.0000000000 0.3395730000 0.0019690000 114545051 0 402718720 3.9396054745 4.0655193329 3.9443767071 415 16.5599999990 0.0113187376 0.0105350568 0.0160688832 0.0147591752 0.5658970000 0.1259950000 0.0568350000 0.0357190000 0.3446560000 0.0019650000 114547827 0 402718720 3.9417433739 4.0661702156 3.9452261925 416 16.6000000000 0.0112885721 0.0105368681 0.0160688832 0.0147470138 0.5306890000 0.1129180000 0.0675330000 0.0000000000 0.3475470000 0.0019650000 114550603 0 402718720 3.9430720806 4.0663418770 3.9458029270 417 16.6400000000 0.0113153746 0.0105387350 0.0160688832 0.0147385919 0.9213090000 0.1111770000 0.0675330000 0.0357200000 0.3499520000 0.3562090000 114553379 0 402718720 3.9454891682 4.0669388771 3.9468553066 418 16.6800000000 0.0113383839 0.0105406480 0.0160688832 0.0147293241 0.5279760000 0.1127820000 0.0606970000 0.0000010000 0.3518020000 0.0019640000 114556155 0 402718720 3.9460582733 4.0658731461 3.9470679760 419 16.7199999990 0.0113922218 0.0105426804 0.0160688832 0.0147231575 0.5569380000 0.1087700000 0.0549920000 0.0355330000 0.3549440000 0.0019650000 114558931 0 402718720 3.9486575127 4.0652570724 3.9481453896 420 16.7600000000 0.0114531722 0.0105448483 0.0160688832 0.0147210524 0.5635090000 0.1353520000 0.0675640000 0.0000000000 0.3578720000 0.0019620000 114561707 0 402718720 3.9503717422 4.0637497902 3.9496304989 421 16.8000000000 0.0114428345 0.0105469813 0.0160688832 0.0147208933 0.9464900000 0.1259440000 0.0579700000 0.0357590000 0.3598800000 0.3662060000 114564483 0 402718720 3.9525759220 4.0620398521 3.9512758255 422 16.8400000000 0.0115025705 0.0105492457 0.0160688832 0.0147154646 0.5382720000 0.1127690000 0.0556280000 0.0000010000 0.3663220000 0.0027140000 114567259 0 402718720 3.9541604519 4.0627017021 3.9519968033 423 16.8799999990 0.0116154691 0.0105517663 0.0160688832 0.0147115740 0.6630810000 0.1453200000 0.0872450000 0.0454540000 0.3815000000 0.0027160000 114570035 0 402718720 3.9563035965 4.0617990494 3.9530878067 424 16.9200000000 0.0116220657 0.0105542906 0.0160688832 0.0147026214 0.5652310000 0.1290550000 0.0650580000 0.0000010000 0.3684130000 0.0019600000 114572811 0 402718720 3.9590697289 4.0605936050 3.9542813301 425 16.9600000000 0.0116946250 0.0105569737 0.0160688832 0.0147087020 0.9771130000 0.1243120000 0.0556760000 0.0351980000 0.3704930000 0.3905950000 114575587 0 402718720 3.9615147114 4.0605626106 3.9564373493 426 17.0000000000 0.0117233479 0.0105597117 0.0160688832 0.0147040114 0.5634300000 0.1293520000 0.0580480000 0.0000010000 0.3733300000 0.0019520000 114578363 0 402718720 3.9639074802 4.0566406250 3.9580101967 427 17.0400000000 0.0116761811 0.0105623264 0.0160688832 0.0146995291 0.5805090000 0.1087030000 0.0574430000 0.0353040000 0.3764170000 0.0018960000 114581139 0 402718720 3.9669716358 4.0556111336 3.9589014053 428 17.0800000000 0.0117600141 0.0105651247 0.0160688832 0.0146940216 0.5490140000 0.1124330000 0.0556590000 0.0000000000 0.3782160000 0.0019550000 114583915 0 402718720 3.9698271751 4.0555281639 3.9602560997 429 17.1200000000 0.0117390221 0.0105678611 0.0160688832 0.0146879990 0.9732670000 0.1126580000 0.0580790000 0.0351850000 0.3801450000 0.3864500000 114586691 0 402718720 3.9722399712 4.0549077988 3.9613785744 430 17.1600000000 0.0118438853 0.0105708286 0.0160688832 0.0146795589 0.5780830000 0.1322170000 0.0608790000 0.0000010000 0.3822580000 0.0019580000 114589467 0 402718720 3.9746956825 4.0574402809 3.9619257450 431 17.2000000000 0.0118080750 0.0105736992 0.0160688832 0.0146735042 0.5935140000 0.1124400000 0.0580440000 0.0356850000 0.3846280000 0.0019620000 114592243 0 402718720 3.9771957397 4.0572071075 3.9623000622 432 17.2400000000 0.0117704086 0.0105764694 0.0160688832 0.0146743130 0.5706660000 0.1253200000 0.0556260000 0.0000000000 0.3870040000 0.0019540000 114595019 0 402718720 3.9797685146 4.0523900986 3.9636452198 433 17.2800000000 0.0118136816 0.0105793267 0.0160688832 0.0146865642 0.9885330000 0.1123850000 0.0556210000 0.0351200000 0.3891980000 0.3954520000 114597795 0 402718720 3.9809961319 4.0483641624 3.9654722214 434 17.3200000000 0.0118326806 0.0105822146 0.0160688832 0.0146907880 0.5784030000 0.1123620000 0.0581000000 0.0000000000 0.4042660000 0.0028140000 114600571 0 402718720 3.9836776257 4.0461854935 3.9670832157 435 17.3600000000 0.0118917571 0.0105852250 0.0160688832 0.0146953516 0.6684150000 0.1445640000 0.0744930000 0.0450270000 0.4016150000 0.0019530000 114603347 0 402718720 3.9859802723 4.0428185463 3.9680998325 436 17.4000000000 0.0118897120 0.0105882170 0.0160688832 0.0146941373 0.5702160000 0.1122530000 0.0582090000 0.0000010000 0.3970370000 0.0019500000 114606123 0 402718720 3.9872050285 4.0410885811 3.9692425728 437 17.4400000000 0.0118882870 0.0105911920 0.0160688832 0.0146897067 1.0183430000 0.1121920000 0.0651400000 0.0351600000 0.3993770000 0.4057170000 114608899 0 402718720 3.9877755642 4.0403642654 3.9696238041 438 17.4800000000 0.0119429696 0.0105942782 0.0160688832 0.0147047328 0.5878040000 0.1249700000 0.0580590000 0.0000010000 0.4020590000 0.0019460000 114611675 0 402718720 3.9879238605 4.0400424004 3.9708812237 439 17.5200000000 0.0119628254 0.0105973956 0.0160688832 0.0147136959 0.6063070000 0.1083370000 0.0550670000 0.0352210000 0.4049780000 0.0019480000 114614451 0 402718720 3.9875481129 4.0390038490 3.9716324806 440 17.5600000000 0.0120056588 0.0106005962 0.0160688832 0.0147172752 0.5774800000 0.1120040000 0.0556030000 0.0000010000 0.4071400000 0.0019540000 114617227 0 402718720 3.9859750271 4.0385594368 3.9720032215 441 17.6000000000 0.0120174326 0.0106038090 0.0160688832 0.0147296489 1.0351440000 0.1082070000 0.0550130000 0.0350570000 0.4127000000 0.4234080000 114620003 0 402718720 3.9846179485 4.0379033089 3.9731152058 442 17.6400000000 0.0120337252 0.0106070441 0.0160688832 0.0148202171 0.5846290000 0.1115780000 0.0551150000 0.0000000000 0.4152090000 0.0019530000 114622779 0 402718720 3.9752550125 4.0346803665 3.9732959270 443 17.6800000000 0.0119918697 0.0106101701 0.0160688832 0.0148291712 0.6424070000 0.1321780000 0.0582130000 0.0355630000 0.4135950000 0.0020480000 114625555 0 402718720 3.9712152481 4.0351271629 3.9731194973 444 17.7200000000 0.0120137604 0.0106133314 0.0160688832 0.0148345041 0.5925890000 0.1113090000 0.0587360000 0.0000000000 0.4198070000 0.0019510000 114628331 0 402718720 3.9687893391 4.0349922180 3.9738149643 445 17.7600000000 0.0120331375 0.0106165220 0.0160688832 0.0148406666 1.0866070000 0.1273170000 0.0607640000 0.0354220000 0.4200010000 0.4422350000 114631107 0 402718720 3.9670546055 4.0308647156 3.9745841026 446 17.8000000000 0.0118665537 0.0106193247 0.0160688832 0.0148493765 0.6499920000 0.1413300000 0.0746600000 0.0000010000 0.4312730000 0.0019440000 114633883 0 402718720 3.9653608799 4.0286717415 3.9754216671 447 17.8400000000 0.0119997226 0.0106224129 0.0160688832 0.0148486334 0.6293530000 0.1107020000 0.0556170000 0.0353730000 0.4249380000 0.0019470000 114636659 0 402718720 3.9664330482 4.0244112015 3.9770870209 448 17.8800000000 0.0119216461 0.0106253129 0.0160688832 0.0148402395 0.5960370000 0.1104250000 0.0555560000 0.0000010000 0.4273800000 0.0018840000 114639435 0 402718720 3.9672958851 4.0215115547 3.9782776833 449 17.9200000000 0.0119394567 0.0106282398 0.0160688832 0.0148311353 1.0652510000 0.1102510000 0.0554890000 0.0348130000 0.4286280000 0.4352870000 114642211 0 402718720 3.9654037952 4.0186500549 3.9804627895 450 17.9600000000 0.0119049894 0.0106310770 0.0160688832 0.0148187192 0.6140250000 0.1226440000 0.0578540000 0.0000000000 0.4307910000 0.0019390000 114644987 0 402718720 3.9662625790 4.0153489113 3.9820709229 451 18.0000000000 0.0119643463 0.0106340332 0.0160688832 0.0148111527 0.6596610000 0.1340050000 0.0555380000 0.0352530000 0.4321220000 0.0019490000 114647763 0 402718720 3.9665141106 4.0146865845 3.9851064682 452 18.0400000000 0.0117895454 0.0106365897 0.0160688832 0.0148057735 0.5953670000 0.1061310000 0.0525370000 0.0000010000 0.4339550000 0.0019330000 114650539 0 402718720 3.9668660164 4.0122156143 3.9881706238 453 18.0800000000 0.0117745996 0.0106391018 0.0160688832 0.0147956896 1.0855140000 0.1087550000 0.0650520000 0.0347360000 0.4350820000 0.4411070000 114653315 0 402718720 3.9678506851 4.0107216835 3.9913918972 454 18.1200000000 0.0117661748 0.0106415844 0.0160688832 0.0147836858 0.6484560000 0.1238990000 0.0882430000 0.0000010000 0.4335660000 0.0019320000 114656091 0 402718720 3.9683029652 4.0101313591 3.9953782558 455 18.1600000000 0.0118247848 0.0106441848 0.0160688832 0.0147688954 0.6464850000 0.1079100000 0.0650680000 0.0346610000 0.4361090000 0.0019400000 114658867 0 402718720 3.9698872566 4.0085744858 3.9992740154 456 18.2000000000 0.0117322188 0.0106465709 0.0160688832 0.0147600782 0.6012010000 0.1061940000 0.0556650000 0.0000000000 0.4366050000 0.0019300000 114661643 0 402718720 3.9710178375 4.0073575974 4.0042562485 457 18.2400000000 0.0117084598 0.0106488945 0.0160688832 0.0147530701 1.0809160000 0.1071360000 0.0582580000 0.0351610000 0.4366310000 0.4429450000 114664419 0 402718720 3.9711065292 4.0103173256 4.0089502335 458 18.2800000000 0.0116732838 0.0106511311 0.0160688832 0.0147421790 0.6047630000 0.1069360000 0.0583290000 0.0000010000 0.4367660000 0.0019260000 114667195 0 402718720 3.9722228050 4.0110211372 4.0151739120 459 18.3200000000 0.0116553595 0.0106533190 0.0160688832 0.0147274595 0.6338170000 0.1041360000 0.0558050000 0.0350960000 0.4360520000 0.0019260000 114669971 0 402718720 3.9745800495 4.0111656189 4.0212697983 460 18.3600000000 0.0115402434 0.0106552471 0.0160688832 0.0147132154 0.6177700000 0.1192790000 0.0611580000 0.0000010000 0.4345960000 0.0019280000 114672747 0 402718720 3.9760203362 4.0147404671 4.0277805328 461 18.4000000000 0.0116561018 0.0106574181 0.0160688832 0.0146984970 1.0870090000 0.1060100000 0.0558910000 0.0344990000 0.4362150000 0.4534860000 114675523 0 402718720 3.9768035412 4.0146474838 4.0350246429 462 18.4400000000 0.0115370387 0.0106593221 0.0160688832 0.0146831486 0.6475050000 0.1340300000 0.0622970000 0.0000010000 0.4484490000 0.0019180000 114678299 0 402718720 3.9801607132 4.0150923729 4.0427274704 463 18.4800000000 0.0115355691 0.0106612146 0.0160688832 0.0146704568 0.6374340000 0.1051070000 0.0585370000 0.0349820000 0.4360720000 0.0019200000 114681075 0 402718720 3.9807605743 4.0173702240 4.0507917404 464 18.5200000000 0.0115454681 0.0106631203 0.0160688832 0.0146574869 0.6013190000 0.1051100000 0.0558850000 0.0000010000 0.4375840000 0.0019200000 114683851 0 402718720 3.9814431667 4.0194191933 4.0599083900 465 18.5600000000 0.0114830742 0.0106648837 0.0160688832 0.0146460902 1.0735800000 0.1047110000 0.0560460000 0.0342420000 0.4357480000 0.4420210000 114686627 0 402718720 3.9854426384 4.0258922577 4.0794439316 466 18.6000000000 0.0114762885 0.0106666249 0.0160688832 0.0146314653 0.6222530000 0.1292710000 0.0587560000 0.0000010000 0.4314810000 0.0019150000 114689403 0 402718720 3.9881520271 4.0298066139 4.0898160934 467 18.6400000000 0.0115944799 0.0106686117 0.0160688832 0.0146166085 0.6292420000 0.1045620000 0.0559960000 0.0345540000 0.4313880000 0.0019200000 114692179 0 402718720 3.9909040928 4.0309023857 4.1008076668 468 18.6800000000 0.0115738986 0.0106705461 0.0160688832 0.0146034559 0.5947930000 0.1045050000 0.0560420000 0.0000010000 0.4314990000 0.0019180000 114694955 0 402718720 3.9929163456 4.0356903076 4.1119012833 469 18.7200000000 0.0115626631 0.0106724483 0.0160688832 0.0145925375 1.0819500000 0.1047230000 0.0584320000 0.0345100000 0.4332960000 0.4500680000 114697731 0 402718720 3.9943995476 4.0389785767 4.1234617233 470 18.7600000000 0.0116788233 0.0106745895 0.0160688832 0.0145860473 0.6572320000 0.1331320000 0.0752320000 0.0000010000 0.4461160000 0.0019240000 114700507 0 402718720 3.9964399338 4.0442447662 4.1352634430 471 18.8000000000 0.0116470521 0.0106766542 0.0160688832 0.0145792173 0.6269600000 0.1029120000 0.0560880000 0.0343230000 0.4308890000 0.0019280000 114703283 0 402718720 3.9978289604 4.0500221252 4.1476740837 472 18.8400000000 0.0115739033 0.0106785551 0.0160688832 0.0145645972 0.5855410000 0.1046620000 0.0483550000 0.0000010000 0.4298260000 0.0018650000 114706059 0 402718720 4.0010581017 4.0561828613 4.1595172882 473 18.8800000000 0.0116573786 0.0106806245 0.0160688832 0.0145493720 1.0545710000 0.1018580000 0.0579180000 0.0338560000 0.4273170000 0.4327950000 114708835 0 402718720 4.0037198067 4.0637941360 4.1714248657 474 18.9200000000 0.0117060905 0.0106827879 0.0160688832 0.0145379098 0.5933450000 0.1190950000 0.0463260000 0.0000010000 0.4251480000 0.0019210000 114711611 0 402718720 4.0070261955 4.0701093674 4.1826539040 475 18.9600000000 0.0115973819 0.0106847134 0.0160688832 0.0145298430 0.6220050000 0.1043310000 0.0560990000 0.0334860000 0.4253280000 0.0019280000 114714387 0 402718720 4.0106811523 4.0748600960 4.1953415871 476 19.0000000000 0.0116787143 0.0106868016 0.0160688832 0.0145201638 0.5787940000 0.1040730000 0.0463940000 0.0000000000 0.4255650000 0.0019220000 114717163 0 402718720 4.0140638351 4.0777206421 4.2073407173 477 19.0400000000 0.0117785744 0.0106890905 0.0160688832 0.0145072897 1.0561070000 0.1043130000 0.0585910000 0.0332900000 0.4243150000 0.4346570000 114719939 0 402718720 4.0155572891 4.0845408440 4.2191734314 478 19.0800000000 0.0116377864 0.0106910752 0.0160688832 0.0144944836 0.6514800000 0.1326360000 0.0752210000 0.0000010000 0.4399830000 0.0026900000 114722715 0 402718720 4.0192818642 4.0917859077 4.2303195000 479 19.1200000000 0.0118363528 0.0106934662 0.0160688832 0.0144842663 0.6370220000 0.1248460000 0.0560360000 0.0331850000 0.4201780000 0.0019330000 114725491 0 402718720 4.0227661133 4.0952839851 4.2422227859 480 19.1600000000 0.0118027991 0.0106957773 0.0160688832 0.0144753176 0.5937390000 0.1126530000 0.0614620000 0.0000000000 0.4169130000 0.0018640000 114728267 0 402718720 4.0265445709 4.1000723839 4.2533640862 481 19.2000000000 0.0117048277 0.0106978751 0.0160688832 0.0144617512 1.0367290000 0.1044640000 0.0560760000 0.0335160000 0.4177720000 0.4240620000 114731043 0 402718720 4.0277247429 4.1100878716 4.2636399269 482 19.2400000000 0.0117204851 0.0106999967 0.0160688832 0.0144598625 0.6038190000 0.1293810000 0.0587800000 0.0000010000 0.4127470000 0.0020090000 114733819 0 402718720 4.0315971375 4.1144533157 4.2752313614 483 19.2800000000 0.0117381671 0.0107021461 0.0160688832 0.0144614740 0.6176460000 0.1042610000 0.0488970000 0.0328600000 0.4279740000 0.0026900000 114736595 0 402718720 4.0341281891 4.1151371002 4.2867422104 484 19.3200000000 0.0117436666 0.0107042980 0.0160688832 0.0144594642 0.6392220000 0.1324720000 0.0752880000 0.0000000000 0.4286750000 0.0019240000 114739371 0 402718720 4.0377030373 4.1164469719 4.2979140282 485 19.3600000000 0.0116522321 0.0107062525 0.0160688832 0.0144471286 1.0947880000 0.1259960000 0.0910730000 0.0417380000 0.4153170000 0.4198160000 114742147 0 402718720 4.0397305489 4.1199574471 4.3090786934 486 19.4000000000 0.0117007922 0.0107082989 0.0160688832 0.0144322281 0.6535840000 0.1290540000 0.0911720000 0.0000010000 0.4297040000 0.0026900000 114744923 0 402718720 4.0427136421 4.1268858910 4.3192081451 487 19.4400000000 0.0116701899 0.0107102740 0.0160688832 0.0144175694 0.6451450000 0.1334850000 0.0642040000 0.0331000000 0.4115720000 0.0019280000 114747699 0 402718720 4.0430765152 4.1309146881 4.3309531212 488 19.4800000000 0.0116839623 0.0107122693 0.0160688832 0.0144030787 0.5862860000 0.1184670000 0.0535270000 0.0000010000 0.4115030000 0.0019280000 114750475 0 402718720 4.0451817513 4.1336483955 4.3419928551 489 19.5200000000 0.0117449779 0.0107143812 0.0160688832 0.0143889397 1.0338550000 0.1188400000 0.0560760000 0.0329680000 0.4094170000 0.4156920000 114753251 0 402718720 4.0458507538 4.1413936615 4.3526043892 490 19.5600000000 0.0118412655 0.0107166809 0.0160688832 0.0143748838 0.6094980000 0.1372960000 0.0614140000 0.0000010000 0.4080020000 0.0019300000 114756027 0 402718720 4.0461983681 4.1468462944 4.3633670807 491 19.6000000000 0.0116725201 0.0107186277 0.0160688832 0.0143605549 0.6131240000 0.1140560000 0.0559480000 0.0328050000 0.4075290000 0.0019270000 114758803 0 402718720 4.0490880013 4.1528573036 4.3736510277 492 19.6400000000 0.0119118271 0.0107210529 0.0160688832 0.0143459842 0.5778080000 0.1058420000 0.0661870000 0.0000010000 0.4028740000 0.0020170000 114761579 0 402718720 4.0492439270 4.1574587822 4.3839468956 493 19.6800000000 0.0118048470 0.0107232512 0.0160688832 0.0143317731 1.0155920000 0.1056010000 0.0582240000 0.0321570000 0.4063120000 0.4124530000 114764355 0 402718720 4.0498261452 4.1599364281 4.3948426247 494 19.7200000000 0.0117368503 0.0107253031 0.0160688832 0.0143172473 0.5710100000 0.1048160000 0.0583290000 0.0000010000 0.4050950000 0.0019230000 114767131 0 402718720 4.0499963760 4.1609845161 4.4060702324 495 19.7600000000 0.0118035767 0.0107274814 0.0160688832 0.0143039176 0.6123110000 0.1159640000 0.0587120000 0.0326340000 0.4022150000 0.0019260000 114769907 0 402718720 4.0506920815 4.1658792496 4.4172186852 496 19.8000000000 0.0118062673 0.0107296564 0.0160688832 0.0142912664 0.5711000000 0.1054470000 0.0587400000 0.0000010000 0.4041250000 0.0019250000 114772683 0 402718720 4.0507392883 4.1726117134 4.4277229309 497 19.8400000000 0.0117676156 0.0107317448 0.0160688832 0.0142791854 1.0090220000 0.1056980000 0.0584620000 0.0319130000 0.4030470000 0.4090560000 114775459 0 402718720 4.0506219864 4.1787548065 4.4387192726 498 19.8800000000 0.0118503664 0.0107339910 0.0160688832 0.0142702949 0.5792570000 0.1262680000 0.0485330000 0.0000010000 0.4017250000 0.0018710000 114778235 0 402718720 4.0493025780 4.1856989861 4.4494810104 499 19.9200000000 0.0118799387 0.0107362875 0.0160688832 0.0142622219 0.5902250000 0.1058290000 0.0509930000 0.0324280000 0.3981820000 0.0019280000 114781011 0 402718720 4.0483779907 4.1919927597 4.4611449242 500 19.9600000000 0.0118118180 0.0107384386 0.0160688832 0.0142523345 0.5646980000 0.1057170000 0.0558850000 0.0000010000 0.4002980000 0.0019260000 114783787 0 402718720 4.0473098755 4.1938018799 4.4723019600 501 20.0000000000 0.0117132450 0.0107403843 0.0160688832 0.0142433983 1.0214520000 0.1290510000 0.0586740000 0.0323290000 0.3958220000 0.4047170000 114786563 0 402718720 4.0458097458 4.1966614723 4.4831333160 502 20.0400000000 0.0117725367 0.0107424404 0.0160688832 0.0142339999 0.5535150000 0.1061880000 0.0464110000 0.0000000000 0.3981280000 0.0019200000 114789339 0 402718720 4.0443840027 4.2014636993 4.4942011833 503 20.0800000000 0.0118549159 0.0107446521 0.0160688832 0.0142220986 0.5938800000 0.1064850000 0.0560260000 0.0315550000 0.3970140000 0.0019300000 114792115 0 402718720 4.0421710014 4.2080545425 4.5050067902 504 20.1200000000 0.0117547167 0.0107466562 0.0160688832 0.0142079950 0.5733220000 0.1183870000 0.0559330000 0.0000010000 0.3962090000 0.0019220000 114794891 0 402718720 4.0395226479 4.2129950523 4.5158891678 505 20.1600000000 0.0118468534 0.0107488348 0.0160688832 0.0141941503 1.0003710000 0.1069270000 0.0586260000 0.0321010000 0.3925680000 0.4091670000 114797667 0 402718720 4.0379786491 4.2194781303 4.5265135765 506 20.2000000000 0.0117725730 0.0107508580 0.0160688832 0.0141833794 0.6298050000 0.1360070000 0.0783780000 0.0000000000 0.4117410000 0.0026840000 114800443 0 402718720 4.0359983444 4.2285556793 4.5364837646 507 20.2400000000 0.0117194699 0.0107527684 0.0160688832 0.0141800761 0.5947130000 0.1121720000 0.0534790000 0.0319790000 0.3942750000 0.0019210000 114803219 0 402718720 4.0331344604 4.2335953712 4.5469646454 508 20.2800000000 0.0117363306 0.0107547046 0.0160688832 0.0141786796 0.5596090000 0.1072730000 0.0587370000 0.0000000000 0.3907830000 0.0019220000 114805995 0 402718720 4.0309190750 4.2382473946 4.5570802689 509 20.3200000000 0.0117483092 0.0107566567 0.0160688832 0.0141901167 1.0469800000 0.1447970000 0.0719070000 0.0385820000 0.3924710000 0.3983340000 114808771 0 402718720 4.0282950401 4.2448892593 4.5666332245 510 20.3600000000 0.0118147070 0.0107587313 0.0160688832 0.0141914500 0.5555130000 0.1075290000 0.0535150000 0.0000010000 0.3916370000 0.0019370000 114811547 0 402718720 4.0243682861 4.2495474815 4.5760836601 511 20.4000000000 0.0117994882 0.0107607680 0.0160688832 0.0141897793 0.5993740000 0.1078580000 0.0558740000 0.0317980000 0.4001520000 0.0026960000 114814323 0 402718720 4.0223126411 4.2543606758 4.5848088264 512 20.4400000000 0.0118144341 0.0107628259 0.0160688832 0.0141953130 0.6263450000 0.1368770000 0.0784270000 0.0000010000 0.4073460000 0.0026890000 114817099 0 402718720 4.0219674110 4.2609310150 4.5928015709 513 20.4800000000 0.0118239373 0.0107648944 0.0160688832 0.0141961285 0.9860700000 0.1086120000 0.0582190000 0.0317080000 0.3902360000 0.3964030000 114869027 0 402718720 4.0203180313 4.2651715279 4.6010780334 514 20.5200000000 0.0118532823 0.0107670118 0.0160688832 0.0141995437 0.5980600000 0.1126390000 0.0750100000 0.0000000000 0.4067030000 0.0026920000 114974203 0 402718720 4.0189447403 4.2673773766 4.6095666885 515 20.5600000000 0.0117729725 0.0107689652 0.0160688832 0.0142055128 0.6501480000 0.1379460000 0.0748980000 0.0381550000 0.3963150000 0.0019390000 114976979 0 402718720 4.0185694695 4.2691721916 4.6166443825 516 20.6000000000 0.0117919464 0.0107709477 0.0160688832 0.0142204264 0.5553340000 0.1064750000 0.0552860000 0.0000010000 0.3908020000 0.0018720000 114979755 0 402718720 4.0185914040 4.2747864723 4.6238455772 517 20.6400000000 0.0118467901 0.0107730286 0.0160688832 0.0142345981 1.0126430000 0.1099230000 0.0557710000 0.0316500000 0.4013840000 0.4129010000 114982531 0 402718720 4.0188131332 4.2784466743 4.6304140091 518 20.6800000000 0.0118317548 0.0107750725 0.0160688832 0.0142529782 0.5940470000 0.1395740000 0.0618230000 0.0000010000 0.3898070000 0.0019380000 114985307 0 402718720 4.0189132690 4.2815065384 4.6368908882 519 20.7200000000 0.0118396487 0.0107771237 0.0160688832 0.0142719889 0.6019930000 0.1194090000 0.0610550000 0.0316850000 0.3869910000 0.0019420000 114988083 0 402718720 4.0208396912 4.2852568626 4.6425914764 520 20.7600000000 0.0117964847 0.0107790840 0.0160688832 0.0143002325 0.5501770000 0.1108710000 0.0459700000 0.0000010000 0.3905550000 0.0018740000 114990859 0 402718720 4.0220537186 4.2881808281 4.6481199265 521 20.8000000000 0.0117452322 0.0107809384 0.0160688832 0.0143251434 0.9842570000 0.1110630000 0.0556260000 0.0309870000 0.3898320000 0.3958520000 114993635 0 402718720 4.0239543915 4.2888011932 4.6534557343 522 20.8400000000 0.0118094962 0.0107829088 0.0160688832 0.0143529311 0.5624420000 0.1111470000 0.0557350000 0.0000010000 0.3918430000 0.0026900000 114996411 0 402718720 4.0253543854 4.2890958786 4.6586527824 523 20.8800000000 0.0117820147 0.0107848192 0.0160688832 0.0143822464 0.6654490000 0.1419520000 0.0747480000 0.0379220000 0.4071040000 0.0026960000 114999187 0 402718720 4.0274558067 4.2888545990 4.6631793976 524 20.9200000000 0.0117933713 0.0107867439 0.0160688832 0.0144164573 0.5951050000 0.1422870000 0.0590910000 0.0000010000 0.3908730000 0.0019310000 115001963 0 402718720 4.0298905373 4.2923393250 4.6673426628 525 20.9600000000 0.0118311988 0.0107887333 0.0160688832 0.0144336352 0.9875770000 0.1114480000 0.0483520000 0.0317030000 0.3880110000 0.4070390000 115004739 0 402718720 4.0325717926 4.2939591408 4.6712479591 526 21.0000000000 0.0118387472 0.0107907296 0.0160688832 0.0144451041 0.6224780000 0.1427010000 0.0715190000 0.0000010000 0.4054090000 0.0019260000 115007515 0 402718720 4.0355343819 4.2933959961 4.6749620438 527 21.0400000000 0.0118900510 0.0107928156 0.0160688832 0.0144619574 0.5951160000 0.1114410000 0.0580580000 0.0310250000 0.3917550000 0.0019300000 115010291 0 402718720 4.0382657051 4.2949595451 4.6784620285 528 21.0800000000 0.0119534824 0.0107950138 0.0160688832 0.0144723501 0.5673700000 0.1114300000 0.0556180000 0.0000010000 0.3965840000 0.0026890000 115013067 0 402718720 4.0417675972 4.2966132164 4.6814584732 529 21.1200000000 0.0119900508 0.0107972728 0.0160688832 0.0144746130 1.0780700000 0.1432430000 0.0746510000 0.0381120000 0.4087270000 0.4122940000 115015843 0 402718720 4.0443458557 4.2967014313 4.6844339371 530 21.1600000000 0.0120355738 0.0107996093 0.0160688832 0.0144798297 0.5843740000 0.1241550000 0.0651130000 0.0000010000 0.3922480000 0.0019230000 115018619 0 402718720 4.0475969315 4.2978811264 4.6871643066 531 21.2000000000 0.0120434538 0.0108019517 0.0160688832 0.0144903045 0.5932810000 0.1084340000 0.0579770000 0.0317100000 0.3923170000 0.0019220000 115021395 0 402718720 4.0513834953 4.2981157303 4.6897506714 532 21.2400000000 0.0120099783 0.0108042224 0.0160688832 0.0145057444 0.5831380000 0.1326590000 0.0582160000 0.0000010000 0.3894030000 0.0019200000 115024171 0 402718720 4.0550117493 4.2974328995 4.6920342445 533 21.2800000000 0.0120065315 0.0108064782 0.0160688832 0.0145243593 1.0021800000 0.1118860000 0.0651320000 0.0318540000 0.3931200000 0.3991770000 115026947 0 402718720 4.0591559410 4.2977375984 4.6942501068 534 21.3200000000 0.0120098144 0.0108087316 0.0160688832 0.0145413706 0.6488700000 0.1440500000 0.0906990000 0.0000010000 0.4103890000 0.0026720000 115029723 0 402718720 4.0632424355 4.2977347374 4.6964702606 535 21.3600000000 0.0120214103 0.0108109983 0.0160688832 0.0145586944 0.6522430000 0.1441900000 0.0779370000 0.0335250000 0.3937390000 0.0019150000 115032499 0 402718720 4.0670018196 4.2982082367 4.6987943649 536 21.4000000000 0.0120805455 0.0108133669 0.0160688832 0.0145761603 0.5611510000 0.1083140000 0.0549520000 0.0000010000 0.3950430000 0.0019140000 115035275 0 402718720 4.0707902908 4.2987971306 4.7009305954 537 21.4400000000 0.0121448133 0.0108158463 0.0160688832 0.0145953962 0.9893980000 0.1122630000 0.0484390000 0.0319720000 0.3948700000 0.4009190000 115038051 0 402718720 4.0752673149 4.2994499207 4.7031807899 538 21.4800000000 0.0121318549 0.0108182924 0.0160688832 0.0146045037 0.5876580000 0.1240520000 0.0644390000 0.0000000000 0.3963670000 0.0018560000 115040827 0 402718720 4.0800142288 4.3003816605 4.7051143646 539 21.5200000000 0.0122102527 0.0108208749 0.0160688832 0.0146147926 0.6382090000 0.1412410000 0.0599980000 0.0320830000 0.4011250000 0.0026800000 115043603 0 402718720 4.0850052834 4.3016505241 4.7067532539 540 21.5600000000 0.0121090626 0.0108232604 0.0160688832 0.0146167374 0.6364530000 0.1446410000 0.0747610000 0.0000000000 0.4133090000 0.0026740000 115046379 0 402718720 4.0888791084 4.3019127846 4.7089858055 541 21.6000000000 0.0122217443 0.0108258454 0.0160688832 0.0146203798 1.0259500000 0.1348670000 0.0579330000 0.0321390000 0.3970380000 0.4030340000 115049155 0 402718720 4.0933089256 4.3020992279 4.7108163834 542 21.6400000000 0.0122653721 0.0108285014 0.0160688832 0.0146280762 0.5809160000 0.1098940000 0.0554970000 0.0000010000 0.4117810000 0.0026710000 115051931 0 402718720 4.0970516205 4.3035292625 4.7127542496 543 21.6800000000 0.0121974275 0.0108310224 0.0160688832 0.0146446135 0.6708080000 0.1448060000 0.0748130000 0.0398020000 0.4085170000 0.0019230000 115054707 0 402718720 4.1010098457 4.3042221069 4.7148566246 544 21.7200000000 0.0122256018 0.0108335860 0.0160688832 0.0146592044 0.5668030000 0.1085500000 0.0549390000 0.0000010000 0.4005100000 0.0018560000 115057483 0 402718720 4.1040596962 4.3048129082 4.7170305252 545 21.7600000000 0.0122689558 0.0108362197 0.0160688832 0.0146736305 1.0348360000 0.1126160000 0.0555810000 0.0318280000 0.4100700000 0.4236670000 115060259 0 402718720 4.1083154678 4.3066730499 4.7191939354 546 21.8000000000 0.0123573542 0.0108390056 0.0160688832 0.0147495935 0.6108310000 0.1447440000 0.0619040000 0.0000010000 0.4013070000 0.0019140000 115063035 0 402718720 4.1139941216 4.3079595566 4.7236285210 547 21.8400000000 0.0123452973 0.0108417594 0.0160688832 0.0147577092 0.6075160000 0.1124400000 0.0580130000 0.0325340000 0.4016460000 0.0019180000 115065811 0 402718720 4.1176099777 4.3087849617 4.7258834839 548 21.8800000000 0.0123041868 0.0108444280 0.0160688832 0.0147707657 0.6027470000 0.1124350000 0.0671090000 0.0000000000 0.4194360000 0.0026750000 115068587 0 402718720 4.1217522621 4.3106074333 4.7276940346 549 21.9200000000 0.0123436144 0.0108471588 0.0160688832 0.0147916030 1.0654100000 0.1447360000 0.0621090000 0.0404560000 0.4083700000 0.4087460000 115071363 0 402718720 4.1252455711 4.3123764992 4.7299165726 550 21.9600000000 0.0123063643 0.0108498119 0.0160688832 0.0148086281 0.5724010000 0.1123750000 0.0460110000 0.0000010000 0.4102640000 0.0026750000 115074139 0 402718720 4.1305875778 4.3133511543 4.7314515114 551 22.0000000000 0.0121964281 0.0108522558 0.0160688832 0.0148356917 0.6812530000 0.1447640000 0.0715230000 0.0398750000 0.4213310000 0.0026670000 115076915 0 402718720 4.1337885857 4.3156948090 4.7331032753 552 22.0400000000 0.0122363158 0.0108547632 0.0160688832 0.0148468036 0.5739200000 0.1203040000 0.0458620000 0.0000000000 0.4048700000 0.0019170000 115079691 0 402718720 4.1384749413 4.3181958199 4.7345085144 553 22.0800000000 0.0121977264 0.0108571917 0.0160688832 0.0148435101 1.0063650000 0.1121470000 0.0433350000 0.0328890000 0.4054580000 0.4115690000 115082467 0 402718720 4.1430659294 4.3180518150 4.7360043526 554 22.1200000000 0.0122265788 0.0108596635 0.0160688832 0.0148369796 0.5671520000 0.1121760000 0.0457650000 0.0000010000 0.4063220000 0.0019120000 115085243 0 402718720 4.1463265419 4.3172526360 4.7380843163 555 22.1600000000 0.0121643730 0.0108620143 0.0160688832 0.0148294439 0.5968880000 0.1122230000 0.0472620000 0.0325220000 0.4018640000 0.0020090000 115088019 0 402718720 4.1524639130 4.3190832138 4.7391510010 556 22.2000000000 0.0120672649 0.0108641821 0.0160688832 0.0148282719 0.5752920000 0.1122790000 0.0433180000 0.0000010000 0.4159470000 0.0026540000 115090795 0 402718720 4.1576318741 4.3219695091 4.7405047417 557 22.2400000000 0.0121235531 0.0108664431 0.0160688832 0.0148245534 1.0860330000 0.1448510000 0.0585710000 0.0404440000 0.4252100000 0.4159950000 115093571 0 402718720 4.1622238159 4.3237662315 4.7420420647 558 22.2800000000 0.0120295137 0.0108685274 0.0160688832 0.0148240812 0.5796360000 0.1250460000 0.0433410000 0.0000010000 0.4083540000 0.0019080000 115096347 0 402718720 4.1675271988 4.3265728951 4.7435770035 559 22.3200000000 0.0120439334 0.0108706301 0.0160688832 0.0148211126 0.6616810000 0.1312550000 0.0603010000 0.0405240000 0.4258480000 0.0026500000 115099123 0 402718720 4.1730275154 4.3292098045 4.7450170517 560 22.3600000000 0.0120110689 0.0108726666 0.0160688832 0.0148170223 0.6333750000 0.1449600000 0.0710130000 0.0000000000 0.4145230000 0.0019010000 115101899 0 402718720 4.1769356728 4.3300213814 4.7475762367 561 22.4000000000 0.0120383380 0.0108747444 0.0160688832 0.0148138395 1.0254810000 0.1122790000 0.0456500000 0.0326350000 0.4089560000 0.4248530000 115104675 0 402718720 4.1812219620 4.3323822021 4.7492733002 562 22.4400000000 0.0119992886 0.0108767454 0.0160688832 0.0148119164 0.6339230000 0.1449920000 0.0584230000 0.0000000000 0.4267500000 0.0026430000 115107451 0 402718720 4.1865873337 4.3356604576 4.7504525185 563 22.4800000000 0.0119948890 0.0108787315 0.0160688832 0.0148051546 0.6088540000 0.1186530000 0.0449490000 0.0332720000 0.4090950000 0.0018990000 115110227 0 402718720 4.1927838326 4.3392167091 4.7510585785 564 22.5200000000 0.0119837681 0.0108806907 0.0160688832 0.0147956582 0.5676090000 0.1124150000 0.0430390000 0.0000000000 0.4092650000 0.0018940000 115113003 0 402718720 4.1970219612 4.3409085274 4.7527556419 565 22.5600000000 0.0120114535 0.0108826921 0.0160688832 0.0147859799 1.0156480000 0.1125240000 0.0430350000 0.0334950000 0.4091020000 0.4165080000 115115779 0 402718720 4.2006406784 4.3419342041 4.7543759346 566 22.6000000000 0.0120109171 0.0108846854 0.0160688832 0.0147770523 0.5679210000 0.1126470000 0.0430490000 0.0000000000 0.4093410000 0.0018960000 115118555 0 402718720 4.2057623863 4.3451256752 4.7556929588 567 22.6400000000 0.0120205628 0.0108866887 0.0160688832 0.0147659650 0.6146460000 0.1126750000 0.0453460000 0.0333400000 0.4195330000 0.0026320000 115121331 0 402718720 4.2104473114 4.3472528458 4.7567596436 568 22.6800000000 0.0120887700 0.0108888051 0.0160688832 0.0147563727 0.6364330000 0.1453180000 0.0604870000 0.0000010000 0.4268760000 0.0026290000 115124107 0 402718720 4.2146801949 4.3491258621 4.7582464218 569 22.7200000000 0.0120955473 0.0108909259 0.0160688832 0.0147453858 1.0361050000 0.1234940000 0.0547730000 0.0328500000 0.4068450000 0.4171460000 115126883 0 402718720 4.2201981544 4.3506317139 4.7585301399 570 22.7600000000 0.0120919179 0.0108930329 0.0160688832 0.0147347513 0.6393080000 0.1503580000 0.0580420000 0.0000010000 0.4271600000 0.0026210000 115129659 0 402718720 4.2243170738 4.3534197807 4.7594456673 571 22.8000000000 0.0121632162 0.0108952574 0.0160688832 0.0147228228 0.6712080000 0.1455200000 0.0704030000 0.0410680000 0.4113340000 0.0018930000 115132435 0 402718720 4.2294154167 4.3561859131 4.7602200508 572 22.8400000000 0.0120935608 0.0108973523 0.0160688832 0.0147104832 0.5692090000 0.1130380000 0.0472440000 0.0000010000 0.4060370000 0.0018880000 115135211 0 402718720 4.2352752686 4.3590607643 4.7598357201 573 22.8800000000 0.0121385353 0.0108995184 0.0160688832 0.0146990383 1.0259700000 0.1115450000 0.0520800000 0.0336790000 0.4097910000 0.4178840000 115137987 0 402718720 4.2394270897 4.3612942696 4.7605915070 574 22.9200000000 0.0121616255 0.0109017172 0.0160688832 0.0146880049 0.5710690000 0.1131700000 0.0450810000 0.0000010000 0.4099260000 0.0018850000 115140763 0 402718720 4.2438158989 4.3644480705 4.7607893944 575 22.9600000000 0.0121446121 0.0109038788 0.0160688832 0.0146753881 0.6014980000 0.1131950000 0.0426540000 0.0330920000 0.4096740000 0.0018880000 115143539 0 402718720 4.2478122711 4.3672504425 4.7614331245 576 23.0000000000 0.0121701276 0.0109060771 0.0160688832 0.0146627146 0.5710290000 0.1132310000 0.0450380000 0.0000000000 0.4098850000 0.0018850000 115146315 0 402718720 4.2515687943 4.3706717491 4.7619647980 577 23.0400000000 0.0122259688 0.0109083646 0.0160688832 0.0146500036 1.0277790000 0.1132620000 0.0519350000 0.0336570000 0.4096180000 0.4183150000 115149091 0 402718720 4.2553853989 4.3742799759 4.7623772621 578 23.0800000000 0.0122540621 0.0109106928 0.0160688832 0.0146374808 0.5866050000 0.1313190000 0.0425360000 0.0000010000 0.4098580000 0.0018830000 115151867 0 402718720 4.2583155632 4.3760919571 4.7627663612 579 23.1200000000 0.0121931471 0.0109129078 0.0160688832 0.0146253480 0.6150690000 0.1269350000 0.0426160000 0.0327950000 0.4098220000 0.0018840000 115154643 0 402718720 4.2621893883 4.3796243668 4.7623791695 580 23.1600000000 0.0122936005 0.0109152883 0.0160688832 0.0146133017 0.5699200000 0.1133420000 0.0470750000 0.0000010000 0.4066050000 0.0018800000 115157419 0 402718720 4.2665729523 4.3854990005 4.7623066902 581 23.2000000000 0.0122742746 0.0109176273 0.0160688832 0.0146007930 1.0673540000 0.1133700000 0.0689590000 0.0335600000 0.4132480000 0.4370730000 115160195 0 402718720 4.2702140808 4.3900842667 4.7621026039 582 23.2400000000 0.0123173753 0.0109200324 0.0160688832 0.0145883002 0.6345080000 0.1461170000 0.0699200000 0.0000010000 0.4155650000 0.0018800000 115162971 0 402718720 4.2727313042 4.3935732841 4.7621335983 583 23.2800000000 0.0123519907 0.0109224886 0.0160688832 0.0145758901 0.6098750000 0.1133930000 0.0512490000 0.0335060000 0.4088220000 0.0018870000 115165747 0 402718720 4.2758321762 4.3986406326 4.7622480392 584 23.3200000000 0.0123174516 0.0109248772 0.0160688832 0.0145645514 0.5699360000 0.1134260000 0.0446810000 0.0000010000 0.4089370000 0.0018750000 115168523 0 402718720 4.2783360481 4.4015069008 4.7615628242 585 23.3600000000 0.0123495981 0.0109273126 0.0160688832 0.0145527218 1.0149170000 0.1134740000 0.0443710000 0.0336790000 0.4043010000 0.4180840000 115171299 0 402718720 4.2809505463 4.4036273956 4.7611541748 586 23.4000000000 0.0123629412 0.0109297625 0.0160688832 0.0145407486 0.5977240000 0.1414310000 0.0446730000 0.0000000000 0.4087200000 0.0018720000 115174075 0 402718720 4.2832198143 4.4065680504 4.7611846924 587 23.4400000000 0.0123638911 0.0109322057 0.0160688832 0.0145283785 0.6732660000 0.1451910000 0.0573120000 0.0409650000 0.4260480000 0.0025960000 115176851 0 402718720 4.2855024338 4.4098219872 4.7609310150 588 23.4800000000 0.0123579549 0.0109346304 0.0160688832 0.0145161061 0.6179780000 0.1463920000 0.0604860000 0.0000010000 0.4082020000 0.0018780000 115179627 0 402718720 4.2876954079 4.4125852585 4.7609205246 589 23.5200000000 0.0123394998 0.0109370156 0.0160688832 0.0145038530 1.0587140000 0.1276510000 0.0564770000 0.0328850000 0.4057410000 0.4348160000 115182403 0 402718720 4.2905359268 4.4153614044 4.7607712746 590 23.5600000000 0.0123759182 0.0109394544 0.0160688832 0.0144915679 0.6420770000 0.1465070000 0.0726700000 0.0000010000 0.4199990000 0.0018740000 115185179 0 402718720 4.2922449112 4.4171681404 4.7612018585 591 23.6000000000 0.0123579148 0.0109418545 0.0160688832 0.0144793799 0.6130070000 0.1135170000 0.0564620000 0.0330460000 0.4070730000 0.0018780000 115187955 0 402718720 4.2942361832 4.4199032784 4.7616815567 592 23.6400000000 0.0123154726 0.0109441748 0.0160688832 0.0144679508 0.5881720000 0.1135270000 0.0538820000 0.0000010000 0.4170010000 0.0025930000 115190731 0 402718720 4.2971205711 4.4225955009 4.7611198425 593 23.6800000000 0.0122426078 0.0109463644 0.0160688832 0.0144593427 1.0242070000 0.1157950000 0.0511460000 0.0327970000 0.4068190000 0.4166190000 115193507 0 402718720 4.3009810448 4.4259066582 4.7615704536 594 23.7200000000 0.0121738622 0.0109484309 0.0160688832 0.0144471639 0.6064270000 0.1454610000 0.0514310000 0.0000010000 0.4066190000 0.0018770000 115196283 0 402718720 4.3020920753 4.4264397621 4.7623405457 595 23.7600000000 0.0121479016 0.0109504468 0.0160688832 0.0144352465 0.6026110000 0.1134920000 0.0468380000 0.0333750000 0.4059550000 0.0018820000 115199059 0 402718720 4.3036031723 4.4283680916 4.7626104355 596 23.8000000000 0.0121027967 0.0109523803 0.0160688832 0.0144231869 0.5668250000 0.1134710000 0.0466140000 0.0000010000 0.4038210000 0.0018760000 115201835 0 402718720 4.3048272133 4.4306893349 4.7634391785 597 23.8400000000 0.0121941436 0.0109544603 0.0160688832 0.0144113693 1.0199000000 0.1134830000 0.0465650000 0.0335930000 0.4051100000 0.4199780000 115204611 0 402718720 4.3060379028 4.4328770638 4.7639474869 598 23.8800000000 0.0121623501 0.0109564802 0.0160688832 0.0144002465 0.6455670000 0.1466970000 0.0723200000 0.0000010000 0.4227660000 0.0025920000 115207387 0 402718720 4.3066534996 4.4338922501 4.7648258209 599 23.9200000000 0.0120577971 0.0109583188 0.0160688832 0.0143902455 0.6284860000 0.1443870000 0.0444980000 0.0327220000 0.4039480000 0.0018840000 115210163 0 402718720 4.3075842857 4.4356660843 4.7656788826 600 23.9600000000 0.0120560015 0.0109601482 0.0160688832 0.0143806009 0.5891610000 0.1261790000 0.0562290000 0.0000010000 0.4029710000 0.0025930000 115212939 0 402718720 4.3076815605 4.4374036789 4.7665739059 601 24.0000000000 0.0119414898 0.0109617811 0.0160688832 0.0143718774 1.0912130000 0.1467260000 0.0597550000 0.0407830000 0.4200700000 0.4228300000 115215715 0 402718720 4.3086180687 4.4409122467 4.7682061195 602 24.0400000000 0.0118996138 0.0109633390 0.0160688832 0.0143613477 0.5643440000 0.1134270000 0.0465610000 0.0000000000 0.4014260000 0.0018800000 115218491 0 402718720 4.3092422485 4.4412684441 4.7688245773 603 24.0800000000 0.0118319094 0.0109647794 0.0160688832 0.0143510704 0.6171550000 0.1134630000 0.0536050000 0.0333010000 0.4129940000 0.0025990000 115221267 0 402718720 4.3098516464 4.4423823357 4.7696270943 604 24.1200000000 0.0118790939 0.0109662931 0.0160688832 0.0143393843 0.6391820000 0.1467350000 0.0723250000 0.0000010000 0.4171900000 0.0018760000 115224043 0 402718720 4.3106818199 4.4437165260 4.7703762054 605 24.1600000000 0.0118535580 0.0109677597 0.0160688832 0.0143276477 1.0011310000 0.1122720000 0.0442790000 0.0334510000 0.3996100000 0.4104770000 115226819 0 402718720 4.3119554520 4.4481120110 4.7715811729 606 24.2000000000 0.0118083088 0.0109691467 0.0160688832 0.0143158039 0.5696910000 0.1134610000 0.0537120000 0.0000010000 0.3995750000 0.0018790000 115229595 0 402718720 4.3125796318 4.4497027397 4.7725229263 607 24.2400000000 0.0117575284 0.0109704456 0.0160688832 0.0143042804 0.6029870000 0.1134380000 0.0537910000 0.0339380000 0.3988870000 0.0018800000 115232371 0 402718720 4.3136725426 4.4513268471 4.7727394104 608 24.2800000000 0.0118332524 0.0109718646 0.0160688832 0.0142926649 0.5596500000 0.1134130000 0.0444520000 0.0000010000 0.3988420000 0.0018770000 115235147 0 402718720 4.3141894341 4.4524106979 4.7736325264 609 24.3200000000 0.0117848516 0.0109731996 0.0160688832 0.0142811477 1.0559730000 0.1256910000 0.0559200000 0.0326960000 0.4121300000 0.4283430000 115237923 0 402718720 4.3147287369 4.4536647797 4.7741074562 610 24.3600000000 0.0117503107 0.0109744735 0.0160688832 0.0142694956 0.6029040000 0.1445600000 0.0559520000 0.0000000000 0.3995200000 0.0018190000 115240699 0 402718720 4.3152656555 4.4563922882 4.7744970322 611 24.4000000000 0.0117330439 0.0109757151 0.0160688832 0.0142578141 0.6081140000 0.1134570000 0.0562570000 0.0330140000 0.4015920000 0.0025950000 115243475 0 402718720 4.3162350655 4.4587936401 4.7746896744 612 24.4400000000 0.0117389774 0.0109769622 0.0160688832 0.0142461619 0.6298600000 0.1467480000 0.0632120000 0.0000010000 0.4161100000 0.0025870000 115246251 0 402718720 4.3158349991 4.4605956078 4.7758221626 613 24.4800000000 0.0117651634 0.0109782480 0.0160688832 0.0142347442 1.0543830000 0.1467590000 0.0601990000 0.0407070000 0.3985390000 0.4071130000 115249027 0 402718720 4.3166728020 4.4631543159 4.7761468887 614 24.5200000000 0.0117723877 0.0109795414 0.0160688832 0.0142237490 0.5789300000 0.1134710000 0.0538210000 0.0000010000 0.4078240000 0.0025890000 115251803 0 402718720 4.3163375854 4.4649472237 4.7771139145 615 24.5600000000 0.0117154783 0.0109807381 0.0160688832 0.0142130485 0.6668420000 0.1467060000 0.0632250000 0.0414690000 0.4124930000 0.0018820000 115254579 0 402718720 4.3154697418 4.4676189423 4.7782664299 616 24.6000000000 0.0117642721 0.0109820100 0.0160688832 0.0142021439 0.5651700000 0.1134300000 0.0537030000 0.0000010000 0.3950810000 0.0018780000 115257355 0 402718720 4.3146772385 4.4695754051 4.7795972824 617 24.6400000000 0.0117237456 0.0109832122 0.0160688832 0.0141908354 1.0021590000 0.1133830000 0.0560190000 0.0332510000 0.3939930000 0.4044420000 115260131 0 402718720 4.3137836456 4.4715180397 4.7807965279 618 24.6800000000 0.0117275156 0.0109844166 0.0160688832 0.0141814781 0.5886580000 0.1378890000 0.0564830000 0.0000010000 0.3913150000 0.0018810000 115262907 0 402718720 4.3129415512 4.4734063148 4.7822079659 619 24.7200000000 0.0116818473 0.0109855433 0.0160688832 0.0141723337 0.6005570000 0.1133900000 0.0580670000 0.0333160000 0.3928180000 0.0018860000 115265683 0 402718720 4.3113241196 4.4761853218 4.7837238312 620 24.7600000000 0.0117106522 0.0109867128 0.0160688832 0.0141637957 0.5776460000 0.1133700000 0.0537430000 0.0000010000 0.4067070000 0.0026080000 115268459 0 402718720 4.3099284172 4.4777946472 4.7850046158 621 24.8000000000 0.0117063001 0.0109878716 0.0160688832 0.0141559471 1.0796380000 0.1466160000 0.0849030000 0.0403850000 0.4047810000 0.4018780000 115271235 0 402718720 4.3078813553 4.4796018600 4.7869195938 622 24.8400000000 0.0116992164 0.0109890152 0.0160688832 0.0141488461 0.5615880000 0.1133140000 0.0539140000 0.0000010000 0.3913830000 0.0018910000 115274011 0 402718720 4.3059916496 4.4815754890 4.7891321182 623 24.8800000000 0.0117539670 0.0109902431 0.0160688832 0.0141445028 0.5888720000 0.1091750000 0.0535690000 0.0321050000 0.3910950000 0.0018400000 115276787 0 402718720 4.3043932915 4.4849796295 4.7910413742 624 24.9200000000 0.0116839744 0.0109913548 0.0160688832 0.0141380886 0.5598290000 0.1133470000 0.0539570000 0.0000010000 0.3895430000 0.0018970000 115279563 0 402718720 4.3032484055 4.4859275818 4.7927737236 625 24.9600000000 0.0116594518 0.0109924238 0.0160688832 0.0141312980 0.9842590000 0.1133370000 0.0447480000 0.0330710000 0.3884980000 0.4033880000 115282339 0 402718720 4.3009586334 4.4883880615 4.7949757576 626 25.0000000000 0.0117191775 0.0109935847 0.0160688832 0.0141247013 0.6290810000 0.1465340000 0.0727260000 0.0000010000 0.4059700000 0.0026260000 115285115 0 402718720 4.2987270355 4.4919381142 4.7970485687 627 25.0400000000 0.0117295189 0.0109947585 0.0160688832 0.0141221907 0.6271560000 0.1464790000 0.0579070000 0.0328680000 0.3868970000 0.0019060000 115287891 0 402718720 4.2975602150 4.4953985214 4.7981433868 628 25.0800000000 0.0117495023 0.0109959603 0.0160688832 0.0141208656 0.5579570000 0.1132990000 0.0569370000 0.0000010000 0.3847240000 0.0019000000 115290667 0 402718720 4.2956390381 4.4978942871 4.7997918129 629 25.1200000000 0.0116755143 0.0109970407 0.0160688832 0.0141230372 0.9723990000 0.1234430000 0.0474260000 0.0328510000 0.3792360000 0.3883550000 115293443 0 402718720 4.2942047119 4.4999737740 4.8009643555 630 25.1600000000 0.0116875879 0.0109981368 0.0160688832 0.0141177535 0.5552600000 0.1132650000 0.0544910000 0.0000000000 0.3845040000 0.0019060000 115296219 0 402718720 4.2904515266 4.5015249252 4.8035168648 631 25.2000000000 0.0117694382 0.0109993591 0.0160688832 0.0141121854 0.5873410000 0.1090690000 0.0539280000 0.0328450000 0.3876150000 0.0026400000 115298995 0 402718720 4.2880902290 4.5039420128 4.8051276207 632 25.2400000000 0.0117182089 0.0110004965 0.0160688832 0.0141057600 0.6109940000 0.1464030000 0.0609280000 0.0000010000 0.3997720000 0.0026460000 115301771 0 402718720 4.2847189903 4.5040016174 4.8078513145 633 25.2800000000 0.0116691655 0.0110015529 0.0160688832 0.0140973496 1.0228510000 0.1463430000 0.0728170000 0.0326000000 0.3809350000 0.3890680000 115304547 0 402718720 4.2809128761 4.5055170059 4.8100547791 634 25.3200000000 0.0117186811 0.0110026840 0.0160688832 0.0140890482 0.5533260000 0.1132090000 0.0570220000 0.0000010000 0.3800790000 0.0019090000 115307323 0 402718720 4.2772717476 4.5083169937 4.8126611710 635 25.3600000000 0.0117315128 0.0110038318 0.0160688832 0.0140815971 0.5825370000 0.1131660000 0.0546620000 0.0328080000 0.3788930000 0.0019170000 115310099 0 402718720 4.2734460831 4.5105719566 4.8154997826 636 25.4000000000 0.0117174583 0.0110049538 0.0160688832 0.0140752038 0.5509850000 0.1131620000 0.0570650000 0.0000010000 0.3777280000 0.0019200000 115312875 0 402718720 4.2698702812 4.5117397308 4.8178143501 637 25.4400000000 0.0116315261 0.0110059374 0.0160688832 0.0140686382 0.9685170000 0.1131180000 0.0453600000 0.0327190000 0.3760080000 0.4000580000 115315651 0 402718720 4.2655925751 4.5127768517 4.8207273483 638 25.4800000000 0.0116260853 0.0110069095 0.0160688832 0.0140614612 0.5979790000 0.1461920000 0.0613000000 0.0000010000 0.3874580000 0.0019170000 115318427 0 402718720 4.2604465485 4.5138640404 4.8242177963 639 25.5200000000 0.0115969731 0.0110078329 0.0160688832 0.0140543215 0.5780880000 0.1239940000 0.0502240000 0.0324740000 0.3682140000 0.0020150000 115321203 0 402718720 4.2558608055 4.5141515732 4.8274745941 640 25.5600000000 0.0115953153 0.0110087508 0.0160688832 0.0140460383 0.5335240000 0.1130500000 0.0455640000 0.0000010000 0.3718740000 0.0019220000 115323979 0 402718720 4.2509508133 4.5134177208 4.8310680389 641 25.6000000000 0.0116110286 0.0110096904 0.0160688832 0.0140380567 0.9571050000 0.1130080000 0.0639980000 0.0322200000 0.3699450000 0.3768310000 115326755 0 402718720 4.2460274696 4.5135664940 4.8342995644 642 25.6400000000 0.0116989147 0.0110107640 0.0160688832 0.0140341222 0.5372030000 0.1129850000 0.0527810000 0.0000010000 0.3683790000 0.0019240000 115329531 0 402718720 4.2418570518 4.5161280632 4.8372173309 643 25.6800000000 0.0116603170 0.0110117742 0.0160688832 0.0140316126 0.5705070000 0.1129860000 0.0457170000 0.0321590000 0.3757060000 0.0026810000 115332307 0 402718720 4.2371149063 4.5172314644 4.8403191566 644 25.7200000000 0.0116401957 0.0110127500 0.0160688832 0.0140281412 0.6057810000 0.1459810000 0.0743640000 0.0000010000 0.3814860000 0.0026820000 115335083 0 402718720 4.2327213287 4.5171451569 4.8431692123 645 25.7600000000 0.0116568254 0.0110137485 0.0160688832 0.0140222822 0.9463170000 0.1344630000 0.0481460000 0.0313210000 0.3623460000 0.3689230000 115337859 0 402718720 4.2285714149 4.5190196037 4.8456935883 646 25.8000000000 0.0116367247 0.0110147129 0.0160688832 0.0140166577 0.5312470000 0.1128720000 0.0552440000 0.0000000000 0.3600750000 0.0019240000 115340635 0 402718720 4.2242612839 4.5205779076 4.8485608101 647 25.8400000000 0.0116661647 0.0110157198 0.0160688832 0.0140105920 0.5599580000 0.1128450000 0.0546970000 0.0318290000 0.3575240000 0.0019360000 115343411 0 402718720 4.2194080353 4.5208368301 4.8517107964 648 25.8800000000 0.0116208503 0.0110166536 0.0160688832 0.0140030616 0.5154670000 0.1109750000 0.0458040000 0.0000010000 0.3556120000 0.0019340000 115346187 0 402718720 4.2150058746 4.5227570534 4.8543710709 649 25.9200000000 0.0115901874 0.0110175373 0.0160688832 0.0139952701 0.9451530000 0.1243790000 0.0605710000 0.0318090000 0.3521860000 0.3749220000 115348963 0 402718720 4.2106146812 4.5245447159 4.8570885658 650 25.9600000000 0.0116634704 0.0110185311 0.0160688832 0.0139885984 0.5895140000 0.1456120000 0.0744590000 0.0000000000 0.3663830000 0.0019280000 115351739 0 402718720 4.2063417435 4.5281124115 4.8595647812 651 26.0000000000 0.0116265975 0.0110194651 0.0160688832 0.0139874763 0.5494320000 0.1122280000 0.0554540000 0.0308320000 0.3478550000 0.0019320000 115354515 0 402718720 4.2031378746 4.5300054550 4.8618149757 652 26.0400000000 0.0116064064 0.0110203653 0.0160688832 0.0139843215 0.5066720000 0.1125630000 0.0458580000 0.0000010000 0.3451890000 0.0019270000 115357291 0 402718720 4.1993412971 4.5321464539 4.8637237549 653 26.0800000000 0.0116234468 0.0110212889 0.0160688832 0.0139829970 0.9001310000 0.1366550000 0.0482490000 0.0314500000 0.3380330000 0.3446120000 115360067 0 402718720 4.1945805550 4.5337142944 4.8660387993 654 26.1200000000 0.0116223637 0.0110222080 0.0160688832 0.0139829680 0.5248680000 0.1256100000 0.0582950000 0.0000000000 0.3378860000 0.0019280000 115362843 0 402718720 4.1901340485 4.5349054337 4.8684062958 655 26.1600000000 0.0115899341 0.0110230747 0.0160688832 0.0139786952 0.5510670000 0.1124250000 0.0649660000 0.0311500000 0.3385600000 0.0026900000 115365619 0 402718720 4.1874713898 4.5383043289 4.8700947762 656 26.2000000000 0.0116451392 0.0110240230 0.0160688832 0.0139746799 0.5787490000 0.1450910000 0.0776840000 0.0000000000 0.3519930000 0.0026820000 115368395 0 402718720 4.1775546074 4.5416145325 4.8739175797 657 26.2400000000 0.0116011351 0.0110249014 0.0160688832 0.0139723369 0.9382110000 0.1450060000 0.0777060000 0.0377040000 0.3366290000 0.3400220000 115371171 0 402718720 4.1748313904 4.5419259071 4.8756241798 658 26.2800000000 0.0115143228 0.0110256452 0.0160688832 0.0139653272 0.5650240000 0.1122510000 0.1126630000 0.0000010000 0.3370280000 0.0019290000 115373947 0 402718720 4.1713199615 4.5438117981 4.8772253990 659 26.3200000000 0.0115908580 0.0110265029 0.0160688832 0.0139609958 0.5449380000 0.1244410000 0.0606690000 0.0310560000 0.3255370000 0.0020270000 115376723 0 402718720 4.1679844856 4.5476298332 4.8786072731 660 26.3600000000 0.0116442731 0.0110274389 0.0160688832 0.0139586387 0.5195250000 0.1121360000 0.0781960000 0.0000010000 0.3261100000 0.0019330000 115379499 0 402718720 4.1640086174 4.5486035347 4.8801283836 661 26.4000000000 0.0115460502 0.0110282235 0.0160688832 0.0139570345 0.8583840000 0.1082430000 0.0579980000 0.0306210000 0.3252960000 0.3349280000 115382275 0 402718720 4.1614775658 4.5523800850 4.8808898926 662 26.4400000000 0.0115655381 0.0110290351 0.0160688832 0.0139513949 0.5755870000 0.1445960000 0.0872340000 0.0000010000 0.3397520000 0.0026850000 115385051 0 402718720 4.1589336395 4.5552830696 4.8817048073 663 26.4800000000 0.0113410065 0.0110295057 0.0160688832 0.0139481262 0.5857110000 0.1445190000 0.0778400000 0.0369250000 0.3233490000 0.0019350000 115387827 0 402718720 4.1551818848 4.5548458099 4.8831949234 664 26.5200000000 0.0114122881 0.0110300822 0.0160688832 0.0139469284 0.5169500000 0.1226050000 0.0709660000 0.0000010000 0.3202810000 0.0019310000 115390603 0 402718720 4.1528000832 4.5564451218 4.8841714859 665 26.5600000000 0.0114119975 0.0110306565 0.0160688832 0.0139451847 0.8593170000 0.1118730000 0.0675900000 0.0304530000 0.3210360000 0.3272140000 115393379 0 402718720 4.1495008469 4.5586762428 4.8853120804 666 26.6000000000 0.0113354474 0.0110311141 0.0160688832 0.0139404329 0.4988580000 0.1080100000 0.0669490000 0.0000000000 0.3208080000 0.0019310000 115396155 0 402718720 4.1467790604 4.5598168373 4.8863110542 667 26.6400000000 0.0114355115 0.0110317204 0.0160688832 0.0139353826 0.5223140000 0.1117520000 0.0580270000 0.0297140000 0.3197130000 0.0019340000 115398931 0 402718720 4.1424789429 4.5617504120 4.8873076439 668 26.6800000000 0.0114774611 0.0110323877 0.0160688832 0.0139301827 0.5114690000 0.1117490000 0.0674590000 0.0000010000 0.3282370000 0.0026860000 115401707 0 402718720 4.1383409500 4.5637192726 4.8883666992 669 26.7200000000 0.0113728279 0.0110328966 0.0160688832 0.0139263482 0.9468020000 0.1440390000 0.1031220000 0.0356490000 0.3332310000 0.3295800000 115404483 0 402718720 4.1345095634 4.5654625893 4.8893380165 670 26.7600000000 0.0114718284 0.0110335517 0.0160688832 0.0139198090 0.5093000000 0.1114890000 0.0807480000 0.0000010000 0.3138010000 0.0020230000 115407259 0 402718720 4.1299939156 4.5646471977 4.8905496597 671 26.8000000000 0.0114705544 0.0110342030 0.0160688832 0.0139148785 0.5191010000 0.1114330000 0.0579460000 0.0301240000 0.3164920000 0.0019330000 115410035 0 402718720 4.1267027855 4.5639128685 4.8921160698 672 26.8400000000 0.0113680018 0.0110346997 0.0160688832 0.0139072683 0.4979550000 0.1112770000 0.0706110000 0.0000010000 0.3128160000 0.0020280000 115412811 0 402718720 4.1226472855 4.5638046265 4.8935341835 673 26.8800000000 0.0114322128 0.0110352903 0.0160688832 0.0138981290 0.8374180000 0.1112090000 0.0580980000 0.0301160000 0.3149840000 0.3218400000 115415587 0 402718720 4.1189417839 4.5638756752 4.8948574066 674 26.9200000000 0.0115431249 0.0110360438 0.0160688832 0.0138944401 0.4998770000 0.1238390000 0.0579510000 0.0000000000 0.3149770000 0.0019280000 115418363 0 402718720 4.1147308350 4.5633492470 4.8964009285 675 26.9600000000 0.0114635145 0.0110366771 0.0160688832 0.0138905785 0.5160680000 0.1108740000 0.0579200000 0.0299530000 0.3142010000 0.0019330000 115421139 0 402718720 4.1106762886 4.5632596016 4.8974747658 676 27.0000000000 0.0113398032 0.0110371255 0.0160688832 0.0138829146 0.5429320000 0.1107550000 0.1152100000 0.0000000000 0.3138340000 0.0019270000 115423915 0 402718720 4.1064319611 4.5634369850 4.8983144760 677 27.0400000000 0.0114458324 0.0110377292 0.0160688832 0.0138760606 0.8313180000 0.1105960000 0.0577970000 0.0298810000 0.3128340000 0.3190320000 115426691 0 402718720 4.1015143394 4.5636072159 4.8990797997 678 27.0800000000 0.0114261126 0.0110383021 0.0160688832 0.0138686375 0.5023620000 0.1104520000 0.0768240000 0.0000000000 0.3119810000 0.0019270000 115429467 0 402718720 4.0969219208 4.5632700920 4.9000806808 679 27.1200000000 0.0121733034 0.0110399736 0.0160688832 0.0138607076 0.5211680000 0.1189590000 0.0576870000 0.0299100000 0.3114870000 0.0019330000 115432243 0 402718720 4.0896601677 4.5620694160 4.9011936188 680 27.1600000000 0.0129712820 0.0110428138 0.0160688832 0.0138561857 0.5041980000 0.1100960000 0.0804950000 0.0000000000 0.3104960000 0.0019300000 115435019 0 402718720 4.0834636688 4.5615348816 4.9026846886 681 27.2000000000 0.0130321691 0.0110457350 0.0160688832 0.0138513950 0.8354940000 0.1099350000 0.0672020000 0.0291580000 0.3108960000 0.3171010000 115437795 0 402718720 4.0807375908 4.5612201691 4.9033908844 682 27.2400000000 0.0131451897 0.0110488134 0.0160688832 0.0138464714 0.5113050000 0.1097860000 0.0903850000 0.0000010000 0.3078630000 0.0020280000 115440571 0 402718720 4.0769448280 4.5606527328 4.9041457176 683 27.2800000000 0.0132016381 0.0110519654 0.0160688832 0.0138412726 0.5203100000 0.1097050000 0.0674390000 0.0296660000 0.3103610000 0.0019390000 115443347 0 402718720 4.0742354393 4.5595340729 4.9050784111 684 27.3200000000 0.0132509330 0.0110551803 0.0160688832 0.0138320870 0.5189230000 0.1094820000 0.0957230000 0.0000000000 0.3105760000 0.0019360000 115446123 0 402718720 4.0684065819 4.5600900650 4.9061613083 685 27.3600000000 0.0119976643 0.0110565562 0.0160688832 0.0138248563 0.8341570000 0.1097020000 0.0673050000 0.0296840000 0.3100250000 0.3162360000 115448899 0 402718720 4.0679731369 4.5610566139 4.9070491791 686 27.4000000000 0.0117024351 0.0110574977 0.0160688832 0.0138196845 0.4902030000 0.1097260000 0.0673260000 0.0000010000 0.3100040000 0.0019390000 115451675 0 402718720 4.0645833015 4.5601830482 4.9081916809 687 27.4400000000 0.0115505718 0.0110582154 0.0160688832 0.0138159107 0.5192700000 0.1097620000 0.0674370000 0.0295320000 0.3093880000 0.0019490000 115454451 0 402718720 4.0611324310 4.5608420372 4.9095501900 688 27.4800000000 0.0115030110 0.0110588619 0.0160688832 0.0138129567 0.4853910000 0.1063850000 0.0667790000 0.0000000000 0.3090950000 0.0019420000 115457227 0 402718720 4.0592927933 4.5613470078 4.9106373787 689 27.5200000000 0.0114184292 0.0110593838 0.0160688832 0.0138088661 0.8435230000 0.1233430000 0.0681330000 0.0296200000 0.3065250000 0.3146960000 115460003 0 402718720 4.0555500984 4.5620756149 4.9114165306 690 27.5600000000 0.0114949681 0.0110600151 0.0160688832 0.0138026748 0.4902760000 0.1095860000 0.0705570000 0.0000010000 0.3068270000 0.0020410000 115462779 0 402718720 4.0520534515 4.5630664825 4.9124984741 691 27.6000000000 0.0114054149 0.0110605149 0.0160688832 0.0137970532 0.5258930000 0.1079140000 0.0768910000 0.0295870000 0.3083370000 0.0019500000 115465555 0 402718720 4.0490350723 4.5632071495 4.9134988785 692 27.6400000000 0.0113328053 0.0110609084 0.0160688832 0.0137912398 0.4792960000 0.1097910000 0.0606060000 0.0000010000 0.3055880000 0.0020440000 115468331 0 402718720 4.0457453728 4.5641984940 4.9147253036 693 27.6800000000 0.0113267964 0.0110612921 0.0160688832 0.0137854810 0.8211390000 0.1095200000 0.0595090000 0.0295520000 0.3076010000 0.3137610000 115471107 0 402718720 4.0413360596 4.5635476112 4.9157452583 694 27.7200000000 0.0113068791 0.0110616459 0.0160688832 0.0137781036 0.4777810000 0.1095410000 0.0579030000 0.0000000000 0.3071720000 0.0019490000 115473883 0 402718720 4.0389380455 4.5638151169 4.9169912338 695 27.7600000000 0.0113589838 0.0110620738 0.0160688832 0.0137724875 0.5605110000 0.1254080000 0.0744710000 0.0345110000 0.3220570000 0.0027000000 115476659 0 402718720 4.0361189842 4.5640826225 4.9180598259 696 27.8000000000 0.0114026824 0.0110625631 0.0160688832 0.0137671462 0.5378230000 0.1405470000 0.0777130000 0.0000010000 0.3163830000 0.0019460000 115479435 0 402718720 4.0322585106 4.5626358986 4.9193477631 697 27.8400000000 0.0114784818 0.0110631599 0.0160688832 0.0137638095 0.8274350000 0.1225100000 0.0554670000 0.0295080000 0.3062870000 0.3124500000 115482211 0 402718720 4.0285873413 4.5633282661 4.9203457832 698 27.8800000000 0.0114478189 0.0110637110 0.0160688832 0.0137598898 0.4763630000 0.1094240000 0.0578570000 0.0000010000 0.3058930000 0.0019510000 115484987 0 402718720 4.0259423256 4.5633893013 4.9214205742 699 27.9200000000 0.0114298640 0.0110642348 0.0160688832 0.0137548745 0.5645430000 0.1184460000 0.1105210000 0.0295130000 0.3027520000 0.0020370000 115487763 0 402718720 4.0221533775 4.5641326904 4.9224629402 700 27.9600000000 0.0115891183 0.0110649846 0.0160688832 0.0137527418 0.4734110000 0.1094590000 0.0555040000 0.0000010000 0.3052560000 0.0019540000 115490539 0 402718720 4.0180625916 4.5643115044 4.9235796928 701 28.0000000000 0.0116515821 0.0110658214 0.0160688832 0.0137494523 0.8244540000 0.1094120000 0.0578020000 0.0294030000 0.3043370000 0.3221180000 115493315 0 402718720 4.0149450302 4.5651564598 4.9245195389 702 28.0400000000 0.0115977973 0.0110665792 0.0160688832 0.0137454956 0.5296790000 0.1400350000 0.0649750000 0.0000010000 0.3205570000 0.0027110000 115496091 0 402718720 4.0103497505 4.5672230721 4.9250745773 703 28.0800000000 0.0116186067 0.0110673645 0.0160688832 0.0137410790 0.5388820000 0.1397870000 0.0631300000 0.0287550000 0.3040030000 0.0019590000 115498867 0 402718720 4.0076584816 4.5677328110 4.9263067245 704 28.1200000000 0.0117532546 0.0110683387 0.0160688832 0.0137362653 0.4741070000 0.1088670000 0.0581140000 0.0000000000 0.3039360000 0.0019650000 115501643 0 402718720 4.0046157837 4.5677485466 4.9273962975 705 28.1600000000 0.0117813814 0.0110693501 0.0160688832 0.0137315615 0.8107220000 0.1092270000 0.0578740000 0.0293980000 0.3034010000 0.3095920000 115504419 0 402718720 4.0016956329 4.5675725937 4.9288635254 706 28.2000000000 0.0119175194 0.0110705515 0.0160688832 0.0137264262 0.4813690000 0.1093380000 0.0650470000 0.0000000000 0.3037740000 0.0019680000 115507195 0 402718720 3.9999797344 4.5667905807 4.9300265312 707 28.2400000000 0.0118840737 0.0110717022 0.0160688832 0.0137217338 0.5026480000 0.1094420000 0.0578910000 0.0293800000 0.3027140000 0.0019720000 115509971 0 402718720 3.9957699776 4.5663385391 4.9311804771 708 28.2800000000 0.0119058415 0.0110728804 0.0160688832 0.0137160016 0.4733860000 0.1094920000 0.0579470000 0.0000010000 0.3027380000 0.0019610000 115512747 0 402718720 3.9934365749 4.5658664703 4.9323492050 709 28.3200000000 0.0118664093 0.0110739996 0.0160688832 0.0137089259 0.8143980000 0.1189380000 0.0582100000 0.0293990000 0.3001140000 0.3064350000 115515523 0 402718720 3.9900705814 4.5671868324 4.9333691597 710 28.3600000000 0.0119022243 0.0110751661 0.0160688832 0.0137026457 0.4724170000 0.1087920000 0.0578850000 0.0000010000 0.3025140000 0.0019710000 115518299 0 402718720 3.9860098362 4.5673418045 4.9343461990 711 28.4000000000 0.0118551766 0.0110762631 0.0160688832 0.0136976832 0.5083720000 0.1094240000 0.0580560000 0.0294270000 0.3073170000 0.0027290000 115521075 0 402718720 3.9822816849 4.5670099258 4.9356074333 712 28.4400000000 0.0118976980 0.0110774169 0.0160688832 0.0136913314 0.4771720000 0.1148400000 0.0578320000 0.0000000000 0.3012870000 0.0019700000 115523851 0 402718720 3.9772586823 4.5670695305 4.9365139008 713 28.4800000000 0.0118707204 0.0110785295 0.0160688832 0.0136848019 0.8026030000 0.1095640000 0.0581640000 0.0294450000 0.2980760000 0.3061210000 115526627 0 402718720 3.9731523991 4.5678458214 4.9374928474 714 28.5200000000 0.0119396029 0.0110797355 0.0160688832 0.0136786039 0.4838830000 0.1223950000 0.0580040000 0.0000010000 0.3002580000 0.0019720000 115529403 0 402718720 3.9693219662 4.5671796799 4.9389204979 715 28.5600000000 0.0119053638 0.0110808902 0.0160688832 0.0136709002 0.4983510000 0.1096780000 0.0581210000 0.0288360000 0.2984710000 0.0019800000 115532179 0 402718720 3.9647204876 4.5675048828 4.9401984215 716 28.6000000000 0.0119475285 0.0110821006 0.0160688832 0.0136655309 0.4669680000 0.1096310000 0.0554880000 0.0000010000 0.2986180000 0.0019780000 115534955 0 402718720 3.9602413177 4.5664358139 4.9413518906 717 28.6400000000 0.0120354788 0.0110834303 0.0160688832 0.0136587764 0.8090470000 0.1223450000 0.0554430000 0.0287300000 0.2975510000 0.3037200000 115537731 0 402718720 3.9559166431 4.5668449402 4.9421706200 718 28.6800000000 0.0121149840 0.0110848670 0.0160688832 0.0136524390 0.4648320000 0.1065600000 0.0577810000 0.0000010000 0.2972440000 0.0019790000 115540507 0 402718720 3.9511370659 4.5676689148 4.9430017471 719 28.7200000000 0.0121311210 0.0110863221 0.0160688832 0.0136492813 0.5307570000 0.1229490000 0.0807180000 0.0294150000 0.2942870000 0.0020700000 115543283 0 402718720 3.9468958378 4.5662670135 4.9438786507 720 28.7600000000 0.0121087860 0.0110877422 0.0160688832 0.0136505609 0.4699950000 0.1099020000 0.0608430000 0.0000000000 0.2959860000 0.0019900000 115546059 0 402718720 3.9434754848 4.5665578842 4.9447145462 721 28.8000000000 0.0121548697 0.0110892223 0.0160688832 0.0136470137 0.7979630000 0.1066650000 0.0619910000 0.0292430000 0.2964030000 0.3024030000 115548835 0 402718720 3.9398970604 4.5655283928 4.9459576607 722 28.8400000000 0.0121932309 0.0110907514 0.0160688832 0.0136423380 0.4670660000 0.1099980000 0.0579160000 0.0000010000 0.2958950000 0.0019820000 115551611 0 402718720 3.9341804981 4.5644092560 4.9468674660 723 28.8800000000 0.0122854831 0.0110924038 0.0160688832 0.0136362485 0.5056580000 0.1228370000 0.0554890000 0.0294540000 0.2946300000 0.0019790000 115554387 0 402718720 3.9304201603 4.5647654533 4.9477429390 724 28.9200000000 0.0123240612 0.0110941050 0.0160688832 0.0136293877 0.4895290000 0.1224650000 0.0697300000 0.0000010000 0.2940770000 0.0019710000 115557163 0 402718720 3.9248614311 4.5641808510 4.9484567642 725 28.9600000000 0.0123118646 0.0110957847 0.0160688832 0.0136221466 0.7934930000 0.1101850000 0.0606940000 0.0293970000 0.2924210000 0.2995310000 115559939 0 402718720 3.9212405682 4.5633678436 4.9496974945 726 29.0000000000 0.0123551283 0.0110975193 0.0160688832 0.0136157647 0.4853760000 0.1102960000 0.0805950000 0.0000010000 0.2910820000 0.0020730000 115562715 0 402718720 3.9176425934 4.5634865761 4.9504313469 727 29.0400000000 0.0123265544 0.0110992099 0.0160688832 0.0136117049 0.4932730000 0.1105420000 0.0581730000 0.0295740000 0.2917280000 0.0019820000 115565491 0 402718720 3.9142055511 4.5634207726 4.9512515068 728 29.0800000000 0.0124134049 0.0111010151 0.0160688832 0.0136082689 0.4646610000 0.1104890000 0.0579610000 0.0000010000 0.2929710000 0.0019700000 115568267 0 402718720 3.9116964340 4.5625190735 4.9520058632 729 29.1200000000 0.0123477848 0.0111027253 0.0160688832 0.0136079238 0.7999590000 0.1221190000 0.0556140000 0.0294280000 0.2927090000 0.2988150000 115571043 0 402718720 3.9087677002 4.5623931885 4.9526491165 730 29.1600000000 0.0123902215 0.0111044890 0.0160688832 0.0136057191 0.4623310000 0.1106750000 0.0556170000 0.0000010000 0.2927880000 0.0019700000 115573819 0 402718720 3.9064745903 4.5613479614 4.9535775185 731 29.2000000000 0.0123851262 0.0111062409 0.0160688832 0.0136033611 0.5132800000 0.1297600000 0.0577890000 0.0292990000 0.2932220000 0.0019200000 115576595 0 402718720 3.9015314579 4.5602307320 4.9538435936 732 29.2400000000 0.0123465257 0.0111079353 0.0160688832 0.0135999777 0.4603930000 0.1075930000 0.0574420000 0.0000010000 0.2920910000 0.0019730000 115579371 0 402718720 3.8983032703 4.5604028702 4.9542250633 733 29.2800000000 0.0123366555 0.0111096116 0.0160688832 0.0135955342 0.7905870000 0.1111470000 0.0579560000 0.0288530000 0.2925500000 0.2987840000 115582147 0 402718720 3.8958115578 4.5587906837 4.9549193382 734 29.3200000000 0.0123348162 0.0111112808 0.0160688832 0.0135889172 0.4766920000 0.1111780000 0.0705680000 0.0000010000 0.2916830000 0.0019770000 115584923 0 402718720 3.8931820393 4.5582318306 4.9552946091 735 29.3600000000 0.0123458141 0.0111129604 0.0160688832 0.0135817048 0.5008880000 0.1112900000 0.0648980000 0.0288570000 0.2925610000 0.0019870000 115587699 0 402718720 3.8896238804 4.5580296516 4.9554333687 736 29.4000000000 0.0124245044 0.0111147424 0.0160688832 0.0135763100 0.4625770000 0.1112920000 0.0554640000 0.0000010000 0.2925420000 0.0019810000 115590475 0 402718720 3.8866908550 4.5566172600 4.9555764198 737 29.4400000000 0.0122985197 0.0111163486 0.0160688832 0.0135710546 0.7909590000 0.1113190000 0.0578240000 0.0288740000 0.2926760000 0.2989690000 115593251 0 402718720 3.8839364052 4.5546956062 4.9557132721 738 29.4800000000 0.0124589261 0.0111181679 0.0160688832 0.0135640762 0.4690610000 0.1078220000 0.0645960000 0.0000010000 0.2934330000 0.0019090000 115596027 0 402718720 3.8826708794 4.5533056259 4.9563364983 739 29.5200000000 0.0124581112 0.0111199810 0.0160688832 0.0135582493 0.5121600000 0.1222030000 0.0650950000 0.0288340000 0.2927610000 0.0019800000 115598803 0 402718720 3.8813183308 4.5512595177 4.9567518234 740 29.5600000000 0.0124215614 0.0111217399 0.0160688832 0.0135554888 0.4759250000 0.1114680000 0.0675610000 0.0000010000 0.2936220000 0.0019790000 115601579 0 402718720 3.8799865246 4.5495581627 4.9568815231 741 29.6000000000 0.0124122584 0.0111234815 0.0160688832 0.0135536400 0.8058310000 0.1078230000 0.0739800000 0.0287820000 0.2941020000 0.2998520000 115604355 0 402718720 3.8778066635 4.5482420921 4.9573225975 742 29.6400000000 0.0124651510 0.0111252897 0.0160688832 0.0135498215 0.4547500000 0.1115060000 0.0460290000 0.0000000000 0.2939400000 0.0019830000 115607131 0 402718720 3.8762485981 4.5470223427 4.9577860832 743 29.6800000000 0.0123820826 0.0111269812 0.0160688832 0.0135472895 0.4932480000 0.1115250000 0.0556790000 0.0289370000 0.2938110000 0.0019840000 115609907 0 402718720 3.8748917580 4.5454483032 4.9578795433 744 29.7200000000 0.0123861330 0.0111286736 0.0160688832 0.0135482630 0.4646540000 0.1114590000 0.0556070000 0.0000010000 0.2943130000 0.0019720000 115612683 0 402718720 3.8717644215 4.5416784286 4.9586215019 745 29.7600000000 0.0123531083 0.0111303172 0.0160688832 0.0135412122 0.8041910000 0.1114630000 0.0673970000 0.0289970000 0.2944600000 0.3005690000 115615459 0 402718720 3.8713173866 4.5393476486 4.9591712952 746 29.8000000000 0.0124675892 0.0111321097 0.0160688832 0.0135336709 0.5222410000 0.1114740000 0.1125720000 0.0000000000 0.2949130000 0.0019790000 115618235 0 402718720 3.8697092533 4.5388374329 4.9595136642 747 29.8400000000 0.0124848001 0.0111339206 0.0160688832 0.0135259641 0.5040410000 0.1113850000 0.0649390000 0.0297300000 0.2946850000 0.0019890000 115621011 0 402718720 3.8685202599 4.5371990204 4.9600605965 748 29.8800000000 0.0124569163 0.0111356893 0.0160688832 0.0135169694 0.4646290000 0.1113820000 0.0547650000 0.0000000000 0.2951880000 0.0019800000 115623787 0 402718720 3.8677661419 4.5357236862 4.9604120255 749 29.9200000000 0.0125497980 0.0111375773 0.0160688832 0.0135081058 0.7951510000 0.1114340000 0.0554330000 0.0295150000 0.2959260000 0.3015280000 115626563 0 402718720 3.8660702705 4.5345506668 4.9607934952 750 29.9600000000 0.0125608761 0.0111394750 0.0160688832 0.0134991625 0.4747330000 0.1114080000 0.0643670000 0.0000000000 0.2956600000 0.0019740000 115629339 0 402718720 3.8648421764 4.5341005325 4.9611196518 751 30.0000000000 0.0125692915 0.0111413789 0.0160688832 0.0134904383 0.4983770000 0.1114320000 0.0606970000 0.0296610000 0.2931310000 0.0020720000 115632115 0 402718720 3.8650009632 4.5307211876 4.9618697166 752 30.0400000000 0.0125757148 0.0111432863 0.0160688832 0.0134818170 0.4800800000 0.1242600000 0.0580460000 0.0000010000 0.2944740000 0.0019760000 115634891 0 402718720 3.8646674156 4.5290012360 4.9626722336 753 30.0800000000 0.0126311034 0.0111452621 0.0160688832 0.0134752595 0.7976590000 0.1113780000 0.0578730000 0.0290450000 0.2959990000 0.3020430000 115637667 0 402718720 3.8635473251 4.5279321671 4.9634556770 754 30.1200000000 0.0126422411 0.0111472475 0.0160688832 0.0134688757 0.4794750000 0.1241710000 0.0555180000 0.0000000000 0.2964860000 0.0019750000 115640443 0 402718720 3.8643658161 4.5261449814 4.9644198418 755 30.1600000000 0.0126500344 0.0111492379 0.0160688832 0.0134625717 0.4982080000 0.1113480000 0.0578860000 0.0292690000 0.2963890000 0.0019790000 115643219 0 402718720 3.8644580841 4.5247864723 4.9655852318 756 30.2000000000 0.0126420287 0.0111512125 0.0160688832 0.0134544718 0.5028470000 0.1113940000 0.0912680000 0.0000000000 0.2968680000 0.0019790000 115645995 0 402718720 3.8640365601 4.5237832069 4.9664211273 757 30.2400000000 0.0126169687 0.0111531488 0.0160688832 0.0134474320 0.8065670000 0.1113950000 0.0650400000 0.0292010000 0.2967370000 0.3028700000 115648771 0 402718720 3.8643329144 4.5220327377 4.9675421715 758 30.2800000000 0.0126108089 0.0111550718 0.0160688832 0.0134424717 0.4671510000 0.1114280000 0.0556960000 0.0000000000 0.2967360000 0.0019710000 115651547 0 402718720 3.8640756607 4.5232787132 4.9686508179 759 30.3200000000 0.0126067232 0.0111569844 0.0160688832 0.0134380760 0.5127090000 0.1225350000 0.0608730000 0.0299420000 0.2960520000 0.0019830000 115654323 0 402718720 3.8646633625 4.5221552849 4.9698486328 760 30.3600000000 0.0126945069 0.0111590075 0.0160688832 0.0134371457 0.4774060000 0.1115880000 0.0683530000 0.0000010000 0.2941700000 0.0019680000 115657099 0 402718720 3.8661384583 4.5199303627 4.9710726738 761 30.4000000000 0.0128457341 0.0111612239 0.0160688832 0.0134318629 0.8343040000 0.1319760000 0.0688550000 0.0350010000 0.2955570000 0.3015800000 115659875 0 402718720 3.8665575981 4.5198173523 4.9726371765 762 30.4400000000 0.0127946027 0.0111633675 0.0160688832 0.0134232414 0.5039780000 0.1116800000 0.0955770000 0.0000010000 0.2934070000 0.0019750000 115662651 0 402718720 3.8672976494 4.5191445351 4.9740591049 763 30.4800000000 0.0128864255 0.0111656257 0.0160688832 0.0134145376 0.4959650000 0.1117540000 0.0581170000 0.0298350000 0.2929440000 0.0019790000 115665427 0 402718720 3.8691341877 4.5166950226 4.9757575989 764 30.5200000000 0.0129033672 0.0111679003 0.0160688832 0.0134069297 0.4667840000 0.1118040000 0.0579190000 0.0000010000 0.2937560000 0.0019750000 115668203 0 402718720 3.8717107773 4.5148963928 4.9773344994 765 30.5600000000 0.0129249152 0.0111701970 0.0160688832 0.0133997194 0.8052350000 0.1245220000 0.0579750000 0.0292380000 0.2929730000 0.2991760000 115670979 0 402718720 3.8739836216 4.5134820938 4.9791779518 766 30.6000000000 0.0129457181 0.0111725149 0.0160688832 0.0133968913 0.4636360000 0.1118810000 0.0556440000 0.0000010000 0.2927810000 0.0019690000 115673755 0 402718720 3.8760762215 4.5118346214 4.9807648659 767 30.6400000000 0.0131296879 0.0111750667 0.0160688832 0.0134012713 0.4970820000 0.1118770000 0.0559170000 0.0298860000 0.2951420000 0.0027280000 115676531 0 402718720 3.8790504932 4.5089640617 4.9825811386 768 30.6800000000 0.0132121975 0.0111777192 0.0160688832 0.0134084279 0.4978360000 0.1437570000 0.0581730000 0.0000000000 0.2925910000 0.0019670000 115679307 0 402718720 3.8822617531 4.5081825256 4.9844245911 769 30.7200000000 0.0132415900 0.0111804030 0.0160688832 0.0134620467 0.7982700000 0.1236050000 0.0562060000 0.0293230000 0.2908510000 0.2969420000 115682083 0 402718720 3.8889882565 4.5059747696 4.9881620407 770 30.7600000000 0.0133268507 0.0111831906 0.0160688832 0.0134908239 0.4619640000 0.1120440000 0.0561000000 0.0000000000 0.2904950000 0.0019690000 115684859 0 402718720 3.8932554722 4.5013470650 4.9896907806 771 30.8000000000 0.0134216314 0.0111860939 0.0160688832 0.0135119335 0.5048330000 0.1261540000 0.0558050000 0.0296110000 0.2899290000 0.0019750000 115687635 0 402718720 3.8968405724 4.4991164207 4.9910373688 772 30.8400000000 0.0134806540 0.0111890661 0.0160688832 0.0135332316 0.4543500000 0.1121730000 0.0513120000 0.0000010000 0.2873920000 0.0020590000 115690411 0 402718720 3.8990743160 4.4980540276 4.9919848442 773 30.8800000000 0.0135294003 0.0111920937 0.0160688832 0.0135566733 0.7851610000 0.1121160000 0.0592410000 0.0296260000 0.2875270000 0.2953000000 115693187 0 402718720 3.9029703140 4.4948506355 4.9936532974 774 30.9200000000 0.0135284290 0.0111951123 0.0160688832 0.0135768466 0.4632130000 0.1121450000 0.0586200000 0.0000010000 0.2891260000 0.0019590000 115695963 0 402718720 3.9066796303 4.4910111427 4.9948444366 775 30.9600000000 0.0135861253 0.0111981974 0.0160688832 0.0135957030 0.4897980000 0.1121930000 0.0560980000 0.0295080000 0.2886630000 0.0019660000 115698739 0 402718720 3.9098474979 4.4890761375 4.9958581924 776 31.0000000000 0.0136966426 0.0112014171 0.0160688832 0.0136177580 0.4604620000 0.1121720000 0.0591150000 0.0000010000 0.2857070000 0.0020530000 115701515 0 402718720 3.9139752388 4.4863986969 4.9975342751 777 31.0400000000 0.0135959126 0.0112044988 0.0160688832 0.0136286741 0.7827430000 0.1122030000 0.0585450000 0.0295860000 0.2874540000 0.2935950000 115704291 0 402718720 3.9174318314 4.4842500687 4.9991106987 778 31.0800000000 0.0138342958 0.0112078790 0.0160688832 0.0136342751 0.4610080000 0.1122030000 0.0584550000 0.0000010000 0.2870290000 0.0019640000 115707067 0 402718720 3.9203474522 4.4808812141 5.0006861687 779 31.1200000000 0.0135982791 0.0112109475 0.0160688832 0.0136333282 0.5113950000 0.1234950000 0.0680710000 0.0303740000 0.2861050000 0.0019670000 115709843 0 402718720 3.9237020016 4.4772601128 5.0027666092 780 31.1600000000 0.0137934322 0.0112142584 0.0160688832 0.0136299222 0.4533610000 0.1081580000 0.0578750000 0.0000010000 0.2838930000 0.0020540000 115712619 0 402718720 3.9265305996 4.4745564461 5.0046887398 781 31.2000000000 0.0138575053 0.0112176429 0.0160688832 0.0136252622 0.7763310000 0.1121680000 0.0583260000 0.0296740000 0.2843530000 0.2904350000 115715395 0 402718720 3.9285979271 4.4709115028 5.0063695908 782 31.2400000000 0.0137842596 0.0112209250 0.0160688832 0.0136220311 0.4551600000 0.1122120000 0.0558360000 0.0000010000 0.2837590000 0.0019580000 115718171 0 402718720 3.9317100048 4.4667739868 5.0086865425 783 31.2800000000 0.0137759056 0.0112241880 0.0160688832 0.0136170385 0.4847260000 0.1122410000 0.0585400000 0.0303470000 0.2801140000 0.0020520000 115720947 0 402718720 3.9342613220 4.4627041817 5.0107336044 784 31.3200000000 0.0136343120 0.0112272622 0.0160688832 0.0136123796 0.4552570000 0.1122720000 0.0586610000 0.0000010000 0.2809880000 0.0019630000 115723723 0 402718720 3.9366381168 4.4575548172 5.0126976967 785 31.3600000000 0.0136796981 0.0112303863 0.0160688832 0.0136071585 0.7788950000 0.1122850000 0.0655160000 0.0297720000 0.2817420000 0.2881900000 115726499 0 402718720 3.9385566711 4.4531083107 5.0144648552 786 31.4000000000 0.0137704927 0.0112336180 0.0160688832 0.0136003440 0.4624100000 0.1122650000 0.0654000000 0.0000010000 0.2813870000 0.0019630000 115729275 0 402718720 3.9401593208 4.4496879578 5.0159235001 787 31.4400000000 0.0138405925 0.0112369305 0.0160688832 0.0135930117 0.4850020000 0.1123110000 0.0583130000 0.0303860000 0.2806150000 0.0019700000 115732051 0 402718720 3.9416317940 4.4434018135 5.0173850060 788 31.4800000000 0.0138107585 0.0112401968 0.0160688832 0.0135897373 0.4518720000 0.1123300000 0.0558300000 0.0000010000 0.2803620000 0.0019540000 115734827 0 402718720 3.9437596798 4.4385285378 5.0193729401 789 31.5200000000 0.0136779454 0.0112432865 0.0160688832 0.0135883995 0.7701730000 0.1123700000 0.0613860000 0.0298340000 0.2792960000 0.2859090000 115737603 0 402718720 3.9452066422 4.4337778091 5.0210084915 790 31.5600000000 0.0137133198 0.0112464131 0.0160688832 0.0135873435 0.4440930000 0.1123620000 0.0488720000 0.0000000000 0.2794960000 0.0019600000 115740379 0 402718720 3.9466154575 4.4270610809 5.0227179527 791 31.6000000000 0.0136616342 0.0112494665 0.0160688832 0.0136120746 0.4952690000 0.1123680000 0.0718740000 0.0305150000 0.2771650000 0.0019620000 115743155 0 402718720 3.9478204250 4.4182815552 5.0254955292 792 31.6400000000 0.0137938093 0.0112526790 0.0160688832 0.0136094720 0.4843600000 0.1311220000 0.0715150000 0.0000000000 0.2783680000 0.0019530000 115745931 0 402718720 3.9483501911 4.4142260551 5.0274848938 793 31.6800000000 0.0135028856 0.0112555166 0.0160688832 0.0136056518 0.7643570000 0.1124560000 0.0586260000 0.0298780000 0.2780080000 0.2840040000 115748707 0 402718720 3.9492259026 4.4072961807 5.0293850899 794 31.7200000000 0.0136428196 0.0112585233 0.0160688832 0.0136006722 0.4519050000 0.1124560000 0.0583670000 0.0000010000 0.2776800000 0.0019540000 115751483 0 402718720 3.9494402409 4.4060602188 5.0309910774 795 31.7600000000 0.0135066416 0.0112613511 0.0160688832 0.0135956303 0.4814490000 0.1126360000 0.0582110000 0.0304700000 0.2767690000 0.0019580000 115754259 0 402718720 3.9492125511 4.4044756889 5.0325708389 796 31.8000000000 0.0134464521 0.0112640962 0.0160688832 0.0135926118 0.4506430000 0.1129690000 0.0583990000 0.0000000000 0.2759200000 0.0019530000 115757035 0 402718720 3.9496278763 4.3991446495 5.0347704887 797 31.8400000000 0.0132615995 0.0112666025 0.0160688832 0.0135932606 0.7731940000 0.1130920000 0.0721360000 0.0306340000 0.2748900000 0.2810440000 115759811 0 402718720 3.9497160912 4.3931899071 5.0373320580 798 31.8800000000 0.0131575223 0.0112689721 0.0160688832 0.0136606457 0.4410460000 0.1132580000 0.0501310000 0.0000000000 0.2742930000 0.0019540000 115762587 0 402718720 3.9510281086 4.3749680519 5.0435557365 799 31.9200000000 0.0131425280 0.0112713170 0.0160688832 0.0136756004 0.4931340000 0.1244010000 0.0616900000 0.0305190000 0.2731460000 0.0019570000 115765363 0 402718720 3.9512577057 4.3666377068 5.0462269783 800 31.9600000000 0.0130056897 0.0112734849 0.0160688832 0.0136818502 0.4602390000 0.1131410000 0.0689130000 0.0000010000 0.2748200000 0.0019500000 115768139 0 402718720 3.9507248402 4.3621807098 5.0484681129 801 32.0000000000 0.0129282940 0.0112755509 0.0160688832 0.0136765433 0.7670700000 0.1131880000 0.0679310000 0.0297040000 0.2743660000 0.2804740000 115770915 0 402718720 3.9503514767 4.3581714630 5.0514483452 802 32.0400000000 0.0129517987 0.0112776409 0.0160688832 0.0136680937 0.4741990000 0.1378340000 0.0588950000 0.0000010000 0.2740950000 0.0019480000 115773691 0 402718720 3.9493007660 4.3502273560 5.0540246964 803 32.0800000000 0.0130288489 0.0112798218 0.0160688832 0.0136597725 0.4802000000 0.1131370000 0.0612850000 0.0304380000 0.2719680000 0.0019570000 115776467 0 402718720 3.9486279488 4.3409662247 5.0571341515 804 32.1199999990 0.0130943274 0.0112820786 0.0160688832 0.0136539076 0.4763700000 0.1130180000 0.0872190000 0.0000000000 0.2727710000 0.0019410000 115779243 0 402718720 3.9469940662 4.3258938789 5.0639023781 805 32.1600000000 0.0140234139 0.0112854840 0.0160688832 0.0136464976 0.7535200000 0.1128920000 0.0579720000 0.0304360000 0.2724120000 0.2783890000 115782019 0 402718720 3.9460802078 4.3227453232 5.0670080185 806 32.2000000000 0.0140186073 0.0112888750 0.0160688832 0.0136380295 0.4549280000 0.1123090000 0.0671720000 0.0000010000 0.2720800000 0.0019420000 115784795 0 402718720 3.9445323944 4.3175096512 5.0703120232 807 32.2400000000 0.0135579491 0.0112916867 0.0160688832 0.0136300393 0.4949540000 0.1129150000 0.0777220000 0.0297240000 0.2712060000 0.0019560000 115787571 0 402718720 3.9431722164 4.3086128235 5.0738263130 808 32.2800000000 0.0140805151 0.0112951382 0.0160688832 0.0136222803 0.4739730000 0.1129460000 0.0870900000 0.0000000000 0.2705550000 0.0019460000 115790347 0 402718720 3.9413592815 4.3030943871 5.0774593353 809 32.3200000000 0.0141079389 0.0112986151 0.0160688832 0.0136142629 0.7809220000 0.1241890000 0.0820630000 0.0303690000 0.2672000000 0.2756670000 115793123 0 402718720 3.9403054714 4.2893323898 5.0822105408 810 32.3600000000 0.0155421626 0.0113038541 0.0160688832 0.0136060450 0.5063870000 0.1129610000 0.1221690000 0.0000000000 0.2678790000 0.0019430000 115795899 0 402718720 3.9392781258 4.2790293694 5.0864224434 811 32.4000000000 0.0160056725 0.0113096516 0.0160688832 0.0135984729 0.4921520000 0.1128450000 0.0772980000 0.0302400000 0.2683830000 0.0019550000 115798675 0 402718720 3.9372513294 4.2760462761 5.0902118683 812 32.4399999990 0.0163731016 0.0113158874 0.0163731016 0.0135922193 0.4281310000 0.1088310000 0.0481550000 0.0000010000 0.2678010000 0.0019060000 115801451 0 402718720 3.9354162216 4.2699952126 5.0945339203 813 32.4800000000 0.0164978355 0.0113222613 0.0164978355 0.0135850439 0.7996180000 0.1129710000 0.1166460000 0.0302880000 0.2661360000 0.2721360000 115804227 0 402718720 3.9339854717 4.2605714798 5.0993547440 814 32.5200000000 0.0165090710 0.0113286333 0.0165090710 0.0135771760 0.4937560000 0.1089680000 0.1160620000 0.0000010000 0.2653290000 0.0019460000 115807003 0 402718720 3.9328999519 4.2494359016 5.1043372154 815 32.5600000000 0.0171074588 0.0113357239 0.0171074588 0.0135700244 0.4747950000 0.1186550000 0.0586470000 0.0295110000 0.2645970000 0.0019470000 115809779 0 402718720 3.9317035675 4.2402095795 5.1091871262 816 32.6000000000 0.0169451945 0.0113425982 0.0171074588 0.0135620063 0.4541020000 0.1090350000 0.0770560000 0.0000000000 0.2646800000 0.0018810000 115812555 0 402718720 3.9304788113 4.2330017090 5.1142859459 817 32.6400000000 0.0160970576 0.0113484176 0.0171074588 0.0135563096 0.7462990000 0.1131720000 0.0680240000 0.0300390000 0.2639970000 0.2696340000 115815331 0 402718720 3.9296131134 4.2192277908 5.1211547852 818 32.6800000000 0.0166162103 0.0113548575 0.0171074588 0.0135480271 0.4945900000 0.1132380000 0.1144340000 0.0000010000 0.2635500000 0.0019390000 115818107 0 402718720 3.9286530018 4.2033338547 5.1277494431 819 32.7200000000 0.0174084455 0.0113622489 0.0174084455 0.0135410474 0.4997570000 0.1239640000 0.0813100000 0.0301940000 0.2607390000 0.0020390000 115820883 0 402718720 3.9271013737 4.1938281059 5.1327099800 820 32.7599999990 0.0167593975 0.0113688308 0.0174084455 0.0135328521 0.4943140000 0.1090520000 0.1201940000 0.0000000000 0.2616780000 0.0019370000 115823659 0 402718720 3.9254062176 4.1870145798 5.1369247437 821 32.7999999990 0.0167202819 0.0113753490 0.0174084455 0.0135247955 0.7666650000 0.1130900000 0.0918890000 0.0300390000 0.2621060000 0.2680960000 115826435 0 402718720 3.9245438576 4.1783828735 5.1416897774 822 32.8400000000 0.0167392902 0.0113818745 0.0174084455 0.0135177130 0.4624050000 0.1289340000 0.0683950000 0.0000000000 0.2616810000 0.0019370000 115829211 0 402718720 3.9245746136 4.1667079926 5.1471338272 823 32.8800000000 0.0166785605 0.0113883103 0.0174084455 0.0135113679 0.4717190000 0.1090350000 0.0678010000 0.0298840000 0.2616700000 0.0018810000 115831987 0 402718720 3.9246485233 4.1546769142 5.1527099609 824 32.9200000000 0.0164995492 0.0113945133 0.0174084455 0.0135040099 0.4360530000 0.1131440000 0.0581650000 0.0000010000 0.2614290000 0.0018740000 115834763 0 402718720 3.9248385429 4.1436123848 5.1582627296 825 32.9600000000 0.0158141647 0.0113998704 0.0174084455 0.0134963122 0.7617280000 0.1131390000 0.0775200000 0.0292430000 0.2620330000 0.2783500000 115837539 0 402718720 3.9245076180 4.1332769394 5.1629147530 826 33.0000000000 0.0153005086 0.0114045927 0.0174084455 0.0134899029 0.4925340000 0.1131220000 0.1161280000 0.0000010000 0.2599060000 0.0019340000 115840315 0 402718720 3.9243731499 4.1240124702 5.1677613258 827 33.0400000000 0.0153914578 0.0114094136 0.0174084455 0.0134827441 0.4709600000 0.1130750000 0.0655330000 0.0298470000 0.2591030000 0.0019490000 115843091 0 402718720 3.9243838787 4.1140313148 5.1722683907 828 33.0800000000 0.0152042489 0.0114139967 0.0174084455 0.0134764016 0.4310000000 0.1130750000 0.0558380000 0.0000010000 0.2586860000 0.0019420000 115845867 0 402718720 3.9243011475 4.1061520576 5.1758618355 829 33.1199999990 0.0150198769 0.0114183464 0.0174084455 0.0134734331 0.7585630000 0.1387510000 0.0663730000 0.0298670000 0.2580750000 0.2639860000 115848643 0 402718720 3.9244692326 4.0950374603 5.1800613403 830 33.1600000000 0.0149671547 0.0114226221 0.0174084455 0.0134696624 0.4212550000 0.1131320000 0.0488050000 0.0000010000 0.2557690000 0.0020300000 115851419 0 402718720 3.9249370098 4.0817918777 5.1850385666 831 33.2000000000 0.0140056806 0.0114257305 0.0174084455 0.0134635528 0.4598050000 0.1090270000 0.0606290000 0.0297210000 0.2570860000 0.0018790000 115854195 0 402718720 3.9254732132 4.0692391396 5.1892600060 832 33.2400000000 0.0147715369 0.0114297519 0.0174084455 0.0134597631 0.4414040000 0.1130120000 0.0678050000 0.0000010000 0.2571860000 0.0019360000 115856971 0 402718720 3.9253473282 4.0615386963 5.1921882629 833 33.2800000000 0.0148030175 0.0114338014 0.0174084455 0.0134549557 0.7486190000 0.1320080000 0.0680210000 0.0291210000 0.2560960000 0.2618790000 115859747 0 402718720 3.9257366657 4.0516648293 5.1956839561 834 33.3200000000 0.0146561880 0.0114376652 0.0174084455 0.0134474997 0.4259220000 0.1088070000 0.0604330000 0.0000000000 0.2531760000 0.0019600000 115862523 0 402718720 3.9260592461 4.0424575806 5.1985554695 835 33.3600000000 0.0145284645 0.0114413667 0.0174084455 0.0134399151 0.4548340000 0.1097080000 0.0583910000 0.0291300000 0.2541900000 0.0019380000 115865299 0 402718720 3.9270098209 4.0351142883 5.2009320259 836 33.4000000000 0.0144305676 0.0114449423 0.0174084455 0.0134362881 0.4383320000 0.1128550000 0.0683010000 0.0000010000 0.2538330000 0.0018600000 115868075 0 402718720 3.9286375046 4.0266895294 5.2040200233 837 33.4399999990 0.0148366094 0.0114489945 0.0174084455 0.0134350004 0.7295220000 0.1087600000 0.0773900000 0.0296150000 0.2532280000 0.2590600000 115870851 0 402718720 3.9296319485 4.0163235664 5.2073497772 838 33.4800000000 0.0148956785 0.0114531075 0.0174084455 0.0134302789 0.4366910000 0.1128920000 0.0675370000 0.0000010000 0.2528680000 0.0019310000 115873627 0 402718720 3.9305469990 4.0062918663 5.2100763321 839 33.5200000000 0.0146706216 0.0114569424 0.0174084455 0.0134225355 0.4757200000 0.1342270000 0.0560000000 0.0296770000 0.2523790000 0.0019410000 115876403 0 402718720 3.9313068390 3.9975421429 5.2120785713 840 33.5600000000 0.0148449866 0.0114609758 0.0174084455 0.0134149286 0.4244460000 0.1128640000 0.0559570000 0.0000000000 0.2522120000 0.0019260000 115879179 0 402718720 3.9325640202 3.9914064407 5.2135157585 841 33.6000000000 0.0144520765 0.0114645324 0.0174084455 0.0134119424 0.7284870000 0.1127670000 0.0758270000 0.0297790000 0.2513110000 0.2573300000 115881955 0 402718720 3.9338490963 3.9784781933 5.2168860435 842 33.6400000000 0.0144830486 0.0114681174 0.0174084455 0.0134045114 0.4809410000 0.1127960000 0.1138100000 0.0000010000 0.2509240000 0.0019250000 115884731 0 402718720 3.9354658127 3.9653599262 5.2208642960 843 33.6800000000 0.0144487843 0.0114716531 0.0174084455 0.0133978253 0.4524930000 0.1128160000 0.0553760000 0.0296650000 0.2512050000 0.0019310000 115887507 0 402718720 3.9360365868 3.9594116211 5.2212648392 844 33.7200000000 0.0139504988 0.0114745902 0.0174084455 0.0133965328 0.4575080000 0.1363420000 0.0658630000 0.0000010000 0.2519380000 0.0018630000 115890283 0 402718720 3.9374022484 3.9520316124 5.2222161293 845 33.7599999990 0.0138405049 0.0114773901 0.0174084455 0.0134001284 0.7111970000 0.1128440000 0.0584420000 0.0296860000 0.2514350000 0.2572970000 115893059 0 402718720 3.9380080700 3.9411630630 5.2239317894 846 33.7999999990 0.0136064114 0.0114799066 0.0174084455 0.0133978126 0.4294680000 0.1089120000 0.0653750000 0.0000000000 0.2517530000 0.0019290000 115895835 0 402718720 3.9392526150 3.9357190132 5.2244887352 847 33.8400000000 0.0135758128 0.0114823811 0.0174084455 0.0133980661 0.4513470000 0.1086640000 0.0577910000 0.0295150000 0.2520040000 0.0018720000 115898611 0 402718720 3.9397814274 3.9305119514 5.2245583534 848 33.8800000000 0.0135354865 0.0114848023 0.0174084455 0.0133950947 0.4339950000 0.1127750000 0.0658690000 0.0000010000 0.2519110000 0.0019360000 115901387 0 402718720 3.9407634735 3.9188327789 5.2274684906 849 33.9200000000 0.0135188578 0.0114871981 0.0174084455 0.0133880673 0.7215380000 0.1248180000 0.0555080000 0.0290000000 0.2524560000 0.2582520000 115904163 0 402718720 3.9401383400 3.9114933014 5.2282104492 850 33.9600000000 0.0131883835 0.0114891995 0.0174084455 0.0133821719 0.4272960000 0.1127090000 0.0580070000 0.0000010000 0.2531680000 0.0019310000 115906939 0 402718720 3.9389984608 3.9073579311 5.2271952629 851 34.0000000000 0.0130229751 0.0114910018 0.0174084455 0.0133759009 0.4548150000 0.1127440000 0.0557760000 0.0296250000 0.2532330000 0.0019270000 115909715 0 402718720 3.9381835461 3.9001579285 5.2276673317 852 34.0400000000 0.0128869377 0.0114926402 0.0174084455 0.0133688806 0.4279320000 0.1127180000 0.0580650000 0.0000010000 0.2537120000 0.0019230000 115912491 0 402718720 3.9375951290 3.8954715729 5.2272114754 853 34.0800000000 0.0128031988 0.0114941766 0.0174084455 0.0133663393 0.7229880000 0.1126990000 0.0652910000 0.0296070000 0.2540580000 0.2598410000 115915267 0 402718720 3.9373805523 3.8910388947 5.2267479897 854 34.1199999990 0.0127690574 0.0114956695 0.0174084455 0.0133661409 0.4385290000 0.1250540000 0.0555410000 0.0000000000 0.2545000000 0.0019220000 115918043 0 402718720 3.9370942116 3.8834927082 5.2270860672 855 34.1600000000 0.0128435129 0.0114972459 0.0174084455 0.0133598131 0.4594430000 0.1126010000 0.0607470000 0.0296960000 0.2529050000 0.0019300000 115920819 0 402718720 3.9375216961 3.8784041405 5.2275042534 856 34.2000000000 0.0127206985 0.0114986752 0.0174084455 0.0133536052 0.4391100000 0.1252250000 0.0556150000 0.0000000000 0.2548470000 0.0019210000 115923595 0 402718720 3.9378774166 3.8764944077 5.2262940407 857 34.2400000000 0.0126034152 0.0114999642 0.0174084455 0.0133513042 0.7168200000 0.1124710000 0.0581960000 0.0289560000 0.2548950000 0.2608020000 115926371 0 402718720 3.9388914108 3.8741154671 5.2251992226 858 34.2800000000 0.0125103500 0.0115011418 0.0174084455 0.0133523733 0.4224450000 0.1083490000 0.0551990000 0.0000010000 0.2554540000 0.0019290000 115929147 0 402718720 3.9400944710 3.8708357811 5.2245235443 859 34.3200000000 0.0125506260 0.0115023636 0.0174084455 0.0133553470 0.4788830000 0.1342630000 0.0557790000 0.0295880000 0.2557860000 0.0019310000 115931923 0 402718720 3.9401810169 3.8688461781 5.2227053642 860 34.3600000000 0.0125827715 0.0115036199 0.0174084455 0.0133538352 0.4306470000 0.1124170000 0.0583750000 0.0000000000 0.2564240000 0.0019180000 115934699 0 402718720 3.9411361217 3.8665084839 5.2214312553 861 34.4000000000 0.0127216354 0.0115050345 0.0174084455 0.0133506616 0.7151340000 0.1083270000 0.0548660000 0.0294030000 0.2577820000 0.2632260000 115937475 0 402718720 3.9431705475 3.8654689789 5.2207717896 862 34.4400000000 0.0127049712 0.0115064266 0.0174084455 0.0133602631 0.4228060000 0.1123760000 0.0484740000 0.0000010000 0.2585090000 0.0019220000 115940251 0 402718720 3.9447219372 3.8622884750 5.2202053070 863 34.4800000000 0.0127047338 0.0115078151 0.0174084455 0.0133700456 0.4617950000 0.1122980000 0.0580960000 0.0288860000 0.2590570000 0.0019300000 115943027 0 402718720 3.9461381435 3.8584866524 5.2198572159 864 34.5200000000 0.0127476146 0.0115092501 0.0174084455 0.0133751969 0.4313560000 0.1121990000 0.0557100000 0.0000010000 0.2599900000 0.0019190000 115945803 0 402718720 3.9462704659 3.8588740826 5.2174649239 865 34.5600000000 0.0128150629 0.0115107597 0.0174084455 0.0133803093 0.7283840000 0.1122160000 0.0581090000 0.0295130000 0.2605350000 0.2664810000 115948579 0 402718720 3.9476420879 3.8577463627 5.2160825729 866 34.6000000000 0.0128381308 0.0115122924 0.0174084455 0.0133803366 0.4556690000 0.1377190000 0.0532110000 0.0000000000 0.2612690000 0.0019230000 115951355 0 402718720 3.9487397671 3.8535861969 5.2155532837 867 34.6400000000 0.0130208023 0.0115140324 0.0174084455 0.0133749875 0.4604290000 0.1080600000 0.0574240000 0.0295290000 0.2619300000 0.0019310000 115954131 0 402718720 3.9493904114 3.8519871235 5.2145442963 868 34.6800000000 0.0130084977 0.0115157541 0.0174084455 0.0133690589 0.4364380000 0.1120510000 0.0579870000 0.0000000000 0.2629340000 0.0019200000 115956907 0 402718720 3.9504361153 3.8510520458 5.2129650116 869 34.7200000000 0.0130102271 0.0115174738 0.0174084455 0.0133633322 0.7467960000 0.1307720000 0.0557860000 0.0295560000 0.2607770000 0.2683660000 115959683 0 402718720 3.9513804913 3.8485584259 5.2122597694 870 34.7600000000 0.0129784951 0.0115191532 0.0174084455 0.0133569675 0.4900740000 0.1079430000 0.1142780000 0.0000010000 0.2643900000 0.0019230000 115962459 0 402718720 3.9526288509 3.8459639549 5.2116441727 871 34.8000000000 0.0129432920 0.0115207882 0.0174084455 0.0133524696 0.4600240000 0.1078760000 0.0550760000 0.0293190000 0.2642760000 0.0019290000 115965235 0 402718720 3.9532880783 3.8425025940 5.2108674049 872 34.8400000000 0.0129069714 0.0115223779 0.0174084455 0.0133473590 0.4482540000 0.1246000000 0.0558560000 0.0000010000 0.2643360000 0.0019230000 115968011 0 402718720 3.9535112381 3.8384971619 5.2108335495 873 34.8800000000 0.0128644118 0.0115239152 0.0174084455 0.0133401746 0.7226140000 0.1117540000 0.0460490000 0.0287890000 0.2642680000 0.2702190000 115970787 0 402718720 3.9541728497 3.8359210491 5.2103815079 874 34.9200000000 0.0127462689 0.0115253137 0.0174084455 0.0133334183 0.4355720000 0.1117120000 0.0557390000 0.0000010000 0.2646600000 0.0019270000 115973563 0 402718720 3.9544169903 3.8339784145 5.2092308998 875 34.9600000000 0.0126456041 0.0115265941 0.0174084455 0.0133271434 0.4985300000 0.1116970000 0.0861960000 0.0294760000 0.2676700000 0.0019330000 115976339 0 402718720 3.9541559219 3.8306443691 5.2085866928 876 35.0000000000 0.0126163596 0.0115278381 0.0174084455 0.0133197026 0.4356060000 0.1116250000 0.0557240000 0.0000010000 0.2647710000 0.0019320000 115979115 0 402718720 3.9551842213 3.8279654980 5.2085351944 877 35.0400000000 0.0124601582 0.0115289012 0.0174084455 0.0133122240 0.7912320000 0.1116100000 0.1131650000 0.0294680000 0.2647560000 0.2706640000 115981891 0 402718720 3.9548344612 3.8255281448 5.2072582245 878 35.0800000000 0.0124250548 0.0115299219 0.0174084455 0.0133049773 0.4312890000 0.1075540000 0.0551830000 0.0000010000 0.2650680000 0.0019260000 115984667 0 402718720 3.9546782970 3.8217973709 5.2063550949 879 35.1200000000 0.0124963997 0.0115310214 0.0174084455 0.0132974477 0.4875350000 0.1339600000 0.0557560000 0.0294190000 0.2648910000 0.0019320000 115987443 0 402718720 3.9551944733 3.8187925816 5.2058520317 880 35.1600000000 0.0124447234 0.0115320597 0.0174084455 0.0132909273 0.4260830000 0.1117150000 0.0458910000 0.0000000000 0.2649900000 0.0019270000 115990219 0 402718720 3.9549365044 3.8140823841 5.2034091949 881 35.2000000000 0.0121967746 0.0115328142 0.0174084455 0.0132839506 0.7363980000 0.1116840000 0.0576180000 0.0294650000 0.2651080000 0.2709620000 115992995 0 402718720 3.9548268318 3.8124985695 5.2017216682 882 35.2400000000 0.0121818380 0.0115335500 0.0174084455 0.0132782791 0.4338780000 0.1117180000 0.0534570000 0.0000010000 0.2652230000 0.0019270000 115995771 0 402718720 3.9547884464 3.8097310066 5.2005038261 883 35.2800000000 0.0122702075 0.0115343843 0.0174084455 0.0132745638 0.4558880000 0.1116690000 0.0461720000 0.0294780000 0.2650570000 0.0019300000 115998547 0 402718720 3.9542605877 3.8071017265 5.1990442276 884 35.3200000000 0.0121610155 0.0115350932 0.0174084455 0.0132739813 0.4361010000 0.1117350000 0.0559360000 0.0000000000 0.2649560000 0.0019150000 116001323 0 402718720 3.9537844658 3.8049097061 5.1971240044 885 35.3600000000 0.0120784892 0.0115357072 0.0174084455 0.0132753368 0.7303260000 0.1117260000 0.0534440000 0.0288610000 0.2644000000 0.2703390000 116004099 0 402718720 3.9534792900 3.8027665615 5.1956262589 886 35.4000000000 0.0120159397 0.0115362492 0.0174084455 0.0132779034 0.4572040000 0.1076670000 0.0710490000 0.0000000000 0.2750140000 0.0019160000 116006875 0 402718720 3.9524469376 3.8009679317 5.1939997673 887 35.4400000000 0.0119897276 0.0115367604 0.0174084455 0.0132810469 0.4922410000 0.1301810000 0.0681160000 0.0295960000 0.2607090000 0.0020090000 116009651 0 402718720 3.9520099163 3.8000545502 5.1923809052 888 35.4800000000 0.0119386017 0.0115372130 0.0174084455 0.0132830808 0.4343510000 0.1117670000 0.0585550000 0.0000010000 0.2605400000 0.0019200000 116012427 0 402718720 3.9505121708 3.7977547646 5.1905679703 889 35.5200000000 0.0118757589 0.0115375938 0.0174084455 0.0132915040 0.7366120000 0.1291530000 0.0485530000 0.0296630000 0.2601270000 0.2675360000 116015203 0 402718720 3.9500188828 3.7962625027 5.1890320778 890 35.5600000000 0.0118212653 0.0115379125 0.0174084455 0.0132977469 0.4336530000 0.1117670000 0.0572880000 0.0000000000 0.2611010000 0.0019200000 116017979 0 402718720 3.9490981102 3.7958819866 5.1873598099 891 35.6000000000 0.0117498869 0.0115381504 0.0174084455 0.0133020460 0.4575520000 0.1117650000 0.0534560000 0.0289760000 0.2598480000 0.0019260000 116020755 0 402718720 3.9473659992 3.7926092148 5.1860179901 892 35.6400000000 0.0117468890 0.0115383844 0.0174084455 0.0133133315 0.4303600000 0.1117780000 0.0558780000 0.0000000000 0.2592040000 0.0019200000 116023531 0 402718720 3.9460945129 3.7915663719 5.1841850281 893 35.6800000000 0.0117063690 0.0115385725 0.0174084455 0.0133243316 0.7171820000 0.1117770000 0.0533750000 0.0289640000 0.2578050000 0.2636840000 116026307 0 402718720 3.9444375038 3.7909979820 5.1823935509 894 35.7200000000 0.0115896594 0.0115386297 0.0174084455 0.0133352547 0.4184490000 0.1117760000 0.0462600000 0.0000010000 0.2568300000 0.0019950000 116029083 0 402718720 3.9428932667 3.7885043621 5.1812057495 895 35.7600000000 0.0115693677 0.0115386640 0.0174084455 0.0133515503 0.4563800000 0.1118190000 0.0558500000 0.0297670000 0.2554220000 0.0019300000 116031859 0 402718720 3.9413115978 3.7862577438 5.1801123619 896 35.8000000000 0.0115126809 0.0115386350 0.0174084455 0.0133745580 0.4156370000 0.1118550000 0.0461090000 0.0000010000 0.2541770000 0.0019220000 116034635 0 402718720 3.9404051304 3.7861707211 5.1786360741 897 35.8400000000 0.0114941504 0.0115385854 0.0174084455 0.0133896427 0.6997420000 0.1118180000 0.0461540000 0.0291700000 0.2525950000 0.2584190000 116037411 0 402718720 3.9399693012 3.7863841057 5.1779298782 898 35.8800000000 0.0115576144 0.0115386066 0.0174084455 0.0133987005 0.4400730000 0.1390240000 0.0461170000 0.0000000000 0.2513940000 0.0019220000 116040187 0 402718720 3.9386494160 3.7856976986 5.1767086983 899 35.9200000000 0.0115470272 0.0115386160 0.0174084455 0.0134067610 0.4412290000 0.1121720000 0.0485360000 0.0292810000 0.2475670000 0.0020120000 116042963 0 402718720 3.9386370182 3.7853224277 5.1768422127 900 35.9600000000 0.0115439612 0.0115386219 0.0174084455 0.0134108128 0.4078200000 0.1119640000 0.0438570000 0.0000010000 0.2484860000 0.0019100000 116045739 0 402718720 3.9378006458 3.7848691940 5.1761379242 901 36.0000000000 0.0115140975 0.0115385947 0.0174084455 0.0134171029 0.6945120000 0.1078700000 0.0553910000 0.0299210000 0.2469640000 0.2527720000 116048515 0 402718720 3.9369561672 3.7841725349 5.1752266884 902 36.0400000000 0.0115140248 0.0115385675 0.0174084455 0.0134267334 0.4143810000 0.1119730000 0.0530270000 0.0000000000 0.2459370000 0.0018500000 116051291 0 402718720 3.9358952045 3.7838315964 5.1745729446 903 36.0800000000 0.0115604000 0.0115385916 0.0174084455 0.0134369637 0.4425660000 0.1119700000 0.0532370000 0.0299920000 0.2438490000 0.0019230000 116054067 0 402718720 3.9341318607 3.7835543156 5.1730527878 904 36.1200000000 0.0115869539 0.0115386451 0.0174084455 0.0134533414 0.4018340000 0.1120400000 0.0437620000 0.0000010000 0.2424920000 0.0019240000 116056843 0 402718720 3.9332189560 3.7824912071 5.1725659370 905 36.1600000000 0.0115806153 0.0115386915 0.0174084455 0.0134760988 0.6804650000 0.1080410000 0.0530330000 0.0298440000 0.2410990000 0.2468690000 116059619 0 402718720 3.9318358898 3.7821397781 5.1714243889 906 36.2000000000 0.0116048930 0.0115387646 0.0174084455 0.0134993657 0.4111810000 0.1120920000 0.0559380000 0.0000000000 0.2396320000 0.0019120000 116062395 0 402718720 3.9307262897 3.7822234631 5.1706566811 907 36.2400000000 0.0116129601 0.0115388464 0.0174084455 0.0135200481 0.4369280000 0.1121500000 0.0536080000 0.0294550000 0.2381710000 0.0019250000 116065171 0 402718720 3.9295821190 3.7808017731 5.1702265739 908 36.2800000000 0.0116313696 0.0115389483 0.0174084455 0.0135370443 0.4085960000 0.1121970000 0.0559040000 0.0000010000 0.2369590000 0.0019200000 116067947 0 402718720 3.9281289577 3.7811515331 5.1695642471 909 36.3200000000 0.0116499932 0.0115390705 0.0174084455 0.0135462397 0.6864160000 0.1239280000 0.0561680000 0.0301710000 0.2334780000 0.2410360000 116070723 0 402718720 3.9266293049 3.7809004784 5.1689119339 910 36.3600000000 0.0116655361 0.0115392094 0.0174084455 0.0135536025 0.3963870000 0.1121720000 0.0461950000 0.0000010000 0.2344620000 0.0019120000 116073499 0 402718720 3.9249339104 3.7803876400 5.1683287621 911 36.4000000000 0.0116627719 0.0115393451 0.0174084455 0.0135602268 0.4226180000 0.1122420000 0.0461250000 0.0295410000 0.2309860000 0.0020070000 116076275 0 402718720 3.9238619804 3.7792689800 5.1680870056 912 36.4400000000 0.0116534540 0.0115394702 0.0174084455 0.0135664270 0.4019140000 0.1121350000 0.0561170000 0.0000000000 0.2301000000 0.0019150000 116079051 0 402718720 3.9221761227 3.7779297829 5.1679100990 913 36.4800000000 0.0116766905 0.0115396205 0.0174084455 0.0136434765 0.6495790000 0.1080810000 0.0458410000 0.0300460000 0.2291830000 0.2348000000 116081827 0 402718720 3.9188361168 3.7777938843 5.1665539742 914 36.5200000000 0.0116608832 0.0115397532 0.0174084455 0.0136622722 0.4029750000 0.1238390000 0.0488160000 0.0000010000 0.2267380000 0.0019160000 116084603 0 402718720 3.9177920818 3.7772941589 5.1664867401 915 36.5600000000 0.0116844531 0.0115399113 0.0174084455 0.0136796172 0.4310220000 0.1119740000 0.0615570000 0.0296490000 0.2241470000 0.0020110000 116087379 0 402718720 3.9160268307 3.7770898342 5.1663818359 916 36.6000000000 0.0116833095 0.0115400678 0.0174084455 0.0136958859 0.3980760000 0.1118480000 0.0590760000 0.0000010000 0.2235980000 0.0019100000 116090155 0 402718720 3.9143028259 3.7770020962 5.1660294533 917 36.6400000000 0.0116868978 0.0115402280 0.0174084455 0.0137075443 0.6495140000 0.1104260000 0.0548910000 0.0293860000 0.2238560000 0.2293070000 116092931 0 402718720 3.9124641418 3.7766366005 5.1657676697 918 36.6800000000 0.0117119076 0.0115404150 0.0174084455 0.0137198620 0.3837520000 0.1117150000 0.0462610000 0.0000010000 0.2221940000 0.0019200000 116095707 0 402718720 3.9109520912 3.7761421204 5.1656656265 919 36.7200000000 0.0116589069 0.0115405439 0.0174084455 0.0137364622 0.4221310000 0.1116640000 0.0559540000 0.0303040000 0.2206430000 0.0019230000 116098483 0 402718720 3.9094099998 3.7755701542 5.1656427383 920 36.7600000000 0.0117017692 0.0115407192 0.0174084455 0.0137542333 0.3766870000 0.1077120000 0.0458240000 0.0000010000 0.2196360000 0.0018510000 116101259 0 402718720 3.9077751637 3.7758643627 5.1652140617 921 36.8000000000 0.0116932616 0.0115408848 0.0174084455 0.0137634816 0.6438890000 0.1243540000 0.0462370000 0.0303740000 0.2176840000 0.2235880000 116104035 0 402718720 3.9061937332 3.7751944065 5.1654334068 922 36.8400000000 0.0117395129 0.0115411002 0.0174084455 0.0137709428 0.4014470000 0.1351040000 0.0467480000 0.0000000000 0.2160070000 0.0019120000 116106811 0 402718720 3.9044833183 3.7744877338 5.1659131050 923 36.8800000000 0.0117486333 0.0115413251 0.0174084455 0.0137766688 0.4028970000 0.1094500000 0.0461200000 0.0297300000 0.2139930000 0.0019270000 116109587 0 402718720 3.9026606083 3.7741107941 5.1666388512 924 36.9200000000 0.0117566949 0.0115415581 0.0174084455 0.0137794198 0.3842200000 0.1116130000 0.0584770000 0.0000010000 0.2103790000 0.0020040000 116112363 0 402718720 3.9008519650 3.7735984325 5.1668009758 925 36.9600000000 0.0117442859 0.0115417773 0.0174084455 0.0137827479 0.6178120000 0.1117000000 0.0484270000 0.0297800000 0.2099870000 0.2162610000 116115139 0 402718720 3.8991122246 3.7735428810 5.1669874191 926 37.0000000000 0.0117145348 0.0115419639 0.0174084455 0.0137868759 0.3759450000 0.1078080000 0.0552710000 0.0000000000 0.2092850000 0.0019190000 116117915 0 402718720 3.8975393772 3.7733790874 5.1669707298 927 37.0400000000 0.0115576824 0.0115419808 0.0174084455 0.0137928947 0.3946680000 0.1078560000 0.0457920000 0.0302140000 0.2072190000 0.0019250000 116120691 0 402718720 3.8962700367 3.7724931240 5.1673607826 928 37.0800000000 0.0113515230 0.0115417756 0.0174084455 0.0138043367 0.3765090000 0.1117310000 0.0558300000 0.0000010000 0.2053620000 0.0019160000 116123467 0 402718720 3.8945677280 3.7727575302 5.1673808098 929 37.1200000000 0.0112032304 0.0115414112 0.0174084455 0.0138153630 0.6120080000 0.1117500000 0.0557460000 0.0298030000 0.2035690000 0.2094920000 116126243 0 402718720 3.8929536343 3.7733685970 5.1667909622 930 37.1600000000 0.0110847419 0.0115409201 0.0174084455 0.0138236958 0.3720180000 0.1117730000 0.0560930000 0.0000000000 0.2005730000 0.0019150000 116129019 0 402718720 3.8911783695 3.7736663818 5.1661386490 931 37.2000000000 0.0109310569 0.0115402651 0.0174084455 0.0138308466 0.4014450000 0.1118170000 0.0557820000 0.0305400000 0.1997160000 0.0019230000 116131795 0 402718720 3.8895297050 3.7731492519 5.1658859253 932 37.2400000000 0.0107507370 0.0115394179 0.0174084455 0.0138474236 0.3661320000 0.1087310000 0.0558400000 0.0000000000 0.1979480000 0.0019130000 116134571 0 402718720 3.8876810074 3.7727184296 5.1650371552 933 37.2800000000 0.0105195176 0.0115383248 0.0174084455 0.0138737975 0.5967370000 0.1118260000 0.0558430000 0.0299430000 0.1957350000 0.2017050000 116137347 0 402718720 3.8858635426 3.7730777264 5.1635532379 934 37.3200000000 0.0104246913 0.0115371325 0.0174084455 0.0138993743 0.3649720000 0.1117240000 0.0557670000 0.0000000000 0.1938850000 0.0019120000 116140123 0 402718720 3.8838605881 3.7743201256 5.1627669334 935 37.3600000000 0.0103534991 0.0115358666 0.0174084455 0.0139143030 0.4154690000 0.1330730000 0.0586360000 0.0300120000 0.1901520000 0.0019150000 116142899 0 402718720 3.8820550442 3.7747635841 5.1612415314 936 37.4000000000 0.0103741633 0.0115346254 0.0174084455 0.0139256723 0.3629620000 0.1116940000 0.0580580000 0.0000010000 0.1896090000 0.0019050000 116145675 0 402718720 3.8805093765 3.7750320435 5.1606245041 937 37.4400000000 0.0103856223 0.0115333992 0.0174084455 0.0139334896 0.5789890000 0.1106070000 0.0555380000 0.0306490000 0.1872510000 0.1932600000 116148451 0 402718720 3.8789553642 3.7766094208 5.1599779129 938 37.4800000000 0.0104313269 0.0115322242 0.0174084455 0.0139369776 0.3557210000 0.1115440000 0.0555740000 0.0000000000 0.1849920000 0.0019050000 116151227 0 402718720 3.8776106834 3.7767844200 5.1595807076 939 37.5200000000 0.0104808956 0.0115311046 0.0174084455 0.0139412513 0.3816060000 0.1089330000 0.0557110000 0.0307110000 0.1826340000 0.0019130000 116154003 0 402718720 3.8762447834 3.7769105434 5.1591229439 940 37.5600000000 0.0104797417 0.0115299861 0.0174084455 0.0139432181 0.3514250000 0.1092550000 0.0580380000 0.0000010000 0.1805250000 0.0019060000 116156779 0 402718720 3.8748564720 3.7771427631 5.1586699486 941 37.6000000000 0.0104801813 0.0115288705 0.0174084455 0.0139446062 0.5689470000 0.1111790000 0.0570410000 0.0300570000 0.1846720000 0.1843120000 116159555 0 402718720 3.8734712601 3.7776606083 5.1573247910 942 37.6400000000 0.0105330683 0.0115278134 0.0174084455 0.0139461024 0.3463020000 0.1110560000 0.0555070000 0.0000010000 0.1761330000 0.0019000000 116162331 0 402718720 3.8721232414 3.7779357433 5.1560149193 943 37.6800000000 0.0105424058 0.0115267684 0.0174084455 0.0139472358 0.3740880000 0.1109260000 0.0556490000 0.0301640000 0.1737380000 0.0019110000 116165107 0 402718720 3.8710055351 3.7775375843 5.1551904678 944 37.7200000000 0.0105611254 0.0115257455 0.0174084455 0.0139495302 0.3444820000 0.1107720000 0.0582200000 0.0000000000 0.1718740000 0.0019050000 116167883 0 402718720 3.8698191643 3.7771878242 5.1548943520 945 37.7600000000 0.0105625084 0.0115247262 0.0174084455 0.0139526152 0.5469850000 0.1105660000 0.0582640000 0.0307530000 0.1698240000 0.1758330000 116170659 0 402718720 3.8683600426 3.7774901390 5.1561555862 946 37.8000000000 0.0105756661 0.0115237230 0.0174084455 0.0139556805 0.3401600000 0.1102820000 0.0580390000 0.0000010000 0.1682950000 0.0018340000 116173435 0 402718720 3.8671026230 3.7770547867 5.1555976868 947 37.8400000000 0.0105873495 0.0115227342 0.0174084455 0.0139575616 0.3677810000 0.1100650000 0.0581410000 0.0301750000 0.1657830000 0.0019080000 116176211 0 402718720 3.8655617237 3.7774405479 5.1552147865 948 37.8800000000 0.0106959539 0.0115218621 0.0174084455 0.0139572849 0.3332830000 0.1099520000 0.0558650000 0.0000000000 0.1638520000 0.0018970000 116178987 0 402718720 3.8642139435 3.7775382996 5.1568183899 949 37.9200000000 0.0107945250 0.0115210956 0.0174084455 0.0139584842 0.5347850000 0.1169320000 0.0558400000 0.0308030000 0.1616950000 0.1678100000 116181763 0 402718720 3.8628530502 3.7834398746 5.1657042503 950 37.9600000000 0.0110279890 0.0115205766 0.0174084455 0.0139591373 0.3290750000 0.1093990000 0.0560820000 0.0000010000 0.1599560000 0.0018930000 116184539 0 402718720 3.8610405922 3.7880802155 5.1752362251 951 38.0000000000 0.0110513121 0.0115200831 0.0174084455 0.0139615595 0.3599560000 0.1091080000 0.0583780000 0.0307740000 0.1580290000 0.0019090000 116187315 0 402718720 3.8597328663 3.7898824215 5.1785521507 952 38.0400000000 0.0111244898 0.0115196676 0.0174084455 0.0139625193 0.3330640000 0.1055470000 0.0671890000 0.0000010000 0.1567940000 0.0018280000 116190091 0 402718720 3.8586611748 3.7908170223 5.1786575317 953 38.0800000000 0.0111848079 0.0115193162 0.0174084455 0.0139595521 0.5244410000 0.1086910000 0.0677290000 0.0308400000 0.1546790000 0.1607750000 116192867 0 402718720 3.8575162888 3.7909297943 5.1785187721 954 38.1200000000 0.0110238949 0.0115187969 0.0174084455 0.0139581958 0.3334120000 0.1086140000 0.0678770000 0.0000010000 0.1532970000 0.0018960000 116195643 0 402718720 3.8564581871 3.7911474705 5.1798572540 955 38.1600000000 0.0109322136 0.0115181827 0.0174084455 0.0139598364 0.3789850000 0.1051660000 0.0797130000 0.0308630000 0.1586310000 0.0026640000 116198419 0 402718720 3.8556582928 3.7904827595 5.1778626442 956 38.2000000000 0.0108179003 0.0115174502 0.0174084455 0.0139611153 0.3831670000 0.1406830000 0.0884580000 0.0000010000 0.1503960000 0.0018930000 116201195 0 402718720 3.8543648720 3.7910625935 5.1778535843 957 38.2400000000 0.0106636398 0.0115165580 0.0174084455 0.0139595254 0.4997170000 0.1085090000 0.0555760000 0.0302960000 0.1487040000 0.1547730000 116203971 0 402718720 3.8530428410 3.7914237976 5.1764736176 958 38.2800000000 0.0105986614 0.0115155999 0.0174084455 0.0139568280 0.3273400000 0.1084570000 0.0677250000 0.0000000000 0.1475440000 0.0018950000 116206747 0 402718720 3.8522117138 3.7895150185 5.1722726822 959 38.3200000000 0.0102873016 0.0115143191 0.0174084455 0.0139559021 0.3667080000 0.1186200000 0.0679070000 0.0309490000 0.1455970000 0.0019040000 116209523 0 402718720 3.8510084152 3.7891056538 5.1721343994 960 38.3600000000 0.0095949313 0.0115123197 0.0174084455 0.0139554961 0.3534620000 0.1086270000 0.0967390000 0.0000010000 0.1444750000 0.0018910000 116212299 0 402718720 3.8495423794 3.7905867100 5.1759290695 961 38.4000000000 0.0099333879 0.0115106767 0.0174084455 0.0139543011 0.5730270000 0.1085310000 0.1340330000 0.0369980000 0.1428130000 0.1489170000 116215075 0 402718720 3.8484249115 3.7900972366 5.1787495613 962 38.4400000000 0.0165916067 0.0115159583 0.0174084455 0.0139568266 0.3710330000 0.1085650000 0.1172730000 0.0000010000 0.1415610000 0.0018880000 116217851 0 402718720 3.8469510078 3.7899770737 5.1885743141 963 38.4800000000 0.0414883345 0.0115470823 0.0414883345 0.0139853044 0.4201660000 0.1266450000 0.1188670000 0.0308840000 0.1401200000 0.0019070000 116220627 0 402718720 3.8453578949 3.7888345718 5.2124266624 964 38.5200000000 0.0736729279 0.0116115282 0.0736729279 0.0140423396 0.3733590000 0.1086090000 0.1227890000 0.0000010000 0.1381430000 0.0019890000 116223403 0 402718720 3.8433344364 3.7906708717 5.2459530830 965 38.5600000000 0.1049214378 0.0117082224 0.1049214378 0.0140874782 0.5179550000 0.1065630000 0.0980730000 0.0308160000 0.1373270000 0.1434240000 116226179 0 402718720 3.8416357040 3.7909951210 5.2756986618 966 38.6000000000 0.1269837171 0.0118275552 0.1269837171 0.0141119009 0.3625700000 0.1052530000 0.1174790000 0.0000000000 0.1362440000 0.0018330000 116228955 0 402718720 3.8401458263 3.7914311886 5.2971744537 967 38.6400000000 0.1390911788 0.0119591618 0.1390911788 0.0141175726 0.3461940000 0.1082960000 0.0689540000 0.0307660000 0.1345150000 0.0019050000 116231731 0 402718720 3.8385791779 3.7925295830 5.3115892410 968 38.6800000000 0.1594524682 0.0121115310 0.1594524682 0.0141360200 0.3011790000 0.1082160000 0.0561150000 0.0000010000 0.1331980000 0.0018880000 116234507 0 402718720 3.8370378017 3.7910919189 5.3295655251 969 38.7200000000 0.2068880051 0.0123125387 0.2068880051 0.0142476415 0.4829440000 0.1223000000 0.0588970000 0.0301020000 0.1316630000 0.1382260000 116237283 0 402718720 3.8346722126 3.7926056385 5.3774304390 970 38.7600000000 0.2582147419 0.0125660461 0.2582147419 0.0143709031 0.2986990000 0.1079810000 0.0560960000 0.0000010000 0.1309780000 0.0018870000 116240059 0 402718720 3.8325977325 3.7930970192 5.4272704124 971 38.8000000000 0.3115353584 0.0128739445 0.3115353584 0.0145047700 0.3174030000 0.1077970000 0.0464610000 0.0299030000 0.1295790000 0.0019090000 116242835 0 402718720 3.8302211761 3.7926559448 5.4784283638 972 38.8400000000 0.3639621437 0.0132351463 0.3639621437 0.0146239335 0.2922270000 0.1045710000 0.0551940000 0.0000010000 0.1288810000 0.0018240000 116245611 0 402718720 3.8277726173 3.7936961651 5.5303835869 973 38.8800000000 0.4163044691 0.0136494005 0.4163044691 0.0147447967 0.4457440000 0.1075560000 0.0456420000 0.0297450000 0.1274590000 0.1336140000 116248387 0 402718720 3.8258030415 3.7937166691 5.5815119743 974 38.9200000000 0.4654050767 0.0141132154 0.4654050767 0.0148453872 0.2811740000 0.1046590000 0.0461940000 0.0000000000 0.1266590000 0.0018980000 116251163 0 402718720 3.8236849308 3.7946612835 5.6307864189 975 38.9600000000 0.5169349313 0.0146289299 0.5169349313 0.0149572557 0.3195350000 0.1072790000 0.0534730000 0.0296310000 0.1254840000 0.0019050000 116253939 0 402718720 3.8215467930 3.7955911160 5.6817569733 976 39.0000000000 0.5644439459 0.0151922650 0.5644439459 0.0150523222 0.2811310000 0.1071390000 0.0455740000 0.0000000000 0.1247480000 0.0018850000 116256715 0 402718720 3.8195011616 3.7948727608 5.7276139259 977 39.0400000000 0.6107808352 0.0158018746 0.6107808352 0.0151326439 0.4479370000 0.1070680000 0.0550100000 0.0301700000 0.1238730000 0.1300460000 116259491 0 402718720 3.8175313473 3.7958257198 5.7734293938 978 39.0800000000 0.6579542756 0.0164584721 0.6579542756 0.0152242543 0.3002250000 0.1249960000 0.0485030000 0.0000010000 0.1228800000 0.0019780000 116262267 0 402718720 3.8157262802 3.7959501743 5.8186383247 979 39.1200000000 0.7087109089 0.0171655737 0.7087109089 0.0153308040 0.3085090000 0.1068980000 0.0458700000 0.0300930000 0.1218030000 0.0019780000 116265043 0 402718720 3.8139057159 3.7949635983 5.8665795326 980 39.1600000000 0.7558785081 0.0179193624 0.7558785081 0.0154185330 0.2781600000 0.1068570000 0.0460760000 0.0000010000 0.1215430000 0.0018970000 116267819 0 402718720 3.8119513988 3.7954945564 5.9120006561 981 39.2000000000 0.8012865186 0.0187179018 0.8012865186 0.0155031077 0.4270940000 0.1037820000 0.0448980000 0.0291190000 0.1207020000 0.1268330000 116270595 0 402718720 3.8102517128 3.7954428196 5.9567923546 982 39.2400000000 0.8476126790 0.0195619902 0.8476126790 0.0155821565 0.2825630000 0.1037260000 0.0550330000 0.0000010000 0.1202100000 0.0018280000 116273371 0 402718720 3.8084535599 3.7957177162 6.0013618469 983 39.2800000000 0.8963761330 0.0204539679 0.8963761330 0.0156734577 0.3052230000 0.1064790000 0.0458420000 0.0298910000 0.1193330000 0.0019000000 116276147 0 402718720 3.8067526817 3.7963907719 6.0485968590 984 39.3200000000 0.9037860036 0.0213516631 0.9037860036 0.0156693567 0.2731190000 0.1063760000 0.0440850000 0.0000000000 0.1189920000 0.0018860000 116278923 0 402718720 3.8060998917 3.7967746258 6.0550751686 985 39.3600000000 0.9544517398 0.0222989728 0.9544517398 0.0157723855 0.4327420000 0.1062720000 0.0529580000 0.0292700000 0.1181350000 0.1243270000 116281699 0 402718720 3.8044629097 3.7972056866 6.1030869484 986 39.4000000000 0.9609225392 0.0232509237 0.9609225392 0.0157686813 0.2838440000 0.1062030000 0.0561980000 0.0000010000 0.1177470000 0.0018820000 116284475 0 402718720 3.8042988777 3.7976682186 6.1079468727 987 39.4400000000 1.0078043938 0.0242484450 1.0078043938 0.0158662564 0.3113440000 0.1059780000 0.0548580000 0.0299080000 0.1169090000 0.0019090000 116287251 0 402718720 3.8030083179 3.7976794243 6.1531310081 988 39.4800000000 1.0137511492 0.0252499659 1.0137511492 0.0158613148 0.2726150000 0.1059520000 0.0465040000 0.0000010000 0.1164690000 0.0018890000 116290027 0 402718720 3.8028824329 3.7978951931 6.1575961113 989 39.5200000000 1.0662301779 0.0263025243 1.0662301779 0.0159723626 0.4283610000 0.1165280000 0.0426960000 0.0292980000 0.1159270000 0.1221210000 116292803 0 402718720 3.8013110161 3.7981634140 6.2074561119 990 39.5600000000 1.0662226677 0.0273529486 1.0662301779 0.0159653829 0.2839370000 0.1057160000 0.0588520000 0.0000010000 0.1155110000 0.0020030000 116295579 0 402718720 3.8013579845 3.7987620831 6.2062225342 991 39.6000000000 1.1166673899 0.0284521560 1.1166673899 0.0160692802 0.3016190000 0.1055710000 0.0473610000 0.0300190000 0.1147770000 0.0019880000 116298355 0 402718720 3.7997338772 3.7991678715 6.2539663315 992 39.6400000000 1.1200617552 0.0295525689 1.1200617552 0.0160627050 0.2689290000 0.1049680000 0.0456000000 0.0000010000 0.1146580000 0.0018970000 116301131 0 402718720 3.7994482517 3.7997007370 6.2553334236 993 39.6800000000 1.1607609987 0.0306917516 1.1607609987 0.0161277885 0.4263200000 0.1043980000 0.0551680000 0.0300030000 0.1143760000 0.1205660000 116303907 0 402718720 3.7980089188 3.7998509407 6.2941360474 994 39.7200000000 1.1597336531 0.0318276086 1.1607609987 0.0161207463 0.2674360000 0.1040240000 0.0454630000 0.0000010000 0.1142610000 0.0018890000 116306683 0 402718720 3.7979040146 3.7996053696 6.2895698547 995 39.7600000000 1.2004982233 0.0330021519 1.2004982233 0.0161798047 0.3326390000 0.1295500000 0.0552690000 0.0300330000 0.1140700000 0.0019010000 116309459 0 402718720 3.7961626053 3.8013720512 6.3271861076 996 39.8000000000 1.1893688440 0.0341631627 1.2004982233 0.0161760095 0.2736270000 0.1052130000 0.0510300000 0.0000010000 0.1135370000 0.0019750000 116312235 0 402718720 3.7961721420 3.8028039932 6.3136191368 997 39.8400000000 1.2226953506 0.0353552712 1.2226953506 0.0162241450 0.4208790000 0.1052230000 0.0506080000 0.0301440000 0.1133900000 0.1197140000 116315011 0 402718720 3.7945058346 3.8049101830 6.3453402519 998 39.8800000000 1.2540330887 0.0365763912 1.2540330887 0.0162633907 0.2764840000 0.1022480000 0.0568400000 0.0000000000 0.1136710000 0.0019000000 116317787 0 402718720 3.7933602333 3.8063955307 6.3745808601 999 39.9200000000 1.2537848949 0.0377948182 1.2540330887 0.0162671803 0.3259040000 0.1196950000 0.0592450000 0.0302200000 0.1128510000 0.0019920000 116320563 0 402718720 3.7928993702 3.8092789650 6.3696570396 1000 39.9600000000 1.2844362259 0.0390414596 1.2844362259 0.0163063178 0.2696880000 0.1047100000 0.0481710000 0.0000000000 0.1130930000 0.0018890000 116323339 0 402718720 3.7910752296 3.8120667934 6.3984107971 1001 40.0000000000 1.3116304874 0.0403127773 1.3116304874 0.0163381946 0.4146910000 0.1045610000 0.0458860000 0.0301820000 0.1130170000 0.1192280000 116326115 0 402718720 3.7898087502 3.8140485287 6.4231786728 1002 40.0400000000 1.2611572742 0.0415311850 1.3116304874 0.0164293869 0.2630140000 0.1043100000 0.0426100000 0.0000000000 0.1123800000 0.0018890000 116328891 0 402718720 3.7914841175 3.8148574829 6.3705635071 1003 40.0800000000 1.2913587093 0.0427772742 1.3116304874 0.0164738101 0.3053700000 0.1042330000 0.0553390000 0.0296870000 0.1123820000 0.0019070000 116331667 0 402718720 3.7892622948 3.8192105293 6.3989882469 1004 40.1200000000 1.3189828396 0.0440483953 1.3189828396 0.0165061371 0.2776720000 0.1013840000 0.0599010000 0.0000010000 0.1126730000 0.0018860000 116334443 0 402718720 3.7883493900 3.8205878735 6.4231619835 1005 40.1600000000 1.3468017578 0.0453446673 1.3468017578 0.0165397554 0.4325580000 0.1166180000 0.0522550000 0.0302820000 0.1126510000 0.1189190000 116337219 0 402718720 3.7872915268 3.8226335049 6.4501485825 1006 40.2000000000 1.3782322407 0.0466696053 1.3782322407 0.0165847085 0.2754090000 0.1037400000 0.0551400000 0.0000010000 0.1128220000 0.0018880000 116339995 0 402718720 3.7860751152 3.8245539665 6.4788980484 1007 40.2400000000 1.4144645929 0.0480278922 1.4144645929 0.0166407155 0.2952560000 0.1035750000 0.0448920000 0.0302980000 0.1127660000 0.0019110000 116342771 0 402718720 3.7850034237 3.8262975216 6.5116157532 1008 40.2800000000 1.3400548697 0.0493096650 1.4144645929 0.0168522652 0.2710340000 0.1036320000 0.0513140000 0.0000010000 0.1123570000 0.0018940000 116345547 0 402718720 3.7881195545 3.8243627548 6.4350156784 1009 40.3200000000 1.3859843016 0.0506344169 1.4144645929 0.0169400639 0.4246630000 0.1131930000 0.0476680000 0.0304520000 0.1126320000 0.1188900000 116348323 0 402718720 3.7850275040 3.8312914371 6.4777884483 1010 40.3600000000 1.4230997562 0.0519932935 1.4230997562 0.0169967725 0.2678960000 0.1034600000 0.0478480000 0.0000010000 0.1128500000 0.0018880000 116351099 0 402718720 3.7839052677 3.8337013721 6.5113139153 1011 40.4000000000 1.4512256384 0.0533773017 1.4512256384 0.0170338652 0.2983130000 0.1032320000 0.0478370000 0.0305340000 0.1127850000 0.0019850000 116353875 0 402718720 3.7828598022 3.8363983631 6.5355577469 1012 40.4400000000 1.4777611494 0.0547847957 1.4777611494 0.0170672280 0.2969410000 0.1227460000 0.0576130000 0.0000010000 0.1128320000 0.0018890000 116356651 0 402718720 3.7817139626 3.8397550583 6.5591053963 1013 40.4800000000 1.5060381889 0.0562174249 1.5060381889 0.0171014954 0.4216960000 0.1030680000 0.0545090000 0.0305350000 0.1127410000 0.1190210000 116359427 0 402718720 3.7805049419 3.8428881168 6.5847287178 1014 40.5200000000 1.3745169640 0.0575175230 1.5060381889 0.0177475155 0.2734830000 0.1003700000 0.0571070000 0.0000010000 0.1121440000 0.0019290000 116362203 0 402718720 3.7863261700 3.8390636444 6.4511790276 1015 40.5600000000 1.4051643610 0.0588452539 1.5060381889 0.0177957474 0.2972520000 0.1027110000 0.0476860000 0.0307710000 0.1121670000 0.0019810000 116364979 0 402718720 3.7820847034 3.8520195484 6.4791688919 1016 40.6000000000 1.4248132706 0.0601897106 1.5060381889 0.0178120933 0.2932320000 0.1026180000 0.0743970000 0.0000010000 0.1124780000 0.0018950000 116367755 0 402718720 3.7811186314 3.8556272984 6.4970459938 1017 40.6400000000 1.4445151091 0.0615508959 1.5060381889 0.0178246352 0.4312620000 0.1025940000 0.0647940000 0.0307700000 0.1125000000 0.1187560000 116370531 0 402718720 3.7799944878 3.8595728874 6.5139665604 1018 40.6800000000 1.4640074968 0.0629285546 1.5060381889 0.0178416269 0.2742670000 0.1024810000 0.0553170000 0.0000010000 0.1127240000 0.0018950000 116373307 0 402718720 3.7788724899 3.8636066914 6.5312919617 1019 40.7200000000 1.4767986536 0.0643160621 1.5060381889 0.0178502151 0.3260380000 0.1115400000 0.0672300000 0.0308060000 0.1126810000 0.0019070000 116376083 0 402718720 3.7779095173 3.8676497936 6.5419468880 1020 40.7600000000 1.4860957861 0.0657099638 1.5060381889 0.0178521364 0.2891260000 0.1149090000 0.0576880000 0.0000000000 0.1127400000 0.0019070000 116378859 0 402718720 3.7770259380 3.8712460995 6.5497307777 1021 40.8000000000 1.4956238270 0.0671104671 1.5060381889 0.0178536397 0.4272290000 0.0995930000 0.0638550000 0.0306270000 0.1127780000 0.1185380000 116381635 0 402718720 3.7760741711 3.8751704693 6.5570569038 1022 40.8400000000 1.5033928156 0.0685158314 1.5060381889 0.0178525854 0.2829310000 0.1019060000 0.0645700000 0.0000010000 0.1126990000 0.0018910000 116384411 0 402718720 3.7750339508 3.8790700436 6.5636014938 1023 40.8800000000 1.5115416050 0.0699264138 1.5115416050 0.0178523515 0.3057180000 0.1018170000 0.0573230000 0.0302580000 0.1125560000 0.0019090000 116387187 0 402718720 3.7739624977 3.8833734989 6.5705504417 1024 40.9200000000 1.5171740055 0.0713397415 1.5171740055 0.0178551205 0.2753110000 0.1016610000 0.0573550000 0.0000010000 0.1124960000 0.0019150000 116389963 0 402718720 3.7731347084 3.8874185085 6.5744771957 1025 40.9600000000 1.5221287012 0.0727551454 1.5221287012 0.0178602809 0.4200540000 0.1014900000 0.0549260000 0.0308880000 0.1122880000 0.1185740000 116491043 0 402718720 3.7724549770 3.8918528557 6.5780344009 1026 41.0000000000 1.5328100920 0.0741782009 1.5328100920 0.0178667228 0.2721160000 0.1014910000 0.0546770000 0.0000000000 0.1121570000 0.0018920000 116698619 0 402718720 3.7711720467 3.8981707096 6.5859794617 1027 41.0400000000 1.5438153744 0.0756092010 1.5438153744 0.0178769628 0.2996260000 0.0992160000 0.0539550000 0.0306900000 0.1120400000 0.0018390000 116701395 0 402718720 3.7700998783 3.9028725624 6.5947809219 1028 41.0800000000 1.5517104864 0.0770450972 1.5517104864 0.0178824040 0.2686410000 0.0991710000 0.0538920000 0.0000010000 0.1118600000 0.0018280000 116704171 0 402718720 3.7692689896 3.9083871841 6.6012263298 1029 41.1200000000 1.5611871481 0.0784874121 1.5611871481 0.0178848471 0.4444730000 0.1259940000 0.0566690000 0.0309790000 0.1113710000 0.1176000000 116706947 0 402718720 3.7682745457 3.9131593704 6.6085634232 1030 41.1600000000 1.5677093267 0.0799332587 1.5677093267 0.0178851904 0.2821950000 0.1013620000 0.0658960000 0.0000000000 0.1111460000 0.0018960000 116709723 0 402718720 3.7675139904 3.9160749912 6.6130952835 1031 41.2000000000 1.5752288103 0.0813835938 1.5752288103 0.0178877327 0.3486880000 0.1013710000 0.0804810000 0.0380600000 0.1239420000 0.0026750000 116712499 0 402718720 3.7665870190 3.9211502075 6.6183066368 1032 41.2400000000 1.5847373009 0.0828403319 1.5847373009 0.0178885950 0.3335510000 0.1075840000 0.1117570000 0.0000010000 0.1104110000 0.0019090000 116715275 0 402718720 3.7658100128 3.9250483513 6.6259341240 1033 41.2800000000 1.5914566517 0.0843007543 1.5914566517 0.0178857784 0.4251680000 0.1012820000 0.0652750000 0.0304060000 0.1100910000 0.1162220000 116718051 0 402718720 3.7650840282 3.9275648594 6.6312794685 1034 41.3200000000 1.5993621349 0.0857659974 1.5993621349 0.0179036124 0.3263500000 0.1012040000 0.1118340000 0.0000010000 0.1095060000 0.0018960000 116720827 0 402718720 3.7641129494 3.9332649708 6.6359162331 1035 41.3600000000 1.5957555771 0.0872249245 1.5993621349 0.0178958840 0.3742270000 0.1139470000 0.1163550000 0.0304680000 0.1094820000 0.0019900000 116723603 0 402718720 3.7640140057 3.9342763424 6.6313052177 1036 41.4000000000 1.5908809900 0.0886763300 1.5993621349 0.0178906300 0.3257350000 0.1009950000 0.1114530000 0.0000010000 0.1095100000 0.0018940000 116726379 0 402718720 3.7635915279 3.9373199940 6.6246204376 1037 41.4400000000 1.5716333389 0.0901063753 1.5993621349 0.0178957196 0.4681410000 0.1008410000 0.1109830000 0.0304520000 0.1088890000 0.1150700000 116729155 0 402718720 3.7633764744 3.9651381969 6.6025691032 1038 41.4800000000 1.5570526123 0.0915196183 1.5993621349 0.0178974406 0.3221840000 0.1006690000 0.1089850000 0.0000010000 0.1087360000 0.0018940000 116731931 0 402718720 3.7634370327 3.9881563187 6.5844383240 1039 41.5200000000 1.6161490679 0.0929870192 1.6161490679 0.0183191474 0.3598790000 0.1110370000 0.1049270000 0.0303790000 0.1097180000 0.0019100000 116734707 0 402718720 3.7603981495 3.8943545818 6.6474413872 1040 41.5600000000 1.6136382818 0.0944491838 1.6161490679 0.0183457121 0.3252300000 0.1003660000 0.1113130000 0.0000010000 0.1097410000 0.0018930000 116737483 0 402718720 3.7601845264 3.8831028938 6.6438970566 1041 41.6000000000 1.9847966433 0.0962650796 1.9847966433 0.0259620538 0.4284190000 0.1001720000 0.0912230000 0.0306500000 0.0990920000 0.1053600000 116740259 0 402718720 3.7558467388 3.3679552078 6.9521899223 1042 41.6400000000 1.9930224419 0.0980853841 1.9930224419 0.0264261349 0.2863580000 0.0977640000 0.0935640000 0.0000000000 0.0912860000 0.0018370000 116743035 0 402718720 3.7578067780 3.2017538548 6.9081959724 1043 41.6800000000 1.9779226780 0.0998877209 1.9930224419 0.0264256178 0.3196590000 0.0998350000 0.0968350000 0.0300930000 0.0890660000 0.0019080000 116745811 0 402718720 3.7580180168 3.2039334774 6.8907380104 1044 41.7200000000 1.9760667086 0.1016848273 1.9930224419 0.0264208967 0.2632800000 0.0974000000 0.0726360000 0.0000000000 0.0894920000 0.0018280000 116748587 0 402718720 3.7579112053 3.2085030079 6.8888621330 1045 41.7600000000 1.9717023373 0.1034743177 1.9930224419 0.0264164696 0.4404000000 0.1180950000 0.1036210000 0.0306910000 0.0899270000 0.0961390000 116751363 0 402718720 3.7580008507 3.2110884190 6.8843054771 1046 41.8000000000 1.9685698748 0.1052573918 1.9930224419 0.0264091157 0.2918410000 0.0991270000 0.0984950000 0.0000010000 0.0904330000 0.0018940000 116754139 0 402718720 3.7579452991 3.2144916058 6.8805460930 1047 41.8400000000 1.9668706656 0.1070354370 1.9930224419 0.0264003733 0.2903030000 0.0987260000 0.0661290000 0.0306540000 0.0909470000 0.0019120000 116756915 0 402718720 3.7580378056 3.2166235447 6.8789634705 1048 41.8800000000 1.9645214081 0.1088078473 1.9930224419 0.0263902538 0.3772330000 0.1323850000 0.1368190000 0.0000000000 0.1038850000 0.0022140000 116759691 0 402718720 3.7579834461 3.2193620205 6.8756337166 1049 41.9200000000 1.9623388052 0.1105747977 1.9930224419 0.0263822930 0.4256270000 0.0982800000 0.1045480000 0.0306610000 0.0918900000 0.0982480000 116762467 0 402718720 3.7579176426 3.2224748135 6.8725771904 1050 41.9600000000 1.9596164227 0.1123357897 1.9930224419 0.0263751909 0.3000130000 0.0981090000 0.1054380000 0.0000010000 0.0924430000 0.0019880000 116765243 0 402718720 3.7579748631 3.2254540920 6.8690824509 1051 42.0000000000 1.9579963684 0.1140918892 1.9930224419 0.0263669300 0.3310090000 0.0979500000 0.1056140000 0.0306740000 0.0929020000 0.0019210000 116768019 0 402718720 3.7581472397 3.2271749973 6.8666701317 1052 42.0400000000 1.9573259354 0.1158440128 1.9930224419 0.0263582709 0.2959200000 0.0977440000 0.1010070000 0.0000000000 0.0933020000 0.0018930000 116770795 0 402718720 3.7581043243 3.2282993793 6.8654670715 1053 42.0800000000 1.9550563097 0.1175906532 1.9930224419 0.0263490771 0.4252440000 0.0975130000 0.1014960000 0.0306290000 0.0936910000 0.0999670000 116773571 0 402718720 3.7580766678 3.2308609486 6.8622655869 1054 42.1200000000 1.9536640644 0.1193326583 1.9930224419 0.0263407676 0.2970480000 0.0973310000 0.1017910000 0.0000010000 0.0940740000 0.0019060000 116776347 0 402718720 3.7580962181 3.2318141460 6.8601427078 1055 42.1600000000 1.9523335695 0.1210700999 1.9930224419 0.0263307104 0.3104850000 0.0970850000 0.0851740000 0.0300090000 0.0943300000 0.0019190000 116779123 0 402718720 3.7578544617 3.2340581417 6.8584771156 1056 42.2000000000 1.9500418901 0.1228020808 1.9930224419 0.0263243809 0.2979910000 0.0967190000 0.1025680000 0.0000000000 0.0948020000 0.0019130000 116781899 0 402718720 3.7577569485 3.2366902828 6.8561048508 1057 42.2400000000 1.9460711479 0.1245270279 1.9930224419 0.0263172660 0.4283690000 0.0963590000 0.1029020000 0.0305520000 0.0951580000 0.1014250000 116784675 0 402718720 3.7578475475 3.2389760017 6.8519277573 1058 42.2800000000 1.9425461292 0.1262453824 1.9930224419 0.0263072506 0.2988390000 0.0960540000 0.1034530000 0.0000010000 0.0954800000 0.0018930000 116787451 0 402718720 3.7578074932 3.2412998676 6.8487453461 1059 42.3200000000 1.9409855604 0.1279590181 1.9930224419 0.0262978173 0.3303580000 0.1054100000 0.0949510000 0.0305190000 0.0956120000 0.0019090000 116790227 0 402718720 3.7576711178 3.2413218021 6.8471746445 1060 42.3600000000 1.9378850460 0.1296664955 1.9930224419 0.0262878337 0.2947310000 0.0952810000 0.0998160000 0.0000000000 0.0957700000 0.0019020000 116793003 0 402718720 3.7575428486 3.2424407005 6.8441839218 1061 42.4000000000 1.9349431992 0.1313679815 1.9930224419 0.0262773888 0.3984900000 0.0948330000 0.0729460000 0.0304570000 0.0959370000 0.1022910000 116795779 0 402718720 3.7573952675 3.2443811893 6.8417196274 1062 42.4400000000 1.9320192337 0.1330635100 1.9930224419 0.0262747272 0.3034050000 0.0937610000 0.1096010000 0.0000000000 0.0961630000 0.0018980000 116798555 0 402718720 3.7570466995 3.2465338707 6.8409991264 1063 42.4800000000 1.9263294935 0.1347504959 1.9930224419 0.0262667157 0.2853800000 0.0932750000 0.0614750000 0.0303250000 0.0964350000 0.0019190000 116801331 0 402718720 3.7573449612 3.2492933273 6.8365163803 1064 42.5200000000 1.9241404533 0.1364322534 1.9930224419 0.0262564803 0.2780400000 0.0909370000 0.0865970000 0.0000010000 0.0966440000 0.0018920000 116804107 0 402718720 3.7574908733 3.2501761913 6.8350667953 1065 42.5600000000 1.9223911762 0.1381092101 1.9930224419 0.0262461951 0.4094900000 0.0904420000 0.0871740000 0.0300900000 0.0968020000 0.1030240000 116806883 0 402718720 3.7577307224 3.2502951622 6.8341317177 1066 42.6000000000 1.9200531244 0.1397808273 1.9930224419 0.0262345893 0.3055640000 0.1022000000 0.1023820000 0.0000010000 0.0971060000 0.0018950000 116809659 0 402718720 3.7578904629 3.2541790009 6.8330135345 1067 42.6400000000 1.9177758694 0.1414471769 1.9930224419 0.0262250526 0.3192050000 0.0915100000 0.0969370000 0.0295730000 0.0972860000 0.0019170000 116812435 0 402718720 3.7581317425 3.2560698986 6.8317732811 1068 42.6800000000 1.9165894985 0.1431092952 1.9930224419 0.0262169501 0.2869140000 0.0892950000 0.0960750000 0.0000000000 0.0977060000 0.0018240000 116815211 0 402718720 3.7585260868 3.2568469048 6.8316154480 1069 42.7200000000 1.9151226282 0.1447669316 1.9930224419 0.0262092228 0.4408330000 0.1008470000 0.1062230000 0.0295350000 0.0979630000 0.1042790000 116817987 0 402718720 3.7589435577 3.2585327625 6.8309898376 1070 42.7600000000 1.9136635065 0.1464201060 1.9930224419 0.0262001058 0.2724890000 0.0900970000 0.0801170000 0.0000020000 0.0984060000 0.0018890000 116820763 0 402718720 3.7592105865 3.2608327866 6.8301043510 1071 42.8000000000 1.9136288166 0.1480701608 1.9930224419 0.0261904564 0.3272380000 0.0884960000 0.1066550000 0.0294450000 0.0987510000 0.0019040000 116823539 0 402718720 3.7591900826 3.2628343105 6.8321647644 1072 42.8400000000 1.9116346836 0.1497152769 1.9930224419 0.0261806490 0.2817790000 0.0892930000 0.0892370000 0.0000010000 0.0993770000 0.0018910000 116826315 0 402718720 3.7591571808 3.2644538879 6.8320565224 1073 42.8800000000 1.9096537828 0.1513554806 1.9930224419 0.0261697829 0.4335280000 0.0885740000 0.1071070000 0.0299670000 0.0998070000 0.1060770000 116829091 0 402718720 3.7591249943 3.2671251297 6.8307337761 1074 42.9200000000 1.9060879946 0.1529893097 1.9930224419 0.0261600542 0.3167510000 0.0997040000 0.1127050000 0.0000010000 0.1002900000 0.0019820000 116831867 0 402718720 3.7589745522 3.2672290802 6.8272180557 1075 42.9600000000 1.9008011818 0.1546151812 1.9930224419 0.0261507406 0.3213070000 0.0857900000 0.1011520000 0.0298310000 0.1006360000 0.0019070000 116834643 0 402718720 3.7590029240 3.2680935860 6.8217597008 1076 43.0000000000 1.8951324224 0.1562327623 1.9930224419 0.0261413558 0.2993500000 0.0869250000 0.1076840000 0.0000010000 0.1008490000 0.0018880000 116837419 0 402718720 3.7591032982 3.2676043510 6.8172421455 1077 43.0400000000 1.8918070793 0.1578442519 1.9930224419 0.0261310419 0.4468940000 0.0994340000 0.1077920000 0.0297370000 0.1008540000 0.1071060000 116840195 0 402718720 3.7591595650 3.2674665451 6.8162937164 1078 43.0800000000 1.8853065968 0.1594467216 1.9930224419 0.0261221393 0.3146850000 0.1018960000 0.1078170000 0.0000010000 0.1010880000 0.0018870000 116842971 0 402718720 3.7594664097 3.2684764862 6.8114652634 1079 43.1200000000 1.8824114799 0.1610435379 1.9930224419 0.0261116034 0.3121050000 0.1015440000 0.0755790000 0.0297020000 0.1012380000 0.0019790000 116845747 0 402718720 3.7596151829 3.2704858780 6.8116741180 1080 43.1600000000 1.8763873577 0.1626318192 1.9930224419 0.0261024803 0.2632410000 0.0856220000 0.0723810000 0.0000010000 0.1013480000 0.0018880000 116848523 0 402718720 3.7599084377 3.2708950043 6.8072342873 1081 43.2000000000 1.8748182058 0.1642157104 1.9930224419 0.0260925191 0.4358730000 0.0850580000 0.1109010000 0.0289760000 0.1013590000 0.1075930000 116851299 0 402718720 3.7600409985 3.2723290920 6.8088307381 1082 43.2400000000 1.8737936020 0.1657957270 1.9930224419 0.0260831174 0.3031880000 0.0843930000 0.1133600000 0.0000010000 0.1015350000 0.0018880000 116854075 0 402718720 3.7601172924 3.2725868225 6.8095641136 1083 43.2800000000 1.8777974844 0.1673765227 1.9930224419 0.0260751377 0.3385970000 0.0958280000 0.1082290000 0.0289290000 0.1016970000 0.0019170000 116856851 0 402718720 3.7602245808 3.2735023499 6.8162894249 1084 43.3200000000 1.8765693903 0.1689532689 1.9930224419 0.0260640505 0.2615360000 0.0834110000 0.0724210000 0.0000010000 0.1018310000 0.0018880000 116859627 0 402718720 3.7606287003 3.2747681141 6.8165292740 1085 43.3600000000 1.8778430223 0.1705282825 1.9930224419 0.0260524929 0.4341990000 0.0851440000 0.1082850000 0.0288600000 0.1018440000 0.1080520000 116862403 0 402718720 3.7608950138 3.2755796909 6.8191208839 1086 43.4000000000 1.8755259514 0.1720982619 1.9930224419 0.0260414456 0.2992490000 0.0852890000 0.1081330000 0.0000010000 0.1019130000 0.0018930000 116865179 0 402718720 3.7613453865 3.2770907879 6.8182015419 1087 43.4400000000 1.8760892153 0.1736658709 1.9930224419 0.0260300590 0.3291290000 0.0857120000 0.1082550000 0.0293930000 0.1018520000 0.0019050000 116867955 0 402718720 3.7616920471 3.2787222862 6.8210339546 1088 43.4800000000 1.8714200258 0.1752263067 1.9930224419 0.0260197084 0.2991420000 0.0859760000 0.1076060000 0.0000010000 0.1016400000 0.0019010000 116870731 0 402718720 3.7621729374 3.2802431583 6.8174386024 1089 43.5200000000 1.8657603264 0.1767786795 1.9930224419 0.0260101965 0.4303900000 0.0952170000 0.0946520000 0.0293660000 0.1014740000 0.1076820000 116873507 0 402718720 3.7628827095 3.2810173035 6.8134078979 1090 43.5600000000 1.8644981384 0.1783270460 1.9930224419 0.0259993570 0.3001470000 0.0864950000 0.1082770000 0.0000000000 0.1014700000 0.0019060000 116876283 0 402718720 3.7636647224 3.2820093632 6.8136682510 1091 43.6000000000 1.8690439463 0.1798767407 1.9930224419 0.0259885008 0.3287010000 0.0869830000 0.1079090000 0.0286370000 0.1012580000 0.0019030000 116879059 0 402718720 3.7643721104 3.2836160660 6.8206095695 1092 43.6400000000 1.8757770061 0.1814297629 1.9930224419 0.0259793545 0.3002190000 0.0875260000 0.1076580000 0.0000010000 0.1011230000 0.0018890000 116881835 0 402718720 3.7650802135 3.2854545116 6.8309049606 1093 43.6800000000 1.8803523779 0.1829841294 1.9930224419 0.0259696213 0.4347570000 0.0880120000 0.1075240000 0.0285180000 0.1012440000 0.1074420000 116884611 0 402718720 3.7657489777 3.2862107754 6.8385658264 1094 43.7200000000 1.8806874752 0.1845359606 1.9930224419 0.0259587067 0.3247710000 0.1119160000 0.1074420000 0.0000000000 0.1014970000 0.0018870000 116887387 0 402718720 3.7663953304 3.2880580425 6.8415536880 1095 43.7600000000 1.8786389828 0.1860830867 1.9930224419 0.0259479333 0.3434980000 0.1019600000 0.1075240000 0.0284560000 0.1016520000 0.0019050000 116890163 0 402718720 3.7669227123 3.2900588512 6.8427567482 1096 43.8000000000 1.8749207258 0.1876239969 1.9930224419 0.0259375369 0.3029190000 0.0899110000 0.1073240000 0.0000010000 0.1017460000 0.0018890000 116892939 0 402718720 3.7675592899 3.2906203270 6.8413200378 1097 43.8400000000 1.8713475466 0.1891588406 1.9930224419 0.0259268010 0.4381600000 0.0905870000 0.1071890000 0.0283880000 0.1019270000 0.1080650000 116895715 0 402718720 3.7681746483 3.2918436527 6.8401799202 1098 43.8800000000 1.8675498962 0.1906874300 1.9930224419 0.0259162797 0.2865300000 0.0910850000 0.0894440000 0.0000000000 0.1020470000 0.0019070000 116898491 0 402718720 3.7688169479 3.2930469513 6.8383917809 1099 43.9200000000 1.8627455235 0.1922088659 1.9930224419 0.0259062117 0.3505420000 0.1033560000 0.1123530000 0.0284110000 0.1024760000 0.0019050000 116901267 0 402718720 3.7694535255 3.2945227623 6.8349180222 1100 43.9600000000 1.8588062525 0.1937239544 1.9930224419 0.0258960467 0.3059930000 0.0923410000 0.1068880000 0.0000010000 0.1028010000 0.0018850000 116904043 0 402718720 3.7701566219 3.2967603207 6.8335494995 1101 44.0000000000 1.8552350998 0.1952330472 1.9930224419 0.0258867107 0.4420400000 0.0923190000 0.1070700000 0.0282480000 0.1031000000 0.1092650000 116906819 0 402718720 3.7708020210 3.2976715565 6.8317251205 1102 44.0400000000 1.8489620686 0.1967337087 1.9930224419 0.0258793078 0.3081530000 0.0937530000 0.1070730000 0.0000010000 0.1033710000 0.0018870000 116909595 0 402718720 3.7714323997 3.2985506058 6.8276910782 1103 44.0800000000 1.8413451910 0.1982247436 1.9930224419 0.0258713757 0.3372020000 0.0945220000 0.1068740000 0.0281940000 0.1036750000 0.0018990000 116912371 0 402718720 3.7721948624 3.3005466461 6.8223500252 1104 44.1200000000 1.8171885014 0.1996911963 1.9930224419 0.0258797267 0.3100740000 0.0951950000 0.1065630000 0.0000010000 0.1043630000 0.0018960000 116915147 0 402718720 3.7730047703 3.3000416756 6.7982177734 1105 44.1600000000 1.8047820330 0.2011437672 1.9930224419 0.0258744594 0.4496540000 0.0959150000 0.1077080000 0.0282010000 0.1048400000 0.1109680000 116917923 0 402718720 3.7738444805 3.2988977432 6.7866983414 1106 44.2000000000 1.8045579195 0.2025935087 1.9930224419 0.0258633407 0.3131930000 0.0964960000 0.1077410000 0.0000010000 0.1049940000 0.0018870000 116920699 0 402718720 3.7745442390 3.3006124496 6.7890076637 1107 44.2400000000 1.7856047153 0.2040235098 1.9930224419 0.0258636912 0.3424490000 0.0972380000 0.1073720000 0.0281670000 0.1057140000 0.0019210000 116923475 0 402718720 3.7752251625 3.2992446423 6.7699952126 1108 44.2800000000 1.7975991964 0.2054617550 1.9930224419 0.0258565364 0.3149160000 0.0979760000 0.1075140000 0.0000000000 0.1054740000 0.0018880000 116926251 0 402718720 3.7756218910 3.3014688492 6.7854886055 1109 44.3200000000 1.7733092308 0.2068755039 1.9930224419 0.0258647139 0.4688870000 0.1074250000 0.1119110000 0.0287650000 0.1062740000 0.1124430000 116929027 0 402718720 3.7763195038 3.3006742001 6.7609605789 1110 44.3600000000 1.7671163082 0.2082811262 1.9930224419 0.0258550989 0.3483140000 0.1254940000 0.1120570000 0.0000010000 0.1068500000 0.0018410000 116931803 0 402718720 3.7772281170 3.3007261753 6.7555561066 1111 44.4000000000 1.7574300766 0.2096754997 1.9930224419 0.0258476432 0.3477210000 0.0997810000 0.1080850000 0.0286900000 0.1071970000 0.0019120000 116934579 0 402718720 3.7779304981 3.2998411655 6.7468400002 1112 44.4400000000 1.7542817593 0.2110645341 1.9930224419 0.0258368637 0.3125620000 0.1003850000 0.1006950000 0.0000010000 0.1075140000 0.0018940000 116937355 0 402718720 3.7786035538 3.3008308411 6.7454099655 1113 44.4800000000 1.7550905943 0.2124517992 1.9930224419 0.0258257716 0.4429620000 0.1007890000 0.0898860000 0.0286350000 0.1077710000 0.1138250000 116940131 0 402718720 3.7792961597 3.3017437458 6.7483925819 1114 44.5200000000 1.7533684969 0.2138350279 1.9930224419 0.0258152033 0.3030960000 0.1014170000 0.0895930000 0.0000010000 0.1081950000 0.0018260000 116942907 0 402718720 3.7800414562 3.3016097546 6.7486939430 1115 44.5600000000 1.7543728352 0.2152166761 1.9930224419 0.0258045492 0.3492270000 0.1018020000 0.1073620000 0.0279160000 0.1081540000 0.0019120000 116945683 0 402718720 3.7807848454 3.3002388477 6.7508578300 1116 44.6000000000 1.7591310740 0.2166001120 1.9930224419 0.0257941844 0.3215670000 0.1023810000 0.1067630000 0.0000010000 0.1084430000 0.0018930000 116948459 0 402718720 3.7813329697 3.2989089489 6.7572436333 1117 44.6400000000 1.7591406107 0.2179810793 1.9930224419 0.0257836242 0.4625600000 0.1029050000 0.1064870000 0.0284570000 0.1082780000 0.1143690000 116951235 0 402718720 3.7820281982 3.3002209663 6.7594227791 1118 44.6800000000 1.7608627081 0.2193611165 1.9930224419 0.0257737121 0.3347780000 0.1161340000 0.1061370000 0.0000000000 0.1085300000 0.0019000000 116954011 0 402718720 3.7828223705 3.2975528240 6.7630963326 1119 44.7200000000 1.7598880529 0.2207378162 1.9930224419 0.0257668752 0.3839600000 0.1326020000 0.1106150000 0.0283810000 0.1082180000 0.0019830000 116956787 0 402718720 3.7833476067 3.2982878685 6.7649364471 1120 44.7600000000 1.7617399693 0.2221137110 1.9930224419 0.0257584413 0.3250290000 0.1043880000 0.1082260000 0.0000010000 0.1084140000 0.0019080000 116959563 0 402718720 3.7840008736 3.2977588177 6.7698497772 1121 44.8000000000 1.7658752203 0.2234908399 1.9930224419 0.0257480613 0.4615390000 0.1046840000 0.1043520000 0.0282600000 0.1080450000 0.1141260000 116962339 0 402718720 3.7846658230 3.2988357544 6.7769007683 1122 44.8400000000 1.7695419788 0.2248687821 1.9930224419 0.0257388062 0.3300940000 0.1022470000 0.1036840000 0.0000000000 0.1191280000 0.0026540000 116965115 0 402718720 3.7854475975 3.3004128933 6.7843208313 1123 44.8800000000 1.7730693817 0.2262474113 1.9930224419 0.0257283257 0.3580860000 0.1155810000 0.1033670000 0.0274290000 0.1077210000 0.0019220000 116967891 0 402718720 3.7862005234 3.3006856441 6.7914624214 1124 44.9200000000 1.7779964209 0.2276279709 1.9930224419 0.0257176199 0.2947490000 0.1055880000 0.0774450000 0.0000010000 0.1077450000 0.0018920000 116970667 0 402718720 3.7869901657 3.3016452789 6.7994627953 1125 44.9600000000 1.7819647789 0.2290096036 1.9930224419 0.0257071984 0.4610330000 0.1336710000 0.0776120000 0.0271510000 0.1073580000 0.1131440000 116973443 0 402718720 3.7877180576 3.3030605316 6.8062577248 1126 45.0000000000 1.7869489193 0.2303932087 1.9930224419 0.0256968660 0.3242910000 0.1060530000 0.1069670000 0.0000010000 0.1071160000 0.0019840000 116976219 0 402718720 3.7884798050 3.3046579361 6.8149051666 1127 45.0400000000 1.7926506996 0.2317794177 1.9930224419 0.0256875421 0.3463510000 0.1063950000 0.1014760000 0.0278100000 0.1066660000 0.0019100000 116978995 0 402718720 3.7892477512 3.3061819077 6.8237562180 1128 45.0800000000 1.8051865101 0.2331742821 1.9930224419 0.0256810389 0.3173910000 0.1065670000 0.1007720000 0.0000000000 0.1060490000 0.0018920000 116981771 0 402718720 3.7897796631 3.3083257675 6.8403859138 1129 45.1200000000 1.8222752810 0.2345818118 1.9930224419 0.0256776448 0.4713070000 0.1215040000 0.1048210000 0.0276500000 0.1045790000 0.1105650000 116984547 0 402718720 3.7901332378 3.3129634857 6.8628497124 1130 45.1600000000 1.8383461237 0.2360010722 1.9930224419 0.0256725816 0.3136690000 0.1040220000 0.1021660000 0.0000000000 0.1033600000 0.0019210000 116987323 0 402718720 3.7906155586 3.3152894974 6.8822975159 1131 45.2000000000 1.8409308195 0.2374201083 1.9930224419 0.0256626201 0.3395780000 0.1072910000 0.0979510000 0.0274160000 0.1029320000 0.0019070000 116990099 0 402718720 3.7916367054 3.3154556751 6.8877639771 1132 45.2400000000 1.8435163498 0.2388389212 1.9930224419 0.0256535408 0.3112830000 0.1074760000 0.0974110000 0.0000010000 0.1023840000 0.0018930000 116992875 0 402718720 3.7924563885 3.3176128864 6.8928565979 1133 45.2800000000 1.8447223902 0.2402562941 1.9930224419 0.0256437435 0.4195790000 0.1076900000 0.0730690000 0.0266140000 0.1021590000 0.1079510000 116995651 0 402718720 3.7934062481 3.3185844421 6.8958964348 1134 45.3200000000 1.8467381001 0.2416729447 1.9930224419 0.0256340418 0.2782990000 0.1077600000 0.0648450000 0.0000000000 0.1016690000 0.0018880000 116998427 0 402718720 3.7945144176 3.3200900555 6.8998665810 1135 45.3600000000 1.8473650217 0.2430876514 1.9930224419 0.0256263264 0.3198870000 0.1080280000 0.0801390000 0.0264810000 0.1012300000 0.0019060000 117001203 0 402718720 3.7957780361 3.3204424381 6.9039897919 1136 45.4000000000 1.8483775854 0.2445007587 1.9930224419 0.0256172280 0.3084370000 0.1081870000 0.0955400000 0.0000010000 0.1007020000 0.0018880000 117003979 0 402718720 3.7968585491 3.3212165833 6.9070048332 1137 45.4400000000 1.8493920565 0.2459122726 1.9930224419 0.0256103837 0.4384320000 0.1083840000 0.0948870000 0.0270470000 0.1001330000 0.1058680000 117006755 0 402718720 3.7981173992 3.3211081028 6.9120440483 1138 45.4800000000 1.8495371342 0.2473214333 1.9930224419 0.0256013468 0.2834830000 0.1085250000 0.0711500000 0.0000000000 0.0997840000 0.0018960000 117009531 0 402718720 3.7999463081 3.3194634914 6.9127817154 1139 45.5200000000 1.8500546217 0.2487285739 1.9930224419 0.0255958898 0.4124830000 0.1397620000 0.1311520000 0.0303820000 0.1071770000 0.0019080000 117012307 0 402718720 3.8014061451 3.3209474087 6.9132099152 1140 45.5600000000 1.8506500721 0.2501337682 1.9930224419 0.0255878327 0.3057100000 0.1087890000 0.0934840000 0.0000010000 0.0993840000 0.0019120000 117015083 0 402718720 3.8033068180 3.3202064037 6.9151153564 1141 45.6000000000 1.8518557549 0.2515375561 1.9930224419 0.0255807161 0.4586300000 0.1283050000 0.0973010000 0.0268590000 0.0991330000 0.1048220000 117017859 0 402718720 3.8051431179 3.3229460716 6.9172387123 1142 45.6400000000 1.8525068760 0.2529394557 1.9930224419 0.0255728966 0.3065460000 0.1091380000 0.0947370000 0.0000010000 0.0986410000 0.0018880000 117020635 0 402718720 3.8070108891 3.3233547211 6.9188899994 1143 45.6800000000 1.8524929285 0.2543388901 1.9930224419 0.0255655426 0.3304420000 0.1093080000 0.0918350000 0.0267320000 0.0985080000 0.0019080000 117023411 0 402718720 3.8083591461 3.3299982548 6.9188675880 1144 45.7200000000 1.8520458937 0.2557354871 1.9930224419 0.0255572391 0.3031880000 0.1094460000 0.0915380000 0.0000010000 0.0981660000 0.0018940000 117026187 0 402718720 3.8099906445 3.3356080055 6.9192032814 1145 45.7600000000 1.8543964624 0.2571316975 1.9930224419 0.0255489239 0.3919050000 0.1096350000 0.0538590000 0.0258280000 0.0974350000 0.1029930000 117028963 0 402718720 3.8119270802 3.3312001228 6.9237809181 1146 45.8000000000 1.8551386595 0.2585261190 1.9930224419 0.0255434832 0.3068300000 0.1225460000 0.0830210000 0.0000010000 0.0972220000 0.0018970000 117031739 0 402718720 3.8133003712 3.3379919529 6.9231357574 1147 45.8400000000 1.8560807705 0.2599189304 1.9930224419 0.0255377235 0.3272890000 0.1098300000 0.0904100000 0.0257630000 0.0972400000 0.0019190000 117034515 0 402718720 3.8153560162 3.3376541138 6.9236063957 1148 45.8800000000 1.8607559204 0.2613133877 1.9930224419 0.0255317591 0.3005340000 0.1099770000 0.0899770000 0.0000010000 0.0965360000 0.0019190000 117037291 0 402718720 3.8173649311 3.3328521252 6.9270906448 1149 45.9200000000 1.8667429686 0.2627106284 1.9930224419 0.0255324894 0.4392250000 0.1182850000 0.0942360000 0.0264270000 0.0962470000 0.1018630000 117040067 0 402718720 3.8193984032 3.3244872093 6.9287023544 1150 45.9600000000 1.8961380720 0.2641310001 1.9930224419 0.0255929717 0.3047340000 0.1229980000 0.0834270000 0.0000010000 0.0942500000 0.0019240000 117042843 0 402718720 3.8216388226 3.2640614510 6.9378261566 1151 46.0000000000 1.8968833685 0.2655495512 1.9930224419 0.0255856504 0.3210350000 0.1102870000 0.0871540000 0.0255270000 0.0940000000 0.0019150000 117045619 0 402718720 3.8233754635 3.2643768787 6.9387984276 1152 46.0400000000 1.9073436260 0.2669747197 1.9930224419 0.0255853827 0.2946590000 0.1103630000 0.0874960000 0.0000010000 0.0927090000 0.0019130000 117048395 0 402718720 3.8255677223 3.2433719635 6.9433770180 1153 46.0800000000 1.9263300896 0.2684138831 1.9930224419 0.0256019729 0.4120100000 0.1105280000 0.0870050000 0.0253930000 0.0907860000 0.0960850000 117051171 0 402718720 3.8274226189 3.2112386227 6.9491534233 1154 46.1200000000 1.9377259016 0.2698604273 1.9930224419 0.0256004727 0.2884710000 0.1105960000 0.0851820000 0.0000010000 0.0886470000 0.0019040000 117053947 0 402718720 3.8297555447 3.1931259632 6.9555702209 1155 46.1600000000 1.9459927082 0.2713116240 1.9930224419 0.0255963314 0.3115920000 0.1107170000 0.0840990000 0.0252990000 0.0874250000 0.0019340000 117056723 0 402718720 3.8323190212 3.1785473824 6.9601140022 1156 46.2000000000 1.9534496069 0.2727667607 1.9930224419 0.0255894927 0.2840820000 0.1107930000 0.0831800000 0.0000010000 0.0860510000 0.0018980000 117059499 0 402718720 3.8349611759 3.1656336784 6.9640927315 1157 46.2400000000 1.9615138769 0.2742263520 1.9930224419 0.0255828628 0.3964820000 0.1108390000 0.0825680000 0.0259830000 0.0848880000 0.0900320000 117062275 0 402718720 3.8379895687 3.1511890888 6.9682946205 1158 46.2800000000 1.9713706970 0.2756919343 1.9930224419 0.0255803295 0.3104410000 0.1349890000 0.0875890000 0.0000010000 0.0836040000 0.0019880000 117065051 0 402718720 3.8408079147 3.1347889900 6.9726490974 1159 46.3200000000 1.9796019793 0.2771620897 1.9930224419 0.0255774109 0.3234160000 0.1250900000 0.0853010000 0.0259450000 0.0830180000 0.0019110000 117067827 0 402718720 3.8437578678 3.1232287884 6.9764800072 1160 46.3600000000 1.9849327803 0.2786343058 1.9930224419 0.0255703284 0.2743260000 0.1076770000 0.0802610000 0.0000010000 0.0823510000 0.0018950000 117070603 0 402718720 3.8472023010 3.1173717976 6.9807906151 1161 46.4000000000 1.9816840887 0.2801011876 1.9930224419 0.0255612420 0.3935870000 0.1111470000 0.0834780000 0.0259880000 0.0827500000 0.0880640000 117073379 0 402718720 3.8507401943 3.1239345074 6.9838142395 1162 46.4400000000 1.9629317522 0.2815494067 1.9930224419 0.0255649650 0.2796450000 0.1111460000 0.0795720000 0.0000000000 0.0848760000 0.0019060000 117076155 0 402718720 3.8547911644 3.1638216972 6.9838991165 1163 46.4800000000 1.9726306200 0.2830034748 1.9930224419 0.0255640808 0.2849760000 0.1112580000 0.0611300000 0.0251370000 0.0833730000 0.0019170000 117078931 0 402718720 3.8553545475 3.1444323063 6.9867753983 1164 46.5200000000 1.8148837090 0.2843195231 1.9930224419 0.0260156200 0.2973990000 0.1113150000 0.0785290000 0.0000000000 0.1034690000 0.0019070000 117081707 0 402718720 3.8671858311 3.2921686172 6.8848333359 1165 46.5600000000 1.6601037979 0.2855004538 1.9930224419 0.0267817696 0.4698040000 0.1075570000 0.0807280000 0.0268890000 0.1235630000 0.1288900000 117084483 0 402718720 3.8699433804 3.2540602684 6.6948328018 1166 46.6000000000 1.5364748240 0.2865733306 1.9930224419 0.0272011279 0.3364460000 0.1114410000 0.0848650000 0.0000010000 0.1360460000 0.0019160000 117087259 0 402718720 3.8769629002 3.2420325279 6.5461668968 1167 46.6400000000 1.2510659695 0.2873998025 1.9930224419 0.0298119478 0.3857380000 0.1115580000 0.0813780000 0.0287420000 0.1599480000 0.0019350000 117090035 0 402718720 3.8846688271 3.2083361149 6.1735506058 1168 46.6800000000 1.0915589333 0.2880882949 1.9930224419 0.0315999798 0.3946680000 0.1111850000 0.0935420000 0.0000010000 0.1858340000 0.0019390000 117092811 0 402718720 3.8964250088 3.1344208717 5.8575172424 1169 46.7200000000 1.0910239220 0.2887751517 1.9930224419 0.0315881011 0.6114650000 0.1215750000 0.1010470000 0.0299730000 0.1751880000 0.1815330000 117095587 0 402718720 3.9006936550 3.1355981827 5.8603835106 1170 46.7600000000 1.0920594931 0.2894617195 1.9930224419 0.0315783706 0.3812070000 0.1116470000 0.0875980000 0.0000010000 0.1778240000 0.0019430000 117098363 0 402718720 3.9026856422 3.1329314709 5.8610582352 1171 46.8000000000 1.0915434361 0.2901466740 1.9930224419 0.0315674451 0.4058630000 0.1116990000 0.0826560000 0.0293050000 0.1779090000 0.0020370000 117101139 0 402718720 3.9045164585 3.1311433315 5.8631305695 1172 46.8400000000 1.0920138359 0.2908308610 1.9930224419 0.0315560037 0.3835670000 0.1117650000 0.0871510000 0.0000010000 0.1805240000 0.0019320000 117103915 0 402718720 3.9060616493 3.1278867722 5.8637366295 1173 46.8800000000 1.0932930708 0.2915149720 1.9930224419 0.0315459668 0.6182710000 0.1117830000 0.1044430000 0.0298670000 0.1819840000 0.1880480000 117106691 0 402718720 3.9076282978 3.1263558865 5.8641715050 1174 46.9200000000 1.0932624340 0.2921978915 1.9930224419 0.0315346031 0.3557570000 0.1079220000 0.0601330000 0.0000000000 0.1836230000 0.0018750000 117109467 0 402718720 3.9092545509 3.1246275902 5.8653030396 1175 46.9600000000 1.0942912102 0.2928805241 1.9930224419 0.0315253128 0.4295290000 0.1079620000 0.1028270000 0.0298530000 0.1847640000 0.0019470000 117112243 0 402718720 3.9103219509 3.1225192547 5.8657908440 1176 47.0000000000 1.0957125425 0.2935632044 1.9930224419 0.0315153727 0.3712850000 0.1119500000 0.0690820000 0.0000000000 0.1861140000 0.0019390000 117115019 0 402718720 3.9116282463 3.1188027859 5.8665423393 1177 47.0400000000 1.0970388651 0.2942458515 1.9930224419 0.0315052144 0.5842490000 0.1118550000 0.0604310000 0.0291690000 0.1873360000 0.1932970000 117117795 0 402718720 3.9130020142 3.1172854900 5.8682918549 1178 47.0800000000 1.0985172987 0.2949285947 1.9930224419 0.0314948594 0.4066900000 0.1118720000 0.1023450000 0.0000000000 0.1883090000 0.0019380000 117120571 0 402718720 3.9143440723 3.1159670353 5.8683772087 1179 47.1200000000 1.0987772942 0.2956104002 1.9930224419 0.0314827606 0.4325810000 0.1238990000 0.0853170000 0.0297840000 0.1894470000 0.0019480000 117123347 0 402718720 3.9158983231 3.1156408787 5.8690857887 1180 47.1600000000 1.1004364491 0.2962924561 1.9930224419 0.0314710908 0.4121820000 0.1118940000 0.1068950000 0.0000010000 0.1892610000 0.0019400000 117126123 0 402718720 3.9173700809 3.1129150391 5.8695240021 1181 47.2000000000 1.1012508869 0.2969740467 1.9930224419 0.0314590824 0.6294900000 0.1080080000 0.1004220000 0.0296250000 0.1918080000 0.1974480000 117128899 0 402718720 3.9190933704 3.1124186516 5.8707590103 1182 47.2400000000 1.1030821800 0.2976560333 1.9930224419 0.0314487371 0.3803350000 0.1080110000 0.0754930000 0.0000010000 0.1927640000 0.0018740000 117131675 0 402718720 3.9203169346 3.1102313995 5.8717770576 1183 47.2800000000 1.1023186445 0.2983362214 1.9930224419 0.0314357811 0.4072160000 0.1119250000 0.0679040000 0.0297550000 0.1934890000 0.0019560000 117134451 0 402718720 3.9217886925 3.1102318764 5.8727984428 1184 47.3200000000 1.1023312807 0.2990152713 1.9930224419 0.0314227394 0.4097470000 0.1100880000 0.1009850000 0.0000000000 0.1945310000 0.0019380000 117137227 0 402718720 3.9228165150 3.1094872952 5.8730711937 1185 47.3600000000 1.1034758091 0.2996941410 1.9930224419 0.0314108192 0.6418370000 0.1121150000 0.1007250000 0.0297100000 0.1955620000 0.2015370000 117140003 0 402718720 3.9239511490 3.1071047783 5.8740344048 1186 47.4000000000 1.1054829359 0.3003735582 1.9930224419 0.0314004327 0.4303150000 0.1255150000 0.1052030000 0.0000010000 0.1952090000 0.0020480000 117142779 0 402718720 3.9248347282 3.1059193611 5.8738059998 1187 47.4400000000 1.1066207886 0.3010527892 1.9930224419 0.0313884972 0.4423800000 0.1081170000 0.1034180000 0.0296360000 0.1970590000 0.0019460000 117145555 0 402718720 3.9259860516 3.1050477028 5.8744206429 1188 47.4800000000 1.1055244207 0.3017299539 1.9930224419 0.0313756862 0.3898130000 0.1120850000 0.0754050000 0.0000000000 0.1981580000 0.0019390000 117148331 0 402718720 3.9268443584 3.1045131683 5.8749508858 1189 47.5200000000 1.1034988165 0.3024042759 1.9930224419 0.0313624837 0.6382580000 0.1251300000 0.0771230000 0.0294800000 0.1993860000 0.2049470000 117151107 0 402718720 3.9277245998 3.1035490036 5.8756847382 1190 47.5600000000 1.1057040691 0.3030793177 1.9930224419 0.0313509206 0.3831170000 0.1121160000 0.0668320000 0.0000000000 0.1999840000 0.0019450000 117153883 0 402718720 3.9287350178 3.1011726856 5.8759398460 1191 47.6000000000 1.1079008579 0.3037550705 1.9930224419 0.0313391466 0.4462420000 0.1121840000 0.0993700000 0.0296040000 0.2009270000 0.0019490000 117156659 0 402718720 3.9292426109 3.0987532139 5.8769178391 1192 47.6400000000 1.1087667942 0.3044304159 1.9930224419 0.0313268393 0.4010480000 0.1121980000 0.0827840000 0.0000000000 0.2018980000 0.0019510000 117159435 0 402718720 3.9293656349 3.0965495110 5.8770108223 1193 47.6800000000 1.1115615368 0.3051069717 1.9930224419 0.0313162771 0.6540940000 0.1122130000 0.0988560000 0.0288730000 0.2029970000 0.2089260000 117162211 0 402718720 3.9294600487 3.0943474770 5.8771286011 1194 47.7200000000 1.1125059128 0.3057831852 1.9930224419 0.0313055349 0.3703520000 0.1122620000 0.0499700000 0.0000010000 0.2039590000 0.0019420000 117164987 0 402718720 3.9296438694 3.0927054882 5.8770852089 1195 47.7600000000 1.1134580374 0.3064590638 1.9930224419 0.0312950758 0.4403650000 0.1122100000 0.0901320000 0.0288400000 0.2050140000 0.0019570000 117167763 0 402718720 3.9299290180 3.0918836594 5.8781008720 1196 47.8000000000 1.1131916046 0.3071335893 1.9930224419 0.0312854854 0.4084050000 0.1083790000 0.0898180000 0.0000000000 0.2060390000 0.0019400000 117170539 0 402718720 3.9297614098 3.0922317505 5.8776235580 1197 47.8400000000 1.1142146587 0.3078078425 1.9930224419 0.0312748679 0.6542010000 0.1122690000 0.0896780000 0.0294810000 0.2073200000 0.2132390000 117173315 0 402718720 3.9299504757 3.0894131660 5.8785734177 1198 47.8800000000 1.1143686771 0.3084810986 1.9930224419 0.0312625314 0.3822370000 0.1123640000 0.0573080000 0.0000010000 0.2083700000 0.0019470000 117176091 0 402718720 3.9301557541 3.0863339901 5.8787236214 1199 47.9200000000 1.1189426184 0.3091570465 1.9930224419 0.0312545195 0.4499890000 0.1310110000 0.0767720000 0.0294700000 0.2083420000 0.0020520000 117178867 0 402718720 3.9298794270 3.0826623440 5.8797221184 1200 47.9600000000 1.1222448349 0.3098346197 1.9930224419 0.0312485642 0.4057840000 0.1084040000 0.0833810000 0.0000010000 0.2098240000 0.0019430000 117181643 0 402718720 3.9295470715 3.0781099796 5.8799371719 1201 48.0000000000 1.1263710260 0.3105145001 1.9930224419 0.0312406370 0.6702030000 0.1123290000 0.0961250000 0.0293790000 0.2121400000 0.2180300000 117184419 0 402718720 3.9302930832 3.0742657185 5.8816566467 1202 48.0400000000 1.1278893948 0.3111945125 1.9930224419 0.0312296540 0.4604920000 0.1113280000 0.1271290000 0.0000010000 0.2178510000 0.0019440000 117187195 0 402718720 3.9306125641 3.0712578297 5.8817934990 1203 48.0800000000 1.1311743259 0.3118761250 1.9930224419 0.0312194528 0.4164660000 0.1123690000 0.0563100000 0.0293260000 0.2142880000 0.0019620000 117189971 0 402718720 3.9308369160 3.0682036877 5.8824839592 1204 48.1200000000 1.1291419268 0.3125549172 1.9930224419 0.0312080645 0.4308940000 0.1239520000 0.0875520000 0.0000010000 0.2151690000 0.0019470000 117192747 0 402718720 3.9314134121 3.0693256855 5.8813323975 1205 48.1600000000 1.1273398399 0.3132310872 1.9930224419 0.0311965749 0.6779060000 0.1124310000 0.0951960000 0.0292870000 0.2164420000 0.2223230000 117195523 0 402718720 3.9316635132 3.0699942112 5.8800091743 1206 48.2000000000 1.1278277636 0.3139065405 1.9930224419 0.0311874062 0.3819890000 0.1123640000 0.0482120000 0.0000010000 0.2171930000 0.0019540000 117198299 0 402718720 3.9316735268 3.0679373741 5.8792834282 1207 48.2400000000 1.2075524330 0.3146469265 1.9930224419 0.0316047704 0.4667980000 0.1123760000 0.1004860000 0.0297820000 0.2199600000 0.0019600000 117201075 0 402718720 3.9332709312 2.9869978428 5.9025969505 1208 48.2800000000 1.2054615021 0.3153843558 1.9930224419 0.0315941413 0.3963900000 0.1084610000 0.0627130000 0.0000010000 0.2210580000 0.0018810000 117203851 0 402718720 3.9346215725 2.9883332253 5.9022521973 1209 48.3200000000 1.2063709497 0.3161213174 1.9930224419 0.0315868554 0.6744430000 0.1220310000 0.0711480000 0.0297250000 0.2216890000 0.2276310000 117206627 0 402718720 3.9360151291 2.9876093864 5.9026675224 1210 48.3600000000 1.2068719864 0.3168574750 1.9930224419 0.0315782735 0.3974300000 0.1123890000 0.0583780000 0.0000010000 0.2224470000 0.0019500000 117209403 0 402718720 3.9376251698 2.9869887829 5.9034657478 1211 48.4000000000 1.2078090906 0.3175931906 1.9930224419 0.0315697752 0.4639480000 0.1124230000 0.0940120000 0.0296940000 0.2236300000 0.0019530000 117212179 0 402718720 3.9398334026 2.9848072529 5.9048686028 1212 48.4400000000 1.2057189941 0.3183259677 1.9930224419 0.0315681945 0.4298480000 0.1085140000 0.0920140000 0.0000000000 0.2251070000 0.0019490000 117214955 0 402718720 3.9428999424 2.9858243465 5.9047713280 1213 48.4800000000 1.2074139118 0.3190589339 1.9930224419 0.0315575289 0.7118930000 0.1252510000 0.0932550000 0.0296390000 0.2263000000 0.2349030000 117217731 0 402718720 3.9448499680 2.9841995239 5.9055652618 1214 48.5200000000 1.2063131332 0.3197897857 1.9930224419 0.0315468940 0.5112300000 0.1450000000 0.1298460000 0.0000010000 0.2321580000 0.0019450000 117220507 0 402718720 3.9470834732 2.9852149487 5.9054079056 1215 48.5600000000 1.2052886486 0.3205185914 1.9930224419 0.0315396405 0.4362940000 0.1124000000 0.0621470000 0.0289750000 0.2285730000 0.0019580000 117223283 0 402718720 3.9485678673 2.9852068424 5.9052891731 1216 48.6000000000 1.2080550194 0.3212484733 1.9930224419 0.0315357107 0.4383060000 0.1123510000 0.0921250000 0.0000010000 0.2296120000 0.0019420000 117226059 0 402718720 3.9512662888 2.9812417030 5.9075112343 1217 48.6400000000 1.2070499659 0.3219763299 1.9930224419 0.0315283562 0.6976680000 0.1084500000 0.0904720000 0.0287360000 0.2310260000 0.2367440000 117228835 0 402718720 3.9533820152 2.9828841686 5.9063429832 1218 48.6800000000 1.2067768574 0.3227027672 1.9930224419 0.0315227177 0.4173300000 0.1122710000 0.0690410000 0.0000000000 0.2318070000 0.0019460000 117231611 0 402718720 3.9557526112 2.9830963612 5.9067630768 1219 48.7200000000 1.2073404789 0.3234284749 1.9930224419 0.0315149264 0.4833030000 0.1225570000 0.0955450000 0.0295440000 0.2312430000 0.0020470000 117234387 0 402718720 3.9580345154 2.9821043015 5.9080543518 1220 48.7600000000 1.2053136826 0.3241513316 1.9930224419 0.0315065346 0.4177100000 0.1332880000 0.0462790000 0.0000010000 0.2338730000 0.0019490000 117237163 0 402718720 3.9608197212 2.9831871986 5.9078035355 1221 48.8000000000 1.2012025118 0.3248696372 1.9930224419 0.0315027669 0.7133570000 0.1120870000 0.0951220000 0.0294280000 0.2335960000 0.2408740000 117239939 0 402718720 3.9635169506 2.9852271080 5.9081730843 1222 48.8400000000 1.1986942291 0.3255847146 1.9930224419 0.0314965406 0.4156160000 0.1119290000 0.0637740000 0.0000020000 0.2356660000 0.0019430000 117242715 0 402718720 3.9665701389 2.9884240627 5.9072375298 1223 48.8800000000 1.1954412460 0.3262959628 1.9930224419 0.0314920671 0.4450410000 0.1081050000 0.0670530000 0.0284820000 0.2372310000 0.0018970000 117245491 0 402718720 3.9683666229 2.9915075302 5.9063544273 1224 48.9200000000 1.1953669786 0.3270059882 1.9930224419 0.0314859418 0.4268350000 0.1246410000 0.0603170000 0.0000000000 0.2376560000 0.0019450000 117248267 0 402718720 3.9710786343 2.9920008183 5.9063148499 1225 48.9600000000 1.1914829016 0.3277116836 1.9930224419 0.0314796914 0.7161110000 0.1116640000 0.0893650000 0.0292390000 0.2388580000 0.2447430000 117251043 0 402718720 3.9739212990 2.9954190254 5.9061832428 1226 49.0000000000 1.1925108433 0.3284170663 1.9930224419 0.0314736437 0.4353740000 0.1242000000 0.0673450000 0.0000000000 0.2395920000 0.0019460000 117253819 0 402718720 3.9766199589 2.9946153164 5.9066104889 1227 49.0400000000 1.1905007362 0.3291196610 1.9930224419 0.0314660035 0.4743590000 0.1114620000 0.0888110000 0.0291930000 0.2406760000 0.0019540000 117256595 0 402718720 3.9797437191 2.9968669415 5.9069981575 1228 49.0800000000 1.1876600981 0.3298187981 1.9930224419 0.0314574800 0.4455920000 0.1113210000 0.0885340000 0.0000010000 0.2414920000 0.0019490000 117259371 0 402718720 3.9823715687 2.9996359348 5.9068326950 1229 49.1200000000 1.1888446808 0.3305177614 1.9930224419 0.0314495324 0.7367830000 0.1211760000 0.0925020000 0.0292000000 0.2428610000 0.2487790000 117262147 0 402718720 3.9853334427 2.9986474514 5.9078488350 1230 49.1600000000 1.1879059076 0.3312148249 1.9930224419 0.0314418813 0.4112350000 0.1111290000 0.0520690000 0.0000010000 0.2438040000 0.0019470000 117264923 0 402718720 3.9872267246 2.9990665913 5.9075136185 1231 49.2000000000 1.1850686073 0.3319084511 1.9930224419 0.0314313985 0.4992520000 0.1300470000 0.0922540000 0.0291630000 0.2433450000 0.0020460000 117267699 0 402718720 3.9893059731 3.0030860901 5.9061441422 1232 49.2400000000 1.1891114712 0.3326042328 1.9930224419 0.0314238281 0.4496390000 0.1111560000 0.0878300000 0.0000000000 0.2464060000 0.0019520000 117270475 0 402718720 3.9914767742 2.9996151924 5.9075493813 1233 49.2800000000 1.1879205704 0.3332979200 1.9930224419 0.0314130253 0.7319250000 0.1112740000 0.0873720000 0.0291340000 0.2479950000 0.2538830000 117273251 0 402718720 3.9938206673 3.0010645390 5.9074606895 1234 49.3200000000 1.1919404268 0.3339937405 1.9930224419 0.0314045845 0.4729430000 0.1303130000 0.0913390000 0.0000010000 0.2468120000 0.0020480000 117276027 0 402718720 3.9957981110 2.9963855743 5.9088859558 1235 49.3600000000 1.1936715841 0.3346898359 1.9930224419 0.0313984035 0.4815870000 0.1113940000 0.0863620000 0.0291470000 0.2504370000 0.0019620000 117278803 0 402718720 3.9982995987 2.9949409962 5.9099397659 1236 49.4000000000 1.1886130571 0.3353807123 1.9930224419 0.0313948965 0.4557100000 0.1114360000 0.0906560000 0.0000010000 0.2491500000 0.0019670000 117281579 0 402718720 3.9994618893 2.9992890358 5.9082736969 1237 49.4400000000 1.1889994144 0.3360707840 1.9930224419 0.0313909284 0.7050420000 0.1114510000 0.0508820000 0.0291270000 0.2526810000 0.2586260000 117284355 0 402718720 4.0015439987 3.0003981590 5.9082164764 1238 49.4800000000 1.1834292412 0.3367552416 1.9930224419 0.0313879194 0.4552810000 0.1114990000 0.0856600000 0.0000010000 0.2538520000 0.0019520000 117287131 0 402718720 4.0030784607 3.0071918964 5.9055681229 1239 49.5200000000 1.1854429245 0.3374402195 1.9930224419 0.0313906097 0.4744520000 0.1116680000 0.0750250000 0.0291210000 0.2543800000 0.0019540000 117289907 0 402718720 4.0051751137 3.0057108402 5.9065170288 1240 49.5600000000 1.1794861555 0.3381192888 1.9930224419 0.0313872340 0.4527270000 0.1079760000 0.0839960000 0.0000010000 0.2564690000 0.0019560000 117292683 0 402718720 4.0064001083 3.0101959705 5.9057183266 1241 49.6000000000 1.1790314913 0.3387968974 1.9930224419 0.0313796498 0.7447800000 0.1079710000 0.0837730000 0.0284180000 0.2581900000 0.2641410000 117295459 0 402718720 4.0093431473 3.0111463070 5.9050574303 1242 49.6400000000 1.1753108501 0.3394704191 1.9930224419 0.0313692264 0.4776060000 0.1274070000 0.0886620000 0.0000000000 0.2572280000 0.0019540000 117298235 0 402718720 4.0094609261 3.0162069798 5.9038424492 1243 49.6800000000 1.1744599342 0.3401421725 1.9930224419 0.0313579233 0.4910430000 0.1115260000 0.0852180000 0.0290490000 0.2610020000 0.0019620000 117301011 0 402718720 4.0114407539 3.0169219971 5.9041209221 1244 49.7200000000 1.1697155237 0.3408090321 1.9930224419 0.0313454374 0.4620310000 0.1114530000 0.0842310000 0.0000010000 0.2621430000 0.0018840000 117303787 0 402718720 4.0123167038 3.0229401588 5.9021472931 1245 49.7600000000 1.1694208384 0.3414745838 1.9930224419 0.0313329661 0.7595810000 0.1113550000 0.0836720000 0.0283520000 0.2639720000 0.2699480000 117306563 0 402718720 4.0134611130 3.0246567726 5.9008150101 1246 49.8000000000 1.1624948978 0.3421335086 1.9930224419 0.0313218680 0.4642610000 0.1112490000 0.0839230000 0.0000010000 0.2648050000 0.0019570000 117309339 0 402718720 4.0130605698 3.0318694115 5.8988947868 1247 49.8400000000 1.1597876549 0.3427892056 1.9930224419 0.0313098677 0.4945180000 0.1112130000 0.0832970000 0.0290530000 0.2666900000 0.0019560000 117312115 0 402718720 4.0134634972 3.0353527069 5.8966522217 1248 49.8800000000 1.1549550295 0.3434399795 1.9930224419 0.0312984243 0.4661820000 0.1111560000 0.0833190000 0.0000000000 0.2674130000 0.0019550000 117314891 0 402718720 4.0129723549 3.0408022404 5.8948473930 1249 49.9200000000 1.1545352936 0.3440893752 1.9930224419 0.0312860153 0.7644270000 0.1075210000 0.0814960000 0.0281570000 0.2696910000 0.2752560000 117317667 0 402718720 4.0138978958 3.0403327942 5.8941750526 1250 49.9600000000 1.1470243931 0.3447317232 1.9930224419 0.0312740145 0.4631560000 0.1075310000 0.0816190000 0.0000000000 0.2697050000 0.0019580000 117320443 0 402718720 4.0125102997 3.0493853092 5.8907871246 1251 50.0000000000 1.1481556892 0.3453739486 1.9930224419 0.0312619117 0.5123260000 0.1238370000 0.0838700000 0.0289880000 0.2713490000 0.0019640000 117323219 0 402718720 4.0137038231 3.0502061844 5.8896875381 1252 50.0400000000 1.1372772455 0.3460064592 1.9930224419 0.0312498685 0.4654050000 0.1076130000 0.0815070000 0.0000000000 0.2719970000 0.0019500000 117325995 0 402718720 4.0099310875 3.0618991852 5.8850855827 1253 50.0800000000 1.1331321001 0.3466346521 1.9930224419 0.0312376577 0.7950180000 0.1251090000 0.0863390000 0.0289870000 0.2727920000 0.2794790000 117328771 0 402718720 4.0100574493 3.0669751167 5.8833417892 1254 50.1200000000 1.1213686466 0.3472524623 1.9930224419 0.0312258022 0.4747560000 0.1111480000 0.0864680000 0.0000020000 0.2728540000 0.0019570000 117331547 0 402718720 4.0078392029 3.0800244808 5.8804020882 1255 50.1600000000 1.1331161261 0.3478786485 1.9930224419 0.0312181881 0.5009100000 0.1111870000 0.0813240000 0.0283680000 0.2757580000 0.0019660000 117334323 0 402718720 4.0100450516 3.0684823990 5.8833208084 1256 50.2000000000 1.1139024496 0.3484885400 1.9930224419 0.0312080081 0.4744480000 0.1112160000 0.0815560000 0.0000000000 0.2773930000 0.0019500000 117337099 0 402718720 4.0069084167 3.0886328220 5.8775739670 1257 50.2400000000 1.1394603252 0.3491177937 1.9930224419 0.0312094059 0.7866100000 0.1112240000 0.0810650000 0.0290650000 0.2785340000 0.2843950000 117339875 0 402718720 4.0118184090 3.0632205009 5.8862166405 1258 50.2800000000 1.1392912865 0.3497459125 1.9930224419 0.0311975391 0.4759580000 0.1111520000 0.0815100000 0.0000010000 0.2789850000 0.0019530000 117342651 0 402718720 4.0076656342 3.0644929409 5.8831334114 1259 50.3200000000 1.1401618719 0.3503737250 1.9930224419 0.0311860120 0.5159140000 0.1212090000 0.0807550000 0.0284080000 0.2812250000 0.0019610000 117345427 0 402718720 4.0085277557 3.0639770031 5.8823304176 1260 50.3600000000 1.1379207373 0.3509987623 1.9930224419 0.0311753508 0.4821170000 0.1112360000 0.0858080000 0.0000010000 0.2805780000 0.0020460000 117348203 0 402718720 4.0038414001 3.0677297115 5.8783740997 1261 50.4000000000 1.1350347996 0.3516205197 1.9930224419 0.0311638718 0.8181170000 0.1242810000 0.0850180000 0.0290510000 0.2857410000 0.2917180000 117350979 0 402718720 4.0001249313 3.0699901581 5.8742818832 1262 50.4400000000 1.1307823658 0.3522379221 1.9930224419 0.0311518274 0.4969360000 0.1110710000 0.0846860000 0.0000010000 0.2969690000 0.0018860000 117353755 0 402718720 3.9924619198 3.0744369030 5.8679261208 1263 50.4800000000 1.1333928108 0.3528564137 1.9930224419 0.0311405210 0.5344120000 0.1302380000 0.0840300000 0.0290330000 0.2865980000 0.0020490000 117356531 0 402718720 3.9886362553 3.0728852749 5.8645558357 1264 50.5200000000 1.1314376593 0.3534723799 1.9930224419 0.0311286705 0.4850180000 0.1109610000 0.0792780000 0.0000010000 0.2904850000 0.0019400000 117359307 0 402718720 3.9839169979 3.0755238533 5.8616557121 1265 50.5600000000 1.1319397688 0.3540877691 1.9930224419 0.0311177319 0.8074580000 0.1108950000 0.0760050000 0.0290520000 0.2913080000 0.2978860000 117362083 0 402718720 3.9840538502 3.0741949081 5.8611431122 1266 50.6000000000 1.1308963299 0.3547013620 1.9930224419 0.0311061669 0.4673280000 0.1108190000 0.0595400000 0.0000000000 0.2926520000 0.0019440000 117364859 0 402718720 3.9820330143 3.0759198666 5.8584818840 1267 50.6400000000 1.1285097599 0.3553121026 1.9930224419 0.0310942811 0.5179270000 0.1107190000 0.0784680000 0.0283730000 0.2960790000 0.0019460000 117367635 0 402718720 3.9795796871 3.0802350044 5.8546566963 1268 50.6800000000 1.1252356768 0.3559192979 1.9930224419 0.0310841881 0.4920230000 0.1105380000 0.0780490000 0.0000010000 0.2991060000 0.0019490000 117370411 0 402718720 3.9778587818 3.0841217041 5.8505783081 1269 50.7200000000 1.1299690008 0.3565292661 1.9930224419 0.0310740706 0.8352550000 0.1190320000 0.0816050000 0.0291570000 0.2978640000 0.3052660000 117373187 0 402718720 3.9755947590 3.0792336464 5.8495073318 1270 50.7600000000 1.1327127218 0.3571404342 1.9930224419 0.0310627632 0.4792200000 0.1101200000 0.0651910000 0.0000010000 0.2995170000 0.0019330000 117375963 0 402718720 3.9758324623 3.0769832134 5.8486371040 1271 50.8000000000 1.1355233192 0.3577528519 1.9930224419 0.0310541937 0.4911630000 0.1098910000 0.0774910000 0.0000010000 0.2995150000 0.0019350000 117378739 0 402718720 3.9758324623 3.0769832134 5.8486371040 1272 50.8400000000 1.1368216276 0.3583653273 1.9930224419 0.0310452628 0.4990890000 0.1062750000 0.0765780000 0.0000000000 0.3108600000 0.0026920000 117381515 0 402718720 3.9758324623 3.0769832134 5.8486371040 1273 50.8800000000 1.1387141943 0.3589783272 1.9930224419 0.0310358458 0.8437370000 0.1420530000 0.0940850000 0.0000010000 0.2994860000 0.3057680000 117384291 0 402718720 3.9758324623 3.0769832134 5.8486371040 1274 50.9200000000 1.1414834261 0.3595925384 1.9930224419 0.0310269582 0.4934160000 0.1095180000 0.0821770000 0.0000010000 0.2974170000 0.0019350000 117387067 0 402718720 3.9758324623 3.0769832134 5.8486371040 1275 50.9600000000 1.1420935392 0.3602062647 1.9930224419 0.0310176615 0.4951270000 0.1094280000 0.0820270000 0.0000010000 0.2993620000 0.0019420000 117389843 0 402718720 3.9758324623 3.0769832134 5.8486371040 1276 51.0000000000 1.1428931952 0.3608196557 1.9930224419 0.0310079239 0.4865250000 0.1060850000 0.0766820000 0.0000010000 0.2994280000 0.0019340000 117392619 0 402718720 3.9758324623 3.0769832134 5.8486371040 1277 51.0400000000 1.1428159475 0.3614320256 1.9930224419 0.0309982316 0.7947920000 0.1096100000 0.0776170000 0.0000010000 0.2994490000 0.3057720000 117395395 0 402718720 3.9758324623 3.0769832134 5.8486371040 1278 51.0800000000 1.1428679228 0.3620434778 1.9930224419 0.0309882882 0.4887380000 0.1096980000 0.0752840000 0.0000000000 0.2994530000 0.0019320000 117398171 0 402718720 3.9758324623 3.0769832134 5.8486371040 1279 51.1200000000 1.1426613331 0.3626538123 1.9930224419 0.0309779543 0.5111030000 0.1183360000 0.0899130000 0.0000010000 0.2985500000 0.0019370000 117400947 0 402718720 3.9758324623 3.0769832134 5.8486371040 1280 51.1600000000 1.1424480677 0.3632630266 1.9930224419 0.0309669285 0.4902250000 0.1100100000 0.0764160000 0.0000010000 0.2994810000 0.0019390000 117403723 0 402718720 3.9758324623 3.0769832134 5.8486371040 1281 51.2000000000 1.1460661888 0.3638741141 1.9930224419 0.0309556393 0.7937840000 0.1100590000 0.0760700000 0.0000000000 0.2994400000 0.3058240000 117406499 0 402718720 3.9758324623 3.0769832134 5.8486371040 1282 51.2400000000 1.1473760605 0.3644852701 1.9930224419 0.0309442355 0.4920500000 0.1102240000 0.0780370000 0.0000000000 0.2994380000 0.0019400000 117409275 0 402718720 3.9758324623 3.0769832134 5.8486371040 1283 51.2800000000 1.1470814943 0.3650952437 1.9930224419 0.0309328016 0.5136840000 0.1310780000 0.0787930000 0.0000010000 0.2994710000 0.0019410000 117412051 0 402718720 3.9758324623 3.0769832134 5.8486371040 1284 51.3200000000 1.1477694511 0.3657048031 1.9930224419 0.0309213101 0.5005750000 0.1105800000 0.0885140000 0.0000000000 0.2971420000 0.0019370000 117414827 0 402718720 3.9758324623 3.0769832134 5.8486371040 1285 51.3600000000 1.1488627195 0.3663142645 1.9930224419 0.0309099242 0.7962540000 0.1107070000 0.0778480000 0.0000010000 0.2994810000 0.3058400000 117417603 0 402718720 3.9758324623 3.0769832134 5.8486371040 1286 51.4000000000 1.1490523815 0.3669229256 1.9930224419 0.0308989846 0.4937320000 0.1108290000 0.0790670000 0.0000000000 0.2994900000 0.0019460000 117420379 0 402718720 3.9758324623 3.0769832134 5.8486371040 1287 51.4400000000 1.1487442255 0.3675304013 1.9930224419 0.0308875031 0.4934560000 0.1108610000 0.0787690000 0.0000000000 0.2994910000 0.0019350000 117423155 0 402718720 3.9758324623 3.0769832134 5.8486371040 1288 51.4800000000 1.1473296881 0.3681358356 1.9930224419 0.0308762773 0.4921190000 0.1109640000 0.0773670000 0.0000010000 0.2994460000 0.0019330000 117425931 0 402718720 3.9758324623 3.0769832134 5.8486371040 1289 51.5200000000 1.1494594812 0.3687419827 1.9930224419 0.0308649564 0.8126400000 0.1200510000 0.0863660000 0.0000010000 0.2980460000 0.3057720000 117428707 0 402718720 3.9758324623 3.0769832134 5.8486371040 1290 51.5600000000 1.1503683329 0.3693478946 1.9930224419 0.0308534629 0.4899140000 0.1111430000 0.0749370000 0.0000010000 0.2994750000 0.0019290000 117431483 0 402718720 3.9758324623 3.0769832134 5.8486371040 1291 51.6000000000 1.1506507397 0.3699530866 1.9930224419 0.0308421381 0.4887630000 0.1110950000 0.0738630000 0.0000000000 0.2994480000 0.0019320000 117434259 0 402718720 3.9758324623 3.0769832134 5.8486371040 1292 51.6400000000 1.1514303684 0.3705579451 1.9930224419 0.0308307736 0.4880580000 0.1110020000 0.0731950000 0.0000010000 0.2995290000 0.0019310000 117437035 0 402718720 3.9758324623 3.0769832134 5.8486371040 1293 51.6800000000 1.1525413990 0.3711627274 1.9930224419 0.0308193511 0.7954330000 0.1148250000 0.0729220000 0.0000010000 0.2994680000 0.3058150000 117439811 0 402718720 3.9758324623 3.0769832134 5.8486371040 1294 51.7200000000 1.1522879601 0.3717663790 1.9930224419 0.0308081794 0.4879350000 0.1109290000 0.0731510000 0.0000010000 0.2994780000 0.0019310000 117442587 0 402718720 3.9758324623 3.0769832134 5.8486371040 1295 51.7600000000 1.1519672871 0.3723688508 1.9930224419 0.0307968992 0.4965440000 0.1109230000 0.0836950000 0.0000000000 0.2975870000 0.0019350000 117445363 0 402718720 3.9758324623 3.0769832134 5.8486371040 1296 51.8000000000 1.1542803049 0.3729721775 1.9930224419 0.0307868773 0.4919310000 0.1107070000 0.0773310000 0.0000010000 0.2995210000 0.0019360000 117448139 0 402718720 3.9758324623 3.0769832134 5.8486371040 1297 51.8400000000 1.1537601948 0.3735741729 1.9930224419 0.0307751408 0.7964190000 0.1107470000 0.0779610000 0.0000010000 0.2994790000 0.3058300000 117450915 0 402718720 3.9758324623 3.0769832134 5.8486371040 1298 51.8800000000 1.1567424536 0.3741775383 1.9930224419 0.0307634928 0.4931340000 0.1107730000 0.0784760000 0.0000000000 0.2994720000 0.0019370000 117453691 0 402718720 3.9758324623 3.0769832134 5.8486371040 1299 51.9200000000 1.1584997177 0.3747813275 1.9930224419 0.0307518579 0.5052940000 0.1225780000 0.0788790000 0.0000010000 0.2994880000 0.0019340000 117456467 0 402718720 3.9758324623 3.0769832134 5.8486371040 1300 51.9600000000 1.1598773003 0.3753852475 1.9930224419 0.0307402268 0.4943290000 0.1110550000 0.0794100000 0.0000010000 0.2994900000 0.0019330000 117459243 0 402718720 3.9758324623 3.0769832134 5.8486371040 1301 52.0000000000 1.1619317532 0.3759898182 1.9930224419 0.0307285587 0.7980100000 0.1105900000 0.0797950000 0.0000010000 0.2994540000 0.3057510000 117462019 0 402718720 3.9758324623 3.0769832134 5.8486371040 1302 52.0400000000 1.1657437086 0.3765963880 1.9930224419 0.0307178430 0.4947640000 0.1111820000 0.0797770000 0.0000000000 0.2994390000 0.0019340000 117464795 0 402718720 3.9758324623 3.0769832134 5.8486371040 1303 52.0800000000 1.1705681086 0.3772057293 1.9930224419 0.0307079777 0.5099530000 0.1257620000 0.0803810000 0.0000010000 0.2994540000 0.0019350000 117467571 0 402718720 3.9758324623 3.0769832134 5.8486371040 1304 52.1200000000 1.1726465225 0.3778157299 1.9930224419 0.0306968997 0.5054240000 0.1112320000 0.0903490000 0.0000010000 0.2994610000 0.0019330000 117470347 0 402718720 3.9758324623 3.0769832134 5.8486371040 1305 52.1600000000 1.1757707596 0.3784271897 1.9930224419 0.0306855526 0.7991090000 0.1111310000 0.0803290000 0.0000010000 0.2994780000 0.3057530000 117473123 0 402718720 3.9758324623 3.0769832134 5.8486371040 1306 52.2000000000 1.1802910566 0.3790411743 1.9930224419 0.0306741810 0.4959460000 0.1110780000 0.0809810000 0.0000010000 0.2994830000 0.0019340000 117475899 0 402718720 3.9758324623 3.0769832134 5.8486371040 1307 52.2400000000 1.1838244200 0.3796569228 1.9930224419 0.0306629382 0.4943900000 0.1099790000 0.0802300000 0.0000010000 0.2998090000 0.0019360000 117478675 0 402718720 3.9758324623 3.0769832134 5.8486371040 1308 52.2800000000 1.1866177320 0.3802738653 1.9930224419 0.0306515200 0.4958050000 0.1109850000 0.0809960000 0.0000010000 0.2994480000 0.0019330000 117481451 0 402718720 3.9758324623 3.0769832134 5.8486371040 1309 52.3200000000 1.1895222664 0.3808920841 1.9930224419 0.0306398993 0.8047090000 0.1109030000 0.0882600000 0.0000000000 0.2973560000 0.3057730000 117484227 0 402718720 3.9758324623 3.0769832134 5.8486371040 1310 52.3600000000 1.1921522617 0.3815113667 1.9930224419 0.0306287999 0.4926470000 0.1106490000 0.0781780000 0.0000010000 0.2994460000 0.0019340000 117487003 0 402718720 3.9758324623 3.0769832134 5.8486371040 1311 52.4000000000 1.1971470118 0.3821335144 1.9930224419 0.0306180489 0.4929780000 0.1104900000 0.0786930000 0.0000000000 0.2994240000 0.0019380000 117489779 0 402718720 3.9758324623 3.0769832134 5.8486371040 1312 52.4400000000 1.2034361362 0.3827595072 1.9930224419 0.0306070445 0.5060980000 0.1230490000 0.0791640000 0.0000000000 0.2995040000 0.0019430000 117492555 0 402718720 3.9758324623 3.0769832134 5.8486371040 1313 52.4800000000 1.2091244459 0.3833888788 1.9930224419 0.0305958982 0.8111780000 0.1238190000 0.0797010000 0.0000010000 0.2994590000 0.3057440000 117495331 0 402718720 3.9758324623 3.0769832134 5.8486371040 1314 52.5200000000 1.2163567543 0.3840227966 1.9930224419 0.0305852261 0.4993300000 0.1102410000 0.0852810000 0.0000010000 0.2993940000 0.0019280000 117498107 0 402718720 3.9758324623 3.0769832134 5.8486371040 1315 52.5600000000 1.2235312462 0.3846612060 1.9930224419 0.0305743030 0.4853630000 0.1069260000 0.0739780000 0.0000000000 0.3001520000 0.0018650000 117500883 0 402718720 3.9758324623 3.0769832134 5.8486371040 1316 52.6000000000 1.2298974991 0.3853034828 1.9930224419 0.0305630724 0.4894520000 0.1108000000 0.0748170000 0.0000010000 0.2994380000 0.0019280000 117503659 0 402718720 3.9758324623 3.0769832134 5.8486371040 1317 52.6400000000 1.2378003597 0.3859507849 1.9930224419 0.0305521621 0.8070040000 0.1111390000 0.0748630000 0.0000010000 0.3000520000 0.3185120000 117506435 0 402718720 3.9758324623 3.0769832134 5.8486371040 1318 52.6800000000 1.2463680506 0.3866036053 1.9930224419 0.0305414310 0.4907470000 0.1113060000 0.0755950000 0.0000000000 0.2994680000 0.0019290000 117509211 0 402718720 3.9758324623 3.0769832134 5.8486371040 1319 52.7200000000 1.2546931505 0.3872617475 1.9930224419 0.0305304422 0.5036550000 0.1221800000 0.0776010000 0.0000010000 0.2994750000 0.0019370000 117511987 0 402718720 3.9758324623 3.0769832134 5.8486371040 1320 52.7600000000 1.2638926506 0.3879258618 1.9930224419 0.0305195917 0.4901720000 0.1115630000 0.0747070000 0.0000000000 0.2995080000 0.0019340000 117514763 0 402718720 3.9758324623 3.0769832134 5.8486371040 1321 52.8000000000 1.2751177549 0.3885974681 1.9930224419 0.0305095371 0.7962830000 0.1115810000 0.0770400000 0.0000010000 0.2994740000 0.3057420000 117517539 0 402718720 3.9758324623 3.0769832134 5.8486371040 1322 52.8400000000 1.2843990326 0.3892750790 1.9930224419 0.0304986533 0.4922070000 0.1116380000 0.0766840000 0.0000000000 0.2994860000 0.0019360000 117520315 0 402718720 3.9758324623 3.0769832134 5.8486371040 1323 52.8800000000 1.2934427261 0.3899585012 1.9930224419 0.0304877894 0.4921550000 0.1115790000 0.0767070000 0.0000010000 0.2994620000 0.0019360000 117523091 0 402718720 3.9758324623 3.0769832134 5.8486371040 1324 52.9200000000 1.3053421974 0.3906498787 1.9930224419 0.0304780159 0.4818670000 0.1116440000 0.0663490000 0.0000010000 0.2994630000 0.0019220000 117525867 0 402718720 3.9758324623 3.0769832134 5.8486371040 1325 52.9600000000 1.3164653778 0.3913486073 1.9930224419 0.0304680877 0.7899110000 0.1116950000 0.0705490000 0.0000010000 0.2994610000 0.3057730000 117528643 0 402718720 3.9758324623 3.0769832134 5.8486371040 1326 53.0000000000 1.3271646500 0.3920543510 1.9930224419 0.0304580428 0.4919900000 0.1117120000 0.0764050000 0.0000010000 0.2994400000 0.0019350000 117531419 0 402718720 3.9758324623 3.0769832134 5.8486371040 1327 53.0400000000 1.3377664089 0.3927670202 1.9930224419 0.0304477211 0.4996390000 0.1117960000 0.0764970000 0.0000010000 0.3058700000 0.0026880000 117534195 0 402718720 3.9758324623 3.0769832134 5.8486371040 1328 53.0800000000 1.3500494957 0.3934878654 1.9930224419 0.0304385309 0.5587850000 0.1441250000 0.1058830000 0.0000000000 0.3043710000 0.0019320000 117536971 0 402718720 3.9758324623 3.0769832134 5.8486371040 1329 53.1200000000 1.3591060638 0.3942144404 1.9930224419 0.0304279346 0.8075830000 0.1220380000 0.0826490000 0.0000000000 0.2969950000 0.3034520000 117539747 0 402718720 3.9758324623 3.0769832134 5.8486371040 1330 53.1600000000 1.3675105572 0.3949462420 1.9930224419 0.0304171921 0.4968130000 0.1082580000 0.0865390000 0.0000010000 0.2975750000 0.0019320000 117542523 0 402718720 3.9758324623 3.0769832134 5.8486371040 1331 53.2000000000 1.3801114559 0.3956864112 1.9930224419 0.0304088499 0.4851890000 0.1083600000 0.0729240000 0.0000010000 0.2995090000 0.0019250000 117545299 0 402718720 3.9758324623 3.0769832134 5.8486371040 1332 53.2400000000 1.3937293291 0.3964356927 1.9930224419 0.0304007523 0.5024080000 0.1254110000 0.0731250000 0.0000000000 0.2994530000 0.0019250000 117548075 0 402718720 3.9758324623 3.0769832134 5.8486371040 1333 53.2800000000 1.4045327902 0.3971919546 1.9930224419 0.0303904809 0.8315630000 0.1398260000 0.0838620000 0.0000010000 0.2996140000 0.3057840000 117550851 0 402718720 3.9758324623 3.0769832134 5.8486371040 1334 53.3200000000 1.4151554108 0.3979550456 1.9930224419 0.0303807401 0.4998910000 0.1123900000 0.0835290000 0.0000010000 0.2995390000 0.0019340000 117553627 0 402718720 3.9758324623 3.0769832134 5.8486371040 1335 53.3600000000 1.4258643389 0.3987250151 1.9930224419 0.0303709971 0.5116700000 0.1250920000 0.0825800000 0.0000010000 0.2995670000 0.0019340000 117556403 0 402718720 3.9758324623 3.0769832134 5.8486371040 1336 53.4000000000 1.4353994131 0.3995009690 1.9930224419 0.0303605686 0.4989500000 0.1123610000 0.0826040000 0.0000010000 0.2995420000 0.0019350000 117559179 0 402718720 3.9758324623 3.0769832134 5.8486371040 1337 53.4400000000 1.4433344603 0.4002816972 1.9930224419 0.0303495921 0.8024350000 0.1124150000 0.0822090000 0.0000000000 0.2995580000 0.3057800000 117561955 0 402718720 3.9758324623 3.0769832134 5.8486371040 1338 53.4800000000 1.4535173178 0.4010688688 1.9930224419 0.0303392104 0.4984460000 0.1124220000 0.0820020000 0.0000010000 0.2995710000 0.0019340000 117564731 0 402718720 3.9758324623 3.0769832134 5.8486371040 1339 53.5200000000 1.4661868811 0.4018643266 1.9930224419 0.0303310234 0.5092800000 0.1234040000 0.0842040000 0.0000010000 0.2972000000 0.0019280000 117567507 0 402718720 3.9758324623 3.0769832134 5.8486371040 1340 53.5600000000 1.4852777719 0.4026728441 1.9930224419 0.0303270215 0.4971800000 0.1123440000 0.0808420000 0.0000010000 0.2995490000 0.0019310000 117570283 0 402718720 3.9758324623 3.0769832134 5.8486371040 1341 53.6000000000 1.4965715408 0.4034885776 1.9930224419 0.0303186616 0.8007850000 0.1124070000 0.0805820000 0.0000010000 0.2994930000 0.3058110000 117573059 0 402718720 3.9758324623 3.0769832134 5.8486371040 1342 53.6400000000 1.5060609579 0.4043101666 1.9930224419 0.0303091779 0.4964560000 0.1123570000 0.0801760000 0.0000010000 0.2994780000 0.0019250000 117575835 0 402718720 3.9758324623 3.0769832134 5.8486371040 1343 53.6800000000 1.5111985207 0.4051343575 1.9930224419 0.0302980833 0.5100040000 0.1251780000 0.0830650000 0.0000000000 0.2973280000 0.0019200000 117578611 0 402718720 3.9758324623 3.0769832134 5.8486371040 1344 53.7200000000 1.5169222355 0.4059615806 1.9930224419 0.0302874323 0.4982870000 0.1122510000 0.0834680000 0.0000010000 0.2980970000 0.0019300000 117581387 0 402718720 3.9758324623 3.0769832134 5.8486371040 1345 53.7600000000 1.5236798525 0.4067925979 1.9930224419 0.0302773862 0.8143030000 0.1250460000 0.0813180000 0.0000000000 0.2996440000 0.3057930000 117584163 0 402718720 3.9758324623 3.0769832134 5.8486371040 1346 53.8000000000 1.5277365446 0.4076253943 1.9930224419 0.0302672755 0.4949390000 0.1119780000 0.0789940000 0.0000000000 0.2995060000 0.0019310000 117586939 0 402718720 3.9758324623 3.0769832134 5.8486371040 1347 53.8400000000 1.5424846411 0.4084679030 1.9930224419 0.0302683733 0.4928790000 0.1115470000 0.0774290000 0.0000000000 0.2994800000 0.0019250000 117589715 0 402718720 3.9758324623 3.0769832134 5.8486371040 1348 53.8800000000 1.5507755280 0.4093153122 1.9930224419 0.0302591944 0.4937110000 0.1114350000 0.0783310000 0.0000000000 0.2994770000 0.0019270000 117592491 0 402718720 3.9758324623 3.0769832134 5.8486371040 1349 53.9200000000 1.5551810265 0.4101647308 1.9930224419 0.0302480817 0.8075680000 0.1229310000 0.0769040000 0.0000010000 0.2994630000 0.3057490000 117595267 0 402718720 3.9758324623 3.0769832134 5.8486371040 1350 53.9600000000 1.5594942570 0.4110160861 1.9930224419 0.0302370186 0.4939780000 0.1113070000 0.0803060000 0.0000010000 0.2979050000 0.0019260000 117598043 0 402718720 3.9758324623 3.0769832134 5.8486371040 1351 54.0000000000 1.5616059303 0.4118677440 1.9930224419 0.0302258896 0.4949890000 0.1112820000 0.0797170000 0.0000010000 0.2995770000 0.0019250000 117600819 0 402718720 3.9758324623 3.0769832134 5.8486371040 1352 54.0400000000 1.5635758638 0.4127195991 1.9930224419 0.0302147124 0.4906150000 0.1102660000 0.0764100000 0.0000010000 0.2994670000 0.0019270000 117603595 0 402718720 3.9758324623 3.0769832134 5.8486371040 1353 54.0800000000 1.5683925152 0.4135737550 1.9930224419 0.0302044767 0.7958040000 0.1113550000 0.0790380000 0.0000000000 0.2971290000 0.3057790000 117606371 0 402718720 3.9758324623 3.0769832134 5.8486371040 1354 54.1200000000 1.5716185570 0.4144290318 1.9930224419 0.0301942728 0.5027450000 0.1232680000 0.0754780000 0.0000010000 0.2995050000 0.0019230000 117609147 0 402718720 3.9758324623 3.0769832134 5.8486371040 1355 54.1600000000 1.5744625330 0.4152851451 1.9930224419 0.0301841734 0.4919900000 0.1115060000 0.0765550000 0.0000010000 0.2995110000 0.0019220000 117611923 0 402718720 3.9758324623 3.0769832134 5.8486371040 1356 54.2000000000 1.5780473948 0.4161426394 1.9930224419 0.0301745849 0.4899240000 0.1115950000 0.0743690000 0.0000010000 0.2994980000 0.0019230000 117614699 0 402718720 3.9758324623 3.0769832134 5.8486371040 1357 54.2400000000 1.5807691813 0.4170008756 1.9930224419 0.0301649960 0.7945850000 0.1116190000 0.0775650000 0.0000010000 0.2970400000 0.3058430000 117617475 0 402718720 3.9758324623 3.0769832134 5.8486371040 1358 54.2800000000 1.5813679695 0.4178582887 1.9930224419 0.0301544769 0.4895770000 0.1117020000 0.0739590000 0.0000010000 0.2994480000 0.0019250000 117620251 0 402718720 3.9758324623 3.0769832134 5.8486371040 1359 54.3200000000 1.5825597048 0.4187153170 1.9930224419 0.0301435349 0.5182630000 0.1393320000 0.0749900000 0.0000000000 0.2994610000 0.0019290000 117623027 0 402718720 3.9758324623 3.0769832134 5.8486371040 1360 54.3600000000 1.5879667997 0.4195750607 1.9930224419 0.0301336640 0.4912060000 0.1118550000 0.0772540000 0.0000010000 0.2976260000 0.0019280000 117625803 0 402718720 3.9758324623 3.0769832134 5.8486371040 1361 54.4000000000 1.5887281895 0.4204341005 1.9930224419 0.0301236492 0.7930590000 0.1117720000 0.0734950000 0.0000000000 0.2994690000 0.3058040000 117628579 0 402718720 3.9758324623 3.0769832134 5.8486371040 1362 54.4400000000 1.5906329155 0.4212932773 1.9930224419 0.0301135106 0.4885930000 0.1117930000 0.0728450000 0.0000010000 0.2994830000 0.0019290000 117631355 0 402718720 3.9758324623 3.0769832134 5.8486371040 1363 54.4800000000 1.5935444832 0.4221533296 1.9930224419 0.0301040069 0.5029900000 0.1248970000 0.0761720000 0.0000010000 0.2974530000 0.0019260000 117634131 0 402718720 3.9758324623 3.0769832134 5.8486371040 1364 54.5200000000 1.5940157175 0.4230124662 1.9930224419 0.0300946312 0.4884070000 0.1117800000 0.0747260000 0.0000010000 0.2973960000 0.0019290000 117636907 0 402718720 3.9758324623 3.0769832134 5.8486371040 1365 54.5600000000 1.5927375555 0.4238694077 1.9930224419 0.0300845185 0.7907990000 0.1119450000 0.0710960000 0.0000010000 0.2994710000 0.3057330000 117639683 0 402718720 3.9758324623 3.0769832134 5.8486371040 1366 54.6000000000 1.5933823586 0.4247255665 1.9930224419 0.0300741984 0.4848260000 0.1097700000 0.0710750000 0.0000010000 0.2995010000 0.0019310000 117642459 0 402718720 3.9758324623 3.0769832134 5.8486371040 1367 54.6400000000 1.5974177122 0.4255834247 1.9930224419 0.0300658577 0.4871110000 0.1121040000 0.0710410000 0.0000010000 0.2994870000 0.0019310000 117645235 0 402718720 3.9758324623 3.0769832134 5.8486371040 1368 54.6800000000 1.5976094007 0.4264401688 1.9930224419 0.0300564511 0.4949810000 0.1121100000 0.0788840000 0.0000010000 0.2994780000 0.0019340000 117648011 0 402718720 3.9758324623 3.0769832134 5.8486371040 1369 54.7200000000 1.5996993780 0.4272971880 1.9930224419 0.0300470898 0.8232840000 0.1341080000 0.0813410000 0.0000010000 0.2995460000 0.3057320000 117650787 0 402718720 3.9758324623 3.0769832134 5.8486371040 1370 54.7600000000 1.6040979624 0.4281561666 1.9930224419 0.0300384455 0.4874370000 0.1122010000 0.0712540000 0.0000010000 0.2994520000 0.0019440000 117653563 0 402718720 3.9758324623 3.0769832134 5.8486371040 1371 54.8000000000 1.6065533161 0.4290156832 1.9930224419 0.0300291654 0.4902930000 0.1121730000 0.0745940000 0.0000000000 0.2990390000 0.0019280000 117656339 0 402718720 3.9758324623 3.0769832134 5.8486371040 1372 54.8400000000 1.6115859747 0.4298776149 1.9930224419 0.0300209220 0.4836290000 0.1121630000 0.0658110000 0.0000000000 0.3000280000 0.0026850000 117659115 0 402718720 3.9758324623 3.0769832134 5.8486371040 1373 54.8800000000 1.6146049500 0.4307404898 1.9930224419 0.0300134191 0.8581860000 0.1445090000 0.1057950000 0.0000000000 0.2995690000 0.3057550000 117661891 0 402718720 3.9758324623 3.0769832134 5.8486371040 1374 54.9200000000 1.6157299280 0.4316029276 1.9930224419 0.0300054777 0.4847970000 0.1121180000 0.0687140000 0.0000010000 0.2994640000 0.0019330000 117664667 0 402718720 3.9758324623 3.0769832134 5.8486371040 1375 54.9600000000 1.6182035208 0.4324659098 1.9930224419 0.0299977373 0.4829170000 0.1122340000 0.0666950000 0.0000000000 0.2994890000 0.0019330000 117667443 0 402718720 3.9758324623 3.0769832134 5.8486371040 1376 55.0000000000 1.6211384535 0.4333297707 1.9930224419 0.0299905750 0.4875360000 0.1121420000 0.0713690000 0.0000010000 0.2994800000 0.0019470000 117670219 0 402718720 3.9758324623 3.0769832134 5.8486371040 1377 55.0400000000 1.6235941648 0.4341941602 1.9930224419 0.0299838900 0.7843160000 0.1121770000 0.0643770000 0.0000010000 0.2994530000 0.3057430000 117672995 0 402718720 3.9758324623 3.0769832134 5.8486371040 1378 55.0800000000 1.6250960827 0.4350583851 1.9930224419 0.0299771658 0.4819200000 0.1122450000 0.0650930000 0.0000010000 0.3001340000 0.0018680000 117675771 0 402718720 3.9758324623 3.0769832134 5.8486371040 1379 55.1200000000 1.6273344755 0.4359229798 1.9930224419 0.0299697306 0.4925850000 0.1223820000 0.0662540000 0.0000000000 0.2994630000 0.0019290000 117678547 0 402718720 3.9758324623 3.0769832134 5.8486371040 1380 55.1600000000 1.6310240030 0.4367889950 1.9930224419 0.0299639657 0.4862050000 0.1123470000 0.0698820000 0.0000010000 0.2994380000 0.0019340000 117681323 0 402718720 3.9758324623 3.0769832134 5.8486371040 1381 55.2000000000 1.6333070993 0.4376554093 1.9930224419 0.0299586654 0.8040230000 0.1250840000 0.0711990000 0.0000010000 0.2994550000 0.3057440000 117684099 0 402718720 3.9758324623 3.0769832134 5.8486371040 1382 55.2400000000 1.6347504854 0.4385216141 1.9930224419 0.0299529697 0.4903910000 0.1124820000 0.0659010000 0.0000010000 0.3063960000 0.0026760000 117686875 0 402718720 3.9758324623 3.0769832134 5.8486371040 1383 55.2800000000 1.6387617588 0.4393894667 1.9930224419 0.0299481423 0.5574400000 0.1448390000 0.1035800000 0.0000010000 0.3045050000 0.0019400000 117689651 0 402718720 3.9758324623 3.0769832134 5.8486371040 1384 55.3200000000 1.6412749290 0.4402578811 1.9930224419 0.0299438616 0.4891430000 0.1126250000 0.0725180000 0.0000000000 0.2994820000 0.0019260000 117692427 0 402718720 3.9758324623 3.0769832134 5.8486371040 1385 55.3600000000 1.6441231966 0.4411270979 1.9930224419 0.0299398908 0.7939140000 0.1126610000 0.0733700000 0.0000010000 0.2994810000 0.3058200000 117695203 0 402718720 3.9758324623 3.0769832134 5.8486371040 1386 55.4000000000 1.6470483541 0.4419971710 1.9930224419 0.0299357794 0.4866310000 0.1127400000 0.0699060000 0.0000010000 0.2994590000 0.0019310000 117697979 0 402718720 3.9758324623 3.0769832134 5.8486371040 1387 55.4400000000 1.6480263472 0.4428666945 1.9930224419 0.0299326334 0.4415060000 0.1256620000 0.0119270000 0.0000010000 0.2994640000 0.0019010000 117700755 0 402718720 3.9758324623 3.0769832134 5.8486371040 1388 55.4800000000 1.6482192278 0.4437351041 1.9930224419 0.0299274712 0.4992750000 0.1255540000 0.0697680000 0.0000010000 0.2994470000 0.0019110000 117703531 0 402718720 3.9758324623 3.0769832134 5.8486371040 1389 55.5200000000 1.6494846344 0.4446031744 1.9930224419 0.0299205804 0.7989060000 0.1216550000 0.0694250000 0.0000000000 0.2994700000 0.3057860000 117706307 0 402718720 3.9758324623 3.0769832134 5.8486371040 1390 55.5600000000 1.6512186527 0.4454712431 1.9930224419 0.0299142734 0.4799660000 0.1129860000 0.0637910000 0.0000010000 0.2986640000 0.0019060000 117709083 0 402718720 3.9758324623 3.0769832134 5.8486371040 1391 55.6000000000 1.6539796591 0.4463400485 1.9930224419 0.0299071914 0.4854100000 0.1131310000 0.0682860000 0.0000000000 0.2994720000 0.0019130000 117711859 0 402718720 3.9758324623 3.0769832134 5.8486371040 1392 55.6400000000 1.6551969051 0.4472084802 1.9930224419 0.0298995999 0.4826850000 0.1131700000 0.0655120000 0.0000000000 0.2994680000 0.0019070000 117714635 0 402718720 3.9758324623 3.0769832134 5.8486371040 1393 55.6800000000 1.6566300392 0.4480766938 1.9930224419 0.0298920738 0.8176420000 0.1402670000 0.0694680000 0.0000010000 0.2995150000 0.3057890000 117717411 0 402718720 3.9758324623 3.0769832134 5.8486371040 1394 55.7200000000 1.6572120190 0.4489440792 1.9930224419 0.0298853943 0.4883750000 0.1132390000 0.0733740000 0.0000000000 0.2970020000 0.0019950000 117720187 0 402718720 3.9758324623 3.0769832134 5.8486371040 1395 55.7600000000 1.6575766802 0.4498104825 1.9930224419 0.0298790112 0.4801690000 0.1093670000 0.0668660000 0.0000010000 0.2994360000 0.0019020000 117722963 0 402718720 3.9758324623 3.0769832134 5.8486371040 1396 55.8000000000 1.6604211330 0.4506776821 1.9930224419 0.0298742994 0.4813470000 0.1133250000 0.0640470000 0.0000000000 0.2994730000 0.0018910000 117725739 0 402718720 3.9758324623 3.0769832134 5.8486371040 1397 55.8400000000 1.6605907679 0.4515437617 1.9930224419 0.0298709772 0.7877690000 0.1133530000 0.0665840000 0.0000010000 0.2995200000 0.3057190000 117728515 0 402718720 3.9758324623 3.0769832134 5.8486371040 1398 55.8800000000 1.6605564356 0.4524085776 1.9930224419 0.0298648566 0.4807330000 0.1091740000 0.0669300000 0.0000000000 0.3001480000 0.0018340000 117731291 0 402718720 3.9758324623 3.0769832134 5.8486371040 1399 55.9200000000 1.6620012522 0.4532731899 1.9930224419 0.0298572757 0.4900400000 0.1133490000 0.0727430000 0.0000000000 0.2994730000 0.0018840000 117734067 0 402718720 3.9758324623 3.0769832134 5.8486371040 1400 55.9600000000 1.6649860144 0.4541386991 1.9930224419 0.0298495289 0.4866050000 0.1134230000 0.0691510000 0.0000010000 0.2995190000 0.0018870000 117736843 0 402718720 3.9758324623 3.0769832134 5.8486371040 1401 56.0000000000 1.6662439108 0.4550038706 1.9930224419 0.0298414583 0.7856390000 0.1133760000 0.0645510000 0.0000000000 0.2994350000 0.3056940000 117739619 0 402718720 3.9758324623 3.0769832134 5.8486371040 1402 56.0400000000 1.6663839817 0.4558679077 1.9930224419 0.0298332336 0.4850370000 0.1133680000 0.0676280000 0.0000010000 0.2995130000 0.0018810000 117742395 0 402718720 3.9758324623 3.0769832134 5.8486371040 1403 56.0800000000 1.6668592691 0.4567310520 1.9930224419 0.0298246618 0.5165420000 0.1404640000 0.0725940000 0.0000010000 0.2989730000 0.0018860000 117745171 0 402718720 3.9758324623 3.0769832134 5.8486371040 1404 56.1200000000 1.6695386171 0.4575948750 1.9930224419 0.0298171974 0.4902330000 0.1092020000 0.0766220000 0.0000010000 0.2999280000 0.0018720000 117747947 0 402718720 3.9758324623 3.0769832134 5.8486371040 1405 56.1600000000 1.6711069345 0.4584585847 1.9930224419 0.0298106729 0.7824080000 0.1091890000 0.0702090000 0.0000000000 0.2970170000 0.3032900000 117750723 0 402718720 3.9758324623 3.0769832134 5.8486371040 1406 56.2000000000 1.6762526035 0.4593247255 1.9930224419 0.0298176887 0.4924880000 0.1133830000 0.0751020000 0.0000000000 0.2994840000 0.0018640000 117753499 0 402718720 3.9758324623 3.0769832134 5.8486371040 1407 56.2400000000 1.6800202131 0.4601923129 1.9930224419 0.0298125681 0.4890350000 0.1133520000 0.0717110000 0.0000010000 0.2994740000 0.0018610000 117756275 0 402718720 3.9758324623 3.0769832134 5.8486371040 1408 56.2800000000 1.6807295084 0.4610591717 1.9930224419 0.0298065402 0.4923900000 0.1132580000 0.0751620000 0.0000000000 0.2994400000 0.0018620000 117759051 0 402718720 3.9758324623 3.0769832134 5.8486371040 1409 56.3200000000 1.6810460091 0.4619250247 1.9930224419 0.0297994543 0.8009240000 0.1131930000 0.0810960000 0.0000000000 0.2983490000 0.3056870000 117761827 0 402718720 3.9758324623 3.0769832134 5.8486371040 1410 56.3600000000 1.6855175495 0.4627928208 1.9930224419 0.0297954094 0.4950160000 0.1129220000 0.0775390000 0.0000010000 0.3000640000 0.0018600000 117764603 0 402718720 3.9758324623 3.0769832134 5.8486371040 1411 56.4000000000 1.6879571676 0.4636611159 1.9930224419 0.0297911198 0.5049320000 0.1258850000 0.0750770000 0.0000010000 0.2994780000 0.0018560000 117767379 0 402718720 3.9758324623 3.0769832134 5.8486371040 1412 56.4400000000 1.6877809763 0.4645280563 1.9930224419 0.0297842201 0.4908300000 0.1125450000 0.0742480000 0.0000010000 0.2995450000 0.0018540000 117770155 0 402718720 3.9758324623 3.0769832134 5.8486371040 1413 56.4800000000 1.6914589405 0.4653963726 1.9930224419 0.0297774657 0.7891440000 0.1084250000 0.0726290000 0.0000010000 0.2997470000 0.3056800000 117772931 0 402718720 3.9758324623 3.0769832134 5.8486371040 1414 56.5200000000 1.6964255571 0.4662669731 1.9930224419 0.0297706366 0.4869500000 0.1124860000 0.0704280000 0.0000010000 0.2995110000 0.0018610000 117775707 0 402718720 3.9758324623 3.0769832134 5.8486371040 1415 56.5600000000 1.6995472908 0.4671385493 1.9930224419 0.0297623036 0.4916180000 0.1126450000 0.0750080000 0.0000010000 0.2994560000 0.0018540000 117778483 0 402718720 3.9758324623 3.0769832134 5.8486371040 1416 56.6000000000 1.7044302225 0.4680123429 1.9930224419 0.0297552077 0.4926980000 0.1127790000 0.0759740000 0.0000010000 0.2994420000 0.0018600000 117781259 0 402718720 3.9758324623 3.0769832134 5.8486371040 1417 56.6400000000 1.7085187435 0.4688877885 1.9930224419 0.0297493852 0.7953620000 0.1129550000 0.0746000000 0.0000010000 0.2994680000 0.3056940000 117784035 0 402718720 3.9758324623 3.0769832134 5.8486371040 1418 56.6800000000 1.7118092775 0.4697643198 1.9930224419 0.0297441589 0.4931290000 0.1129920000 0.0761430000 0.0000000000 0.2995010000 0.0018570000 117786811 0 402718720 3.9758324623 3.0769832134 5.8486371040 1419 56.7200000000 1.7145701647 0.4706415614 1.9930224419 0.0297392983 0.5070630000 0.1236860000 0.0794310000 0.0000010000 0.2994380000 0.0018570000 117789587 0 402718720 3.9758324623 3.0769832134 5.8486371040 1420 56.7600000000 1.7182911634 0.4715201879 1.9930224419 0.0297341368 0.4932540000 0.1132320000 0.0754550000 0.0000000000 0.3001180000 0.0018000000 117792363 0 402718720 3.9758324623 3.0769832134 5.8486371040 1421 56.8000000000 1.7206542492 0.4723992407 1.9930224419 0.0297283053 0.7965170000 0.1133350000 0.0752150000 0.0000000000 0.2994750000 0.3058050000 117795139 0 402718720 3.9758324623 3.0769832134 5.8486371040 1422 56.8400000000 1.7237044573 0.4732792022 1.9930224419 0.0297220649 0.5017620000 0.1137570000 0.0862190000 0.0000010000 0.2970330000 0.0019480000 117797915 0 402718720 3.9758324623 3.0769832134 5.8486371040 1423 56.8800000000 1.7278920412 0.4741608697 1.9930224419 0.0297157444 0.5021630000 0.1262380000 0.0719510000 0.0000000000 0.2994890000 0.0018410000 117800691 0 402718720 3.9758324623 3.0769832134 5.8486371040 1424 56.9200000000 1.7318458557 0.4750440755 1.9930224419 0.0297094087 0.4954660000 0.1134010000 0.0785330000 0.0000010000 0.2990120000 0.0018530000 117803467 0 402718720 3.9758324623 3.0769832134 5.8486371040 1425 56.9600000000 1.7318545580 0.4759260477 1.9930224419 0.0297017792 0.8059970000 0.1261680000 0.0720160000 0.0000010000 0.2995030000 0.3056820000 117806243 0 402718720 3.9758324623 3.0769832134 5.8486371040 1426 57.0000000000 1.7344685793 0.4768086161 1.9930224419 0.0296939690 0.4932750000 0.1134050000 0.0781430000 0.0000010000 0.2969840000 0.0019400000 117809019 0 402718720 3.9758324623 3.0769832134 5.8486371040 1427 57.0400000000 1.7382737398 0.4776926141 1.9930224419 0.0296870057 0.4886830000 0.1134360000 0.0712390000 0.0000010000 0.2995160000 0.0018480000 117811795 0 402718720 3.9758324623 3.0769832134 5.8486371040 1428 57.0800000000 1.7406547070 0.4785770413 1.9930224419 0.0296799637 0.5109680000 0.1134240000 0.0759510000 0.0000010000 0.3160030000 0.0025390000 117814571 0 402718720 3.9758324623 3.0769832134 5.8486371040 1429 57.1200000000 1.7438224554 0.4794624475 1.9930224419 0.0296726941 0.8204650000 0.1348870000 0.0777300000 0.0000000000 0.2994870000 0.3057080000 117817347 0 402718720 3.9758324623 3.0769832134 5.8486371040 1430 57.1600000000 1.7470303774 0.4803488587 1.9930224419 0.0296661936 0.4949090000 0.1133960000 0.0785980000 0.0000010000 0.2983620000 0.0018380000 117820123 0 402718720 3.9758324623 3.0769832134 5.8486371040 1431 57.2000000000 1.7485849857 0.4812351173 1.9930224419 0.0296598498 0.4908150000 0.1133930000 0.0734300000 0.0000010000 0.2994720000 0.0018370000 117822899 0 402718720 3.9758324623 3.0769832134 5.8486371040 1432 57.2400000000 1.7508766651 0.4821217385 1.9930224419 0.0296532145 0.5181790000 0.1334060000 0.0809680000 0.0000010000 0.2992890000 0.0018350000 117825675 0 402718720 3.9758324623 3.0769832134 5.8486371040 1433 57.2800000000 1.7541289330 0.4830093918 1.9930224419 0.0296467863 0.7909850000 0.1090470000 0.0786880000 0.0000000000 0.2971540000 0.3034430000 117828451 0 402718720 3.9758324623 3.0769832134 5.8486371040 1434 57.3200000000 1.7564899921 0.4838974536 1.9930224419 0.0296417556 0.4906990000 0.1130060000 0.0736560000 0.0000000000 0.2995030000 0.0018330000 117831227 0 402718720 3.9758324623 3.0769832134 5.8486371040 1435 57.3600000000 1.7590826750 0.4847860844 1.9930224419 0.0296371038 0.4908490000 0.1129340000 0.0739320000 0.0000010000 0.2994840000 0.0018260000 117834003 0 402718720 3.9758324623 3.0769832134 5.8486371040 1436 57.4000000000 1.7621146441 0.4856755890 1.9930224419 0.0296321254 0.5034720000 0.1257410000 0.0737540000 0.0000010000 0.2994650000 0.0018250000 117836779 0 402718720 3.9758324623 3.0769832134 5.8486371040 1437 57.4400000000 1.7650136948 0.4865658730 1.9930224419 0.0296272980 0.7929760000 0.1105010000 0.0746450000 0.0000000000 0.2994580000 0.3057250000 117839555 0 402718720 3.9758324623 3.0769832134 5.8486371040 1438 57.4800000000 1.7704240084 0.4874586811 1.9930224419 0.0296219364 0.5475320000 0.1139670000 0.1115710000 0.0000010000 0.3164100000 0.0025160000 117842331 0 402718720 3.9758324623 3.0769832134 5.8486371040 1439 57.5200000000 1.7770565748 0.4883548576 1.9930224419 0.0296183353 0.5135870000 0.1346890000 0.0749240000 0.0000010000 0.2994750000 0.0018360000 117845107 0 402718720 3.9758324623 3.0769832134 5.8486371040 1440 57.5600000000 1.7808744907 0.4892524406 1.9930224419 0.0296138179 0.4952440000 0.1091190000 0.0844320000 0.0000000000 0.2969800000 0.0019230000 117847883 0 402718720 3.9758324623 3.0769832134 5.8486371040 1441 57.6000000000 1.7839105129 0.4901508848 1.9930224419 0.0296086715 0.7961320000 0.1132930000 0.0749380000 0.0000010000 0.2994880000 0.3057410000 117850659 0 402718720 3.9758324623 3.0769832134 5.8486371040 1442 57.6400000000 1.7890757322 0.4910516649 1.9930224419 0.0296026286 0.4922940000 0.1132480000 0.0750250000 0.0000010000 0.2994760000 0.0018260000 117853435 0 402718720 3.9758324623 3.0769832134 5.8486371040 1443 57.6800000000 1.7928164005 0.4919537888 1.9930224419 0.0295964269 0.4931970000 0.1132550000 0.0757630000 0.0000010000 0.2996730000 0.0017740000 117856211 0 402718720 3.9758324623 3.0769832134 5.8486371040 1444 57.7200000000 1.7939784527 0.4928554679 1.9930224419 0.0295885739 0.4921710000 0.1132010000 0.0749520000 0.0000010000 0.2994520000 0.0018250000 117858987 0 402718720 3.9758324623 3.0769832134 5.8486371040 1445 57.7600000000 1.7971203327 0.4937580733 1.9930224419 0.0295815725 0.7956810000 0.1131390000 0.0741960000 0.0000010000 0.2999410000 0.3056710000 117861763 0 402718720 3.9758324623 3.0769832134 5.8486371040 1446 57.8000000000 1.8022724390 0.4946629934 1.9930224419 0.0295742290 0.4917550000 0.1130850000 0.0745890000 0.0000010000 0.2994850000 0.0018230000 117864539 0 402718720 3.9758324623 3.0769832134 5.8486371040 1447 57.8400000000 1.8033932447 0.4955674372 1.9930224419 0.0295656524 0.4865430000 0.1101130000 0.0724250000 0.0000000000 0.2994820000 0.0018140000 117867315 0 402718720 3.9758324623 3.0769832134 5.8486371040 1448 57.8800000000 1.8044071198 0.4964713320 1.9930224419 0.0295569666 0.4895260000 0.1125910000 0.0728340000 0.0000010000 0.2995210000 0.0018110000 117870091 0 402718720 3.9758324623 3.0769832134 5.8486371040 1449 57.9200000000 1.8072277308 0.4973759258 1.9930224419 0.0295489359 0.8168880000 0.1128940000 0.0788990000 0.0000010000 0.3164170000 0.3059900000 117872867 0 402718720 3.9758324623 3.0769832134 5.8486371040 1450 57.9600000000 1.8100386858 0.4982812105 1.9930224419 0.0295426368 0.4891550000 0.1127750000 0.0723980000 0.0000010000 0.2994580000 0.0018090000 117875643 0 402718720 3.9758324623 3.0769832134 5.8486371040 1451 58.0000000000 1.8120815754 0.4991866552 1.9930224419 0.0295364508 0.5070070000 0.1275090000 0.0754750000 0.0000000000 0.2995070000 0.0018070000 117878419 0 402718720 3.9758324623 3.0769832134 5.8486371040 1452 58.0400000000 1.8146255016 0.5000926049 1.9930224419 0.0295297736 0.4875940000 0.1125260000 0.0710750000 0.0000010000 0.2994590000 0.0018030000 117881195 0 402718720 3.9758324623 3.0769832134 5.8486371040 1453 58.0800000000 1.8170292377 0.5009989618 1.9930224419 0.0295228441 0.7919640000 0.1123130000 0.0717220000 0.0000010000 0.2995110000 0.3056930000 117883971 0 402718720 3.9758324623 3.0769832134 5.8486371040 1454 58.1200000000 1.8176145554 0.5019044746 1.9930224419 0.0295141649 0.4825940000 0.1122500000 0.0663480000 0.0000010000 0.2994590000 0.0017980000 117886747 0 402718720 3.9758324623 3.0769832134 5.8486371040 1455 58.1600000000 1.8183910847 0.5028092764 1.9930224419 0.0295050913 0.4809220000 0.1121250000 0.0646980000 0.0000010000 0.2995610000 0.0018010000 117889523 0 402718720 3.9758324623 3.0769832134 5.8486371040 1456 58.2000000000 1.8189762831 0.5037132372 1.9930224419 0.0294962587 0.4793630000 0.1120260000 0.0632580000 0.0000000000 0.2995020000 0.0017960000 117892299 0 402718720 3.9758324623 3.0769832134 5.8486371040 1457 58.2400000000 1.8211779594 0.5046174683 1.9930224419 0.0294879606 0.7817810000 0.1120610000 0.0618950000 0.0000000000 0.2994770000 0.3056040000 117895075 0 402718720 3.9758324623 3.0769832134 5.8486371040 1458 58.2800000000 1.8237560987 0.5055222274 1.9930224419 0.0294800017 0.4770140000 0.1121680000 0.0608080000 0.0000010000 0.2994890000 0.0017960000 117897851 0 402718720 3.9758324623 3.0769832134 5.8486371040 1459 58.3200000000 1.8246971369 0.5064263911 1.9930224419 0.0294717080 0.4778060000 0.1123520000 0.0614610000 0.0000000000 0.2994570000 0.0017910000 117900627 0 402718720 3.9758324623 3.0769832134 5.8486371040 1460 58.3600000000 1.8250364065 0.5073295486 1.9930224419 0.0294632643 0.4767810000 0.1124870000 0.0602930000 0.0000010000 0.2994500000 0.0017840000 117903403 0 402718720 3.9758324623 3.0769832134 5.8486371040 1461 58.4000000000 1.8263068199 0.5082323394 1.9930224419 0.0294546464 0.7802180000 0.1126260000 0.0597560000 0.0000010000 0.2994780000 0.3055980000 117906179 0 402718720 3.9758324623 3.0769832134 5.8486371040 1462 58.4400000000 1.8269519806 0.5091343364 1.9930224419 0.0294454055 0.5154100000 0.1462440000 0.0649960000 0.0000010000 0.2996130000 0.0017930000 117908955 0 402718720 3.9758324623 3.0769832134 5.8486371040 1463 58.4800000000 1.8281450272 0.5100359158 1.9930224419 0.0294360286 0.4767210000 0.1127250000 0.0599220000 0.0000010000 0.2994410000 0.0017910000 117911731 0 402718720 3.9758324623 3.0769832134 5.8486371040 1464 58.5200000000 1.8291682005 0.5109369625 1.9930224419 0.0294266681 0.4810940000 0.1128140000 0.0664860000 0.0000010000 0.2972200000 0.0017940000 117914507 0 402718720 3.9758324623 3.0769832134 5.8486371040 1465 58.5600000000 1.8299285173 0.5118372980 1.9930224419 0.0294173410 0.7866160000 0.1128410000 0.0675090000 0.0000010000 0.2976940000 0.3058330000 117917283 0 402718720 3.9758324623 3.0769832134 5.8486371040 1466 58.6000000000 1.8301028013 0.5127365241 1.9930224419 0.0294082215 0.4788370000 0.1129070000 0.0618890000 0.0000010000 0.2994820000 0.0017810000 117920059 0 402718720 3.9758324623 3.0769832134 5.8486371040 1467 58.6400000000 1.8315728903 0.5136355264 1.9930224419 0.0293993273 0.4784360000 0.1130650000 0.0613890000 0.0000010000 0.2994630000 0.0017800000 117922835 0 402718720 3.9758324623 3.0769832134 5.8486371040 1468 58.6800000000 1.8323260546 0.5145338170 1.9930224419 0.0293903490 0.4689650000 0.1130860000 0.0518000000 0.0000010000 0.2995230000 0.0017830000 117925611 0 402718720 3.9758324623 3.0769832134 5.8486371040 1469 58.7200000000 1.8331388235 0.5154314378 1.9930224419 0.0293813404 0.7887460000 0.1131130000 0.0677530000 0.0000010000 0.2994580000 0.3056710000 117928387 0 402718720 3.9758324623 3.0769832134 5.8486371040 1470 58.7600000000 1.8362774849 0.5163299725 1.9930224419 0.0293731769 0.5557590000 0.1419920000 0.1030370000 0.0000000000 0.3061330000 0.0017870000 117931163 0 402718720 3.9758324623 3.0769832134 5.8486371040 1471 58.8000000000 1.8387898207 0.5172289935 1.9930224419 0.0293650962 0.4829230000 0.1090830000 0.0693150000 0.0000000000 0.2999520000 0.0017790000 117933939 0 402718720 3.9758324623 3.0769832134 5.8486371040 1472 58.8400000000 1.8409337997 0.5181282495 1.9930224419 0.0293565030 0.5028160000 0.1182160000 0.0815860000 0.0000000000 0.2984450000 0.0017790000 117936715 0 402718720 3.9758324623 3.0769832134 5.8486371040 1473 58.8800000000 1.8433985710 0.5190279578 1.9930224419 0.0293481245 0.7905070000 0.1133600000 0.0693620000 0.0000010000 0.2994630000 0.3055660000 117939491 0 402718720 3.9758324623 3.0769832134 5.8486371040 1474 58.9200000000 1.8456625938 0.5199279813 1.9930224419 0.0293404977 0.4945270000 0.1133360000 0.0770140000 0.0000010000 0.2996050000 0.0017800000 117942267 0 402718720 3.9758324623 3.0769832134 5.8486371040 1475 58.9600000000 1.8481236696 0.5208284529 1.9930224419 0.0293328959 0.4846730000 0.1091820000 0.0708020000 0.0000010000 0.3001750000 0.0017190000 117945043 0 402718720 3.9758324623 3.0769832134 5.8486371040 1476 59.0000000000 1.8513922691 0.5217299189 1.9930224419 0.0293249400 0.4831100000 0.1091810000 0.0695700000 0.0000000000 0.2997640000 0.0017650000 117947819 0 402718720 3.9758324623 3.0769832134 5.8486371040 1477 59.0400000000 1.8538186550 0.5226318070 1.9930224419 0.0293163573 0.7933980000 0.1133450000 0.0722060000 0.0000010000 0.2994740000 0.3056160000 117950595 0 402718720 3.9758324623 3.0769832134 5.8486371040 1478 59.0800000000 1.8564462662 0.5235342526 1.9930224419 0.0293071411 0.5006330000 0.1260830000 0.0704870000 0.0000000000 0.2994790000 0.0017640000 117953371 0 402718720 3.9758324623 3.0769832134 5.8486371040 1479 59.1200000000 1.8616890907 0.5244390226 1.9930224419 0.0292993403 0.4904460000 0.1132040000 0.0732690000 0.0000010000 0.2994610000 0.0017730000 117956147 0 402718720 3.9758324623 3.0769832134 5.8486371040 1480 59.1600000000 1.8647629023 0.5253446468 1.9930224419 0.0292900584 0.4895710000 0.1131500000 0.0719570000 0.0000010000 0.2999260000 0.0017180000 117958923 0 402718720 3.9758324623 3.0769832134 5.8486371040 1481 59.2000000000 1.8663130999 0.5262500948 1.9930224419 0.0292807046 0.7928590000 0.1130760000 0.0719010000 0.0000010000 0.2994520000 0.3056540000 117961699 0 402718720 3.9758324623 3.0769832134 5.8486371040 1482 59.2400000000 1.8690050840 0.5271561373 1.9930224419 0.0292712605 0.5112570000 0.1312840000 0.0781560000 0.0000010000 0.2972410000 0.0017680000 117964475 0 402718720 3.9758324623 3.0769832134 5.8486371040 1483 59.2800000000 1.8718968630 0.5280629078 1.9930224419 0.0292619906 0.4995410000 0.1129820000 0.0790840000 0.0000010000 0.3019000000 0.0024070000 117967251 0 402718720 3.9758324623 3.0769832134 5.8486371040 1484 59.3200000000 1.8741811514 0.5289699956 1.9930224419 0.0292528474 0.5705720000 0.1466700000 0.1122480000 0.0000010000 0.3070550000 0.0017690000 117970027 0 402718720 3.9758324623 3.0769832134 5.8486371040 1485 59.3600000000 1.8758513927 0.5298769864 1.9930224419 0.0292439634 0.7950760000 0.1128970000 0.0742890000 0.0000010000 0.2994530000 0.3056620000 117972803 0 402718720 3.9758324623 3.0769832134 5.8486371040 1486 59.4000000000 1.8772678375 0.5307837098 1.9930224419 0.0292348498 0.4911000000 0.1129480000 0.0741110000 0.0000010000 0.2994620000 0.0017580000 117975579 0 402718720 3.9758324623 3.0769832134 5.8486371040 1487 59.4400000000 1.8790230751 0.5316903939 1.9930224419 0.0292258045 0.4871650000 0.1089310000 0.0741610000 0.0000010000 0.2995070000 0.0017520000 117978355 0 402718720 3.9758324623 3.0769832134 5.8486371040 1488 59.4800000000 1.8816444874 0.5325976211 1.9930224419 0.0292172257 0.4913590000 0.1131370000 0.0741890000 0.0000000000 0.2994320000 0.0017560000 117981131 0 402718720 3.9758324623 3.0769832134 5.8486371040 1489 59.5200000000 1.8832926750 0.5335047367 1.9930224419 0.0292083204 0.8086270000 0.1259540000 0.0747660000 0.0000000000 0.2995120000 0.3056050000 117983907 0 402718720 3.9758324623 3.0769832134 5.8486371040 1490 59.5600000000 1.8859449625 0.5344124147 1.9930224419 0.0291992935 0.4920440000 0.1133990000 0.0745670000 0.0000010000 0.2994570000 0.0017510000 117986683 0 402718720 3.9758324623 3.0769832134 5.8486371040 1491 59.6000000000 1.8883452415 0.5353204850 1.9930224419 0.0291900974 0.5205250000 0.1340890000 0.0823940000 0.0000010000 0.2994400000 0.0017470000 117989459 0 402718720 3.9758324623 3.0769832134 5.8486371040 1492 59.6400000000 1.8901278973 0.5362285329 1.9930224419 0.0291806079 0.4974870000 0.1133800000 0.0811920000 0.0000010000 0.2982400000 0.0017470000 117992235 0 402718720 3.9758324623 3.0769832134 5.8486371040 1493 59.6800000000 1.8938267231 0.5371378418 1.9930224419 0.0291713738 0.8069670000 0.1133750000 0.0755400000 0.0000010000 0.2994850000 0.3153930000 117995011 0 402718720 3.9758324623 3.0769832134 5.8486371040 1494 59.7200000000 1.8957231045 0.5380472027 1.9930224419 0.0291619303 0.5706520000 0.1468790000 0.1134920000 0.0000000000 0.3056990000 0.0017460000 117997787 0 402718720 3.9758324623 3.0769832134 5.8486371040 1495 59.7600000000 1.8975052834 0.5389565392 1.9930224419 0.0291526295 0.4973570000 0.1133910000 0.0823060000 0.0000010000 0.2968800000 0.0018320000 118000563 0 402718720 3.9758324623 3.0769832134 5.8486371040 1496 59.8000000000 1.8990802765 0.5398657128 1.9930224419 0.0291434860 0.4977560000 0.1133940000 0.0818720000 0.0000010000 0.2978940000 0.0017450000 118003339 0 402718720 3.9758324623 3.0769832134 5.8486371040 1497 59.8400000000 1.9014799595 0.5407752748 1.9930224419 0.0291345523 0.7930410000 0.1092300000 0.0759000000 0.0000000000 0.2994890000 0.3055910000 118006115 0 402718720 3.9758324623 3.0769832134 5.8486371040 1498 59.8800000000 1.9048311710 0.5416858595 1.9930224419 0.0291256650 0.4929880000 0.1133720000 0.0755810000 0.0000010000 0.2994430000 0.0017430000 118008891 0 402718720 3.9758324623 3.0769832134 5.8486371040 1499 59.9200000000 1.9066029787 0.5425964113 1.9930224419 0.0291163308 0.4932060000 0.1133360000 0.0758540000 0.0000010000 0.2994680000 0.0017370000 118011667 0 402718720 3.9758324623 3.0769832134 5.8486371040 1500 59.9600000000 1.9074786901 0.5435063328 1.9930224419 0.0291069807 0.4938190000 0.1133350000 0.0765160000 0.0000000000 0.2994540000 0.0017390000 118014443 0 402718720 3.9758324623 3.0769832134 5.8486371040 1501 60.0000000000 1.9085170031 0.5444157337 1.9930224419 0.0290977861 0.8158310000 0.1316660000 0.0762340000 0.0000010000 0.2994500000 0.3056430000 118017219 0 402718720 3.9758324623 3.0769832134 5.8486371040 1502 60.0400000000 1.9094513655 0.5453245457 1.9930224419 0.0290885548 0.4999780000 0.1132630000 0.0827510000 0.0000000000 0.2994120000 0.0017390000 118019995 0 402718720 3.9758324623 3.0769832134 5.8486371040 1503 60.0800000000 1.9098283052 0.5462323991 1.9930224419 0.0290794033 0.4918160000 0.1090860000 0.0787210000 0.0000000000 0.2994810000 0.0017340000 118022771 0 402718720 3.9758324623 3.0769832134 5.8486371040 1504 60.1200000000 1.9110409021 0.5471398516 1.9930224419 0.0290704477 0.4931600000 0.1132240000 0.0759350000 0.0000010000 0.2994590000 0.0017330000 118025547 0 402718720 3.9758324623 3.0769832134 5.8486371040 1505 60.1600000000 1.9115896225 0.5480464627 1.9930224419 0.0290618575 0.8083740000 0.1247370000 0.0757800000 0.0000010000 0.2994700000 0.3056090000 118028323 0 402718720 3.9758324623 3.0769832134 5.8486371040 1506 60.2000000000 1.9123111963 0.5489523490 1.9930224419 0.0290535894 0.4916360000 0.1128380000 0.0747530000 0.0000010000 0.2995010000 0.0017290000 118031099 0 402718720 3.9758324623 3.0769832134 5.8486371040 1507 60.2400000000 1.9115531445 0.5498565300 1.9930224419 0.0290456111 0.5034360000 0.1255370000 0.0738510000 0.0000010000 0.2994980000 0.0017270000 118033875 0 402718720 3.9758324623 3.0769832134 5.8486371040 1508 60.2800000000 1.9116135836 0.5507595520 1.9930224419 0.0290369236 0.4967590000 0.1125360000 0.0821910000 0.0000010000 0.2974680000 0.0017260000 118036651 0 402718720 3.9758324623 3.0769832134 5.8486371040 1509 60.3200000000 1.9117895365 0.5516614936 1.9930224419 0.0290281849 0.7939020000 0.1124930000 0.0736390000 0.0000000000 0.2994380000 0.3055450000 118039427 0 402718720 3.9758324623 3.0769832134 5.8486371040 1510 60.3600000000 1.9109404087 0.5525616783 1.9930224419 0.0290187030 0.4740490000 0.1125070000 0.0574840000 0.0000000000 0.2995150000 0.0017240000 118042203 0 402718720 3.9758324623 3.0769832134 5.8486371040 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:51:51 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002853 0.0000002853 0.0000002853 -nan 0.7638650000 0.1907540000 0.0280250000 0.0712670000 0.0000030000 0.4737280000 106014494 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0004263568 0.0002133210 0.0004263568 0.0040680543 0.2785290000 0.1768830000 0.0260010000 0.0711450000 0.0000000000 0.0044690000 112903139 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0024013643 0.0009426688 0.0024013643 0.0044545561 0.2660920000 0.1645340000 0.0260220000 0.0710400000 0.0000010000 0.0044640000 112906307 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0017003767 0.0011320958 0.0024013643 0.0049657320 0.7116490000 0.1634980000 0.0260060000 0.0711460000 0.4465170000 0.0044510000 112909483 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0009065330 0.0010869832 0.0024013643 0.0044320641 1.3659170000 0.1637450000 0.2174350000 0.0711110000 0.4475930000 0.4659960000 112912643 0 402718720 4.0000848770 3.9995701313 4.0000095367 6 0.2000000000 0.0008841971 0.0010531855 0.0024013643 0.0040876570 0.4561050000 0.0969180000 0.0666390000 0.0000010000 0.2905970000 0.0019150000 112916219 0 402718720 4.0001263618 3.9984500408 3.9996979237 7 0.2400000000 0.0009241140 0.0010347467 0.0024013643 0.0037765129 0.4978540000 0.0969260000 0.0797130000 0.0330650000 0.2862000000 0.0019130000 112918995 0 402718720 4.0001134872 3.9982912540 3.9996078014 8 0.2800000000 0.0010749133 0.0010397676 0.0024013643 0.0035587599 0.4427180000 0.0948820000 0.0567910000 0.0000010000 0.2890960000 0.0019100000 112921771 0 402718720 4.0004029274 3.9995920658 4.0000352859 9 0.3200000000 0.0010728099 0.0010434389 0.0024013643 0.0033320192 0.7904340000 0.1179610000 0.0601720000 0.0330830000 0.2857380000 0.2934330000 112925315 0 402718720 4.0005893707 3.9996204376 4.0000782013 10 0.3600000000 0.0011573778 0.0010548328 0.0024013643 0.0031521192 0.4439200000 0.0968240000 0.0572640000 0.0000010000 0.2878780000 0.0019110000 112929691 0 402718720 4.0006341934 3.9989976883 3.9999096394 11 0.4000000000 0.0011061265 0.0010594959 0.0024013643 0.0029931261 0.4644080000 0.0969900000 0.0453780000 0.0325770000 0.2875000000 0.0019190000 112932467 0 402718720 4.0004959106 3.9995486736 4.0000967979 12 0.4400000000 0.0010835755 0.0010615025 0.0024013643 0.0028619159 0.4626460000 0.0970090000 0.0762080000 0.0000010000 0.2874840000 0.0019030000 112935243 0 402718720 4.0005831718 4.0002679825 4.0004057884 13 0.4800000000 0.0011524090 0.0010684953 0.0024013643 0.0027522895 0.8414380000 0.1151530000 0.1130110000 0.0330260000 0.2871970000 0.2929970000 112938019 0 402718720 4.0004262924 4.0009288788 4.0007162094 14 0.5200000000 0.0011285453 0.0010727846 0.0024013643 0.0027275566 0.4647390000 0.0969480000 0.0789650000 0.0000000000 0.2868600000 0.0019150000 112940795 0 402718720 4.0006041527 4.0009522438 4.0007972717 15 0.5600000000 0.0011160604 0.0010756697 0.0024013643 0.0027159855 0.4758010000 0.0968300000 0.0572460000 0.0330060000 0.2867510000 0.0019160000 112943571 0 402718720 4.0006380081 4.0009727478 4.0008926392 16 0.6000000000 0.0011508107 0.0010803660 0.0024013643 0.0026447430 0.4324120000 0.0949810000 0.0473010000 0.0000000000 0.2881700000 0.0019060000 112946347 0 402718720 4.0010671616 4.0008988380 4.0008115768 17 0.6400000000 0.0012706750 0.0010915606 0.0024013643 0.0025678550 0.7596640000 0.0971030000 0.0478100000 0.0325260000 0.2880860000 0.2940840000 112950659 0 402718720 4.0009832382 4.0008902550 4.0008578300 18 0.6800000000 0.0013075994 0.0011035628 0.0024013643 0.0025013930 0.4353190000 0.0970370000 0.0478680000 0.0000010000 0.2884440000 0.0019130000 112956635 0 402718720 4.0010814667 4.0001606941 4.0006108284 19 0.7200000000 0.0012388667 0.0011106840 0.0024013643 0.0025390953 0.4868510000 0.0970420000 0.0669040000 0.0329830000 0.2879410000 0.0019230000 112959411 0 402718720 4.0010013580 4.0001626015 4.0005259514 20 0.7600000000 0.0012226361 0.0011162816 0.0024013643 0.0026345972 0.4693180000 0.1203330000 0.0602360000 0.0000010000 0.2867740000 0.0019110000 112962187 0 402718720 4.0007801056 3.9999024868 4.0004496574 21 0.8000000000 0.0013096618 0.0011254902 0.0024013643 0.0027448054 0.7764800000 0.0968890000 0.0669150000 0.0325940000 0.2871140000 0.2929100000 112964963 0 402718720 4.0007944107 3.9998397827 4.0002942085 22 0.8400000000 0.0012807263 0.0011325464 0.0024013643 0.0027257447 0.4411200000 0.0967130000 0.0549670000 0.0000010000 0.2874660000 0.0019140000 112967739 0 402718720 4.0008220673 4.0000262260 4.0004067421 23 0.8800000000 0.0012882811 0.0011393175 0.0024013643 0.0027023151 0.5064680000 0.1173780000 0.0668020000 0.0330340000 0.2872700000 0.0019180000 112970515 0 402718720 4.0005874634 3.9997990131 4.0003347397 24 0.9200000000 0.0013735757 0.0011490782 0.0024013643 0.0026493323 0.4697050000 0.0969020000 0.0834780000 0.0000010000 0.2873590000 0.0019060000 112973291 0 402718720 4.0006728172 4.0000114441 4.0003337860 25 0.9600000000 0.0013914572 0.0011587734 0.0024013643 0.0025959421 0.7581170000 0.0969790000 0.0478890000 0.0330850000 0.2872230000 0.2928760000 112976067 0 402718720 4.0004816055 3.9999401569 4.0003428459 26 1.0000000000 0.0014211355 0.0011688642 0.0024013643 0.0025452400 0.5131990000 0.1095280000 0.1141900000 0.0000010000 0.2874980000 0.0019170000 112978843 0 402718720 4.0006237030 4.0002737045 4.0003814697 27 1.0400000000 0.0015454425 0.0011828116 0.0024013643 0.0025015929 0.4647080000 0.0966250000 0.0454760000 0.0330760000 0.2875460000 0.0019180000 112981619 0 402718720 4.0004606247 4.0003185272 4.0003733635 28 1.0800000000 0.0015383706 0.0011955101 0.0024013643 0.0024755606 0.4521480000 0.1095420000 0.0479200000 0.0000010000 0.2919390000 0.0026730000 112984395 0 402718720 4.0003805161 4.0001549721 4.0004057884 29 1.1200000000 0.0014717150 0.0012050344 0.0024013643 0.0024409811 0.8088070000 0.1238370000 0.0583870000 0.0409080000 0.2923480000 0.2932570000 112987171 0 402718720 4.0000195503 4.0003018379 4.0005135536 30 1.1600000000 0.0015678141 0.0012171271 0.0024013643 0.0024122168 0.4347100000 0.0969560000 0.0479130000 0.0000010000 0.2878450000 0.0019240000 112989947 0 402718720 4.0002760887 4.0008268356 4.0004897118 31 1.2000000000 0.0014954547 0.0012261054 0.0024013643 0.0023901438 0.4870320000 0.0967960000 0.0669580000 0.0330300000 0.2882630000 0.0019160000 112992723 0 402718720 4.0000352859 4.0005130768 4.0004620552 32 1.2400000000 0.0014775471 0.0012339630 0.0024013643 0.0023570551 0.4352080000 0.0969470000 0.0479130000 0.0000000000 0.2883680000 0.0019090000 112995499 0 402718720 3.9997668266 4.0001139641 4.0004191399 33 1.2800000000 0.0015027493 0.0012421080 0.0024013643 0.0023521396 0.7696060000 0.1068120000 0.0478500000 0.0326180000 0.2881640000 0.2940840000 113001347 0 402718720 3.9995870590 4.0002036095 4.0005879402 34 1.3200000000 0.0016297959 0.0012535106 0.0024013643 0.0023408926 0.4352450000 0.0966230000 0.0502660000 0.0000010000 0.2863700000 0.0019090000 113010523 0 402718720 3.9991927147 4.0000429153 4.0006513596 35 1.3600000000 0.0014821411 0.0012600429 0.0024013643 0.0023237440 0.4840090000 0.0968140000 0.0644200000 0.0326250000 0.2881560000 0.0019180000 113013299 0 402718720 3.9987952709 3.9990284443 4.0004086494 36 1.4000000000 0.0015154232 0.0012671368 0.0024013643 0.0022973755 0.5009930000 0.0968990000 0.1139000000 0.0000010000 0.2882050000 0.0019110000 113016075 0 402718720 3.9983813763 3.9989931583 4.0003924370 37 1.4400000000 0.0013920824 0.0012705137 0.0024013643 0.0022660041 0.7837580000 0.0950830000 0.0754960000 0.0328190000 0.2874420000 0.2928370000 113018851 0 402718720 3.9980838299 3.9994890690 4.0005960464 38 1.4800000000 0.0013111165 0.0012715822 0.0024013643 0.0022351888 0.4532160000 0.0972690000 0.0668720000 0.0000010000 0.2870860000 0.0019060000 113021627 0 402718720 3.9977543354 3.9989535809 4.0006341934 39 1.5200000000 0.0012521170 0.0012710831 0.0024013643 0.0022163013 0.5324480000 0.1096560000 0.0772460000 0.0409270000 0.3018530000 0.0026740000 113024403 0 402718720 3.9970295429 3.9974632263 4.0002694130 40 1.5600000000 0.0011238497 0.0012674022 0.0024013643 0.0022928654 0.4747680000 0.1247590000 0.0573970000 0.0000010000 0.2906210000 0.0019040000 113027179 0 402718720 3.9966287613 3.9978201389 4.0006833076 41 1.6000000000 0.0011376519 0.0012642376 0.0024013643 0.0024313440 0.8227940000 0.1253160000 0.0836180000 0.0325600000 0.2876790000 0.2935260000 113029955 0 402718720 3.9962599277 3.9990513325 4.0014185905 42 1.6400000000 0.0011786101 0.0012621988 0.0024013643 0.0025060144 0.4618890000 0.0980620000 0.0743570000 0.0000000000 0.2874730000 0.0019050000 113032731 0 402718720 3.9956030846 3.9988551140 4.0017685890 43 1.6800000000 0.0012124282 0.0012610414 0.0024013643 0.0025108862 0.5111840000 0.1202780000 0.0703940000 0.0330460000 0.2854570000 0.0019130000 113035507 0 402718720 3.9952819347 3.9988086224 4.0023140907 44 1.7200000000 0.0012442269 0.0012606592 0.0024013643 0.0024926670 0.4831720000 0.0982160000 0.0957620000 0.0000010000 0.2871970000 0.0019050000 113038283 0 402718720 3.9948816299 3.9991953373 4.0029864311 45 1.7600000000 0.0012337221 0.0012600606 0.0024013643 0.0024871777 0.8012130000 0.0981830000 0.0901100000 0.0331150000 0.2860570000 0.2936530000 113041059 0 402718720 3.9946844578 3.9986555576 4.0035066605 46 1.8000000000 0.0012836086 0.0012605725 0.0024013643 0.0026042749 0.4541390000 0.0983590000 0.0648860000 0.0000010000 0.2888950000 0.0019040000 113043835 0 402718720 3.9944636822 3.9975686073 4.0040483475 47 1.8400000000 0.0012796598 0.0012609787 0.0024013643 0.0027655718 0.4969670000 0.0978220000 0.0768050000 0.0330660000 0.2872580000 0.0019170000 113046611 0 402718720 3.9944081306 3.9971714020 4.0049519539 48 1.8800000000 0.0011734749 0.0012591557 0.0024013643 0.0029387594 0.4541920000 0.0990630000 0.0649340000 0.0000010000 0.2881880000 0.0019090000 113049387 0 402718720 3.9940619469 3.9970042706 4.0063676834 49 1.9200000000 0.0011819648 0.0012575803 0.0024013643 0.0032186393 0.7713350000 0.0990190000 0.0579730000 0.0325150000 0.2878690000 0.2938600000 113052163 0 402718720 3.9940652847 3.9956121445 4.0073895454 50 1.9600000000 0.0012043528 0.0012565158 0.0024013643 0.0035101627 0.4590780000 0.0993770000 0.0673840000 0.0000010000 0.2903650000 0.0018480000 113054939 0 402718720 3.9940497875 3.9951140881 4.0089092255 51 2.0000000000 0.0012405880 0.0012562035 0.0024013643 0.0036862889 0.4783410000 0.0997220000 0.0553270000 0.0330440000 0.2882320000 0.0019140000 113057715 0 402718720 3.9941513538 3.9953296185 4.0108203888 52 2.0400000000 0.0012972216 0.0012569923 0.0024013643 0.0038228207 0.4480300000 0.0996380000 0.0580300000 0.0000000000 0.2883510000 0.0019060000 113060491 0 402718720 3.9947869778 3.9952323437 4.0127410889 53 2.0800000000 0.0013281691 0.0012583353 0.0024013643 0.0038897487 0.7964100000 0.1158560000 0.0672900000 0.0328050000 0.2874590000 0.2928900000 113063267 0 402718720 3.9951393604 3.9940466881 4.0143918991 54 2.1200000000 0.0013535182 0.0012600979 0.0024013643 0.0039551119 0.4490420000 0.0998870000 0.0579210000 0.0000010000 0.2892870000 0.0018380000 113066043 0 402718720 3.9961614609 3.9933357239 4.0161705017 55 2.1600000000 0.0013260342 0.0012612967 0.0024013643 0.0039588107 0.4891120000 0.0999130000 0.0671920000 0.0329850000 0.2870010000 0.0019160000 113068819 0 402718720 3.9964470863 3.9935936928 4.0186834335 56 2.2000000000 0.0012319797 0.0012607732 0.0024013643 0.0039376452 0.4633220000 0.0998870000 0.0743440000 0.0000010000 0.2870710000 0.0019130000 113071595 0 402718720 3.9968552589 3.9937725067 4.0211911201 57 2.2400000000 0.0012843428 0.0012611867 0.0024013643 0.0039532340 0.7621280000 0.0974310000 0.0547830000 0.0327430000 0.2857200000 0.2913390000 113074371 0 402718720 3.9980320930 3.9937179089 4.0235986710 58 2.2800000000 0.0013257751 0.0012623003 0.0024013643 0.0040120615 0.4413870000 0.0991780000 0.0554170000 0.0000010000 0.2847740000 0.0019080000 113077147 0 402718720 3.9987235069 3.9947886467 4.0264468193 59 2.3200000000 0.0013964641 0.0012645743 0.0024013643 0.0041114094 0.4745770000 0.0985390000 0.0578540000 0.0325760000 0.2835800000 0.0019120000 113079923 0 402718720 4.0000019073 3.9945938587 4.0290923119 60 2.3600000000 0.0014046086 0.0012669082 0.0024013643 0.0044119564 0.4386610000 0.0979610000 0.0557280000 0.0000010000 0.2829580000 0.0019020000 113082699 0 402718720 4.0009665489 3.9932777882 4.0314922333 61 2.4000000000 0.0014584631 0.0012700484 0.0024013643 0.0046756938 0.7583330000 0.0977530000 0.0558810000 0.0329460000 0.2828130000 0.2888250000 113085475 0 402718720 4.0024142265 3.9932465553 4.0344185829 62 2.4400000000 0.0014690553 0.0012732582 0.0024013643 0.0049254781 0.4687600000 0.1252380000 0.0611410000 0.0000000000 0.2802580000 0.0019910000 113088251 0 402718720 4.0036835670 3.9931933880 4.0373234749 63 2.4800000000 0.0015946700 0.0012783600 0.0024013643 0.0051086720 0.4834330000 0.1094100000 0.0585440000 0.0330500000 0.2803910000 0.0019150000 113091027 0 402718720 4.0051698685 3.9926538467 4.0400347710 64 2.5200000000 0.0015815118 0.0012830967 0.0024013643 0.0052470883 0.4404320000 0.0966170000 0.0581040000 0.0000010000 0.2837480000 0.0018440000 113093803 0 402718720 4.0067815781 3.9929549694 4.0431938171 65 2.5600000000 0.0015862110 0.0012877600 0.0024013643 0.0054882542 0.7555160000 0.0956540000 0.0581400000 0.0324610000 0.2816740000 0.2874630000 113102723 0 402718720 4.0081090927 3.9925067425 4.0460486412 66 2.6000000000 0.0013666279 0.0012889550 0.0024013643 0.0058370283 0.4511850000 0.0962630000 0.0679660000 0.0000000000 0.2849230000 0.0019090000 113118299 0 402718720 4.0096697807 3.9914128780 4.0485529900 67 2.6400000000 0.0013214924 0.0012894406 0.0024013643 0.0061137235 0.4885040000 0.0948860000 0.0767230000 0.0325130000 0.2823410000 0.0019210000 113121075 0 402718720 4.0117030144 3.9928615093 4.0518717766 68 2.6800000000 0.0013328413 0.0012900789 0.0024013643 0.0065269656 0.4482970000 0.0967950000 0.0655310000 0.0000000000 0.2839280000 0.0019180000 113123851 0 402718720 4.0120272636 3.9930984974 4.0547242165 69 2.7200000000 0.0013751131 0.0012913113 0.0024013643 0.0067398598 0.7553850000 0.0968030000 0.0580220000 0.0329270000 0.2808030000 0.2867000000 113126627 0 402718720 4.0139622688 3.9922268391 4.0573906898 70 2.7600000000 0.0014167432 0.0012931031 0.0024013643 0.0068650940 0.4411870000 0.0972110000 0.0580810000 0.0000000000 0.2838520000 0.0019130000 113129403 0 402718720 4.0155162811 3.9915122986 4.0598707199 71 2.8000000000 0.0014380988 0.0012951453 0.0024013643 0.0068882744 0.4798210000 0.0976470000 0.0673030000 0.0324090000 0.2804150000 0.0019150000 113132179 0 402718720 4.0168271065 3.9922182560 4.0629100800 72 2.8400000000 0.0013815875 0.0012963459 0.0024013643 0.0068800855 0.4414620000 0.0983030000 0.0573640000 0.0000010000 0.2838200000 0.0018430000 113134955 0 402718720 4.0181655884 3.9919662476 4.0655765533 73 2.8800000000 0.0012845139 0.0012961838 0.0024013643 0.0068667212 0.7796290000 0.1277060000 0.0552720000 0.0328660000 0.2788810000 0.2847640000 113137731 0 402718720 4.0193538666 3.9914057255 4.0680384636 74 2.9200000000 0.0012850146 0.0012960329 0.0024013643 0.0068791933 0.4437090000 0.0997470000 0.0607090000 0.0000010000 0.2812100000 0.0019070000 113140507 0 402718720 4.0208907127 3.9922404289 4.0709204674 75 2.9600000000 0.0013879626 0.0012972586 0.0024013643 0.0069511357 0.4717290000 0.1005090000 0.0576510000 0.0324600000 0.2790600000 0.0019140000 113143283 0 402718720 4.0222954750 3.9926767349 4.0736184120 76 3.0000000000 0.0013657829 0.0012981603 0.0024013643 0.0071177440 0.4368490000 0.1013930000 0.0509020000 0.0000000000 0.2825060000 0.0019100000 113146059 0 402718720 4.0237441063 3.9914441109 4.0757980347 77 3.0400000000 0.0013555792 0.0012989060 0.0024013643 0.0072807650 0.7577570000 0.1022950000 0.0578160000 0.0324570000 0.2795270000 0.2855220000 113148835 0 402718720 4.0248904228 3.9902617931 4.0779099464 78 3.0800000000 0.0012423655 0.0012981811 0.0024013643 0.0075049850 0.4672300000 0.1030310000 0.0773400000 0.0000010000 0.2848160000 0.0019030000 113151611 0 402718720 4.0261349678 3.9909489155 4.0807323456 79 3.1200000000 0.0012255502 0.0012972617 0.0024013643 0.0077075577 0.4775930000 0.1036920000 0.0579370000 0.0329190000 0.2810050000 0.0019040000 113154387 0 402718720 4.0268478394 3.9911732674 4.0834579468 80 3.1600000000 0.0012736981 0.0012969672 0.0024013643 0.0078492937 0.4580160000 0.1044410000 0.0651640000 0.0000000000 0.2863690000 0.0019020000 113157163 0 402718720 4.0280365944 3.9901251793 4.0856828690 81 3.2000000000 0.0013623945 0.0012977749 0.0024013643 0.0079957086 0.7746840000 0.1052600000 0.0672930000 0.0325310000 0.2814420000 0.2880140000 113159939 0 402718720 4.0295147896 3.9899263382 4.0882039070 82 3.2400000000 0.0013789915 0.0012987654 0.0024013643 0.0081718206 0.4625480000 0.1059690000 0.0677450000 0.0000010000 0.2867860000 0.0019040000 113162715 0 402718720 4.0299239159 3.9897520542 4.0907139778 83 3.2800000000 0.0013335857 0.0012991849 0.0024013643 0.0083556537 0.5013240000 0.1158940000 0.0672740000 0.0330440000 0.2830530000 0.0019110000 113165491 0 402718720 4.0309648514 3.9888012409 4.0931081772 84 3.3200000000 0.0013275893 0.0012995230 0.0024013643 0.0084569301 0.4835210000 0.1255470000 0.0709300000 0.0000010000 0.2848860000 0.0020000000 113168267 0 402718720 4.0315895081 3.9886298180 4.0956411362 85 3.3600000000 0.0013097133 0.0012996429 0.0024013643 0.0085285356 0.7932710000 0.1075420000 0.0803960000 0.0332600000 0.2813650000 0.2905580000 113171043 0 402718720 4.0320849419 3.9890172482 4.0984077454 86 3.4000000000 0.0014496699 0.0013013874 0.0024013643 0.0085865465 0.5052050000 0.1080680000 0.0900400000 0.0000010000 0.3042660000 0.0026610000 113173819 0 402718720 4.0331001282 3.9889760017 4.1009826660 87 3.4400000000 0.0013875513 0.0013023778 0.0024013643 0.0086594898 0.5225980000 0.1378460000 0.0652310000 0.0331990000 0.2842560000 0.0019140000 113176595 0 402718720 4.0339002609 3.9889769554 4.1038331985 88 3.4800000000 0.0014567720 0.0013041323 0.0024013643 0.0087448598 0.4653070000 0.1086350000 0.0651030000 0.0000010000 0.2895790000 0.0018380000 113179371 0 402718720 4.0346302986 3.9887206554 4.1065897942 89 3.5200000000 0.0014204320 0.0013054390 0.0024013643 0.0088265562 0.7842180000 0.1216290000 0.0553980000 0.0332070000 0.2834960000 0.2903310000 113182147 0 402718720 4.0354819298 3.9887082577 4.1094946861 90 3.5600000000 0.0014104209 0.0013066055 0.0024013643 0.0089449604 0.4565140000 0.1088790000 0.0582310000 0.0000000000 0.2873400000 0.0019070000 113184923 0 402718720 4.0357699394 3.9887402058 4.1124587059 91 3.6000000000 0.0014181108 0.0013078308 0.0024013643 0.0090821858 0.4851840000 0.1090040000 0.0580420000 0.0328180000 0.2832480000 0.0019120000 113187699 0 402718720 4.0370979309 3.9881715775 4.1154561043 92 3.6400000000 0.0014574369 0.0013094570 0.0024013643 0.0091689150 0.4653680000 0.1090760000 0.0678400000 0.0000010000 0.2863830000 0.0019090000 113190475 0 402718720 4.0375509262 3.9879806042 4.1186318398 93 3.6800000000 0.0014029737 0.0013104625 0.0024013643 0.0091711818 0.7804020000 0.1056500000 0.0665760000 0.0331060000 0.2839120000 0.2909940000 113193251 0 402718720 4.0379114151 3.9874186516 4.1215682030 94 3.7200000000 0.0015596851 0.0013131138 0.0024013643 0.0091493500 0.5179150000 0.1092680000 0.1177670000 0.0000010000 0.2888020000 0.0019090000 113196027 0 402718720 4.0389337540 3.9877634048 4.1247520447 95 3.7600000000 0.0014539567 0.0013145964 0.0024013643 0.0091378296 0.5439100000 0.1093190000 0.1147000000 0.0334270000 0.2843830000 0.0019180000 113198803 0 402718720 4.0397167206 3.9874563217 4.1278076172 96 3.8000000000 0.0015073612 0.0013166044 0.0024013643 0.0091576455 0.4768580000 0.1062980000 0.0769470000 0.0000010000 0.2907560000 0.0026690000 113201579 0 402718720 4.0406155586 3.9876637459 4.1310529709 97 3.8400000000 0.0014266755 0.0013177391 0.0024013643 0.0092710194 0.8639510000 0.1409570000 0.0871820000 0.0415360000 0.2996930000 0.2944150000 113204355 0 402718720 4.0411739349 3.9890315533 4.1346874237 98 3.8800000000 0.0015510251 0.0013201196 0.0024013643 0.0093968583 0.4633050000 0.1060620000 0.0672550000 0.0000010000 0.2879750000 0.0018430000 113207131 0 402718720 4.0417342186 3.9890341759 4.1378316879 99 3.9200000000 0.0015210784 0.0013221495 0.0024013643 0.0095269473 0.4830010000 0.1061160000 0.0574340000 0.0327530000 0.2846090000 0.0019150000 113209907 0 402718720 4.0426893234 3.9890162945 4.1410517693 100 3.9600000000 0.0015353983 0.0013242820 0.0024013643 0.0096389089 0.4559330000 0.1098330000 0.0558130000 0.0000000000 0.2882030000 0.0019110000 113212683 0 402718720 4.0428619385 3.9906501770 4.1446661949 101 4.0000000000 0.0016134460 0.0013271450 0.0024013643 0.0096906865 0.7751770000 0.1099910000 0.0554380000 0.0331610000 0.2847720000 0.2916420000 113215459 0 402718720 4.0433793068 3.9912884235 4.1480407715 102 4.0400000000 0.0016134294 0.0013299517 0.0024013643 0.0097042406 0.4662580000 0.1101790000 0.0650740000 0.0000010000 0.2889180000 0.0019110000 113218235 0 402718720 4.0440034866 3.9909744263 4.1509838104 103 4.0800000000 0.0015723248 0.0013323048 0.0024013643 0.0097159070 0.4978030000 0.1186700000 0.0576250000 0.0337050000 0.2857070000 0.0019160000 113221011 0 402718720 4.0444140434 3.9921500683 4.1543827057 104 4.1200000000 0.0015324421 0.0013342292 0.0024013643 0.0097212759 0.4941430000 0.1350250000 0.0673190000 0.0000010000 0.2897000000 0.0019130000 113223787 0 402718720 4.0452332497 3.9921472073 4.1575202942 105 4.1600000000 0.0016245840 0.0013369945 0.0024013643 0.0097301374 0.7896950000 0.1108290000 0.0670450000 0.0332760000 0.2857270000 0.2926350000 113226563 0 402718720 4.0456252098 3.9923646450 4.1602549553 106 4.2000000000 0.0016402403 0.0013398553 0.0024013643 0.0097217721 0.4576590000 0.1109540000 0.0553610000 0.0000000000 0.2892460000 0.0019150000 113229339 0 402718720 4.0452661514 3.9929809570 4.1630811691 107 4.2400000000 0.0015692965 0.0013419996 0.0024013643 0.0096968927 0.4881320000 0.1093070000 0.0574770000 0.0338240000 0.2854120000 0.0019280000 113232115 0 402718720 4.0461325645 3.9923436642 4.1655516624 108 4.2800000000 0.0018232852 0.0013464560 0.0024013643 0.0096896895 0.4580780000 0.1112670000 0.0553330000 0.0000000000 0.2893690000 0.0019210000 113234891 0 402718720 4.0456161499 3.9932417870 4.1683020592 109 4.3200000000 0.0018597605 0.0013511652 0.0024013643 0.0096735330 0.7791970000 0.1113980000 0.0550400000 0.0338210000 0.2860630000 0.2926900000 113237667 0 402718720 4.0457434654 3.9941141605 4.1709737778 110 4.3600000000 0.0020518489 0.0013575350 0.0024013643 0.0096376763 0.4626350000 0.1115250000 0.0573930000 0.0000010000 0.2916070000 0.0019230000 113240443 0 402718720 4.0457258224 3.9943451881 4.1735253334 111 4.4000000000 0.0021198038 0.0013644023 0.0024013643 0.0096055108 0.5036490000 0.1247740000 0.0570050000 0.0334920000 0.2862520000 0.0019330000 113243219 0 402718720 4.0460739136 3.9944756031 4.1760773659 112 4.4400000000 0.0024817991 0.0013743791 0.0024817991 0.0095742744 0.4611660000 0.1117830000 0.0548800000 0.0000000000 0.2923830000 0.0019290000 113245995 0 402718720 4.0461559296 3.9947733879 4.1784787178 113 4.4800000000 0.0020885989 0.0013806996 0.0024817991 0.0095405434 0.8096760000 0.1227950000 0.0769980000 0.0341320000 0.2833830000 0.2921710000 113248771 0 402718720 4.0461363792 3.9952516556 4.1809263229 114 4.5200000000 0.0024075219 0.0013897068 0.0024817991 0.0095095905 0.4647120000 0.1119970000 0.0572230000 0.0000010000 0.2933640000 0.0019330000 113251547 0 402718720 4.0461950302 3.9951968193 4.1833353043 115 4.5600000000 0.0021332360 0.0013961723 0.0024817991 0.0094793667 0.4933830000 0.1120780000 0.0597760000 0.0341230000 0.2852770000 0.0019340000 113254323 0 402718720 4.0468401909 3.9950270653 4.1857061386 116 4.6000000000 0.0023886813 0.0014047284 0.0024817991 0.0094605942 0.4739250000 0.1248890000 0.0549950000 0.0000010000 0.2919110000 0.0019320000 113257099 0 402718720 4.0464463234 3.9957978725 4.1882734299 117 4.6400000000 0.0023147734 0.0014125066 0.0024817991 0.0094293617 0.7909610000 0.1082400000 0.0658310000 0.0332140000 0.2883050000 0.2951720000 113259875 0 402718720 4.0467066765 3.9954388142 4.1907277107 118 4.6800000000 0.0021953254 0.0014191406 0.0024817991 0.0094017990 0.4558210000 0.1122430000 0.0478770000 0.0000010000 0.2935630000 0.0019400000 113262651 0 402718720 4.0469403267 3.9956836700 4.1934227943 119 4.7200000000 0.0025090161 0.0014282992 0.0025090161 0.0093770673 0.4913870000 0.1123520000 0.0545320000 0.0337200000 0.2886290000 0.0019490000 113265427 0 402718720 4.0470776558 3.9958119392 4.1963720322 120 4.7600000000 0.0022620237 0.0014352469 0.0025090161 0.0093508697 0.4663640000 0.1123730000 0.0573000000 0.0000010000 0.2945470000 0.0019390000 113268203 0 402718720 4.0474119186 3.9954135418 4.1991491318 121 4.8000000000 0.0024955685 0.0014440099 0.0025090161 0.0093396965 0.7863210000 0.1123910000 0.0546820000 0.0337410000 0.2891650000 0.2961380000 113270979 0 402718720 4.0474834442 3.9957740307 4.2021942139 122 4.8400000000 0.0025673374 0.0014532175 0.0025673374 0.0093452508 0.4641520000 0.1124100000 0.0550020000 0.0000000000 0.2945970000 0.0019340000 113273755 0 402718720 4.0474371910 3.9958207607 4.2052774429 123 4.8800000000 0.0023844310 0.0014607884 0.0025673374 0.0093292806 0.5123180000 0.1227440000 0.0639010000 0.0343090000 0.2892190000 0.0019340000 113276531 0 402718720 4.0477495193 3.9959812164 4.2084522247 124 4.9200000000 0.0024533793 0.0014687931 0.0025673374 0.0093066281 0.4658370000 0.1124560000 0.0573990000 0.0000010000 0.2938430000 0.0019290000 113279307 0 402718720 4.0477404594 3.9963326454 4.2115163803 125 4.9600000000 0.0024323019 0.0014765012 0.0025673374 0.0092853504 0.8122760000 0.1384960000 0.0545100000 0.0343400000 0.2888810000 0.2958320000 113282083 0 402718720 4.0480647087 3.9966602325 4.2148175240 126 5.0000000000 0.0023673021 0.0014835711 0.0025673374 0.0092714037 0.4651980000 0.1125340000 0.0548630000 0.0000000000 0.2956600000 0.0019280000 113284859 0 402718720 4.0484352112 3.9966349602 4.2179608345 127 5.0400000000 0.0023740029 0.0014905823 0.0025673374 0.0092721636 0.4989560000 0.1084540000 0.0632920000 0.0335040000 0.2916180000 0.0018740000 113287635 0 402718720 4.0488457680 3.9966101646 4.2212224007 128 5.0800000000 0.0024439748 0.0014980307 0.0025673374 0.0092885267 0.4570150000 0.1126020000 0.0455300000 0.0000010000 0.2967370000 0.0019310000 113290411 0 402718720 4.0492463112 3.9971413612 4.2243957520 129 5.1200000000 0.0024660062 0.0015055344 0.0025673374 0.0092732246 0.7951110000 0.1125820000 0.0569470000 0.0344400000 0.2919390000 0.2989840000 113305475 0 402718720 4.0498256683 3.9972660542 4.2275195122 130 5.1600000000 0.0025059101 0.0015132296 0.0025673374 0.0092611896 0.4659440000 0.1126100000 0.0549260000 0.0000010000 0.2962540000 0.0019380000 113333851 0 402718720 4.0504422188 3.9966120720 4.2301378250 131 5.2000000000 0.0024059950 0.0015200446 0.0025673374 0.0092503309 0.4907760000 0.1085670000 0.0541090000 0.0341800000 0.2917490000 0.0019500000 113336627 0 402718720 4.0510840416 3.9967215061 4.2329359055 132 5.2400000000 0.0024760200 0.0015272868 0.0025673374 0.0092299927 0.4535390000 0.1099910000 0.0454740000 0.0000000000 0.2959090000 0.0019420000 113339403 0 402718720 4.0513644218 3.9973073006 4.2358841896 133 5.2800000000 0.0025487561 0.0015349671 0.0025673374 0.0092236553 0.7924390000 0.1217200000 0.0475950000 0.0345860000 0.2895680000 0.2987430000 113342179 0 402718720 4.0520291328 3.9968388081 4.2384138107 134 5.3200000000 0.0025857692 0.0015428089 0.0025857692 0.0092499580 0.4687670000 0.1127440000 0.0604500000 0.0000010000 0.2932940000 0.0020420000 113344955 0 402718720 4.0525918007 3.9975159168 4.2414579391 135 5.3600000000 0.0025361138 0.0015501667 0.0025857692 0.0092504716 0.4995280000 0.1128100000 0.0576370000 0.0340510000 0.2928530000 0.0019470000 113347731 0 402718720 4.0531001091 3.9970941544 4.2437319756 136 5.4000000000 0.0024891573 0.0015570710 0.0025857692 0.0092559388 0.4685790000 0.1127240000 0.0549850000 0.0000010000 0.2986950000 0.0019450000 113350507 0 402718720 4.0538716316 3.9963383675 4.2460198402 137 5.4400000000 0.0025182064 0.0015640866 0.0025857692 0.0092542984 0.7892790000 0.1127980000 0.0477040000 0.0345730000 0.2936100000 0.3003670000 113353283 0 402718720 4.0546431541 3.9961514473 4.2485232353 138 5.4800000000 0.0025671506 0.0015713552 0.0025857692 0.0092360200 0.4709800000 0.1127800000 0.0574020000 0.0000010000 0.2986240000 0.0019390000 113356059 0 402718720 4.0550665855 3.9962964058 4.2508368492 139 5.5200000000 0.0024762305 0.0015778651 0.0025857692 0.0092256447 0.5005350000 0.1127730000 0.0569020000 0.0346250000 0.2940520000 0.0019470000 113358835 0 402718720 4.0554676056 3.9959921837 4.2530956268 140 5.5600000000 0.0024943224 0.0015844112 0.0025857692 0.0092189856 0.4611420000 0.1127770000 0.0453760000 0.0000000000 0.3008140000 0.0019380000 113361611 0 402718720 4.0557384491 3.9955599308 4.2553648949 141 5.6000000000 0.0025863810 0.0015915174 0.0025863810 0.0092719985 0.7888120000 0.1126550000 0.0424610000 0.0346800000 0.2960710000 0.3027100000 113364387 0 402718720 4.0558023453 3.9952862263 4.2596335411 142 5.6400000000 0.0025817216 0.0015984906 0.0025863810 0.0092796772 0.4725480000 0.1127020000 0.0544590000 0.0000000000 0.3032110000 0.0019380000 113367163 0 402718720 4.0557155609 3.9948089123 4.2616815567 143 5.6800000000 0.0025376896 0.0016050585 0.0025863810 0.0092835453 0.5289320000 0.1242650000 0.0451210000 0.0410340000 0.3155490000 0.0026900000 113369939 0 402718720 4.0555586815 3.9943025112 4.2635836601 144 5.7200000000 0.0026069731 0.0016120162 0.0026069731 0.0092812898 0.4973410000 0.1367400000 0.0549670000 0.0000000000 0.3034550000 0.0019360000 113372715 0 402718720 4.0550770760 3.9944820404 4.2655682564 145 5.7600000000 0.0025977739 0.0016188145 0.0026069731 0.0092714415 0.8241440000 0.1284650000 0.0569460000 0.0346340000 0.2986510000 0.3052030000 113375491 0 402718720 4.0544500351 3.9944667816 4.2673349380 146 5.8000000000 0.0026414925 0.0016258192 0.0026414925 0.0092740358 0.4633820000 0.1125330000 0.0451740000 0.0000010000 0.3034970000 0.0019330000 113378267 0 402718720 4.0538415909 3.9947485924 4.2692785263 147 5.8400000000 0.0026170812 0.0016325625 0.0026414925 0.0092660804 0.4949910000 0.1124920000 0.0472860000 0.0347110000 0.2983110000 0.0019400000 113381043 0 402718720 4.0531654358 3.9937944412 4.2708148956 148 5.8800000000 0.0027166326 0.0016398873 0.0027166326 0.0092485133 0.4697920000 0.1083360000 0.0570930000 0.0000010000 0.3021360000 0.0019670000 113383819 0 402718720 4.0522689819 3.9932034016 4.2722148895 149 5.9200000000 0.0027322019 0.0016472182 0.0027322019 0.0092322416 0.8007600000 0.1123620000 0.0476200000 0.0346980000 0.2987460000 0.3070800000 113386595 0 402718720 4.0513148308 3.9931230545 4.2739710808 150 5.9600000000 0.0028228192 0.0016550556 0.0028228192 0.0092164334 0.4752040000 0.1122410000 0.0550390000 0.0000010000 0.3057370000 0.0019350000 113389371 0 402718720 4.0503892899 3.9929866791 4.2760028839 151 6.0000000000 0.0027854252 0.0016625415 0.0028228192 0.0091979637 0.5042980000 0.1121350000 0.0547190000 0.0345960000 0.3006530000 0.0019430000 113392147 0 402718720 4.0492591858 3.9927494526 4.2777647972 152 6.0400000000 0.0028194317 0.0016701526 0.0028228192 0.0091836852 0.4742970000 0.1110830000 0.0550850000 0.0000010000 0.3059350000 0.0019380000 113394923 0 402718720 4.0481505394 3.9925680161 4.2796621323 153 6.0800000000 0.0028647310 0.0016779603 0.0028647310 0.0091721295 0.8489200000 0.1209720000 0.0546540000 0.0345730000 0.3105600000 0.3278730000 113397699 0 402718720 4.0470757484 3.9923732281 4.2819848061 154 6.1200000000 0.0028909203 0.0016858366 0.0028909203 0.0091567920 0.5212800000 0.1458050000 0.0662220000 0.0000010000 0.3070570000 0.0019360000 113400475 0 402718720 4.0458245277 3.9919652939 4.2839627266 155 6.1600000000 0.0028299629 0.0016932181 0.0028909203 0.0091379710 0.4974870000 0.1118980000 0.0500850000 0.0342240000 0.2989720000 0.0020380000 113403251 0 402718720 4.0444049835 3.9916768074 4.2859873772 156 6.2000000000 0.0029316067 0.0017011565 0.0029316067 0.0091489072 0.4750540000 0.1078180000 0.0564260000 0.0000010000 0.3086080000 0.0019380000 113406027 0 402718720 4.0415196419 3.9908666611 4.2901697159 157 6.2400000000 0.0030177261 0.0017095423 0.0030177261 0.0091323603 0.8122290000 0.1117850000 0.0545650000 0.0344690000 0.3024110000 0.3087390000 113408803 0 402718720 4.0401053429 3.9908530712 4.2924919128 158 6.2800000000 0.0031395264 0.0017185928 0.0031395264 0.0091156480 0.4737990000 0.1117820000 0.0526640000 0.0000010000 0.3071570000 0.0019290000 113411579 0 402718720 4.0386056900 3.9905354977 4.2944707870 159 6.3200000000 0.0032256159 0.0017280710 0.0032256159 0.0091026708 0.5056800000 0.1117940000 0.0547970000 0.0344380000 0.3024440000 0.0019340000 113414355 0 402718720 4.0369601250 3.9904122353 4.2965040207 160 6.3600000000 0.0033104457 0.0017379608 0.0033104457 0.0090869565 0.4761900000 0.1118590000 0.0552410000 0.0000010000 0.3068940000 0.0019260000 113417131 0 402718720 4.0354032516 3.9905860424 4.2986450195 161 6.4000000000 0.0033212758 0.0017477950 0.0033212758 0.0090773969 0.8122300000 0.1117710000 0.0548820000 0.0344560000 0.3022580000 0.3085960000 113419907 0 402718720 4.0337262154 3.9905204773 4.3005394936 162 6.4400000000 0.0034415196 0.0017582501 0.0034415196 0.0090849721 0.4756220000 0.1109740000 0.0553560000 0.0000010000 0.3070940000 0.0019260000 113422683 0 402718720 4.0319390297 3.9904110432 4.3023695946 163 6.4800000000 0.0035138095 0.0017690204 0.0035138095 0.0090771816 0.5212330000 0.1366440000 0.0454950000 0.0344720000 0.3024120000 0.0019270000 113425459 0 402718720 4.0303783417 3.9904708862 4.3040661812 164 6.5200000000 0.0036671385 0.0017805943 0.0036671385 0.0090633298 0.4673980000 0.1119060000 0.0458080000 0.0000000000 0.3074780000 0.0019230000 113428235 0 402718720 4.0288634300 3.9906466007 4.3061184883 165 6.5600000000 0.0037386471 0.0017924613 0.0037386471 0.0090552415 0.8510950000 0.1394720000 0.0643150000 0.0346120000 0.3030400000 0.3093710000 113431011 0 402718720 4.0272789001 3.9904944897 4.3081912994 166 6.6000000000 0.0039662905 0.0018055567 0.0039662905 0.0090413766 0.4697000000 0.1119130000 0.0480370000 0.0000010000 0.3075440000 0.0019230000 113433787 0 402718720 4.0258278847 3.9906435013 4.3100948334 167 6.6400000000 0.0039773742 0.0018185616 0.0039773742 0.0090316453 0.4968810000 0.1118430000 0.0454480000 0.0343830000 0.3029970000 0.0019280000 113436563 0 402718720 4.0243377686 3.9909894466 4.3123764992 168 6.6800000000 0.0040998217 0.0018321405 0.0040998217 0.0090160695 0.4773730000 0.1117980000 0.0552260000 0.0000000000 0.3081390000 0.0019270000 113439339 0 402718720 4.0228533745 3.9905157089 4.3138904572 169 6.7200000000 0.0042246901 0.0018462976 0.0042246901 0.0090019108 0.8042370000 0.1117700000 0.0455340000 0.0343150000 0.3029730000 0.3093640000 113442115 0 402718720 4.0213661194 3.9904377460 4.3153662682 170 6.7600000000 0.0042846561 0.0018606409 0.0042846561 0.0089878813 0.4800900000 0.1117120000 0.0577780000 0.0000000000 0.3083810000 0.0019250000 113444891 0 402718720 4.0202403069 3.9903194904 4.3171529770 171 6.8000000000 0.0042961794 0.0018748838 0.0042961794 0.0089752207 0.5060780000 0.1115540000 0.0548740000 0.0343120000 0.3031150000 0.0019350000 113447667 0 402718720 4.0192127228 3.9895579815 4.3186545372 172 6.8400000000 0.0043882709 0.0018894965 0.0043882709 0.0089589672 0.4771510000 0.1114020000 0.0552560000 0.0000010000 0.3082710000 0.0019330000 113450443 0 402718720 4.0180487633 3.9890902042 4.3197774887 173 6.8800000000 0.0043430943 0.0019036792 0.0043882709 0.0089446145 0.8228430000 0.1213230000 0.0576190000 0.0337580000 0.3003110000 0.3095380000 113453219 0 402718720 4.0170979500 3.9885375500 4.3207650185 174 6.9200000000 0.0043682568 0.0019178434 0.0043882709 0.0089539457 0.4642770000 0.1070640000 0.0453110000 0.0000000000 0.3097470000 0.0018610000 113455995 0 402718720 4.0162591934 3.9880518913 4.3218212128 175 6.9600000000 0.0043726680 0.0019318710 0.0043882709 0.0089723715 0.5201720000 0.1237760000 0.0563960000 0.0342080000 0.3035600000 0.0019350000 113458771 0 402718720 4.0154213905 3.9874718189 4.3229703903 176 7.0000000000 0.0043711052 0.0019457303 0.0043882709 0.0089814710 0.4774690000 0.1104140000 0.0552940000 0.0000010000 0.3095390000 0.0019260000 113461547 0 402718720 4.0145716667 3.9869740009 4.3236317635 177 7.0400000000 0.0044262931 0.0019597447 0.0044262931 0.0090077733 0.8152500000 0.1102510000 0.0568070000 0.0341150000 0.3037350000 0.3100430000 113464323 0 402718720 4.0139713287 3.9864115715 4.3245267868 178 7.0800000000 0.0044637928 0.0019738124 0.0044637928 0.0090146238 0.4775550000 0.1101980000 0.0552060000 0.0000010000 0.3099280000 0.0019230000 113467099 0 402718720 4.0133895874 3.9858589172 4.3252863884 179 7.1200000000 0.0044292891 0.0019875302 0.0044637928 0.0090220330 0.5066140000 0.1101640000 0.0571610000 0.0335210000 0.3035380000 0.0019270000 113469875 0 402718720 4.0129060745 3.9854366779 4.3260612488 180 7.1600000000 0.0044372366 0.0020011396 0.0044637928 0.0090503565 0.4680330000 0.1102300000 0.0456520000 0.0000010000 0.3099250000 0.0019230000 113472651 0 402718720 4.0124993324 3.9849205017 4.3270182610 181 7.2000000000 0.0044590966 0.0020147195 0.0044637928 0.0090699451 0.8141590000 0.1102260000 0.0571260000 0.0334170000 0.3034620000 0.3096260000 113475427 0 402718720 4.0119781494 3.9845790863 4.3275308609 182 7.2400000000 0.0045641111 0.0020287272 0.0045641111 0.0090891181 0.4683310000 0.1081560000 0.0480930000 0.0000010000 0.3098510000 0.0019260000 113478203 0 402718720 4.0114936829 3.9844467640 4.3280639648 183 7.2800000000 0.0046046148 0.0020428031 0.0046046148 0.0091155926 0.5450090000 0.1205780000 0.0868870000 0.0342380000 0.3009600000 0.0020230000 113480979 0 402718720 4.0111012459 3.9841208458 4.3283929825 184 7.3200000000 0.0048228516 0.0020579120 0.0048228516 0.0092584234 0.4800430000 0.1084750000 0.0546160000 0.0000000000 0.3147210000 0.0019190000 113483755 0 402718720 4.0103721619 3.9837269783 4.3291931152 185 7.3600000000 0.0050340644 0.0020739993 0.0050340644 0.0092826553 0.8367600000 0.1372250000 0.0538890000 0.0337530000 0.3025870000 0.3089900000 113486531 0 402718720 4.0100564957 3.9835653305 4.3297219276 186 7.4000000000 0.0052152183 0.0020908876 0.0052152183 0.0092848670 0.4726950000 0.1058370000 0.0546480000 0.0000010000 0.3099690000 0.0019220000 113489307 0 402718720 4.0095357895 3.9832704067 4.3310365677 187 7.4400000000 0.0052495664 0.0021077789 0.0052495664 0.0092721063 0.5037090000 0.1089210000 0.0570350000 0.0331630000 0.3023520000 0.0019240000 113492083 0 402718720 4.0092124939 3.9830069542 4.3325691223 188 7.4800000000 0.0053138118 0.0021248323 0.0053138118 0.0092587140 0.4753630000 0.1087180000 0.0551900000 0.0000010000 0.3092230000 0.0019180000 113494859 0 402718720 4.0090017319 3.9827594757 4.3340349197 189 7.5200000000 0.0053553255 0.0021419249 0.0053553255 0.0092528922 0.8064850000 0.1084430000 0.0546800000 0.0337490000 0.3014480000 0.3078200000 113497635 0 402718720 4.0088500977 3.9824533463 4.3355474472 190 7.5600000000 0.0053959014 0.0021590510 0.0053959014 0.0092626017 0.4744540000 0.1085120000 0.0552170000 0.0000000000 0.3084930000 0.0019130000 113500411 0 402718720 4.0088543892 3.9825725555 4.3371753693 191 7.6000000000 0.0055533210 0.0021768221 0.0055533210 0.0092521468 0.5032980000 0.1084400000 0.0573060000 0.0341750000 0.3012090000 0.0018470000 113503187 0 402718720 4.0091495514 3.9824445248 4.3388328552 192 7.6400000000 0.0059535424 0.0021964925 0.0059535424 0.0092415061 0.4871790000 0.1083380000 0.0680240000 0.0000010000 0.3085930000 0.0019050000 113505963 0 402718720 4.0092096329 3.9822123051 4.3411698341 193 7.6800000000 0.0065322821 0.0022189577 0.0065322821 0.0092310465 0.8187560000 0.1178010000 0.0574960000 0.0339700000 0.3010290000 0.3081310000 113508739 0 402718720 4.0092058182 3.9821381569 4.3435101509 194 7.7200000000 0.0071481150 0.0022443658 0.0071481150 0.0092189993 0.4944570000 0.1085990000 0.0742300000 0.0000010000 0.3094020000 0.0019000000 113511515 0 402718720 4.0093359947 3.9821486473 4.3456501961 195 7.7600000000 0.0077068284 0.0022723784 0.0077068284 0.0092065335 0.5375780000 0.1218520000 0.0760490000 0.0341530000 0.3032900000 0.0019090000 113514291 0 402718720 4.0095229149 3.9820113182 4.3475074768 196 7.8000000000 0.0085575366 0.0023044455 0.0085575366 0.0091958308 0.4979470000 0.1085840000 0.0766040000 0.0000010000 0.3105340000 0.0019040000 113517067 0 402718720 4.0096511841 3.9817957878 4.3495159149 197 7.8400000000 0.0101665668 0.0023443548 0.0101665668 0.0091887500 0.8700980000 0.1051510000 0.1126700000 0.0333830000 0.3061280000 0.3124430000 113519843 0 402718720 4.0098037720 3.9815375805 4.3522472382 198 7.8800000000 0.0101185469 0.0023836184 0.0101665668 0.0091737845 0.5123090000 0.1211320000 0.0551290000 0.0000010000 0.3330210000 0.0026570000 113522619 0 402718720 4.0100274086 3.9814329147 4.3531999588 199 7.9200000000 0.0104440311 0.0024241230 0.0104440311 0.0091637609 0.5482600000 0.1419840000 0.0630240000 0.0338230000 0.3071920000 0.0019070000 113525395 0 402718720 4.0102972984 3.9811985493 4.3540201187 200 7.9600000000 0.0099845659 0.0024619252 0.0104440311 0.0091560890 0.5014570000 0.1084000000 0.0764630000 0.0000000000 0.3143620000 0.0019030000 113528171 0 402718720 4.0105175972 3.9809398651 4.3543100357 201 8.0000000000 0.0096455310 0.0024976645 0.0104440311 0.0091429117 0.8798700000 0.1053500000 0.1126190000 0.0343020000 0.3098110000 0.3174590000 113530947 0 402718720 4.0106477737 3.9807672501 4.3547601700 202 8.0400000000 0.0105833830 0.0025376928 0.0105833830 0.0091374300 0.4852590000 0.1091640000 0.0575450000 0.0000010000 0.3163070000 0.0019080000 113533723 0 402718720 4.0108790398 3.9807050228 4.3561768532 203 8.0800000000 0.0100529613 0.0025747138 0.0105833830 0.0091282727 0.5277210000 0.1206610000 0.0600540000 0.0349960000 0.3096530000 0.0020000000 113536499 0 402718720 4.0109901428 3.9807596207 4.3559541702 204 8.1200000000 0.0100024249 0.0026111242 0.0105833830 0.0091269681 0.5496920000 0.1099130000 0.1186530000 0.0000010000 0.3188770000 0.0019060000 113539275 0 402718720 4.0111007690 3.9808247089 4.3564500809 205 8.1600000000 0.0103675844 0.0026489606 0.0105833830 0.0091300112 0.8490520000 0.1101130000 0.0666150000 0.0350130000 0.3146810000 0.3222930000 113542051 0 402718720 4.0111680031 3.9809048176 4.3574438095 206 8.1999999990 0.0107106166 0.0026880948 0.0107106166 0.0091330439 0.5177990000 0.1103550000 0.0837190000 0.0000000000 0.3215470000 0.0018380000 113544827 0 402718720 4.0111455917 3.9812300205 4.3579635620 207 8.2400000000 0.0098144058 0.0027225215 0.0107106166 0.0091560477 0.5320900000 0.1105620000 0.0665370000 0.0352810000 0.3174600000 0.0019070000 113547603 0 402718720 4.0112657547 3.9813115597 4.3573193550 208 8.2799999990 0.0099941213 0.0027574811 0.0107106166 0.0091908728 0.6153120000 0.1310870000 0.0712580000 0.0000010000 0.4071500000 0.0052010000 113550379 0 402718720 4.0112547874 3.9814517498 4.3576049805 209 8.3200000000 0.0097190822 0.0027907902 0.0107106166 0.0092168420 0.8810400000 0.1106700000 0.0854750000 0.0354950000 0.3208400000 0.3282150000 113553155 0 402718720 4.0112271309 3.9813246727 4.3572802544 210 8.3599999990 0.0094709937 0.0028226007 0.0107106166 0.0092137351 0.5105900000 0.1236410000 0.0577110000 0.0000010000 0.3269860000 0.0018980000 113555931 0 402718720 4.0111007690 3.9814305305 4.3571648598 211 8.4000000000 0.0091571324 0.0028526221 0.0107106166 0.0092039433 0.5395990000 0.1109530000 0.0668530000 0.0350470000 0.3244960000 0.0019000000 113558707 0 402718720 4.0111060143 3.9815616608 4.3566684723 212 8.4399999990 0.0094016129 0.0028835136 0.0107106166 0.0092022075 0.5012620000 0.1110940000 0.0578080000 0.0000010000 0.3301110000 0.0018970000 113561483 0 402718720 4.0110907555 3.9818546772 4.3564357758 213 8.4800000000 0.0093603786 0.0029139214 0.0107106166 0.0092125313 0.8965280000 0.1211200000 0.0763410000 0.0359420000 0.3276900000 0.3350820000 113564259 0 402718720 4.0111064911 3.9818572998 4.3560857773 214 8.5200000000 0.0090232603 0.0029424697 0.0107106166 0.0092075631 0.5051710000 0.1114420000 0.0581720000 0.0000000000 0.3333070000 0.0018960000 113567035 0 402718720 4.0111465454 3.9819352627 4.3551778793 215 8.5600000000 0.0093850363 0.0029724352 0.0107106166 0.0092000718 0.5480400000 0.1115530000 0.0668860000 0.0363440000 0.3310060000 0.0019030000 113569811 0 402718720 4.0110449791 3.9823534489 4.3551645279 216 8.6000000000 0.0092983358 0.0030017217 0.0107106166 0.0092043617 0.5189050000 0.1245630000 0.0552630000 0.0000010000 0.3368150000 0.0019010000 113572587 0 402718720 4.0109777451 3.9826960564 4.3545193672 217 8.6400000000 0.0088762473 0.0030287933 0.0107106166 0.0092116907 0.9145770000 0.1079620000 0.0921810000 0.0360540000 0.3353180000 0.3426980000 113575363 0 402718720 4.0108361244 3.9829931259 4.3535966873 218 8.6800000000 0.0087418463 0.0030549999 0.0107106166 0.0092251591 0.5607720000 0.1120870000 0.1050120000 0.0000000000 0.3414060000 0.0019010000 113578139 0 402718720 4.0107302666 3.9834001064 4.3528952599 219 8.7200000000 0.0091147302 0.0030826699 0.0107106166 0.0092407180 0.5610870000 0.1249730000 0.0572280000 0.0368660000 0.3397560000 0.0019050000 113580915 0 402718720 4.0105924606 3.9838211536 4.3529152870 220 8.7600000000 0.0084508350 0.0031070707 0.0107106166 0.0092470303 0.5253640000 0.1122710000 0.0646290000 0.0000000000 0.3461900000 0.0019120000 113583691 0 402718720 4.0105366707 3.9841866493 4.3515529633 221 8.8000000000 0.0086201681 0.0031320168 0.0107106166 0.0092629922 0.8992110000 0.1100590000 0.0565970000 0.0359940000 0.3447880000 0.3514100000 113586467 0 402718720 4.0104379654 3.9843995571 4.3513436317 222 8.8400000000 0.0082570277 0.0031551025 0.0107106166 0.0092652367 0.5267460000 0.1125110000 0.0653390000 0.0000010000 0.3465110000 0.0020070000 113589243 0 402718720 4.0103235245 3.9847569466 4.3503870964 223 8.8800000000 0.0080494042 0.0031770500 0.0107106166 0.0092760707 0.5700870000 0.1265590000 0.0576020000 0.0367880000 0.3468480000 0.0019150000 113592019 0 402718720 4.0100193024 3.9852139950 4.3494920731 224 8.9200000000 0.0080213705 0.0031986764 0.0107106166 0.0093019355 0.5160180000 0.1125820000 0.0479890000 0.0000010000 0.3531560000 0.0019100000 113594795 0 402718720 4.0097193718 3.9855077267 4.3487672806 225 8.9600000000 0.0080285212 0.0032201424 0.0107106166 0.0093216209 0.9669380000 0.1126250000 0.1113220000 0.0364920000 0.3494540000 0.3566760000 113597571 0 402718720 4.0093760490 3.9860880375 4.3479490280 226 9.0000000000 0.0075005149 0.0032390821 0.0107106166 0.0093464966 0.5329300000 0.1098060000 0.0645400000 0.0000000000 0.3562950000 0.0019140000 113600347 0 402718720 4.0091304779 3.9864099026 4.3465161324 227 9.0400000000 0.0076728887 0.0032586143 0.0107106166 0.0093661184 0.5518200000 0.1126010000 0.0477650000 0.0360430000 0.3531200000 0.0019170000 113603123 0 402718720 4.0087342262 3.9868617058 4.3459019661 228 9.0800000000 0.0080974726 0.0032798374 0.0107106166 0.0093974866 0.5727970000 0.1085500000 0.1013350000 0.0000010000 0.3606810000 0.0018540000 113605899 0 402718720 4.0083360672 3.9873511791 4.3455843925 229 9.1200000000 0.0080050528 0.0033004715 0.0107106166 0.0094272776 0.9328710000 0.1125260000 0.0641720000 0.0361040000 0.3561700000 0.3635250000 113608675 0 402718720 4.0079236031 3.9874291420 4.3445200920 230 9.1600000000 0.0077060177 0.0033196261 0.0107106166 0.0094336682 0.5240800000 0.1125620000 0.0481490000 0.0000010000 0.3610590000 0.0019290000 113611451 0 402718720 4.0074653625 3.9881649017 4.3428506851 231 9.2000000000 0.0075310976 0.0033378575 0.0107106166 0.0094492139 0.6120930000 0.1374300000 0.0775780000 0.0369580000 0.3578150000 0.0019260000 113614227 0 402718720 4.0069198608 3.9886119366 4.3416609764 232 9.2400000000 0.0076086987 0.0033562663 0.0107106166 0.0094685796 0.5385000000 0.1125950000 0.0603950000 0.0000010000 0.3631820000 0.0019310000 113617003 0 402718720 4.0064029694 3.9892473221 4.3407001495 233 9.2800000000 0.0080066323 0.0033762250 0.0107106166 0.0094982505 0.9677960000 0.1340770000 0.0669530000 0.0371300000 0.3608630000 0.3683810000 113619779 0 402718720 4.0057978630 3.9899055958 4.3403215408 234 9.3200000000 0.0078051230 0.0033951519 0.0107106166 0.0095242905 0.5382850000 0.1125340000 0.0604000000 0.0000010000 0.3629100000 0.0020420000 113622555 0 402718720 4.0051703453 3.9905428886 4.3385977745 235 9.3600000000 0.0078043458 0.0034139144 0.0107106166 0.0095366600 0.5689130000 0.1124780000 0.0551470000 0.0363890000 0.3625750000 0.0019390000 113625331 0 402718720 4.0045490265 3.9907798767 4.3376979828 236 9.4000000000 0.0078043314 0.0034325179 0.0107106166 0.0095398916 0.5274710000 0.1124560000 0.0456340000 0.0000000000 0.3670570000 0.0019350000 113628107 0 402718720 4.0038366318 3.9914083481 4.3365106583 237 9.4400000000 0.0077739200 0.0034508360 0.0107106166 0.0095491638 0.9647720000 0.1084210000 0.0830270000 0.0367220000 0.3642520000 0.3719660000 113630883 0 402718720 4.0030679703 3.9918270111 4.3354392052 238 9.4800000000 0.0078881048 0.0034694800 0.0107106166 0.0096221260 0.5426020000 0.1122310000 0.0573350000 0.0000010000 0.3707000000 0.0019420000 113633659 0 402718720 4.0012450218 3.9939675331 4.3329348564 239 9.5200000000 0.0078339521 0.0034877414 0.0107106166 0.0096506470 0.5632880000 0.1120550000 0.0452080000 0.0362420000 0.3674530000 0.0019410000 113636435 0 402718720 4.0002908707 3.9947125912 4.3317461014 240 9.5600000000 0.0079451157 0.0035063138 0.0107106166 0.0096761810 0.5597500000 0.1301050000 0.0550160000 0.0000000000 0.3722880000 0.0019390000 113639211 0 402718720 3.9992208481 3.9963469505 4.3302507401 241 9.6000000000 0.0079720216 0.0035248437 0.0107106166 0.0097435772 0.9495240000 0.1116630000 0.0566210000 0.0369500000 0.3666480000 0.3772460000 113641987 0 402718720 3.9981620312 3.9971845150 4.3292679787 242 9.6400000000 0.0082192486 0.0035442421 0.0107106166 0.0098147609 0.5430930000 0.1112250000 0.0548430000 0.0000010000 0.3746790000 0.0019460000 113644763 0 402718720 3.9971466064 3.9982283115 4.3282394409 243 9.6800000000 0.0083296159 0.0035639350 0.0107106166 0.0098702230 0.6013500000 0.1336510000 0.0596320000 0.0363310000 0.3693780000 0.0019480000 113647539 0 402718720 3.9960696697 3.9992499352 4.3266434669 244 9.7200000000 0.0084418142 0.0035839263 0.0107106166 0.0099244572 0.5448220000 0.1111120000 0.0575350000 0.0000000000 0.3738890000 0.0018860000 113650315 0 402718720 3.9949555397 4.0002803802 4.3254647255 245 9.7600000000 0.0083120335 0.0036032247 0.0107106166 0.0099680857 0.9551840000 0.1110720000 0.0546320000 0.0369530000 0.3719970000 0.3801240000 113653091 0 402718720 3.9939839840 4.0007925034 4.3239359856 246 9.8000000000 0.0084652957 0.0036229892 0.0107106166 0.0099941418 0.5649090000 0.1110710000 0.0763620000 0.0000010000 0.3751220000 0.0019440000 113655867 0 402718720 3.9927926064 4.0018925667 4.3224258423 247 9.8400000000 0.0084372880 0.0036424803 0.0107106166 0.0100324674 0.5871760000 0.1111550000 0.0641760000 0.0368240000 0.3726750000 0.0019440000 113658643 0 402718720 3.9917790890 4.0030269623 4.3209624290 248 9.8800000000 0.0084401481 0.0036618257 0.0107106166 0.0100822766 0.5655530000 0.1111950000 0.0548370000 0.0000010000 0.3963710000 0.0026870000 113661419 0 402718720 3.9906897545 4.0040793419 4.3191909790 249 9.9200000000 0.0085727302 0.0036815482 0.0107106166 0.0101352619 0.9803920000 0.1345060000 0.0544380000 0.0362510000 0.3733240000 0.3814630000 113664195 0 402718720 3.9896817207 4.0048918724 4.3176603317 250 9.9600000000 0.0085543841 0.0037010396 0.0107106166 0.0101788822 0.5427250000 0.1075380000 0.0552080000 0.0000000000 0.3776260000 0.0019380000 113666971 0 402718720 3.9886760712 4.0057868958 4.3161759377 251 10.0000000000 0.0085194567 0.0037202365 0.0107106166 0.0102218030 0.5792780000 0.1116340000 0.0543210000 0.0369310000 0.3740330000 0.0019400000 113669747 0 402718720 3.9875874519 4.0071310997 4.3145270348 252 10.0400000000 0.0086600883 0.0037398390 0.0107106166 0.0102822670 0.5386820000 0.1117510000 0.0450380000 0.0000000000 0.3795440000 0.0019330000 113672523 0 402718720 3.9866106510 4.0082459450 4.3129935265 253 10.0800000000 0.0086943042 0.0037594219 0.0107106166 0.0103174660 0.9562490000 0.1120480000 0.0494760000 0.0369140000 0.3732580000 0.3841380000 113675299 0 402718720 3.9857380390 4.0093359947 4.3112182617 254 10.1200000000 0.0087858550 0.0037792110 0.0107106166 0.0103530311 0.5418650000 0.1121920000 0.0496910000 0.0000000000 0.3776340000 0.0019290000 113678075 0 402718720 3.9847829342 4.0105633736 4.3096551895 255 10.1600000000 0.0088823121 0.0037992232 0.0107106166 0.0104015202 0.5945090000 0.1250810000 0.0537880000 0.0369070000 0.3763780000 0.0019300000 113680851 0 402718720 3.9837472439 4.0116925240 4.3080205917 256 10.2000000000 0.0087136086 0.0038184200 0.0107106166 0.0104427961 0.5508210000 0.1125070000 0.0541370000 0.0000010000 0.3818200000 0.0019330000 113683627 0 402718720 3.9829239845 4.0125880241 4.3061599731 257 10.2400000000 0.0087689543 0.0038376828 0.0107106166 0.0104856064 1.0424130000 0.1306550000 0.0721320000 0.0486900000 0.3970040000 0.3935010000 113710979 0 402718720 3.9819517136 4.0136251450 4.3047518730 258 10.2800000000 0.0086233914 0.0038562320 0.0107106166 0.0104971064 0.5808970000 0.1435520000 0.0568250000 0.0000010000 0.3780420000 0.0020320000 113764955 0 402718720 3.9811775684 4.0145072937 4.3028593063 259 10.3200000000 0.0085788583 0.0038744661 0.0107106166 0.0104986651 0.5846110000 0.1127960000 0.0539500000 0.0370300000 0.3784760000 0.0019320000 113767731 0 402718720 3.9802730083 4.0153536797 4.3011951447 260 10.3600000000 0.0087165451 0.0038930895 0.0107106166 0.0105163465 0.5551450000 0.1128170000 0.0564940000 0.0000010000 0.3834770000 0.0019270000 113770507 0 402718720 3.9792587757 4.0167350769 4.2995734215 261 10.4000000000 0.0087324260 0.0039116310 0.0107106166 0.0105495209 0.9664850000 0.1087830000 0.0530490000 0.0362090000 0.3796210000 0.3883910000 113773283 0 402718720 3.9784784317 4.0174217224 4.2980623245 262 10.4400000000 0.0085307341 0.0039292612 0.0107106166 0.0105610090 0.5561340000 0.1129260000 0.0564350000 0.0000010000 0.3844140000 0.0019260000 113776059 0 402718720 3.9776356220 4.0179781914 4.2962408066 263 10.4800000000 0.0086042872 0.0039470369 0.0107106166 0.0105609478 0.6068580000 0.1332930000 0.0563810000 0.0372780000 0.3775210000 0.0019370000 113778835 0 402718720 3.9767706394 4.0189156532 4.2947640419 264 10.5200000000 0.0085091684 0.0039643177 0.0107106166 0.0105639804 0.5562720000 0.1128880000 0.0562300000 0.0000010000 0.3847850000 0.0019250000 113781611 0 402718720 3.9758484364 4.0197610855 4.2929439545 265 10.5600000000 0.0085867681 0.0039817609 0.0107106166 0.0105893983 0.9781700000 0.1129320000 0.0534530000 0.0367030000 0.3823100000 0.3923310000 113784387 0 402718720 3.9749622345 4.0200138092 4.2916979790 266 10.6000000000 0.0086134765 0.0039991734 0.0107106166 0.0105876352 0.5525700000 0.1088550000 0.0531060000 0.0000010000 0.3882530000 0.0019150000 113787163 0 402718720 3.9742283821 4.0205335617 4.2899489403 267 10.6400000000 0.0086322408 0.0040165257 0.0107106166 0.0105714777 0.5883200000 0.1088610000 0.0555280000 0.0373580000 0.3842170000 0.0019130000 113789939 0 402718720 3.9733622074 4.0212388039 4.2883787155 268 10.6800000000 0.0085264267 0.0040333537 0.0107106166 0.0105619561 0.5768450000 0.1325100000 0.0535150000 0.0000010000 0.3884580000 0.0019050000 113792715 0 402718720 3.9725353718 4.0216321945 4.2864956856 269 10.7200000000 0.0086164763 0.0040503913 0.0107106166 0.0105601871 0.9861120000 0.1129770000 0.0533460000 0.0374300000 0.3857330000 0.3961780000 113795491 0 402718720 3.9716682434 4.0219807625 4.2851171494 270 10.7600000000 0.0087221200 0.0040676940 0.0107106166 0.0105651474 0.5563140000 0.1088780000 0.0528020000 0.0000000000 0.3922770000 0.0019070000 113798267 0 402718720 3.9708497524 4.0224156380 4.2834830284 271 10.8000000000 0.0086975917 0.0040847785 0.0107106166 0.0105591328 0.5954160000 0.1130090000 0.0554840000 0.0375060000 0.3871150000 0.0018540000 113801043 0 402718720 3.9701395035 4.0230250359 4.2812886238 272 10.8400000000 0.0087018888 0.0041017532 0.0107106166 0.0105453726 0.5702420000 0.1129480000 0.0648850000 0.0000010000 0.3900510000 0.0019040000 113803819 0 402718720 3.9692380428 4.0236549377 4.2795772552 273 10.8800000000 0.0086450968 0.0041183955 0.0107106166 0.0105502457 1.0010650000 0.1229620000 0.0531340000 0.0369490000 0.3882760000 0.3992990000 113806595 0 402718720 3.9684717655 4.0241036415 4.2776517868 274 10.9200000000 0.0086833872 0.0041350560 0.0107106166 0.0105490541 0.5729370000 0.1129360000 0.0644860000 0.0000000000 0.3931670000 0.0018900000 113809371 0 402718720 3.9675753117 4.0243430138 4.2760138512 275 10.9600000000 0.0088319024 0.0041521355 0.0107106166 0.0105357338 0.6502640000 0.1374480000 0.0832300000 0.0377360000 0.3894950000 0.0018930000 113812147 0 402718720 3.9669933319 4.0244817734 4.2741317749 276 11.0000000000 0.0088128000 0.0041690220 0.0107106166 0.0105207506 0.5819680000 0.1129510000 0.0734730000 0.0000000000 0.3932010000 0.0018820000 113814923 0 402718720 3.9663686752 4.0246520042 4.2723226547 277 11.0400000000 0.0086808000 0.0041853100 0.0107106166 0.0105117045 1.0076690000 0.1129360000 0.0616900000 0.0370970000 0.3918280000 0.4036590000 113817699 0 402718720 3.9654307365 4.0246505737 4.2706999779 278 11.0800000000 0.0087259067 0.0042016430 0.0107106166 0.0105047207 0.5648410000 0.1128840000 0.0526980000 0.0000010000 0.3969180000 0.0018830000 113820475 0 402718720 3.9647018909 4.0247936249 4.2690734863 279 11.1200000000 0.0086963726 0.0042177532 0.0107106166 0.0104899240 0.5996120000 0.1129340000 0.0547840000 0.0370330000 0.3925160000 0.0018780000 113823251 0 402718720 3.9640977383 4.0247492790 4.2673583031 280 11.1600000000 0.0086401617 0.0042335475 0.0107106166 0.0104719663 0.5626720000 0.1128730000 0.0527300000 0.0000010000 0.3947230000 0.0018800000 113826027 0 402718720 3.9633708000 4.0251955986 4.2655425072 281 11.2000000000 0.0087319491 0.0042495560 0.0107106166 0.0104560657 1.0038120000 0.1128590000 0.0525160000 0.0376630000 0.3942730000 0.4060390000 113828803 0 402718720 3.9625384808 4.0254673958 4.2641019821 282 11.2400000000 0.0086688129 0.0042652272 0.0107106166 0.0104397961 0.5674110000 0.1128720000 0.0548150000 0.0000000000 0.3973890000 0.0018700000 113831579 0 402718720 3.9618237019 4.0258121490 4.2623252869 283 11.2800000000 0.0085482318 0.0042803615 0.0107106166 0.0104224069 0.6295610000 0.1209460000 0.0723700000 0.0376350000 0.3962650000 0.0018740000 113834355 0 402718720 3.9605491161 4.0258998871 4.2607660294 284 11.3200000000 0.0086522922 0.0042957556 0.0107106166 0.0104044222 0.5842090000 0.1294270000 0.0549080000 0.0000010000 0.3975270000 0.0018680000 113837131 0 402718720 3.9598774910 4.0262055397 4.2592387199 285 11.3600000000 0.0087550301 0.0043114022 0.0107106166 0.0103864515 1.0170800000 0.1128550000 0.0570620000 0.0378030000 0.3973460000 0.4115430000 113839907 0 402718720 3.9588403702 4.0264782906 4.2575426102 286 11.4000000000 0.0087183323 0.0043268110 0.0107106166 0.0103687855 0.5692250000 0.1128650000 0.0521200000 0.0000010000 0.4019060000 0.0018560000 113842683 0 402718720 3.9580571651 4.0265946388 4.2554101944 287 11.4400000000 0.0087882206 0.0043423560 0.0107106166 0.0103509909 0.6069190000 0.1128480000 0.0519040000 0.0376940000 0.4021350000 0.0018580000 113845459 0 402718720 3.9570226669 4.0265340805 4.2538604736 288 11.4800000000 0.0086945705 0.0043574678 0.0107106166 0.0103334616 0.5853890000 0.1257290000 0.0519990000 0.0000000000 0.4053220000 0.0018550000 113848235 0 402718720 3.9561150074 4.0265297890 4.2514495850 289 11.5200000000 0.0087759355 0.0043727567 0.0107106166 0.0103163976 1.0304420000 0.1128610000 0.0539980000 0.0371360000 0.4068090000 0.4191620000 113851011 0 402718720 3.9543569088 4.0262994766 4.2502226830 290 11.5600000000 0.0087136347 0.0043877252 0.0107106166 0.0102992651 0.5789970000 0.1128610000 0.0540750000 0.0000010000 0.4097220000 0.0018540000 113853787 0 402718720 3.9531888962 4.0262246132 4.2478680611 291 11.6000000000 0.0086974893 0.0044025354 0.0107106166 0.0102859764 0.6169570000 0.1128600000 0.0538750000 0.0378300000 0.4100560000 0.0018530000 113856563 0 402718720 3.9517393112 4.0259351730 4.2461647987 292 11.6400000000 0.0085703339 0.0044168087 0.0107106166 0.0102687685 0.6007200000 0.1327980000 0.0542320000 0.0000010000 0.4113490000 0.0018510000 113859339 0 402718720 3.9502305984 4.0252323151 4.2443351746 293 11.6800000000 0.0085877674 0.0044310440 0.0107106166 0.0102576782 1.0422020000 0.1128190000 0.0564670000 0.0378890000 0.4093110000 0.4252320000 113862115 0 402718720 3.9484856129 4.0246891975 4.2427263260 294 11.7200000000 0.0085818497 0.0044451624 0.0107106166 0.0102409142 0.6147730000 0.1127750000 0.0654010000 0.0000010000 0.4335350000 0.0025090000 113864891 0 402718720 3.9466354847 4.0246815681 4.2406353951 295 11.7600000000 0.0085199205 0.0044589752 0.0107106166 0.0102254793 0.6372630000 0.1264990000 0.0536700000 0.0377440000 0.4170170000 0.0018420000 113867667 0 402718720 3.9445574284 4.0245504379 4.2390336990 296 11.8000000000 0.0085449032 0.0044727790 0.0107106166 0.0102088482 0.5859830000 0.1127440000 0.0513130000 0.0000010000 0.4195970000 0.0018340000 113870443 0 402718720 3.9425137043 4.0244107246 4.2374110222 297 11.8400000000 0.0087014744 0.0044870170 0.0107106166 0.0101918460 1.0540140000 0.1127940000 0.0510470000 0.0371700000 0.4195310000 0.4329790000 113873219 0 402718720 3.9403250217 4.0243682861 4.2360582352 298 11.8800000000 0.0086102169 0.0045008532 0.0107106166 0.0101797167 0.5868000000 0.1127930000 0.0536110000 0.0000010000 0.4179500000 0.0019330000 113875995 0 402718720 3.9382991791 4.0241498947 4.2342839241 299 11.9200000000 0.0085961251 0.0045145498 0.0107106166 0.0101702083 0.6282270000 0.1127620000 0.0533940000 0.0377190000 0.4220320000 0.0018260000 113878771 0 402718720 3.9358215332 4.0242724419 4.2329096794 300 11.9600000000 0.0085098753 0.0045278675 0.0107106166 0.0101561542 0.6128280000 0.1329360000 0.0557500000 0.0000010000 0.4218180000 0.0018220000 113881547 0 402718720 3.9334874153 4.0239734650 4.2312417030 301 12.0000000000 0.0086232759 0.0045414736 0.0107106166 0.0101456530 1.0636440000 0.1127860000 0.0507000000 0.0372620000 0.4246670000 0.4377360000 113884323 0 402718720 3.9310765266 4.0242285728 4.2297539711 302 12.0400000000 0.0085633807 0.0045547911 0.0107106166 0.0101336644 0.6366590000 0.1207070000 0.0684640000 0.0000010000 0.4444600000 0.0024630000 113887099 0 402718720 3.9285736084 4.0245447159 4.2280697823 303 12.0800000000 0.0085690357 0.0045680395 0.0107106166 0.0101197908 0.6769670000 0.1458590000 0.0637650000 0.0377000000 0.4273090000 0.0018220000 113889875 0 402718720 3.9261620045 4.0245132446 4.2265377045 304 12.1200000000 0.0085649332 0.0045811871 0.0107106166 0.0101089493 0.5960380000 0.1127790000 0.0531260000 0.0000010000 0.4278020000 0.0018260000 113892651 0 402718720 3.9237511158 4.0243330002 4.2250885963 305 12.1600000000 0.0085644769 0.0045942471 0.0107106166 0.0101008856 1.0749920000 0.1128150000 0.0503520000 0.0377590000 0.4300320000 0.4435360000 113895427 0 402718720 3.9212188721 4.0247130394 4.2234997749 306 12.2000000000 0.0086192973 0.0046074009 0.0107106166 0.0100873549 0.5945690000 0.1087340000 0.0501070000 0.0000000000 0.4334010000 0.0018200000 113898203 0 402718720 3.9186599255 4.0251407623 4.2219152451 307 12.2400000000 0.0086429249 0.0046205459 0.0107106166 0.0100711366 0.6431870000 0.1128350000 0.0589360000 0.0370840000 0.4319970000 0.0018230000 113900979 0 402718720 3.9161655903 4.0252590179 4.2202773094 308 12.2800000000 0.0085637141 0.0046333484 0.0107106166 0.0100553326 0.6213900000 0.1320290000 0.0555030000 0.0000010000 0.4315220000 0.0018220000 113903755 0 402718720 3.9138407707 4.0246143341 4.2190537453 309 12.3200000000 0.0085716760 0.0046460938 0.0107106166 0.0100455314 1.0748990000 0.1129060000 0.0418610000 0.0376410000 0.4339030000 0.4480860000 113906531 0 402718720 3.9113376141 4.0243177414 4.2177562714 310 12.3600000000 0.0085855257 0.0046588016 0.0107106166 0.0100369065 0.6014220000 0.1087920000 0.0523580000 0.0000000000 0.4379270000 0.0018270000 113909307 0 402718720 3.9088468552 4.0245389938 4.2162728310 311 12.4000000000 0.0085826349 0.0046714185 0.0107106166 0.0100211367 0.6499590000 0.1129180000 0.0612200000 0.0377170000 0.4357600000 0.0018260000 113912083 0 402718720 3.9061012268 4.0245714188 4.2152028084 312 12.4400000000 0.0085679367 0.0046839073 0.0107106166 0.0100053560 0.6073980000 0.1129230000 0.0529050000 0.0000010000 0.4392150000 0.0018250000 113914859 0 402718720 3.9037101269 4.0241284370 4.2139759064 313 12.4800000000 0.0086872177 0.0046966974 0.0107106166 0.0099907266 1.1015760000 0.1227620000 0.0505160000 0.0370760000 0.4378610000 0.4528450000 113917635 0 402718720 3.9012842178 4.0239715576 4.2129006386 314 12.5200000000 0.0086305151 0.0047092255 0.0107106166 0.0099751357 0.6317090000 0.1259890000 0.0615060000 0.0000000000 0.4418620000 0.0018250000 113920411 0 402718720 3.8984606266 4.0235543251 4.2121152878 315 12.5600000000 0.0085681519 0.0047214761 0.0107106166 0.0099608899 0.6514390000 0.1128930000 0.0589060000 0.0371180000 0.4401640000 0.0018320000 113923187 0 402718720 3.8961706161 4.0224804878 4.2112421989 316 12.6000000000 0.0086917523 0.0047340402 0.0107106166 0.0099500161 0.6127000000 0.1129310000 0.0528970000 0.0000010000 0.4445170000 0.0018290000 113925963 0 402718720 3.8937942982 4.0218844414 4.2104167938 317 12.6400000000 0.0086524216 0.0047464011 0.0107106166 0.0099396185 1.1423100000 0.1129540000 0.0761180000 0.0490140000 0.4460400000 0.4576640000 113928739 0 402718720 3.8917367458 4.0208964348 4.2094874382 318 12.6800000000 0.0087024616 0.0047588415 0.0107106166 0.0099418508 0.6364340000 0.1230300000 0.0645420000 0.0000010000 0.4464870000 0.0018220000 113931515 0 402718720 3.8895967007 4.0201835632 4.2086648941 319 12.7200000000 0.0087663587 0.0047714043 0.0107106166 0.0099380096 0.7008480000 0.1129900000 0.1041100000 0.0370630000 0.4443180000 0.0018290000 113934291 0 402718720 3.8875098228 4.0199675560 4.2075295448 320 12.7600000000 0.0087825432 0.0047839391 0.0107106166 0.0099239867 0.6417690000 0.1129450000 0.0790520000 0.0000000000 0.4473940000 0.0018300000 113937067 0 402718720 3.8856234550 4.0198092461 4.2062897682 321 12.8000000000 0.0087818420 0.0047963936 0.0107106166 0.0099088755 1.1115900000 0.1129230000 0.0529980000 0.0370070000 0.4461180000 0.4620170000 113939843 0 402718720 3.8839869499 4.0190901756 4.2049717903 322 12.8400000000 0.0089296782 0.0048092299 0.0107106166 0.0098964163 0.6260900000 0.1129360000 0.0616990000 0.0000010000 0.4490900000 0.0018300000 113942619 0 402718720 3.8825302124 4.0179777145 4.2038578987 323 12.8800000000 0.0089509105 0.0048220524 0.0107106166 0.0098904016 0.6826110000 0.1244790000 0.0703060000 0.0375540000 0.4478960000 0.0018310000 113945395 0 402718720 3.8808028698 4.0177202225 4.2025709152 324 12.9200000000 0.0089896759 0.0048349154 0.0107106166 0.0098789476 0.6280730000 0.1128950000 0.0616680000 0.0000010000 0.4511340000 0.0018290000 113948171 0 402718720 3.8789653778 4.0172953606 4.2010722160 325 12.9600000000 0.0090532759 0.0048478950 0.0107106166 0.0098663632 1.1249570000 0.1128830000 0.0646190000 0.0376170000 0.4447420000 0.4645590000 113950947 0 402718720 3.8775017262 4.0165119171 4.1996741295 326 13.0000000000 0.0087937023 0.0048599987 0.0107106166 0.0098566721 0.6283550000 0.1111400000 0.0616080000 0.0000010000 0.4532340000 0.0018290000 113953723 0 402718720 3.8760657310 4.0153727531 4.1981167793 327 13.0400000000 0.0088745141 0.0048722755 0.0107106166 0.0098479621 0.6781390000 0.1256140000 0.0614130000 0.0369460000 0.4517850000 0.0018300000 113956499 0 402718720 3.8743357658 4.0149431229 4.1964898109 328 13.0800000000 0.0090208584 0.0048849236 0.0107106166 0.0098360111 0.6315140000 0.1129200000 0.0617540000 0.0000010000 0.4545050000 0.0017870000 113959275 0 402718720 3.8728537560 4.0144772530 4.1951351166 329 13.1200000000 0.0091194389 0.0048977945 0.0107106166 0.0098261419 1.1430930000 0.1128500000 0.0701190000 0.0369190000 0.4531590000 0.4695040000 113962051 0 402718720 3.8713567257 4.0138835907 4.1934227943 330 13.1600000000 0.0092633097 0.0049110233 0.0107106166 0.0098160109 0.6317640000 0.1128120000 0.0618060000 0.0000000000 0.4547470000 0.0018310000 113964827 0 402718720 3.8699700832 4.0132918358 4.1916337013 331 13.2000000000 0.0092634773 0.0049241728 0.0107106166 0.0098061796 0.6955980000 0.1382620000 0.0648210000 0.0375310000 0.4525860000 0.0018350000 113967603 0 402718720 3.8685421944 4.0128288269 4.1896853447 332 13.2400000000 0.0092219934 0.0049371180 0.0107106166 0.0097973830 0.6405840000 0.1087260000 0.0727880000 0.0000000000 0.4566690000 0.0018400000 113970379 0 402718720 3.8670611382 4.0120282173 4.1877326965 333 13.2800000000 0.0091034239 0.0049496294 0.0107106166 0.0097924981 1.1573880000 0.1312350000 0.0648340000 0.0374460000 0.4519540000 0.4713570000 113973155 0 402718720 3.8659093380 4.0117940903 4.1852283478 334 13.3200000000 0.0091257598 0.0049621328 0.0107106166 0.0097825374 0.6332750000 0.1126950000 0.0617700000 0.0000000000 0.4564180000 0.0018340000 113975931 0 402718720 3.8645317554 4.0115365982 4.1829376221 335 13.3600000000 0.0092925848 0.0049750595 0.0107106166 0.0097736557 0.7105480000 0.1126890000 0.1084930000 0.0369130000 0.4499330000 0.0019370000 113978707 0 402718720 3.8632330894 4.0100636482 4.1810088158 336 13.4000000000 0.0093055423 0.0049879479 0.0107106166 0.0097999463 0.6521950000 0.1127400000 0.0703060000 0.0000010000 0.4660320000 0.0024800000 113981483 0 402718720 3.8620824814 4.0100903511 4.1783561707 337 13.4400000000 0.0093785748 0.0050009764 0.0107106166 0.0098094237 1.2421440000 0.1452360000 0.1175850000 0.0484090000 0.4582020000 0.4721560000 113984259 0 402718720 3.8607199192 4.0107007027 4.1750121117 338 13.4800000000 0.0092985863 0.0050136913 0.0107106166 0.0098066683 0.6258830000 0.1125630000 0.0532450000 0.0000010000 0.4576770000 0.0018390000 113987035 0 402718720 3.8594112396 4.0103607178 4.1726083755 339 13.5200000000 0.0092446832 0.0050261721 0.0107106166 0.0098053140 0.7272150000 0.1256820000 0.1049480000 0.0373410000 0.4568260000 0.0018400000 113989811 0 402718720 3.8580238819 4.0107426643 4.1699490547 340 13.5600000000 0.0094005028 0.0050390377 0.0107106166 0.0097933378 0.6438110000 0.1124750000 0.0707050000 0.0000010000 0.4582330000 0.0018380000 113992587 0 402718720 3.8564898968 4.0114355087 4.1671380997 341 13.6000000000 0.0094472682 0.0050519651 0.0107106166 0.0097789440 1.1862320000 0.1124950000 0.1052540000 0.0368220000 0.4576350000 0.4734670000 113995363 0 402718720 3.8552200794 4.0116620064 4.1646685600 342 13.6400000000 0.0096481442 0.0050654042 0.0107106166 0.0097646319 0.6761000000 0.1125090000 0.1030750000 0.0000010000 0.4581120000 0.0018410000 113998139 0 402718720 3.8538417816 4.0116019249 4.1619896889 343 13.6800000000 0.0099069178 0.0050795194 0.0107106166 0.0097509085 0.7484810000 0.1412020000 0.0971460000 0.0373990000 0.4695810000 0.0024950000 114000915 0 402718720 3.8529510498 4.0112371445 4.1594028473 344 13.7200000000 0.0099813677 0.0050937690 0.0107106166 0.0097448709 0.7522220000 0.1450810000 0.1411440000 0.0000010000 0.4635740000 0.0018420000 114003691 0 402718720 3.8520829678 4.0114040375 4.1561174393 345 13.7600000000 0.0097298687 0.0051072070 0.0107106166 0.0097363403 1.1498450000 0.1124250000 0.0742350000 0.0372630000 0.4519430000 0.4734010000 114006467 0 402718720 3.8510286808 4.0115208626 4.1530075073 346 13.8000000000 0.0097887637 0.0051207375 0.0107106166 0.0097226834 0.6179350000 0.1124090000 0.0446230000 0.0000010000 0.4584780000 0.0018390000 114009243 0 402718720 3.8501253128 4.0116505623 4.1502170563 347 13.8400000000 0.0098979762 0.0051345047 0.0107106166 0.0097086677 0.6602580000 0.1123920000 0.0510480000 0.0367460000 0.4576400000 0.0018460000 114012019 0 402718720 3.8491096497 4.0115370750 4.1473431587 348 13.8800000000 0.0099711632 0.0051484032 0.0107106166 0.0096951743 0.6690440000 0.1083700000 0.1001310000 0.0000000000 0.4581190000 0.0018420000 114014795 0 402718720 3.8480529785 4.0112171173 4.1447124481 349 13.9200000000 0.0098346574 0.0051618308 0.0107106166 0.0096829929 1.1511470000 0.1123640000 0.0710190000 0.0366760000 0.4575390000 0.4729770000 114017571 0 402718720 3.8471574783 4.0106983185 4.1419034004 350 13.9600000000 0.0098660877 0.0051752716 0.0107106166 0.0096729744 0.6305820000 0.1083080000 0.0613440000 0.0000000000 0.4585020000 0.0018460000 114020347 0 402718720 3.8463683128 4.0104084015 4.1386771202 351 14.0000000000 0.0099248458 0.0051888031 0.0107106166 0.0096623864 0.6709120000 0.1123210000 0.0620170000 0.0365290000 0.4576230000 0.0018400000 114023123 0 402718720 3.8455882072 4.0099081993 4.1358728409 352 14.0400000000 0.0100966645 0.0052027459 0.0107106166 0.0096557909 0.6438430000 0.1122880000 0.0707370000 0.0000000000 0.4583900000 0.0018390000 114025899 0 402718720 3.8447630405 4.0097489357 4.1327924728 353 14.0800000000 0.0099903708 0.0052163086 0.0107106166 0.0096475658 1.1952190000 0.1458710000 0.0833100000 0.0371940000 0.4552310000 0.4730190000 114028675 0 402718720 3.8441095352 4.0093722343 4.1300191879 354 14.1200000000 0.0098447576 0.0052293833 0.0107106166 0.0096363588 0.6277330000 0.1122730000 0.0560170000 0.0000010000 0.4570070000 0.0018450000 114031451 0 402718720 3.8429872990 4.0094957352 4.1270804405 355 14.1600000000 0.0100034932 0.0052428315 0.0107106166 0.0096228985 0.6890540000 0.1121740000 0.0834880000 0.0371330000 0.4538180000 0.0018410000 114034227 0 402718720 3.8421750069 4.0095210075 4.1246795654 356 14.2000000000 0.0099483738 0.0052560493 0.0107106166 0.0096094524 0.6157850000 0.1121420000 0.0425250000 0.0000000000 0.4586850000 0.0018350000 114037003 0 402718720 3.8412659168 4.0093188286 4.1219320297 357 14.2400000000 0.0098883091 0.0052690248 0.0107106166 0.0095961620 1.1427560000 0.1121520000 0.0619830000 0.0364630000 0.4583190000 0.4732440000 114039779 0 402718720 3.8406033516 4.0095238686 4.1192955971 358 14.2800000000 0.0102272211 0.0052828745 0.0107106166 0.0095866900 0.6533900000 0.1120710000 0.0790940000 0.0000010000 0.4598020000 0.0018260000 114042555 0 402718720 3.8399188519 4.0099773407 4.1172780991 359 14.3200000000 0.0101762209 0.0052965050 0.0107106166 0.0095798685 0.6621230000 0.1120610000 0.0530170000 0.0363810000 0.4582190000 0.0018310000 114045331 0 402718720 3.8395137787 4.0089612007 4.1146821976 360 14.3600000000 0.0101793399 0.0053100685 0.0107106166 0.0095676164 0.6467790000 0.1248330000 0.0650500000 0.0000000000 0.4541790000 0.0020700000 114048107 0 402718720 3.8393173218 4.0080013275 4.1123914719 361 14.4000000000 0.0101343095 0.0053234320 0.0107106166 0.0095644324 1.1631110000 0.1298250000 0.0624580000 0.0369590000 0.4592700000 0.4739870000 114050883 0 402718720 3.8386554718 4.0078334808 4.1101136208 362 14.4400000000 0.0102178203 0.0053369524 0.0107106166 0.0095535331 0.6294020000 0.1119240000 0.0530650000 0.0000010000 0.4619790000 0.0018340000 114053659 0 402718720 3.8382701874 4.0079197884 4.1073093414 363 14.4800000000 0.0100627681 0.0053499712 0.0107106166 0.0095407961 0.7046550000 0.1355300000 0.0712340000 0.0368630000 0.4585790000 0.0018350000 114056435 0 402718720 3.8377678394 4.0070166588 4.1052217484 364 14.5200000000 0.0101859439 0.0053632568 0.0107106166 0.0095326141 0.6398640000 0.1119240000 0.0615920000 0.0000010000 0.4639000000 0.0018390000 114059211 0 402718720 3.8374266624 4.0067429543 4.1028256416 365 14.5600000000 0.0103943078 0.0053770405 0.0107106166 0.0095221425 1.1377560000 0.1079330000 0.0522950000 0.0364720000 0.4629630000 0.4774860000 114061987 0 402718720 3.8367621899 4.0074558258 4.1003327370 366 14.6000000000 0.0103192786 0.0053905439 0.0107106166 0.0095129524 0.6486160000 0.1118830000 0.0701970000 0.0000000000 0.4640780000 0.0018520000 114064763 0 402718720 3.8368313313 4.0074687004 4.0979933739 367 14.6400000000 0.0102774538 0.0054038597 0.0107106166 0.0095042212 0.6790830000 0.1079140000 0.0693140000 0.0359040000 0.4634990000 0.0018390000 114067539 0 402718720 3.8365910053 4.0061740875 4.0955958366 368 14.6800000000 0.0102310227 0.0054169770 0.0107106166 0.0094948848 0.6546850000 0.1079340000 0.0781080000 0.0000010000 0.4661740000 0.0018500000 114070315 0 402718720 3.8362102509 4.0055642128 4.0932292938 369 14.7200000000 0.0103246039 0.0054302768 0.0107106166 0.0094857717 1.1721290000 0.1296620000 0.0546020000 0.0363440000 0.4650950000 0.4857310000 114073091 0 402718720 3.8354578018 4.0056185722 4.0908336639 370 14.7600000000 0.0102733616 0.0054433663 0.0107106166 0.0094736861 0.7010640000 0.1445620000 0.0714930000 0.0000000000 0.4825410000 0.0018510000 114075867 0 402718720 3.8352262974 4.0058808327 4.0887088776 371 14.8000000000 0.0102046961 0.0054562000 0.0107106166 0.0094612159 0.7206990000 0.1112290000 0.1042170000 0.0366660000 0.4661090000 0.0018490000 114078643 0 402718720 3.8344433308 4.0063872337 4.0860219002 372 14.8400000000 0.0104899118 0.0054697315 0.0107106166 0.0094544823 0.6404230000 0.1078580000 0.0608740000 0.0000010000 0.4692210000 0.0018530000 114081419 0 402718720 3.8338811398 4.0066270828 4.0830821991 373 14.8800000000 0.0103619024 0.0054828473 0.0107106166 0.0094479081 1.1814390000 0.1270630000 0.0710310000 0.0365930000 0.4638020000 0.4823240000 114084195 0 402718720 3.8337049484 4.0069141388 4.0803518295 374 14.9200000000 0.0103840791 0.0054959522 0.0107106166 0.0094524587 0.6371230000 0.1117630000 0.0526850000 0.0000000000 0.4702130000 0.0018380000 114086971 0 402718720 3.8329877853 4.0073075294 4.0780243874 375 14.9600000000 0.0105133327 0.0055093318 0.0107106166 0.0094656813 0.6666190000 0.1079130000 0.0519390000 0.0355960000 0.4687510000 0.0017910000 114089747 0 402718720 3.8320598602 4.0062427521 4.0760197639 376 15.0000000000 0.0104909949 0.0055225809 0.0107106166 0.0094562725 0.6544390000 0.1118350000 0.0610730000 0.0000000000 0.4783430000 0.0024800000 114092523 0 402718720 3.8319203854 4.0056867599 4.0737385750 377 15.0400000000 0.0103850951 0.0055354789 0.0107106166 0.0094442143 1.2314200000 0.1443620000 0.0825790000 0.0464710000 0.4738210000 0.4835610000 114095299 0 402718720 3.8306221962 4.0066347122 4.0712919235 378 15.0800000000 0.0105696674 0.0055487968 0.0107106166 0.0094538530 0.6596020000 0.1259920000 0.0602730000 0.0000000000 0.4708590000 0.0018310000 114098075 0 402718720 3.8304834366 4.0063552856 4.0685153008 379 15.1200000000 0.0108478656 0.0055627785 0.0108478656 0.0094495986 0.6717980000 0.1119840000 0.0524520000 0.0363920000 0.4684950000 0.0018290000 114100851 0 402718720 3.8302266598 4.0055985451 4.0661263466 380 15.1600000000 0.0105833579 0.0055759906 0.0108478656 0.0094371616 0.6695380000 0.1120020000 0.0890230000 0.0000010000 0.4659200000 0.0019330000 114103627 0 402718720 3.8294608593 4.0055322647 4.0632610321 381 15.2000000000 0.0109113511 0.0055899941 0.0109113511 0.0094259209 1.1673850000 0.1248210000 0.0529910000 0.0355010000 0.4697510000 0.4836860000 114106403 0 402718720 3.8284816742 4.0058536530 4.0610651970 382 15.2400000000 0.0110317711 0.0056042396 0.0110317711 0.0094147664 0.6475030000 0.1118980000 0.0612620000 0.0000000000 0.4718760000 0.0018250000 114109179 0 402718720 3.8281922340 4.0055837631 4.0581464767 383 15.2800000000 0.0105993254 0.0056172816 0.0110317711 0.0094025976 0.6915010000 0.1226630000 0.0526630000 0.0355670000 0.4774020000 0.0024730000 114111955 0 402718720 3.8272888660 4.0052990913 4.0559930801 384 15.3200000000 0.0108331628 0.0056308647 0.0110317711 0.0093910358 0.7139900000 0.1440130000 0.0824910000 0.0000000000 0.4850210000 0.0018140000 114114731 0 402718720 3.8259854317 4.0057940483 4.0533299446 385 15.3600000000 0.0107111856 0.0056440603 0.0110317711 0.0093813560 1.1868860000 0.1323820000 0.0730160000 0.0360350000 0.4644490000 0.4803590000 114117507 0 402718720 3.8248314857 4.0060210228 4.0510697365 386 15.4000000000 0.0107784262 0.0056573618 0.0110317711 0.0093707597 0.6479580000 0.1120130000 0.0610650000 0.0000000000 0.4724090000 0.0018200000 114120283 0 402718720 3.8240849972 4.0062098503 4.0481433868 387 15.4400000000 0.0108895665 0.0056708817 0.0110317711 0.0093589502 0.7213990000 0.1119900000 0.1012500000 0.0353860000 0.4703060000 0.0018120000 114123059 0 402718720 3.8227839470 4.0068483353 4.0453782082 388 15.4800000000 0.0107815517 0.0056840535 0.0110317711 0.0093510702 0.6893720000 0.1096410000 0.1036060000 0.0000000000 0.4736540000 0.0018150000 114125835 0 402718720 3.8214316368 4.0074720383 4.0434064865 389 15.5200000000 0.0106177162 0.0056967364 0.0110317711 0.0093479882 1.1565750000 0.1082180000 0.0599440000 0.0354480000 0.4705750000 0.4817410000 114128611 0 402718720 3.8204889297 4.0077052116 4.0406651497 390 15.5600000000 0.0108208247 0.0057098751 0.0110317711 0.0093414963 0.6904240000 0.1119200000 0.1034460000 0.0000010000 0.4725850000 0.0018070000 114131387 0 402718720 3.8188157082 4.0082149506 4.0383992195 391 15.6000000000 0.0104800183 0.0057220750 0.0110317711 0.0093324266 0.6774980000 0.1119680000 0.0585400000 0.0352340000 0.4692870000 0.0018060000 114134163 0 402718720 3.8174090385 4.0089440346 4.0358686447 392 15.6400000000 0.0105892802 0.0057344913 0.0110317711 0.0093328960 0.6460300000 0.1118640000 0.0607480000 0.0000010000 0.4709560000 0.0018070000 114136939 0 402718720 3.8159236908 4.0096459389 4.0334672928 393 15.6800000000 0.0106244180 0.0057469339 0.0110317711 0.0093307658 1.1696120000 0.1319360000 0.0548710000 0.0357350000 0.4663810000 0.4800250000 114139715 0 402718720 3.8152008057 4.0099873543 4.0309972763 394 15.7200000000 0.0106009180 0.0057592536 0.0110317711 0.0093260860 0.6906860000 0.1116890000 0.1064110000 0.0000000000 0.4701140000 0.0018070000 114142491 0 402718720 3.8138670921 4.0104947090 4.0286388397 395 15.7600000000 0.0106594553 0.0057716592 0.0110317711 0.0093193214 0.7054210000 0.1115740000 0.0907600000 0.0350810000 0.4655220000 0.0018130000 114145267 0 402718720 3.8117177486 4.0114297867 4.0259785652 396 15.8000000000 0.0105836634 0.0057838107 0.0110317711 0.0093150767 0.6900020000 0.1115840000 0.1073700000 0.0000010000 0.4685610000 0.0018150000 114148043 0 402718720 3.8110852242 4.0122766495 4.0231189728 397 15.8400000000 0.0105866147 0.0057959085 0.0110317711 0.0093193692 1.1480870000 0.1115830000 0.0532570000 0.0350210000 0.4706910000 0.4768630000 114150819 0 402718720 3.8095269203 4.0129451752 4.0210938454 398 15.8800000000 0.0106068971 0.0058079964 0.0110317711 0.0093287968 0.6625420000 0.1211050000 0.0727780000 0.0000010000 0.4661770000 0.0018110000 114153595 0 402718720 3.8083164692 4.0124807358 4.0184659958 399 15.9200000000 0.0106098158 0.0058200310 0.0110317711 0.0093213148 0.6926980000 0.1113280000 0.0776390000 0.0354950000 0.4657440000 0.0018150000 114156371 0 402718720 3.8071076870 4.0123796463 4.0162887573 400 15.9600000000 0.0105909100 0.0058319582 0.0110317711 0.0093105963 0.6423270000 0.1111850000 0.0608240000 0.0000010000 0.4678260000 0.0018110000 114159147 0 402718720 3.8056671619 4.0136046410 4.0137553215 401 16.0000000000 0.0104948673 0.0058435864 0.0110317711 0.0093153355 1.1379750000 0.1110150000 0.0520700000 0.0348390000 0.4649710000 0.4744110000 114161923 0 402718720 3.8049657345 4.0136775970 4.0114240646 402 16.0400000000 0.0104106786 0.0058549474 0.0110317711 0.0093117463 0.6976530000 0.1240180000 0.1032580000 0.0000000000 0.4678770000 0.0018140000 114164699 0 402718720 3.8034813404 4.0139546394 4.0092058182 403 16.0800000000 0.0103707127 0.0058661527 0.0110317711 0.0093135799 0.6735670000 0.1108270000 0.0604970000 0.0353650000 0.4644190000 0.0017700000 114167475 0 402718720 3.8022227287 4.0146470070 4.0069308281 404 16.1200000000 0.0105641382 0.0058777814 0.0110317711 0.0093290508 0.6290780000 0.1072320000 0.0515830000 0.0000010000 0.4677780000 0.0018120000 114170251 0 402718720 3.8020873070 4.0153770447 4.0043716431 405 16.1600000000 0.0105147846 0.0058892308 0.0110317711 0.0093502780 1.1681320000 0.1107640000 0.0853590000 0.0346910000 0.4637800000 0.4728570000 114173027 0 402718720 3.8007528782 4.0149936676 4.0026035309 406 16.2000000000 0.0105591267 0.0059007330 0.0110317711 0.0093452995 0.6550100000 0.1073120000 0.0771350000 0.0000000000 0.4680780000 0.0018090000 114175803 0 402718720 3.8002605438 4.0165576935 4.0001907349 407 16.2400000000 0.0106831472 0.0059124834 0.0110317711 0.0093609000 0.7092610000 0.1074000000 0.1015250000 0.0349470000 0.4628880000 0.0018150000 114178579 0 402718720 3.7993721962 4.0168142319 3.9983990192 408 16.2800000000 0.0106358305 0.0059240602 0.0110317711 0.0093658648 0.7187810000 0.1434470000 0.1077120000 0.0000010000 0.4651040000 0.0018160000 114181355 0 402718720 3.7987835407 4.0169181824 3.9962487221 409 16.3200000000 0.0106830988 0.0059356960 0.0110317711 0.0093591055 1.1764070000 0.1111470000 0.0815340000 0.0352350000 0.4614930000 0.4862200000 114184131 0 402718720 3.7978572845 4.0170183182 3.9942204952 410 16.3600000000 0.0105613712 0.0059469782 0.0110317711 0.0093496411 0.7282310000 0.1435290000 0.1163750000 0.0000000000 0.4658110000 0.0018230000 114186907 0 402718720 3.7974321842 4.0181112289 3.9920072556 411 16.3999999990 0.0105060181 0.0059580707 0.0110317711 0.0093565923 0.6688650000 0.1111820000 0.0606820000 0.0345430000 0.4599330000 0.0018260000 114189683 0 402718720 3.7971656322 4.0185642242 3.9899811745 412 16.4400000000 0.0104665654 0.0059690137 0.0110317711 0.0093621491 0.6750530000 0.1076380000 0.1022710000 0.0000000000 0.4626280000 0.0018220000 114192459 0 402718720 3.7969121933 4.0191965103 3.9877858162 413 16.4800000000 0.0103897061 0.0059797175 0.0110317711 0.0093605599 1.1237870000 0.1113070000 0.0521870000 0.0350830000 0.4585150000 0.4660020000 114195235 0 402718720 3.7961671352 4.0192565918 3.9857189655 414 16.5200000000 0.0105403634 0.0059907336 0.0110317711 0.0093527900 0.6782130000 0.1113080000 0.1037730000 0.0000010000 0.4606090000 0.0018240000 114198011 0 402718720 3.7960526943 4.0196270943 3.9835782051 415 16.5599999990 0.0106041394 0.0060018502 0.0110317711 0.0093420324 0.7323300000 0.1383430000 0.1000010000 0.0351410000 0.4562980000 0.0018360000 114200787 0 402718720 3.7956075668 4.0206193924 3.9810981750 416 16.6000000000 0.0104925456 0.0060126452 0.0110317711 0.0093354788 0.6433460000 0.1112880000 0.0700060000 0.0000000000 0.4595090000 0.0018340000 114203563 0 402718720 3.7952816486 4.0206522942 3.9789309502 417 16.6400000000 0.0105049498 0.0060234181 0.0110317711 0.0093299298 1.1601750000 0.1241940000 0.0784870000 0.0349950000 0.4573660000 0.4644260000 114206339 0 402718720 3.7944326401 4.0213060379 3.9765625000 418 16.6800000000 0.0105358884 0.0060342135 0.0110317711 0.0093294573 0.6803050000 0.1302990000 0.0885340000 0.0000000000 0.4589180000 0.0018400000 114209115 0 402718720 3.7935378551 4.0223541260 3.9741353989 419 16.7199999990 0.0105214724 0.0060449229 0.0110317711 0.0093414038 0.6621980000 0.1113370000 0.0551460000 0.0344870000 0.4586680000 0.0018400000 114211891 0 402718720 3.7929069996 4.0236010551 3.9713900089 420 16.7600000000 0.0109038763 0.0060564918 0.0110317711 0.0093633871 0.6827080000 0.1112470000 0.1094390000 0.0000010000 0.4594690000 0.0018430000 114214667 0 402718720 3.7932765484 4.0238838196 3.9689228535 421 16.8000000000 0.0108448956 0.0060678657 0.0110317711 0.0093600125 1.1401130000 0.1112480000 0.0786700000 0.0343570000 0.4539780000 0.4611490000 114217443 0 402718720 3.7924299240 4.0244660378 3.9661486149 422 16.8400000000 0.0109519074 0.0060794393 0.0110317711 0.0093549830 0.6454140000 0.1277030000 0.0649000000 0.0000010000 0.4501090000 0.0019530000 114220219 0 402718720 3.7931177616 4.0253624916 3.9633109570 423 16.8799999990 0.0109179178 0.0060908778 0.0110317711 0.0093500490 0.6644610000 0.1112760000 0.0530290000 0.0343040000 0.4625140000 0.0025210000 114222995 0 402718720 3.7922711372 4.0259375572 3.9607260227 424 16.9200000000 0.0108647915 0.0061021370 0.0110317711 0.0093447660 0.6920030000 0.1442020000 0.0920370000 0.0000000000 0.4531960000 0.0018490000 114225771 0 402718720 3.7922081947 4.0269670486 3.9576671124 425 16.9600000000 0.0109215379 0.0061134768 0.0110317711 0.0093613619 1.1394040000 0.1112270000 0.0878710000 0.0348220000 0.4487720000 0.4559970000 114228547 0 402718720 3.7921512127 4.0272798538 3.9546146393 426 17.0000000000 0.0109918192 0.0061249283 0.0110317711 0.0093603386 0.6543030000 0.1111620000 0.0928300000 0.0000010000 0.4477270000 0.0018600000 114231323 0 402718720 3.7924406528 4.0274353027 3.9517340660 427 17.0400000000 0.0109611712 0.0061362544 0.0110317711 0.0093502261 0.6578740000 0.1112640000 0.0623040000 0.0347400000 0.4469760000 0.0018570000 114234099 0 402718720 3.7923603058 4.0270614624 3.9488947392 428 17.0800000000 0.0110494746 0.0061477338 0.0110494746 0.0093394140 0.6427440000 0.1210980000 0.0744310000 0.0000010000 0.4446340000 0.0018530000 114236875 0 402718720 3.7939713001 4.0278301239 3.9455106258 429 17.1200000000 0.0110429348 0.0061591446 0.0110494746 0.0093296225 1.1051970000 0.1112020000 0.0710810000 0.0341460000 0.4406440000 0.4474000000 114239651 0 402718720 3.7943868637 4.0279674530 3.9423205853 430 17.1600000000 0.0110870283 0.0061706048 0.0110870283 0.0093190110 0.6375870000 0.1111990000 0.0836970000 0.0000010000 0.4401160000 0.0018500000 114242427 0 402718720 3.7941000462 4.0283021927 3.9393603802 431 17.2000000000 0.0109941391 0.0061817963 0.0110870283 0.0093083160 0.6414120000 0.1113020000 0.0535470000 0.0346780000 0.4392970000 0.0018530000 114245203 0 402718720 3.7942016125 4.0290575027 3.9358520508 432 17.2400000000 0.0111222668 0.0061932325 0.0111222668 0.0093025870 0.6545070000 0.1074760000 0.1057560000 0.0000010000 0.4386910000 0.0018570000 114247979 0 402718720 3.7940471172 4.0295944214 3.9329068661 433 17.2800000000 0.0110343918 0.0062044130 0.0111222668 0.0093003331 1.1272430000 0.1075140000 0.1047590000 0.0337840000 0.4373350000 0.4431230000 114250755 0 402718720 3.7938253880 4.0298166275 3.9295465946 434 17.3200000000 0.0111266393 0.0062157546 0.0111266393 0.0092932478 0.6046250000 0.1112500000 0.0535140000 0.0000010000 0.4372660000 0.0018550000 114253531 0 402718720 3.7944147587 4.0303187370 3.9265520573 435 17.3600000000 0.0109875295 0.0062267242 0.0111266393 0.0092838086 0.6644110000 0.1112390000 0.0800540000 0.0339850000 0.4365330000 0.0018640000 114256307 0 402718720 3.7945272923 4.0316252708 3.9230918884 436 17.4000000000 0.0111315874 0.0062379739 0.0111315874 0.0092917819 0.6566500000 0.1112030000 0.1056990000 0.0000010000 0.4371580000 0.0018610000 114259083 0 402718720 3.7955234051 4.0321965218 3.9198851585 437 17.4400000000 0.0111521296 0.0062492191 0.0111521296 0.0093078844 1.0895890000 0.1111730000 0.0621690000 0.0346060000 0.4390430000 0.4418680000 114261859 0 402718720 3.7961654663 4.0324511528 3.9171357155 438 17.4800000000 0.0109031228 0.0062598444 0.0111521296 0.0093054726 0.6257020000 0.1153650000 0.0748520000 0.0000000000 0.4328880000 0.0018620000 114264635 0 402718720 3.7971358299 4.0325078964 3.9138474464 439 17.5200000000 0.0109115532 0.0062704406 0.0111521296 0.0093040447 0.6501010000 0.1112200000 0.0714780000 0.0345090000 0.4302690000 0.0018830000 114267411 0 402718720 3.7994053364 4.0329680443 3.9107463360 440 17.5600000000 0.0110138794 0.0062812211 0.0111521296 0.0093083010 0.6500670000 0.1112010000 0.1065100000 0.0000010000 0.4297410000 0.0018680000 114270187 0 402718720 3.8001222610 4.0333189964 3.9080727100 441 17.6000000000 0.0109930243 0.0062919055 0.0111521296 0.0093125493 1.0771450000 0.1112330000 0.0713560000 0.0345390000 0.4263410000 0.4329320000 114272963 0 402718720 3.8006768227 4.0338454247 3.9054214954 442 17.6400000000 0.0109018544 0.0063023352 0.0111521296 0.0093238047 0.6246710000 0.1238840000 0.0712860000 0.0000010000 0.4268890000 0.0018640000 114275739 0 402718720 3.8007631302 4.0334014893 3.9026868343 443 17.6800000000 0.0109833395 0.0063129018 0.0111521296 0.0093262665 0.6596310000 0.1111950000 0.0886780000 0.0338890000 0.4232440000 0.0018710000 114278515 0 402718720 3.8009157181 4.0329055786 3.9003489017 444 17.7200000000 0.0111334529 0.0063237589 0.0111521296 0.0093192291 0.6432100000 0.1111770000 0.1064180000 0.0000010000 0.4230010000 0.0018690000 114281291 0 402718720 3.8006386757 4.0329632759 3.8977634907 445 17.7600000000 0.0108090173 0.0063338382 0.0111521296 0.0093087487 1.0941130000 0.1111530000 0.0978860000 0.0338470000 0.4218540000 0.4286180000 114284067 0 402718720 3.8015296459 4.0335459709 3.8949284554 446 17.8000000000 0.0110559836 0.0063444259 0.0111521296 0.0092991839 0.6677460000 0.1326130000 0.1105770000 0.0000010000 0.4219210000 0.0018770000 114286843 0 402718720 3.8007347584 4.0338678360 3.8921883106 447 17.8400000000 0.0109154917 0.0063546520 0.0111521296 0.0092925644 0.6324430000 0.1111520000 0.0626360000 0.0344480000 0.4215660000 0.0018780000 114289619 0 402718720 3.8013172150 4.0343518257 3.8897173405 448 17.8800000000 0.0112260329 0.0063655256 0.0112260329 0.0092836483 0.6645600000 0.1344280000 0.1053140000 0.0000010000 0.4222360000 0.0018180000 114292395 0 402718720 3.8008792400 4.0346226692 3.8872170448 449 17.9200000000 0.0111651532 0.0063762152 0.0112260329 0.0092765628 1.1050540000 0.1112890000 0.1111730000 0.0343840000 0.4204690000 0.4269790000 114295171 0 402718720 3.8019340038 4.0335798264 3.8849940300 450 17.9600000000 0.0111657195 0.0063868586 0.0112260329 0.0092665108 0.6135850000 0.1112640000 0.0631960000 0.0000010000 0.4357150000 0.0025480000 114297947 0 402718720 3.8016297817 4.0346260071 3.8798704147 451 18.0000000000 0.0112169227 0.0063975683 0.0112260329 0.0092732117 0.7573090000 0.1448970000 0.1431020000 0.0432380000 0.4234260000 0.0018730000 114300723 0 402718720 3.8019089699 4.0344038010 3.8773777485 452 18.0400000000 0.0111450087 0.0064080714 0.0112260329 0.0092805390 0.6390210000 0.1111690000 0.1067590000 0.0000010000 0.4184580000 0.0018690000 114303499 0 402718720 3.8017003536 4.0331034660 3.8752470016 453 18.0800000000 0.0112304119 0.0064187168 0.0112304119 0.0092854573 1.0933130000 0.1112610000 0.1067350000 0.0343220000 0.4167390000 0.4234840000 114306275 0 402718720 3.8010406494 4.0325074196 3.8729562759 454 18.1200000000 0.0111866212 0.0064292188 0.0112304119 0.0092802250 0.5981190000 0.1314460000 0.0473800000 0.0000010000 0.4166470000 0.0018740000 114309051 0 402718720 3.8009066582 4.0330634117 3.8700985909 455 18.1600000000 0.0110513670 0.0064393773 0.0112304119 0.0092701820 0.6292390000 0.1111900000 0.0659490000 0.0343470000 0.4150920000 0.0018800000 114311827 0 402718720 3.8005771637 4.0341773033 3.8671021461 456 18.2000000000 0.0113229994 0.0064500870 0.0113229994 0.0092606813 0.6380660000 0.1112250000 0.1124620000 0.0000000000 0.4116090000 0.0019690000 114314603 0 402718720 3.7994742393 4.0353808403 3.8643531799 457 18.2400000000 0.0112259677 0.0064605375 0.0113229994 0.0092636635 1.1166900000 0.1111980000 0.1068380000 0.0342730000 0.4278030000 0.4357820000 114317379 0 402718720 3.7994654179 4.0350370407 3.8619022369 458 18.2800000000 0.0113184741 0.0064711444 0.0113229994 0.0092603045 0.6602960000 0.1327320000 0.1116660000 0.0000010000 0.4132340000 0.0018750000 114320155 0 402718720 3.7983071804 4.0358576775 3.8590755463 459 18.3200000000 0.0111707170 0.0064813831 0.0113229994 0.0092771344 0.6138000000 0.1112480000 0.0566890000 0.0337750000 0.4094260000 0.0018800000 114322931 0 402718720 3.7977578640 4.0358881950 3.8565034866 460 18.3600000000 0.0112125417 0.0064916682 0.0113229994 0.0092827398 0.5865270000 0.1112110000 0.0631230000 0.0000000000 0.4095410000 0.0018730000 114325707 0 402718720 3.7973382473 4.0360627174 3.8535537720 461 18.4000000000 0.0112069305 0.0065018966 0.0113229994 0.0092797198 1.0286620000 0.1112360000 0.0632400000 0.0336140000 0.4064940000 0.4132990000 114328483 0 402718720 3.7964751720 4.0363497734 3.8507883549 462 18.4400000000 0.0112668918 0.0065122104 0.0113229994 0.0093015194 0.6518670000 0.1352310000 0.1071760000 0.0000000000 0.4067910000 0.0018780000 114331259 0 402718720 3.7961304188 4.0355768204 3.8482859135 463 18.4800000000 0.0112538673 0.0065224516 0.0113229994 0.0093072464 0.6398790000 0.1112630000 0.0897360000 0.0341620000 0.4020370000 0.0018930000 114334035 0 402718720 3.7956244946 4.0357341766 3.8453304768 464 18.5200000000 0.0112707643 0.0065326850 0.0113229994 0.0093080440 0.5920830000 0.1240300000 0.0634940000 0.0000010000 0.4018820000 0.0018830000 114336811 0 402718720 3.7947192192 4.0351080894 3.8427863121 465 18.5600000000 0.0112444069 0.0065428177 0.0113229994 0.0093054109 1.0470910000 0.1111740000 0.0635300000 0.0341730000 0.4146180000 0.4227080000 114339587 0 402718720 3.7940521240 4.0355334282 3.8397159576 466 18.6000000000 0.0111939842 0.0065527988 0.0113229994 0.0092962867 0.6076210000 0.1335220000 0.0726300000 0.0000010000 0.3987940000 0.0018830000 114342363 0 402718720 3.7927386761 4.0367960930 3.8364193439 467 18.6400000000 0.0112359207 0.0065628269 0.0113229994 0.0092864151 0.5999380000 0.1112390000 0.0547420000 0.0335640000 0.3976950000 0.0018910000 114345139 0 402718720 3.7913997173 4.0380377769 3.8333001137 468 18.6800000000 0.0113037853 0.0065729571 0.0113229994 0.0092772160 0.6329810000 0.1222560000 0.1108070000 0.0000000000 0.3972320000 0.0018800000 114347915 0 402718720 3.7897844315 4.0392327309 3.8301084042 469 18.7200000000 0.0112971775 0.0065830301 0.0113229994 0.0092769571 1.0530910000 0.1111820000 0.1080330000 0.0335290000 0.3965470000 0.4030170000 114350691 0 402718720 3.7892613411 4.0396575928 3.8272440434 470 18.7600000000 0.0113066332 0.0065930803 0.0113229994 0.0092674628 0.6315370000 0.1243480000 0.1085980000 0.0000010000 0.3959070000 0.0018850000 114353467 0 402718720 3.7872285843 4.0423612595 3.8238208294 471 18.8000000000 0.0112861739 0.0066030444 0.0113229994 0.0092993527 0.6151650000 0.1112430000 0.0760430000 0.0341020000 0.3910810000 0.0018960000 114356243 0 402718720 3.7873504162 4.0420894623 3.8211731911 472 18.8400000000 0.0112841018 0.0066129619 0.0113229994 0.0093883878 0.6073100000 0.1111770000 0.0804910000 0.0000000000 0.4121380000 0.0025870000 114359019 0 402718720 3.7865447998 4.0432639122 3.8181388378 473 18.8800000000 0.0112524685 0.0066227706 0.0113229994 0.0094548052 1.0525750000 0.1449870000 0.0853770000 0.0429330000 0.3861230000 0.3923530000 114361795 0 402718720 3.7855515480 4.0428609848 3.8151347637 474 18.9200000000 0.0112852370 0.0066326070 0.0113229994 0.0094547366 0.5720550000 0.1112070000 0.0730940000 0.0000010000 0.3850580000 0.0018930000 114364571 0 402718720 3.7837617397 4.0433964729 3.8123617172 475 18.9600000000 0.0112494482 0.0066423267 0.0113229994 0.0094503931 0.6027760000 0.1111780000 0.0728430000 0.0335290000 0.3825220000 0.0018970000 114367347 0 402718720 3.7825913429 4.0447263718 3.8095622063 476 19.0000000000 0.0113213295 0.0066521565 0.0113229994 0.0094660478 0.5695360000 0.1111960000 0.0728840000 0.0000000000 0.3827520000 0.0018940000 114370123 0 402718720 3.7812664509 4.0464501381 3.8066780567 477 19.0400000000 0.0112561779 0.0066618086 0.0113229994 0.0094647496 0.9705810000 0.1073360000 0.0633780000 0.0338680000 0.3791720000 0.3860180000 114372899 0 402718720 3.7804820538 4.0483613014 3.8036210537 478 19.0800000000 0.0112843458 0.0066714792 0.0113229994 0.0094561275 0.5904830000 0.1432860000 0.0672240000 0.0000000000 0.3772520000 0.0018980000 114375675 0 402718720 3.7794098854 4.0505452156 3.8010742664 479 19.1200000000 0.0112251434 0.0066809858 0.0113229994 0.0094545908 0.5703580000 0.1111810000 0.0461170000 0.0340970000 0.3762440000 0.0018980000 114378451 0 402718720 3.7780516148 4.0514650345 3.7984602451 480 19.1600000000 0.0113437297 0.0066906998 0.0113437297 0.0094566486 0.6066930000 0.1111270000 0.1091800000 0.0000010000 0.3836760000 0.0018960000 114381227 0 402718720 3.7769339085 4.0524926186 3.7959139347 481 19.2000000000 0.0112274606 0.0067001317 0.0113437297 0.0094536295 0.9736910000 0.1111300000 0.0768960000 0.0341450000 0.3700590000 0.3806510000 114384003 0 402718720 3.7760121822 4.0531344414 3.7934200764 482 19.2400000000 0.0112798037 0.0067096331 0.0113437297 0.0094511782 0.5514720000 0.1112090000 0.0641730000 0.0000000000 0.3733660000 0.0019080000 114386779 0 402718720 3.7752513885 4.0542645454 3.7908611298 483 19.2800000000 0.0113317138 0.0067192027 0.0113437297 0.0094721543 0.5719530000 0.1111470000 0.0550460000 0.0334990000 0.3695270000 0.0019050000 114389555 0 402718720 3.7741789818 4.0535850525 3.7888243198 484 19.3200000000 0.0113225058 0.0067287136 0.0113437297 0.0094697759 0.5479920000 0.1111800000 0.0642900000 0.0000000000 0.3697920000 0.0019030000 114392331 0 402718720 3.7737438679 4.0540013313 3.7867338657 485 19.3600000000 0.0113248015 0.0067381901 0.0113437297 0.0094616129 0.9522680000 0.1111280000 0.0642540000 0.0334490000 0.3676950000 0.3749190000 114395107 0 402718720 3.7734999657 4.0542531013 3.7850239277 486 19.4000000000 0.0113167465 0.0067476110 0.0113437297 0.0094530163 0.5367080000 0.1110930000 0.0553650000 0.0000000000 0.3675250000 0.0018970000 114397883 0 402718720 3.7733876705 4.0549144745 3.7829170227 487 19.4400000000 0.0114007480 0.0067571657 0.0114007480 0.0094465917 0.6484810000 0.1370550000 0.1099620000 0.0334410000 0.3652770000 0.0019130000 114400659 0 402718720 3.7727906704 4.0560493469 3.7809317112 488 19.4800000000 0.0114408340 0.0067667634 0.0114408340 0.0094428589 0.5571330000 0.1333530000 0.0553710000 0.0000010000 0.3656630000 0.0019110000 114403435 0 402718720 3.7721989155 4.0567860603 3.7787992954 489 19.5200000000 0.0114026144 0.0067762436 0.0114408340 0.0094474046 0.9554600000 0.1110300000 0.0745100000 0.0339990000 0.3636620000 0.3714310000 114406211 0 402718720 3.7725155354 4.0564274788 3.7768924236 490 19.5600000000 0.0113979001 0.0067856756 0.0114408340 0.0094423585 0.5363800000 0.1110390000 0.0580460000 0.0000000000 0.3646020000 0.0018540000 114408987 0 402718720 3.7723789215 4.0571551323 3.7748980522 491 19.6000000000 0.0114950761 0.0067952670 0.0114950761 0.0094342341 0.5837470000 0.1109490000 0.0735710000 0.0339740000 0.3625060000 0.0019140000 114411763 0 402718720 3.7711498737 4.0575041771 3.7729647160 492 19.6400000000 0.0115135675 0.0068048571 0.0115135675 0.0094258944 0.5629480000 0.1236380000 0.0735680000 0.0000010000 0.3629950000 0.0019060000 114414539 0 402718720 3.7714884281 4.0584321022 3.7710516453 493 19.6800000000 0.0115137845 0.0068144086 0.0115137845 0.0094211152 0.9765550000 0.1070790000 0.1062550000 0.0335630000 0.3609970000 0.3678240000 114417315 0 402718720 3.7711830139 4.0585575104 3.7691061497 494 19.7200000000 0.0115161100 0.0068239263 0.0115161100 0.0094134560 0.5298940000 0.1107500000 0.0553740000 0.0000010000 0.3610240000 0.0019060000 114420091 0 402718720 3.7714197636 4.0595140457 3.7671341896 495 19.7600000000 0.0115259159 0.0068334252 0.0115259159 0.0094159024 0.6123350000 0.1105760000 0.0824400000 0.0409800000 0.3747640000 0.0026190000 114422867 0 402718720 3.7704138756 4.0590920448 3.7650074959 496 19.8000000000 0.0115334401 0.0068429011 0.0115334401 0.0094164563 0.6128220000 0.1441430000 0.0986340000 0.0000010000 0.3672910000 0.0019060000 114425643 0 402718720 3.7691297531 4.0592217445 3.7626044750 497 19.8400000000 0.0116136223 0.0068525001 0.0116136223 0.0094134690 0.9279390000 0.1103070000 0.0668010000 0.0337350000 0.3546380000 0.3616100000 114428419 0 402718720 3.7688243389 4.0587201118 3.7607362270 498 19.8800000000 0.0116699347 0.0068621737 0.0116699347 0.0094088611 0.6007170000 0.1310470000 0.1108650000 0.0000010000 0.3561070000 0.0018370000 114431195 0 402718720 3.7697687149 4.0569067001 3.7594642639 499 19.9200000000 0.0116674062 0.0068718034 0.0116699347 0.0094001473 0.6156180000 0.1102680000 0.1156280000 0.0337790000 0.3531830000 0.0019040000 114433971 0 402718720 3.7706511021 4.0571250916 3.7573087215 500 19.9600000000 0.0116594750 0.0068813787 0.0116699347 0.0093912252 0.5223440000 0.1101840000 0.0555500000 0.0000010000 0.3538600000 0.0018960000 114436747 0 402718720 3.7719936371 4.0577044487 3.7549929619 501 20.0000000000 0.0116879931 0.0068909728 0.0116879931 0.0094055496 0.9169850000 0.1064800000 0.0668690000 0.0337220000 0.3512670000 0.3577900000 114439523 0 402718720 3.7707128525 4.0556459427 3.7525427341 502 20.0400000000 0.0116647016 0.0069004822 0.0116879931 0.0094227528 0.5305600000 0.1101050000 0.0583740000 0.0000000000 0.3585100000 0.0026100000 114442299 0 402718720 3.7699122429 4.0548548698 3.7496788502 503 20.0800000000 0.0117882378 0.0069101994 0.0117882378 0.0094146305 0.7042410000 0.1438100000 0.1477160000 0.0421240000 0.3670060000 0.0026090000 114445075 0 402718720 3.7698934078 4.0559883118 3.7469563484 504 20.1200000000 0.0117599769 0.0069198220 0.0117882378 0.0094060792 0.5338690000 0.1144470000 0.0647040000 0.0000010000 0.3519650000 0.0018980000 114447851 0 402718720 3.7708215714 4.0565977097 3.7446680069 505 20.1600000000 0.0117029576 0.0069292935 0.0117882378 0.0093980099 0.9235780000 0.1238870000 0.0583720000 0.0337260000 0.3495670000 0.3571680000 114450627 0 402718720 3.7714097500 4.0577635765 3.7419092655 506 20.2000000000 0.0117341066 0.0069387892 0.0117882378 0.0093897312 0.5308470000 0.1103700000 0.0680850000 0.0000010000 0.3495010000 0.0019950000 114453403 0 402718720 3.7711801529 4.0588040352 3.7395126820 507 20.2400000000 0.0117303124 0.0069482399 0.0117882378 0.0093852119 0.5612200000 0.1103810000 0.0623030000 0.0337360000 0.3520310000 0.0019000000 114456179 0 402718720 3.7704625130 4.0576543808 3.7369396687 508 20.2800000000 0.0117686819 0.0069577290 0.0117882378 0.0093788045 0.5420570000 0.1263570000 0.0584640000 0.0000010000 0.3544810000 0.0018930000 114458955 0 402718720 3.7707614899 4.0576457977 3.7342083454 509 20.3200000000 0.0117634851 0.0069671706 0.0117882378 0.0093762609 0.9095610000 0.1105900000 0.0573830000 0.0337550000 0.3496780000 0.3572950000 114461731 0 402718720 3.7719230652 4.0570940971 3.7321329117 510 20.3600000000 0.0117770638 0.0069766017 0.0117882378 0.0093776299 0.5273280000 0.1068750000 0.0640720000 0.0000010000 0.3536190000 0.0018910000 114464507 0 402718720 3.7721982002 4.0581555367 3.7297708988 511 20.4000000000 0.0118709356 0.0069861797 0.0118709356 0.0093704201 0.5558210000 0.1106450000 0.0555860000 0.0338140000 0.3521680000 0.0026160000 114467283 0 402718720 3.7720336914 4.0587935448 3.7271368504 512 20.4400000000 0.0118503161 0.0069956800 0.0118709356 0.0093621511 0.5898100000 0.1443190000 0.0752830000 0.0000020000 0.3666000000 0.0026090000 114470059 0 402718720 3.7723312378 4.0594062805 3.7242946625 513 20.4800000000 0.0118850330 0.0070052109 0.0118850330 0.0093545772 0.9900950000 0.1443140000 0.0997900000 0.0417310000 0.3480380000 0.3553430000 114521987 0 402718720 3.7751047611 4.0608544350 3.7214610577 514 20.5200000000 0.0118657835 0.0070146672 0.0118850330 0.0093492833 0.5319950000 0.1069340000 0.0735370000 0.0000010000 0.3487520000 0.0018900000 114627163 0 402718720 3.7757458687 4.0608391762 3.7183032036 515 20.5600000000 0.0119349929 0.0070242213 0.0119349929 0.0093430065 0.5481180000 0.1107300000 0.0559220000 0.0338470000 0.3448380000 0.0018990000 114629939 0 402718720 3.7771322727 4.0602788925 3.7155938148 516 20.6000000000 0.0119321682 0.0070337328 0.0119349929 0.0093397976 0.5237520000 0.1105910000 0.0653280000 0.0000010000 0.3450330000 0.0018950000 114632715 0 402718720 3.7797086239 4.0597352982 3.7129526138 517 20.6400000000 0.0120033082 0.0070433451 0.0120033082 0.0093323080 0.9140690000 0.1106220000 0.0782500000 0.0338780000 0.3396530000 0.3507920000 114635491 0 402718720 3.7818353176 4.0601162910 3.7105209827 518 20.6800000000 0.0119723547 0.0070528606 0.0120033082 0.0093269287 0.5327320000 0.1213270000 0.0684520000 0.0000010000 0.3400240000 0.0020080000 114638267 0 402718720 3.7837238312 4.0608725548 3.7079832554 519 20.7200000000 0.0119824009 0.0070623587 0.0120033082 0.0093221639 0.5770300000 0.1105970000 0.0781650000 0.0339630000 0.3506640000 0.0026230000 114641043 0 402718720 3.7850461006 4.0615134239 3.7053444386 520 20.7600000000 0.0120565118 0.0070719629 0.0120565118 0.0093175597 0.6455570000 0.1442970000 0.1457500000 0.0000010000 0.3527140000 0.0018990000 114643819 0 402718720 3.7858486176 4.0612344742 3.7029519081 521 20.8000000000 0.0120655904 0.0070815476 0.0120655904 0.0093092832 0.9011900000 0.1068530000 0.0736680000 0.0330700000 0.3396730000 0.3470380000 114646595 0 402718720 3.7866916656 4.0623531342 3.7007834911 522 20.8400000000 0.0120718386 0.0070911075 0.0120718386 0.0093010817 0.5296150000 0.1107500000 0.0747080000 0.0000010000 0.3413530000 0.0019020000 114649371 0 402718720 3.7873311043 4.0644435883 3.6983807087 523 20.8800000000 0.0120915053 0.0071006685 0.0120915053 0.0092928899 0.5902650000 0.1069520000 0.1075910000 0.0336270000 0.3392830000 0.0019060000 114652147 0 402718720 3.7882034779 4.0649333000 3.6961228848 524 20.9200000000 0.0121420408 0.0071102894 0.0121420408 0.0092850657 0.5638130000 0.1069840000 0.0963060000 0.0000010000 0.3568850000 0.0026250000 114654923 0 402718720 3.7881634235 4.0649738312 3.6936590672 525 20.9600000000 0.0121187819 0.0071198294 0.0121420408 0.0092793433 0.9744040000 0.1444430000 0.0999400000 0.0426850000 0.3406020000 0.3458260000 114657699 0 402718720 3.7887778282 4.0651555061 3.6913385391 526 21.0000000000 0.0121619310 0.0071294152 0.0121619310 0.0092754611 0.5288820000 0.1108120000 0.0745900000 0.0000000000 0.3406660000 0.0019010000 114660475 0 402718720 3.7895712852 4.0658087730 3.6891906261 527 21.0400000000 0.0121964617 0.0071390301 0.0121964617 0.0092705779 0.5495690000 0.1107840000 0.0652490000 0.0333130000 0.3374020000 0.0019040000 114663251 0 402718720 3.7900447845 4.0660324097 3.6873478889 528 21.0800000000 0.0121824164 0.0071485819 0.0121964617 0.0092723648 0.5226160000 0.1201270000 0.0589650000 0.0000010000 0.3407160000 0.0018980000 114666027 0 402718720 3.7912106514 4.0662894249 3.6855304241 529 21.1200000000 0.0122154495 0.0071581601 0.0122154495 0.0092712012 0.8872660000 0.1107960000 0.0588680000 0.0333860000 0.3364060000 0.3469100000 114668803 0 402718720 3.7918853760 4.0654330254 3.6836636066 530 21.1600000000 0.0123072555 0.0071678754 0.0123072555 0.0092725110 0.5133350000 0.1107190000 0.0561540000 0.0000010000 0.3436700000 0.0018860000 114671579 0 402718720 3.7915666103 4.0654449463 3.6818230152 531 21.2000000000 0.0123576894 0.0071776491 0.0123576894 0.0092792540 0.5879360000 0.1308490000 0.0778580000 0.0339590000 0.3424550000 0.0018930000 114674355 0 402718720 3.7921013832 4.0657491684 3.6800091267 532 21.2400000000 0.0123295421 0.0071873331 0.0123576894 0.0092889100 0.5351600000 0.1106610000 0.0781350000 0.0000010000 0.3434160000 0.0019950000 114677131 0 402718720 3.7929677963 4.0642967224 3.6783914566 533 21.2800000000 0.0123640327 0.0071970454 0.0123640327 0.0092974102 0.9151980000 0.1234820000 0.0571100000 0.0339570000 0.3461110000 0.3536250000 114679907 0 402718720 3.7935266495 4.0640082359 3.6767866611 534 21.3200000000 0.0124448407 0.0072068728 0.0124448407 0.0092914371 0.5372930000 0.1107590000 0.0745620000 0.0000000000 0.3491700000 0.0018920000 114682683 0 402718720 3.7939982414 4.0631971359 3.6754043102 535 21.3600000000 0.0124469223 0.0072166673 0.0124469223 0.0092885329 0.5598580000 0.1108530000 0.0651130000 0.0339790000 0.3470970000 0.0018910000 114685459 0 402718720 3.7941741943 4.0622153282 3.6740238667 536 21.4000000000 0.0125515340 0.0072266204 0.0125515340 0.0092877874 0.5388920000 0.1110030000 0.0746090000 0.0000000000 0.3504620000 0.0018870000 114688235 0 402718720 3.7943351269 4.0625047684 3.6724669933 537 21.4400000000 0.0125481505 0.0072365301 0.0125515340 0.0092858679 0.9643280000 0.1110540000 0.1108280000 0.0334230000 0.3502970000 0.3578100000 114691011 0 402718720 3.7944343090 4.0615315437 3.6712298393 538 21.4800000000 0.0125685548 0.0072464409 0.0125685548 0.0092969565 0.5199780000 0.1073450000 0.0580640000 0.0000010000 0.3516730000 0.0019220000 114693787 0 402718720 3.7948336601 4.0613799095 3.6700785160 539 21.5200000000 0.0125485705 0.0072562779 0.0125685548 0.0093136786 0.5655520000 0.1112410000 0.0648170000 0.0340070000 0.3526700000 0.0018890000 114696563 0 402718720 3.7954583168 4.0603976250 3.6687853336 540 21.5600000000 0.0127480160 0.0072664478 0.0127480160 0.0093211836 0.5474920000 0.1327060000 0.0586910000 0.0000010000 0.3531410000 0.0019820000 114699339 0 402718720 3.7949368954 4.0602550507 3.6675584316 541 21.6000000000 0.0126989475 0.0072764894 0.0127480160 0.0093256175 0.9230630000 0.1112570000 0.0557740000 0.0341380000 0.3566860000 0.3642750000 114702115 0 402718720 3.7948613167 4.0599794388 3.6662037373 542 21.6400000000 0.0126927998 0.0072864826 0.0127480160 0.0093264757 0.5867250000 0.1112220000 0.1110150000 0.0000010000 0.3616630000 0.0018860000 114704891 0 402718720 3.7953834534 4.0586471558 3.6650393009 543 21.6800000000 0.0127496570 0.0072965437 0.0127496570 0.0093286644 0.6346960000 0.1236080000 0.1159900000 0.0341720000 0.3580790000 0.0018950000 114707667 0 402718720 3.7943739891 4.0577321053 3.6638538837 544 21.7200000000 0.0127375936 0.0073065456 0.0127496570 0.0093259345 0.5520400000 0.1111370000 0.0744300000 0.0000010000 0.3636320000 0.0018950000 114710443 0 402718720 3.7944176197 4.0566744804 3.6626815796 545 21.7600000000 0.0127737783 0.0073165772 0.0127737783 0.0093209415 0.9653310000 0.1241280000 0.0779170000 0.0342980000 0.3603580000 0.3677610000 114713219 0 402718720 3.7939934731 4.0553417206 3.6616530418 546 21.8000000000 0.0127585102 0.0073265441 0.0127737783 0.0093270865 0.5446580000 0.1108400000 0.0651890000 0.0000000000 0.3658470000 0.0019030000 114715995 0 402718720 3.7937853336 4.0544238091 3.6606948376 547 21.8400000000 0.0126993963 0.0073363665 0.0127737783 0.0093503607 0.5617910000 0.1069080000 0.0550930000 0.0340200000 0.3630310000 0.0018540000 114718771 0 402718720 3.7938780785 4.0529036522 3.6596744061 548 21.8800000000 0.0127084265 0.0073461696 0.0127737783 0.0093639030 0.5476480000 0.1200970000 0.0561160000 0.0000010000 0.3686180000 0.0019150000 114721547 0 402718720 3.7935471535 4.0519008636 3.6584522724 549 21.9200000000 0.0126646804 0.0073558572 0.0127737783 0.0093740735 0.9684610000 0.1303080000 0.0685540000 0.0344830000 0.3616950000 0.3725380000 114724323 0 402718720 3.7928857803 4.0483760834 3.6573891640 550 21.9600000000 0.0126707694 0.0073655207 0.0127737783 0.0093829529 0.5702120000 0.1113680000 0.0883140000 0.0000010000 0.3675700000 0.0020190000 114727099 0 402718720 3.7920746803 4.0475935936 3.6562862396 551 22.0000000000 0.0127268881 0.0073752509 0.0127737783 0.0093804322 0.5934210000 0.1115080000 0.0653440000 0.0344420000 0.3793050000 0.0019190000 114729875 0 402718720 3.7915086746 4.0478620529 3.6551439762 552 22.0400000000 0.0125318291 0.0073845926 0.0127737783 0.0093769180 0.5411680000 0.1115480000 0.0565570000 0.0000000000 0.3702400000 0.0019190000 114732651 0 402718720 3.7908167839 4.0467619896 3.6541566849 553 22.0800000000 0.0126061076 0.0073940347 0.0127737783 0.0093770119 0.9485460000 0.1077870000 0.0652930000 0.0345220000 0.3660620000 0.3739920000 114735427 0 402718720 3.7898097038 4.0448627472 3.6532425880 554 22.1200000000 0.0126742795 0.0074035658 0.0127737783 0.0093850955 0.5641120000 0.1078390000 0.0652070000 0.0000010000 0.3873720000 0.0026620000 114738203 0 402718720 3.7891123295 4.0447330475 3.6524069309 555 22.1600000000 0.0126071945 0.0074129417 0.0127737783 0.0093882253 0.6524490000 0.1452420000 0.0879150000 0.0445000000 0.3719650000 0.0019280000 114740979 0 402718720 3.7887754440 4.0460295677 3.6512737274 556 22.2000000000 0.0126850046 0.0074224239 0.0127737783 0.0093821074 0.5416000000 0.1117200000 0.0568940000 0.0000010000 0.3701290000 0.0019260000 114743755 0 402718720 3.7889258862 4.0458359718 3.6503646374 557 22.2400000000 0.0127311675 0.0074319548 0.0127737783 0.0093748538 0.9517740000 0.1116800000 0.0658190000 0.0337740000 0.3658790000 0.3737180000 114746531 0 402718720 3.7887079716 4.0442404747 3.6496405602 558 22.2800000000 0.0127080148 0.0074414101 0.0127737783 0.0093732225 0.5788760000 0.1366640000 0.0693640000 0.0000010000 0.3700050000 0.0019340000 114749307 0 402718720 3.7889375687 4.0437746048 3.6490762234 559 22.3200000000 0.0127089359 0.0074508333 0.0127737783 0.0093766449 0.6008980000 0.1117330000 0.0887710000 0.0341670000 0.3633810000 0.0019370000 114752083 0 402718720 3.7886509895 4.0434408188 3.6480777264 560 22.3600000000 0.0127075752 0.0074602203 0.0127737783 0.0093741067 0.5568930000 0.1117890000 0.0568520000 0.0000010000 0.3845260000 0.0026800000 114754859 0 402718720 3.7883126736 4.0435895920 3.6473093033 561 22.4000000000 0.0127500230 0.0074696495 0.0127737783 0.0093716620 1.0886600000 0.1453410000 0.1502470000 0.0439440000 0.3730720000 0.3751470000 114757635 0 402718720 3.7884416580 4.0429892540 3.6466286182 562 22.4400000000 0.0127268545 0.0074790040 0.0127737783 0.0093683400 0.5429800000 0.1117430000 0.0569350000 0.0000010000 0.3714460000 0.0019390000 114760411 0 402718720 3.7879700661 4.0423369408 3.6458783150 563 22.4800000000 0.0127334129 0.0074883369 0.0127737783 0.0093655778 0.5735970000 0.1117780000 0.0567690000 0.0341290000 0.3680620000 0.0019400000 114763187 0 402718720 3.7879188061 4.0418758392 3.6453189850 564 22.5200000000 0.0127702132 0.0074977019 0.0127737783 0.0093656993 0.5438050000 0.1116470000 0.0570120000 0.0000000000 0.3722900000 0.0019380000 114765963 0 402718720 3.7877657413 4.0418152809 3.6447167397 565 22.5600000000 0.0127542913 0.0075070056 0.0127737783 0.0093683295 0.9581990000 0.1116340000 0.0661220000 0.0341830000 0.3689400000 0.3763870000 114768739 0 402718720 3.7870354652 4.0409426689 3.6438751221 566 22.6000000000 0.0128047029 0.0075163655 0.0128047029 0.0093679463 0.5517600000 0.1117300000 0.0641210000 0.0000010000 0.3730520000 0.0019340000 114771515 0 402718720 3.7872514725 4.0407257080 3.6434717178 567 22.6400000000 0.0128287710 0.0075257348 0.0128287710 0.0093662008 0.6224280000 0.1120950000 0.0890790000 0.0347960000 0.3827060000 0.0026860000 114774291 0 402718720 3.7868437767 4.0403790474 3.6426119804 568 22.6800000000 0.0128061222 0.0075350313 0.0128287710 0.0093655243 0.6285680000 0.1453340000 0.0984730000 0.0000010000 0.3818890000 0.0019400000 114777067 0 402718720 3.7865824699 4.0397028923 3.6422421932 569 22.7200000000 0.0129068578 0.0075444721 0.0129068578 0.0093720887 0.9830940000 0.1118950000 0.0874900000 0.0348240000 0.3703190000 0.3776450000 114779843 0 402718720 3.7862584591 4.0395054817 3.6416184902 570 22.7600000000 0.0128983511 0.0075538649 0.0129068578 0.0093748610 0.5723660000 0.1119870000 0.0832630000 0.0000010000 0.3742270000 0.0019450000 114782619 0 402718720 3.7857818604 4.0391383171 3.6410005093 571 22.8000000000 0.0129075311 0.0075632408 0.0129075311 0.0093801134 0.5873880000 0.1120760000 0.0668800000 0.0342930000 0.3712530000 0.0019450000 114785395 0 402718720 3.7856237888 4.0381236076 3.6402959824 572 22.8400000000 0.0128958765 0.0075725636 0.0129075311 0.0093903366 0.5642780000 0.1121820000 0.0739710000 0.0000010000 0.3752490000 0.0019430000 114788171 0 402718720 3.7855179310 4.0384149551 3.6395466328 573 22.8800000000 0.0129117798 0.0075818816 0.0129117798 0.0093896630 0.9639910000 0.1124010000 0.0668560000 0.0343810000 0.3712330000 0.3781980000 114790947 0 402718720 3.7851464748 4.0379505157 3.6386964321 574 22.9200000000 0.0129648848 0.0075912597 0.0129648848 0.0093915813 0.5576470000 0.1125210000 0.0673550000 0.0000010000 0.3748850000 0.0019510000 114793723 0 402718720 3.7854719162 4.0371522903 3.6377031803 575 22.9600000000 0.0129676396 0.0076006099 0.0129676396 0.0093959320 0.5833750000 0.1085930000 0.0663240000 0.0341120000 0.3715010000 0.0019020000 114796499 0 402718720 3.7854759693 4.0364947319 3.6368603706 576 23.0000000000 0.0129562011 0.0076099078 0.0129676396 0.0094031934 0.5848320000 0.1395530000 0.0673410000 0.0000010000 0.3750260000 0.0019600000 114799275 0 402718720 3.7851166725 4.0356130600 3.6358087063 577 23.0400000000 0.0130822808 0.0076193920 0.0130822808 0.0094109766 0.9724410000 0.1086860000 0.0792000000 0.0346640000 0.3703540000 0.3786020000 114802051 0 402718720 3.7854969501 4.0346884727 3.6350150108 578 23.0800000000 0.0131733613 0.0076290009 0.0131733613 0.0094195586 0.5624200000 0.1267350000 0.0607370000 0.0000000000 0.3720470000 0.0019550000 114804827 0 402718720 3.7856049538 4.0336918831 3.6342577934 579 23.1200000000 0.0131742200 0.0076385781 0.0131742200 0.0094252802 0.5888470000 0.1127550000 0.0702680000 0.0350170000 0.3677660000 0.0020650000 114807603 0 402718720 3.7855944633 4.0328011513 3.6334121227 580 23.1600000000 0.0132050915 0.0076481756 0.0132050915 0.0094316877 0.5719110000 0.1127880000 0.0804770000 0.0000010000 0.3757330000 0.0019580000 114810379 0 402718720 3.7854428291 4.0321750641 3.6326785088 581 23.2000000000 0.0130709726 0.0076575091 0.0132050915 0.0094341247 0.9775720000 0.1127970000 0.0764080000 0.0344030000 0.3727830000 0.3802380000 114813155 0 402718720 3.7852661610 4.0310740471 3.6321167946 582 23.2400000000 0.0130574554 0.0076667874 0.0132050915 0.0094356195 0.5604600000 0.1128120000 0.0672610000 0.0000000000 0.3774730000 0.0019540000 114815931 0 402718720 3.7859582901 4.0306110382 3.6315410137 583 23.2800000000 0.0130982194 0.0076761037 0.0132050915 0.0094426442 0.6033550000 0.1128470000 0.0668990000 0.0350550000 0.3847420000 0.0027150000 114818707 0 402718720 3.7867636681 4.0307455063 3.6309201717 584 23.3200000000 0.0132025229 0.0076855668 0.0132050915 0.0094432187 0.6336150000 0.1458520000 0.0899140000 0.0000010000 0.3949360000 0.0019520000 114821483 0 402718720 3.7862870693 4.0294361115 3.6303613186 585 23.3600000000 0.0131822396 0.0076949628 0.0132050915 0.0094537642 0.9740070000 0.1128070000 0.0668110000 0.0350650000 0.3754890000 0.3828840000 114824259 0 402718720 3.7869248390 4.0289659500 3.6301524639 586 23.4000000000 0.0132181505 0.0077043880 0.0132181505 0.0094697320 0.5632060000 0.1128170000 0.0670970000 0.0000010000 0.3803740000 0.0019510000 114827035 0 402718720 3.7871196270 4.0292263031 3.6296451092 587 23.4400000000 0.0131242694 0.0077136212 0.0132181505 0.0094741596 0.5950090000 0.1129010000 0.0668660000 0.0350950000 0.3772100000 0.0019610000 114829811 0 402718720 3.7870755196 4.0286531448 3.6290869713 588 23.4800000000 0.0131843900 0.0077229253 0.0132181505 0.0094796927 0.5858550000 0.1341930000 0.0671710000 0.0000010000 0.3815690000 0.0019600000 114832587 0 402718720 3.7876970768 4.0281167030 3.6292374134 589 23.5200000000 0.0131891472 0.0077322058 0.0132181505 0.0094864964 0.9948340000 0.1088400000 0.0574420000 0.0351280000 0.3881500000 0.4041910000 114835363 0 402718720 3.7876679897 4.0279617310 3.6288056374 590 23.5600000000 0.0132312346 0.0077415262 0.0132312346 0.0094908173 0.6088770000 0.1456970000 0.0773330000 0.0000010000 0.3829170000 0.0019590000 114838139 0 402718720 3.7878091335 4.0277266502 3.6285943985 591 23.6000000000 0.0131891714 0.0077507438 0.0132312346 0.0094902616 0.6066970000 0.1129200000 0.0764390000 0.0351230000 0.3792620000 0.0019620000 114840915 0 402718720 3.7876479626 4.0262103081 3.6285336018 592 23.6400000000 0.0132400095 0.0077600162 0.0132400095 0.0095007979 0.5664740000 0.1129450000 0.0671190000 0.0000000000 0.3834860000 0.0019620000 114843691 0 402718720 3.7875409126 4.0256257057 3.6282572746 593 23.6800000000 0.0132683134 0.0077693051 0.0132683134 0.0095059628 1.0051950000 0.1327660000 0.0701620000 0.0353690000 0.3784350000 0.3874900000 114846467 0 402718720 3.7874612808 4.0253028870 3.6280462742 594 23.7200000000 0.0131379087 0.0077783432 0.0132683134 0.0095044307 0.5691140000 0.1128700000 0.0705540000 0.0000010000 0.3827470000 0.0019560000 114849243 0 402718720 3.7873980999 4.0247731209 3.6274936199 595 23.7600000000 0.0131834233 0.0077874273 0.0132683134 0.0095055688 0.6822940000 0.1436940000 0.0896610000 0.0447250000 0.4003680000 0.0027150000 114852019 0 402718720 3.7873897552 4.0239286423 3.6273937225 596 23.8000000000 0.0132455369 0.0077965852 0.0132683134 0.0095097777 0.5848430000 0.1454890000 0.0511390000 0.0000010000 0.3852740000 0.0019590000 114854795 0 402718720 3.7868623734 4.0235161781 3.6272411346 597 23.8400000000 0.0132516501 0.0078057227 0.0132683134 0.0095095383 0.9905460000 0.1128900000 0.0551430000 0.0346560000 0.3827270000 0.4040220000 114857571 0 402718720 3.7870330811 4.0233449936 3.6274406910 598 23.8800000000 0.0132461637 0.0078148204 0.0132683134 0.0095066185 0.6269810000 0.1454320000 0.0774250000 0.0000010000 0.4011880000 0.0019560000 114860347 0 402718720 3.7869102955 4.0227847099 3.6272633076 599 23.9200000000 0.0131782703 0.0078237744 0.0132683134 0.0095007662 0.5891790000 0.1128680000 0.0550920000 0.0352490000 0.3830070000 0.0019590000 114863123 0 402718720 3.7869341373 4.0214924812 3.6272990704 600 23.9600000000 0.0132486960 0.0078328160 0.0132683134 0.0094956002 0.5644080000 0.1087780000 0.0671430000 0.0000010000 0.3855430000 0.0019560000 114865899 0 402718720 3.7871706486 4.0205688477 3.6273145676 601 24.0000000000 0.0133305127 0.0078419635 0.0133305127 0.0094928151 0.9900930000 0.1128660000 0.0670110000 0.0352750000 0.3833170000 0.3906450000 114868675 0 402718720 3.7869777679 4.0199160576 3.6271550655 602 24.0400000000 0.0133138495 0.0078510531 0.0133305127 0.0094927442 0.5626770000 0.1160320000 0.0553360000 0.0000010000 0.3883570000 0.0019590000 114871451 0 402718720 3.7871890068 4.0188164711 3.6273148060 603 24.0800000000 0.0133752506 0.0078602143 0.0133752506 0.0095006242 0.5883720000 0.1108000000 0.0550580000 0.0353460000 0.3842130000 0.0019610000 114874227 0 402718720 3.7872831821 4.0181574821 3.6274981499 604 24.1200000000 0.0132946093 0.0078692116 0.0133752506 0.0095036967 0.5601950000 0.1127670000 0.0604490000 0.0000010000 0.3838790000 0.0020630000 114877003 0 402718720 3.7874927521 4.0175390244 3.6279096603 605 24.1600000000 0.0133239562 0.0078782277 0.0133752506 0.0095012562 1.0054360000 0.1255340000 0.0668360000 0.0354040000 0.3846570000 0.3920100000 114879779 0 402718720 3.7871127129 4.0174760818 3.6277246475 606 24.2000000000 0.0133744599 0.0078872974 0.0133752506 0.0094949067 0.5734720000 0.1086240000 0.0735030000 0.0000010000 0.3884610000 0.0018940000 114882555 0 402718720 3.7873487473 4.0168895721 3.6278023720 607 24.2400000000 0.0133975735 0.0078963753 0.0133975735 0.0094882859 0.5855670000 0.1085760000 0.0544960000 0.0345280000 0.3850150000 0.0019530000 114885331 0 402718720 3.7877860069 4.0164875984 3.6279923916 608 24.2800000000 0.0134448092 0.0079055010 0.0134448092 0.0094814508 0.5686800000 0.1219600000 0.0605730000 0.0000010000 0.3830580000 0.0020510000 114888107 0 402718720 3.7882702351 4.0160856247 3.6280941963 609 24.3200000000 0.0134975770 0.0079146834 0.0134975770 0.0094746280 0.9835920000 0.1125840000 0.0587680000 0.0356830000 0.3841390000 0.3914180000 114890883 0 402718720 3.7874808311 4.0148291588 3.6279380322 610 24.3600000000 0.0135614797 0.0079239404 0.0135614797 0.0094743472 0.5860520000 0.1262570000 0.0703740000 0.0000000000 0.3864660000 0.0019480000 114893659 0 402718720 3.7877171040 4.0147933960 3.6277134418 611 24.4000000000 0.0135152321 0.0079330915 0.0135614797 0.0094689670 0.5983220000 0.1085120000 0.0662530000 0.0351140000 0.3854780000 0.0019570000 114896435 0 402718720 3.7879459858 4.0137534142 3.6279249191 612 24.4400000000 0.0135350935 0.0079422451 0.0135614797 0.0094661964 0.5798610000 0.1125040000 0.0575260000 0.0000010000 0.4059800000 0.0027050000 114899211 0 402718720 3.7880461216 4.0135836601 3.6275475025 613 24.4800000000 0.0135711553 0.0079514276 0.0135711553 0.0094612672 1.0794660000 0.1449940000 0.0770730000 0.0452290000 0.3987650000 0.4122620000 114901987 0 402718720 3.7890453339 4.0145912170 3.6278321743 614 24.5200000000 0.0137483058 0.0079608688 0.0137483058 0.0094536365 0.6123860000 0.1450300000 0.0741710000 0.0000010000 0.3902410000 0.0019450000 114904763 0 402718720 3.7890946865 4.0146393776 3.6277594566 615 24.5600000000 0.0137978662 0.0079703599 0.0137978662 0.0094464222 0.5991770000 0.1125140000 0.0644870000 0.0355900000 0.3836210000 0.0019470000 114907539 0 402718720 3.7884976864 4.0131678581 3.6274905205 616 24.6000000000 0.0137853092 0.0079797997 0.0137978662 0.0094443527 0.5729710000 0.1124520000 0.0698970000 0.0000000000 0.3876630000 0.0019440000 114910315 0 402718720 3.7882602215 4.0113801956 3.6271581650 617 24.6400000000 0.0138398716 0.0079892974 0.0138398716 0.0094461304 0.9810400000 0.1123870000 0.0571380000 0.0349970000 0.3840120000 0.3914880000 114913091 0 402718720 3.7886974812 4.0111007690 3.6272573471 618 24.6800000000 0.0139588621 0.0079989569 0.0139588621 0.0094464954 0.5926180000 0.1363100000 0.0702180000 0.0000010000 0.3831260000 0.0019450000 114915867 0 402718720 3.7892618179 4.0105323792 3.6271057129 619 24.7200000000 0.0139593780 0.0080085860 0.0139593780 0.0094590922 0.5916720000 0.1122730000 0.0570590000 0.0350120000 0.3843490000 0.0019470000 114918643 0 402718720 3.7898058891 4.0104212761 3.6268477440 620 24.7600000000 0.0140617946 0.0080183492 0.0140617946 0.0094641875 0.5612160000 0.1122550000 0.0572980000 0.0000010000 0.3886910000 0.0019450000 114921419 0 402718720 3.7899703979 4.0111799240 3.6258547306 621 24.8000000000 0.0140880933 0.0080281234 0.0140880933 0.0094572996 0.9880790000 0.1122710000 0.0640590000 0.0350270000 0.3841850000 0.3915120000 114924195 0 402718720 3.7906556129 4.0111179352 3.6255989075 622 24.8400000000 0.0142967859 0.0080382016 0.0142967859 0.0094497079 0.5553000000 0.1082190000 0.0568460000 0.0000010000 0.3873240000 0.0018840000 114926971 0 402718720 3.7918219566 4.0107045174 3.6256406307 623 24.8800000000 0.0142439594 0.0080481627 0.0142967859 0.0094423342 0.6106530000 0.1122850000 0.0666320000 0.0355930000 0.3922690000 0.0027070000 114929747 0 402718720 3.7927172184 4.0102391243 3.6257441044 624 24.9200000000 0.0143053783 0.0080581903 0.0143053783 0.0094351289 0.6323610000 0.1447980000 0.0771420000 0.0000010000 0.4065480000 0.0027030000 114932523 0 402718720 3.7932102680 4.0094528198 3.6253151894 625 24.9600000000 0.0144114355 0.0080683555 0.0144114355 0.0094296136 0.9831740000 0.1191960000 0.0571370000 0.0355680000 0.3814420000 0.3888080000 114935299 0 402718720 3.7946202755 4.0097560883 3.6255853176 626 25.0000000000 0.0145061985 0.0080786396 0.0145061985 0.0094222690 0.5543970000 0.1122510000 0.0550730000 0.0000010000 0.3840990000 0.0019460000 114938075 0 402718720 3.7958633900 4.0102043152 3.6255981922 627 25.0400000000 0.0145016750 0.0080888837 0.0145061985 0.0094147889 0.6028950000 0.1253460000 0.0600620000 0.0358640000 0.3786160000 0.0019520000 114940851 0 402718720 3.7969877720 4.0093393326 3.6255378723 628 25.0800000000 0.0146010136 0.0080992533 0.0146010136 0.0094104464 0.5794730000 0.1289110000 0.0674830000 0.0000010000 0.3799460000 0.0020470000 114943627 0 402718720 3.7984068394 4.0098357201 3.6254730225 629 25.1200000000 0.0146089159 0.0081096025 0.0146089159 0.0094040781 0.9679400000 0.1082290000 0.0553380000 0.0355820000 0.3801260000 0.3876380000 114946403 0 402718720 3.8001539707 4.0112776756 3.6250791550 630 25.1600000000 0.0147272777 0.0081201068 0.0147272777 0.0094008571 0.5609740000 0.1122510000 0.0643750000 0.0000010000 0.3813570000 0.0019480000 114949179 0 402718720 3.8012652397 4.0110020638 3.6252832413 631 25.2000000000 0.0147810364 0.0081306629 0.0147810364 0.0093946932 0.5962220000 0.1122740000 0.0667090000 0.0350200000 0.3792370000 0.0019530000 114951955 0 402718720 3.8030562401 4.0103979111 3.6256625652 632 25.2400000000 0.0147908935 0.0081412012 0.0147908935 0.0093872597 0.5531490000 0.1123150000 0.0574660000 0.0000000000 0.3803680000 0.0019530000 114954731 0 402718720 3.8046009541 4.0104255676 3.6255984306 633 25.2800000000 0.0148522034 0.0081518031 0.0148522034 0.0093798548 0.9724840000 0.1123010000 0.0573880000 0.0355580000 0.3795940000 0.3866050000 114957507 0 402718720 3.8061950207 4.0115909576 3.6256711483 634 25.3200000000 0.0149558447 0.0081625351 0.0149558447 0.0093742924 0.5529740000 0.1123140000 0.0571260000 0.0000010000 0.3805360000 0.0019560000 114960283 0 402718720 3.8081312180 4.0115466118 3.6262876987 635 25.3600000000 0.0149972849 0.0081732985 0.0149972849 0.0093690396 0.6114830000 0.1124140000 0.0569000000 0.0408640000 0.3974030000 0.0027090000 114963059 0 402718720 3.8101933002 4.0112380981 3.6270611286 636 25.4000000000 0.0151073039 0.0081842010 0.0151073039 0.0093626133 0.6098710000 0.1449350000 0.0737750000 0.0000010000 0.3881660000 0.0019500000 114965835 0 402718720 3.8119623661 4.0115041733 3.6268105507 637 25.4400000000 0.0151562309 0.0081951461 0.0151562309 0.0093568731 0.9711680000 0.1124260000 0.0696510000 0.0355710000 0.3713260000 0.3811370000 114968611 0 402718720 3.8141868114 4.0117931366 3.6272225380 638 25.4800000000 0.0152086169 0.0082061390 0.0152086169 0.0093530584 0.5700920000 0.1304860000 0.0600320000 0.0000010000 0.3765580000 0.0019490000 114971387 0 402718720 3.8158926964 4.0107870102 3.6277539730 639 25.5200000000 0.0151598863 0.0082170212 0.0152086169 0.0093457712 0.5841920000 0.1124970000 0.0598550000 0.0355480000 0.3732810000 0.0019540000 114974163 0 402718720 3.8181865215 4.0108313560 3.6278479099 640 25.5600000000 0.0152903395 0.0082280733 0.0152903395 0.0093388011 0.5708010000 0.1253850000 0.0675670000 0.0000010000 0.3748350000 0.0019490000 114976939 0 402718720 3.8206222057 4.0113554001 3.6284148693 641 25.6000000000 0.0153329028 0.0082391573 0.0153329028 0.0093320519 0.9968030000 0.1124980000 0.0547710000 0.0349080000 0.3926410000 0.4007950000 114979715 0 402718720 3.8234505653 4.0118656158 3.6290900707 642 25.6400000000 0.0154262055 0.0082503520 0.0154262055 0.0093267739 0.5819660000 0.1292770000 0.0760800000 0.0000010000 0.3736080000 0.0019440000 114982491 0 402718720 3.8255240917 4.0114130974 3.6292412281 643 25.6800000000 0.0154014332 0.0082614735 0.0154262055 0.0093195144 0.5886970000 0.1125520000 0.0664700000 0.0348410000 0.3709190000 0.0027040000 114985267 0 402718720 3.8280429840 4.0120649338 3.6294589043 644 25.7200000000 0.0155037101 0.0082727192 0.0155037101 0.0093130652 0.6280100000 0.1450740000 0.0863860000 0.0000010000 0.3926350000 0.0027060000 114988043 0 402718720 3.8305981159 4.0119309425 3.6302757263 645 25.7600000000 0.0154691786 0.0082838765 0.0155037101 0.0093059404 1.0186490000 0.1450910000 0.0894610000 0.0378990000 0.3690250000 0.3761130000 114990819 0 402718720 3.8331718445 4.0112228394 3.6310014725 646 25.8000000000 0.0155008128 0.0082950482 0.0155037101 0.0093006480 0.5520300000 0.1125050000 0.0548720000 0.0000010000 0.3807380000 0.0026940000 114993595 0 402718720 3.8356425762 4.0117306709 3.6313416958 647 25.8400000000 0.0154517647 0.0083061096 0.0155037101 0.0092934565 0.6596060000 0.1450470000 0.0769380000 0.0450400000 0.3886580000 0.0027020000 114996371 0 402718720 3.8383777142 4.0121259689 3.6323025227 648 25.8800000000 0.0155061260 0.0083172207 0.0155061260 0.0092872551 0.5490430000 0.1125600000 0.0675140000 0.0000010000 0.3658120000 0.0020440000 114999147 0 402718720 3.8405506611 4.0115561485 3.6331069469 649 25.9200000000 0.0155415135 0.0083283522 0.0155415135 0.0092800967 0.9435920000 0.1085200000 0.0593390000 0.0345370000 0.3660390000 0.3740860000 115001923 0 402718720 3.8431024551 4.0111908913 3.6334528923 650 25.9600000000 0.0154825877 0.0083393587 0.0155415135 0.0092734374 0.5518150000 0.1239130000 0.0573170000 0.0000000000 0.3675600000 0.0019390000 115004699 0 402718720 3.8458027840 4.0116071701 3.6342108250 651 26.0000000000 0.0154888211 0.0083503409 0.0155415135 0.0092663171 0.5715610000 0.1125040000 0.0548950000 0.0353030000 0.3658380000 0.0019410000 115007475 0 402718720 3.8482799530 4.0121517181 3.6346504688 652 26.0400000000 0.0156227443 0.0083614949 0.0156227443 0.0092593754 0.5459650000 0.1124900000 0.0573100000 0.0000010000 0.3722500000 0.0026940000 115010251 0 402718720 3.8506388664 4.0124006271 3.6345844269 653 26.0800000000 0.0156354588 0.0083726342 0.0156354588 0.0092524040 1.0452720000 0.1449940000 0.0863700000 0.0449650000 0.3864850000 0.3813880000 115013027 0 402718720 3.8528757095 4.0122089386 3.6347424984 654 26.1200000000 0.0156576317 0.0083837734 0.0156576317 0.0092458438 0.5383780000 0.1124740000 0.0574890000 0.0000000000 0.3654000000 0.0019370000 115015803 0 402718720 3.8585941792 4.0130195618 3.6367509365 655 26.1600000000 0.0156926159 0.0083949319 0.0156926159 0.0092388719 0.5895360000 0.1124940000 0.0738750000 0.0352380000 0.3648950000 0.0019430000 115018579 0 402718720 3.8608336449 4.0124144554 3.6371314526 656 26.2000000000 0.0156326760 0.0084059651 0.0156926159 0.0092321916 0.5476110000 0.1124890000 0.0668740000 0.0000010000 0.3652280000 0.0019360000 115021355 0 402718720 3.8637614250 4.0128097534 3.6381790638 657 26.2400000000 0.0156976711 0.0084170636 0.0156976711 0.0092251905 0.9331950000 0.1125170000 0.0480110000 0.0351660000 0.3644640000 0.3719540000 115024131 0 402718720 3.8664216995 4.0127873421 3.6393318176 658 26.2800000000 0.0157478433 0.0084282046 0.0157478433 0.0092182918 0.5608030000 0.1296820000 0.0456200000 0.0000010000 0.3815700000 0.0026980000 115026907 0 402718720 3.8689832687 4.0126271248 3.6399400234 659 26.3200000000 0.0157637671 0.0084393359 0.0157637671 0.0092122939 0.6477650000 0.1449310000 0.0739970000 0.0455480000 0.3802540000 0.0019360000 115029683 0 402718720 3.8715426922 4.0131273270 3.6400713921 660 26.3600000000 0.0158229489 0.0084505232 0.0158229489 0.0092053055 0.5281700000 0.1124880000 0.0479990000 0.0000010000 0.3646560000 0.0019350000 115032459 0 402718720 3.8741359711 4.0127105713 3.6409273148 661 26.4000000000 0.0158496108 0.0084617170 0.0158496108 0.0091988279 0.9430770000 0.1084440000 0.0638950000 0.0348210000 0.3638700000 0.3709580000 115035235 0 402718720 3.8771069050 4.0124483109 3.6422502995 662 26.4400000000 0.0158861764 0.0084729322 0.0158861764 0.0091932776 0.5860660000 0.1331850000 0.0876220000 0.0000010000 0.3622140000 0.0019360000 115038011 0 402718720 3.8797891140 4.0126357079 3.6429009438 663 26.4800000000 0.0157960821 0.0084839777 0.0158861764 0.0091863596 0.5913180000 0.1124620000 0.0801650000 0.0352030000 0.3602880000 0.0020410000 115040787 0 402718720 3.8822598457 4.0119376183 3.6434309483 664 26.5200000000 0.0159339793 0.0084951975 0.0159339793 0.0091797798 0.5459040000 0.1099310000 0.0573580000 0.0000000000 0.3746510000 0.0027070000 115043563 0 402718720 3.8846678734 4.0109219551 3.6442553997 665 26.5600000000 0.0159802306 0.0085064532 0.0159802306 0.0091750654 1.0354020000 0.1448270000 0.0865400000 0.0454310000 0.3845290000 0.3729630000 115046339 0 402718720 3.8867318630 4.0093388557 3.6444149017 666 26.6000000000 0.0160011761 0.0085177066 0.0160011761 0.0091751095 0.5377290000 0.1123070000 0.0572780000 0.0000000000 0.3649640000 0.0020760000 115049115 0 402718720 3.8892571926 4.0087742805 3.6448774338 667 26.6400000000 0.0159774181 0.0085288905 0.0160011761 0.0091734613 0.5687480000 0.1122690000 0.0548400000 0.0345160000 0.3640730000 0.0019390000 115051891 0 402718720 3.8916418552 4.0080356598 3.6450066566 668 26.6800000000 0.0160859078 0.0085402034 0.0160859078 0.0091693136 0.5457270000 0.1220310000 0.0577770000 0.0000010000 0.3628690000 0.0019340000 115054667 0 402718720 3.8940596581 4.0074820518 3.6455252171 669 26.7200000000 0.0161222238 0.0085515368 0.0161222238 0.0091644145 0.9433410000 0.1120940000 0.0574540000 0.0350880000 0.3650560000 0.3725580000 115057443 0 402718720 3.8963086605 4.0063881874 3.6454870701 670 26.7600000000 0.0162124690 0.0085629710 0.0162124690 0.0091638550 0.5687350000 0.1120400000 0.0640690000 0.0000010000 0.3886620000 0.0026880000 115060219 0 402718720 3.8986732960 4.0060911179 3.6453049183 671 26.8000000000 0.0162705239 0.0085744577 0.0162705239 0.0091605302 0.6408320000 0.1443070000 0.0740680000 0.0445390000 0.3748630000 0.0019330000 115062995 0 402718720 3.9012582302 4.0064616203 3.6448998451 672 26.8400000000 0.0162411612 0.0085858665 0.0162705239 0.0091539787 0.5425710000 0.1079470000 0.0640260000 0.0000010000 0.3676100000 0.0018710000 115065771 0 402718720 3.9034998417 4.0050697327 3.6447067261 673 26.8800000000 0.0162529759 0.0085972589 0.0162705239 0.0091558260 0.9470230000 0.1117790000 0.0572230000 0.0345450000 0.3672600000 0.3751020000 115068547 0 402718720 3.9060039520 4.0043005943 3.6445605755 674 26.9200000000 0.0163590070 0.0086087749 0.0163590070 0.0091634209 0.5490470000 0.1115520000 0.0665990000 0.0000000000 0.3678340000 0.0019280000 115071323 0 402718720 3.9087376595 4.0051436424 3.6441612244 675 26.9600000000 0.0164100491 0.0086203323 0.0164100491 0.0091590099 0.5707810000 0.1115290000 0.0548330000 0.0350980000 0.3662700000 0.0019290000 115074099 0 402718720 3.9112730026 4.0051584244 3.6431379318 676 27.0000000000 0.0164252184 0.0086318780 0.0164252184 0.0091527015 0.5502980000 0.1115010000 0.0526660000 0.0000010000 0.3821660000 0.0026860000 115076875 0 402718720 3.9137787819 4.0038166046 3.6430976391 677 27.0400000000 0.0164549146 0.0086434334 0.0164549146 0.0091495556 1.0252570000 0.1439670000 0.0770300000 0.0452340000 0.3843380000 0.3735700000 115079651 0 402718720 3.9164628983 4.0037846565 3.6419944763 678 27.0800000000 0.0165474191 0.0086550912 0.0165474191 0.0091450168 0.5360430000 0.1207330000 0.0470960000 0.0000000000 0.3651530000 0.0019330000 115082427 0 402718720 3.9191639423 4.0035538673 3.6413688660 679 27.1200000000 0.0165020097 0.0086666478 0.0165474191 0.0091420591 0.5759490000 0.1242400000 0.0477700000 0.0349620000 0.3659110000 0.0019320000 115085203 0 402718720 3.9214744568 4.0030126572 3.6402013302 680 27.1600000000 0.0166014507 0.0086783166 0.0166014507 0.0091409205 0.5586570000 0.1324620000 0.0576440000 0.0000010000 0.3654710000 0.0019320000 115087979 0 402718720 3.9242451191 4.0035424232 3.6388721466 681 27.2000000000 0.0165661592 0.0086898994 0.0166014507 0.0091345803 0.9387470000 0.1113540000 0.0548350000 0.0343200000 0.3649880000 0.3721170000 115090755 0 402718720 3.9268829823 4.0033698082 3.6377565861 682 27.2400000000 0.0165900160 0.0087014831 0.0166014507 0.0091285206 0.5345650000 0.1100630000 0.0549290000 0.0000010000 0.3665110000 0.0019310000 115093531 0 402718720 3.9294364452 4.0030775070 3.6361291409 683 27.2800000000 0.0167169888 0.0087132189 0.0167169888 0.0091234997 0.5687290000 0.1114360000 0.0576490000 0.0349190000 0.3616490000 0.0019370000 115096307 0 402718720 3.9322969913 4.0032215118 3.6348853111 684 27.3200000000 0.0167177320 0.0087249214 0.0167177320 0.0091169751 0.5362580000 0.1115050000 0.0574430000 0.0000000000 0.3642390000 0.0019340000 115099083 0 402718720 3.9351103306 4.0030665398 3.6331884861 685 27.3600000000 0.0167753268 0.0087366738 0.0167753268 0.0091103802 0.9734630000 0.1115120000 0.0646320000 0.0348180000 0.3706020000 0.3906000000 115101859 0 402718720 3.9377315044 4.0012569427 3.6320564747 686 27.4000000000 0.0167570990 0.0087483654 0.0167753268 0.0091094093 0.6036250000 0.1439810000 0.0897460000 0.0000010000 0.3668180000 0.0019340000 115104635 0 402718720 3.9404659271 4.0003466606 3.6305513382 687 27.4400000000 0.0168093368 0.0087600989 0.0168093368 0.0091113015 0.5685900000 0.1113750000 0.0571710000 0.0342060000 0.3627580000 0.0019380000 115107411 0 402718720 3.9434943199 4.0005354881 3.6285645962 688 27.4800000000 0.0167770218 0.0087717514 0.0168093368 0.0091118015 0.5365430000 0.1241360000 0.0455050000 0.0000010000 0.3638110000 0.0019300000 115110187 0 402718720 3.9465477467 4.0004663467 3.6266410351 689 27.5200000000 0.0167994313 0.0087834027 0.0168093368 0.0091124426 0.9381000000 0.1249110000 0.0501440000 0.0348030000 0.3581590000 0.3689310000 115112963 0 402718720 3.9493086338 4.0001091957 3.6245112419 690 27.5600000000 0.0168714318 0.0087951244 0.0168714318 0.0091166590 0.5433980000 0.1112350000 0.0676590000 0.0000010000 0.3614240000 0.0019310000 115115739 0 402718720 3.9526193142 4.0009913445 3.6222665310 691 27.6000000000 0.0168612078 0.0088067975 0.0168714318 0.0091101767 0.5885150000 0.1111960000 0.0576310000 0.0347770000 0.3808850000 0.0026950000 115118515 0 402718720 3.9559073448 4.0019383430 3.6198365688 692 27.6400000000 0.0169174057 0.0088185180 0.0169174057 0.0091069235 0.6071160000 0.1437960000 0.0870640000 0.0000010000 0.3731710000 0.0019260000 115121291 0 402718720 3.9589748383 4.0021104813 3.6173303127 693 27.6800000000 0.0168944150 0.0088301716 0.0169174057 0.0091033654 0.9285890000 0.1111460000 0.0553530000 0.0346100000 0.3597170000 0.3666080000 115124067 0 402718720 3.9619398117 4.0013012886 3.6154980659 694 27.7200000000 0.0169290714 0.0088418414 0.0169290714 0.0090967966 0.5290480000 0.1110760000 0.0547980000 0.0000010000 0.3600890000 0.0019270000 115126843 0 402718720 3.9649310112 4.0010437965 3.6132011414 695 27.7600000000 0.0169611424 0.0088535239 0.0169611424 0.0090904616 0.5731170000 0.1110880000 0.0648870000 0.0340030000 0.3600470000 0.0019320000 115129619 0 402718720 3.9679465294 4.0005550385 3.6112954617 696 27.8000000000 0.0168933161 0.0088650753 0.0169611424 0.0090859653 0.5429140000 0.1237960000 0.0552110000 0.0000000000 0.3608210000 0.0019290000 115132395 0 402718720 3.9707841873 4.0001039505 3.6096322536 697 27.8400000000 0.0168292113 0.0088765016 0.0169611424 0.0090832688 0.9447290000 0.1234080000 0.0576050000 0.0345260000 0.3606380000 0.3673970000 115135171 0 402718720 3.9765379429 4.0009846687 3.6048061848 698 27.8800000000 0.0169225745 0.0088880289 0.0169611424 0.0090767610 0.5513060000 0.1213330000 0.0678460000 0.0000010000 0.3590290000 0.0019240000 115137947 0 402718720 3.9790549278 3.9999699593 3.6032357216 699 27.9200000000 0.0168687124 0.0088994462 0.0169611424 0.0090940851 0.5610370000 0.1111510000 0.0551260000 0.0346180000 0.3570530000 0.0019220000 115140723 0 402718720 3.9836244583 3.9996595383 3.5991935730 700 27.9600000000 0.0168051049 0.0089107400 0.0169611424 0.0090886589 0.5402650000 0.1111470000 0.0641470000 0.0000010000 0.3619430000 0.0018620000 115143499 0 402718720 3.9857044220 3.9989392757 3.5971391201 701 28.0000000000 0.0168277454 0.0089220339 0.0169611424 0.0090853738 0.9384940000 0.1111450000 0.0644540000 0.0344900000 0.3602130000 0.3670250000 115146275 0 402718720 3.9878730774 3.9979398251 3.5958790779 702 28.0400000000 0.0168183446 0.0089332822 0.0169611424 0.0090905216 0.5550960000 0.1343640000 0.0579220000 0.0000010000 0.3597300000 0.0019220000 115149051 0 402718720 3.9898118973 3.9970154762 3.5943136215 703 28.0800000000 0.0166608803 0.0089442745 0.0169611424 0.0091090086 0.5831760000 0.1113820000 0.0552970000 0.0345230000 0.3779350000 0.0026890000 115151827 0 402718720 3.9919700623 3.9971199036 3.5923297405 704 28.1200000000 0.0166468900 0.0089552157 0.0169611424 0.0091151518 0.5891480000 0.1440040000 0.0616550000 0.0000010000 0.3803950000 0.0019220000 115154603 0 402718720 3.9943642616 3.9972026348 3.5908122063 705 28.1600000000 0.0166889243 0.0089661855 0.0169611424 0.0091153718 0.9357060000 0.1242710000 0.0455860000 0.0344830000 0.3616610000 0.3685040000 115157379 0 402718720 3.9963030815 3.9963657856 3.5894474983 706 28.2000000000 0.0166334659 0.0089770457 0.0169611424 0.0091210437 0.5340560000 0.1116420000 0.0550120000 0.0000010000 0.3643090000 0.0019200000 115160155 0 402718720 3.9984323978 3.9958643913 3.5881123543 707 28.2400000000 0.0166561268 0.0089879072 0.0169611424 0.0091258045 0.5961350000 0.1308650000 0.0675590000 0.0346750000 0.3599150000 0.0019260000 115162931 0 402718720 4.0008206367 3.9967029095 3.5864868164 708 28.2800000000 0.0166541561 0.0089987352 0.0169611424 0.0091195183 0.5218340000 0.1118250000 0.0479290000 0.0000010000 0.3588190000 0.0020200000 115165707 0 402718720 4.0033454895 3.9969184399 3.5849380493 709 28.3200000000 0.0166623499 0.0090095443 0.0169611424 0.0091132043 0.9341690000 0.1118030000 0.0563770000 0.0347020000 0.3616070000 0.3684970000 115168483 0 402718720 4.0055088997 3.9958884716 3.5841581821 710 28.3600000000 0.0166605450 0.0090203204 0.0169611424 0.0091109367 0.5304740000 0.1118530000 0.0526820000 0.0000010000 0.3628450000 0.0019170000 115171259 0 402718720 4.0079231262 3.9954881668 3.5834782124 711 28.4000000000 0.0167365670 0.0090311730 0.0169611424 0.0091090350 0.5633510000 0.1118840000 0.0526750000 0.0338610000 0.3618280000 0.0019240000 115174035 0 402718720 4.0105099678 3.9962074757 3.5821440220 712 28.4400000000 0.0167074222 0.0090419543 0.0169611424 0.0091026396 0.5555160000 0.1263510000 0.0527760000 0.0000010000 0.3723400000 0.0026820000 115176811 0 402718720 4.0128922462 3.9953191280 3.5818290710 713 28.4800000000 0.0166635644 0.0090526438 0.0169611424 0.0090972044 1.0194150000 0.1444190000 0.0742220000 0.0435380000 0.3826210000 0.3734320000 115179587 0 402718720 4.0152153969 3.9944462776 3.5814917088 714 28.5200000000 0.0165902022 0.0090632006 0.0169611424 0.0090954539 0.5246530000 0.1120370000 0.0479520000 0.0000010000 0.3615520000 0.0019210000 115182363 0 402718720 4.0178217888 3.9948256016 3.5806961060 715 28.5600000000 0.0166016910 0.0090737439 0.0169611424 0.0090900088 0.5777070000 0.1081200000 0.0544650000 0.0335640000 0.3774980000 0.0026800000 115185139 0 402718720 4.0208482742 3.9958369732 3.5801150799 716 28.6000000000 0.0165720079 0.0090842163 0.0169611424 0.0090851064 0.6025750000 0.1445330000 0.0742330000 0.0000000000 0.3806970000 0.0019220000 115187915 0 402718720 4.0237364769 3.9962358475 3.5799179077 717 28.6400000000 0.0165724419 0.0090946602 0.0169611424 0.0090819192 0.9527620000 0.1308510000 0.0551150000 0.0344060000 0.3622660000 0.3689220000 115190691 0 402718720 4.0265741348 3.9959366322 3.5797848701 718 28.6800000000 0.0165899675 0.0091050993 0.0169611424 0.0090759168 0.5318640000 0.1103940000 0.0545490000 0.0000000000 0.3638630000 0.0018630000 115193467 0 402718720 4.0293240547 3.9958145618 3.5798430443 719 28.7200000000 0.0165428761 0.0091154439 0.0169611424 0.0090696272 0.5555530000 0.1120090000 0.0432480000 0.0343810000 0.3627880000 0.0019240000 115196243 0 402718720 4.0322208405 3.9953956604 3.5802602768 720 28.7600000000 0.0164652485 0.0091256520 0.0169611424 0.0090660346 0.5249750000 0.1120790000 0.0456300000 0.0000000000 0.3641430000 0.0019210000 115199019 0 402718720 4.0354218483 3.9950459003 3.5809912682 721 28.8000000000 0.0164420959 0.0091357996 0.0169611424 0.0090676188 0.9631210000 0.1121050000 0.0550540000 0.0344160000 0.3687760000 0.3914000000 115201795 0 402718720 4.0387396812 3.9962861538 3.5809829235 722 28.8400000000 0.0164272934 0.0091458987 0.0169611424 0.0090614243 0.5961310000 0.1446020000 0.0742790000 0.0000010000 0.3741240000 0.0019180000 115204571 0 402718720 4.0423040390 3.9966323376 3.5816750526 723 28.8800000000 0.0163804479 0.0091559049 0.0169611424 0.0090554864 0.5605190000 0.1121240000 0.0504530000 0.0344410000 0.3602160000 0.0020160000 115207347 0 402718720 4.0456981659 3.9967541695 3.5823776722 724 28.9200000000 0.0164158773 0.0091659325 0.0169611424 0.0090493253 0.5482420000 0.1121550000 0.0552820000 0.0000010000 0.3767490000 0.0026740000 115210123 0 402718720 4.0491437912 3.9969604015 3.5832715034 725 28.9600000000 0.0163441245 0.0091758335 0.0169611424 0.0090431804 1.0182630000 0.1446070000 0.0711230000 0.0440850000 0.3845150000 0.3727200000 115212899 0 402718720 4.0528140068 3.9968786240 3.5844414234 726 29.0000000000 0.0162665229 0.0091856003 0.0169611424 0.0090381783 0.5338100000 0.1121580000 0.0555660000 0.0000010000 0.3629380000 0.0019310000 115215675 0 402718720 4.0560321808 3.9967033863 3.5852212906 727 29.0400000000 0.0162896533 0.0091953720 0.0169611424 0.0090387072 0.5749590000 0.1122170000 0.0480460000 0.0343670000 0.3771850000 0.0019210000 115218451 0 402718720 4.0600252151 3.9976952076 3.5864231586 728 29.0800000000 0.0162642412 0.0092050820 0.0169611424 0.0090330537 0.5297240000 0.1121800000 0.0481240000 0.0000010000 0.3662640000 0.0019230000 115221227 0 402718720 4.0638780594 3.9984006882 3.5875012875 729 29.1200000000 0.0162124857 0.0092146943 0.0169611424 0.0090269377 0.9416990000 0.1122670000 0.0551200000 0.0346490000 0.3658870000 0.3725770000 115224003 0 402718720 4.0673694611 3.9977204800 3.5889618397 730 29.1600000000 0.0161616802 0.0092242108 0.0169611424 0.0090300673 0.5288040000 0.1122530000 0.0457210000 0.0000000000 0.3676750000 0.0019300000 115226779 0 402718720 4.0706853867 3.9975709915 3.5901525021 731 29.2000000000 0.0162511226 0.0092338235 0.0169611424 0.0090345822 0.5643960000 0.1122490000 0.0480060000 0.0337420000 0.3672430000 0.0019310000 115229555 0 402718720 4.0746345520 3.9982128143 3.5916867256 732 29.2400000000 0.0162575711 0.0092434188 0.0169611424 0.0090323946 0.5371820000 0.1214470000 0.0479900000 0.0000010000 0.3644400000 0.0020230000 115232331 0 402718720 4.0781855583 3.9984552860 3.5929608345 733 29.2800000000 0.0162290670 0.0092529490 0.0169611424 0.0090294557 0.9611930000 0.1123050000 0.0478830000 0.0343930000 0.3706610000 0.3945480000 115235107 0 402718720 4.0816149712 3.9988000393 3.5937762260 734 29.3200000000 0.0161210373 0.0092623061 0.0169611424 0.0090246594 0.6016290000 0.1448560000 0.0742840000 0.0000010000 0.3793340000 0.0019300000 115237883 0 402718720 4.0851478577 3.9989168644 3.5950155258 735 29.3600000000 0.0161850862 0.0092717248 0.0169611424 0.0090186824 0.5860760000 0.1250580000 0.0551850000 0.0336910000 0.3689580000 0.0019330000 115240659 0 402718720 4.0883135796 3.9988372326 3.5961148739 736 29.4000000000 0.0160963424 0.0092809974 0.0169611424 0.0090126540 0.5534950000 0.1251600000 0.0552400000 0.0000000000 0.3699280000 0.0019300000 115243435 0 402718720 4.0913138390 3.9983453751 3.5974071026 737 29.4400000000 0.0161466580 0.0092903131 0.0169611424 0.0090083560 0.9587920000 0.1124040000 0.0646670000 0.0337770000 0.3701670000 0.3765460000 115246211 0 402718720 4.0942306519 3.9983477592 3.5983901024 738 29.4800000000 0.0160996690 0.0092995399 0.0169611424 0.0090038869 0.5326250000 0.1123470000 0.0456820000 0.0000000000 0.3714330000 0.0019290000 115248987 0 402718720 4.0972981453 3.9986233711 3.5994863510 739 29.5200000000 0.0160746668 0.0093087078 0.0169611424 0.0089979337 0.5868600000 0.1083290000 0.0544810000 0.0343460000 0.3855930000 0.0026890000 115251763 0 402718720 4.0999560356 3.9980278015 3.6006753445 740 29.5600000000 0.0159943793 0.0093177425 0.0169611424 0.0089953591 0.6007400000 0.1449560000 0.0616860000 0.0000010000 0.3909380000 0.0019240000 115254539 0 402718720 4.1023144722 3.9971086979 3.6018602848 741 29.6000000000 0.0159708615 0.0093267211 0.0169611424 0.0090028929 0.9526460000 0.1124570000 0.0551490000 0.0336540000 0.3718760000 0.3782730000 115257315 0 402718720 4.1045470238 3.9969375134 3.6028130054 742 29.6400000000 0.0159512032 0.0093356490 0.0169611424 0.0090051719 0.6102480000 0.1347940000 0.0774840000 0.0000000000 0.3938480000 0.0026880000 115260091 0 402718720 4.1072931290 3.9972193241 3.6038062572 743 29.6800000000 0.0158926956 0.0093444741 0.0169611424 0.0090020841 0.6329270000 0.1451460000 0.0616820000 0.0430700000 0.3798450000 0.0019270000 115262867 0 402718720 4.1096091270 3.9973115921 3.6045942307 744 29.7200000000 0.0159183610 0.0093533099 0.0169611424 0.0089970233 0.5459590000 0.1126020000 0.0553270000 0.0000010000 0.3748550000 0.0019230000 115265643 0 402718720 4.1117835045 3.9971253872 3.6054613590 745 29.7600000000 0.0159327220 0.0093621413 0.0169611424 0.0089932948 0.9782410000 0.1085060000 0.0474380000 0.0340120000 0.3868340000 0.4000380000 115268419 0 402718720 4.1141195297 3.9979081154 3.6060998440 746 29.8000000000 0.0159515087 0.0093709743 0.0169611424 0.0089892816 0.5839790000 0.1451550000 0.0617990000 0.0000010000 0.3738520000 0.0019230000 115271195 0 402718720 4.1161084175 3.9985411167 3.6063868999 747 29.8400000000 0.0159435049 0.0093797728 0.0169611424 0.0089897175 0.5703000000 0.1125010000 0.0434060000 0.0342250000 0.3760470000 0.0026850000 115273971 0 402718720 4.1177372932 3.9974691868 3.6073393822 748 29.8800000000 0.0158530921 0.0093884270 0.0169611424 0.0089973985 0.6039120000 0.1278560000 0.0776710000 0.0000010000 0.3942730000 0.0026840000 115276747 0 402718720 4.1216573715 3.9975979328 3.6091690063 749 29.9200000000 0.0159223080 0.0093971505 0.0169611424 0.0089914209 1.0168930000 0.1451940000 0.0618660000 0.0437780000 0.3840480000 0.3807480000 115279523 0 402718720 4.1238183975 3.9980950356 3.6099052429 750 29.9600000000 0.0159073360 0.0094058307 0.0169611424 0.0089858243 0.5476290000 0.1125170000 0.0553540000 0.0000010000 0.3756000000 0.0026790000 115282299 0 402718720 4.1254215240 3.9980885983 3.6104767323 751 30.0000000000 0.0158855654 0.0094144589 0.0169611424 0.0089798591 0.6630150000 0.1451510000 0.0770760000 0.0429970000 0.3936430000 0.0026890000 115285075 0 402718720 4.1273775101 3.9986352921 3.6110086441 752 30.0400000000 0.0159365181 0.0094231318 0.0169611424 0.0089763581 0.5747440000 0.1451300000 0.0514380000 0.0000010000 0.3749800000 0.0019180000 115287851 0 402718720 4.1293940544 3.9991829395 3.6115164757 753 30.0800000000 0.0158508848 0.0094316680 0.0169611424 0.0089736884 0.9674620000 0.1125370000 0.0505520000 0.0343060000 0.3728910000 0.3957230000 115290627 0 402718720 4.1311736107 3.9986989498 3.6121664047 754 30.1200000000 0.0158969201 0.0094402426 0.0169611424 0.0089678118 0.6295690000 0.1450670000 0.0871890000 0.0000010000 0.3941200000 0.0019200000 115293403 0 402718720 4.1332011223 3.9990391731 3.6126158237 755 30.1600000000 0.0158467144 0.0094487280 0.0169611424 0.0089626333 0.5672390000 0.1084130000 0.0452060000 0.0339160000 0.3765710000 0.0018650000 115296179 0 402718720 4.1349859238 3.9989359379 3.6131360531 756 30.2000000000 0.0158845354 0.0094572410 0.0169611424 0.0089568614 0.5602080000 0.1124500000 0.0647930000 0.0000010000 0.3788430000 0.0026810000 115298955 0 402718720 4.1365327835 3.9980382919 3.6139249802 757 30.2400000000 0.0157827679 0.0094655970 0.0169611424 0.0089573115 1.0527500000 0.1451180000 0.0743170000 0.0429370000 0.3957310000 0.3933890000 115301731 0 402718720 4.1383399963 3.9971153736 3.6147441864 758 30.2800000000 0.0158149749 0.0094739735 0.0169611424 0.0089750497 0.5499710000 0.1125820000 0.0551000000 0.0000010000 0.3790970000 0.0019250000 115304507 0 402718720 4.1402430534 3.9973337650 3.6149415970 759 30.3200000000 0.0157624148 0.0094822587 0.0169611424 0.0089875932 0.5820950000 0.1126190000 0.0550040000 0.0335940000 0.3776780000 0.0019170000 115307283 0 402718720 4.1426753998 3.9976413250 3.6153438091 760 30.3600000000 0.0157450717 0.0094904992 0.0169611424 0.0089912726 0.5441470000 0.1126260000 0.0480300000 0.0000010000 0.3802970000 0.0019150000 115310059 0 402718720 4.1447653770 3.9973368645 3.6159327030 761 30.4000000000 0.0156986546 0.0094986571 0.0169611424 0.0090001731 0.9665950000 0.1127130000 0.0550840000 0.0336200000 0.3787670000 0.3851310000 115312835 0 402718720 4.1467523575 3.9969537258 3.6161680222 762 30.4400000000 0.0156991910 0.0095067943 0.0169611424 0.0090159061 0.5764970000 0.1295960000 0.0456370000 0.0000010000 0.3971180000 0.0026880000 115315611 0 402718720 4.1491928101 3.9970486164 3.6168320179 763 30.4800000000 0.0156660341 0.0095148667 0.0169611424 0.0090262706 0.6495360000 0.1455460000 0.0647790000 0.0430340000 0.3929730000 0.0019180000 115318387 0 402718720 4.1517939568 3.9972462654 3.6170697212 764 30.5200000000 0.0156385843 0.0095228820 0.0169611424 0.0090342604 0.5527930000 0.1127950000 0.0552480000 0.0000000000 0.3815460000 0.0019180000 115321163 0 402718720 4.1542634964 3.9968800545 3.6175169945 765 30.5600000000 0.0156215960 0.0095308542 0.0169611424 0.0090515565 0.9525740000 0.1090770000 0.0431670000 0.0336580000 0.3795250000 0.3858530000 115323939 0 402718720 4.1565923691 3.9967172146 3.6178629398 766 30.6000000000 0.0155869918 0.0095387604 0.0169611424 0.0090667172 0.5567720000 0.1256630000 0.0456990000 0.0000010000 0.3821910000 0.0019250000 115326715 0 402718720 4.1590838432 3.9973948002 3.6178019047 767 30.6400000000 0.0155578610 0.0095466080 0.0169611424 0.0090671273 0.5859180000 0.1128130000 0.0603600000 0.0337790000 0.3755820000 0.0020210000 115329491 0 402718720 4.1616826057 3.9978458881 3.6177189350 768 30.6800000000 0.0156636573 0.0095545729 0.0169611424 0.0090652762 0.5655900000 0.1128220000 0.0578330000 0.0000010000 0.3907690000 0.0026780000 115332267 0 402718720 4.1637597084 3.9976761341 3.6177403927 769 30.7200000000 0.0156765655 0.0095625339 0.0169611424 0.0090671643 1.0475430000 0.1456970000 0.0744940000 0.0429110000 0.3968700000 0.3862720000 115335043 0 402718720 4.1660814285 3.9982039928 3.6175856590 770 30.7600000000 0.0156256035 0.0095704080 0.0169611424 0.0090631541 0.5522100000 0.1127790000 0.0583190000 0.0000010000 0.3778950000 0.0019190000 115337819 0 402718720 4.1682963371 3.9986765385 3.6173431873 771 30.8000000000 0.0154904472 0.0095780864 0.0169611424 0.0090574316 0.5856900000 0.1127640000 0.0556950000 0.0340770000 0.3799240000 0.0019260000 115340595 0 402718720 4.1701292992 3.9978148937 3.6172387600 772 30.8400000000 0.0154412230 0.0095856811 0.0169611424 0.0090608669 0.5746640000 0.1319730000 0.0612620000 0.0000010000 0.3781940000 0.0019200000 115343371 0 402718720 4.1717228889 3.9976809025 3.6169326305 773 30.8800000000 0.0154529419 0.0095932714 0.0169611424 0.0090608904 0.9699940000 0.1126580000 0.0585190000 0.0344400000 0.3757930000 0.3871080000 115346147 0 402718720 4.1739120483 3.9982564449 3.6166722775 774 30.9200000000 0.0155178802 0.0096009259 0.0169611424 0.0090554383 0.6259060000 0.1456620000 0.0782030000 0.0000010000 0.3978640000 0.0026790000 115348923 0 402718720 4.1757898331 3.9983503819 3.6165039539 775 30.9600000000 0.0155637152 0.0096086198 0.0169611424 0.0090497551 0.6925830000 0.1456960000 0.1307660000 0.0335020000 0.3793870000 0.0019190000 115351699 0 402718720 4.1774210930 3.9987332821 3.6161723137 776 31.0000000000 0.0156129887 0.0096163574 0.0169611424 0.0090470922 0.5506650000 0.1126830000 0.0556880000 0.0000010000 0.3790620000 0.0019190000 115354475 0 402718720 4.1792616844 3.9988417625 3.6161007881 777 31.0400000000 0.0155616216 0.0096240090 0.0169611424 0.0090431861 0.9700200000 0.1125940000 0.0584680000 0.0340670000 0.3787060000 0.3848790000 115357251 0 402718720 4.1807789803 3.9986405373 3.6160025597 778 31.0800000000 0.0155857131 0.0096316718 0.0169611424 0.0090378822 0.5527660000 0.1127370000 0.0581340000 0.0000010000 0.3786600000 0.0019160000 115360027 0 402718720 4.1822938919 3.9997522831 3.6152832508 779 31.1200000000 0.0157291517 0.0096394992 0.0169611424 0.0090487755 0.5884210000 0.1126930000 0.0584430000 0.0334810000 0.3796090000 0.0026840000 115362803 0 402718720 4.1835460663 4.0006818771 3.6146030426 780 31.1600000000 0.0158307366 0.0096474366 0.0169611424 0.0090834246 0.6216980000 0.1455780000 0.0748810000 0.0000000000 0.3970690000 0.0026730000 115365579 0 402718720 4.1845355034 4.0010294914 3.6142861843 781 31.2000000000 0.0157960523 0.0096553094 0.0169611424 0.0091182458 1.0311810000 0.1455300000 0.0782160000 0.0415060000 0.3791320000 0.3854910000 115368355 0 402718720 4.1852831841 4.0011153221 3.6137278080 782 31.2400000000 0.0157730822 0.0096631326 0.0169611424 0.0091503496 0.5706230000 0.1261180000 0.0618150000 0.0000010000 0.3794350000 0.0019230000 115371131 0 402718720 4.1861329079 4.0014362335 3.6133472919 783 31.2800000000 0.0157953408 0.0096709643 0.0169611424 0.0091809435 0.5846900000 0.1126850000 0.0589930000 0.0341070000 0.3754870000 0.0020270000 115373907 0 402718720 4.1869449615 4.0014572144 3.6130208969 784 31.3200000000 0.0157183856 0.0096786779 0.0169611424 0.0091964302 0.5635620000 0.1126900000 0.0678310000 0.0000010000 0.3797800000 0.0019250000 115376683 0 402718720 4.1875548363 4.0011425018 3.6128010750 785 31.3600000000 0.0157756824 0.0096864447 0.0169611424 0.0091945158 0.9780630000 0.1126230000 0.0460940000 0.0333870000 0.3800030000 0.4044460000 115379459 0 402718720 4.1883091927 4.0009255409 3.6127641201 786 31.4000000000 0.0157842711 0.0096942028 0.0169611424 0.0091888389 0.6028410000 0.1452570000 0.0622040000 0.0000010000 0.3921250000 0.0019270000 115382235 0 402718720 4.1893444061 4.0017104149 3.6124026775 787 31.4400000000 0.0158218313 0.0097019888 0.0169611424 0.0091892191 0.5740870000 0.1126430000 0.0483460000 0.0341460000 0.3755360000 0.0020250000 115385011 0 402718720 4.1902713776 4.0023846626 3.6121804714 788 31.4800000000 0.0158041846 0.0097097328 0.0169611424 0.0091921729 0.5534330000 0.1125680000 0.0578790000 0.0000000000 0.3797290000 0.0019240000 115387787 0 402718720 4.1911907196 4.0028305054 3.6121199131 789 31.5200000000 0.0158026200 0.0097174550 0.0169611424 0.0091962560 0.9806480000 0.1252420000 0.0556650000 0.0333360000 0.3793810000 0.3856810000 115390563 0 402718720 4.1922197342 4.0038981438 3.6118304729 790 31.5600000000 0.0158002991 0.0097251548 0.0169611424 0.0092261497 0.5411870000 0.1124300000 0.0458470000 0.0000010000 0.3796610000 0.0019270000 115393339 0 402718720 4.1930713654 4.0046753883 3.6117455959 791 31.6000000000 0.0158820543 0.0097329385 0.0169611424 0.0092606853 0.5981950000 0.1123290000 0.0554010000 0.0339350000 0.3923050000 0.0026850000 115396115 0 402718720 4.1940903664 4.0049729347 3.6117315292 792 31.6400000000 0.0158873070 0.0097407092 0.0169611424 0.0092721548 0.6163250000 0.1447370000 0.0713810000 0.0000010000 0.3969200000 0.0019290000 115398891 0 402718720 4.1951928139 4.0054755211 3.6118888855 793 31.6800000000 0.0158960726 0.0097484713 0.0169611424 0.0092817659 0.9740020000 0.1121700000 0.0579830000 0.0339340000 0.3783260000 0.3900700000 115401667 0 402718720 4.1959476471 4.0062608719 3.6118102074 794 31.7200000000 0.0158524364 0.0097561589 0.0169611424 0.0093038222 0.5513630000 0.1145790000 0.0553520000 0.0000010000 0.3781750000 0.0019290000 115404443 0 402718720 4.1968774796 4.0072164536 3.6118705273 795 31.7600000000 0.0157951266 0.0097637551 0.0169611424 0.0093328957 0.6040860000 0.1119410000 0.0805790000 0.0339660000 0.3743150000 0.0019310000 115407219 0 402718720 4.1975941658 4.0076990128 3.6122369766 796 31.8000000000 0.0158555340 0.0097714081 0.0169611424 0.0093658388 0.5458630000 0.1118890000 0.0581870000 0.0000010000 0.3723570000 0.0020280000 115409995 0 402718720 4.1982474327 4.0086193085 3.6124322414 797 31.8400000000 0.0157850366 0.0097789534 0.0169611424 0.0094462902 1.0023440000 0.1249610000 0.0552890000 0.0338830000 0.3866850000 0.3999950000 115412771 0 402718720 4.1990308762 4.0094695091 3.6127662659 798 31.8800000000 0.0159585532 0.0097866973 0.0169611424 0.0095461372 0.5974470000 0.1436640000 0.0742970000 0.0000010000 0.3761970000 0.0019350000 115415547 0 402718720 4.1992020607 4.0099287033 3.6128785610 799 31.9200000000 0.0159506612 0.0097944119 0.0169611424 0.0096006283 0.5765690000 0.1109170000 0.0582830000 0.0339540000 0.3699360000 0.0021070000 115418323 0 402718720 4.1997728348 4.0102090836 3.6132278442 800 31.9600000000 0.0158325788 0.0098019596 0.0169611424 0.0096201852 0.5438830000 0.1108210000 0.0577860000 0.0000010000 0.3719710000 0.0019380000 115421099 0 402718720 4.2003083229 4.0103335381 3.6134622097 801 32.0000000000 0.0158738811 0.0098095400 0.0169611424 0.0096232446 0.9451400000 0.1069170000 0.0547970000 0.0334430000 0.3715110000 0.3771230000 115423875 0 402718720 4.2010693550 4.0106005669 3.6140170097 802 32.0400000000 0.0158348940 0.0098170529 0.0169611424 0.0096256450 0.5489880000 0.1222460000 0.0555510000 0.0000000000 0.3678960000 0.0019280000 115426651 0 402718720 4.2018260956 4.0107808113 3.6144390106 803 32.0800000000 0.0158573464 0.0098245751 0.0169611424 0.0096240538 0.6110410000 0.1154550000 0.0616300000 0.0423000000 0.3874340000 0.0026910000 115429427 0 402718720 4.2026677132 4.0111742020 3.6148679256 804 32.1199999990 0.0159557294 0.0098322009 0.0169611424 0.0096229415 0.5977540000 0.1434200000 0.0742990000 0.0000010000 0.3767450000 0.0019270000 115432203 0 402718720 4.2033877373 4.0114974976 3.6155390739 805 32.1600000000 0.0158640854 0.0098396939 0.0169611424 0.0096238658 0.9446270000 0.1237380000 0.0457370000 0.0331360000 0.3672260000 0.3734390000 115434979 0 402718720 4.2039971352 4.0116448402 3.6160261631 806 32.2000000000 0.0159266442 0.0098472460 0.0169611424 0.0096230039 0.5382090000 0.1108970000 0.0577100000 0.0000010000 0.3663140000 0.0019350000 115437755 0 402718720 4.2045989037 4.0116591454 3.6166687012 807 32.2400000000 0.0159563757 0.0098548162 0.0169611424 0.0096179864 0.5718330000 0.1236760000 0.0458690000 0.0338210000 0.3651480000 0.0019390000 115440531 0 402718720 4.2054810524 4.0118546486 3.6172406673 808 32.2800000000 0.0160028823 0.0098624252 0.0169611424 0.0096128320 0.5372900000 0.1109830000 0.0578510000 0.0000000000 0.3652180000 0.0018810000 115443307 0 402718720 4.2060317993 4.0121006966 3.6178078651 809 32.3200000000 0.0159477275 0.0098699472 0.0169611424 0.0096090348 0.9352830000 0.1109700000 0.0554090000 0.0337430000 0.3636700000 0.3701330000 115446083 0 402718720 4.2067651749 4.0121846199 3.6184365749 810 32.3600000000 0.0159825254 0.0098774936 0.0169611424 0.0096056290 0.5318060000 0.1071500000 0.0572420000 0.0000000000 0.3640920000 0.0019320000 115448859 0 402718720 4.2073693275 4.0120449066 3.6192595959 811 32.4000000000 0.0160271563 0.0098850764 0.0169611424 0.0095999346 0.5657170000 0.1110260000 0.0548810000 0.0337270000 0.3627720000 0.0019390000 115451635 0 402718720 4.2081274986 4.0119876862 3.6200463772 812 32.4399999990 0.0160452481 0.0098926628 0.0169611424 0.0095942652 0.5612490000 0.1200580000 0.0751970000 0.0000010000 0.3626900000 0.0019340000 115454411 0 402718720 4.2088966370 4.0118432045 3.6209418774 813 32.4800000000 0.0160978213 0.0099002952 0.0169611424 0.0095891754 0.9298280000 0.1109900000 0.0580490000 0.0337790000 0.3575870000 0.3680620000 115457187 0 402718720 4.2098407745 4.0120391846 3.6216998100 814 32.5200000000 0.0161598399 0.0099079851 0.0169611424 0.0095862955 0.5311960000 0.1110100000 0.0581310000 0.0000010000 0.3587520000 0.0019340000 115459963 0 402718720 4.2105894089 4.0118999481 3.6227066517 815 32.5600000000 0.0162311569 0.0099157436 0.0169611424 0.0095882508 0.5633470000 0.1108920000 0.0551560000 0.0336990000 0.3602670000 0.0019350000 115462739 0 402718720 4.2113490105 4.0118823051 3.6236920357 816 32.6000000000 0.0161972083 0.0099234414 0.0169611424 0.0095907804 0.5296050000 0.1108180000 0.0552050000 0.0000010000 0.3602680000 0.0019310000 115465515 0 402718720 4.2121481895 4.0120458603 3.6245291233 817 32.6400000000 0.0162425805 0.0099311760 0.0169611424 0.0095929445 0.9462410000 0.1108790000 0.0741790000 0.0337350000 0.3597370000 0.3663290000 115468291 0 402718720 4.2128095627 4.0119738579 3.6255080700 818 32.6800000000 0.0163148232 0.0099389800 0.0169611424 0.0095964909 0.5315410000 0.1109210000 0.0576190000 0.0000000000 0.3596640000 0.0019360000 115471067 0 402718720 4.2134828568 4.0120286942 3.6264443398 819 32.7200000000 0.0162664633 0.0099467058 0.0169611424 0.0095981412 0.5623880000 0.1109180000 0.0551790000 0.0332420000 0.3597250000 0.0019300000 115473843 0 402718720 4.2140097618 4.0119032860 3.6275389194 820 32.7599999990 0.0163597427 0.0099545266 0.0169611424 0.0096013261 0.5217880000 0.1109550000 0.0480880000 0.0000000000 0.3594180000 0.0019320000 115476619 0 402718720 4.2141947746 4.0117678642 3.6284201145 821 32.7999999990 0.0162654612 0.0099622135 0.0169611424 0.0096046229 0.9159910000 0.1110490000 0.0457930000 0.0331000000 0.3590850000 0.3655920000 115479395 0 402718720 4.2143664360 4.0115909576 3.6291899681 822 32.8400000000 0.0163217094 0.0099699501 0.0169611424 0.0096079467 0.5488030000 0.1412330000 0.0480890000 0.0000010000 0.3561560000 0.0019260000 115482171 0 402718720 4.2143034935 4.0111050606 3.6301136017 823 32.8800000000 0.0162351709 0.0099775628 0.0169611424 0.0096191020 0.5584370000 0.1072770000 0.0547520000 0.0334560000 0.3596730000 0.0018710000 115484947 0 402718720 4.2146034241 4.0106849670 3.6313776970 824 32.9200000000 0.0162073579 0.0099851232 0.0169611424 0.0096279042 0.5288370000 0.1113770000 0.0552270000 0.0000010000 0.3589160000 0.0019260000 115487723 0 402718720 4.2144918442 4.0101470947 3.6322987080 825 32.9600000000 0.0161256362 0.0099925663 0.0169611424 0.0096390762 0.9174020000 0.1114910000 0.0458330000 0.0339300000 0.3590300000 0.3657100000 115490499 0 402718720 4.2144708633 4.0097312927 3.6332805157 826 33.0000000000 0.0160642304 0.0099999169 0.0169611424 0.0096499759 0.5321950000 0.1116220000 0.0577010000 0.0000000000 0.3595580000 0.0019260000 115493275 0 402718720 4.2142434120 4.0096430779 3.6338841915 827 33.0400000000 0.0160497129 0.0100072323 0.0169611424 0.0096546235 0.5537250000 0.1117860000 0.0457850000 0.0334110000 0.3594230000 0.0019180000 115496051 0 402718720 4.2140455246 4.0092339516 3.6347751617 828 33.0800000000 0.0160384402 0.0100145164 0.0169611424 0.0096626486 0.5207020000 0.1119210000 0.0457370000 0.0000010000 0.3597270000 0.0019150000 115498827 0 402718720 4.2135686874 4.0087022781 3.6353805065 829 33.1199999990 0.0160744023 0.0100218262 0.0169611424 0.0096714801 0.9184330000 0.1120380000 0.0457690000 0.0332260000 0.3597930000 0.3662060000 115501603 0 402718720 4.2131228447 4.0088353157 3.6359531879 830 33.1600000000 0.0161056723 0.0100291562 0.0169611424 0.0096714327 0.5330140000 0.1121090000 0.0577410000 0.0000010000 0.3598620000 0.0019160000 115504379 0 402718720 4.2128734589 4.0087957382 3.6371464729 831 33.2000000000 0.0161380563 0.0100365074 0.0169611424 0.0096749388 0.5730220000 0.1319120000 0.0481700000 0.0338890000 0.3555490000 0.0020180000 115507155 0 402718720 4.2114524841 4.0089082718 3.6383030415 832 33.2400000000 0.0161926076 0.0100439066 0.0169611424 0.0096695785 0.5227230000 0.1121470000 0.0482050000 0.0000010000 0.3590380000 0.0019150000 115509931 0 402718720 4.2111911774 4.0087642670 3.6394600868 833 33.2800000000 0.0161769129 0.0100512691 0.0169611424 0.0096651652 0.9232850000 0.1082220000 0.0476320000 0.0338400000 0.3571610000 0.3748110000 115512707 0 402718720 4.2103600502 4.0085053444 3.6402299404 834 33.3200000000 0.0162115041 0.0100586555 0.0169611424 0.0096611378 0.5863130000 0.1447020000 0.0586370000 0.0000000000 0.3786960000 0.0026720000 115515483 0 402718720 4.2096447945 4.0087490082 3.6411216259 835 33.3600000000 0.0162710063 0.0100660955 0.0169611424 0.0096554802 0.5899780000 0.1447420000 0.0509020000 0.0332360000 0.3577460000 0.0019180000 115518259 0 402718720 4.2091445923 4.0088691711 3.6422326565 836 33.4000000000 0.0162722301 0.0100735191 0.0169611424 0.0096498447 0.5414190000 0.1250250000 0.0553400000 0.0000010000 0.3577160000 0.0019150000 115521035 0 402718720 4.2081522942 4.0084695816 3.6431620121 837 33.4399999990 0.0163606815 0.0100810306 0.0169611424 0.0096450689 0.9209840000 0.1122170000 0.0525180000 0.0338890000 0.3571830000 0.3637570000 115523811 0 402718720 4.2071447372 4.0082588196 3.6439542770 838 33.4800000000 0.0163228344 0.0100884791 0.0169611424 0.0096402356 0.5285930000 0.1126260000 0.0555390000 0.0000010000 0.3570890000 0.0019180000 115526587 0 402718720 4.2061390877 4.0081925392 3.6446418762 839 33.5200000000 0.0163607951 0.0100959550 0.0169611424 0.0096347120 0.5512160000 0.1122970000 0.0460770000 0.0332480000 0.3562500000 0.0019200000 115529363 0 402718720 4.2049746513 4.0080804825 3.6450495720 840 33.5600000000 0.0163711887 0.0101034255 0.0169611424 0.0096293848 0.5484560000 0.1331530000 0.0556200000 0.0000010000 0.3563390000 0.0019160000 115532139 0 402718720 4.2038121223 4.0073318481 3.6458549500 841 33.6000000000 0.0163398478 0.0101108410 0.0169611424 0.0096267869 0.9217280000 0.1123520000 0.0555130000 0.0339100000 0.3560120000 0.3625240000 115534915 0 402718720 4.2024831772 4.0063199997 3.6471121311 842 33.6400000000 0.0164015722 0.0101183122 0.0169611424 0.0096324298 0.5385240000 0.1256410000 0.0483050000 0.0000010000 0.3602310000 0.0026770000 115537691 0 402718720 4.2012529373 4.0059523582 3.6477999687 843 33.6800000000 0.0164421685 0.0101258138 0.0169611424 0.0096337945 0.6454190000 0.1450950000 0.0774440000 0.0425900000 0.3759790000 0.0026740000 115540467 0 402718720 4.2000846863 4.0059618950 3.6485033035 844 33.7200000000 0.0165325124 0.0101334047 0.0169611424 0.0096311456 0.6044270000 0.1451470000 0.0776770000 0.0000010000 0.3772710000 0.0026780000 115543243 0 402718720 4.1987767220 4.0055351257 3.6494801044 845 33.7599999990 0.0165523123 0.0101410010 0.0169611424 0.0096321582 0.9885690000 0.1452280000 0.0742490000 0.0426290000 0.3639130000 0.3611250000 115546019 0 402718720 4.1973767281 4.0053925514 3.6496584415 846 33.7999999990 0.0165973976 0.0101486327 0.0169611424 0.0096321174 0.5179920000 0.1124810000 0.0457140000 0.0000000000 0.3564510000 0.0019150000 115548795 0 402718720 4.1961989403 4.0056877136 3.6502988338 847 33.8400000000 0.0166650899 0.0101563262 0.0169611424 0.0096282158 0.5580900000 0.1125370000 0.0551150000 0.0334150000 0.3536540000 0.0019160000 115551571 0 402718720 4.1951084137 4.0058550835 3.6512856483 848 33.8800000000 0.0167107154 0.0101640555 0.0169611424 0.0096227389 0.5210900000 0.1084330000 0.0548460000 0.0000000000 0.3544430000 0.0019140000 115554347 0 402718720 4.1937513351 4.0059738159 3.6517913342 849 33.9200000000 0.0167968906 0.0101718680 0.0169611424 0.0096172509 0.9133210000 0.1124930000 0.0551790000 0.0338450000 0.3519990000 0.3583720000 115557123 0 402718720 4.1925840378 4.0062675476 3.6522781849 850 33.9600000000 0.0167454965 0.0101796017 0.0169611424 0.0096124143 0.5226470000 0.1124810000 0.0551340000 0.0000000000 0.3516300000 0.0019140000 115559899 0 402718720 4.1913633347 4.0061450005 3.6535124779 851 34.0000000000 0.0167581886 0.0101873321 0.0169611424 0.0096088223 0.5540800000 0.1124600000 0.0550040000 0.0338210000 0.3494390000 0.0019130000 115562675 0 402718720 4.1899881363 4.0059781075 3.6536359787 852 34.0400000000 0.0167506505 0.0101950355 0.0169611424 0.0096054098 0.5458430000 0.1385490000 0.0551150000 0.0000000000 0.3488350000 0.0019080000 115565451 0 402718720 4.1882433891 4.0058083534 3.6533441544 853 34.0800000000 0.0167778023 0.0102027527 0.0169611424 0.0096016150 0.9017920000 0.1124300000 0.0574960000 0.0338120000 0.3438100000 0.3528040000 115568227 0 402718720 4.1868481636 4.0054478645 3.6537506580 854 34.1199999990 0.0167551357 0.0102104253 0.0169611424 0.0095972669 0.5228990000 0.1122760000 0.0608140000 0.0000010000 0.3464530000 0.0019070000 115571003 0 402718720 4.1855893135 4.0048422813 3.6546711922 855 34.1600000000 0.0167304892 0.0102180511 0.0169611424 0.0095923371 0.5413850000 0.1122390000 0.0479830000 0.0331260000 0.3446510000 0.0019120000 115573779 0 402718720 4.1842794418 4.0034718513 3.6559739113 856 34.2000000000 0.0168237146 0.0102257680 0.0169611424 0.0095903309 0.5397230000 0.1121490000 0.0778480000 0.0000000000 0.3462130000 0.0020060000 115576555 0 402718720 4.1831507683 4.0026979446 3.6576406956 857 34.2400000000 0.0168039128 0.0102334438 0.0169611424 0.0095911865 0.9169450000 0.1355410000 0.0574830000 0.0337630000 0.3401770000 0.3485300000 115579331 0 402718720 4.1821107864 4.0027775764 3.6586492062 858 34.2800000000 0.0168382991 0.0102411418 0.0169611424 0.0095867928 0.5129820000 0.1080840000 0.0547530000 0.0000010000 0.3467730000 0.0019050000 115582107 0 402718720 4.1808600426 4.0021862984 3.6600401402 859 34.3200000000 0.0168934204 0.0102488860 0.0169611424 0.0095841046 0.5452970000 0.1119450000 0.0547040000 0.0337970000 0.3414660000 0.0019120000 115584883 0 402718720 4.1794705391 4.0017509460 3.6616680622 860 34.3600000000 0.0169357192 0.0102566614 0.0169611424 0.0095802800 0.5116800000 0.1079500000 0.0545530000 0.0000010000 0.3458890000 0.0018420000 115587659 0 402718720 4.1780886650 4.0019640923 3.6629307270 861 34.4000000000 0.0169377401 0.0102644210 0.0169611424 0.0095748858 0.8876900000 0.1116960000 0.0548120000 0.0336120000 0.3398080000 0.3462860000 115590435 0 402718720 4.1766200066 4.0017485619 3.6643638611 862 34.4400000000 0.0170580298 0.0102723022 0.0170580298 0.0095694148 0.5328110000 0.1218980000 0.0678360000 0.0000010000 0.3395180000 0.0020060000 115593211 0 402718720 4.1751728058 4.0017075539 3.6661000252 863 34.4800000000 0.0169903021 0.0102800867 0.0170580298 0.0095639178 0.5422170000 0.1116180000 0.0576640000 0.0336470000 0.3357330000 0.0020100000 115595987 0 402718720 4.1736717224 4.0019173622 3.6677162647 864 34.5200000000 0.0170143191 0.0102878810 0.0170580298 0.0095589288 0.5133400000 0.1115700000 0.0578820000 0.0000000000 0.3404950000 0.0019060000 115598763 0 402718720 4.1717839241 4.0021901131 3.6697063446 865 34.5600000000 0.0171605852 0.0102958263 0.0171605852 0.0095551609 0.8785500000 0.1077140000 0.0543480000 0.0336000000 0.3375180000 0.3439010000 115601539 0 402718720 4.1699147224 4.0019650459 3.6718287468 866 34.6000000000 0.0171312261 0.0103037194 0.0171605852 0.0095497074 0.5224080000 0.1241950000 0.0550770000 0.0000010000 0.3397600000 0.0019040000 115604315 0 402718720 4.1678185463 4.0016350746 3.6741638184 867 34.6400000000 0.0171388239 0.0103116030 0.0171605852 0.0095445706 0.5442210000 0.1132220000 0.0575510000 0.0336540000 0.3363990000 0.0019080000 115607091 0 402718720 4.1656723022 4.0022025108 3.6758522987 868 34.6800000000 0.0172143523 0.0103195555 0.0172143523 0.0095407093 0.5086010000 0.1113800000 0.0577700000 0.0000010000 0.3358910000 0.0020050000 115609867 0 402718720 4.1633982658 4.0027775764 3.6779446602 869 34.7200000000 0.0171987377 0.0103274717 0.0172143523 0.0095383330 0.8771420000 0.1112460000 0.0594530000 0.0336450000 0.3322170000 0.3390470000 115612643 0 402718720 4.1610956192 4.0034809113 3.6799654961 870 34.7600000000 0.0172053687 0.0103353773 0.0172143523 0.0095412151 0.5085910000 0.1112860000 0.0578120000 0.0000000000 0.3361030000 0.0019090000 115615419 0 402718720 4.1584830284 4.0038990974 3.6824388504 871 34.8000000000 0.0172088575 0.0103432688 0.0172143523 0.0095444920 0.5371810000 0.1113470000 0.0547790000 0.0335130000 0.3341340000 0.0019090000 115618195 0 402718720 4.1557416916 4.0033016205 3.6849138737 872 34.8400000000 0.0171985961 0.0103511304 0.0172143523 0.0095390368 0.5163040000 0.1211270000 0.0578780000 0.0000000000 0.3337580000 0.0020050000 115620971 0 402718720 4.1528348923 4.0027785301 3.6877558231 873 34.8800000000 0.0171919316 0.0103589664 0.0172143523 0.0095380377 0.8748060000 0.1111490000 0.0543190000 0.0335280000 0.3338620000 0.3404700000 115623747 0 402718720 4.1501216888 4.0040912628 3.6899387836 874 34.9200000000 0.0173256882 0.0103669374 0.0173256882 0.0095333024 0.5053820000 0.1111520000 0.0549950000 0.0000000000 0.3358290000 0.0019080000 115626523 0 402718720 4.1473455429 4.0054841042 3.6919941902 875 34.9600000000 0.0173322018 0.0103748977 0.0173322018 0.0095368197 0.5365720000 0.1112900000 0.0548390000 0.0334990000 0.3335460000 0.0019090000 115629299 0 402718720 4.1443600655 4.0058207512 3.6942431927 876 35.0000000000 0.0174091663 0.0103829277 0.0174091663 0.0095401190 0.5051900000 0.1113290000 0.0548650000 0.0000010000 0.3355890000 0.0019080000 115632075 0 402718720 4.1413459778 4.0061683655 3.6965565681 877 35.0400000000 0.0173644759 0.0103908884 0.0174091663 0.0095410903 0.8722730000 0.1113580000 0.0551390000 0.0338090000 0.3315570000 0.3389310000 115634851 0 402718720 4.1383495331 4.0067501068 3.6988391876 878 35.0800000000 0.0175130833 0.0103990003 0.0175130833 0.0095459207 0.5103160000 0.1076290000 0.0639210000 0.0000010000 0.3354130000 0.0018430000 115637627 0 402718720 4.1352214813 4.0066838264 3.7012224197 879 35.1200000000 0.0173922610 0.0104069562 0.0175130833 0.0095442062 0.5211770000 0.1075910000 0.0451800000 0.0331940000 0.3317950000 0.0019070000 115640403 0 402718720 4.1321668625 4.0071325302 3.7031521797 880 35.1600000000 0.0174952894 0.0104150111 0.0175130833 0.0095506616 0.5037840000 0.1114290000 0.0551280000 0.0000010000 0.3338160000 0.0019060000 115643179 0 402718720 4.1292252541 4.0081796646 3.7057192326 881 35.2000000000 0.0175137203 0.0104230687 0.0175137203 0.0095674476 0.8582220000 0.1113220000 0.0452300000 0.0325590000 0.3307800000 0.3368440000 115645955 0 402718720 4.1261482239 4.0080590248 3.7076480389 882 35.2400000000 0.0175480284 0.0104311469 0.0175480284 0.0095685572 0.5086670000 0.1254470000 0.0504570000 0.0000010000 0.3291900000 0.0020080000 115648731 0 402718720 4.1231422424 4.0080361366 3.7101976871 883 35.2800000000 0.0174840130 0.0104391343 0.0175480284 0.0095648670 0.5312080000 0.1112900000 0.0577620000 0.0330060000 0.3257410000 0.0019060000 115651507 0 402718720 4.1199703217 4.0081105232 3.7124807835 884 35.3200000000 0.0175073445 0.0104471300 0.0175480284 0.0095604906 0.5259140000 0.1111510000 0.0578930000 0.0000010000 0.3525160000 0.0026590000 115654283 0 402718720 4.1171879768 4.0090479851 3.7144882679 885 35.3600000000 0.0174550954 0.0104550486 0.0175480284 0.0095572485 0.9523900000 0.1438220000 0.0772230000 0.0418370000 0.3487960000 0.3392140000 115657059 0 402718720 4.1142549515 4.0094614029 3.7165217400 886 35.4000000000 0.0175126381 0.0104630143 0.0175480284 0.0095528592 0.4918390000 0.1110220000 0.0480350000 0.0000010000 0.3293790000 0.0018980000 115659835 0 402718720 4.1112675667 4.0094404221 3.7187054157 887 35.4400000000 0.0175275952 0.0104709788 0.0175480284 0.0095476346 0.5571200000 0.1374300000 0.0576940000 0.0329620000 0.3256000000 0.0019020000 115662611 0 402718720 4.1083359718 4.0095090866 3.7205340862 888 35.4800000000 0.0177267194 0.0104791497 0.0177267194 0.0095423632 0.4982520000 0.1107040000 0.0578790000 0.0000010000 0.3260890000 0.0020000000 115665387 0 402718720 4.1055808067 4.0097332001 3.7224745750 889 35.5200000000 0.0177247971 0.0104873001 0.0177267194 0.0095387594 0.8545240000 0.1106290000 0.0574950000 0.0329230000 0.3225780000 0.3293280000 115668163 0 402718720 4.1029582024 4.0102572441 3.7239701748 890 35.5600000000 0.0176160708 0.0104953099 0.0177267194 0.0095339541 0.4990010000 0.1104880000 0.0573390000 0.0000010000 0.3277550000 0.0019030000 115670939 0 402718720 4.1003103256 4.0107693672 3.7256674767 891 35.6000000000 0.0175938606 0.0105032769 0.0177267194 0.0095286938 0.5229990000 0.1102390000 0.0546200000 0.0326880000 0.3220110000 0.0019050000 115673715 0 402718720 4.0977010727 4.0115351677 3.7274544239 892 35.6400000000 0.0176578481 0.0105112977 0.0177267194 0.0095234103 0.5165080000 0.1190030000 0.0675460000 0.0000010000 0.3265220000 0.0019040000 115676491 0 402718720 4.0951614380 4.0120415688 3.7292048931 893 35.6800000000 0.0176179390 0.0105192558 0.0177267194 0.0095181396 0.8636410000 0.1098040000 0.0570360000 0.0332020000 0.3182920000 0.3435910000 115679267 0 402718720 4.0925946236 4.0124816895 3.7306847572 894 35.7200000000 0.0177609958 0.0105273562 0.0177609958 0.0095129980 0.5683050000 0.1410040000 0.0769400000 0.0000010000 0.3459640000 0.0026590000 115682043 0 402718720 4.0901079178 4.0131125450 3.7322707176 895 35.7600000000 0.0176942404 0.0105353639 0.0177609958 0.0095082243 0.5995820000 0.1402600000 0.0733010000 0.0420530000 0.3395630000 0.0026680000 115684819 0 402718720 4.0876121521 4.0134034157 3.7335727215 896 35.8000000000 0.0178283118 0.0105435034 0.0178283118 0.0095031618 0.5541240000 0.1394550000 0.0771370000 0.0000010000 0.3341000000 0.0019070000 115687595 0 402718720 4.0851879120 4.0136599541 3.7349843979 897 35.8400000000 0.0178289749 0.0105516254 0.0178289749 0.0094979859 0.8420930000 0.1085260000 0.0598620000 0.0330220000 0.3162020000 0.3229730000 115690371 0 402718720 4.0827970505 4.0141553879 3.7361209393 898 35.8800000000 0.0179543886 0.0105598690 0.0179543886 0.0094929944 0.5029590000 0.1051180000 0.0730550000 0.0000020000 0.3213640000 0.0019070000 115693147 0 402718720 4.0803456306 4.0149507523 3.7373466492 899 35.9200000000 0.0179227274 0.0105680591 0.0179543886 0.0094883726 0.5131510000 0.1069330000 0.0544400000 0.0328030000 0.3155490000 0.0019060000 115695923 0 402718720 4.0777530670 4.0151028633 3.7380118370 900 35.9600000000 0.0179465618 0.0105762574 0.0179543886 0.0094831364 0.4949750000 0.1058440000 0.0642200000 0.0000010000 0.3214770000 0.0019070000 115698699 0 402718720 4.0752067566 4.0147852898 3.7387521267 901 36.0000000000 0.0178749170 0.0105843580 0.0179543886 0.0094795800 0.8337630000 0.1049830000 0.0569200000 0.0327470000 0.3154830000 0.3221040000 115701475 0 402718720 4.0728302002 4.0148916245 3.7388510704 902 36.0400000000 0.0179895870 0.0105925678 0.0179895870 0.0094744252 0.5001500000 0.1158770000 0.0602500000 0.0000010000 0.3204010000 0.0020050000 115704251 0 402718720 4.0704712868 4.0153460503 3.7389249802 903 36.0800000000 0.0179952066 0.0106007657 0.0179952066 0.0094692855 0.5400980000 0.1017370000 0.0861080000 0.0328070000 0.3160610000 0.0018410000 115707027 0 402718720 4.0678977966 4.0152549744 3.7394218445 904 36.1200000000 0.0180759765 0.0106090347 0.0180759765 0.0094641187 0.4756530000 0.1035830000 0.0478610000 0.0000010000 0.3205920000 0.0020000000 115709803 0 402718720 4.0654664040 4.0153985023 3.7395164967 905 36.1600000000 0.0179731734 0.0106171719 0.0180759765 0.0094594006 0.8561430000 0.1024670000 0.0773690000 0.0330480000 0.3173500000 0.3243820000 115712579 0 402718720 4.0629801750 4.0157332420 3.7401843071 906 36.2000000000 0.0180878285 0.0106254176 0.0180878285 0.0094559020 0.4852100000 0.1030900000 0.0549210000 0.0000010000 0.3237490000 0.0019030000 115715355 0 402718720 4.0603795052 4.0158352852 3.7402470112 907 36.2400000000 0.0181157440 0.0106336760 0.0181157440 0.0094524364 0.5320690000 0.1033030000 0.0734370000 0.0324740000 0.3194090000 0.0019040000 115718131 0 402718720 4.0577673912 4.0156111717 3.7397418022 908 36.2800000000 0.0180806331 0.0106418775 0.0181157440 0.0094473230 0.4794230000 0.1037710000 0.0479660000 0.0000000000 0.3242420000 0.0018980000 115720907 0 402718720 4.0551028252 4.0154228210 3.7391848564 909 36.3200000000 0.0180583913 0.0106500364 0.0181157440 0.0094421403 0.8421880000 0.1042540000 0.0571260000 0.0330850000 0.3198760000 0.3262980000 115723683 0 402718720 4.0524697304 4.0154290199 3.7390658855 910 36.3600000000 0.0180695746 0.0106581898 0.0181157440 0.0094370092 0.4999980000 0.1048230000 0.0670540000 0.0000000000 0.3246850000 0.0019020000 115726459 0 402718720 4.0498495102 4.0156731606 3.7390472889 911 36.4000000000 0.0181250796 0.0106663862 0.0181250796 0.0094322253 0.5195100000 0.1053020000 0.0548420000 0.0332800000 0.3226310000 0.0019010000 115729235 0 402718720 4.0471997261 4.0154275894 3.7386813164 912 36.4400000000 0.0181160774 0.0106745547 0.0181250796 0.0094270594 0.5079450000 0.1218800000 0.0551440000 0.0000010000 0.3274660000 0.0019000000 115732011 0 402718720 4.0447015762 4.0156202316 3.7388741970 913 36.4800000000 0.0181058105 0.0106826941 0.0181250796 0.0094221958 0.8540220000 0.1063890000 0.0572760000 0.0328520000 0.3246880000 0.3312450000 115734787 0 402718720 4.0422139168 4.0159101486 3.7392225266 914 36.5200000000 0.0181245096 0.0106908361 0.0181250796 0.0094187010 0.4850940000 0.1068570000 0.0456260000 0.0000010000 0.3291530000 0.0019010000 115737563 0 402718720 4.0395693779 4.0157446861 3.7391462326 915 36.5600000000 0.0181738194 0.0106990142 0.0181738194 0.0094148529 0.5430540000 0.1342930000 0.0477860000 0.0337210000 0.3236120000 0.0020050000 115740339 0 402718720 4.0371332169 4.0155882835 3.7386598587 916 36.6000000000 0.0181122515 0.0107071073 0.0181738194 0.0094099892 0.5000310000 0.1080200000 0.0604080000 0.0000010000 0.3281410000 0.0019010000 115743115 0 402718720 4.0347285271 4.0153894424 3.7387938499 917 36.6400000000 0.0181339737 0.0107152064 0.0181738194 0.0094048622 0.8889810000 0.1084410000 0.0832850000 0.0338000000 0.3273740000 0.3344790000 115745891 0 402718720 4.0322976112 4.0147275925 3.7387406826 918 36.6800000000 0.0181411970 0.0107232957 0.0181738194 0.0094000161 0.4988060000 0.1087980000 0.0552040000 0.0000000000 0.3313440000 0.0019020000 115748667 0 402718720 4.0300402641 4.0146856308 3.7390685081 919 36.7200000000 0.0181456003 0.0107313722 0.0181738194 0.0093949569 0.5338740000 0.1090540000 0.0574110000 0.0337630000 0.3301650000 0.0019040000 115751443 0 402718720 4.0280032158 4.0150017738 3.7386524677 920 36.7600000000 0.0181729030 0.0107394608 0.0181738194 0.0093901751 0.5262890000 0.1221060000 0.0669370000 0.0000010000 0.3337790000 0.0019000000 115754219 0 402718720 4.0259571075 4.0148029327 3.7390148640 921 36.8000000000 0.0181814022 0.0107475411 0.0181814022 0.0093851025 0.8844200000 0.1225120000 0.0572590000 0.0338660000 0.3311480000 0.3380850000 115756995 0 402718720 4.0241446495 4.0150098801 3.7391011715 922 36.8400000000 0.0182225071 0.0107556484 0.0182225071 0.0093805065 0.5265490000 0.1227950000 0.0678950000 0.0000000000 0.3322110000 0.0020020000 115759771 0 402718720 4.0225052834 4.0155467987 3.7398593426 923 36.8800000000 0.0182569083 0.0107637755 0.0182569083 0.0093766299 0.6063710000 0.1228080000 0.1141310000 0.0338720000 0.3320990000 0.0018980000 115762547 0 402718720 4.0209355354 4.0157136917 3.7398903370 924 36.9200000000 0.0182842016 0.0107719144 0.0182842016 0.0093738617 0.5233230000 0.1286060000 0.0578630000 0.0000010000 0.3332120000 0.0020010000 115765323 0 402718720 4.0195016861 4.0155177116 3.7391052246 925 36.9600000000 0.0183104537 0.0107800642 0.0183104537 0.0093696211 0.8941110000 0.1102440000 0.0755060000 0.0340910000 0.3329670000 0.3397420000 115768099 0 402718720 4.0179600716 4.0153102875 3.7395246029 926 37.0000000000 0.0182846114 0.0107881685 0.0183104537 0.0093646142 0.5164970000 0.1101890000 0.0671970000 0.0000010000 0.3356540000 0.0018980000 115770875 0 402718720 4.0166873932 4.0155901909 3.7389533520 927 37.0400000000 0.0182807557 0.0107962511 0.0183104537 0.0093601341 0.5369150000 0.1102990000 0.0550550000 0.0342350000 0.3338490000 0.0019010000 115773651 0 402718720 4.0155625343 4.0157175064 3.7391002178 928 37.0800000000 0.0183426831 0.0108043830 0.0183426831 0.0093568557 0.5084430000 0.1103030000 0.0575080000 0.0000010000 0.3371510000 0.0018990000 115776427 0 402718720 4.0145502090 4.0165615082 3.7395246029 929 37.1200000000 0.0183092616 0.0108124615 0.0183426831 0.0093560481 0.8698320000 0.1101760000 0.0478050000 0.0341350000 0.3346250000 0.3415350000 115779203 0 402718720 4.0135293007 4.0167188644 3.7399542332 930 37.1600000000 0.0183515958 0.0108205681 0.0183515958 0.0093550680 0.5159410000 0.1101340000 0.0646520000 0.0000010000 0.3376580000 0.0019010000 115781979 0 402718720 4.0127086639 4.0169825554 3.7400701046 931 37.2000000000 0.0183490980 0.0108286546 0.0183515958 0.0093532969 0.5365910000 0.1101080000 0.0549940000 0.0336500000 0.3343520000 0.0019060000 115784755 0 402718720 4.0119256973 4.0173053741 3.7403814793 932 37.2400000000 0.0183691643 0.0108367452 0.0183691643 0.0093503139 0.4978920000 0.1100090000 0.0505110000 0.0000000000 0.3338810000 0.0019030000 115787531 0 402718720 4.0112895966 4.0175132751 3.7404174805 933 37.2800000000 0.0183434952 0.0108447911 0.0183691643 0.0093472580 0.8659020000 0.1098800000 0.0455790000 0.0337010000 0.3341520000 0.3409980000 115790307 0 402718720 4.0105934143 4.0179181099 3.7408347130 934 37.3200000000 0.0183772035 0.0108528557 0.0183772035 0.0093448122 0.5024530000 0.1062110000 0.0598410000 0.0000010000 0.3328100000 0.0019370000 115793083 0 402718720 4.0100641251 4.0186648369 3.7411973476 935 37.3600000000 0.0182881914 0.0108608080 0.0183772035 0.0093444412 0.5351410000 0.1097600000 0.0577640000 0.0342790000 0.3296370000 0.0020080000 115795859 0 402718720 4.0096840858 4.0189533234 3.7412314415 936 37.4000000000 0.0183517169 0.0108688111 0.0183772035 0.0093426656 0.5707030000 0.1090140000 0.1024710000 0.0000000000 0.3547420000 0.0026550000 115798635 0 402718720 4.0092573166 4.0191607475 3.7412333488 937 37.4400000000 0.0183676276 0.0108768141 0.0183772035 0.0093391985 0.9622630000 0.1410730000 0.0774760000 0.0431690000 0.3533960000 0.3455740000 115801411 0 402718720 4.0089945793 4.0191626549 3.7412390709 938 37.4800000000 0.0184074752 0.0108848425 0.0184074752 0.0093358406 0.5582460000 0.1096120000 0.1124320000 0.0000010000 0.3326970000 0.0019020000 115804187 0 402718720 4.0087032318 4.0191884041 3.7411735058 939 37.5200000000 0.0183589160 0.0108928021 0.0184074752 0.0093315372 0.5265730000 0.1096430000 0.0480920000 0.0341290000 0.3312040000 0.0019080000 115806963 0 402718720 4.0087041855 4.0193605423 3.7409288883 940 37.5600000000 0.0183244608 0.0109007081 0.0184074752 0.0093273515 0.4995820000 0.1095840000 0.0552750000 0.0000000000 0.3312150000 0.0019030000 115809739 0 402718720 4.0087022781 4.0196247101 3.7409281731 941 37.6000000000 0.0183623154 0.0109086376 0.0184074752 0.0093236676 0.8816150000 0.1222840000 0.0576990000 0.0341110000 0.3296040000 0.3363310000 115812515 0 402718720 4.0086436272 4.0201931000 3.7409684658 942 37.6400000000 0.0183553081 0.0109165428 0.0184074752 0.0093204292 0.5450480000 0.1239790000 0.0880480000 0.0000010000 0.3295220000 0.0018980000 115815291 0 402718720 4.0088095665 4.0206589699 3.7408492565 943 37.6800000000 0.0182858650 0.0109243575 0.0184074752 0.0093189066 0.5574500000 0.1342840000 0.0605440000 0.0341570000 0.3247750000 0.0020010000 115818067 0 402718720 4.0088963509 4.0208106041 3.7406821251 944 37.7200000000 0.0182884820 0.0109321585 0.0184074752 0.0093166004 0.5054810000 0.1095980000 0.0633500000 0.0000010000 0.3290370000 0.0018970000 115820843 0 402718720 4.0090146065 4.0213060379 3.7405385971 945 37.7600000000 0.0182794221 0.0109399334 0.0184074752 0.0093142041 0.9365880000 0.1096990000 0.1005990000 0.0341560000 0.3343450000 0.3559710000 115823619 0 402718720 4.0091443062 4.0215916634 3.7403564453 946 37.8000000000 0.0182877295 0.0109477006 0.0184074752 0.0093117658 0.5571530000 0.1411030000 0.0618150000 0.0000010000 0.3497470000 0.0026550000 115826395 0 402718720 4.0091490746 4.0217514038 3.7401342392 947 37.8400000000 0.0183610227 0.0109555288 0.0184074752 0.0093083025 0.6231640000 0.1410330000 0.0871260000 0.0430410000 0.3474580000 0.0026580000 115829171 0 402718720 4.0092954636 4.0221152306 3.7401278019 948 37.8800000000 0.0182792768 0.0109632543 0.0184074752 0.0093056248 0.5644710000 0.1409780000 0.0933840000 0.0000010000 0.3266000000 0.0018980000 115831947 0 402718720 4.0094003677 4.0222330093 3.7400319576 949 37.9200000000 0.0182836093 0.0109709681 0.0184074752 0.0093026488 0.8459870000 0.1097670000 0.0456540000 0.0334710000 0.3244100000 0.3310800000 115834723 0 402718720 4.0096096992 4.0225276947 3.7398087978 950 37.9600000000 0.0182989966 0.0109786818 0.0184074752 0.0092987917 0.5101830000 0.1097910000 0.0719710000 0.0000010000 0.3248970000 0.0019000000 115837499 0 402718720 4.0098543167 4.0229554176 3.7396678925 951 38.0000000000 0.0182794146 0.0109863587 0.0184074752 0.0092945502 0.5184770000 0.1097210000 0.0482380000 0.0334720000 0.3235090000 0.0019050000 115840275 0 402718720 4.0100598335 4.0232052803 3.7394809723 952 38.0400000000 0.0182735100 0.0109940132 0.0184074752 0.0092921426 0.5072780000 0.1139300000 0.0681280000 0.0000010000 0.3215280000 0.0019970000 115843051 0 402718720 4.0102119446 4.0234365463 3.7395629883 953 38.0800000000 0.0182800740 0.0110016586 0.0184074752 0.0092880599 0.8460920000 0.1098400000 0.0506670000 0.0335400000 0.3207120000 0.3297160000 115845827 0 402718720 4.0105557442 4.0237064362 3.7392866611 954 38.1200000000 0.0183184296 0.0110093282 0.0184074752 0.0092832677 0.4860740000 0.1064900000 0.0523990000 0.0000000000 0.3236410000 0.0018990000 115848603 0 402718720 4.0108451843 4.0240941048 3.7389779091 955 38.1600000000 0.0182843897 0.0110169461 0.0184074752 0.0092788265 0.5323630000 0.1064910000 0.0668200000 0.0337200000 0.3217830000 0.0019050000 115851379 0 402718720 4.0109758377 4.0240788460 3.7392284870 956 38.2000000000 0.0183535498 0.0110246203 0.0184074752 0.0092739854 0.4813030000 0.1065620000 0.0478900000 0.0000000000 0.3233750000 0.0018380000 115854155 0 402718720 4.0113162994 4.0245208740 3.7386944294 957 38.2400000000 0.0183637086 0.0110322892 0.0184074752 0.0092692561 0.8391490000 0.1065160000 0.0481290000 0.0339650000 0.3210650000 0.3278440000 115856931 0 402718720 4.0114417076 4.0243902206 3.7384405136 958 38.2800000000 0.0183389783 0.0110399162 0.0184074752 0.0092645725 0.4902530000 0.1097960000 0.0555560000 0.0000000000 0.3213440000 0.0018990000 115859707 0 402718720 4.0115804672 4.0246014595 3.7385153770 959 38.3200000000 0.0183612294 0.0110475505 0.0184074752 0.0092599022 0.5256880000 0.1098200000 0.0580580000 0.0339170000 0.3203610000 0.0019010000 115862483 0 402718720 4.0118765831 4.0246176720 3.7381563187 960 38.3600000000 0.0183870476 0.0110551959 0.0184074752 0.0092553832 0.5178110000 0.1097620000 0.0843070000 0.0000010000 0.3202120000 0.0019000000 115865259 0 402718720 4.0120449066 4.0247845650 3.7382285595 961 38.4000000000 0.0183788892 0.0110628168 0.0184074752 0.0092509003 0.8477040000 0.1097620000 0.0555840000 0.0339140000 0.3199880000 0.3268290000 115868035 0 402718720 4.0123534203 4.0248999596 3.7378814220 962 38.4400000000 0.0183934625 0.0110704370 0.0184074752 0.0092462898 0.5034250000 0.1334030000 0.0482620000 0.0000010000 0.3180380000 0.0019970000 115870811 0 402718720 4.0126137733 4.0250139236 3.7376742363 963 38.4800000000 0.0184041020 0.0110780524 0.0184074752 0.0092415900 0.5225620000 0.1065250000 0.0600300000 0.0330580000 0.3194050000 0.0019020000 115873587 0 402718720 4.0128874779 4.0248861313 3.7375738621 964 38.5200000000 0.0184163656 0.0110856648 0.0184163656 0.0092368720 0.4910150000 0.1096820000 0.0579750000 0.0000010000 0.3198030000 0.0019000000 115876363 0 402718720 4.0132188797 4.0251045227 3.7373907566 965 38.5600000000 0.0184221845 0.0110932674 0.0184221845 0.0092321460 0.8369860000 0.1096210000 0.0482300000 0.0338490000 0.3183800000 0.3252710000 115879139 0 402718720 4.0135145187 4.0251889229 3.7373771667 966 38.6000000000 0.0184141658 0.0111008459 0.0184221845 0.0092275583 0.4773520000 0.1096040000 0.0457830000 0.0000010000 0.3184150000 0.0019040000 115881915 0 402718720 4.0137820244 4.0251598358 3.7372002602 967 38.6400000000 0.0183733255 0.0111083666 0.0184221845 0.0092228102 0.5093830000 0.1063650000 0.0478160000 0.0334620000 0.3182670000 0.0018410000 115884691 0 402718720 4.0140600204 4.0251574516 3.7372119427 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 11:02:35 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 -nan 1.0411020000 0.1798490000 0.0281160000 0.0773870000 0.0000020000 0.7556700000 106006334 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378911 0.2863740000 0.1790780000 0.0260190000 0.0767090000 0.0000010000 0.0045400000 112894947 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728699 0.2863230000 0.1790970000 0.0260230000 0.0766250000 0.0000000000 0.0045470000 112898115 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723129 1.0183670000 0.1788050000 0.0260400000 0.0767110000 0.7322300000 0.0045510000 112901291 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276572 0.0024566334 0.0055015511 0.0048987944 1.8792860000 0.1788290000 0.1461630000 0.0774370000 0.7291040000 0.7477190000 112904451 0 402718720 3.9957129955 4.0020360947 4.0009112358 6 0.2000000000 0.0021158110 0.0023998297 0.0055015511 0.0043899454 0.6313120000 0.1032100000 0.0480570000 0.0000010000 0.4780890000 0.0019220000 112908027 0 402718720 3.9965538979 4.0017571449 4.0000624657 7 0.2400000000 0.0020491821 0.0023497372 0.0055015511 0.0040164420 0.6667050000 0.1033470000 0.0481330000 0.0357020000 0.4775670000 0.0019200000 112910803 0 402718720 3.9963860512 4.0014791489 4.0003576279 8 0.2800000000 0.0021295445 0.0023222131 0.0055015511 0.0037227656 0.6312550000 0.1031870000 0.0481590000 0.0000010000 0.4779580000 0.0019140000 112913579 0 402718720 3.9949586391 4.0019369125 4.0002703667 9 0.3200000000 0.0021676212 0.0023050362 0.0055015511 0.0035287190 1.1461410000 0.1032690000 0.0456890000 0.0358000000 0.4776640000 0.4836770000 112917123 0 402718720 3.9930224419 4.0012898445 4.0003123283 10 0.3600000000 0.0022070820 0.0022952408 0.0055015511 0.0033889795 0.6284320000 0.1031390000 0.0457330000 0.0000010000 0.4776030000 0.0019160000 112921499 0 402718720 3.9929070473 4.0026335716 4.0009012222 11 0.4000000000 0.0022589520 0.0022919418 0.0055015511 0.0033576189 0.6730610000 0.1031250000 0.0552570000 0.0351730000 0.4775430000 0.0019220000 112924275 0 402718720 3.9919445515 4.0017886162 4.0016002655 12 0.4400000000 0.0022642231 0.0022896319 0.0055015511 0.0034313183 0.6297250000 0.1032150000 0.0458220000 0.0000010000 0.4787310000 0.0019140000 112927051 0 402718720 3.9918570518 4.0017395020 4.0008211136 13 0.4800000000 0.0022805610 0.0022889341 0.0055015511 0.0034363100 1.1470360000 0.1033770000 0.0456640000 0.0356130000 0.4780720000 0.4842650000 112929827 0 402718720 3.9894258976 4.0015444756 4.0013942719 14 0.5200000000 0.0023237555 0.0022914214 0.0055015511 0.0033244394 0.6971760000 0.1034390000 0.1124860000 0.0000010000 0.4792860000 0.0019170000 112932603 0 402718720 3.9894292355 4.0028066635 4.0008144379 15 0.5600000000 0.0023150046 0.0022929936 0.0055015511 0.0032122929 0.6712380000 0.1035070000 0.0527940000 0.0352090000 0.4777580000 0.0019220000 112935379 0 402718720 3.9863409996 4.0038948059 4.0015859604 16 0.6000000000 0.0023959943 0.0022994311 0.0055015511 0.0031281558 0.6513070000 0.1035340000 0.0671830000 0.0000000000 0.4786250000 0.0019160000 112938155 0 402718720 3.9871168137 4.0023279190 4.0005326271 17 0.6400000000 0.0024173490 0.0023063675 0.0055015511 0.0030498713 1.1553060000 0.1036080000 0.0526880000 0.0352290000 0.4789880000 0.4847390000 112942467 0 402718720 3.9851160049 4.0009012222 3.9991016388 18 0.6800000000 0.0024465756 0.0023141568 0.0055015511 0.0029600766 0.6406350000 0.1038620000 0.0550970000 0.0000010000 0.4796920000 0.0019300000 112948443 0 402718720 3.9835419655 4.0011630058 4.0000805855 19 0.7200000000 0.0024327487 0.0023203985 0.0055015511 0.0029192979 0.6731630000 0.1041490000 0.0527460000 0.0357100000 0.4785780000 0.0019260000 112951219 0 402718720 3.9820523262 4.0014057159 3.9996454716 20 0.7600000000 0.0025416065 0.0023314589 0.0055015511 0.0029368847 0.6317140000 0.1043590000 0.0454830000 0.0000000000 0.4798920000 0.0019250000 112953995 0 402718720 3.9790832996 4.0002136230 3.9993202686 21 0.8000000000 0.0025815826 0.0023433696 0.0055015511 0.0028725862 1.1607490000 0.1048850000 0.0552120000 0.0357180000 0.4791530000 0.4857240000 112956771 0 402718720 3.9761934280 4.0010938644 3.9996607304 22 0.8400000000 0.0028564115 0.0023666896 0.0055015511 0.0028130267 0.6357510000 0.1051880000 0.0482140000 0.0000010000 0.4803710000 0.0019200000 112959547 0 402718720 3.9707217216 4.0004553795 3.9992079735 23 0.8800000000 0.0028553416 0.0023879354 0.0055015511 0.0027483850 0.6804650000 0.1054570000 0.0576140000 0.0357150000 0.4796930000 0.0019230000 112962323 0 402718720 3.9713084698 3.9995710850 3.9975645542 24 0.9200000000 0.0028111078 0.0024055676 0.0055015511 0.0026883341 0.6357980000 0.1062100000 0.0457630000 0.0000000000 0.4818460000 0.0019180000 112965099 0 402718720 3.9629049301 4.0010108948 3.9969229698 25 0.9600000000 0.0027974381 0.0024212424 0.0055015511 0.0026601564 1.1560700000 0.1064510000 0.0458190000 0.0357670000 0.4808340000 0.4871340000 112967875 0 402718720 3.9617187977 4.0022764206 3.9961574078 26 1.0000000000 0.0028473693 0.0024376319 0.0055015511 0.0026078818 0.6459430000 0.1068590000 0.0552430000 0.0000010000 0.4818530000 0.0019220000 112970651 0 402718720 3.9554531574 4.0008072853 3.9970502853 27 1.0400000000 0.0026990655 0.0024473146 0.0055015511 0.0026330426 0.6795150000 0.1074360000 0.0527470000 0.0357250000 0.4816180000 0.0019220000 112973427 0 402718720 3.9496529102 4.0000429153 3.9948580265 28 1.0800000000 0.0027756963 0.0024590425 0.0055015511 0.0027070679 0.6479510000 0.1079880000 0.0553350000 0.0000000000 0.4826400000 0.0019170000 112976203 0 402718720 3.9448723793 4.0019140244 3.9945604801 29 1.1200000000 0.0027233341 0.0024681560 0.0055015511 0.0027849814 1.1765570000 0.1083370000 0.0621890000 0.0359140000 0.4819110000 0.4881390000 112978979 0 402718720 3.9388144016 4.0020332336 3.9917833805 30 1.1600000000 0.0029728520 0.0024849792 0.0055015511 0.0027877239 0.6520210000 0.1089390000 0.0577570000 0.0000010000 0.4833390000 0.0019150000 112981755 0 402718720 3.9293606281 4.0014405251 3.9938361645 31 1.2000000000 0.0028916113 0.0024980964 0.0055015511 0.0027640601 0.6946720000 0.1091660000 0.0647880000 0.0358750000 0.4828540000 0.0019170000 112984531 0 402718720 3.9227759838 4.0022110939 3.9920411110 32 1.2400000000 0.0029374377 0.0025118258 0.0055015511 0.0027640904 0.6518690000 0.1095400000 0.0553040000 0.0000010000 0.4850320000 0.0019170000 112987307 0 402718720 3.9160683155 4.0025386810 3.9897449017 33 1.2800000000 0.0029340412 0.0025246202 0.0055015511 0.0028064276 1.1741680000 0.1096560000 0.0552390000 0.0354230000 0.4835950000 0.4901780000 112993155 0 402718720 3.9104619026 4.0022311211 3.9895088673 34 1.3200000000 0.0028943860 0.0025354957 0.0055015511 0.0027796966 0.6505540000 0.1070130000 0.0547820000 0.0000000000 0.4867580000 0.0019210000 113002331 0 402718720 3.8820009232 4.0016932487 3.9892089367 35 1.3600000000 0.0030738816 0.0025508781 0.0055015511 0.0030460748 0.6861000000 0.1102220000 0.0529890000 0.0355280000 0.4853630000 0.0019190000 113005107 0 402718720 3.8787074089 4.0025601387 3.9865632057 36 1.4000000000 0.0030332492 0.0025642773 0.0055015511 0.0035563692 0.6539720000 0.1101130000 0.0549610000 0.0000000000 0.4869000000 0.0019190000 113007883 0 402718720 3.8730516434 4.0033059120 3.9847655296 37 1.4400000000 0.0030154623 0.0025764715 0.0055015511 0.0035939158 1.1853040000 0.1104860000 0.0625670000 0.0355060000 0.4852150000 0.4914470000 113010659 0 402718720 3.8621103764 4.0013189316 3.9860274792 38 1.4800000000 0.0031999133 0.0025928779 0.0055015511 0.0035536543 0.6564350000 0.1105030000 0.0577490000 0.0000010000 0.4861830000 0.0019160000 113013435 0 402718720 3.8505403996 4.0007653236 3.9867565632 39 1.5200000000 0.0032571063 0.0026099094 0.0055015511 0.0035109164 0.6803830000 0.1106520000 0.0456900000 0.0360440000 0.4859960000 0.0019180000 113016211 0 402718720 3.8474044800 4.0001387596 3.9834108353 40 1.5600000000 0.0033193335 0.0026276450 0.0055015511 0.0034941483 0.6464810000 0.1106500000 0.0458400000 0.0000010000 0.4879830000 0.0019190000 113018987 0 402718720 3.8375031948 3.9985284805 3.9840960503 41 1.6000000000 0.0033398385 0.0026450156 0.0055015511 0.0035146411 1.1858840000 0.1108300000 0.0576040000 0.0355710000 0.4876990000 0.4940900000 113021763 0 402718720 3.8271040916 3.9974167347 3.9858503342 42 1.6400000000 0.0033447403 0.0026616757 0.0055015511 0.0034758332 0.6482760000 0.1109490000 0.0457750000 0.0000010000 0.4895460000 0.0019160000 113024539 0 402718720 3.8137383461 3.9989140034 3.9880638123 43 1.6800000000 0.0033269953 0.0026771482 0.0055015511 0.0034550474 0.6796340000 0.1108910000 0.0434790000 0.0360880000 0.4871490000 0.0019360000 113027315 0 402718720 3.8069221973 3.9993491173 3.9914362431 44 1.7200000000 0.0033242137 0.0026918542 0.0055015511 0.0034860307 0.6500190000 0.1108970000 0.0482900000 0.0000000000 0.4888240000 0.0019140000 113030091 0 402718720 3.8006069660 3.9986829758 3.9893226624 45 1.7600000000 0.0033446511 0.0027063608 0.0055015511 0.0035048258 1.1858460000 0.1109830000 0.0580170000 0.0361510000 0.4869070000 0.4936930000 113032867 0 402718720 3.7922325134 4.0006752014 3.9930369854 46 1.8000000000 0.0034072120 0.0027215967 0.0055015511 0.0035113607 0.6576790000 0.1109980000 0.0578080000 0.0000010000 0.4868620000 0.0019140000 113035643 0 402718720 3.7862718105 4.0012893677 3.9931349754 47 1.8400000000 0.0034262044 0.0027365884 0.0055015511 0.0036170453 0.6817670000 0.1110430000 0.0460080000 0.0361470000 0.4865530000 0.0019180000 113038419 0 402718720 3.7832627296 3.9994776249 3.9928348064 48 1.8800000000 0.0033775966 0.0027499427 0.0055015511 0.0036604500 0.6555060000 0.1109960000 0.0556750000 0.0000000000 0.4868190000 0.0019170000 113041195 0 402718720 3.7786984444 3.9991877079 3.9939415455 49 1.9200000000 0.0035794962 0.0027668724 0.0055015511 0.0036222464 1.1847470000 0.1109420000 0.0579960000 0.0361300000 0.4866350000 0.4929450000 113043971 0 402718720 3.7715675831 4.0004119873 3.9947507381 50 1.9600000000 0.0035755283 0.0027830455 0.0055015511 0.0036078949 0.6551270000 0.1110790000 0.0554030000 0.0000010000 0.4866280000 0.0019180000 113046747 0 402718720 3.7572419643 4.0000791550 3.9996900558 51 2.0000000000 0.0035176135 0.0027974488 0.0055015511 0.0035821646 0.6911050000 0.1110000000 0.0554650000 0.0361580000 0.4864530000 0.0019280000 113049523 0 402718720 3.7588238716 3.9999406338 3.9966928959 52 2.0400000000 0.0035654043 0.0028122172 0.0055015511 0.0035470286 0.6581780000 0.1110090000 0.0578030000 0.0000000000 0.4873360000 0.0019270000 113052299 0 402718720 3.7548794746 4.0003600121 3.9959797859 53 2.0800000000 0.0034978678 0.0028251540 0.0055015511 0.0035915721 1.1939460000 0.1109590000 0.0649720000 0.0362360000 0.4874940000 0.4941780000 113055075 0 402718720 3.7528634071 3.9979717731 3.9927268028 54 2.1200000000 0.0036589163 0.0028405940 0.0055015511 0.0036669780 0.6464190000 0.1109890000 0.0461440000 0.0000010000 0.4872600000 0.0019200000 113057851 0 402718720 3.7398264408 3.9965586662 3.9985253811 55 2.1600000000 0.0035312437 0.0028531513 0.0055015511 0.0037613964 0.6914040000 0.1110400000 0.0558680000 0.0356630000 0.4867990000 0.0019240000 113060627 0 402718720 3.7374930382 3.9971899986 3.9982156754 56 2.2000000000 0.0036821461 0.0028679548 0.0055015511 0.0037687801 0.6555700000 0.1110270000 0.0555940000 0.0000010000 0.4869230000 0.0019140000 113063403 0 402718720 3.7176368237 3.9976871014 4.0073909760 57 2.2400000000 0.0038216624 0.0028846865 0.0055015511 0.0037477414 1.1810670000 0.1109610000 0.0555860000 0.0361280000 0.4857460000 0.4925350000 113066179 0 402718720 3.7128341198 3.9951198101 4.0079884529 58 2.2800000000 0.0036931641 0.0028986258 0.0055015511 0.0037567965 0.6547090000 0.1110700000 0.0554780000 0.0000010000 0.4861280000 0.0019200000 113068955 0 402718720 3.7034840584 3.9942684174 4.0107660294 59 2.3200000000 0.0038717564 0.0029151195 0.0055015511 0.0038957554 0.6782830000 0.1110850000 0.0436300000 0.0360750000 0.4854580000 0.0019180000 113071731 0 402718720 3.6893465519 3.9967937469 4.0165214539 60 2.3600000000 0.0038588569 0.0029308484 0.0055015511 0.0040109096 0.6479350000 0.1110630000 0.0484970000 0.0000010000 0.4863390000 0.0019190000 113074507 0 402718720 3.6862201691 3.9950735569 4.0145802498 61 2.4000000000 0.0038687293 0.0029462235 0.0055015511 0.0041277474 1.1803480000 0.1110500000 0.0531270000 0.0361610000 0.4867080000 0.4931850000 113077283 0 402718720 3.6794517040 3.9935901165 4.0143709183 62 2.4400000000 0.0038832752 0.0029613373 0.0055015511 0.0042927859 0.6541220000 0.1111850000 0.0529740000 0.0000010000 0.4879270000 0.0019180000 113080059 0 402718720 3.6557703018 3.9940490723 4.0246829987 63 2.4800000000 0.0039049089 0.0029763146 0.0055015511 0.0044367852 0.6944570000 0.1112670000 0.0575980000 0.0362690000 0.4872830000 0.0019190000 113082835 0 402718720 3.6470935345 3.9929676056 4.0258560181 64 2.5200000000 0.0039105196 0.0029909116 0.0055015511 0.0047970457 0.6577770000 0.1113640000 0.0554310000 0.0000010000 0.4889400000 0.0019220000 113085611 0 402718720 3.6345653534 3.9940972328 4.0304169655 65 2.5600000000 0.0039082868 0.0030050250 0.0055015511 0.0051042005 1.1863510000 0.1114220000 0.0552810000 0.0363310000 0.4880880000 0.4951040000 113094531 0 402718720 3.6207096577 3.9939799309 4.0341434479 66 2.6000000000 0.0040705511 0.0030211694 0.0055015511 0.0051950389 0.6492940000 0.1114660000 0.0458230000 0.0000010000 0.4899510000 0.0019290000 113110107 0 402718720 3.6102125645 3.9952816963 4.0361304283 67 2.6400000000 0.0041003362 0.0030372763 0.0055015511 0.0052461908 0.6967790000 0.1115670000 0.0576000000 0.0364260000 0.4891420000 0.0019190000 113112883 0 402718720 3.6000034809 3.9977250099 4.0384030342 68 2.6800000000 0.0043068561 0.0030559466 0.0055015511 0.0052293526 0.6618720000 0.1115660000 0.0576910000 0.0000000000 0.4905650000 0.0019190000 113115659 0 402718720 3.5890212059 3.9976363182 4.0377335548 69 2.7200000000 0.0043245251 0.0030743318 0.0055015511 0.0051926977 1.1903550000 0.1116020000 0.0552190000 0.0365440000 0.4897010000 0.4971590000 113118435 0 402718720 3.5794928074 3.9978675842 4.0422286987 70 2.7600000000 0.0044265669 0.0030936495 0.0055015511 0.0051650836 0.6602390000 0.1117200000 0.0551490000 0.0000000000 0.4913310000 0.0019070000 113121211 0 402718720 3.5706286430 3.9997210503 4.0418820381 71 2.8000000000 0.0044237166 0.0031123828 0.0055015511 0.0052162231 0.6855530000 0.1117240000 0.0455450000 0.0361660000 0.4900850000 0.0019020000 113123987 0 402718720 3.5634367466 4.0003190041 4.0388026237 72 2.8400000000 0.0047287233 0.0031348320 0.0055015511 0.0058996802 0.6598680000 0.1117830000 0.0552350000 0.0000000000 0.4908320000 0.0018840000 113126763 0 402718720 3.5476489067 4.0055427551 4.0417666435 73 2.8800000000 0.0047875396 0.0031574718 0.0055015511 0.0059716349 1.1925730000 0.1118420000 0.0540370000 0.0364510000 0.4909160000 0.4992070000 113129539 0 402718720 3.5377211571 4.0069351196 4.0434441566 74 2.9200000000 0.0048681931 0.0031805897 0.0055015511 0.0060621519 0.6520970000 0.1119220000 0.0472480000 0.0000000000 0.4909290000 0.0018700000 113132315 0 402718720 3.5356779099 4.0086226463 4.0402946472 75 2.9600000000 0.0050430400 0.0032054223 0.0055015511 0.0061161711 0.6973820000 0.1119110000 0.0564070000 0.0363230000 0.4907410000 0.0018680000 113135091 0 402718720 3.5345196724 4.0122642517 4.0375232697 76 3.0000000000 0.0050761686 0.0032300374 0.0055015511 0.0061503207 0.6605350000 0.1118150000 0.0536490000 0.0000000000 0.4930770000 0.0018600000 113137867 0 402718720 3.5365369320 4.0153903961 4.0294227600 77 3.0400000000 0.0048925867 0.0032516290 0.0055015511 0.0061735152 1.1894890000 0.1117950000 0.0441090000 0.0369950000 0.4929040000 0.5035530000 113140643 0 402718720 3.5357232094 4.0158743858 4.0226492882 78 3.0800000000 0.0045041814 0.0032676873 0.0055015511 0.0061426521 0.6616720000 0.1116700000 0.0531630000 0.0000010000 0.4948550000 0.0018490000 113143419 0 402718720 3.5368628502 4.0172085762 4.0154633522 79 3.1200000000 0.0043800999 0.0032817685 0.0055015511 0.0061045610 0.6917120000 0.1116540000 0.0461600000 0.0372060000 0.4947190000 0.0018380000 113146195 0 402718720 3.5297706127 4.0203032494 4.0133008957 80 3.1600000000 0.0041133096 0.0032921628 0.0055015511 0.0060691054 0.6655050000 0.1115530000 0.0549690000 0.0000010000 0.4970130000 0.0018320000 113148971 0 402718720 3.5258674622 4.0231761932 4.0096025467 81 3.2000000000 0.0041706827 0.0033030087 0.0055015511 0.0060411054 1.2591400000 0.1113400000 0.1060940000 0.0372830000 0.4951190000 0.5091620000 113151747 0 402718720 3.5140287876 4.0221824646 4.0126132965 82 3.2400000000 0.0044026673 0.0033164192 0.0055015511 0.0060492390 0.6710740000 0.1115400000 0.0613890000 0.0000000000 0.4961810000 0.0018180000 113154523 0 402718720 3.5058374405 4.0223245621 4.0121927261 83 3.2800000000 0.0043057119 0.0033283384 0.0055015511 0.0060867765 0.6919150000 0.1115400000 0.0454290000 0.0375470000 0.4954360000 0.0018210000 113157299 0 402718720 3.4979181290 4.0244026184 4.0090556145 84 3.3200000000 0.0042919992 0.0033398105 0.0055015511 0.0060776519 0.6642820000 0.1115530000 0.0541110000 0.0000000000 0.4966490000 0.0018240000 113160075 0 402718720 3.4851744175 4.0234193802 4.0093326569 85 3.3600000000 0.0045051114 0.0033535199 0.0055015511 0.0060684727 1.2179900000 0.1115830000 0.0602080000 0.0378290000 0.4952850000 0.5129420000 113162851 0 402718720 3.4719922543 4.0243110657 4.0097422600 86 3.4000000000 0.0045108497 0.0033669772 0.0055015511 0.0061073659 0.6636250000 0.1116300000 0.0535480000 0.0000010000 0.4965180000 0.0017810000 113165627 0 402718720 3.4569864273 4.0252108574 4.0138020515 87 3.4400000000 0.0041972422 0.0033765205 0.0055015511 0.0062320523 0.7091710000 0.1116320000 0.0620240000 0.0380080000 0.4955760000 0.0017840000 113168403 0 402718720 3.4468989372 4.0239324570 4.0134744644 88 3.4800000000 0.0038751555 0.0033821868 0.0055015511 0.0063827547 0.6548550000 0.1116730000 0.0444760000 0.0000000000 0.4967870000 0.0017720000 113171179 0 402718720 3.4334411621 4.0241980553 4.0137104988 89 3.5200000000 0.0040128706 0.0033892732 0.0055015511 0.0065287169 1.2203510000 0.1116910000 0.0594210000 0.0381920000 0.4953360000 0.5155620000 113173955 0 402718720 3.4244003296 4.0244135857 4.0138196945 90 3.5600000000 0.0044016717 0.0034005220 0.0055015511 0.0066376287 0.6587370000 0.1117280000 0.0485230000 0.0000010000 0.4965690000 0.0017640000 113176731 0 402718720 3.4174859524 4.0226664543 4.0125904083 91 3.6000000000 0.0041540968 0.0034088031 0.0055015511 0.0066781526 0.6970690000 0.1117940000 0.0503420000 0.0383390000 0.4946760000 0.0017650000 113179507 0 402718720 3.4026191235 4.0213499069 4.0156250000 92 3.6400000000 0.0042262473 0.0034176883 0.0055015511 0.0066900917 0.6624980000 0.1118710000 0.0526160000 0.0000000000 0.4961030000 0.0017560000 113182283 0 402718720 3.3875238895 4.0234808922 4.0208220482 93 3.6800000000 0.0041639213 0.0034257124 0.0055015511 0.0066694956 1.2128590000 0.1118800000 0.0501850000 0.0384800000 0.4947750000 0.5173840000 113185059 0 402718720 3.3825466633 4.0226335526 4.0174212456 94 3.7200000000 0.0040704617 0.0034325714 0.0055015511 0.0066416117 0.6686800000 0.1118720000 0.0588680000 0.0000000000 0.4960350000 0.0017490000 113187835 0 402718720 3.3752634525 4.0201725960 4.0169787407 95 3.7600000000 0.0041920142 0.0034405655 0.0055015511 0.0066270801 0.6993200000 0.1119560000 0.0522990000 0.0385770000 0.4945780000 0.0017490000 113190611 0 402718720 3.3623652458 4.0215301514 4.0235357285 96 3.8000000000 0.0041401931 0.0034478533 0.0055015511 0.0065993539 0.6681690000 0.1119180000 0.0586250000 0.0000010000 0.4957170000 0.0017490000 113193387 0 402718720 3.3520407677 4.0210213661 4.0231161118 97 3.8400000000 0.0042939070 0.0034565755 0.0055015511 0.0065655837 1.2157170000 0.1119300000 0.0521110000 0.0387340000 0.4944680000 0.5183130000 113196163 0 402718720 3.3467414379 4.0183086395 4.0250144005 98 3.8800000000 0.0042408071 0.0034645779 0.0055015511 0.0065401926 0.6595280000 0.1120150000 0.0499170000 0.0000010000 0.4956920000 0.0017440000 113198939 0 402718720 3.3321299553 4.0176296234 4.0290880203 99 3.9200000000 0.0043201977 0.0034732205 0.0055015511 0.0065130113 0.6979400000 0.1120690000 0.0518270000 0.0383280000 0.4938000000 0.0017440000 113201715 0 402718720 3.3266952038 4.0190453529 4.0322289467 100 3.9600000000 0.0044207042 0.0034826953 0.0055015511 0.0064802521 0.6620990000 0.1162680000 0.0499760000 0.0000010000 0.4939450000 0.0017430000 113204491 0 402718720 3.3185455799 4.0186195374 4.0362682343 101 4.0000000000 0.0041632871 0.0034894339 0.0055015511 0.0064505820 1.2286660000 0.1120830000 0.0663570000 0.0389720000 0.4929750000 0.5181140000 113207267 0 402718720 3.3094794750 4.0169034004 4.0422878265 102 4.0400000000 0.0041436036 0.0034958473 0.0055015511 0.0064299335 0.6573550000 0.1121170000 0.0499020000 0.0000010000 0.4934250000 0.0017450000 113210043 0 402718720 3.3058986664 4.0154032707 4.0439085960 103 4.0800000000 0.0041677468 0.0035023706 0.0055015511 0.0063992531 0.6946590000 0.1120680000 0.0498020000 0.0388600000 0.4920070000 0.0017510000 113212819 0 402718720 3.2951962948 4.0149850845 4.0505404472 104 4.1200000000 0.0042502196 0.0035095615 0.0055015511 0.0063736923 0.6472700000 0.1120290000 0.0413580000 0.0000000000 0.4919690000 0.0017410000 113215595 0 402718720 3.2826046944 4.0132393837 4.0633497238 105 4.1600000000 0.0042673857 0.0035167788 0.0055015511 0.0063732995 1.2106190000 0.1121300000 0.0516580000 0.0389720000 0.4909250000 0.5167630000 113218371 0 402718720 3.2798771858 4.0129690170 4.0651121140 106 4.2000000000 0.0042478214 0.0035236755 0.0055015511 0.0063807320 0.6657900000 0.1120750000 0.0604070000 0.0000010000 0.4913880000 0.0017460000 113221147 0 402718720 3.2734208107 4.0136251450 4.0701680183 107 4.2400000000 0.0043475302 0.0035313750 0.0055015511 0.0063642761 0.6937890000 0.1120190000 0.0495530000 0.0389990000 0.4913010000 0.0017400000 113223923 0 402718720 3.2732248306 4.0103797913 4.0664858818 108 4.2800000000 0.0040788203 0.0035364440 0.0055015511 0.0063354932 0.6547910000 0.1120840000 0.0496560000 0.0000000000 0.4911370000 0.0017380000 113226699 0 402718720 3.2631099224 4.0093364716 4.0749421120 109 4.3200000000 0.0042341161 0.0035428446 0.0055015511 0.0063172163 1.2072440000 0.1121010000 0.0493400000 0.0390590000 0.4898480000 0.5167180000 113229475 0 402718720 3.2616026402 4.0093712807 4.0760254860 110 4.3600000000 0.0045659528 0.0035521456 0.0055015511 0.0063272805 0.6502490000 0.1081280000 0.0491020000 0.0000010000 0.4910980000 0.0017400000 113232251 0 402718720 3.2542779446 4.0088267326 4.0843906403 111 4.4000000000 0.0043278299 0.0035591338 0.0055015511 0.0063264244 0.6986450000 0.1121570000 0.0574650000 0.0386400000 0.4884630000 0.0017390000 113235027 0 402718720 3.2475368977 4.0074939728 4.0910830498 112 4.4400000000 0.0043356782 0.0035660672 0.0055015511 0.0063277489 0.6530750000 0.1122510000 0.0493720000 0.0000000000 0.4895300000 0.0017390000 113237803 0 402718720 3.2396199703 4.0080809593 4.0989532471 113 4.4800000000 0.0044070999 0.0035735100 0.0055015511 0.0063347628 1.2041420000 0.1122670000 0.0512110000 0.0387190000 0.4869340000 0.5148250000 113240579 0 402718720 3.2355213165 4.0079317093 4.1031603813 114 4.5200000000 0.0044044671 0.0035807991 0.0055015511 0.0063809603 0.6595080000 0.1122930000 0.0578340000 0.0000000000 0.4874580000 0.0017390000 113243355 0 402718720 3.2246820927 4.0078315735 4.1154465675 115 4.5600000000 0.0044466639 0.0035883283 0.0055015511 0.0064041909 0.6872790000 0.1123400000 0.0489970000 0.0388590000 0.4851550000 0.0017420000 113246131 0 402718720 3.2240986824 4.0077052116 4.1172876358 116 4.6000000000 0.0044554113 0.0035958032 0.0055015511 0.0064448084 0.6431830000 0.1124020000 0.0430050000 0.0000010000 0.4858510000 0.0017380000 113248907 0 402718720 3.2136876583 4.0103321075 4.1293320656 117 4.6400000000 0.0045373328 0.0036038504 0.0055015511 0.0064524204 1.1871080000 0.1124400000 0.0408050000 0.0393370000 0.4828030000 0.5115330000 113251683 0 402718720 3.2061185837 4.0132799149 4.1397848129 118 4.6800000000 0.0045158495 0.0036115792 0.0055015511 0.0064252242 0.6487680000 0.1123740000 0.0512790000 0.0000000000 0.4831820000 0.0017410000 113254459 0 402718720 3.2004351616 4.0117278099 4.1439838409 119 4.7200000000 0.0043863128 0.0036180896 0.0055015511 0.0064032672 0.6843830000 0.1124000000 0.0491740000 0.0390040000 0.4818700000 0.0017420000 113257235 0 402718720 3.1939780712 4.0112380981 4.1509799957 120 4.7600000000 0.0043862257 0.0036244907 0.0055015511 0.0063785544 0.6960200000 0.1124800000 0.0996490000 0.0000010000 0.4819620000 0.0017340000 113260011 0 402718720 3.1871008873 4.0125837326 4.1592187881 121 4.8000000000 0.0042404006 0.0036295809 0.0055015511 0.0063613510 1.2001250000 0.1124890000 0.0597570000 0.0394630000 0.4792860000 0.5089310000 113262787 0 402718720 3.1776623726 4.0120396614 4.1769466400 122 4.8400000000 0.0044010296 0.0036359043 0.0055015511 0.0063388918 0.6442920000 0.1125100000 0.0491790000 0.0000010000 0.4806710000 0.0017320000 113265563 0 402718720 3.1762077808 4.0135498047 4.1777963638 123 4.8800000000 0.0044368701 0.0036424162 0.0055015511 0.0063168059 0.6833370000 0.1124720000 0.0506650000 0.0394980000 0.4787660000 0.0017320000 113268339 0 402718720 3.1705744267 4.0177206993 4.1841769218 124 4.9200000000 0.0046311314 0.0036503897 0.0055015511 0.0062968014 0.6517760000 0.1124420000 0.0595330000 0.0000000000 0.4778700000 0.0017290000 113271115 0 402718720 3.1614460945 4.0186781883 4.2000846863 125 4.9600000000 0.0045896699 0.0036579039 0.0055015511 0.0062866781 1.1840270000 0.1124460000 0.0489640000 0.0395570000 0.4763490000 0.5065000000 113273891 0 402718720 3.1570653915 4.0184311867 4.2050795555 126 5.0000000000 0.0044050813 0.0036638339 0.0055015511 0.0062673728 0.6486810000 0.1124360000 0.0575650000 0.0000000000 0.4767440000 0.0017320000 113276667 0 402718720 3.1520693302 4.0195231438 4.2123708725 127 5.0400000000 0.0045688478 0.0036709600 0.0055015511 0.0062431385 0.6867270000 0.1123800000 0.0594490000 0.0391290000 0.4738270000 0.0017360000 113279443 0 402718720 3.1427514553 4.0205116272 4.2293543816 128 5.0800000000 0.0045409449 0.0036777568 0.0055015511 0.0062205812 0.6400240000 0.1123820000 0.0512850000 0.0000000000 0.4744130000 0.0017330000 113282219 0 402718720 3.1372504234 4.0203294754 4.2351384163 129 5.1200000000 0.0045614080 0.0036846068 0.0055015511 0.0061976549 1.1801110000 0.1124420000 0.0510300000 0.0396280000 0.4728390000 0.5039560000 113297283 0 402718720 3.1333069801 4.0207037926 4.2418141365 130 5.1600000000 0.0044114455 0.0036901978 0.0055015511 0.0061928102 0.6441670000 0.1123900000 0.0575410000 0.0000010000 0.4722930000 0.0017330000 113325659 0 402718720 3.1245474815 4.0204772949 4.2598071098 131 5.2000000000 0.0045643463 0.0036968707 0.0055015511 0.0062237472 0.6754980000 0.1124610000 0.0509950000 0.0396430000 0.4704540000 0.0017300000 113328435 0 402718720 3.1211020947 4.0210733414 4.2639183998 132 5.2400000000 0.0045129168 0.0037030529 0.0055015511 0.0062357384 0.6373010000 0.1124960000 0.0510800000 0.0000000000 0.4717750000 0.0017300000 113331211 0 402718720 3.1206114292 4.0208106041 4.2615990639 133 5.2800000000 0.0044246782 0.0037084786 0.0055015511 0.0062355944 1.1710300000 0.1124440000 0.0509390000 0.0393960000 0.4681920000 0.4998420000 113333987 0 402718720 3.1102170944 4.0209898949 4.2807106972 134 5.3200000000 0.0049287020 0.0037175848 0.0055015511 0.0062677905 0.6317420000 0.1124450000 0.0490060000 0.0000010000 0.4683420000 0.0017300000 113336763 0 402718720 3.1016800404 4.0238060951 4.2973427773 135 5.3600000000 0.0050961445 0.0037277963 0.0055015511 0.0062886520 0.6690500000 0.1124270000 0.0482660000 0.0395680000 0.4668940000 0.0016780000 113339539 0 402718720 3.0985407829 4.0243096352 4.3013396263 136 5.4000000000 0.0052472954 0.0037389691 0.0055015511 0.0063253859 0.6244570000 0.1083470000 0.0485540000 0.0000000000 0.4656060000 0.0017240000 113342315 0 402718720 3.0917916298 4.0244417191 4.3133792877 137 5.4400000000 0.0051860390 0.0037495317 0.0055015511 0.0063784490 1.1620800000 0.1123590000 0.0510420000 0.0400550000 0.4628500000 0.4955510000 113345091 0 402718720 3.0863974094 4.0248107910 4.3226222992 138 5.4800000000 0.0052012494 0.0037600514 0.0055015511 0.0064212925 0.6266540000 0.1123100000 0.0489660000 0.0000000000 0.4634270000 0.0017250000 113347867 0 402718720 3.0808439255 4.0239596367 4.3273110390 139 5.5200000000 0.0050532860 0.0037693552 0.0055015511 0.0064636493 0.6644040000 0.1123400000 0.0487020000 0.0402970000 0.4611130000 0.0017280000 113350643 0 402718720 3.0747225285 4.0218124390 4.3325128555 140 5.5600000000 0.0050790431 0.0037787101 0.0055015511 0.0065358259 0.6253020000 0.1123770000 0.0488630000 0.0000000000 0.4621070000 0.0017200000 113353419 0 402718720 3.0654623508 4.0225467682 4.3467926979 141 5.6000000000 0.0050911722 0.0037880184 0.0055015511 0.0065696501 1.1538530000 0.1123800000 0.0485180000 0.0403350000 0.4593480000 0.4930460000 113356195 0 402718720 3.0600960255 4.0237660408 4.3522591591 142 5.6400000000 0.0051346272 0.0037975015 0.0055015511 0.0066041802 0.6172720000 0.1123700000 0.0427080000 0.0000000000 0.4602300000 0.0017340000 113358971 0 402718720 3.0508592129 4.0238814354 4.3669767380 143 5.6800000000 0.0051638614 0.0038070565 0.0055015511 0.0066806805 0.6609200000 0.1124820000 0.0485900000 0.0405650000 0.4573320000 0.0017200000 113361747 0 402718720 3.0456206799 4.0261344910 4.3769865036 144 5.7200000000 0.0052319150 0.0038169513 0.0055015511 0.0067245421 0.6215630000 0.1124560000 0.0489300000 0.0000010000 0.4582250000 0.0017160000 113364523 0 402718720 3.0393989086 4.0278778076 4.3848643303 145 5.7600000000 0.0052130199 0.0038265794 0.0055015511 0.0067245803 1.1485530000 0.1124220000 0.0486240000 0.0406580000 0.4560480000 0.4905680000 113367299 0 402718720 3.0338442326 4.0269403458 4.3916125298 146 5.8000000000 0.0052597052 0.0038363953 0.0055015511 0.0067158549 0.6220790000 0.1124160000 0.0509960000 0.0000000000 0.4567130000 0.0017170000 113370075 0 402718720 3.0280060768 4.0271043777 4.4010787010 147 5.8400000000 0.0052898335 0.0038462827 0.0055015511 0.0066993779 0.6580980000 0.1124270000 0.0487170000 0.0407730000 0.4541960000 0.0017490000 113372851 0 402718720 3.0178167820 4.0263433456 4.4220151901 148 5.8800000000 0.0053264624 0.0038562839 0.0055015511 0.0066788067 0.6212390000 0.1124270000 0.0509530000 0.0000010000 0.4559050000 0.0017180000 113375627 0 402718720 3.0163965225 4.0262646675 4.4253935814 149 5.9200000000 0.0052922224 0.0038659211 0.0055015511 0.0066621779 1.1442260000 0.1124340000 0.0486230000 0.0404200000 0.4535790000 0.4889300000 113378403 0 402718720 3.0120387077 4.0269508362 4.4364528656 150 5.9600000000 0.0053407168 0.0038757530 0.0055015511 0.0066438029 0.6200500000 0.1124640000 0.0509430000 0.0000010000 0.4546820000 0.0017150000 113381179 0 402718720 3.0084671974 4.0267353058 4.4451737404 151 6.0000000000 0.0053846566 0.0038857458 0.0055015511 0.0066251799 0.6562870000 0.1124930000 0.0485970000 0.0404720000 0.4527710000 0.0017140000 113383955 0 402718720 3.0051720142 4.0272493362 4.4549055099 152 6.0400000000 0.0053586345 0.0038954358 0.0055015511 0.0066116985 0.6167760000 0.1125100000 0.0488220000 0.0000010000 0.4534910000 0.0017110000 113386731 0 402718720 3.0020675659 4.0285520554 4.4656896591 153 6.0800000000 0.0054439902 0.0039055571 0.0055015511 0.0066009626 1.1409160000 0.1125220000 0.0485990000 0.0410540000 0.4515520000 0.4869430000 113389507 0 402718720 2.9984292984 4.0275931358 4.4742760658 154 6.1200000000 0.0054130191 0.0039153458 0.0055015511 0.0066197730 0.6159540000 0.1125220000 0.0487550000 0.0000010000 0.4527200000 0.0017100000 113392283 0 402718720 2.9939517975 4.0269031525 4.4865956306 155 6.1600000000 0.0053891353 0.0039248541 0.0055015511 0.0066831281 0.6567100000 0.1125110000 0.0505930000 0.0410980000 0.4505430000 0.0017150000 113395059 0 402718720 2.9923000336 4.0259671211 4.4942002296 156 6.2000000000 0.0054081385 0.0039343624 0.0055015511 0.0067948657 0.6235100000 0.1125560000 0.0570310000 0.0000000000 0.4519600000 0.0017110000 113397835 0 402718720 2.9876058102 4.0271072388 4.5091543198 157 6.2400000000 0.0054318612 0.0039439006 0.0055015511 0.0068857042 1.1352460000 0.1125260000 0.0484860000 0.0411510000 0.4486710000 0.4841580000 113400611 0 402718720 2.9853529930 4.0277280807 4.5200800896 158 6.2800000000 0.0054322518 0.0039533205 0.0055015511 0.0069625613 0.6044700000 0.1125060000 0.0405080000 0.0000000000 0.4494900000 0.0017070000 113403387 0 402718720 2.9823577404 4.0280251503 4.5365891457 159 6.3200000000 0.0054653808 0.0039628303 0.0055015511 0.0069930917 0.6523150000 0.1125160000 0.0485470000 0.0410500000 0.4482370000 0.0017090000 113406163 0 402718720 2.9817945957 4.0274329185 4.5443048477 160 6.3600000000 0.0054742605 0.0039722768 0.0055015511 0.0070308576 0.6116240000 0.1125270000 0.0486810000 0.0000000000 0.4484460000 0.0017100000 113408939 0 402718720 2.9806611538 4.0288162231 4.5597834587 161 6.4000000000 0.0055507175 0.0039820807 0.0055507175 0.0070161054 1.1292580000 0.1125690000 0.0484150000 0.0411340000 0.4460410000 0.4808420000 113411715 0 402718720 2.9807789326 4.0293169022 4.5706095695 162 6.4400000000 0.0056470991 0.0039923586 0.0056470991 0.0069965404 0.6103600000 0.1125730000 0.0486720000 0.0000010000 0.4471480000 0.0017040000 113414491 0 402718720 2.9806866646 4.0276365280 4.5817770958 163 6.4800000000 0.0055902009 0.0040021614 0.0056470991 0.0069797669 0.6417160000 0.1126360000 0.0402460000 0.0412960000 0.4455590000 0.0017140000 113417267 0 402718720 2.9797108173 4.0289020538 4.5947856903 164 6.5200000000 0.0055996496 0.0040119021 0.0056470991 0.0069633113 0.6165520000 0.1125870000 0.0545420000 0.0000000000 0.4474530000 0.0017070000 113420043 0 402718720 2.9796066284 4.0302739143 4.6066117287 165 6.5600000000 0.0056440299 0.0040217938 0.0056470991 0.0069537965 1.1259720000 0.1126250000 0.0484560000 0.0412060000 0.4442370000 0.4791840000 113422819 0 402718720 2.9785752296 4.0315289497 4.6246061325 166 6.6000000000 0.0056573348 0.0040316465 0.0056573348 0.0069708477 0.6082000000 0.1125850000 0.0486430000 0.0000000000 0.4449920000 0.0017090000 113425595 0 402718720 2.9793541431 4.0322504044 4.6359019279 167 6.6400000000 0.0056382255 0.0040412667 0.0056573348 0.0069782348 0.6475190000 0.1125870000 0.0484360000 0.0413160000 0.4432050000 0.0017060000 113428371 0 402718720 2.9804069996 4.0341529846 4.6462702751 168 6.6800000000 0.0057062036 0.0040511770 0.0057062036 0.0069805383 0.6072130000 0.1126380000 0.0486940000 0.0000000000 0.4439010000 0.0017060000 113431147 0 402718720 2.9809176922 4.0344367027 4.6587128639 169 6.7200000000 0.0057201544 0.0040610527 0.0057201544 0.0069670472 1.1228130000 0.1126140000 0.0487860000 0.0407200000 0.4431770000 0.4772420000 113433923 0 402718720 2.9809844494 4.0322656631 4.6730995178 170 6.7600000000 0.0057212650 0.0040708186 0.0057212650 0.0069591509 0.6064080000 0.1126440000 0.0487180000 0.0000010000 0.4430620000 0.0017080000 113436699 0 402718720 2.9790873528 4.0343155861 4.6902017593 171 6.8000000000 0.0057250280 0.0040804923 0.0057250280 0.0069523375 0.6462130000 0.1126330000 0.0486450000 0.0412230000 0.4417210000 0.0017110000 113439475 0 402718720 2.9801506996 4.0371127129 4.6993947029 172 6.8400000000 0.0057912869 0.0040904388 0.0057912869 0.0069340984 0.6054040000 0.1126590000 0.0486990000 0.0000000000 0.4420610000 0.0017050000 113442251 0 402718720 2.9806754589 4.0384068489 4.7124361992 173 6.8800000000 0.0057722367 0.0041001602 0.0057912869 0.0069149086 1.1290260000 0.1126710000 0.0589840000 0.0411000000 0.4410760000 0.4749190000 113445027 0 402718720 2.9803085327 4.0399904251 4.7263550758 174 6.9200000000 0.0058460985 0.0041101943 0.0058460985 0.0068955029 0.6046730000 0.1127210000 0.0486630000 0.0000000000 0.4413030000 0.0017040000 113447803 0 402718720 2.9792556763 4.0417943001 4.7390246391 175 6.9600000000 0.0058212103 0.0041199716 0.0058460985 0.0068757263 0.6442120000 0.1127450000 0.0486180000 0.0407100000 0.4401480000 0.0017070000 113450579 0 402718720 2.9797308445 4.0427136421 4.7508444786 176 7.0000000000 0.0058266046 0.0041296683 0.0058460985 0.0068599815 0.6028580000 0.1127020000 0.0487560000 0.0000000000 0.4394030000 0.0017090000 113453355 0 402718720 2.9784677029 4.0430545807 4.7653627396 177 7.0400000000 0.0058574192 0.0041394296 0.0058574192 0.0068705394 1.1134560000 0.1127000000 0.0490750000 0.0412060000 0.4386240000 0.4715630000 113456131 0 402718720 2.9795131683 4.0406632423 4.7724642754 178 7.0800000000 0.0059058997 0.0041493536 0.0059058997 0.0068563531 0.6019140000 0.1126690000 0.0490310000 0.0000000000 0.4382200000 0.0017060000 113458907 0 402718720 2.9807684422 4.0402379036 4.7797541618 179 7.1200000000 0.0058047147 0.0041586015 0.0059058997 0.0068423527 0.6416740000 0.1126900000 0.0488640000 0.0410010000 0.4371180000 0.0017130000 113461683 0 402718720 2.9809682369 4.0426149368 4.7934060097 180 7.1600000000 0.0058543165 0.0041680221 0.0059058997 0.0068240562 0.6007700000 0.1126240000 0.0489830000 0.0000000000 0.4371620000 0.0017070000 113464459 0 402718720 2.9817631245 4.0450983047 4.8064532280 181 7.2000000000 0.0058558639 0.0041773472 0.0059058997 0.0068093221 1.0996830000 0.1126020000 0.0405680000 0.0409770000 0.4365110000 0.4687300000 113467235 0 402718720 2.9839107990 4.0457572937 4.8172659874 182 7.2400000000 0.0058802455 0.0041867038 0.0059058997 0.0067924677 0.5943540000 0.1126810000 0.0427290000 0.0000010000 0.4369420000 0.0017060000 113470011 0 402718720 2.9835863113 4.0460371971 4.8312382698 183 7.2800000000 0.0058860681 0.0041959899 0.0059058997 0.0067773488 0.6425510000 0.1126820000 0.0509870000 0.0409520000 0.4359250000 0.0017080000 113472787 0 402718720 2.9818973541 4.0466079712 4.8474216461 184 7.3200000000 0.0058987644 0.0042052441 0.0059058997 0.0067594228 0.6017130000 0.1126560000 0.0510110000 0.0000000000 0.4360420000 0.0017050000 113475563 0 402718720 2.9840862751 4.0461874008 4.8580303192 185 7.3600000000 0.0058645690 0.0042142135 0.0059058997 0.0067437688 1.1067170000 0.1126750000 0.0509240000 0.0409290000 0.4351940000 0.4666920000 113478339 0 402718720 2.9856257439 4.0464396477 4.8734178543 186 7.4000000000 0.0058134235 0.0042228114 0.0059058997 0.0067313505 0.5908410000 0.1126030000 0.0405410000 0.0000000000 0.4356940000 0.0017040000 113481115 0 402718720 2.9854891300 4.0460724831 4.8915262222 187 7.4400000000 0.0057839160 0.0042311595 0.0059058997 0.0067249316 0.6409270000 0.1126250000 0.0506120000 0.0409700000 0.4347170000 0.0017040000 113483891 0 402718720 2.9886188507 4.0460748672 4.8999147415 188 7.4800000000 0.0058073099 0.0042395433 0.0059058997 0.0067333818 0.5992630000 0.1126470000 0.0486600000 0.0000000000 0.4359540000 0.0016990000 113486667 0 402718720 2.9909894466 4.0496392250 4.9153795242 189 7.5200000000 0.0057971785 0.0042477847 0.0059058997 0.0067172522 1.0936690000 0.1126190000 0.0401840000 0.0409130000 0.4343510000 0.4652970000 113489443 0 402718720 2.9931449890 4.0523657799 4.9329857826 190 7.5600000000 0.0058565969 0.0042562522 0.0059058997 0.0067072208 0.5990210000 0.1126150000 0.0485430000 0.0000000000 0.4358540000 0.0017000000 113492219 0 402718720 2.9954161644 4.0513286591 4.9477581978 191 7.6000000000 0.0058575352 0.0042646359 0.0059058997 0.0066955352 0.6385300000 0.1126500000 0.0484320000 0.0410420000 0.4343920000 0.0017060000 113494995 0 402718720 2.9967222214 4.0535864830 4.9640693665 192 7.6400000000 0.0059486316 0.0042734067 0.0059486316 0.0066883515 0.5988170000 0.1126210000 0.0484260000 0.0000000000 0.4357550000 0.0016990000 113497771 0 402718720 3.0003898144 4.0597462654 4.9791512489 193 7.6800000000 0.0060097170 0.0042824031 0.0060097170 0.0066897118 1.1107800000 0.1126490000 0.0561380000 0.0410210000 0.4349830000 0.4656770000 113500547 0 402718720 3.0004115105 4.0602493286 4.9974379539 194 7.7200000000 0.0061121238 0.0042918346 0.0061121238 0.0066870532 0.5995430000 0.1126400000 0.0483290000 0.0000000000 0.4365670000 0.0016970000 113503323 0 402718720 3.0001449585 4.0562372208 5.0137414932 195 7.7600000000 0.0061011314 0.0043011131 0.0061121238 0.0066902286 0.6308630000 0.1126190000 0.0399200000 0.0411040000 0.4352060000 0.0016970000 113506099 0 402718720 3.0013740063 4.0558047295 5.0267815590 196 7.8000000000 0.0060806335 0.0043101923 0.0061121238 0.0067270353 0.5986740000 0.1125050000 0.0482230000 0.0000010000 0.4359340000 0.0016960000 113508875 0 402718720 3.0032432079 4.0594563484 5.0435519218 197 7.8400000000 0.0061658588 0.0043196119 0.0061658588 0.0067526459 1.1009200000 0.1123610000 0.0479850000 0.0407900000 0.4346580000 0.4648100000 113511651 0 402718720 3.0050923824 4.0629286766 5.0556225777 198 7.8800000000 0.0060447548 0.0043283247 0.0061658588 0.0067704937 0.5963460000 0.1122390000 0.0460820000 0.0000000000 0.4360170000 0.0016910000 113514427 0 402718720 3.0062143803 4.0666213036 5.0721526146 199 7.9200000000 0.0060697133 0.0043370754 0.0061658588 0.0067637197 0.6374140000 0.1122360000 0.0477620000 0.0407190000 0.4346870000 0.0016870000 113517203 0 402718720 3.0082845688 4.0675587654 5.0879645348 200 7.9600000000 0.0062711644 0.0043467459 0.0062711644 0.0067543739 0.5984420000 0.1122120000 0.0479250000 0.0000010000 0.4362970000 0.0016850000 113519979 0 402718720 3.0084707737 4.0661644936 5.1020331383 201 8.0000000000 0.0062078196 0.0043560050 0.0062711644 0.0067697167 1.1018030000 0.1121560000 0.0477250000 0.0413710000 0.4348930000 0.4653300000 113522755 0 402718720 3.0091068745 4.0665392876 5.1207494736 202 8.0400000000 0.0061857253 0.0043650630 0.0062711644 0.0067868306 0.6001910000 0.1121210000 0.0498360000 0.0000000000 0.4362260000 0.0016800000 113525531 0 402718720 3.0119180679 4.0674557686 5.1310119629 203 8.0800000000 0.0062815491 0.0043745038 0.0062815491 0.0067963243 0.6375430000 0.1121650000 0.0476420000 0.0411440000 0.4345870000 0.0016760000 113528307 0 402718720 3.0142195225 4.0692563057 5.1484413147 204 8.1200000000 0.0061513870 0.0043832140 0.0062815491 0.0067885155 0.5974900000 0.1122330000 0.0476980000 0.0000010000 0.4355530000 0.0016760000 113531083 0 402718720 3.0161039829 4.0686759949 5.1607160568 205 8.1600000000 0.0062230015 0.0043921886 0.0062815491 0.0067806402 1.1003900000 0.1122860000 0.0476330000 0.0414200000 0.4344680000 0.4642490000 113533859 0 402718720 3.0190234184 4.0676646233 5.1724820137 206 8.1999999990 0.0062240730 0.0044010812 0.0062815491 0.0067714126 0.6051260000 0.1122920000 0.0557970000 0.0000010000 0.4350320000 0.0016700000 113536635 0 402718720 3.0223901272 4.0677237511 5.1860342026 207 8.2400000000 0.0062141907 0.0044098402 0.0062815491 0.0067641223 0.6368810000 0.1123190000 0.0475860000 0.0413900000 0.4335740000 0.0016750000 113539411 0 402718720 3.0269131660 4.0706071854 5.1996097565 208 8.2799999990 0.0061819297 0.0044183599 0.0062815491 0.0067514201 0.6036610000 0.1122800000 0.0557480000 0.0000000000 0.4336300000 0.0016680000 113542187 0 402718720 3.0311322212 4.0727300644 5.2122216225 209 8.3200000000 0.0062869927 0.0044273007 0.0062869927 0.0067487950 1.0887000000 0.1122450000 0.0394530000 0.0413720000 0.4330200000 0.4622750000 113544963 0 402718720 3.0356910229 4.0745863914 5.2253456116 210 8.3599999990 0.0062917774 0.0044361792 0.0062917774 0.0067726786 0.5979490000 0.1122590000 0.0493840000 0.0000010000 0.4343010000 0.0016690000 113547739 0 402718720 3.0413239002 4.0754160881 5.2363576889 211 8.4000000000 0.0063498723 0.0044452488 0.0063498723 0.0067924644 0.6368950000 0.1122340000 0.0472440000 0.0417120000 0.4336970000 0.0016670000 113550515 0 402718720 3.0463747978 4.0736050606 5.2501130104 212 8.4399999990 0.0063881902 0.0044544136 0.0063881902 0.0067785910 0.5899720000 0.1121490000 0.0414020000 0.0000010000 0.4344150000 0.0016630000 113553291 0 402718720 3.0536608696 4.0765557289 5.2617306709 213 8.4800000000 0.0064295386 0.0044636865 0.0064295386 0.0067801780 1.0990900000 0.1121470000 0.0491060000 0.0413210000 0.4337540000 0.4624170000 113556067 0 402718720 3.0600943565 4.0804629326 5.2762346268 214 8.5200000000 0.0064639715 0.0044730336 0.0064639715 0.0068429836 0.5966580000 0.1121020000 0.0470310000 0.0000010000 0.4355140000 0.0016650000 113558843 0 402718720 3.0671529770 4.0807352066 5.2883744240 215 8.5600000000 0.0064857411 0.0044823951 0.0064857411 0.0068524105 0.6384730000 0.1120640000 0.0489070000 0.0407650000 0.4347190000 0.0016710000 113561619 0 402718720 3.0750346184 4.0800480843 5.2988829613 216 8.6000000000 0.0065716840 0.0044920677 0.0065716840 0.0068376302 0.5966840000 0.1120140000 0.0471470000 0.0000010000 0.4355100000 0.0016660000 113564395 0 402718720 3.0843448639 4.0845665932 5.3104929924 217 8.6400000000 0.0066949655 0.0045022193 0.0066949655 0.0068615404 1.0974120000 0.1119340000 0.0469820000 0.0410730000 0.4344200000 0.4626530000 113567171 0 402718720 3.0933361053 4.0876040459 5.3273506165 218 8.6800000000 0.0065484387 0.0045116056 0.0066949655 0.0069121654 0.5967720000 0.1119650000 0.0470920000 0.0000010000 0.4356880000 0.0016760000 113569947 0 402718720 3.1017620564 4.0873346329 5.3364210129 219 8.7200000000 0.0067064031 0.0045216275 0.0067064031 0.0069122571 0.6281560000 0.1118720000 0.0390540000 0.0411550000 0.4340450000 0.0016760000 113572723 0 402718720 3.1119294167 4.0902061462 5.3467526436 220 8.7600000000 0.0068509472 0.0045322153 0.0068509472 0.0069154862 0.5962070000 0.1118070000 0.0470970000 0.0000010000 0.4352750000 0.0016740000 113575499 0 402718720 3.1225156784 4.0952215195 5.3585186005 221 8.8000000000 0.0067555718 0.0045422758 0.0068509472 0.0069529308 1.0934730000 0.1117340000 0.0468930000 0.0410430000 0.4338080000 0.4596440000 113578275 0 402718720 3.1321761608 4.0963492393 5.3702974319 222 8.8400000000 0.0069386591 0.0045530703 0.0069386591 0.0069614446 0.5879260000 0.1116770000 0.0391870000 0.0000000000 0.4350180000 0.0016800000 113581051 0 402718720 3.1414833069 4.0981950760 5.3848524094 223 8.8800000000 0.0069505475 0.0045638213 0.0069505475 0.0069622490 0.6349670000 0.1115560000 0.0470030000 0.0409910000 0.4333630000 0.0016910000 113583827 0 402718720 3.1521344185 4.1013598442 5.3942251205 224 8.9200000000 0.0069109206 0.0045742994 0.0069505475 0.0069681653 0.5956530000 0.1115550000 0.0471390000 0.0000000000 0.4349090000 0.0016890000 113586603 0 402718720 3.1628515720 4.1044287682 5.4048337936 225 8.9600000000 0.0069391085 0.0045848097 0.0069505475 0.0069655074 1.0872610000 0.1114930000 0.0469580000 0.0410300000 0.4317840000 0.4556330000 113589379 0 402718720 3.1733241081 4.1071009636 5.4128794670 226 9.0000000000 0.0072767679 0.0045967210 0.0072767679 0.0069519125 0.5940170000 0.1113780000 0.0472010000 0.0000010000 0.4333760000 0.0016910000 113592155 0 402718720 3.1837801933 4.1113400459 5.4245223999 227 9.0400000000 0.0071052541 0.0046077718 0.0072767679 0.0069381143 0.6271160000 0.1113990000 0.0413220000 0.0411670000 0.4311590000 0.0016980000 113594931 0 402718720 3.1957530975 4.1171164513 5.4329152107 228 9.0800000000 0.0072718351 0.0046194563 0.0072767679 0.0069493676 0.5958280000 0.1115830000 0.0495590000 0.0000010000 0.4326100000 0.0017030000 113597707 0 402718720 3.2073085308 4.1231775284 5.4464230537 229 9.1200000000 0.0072267861 0.0046308420 0.0072767679 0.0070086768 1.0793140000 0.1117680000 0.0496040000 0.0408680000 0.4279330000 0.4487710000 113600483 0 402718720 3.2178835869 4.1272521019 5.4538555145 230 9.1600000000 0.0072583845 0.0046422661 0.0072767679 0.0071100101 0.5940010000 0.1120010000 0.0499680000 0.0000010000 0.4299410000 0.0017230000 113603259 0 402718720 3.2287743092 4.1313381195 5.4607195854 231 9.2000000000 0.0071190111 0.0046529880 0.0072767679 0.0073229611 0.6226780000 0.1120870000 0.0421510000 0.0406870000 0.4256400000 0.0017380000 113606035 0 402718720 3.2380225658 4.1321673393 5.4681487083 232 9.2400000000 0.0072430805 0.0046641522 0.0072767679 0.0074876686 0.5909640000 0.1119560000 0.0490200000 0.0000010000 0.4278720000 0.0017400000 113608811 0 402718720 3.2475469112 4.1352400780 5.4765129089 233 9.2800000000 0.0071944590 0.0046750119 0.0072767679 0.0076314484 1.0650490000 0.1118940000 0.0491650000 0.0406630000 0.4225960000 0.4403580000 113611587 0 402718720 3.2571525574 4.1380000114 5.4838109016 234 9.3200000000 0.0072319899 0.0046859391 0.0072767679 0.0077353356 0.5880450000 0.1117770000 0.0489880000 0.0000000000 0.4251470000 0.0017580000 113614363 0 402718720 3.2671065331 4.1417446136 5.4907121658 235 9.3600000000 0.0071949908 0.0046966159 0.0072767679 0.0078124396 0.6240010000 0.1116620000 0.0493380000 0.0403260000 0.4205130000 0.0017780000 113617139 0 402718720 3.2772114277 4.1449484825 5.4980020523 236 9.4000000000 0.0073567210 0.0047078876 0.0073567210 0.0078735624 0.5884890000 0.1116390000 0.0520970000 0.0000010000 0.4225870000 0.0017880000 113619915 0 402718720 3.2866821289 4.1479249001 5.5063810349 237 9.4400000000 0.0072660847 0.0047186816 0.0073567210 0.0079018924 1.0474050000 0.1116820000 0.0416260000 0.0401440000 0.4189680000 0.4346020000 113622691 0 402718720 3.2966554165 4.1518902779 5.5128412247 238 9.4800000000 0.0074616163 0.0047302066 0.0074616163 0.0079238654 0.5841270000 0.1116880000 0.0505420000 0.0000010000 0.4196960000 0.0018170000 113625467 0 402718720 3.3075459003 4.1581254005 5.5206289291 239 9.5200000000 0.0073893070 0.0047413325 0.0074616163 0.0079676364 0.6206700000 0.1116130000 0.0509160000 0.0399440000 0.4159720000 0.0018390000 113628243 0 402718720 3.3182697296 4.1632127762 5.5281629562 240 9.5600000000 0.0074287611 0.0047525301 0.0074616163 0.0080216426 0.5750350000 0.1114090000 0.0428510000 0.0000010000 0.4185810000 0.0018110000 113631019 0 402718720 3.3284800053 4.1680307388 5.5367298126 241 9.6000000000 0.0073921420 0.0047634829 0.0074616163 0.0080763807 1.0419420000 0.1079500000 0.0541400000 0.0393430000 0.4151510000 0.4249700000 113633795 0 402718720 3.3377785683 4.1687717438 5.5454502106 242 9.6400000000 0.0072748684 0.0047738605 0.0074616163 0.0080971773 0.5837100000 0.1109230000 0.0557340000 0.0000010000 0.4147520000 0.0019130000 113636571 0 402718720 3.3475270271 4.1711668968 5.5539975166 243 9.6800000000 0.0072706779 0.0047841355 0.0074616163 0.0081115274 0.6269680000 0.1107800000 0.0632690000 0.0396440000 0.4109540000 0.0019300000 113639347 0 402718720 3.3585076332 4.1771368980 5.5617566109 244 9.7200000000 0.0072713611 0.0047943290 0.0074616163 0.0081584067 0.5817810000 0.1105100000 0.0568830000 0.0000010000 0.4120640000 0.0019310000 113642123 0 402718720 3.3698019981 4.1835808754 5.5698709488 245 9.7600000000 0.0071366904 0.0048038897 0.0074616163 0.0082217091 1.0299640000 0.1104170000 0.0569510000 0.0397160000 0.4066260000 0.4158640000 113644899 0 402718720 3.3800346851 4.1859488487 5.5777730942 246 9.8000000000 0.0071365130 0.0048133719 0.0074616163 0.0082414560 0.5691020000 0.1106950000 0.0477790000 0.0000000000 0.4082940000 0.0019280000 113647675 0 402718720 3.3903782368 4.1888141632 5.5867428780 247 9.8400000000 0.0072166366 0.0048231017 0.0074616163 0.0082465871 0.6129760000 0.1107130000 0.0570280000 0.0401500000 0.4027610000 0.0019310000 113650451 0 402718720 3.3998949528 4.1891536713 5.5967302322 248 9.8800000000 0.0072048940 0.0048327057 0.0074616163 0.0082317795 0.5737500000 0.1105200000 0.0573130000 0.0000010000 0.4035920000 0.0019250000 113653227 0 402718720 3.4092273712 4.1909055710 5.6052246094 249 9.9200000000 0.0071797455 0.0048421316 0.0074616163 0.0082163545 1.0164400000 0.1104050000 0.0547740000 0.0403470000 0.4002680000 0.4102480000 113656003 0 402718720 3.4192583561 4.1931700706 5.6128754616 250 9.9600000000 0.0071951598 0.0048515437 0.0074616163 0.0082001774 0.5600660000 0.1105070000 0.0455000000 0.0000000000 0.4017280000 0.0019290000 113658779 0 402718720 3.4289419651 4.1953783035 5.6218295097 251 10.0000000000 0.0072794626 0.0048612167 0.0074616163 0.0081840329 0.6106740000 0.1105350000 0.0570710000 0.0405020000 0.4002320000 0.0019330000 113661555 0 402718720 3.4390602112 4.1985430717 5.6306118965 252 10.0400000000 0.0072284313 0.0048706104 0.0074616163 0.0081708800 0.5711330000 0.1106280000 0.0573370000 0.0000000000 0.4008190000 0.0019370000 113664331 0 402718720 3.4475920200 4.1975808144 5.6410799026 253 10.0800000000 0.0071692928 0.0048796961 0.0074616163 0.0081555893 1.0359870000 0.1107380000 0.0737350000 0.0411150000 0.3997890000 0.4102050000 113667107 0 402718720 3.4551355839 4.1944413185 5.6509008408 254 10.1200000000 0.0072378851 0.0048889803 0.0074616163 0.0081758421 0.5691610000 0.1106060000 0.0549830000 0.0000000000 0.4012310000 0.0019350000 113669883 0 402718720 3.4649245739 4.1983070374 5.6597871780 255 10.1600000000 0.0072411266 0.0048982044 0.0074616163 0.0081910939 0.6094600000 0.1103890000 0.0550390000 0.0412880000 0.4003990000 0.0019350000 113672659 0 402718720 3.4758083820 4.2051796913 5.6686925888 256 10.2000000000 0.0072721345 0.0049074776 0.0074616163 0.0081785964 0.5583990000 0.1103180000 0.0457010000 0.0000010000 0.4000390000 0.0019300000 113675435 0 402718720 3.4870095253 4.2101101875 5.6771502495 257 10.2400000000 0.0072193677 0.0049164732 0.0074616163 0.0081643149 1.0167930000 0.1105190000 0.0575700000 0.0413370000 0.3983350000 0.4086150000 113702787 0 402718720 3.4963767529 4.2097620964 5.6859579086 258 10.2800000000 0.0072357845 0.0049254628 0.0074616163 0.0081484602 0.5681720000 0.1101800000 0.0575570000 0.0000010000 0.3980850000 0.0019340000 113756763 0 402718720 3.5067279339 4.2148509026 5.6947841644 259 10.3200000000 0.0072563435 0.0049344624 0.0074616163 0.0081426283 0.6067480000 0.1101310000 0.0573160000 0.0409600000 0.3959830000 0.0019360000 113759539 0 402718720 3.5172092915 4.2187500000 5.7011909485 260 10.3600000000 0.0072632153 0.0049434191 0.0074616163 0.0081486571 0.5636130000 0.1102100000 0.0549170000 0.0000010000 0.3961370000 0.0019320000 113762315 0 402718720 3.5271883011 4.2203545570 5.7094283104 261 10.4000000000 0.0072004814 0.0049520668 0.0074616163 0.0081483699 1.0075420000 0.1102730000 0.0547520000 0.0411660000 0.3947530000 0.4061750000 113765091 0 402718720 3.5367507935 4.2198147774 5.7162618637 262 10.4400000000 0.0072213090 0.0049607281 0.0074616163 0.0081359879 0.5658160000 0.1104790000 0.0571650000 0.0000000000 0.3958240000 0.0019240000 113767867 0 402718720 3.5462799072 4.2201066017 5.7234716415 263 10.4800000000 0.0071934932 0.0049692177 0.0074616163 0.0081225182 0.6060990000 0.1106110000 0.0570380000 0.0413140000 0.3947850000 0.0019240000 113770643 0 402718720 3.5570728779 4.2215242386 5.7290892601 264 10.5200000000 0.0071800184 0.0049775919 0.0074616163 0.0081122491 0.6217090000 0.1107460000 0.1133960000 0.0000000000 0.3952150000 0.0019210000 113773419 0 402718720 3.5673856735 4.2211599350 5.7350730896 265 10.5600000000 0.0072342730 0.0049861077 0.0074616163 0.0080971256 1.0062080000 0.1108760000 0.0545820000 0.0411690000 0.3934700000 0.4056800000 113776195 0 402718720 3.5786347389 4.2230925560 5.7412729263 266 10.6000000000 0.0071461103 0.0049942280 0.0074616163 0.0080863163 0.5697960000 0.1108460000 0.0640560000 0.0000000000 0.3925400000 0.0019210000 113778971 0 402718720 3.5906207561 4.2253227234 5.7455916405 267 10.6400000000 0.0071713016 0.0050023818 0.0074616163 0.0080826286 0.6024900000 0.1109790000 0.0571790000 0.0409470000 0.3910240000 0.0019240000 113781747 0 402718720 3.6018867493 4.2244310379 5.7496118546 268 10.6800000000 0.0071903309 0.0050105458 0.0074616163 0.0080758664 0.5716790000 0.1109320000 0.0667090000 0.0000000000 0.3916780000 0.0019230000 113784523 0 402718720 3.6132254601 4.2238874435 5.7556567192 269 10.7200000000 0.0071410621 0.0050184660 0.0074616163 0.0080648865 1.0099640000 0.1111150000 0.0643990000 0.0406540000 0.3907040000 0.4026540000 113787299 0 402718720 3.6251244545 4.2236833572 5.7579836845 270 10.7600000000 0.0071280687 0.0050262793 0.0074616163 0.0080556395 0.5578740000 0.1111120000 0.0549380000 0.0000000000 0.3894640000 0.0019200000 113790075 0 402718720 3.6505210400 4.2284116745 5.7683305740 271 10.8000000000 0.0071169273 0.0050339939 0.0074616163 0.0080726564 0.5928900000 0.1111670000 0.0546040000 0.0399550000 0.3848010000 0.0019240000 113792851 0 402718720 3.6648480892 4.2321486473 5.7716684341 272 10.8400000000 0.0071337242 0.0050417135 0.0074616163 0.0081346348 0.5603480000 0.1110140000 0.0642510000 0.0000000000 0.3827140000 0.0019250000 113795627 0 402718720 3.6768028736 4.2302894592 5.7751069069 273 10.8800000000 0.0071293619 0.0050493605 0.0074616163 0.0081430899 0.9796670000 0.1110610000 0.0572700000 0.0397610000 0.3799810000 0.3911500000 113798403 0 402718720 3.6894080639 4.2310085297 5.7796673775 274 10.9200000000 0.0071591148 0.0050570604 0.0074616163 0.0081519485 0.5498720000 0.1111820000 0.0573460000 0.0000000000 0.3789750000 0.0019260000 113801179 0 402718720 3.7026886940 4.2322463989 5.7833504677 275 10.9600000000 0.0071381349 0.0050646279 0.0074616163 0.0081575886 0.5777810000 0.1111960000 0.0480690000 0.0394980000 0.3766290000 0.0019300000 113803955 0 402718720 3.7155780792 4.2321848869 5.7861132622 276 11.0000000000 0.0071569942 0.0050722090 0.0074616163 0.0081547927 0.5473550000 0.1111950000 0.0577460000 0.0000010000 0.3760390000 0.0019270000 113806731 0 402718720 3.7290418148 4.2340860367 5.7898797989 277 11.0400000000 0.0071765706 0.0050798059 0.0074616163 0.0081603711 0.9653660000 0.1112700000 0.0552430000 0.0392660000 0.3737830000 0.3853530000 113809507 0 402718720 3.7426111698 4.2355852127 5.7932310104 278 11.0800000000 0.0072011533 0.0050874367 0.0074616163 0.0081662420 0.5440630000 0.1113960000 0.0576450000 0.0000010000 0.3726500000 0.0019240000 113812283 0 402718720 3.7561986446 4.2373485565 5.7966151237 279 11.1200000000 0.0071806516 0.0050949392 0.0074616163 0.0081755457 0.5803920000 0.1113730000 0.0575060000 0.0390210000 0.3701040000 0.0019320000 113815059 0 402718720 3.7701516151 4.2390937805 5.8006010056 280 11.1600000000 0.0071908194 0.0051024245 0.0074616163 0.0081837902 0.5395770000 0.1112500000 0.0575550000 0.0000000000 0.3683850000 0.0019290000 113817835 0 402718720 3.7841577530 4.2416052818 5.8037514687 281 11.2000000000 0.0072194231 0.0051099583 0.0074616163 0.0081901615 0.9502940000 0.1112970000 0.0575930000 0.0380850000 0.3660460000 0.3768160000 113820611 0 402718720 3.7973062992 4.2424798012 5.8063597679 282 11.2400000000 0.0071897241 0.0051173334 0.0074616163 0.0081855324 0.5365320000 0.1112960000 0.0576310000 0.0000000000 0.3652150000 0.0019270000 113823387 0 402718720 3.8091518879 4.2414660454 5.8109831810 283 11.2800000000 0.0071856482 0.0051246419 0.0074616163 0.0081712248 0.5740090000 0.1113730000 0.0576360000 0.0385460000 0.3641280000 0.0018650000 113826163 0 402718720 3.8214502335 4.2427768707 5.8134665489 284 11.3200000000 0.0072144126 0.0051320003 0.0074616163 0.0081603438 0.5291170000 0.1077140000 0.0546320000 0.0000010000 0.3643880000 0.0019230000 113828939 0 402718720 3.8340375423 4.2448954582 5.8188257217 285 11.3600000000 0.0073153866 0.0051396613 0.0074616163 0.0081575717 0.9487050000 0.1113120000 0.0646640000 0.0381560000 0.3616920000 0.3724250000 113831715 0 402718720 3.8456478119 4.2460994720 5.8229556084 286 11.4000000000 0.0072101699 0.0051469008 0.0074616163 0.0081495061 0.5411780000 0.1112570000 0.0671990000 0.0000000000 0.3603360000 0.0019240000 113834491 0 402718720 3.8561484814 4.2459526062 5.8269801140 287 11.4400000000 0.0072557759 0.0051542488 0.0074616163 0.0081353311 0.5682430000 0.1112400000 0.0577040000 0.0379900000 0.3589060000 0.0019330000 113837267 0 402718720 3.8656806946 4.2456121445 5.8311800957 288 11.4800000000 0.0071802526 0.0051612835 0.0074616163 0.0081220365 0.5298910000 0.1110770000 0.0576700000 0.0000000000 0.3587580000 0.0019140000 113840043 0 402718720 3.8745238781 4.2454209328 5.8351302147 289 11.5200000000 0.0072402414 0.0051684772 0.0074616163 0.0081093353 0.9313860000 0.1108720000 0.0576080000 0.0375780000 0.3573370000 0.3675200000 113842819 0 402718720 3.8830747604 4.2453570366 5.8416953087 290 11.5600000000 0.0072476305 0.0051756467 0.0074616163 0.0081010814 0.5858100000 0.1108840000 0.1146770000 0.0000010000 0.3578600000 0.0019140000 113845595 0 402718720 3.8913929462 4.2457671165 5.8474459648 291 11.6000000000 0.0072873351 0.0051829033 0.0074616163 0.0080908995 0.6195220000 0.1108620000 0.1116130000 0.0374140000 0.3572360000 0.0019190000 113848371 0 402718720 3.8989489079 4.2449035645 5.8545689583 292 11.6400000000 0.0072833472 0.0051900966 0.0074616163 0.0080787854 0.5474960000 0.1106970000 0.0769490000 0.0000010000 0.3574540000 0.0019170000 113851147 0 402718720 3.9069895744 4.2458872795 5.8603348732 293 11.6800000000 0.0072763562 0.0051972170 0.0074616163 0.0080650604 0.9155730000 0.1105670000 0.0458510000 0.0371890000 0.3560620000 0.3654200000 113853923 0 402718720 3.9139604568 4.2461409569 5.8671922684 294 11.7200000000 0.0073164706 0.0052044253 0.0074616163 0.0080527573 0.5273020000 0.1106740000 0.0577850000 0.0000010000 0.3564400000 0.0019190000 113856699 0 402718720 3.9200868607 4.2454547882 5.8745579720 295 11.7600000000 0.0073079029 0.0052115557 0.0074616163 0.0080448664 0.5619700000 0.1106730000 0.0552400000 0.0371600000 0.3564890000 0.0019200000 113859475 0 402718720 3.9257743359 4.2454037666 5.8815064430 296 11.8000000000 0.0072919996 0.0052185843 0.0074616163 0.0080358238 0.5267280000 0.1107550000 0.0551830000 0.0000000000 0.3581560000 0.0020040000 113862251 0 402718720 3.9316251278 4.2455754280 5.8880348206 297 11.8400000000 0.0073328521 0.0052257030 0.0074616163 0.0080273241 0.9299230000 0.1108680000 0.0551860000 0.0371600000 0.3582070000 0.3680180000 113865027 0 402718720 3.9365301132 4.2451453209 5.8955893517 298 11.8800000000 0.0073535987 0.0052328436 0.0074616163 0.0080228082 0.5288280000 0.1109270000 0.0551520000 0.0000010000 0.3603420000 0.0019190000 113867803 0 402718720 3.9414250851 4.2445259094 5.9035563469 299 11.9200000000 0.0073325117 0.0052398659 0.0074616163 0.0080138164 0.5668300000 0.1110520000 0.0552300000 0.0372650000 0.3608720000 0.0019170000 113870579 0 402718720 3.9464676380 4.2445230484 5.9116840363 300 11.9600000000 0.0073402352 0.0052468671 0.0074616163 0.0080012860 0.5305110000 0.1110560000 0.0553700000 0.0000010000 0.3616770000 0.0019180000 113873355 0 402718720 3.9514849186 4.2453455925 5.9199757576 301 12.0000000000 0.0073363390 0.0052538089 0.0074616163 0.0079882122 0.9339930000 0.1112240000 0.0530050000 0.0368300000 0.3612060000 0.3712340000 113876131 0 402718720 3.9561207294 4.2456245422 5.9292058945 302 12.0400000000 0.0073870365 0.0052608726 0.0074616163 0.0079775912 0.5321170000 0.1111770000 0.0552040000 0.0000010000 0.3633270000 0.0019130000 113878907 0 402718720 3.9600951672 4.2455172539 5.9390950203 303 12.0800000000 0.0073380889 0.0052677281 0.0074616163 0.0079716658 0.5687830000 0.1111880000 0.0551250000 0.0374520000 0.3626000000 0.0019150000 113881683 0 402718720 3.9642815590 4.2457633018 5.9490523338 304 12.1200000000 0.0074516470 0.0052749120 0.0074616163 0.0079706564 0.5520130000 0.1112580000 0.0742120000 0.0000000000 0.3641290000 0.0019130000 113884459 0 402718720 3.9682221413 4.2461366653 5.9593138695 305 12.1600000000 0.0074006990 0.0052818818 0.0074616163 0.0079677473 0.9431890000 0.1112480000 0.0553140000 0.0374830000 0.3642500000 0.3743780000 113887235 0 402718720 3.9718790054 4.2459454536 5.9705963135 306 12.2000000000 0.0074325707 0.0052889102 0.0074616163 0.0079611480 0.5418460000 0.1163840000 0.0578710000 0.0000010000 0.3651750000 0.0019120000 113890011 0 402718720 3.9754960537 4.2459411621 5.9821100235 307 12.2400000000 0.0074773002 0.0052960385 0.0074773002 0.0079629999 0.5739220000 0.1113590000 0.0569990000 0.0375290000 0.3656110000 0.0019170000 113892787 0 402718720 3.9787797928 4.2467141151 5.9937496185 308 12.2800000000 0.0075059193 0.0053032134 0.0075059193 0.0079670368 0.5266500000 0.1114340000 0.0456420000 0.0000010000 0.3671590000 0.0019120000 113895563 0 402718720 3.9814155102 4.2468461990 6.0053219795 309 12.3200000000 0.0074744560 0.0053102401 0.0075059193 0.0079784516 0.9513430000 0.1114710000 0.0544550000 0.0376630000 0.3685620000 0.3786760000 113898339 0 402718720 3.9833290577 4.2464222908 6.0162529945 310 12.3600000000 0.0075207166 0.0053173707 0.0075207166 0.0079973880 0.5496510000 0.1115690000 0.0645140000 0.0000010000 0.3711510000 0.0019080000 113901115 0 402718720 3.9850046635 4.2459468842 6.0282158852 311 12.4000000000 0.0075486652 0.0053245453 0.0075486652 0.0080112926 0.5904180000 0.1116560000 0.0669930000 0.0374190000 0.3719240000 0.0019140000 113903891 0 402718720 3.9872267246 4.2467899323 6.0390067101 312 12.4400000000 0.0075917211 0.0053318119 0.0075917211 0.0080484897 0.5454070000 0.1117670000 0.0576610000 0.0000010000 0.3735650000 0.0019070000 113906667 0 402718720 3.9895844460 4.2465457916 6.0628476143 313 12.4800000000 0.0075928867 0.0053390357 0.0075928867 0.0080423433 0.9610110000 0.1117220000 0.0551550000 0.0374580000 0.3729170000 0.3832420000 113909443 0 402718720 3.9901728630 4.2463450432 6.0736074448 314 12.5200000000 0.0076422691 0.0053463709 0.0076422691 0.0080346800 0.5424260000 0.1117580000 0.0548080000 0.0000010000 0.3734240000 0.0019090000 113912219 0 402718720 3.9902350903 4.2452578545 6.0861673355 315 12.5600000000 0.0076716118 0.0053537526 0.0076716118 0.0080350010 0.5799610000 0.1117440000 0.0543770000 0.0375210000 0.3739490000 0.0018500000 113914995 0 402718720 3.9906888008 4.2455143929 6.0975208282 316 12.6000000000 0.0076652123 0.0053610673 0.0076716118 0.0080247965 0.5377930000 0.1078680000 0.0543020000 0.0000010000 0.3731990000 0.0019080000 113917771 0 402718720 3.9908723831 4.2457532883 6.1096854210 317 12.6400000000 0.0076088384 0.0053681581 0.0076716118 0.0080122422 0.9553380000 0.1115250000 0.0548690000 0.0377900000 0.3706520000 0.3799770000 113920547 0 402718720 3.9905524254 4.2450346947 6.1213402748 318 12.6800000000 0.0076099662 0.0053752078 0.0076716118 0.0079995964 0.5378620000 0.1114430000 0.0548950000 0.0000010000 0.3690970000 0.0019020000 113923323 0 402718720 3.9899132252 4.2445111275 6.1326947212 319 12.7200000000 0.0075600594 0.0053820569 0.0076716118 0.0079870219 0.5822800000 0.1112810000 0.0643570000 0.0374900000 0.3667100000 0.0019130000 113926099 0 402718720 3.9891824722 4.2445712090 6.1427326202 320 12.7600000000 0.0075158817 0.0053887251 0.0076716118 0.0079744997 0.5905030000 0.1112080000 0.1115860000 0.0000010000 0.3652820000 0.0019030000 113928875 0 402718720 3.9879856110 4.2446589470 6.1529641151 321 12.8000000000 0.0074558225 0.0053951646 0.0076716118 0.0079644594 0.9486730000 0.1110940000 0.0667390000 0.0372870000 0.3622690000 0.3707580000 113931651 0 402718720 3.9858410358 4.2435073853 6.1637725830 322 12.8400000000 0.0073753861 0.0054013144 0.0076716118 0.0079542240 0.5302420000 0.1109120000 0.0570910000 0.0000000000 0.3597970000 0.0019080000 113934427 0 402718720 3.9841988087 4.2437758446 6.1732654572 323 12.8800000000 0.0073274393 0.0054072776 0.0076716118 0.0079453862 0.5625990000 0.1106260000 0.0572270000 0.0363660000 0.3559380000 0.0019060000 113937203 0 402718720 3.9822432995 4.2426185608 6.1819972992 324 12.9200000000 0.0072674248 0.0054130188 0.0076716118 0.0079340732 0.5206420000 0.1103420000 0.0544800000 0.0000010000 0.3533770000 0.0019060000 113939979 0 402718720 3.9802594185 4.2419176102 6.1912226677 325 12.9600000000 0.0071599390 0.0054183940 0.0076716118 0.0079220285 0.9166750000 0.1101820000 0.0642360000 0.0355490000 0.3492910000 0.3568820000 113942755 0 402718720 3.9788591862 4.2426443100 6.2003326416 326 13.0000000000 0.0071241981 0.0054236265 0.0076716118 0.0079104252 0.5124060000 0.1096160000 0.0546650000 0.0000010000 0.3456870000 0.0019030000 113945531 0 402718720 3.9769036770 4.2422614098 6.2076044083 327 13.0400000000 0.0071436106 0.0054288864 0.0076716118 0.0078996807 0.5519500000 0.1093660000 0.0641210000 0.0350510000 0.3409620000 0.0019080000 113948307 0 402718720 3.9749703407 4.2426605225 6.2173566818 328 13.0800000000 0.0071440879 0.0054341157 0.0076716118 0.0078887955 0.5004550000 0.1092890000 0.0523570000 0.0000000000 0.3363590000 0.0019000000 113951083 0 402718720 3.9744548798 4.2453594208 6.2239298820 329 13.1200000000 0.0071055158 0.0054391959 0.0076716118 0.0078773605 0.8691090000 0.1091930000 0.0547410000 0.0347360000 0.3314420000 0.3384490000 113953859 0 402718720 3.9728496075 4.2461004257 6.2330112457 330 13.1600000000 0.0070696264 0.0054441366 0.0076716118 0.0078665483 0.4846280000 0.1091300000 0.0454170000 0.0000000000 0.3276380000 0.0018980000 113956635 0 402718720 3.9709458351 4.2463288307 6.2410712242 331 13.2000000000 0.0071229460 0.0054492085 0.0076716118 0.0078550488 0.5241720000 0.1090380000 0.0547500000 0.0341610000 0.3237720000 0.0019030000 113959411 0 402718720 3.9692504406 4.2469468117 6.2511239052 332 13.2400000000 0.0072602420 0.0054546634 0.0076716118 0.0078453327 0.4850120000 0.1089560000 0.0523530000 0.0000010000 0.3212530000 0.0019040000 113962187 0 402718720 3.9675033092 4.2475481033 6.2597165108 333 13.2800000000 0.0072152759 0.0054599506 0.0076716118 0.0078345706 0.8381970000 0.1092400000 0.0547990000 0.0339460000 0.3165580000 0.3231050000 113964963 0 402718720 3.9654014111 4.2477531433 6.2690443993 334 13.3200000000 0.0072395792 0.0054652788 0.0076716118 0.0078233485 0.4885760000 0.1095010000 0.0642300000 0.0000000000 0.3123910000 0.0019050000 113967739 0 402718720 3.9631891251 4.2476739883 6.2770118713 335 13.3600000000 0.0072194412 0.0054705151 0.0076716118 0.0078118109 0.4990640000 0.1097130000 0.0453200000 0.0336310000 0.3079330000 0.0019090000 113970515 0 402718720 3.9611425400 4.2486348152 6.2856078148 336 13.4000000000 0.0072233132 0.0054757318 0.0076716118 0.0078002169 0.4711970000 0.1098710000 0.0547920000 0.0000010000 0.3040660000 0.0019080000 113973291 0 402718720 3.9596958160 4.2505173683 6.2934222221 337 13.4400000000 0.0072197770 0.0054809070 0.0076716118 0.0077988752 0.7929580000 0.1100590000 0.0452370000 0.0332260000 0.2987280000 0.3051400000 113976067 0 402718720 3.9580221176 4.2529125214 6.3008494377 338 13.4800000000 0.0072445720 0.0054861249 0.0076716118 0.0078049631 0.4524800000 0.1104550000 0.0452530000 0.0000010000 0.2943030000 0.0019120000 113978843 0 402718720 3.9562587738 4.2545375824 6.3070497513 339 13.5200000000 0.0072498820 0.0054913277 0.0076716118 0.0078208801 0.4898280000 0.1107110000 0.0546620000 0.0328900000 0.2890800000 0.0019170000 113981619 0 402718720 3.9538569450 4.2545356750 6.3125023842 340 13.5600000000 0.0072549884 0.0054965150 0.0076716118 0.0078173487 0.4536710000 0.1107590000 0.0548170000 0.0000000000 0.2856120000 0.0019160000 113984395 0 402718720 3.9514706135 4.2548875809 6.3176550865 341 13.6000000000 0.0072930930 0.0055017835 0.0076716118 0.0078107062 0.7670620000 0.1109820000 0.0548360000 0.0325770000 0.2809000000 0.2871990000 113987171 0 402718720 3.9493386745 4.2552766800 6.3225054741 342 13.6400000000 0.0072628916 0.0055069330 0.0076716118 0.0078023546 0.4453700000 0.1110430000 0.0547500000 0.0000010000 0.2770830000 0.0019220000 113989947 0 402718720 3.9472227097 4.2555947304 6.3280220032 343 13.6800000000 0.0073302942 0.0055122489 0.0076716118 0.0077913595 0.4710370000 0.1111660000 0.0524790000 0.0322420000 0.2726490000 0.0019290000 113992723 0 402718720 3.9453353882 4.2559194565 6.3327536583 344 13.7200000000 0.0073574288 0.0055176128 0.0076716118 0.0077801410 0.4372680000 0.1113370000 0.0547910000 0.0000010000 0.2686540000 0.0019190000 113995499 0 402718720 3.9442887306 4.2575597763 6.3382897377 345 13.7600000000 0.0073769367 0.0055230021 0.0076716118 0.0077722123 0.7339770000 0.1113520000 0.0569390000 0.0319980000 0.2633460000 0.2697630000 113998275 0 402718720 3.9424145222 4.2574386597 6.3437047005 346 13.8000000000 0.0073661678 0.0055283292 0.0076716118 0.0077664160 0.4275700000 0.1114010000 0.0546350000 0.0000000000 0.2590360000 0.0019220000 114001051 0 402718720 3.9407751560 4.2572927475 6.3486976624 347 13.8400000000 0.0073192627 0.0055334904 0.0076716118 0.0077556474 0.4559980000 0.1113600000 0.0547040000 0.0317510000 0.2556800000 0.0019220000 114003827 0 402718720 3.9384045601 4.2558736801 6.3532967567 348 13.8800000000 0.0072824503 0.0055385161 0.0076716118 0.0077451085 0.4212960000 0.1114830000 0.0547300000 0.0000000000 0.2525790000 0.0019100000 114006603 0 402718720 3.9378387928 4.2580461502 6.3590869904 349 13.9200000000 0.0072682160 0.0055434723 0.0076716118 0.0077421796 0.6900600000 0.1115700000 0.0428210000 0.0309970000 0.2488920000 0.2551950000 114009379 0 402718720 3.9362008572 4.2576818466 6.3647947311 350 13.9600000000 0.0072508007 0.0055483504 0.0076716118 0.0077340781 0.4229620000 0.1115740000 0.0638920000 0.0000010000 0.2450010000 0.0019110000 114012155 0 402718720 3.9341835976 4.2562866211 6.3736209869 351 14.0000000000 0.0071024145 0.0055527779 0.0076716118 0.0077239088 0.4448820000 0.1116670000 0.0573900000 0.0312490000 0.2420660000 0.0019220000 114014931 0 402718720 3.9339320660 4.2568283081 6.3782668114 352 14.0400000000 0.0071056960 0.0055571896 0.0076716118 0.0077156648 0.4096750000 0.1116880000 0.0551190000 0.0000000000 0.2403680000 0.0019130000 114017707 0 402718720 3.9333546162 4.2564220428 6.3830375671 353 14.0800000000 0.0071055046 0.0055615758 0.0076716118 0.0077047411 0.7021130000 0.1116830000 0.0741860000 0.0311080000 0.2393160000 0.2452250000 114020483 0 402718720 3.9330198765 4.2554140091 6.3873314857 354 14.1200000000 0.0071234396 0.0055659878 0.0076716118 0.0076938677 0.4187920000 0.1117740000 0.0670340000 0.0000010000 0.2374630000 0.0019230000 114023259 0 402718720 3.9333472252 4.2559595108 6.3921651840 355 14.1600000000 0.0071409922 0.0055704245 0.0076716118 0.0076833800 0.4359550000 0.1117390000 0.0550760000 0.0310030000 0.2356170000 0.0019230000 114026035 0 402718720 3.9328427315 4.2545428276 6.3968973160 356 14.2000000000 0.0070905704 0.0055746945 0.0076716118 0.0076747996 0.4131150000 0.1117830000 0.0644620000 0.0000010000 0.2343660000 0.0019100000 114028811 0 402718720 3.9331150055 4.2543263435 6.4015493393 357 14.2400000000 0.0070079477 0.0055787092 0.0076716118 0.0076644833 0.6687930000 0.1116800000 0.0551470000 0.0308910000 0.2320870000 0.2383780000 114031587 0 402718720 3.9333965778 4.2547597885 6.4071617126 358 14.2800000000 0.0070295255 0.0055827618 0.0076716118 0.0076545039 0.4000330000 0.1116710000 0.0552390000 0.0000000000 0.2306100000 0.0019110000 114034363 0 402718720 3.9331190586 4.2533850670 6.4125409126 359 14.3200000000 0.0070163021 0.0055867550 0.0076716118 0.0076453217 0.4294200000 0.1117010000 0.0550980000 0.0307850000 0.2293130000 0.0019220000 114037139 0 402718720 3.9324913025 4.2515683174 6.4179816246 360 14.3600000000 0.0069752345 0.0055906118 0.0076716118 0.0076369585 0.4098250000 0.1116970000 0.0670600000 0.0000000000 0.2285580000 0.0019050000 114039915 0 402718720 3.9323208332 4.2502374649 6.4240946770 361 14.4000000000 0.0069827149 0.0055944681 0.0076716118 0.0076335005 0.6610880000 0.1116160000 0.0570550000 0.0305780000 0.2277490000 0.2334840000 114042691 0 402718720 3.9322178364 4.2500553131 6.4305825233 362 14.4400000000 0.0069870846 0.0055983151 0.0076716118 0.0076273462 0.3951210000 0.1115640000 0.0549560000 0.0000010000 0.2260930000 0.0019000000 114045467 0 402718720 3.9322206974 4.2502603531 6.4370903969 363 14.4800000000 0.0069895200 0.0056021476 0.0076716118 0.0076171755 0.4354090000 0.1115330000 0.0669010000 0.0306330000 0.2238300000 0.0019010000 114048243 0 402718720 3.9323735237 4.2511458397 6.4442524910 364 14.5200000000 0.0069873286 0.0056059530 0.0076716118 0.0076075484 0.4099980000 0.1114830000 0.0736200000 0.0000000000 0.2223910000 0.0018940000 114051019 0 402718720 3.9320209026 4.2504782677 6.4514498711 365 14.5600000000 0.0070065614 0.0056097903 0.0076716118 0.0075974306 0.6826440000 0.1114950000 0.0922410000 0.0305540000 0.2208670000 0.2268620000 114053795 0 402718720 3.9314646721 4.2495603561 6.4584536552 366 14.6000000000 0.0070164762 0.0056136337 0.0076716118 0.0075870521 0.3995590000 0.1114010000 0.0661870000 0.0000000000 0.2194740000 0.0018780000 114056571 0 402718720 3.9313764572 4.2504673004 6.4662818909 367 14.6400000000 0.0070866477 0.0056176474 0.0076716118 0.0075768560 0.4258920000 0.1113740000 0.0636700000 0.0305060000 0.2178500000 0.0018740000 114059347 0 402718720 3.9314610958 4.2514333725 6.4735035896 368 14.6800000000 0.0071337856 0.0056217673 0.0076716118 0.0075691478 0.3873650000 0.1112590000 0.0564170000 0.0000010000 0.2172020000 0.0018660000 114062123 0 402718720 3.9312896729 4.2519516945 6.4812493324 369 14.7200000000 0.0071396520 0.0056258808 0.0076716118 0.0075689501 0.6712120000 0.1112610000 0.0904520000 0.0305560000 0.2161940000 0.2221300000 114064899 0 402718720 3.9305160046 4.2516827583 6.4886775017 370 14.7600000000 0.0071661421 0.0056300437 0.0076716118 0.0075670686 0.4039870000 0.1112670000 0.0742330000 0.0000010000 0.2160370000 0.0018310000 114067675 0 402718720 3.9303317070 4.2520518303 6.4966096878 371 14.8000000000 0.0071938280 0.0056342588 0.0076716118 0.0075613718 0.4149440000 0.1112110000 0.0556060000 0.0299770000 0.2156870000 0.0018390000 114070451 0 402718720 3.9303183556 4.2517461777 6.5037484169 372 14.8400000000 0.0072006537 0.0056384695 0.0076716118 0.0075576683 0.4042780000 0.1111570000 0.0736620000 0.0000010000 0.2170090000 0.0018250000 114073227 0 402718720 3.9301118851 4.2512187958 6.5107808113 373 14.8800000000 0.0072096605 0.0056426818 0.0076716118 0.0075583944 0.6299270000 0.1111470000 0.0461070000 0.0300690000 0.2181130000 0.2238530000 114076003 0 402718720 3.9300034046 4.2509779930 6.5180397034 374 14.9200000000 0.0072548008 0.0056469923 0.0076716118 0.0075551244 0.3979400000 0.1111530000 0.0640220000 0.0000000000 0.2203000000 0.0018290000 114078779 0 402718720 3.9298872948 4.2503023148 6.5252346992 375 14.9600000000 0.0072973794 0.0056513933 0.0076716118 0.0075578933 0.4313240000 0.1111190000 0.0638370000 0.0309160000 0.2230420000 0.0017770000 114081555 0 402718720 3.9301769733 4.2499341965 6.5321774483 376 15.0000000000 0.0073219724 0.0056558364 0.0076716118 0.0075574054 0.4257460000 0.1073590000 0.0897350000 0.0000010000 0.2262080000 0.0018130000 114084331 0 402718720 3.9311897755 4.2513003349 6.5395927429 377 15.0400000000 0.0073588272 0.0056603536 0.0076716118 0.0075503318 0.6692920000 0.1110970000 0.0548420000 0.0306310000 0.2331250000 0.2389570000 114087107 0 402718720 3.9335246086 4.2523903847 6.5526857376 378 15.0800000000 0.0074699428 0.0056651408 0.0076716118 0.0075403948 0.4116980000 0.1111130000 0.0614090000 0.0000000000 0.2367240000 0.0018160000 114089883 0 402718720 3.9355649948 4.2536430359 6.5589880943 379 15.1200000000 0.0074569490 0.0056698686 0.0076716118 0.0075304786 0.4383960000 0.1110380000 0.0548070000 0.0314180000 0.2386610000 0.0018260000 114092659 0 402718720 3.9374151230 4.2540721893 6.5646743774 380 15.1600000000 0.0075095776 0.0056747099 0.0076716118 0.0075216952 0.4074140000 0.1110190000 0.0526960000 0.0000000000 0.2412330000 0.0018250000 114095435 0 402718720 3.9402084351 4.2551655769 6.5700998306 381 15.2000000000 0.0075312504 0.0056795827 0.0076716118 0.0075119464 0.7445790000 0.1109590000 0.1091330000 0.0310740000 0.2434330000 0.2493350000 114098211 0 402718720 3.9425907135 4.2561411858 6.5751762390 382 15.2400000000 0.0075565823 0.0056844963 0.0076716118 0.0075032716 0.4100670000 0.1108730000 0.0505730000 0.0000010000 0.2461470000 0.0018330000 114100987 0 402718720 3.9448361397 4.2565035820 6.5799899101 383 15.2800000000 0.0076028970 0.0056895052 0.0076716118 0.0074940688 0.4465880000 0.1108290000 0.0529320000 0.0318080000 0.2485300000 0.0018410000 114103763 0 402718720 3.9475300312 4.2574934959 6.5845694542 384 15.3200000000 0.0076136766 0.0056945161 0.0076716118 0.0074843712 0.4185180000 0.1106640000 0.0530440000 0.0000000000 0.2523210000 0.0018420000 114106539 0 402718720 3.9503481388 4.2581415176 6.5883955956 385 15.3600000000 0.0076913997 0.0056997028 0.0076913997 0.0074756275 0.7137310000 0.1106500000 0.0533430000 0.0321300000 0.2555850000 0.2613750000 114109315 0 402718720 3.9529111385 4.2577886581 6.5909361839 386 15.4000000000 0.0076887608 0.0057048558 0.0076913997 0.0074732398 0.4257050000 0.1105200000 0.0535250000 0.0000010000 0.2591450000 0.0018600000 114112091 0 402718720 3.9559447765 4.2583432198 6.5931248665 387 15.4400000000 0.0077219009 0.0057100678 0.0077219009 0.0074751331 0.4713720000 0.1102850000 0.0630100000 0.0325040000 0.2630410000 0.0018730000 114114867 0 402718720 3.9596540928 4.2604727745 6.5953388214 388 15.4800000000 0.0077043646 0.0057152077 0.0077219009 0.0074661559 0.4359880000 0.1098590000 0.0543040000 0.0000010000 0.2692960000 0.0018740000 114117643 0 402718720 3.9626574516 4.2616281509 6.5963850021 389 15.5200000000 0.0077037797 0.0057203197 0.0077219009 0.0074573498 0.7543380000 0.1095950000 0.0548310000 0.0330920000 0.2748280000 0.2813370000 114120419 0 402718720 3.9652726650 4.2617363930 6.5973877907 390 15.5600000000 0.0076893289 0.0057253685 0.0077219009 0.0074478841 0.4454390000 0.1092790000 0.0526080000 0.0000000000 0.2809900000 0.0019030000 114123195 0 402718720 3.9691407681 4.2647781372 6.5986390114 391 15.6000000000 0.0076362211 0.0057302556 0.0077219009 0.0074552733 0.4856250000 0.1089070000 0.0552720000 0.0333670000 0.2854990000 0.0019170000 114125971 0 402718720 3.9722785950 4.2649888992 6.5999808311 392 15.6400000000 0.0076507074 0.0057351547 0.0077219009 0.0074467059 0.4582520000 0.1089070000 0.0552270000 0.0000010000 0.2915500000 0.0019090000 114128747 0 402718720 3.9751245975 4.2647914886 6.6003823280 393 15.6800000000 0.0075915791 0.0057398784 0.0077219009 0.0074374760 0.8019860000 0.1089360000 0.0551020000 0.0337030000 0.2984360000 0.3051390000 114131523 0 402718720 3.9771935940 4.2632117271 6.6010365486 394 15.7200000000 0.0076372661 0.0057446941 0.0077219009 0.0074293767 0.4638210000 0.1092620000 0.0455300000 0.0000010000 0.3064540000 0.0019090000 114134299 0 402718720 3.9792466164 4.2614560127 6.6020488739 395 15.7600000000 0.0076763853 0.0057495845 0.0077219009 0.0074314712 0.5169990000 0.1097100000 0.0573870000 0.0343230000 0.3129910000 0.0019150000 114137075 0 402718720 3.9825839996 4.2619113922 6.6026477814 396 15.8000000000 0.0076967576 0.0057545016 0.0077219009 0.0074260246 0.4907130000 0.1102930000 0.0573570000 0.0000000000 0.3204820000 0.0019160000 114139851 0 402718720 3.9863576889 4.2621870041 6.6028728485 397 15.8400000000 0.0076615624 0.0057593053 0.0077219009 0.0074289897 0.8654350000 0.1108260000 0.0548810000 0.0349480000 0.3282920000 0.3358240000 114142627 0 402718720 3.9892189503 4.2613611221 6.6028366089 398 15.8800000000 0.0076456224 0.0057640447 0.0077219009 0.0074238757 0.5080320000 0.1111290000 0.0550040000 0.0000000000 0.3393120000 0.0019160000 114145403 0 402718720 3.9921398163 4.2595429420 6.6021556854 399 15.9200000000 0.0076082526 0.0057686668 0.0077219009 0.0074160201 0.5463520000 0.1113860000 0.0548130000 0.0356640000 0.3418970000 0.0019170000 114148179 0 402718720 3.9966585636 4.2611665726 6.6007113457 400 15.9600000000 0.0075803832 0.0057731961 0.0077219009 0.0074089932 0.5178610000 0.1116680000 0.0549840000 0.0000000000 0.3486120000 0.0019170000 114150955 0 402718720 4.0009818077 4.2621736526 6.6008887291 401 16.0000000000 0.0075369016 0.0057775944 0.0077219009 0.0074035873 0.9198170000 0.1118430000 0.0549270000 0.0364230000 0.3538150000 0.3621350000 114153731 0 402718720 4.0053157806 4.2625412941 6.6012811661 402 16.0400000000 0.0075477832 0.0057819978 0.0077219009 0.0073951819 0.5212030000 0.1121010000 0.0454150000 0.0000010000 0.3610950000 0.0019070000 114156507 0 402718720 4.0108489990 4.2631583214 6.6009774208 403 16.0800000000 0.0075775385 0.0057864533 0.0077219009 0.0073897018 0.5734080000 0.1122130000 0.0547510000 0.0385870000 0.3652700000 0.0018950000 114159283 0 402718720 4.0154705048 4.2626533508 6.6022601128 404 16.1200000000 0.0076768277 0.0057911324 0.0077219009 0.0073812103 0.5399590000 0.1123170000 0.0540290000 0.0000010000 0.3710640000 0.0018700000 114162059 0 402718720 4.0204486847 4.2631592751 6.6009840965 405 16.1600000000 0.0078478130 0.0057962106 0.0078478130 0.0073725938 0.9618830000 0.1123650000 0.0444120000 0.0397990000 0.3744620000 0.3901640000 114164835 0 402718720 4.0258936882 4.2636609077 6.6018962860 406 16.2000000000 0.0080615068 0.0058017902 0.0080615068 0.0073639713 0.5382050000 0.1123650000 0.0441000000 0.0000010000 0.3792010000 0.0018450000 114167611 0 402718720 4.0318479538 4.2653541565 6.6040320396 407 16.2400000000 0.0081052268 0.0058074497 0.0081052268 0.0073562295 0.5828050000 0.1123920000 0.0435740000 0.0412870000 0.3830240000 0.0018350000 114170387 0 402718720 4.0370273590 4.2662615776 6.6059355736 408 16.2800000000 0.0081622833 0.0058132214 0.0081622833 0.0073590109 0.5585460000 0.1123820000 0.0543530000 0.0000000000 0.3893000000 0.0018180000 114173163 0 402718720 4.0423288345 4.2668728828 6.6086626053 409 16.3200000000 0.0081172455 0.0058188547 0.0081622833 0.0073621059 1.0232760000 0.1123270000 0.0536340000 0.0430500000 0.3921940000 0.4213780000 114175939 0 402718720 4.0489912033 4.2704200745 6.6114940643 410 16.3600000000 0.0082142381 0.0058246971 0.0082142381 0.0073533563 0.5626200000 0.1123200000 0.0508760000 0.0000010000 0.3969460000 0.0017870000 114178715 0 402718720 4.0551929474 4.2735505104 6.6157202721 411 16.3999999990 0.0082524642 0.0058306041 0.0082524642 0.0073473900 0.6093730000 0.1123520000 0.0503180000 0.0448830000 0.3993410000 0.0017750000 114181491 0 402718720 4.0587258339 4.2723526955 6.6174726486 412 16.4400000000 0.0082214251 0.0058364070 0.0082524642 0.0073633006 0.5704300000 0.1122960000 0.0498800000 0.0000000000 0.4057850000 0.0017720000 114184267 0 402718720 4.0639405251 4.2721977234 6.6239356995 413 16.4800000000 0.0082820775 0.0058423288 0.0082820775 0.0073776586 1.0660430000 0.1122850000 0.0488930000 0.0458970000 0.4098420000 0.4484280000 114187043 0 402718720 4.0702919960 4.2736678123 6.6310172081 414 16.5200000000 0.0083177537 0.0058483080 0.0083177537 0.0073739144 0.5819550000 0.1122650000 0.0515950000 0.0000000000 0.4156260000 0.0017660000 114189819 0 402718720 4.0751252174 4.2716073990 6.6345558167 415 16.5599999990 0.0084180105 0.0058545001 0.0084180105 0.0073886637 0.6318670000 0.1122870000 0.0507380000 0.0472360000 0.4191330000 0.0017670000 114192595 0 402718720 4.0783371925 4.2659091949 6.6401162148 416 16.6000000000 0.0084785866 0.0058608080 0.0084785866 0.0074715267 0.5896630000 0.1122370000 0.0491750000 0.0000000000 0.4257830000 0.0017620000 114195371 0 402718720 4.0846791267 4.2659516335 6.6458349228 417 16.6400000000 0.0085252468 0.0058671975 0.0085252468 0.0075049422 1.1107280000 0.1121110000 0.0507330000 0.0471400000 0.4286320000 0.4714110000 114198147 0 402718720 4.0909976959 4.2676224709 6.6474542618 418 16.6800000000 0.0085992971 0.0058737337 0.0085992971 0.0075096374 0.6009890000 0.1120490000 0.0513040000 0.0000010000 0.4351740000 0.0017590000 114200923 0 402718720 4.0932183266 4.2645206451 6.6467676163 419 16.7199999990 0.0087187840 0.0058805238 0.0087187840 0.0075417492 0.6501670000 0.1118760000 0.0506460000 0.0473430000 0.4378240000 0.0017590000 114203699 0 402718720 4.1010708809 4.2676033974 6.6524934769 420 16.7600000000 0.0087198839 0.0058872841 0.0087198839 0.0075331289 0.6087550000 0.1118210000 0.0512670000 0.0000000000 0.4432030000 0.0017540000 114206475 0 402718720 4.1084218025 4.2703466415 6.6524267197 421 16.8000000000 0.0088062845 0.0058942176 0.0088062845 0.0075443268 1.1456810000 0.1117370000 0.0506110000 0.0476430000 0.4445970000 0.4903840000 114209251 0 402718720 4.1123619080 4.2659120560 6.6533489227 422 16.8400000000 0.0089208828 0.0059013898 0.0089208828 0.0075417779 0.6211530000 0.1116890000 0.0507290000 0.0000000000 0.4562750000 0.0017450000 114212027 0 402718720 4.1212568283 4.2593674660 6.6553716660 423 16.8799999990 0.0088939760 0.0059084645 0.0089208828 0.0075381218 0.6667800000 0.1118140000 0.0474960000 0.0486780000 0.4563390000 0.0017370000 114214803 0 402718720 4.1283140182 4.2582855225 6.6553282738 424 16.9200000000 0.0087348362 0.0059151305 0.0089208828 0.0075297481 0.6259630000 0.1118050000 0.0504900000 0.0000010000 0.4612100000 0.0017360000 114217579 0 402718720 4.1335811615 4.2552814484 6.6530485153 425 16.9600000000 0.0086068809 0.0059214640 0.0089208828 0.0075293087 1.1860420000 0.1118380000 0.0499990000 0.0489260000 0.4609800000 0.5135780000 114220355 0 402718720 4.1412916183 4.2557654381 6.6504025459 426 17.0000000000 0.0086144665 0.0059277856 0.0089208828 0.0075216521 0.6301800000 0.1119470000 0.0504450000 0.0000000000 0.4653430000 0.0017290000 114223131 0 402718720 4.1501703262 4.2558498383 6.6497073174 427 17.0400000000 0.0086122649 0.0059340724 0.0089208828 0.0075197112 0.7029600000 0.1118980000 0.0739900000 0.0491390000 0.4654830000 0.0017290000 114225907 0 402718720 4.1560473442 4.2520780563 6.6452398300 428 17.0800000000 0.0086340914 0.0059403809 0.0089208828 0.0075115171 0.6505130000 0.1119500000 0.0664870000 0.0000010000 0.4696280000 0.0017230000 114228683 0 402718720 4.1657967567 4.2503290176 6.6419210434 429 17.1200000000 0.0084428778 0.0059462142 0.0089208828 0.0075047061 1.2294950000 0.1120650000 0.0737010000 0.0491830000 0.4684950000 0.5253290000 114231459 0 402718720 4.1761436462 4.2491579056 6.6403541565 430 17.1600000000 0.0087436717 0.0059527199 0.0089208828 0.0075022424 0.6684710000 0.1120630000 0.0822190000 0.0000010000 0.4717450000 0.0017170000 114234235 0 402718720 4.1845979691 4.2454924583 6.6335949898 431 17.2000000000 0.0089057405 0.0059595715 0.0089208828 0.0074936139 0.7007000000 0.1121120000 0.0655040000 0.0498290000 0.4708040000 0.0017190000 114237011 0 402718720 4.1941733360 4.2411966324 6.6301770210 432 17.2400000000 0.0090929978 0.0059668248 0.0090929978 0.0074923979 0.6878690000 0.1121740000 0.0976840000 0.0000000000 0.4755660000 0.0017080000 114239787 0 402718720 4.2063255310 4.2399210930 6.6254682541 433 17.2800000000 0.0088450620 0.0059734720 0.0090929978 0.0074852004 1.2351730000 0.1122510000 0.0569580000 0.0495070000 0.4773480000 0.5383760000 114242563 0 402718720 4.2174954414 4.2383737564 6.6198000908 434 17.3200000000 0.0087821800 0.0059799437 0.0090929978 0.0074766285 0.6755540000 0.1121480000 0.0813380000 0.0000000000 0.4796290000 0.0016990000 114245339 0 402718720 4.2272496223 4.2337698936 6.6112780571 435 17.3600000000 0.0087425625 0.0059862945 0.0090929978 0.0074880481 0.7354550000 0.1121870000 0.0885090000 0.0514000000 0.4809160000 0.0016920000 114248115 0 402718720 4.2401709557 4.2329554558 6.6059064865 436 17.4000000000 0.0086943628 0.0059925057 0.0090929978 0.0074932990 0.6629860000 0.1123090000 0.0648550000 0.0000000000 0.4833900000 0.0016840000 114250891 0 402718720 4.2560591698 4.2366790771 6.5988945961 437 17.4400000000 0.0087657049 0.0059988517 0.0090929978 0.0074908281 1.2593730000 0.1122280000 0.0644140000 0.0508310000 0.4817070000 0.5494590000 114253667 0 402718720 4.2734279633 4.2422299385 6.5902833939 438 17.4800000000 0.0087358588 0.0060051005 0.0090929978 0.0075952634 0.6761210000 0.1121620000 0.0799640000 0.0000010000 0.4815670000 0.0016840000 114256443 0 402718720 4.2867851257 4.2434892654 6.5822420120 439 17.5200000000 0.0086009437 0.0060110136 0.0090929978 0.0077365926 0.7339650000 0.1121090000 0.0879920000 0.0507180000 0.4807050000 0.0016920000 114259219 0 402718720 4.2942361832 4.2380166054 6.5713677406 440 17.5600000000 0.0085557913 0.0060167972 0.0090929978 0.0077660468 0.6787510000 0.1121520000 0.0804720000 0.0000010000 0.4836940000 0.0016870000 114261995 0 402718720 4.3002119064 4.2294054031 6.5629191399 441 17.6000000000 0.0086436644 0.0060227538 0.0090929978 0.0077624756 1.3000910000 0.1121540000 0.0957220000 0.0507970000 0.4841380000 0.5565380000 114264771 0 402718720 4.3081212044 4.2225799561 6.5553650856 442 17.6400000000 0.0084955813 0.0060283485 0.0090929978 0.0078219924 0.6745290000 0.1121550000 0.0720970000 0.0000010000 0.4878410000 0.0016820000 114267547 0 402718720 4.3215341568 4.2234730721 6.5462937355 443 17.6800000000 0.0083404388 0.0060335676 0.0090929978 0.0078446314 0.7211070000 0.1121590000 0.0640350000 0.0510310000 0.4914500000 0.0016760000 114270323 0 402718720 4.3469862938 4.2275543213 6.5288252831 444 17.7200000000 0.0079179024 0.0060378116 0.0090929978 0.0078397311 0.6876690000 0.1121060000 0.0799140000 0.0000010000 0.4932180000 0.0016750000 114273099 0 402718720 4.3558945656 4.2267994881 6.5169577599 445 17.7600000000 0.0079211891 0.0060420439 0.0090929978 0.0078358971 1.2862510000 0.1121850000 0.0563230000 0.0513890000 0.4935780000 0.5720210000 114275875 0 402718720 4.3660578728 4.2239761353 6.5088543892 446 17.8000000000 0.0079909796 0.0060464137 0.0090929978 0.0078271042 0.7055200000 0.1121070000 0.0955140000 0.0000000000 0.4954680000 0.0016710000 114278651 0 402718720 4.3761582375 4.2241683006 6.4997229576 447 17.8400000000 0.0077455477 0.0060502149 0.0090929978 0.0078227240 0.7545270000 0.1120960000 0.0930400000 0.0516130000 0.4953470000 0.0016680000 114281427 0 402718720 4.3836579323 4.2211604118 6.4918913841 448 17.8800000000 0.0078992443 0.0060543422 0.0090929978 0.0078140436 0.6613700000 0.1121120000 0.0482010000 0.0000010000 0.4986370000 0.0016630000 114284203 0 402718720 4.3914852142 4.2192091942 6.4844436646 449 17.9200000000 0.0079803923 0.0060586319 0.0090929978 0.0078055418 1.3431720000 0.1121100000 0.0942280000 0.0518100000 0.4998130000 0.5844470000 114286979 0 402718720 4.3996129036 4.2173681259 6.4764127731 450 17.9600000000 0.0079378029 0.0060628078 0.0090929978 0.0077980658 0.7129600000 0.1120810000 0.0936990000 0.0000010000 0.5047670000 0.0016520000 114289755 0 402718720 4.4062395096 4.2131748199 6.4706416130 451 18.0000000000 0.0077359020 0.0060665176 0.0090929978 0.0078013371 0.7646440000 0.1120840000 0.0930910000 0.0523900000 0.5046610000 0.0016460000 114292531 0 402718720 4.4154477119 4.2127170563 6.4646935463 452 18.0400000000 0.0078838514 0.0060705382 0.0090929978 0.0077952878 0.7008630000 0.1121020000 0.0780710000 0.0000000000 0.5082750000 0.0016430000 114295307 0 402718720 4.4255399704 4.2128300667 6.4581322670 453 18.0800000000 0.0078459280 0.0060744574 0.0090929978 0.0077866681 1.3450550000 0.1121130000 0.0699120000 0.0524520000 0.5089840000 0.6008290000 114298083 0 402718720 4.4330358505 4.2095031738 6.4515299797 454 18.1200000000 0.0077385725 0.0060781228 0.0090929978 0.0077858799 0.7109440000 0.1121020000 0.0849020000 0.0000010000 0.5115300000 0.0016410000 114300859 0 402718720 4.4429087639 4.2087130547 6.4459066391 455 18.1600000000 0.0076996111 0.0060816866 0.0090929978 0.0077785163 0.7710170000 0.1121050000 0.0921840000 0.0528870000 0.5114300000 0.0016340000 114303635 0 402718720 4.4531464577 4.2077465057 6.4406499863 456 18.2000000000 0.0077968026 0.0060854478 0.0090929978 0.0077715822 0.6762210000 0.1121840000 0.0472070000 0.0000010000 0.5144110000 0.0016340000 114306411 0 402718720 4.4618935585 4.2045965195 6.4341268539 457 18.2400000000 0.0077284165 0.0060890429 0.0090929978 0.0077726860 1.3667820000 0.1122430000 0.0767420000 0.0521600000 0.5159490000 0.6089200000 114309187 0 402718720 4.4709453583 4.2017774582 6.4291400909 458 18.2800000000 0.0077193514 0.0060926025 0.0090929978 0.0077872168 0.7237260000 0.1122630000 0.0918480000 0.0000000000 0.5172160000 0.0016260000 114311963 0 402718720 4.4827098846 4.2030224800 6.4261960983 459 18.3200000000 0.0079262061 0.0060965973 0.0090929978 0.0077807133 0.7774540000 0.1123340000 0.0917540000 0.0531390000 0.5178080000 0.0016300000 114314739 0 402718720 4.4961342812 4.2054147720 6.4199547768 460 18.3600000000 0.0076763872 0.0061000316 0.0090929978 0.0077804978 0.7034280000 0.1123160000 0.0692540000 0.0000010000 0.5194400000 0.0016280000 114317515 0 402718720 4.5040698051 4.2014307976 6.4161076546 461 18.4000000000 0.0076082721 0.0061033033 0.0090929978 0.0077730218 1.3718980000 0.1124340000 0.0690140000 0.0530510000 0.5202560000 0.6163630000 114320291 0 402718720 4.5151848793 4.1995601654 6.4131417274 462 18.4400000000 0.0075724414 0.0061064832 0.0090929978 0.0077656458 0.6983700000 0.1124250000 0.0615070000 0.0000010000 0.5220230000 0.0016280000 114323067 0 402718720 4.5263571739 4.2004337311 6.4074263573 463 18.4800000000 0.0075631151 0.0061096293 0.0090929978 0.0077599577 0.7594940000 0.1124460000 0.0687600000 0.0532010000 0.5226530000 0.0016350000 114325843 0 402718720 4.5355863571 4.1984014511 6.4012360573 464 18.5200000000 0.0076048984 0.0061128519 0.0090929978 0.0077536864 0.7093590000 0.1124710000 0.0693280000 0.0000010000 0.5251300000 0.0016370000 114328619 0 402718720 4.5434427261 4.1948685646 6.3982567787 465 18.5600000000 0.0076133981 0.0061160789 0.0090929978 0.0077495474 1.3618200000 0.1125240000 0.0464850000 0.0536000000 0.5258010000 0.6226200000 114331395 0 402718720 4.5513887405 4.1907844543 6.3951778412 466 18.6000000000 0.0074353274 0.0061189099 0.0090929978 0.0077661170 0.6959960000 0.1125210000 0.0466850000 0.0000010000 0.5337230000 0.0021690000 114334171 0 402718720 4.5629982948 4.1917505264 6.3920536041 467 18.6400000000 0.0072897612 0.0061214170 0.0090929978 0.0077612576 0.7906490000 0.1453790000 0.0587370000 0.0542200000 0.5298700000 0.0016340000 114336947 0 402718720 4.5739493370 4.1901116371 6.3893938065 468 18.6800000000 0.0074105239 0.0061241715 0.0090929978 0.0077628692 0.7255530000 0.1126000000 0.0756810000 0.0000000000 0.5348470000 0.0016230000 114339723 0 402718720 4.5840463638 4.1866407394 6.3885984421 469 18.7200000000 0.0073909136 0.0061268725 0.0090929978 0.0077849567 1.3983130000 0.1126340000 0.0600940000 0.0550490000 0.5344370000 0.6353050000 114342499 0 402718720 4.5933551788 4.1851038933 6.3872776031 470 18.7600000000 0.0074187927 0.0061296213 0.0090929978 0.0078035242 0.7004860000 0.1126610000 0.0457160000 0.0000010000 0.5396920000 0.0016280000 114345275 0 402718720 4.6015200615 4.1817765236 6.3868007660 471 18.8000000000 0.0073789097 0.0061322737 0.0090929978 0.0078552428 0.7699090000 0.1126110000 0.0595800000 0.0556710000 0.5396130000 0.0016400000 114348051 0 402718720 4.6127567291 4.1800146103 6.3846931458 472 18.8400000000 0.0073489645 0.0061348514 0.0090929978 0.0078988928 0.7282310000 0.1125260000 0.0679670000 0.0000010000 0.5453320000 0.0016050000 114350827 0 402718720 4.6235008240 4.1802945137 6.3816909790 473 18.8800000000 0.0074281697 0.0061375857 0.0090929978 0.0079077668 1.3955100000 0.1086290000 0.0450900000 0.0560990000 0.5440570000 0.6408430000 114353603 0 402718720 4.6332430840 4.1803550720 6.3776397705 474 18.9200000000 0.0073797423 0.0061402063 0.0090929978 0.0079053942 0.7159950000 0.1122100000 0.0538400000 0.0000010000 0.5474810000 0.0016550000 114356379 0 402718720 4.6385388374 4.1789021492 6.3700861931 475 18.9600000000 0.0074063484 0.0061428718 0.0090929978 0.0079041031 0.7717770000 0.1120240000 0.0535390000 0.0567920000 0.5469520000 0.0016630000 114359155 0 402718720 4.6473050117 4.1769609451 6.3679347038 476 19.0000000000 0.0074404050 0.0061455978 0.0090929978 0.0079099658 0.7175040000 0.1116540000 0.0521630000 0.0000010000 0.5512100000 0.0016730000 114361931 0 402718720 4.6566410065 4.1767654419 6.3652024269 477 19.0400000000 0.0073759733 0.0061481772 0.0090929978 0.0079080738 1.4183380000 0.1115620000 0.0540050000 0.0574810000 0.5509760000 0.6435170000 114364707 0 402718720 4.6649236679 4.1767821312 6.3572793007 478 19.0800000000 0.0074607139 0.0061509230 0.0090929978 0.0079020333 0.7313210000 0.1115440000 0.0626340000 0.0000010000 0.5545790000 0.0017300000 114367483 0 402718720 4.6777582169 4.1761469841 6.3603734970 479 19.1200000000 0.0075112763 0.0061537630 0.0090929978 0.0078949583 0.7738390000 0.1115120000 0.0477800000 0.0580820000 0.5538960000 0.0017560000 114370259 0 402718720 4.6850137711 4.1733994484 6.3590998650 480 19.1600000000 0.0076212673 0.0061568203 0.0090929978 0.0079001852 0.7283560000 0.1115980000 0.0568590000 0.0000010000 0.5573200000 0.0017670000 114373035 0 402718720 4.6954879761 4.1714663506 6.3609676361 481 19.2000000000 0.0079555828 0.0061605600 0.0090929978 0.0079157744 1.4256370000 0.1115040000 0.0571150000 0.0587170000 0.5554350000 0.6420570000 114375811 0 402718720 4.7034287453 4.1736955643 6.3550872803 482 19.2400000000 0.0079198526 0.0061642100 0.0090929978 0.0079080904 0.7707380000 0.1117280000 0.0993790000 0.0000000000 0.5570010000 0.0018100000 114378587 0 402718720 4.7132158279 4.1732730865 6.3562746048 483 19.2800000000 0.0077997986 0.0061675963 0.0090929978 0.0079001217 0.7965930000 0.1118840000 0.0670500000 0.0592430000 0.5557730000 0.0018210000 114381363 0 402718720 4.7218308449 4.1709127426 6.3550539017 484 19.3200000000 0.0080010314 0.0061713844 0.0090929978 0.0078967479 0.7744470000 0.1119590000 0.1021420000 0.0000010000 0.5577050000 0.0018220000 114384139 0 402718720 4.7270078659 4.1708059311 6.3505158424 485 19.3600000000 0.0081781829 0.0061755221 0.0090929978 0.0078938446 1.4402080000 0.1120570000 0.0747630000 0.0594510000 0.5546490000 0.6384760000 114386915 0 402718720 4.7366366386 4.1739473343 6.3461055756 486 19.4000000000 0.0079388693 0.0061791504 0.0090929978 0.0078966666 0.7293010000 0.1119090000 0.0597290000 0.0000010000 0.5550240000 0.0018080000 114389691 0 402718720 4.7453866005 4.1768498421 6.3437261581 487 19.4400000000 0.0080872141 0.0061830684 0.0090929978 0.0079389193 0.7828870000 0.1118910000 0.0577540000 0.0594010000 0.5511990000 0.0018070000 114392467 0 402718720 4.7514519691 4.1737365723 6.3408346176 488 19.4800000000 0.0080310423 0.0061868552 0.0090929978 0.0079382771 0.7267400000 0.1120160000 0.0604210000 0.0000000000 0.5516660000 0.0018110000 114395243 0 402718720 4.7512931824 4.1710987091 6.3332810402 489 19.5200000000 0.0080556162 0.0061906768 0.0090929978 0.0079302995 1.4042140000 0.1121330000 0.0516470000 0.0598810000 0.5489580000 0.6307710000 114398019 0 402718720 4.7562885284 4.1705732346 6.3289628029 490 19.5600000000 0.0080314344 0.0061944334 0.0090929978 0.0079224742 0.7174580000 0.1123460000 0.0515550000 0.0000010000 0.5509310000 0.0018010000 114400795 0 402718720 4.7603421211 4.1698455811 6.3206729889 491 19.6000000000 0.0080081709 0.0061981274 0.0090929978 0.0079146129 0.7967500000 0.1123850000 0.0758130000 0.0599960000 0.5459180000 0.0017960000 114403571 0 402718720 4.7661290169 4.1690607071 6.3163204193 492 19.6400000000 0.0081586130 0.0062021121 0.0090929978 0.0079066465 0.7132370000 0.1124260000 0.0513790000 0.0000000000 0.5468080000 0.0017950000 114406347 0 402718720 4.7664828300 4.1695656776 6.3046636581 493 19.6800000000 0.0080960235 0.0062059537 0.0090929978 0.0079039345 1.3935190000 0.1125900000 0.0595720000 0.0598500000 0.5407910000 0.6198810000 114409123 0 402718720 4.7685031891 4.1687369347 6.2936515808 494 19.7200000000 0.0079585612 0.0062095015 0.0090929978 0.0079053513 0.7178390000 0.1127850000 0.0599590000 0.0000000000 0.5424620000 0.0017870000 114411899 0 402718720 4.7698230743 4.1636896133 6.2864122391 495 19.7600000000 0.0079884427 0.0062130953 0.0090929978 0.0078987326 0.7716570000 0.1128750000 0.0597170000 0.0596230000 0.5368210000 0.0017880000 114414675 0 402718720 4.7696614265 4.1607551575 6.2758126259 496 19.8000000000 0.0080360500 0.0062167707 0.0090929978 0.0078948404 0.7140360000 0.1129110000 0.0603700000 0.0000000000 0.5381290000 0.0017840000 114417451 0 402718720 4.7683358192 4.1609411240 6.2685709000 497 19.8400000000 0.0079805935 0.0062203196 0.0090929978 0.0078873432 1.3660120000 0.1130280000 0.0515070000 0.0597230000 0.5331530000 0.6077590000 114420227 0 402718720 4.7716779709 4.1578383446 6.2622852325 498 19.8800000000 0.0080197146 0.0062239328 0.0090929978 0.0078806321 0.6994260000 0.1129930000 0.0495010000 0.0000000000 0.5342970000 0.0017830000 114423003 0 402718720 4.7699561119 4.1567568779 6.2513217926 499 19.9200000000 0.0081107682 0.0062277141 0.0090929978 0.0078727923 0.7712190000 0.1130740000 0.0659800000 0.0596890000 0.5298440000 0.0017790000 114425779 0 402718720 4.7709164619 4.1555504799 6.2447481155 500 19.9600000000 0.0081130061 0.0062314847 0.0090929978 0.0078651440 0.7065260000 0.1131050000 0.0599140000 0.0000000000 0.5308830000 0.0017740000 114428555 0 402718720 4.7707295418 4.1541757584 6.2344417572 501 20.0000000000 0.0081946310 0.0062354031 0.0090929978 0.0078580068 1.3582270000 0.1131030000 0.0658450000 0.0595770000 0.5249080000 0.5939480000 114431331 0 402718720 4.7716569901 4.1525135040 6.2238039970 502 20.0400000000 0.0081342179 0.0062391856 0.0090929978 0.0078502660 0.6915620000 0.1130330000 0.0494460000 0.0000010000 0.5264500000 0.0017720000 114434107 0 402718720 4.7749843597 4.1501336098 6.2177968025 503 20.0800000000 0.0080355648 0.0062427569 0.0090929978 0.0078435640 0.7651660000 0.1130320000 0.0682250000 0.0594440000 0.5218370000 0.0017710000 114436883 0 402718720 4.7770185471 4.1501655579 6.2049918175 504 20.1200000000 0.0081957243 0.0062466319 0.0090929978 0.0078366977 0.7243430000 0.1130900000 0.0854940000 0.0000010000 0.5231390000 0.0017680000 114439659 0 402718720 4.7757124901 4.1470875740 6.1944208145 505 20.1600000000 0.0081573464 0.0062504155 0.0090929978 0.0078323875 1.3549070000 0.1129870000 0.0767440000 0.0593710000 0.5194510000 0.5854970000 114442435 0 402718720 4.7716903687 4.1452107430 6.1814904213 506 20.2000000000 0.0083629312 0.0062545904 0.0090929978 0.0078290578 0.6972260000 0.1130020000 0.0604160000 0.0000000000 0.5211790000 0.0017740000 114445211 0 402718720 4.7709670067 4.1480026245 6.1725091934 507 20.2400000000 0.0083948746 0.0062588119 0.0090929978 0.0078276670 0.7593200000 0.1129870000 0.0683350000 0.0591720000 0.5161760000 0.0017780000 114447987 0 402718720 4.7711524963 4.1490216255 6.1611690521 508 20.2800000000 0.0083061326 0.0062628420 0.0090929978 0.0078329535 0.6905690000 0.1129320000 0.0581430000 0.0000010000 0.5168430000 0.0017760000 114450763 0 402718720 4.7637953758 4.1464400291 6.1515974998 509 20.3200000000 0.0083045401 0.0062668532 0.0090929978 0.0078268738 1.3234090000 0.1128290000 0.0603850000 0.0588410000 0.5133550000 0.5771360000 114453539 0 402718720 4.7674899101 4.1452460289 6.1420102119 510 20.3600000000 0.0083767986 0.0062709904 0.0090929978 0.0078194753 0.6905430000 0.1128850000 0.0605250000 0.0000010000 0.5144750000 0.0017790000 114456315 0 402718720 4.7718486786 4.1464314461 6.1271328926 511 20.4000000000 0.0083776349 0.0062751130 0.0090929978 0.0078129500 0.7441760000 0.1128150000 0.0603680000 0.0586210000 0.5097040000 0.0017820000 114459091 0 402718720 4.7747678757 4.1503343582 6.1148076057 512 20.4400000000 0.0084094116 0.0062792815 0.0090929978 0.0078243163 0.6944720000 0.1128140000 0.0688280000 0.0000000000 0.5101660000 0.0017890000 114461867 0 402718720 4.7714276314 4.1509490013 6.1018805504 513 20.4800000000 0.0085161543 0.0062836419 0.0090929978 0.0078309814 1.2979600000 0.1127550000 0.0518650000 0.0580960000 0.5066640000 0.5676990000 114513795 0 402718720 4.7761340141 4.1494536400 6.0906438828 514 20.5200000000 0.0085583730 0.0062880674 0.0090929978 0.0078250880 0.6830260000 0.1126970000 0.0604980000 0.0000010000 0.5071480000 0.0017980000 114618971 0 402718720 4.7775826454 4.1509900093 6.0790534019 515 20.5600000000 0.0085863126 0.0062925301 0.0090929978 0.0078248935 0.7353970000 0.1127150000 0.0602970000 0.0577140000 0.5019660000 0.0018040000 114621747 0 402718720 4.7828221321 4.1531600952 6.0666799545 516 20.6000000000 0.0086376788 0.0062970749 0.0090929978 0.0078347892 0.6788990000 0.1125780000 0.0604450000 0.0000010000 0.5031920000 0.0017940000 114624523 0 402718720 4.7857370377 4.1523613930 6.0531039238 517 20.6400000000 0.0086757382 0.0063016758 0.0090929978 0.0078380366 1.2905830000 0.1124560000 0.0600470000 0.0576320000 0.4988710000 0.5606880000 114627299 0 402718720 4.7814764977 4.1500391960 6.0542597771 518 20.6800000000 0.0085777128 0.0063060697 0.0090929978 0.0078307237 0.6846220000 0.1125180000 0.0692920000 0.0000000000 0.5001310000 0.0017900000 114630075 0 402718720 4.7957053185 4.1501960754 6.0334496498 519 20.7200000000 0.0086723389 0.0063106290 0.0090929978 0.0078243874 0.7178870000 0.1123910000 0.0495450000 0.0577340000 0.4955250000 0.0017890000 114632851 0 402718720 4.7866344452 4.1529788971 6.0375576019 520 20.7600000000 0.0087109869 0.0063152451 0.0090929978 0.0078287287 0.6810890000 0.1124240000 0.0687750000 0.0000010000 0.4972070000 0.0017890000 114635627 0 402718720 4.7795882225 4.1547780037 6.0377321243 521 20.8000000000 0.0086222896 0.0063196732 0.0090929978 0.0078426610 1.2763370000 0.1123200000 0.0601180000 0.0576040000 0.4917830000 0.5536240000 114638403 0 402718720 4.7772850990 4.1525940895 6.0301485062 522 20.8400000000 0.0086988332 0.0063242310 0.0090929978 0.0078396567 0.6609100000 0.1122410000 0.0521390000 0.0000010000 0.4938320000 0.0017840000 114641179 0 402718720 4.7789225578 4.1489768028 6.0235829353 523 20.8800000000 0.0086330110 0.0063286454 0.0090929978 0.0078327614 0.7236640000 0.1123300000 0.0604370000 0.0575370000 0.4906720000 0.0017810000 114643955 0 402718720 4.7685317993 4.1477470398 6.0293393135 524 20.9200000000 0.0086885160 0.0063331490 0.0090929978 0.0078286982 0.6677100000 0.1123120000 0.0609750000 0.0000010000 0.4917390000 0.0017760000 114646731 0 402718720 4.7853069305 4.1480684280 6.0077776909 525 20.9600000000 0.0085994983 0.0063374659 0.0090929978 0.0078212480 1.2617180000 0.1123160000 0.0518930000 0.0573600000 0.4885350000 0.5507220000 114649507 0 402718720 4.7850847244 4.1473231316 6.0028038025 526 21.0000000000 0.0085222190 0.0063416194 0.0090929978 0.0078142329 0.6637190000 0.1123350000 0.0585210000 0.0000010000 0.4901830000 0.0017730000 114652283 0 402718720 4.7930755615 4.1437692642 5.9898152351 527 21.0400000000 0.0085464902 0.0063458032 0.0090929978 0.0078147313 0.7291790000 0.1123980000 0.0688230000 0.0572410000 0.4880670000 0.0017360000 114655059 0 402718720 4.7941260338 4.1442828178 5.9807057381 528 21.0800000000 0.0086588776 0.0063501840 0.0090929978 0.0078075216 0.6719980000 0.1100760000 0.0690390000 0.0000010000 0.4901880000 0.0017770000 114657835 0 402718720 4.7967929840 4.1438317299 5.9759039879 529 21.1200000000 0.0085556414 0.0063543531 0.0090929978 0.0078010638 1.2629660000 0.1124410000 0.0604360000 0.0570730000 0.4859310000 0.5461480000 114660611 0 402718720 4.8099975586 4.1417102814 5.9553442001 530 21.1600000000 0.0085447952 0.0063584860 0.0090929978 0.0077963995 0.6855750000 0.1173450000 0.0775570000 0.0000010000 0.4879780000 0.0017810000 114663387 0 402718720 4.8066258430 4.1419329643 5.9535622597 531 21.2000000000 0.0086331312 0.0063627697 0.0090929978 0.0077897553 0.7161010000 0.1124800000 0.0605250000 0.0570180000 0.4833690000 0.0017800000 114666163 0 402718720 4.8146767616 4.1408295631 5.9383897781 532 21.2400000000 0.0086334758 0.0063670380 0.0090929978 0.0077836785 0.6700640000 0.1124800000 0.0692030000 0.0000000000 0.4856870000 0.0017770000 114668939 0 402718720 4.8151369095 4.1394829750 5.9303216934 533 21.2800000000 0.0085800970 0.0063711901 0.0090929978 0.0077776293 1.2558170000 0.1125210000 0.0604370000 0.0570040000 0.4823150000 0.5426300000 114671715 0 402718720 4.8137030602 4.1384258270 5.9252443314 534 21.3200000000 0.0086919023 0.0063755360 0.0090929978 0.0077728442 0.6603900000 0.1125150000 0.0608100000 0.0000000000 0.4843630000 0.0017760000 114674491 0 402718720 4.8210268021 4.1368756294 5.9098916054 535 21.3600000000 0.0086698867 0.0063798245 0.0090929978 0.0077687336 0.7129850000 0.1125170000 0.0605960000 0.0567410000 0.4804170000 0.0017870000 114677267 0 402718720 4.8266716003 4.1390194893 5.8950157166 536 21.4000000000 0.0086471075 0.0063840545 0.0090929978 0.0077623959 0.6578380000 0.1125160000 0.0606520000 0.0000010000 0.4819490000 0.0017860000 114680043 0 402718720 4.8242645264 4.1381802559 5.8911380768 537 21.4400000000 0.0089005260 0.0063887407 0.0090929978 0.0077552591 1.2550690000 0.1125060000 0.0690630000 0.0561700000 0.4788820000 0.5375230000 114682819 0 402718720 4.8320388794 4.1367235184 5.8738913536 538 21.4800000000 0.0089035202 0.0063934150 0.0090929978 0.0077482594 0.6651450000 0.1124930000 0.0692420000 0.0000010000 0.4806850000 0.0017920000 114685595 0 402718720 4.8321499825 4.1366648674 5.8656511307 539 21.5200000000 0.0090734763 0.0063983873 0.0090929978 0.0077411912 0.7511870000 0.1124770000 0.1030350000 0.0561510000 0.4767800000 0.0017950000 114688371 0 402718720 4.8304452896 4.1363554001 5.8576750755 540 21.5600000000 0.0093104737 0.0064037800 0.0093104737 0.0077351144 0.6627410000 0.1124870000 0.0695290000 0.0000010000 0.4779990000 0.0017920000 114691147 0 402718720 4.8335738182 4.1376209259 5.8430185318 541 21.6000000000 0.0091404459 0.0064088385 0.0093104737 0.0077283687 1.2292160000 0.1124590000 0.0521260000 0.0560840000 0.4746220000 0.5329940000 114693923 0 402718720 4.8341526985 4.1392879486 5.8337330818 542 21.6400000000 0.0090435296 0.0064136996 0.0093104737 0.0077260559 0.6600090000 0.1124990000 0.0693180000 0.0000010000 0.4754540000 0.0017990000 114696699 0 402718720 4.8365230560 4.1373076439 5.8208861351 543 21.6800000000 0.0090612285 0.0064185753 0.0093104737 0.0077190379 0.7050370000 0.1125480000 0.0608270000 0.0555970000 0.4733200000 0.0018050000 114699475 0 402718720 4.8374691010 4.1347441673 5.8156094551 544 21.7200000000 0.0091494843 0.0064235954 0.0093104737 0.0077187985 0.6508650000 0.1125420000 0.0613480000 0.0000000000 0.4742280000 0.0018060000 114702251 0 402718720 4.8380527496 4.1355752945 5.8053908348 545 21.7600000000 0.0093205879 0.0064289110 0.0093205879 0.0077153508 1.2414090000 0.1125630000 0.0699430000 0.0552260000 0.4730700000 0.5296800000 114705027 0 402718720 4.8408746719 4.1341834068 5.7932701111 546 21.8000000000 0.0093672434 0.0064342925 0.0093672434 0.0077197668 0.6509990000 0.1125400000 0.0614550000 0.0000010000 0.4742460000 0.0018180000 114707803 0 402718720 4.8423585892 4.1348471642 5.7866020203 547 21.8400000000 0.0095091499 0.0064399138 0.0095091499 0.0077177903 0.7039660000 0.1125880000 0.0614280000 0.0553430000 0.4718340000 0.0018260000 114710579 0 402718720 4.8443841934 4.1367683411 5.7748155594 548 21.8800000000 0.0095082279 0.0064455130 0.0095091499 0.0077108919 0.6588220000 0.1125980000 0.0700100000 0.0000000000 0.4734540000 0.0018150000 114713355 0 402718720 4.8410840034 4.1370549202 5.7714791298 549 21.9200000000 0.0091473144 0.0064504343 0.0095091499 0.0077043158 1.2286110000 0.1126720000 0.0611690000 0.0553990000 0.4711770000 0.5272480000 114716131 0 402718720 4.8421788216 4.1360764503 5.7651500702 550 21.9600000000 0.0092324866 0.0064554925 0.0095091499 0.0076979283 0.6415550000 0.1125430000 0.0524080000 0.0000000000 0.4738390000 0.0018170000 114718907 0 402718720 4.8417248726 4.1383628845 5.7583198547 551 22.0000000000 0.0093199397 0.0064606912 0.0095091499 0.0076922633 0.7098230000 0.1125590000 0.0696580000 0.0548730000 0.4699580000 0.0018220000 114721683 0 402718720 4.8422098160 4.1383743286 5.7502875328 552 22.0400000000 0.0096580191 0.0064664834 0.0096580191 0.0076854886 0.6403910000 0.1125810000 0.0527300000 0.0000000000 0.4722940000 0.0018280000 114724459 0 402718720 4.8455185890 4.1399707794 5.7419290543 553 22.0800000000 0.0097241309 0.0064723743 0.0097241309 0.0076819902 1.2296360000 0.1125180000 0.0693230000 0.0551340000 0.4682800000 0.5234310000 114727235 0 402718720 4.8441090584 4.1400346756 5.7395310402 554 22.1200000000 0.0095126722 0.0064778622 0.0097241309 0.0076760348 0.6473440000 0.1124600000 0.0612670000 0.0000010000 0.4708360000 0.0018200000 114730011 0 402718720 4.8444814682 4.1382026672 5.7326364517 555 22.1600000000 0.0094931796 0.0064832952 0.0097241309 0.0076697099 0.6988890000 0.1123990000 0.0609870000 0.0550340000 0.4676740000 0.0018250000 114732787 0 402718720 4.8452095985 4.1407437325 5.7245163918 556 22.2000000000 0.0099357562 0.0064895047 0.0099357562 0.0076659708 0.6446680000 0.1124020000 0.0611850000 0.0000010000 0.4682950000 0.0018220000 114735563 0 402718720 4.8450446129 4.1436285973 5.7156705856 557 22.2400000000 0.0100850333 0.0064959598 0.0100850333 0.0076735290 1.2025420000 0.1123500000 0.0501690000 0.0547280000 0.4654920000 0.5188390000 114738339 0 402718720 4.8445754051 4.1410117149 5.7114586830 558 22.2800000000 0.0101991929 0.0065025965 0.0101991929 0.0076667841 0.6352380000 0.1123310000 0.0526100000 0.0000010000 0.4675060000 0.0018240000 114741115 0 402718720 4.8425407410 4.1385340691 5.7054066658 559 22.3200000000 0.0100368010 0.0065089188 0.0101991929 0.0076620588 0.6856010000 0.1122500000 0.0503660000 0.0549270000 0.4652610000 0.0018270000 114743891 0 402718720 4.8420143127 4.1408100128 5.7001476288 560 22.3600000000 0.0102319950 0.0065155672 0.0102319950 0.0076564320 0.6357310000 0.1121900000 0.0526700000 0.0000000000 0.4680770000 0.0018290000 114746667 0 402718720 4.8407635689 4.1408810616 5.6967220306 561 22.4000000000 0.0103534237 0.0065224083 0.0103534237 0.0076505921 1.2017030000 0.1121490000 0.0524540000 0.0547940000 0.4644840000 0.5168520000 114749443 0 402718720 4.8441815376 4.1398978233 5.6883001328 562 22.4400000000 0.0108382627 0.0065300877 0.0108382627 0.0076439892 0.6410630000 0.1120930000 0.0586990000 0.0000010000 0.4674570000 0.0018330000 114752219 0 402718720 4.8427109718 4.1416430473 5.6850223541 563 22.4800000000 0.0109629836 0.0065379614 0.0109629836 0.0076396485 0.6909140000 0.1121250000 0.0587500000 0.0541450000 0.4630840000 0.0018300000 114754995 0 402718720 4.8449020386 4.1417393684 5.6756873131 564 22.5200000000 0.0108445287 0.0065455972 0.0109629836 0.0076363787 0.6306600000 0.1120370000 0.0505430000 0.0000010000 0.4652720000 0.0018280000 114757771 0 402718720 4.8451189995 4.1396098137 5.6699748039 565 22.5600000000 0.0108036287 0.0065531335 0.0109629836 0.0076297081 1.1874470000 0.1120440000 0.0526920000 0.0545250000 0.4587150000 0.5084940000 114760547 0 402718720 4.8484692574 4.1370229721 5.6585321426 566 22.6000000000 0.0110747162 0.0065611222 0.0110747162 0.0076245651 0.6788560000 0.1120410000 0.1026650000 0.0000010000 0.4613430000 0.0018370000 114763323 0 402718720 4.8492903709 4.1363368034 5.6516833305 567 22.6400000000 0.0110513447 0.0065690415 0.0110747162 0.0076186431 0.6755120000 0.1120060000 0.0528820000 0.0531200000 0.4546680000 0.0018470000 114766099 0 402718720 4.8506536484 4.1357679367 5.6452822685 568 22.6800000000 0.0112534640 0.0065772887 0.0112534640 0.0076122088 0.6426630000 0.1119630000 0.0709420000 0.0000000000 0.4569290000 0.0018490000 114768875 0 402718720 4.8529238701 4.1337819099 5.6363520622 569 22.7200000000 0.0115294559 0.0065859920 0.0115294559 0.0076078062 1.1712950000 0.1119590000 0.0597820000 0.0530050000 0.4504840000 0.4950790000 114771651 0 402718720 4.8550591469 4.1323843002 5.6257352829 570 22.7600000000 0.0117336418 0.0065950229 0.0117336418 0.0076041415 0.6200920000 0.1119170000 0.0538150000 0.0000000000 0.4515110000 0.0018560000 114774427 0 402718720 4.8539633751 4.1351041794 5.6158213615 571 22.8000000000 0.0117786676 0.0066041011 0.0117786676 0.0075989401 0.6754450000 0.1119610000 0.0624620000 0.0523650000 0.4458100000 0.0018550000 114777203 0 402718720 4.8526873589 4.1364340782 5.6073336601 572 22.8400000000 0.0119740665 0.0066134892 0.0119740665 0.0075970473 0.6139010000 0.1119740000 0.0516960000 0.0000010000 0.4473800000 0.0018570000 114779979 0 402718720 4.8526282310 4.1326007843 5.5988049507 573 22.8800000000 0.0114344675 0.0066219027 0.0119740665 0.0075925714 1.1423290000 0.1120100000 0.0517320000 0.0520240000 0.4422120000 0.4833620000 114782755 0 402718720 4.8517303467 4.1318717003 5.5901198387 574 22.9200000000 0.0110143693 0.0066295551 0.0119740665 0.0075860265 0.6101520000 0.1119940000 0.0519180000 0.0000010000 0.4433880000 0.0018530000 114785531 0 402718720 4.8488316536 4.1331305504 5.5837430954 575 22.9600000000 0.0105715273 0.0066364107 0.0119740665 0.0075812143 0.6596310000 0.1120220000 0.0540050000 0.0513650000 0.4394320000 0.0018010000 114788307 0 402718720 4.8474764824 4.1297054291 5.5744657516 576 23.0000000000 0.0106274029 0.0066433395 0.0119740665 0.0075764338 0.6176840000 0.1114800000 0.0632410000 0.0000000000 0.4400960000 0.0018600000 114791083 0 402718720 4.8465490341 4.1262664795 5.5672039986 577 23.0400000000 0.0107132914 0.0066503932 0.0119740665 0.0075776861 1.1243630000 0.1120400000 0.0521190000 0.0513680000 0.4353530000 0.4724840000 114793859 0 402718720 4.8451986313 4.1279511452 5.5576424599 578 23.0800000000 0.0108655430 0.0066576858 0.0119740665 0.0075711397 0.6030750000 0.1120520000 0.0523290000 0.0000010000 0.4358340000 0.0018620000 114796635 0 402718720 4.8442497253 4.1274347305 5.5480670929 579 23.1200000000 0.0108361477 0.0066649025 0.0119740665 0.0075646897 0.6494690000 0.1121040000 0.0523440000 0.0507130000 0.4314250000 0.0018730000 114799411 0 402718720 4.8436870575 4.1246800423 5.5389552116 580 23.1600000000 0.0110822441 0.0066725186 0.0119740665 0.0075598156 0.6191270000 0.1120580000 0.0727310000 0.0000000000 0.4314510000 0.0018740000 114802187 0 402718720 4.8430705070 4.1238975525 5.5286035538 581 23.2000000000 0.0109444587 0.0066798714 0.0119740665 0.0075536225 1.1174030000 0.1119980000 0.0638170000 0.0500340000 0.4282530000 0.4622940000 114804963 0 402718720 4.8414826393 4.1239771843 5.5193305016 582 23.2400000000 0.0108995391 0.0066871216 0.0119740665 0.0075475968 0.5948490000 0.1119700000 0.0528500000 0.0000000000 0.4271280000 0.0018860000 114807739 0 402718720 4.8400874138 4.1217536926 5.5082564354 583 23.2800000000 0.0110947751 0.0066946819 0.0119740665 0.0075415710 0.6427350000 0.1119140000 0.0526730000 0.0496920000 0.4255460000 0.0018900000 114810515 0 402718720 4.8400340080 4.1186070442 5.4987144470 584 23.3200000000 0.0113031724 0.0067025732 0.0119740665 0.0075420153 0.5938200000 0.1118900000 0.0527420000 0.0000010000 0.4262870000 0.0018840000 114813291 0 402718720 4.8379788399 4.1192593575 5.4873881340 585 23.3600000000 0.0114202974 0.0067106377 0.0119740665 0.0075369385 1.0919920000 0.1118360000 0.0551090000 0.0490480000 0.4222980000 0.4526900000 114816067 0 402718720 4.8367080688 4.1185927391 5.4759573936 586 23.4000000000 0.0115208654 0.0067188463 0.0119740665 0.0075327481 0.5906940000 0.1117460000 0.0529690000 0.0000010000 0.4230690000 0.0018900000 114818843 0 402718720 4.8363370895 4.1153979301 5.4648108482 587 23.4400000000 0.0115839634 0.0067271344 0.0119740665 0.0075369398 0.6340960000 0.1116480000 0.0528220000 0.0490000000 0.4177170000 0.0018880000 114821619 0 402718720 4.8349223137 4.1148934364 5.4552354813 588 23.4800000000 0.0118170176 0.0067357906 0.0119740665 0.0075447021 0.5862340000 0.1116110000 0.0531800000 0.0000010000 0.4185170000 0.0019020000 114824395 0 402718720 4.8322467804 4.1171469688 5.4276041985 589 23.5200000000 0.0118968217 0.0067445530 0.0119740665 0.0075389448 1.0634510000 0.1115720000 0.0554470000 0.0479440000 0.4108360000 0.4366300000 114827171 0 402718720 4.8303833008 4.1186714172 5.4177179337 590 23.5600000000 0.0120760901 0.0067535895 0.0120760901 0.0075364577 0.5808550000 0.1115700000 0.0554400000 0.0000010000 0.4109800000 0.0018430000 114829947 0 402718720 4.8280673027 4.1205010414 5.4060993195 591 23.6000000000 0.0120496135 0.0067625506 0.0120760901 0.0075407279 0.6123370000 0.1115370000 0.0445090000 0.0469270000 0.4064260000 0.0019020000 114832723 0 402718720 4.8268642426 4.1181950569 5.3948903084 592 23.6400000000 0.0121648349 0.0067716761 0.0121648349 0.0075346269 0.5761630000 0.1114940000 0.0560490000 0.0000010000 0.4056790000 0.0019160000 114835499 0 402718720 4.8257737160 4.1157302856 5.3807854652 593 23.6800000000 0.0122718634 0.0067809513 0.0122718634 0.0075303274 1.0409850000 0.1115090000 0.0561150000 0.0465510000 0.4017420000 0.4240410000 114838275 0 402718720 4.8239660263 4.1157021523 5.3681807518 594 23.7200000000 0.0124184527 0.0067904420 0.0124184527 0.0075261164 0.6285030000 0.1114820000 0.1118430000 0.0000010000 0.4022340000 0.0019100000 114841051 0 402718720 4.8224959373 4.1156921387 5.3562326431 595 23.7600000000 0.0122724660 0.0067996555 0.0124184527 0.0075229365 0.6121420000 0.1114520000 0.0539060000 0.0458770000 0.3979390000 0.0019210000 114843827 0 402718720 4.8198800087 4.1146612167 5.3472790718 596 23.8000000000 0.0122666070 0.0068088282 0.0124184527 0.0075221975 0.5661220000 0.1114330000 0.0542390000 0.0000010000 0.3974910000 0.0019220000 114846603 0 402718720 4.8180880547 4.1160087585 5.3343186378 597 23.8400000000 0.0123703415 0.0068181440 0.0124184527 0.0075161596 1.0188330000 0.1114130000 0.0566160000 0.0452000000 0.3924800000 0.4120850000 114849379 0 402718720 4.8153333664 4.1177778244 5.3237066269 598 23.8800000000 0.0125158522 0.0068276720 0.0125158522 0.0075107427 0.5632750000 0.1114510000 0.0568200000 0.0000010000 0.3920440000 0.0019320000 114852155 0 402718720 4.8136506081 4.1177043915 5.3099417686 599 23.9200000000 0.0124755241 0.0068371008 0.0125158522 0.0075048862 0.6008550000 0.1113740000 0.0545120000 0.0440390000 0.3879350000 0.0019360000 114854931 0 402718720 4.8106231689 4.1196928024 5.2997298241 600 23.9600000000 0.0127049051 0.0068468804 0.0127049051 0.0075019996 0.5648990000 0.1113230000 0.0639570000 0.0000010000 0.3866300000 0.0019400000 114857707 0 402718720 4.8086056709 4.1200070381 5.2883496284 601 24.0000000000 0.0126478672 0.0068565327 0.0127049051 0.0074964128 0.9966580000 0.1111760000 0.0570770000 0.0439970000 0.3831470000 0.4002200000 114860483 0 402718720 4.8055596352 4.1201071739 5.2780804634 602 24.0400000000 0.0127178263 0.0068662690 0.0127178263 0.0074902654 0.5519760000 0.1111100000 0.0547930000 0.0000000000 0.3830600000 0.0019240000 114863259 0 402718720 4.8035507202 4.1201429367 5.2654466629 603 24.0800000000 0.0126643237 0.0068758844 0.0127178263 0.0074840916 0.5950050000 0.1110560000 0.0571180000 0.0435400000 0.3803020000 0.0019250000 114866035 0 402718720 4.8001308441 4.1204380989 5.2565212250 604 24.1200000000 0.0125875678 0.0068853408 0.0127178263 0.0074778942 0.5490750000 0.1109830000 0.0547520000 0.0000000000 0.3803530000 0.0019220000 114868811 0 402718720 4.7967610359 4.1212220192 5.2485837936 605 24.1600000000 0.0124128219 0.0068944771 0.0127178263 0.0074720824 0.9810020000 0.1109760000 0.0546210000 0.0433370000 0.3775380000 0.3934870000 114871587 0 402718720 4.7938899994 4.1201281548 5.2399682999 606 24.2000000000 0.0123795103 0.0069035283 0.0127178263 0.0074661183 0.5387070000 0.1109410000 0.0477220000 0.0000010000 0.3770560000 0.0019280000 114874363 0 402718720 4.7913932800 4.1177153587 5.2324547768 607 24.2400000000 0.0123650413 0.0069125259 0.0127178263 0.0074603968 0.5879290000 0.1109220000 0.0477490000 0.0427720000 0.3826150000 0.0026630000 114877139 0 402718720 4.7892193794 4.1171021461 5.2197151184 608 24.2800000000 0.0124157565 0.0069215773 0.0127178263 0.0074546345 0.6385840000 0.1429710000 0.0988800000 0.0000010000 0.3928790000 0.0026700000 114879915 0 402718720 4.7861332893 4.1186313629 5.2109432220 609 24.3200000000 0.0123969195 0.0069305680 0.0127178263 0.0074503749 0.9734080000 0.1230590000 0.0549020000 0.0427560000 0.3690870000 0.3825350000 114882691 0 402718720 4.7844810486 4.1158547401 5.2019200325 610 24.3600000000 0.0126757063 0.0069399862 0.0127178263 0.0074445613 0.5404660000 0.1108210000 0.0574800000 0.0000010000 0.3691580000 0.0019340000 114885467 0 402718720 4.7824602127 4.1120743752 5.1934452057 611 24.4000000000 0.0127057554 0.0069494228 0.0127178263 0.0074430870 0.5764310000 0.1108960000 0.0549810000 0.0420150000 0.3655200000 0.0019440000 114888243 0 402718720 4.7810897827 4.1113486290 5.1798810959 612 24.4400000000 0.0127323810 0.0069588721 0.0127323810 0.0074381782 0.5461730000 0.1109220000 0.0670710000 0.0000000000 0.3651610000 0.0019380000 114891019 0 402718720 4.7782015800 4.1117572784 5.1706242561 613 24.4800000000 0.0127595747 0.0069683349 0.0127595747 0.0074328234 0.9463940000 0.1109300000 0.0577610000 0.0421820000 0.3615830000 0.3728660000 114893795 0 402718720 4.7760362625 4.1098108292 5.1632547379 614 24.5200000000 0.0129093304 0.0069780108 0.0129093304 0.0074268652 0.5302570000 0.1109860000 0.0555020000 0.0000000000 0.3607440000 0.0019570000 114896571 0 402718720 4.7741909027 4.1075210571 5.1500101089 615 24.5600000000 0.0129322140 0.0069876924 0.0129322140 0.0074212042 0.5730820000 0.1111050000 0.0578480000 0.0419580000 0.3591360000 0.0019520000 114899347 0 402718720 4.7728018761 4.1062254906 5.1416816711 616 24.6000000000 0.0130292596 0.0069975002 0.0130292596 0.0074160478 0.5312720000 0.1111480000 0.0579700000 0.0000010000 0.3591240000 0.0019550000 114902123 0 402718720 4.7712850571 4.1034340858 5.1305236816 617 24.6400000000 0.0130158933 0.0070072545 0.0130292596 0.0074150512 0.9290320000 0.1112620000 0.0577600000 0.0412100000 0.3542620000 0.3634610000 114904899 0 402718720 4.7693781853 4.1018366814 5.1196489334 618 24.6800000000 0.0131767374 0.0070172375 0.0131767374 0.0074153068 0.5249240000 0.1113630000 0.0553780000 0.0000010000 0.3551540000 0.0019570000 114907675 0 402718720 4.7682647705 4.1001195908 5.1067090034 619 24.7200000000 0.0130367121 0.0070269620 0.0131767374 0.0074167527 0.5615940000 0.1114600000 0.0576700000 0.0411750000 0.3482370000 0.0019610000 114910451 0 402718720 4.7670836449 4.0992507935 5.0915746689 620 24.7600000000 0.0131783672 0.0070368836 0.0131783672 0.0074140051 0.5332730000 0.1116240000 0.0672620000 0.0000010000 0.3513420000 0.0019530000 114913227 0 402718720 4.7641768456 4.1002140045 5.0825591087 621 24.8000000000 0.0132101132 0.0070468244 0.0132101132 0.0074081612 0.9068510000 0.1116810000 0.0551590000 0.0408570000 0.3451690000 0.3529040000 114916003 0 402718720 4.7624697685 4.0996856689 5.0722184181 622 24.8400000000 0.0131107243 0.0070565734 0.0132101132 0.0074024372 0.5292120000 0.1117120000 0.0673000000 0.0000000000 0.3471570000 0.0019500000 114918779 0 402718720 4.7605600357 4.0975704193 5.0613865852 623 24.8800000000 0.0134484200 0.0070668332 0.0134484200 0.0073998046 0.5546090000 0.1117890000 0.0575580000 0.0405880000 0.3416380000 0.0019430000 114921555 0 402718720 4.7582392693 4.0983347893 5.0504021645 624 24.9200000000 0.0136067793 0.0070773139 0.0136067793 0.0073944855 0.5159940000 0.1117010000 0.0578650000 0.0000010000 0.3434050000 0.0019430000 114924331 0 402718720 4.7552828789 4.0992212296 5.0391073227 625 24.9600000000 0.0137285907 0.0070879559 0.0137285907 0.0073886919 0.8957270000 0.1116790000 0.0577310000 0.0404510000 0.3383750000 0.3464000000 114927107 0 402718720 4.7525014877 4.0976247787 5.0290646553 626 25.0000000000 0.0138380304 0.0070987388 0.0138380304 0.0073836743 0.5126310000 0.1116530000 0.0577140000 0.0000010000 0.3402230000 0.0019410000 114929883 0 402718720 4.7505483627 4.0956354141 5.0196480751 627 25.0400000000 0.0139507875 0.0071096671 0.0139507875 0.0073805552 0.5472690000 0.1116290000 0.0574500000 0.0400240000 0.3351150000 0.0019410000 114932659 0 402718720 4.7477478981 4.0953426361 5.0092506409 628 25.0800000000 0.0139383757 0.0071205408 0.0139507875 0.0073749906 0.5095640000 0.1115070000 0.0577480000 0.0000010000 0.3372820000 0.0019330000 114935435 0 402718720 4.7439327240 4.0972094536 4.9996967316 629 25.1200000000 0.0138489306 0.0071312378 0.0139507875 0.0073717650 0.8783050000 0.1114760000 0.0574540000 0.0396650000 0.3303880000 0.3382250000 114938211 0 402718720 4.7413287163 4.0965309143 4.9936118126 630 25.1600000000 0.0139861666 0.0071421186 0.0139861666 0.0073666592 0.5045200000 0.1112400000 0.0577480000 0.0000010000 0.3324780000 0.0019320000 114940987 0 402718720 4.7374229431 4.0965795517 4.9841227531 631 25.2000000000 0.0138904890 0.0071528134 0.0139861666 0.0073631289 0.5436240000 0.1111270000 0.0645180000 0.0392360000 0.3256940000 0.0019280000 114943763 0 402718720 4.7334547043 4.0973782539 4.9755215645 632 25.2400000000 0.0140511403 0.0071637284 0.0140511403 0.0073620699 0.5086080000 0.1109190000 0.0673230000 0.0000000000 0.3273400000 0.0019260000 114946539 0 402718720 4.7296700478 4.0964918137 4.9697899818 633 25.2800000000 0.0137528200 0.0071741377 0.0140511403 0.0073579374 0.8660910000 0.1107180000 0.0670380000 0.0388070000 0.3204970000 0.3278840000 114949315 0 402718720 4.7256278992 4.0974655151 4.9597549438 634 25.3200000000 0.0145123182 0.0071857122 0.0145123182 0.0073547765 0.5100010000 0.1181750000 0.0673530000 0.0000000000 0.3214290000 0.0019240000 114952091 0 402718720 4.7204370499 4.0991811752 4.9509334564 635 25.3600000000 0.0145169757 0.0071972575 0.0145169757 0.0073573085 0.5816330000 0.1102530000 0.1145250000 0.0384360000 0.3153780000 0.0019250000 114954867 0 402718720 4.7164082527 4.0990481377 4.9453773499 636 25.4000000000 0.0143986056 0.0072085803 0.0145169757 0.0073575197 0.4976850000 0.1100820000 0.0672830000 0.0000010000 0.3172930000 0.0019210000 114957643 0 402718720 4.7129368782 4.0973916054 4.9363837242 637 25.4400000000 0.0145240072 0.0072200645 0.0145240072 0.0073523825 0.8362190000 0.1097990000 0.0575960000 0.0381100000 0.3112420000 0.3183410000 114960419 0 402718720 4.7084517479 4.0978560448 4.9292778969 638 25.4800000000 0.0145335132 0.0072315276 0.0145335132 0.0073480561 0.4737590000 0.1094550000 0.0482920000 0.0000010000 0.3129660000 0.0019310000 114963195 0 402718720 4.7051253319 4.0961995125 4.9213290215 639 25.5200000000 0.0147052426 0.0072432236 0.0147052426 0.0073424691 0.5339960000 0.1089850000 0.0768540000 0.0377670000 0.3073400000 0.0019270000 114965971 0 402718720 4.6999983788 4.0941600800 4.9153838158 640 25.5600000000 0.0148539208 0.0072551153 0.0148539208 0.0073374811 0.4982840000 0.1086130000 0.0772010000 0.0000010000 0.3094280000 0.0019190000 114968747 0 402718720 4.6958847046 4.0927953720 4.9091482162 641 25.6000000000 0.0147991832 0.0072668845 0.0148539208 0.0073324071 0.8206900000 0.1080890000 0.0578240000 0.0374180000 0.3045630000 0.3116720000 114971523 0 402718720 4.6907978058 4.0917105675 4.9027686119 642 25.6400000000 0.0150783854 0.0072790519 0.0150783854 0.0073277440 0.4843030000 0.1076430000 0.0676690000 0.0000010000 0.3059440000 0.0019220000 114974299 0 402718720 4.6854147911 4.0906434059 4.8976254463 643 25.6800000000 0.0150267500 0.0072911012 0.0150783854 0.0073223447 0.5264230000 0.1070840000 0.0769450000 0.0372010000 0.3021460000 0.0019230000 114977075 0 402718720 4.6807475090 4.0890016556 4.8911552429 644 25.7200000000 0.0153927961 0.0073036815 0.0153927961 0.0073167624 0.4686630000 0.1063940000 0.0557550000 0.0000010000 0.3034650000 0.0019190000 114979851 0 402718720 4.6750431061 4.0881185532 4.8858375549 645 25.7600000000 0.0155136203 0.0073164101 0.0155136203 0.0073113222 0.8475410000 0.1059100000 0.0961900000 0.0370060000 0.3000370000 0.3072830000 114982627 0 402718720 4.6700625420 4.0861444473 4.8794808388 646 25.8000000000 0.0157377459 0.0073294462 0.0157377459 0.0073056958 0.4771920000 0.1053360000 0.0676930000 0.0000010000 0.3011100000 0.0019160000 114985403 0 402718720 4.6636357307 4.0845594406 4.8753085136 647 25.8400000000 0.0158177614 0.0073425657 0.0158177614 0.0073001072 0.5085910000 0.1047690000 0.0675750000 0.0362860000 0.2968910000 0.0019190000 114988179 0 402718720 4.6562943459 4.0850458145 4.8696122169 648 25.8800000000 0.0161041413 0.0073560867 0.0161041413 0.0072978224 0.4603070000 0.1040920000 0.0557450000 0.0000000000 0.2974270000 0.0019180000 114990955 0 402718720 4.6495676041 4.0844254494 4.8649473190 649 25.9200000000 0.0161490925 0.0073696352 0.0161490925 0.0072965582 0.8141230000 0.1034780000 0.0772820000 0.0365890000 0.2942180000 0.3014230000 114993731 0 402718720 4.6424565315 4.0814476013 4.8598761559 650 25.9600000000 0.0166458171 0.0073839063 0.0166458171 0.0072925380 0.4890520000 0.1025530000 0.0865840000 0.0000000000 0.2968810000 0.0019150000 114996507 0 402718720 4.6283845901 4.0748252869 4.8507747650 651 26.0000000000 0.0171005595 0.0073988320 0.0171005595 0.0072934674 0.5170230000 0.1017010000 0.0860590000 0.0362000000 0.2900010000 0.0019170000 114999283 0 402718720 4.6109251976 4.0750308037 4.8402171135 652 26.0400000000 0.0174789596 0.0074142923 0.0174789596 0.0072879922 0.4640630000 0.1012820000 0.0676440000 0.0000000000 0.2920860000 0.0019180000 115002059 0 402718720 4.6015329361 4.0758991241 4.8341441154 653 26.0800000000 0.0175841525 0.0074298664 0.0175841525 0.0072849331 0.7784800000 0.1009390000 0.0580080000 0.0359830000 0.2876070000 0.2947940000 115004835 0 402718720 4.5913214684 4.0787172318 4.8294219971 654 26.1200000000 0.0180822387 0.0074461544 0.0180822387 0.0072914446 0.4590580000 0.1004820000 0.0675530000 0.0000010000 0.2879470000 0.0019160000 115007611 0 402718720 4.5809822083 4.0787110329 4.8255228996 655 26.1600000000 0.0188837387 0.0074636164 0.0188837387 0.0072869277 0.5385600000 0.0999290000 0.1155180000 0.0357250000 0.2843110000 0.0019200000 115010387 0 402718720 4.5715279579 4.0763998032 4.8187041283 656 26.2000000000 0.0182885472 0.0074801178 0.0188837387 0.0072855562 0.4642920000 0.0995810000 0.0750900000 0.0000010000 0.2865510000 0.0019150000 115013163 0 402718720 4.5607094765 4.0769529343 4.8153810501 657 26.2400000000 0.0184822287 0.0074968638 0.0188837387 0.0072855383 0.8209210000 0.0977030000 0.1156980000 0.0355360000 0.2818140000 0.2890230000 115015939 0 402718720 4.5500988960 4.0773506165 4.8116216660 658 26.2800000000 0.0182952061 0.0075132746 0.0188837387 0.0072871863 0.4534830000 0.0998920000 0.0678350000 0.0000010000 0.2826840000 0.0019080000 115018715 0 402718720 4.5388784409 4.0786614418 4.8072714806 659 26.3200000000 0.0186780151 0.0075302166 0.0188837387 0.0072845490 0.5121170000 0.1002860000 0.0962940000 0.0353570000 0.2770940000 0.0019140000 115021491 0 402718720 4.5270962715 4.0814900398 4.8036818504 660 26.3600000000 0.0182407275 0.0075464446 0.0188837387 0.0072795398 0.4410290000 0.1003540000 0.0579740000 0.0000000000 0.2796310000 0.0019100000 115024267 0 402718720 4.5162668228 4.0826258659 4.8006734848 661 26.4000000000 0.0184561275 0.0075629494 0.0188837387 0.0072744260 0.7617740000 0.1004370000 0.0673970000 0.0352000000 0.2753030000 0.2822780000 115027043 0 402718720 4.5041904449 4.0852174759 4.7965884209 662 26.4400000000 0.0184344146 0.0075793716 0.0188837387 0.0072733384 0.4949220000 0.1005530000 0.1152490000 0.0000010000 0.2760260000 0.0019100000 115029819 0 402718720 4.4923396111 4.0885839462 4.7951407433 663 26.4800000000 0.0185455941 0.0075959119 0.0188837387 0.0072907697 0.4773870000 0.1006210000 0.0672740000 0.0350120000 0.2713830000 0.0019190000 115032595 0 402718720 4.4816570282 4.0880455971 4.7914743423 664 26.5200000000 0.0188224800 0.0076128194 0.0188837387 0.0072984506 0.4352920000 0.1014010000 0.0579280000 0.0000000000 0.2728860000 0.0019090000 115035371 0 402718720 4.4714784622 4.0851020813 4.7854814529 665 26.5600000000 0.0189464781 0.0076298625 0.0189464781 0.0072935279 0.7988740000 0.1023290000 0.1153580000 0.0348780000 0.2689300000 0.2762140000 115038147 0 402718720 4.4609098434 4.0856466293 4.7824201584 666 26.6000000000 0.0184563808 0.0076461185 0.0189464781 0.0072896955 0.4924900000 0.1031420000 0.1155200000 0.0000000000 0.2707400000 0.0019130000 115040923 0 402718720 4.4497919083 4.0878577232 4.7795438766 667 26.6400000000 0.0189545918 0.0076630727 0.0189545918 0.0072935848 0.4657450000 0.1037080000 0.0580160000 0.0347210000 0.2661920000 0.0019180000 115043699 0 402718720 4.4391350746 4.0908732414 4.7775058746 668 26.6800000000 0.0186531432 0.0076795249 0.0189545918 0.0073154889 0.4409940000 0.1040700000 0.0676180000 0.0000010000 0.2662030000 0.0019160000 115046475 0 402718720 4.4280800819 4.0950183868 4.7747564316 669 26.7200000000 0.0190181397 0.0076964735 0.0190181397 0.0073583479 0.7516930000 0.1043650000 0.0770650000 0.0345190000 0.2636770000 0.2708850000 115049251 0 402718720 4.4171376228 4.0963935852 4.7714099884 670 26.7600000000 0.0184516367 0.0077125260 0.0190181397 0.0073951990 0.4505370000 0.1047770000 0.0770320000 0.0000010000 0.2656320000 0.0019130000 115052027 0 402718720 4.4074807167 4.0959854126 4.7691612244 671 26.8000000000 0.0186182223 0.0077287789 0.0190181397 0.0074021257 0.5199710000 0.1050420000 0.1151990000 0.0343960000 0.2622130000 0.0019170000 115054803 0 402718720 4.3979692459 4.0964045525 4.7652826309 672 26.8400000000 0.0186775941 0.0077450718 0.0190181397 0.0073980850 0.4776900000 0.1055460000 0.1059160000 0.0000010000 0.2631280000 0.0019130000 115057579 0 402718720 4.3883886337 4.0989823341 4.7610974312 673 26.8800000000 0.0179560557 0.0077602441 0.0190181397 0.0073941120 0.7564760000 0.1059300000 0.0866010000 0.0342880000 0.2604910000 0.2679760000 115060355 0 402718720 4.3793859482 4.0995230675 4.7584581375 674 26.9200000000 0.0182863660 0.0077758615 0.0190181397 0.0073886996 0.4299540000 0.1064030000 0.0579310000 0.0000010000 0.2625100000 0.0019150000 115063131 0 402718720 4.3706321716 4.1005582809 4.7541909218 675 26.9600000000 0.0179535095 0.0077909395 0.0190181397 0.0073832633 0.5189980000 0.1069160000 0.1150170000 0.0341840000 0.2597520000 0.0019200000 115065907 0 402718720 4.3618955612 4.1025314331 4.7519364357 676 27.0000000000 0.0183415599 0.0078065469 0.0190181397 0.0073789386 0.4406920000 0.1073280000 0.0673780000 0.0000000000 0.2628440000 0.0019430000 115068683 0 402718720 4.3528404236 4.1068377495 4.7479324341 677 27.0400000000 0.0183921959 0.0078221831 0.0190181397 0.0073875213 0.7813660000 0.1075120000 0.1144930000 0.0340940000 0.2582590000 0.2657670000 115071459 0 402718720 4.3441147804 4.1099624634 4.7461061478 678 27.0800000000 0.0178607851 0.0078369893 0.0190181397 0.0074006754 0.4574530000 0.1076700000 0.0863180000 0.0000010000 0.2603250000 0.0019350000 115074235 0 402718720 4.3358831406 4.1119327545 4.7436766624 679 27.1200000000 0.0183267985 0.0078524382 0.0190181397 0.0074102948 0.4583270000 0.1080540000 0.0576470000 0.0340220000 0.2554560000 0.0019320000 115077011 0 402718720 4.3270173073 4.1140685081 4.7392635345 680 27.1600000000 0.0175334550 0.0078666750 0.0190181397 0.0074125749 0.4348390000 0.1083080000 0.0665010000 0.0000010000 0.2568820000 0.0019300000 115079787 0 402718720 4.3191804886 4.1139731407 4.7356152534 681 27.2000000000 0.0185542777 0.0078823689 0.0190181397 0.0074073698 0.7758200000 0.1084460000 0.1151750000 0.0339510000 0.2549150000 0.2621210000 115082563 0 402718720 4.3112211227 4.1152133942 4.7306427956 682 27.2400000000 0.0185280312 0.0078979784 0.0190181397 0.0074022668 0.4441760000 0.1085390000 0.0769720000 0.0000010000 0.2555150000 0.0019370000 115085339 0 402718720 4.3029751778 4.1188259125 4.7266125679 683 27.2800000000 0.0192934927 0.0079146629 0.0192934927 0.0074013511 0.4663250000 0.1088450000 0.0672820000 0.0338780000 0.2531720000 0.0019360000 115088115 0 402718720 4.2950792313 4.1217074394 4.7213077545 684 27.3200000000 0.0189083759 0.0079307356 0.0192934927 0.0074065435 0.4333000000 0.1090170000 0.0673150000 0.0000000000 0.2538210000 0.0019340000 115090891 0 402718720 4.2867383957 4.1227903366 4.7175636292 685 27.3600000000 0.0196167212 0.0079477954 0.0196167212 0.0074058815 0.7320790000 0.1092620000 0.0768900000 0.0332720000 0.2520940000 0.2593540000 115093667 0 402718720 4.2790741920 4.1236090660 4.7111730576 686 27.4000000000 0.0195210855 0.0079646661 0.0196167212 0.0074026400 0.4426920000 0.1094340000 0.0769850000 0.0000000000 0.2531170000 0.0019320000 115096443 0 402718720 4.2705335617 4.1271228790 4.7058401108 687 27.4400000000 0.0192182139 0.0079810468 0.0196167212 0.0074095320 0.4749780000 0.1095630000 0.0767350000 0.0337590000 0.2516140000 0.0020810000 115099219 0 402718720 4.2623248100 4.1307010651 4.7007274628 688 27.4800000000 0.0196089000 0.0079979478 0.0196167212 0.0074252862 0.4336570000 0.1098630000 0.0671810000 0.0000000000 0.2534480000 0.0019320000 115101995 0 402718720 4.2540426254 4.1323919296 4.6947884560 689 27.5200000000 0.0195114408 0.0080146582 0.0196167212 0.0074350395 0.7217940000 0.1100830000 0.0670600000 0.0336800000 0.2513310000 0.2584210000 115104771 0 402718720 4.2456631660 4.1340537071 4.6893081665 690 27.5600000000 0.0193458330 0.0080310802 0.0196167212 0.0074361715 0.4344760000 0.1103350000 0.0673070000 0.0000010000 0.2536820000 0.0019310000 115107547 0 402718720 4.2377328873 4.1354370117 4.6827864647 691 27.6000000000 0.0195984393 0.0080478202 0.0196167212 0.0074363424 0.4559590000 0.1104420000 0.0576080000 0.0336090000 0.2511240000 0.0019380000 115110323 0 402718720 4.2288646698 4.1397523880 4.6762681007 692 27.6400000000 0.0201805234 0.0080653530 0.0201805234 0.0074506552 0.4251170000 0.1105900000 0.0576980000 0.0000010000 0.2536640000 0.0019330000 115113099 0 402718720 4.2202043533 4.1435914040 4.6692476273 693 27.6800000000 0.0205435585 0.0080833591 0.0205435585 0.0074810312 0.7322230000 0.1107550000 0.0765220000 0.0335910000 0.2515200000 0.2585920000 115115875 0 402718720 4.2123670578 4.1440515518 4.6615252495 694 27.7200000000 0.0213316046 0.0081024488 0.0213316046 0.0074956330 0.4349760000 0.1108840000 0.0672190000 0.0000000000 0.2536920000 0.0019340000 115118651 0 402718720 4.2048916817 4.1434268951 4.6524500847 695 27.7600000000 0.0216351189 0.0081219203 0.0216351189 0.0074954921 0.4846790000 0.1110210000 0.0839570000 0.0335980000 0.2529150000 0.0019380000 115121427 0 402718720 4.1977882385 4.1426601410 4.6447806358 696 27.8000000000 0.0222926661 0.0081422805 0.0222926661 0.0074914560 0.4455480000 0.1110910000 0.0768990000 0.0000010000 0.2543910000 0.0019310000 115124203 0 402718720 4.1900396347 4.1451768875 4.6366558075 697 27.8400000000 0.0229611360 0.0081635414 0.0229611360 0.0074886086 0.7501650000 0.1112400000 0.0863760000 0.0336080000 0.2555490000 0.2621600000 115126979 0 402718720 4.1819186211 4.1486511230 4.6289114952 698 27.8800000000 0.0233075544 0.0081852377 0.0233075544 0.0074907817 0.4293340000 0.1113320000 0.0578260000 0.0000010000 0.2569950000 0.0019330000 115129755 0 402718720 4.1729173660 4.1532144547 4.6221060753 699 27.9200000000 0.0233512744 0.0082069345 0.0233512744 0.0075016235 0.4728260000 0.1114990000 0.0672690000 0.0330460000 0.2578170000 0.0019400000 115132531 0 402718720 4.1645278931 4.1573090553 4.6159877777 700 27.9600000000 0.0231949259 0.0082283459 0.0233512744 0.0075186796 0.4324660000 0.1115840000 0.0576680000 0.0000010000 0.2600140000 0.0019340000 115135307 0 402718720 4.1558327675 4.1605234146 4.6094846725 701 28.0000000000 0.0229084510 0.0082492876 0.0233512744 0.0075377034 0.7293220000 0.1116610000 0.0576600000 0.0335260000 0.2590410000 0.2661840000 115138083 0 402718720 4.1475982666 4.1628174782 4.6037154198 702 28.0400000000 0.0222024675 0.0082691639 0.0233512744 0.0075529298 0.4440920000 0.1117270000 0.0671420000 0.0000010000 0.2620250000 0.0019460000 115140859 0 402718720 4.1395449638 4.1639704704 4.5983529091 703 28.0800000000 0.0212234855 0.0082875911 0.0233512744 0.0075614893 0.4581640000 0.1118360000 0.0481630000 0.0336280000 0.2613060000 0.0019640000 115143635 0 402718720 4.1323180199 4.1650443077 4.5948982239 704 28.1200000000 0.0201143622 0.0083043905 0.0233512744 0.0075686710 0.4313640000 0.1119410000 0.0528590000 0.0000000000 0.2633720000 0.0019430000 115146411 0 402718720 4.1234035492 4.1713476181 4.5921468735 705 28.1600000000 0.0192461349 0.0083199107 0.0233512744 0.0075930234 0.7456370000 0.1119650000 0.0669860000 0.0336650000 0.2623130000 0.2694610000 115149187 0 402718720 4.1149497032 4.1755924225 4.5891218185 706 28.2000000000 0.0186175201 0.0083344966 0.0233512744 0.0076141890 0.4378240000 0.1120560000 0.0576170000 0.0000010000 0.2649530000 0.0019450000 115151963 0 402718720 4.1076750755 4.1756577492 4.5861449242 707 28.2400000000 0.0181597006 0.0083483936 0.0233512744 0.0076166740 0.4792620000 0.1120620000 0.0670450000 0.0334470000 0.2634820000 0.0019520000 115154739 0 402718720 4.0998449326 4.1791048050 4.5828747749 708 28.2800000000 0.0175591353 0.0083614031 0.0233512744 0.0076141079 0.4489580000 0.1121070000 0.0671800000 0.0000010000 0.2664500000 0.0019520000 115157515 0 402718720 4.0915670395 4.1835422516 4.5810122490 709 28.3200000000 0.0164939351 0.0083728735 0.0233512744 0.0076097853 0.7425960000 0.1122040000 0.0578370000 0.0334280000 0.2653940000 0.2724740000 115160291 0 402718720 4.0852108002 4.1805806160 4.5794663429 710 28.3600000000 0.0157094803 0.0083832068 0.0233512744 0.0076062023 0.4586100000 0.1121750000 0.0768210000 0.0000010000 0.2663900000 0.0019520000 115163067 0 402718720 4.0783295631 4.1815567017 4.5773324966 711 28.4000000000 0.0153429834 0.0083929955 0.0233512744 0.0076012234 0.4731510000 0.1121710000 0.0579070000 0.0335510000 0.2662830000 0.0019590000 115165843 0 402718720 4.0697774887 4.1894488335 4.5763201714 712 28.4400000000 0.0150054768 0.0084022827 0.0233512744 0.0075983208 0.4409030000 0.1121240000 0.0577400000 0.0000000000 0.2678000000 0.0019500000 115168619 0 402718720 4.0618896484 4.1916937828 4.5742406845 713 28.4800000000 0.0148369307 0.0084113074 0.0233512744 0.0075952743 0.7587040000 0.1121660000 0.0582130000 0.0331980000 0.2777530000 0.2760950000 115171395 0 402718720 4.0568776131 4.1882457733 4.5737161636 714 28.5200000000 0.0148645425 0.0084203456 0.0233512744 0.0076141077 0.4378050000 0.1121290000 0.0556240000 0.0000010000 0.2668110000 0.0019530000 115174171 0 402718720 4.0485301018 4.1957726479 4.5732245445 715 28.5600000000 0.0147320414 0.0084291731 0.0233512744 0.0076093367 0.4824810000 0.1121040000 0.0673610000 0.0332620000 0.2665140000 0.0019520000 115176947 0 402718720 4.0397653580 4.2026052475 4.5732140541 716 28.6000000000 0.0147090945 0.0084379440 0.0233512744 0.0076099219 0.4414240000 0.1121540000 0.0576690000 0.0000010000 0.2683640000 0.0019510000 115179723 0 402718720 4.0330166817 4.2043671608 4.5753340721 717 28.6400000000 0.0146607002 0.0084466229 0.0233512744 0.0076072809 0.7492360000 0.1121630000 0.0648380000 0.0326770000 0.2655030000 0.2727820000 115182499 0 402718720 4.0265669823 4.2059402466 4.5781021118 718 28.6800000000 0.0147138787 0.0084553516 0.0233512744 0.0076025555 0.4494250000 0.1121520000 0.0672930000 0.0000010000 0.2667390000 0.0019490000 115185275 0 402718720 4.0192346573 4.2106471062 4.5808291435 719 28.7200000000 0.0146974446 0.0084640333 0.0233512744 0.0076014225 0.4674310000 0.1121650000 0.0551670000 0.0331480000 0.2637030000 0.0019530000 115188051 0 402718720 4.0114970207 4.2139134407 4.5830335617 720 28.7600000000 0.0147138191 0.0084727135 0.0233512744 0.0075993123 0.4390690000 0.1122030000 0.0576880000 0.0000010000 0.2659330000 0.0019520000 115190827 0 402718720 4.0040450096 4.2162699699 4.5866856575 721 28.8000000000 0.0147547871 0.0084814265 0.0233512744 0.0075945055 0.7349990000 0.1121940000 0.0553320000 0.0331030000 0.2628900000 0.2702020000 115193603 0 402718720 3.9971630573 4.2171840668 4.5912942886 722 28.8400000000 0.0147758471 0.0084901445 0.0233512744 0.0075892618 0.4348030000 0.1121990000 0.0554350000 0.0000010000 0.2639320000 0.0019490000 115196379 0 402718720 3.9893207550 4.2196559906 4.5956697464 723 28.8800000000 0.0147663504 0.0084988253 0.0233512744 0.0075840589 0.4683820000 0.1121360000 0.0578450000 0.0330100000 0.2621370000 0.0019510000 115199155 0 402718720 3.9816381931 4.2209305763 4.6011962891 724 28.9200000000 0.0147151304 0.0085074114 0.0233512744 0.0075788513 0.4349740000 0.1121810000 0.0579160000 0.0000010000 0.2616930000 0.0018840000 115201931 0 402718720 3.9733691216 4.2232856750 4.6065816879 725 28.9600000000 0.0146815358 0.0085159274 0.0233512744 0.0075761833 0.7378440000 0.1081770000 0.0665550000 0.0326270000 0.2612060000 0.2679960000 115204707 0 402718720 3.9647216797 4.2259287834 4.6123242378 726 29.0000000000 0.0147365415 0.0085244958 0.0233512744 0.0075812159 0.4309170000 0.1081970000 0.0572860000 0.0000010000 0.2621800000 0.0019490000 115207483 0 402718720 3.9566156864 4.2273659706 4.6183986664 727 29.0400000000 0.0146764060 0.0085329578 0.0233512744 0.0075855893 0.4612550000 0.1121200000 0.0551750000 0.0322650000 0.2584250000 0.0019520000 115210259 0 402718720 3.9474382401 4.2294197083 4.6243100166 728 29.0800000000 0.0147503419 0.0085414982 0.0233512744 0.0075893179 0.4326740000 0.1121470000 0.0577120000 0.0000010000 0.2595640000 0.0019490000 115213035 0 402718720 3.9386706352 4.2318911552 4.6308989525 729 29.1200000000 0.0147214709 0.0085499755 0.0233512744 0.0075889459 0.7239290000 0.1121850000 0.0576600000 0.0327300000 0.2563960000 0.2636560000 115215811 0 402718720 3.9299066067 4.2344937325 4.6379032135 730 29.1600000000 0.0148527091 0.0085586094 0.0233512744 0.0075854443 0.4483090000 0.1121370000 0.0769100000 0.0000000000 0.2560060000 0.0019470000 115218587 0 402718720 3.9211583138 4.2358336449 4.6447067261 731 29.2000000000 0.0148842754 0.0085672628 0.0233512744 0.0075808931 0.4587590000 0.1121590000 0.0554400000 0.0326440000 0.2552340000 0.0019510000 115221363 0 402718720 3.9117937088 4.2384829521 4.6511449814 732 29.2400000000 0.0150375254 0.0085761020 0.0233512744 0.0075767643 0.4294490000 0.1121720000 0.0577810000 0.0000000000 0.2562350000 0.0019470000 115224139 0 402718720 3.9016928673 4.2428708076 4.6576747894 733 29.2800000000 0.0149560655 0.0085848059 0.0233512744 0.0075720686 0.7203130000 0.1121910000 0.0553430000 0.0319530000 0.2562580000 0.2632590000 115226915 0 402718720 3.8919477463 4.2461242676 4.6660585403 734 29.3200000000 0.0148694282 0.0085933680 0.0233512744 0.0075676582 0.4307880000 0.1122060000 0.0579250000 0.0000010000 0.2573830000 0.0019460000 115229691 0 402718720 3.8828315735 4.2497677803 4.6753087044 735 29.3600000000 0.0147378212 0.0086017278 0.0233512744 0.0075646376 0.4611970000 0.1121960000 0.0579690000 0.0318820000 0.2558670000 0.0019550000 115232467 0 402718720 3.8739504814 4.2531852722 4.6840567589 736 29.4000000000 0.0145881707 0.0086098616 0.0233512744 0.0075614297 0.4286220000 0.1121940000 0.0555200000 0.0000010000 0.2576500000 0.0019480000 115235243 0 402718720 3.8653521538 4.2574095726 4.6932539940 737 29.4400000000 0.0143837351 0.0086176959 0.0233512744 0.0075567328 0.7288430000 0.1121840000 0.0649350000 0.0323260000 0.2556310000 0.2624610000 115238019 0 402718720 3.8570718765 4.2605562210 4.7020592690 738 29.4800000000 0.0142558999 0.0086253357 0.0233512744 0.0075553828 0.4323400000 0.1121530000 0.0576720000 0.0000000000 0.2592360000 0.0019460000 115240795 0 402718720 3.8485698700 4.2640337944 4.7108330727 739 29.5200000000 0.0141415959 0.0086328002 0.0233512744 0.0075704804 0.4573610000 0.1121490000 0.0549120000 0.0322340000 0.2547810000 0.0019530000 115243571 0 402718720 3.8407325745 4.2669119835 4.7196936607 740 29.5600000000 0.0141826235 0.0086403000 0.0233512744 0.0075899780 0.4293680000 0.1124010000 0.0550900000 0.0000010000 0.2585980000 0.0019450000 115246347 0 402718720 3.8336591721 4.2696223259 4.7282929420 741 29.6000000000 0.0142475953 0.0086478672 0.0233512744 0.0076141965 0.7200650000 0.1121380000 0.0642150000 0.0322560000 0.2516100000 0.2585140000 115249123 0 402718720 3.8264122009 4.2740077972 4.7367625237 742 29.6400000000 0.0142992474 0.0086554836 0.0233512744 0.0076326413 0.4277780000 0.1120630000 0.0549650000 0.0000010000 0.2574660000 0.0019490000 115251899 0 402718720 3.8202168941 4.2777028084 4.7457418442 743 29.6800000000 0.0142428987 0.0086630037 0.0233512744 0.0076322619 0.4537510000 0.1120290000 0.0572940000 0.0321740000 0.2489660000 0.0019520000 115254675 0 402718720 3.8153858185 4.2787127495 4.7539334297 744 29.7200000000 0.0142505746 0.0086705139 0.0233512744 0.0076276343 0.4331830000 0.1120020000 0.0674250000 0.0000010000 0.2504730000 0.0019500000 115257451 0 402718720 3.8104197979 4.2806997299 4.7609424591 745 29.7600000000 0.0142668411 0.0086780257 0.0233512744 0.0076254246 0.7009570000 0.1119680000 0.0555280000 0.0320810000 0.2465630000 0.2534950000 115260227 0 402718720 3.8052415848 4.2834205627 4.7673816681 746 29.8000000000 0.0142736537 0.0086855265 0.0233512744 0.0076214598 0.4217750000 0.1119230000 0.0579330000 0.0000010000 0.2486390000 0.0019500000 115263003 0 402718720 3.8004190922 4.2852978706 4.7737188339 747 29.8400000000 0.0142632993 0.0086929934 0.0233512744 0.0076165498 0.4488030000 0.1118270000 0.0576670000 0.0320410000 0.2439560000 0.0019530000 115265779 0 402718720 3.7951688766 4.2883815765 4.7794537544 748 29.8800000000 0.0142286215 0.0087003940 0.0233512744 0.0076137418 0.4315960000 0.1118270000 0.0672410000 0.0000010000 0.2492360000 0.0019430000 115268555 0 402718720 3.7901794910 4.2918977737 4.7853975296 749 29.9200000000 0.0142298425 0.0087077765 0.0233512744 0.0076102851 0.6870490000 0.1117430000 0.0549820000 0.0320230000 0.2400550000 0.2469170000 115271331 0 402718720 3.7858836651 4.2947926521 4.7910490036 750 29.9600000000 0.0142519251 0.0087151687 0.0233512744 0.0076072234 0.4182950000 0.1116330000 0.0575320000 0.0000000000 0.2458340000 0.0019490000 115274107 0 402718720 3.7818362713 4.2976222038 4.7962789536 751 30.0000000000 0.0142905992 0.0087225927 0.0233512744 0.0076042056 0.4412050000 0.1115470000 0.0572960000 0.0319970000 0.2370700000 0.0019490000 115276883 0 402718720 3.7780642509 4.2998027802 4.8008928299 752 30.0400000000 0.0143336076 0.0087300541 0.0233512744 0.0076013459 0.4144530000 0.1115440000 0.0575090000 0.0000010000 0.2421170000 0.0019470000 115279659 0 402718720 3.7744960785 4.3025217056 4.8052005768 753 30.0800000000 0.0143398810 0.0087375041 0.0233512744 0.0076005512 0.6738310000 0.1114460000 0.0548140000 0.0319580000 0.2337780000 0.2404920000 115282435 0 402718720 3.7707960606 4.3044776917 4.8089265823 754 30.1200000000 0.0143738789 0.0087449794 0.0233512744 0.0076060839 0.4092140000 0.1113650000 0.0548810000 0.0000010000 0.2396660000 0.0019460000 115285211 0 402718720 3.7672472000 4.3066134453 4.8124904633 755 30.1600000000 0.0144265853 0.0087525047 0.0233512744 0.0076173919 0.4342940000 0.1112490000 0.0570140000 0.0320080000 0.2307030000 0.0019600000 115287987 0 402718720 3.7631943226 4.3080887794 4.8157405853 756 30.2000000000 0.0144381188 0.0087600253 0.0233512744 0.0076287747 0.4144520000 0.1111350000 0.0643630000 0.0000000000 0.2356530000 0.0019390000 115290763 0 402718720 3.7589230537 4.3108391762 4.8193087578 757 30.2400000000 0.0144097600 0.0087674887 0.0233512744 0.0076304369 0.6593660000 0.1110110000 0.0546560000 0.0319470000 0.2268600000 0.2335310000 115293539 0 402718720 3.7541165352 4.3138966560 4.8223395348 758 30.2800000000 0.0144001096 0.0087749196 0.0233512744 0.0076335782 0.4020330000 0.1109360000 0.0572840000 0.0000000000 0.2304990000 0.0019370000 115296315 0 402718720 3.7492225170 4.3156218529 4.8257851601 759 30.3200000000 0.0144507959 0.0087823977 0.0233512744 0.0076505562 0.4230630000 0.1107710000 0.0545930000 0.0319670000 0.2224120000 0.0019480000 115299091 0 402718720 3.7437047958 4.3186869621 4.8292684555 760 30.3600000000 0.0144657297 0.0087898757 0.0233512744 0.0076634183 0.4101600000 0.1106030000 0.0664420000 0.0000010000 0.2298010000 0.0019440000 115301867 0 402718720 3.7374002934 4.3235478401 4.8322830200 761 30.4000000000 0.0144892232 0.0087973650 0.0233512744 0.0076724419 0.6405730000 0.1105200000 0.0567130000 0.0312960000 0.2170470000 0.2236340000 115304643 0 402718720 3.7310729027 4.3270382881 4.8350124359 762 30.4400000000 0.0144963767 0.0088048440 0.0233512744 0.0076737192 0.3934460000 0.1104580000 0.0571880000 0.0000000000 0.2225080000 0.0019340000 115307419 0 402718720 3.7242763042 4.3306717873 4.8371987343 763 30.4800000000 0.0145547530 0.0088123800 0.0233512744 0.0076725511 0.4156220000 0.1103270000 0.0569730000 0.0318700000 0.2131200000 0.0019390000 115310195 0 402718720 3.7170805931 4.3347530365 4.8394103050 764 30.5200000000 0.0146046998 0.0088199615 0.0233512744 0.0076723406 0.3952230000 0.1102560000 0.0643090000 0.0000010000 0.2173570000 0.0019340000 115312971 0 402718720 3.7093448639 4.3386311531 4.8416004181 765 30.5600000000 0.0145876911 0.0088275010 0.0233512744 0.0076700881 0.6182450000 0.1101740000 0.0571380000 0.0318820000 0.2055360000 0.2121480000 115315747 0 402718720 3.7016611099 4.3426456451 4.8438897133 766 30.6000000000 0.0146795511 0.0088351408 0.0233512744 0.0076690959 0.3795560000 0.1101830000 0.0573410000 0.0000010000 0.2087240000 0.0019270000 115318523 0 402718720 3.6939783096 4.3462953568 4.8461818695 767 30.6400000000 0.0146571454 0.0088427314 0.0233512744 0.0076677611 0.4053950000 0.1100560000 0.0572610000 0.0312620000 0.2034920000 0.0019400000 115321299 0 402718720 3.6854782104 4.3502860069 4.8480200768 768 30.6800000000 0.0147055211 0.0088503653 0.0233512744 0.0076688986 0.3746830000 0.1100330000 0.0573330000 0.0000010000 0.2040050000 0.0019390000 115324075 0 402718720 3.6771624088 4.3539681435 4.8500971794 769 30.7200000000 0.0147271939 0.0088580074 0.0233512744 0.0076695478 0.6040810000 0.1099690000 0.0572610000 0.0317430000 0.1987240000 0.2050080000 115326851 0 402718720 3.6687896252 4.3582324982 4.8522167206 770 30.7600000000 0.0147343734 0.0088656391 0.0233512744 0.0076667461 0.3723940000 0.1100180000 0.0574370000 0.0000010000 0.2016190000 0.0019330000 115329627 0 402718720 3.6604037285 4.3625173569 4.8543057442 771 30.8000000000 0.0147430310 0.0088732621 0.0233512744 0.0076630582 0.3959300000 0.1100110000 0.0550480000 0.0316600000 0.1958780000 0.0019400000 115332403 0 402718720 3.6519451141 4.3663187027 4.8560152054 772 30.8400000000 0.0148011269 0.0088809407 0.0233512744 0.0076606958 0.3657250000 0.1098380000 0.0574420000 0.0000000000 0.1951260000 0.0019420000 115335179 0 402718720 3.6436421871 4.3689246178 4.8578038216 773 30.8800000000 0.0148021160 0.0088886007 0.0233512744 0.0076593043 0.5865010000 0.1099200000 0.0574200000 0.0316060000 0.1899620000 0.1962260000 115337955 0 402718720 3.6351256371 4.3719987869 4.8596377373 774 30.9200000000 0.0148384711 0.0088962879 0.0233512744 0.0076626890 0.3691970000 0.1098170000 0.0667580000 0.0000000000 0.1892980000 0.0019310000 115340731 0 402718720 3.6270604134 4.3744473457 4.8616709709 775 30.9600000000 0.0148819489 0.0089040113 0.0233512744 0.0076679737 0.3881110000 0.1097910000 0.0549660000 0.0316760000 0.1883190000 0.0019500000 115343507 0 402718720 3.6187679768 4.3760251999 4.8631415367 776 31.0000000000 0.0148891127 0.0089117241 0.0233512744 0.0076756197 0.3599850000 0.1097720000 0.0573100000 0.0000000000 0.1895750000 0.0019300000 115346283 0 402718720 3.6101977825 4.3779783249 4.8646664619 777 31.0400000000 0.0149273751 0.0089194662 0.0233512744 0.0076864021 0.5755740000 0.1097130000 0.0570490000 0.0315150000 0.1848710000 0.1910270000 115349059 0 402718720 3.6017255783 4.3812131882 4.8659505844 778 31.0800000000 0.0149481492 0.0089272152 0.0233512744 0.0076874360 0.3531110000 0.1096880000 0.0548200000 0.0000010000 0.1852590000 0.0019390000 115351835 0 402718720 3.5933949947 4.3845686913 4.8671150208 779 31.1200000000 0.0149640730 0.0089349647 0.0233512744 0.0076859350 0.3805920000 0.1097310000 0.0572090000 0.0308630000 0.1794430000 0.0019410000 115354611 0 402718720 3.5855274200 4.3868198395 4.8686480522 780 31.1600000000 0.0149712702 0.0089427035 0.0233512744 0.0076849435 0.3506590000 0.1097650000 0.0573090000 0.0000000000 0.1802480000 0.0019340000 115357387 0 402718720 3.5778188705 4.3894400597 4.8701801300 781 31.2000000000 0.0150264446 0.0089504932 0.0233512744 0.0076827327 0.5590000000 0.1096890000 0.0548620000 0.0307600000 0.1780180000 0.1842820000 115360163 0 402718720 3.5701205730 4.3918690681 4.8709416389 782 31.2400000000 0.0150156375 0.0089582492 0.0233512744 0.0076786790 0.4007200000 0.1096290000 0.1119640000 0.0000000000 0.1757620000 0.0019390000 115362939 0 402718720 3.5628235340 4.3931927681 4.8722143173 783 31.2800000000 0.0150131965 0.0089659822 0.0233512744 0.0076741431 0.3853100000 0.1096390000 0.0669710000 0.0313060000 0.1740240000 0.0019410000 115365715 0 402718720 3.5556249619 4.3948693275 4.8735790253 784 31.3200000000 0.0150502631 0.0089737427 0.0233512744 0.0076694032 0.3416780000 0.1095980000 0.0551360000 0.0000010000 0.1735940000 0.0019400000 115368491 0 402718720 3.5489912033 4.3961663246 4.8749947548 785 31.3600000000 0.0150435688 0.0089814750 0.0233512744 0.0076646761 0.5506920000 0.1096030000 0.0576560000 0.0305880000 0.1725960000 0.1788320000 115371267 0 402718720 3.5425894260 4.3967661858 4.8761248589 786 31.4000000000 0.0150611447 0.0089892099 0.0233512744 0.0076614812 0.3396260000 0.1095590000 0.0553950000 0.0000000000 0.1713090000 0.0019320000 115374043 0 402718720 3.5361716747 4.3976860046 4.8773646355 787 31.4400000000 0.0150526669 0.0089969145 0.0233512744 0.0076581542 0.3685910000 0.1095780000 0.0577810000 0.0311410000 0.1667210000 0.0019480000 115376819 0 402718720 3.5303952694 4.3996429443 4.8785405159 788 31.4800000000 0.0150784692 0.0090046322 0.0233512744 0.0076562967 0.3377410000 0.1096240000 0.0579330000 0.0000010000 0.1668200000 0.0019420000 115379595 0 402718720 3.5251777172 4.4005494118 4.8801555634 789 31.5200000000 0.0151020698 0.0090123602 0.0233512744 0.0076548107 0.5351600000 0.1096990000 0.0555350000 0.0310320000 0.1655420000 0.1719160000 115382371 0 402718720 3.5198807716 4.4006204605 4.8812360764 790 31.5600000000 0.0150915738 0.0090200554 0.0233512744 0.0076511074 0.3441270000 0.1096710000 0.0650690000 0.0000010000 0.1660140000 0.0019390000 115385147 0 402718720 3.5147688389 4.4007935524 4.8826942444 791 31.6000000000 0.0150817251 0.0090277187 0.0233512744 0.0076464222 0.4226890000 0.1096910000 0.1124330000 0.0310930000 0.1660830000 0.0019540000 115387923 0 402718720 3.5099227428 4.4010372162 4.8839001656 792 31.6400000000 0.0150830429 0.0090353643 0.0233512744 0.0076416308 0.3918930000 0.1095780000 0.1124410000 0.0000010000 0.1664890000 0.0019250000 115390699 0 402718720 3.5056571960 4.4006567001 4.8852944374 793 31.6800000000 0.0150850303 0.0090429932 0.0233512744 0.0076384750 0.5407700000 0.1096660000 0.0579880000 0.0311260000 0.1671400000 0.1734200000 115393475 0 402718720 3.5018048286 4.3998723030 4.8865065575 794 31.7200000000 0.0150835877 0.0090506010 0.0233512744 0.0076411156 0.3394080000 0.1098010000 0.0582850000 0.0000010000 0.1679470000 0.0019350000 115396251 0 402718720 3.4985013008 4.3987770081 4.8879151344 795 31.7600000000 0.0150802536 0.0090581854 0.0233512744 0.0076503795 0.3687450000 0.1098200000 0.0556090000 0.0311610000 0.1687660000 0.0019460000 115399027 0 402718720 3.4952445030 4.3977527618 4.8892078400 796 31.8000000000 0.0150726167 0.0090657413 0.0233512744 0.0076678022 0.3386980000 0.1098110000 0.0557710000 0.0000010000 0.1697240000 0.0019500000 115401803 0 402718720 3.4920802116 4.3966498375 4.8908762932 797 31.8400000000 0.0151113234 0.0090733267 0.0233512744 0.0076874633 0.5466880000 0.1099770000 0.0556130000 0.0311830000 0.1711260000 0.1773480000 115404579 0 402718720 3.4897077084 4.3955707550 4.8924870491 798 31.8800000000 0.0150987310 0.0090808773 0.0233512744 0.0077056836 0.3378350000 0.1063870000 0.0549480000 0.0000010000 0.1731150000 0.0019420000 115407355 0 402718720 3.4868655205 4.3940782547 4.8937945366 799 31.9200000000 0.0151205398 0.0090884363 0.0233512744 0.0077160539 0.3657640000 0.1101480000 0.0459460000 0.0311800000 0.1750800000 0.0019590000 115410131 0 402718720 3.4842562675 4.3923106194 4.8951983452 800 31.9600000000 0.0150827002 0.0090959292 0.0233512744 0.0077237745 0.3368600000 0.1102670000 0.0459220000 0.0000000000 0.1772640000 0.0019560000 115412907 0 402718720 3.4818847179 4.3902893066 4.8967218399 801 32.0000000000 0.0150736310 0.0091033920 0.0233512744 0.0077367580 0.5616830000 0.1103330000 0.0555890000 0.0311650000 0.1784350000 0.1847180000 115415683 0 402718720 3.4799084663 4.3885941505 4.8987703323 802 32.0400000000 0.0150986463 0.0091108674 0.0233512744 0.0077426438 0.3467540000 0.1103890000 0.0532500000 0.0000000000 0.1796980000 0.0019500000 115418459 0 402718720 3.4778156281 4.3865332603 4.9005703926 803 32.0800000000 0.0150800496 0.0091183010 0.0233512744 0.0077538408 0.3715520000 0.1104850000 0.0463390000 0.0311340000 0.1802370000 0.0018970000 115421235 0 402718720 3.4769480228 4.3861894608 4.9031639099 804 32.1199999990 0.0151074873 0.0091257502 0.0233512744 0.0077703233 0.3468600000 0.1067450000 0.0553680000 0.0000010000 0.1813980000 0.0018900000 115424011 0 402718720 3.4758353233 4.3854436874 4.9051742554 805 32.1600000000 0.0150720598 0.0091331369 0.0233512744 0.0077864194 0.5676730000 0.1068580000 0.0576740000 0.0309360000 0.1823240000 0.1884310000 115426787 0 402718720 3.4748411179 4.3837227821 4.9073748589 806 32.2000000000 0.0150884856 0.0091405257 0.0233512744 0.0078031098 0.3538170000 0.1106600000 0.0558040000 0.0000010000 0.1839400000 0.0019480000 115429563 0 402718720 3.4736046791 4.3821749687 4.9090938568 807 32.2400000000 0.0150986873 0.0091479088 0.0233512744 0.0078205229 0.3762200000 0.1107280000 0.0461410000 0.0304170000 0.1854930000 0.0019650000 115432339 0 402718720 3.4730107784 4.3791165352 4.9110908508 808 32.2800000000 0.0151056871 0.0091552823 0.0233512744 0.0078296248 0.3574970000 0.1108150000 0.0557450000 0.0000010000 0.1875040000 0.0019570000 115435115 0 402718720 3.4718143940 4.3767051697 4.9133591652 809 32.3200000000 0.0150888450 0.0091626167 0.0233512744 0.0078356389 0.5829520000 0.1108550000 0.0556050000 0.0310500000 0.1888360000 0.1951430000 115437891 0 402718720 3.4715929031 4.3729968071 4.9157872200 810 32.3600000000 0.0151186101 0.0091699698 0.0233512744 0.0078424754 0.3536800000 0.1108860000 0.0484010000 0.0000010000 0.1909590000 0.0019540000 115440667 0 402718720 3.4708123207 4.3706545830 4.9178938866 811 32.4000000000 0.0151084093 0.0091772922 0.0233512744 0.0078410332 0.4214420000 0.1109390000 0.0839610000 0.0309980000 0.1920910000 0.0019670000 115443443 0 402718720 3.4697291851 4.3668389320 4.9199810028 812 32.4399999990 0.0151165519 0.0091846065 0.0233512744 0.0078400612 0.3657900000 0.1109230000 0.0578720000 0.0000010000 0.1935500000 0.0019580000 115446219 0 402718720 3.4689629078 4.3633255959 4.9221992493 813 32.4800000000 0.0150803132 0.0091918583 0.0233512744 0.0078402135 0.5841650000 0.1109950000 0.0459470000 0.0310140000 0.1942170000 0.2005310000 115448995 0 402718720 3.4687523842 4.3607463837 4.9252486229 814 32.5200000000 0.0150981508 0.0091991142 0.0233512744 0.0078407330 0.3678790000 0.1110250000 0.0579240000 0.0000010000 0.1954840000 0.0019670000 115451771 0 402718720 3.4681792259 4.3579263687 4.9280862808 815 32.5600000000 0.0150615275 0.0092063073 0.0233512744 0.0078383279 0.3992940000 0.1109740000 0.0577710000 0.0302870000 0.1968040000 0.0019670000 115454547 0 402718720 3.4673619270 4.3548974991 4.9308180809 816 32.6000000000 0.0150765264 0.0092135012 0.0233512744 0.0078363535 0.3712700000 0.1110630000 0.0577240000 0.0000010000 0.1990430000 0.0019690000 115457323 0 402718720 3.4671134949 4.3506264687 4.9341340065 817 32.6400000000 0.0150323957 0.0092206235 0.0233512744 0.0078326127 0.6158570000 0.1110860000 0.0647050000 0.0308820000 0.2007150000 0.2069840000 115460099 0 402718720 3.4663503170 4.3471736908 4.9370250702 818 32.6800000000 0.0150204757 0.0092277138 0.0233512744 0.0078280664 0.3749410000 0.1111140000 0.0576720000 0.0000000000 0.2027020000 0.0019560000 115462875 0 402718720 3.4656968117 4.3435263634 4.9407305717 819 32.7200000000 0.0150380023 0.0092348082 0.0233512744 0.0078247248 0.4039710000 0.1111300000 0.0554240000 0.0301910000 0.2037650000 0.0019670000 115465651 0 402718720 3.4654932022 4.3416051865 4.9449887276 820 32.7599999990 0.0150186950 0.0092418617 0.0233512744 0.0078219032 0.3775890000 0.1111560000 0.0578790000 0.0000000000 0.2051170000 0.0019560000 115468427 0 402718720 3.4648957253 4.3391785622 4.9492588043 821 32.7999999990 0.0149327442 0.0092487933 0.0233512744 0.0078259012 0.6267060000 0.1111900000 0.0651620000 0.0301230000 0.2062040000 0.2125340000 115471203 0 402718720 3.4654138088 4.3371086121 4.9548134804 822 32.8400000000 0.0149724698 0.0092557564 0.0233512744 0.0078495027 0.3804630000 0.1112330000 0.0583270000 0.0000010000 0.2074410000 0.0019680000 115473979 0 402718720 3.4651443958 4.3345675468 4.9597039223 823 32.8800000000 0.0149037838 0.0092626192 0.0233512744 0.0078594626 0.4123030000 0.1112640000 0.0579570000 0.0307360000 0.2088570000 0.0019680000 115476755 0 402718720 3.4645307064 4.3324842453 4.9647130966 824 32.9200000000 0.0149698993 0.0092695455 0.0233512744 0.0078638596 0.3999990000 0.1112840000 0.0745130000 0.0000010000 0.2107370000 0.0019660000 115479531 0 402718720 3.4641706944 4.3316760063 4.9705581665 825 32.9600000000 0.0148788774 0.0092763447 0.0233512744 0.0078765782 0.6285950000 0.1113220000 0.0557450000 0.0306980000 0.2115370000 0.2177890000 115482307 0 402718720 3.4638729095 4.3292255402 4.9765763283 826 33.0000000000 0.0147720380 0.0092829981 0.0233512744 0.0078844755 0.3857650000 0.1113290000 0.0581560000 0.0000010000 0.2128330000 0.0019580000 115485083 0 402718720 3.4634253979 4.3278584480 4.9827547073 827 33.0400000000 0.0146980109 0.0092895458 0.0233512744 0.0079010551 0.4057280000 0.1114330000 0.0463450000 0.0306140000 0.2138600000 0.0019680000 115487859 0 402718720 3.4628810883 4.3246421814 4.9886064529 828 33.0800000000 0.0146539258 0.0092960246 0.0233512744 0.0079280593 0.3862850000 0.1113630000 0.0556750000 0.0000000000 0.2157690000 0.0019570000 115490635 0 402718720 3.4625787735 4.3208298683 4.9941730499 829 33.1199999990 0.0146066155 0.0093024306 0.0233512744 0.0079491463 0.6434390000 0.1113950000 0.0578350000 0.0305060000 0.2179480000 0.2242380000 115493411 0 402718720 3.4618530273 4.3176083565 5.0003871918 830 33.1600000000 0.0144903706 0.0093086811 0.0233512744 0.0079649074 0.3907780000 0.1113890000 0.0553000000 0.0000010000 0.2206080000 0.0019650000 115496187 0 402718720 3.4612102509 4.3140997887 5.0062475204 831 33.2000000000 0.0143416012 0.0093147376 0.0233512744 0.0079825149 0.4133710000 0.1114820000 0.0458320000 0.0295480000 0.2230360000 0.0019660000 115498963 0 402718720 3.4613375664 4.3090124130 5.0130553246 832 33.2400000000 0.0141862324 0.0093205927 0.0233512744 0.0079923173 0.3861070000 0.1114490000 0.0457010000 0.0000010000 0.2254770000 0.0019640000 115501739 0 402718720 3.4606308937 4.3048071861 5.0195326805 833 33.2800000000 0.0140258484 0.0093262413 0.0233512744 0.0079952674 0.6612770000 0.1115370000 0.0576500000 0.0303160000 0.2270520000 0.2332100000 115504515 0 402718720 3.4596762657 4.3013143539 5.0264215469 834 33.3200000000 0.0139696375 0.0093318089 0.0233512744 0.0079993462 0.4086180000 0.1114530000 0.0649840000 0.0000010000 0.2287210000 0.0019520000 115507291 0 402718720 3.4588866234 4.2961797714 5.0329394341 835 33.3600000000 0.0137962420 0.0093371555 0.0233512744 0.0080058730 0.4228320000 0.1115220000 0.0481820000 0.0296210000 0.2300320000 0.0019680000 115510067 0 402718720 3.4575645924 4.2933826447 5.0391206741 836 33.4000000000 0.0136958221 0.0093423693 0.0233512744 0.0080150500 0.4141070000 0.1114880000 0.0672750000 0.0000000000 0.2318640000 0.0019580000 115512843 0 402718720 3.4566779137 4.2896971703 5.0458164215 837 33.4399999990 0.0135466177 0.0093473923 0.0233512744 0.0080304340 0.6735600000 0.1115400000 0.0577730000 0.0300060000 0.2332570000 0.2394640000 115515619 0 402718720 3.4555311203 4.2870082855 5.0522093773 838 33.4800000000 0.0134764295 0.0093523195 0.0233512744 0.0080596837 0.4058860000 0.1115710000 0.0554140000 0.0000000000 0.2354120000 0.0019540000 115518395 0 402718720 3.4551227093 4.2821125984 5.0581946373 839 33.5200000000 0.0133192986 0.0093570477 0.0233512744 0.0080906657 0.4348460000 0.1115310000 0.0528800000 0.0299730000 0.2369640000 0.0019640000 115521171 0 402718720 3.4545810223 4.2794990540 5.0646443367 840 33.5600000000 0.0131152682 0.0093615218 0.0233512744 0.0081117443 0.4118820000 0.1115940000 0.0577420000 0.0000010000 0.2390530000 0.0019540000 115523947 0 402718720 3.4523522854 4.2768273354 5.0693006516 841 33.6000000000 0.0129142907 0.0093657463 0.0233512744 0.0081143119 0.6849650000 0.1116580000 0.0552150000 0.0298730000 0.2403100000 0.2463680000 115526723 0 402718720 3.4509463310 4.2746286392 5.0747814178 842 33.6400000000 0.0127413776 0.0093697553 0.0233512744 0.0081127644 0.4118710000 0.1115940000 0.0547480000 0.0000000000 0.2420280000 0.0019590000 115529499 0 402718720 3.4495279789 4.2723350525 5.0798501968 843 33.6800000000 0.0125573156 0.0093735365 0.0233512744 0.0081126608 0.4454730000 0.1116040000 0.0576800000 0.0298080000 0.2428730000 0.0019690000 115532275 0 402718720 3.4484887123 4.2687792778 5.0850963593 844 33.7200000000 0.0123832244 0.0093771025 0.0233512744 0.0081177720 0.4149960000 0.1115670000 0.0553190000 0.0000010000 0.2446050000 0.0019560000 115535051 0 402718720 3.4477658272 4.2637281418 5.0899744034 845 33.7599999990 0.0121930139 0.0093804350 0.0233512744 0.0081286688 0.6989310000 0.1115060000 0.0576130000 0.0298080000 0.2462090000 0.2522640000 115537827 0 402718720 3.4476866722 4.2603931427 5.0951724052 846 33.7999999990 0.0117897931 0.0093832829 0.0233512744 0.0081357463 0.4180740000 0.1114400000 0.0551560000 0.0000000000 0.2479730000 0.0019550000 115540603 0 402718720 3.4465007782 4.2577433586 5.0997476578 847 33.8400000000 0.0114810253 0.0093857596 0.0233512744 0.0081345956 0.4610300000 0.1114660000 0.0669360000 0.0297200000 0.2493940000 0.0019740000 115543379 0 402718720 3.4456999302 4.2527389526 5.1033849716 848 33.8800000000 0.0111957593 0.0093878940 0.0233512744 0.0081301417 0.4207920000 0.1114610000 0.0550150000 0.0000010000 0.2508150000 0.0019540000 115546155 0 402718720 3.4448411465 4.2490587234 5.1074686050 849 33.9200000000 0.0108165443 0.0093895767 0.0233512744 0.0081253801 0.7001550000 0.1114720000 0.0480820000 0.0289570000 0.2520190000 0.2580820000 115548931 0 402718720 3.4440567493 4.2433156967 5.1110372543 850 33.9600000000 0.0105635552 0.0093909579 0.0233512744 0.0081209261 0.4232910000 0.1114280000 0.0551010000 0.0000000000 0.2532480000 0.0019680000 115551707 0 402718720 3.4432821274 4.2394280434 5.1147055626 851 34.0000000000 0.0103455475 0.0093920796 0.0233512744 0.0081161801 0.4561640000 0.1113970000 0.0576500000 0.0296660000 0.2539120000 0.0019760000 115554483 0 402718720 3.4423933029 4.2363877296 5.1186470985 852 34.0400000000 0.0101858759 0.0093930113 0.0233512744 0.0081114348 0.4275610000 0.1114480000 0.0576010000 0.0000000000 0.2550120000 0.0019630000 115557259 0 402718720 3.4427118301 4.2310724258 5.1225113869 853 34.0800000000 0.0098616853 0.0093935608 0.0233512744 0.0081089823 0.7078700000 0.1114250000 0.0479660000 0.0289200000 0.2560120000 0.2620010000 115560035 0 402718720 3.4417600632 4.2269310951 5.1255068779 854 34.1199999990 0.0095335143 0.0093937246 0.0233512744 0.0081073179 0.4298920000 0.1114140000 0.0574140000 0.0000010000 0.2575730000 0.0019150000 115562811 0 402718720 3.4415268898 4.2241139412 5.1290559769 855 34.1600000000 0.0091073550 0.0093933897 0.0233512744 0.0081081899 0.4578760000 0.1114180000 0.0551720000 0.0295310000 0.2582080000 0.0019750000 115565587 0 402718720 3.4417974949 4.2204065323 5.1325650215 856 34.2000000000 0.0087345447 0.0093926200 0.0233512744 0.0081081164 0.4294750000 0.1113440000 0.0550950000 0.0000010000 0.2594860000 0.0019820000 115568363 0 402718720 3.4413003922 4.2172164917 5.1353907585 857 34.2400000000 0.0083797229 0.0093914381 0.0233512744 0.0081040189 0.7255380000 0.1113920000 0.0576210000 0.0294610000 0.2596900000 0.2658170000 115571139 0 402718720 3.4402499199 4.2158637047 5.1382570267 858 34.2800000000 0.0080995876 0.0093899325 0.0233512744 0.0080994451 0.4422070000 0.1113260000 0.0673130000 0.0000000000 0.2600570000 0.0019650000 115573915 0 402718720 3.4390921593 4.2133712769 5.1406407356 859 34.3200000000 0.0079443324 0.0093882496 0.0233512744 0.0080950212 0.4623220000 0.1113360000 0.0576790000 0.0294910000 0.2602530000 0.0019730000 115576691 0 402718720 3.4394061565 4.2072210312 5.1425852776 860 34.3600000000 0.0075950222 0.0093861644 0.0233512744 0.0080905840 0.4217610000 0.1112770000 0.0456200000 0.0000010000 0.2613290000 0.0019630000 115579467 0 402718720 3.4387748241 4.2020564079 5.1440510750 861 34.4000000000 0.0072228098 0.0093836518 0.0233512744 0.0080862757 0.7269420000 0.1112460000 0.0551080000 0.0295150000 0.2617470000 0.2677530000 115582243 0 402718720 3.4384362698 4.1983604431 5.1465430260 862 34.4400000000 0.0068617458 0.0093807262 0.0233512744 0.0080816080 0.4325560000 0.1112140000 0.0551500000 0.0000010000 0.2627140000 0.0019060000 115585019 0 402718720 3.4383118153 4.1940240860 5.1484928131 863 34.4800000000 0.0065086121 0.0093773981 0.0233512744 0.0080772433 0.4680360000 0.1074690000 0.0639290000 0.0292630000 0.2638200000 0.0019730000 115587795 0 402718720 3.4381721020 4.1874318123 5.1497011185 864 34.5200000000 0.0060881614 0.0093735911 0.0233512744 0.0080729174 0.4344200000 0.1113410000 0.0550270000 0.0000010000 0.2644870000 0.0019750000 115590571 0 402718720 3.4383645058 4.1837186813 5.1514658928 865 34.5600000000 0.0058718715 0.0093695429 0.0233512744 0.0080682496 0.7519930000 0.1112570000 0.0739860000 0.0294310000 0.2649250000 0.2708140000 115593347 0 402718720 3.4374175072 4.1824464798 5.1531739235 866 34.6000000000 0.0058020283 0.0093654234 0.0233512744 0.0080657646 0.4260500000 0.1112720000 0.0457950000 0.0000010000 0.2654300000 0.0019750000 115596123 0 402718720 3.4361810684 4.1809463501 5.1542935371 867 34.6400000000 0.0056588706 0.0093611482 0.0233512744 0.0080624948 0.4668660000 0.1113270000 0.0577840000 0.0287100000 0.2654880000 0.0019790000 115598899 0 402718720 3.4364159107 4.1781578064 5.1559224129 868 34.6800000000 0.0056493687 0.0093568720 0.0233512744 0.0080583791 0.4291650000 0.1114400000 0.0481480000 0.0000010000 0.2660200000 0.0019700000 115601675 0 402718720 3.4357917309 4.1743750572 5.1566791534 869 34.7200000000 0.0054620504 0.0093523900 0.0233512744 0.0080541378 0.7456700000 0.1113440000 0.0646050000 0.0294260000 0.2664500000 0.2722700000 115604451 0 402718720 3.4363894463 4.1708836555 5.1577296257 870 34.7600000000 0.0053618466 0.0093478032 0.0233512744 0.0080497817 0.4279320000 0.1113050000 0.0456530000 0.0000000000 0.2674080000 0.0019720000 115607227 0 402718720 3.4354293346 4.1682219505 5.1582021713 871 34.8000000000 0.0053467890 0.0093432096 0.0233512744 0.0080451552 0.4551610000 0.1113130000 0.0432620000 0.0294210000 0.2675890000 0.0019750000 115610003 0 402718720 3.4344561100 4.1663880348 5.1589355469 872 34.8400000000 0.0052606040 0.0093385277 0.0233512744 0.0080409078 0.4288150000 0.1112930000 0.0457460000 0.0000000000 0.2682310000 0.0019620000 115612779 0 402718720 3.4333724976 4.1631898880 5.1595630646 873 34.8800000000 0.0051375269 0.0093337156 0.0233512744 0.0080364544 0.7395220000 0.1113230000 0.0552000000 0.0286800000 0.2684710000 0.2742500000 115615555 0 402718720 3.4329683781 4.1610980034 5.1609392166 874 34.9200000000 0.0051903953 0.0093289749 0.0233512744 0.0080325619 0.4373470000 0.1101130000 0.0546690000 0.0000000000 0.2690050000 0.0019660000 115618331 0 402718720 3.4322733879 4.1598892212 5.1621251106 875 34.9600000000 0.0050567188 0.0093240923 0.0233512744 0.0080290433 0.4616200000 0.1112740000 0.0482340000 0.0293810000 0.2691550000 0.0019690000 115621107 0 402718720 3.4307456017 4.1599001884 5.1636037827 876 35.0000000000 0.0051328568 0.0093193078 0.0233512744 0.0080253122 0.4324100000 0.1113290000 0.0483180000 0.0000000000 0.2691820000 0.0019690000 115623883 0 402718720 3.4299657345 4.1590905190 5.1649498940 877 35.0400000000 0.0050672702 0.0093144594 0.0233512744 0.0080207473 0.7346350000 0.1112900000 0.0482800000 0.0293350000 0.2691650000 0.2749640000 115626659 0 402718720 3.4290809631 4.1587533951 5.1663470268 878 35.0800000000 0.0051806886 0.0093097513 0.0233512744 0.0080163208 0.4404360000 0.1097340000 0.0580840000 0.0000010000 0.2690390000 0.0019710000 115629435 0 402718720 3.4280533791 4.1590929031 5.1675038338 879 35.1200000000 0.0051499410 0.0093050188 0.0233512744 0.0080117793 0.4704110000 0.1113370000 0.0579930000 0.0286590000 0.2688380000 0.0019760000 115632211 0 402718720 3.4272058010 4.1580247879 5.1685924530 880 35.1600000000 0.0051157954 0.0093002584 0.0233512744 0.0080075882 0.4394230000 0.1113090000 0.0556810000 0.0000000000 0.2688620000 0.0019600000 115634987 0 402718720 3.4265775681 4.1589345932 5.1699342728 881 35.2000000000 0.0051807570 0.0092955824 0.0233512744 0.0080037246 0.7325500000 0.1113280000 0.0482660000 0.0286490000 0.2684280000 0.2742700000 115637763 0 402718720 3.4255299568 4.1588153839 5.1712384224 882 35.2400000000 0.0050666705 0.0092907877 0.0233512744 0.0080003570 0.4418030000 0.1113900000 0.0579620000 0.0000000000 0.2688630000 0.0019710000 115640539 0 402718720 3.4260826111 4.1547574997 5.1718707085 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 11:12:25 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002920 0.0000002920 0.0000002920 -nan 0.9156550000 0.1737840000 0.0281210000 0.0739490000 0.0000030000 0.6396980000 106139198 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0040127714 0.0020065317 0.0040127714 0.0032323198 0.2777470000 0.1732370000 0.0260730000 0.0739220000 0.0000010000 0.0044820000 113224451 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0039232424 0.0026454353 0.0040127714 0.0045263772 0.2775290000 0.1731680000 0.0260580000 0.0737850000 0.0000000000 0.0044820000 113227619 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0033563883 0.0028231735 0.0040127714 0.0050261389 0.9143100000 0.1938330000 0.0262140000 0.0739080000 0.6158350000 0.0044820000 113230795 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0020580813 0.0026701551 0.0040127714 0.0052619329 1.6246180000 0.1726770000 0.1304240000 0.0738430000 0.6144820000 0.6331550000 113233955 0 402718720 4.0005683899 4.0062360764 4.0028858185 6 0.2000000000 0.0022257259 0.0025960836 0.0040127714 0.0049518983 0.5680650000 0.1003500000 0.0647050000 0.0000010000 0.4010560000 0.0019150000 113237531 0 402718720 4.0035071373 3.9963686466 4.0019783974 7 0.2400000000 0.0022985912 0.0025535847 0.0040127714 0.0047230099 0.5964650000 0.1010380000 0.0574770000 0.0343360000 0.4016570000 0.0019170000 113240307 0 402718720 4.0037336349 3.9863734245 3.9988579750 8 0.2800000000 0.0024033717 0.0025348080 0.0040127714 0.0043795128 0.5784360000 0.1156850000 0.0574900000 0.0000010000 0.4032940000 0.0019190000 113243083 0 402718720 4.0014562607 3.9884219170 3.9979789257 9 0.3200000000 0.0023827848 0.0025179166 0.0040127714 0.0050603412 0.9984880000 0.1010900000 0.0603440000 0.0343570000 0.3970960000 0.4055550000 113246627 0 402718720 4.0003557205 3.9923224449 4.0009708405 10 0.3600000000 0.0024723008 0.0025133550 0.0040127714 0.0047860726 0.5809420000 0.1202450000 0.0576930000 0.0000000000 0.4010370000 0.0019170000 113251003 0 402718720 3.9983146191 3.9848935604 3.9990823269 11 0.4000000000 0.0026046433 0.0025216539 0.0040127714 0.0045841143 0.6246090000 0.1010480000 0.0878080000 0.0343920000 0.3993960000 0.0019160000 113253779 0 402718720 3.9983012676 3.9888913631 3.9978275299 12 0.4400000000 0.0026440211 0.0025318512 0.0040127714 0.0046244994 0.5612500000 0.1004990000 0.0579430000 0.0000010000 0.4008460000 0.0019130000 113256555 0 402718720 3.9992923737 3.9987778664 4.0008053780 13 0.4800000000 0.0025809682 0.0025356294 0.0040127714 0.0044315971 1.0116320000 0.1111100000 0.0603630000 0.0343550000 0.3997590000 0.4059920000 113259331 0 402718720 4.0013046265 3.9965155125 4.0008144379 14 0.5200000000 0.0027121380 0.0025482372 0.0040127714 0.0043591954 0.5710140000 0.1007060000 0.0671700000 0.0000000000 0.4011730000 0.0019120000 113262107 0 402718720 4.0040993690 3.9890573025 3.9980893135 15 0.5600000000 0.0027319994 0.0025604880 0.0040127714 0.0042933368 0.6228610000 0.1003890000 0.0878360000 0.0343960000 0.3981440000 0.0020240000 113264883 0 402718720 4.0069050789 3.9907155037 3.9979007244 16 0.6000000000 0.0027423620 0.0025718551 0.0040127714 0.0041517551 0.5600340000 0.1004090000 0.0577520000 0.0000010000 0.3999020000 0.0019180000 113267659 0 402718720 4.0079178810 3.9920563698 3.9981825352 17 0.6400000000 0.0027839276 0.0025843300 0.0040127714 0.0040370770 1.0128990000 0.1121040000 0.0602740000 0.0343720000 0.3982410000 0.4078480000 113271971 0 402718720 4.0076699257 3.9883072376 3.9963228703 18 0.6800000000 0.0028498853 0.0025990830 0.0040127714 0.0039179105 0.5694580000 0.1009410000 0.0646850000 0.0000010000 0.4018590000 0.0019150000 113277947 0 402718720 4.0069394112 3.9893963337 3.9949455261 19 0.7200000000 0.0028617827 0.0026129093 0.0040127714 0.0039443988 0.6060790000 0.1006800000 0.0681320000 0.0343850000 0.4009020000 0.0019210000 113280723 0 402718720 4.0073871613 3.9935777187 3.9951608181 20 0.7600000000 0.0029027741 0.0026274026 0.0040127714 0.0042036664 0.5627310000 0.1009440000 0.0577500000 0.0000010000 0.4020680000 0.0019110000 113283499 0 402718720 4.0069408417 3.9922833443 3.9925367832 21 0.8000000000 0.0029292013 0.0026417740 0.0040127714 0.0043504855 1.0012310000 0.1006660000 0.0578140000 0.0343700000 0.4009180000 0.4074050000 113286275 0 402718720 4.0093941689 3.9955034256 3.9927725792 22 0.8400000000 0.0029451062 0.0026555618 0.0040127714 0.0042740080 0.5786140000 0.1006200000 0.0748440000 0.0000010000 0.4011750000 0.0019140000 113289051 0 402718720 4.0094890594 3.9983549118 3.9931788445 23 0.8800000000 0.0030370620 0.0026721487 0.0040127714 0.0042449337 0.6038840000 0.1094520000 0.0550670000 0.0345040000 0.4028770000 0.0019200000 113291827 0 402718720 4.0121717453 3.9920437336 3.9892230034 24 0.9200000000 0.0032707753 0.0026970915 0.0040127714 0.0042405392 0.5664070000 0.1011250000 0.0592230000 0.0000010000 0.4040780000 0.0019190000 113294603 0 402718720 4.0143847466 3.9935011864 3.9894285202 25 0.9600000000 0.0032610116 0.0027196483 0.0040127714 0.0041528139 1.0049710000 0.1014750000 0.0578790000 0.0345310000 0.4010290000 0.4099910000 113297379 0 402718720 4.0145549774 3.9904427528 3.9862995148 26 1.0000000000 0.0033026387 0.0027420710 0.0040127714 0.0040694828 0.5654430000 0.0994100000 0.0572360000 0.0000010000 0.4068190000 0.0019140000 113300155 0 402718720 4.0128369331 3.9902217388 3.9853107929 27 1.0400000000 0.0033008559 0.0027627668 0.0040127714 0.0040029608 0.6238690000 0.1149010000 0.0679080000 0.0345550000 0.4045180000 0.0019170000 113302931 0 402718720 4.0138897896 3.9860486984 3.9828360081 28 1.0800000000 0.0033147153 0.0027824792 0.0040127714 0.0039328510 0.5720810000 0.1025980000 0.0590480000 0.0000010000 0.4084580000 0.0019110000 113305707 0 402718720 4.0126261711 3.9840126038 3.9814455509 29 1.1200000000 0.0033198211 0.0028010082 0.0040127714 0.0039433032 1.0128490000 0.1030210000 0.0551660000 0.0345050000 0.4070050000 0.4130810000 113308483 0 402718720 4.0137228966 3.9820182323 3.9802529812 30 1.1600000000 0.0034067915 0.0028212010 0.0040127714 0.0039087989 0.5729650000 0.1033810000 0.0579030000 0.0000000000 0.4096950000 0.0019130000 113311259 0 402718720 4.0170226097 3.9830427170 3.9798839092 31 1.2000000000 0.0035715012 0.0028454043 0.0040127714 0.0039120434 0.5949820000 0.1036330000 0.0480950000 0.0340940000 0.4071640000 0.0019250000 113314035 0 402718720 4.0219497681 3.9843258858 3.9785232544 32 1.2400000000 0.0035979643 0.0028689218 0.0040127714 0.0039572953 0.5709730000 0.1043690000 0.0551960000 0.0000000000 0.4093980000 0.0019360000 113316811 0 402718720 4.0223503113 3.9875771999 3.9773924351 33 1.2800000000 0.0036611217 0.0028929278 0.0040127714 0.0041814200 1.0234180000 0.1141360000 0.0578150000 0.0347110000 0.4040010000 0.4126760000 113322659 0 402718720 4.0236759186 3.9915440083 3.9773106575 34 1.3200000000 0.0036390156 0.0029148716 0.0040127714 0.0043693847 0.5806620000 0.1061980000 0.0577430000 0.0000010000 0.4147390000 0.0019040000 113331835 0 402718720 4.0318417549 3.9939956665 3.9749901295 35 1.3600000000 0.0035942947 0.0029342837 0.0040127714 0.0043074463 0.6095050000 0.1070530000 0.0547700000 0.0346470000 0.4110500000 0.0019050000 113334611 0 402718720 4.0310921669 3.9926083088 3.9733870029 36 1.4000000000 0.0036857426 0.0029551575 0.0040127714 0.0042549371 0.5922440000 0.1277440000 0.0484470000 0.0000010000 0.4140670000 0.0019000000 113337387 0 402718720 4.0315017700 3.9903364182 3.9700062275 37 1.4400000000 0.0035898215 0.0029723106 0.0040127714 0.0041967456 1.0275970000 0.1081740000 0.0575520000 0.0347960000 0.4088740000 0.4181210000 113340163 0 402718720 4.0340137482 3.9892373085 3.9676895142 38 1.4800000000 0.0038698253 0.0029959294 0.0040127714 0.0041400052 0.5833440000 0.1088250000 0.0575410000 0.0000010000 0.4149870000 0.0019070000 113342939 0 402718720 4.0341835022 3.9894325733 3.9674465656 39 1.5200000000 0.0037605835 0.0030155359 0.0040127714 0.0041060948 0.6161700000 0.1091130000 0.0573020000 0.0347480000 0.4130090000 0.0019140000 113345715 0 402718720 4.0347733498 3.9901697636 3.9665136337 40 1.5600000000 0.0039174468 0.0030380837 0.0040127714 0.0043027630 0.5866620000 0.1093310000 0.0575870000 0.0000000000 0.4177530000 0.0019040000 113348491 0 402718720 4.0378718376 3.9905848503 3.9656789303 41 1.6000000000 0.0039443555 0.0030601879 0.0040127714 0.0045485650 1.0216640000 0.1064890000 0.0448790000 0.0345870000 0.4147070000 0.4209130000 113351267 0 402718720 4.0434789658 3.9923052788 3.9650862217 42 1.6400000000 0.0044113849 0.0030923592 0.0044113849 0.0045186470 0.5813960000 0.1069520000 0.0550700000 0.0000010000 0.4173750000 0.0019090000 113354043 0 402718720 4.0444531441 3.9923741817 3.9638378620 43 1.6800000000 0.0042231237 0.0031186561 0.0044113849 0.0044999138 0.6324070000 0.1193310000 0.0599560000 0.0349870000 0.4161870000 0.0018510000 113356819 0 402718720 4.0460572243 3.9921064377 3.9622681141 44 1.7200000000 0.0044247922 0.0031483410 0.0044247922 0.0044691722 0.5882800000 0.1102240000 0.0574720000 0.0000000000 0.4185850000 0.0019040000 113359595 0 402718720 4.0482449532 3.9931311607 3.9621045589 45 1.7600000000 0.0045941151 0.0031804693 0.0045941151 0.0046644492 1.0409300000 0.1100530000 0.0548640000 0.0350470000 0.4158610000 0.4249990000 113362371 0 402718720 4.0502967834 3.9947745800 3.9609956741 46 1.8000000000 0.0046150438 0.0032116557 0.0046150438 0.0047519706 0.6025300000 0.1143740000 0.0669330000 0.0000010000 0.4192230000 0.0019040000 113365147 0 402718720 4.0516996384 3.9956297874 3.9602923393 47 1.8400000000 0.0042889095 0.0032345760 0.0046150438 0.0047472409 0.6216920000 0.1101480000 0.0572130000 0.0350470000 0.4172850000 0.0019030000 113367923 0 402718720 4.0530538559 3.9980163574 3.9598886967 48 1.8800000000 0.0045054089 0.0032610517 0.0046150438 0.0047346354 0.5874260000 0.1101650000 0.0550670000 0.0000010000 0.4201960000 0.0019010000 113370699 0 402718720 4.0552129745 3.9992587566 3.9601185322 49 1.9200000000 0.0044517783 0.0032853522 0.0046150438 0.0047600464 1.0584770000 0.1189090000 0.0597120000 0.0355310000 0.4186200000 0.4256030000 113373475 0 402718720 4.0561485291 3.9968552589 3.9582502842 50 1.9600000000 0.0045644990 0.0033109352 0.0046150438 0.0047332648 0.6084980000 0.1103530000 0.0740550000 0.0000000000 0.4220890000 0.0018990000 113376251 0 402718720 4.0514593124 3.9992833138 3.9562706947 51 2.0000000000 0.0044318852 0.0033329146 0.0046150438 0.0047265786 0.6299380000 0.1104160000 0.0575670000 0.0349570000 0.4249920000 0.0019010000 113379027 0 402718720 4.0505089760 4.0037045479 3.9571378231 52 2.0400000000 0.0046657328 0.0033585457 0.0046657328 0.0047021323 0.6151730000 0.1356840000 0.0577530000 0.0000000000 0.4197290000 0.0018960000 113381803 0 402718720 4.0509791374 4.0014724731 3.9568996429 53 2.0800000000 0.0045960541 0.0033818949 0.0046657328 0.0046667830 1.0673260000 0.1107720000 0.0737430000 0.0353510000 0.4198440000 0.4275110000 113384579 0 402718720 4.0511884689 3.9970257282 3.9545528889 54 2.1200000000 0.0045519783 0.0034035631 0.0046657328 0.0046840577 0.6046820000 0.1105630000 0.0694010000 0.0000000000 0.4227090000 0.0019000000 113387355 0 402718720 4.0513319969 3.9984076023 3.9549889565 55 2.1600000000 0.0044716275 0.0034229825 0.0046657328 0.0046738342 0.6477160000 0.1291370000 0.0601460000 0.0354920000 0.4209240000 0.0019030000 113390131 0 402718720 4.0520601273 4.0006947517 3.9550182819 56 2.2000000000 0.0043942085 0.0034403258 0.0046657328 0.0046764948 0.6037790000 0.1109190000 0.0669700000 0.0000010000 0.4238830000 0.0018980000 113392907 0 402718720 4.0533800125 3.9998557568 3.9541141987 57 2.2400000000 0.0045143897 0.0034591690 0.0046657328 0.0046969761 1.0547110000 0.1106960000 0.0548620000 0.0355250000 0.4228360000 0.4306800000 113395683 0 402718720 4.0539045334 3.9971239567 3.9518086910 58 2.2800000000 0.0045525744 0.0034780208 0.0046657328 0.0048543186 0.5950980000 0.1107080000 0.0575800000 0.0000010000 0.4247980000 0.0019010000 113398459 0 402718720 4.0575075150 3.9987397194 3.9523828030 59 2.3200000000 0.0047503761 0.0034995862 0.0047503761 0.0050199395 0.6289080000 0.1107960000 0.0573500000 0.0351640000 0.4235760000 0.0019070000 113401235 0 402718720 4.0615100861 4.0015845299 3.9516880512 60 2.3600000000 0.0049287248 0.0035234052 0.0049287248 0.0050717733 0.6242120000 0.1291230000 0.0703230000 0.0000000000 0.4227430000 0.0019030000 113404011 0 402718720 4.0651259422 3.9972057343 3.9490871429 61 2.4000000000 0.0049401396 0.0035466303 0.0049401396 0.0050619022 1.0786540000 0.1238090000 0.0576650000 0.0357630000 0.4266320000 0.4346660000 113406787 0 402718720 4.0648927689 3.9946084023 3.9476466179 62 2.4400000000 0.0046699937 0.0035647491 0.0049401396 0.0050983872 0.5949630000 0.1071210000 0.0569800000 0.0000010000 0.4288400000 0.0019050000 113409563 0 402718720 4.0665540695 3.9957406521 3.9481992722 63 2.4800000000 0.0050027980 0.0035875753 0.0050027980 0.0051367729 0.6340750000 0.1110620000 0.0573440000 0.0358500000 0.4277950000 0.0019090000 113412339 0 402718720 4.0733308792 3.9973218441 3.9481511116 64 2.5200000000 0.0049056760 0.0036081706 0.0050027980 0.0051108918 0.5988480000 0.1110710000 0.0551370000 0.0000010000 0.4306170000 0.0019050000 113415115 0 402718720 4.0755009651 3.9931821823 3.9442312717 65 2.5600000000 0.0049635922 0.0036290232 0.0050027980 0.0051017275 1.1108260000 0.1111730000 0.0951100000 0.0359860000 0.4302140000 0.4382170000 113424035 0 402718720 4.0765681267 3.9943192005 3.9443941116 66 2.6000000000 0.0050756987 0.0036509425 0.0050756987 0.0050636549 0.5939190000 0.1111580000 0.0481260000 0.0000010000 0.4326030000 0.0019070000 113439611 0 402718720 4.0738821030 3.9897673130 3.9425475597 67 2.6400000000 0.0051368088 0.0036731197 0.0051368088 0.0050957446 0.6370310000 0.1112400000 0.0548710000 0.0360870000 0.4327990000 0.0019100000 113442387 0 402718720 4.0741081238 3.9883644581 3.9407348633 68 2.6800000000 0.0051934300 0.0036954772 0.0051934300 0.0051677433 0.6416100000 0.1393780000 0.0646580000 0.0000010000 0.4355270000 0.0019150000 113445163 0 402718720 4.0791983604 3.9858870506 3.9403738976 69 2.7200000000 0.0049865954 0.0037141890 0.0051934300 0.0051846738 1.0801770000 0.1113800000 0.0548440000 0.0361960000 0.4350050000 0.4426250000 113447939 0 402718720 4.0803523064 3.9865238667 3.9391908646 70 2.7600000000 0.0050990144 0.0037339722 0.0051934300 0.0052333243 0.6056820000 0.1113900000 0.0551490000 0.0000010000 0.4371030000 0.0019120000 113450715 0 402718720 4.0830793381 3.9879851341 3.9385216236 71 2.8000000000 0.0052180174 0.0037548743 0.0052180174 0.0052796029 0.6412650000 0.1113870000 0.0549370000 0.0362850000 0.4366110000 0.0019140000 113453491 0 402718720 4.0858368874 3.9886476994 3.9367866516 72 2.8400000000 0.0051647141 0.0037744554 0.0052180174 0.0052992146 0.5979350000 0.1113910000 0.0456490000 0.0000010000 0.4388570000 0.0019070000 113456267 0 402718720 4.0873847008 3.9884057045 3.9358909130 73 2.8800000000 0.0051247515 0.0037929526 0.0052180174 0.0053408292 1.0780820000 0.1114770000 0.0455890000 0.0363420000 0.4384740000 0.4460670000 113459043 0 402718720 4.0898084641 3.9910185337 3.9336442947 74 2.9200000000 0.0051765218 0.0038116495 0.0052180174 0.0054583881 0.6001680000 0.1115320000 0.0456620000 0.0000010000 0.4409300000 0.0019090000 113461819 0 402718720 4.0917582512 3.9908313751 3.9306187630 75 2.9600000000 0.0052652997 0.0038310315 0.0052652997 0.0055001550 0.6550870000 0.1225570000 0.0575970000 0.0366250000 0.4362550000 0.0019110000 113464595 0 402718720 4.0974493027 3.9907934666 3.9291739464 76 3.0000000000 0.0052243350 0.0038493644 0.0052652997 0.0055208855 0.6012800000 0.1116120000 0.0455970000 0.0000000000 0.4420290000 0.0019030000 113467371 0 402718720 4.1008691788 3.9922552109 3.9274508953 77 3.0400000000 0.0051044035 0.0038656636 0.0052652997 0.0055433276 1.0819140000 0.1075770000 0.0473290000 0.0364030000 0.4413270000 0.4491380000 113470147 0 402718720 4.1035346985 3.9928438663 3.9264152050 78 3.0800000000 0.0050205337 0.0038804697 0.0052652997 0.0055146192 0.6123960000 0.1119180000 0.0548910000 0.0000000000 0.4435490000 0.0018980000 113472923 0 402718720 4.1065578461 3.9903247356 3.9228420258 79 3.1200000000 0.0049576955 0.0038941054 0.0052652997 0.0055358879 0.6340320000 0.1076050000 0.0446980000 0.0365720000 0.4431180000 0.0018960000 113475699 0 402718720 4.1102123260 3.9917151928 3.9223756790 80 3.1600000000 0.0049895360 0.0039077983 0.0052652997 0.0055198139 0.6120490000 0.1076620000 0.0569070000 0.0000010000 0.4454480000 0.0018880000 113478475 0 402718720 4.1140623093 3.9913604259 3.9195008278 81 3.2000000000 0.0049960348 0.0039212333 0.0052652997 0.0054986338 1.1138680000 0.1245190000 0.0536200000 0.0367360000 0.4449310000 0.4539130000 113481251 0 402718720 4.1196751595 3.9899206161 3.9178891182 82 3.2400000000 0.0049639656 0.0039339496 0.0052652997 0.0054715627 0.6116040000 0.1079290000 0.0543060000 0.0000010000 0.4473500000 0.0018750000 113484027 0 402718720 4.1236553192 3.9884662628 3.9155747890 83 3.2800000000 0.0050082733 0.0039468932 0.0052652997 0.0054585059 0.6506630000 0.1116650000 0.0538540000 0.0367840000 0.4463310000 0.0018810000 113486803 0 402718720 4.1255698204 3.9883010387 3.9134457111 84 3.3200000000 0.0050187325 0.0039596532 0.0052652997 0.0054347451 0.6052520000 0.1096910000 0.0447430000 0.0000000000 0.4487980000 0.0018720000 113489579 0 402718720 4.1318254471 3.9879736900 3.9106564522 85 3.3600000000 0.0050366828 0.0039723242 0.0052652997 0.0054051511 1.1217410000 0.1350740000 0.0467290000 0.0369650000 0.4466780000 0.4561390000 113492355 0 402718720 4.1423039436 3.9913547039 3.9105973244 86 3.4000000000 0.0050756452 0.0039851535 0.0052652997 0.0054191978 0.6177370000 0.1122070000 0.0540320000 0.0000000000 0.4494770000 0.0018660000 113495131 0 402718720 4.1448736191 3.9936723709 3.9082918167 87 3.4400000000 0.0051077991 0.0039980575 0.0052652997 0.0054139459 0.6466020000 0.1078920000 0.0531670000 0.0366940000 0.4468250000 0.0018700000 113497907 0 402718720 4.1470718384 3.9930238724 3.9054143429 88 3.4800000000 0.0050761485 0.0040103085 0.0052652997 0.0053890187 0.6089480000 0.1119570000 0.0468900000 0.0000010000 0.4480830000 0.0018610000 113500683 0 402718720 4.1524519920 3.9958236217 3.9047410488 89 3.5200000000 0.0050717467 0.0040222348 0.0052652997 0.0053719035 1.1058430000 0.1118840000 0.0511020000 0.0370560000 0.4474000000 0.4582440000 113503459 0 402718720 4.1555032730 3.9961369038 3.9035372734 90 3.5600000000 0.0053065773 0.0040365052 0.0053065773 0.0053451723 0.6293050000 0.1226150000 0.0559430000 0.0000000000 0.4487290000 0.0018570000 113506235 0 402718720 4.1586585045 3.9964354038 3.9019558430 91 3.6000000000 0.0053630038 0.0040510821 0.0053630038 0.0053808990 0.6535970000 0.1118840000 0.0584180000 0.0371690000 0.4441040000 0.0018610000 113509011 0 402718720 4.1651101112 3.9967026711 3.9009869099 92 3.6400000000 0.0052853269 0.0040644978 0.0053630038 0.0054540982 0.6138500000 0.1102910000 0.0536730000 0.0000010000 0.4478700000 0.0018570000 113511787 0 402718720 4.1743369102 3.9995176792 3.9010283947 93 3.6800000000 0.0052669668 0.0040774276 0.0053630038 0.0054682077 1.1067250000 0.1118970000 0.0534410000 0.0365760000 0.4466480000 0.4580030000 113514563 0 402718720 4.1824121475 4.0035519600 3.8995797634 94 3.7200000000 0.0052438350 0.0040898362 0.0053630038 0.0054451667 0.6438170000 0.1298940000 0.0598750000 0.0000010000 0.4520320000 0.0018490000 113517339 0 402718720 4.1906890869 4.0027933121 3.8970139027 95 3.7600000000 0.0052345046 0.0041018853 0.0053630038 0.0054178963 0.6623160000 0.1239450000 0.0531420000 0.0370080000 0.4462000000 0.0018520000 113520115 0 402718720 4.1967506409 4.0028181076 3.8945457935 96 3.8000000000 0.0052892626 0.0041142539 0.0053630038 0.0054027585 0.6059510000 0.1119710000 0.0442120000 0.0000010000 0.4477600000 0.0018450000 113522891 0 402718720 4.2042808533 4.0015439987 3.8925478458 97 3.8400000000 0.0052581476 0.0041260466 0.0053630038 0.0053768291 1.0965850000 0.1101540000 0.0440290000 0.0369330000 0.4465150000 0.4587860000 113525667 0 402718720 4.2121443748 4.0030817986 3.8894498348 98 3.8800000000 0.0052906871 0.0041379307 0.0053630038 0.0053500678 0.6155170000 0.1120260000 0.0532190000 0.0000010000 0.4482590000 0.0018450000 113528443 0 402718720 4.2206373215 4.0032105446 3.8886256218 99 3.9200000000 0.0052909115 0.0041495769 0.0053630038 0.0053601522 0.6670480000 0.1331350000 0.0462930000 0.0370760000 0.4477950000 0.0025530000 113531219 0 402718720 4.2288546562 4.0025620461 3.8867139816 100 3.9600000000 0.0053553698 0.0041616349 0.0053630038 0.0053350662 0.6215440000 0.1183660000 0.0533420000 0.0000010000 0.4478180000 0.0018460000 113533995 0 402718720 4.2364711761 4.0030851364 3.8862876892 101 4.0000000000 0.0053385310 0.0041732873 0.0053630038 0.0053244566 1.1084400000 0.1120740000 0.0531870000 0.0369970000 0.4468550000 0.4591490000 113536771 0 402718720 4.2450804710 4.0052132607 3.8849759102 102 4.0400000000 0.0054634884 0.0041859363 0.0054634884 0.0053351155 0.6184130000 0.1120890000 0.0533520000 0.0000000000 0.4509520000 0.0018460000 113539547 0 402718720 4.2498078346 4.0046291351 3.8829164505 103 4.0800000000 0.0054653785 0.0041983581 0.0054653785 0.0053097892 0.6510660000 0.1121100000 0.0531800000 0.0369110000 0.4468970000 0.0017920000 113542323 0 402718720 4.2578520775 4.0080585480 3.8836960793 104 4.1200000000 0.0054960302 0.0042108357 0.0054960302 0.0052851005 0.6101640000 0.1080380000 0.0528130000 0.0000010000 0.4472600000 0.0018780000 113545099 0 402718720 4.2683234215 4.0106892586 3.8829593658 105 4.1600000000 0.0055246749 0.0042233485 0.0055246749 0.0052773632 1.1090540000 0.1224490000 0.0441600000 0.0369880000 0.4464720000 0.4588070000 113547875 0 402718720 4.2748832703 4.0120396614 3.8827350140 106 4.2000000000 0.0056007728 0.0042363430 0.0056007728 0.0052895554 0.6153810000 0.1120920000 0.0534840000 0.0000010000 0.4478310000 0.0017930000 113550651 0 402718720 4.2819352150 4.0102195740 3.8801758289 107 4.2400000000 0.0055414457 0.0042485403 0.0056007728 0.0052669828 0.6433900000 0.1125130000 0.0463670000 0.0369180000 0.4455610000 0.0018490000 113553427 0 402718720 4.2897701263 4.0092830658 3.8789701462 108 4.2800000000 0.0055909944 0.0042609704 0.0056007728 0.0052510152 0.6302320000 0.1248890000 0.0557740000 0.0000010000 0.4475340000 0.0018510000 113556203 0 402718720 4.2984523773 4.0095047951 3.8772041798 109 4.3200000000 0.0055099106 0.0042724286 0.0056007728 0.0052311126 1.1061090000 0.1121510000 0.0532670000 0.0370680000 0.4457810000 0.4576570000 113558979 0 402718720 4.3154935837 4.0090885162 3.8746540546 110 4.3600000000 0.0056754397 0.0042851832 0.0056754397 0.0052284424 0.6420670000 0.1344130000 0.0571550000 0.0000010000 0.4484530000 0.0018530000 113561755 0 402718720 4.3276238441 4.0103363991 3.8738803864 111 4.4000000000 0.0056730574 0.0042976866 0.0056754397 0.0052049857 0.6509770000 0.1121180000 0.0561650000 0.0367780000 0.4438730000 0.0018540000 113564531 0 402718720 4.3374409676 4.0094919205 3.8721804619 112 4.4400000000 0.0056493315 0.0043097548 0.0056754397 0.0051899401 0.6009570000 0.1080490000 0.0445010000 0.0000010000 0.4463650000 0.0018530000 113567307 0 402718720 4.3432354927 4.0052833557 3.8694496155 113 4.4800000000 0.0056214072 0.0043213624 0.0056754397 0.0051667295 1.0958880000 0.1121360000 0.0443800000 0.0363570000 0.4457300000 0.4570940000 113570083 0 402718720 4.3522453308 4.0045685768 3.8688046932 114 4.5200000000 0.0056883688 0.0043333537 0.0056883688 0.0051504359 0.6141730000 0.1121360000 0.0536870000 0.0000010000 0.4463050000 0.0018530000 113572859 0 402718720 4.3631119728 4.0046496391 3.8679351807 115 4.5600000000 0.0056261267 0.0043445952 0.0056883688 0.0051374012 0.6554610000 0.1121510000 0.0562800000 0.0369180000 0.4480570000 0.0018590000 113575635 0 402718720 4.3730711937 4.0026664734 3.8666355610 116 4.6000000000 0.0056090951 0.0043554960 0.0056883688 0.0051172922 0.6169020000 0.1121600000 0.0559600000 0.0000010000 0.4467090000 0.0018750000 113578411 0 402718720 4.3809509277 3.9996459484 3.8650290966 117 4.6400000000 0.0056395610 0.0043664709 0.0056883688 0.0051214322 1.0988840000 0.1121570000 0.0470540000 0.0366510000 0.4457640000 0.4570610000 113581187 0 402718720 4.3884038925 3.9971790314 3.8638875484 118 4.6800000000 0.0056643169 0.0043774696 0.0056883688 0.0051348048 0.6014480000 0.1081590000 0.0440330000 0.0000010000 0.4472030000 0.0018550000 113583963 0 402718720 4.3975477219 3.9972617626 3.8635473251 119 4.7200000000 0.0056118076 0.0043878422 0.0056883688 0.0051733845 0.6504430000 0.1123070000 0.0535440000 0.0365780000 0.4459550000 0.0018620000 113586739 0 402718720 4.4116582870 3.9979138374 3.8654170036 120 4.7600000000 0.0057087955 0.0043988502 0.0057087955 0.0051519612 0.6270680000 0.1231600000 0.0557870000 0.0000010000 0.4460590000 0.0018550000 113589515 0 402718720 4.4229173660 3.9999046326 3.8668234348 121 4.8000000000 0.0056679980 0.0044093390 0.0057087955 0.0051477226 1.1030650000 0.1123250000 0.0536540000 0.0360460000 0.4449850000 0.4558540000 113592291 0 402718720 4.4314265251 3.9985029697 3.8652963638 122 4.8400000000 0.0057426281 0.0044202676 0.0057426281 0.0051465605 0.6174700000 0.1251130000 0.0445560000 0.0000000000 0.4457360000 0.0018580000 113595067 0 402718720 4.4404845238 3.9990687370 3.8647596836 123 4.8800000000 0.0056929048 0.0044306142 0.0057426281 0.0051263577 0.6689210000 0.1402410000 0.0459600000 0.0364100000 0.4442370000 0.0018620000 113597843 0 402718720 4.4517545700 4.0015177727 3.8667833805 124 4.9200000000 0.0057966472 0.0044416306 0.0057966472 0.0051071484 0.6128270000 0.1124070000 0.0536510000 0.0000010000 0.4447060000 0.0018570000 113600619 0 402718720 4.4581632614 4.0030889511 3.8700370789 125 4.9600000000 0.0057355915 0.0044519823 0.0057966472 0.0050991126 1.1120950000 0.1255880000 0.0535140000 0.0363580000 0.4427760000 0.4536490000 113603395 0 402718720 4.4616246223 4.0026483536 3.8714601994 126 5.0000000000 0.0058933846 0.0044634220 0.0058933846 0.0050854569 0.6021480000 0.1124430000 0.0439740000 0.0000010000 0.4436630000 0.0018580000 113606171 0 402718720 4.4710540771 4.0028629303 3.8731498718 127 5.0400000000 0.0058908891 0.0044746619 0.0058933846 0.0050681504 0.6491020000 0.1124490000 0.0560540000 0.0362870000 0.4422320000 0.0018670000 113608947 0 402718720 4.4812207222 4.0027236938 3.8753199577 128 5.0800000000 0.0059051975 0.0044858380 0.0059051975 0.0050622077 0.6116110000 0.1124640000 0.0547670000 0.0000000000 0.4423060000 0.0018610000 113611723 0 402718720 4.4930148125 4.0041356087 3.8786978722 129 5.1200000000 0.0058639767 0.0044965212 0.0059051975 0.0050545315 1.1385330000 0.1127100000 0.0850450000 0.0457250000 0.4439450000 0.4508910000 113626787 0 402718720 4.5040783882 4.0054659843 3.8822605610 130 5.1600000000 0.0059674410 0.0045078360 0.0059674410 0.0050366899 0.6218750000 0.1251040000 0.0538420000 0.0000000000 0.4408420000 0.0018700000 113655163 0 402718720 4.5107812881 4.0063896179 3.8847129345 131 5.2000000000 0.0060016019 0.0045192388 0.0060016019 0.0050726643 0.6736690000 0.1317330000 0.0517290000 0.0360210000 0.4513440000 0.0025940000 113657939 0 402718720 4.5174293518 4.0055356026 3.8878505230 132 5.2400000000 0.0059270328 0.0045299039 0.0060016019 0.0050582913 0.6744790000 0.1452500000 0.0761270000 0.0000010000 0.4510150000 0.0018690000 113660715 0 402718720 4.5281419754 4.0060276985 3.8916609287 133 5.2800000000 0.0058690002 0.0045399723 0.0060016019 0.0050392297 1.0839860000 0.1123760000 0.0567210000 0.0359700000 0.4323440000 0.4463570000 113663491 0 402718720 4.5387139320 4.0069255829 3.8960807323 134 5.3200000000 0.0059177480 0.0045502542 0.0060016019 0.0050864541 0.6077020000 0.1123480000 0.0543820000 0.0000010000 0.4388850000 0.0018700000 113666267 0 402718720 4.5474066734 4.0064744949 3.8987257481 135 5.3600000000 0.0059668263 0.0045607473 0.0060016019 0.0051005557 0.6259950000 0.1083410000 0.0424680000 0.0354200000 0.4376680000 0.0018750000 113669043 0 402718720 4.5571231842 4.0076532364 3.9021749496 136 5.4000000000 0.0059743440 0.0045711414 0.0060016019 0.0051269938 0.6099020000 0.1196350000 0.0546900000 0.0000010000 0.4334730000 0.0018760000 113671819 0 402718720 4.5712246895 4.0152902603 3.9084386826 137 5.4400000000 0.0059446804 0.0045811672 0.0060016019 0.0051233113 1.0749970000 0.1123780000 0.0448240000 0.0357190000 0.4362210000 0.4456310000 113674595 0 402718720 4.5763168335 4.0192751884 3.9122960567 138 5.4800000000 0.0060389256 0.0045917307 0.0060389256 0.0051687680 0.6043440000 0.1123710000 0.0598080000 0.0000010000 0.4299520000 0.0019690000 113677371 0 402718720 4.5800695419 4.0180993080 3.9150669575 139 5.5200000000 0.0060375789 0.0046021325 0.0060389256 0.0051502285 0.6532220000 0.1265590000 0.0540250000 0.0355960000 0.4349270000 0.0018830000 113680147 0 402718720 4.5889368057 4.0188269615 3.9200239182 140 5.5600000000 0.0060958490 0.0046128019 0.0060958490 0.0051338643 0.6017040000 0.1123470000 0.0573530000 0.0000010000 0.4298980000 0.0018780000 113682923 0 402718720 4.5973191261 4.0202040672 3.9251701832 141 5.6000000000 0.0060511455 0.0046230029 0.0060958490 0.0051158107 1.0815200000 0.1123660000 0.0571380000 0.0355560000 0.4336550000 0.4425730000 113685699 0 402718720 4.6059870720 4.0210452080 3.9299967289 142 5.6400000000 0.0060158474 0.0046328117 0.0060958490 0.0051009404 0.6205660000 0.1296080000 0.0557300000 0.0000010000 0.4331150000 0.0018800000 113688475 0 402718720 4.6169290543 4.0214133263 3.9351556301 143 5.6800000000 0.0060139932 0.0046424703 0.0060958490 0.0050912020 0.6532670000 0.1122900000 0.0575550000 0.0355550000 0.4449800000 0.0026220000 113691251 0 402718720 4.6258540154 4.0235223770 3.9404745102 144 5.7200000000 0.0060284669 0.0046520953 0.0060958490 0.0051101527 0.6620490000 0.1450750000 0.0741700000 0.0000000000 0.4406810000 0.0018850000 113694027 0 402718720 4.6318869591 4.0234799385 3.9449143410 145 5.7600000000 0.0060078083 0.0046614450 0.0060958490 0.0050973941 1.0600270000 0.1090860000 0.0456810000 0.0347380000 0.4310370000 0.4392470000 113696803 0 402718720 4.6398348808 4.0239591599 3.9502172470 146 5.8000000000 0.0060349363 0.0046708525 0.0060958490 0.0050823956 0.5924150000 0.1123350000 0.0474620000 0.0000010000 0.4304910000 0.0018890000 113699579 0 402718720 4.6495938301 4.0255780220 3.9563992023 147 5.8400000000 0.0059313709 0.0046794274 0.0060958490 0.0050651658 0.6578510000 0.1328860000 0.0457220000 0.0351760000 0.4411500000 0.0026380000 113702355 0 402718720 4.6589198112 4.0294547081 3.9625163078 148 5.8800000000 0.0060377927 0.0046886056 0.0060958490 0.0050886444 0.6619420000 0.1450170000 0.0737060000 0.0000010000 0.4410870000 0.0018880000 113705131 0 402718720 4.6632223129 4.0291447639 3.9671950340 149 5.9200000000 0.0060869716 0.0046979906 0.0060958490 0.0050736987 1.0678460000 0.1123320000 0.0554540000 0.0351640000 0.4283970000 0.4362550000 113707907 0 402718720 4.6690359116 4.0285801888 3.9715552330 150 5.9600000000 0.0060334587 0.0047068937 0.0060958490 0.0050798338 0.5977490000 0.1123770000 0.0549820000 0.0000010000 0.4282470000 0.0018940000 113710683 0 402718720 4.6769700050 4.0318031311 3.9775710106 151 6.0000000000 0.0059607732 0.0047151976 0.0060958490 0.0050766595 0.6328590000 0.1122970000 0.0555890000 0.0351160000 0.4277020000 0.0019080000 113713459 0 402718720 4.6847858429 4.0338420868 3.9822688103 152 6.0400000000 0.0059654335 0.0047234228 0.0060958490 0.0050838723 0.5960140000 0.1224990000 0.0483180000 0.0000010000 0.4230420000 0.0019010000 113716235 0 402718720 4.6980004311 4.0334286690 3.9913592339 153 6.0800000000 0.0059715798 0.0047315807 0.0060958490 0.0051028804 1.1239180000 0.1126330000 0.0781740000 0.0435150000 0.4445070000 0.4448420000 113719011 0 402718720 4.7057662010 4.0345115662 3.9967339039 154 6.1200000000 0.0059532435 0.0047395136 0.0060958490 0.0050865397 0.6051940000 0.1122610000 0.0650950000 0.0000010000 0.4256810000 0.0019060000 113721787 0 402718720 4.7119517326 4.0361437798 4.0017743111 155 6.1600000000 0.0059368811 0.0047472385 0.0060958490 0.0050861473 0.6362400000 0.1257110000 0.0485450000 0.0348110000 0.4250080000 0.0019070000 113724563 0 402718720 4.7162318230 4.0360136032 4.0059814453 156 6.2000000000 0.0059418837 0.0047548965 0.0060958490 0.0050987778 0.5862890000 0.1082220000 0.0555190000 0.0000010000 0.4203880000 0.0019040000 113727339 0 402718720 4.7249355316 4.0374884605 4.0115895271 157 6.2400000000 0.0059559722 0.0047625467 0.0060958490 0.0051092456 1.0879720000 0.1336500000 0.0654130000 0.0347340000 0.4233860000 0.4305250000 113730115 0 402718720 4.7316074371 4.0387134552 4.0176305771 158 6.2800000000 0.0059683351 0.0047701782 0.0060958490 0.0051187426 0.5931780000 0.1122340000 0.0558000000 0.0000010000 0.4229830000 0.0019020000 113732891 0 402718720 4.7362051010 4.0396409035 4.0234017372 159 6.3200000000 0.0059575015 0.0047776457 0.0060958490 0.0051481859 0.6287470000 0.1122080000 0.0587760000 0.0347290000 0.4208680000 0.0019050000 113735667 0 402718720 4.7435469627 4.0417418480 4.0302281380 160 6.3600000000 0.0058932216 0.0047846180 0.0060958490 0.0052038265 0.5905970000 0.1122040000 0.0559780000 0.0000010000 0.4202460000 0.0019050000 113738443 0 402718720 4.7568788528 4.0455374718 4.0446181297 161 6.4000000000 0.0059649311 0.0047919492 0.0060958490 0.0052269629 1.0497680000 0.1109100000 0.0583680000 0.0343700000 0.4195160000 0.4263410000 113741219 0 402718720 4.7610650063 4.0478014946 4.0513434410 162 6.4400000000 0.0058681569 0.0047985924 0.0060958490 0.0052168641 0.6425400000 0.1399990000 0.0814790000 0.0000010000 0.4188820000 0.0019070000 113743995 0 402718720 4.7661476135 4.0501503944 4.0590720177 163 6.4800000000 0.0058330749 0.0048049389 0.0060958490 0.0052254704 0.6233520000 0.1120710000 0.0485050000 0.0344220000 0.4253890000 0.0026630000 113746771 0 402718720 4.7726855278 4.0508494377 4.0670971870 164 6.5200000000 0.0057688826 0.0048108166 0.0060958490 0.0052359935 0.6580890000 0.1446420000 0.0752590000 0.0000010000 0.4352220000 0.0026650000 113749547 0 402718720 4.7804541588 4.0506496429 4.0751562119 165 6.5600000000 0.0057787062 0.0048166826 0.0060958490 0.0052423032 1.0481290000 0.1122320000 0.0631540000 0.0341500000 0.4157750000 0.4225460000 113752323 0 402718720 4.7890896797 4.0535554886 4.0839943886 166 6.6000000000 0.0057559735 0.0048223410 0.0060958490 0.0052644790 0.5876050000 0.1120260000 0.0584230000 0.0000000000 0.4149750000 0.0019080000 113755099 0 402718720 4.7970709801 4.0574846268 4.0930643082 167 6.6400000000 0.0057360223 0.0048278122 0.0060958490 0.0053160429 0.6202070000 0.1118910000 0.0582950000 0.0340640000 0.4137700000 0.0019110000 113757875 0 402718720 4.8014206886 4.0593180656 4.1012535095 168 6.6800000000 0.0057027084 0.0048330199 0.0060958490 0.0053196956 0.5790220000 0.1079410000 0.0552220000 0.0000000000 0.4137290000 0.0018540000 113760651 0 402718720 4.8085103035 4.0617184639 4.1100020409 169 6.7200000000 0.0056848447 0.0048380603 0.0060958490 0.0053135631 1.0217590000 0.1118910000 0.0462040000 0.0339950000 0.4112750000 0.4181180000 113763427 0 402718720 4.8172564507 4.0663189888 4.1206364632 170 6.7600000000 0.0057022427 0.0048431437 0.0060958490 0.0053272461 0.5830250000 0.1118030000 0.0583120000 0.0000000000 0.4107230000 0.0019100000 113766203 0 402718720 4.8229627609 4.0676670074 4.1289138794 171 6.8000000000 0.0056457850 0.0048478375 0.0060958490 0.0053117430 0.6282510000 0.1254530000 0.0612060000 0.0339460000 0.4054530000 0.0019100000 113768979 0 402718720 4.8323183060 4.0704984665 4.1391692162 172 6.8400000000 0.0056346240 0.0048524118 0.0060958490 0.0052962974 0.6076930000 0.1202800000 0.0590730000 0.0000010000 0.4253590000 0.0026590000 113771755 0 402718720 4.8403735161 4.0731954575 4.1494617462 173 6.8800000000 0.0056142737 0.0048568157 0.0060958490 0.0052814631 1.0813520000 0.1441540000 0.0749190000 0.0422890000 0.4068240000 0.4128830000 113774531 0 402718720 4.8442239761 4.0731387138 4.1566748619 174 6.9200000000 0.0056373533 0.0048613015 0.0060958490 0.0052745983 0.5838570000 0.1098190000 0.0559090000 0.0000010000 0.4151430000 0.0026650000 113777307 0 402718720 4.8526663780 4.0754041672 4.1664242744 175 6.9600000000 0.0056059919 0.0048655569 0.0060958490 0.0052623979 0.6828160000 0.1441530000 0.0785110000 0.0412920000 0.4166630000 0.0019100000 113780083 0 402718720 4.8623528481 4.0791711807 4.1769199371 176 7.0000000000 0.0056298394 0.0048698994 0.0060958490 0.0052475266 0.5673420000 0.1076270000 0.0552920000 0.0000010000 0.4022200000 0.0019040000 113782859 0 402718720 4.8692064285 4.0816950798 4.1868724823 177 7.0400000000 0.0055417400 0.0048736951 0.0060958490 0.0052881711 1.0215660000 0.1243740000 0.0558900000 0.0334250000 0.4003810000 0.4072030000 113785635 0 402718720 4.8738942146 4.0814375877 4.1950492859 178 7.0800000000 0.0054742210 0.0048770688 0.0060958490 0.0053158296 0.5819760000 0.1242260000 0.0561420000 0.0000000000 0.3994130000 0.0019020000 113788411 0 402718720 4.8781676292 4.0814075470 4.2028789520 179 7.1200000000 0.0054615531 0.0048803341 0.0060958490 0.0053014185 0.6149420000 0.1271580000 0.0586680000 0.0334020000 0.3935130000 0.0019090000 113791187 0 402718720 4.8842339516 4.0839209557 4.2120676041 180 7.1600000000 0.0054454384 0.0048834736 0.0060958490 0.0052917415 0.5689020000 0.1111210000 0.0583710000 0.0000000000 0.3972150000 0.0019020000 113793963 0 402718720 4.8905630112 4.0852007866 4.2211656570 181 7.2000000000 0.0054440675 0.0048865708 0.0060958490 0.0052773028 0.9944190000 0.1075060000 0.0552230000 0.0329610000 0.3962600000 0.4021760000 113796739 0 402718720 4.8943500519 4.0859708786 4.2300100327 182 7.2400000000 0.0054698428 0.0048897756 0.0060958490 0.0052636688 0.5759120000 0.1242470000 0.0585180000 0.0000010000 0.3909460000 0.0019020000 113799515 0 402718720 4.9002003670 4.0878362656 4.2386245728 183 7.2800000000 0.0053863255 0.0048924890 0.0060958490 0.0052494308 0.5969270000 0.1114360000 0.0567400000 0.0330610000 0.3934820000 0.0019070000 113802291 0 402718720 4.9054613113 4.0899310112 4.2479820251 184 7.3200000000 0.0053422772 0.0048949335 0.0060958490 0.0052418390 0.5738520000 0.1240380000 0.0556560000 0.0000010000 0.3919500000 0.0019090000 113805067 0 402718720 4.9109268188 4.0905556679 4.2555375099 185 7.3600000000 0.0053698542 0.0048975006 0.0060958490 0.0052323894 0.9862230000 0.1074050000 0.0576510000 0.0321440000 0.3915110000 0.3972110000 113807843 0 402718720 4.9146399498 4.0901594162 4.2616729736 186 7.4000000000 0.0053694327 0.0049000379 0.0060958490 0.0052192290 0.5522280000 0.1112550000 0.0487260000 0.0000010000 0.3900380000 0.0019060000 113810619 0 402718720 4.9200654030 4.0917906761 4.2710614204 187 7.4400000000 0.0052966136 0.0049021586 0.0060958490 0.0052190549 0.6291170000 0.1333740000 0.0579650000 0.0329590000 0.4017950000 0.0026730000 113813395 0 402718720 4.9250154495 4.0927376747 4.2783474922 188 7.4800000000 0.0052770209 0.0049041526 0.0060958490 0.0052057704 0.6199740000 0.1436480000 0.0782830000 0.0000000000 0.3958330000 0.0019070000 113816171 0 402718720 4.9291577339 4.0936212540 4.2850437164 189 7.5200000000 0.0052730711 0.0049061045 0.0060958490 0.0051927669 0.9819890000 0.1111780000 0.0583370000 0.0328310000 0.3863090000 0.3930080000 113818947 0 402718720 4.9322443008 4.0934920311 4.2914619446 190 7.5600000000 0.0052313223 0.0049078162 0.0060958490 0.0051842577 0.5550340000 0.1111690000 0.0558520000 0.0000010000 0.3857960000 0.0019050000 113821723 0 402718720 4.9373927116 4.0942158699 4.2995033264 191 7.6000000000 0.0051722671 0.0049092007 0.0060958490 0.0051751196 0.5932170000 0.1111300000 0.0582240000 0.0327280000 0.3881090000 0.0026750000 113824499 0 402718720 4.9411063194 4.0960845947 4.3077535629 192 7.6400000000 0.0052012503 0.0049107218 0.0060958490 0.0051621364 0.6374630000 0.1435710000 0.0911530000 0.0000010000 0.3997210000 0.0026650000 113827275 0 402718720 4.9438667297 4.0977087021 4.3162093163 193 7.6800000000 0.0051276293 0.0049118457 0.0060958490 0.0051500220 0.9977720000 0.1412760000 0.0580140000 0.0325730000 0.3795600000 0.3860330000 113830051 0 402718720 4.9492850304 4.0995283127 4.3316264153 194 7.7200000000 0.0051593464 0.0049131215 0.0060958490 0.0051366894 0.5627740000 0.1239020000 0.0582300000 0.0000000000 0.3784140000 0.0019070000 113832827 0 402718720 4.9529871941 4.1020145416 4.3403816223 195 7.7600000000 0.0050415434 0.0049137801 0.0060958490 0.0051236389 0.5750690000 0.1111290000 0.0586600000 0.0324840000 0.3706350000 0.0018410000 113835603 0 402718720 4.9577522278 4.1034221649 4.3589491844 196 7.8000000000 0.0051601720 0.0049150372 0.0060958490 0.0051173309 0.5565020000 0.1239200000 0.0555080000 0.0000010000 0.3749210000 0.0018370000 113838379 0 402718720 4.9580464363 4.1025767326 4.3676533699 197 7.8400000000 0.0051478879 0.0049162191 0.0060958490 0.0051055267 0.9721830000 0.1231470000 0.0586360000 0.0323800000 0.3736630000 0.3840340000 113841155 0 402718720 4.9606962204 4.1033263206 4.3778591156 198 7.8800000000 0.0050222394 0.0049167546 0.0060958490 0.0050927430 0.5354720000 0.1072810000 0.0579790000 0.0000010000 0.3679920000 0.0019020000 113843931 0 402718720 4.9626541138 4.1039075851 4.3887963295 199 7.9200000000 0.0051147672 0.0049177496 0.0060958490 0.0050875646 0.5798270000 0.1111180000 0.0656120000 0.0315250000 0.3693480000 0.0019070000 113846707 0 402718720 4.9628152847 4.1031303406 4.3988523483 200 7.9600000000 0.0051157852 0.0049187398 0.0060958490 0.0050767978 0.5473780000 0.1111260000 0.0655320000 0.0000010000 0.3684960000 0.0019000000 113849483 0 402718720 4.9650063515 4.1039495468 4.4098243713 201 8.0000000000 0.0050035091 0.0049191615 0.0060958490 0.0050649304 0.9536650000 0.1239370000 0.0582900000 0.0314360000 0.3665960000 0.3730790000 113852259 0 402718720 4.9673080444 4.1037092209 4.4213352203 202 8.0400000000 0.0050154179 0.0049196381 0.0060958490 0.0050530248 0.5322810000 0.1111130000 0.0584880000 0.0000010000 0.3603350000 0.0020050000 113855035 0 402718720 4.9670395851 4.1040897369 4.4316530228 203 8.0800000000 0.0050264494 0.0049201642 0.0060958490 0.0050408286 0.5650660000 0.1111370000 0.0557850000 0.0319380000 0.3639730000 0.0019070000 113857811 0 402718720 4.9669303894 4.1043562889 4.4423117638 204 8.1200000000 0.0050853710 0.0049209741 0.0060958490 0.0050318129 0.5349440000 0.1111000000 0.0582890000 0.0000000000 0.3633210000 0.0019040000 113860587 0 402718720 4.9671258926 4.1058158875 4.4530215263 205 8.1600000000 0.0051824553 0.0049222496 0.0060958490 0.0050439510 0.9322800000 0.1111200000 0.0583950000 0.0318400000 0.3620880000 0.3685080000 113863363 0 402718720 4.9684095383 4.1076173782 4.4647197723 206 8.1999999990 0.0051281322 0.0049232490 0.0060958490 0.0050512272 0.5562760000 0.1350110000 0.0584700000 0.0000000000 0.3605620000 0.0018960000 113866139 0 402718720 4.9690670967 4.1096677780 4.4768743515 207 8.2400000000 0.0050610020 0.0049239145 0.0060958490 0.0050464457 0.5702580000 0.1111970000 0.0712580000 0.0317640000 0.3536880000 0.0020020000 113868915 0 402718720 4.9698276520 4.1120510101 4.4897274971 208 8.2799999990 0.0051051914 0.0049247860 0.0060958490 0.0050474483 0.5397970000 0.1241220000 0.0559630000 0.0000010000 0.3574680000 0.0019050000 113871691 0 402718720 4.9695143700 4.1151671410 4.5014781952 209 8.3200000000 0.0051811715 0.0049260127 0.0060958490 0.0050415916 0.9278340000 0.1112110000 0.0559180000 0.0310210000 0.3554920000 0.3738100000 113874467 0 402718720 4.9697513580 4.1167154312 4.5131187439 210 8.3599999990 0.0050539444 0.0049266219 0.0060958490 0.0050304200 0.5917120000 0.1436440000 0.0752230000 0.0000010000 0.3701980000 0.0023080000 113877243 0 402718720 4.9703555107 4.1181397438 4.5251955986 211 8.4000000000 0.0050856415 0.0049273756 0.0060958490 0.0050267121 0.5431930000 0.1112330000 0.0463090000 0.0314940000 0.3519070000 0.0019100000 113880019 0 402718720 4.9707818031 4.1203346252 4.5376038551 212 8.4399999990 0.0050395178 0.0049279046 0.0060958490 0.0050192742 0.5449620000 0.1360340000 0.0584960000 0.0000000000 0.3481830000 0.0019000000 113882795 0 402718720 4.9697465897 4.1220951080 4.5499958992 213 8.4800000000 0.0050803740 0.0049286204 0.0060958490 0.0050114620 0.9028230000 0.1113770000 0.0558030000 0.0313660000 0.3488620000 0.3550710000 113885571 0 402718720 4.9685578346 4.1240544319 4.5615019798 214 8.5200000000 0.0051954351 0.0049298672 0.0060958490 0.0050080943 0.5169390000 0.1113560000 0.0560110000 0.0000010000 0.3473290000 0.0018950000 113888347 0 402718720 4.9679813385 4.1262798309 4.5728154182 215 8.5600000000 0.0052000405 0.0049311238 0.0060958490 0.0049990775 0.5668340000 0.1114360000 0.0752200000 0.0312710000 0.3458370000 0.0026670000 113891123 0 402718720 4.9681687355 4.1294674873 4.5849633217 216 8.6000000000 0.0049797045 0.0049313487 0.0060958490 0.0049911398 0.5856550000 0.1437980000 0.0784330000 0.0000000000 0.3603680000 0.0026590000 113893899 0 402718720 4.9686121941 4.1316127777 4.5973291397 217 8.6400000000 0.0050279922 0.0049317941 0.0060958490 0.0049843792 0.9513450000 0.1438330000 0.0782220000 0.0371480000 0.3432500000 0.3485380000 113896675 0 402718720 4.9674849510 4.1332736015 4.6082348824 218 8.6800000000 0.0050614085 0.0049323886 0.0060958490 0.0049787271 0.5269300000 0.1114490000 0.0653170000 0.0000010000 0.3471010000 0.0026610000 113899451 0 402718720 4.9658946991 4.1347370148 4.6188888550 219 8.7200000000 0.0051426515 0.0049333487 0.0060958490 0.0049720272 0.6301500000 0.1438220000 0.0911460000 0.0369640000 0.3551540000 0.0026650000 113902227 0 402718720 4.9632039070 4.1358146667 4.6292366982 220 8.7600000000 0.0051577906 0.0049343689 0.0060958490 0.0049624268 0.5449860000 0.1438220000 0.0608230000 0.0000000000 0.3380520000 0.0019310000 113905003 0 402718720 4.9599018097 4.1361222267 4.6388030052 221 8.8000000000 0.0051364144 0.0049352832 0.0060958490 0.0049516900 0.8782340000 0.1114050000 0.0586120000 0.0310600000 0.3336500000 0.3431480000 113907779 0 402718720 4.9602560997 4.1384243965 4.6508846283 222 8.8400000000 0.0050162571 0.0049356479 0.0060958490 0.0049429717 0.5558420000 0.1235260000 0.0945780000 0.0000010000 0.3354740000 0.0019020000 113910555 0 402718720 4.9585785866 4.1390323639 4.6616201401 223 8.8800000000 0.0049933107 0.0049359065 0.0060958490 0.0049318637 0.5372440000 0.1113280000 0.0584260000 0.0309180000 0.3343010000 0.0019070000 113913331 0 402718720 4.9558148384 4.1389861107 4.6712126732 224 8.9200000000 0.0049084336 0.0049357838 0.0060958490 0.0049218848 0.5315760000 0.1307290000 0.0687880000 0.0000010000 0.3298000000 0.0018940000 113916107 0 402718720 4.9540829659 4.1395258904 4.6816358566 225 8.9600000000 0.0047974144 0.0049351689 0.0060958490 0.0049141076 0.8700640000 0.1112840000 0.0581760000 0.0308230000 0.3315850000 0.3378300000 113918883 0 402718720 4.9537901878 4.1410856247 4.6929678917 226 9.0000000000 0.0049354341 0.0049351700 0.0060958490 0.0049039574 0.4975750000 0.1112580000 0.0557410000 0.0000010000 0.3283050000 0.0019070000 113921659 0 402718720 4.9550132751 4.1433877945 4.7148394585 227 9.0400000000 0.0047719809 0.0049344511 0.0060958490 0.0048931907 0.5258400000 0.1111900000 0.0557840000 0.0300360000 0.3265480000 0.0019100000 113924435 0 402718720 4.9551076889 4.1454472542 4.7256002426 228 9.0800000000 0.0049020327 0.0049343089 0.0060958490 0.0048844652 0.4959520000 0.1111860000 0.0463230000 0.0000000000 0.3353620000 0.0026640000 113927211 0 402718720 4.9528565407 4.1470003128 4.7345972061 229 9.1200000000 0.0048088506 0.0049337611 0.0060958490 0.0048955301 0.9310110000 0.1436430000 0.0753540000 0.0369750000 0.3400830000 0.3345820000 113929987 0 402718720 4.9530353546 4.1487116814 4.7457585335 230 9.1600000000 0.0046948246 0.0049327222 0.0060958490 0.0048922855 0.4839950000 0.1112460000 0.0486590000 0.0000010000 0.3218070000 0.0019080000 113932763 0 402718720 4.9536199570 4.1500306129 4.7560057640 231 9.2000000000 0.0046059191 0.0049313075 0.0060958490 0.0048871669 0.5313100000 0.1111880000 0.0680200000 0.0304100000 0.3194020000 0.0019130000 113935539 0 402718720 4.9529142380 4.1512746811 4.7746539116 232 9.2400000000 0.0046339431 0.0049300258 0.0060958490 0.0048801877 0.4868070000 0.1111200000 0.0557750000 0.0000010000 0.3176250000 0.0019080000 113938315 0 402718720 4.9537067413 4.1536602974 4.7866368294 233 9.2800000000 0.0045418711 0.0049283599 0.0060958490 0.0048816881 0.8451530000 0.1110480000 0.0677580000 0.0303000000 0.3147030000 0.3209610000 113941091 0 402718720 4.9543180466 4.1562538147 4.7987241745 234 9.3200000000 0.0046705855 0.0049272583 0.0060958490 0.0048801339 0.4968780000 0.1110720000 0.0683430000 0.0000000000 0.3143640000 0.0026690000 113943867 0 402718720 4.9535803795 4.1589069366 4.8094582558 235 9.3600000000 0.0044982363 0.0049254326 0.0060958490 0.0048785267 0.5988490000 0.1434760000 0.0906790000 0.0363110000 0.3252830000 0.0026670000 113946643 0 402718720 4.9532971382 4.1600914001 4.8202900887 236 9.4000000000 0.0046271887 0.0049241689 0.0060958490 0.0048728715 0.5400570000 0.1435170000 0.0875270000 0.0000000000 0.3067190000 0.0019120000 113949419 0 402718720 4.9549207687 4.1608443260 4.8297982216 237 9.4400000000 0.0046067922 0.0049228298 0.0060958490 0.0048810403 0.8112300000 0.1111450000 0.0556940000 0.0300570000 0.3038150000 0.3101340000 113952195 0 402718720 4.9556140900 4.1634798050 4.8408584595 238 9.4800000000 0.0045545772 0.0049212825 0.0060958490 0.0048789308 0.4711530000 0.1111090000 0.0557020000 0.0000020000 0.3020440000 0.0019120000 113954971 0 402718720 4.9564075470 4.1650128365 4.8516621590 239 9.5200000000 0.0046207621 0.0049200251 0.0060958490 0.0048848200 0.5083450000 0.1110740000 0.0655550000 0.0299440000 0.2994720000 0.0019160000 113957747 0 402718720 4.9583153725 4.1672468185 4.8624176979 240 9.5600000000 0.0044996883 0.0049182737 0.0060958490 0.0048831992 0.4574550000 0.1110430000 0.0461890000 0.0000010000 0.2979260000 0.0019100000 113960523 0 402718720 4.9579353333 4.1680469513 4.8719539642 241 9.6000000000 0.0044662687 0.0049163981 0.0060958490 0.0048730579 0.8313330000 0.1110150000 0.0779500000 0.0292370000 0.2956000000 0.3170860000 113963299 0 402718720 4.9562096596 4.1694989204 4.8817052841 242 9.6400000000 0.0043910965 0.0049142275 0.0060958490 0.0048764026 0.5359640000 0.1433130000 0.0782300000 0.0000010000 0.3113010000 0.0026710000 113966075 0 402718720 4.9574131966 4.1718692780 4.8938641548 243 9.6800000000 0.0044384073 0.0049122693 0.0060958490 0.0048671395 0.5030280000 0.1220780000 0.0556090000 0.0297390000 0.2932920000 0.0019150000 113968851 0 402718720 4.9604167938 4.1743550301 4.9075436592 244 9.7200000000 0.0042979484 0.0049097516 0.0060958490 0.0048571307 0.4874920000 0.1352040000 0.0610120000 0.0000010000 0.2889600000 0.0019120000 113971627 0 402718720 4.9616990089 4.1779670715 4.9196000099 245 9.7600000000 0.0044038268 0.0049076866 0.0060958490 0.0048489746 0.7882240000 0.1108050000 0.0555860000 0.0322370000 0.2938430000 0.2953460000 113974403 0 402718720 4.9617691040 4.1787514687 4.9292149544 246 9.8000000000 0.0041897558 0.0049047682 0.0060958490 0.0048391012 0.4551640000 0.1107130000 0.0549740000 0.0000010000 0.2871610000 0.0019110000 113977179 0 402718720 4.9632329941 4.1814274788 4.9409475327 247 9.8400000000 0.0042371922 0.0049020655 0.0060958490 0.0048294766 0.4825300000 0.1107460000 0.0556410000 0.0288280000 0.2849990000 0.0019160000 113979955 0 402718720 4.9635281563 4.1840429306 4.9526352882 248 9.8800000000 0.0043421583 0.0048998078 0.0060958490 0.0048245235 0.4486720000 0.1107910000 0.0485040000 0.0000010000 0.2862450000 0.0026750000 113982731 0 402718720 4.9635639191 4.1872110367 4.9626893997 249 9.9200000000 0.0041170358 0.0048966641 0.0060958490 0.0048149192 0.8530050000 0.1431580000 0.0782000000 0.0341150000 0.2955310000 0.3015930000 113985507 0 402718720 4.9647970200 4.1882143021 4.9734525681 250 9.9600000000 0.0042088185 0.0048939127 0.0060958490 0.0048056323 0.4496260000 0.1107170000 0.0579850000 0.0000010000 0.2786120000 0.0019020000 113988283 0 402718720 4.9654664993 4.1900734901 4.9843363762 251 10.0000000000 0.0041155624 0.0048908118 0.0060958490 0.0047978903 0.4989540000 0.1236840000 0.0673460000 0.0292940000 0.2763090000 0.0019110000 113991059 0 402718720 4.9649024010 4.1908321381 4.9934535027 252 10.0400000000 0.0040366268 0.0048874221 0.0060958490 0.0047883408 0.4543150000 0.1225800000 0.0553950000 0.0000000000 0.2740830000 0.0018420000 113993835 0 402718720 4.9653139114 4.1924786568 5.0030531883 253 10.0800000000 0.0041710008 0.0048845904 0.0060958490 0.0047793290 0.7557500000 0.1107660000 0.0673760000 0.0291640000 0.2708840000 0.2771470000 113996611 0 402718720 4.9657230377 4.1942119598 5.0124678612 254 10.1200000000 0.0041101719 0.0048815415 0.0060958490 0.0047737046 0.4786180000 0.1393510000 0.0708650000 0.0000010000 0.2659570000 0.0020050000 113999387 0 402718720 4.9659590721 4.1962327957 5.0217938423 255 10.1600000000 0.0041243667 0.0048785722 0.0060958490 0.0047645883 0.5301300000 0.1108730000 0.1128910000 0.0290960000 0.2741340000 0.0026680000 114002163 0 402718720 4.9653406143 4.1979327202 5.0309615135 256 10.2000000000 0.0039550872 0.0048749649 0.0060958490 0.0047663418 0.5162590000 0.1430270000 0.0908810000 0.0000010000 0.2792210000 0.0026590000 114004939 0 402718720 4.9640836716 4.1987032890 5.0385994911 257 10.2400000000 0.0039095115 0.0048712082 0.0060958490 0.0047768950 0.7836550000 0.1429720000 0.0782740000 0.0301130000 0.2627690000 0.2691010000 114032291 0 402718720 4.9631805420 4.2003817558 5.0474252701 258 10.2800000000 0.0039843312 0.0048677707 0.0060958490 0.0047782551 0.4323610000 0.1105190000 0.0608840000 0.0000010000 0.2586300000 0.0019010000 114086267 0 402718720 4.9636392593 4.2020225525 5.0570554733 259 10.3200000000 0.0041180342 0.0048648760 0.0060958490 0.0047887232 0.4675530000 0.1104950000 0.0676440000 0.0289200000 0.2581580000 0.0019120000 114089043 0 402718720 4.9632019997 4.2028975487 5.0650701523 260 10.3600000000 0.0042968816 0.0048626914 0.0060958490 0.0047912228 0.4358610000 0.1103870000 0.0669370000 0.0000000000 0.2562110000 0.0018930000 114091819 0 402718720 4.9610257149 4.2043433189 5.0726251602 261 10.4000000000 0.0042064376 0.0048601770 0.0060958490 0.0047832077 0.7218830000 0.1102810000 0.0672690000 0.0281140000 0.2547950000 0.2609920000 114094595 0 402718720 4.9597668648 4.2061128616 5.0822491646 262 10.4400000000 0.0044421763 0.0048585816 0.0060958490 0.0047741660 0.4484860000 0.1336160000 0.0593520000 0.0000010000 0.2531830000 0.0018940000 114097371 0 402718720 4.9608960152 4.2074708939 5.0913810730 263 10.4800000000 0.0042811767 0.0048563861 0.0060958490 0.0047650834 0.4578340000 0.1102620000 0.0648940000 0.0286860000 0.2516500000 0.0019100000 114100147 0 402718720 4.9602732658 4.2089705467 5.1009869576 264 10.5200000000 0.0042886361 0.0048542356 0.0060958490 0.0047590110 0.4482080000 0.1101570000 0.0879620000 0.0000010000 0.2477450000 0.0019070000 114102923 0 402718720 4.9586081505 4.2094860077 5.1088953018 265 10.5600000000 0.0044747074 0.0048528034 0.0060958490 0.0047511962 0.6947320000 0.1100360000 0.0579950000 0.0286610000 0.2455950000 0.2519950000 114105699 0 402718720 4.9574728012 4.2096829414 5.1163692474 266 10.6000000000 0.0044050934 0.0048511203 0.0060958490 0.0047424089 0.4204010000 0.1063150000 0.0653370000 0.0000010000 0.2464110000 0.0019050000 114108475 0 402718720 4.9581022263 4.2107658386 5.1249990463 267 10.6400000000 0.0043873144 0.0048493832 0.0060958490 0.0047352887 0.5491270000 0.1376870000 0.1161130000 0.0326930000 0.2594720000 0.0026680000 114111251 0 402718720 4.9572463036 4.2121601105 5.1336565018 268 10.6800000000 0.0043097422 0.0048473696 0.0060958490 0.0047292311 0.4805900000 0.1421590000 0.0874790000 0.0000010000 0.2486190000 0.0018880000 114114027 0 402718720 4.9560499191 4.2141876221 5.1430559158 269 10.7200000000 0.0042733168 0.0048452355 0.0060958490 0.0047249364 0.6839130000 0.1099360000 0.0552530000 0.0284680000 0.2417710000 0.2480400000 114116803 0 402718720 4.9542870522 4.2149820328 5.1522665024 270 10.7600000000 0.0043597566 0.0048434375 0.0060958490 0.0047186911 0.4208020000 0.1098690000 0.0577190000 0.0000000000 0.2500520000 0.0026620000 114119579 0 402718720 4.9523940086 4.2172536850 5.1613631248 271 10.8000000000 0.0042401818 0.0048412114 0.0060958490 0.0047117224 0.5589810000 0.1420720000 0.1286790000 0.0324130000 0.2526460000 0.0026660000 114122355 0 402718720 4.9501719475 4.2191438675 5.1713089943 272 10.8400000000 0.0041783131 0.0048387743 0.0060958490 0.0047030252 0.4412310000 0.1419750000 0.0603470000 0.0000010000 0.2365530000 0.0019090000 114125131 0 402718720 4.9473023415 4.2209734917 5.1805338860 273 10.8800000000 0.0039837742 0.0048356424 0.0060958490 0.0046946087 0.6803970000 0.1097980000 0.0704400000 0.0283130000 0.2322020000 0.2391910000 114127907 0 402718720 4.9433145523 4.2213926315 5.1895108223 274 10.9200000000 0.0037932897 0.0048318382 0.0060958490 0.0046870208 0.4109170000 0.1090620000 0.0672860000 0.0000010000 0.2322060000 0.0019090000 114130683 0 402718720 4.9416022301 4.2234697342 5.1999535561 275 10.9600000000 0.0038024208 0.0048280949 0.0060958490 0.0046808115 0.4388370000 0.1098200000 0.0704800000 0.0282540000 0.2278020000 0.0020070000 114133459 0 402718720 4.9390177727 4.2271432877 5.2095675468 276 11.0000000000 0.0038199180 0.0048244421 0.0060958490 0.0046740568 0.4006410000 0.1097370000 0.0595570000 0.0000010000 0.2289940000 0.0019010000 114136235 0 402718720 4.9353971481 4.2263431549 5.2174038887 277 11.0400000000 0.0037446306 0.0048205439 0.0060958490 0.0046697601 0.6755720000 0.1294850000 0.0606340000 0.0281910000 0.2249480000 0.2318480000 114139011 0 402718720 4.9349646568 4.2285699844 5.2286620140 278 11.0800000000 0.0037703968 0.0048167663 0.0060958490 0.0046613245 0.4044120000 0.1097110000 0.0672280000 0.0000010000 0.2251220000 0.0018940000 114141787 0 402718720 4.9298901558 4.2296943665 5.2375965118 279 11.1200000000 0.0036765051 0.0048126794 0.0060958490 0.0046541806 0.4222540000 0.1096810000 0.0605400000 0.0281080000 0.2214340000 0.0020110000 114144563 0 402718720 4.9250650406 4.2296915054 5.2468419075 280 11.1600000000 0.0036119143 0.0048083909 0.0060958490 0.0046458809 0.4111980000 0.1097150000 0.0780560000 0.0000010000 0.2210500000 0.0019160000 114147339 0 402718720 4.9225172997 4.2322182655 5.2576608658 281 11.2000000000 0.0036628793 0.0048043144 0.0060958490 0.0046379244 0.6418300000 0.1097000000 0.0605800000 0.0280250000 0.2182620000 0.2247930000 114150115 0 402718720 4.9204602242 4.2360267639 5.2671189308 282 11.2400000000 0.0036106526 0.0048000815 0.0060958490 0.0046302654 0.3972840000 0.1096590000 0.0578340000 0.0000010000 0.2265990000 0.0026650000 114152891 0 402718720 4.9169759750 4.2370576859 5.2758088112 283 11.2800000000 0.0035249304 0.0047955757 0.0060958490 0.0046228377 0.4987740000 0.1417340000 0.0906990000 0.0316820000 0.2314630000 0.0026680000 114155667 0 402718720 4.9137787819 4.2400751114 5.2853612900 284 11.3200000000 0.0035629573 0.0047912355 0.0060958490 0.0046156836 0.4168860000 0.1125400000 0.0864300000 0.0000010000 0.2155350000 0.0019120000 114158443 0 402718720 4.9087996483 4.2428188324 5.2963886261 285 11.3600000000 0.0036417744 0.0047872023 0.0060958490 0.0046081416 0.6389910000 0.1096770000 0.0704050000 0.0279410000 0.2120020000 0.2184900000 114161219 0 402718720 4.9041223526 4.2434582710 5.3052306175 286 11.4000000000 0.0036330998 0.0047831670 0.0060958490 0.0046124799 0.4020650000 0.1117780000 0.0760830000 0.0000010000 0.2118430000 0.0018920000 114163995 0 402718720 4.9054269791 4.2467765808 5.3157920837 287 11.4400000000 0.0036111376 0.0047790833 0.0060958490 0.0046054180 0.4020580000 0.1138110000 0.0504530000 0.0278990000 0.2074160000 0.0019860000 114166771 0 402718720 4.9028534889 4.2502546310 5.3247637749 288 11.4800000000 0.0036186592 0.0047750540 0.0060958490 0.0045975255 0.3882480000 0.1096130000 0.0702630000 0.0000010000 0.2060070000 0.0018920000 114169547 0 402718720 4.8958106041 4.2511811256 5.3315129280 289 11.5200000000 0.0034934084 0.0047706192 0.0060958490 0.0045900732 0.6143780000 0.1096380000 0.0575760000 0.0277900000 0.2063210000 0.2125760000 114172323 0 402718720 4.8901052475 4.2497301102 5.3387904167 290 11.5600000000 0.0033804141 0.0047658254 0.0060958490 0.0045829575 0.4239890000 0.1208980000 0.0956140000 0.0000010000 0.2050820000 0.0019130000 114175099 0 402718720 4.8870859146 4.2507395744 5.3476800919 291 11.6000000000 0.0033414422 0.0047609306 0.0060958490 0.0045753972 0.4612150000 0.1224600000 0.1050590000 0.0277390000 0.2035680000 0.0019060000 114177875 0 402718720 4.8846268654 4.2532548904 5.3560776711 292 11.6400000000 0.0032755060 0.0047558436 0.0060958490 0.0045678206 0.4027510000 0.1059470000 0.0921530000 0.0000010000 0.2023270000 0.0018410000 114180651 0 402718720 4.8815045357 4.2538151741 5.3638186455 293 11.6800000000 0.0031179169 0.0047502534 0.0060958490 0.0045600421 0.6280630000 0.1088970000 0.0836840000 0.0276750000 0.2005260000 0.2067890000 114183427 0 402718720 4.8796205521 4.2559728622 5.3703355789 294 11.7200000000 0.0030304051 0.0047444036 0.0060958490 0.0045583584 0.3887650000 0.1094560000 0.0774450000 0.0000000000 0.1994450000 0.0019320000 114186203 0 402718720 4.8755145073 4.2551789284 5.3768424988 295 11.7600000000 0.0029475533 0.0047383125 0.0060958490 0.0045586546 0.4177280000 0.1222340000 0.0672510000 0.0276160000 0.1982180000 0.0019160000 114188979 0 402718720 4.8740925789 4.2559342384 5.3846497536 296 11.8000000000 0.0029456206 0.0047322562 0.0060958490 0.0045770905 0.3821110000 0.1234840000 0.0607910000 0.0000010000 0.1953380000 0.0019840000 114191755 0 402718720 4.8716797829 4.2562890053 5.3924212456 297 11.8400000000 0.0029124506 0.0047261289 0.0060958490 0.0046043528 0.6060290000 0.1094110000 0.0706610000 0.0275140000 0.1958300000 0.2021160000 114194531 0 402718720 4.8673563004 4.2561683655 5.3996829987 298 11.8800000000 0.0027597388 0.0047195302 0.0060958490 0.0046171127 0.3831150000 0.1093310000 0.0769080000 0.0000010000 0.1944940000 0.0018920000 114197307 0 402718720 4.8643798828 4.2556953430 5.4085106850 299 11.9200000000 0.0026802514 0.0047127099 0.0060958490 0.0046155839 0.4286810000 0.1167820000 0.0789950000 0.0274870000 0.2021970000 0.0026570000 114200083 0 402718720 4.8624510765 4.2553634644 5.4166340828 300 11.9600000000 0.0025638042 0.0047055469 0.0060958490 0.0046144641 0.4274050000 0.1409650000 0.0777350000 0.0000010000 0.2054950000 0.0026520000 114202859 0 402718720 4.8605790138 4.2547764778 5.4242830276 301 12.0000000000 0.0025017790 0.0046982254 0.0060958490 0.0046098429 0.6521870000 0.1408630000 0.0904220000 0.0316700000 0.1926900000 0.1960420000 114205635 0 402718720 4.8595447540 4.2555656433 5.4338665009 302 12.0400000000 0.0024071028 0.0046906389 0.0060958490 0.0046033759 0.3572870000 0.1092780000 0.0575480000 0.0000010000 0.1880560000 0.0019020000 114208411 0 402718720 4.8588185310 4.2558598518 5.4424996376 303 12.0800000000 0.0023933216 0.0046830570 0.0060958490 0.0045974505 0.3925760000 0.1092230000 0.0669750000 0.0272890000 0.1866750000 0.0019080000 114211187 0 402718720 4.8568305969 4.2550930977 5.4500627518 304 12.1200000000 0.0023130295 0.0046752609 0.0060958490 0.0045913780 0.3637910000 0.1090980000 0.0671190000 0.0000000000 0.1851850000 0.0018830000 114213963 0 402718720 4.8556370735 4.2559781075 5.4596695900 305 12.1600000000 0.0022073048 0.0046671692 0.0060958490 0.0045839188 0.5666480000 0.1090140000 0.0576160000 0.0272080000 0.1830210000 0.1892820000 114216739 0 402718720 4.8544716835 4.2570261955 5.4693274498 306 12.2000000000 0.0022291897 0.0046592019 0.0060958490 0.0045765243 0.3717950000 0.1183610000 0.0704800000 0.0000010000 0.1804130000 0.0020040000 114219515 0 402718720 4.8518376350 4.2580423355 5.4781646729 307 12.2400000000 0.0021132552 0.0046509090 0.0060958490 0.0045706668 0.3716680000 0.1088970000 0.0553780000 0.0270890000 0.1778010000 0.0019780000 114222291 0 402718720 4.8496985435 4.2598505020 5.4877514839 308 12.2800000000 0.0020026853 0.0046423108 0.0060958490 0.0045689419 0.3447420000 0.1054110000 0.0572090000 0.0000010000 0.1788780000 0.0026680000 114225067 0 402718720 4.8485841751 4.2605280876 5.4974889755 309 12.3200000000 0.0020185146 0.0046338196 0.0060958490 0.0045670318 0.6315110000 0.1394390000 0.0777960000 0.0309700000 0.1880220000 0.1947070000 114227843 0 402718720 4.8472166061 4.2611656189 5.5066146851 310 12.3600000000 0.0020534659 0.0046254959 0.0060958490 0.0045744475 0.3983710000 0.1391880000 0.0847780000 0.0000000000 0.1719880000 0.0019070000 114230619 0 402718720 4.8461780548 4.2638406754 5.5166068077 311 12.4000000000 0.0020459578 0.0046172015 0.0060958490 0.0045943860 0.3869410000 0.1285880000 0.0606150000 0.0268500000 0.1683520000 0.0019980000 114233395 0 402718720 4.8449320793 4.2660408020 5.5268278122 312 12.4400000000 0.0020244028 0.0046088913 0.0060958490 0.0046012547 0.3455050000 0.1080080000 0.0678940000 0.0000000000 0.1672050000 0.0018790000 114236171 0 402718720 4.8438911438 4.2649378777 5.5345139503 313 12.4800000000 0.0018766895 0.0046001622 0.0060958490 0.0046023285 0.5286020000 0.1079840000 0.0576650000 0.0267560000 0.1647270000 0.1709430000 114238947 0 402718720 4.8426361084 4.2659935951 5.5441503525 314 12.5200000000 0.0017445020 0.0045910677 0.0060958490 0.0046009655 0.3523470000 0.1077340000 0.0804940000 0.0000010000 0.1615870000 0.0019940000 114241723 0 402718720 4.8408803940 4.2671165466 5.5534086227 315 12.5600000000 0.0017124455 0.0045819292 0.0060958490 0.0045960139 0.3720730000 0.1235340000 0.0586840000 0.0266760000 0.1607490000 0.0018970000 114244499 0 402718720 4.8394742012 4.2681322098 5.5615634918 316 12.6000000000 0.0017870663 0.0045730847 0.0060958490 0.0045889643 0.3457520000 0.1073300000 0.0767480000 0.0000010000 0.1592540000 0.0018970000 114247275 0 402718720 4.8400912285 4.2677745819 5.5694947243 317 12.6400000000 0.0017169790 0.0045640749 0.0060958490 0.0045820744 0.5140980000 0.1071840000 0.0577330000 0.0266110000 0.1579290000 0.1641080000 114250051 0 402718720 4.8393049240 4.2689242363 5.5784416199 318 12.6800000000 0.0018758806 0.0045556215 0.0060958490 0.0045776920 0.3838170000 0.1322630000 0.0781310000 0.0000010000 0.1701830000 0.0026440000 114252827 0 402718720 4.8390464783 4.2707138062 5.5874280930 319 12.7200000000 0.0019970404 0.0045476009 0.0060958490 0.0045716788 0.4166020000 0.1368150000 0.0780520000 0.0303000000 0.1681700000 0.0026670000 114255603 0 402718720 4.8364334106 4.2735219002 5.5978446007 320 12.7600000000 0.0019982471 0.0045396341 0.0060958490 0.0045714290 0.3501080000 0.1276800000 0.0673900000 0.0000010000 0.1526140000 0.0018990000 114258379 0 402718720 4.8342790604 4.2745776176 5.6068615913 321 12.8000000000 0.0020279493 0.0045318096 0.0060958490 0.0045825267 0.5260040000 0.1064860000 0.0863900000 0.0257070000 0.1504000000 0.1564890000 114261155 0 402718720 4.8327102661 4.2766089439 5.6161746979 322 12.8400000000 0.0020537777 0.0045241138 0.0060958490 0.0045877883 0.3333130000 0.1061480000 0.0767130000 0.0000010000 0.1480300000 0.0018930000 114263931 0 402718720 4.8316364288 4.2789192200 5.6251368523 323 12.8800000000 0.0020554648 0.0045164710 0.0060958490 0.0045999143 0.3475220000 0.1058100000 0.0671660000 0.0263680000 0.1457330000 0.0019040000 114266707 0 402718720 4.8304247856 4.2803859711 5.6330437660 324 12.9200000000 0.0019887581 0.0045086694 0.0060958490 0.0046120770 0.3381790000 0.1054040000 0.0865000000 0.0000000000 0.1438690000 0.0018720000 114269483 0 402718720 4.8292636871 4.2805337906 5.6400165558 325 12.9600000000 0.0019970676 0.0045009414 0.0060958490 0.0046243493 0.4925820000 0.1049700000 0.0700560000 0.0262990000 0.1422870000 0.1484230000 114272259 0 402718720 4.8288741112 4.2809948921 5.6471815109 326 13.0000000000 0.0021204932 0.0044936394 0.0060958490 0.0046329384 0.3245970000 0.1046660000 0.0768920000 0.0000010000 0.1406080000 0.0018930000 114275035 0 402718720 4.8277010918 4.2818493843 5.6553397179 327 13.0400000000 0.0020684910 0.0044862230 0.0060958490 0.0047404263 0.3334120000 0.1037370000 0.0652600000 0.0261650000 0.1358120000 0.0018890000 114277811 0 402718720 4.8240280151 4.2863831520 5.6748781204 328 13.0800000000 0.0021250437 0.0044790243 0.0060958490 0.0047590513 0.3397870000 0.1031380000 0.0865190000 0.0000000000 0.1468770000 0.0026370000 114280587 0 402718720 4.8221502304 4.2871017456 5.6827187538 329 13.1200000000 0.0021192119 0.0044718516 0.0060958490 0.0047642920 0.4841930000 0.1201130000 0.0671580000 0.0260970000 0.1321090000 0.1381580000 114283363 0 402718720 4.8200297356 4.2880840302 5.6906828880 330 13.1600000000 0.0022079756 0.0044649914 0.0060958490 0.0047635016 0.2993890000 0.1018920000 0.0647340000 0.0000000000 0.1304050000 0.0018070000 114286139 0 402718720 4.8185877800 4.2884802818 5.6978998184 331 13.2000000000 0.0022022643 0.0044581554 0.0060958490 0.0047632488 0.3314930000 0.1011640000 0.0743000000 0.0253270000 0.1282640000 0.0018880000 114288915 0 402718720 4.8178381920 4.2884225845 5.7046389580 332 13.2400000000 0.0022676503 0.0044515574 0.0060958490 0.0047601647 0.3056920000 0.1003830000 0.0767690000 0.0000010000 0.1261230000 0.0018720000 114291691 0 402718720 4.8168268204 4.2899332047 5.7123246193 333 13.2800000000 0.0022403558 0.0044449172 0.0060958490 0.0047552725 0.4966920000 0.0997760000 0.0956530000 0.0253010000 0.1315320000 0.1437970000 114294467 0 402718720 4.8157939911 4.2913670540 5.7198181152 334 13.3200000000 0.0021912353 0.0044381697 0.0060958490 0.0047574216 0.3490830000 0.1262590000 0.0842130000 0.0000010000 0.1353400000 0.0026430000 114297243 0 402718720 4.8153772354 4.2914423943 5.7258901596 335 13.3600000000 0.0021489367 0.0044313361 0.0060958490 0.0047631278 0.3673080000 0.1257700000 0.0779750000 0.0284370000 0.1326770000 0.0018920000 114300019 0 402718720 4.8132376671 4.2942380905 5.7346043587 336 13.4000000000 0.0021058922 0.0044244152 0.0060958490 0.0047768478 0.2768260000 0.0979450000 0.0576430000 0.0000010000 0.1187880000 0.0018960000 114302795 0 402718720 4.8112077713 4.2950043678 5.7408123016 337 13.4400000000 0.0019614280 0.0044171066 0.0060958490 0.0048015954 0.4103210000 0.0956080000 0.0479250000 0.0258760000 0.1173400000 0.1230040000 114305571 0 402718720 4.8098897934 4.2940378189 5.7460145950 338 13.4800000000 0.0019363157 0.0044097670 0.0060958490 0.0048293292 0.2996350000 0.0972040000 0.0840460000 0.0000010000 0.1159030000 0.0019180000 114308347 0 402718720 4.8064351082 4.2940921783 5.7514643669 339 13.5200000000 0.0019581504 0.0044025351 0.0060958490 0.0048508201 0.3748300000 0.1285350000 0.0875990000 0.0283350000 0.1270520000 0.0026670000 114311123 0 402718720 4.8044929504 4.2958016396 5.7590370178 340 13.5600000000 0.0019631446 0.0043953604 0.0060958490 0.0048752800 0.3313220000 0.1237700000 0.0780340000 0.0000010000 0.1262430000 0.0026400000 114313899 0 402718720 4.7998962402 4.2960667610 5.7647409439 341 13.6000000000 0.0018910823 0.0043880165 0.0060958490 0.0048845924 0.4883120000 0.1236730000 0.1033330000 0.0283060000 0.1133400000 0.1190820000 114316675 0 402718720 4.7961649895 4.2970385551 5.7720041275 342 13.6400000000 0.0020506103 0.0043811819 0.0060958490 0.0048977784 0.2787760000 0.0963000000 0.0674080000 0.0000000000 0.1126240000 0.0018760000 114319451 0 402718720 4.7925386429 4.2994198799 5.7800984383 343 13.6800000000 0.0021614351 0.0043747104 0.0060958490 0.0049164390 0.2912690000 0.0955510000 0.0577890000 0.0258530000 0.1096040000 0.0018950000 114322227 0 402718720 4.7883205414 4.3029127121 5.7885365486 344 13.7200000000 0.0022029944 0.0043683972 0.0060958490 0.0049206551 0.2647990000 0.0963050000 0.0550710000 0.0000010000 0.1101410000 0.0026390000 114325003 0 402718720 4.7843770981 4.3048868179 5.7943892479 345 13.7600000000 0.0022467866 0.0043622477 0.0060958490 0.0049228305 0.4889310000 0.1237920000 0.0904280000 0.0291700000 0.1191720000 0.1257110000 114327779 0 402718720 4.7826223373 4.3040075302 5.7990355492 346 13.8000000000 0.0023349649 0.0043563885 0.0060958490 0.0049235409 0.3997520000 0.1240340000 0.1541730000 0.0000010000 0.1182530000 0.0026410000 114330555 0 402718720 4.7800998688 4.3044333458 5.8030052185 347 13.8400000000 0.0023937658 0.0043507325 0.0060958490 0.0049315153 0.2917740000 0.1008700000 0.0579210000 0.0258170000 0.1046930000 0.0018920000 114333331 0 402718720 4.7762517929 4.3038282394 5.8087382317 348 13.8800000000 0.0025077048 0.0043454364 0.0060958490 0.0049449187 0.2839270000 0.1101320000 0.0676600000 0.0000000000 0.1036660000 0.0018810000 114336107 0 402718720 4.7717409134 4.3043823242 5.8153896332 349 13.9200000000 0.0025700363 0.0043403493 0.0060958490 0.0049535077 0.3993240000 0.0955210000 0.0668960000 0.0249220000 0.1027500000 0.1086460000 114338883 0 402718720 4.7656702995 4.3048477173 5.8227381706 350 13.9600000000 0.0027695242 0.0043358612 0.0060958490 0.0049628655 0.2920700000 0.0978050000 0.0774290000 0.0000010000 0.1135310000 0.0026500000 114341659 0 402718720 4.7600741386 4.3061351776 5.8303346634 351 14.0000000000 0.0027644364 0.0043313843 0.0060958490 0.0049630596 0.3594830000 0.1253940000 0.0905580000 0.0280520000 0.1121600000 0.0026610000 114344435 0 402718720 4.7547936440 4.3076291084 5.8368029594 352 14.0400000000 0.0028265927 0.0043271093 0.0060958490 0.0049636499 0.3310470000 0.1254710000 0.0905840000 0.0000010000 0.1116820000 0.0026520000 114347211 0 402718720 4.7491912842 4.3073239326 5.8405246735 353 14.0800000000 0.0028190878 0.0043228373 0.0060958490 0.0049618694 0.4050630000 0.1077120000 0.0674130000 0.0257080000 0.0988670000 0.1047670000 114349987 0 402718720 4.7448315620 4.3063306808 5.8459262848 354 14.1200000000 0.0028831197 0.0043187703 0.0060958490 0.0049631573 0.2563280000 0.0987400000 0.0579300000 0.0000010000 0.0971980000 0.0018790000 114352763 0 402718720 4.7388010025 4.3086938858 5.8550028801 355 14.1600000000 0.0030469038 0.0043151875 0.0060958490 0.0049597847 0.3148780000 0.1242830000 0.0672000000 0.0249420000 0.0957850000 0.0020190000 114355539 0 402718720 4.7330827713 4.3096084595 5.8600873947 356 14.2000000000 0.0031969494 0.0043120464 0.0060958490 0.0049567358 0.3317650000 0.1064790000 0.1152830000 0.0000000000 0.1067240000 0.0026100000 114358315 0 402718720 4.7271194458 4.3096108437 5.8644819260 357 14.2400000000 0.0033001280 0.0043092119 0.0060958490 0.0049535327 0.4620130000 0.1269300000 0.0898310000 0.0279710000 0.1052020000 0.1114040000 114361091 0 402718720 4.7197494507 4.3108553886 5.8708271980 358 14.2800000000 0.0033865364 0.0043066346 0.0060958490 0.0049472447 0.3116940000 0.1271000000 0.0890750000 0.0000010000 0.0930880000 0.0018340000 114363867 0 402718720 4.7144279480 4.3110399246 5.8763384819 359 14.3200000000 0.0034186207 0.0043041610 0.0060958490 0.0049407675 0.2939450000 0.0975830000 0.0777210000 0.0256140000 0.0905710000 0.0018400000 114366643 0 402718720 4.7054657936 4.3146457672 5.8838782310 360 14.3600000000 0.0036263515 0.0043022782 0.0060958490 0.0049420892 0.2448060000 0.0976460000 0.0577780000 0.0000010000 0.0869510000 0.0018130000 114369419 0 402718720 4.6897640228 4.3178768158 5.8957576752 361 14.4000000000 0.0040626982 0.0043016146 0.0060958490 0.0049353498 0.3454430000 0.0998550000 0.0471410000 0.0256240000 0.0836960000 0.0885160000 114372195 0 402718720 4.6806988716 4.3223843575 5.9043478966 362 14.4400000000 0.0041346499 0.0043011533 0.0060958490 0.0049305795 0.2606900000 0.1001340000 0.0664910000 0.0000010000 0.0910840000 0.0023010000 114374971 0 402718720 4.6639328003 4.3215966225 5.9105958939 363 14.4800000000 0.0040581087 0.0043004838 0.0060958490 0.0049265221 0.3292820000 0.1277180000 0.0808530000 0.0278180000 0.0899380000 0.0022660000 114377747 0 402718720 4.6579642296 4.3205995560 5.9145379066 364 14.5200000000 0.0039700833 0.0042995761 0.0060958490 0.0049197759 0.3532910000 0.1276000000 0.1349150000 0.0000010000 0.0878970000 0.0021940000 114380523 0 402718720 4.6502051353 4.3211832047 5.9206333160 365 14.5600000000 0.0041655106 0.0042992088 0.0060958490 0.0049130502 0.3593370000 0.1102980000 0.0647750000 0.0256180000 0.0769810000 0.0810430000 114383299 0 402718720 4.6421799660 4.3212232590 5.9257187843 366 14.6000000000 0.0043492843 0.0042993456 0.0060958490 0.0049071184 0.2382330000 0.1002090000 0.0586750000 0.0000010000 0.0771340000 0.0015810000 114386075 0 402718720 4.6258230209 4.3274226189 5.9402780533 367 14.6400000000 0.0047744829 0.0043006403 0.0060958490 0.0049008144 0.2741510000 0.0980760000 0.0627660000 0.0255410000 0.0856750000 0.0014790000 114388851 0 402718720 4.6166267395 4.3313608170 5.9453516006 368 14.6800000000 0.0050579445 0.0043026982 0.0060958490 0.0048957465 0.2614960000 0.1119430000 0.0589800000 0.0000010000 0.0884970000 0.0014580000 114391627 0 402718720 4.6080060005 4.3316044807 5.9491863251 369 14.7200000000 0.0051597808 0.0043050209 0.0060958490 0.0048910856 0.3579590000 0.1005230000 0.0508220000 0.0255230000 0.0885310000 0.0919360000 114394403 0 402718720 4.5996031761 4.3292603493 5.9505982399 370 14.7600000000 0.0050884881 0.0043071384 0.0060958490 0.0048852027 0.2491660000 0.1007410000 0.0579940000 0.0000010000 0.0883640000 0.0014540000 114397179 0 402718720 4.5914602280 4.3280730247 5.9522361755 371 14.8000000000 0.0049631903 0.0043089067 0.0060958490 0.0048802266 0.2710060000 0.1005670000 0.0515110000 0.0255720000 0.0912860000 0.0014560000 114399955 0 402718720 4.5819821358 4.3302497864 5.9589428902 372 14.8400000000 0.0050869589 0.0043109982 0.0060958490 0.0048742404 0.2931350000 0.1006320000 0.0904450000 0.0000010000 0.0999070000 0.0015110000 114402731 0 402718720 4.5733871460 4.3315601349 5.9641170502 373 14.8800000000 0.0053051515 0.0043136635 0.0060958490 0.0048700323 0.4176440000 0.1006210000 0.0752890000 0.0255840000 0.1060680000 0.1094320000 114405507 0 402718720 4.5637626648 4.3326058388 5.9687685966 374 14.9200000000 0.0059234640 0.0043179678 0.0060958490 0.0048645464 0.2778320000 0.1004020000 0.0641910000 0.0000010000 0.1111740000 0.0014400000 114408283 0 402718720 4.5531592369 4.3330936432 5.9720582962 375 14.9600000000 0.0060447282 0.0043225725 0.0060958490 0.0048622535 0.3152080000 0.1000590000 0.0713860000 0.0255330000 0.1161630000 0.0014380000 114411059 0 402718720 4.5428442955 4.3326420784 5.9733858109 376 15.0000000000 0.0062050228 0.0043275790 0.0062050228 0.0048560668 0.2826290000 0.0999840000 0.0532060000 0.0000010000 0.1272720000 0.0015120000 114413835 0 402718720 4.5338435173 4.3321771622 5.9786949158 377 15.0400000000 0.0061464515 0.0043324036 0.0062050228 0.0048534391 0.4513770000 0.1003040000 0.0611880000 0.0255560000 0.1297830000 0.1339140000 114416611 0 402718720 4.5127916336 4.3334603310 5.9859542847 378 15.0800000000 0.0068345466 0.0043390230 0.0068345466 0.0048509928 0.3018640000 0.1004170000 0.0655370000 0.0000010000 0.1338200000 0.0014610000 114419387 0 402718720 4.5044140816 4.3338489532 5.9899539948 379 15.1200000000 0.0073460657 0.0043469572 0.0073460657 0.0048456171 0.3136230000 0.1006900000 0.0517140000 0.0255290000 0.1335730000 0.0014890000 114422163 0 402718720 4.4973840714 4.3333277702 5.9929904938 380 15.1600000000 0.0076726135 0.0043557089 0.0076726135 0.0048422498 0.3244810000 0.1009090000 0.0882440000 0.0000010000 0.1332190000 0.0014720000 114424939 0 402718720 4.4902558327 4.3320446014 5.9966878891 381 15.2000000000 0.0081032813 0.0043655451 0.0081032813 0.0048476979 0.4571390000 0.1010710000 0.0602480000 0.0255340000 0.1329100000 0.1367350000 114427715 0 402718720 4.4825787544 4.3331193924 6.0027213097 382 15.2400000000 0.0087849032 0.0043771141 0.0087849032 0.0048478759 0.3252730000 0.1014430000 0.0894630000 0.0000010000 0.1322210000 0.0015030000 114430491 0 402718720 4.4730105400 4.3325514793 6.0036273003 383 15.2800000000 0.0088587590 0.0043888155 0.0088587590 0.0048603263 0.3275980000 0.1017900000 0.0682250000 0.0247620000 0.1306700000 0.0015110000 114433267 0 402718720 4.4645471573 4.3324475288 6.0062503815 384 15.3200000000 0.0084580751 0.0043994125 0.0088587590 0.0048803063 0.2785890000 0.1020390000 0.0467400000 0.0000000000 0.1276620000 0.0015130000 114436043 0 402718720 4.4555630684 4.3342480659 6.0115475655 385 15.3600000000 0.0086931325 0.0044105650 0.0088587590 0.0048799402 0.4913410000 0.1135290000 0.0965030000 0.0255860000 0.1254410000 0.1296270000 114438819 0 402718720 4.4478716850 4.3341779709 6.0143332481 386 15.4000000000 0.0084506618 0.0044210316 0.0088587590 0.0048833418 0.3446430000 0.1027200000 0.1054750000 0.0000010000 0.1342720000 0.0015290000 114441595 0 402718720 4.4402613640 4.3348321915 6.0174145699 387 15.4400000000 0.0084764296 0.0044315107 0.0088587590 0.0048874675 0.3496280000 0.1029170000 0.0927810000 0.0255440000 0.1261970000 0.0015430000 114444371 0 402718720 4.4338960648 4.3355216980 6.0212936401 388 15.4800000000 0.0080679366 0.0044408829 0.0088587590 0.0048979887 0.3295100000 0.1274320000 0.0743640000 0.0000010000 0.1254070000 0.0016290000 114447147 0 402718720 4.4270009995 4.3368558884 6.0250172615 389 15.5200000000 0.0082899006 0.0044507775 0.0088587590 0.0048980516 0.4770030000 0.1035150000 0.0936930000 0.0255350000 0.1247000000 0.1289070000 114449923 0 402718720 4.4193148613 4.3378872871 6.0290637016 390 15.5600000000 0.0081653362 0.0044603021 0.0088587590 0.0049163799 0.3262330000 0.1010770000 0.0989790000 0.0000010000 0.1239570000 0.0015610000 114452699 0 402718720 4.4111371040 4.3385634422 6.0322065353 391 15.6000000000 0.0078406101 0.0044689473 0.0088587590 0.0049191300 0.3479280000 0.1039880000 0.0948220000 0.0255930000 0.1212860000 0.0015870000 114455475 0 402718720 4.4038987160 4.3394169807 6.0356297493 392 15.6400000000 0.0075867292 0.0044769009 0.0088587590 0.0049323962 0.3225200000 0.1041480000 0.0956550000 0.0000010000 0.1204720000 0.0015970000 114458251 0 402718720 4.3967752457 4.3404645920 6.0405268669 393 15.6800000000 0.0079414025 0.0044857164 0.0088587590 0.0049284166 0.4712390000 0.1045250000 0.0954820000 0.0256020000 0.1202910000 0.1246750000 114461027 0 402718720 4.3903083801 4.3402619362 6.0434370041 394 15.7200000000 0.0078164134 0.0044941699 0.0088587590 0.0049311429 0.3223760000 0.1031300000 0.0967220000 0.0000010000 0.1202610000 0.0016140000 114463803 0 402718720 4.3833961487 4.3410229683 6.0467209816 395 15.7600000000 0.0077797868 0.0045024880 0.0088587590 0.0049337088 0.3639550000 0.1147780000 0.1025850000 0.0248990000 0.1192900000 0.0017210000 114466579 0 402718720 4.3767213821 4.3419017792 6.0528941154 396 15.8000000000 0.0080203600 0.0045113715 0.0088587590 0.0049307022 0.3247310000 0.1050210000 0.0989580000 0.0000010000 0.1184660000 0.0016230000 114469355 0 402718720 4.3697476387 4.3436913490 6.0580587387 397 15.8400000000 0.0078305947 0.0045197322 0.0088587590 0.0049297034 0.5230370000 0.1045360000 0.1306170000 0.0277060000 0.1272370000 0.1321940000 114472131 0 402718720 4.3631992340 4.3432903290 6.0605978966 398 15.8800000000 0.0073103434 0.0045267438 0.0088587590 0.0049325021 0.4008230000 0.1347080000 0.1354390000 0.0000000000 0.1276810000 0.0022510000 114474907 0 402718720 4.3571114540 4.3442463875 6.0677871704 399 15.9200000000 0.0072993953 0.0045336928 0.0088587590 0.0049358546 0.3299160000 0.1266990000 0.0592120000 0.0256630000 0.1160050000 0.0016700000 114477683 0 402718720 4.3489251137 4.3460536003 6.0713534355 400 15.9600000000 0.0069112810 0.0045396368 0.0088587590 0.0049405360 0.2905080000 0.1028330000 0.0701120000 0.0000000000 0.1151650000 0.0017080000 114480459 0 402718720 4.3426361084 4.3454170227 6.0746736526 401 16.0000000000 0.0061452300 0.0045436408 0.0088587590 0.0049471090 0.4720070000 0.1059920000 0.1067160000 0.0257060000 0.1140440000 0.1188790000 114483235 0 402718720 4.3349809647 4.3448977470 6.0788702965 402 16.0400000000 0.0057651387 0.0045466793 0.0088587590 0.0049609168 0.3316180000 0.1317600000 0.0857640000 0.0000010000 0.1117320000 0.0016830000 114486011 0 402718720 4.3266849518 4.3457350731 6.0855817795 403 16.0800000000 0.0058079124 0.0045498089 0.0088587590 0.0049571436 0.3302310000 0.1060010000 0.0855380000 0.0256820000 0.1106450000 0.0016930000 114488787 0 402718720 4.3211679459 4.3463015556 6.0917277336 404 16.1200000000 0.0059616813 0.0045533037 0.0088587590 0.0049526550 0.2968410000 0.1029640000 0.0848200000 0.0000010000 0.1067450000 0.0016370000 114491563 0 402718720 4.3141837120 4.3461427689 6.0961017609 405 16.1600000000 0.0063899192 0.0045578385 0.0088587590 0.0049600083 0.4520310000 0.1294110000 0.0818200000 0.0257870000 0.1046800000 0.1096170000 114494339 0 402718720 4.3068184853 4.3458719254 6.1001195908 406 16.2000000000 0.0068152803 0.0045633987 0.0088587590 0.0049798772 0.3243190000 0.1058760000 0.1092990000 0.0000010000 0.1068000000 0.0016660000 114497115 0 402718720 4.3009872437 4.3474345207 6.1086430550 407 16.2400000000 0.0074332952 0.0045704501 0.0088587590 0.0049914315 0.3493470000 0.1186150000 0.0948300000 0.0257220000 0.1071310000 0.0022780000 114499891 0 402718720 4.2942943573 4.3501315117 6.1141476631 408 16.2800000000 0.0081318310 0.0045791789 0.0088587590 0.0050037564 0.3285090000 0.1355020000 0.0816050000 0.0000010000 0.1083560000 0.0022700000 114502667 0 402718720 4.2893843651 4.3513417244 6.1187214851 409 16.3200000000 0.0087046297 0.0045892656 0.0088587590 0.0050172258 0.4946570000 0.1351780000 0.1153200000 0.0288500000 0.1047790000 0.1097540000 114505443 0 402718720 4.2829608917 4.3527927399 6.1255631447 410 16.3600000000 0.0093358625 0.0046008427 0.0093358625 0.0050183441 0.2773980000 0.1074310000 0.0755620000 0.0000010000 0.0920660000 0.0016590000 114508219 0 402718720 4.2779464722 4.3538227081 6.1295189857 411 16.3999999990 0.0100999866 0.0046142226 0.0100999866 0.0050217175 0.2824500000 0.1048890000 0.0589950000 0.0257680000 0.0904530000 0.0016530000 114510995 0 402718720 4.2725977898 4.3547554016 6.1328291893 412 16.4400000000 0.0100555439 0.0046274297 0.0100999866 0.0050158988 0.2828420000 0.1045710000 0.0834310000 0.0000000000 0.0925140000 0.0016370000 114513771 0 402718720 4.2678527832 4.3544383049 6.1381883621 413 16.4800000000 0.0102978991 0.0046411596 0.0102978991 0.0050243188 0.4125440000 0.1172850000 0.0754420000 0.0257960000 0.0943290000 0.0989850000 114516547 0 402718720 4.2623648643 4.3558278084 6.1453900337 414 16.5200000000 0.0124873808 0.0046601119 0.0124873808 0.0050376080 0.2714010000 0.1043790000 0.0670640000 0.0000010000 0.0976400000 0.0016300000 114519323 0 402718720 4.2587633133 4.3582634926 6.1508946419 415 16.5599999990 0.0127718067 0.0046796581 0.0127718067 0.0050379998 0.3533780000 0.1205570000 0.1034820000 0.0258950000 0.1009960000 0.0017240000 114522099 0 402718720 4.2534646988 4.3599734306 6.1575860977 416 16.6000000000 0.0151656372 0.0047048648 0.0151656372 0.0050779431 0.2685460000 0.1043720000 0.0584940000 0.0000000000 0.1033830000 0.0016040000 114524875 0 402718720 4.2491497993 4.3631782532 6.1616969109 417 16.6400000000 0.0099449512 0.0047174309 0.0151656372 0.0050816525 0.4238530000 0.1043630000 0.0805310000 0.0258340000 0.1040030000 0.1084180000 114527651 0 402718720 4.2369332314 4.3617911339 6.1651978493 418 16.6800000000 0.0129291834 0.0047370763 0.0151656372 0.0051802012 0.3120010000 0.1256010000 0.0745190000 0.0000000000 0.1095970000 0.0015840000 114530427 0 402718720 4.2270264626 4.3662214279 6.1743726730 419 16.7199999990 0.0163026694 0.0047646791 0.0163026694 0.0052106577 0.3729260000 0.1046780000 0.1163690000 0.0280740000 0.1208850000 0.0021290000 114533203 0 402718720 4.2293477058 4.3660850525 6.1809082031 420 16.7600000000 0.0249481928 0.0048127351 0.0249481928 0.0053538269 0.3312490000 0.1344100000 0.0679360000 0.0000010000 0.1259960000 0.0021140000 114535979 0 402718720 4.2308168411 4.3726334572 6.1870288849 421 16.8000000000 0.0219752379 0.0048535012 0.0249481928 0.0053599618 0.5097090000 0.1345370000 0.0970340000 0.0282270000 0.1263940000 0.1228010000 114538755 0 402718720 4.2222957611 4.3728184700 6.1922178268 422 16.8400000000 0.0166429393 0.0048814382 0.0249481928 0.0053621160 0.3003170000 0.1048610000 0.0706360000 0.0000000000 0.1225460000 0.0015600000 114541531 0 402718720 4.2129325867 4.3699240685 6.1968946457 423 16.8799999990 0.0179028753 0.0049122218 0.0249481928 0.0054310939 0.3031900000 0.1050040000 0.0484840000 0.0260820000 0.1213380000 0.0015780000 114544307 0 402718720 4.2083029747 4.3716435432 6.2021865845 424 16.9200000000 0.0146347638 0.0049351523 0.0249481928 0.0054494791 0.3131400000 0.1050170000 0.0789500000 0.0000010000 0.1269070000 0.0015660000 114547083 0 402718720 4.1943030357 4.3713102341 6.2117767334 425 16.9600000000 0.0119560873 0.0049516721 0.0249481928 0.0054441952 0.4746810000 0.1019680000 0.0919510000 0.0252750000 0.1253470000 0.1294290000 114549859 0 402718720 4.1878881454 4.3703002930 6.2153000832 426 17.0000000000 0.0114840586 0.0049670064 0.0249481928 0.0054586558 0.3046660000 0.1051800000 0.0631450000 0.0000000000 0.1340740000 0.0015540000 114552635 0 402718720 4.1817417145 4.3717107773 6.2203288078 427 17.0400000000 0.0109543726 0.0049810283 0.0249481928 0.0054627551 0.3377450000 0.1052350000 0.0628300000 0.0262780000 0.1411190000 0.0015650000 114555411 0 402718720 4.1758308411 4.3731675148 6.2247896194 428 17.0800000000 0.0113292960 0.0049958607 0.0249481928 0.0054718502 0.3312990000 0.1053360000 0.0781400000 0.0000000000 0.1455530000 0.0015410000 114558187 0 402718720 4.1709008217 4.3756303787 6.2287402153 429 17.1200000000 0.0109828161 0.0050098163 0.0249481928 0.0054718389 0.5147290000 0.1021990000 0.0916180000 0.0263940000 0.1447370000 0.1490560000 114560963 0 402718720 4.1655430794 4.3757209778 6.2309722900 430 17.1600000000 0.0111071607 0.0050239962 0.0249481928 0.0054747126 0.3598820000 0.1356220000 0.0646500000 0.0000010000 0.1567240000 0.0020700000 114563739 0 402718720 4.1606583595 4.3762221336 6.2344894409 431 17.2000000000 0.0106317466 0.0050370072 0.0249481928 0.0054721494 0.4084140000 0.1357920000 0.0851210000 0.0291770000 0.1554380000 0.0020770000 114566515 0 402718720 4.1558260918 4.3753571510 6.2381510735 432 17.2400000000 0.0107425628 0.0050502145 0.0249481928 0.0054723685 0.3797060000 0.1358270000 0.0978980000 0.0000000000 0.1437200000 0.0015380000 114569291 0 402718720 4.1505503654 4.3760552406 6.2427020073 433 17.2800000000 0.0103275431 0.0050624023 0.0249481928 0.0054701247 0.5005670000 0.1244580000 0.0575550000 0.0266630000 0.1432340000 0.1479250000 114572067 0 402718720 4.1465582848 4.3770747185 6.2464590073 434 17.3200000000 0.0108065112 0.0050756376 0.0249481928 0.0054724360 0.3020570000 0.1057550000 0.0499700000 0.0000010000 0.1440490000 0.0015570000 114574843 0 402718720 4.1411061287 4.3787641525 6.2488698959 435 17.3600000000 0.0106398324 0.0050884289 0.0249481928 0.0054704631 0.3881020000 0.1192600000 0.0973610000 0.0259960000 0.1431020000 0.0016210000 114577619 0 402718720 4.1357660294 4.3771662712 6.2503690720 436 17.4000000000 0.0111188861 0.0051022602 0.0249481928 0.0054765218 0.3015470000 0.1059490000 0.0498470000 0.0000010000 0.1433620000 0.0016230000 114580395 0 402718720 4.1307864189 4.3774070740 6.2531547546 437 17.4400000000 0.0109663345 0.0051156791 0.0249481928 0.0054746782 0.5009850000 0.1060140000 0.0741960000 0.0268170000 0.1443380000 0.1488810000 114583171 0 402718720 4.1244425774 4.3785552979 6.2562055588 438 17.4800000000 0.0106127793 0.0051282296 0.0249481928 0.0054739153 0.3457980000 0.1061610000 0.0933340000 0.0000000000 0.1440240000 0.0015460000 114585947 0 402718720 4.1193075180 4.3767437935 6.2585515976 439 17.5200000000 0.0101243155 0.0051396102 0.0249481928 0.0054715667 0.3458850000 0.1189500000 0.0549370000 0.0267360000 0.1430050000 0.0015230000 114588723 0 402718720 4.1143631935 4.3761105537 6.2608966827 440 17.5600000000 0.0104140677 0.0051515976 0.0249481928 0.0054721429 0.3422460000 0.1090560000 0.0763560000 0.0000000000 0.1539240000 0.0020810000 114591499 0 402718720 4.1091418266 4.3761868477 6.2630462646 441 17.6000000000 0.0105235688 0.0051637789 0.0249481928 0.0054709777 0.5449910000 0.1370540000 0.0765350000 0.0310630000 0.1532880000 0.1463070000 114594275 0 402718720 4.1033310890 4.3760209084 6.2644796371 442 17.6400000000 0.0107535822 0.0051764255 0.0249481928 0.0054702709 0.2987930000 0.1065900000 0.0482130000 0.0000000000 0.1416700000 0.0015710000 114597051 0 402718720 4.0981030464 4.3749485016 6.2655920982 443 17.6800000000 0.0107079837 0.0051889121 0.0249481928 0.0054703279 0.3414240000 0.1068470000 0.0640370000 0.0270020000 0.1411980000 0.0015930000 114599827 0 402718720 4.0923604965 4.3760309219 6.2674374580 444 17.7200000000 0.0104849357 0.0052008401 0.0249481928 0.0054677699 0.3005490000 0.1068790000 0.0508550000 0.0000000000 0.1404970000 0.0015780000 114602603 0 402718720 4.0868678093 4.3753361702 6.2698788643 445 17.7600000000 0.0103883464 0.0052124974 0.0249481928 0.0054649384 0.4819070000 0.1070560000 0.0639870000 0.0270830000 0.1390750000 0.1439520000 114605379 0 402718720 4.0819168091 4.3750019073 6.2715220451 446 17.8000000000 0.0113480818 0.0052262543 0.0249481928 0.0054666160 0.3166050000 0.1200010000 0.0565450000 0.0000010000 0.1377170000 0.0015890000 114608155 0 402718720 4.0762701035 4.3751592636 6.2730402946 447 17.8400000000 0.0114234779 0.0052401184 0.0249481928 0.0054665087 0.3584510000 0.1072720000 0.0846040000 0.0271990000 0.1369210000 0.0016750000 114610931 0 402718720 4.0705928802 4.3748421669 6.2764759064 448 17.8800000000 0.0113041624 0.0052536542 0.0249481928 0.0054655819 0.3514110000 0.1287170000 0.0829750000 0.0000010000 0.1372610000 0.0016840000 114613707 0 402718720 4.0639481544 4.3745918274 6.2784004211 449 17.9200000000 0.0112725701 0.0052670593 0.0249481928 0.0054633679 0.5157700000 0.1074430000 0.1013720000 0.0273080000 0.1366750000 0.1422150000 114616483 0 402718720 4.0584993362 4.3736047745 6.2794084549 450 17.9600000000 0.0112117445 0.0052802698 0.0249481928 0.0054599566 0.3325400000 0.1075220000 0.0728800000 0.0000010000 0.1491240000 0.0021640000 114619259 0 402718720 4.0529956818 4.3722710609 6.2807731628 451 18.0000000000 0.0105325049 0.0052919155 0.0249481928 0.0054616018 0.4538190000 0.1384620000 0.1338790000 0.0317290000 0.1466960000 0.0021910000 114622035 0 402718720 4.0396637917 4.3701996803 6.2847151756 452 18.0400000000 0.0054798243 0.0052923312 0.0249481928 0.0054582291 0.3728180000 0.1385020000 0.0906740000 0.0000000000 0.1412630000 0.0016260000 114624811 0 402718720 4.0337920189 4.3638882637 6.2871298790 453 18.0800000000 0.0042482624 0.0052900265 0.0249481928 0.0054532766 0.4792020000 0.1076550000 0.0747110000 0.0273270000 0.1316290000 0.1371060000 114627587 0 402718720 4.0274047852 4.3595986366 6.2893252373 454 18.1200000000 0.0049019549 0.0052891717 0.0249481928 0.0054498745 0.3475850000 0.1076850000 0.1036440000 0.0000010000 0.1331700000 0.0022170000 114630363 0 402718720 4.0200223923 4.3560800552 6.2927718163 455 18.1600000000 0.0056577087 0.0052899816 0.0249481928 0.0054453582 0.3507070000 0.1302240000 0.0590820000 0.0273730000 0.1315980000 0.0016570000 114633139 0 402718720 4.0132746696 4.3550162315 6.2963070869 456 18.2000000000 0.0090180673 0.0052981573 0.0249481928 0.0054418919 0.2950200000 0.1076000000 0.0537210000 0.0000010000 0.1311690000 0.0017410000 114635915 0 402718720 4.0077052116 4.3493857384 6.2979168892 457 18.2400000000 0.0089621833 0.0053061748 0.0249481928 0.0054392582 0.5090440000 0.1076950000 0.1061580000 0.0274150000 0.1304990000 0.1365010000 114638691 0 402718720 4.0008139610 4.3492121696 6.3006010056 458 18.2800000000 0.0153693277 0.0053281468 0.0249481928 0.0054489585 0.2940830000 0.1076320000 0.0545530000 0.0000010000 0.1293580000 0.0017460000 114641467 0 402718720 3.9935863018 4.3425412178 6.3023171425 459 18.3200000000 0.0175838023 0.0053548476 0.0249481928 0.0054489202 0.3549850000 0.1077230000 0.0893670000 0.0274680000 0.1278520000 0.0017720000 114644243 0 402718720 3.9872338772 4.3392081261 6.3037624359 460 18.3600000000 0.0358920023 0.0054212327 0.0358920023 0.0054981210 0.3377840000 0.1076630000 0.1023760000 0.0000010000 0.1252950000 0.0016730000 114647019 0 402718720 3.9814260006 4.3195929527 6.3054723740 461 18.4000000000 0.0295599718 0.0054735944 0.0358920023 0.0055041995 0.4945030000 0.1077070000 0.1056620000 0.0274570000 0.1233670000 0.1295240000 114649795 0 402718720 3.9743139744 4.3246660233 6.3081517220 462 18.4400000000 0.2312761098 0.0059623444 0.2312761098 0.0108293854 0.3552160000 0.1291740000 0.1090530000 0.0000010000 0.1144010000 0.0017730000 114652571 0 402718720 3.9672319889 4.1220841408 6.3107466698 463 18.4800000000 0.8001996875 0.0076777598 0.8001996875 0.0285437363 0.3214950000 0.1076820000 0.0647050000 0.0274870000 0.1191500000 0.0016930000 114655347 0 402718720 3.9614357948 3.5533118248 6.3084807396 464 18.5200000000 0.6862425804 0.0091401840 0.8001996875 0.0290197366 0.3305500000 0.1077490000 0.1086250000 0.0000010000 0.1114800000 0.0018790000 114658123 0 402718720 3.9558639526 3.6658422947 6.3112840652 465 18.5600000000 0.7877927423 0.0108147056 0.8001996875 0.0293478098 0.4956260000 0.1238340000 0.0983130000 0.0275250000 0.1197960000 0.1253750000 114660899 0 402718720 3.9490659237 3.5631241798 6.3139758110 466 18.6000000000 0.6529104114 0.0121925934 0.8001996875 0.0300073171 0.3246950000 0.1077810000 0.1037800000 0.0000010000 0.1106340000 0.0017150000 114663675 0 402718720 3.9429125786 3.6967453957 6.3170866966 467 18.6400000000 0.8156625032 0.0139130857 0.8156625032 0.0308896776 0.3651030000 0.1078320000 0.1045450000 0.0268690000 0.1232170000 0.0018250000 114666451 0 402718720 3.9368350506 3.5344417095 6.3178358078 468 18.6800000000 0.8070219159 0.0156077627 0.8156625032 0.0308629862 0.2900660000 0.1079520000 0.0563480000 0.0000010000 0.1232530000 0.0017190000 114669227 0 402718720 3.9315049648 3.5421562195 6.3174953461 469 18.7200000000 0.8070818782 0.0172953408 0.8156625032 0.0308312050 0.4882740000 0.1044220000 0.1013420000 0.0274260000 0.1244690000 0.1298100000 114672003 0 402718720 3.9250161648 3.5420920849 6.3197088242 470 18.7600000000 0.8056408763 0.0189726717 0.8156625032 0.0307991650 0.3506270000 0.1193070000 0.1040920000 0.0000010000 0.1247010000 0.0017280000 114674779 0 402718720 3.9190618992 3.5425157547 6.3204140663 471 18.8000000000 0.4642910957 0.0199181461 0.8156625032 0.0347248302 0.4048260000 0.1104600000 0.1336520000 0.0314610000 0.1259090000 0.0024500000 114677555 0 402718720 3.9053916931 3.8796319962 6.3223080635 472 18.8400000000 0.5978472829 0.0211425722 0.8156625032 0.0352142293 0.4073490000 0.1394860000 0.1385720000 0.0000000000 0.1255220000 0.0027420000 114680331 0 402718720 3.9001274109 3.7449028492 6.3233437538 473 18.8800000000 0.6735743880 0.0225219207 0.8156625032 0.0353383964 0.5314380000 0.1396630000 0.1254550000 0.0276600000 0.1160800000 0.1217780000 114683107 0 402718720 3.8984527588 3.6670916080 6.3220610619 474 18.9200000000 0.6654174924 0.0238782404 0.8156625032 0.0353063427 0.3238970000 0.1084960000 0.0961910000 0.0000010000 0.1166160000 0.0017970000 114685883 0 402718720 3.8961224556 3.6734218597 6.3223209381 475 18.9600000000 0.6623528004 0.0252223974 0.8156625032 0.0352713916 0.3613020000 0.1186070000 0.0951190000 0.0269970000 0.1179790000 0.0017950000 114688659 0 402718720 3.8925273418 3.6756746769 6.3238630295 476 19.0000000000 0.6423436999 0.0265188707 0.8156625032 0.0352593659 0.3581510000 0.1227830000 0.1145020000 0.0000010000 0.1181510000 0.0018860000 114691435 0 402718720 3.8873877525 3.6929986477 6.3241705894 477 19.0400000000 0.6570855379 0.0278408134 0.8156625032 0.0352291842 0.4918080000 0.1053750000 0.1084550000 0.0276560000 0.1219810000 0.1275020000 114694211 0 402718720 3.8851363659 3.6759614944 6.3235373497 478 19.0800000000 0.6234713197 0.0290869023 0.8156625032 0.0352465511 0.3415440000 0.1089430000 0.1100880000 0.0000000000 0.1198930000 0.0018250000 114696987 0 402718720 3.8789258003 3.7073111534 6.3296060562 479 19.1200000000 0.6086615324 0.0302968703 0.8156625032 0.0352205506 0.3791680000 0.1219470000 0.1065170000 0.0278250000 0.1202250000 0.0018470000 114699763 0 402718720 3.8784666061 3.7221269608 6.3301010132 480 19.1600000000 0.6453762650 0.0315782857 0.8156625032 0.0352172200 0.3409320000 0.1091610000 0.1040800000 0.0000010000 0.1250580000 0.0018270000 114702539 0 402718720 3.8783988953 3.6847984791 6.3292317390 481 19.2000000000 0.5954067111 0.0327504861 0.8156625032 0.0352753157 0.5723840000 0.1119810000 0.1466860000 0.0319770000 0.1372830000 0.1435260000 114705315 0 402718720 3.8768274784 3.7340178490 6.3305792809 482 19.2400000000 0.6206087470 0.0339701091 0.8156625032 0.0352536461 0.4277640000 0.1406530000 0.1424040000 0.0000010000 0.1412270000 0.0025600000 114708091 0 402718720 3.8761279583 3.7090818882 6.3309464455 483 19.2800000000 0.5781716704 0.0350968204 0.8156625032 0.0352881755 0.3836130000 0.1184560000 0.1085440000 0.0279760000 0.1259600000 0.0018650000 114710867 0 402718720 3.8751921654 3.7503075600 6.3324341774 484 19.3200000000 0.6077389717 0.0362799653 0.8156625032 0.0352696412 0.3211040000 0.1093870000 0.0790670000 0.0000010000 0.1299960000 0.0018460000 114713643 0 402718720 3.8755981922 3.7202692032 6.3332848549 485 19.3600000000 0.5571302772 0.0373538835 0.8156625032 0.0353382702 0.5228180000 0.1210950000 0.1083240000 0.0280730000 0.1292490000 0.1352530000 114716419 0 402718720 3.8758952618 3.7708075047 6.3335585594 486 19.4000000000 0.3052718043 0.0379051549 0.8156625032 0.0372215750 0.3376520000 0.1094930000 0.1023280000 0.0000010000 0.1230250000 0.0019540000 114719195 0 402718720 3.8746724129 4.0227136612 6.3370623589 487 19.4400000000 0.7217246294 0.0393093017 0.8156625032 0.0415786640 0.3459700000 0.1226260000 0.0464000000 0.0281900000 0.1459420000 0.0019540000 114721971 0 402718720 3.8751435280 3.6063761711 6.3374090195 488 19.4800000000 0.2538776100 0.0397489909 0.8156625032 0.0468352926 0.3295620000 0.1095810000 0.0915780000 0.0000010000 0.1257040000 0.0018730000 114724747 0 402718720 3.8753519058 4.0731749535 6.3419566154 489 19.5200000000 0.7300555706 0.0411606608 0.8156625032 0.0514024917 0.4882010000 0.1094460000 0.0436090000 0.0282330000 0.1492040000 0.1568870000 114727523 0 402718720 3.8726220131 3.5974521637 6.3451852798 490 19.5600000000 0.2615383863 0.0416104112 0.8156625032 0.0556771991 0.3272960000 0.1094880000 0.0881790000 0.0000010000 0.1269380000 0.0018630000 114730299 0 402718720 3.8743021488 4.0667214394 6.3486952782 491 19.6000000000 0.7210810781 0.0429942619 0.8156625032 0.0592772041 0.3406440000 0.1093730000 0.0512460000 0.0283340000 0.1489820000 0.0018770000 114733075 0 402718720 3.8738811016 3.6075627804 6.3497548103 492 19.6400000000 0.7213269472 0.0443729868 0.8156625032 0.0592255431 0.3258260000 0.1094890000 0.0646380000 0.0000010000 0.1490230000 0.0018590000 114735851 0 402718720 3.8738811016 3.6075627804 6.3497548103 493 19.6800000000 0.7229049802 0.0457493195 0.8156625032 0.0591738378 0.4811610000 0.1094620000 0.0649060000 0.0000010000 0.1490500000 0.1569120000 114738627 0 402718720 3.8738811016 3.6075627804 6.3497548103 494 19.7200000000 0.7228264809 0.0471199210 0.8156625032 0.0591287969 0.3260840000 0.1093980000 0.0648190000 0.0000000000 0.1491760000 0.0018660000 114741403 0 402718720 3.8738811016 3.6075627804 6.3497548103 495 19.7600000000 0.7227870822 0.0484849052 0.8156625032 0.0590830585 0.3503030000 0.1333690000 0.0652160000 0.0000000000 0.1490150000 0.0018720000 114744179 0 402718720 3.8738811016 3.6075627804 6.3497548103 496 19.8000000000 0.7236635089 0.0498461524 0.8156625032 0.0590352731 0.3377420000 0.1221280000 0.0639410000 0.0000000000 0.1489770000 0.0018560000 114746955 0 402718720 3.8738811016 3.6075627804 6.3497548103 497 19.8400000000 0.7249611020 0.0512045326 0.8156625032 0.0589845083 0.4792610000 0.1094280000 0.0631400000 0.0000000000 0.1489840000 0.1568560000 114749731 0 402718720 3.8738811016 3.6075627804 6.3497548103 498 19.8800000000 0.7256401181 0.0525588209 0.8156625032 0.0589347019 0.3239800000 0.1094050000 0.0628370000 0.0000000000 0.1490380000 0.0018610000 114752507 0 402718720 3.8738811016 3.6075627804 6.3497548103 499 19.9200000000 0.7254298329 0.0539072598 0.8156625032 0.0588868874 0.3224070000 0.1094120000 0.0612870000 0.0000010000 0.1490140000 0.0018540000 114755283 0 402718720 3.8738811016 3.6075627804 6.3497548103 500 19.9600000000 0.7267236114 0.0552528925 0.8156625032 0.0588368036 0.3227260000 0.1093860000 0.0616260000 0.0000000000 0.1490150000 0.0018540000 114758059 0 402718720 3.8738811016 3.6075627804 6.3497548103 501 20.0000000000 0.7273796201 0.0565944628 0.8156625032 0.0587899487 0.4745170000 0.1093290000 0.0582710000 0.0000010000 0.1490030000 0.1570700000 114760835 0 402718720 3.8738811016 3.6075627804 6.3497548103 502 20.0400000000 0.7279881239 0.0579319004 0.8156625032 0.0587455979 0.3177670000 0.1093850000 0.0566690000 0.0000000000 0.1490080000 0.0018660000 114763611 0 402718720 3.8738811016 3.6075627804 6.3497548103 503 20.0800000000 0.7290874124 0.0592662056 0.8156625032 0.0587006207 0.3164930000 0.1093260000 0.0554640000 0.0000010000 0.1490080000 0.0018520000 114766387 0 402718720 3.8738811016 3.6075627804 6.3497548103 504 20.1200000000 0.7295057178 0.0605960459 0.8156625032 0.0586572122 0.3173750000 0.1097520000 0.0558960000 0.0000000000 0.1490230000 0.0018550000 114769163 0 402718720 3.8738811016 3.6075627804 6.3497548103 505 20.1600000000 0.7304962277 0.0619225809 0.8156625032 0.0586137266 0.4716710000 0.1093020000 0.0556210000 0.0000010000 0.1489890000 0.1569030000 114771939 0 402718720 3.8738811016 3.6075627804 6.3497548103 506 20.2000000000 0.7308453918 0.0632445627 0.8156625032 0.0585713661 0.3164220000 0.1092110000 0.0555190000 0.0000000000 0.1489790000 0.0018550000 114774715 0 402718720 3.8738811016 3.6075627804 6.3497548103 507 20.2400000000 0.7306682467 0.0645609802 0.8156625032 0.0585277696 0.3167040000 0.1092100000 0.0557820000 0.0000000000 0.1489930000 0.0018620000 114777491 0 402718720 3.8738811016 3.6075627804 6.3497548103 508 20.2800000000 0.7304331660 0.0658717523 0.8156625032 0.0584838734 0.3179550000 0.1091240000 0.0571220000 0.0000000000 0.1489910000 0.0018620000 114780267 0 402718720 3.8738811016 3.6075627804 6.3497548103 509 20.3200000000 0.7301380634 0.0671767941 0.8156625032 0.0584420793 0.4731130000 0.1090200000 0.0572130000 0.0000000000 0.1490420000 0.1569340000 114783043 0 402718720 3.8738811016 3.6075627804 6.3497548103 510 20.3600000000 0.7307205796 0.0684778604 0.8156625032 0.0583961728 0.3139870000 0.1057700000 0.0562310000 0.0000010000 0.1493250000 0.0017970000 114785819 0 402718720 3.8738811016 3.6075627804 6.3497548103 511 20.4000000000 0.7304816246 0.0697733668 0.8156625032 0.0583510293 0.3166830000 0.1089900000 0.0558800000 0.0000010000 0.1490610000 0.0018810000 114788595 0 402718720 3.8738811016 3.6075627804 6.3497548103 512 20.4400000000 0.7311257124 0.0710650706 0.8156625032 0.0583047138 0.3146220000 0.1089030000 0.0539660000 0.0000000000 0.1490090000 0.0018790000 114791371 0 402718720 3.8738811016 3.6075627804 6.3497548103 513 20.4800000000 0.7313159108 0.0723521092 0.8156625032 0.0582566193 0.4737340000 0.1090820000 0.0583670000 0.0000010000 0.1486920000 0.1566580000 114843299 0 402718720 3.8738811016 3.6075627804 6.3497548103 514 20.5200000000 0.7316609621 0.0736348113 0.8156625032 0.0582086643 0.3178130000 0.1090380000 0.0571530000 0.0000010000 0.1487330000 0.0019810000 114948475 0 402718720 3.8738811016 3.6075627804 6.3497548103 515 20.5600000000 0.7315248251 0.0749122676 0.8156625032 0.0581585823 0.3251830000 0.1183160000 0.0551160000 0.0000010000 0.1489980000 0.0018720000 114951251 0 402718720 3.8738811016 3.6075627804 6.3497548103 516 20.6000000000 0.7314243913 0.0761845779 0.8156625032 0.0581074275 0.3180180000 0.1090700000 0.0573670000 0.0000010000 0.1487090000 0.0019670000 114954027 0 402718720 3.8738811016 3.6075627804 6.3497548103 517 20.6400000000 0.7308914661 0.0774509356 0.8156625032 0.0580558430 0.4722410000 0.1090950000 0.0565630000 0.0000000000 0.1487910000 0.1568950000 114956803 0 402718720 3.8738811016 3.6075627804 6.3497548103 518 20.6800000000 0.7301972508 0.0787110636 0.8156625032 0.0580053416 0.3146780000 0.1090370000 0.0538840000 0.0000010000 0.1489950000 0.0018880000 114959579 0 402718720 3.8738811016 3.6075627804 6.3497548103 519 20.7200000000 0.7302394509 0.0799664169 0.8156625032 0.0579553303 0.3250930000 0.1187530000 0.0547150000 0.0000000000 0.1487270000 0.0019770000 114962355 0 402718720 3.8738811016 3.6075627804 6.3497548103 520 20.7600000000 0.7287010550 0.0812139835 0.8156625032 0.0579045030 0.3151770000 0.1089960000 0.0545620000 0.0000000000 0.1487190000 0.0019820000 114965131 0 402718720 3.8738811016 3.6075627804 6.3497548103 521 20.8000000000 0.7280374169 0.0824554872 0.8156625032 0.0578533688 0.4697680000 0.1087460000 0.0540340000 0.0000000000 0.1490220000 0.1570740000 114967907 0 402718720 3.8738811016 3.6075627804 6.3497548103 522 20.8400000000 0.4330223203 0.0831270712 0.8156625032 0.0675529570 0.3692420000 0.1081920000 0.0837550000 0.0000010000 0.1744970000 0.0019180000 114970683 0 402718720 3.8513386250 3.9549250603 6.6300334930 523 20.8800000000 0.3156350553 0.0835716372 0.8156625032 0.0676873851 0.3585190000 0.1086450000 0.0844120000 0.0301180000 0.1325010000 0.0019350000 114973459 0 402718720 3.8504242897 4.0856952667 6.6080441475 524 20.9200000000 0.3180173337 0.0840190526 0.8156625032 0.0676274283 0.3347900000 0.1086630000 0.0897990000 0.0000010000 0.1335040000 0.0019270000 114976235 0 402718720 3.8487789631 4.0886144638 6.6164512634 525 20.9600000000 0.3170613945 0.0844629428 0.8156625032 0.0675631077 0.5103110000 0.1195620000 0.0896150000 0.0295840000 0.1322820000 0.1383660000 114979011 0 402718720 3.8456287384 4.0870690346 6.6162424088 526 21.0000000000 0.2994144261 0.0848715958 0.8156625032 0.0675051983 0.3447940000 0.1085520000 0.0926130000 0.0000010000 0.1408190000 0.0019170000 114981787 0 402718720 3.8429167271 4.1084780693 6.6102418900 527 21.0400000000 0.2975708544 0.0852751997 0.8156625032 0.0674418570 0.3871310000 0.1212570000 0.0967500000 0.0303500000 0.1359410000 0.0019340000 114984563 0 402718720 3.8403048515 4.1111750603 6.6065273285 528 21.0800000000 0.2859330773 0.0856552336 0.8156625032 0.0673819769 0.3489050000 0.1084210000 0.0936670000 0.0000010000 0.1439880000 0.0019290000 114987339 0 402718720 3.8360424042 4.1235604286 6.6049709320 529 21.1200000000 0.2854804695 0.0860329750 0.8156625032 0.0673183383 0.5120860000 0.1050670000 0.0914380000 0.0301940000 0.1393520000 0.1451260000 114990115 0 402718720 3.8318707943 4.1222710609 6.6023049355 530 21.1600000000 0.2915934920 0.0864208251 0.8156625032 0.0672549096 0.3497320000 0.1080440000 0.0932040000 0.0000010000 0.1456650000 0.0019140000 114992891 0 402718720 3.8292639256 4.1142945290 6.5978045464 531 21.2000000000 0.2895015180 0.0868032746 0.8156625032 0.0671918192 0.3767520000 0.1080200000 0.0937030000 0.0304730000 0.1417120000 0.0019330000 114995667 0 402718720 3.8259255886 4.1153292656 6.5941128731 532 21.2400000000 0.2833428085 0.0871727098 0.8156625032 0.0671304718 0.3471160000 0.1079170000 0.0875680000 0.0000010000 0.1488040000 0.0019210000 114998443 0 402718720 3.8214802742 4.1221466064 6.5910258293 533 21.2800000000 0.2819041014 0.0875380595 0.8156625032 0.0670679922 0.5328370000 0.1283780000 0.0757150000 0.0305810000 0.1454000000 0.1518530000 115001219 0 402718720 3.8177840710 4.1239309311 6.5890522003 534 21.3200000000 0.2792020142 0.0878969808 0.8156625032 0.0670057129 0.3507230000 0.1078160000 0.0883370000 0.0000010000 0.1517490000 0.0019190000 115003995 0 402718720 3.8137745857 4.1238770485 6.5861625671 535 21.3600000000 0.2775118351 0.0882514010 0.8156625032 0.0669432267 0.4003310000 0.1166390000 0.1018530000 0.0306710000 0.1483230000 0.0019310000 115006771 0 402718720 3.8084895611 4.1240191460 6.5851650238 536 21.4000000000 0.2744688392 0.0885988216 0.8156625032 0.0668808415 0.3638370000 0.1044400000 0.1016630000 0.0000010000 0.1548240000 0.0019590000 115009547 0 402718720 3.8046562672 4.1242280006 6.5784587860 537 21.4400000000 0.2744696438 0.0889449498 0.8156625032 0.0668184672 0.5627160000 0.1073930000 0.1028600000 0.0301560000 0.1506490000 0.1706270000 115012323 0 402718720 3.8003499508 4.1241631508 6.5734105110 538 21.4800000000 0.2725090384 0.0892861470 0.8156625032 0.0667564041 0.3364100000 0.1116280000 0.0660750000 0.0000010000 0.1558780000 0.0019180000 115015099 0 402718720 3.7956526279 4.1254348755 6.5677862167 539 21.5200000000 0.2687268853 0.0896190612 0.8156625032 0.0666946883 0.3671600000 0.1069680000 0.0743350000 0.0307550000 0.1522480000 0.0019280000 115017875 0 402718720 3.7913649082 4.1278629303 6.5639538765 540 21.5600000000 0.2637577951 0.0899415403 0.8156625032 0.0666339090 0.3436880000 0.1068320000 0.0754710000 0.0000010000 0.1586080000 0.0018520000 115020651 0 402718720 3.7864170074 4.1337652206 6.5610041618 541 21.6000000000 0.2617716193 0.0902591560 0.8156625032 0.0665723144 0.5198950000 0.1066260000 0.0669710000 0.0302860000 0.1542440000 0.1608380000 115023427 0 402718720 3.7815668583 4.1331553459 6.5571141243 542 21.6400000000 0.2583074272 0.0905692081 0.8156625032 0.0665112669 0.3616150000 0.1191520000 0.0763500000 0.0000000000 0.1632750000 0.0019190000 115026203 0 402718720 3.7775080204 4.1318492889 6.5527000427 543 21.6800000000 0.2575426400 0.0908767098 0.8156625032 0.0664504804 0.3965450000 0.1040620000 0.1013370000 0.0309700000 0.1573150000 0.0019300000 115028979 0 402718720 3.7732648849 4.1282925606 6.5471034050 544 21.7200000000 0.2560223043 0.0911802863 0.8156625032 0.0663945224 0.3823740000 0.1055700000 0.1041440000 0.0000000000 0.1698010000 0.0019250000 115031755 0 402718720 3.7656958103 4.1225199699 6.5326013565 545 21.7600000000 0.2566393316 0.0914838809 0.8156625032 0.0663336197 0.5803490000 0.1148690000 0.1090840000 0.0310370000 0.1588210000 0.1656080000 115034531 0 402718720 3.7608349323 4.1232595444 6.5257773399 546 21.8000000000 0.2665389478 0.0918044946 0.8156625032 0.0662743784 0.3917430000 0.1194000000 0.1093860000 0.0000010000 0.1601110000 0.0019190000 115037307 0 402718720 3.7563402653 4.1095185280 6.5213527679 547 21.8400000000 0.2626278996 0.0921167860 0.8156625032 0.0662146229 0.4084740000 0.1049240000 0.1113550000 0.0310400000 0.1582890000 0.0019300000 115040083 0 402718720 3.7517056465 4.1108326912 6.5153708458 548 21.8800000000 0.2752587795 0.0924509867 0.8156625032 0.0661561942 0.3742870000 0.1048560000 0.1057590000 0.0000010000 0.1608160000 0.0019240000 115042859 0 402718720 3.7459180355 4.0989298820 6.5091476440 549 21.9200000000 0.2865964770 0.0928046215 0.8156625032 0.0660966097 0.5664180000 0.1048330000 0.1060200000 0.0310390000 0.1583580000 0.1652240000 115045635 0 402718720 3.7406704426 4.0899915695 6.5072813034 550 21.9600000000 0.2916214168 0.0931661065 0.8156625032 0.0660381309 0.3738210000 0.1019960000 0.1063210000 0.0000010000 0.1627240000 0.0018430000 115048411 0 402718720 3.7372577190 4.0759482384 6.5040884018 551 22.0000000000 0.2879230380 0.0935195674 0.8156625032 0.0659790024 0.4009690000 0.1018700000 0.1070060000 0.0308740000 0.1583650000 0.0019210000 115051187 0 402718720 3.7330448627 4.0773501396 6.4955224991 552 22.0400000000 0.2987578809 0.0938913759 0.8156625032 0.0659201083 0.3773170000 0.1043710000 0.1081790000 0.0000000000 0.1619260000 0.0019040000 115053963 0 402718720 3.7275519371 4.0714526176 6.4892349243 553 22.0800000000 0.2970969081 0.0942588362 0.8156625032 0.0658606926 0.5818230000 0.1171410000 0.1086980000 0.0310830000 0.1586260000 0.1653120000 115056739 0 402718720 3.7234349251 4.0742840767 6.4834470749 554 22.1200000000 0.3007560968 0.0946315750 0.8156625032 0.0658011715 0.3803440000 0.1019140000 0.1113230000 0.0000000000 0.1642570000 0.0019070000 115059515 0 402718720 3.7192716599 4.0666298866 6.4777555466 555 22.1600000000 0.3024210334 0.0950059704 0.8156625032 0.0657417687 0.4410130000 0.1318340000 0.1154160000 0.0311770000 0.1595740000 0.0020130000 115062291 0 402718720 3.7153294086 4.0651745796 6.4710912704 556 22.2000000000 0.3051054478 0.0953838471 0.8156625032 0.0656826388 0.3833310000 0.1044760000 0.1103620000 0.0000000000 0.1656210000 0.0019140000 115065067 0 402718720 3.7120890617 4.0578403473 6.4626765251 557 22.2400000000 0.3045260906 0.0957593269 0.8156625032 0.0656240538 0.5733890000 0.1045510000 0.1106620000 0.0311860000 0.1595930000 0.1664350000 115067843 0 402718720 3.7076539993 4.0576024055 6.4514222145 558 22.2800000000 0.3068659604 0.0961376542 0.8156625032 0.0655651797 0.3848150000 0.1046500000 0.1114460000 0.0000000000 0.1658600000 0.0019040000 115070619 0 402718720 3.7043633461 4.0515003204 6.4422211647 559 22.3200000000 0.2321137488 0.0963809031 0.8156625032 0.0656419377 0.4348040000 0.1233050000 0.1186100000 0.0313480000 0.1585500000 0.0019910000 115073395 0 402718720 3.7019009590 4.0914850235 6.3516921997 560 22.3600000000 0.1934231073 0.0965541927 0.8156625032 0.0657865025 0.4412300000 0.1260050000 0.1163920000 0.0000010000 0.1959790000 0.0019060000 115076171 0 402718720 3.7004377842 4.1181206703 6.2329974174 561 22.4000000000 0.1694127321 0.0966840653 0.8156625032 0.0657468474 0.5517840000 0.1052660000 0.1067310000 0.0314780000 0.1502180000 0.1571310000 115078947 0 402718720 3.6973538399 4.1479635239 6.2041215897 562 22.4400000000 0.2051327527 0.0968770345 0.8156625032 0.0657424023 0.3691370000 0.1054300000 0.1121200000 0.0000010000 0.1487250000 0.0018970000 115081723 0 402718720 3.6932866573 4.0992379189 6.2445068359 563 22.4800000000 0.1998060197 0.0970598569 0.8156625032 0.0656846691 0.4019770000 0.1055750000 0.1140960000 0.0315530000 0.1478750000 0.0019080000 115084499 0 402718720 3.6904804707 4.1029572487 6.2332592010 564 22.5200000000 0.1717970222 0.0971923696 0.8156625032 0.0656585586 0.3574330000 0.1057110000 0.1024650000 0.0000010000 0.1463970000 0.0019010000 115087275 0 402718720 3.6868257523 4.1326422691 6.2633767128 565 22.5600000000 0.1993589252 0.0973731953 0.8156625032 0.0656049645 0.5653120000 0.1169800000 0.1131390000 0.0316740000 0.1478550000 0.1546920000 115090051 0 402718720 3.6792960167 4.1085677147 6.2578020096 566 22.6000000000 0.1759263724 0.0975119819 0.8156625032 0.0655892948 0.3672910000 0.1061080000 0.1118350000 0.0000010000 0.1464850000 0.0019000000 115092827 0 402718720 3.6751143932 4.1420092583 6.2937107086 567 22.6400000000 0.1917650998 0.0976782131 0.8156625032 0.0655380221 0.4069210000 0.1064060000 0.1189050000 0.0317700000 0.1468360000 0.0019970000 115095603 0 402718720 3.6719710827 4.1181607246 6.2709584236 568 22.6800000000 0.2006901950 0.0978595722 0.8156625032 0.0655170902 0.3679970000 0.1060150000 0.1115980000 0.0000010000 0.1475260000 0.0018830000 115098379 0 402718720 3.6679685116 4.1323795319 6.3118309975 569 22.7200000000 0.1955719441 0.0980312987 0.8156625032 0.0654637939 0.5554030000 0.1066770000 0.1147590000 0.0318670000 0.1471620000 0.1539670000 115101155 0 402718720 3.6645317078 4.1298317909 6.2897038460 570 22.7600000000 0.2067904025 0.0982221042 0.8156625032 0.0654454057 0.3691890000 0.1067810000 0.1120350000 0.0000010000 0.1475120000 0.0018830000 115103931 0 402718720 3.6606943607 4.1447982788 6.3311724663 571 22.8000000000 0.2067360878 0.0984121462 0.8156625032 0.0653925138 0.4000930000 0.1038840000 0.1135350000 0.0317550000 0.1481060000 0.0018290000 115106707 0 402718720 3.6584699154 4.1285724640 6.3087501526 572 22.8400000000 0.2228854597 0.0986297569 0.8156625032 0.0653849402 0.3829460000 0.1198070000 0.1121340000 0.0000010000 0.1481320000 0.0018810000 115109483 0 402718720 3.6545286179 4.1635322571 6.3542971611 573 22.8800000000 0.2201064974 0.0988417582 0.8156625032 0.0653559916 0.5577320000 0.1071180000 0.1138990000 0.0321480000 0.1483470000 0.1552300000 115112259 0 402718720 3.6508963108 4.1315135956 6.3143200874 574 22.9200000000 0.2598040998 0.0991221804 0.8156625032 0.0653658892 0.3723850000 0.1073100000 0.1118450000 0.0000010000 0.1503670000 0.0018800000 115115035 0 402718720 3.6453058720 4.1420865059 6.3727807999 575 22.9600000000 0.2455485612 0.0993768349 0.8156625032 0.0653270626 0.4324640000 0.1252020000 0.1238230000 0.0323270000 0.1480760000 0.0019880000 115117811 0 402718720 3.6424016953 4.1775598526 6.3720283508 576 23.0000000000 0.2484552413 0.0996356516 0.8156625032 0.0652703293 0.3767830000 0.1044040000 0.1202640000 0.0000010000 0.1491930000 0.0019030000 115120587 0 402718720 3.6389377117 4.1685414314 6.3671975136 577 23.0400000000 0.2643258572 0.0999210766 0.8156625032 0.0652344145 0.5647960000 0.1077800000 0.1186220000 0.0324760000 0.1490460000 0.1558760000 115123363 0 402718720 3.6343977451 4.1872949600 6.3883233070 578 23.0800000000 0.2620253265 0.1002015338 0.8156625032 0.0651780306 0.3751690000 0.1047060000 0.1156140000 0.0000000000 0.1519770000 0.0018940000 115126139 0 402718720 3.6321828365 4.1900773048 6.3790636063 579 23.1200000000 0.2825384736 0.1005164507 0.8156625032 0.0651303040 0.4083620000 0.1080550000 0.1149630000 0.0320540000 0.1504000000 0.0018960000 115128915 0 402718720 3.6302917004 4.1948971748 6.3946099281 580 23.1600000000 0.2882455885 0.1008401217 0.8156625032 0.0650754621 0.3159290000 0.1081330000 0.0484990000 0.0000000000 0.1564160000 0.0018970000 115131691 0 402718720 3.6289281845 4.1994633675 6.3949804306 581 23.2000000000 0.3107162118 0.1012013542 0.8156625032 0.0650375586 0.5746970000 0.1083780000 0.1143640000 0.0328490000 0.1546390000 0.1634740000 115134467 0 402718720 3.6234207153 4.2179865837 6.4171953201 582 23.2400000000 0.3263103962 0.1015881395 0.8156625032 0.0649901365 0.3863540000 0.1086070000 0.1162920000 0.0000000000 0.1585680000 0.0018910000 115137243 0 402718720 3.6159515381 4.2204904556 6.4287157059 583 23.2800000000 0.3453984857 0.1020063390 0.8156625032 0.0649425714 0.4148690000 0.1088550000 0.1149540000 0.0331110000 0.1550540000 0.0018950000 115140019 0 402718720 3.6134705544 4.2261061668 6.4423594475 584 23.3200000000 0.3613340557 0.1024503934 0.8156625032 0.0648932363 0.3918830000 0.1226290000 0.1058030000 0.0000000000 0.1605670000 0.0018900000 115142795 0 402718720 3.6098010540 4.2327666283 6.4528717995 585 23.3600000000 0.3739826083 0.1029145510 0.8156625032 0.0648407503 0.5801690000 0.1092840000 0.1153980000 0.0334120000 0.1559360000 0.1651420000 115145571 0 402718720 3.6031658649 4.2315368652 6.4587917328 586 23.4000000000 0.3872189820 0.1033997121 0.8156625032 0.0647876529 0.3898460000 0.1094080000 0.1148250000 0.0000010000 0.1627350000 0.0018940000 115148347 0 402718720 3.5998287201 4.2124958038 6.4634866714 587 23.4400000000 0.3967681527 0.1038994880 0.8156625032 0.0647355944 0.4168040000 0.1094960000 0.1151890000 0.0337350000 0.1554800000 0.0018960000 115151123 0 402718720 3.5951147079 4.2155308723 6.4675674438 588 23.4800000000 0.4006741643 0.1044042069 0.8156625032 0.0646822931 0.3928300000 0.1096590000 0.1152240000 0.0000010000 0.1650470000 0.0019000000 115153899 0 402718720 3.5882236958 4.1906590462 6.4604167938 589 23.5200000000 0.4002737403 0.1049065320 0.8156625032 0.0646284617 0.5902230000 0.1098440000 0.1223150000 0.0340450000 0.1567900000 0.1662150000 115156675 0 402718720 3.5818891525 4.1892232895 6.4530992508 590 23.5600000000 0.4015249312 0.1054092751 0.8156625032 0.0645737541 0.3626410000 0.1099070000 0.0870170000 0.0000010000 0.1628160000 0.0018930000 115159451 0 402718720 3.5758750439 4.1777410507 6.4448618889 591 23.6000000000 0.4034782350 0.1059136219 0.8156625032 0.0645190757 0.4249340000 0.1099790000 0.1215740000 0.0342820000 0.1560500000 0.0019840000 115162227 0 402718720 3.5694651604 4.1710815430 6.4386739731 592 23.6400000000 0.4030397832 0.1064155242 0.8156625032 0.0644647914 0.3925570000 0.1100670000 0.1189850000 0.0000010000 0.1606000000 0.0018880000 115165003 0 402718720 3.5631928444 4.1689496040 6.4298853874 593 23.6800000000 0.4018731415 0.1069137664 0.8156625032 0.0644115127 0.5806620000 0.1102210000 0.1160470000 0.0345360000 0.1547710000 0.1640620000 115167779 0 402718720 3.5572342873 4.1704168320 6.4214220047 594 23.7200000000 0.4051345289 0.1074158215 0.8156625032 0.0643572897 0.3908100000 0.1102910000 0.1159030000 0.0000000000 0.1617130000 0.0018980000 115170555 0 402718720 3.5499386787 4.1588835716 6.4153447151 595 23.7600000000 0.4028098583 0.1079122821 0.8156625032 0.0643047684 0.3978530000 0.1105180000 0.0973750000 0.0348610000 0.1521670000 0.0019040000 115173331 0 402718720 3.5414111614 4.1602063179 6.4067072868 596 23.8000000000 0.3975726664 0.1083982895 0.8156625032 0.0642529003 0.3349720000 0.1104980000 0.0664140000 0.0000000000 0.1551410000 0.0018890000 115176107 0 402718720 3.5340006351 4.1668925285 6.3960394859 597 23.8400000000 0.3961644769 0.1088803099 0.8156625032 0.0641991540 0.5890700000 0.1305330000 0.1166290000 0.0350640000 0.1490290000 0.1567790000 115178883 0 402718720 3.5301187038 4.1684355736 6.3868918419 598 23.8800000000 0.3965424299 0.1093613502 0.8156625032 0.0641459147 0.3680350000 0.1105950000 0.1022920000 0.0000000000 0.1520940000 0.0019790000 115181659 0 402718720 3.5215938091 4.1658544540 6.3788065910 599 23.9200000000 0.3946751058 0.1098376670 0.8156625032 0.0640935844 0.3773740000 0.1106160000 0.0822910000 0.0348180000 0.1467130000 0.0019050000 115184435 0 402718720 3.5131866932 4.1676912308 6.3687405586 600 23.9600000000 0.3923749924 0.1103085625 0.8156625032 0.0640416043 0.3536830000 0.1107620000 0.0875940000 0.0000000000 0.1523890000 0.0019030000 115187211 0 402718720 3.5072634220 4.1703495979 6.3594121933 601 24.0000000000 0.3907363415 0.1107751645 0.8156625032 0.0639898750 0.5626580000 0.1108170000 0.1160180000 0.0356390000 0.1457820000 0.1533690000 115189987 0 402718720 3.4997947216 4.1706848145 6.3500061035 602 24.0400000000 0.3867186010 0.1112335423 0.8156625032 0.0639429116 0.3337880000 0.1097980000 0.0688990000 0.0000000000 0.1521730000 0.0019010000 115192763 0 402718720 3.4835081100 4.1749119759 6.3303408623 603 24.0800000000 0.3864186704 0.1116899024 0.8156625032 0.0638914582 0.3619440000 0.1109150000 0.0676080000 0.0354790000 0.1450020000 0.0019150000 115195539 0 402718720 3.4743244648 4.1726126671 6.3219485283 604 24.1200000000 0.3849101663 0.1121422538 0.8156625032 0.0638407970 0.3354170000 0.1109530000 0.0728700000 0.0000010000 0.1485190000 0.0019970000 115198315 0 402718720 3.4625053406 4.1741843224 6.3126406670 605 24.1600000000 0.3800335526 0.1125850493 0.8156625032 0.0637901865 0.5164820000 0.1201750000 0.0566390000 0.0362550000 0.1459400000 0.1564330000 115201091 0 402718720 3.4562351704 4.1807575226 6.3008966446 606 24.2000000000 0.3780824840 0.1130231639 0.8156625032 0.0637386975 0.3338120000 0.1110080000 0.0688530000 0.0000000000 0.1510150000 0.0019030000 115203867 0 402718720 3.4509038925 4.1833405495 6.2909717560 607 24.2400000000 0.3778812587 0.1134595034 0.8156625032 0.0636868550 0.3578420000 0.1110460000 0.0584610000 0.0365490000 0.1488280000 0.0019110000 115206643 0 402718720 3.4439885616 4.1820874214 6.2822070122 608 24.2800000000 0.3776861727 0.1138940868 0.8156625032 0.0636351644 0.3249410000 0.1109940000 0.0586450000 0.0000010000 0.1523560000 0.0019100000 115209419 0 402718720 3.4358663559 4.1812911034 6.2730016708 609 24.3200000000 0.3752975166 0.1143233207 0.8156625032 0.0635841261 0.5203080000 0.1110330000 0.0587240000 0.0366520000 0.1493410000 0.1635090000 115212195 0 402718720 3.4277136326 4.1830806732 6.2627859116 610 24.3600000000 0.3826062381 0.1147631287 0.8156625032 0.0635355988 0.3424330000 0.1233720000 0.0614240000 0.0000000000 0.1545350000 0.0020120000 115214971 0 402718720 3.4226212502 4.1702113152 6.2595820427 611 24.4000000000 0.3842175603 0.1152041343 0.8156625032 0.0634842805 0.4141250000 0.1385570000 0.0812770000 0.0369200000 0.1534960000 0.0026830000 115217747 0 402718720 3.4178037643 4.1657443047 6.2518982887 612 24.4400000000 0.3799657822 0.1156367514 0.8156625032 0.0634342635 0.4050630000 0.1426450000 0.1045660000 0.0000000000 0.1548760000 0.0019180000 115220523 0 402718720 3.4113068581 4.1602478027 6.2380452156 613 24.4800000000 0.3802964389 0.1160684964 0.8156625032 0.0633841010 0.5721970000 0.1111720000 0.1067440000 0.0370940000 0.1513920000 0.1647410000 115223299 0 402718720 3.4041914940 4.1603026390 6.2295193672 614 24.5200000000 0.3868047893 0.1165094350 0.8156625032 0.0633343495 0.3871070000 0.1110760000 0.1161320000 0.0000000000 0.1569350000 0.0019270000 115226075 0 402718720 3.3974297047 4.1555948257 6.2275753021 615 24.5600000000 0.3873732686 0.1169498640 0.8156625032 0.0632837819 0.4061160000 0.1110860000 0.1017450000 0.0373290000 0.1528310000 0.0020220000 115228851 0 402718720 3.3917946815 4.1515855789 6.2185854912 616 24.6000000000 0.3883856237 0.1173905065 0.8156625032 0.0632335484 0.3495150000 0.1111190000 0.0777960000 0.0000010000 0.1576130000 0.0019260000 115231627 0 402718720 3.3843190670 4.1495347023 6.2099032402 617 24.6400000000 0.3894375265 0.1178314255 0.8156625032 0.0631831741 0.5793280000 0.1106350000 0.1064820000 0.0374900000 0.1551740000 0.1685100000 115234403 0 402718720 3.3772125244 4.1456689835 6.2009491920 618 24.6800000000 0.3909062743 0.1182732941 0.8156625032 0.0631330198 0.3512320000 0.1111010000 0.0777020000 0.0000010000 0.1594460000 0.0019270000 115237179 0 402718720 3.3728249073 4.1439490318 6.1931943893 619 24.7200000000 0.3906543553 0.1187133282 0.8156625032 0.0630825623 0.3968880000 0.1111710000 0.0870500000 0.0377140000 0.1579460000 0.0019330000 115239955 0 402718720 3.3695256710 4.1412754059 6.1845860481 620 24.7600000000 0.3934696615 0.1191564835 0.8156625032 0.0630361118 0.3566600000 0.1111890000 0.0778910000 0.0000010000 0.1645850000 0.0019300000 115242731 0 402718720 3.3571515083 4.1365547180 6.1673116684 621 24.8000000000 0.3949467838 0.1196005903 0.8156625032 0.0629862648 0.5577350000 0.1112430000 0.0580680000 0.0379840000 0.1654270000 0.1839550000 115245507 0 402718720 3.3526427746 4.1332364082 6.1599349976 622 24.8400000000 0.3940828741 0.1200418802 0.8156625032 0.0629363537 0.3991600000 0.1112130000 0.1163320000 0.0000000000 0.1686180000 0.0019330000 115248283 0 402718720 3.3457691669 4.1287608147 6.1484694481 623 24.8800000000 0.3957474530 0.1204844252 0.8156625032 0.0628862512 0.3996270000 0.1111880000 0.0774130000 0.0382500000 0.1697720000 0.0019390000 115251059 0 402718720 3.3404133320 4.1254019737 6.1403775215 624 24.9200000000 0.3966560066 0.1209270079 0.8156625032 0.0628360030 0.3769340000 0.1315100000 0.0713550000 0.0000010000 0.1709100000 0.0020330000 115253835 0 402718720 3.3348219395 4.1214623451 6.1311435699 625 24.9600000000 0.3981702030 0.1213705970 0.8156625032 0.0627859046 0.6050260000 0.1111810000 0.0914790000 0.0382550000 0.1704510000 0.1925990000 115256611 0 402718720 3.3291957378 4.1191668510 6.1217532158 626 25.0000000000 0.3988663554 0.1218138810 0.8156625032 0.0627359320 0.3635760000 0.1111570000 0.0776290000 0.0000010000 0.1717660000 0.0019420000 115259387 0 402718720 3.3222026825 4.1165847778 6.1112298965 627 25.0400000000 0.3999738097 0.1222575172 0.8156625032 0.0626863935 0.4238730000 0.1111640000 0.1012850000 0.0378170000 0.1704220000 0.0020460000 115262163 0 402718720 3.3170964718 4.1128616333 6.1015830040 628 25.0800000000 0.4013415277 0.1227019185 0.8156625032 0.0626368512 0.3540560000 0.1111390000 0.0677760000 0.0000010000 0.1721170000 0.0019440000 115264939 0 402718720 3.3117830753 4.1087818146 6.0923008919 629 25.1200000000 0.4034013450 0.1231481815 0.8156625032 0.0625872747 0.5950280000 0.1072230000 0.0863360000 0.0378250000 0.1705640000 0.1919920000 115267715 0 402718720 3.3047702312 4.1058297157 6.0810427666 630 25.1600000000 0.4032287598 0.1235927538 0.8156625032 0.0625381051 0.3528220000 0.1110340000 0.0677480000 0.0000000000 0.1710150000 0.0019460000 115270491 0 402718720 3.3005485535 4.1024947166 6.0699877739 631 25.2000000000 0.4039886594 0.1240371214 0.8156625032 0.0624884994 0.4429120000 0.1110880000 0.1214510000 0.0382790000 0.1689010000 0.0020510000 115273267 0 402718720 3.2972772121 4.0993247032 6.0599765778 632 25.2400000000 0.4054371417 0.1244823746 0.8156625032 0.0624390120 0.3630720000 0.1110440000 0.0812640000 0.0000010000 0.1675780000 0.0020490000 115276043 0 402718720 3.2903766632 4.0953340530 6.0476899147 633 25.2800000000 0.4064263701 0.1249277837 0.8156625032 0.0623900747 0.5636360000 0.1110000000 0.0582600000 0.0380650000 0.1669830000 0.1882520000 115278819 0 402718720 3.2841200829 4.0906281471 6.0355615616 634 25.3200000000 0.4070149362 0.1253727161 0.8156625032 0.0623411380 0.3960480000 0.1109690000 0.1158880000 0.0000010000 0.1661490000 0.0019420000 115281595 0 402718720 3.2810966969 4.0874767303 6.0254297256 635 25.3600000000 0.4083806872 0.1258183980 0.8156625032 0.0622924368 0.4055560000 0.1227220000 0.0773270000 0.0375000000 0.1649600000 0.0019480000 115284371 0 402718720 3.2803328037 4.0844368935 6.0175981522 636 25.4000000000 0.4107165933 0.1262663511 0.8156625032 0.0622470809 0.3541770000 0.1109840000 0.0776650000 0.0000010000 0.1624970000 0.0019390000 115287147 0 402718720 3.2710375786 4.0804405212 6.0049004555 637 25.4400000000 0.4120892286 0.1267150526 0.8156625032 0.0621981636 0.5776450000 0.1290180000 0.0681500000 0.0379110000 0.1608800000 0.1805870000 115289923 0 402718720 3.2619884014 4.0771665573 5.9907188416 638 25.4800000000 0.4121810794 0.1271624916 0.8156625032 0.0621500725 0.3666560000 0.1109770000 0.0910180000 0.0000010000 0.1616080000 0.0019410000 115292699 0 402718720 3.2619173527 4.0756583214 5.9806747437 639 25.5200000000 0.4137063622 0.1276109170 0.8156625032 0.0621013886 0.3911660000 0.1109410000 0.0775040000 0.0377890000 0.1618880000 0.0019460000 115295475 0 402718720 3.2575480938 4.0725154877 5.9696803093 640 25.5600000000 0.4151040316 0.1280601250 0.8156625032 0.0620531106 0.3506710000 0.1109210000 0.0749630000 0.0000010000 0.1617330000 0.0019450000 115298251 0 402718720 3.2534635067 4.0681691170 5.9574213028 641 25.6000000000 0.4162859619 0.1285097753 0.8156625032 0.0620047681 0.5475200000 0.1070370000 0.0576800000 0.0373550000 0.1621250000 0.1822230000 115301027 0 402718720 3.2509875298 4.0652203560 5.9467525482 642 25.6400000000 0.4161008000 0.1289577364 0.8156625032 0.0619564150 0.3442570000 0.1108990000 0.0680280000 0.0000010000 0.1622860000 0.0019530000 115303803 0 402718720 3.2477858067 4.0613107681 5.9336810112 643 25.6800000000 0.4192580283 0.1294092143 0.8156625032 0.0619082185 0.3810130000 0.1108460000 0.0678420000 0.0377350000 0.1615220000 0.0019520000 115306579 0 402718720 3.2451581955 4.0564494133 5.9241333008 644 25.7200000000 0.4198244214 0.1298601696 0.8156625032 0.0618602001 0.3498630000 0.1070190000 0.0769630000 0.0000010000 0.1628250000 0.0019470000 115309355 0 402718720 3.2416417599 4.0519132614 5.9125137329 645 25.7600000000 0.4206813574 0.1303110552 0.8156625032 0.0618122875 0.6045290000 0.1201310000 0.1021270000 0.0377270000 0.1616500000 0.1817760000 115312131 0 402718720 3.2363438606 4.0486197472 5.9001078606 646 25.8000000000 0.4226159155 0.1307635395 0.8156625032 0.0617646549 0.3452090000 0.1108470000 0.0679220000 0.0000000000 0.1633860000 0.0019430000 115314907 0 402718720 3.2334558964 4.0451641083 5.8891272545 647 25.8400000000 0.4240182936 0.1312167926 0.8156625032 0.0617170398 0.4302490000 0.1108210000 0.1158670000 0.0377080000 0.1627870000 0.0019510000 115317683 0 402718720 3.2309837341 4.0427627563 5.8780932426 648 25.8800000000 0.4248377085 0.1316699113 0.8156625032 0.0616695121 0.3664930000 0.1108120000 0.0867330000 0.0000000000 0.1658820000 0.0019430000 115320459 0 402718720 3.2305173874 4.0395188332 5.8692278862 649 25.9200000000 0.4269612730 0.1321249057 0.8156625032 0.0616225117 0.5532930000 0.1078270000 0.0580130000 0.0372670000 0.1644460000 0.1846370000 115323235 0 402718720 3.2262208462 4.0347938538 5.8583207130 650 25.9600000000 0.4291342199 0.1325818431 0.8156625032 0.0615754824 0.3884190000 0.1267090000 0.0913190000 0.0000010000 0.1671730000 0.0020460000 115326011 0 402718720 3.2221753597 4.0301256180 5.8475089073 651 26.0000000000 0.4309566319 0.1330401761 0.8156625032 0.0615286462 0.3992610000 0.1108780000 0.0808640000 0.0373810000 0.1670400000 0.0019450000 115328787 0 402718720 3.2198348045 4.0254631042 5.8384094238 652 26.0400000000 0.4318897128 0.1334985343 0.8156625032 0.0614820279 0.3518730000 0.1108950000 0.0677980000 0.0000000000 0.1701190000 0.0019410000 115331563 0 402718720 3.2177138329 4.0212554932 5.8272104263 653 26.0800000000 0.4338326752 0.1339584640 0.8156625032 0.0614354498 0.5857850000 0.1109370000 0.0771410000 0.0378940000 0.1692250000 0.1894650000 115334339 0 402718720 3.2131881714 4.0157432556 5.8161244392 654 26.1200000000 0.4353905618 0.1344193694 0.8156625032 0.0613890814 0.3640350000 0.1109300000 0.0770950000 0.0000000000 0.1729420000 0.0019380000 115337115 0 402718720 3.2099661827 4.0109872818 5.8062267303 655 26.1600000000 0.4369584918 0.1348812612 0.8156625032 0.0613426990 0.4363920000 0.1232760000 0.1008090000 0.0381630000 0.1710710000 0.0019420000 115339891 0 402718720 3.2066805363 4.0056328773 5.7962183952 656 26.2000000000 0.4388442636 0.1353446194 0.8156625032 0.0612967000 0.3847530000 0.1109310000 0.0964830000 0.0000010000 0.1742800000 0.0019380000 115342667 0 402718720 3.2024335861 4.0004734993 5.7858352661 657 26.2400000000 0.4415652454 0.1358107086 0.8156625032 0.0612502395 0.6249370000 0.1070130000 0.1142940000 0.0376280000 0.1725380000 0.1923350000 115345443 0 402718720 3.1971197128 3.9940760136 5.7757110596 658 26.2800000000 0.4424353540 0.1362767035 0.8156625032 0.0612039678 0.4043540000 0.1104740000 0.1157450000 0.0000010000 0.1750720000 0.0019400000 115348219 0 402718720 3.1948504448 3.9899806976 5.7664093971 659 26.3200000000 0.4441702068 0.1367439167 0.8156625032 0.0611578914 0.4366000000 0.1070100000 0.1145030000 0.0376510000 0.1743580000 0.0019450000 115350995 0 402718720 3.1906208992 3.9856510162 5.7556681633 660 26.3600000000 0.4456738532 0.1372119924 0.8156625032 0.0611118266 0.4087220000 0.1108980000 0.1178740000 0.0000010000 0.1768670000 0.0019420000 115353771 0 402718720 3.1875908375 3.9811944962 5.7453351021 661 26.4000000000 0.4477112591 0.1376817341 0.8156625032 0.0610660025 0.6155500000 0.1109200000 0.0961360000 0.0382280000 0.1748670000 0.1942540000 115356547 0 402718720 3.1835243702 3.9764764309 5.7346749306 662 26.4400000000 0.4495284259 0.1381528016 0.8156625032 0.0610204573 0.3687520000 0.1303660000 0.0582730000 0.0000010000 0.1770240000 0.0019400000 115359323 0 402718720 3.1782610416 3.9719674587 5.7230911255 663 26.4800000000 0.4513989389 0.1386252694 0.8156625032 0.0609746590 0.4404840000 0.1070550000 0.1149670000 0.0378220000 0.1776030000 0.0018850000 115362099 0 402718720 3.1731154919 3.9679946899 5.7104358673 664 26.5200000000 0.4529992342 0.1390987242 0.8156625032 0.0609292709 0.4088930000 0.1109040000 0.1159650000 0.0000010000 0.1789430000 0.0019460000 115364875 0 402718720 3.1689674854 3.9635391235 5.6991553307 665 26.5600000000 0.4562313855 0.1395756154 0.8156625032 0.0608867049 0.6572370000 0.1198790000 0.1233010000 0.0381120000 0.1772290000 0.1975770000 115367651 0 402718720 3.1607515812 3.9567346573 5.6756143570 666 26.6000000000 0.4581904709 0.1400540161 0.8156625032 0.0608412411 0.4115060000 0.1109990000 0.1161710000 0.0000010000 0.1813080000 0.0018840000 115370427 0 402718720 3.1557393074 3.9535319805 5.6622653008 667 26.6400000000 0.4591351151 0.1405323985 0.8156625032 0.0607958618 0.3994680000 0.1109980000 0.0676550000 0.0383180000 0.1793860000 0.0019470000 115373203 0 402718720 3.1522836685 3.9510791302 5.6503300667 668 26.6800000000 0.4614691138 0.1410128427 0.8156625032 0.0607505368 0.4242080000 0.1238490000 0.1159090000 0.0000010000 0.1813240000 0.0019420000 115375979 0 402718720 3.1469960213 3.9469656944 5.6374583244 669 26.7200000000 0.4627290964 0.1414937340 0.8156625032 0.0607056424 0.6474990000 0.1110710000 0.1155270000 0.0381780000 0.1810490000 0.2005180000 115378755 0 402718720 3.1437757015 3.9445621967 5.6252593994 670 26.7600000000 0.4639436007 0.1419750024 0.8156625032 0.0606606996 0.3752820000 0.1110920000 0.0678280000 0.0000000000 0.1932700000 0.0019440000 115381531 0 402718720 3.1407022476 3.9430117607 5.6126198769 671 26.8000000000 0.4658853710 0.1424577302 0.8156625032 0.0606158004 0.4504530000 0.1110750000 0.1152030000 0.0382770000 0.1827770000 0.0019440000 115384307 0 402718720 3.1352348328 3.9386618137 5.6001377106 672 26.8400000000 0.4675849080 0.1429415505 0.8156625032 0.0605715412 0.4154820000 0.1110520000 0.1153400000 0.0000010000 0.1860210000 0.0019340000 115387083 0 402718720 3.1301829815 3.9340300560 5.5880622864 673 26.8800000000 0.4694006443 0.1434266308 0.8156625032 0.0605272630 0.6592400000 0.1110640000 0.1154320000 0.0383880000 0.1860770000 0.2071300000 115389859 0 402718720 3.1264569759 3.9294147491 5.5760068893 674 26.9200000000 0.4713667035 0.1439131888 0.8156625032 0.0604826213 0.4312520000 0.1243930000 0.1151260000 0.0000010000 0.1886490000 0.0019280000 115392635 0 402718720 3.1255562305 3.9250266552 5.5652141571 675 26.9600000000 0.4733431339 0.1444012332 0.8156625032 0.0604386923 0.4269460000 0.1071700000 0.0897000000 0.0384000000 0.1884930000 0.0019720000 115395411 0 402718720 3.1240873337 3.9201889038 5.5539612770 676 27.0000000000 0.4751250446 0.1448904696 0.8156625032 0.0603958999 0.4273410000 0.1110750000 0.1209350000 0.0000010000 0.1921040000 0.0020220000 115398187 0 402718720 3.1204729080 3.9162404537 5.5413365364 677 27.0400000000 0.4769740701 0.1453809919 0.8156625032 0.0603525788 0.6585320000 0.1110820000 0.0952280000 0.0386950000 0.1943580000 0.2180070000 115400963 0 402718720 3.1168284416 3.9124541283 5.5295414925 678 27.0800000000 0.4783158302 0.1458720462 0.8156625032 0.0603094140 0.4268120000 0.1111210000 0.1139370000 0.0000000000 0.1986630000 0.0019160000 115403739 0 402718720 3.1138527393 3.9098663330 5.5192332268 679 27.1200000000 0.4798993766 0.1463639863 0.8156625032 0.0602662533 0.4782990000 0.1237760000 0.1135680000 0.0385870000 0.1992660000 0.0019220000 115406515 0 402718720 3.1110000610 3.9062132835 5.5088634491 680 27.1600000000 0.4811096191 0.1468562593 0.8156625032 0.0602228683 0.4449770000 0.1210690000 0.1195460000 0.0000010000 0.2012930000 0.0019170000 115409291 0 402718720 3.1082363129 3.9036102295 5.4997658730 681 27.2000000000 0.4825945795 0.1473492671 0.8156625032 0.0601797327 0.6671440000 0.1111040000 0.0848180000 0.0389840000 0.2026800000 0.2283980000 115412067 0 402718720 3.1053218842 3.9007596970 5.4897637367 682 27.2400000000 0.4840343297 0.1478429402 0.8156625032 0.0601366193 0.3768300000 0.1071910000 0.0568150000 0.0000000000 0.2097540000 0.0019130000 115414843 0 402718720 3.1014719009 3.8980443478 5.4783205986 683 27.2800000000 0.4859000742 0.1483378994 0.8156625032 0.0600928320 0.4748650000 0.1111550000 0.1189470000 0.0390240000 0.2025080000 0.0020180000 115417619 0 402718720 3.0963649750 3.8950679302 5.4668903351 684 27.3200000000 0.4872044027 0.1488333183 0.8156625032 0.0600498741 0.4341180000 0.1071960000 0.1176890000 0.0000000000 0.2060490000 0.0019590000 115420395 0 402718720 3.0954766273 3.8910114765 5.4580864906 685 27.3600000000 0.4885539114 0.1493292608 0.8156625032 0.0600071043 0.7133590000 0.1202510000 0.1127540000 0.0390390000 0.2067060000 0.2334330000 115423171 0 402718720 3.0952670574 3.8885779381 5.4488716125 686 27.4000000000 0.4900171757 0.1498258904 0.8156625032 0.0599653355 0.4632600000 0.1338990000 0.1191220000 0.0000010000 0.2071670000 0.0019010000 115425947 0 402718720 3.0893456936 3.8850574493 5.4358205795 687 27.4400000000 0.4920742512 0.1503240685 0.8156625032 0.0599222207 0.4778160000 0.1111430000 0.1186090000 0.0390580000 0.2059340000 0.0018940000 115428723 0 402718720 3.0854926109 3.8804674149 5.4254689217 688 27.4800000000 0.4934946299 0.1508228629 0.8156625032 0.0598791022 0.4349100000 0.1111760000 0.1126340000 0.0000010000 0.2080400000 0.0018850000 115431499 0 402718720 3.0831058025 3.8782017231 5.4163126945 689 27.5200000000 0.4953948557 0.1513229674 0.8156625032 0.0598357858 0.7099040000 0.1111250000 0.1188060000 0.0390580000 0.2057660000 0.2339790000 115434275 0 402718720 3.0777287483 3.8746035099 5.4035792351 690 27.5600000000 0.4965617657 0.1518233135 0.8156625032 0.0597928922 0.4344240000 0.1111180000 0.1117620000 0.0000010000 0.2085050000 0.0018690000 115437051 0 402718720 3.0769431591 3.8721003532 5.3932108879 691 27.6000000000 0.4978895485 0.1523241329 0.8156625032 0.0597497362 0.4197200000 0.1111840000 0.0588890000 0.0390880000 0.2073490000 0.0019680000 115439827 0 402718720 3.0749673843 3.8689055443 5.3827972412 692 27.6400000000 0.4999584854 0.1528264947 0.8156625032 0.0597065841 0.4396150000 0.1111970000 0.1162470000 0.0000000000 0.2091480000 0.0018440000 115442603 0 402718720 3.0727198124 3.8641164303 5.3713393211 693 27.6800000000 0.5013679862 0.1533294406 0.8156625032 0.0596635028 0.6952270000 0.1111690000 0.1008720000 0.0386360000 0.2081280000 0.2352360000 115445379 0 402718720 3.0702881813 3.8608980179 5.3593544960 694 27.7200000000 0.5030958056 0.1538334267 0.8156625032 0.0596206063 0.4144890000 0.1111510000 0.0912480000 0.0000000000 0.2090760000 0.0018320000 115448155 0 402718720 3.0685985088 3.8566238880 5.3479814529 695 27.7600000000 0.5053542852 0.1543392121 0.8156625032 0.0595782877 0.4642820000 0.1204700000 0.0954740000 0.0389890000 0.2061700000 0.0019160000 115450931 0 402718720 3.0661585331 3.8506319523 5.3365154266 696 27.8000000000 0.5071465969 0.1548461193 0.8156625032 0.0595356463 0.4351480000 0.1111180000 0.1139830000 0.0000000000 0.2070640000 0.0018030000 115453707 0 402718720 3.0638642311 3.8462171555 5.3243165016 697 27.8400000000 0.5116868615 0.1553580859 0.8156625032 0.0594948737 0.6988730000 0.1110190000 0.1101410000 0.0387520000 0.2054480000 0.2323280000 115456483 0 402718720 3.0593583584 3.8334836960 5.3002691269 698 27.8800000000 0.5137171745 0.1558714943 0.8156625032 0.0594522741 0.3985030000 0.1107270000 0.0796840000 0.0000010000 0.2051160000 0.0017800000 115459259 0 402718720 3.0592930317 3.8280003071 5.2907204628 699 27.9200000000 0.5155934095 0.1563861180 0.8156625032 0.0594130721 0.4591470000 0.1070160000 0.1070950000 0.0381310000 0.2039730000 0.0017240000 115462035 0 402718720 3.0564072132 3.8264086246 5.2760753632 700 27.9600000000 0.5175928473 0.1569021276 0.8156625032 0.0593708639 0.3972090000 0.1108690000 0.0809930000 0.0000000000 0.2023880000 0.0017720000 115464811 0 402718720 3.0554599762 3.8238584995 5.2611966133 701 28.0000000000 0.5194481015 0.1574193116 0.8156625032 0.0593296771 0.6565340000 0.1108920000 0.0714460000 0.0379680000 0.2043040000 0.2307310000 115467587 0 402718720 3.0571799278 3.8201889992 5.2496771812 702 28.0400000000 0.5210117698 0.1579372495 0.8156625032 0.0592875382 0.4256100000 0.1108580000 0.1073680000 0.0000010000 0.2044090000 0.0017790000 115470363 0 402718720 3.0570068359 3.8181083202 5.2366638184 703 28.0800000000 0.5235691667 0.1584573518 0.8156625032 0.0592455822 0.4275510000 0.1108880000 0.0718470000 0.0382710000 0.2035510000 0.0017800000 115473139 0 402718720 3.0536623001 3.8128323555 5.2225241661 704 28.1200000000 0.5258301497 0.1589791882 0.8156625032 0.0592053994 0.3801170000 0.1108750000 0.0624670000 0.0000010000 0.2037920000 0.0017740000 115475915 0 402718720 3.0541851521 3.8067510128 5.2107939720 705 28.1600000000 0.5283147097 0.1595030684 0.8156625032 0.0591636275 0.6803470000 0.1187230000 0.0892040000 0.0381690000 0.2037850000 0.2292560000 115478691 0 402718720 3.0538704395 3.7999193668 5.1982798576 706 28.2000000000 0.5310134292 0.1600292870 0.8156625032 0.0591217006 0.4199950000 0.1069530000 0.1061900000 0.0000000000 0.2038730000 0.0017740000 115481467 0 402718720 3.0532009602 3.7927596569 5.1860108376 707 28.2400000000 0.5331506133 0.1605570399 0.8156625032 0.0590808168 0.4588370000 0.1069900000 0.1073670000 0.0376780000 0.2038550000 0.0017300000 115484243 0 402718720 3.0531749725 3.7896378040 5.1717677116 708 28.2800000000 0.5348122120 0.1610856489 0.8156625032 0.0590395432 0.4267850000 0.1109270000 0.1087350000 0.0000010000 0.2041410000 0.0017700000 115487019 0 402718720 3.0500233173 3.7880108356 5.1560010910 709 28.3200000000 0.5374046564 0.1616164233 0.8156625032 0.0590000162 0.6719300000 0.1100080000 0.0893800000 0.0380440000 0.2041980000 0.2290760000 115489795 0 402718720 3.0495500565 3.7819132805 5.1432008743 710 28.3600000000 0.5393281579 0.1621484116 0.8156625032 0.0589588604 0.4222700000 0.1110210000 0.0994710000 0.0000010000 0.2087910000 0.0017760000 115492571 0 402718720 3.0524170399 3.7783806324 5.1337800026 711 28.4000000000 0.5412191749 0.1626815632 0.8156625032 0.0589174578 0.4647310000 0.1110300000 0.1076370000 0.0379750000 0.2050940000 0.0017790000 115495347 0 402718720 3.0510778427 3.7747118473 5.1214199066 712 28.4400000000 0.5430634618 0.1632158075 0.8156625032 0.0588761586 0.4222750000 0.1070750000 0.1058060000 0.0000010000 0.2063980000 0.0017740000 115498123 0 402718720 3.0507745743 3.7701194286 5.1104807854 713 28.4800000000 0.5452312231 0.1637515934 0.8156625032 0.0588348287 0.6903280000 0.1110850000 0.1063090000 0.0378760000 0.2048360000 0.2290020000 115500899 0 402718720 3.0524852276 3.7646543980 5.1013312340 714 28.5200000000 0.5469337702 0.1642882632 0.8156625032 0.0587949334 0.4268260000 0.1110600000 0.1071020000 0.0000010000 0.2056810000 0.0017780000 115503675 0 402718720 3.0516469479 3.7617449760 5.0901994705 715 28.5600000000 0.5489026308 0.1648261854 0.8156625032 0.0587550371 0.4426140000 0.1234430000 0.0726070000 0.0377850000 0.2057610000 0.0017810000 115506451 0 402718720 3.0497655869 3.7604439259 5.0750894547 716 28.6000000000 0.5506610870 0.1653650609 0.8156625032 0.0587142817 0.4288730000 0.1110960000 0.1070840000 0.0000010000 0.2077000000 0.0017740000 115509227 0 402718720 3.0495650768 3.7573592663 5.0625987053 717 28.6400000000 0.5523532033 0.1659047933 0.8156625032 0.0586749002 0.6804920000 0.1111700000 0.0887990000 0.0378370000 0.2084440000 0.2330110000 115512003 0 402718720 3.0510065556 3.7517385483 5.0552735329 718 28.6800000000 0.5538528562 0.1664451110 0.8156625032 0.0586346088 0.4310290000 0.1112010000 0.1066930000 0.0000000000 0.2101190000 0.0017830000 115514779 0 402718720 3.0503287315 3.7489538193 5.0468029976 719 28.7200000000 0.5558157563 0.1669866557 0.8156625032 0.0585943284 0.4548830000 0.1113020000 0.0945030000 0.0378040000 0.2081090000 0.0018670000 115517555 0 402718720 3.0474197865 3.7454283237 5.0344676971 720 28.7600000000 0.5578875542 0.1675295736 0.8156625032 0.0585538768 0.4320100000 0.1112630000 0.1063110000 0.0000010000 0.2114420000 0.0017720000 115520331 0 402718720 3.0456953049 3.7418076992 5.0237965584 721 28.8000000000 0.5589747429 0.1680724934 0.8156625032 0.0585139567 0.7282430000 0.1278030000 0.1132420000 0.0378000000 0.2108710000 0.2372930000 115523107 0 402718720 3.0465714931 3.7411546707 5.0127115250 722 28.8400000000 0.5608369708 0.1686164885 0.8156625032 0.0584747525 0.4322240000 0.1072940000 0.1076740000 0.0000000000 0.2142620000 0.0017630000 115525883 0 402718720 3.0407421589 3.7401988506 4.9998383522 723 28.8800000000 0.5625946522 0.1691614099 0.8156625032 0.0584350378 0.4403750000 0.1073140000 0.0785700000 0.0373830000 0.2141660000 0.0017050000 115528659 0 402718720 3.0349416733 3.7375612259 4.9887576103 724 28.9200000000 0.5638838410 0.1697066066 0.8156625032 0.0583952170 0.4327240000 0.1102460000 0.1035780000 0.0000010000 0.2159060000 0.0017540000 115531435 0 402718720 3.0318846703 3.7359294891 4.9796857834 725 28.9600000000 0.5653831959 0.1702523674 0.8156625032 0.0583551569 0.6714180000 0.1227880000 0.0561220000 0.0378470000 0.2133500000 0.2400670000 115534211 0 402718720 3.0271222591 3.7342431545 4.9678897858 726 29.0000000000 0.5672565103 0.1707992051 0.8156625032 0.0583164619 0.4130930000 0.1113040000 0.0817470000 0.0000010000 0.2170630000 0.0017370000 115536987 0 402718720 3.0243582726 3.7297141552 4.9549717903 727 29.0400000000 0.5710058212 0.1713496956 0.8156625032 0.0582776109 0.4798400000 0.1112800000 0.1047230000 0.0377680000 0.2230980000 0.0017260000 115539763 0 402718720 3.0139038563 3.7238712311 4.9356670380 728 29.0800000000 0.5739881396 0.1719027704 0.8156625032 0.0582387815 0.4548780000 0.1112460000 0.1031850000 0.0000010000 0.2375070000 0.0017040000 115542539 0 402718720 3.0030722618 3.7194278240 4.9219880104 729 29.1200000000 0.5755128264 0.1724564193 0.8156625032 0.0582079697 0.7589670000 0.1112840000 0.1014090000 0.0377100000 0.2410200000 0.2662990000 115545315 0 402718720 2.9997675419 3.7127196789 4.9156179428 730 29.1600000000 0.5769850016 0.1730105681 0.8156625032 0.0581684792 0.4598720000 0.1112930000 0.1022700000 0.0000000000 0.2433620000 0.0016920000 115548091 0 402718720 2.9969422817 3.7104954720 4.9067444801 731 29.2000000000 0.5789663196 0.1735659111 0.8156625032 0.0581287472 0.5039070000 0.1112860000 0.1028350000 0.0371310000 0.2497130000 0.0016810000 115550867 0 402718720 2.9883708954 3.7099447250 4.8922352791 732 29.2400000000 0.5805498362 0.1741219001 0.8156625032 0.0580910982 0.4859350000 0.1285020000 0.1008030000 0.0000010000 0.2536710000 0.0016960000 115553643 0 402718720 2.9826712608 3.7086725235 4.8810234070 733 29.2800000000 0.5819086432 0.1746782258 0.8156625032 0.0580522737 0.7921020000 0.1073010000 0.1058450000 0.0372370000 0.2562490000 0.2842100000 115556419 0 402718720 2.9791390896 3.7089798450 4.8703780174 734 29.3200000000 0.5827000141 0.1752341138 0.8156625032 0.0580128492 0.4780020000 0.1112570000 0.1011550000 0.0000010000 0.2626810000 0.0016600000 115559195 0 402718720 2.9710514545 3.7108979225 4.8567461967 735 29.3600000000 0.5847044587 0.1757912163 0.8156625032 0.0579814211 0.5378170000 0.1267050000 0.1034540000 0.0375130000 0.2672170000 0.0016520000 115561971 0 402718720 2.9658493996 3.7067575455 4.8478178978 736 29.4000000000 0.5862366557 0.1763488867 0.8156625032 0.0579442974 0.4848340000 0.1073270000 0.1029770000 0.0000000000 0.2716180000 0.0016450000 115564747 0 402718720 2.9631721973 3.7055613995 4.8398079872 737 29.4400000000 0.5870044231 0.1769060855 0.8156625032 0.0579049524 0.8188790000 0.1112200000 0.0751070000 0.0374390000 0.2847250000 0.3091340000 115567523 0 402718720 2.9579119682 3.7081568241 4.8262524605 738 29.4800000000 0.5885850191 0.1774639161 0.8156625032 0.0578707376 0.5000200000 0.1072900000 0.0962730000 0.0000010000 0.2935550000 0.0016330000 115570299 0 402718720 2.9529638290 3.7068116665 4.8155393600 739 29.5200000000 0.5896372795 0.1780216608 0.8156625032 0.0578373317 0.5391710000 0.1112050000 0.0949640000 0.0368780000 0.2932200000 0.0016290000 115573075 0 402718720 2.9524216652 3.7039422989 4.8104839325 740 29.5600000000 0.5911468863 0.1785799381 0.8156625032 0.0577986908 0.5125690000 0.1090360000 0.0959830000 0.0000000000 0.3046510000 0.0016260000 115575851 0 402718720 2.9500656128 3.7015395164 4.8018884659 741 29.6000000000 0.5923182964 0.1791382895 0.8156625032 0.0577598395 0.8736180000 0.1111820000 0.0727610000 0.0373360000 0.3120780000 0.3389910000 115578627 0 402718720 2.9476246834 3.6999685764 4.7908711433 742 29.6400000000 0.5946741104 0.1796983108 0.8156625032 0.0577211553 0.5273440000 0.1112050000 0.0958110000 0.0000010000 0.3174320000 0.0016250000 115581403 0 402718720 2.9455287457 3.6981418133 4.7811627388 743 29.6800000000 0.5956218839 0.1802581003 0.8156625032 0.0576826834 0.5343170000 0.1112100000 0.0490670000 0.0373980000 0.3337460000 0.0016250000 115584179 0 402718720 2.9418270588 3.6982502937 4.7717499733 744 29.7200000000 0.5968730450 0.1808180666 0.8156625032 0.0576444992 0.5467930000 0.1111890000 0.0956100000 0.0000010000 0.3371260000 0.0016090000 115586955 0 402718720 2.9358341694 3.6982469559 4.7626776695 745 29.7600000000 0.5974518657 0.1813773066 0.8156625032 0.0576088813 0.9287730000 0.1111810000 0.0749850000 0.0374200000 0.3336610000 0.3702560000 115589731 0 402718720 2.9325366020 3.6977488995 4.7568111420 746 29.8000000000 0.5987129807 0.1819367378 0.8156625032 0.0575723777 0.5431350000 0.1111290000 0.0944150000 0.0000010000 0.3346990000 0.0016000000 115592507 0 402718720 2.9277727604 3.6968929768 4.7485442162 747 29.8400000000 0.5988690853 0.1824948802 0.8156625032 0.0575404518 0.5848740000 0.1112400000 0.0982600000 0.0373990000 0.3350620000 0.0016120000 115595283 0 402718720 2.9322776794 3.6951744556 4.7433280945 748 29.8800000000 0.5995631218 0.1830524580 0.8156625032 0.0575028848 0.4957100000 0.1112570000 0.0472580000 0.0000010000 0.3342990000 0.0016190000 115598059 0 402718720 2.9343690872 3.6914947033 4.7408390045 749 29.9200000000 0.6013980508 0.1836109969 0.8156625032 0.0574653158 0.9475650000 0.1112440000 0.0941650000 0.0373430000 0.3342230000 0.3693010000 115600835 0 402718720 2.9304497242 3.6895372868 4.7332949638 750 29.9600000000 0.6019121408 0.1841687317 0.8156625032 0.0574271309 0.5833280000 0.1484440000 0.1010880000 0.0000000000 0.3307630000 0.0017000000 115603611 0 402718720 2.9270446301 3.6906390190 4.7223095894 751 30.0000000000 0.6035897136 0.1847272151 0.8156625032 0.0573911240 0.5797800000 0.1112300000 0.0924590000 0.0374030000 0.3358050000 0.0015790000 115606387 0 402718720 2.9255480766 3.6875445843 4.7180109024 752 30.0400000000 0.6040758491 0.1852848595 0.8156625032 0.0573535690 0.5485620000 0.1112400000 0.0973990000 0.0000000000 0.3370220000 0.0016080000 115609163 0 402718720 2.9230132103 3.6859054565 4.7144150734 753 30.0800000000 0.6051978469 0.1858425129 0.8156625032 0.0573154924 0.9626120000 0.1112550000 0.0947630000 0.0374330000 0.3394940000 0.3783630000 115611939 0 402718720 2.9184603691 3.6871316433 4.7042336464 754 30.1200000000 0.6062012315 0.1864000178 0.8156625032 0.0572820252 0.5241030000 0.1112330000 0.0695640000 0.0000010000 0.3403860000 0.0016050000 115614715 0 402718720 2.9194781780 3.6832814217 4.7000403404 755 30.1600000000 0.6066709161 0.1869566680 0.8156625032 0.0572452821 0.5605230000 0.1199080000 0.0636030000 0.0375210000 0.3365730000 0.0016110000 115617491 0 402718720 2.9237177372 3.6803178787 4.6986126900 756 30.2000000000 0.6082043052 0.1875138739 0.8156625032 0.0572076286 0.5456270000 0.1113180000 0.0934140000 0.0000010000 0.3379900000 0.0016030000 115620267 0 402718720 2.9215834141 3.6782319546 4.6915025711 757 30.2400000000 0.6093285084 0.1880710927 0.8156625032 0.0571701497 0.9280790000 0.1241620000 0.0476110000 0.0374940000 0.3389990000 0.3785110000 115623043 0 402718720 2.9194259644 3.6760261059 4.6849741936 758 30.2800000000 0.6100072265 0.1886277367 0.8156625032 0.0571325959 0.5488600000 0.1113140000 0.0930720000 0.0000010000 0.3415670000 0.0016060000 115625819 0 402718720 2.9169321060 3.6752488613 4.6781349182 759 30.3200000000 0.6109078526 0.1891841005 0.8156625032 0.0570950175 0.5715810000 0.1331010000 0.0591790000 0.0375090000 0.3387140000 0.0016990000 115628595 0 402718720 2.9155812263 3.6761589050 4.6676092148 760 30.3600000000 0.6124163270 0.1897409850 0.8156625032 0.0570610286 0.5480670000 0.1113900000 0.0922280000 0.0000010000 0.3415220000 0.0016140000 115631371 0 402718720 2.9189684391 3.6719362736 4.6628746986 761 30.4000000000 0.6134648919 0.1902977838 0.8156625032 0.0570243563 0.9629340000 0.1114960000 0.0922880000 0.0374810000 0.3401320000 0.3802260000 115634147 0 402718720 2.9193084240 3.6694831848 4.6585798264 762 30.4400000000 0.6147283912 0.1908547793 0.8156625032 0.0569872070 0.5281420000 0.1114320000 0.0703610000 0.0000010000 0.3434280000 0.0016130000 115636923 0 402718720 2.9160621166 3.6677918434 4.6510896683 763 30.4800000000 0.6154949665 0.1914113196 0.8156625032 0.0569518634 0.5876800000 0.1114650000 0.0927580000 0.0376590000 0.3428540000 0.0016180000 115639699 0 402718720 2.9155924320 3.6644299030 4.6437726021 764 30.5200000000 0.6167853475 0.1919680919 0.8156625032 0.0569147551 0.5511900000 0.1114580000 0.0936540000 0.0000010000 0.3431420000 0.0016130000 115642475 0 402718720 2.9166505337 3.6638574600 4.6367740631 765 30.5600000000 0.6182262897 0.1925252921 0.8156625032 0.0568781757 0.9801220000 0.1227640000 0.0933220000 0.0374640000 0.3420500000 0.3831960000 115645251 0 402718720 2.9172592163 3.6610257626 4.6283831596 766 30.6000000000 0.6195945144 0.1930828237 0.8156625032 0.0568428293 0.5476490000 0.1115710000 0.0926880000 0.0000010000 0.3404980000 0.0015860000 115648027 0 402718720 2.9221665859 3.6548488140 4.6260771751 767 30.6400000000 0.6208664775 0.1936405599 0.8156625032 0.0568058727 0.5850340000 0.1116360000 0.0943330000 0.0375140000 0.3385910000 0.0016250000 115650803 0 402718720 2.9220952988 3.6532006264 4.6159458160 768 30.6800000000 0.6236522794 0.1942004710 0.8156625032 0.0567695409 0.5441840000 0.1086300000 0.0940220000 0.0000000000 0.3384510000 0.0017540000 115653579 0 402718720 2.9226713181 3.6490223408 4.6077523232 769 30.7200000000 0.6243777275 0.1947598693 0.8156625032 0.0567347995 0.9271810000 0.1117220000 0.0704360000 0.0369940000 0.3337810000 0.3729130000 115656355 0 402718720 2.9288470745 3.6429286003 4.6067786217 770 30.7600000000 0.6258330941 0.1953197046 0.8156625032 0.0566987676 0.5551380000 0.1248830000 0.0946430000 0.0000000000 0.3326430000 0.0016340000 115659131 0 402718720 2.9299688339 3.6408867836 4.5994553566 771 30.8000000000 0.6285238862 0.1958815778 0.8156625032 0.0566620789 0.5777600000 0.1118110000 0.0945330000 0.0374640000 0.3309730000 0.0016360000 115661907 0 402718720 2.9302389622 3.6362495422 4.5907711983 772 30.8400000000 0.6297916770 0.1964436375 0.8156625032 0.0566255510 0.5322040000 0.1078940000 0.0935690000 0.0000000000 0.3277650000 0.0016490000 115664683 0 402718720 2.9365384579 3.6309778690 4.5860276222 773 30.8800000000 0.6312538981 0.1970061346 0.8156625032 0.0565901021 0.9254730000 0.1119230000 0.0953140000 0.0375560000 0.3210720000 0.3582790000 115667459 0 402718720 2.9422771931 3.6276326180 4.5801506042 774 30.9200000000 0.6328639388 0.1975692583 0.8156625032 0.0565570532 0.4871630000 0.1119570000 0.0493820000 0.0000010000 0.3228390000 0.0016570000 115670235 0 402718720 2.9407255650 3.6264135838 4.5708351135 775 30.9600000000 0.6341126561 0.1981325402 0.8156625032 0.0565215856 0.5835320000 0.1208150000 0.0999380000 0.0375930000 0.3221760000 0.0016590000 115673011 0 402718720 2.9388782978 3.6245350838 4.5631136894 776 31.0000000000 0.6354584694 0.1986961045 0.8156625032 0.0564857214 0.4872010000 0.1119620000 0.0516450000 0.0000010000 0.3205910000 0.0016590000 115675787 0 402718720 2.9375288486 3.6226294041 4.5564813614 777 31.0400000000 0.6361759901 0.1992591417 0.8156625032 0.0564496766 0.9245330000 0.1119970000 0.0963080000 0.0376270000 0.3195490000 0.3577030000 115678563 0 402718720 2.9415891171 3.6208114624 4.5503196716 778 31.0800000000 0.6381194592 0.1998232295 0.8156625032 0.0564140625 0.4763740000 0.1119750000 0.0412150000 0.0000000000 0.3201740000 0.0016620000 115681339 0 402718720 2.9408390522 3.6184020042 4.5431418419 779 31.1200000000 0.6385735273 0.2003864519 0.8156625032 0.0563798772 0.5558960000 0.1232880000 0.0737870000 0.0378620000 0.3179180000 0.0016710000 115684115 0 402718720 2.9412589073 3.6202268600 4.5343313217 780 31.1600000000 0.6401044130 0.2009501929 0.8156625032 0.0563451119 0.5073900000 0.1119380000 0.0742400000 0.0000000000 0.3181940000 0.0016770000 115686891 0 402718720 2.9414682388 3.6229169369 4.5243539810 781 31.2000000000 0.6404411197 0.2015129214 0.8156625032 0.0563091615 0.9094040000 0.1119830000 0.0972270000 0.0377440000 0.3114270000 0.3496750000 115689667 0 402718720 2.9463076591 3.6224858761 4.5161685944 782 31.2400000000 0.6424387097 0.2020767651 0.8156625032 0.0562732481 0.5197000000 0.1120220000 0.0974200000 0.0000010000 0.3072040000 0.0017070000 115692443 0 402718720 2.9509055614 3.6189305782 4.5105814934 783 31.2800000000 0.6429704428 0.2026398477 0.8156625032 0.0562377856 0.5059470000 0.1120100000 0.0497370000 0.0377000000 0.3034000000 0.0017220000 115695219 0 402718720 2.9551784992 3.6179254055 4.5060853958 784 31.3200000000 0.6447944641 0.2032038204 0.8156625032 0.0562022046 0.4988350000 0.1119580000 0.0830070000 0.0000010000 0.3007880000 0.0017270000 115697995 0 402718720 2.9562444687 3.6156034470 4.4974203110 785 31.3600000000 0.6457911134 0.2037676259 0.8156625032 0.0561670264 0.8545950000 0.1216780000 0.0612650000 0.0380430000 0.2973410000 0.3349000000 115700771 0 402718720 2.9548783302 3.6128790379 4.4921436310 786 31.4000000000 0.6468419433 0.2043313337 0.8156625032 0.0561324297 0.5148400000 0.1119690000 0.1017010000 0.0000000000 0.2980640000 0.0017430000 115703547 0 402718720 2.9587876797 3.6075479984 4.4892439842 787 31.4400000000 0.6476011872 0.2048945736 0.8156625032 0.0560971256 0.5478590000 0.1121110000 0.0994490000 0.0379280000 0.2952440000 0.0017560000 115706323 0 402718720 2.9619181156 3.6042346954 4.4861807823 788 31.4800000000 0.6485544443 0.2054575938 0.8156625032 0.0560619002 0.5138070000 0.1121600000 0.1005970000 0.0000010000 0.2979330000 0.0017580000 115709099 0 402718720 2.9645814896 3.6027314663 4.4811301231 789 31.5200000000 0.6492604017 0.2060200815 0.8156625032 0.0560267864 0.8879150000 0.1118630000 0.1008570000 0.0380130000 0.2984790000 0.3373380000 115711875 0 402718720 2.9660682678 3.6016292572 4.4747529030 790 31.5600000000 0.6504628062 0.2065826672 0.8156625032 0.0559916712 0.4781030000 0.1121790000 0.0592960000 0.0000010000 0.3034830000 0.0017720000 115714651 0 402718720 2.9677605629 3.5999867916 4.4718031883 791 31.6000000000 0.6512598991 0.2071448382 0.8156625032 0.0559570072 0.5712810000 0.1397780000 0.0894570000 0.0381930000 0.3006890000 0.0017830000 115717427 0 402718720 2.9667706490 3.6003866196 4.4641103745 792 31.6400000000 0.6521382332 0.2077066985 0.8156625032 0.0559221737 0.5229060000 0.1122290000 0.1006320000 0.0000010000 0.3069150000 0.0017780000 115720203 0 402718720 2.9662368298 3.5968301296 4.4595732689 793 31.6800000000 0.6534365416 0.2082687790 0.8156625032 0.0558870573 0.9505610000 0.1313970000 0.0997530000 0.0505790000 0.3180320000 0.3494160000 115722979 0 402718720 2.9690835476 3.5929136276 4.4597377777 794 31.7200000000 0.6539811492 0.2088301296 0.8156625032 0.0558526140 0.5304280000 0.1122490000 0.1076630000 0.0000010000 0.3073050000 0.0018380000 115725755 0 402718720 2.9671790600 3.5927610397 4.4510941505 795 31.7600000000 0.6549414992 0.2093912760 0.8156625032 0.0558177330 0.5346320000 0.1308040000 0.0541240000 0.0383000000 0.3080640000 0.0018780000 115728531 0 402718720 2.9658083916 3.5908739567 4.4461960793 796 31.8000000000 0.6552343965 0.2099513804 0.8156625032 0.0557828623 0.5306610000 0.1118740000 0.1012020000 0.0000010000 0.3144360000 0.0017770000 115731307 0 402718720 2.9687018394 3.5885317326 4.4438982010 797 31.8400000000 0.6560164690 0.2105110606 0.8156625032 0.0557479640 0.9283220000 0.1122780000 0.1014650000 0.0383300000 0.3159490000 0.3589280000 115734083 0 402718720 2.9707157612 3.5872483253 4.4395346642 798 31.8800000000 0.6572654843 0.2110709032 0.8156625032 0.0557130826 0.5587600000 0.1328470000 0.1068260000 0.0000000000 0.3159130000 0.0017810000 115736859 0 402718720 2.9698371887 3.5837507248 4.4370961189 799 31.9200000000 0.6576849818 0.2116298695 0.8156625032 0.0556802825 0.5539880000 0.1123350000 0.0822340000 0.0380000000 0.3182540000 0.0017810000 115739635 0 402718720 2.9671583176 3.5875313282 4.4268703461 800 31.9600000000 0.6592589617 0.2121894059 0.8156625032 0.0556473747 0.5169830000 0.1250450000 0.0681130000 0.0000010000 0.3206640000 0.0017760000 115742411 0 402718720 2.9648671150 3.5813698769 4.4230690002 801 32.0000000000 0.6602581143 0.2127487926 0.8156625032 0.0556156204 0.9084990000 0.1083680000 0.0689670000 0.0385470000 0.3233980000 0.3678300000 115745187 0 402718720 2.9710178375 3.5712897778 4.4291667938 802 32.0400000000 0.6611866951 0.2133079421 0.8156625032 0.0555836281 0.5169580000 0.1123270000 0.0765900000 0.0000010000 0.3248540000 0.0017820000 115747963 0 402718720 2.9706501961 3.5694289207 4.4247484207 803 32.0800000000 0.6625525355 0.2138673998 0.8156625032 0.0555507569 0.5558950000 0.1291540000 0.0637620000 0.0385010000 0.3211050000 0.0018740000 115750739 0 402718720 2.9694032669 3.5688197613 4.4169955254 804 32.1199999990 0.6630947590 0.2144261403 0.8156625032 0.0555164319 0.5188240000 0.1281880000 0.0607500000 0.0000020000 0.3267250000 0.0017720000 115753515 0 402718720 2.9694406986 3.5653796196 4.4147005081 805 32.1600000000 0.6645685434 0.2149853234 0.8156625032 0.0554823381 0.9578110000 0.1124660000 0.1071670000 0.0385710000 0.3261990000 0.3720170000 115756291 0 402718720 2.9686284065 3.5603702068 4.4111824036 806 32.2000000000 0.6673654914 0.2155465892 0.8156625032 0.0554540999 0.5143480000 0.1084410000 0.0688060000 0.0000010000 0.3339800000 0.0017210000 115759067 0 402718720 2.9733269215 3.5596559048 4.3936395645 807 32.2400000000 0.6679536700 0.2161071927 0.8156625032 0.0554215750 0.5953440000 0.1124870000 0.1074270000 0.0385960000 0.3336510000 0.0017720000 115761843 0 402718720 2.9732503891 3.5600855350 4.3875336647 808 32.2800000000 0.6693198681 0.2166680995 0.8156625032 0.0553906013 0.5520870000 0.1085390000 0.1020500000 0.0000010000 0.3383420000 0.0017710000 115764619 0 402718720 2.9716734886 3.5634303093 4.3769659996 809 32.3200000000 0.6706265211 0.2172292348 0.8156625032 0.0553574065 0.9811690000 0.1126120000 0.1013660000 0.0386160000 0.3389700000 0.3882110000 115767395 0 402718720 2.9666805267 3.5610210896 4.3693432808 810 32.3600000000 0.6716545820 0.2177902537 0.8156625032 0.0553251160 0.5208190000 0.1126560000 0.0596550000 0.0000010000 0.3453250000 0.0017710000 115770171 0 402718720 2.9659357071 3.5566051006 4.3670487404 811 32.4000000000 0.6735602021 0.2183522388 0.8156625032 0.0552927194 0.5721840000 0.1256300000 0.0596160000 0.0390560000 0.3446780000 0.0017730000 115772947 0 402718720 2.9625561237 3.5489192009 4.3623695374 812 32.4399999990 0.6746084690 0.2189141308 0.8156625032 0.0552603878 0.5363480000 0.1127750000 0.0685910000 0.0000000000 0.3517900000 0.0017790000 115775723 0 402718720 2.9657354355 3.5414192677 4.3640770912 813 32.4800000000 0.6754323840 0.2194756538 0.8156625032 0.0552373232 1.0186950000 0.1344130000 0.0999940000 0.0389910000 0.3454290000 0.3984560000 115778499 0 402718720 2.9650762081 3.5490286350 4.3492736816 814 32.5200000000 0.6776570678 0.2200385303 0.8156625032 0.0552073473 0.5390640000 0.1127380000 0.0698260000 0.0000010000 0.3532670000 0.0018070000 115781275 0 402718720 2.9586157799 3.5551500320 4.3299674988 815 32.5600000000 0.6785348654 0.2206011024 0.8156625032 0.0551808016 0.5751390000 0.1126720000 0.0681840000 0.0386070000 0.3524560000 0.0017840000 115784051 0 402718720 2.9566113949 3.5464646816 4.3302683830 816 32.6000000000 0.6799498200 0.2211640298 0.8156625032 0.0551477993 0.5757670000 0.1126450000 0.1018570000 0.0000010000 0.3580580000 0.0017820000 115786827 0 402718720 2.9555258751 3.5417463779 4.3265047073 817 32.6400000000 0.6812082529 0.2217271194 0.8156625032 0.0551151560 0.9750510000 0.1126630000 0.0599980000 0.0390790000 0.3556850000 0.4062240000 115789603 0 402718720 2.9519910812 3.5402975082 4.3184461594 818 32.6800000000 0.6831399798 0.2222911938 0.8156625032 0.0550820577 0.5780110000 0.1125660000 0.1021380000 0.0000010000 0.3601020000 0.0017880000 115792379 0 402718720 2.9471395016 3.5355618000 4.3110866547 819 32.7200000000 0.6849040389 0.2228560447 0.8156625032 0.0550496896 0.5812270000 0.1126170000 0.0685150000 0.0392640000 0.3576070000 0.0017960000 115795155 0 402718720 2.9450767040 3.5279424191 4.3081879616 820 32.7599999990 0.6859624386 0.2234208086 0.8156625032 0.0550166993 0.5375080000 0.1126010000 0.0604160000 0.0000000000 0.3612820000 0.0017930000 115797931 0 402718720 2.9454052448 3.5272367001 4.3016710281 821 32.7999999990 0.6875709891 0.2239861559 0.8156625032 0.0549838474 0.9836220000 0.1126480000 0.0604810000 0.0387180000 0.3598320000 0.4105180000 115800707 0 402718720 2.9419434071 3.5260958672 4.2928748131 822 32.8400000000 0.6888819337 0.2245517226 0.8156625032 0.0549507953 0.5743140000 0.1308580000 0.0772440000 0.0000010000 0.3629810000 0.0018050000 115803483 0 402718720 2.9390516281 3.5228755474 4.2866077423 823 32.8800000000 0.6901116371 0.2251174090 0.8156625032 0.0549180946 0.6127310000 0.1312560000 0.0771430000 0.0393080000 0.3617750000 0.0018010000 115806259 0 402718720 2.9374895096 3.5220930576 4.2801060677 824 32.9200000000 0.6915110946 0.2256834207 0.8156625032 0.0548854466 0.5685790000 0.1127140000 0.0905750000 0.0000020000 0.3620550000 0.0018020000 115809035 0 402718720 2.9332363605 3.5215263367 4.2701992989 825 32.9600000000 0.6929073930 0.2262497528 0.8156625032 0.0548542586 1.0057600000 0.1127490000 0.0721310000 0.0395870000 0.3644330000 0.4154390000 115811811 0 402718720 2.9330375195 3.5149123669 4.2680835724 826 33.0000000000 0.6938680410 0.2268158766 0.8156625032 0.0548215790 0.5995640000 0.1257100000 0.1018810000 0.0000000000 0.3687300000 0.0018090000 115814587 0 402718720 2.9348840714 3.5148139000 4.2623963356 827 33.0400000000 0.6957917809 0.2273829575 0.8156625032 0.0547889261 0.5913970000 0.1128760000 0.0687300000 0.0394690000 0.3670560000 0.0018160000 115817363 0 402718720 2.9301640987 3.5107114315 4.2531971931 828 33.0800000000 0.6970236301 0.2279501564 0.8156625032 0.0547584384 0.5648950000 0.1128700000 0.0774050000 0.0000010000 0.3713760000 0.0018070000 115820139 0 402718720 2.9308788776 3.5012731552 4.2542037964 829 33.1199999990 0.6981750727 0.2285173759 0.8156625032 0.0547283606 1.0475830000 0.1128840000 0.1022080000 0.0395610000 0.3705600000 0.4209330000 115822915 0 402718720 2.9321928024 3.5012929440 4.2479038239 830 33.1600000000 0.6995473504 0.2290848819 0.8156625032 0.0547004853 0.5741720000 0.1368180000 0.0640000000 0.0000010000 0.3700890000 0.0018210000 115825691 0 402718720 2.9241120815 3.5036880970 4.2339725494 831 33.2000000000 0.7010659575 0.2296528495 0.8156625032 0.0546686724 0.6066950000 0.1127460000 0.0807690000 0.0398790000 0.3700280000 0.0018280000 115828467 0 402718720 2.9225373268 3.4988100529 4.2299041748 832 33.2400000000 0.7017494440 0.2302202733 0.8156625032 0.0546364990 0.5810140000 0.1128610000 0.0845510000 0.0000010000 0.3803280000 0.0018230000 115831243 0 402718720 2.9262762070 3.4942975044 4.2295084000 833 33.2800000000 0.7031986713 0.2307880745 0.8156625032 0.0546052137 1.0529160000 0.1336790000 0.0805480000 0.0398350000 0.3724810000 0.4249230000 115834019 0 402718720 2.9270124435 3.4921805859 4.2223582268 834 33.3200000000 0.7043950558 0.2313559485 0.8156625032 0.0545741420 0.5873990000 0.1128060000 0.0864900000 0.0000000000 0.3840000000 0.0024610000 115836795 0 402718720 2.9235997200 3.4893827438 4.2151522636 835 33.3600000000 0.7062039375 0.2319246288 0.8156625032 0.0545427849 0.6149610000 0.1170000000 0.0766280000 0.0399350000 0.3781140000 0.0018350000 115839571 0 402718720 2.9219174385 3.4871354103 4.2068958282 836 33.4000000000 0.7073493004 0.2324933186 0.8156625032 0.0545114359 0.5698610000 0.1087520000 0.0761780000 0.0000010000 0.3816500000 0.0018310000 115842347 0 402718720 2.9215278625 3.4864532948 4.1988682747 837 33.4399999990 0.7084835768 0.2330620046 0.8156625032 0.0544795259 1.0191280000 0.1087320000 0.0591730000 0.0394460000 0.3807520000 0.4295930000 115845123 0 402718720 2.9218189716 3.4836738110 4.1927275658 838 33.4800000000 0.7098539472 0.2336309688 0.8156625032 0.0544475038 0.6008540000 0.1369110000 0.0806100000 0.0000010000 0.3798570000 0.0019440000 115847899 0 402718720 2.9228894711 3.4793109894 4.1873693466 839 33.5200000000 0.7118628621 0.2342009710 0.8156625032 0.0544160196 0.6313490000 0.1223060000 0.0847000000 0.0399420000 0.3811230000 0.0018310000 115850675 0 402718720 2.9254579544 3.4778695107 4.1766138077 840 33.5600000000 0.7131932974 0.2347712000 0.8156625032 0.0543843074 0.5950230000 0.1254310000 0.0768010000 0.0000010000 0.3894940000 0.0018280000 115853451 0 402718720 2.9323225021 3.4710614681 4.1735110283 841 33.6000000000 0.7148054838 0.2353419899 0.8156625032 0.0543524697 1.0576710000 0.1126830000 0.0934420000 0.0399800000 0.3808020000 0.4292670000 115856227 0 402718720 2.9358007908 3.4665348530 4.1678261757 842 33.6400000000 0.7164276838 0.2359133506 0.8156625032 0.0543222203 0.5958900000 0.1253950000 0.0853700000 0.0000010000 0.3817970000 0.0018250000 115859003 0 402718720 2.9369394779 3.4634637833 4.1594352722 843 33.6800000000 0.7194399238 0.2364869289 0.8156625032 0.0542942825 0.6280230000 0.1219150000 0.0858220000 0.0401010000 0.3768500000 0.0018190000 115861779 0 402718720 2.9444892406 3.4566979408 4.1444563866 844 33.7200000000 0.7214452624 0.2370615241 0.8156625032 0.0542631378 0.5893140000 0.1125190000 0.0987300000 0.0000010000 0.3747510000 0.0018200000 115864555 0 402718720 2.9466032982 3.4534168243 4.1352648735 845 33.7599999990 0.7227760553 0.2376363342 0.8156625032 0.0542333146 1.0528380000 0.1126090000 0.1025480000 0.0401740000 0.3743820000 0.4216010000 115867331 0 402718720 2.9465723038 3.4534924030 4.1237859726 846 33.7999999990 0.7242647409 0.2382115451 0.8156625032 0.0542030280 0.6224110000 0.1396680000 0.1079830000 0.0000010000 0.3712470000 0.0019160000 115870107 0 402718720 2.9471249580 3.4563441277 4.1115593910 847 33.8400000000 0.7258995771 0.2387873279 0.8156625032 0.0541713148 0.6305130000 0.1126070000 0.1020770000 0.0402290000 0.3722960000 0.0018170000 115872883 0 402718720 2.9517953396 3.4555418491 4.1008191109 848 33.8800000000 0.7276061773 0.2393637652 0.8156625032 0.0541405760 0.6079850000 0.1242030000 0.1074730000 0.0000010000 0.3730100000 0.0018060000 115875659 0 402718720 2.9604899883 3.4519319534 4.0936913490 849 33.9200000000 0.7294227481 0.2399409843 0.8156625032 0.0541089303 1.0452980000 0.1126310000 0.1026460000 0.0401130000 0.3708110000 0.4175930000 115878435 0 402718720 2.9622070789 3.4463019371 4.0865163803 850 33.9600000000 0.7314607501 0.2405192428 0.8156625032 0.0540771098 0.5883680000 0.1125970000 0.1029110000 0.0000010000 0.3695660000 0.0018050000 115881211 0 402718720 2.9696397781 3.4415955544 4.0782141685 851 34.0000000000 0.7328673005 0.2410977952 0.8156625032 0.0540453117 0.6213890000 0.1087090000 0.1017310000 0.0394520000 0.3681930000 0.0018010000 115883987 0 402718720 2.9768190384 3.4373080730 4.0715255737 852 34.0400000000 0.7345988750 0.2416770218 0.8156625032 0.0540136277 0.5821670000 0.1087140000 0.1022240000 0.0000000000 0.3679870000 0.0017530000 115886763 0 402718720 2.9801287651 3.4350783825 4.0620355606 853 34.0800000000 0.7359319925 0.2422564532 0.8156625032 0.0539819755 1.0540260000 0.1266730000 0.1081620000 0.0399050000 0.3661090000 0.4116860000 115889539 0 402718720 2.9855947495 3.4349560738 4.0516729355 854 34.1199999990 0.7373625040 0.2428362027 0.8156625032 0.0539505986 0.5858150000 0.1126670000 0.1031460000 0.0000000000 0.3666940000 0.0017990000 115892315 0 402718720 2.9885110855 3.4330055714 4.0435776711 855 34.1600000000 0.7393069267 0.2434168702 0.8156625032 0.0539191581 0.6287210000 0.1127150000 0.1079210000 0.0398040000 0.3649620000 0.0018030000 115895091 0 402718720 2.9929008484 3.4282863140 4.0365705490 856 34.2000000000 0.7406441569 0.2439977432 0.8156625032 0.0538880201 0.5756120000 0.1126590000 0.0946620000 0.0000010000 0.3650080000 0.0017990000 115897867 0 402718720 2.9997558594 3.4261922836 4.0292901993 857 34.2400000000 0.7417874336 0.2445785946 0.8156625032 0.0538567496 1.0293800000 0.1127460000 0.1027090000 0.0398300000 0.3639220000 0.4086690000 115900643 0 402718720 3.0034394264 3.4232728481 4.0220246315 858 34.2800000000 0.7430677414 0.2451595843 0.8156625032 0.0538256053 0.5890750000 0.1127370000 0.1075560000 0.0000010000 0.3654860000 0.0017820000 115903419 0 402718720 3.0082871914 3.4195196629 4.0166730881 859 34.3200000000 0.7446141839 0.2457410216 0.8156625032 0.0537957614 0.6282740000 0.1126710000 0.1077500000 0.0399720000 0.3645680000 0.0017830000 115906195 0 402718720 3.0121488571 3.4193286896 4.0066623688 860 34.3600000000 0.7460700274 0.2463227995 0.8156625032 0.0537647412 0.5654570000 0.1092080000 0.0859210000 0.0000010000 0.3670330000 0.0017820000 115908971 0 402718720 3.0162148476 3.4174742699 3.9977335930 861 34.4000000000 0.7477115393 0.2469051325 0.8156625032 0.0537337939 1.0346630000 0.1126890000 0.1020510000 0.0398630000 0.3669690000 0.4115670000 115911747 0 402718720 3.0213632584 3.4129168987 3.9916093349 862 34.4400000000 0.7488345504 0.2474874172 0.8156625032 0.0537028304 0.6088320000 0.1290980000 0.1073130000 0.0000010000 0.3691270000 0.0017770000 115914523 0 402718720 3.0258271694 3.4101512432 3.9846575260 863 34.4800000000 0.7499420047 0.2480696357 0.8156625032 0.0536719280 0.6451100000 0.1260200000 0.1069080000 0.0400080000 0.3688620000 0.0017790000 115917299 0 402718720 3.0315737724 3.4097137451 3.9771096706 864 34.5200000000 0.7514917254 0.2486523002 0.8156625032 0.0536412884 0.5946600000 0.1127040000 0.1067570000 0.0000010000 0.3719010000 0.0017690000 115920075 0 402718720 3.0351302624 3.4096438885 3.9674320221 865 34.5600000000 0.7529333830 0.2492352841 0.8156625032 0.0536120320 1.0454840000 0.1127540000 0.1023910000 0.0400340000 0.3723740000 0.4164220000 115922851 0 402718720 3.0404174328 3.4029409885 3.9631774426 866 34.6000000000 0.7548230886 0.2498191037 0.8156625032 0.0535824381 0.5941370000 0.1128710000 0.1020300000 0.0000010000 0.3759580000 0.0017630000 115925627 0 402718720 3.0435860157 3.3913195133 3.9637014866 867 34.6400000000 0.7578502893 0.2504050682 0.8156625032 0.0535593236 0.6262530000 0.1127770000 0.0924580000 0.0400800000 0.3776410000 0.0017650000 115928403 0 402718720 3.0474328995 3.3850002289 3.9478211403 868 34.6800000000 0.7588809729 0.2509908699 0.8156625032 0.0535297647 0.5937160000 0.1088040000 0.0998650000 0.0000000000 0.3817650000 0.0017640000 115931179 0 402718720 3.0540916920 3.3819737434 3.9421217442 869 34.7200000000 0.7602074146 0.2515768498 0.8156625032 0.0535010153 1.0613670000 0.1127150000 0.1005440000 0.0402640000 0.3816550000 0.4246600000 115933955 0 402718720 3.0557103157 3.3803081512 3.9336075783 870 34.7600000000 0.7618719339 0.2521633959 0.8156625032 0.0534711679 0.5915860000 0.1126930000 0.0868870000 0.0000000000 0.3879210000 0.0023620000 115936731 0 402718720 3.0606539249 3.3771245480 3.9253008366 871 34.8000000000 0.7629818916 0.2527498695 0.8156625032 0.0534407200 0.6456860000 0.1253630000 0.0921660000 0.0401850000 0.3846730000 0.0017610000 115939507 0 402718720 3.0671589375 3.3727302551 3.9212839603 872 34.8400000000 0.7646338344 0.2533368924 0.8156625032 0.0534116119 0.5784180000 0.1126260000 0.0755960000 0.0000010000 0.3869200000 0.0017550000 115942283 0 402718720 3.0687298775 3.3692264557 3.9147868156 873 34.8800000000 0.7654827237 0.2539235428 0.8156625032 0.0533832056 1.0400880000 0.1211980000 0.0621040000 0.0403690000 0.3865180000 0.4283580000 115945059 0 402718720 3.0767695904 3.3718483448 3.9052143097 874 34.9200000000 0.7669927478 0.2545105785 0.8156625032 0.0533534151 0.5642870000 0.1125930000 0.0590950000 0.0000010000 0.3892960000 0.0017580000 115947835 0 402718720 3.0775198936 3.3706262112 3.8962106705 875 34.9600000000 0.7677614093 0.2550971509 0.8156625032 0.0533237208 0.6109160000 0.1086420000 0.0694990000 0.0400170000 0.3894530000 0.0017520000 115950611 0 402718720 3.0823831558 3.3727653027 3.8872935772 876 35.0000000000 0.7690656185 0.2556838729 0.8156625032 0.0532934949 0.5766240000 0.1088210000 0.0667420000 0.0000000000 0.3969940000 0.0023240000 115953387 0 402718720 3.0873413086 3.3699982166 3.8806948662 877 35.0400000000 0.7697825432 0.2562700744 0.8156625032 0.0532632034 1.0493670000 0.1148670000 0.0664390000 0.0402730000 0.3927280000 0.4335340000 115956163 0 402718720 3.0960433483 3.3657135963 3.8778092861 878 35.0800000000 0.7714248896 0.2568568110 0.8156625032 0.0532331756 0.6013260000 0.1439540000 0.0610660000 0.0000010000 0.3930100000 0.0017440000 115958939 0 402718720 3.0993196964 3.3606464863 3.8729381561 879 35.1200000000 0.7724664211 0.2574433976 0.8156625032 0.0532052461 0.6023940000 0.1125110000 0.0502940000 0.0402290000 0.3961210000 0.0016940000 115961715 0 402718720 3.1022226810 3.3624179363 3.8612167835 880 35.1600000000 0.7736180425 0.2580299597 0.8156625032 0.0531751032 0.5716860000 0.1125640000 0.0578490000 0.0000010000 0.3980070000 0.0017270000 115964491 0 402718720 3.1107103825 3.3589673042 3.8555707932 881 35.2000000000 0.7743341327 0.2586160031 0.8156625032 0.0531451397 1.0627150000 0.1084870000 0.0732310000 0.0402640000 0.3995730000 0.4396100000 115967267 0 402718720 3.1154980659 3.3556258678 3.8515043259 882 35.2400000000 0.7756258249 0.2592021820 0.8156625032 0.0531155426 0.6079540000 0.1124730000 0.0894770000 0.0000010000 0.4027420000 0.0017140000 115970043 0 402718720 3.1220941544 3.3538296223 3.8431274891 883 35.2800000000 0.7774115801 0.2597890556 0.8156625032 0.0530859476 0.6380430000 0.1229330000 0.0682050000 0.0406720000 0.4029680000 0.0017250000 115972819 0 402718720 3.1238024235 3.3511912823 3.8337948322 884 35.3200000000 0.7782025337 0.2603754962 0.8156625032 0.0530561301 0.5885720000 0.1251390000 0.0491560000 0.0000010000 0.4102520000 0.0022660000 115975595 0 402718720 3.1319923401 3.3497648239 3.8275201321 885 35.3600000000 0.7792111635 0.2609617512 0.8156625032 0.0530271439 1.1221720000 0.1460610000 0.0845290000 0.0397600000 0.4055680000 0.4447070000 115978371 0 402718720 3.1396002769 3.3418767452 3.8251123428 886 35.4000000000 0.7814040780 0.2615491579 0.8156625032 0.0529982213 0.5911590000 0.1312960000 0.0492910000 0.0000000000 0.4072980000 0.0017030000 115981147 0 402718720 3.1404030323 3.3325290680 3.8208942413 887 35.4400000000 0.7830507159 0.2621370965 0.8156625032 0.0529691104 0.6435130000 0.1123510000 0.0805780000 0.0402570000 0.4070640000 0.0017030000 115983923 0 402718720 3.1428625584 3.3295686245 3.8102600574 888 35.4800000000 0.7847656608 0.2627256422 0.8156625032 0.0529395138 0.6075650000 0.1314910000 0.0677640000 0.0000010000 0.4048680000 0.0018050000 115986699 0 402718720 3.1478903294 3.3236975670 3.8044683933 889 35.5200000000 0.7862877846 0.2633145760 0.8156625032 0.0529104722 1.0890690000 0.1083450000 0.0871140000 0.0399660000 0.4068850000 0.4452040000 115989475 0 402718720 3.1522314548 3.3192205429 3.7980015278 890 35.5600000000 0.7879538536 0.2639040583 0.8156625032 0.0528831391 0.5724860000 0.1122640000 0.0494090000 0.0000010000 0.4075290000 0.0017030000 115992251 0 402718720 3.1564745903 3.3177518845 3.7887058258 891 35.6000000000 0.7897027135 0.2644941803 0.8156625032 0.0528555299 0.6185120000 0.1122810000 0.0566940000 0.0402060000 0.4060420000 0.0017010000 115995027 0 402718720 3.1625165939 3.3168890476 3.7766623497 892 35.6400000000 0.7916436791 0.2650851550 0.8156625032 0.0528266646 0.5875340000 0.1123050000 0.0647710000 0.0000000000 0.4072220000 0.0016530000 115997803 0 402718720 3.1665952206 3.3146340847 3.7678053379 893 35.6800000000 0.7928085327 0.2656761107 0.8156625032 0.0527975962 1.1082320000 0.1237350000 0.0957980000 0.0401590000 0.4048300000 0.4421410000 116000579 0 402718720 3.1739675999 3.3109347820 3.7626173496 894 35.7200000000 0.7939460874 0.2662670167 0.8156625032 0.0527691421 0.5859860000 0.1123160000 0.0650060000 0.0000000000 0.4053740000 0.0017070000 116003355 0 402718720 3.1820015907 3.3106725216 3.7558081150 895 35.7600000000 0.7955573797 0.2668584026 0.8156625032 0.0527408399 0.6162140000 0.1122240000 0.0570460000 0.0401520000 0.4034860000 0.0017140000 116006131 0 402718720 3.1873295307 3.3094248772 3.7450306416 896 35.8000000000 0.7969667912 0.2674500414 0.8156625032 0.0527123768 0.5856770000 0.1123080000 0.0652480000 0.0000010000 0.4048430000 0.0017130000 116008907 0 402718720 3.1927542686 3.3091719151 3.7364096642 897 35.8400000000 0.7980857491 0.2680416085 0.8156625032 0.0526845200 1.0453630000 0.1123240000 0.0495340000 0.0400740000 0.4026710000 0.4391890000 116011683 0 402718720 3.2002549171 3.3136031628 3.7233927250 898 35.8800000000 0.7991532087 0.2686330468 0.8156625032 0.0526573247 0.5765610000 0.1123100000 0.0575380000 0.0000000000 0.4034120000 0.0017220000 116014459 0 402718720 3.2081527710 3.3128993511 3.7167634964 899 35.9200000000 0.8006845713 0.2692248728 0.8156625032 0.0526305361 0.6291190000 0.1123410000 0.0650810000 0.0395870000 0.4087910000 0.0017340000 116017235 0 402718720 3.2149262428 3.3091211319 3.7098965645 900 35.9600000000 0.8021786213 0.2698170436 0.8156625032 0.0526038990 0.5741520000 0.1083640000 0.0570910000 0.0000010000 0.4053710000 0.0017340000 116020011 0 402718720 3.2237472534 3.3008115292 3.7078502178 901 36.0000000000 0.8039975762 0.2704099188 0.8156625032 0.0525763828 1.0606660000 0.1100050000 0.0652310000 0.0397420000 0.4045100000 0.4395980000 116022787 0 402718720 3.2269709110 3.2932963371 3.7048439980 902 36.0400000000 0.8063615561 0.2710041002 0.8156625032 0.0525500387 0.5936270000 0.1263020000 0.0605140000 0.0000010000 0.4034730000 0.0017180000 116025563 0 402718720 3.2325673103 3.2907536030 3.6917259693 903 36.0800000000 0.8081553578 0.2715989521 0.8156625032 0.0525229314 0.6194480000 0.1122620000 0.0597030000 0.0403510000 0.4038150000 0.0017200000 116028339 0 402718720 3.2388362885 3.2856507301 3.6857995987 904 36.1200000000 0.8076871634 0.2721919700 0.8156625032 0.0524953721 0.5792790000 0.1122430000 0.0573230000 0.0000000000 0.4064170000 0.0017120000 116031115 0 402718720 3.2515301704 3.2853977680 3.6894083023 905 36.1600000000 0.8125353456 0.2727890345 0.8156625032 0.0524815146 1.0487190000 0.1121750000 0.0570380000 0.0400940000 0.4023510000 0.4354620000 116033891 0 402718720 3.2749552727 3.2788569927 3.6634724140 906 36.2000000000 0.8141785264 0.2733865946 0.8156625032 0.0524538958 0.6158700000 0.1122420000 0.0973020000 0.0000000000 0.4030040000 0.0017180000 116036667 0 402718720 3.2820727825 3.2748680115 3.6557183266 907 36.2400000000 0.8158137798 0.2739846401 0.8158137798 0.0524260331 0.6337890000 0.1250750000 0.0650740000 0.0400140000 0.4002780000 0.0017330000 116039443 0 402718720 3.2883884907 3.2687501907 3.6522326469 908 36.2800000000 0.8167566061 0.2745824065 0.8167566061 0.0524001438 0.5789890000 0.1082650000 0.0652100000 0.0000000000 0.4021810000 0.0017320000 116042219 0 402718720 3.2924635410 3.2682523727 3.6455807686 909 36.3200000000 0.8169043064 0.2751790203 0.8169043064 0.0523728888 1.0681530000 0.1249050000 0.0740100000 0.0400060000 0.3978870000 0.4297310000 116044995 0 402718720 3.3025105000 3.2708210945 3.6407129765 910 36.3600000000 0.8172274232 0.2757746779 0.8172274232 0.0523454716 0.6065050000 0.1361300000 0.0699610000 0.0000000000 0.3970650000 0.0017450000 116047771 0 402718720 3.3112318516 3.2696385384 3.6395747662 911 36.4000000000 0.8180014491 0.2763698774 0.8180014491 0.0523181139 0.6064270000 0.1089350000 0.0581310000 0.0399470000 0.3960520000 0.0017420000 116050547 0 402718720 3.3162522316 3.2665586472 3.6377310753 912 36.4400000000 0.8188895583 0.2769647455 0.8188895583 0.0522905494 0.5792980000 0.1120400000 0.0671240000 0.0000010000 0.3967960000 0.0017420000 116053323 0 402718720 3.3235497475 3.2658193111 3.6312716007 913 36.4800000000 0.8200400472 0.2775595706 0.8200400472 0.0522629250 1.0402960000 0.1210680000 0.0586790000 0.0398200000 0.3942300000 0.4248860000 116056099 0 402718720 3.3307294846 3.2634603977 3.6266958714 914 36.5200000000 0.8209586740 0.2781540991 0.8209586740 0.0522350405 0.5693720000 0.1119450000 0.0591620000 0.0000010000 0.3949070000 0.0017490000 116058875 0 402718720 3.3364162445 3.2596600056 3.6233429909 915 36.5600000000 0.8209615946 0.2787473314 0.8209615946 0.0522070600 0.6307800000 0.1119850000 0.0836790000 0.0392440000 0.3924910000 0.0017550000 116061651 0 402718720 3.3452515602 3.2595126629 3.6211688519 916 36.6000000000 0.8216605186 0.2793400313 0.8216605186 0.0521795157 0.5720820000 0.1080450000 0.0672960000 0.0000000000 0.3933910000 0.0017560000 116064427 0 402718720 3.3539752960 3.2603878975 3.6156909466 917 36.6400000000 0.8227018118 0.2799325742 0.8227018118 0.0521514889 1.0452290000 0.1098330000 0.0841490000 0.0396730000 0.3904220000 0.4195570000 116067203 0 402718720 3.3603665829 3.2552218437 3.6134159565 918 36.6800000000 0.8240242600 0.2805252666 0.8240242600 0.0521237988 0.5935350000 0.1387990000 0.0624510000 0.0000000000 0.3886950000 0.0018720000 116069979 0 402718720 3.3663330078 3.2497737408 3.6102840900 919 36.7200000000 0.8244515061 0.2811171342 0.8244515061 0.0520963589 0.6061670000 0.1119090000 0.0624960000 0.0399250000 0.3884270000 0.0017740000 116072755 0 402718720 3.3738267422 3.2509071827 3.6061387062 920 36.7600000000 0.8254468441 0.2817087969 0.8254468441 0.0520684756 0.5676130000 0.1120640000 0.0627290000 0.0000010000 0.3894280000 0.0017790000 116075531 0 402718720 3.3796582222 3.2506453991 3.5994455814 921 36.8000000000 0.8251240253 0.2822988243 0.8254468441 0.0520406322 1.0650780000 0.1418250000 0.0778830000 0.0395730000 0.3881330000 0.4160430000 116078307 0 402718720 3.3912861347 3.2533750534 3.5972845554 922 36.8400000000 0.8263220191 0.2828888711 0.8263220191 0.0520138919 0.5807700000 0.1120570000 0.0771870000 0.0000000000 0.3881210000 0.0017850000 116081083 0 402718720 3.4012303352 3.2480952740 3.5967748165 923 36.8800000000 0.8263372779 0.2834776560 0.8263372779 0.0519858735 0.6043810000 0.1229400000 0.0518620000 0.0396020000 0.3865610000 0.0017890000 116083859 0 402718720 3.4084720612 3.2458772659 3.5952095985 924 36.9200000000 0.8274660707 0.2840663880 0.8274660707 0.0519584630 0.5630420000 0.1121190000 0.0610450000 0.0000020000 0.3864500000 0.0017950000 116086635 0 402718720 3.4195344448 3.2474942207 3.5873990059 925 36.9600000000 0.8282824755 0.2846547297 0.8282824755 0.0519315382 1.0133810000 0.1120540000 0.0637550000 0.0394150000 0.3849050000 0.4116120000 116089411 0 402718720 3.4302654266 3.2462391853 3.5823245049 926 37.0000000000 0.8294547796 0.2852430667 0.8294547796 0.0519062756 0.5967850000 0.1469780000 0.0614190000 0.0000010000 0.3849440000 0.0018100000 116092187 0 402718720 3.4463768005 3.2458040714 3.5744049549 927 37.0400000000 0.8298482895 0.2858305589 0.8298482895 0.0518789539 0.6006230000 0.1121840000 0.0640690000 0.0392740000 0.3816270000 0.0018220000 116094963 0 402718720 3.4591567516 3.2460198402 3.5713961124 928 37.0800000000 0.8306827545 0.2864176841 0.8306827545 0.0518514821 0.5598320000 0.1122830000 0.0613430000 0.0000010000 0.3827610000 0.0018240000 116097739 0 402718720 3.4667797089 3.2412021160 3.5693016052 929 37.1200000000 0.8317250609 0.2870046673 0.8317250609 0.0518240387 1.0490580000 0.1145620000 0.0824120000 0.0504450000 0.3957050000 0.4043050000 116100515 0 402718720 3.4762074947 3.2373461723 3.5668883324 930 37.1600000000 0.8321658373 0.2875908621 0.8321658373 0.0517967584 0.5599340000 0.1123030000 0.0649840000 0.0000010000 0.3791590000 0.0018480000 116103291 0 402718720 3.4865562916 3.2364282608 3.5634512901 931 37.2000000000 0.8331322074 0.2881768356 0.8331322074 0.0517693664 0.5947970000 0.1124020000 0.0615810000 0.0388910000 0.3784140000 0.0018550000 116106067 0 402718720 3.4937283993 3.2329514027 3.5593020916 932 37.2400000000 0.8333137035 0.2887617464 0.8333137035 0.0517419903 0.5577070000 0.1123760000 0.0622530000 0.0000010000 0.3795790000 0.0018500000 116108843 0 402718720 3.5048782825 3.2342607975 3.5585999489 933 37.2800000000 0.8338004351 0.2893459250 0.8338004351 0.0517149374 1.0068970000 0.1230700000 0.0654120000 0.0387210000 0.3776740000 0.4003700000 116111619 0 402718720 3.5156860352 3.2349262238 3.5536048412 934 37.3200000000 0.8345558047 0.2899296615 0.8345558047 0.0516881800 0.5714880000 0.1122550000 0.0743680000 0.0000010000 0.3813760000 0.0018410000 116114395 0 402718720 3.5261766911 3.2349958420 3.5489592552 935 37.3600000000 0.8350658417 0.2905126949 0.8350658417 0.0516614688 0.5971740000 0.1121950000 0.0635400000 0.0386130000 0.3793150000 0.0018450000 116117171 0 402718720 3.5376434326 3.2348759174 3.5477571487 936 37.4000000000 0.8347480297 0.2910941429 0.8350658417 0.0516343233 0.5797190000 0.1249910000 0.0704830000 0.0000010000 0.3807430000 0.0018360000 116119947 0 402718720 3.5485906601 3.2336134911 3.5488805771 937 37.4400000000 0.8350682259 0.2916746915 0.8350682259 0.0516073109 0.9994090000 0.1120800000 0.0703570000 0.0384680000 0.3785650000 0.3982950000 116122723 0 402718720 3.5599086285 3.2317986488 3.5486333370 938 37.4800000000 0.8362803459 0.2922552946 0.8362803459 0.0515801712 0.5676830000 0.1237100000 0.0626750000 0.0000000000 0.3778000000 0.0018430000 116125499 0 402718720 3.5674500465 3.2279059887 3.5462210178 939 37.5200000000 0.8363492489 0.2928347344 0.8363492489 0.0515535957 0.5914670000 0.1120280000 0.0621470000 0.0382740000 0.3754940000 0.0018530000 116128275 0 402718720 3.5789337158 3.2302105427 3.5416772366 940 37.5600000000 0.8362905383 0.2934128788 0.8363492489 0.0515265587 0.5532500000 0.1120420000 0.0624840000 0.0000000000 0.3752170000 0.0018500000 116131051 0 402718720 3.5906701088 3.2321417332 3.5415103436 941 37.6000000000 0.8369576335 0.2939905034 0.8369576335 0.0514995353 0.9889520000 0.1251140000 0.0623640000 0.0382440000 0.3722810000 0.3893040000 116133827 0 402718720 3.5990951061 3.2292859554 3.5398139954 942 37.6400000000 0.8378853202 0.2945678865 0.8378853202 0.0514726632 0.5636590000 0.1080090000 0.0796430000 0.0000000000 0.3724780000 0.0018720000 116136603 0 402718720 3.6071581841 3.2254481316 3.5374646187 943 37.6800000000 0.8378843069 0.2951440439 0.8378853202 0.0514459414 0.6291920000 0.1431050000 0.0630420000 0.0379780000 0.3805860000 0.0025630000 116139379 0 402718720 3.6186366081 3.2249372005 3.5373232365 944 37.7200000000 0.8378515840 0.2957189459 0.8378853202 0.0514191052 0.5494020000 0.1119090000 0.0664430000 0.0000010000 0.3673050000 0.0019930000 116142155 0 402718720 3.6268785000 3.2237601280 3.5384352207 945 37.7600000000 0.8374947906 0.2962922537 0.8378853202 0.0513923144 0.9501590000 0.1118390000 0.0546890000 0.0377000000 0.3655260000 0.3787270000 116144931 0 402718720 3.6385359764 3.2228486538 3.5401039124 946 37.8000000000 0.8380720615 0.2968649596 0.8380720615 0.0513657655 0.5431500000 0.1116710000 0.0641820000 0.0000020000 0.3637320000 0.0019060000 116147707 0 402718720 3.6480522156 3.2205386162 3.5393266678 947 37.8400000000 0.8387235999 0.2974371440 0.8387235999 0.0513401970 0.5787860000 0.1114280000 0.0672530000 0.0375630000 0.3587520000 0.0020240000 116150483 0 402718720 3.6573631763 3.2178475857 3.5363156796 948 37.8800000000 0.8391195536 0.2980085390 0.8391195536 0.0513143906 0.5526730000 0.1229220000 0.0678930000 0.0000010000 0.3582730000 0.0019230000 116153259 0 402718720 3.6671938896 3.2152969837 3.5355861187 949 37.9200000000 0.8399212360 0.2985795745 0.8399212360 0.0512888367 0.9324760000 0.1110760000 0.0647970000 0.0372290000 0.3532640000 0.3644330000 116156035 0 402718720 3.6766016483 3.2142229080 3.5318832397 950 37.9600000000 0.8401816487 0.2991496819 0.8401816487 0.0512626959 0.5317950000 0.1111890000 0.0653410000 0.0000010000 0.3516620000 0.0019340000 116158811 0 402718720 3.6867730618 3.2135698795 3.5299808979 951 38.0000000000 0.8408694863 0.2997193137 0.8408694863 0.0512363576 0.5660870000 0.1114210000 0.0653210000 0.0369170000 0.3488010000 0.0019460000 116161587 0 402718720 3.6956989765 3.2112405300 3.5295073986 952 38.0400000000 0.8418796062 0.3002888098 0.8418796062 0.0512102790 0.5465570000 0.1249810000 0.0685770000 0.0000010000 0.3493700000 0.0019440000 116164363 0 402718720 3.7052481174 3.2080488205 3.5276069641 953 38.0800000000 0.8419647217 0.3008572001 0.8419647217 0.0511842999 0.9214350000 0.1117200000 0.0687120000 0.0368030000 0.3470150000 0.3554740000 116167139 0 402718720 3.7152705193 3.2074756622 3.5268721581 954 38.1200000000 0.8425989151 0.3014250635 0.8425989151 0.0511580729 0.5296080000 0.1116850000 0.0659700000 0.0000010000 0.3483230000 0.0019460000 116169915 0 402718720 3.7259025574 3.2060761452 3.5255022049 955 38.1600000000 0.8429017663 0.3019920548 0.8429017663 0.0511325448 0.5602930000 0.1078440000 0.0650720000 0.0357190000 0.3480250000 0.0019490000 116172691 0 402718720 3.7356679440 3.2065658569 3.5233609676 956 38.2000000000 0.8436454535 0.3025586379 0.8436454535 0.0511064269 0.5323400000 0.1118320000 0.0660030000 0.0000010000 0.3508660000 0.0019480000 116175467 0 402718720 3.7466044426 3.2053248882 3.5208003521 957 38.2400000000 0.8445709348 0.3031250039 0.8445709348 0.0510801074 0.9257100000 0.1117890000 0.0657610000 0.0368910000 0.3508590000 0.3587210000 116178243 0 402718720 3.7573282719 3.2040288448 3.5178167820 958 38.2800000000 0.8454939127 0.3036911510 0.8454939127 0.0510538103 0.5261660000 0.1118570000 0.0567580000 0.0000010000 0.3539130000 0.0019430000 116181019 0 402718720 3.7657535076 3.2013876438 3.5150172710 959 38.3200000000 0.8456905484 0.3042563224 0.8456905484 0.0510278357 0.5852510000 0.1245780000 0.0662150000 0.0363740000 0.3544220000 0.0019480000 116183795 0 402718720 3.7768614292 3.2035758495 3.5123615265 960 38.3600000000 0.8455088735 0.3048201271 0.8456905484 0.0510019081 0.5303260000 0.1116870000 0.0572050000 0.0000010000 0.3578040000 0.0019400000 116186571 0 402718720 3.7904174328 3.2071683407 3.5104076862 961 38.4000000000 0.8461176753 0.3053833920 0.8461176753 0.0509787827 0.9406990000 0.1116790000 0.0660420000 0.0363310000 0.3588460000 0.3661160000 116189347 0 402718720 3.7992002964 3.2011446953 3.5118789673 962 38.4400000000 0.8463447094 0.3059457219 0.8463447094 0.0509534109 0.5308800000 0.1082960000 0.0573200000 0.0000010000 0.3616250000 0.0019420000 116192123 0 402718720 3.8089737892 3.1985645294 3.5114467144 963 38.4800000000 0.8468527794 0.3065074114 0.8468527794 0.0509283179 0.5684880000 0.1115930000 0.0551530000 0.0362040000 0.3618780000 0.0019450000 116194899 0 402718720 3.8208022118 3.1960897446 3.5099806786 964 38.5200000000 0.8471379280 0.3070682315 0.8471379280 0.0509031758 0.5440930000 0.1116460000 0.0648760000 0.0000000000 0.3639210000 0.0019470000 116197675 0 402718720 3.8309578896 3.1939518452 3.5101335049 965 38.5600000000 0.8478033543 0.3076285788 0.8478033543 0.0508774164 0.9499210000 0.1117540000 0.0646660000 0.0357020000 0.3649450000 0.3711620000 116200451 0 402718720 3.8415138721 3.1909420490 3.5071296692 966 38.6000000000 0.8481975198 0.3081881739 0.8481975198 0.0508516824 0.5501110000 0.1117980000 0.0670780000 0.0000000000 0.3675950000 0.0019410000 116203227 0 402718720 3.8509767056 3.1885149479 3.5059576035 967 38.6400000000 0.8483229876 0.3087467415 0.8483229876 0.0508266616 0.5771670000 0.1118940000 0.0576310000 0.0359440000 0.3680590000 0.0019380000 116206003 0 402718720 3.8620386124 3.1872611046 3.5053043365 968 38.6800000000 0.8491179943 0.3093049762 0.8491179943 0.0508013255 0.5992690000 0.1239910000 0.0902070000 0.0000010000 0.3814810000 0.0018710000 116208779 0 402718720 3.8716259003 3.1844933033 3.5024619102 969 38.7200000000 0.8489249945 0.3098618596 0.8491179943 0.0507756371 0.9585240000 0.1117260000 0.0578690000 0.0359270000 0.3724000000 0.3788910000 116211555 0 402718720 3.8819005489 3.1844103336 3.5018293858 970 38.7600000000 0.8497667909 0.3104184627 0.8497667909 0.0507499438 0.5615650000 0.1115200000 0.0708060000 0.0000010000 0.3756060000 0.0019240000 116214331 0 402718720 3.8896243572 3.1814227104 3.4982850552 971 38.8000000000 0.8501691222 0.3109743336 0.8501691222 0.0507243555 0.5845340000 0.1113500000 0.0579450000 0.0359560000 0.3756290000 0.0019330000 116217107 0 402718720 3.9001612663 3.1808397770 3.4954082966 972 38.8400000000 0.8502552509 0.3115291493 0.8502552509 0.0506997306 0.5511000000 0.1110310000 0.0581340000 0.0000010000 0.3783110000 0.0019230000 116219883 0 402718720 3.9100148678 3.1803963184 3.4934821129 973 38.8800000000 0.8502757549 0.3120828458 0.8502757549 0.0506771224 0.9701380000 0.1108600000 0.0581820000 0.0358480000 0.3784540000 0.3850840000 116222659 0 402718720 3.9204602242 3.1800749302 3.4921996593 974 38.9200000000 0.8501590490 0.3126352854 0.8502757549 0.0506542519 0.5506410000 0.1106920000 0.0556420000 0.0000000000 0.3806630000 0.0019270000 116225435 0 402718720 3.9286129475 3.1782414913 3.4935567379 975 38.9600000000 0.8501604199 0.3131865932 0.8502757549 0.0506293952 0.5861670000 0.1096550000 0.0555130000 0.0358250000 0.3815180000 0.0019260000 116228211 0 402718720 3.9377009869 3.1765644550 3.4939379692 976 39.0000000000 0.8502507210 0.3137368638 0.8502757549 0.0506041598 0.5611210000 0.1105690000 0.0579070000 0.0000010000 0.3880190000 0.0026760000 116230987 0 402718720 3.9471845627 3.1747615337 3.4936139584 977 39.0400000000 0.8502349854 0.3142859919 0.8502757549 0.0505787805 1.0520850000 0.1442500000 0.0776850000 0.0462830000 0.3912700000 0.3908950000 116233763 0 402718720 3.9576025009 3.1744780540 3.4929308891 978 39.0800000000 0.8497398496 0.3148334907 0.8502757549 0.0505534223 0.5711660000 0.1207510000 0.0605740000 0.0000010000 0.3861880000 0.0019240000 116236539 0 402718720 3.9668884277 3.1733744144 3.4949595928 979 39.1200000000 0.8502531648 0.3153803954 0.8502757549 0.0505294995 0.5980050000 0.1113150000 0.0596610000 0.0358690000 0.3875050000 0.0019240000 116239315 0 402718720 3.9752104282 3.1707229614 3.4926557541 980 39.1600000000 0.8503463268 0.3159262790 0.8503463268 0.0505050617 0.5633610000 0.1114400000 0.0576490000 0.0000010000 0.3906420000 0.0019200000 116242091 0 402718720 3.9865617752 3.1701047421 3.4906296730 981 39.2000000000 0.8499787450 0.3164706750 0.8503463268 0.0504800246 1.0055870000 0.1115870000 0.0669360000 0.0361450000 0.3911390000 0.3980310000 116244867 0 402718720 3.9987173080 3.1714026928 3.4899504185 982 39.2400000000 0.8498097658 0.3170137902 0.8503463268 0.0504549734 0.5800180000 0.1242530000 0.0572480000 0.0000000000 0.3948950000 0.0019090000 116247643 0 402718720 4.0047221184 3.1702985764 3.4910864830 983 39.2800000000 0.8498063684 0.3175557969 0.8503463268 0.0504300470 0.6036290000 0.1114820000 0.0572070000 0.0366220000 0.3946640000 0.0019120000 116250419 0 402718720 4.0144643784 3.1691455841 3.4917221069 984 39.3200000000 0.8498563170 0.3180967527 0.8503463268 0.0504051443 0.5788390000 0.1107350000 0.0666190000 0.0000000000 0.3978490000 0.0019070000 116253195 0 402718720 4.0258355141 3.1689152718 3.4908251762 985 39.3600000000 0.8501640558 0.3186369225 0.8503463268 0.0503802108 1.0213350000 0.1113570000 0.0662710000 0.0371160000 0.3985310000 0.4063200000 116255971 0 402718720 4.0340466499 3.1664533615 3.4909651279 986 39.4000000000 0.8496696949 0.3191754953 0.8503463268 0.0503551599 0.5825480000 0.1113930000 0.0662120000 0.0000010000 0.4013110000 0.0018910000 116258747 0 402718720 4.0419282913 3.1658859253 3.4939517975 987 39.4400000000 0.8496252894 0.3197129318 0.8503463268 0.0503302422 0.6195900000 0.1114110000 0.0658130000 0.0371740000 0.4015530000 0.0018920000 116261523 0 402718720 4.0515151024 3.1648812294 3.4955730438 988 39.4800000000 0.8495811224 0.3202492356 0.8503463268 0.0503052197 0.6287530000 0.1433840000 0.0784240000 0.0000010000 0.4033170000 0.0018850000 116264299 0 402718720 4.0619916916 3.1640543938 3.4960141182 989 39.5200000000 0.8496390581 0.3207845135 0.8503463268 0.0502801738 1.0187210000 0.1116950000 0.0592570000 0.0378730000 0.3990830000 0.4090800000 116267075 0 402718720 4.0708980560 3.1632690430 3.4962821007 990 39.5600000000 0.8493890166 0.3213184574 0.8503463268 0.0502550691 0.5827910000 0.1117530000 0.0633860000 0.0000000000 0.4040420000 0.0018810000 116269851 0 402718720 4.0806436539 3.1637046337 3.4968099594 991 39.6000000000 0.8484410048 0.3218503672 0.8503463268 0.0502299977 0.6320970000 0.1117920000 0.0748510000 0.0379920000 0.4038120000 0.0018810000 116272627 0 402718720 4.0903596878 3.1663100719 3.4997272491 992 39.6400000000 0.8478662372 0.3223806251 0.8503463268 0.0502051234 0.5820640000 0.1078680000 0.0649140000 0.0000020000 0.4056710000 0.0018750000 116275403 0 402718720 4.1000423431 3.1689617634 3.5005681515 993 39.6800000000 0.8468425274 0.3229087841 0.8503463268 0.0501810842 1.0357860000 0.1101120000 0.0654900000 0.0380550000 0.4060020000 0.4143860000 116278179 0 402718720 4.1091952324 3.1718044281 3.5045135021 994 39.7200000000 0.8462907672 0.3234353254 0.8503463268 0.0501572514 0.5883720000 0.1116430000 0.0654510000 0.0000010000 0.4076590000 0.0018780000 116280955 0 402718720 4.1188125610 3.1729824543 3.5065109730 995 39.7600000000 0.8460611105 0.3239605774 0.8503463268 0.0501334592 0.6266350000 0.1115560000 0.0653160000 0.0376830000 0.4084390000 0.0018710000 116283731 0 402718720 4.1271848679 3.1720848083 3.5086784363 996 39.8000000000 0.8455771804 0.3244842888 0.8503463268 0.0501088593 0.6132140000 0.1320450000 0.0683320000 0.0000010000 0.4091900000 0.0018720000 116286507 0 402718720 4.1366572380 3.1716709137 3.5113077164 997 39.8400000000 0.8451155424 0.3250064867 0.8503463268 0.0500842890 1.0448000000 0.1113430000 0.0668170000 0.0379110000 0.4091830000 0.4178100000 116289283 0 402718720 4.1472511292 3.1721067429 3.5132498741 998 39.8800000000 0.8447842598 0.3255273061 0.8503463268 0.0500598415 0.6015420000 0.1250010000 0.0631830000 0.0000000000 0.4097360000 0.0018670000 116292059 0 402718720 4.1564240456 3.1716272831 3.5148165226 999 39.9200000000 0.8436957002 0.3260459932 0.8503463268 0.0500350761 0.6327680000 0.1072640000 0.0739160000 0.0380180000 0.4099400000 0.0018650000 116294835 0 402718720 4.1690874100 3.1765084267 3.5175929070 1000 39.9600000000 0.8434973359 0.3265634445 0.8503463268 0.0500109103 0.6120340000 0.1235320000 0.0743220000 0.0000000000 0.4105500000 0.0018590000 116297611 0 402718720 4.1779875755 3.1758496761 3.5177919865 1001 40.0000000000 0.8434484601 0.3270798132 0.8503463268 0.0499861866 1.0411610000 0.1068360000 0.0643880000 0.0377980000 0.4106970000 0.4196770000 116300387 0 402718720 4.1871485710 3.1749930382 3.5192370415 1002 40.0400000000 0.8427953720 0.3275944994 0.8503463268 0.0499615517 0.6183880000 0.1104100000 0.0926280000 0.0000000000 0.4117240000 0.0018500000 116303163 0 402718720 4.1976661682 3.1766343117 3.5218842030 1003 40.0800000000 0.8419052958 0.3281072718 0.8503463268 0.0499370612 0.6375950000 0.1104610000 0.0741930000 0.0383970000 0.4109220000 0.0018490000 116305939 0 402718720 4.2090287209 3.1793434620 3.5232670307 1004 40.1200000000 0.8413092494 0.3286184292 0.8503463268 0.0499135392 0.6189240000 0.1348310000 0.0680310000 0.0000010000 0.4124410000 0.0018420000 116308715 0 402718720 4.2177634239 3.1789712906 3.5254805088 1005 40.1600000000 0.8407979012 0.3291280605 0.8503463268 0.0498890092 1.0672630000 0.1107840000 0.0829210000 0.0381830000 0.4121780000 0.4214280000 116311491 0 402718720 4.2271833420 3.1792819500 3.5264754295 1006 40.2000000000 0.8396509886 0.3296355386 0.8503463268 0.0498644571 0.6330870000 0.1109570000 0.1057730000 0.0000010000 0.4127540000 0.0018310000 116314267 0 402718720 4.2374286652 3.1823561192 3.5296528339 1007 40.2400000000 0.8383299112 0.3301406968 0.8503463268 0.0498401672 0.6484900000 0.1111690000 0.0826980000 0.0381800000 0.4128340000 0.0018340000 116317043 0 402718720 4.2471938133 3.1844556332 3.5322678089 1008 40.2800000000 0.8375380635 0.3306440672 0.8503463268 0.0498161125 0.6644560000 0.1351640000 0.1151270000 0.0000000000 0.4104800000 0.0018240000 116319819 0 402718720 4.2551751137 3.1846964359 3.5350725651 1009 40.3200000000 0.8364143372 0.3311453262 0.8503463268 0.0497917788 1.0752690000 0.1115320000 0.0865910000 0.0384520000 0.4138100000 0.4231020000 116322595 0 402718720 4.2636885643 3.1855590343 3.5373587608 1010 40.3600000000 0.8360114694 0.3316451936 0.8503463268 0.0497676867 0.6400580000 0.1116740000 0.1094220000 0.0000010000 0.4153610000 0.0018220000 116325371 0 402718720 4.2735729218 3.1872191429 3.5415306091 1011 40.4000000000 0.8357607722 0.3321438243 0.8503463268 0.0497437012 0.6504530000 0.1112000000 0.0818010000 0.0382940000 0.4155520000 0.0018140000 116328147 0 402718720 4.2814292908 3.1868133545 3.5434567928 1012 40.4400000000 0.8353311419 0.3326410450 0.8503463268 0.0497193959 0.6101060000 0.1304230000 0.0575860000 0.0000010000 0.4175930000 0.0025020000 116330923 0 402718720 4.2893033028 3.1852600574 3.5440871716 1013 40.4800000000 0.8340460658 0.3331360154 0.8503463268 0.0496952996 1.1589240000 0.1457720000 0.1301710000 0.0384200000 0.4165020000 0.4262750000 116333699 0 402718720 4.2982969284 3.1867341995 3.5478045940 1014 40.5200000000 0.8343155980 0.3336302753 0.8503463268 0.0496709559 0.6146480000 0.1120270000 0.0810770000 0.0000010000 0.4179430000 0.0017970000 116336475 0 402718720 4.3054037094 3.1881680489 3.5535225868 1015 40.5600000000 0.8341580629 0.3341234061 0.8503463268 0.0496470425 0.6526740000 0.1121020000 0.0808360000 0.0384110000 0.4177290000 0.0017990000 116339251 0 402718720 4.3133502007 3.1866660118 3.5541839600 1016 40.6000000000 0.8335902095 0.3346150073 0.8503463268 0.0496230300 0.6157620000 0.1120470000 0.0805560000 0.0000010000 0.4195890000 0.0017920000 116342027 0 402718720 4.3207192421 3.1844816208 3.5546131134 1017 40.6400000000 0.8324347138 0.3351045056 0.8503463268 0.0495991864 1.0803780000 0.1120840000 0.0803880000 0.0384130000 0.4186580000 0.4290440000 116344803 0 402718720 4.3277468681 3.1860649586 3.5582907200 1018 40.6800000000 0.8316496015 0.3355922709 0.8503463268 0.0495750328 0.6602570000 0.1303480000 0.1070010000 0.0000010000 0.4193010000 0.0017930000 116347579 0 402718720 4.3362312317 3.1864786148 3.5608496666 1019 40.7200000000 0.8310421109 0.3360784827 0.8503463268 0.0495509312 0.6619590000 0.1120890000 0.0891010000 0.0384050000 0.4187540000 0.0017950000 116350355 0 402718720 4.3430414200 3.1879198551 3.5656423569 1020 40.7600000000 0.8301336169 0.3365628505 0.8503463268 0.0495268826 0.6633250000 0.1120250000 0.1069070000 0.0000010000 0.4398810000 0.0024720000 116353131 0 402718720 4.3517518044 3.1888890266 3.5696465969 1021 40.8000000000 0.8290756345 0.3370452332 0.8503463268 0.0495027976 1.0937950000 0.1255460000 0.0800170000 0.0379070000 0.4189490000 0.4295840000 116355907 0 402718720 4.3598337173 3.1904211044 3.5738456249 1022 40.8400000000 0.8273676634 0.3375250008 0.8503463268 0.0494787341 0.6066140000 0.1120230000 0.0710990000 0.0000010000 0.4199040000 0.0017880000 116358683 0 402718720 4.3671422005 3.1924550533 3.5788152218 1023 40.8800000000 0.8275553584 0.3380040138 0.8503463268 0.0494547943 0.6794280000 0.1119820000 0.1060580000 0.0384040000 0.4193880000 0.0017880000 116361459 0 402718720 4.3742632866 3.1946461201 3.5870063305 1024 40.9200000000 0.8252207637 0.3384798114 0.8503463268 0.0494312995 0.6153640000 0.1119600000 0.0797340000 0.0000000000 0.4200670000 0.0017910000 116364235 0 402718720 4.3835134506 3.1954789162 3.5877172947 1025 40.9600000000 0.8250917196 0.3389545547 0.8503463268 0.0494077441 1.0979170000 0.1119400000 0.0970140000 0.0376830000 0.4195630000 0.4298860000 116477507 0 402718720 4.3930330276 3.1980574131 3.5959606171 1026 41.0000000000 0.8238952160 0.3394272065 0.8503463268 0.0493842348 0.6153870000 0.1118160000 0.0794990000 0.0000010000 0.4204720000 0.0017910000 116672891 0 402718720 4.3990802765 3.1991183758 3.6012976170 1027 41.0400000000 0.8233962655 0.3398984519 0.8503463268 0.0493604683 0.6650460000 0.1078730000 0.0956020000 0.0377330000 0.4202270000 0.0017900000 116675667 0 402718720 4.4073400497 3.1978290081 3.6024451256 1028 41.0800000000 0.8224151134 0.3403678261 0.8503463268 0.0493368649 0.6501140000 0.1376150000 0.0877970000 0.0000010000 0.4210840000 0.0017890000 116678443 0 402718720 4.4182920456 3.2018251419 3.6109769344 1029 41.1200000000 0.8215687871 0.3408354655 0.8503463268 0.0493134107 1.0826310000 0.1117490000 0.0824750000 0.0382440000 0.4160820000 0.4322500000 116681219 0 402718720 4.4268612862 3.2018356323 3.6122925282 1030 41.1600000000 0.8212523460 0.3413018897 0.8503463268 0.0492902369 0.6015850000 0.1117110000 0.0643640000 0.0000010000 0.4218530000 0.0017990000 116683995 0 402718720 4.4348716736 3.2023091316 3.6163272858 1031 41.2000000000 0.8199270964 0.3417661236 0.8503463268 0.0492674284 0.6630930000 0.1117730000 0.0870050000 0.0379060000 0.4228060000 0.0017860000 116686771 0 402718720 4.4437384605 3.2023293972 3.6200287342 1032 41.2400000000 0.8192670941 0.3422288183 0.8503463268 0.0492447102 0.6222420000 0.1078330000 0.0862400000 0.0000000000 0.4245970000 0.0017330000 116689547 0 402718720 4.4522957802 3.2034764290 3.6253945827 1033 41.2800000000 0.8179799318 0.3426893712 0.8503463268 0.0492219207 1.0801900000 0.1079100000 0.0777110000 0.0366110000 0.4228940000 0.4332210000 116692323 0 402718720 4.4622087479 3.2057957649 3.6304955482 1034 41.3200000000 0.8168872595 0.3431479765 0.8503463268 0.0491998581 0.6258540000 0.1119870000 0.0871060000 0.0000010000 0.4231670000 0.0017380000 116695099 0 402718720 4.4722809792 3.2072634697 3.6355392933 1035 41.3600000000 0.8163080215 0.3436051360 0.8503463268 0.0491782974 0.6455550000 0.1119840000 0.0695730000 0.0369920000 0.4233570000 0.0017920000 116697875 0 402718720 4.4783811569 3.2082879543 3.6398224831 1036 41.4000000000 0.8157929182 0.3440609157 0.8503463268 0.0491551691 0.6445080000 0.1392230000 0.0817920000 0.0000000000 0.4198500000 0.0017900000 116700651 0 402718720 4.4848084450 3.2065131664 3.6429643631 1037 41.4400000000 0.8153451681 0.3445153846 0.8503463268 0.0491318910 1.0898870000 0.1250170000 0.0691260000 0.0363430000 0.4232220000 0.4343320000 116703427 0 402718720 4.4943561554 3.2064797878 3.6468322277 1038 41.4800000000 0.8137924671 0.3449674820 0.8503463268 0.0491085873 0.6288030000 0.1122120000 0.0889860000 0.0000000000 0.4239600000 0.0017890000 116706203 0 402718720 4.5036993027 3.2094261646 3.6514382362 1039 41.5200000000 0.8128283024 0.3454177811 0.8503463268 0.0490851918 0.6562050000 0.1082270000 0.0851400000 0.0356030000 0.4235780000 0.0017950000 116708979 0 402718720 4.5129609108 3.2118861675 3.6552741528 1040 41.5600000000 0.8116877079 0.3458661176 0.8503463268 0.0490618191 0.6182380000 0.1122480000 0.0773450000 0.0000010000 0.4249870000 0.0017940000 116711755 0 402718720 4.5203728676 3.2154810429 3.6593806744 1041 41.6000000000 0.8116791844 0.3463135845 0.8503463268 0.0490384816 1.0839720000 0.1083550000 0.0761750000 0.0351170000 0.4258590000 0.4366180000 116714531 0 402718720 4.5277166367 3.2155973911 3.6609244347 1042 41.6400000000 0.8104614019 0.3467590239 0.8503463268 0.0490157753 0.6032890000 0.1124390000 0.0602880000 0.0000010000 0.4269130000 0.0017890000 116717307 0 402718720 4.5378155708 3.2188198566 3.6666567326 1043 41.6800000000 0.8093040586 0.3472024995 0.8503463268 0.0489948342 0.6650990000 0.1124510000 0.0850800000 0.0360380000 0.4278700000 0.0017900000 116720083 0 402718720 4.5439844131 3.2210578918 3.6710066795 1044 41.7200000000 0.8083904386 0.3476442504 0.8503463268 0.0489811858 0.6553960000 0.1314410000 0.0909480000 0.0000010000 0.4293400000 0.0017900000 116722859 0 402718720 4.5576486588 3.2224385738 3.6755831242 1045 41.7600000000 0.8076447845 0.3480844423 0.8503463268 0.0489607133 1.1205330000 0.1251150000 0.0851820000 0.0361030000 0.4303300000 0.4419480000 116725635 0 402718720 4.5649175644 3.2234025002 3.6791865826 1046 41.8000000000 0.8062818050 0.3485224895 0.8503463268 0.0489388505 0.6072140000 0.1124250000 0.0597080000 0.0000000000 0.4314310000 0.0017930000 116728411 0 402718720 4.5702757835 3.2262346745 3.6857135296 1047 41.8400000000 0.8060352802 0.3489594644 0.8503463268 0.0489158160 0.6548400000 0.1250860000 0.0593550000 0.0354470000 0.4312800000 0.0017900000 116731187 0 402718720 4.5770592690 3.2263486385 3.6882932186 1048 41.8800000000 0.8049529195 0.3493945727 0.8503463268 0.0488929004 0.6507640000 0.1380350000 0.0798830000 0.0000010000 0.4291670000 0.0017920000 116733963 0 402718720 4.5850520134 3.2283909321 3.6946263313 1049 41.9200000000 0.8040941358 0.3498280327 0.8503463268 0.0488701049 1.0852230000 0.1124090000 0.0590720000 0.0360230000 0.4320560000 0.4438090000 116736739 0 402718720 4.5922017097 3.2294120789 3.6984832287 1050 41.9600000000 0.8036575317 0.3502602513 0.8503463268 0.0488469674 0.6250760000 0.1124250000 0.0752500000 0.0000010000 0.4337440000 0.0017880000 116739515 0 402718720 4.5981969833 3.2302308083 3.7010498047 1051 42.0000000000 0.8028687835 0.3506908969 0.8503463268 0.0488238930 0.6855790000 0.1124090000 0.0997290000 0.0361160000 0.4336720000 0.0017890000 116742291 0 402718720 4.6059756279 3.2302424908 3.7044384480 1052 42.0400000000 0.8023514152 0.3511202320 0.8503463268 0.0488009487 0.6381150000 0.1326980000 0.0668590000 0.0000010000 0.4348990000 0.0017860000 116745067 0 402718720 4.6127281189 3.2326226234 3.7107827663 1053 42.0800000000 0.8012879491 0.3515477417 0.8503463268 0.0487779091 1.1247120000 0.1083550000 0.1028030000 0.0358590000 0.4303690000 0.4454530000 116747843 0 402718720 4.6188158989 3.2349119186 3.7136869431 1054 42.1200000000 0.8008081317 0.3519739849 0.8503463268 0.0487550149 0.6308580000 0.1124300000 0.0664510000 0.0000000000 0.4473920000 0.0024630000 116750619 0 402718720 4.6250948906 3.2361495495 3.7191123962 1055 42.1600000000 0.7991928458 0.3523978891 0.8503463268 0.0487325086 0.6661690000 0.1161030000 0.0742870000 0.0355430000 0.4365370000 0.0017920000 116753395 0 402718720 4.6369113922 3.2377002239 3.7259874344 1056 42.2000000000 0.7987587452 0.3528205793 0.8503463268 0.0487095770 0.6435410000 0.1124490000 0.0901320000 0.0000000000 0.4372950000 0.0017870000 116756171 0 402718720 4.6433515549 3.2386403084 3.7311780453 1057 42.2400000000 0.7973828316 0.3532411680 0.8503463268 0.0486866506 1.1097680000 0.1125360000 0.0738630000 0.0362020000 0.4367650000 0.4485350000 116758947 0 402718720 4.6495113373 3.2403881550 3.7362828255 1058 42.2800000000 0.7962215543 0.3536598640 0.8503463268 0.0486639450 0.6412180000 0.1259180000 0.0737080000 0.0000000000 0.4379320000 0.0017870000 116761723 0 402718720 4.6557183266 3.2431614399 3.7437381744 1059 42.3200000000 0.7949897051 0.3540766061 0.8503463268 0.0486412870 0.6878720000 0.1124560000 0.0975470000 0.0360900000 0.4380800000 0.0017930000 116764499 0 402718720 4.6600351334 3.2465484142 3.7478311062 1060 42.3600000000 0.7945917845 0.3544921864 0.8503463268 0.0486187955 0.6287630000 0.1124410000 0.0733930000 0.0000010000 0.4392480000 0.0017880000 116767275 0 402718720 4.6646213531 3.2484202385 3.7539613247 1061 42.4000000000 0.7936791182 0.3549061232 0.8503463268 0.0485961012 1.1254100000 0.1083990000 0.0882810000 0.0358430000 0.4392280000 0.4515190000 116770051 0 402718720 4.6697654724 3.2504501343 3.7588195801 1062 42.4400000000 0.7929856777 0.3553186275 0.8503463268 0.0485736448 0.6907180000 0.1461230000 0.0902310000 0.0000010000 0.4506870000 0.0017910000 116772827 0 402718720 4.6746120453 3.2528645992 3.7655577660 1063 42.4800000000 0.7918128967 0.3557292524 0.8503463268 0.0485517349 0.6497220000 0.1125140000 0.0571270000 0.0360850000 0.4402960000 0.0017930000 116775603 0 402718720 4.6801934242 3.2550752163 3.7713875771 1064 42.5200000000 0.7908251882 0.3561381771 0.8503463268 0.0485299487 0.6545670000 0.1124950000 0.0969170000 0.0000010000 0.4414910000 0.0017920000 116778379 0 402718720 4.6851220131 3.2565670013 3.7766790390 1065 42.5600000000 0.7907344699 0.3565462488 0.8503463268 0.0485077244 1.1332620000 0.1124630000 0.0888250000 0.0361090000 0.4413580000 0.4526120000 116781155 0 402718720 4.6891264915 3.2581768036 3.7823181152 1066 42.6000000000 0.7893691063 0.3569522740 0.8503463268 0.0484852703 0.6470470000 0.1124810000 0.0886540000 0.0000010000 0.4422230000 0.0017920000 116783931 0 402718720 4.6936655045 3.2611382008 3.7878701687 1067 42.6400000000 0.7887685299 0.3573569752 0.8503463268 0.0484631095 0.6891480000 0.1341800000 0.0726070000 0.0360240000 0.4426170000 0.0017930000 116786707 0 402718720 4.6983056068 3.2626297474 3.7926926613 1068 42.6800000000 0.7881779671 0.3577603657 0.8503463268 0.0484406453 0.6563480000 0.1124520000 0.1008430000 0.0000000000 0.4393540000 0.0017910000 116789483 0 402718720 4.7008843422 3.2652595043 3.7985024452 1069 42.7200000000 0.7866888046 0.3581616084 0.8503463268 0.0484188329 1.1485760000 0.1125020000 0.1010240000 0.0362720000 0.4425110000 0.4543580000 116792259 0 402718720 4.7079062462 3.2696242332 3.8046004772 1070 42.7600000000 0.7850657701 0.3585605842 0.8503463268 0.0483983531 0.6431780000 0.1124820000 0.0814440000 0.0000010000 0.4456130000 0.0017430000 116795035 0 402718720 4.7133469582 3.2755262852 3.8109352589 1071 42.8000000000 0.7850986123 0.3589588457 0.8503463268 0.0483778681 0.6692200000 0.1125200000 0.0714930000 0.0355900000 0.4458960000 0.0017960000 116797811 0 402718720 4.7181048393 3.2787628174 3.8204901218 1072 42.8400000000 0.7858525515 0.3593570674 0.8503463268 0.0483553767 0.6185170000 0.1125570000 0.0562350000 0.0000010000 0.4460020000 0.0017950000 116800587 0 402718720 4.7227859497 3.2820744514 3.8290650845 1073 42.8800000000 0.7834842205 0.3597523397 0.8503463268 0.0483333115 1.1252490000 0.1125190000 0.0718150000 0.0359630000 0.4462730000 0.4567600000 116803363 0 402718720 4.7254509926 3.2847597599 3.8347930908 1074 42.9200000000 0.7823439240 0.3601458142 0.8503463268 0.0483111416 0.6348760000 0.1125630000 0.0716520000 0.0000000000 0.4469470000 0.0017990000 116806139 0 402718720 4.7313094139 3.2885863781 3.8414449692 1075 42.9600000000 0.7804196477 0.3605367666 0.8503463268 0.0482889075 0.6933050000 0.1125730000 0.0946940000 0.0352760000 0.4470290000 0.0018090000 116808915 0 402718720 4.7352805138 3.2927961349 3.8487019539 1076 43.0000000000 0.7794045806 0.3609260489 0.8503463268 0.0482671090 0.6586210000 0.1125820000 0.0945770000 0.0000000000 0.4477350000 0.0018050000 116811691 0 402718720 4.7392606735 3.2970061302 3.8539898396 1077 43.0400000000 0.7806370258 0.3613157527 0.8503463268 0.0482454912 1.1520710000 0.1126250000 0.0946560000 0.0358640000 0.4482900000 0.4587070000 116814467 0 402718720 4.7448897362 3.2989332676 3.8616721630 1078 43.0800000000 0.7798233032 0.3617039787 0.8503463268 0.0482239253 0.6607560000 0.1291740000 0.0794180000 0.0000010000 0.4484290000 0.0018080000 116817243 0 402718720 4.7479252815 3.3019475937 3.8670830727 1079 43.1200000000 0.7773225307 0.3620891673 0.8503463268 0.0482020554 0.6952410000 0.1125810000 0.0952400000 0.0351870000 0.4484580000 0.0018140000 116820019 0 402718720 4.7520880699 3.3052310944 3.8704280853 1080 43.1600000000 0.7778030038 0.3624740875 0.8503463268 0.0481800222 0.6597350000 0.1125600000 0.0949060000 0.0000010000 0.4485070000 0.0018110000 116822795 0 402718720 4.7574629784 3.3079855442 3.8813037872 1081 43.2000000000 0.7750506997 0.3628557495 0.8503463268 0.0481581176 1.1523930000 0.1125830000 0.0948400000 0.0357700000 0.4486930000 0.4585760000 116825571 0 402718720 4.7615947723 3.3107132912 3.8867969513 1082 43.2400000000 0.7766794562 0.3632382113 0.8503463268 0.0481359508 0.6492260000 0.1333280000 0.0635210000 0.0000010000 0.4486340000 0.0018180000 116828347 0 402718720 4.7637248039 3.3130748272 3.8966193199 1083 43.2800000000 0.7722980976 0.3636159213 0.8503463268 0.0481138185 0.6955550000 0.1126470000 0.0945610000 0.0360000000 0.4485900000 0.0018270000 116831123 0 402718720 4.7691359520 3.3171679974 3.9031190872 1084 43.3200000000 0.7735757232 0.3639941130 0.8503463268 0.0480917151 0.6090800000 0.1084730000 0.0473350000 0.0000000000 0.4495140000 0.0018270000 116833899 0 402718720 4.7747044563 3.3188850880 3.9151890278 1085 43.3600000000 0.7720283866 0.3643701815 0.8503463268 0.0480700662 1.1299110000 0.1125790000 0.0709660000 0.0356540000 0.4494390000 0.4593490000 116836675 0 402718720 4.7778415680 3.3231005669 3.9198358059 1086 43.4000000000 0.7706604004 0.3647442977 0.8503463268 0.0480479745 0.6450960000 0.1126510000 0.0786610000 0.0000010000 0.4500040000 0.0018270000 116839451 0 402718720 4.7821931839 3.3260865211 3.9259421825 1087 43.4400000000 0.7695532441 0.3651167070 0.8503463268 0.0480259090 0.6731210000 0.1126290000 0.0707720000 0.0355770000 0.4503630000 0.0018310000 116842227 0 402718720 4.7858667374 3.3289203644 3.9341070652 1088 43.4800000000 0.7683281898 0.3654873058 0.8503463268 0.0480039330 0.6486370000 0.1233110000 0.0707490000 0.0000000000 0.4508030000 0.0018350000 116845003 0 402718720 4.7886128426 3.3310496807 3.9397852421 1089 43.5200000000 0.7678834200 0.3658568156 0.8503463268 0.0479819206 1.1551480000 0.1126580000 0.0938440000 0.0355360000 0.4506980000 0.4604760000 116847779 0 402718720 4.7924180031 3.3325922489 3.9470405579 1090 43.5600000000 0.7672852278 0.3662250985 0.8503463268 0.0479599763 0.6478740000 0.1126570000 0.0804950000 0.0000010000 0.4509150000 0.0018400000 116850555 0 402718720 4.7965245247 3.3353164196 3.9566962719 1091 43.6000000000 0.7663884163 0.3665918843 0.8503463268 0.0479384591 0.6967340000 0.1126660000 0.0933540000 0.0355290000 0.4513770000 0.0018480000 116853331 0 402718720 4.8007421494 3.3377385139 3.9650232792 1092 43.6400000000 0.7644482851 0.3669562217 0.8503463268 0.0479168042 0.6542890000 0.1126820000 0.0856180000 0.0000010000 0.4521680000 0.0018460000 116856107 0 402718720 4.8036370277 3.3415558338 3.9709668159 1093 43.6800000000 0.7619905472 0.3673176437 0.8503463268 0.0478954348 1.1545240000 0.1089260000 0.0931150000 0.0357060000 0.4526340000 0.4621840000 116858883 0 402718720 4.8074436188 3.3451573849 3.9786708355 1094 43.7200000000 0.7593802214 0.3676760190 0.8503463268 0.0478738480 0.6629680000 0.1127010000 0.0929490000 0.0000010000 0.4534660000 0.0018520000 116861659 0 402718720 4.8092298508 3.3497169018 3.9840674400 1095 43.7600000000 0.7565605640 0.3680311648 0.8503463268 0.0478521830 0.6958330000 0.1127200000 0.0776570000 0.0354500000 0.4661530000 0.0018590000 116864435 0 402718720 4.8096737862 3.3525681496 3.9878230095 1096 43.8000000000 0.7536343336 0.3683829925 0.8503463268 0.0478304469 0.6516500000 0.1086300000 0.0845160000 0.0000000000 0.4546820000 0.0018620000 116867211 0 402718720 4.8127007484 3.3565065861 3.9931180477 1097 43.8400000000 0.7523190975 0.3687329798 0.8503463268 0.0478088357 1.1819620000 0.1299910000 0.0975590000 0.0354920000 0.4534420000 0.4635240000 116869987 0 402718720 4.8160686493 3.3599905968 4.0029439926 1098 43.8800000000 0.7495730519 0.3690798287 0.8503463268 0.0477887382 0.6737270000 0.1222810000 0.0932680000 0.0000010000 0.4543460000 0.0018700000 116872763 0 402718720 4.8205480576 3.3631782532 4.0118331909 1099 43.9200000000 0.7497486472 0.3694262061 0.8503463268 0.0477684492 0.7020670000 0.1127830000 0.0971560000 0.0354250000 0.4528520000 0.0018740000 116875539 0 402718720 4.8215322495 3.3655216694 4.0194354057 1100 43.9600000000 0.7495656610 0.3697717874 0.8503463268 0.0477470302 0.6486980000 0.1128080000 0.0772450000 0.0000010000 0.4548020000 0.0018760000 116878315 0 402718720 4.8215374947 3.3683595657 4.0271105766 1101 44.0000000000 0.7493008971 0.3701165005 0.8503463268 0.0477253874 1.1612950000 0.1127910000 0.0923190000 0.0353720000 0.4546860000 0.4641600000 116881091 0 402718720 4.8233804703 3.3709535599 4.0359745026 1102 44.0400000000 0.7450191379 0.3704567026 0.8503463268 0.0477038244 0.6769530000 0.1127490000 0.0921370000 0.0000000000 0.4672270000 0.0025990000 116883867 0 402718720 4.8246469498 3.3749032021 4.0419588089 1103 44.0800000000 0.7440551519 0.3707954138 0.8503463268 0.0476823312 0.7277810000 0.1459800000 0.0875130000 0.0353260000 0.4550970000 0.0018830000 116886643 0 402718720 4.8262505531 3.3774886131 4.0520830154 1104 44.1200000000 0.7405809164 0.3711303644 0.8503463268 0.0476608086 0.6634000000 0.1127990000 0.0918990000 0.0000010000 0.4548210000 0.0018910000 116889419 0 402718720 4.8268995285 3.3804333210 4.0607647896 1105 44.1600000000 0.7392563820 0.3714635101 0.8503463268 0.0476392982 1.1810900000 0.1339620000 0.0917060000 0.0351550000 0.4546390000 0.4636620000 116892195 0 402718720 4.8286480904 3.3832385540 4.0725536346 1106 44.2000000000 0.7369327545 0.3717939525 0.8503463268 0.0476179717 0.6627340000 0.1128160000 0.0915800000 0.0000000000 0.4544640000 0.0018960000 116894971 0 402718720 4.8308057785 3.3861987591 4.0830526352 1107 44.2400000000 0.7354220152 0.3721224331 0.8503463268 0.0475968159 0.6681830000 0.1127640000 0.0614560000 0.0350560000 0.4549140000 0.0019840000 116897747 0 402718720 4.8327531815 3.3893401623 4.0942497253 1108 44.2800000000 0.7309372425 0.3724462732 0.8503463268 0.0475757202 0.6616340000 0.1312170000 0.0724610000 0.0000010000 0.4540490000 0.0019100000 116900523 0 402718720 4.8350133896 3.3940393925 4.1031327248 1109 44.3200000000 0.7291226387 0.3727678930 0.8503463268 0.0475543522 1.1540010000 0.1127370000 0.0857160000 0.0350550000 0.4549230000 0.4635920000 116903299 0 402718720 4.8364129066 3.3970329762 4.1129240990 1110 44.3600000000 0.7248412967 0.3730850762 0.8503463268 0.0475330119 0.6677790000 0.1255680000 0.0837560000 0.0000010000 0.4545430000 0.0019100000 116906075 0 402718720 4.8378119469 3.4037086964 4.1215386391 1111 44.4000000000 0.7225255370 0.3733996041 0.8503463268 0.0475119677 0.6772240000 0.1086680000 0.0754570000 0.0342610000 0.4549590000 0.0018550000 116908851 0 402718720 4.8402042389 3.4069771767 4.1318845749 1112 44.4400000000 0.7192106843 0.3737105853 0.8503463268 0.0474908050 0.6391540000 0.1127430000 0.0689540000 0.0000010000 0.4535400000 0.0019160000 116911627 0 402718720 4.8433570862 3.4115862846 4.1429591179 1113 44.4800000000 0.7161622643 0.3740182687 0.8503463268 0.0474700106 1.1515060000 0.1401820000 0.0613630000 0.0348470000 0.4524860000 0.4606360000 116914403 0 402718720 4.8473753929 3.4168655872 4.1545395851 1114 44.5200000000 0.7131840587 0.3743227264 0.8503463268 0.0474492968 0.6633920000 0.1127470000 0.0956430000 0.0000010000 0.4510840000 0.0019180000 116917179 0 402718720 4.8490972519 3.4206857681 4.1618862152 1115 44.5600000000 0.7110510468 0.3746247249 0.8503463268 0.0474280913 0.6720570000 0.1127320000 0.0688460000 0.0348000000 0.4517310000 0.0019260000 116919955 0 402718720 4.8516345024 3.4245202541 4.1710662842 1116 44.6000000000 0.7069941163 0.3749225469 0.8503463268 0.0474069755 0.6326560000 0.1086350000 0.0697790000 0.0000000000 0.4503070000 0.0019270000 116922731 0 402718720 4.8566994667 3.4307563305 4.1818623543 1117 44.6400000000 0.7053599954 0.3752183727 0.8503463268 0.0473857745 1.1440210000 0.1126820000 0.0880700000 0.0348800000 0.4489130000 0.4574830000 116925507 0 402718720 4.8576345444 3.4351735115 4.1922326088 1118 44.6800000000 0.7023364305 0.3755109649 0.8503463268 0.0473646952 0.6440440000 0.1218990000 0.0693110000 0.0000010000 0.4488880000 0.0019320000 116928283 0 402718720 4.8606591225 3.4384124279 4.1999545097 1119 44.7200000000 0.7012012005 0.3758020196 0.8503463268 0.0473436369 0.6565000000 0.1085920000 0.0610180000 0.0342660000 0.4486470000 0.0019360000 116931059 0 402718720 4.8632917404 3.4414510727 4.2116422653 1120 44.7600000000 0.6976438165 0.3760893784 0.8503463268 0.0473226768 0.6329640000 0.1125830000 0.0695680000 0.0000000000 0.4468580000 0.0019330000 116933835 0 402718720 4.8659801483 3.4459896088 4.2218856812 1121 44.8000000000 0.6965177059 0.3763752199 0.8503463268 0.0473015911 1.1318160000 0.1327830000 0.0631520000 0.0345160000 0.4460490000 0.4533100000 116936611 0 402718720 4.8689107895 3.4494972229 4.2327237129 1122 44.8400000000 0.6935480237 0.3766579051 0.8503463268 0.0472805919 0.6466830000 0.1126120000 0.0844430000 0.0000010000 0.4456570000 0.0019300000 116939387 0 402718720 4.8708267212 3.4543516636 4.2411675453 1123 44.8800000000 0.6919038892 0.3769386228 0.8503463268 0.0472595943 0.6823400000 0.1367420000 0.0648760000 0.0344780000 0.4422530000 0.0019380000 116942163 0 402718720 4.8738660812 3.4593472481 4.2520637512 1124 44.9200000000 0.6892369986 0.3772164683 0.8503463268 0.0472387671 0.6206430000 0.1125370000 0.0618400000 0.0000010000 0.4422910000 0.0019280000 116944939 0 402718720 4.8769493103 3.4640319347 4.2617034912 1125 44.9600000000 0.6864737272 0.3774913637 0.8503463268 0.0472179188 1.0927540000 0.1125700000 0.0542420000 0.0343200000 0.4413960000 0.4481820000 116947715 0 402718720 4.8789334297 3.4698853493 4.2709178925 1126 45.0000000000 0.6842492223 0.3777637952 0.8503463268 0.0471970604 0.6481990000 0.1125910000 0.0918070000 0.0000010000 0.4398350000 0.0019250000 116950491 0 402718720 4.8812675476 3.4738433361 4.2796921730 1127 45.0400000000 0.6824551225 0.3780341513 0.8503463268 0.0471761389 0.6509980000 0.1125740000 0.0616190000 0.0335740000 0.4392330000 0.0019260000 116953267 0 402718720 4.8829455376 3.4765539169 4.2870602608 1128 45.0800000000 0.6803227663 0.3783021376 0.8503463268 0.0471553313 0.6274420000 0.1237930000 0.0617790000 0.0000010000 0.4379040000 0.0019230000 116956043 0 402718720 4.8854632378 3.4801397324 4.2962656021 1129 45.1200000000 0.6782047153 0.3785677732 0.8503463268 0.0471345033 1.1057710000 0.1328750000 0.0569090000 0.0340740000 0.4355810000 0.4442850000 116958819 0 402718720 4.8888883591 3.4841516018 4.3058400154 1130 45.1600000000 0.6764528155 0.3788313883 0.8503463268 0.0471136588 0.6246920000 0.1125640000 0.0726210000 0.0000010000 0.4355380000 0.0019230000 116961595 0 402718720 4.8916530609 3.4864418507 4.3138146400 1131 45.2000000000 0.6750304103 0.3790932796 0.8503463268 0.0470928371 0.6699980000 0.1124590000 0.0839190000 0.0339340000 0.4356980000 0.0019260000 116964371 0 402718720 4.8926820755 3.4887125492 4.3211297989 1132 45.2400000000 0.6734898090 0.3793533472 0.8503463268 0.0470720797 0.6053460000 0.1125130000 0.0542130000 0.0000010000 0.4346640000 0.0019220000 116967147 0 402718720 4.8955893517 3.4898161888 4.3281631470 1133 45.2800000000 0.6717854142 0.3796114514 0.8503463268 0.0470514321 1.0859650000 0.1124250000 0.0617530000 0.0339290000 0.4346080000 0.4412000000 116969923 0 402718720 4.8980793953 3.4916067123 4.3366165161 1134 45.3200000000 0.6696984768 0.3798672600 0.8503463268 0.0470307268 0.6042000000 0.1124820000 0.0543650000 0.0000010000 0.4333890000 0.0019230000 116972699 0 402718720 4.9020218849 3.4950518608 4.3447065353 1135 45.3600000000 0.6679440141 0.3801210721 0.8503463268 0.0470102329 0.6395820000 0.1124800000 0.0570100000 0.0338350000 0.4322730000 0.0019270000 116975475 0 402718720 4.9047842026 3.4972352982 4.3519730568 1136 45.4000000000 0.6652261019 0.3803720449 0.8503463268 0.0469895965 0.6383390000 0.1124510000 0.0713580000 0.0000010000 0.4496780000 0.0026810000 116978251 0 402718720 4.9088287354 3.5030035973 4.3591294289 1137 45.4400000000 0.6633790135 0.3806209516 0.8503463268 0.0469689641 1.0727330000 0.1124440000 0.0541950000 0.0331480000 0.4320480000 0.4388230000 116981027 0 402718720 4.9100432396 3.5072455406 4.3658976555 1138 45.4800000000 0.6614542007 0.3808677295 0.8503463268 0.0469483416 0.6056390000 0.1223810000 0.0491880000 0.0000010000 0.4300870000 0.0019200000 116983803 0 402718720 4.9120335579 3.5108187199 4.3717365265 1139 45.5200000000 0.6592742801 0.3811121602 0.8503463268 0.0469277691 0.6350590000 0.1123310000 0.0542450000 0.0336590000 0.4307930000 0.0019230000 116986579 0 402718720 4.9155559540 3.5156338215 4.3785939217 1140 45.5600000000 0.6576730013 0.3813547574 0.8503463268 0.0469073544 0.6008760000 0.1123400000 0.0543880000 0.0000010000 0.4299700000 0.0020980000 116989355 0 402718720 4.9158725739 3.5186805725 4.3827910423 1141 45.6000000000 0.6564466953 0.3815958547 0.8503463268 0.0468868086 1.0690800000 0.1123050000 0.0544050000 0.0335690000 0.4301240000 0.4366210000 116992131 0 402718720 4.9168558121 3.5208377838 4.3886885643 1142 45.6400000000 0.6541442275 0.3818345135 0.8503463268 0.0468664370 0.5998720000 0.1123520000 0.0547800000 0.0000000000 0.4287250000 0.0019250000 116994907 0 402718720 4.9209151268 3.5258119106 4.3958482742 1143 45.6800000000 0.6523870826 0.3820712174 0.8503463268 0.0468459658 0.6324150000 0.1122400000 0.0543770000 0.0328450000 0.4288870000 0.0019290000 116997683 0 402718720 4.9245305061 3.5278899670 4.4025325775 1144 45.7200000000 0.6507556438 0.3823060814 0.8503463268 0.0468255138 0.6109180000 0.1123300000 0.0546800000 0.0000010000 0.4388760000 0.0026820000 117000459 0 402718720 4.9272437096 3.5306036472 4.4090580940 1145 45.7600000000 0.6484087110 0.3825384855 0.8503463268 0.0468050944 1.1039740000 0.1428970000 0.0621080000 0.0333630000 0.4284150000 0.4351100000 117003235 0 402718720 4.9303135872 3.5349204540 4.4153766632 1146 45.8000000000 0.6466502547 0.3827689495 0.8503463268 0.0467846803 0.6062690000 0.1122910000 0.0623910000 0.0000000000 0.4275570000 0.0019210000 117006011 0 402718720 4.9341821671 3.5369620323 4.4224448204 1147 45.8400000000 0.6450461745 0.3829976131 0.8503463268 0.0467642930 0.6394620000 0.1122310000 0.0623450000 0.0326720000 0.4281830000 0.0019290000 117008787 0 402718720 4.9368271828 3.5394902229 4.4284367561 1148 45.8800000000 0.6427595615 0.3832238866 0.8503463268 0.0467439860 0.6226240000 0.1345850000 0.0578310000 0.0000010000 0.4261980000 0.0019240000 117011563 0 402718720 4.9388413429 3.5423934460 4.4349436760 1149 45.9200000000 0.6415380836 0.3834487032 0.8503463268 0.0467237011 1.0732400000 0.1121240000 0.0627550000 0.0331740000 0.4282850000 0.4347940000 117014339 0 402718720 4.9426155090 3.5440764427 4.4428858757 1150 45.9600000000 0.6388277411 0.3836707719 0.8503463268 0.0467034527 0.6045180000 0.1101430000 0.0629390000 0.0000010000 0.4274120000 0.0019220000 117017115 0 402718720 4.9441952705 3.5478916168 4.4498591423 1151 46.0000000000 0.6374496222 0.3838912574 0.8503463268 0.0466832040 0.6503680000 0.1121600000 0.0740830000 0.0331370000 0.4269310000 0.0019400000 117019891 0 402718720 4.9477391243 3.5492246151 4.4581441879 1152 46.0400000000 0.6357426047 0.3841098784 0.8503463268 0.0466630609 0.6140430000 0.1121580000 0.0708960000 0.0000010000 0.4269430000 0.0019260000 117022667 0 402718720 4.9494915009 3.5524594784 4.4679946899 1153 46.0800000000 0.6350449920 0.3843275151 0.8503463268 0.0466431413 1.0984600000 0.1082280000 0.0929270000 0.0321580000 0.4286390000 0.4344160000 117025443 0 402718720 4.9505805969 3.5529966354 4.4760866165 1154 46.1200000000 0.6344931722 0.3845442964 0.8503463268 0.0466229345 0.6069540000 0.1121460000 0.0636590000 0.0000010000 0.4271140000 0.0019300000 117028219 0 402718720 4.9509930611 3.5545191765 4.4844918251 1155 46.1600000000 0.6313255429 0.3847579598 0.8503463268 0.0466030173 0.6329840000 0.1121330000 0.0561440000 0.0322950000 0.4283820000 0.0019340000 117030995 0 402718720 4.9517865181 3.5618450642 4.4941644669 1156 46.2000000000 0.6305081248 0.3849705465 0.8503463268 0.0465829408 0.6217030000 0.1108430000 0.0797470000 0.0000020000 0.4270670000 0.0019300000 117033771 0 402718720 4.9538249969 3.5644867420 4.5036344528 1157 46.2400000000 0.6281294227 0.3851807097 0.8503463268 0.0465629873 1.1043760000 0.1120350000 0.0953210000 0.0327830000 0.4278500000 0.4342780000 117036547 0 402718720 4.9561977386 3.5697224140 4.5138859749 1158 46.2800000000 0.6254621148 0.3853882066 0.8503463268 0.0465431067 0.6203600000 0.1269740000 0.0641940000 0.0000010000 0.4251450000 0.0019300000 117039323 0 402718720 4.9591989517 3.5774598122 4.5339932442 1159 46.3200000000 0.6246979833 0.3855946861 0.8503463268 0.0465231173 0.6306020000 0.1120100000 0.0561540000 0.0326000000 0.4257920000 0.0019340000 117042099 0 402718720 4.9612751007 3.5803501606 4.5420713425 1160 46.3600000000 0.6232364178 0.3857995497 0.8503463268 0.0465030806 0.6333150000 0.1247470000 0.0800850000 0.0000000000 0.4244610000 0.0019270000 117044875 0 402718720 4.9613671303 3.5854613781 4.5514941216 1161 46.4000000000 0.6205729842 0.3860017663 0.8503463268 0.0464833656 1.0956010000 0.1119540000 0.0919820000 0.0324370000 0.4253460000 0.4317680000 117047651 0 402718720 4.9618444443 3.5925352573 4.5598807335 1162 46.4400000000 0.6192332506 0.3862024818 0.8503463268 0.0464634684 0.6484300000 0.1237270000 0.0965690000 0.0000010000 0.4240970000 0.0019230000 117050427 0 402718720 4.9635806084 3.5965707302 4.5695185661 1163 46.4800000000 0.6170018315 0.3864009336 0.8503463268 0.0464435387 0.6303580000 0.1118460000 0.0568840000 0.0324430000 0.4251180000 0.0019320000 117053203 0 402718720 4.9641275406 3.6005508900 4.5791602135 1164 46.5200000000 0.6149438024 0.3865972762 0.8503463268 0.0464238113 0.6054200000 0.1118240000 0.0653920000 0.0000010000 0.4241750000 0.0019240000 117055979 0 402718720 4.9653520584 3.6051781178 4.5876278877 1165 46.5600000000 0.6123833656 0.3867910840 0.8503463268 0.0464040894 1.0606940000 0.1118720000 0.0575060000 0.0322480000 0.4253010000 0.4316380000 117058755 0 402718720 4.9683456421 3.6124098301 4.5979323387 1166 46.6000000000 0.6104766726 0.3869829242 0.8503463268 0.0463842588 0.6052370000 0.1118320000 0.0654530000 0.0000000000 0.4239160000 0.0019230000 117061531 0 402718720 4.9683880806 3.6163141727 4.6077780724 1167 46.6400000000 0.6081541181 0.3871724453 0.8503463268 0.0463644797 0.6262270000 0.1079810000 0.0568450000 0.0319470000 0.4253950000 0.0019300000 117064307 0 402718720 4.9682302475 3.6220068932 4.6165208817 1168 46.6800000000 0.6058817506 0.3873596964 0.8503463268 0.0463446714 0.6174280000 0.1213720000 0.0687890000 0.0000010000 0.4232270000 0.0019260000 117067083 0 402718720 4.9690027237 3.6256806850 4.6261353493 1169 46.7200000000 0.6043623090 0.3875453274 0.8503463268 0.0463250179 1.0812620000 0.1118110000 0.0817020000 0.0318460000 0.4237590000 0.4300240000 117069859 0 402718720 4.9686770439 3.6291227341 4.6345453262 1170 46.7600000000 0.6010139585 0.3877277792 0.8503463268 0.0463055110 0.5971880000 0.1116390000 0.0586100000 0.0000010000 0.4229470000 0.0018580000 117072635 0 402718720 4.9673781395 3.6352300644 4.6426720619 1171 46.8000000000 0.5994617939 0.3879085939 0.8503463268 0.0462861706 0.6699320000 0.1116480000 0.0989100000 0.0319720000 0.4233460000 0.0019270000 117075411 0 402718720 4.9683575630 3.6410830021 4.6528811455 1172 46.8400000000 0.5961634517 0.3880862858 0.8503463268 0.0462665886 0.6031470000 0.1116060000 0.0665390000 0.0000010000 0.4209520000 0.0019200000 117078187 0 402718720 4.9671807289 3.6492788792 4.6623272896 1173 46.8800000000 0.5935980678 0.3882614877 0.8503463268 0.0462469405 1.0665930000 0.1114140000 0.0743270000 0.0318780000 0.4202740000 0.4265570000 117080963 0 402718720 4.9668164253 3.6532318592 4.6717734337 1174 46.9200000000 0.5906095505 0.3884338455 0.8503463268 0.0462274099 0.6324710000 0.1112980000 0.0991890000 0.0000000000 0.4179210000 0.0019240000 117083739 0 402718720 4.9673452377 3.6590292454 4.6808862686 1175 46.9600000000 0.5882161260 0.3886038729 0.8503463268 0.0462078226 0.6330950000 0.1208560000 0.0589150000 0.0317710000 0.4174620000 0.0019300000 117086515 0 402718720 4.9668240547 3.6620919704 4.6888380051 1176 47.0000000000 0.5820852518 0.3887683979 0.8503463268 0.0461885346 0.5838270000 0.1073180000 0.0579730000 0.0000000000 0.4144800000 0.0019200000 117089291 0 402718720 4.9662995338 3.6732261181 4.7065954208 1177 47.0400000000 0.5811131597 0.3889318174 0.8503463268 0.0461689103 1.0542050000 0.1110710000 0.0748130000 0.0315950000 0.4141430000 0.4204430000 117092067 0 402718720 4.9675331116 3.6763639450 4.7158918381 1178 47.0800000000 0.5788205862 0.3890930133 0.8503463268 0.0461493474 0.6218100000 0.1071920000 0.0983680000 0.0000010000 0.4121770000 0.0019200000 117094843 0 402718720 4.9687728882 3.6787211895 4.7253665924 1179 47.1200000000 0.5753912926 0.3892510271 0.8503463268 0.0461298497 0.6692290000 0.1070720000 0.0986040000 0.0315450000 0.4268750000 0.0026840000 117097619 0 402718720 4.9678888321 3.6833398342 4.7330985069 1180 47.1600000000 0.5658782125 0.3894007112 0.8503463268 0.0461128425 0.6371080000 0.1235140000 0.1003790000 0.0000010000 0.4091650000 0.0019220000 117100395 0 402718720 4.9681463242 3.6974267960 4.7399511337 1181 47.2000000000 0.5642998815 0.3895488053 0.8503463268 0.0460933736 1.0510960000 0.1107970000 0.0833750000 0.0313960000 0.4085500000 0.4148310000 117103171 0 402718720 4.9650287628 3.7001566887 4.7481379509 1182 47.2400000000 0.5372052193 0.3896737261 0.8503463268 0.0460870805 0.6043170000 0.1107460000 0.0839730000 0.0000000000 0.4055380000 0.0019260000 117105947 0 402718720 4.9632258415 3.7287740707 4.7447981834 1183 47.2800000000 0.5346939564 0.3897963130 0.8503463268 0.0460683100 0.6278940000 0.1108340000 0.0754680000 0.0312800000 0.4062120000 0.0019240000 117108723 0 402718720 4.9631714821 3.7323956490 4.7547655106 1184 47.3200000000 0.5331348181 0.3899173759 0.8503463268 0.0460491560 0.6128600000 0.1108560000 0.0926810000 0.0000000000 0.4052280000 0.0019250000 117111499 0 402718720 4.9673924446 3.7360038757 4.7674307823 1185 47.3600000000 0.5313168168 0.3900367003 0.8503463268 0.0460300596 1.0432240000 0.1108520000 0.0845050000 0.0311590000 0.4040860000 0.4104400000 117114275 0 402718720 4.9704227448 3.7363758087 4.7774100304 1186 47.4000000000 0.5298199058 0.3901545614 0.8503463268 0.0460111231 0.5863800000 0.1108840000 0.0682970000 0.0000010000 0.4031170000 0.0019240000 117117051 0 402718720 4.9703059196 3.7379744053 4.7864742279 1187 47.4400000000 0.5275365114 0.3902703002 0.8503463268 0.0459918475 0.6578770000 0.1108730000 0.1015500000 0.0310730000 0.4102580000 0.0019270000 117119827 0 402718720 4.9711680412 3.7423701286 4.7961506844 1188 47.4800000000 0.5265707970 0.3903850312 0.8503463268 0.0459725080 0.5861700000 0.1108840000 0.0679730000 0.0000010000 0.4032820000 0.0018600000 117122603 0 402718720 4.9703960419 3.7437012196 4.8049750328 1189 47.5200000000 0.5245647430 0.3904978821 0.8503463268 0.0459539486 1.0413900000 0.1108320000 0.0853000000 0.0309690000 0.4028600000 0.4092510000 117125379 0 402718720 4.9690990448 3.7455747128 4.8131427765 1190 47.5600000000 0.5224621892 0.3906087765 0.8503463268 0.0459352024 0.5849400000 0.1108870000 0.0685290000 0.0000010000 0.4014320000 0.0019180000 117128155 0 402718720 4.9700174332 3.7488908768 4.8230462074 1191 47.6000000000 0.5211095214 0.3907183489 0.8503463268 0.0459159809 0.6147010000 0.1108990000 0.0684360000 0.0301550000 0.4010760000 0.0019270000 117130931 0 402718720 4.9715495110 3.7496273518 4.8334722519 1192 47.6400000000 0.5202644467 0.3908270285 0.8503463268 0.0458967451 0.6123610000 0.1071750000 0.1012960000 0.0000010000 0.3998420000 0.0019150000 117133707 0 402718720 4.9756855965 3.7507848740 4.8441519737 1193 47.6800000000 0.5183793306 0.3909339458 0.8503463268 0.0458775443 1.0505880000 0.1108740000 0.1024780000 0.0306580000 0.3990100000 0.4053820000 117136483 0 402718720 4.9785642624 3.7526254654 4.8535218239 1194 47.7200000000 0.5172905326 0.3910397721 0.8503463268 0.0458584188 0.6114750000 0.1070710000 0.1026380000 0.0000000000 0.3976870000 0.0019220000 117139259 0 402718720 4.9769153595 3.7529046535 4.8620986938 1195 47.7600000000 0.5154022574 0.3911438411 0.8503463268 0.0458393716 0.6407390000 0.1220720000 0.0863610000 0.0305420000 0.3976200000 0.0019260000 117142035 0 402718720 4.9790029526 3.7559580803 4.8726692200 1196 47.8000000000 0.5135123134 0.3912461559 0.8503463268 0.0458203238 0.5802730000 0.1107200000 0.0697410000 0.0000010000 0.3956170000 0.0020000000 117144811 0 402718720 4.9835848808 3.7596054077 4.8838534355 1197 47.8400000000 0.5117120147 0.3913467957 0.8503463268 0.0458012974 1.0080980000 0.1106680000 0.0695720000 0.0297710000 0.3947660000 0.4011520000 117147587 0 402718720 4.9871973991 3.7622888088 4.8942861557 1198 47.8800000000 0.5101991296 0.3914460047 0.8503463268 0.0457822857 0.6115440000 0.1095560000 0.1045630000 0.0000010000 0.3933350000 0.0019180000 117150363 0 402718720 4.9894237518 3.7656762600 4.9048571587 1199 47.9200000000 0.5084974766 0.3915436289 0.8503463268 0.0457634431 0.6165490000 0.1106230000 0.0788410000 0.0303200000 0.3925680000 0.0019270000 117153139 0 402718720 4.9920439720 3.7682957649 4.9152741432 1200 47.9600000000 0.5089709163 0.3916414850 0.8503463268 0.0457445018 0.5955720000 0.1105390000 0.0882980000 0.0000010000 0.3926250000 0.0019250000 117155915 0 402718720 4.9922847748 3.7664086819 4.9237961769 1201 48.0000000000 0.5084696412 0.3917387607 0.8503463268 0.0457259180 1.0155730000 0.1106760000 0.0792060000 0.0295570000 0.3937990000 0.4001570000 117158691 0 402718720 4.9975705147 3.7684733868 4.9356560707 1202 48.0400000000 0.5072090626 0.3918348259 0.8503463268 0.0457075840 0.6007480000 0.1235720000 0.0801070000 0.0000000000 0.3929590000 0.0019250000 117161467 0 402718720 5.0029850006 3.7721223831 4.9482641220 1203 48.0800000000 0.5061593056 0.3919298587 0.8503463268 0.0456886375 0.6437150000 0.1106120000 0.1062200000 0.0301190000 0.3926210000 0.0019330000 117164243 0 402718720 5.0058021545 3.7740697861 4.9583497047 1204 48.1200000000 0.5051185489 0.3920238692 0.8503463268 0.0456706600 0.5784610000 0.1106750000 0.0718600000 0.0000000000 0.3918130000 0.0019290000 117167019 0 402718720 5.0089330673 3.7760064602 4.9688496590 1205 48.1600000000 0.5042561889 0.3921170081 0.8503463268 0.0456518192 1.0396640000 0.1369200000 0.0806590000 0.0299560000 0.3918000000 0.3981360000 117169795 0 402718720 5.0125012398 3.7791154385 4.9801526070 1206 48.2000000000 0.5025664568 0.3922085914 0.8503463268 0.0456329038 0.5952480000 0.1104820000 0.0899870000 0.0000000000 0.3906510000 0.0019260000 117172571 0 402718720 5.0167679787 3.7823400497 4.9901833534 1207 48.2400000000 0.5019152164 0.3922994833 0.8503463268 0.0456140128 0.6348950000 0.1105360000 0.0992880000 0.0299010000 0.3910320000 0.0019320000 117175347 0 402718720 5.0186233521 3.7829151154 4.9994087219 1208 48.2800000000 0.5021442175 0.3923904144 0.8503463268 0.0455951287 0.5962080000 0.1105480000 0.0910060000 0.0000010000 0.3905360000 0.0019280000 117178123 0 402718720 5.0222539902 3.7835531235 5.0100312233 1209 48.3200000000 0.5024496317 0.3924814477 0.8503463268 0.0455763184 1.0495000000 0.1068510000 0.1083960000 0.0297760000 0.3910200000 0.4109110000 117180899 0 402718720 5.0259857178 3.7851142883 5.0208973885 1210 48.3600000000 0.5031512976 0.3925729104 0.8503463268 0.0455575887 0.6015870000 0.1330410000 0.0739600000 0.0000010000 0.3904550000 0.0019220000 117183675 0 402718720 5.0264067650 3.7849547863 5.0305294991 1211 48.4000000000 0.5039637685 0.3926648929 0.8503463268 0.0455388549 0.6213010000 0.1105970000 0.0871750000 0.0297490000 0.3896490000 0.0019290000 117186451 0 402718720 5.0288701057 3.7844362259 5.0404520035 1212 48.4400000000 0.5031539798 0.3927560555 0.8503463268 0.0455205839 0.5962880000 0.1105710000 0.0940590000 0.0000000000 0.3875230000 0.0019200000 117189227 0 402718720 5.0347137451 3.7887628078 5.0609173775 1213 48.4800000000 0.5021514297 0.3928462413 0.8503463268 0.0455024431 0.9961970000 0.1105340000 0.0746430000 0.0295070000 0.3865270000 0.3927640000 117192003 0 402718720 5.0347456932 3.7912993431 5.0687942505 1214 48.5200000000 0.5014768243 0.3929357229 0.8503463268 0.0454841841 0.5924960000 0.1104410000 0.0933230000 0.0000000000 0.3846030000 0.0019230000 117194779 0 402718720 5.0344877243 3.7924218178 5.0764279366 1215 48.5600000000 0.5010594726 0.3930247136 0.8503463268 0.0454658606 0.6539880000 0.1215880000 0.1151370000 0.0294300000 0.3836700000 0.0019250000 117197555 0 402718720 5.0341610909 3.7933812141 5.0843610764 1216 48.6000000000 0.4997414649 0.3931124741 0.8503463268 0.0454487210 0.5913420000 0.1230480000 0.0846590000 0.0000000000 0.3794990000 0.0019220000 117200331 0 402718720 5.0355482101 3.7974534035 5.0996761322 1217 48.6400000000 0.4990319014 0.3931995073 0.8503463268 0.0454300536 0.9767740000 0.1066850000 0.0769900000 0.0291070000 0.3775840000 0.3841820000 117203107 0 402718720 5.0369300842 3.7994215488 5.1074137688 1218 48.6800000000 0.4982198179 0.3932857309 0.8503463268 0.0454118291 0.5862670000 0.1283420000 0.0789170000 0.0000010000 0.3748670000 0.0019140000 117205883 0 402718720 5.0387196541 3.8016326427 5.1152501106 1219 48.7200000000 0.4977824986 0.3933714542 0.8503463268 0.0453936336 0.6340790000 0.1100940000 0.1175150000 0.0284720000 0.3738310000 0.0019220000 117208659 0 402718720 5.0401816368 3.8017022610 5.1218047142 1220 48.7600000000 0.4967296124 0.3934561740 0.8503463268 0.0453754953 0.6123600000 0.1228570000 0.1126190000 0.0000010000 0.3727480000 0.0019100000 117211435 0 402718720 5.0398483276 3.8044321537 5.1287565231 1221 48.8000000000 0.4958404899 0.3935400269 0.8503463268 0.0453572380 0.9846670000 0.1100150000 0.0936150000 0.0284520000 0.3720690000 0.3782570000 117214211 0 402718720 5.0394020081 3.8066499233 5.1359529495 1222 48.8400000000 0.4950234890 0.3936230739 0.8503463268 0.0453388588 0.5588700000 0.1099660000 0.0764160000 0.0000010000 0.3681420000 0.0020100000 117216987 0 402718720 5.0379862785 3.8098213673 5.1428227425 1223 48.8800000000 0.4946494102 0.3937056792 0.8503463268 0.0453203462 0.5874100000 0.1099650000 0.0751200000 0.0282680000 0.3698810000 0.0019230000 117219763 0 402718720 5.0382471085 3.8107767105 5.1510095596 1224 48.9200000000 0.4941094816 0.3937877085 0.8503463268 0.0453020918 0.6004610000 0.1407090000 0.0882560000 0.0000000000 0.3673630000 0.0019170000 117222539 0 402718720 5.0391502380 3.8116848469 5.1583242416 1225 48.9600000000 0.4934188128 0.3938690400 0.8503463268 0.0452839162 0.9987240000 0.1184450000 0.1123960000 0.0281210000 0.3656740000 0.3718540000 117225315 0 402718720 5.0382738113 3.8129434586 5.1664438248 1226 49.0000000000 0.4924681187 0.3939494634 0.8503463268 0.0452658023 0.5898780000 0.1097900000 0.1125850000 0.0000010000 0.3633670000 0.0019140000 117228091 0 402718720 5.0365810394 3.8148205280 5.1743535995 1227 49.0400000000 0.4915808439 0.3940290326 0.8503463268 0.0452474747 0.6211190000 0.1097000000 0.1163070000 0.0287420000 0.3622030000 0.0019160000 117230867 0 402718720 5.0349359512 3.8167471886 5.1821560860 1228 49.0800000000 0.4904844165 0.3941075793 0.8503463268 0.0452291695 0.5897250000 0.1096340000 0.1178690000 0.0000010000 0.3580540000 0.0019130000 117233643 0 402718720 5.0333085060 3.8198385239 5.1901516914 1229 49.1200000000 0.4892843962 0.3941850218 0.8503463268 0.0452109804 0.9757260000 0.1095600000 0.1120990000 0.0286750000 0.3584670000 0.3646390000 117236419 0 402718720 5.0313291550 3.8223500252 5.1984086037 1230 49.1600000000 0.4883054793 0.3942615425 0.8503463268 0.0451930725 0.5481590000 0.1203200000 0.0693310000 0.0000010000 0.3543610000 0.0018980000 117239195 0 402718720 5.0300035477 3.8242280483 5.2078371048 1231 49.2000000000 0.4871915579 0.3943370340 0.8503463268 0.0451749254 0.6046540000 0.1095080000 0.1080900000 0.0285770000 0.3543020000 0.0019210000 117241971 0 402718720 5.0289893150 3.8264334202 5.2158818245 1232 49.2400000000 0.4861444831 0.3944115530 0.8503463268 0.0451568833 0.5518840000 0.1094140000 0.0753420000 0.0000000000 0.3619130000 0.0026690000 117244747 0 402718720 5.0270700455 3.8283436298 5.2238130569 1233 49.2800000000 0.4852994978 0.3944852658 0.8503463268 0.0451386848 0.9749560000 0.1401740000 0.0891500000 0.0325540000 0.3527150000 0.3580910000 117247523 0 402718720 5.0229940414 3.8300473690 5.2310609818 1234 49.3200000000 0.4845055044 0.3945582158 0.8503463268 0.0451204136 0.5487000000 0.1093870000 0.0846010000 0.0000000000 0.3505330000 0.0019060000 117250299 0 402718720 5.0198292732 3.8313920498 5.2397665977 1235 49.3600000000 0.4835991859 0.3946303137 0.8503463268 0.0451024177 0.6022390000 0.1404630000 0.0789890000 0.0284510000 0.3502120000 0.0018520000 117253075 0 402718720 5.0178747177 3.8331346512 5.2482309341 1236 49.4000000000 0.4828144312 0.3947016601 0.8503463268 0.0450841966 0.5752900000 0.1093860000 0.1128200000 0.0000000000 0.3489010000 0.0019000000 117255851 0 402718720 5.0151948929 3.8346533775 5.2561073303 1237 49.4400000000 0.4818326533 0.3947720975 0.8503463268 0.0450661388 0.9463030000 0.1093600000 0.1038200000 0.0282910000 0.3482230000 0.3543300000 117258627 0 402718720 5.0148029327 3.8367967606 5.2656636238 1238 49.4800000000 0.4806989729 0.3948415053 0.8503463268 0.0450479816 0.5711270000 0.1065800000 0.1133030000 0.0000010000 0.3470700000 0.0019100000 117261403 0 402718720 5.0135626793 3.8387684822 5.2734165192 1239 49.5200000000 0.4793841541 0.3949097399 0.8503463268 0.0450298786 0.6022290000 0.1093850000 0.1132090000 0.0280920000 0.3473320000 0.0019120000 117264179 0 402718720 5.0114922523 3.8424110413 5.2813620567 1240 49.5600000000 0.4776595235 0.3949764736 0.8503463268 0.0450117860 0.5282290000 0.1092820000 0.0695770000 0.0000010000 0.3451880000 0.0019110000 117266955 0 402718720 5.0104398727 3.8467686176 5.2902259827 1241 49.6000000000 0.4763606489 0.3950420531 0.8503463268 0.0449936848 0.9189470000 0.1093010000 0.0850350000 0.0274390000 0.3444350000 0.3504650000 117269731 0 402718720 5.0075426102 3.8499491215 5.2972178459 1242 49.6400000000 0.4753569663 0.3951067189 0.8503463268 0.0449757328 0.5459250000 0.1225820000 0.0761140000 0.0000000000 0.3430450000 0.0019060000 117272507 0 402718720 5.0063490868 3.8521401882 5.3036575317 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 11:24:52 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188253 0.0606188253 0.0606188253 -nan 0.7549850000 0.1198240000 0.0216900000 0.0612900000 0.0000020000 0.5519660000 106585814 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 1305031229.5644419193 0.0642096773 0.0624142513 0.0642096773 0.1658525169 0.2058420000 0.1212380000 0.0197630000 0.0612150000 0.0000000000 0.0035690000 114065147 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 1305031229.5966169834 0.0662607327 0.0636964117 0.0662607327 0.1252029927 0.2165350000 0.1315220000 0.0195430000 0.0618620000 0.0000010000 0.0035490000 114069211 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 1305031229.6287899017 0.0688454211 0.0649836641 0.0688454211 0.1129913759 0.7496720000 0.1401780000 0.0199670000 0.0612500000 0.5245260000 0.0036790000 114073227 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 1305031229.6646571159 0.0659985021 0.0651866317 0.0688454211 0.1146822455 1.3221540000 0.1226650000 0.1624140000 0.0624320000 0.4775560000 0.4970230000 114077339 0 402718720 3.9731428623 4.0052924156 4.0138831139 6 1305031229.6968429089 0.0563633256 0.0637160807 0.0688454211 0.1026612804 0.4846420000 0.0744060000 0.0798780000 0.0000000000 0.3285560000 0.0017400000 114081867 0 402718720 3.9885785580 3.9999742508 4.0209751129 7 1305031229.7290771008 0.0504621193 0.0618226576 0.0688454211 0.0944322097 0.4776670000 0.0747200000 0.0805500000 0.0305580000 0.2900240000 0.0017530000 114085483 0 402718720 3.9916830063 4.0025734901 4.0272126198 8 1305031229.7648689747 0.0483604819 0.0601398856 0.0688454211 0.0875845650 0.4243740000 0.0755630000 0.0484050000 0.0000000000 0.2985910000 0.0017520000 114089267 0 402718720 3.9982976913 3.9969143867 4.0331096649 9 1305031229.7969229221 0.0485941134 0.0588570221 0.0688454211 0.0820243503 0.7288580000 0.1173810000 0.0481980000 0.0307710000 0.2590420000 0.2733890000 114093707 0 402718720 3.9983580112 3.9944632053 4.0363550186 10 1305031229.8256299496 0.0431735180 0.0572886717 0.0688454211 0.0773873784 0.4212780000 0.0950080000 0.0532160000 0.0000010000 0.2711200000 0.0018520000 114098867 0 402718720 4.0013957024 3.9980599880 4.0419950485 11 1305031229.8630619049 0.0423474684 0.0559303805 0.0688454211 0.0737733488 0.4326570000 0.0786680000 0.0840490000 0.0308680000 0.2372300000 0.0017720000 114102763 0 402718720 4.0051603317 3.9987072945 4.0450425148 12 1305031229.8969380856 0.0430173129 0.0548542915 0.0688454211 0.0708072783 0.3899320000 0.0780610000 0.0596570000 0.0000000000 0.2503640000 0.0017760000 114106435 0 402718720 4.0110363960 4.0005564690 4.0481514931 13 1305031229.9262549877 0.0434668511 0.0539783345 0.0688454211 0.0678480058 0.6699250000 0.0799720000 0.0871640000 0.0314180000 0.2262840000 0.2450110000 114110051 0 402718720 4.0163755417 4.0022850037 4.0533413887 14 1305031229.9662408829 0.0455426462 0.0533757854 0.0688454211 0.0652222451 0.4077710000 0.0780870000 0.0782430000 0.0000000000 0.2495930000 0.0017720000 114113947 0 402718720 4.0200061798 4.0031862259 4.0585093498 15 1305031229.9979310036 0.0476508923 0.0529941258 0.0688454211 0.0632082101 0.3758650000 0.0795960000 0.0452210000 0.0316790000 0.2175260000 0.0017670000 114117563 0 402718720 4.0225749016 4.0032062531 4.0627470016 16 1305031230.0300021172 0.0504597872 0.0528357297 0.0688454211 0.0611115681 0.4007980000 0.0786760000 0.0860000000 0.0000010000 0.2342880000 0.0017540000 114121235 0 402718720 4.0251259804 4.0037541389 4.0669641495 17 1305031230.0656960011 0.0551584736 0.0529723617 0.0688454211 0.0592800693 0.6242720000 0.0911790000 0.0565920000 0.0318360000 0.2132910000 0.2312900000 114126555 0 402718720 4.0274100304 4.0023450851 4.0702166557 18 1305031230.0982739925 0.0570044406 0.0531963660 0.0688454211 0.0575957224 0.3658990000 0.0786340000 0.0615840000 0.0000010000 0.2237360000 0.0018530000 114133427 0 402718720 4.0272107124 4.0021748543 4.0725789070 19 1305031230.1299350262 0.0595816225 0.0535324322 0.0688454211 0.0559920050 0.4023100000 0.0783220000 0.0821320000 0.0319880000 0.2079240000 0.0018500000 114137099 0 402718720 4.0281023979 4.0029788017 4.0757107735 20 1305031230.1657800674 0.0632345825 0.0540175397 0.0688454211 0.0545691395 0.3724670000 0.0923470000 0.0587040000 0.0000010000 0.2195200000 0.0018090000 114140883 0 402718720 4.0281786919 4.0023169518 4.0780658722 21 1305031230.1977820396 0.0653965548 0.0545593976 0.0688454211 0.0532405522 0.6327140000 0.0795040000 0.0860220000 0.0320700000 0.2086750000 0.2263570000 114144555 0 402718720 4.0273065567 4.0007491112 4.0797414780 22 1305031230.2298529148 0.0664541200 0.0551000668 0.0688454211 0.0520189167 0.4220830000 0.1120750000 0.0918100000 0.0000010000 0.2162160000 0.0018660000 114148227 0 402718720 4.0250487328 4.0002617836 4.0808320045 23 1305031230.2655899525 0.0660247803 0.0555750543 0.0688454211 0.0509031084 0.3771470000 0.0794830000 0.0511540000 0.0322120000 0.2124110000 0.0017940000 114152011 0 402718720 4.0201339722 3.9984073639 4.0805301666 24 1305031230.2979929447 0.0668007433 0.0560427913 0.0688454211 0.0497969449 0.3654200000 0.0790290000 0.0618840000 0.0000010000 0.2226200000 0.0017950000 114155683 0 402718720 4.0179405212 3.9989321232 4.0822286606 25 1305031230.3351120949 0.0693960413 0.0565769213 0.0693960413 0.0487940736 0.6251510000 0.0779430000 0.0506340000 0.0321020000 0.2217480000 0.2426240000 114159523 0 402718720 4.0160169601 3.9960601330 4.0837168694 26 1305031230.3656799793 0.0678694472 0.0570112493 0.0693960413 0.0478352673 0.4303440000 0.1009880000 0.0984980000 0.0000010000 0.2289410000 0.0018200000 114163139 0 402718720 4.0121064186 3.9971234798 4.0844988823 27 1305031230.3973290920 0.0668442324 0.0573754338 0.0693960413 0.0469088970 0.4155430000 0.0935770000 0.0587070000 0.0323100000 0.2290260000 0.0018220000 114166867 0 402718720 4.0075702667 3.9959928989 4.0858283043 28 1305031230.4368140697 0.0693910494 0.0578045629 0.0693960413 0.0465535954 0.4090350000 0.0796070000 0.0891930000 0.0000000000 0.2383020000 0.0018350000 114170707 0 402718720 4.0056290627 3.9953072071 4.0883073807 29 1305031230.4653120041 0.0682877004 0.0581660504 0.0693960413 0.0458265882 0.6952270000 0.0791170000 0.0859790000 0.0321080000 0.2410640000 0.2568600000 114174267 0 402718720 3.9983274937 3.9911072254 4.0866594315 30 1305031230.4972999096 0.0652221441 0.0584012536 0.0693960413 0.0450806140 0.4274640000 0.0779790000 0.0923310000 0.0000010000 0.2551970000 0.0018560000 114177995 0 402718720 3.9887623787 3.9884991646 4.0839571953 31 1305031230.5301918983 0.0636972860 0.0585720933 0.0693960413 0.0443614479 0.4508760000 0.0794230000 0.0775510000 0.0322910000 0.2596660000 0.0018440000 114181611 0 402718720 3.9802725315 3.9850406647 4.0815019608 32 1305031230.5661149025 0.0645725727 0.0587596083 0.0693960413 0.0440506128 0.4196030000 0.0883010000 0.0549890000 0.0000000000 0.2743580000 0.0018480000 114185451 0 402718720 3.9731605053 3.9821474552 4.0819492340 33 1305031230.5988430977 0.0627241656 0.0588797464 0.0693960413 0.0433950134 0.7692960000 0.0778540000 0.0841430000 0.0317050000 0.2815340000 0.2939530000 114192195 0 402718720 3.9628067017 3.9789595604 4.0794944763 34 1305031230.6319139004 0.0611348078 0.0589460717 0.0693960413 0.0428637910 0.4730680000 0.1046480000 0.0722600000 0.0000000000 0.2942210000 0.0018260000 114202323 0 402718720 3.9490034580 3.9742074013 4.0775780678 35 1305031230.6660470963 0.0583774559 0.0589298256 0.0693960413 0.0423817478 0.4741840000 0.0761840000 0.0629640000 0.0320820000 0.3010420000 0.0018050000 114206051 0 402718720 3.9365048409 3.9741475582 4.0758085251 36 1305031230.6979451180 0.0597653799 0.0589530354 0.0693960413 0.0418331146 0.4684900000 0.0755940000 0.0772060000 0.0000000000 0.3137790000 0.0018050000 114209667 0 402718720 3.9269452095 3.9702455997 4.0760126114 37 1305031230.7336409092 0.0617954507 0.0590298575 0.0693960413 0.0414694411 0.8705060000 0.0750150000 0.0817410000 0.0387100000 0.3407570000 0.3341720000 114213395 0 402718720 3.9188454151 3.9673454762 4.0739350319 38 1305031230.7659239769 0.0654406846 0.0591985634 0.0693960413 0.0409306499 0.5211850000 0.1007150000 0.0867210000 0.0000000000 0.3318340000 0.0017950000 114217123 0 402718720 3.9110875130 3.9628832340 4.0717010498 39 1305031230.7973229885 0.0700017884 0.0594755692 0.0700017884 0.0404521559 0.5194180000 0.0733040000 0.0704210000 0.0319200000 0.3418730000 0.0017870000 114220795 0 402718720 3.9019260406 3.9574902058 4.0684852600 40 1305031230.8317570686 0.0753399357 0.0598721784 0.0753399357 0.0399649438 0.4940930000 0.0715490000 0.0664610000 0.0000010000 0.3541780000 0.0017910000 114224523 0 402718720 3.8932869434 3.9517424107 4.0669732094 41 1305031230.8655419350 0.0775204226 0.0603026233 0.0775204226 0.0396860748 0.9004330000 0.0722100000 0.0590620000 0.0319440000 0.3642930000 0.3728060000 114228195 0 402718720 3.8833835125 3.9490649700 4.0669836998 42 1305031230.8973939419 0.0850835443 0.0608926453 0.0850835443 0.0392766750 0.5292950000 0.0698500000 0.0785020000 0.0000010000 0.3790230000 0.0018050000 114231923 0 402718720 3.8754906654 3.9414772987 4.0733103752 43 1305031230.9373099804 0.1036899388 0.0618879312 0.1036899388 0.0394564025 0.5749500000 0.0698450000 0.0821550000 0.0320100000 0.3890230000 0.0017990000 114235763 0 402718720 3.8576798439 3.9270317554 4.0863752365 44 1305031230.9650349617 0.1126570180 0.0630417740 0.1126570180 0.0396331009 0.5660470000 0.0917960000 0.0754800000 0.0000010000 0.3968190000 0.0018260000 114239323 0 402718720 3.8492517471 3.9250791073 4.1066870689 45 1305031230.9971239567 0.1230858117 0.0643760860 0.1230858117 0.0395538091 0.9884260000 0.0686340000 0.0762720000 0.0315640000 0.3986050000 0.4132170000 114243051 0 402718720 3.8426215649 3.9233472347 4.1250786781 46 1305031231.0367500782 0.1287320852 0.0657751295 0.1287320852 0.0392468978 0.6094220000 0.0832760000 0.1004310000 0.0000010000 0.4238050000 0.0017860000 114246891 0 402718720 3.8392167091 3.9225435257 4.1341891289 47 1305031231.0644741058 0.1268777847 0.0670751860 0.1287320852 0.0388387203 0.5780000000 0.0642740000 0.0787470000 0.0313540000 0.4017100000 0.0017870000 114250395 0 402718720 3.8372349739 3.9250528812 4.1334557533 48 1305031231.0967879295 0.1188802272 0.0681544576 0.1287320852 0.0384417861 0.5436440000 0.0658090000 0.0751240000 0.0000010000 0.4008020000 0.0017830000 114254123 0 402718720 3.8389544487 3.9322116375 4.1301860809 49 1305031231.1347110271 0.1252817214 0.0693203202 0.1287320852 0.0380516096 0.9715190000 0.0654170000 0.0644710000 0.0321130000 0.4000520000 0.4093350000 114257907 0 402718720 3.8390495777 3.9264283180 4.1354303360 50 1305031231.1652760506 0.1261962354 0.0704578385 0.1287320852 0.0377122753 0.5460630000 0.0669770000 0.0783800000 0.0000010000 0.3987800000 0.0017930000 114261579 0 402718720 3.8398590088 3.9260206223 4.1374444962 51 1305031231.1977710724 0.1144091487 0.0713196289 0.1287320852 0.0374337448 0.5577710000 0.0678390000 0.0599470000 0.0319060000 0.3961290000 0.0018180000 114265307 0 402718720 3.8442761898 3.9357490540 4.1323261261 52 1305031231.2344679832 0.1070481837 0.0720067165 0.1287320852 0.0376470869 0.5410950000 0.0705920000 0.0807770000 0.0000010000 0.3877830000 0.0018100000 114269091 0 402718720 3.8509349823 3.9358294010 4.1209311485 53 1305031231.2656350136 0.0896527171 0.0723396599 0.1287320852 0.0374550628 0.9793530000 0.1001910000 0.0842250000 0.0318670000 0.3771520000 0.3857770000 114272707 0 402718720 3.8587925434 3.9474232197 4.1027674675 54 1305031231.2978610992 0.0761162415 0.0724095966 0.1287320852 0.0374344698 0.5179710000 0.0732270000 0.0803980000 0.0000010000 0.3624110000 0.0017990000 114276435 0 402718720 3.8620061874 3.9634418488 4.0747075081 55 1305031231.3351519108 0.0692430511 0.0723520230 0.1287320852 0.0373614807 0.5406140000 0.0735640000 0.0862770000 0.0318150000 0.3470200000 0.0017980000 114280219 0 402718720 3.8728494644 3.9747853279 4.0629620552 56 1305031231.3650770187 0.0627845973 0.0721811761 0.1287320852 0.0371171109 0.5031460000 0.0882000000 0.0820100000 0.0000010000 0.3309990000 0.0017920000 114283835 0 402718720 3.8816637993 3.9860460758 4.0579943657 57 1305031231.3973300457 0.0549503267 0.0718788805 0.1287320852 0.0368289985 0.8107430000 0.0752800000 0.0632460000 0.0318160000 0.3153850000 0.3248730000 114287563 0 402718720 3.8939781189 3.9880735874 4.0661745071 58 1305031231.4368579388 0.0492206663 0.0714882217 0.1287320852 0.0365562138 0.4990320000 0.1080750000 0.0904970000 0.0000010000 0.2985180000 0.0017910000 114291403 0 402718720 3.9071052074 3.9883763790 4.0771036148 59 1305031231.4649889469 0.0474568456 0.0710809102 0.1287320852 0.0363023158 0.4813940000 0.0773710000 0.0873520000 0.0313890000 0.2833330000 0.0018040000 114294963 0 402718720 3.9147570133 3.9901704788 4.0795464516 60 1305031231.4992439747 0.0418131463 0.0705931141 0.1287320852 0.0360880520 0.4516220000 0.0783240000 0.0939290000 0.0000000000 0.2774140000 0.0018080000 114298635 0 402718720 3.9260337353 3.9977762699 4.0803112984 61 1305031231.5331959724 0.0396660976 0.0700861139 0.1287320852 0.0358448233 0.7506810000 0.0922480000 0.0888240000 0.0320410000 0.2640500000 0.2733650000 114302475 0 402718720 3.9337244034 4.0011420250 4.0835018158 62 1305031231.5650680065 0.0378991328 0.0695669690 0.1287320852 0.0356285408 0.4317020000 0.0797780000 0.0886040000 0.0000000000 0.2613940000 0.0017730000 114306091 0 402718720 3.9431242943 4.0042195320 4.0895094872 63 1305031231.6013169289 0.0356009118 0.0690278252 0.1287320852 0.0353482029 0.4757250000 0.1060170000 0.0893130000 0.0320860000 0.2463610000 0.0017900000 114309875 0 402718720 3.9476096630 4.0091195107 4.0908470154 64 1305031231.6331589222 0.0349087715 0.0684947150 0.1287320852 0.0351350976 0.4128150000 0.0803610000 0.0894060000 0.0000000000 0.2410980000 0.0017890000 114313603 0 402718720 3.9524562359 4.0122566223 4.0923275948 65 1305031231.6650550365 0.0355562493 0.0679879694 0.1287320852 0.0348670700 0.6696420000 0.0800290000 0.0864770000 0.0321950000 0.2306880000 0.2400950000 114323363 0 402718720 3.9610505104 4.0157055855 4.0960597992 66 1305031231.7035079002 0.0358012505 0.0675002918 0.1287320852 0.0347945289 0.3948920000 0.0799810000 0.0899230000 0.0000000000 0.2229860000 0.0018410000 114340059 0 402718720 3.9645161629 4.0162410736 4.0987977982 67 1305031231.7339379787 0.0358385108 0.0670277279 0.1287320852 0.0346325420 0.3879850000 0.0799140000 0.0602450000 0.0316010000 0.2142330000 0.0018260000 114343619 0 402718720 3.9677579403 4.0173344612 4.0998659134 68 1305031231.7655088902 0.0360293053 0.0665718688 0.1287320852 0.0344285492 0.3990790000 0.0999660000 0.0894450000 0.0000010000 0.2076810000 0.0018150000 114347291 0 402718720 3.9716196060 4.0189461708 4.1014842987 69 1305031231.8011910915 0.0391952097 0.0661751056 0.1287320852 0.0342010689 0.5752910000 0.0802040000 0.0710720000 0.0321140000 0.1913020000 0.2004360000 114351075 0 402718720 3.9765796661 4.0176439285 4.1017713547 70 1305031231.8332920074 0.0400782488 0.0658022934 0.1287320852 0.0341464826 0.3339990000 0.0798390000 0.0671570000 0.0000000000 0.1850480000 0.0017830000 114354747 0 402718720 3.9782562256 4.0165972710 4.0989818573 71 1305031231.8649590015 0.0408231094 0.0654504739 0.1287320852 0.0339427774 0.3790440000 0.0799140000 0.0941160000 0.0318970000 0.1711620000 0.0017880000 114358419 0 402718720 3.9797580242 4.0160589218 4.0948581696 72 1305031231.9012699127 0.0461730175 0.0651827314 0.1287320852 0.0340012191 0.3242040000 0.0797330000 0.0828660000 0.0000010000 0.1596700000 0.0017690000 114362203 0 402718720 3.9712417126 4.0084915161 4.0849556923 73 1305031231.9330461025 0.0497045591 0.0649707017 0.1287320852 0.0338334808 0.5084130000 0.0918470000 0.0749640000 0.0317660000 0.1507950000 0.1588670000 114365875 0 402718720 3.9763236046 4.0056705475 4.0835447311 74 1305031231.9650299549 0.0509761684 0.0647815864 0.1287320852 0.0336220517 0.3104550000 0.0794830000 0.0792330000 0.0000000000 0.1498160000 0.0017520000 114369547 0 402718720 3.9758706093 4.0049490929 4.0796861649 75 1305031232.0007200241 0.0518331155 0.0646089401 0.1287320852 0.0335303696 0.3295790000 0.0788820000 0.0669550000 0.0315910000 0.1502310000 0.0017500000 114373331 0 402718720 3.9753057957 4.0050473213 4.0766091347 76 1305031232.0332028866 0.0543274656 0.0644736575 0.1287320852 0.0334250766 0.3533760000 0.1051130000 0.0939310000 0.0000010000 0.1523090000 0.0018340000 114377059 0 402718720 3.9729013443 4.0031199455 4.0722851753 77 1305031232.0651450157 0.0566727743 0.0643723474 0.1287320852 0.0332485443 0.4976120000 0.0793670000 0.0709620000 0.0314450000 0.1542100000 0.1614520000 114380675 0 402718720 3.9697327614 4.0027112961 4.0676150322 78 1305031232.1007990837 0.0591597632 0.0643055194 0.1287320852 0.0331114089 0.3199770000 0.0943740000 0.0634430000 0.0000010000 0.1601120000 0.0018610000 114384459 0 402718720 3.9653136730 4.0032658577 4.0626716614 79 1305031232.1328380108 0.0633349493 0.0642932337 0.1287320852 0.0329577108 0.3476260000 0.0796720000 0.0709530000 0.0312400000 0.1638220000 0.0017600000 114388187 0 402718720 3.9616346359 4.0014162064 4.0583844185 80 1305031232.1650519371 0.0659113750 0.0643134604 0.1287320852 0.0327724299 0.3050130000 0.0798230000 0.0553560000 0.0000010000 0.1679120000 0.0017470000 114391803 0 402718720 3.9591426849 4.0010166168 4.0545811653 81 1305031232.1992239952 0.0667748749 0.0643438483 0.1287320852 0.0326108942 0.5372510000 0.0925490000 0.0597630000 0.0309920000 0.1735260000 0.1802400000 114395531 0 402718720 3.9591412544 4.0022354126 4.0513968468 82 1305031232.2364680767 0.0681118742 0.0643897998 0.1287320852 0.0324447831 0.3493650000 0.0795060000 0.0883770000 0.0000000000 0.1795490000 0.0017510000 114399371 0 402718720 3.9584732056 4.0026149750 4.0482001305 83 1305031232.2626979351 0.0711349547 0.0644710667 0.1287320852 0.0324036627 0.3943950000 0.0903460000 0.0875900000 0.0307010000 0.1838110000 0.0017650000 114402875 0 402718720 3.9578933716 4.0005269051 4.0453333855 84 1305031232.2980248928 0.0714995340 0.0645547389 0.1287320852 0.0323663193 0.3444170000 0.0765900000 0.0754790000 0.0000000000 0.1904200000 0.0017440000 114406659 0 402718720 3.9577286243 4.0016460419 4.0424613953 85 1305031232.3321430683 0.0766288489 0.0646967873 0.1287320852 0.0322480524 0.5946820000 0.0764460000 0.0854430000 0.0299560000 0.1982660000 0.2043760000 114410387 0 402718720 3.9540350437 3.9985842705 4.0386528969 86 1305031232.3647489548 0.0777127072 0.0648481352 0.1287320852 0.0320969083 0.3663860000 0.0748600000 0.0839330000 0.0000010000 0.2056780000 0.0017300000 114414003 0 402718720 3.9514944553 4.0013804436 4.0351896286 87 1305031232.4008779526 0.0808003247 0.0650314937 0.1287320852 0.0319302942 0.3895440000 0.0854210000 0.0626000000 0.0303150000 0.2092910000 0.0017260000 114417843 0 402718720 3.9476492405 4.0026569366 4.0314760208 88 1305031232.4331440926 0.0822413638 0.0652270604 0.1287320852 0.0317480266 0.3898190000 0.0871170000 0.0868210000 0.0000010000 0.2138810000 0.0017960000 114421571 0 402718720 3.9461178780 4.0030684471 4.0289101601 89 1305031232.4647209644 0.0859428868 0.0654598225 0.1287320852 0.0315702519 0.5994340000 0.0741560000 0.0585260000 0.0299180000 0.2151130000 0.2215300000 114425131 0 402718720 3.9408318996 4.0039510727 4.0259795189 90 1305031232.5015261173 0.0900135934 0.0657326422 0.1287320852 0.0314009683 0.3820380000 0.0732370000 0.0824050000 0.0000010000 0.2245080000 0.0016920000 114428971 0 402718720 3.9379582405 4.0000829697 4.0233116150 91 1305031232.5324640274 0.0992107466 0.0661005334 0.1287320852 0.0312332050 0.4301670000 0.0736630000 0.0876670000 0.0303620000 0.2365690000 0.0017090000 114432643 0 402718720 3.9294919968 3.9937605858 4.0196180344 92 1305031232.5647449493 0.1077672914 0.0665534330 0.1287320852 0.0310978853 0.3848630000 0.0734720000 0.0630240000 0.0000000000 0.2464510000 0.0017030000 114436315 0 402718720 3.9209258556 3.9889559746 4.0161414146 93 1305031232.6003499031 0.1180515960 0.0671071767 0.1287320852 0.0309538235 0.6896720000 0.0926070000 0.0589190000 0.0304100000 0.2496680000 0.2578610000 114440043 0 402718720 3.9122219086 3.9815905094 4.0124764442 94 1305031232.6294269562 0.1234740466 0.0677068242 0.1287320852 0.0308216142 0.4161620000 0.0864270000 0.0623620000 0.0000000000 0.2654610000 0.0017070000 114443603 0 402718720 3.9070971012 3.9794797897 4.0087461472 95 1305031232.6647078991 0.1261674166 0.0683221989 0.1287320852 0.0306611758 0.4504650000 0.0867370000 0.0680090000 0.0305510000 0.2632390000 0.0017240000 114447443 0 402718720 3.9018466473 3.9812800884 4.0058493614 96 1305031232.7005090714 0.1333872229 0.0689999595 0.1333872229 0.0305119943 0.4336480000 0.0736430000 0.0834530000 0.0000010000 0.2746180000 0.0017280000 114451171 0 402718720 3.8938946724 3.9794795513 4.0022945404 97 1305031232.7327980995 0.1361373812 0.0696920979 0.1361373812 0.0303970804 0.7461270000 0.0734310000 0.0868790000 0.0307080000 0.2701650000 0.2847380000 114454843 0 402718720 3.8910510540 3.9804093838 3.9986655712 98 1305031232.7684600353 0.1406137943 0.0704157887 0.1406137943 0.0303106250 0.4464720000 0.0866270000 0.0567120000 0.0000010000 0.3005700000 0.0023330000 114458627 0 402718720 3.8864500523 3.9775633812 3.9964003563 99 1305031232.8045380116 0.1473866999 0.0711932726 0.1473866999 0.0301730236 0.4969280000 0.0915110000 0.0833920000 0.0340270000 0.2860540000 0.0017410000 114462411 0 402718720 3.8794465065 3.9729082584 3.9933760166 100 1305031232.8346450329 0.1512111425 0.0719934513 0.1512111425 0.0300623832 0.4278800000 0.0719450000 0.0563490000 0.0000010000 0.2976560000 0.0017260000 114466027 0 402718720 3.8742320538 3.9747250080 3.9896597862 101 1305031232.8685569763 0.1544285566 0.0728096405 0.1544285566 0.0299495823 0.7860170000 0.0715460000 0.0654280000 0.0311110000 0.2953880000 0.3223380000 114469811 0 402718720 3.8700299263 3.9746770859 3.9867935181 102 1305031232.9041829109 0.1580103785 0.0736449419 0.1580103785 0.0298306712 0.4423070000 0.0711090000 0.0633530000 0.0000000000 0.3059050000 0.0017260000 114473539 0 402718720 3.8650848866 3.9743585587 3.9844183922 103 1305031232.9330000877 0.1594838947 0.0744783297 0.1594838947 0.0297297950 0.4820380000 0.0820640000 0.0667240000 0.0313040000 0.2998890000 0.0018280000 114477099 0 402718720 3.8629298210 3.9767119884 3.9822015762 104 1305031232.9683640003 0.1583659500 0.0752849415 0.1594838947 0.0295854617 0.4368700000 0.0808090000 0.0523430000 0.0000010000 0.3016780000 0.0018090000 114480939 0 402718720 3.8635795116 3.9770984650 3.9805185795 105 1305031233.0011510849 0.1550248116 0.0760443688 0.1594838947 0.0294876365 0.8207900000 0.0703410000 0.0705110000 0.0311550000 0.3036780000 0.3448630000 114484611 0 402718720 3.8653883934 3.9830055237 3.9795010090 106 1305031233.0330219269 0.1526522040 0.0767670842 0.1594838947 0.0296513580 0.4815330000 0.0894640000 0.0874000000 0.0000010000 0.3027310000 0.0017230000 114488283 0 402718720 3.8634009361 3.9889297485 3.9824063778 107 1305031233.0688428879 0.1467103958 0.0774207601 0.1594838947 0.0297925799 0.4425000000 0.0720950000 0.0577970000 0.0310050000 0.2796610000 0.0017280000 114491955 0 402718720 3.8674135208 3.9923021793 3.9837896824 108 1305031233.1004469395 0.1359594017 0.0779627845 0.1594838947 0.0297420789 0.4246730000 0.0932850000 0.0620680000 0.0000010000 0.2673630000 0.0017380000 114495571 0 402718720 3.8749740124 4.0035457611 3.9880795479 109 1305031233.1328918934 0.1288284957 0.0784294424 0.1594838947 0.0300856054 0.7011300000 0.0727360000 0.0566730000 0.0301250000 0.2620040000 0.2793500000 114499243 0 402718720 3.8847763538 3.9985959530 3.9897806644 110 1305031233.1684799194 0.1172989011 0.0787828011 0.1594838947 0.0300821056 0.4151130000 0.0906780000 0.0746610000 0.0000000000 0.2478470000 0.0017050000 114503027 0 402718720 3.9009091854 4.0019965172 3.9902150631 111 1305031233.2006340027 0.1139551997 0.0790996696 0.1594838947 0.0299860968 0.4013390000 0.0728120000 0.0565700000 0.0299770000 0.2400390000 0.0017140000 114506699 0 402718720 3.9043297768 4.0019941330 3.9933495522 112 1305031233.2330091000 0.1111907512 0.0793861971 0.1594838947 0.0299602867 0.4051320000 0.0975560000 0.0676830000 0.0000010000 0.2379570000 0.0017070000 114510371 0 402718720 3.9042661190 4.0035028458 3.9971561432 113 1305031233.2684679031 0.1098364145 0.0796556680 0.1594838947 0.0306046787 0.6213450000 0.0744030000 0.0643700000 0.0303310000 0.2226550000 0.2293520000 114514155 0 402718720 3.9010996819 4.0039782524 4.0019555092 114 1305031233.3003950119 0.0954127386 0.0797938880 0.1594838947 0.0308549453 0.3668690000 0.0722510000 0.0813790000 0.0000000000 0.2112820000 0.0017280000 114517827 0 402718720 3.9099018574 4.0133056641 4.0098104477 115 1305031233.3325300217 0.0881753638 0.0798667704 0.1594838947 0.0307384580 0.3842090000 0.0741610000 0.0774960000 0.0298420000 0.2007540000 0.0017230000 114521499 0 402718720 3.9127538204 4.0038580894 4.0230722427 116 1305031233.3686299324 0.0700520128 0.0797821604 0.1594838947 0.0307026557 0.3434430000 0.0755090000 0.0804750000 0.0000010000 0.1855110000 0.0017140000 114525171 0 402718720 3.9359221458 4.0127429962 4.0282840729 117 1305031233.4008929729 0.0578457750 0.0795946699 0.1594838947 0.0306835630 0.5426670000 0.0769880000 0.0816170000 0.0309260000 0.1729210000 0.1799720000 114528899 0 402718720 3.9621927738 4.0260009766 4.0355463028 118 1305031233.4330079556 0.0598619767 0.0794274437 0.1594838947 0.0307027249 0.3451180000 0.0921100000 0.0849040000 0.0000000000 0.1661150000 0.0017490000 114532627 0 402718720 3.9575488567 4.0160932541 4.0406985283 119 1305031233.4687869549 0.0625109449 0.0792852882 0.1594838947 0.0307164055 0.3153650000 0.0778350000 0.0464120000 0.0312070000 0.1579150000 0.0017580000 114536299 0 402718720 3.9560811520 4.0093278885 4.0449199677 120 1305031233.5007359982 0.0640520304 0.0791583444 0.1594838947 0.0306172050 0.3033420000 0.0773990000 0.0656030000 0.0000000000 0.1584050000 0.0016940000 114540027 0 402718720 3.9523894787 4.0066533089 4.0465974808 121 1305031233.5341610909 0.0649522170 0.0790409384 0.1594838947 0.0305908436 0.4932080000 0.0788090000 0.0658330000 0.0314870000 0.1546610000 0.1621720000 114543755 0 402718720 3.9527959824 4.0051927567 4.0493841171 122 1305031233.5697269440 0.0640841946 0.0789183422 0.1594838947 0.0304913122 0.3140040000 0.0790640000 0.0802720000 0.0000010000 0.1526820000 0.0017420000 114547483 0 402718720 3.9536235332 4.0051274300 4.0530686378 123 1305031233.6012749672 0.0664493665 0.0788169684 0.1594838947 0.0304277111 0.3698350000 0.0943470000 0.0917140000 0.0312220000 0.1505620000 0.0017460000 114551155 0 402718720 3.9524812698 4.0021505356 4.0542078018 124 1305031233.6330409050 0.0666143373 0.0787185601 0.1594838947 0.0303608432 0.2987660000 0.0790760000 0.0698910000 0.0000000000 0.1476950000 0.0018450000 114554827 0 402718720 3.9529836178 3.9992964268 4.0585460663 125 1305031233.6717829704 0.0658454001 0.0786155748 0.1594838947 0.0302413259 0.5225780000 0.0916880000 0.0908180000 0.0318200000 0.1504430000 0.1575570000 114558723 0 402718720 3.9496929646 3.9993717670 4.0597534180 126 1305031233.7022960186 0.0630156696 0.0784917660 0.1594838947 0.0302969566 0.3259150000 0.0793510000 0.0891220000 0.0000000000 0.1554400000 0.0017570000 114562395 0 402718720 3.9507901669 4.0011777878 4.0634360313 127 1305031233.7312009335 0.0558265448 0.0783132997 0.1594838947 0.0304752761 0.3693750000 0.0892470000 0.0884150000 0.0320040000 0.1576910000 0.0017640000 114565955 0 402718720 3.9584050179 4.0091390610 4.0705280304 128 1305031233.7691600323 0.0526046343 0.0781124507 0.1594838947 0.0305258318 0.3262400000 0.0922940000 0.0740510000 0.0000010000 0.1578810000 0.0017610000 114569739 0 402718720 3.9619119167 4.0133366585 4.0732717514 129 1305031233.7997679710 0.0529925004 0.0779177225 0.1594838947 0.0304195217 0.5223040000 0.0788840000 0.0891600000 0.0319210000 0.1573320000 0.1647430000 114585643 0 402718720 3.9606604576 4.0120925903 4.0722904205 130 1305031233.8338310719 0.0564669557 0.0777527166 0.1594838947 0.0303726359 0.2822460000 0.0781770000 0.0448200000 0.0000000000 0.1572390000 0.0017540000 114614971 0 402718720 3.9562339783 4.0063147545 4.0687160492 131 1305031233.8655700684 0.0583856255 0.0776048762 0.1594838947 0.0303005112 0.3417290000 0.0767040000 0.0763050000 0.0320480000 0.1545620000 0.0018320000 114618643 0 402718720 3.9571323395 4.0045180321 4.0681958199 132 1305031233.8986968994 0.0574504584 0.0774521912 0.1594838947 0.0301855844 0.3099980000 0.0768940000 0.0769310000 0.0000000000 0.1540730000 0.0018260000 114622427 0 402718720 3.9572234154 4.0054478645 4.0681071281 133 1305031233.9320030212 0.0571810342 0.0772997765 0.1594838947 0.0301122725 0.5242900000 0.0878450000 0.0875380000 0.0320110000 0.1547850000 0.1618450000 114626099 0 402718720 3.9633123875 4.0055994987 4.0709581375 134 1305031233.9681589603 0.0554743856 0.0771369004 0.1594838947 0.0300186013 0.3087080000 0.0784120000 0.0736980000 0.0000010000 0.1545870000 0.0017500000 114629883 0 402718720 3.9687356949 4.0080142021 4.0727877617 135 1305031233.9989380836 0.0562990308 0.0769825458 0.1594838947 0.0299491631 0.3570890000 0.0781570000 0.0888480000 0.0319450000 0.1561210000 0.0017550000 114633555 0 402718720 3.9697422981 4.0068860054 4.0714769363 136 1305031234.0370678902 0.0539768450 0.0768133863 0.1594838947 0.0298507269 0.3175830000 0.0786440000 0.0749810000 0.0000000000 0.1619500000 0.0017430000 114637395 0 402718720 3.9753484726 4.0109343529 4.0731372833 137 1305031234.0687561035 0.0530195981 0.0766397090 0.1594838947 0.0297435507 0.5188150000 0.0790200000 0.0529090000 0.0315170000 0.1717590000 0.1833360000 114641011 0 402718720 3.9768660069 4.0123057365 4.0723552704 138 1305031234.0997409821 0.0534485094 0.0764716568 0.1594838947 0.0296415118 0.3639010000 0.0895200000 0.0907320000 0.0000000000 0.1816240000 0.0017520000 114644683 0 402718720 3.9840080738 4.0152192116 4.0743722916 139 1305031234.1350688934 0.0530311875 0.0763030203 0.1594838947 0.0295501316 0.3959250000 0.0794210000 0.0905480000 0.0319420000 0.1919760000 0.0017680000 114648411 0 402718720 3.9847991467 4.0166735649 4.0729146004 140 1305031234.1659009457 0.0493116938 0.0761102251 0.1594838947 0.0295138407 0.4000950000 0.1030020000 0.0933920000 0.0000000000 0.2016660000 0.0017580000 114652083 0 402718720 3.9853672981 4.0226397514 4.0733938217 141 1305031234.2010040283 0.0494857058 0.0759213988 0.1594838947 0.0294643135 0.6213380000 0.0789990000 0.0924270000 0.0320910000 0.2004770000 0.2170480000 114655811 0 402718720 3.9849593639 4.0220084190 4.0723714828 142 1305031234.2385749817 0.0482893176 0.0757268066 0.1594838947 0.0293628755 0.3503910000 0.0792060000 0.0545850000 0.0000010000 0.2145480000 0.0017800000 114659707 0 402718720 3.9865841866 4.0250701904 4.0729365349 143 1305031234.2655100822 0.0450086258 0.0755119942 0.1594838947 0.0292839650 0.4221020000 0.0780360000 0.0907010000 0.0318150000 0.2195090000 0.0017650000 114663155 0 402718720 3.9885203838 4.0325427055 4.0756807327 144 1305031234.3024549484 0.0448052622 0.0752987530 0.1594838947 0.0291815203 0.3753590000 0.0782580000 0.0655990000 0.0000000000 0.2294420000 0.0017810000 114667051 0 402718720 3.9890165329 4.0326757431 4.0759558678 145 1305031234.3384580612 0.0440459028 0.0750832161 0.1594838947 0.0290998330 0.6504420000 0.0902120000 0.0437300000 0.0323670000 0.2314160000 0.2524330000 114670835 0 402718720 3.9874877930 4.0339632034 4.0748753548 146 1305031234.3661808968 0.0416199453 0.0748540156 0.1594838947 0.0290449139 0.3799670000 0.0780000000 0.0582970000 0.0000000000 0.2415700000 0.0018180000 114674339 0 402718720 3.9888837337 4.0394182205 4.0776295662 147 1305031234.4000349045 0.0422173366 0.0746319974 0.1594838947 0.0289458968 0.4030320000 0.0794000000 0.0507980000 0.0326250000 0.2381130000 0.0018150000 114678067 0 402718720 3.9909534454 4.0409860611 4.0788493156 148 1305031234.4367709160 0.0448066369 0.0744304747 0.1594838947 0.0289160662 0.3868790000 0.0902750000 0.0444060000 0.0000010000 0.2500800000 0.0018340000 114681907 0 402718720 3.9956295490 4.0407719612 4.0795955658 149 1305031234.4676060677 0.0457032621 0.0742376746 0.1594838947 0.0288282336 0.6964660000 0.0792860000 0.0577210000 0.0329200000 0.2514620000 0.2747930000 114685523 0 402718720 3.9979336262 4.0435767174 4.0797481537 150 1305031234.4977810383 0.0463603400 0.0740518257 0.1594838947 0.0287368489 0.4040300000 0.0781890000 0.0589850000 0.0000000000 0.2647110000 0.0018570000 114689139 0 402718720 3.9994444847 4.0472950935 4.0799775124 151 1305031234.5376710892 0.0502796620 0.0738943942 0.1594838947 0.0288203806 0.4473380000 0.0773050000 0.0640980000 0.0332170000 0.2705530000 0.0018790000 114693035 0 402718720 4.0034179688 4.0437989235 4.0765528679 152 1305031234.5690369606 0.0539234988 0.0737630067 0.1594838947 0.0288334763 0.4777340000 0.1006860000 0.0862670000 0.0000010000 0.2885940000 0.0018900000 114696651 0 402718720 4.0089354515 4.0508003235 4.0795750618 153 1305031234.5982480049 0.0582869574 0.0736618560 0.1594838947 0.0287427409 0.8265890000 0.0958840000 0.0848790000 0.0338860000 0.2935140000 0.3181330000 114700323 0 402718720 4.0136051178 4.0551052094 4.0807332993 154 1305031234.6336491108 0.0602641366 0.0735748579 0.1594838947 0.0286822749 0.4486470000 0.0749950000 0.0621270000 0.0000000000 0.3093180000 0.0019110000 114703995 0 402718720 4.0149583817 4.0545597076 4.0771722794 155 1305031234.6658589840 0.0632068291 0.0735079674 0.1594838947 0.0286147098 0.5147250000 0.0743830000 0.0857860000 0.0338810000 0.3184850000 0.0018940000 114707723 0 402718720 4.0166993141 4.0579414368 4.0755376816 156 1305031234.6987318993 0.0645369217 0.0734504606 0.1594838947 0.0285358809 0.5027610000 0.0739020000 0.0935440000 0.0000010000 0.3330970000 0.0019170000 114711451 0 402718720 4.0146703720 4.0600442886 4.0703015327 157 1305031234.7344369888 0.0658696368 0.0734021751 0.1594838947 0.0284544443 0.9036060000 0.0737470000 0.0870230000 0.0348650000 0.3418050000 0.3658680000 114715123 0 402718720 4.0115413666 4.0639581680 4.0652060509 158 1305031234.7689719200 0.0691759959 0.0733754272 0.1594838947 0.0283697970 0.5332960000 0.0858090000 0.0899570000 0.0000010000 0.3553040000 0.0019250000 114718907 0 402718720 4.0121312141 4.0682411194 4.0634398460 159 1305031234.8015530109 0.0728643090 0.0733722126 0.1594838947 0.0283993049 0.5641040000 0.0726900000 0.0931520000 0.0354190000 0.3606280000 0.0019090000 114722635 0 402718720 4.0073704720 4.0814766884 4.0645761490 160 1305031234.8378078938 0.0757927820 0.0733873412 0.1594838947 0.0283279071 0.4985040000 0.0723810000 0.0540590000 0.0000010000 0.3698120000 0.0019470000 114726475 0 402718720 4.0055475235 4.0884151459 4.0672245026 161 1305031234.8693211079 0.0780043975 0.0734160185 0.1594838947 0.0282561159 0.9763020000 0.0717830000 0.0945430000 0.0356920000 0.3756110000 0.3983740000 114730035 0 402718720 3.9987509251 4.0940370560 4.0624985695 162 1305031234.9019980431 0.0819698274 0.0734688198 0.1594838947 0.0281785195 0.5282600000 0.0695650000 0.0753820000 0.0000010000 0.3810740000 0.0019380000 114733763 0 402718720 3.9960074425 4.1018137932 4.0667815208 163 1305031234.9381608963 0.0840836018 0.0735339412 0.1594838947 0.0282682719 0.5944140000 0.0927570000 0.0869280000 0.0358880000 0.3764600000 0.0020500000 114737547 0 402718720 3.9898264408 4.1087927818 4.0727496147 164 1305031234.9730799198 0.0854578763 0.0736066481 0.1594838947 0.0281846438 0.5364960000 0.0712380000 0.0884290000 0.0000000000 0.3745660000 0.0019540000 114741331 0 402718720 3.9887092113 4.1117429733 4.0790677071 165 1305031235.0050830841 0.0845754519 0.0736731257 0.1594838947 0.0282486980 1.0046910000 0.0716940000 0.1169900000 0.0455120000 0.3854360000 0.3847500000 114744947 0 402718720 3.9892458916 4.1127963066 4.0884637833 166 1305031235.0399720669 0.0796438381 0.0737090938 0.1594838947 0.0281697454 0.5172620000 0.0721950000 0.0846440000 0.0000010000 0.3581910000 0.0019240000 114748731 0 402718720 3.9947669506 4.1054000854 4.0937757492 167 1305031235.0729401112 0.0756529197 0.0737207335 0.1594838947 0.0281285089 0.5343920000 0.0728550000 0.0779800000 0.0348700000 0.3464390000 0.0019350000 114752403 0 402718720 3.9977025986 4.1008996964 4.1021809578 168 1305031235.0995910168 0.0684178025 0.0736891685 0.1594838947 0.0280543909 0.5176870000 0.0856220000 0.0917970000 0.0000010000 0.3380290000 0.0019240000 114755963 0 402718720 4.0000967979 4.0923309326 4.1051754951 169 1305031235.1362709999 0.0603782237 0.0736104055 0.1594838947 0.0280242959 0.8817510000 0.0841030000 0.0916790000 0.0344660000 0.3305660000 0.3406180000 114759747 0 402718720 4.0037837029 4.0792369843 4.1046710014 170 1305031235.1663711071 0.0562134832 0.0735080706 0.1594838947 0.0280107071 0.5129610000 0.0943550000 0.0920450000 0.0000010000 0.3243020000 0.0019350000 114763363 0 402718720 4.0026946068 4.0766286850 4.1087365150 171 1305031235.1998469830 0.0541367605 0.0733947881 0.1594838947 0.0279362347 0.5027930000 0.0730480000 0.0819800000 0.0345620000 0.3109700000 0.0019160000 114766979 0 402718720 4.0059409142 4.0718340874 4.1153326035 172 1305031235.2375700474 0.0505120307 0.0732617488 0.1594838947 0.0279274475 0.4683860000 0.0734670000 0.0911270000 0.0000010000 0.3015980000 0.0018740000 114770819 0 402718720 4.0045266151 4.0714859962 4.1189770699 173 1305031235.2690389156 0.0476990454 0.0731139875 0.1594838947 0.0278480822 0.8153780000 0.1037800000 0.0890390000 0.0341280000 0.2899750000 0.2981260000 114774491 0 402718720 4.0029401779 4.0713810921 4.1240448952 174 1305031235.3064870834 0.0443161540 0.0729484827 0.1594838947 0.0278761503 0.4812940000 0.1031250000 0.0789950000 0.0000010000 0.2962800000 0.0025320000 114778331 0 402718720 3.9991414547 4.0752329826 4.1285748482 175 1305031235.3380000591 0.0359292850 0.0727369445 0.1594838947 0.0277986088 0.5150380000 0.0967780000 0.1063480000 0.0417610000 0.2679280000 0.0018980000 114781947 0 402718720 3.9908354282 4.0760240555 4.1289443970 176 1305031235.3698880672 0.0269682948 0.0724768953 0.1594838947 0.0277669952 0.4196650000 0.0778360000 0.0877220000 0.0000010000 0.2519020000 0.0018700000 114785619 0 402718720 3.9817872047 4.0749225616 4.1244516373 177 1305031235.4060161114 0.0220366586 0.0721919222 0.1594838947 0.0278118767 0.6665330000 0.0790480000 0.0665280000 0.0331410000 0.2403880000 0.2470970000 114789403 0 402718720 3.9765932560 4.0747528076 4.1230149269 178 1305031235.4381530285 0.0191644691 0.0718940152 0.1594838947 0.0277662075 0.3943960000 0.0924140000 0.0754010000 0.0000000000 0.2243780000 0.0018640000 114793075 0 402718720 3.9684813023 4.0773139000 4.1232652664 179 1305031235.4700589180 0.0202770177 0.0716056521 0.1594838947 0.0277565287 0.3990270000 0.0807680000 0.0743630000 0.0320350000 0.2096820000 0.0018470000 114796747 0 402718720 3.9641058445 4.0682826042 4.1164927483 180 1305031235.5059850216 0.0247042961 0.0713450890 0.1594838947 0.0276904833 0.3667280000 0.0805290000 0.0882330000 0.0000010000 0.1958140000 0.0018220000 114800531 0 402718720 3.9595046043 4.0662961006 4.1160759926 181 1305031235.5385539532 0.0252654124 0.0710905051 0.1594838947 0.0276226055 0.5560780000 0.1100280000 0.0547620000 0.0321580000 0.1757610000 0.1830190000 114804203 0 402718720 3.9591276646 4.0643687248 4.1180429459 182 1305031235.5703649521 0.0268646255 0.0708475058 0.1594838947 0.0275570700 0.3150860000 0.0806450000 0.0663620000 0.0000010000 0.1659620000 0.0017770000 114807875 0 402718720 3.9614250660 4.0597810745 4.1208095551 183 1305031235.6060059071 0.0316856839 0.0706335068 0.1594838947 0.0275162179 0.3150150000 0.0808410000 0.0481820000 0.0318310000 0.1519370000 0.0018680000 114811715 0 402718720 3.9569501877 4.0589609146 4.1228494644 184 1305031235.6389510632 0.0381410718 0.0704569175 0.1594838947 0.0274737814 0.3114000000 0.0810130000 0.0866190000 0.0000010000 0.1416700000 0.0017530000 114815387 0 402718720 3.9553086758 4.0536494255 4.1245260239 185 1305031235.6705160141 0.0424933806 0.0703057632 0.1594838947 0.0274070322 0.4826840000 0.0809330000 0.0953560000 0.0316330000 0.1337100000 0.1406990000 114819003 0 402718720 3.9533808231 4.0515227318 4.1274485588 186 1305031235.7057778835 0.0465523340 0.0701780566 0.1594838947 0.0273331113 0.2648070000 0.0804400000 0.0518560000 0.0000010000 0.1304100000 0.0017580000 114822787 0 402718720 3.9587955475 4.0468769073 4.1348309517 187 1305031235.7387969494 0.0542412251 0.0700928329 0.1594838947 0.0272941347 0.3258620000 0.0794810000 0.0713230000 0.0311450000 0.1417880000 0.0017810000 114826515 0 402718720 3.9563879967 4.0423746109 4.1383605003 188 1305031235.7696299553 0.0599525310 0.0700388951 0.1594838947 0.0272315098 0.3499110000 0.0908730000 0.0935750000 0.0000000000 0.1633370000 0.0017740000 114830131 0 402718720 3.9518756866 4.0412497520 4.1408658028 189 1305031235.8072249889 0.0701893121 0.0700396910 0.1594838947 0.0271721398 0.4938010000 0.0780790000 0.0650350000 0.0317090000 0.1538810000 0.1647410000 114834083 0 402718720 3.9475343227 4.0369982719 4.1424622536 190 1305031235.8388121128 0.0769351050 0.0700759826 0.1594838947 0.0271302788 0.3376280000 0.0781430000 0.0816570000 0.0000010000 0.1757120000 0.0017680000 114837755 0 402718720 3.9454090595 4.0338354111 4.1466507912 191 1305031235.8700668812 0.0833352059 0.0701454026 0.1594838947 0.0270883968 0.3222430000 0.0782790000 0.0514150000 0.0319310000 0.1585040000 0.0017600000 114841483 0 402718720 3.9429342747 4.0313310623 4.1505513191 192 1305031235.9061110020 0.0903465375 0.0702506169 0.1594838947 0.0270223284 0.3619210000 0.0900820000 0.0903460000 0.0000000000 0.1793870000 0.0017490000 114845323 0 402718720 3.9423956871 4.0286564827 4.1549630165 193 1305031235.9382328987 0.0999058038 0.0704042707 0.1594838947 0.0269786448 0.5534790000 0.0880120000 0.0804260000 0.0322720000 0.1685010000 0.1839120000 114849107 0 402718720 3.9426331520 4.0220303535 4.1601161957 194 1305031235.9700109959 0.1032017395 0.0705733298 0.1594838947 0.0269129517 0.3569230000 0.0759870000 0.0926030000 0.0000010000 0.1862290000 0.0017490000 114852779 0 402718720 3.9384560585 4.0234069824 4.1620554924 195 1305031236.0068531036 0.1124825329 0.0707882488 0.1594838947 0.0268532524 0.3315320000 0.0750350000 0.0454050000 0.0320730000 0.1769190000 0.0017380000 114856675 0 402718720 3.9408464432 4.0176653862 4.1706490517 196 1305031236.0380480289 0.1177900806 0.0710280541 0.1594838947 0.0267908122 0.3802540000 0.0875990000 0.0914030000 0.0000000000 0.1991520000 0.0017420000 114860347 0 402718720 3.9367740154 4.0170059204 4.1720943451 197 1305031236.0698781013 0.1266420633 0.0713103587 0.1594838947 0.0268006998 0.5825610000 0.0741900000 0.0903150000 0.0328080000 0.1819820000 0.2029090000 114864075 0 402718720 3.9310870171 4.0128555298 4.1743607521 198 1305031236.1058719158 0.1313848197 0.0716137651 0.1594838947 0.0267411220 0.3818050000 0.0863210000 0.0939400000 0.0000010000 0.1994310000 0.0017400000 114867915 0 402718720 3.9309225082 4.0116887093 4.1785678864 199 1305031236.1383249760 0.1362339109 0.0719384894 0.1594838947 0.0266806310 0.3785580000 0.0730810000 0.0902070000 0.0329550000 0.1802150000 0.0017390000 114871699 0 402718720 3.9274280071 4.0101552010 4.1799659729 200 1305031236.1709330082 0.1378589869 0.0722680919 0.1594838947 0.0266142717 0.3594940000 0.0728110000 0.0960140000 0.0000000000 0.1885640000 0.0017380000 114875427 0 402718720 3.9287059307 4.0108075142 4.1841168404 201 1305031236.2071900368 0.1399473250 0.0726048045 0.1594838947 0.0265541151 0.5570830000 0.0725990000 0.0760910000 0.0330160000 0.1779570000 0.1970530000 114879323 0 402718720 3.9279782772 4.0112872124 4.1861696243 202 1305031236.2383749485 0.1445883214 0.0729611586 0.1594838947 0.0265272859 0.3612420000 0.0837140000 0.0910860000 0.0000000000 0.1843190000 0.0017390000 114883051 0 402718720 3.9266915321 4.0077714920 4.1899757385 203 1305031236.2699589729 0.1475699991 0.0733286898 0.1594838947 0.0264633898 0.4013430000 0.0967800000 0.0915200000 0.0331290000 0.1777910000 0.0017470000 114886723 0 402718720 3.9267842770 4.0046052933 4.1920328140 204 1305031236.3069939613 0.1480794400 0.0736951150 0.1594838947 0.0264433993 0.3380250000 0.0726110000 0.0924900000 0.0000010000 0.1708170000 0.0017380000 114890619 0 402718720 3.9279844761 4.0020151138 4.1935267448 205 1305031236.3392169476 0.1498375684 0.0740665416 0.1594838947 0.0263870667 0.5425340000 0.0726910000 0.0928730000 0.0329770000 0.1640350000 0.1795850000 114894347 0 402718720 3.9304738045 3.9976963997 4.1945557594 206 1305031236.3700959682 0.1465731114 0.0744185153 0.1594838947 0.0263298393 0.3353030000 0.0735020000 0.0978350000 0.0000000000 0.1617690000 0.0018200000 114898019 0 402718720 3.9322378635 3.9973504543 4.1904020309 207 1305031236.4058690071 0.1395252645 0.0747330406 0.1594838947 0.0263122840 0.3520930000 0.0725640000 0.0877770000 0.0323370000 0.1572820000 0.0017530000 114901859 0 402718720 3.9370782375 3.9987304211 4.1863794327 208 1305031236.4387879372 0.1317686588 0.0750072503 0.1594838947 0.0262514957 0.3564670000 0.1050180000 0.0929990000 0.0000000000 0.1563220000 0.0017420000 114905587 0 402718720 3.9437308311 4.0005679131 4.1818308830 209 1305031236.4751410484 0.1226191521 0.0752350585 0.1594838947 0.0261939720 0.5203030000 0.0751820000 0.0930270000 0.0326550000 0.1546060000 0.1644480000 114909483 0 402718720 3.9495904446 4.0034193993 4.1757273674 210 1305031236.5077209473 0.1151945144 0.0754253416 0.1594838947 0.0261384104 0.3376020000 0.0885090000 0.0932860000 0.0000010000 0.1536730000 0.0017450000 114913267 0 402718720 3.9525430202 4.0054421425 4.1692404747 211 1305031236.5386450291 0.1116628274 0.0755970832 0.1594838947 0.0260922783 0.3427810000 0.0765920000 0.0789210000 0.0323750000 0.1527550000 0.0017500000 114916939 0 402718720 3.9502544403 4.0041747093 4.1591644287 212 1305031236.5740950108 0.1037863195 0.0757300513 0.1594838947 0.0260363316 0.3225000000 0.0764380000 0.0932370000 0.0000000000 0.1507260000 0.0017060000 114920779 0 402718720 3.9496479034 4.0059747696 4.1502208710 213 1305031236.6057569981 0.1031839326 0.0758589428 0.1594838947 0.0259766724 0.5135480000 0.0988390000 0.0771360000 0.0321350000 0.1485980000 0.1564470000 114924451 0 402718720 3.9510052204 4.0015444756 4.1452255249 214 1305031236.6384010315 0.0978401452 0.0759616587 0.1594838947 0.0259541875 0.3188320000 0.0783340000 0.0912790000 0.0000000000 0.1470730000 0.0017500000 114928179 0 402718720 3.9529936314 4.0022811890 4.1384420395 215 1305031236.6751470566 0.0916145816 0.0760344630 0.1594838947 0.0259092867 0.3507450000 0.0777400000 0.0946490000 0.0319250000 0.1441820000 0.0018390000 114931963 0 402718720 3.9544651508 4.0025300980 4.1320700645 216 1305031236.7033619881 0.0875913650 0.0760879672 0.1594838947 0.0258532281 0.2870370000 0.0780820000 0.0634780000 0.0000010000 0.1432100000 0.0018530000 114935523 0 402718720 3.9619259834 4.0014905930 4.1295990944 217 1305031236.7339220047 0.0786312819 0.0760996875 0.1594838947 0.0258320932 0.4683050000 0.0794040000 0.0634960000 0.0317950000 0.1428490000 0.1503600000 114939139 0 402718720 3.9615194798 4.0073719025 4.1184124947 218 1305031236.7740409374 0.0715809911 0.0760789595 0.1594838947 0.0257978248 0.3064830000 0.0891760000 0.0759620000 0.0000000000 0.1391820000 0.0017620000 114943035 0 402718720 3.9616558552 4.0096535683 4.1101069450 219 1305031236.8025879860 0.0697719604 0.0760501605 0.1594838947 0.0258531367 0.3092400000 0.0786160000 0.0590510000 0.0314430000 0.1380010000 0.0017280000 114946707 0 402718720 3.9616637230 4.0106177330 4.1009659767 220 1305031236.8364150524 0.0614533573 0.0759838114 0.1594838947 0.0257968603 0.2754860000 0.0805310000 0.0532730000 0.0000010000 0.1395330000 0.0017560000 114950379 0 402718720 3.9641547203 4.0150504112 4.0941677094 221 1305031236.8743979931 0.0566883497 0.0758965016 0.1594838947 0.0257528701 0.4622650000 0.0810600000 0.0536670000 0.0317000000 0.1442980000 0.1511340000 114954219 0 402718720 3.9643175602 4.0160803795 4.0861883163 222 1305031236.9060690403 0.0543760955 0.0757995628 0.1594838947 0.0257425823 0.2913360000 0.0807290000 0.0537400000 0.0000010000 0.1547110000 0.0017570000 114957891 0 402718720 3.9663751125 4.0169000626 4.0788822174 223 1305031236.9344370365 0.0521720685 0.0756936099 0.1594838947 0.0257001692 0.4006760000 0.1134520000 0.0825270000 0.0318820000 0.1706160000 0.0017890000 114961451 0 402718720 3.9695770741 4.0181369781 4.0732874870 224 1305031236.9744000435 0.0473874249 0.0755672430 0.1594838947 0.0256456318 0.3460160000 0.0796180000 0.0813210000 0.0000010000 0.1828830000 0.0017860000 114965291 0 402718720 3.9725613594 4.0207943916 4.0680646896 225 1305031237.0074260235 0.0472309701 0.0754413040 0.1594838947 0.0256001180 0.6154920000 0.0787360000 0.0882970000 0.0322740000 0.2033370000 0.2124390000 114969075 0 402718720 3.9817049503 4.0231418610 4.0660915375 226 1305031237.0370240211 0.0476972088 0.0753185425 0.1594838947 0.0255756716 0.3679400000 0.0776300000 0.0660610000 0.0000000000 0.2220480000 0.0017920000 114972691 0 402718720 3.9867033958 4.0278739929 4.0624499321 227 1305031237.0734269619 0.0500125289 0.0752070623 0.1594838947 0.0255225914 0.4130530000 0.0771900000 0.0658600000 0.0320380000 0.2357100000 0.0018480000 114976419 0 402718720 3.9914259911 4.0286140442 4.0586271286 228 1305031237.1059679985 0.0559529550 0.0751226145 0.1594838947 0.0254814831 0.4138560000 0.0779890000 0.0853750000 0.0000000000 0.2482220000 0.0018610000 114980147 0 402718720 3.9990394115 4.0290575027 4.0566067696 229 1305031237.1378319263 0.0633799881 0.0750713366 0.1594838947 0.0254368639 0.7203650000 0.0773930000 0.0667830000 0.0332710000 0.2658800000 0.2766320000 114983819 0 402718720 4.0078501701 4.0303525925 4.0542521477 230 1305031237.1712269783 0.0691531152 0.0750456052 0.1594838947 0.0254823114 0.4458010000 0.0764510000 0.0881040000 0.0000010000 0.2789440000 0.0018860000 114987547 0 402718720 4.0147571564 4.0374298096 4.0551624298 231 1305031237.2042291164 0.0755300894 0.0750477026 0.1594838947 0.0254832504 0.5012330000 0.0872990000 0.0884830000 0.0333560000 0.2897660000 0.0019100000 114991163 0 402718720 4.0217604637 4.0356669426 4.0519642830 232 1305031237.2375690937 0.0836432949 0.0750847525 0.1594838947 0.0254601575 0.4505330000 0.0862130000 0.0596150000 0.0000000000 0.3023840000 0.0019030000 114994947 0 402718720 4.0294003487 4.0370798111 4.0498380661 233 1305031237.2746589184 0.0853610411 0.0751288568 0.1594838947 0.0254274299 0.8376290000 0.0967160000 0.0709650000 0.0344630000 0.3118490000 0.3232130000 114998731 0 402718720 4.0303215981 4.0380368233 4.0430893898 234 1305031237.3058099747 0.0876939893 0.0751825539 0.1594838947 0.0253790509 0.4677790000 0.0731680000 0.0719470000 0.0000010000 0.3203340000 0.0019060000 115002403 0 402718720 4.0313754082 4.0388102531 4.0349426270 235 1305031237.3371419907 0.0896629170 0.0752441725 0.1594838947 0.0253618260 0.5034340000 0.0730150000 0.0534830000 0.0348400000 0.3390720000 0.0025470000 115006075 0 402718720 4.0311512947 4.0383996964 4.0264444351 236 1305031237.3741660118 0.0909481943 0.0753107150 0.1594838947 0.0253278857 0.5194680000 0.0916430000 0.0710020000 0.0000000000 0.3544730000 0.0019220000 115009803 0 402718720 4.0287613869 4.0422172546 4.0169715881 237 1305031237.4057340622 0.0905416757 0.0753749806 0.1594838947 0.0253276521 0.8936260000 0.0722460000 0.0765390000 0.0352550000 0.3485320000 0.3606310000 115013531 0 402718720 4.0234990120 4.0515232086 4.0124731064 238 1305031237.4377219677 0.0952836350 0.0754586304 0.1594838947 0.0253246034 0.5254310000 0.0836940000 0.0838120000 0.0000010000 0.3556180000 0.0018720000 115017203 0 402718720 4.0254912376 4.0552806854 4.0089306831 239 1305031237.4741280079 0.0967084020 0.0755475416 0.1594838947 0.0252930158 0.5293050000 0.0715350000 0.0573320000 0.0356180000 0.3624510000 0.0019340000 115020931 0 402718720 4.0213956833 4.0612483025 4.0022163391 240 1305031237.5060451031 0.0991164371 0.0756457453 0.1594838947 0.0252778007 0.5021410000 0.0715470000 0.0550250000 0.0000000000 0.3731910000 0.0019430000 115024659 0 402718720 4.0173964500 4.0714831352 4.0024414062 241 1305031237.5376501083 0.1010751799 0.0757512617 0.1594838947 0.0252330369 0.9721860000 0.0712700000 0.0885000000 0.0358500000 0.3785230000 0.3976090000 115028331 0 402718720 4.0185818672 4.0718488693 3.9974846840 242 1305031237.5739479065 0.1019245014 0.0758594155 0.1594838947 0.0251930158 0.5319250000 0.0714280000 0.0699330000 0.0000010000 0.3881720000 0.0019560000 115032059 0 402718720 4.0138044357 4.0746836662 3.9915974140 243 1305031237.6068129539 0.1070502698 0.0759877730 0.1594838947 0.0251652275 0.6273940000 0.1005420000 0.0966030000 0.0360780000 0.3917710000 0.0019570000 115035843 0 402718720 4.0135116577 4.0862364769 3.9968657494 244 1305031237.6378550529 0.1094982252 0.0761251109 0.1594838947 0.0251223770 0.5355560000 0.0700730000 0.0643360000 0.0000010000 0.3980810000 0.0025750000 115039459 0 402718720 4.0129265785 4.0901770592 3.9963383675 245 1305031237.6752760410 0.1129699498 0.0762754980 0.1594838947 0.0250870009 1.0862110000 0.0877790000 0.1165150000 0.0464280000 0.4153700000 0.4196870000 115043243 0 402718720 4.0091605186 4.0972867012 3.9977207184 246 1305031237.7071180344 0.1138600111 0.0764282806 0.1594838947 0.0250383400 0.5543950000 0.0699100000 0.0866510000 0.0000010000 0.3953170000 0.0020600000 115046971 0 402718720 4.0068616867 4.0992832184 3.9966270924 247 1305031237.7416670322 0.1155111045 0.0765865106 0.1594838947 0.0250184883 0.5955750000 0.0696980000 0.0892760000 0.0362920000 0.3979000000 0.0019660000 115050699 0 402718720 4.0038051605 4.1047272682 4.0007910728 248 1305031237.7743060589 0.1153268591 0.0767427217 0.1594838947 0.0250520581 0.5744360000 0.0821820000 0.0950960000 0.0000000000 0.3947480000 0.0019580000 115054315 0 402718720 4.0077509880 4.1012945175 3.9999520779 249 1305031237.8064959049 0.1129668131 0.0768882000 0.1594838947 0.0250094504 1.0168330000 0.0700480000 0.0903990000 0.0357380000 0.3996150000 0.4205920000 115058043 0 402718720 4.0038852692 4.0990920067 3.9944260120 250 1305031237.8430309296 0.1178865433 0.0770521933 0.1594838947 0.0250919071 0.5433650000 0.0827490000 0.0609580000 0.0000000000 0.3972410000 0.0019650000 115061883 0 402718720 4.0012211800 4.1087965965 4.0042428970 251 1305031237.8754220009 0.1149450988 0.0772031611 0.1594838947 0.0252838908 0.6069200000 0.0820030000 0.0916250000 0.0356930000 0.3951920000 0.0019580000 115065499 0 402718720 4.0068974495 4.1011543274 4.0002646446 252 1305031237.9077839851 0.1118995473 0.0773408452 0.1594838947 0.0252503202 0.5420770000 0.0704100000 0.0692690000 0.0000010000 0.3999870000 0.0019620000 115069227 0 402718720 4.0035700798 4.0974640846 3.9940366745 253 1305031237.9441869259 0.1199966744 0.0775094453 0.1594838947 0.0254261998 1.0086480000 0.0970820000 0.0646440000 0.0356650000 0.3956520000 0.4151340000 115073011 0 402718720 4.0057106018 4.1104440689 4.0108737946 254 1305031237.9738099575 0.1219347492 0.0776843481 0.1594838947 0.0253921130 0.5356650000 0.0714750000 0.0724600000 0.0000000000 0.3893250000 0.0019570000 115076515 0 402718720 4.0128293037 4.1093840599 4.0188093185 255 1305031238.0069320202 0.1195349991 0.0778484683 0.1594838947 0.0253573036 0.5542250000 0.0716840000 0.0627890000 0.0353690000 0.3819700000 0.0019540000 115080299 0 402718720 4.0171308517 4.1045441628 4.0255126953 256 1305031238.0431399345 0.1201326847 0.0780136410 0.1594838947 0.0255386416 0.5222660000 0.0723440000 0.0773450000 0.0000010000 0.3701730000 0.0019460000 115084083 0 402718720 4.0273408890 4.0990347862 4.0377020836 257 1305031238.0740320683 0.1125196218 0.0781479055 0.1594838947 0.0255702548 0.9016200000 0.0725470000 0.0684400000 0.0355810000 0.3571720000 0.3674180000 115112275 0 402718720 4.0329618454 4.0834727287 4.0405282974 258 1305031238.1065878868 0.1031120494 0.0782446657 0.1594838947 0.0255918202 0.5193870000 0.0823090000 0.0936540000 0.0000000000 0.3409110000 0.0020260000 115167147 0 402718720 4.0354118347 4.0658435822 4.0417470932 259 1305031238.1433279514 0.1013507321 0.0783338784 0.1594838947 0.0256426334 0.5278070000 0.0727510000 0.0878510000 0.0350610000 0.3297640000 0.0019100000 115170931 0 402718720 4.0378584862 4.0582461357 4.0483932495 260 1305031238.1723001003 0.0971959680 0.0784064248 0.1594838947 0.0256183619 0.4979920000 0.0948130000 0.0906130000 0.0000010000 0.3100250000 0.0020440000 115174603 0 402718720 4.0311760902 4.0627427101 4.0603351593 261 1305031238.2054259777 0.0962625146 0.0784748390 0.1594838947 0.0264152847 0.7954760000 0.0754810000 0.0854230000 0.0000000000 0.3128260000 0.3212770000 115178219 0 402718720 4.0311760902 4.0627427101 4.0603351593 262 1305031238.2401471138 0.0820016935 0.0784883003 0.1594838947 0.0268050948 0.4507690000 0.0896640000 0.0761030000 0.0000000000 0.2826220000 0.0019040000 115182003 0 402718720 4.0180029869 4.0581789017 4.0629901886 263 1305031238.2725269794 0.0690310225 0.0784523410 0.1594838947 0.0267625571 0.4847730000 0.0944500000 0.0867170000 0.0336660000 0.2675770000 0.0018850000 115185731 0 402718720 4.0041847229 4.0578002930 4.0589809418 264 1305031238.3060529232 0.0621284656 0.0783905082 0.1594838947 0.0269335692 0.4227120000 0.0786440000 0.0903880000 0.0000010000 0.2513180000 0.0018820000 115189403 0 402718720 3.9928126335 4.0651230812 4.0587296486 265 1305031238.3425960541 0.0506667309 0.0782858901 0.1594838947 0.0270009474 0.6847860000 0.0899150000 0.0857720000 0.0329220000 0.2339060000 0.2417880000 115193187 0 402718720 3.9840385914 4.0550394058 4.0523252487 266 1305031238.3741040230 0.0470737293 0.0781685512 0.1594838947 0.0269736916 0.3702020000 0.0793080000 0.0693690000 0.0000010000 0.2192040000 0.0018370000 115196859 0 402718720 3.9794921875 4.0491843224 4.0489730835 267 1305031238.4060359001 0.0441000946 0.0780409540 0.1594838947 0.0269247652 0.3865110000 0.0920710000 0.0575250000 0.0324130000 0.2022070000 0.0018120000 115200531 0 402718720 3.9772894382 4.0452394485 4.0514421463 268 1305031238.4434239864 0.0442272350 0.0779147834 0.1594838947 0.0268799046 0.3342550000 0.0898680000 0.0611130000 0.0000010000 0.1808620000 0.0019000000 115204315 0 402718720 3.9748802185 4.0407361984 4.0512776375 269 1305031238.4740819931 0.0450212695 0.0777925027 0.1594838947 0.0268433481 0.5291570000 0.0792410000 0.0654020000 0.0320290000 0.1724740000 0.1795220000 115207987 0 402718720 3.9748651981 4.0361843109 4.0540018082 270 1305031238.5058109760 0.0460570380 0.0776749639 0.1594838947 0.0268658270 0.3272000000 0.0776560000 0.0871600000 0.0000010000 0.1601830000 0.0017130000 115211659 0 402718720 3.9730110168 4.0308761597 4.0558829308 271 1305031238.5432639122 0.0498954505 0.0775724565 0.1594838947 0.0268181065 0.3530410000 0.0922210000 0.0744590000 0.0312930000 0.1528130000 0.0017640000 115215499 0 402718720 3.9703485966 4.0247492790 4.0563344955 272 1305031238.5741839409 0.0488920361 0.0774670138 0.1594838947 0.0267755471 0.2916640000 0.0773600000 0.0587170000 0.0000010000 0.1533300000 0.0017640000 115219059 0 402718720 3.9678890705 4.0250010490 4.0593395233 273 1305031238.6058249474 0.0504921526 0.0773682047 0.1594838947 0.0267303153 0.4942210000 0.0982230000 0.0545240000 0.0314610000 0.1513670000 0.1581210000 115222787 0 402718720 3.9640312195 4.0222434998 4.0609979630 274 1305031238.6427590847 0.0516233332 0.0772742454 0.1594838947 0.0266861162 0.2836960000 0.0773770000 0.0515420000 0.0000010000 0.1525170000 0.0017590000 115226627 0 402718720 3.9636712074 4.0210843086 4.0651340485 275 1305031238.6738131046 0.0545989759 0.0771917898 0.1594838947 0.0266431173 0.3253400000 0.0765070000 0.0616880000 0.0319760000 0.1529160000 0.0017530000 115230187 0 402718720 3.9602808952 4.0200562477 4.0664258003 276 1305031238.7051889896 0.0547888838 0.0771106199 0.1594838947 0.0265959767 0.3084260000 0.0765360000 0.0769590000 0.0000000000 0.1525730000 0.0018390000 115233859 0 402718720 3.9585955143 4.0213418007 4.0691189766 277 1305031238.7413070202 0.0592740104 0.0770462278 0.1594838947 0.0265854812 0.4826980000 0.0758420000 0.0590290000 0.0320120000 0.1536260000 0.1616860000 115237699 0 402718720 3.9554624557 4.0176553726 4.0703926086 278 1305031238.7717959881 0.0642596409 0.0770002329 0.1594838947 0.0265656344 0.3109510000 0.0868910000 0.0673330000 0.0000000000 0.1544770000 0.0017460000 115241371 0 402718720 3.9518663883 4.0140252113 4.0707216263 279 1305031238.8070189953 0.0661734417 0.0769614272 0.1594838947 0.0265408673 0.3446610000 0.0757470000 0.0792360000 0.0321280000 0.1552820000 0.0017530000 115245155 0 402718720 3.9496755600 4.0152859688 4.0718665123 280 1305031238.8429400921 0.0690639168 0.0769332218 0.1594838947 0.0264971865 0.3306690000 0.0761660000 0.0955680000 0.0000000000 0.1566880000 0.0017450000 115248995 0 402718720 3.9495019913 4.0130119324 4.0761508942 281 1305031238.8737230301 0.0786037445 0.0769391667 0.1594838947 0.0265050217 0.5256530000 0.0758780000 0.0912040000 0.0323050000 0.1589180000 0.1668390000 115252723 0 402718720 3.9496743679 4.0046048164 4.0797863007 282 1305031238.9061720371 0.0835771561 0.0769627057 0.1594838947 0.0264709906 0.3443370000 0.0892610000 0.0928250000 0.0000010000 0.1599960000 0.0017480000 115256395 0 402718720 3.9501461983 4.0004434586 4.0832595825 283 1305031238.9427859783 0.0845612437 0.0769895556 0.1594838947 0.0264243553 0.3566750000 0.0905190000 0.0705960000 0.0324510000 0.1608310000 0.0017590000 115260291 0 402718720 3.9488432407 4.0010609627 4.0832920074 284 1305031238.9723079205 0.0894701257 0.0770335013 0.1594838947 0.0263873141 0.3325940000 0.0757120000 0.0936330000 0.0000010000 0.1609990000 0.0017460000 115263963 0 402718720 3.9502863884 3.9968454838 4.0878596306 285 1305031239.0104830265 0.0907615572 0.0770816699 0.1594838947 0.0263629657 0.5492940000 0.0755460000 0.0819110000 0.0321130000 0.1753380000 0.1838110000 115267859 0 402718720 3.9490695000 3.9975574017 4.0870838165 286 1305031239.0408790112 0.0937909409 0.0771400939 0.1594838947 0.0263227933 0.3781360000 0.0952120000 0.1040690000 0.0000000000 0.1758740000 0.0024020000 115271531 0 402718720 3.9477102757 3.9955217838 4.0887026787 287 1305031239.0746610165 0.1013262793 0.0772243664 0.1594838947 0.0263234712 0.3737530000 0.0829390000 0.0935630000 0.0329040000 0.1620800000 0.0017530000 115275315 0 402718720 3.9482223988 3.9886269569 4.0932617188 288 1305031239.1109058857 0.1041481569 0.0773178517 0.1594838947 0.0262780540 0.3251960000 0.0907710000 0.0700010000 0.0000010000 0.1621560000 0.0017420000 115279211 0 402718720 3.9479749203 3.9860832691 4.0940680504 289 1305031239.1417789459 0.1054509878 0.0774151982 0.1594838947 0.0262436890 0.5265790000 0.0743470000 0.0858640000 0.0327960000 0.1622500000 0.1707480000 115282883 0 402718720 3.9470875263 3.9842383862 4.0939912796 290 1305031239.1757500172 0.1056288183 0.0775124866 0.1594838947 0.0262347063 0.3471210000 0.0875750000 0.0943560000 0.0000010000 0.1629310000 0.0017360000 115286667 0 402718720 3.9457759857 3.9833574295 4.0898432732 291 1305031239.2096450329 0.1023397520 0.0775978036 0.1594838947 0.0261981909 0.3423370000 0.0748350000 0.0703620000 0.0327160000 0.1621410000 0.0017550000 115290451 0 402718720 3.9466547966 3.9862179756 4.0876007080 292 1305031239.2417099476 0.1024958417 0.0776830709 0.1594838947 0.0261703902 0.3116520000 0.0750520000 0.0720890000 0.0000000000 0.1622300000 0.0017450000 115294179 0 402718720 3.9456961155 3.9851787090 4.0849742889 293 1305031239.2738199234 0.0999998227 0.0777592373 0.1594838947 0.0261448935 0.5564050000 0.0962870000 0.0953390000 0.0326560000 0.1617340000 0.1698580000 115297907 0 402718720 3.9462914467 3.9863121510 4.0825605392 294 1305031239.3101770878 0.0984089002 0.0778294742 0.1594838947 0.0261011552 0.3380890000 0.0761970000 0.0986260000 0.0000010000 0.1609880000 0.0017430000 115301803 0 402718720 3.9464890957 3.9869365692 4.0798082352 295 1305031239.3419699669 0.0949563533 0.0778875314 0.1594838947 0.0260621248 0.3515480000 0.0759800000 0.0816230000 0.0324930000 0.1590510000 0.0018440000 115305531 0 402718720 3.9477059841 3.9893486500 4.0773706436 296 1305031239.3750240803 0.0917521045 0.0779343712 0.1594838947 0.0260317337 0.3313040000 0.0749200000 0.0963350000 0.0000000000 0.1576900000 0.0017970000 115309203 0 402718720 3.9484219551 3.9910595417 4.0746774673 297 1305031239.4106309414 0.0876879245 0.0779672115 0.1594838947 0.0259891139 0.5258100000 0.0763360000 0.0963460000 0.0322650000 0.1562820000 0.1640460000 115312987 0 402718720 3.9490983486 3.9940688610 4.0720615387 298 1305031239.4415419102 0.0878989846 0.0780005396 0.1594838947 0.0259484193 0.3949080000 0.1022160000 0.1209190000 0.0000000000 0.1687980000 0.0023740000 115316659 0 402718720 3.9512515068 3.9924108982 4.0710916519 299 1305031239.4733181000 0.0800415874 0.0780073658 0.1594838947 0.0259089188 0.4087670000 0.0965730000 0.1200710000 0.0359520000 0.1538780000 0.0017570000 115320331 0 402718720 3.9527530670 3.9993197918 4.0683922768 300 1305031239.5097389221 0.0746797845 0.0779962739 0.1594838947 0.0258708549 0.3212400000 0.0762170000 0.0888850000 0.0000000000 0.1538540000 0.0017390000 115324115 0 402718720 3.9557290077 4.0041785240 4.0662074089 301 1305031239.5438020229 0.0709898919 0.0779729969 0.1594838947 0.0258363449 0.5108560000 0.0763130000 0.0882320000 0.0319840000 0.1529610000 0.1608210000 115327899 0 402718720 3.9565665722 4.0068783760 4.0627436638 302 1305031239.5761160851 0.0688320249 0.0779427287 0.1594838947 0.0258015787 0.2983880000 0.0770270000 0.0664570000 0.0000000000 0.1526120000 0.0017420000 115331571 0 402718720 3.9574930668 4.0086178780 4.0598497391 303 1305031239.6111609936 0.0671854094 0.0779072260 0.1594838947 0.0257626055 0.3640000000 0.1053480000 0.0737700000 0.0314440000 0.1511190000 0.0017590000 115335355 0 402718720 3.9588384628 4.0100975037 4.0569272041 304 1305031239.6414220333 0.0670190156 0.0778714096 0.1594838947 0.0257232111 0.3091440000 0.0788920000 0.0776470000 0.0000010000 0.1502920000 0.0017540000 115338971 0 402718720 3.9598078728 4.0100564957 4.0534749031 305 1305031239.6710560322 0.0638276041 0.0778253643 0.1594838947 0.0256964710 0.5119050000 0.0792450000 0.0935170000 0.0319210000 0.1499520000 0.1566910000 115342531 0 402718720 3.9598288536 4.0135879517 4.0499963760 306 1305031239.7075550556 0.0625922158 0.0777755828 0.1594838947 0.0256918146 0.3279400000 0.0792840000 0.0945280000 0.0000000000 0.1516960000 0.0018460000 115346315 0 402718720 3.9657475948 4.0144820213 4.0494713783 307 1305031239.7417550087 0.0630552173 0.0777276337 0.1594838947 0.0256512330 0.3314770000 0.0794880000 0.0559210000 0.0319530000 0.1617710000 0.0017780000 115350099 0 402718720 3.9660677910 4.0135483742 4.0450081825 308 1305031239.7712600231 0.0629684553 0.0776797143 0.1594838947 0.0256112223 0.3545470000 0.0917000000 0.0857730000 0.0000000000 0.1747300000 0.0017700000 115353659 0 402718720 3.9728422165 4.0145497322 4.0448145866 309 1305031239.8060870171 0.0640768707 0.0776356921 0.1594838947 0.0256502448 0.5571420000 0.0789020000 0.0666600000 0.0321620000 0.1858640000 0.1929870000 115357387 0 402718720 3.9809620380 4.0143265724 4.0446195602 310 1305031239.8392889500 0.0594057366 0.0775768858 0.1594838947 0.0256629287 0.3542710000 0.0780620000 0.0670050000 0.0000010000 0.2068250000 0.0018130000 115361115 0 402718720 3.9806106091 4.0218129158 4.0418200493 311 1305031239.8744299412 0.0573903508 0.0775119773 0.1594838947 0.0256282976 0.4348530000 0.0896730000 0.0880790000 0.0322310000 0.2224680000 0.0018330000 115364787 0 402718720 3.9811205864 4.0253467560 4.0405340195 312 1305031239.9090619087 0.0596994944 0.0774548861 0.1594838947 0.0256317301 0.3772440000 0.0772780000 0.0516930000 0.0000000000 0.2451820000 0.0024520000 115368571 0 402718720 3.9872612953 4.0275015831 4.0412178040 313 1305031239.9403729439 0.0617336743 0.0774046585 0.1594838947 0.0256174525 0.7495620000 0.0973800000 0.0786300000 0.0410750000 0.2657930000 0.2661160000 115372187 0 402718720 3.9918098450 4.0313968658 4.0417642593 314 1305031239.9710669518 0.0653923303 0.0773664027 0.1594838947 0.0256310073 0.4297490000 0.0763080000 0.0888940000 0.0000010000 0.2621620000 0.0018190000 115375859 0 402718720 3.9976253510 4.0353231430 4.0443949699 315 1305031240.0088651180 0.0699790269 0.0773429507 0.1594838947 0.0256563342 0.4441320000 0.0758880000 0.0622990000 0.0331870000 0.2701580000 0.0020000000 115379755 0 402718720 4.0029191971 4.0329670906 4.0428161621 316 1305031240.0396599770 0.0762730911 0.0773395651 0.1594838947 0.0256220897 0.4288420000 0.0757870000 0.0662060000 0.0000010000 0.2843640000 0.0019120000 115383315 0 402718720 4.0100450516 4.0334405899 4.0424871445 317 1305031240.0711870193 0.0837013647 0.0773596339 0.1594838947 0.0255827217 0.7588630000 0.0749080000 0.0546450000 0.0342200000 0.2920650000 0.3024450000 115386987 0 402718720 4.0182976723 4.0319423676 4.0435891151 318 1305031240.1093459129 0.0899581611 0.0773992519 0.1594838947 0.0255959928 0.4729600000 0.0890230000 0.0739680000 0.0000000000 0.3074700000 0.0019140000 115390827 0 402718720 4.0251326561 4.0272464752 4.0400762558 319 1305031240.1435019970 0.0977027640 0.0774628993 0.1594838947 0.0256164419 0.5182910000 0.0731580000 0.0859540000 0.0348150000 0.3218510000 0.0019330000 115394611 0 402718720 4.0330939293 4.0218439102 4.0333585739 320 1305031240.1775770187 0.1010773107 0.0775366943 0.1594838947 0.0255878938 0.4841390000 0.0723820000 0.0752830000 0.0000000000 0.3339640000 0.0019250000 115398283 0 402718720 4.0364542007 4.0287022591 4.0334916115 321 1305031240.2093310356 0.1060130671 0.0776254057 0.1594838947 0.0256340274 0.8962970000 0.0713700000 0.0899290000 0.0344770000 0.3448620000 0.3550830000 115402011 0 402718720 4.0413875580 4.0285415649 4.0270633698 322 1305031240.2410049438 0.1080452651 0.0777198773 0.1594838947 0.0256204544 0.5043100000 0.0722280000 0.0688040000 0.0000000000 0.3607400000 0.0019500000 115405627 0 402718720 4.0409846306 4.0365033150 4.0182881355 323 1305031240.2774341106 0.1111755669 0.0778234553 0.1594838947 0.0255898494 0.5836700000 0.0823870000 0.0925760000 0.0359150000 0.3702470000 0.0019560000 115409411 0 402718720 4.0415053368 4.0509285927 4.0224738121 324 1305031240.3089289665 0.1118836254 0.0779285793 0.1594838947 0.0255629205 0.5619550000 0.0927350000 0.0830430000 0.0000000000 0.3836190000 0.0019670000 115413027 0 402718720 4.0373735428 4.0594000816 4.0139322281 325 1305031240.3422729969 0.1157391071 0.0780449194 0.1594838947 0.0255533334 0.9945540000 0.0708280000 0.0786330000 0.0362360000 0.3962930000 0.4119810000 115416755 0 402718720 4.0305619240 4.0790958405 4.0171074867 326 1305031240.3774259090 0.1224000007 0.0781809779 0.1594838947 0.0255662738 0.5690840000 0.0684530000 0.0906960000 0.0000010000 0.4074170000 0.0019270000 115420539 0 402718720 4.0232744217 4.0974345207 4.0200977325 327 1305031240.4091110229 0.1249317974 0.0783239468 0.1594838947 0.0255351165 0.6123460000 0.0702950000 0.0900020000 0.0364000000 0.4130780000 0.0019750000 115424155 0 402718720 4.0108094215 4.1102271080 4.0154151917 328 1305031240.4417860508 0.1350894421 0.0784970123 0.1594838947 0.0255053975 0.5840150000 0.0906610000 0.0732570000 0.0000010000 0.4174980000 0.0020030000 115427883 0 402718720 4.0022907257 4.1267595291 4.0203008652 329 1305031240.4776389599 0.1459030509 0.0787018939 0.1594838947 0.0254769707 1.0574110000 0.0683960000 0.0884130000 0.0366690000 0.4226770000 0.4406690000 115431667 0 402718720 3.9953162670 4.1414551735 4.0257349014 330 1305031240.5084490776 0.1514376849 0.0789223054 0.1594838947 0.0254515621 0.5850450000 0.0683020000 0.0859000000 0.0000000000 0.4282580000 0.0019820000 115435227 0 402718720 3.9920308590 4.1480464935 4.0259299278 331 1305031240.5412700176 0.1615040898 0.0791717972 0.1615040898 0.0254542031 0.5928550000 0.0663230000 0.0581070000 0.0365990000 0.4292500000 0.0019780000 115438955 0 402718720 3.9841744900 4.1605544090 4.0325942039 332 1305031240.5759088993 0.1675468832 0.0794379872 0.1675468832 0.0254289513 0.6096640000 0.0932690000 0.0860130000 0.0000010000 0.4278070000 0.0019630000 115442739 0 402718720 3.9851016998 4.1656827927 4.0383076668 333 1305031240.6101338863 0.1653440148 0.0796959633 0.1675468832 0.0254022759 1.0636920000 0.0676150000 0.0865950000 0.0369540000 0.4265910000 0.4453430000 115446467 0 402718720 3.9871368408 4.1630320549 4.0390481949 334 1305031240.6398229599 0.1618638933 0.0799419750 0.1675468832 0.0253878848 0.5821430000 0.0684700000 0.0891780000 0.0000010000 0.4219070000 0.0019770000 115450027 0 402718720 3.9917695522 4.1579914093 4.0416145325 335 1305031240.6747570038 0.1521810740 0.0801576141 0.1675468832 0.0253581431 0.6170360000 0.0686330000 0.0936250000 0.0366810000 0.4155350000 0.0019570000 115453811 0 402718720 4.0000658035 4.1457033157 4.0409889221 336 1305031240.7079319954 0.1468366086 0.0803560635 0.1675468832 0.0253535101 0.5864600000 0.0825970000 0.0893480000 0.0000000000 0.4119750000 0.0019270000 115457539 0 402718720 4.0028142929 4.1392440796 4.0434269905 337 1305031240.7439579964 0.1443773955 0.0805460378 0.1675468832 0.0253267435 0.9968980000 0.0705010000 0.0754170000 0.0364150000 0.4004010000 0.4135640000 115461211 0 402718720 4.0079593658 4.1353306770 4.0490641594 338 1305031240.7768330574 0.1328160465 0.0807006828 0.1675468832 0.0252988108 0.5548260000 0.0704300000 0.0883970000 0.0000010000 0.3934260000 0.0019570000 115464995 0 402718720 4.0125842094 4.1209182739 4.0441861153 339 1305031240.8096249104 0.1291012615 0.0808434574 0.1675468832 0.0252815066 0.5885770000 0.0711460000 0.0963430000 0.0362020000 0.3821790000 0.0020670000 115468667 0 402718720 4.0137972832 4.1165933609 4.0469756126 340 1305031240.8425960541 0.1244413778 0.0809716865 0.1675468832 0.0252658232 0.5596130000 0.0910010000 0.0907450000 0.0000000000 0.3752940000 0.0019500000 115472339 0 402718720 4.0175623894 4.1097035408 4.0516362190 341 1305031240.8794100285 0.1112081558 0.0810603565 0.1675468832 0.0252442945 0.9149660000 0.0720780000 0.0646060000 0.0358800000 0.3656510000 0.3761290000 115476179 0 402718720 4.0200681686 4.0921416283 4.0446410179 342 1305031240.9084498882 0.1043237150 0.0811283781 0.1675468832 0.0252269970 0.5019550000 0.0721380000 0.0724000000 0.0000000000 0.3547260000 0.0020450000 115479795 0 402718720 4.0197257996 4.0839905739 4.0458970070 343 1305031240.9423189163 0.0867061466 0.0811446398 0.1675468832 0.0252374200 0.5634930000 0.0898420000 0.0895230000 0.0354640000 0.3460940000 0.0019410000 115483467 0 402718720 4.0058298111 4.0734696388 4.0390534401 344 1305031240.9779360294 0.0772463083 0.0811333074 0.1675468832 0.0252124108 0.4830180000 0.0726280000 0.0782590000 0.0000000000 0.3295780000 0.0019220000 115487251 0 402718720 4.0044169426 4.0599851608 4.0370631218 345 1305031241.0083029270 0.0711744204 0.0811044411 0.1675468832 0.0253050779 0.8453830000 0.0733580000 0.0878180000 0.0347960000 0.3207640000 0.3280230000 115490867 0 402718720 4.0000443459 4.0599813461 4.0428647995 346 1305031241.0401480198 0.0665623397 0.0810624119 0.1675468832 0.0252849080 0.4632940000 0.0860450000 0.0720050000 0.0000000000 0.3026880000 0.0019150000 115494427 0 402718720 3.9970121384 4.0633378029 4.0546607971 347 1305031241.0759329796 0.0587931648 0.0809982354 0.1675468832 0.0252706774 0.4530350000 0.0756380000 0.0524710000 0.0335680000 0.2888280000 0.0019000000 115498267 0 402718720 3.9907867908 4.0613136292 4.0531425476 348 1305031241.1065559387 0.0527410097 0.0809170364 0.1675468832 0.0252434241 0.4468740000 0.0770470000 0.0930030000 0.0000000000 0.2742820000 0.0018990000 115501883 0 402718720 3.9834227562 4.0639986992 4.0567235947 349 1305031241.1400520802 0.0477525294 0.0808220092 0.1675468832 0.0252369611 0.7068110000 0.0776060000 0.0729960000 0.0329080000 0.2579260000 0.2647380000 115505555 0 402718720 3.9773559570 4.0648488998 4.0568332672 350 1305031241.1781818867 0.0430785343 0.0807141707 0.1675468832 0.0252399646 0.3973290000 0.0798040000 0.0730820000 0.0000010000 0.2419410000 0.0018670000 115509395 0 402718720 3.9747953415 4.0620040894 4.0569748878 351 1305031241.2106790543 0.0377051793 0.0805916380 0.1675468832 0.0252105807 0.4191210000 0.0785050000 0.0789940000 0.0320680000 0.2270950000 0.0018200000 115513123 0 402718720 3.9670448303 4.0586647987 4.0538611412 352 1305031241.2393150330 0.0374610685 0.0804691079 0.1675468832 0.0252523620 0.3503260000 0.0777480000 0.0602420000 0.0000010000 0.2098670000 0.0018240000 115516627 0 402718720 3.9677364826 4.0526413918 4.0530390739 353 1305031241.2768468857 0.0369863398 0.0803459273 0.1675468832 0.0252396836 0.6064970000 0.0908410000 0.0912200000 0.0323520000 0.1923070000 0.1991000000 115520523 0 402718720 3.9675180912 4.0490283966 4.0533790588 354 1305031241.3063299656 0.0356716104 0.0802197287 0.1675468832 0.0252057157 0.3522330000 0.0795710000 0.0925730000 0.0000010000 0.1776570000 0.0017960000 115524139 0 402718720 3.9655728340 4.0494565964 4.0549435616 355 1305031241.3424758911 0.0348575786 0.0800919480 0.1675468832 0.0251930374 0.3409970000 0.0792660000 0.0513820000 0.0319520000 0.1752820000 0.0023950000 115527923 0 402718720 3.9698765278 4.0471501350 4.0611686707 356 1305031241.3795149326 0.0399640128 0.0799792290 0.1675468832 0.0252328910 0.3500740000 0.1004780000 0.0806160000 0.0000010000 0.1658670000 0.0023850000 115531707 0 402718720 3.9675416946 4.0404396057 4.0606789589 357 1305031241.4096820354 0.0438272953 0.0798779631 0.1675468832 0.0252148671 0.5160570000 0.1004350000 0.0769530000 0.0318510000 0.1499180000 0.1562430000 115535323 0 402718720 3.9673743248 4.0377225876 4.0631451607 358 1305031241.4455459118 0.0470470823 0.0797862567 0.1675468832 0.0251934665 0.3062250000 0.0978330000 0.0564630000 0.0000010000 0.1493770000 0.0018710000 115539107 0 402718720 3.9673130512 4.0368089676 4.0680279732 359 1305031241.4775071144 0.0510661937 0.0797062566 0.1675468832 0.0253684132 0.3424250000 0.0782160000 0.0792760000 0.0319240000 0.1505900000 0.0017590000 115542779 0 402718720 3.9660143852 4.0328998566 4.0704841614 360 1305031241.5098490715 0.0552950129 0.0796384476 0.1675468832 0.0253648891 0.3185050000 0.0771970000 0.0882680000 0.0000010000 0.1506450000 0.0017340000 115546451 0 402718720 3.9618303776 4.0289111137 4.0690736771 361 1305031241.5477299690 0.0584962703 0.0795798820 0.1675468832 0.0253404961 0.5058130000 0.0769690000 0.0884620000 0.0319600000 0.1501670000 0.1576010000 115550347 0 402718720 3.9583950043 4.0263996124 4.0656609535 362 1305031241.5783948898 0.0583972745 0.0795213665 0.1675468832 0.0253224038 0.3026100000 0.0770170000 0.0741480000 0.0000010000 0.1490490000 0.0017390000 115553907 0 402718720 3.9600253105 4.0263695717 4.0669188499 363 1305031241.6092638969 0.0597163662 0.0794668073 0.1675468832 0.0253205632 0.3635490000 0.0882290000 0.0924650000 0.0320050000 0.1483300000 0.0018250000 115557523 0 402718720 3.9604947567 4.0250043869 4.0643577576 364 1305031241.6475839615 0.0623925105 0.0794198998 0.1675468832 0.0252904333 0.3463980000 0.1025280000 0.0934710000 0.0000000000 0.1478680000 0.0018370000 115561419 0 402718720 3.9610521793 4.0213394165 4.0620050430 365 1305031241.6783659458 0.0560827330 0.0793559624 0.1675468832 0.0253210265 0.4834640000 0.0780450000 0.0669890000 0.0319160000 0.1495620000 0.1562820000 115565091 0 402718720 3.9628319740 4.0277514458 4.0615768433 366 1305031241.7098269463 0.0554937720 0.0792907652 0.1675468832 0.0252929916 0.2893580000 0.0779760000 0.0592650000 0.0000010000 0.1497180000 0.0017400000 115568651 0 402718720 3.9628546238 4.0283222198 4.0593266487 367 1305031241.7471020222 0.0536564998 0.0792209170 0.1675468832 0.0252628887 0.3467740000 0.0761600000 0.0872740000 0.0312130000 0.1497140000 0.0017470000 115572547 0 402718720 3.9634604454 4.0296745300 4.0582470894 368 1305031241.7782680988 0.0539337546 0.0791522019 0.1675468832 0.0252437172 0.3355560000 0.0983500000 0.0856360000 0.0000000000 0.1491570000 0.0017390000 115576219 0 402718720 3.9640953541 4.0293459892 4.0568852425 369 1305031241.8098289967 0.0510132201 0.0790759445 0.1675468832 0.0252426017 0.5044880000 0.0764060000 0.0917780000 0.0318190000 0.1489390000 0.1548390000 115579779 0 402718720 3.9635334015 4.0323591232 4.0565085411 370 1305031241.8464360237 0.0540163256 0.0790082158 0.1675468832 0.0252505126 0.3305830000 0.0786800000 0.0886250000 0.0000000000 0.1601400000 0.0023750000 115583619 0 402718720 3.9627516270 4.0288033485 4.0536785126 371 1305031241.8787989616 0.0532705225 0.0789388420 0.1675468832 0.0253218339 0.3525440000 0.1008340000 0.0644980000 0.0319380000 0.1528330000 0.0017680000 115587347 0 402718720 3.9612479210 4.0299382210 4.0523457527 372 1305031241.9114871025 0.0480248593 0.0788557399 0.1675468832 0.0253517972 0.3060910000 0.0788040000 0.0712370000 0.0000010000 0.1534990000 0.0018380000 115591019 0 402718720 3.9637837410 4.0353860855 4.0554208755 373 1305031241.9477050304 0.0489715151 0.0787756213 0.1675468832 0.0253367433 0.5028990000 0.0787280000 0.0744620000 0.0320260000 0.1552770000 0.1617340000 115594803 0 402718720 3.9641973972 4.0344820023 4.0548844337 374 1305031241.9783430099 0.0480709076 0.0786935231 0.1675468832 0.0254434871 0.3324930000 0.0784990000 0.0972520000 0.0000000000 0.1541970000 0.0018480000 115598475 0 402718720 3.9643349648 4.0356535912 4.0551476479 375 1305031242.0105700493 0.0468432456 0.0786085891 0.1675468832 0.0255245884 0.3311160000 0.0775300000 0.0649740000 0.0320450000 0.1541270000 0.0017600000 115602091 0 402718720 3.9612116814 4.0372414589 4.0536804199 376 1305031242.0463600159 0.0478872098 0.0785268833 0.1675468832 0.0255797417 0.2933340000 0.0770930000 0.0596110000 0.0000010000 0.1542000000 0.0017490000 115605875 0 402718720 3.9574692249 4.0362825394 4.0513067245 377 1305031242.0795490742 0.0506051667 0.0784528204 0.1675468832 0.0256636536 0.4841760000 0.0766400000 0.0592800000 0.0319940000 0.1538850000 0.1617000000 115609547 0 402718720 3.9514868259 4.0339074135 4.0469841957 378 1305031242.1105840206 0.0543702953 0.0783891100 0.1675468832 0.0257217307 0.2977700000 0.0893450000 0.0519070000 0.0000010000 0.1540860000 0.0017350000 115613219 0 402718720 3.9467551708 4.0301623344 4.0433130264 379 1305031242.1466050148 0.0582283139 0.0783359153 0.1675468832 0.0258147409 0.3452270000 0.0982150000 0.0592310000 0.0320110000 0.1533230000 0.0017530000 115617003 0 402718720 3.9434592724 4.0261850357 4.0404901505 380 1305031242.1797080040 0.0646216348 0.0782998251 0.1675468832 0.0258934069 0.3184140000 0.0758550000 0.0873990000 0.0000010000 0.1527220000 0.0017380000 115620731 0 402718720 3.9368968010 4.0200195312 4.0359268188 381 1305031242.2087249756 0.0688413680 0.0782749997 0.1675468832 0.0259193375 0.5226440000 0.0888440000 0.0871110000 0.0313240000 0.1531070000 0.1615470000 115624291 0 402718720 3.9339828491 4.0146398544 4.0338892937 382 1305031242.2478089333 0.0725933313 0.0782601262 0.1675468832 0.0259634683 0.3147940000 0.0731960000 0.0857060000 0.0000010000 0.1535130000 0.0016850000 115628187 0 402718720 3.9313805103 4.0097627640 4.0317668915 383 1305031242.2794981003 0.0740770698 0.0782492044 0.1675468832 0.0259960870 0.3809810000 0.0963790000 0.0959590000 0.0321440000 0.1540580000 0.0017410000 115631859 0 402718720 3.9300620556 4.0079717636 4.0300941467 384 1305031242.3097639084 0.0771192834 0.0782462619 0.1675468832 0.0260018352 0.3040600000 0.0738640000 0.0730070000 0.0000010000 0.1547480000 0.0017380000 115635419 0 402718720 3.9287483692 4.0039434433 4.0280032158 385 1305031242.3471269608 0.0783686787 0.0782465799 0.1675468832 0.0260823834 0.5001380000 0.0744660000 0.0729360000 0.0321480000 0.1555430000 0.1643420000 115639315 0 402718720 3.9291937351 4.0009498596 4.0266718864 386 1305031242.3784790039 0.0780358315 0.0782460339 0.1675468832 0.0261745445 0.2845620000 0.0745580000 0.0514820000 0.0000000000 0.1560910000 0.0017270000 115642987 0 402718720 3.9285695553 4.0002722740 4.0258426666 387 1305031242.4109969139 0.0797387511 0.0782498910 0.1675468832 0.0262182797 0.3298620000 0.0733510000 0.0653410000 0.0321980000 0.1565160000 0.0017470000 115646659 0 402718720 3.9282782078 3.9971127510 4.0241336823 388 1305031242.4470989704 0.0805788264 0.0782558935 0.1675468832 0.0263366176 0.3108610000 0.0861840000 0.0651450000 0.0000010000 0.1569510000 0.0018480000 115650499 0 402718720 3.9269919395 3.9949553013 4.0215454102 389 1305031242.4776470661 0.0814528912 0.0782641120 0.1675468832 0.0264168834 0.5163530000 0.0755440000 0.0812560000 0.0321850000 0.1587330000 0.1679260000 115654171 0 402718720 3.9257857800 3.9941501617 4.0183682442 390 1305031242.5097260475 0.0852187648 0.0782819444 0.1675468832 0.0266092388 0.2986550000 0.0756320000 0.0592100000 0.0000010000 0.1613400000 0.0017660000 115657843 0 402718720 3.9217827320 3.9907250404 4.0131044388 391 1305031242.5485460758 0.0837611035 0.0782959576 0.1675468832 0.0270194164 0.3389130000 0.0751330000 0.0664130000 0.0315750000 0.1633160000 0.0017690000 115661739 0 402718720 3.9201133251 3.9925570488 4.0107612610 392 1305031242.5748429298 0.0849244297 0.0783128670 0.1675468832 0.0271321967 0.3108050000 0.0762620000 0.0669260000 0.0000010000 0.1651470000 0.0017640000 115665187 0 402718720 3.9176702499 3.9930372238 4.0076041222 393 1305031242.6061151028 0.0907734036 0.0783445732 0.1675468832 0.0271865617 0.5275260000 0.0899920000 0.0642290000 0.0322740000 0.1652450000 0.1750450000 115668915 0 402718720 3.9099228382 3.9904465675 4.0012154579 394 1305031242.6438109875 0.0929386690 0.0783816140 0.1675468832 0.0273843282 0.3187670000 0.0971920000 0.0513960000 0.0000010000 0.1676970000 0.0017570000 115672755 0 402718720 3.9067449570 3.9898941517 3.9977664948 395 1305031242.6752018929 0.0923164710 0.0784168921 0.1675468832 0.0276598359 0.3459810000 0.0743120000 0.0722390000 0.0315330000 0.1653150000 0.0018280000 115676483 0 402718720 3.9054093361 3.9908206463 3.9966185093 396 1305031242.7139821053 0.0933243185 0.0784545371 0.1675468832 0.0279826596 0.3172850000 0.0750570000 0.0731340000 0.0000010000 0.1665250000 0.0018290000 115680435 0 402718720 3.9020109177 3.9914338589 3.9948563576 397 1305031242.7452580929 0.0961833969 0.0784991942 0.1675468832 0.0280349286 0.5184430000 0.0762380000 0.0664410000 0.0322950000 0.1666890000 0.1760510000 115684107 0 402718720 3.8980841637 3.9914414883 3.9916119576 398 1305031242.7775399685 0.1001001671 0.0785534680 0.1675468832 0.0281627672 0.3616400000 0.0954800000 0.0961460000 0.0000010000 0.1675030000 0.0017760000 115687835 0 402718720 3.8921296597 3.9896676540 3.9884402752 399 1305031242.8140709400 0.0982050449 0.0786027201 0.1675468832 0.0283522003 0.3631390000 0.0751910000 0.0799950000 0.0323320000 0.1724090000 0.0023930000 115691675 0 402718720 3.8936796188 3.9929425716 3.9897580147 400 1305031242.8443179131 0.1000656709 0.0786563775 0.1675468832 0.0283819981 0.3510810000 0.0927630000 0.0873410000 0.0000010000 0.1684760000 0.0017690000 115695347 0 402718720 3.8904356956 3.9934999943 3.9887208939 401 1305031242.8740880489 0.1056433320 0.0787236766 0.1675468832 0.0284048644 0.5482470000 0.0741430000 0.0959550000 0.0323650000 0.1676590000 0.1774000000 115699075 0 402718720 3.8838043213 3.9903631210 3.9869940281 402 1305031242.9137070179 0.1130426377 0.0788090472 0.1675468832 0.0284642931 0.3473930000 0.0869000000 0.0872140000 0.0000010000 0.1707860000 0.0017630000 115703083 0 402718720 3.8744654655 3.9897425175 3.9827105999 403 1305031242.9444379807 0.1122966856 0.0788921430 0.1675468832 0.0286010765 0.3713470000 0.0870760000 0.0812510000 0.0317900000 0.1686050000 0.0018660000 115706755 0 402718720 3.8733990192 3.9941043854 3.9830315113 404 1305031242.9760620594 0.1155995727 0.0789830030 0.1675468832 0.0286377955 0.3335760000 0.0750040000 0.0858110000 0.0000010000 0.1702560000 0.0017760000 115710427 0 402718720 3.8649687767 3.9971218109 3.9806692600 405 1305031243.0141661167 0.1193846762 0.0790827602 0.1675468832 0.0286816618 0.5439060000 0.0735540000 0.0947810000 0.0317150000 0.1670350000 0.1760570000 115714323 0 402718720 3.8587083817 3.9979810715 3.9799790382 406 1305031243.0469100475 0.1189355999 0.0791809199 0.1675468832 0.0286754173 0.3359760000 0.0718070000 0.0943000000 0.0000010000 0.1673560000 0.0017720000 115718219 0 402718720 3.8570413589 4.0005941391 3.9808878899 407 1305031243.0780448914 0.1197378039 0.0792805683 0.1675468832 0.0286617200 0.3264670000 0.0734590000 0.0516610000 0.0317200000 0.1670990000 0.0017780000 115721947 0 402718720 3.8541595936 4.0028929710 3.9803597927 408 1305031243.1136150360 0.1210593581 0.0793829673 0.1675468832 0.0286607779 0.3539010000 0.1037750000 0.0786600000 0.0000010000 0.1688020000 0.0018730000 115725731 0 402718720 3.8497946262 4.0055694580 3.9789943695 409 1305031243.1458160877 0.1237049550 0.0794913340 0.1675468832 0.0286306592 0.5095370000 0.0707770000 0.0608850000 0.0319220000 0.1682380000 0.1769540000 115729515 0 402718720 3.8440604210 4.0082983971 3.9759595394 410 1305031243.1780760288 0.1229627281 0.0795973618 0.1675468832 0.0286172371 0.3066620000 0.0735890000 0.0617460000 0.0000010000 0.1686710000 0.0018740000 115733243 0 402718720 3.8425748348 4.0100741386 3.9750316143 411 1305031243.2136580944 0.1172510460 0.0796889766 0.1675468832 0.0286279337 0.3532860000 0.0727940000 0.0806870000 0.0320820000 0.1650750000 0.0018670000 115737083 0 402718720 3.8490991592 4.0087685585 3.9790720940 412 1305031243.2455608845 0.1190747097 0.0797845730 0.1675468832 0.0288876610 0.3237590000 0.0864400000 0.0693390000 0.0000000000 0.1654590000 0.0017630000 115740811 0 402718720 3.8501117229 4.0046000481 3.9786622524 413 1305031243.2781798840 0.1121570393 0.0798629567 0.1675468832 0.0289526261 0.5472360000 0.0951610000 0.0811080000 0.0316760000 0.1648560000 0.1736470000 115744595 0 402718720 3.8622374535 4.0044498444 3.9816648960 414 1305031243.3142709732 0.1154237092 0.0799488523 0.1675468832 0.0289917611 0.3392020000 0.0717740000 0.0982350000 0.0000000000 0.1666690000 0.0017710000 115748379 0 402718720 3.8599612713 3.9988505840 3.9835059643 415 1305031243.3460359573 0.1155136526 0.0800345506 0.1675468832 0.0292979765 0.3604970000 0.0741460000 0.0859700000 0.0323340000 0.1655190000 0.0017750000 115752163 0 402718720 3.8635377884 3.9966878891 3.9846904278 416 1305031243.3789350986 0.1089314595 0.0801040143 0.1675468832 0.0293308618 0.3202210000 0.0748240000 0.0770620000 0.0000010000 0.1658010000 0.0017730000 115755947 0 402718720 3.8751883507 4.0002293587 3.9888124466 417 1305031243.4139740467 0.1140025109 0.0801853057 0.1675468832 0.0294081153 0.5410740000 0.0737790000 0.0969650000 0.0321630000 0.1643930000 0.1730030000 115759731 0 402718720 3.8660717010 3.9995276928 3.9881329536 418 1305031243.4470911026 0.1076558158 0.0802510246 0.1675468832 0.0296057652 0.3478850000 0.0867170000 0.0963450000 0.0000010000 0.1621540000 0.0018650000 115763515 0 402718720 3.8772814274 4.0036401749 3.9925179482 419 1305031243.4780371189 0.1084342822 0.0803182877 0.1675468832 0.0296335366 0.3478650000 0.0767950000 0.0732850000 0.0323690000 0.1628670000 0.0017840000 115767187 0 402718720 3.8761565685 4.0068655014 3.9925985336 420 1305031243.5154008865 0.1094996557 0.0803877672 0.1675468832 0.0297346600 0.3209230000 0.0762820000 0.0788490000 0.0000010000 0.1632540000 0.0017670000 115771083 0 402718720 3.8705263138 4.0113801956 3.9925456047 421 1305031243.5459430218 0.1076990142 0.0804526395 0.1675468832 0.0297845869 0.5381490000 0.0769670000 0.0917560000 0.0322320000 0.1634760000 0.1729450000 115774811 0 402718720 3.8723912239 4.0148758888 3.9937326908 422 1305031243.5779840946 0.1030720547 0.0805062400 0.1675468832 0.0297756340 0.3397650000 0.0778110000 0.0997240000 0.0000010000 0.1596780000 0.0017770000 115778427 0 402718720 3.8742983341 4.0205464363 3.9968283176 423 1305031243.6140549183 0.1008899882 0.0805544286 0.1675468832 0.0300221078 0.3456860000 0.0950870000 0.0581270000 0.0322700000 0.1575210000 0.0018700000 115782211 0 402718720 3.8757398129 4.0245823860 3.9983980656 424 1305031243.6461870670 0.1038303599 0.0806093246 0.1675468832 0.0302881419 0.3411490000 0.0797830000 0.1004630000 0.0000000000 0.1583780000 0.0017380000 115785995 0 402718720 3.8737235069 4.0222110748 3.9959366322 425 1305031243.6782801151 0.1081431657 0.0806741101 0.1675468832 0.0303149235 0.5661540000 0.0979130000 0.0991480000 0.0321670000 0.1641830000 0.1719610000 115789667 0 402718720 3.8687412739 4.0182070732 3.9938828945 426 1305031243.7142961025 0.0987639800 0.0807165746 0.1675468832 0.0306335192 0.3383430000 0.0784340000 0.0864150000 0.0000010000 0.1709170000 0.0017990000 115793395 0 402718720 3.8780181408 4.0269670486 3.9983785152 427 1305031243.7473781109 0.0984757617 0.0807581652 0.1675468832 0.0308731047 0.3766680000 0.0801670000 0.0878190000 0.0322350000 0.1738660000 0.0017930000 115797123 0 402718720 3.8826036453 4.0248861313 3.9985675812 428 1305031243.7790360451 0.0996772572 0.0808023687 0.1675468832 0.0310114682 0.3661390000 0.0903940000 0.0955350000 0.0000010000 0.1774890000 0.0019050000 115800739 0 402718720 3.8819997311 4.0194926262 3.9999063015 429 1305031243.8141930103 0.0899841115 0.0808237714 0.1675468832 0.0314415645 0.5895220000 0.0813560000 0.1039080000 0.0318750000 0.1825610000 0.1890460000 115804467 0 402718720 3.8969049454 4.0238704681 4.0060887337 430 1305031243.8462920189 0.0886892676 0.0808420632 0.1675468832 0.0317377869 0.3776320000 0.0815190000 0.1008780000 0.0000010000 0.1926180000 0.0018260000 115808139 0 402718720 3.9058911800 4.0219268799 4.0080771446 431 1305031243.8788089752 0.0833956972 0.0808479881 0.1675468832 0.0318370564 0.4181890000 0.0793340000 0.0991100000 0.0322600000 0.2048580000 0.0018380000 115811867 0 402718720 3.9132456779 4.0240273476 4.0124402046 432 1305031243.9140000343 0.0746706352 0.0808336887 0.1675468832 0.0320287169 0.3955150000 0.0796970000 0.0977290000 0.0000010000 0.2154620000 0.0018310000 115815539 0 402718720 3.9232189655 4.0285539627 4.0196986198 433 1305031243.9470779896 0.0645311847 0.0807960386 0.1675468832 0.0321344551 0.6417330000 0.0954910000 0.0598420000 0.0329580000 0.2221030000 0.2305320000 115819323 0 402718720 3.9348526001 4.0369696617 4.0293078423 434 1305031243.9816520214 0.0565168187 0.0807400957 0.1675468832 0.0322126390 0.3904720000 0.0921870000 0.0636720000 0.0000010000 0.2319670000 0.0018480000 115823051 0 402718720 3.9426288605 4.0436878204 4.0381851196 435 1305031244.0112700462 0.0531991385 0.0806767831 0.1675468832 0.0322617095 0.4435280000 0.0789810000 0.0920250000 0.0332860000 0.2365720000 0.0018680000 115826667 0 402718720 3.9486191273 4.0483675003 4.0427656174 436 1305031244.0438230038 0.0487034284 0.0806034497 0.1675468832 0.0322691114 0.4532530000 0.0910000000 0.1111880000 0.0000000000 0.2484080000 0.0018560000 115830339 0 402718720 3.9491310120 4.0583748817 4.0453476906 437 1305031244.0818090439 0.0462268032 0.0805247846 0.1675468832 0.0323040651 0.6866650000 0.0883840000 0.0702380000 0.0333830000 0.2434240000 0.2504370000 115834179 0 402718720 3.9466845989 4.0638990402 4.0451383591 438 1305031244.1127901077 0.0479265377 0.0804503594 0.1675468832 0.0323866218 0.4309400000 0.0889500000 0.0948750000 0.0000000000 0.2444610000 0.0018540000 115837851 0 402718720 3.9511468410 4.0634975433 4.0464053154 439 1305031244.1484949589 0.0454276204 0.0803705810 0.1675468832 0.0323767215 0.4401040000 0.0782280000 0.0798020000 0.0332650000 0.2461410000 0.0018650000 115841635 0 402718720 3.9520993233 4.0688862801 4.0494904518 440 1305031244.1824309826 0.0420818888 0.0802835612 0.1675468832 0.0324394294 0.3801220000 0.0765200000 0.0554470000 0.0000000000 0.2455050000 0.0018440000 115845307 0 402718720 3.9545879364 4.0746493340 4.0542240143 441 1305031244.2124009132 0.0424793437 0.0801978374 0.1675468832 0.0325448123 0.6693600000 0.0763460000 0.0636590000 0.0329470000 0.2444900000 0.2511130000 115848979 0 402718720 3.9583125114 4.0773277283 4.0563206673 442 1305031244.2473471165 0.0401310436 0.0801071885 0.1675468832 0.0326916200 0.3855570000 0.0741480000 0.0627790000 0.0000010000 0.2460140000 0.0017950000 115852707 0 402718720 3.9612586498 4.0826730728 4.0590572357 443 1305031244.2831470966 0.0373406596 0.0800106501 0.1675468832 0.0328056482 0.4441690000 0.1056700000 0.0590990000 0.0334780000 0.2432590000 0.0018500000 115856491 0 402718720 3.9660499096 4.0878891945 4.0626764297 444 1305031244.3137950897 0.0364446677 0.0799125285 0.1675468832 0.0329249181 0.3875840000 0.0743270000 0.0668280000 0.0000000000 0.2437670000 0.0018380000 115860051 0 402718720 3.9710738659 4.0953502655 4.0657577515 445 1305031244.3459599018 0.0376134254 0.0798174743 0.1675468832 0.0330812369 0.6628130000 0.0749150000 0.0667130000 0.0331310000 0.2402390000 0.2469980000 115863779 0 402718720 3.9768593311 4.1036386490 4.0686612129 446 1305031244.3808560371 0.0367385522 0.0797208848 0.1675468832 0.0332125184 0.3985860000 0.0919790000 0.0664740000 0.0000010000 0.2374640000 0.0018340000 115867507 0 402718720 3.9784152508 4.1087360382 4.0675153732 447 1305031244.4130189419 0.0410942435 0.0796344717 0.1675468832 0.0333939544 0.4430440000 0.0765850000 0.0964580000 0.0331830000 0.2341570000 0.0018460000 115871179 0 402718720 3.9870753288 4.1165466309 4.0706148148 448 1305031244.4451670647 0.0428748131 0.0795524189 0.1675468832 0.0334563323 0.4047570000 0.0874550000 0.0672120000 0.0000010000 0.2466730000 0.0024880000 115874851 0 402718720 3.9881942272 4.1265287399 4.0696792603 449 1305031244.4806590080 0.0430366434 0.0794710920 0.1675468832 0.0335063210 0.7448670000 0.0967630000 0.1248190000 0.0411820000 0.2431110000 0.2381820000 115878635 0 402718720 3.9869313240 4.1321640015 4.0674529076 450 1305031244.5142281055 0.0444211848 0.0793932034 0.1675468832 0.0336018585 0.3772580000 0.0761830000 0.0712500000 0.0000010000 0.2271790000 0.0018320000 115882363 0 402718720 3.9860613346 4.1367397308 4.0655093193 451 1305031244.5462141037 0.0444576554 0.0793157409 0.1675468832 0.0335840267 0.4310770000 0.0762560000 0.0929220000 0.0328080000 0.2264270000 0.0018410000 115886035 0 402718720 3.9828631878 4.1439604759 4.0661540031 452 1305031244.5808050632 0.0427500121 0.0792348433 0.1675468832 0.0336258133 0.3964570000 0.0768800000 0.0932300000 0.0000010000 0.2236770000 0.0018420000 115889763 0 402718720 3.9801387787 4.1454977989 4.0662150383 453 1305031244.6132769585 0.0419860519 0.0791526164 0.1675468832 0.0337009143 0.6578420000 0.0765790000 0.0984220000 0.0331890000 0.2212190000 0.2276170000 115893491 0 402718720 3.9784488678 4.1470088959 4.0659909248 454 1305031244.6428399086 0.0420859829 0.0790709718 0.1675468832 0.0336831892 0.3929550000 0.0762230000 0.0914640000 0.0000010000 0.2226130000 0.0018300000 115897051 0 402718720 3.9762072563 4.1523337364 4.0675787926 455 1305031244.6806099415 0.0415150300 0.0789884313 0.1675468832 0.0337338076 0.4090120000 0.0764750000 0.0761310000 0.0325800000 0.2211650000 0.0018340000 115900835 0 402718720 3.9761068821 4.1555032730 4.0705699921 456 1305031244.7152500153 0.0394009054 0.0789016166 0.1675468832 0.0337397068 0.3925710000 0.0775580000 0.0925110000 0.0000010000 0.2198350000 0.0018320000 115904619 0 402718720 3.9728190899 4.1588215828 4.0715456009 457 1305031244.7458879948 0.0375159308 0.0788110571 0.1675468832 0.0339136558 0.6437390000 0.0761380000 0.0920470000 0.0325790000 0.2182660000 0.2238820000 115908235 0 402718720 3.9737193584 4.1573309898 4.0727963448 458 1305031244.7818510532 0.0351481475 0.0787157232 0.1675468832 0.0340158274 0.4233650000 0.1070410000 0.0944620000 0.0000000000 0.2191950000 0.0018200000 115912075 0 402718720 3.9705121517 4.1548171043 4.0690860748 459 1305031244.8140940666 0.0265415497 0.0786020540 0.1675468832 0.0348541789 0.4315280000 0.0799590000 0.0930120000 0.0328320000 0.2230540000 0.0018230000 115915747 0 402718720 3.9742972851 4.1593122482 4.0708389282 460 1305031244.8418219090 0.0303209145 0.0784970950 0.1675468832 0.0348516660 0.4042030000 0.0770250000 0.0987450000 0.0000010000 0.2257560000 0.0018290000 115919251 0 402718720 3.9720027447 4.1611886024 4.0655260086 461 1305031244.8818008900 0.0357276574 0.0784043196 0.1675468832 0.0348223881 0.7201280000 0.0757680000 0.1075360000 0.0406320000 0.2443730000 0.2508740000 115923147 0 402718720 3.9642748833 4.1666193008 4.0595254898 462 1305031244.9149079323 0.0357276574 0.0783119459 0.1675468832 0.0347845993 0.4085480000 0.0885320000 0.0880710000 0.0000010000 0.2292780000 0.0018190000 115926819 0 402718720 3.9642748833 4.1666193008 4.0595254898 463 1305031244.9458680153 0.0350491479 0.0782185057 0.1675468832 0.0347576856 0.4322300000 0.1044400000 0.0967600000 0.0000000000 0.2282180000 0.0019220000 115930435 0 402718720 3.9642748833 4.1666193008 4.0595254898 464 1305031244.9818000793 0.0387820713 0.0781335134 0.1675468832 0.0348683681 0.4059130000 0.0742200000 0.0956380000 0.0000010000 0.2334000000 0.0018140000 115934219 0 402718720 3.9722533226 4.1829233170 4.0706367493 465 1305031245.0140550137 0.0387820713 0.0780488867 0.1675468832 0.0348307741 0.6353110000 0.0757230000 0.0861450000 0.0000000000 0.2332560000 0.2393470000 115937891 0 402718720 3.9722533226 4.1829233170 4.0706367493 466 1305031245.0464398861 0.0431287922 0.0779739508 0.1675468832 0.0348011208 0.4037790000 0.0758300000 0.0905980000 0.0000010000 0.2346550000 0.0018300000 115941563 0 402718720 3.9709751606 4.1888737679 4.0711240768 467 1305031245.0817689896 0.0439901240 0.0779011803 0.1675468832 0.0347672154 0.3957910000 0.0744200000 0.0841720000 0.0000010000 0.2345230000 0.0018180000 115945347 0 402718720 3.9709751606 4.1888737679 4.0711240768 468 1305031245.1143150330 0.0459375568 0.0778328820 0.1675468832 0.0347351778 0.4039270000 0.0760500000 0.0909970000 0.0000010000 0.2341910000 0.0018340000 115948963 0 402718720 3.9709751606 4.1888737679 4.0711240768 469 1305031245.1457099915 0.0492718555 0.0777719843 0.1675468832 0.0346987502 0.6430400000 0.0755160000 0.0914570000 0.0000010000 0.2344300000 0.2407800000 115952691 0 402718720 3.9709751606 4.1888737679 4.0711240768 470 1305031245.1818709373 0.0528811216 0.0777190250 0.1675468832 0.0346699233 0.4276600000 0.0953220000 0.0907450000 0.0000010000 0.2381610000 0.0024610000 115956419 0 402718720 3.9709751606 4.1888737679 4.0711240768 471 1305031245.2140939236 0.0586075373 0.0776784486 0.1675468832 0.0346581870 0.4161670000 0.0942800000 0.0846790000 0.0000010000 0.2344840000 0.0018620000 115960091 0 402718720 3.9709751606 4.1888737679 4.0711240768 472 1305031245.2487950325 0.0629660860 0.0776472783 0.1675468832 0.0346650590 0.4092830000 0.0867620000 0.0853060000 0.0000000000 0.2344930000 0.0018560000 115963875 0 402718720 3.9709751606 4.1888737679 4.0711240768 473 1305031245.2807950974 0.0498734340 0.0775885598 0.1675468832 0.0363498476 0.7182410000 0.0901280000 0.0965860000 0.0336290000 0.2453670000 0.2516750000 115967491 0 402718720 3.9668569565 4.1662139893 4.0672755241 474 1305031245.3143179417 0.0539651178 0.0775387214 0.1675468832 0.0364987040 0.4263610000 0.0754100000 0.0994270000 0.0000000000 0.2487830000 0.0018720000 115971163 0 402718720 3.9670794010 4.1660304070 4.0692777634 475 1305031245.3491809368 0.0530997626 0.0774872709 0.1675468832 0.0367057798 0.4278380000 0.0737200000 0.0665490000 0.0329360000 0.2519380000 0.0018290000 115975003 0 402718720 3.9654712677 4.1597194672 4.0666413307 476 1305031245.3806860447 0.0507475063 0.0774310949 0.1675468832 0.0368889852 0.3976450000 0.0750940000 0.0670550000 0.0000010000 0.2527530000 0.0018640000 115978563 0 402718720 3.9621164799 4.1511969566 4.0604763031 477 1305031245.4133110046 0.0495194271 0.0773725799 0.1675468832 0.0370399466 0.6858130000 0.0744980000 0.0735570000 0.0335170000 0.2484370000 0.2549320000 115982235 0 402718720 3.9596207142 4.1425433159 4.0561981201 478 1305031245.4489970207 0.0497454926 0.0773147827 0.1675468832 0.0370224920 0.4006170000 0.0993310000 0.0497410000 0.0000000000 0.2488040000 0.0018470000 115985963 0 402718720 3.9647343159 4.1296339035 4.0515632629 479 1305031245.4846711159 0.0521530733 0.0772622530 0.1675468832 0.0372259676 0.4702540000 0.0884910000 0.0886370000 0.0334970000 0.2568840000 0.0018670000 115989747 0 402718720 3.9641520977 4.1272978783 4.0481839180 480 1305031245.5124320984 0.0502710156 0.0772060212 0.1675468832 0.0373117581 0.4229830000 0.0746080000 0.0874300000 0.0000010000 0.2582280000 0.0018420000 115993307 0 402718720 3.9589266777 4.1227216721 4.0428752899 481 1305031245.5481460094 0.0494254455 0.0771482654 0.1675468832 0.0374440868 0.6962030000 0.0756090000 0.0663270000 0.0335130000 0.2568450000 0.2630270000 115997035 0 402718720 3.9543173313 4.1171627045 4.0379815102 482 1305031245.5786890984 0.0502204709 0.0770923986 0.1675468832 0.0374517625 0.3888480000 0.0758130000 0.0574360000 0.0000000000 0.2528620000 0.0018510000 116000707 0 402718720 3.9549918175 4.1127896309 4.0361461639 483 1305031245.6104750633 0.0502977781 0.0770369232 0.1675468832 0.0375077160 0.4530610000 0.0926950000 0.0736240000 0.0334870000 0.2503790000 0.0019470000 116004323 0 402718720 3.9509270191 4.1055293083 4.0297079086 484 1305031245.6494629383 0.0500437357 0.0769811521 0.1675468832 0.0376624698 0.4132550000 0.0876720000 0.0737180000 0.0000010000 0.2491340000 0.0018410000 116008163 0 402718720 3.9489696026 4.1025266647 4.0278968811 485 1305031245.6802349091 0.0496953726 0.0769248928 0.1675468832 0.0376849145 0.6906220000 0.0769640000 0.0812080000 0.0334360000 0.2456420000 0.2524830000 116011835 0 402718720 3.9467682838 4.1018519402 4.0276370049 486 1305031245.7110319138 0.0497486144 0.0768689745 0.1675468832 0.0376889537 0.3953670000 0.0773760000 0.0738390000 0.0000010000 0.2414350000 0.0018360000 116015507 0 402718720 3.9433312416 4.0988535881 4.0242881775 487 1305031245.7497749329 0.0498391688 0.0768134718 0.1675468832 0.0377503167 0.4096350000 0.0785230000 0.0597360000 0.0331090000 0.2355400000 0.0018380000 116019347 0 402718720 3.9407308102 4.0988545418 4.0230960846 488 1305031245.7818500996 0.0508505516 0.0767602691 0.1675468832 0.0377819107 0.4188910000 0.0975090000 0.0898840000 0.0000000000 0.2287630000 0.0018390000 116023075 0 402718720 3.9352655411 4.0964727402 4.0181231499 489 1305031245.8135690689 0.0529805534 0.0767116399 0.1675468832 0.0378639987 0.6298530000 0.0787270000 0.0661180000 0.0325510000 0.2229740000 0.2285910000 116026691 0 402718720 3.9309954643 4.0944609642 4.0142507553 490 1305031245.8491089344 0.0547762923 0.0766668738 0.1675468832 0.0378936479 0.3835850000 0.0778460000 0.0866730000 0.0000010000 0.2164050000 0.0017650000 116030475 0 402718720 3.9280619621 4.0884828568 4.0104999542 491 1305031245.8820281029 0.0574003644 0.0766276345 0.1675468832 0.0379083290 0.3910090000 0.0793130000 0.0659360000 0.0324660000 0.2105960000 0.0018050000 116034203 0 402718720 3.9223110676 4.0813860893 4.0061459541 492 1305031245.9126079082 0.0595083088 0.0765928391 0.1675468832 0.0379110585 0.3870540000 0.0916890000 0.0874240000 0.0000010000 0.2052630000 0.0017790000 116037819 0 402718720 3.9229307175 4.0774850845 4.0043463707 493 1305031245.9458959103 0.0626807213 0.0765646198 0.1675468832 0.0379436664 0.6212760000 0.0917690000 0.0885990000 0.0323650000 0.2008910000 0.2067510000 116041491 0 402718720 3.9179677963 4.0714068413 4.0003266335 494 1305031245.9808180332 0.0632167906 0.0765375999 0.1675468832 0.0379598889 0.3424860000 0.0787890000 0.0658040000 0.0000000000 0.1950900000 0.0018690000 116045275 0 402718720 3.9209134579 4.0690369606 3.9999840260 495 1305031246.0110030174 0.0648823008 0.0765140539 0.1675468832 0.0379661995 0.3873690000 0.0788100000 0.0817610000 0.0321950000 0.1919280000 0.0017750000 116048891 0 402718720 3.9249980450 4.0661902428 3.9991116524 496 1305031246.0483930111 0.0668779686 0.0764946263 0.1675468832 0.0380335821 0.3380830000 0.0787940000 0.0668170000 0.0000000000 0.1898100000 0.0017610000 116052787 0 402718720 3.9242315292 4.0624184608 3.9966490269 497 1305031246.0805249214 0.0689880252 0.0764795225 0.1675468832 0.0380943374 0.5821750000 0.0785430000 0.0886400000 0.0321280000 0.1879580000 0.1939930000 116056347 0 402718720 3.9232599735 4.0589928627 3.9946162701 498 1305031246.1123559475 0.0699270144 0.0764663648 0.1675468832 0.0381831262 0.3714680000 0.0952860000 0.0853890000 0.0000000000 0.1881600000 0.0017270000 116060075 0 402718720 3.9251585007 4.0574798584 3.9946262836 499 1305031246.1484489441 0.0731687322 0.0764597563 0.1675468832 0.0382559875 0.3626550000 0.0762260000 0.0645270000 0.0316480000 0.1874980000 0.0018160000 116063803 0 402718720 3.9196748734 4.0541219711 3.9895200729 500 1305031246.1805961132 0.0766199827 0.0764600768 0.1675468832 0.0382897917 0.3631410000 0.0784080000 0.0928710000 0.0000000000 0.1891850000 0.0017670000 116067419 0 402718720 3.9121081829 4.0507822037 3.9838819504 501 1305031246.2111370564 0.0807508528 0.0764686412 0.1675468832 0.0383674545 0.5880130000 0.0774860000 0.0956910000 0.0323420000 0.1871680000 0.1944260000 116071091 0 402718720 3.9054744244 4.0443944931 3.9792532921 502 1305031246.2469689846 0.0843906775 0.0764844222 0.1675468832 0.0384633043 0.3420980000 0.0779130000 0.0729230000 0.0000000000 0.1885770000 0.0017790000 116074875 0 402718720 3.8994109631 4.0410141945 3.9747004509 503 1305031246.2796959877 0.0883166865 0.0765079455 0.1675468832 0.0385081055 0.4464320000 0.0858650000 0.1148440000 0.0397410000 0.2025600000 0.0023970000 116078547 0 402718720 3.8968033791 4.0367789268 3.9711008072 504 1305031246.3124730587 0.0909263119 0.0765365534 0.1675468832 0.0386061541 0.4146220000 0.0961130000 0.1148840000 0.0000000000 0.2009250000 0.0017830000 116082275 0 402718720 3.8916678429 4.0349531174 3.9684174061 505 1305031246.3482720852 0.0926522985 0.0765684658 0.1675468832 0.0387108129 0.5821430000 0.0764750000 0.0860280000 0.0324110000 0.1900960000 0.1962120000 116086059 0 402718720 3.8911385536 4.0329899788 3.9678907394 506 1305031246.3782060146 0.0941594169 0.0766032305 0.1675468832 0.0388460121 0.3587070000 0.0763830000 0.0862000000 0.0000010000 0.1934240000 0.0017830000 116089675 0 402718720 3.8857846260 4.0333399773 3.9662225246 507 1305031246.4156370163 0.0953498483 0.0766402061 0.1675468832 0.0389931278 0.4246440000 0.0990940000 0.0944730000 0.0324080000 0.1959610000 0.0017820000 116093571 0 402718720 3.8789660931 4.0329356194 3.9661166668 508 1305031246.4452888966 0.1013114154 0.0766887715 0.1675468832 0.0390490001 0.3563470000 0.0931040000 0.0634790000 0.0000010000 0.1969010000 0.0018880000 116097187 0 402718720 3.8679523468 4.0281906128 3.9623856544 509 1305031246.4774649143 0.1057835668 0.0767459322 0.1675468832 0.0391188407 0.6140770000 0.0762200000 0.0947620000 0.0323750000 0.2011590000 0.2086450000 116100971 0 402718720 3.8596847057 4.0279083252 3.9591224194 510 1305031246.5163950920 0.1053442582 0.0768020073 0.1675468832 0.0392272347 0.3307610000 0.0767730000 0.0488900000 0.0000000000 0.2022360000 0.0018960000 116104867 0 402718720 3.8599669933 4.0322957039 3.9598085880 511 1305031246.5491750240 0.1048972681 0.0768569882 0.1675468832 0.0393346406 0.4259730000 0.0906630000 0.0961770000 0.0319270000 0.2044580000 0.0018080000 116108651 0 402718720 3.8578484058 4.0363583565 3.9601101875 512 1305031246.5795109272 0.1054623500 0.0769128581 0.1675468832 0.0394096094 0.3848110000 0.0916610000 0.0876170000 0.0000000000 0.2027810000 0.0018190000 116112323 0 402718720 3.8528227806 4.0392651558 3.9596745968 513 1305031246.6164529324 0.1071167588 0.0769717351 0.1675468832 0.0394575982 0.6225490000 0.0957560000 0.0879310000 0.0318650000 0.1997170000 0.2063140000 116165371 0 402718720 3.8526012897 4.0419616699 3.9584584236 514 1305031246.6477630138 0.1082049981 0.0770325002 0.1675468832 0.0394990089 0.3696010000 0.0792100000 0.0887820000 0.0000010000 0.1988490000 0.0018230000 116271499 0 402718720 3.8490087986 4.0448489189 3.9576325417 515 1305031246.6807579994 0.1079445556 0.0770925236 0.1675468832 0.0395725351 0.4084680000 0.0798470000 0.0981950000 0.0318500000 0.1958140000 0.0018180000 116275283 0 402718720 3.8458969593 4.0470471382 3.9578039646 516 1305031246.7169740200 0.1120011136 0.0771601759 0.1675468832 0.0396773972 0.4136470000 0.0807870000 0.1180490000 0.0000000000 0.2112600000 0.0024540000 116279179 0 402718720 3.8375136852 4.0490255356 3.9541525841 517 1305031246.7491660118 0.1138903573 0.0772312207 0.1675468832 0.0397422574 0.6855430000 0.1006270000 0.1185540000 0.0396070000 0.2130450000 0.2127700000 116282907 0 402718720 3.8333840370 4.0525307655 3.9513504505 518 1305031246.7808170319 0.1133827269 0.0773010113 0.1675468832 0.0397912152 0.3858660000 0.0922970000 0.0893580000 0.0000000000 0.2014370000 0.0018250000 116286691 0 402718720 3.8327512741 4.0553841591 3.9509842396 519 1305031246.8168079853 0.1175960228 0.0773786510 0.1675468832 0.0398242073 0.4321660000 0.0958420000 0.0988140000 0.0322100000 0.2024060000 0.0019130000 116290587 0 402718720 3.8282423019 4.0579295158 3.9467732906 520 1305031246.8488121033 0.1179679409 0.0774567073 0.1675468832 0.0398398352 0.3746200000 0.0796440000 0.0882200000 0.0000000000 0.2039840000 0.0018160000 116294371 0 402718720 3.8261857033 4.0608706474 3.9453682899 521 1305031246.8806428909 0.1133436784 0.0775255883 0.1675468832 0.0398990527 0.6342290000 0.0922470000 0.0993160000 0.0316290000 0.1998550000 0.2102020000 116298155 0 402718720 3.8309168816 4.0661106110 3.9465599060 522 1305031246.9166710377 0.1117378771 0.0775911291 0.1675468832 0.0399594198 0.3419350000 0.0797820000 0.0604870000 0.0000000000 0.1988980000 0.0018190000 116302051 0 402718720 3.8308696747 4.0688076019 3.9452300072 523 1305031246.9495339394 0.1161803603 0.0776649134 0.1675468832 0.0399474698 0.4065970000 0.0964410000 0.0812680000 0.0316540000 0.1944520000 0.0018220000 116305835 0 402718720 3.8264076710 4.0711174011 3.9397790432 524 1305031246.9775969982 0.1182631925 0.0777423911 0.1675468832 0.0399268949 0.3708140000 0.0794870000 0.0985100000 0.0000010000 0.1900420000 0.0018070000 116309451 0 402718720 3.8233551979 4.0715851784 3.9370462894 525 1305031247.0167899132 0.1143623069 0.0778121433 0.1675468832 0.0400025924 0.5890980000 0.0793750000 0.0944630000 0.0319760000 0.1860340000 0.1962870000 116313403 0 402718720 3.8251891136 4.0749802589 3.9376223087 526 1305031247.0479340553 0.1179772243 0.0778885028 0.1675468832 0.0399751997 0.3573370000 0.0794910000 0.0904460000 0.0000000000 0.1846230000 0.0018130000 116317187 0 402718720 3.8190677166 4.0752329826 3.9325704575 527 1305031247.0778899193 0.1155477613 0.0779599625 0.1675468832 0.0399622546 0.3838970000 0.0760790000 0.0895550000 0.0320030000 0.1834920000 0.0018020000 116320915 0 402718720 3.8186061382 4.0775351524 3.9318430424 528 1305031247.1162130833 0.1173707917 0.0780346042 0.1675468832 0.0399283625 0.3613860000 0.0866340000 0.0886320000 0.0000010000 0.1832250000 0.0018830000 116324867 0 402718720 3.8118779659 4.0798482895 3.9279203415 529 1305031247.1473660469 0.1189174056 0.0781118874 0.1675468832 0.0399142628 0.5838910000 0.0767430000 0.0923660000 0.0319060000 0.1861030000 0.1958050000 116328651 0 402718720 3.8097410202 4.0814266205 3.9246933460 530 1305031247.1796920300 0.1203577742 0.0781915966 0.1675468832 0.0398789381 0.3553380000 0.0769730000 0.0883240000 0.0000000000 0.1872730000 0.0017910000 116332435 0 402718720 3.8083727360 4.0779924393 3.9234790802 531 1305031247.2169430256 0.1152779162 0.0782614390 0.1675468832 0.0398504709 0.3867520000 0.0760020000 0.0882820000 0.0314840000 0.1882260000 0.0017880000 116336387 0 402718720 3.8134460449 4.0796995163 3.9251165390 532 1305031247.2487928867 0.1111844704 0.0783233244 0.1675468832 0.0398262224 0.3557420000 0.0767630000 0.0892820000 0.0000010000 0.1869250000 0.0017940000 116340115 0 402718720 3.8163716793 4.0796756744 3.9274730682 533 1305031247.2794220448 0.1164251342 0.0783948100 0.1675468832 0.0398068011 0.5928660000 0.0877410000 0.0928870000 0.0314900000 0.1849960000 0.1947670000 116343843 0 402718720 3.8118937016 4.0769519806 3.9235243797 534 1305031247.3166429996 0.1148737594 0.0784631226 0.1675468832 0.0398019377 0.3494050000 0.0765310000 0.0865110000 0.0000010000 0.1835900000 0.0017930000 116347795 0 402718720 3.8169162273 4.0732779503 3.9249973297 535 1305031247.3477900028 0.1167504042 0.0785346876 0.1675468832 0.0398507924 0.3920020000 0.0758720000 0.1010120000 0.0321010000 0.1802520000 0.0017890000 116351579 0 402718720 3.8164706230 4.0708451271 3.9251708984 536 1305031247.3786110878 0.1146131679 0.0786019982 0.1675468832 0.0398556457 0.3568520000 0.0762910000 0.0965260000 0.0000000000 0.1812460000 0.0018000000 116355307 0 402718720 3.8206048012 4.0694994926 3.9273946285 537 1305031247.4168620110 0.1163657233 0.0786723217 0.1675468832 0.0398885747 0.5490880000 0.0771160000 0.0705370000 0.0322030000 0.1783000000 0.1899130000 116359315 0 402718720 3.8201267719 4.0660176277 3.9285831451 538 1305031247.4487700462 0.1170077696 0.0787435772 0.1675468832 0.0400035777 0.3450390000 0.0863350000 0.0761880000 0.0000000000 0.1797260000 0.0017960000 116363099 0 402718720 3.8207561970 4.0649085045 3.9303910732 539 1305031247.4802629948 0.1136748791 0.0788083848 0.1675468832 0.0400487332 0.3880820000 0.0765630000 0.0975670000 0.0322550000 0.1789030000 0.0018040000 116366771 0 402718720 3.8246145248 4.0669078827 3.9344549179 540 1305031247.5178461075 0.1147113144 0.0788748717 0.1675468832 0.0401174572 0.3426570000 0.0766910000 0.0835430000 0.0000000000 0.1796340000 0.0018010000 116370779 0 402718720 3.8261799812 4.0663857460 3.9364800453 541 1305031247.5459010601 0.1144432649 0.0789406174 0.1675468832 0.0401930408 0.5709200000 0.0751290000 0.0980120000 0.0323750000 0.1767550000 0.1876710000 116374395 0 402718720 3.8276100159 4.0645766258 3.9390687943 542 1305031247.5779209137 0.1131675616 0.0790037667 0.1675468832 0.0402470488 0.3376710000 0.0756860000 0.0816190000 0.0000000000 0.1775980000 0.0017670000 116378123 0 402718720 3.8300619125 4.0644254684 3.9414942265 543 1305031247.6152799129 0.1130434275 0.0790664548 0.1675468832 0.0403764332 0.3905140000 0.0938260000 0.0830480000 0.0324360000 0.1783870000 0.0018120000 116381963 0 402718720 3.8331737518 4.0639290810 3.9432654381 544 1305031247.6484000683 0.1128932983 0.0791286365 0.1675468832 0.0404824802 0.3733840000 0.0912410000 0.0989950000 0.0000000000 0.1803340000 0.0018060000 116385747 0 402718720 3.8350603580 4.0626578331 3.9442515373 545 1305031247.6835579872 0.1111570448 0.0791874043 0.1675468832 0.0406176650 0.5840550000 0.0786650000 0.0961330000 0.0324750000 0.1818230000 0.1939580000 116389531 0 402718720 3.8381857872 4.0618000031 3.9460024834 546 1305031247.7159609795 0.1064039692 0.0792372515 0.1675468832 0.0407870132 0.3661510000 0.0773240000 0.0980240000 0.0000010000 0.1880370000 0.0017730000 116393259 0 402718720 3.8465034962 4.0623245239 3.9513144493 547 1305031247.7469019890 0.1043038070 0.0792830770 0.1675468832 0.0409740412 0.3908760000 0.0767060000 0.0944640000 0.0325240000 0.1843830000 0.0018000000 116396987 0 402718720 3.8485414982 4.0608644485 3.9532420635 548 1305031247.7822608948 0.1076310053 0.0793348068 0.1675468832 0.0411032252 0.3544250000 0.0924380000 0.0672300000 0.0000000000 0.1919320000 0.0018110000 116400771 0 402718720 3.8436663151 4.0526065826 3.9514222145 549 1305031247.8139829636 0.1064451337 0.0793841881 0.1675468832 0.0413379269 0.5998520000 0.0778080000 0.0967260000 0.0324630000 0.1915550000 0.2002990000 116404331 0 402718720 3.8516721725 4.0485196114 3.9524650574 550 1305031247.8484420776 0.1044726148 0.0794298034 0.1675468832 0.0414877591 0.3726450000 0.0801280000 0.0947610000 0.0000000000 0.1949270000 0.0018210000 116408227 0 402718720 3.8629145622 4.0507793427 3.9514253139 551 1305031247.8820719719 0.1085720882 0.0794826932 0.1675468832 0.0415214818 0.4052460000 0.0795800000 0.0938120000 0.0327860000 0.1962120000 0.0018410000 116411899 0 402718720 3.8590683937 4.0415439606 3.9482243061 552 1305031247.9173319340 0.1040590405 0.0795272155 0.1675468832 0.0414996124 0.3936430000 0.0798140000 0.1011490000 0.0000000000 0.2098350000 0.0018340000 116415683 0 402718720 3.8559668064 4.0488615036 3.9437048435 553 1305031247.9496860504 0.0961977690 0.0795573612 0.1675468832 0.0415667741 0.6499620000 0.0944700000 0.0785080000 0.0330270000 0.2170260000 0.2259230000 116419299 0 402718720 3.8671982288 4.0563063622 3.9467368126 554 1305031247.9861450195 0.0990176424 0.0795924881 0.1675468832 0.0417292660 0.3973190000 0.0808760000 0.0923230000 0.0000000000 0.2212420000 0.0018500000 116423139 0 402718720 3.8716194630 4.0513105392 3.9414720535 555 1305031248.0181560516 0.0983293727 0.0796262482 0.1675468832 0.0416991856 0.4462200000 0.0811760000 0.1022330000 0.0333490000 0.2264340000 0.0019730000 116426755 0 402718720 3.8675024509 4.0547142029 3.9351513386 556 1305031248.0499138832 0.0941734314 0.0796524122 0.1675468832 0.0417184388 0.4198820000 0.0805540000 0.1001560000 0.0000000000 0.2362830000 0.0018810000 116430427 0 402718720 3.8738181591 4.0581207275 3.9354703426 557 1305031248.0857460499 0.0901902989 0.0796713312 0.1675468832 0.0418721165 0.7115000000 0.0806790000 0.0949680000 0.0331900000 0.2476810000 0.2539600000 116434155 0 402718720 3.8856720924 4.0582933426 3.9366881847 558 1305031248.1175789833 0.0868799388 0.0796842499 0.1675468832 0.0418847935 0.4368620000 0.1092730000 0.0668320000 0.0000010000 0.2578460000 0.0018790000 116437827 0 402718720 3.9003868103 4.0590229034 3.9414527416 559 1305031248.1493461132 0.0807186589 0.0796861003 0.1675468832 0.0418787514 0.4434580000 0.0764200000 0.0651790000 0.0337550000 0.2651080000 0.0019320000 116441499 0 402718720 3.9121248722 4.0612525940 3.9496293068 560 1305031248.1848630905 0.0789790675 0.0796848378 0.1675468832 0.0420037057 0.4560160000 0.0783200000 0.0998230000 0.0000010000 0.2749610000 0.0018890000 116445227 0 402718720 3.9290792942 4.0650243759 3.9580070972 561 1305031248.2167689800 0.0750985965 0.0796766627 0.1675468832 0.0420327268 0.7282470000 0.0773800000 0.0927150000 0.0000010000 0.2752050000 0.2819190000 116448899 0 402718720 3.9290792942 4.0650243759 3.9580070972 562 1305031248.2488510609 0.0718179345 0.0796626792 0.1675468832 0.0420764347 0.4559600000 0.0770820000 0.1006340000 0.0000000000 0.2753120000 0.0019090000 116452515 0 402718720 3.9290792942 4.0650243759 3.9580070972 563 1305031248.2847399712 0.0684432909 0.0796427513 0.1675468832 0.0420713291 0.4632450000 0.0910020000 0.0964580000 0.0000010000 0.2727160000 0.0020110000 116456355 0 402718720 3.9290792942 4.0650243759 3.9580070972 564 1305031248.3161809444 0.0662508160 0.0796190067 0.1675468832 0.0420545325 0.4402700000 0.0761800000 0.0857690000 0.0000010000 0.2753960000 0.0018880000 116460027 0 402718720 3.9290792942 4.0650243759 3.9580070972 565 1305031248.3488430977 0.0862899050 0.0796308136 0.1675468832 0.0429097871 0.7788530000 0.0758450000 0.0678120000 0.0347150000 0.2958340000 0.3036250000 116463643 0 402718720 3.9661464691 4.0828800201 3.9699842930 566 1305031248.3881969452 0.0911050588 0.0796510862 0.1675468832 0.0429025172 0.4427080000 0.0756860000 0.0647030000 0.0000000000 0.2994050000 0.0018670000 116467539 0 402718720 3.9756062031 4.0859432220 3.9777240753 567 1305031248.4155070782 0.0957880393 0.0796795464 0.1675468832 0.0429333677 0.5088210000 0.0750100000 0.0964370000 0.0344770000 0.2999250000 0.0019090000 116471099 0 402718720 3.9820516109 4.0902771950 3.9797081947 568 1305031248.4482519627 0.0993306935 0.0797141435 0.1675468832 0.0429431750 0.5241140000 0.1022260000 0.1074660000 0.0000010000 0.3114650000 0.0019170000 116474771 0 402718720 3.9865384102 4.0926690102 3.9793431759 569 1305031248.4852969646 0.1027821302 0.0797546848 0.1675468832 0.0429972761 0.8183990000 0.0948210000 0.0677320000 0.0344840000 0.3051210000 0.3152130000 116478555 0 402718720 3.9900081158 4.0941748619 3.9752521515 570 1305031248.5154309273 0.1025162488 0.0797946173 0.1675468832 0.0429677685 0.4570380000 0.0723180000 0.0733660000 0.0000010000 0.3082860000 0.0019850000 116482227 0 402718720 3.9894726276 4.1034231186 3.9756786823 571 1305031248.5470030308 0.1053958163 0.0798394531 0.1675468832 0.0429855680 0.5228000000 0.0752100000 0.0863130000 0.0343320000 0.3232420000 0.0025350000 116485899 0 402718720 3.9928960800 4.1111507416 3.9774873257 572 1305031248.5860579014 0.1031766981 0.0798802524 0.1675468832 0.0430271068 0.5116740000 0.0938690000 0.0833450000 0.0000010000 0.3307620000 0.0025290000 116489739 0 402718720 3.9905009270 4.1164078712 3.9698598385 573 1305031248.6180379391 0.0954764932 0.0799074710 0.1675468832 0.0430767672 0.8271100000 0.0849740000 0.0640140000 0.0348990000 0.3175820000 0.3246100000 116493355 0 402718720 3.9764497280 4.1222105026 3.9555082321 574 1305031248.6494390965 0.0954815298 0.0799346035 0.1675468832 0.0430661023 0.4730610000 0.0730260000 0.0751470000 0.0000000000 0.3219180000 0.0019120000 116497027 0 402718720 3.9742202759 4.1282095909 3.9513361454 575 1305031248.6860280037 0.0954905823 0.0799616574 0.1675468832 0.0430978705 0.5306910000 0.0728790000 0.0947720000 0.0350960000 0.3249800000 0.0019120000 116500867 0 402718720 3.9726777077 4.1376605034 3.9499711990 576 1305031248.7199230194 0.0960451439 0.0799895801 0.1675468832 0.0431021589 0.4742340000 0.0723350000 0.0713950000 0.0000010000 0.3275310000 0.0019130000 116504539 0 402718720 3.9705519676 4.1457839012 3.9464857578 577 1305031248.7498369217 0.0961863250 0.0800176507 0.1675468832 0.0431669626 0.8780990000 0.0833390000 0.0939740000 0.0346670000 0.3288780000 0.3361980000 116508155 0 402718720 3.9676074982 4.1527833939 3.9428949356 578 1305031248.7856750488 0.0966725573 0.0800464654 0.1675468832 0.0432248256 0.5154080000 0.0844750000 0.0930940000 0.0000010000 0.3349130000 0.0018630000 116511939 0 402718720 3.9590275288 4.1610689163 3.9327065945 579 1305031248.8181409836 0.0994649529 0.0800800034 0.1675468832 0.0432023284 0.5494880000 0.0962190000 0.0804810000 0.0352070000 0.3346130000 0.0018960000 116515611 0 402718720 3.9528107643 4.1772885323 3.9338283539 580 1305031248.8496789932 0.0961749107 0.0801077533 0.1675468832 0.0431929675 0.4802920000 0.0716130000 0.0730790000 0.0000010000 0.3325070000 0.0019950000 116519283 0 402718720 3.9528107643 4.1772885323 3.9338283539 581 1305031248.8855929375 0.0924643874 0.0801290211 0.1675468832 0.0431998361 0.8745310000 0.0717790000 0.0940480000 0.0000000000 0.3461880000 0.3613410000 116523067 0 402718720 3.9528107643 4.1772885323 3.9338283539 582 1305031248.9178819656 0.0896763727 0.0801454255 0.1675468832 0.0431701586 0.5436510000 0.0913550000 0.1060060000 0.0000000000 0.3433850000 0.0018410000 116526739 0 402718720 3.9528107643 4.1772885323 3.9338283539 583 1305031248.9526810646 0.0866879746 0.0801566477 0.1675468832 0.0431646900 0.5049370000 0.0844420000 0.0847520000 0.0000000000 0.3326910000 0.0019370000 116530523 0 402718720 3.9528107643 4.1772885323 3.9338283539 584 1305031248.9845540524 0.0839538351 0.0801631498 0.1675468832 0.0431440623 0.4880330000 0.0722880000 0.0781590000 0.0000010000 0.3347130000 0.0018080000 116534195 0 402718720 3.9528107643 4.1772885323 3.9338283539 585 1305031249.0169510841 0.0832873434 0.0801684903 0.1675468832 0.0431167216 0.8225560000 0.0716010000 0.0715210000 0.0000010000 0.3353040000 0.3430840000 116537867 0 402718720 3.9528107643 4.1772885323 3.9338283539 586 1305031249.0523660183 0.0830787942 0.0801734566 0.1675468832 0.0430878430 0.4781760000 0.0703390000 0.0697220000 0.0000010000 0.3352280000 0.0017960000 116541651 0 402718720 3.9528107643 4.1772885323 3.9338283539 587 1305031249.0845029354 0.0844932795 0.0801808158 0.1675468832 0.0430575598 0.4770800000 0.0701580000 0.0687680000 0.0000010000 0.3352890000 0.0018010000 116545323 0 402718720 3.9528107643 4.1772885323 3.9338283539 588 1305031249.1168839931 0.0859431773 0.0801906157 0.1675468832 0.0430210699 0.4873410000 0.0799120000 0.0693400000 0.0000010000 0.3352290000 0.0017960000 116548995 0 402718720 3.9528107643 4.1772885323 3.9338283539 589 1305031249.1534469128 0.0889527947 0.0802054921 0.1675468832 0.0430096532 0.8437650000 0.0849380000 0.0736110000 0.0000010000 0.3325570000 0.3514550000 116552779 0 402718720 3.9528107643 4.1772885323 3.9338283539 590 1305031249.1847391129 0.0908615664 0.0802235532 0.1675468832 0.0429808556 0.5598160000 0.0906700000 0.1123750000 0.0000010000 0.3531260000 0.0024200000 116556451 0 402718720 3.9528107643 4.1772885323 3.9338283539 591 1305031249.2168650627 0.0924837664 0.0802442981 0.1675468832 0.0429681267 0.5065150000 0.0844860000 0.0838830000 0.0000010000 0.3352740000 0.0018000000 116560123 0 402718720 3.9528107643 4.1772885323 3.9338283539 592 1305031249.2532238960 0.0947451517 0.0802687928 0.1675468832 0.0430204268 0.5082310000 0.0849840000 0.0851520000 0.0000000000 0.3351930000 0.0018140000 116563907 0 402718720 3.9528107643 4.1772885323 3.9338283539 593 1305031249.2848041058 0.0961160436 0.0802955166 0.1675468832 0.0430113261 0.8595420000 0.0951540000 0.0851040000 0.0000000000 0.3352300000 0.3429820000 116567523 0 402718720 3.9528107643 4.1772885323 3.9338283539 594 1305031249.3174340725 0.0974122286 0.0803243327 0.1675468832 0.0429928970 0.4819840000 0.0715070000 0.0680680000 0.0000000000 0.3387870000 0.0024080000 116571251 0 402718720 3.9528107643 4.1772885323 3.9338283539 595 1305031249.3527359962 0.0984665379 0.0803548238 0.1675468832 0.0429619462 0.5369960000 0.0891070000 0.0911030000 0.0000010000 0.3531720000 0.0023920000 116574979 0 402718720 3.9528107643 4.1772885323 3.9338283539 596 1305031249.3847539425 0.0996559933 0.0803872083 0.1675468832 0.0429343462 0.5188300000 0.0893030000 0.0911350000 0.0000010000 0.3355020000 0.0017990000 116578651 0 402718720 3.9528107643 4.1772885323 3.9338283539 597 1305031249.4178340435 0.0995125771 0.0804192441 0.1675468832 0.0429303323 0.8174580000 0.0707970000 0.0704780000 0.0000010000 0.3325580000 0.3425610000 116582323 0 402718720 3.9528107643 4.1772885323 3.9338283539 598 1305031249.4537220001 0.1017636806 0.0804549371 0.1675468832 0.0429780458 0.4812320000 0.0713010000 0.0718080000 0.0000010000 0.3352360000 0.0018020000 116586107 0 402718720 3.9528107643 4.1772885323 3.9338283539 599 1305031249.4859149456 0.1022408381 0.0804913076 0.1675468832 0.0430366185 0.5046840000 0.0841540000 0.0760590000 0.0000000000 0.3408260000 0.0024090000 116589779 0 402718720 3.9528107643 4.1772885323 3.9338283539 600 1305031249.5177340508 0.1025596634 0.0805280882 0.1675468832 0.0430913730 0.4913440000 0.0805920000 0.0726040000 0.0000010000 0.3352300000 0.0018080000 116593451 0 402718720 3.9528107643 4.1772885323 3.9338283539 601 1305031249.5543251038 0.1036689207 0.0805665920 0.1675468832 0.0432002884 0.8246710000 0.0708170000 0.0746930000 0.0000000000 0.3349830000 0.3430920000 116597235 0 402718720 3.9528107643 4.1772885323 3.9338283539 602 1305031249.5859050751 0.1051659808 0.0806074548 0.1675468832 0.0432972465 0.5067150000 0.0956040000 0.0755660000 0.0000010000 0.3326420000 0.0017970000 116600851 0 402718720 3.9528107643 4.1772885323 3.9338283539 603 1305031249.6180789471 0.2316190004 0.0808578885 0.2316190004 0.0433326075 0.5183720000 0.0728850000 0.0731070000 0.0347550000 0.3346800000 0.0018380000 116604523 0 402718720 3.7884745598 4.1582164764 3.8304626942 604 1305031249.6542129517 0.2351291925 0.0811133046 0.2351291925 0.0437726310 0.4972930000 0.0715470000 0.0890420000 0.0000000000 0.3337300000 0.0018610000 116608251 0 402718720 3.7729599476 4.1782641411 3.8446850777 605 1305031249.6856739521 0.2288090140 0.0813574298 0.2351291925 0.0438806284 0.8635160000 0.0861650000 0.0763730000 0.0341880000 0.3271910000 0.3385090000 116611923 0 402718720 3.7738714218 4.1673903465 3.8479101658 606 1305031249.7177898884 0.2073943466 0.0815654115 0.2351291925 0.0440093635 0.4691480000 0.0742370000 0.0779770000 0.0000010000 0.3139660000 0.0018590000 116615595 0 402718720 3.7881731987 4.1578526497 3.8608388901 607 1305031249.7539620399 0.2081942856 0.0817740258 0.2351291925 0.0443491870 0.4680230000 0.0736830000 0.0767520000 0.0000010000 0.3146770000 0.0018090000 116619323 0 402718720 3.7881731987 4.1578526497 3.8608388901 608 1305031249.7854170799 0.2077362537 0.0819812005 0.2351291925 0.0445195265 0.4692280000 0.0753970000 0.0768970000 0.0000000000 0.3139710000 0.0018500000 116622939 0 402718720 3.7881731987 4.1578526497 3.8608388901 609 1305031249.8186020851 0.2082684487 0.0821885687 0.2351291925 0.0446485084 0.8150300000 0.0913750000 0.0881250000 0.0000010000 0.3112340000 0.3231830000 116626723 0 402718720 3.7881731987 4.1578526497 3.8608388901 610 1305031249.8537468910 0.2092848867 0.0823969233 0.2351291925 0.0451580656 0.4699820000 0.0760760000 0.0771170000 0.0000000000 0.3138440000 0.0018420000 116630395 0 402718720 3.7881731987 4.1578526497 3.8608388901 611 1305031249.8855249882 0.0845979303 0.0824005256 0.2351291925 0.0504056944 0.4795670000 0.0752290000 0.0861980000 0.0333410000 0.2818210000 0.0018500000 116634067 0 402718720 3.9270153046 4.1228837967 3.9393131733 612 1305031249.9170649052 0.0852963254 0.0824052573 0.2351291925 0.0504134810 0.4567480000 0.0839230000 0.0867470000 0.0000010000 0.2831240000 0.0018300000 116637795 0 402718720 3.9249706268 4.1185736656 3.9385666847 613 1305031249.9533979893 0.0889508426 0.0824159353 0.2351291925 0.0504089194 0.7747490000 0.0729020000 0.0923260000 0.0327960000 0.2813840000 0.2942380000 116641523 0 402718720 3.9196336269 4.1150870323 3.9351501465 614 1305031249.9851789474 0.0919064805 0.0824313922 0.2351291925 0.0504031514 0.4502920000 0.0717190000 0.0919980000 0.0000010000 0.2835080000 0.0019070000 116645195 0 402718720 3.9133341312 4.1137413979 3.9330770969 615 1305031250.0164399147 0.0941436291 0.0824504365 0.2351291925 0.0503812476 0.4704610000 0.0718410000 0.0703280000 0.0328580000 0.2917330000 0.0024070000 116648867 0 402718720 3.9105799198 4.1105260849 3.9312632084 616 1305031250.0531940460 0.0973223150 0.0824745791 0.2351291925 0.0504148961 0.4692950000 0.0881100000 0.0736640000 0.0000010000 0.3038820000 0.0023770000 116652651 0 402718720 3.9077992439 4.1040897369 3.9277453423 617 1305031250.0845069885 0.0994889364 0.0825021551 0.2351291925 0.0504567738 0.8256260000 0.0867180000 0.1083960000 0.0395650000 0.2890420000 0.3007810000 116656267 0 402718720 3.9047513008 4.1024961472 3.9269433022 618 1305031250.1208500862 0.0999266505 0.0825303501 0.2351291925 0.0505246369 0.4265490000 0.0694640000 0.0685670000 0.0000000000 0.2855880000 0.0017860000 116660107 0 402718720 3.8987729549 4.0996046066 3.9280414581 619 1305031250.1532480717 0.0990451574 0.0825570299 0.2351291925 0.0507026741 0.4651600000 0.0717580000 0.0766420000 0.0328340000 0.2809650000 0.0018240000 116663723 0 402718720 3.8962411880 4.0950593948 3.9310202599 620 1305031250.1853280067 0.0949503034 0.0825770190 0.2351291925 0.0506962903 0.4352760000 0.0936940000 0.0699280000 0.0000000000 0.2685400000 0.0019180000 116667339 0 402718720 3.8996930122 4.0873751640 3.9359939098 621 1305031250.2214460373 0.0928272456 0.0825935250 0.2351291925 0.0506949553 0.7249680000 0.0722240000 0.0822210000 0.0328620000 0.2648780000 0.2716690000 116671179 0 402718720 3.8926064968 4.0761361122 3.9380009174 622 1305031250.2537350655 0.0918092728 0.0826083413 0.2351291925 0.0507638972 0.4125160000 0.0838750000 0.0677560000 0.0000000000 0.2579420000 0.0017990000 116674851 0 402718720 3.8952226639 4.0730690956 3.9420652390 623 1305031250.2852239609 0.0920087174 0.0826234302 0.2351291925 0.0507632125 0.4961060000 0.0733690000 0.1085930000 0.0404910000 0.2700000000 0.0023890000 116678467 0 402718720 3.8966796398 4.0690040588 3.9441030025 624 1305031250.3208620548 0.0885368735 0.0826329069 0.2351291925 0.0507971370 0.4663140000 0.0920050000 0.1102140000 0.0000000000 0.2611380000 0.0018070000 116682195 0 402718720 3.8954718113 4.0670113564 3.9498207569 625 1305031250.3517000675 0.0865122899 0.0826391139 0.2351291925 0.0508110807 0.6934850000 0.0735290000 0.0831980000 0.0329430000 0.2482230000 0.2544670000 116685811 0 402718720 3.9002165794 4.0692496300 3.9552016258 626 1305031250.3851490021 0.0866779909 0.0826455658 0.2351291925 0.0508188932 0.3969770000 0.0736220000 0.0700060000 0.0000010000 0.2496620000 0.0024100000 116689483 0 402718720 3.8952937126 4.0657801628 3.9573602676 627 1305031250.4215359688 0.0896203667 0.0826566899 0.2351291925 0.0508220211 0.4964740000 0.0921250000 0.1105890000 0.0405090000 0.2502810000 0.0018110000 116693323 0 402718720 3.8917083740 4.0670852661 3.9559175968 628 1305031250.4540181160 0.0902531818 0.0826687862 0.2351291925 0.0508852274 0.4074240000 0.0737720000 0.0830560000 0.0000010000 0.2476280000 0.0018050000 116697107 0 402718720 3.8895509243 4.0693154335 3.9578335285 629 1305031250.4856131077 0.0907923728 0.0826817013 0.2351291925 0.0508771773 0.6867570000 0.0737000000 0.0828360000 0.0326840000 0.2451020000 0.2513060000 116700723 0 402718720 3.8894088268 4.0723481178 3.9598658085 630 1305031250.5215380192 0.0918326080 0.0826962265 0.2351291925 0.0508518031 0.4147530000 0.0864630000 0.0822130000 0.0000010000 0.2431360000 0.0017950000 116704563 0 402718720 3.8844127655 4.0721130371 3.9599764347 631 1305031250.5536580086 0.0940224230 0.0827141761 0.2351291925 0.0508314122 0.4587570000 0.0934040000 0.0900310000 0.0325320000 0.2396850000 0.0019080000 116708347 0 402718720 3.8797690868 4.0718350410 3.9602184296 632 1305031250.5853788853 0.0965041295 0.0827359957 0.2351291925 0.0508091984 0.4229260000 0.0938590000 0.0867470000 0.0000010000 0.2393470000 0.0017940000 116712019 0 402718720 3.8761415482 4.0756568909 3.9587681293 633 1305031250.6213030815 0.0984156653 0.0827607661 0.2351291925 0.0507837356 0.6733980000 0.0747540000 0.0829760000 0.0324280000 0.2380010000 0.2440930000 116715859 0 402718720 3.8745644093 4.0791187286 3.9587090015 634 1305031250.6535439491 0.0982886627 0.0827852580 0.2351291925 0.0507936273 0.3952320000 0.0730600000 0.0823060000 0.0000010000 0.2369130000 0.0018010000 116719699 0 402718720 3.8732259274 4.0802760124 3.9610302448 635 1305031250.6852970123 0.0959603861 0.0828060063 0.2351291925 0.0508014147 0.4280910000 0.0755720000 0.0835470000 0.0319210000 0.2340780000 0.0018120000 116723371 0 402718720 3.8777284622 4.0841603279 3.9659163952 636 1305031250.7216401100 0.0936317965 0.0828230279 0.2351291925 0.0507766042 0.3937860000 0.0761670000 0.0841060000 0.0000000000 0.2305470000 0.0018010000 116727211 0 402718720 3.8773725033 4.0858263969 3.9698162079 637 1305031250.7534279823 0.0932701230 0.0828394284 0.2351291925 0.0507502748 0.6647770000 0.0862750000 0.0839030000 0.0317160000 0.2278400000 0.2338780000 116730939 0 402718720 3.8694300652 4.0828576088 3.9715223312 638 1305031250.7853651047 0.0907581747 0.0828518402 0.2351291925 0.0507263293 0.3939240000 0.0763580000 0.0909700000 0.0000000000 0.2236170000 0.0018070000 116734667 0 402718720 3.8577749729 4.0717587471 3.9773964882 639 1305031250.8217930794 0.0911535546 0.0828648320 0.2351291925 0.0506912087 0.4674070000 0.0766660000 0.1123420000 0.0389870000 0.2356940000 0.0024170000 116738619 0 402718720 3.8534367085 4.0731739998 3.9775986671 640 1305031250.8538279533 0.0891450122 0.0828746447 0.2351291925 0.0506554841 0.4434640000 0.0949950000 0.1120110000 0.0000010000 0.2335000000 0.0017900000 116742403 0 402718720 3.8560855389 4.0749325752 3.9793272018 641 1305031250.8820140362 0.0894136205 0.0828848460 0.2351291925 0.0506175535 0.6378060000 0.0768810000 0.0848620000 0.0319400000 0.2184810000 0.2244190000 116746019 0 402718720 3.8554909229 4.0741815567 3.9795532227 642 1305031250.9217998981 0.0904324576 0.0828966024 0.2351291925 0.0505799792 0.3750140000 0.0870500000 0.0682120000 0.0000000000 0.2167540000 0.0018130000 116749971 0 402718720 3.8552043438 4.0752573013 3.9778604507 643 1305031250.9535419941 0.0937212780 0.0829134370 0.2351291925 0.0505557737 0.4664620000 0.0935660000 0.0989010000 0.0391270000 0.2311390000 0.0024090000 116753755 0 402718720 3.8497073650 4.0739264488 3.9738185406 644 1305031250.9853079319 0.0914053917 0.0829266233 0.2351291925 0.0505197499 0.4188380000 0.0963500000 0.0866140000 0.0000010000 0.2321390000 0.0024120000 116757427 0 402718720 3.8530220985 4.0736589432 3.9753799438 645 1305031251.0214879513 0.0913762450 0.0829397235 0.2351291925 0.0504927419 0.6290050000 0.0829900000 0.0743830000 0.0321710000 0.2161900000 0.2221160000 116761267 0 402718720 3.8551766872 4.0726656914 3.9747245312 646 1305031251.0534679890 0.0936340392 0.0829562781 0.2351291925 0.0504910660 0.3839640000 0.0769910000 0.0893810000 0.0000010000 0.2146080000 0.0017950000 116764995 0 402718720 3.8520305157 4.0700292587 3.9709386826 647 1305031251.0851860046 0.0925294608 0.0829710744 0.2351291925 0.0504791939 0.4718180000 0.0990600000 0.1012530000 0.0393450000 0.2284190000 0.0024120000 116768723 0 402718720 3.8534104824 4.0661725998 3.9704773426 648 1305031251.1214449406 0.0917077959 0.0829845570 0.2351291925 0.0504686161 0.4486700000 0.0959470000 0.1191660000 0.0000010000 0.2298120000 0.0024110000 116772563 0 402718720 3.8572928905 4.0636544228 3.9695992470 649 1305031251.1537809372 0.0889967158 0.0829938207 0.2351291925 0.0505288604 0.6850820000 0.0887760000 0.0909030000 0.0342820000 0.2317480000 0.2380350000 116776347 0 402718720 3.8634271622 4.0620546341 3.9690470695 650 1305031251.1851599216 0.0886474326 0.0830025186 0.2351291925 0.0505374661 0.4445810000 0.0959840000 0.1226780000 0.0000000000 0.2229070000 0.0018160000 116780019 0 402718720 3.8676369190 4.0570230484 3.9677548409 651 1305031251.2204658985 0.0857525840 0.0830067429 0.2351291925 0.0505361937 0.4267680000 0.0764860000 0.0934470000 0.0323140000 0.2215640000 0.0017720000 116783803 0 402718720 3.8732244968 4.0546002388 3.9683294296 652 1305031251.2524240017 0.0836126655 0.0830076723 0.2351291925 0.0505693675 0.4182130000 0.0954310000 0.0978750000 0.0000000000 0.2217350000 0.0019080000 116787475 0 402718720 3.8791959286 4.0515384674 3.9687359333 653 1305031251.2844820023 0.0843967795 0.0830097995 0.2351291925 0.0507184417 0.6582770000 0.0747550000 0.0941980000 0.0327540000 0.2247120000 0.2306560000 116791203 0 402718720 3.8830471039 4.0469303131 3.9657518864 654 1305031251.3190040588 0.0826764703 0.0830092899 0.2351291925 0.0507763959 0.4207150000 0.0897380000 0.0989040000 0.0000010000 0.2290490000 0.0018080000 116794987 0 402718720 3.8922982216 4.0452914238 3.9667785168 655 1305031251.3532440662 0.0796536803 0.0830041668 0.2351291925 0.0508249964 0.4402880000 0.0753980000 0.0956040000 0.0329930000 0.2332740000 0.0018180000 116798659 0 402718720 3.9004549980 4.0430874825 3.9692494869 656 1305031251.3870069981 0.0769838169 0.0829949894 0.2351291925 0.0508435186 0.3759530000 0.0735240000 0.0618540000 0.0000010000 0.2375820000 0.0017800000 116802387 0 402718720 3.9097385406 4.0444989204 3.9733886719 657 1305031251.4210500717 0.0791666880 0.0829891625 0.2351291925 0.0509126209 0.7168270000 0.0982780000 0.0947210000 0.0331070000 0.2417690000 0.2477600000 116806115 0 402718720 3.9123725891 4.0403084755 3.9699380398 658 1305031251.4496629238 0.0776012912 0.0829809742 0.2351291925 0.0509503026 0.4133270000 0.0754580000 0.0869770000 0.0000010000 0.2478490000 0.0018450000 116809675 0 402718720 3.9237298965 4.0408697128 3.9755361080 659 1305031251.4890139103 0.0753225088 0.0829693529 0.2351291925 0.0510133555 0.4469740000 0.0757820000 0.0830700000 0.0333230000 0.2517520000 0.0018410000 116813515 0 402718720 3.9297940731 4.0424094200 3.9779596329 660 1305031251.5207729340 0.0754576176 0.0829579715 0.2351291925 0.0510827710 0.4291730000 0.0756160000 0.0944890000 0.0000000000 0.2560230000 0.0018390000 116817243 0 402718720 3.9385550022 4.0442433357 3.9806404114 661 1305031251.5530450344 0.0752400309 0.0829462953 0.2351291925 0.0511588958 0.7228960000 0.0757620000 0.0877920000 0.0333460000 0.2593810000 0.2654240000 116820915 0 402718720 3.9445698261 4.0468134880 3.9812376499 662 1305031251.5887598991 0.0729353800 0.0829311731 0.2351291925 0.0511777419 0.4409450000 0.0921450000 0.0826020000 0.0000010000 0.2631210000 0.0018560000 116824643 0 402718720 3.9456501007 4.0539979935 3.9818079472 663 1305031251.6208739281 0.0720907673 0.0829148226 0.2351291925 0.0511990218 0.4986220000 0.0769220000 0.1051610000 0.0415380000 0.2719380000 0.0018620000 116828371 0 402718720 3.9499940872 4.0571784973 3.9845070839 664 1305031251.6528749466 0.0713888332 0.0828974641 0.2351291925 0.0512477514 0.4325720000 0.0769800000 0.0863620000 0.0000010000 0.2661270000 0.0018840000 116832043 0 402718720 3.9529170990 4.0615582466 3.9852128029 665 1305031251.6897680759 0.0712526068 0.0828799531 0.2351291925 0.0512699971 0.7510560000 0.0760430000 0.0899220000 0.0336330000 0.2721070000 0.2781440000 116835827 0 402718720 3.9536502361 4.0665316582 3.9849584103 666 1305031251.7204608917 0.0722942948 0.0828640587 0.2351291925 0.0513141831 0.4562010000 0.0974740000 0.0822640000 0.0000010000 0.2733520000 0.0018850000 116839499 0 402718720 3.9588203430 4.0666537285 3.9875791073 667 1305031251.7531440258 0.0757010058 0.0828533195 0.2351291925 0.0513895868 0.5076520000 0.0919120000 0.1045120000 0.0339820000 0.2739800000 0.0019980000 116843171 0 402718720 3.9670920372 4.0626711845 3.9892392159 668 1305031251.7892498970 0.0802222937 0.0828493808 0.2351291925 0.0514144587 0.4409720000 0.0766390000 0.0789360000 0.0000010000 0.2822570000 0.0019020000 116846955 0 402718720 3.9747476578 4.0662541389 3.9936392307 669 1305031251.8209791183 0.0832259282 0.0828499437 0.2351291925 0.0514372543 0.7585460000 0.0761430000 0.0699100000 0.0343290000 0.2844120000 0.2925360000 116850627 0 402718720 3.9814383984 4.0680041313 3.9992468357 670 1305031251.8537969589 0.0905276835 0.0828614030 0.2351291925 0.0515314634 0.4640280000 0.0755620000 0.0735970000 0.0000010000 0.3109460000 0.0025340000 116854299 0 402718720 3.9925084114 4.0653834343 4.0038552284 671 1305031251.8896539211 0.0995327681 0.0828862485 0.2351291925 0.0515196029 0.5854240000 0.0944030000 0.1259250000 0.0438070000 0.3181410000 0.0019130000 116858027 0 402718720 4.0037183762 4.0679707527 4.0103430748 672 1305031251.9219300747 0.1002601683 0.0829121026 0.2351291925 0.0515040566 0.4781960000 0.0729110000 0.0915200000 0.0000000000 0.3105240000 0.0019580000 116861755 0 402718720 4.0053639412 4.0775742531 4.0170106888 673 1305031251.9538369179 0.1000148356 0.0829375153 0.2351291925 0.0514993657 0.8440810000 0.0872170000 0.0812440000 0.0348650000 0.3156030000 0.3239270000 116865371 0 402718720 4.0055775642 4.0854644775 4.0214061737 674 1305031251.9898068905 0.1010225713 0.0829643477 0.2351291925 0.0514882069 0.4740780000 0.0736200000 0.0793270000 0.0000010000 0.3179970000 0.0018990000 116869155 0 402718720 4.0079412460 4.0878734589 4.0241012573 675 1305031252.0221600533 0.1024622694 0.0829932335 0.2351291925 0.0514996092 0.5318260000 0.0859040000 0.0874870000 0.0349320000 0.3203580000 0.0019050000 116872883 0 402718720 4.0106596947 4.0940713882 4.0279350281 676 1305031252.0537619591 0.1043124199 0.0830247708 0.2351291925 0.0514906433 0.5210990000 0.1112240000 0.0856130000 0.0000010000 0.3211080000 0.0019040000 116876555 0 402718720 4.0142140388 4.1060452461 4.0350642204 677 1305031252.0895619392 0.1025843397 0.0830536623 0.2351291925 0.0515229612 0.8150070000 0.0725180000 0.0585880000 0.0349100000 0.3197320000 0.3279330000 116880283 0 402718720 4.0125279427 4.1188287735 4.0362415314 678 1305031252.1221520901 0.0961337760 0.0830729545 0.2351291925 0.0515642944 0.4610880000 0.0722460000 0.0670900000 0.0000000000 0.3186480000 0.0018690000 116884011 0 402718720 4.0071549416 4.1274504662 4.0320339203 679 1305031252.1539709568 0.0924636424 0.0830867847 0.2351291925 0.0516576744 0.5096030000 0.0724920000 0.0848260000 0.0349660000 0.3139940000 0.0020300000 116887571 0 402718720 4.0035986900 4.1411809921 4.0303311348 680 1305031252.1897890568 0.0885458812 0.0830948128 0.2351291925 0.0516357200 0.4861780000 0.0727460000 0.0941730000 0.0000000000 0.3161020000 0.0019140000 116891355 0 402718720 3.9873659611 4.1621050835 4.0244393349 681 1305031252.2220859528 0.0867563412 0.0831001895 0.2351291925 0.0516089649 0.8324810000 0.0729190000 0.0999940000 0.0349410000 0.3069790000 0.3164200000 116895083 0 402718720 3.9707469940 4.1761960983 4.0187005997 682 1305031252.2530639172 0.0815000609 0.0830978432 0.2351291925 0.0515751053 0.4679000000 0.0736540000 0.0838030000 0.0000000000 0.3071000000 0.0020340000 116898755 0 402718720 3.9707469940 4.1761960983 4.0187005997 683 1305031252.2888779640 0.2300122380 0.0833129448 0.2351291925 0.0528403817 0.4959560000 0.0725550000 0.0823210000 0.0348340000 0.3031320000 0.0018300000 116902427 0 402718720 3.7721149921 4.1903553009 3.8972015381 684 1305031252.3206090927 0.2309636325 0.0835288084 0.2351291925 0.0528053977 0.5229570000 0.0912930000 0.1068690000 0.0000000000 0.3209550000 0.0024330000 116906099 0 402718720 3.7721149921 4.1903553009 3.8972015381 685 1305031252.3528549671 0.2314139754 0.0837446992 0.2351291925 0.0527674311 0.8209240000 0.0921520000 0.1055900000 0.0000010000 0.3093110000 0.3126380000 116909715 0 402718720 3.7721149921 4.1903553009 3.8972015381 686 1305031252.3893189430 0.2307180613 0.0839589460 0.2351291925 0.0527434106 0.4529720000 0.0714150000 0.0744320000 0.0000010000 0.3040500000 0.0018140000 116913499 0 402718720 3.7721149921 4.1903553009 3.8972015381 687 1305031252.4217019081 0.2296109945 0.0841709578 0.2351291925 0.0527258037 0.4699550000 0.0883180000 0.0751310000 0.0000000000 0.3034300000 0.0018140000 116917227 0 402718720 3.7721149921 4.1903553009 3.8972015381 688 1305031252.4538249969 0.2276071161 0.0843794405 0.2351291925 0.0526943898 0.4542140000 0.0721040000 0.0780150000 0.0000000000 0.3008990000 0.0019020000 116920899 0 402718720 3.7721149921 4.1903553009 3.8972015381 689 1305031252.4895589352 0.2269209772 0.0845863223 0.2351291925 0.0526583500 0.7648410000 0.0718560000 0.0755720000 0.0000010000 0.3034880000 0.3126790000 116924571 0 402718720 3.7721149921 4.1903553009 3.8972015381 690 1305031252.5221700668 0.2258756757 0.0847910895 0.2351291925 0.0526224227 0.4664120000 0.0831760000 0.0767080000 0.0000010000 0.3034420000 0.0018030000 116928299 0 402718720 3.7721149921 4.1903553009 3.8972015381 691 1305031252.5537741184 0.2250270993 0.0849940360 0.2351291925 0.0526067231 0.4606810000 0.0726970000 0.0814340000 0.0000010000 0.3034430000 0.0018270000 116931971 0 402718720 3.7721149921 4.1903553009 3.8972015381 692 1305031252.5897459984 0.2247109860 0.0851959391 0.2351291925 0.0525790833 0.4749820000 0.0841490000 0.0852780000 0.0000010000 0.3024410000 0.0018260000 116935699 0 402718720 3.7721149921 4.1903553009 3.8972015381 693 1305031252.6221249104 0.2244515121 0.0853968851 0.2351291925 0.0525429941 0.7819840000 0.0838970000 0.0805630000 0.0000000000 0.3034900000 0.3127900000 116939427 0 402718720 3.7721149921 4.1903553009 3.8972015381 694 1305031252.6578559875 0.2251130193 0.0855982051 0.2351291925 0.0525256496 0.4574740000 0.0712200000 0.0796800000 0.0000010000 0.3034670000 0.0018230000 116943155 0 402718720 3.7721149921 4.1903553009 3.8972015381 695 1305031252.6889979839 0.2250605971 0.0857988704 0.2351291925 0.0525444085 0.4611680000 0.0733260000 0.0813180000 0.0000010000 0.3034340000 0.0018300000 116946771 0 402718720 3.7721149921 4.1903553009 3.8972015381 696 1305031252.7216539383 0.2243391126 0.0859979225 0.2351291925 0.0526359198 0.4769700000 0.0874580000 0.0827370000 0.0000010000 0.3036790000 0.0018120000 116950443 0 402718720 3.7721149921 4.1903553009 3.8972015381 697 1305031252.7578220367 0.2232113481 0.0861947854 0.2351291925 0.0530743173 0.7697100000 0.0739160000 0.0798010000 0.0000000000 0.3014770000 0.3132620000 116954283 0 402718720 3.7721149921 4.1903553009 3.8972015381 698 1305031252.7896919250 0.2221797109 0.0863896062 0.2351291925 0.0532289768 0.5133030000 0.0924320000 0.0960890000 0.0000000000 0.3209180000 0.0024330000 116957899 0 402718720 3.7721149921 4.1903553009 3.8972015381 699 1305031252.8224050999 0.2214918435 0.0865828855 0.2351291925 0.0532983964 0.5059870000 0.0932510000 0.0955040000 0.0000010000 0.3141290000 0.0018060000 116961627 0 402718720 3.7721149921 4.1903553009 3.8972015381 700 1305031252.8539779186 0.2214395702 0.0867755379 0.2351291925 0.0533631736 0.4470780000 0.0735210000 0.0669710000 0.0000010000 0.3035030000 0.0017900000 116965187 0 402718720 3.7721149921 4.1903553009 3.8972015381 701 1305031252.8897290230 0.2212792039 0.0869674119 0.2351291925 0.0533649942 0.7718510000 0.0866550000 0.0676370000 0.0000000000 0.3034430000 0.3128490000 116968971 0 402718720 3.7721149921 4.1903553009 3.8972015381 702 1305031252.9206719398 0.3881592453 0.0873964601 0.3881592453 0.0544319012 0.4758800000 0.0826860000 0.0798130000 0.0000010000 0.3101470000 0.0018890000 116972643 0 402718720 3.6364207268 4.1320672035 3.7722074986 703 1305031252.9578649998 0.4317101836 0.0878862378 0.4317101836 0.0545326580 0.5271380000 0.0873570000 0.0797990000 0.0340920000 0.3228190000 0.0017970000 116976539 0 402718720 3.5947325230 4.1185336113 3.7483286858 704 1305031252.9894239902 0.4451767802 0.0883937528 0.4451767802 0.0546082404 0.4771220000 0.0748560000 0.0702220000 0.0000010000 0.3289420000 0.0018020000 116980099 0 402718720 3.5793509483 4.1124095917 3.7424554825 705 1305031253.0196959972 0.4554064572 0.0889143382 0.4554064572 0.0547468490 0.9070660000 0.0863290000 0.0697860000 0.0339660000 0.3449940000 0.3705440000 116983771 0 402718720 3.5633711815 4.1058950424 3.7418959141 706 1305031253.0574259758 0.4700120389 0.0894541366 0.4700120389 0.0548116083 0.5424090000 0.0950050000 0.0958290000 0.0000000000 0.3476970000 0.0024060000 116987611 0 402718720 3.5461349487 4.0914802551 3.7358441353 707 1305031253.0895500183 0.4676328003 0.0899890428 0.4700120389 0.0548536739 0.5890330000 0.0953180000 0.0949610000 0.0424880000 0.3531670000 0.0017920000 116991227 0 402718720 3.5467243195 4.0795569420 3.7355492115 708 1305031253.1197240353 0.4788748920 0.0905383166 0.4788748920 0.0549079588 0.4922890000 0.0755540000 0.0680950000 0.0000000000 0.3455260000 0.0017890000 116994899 0 402718720 3.5338368416 4.0775389671 3.7300064564 709 1305031253.1573839188 0.4765303135 0.0910827341 0.4788748920 0.0548859359 0.8590740000 0.0759480000 0.0679680000 0.0000010000 0.3453790000 0.3684890000 116998683 0 402718720 3.5338368416 4.0775389671 3.7300064564 710 1305031253.1892180443 0.4759637117 0.0916248200 0.4788748920 0.0548565424 0.4932100000 0.0765370000 0.0681460000 0.0000010000 0.3454210000 0.0018040000 117002299 0 402718720 3.5338368416 4.0775389671 3.7300064564 711 1305031253.2180271149 0.4756681919 0.0921649654 0.4788748920 0.0548356177 0.4924230000 0.0757680000 0.0680900000 0.0000000000 0.3454450000 0.0018060000 117005971 0 402718720 3.5338368416 4.0775389671 3.7300064564 712 1305031253.2578470707 0.4755855799 0.0927034775 0.4788748920 0.0548465404 0.5104920000 0.0924320000 0.0694300000 0.0000010000 0.3455060000 0.0018120000 117009867 0 402718720 3.5338368416 4.0775389671 3.7300064564 713 1305031253.2897419930 0.4760679603 0.0932411555 0.4788748920 0.0548216865 0.8733150000 0.0778720000 0.0803680000 0.0000010000 0.3452310000 0.3685370000 117013483 0 402718720 3.5338368416 4.0775389671 3.7300064564 714 1305031253.3220069408 0.4766198993 0.0937781006 0.4788748920 0.0547896449 0.5083800000 0.0770830000 0.0827920000 0.0000000000 0.3453450000 0.0018450000 117017211 0 402718720 3.5338368416 4.0775389671 3.7300064564 715 1305031253.3578300476 0.1080117598 0.0937980078 0.4788748920 0.0563712778 0.4647730000 0.0765540000 0.0744410000 0.0338610000 0.2767440000 0.0018470000 117020939 0 402718720 3.8577353954 4.0874786377 3.9450349808 716 1305031253.3880970478 0.0699215829 0.0937646608 0.4788748920 0.0564056890 0.4247780000 0.0890800000 0.0638630000 0.0000000000 0.2686500000 0.0018640000 117024555 0 402718720 3.9460330009 4.0867877007 4.0073990822 717 1305031253.4213519096 0.0719999298 0.0937343055 0.4788748920 0.0563678914 0.7661600000 0.0960260000 0.0813770000 0.0340770000 0.2733840000 0.2799880000 117028283 0 402718720 3.9488000870 4.0854272842 4.0088806152 718 1305031253.4579629898 0.0727093890 0.0937050229 0.4788748920 0.0563304307 0.4581550000 0.0755200000 0.0886310000 0.0000000000 0.2900320000 0.0024880000 117032067 0 402718720 3.9488215446 4.0867247581 4.0100469589 719 1305031253.4896900654 0.0710400268 0.0936735000 0.4788748920 0.0562915900 0.5507140000 0.0939400000 0.1150160000 0.0425550000 0.2952380000 0.0024870000 117035739 0 402718720 3.9448940754 4.0892381668 4.0097208023 720 1305031253.5207340717 0.0716828182 0.0936429574 0.4788748920 0.0562541718 0.4216330000 0.0946010000 0.0444480000 0.0000010000 0.2793960000 0.0018720000 117039411 0 402718720 3.9441678524 4.0868196487 4.0086035728 721 1305031253.5578539371 0.0718862340 0.0936127816 0.4788748920 0.0562173930 0.7664060000 0.0733860000 0.0865160000 0.0340410000 0.2826380000 0.2885030000 117043195 0 402718720 3.9411954880 4.0887908936 4.0072932243 722 1305031253.5898048878 0.0692956448 0.0935791014 0.4788748920 0.0561838130 0.4510950000 0.0930050000 0.0735220000 0.0000000000 0.2813610000 0.0018780000 117046867 0 402718720 3.9379673004 4.0914125443 4.0103273392 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 11:30:52 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253987648 0.0253987648 0.0253987648 -nan 0.7965740000 0.1260610000 0.0222550000 0.0619560000 0.0000020000 0.5859710000 106610750 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 1305031102.2112140656 0.0277590584 0.0265789116 0.0277590584 0.0329535045 0.2130840000 0.1262950000 0.0202650000 0.0626960000 0.0000000000 0.0037700000 114090227 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 1305031102.2432110310 0.0337214470 0.0289597567 0.0337214470 0.0304149093 0.2154390000 0.1276420000 0.0212350000 0.0625820000 0.0000000000 0.0039160000 114094291 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 1305031102.2753260136 0.0413634107 0.0320606702 0.0413634107 0.0283056841 0.7000910000 0.1271740000 0.0203610000 0.0617970000 0.4869540000 0.0037440000 114098363 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 1305031102.3112668991 0.0195332766 0.0295551915 0.0413634107 0.0301329753 1.2286290000 0.1276840000 0.1064020000 0.0614070000 0.4583750000 0.4746980000 114102531 0 402718720 3.9956066608 3.9985215664 4.0339016914 6 1305031102.3432331085 0.0165448003 0.0273867929 0.0413634107 0.0279478731 0.4477420000 0.0744640000 0.0741980000 0.0000010000 0.2971540000 0.0018530000 114107003 0 402718720 3.9933164120 3.9975044727 4.0460615158 7 1305031102.3753290176 0.0143036284 0.0255177694 0.0413634107 0.0256299680 0.4464960000 0.0740860000 0.0595880000 0.0302830000 0.2807220000 0.0017510000 114110619 0 402718720 3.9915566444 3.9987485409 4.0578479767 8 1305031102.4112579823 0.0161067452 0.0243413914 0.0413634107 0.0248946716 0.3914280000 0.0736580000 0.0423330000 0.0000010000 0.2736240000 0.0017460000 114114459 0 402718720 3.9903655052 4.0006780624 4.0697340965 9 1305031102.4432709217 0.0140145542 0.0231939650 0.0413634107 0.0252534511 0.7007440000 0.0974210000 0.0496890000 0.0297470000 0.2560050000 0.2677990000 114118899 0 402718720 3.9873249531 4.0034270287 4.0821075439 10 1305031102.4753179550 0.0116283912 0.0220374077 0.0413634107 0.0240293084 0.4263950000 0.0961160000 0.0671040000 0.0000000000 0.2607200000 0.0023760000 114124115 0 402718720 3.9876616001 4.0076684952 4.0952634811 11 1305031102.5112190247 0.0164479204 0.0215292725 0.0413634107 0.0234064148 0.4466910000 0.0964370000 0.0756840000 0.0361120000 0.2366250000 0.0017610000 114127899 0 402718720 3.9873962402 4.0066900253 4.1077766418 12 1305031102.5432200432 0.0179824233 0.0212337017 0.0413634107 0.0223184470 0.3631000000 0.0762460000 0.0599120000 0.0000000000 0.2250040000 0.0018530000 114131627 0 402718720 3.9864506721 4.0065860748 4.1198139191 13 1305031102.5752859116 0.0202759616 0.0211600294 0.0413634107 0.0221564451 0.6267900000 0.0760740000 0.0888610000 0.0299480000 0.2128170000 0.2190140000 114135243 0 402718720 3.9834635258 4.0057702065 4.1314334869 14 1305031102.6112329960 0.0283787381 0.0216756514 0.0413634107 0.0226241234 0.3705770000 0.1060050000 0.0572260000 0.0000000000 0.2055180000 0.0017430000 114139027 0 402718720 3.9843080044 4.0026230812 4.1423969269 15 1305031102.6432650089 0.0308783725 0.0222891662 0.0413634107 0.0225262051 0.3851690000 0.0747700000 0.0848130000 0.0291700000 0.1946340000 0.0017040000 114142699 0 402718720 3.9798226357 4.0030684471 4.1535353661 16 1305031102.6752851009 0.0282430165 0.0226612818 0.0413634107 0.0223398661 0.3188460000 0.0754600000 0.0501790000 0.0000010000 0.1914120000 0.0017130000 114146371 0 402718720 3.9764246941 4.0097103119 4.1653318405 17 1305031102.7112629414 0.0316452645 0.0231897514 0.0413634107 0.0218825356 0.5730400000 0.0756570000 0.0908720000 0.0297330000 0.1852630000 0.1914140000 114151691 0 402718720 3.9767246246 4.0127506256 4.1776738167 18 1305031102.7432339191 0.0347411111 0.0238314936 0.0413634107 0.0213005051 0.3489010000 0.0755550000 0.0849030000 0.0000010000 0.1860170000 0.0023350000 114158619 0 402718720 3.9764032364 4.0140333176 4.1903018951 19 1305031102.7754719257 0.0331617072 0.0243225575 0.0413634107 0.0211256508 0.4047280000 0.0986880000 0.0780230000 0.0354200000 0.1901380000 0.0023660000 114162235 0 402718720 3.9770960808 4.0198845863 4.2032308578 20 1305031102.8112320900 0.0379274115 0.0250028002 0.0413634107 0.0206128080 0.3543380000 0.0988870000 0.0685810000 0.0000000000 0.1844120000 0.0023610000 114166019 0 402718720 3.9762568474 4.0221443176 4.2156372070 21 1305031102.8432900906 0.0389956944 0.0256691285 0.0413634107 0.0201184745 0.5461030000 0.0928890000 0.0874070000 0.0294620000 0.1650490000 0.1711960000 114169747 0 402718720 3.9772496223 4.0255994797 4.2280049324 22 1305031102.8753631115 0.0411703959 0.0263737315 0.0413634107 0.0197014942 0.3005420000 0.0789470000 0.0586140000 0.0000010000 0.1611530000 0.0017350000 114173363 0 402718720 3.9740362167 4.0273656845 4.2397809029 23 1305031102.9111850262 0.0446442552 0.0271681021 0.0446442552 0.0193051934 0.3419330000 0.0775920000 0.0720340000 0.0294280000 0.1604310000 0.0023450000 114177147 0 402718720 3.9713394642 4.0299930573 4.2513957024 24 1305031102.9432289600 0.0453415141 0.0279253276 0.0453415141 0.0191956416 0.3513660000 0.0982620000 0.0864720000 0.0000010000 0.1641750000 0.0023510000 114180875 0 402718720 3.9698371887 4.0335559845 4.2626981735 25 1305031102.9752030373 0.0475470871 0.0287101980 0.0475470871 0.0199041884 0.5468220000 0.0984380000 0.0862500000 0.0349010000 0.1628890000 0.1642390000 114184435 0 402718720 3.9654788971 4.0359382629 4.2742710114 26 1305031103.0112149715 0.0510667562 0.0295700656 0.0510667562 0.0195126625 0.3178010000 0.0797060000 0.0879280000 0.0000000000 0.1483170000 0.0017450000 114188275 0 402718720 3.9648768902 4.0386009216 4.2861423492 27 1305031103.0432269573 0.0534115098 0.0304530821 0.0534115098 0.0191467771 0.3258850000 0.0910880000 0.0592020000 0.0289090000 0.1448300000 0.0017520000 114192003 0 402718720 3.9658265114 4.0412497520 4.2976756096 28 1305031103.0753190517 0.0555776730 0.0313503889 0.0555776730 0.0193429700 0.3386230000 0.1066320000 0.0878060000 0.0000010000 0.1423540000 0.0017230000 114195619 0 402718720 3.9671442509 4.0437264442 4.3083209991 29 1305031103.1112399101 0.0594772063 0.0323202791 0.0594772063 0.0191864859 0.5256070000 0.1023220000 0.0769640000 0.0346610000 0.1525910000 0.1589490000 114199403 0 402718720 3.9668531418 4.0455884933 4.3179030418 30 1305031103.1433179379 0.0581849292 0.0331824341 0.0594772063 0.0188822087 0.3691100000 0.0996770000 0.1148870000 0.0000010000 0.1520700000 0.0023610000 114203075 0 402718720 3.9674313068 4.0516209602 4.3274435997 31 1305031103.1754519939 0.0602662116 0.0340561044 0.0602662116 0.0185820146 0.3391540000 0.0845370000 0.0867990000 0.0292410000 0.1367390000 0.0017330000 114206747 0 402718720 3.9663879871 4.0536775589 4.3364024162 32 1305031103.2112200260 0.0610714592 0.0349003342 0.0610714592 0.0191084643 0.2742880000 0.0798980000 0.0585300000 0.0000000000 0.1340200000 0.0017330000 114210531 0 402718720 3.9658615589 4.0586519241 4.3452491760 33 1305031103.2432160378 0.0621631145 0.0357264791 0.0621631145 0.0188304828 0.4405530000 0.0809350000 0.0659950000 0.0291770000 0.1291930000 0.1351340000 114217331 0 402718720 3.9667422771 4.0620641708 4.3542580605 34 1305031103.2753698826 0.0650172383 0.0365879720 0.0650172383 0.0188643603 0.2679090000 0.0811500000 0.0614650000 0.0000000000 0.1234340000 0.0017460000 114227347 0 402718720 3.9674181938 4.0629873276 4.3626980782 35 1305031103.3112099171 0.0700983480 0.0375454113 0.0700983480 0.0192433774 0.2842290000 0.0813750000 0.0521090000 0.0291320000 0.1197490000 0.0017510000 114231131 0 402718720 3.9659059048 4.0604457855 4.3701777458 36 1305031103.3432230949 0.0758346096 0.0386090002 0.0758346096 0.0198475562 0.2577460000 0.0811520000 0.0579040000 0.0000000000 0.1168360000 0.0017390000 114234859 0 402718720 3.9654288292 4.0556077957 4.3751139641 37 1305031103.3753271103 0.0763622895 0.0396293593 0.0763622895 0.0198080015 0.4033790000 0.0790120000 0.0569480000 0.0290470000 0.1161980000 0.1220530000 114238475 0 402718720 3.9691960812 4.0556817055 4.3777918816 38 1305031103.4112598896 0.0775924698 0.0406283885 0.0775924698 0.0196994887 0.2852450000 0.0788860000 0.0895160000 0.0000000000 0.1149000000 0.0018160000 114242259 0 402718720 3.9701089859 4.0531826019 4.3786330223 39 1305031103.4432799816 0.0807357281 0.0416567819 0.0807357281 0.0195271509 0.3026280000 0.0894060000 0.0673470000 0.0292270000 0.1148020000 0.0017250000 114245987 0 402718720 3.9694337845 4.0481319427 4.3773794174 40 1305031103.4752740860 0.0811245218 0.0426434754 0.0811245218 0.0192943707 0.2625360000 0.0802490000 0.0609720000 0.0000010000 0.1188160000 0.0023700000 114249603 0 402718720 3.9697148800 4.0450797081 4.3745708466 41 1305031103.5113329887 0.0812020451 0.0435839283 0.0812020451 0.0191578072 0.4814050000 0.1009700000 0.0957570000 0.0347010000 0.1264270000 0.1234220000 114253387 0 402718720 3.9699931145 4.0407695770 4.3698463440 42 1305031103.5434439182 0.0811105222 0.0444774186 0.0812020451 0.0190312263 0.2849320000 0.0803220000 0.0837280000 0.0000010000 0.1189130000 0.0018380000 114257115 0 402718720 3.9699738026 4.0357708931 4.3631577492 43 1305031103.5754740238 0.0802845061 0.0453101416 0.0812020451 0.0188522486 0.2860740000 0.0803840000 0.0514270000 0.0292300000 0.1231660000 0.0017460000 114260731 0 402718720 3.9710917473 4.0310411453 4.3548955917 44 1305031103.6112229824 0.0770353898 0.0460311700 0.0812020451 0.0187215400 0.3387840000 0.1180110000 0.0920510000 0.0000010000 0.1267430000 0.0018360000 114264515 0 402718720 3.9729056358 4.0282793045 4.3457403183 45 1305031103.6434450150 0.0753249526 0.0466821429 0.0812020451 0.0185130420 0.4568620000 0.0809410000 0.0775890000 0.0293860000 0.1313490000 0.1374620000 114268243 0 402718720 3.9737975597 4.0236873627 4.3359375000 46 1305031103.6755230427 0.0724255741 0.0472417827 0.0812020451 0.0183416714 0.3018750000 0.0802730000 0.0806250000 0.0000000000 0.1391050000 0.0017420000 114271859 0 402718720 3.9728000164 4.0198273659 4.3255729675 47 1305031103.7116100788 0.0688651800 0.0477018550 0.0812020451 0.0181590727 0.3168600000 0.0796030000 0.0587060000 0.0294700000 0.1472030000 0.0017490000 114275643 0 402718720 3.9737908840 4.0162081718 4.3144435883 48 1305031103.7433259487 0.0657515079 0.0480778894 0.0812020451 0.0180129600 0.3207340000 0.0785480000 0.0868630000 0.0000000000 0.1534460000 0.0017490000 114279371 0 402718720 3.9763457775 4.0123820305 4.3024854660 49 1305031103.7753419876 0.0638061911 0.0483988752 0.0812020451 0.0178254586 0.5302680000 0.0894740000 0.0874490000 0.0295810000 0.1588380000 0.1647860000 114282987 0 402718720 3.9765441418 4.0067057610 4.2898883820 50 1305031103.8112421036 0.0589361712 0.0486096211 0.0812020451 0.0180277803 0.3111980000 0.0773470000 0.0653200000 0.0000000000 0.1666520000 0.0017440000 114286771 0 402718720 3.9777004719 4.0048713684 4.2767829895 51 1305031103.8432509899 0.0550149754 0.0487352163 0.0812020451 0.0180151537 0.3340070000 0.0766150000 0.0577330000 0.0296580000 0.1681210000 0.0017450000 114290499 0 402718720 3.9791316986 4.0025763512 4.2640256882 52 1305031103.8753609657 0.0524332896 0.0488063331 0.0812020451 0.0179584012 0.3384930000 0.0775890000 0.0861200000 0.0000010000 0.1729040000 0.0017400000 114294115 0 402718720 3.9783585072 3.9991288185 4.2520022392 53 1305031103.9112210274 0.0556279793 0.0489350434 0.0812020451 0.0188788245 0.5252830000 0.0776590000 0.0573860000 0.0297890000 0.1759120000 0.1843850000 114297899 0 402718720 3.9778292179 3.9886002541 4.2391610146 54 1305031103.9432110786 0.0558921732 0.0490638791 0.0812020451 0.0187512808 0.3793760000 0.0987490000 0.0773910000 0.0000000000 0.2006870000 0.0023930000 114301627 0 402718720 3.9790174961 3.9813640118 4.2256398201 55 1305031103.9753730297 0.0520141013 0.0491175195 0.0812020451 0.0186915493 0.3867400000 0.0977700000 0.0578970000 0.0359230000 0.1932320000 0.0017760000 114305299 0 402718720 3.9803924561 3.9784111977 4.2111148834 56 1305031104.0112318993 0.0503256321 0.0491390930 0.0812020451 0.0188833013 0.3918800000 0.0897280000 0.0859260000 0.0000000000 0.2136670000 0.0023990000 114309027 0 402718720 3.9829475880 3.9732463360 4.1966362000 57 1305031104.0432488918 0.0481188856 0.0491211946 0.0812020451 0.0188220346 0.6957160000 0.0976710000 0.1147740000 0.0362200000 0.2198130000 0.2270800000 114312755 0 402718720 3.9865407944 3.9676470757 4.1817522049 58 1305031104.0754249096 0.0415088199 0.0489899467 0.0812020451 0.0188578536 0.3470560000 0.0825330000 0.0509290000 0.0000000000 0.2116670000 0.0017810000 114316371 0 402718720 3.9869670868 3.9672598839 4.1664290428 59 1305031104.1112349033 0.0357156806 0.0487649592 0.0812020451 0.0187867509 0.4046520000 0.0987850000 0.0604320000 0.0302470000 0.2131570000 0.0018690000 114320155 0 402718720 3.9884612560 3.9667315483 4.1516323090 60 1305031104.1432299614 0.0334386043 0.0485095199 0.0812020451 0.0187430862 0.3522350000 0.0758990000 0.0577080000 0.0000010000 0.2167150000 0.0017630000 114323883 0 402718720 3.9907071590 3.9611439705 4.1370897293 61 1305031104.1754240990 0.0299056713 0.0482045388 0.0812020451 0.0186869969 0.6155930000 0.0754420000 0.0644000000 0.0302670000 0.2195040000 0.2258250000 114327499 0 402718720 3.9871833324 3.9578177929 4.1231317520 62 1305031104.2112829685 0.0269927736 0.0478624136 0.0812020451 0.0185870066 0.4046020000 0.0872510000 0.0856120000 0.0000000000 0.2298250000 0.0017630000 114331283 0 402718720 3.9879481792 3.9558639526 4.1095061302 63 1305031104.2431960106 0.0239699520 0.0474831681 0.0812020451 0.0184640450 0.4338380000 0.0751080000 0.0904570000 0.0303810000 0.2358600000 0.0018620000 114335011 0 402718720 3.9891138077 3.9525098801 4.0963754654 64 1305031104.2755460739 0.0197000019 0.0470490562 0.0812020451 0.0183253295 0.3967290000 0.0877270000 0.0609570000 0.0000000000 0.2461040000 0.0017800000 114338627 0 402718720 3.9895319939 3.9513356686 4.0832109451 65 1305031104.3112189770 0.0164004192 0.0465775387 0.0812020451 0.0182273890 0.7047640000 0.0747090000 0.0787960000 0.0304460000 0.2572750000 0.2633680000 114348555 0 402718720 3.9909451008 3.9509439468 4.0705351830 66 1305031104.3433420658 0.0120569654 0.0460544997 0.0812020451 0.0181293780 0.3937130000 0.0739330000 0.0501800000 0.0000010000 0.2676670000 0.0017720000 114365083 0 402718720 3.9924015999 3.9502351284 4.0582695007 67 1305031104.3758370876 0.0093841795 0.0455071815 0.0812020451 0.0180560274 0.4298330000 0.0743740000 0.0504180000 0.0305680000 0.2725180000 0.0017900000 114368699 0 402718720 3.9932262897 3.9502370358 4.0463938713 68 1305031104.4115090370 0.0065708635 0.0449345886 0.0812020451 0.0179884794 0.4225100000 0.0735240000 0.0638330000 0.0000010000 0.2832240000 0.0017670000 114372483 0 402718720 3.9933240414 3.9497425556 4.0350370407 69 1305031104.4432880878 0.0045642196 0.0443495108 0.0812020451 0.0179139239 0.7849250000 0.0832070000 0.0846470000 0.0302250000 0.2904350000 0.2962470000 114376155 0 402718720 3.9936602116 3.9486763477 4.0246362686 70 1305031104.4754559994 0.0045716129 0.0437812551 0.0812020451 0.0178385911 0.4466850000 0.0915430000 0.0575880000 0.0000010000 0.2956190000 0.0017650000 114379827 0 402718720 3.9928171635 3.9481384754 4.0151977539 71 1305031104.5113289356 0.0073958761 0.0432687849 0.0812020451 0.0179184016 0.4908320000 0.0726530000 0.0847820000 0.0306690000 0.3007890000 0.0017710000 114383611 0 402718720 3.9901397228 3.9458959103 4.0059709549 72 1305031104.5433681011 0.0059200213 0.0427500521 0.0812020451 0.0178895884 0.4324680000 0.0719370000 0.0525000000 0.0000000000 0.3060730000 0.0017880000 114387339 0 402718720 3.9909553528 3.9422240257 3.9962780476 73 1305031104.5753428936 0.0045452854 0.0422266991 0.0812020451 0.0179959712 0.8878360000 0.0872720000 0.1127940000 0.0373210000 0.3225730000 0.3277070000 114390899 0 402718720 3.9940025806 3.9403240681 3.9862928391 74 1305031104.6113359928 0.0067446213 0.0417472116 0.0812020451 0.0186776033 0.4577310000 0.0847690000 0.0505910000 0.0000010000 0.3204040000 0.0017890000 114394739 0 402718720 3.9983911514 3.9357538223 3.9751882553 75 1305031104.6432430744 0.0102995997 0.0413279101 0.0812020451 0.0186744785 0.4814950000 0.0736740000 0.0501360000 0.0309300000 0.3247720000 0.0018110000 114398411 0 402718720 4.0061154366 3.9320659637 3.9621164799 76 1305031104.6755249500 0.0169678424 0.0410073829 0.0812020451 0.0185561080 0.4698200000 0.0741890000 0.0508550000 0.0000000000 0.3427900000 0.0018110000 114402083 0 402718720 4.0108380318 3.9379408360 3.9479756355 77 1305031104.7112770081 0.0212801844 0.0407511855 0.0812020451 0.0187398714 0.8662080000 0.0739020000 0.0558930000 0.0310790000 0.3479470000 0.3572150000 114405867 0 402718720 4.0134239197 3.9396235943 3.9331493378 78 1305031104.7432799339 0.0287661534 0.0405975313 0.0812020451 0.0186398677 0.5025620000 0.0733580000 0.0639690000 0.0000000000 0.3632140000 0.0018410000 114409539 0 402718720 4.0139846802 3.9449667931 3.9176707268 79 1305031104.7753269672 0.0388049223 0.0405748400 0.0812020451 0.0185437253 0.5629680000 0.0878450000 0.0821920000 0.0314090000 0.3595050000 0.0018340000 114413155 0 402718720 4.0166983604 3.9518728256 3.9037420750 80 1305031104.8114650249 0.0466484129 0.0406507597 0.0812020451 0.0184725479 0.5074280000 0.0724830000 0.0677600000 0.0000010000 0.3650330000 0.0019560000 114416995 0 402718720 4.0195860863 3.9574120045 3.8916897774 81 1305031104.8432579041 0.0574648343 0.0408583408 0.0812020451 0.0183827176 0.9284690000 0.0716180000 0.0688450000 0.0311550000 0.3703750000 0.3862930000 114420667 0 402718720 4.0245394707 3.9650809765 3.8812477589 82 1305031104.8753499985 0.0630491674 0.0411289607 0.0812020451 0.0184039214 0.5289950000 0.0711940000 0.0646040000 0.0000010000 0.3905450000 0.0024570000 114424339 0 402718720 4.0252652168 3.9698758125 3.8749456406 83 1305031104.9115340710 0.0689976066 0.0414647275 0.0812020451 0.0183380255 0.6097420000 0.0874630000 0.0911830000 0.0387810000 0.3902840000 0.0018440000 114428123 0 402718720 4.0269904137 3.9756782055 3.8711915016 84 1305031104.9432621002 0.0730600655 0.0418408625 0.0812020451 0.0182344679 0.5247270000 0.0891880000 0.0597490000 0.0000010000 0.3737540000 0.0018410000 114431795 0 402718720 4.0284914970 3.9794487953 3.8703057766 85 1305031104.9752020836 0.0746938363 0.0422273681 0.0812020451 0.0182118694 0.9192420000 0.0684210000 0.0516970000 0.0318760000 0.3726700000 0.3943870000 114435467 0 402718720 4.0285568237 3.9817826748 3.8721382618 86 1305031105.0112900734 0.0783999339 0.0426479793 0.0812020451 0.0182820614 0.5110730000 0.0701660000 0.0649610000 0.0000010000 0.3739090000 0.0018490000 114439251 0 402718720 4.0292491913 3.9877192974 3.8782682419 87 1305031105.0433731079 0.0813317299 0.0430926201 0.0813317299 0.0182361438 0.5501870000 0.0827220000 0.0651670000 0.0315960000 0.3686450000 0.0018620000 114442923 0 402718720 4.0292625427 3.9938180447 3.8861389160 88 1305031105.0753200054 0.0782600120 0.0434922495 0.0813317299 0.0181676324 0.4920330000 0.0716100000 0.0611020000 0.0000010000 0.3572820000 0.0018460000 114446595 0 402718720 4.0261106491 3.9942131042 3.8962888718 89 1305031105.1112990379 0.0760959834 0.0438585836 0.0813317299 0.0180806266 0.9307970000 0.1021290000 0.0867020000 0.0314510000 0.3489010000 0.3614120000 114450379 0 402718720 4.0241384506 3.9939560890 3.9075140953 90 1305031105.1431059837 0.0710808262 0.0441610530 0.0813317299 0.0180684402 0.5019440000 0.0722500000 0.0909900000 0.0000000000 0.3365370000 0.0019550000 114454051 0 402718720 4.0197277069 3.9925024509 3.9200537205 91 1305031105.1751589775 0.0692892671 0.0444371872 0.0813317299 0.0185175985 0.4850960000 0.0730610000 0.0543350000 0.0307830000 0.3248730000 0.0018430000 114457723 0 402718720 4.0153026581 3.9975647926 3.9365015030 92 1305031105.2112679482 0.0653555468 0.0446645607 0.0813317299 0.0185446422 0.5028920000 0.0740140000 0.0967260000 0.0000010000 0.3301050000 0.0018430000 114461507 0 402718720 4.0104818344 3.9985828400 3.9543209076 93 1305031105.2432699203 0.0548846051 0.0447744536 0.0813317299 0.0185405440 0.7789740000 0.0872930000 0.0510350000 0.0308660000 0.3011220000 0.3084490000 114465179 0 402718720 4.0068225861 3.9912407398 3.9692366123 94 1305031105.2752881050 0.0486398973 0.0448155754 0.0813317299 0.0187002455 0.4334740000 0.0852740000 0.0616620000 0.0000010000 0.2843830000 0.0019330000 114468851 0 402718720 4.0029997826 3.9906864166 3.9858615398 95 1305031105.3112900257 0.0421431772 0.0447874449 0.0813317299 0.0186893643 0.4369990000 0.0753040000 0.0443160000 0.0307070000 0.2840100000 0.0024380000 114472635 0 402718720 3.9951446056 3.9886028767 4.0023217201 96 1305031105.3433020115 0.0337641127 0.0446726185 0.0813317299 0.0186144740 0.4492920000 0.0949630000 0.0682410000 0.0000010000 0.2834540000 0.0024050000 114476307 0 402718720 3.9893426895 3.9846034050 4.0176653862 97 1305031105.3753380775 0.0263128094 0.0444833421 0.0813317299 0.0187500140 0.7346340000 0.0954040000 0.0681810000 0.0368060000 0.2675760000 0.2664540000 114479979 0 402718720 3.9844987392 3.9794325829 4.0319218636 98 1305031105.4112861156 0.0249329600 0.0442838484 0.0813317299 0.0187827466 0.3693930000 0.0749210000 0.0368270000 0.0000010000 0.2556580000 0.0017790000 114483763 0 402718720 3.9820706844 3.9786677361 4.0462942123 99 1305031105.4433159828 0.0220936444 0.0440597049 0.0813317299 0.0187001048 0.4190570000 0.0754540000 0.0655380000 0.0303190000 0.2457480000 0.0017870000 114487435 0 402718720 3.9774606228 3.9829893112 4.0610370636 100 1305031105.4752800465 0.0181026235 0.0438001341 0.0813317299 0.0186331318 0.4046400000 0.0967760000 0.0683810000 0.0000010000 0.2373730000 0.0018790000 114491107 0 402718720 3.9746096134 3.9801485538 4.0751066208 101 1305031105.5113320351 0.0191018824 0.0435555970 0.0813317299 0.0186148432 0.6343030000 0.0746470000 0.0607900000 0.0302410000 0.2307710000 0.2376330000 114494891 0 402718720 3.9733698368 3.9811222553 4.0892319679 102 1305031105.5432820320 0.0173149202 0.0432983354 0.0813317299 0.0185446018 0.3468740000 0.0755890000 0.0439290000 0.0000010000 0.2253800000 0.0017660000 114498563 0 402718720 3.9719152451 3.9825704098 4.1032299995 103 1305031105.5754489899 0.0173513126 0.0430464226 0.0813317299 0.0184593532 0.3931070000 0.0746670000 0.0630150000 0.0296490000 0.2231830000 0.0023500000 114502235 0 402718720 3.9711961746 3.9818112850 4.1167306900 104 1305031105.6113779545 0.0208627470 0.0428331180 0.0813317299 0.0183757081 0.3461760000 0.0748150000 0.0573090000 0.0000010000 0.2120990000 0.0017380000 114506019 0 402718720 3.9703521729 3.9835534096 4.1304092407 105 1305031105.6432731152 0.0232939292 0.0426470305 0.0813317299 0.0183523281 0.5598330000 0.0722620000 0.0446680000 0.0293440000 0.2038320000 0.2094920000 114509691 0 402718720 3.9703779221 3.9824774265 4.1442584991 106 1305031105.6751658916 0.0235856641 0.0424672063 0.0813317299 0.0183162558 0.3198010000 0.0738090000 0.0436620000 0.0000000000 0.2004220000 0.0016860000 114513363 0 402718720 3.9692256451 3.9850473404 4.1583466530 107 1305031105.7113089561 0.0277986173 0.0423301167 0.0813317299 0.0184054547 0.3535460000 0.0745830000 0.0527980000 0.0298700000 0.1942510000 0.0018110000 114517147 0 402718720 3.9712197781 3.9876375198 4.1717796326 108 1305031105.7433118820 0.0305836853 0.0422213534 0.0813317299 0.0183270230 0.3220960000 0.0761440000 0.0535080000 0.0000000000 0.1904850000 0.0017390000 114520819 0 402718720 3.9726266861 3.9884381294 4.1854858398 109 1305031105.7753388882 0.0288907494 0.0420990543 0.0813317299 0.0182505308 0.5939400000 0.0749450000 0.0856050000 0.0296080000 0.1981650000 0.2053650000 114524491 0 402718720 3.9729471207 3.9941985607 4.1993179321 110 1305031105.8112831116 0.0342782438 0.0420279560 0.0813317299 0.0181863336 0.4094360000 0.0975350000 0.1149060000 0.0000010000 0.1943890000 0.0023550000 114528275 0 402718720 3.9727361202 3.9959793091 4.2128548622 111 1305031105.8432710171 0.0352663435 0.0419670406 0.0813317299 0.0181067827 0.3492810000 0.0906030000 0.0504860000 0.0295350000 0.1766970000 0.0017300000 114531947 0 402718720 3.9727258682 3.9990487099 4.2265686989 112 1305031105.8753368855 0.0358839668 0.0419127275 0.0813317299 0.0180468625 0.2953790000 0.0768000000 0.0435270000 0.0000010000 0.1730970000 0.0017250000 114535619 0 402718720 3.9746856689 4.0031204224 4.2401175499 113 1305031105.9112620354 0.0377260819 0.0418756775 0.0813317299 0.0180715643 0.5131000000 0.0781830000 0.0586800000 0.0294440000 0.1693400000 0.1771910000 114539403 0 402718720 3.9756298065 4.0091061592 4.2542767525 114 1305031105.9432721138 0.0392320976 0.0418524882 0.0813317299 0.0180075643 0.3471840000 0.0990100000 0.0689170000 0.0000000000 0.1766400000 0.0023540000 114543075 0 402718720 3.9771828651 4.0124645233 4.2675724030 115 1305031105.9753289223 0.0400759317 0.0418370399 0.0813317299 0.0179890469 0.4254710000 0.0989980000 0.1160160000 0.0356520000 0.1721900000 0.0023570000 114546747 0 402718720 3.9758052826 4.0170826912 4.2805562019 116 1305031106.0112850666 0.0446880832 0.0418616178 0.0813317299 0.0179360958 0.2907220000 0.0787140000 0.0583050000 0.0000010000 0.1517780000 0.0016860000 114550531 0 402718720 3.9756109715 4.0205974579 4.2933168411 117 1305031106.0433549881 0.0464578904 0.0419009022 0.0813317299 0.0178590445 0.4591320000 0.0786810000 0.0582040000 0.0293330000 0.1432800000 0.1493890000 114554259 0 402718720 3.9773213863 4.0242185593 4.3055949211 118 1305031106.0753300190 0.0491764136 0.0419625591 0.0813317299 0.0177993208 0.3058830000 0.0783300000 0.0862440000 0.0000000000 0.1393550000 0.0017210000 114557875 0 402718720 3.9761838913 4.0270848274 4.3177552223 119 1305031106.1113269329 0.0524685904 0.0420508451 0.0813317299 0.0177869495 0.3312380000 0.0905620000 0.0581140000 0.0314700000 0.1484630000 0.0023590000 114561659 0 402718720 3.9734148979 4.0314941406 4.3292603493 120 1305031106.1433548927 0.0534582622 0.0421459069 0.0813317299 0.0177203933 0.3228350000 0.1000980000 0.0771520000 0.0000000000 0.1429510000 0.0023630000 114565387 0 402718720 3.9727587700 4.0356721878 4.3409838676 121 1305031106.1755340099 0.0581432320 0.0422781162 0.0813317299 0.0176528341 0.4758580000 0.0987640000 0.0671450000 0.0346310000 0.1391300000 0.1359390000 114569003 0 402718720 3.9719858170 4.0358958244 4.3519001007 122 1305031106.2112751007 0.0621875487 0.0424413083 0.0813317299 0.0175840827 0.2894030000 0.0787910000 0.0860190000 0.0000010000 0.1226260000 0.0017220000 114572787 0 402718720 3.9704883099 4.0378603935 4.3617601395 123 1305031106.2432670593 0.0667688698 0.0426390933 0.0813317299 0.0175158417 0.2853850000 0.0770580000 0.0568590000 0.0291840000 0.1203190000 0.0017170000 114576515 0 402718720 3.9685785770 4.0376701355 4.3709645271 124 1305031106.2763850689 0.0687034428 0.0428492897 0.0813317299 0.0174513830 0.2646580000 0.0860810000 0.0569160000 0.0000010000 0.1197380000 0.0016760000 114580187 0 402718720 3.9681861401 4.0408697128 4.3785452843 125 1305031106.3112380505 0.0682735220 0.0430526835 0.0813317299 0.0173941323 0.4354250000 0.0781910000 0.0847690000 0.0290040000 0.1188030000 0.1243960000 114583915 0 402718720 3.9683587551 4.0449423790 4.3854069710 126 1305031106.3432579041 0.0698269159 0.0432651774 0.0813317299 0.0174016580 0.2860770000 0.0783550000 0.0904530000 0.0000000000 0.1151910000 0.0018080000 114587643 0 402718720 3.9694843292 4.0468521118 4.3916778564 127 1305031106.3753879070 0.0690261945 0.0434680201 0.0813317299 0.0174265570 0.2990840000 0.0802270000 0.0756580000 0.0291440000 0.1119340000 0.0018510000 114591259 0 402718720 3.9689815044 4.0499095917 4.3965573311 128 1305031106.4113199711 0.0734385252 0.0437021647 0.0813317299 0.0175681043 0.2552420000 0.0797440000 0.0645980000 0.0000010000 0.1089130000 0.0017400000 114595043 0 402718720 3.9698896408 4.0465908051 4.3997197151 129 1305031106.4432780743 0.0795682520 0.0439801963 0.0813317299 0.0177044062 0.4157190000 0.1035320000 0.0603340000 0.0291930000 0.1081420000 0.1142240000 114611003 0 402718720 3.9674446583 4.0398173332 4.4007806778 130 1305031106.4753448963 0.0819069892 0.0442719409 0.0819069892 0.0177626732 0.2710630000 0.0759580000 0.0839970000 0.0000010000 0.1091470000 0.0017040000 114640275 0 402718720 3.9651768208 4.0355730057 4.3989496231 131 1305031106.5111289024 0.0822591633 0.0445619197 0.0822591633 0.0177704235 0.3024070000 0.0776110000 0.0841570000 0.0290350000 0.1096450000 0.0016910000 114643891 0 402718720 3.9657113552 4.0316600800 4.3946104050 132 1305031106.5433020592 0.0827321857 0.0448510884 0.0827321857 0.0177177618 0.2764880000 0.0789020000 0.0848700000 0.0000010000 0.1107150000 0.0017390000 114647619 0 402718720 3.9648811817 4.0269875526 4.3879418373 133 1305031106.5752820969 0.0807005242 0.0451206330 0.0827321857 0.0176728428 0.4110000000 0.0791870000 0.0713150000 0.0286750000 0.1127080000 0.1188430000 114651235 0 402718720 3.9670767784 4.0240936279 4.3790407181 134 1305031106.6111509800 0.0772350281 0.0453602927 0.0827321857 0.0176958103 0.2900960000 0.0877220000 0.0851110000 0.0000000000 0.1152640000 0.0017320000 114655019 0 402718720 3.9659602642 4.0217733383 4.3692855835 135 1305031106.6432070732 0.0750572830 0.0455802704 0.0827321857 0.0176650855 0.2940410000 0.0792030000 0.0679080000 0.0292290000 0.1155930000 0.0018200000 114658747 0 402718720 3.9654846191 4.0184941292 4.3589243889 136 1305031106.6752789021 0.0760672912 0.0458044397 0.0827321857 0.0176240004 0.2749900000 0.0791210000 0.0756200000 0.0000010000 0.1182430000 0.0017410000 114662363 0 402718720 3.9656271935 4.0117211342 4.3473787308 137 1305031106.7115080357 0.0730910078 0.0460036117 0.0827321857 0.0176527550 0.4216680000 0.0910450000 0.0507050000 0.0292620000 0.1221280000 0.1282420000 114666147 0 402718720 3.9653348923 4.0090885162 4.3350458145 138 1305031106.7433409691 0.0729951411 0.0461992025 0.0827321857 0.0176415612 0.2746750000 0.0803120000 0.0684300000 0.0000010000 0.1237940000 0.0018540000 114669875 0 402718720 3.9652156830 4.0032668114 4.3222494125 139 1305031106.7753899097 0.0718777999 0.0463839406 0.0827321857 0.0175831488 0.3203860000 0.0929390000 0.0684000000 0.0288560000 0.1280750000 0.0018220000 114673491 0 402718720 3.9664740562 3.9985821247 4.3087601662 140 1305031106.8112890720 0.0690651610 0.0465459493 0.0827321857 0.0175425782 0.2877450000 0.0794000000 0.0731260000 0.0000010000 0.1332120000 0.0017330000 114677275 0 402718720 3.9699554443 3.9956429005 4.2942056656 141 1305031106.8434159756 0.0659333766 0.0466834488 0.0827321857 0.0175077936 0.4577310000 0.0786030000 0.0604370000 0.0290610000 0.1413980000 0.1479280000 114680947 0 402718720 3.9711613655 3.9927198887 4.2797946930 142 1305031106.8759050369 0.0670844838 0.0468271181 0.0827321857 0.0176392102 0.2948360000 0.0791240000 0.0611000000 0.0000000000 0.1525820000 0.0017470000 114684619 0 402718720 3.9705624580 3.9839737415 4.2641391754 143 1305031106.9112429619 0.0634805709 0.0469435758 0.0827321857 0.0176939017 0.3447760000 0.0790200000 0.0653370000 0.0302920000 0.1674260000 0.0023920000 114688403 0 402718720 3.9660115242 3.9808037281 4.2469468117 144 1305031106.9434390068 0.0559368245 0.0470060289 0.0827321857 0.0176488471 0.3701670000 0.0972580000 0.0953660000 0.0000010000 0.1748970000 0.0023380000 114692075 0 402718720 3.9670143127 3.9809653759 4.2293119431 145 1305031106.9755470753 0.0548873097 0.0470603825 0.0827321857 0.0176597080 0.5616230000 0.0979660000 0.0775880000 0.0357870000 0.1752590000 0.1747330000 114695747 0 402718720 3.9662759304 3.9740393162 4.2116651535 146 1305031107.0115759373 0.0524646342 0.0470973980 0.0827321857 0.0176188431 0.3338660000 0.0777710000 0.0799730000 0.0000000000 0.1740860000 0.0017400000 114699587 0 402718720 3.9651806355 3.9688608646 4.1933994293 147 1305031107.0432810783 0.0422037058 0.0470641075 0.0827321857 0.0176450335 0.3676300000 0.0759830000 0.0784940000 0.0299530000 0.1811830000 0.0017280000 114703259 0 402718720 3.9650340080 3.9724683762 4.1755414009 148 1305031107.0754320621 0.0413337871 0.0470253892 0.0827321857 0.0176770827 0.3544550000 0.0770180000 0.0859590000 0.0000010000 0.1894360000 0.0017470000 114706875 0 402718720 3.9630610943 3.9659025669 4.1593146324 149 1305031107.1112289429 0.0410690866 0.0469854140 0.0827321857 0.0176230403 0.5838950000 0.1021380000 0.0605230000 0.0301160000 0.1922630000 0.1985320000 114710659 0 402718720 3.9622590542 3.9599416256 4.1429395676 150 1305031107.1432600021 0.0347065702 0.0469035550 0.0827321857 0.0176196984 0.3407970000 0.0750140000 0.0637610000 0.0000010000 0.2000300000 0.0016930000 114714387 0 402718720 3.9628305435 3.9609189034 4.1273384094 151 1305031107.1753990650 0.0297651775 0.0467900558 0.0827321857 0.0175714001 0.3630150000 0.0735200000 0.0517020000 0.0302890000 0.2053720000 0.0018170000 114718003 0 402718720 3.9638876915 3.9599552155 4.1125588417 152 1305031107.2113580704 0.0317192897 0.0466909061 0.0827321857 0.0176556811 0.3748250000 0.0741320000 0.0888880000 0.0000010000 0.2097710000 0.0017360000 114721787 0 402718720 3.9625425339 3.9531273842 4.0978264809 153 1305031107.2433779240 0.0279085860 0.0465681458 0.0827321857 0.0176054939 0.6341460000 0.0755060000 0.0648460000 0.0366040000 0.2293880000 0.2274980000 114725459 0 402718720 3.9637911320 3.9513616562 4.0835008621 154 1305031107.2753980160 0.0235042181 0.0464183800 0.0827321857 0.0175589864 0.3675330000 0.0750220000 0.0607000000 0.0000000000 0.2297410000 0.0017700000 114729131 0 402718720 3.9653911591 3.9513115883 4.0696172714 155 1305031107.3112258911 0.0217300579 0.0462591005 0.0827321857 0.0175587236 0.4322010000 0.0752390000 0.0862720000 0.0304550000 0.2381610000 0.0017760000 114732915 0 402718720 3.9670379162 3.9488852024 4.0556669235 156 1305031107.3435089588 0.0224892702 0.0461067298 0.0827321857 0.0176219783 0.3864920000 0.0750720000 0.0612610000 0.0000000000 0.2480650000 0.0017850000 114736643 0 402718720 3.9658179283 3.9449768066 4.0422096252 157 1305031107.3754129410 0.0173264351 0.0459234158 0.0827321857 0.0176483392 0.6788640000 0.0756390000 0.0442360000 0.0305890000 0.2610400000 0.2670620000 114740259 0 402718720 3.9710803032 3.9457480907 4.0293822289 158 1305031107.4112710953 0.0139640914 0.0457211416 0.0827321857 0.0176214882 0.4195430000 0.0979100000 0.0537470000 0.0000010000 0.2657790000 0.0017910000 114744043 0 402718720 3.9762485027 3.9494333267 4.0195693970 159 1305031107.4434189796 0.0149396062 0.0455275471 0.0827321857 0.0175714537 0.4683880000 0.0958940000 0.0658960000 0.0302190000 0.2742530000 0.0018070000 114747771 0 402718720 3.9797947407 3.9506931305 4.0114903450 160 1305031107.4753770828 0.0168812331 0.0453485076 0.0827321857 0.0175240286 0.4048240000 0.0745300000 0.0539470000 0.0000000000 0.2742530000 0.0017870000 114751443 0 402718720 3.9860079288 3.9541079998 4.0057187080 161 1305031107.5113520622 0.0212573763 0.0451988733 0.0827321857 0.0174950828 0.7518830000 0.0745060000 0.0610050000 0.0307490000 0.2879860000 0.2972940000 114755171 0 402718720 3.9895393848 3.9562640190 4.0014185905 162 1305031107.5436050892 0.0259126425 0.0450798224 0.0827321857 0.0175099106 0.4391300000 0.0927360000 0.0577550000 0.0000000000 0.2865410000 0.0017830000 114758899 0 402718720 3.9930422306 3.9616842270 3.9998235703 163 1305031107.5754539967 0.0259858333 0.0449626814 0.0827321857 0.0174897559 0.4318260000 0.0735370000 0.0506710000 0.0307150000 0.2747990000 0.0017910000 114762515 0 402718720 3.9951105118 3.9604098797 3.9987828732 164 1305031107.6112709045 0.0258845091 0.0448463511 0.0827321857 0.0174465761 0.4020180000 0.0792950000 0.0460760000 0.0000010000 0.2745410000 0.0017850000 114766299 0 402718720 3.9977681637 3.9587149620 3.9980978966 165 1305031107.6433229446 0.0264126770 0.0447346319 0.0827321857 0.0174356199 0.7484980000 0.0742280000 0.0866880000 0.0307110000 0.2749430000 0.2816130000 114770027 0 402718720 4.0025115013 3.9650483131 3.9997739792 166 1305031107.6755681038 0.0257152375 0.0446200572 0.0827321857 0.0174026703 0.4340180000 0.0731480000 0.0852210000 0.0000000000 0.2735510000 0.0017800000 114773643 0 402718720 4.0016832352 3.9649858475 4.0012631416 167 1305031107.7113070488 0.0243254583 0.0444985326 0.0827321857 0.0173584554 0.4723520000 0.0842510000 0.0844350000 0.0307280000 0.2708400000 0.0017750000 114777427 0 402718720 4.0019474030 3.9658055305 4.0030279160 168 1305031107.7435379028 0.0247063655 0.0443807221 0.0827321857 0.0173394955 0.4101310000 0.0724340000 0.0668620000 0.0000010000 0.2687300000 0.0017790000 114781099 0 402718720 4.0004129410 3.9692940712 4.0055809021 169 1305031107.7758018970 0.0246568080 0.0442640126 0.0827321857 0.0172962002 0.7236160000 0.1065460000 0.0509970000 0.0306030000 0.2643810000 0.2707540000 114784771 0 402718720 3.9987618923 3.9714424610 4.0082297325 170 1305031107.8115959167 0.0226262417 0.0441367316 0.0827321857 0.0172470801 0.3965900000 0.0739440000 0.0605980000 0.0000010000 0.2599510000 0.0017750000 114788555 0 402718720 3.9976880550 3.9702937603 4.0107874870 171 1305031107.8433320522 0.0211628191 0.0440023812 0.0827321857 0.0172056189 0.4289270000 0.0737030000 0.0643320000 0.0305830000 0.2582010000 0.0017750000 114792227 0 402718720 3.9988255501 3.9714353085 4.0133228302 172 1305031107.8753581047 0.0208955426 0.0438680391 0.0827321857 0.0171810271 0.4195870000 0.0726060000 0.0891360000 0.0000010000 0.2557540000 0.0017600000 114795899 0 402718720 3.9981234074 3.9705915451 4.0153617859 173 1305031107.9115409851 0.0204093177 0.0437324396 0.0827321857 0.0171635043 0.6716590000 0.0732850000 0.0507960000 0.0300380000 0.2554140000 0.2617950000 114799683 0 402718720 4.0001273155 3.9689407349 4.0168457031 174 1305031107.9431219101 0.0223061759 0.0436093001 0.0827321857 0.0171681021 0.3866360000 0.0745700000 0.0536970000 0.0000010000 0.2562690000 0.0017650000 114803355 0 402718720 4.0023880005 3.9692475796 4.0179944038 175 1305031107.9758069515 0.0260662846 0.0435090543 0.0827321857 0.0171544566 0.4179360000 0.0745220000 0.0504960000 0.0305170000 0.2602950000 0.0017710000 114807027 0 402718720 4.0067138672 3.9700901508 4.0189943314 176 1305031108.0113201141 0.0289823804 0.0434265164 0.0827321857 0.0171205397 0.3872100000 0.0761060000 0.0443460000 0.0000000000 0.2646390000 0.0017880000 114810811 0 402718720 4.0115118027 3.9703288078 4.0201144218 177 1305031108.0434179306 0.0322092250 0.0433631419 0.0827321857 0.0170816691 0.7298050000 0.0747380000 0.0511700000 0.0299800000 0.2823870000 0.2911520000 114814483 0 402718720 4.0184340477 3.9735033512 4.0215945244 178 1305031108.0753519535 0.0350109413 0.0433162194 0.0827321857 0.0170470416 0.4571480000 0.0964010000 0.0783660000 0.0000000000 0.2802410000 0.0018010000 114818099 0 402718720 4.0270986557 3.9771957397 4.0230693817 179 1305031108.1113779545 0.0432126336 0.0433156407 0.0827321857 0.0170067275 0.4884270000 0.0878990000 0.0880130000 0.0305620000 0.2798120000 0.0018030000 114821883 0 402718720 4.0323181152 3.9769873619 4.0245289803 180 1305031108.1433339119 0.0475717410 0.0433392857 0.0827321857 0.0169791731 0.4557460000 0.0761730000 0.0916030000 0.0000010000 0.2858300000 0.0018000000 114825555 0 402718720 4.0389385223 3.9781277180 4.0271120071 181 1305031108.1760580540 0.0520508923 0.0433874161 0.0827321857 0.0170099633 0.7664860000 0.1021130000 0.0607270000 0.0306200000 0.2815850000 0.2910650000 114829227 0 402718720 4.0505695343 3.9824442863 4.0301022530 182 1305031108.2114748955 0.0537128560 0.0434441493 0.0827321857 0.0169997297 0.4239640000 0.0760220000 0.0614000000 0.0000010000 0.2843900000 0.0018090000 114833011 0 402718720 4.0602483749 3.9871447086 4.0344204903 183 1305031108.2433469296 0.0539054573 0.0435013149 0.0827321857 0.0169943606 0.4713700000 0.0761510000 0.0852580000 0.0300510000 0.2777520000 0.0018050000 114836683 0 402718720 4.0698661804 3.9832146168 4.0378580093 184 1305031108.2753579617 0.0546374023 0.0435618372 0.0827321857 0.0169501948 0.4443290000 0.0961830000 0.0570170000 0.0000020000 0.2883160000 0.0024250000 114840355 0 402718720 4.0799803734 3.9796652794 4.0405969620 185 1305031108.3113319874 0.0608691946 0.0436553904 0.0827321857 0.0170661007 0.8100510000 0.0968410000 0.0954780000 0.0368270000 0.2858230000 0.2947320000 114844139 0 402718720 4.0876288414 3.9858455658 4.0441422462 186 1305031108.3432779312 0.0618119463 0.0437530063 0.0827321857 0.0170553393 0.4245620000 0.0770600000 0.0724940000 0.0000010000 0.2728520000 0.0018020000 114847867 0 402718720 4.0964870453 3.9883971214 4.0483436584 187 1305031108.3754100800 0.0612543076 0.0438465962 0.0827321857 0.0170258133 0.4251890000 0.0778110000 0.0513220000 0.0299060000 0.2639930000 0.0018040000 114851483 0 402718720 4.1068916321 3.9881503582 4.0522985458 188 1305031108.4113609791 0.0634890720 0.0439510774 0.0827321857 0.0169852373 0.3876270000 0.0776750000 0.0451260000 0.0000000000 0.2626830000 0.0017890000 114855267 0 402718720 4.1184749603 3.9870743752 4.0560483932 189 1305031108.4436099529 0.0609316789 0.0440409219 0.0827321857 0.0169966248 0.6998410000 0.0894810000 0.0601260000 0.0302910000 0.2552800000 0.2643030000 114858995 0 402718720 4.1322679520 3.9853191376 4.0588231087 190 1305031108.4754710197 0.0602324642 0.0441261405 0.0827321857 0.0169973507 0.4101520000 0.0785690000 0.0752950000 0.0000010000 0.2541400000 0.0017870000 114862611 0 402718720 4.1444573402 3.9838175774 4.0613393784 191 1305031108.5113780499 0.0647718683 0.0442342333 0.0827321857 0.0172469563 0.4255180000 0.0907530000 0.0526080000 0.0302880000 0.2497100000 0.0017900000 114866395 0 402718720 4.1559658051 3.9809162617 4.0625433922 192 1305031108.5437369347 0.0651191846 0.0443430091 0.0827321857 0.0172908639 0.4150550000 0.0795070000 0.0670820000 0.0000020000 0.2656410000 0.0024270000 114870123 0 402718720 4.1685142517 3.9788911343 4.0621080399 193 1305031108.5754139423 0.0671851858 0.0444613624 0.0827321857 0.0173272103 0.7446030000 0.1005560000 0.0690320000 0.0364550000 0.2645800000 0.2736200000 114873739 0 402718720 4.1782450676 3.9800555706 4.0626482964 194 1305031108.6114070415 0.0729852393 0.0446083927 0.0827321857 0.0173244702 0.4385640000 0.0918810000 0.0873880000 0.0000010000 0.2571360000 0.0017920000 114877523 0 402718720 4.1861453056 3.9874958992 4.0636935234 195 1305031108.6433029175 0.0745668411 0.0447620257 0.0827321857 0.0172898501 0.4109980000 0.0786700000 0.0507370000 0.0302560000 0.2491790000 0.0017850000 114881251 0 402718720 4.1961426735 3.9880468845 4.0646839142 196 1305031108.6753749847 0.0760406777 0.0449216107 0.0827321857 0.0172891482 0.4151780000 0.0784610000 0.0807540000 0.0000010000 0.2538080000 0.0017890000 114884867 0 402718720 4.2049217224 3.9921939373 4.0665912628 197 1305031108.7114109993 0.0800849348 0.0451001047 0.0827321857 0.0173023559 0.7052540000 0.0792830000 0.0877770000 0.0302900000 0.2479820000 0.2595530000 114888595 0 402718720 4.2139573097 3.9949293137 4.0679545403 198 1305031108.7435019016 0.0825972110 0.0452894841 0.0827321857 0.0172752181 0.3825240000 0.0792440000 0.0449770000 0.0000000000 0.2561370000 0.0017900000 114892323 0 402718720 4.2215251923 3.9930949211 4.0688986778 199 1305031108.7754929066 0.0834045336 0.0454810170 0.0834045336 0.0172346730 0.4534510000 0.0906160000 0.0868400000 0.0298210000 0.2440070000 0.0017880000 114895939 0 402718720 4.2292137146 3.9930264950 4.0694503784 200 1305031108.8112440109 0.0843561143 0.0456753925 0.0843561143 0.0171932275 0.4108520000 0.0794750000 0.0700780000 0.0000000000 0.2584740000 0.0024100000 114899723 0 402718720 4.2369222641 3.9950866699 4.0694894791 201 1305031108.8432641029 0.0833196118 0.0458626771 0.0843561143 0.0185378933 0.7694620000 0.0992150000 0.1179830000 0.0364390000 0.2524300000 0.2630150000 114903451 0 402718720 4.2439131737 3.9941768646 4.0684285164 202 1305031108.8765149117 0.0772105306 0.0460178645 0.0843561143 0.0185673599 0.3827310000 0.0789880000 0.0604050000 0.0000010000 0.2411800000 0.0017750000 114907123 0 402718720 4.2511010170 3.9933032990 4.0665268898 203 1305031108.9113640785 0.0731635988 0.0461515873 0.0843561143 0.0186459801 0.3968420000 0.0784260000 0.0453450000 0.0302330000 0.2406760000 0.0017750000 114910851 0 402718720 4.2563552856 3.9929349422 4.0641236305 204 1305031108.9432430267 0.0728973523 0.0462826940 0.0843561143 0.0187147162 0.4498450000 0.1169370000 0.0899530000 0.0000000000 0.2407760000 0.0017880000 114914579 0 402718720 4.2590894699 3.9889969826 4.0609197617 205 1305031108.9752678871 0.0700460225 0.0463986127 0.0843561143 0.0186946197 0.6542220000 0.0793550000 0.0548580000 0.0298120000 0.2391600000 0.2506480000 114918251 0 402718720 4.2593193054 3.9896249771 4.0581278801 206 1305031109.0112690926 0.0642224029 0.0464851360 0.0843561143 0.0186648858 0.3733230000 0.0783300000 0.0547250000 0.0000010000 0.2379890000 0.0018770000 114921979 0 402718720 4.2578983307 3.9944353104 4.0564508438 207 1305031109.0432770252 0.0610071570 0.0465552907 0.0843561143 0.0186468290 0.4220190000 0.0770210000 0.0766130000 0.0302840000 0.2359370000 0.0017730000 114925707 0 402718720 4.2559843063 3.9924230576 4.0542244911 208 1305031109.0754098892 0.0601996928 0.0466208887 0.0843561143 0.0186426698 0.3802310000 0.0781470000 0.0547620000 0.0000010000 0.2444790000 0.0024070000 114929323 0 402718720 4.2496042252 3.9928479195 4.0531649590 209 1305031109.1112821102 0.0552141853 0.0466620050 0.0843561143 0.0186150750 0.6971260000 0.0986970000 0.0890630000 0.0364480000 0.2326570000 0.2398680000 114933107 0 402718720 4.2423849106 3.9960656166 4.0529804230 210 1305031109.1433339119 0.0529949293 0.0466921618 0.0843561143 0.0185950273 0.3576960000 0.0776020000 0.0515830000 0.0000010000 0.2263500000 0.0017690000 114936835 0 402718720 4.2356867790 3.9921648502 4.0519385338 211 1305031109.1754639149 0.0510937013 0.0467130222 0.0843561143 0.0186016675 0.3976370000 0.0782690000 0.0701910000 0.0302800000 0.2166160000 0.0018650000 114940451 0 402718720 4.2282490730 3.9907338619 4.0510916710 212 1305031109.2113790512 0.0441324525 0.0467008497 0.0843561143 0.0185990857 0.3470500000 0.0787280000 0.0523830000 0.0000000000 0.2137590000 0.0017770000 114944235 0 402718720 4.2202668190 3.9951231480 4.0516691208 213 1305031109.2432899475 0.0396799073 0.0466678875 0.0843561143 0.0185626634 0.5825740000 0.0794130000 0.0525720000 0.0302280000 0.2067210000 0.2132380000 114947963 0 402718720 4.2112946510 3.9992573261 4.0534229279 214 1305031109.2753078938 0.0397714227 0.0466356610 0.0843561143 0.0187015397 0.3697120000 0.0980140000 0.0637080000 0.0000010000 0.2058020000 0.0017830000 114951579 0 402718720 4.2012085915 3.9917576313 4.0537781715 215 1305031109.3113288879 0.0382875614 0.0465968326 0.0843561143 0.0187654899 0.3692790000 0.0795250000 0.0561760000 0.0298250000 0.2014770000 0.0018540000 114955363 0 402718720 4.1893839836 3.9851577282 4.0533165932 216 1305031109.3432478905 0.0337892361 0.0465375382 0.0843561143 0.0187979732 0.3390940000 0.0793110000 0.0555970000 0.0000010000 0.2018800000 0.0018780000 114959091 0 402718720 4.1778421402 3.9897897243 4.0540161133 217 1305031109.3753969669 0.0313142464 0.0464673848 0.0843561143 0.0187599287 0.5871770000 0.0797760000 0.0525700000 0.0302680000 0.2031130000 0.2209990000 114962707 0 402718720 4.1657443047 3.9903171062 4.0551118851 218 1305031109.4113290310 0.0274421740 0.0463801132 0.0843561143 0.0187199341 0.3886950000 0.1009990000 0.0706450000 0.0000010000 0.2141760000 0.0024140000 114966491 0 402718720 4.1552472115 3.9867451191 4.0553321838 219 1305031109.4433019161 0.0231294222 0.0462739457 0.0843561143 0.0186983590 0.4207690000 0.1007190000 0.0807390000 0.0365460000 0.2005690000 0.0017890000 114970163 0 402718720 4.1444435120 3.9893641472 4.0557923317 220 1305031109.4753630161 0.0223277137 0.0461650991 0.0843561143 0.0186833037 0.3380260000 0.0794130000 0.0556450000 0.0000010000 0.2006630000 0.0018770000 114973779 0 402718720 4.1312494278 3.9886171818 4.0559058189 221 1305031109.5112729073 0.0211832169 0.0460520590 0.0843561143 0.0186662399 0.5721720000 0.0776790000 0.0621390000 0.0301400000 0.1976990000 0.2040920000 114977563 0 402718720 4.1181325912 3.9850716591 4.0549349785 222 1305031109.5432939529 0.0227178503 0.0459469499 0.0843561143 0.0186434915 0.3306900000 0.0779670000 0.0523530000 0.0000010000 0.1982210000 0.0017310000 114981291 0 402718720 4.1044592857 3.9826099873 4.0532240868 223 1305031109.5753619671 0.0196020417 0.0458288113 0.0843561143 0.0186033507 0.3625790000 0.0786630000 0.0524850000 0.0302750000 0.1989670000 0.0017760000 114984963 0 402718720 4.0937557220 3.9846591949 4.0513129234 224 1305031109.6113100052 0.0158879310 0.0456951467 0.0843561143 0.0185858807 0.3262710000 0.0783060000 0.0448530000 0.0000010000 0.2009380000 0.0017600000 114988691 0 402718720 4.0803503990 3.9865844250 4.0496654510 225 1305031109.6432290077 0.0156035190 0.0455614061 0.0843561143 0.0185453004 0.5647880000 0.0778920000 0.0448150000 0.0302870000 0.2025910000 0.2087800000 114992419 0 402718720 4.0679965019 3.9873325825 4.0485086441 226 1305031109.6752629280 0.0130617060 0.0454176021 0.0843561143 0.0185067151 0.3576250000 0.0774390000 0.0731920000 0.0000000000 0.2048330000 0.0017450000 114996035 0 402718720 4.0583233833 3.9893059731 4.0477499962 227 1305031109.7113120556 0.0110451402 0.0452661816 0.0843561143 0.0185345984 0.4715010000 0.0978510000 0.1182410000 0.0365990000 0.2159370000 0.0024040000 114999819 0 402718720 4.0457243919 3.9905467033 4.0477519035 228 1305031109.7432739735 0.0093874419 0.0451088187 0.0843561143 0.0184947827 0.3926650000 0.0989340000 0.0692480000 0.0000010000 0.2216080000 0.0024000000 115003547 0 402718720 4.0324444771 3.9932167530 4.0487537384 229 1305031109.7752768993 0.0103164427 0.0449568869 0.0843561143 0.0184720064 0.6110420000 0.0884100000 0.0844200000 0.0303500000 0.2005360000 0.2068990000 115007163 0 402718720 4.0196275711 3.9923391342 4.0500073433 230 1305031109.8113710880 0.0098473225 0.0448042366 0.0843561143 0.0184403318 0.3672490000 0.0747210000 0.0852440000 0.0000010000 0.2051180000 0.0017350000 115010947 0 402718720 4.0069684982 3.9921712875 4.0511651039 231 1305031109.8432960510 0.0087150699 0.0446480065 0.0843561143 0.0184076973 0.4073780000 0.1031800000 0.0720060000 0.0297760000 0.2002490000 0.0017400000 115014675 0 402718720 3.9940683842 3.9941053391 4.0530533791 232 1305031109.8753058910 0.0088616842 0.0444937551 0.0843561143 0.0183758759 0.3366160000 0.0763200000 0.0507130000 0.0000000000 0.2074250000 0.0017280000 115018291 0 402718720 3.9805068970 3.9946992397 4.0558042526 233 1305031109.9112648964 0.0116023123 0.0443525901 0.0843561143 0.0183527580 0.5643360000 0.0762380000 0.0505050000 0.0302820000 0.2002200000 0.2066600000 115022075 0 402718720 3.9615740776 3.9932827950 4.0589885712 234 1305031109.9432990551 0.0128790168 0.0442180876 0.0843561143 0.0183421432 0.3898550000 0.0910270000 0.0913520000 0.0000000000 0.2052000000 0.0018220000 115025803 0 402718720 3.9497838020 3.9932222366 4.0623369217 235 1305031109.9752581120 0.0105223740 0.0440747016 0.0843561143 0.0183079756 0.4142980000 0.0880200000 0.0860720000 0.0303340000 0.2070390000 0.0023530000 115029419 0 402718720 3.9374988079 3.9972128868 4.0661320686 236 1305031110.0112559795 0.0143559529 0.0439487747 0.0843561143 0.0182730171 0.4451740000 0.0966880000 0.1151600000 0.0000010000 0.2304720000 0.0023660000 115033203 0 402718720 3.9242753983 3.9951114655 4.0696325302 237 1305031110.0432989597 0.0154830357 0.0438286661 0.0843561143 0.0182360230 0.6516810000 0.0967880000 0.0773050000 0.0364880000 0.2229520000 0.2177090000 115036931 0 402718720 3.9114537239 3.9954564571 4.0732417107 238 1305031110.0753190517 0.0172843710 0.0437171355 0.0843561143 0.0182125685 0.3437670000 0.0743940000 0.0508190000 0.0000010000 0.2163930000 0.0017230000 115040547 0 402718720 3.9006943703 3.9956622124 4.0767188072 239 1305031110.1113250256 0.0186518282 0.0436122597 0.0843561143 0.0182294111 0.4133540000 0.0889490000 0.0864770000 0.0303770000 0.2053390000 0.0017690000 115044331 0 402718720 3.8858518600 3.9962930679 4.0806875229 240 1305031110.1434319019 0.0225742031 0.0435246011 0.0843561143 0.0182575103 0.3814770000 0.0761190000 0.0865450000 0.0000000000 0.2166080000 0.0017560000 115048059 0 402718720 3.8740017414 3.9930946827 4.0841169357 241 1305031110.1756410599 0.0256931297 0.0434506116 0.0843561143 0.0182199250 0.6067800000 0.0762250000 0.0863360000 0.0299380000 0.2034860000 0.2103570000 115051675 0 402718720 3.8642046452 3.9915456772 4.0874490738 242 1305031110.2116370201 0.0263532195 0.0433799612 0.0843561143 0.0181904497 0.3564580000 0.0755920000 0.0651060000 0.0000010000 0.2135610000 0.0017540000 115055515 0 402718720 3.8545739651 3.9948182106 4.0898756981 243 1305031110.2433230877 0.0307338759 0.0433279197 0.0843561143 0.0181901143 0.3757760000 0.0753520000 0.0601880000 0.0305320000 0.2073810000 0.0018520000 115059187 0 402718720 3.8445811272 3.9907658100 4.0925049782 244 1305031110.2793209553 0.0338526741 0.0432890868 0.0843561143 0.0181660814 0.3764820000 0.0987210000 0.0582500000 0.0000000000 0.2166180000 0.0023800000 115062971 0 402718720 3.8337950706 3.9892344475 4.0943546295 245 1305031110.3114039898 0.0346794836 0.0432539455 0.0843561143 0.0181304840 0.6091960000 0.0754830000 0.0758320000 0.0300250000 0.2101550000 0.2172220000 115066587 0 402718720 3.8245391846 3.9892706871 4.0951023102 246 1305031110.3433549404 0.0343451053 0.0432177307 0.0843561143 0.0181038074 0.3507440000 0.0760320000 0.0542210000 0.0000010000 0.2182970000 0.0017480000 115070259 0 402718720 3.8134694099 3.9908826351 4.0956687927 247 1305031110.3792810440 0.0362197720 0.0431893989 0.0843561143 0.0180919359 0.3935280000 0.0759810000 0.0653520000 0.0305310000 0.2194290000 0.0017860000 115074043 0 402718720 3.8040144444 3.9925601482 4.0961327553 248 1305031110.4114689827 0.0372083038 0.0431652816 0.0843561143 0.0180710844 0.3977250000 0.0761930000 0.0877250000 0.0000010000 0.2309060000 0.0023920000 115077715 0 402718720 3.7931263447 3.9934601784 4.0967860222 249 1305031110.4432599545 0.0369965509 0.0431405076 0.0843561143 0.0180416537 0.6819090000 0.0970200000 0.0903630000 0.0301740000 0.2282320000 0.2356690000 115081387 0 402718720 3.7818877697 3.9982602596 4.0979995728 250 1305031110.4793310165 0.0413910560 0.0431335098 0.0843561143 0.0180682951 0.4080910000 0.0768520000 0.0929110000 0.0000010000 0.2359620000 0.0018860000 115085227 0 402718720 3.7711479664 3.9979822636 4.0995626450 251 1305031110.5114290714 0.0466742292 0.0431476162 0.0843561143 0.0180551735 0.4033460000 0.0774710000 0.0591740000 0.0307420000 0.2336970000 0.0018020000 115088843 0 402718720 3.7638070583 3.9948711395 4.1017050743 252 1305031110.5434079170 0.0485416502 0.0431690211 0.0843561143 0.0180291694 0.3847360000 0.0766120000 0.0628350000 0.0000010000 0.2430190000 0.0018070000 115092571 0 402718720 3.7534403801 3.9960911274 4.1035337448 253 1305031110.5794260502 0.0514037572 0.0432015695 0.0843561143 0.0180211084 0.7173440000 0.0783560000 0.0891040000 0.0303930000 0.2528420000 0.2661360000 115096355 0 402718720 3.7441918850 4.0001478195 4.1052513123 254 1305031110.6113069057 0.0529301167 0.0432398708 0.0843561143 0.0180337476 0.4573330000 0.0994990000 0.0904630000 0.0000010000 0.2644030000 0.0024490000 115099971 0 402718720 3.7328271866 4.0000910759 4.1076407433 255 1305031110.6434180737 0.0581885949 0.0432984933 0.0843561143 0.0180658287 0.4481810000 0.0831680000 0.0894360000 0.0309760000 0.2423130000 0.0018210000 115103699 0 402718720 3.7267596722 3.9938857555 4.1096887589 256 1305031110.6796059608 0.0585674979 0.0433581378 0.0843561143 0.0180808894 0.4145650000 0.0785480000 0.0882440000 0.0000000000 0.2454830000 0.0018150000 115107427 0 402718720 3.7175207138 3.9953131676 4.1099433899 257 1305031110.7114119530 0.0578740910 0.0434146202 0.0843561143 0.0180520503 0.6976500000 0.0781610000 0.0834710000 0.0309970000 0.2470420000 0.2575070000 115135675 0 402718720 3.7100641727 3.9992482662 4.1108217239 258 1305031110.7432489395 0.0608755127 0.0434822980 0.0843561143 0.0180655250 0.4000260000 0.0764190000 0.0709460000 0.0000000000 0.2502910000 0.0018690000 115190547 0 402718720 3.7058675289 3.9951467514 4.1122765541 259 1305031110.7791929245 0.0625504181 0.0435559201 0.0843561143 0.0180316499 0.4308840000 0.0903130000 0.0588000000 0.0310320000 0.2484450000 0.0018130000 115194331 0 402718720 3.7008786201 3.9933254719 4.1130509377 260 1305031110.8113861084 0.0618401766 0.0436262442 0.0843561143 0.0179982189 0.4084530000 0.0763600000 0.0789390000 0.0000010000 0.2508910000 0.0017850000 115198003 0 402718720 3.6984248161 3.9954841137 4.1129107475 261 1305031110.8432180882 0.0606170408 0.0436913430 0.0843561143 0.0179756733 0.7167970000 0.0772530000 0.0680220000 0.0305690000 0.2633540000 0.2770650000 115201675 0 402718720 3.6945300102 3.9963338375 4.1130003929 262 1305031110.8793129921 0.0632079020 0.0437658337 0.0843561143 0.0179431228 0.4871900000 0.0983190000 0.1204760000 0.0000000000 0.2660960000 0.0018060000 115205459 0 402718720 3.6928434372 3.9920649529 4.1148738861 263 1305031110.9113330841 0.0632262006 0.0438398275 0.0843561143 0.0179193747 0.4509740000 0.0760950000 0.0890190000 0.0310770000 0.2525030000 0.0017950000 115209131 0 402718720 3.6950886250 3.9934179783 4.1150484085 264 1305031110.9438619614 0.0635288283 0.0439144070 0.0843561143 0.0179081449 0.4382650000 0.0876570000 0.0944770000 0.0000010000 0.2538520000 0.0017930000 115212859 0 402718720 3.6959555149 3.9923815727 4.1160039902 265 1305031110.9793450832 0.0620852560 0.0439829763 0.0843561143 0.0179325578 0.6732320000 0.0762470000 0.0527610000 0.0311370000 0.2505200000 0.2620910000 115216531 0 402718720 3.7002506256 3.9939367771 4.1160068512 266 1305031111.0114309788 0.0604526140 0.0440448922 0.0843561143 0.0179218034 0.3908950000 0.0781740000 0.0616080000 0.0000010000 0.2488190000 0.0018060000 115220259 0 402718720 3.7066214085 3.9972076416 4.1161098480 267 1305031111.0433270931 0.0620134547 0.0441121902 0.0843561143 0.0178887059 0.4505030000 0.0981230000 0.0812180000 0.0310690000 0.2376800000 0.0018910000 115223931 0 402718720 3.7121372223 3.9944007397 4.1173310280 268 1305031111.0792829990 0.0574038252 0.0441617859 0.0843561143 0.0178854971 0.4114610000 0.0784320000 0.0979800000 0.0000010000 0.2327520000 0.0018030000 115227659 0 402718720 3.7165091038 3.9974420071 4.1160020828 269 1305031111.1115078926 0.0567198619 0.0442084701 0.0843561143 0.0178671490 0.6450180000 0.0913130000 0.0543550000 0.0310130000 0.2298960000 0.2379460000 115231387 0 402718720 3.7246980667 3.9970877171 4.1154527664 270 1305031111.1432569027 0.0579504557 0.0442593664 0.0843561143 0.0178511545 0.3796130000 0.0768190000 0.0727510000 0.0000010000 0.2277500000 0.0017960000 115235059 0 402718720 3.7343401909 3.9945447445 4.1154108047 271 1305031111.1793260574 0.0548760928 0.0442985425 0.0843561143 0.0178959647 0.4263520000 0.0780820000 0.0911480000 0.0304710000 0.2243480000 0.0018060000 115238843 0 402718720 3.7424743176 3.9952414036 4.1142168045 272 1305031111.2114329338 0.0529040582 0.0443301804 0.0843561143 0.0178791289 0.3558800000 0.0790120000 0.0541390000 0.0000010000 0.2204210000 0.0017990000 115242459 0 402718720 3.7551350594 3.9969453812 4.1125903130 273 1305031111.2432360649 0.0494589061 0.0443489670 0.0843561143 0.0179215393 0.6358190000 0.0763960000 0.0906420000 0.0306730000 0.2154210000 0.2221880000 115246131 0 402718720 3.7615530491 3.9982473850 4.1109542847 274 1305031111.2793080807 0.0494410247 0.0443675511 0.0843561143 0.0179791317 0.3792360000 0.0885380000 0.0747060000 0.0000010000 0.2137080000 0.0017750000 115249915 0 402718720 3.7718634605 3.9934346676 4.1099691391 275 1305031111.3115470409 0.0473823547 0.0443785140 0.0843561143 0.0179887942 0.3744160000 0.0770220000 0.0530090000 0.0307840000 0.2113080000 0.0017830000 115253587 0 402718720 3.7849497795 3.9946784973 4.1089682579 276 1305031111.3433969021 0.0404765792 0.0443643766 0.0843561143 0.0181342138 0.3764030000 0.0745110000 0.0887200000 0.0000010000 0.2109340000 0.0017320000 115257259 0 402718720 3.7894837856 4.0015349388 4.1070003510 277 1305031111.3791339397 0.0446392000 0.0443653687 0.0843561143 0.0182742633 0.6292190000 0.0751920000 0.0882320000 0.0307980000 0.2101090000 0.2243150000 115261043 0 402718720 3.8025631905 3.9949879646 4.1091289520 278 1305031111.4112958908 0.0453953966 0.0443690739 0.0843561143 0.0182512132 0.4050470000 0.0966090000 0.0963380000 0.0000010000 0.2098170000 0.0017750000 115264659 0 402718720 3.8150086403 3.9919254780 4.1087164879 279 1305031111.4433860779 0.0403874926 0.0443548030 0.0843561143 0.0182426119 0.3804690000 0.0751320000 0.0623300000 0.0308080000 0.2097930000 0.0018720000 115268387 0 402718720 3.8229146004 3.9968690872 4.1073861122 280 1305031111.4792590141 0.0394656397 0.0443373417 0.0843561143 0.0186976540 0.3802970000 0.0766430000 0.0895320000 0.0000010000 0.2118200000 0.0017810000 115272171 0 402718720 3.8423974514 3.9953968525 4.1068887711 281 1305031111.5112640858 0.0368298031 0.0443106245 0.0843561143 0.0186958250 0.6200830000 0.0773230000 0.0896140000 0.0306300000 0.2077790000 0.2142100000 115275787 0 402718720 3.8570454121 3.9954557419 4.1045665741 282 1305031111.5432500839 0.0360028073 0.0442811641 0.0843561143 0.0186781193 0.3428650000 0.0772380000 0.0604450000 0.0000000000 0.2028780000 0.0017780000 115279515 0 402718720 3.8644835949 3.9940717220 4.1026639938 283 1305031111.5792369843 0.0352517962 0.0442492582 0.0843561143 0.0187002826 0.3701250000 0.0766570000 0.0603260000 0.0305890000 0.2002480000 0.0017740000 115283299 0 402718720 3.8785448074 3.9931218624 4.1007347107 284 1305031111.6112709045 0.0322567709 0.0442070312 0.0843561143 0.0187835030 0.3404100000 0.0764710000 0.0653340000 0.0000010000 0.1963100000 0.0017640000 115286859 0 402718720 3.8892002106 3.9962499142 4.0993742943 285 1305031111.6433949471 0.0375545919 0.0441836893 0.0843561143 0.0188091150 0.5548240000 0.0756660000 0.0533680000 0.0300000000 0.1944970000 0.2007590000 115290587 0 402718720 3.8994643688 3.9901971817 4.0995583534 286 1305031111.6793200970 0.0370849632 0.0441588685 0.0843561143 0.0190104167 0.3379360000 0.0771880000 0.0621760000 0.0000000000 0.1962880000 0.0017560000 115294315 0 402718720 3.9181487560 3.9887106419 4.0982456207 287 1305031111.7117600441 0.0295289755 0.0441078933 0.0843561143 0.0190313446 0.3658040000 0.0777810000 0.0616130000 0.0299320000 0.1941550000 0.0017790000 115298043 0 402718720 3.9327490330 3.9960370064 4.0961804390 288 1305031111.7433860302 0.0315963663 0.0440644505 0.0843561143 0.0191212580 0.3443610000 0.0771940000 0.0751730000 0.0000010000 0.1896890000 0.0017650000 115301715 0 402718720 3.9459061623 3.9929928780 4.0948867798 289 1305031111.7794229984 0.0312431157 0.0440200860 0.0843561143 0.0192101824 0.5750360000 0.0905060000 0.0758840000 0.0301770000 0.1858890000 0.1920310000 115305499 0 402718720 3.9610736370 3.9945504665 4.0932106972 290 1305031111.8114058971 0.0309974663 0.0439751804 0.0843561143 0.0192326953 0.3517880000 0.0778600000 0.0906410000 0.0000000000 0.1810160000 0.0017290000 115309115 0 402718720 3.9711933136 3.9972043037 4.0914487839 291 1305031111.8432989120 0.0350823812 0.0439446210 0.0843561143 0.0192113101 0.3420040000 0.0768150000 0.0525470000 0.0300460000 0.1803290000 0.0017320000 115312787 0 402718720 3.9799134731 3.9963393211 4.0900349617 292 1305031111.8794419765 0.0369211696 0.0439205681 0.0843561143 0.0192126409 0.3275070000 0.0776300000 0.0678230000 0.0000010000 0.1797770000 0.0017330000 115316515 0 402718720 3.9915602207 4.0003929138 4.0898785591 293 1305031111.9113540649 0.0385330766 0.0439021807 0.0843561143 0.0192381321 0.5760720000 0.1008810000 0.0803540000 0.0300850000 0.1788810000 0.1853200000 115320243 0 402718720 4.0034899712 3.9984619617 4.0902042389 294 1305031111.9433000088 0.0403589420 0.0438901289 0.0843561143 0.0192062330 0.3193580000 0.0767760000 0.0611460000 0.0000000000 0.1791500000 0.0017350000 115323915 0 402718720 4.0166935921 3.9948792458 4.0906043053 295 1305031111.9794490337 0.0396816134 0.0438758627 0.0843561143 0.0193524366 0.3382470000 0.0782510000 0.0466810000 0.0300830000 0.1809110000 0.0017620000 115327643 0 402718720 4.0330767632 3.9964754581 4.0908541679 296 1305031112.0114328861 0.0370296985 0.0438527338 0.0843561143 0.0193768381 0.3212440000 0.0910150000 0.0461360000 0.0000010000 0.1817750000 0.0017600000 115331371 0 402718720 4.0462541580 3.9994859695 4.0893459320 297 1305031112.0432701111 0.0419965535 0.0438464840 0.0843561143 0.0193449533 0.5322000000 0.0793290000 0.0532360000 0.0300850000 0.1813230000 0.1876630000 115335043 0 402718720 4.0535740852 3.9982314110 4.0880808830 298 1305031112.0793390274 0.0463424437 0.0438548597 0.0843561143 0.0193862076 0.3161990000 0.0792960000 0.0531300000 0.0000010000 0.1814600000 0.0017610000 115338827 0 402718720 4.0644254684 3.9996919632 4.0865554810 299 1305031112.1114230156 0.0516517200 0.0438809362 0.0843561143 0.0194532237 0.3734160000 0.0922860000 0.0681890000 0.0296590000 0.1809260000 0.0017880000 115342443 0 402718720 4.0704245567 4.0003337860 4.0853509903 300 1305031112.1443419456 0.0550344251 0.0439181145 0.0843561143 0.0194307528 0.3351020000 0.0793640000 0.0717840000 0.0000010000 0.1814990000 0.0018750000 115346115 0 402718720 4.0793800354 4.0007500648 4.0850095749 301 1305031112.1793899536 0.0607215129 0.0439739397 0.0843561143 0.0195112544 0.5701870000 0.0805770000 0.0884370000 0.0302910000 0.1820090000 0.1883020000 115349787 0 402718720 4.0901017189 4.0027999878 4.0845170021 302 1305031112.2112538815 0.0663700849 0.0440480992 0.0843561143 0.0195030042 0.3171560000 0.0802340000 0.0534200000 0.0000010000 0.1811650000 0.0017660000 115353459 0 402718720 4.0984992981 3.9994509220 4.0841565132 303 1305031112.2433691025 0.0708225965 0.0441364638 0.0843561143 0.0195270920 0.3469100000 0.0787140000 0.0529970000 0.0301070000 0.1827940000 0.0017410000 115357187 0 402718720 4.1094512939 3.9927930832 4.0823383331 304 1305031112.2793529034 0.0764449164 0.0442427416 0.0843561143 0.0195145589 0.3269910000 0.0797120000 0.0559530000 0.0000010000 0.1889910000 0.0017610000 115360915 0 402718720 4.1203026772 3.9936800003 4.0811691284 305 1305031112.3113119602 0.0782505497 0.0443542427 0.0843561143 0.0195069913 0.5724580000 0.0790110000 0.0598290000 0.0302930000 0.1977380000 0.2050170000 115364643 0 402718720 4.1309332848 3.9929411411 4.0801463127 306 1305031112.3433229923 0.0780273601 0.0444642855 0.0843561143 0.0194848741 0.3756840000 0.0787560000 0.0869000000 0.0000000000 0.2076930000 0.0017640000 115368315 0 402718720 4.1437845230 3.9921169281 4.0786089897 307 1305031112.3793599606 0.0805066228 0.0445816873 0.0843561143 0.0194602228 0.3973620000 0.0972840000 0.0557230000 0.0298720000 0.2120050000 0.0018700000 115372155 0 402718720 4.1558246613 3.9956769943 4.0777482986 308 1305031112.4114420414 0.0783671886 0.0446913805 0.0843561143 0.0194395394 0.3889170000 0.0769190000 0.0947340000 0.0000010000 0.2148270000 0.0018460000 115375771 0 402718720 4.1690273285 3.9975385666 4.0771584511 309 1305031112.4433910847 0.0765870288 0.0447946026 0.0843561143 0.0194252970 0.6195880000 0.0906680000 0.0557620000 0.0303360000 0.2171200000 0.2251110000 115379499 0 402718720 4.1818814278 3.9973814487 4.0764274597 310 1305031112.4794180393 0.0775782689 0.0449003564 0.0843561143 0.0194065645 0.3967220000 0.0779900000 0.0969620000 0.0000000000 0.2194120000 0.0017850000 115383283 0 402718720 4.1947588921 3.9962878227 4.0753545761 311 1305031112.5115039349 0.0746352002 0.0449959668 0.0843561143 0.0193921654 0.3848980000 0.0773690000 0.0538630000 0.0301220000 0.2212240000 0.0017380000 115386899 0 402718720 4.2070727348 3.9981932640 4.0741748810 312 1305031112.5432119370 0.0732262731 0.0450864486 0.0843561143 0.0193727278 0.3570120000 0.0752020000 0.0590540000 0.0000000000 0.2204580000 0.0017170000 115390571 0 402718720 4.2179446220 3.9972567558 4.0735263824 313 1305031112.5792520046 0.0746044070 0.0451807551 0.0843561143 0.0193437199 0.6003640000 0.0765000000 0.0446380000 0.0302420000 0.2204820000 0.2279280000 115394299 0 402718720 4.2276015282 3.9982960224 4.0732450485 314 1305031112.6112608910 0.0724844709 0.0452677097 0.0843561143 0.0193860606 0.3667000000 0.0920700000 0.0521290000 0.0000010000 0.2201550000 0.0017620000 115397971 0 402718720 4.2381277084 3.9999136925 4.0729856491 315 1305031112.6432459354 0.0716236457 0.0453513793 0.0843561143 0.0194109807 0.3882340000 0.0781480000 0.0531930000 0.0301460000 0.2243840000 0.0017830000 115401699 0 402718720 4.2459554672 4.0034093857 4.0732817650 316 1305031112.6799519062 0.0752258673 0.0454459188 0.0843561143 0.0194041609 0.3744960000 0.0787010000 0.0609400000 0.0000000000 0.2324830000 0.0017830000 115405483 0 402718720 4.2499647141 4.0029563904 4.0738053322 317 1305031112.7112510204 0.0763755739 0.0455434887 0.0843561143 0.0194032782 0.6541960000 0.0898960000 0.0527940000 0.0301910000 0.2353570000 0.2453680000 115409099 0 402718720 4.2529144287 4.0035386086 4.0747628212 318 1305031112.7432448864 0.0762917995 0.0456401815 0.0843561143 0.0194000721 0.3699460000 0.0788560000 0.0528020000 0.0000000000 0.2359170000 0.0017790000 115412827 0 402718720 4.2551212311 4.0078043938 4.0763635635 319 1305031112.7793099880 0.0754704550 0.0457336933 0.0843561143 0.0194024266 0.3945180000 0.0784240000 0.0507670000 0.0300030000 0.2329310000 0.0017970000 115416611 0 402718720 4.2555909157 4.0124435425 4.0786705017 320 1305031112.8113100529 0.0744487047 0.0458234277 0.0843561143 0.0194179969 0.3852970000 0.1009510000 0.0525970000 0.0000000000 0.2293770000 0.0017710000 115420227 0 402718720 4.2561397552 4.0073614120 4.0795855522 321 1305031112.8432860374 0.0722057670 0.0459056157 0.0843561143 0.0194319096 0.6655320000 0.0791360000 0.0894480000 0.0301610000 0.2272520000 0.2389450000 115423899 0 402718720 4.2552008629 4.0085453987 4.0811958313 322 1305031112.8794209957 0.0671459362 0.0459715794 0.0843561143 0.0194390812 0.3938070000 0.0794130000 0.0896740000 0.0000010000 0.2223560000 0.0017660000 115427683 0 402718720 4.2553033829 4.0114316940 4.0825524330 323 1305031112.9114110470 0.0636631027 0.0460263520 0.0843561143 0.0194113256 0.3737780000 0.0794480000 0.0454630000 0.0301140000 0.2163870000 0.0017680000 115431411 0 402718720 4.2544956207 4.0107455254 4.0835256577 324 1305031112.9433209896 0.0608730279 0.0460721750 0.0843561143 0.0193846779 0.3618290000 0.1027350000 0.0455550000 0.0000000000 0.2111710000 0.0017570000 115435083 0 402718720 4.2517209053 4.0091810226 4.0840353966 325 1305031112.9792780876 0.0569248646 0.0461055679 0.0843561143 0.0194050510 0.5822140000 0.0790300000 0.0632770000 0.0301600000 0.2005920000 0.2085520000 115438867 0 402718720 4.2477850914 4.0065441132 4.0841040611 326 1305031113.0113530159 0.0540447496 0.0461299212 0.0843561143 0.0193809063 0.3147860000 0.0784800000 0.0451130000 0.0000010000 0.1888160000 0.0017650000 115442483 0 402718720 4.2432503700 4.0059351921 4.0838685036 327 1305031113.0432310104 0.0515431128 0.0461464753 0.0843561143 0.0193596780 0.3489780000 0.0788770000 0.0523790000 0.0301320000 0.1852190000 0.0017650000 115446211 0 402718720 4.2360415459 4.0062141418 4.0838794708 328 1305031113.0792510509 0.0493468232 0.0461562325 0.0843561143 0.0193713694 0.3091130000 0.0786220000 0.0448820000 0.0000000000 0.1832580000 0.0017470000 115449995 0 402718720 4.2272167206 4.0002670288 4.0827074051 329 1305031113.1113159657 0.0489289090 0.0461646601 0.0843561143 0.0193641519 0.5524310000 0.0987330000 0.0510890000 0.0296550000 0.1829910000 0.1893460000 115453611 0 402718720 4.2192063332 3.9959685802 4.0807471275 330 1305031113.1433060169 0.0457066745 0.0461632723 0.0843561143 0.0193460058 0.3595850000 0.0793900000 0.0949610000 0.0000000000 0.1827310000 0.0018660000 115457339 0 402718720 4.2088327408 3.9993612766 4.0799460411 331 1305031113.1793429852 0.0412305705 0.0461483698 0.0843561143 0.0193599700 0.3607680000 0.0777670000 0.0697260000 0.0300130000 0.1808140000 0.0018020000 115461123 0 402718720 4.1979393959 3.9978818893 4.0792379379 332 1305031113.2112588882 0.0435142964 0.0461404359 0.0843561143 0.0193476831 0.3318400000 0.0794080000 0.0679540000 0.0000000000 0.1821030000 0.0017480000 115464739 0 402718720 4.1869297028 3.9912791252 4.0775218010 333 1305031113.2432270050 0.0399023518 0.0461217029 0.0843561143 0.0193452038 0.5496610000 0.0929110000 0.0560270000 0.0296840000 0.1819860000 0.1884240000 115468467 0 402718720 4.1757507324 3.9932677746 4.0770702362 334 1305031113.2793118954 0.0343038104 0.0460863200 0.0843561143 0.0193616009 0.3418300000 0.1004750000 0.0558280000 0.0000010000 0.1831400000 0.0017640000 115472195 0 402718720 4.1642079353 3.9914245605 4.0770063400 335 1305031113.3114519119 0.0371926390 0.0460597717 0.0843561143 0.0194276913 0.3517210000 0.0801470000 0.0566500000 0.0302480000 0.1821440000 0.0018700000 115475867 0 402718720 4.1524538994 3.9829146862 4.0758647919 336 1305031113.3432519436 0.0342102610 0.0460245053 0.0843561143 0.0194374076 0.3667050000 0.0801360000 0.0964310000 0.0000010000 0.1876140000 0.0018720000 115479539 0 402718720 4.1397986412 3.9833407402 4.0746660233 337 1305031113.3793120384 0.0219009891 0.0459529221 0.0843561143 0.0194680991 0.5531910000 0.0802750000 0.0536110000 0.0301880000 0.1911580000 0.1973200000 115483267 0 402718720 4.1280374527 3.9910004139 4.0763144493 338 1305031113.4116249084 0.0228058640 0.0458844397 0.0843561143 0.0194905549 0.3223100000 0.0781740000 0.0526290000 0.0000010000 0.1890860000 0.0017870000 115486995 0 402718720 4.1128282547 3.9855408669 4.0778675079 339 1305031113.4432659149 0.0220180284 0.0458140373 0.0843561143 0.0194726501 0.3738780000 0.1039850000 0.0457510000 0.0302160000 0.1914900000 0.0017950000 115490667 0 402718720 4.0979113579 3.9834389687 4.0787053108 340 1305031113.4793109894 0.0154933678 0.0457248589 0.0843561143 0.0194959549 0.3140030000 0.0789940000 0.0405070000 0.0000010000 0.1919690000 0.0018690000 115494395 0 402718720 4.0784416199 3.9873912334 4.0809884071 341 1305031113.5115230083 0.0151732834 0.0456352648 0.0843561143 0.0194730454 0.5520720000 0.0787040000 0.0555520000 0.0302760000 0.1902490000 0.1966470000 115498123 0 402718720 4.0603260994 3.9856846333 4.0831794739 342 1305031113.5432419777 0.0164380819 0.0455498929 0.0843561143 0.0194658902 0.3233950000 0.0778090000 0.0523370000 0.0000000000 0.1908490000 0.0017610000 115501795 0 402718720 4.0451145172 3.9817056656 4.0843839645 343 1305031113.5793011189 0.0157411546 0.0454629870 0.0843561143 0.0194410406 0.3546780000 0.0769240000 0.0521020000 0.0302100000 0.1930400000 0.0017600000 115505523 0 402718720 4.0280075073 3.9796676636 4.0851416588 344 1305031113.6112680435 0.0127962707 0.0453680256 0.0843561143 0.0194164684 0.3458570000 0.0928580000 0.0553480000 0.0000010000 0.1952510000 0.0017500000 115509251 0 402718720 4.0124030113 3.9820258617 4.0866494179 345 1305031113.6432220936 0.0126505950 0.0452731925 0.0843561143 0.0193931801 0.5585150000 0.0760270000 0.0544910000 0.0302480000 0.1953990000 0.2016680000 115512923 0 402718720 3.9987409115 3.9817390442 4.0875020027 346 1305031113.6792879105 0.0130971037 0.0451801980 0.0843561143 0.0193727959 0.3646220000 0.0753540000 0.0912260000 0.0000000000 0.1956580000 0.0017320000 115516763 0 402718720 3.9837582111 3.9802820683 4.0879874229 347 1305031113.7119309902 0.0134602487 0.0450887861 0.0843561143 0.0193476571 0.3927810000 0.0954500000 0.0690910000 0.0301630000 0.1955540000 0.0018370000 115520379 0 402718720 3.9697830677 3.9799807072 4.0882291794 348 1305031113.7435901165 0.0133844325 0.0449976816 0.0843561143 0.0193206593 0.3393280000 0.0868850000 0.0537800000 0.0000000000 0.1962620000 0.0017430000 115524107 0 402718720 3.9550158978 3.9801862240 4.0886363983 349 1305031113.7793200016 0.0121799177 0.0449036479 0.0843561143 0.0193094306 0.6119400000 0.0954520000 0.0862090000 0.0301960000 0.1966440000 0.2027700000 115527835 0 402718720 3.9425892830 3.9807014465 4.0890130997 350 1305031113.8112370968 0.0134764351 0.0448138558 0.0843561143 0.0192836392 0.3362200000 0.0750290000 0.0614890000 0.0000000000 0.1971720000 0.0018330000 115531451 0 402718720 3.9274158478 3.9802994728 4.0901951790 351 1305031113.8432950974 0.0101674385 0.0447151481 0.0843561143 0.0192667767 0.3508380000 0.0736790000 0.0456490000 0.0302670000 0.1988420000 0.0017400000 115535179 0 402718720 3.9151790142 3.9840152264 4.0910224915 352 1305031113.8792810440 0.0118764220 0.0446218563 0.0843561143 0.0193056302 0.3626360000 0.0749020000 0.0865820000 0.0000000000 0.1987560000 0.0017360000 115538963 0 402718720 3.9000768661 3.9824461937 4.0923738480 353 1305031113.9112899303 0.0147979036 0.0445373692 0.0843561143 0.0192784834 0.6089120000 0.0759540000 0.0922060000 0.0303270000 0.2017410000 0.2080180000 115542635 0 402718720 3.8875291348 3.9802706242 4.0936565399 354 1305031113.9432909489 0.0118025821 0.0444448980 0.0843561143 0.0192637913 0.3463740000 0.0920320000 0.0459670000 0.0000010000 0.2058300000 0.0018400000 115546307 0 402718720 3.8767306805 3.9844861031 4.0943460464 355 1305031113.9792931080 0.0122555327 0.0443542237 0.0843561143 0.0192394641 0.3703290000 0.0747630000 0.0535960000 0.0303340000 0.2090840000 0.0018440000 115550091 0 402718720 3.8625714779 3.9857110977 4.0950641632 356 1305031114.0112569332 0.0110558327 0.0442606889 0.0843561143 0.0192277890 0.3859100000 0.0862540000 0.0824080000 0.0000010000 0.2148100000 0.0017590000 115553763 0 402718720 3.8477315903 3.9875154495 4.0959448814 357 1305031114.0433011055 0.0119490344 0.0441701801 0.0843561143 0.0192310536 0.6106180000 0.0759790000 0.0620740000 0.0303870000 0.2174280000 0.2240770000 115557435 0 402718720 3.8307838440 3.9889550209 4.0980458260 358 1305031114.0792849064 0.0140099898 0.0440859338 0.0843561143 0.0192256289 0.3749750000 0.0763650000 0.0733520000 0.0000000000 0.2227800000 0.0017930000 115561219 0 402718720 3.8166890144 3.9876053333 4.0999851227 359 1305031114.1112630367 0.0145268459 0.0440035965 0.0843561143 0.0192023451 0.4385160000 0.0896890000 0.0880760000 0.0304190000 0.2278470000 0.0018040000 115564891 0 402718720 3.8029789925 3.9902913570 4.1020283699 360 1305031114.1432840824 0.0165109113 0.0439272279 0.0843561143 0.0191786643 0.4002130000 0.0954810000 0.0697450000 0.0000010000 0.2325070000 0.0017910000 115568619 0 402718720 3.7877748013 3.9938504696 4.1050672531 361 1305031114.1793370247 0.0185721070 0.0438569921 0.0843561143 0.0191910568 0.6725760000 0.0757560000 0.0876430000 0.0305000000 0.2359250000 0.2420720000 115572403 0 402718720 3.7774739265 3.9926843643 4.1072521210 362 1305031114.2113029957 0.0198408458 0.0437906492 0.0843561143 0.0191881932 0.3843420000 0.0751620000 0.0656190000 0.0000000000 0.2410880000 0.0017980000 115576019 0 402718720 3.7650709152 3.9952187538 4.1096782684 363 1305031114.2433369160 0.0228222087 0.0437328849 0.0843561143 0.0192004054 0.4160820000 0.0751580000 0.0657230000 0.0305180000 0.2421950000 0.0017990000 115579691 0 402718720 3.7463934422 4.0012340546 4.1133594513 364 1305031114.2793900967 0.0240331665 0.0436787647 0.0843561143 0.0192468699 0.4163820000 0.1000100000 0.0703410000 0.0000000000 0.2435400000 0.0018020000 115583475 0 402718720 3.7347843647 3.9979832172 4.1168212891 365 1305031114.3114290237 0.0277326554 0.0436350768 0.0843561143 0.0192297748 0.6714920000 0.0773160000 0.0628890000 0.0305600000 0.2469050000 0.2531310000 115587147 0 402718720 3.7226245403 3.9992020130 4.1211767197 366 1305031114.3433310986 0.0306915939 0.0435997121 0.0843561143 0.0192158369 0.4198470000 0.0759740000 0.0883680000 0.0000010000 0.2530160000 0.0018040000 115590875 0 402718720 3.7141351700 4.0012044907 4.1244859695 367 1305031114.3793199062 0.0336401239 0.0435725742 0.0843561143 0.0191980581 0.4527450000 0.0771220000 0.0889900000 0.0301170000 0.2539990000 0.0018200000 115594659 0 402718720 3.7077214718 4.0012907982 4.1268849373 368 1305031114.4113969803 0.0349486694 0.0435491397 0.0843561143 0.0191800677 0.4038190000 0.0769280000 0.0671270000 0.0000000000 0.2572520000 0.0018220000 115598331 0 402718720 3.6950483322 4.0003890991 4.1294465065 369 1305031114.4433450699 0.0373842642 0.0435324327 0.0843561143 0.0191705773 0.7391460000 0.0910980000 0.0895600000 0.0306200000 0.2605450000 0.2666330000 115602003 0 402718720 3.6805930138 3.9995326996 4.1331138611 370 1305031114.4793319702 0.0404347740 0.0435240607 0.0843561143 0.0191759553 0.4182910000 0.0786430000 0.0718490000 0.0000010000 0.2652620000 0.0018350000 115605787 0 402718720 3.6716635227 3.9969043732 4.1368136406 371 1305031114.5112659931 0.0426381342 0.0435216727 0.0843561143 0.0191538752 0.4919830000 0.0932240000 0.0964350000 0.0307410000 0.2688970000 0.0019480000 115609403 0 402718720 3.6637687683 3.9949824810 4.1404299736 372 1305031114.5432360172 0.0459910370 0.0435283108 0.0843561143 0.0191392205 0.4115350000 0.0781660000 0.0561770000 0.0000010000 0.2746590000 0.0018400000 115613131 0 402718720 3.6582801342 3.9956109524 4.1447668076 373 1305031114.5792369843 0.0469257236 0.0435374192 0.0843561143 0.0191197018 0.7535180000 0.0777180000 0.0903830000 0.0307450000 0.2738130000 0.2801650000 115616915 0 402718720 3.6550526619 3.9920897484 4.1462121010 374 1305031114.6113910675 0.0480837300 0.0435495751 0.0843561143 0.0191037816 0.4349060000 0.0955370000 0.0613570000 0.0000010000 0.2754870000 0.0018240000 115620531 0 402718720 3.6489408016 3.9920616150 4.1487069130 375 1305031114.6441500187 0.0486939698 0.0435632934 0.0843561143 0.0190875261 0.4617980000 0.0788030000 0.0760970000 0.0307270000 0.2736240000 0.0018440000 115624259 0 402718720 3.6434350014 3.9935750961 4.1501493454 376 1305031114.6792509556 0.0509098433 0.0435828321 0.0843561143 0.0190806837 0.4510440000 0.0783850000 0.0964160000 0.0000010000 0.2736950000 0.0018500000 115627931 0 402718720 3.6408073902 3.9874267578 4.1520557404 377 1305031114.7113060951 0.0537641943 0.0436098384 0.0843561143 0.0190776197 0.7703610000 0.0907630000 0.0923470000 0.0307710000 0.2745200000 0.2812530000 115631547 0 402718720 3.6398148537 3.9826378822 4.1537795067 378 1305031114.7432758808 0.0554646552 0.0436412004 0.0843561143 0.0190552911 0.4493730000 0.0787720000 0.0915500000 0.0000000000 0.2765030000 0.0018380000 115635275 0 402718720 3.6395142078 3.9813787937 4.1543712616 379 1305031114.7792890072 0.0592234619 0.0436823145 0.0843561143 0.0190371662 0.4704130000 0.0892360000 0.0687870000 0.0308300000 0.2789930000 0.0018460000 115639059 0 402718720 3.6393218040 3.9782428741 4.1569166183 380 1305031114.8113029003 0.0590630658 0.0437227902 0.0843561143 0.0190243417 0.4276680000 0.0764010000 0.0673970000 0.0000010000 0.2813370000 0.0018280000 115642675 0 402718720 3.6382715702 3.9804971218 4.1569733620 381 1305031114.8432080746 0.0590746254 0.0437630837 0.0843561143 0.0190003167 0.7491940000 0.0753650000 0.0738500000 0.0306900000 0.2808940000 0.2876810000 115646403 0 402718720 3.6382570267 3.9810411930 4.1567058563 382 1305031114.8792810440 0.0577721521 0.0437997567 0.0843561143 0.0189754448 0.4706660000 0.0949770000 0.0937070000 0.0000010000 0.2794440000 0.0018180000 115650131 0 402718720 3.6395647526 3.9821774960 4.1555891037 383 1305031114.9128789902 0.0572085306 0.0438347665 0.0843561143 0.0189542060 0.4749930000 0.0770420000 0.0870250000 0.0308790000 0.2775020000 0.0018270000 115653915 0 402718720 3.6434783936 3.9844737053 4.1549544334 384 1305031114.9432640076 0.0573254228 0.0438698984 0.0843561143 0.0189309819 0.4713320000 0.0990440000 0.0948180000 0.0000010000 0.2748040000 0.0019140000 115657475 0 402718720 3.6469776630 3.9872756004 4.1561651230 385 1305031114.9792799950 0.0548047721 0.0438983007 0.0843561143 0.0189108014 0.7528560000 0.0787030000 0.0926720000 0.0308450000 0.2714650000 0.2784370000 115661259 0 402718720 3.6551516056 3.9902236462 4.1547827721 386 1305031115.0113000870 0.0508713163 0.0439163655 0.0843561143 0.0188942384 0.4237840000 0.0786330000 0.0762110000 0.0000010000 0.2663830000 0.0018260000 115664931 0 402718720 3.6595597267 3.9952430725 4.1527657509 387 1305031115.0435299873 0.0494192950 0.0439305850 0.0843561143 0.0188908202 0.4331190000 0.0792960000 0.0613540000 0.0302790000 0.2596170000 0.0018440000 115668659 0 402718720 3.6702733040 3.9965834618 4.1527190208 388 1305031115.0792379379 0.0464860722 0.0439371713 0.0843561143 0.0188685890 0.4267550000 0.0795570000 0.0917810000 0.0000010000 0.2528830000 0.0018160000 115672443 0 402718720 3.6819779873 3.9967017174 4.1520309448 389 1305031115.1112298965 0.0451116636 0.0439401905 0.0843561143 0.0188609013 0.7148730000 0.0887630000 0.0929090000 0.0307330000 0.2488190000 0.2529110000 115676059 0 402718720 3.6931593418 3.9980714321 4.1527905464 390 1305031115.1432940960 0.0413136706 0.0439334559 0.0843561143 0.0188544331 0.3835100000 0.0806530000 0.0622160000 0.0000000000 0.2380760000 0.0018260000 115679787 0 402718720 3.7107183933 3.9999387264 4.1509323120 391 1305031115.1794400215 0.0379397050 0.0439181266 0.0843561143 0.0188587249 0.4404720000 0.0793070000 0.0976740000 0.0306620000 0.2302770000 0.0018150000 115683571 0 402718720 3.7191326618 3.9997210503 4.1517524719 392 1305031115.2113740444 0.0375274308 0.0439018238 0.0843561143 0.0188651243 0.3796940000 0.0893730000 0.0613490000 0.0000000000 0.2264290000 0.0017950000 115687187 0 402718720 3.7322068214 3.9975676537 4.1533651352 393 1305031115.2432971001 0.0382584482 0.0438874640 0.0843561143 0.0188611114 0.6533380000 0.0907090000 0.0781990000 0.0305610000 0.2234630000 0.2296600000 115690915 0 402718720 3.7494571209 3.9933393002 4.1551790237 394 1305031115.2799661160 0.0349957645 0.0438648963 0.0843561143 0.0188888313 0.3929080000 0.0964460000 0.0729890000 0.0000010000 0.2208000000 0.0018900000 115694643 0 402718720 3.7593166828 3.9963223934 4.1575412750 395 1305031115.3117039204 0.0324774310 0.0438360673 0.0843561143 0.0189102396 0.3938210000 0.0776980000 0.0654060000 0.0304820000 0.2176910000 0.0017930000 115698371 0 402718720 3.7755572796 3.9982855320 4.1590981483 396 1305031115.3434259892 0.0319632925 0.0438060855 0.0843561143 0.0188953502 0.3889380000 0.0764250000 0.0964900000 0.0000000000 0.2133880000 0.0018510000 115702043 0 402718720 3.7923202515 3.9960212708 4.1596965790 397 1305031115.3791658878 0.0303756464 0.0437722557 0.0843561143 0.0191597040 0.5884620000 0.0772880000 0.0561330000 0.0303160000 0.2087160000 0.2152510000 115705715 0 402718720 3.7991716862 4.0045995712 4.1620278358 398 1305031115.4112370014 0.0338797644 0.0437474002 0.0843561143 0.0191465250 0.3340550000 0.0759040000 0.0523280000 0.0000010000 0.2032990000 0.0017610000 115709387 0 402718720 3.8105051517 4.0032954216 4.1649103165 399 1305031115.4431591034 0.0347170755 0.0437247678 0.0843561143 0.0191832237 0.3734540000 0.0873100000 0.0525930000 0.0303010000 0.2007010000 0.0017840000 115713059 0 402718720 3.8316471577 4.0001873970 4.1685519218 400 1305031115.4792408943 0.0362008996 0.0437059581 0.0843561143 0.0191652342 0.3476610000 0.0765970000 0.0720590000 0.0000000000 0.1964680000 0.0017710000 115716843 0 402718720 3.8500761986 4.0013732910 4.1709399223 401 1305031115.5112531185 0.0390977003 0.0436944662 0.0843561143 0.0192317735 0.5602500000 0.0765700000 0.0645330000 0.0302110000 0.1909020000 0.1972340000 115720459 0 402718720 3.8666274548 3.9991841316 4.1728692055 402 1305031115.5436201096 0.0383816473 0.0436812502 0.0843561143 0.0192715308 0.3108250000 0.0772930000 0.0459200000 0.0000010000 0.1850830000 0.0017540000 115724187 0 402718720 3.8897919655 3.9974384308 4.1730179787 403 1305031115.5793149471 0.0400408655 0.0436722170 0.0843561143 0.0192484940 0.3545900000 0.0907430000 0.0538080000 0.0295520000 0.1779360000 0.0017730000 115727971 0 402718720 3.9063088894 3.9975931644 4.1716527939 404 1305031115.6114239693 0.0423435643 0.0436689283 0.0843561143 0.0192287518 0.3372870000 0.1038490000 0.0580400000 0.0000010000 0.1727510000 0.0018490000 115731587 0 402718720 3.9198071957 3.9965405464 4.1705265045 405 1305031115.6432540417 0.0419174656 0.0436646037 0.0843561143 0.0192070935 0.5447650000 0.0785010000 0.0900010000 0.0299430000 0.1696290000 0.1759260000 115735259 0 402718720 3.9368696213 3.9959537983 4.1690263748 406 1305031115.6792409420 0.0458523557 0.0436699922 0.0843561143 0.0191906360 0.3055870000 0.0779590000 0.0588770000 0.0000010000 0.1661260000 0.0018260000 115739043 0 402718720 3.9526023865 3.9947783947 4.1674895287 407 1305031115.7113199234 0.0462944955 0.0436764406 0.0843561143 0.0192111091 0.3308090000 0.0779970000 0.0557420000 0.0293900000 0.1651580000 0.0017550000 115742715 0 402718720 3.9674813747 3.9950652122 4.1660361290 408 1305031115.7432498932 0.0420541577 0.0436724644 0.0843561143 0.0192499029 0.3220730000 0.0786420000 0.0773360000 0.0000010000 0.1635840000 0.0017420000 115746443 0 402718720 3.9873437881 3.9971857071 4.1640839577 409 1305031115.7794249058 0.0429836586 0.0436707803 0.0843561143 0.0192560270 0.5077350000 0.0896150000 0.0571820000 0.0299240000 0.1619510000 0.1682560000 115750227 0 402718720 4.0084676743 3.9960796833 4.1615929604 410 1305031115.8112769127 0.0433246344 0.0436699361 0.0843561143 0.0192515420 0.3154970000 0.0766400000 0.0739300000 0.0000010000 0.1624260000 0.0017290000 115753843 0 402718720 4.0207858086 3.9979691505 4.1597805023 411 1305031115.8432240486 0.0403377637 0.0436618286 0.0843561143 0.0192396367 0.3303960000 0.0787260000 0.0579550000 0.0299260000 0.1611320000 0.0018460000 115757571 0 402718720 4.0370903015 4.0014190674 4.1581945419 412 1305031115.8791980743 0.0479016788 0.0436721195 0.0843561143 0.0192298192 0.3257960000 0.0791960000 0.0832500000 0.0000000000 0.1608170000 0.0017480000 115761243 0 402718720 4.0491890907 3.9981777668 4.1574134827 413 1305031115.9111180305 0.0493553393 0.0436858803 0.0843561143 0.0192151880 0.4830830000 0.0793380000 0.0470020000 0.0294660000 0.1600630000 0.1664240000 115764915 0 402718720 4.0621209145 3.9983232021 4.1565642357 414 1305031115.9433109760 0.0466447473 0.0436930273 0.0843561143 0.0192121318 0.3042280000 0.0869600000 0.0550730000 0.0000010000 0.1596470000 0.0017630000 115768531 0 402718720 4.0762157440 4.0029411316 4.1565256119 415 1305031115.9807400703 0.0528025404 0.0437149780 0.0843561143 0.0192032881 0.3154480000 0.0802510000 0.0473480000 0.0294100000 0.1558780000 0.0017700000 115772315 0 402718720 4.0852923393 4.0047464371 4.1574993134 416 1305031116.0113790035 0.0529690981 0.0437372234 0.0843561143 0.0192449784 0.2863660000 0.0810830000 0.0473030000 0.0000010000 0.1554350000 0.0017670000 115775931 0 402718720 4.0967230797 4.0078721046 4.1578884125 417 1305031116.0431640148 0.0554613248 0.0437653388 0.0843561143 0.0192291827 0.4897360000 0.0819880000 0.0657950000 0.0300080000 0.1521060000 0.1590100000 115779659 0 402718720 4.1048936844 4.0110983849 4.1587877274 418 1305031116.0800299644 0.0630822554 0.0438115515 0.0843561143 0.0192311883 0.2925350000 0.0814190000 0.0550230000 0.0000000000 0.1535480000 0.0017600000 115783443 0 402718720 4.1127204895 4.0125985146 4.1609625816 419 1305031116.1112999916 0.0646167472 0.0438612059 0.0843561143 0.0192146604 0.3392770000 0.0953810000 0.0626120000 0.0300350000 0.1486630000 0.0017880000 115787059 0 402718720 4.1222147942 4.0150403976 4.1633434296 420 1305031116.1434469223 0.0675029755 0.0439174959 0.0843561143 0.0191947512 0.3029720000 0.0799600000 0.0691890000 0.0000010000 0.1513160000 0.0017140000 115790731 0 402718720 4.1319837570 4.0143656731 4.1653041840 421 1305031116.1795721054 0.0729992464 0.0439865736 0.0843561143 0.0191751595 0.5251560000 0.1070630000 0.0815590000 0.0300110000 0.1484410000 0.1572860000 115794515 0 402718720 4.1417741776 4.0139904022 4.1670498848 422 1305031116.2113199234 0.0733248964 0.0440560957 0.0843561143 0.0191553536 0.3068290000 0.0807490000 0.0738280000 0.0000000000 0.1495690000 0.0018540000 115798187 0 402718720 4.1514191628 4.0165052414 4.1689877510 423 1305031116.2433199883 0.0747144893 0.0441285742 0.0843561143 0.0191410066 0.3538230000 0.0808630000 0.0986040000 0.0301140000 0.1416820000 0.0017620000 115801859 0 402718720 4.1614465714 4.0159287453 4.1700396538 424 1305031116.2793850899 0.0790416077 0.0442109163 0.0843561143 0.0191540290 0.2945860000 0.0812260000 0.0665220000 0.0000000000 0.1442930000 0.0017450000 115805699 0 402718720 4.1698584557 4.0164990425 4.1696109772 425 1305031116.3113360405 0.0792772248 0.0442934252 0.0843561143 0.0191523944 0.4880990000 0.0928300000 0.0550340000 0.0301400000 0.1494530000 0.1598450000 115809315 0 402718720 4.1781859398 4.0173435211 4.1696782112 426 1305031116.3432919979 0.0793654993 0.0443757540 0.0843561143 0.0191381551 0.3170920000 0.0794230000 0.0691550000 0.0000000000 0.1659920000 0.0017200000 115812987 0 402718720 4.1863298416 4.0162382126 4.1682677269 427 1305031116.3793840408 0.0815987512 0.0444629273 0.0843561143 0.0191276574 0.3371630000 0.0810320000 0.0545910000 0.0301580000 0.1688050000 0.0017590000 115816715 0 402718720 4.1919732094 4.0143141747 4.1652975082 428 1305031116.4113330841 0.0790861025 0.0445438226 0.0843561143 0.0191091765 0.3473360000 0.0813910000 0.0930880000 0.0000000000 0.1702920000 0.0017610000 115820443 0 402718720 4.1973381042 4.0169572830 4.1627321243 429 1305031116.4433689117 0.0749503002 0.0446147002 0.0843561143 0.0190973916 0.5459230000 0.0941790000 0.0636840000 0.0301770000 0.1711650000 0.1859100000 115824171 0 402718720 4.2029089928 4.0188665390 4.1613907814 430 1305031116.4798500538 0.0721920580 0.0446788336 0.0843561143 0.0190791032 0.3337490000 0.0808610000 0.0756820000 0.0000010000 0.1745100000 0.0018480000 115827955 0 402718720 4.2055249214 4.0174665451 4.1593866348 431 1305031116.5112049580 0.0712158456 0.0447404044 0.0843561143 0.0190628975 0.3698160000 0.0918740000 0.0727540000 0.0302150000 0.1722740000 0.0018410000 115831571 0 402718720 4.2028217316 4.0172681808 4.1569066048 432 1305031116.5432620049 0.0696312189 0.0447980220 0.0843561143 0.0190411444 0.3477150000 0.0808490000 0.0937820000 0.0000010000 0.1705160000 0.0017490000 115835243 0 402718720 4.1987104416 4.0167355537 4.1548414230 433 1305031116.5793130398 0.0639744699 0.0448423094 0.0843561143 0.0190521319 0.5209610000 0.0807500000 0.0552830000 0.0297040000 0.1699690000 0.1844400000 115839027 0 402718720 4.1932053566 4.0177035332 4.1535062790 434 1305031116.6112608910 0.0608310588 0.0448791498 0.0843561143 0.0190497575 0.3382520000 0.0963840000 0.0733230000 0.0000000000 0.1659740000 0.0017520000 115842643 0 402718720 4.1867208481 4.0166516304 4.1519317627 435 1305031116.6433548927 0.0595885739 0.0449129646 0.0843561143 0.0190454740 0.3437790000 0.0815190000 0.0740220000 0.0302170000 0.1553170000 0.0018490000 115846315 0 402718720 4.1766514778 4.0153021812 4.1507539749 436 1305031116.6792809963 0.0536410585 0.0449329832 0.0843561143 0.0190357837 0.3046680000 0.1005530000 0.0579500000 0.0000010000 0.1434570000 0.0018540000 115850211 0 402718720 4.1663084030 4.0147509575 4.1501960754 437 1305031116.7116339207 0.0530517660 0.0449515616 0.0843561143 0.0190169621 0.4937160000 0.0810590000 0.0953650000 0.0301690000 0.1395720000 0.1467280000 115853827 0 402718720 4.1535201073 4.0129790306 4.1494150162 438 1305031116.7432909012 0.0526521467 0.0449691429 0.0843561143 0.0190113240 0.2891110000 0.0807800000 0.0658440000 0.0000010000 0.1397960000 0.0018330000 115857499 0 402718720 4.1390199661 4.0121245384 4.1492595673 439 1305031116.7792980671 0.0495279357 0.0449795274 0.0843561143 0.0190094348 0.3141210000 0.0943680000 0.0468570000 0.0302550000 0.1400560000 0.0017560000 115861283 0 402718720 4.1242556572 4.0106620789 4.1488709450 440 1305031116.8113429546 0.0505191758 0.0449921175 0.0843561143 0.0190495969 0.3088730000 0.0809050000 0.0840000000 0.0000010000 0.1413730000 0.0017700000 115864955 0 402718720 4.1095733643 4.0079054832 4.1476178169 441 1305031116.8460888863 0.0484447069 0.0449999465 0.0843561143 0.0191491596 0.4753870000 0.0815990000 0.0731000000 0.0296620000 0.1416910000 0.1484720000 115868683 0 402718720 4.0942726135 4.0057673454 4.1464915276 442 1305031116.8801651001 0.0459067933 0.0450019982 0.0843561143 0.0191278398 0.2815690000 0.0817350000 0.0537180000 0.0000010000 0.1435250000 0.0017600000 115872411 0 402718720 4.0797643661 4.0074782372 4.1458477974 443 1305031116.9120440483 0.0468735248 0.0450062228 0.0843561143 0.0191190573 0.3183100000 0.0813700000 0.0608080000 0.0300990000 0.1434390000 0.0017590000 115876083 0 402718720 4.0651903152 4.0055913925 4.1458373070 444 1305031116.9432959557 0.0436234400 0.0450031084 0.0843561143 0.0191111140 0.3248730000 0.0898910000 0.0872330000 0.0000010000 0.1450170000 0.0018530000 115879755 0 402718720 4.0515003204 4.0078425407 4.1454415321 445 1305031116.9793510437 0.0422326624 0.0449968827 0.0843561143 0.0191160012 0.4789970000 0.0805930000 0.0678180000 0.0299880000 0.1466680000 0.1530870000 115883483 0 402718720 4.0345306396 4.0087571144 4.1455783844 446 1305031117.0113821030 0.0420063995 0.0449901776 0.0843561143 0.0191133781 0.2828930000 0.0801360000 0.0529520000 0.0000000000 0.1472060000 0.0017550000 115887211 0 402718720 4.0186395645 4.0101013184 4.1448631287 447 1305031117.0432610512 0.0414070152 0.0449821616 0.0843561143 0.0190939897 0.3117080000 0.0792410000 0.0525540000 0.0294540000 0.1478490000 0.0017620000 115890883 0 402718720 4.0001254082 4.0135617256 4.1451978683 448 1305031117.0795199871 0.0401987694 0.0449714844 0.0843561143 0.0190896146 0.3172410000 0.0777320000 0.0884110000 0.0000010000 0.1485050000 0.0017530000 115894667 0 402718720 3.9859189987 4.0165762901 4.1457414627 449 1305031117.1112380028 0.0426575579 0.0449663309 0.0843561143 0.0190861965 0.4963690000 0.0887580000 0.0742120000 0.0298870000 0.1482740000 0.1543860000 115898283 0 402718720 3.9745724201 4.0165491104 4.1471533775 450 1305031117.1432180405 0.0444185324 0.0449651135 0.0843561143 0.0190688634 0.3214270000 0.0790580000 0.0896300000 0.0000000000 0.1501650000 0.0017400000 115902011 0 402718720 3.9628849030 4.0178003311 4.1491494179 451 1305031117.1792640686 0.0430216044 0.0449608042 0.0843561143 0.0190503917 0.3250330000 0.0785620000 0.0596290000 0.0298930000 0.1543510000 0.0017490000 115905795 0 402718720 3.9546260834 4.0211768150 4.1501488686 452 1305031117.2113609314 0.0450052097 0.0449609024 0.0843561143 0.0190520687 0.3126490000 0.0786290000 0.0708900000 0.0000010000 0.1604030000 0.0018400000 115909467 0 402718720 3.9458923340 4.0208959579 4.1518950462 453 1305031117.2432770729 0.0435198508 0.0449577213 0.0843561143 0.0190495111 0.5274230000 0.0779270000 0.0934750000 0.0300490000 0.1592350000 0.1658770000 115913139 0 402718720 3.9435541630 4.0233821869 4.1536107063 454 1305031117.2792990208 0.0429969504 0.0449534024 0.0843561143 0.0190346870 0.3594880000 0.1007000000 0.0929100000 0.0000010000 0.1631500000 0.0018400000 115916923 0 402718720 3.9391250610 4.0243439674 4.1552367210 455 1305031117.3111999035 0.0460421331 0.0449557952 0.0843561143 0.0190234966 0.3424360000 0.0896030000 0.0619760000 0.0301350000 0.1581180000 0.0017420000 115920539 0 402718720 3.9350347519 4.0211272240 4.1570329666 456 1305031117.3432428837 0.0498420969 0.0449665108 0.0843561143 0.0190132726 0.3059450000 0.0760690000 0.0649100000 0.0000010000 0.1623880000 0.0017160000 115924267 0 402718720 3.9301142693 4.0166416168 4.1580982208 457 1305031117.3794538975 0.0503938124 0.0449783867 0.0843561143 0.0190033634 0.4990600000 0.0771130000 0.0693260000 0.0301170000 0.1573640000 0.1642420000 115928051 0 402718720 3.9285671711 4.0129337311 4.1580557823 458 1305031117.4112210274 0.0506233014 0.0449907119 0.0843561143 0.0189837024 0.3126260000 0.0768610000 0.0772520000 0.0000000000 0.1559290000 0.0017220000 115931723 0 402718720 3.9270210266 4.0092244148 4.1574072838 459 1305031117.4432740211 0.0495867059 0.0450007249 0.0843561143 0.0189647637 0.3326020000 0.0771920000 0.0672980000 0.0301630000 0.1553440000 0.0017540000 115935395 0 402718720 3.9275581837 4.0055031776 4.1565065384 460 1305031117.4794030190 0.0454119295 0.0450016189 0.0843561143 0.0189492952 0.2983030000 0.0770150000 0.0625050000 0.0000000000 0.1560590000 0.0018260000 115939179 0 402718720 3.9285278320 4.0024604797 4.1554136276 461 1305031117.5113248825 0.0454007015 0.0450024846 0.0843561143 0.0189310396 0.5068860000 0.0772080000 0.0749040000 0.0302170000 0.1587500000 0.1649270000 115942851 0 402718720 3.9280290604 3.9960541725 4.1546602249 462 1305031117.5442850590 0.0429418460 0.0449980243 0.0843561143 0.0189132306 0.3321070000 0.0773610000 0.0900910000 0.0000010000 0.1620520000 0.0017380000 115946467 0 402718720 3.9272925854 3.9919126034 4.1536083221 463 1305031117.5791549683 0.0367566161 0.0449802243 0.0843561143 0.0188944167 0.3462460000 0.0878280000 0.0598270000 0.0301580000 0.1658260000 0.0017480000 115950307 0 402718720 3.9272322655 3.9889335632 4.1532101631 464 1305031117.6111590862 0.0347299874 0.0449581333 0.0843561143 0.0188753380 0.3045110000 0.0855930000 0.0472290000 0.0000010000 0.1690660000 0.0017550000 115953923 0 402718720 3.9263298512 3.9841744900 4.1544904709 465 1305031117.6432840824 0.0346885882 0.0449360482 0.0843561143 0.0188572600 0.5319000000 0.0767090000 0.0745110000 0.0301740000 0.1717250000 0.1778990000 115957651 0 402718720 3.9264023304 3.9769971371 4.1565966606 466 1305031117.6792619228 0.0307766814 0.0449056633 0.0843561143 0.0188427706 0.3006220000 0.0759310000 0.0472710000 0.0000010000 0.1746660000 0.0018380000 115961435 0 402718720 3.9254469872 3.9717390537 4.1592445374 467 1305031117.7112150192 0.0310475472 0.0448759885 0.0843561143 0.0188242076 0.3373460000 0.0755380000 0.0518060000 0.0301450000 0.1772220000 0.0017530000 115965051 0 402718720 3.9265251160 3.9639647007 4.1628856659 468 1305031117.7431840897 0.0321109630 0.0448487128 0.0843561143 0.0188065414 0.3026720000 0.0756280000 0.0449110000 0.0000000000 0.1795070000 0.0017420000 115968723 0 402718720 3.9270863533 3.9549479485 4.1668405533 469 1305031117.7794671059 0.0296639707 0.0448163360 0.0843561143 0.0187866653 0.5817590000 0.0922510000 0.0881230000 0.0296850000 0.1823070000 0.1885100000 115972507 0 402718720 3.9259493351 3.9477994442 4.1704764366 470 1305031117.8113200665 0.0284128524 0.0447814350 0.0843561143 0.0187702829 0.3530950000 0.0746050000 0.0918820000 0.0000000000 0.1838480000 0.0018400000 115976179 0 402718720 3.9277966022 3.9402589798 4.1743884087 471 1305031117.8433070183 0.0303664412 0.0447508299 0.0843561143 0.0187622610 0.3584060000 0.0747380000 0.0513840000 0.0301320000 0.1987950000 0.0023680000 115979739 0 402718720 3.9296884537 3.9294805527 4.1786298752 472 1305031117.8794670105 0.0267820321 0.0447127604 0.0843561143 0.0187456789 0.3676050000 0.0898690000 0.0864530000 0.0000010000 0.1886520000 0.0017540000 115983523 0 402718720 3.9303965569 3.9231138229 4.1819262505 473 1305031117.9114069939 0.0280774962 0.0446775907 0.0843561143 0.0187269830 0.5447980000 0.0728850000 0.0569590000 0.0300880000 0.1889000000 0.1950730000 115987139 0 402718720 3.9289245605 3.9144916534 4.1860642433 474 1305031117.9432721138 0.0297202263 0.0446460351 0.0843561143 0.0187079779 0.3717430000 0.0936190000 0.0848890000 0.0000010000 0.1906430000 0.0016970000 115990811 0 402718720 3.9281082153 3.9054889679 4.1907987595 475 1305031117.9792630672 0.0286165494 0.0446122888 0.0843561143 0.0187009637 0.3758440000 0.0705750000 0.0828160000 0.0293670000 0.1904990000 0.0016980000 115994595 0 402718720 3.9258730412 3.8996431828 4.1953296661 476 1305031118.0112280846 0.0316037983 0.0445849600 0.0843561143 0.0186852174 0.3269520000 0.0717100000 0.0629130000 0.0000000000 0.1896980000 0.0017320000 115998211 0 402718720 3.9235303402 3.8894243240 4.2010011673 477 1305031118.0435490608 0.0338153578 0.0445623823 0.0843561143 0.0186694972 0.5459960000 0.0719390000 0.0561310000 0.0295430000 0.1907140000 0.1967750000 116001939 0 402718720 3.9253718853 3.8782391548 4.2064156532 478 1305031118.0793690681 0.0341859721 0.0445406743 0.0843561143 0.0186534624 0.3131450000 0.0700450000 0.0483480000 0.0000010000 0.1921630000 0.0016810000 116005723 0 402718720 3.9230699539 3.8706598282 4.2115654945 479 1305031118.1112170219 0.0354056768 0.0445216033 0.0843561143 0.0186409722 0.3924490000 0.0850280000 0.0834190000 0.0295100000 0.1918480000 0.0017400000 116009339 0 402718720 3.9241440296 3.8617908955 4.2163362503 480 1305031118.1432559490 0.0376456007 0.0445072783 0.0843561143 0.0186239526 0.3662540000 0.0845960000 0.0876320000 0.0000010000 0.1912740000 0.0018130000 116013067 0 402718720 3.9225323200 3.8523812294 4.2209329605 481 1305031118.1793229580 0.0387750305 0.0444953609 0.0843561143 0.0186065472 0.5314930000 0.0707260000 0.0417000000 0.0293790000 0.1913670000 0.1974120000 116016851 0 402718720 3.9211733341 3.8436903954 4.2254080772 482 1305031118.2112019062 0.0417837426 0.0444897352 0.0843561143 0.0185980897 0.3506200000 0.0708380000 0.0821910000 0.0000010000 0.1949600000 0.0017080000 116020467 0 402718720 3.9210126400 3.8320095539 4.2297439575 483 1305031118.2431728840 0.0440870784 0.0444889015 0.0843561143 0.0185904499 0.3860610000 0.0687940000 0.0855570000 0.0297050000 0.1993790000 0.0017150000 116024139 0 402718720 3.9177618027 3.8231520653 4.2337841988 484 1305031118.2791941166 0.0448899716 0.0444897302 0.0843561143 0.0185925914 0.3622100000 0.0976030000 0.0549070000 0.0000000000 0.2070730000 0.0017070000 116027923 0 402718720 3.9170045853 3.8152496815 4.2371268272 485 1305031118.3112990856 0.0473541357 0.0444956362 0.0843561143 0.0185738280 0.6145340000 0.0698010000 0.0812750000 0.0297880000 0.2133920000 0.2193540000 116031595 0 402718720 3.9154736996 3.8062694073 4.2408967018 486 1305031118.3433239460 0.0467492677 0.0445002733 0.0843561143 0.0185664125 0.3743790000 0.0703460000 0.0811890000 0.0000010000 0.2201870000 0.0017420000 116035267 0 402718720 3.9145452976 3.8037931919 4.2436122894 487 1305031118.3792080879 0.0479015149 0.0445072573 0.0843561143 0.0185479135 0.3657850000 0.0703950000 0.0410710000 0.0298250000 0.2218250000 0.0017520000 116039051 0 402718720 3.9124398232 3.7989141941 4.2473940849 488 1305031118.4112958908 0.0501499362 0.0445188202 0.0843561143 0.0185409118 0.3536430000 0.0701980000 0.0538490000 0.0000010000 0.2269480000 0.0017270000 116042723 0 402718720 3.9090573788 3.7944014072 4.2516608238 489 1305031118.4457030296 0.0483622439 0.0445266800 0.0843561143 0.0185248001 0.6054010000 0.0689100000 0.0465690000 0.0298080000 0.2265680000 0.2326380000 116046451 0 402718720 3.9122073650 3.7938427925 4.2553520203 490 1305031118.4792850018 0.0487602726 0.0445353200 0.0843561143 0.0185059613 0.3535600000 0.0694730000 0.0537350000 0.0000010000 0.2276860000 0.0017470000 116050123 0 402718720 3.9124763012 3.7913100719 4.2582468987 491 1305031118.5112550259 0.0496717803 0.0445457812 0.0843561143 0.0184914437 0.3885720000 0.0691010000 0.0597450000 0.0298090000 0.2272460000 0.0017420000 116053795 0 402718720 3.9123930931 3.7893011570 4.2609553337 492 1305031118.5451989174 0.0471340828 0.0445510420 0.0843561143 0.0184881030 0.3576190000 0.0692590000 0.0600670000 0.0000010000 0.2256240000 0.0017350000 116057523 0 402718720 3.9140028954 3.7940223217 4.2627506256 493 1305031118.5792849064 0.0471939072 0.0445564027 0.0843561143 0.0184703434 0.6468810000 0.0882160000 0.0771610000 0.0298300000 0.2223320000 0.2284000000 116061307 0 402718720 3.9151377678 3.7955446243 4.2639312744 494 1305031118.6161420345 0.0474535450 0.0445622674 0.0843561143 0.0184541525 0.3996540000 0.0935190000 0.0843710000 0.0000000000 0.2190880000 0.0017360000 116065091 0 402718720 3.9159700871 3.7983913422 4.2639741898 495 1305031118.6453309059 0.0451587401 0.0445634724 0.0843561143 0.0184395757 0.4022710000 0.0700320000 0.0842430000 0.0297680000 0.2155580000 0.0017360000 116068707 0 402718720 3.9179728031 3.8037533760 4.2628145218 496 1305031118.6792950630 0.0443555377 0.0445630532 0.0843561143 0.0184264188 0.3410500000 0.0705870000 0.0570960000 0.0000010000 0.2105730000 0.0018170000 116072491 0 402718720 3.9190926552 3.8098878860 4.2614383698 497 1305031118.7114210129 0.0457588509 0.0445654592 0.0843561143 0.0184182907 0.5780850000 0.0703340000 0.0567390000 0.0297260000 0.2071180000 0.2132250000 116076107 0 402718720 3.9182307720 3.8140189648 4.2589020729 498 1305031118.7468008995 0.0496120192 0.0445755929 0.0843561143 0.0184170689 0.3415640000 0.0709190000 0.0612390000 0.0000000000 0.2067410000 0.0017320000 116079891 0 402718720 3.9173643589 3.8175692558 4.2560114861 499 1305031118.7792770863 0.0450118519 0.0445764671 0.0843561143 0.0184473625 0.3685540000 0.0719310000 0.0577460000 0.0297890000 0.2064010000 0.0017420000 116083619 0 402718720 3.9193212986 3.8295524120 4.2532496452 500 1305031118.8112208843 0.0425301455 0.0445723745 0.0843561143 0.0184470506 0.3504560000 0.0708710000 0.0744750000 0.0000000000 0.2024210000 0.0017340000 116087235 0 402718720 3.9219520092 3.8387439251 4.2496843338 501 1305031118.8467741013 0.0477919206 0.0445788007 0.0843561143 0.0184702016 0.5493560000 0.0701070000 0.0408100000 0.0293600000 0.2009730000 0.2071630000 116091019 0 402718720 3.9250619411 3.8413679600 4.2438640594 502 1305031118.8792080879 0.0419714972 0.0445736069 0.0843561143 0.0185236173 0.3598490000 0.0717030000 0.0830040000 0.0000000000 0.2024630000 0.0017290000 116094747 0 402718720 3.9254529476 3.8571355343 4.2375392914 503 1305031118.9111769199 0.0400707908 0.0445646550 0.0843561143 0.0185243583 0.3712460000 0.0714820000 0.0684220000 0.0298390000 0.1988140000 0.0017340000 116098363 0 402718720 3.9244956970 3.8686401844 4.2315936089 504 1305031118.9470090866 0.0432176851 0.0445619824 0.0843561143 0.0185064706 0.3320260000 0.0837790000 0.0495520000 0.0000010000 0.1960080000 0.0017360000 116102147 0 402718720 3.9257683754 3.8763368130 4.2241148949 505 1305031118.9793939590 0.0395152234 0.0445519888 0.0843561143 0.0185009897 0.5449210000 0.0728070000 0.0491230000 0.0298570000 0.1932730000 0.1989120000 116105875 0 402718720 3.9249792099 3.8897919655 4.2171235085 506 1305031119.0113630295 0.0382913053 0.0445396159 0.0843561143 0.0184892584 0.3702180000 0.0917790000 0.0883190000 0.0000000000 0.1872960000 0.0018220000 116109491 0 402718720 3.9230244160 3.9011454582 4.2109031677 507 1305031119.0471799374 0.0419023111 0.0445344141 0.0843561143 0.0184771889 0.3347640000 0.0733920000 0.0437650000 0.0299640000 0.1849400000 0.0017360000 116113275 0 402718720 3.9223144054 3.9093105793 4.2038898468 508 1305031119.0792229176 0.0421859287 0.0445297911 0.0843561143 0.0184629377 0.3116850000 0.0729870000 0.0520330000 0.0000010000 0.1838680000 0.0017910000 116116891 0 402718720 3.9211924076 3.9182076454 4.1971588135 509 1305031119.1113278866 0.0419763066 0.0445247745 0.0843561143 0.0184484209 0.5864680000 0.0926060000 0.0873390000 0.0300000000 0.1846900000 0.1908590000 116120619 0 402718720 3.9198257923 3.9274880886 4.1903271675 510 1305031119.1476290226 0.0425546505 0.0445209115 0.0843561143 0.0184363904 0.3093320000 0.0748960000 0.0462710000 0.0000000000 0.1853130000 0.0018340000 116124403 0 402718720 3.9204549789 3.9380774498 4.1837859154 511 1305031119.1792619228 0.0422568694 0.0445164809 0.0843561143 0.0184305913 0.3476130000 0.0748620000 0.0533520000 0.0301560000 0.1865270000 0.0017450000 116128075 0 402718720 3.9195952415 3.9469783306 4.1773676872 512 1305031119.2113640308 0.0422684737 0.0445120902 0.0843561143 0.0184184515 0.3555320000 0.0744190000 0.0903160000 0.0000010000 0.1880660000 0.0017490000 116131747 0 402718720 3.9202258587 3.9551069736 4.1712074280 513 1305031119.2476599216 0.0421014950 0.0445073912 0.0843561143 0.0184070499 0.5345180000 0.0746530000 0.0435250000 0.0301520000 0.1894950000 0.1957060000 116184683 0 402718720 3.9204685688 3.9666583538 4.1651468277 514 1305031119.2792439461 0.0409545489 0.0445004791 0.0843561143 0.0183923569 0.3316250000 0.0881640000 0.0510340000 0.0000010000 0.1896990000 0.0017420000 116290755 0 402718720 3.9195189476 3.9768178463 4.1599860191 515 1305031119.3112120628 0.0407933667 0.0444932808 0.0843561143 0.0183756021 0.3565030000 0.0760160000 0.0584920000 0.0302100000 0.1890440000 0.0017640000 116294427 0 402718720 3.9199888706 3.9855475426 4.1554002762 516 1305031119.3477499485 0.0447151847 0.0444937108 0.0843561143 0.0183592302 0.3208060000 0.0768470000 0.0521400000 0.0000010000 0.1890810000 0.0017630000 116298211 0 402718720 3.9211025238 3.9927265644 4.1510176659 517 1305031119.3792390823 0.0435764380 0.0444919366 0.0843561143 0.0183496792 0.5468500000 0.0772130000 0.0524680000 0.0302030000 0.1898740000 0.1961230000 116301883 0 402718720 3.9204881191 4.0030622482 4.1470227242 518 1305031119.4114921093 0.0428078882 0.0444886856 0.0843561143 0.0183395303 0.3206010000 0.0769220000 0.0518530000 0.0000010000 0.1890910000 0.0017730000 116305555 0 402718720 3.9210813046 4.0133013725 4.1431493759 519 1305031119.4477260113 0.0465663634 0.0444926888 0.0843561143 0.0183224086 0.3689650000 0.0907940000 0.0593510000 0.0297720000 0.1862850000 0.0017730000 116309395 0 402718720 3.9220552444 4.0223712921 4.1394639015 520 1305031119.4792668819 0.0478702970 0.0444991842 0.0843561143 0.0183067607 0.3758140000 0.1012180000 0.0880850000 0.0000000000 0.1837670000 0.0017450000 116312955 0 402718720 3.9208581448 4.0305624008 4.1352543831 521 1305031119.5112578869 0.0476347953 0.0445052026 0.0843561143 0.0182950173 0.5711770000 0.0772990000 0.0933640000 0.0301970000 0.1813390000 0.1879920000 116316627 0 402718720 3.9188177586 4.0419058800 4.1319041252 522 1305031119.5474140644 0.0518750474 0.0445193211 0.0843561143 0.0182777859 0.3353740000 0.0770760000 0.0759000000 0.0000000000 0.1796730000 0.0017420000 116320467 0 402718720 3.9185771942 4.0511808395 4.1285228729 523 1305031119.5795691013 0.0515036657 0.0445326755 0.0843561143 0.0182730372 0.3410880000 0.0781480000 0.0522140000 0.0301790000 0.1778080000 0.0017550000 116324139 0 402718720 3.9201576710 4.0622415543 4.1256527901 524 1305031119.6150240898 0.0528810732 0.0445486076 0.0843561143 0.0182614697 0.3551360000 0.0948850000 0.0807140000 0.0000010000 0.1767850000 0.0017580000 116327923 0 402718720 3.9185676575 4.0719709396 4.1231021881 525 1305031119.6488890648 0.0587384254 0.0445756358 0.0843561143 0.0182591951 0.5434320000 0.0779980000 0.0591880000 0.0302170000 0.1842630000 0.1907630000 116331651 0 402718720 3.9172410965 4.0807332993 4.1216120720 526 1305031119.6792080402 0.0592452325 0.0446035248 0.0843561143 0.0182499465 0.3348000000 0.0905030000 0.0444200000 0.0000000000 0.1971080000 0.0017640000 116335211 0 402718720 3.9157211781 4.0920133591 4.1201286316 527 1305031119.7152490616 0.0615490079 0.0446356794 0.0843561143 0.0182348139 0.3806160000 0.0777430000 0.0865760000 0.0297050000 0.1838210000 0.0017660000 116338995 0 402718720 3.9132003784 4.1017169952 4.1193914413 528 1305031119.7471930981 0.0698051527 0.0446833488 0.0843561143 0.0182259511 0.3306140000 0.0772290000 0.0592190000 0.0000000000 0.1914110000 0.0017570000 116342723 0 402718720 3.9115748405 4.1058759689 4.1190624237 529 1305031119.7791690826 0.0720024556 0.0447349918 0.0843561143 0.0182097954 0.5599900000 0.0896550000 0.0584320000 0.0295960000 0.1869220000 0.1943770000 116346395 0 402718720 3.9103660583 4.1145777702 4.1182918549 530 1305031119.8145709038 0.0748392567 0.0447917923 0.0843561143 0.0181970860 0.3512400000 0.0764980000 0.0768100000 0.0000000000 0.1950430000 0.0018290000 116350067 0 402718720 3.9107604027 4.1216626167 4.1175217628 531 1305031119.8474450111 0.0786315501 0.0448555206 0.0843561143 0.0181855938 0.3843170000 0.0768560000 0.0853410000 0.0301590000 0.1890680000 0.0018370000 116353851 0 402718720 3.9124369621 4.1306347847 4.1165480614 532 1305031119.8792319298 0.0805823505 0.0449226763 0.0843561143 0.0181742182 0.3643660000 0.0759560000 0.0895400000 0.0000010000 0.1961320000 0.0017310000 116357467 0 402718720 3.9104678631 4.1374340057 4.1150212288 533 1305031119.9114239216 0.0810584575 0.0449904733 0.0843561143 0.0181748028 0.5878600000 0.0748920000 0.0850690000 0.0300860000 0.1943240000 0.2024830000 116361139 0 402718720 3.9087889194 4.1459045410 4.1130390167 534 1305031119.9474620819 0.0828508139 0.0450613728 0.0843561143 0.0181630936 0.4081880000 0.0985440000 0.1023040000 0.0000010000 0.2045700000 0.0017360000 116364979 0 402718720 3.9089789391 4.1550498009 4.1115021706 535 1305031119.9795460701 0.0855205208 0.0451369974 0.0855205208 0.0181497112 0.3870710000 0.0761890000 0.0851070000 0.0300790000 0.1929420000 0.0017410000 116368651 0 402718720 3.9082241058 4.1588964462 4.1104555130 536 1305031120.0152831078 0.0851749331 0.0452116950 0.0855205208 0.0181597208 0.3669990000 0.0764740000 0.0867650000 0.0000000000 0.2010380000 0.0017010000 116372379 0 402718720 3.9062681198 4.1666793823 4.1093726158 537 1305031120.0473101139 0.0883493423 0.0452920258 0.0883493423 0.0181542121 0.5804190000 0.0766490000 0.0788200000 0.0295790000 0.1926780000 0.2016690000 116376107 0 402718720 3.9073877335 4.1704711914 4.1095552444 538 1305031120.0794179440 0.0941584706 0.0453828556 0.0941584706 0.0181609895 0.3293430000 0.0758420000 0.0508120000 0.0000000000 0.1999710000 0.0016930000 116379779 0 402718720 3.9086911678 4.1661705971 4.1105213165 539 1305031120.1152489185 0.0925978571 0.0454704530 0.0941584706 0.0181539912 0.3826470000 0.0905140000 0.0657410000 0.0300620000 0.1935690000 0.0017340000 116383507 0 402718720 3.9079284668 4.1694884300 4.1097507477 540 1305031120.1481750011 0.0908213630 0.0455544362 0.0941584706 0.0181541574 0.3262590000 0.0741470000 0.0503050000 0.0000010000 0.1990900000 0.0016890000 116387235 0 402718720 3.9081254005 4.1700716019 4.1094479561 541 1305031120.1792609692 0.0933835432 0.0456428449 0.0941584706 0.0181454678 0.5905230000 0.0757330000 0.0876390000 0.0301320000 0.1931910000 0.2028020000 116390851 0 402718720 3.9078817368 4.1638035774 4.1107244492 542 1305031120.2152600288 0.0933406428 0.0457308482 0.0941584706 0.0181309060 0.3474780000 0.0762740000 0.0809450000 0.0000000000 0.1875030000 0.0017290000 116394635 0 402718720 3.9083387852 4.1580762863 4.1107378006 543 1305031120.2480180264 0.0854947343 0.0458040782 0.0941584706 0.0181164119 0.3827420000 0.0762770000 0.0876940000 0.0302320000 0.1857630000 0.0017370000 116398363 0 402718720 3.9048869610 4.1580553055 4.1087541580 544 1305031120.2794411182 0.0819252580 0.0458704775 0.0941584706 0.0181008366 0.3560570000 0.0762340000 0.0927800000 0.0000000000 0.1841380000 0.0018220000 116402035 0 402718720 3.9008495808 4.1534924507 4.1081514359 545 1305031120.3152129650 0.0777380913 0.0459289501 0.0941584706 0.0180847020 0.5740550000 0.0758940000 0.0923230000 0.0296630000 0.1833520000 0.1917890000 116405763 0 402718720 3.8964500427 4.1488313675 4.1074681282 546 1305031120.3477969170 0.0706129149 0.0459741589 0.0941584706 0.0180687989 0.3501680000 0.0764620000 0.0873920000 0.0000000000 0.1835430000 0.0017280000 116409491 0 402718720 3.8937954903 4.1433901787 4.1068539619 547 1305031120.3794460297 0.0678012893 0.0460140622 0.0941584706 0.0180532654 0.3489820000 0.0764760000 0.0586200000 0.0296070000 0.1814970000 0.0017430000 116413163 0 402718720 3.8941798210 4.1365008354 4.1092629433 548 1305031120.4154899120 0.0654740930 0.0460495732 0.0941584706 0.0181058060 0.3648110000 0.0826510000 0.0883160000 0.0000000000 0.1910600000 0.0017400000 116416891 0 402718720 3.9037449360 4.1233716011 4.1106901169 549 1305031120.4474329948 0.0590077229 0.0460731764 0.0941584706 0.0180996762 0.5560360000 0.0986850000 0.0662860000 0.0300240000 0.1765220000 0.1834850000 116420619 0 402718720 3.9005899429 4.1178498268 4.1141667366 550 1305031120.4794321060 0.0531998686 0.0460861340 0.0941584706 0.0180852554 0.3421260000 0.0779260000 0.0872440000 0.0000010000 0.1741650000 0.0017430000 116424291 0 402718720 3.9067451954 4.1130943298 4.1171035767 551 1305031120.5148770809 0.0539322719 0.0461003738 0.0941584706 0.0180755810 0.3281230000 0.0788790000 0.0445930000 0.0299890000 0.1718510000 0.0017580000 116428019 0 402718720 3.9087307453 4.1011161804 4.1216149330 552 1305031120.5478069782 0.0477545187 0.0461033705 0.0941584706 0.0180621493 0.3239620000 0.0790000000 0.0699350000 0.0000000000 0.1722290000 0.0017520000 116431747 0 402718720 3.9115910530 4.0940299034 4.1252903938 553 1305031120.5795590878 0.0434210002 0.0460985199 0.0941584706 0.0180515983 0.5388430000 0.0789100000 0.0740010000 0.0300300000 0.1743150000 0.1804930000 116435419 0 402718720 3.9152159691 4.0897846222 4.1294288635 554 1305031120.6152710915 0.0429218225 0.0460927858 0.0941584706 0.0180404377 0.3307680000 0.0902860000 0.0632520000 0.0000000000 0.1742930000 0.0018420000 116439091 0 402718720 3.9182398319 4.0811777115 4.1342859268 555 1305031120.6473538876 0.0380230285 0.0460782457 0.0941584706 0.0180282782 0.3431790000 0.0780200000 0.0552980000 0.0301060000 0.1768120000 0.0018380000 116442819 0 402718720 3.9197769165 4.0737004280 4.1384062767 556 1305031120.6793179512 0.0348600559 0.0460580691 0.0941584706 0.0180360727 0.3138300000 0.0776940000 0.0523980000 0.0000010000 0.1809760000 0.0017080000 116446435 0 402718720 3.9217967987 4.0689930916 4.1426081657 557 1305031120.7145531178 0.0334800892 0.0460354874 0.0941584706 0.0180205401 0.5463920000 0.0771840000 0.0667250000 0.0300340000 0.1827580000 0.1886490000 116450219 0 402718720 3.9226689339 4.0613088608 4.1469078064 558 1305031120.7473959923 0.0296550561 0.0460061318 0.0941584706 0.0180076337 0.3462110000 0.0772230000 0.0812700000 0.0000000000 0.1849070000 0.0017470000 116453947 0 402718720 3.9221985340 4.0533437729 4.1513085365 559 1305031120.7799079418 0.0305377152 0.0459784602 0.0941584706 0.0179964244 0.3760270000 0.0924060000 0.0631560000 0.0301400000 0.1873760000 0.0018450000 116457675 0 402718720 3.9228396416 4.0433487892 4.1556220055 560 1305031120.8149440289 0.0291504432 0.0459484102 0.0941584706 0.0179883172 0.3418000000 0.0927210000 0.0550990000 0.0000000000 0.1910200000 0.0018510000 116461403 0 402718720 3.9233202934 4.0362458229 4.1591720581 561 1305031120.8479421139 0.0240992121 0.0459094633 0.0941584706 0.0179725666 0.5882790000 0.0764330000 0.0877130000 0.0300710000 0.1934030000 0.1996030000 116465131 0 402718720 3.9222683907 4.0304241180 4.1627111435 562 1305031120.8834540844 0.0254136156 0.0458729938 0.0941584706 0.0179652707 0.3176300000 0.0750710000 0.0442520000 0.0000000000 0.1954860000 0.0017630000 116468859 0 402718720 3.9244396687 4.0192966461 4.1658697128 563 1305031120.9154539108 0.0237693507 0.0458337334 0.0941584706 0.0179583902 0.3641000000 0.0752510000 0.0584790000 0.0299520000 0.1975710000 0.0017730000 116472531 0 402718720 3.9235551357 4.0130476952 4.1690149307 564 1305031120.9475090504 0.0210952442 0.0457898708 0.0941584706 0.0179432164 0.3445730000 0.0759160000 0.0675790000 0.0000010000 0.1982490000 0.0017650000 116476203 0 402718720 3.9222080708 4.0051116943 4.1719050407 565 1305031120.9833900928 0.0215503927 0.0457469691 0.0941584706 0.0179307932 0.5691590000 0.0757710000 0.0583680000 0.0295890000 0.1990640000 0.2052980000 116479987 0 402718720 3.9219865799 3.9961833954 4.1748938560 566 1305031121.0150289536 0.0236241594 0.0457078828 0.0941584706 0.0179216936 0.3779830000 0.0873620000 0.0869430000 0.0000000000 0.2008360000 0.0017620000 116483603 0 402718720 3.9204480648 3.9865674973 4.1777386665 567 1305031121.0477550030 0.0191495977 0.0456610428 0.0941584706 0.0179060016 0.3865640000 0.0751480000 0.0756910000 0.0301160000 0.2027610000 0.0017760000 116487387 0 402718720 3.9205048084 3.9808001518 4.1799306870 568 1305031121.0831170082 0.0221717861 0.0456196885 0.0941584706 0.0178948000 0.3820310000 0.0887670000 0.0862570000 0.0000010000 0.2041330000 0.0017940000 116491115 0 402718720 3.9179153442 3.9704644680 4.1825237274 569 1305031121.1148779392 0.0220635831 0.0455782894 0.0941584706 0.0178815069 0.6172690000 0.0756530000 0.0913710000 0.0301450000 0.2063590000 0.2126020000 116494731 0 402718720 3.9193449020 3.9615459442 4.1847686768 570 1305031121.1473550797 0.0199378375 0.0455333061 0.0941584706 0.0178666393 0.3401880000 0.0733620000 0.0527830000 0.0000010000 0.2111890000 0.0017740000 116498459 0 402718720 3.9175708294 3.9547431469 4.1868667603 571 1305031121.1832809448 0.0219208375 0.0454919533 0.0941584706 0.0178510330 0.3767470000 0.0747820000 0.0534010000 0.0301820000 0.2153640000 0.0018800000 116502243 0 402718720 3.9153079987 3.9461617470 4.1892318726 572 1305031121.2114310265 0.0216167010 0.0454502133 0.0941584706 0.0178397855 0.3619010000 0.0877120000 0.0505690000 0.0000010000 0.2207610000 0.0017760000 116505747 0 402718720 3.9158618450 3.9380125999 4.1914763451 573 1305031121.2472009659 0.0214796774 0.0454083799 0.0941584706 0.0178253489 0.6522060000 0.0880510000 0.0783600000 0.0301360000 0.2242740000 0.2303010000 116509531 0 402718720 3.9141323566 3.9318523407 4.1941561699 574 1305031121.2828760147 0.0242502168 0.0453715190 0.0941584706 0.0178101306 0.3831760000 0.0982710000 0.0558140000 0.0000010000 0.2262090000 0.0017750000 116513315 0 402718720 3.9120819569 3.9227128029 4.1975789070 575 1305031121.3135879040 0.0253025591 0.0453366165 0.0941584706 0.0178035865 0.4192480000 0.0727510000 0.0843140000 0.0299220000 0.2294160000 0.0017560000 116516931 0 402718720 3.9131767750 3.9123301506 4.2005639076 576 1305031121.3475399017 0.0272710118 0.0453052526 0.0941584706 0.0177922238 0.3946330000 0.0722090000 0.0862160000 0.0000000000 0.2333240000 0.0017870000 116520659 0 402718720 3.9103882313 3.9053876400 4.2041363716 577 1305031121.3832480907 0.0268271361 0.0452732281 0.0941584706 0.0177878975 0.6400080000 0.0733980000 0.0565180000 0.0300860000 0.2363950000 0.2425100000 116524443 0 402718720 3.9116089344 3.8965048790 4.2076292038 578 1305031121.4143280983 0.0289391950 0.0452449686 0.0941584706 0.0177737636 0.3645320000 0.0713740000 0.0489160000 0.0000000000 0.2414040000 0.0017450000 116528059 0 402718720 3.9101536274 3.8880500793 4.2102065086 579 1305031121.4473190308 0.0317982100 0.0452217445 0.0941584706 0.0177667046 0.4200290000 0.0834230000 0.0586690000 0.0302050000 0.2448460000 0.0017910000 116531787 0 402718720 3.9067275524 3.8834686279 4.2138805389 580 1305031121.4830150604 0.0312592275 0.0451976711 0.0941584706 0.0177695315 0.3919420000 0.0726920000 0.0696530000 0.0000010000 0.2467140000 0.0017890000 116535515 0 402718720 3.9090309143 3.8738136292 4.2167644501 581 1305031121.5141639709 0.0338396318 0.0451781220 0.0941584706 0.0177588037 0.6608160000 0.0726070000 0.0520610000 0.0301490000 0.2491290000 0.2557690000 116539131 0 402718720 3.9069821835 3.8633761406 4.2196259499 582 1305031121.5472700596 0.0343812965 0.0451595708 0.0941584706 0.0177533667 0.3985850000 0.0702100000 0.0741890000 0.0000000000 0.2513060000 0.0017660000 116542915 0 402718720 3.9065034389 3.8562188148 4.2237114906 583 1305031121.5832130909 0.0346808508 0.0451415970 0.0941584706 0.0177410584 0.4094660000 0.0713590000 0.0549180000 0.0295720000 0.2507210000 0.0017910000 116546699 0 402718720 3.9065127373 3.8476965427 4.2266345024 584 1305031121.6147189140 0.0357190892 0.0451254626 0.0941584706 0.0177281202 0.4338260000 0.0939510000 0.0860020000 0.0000010000 0.2509810000 0.0017730000 116550315 0 402718720 3.9064037800 3.8362426758 4.2293972969 585 1305031121.6471829414 0.0353119709 0.0451086874 0.0941584706 0.0177213886 0.7069310000 0.0713580000 0.0863810000 0.0300010000 0.2593950000 0.2586920000 116553987 0 402718720 3.9088985920 3.8293728828 4.2316789627 586 1305031121.6832110882 0.0373851210 0.0450955072 0.0941584706 0.0177117143 0.3870230000 0.0709260000 0.0616150000 0.0000010000 0.2515950000 0.0017780000 116557827 0 402718720 3.9068815708 3.8220939636 4.2348527908 587 1305031121.7145280838 0.0413179733 0.0450890719 0.0941584706 0.0176978673 0.4174060000 0.0695940000 0.0642620000 0.0294680000 0.2511980000 0.0017690000 116561443 0 402718720 3.9036567211 3.8117523193 4.2373490334 588 1305031121.7471449375 0.0428195409 0.0450852121 0.0941584706 0.0176849272 0.4031350000 0.0683970000 0.0792920000 0.0000010000 0.2525800000 0.0017530000 116565115 0 402718720 3.9035704136 3.8076140881 4.2404599190 589 1305031121.7828710079 0.0434653871 0.0450824620 0.0941584706 0.0176708158 0.6868520000 0.0915300000 0.0538820000 0.0299950000 0.2522260000 0.2580910000 116568899 0 402718720 3.9049921036 3.8004283905 4.2435917854 590 1305031121.8115448952 0.0448238552 0.0450820237 0.0941584706 0.0176605455 0.3852520000 0.0687390000 0.0605210000 0.0000010000 0.2531200000 0.0017540000 116572459 0 402718720 3.9048748016 3.7952237129 4.2466311455 591 1305031121.8473351002 0.0454974957 0.0450827267 0.0941584706 0.0176477524 0.4308150000 0.0671190000 0.0791370000 0.0297050000 0.2519770000 0.0017510000 116576243 0 402718720 3.9070525169 3.7918944359 4.2493314743 592 1305031121.8821229935 0.0462109186 0.0450846324 0.0941584706 0.0176328475 0.3775590000 0.0688960000 0.0546450000 0.0000010000 0.2511490000 0.0017430000 116579971 0 402718720 3.9065244198 3.7890555859 4.2516999245 593 1305031121.9149429798 0.0455113575 0.0450853520 0.0941584706 0.0176187069 0.6586630000 0.0687570000 0.0544540000 0.0294170000 0.2494390000 0.2554750000 116583699 0 402718720 3.9078814983 3.7874510288 4.2531509399 594 1305031121.9473180771 0.0461862311 0.0450872054 0.0941584706 0.0176069169 0.3846810000 0.0837040000 0.0494000000 0.0000010000 0.2485540000 0.0018300000 116587371 0 402718720 3.9070968628 3.7861247063 4.2542314529 595 1305031121.9829349518 0.0433286503 0.0450842498 0.0941584706 0.0175927955 0.4129990000 0.0684810000 0.0634240000 0.0299300000 0.2482730000 0.0017570000 116591155 0 402718720 3.9092867374 3.7899677753 4.2546639442 596 1305031122.0144240856 0.0431878790 0.0450810680 0.0941584706 0.0175789890 0.3650870000 0.0685570000 0.0469970000 0.0000010000 0.2466600000 0.0017430000 116594827 0 402718720 3.9080836773 3.7923066616 4.2543616295 597 1305031122.0473060608 0.0432175659 0.0450779465 0.0941584706 0.0175649791 0.6785450000 0.0692530000 0.0805500000 0.0298890000 0.2458980000 0.2518090000 116598499 0 402718720 3.9078061581 3.7949228287 4.2532114983 598 1305031122.0829689503 0.0418992341 0.0450726310 0.0941584706 0.0175509198 0.3786300000 0.0695970000 0.0609590000 0.0000000000 0.2451830000 0.0017540000 116602283 0 402718720 3.9073686600 3.8016610146 4.2514486313 599 1305031122.1146879196 0.0410628319 0.0450659368 0.0941584706 0.0175373045 0.4332540000 0.0857470000 0.0712330000 0.0300050000 0.2432050000 0.0018660000 116605899 0 402718720 3.9073593616 3.8090188503 4.2483563423 600 1305031122.1507480145 0.0397462025 0.0450570706 0.0941584706 0.0175281690 0.3709600000 0.0709370000 0.0549840000 0.0000010000 0.2421460000 0.0017610000 116609683 0 402718720 3.9072043896 3.8186283112 4.2455387115 601 1305031122.1830520630 0.0383413993 0.0450458964 0.0941584706 0.0175255933 0.6391950000 0.0710050000 0.0508710000 0.0299300000 0.2397650000 0.2464890000 116613411 0 402718720 3.9089169502 3.8270194530 4.2413306236 602 1305031122.2149689198 0.0358031914 0.0450305431 0.0941584706 0.0175522298 0.3606540000 0.0717530000 0.0487410000 0.0000000000 0.2372380000 0.0017730000 116617027 0 402718720 3.9078371525 3.8404650688 4.2384157181 603 1305031122.2513549328 0.0367471986 0.0450168062 0.0941584706 0.0175440915 0.4142420000 0.0721600000 0.0793860000 0.0294780000 0.2300930000 0.0018760000 116620867 0 402718720 3.9056291580 3.8518576622 4.2346634865 604 1305031122.2838659286 0.0379926711 0.0450051768 0.0941584706 0.0175346640 0.3885000000 0.0724800000 0.0865050000 0.0000010000 0.2265920000 0.0017700000 116624595 0 402718720 3.9048426151 3.8598458767 4.2285442352 605 1305031122.3143088818 0.0334992111 0.0449861587 0.0941584706 0.0175550916 0.6563580000 0.0853610000 0.0875380000 0.0299560000 0.2229210000 0.2294140000 116628155 0 402718720 3.9042351246 3.8762321472 4.2241024971 606 1305031122.3513510227 0.0353197567 0.0449702076 0.0941584706 0.0175470039 0.3480310000 0.0728500000 0.0486810000 0.0000000000 0.2235920000 0.0017560000 116631939 0 402718720 3.9051430225 3.8835813999 4.2199549675 607 1305031122.3826780319 0.0347379111 0.0449533504 0.0941584706 0.0175357103 0.4120520000 0.0842290000 0.0829950000 0.0300020000 0.2119130000 0.0017560000 116635667 0 402718720 3.9068474770 3.8916192055 4.2147097588 608 1305031122.4150080681 0.0366994478 0.0449397749 0.0941584706 0.0175332787 0.3661320000 0.0721170000 0.0828260000 0.0000000000 0.2083240000 0.0017090000 116639227 0 402718720 3.9062411785 3.8982272148 4.2090091705 609 1305031122.4512720108 0.0382714048 0.0449288252 0.0941584706 0.0175214797 0.5860220000 0.0871470000 0.0501700000 0.0301940000 0.2056390000 0.2117230000 116643067 0 402718720 3.9071893692 3.9074087143 4.2032861710 610 1305031122.4833879471 0.0368078724 0.0449155122 0.0941584706 0.0175082412 0.3883890000 0.0966320000 0.0858950000 0.0000010000 0.2029510000 0.0017560000 116646739 0 402718720 3.9065599442 3.9177114964 4.1975975037 611 1305031122.5151350498 0.0367200300 0.0449020989 0.0941584706 0.0174977345 0.3608630000 0.0745070000 0.0500860000 0.0301730000 0.2031700000 0.0017620000 116650411 0 402718720 3.9068036079 3.9261274338 4.1922254562 612 1305031122.5515100956 0.0380034558 0.0448908266 0.0941584706 0.0174905011 0.3533280000 0.0875980000 0.0603370000 0.0000000000 0.2023320000 0.0018450000 116654195 0 402718720 3.9070637226 3.9366571903 4.1868243217 613 1305031122.5832169056 0.0377781503 0.0448792236 0.0941584706 0.0174772137 0.5698890000 0.0864720000 0.0458840000 0.0297950000 0.1999380000 0.2066220000 116657867 0 402718720 3.9068977833 3.9460377693 4.1814150810 614 1305031122.6150169373 0.0393816642 0.0448702699 0.0941584706 0.0174709329 0.3529460000 0.0982090000 0.0532570000 0.0000010000 0.1983960000 0.0018670000 116661483 0 402718720 3.9061820507 3.9532282352 4.1758770943 615 1305031122.6488099098 0.0432934128 0.0448677059 0.0941584706 0.0174569478 0.3604000000 0.0757870000 0.0520850000 0.0298720000 0.1997090000 0.0017790000 116665267 0 402718720 3.9059991837 3.9615316391 4.1703667641 616 1305031122.6834199429 0.0419866107 0.0448630288 0.0941584706 0.0174430839 0.3290700000 0.0750880000 0.0508810000 0.0000010000 0.2001670000 0.0017550000 116668995 0 402718720 3.9057867527 3.9727842808 4.1653885841 617 1305031122.7152190208 0.0424917303 0.0448591855 0.0941584706 0.0174312377 0.6023690000 0.0762440000 0.0878350000 0.0298080000 0.2004910000 0.2068280000 116672611 0 402718720 3.9057815075 3.9818747044 4.1612882614 618 1305031122.7513089180 0.0441373624 0.0448580175 0.0941584706 0.0174251042 0.3548570000 0.0766380000 0.0735810000 0.0000000000 0.2016880000 0.0017780000 116676451 0 402718720 3.9075000286 3.9935193062 4.1572070122 619 1305031122.7834379673 0.0416156687 0.0448527795 0.0941584706 0.0174174954 0.3762910000 0.0887490000 0.0547290000 0.0303510000 0.1994910000 0.0017780000 116680123 0 402718720 3.9075875282 4.0067062378 4.1541953087 620 1305031122.8125650883 0.0426026694 0.0448491503 0.0941584706 0.0174053281 0.3552280000 0.0772740000 0.0662540000 0.0000010000 0.2079860000 0.0023880000 116683739 0 402718720 3.9083924294 4.0157461166 4.1515264511 621 1305031122.8514859676 0.0476629846 0.0448536814 0.0941584706 0.0174039968 0.6034410000 0.0972230000 0.0898720000 0.0302940000 0.1893290000 0.1955420000 116687579 0 402718720 3.9079477787 4.0226507187 4.1490311623 622 1305031122.8837749958 0.0478987284 0.0448585770 0.0941584706 0.0173925745 0.3288290000 0.0776380000 0.0647950000 0.0000010000 0.1834390000 0.0017530000 116691307 0 402718720 3.9096710682 4.0317544937 4.1464800835 623 1305031122.9145851135 0.0502291843 0.0448671975 0.0941584706 0.0173857077 0.3812660000 0.0777450000 0.0920090000 0.0302390000 0.1783230000 0.0017580000 116694867 0 402718720 3.9072673321 4.0380105972 4.1438112259 624 1305031122.9514129162 0.0551560707 0.0448836861 0.0941584706 0.0173735952 0.3382460000 0.0970490000 0.0626140000 0.0000010000 0.1756320000 0.0017530000 116698707 0 402718720 3.9059674740 4.0437483788 4.1412916183 625 1305031122.9830000401 0.0558075532 0.0449011643 0.0941584706 0.0173620523 0.5525200000 0.0770220000 0.0883490000 0.0302680000 0.1747630000 0.1809250000 116702379 0 402718720 3.9071097374 4.0512986183 4.1390881538 626 1305031123.0154619217 0.0575764179 0.0449214123 0.0941584706 0.0173485325 0.3102350000 0.0769640000 0.0555720000 0.0000010000 0.1746090000 0.0018390000 116705995 0 402718720 3.9056594372 4.0579519272 4.1370410919 627 1305031123.0518379211 0.0622849315 0.0449491053 0.0941584706 0.0173384149 0.3572620000 0.0772060000 0.0701560000 0.0303010000 0.1766590000 0.0017600000 116709835 0 402718720 3.9056184292 4.0635232925 4.1347174644 628 1305031123.0829920769 0.0625482425 0.0449771294 0.0941584706 0.0173285960 0.3248180000 0.0768940000 0.0662110000 0.0000000000 0.1787560000 0.0017520000 116713507 0 402718720 3.9049568176 4.0721716881 4.1322379112 629 1305031123.1139390469 0.0614686012 0.0450033480 0.0941584706 0.0173215261 0.5677080000 0.0775610000 0.0934860000 0.0302720000 0.1792260000 0.1859630000 116717067 0 402718720 3.9066350460 4.0827174187 4.1301040649 630 1305031123.1508400440 0.0666238740 0.0450376663 0.0941584706 0.0173081012 0.3191780000 0.0772090000 0.0592640000 0.0000000000 0.1797470000 0.0017450000 116720907 0 402718720 3.9043691158 4.0894298553 4.1289930344 631 1305031123.1821761131 0.0678842217 0.0450738732 0.0941584706 0.0173056481 0.3435490000 0.0772510000 0.0529040000 0.0303010000 0.1800180000 0.0018390000 116724579 0 402718720 3.9040493965 4.0986242294 4.1275033951 632 1305031123.2147240639 0.0679798648 0.0451101168 0.0941584706 0.0172947330 0.3160660000 0.0771060000 0.0545400000 0.0000000000 0.1814590000 0.0017610000 116728251 0 402718720 3.9065289497 4.1096081734 4.1265373230 633 1305031123.2506411076 0.0730004981 0.0451541775 0.0941584706 0.0173052981 0.5393850000 0.0747410000 0.0651380000 0.0295180000 0.1808510000 0.1879380000 116732035 0 402718720 3.9034583569 4.1186504364 4.1259460449 634 1305031123.2823629379 0.0771023408 0.0452045689 0.0941584706 0.0172982262 0.3599160000 0.0841730000 0.0919750000 0.0000010000 0.1808040000 0.0017430000 116735707 0 402718720 3.9067459106 4.1257777214 4.1266698837 635 1305031123.3209919930 0.0838040635 0.0452653555 0.0941584706 0.0172898774 0.3674900000 0.0748420000 0.0801530000 0.0295080000 0.1800230000 0.0017500000 116739547 0 402718720 3.9052491188 4.1325483322 4.1272211075 636 1305031123.3504929543 0.0860349163 0.0453294586 0.0941584706 0.0172772896 0.3043570000 0.0763800000 0.0446010000 0.0000000000 0.1804170000 0.0017450000 116743163 0 402718720 3.9048151970 4.1407599449 4.1271309853 637 1305031123.3822629452 0.0892681628 0.0453984361 0.0941584706 0.0172652474 0.5937190000 0.0975380000 0.0932880000 0.0302110000 0.1810060000 0.1904730000 116746835 0 402718720 3.9070088863 4.1475977898 4.1271648407 638 1305031123.4213430882 0.0952222124 0.0454765298 0.0952222124 0.0172521582 0.3185060000 0.0767760000 0.0522590000 0.0000010000 0.1865270000 0.0017320000 116750675 0 402718720 3.9070060253 4.1536984444 4.1270885468 639 1305031123.4512660503 0.0984851196 0.0455594854 0.0984851196 0.0172470467 0.3692450000 0.0880290000 0.0624920000 0.0301560000 0.1856060000 0.0017370000 116754235 0 402718720 3.9058046341 4.1593456268 4.1266260147 640 1305031123.4836049080 0.0992305800 0.0456433465 0.0992305800 0.0172361413 0.3642320000 0.0769050000 0.0890620000 0.0000010000 0.1953300000 0.0017250000 116757963 0 402718720 3.9074711800 4.1679663658 4.1254944801 641 1305031123.5197250843 0.1026702374 0.0457323120 0.1026702374 0.0172241258 0.5894250000 0.0773320000 0.0950700000 0.0301540000 0.1877600000 0.1978580000 116761691 0 402718720 3.9070456028 4.1754074097 4.1243815422 642 1305031123.5515730381 0.1045782492 0.0458239723 0.1045782492 0.0172111443 0.3448750000 0.0770480000 0.0707390000 0.0000010000 0.1939980000 0.0018180000 116765419 0 402718720 3.9087748528 4.1815118790 4.1236128807 643 1305031123.5796160698 0.1058567539 0.0459173359 0.1058567539 0.0171999325 0.3941240000 0.0767420000 0.0895840000 0.0302010000 0.1946390000 0.0017380000 116768923 0 402718720 3.9092040062 4.1884160042 4.1226453781 644 1305031123.6203870773 0.1085295230 0.0460145598 0.1085295230 0.0171952656 0.3838710000 0.0893420000 0.0897750000 0.0000000000 0.2017910000 0.0017330000 116772819 0 402718720 3.9110667706 4.1956305504 4.1217918396 645 1305031123.6524300575 0.1088066846 0.0461119119 0.1088066846 0.0171832417 0.6149980000 0.0781670000 0.1017440000 0.0363670000 0.1944190000 0.2030900000 116776491 0 402718720 3.9138019085 4.2034091949 4.1212677956 646 1305031123.6837849617 0.1093539894 0.0462098099 0.1093539894 0.0171719159 0.3754920000 0.0782100000 0.0902920000 0.0000010000 0.2040260000 0.0017410000 116780163 0 402718720 3.9129958153 4.2103605270 4.1208095551 647 1305031123.7199749947 0.1122111082 0.0463118211 0.1122111082 0.0171594840 0.3913650000 0.0782370000 0.0815290000 0.0302250000 0.1983930000 0.0017490000 116783947 0 402718720 3.9128539562 4.2155079842 4.1202893257 648 1305031123.7519800663 0.1129953563 0.0464147278 0.1129953563 0.0171521540 0.3498580000 0.0779230000 0.0604600000 0.0000010000 0.2085020000 0.0017400000 116787619 0 402718720 3.9125611782 4.2189640999 4.1195478439 649 1305031123.7841379642 0.1140335798 0.0465189171 0.1140335798 0.0171434406 0.5813180000 0.0899340000 0.0597660000 0.0303940000 0.1940990000 0.2059080000 116791235 0 402718720 3.9137682915 4.2204852104 4.1192131042 650 1305031123.8196959496 0.1137822643 0.0466223992 0.1140335798 0.0171316499 0.3391420000 0.0769980000 0.0629030000 0.0000010000 0.1961510000 0.0018180000 116795075 0 402718720 3.9153077602 4.2227501869 4.1182932854 651 1305031123.8515510559 0.1135854274 0.0467252610 0.1140335798 0.0171187623 0.3953830000 0.0764140000 0.0935670000 0.0299050000 0.1923780000 0.0018200000 116798747 0 402718720 3.9158895016 4.2224702835 4.1176276207 652 1305031123.8838191032 0.1137546077 0.0468280667 0.1140335798 0.0171086878 0.3563210000 0.0886240000 0.0704410000 0.0000010000 0.1942830000 0.0017340000 116802419 0 402718720 3.9156949520 4.2208709717 4.1174721718 653 1305031123.9157938957 0.1122817174 0.0469283020 0.1140335798 0.0170972667 0.5642420000 0.0776300000 0.0637790000 0.0304700000 0.1892880000 0.2018600000 116806035 0 402718720 3.9157853127 4.2182316780 4.1168375015 654 1305031123.9515299797 0.1084398404 0.0470223564 0.1140335798 0.0170959942 0.3458710000 0.0921360000 0.0602630000 0.0000010000 0.1905010000 0.0017340000 116809875 0 402718720 3.9163370132 4.2187080383 4.1162152290 655 1305031123.9834210873 0.1097438782 0.0471181144 0.1140335798 0.0170950009 0.3701050000 0.0771550000 0.0723980000 0.0304560000 0.1869770000 0.0018200000 116813547 0 402718720 3.9155850410 4.2128062248 4.1180205345 656 1305031124.0197370052 0.1104772985 0.0472146986 0.1140335798 0.0171078822 0.3442160000 0.0911110000 0.0649340000 0.0000000000 0.1851760000 0.0017550000 116817331 0 402718720 3.9144225121 4.2037124634 4.1206159592 657 1305031124.0515310764 0.1063107923 0.0473046469 0.1140335798 0.0171065882 0.5564840000 0.0783520000 0.0689550000 0.0303720000 0.1840550000 0.1935210000 116820947 0 402718720 3.9155960083 4.2013959885 4.1207742691 658 1305031124.0839018822 0.1054362878 0.0473929929 0.1140335798 0.0170983897 0.3408540000 0.0781920000 0.0765250000 0.0000000000 0.1831670000 0.0017410000 116824619 0 402718720 3.9162256718 4.1959505081 4.1233553886 659 1305031124.1196689606 0.1043581739 0.0474794348 0.1140335798 0.0171026056 0.3941120000 0.0881630000 0.0931810000 0.0303410000 0.1794230000 0.0017560000 116828403 0 402718720 3.9098300934 4.1855287552 4.1255440712 660 1305031124.1474580765 0.1008459106 0.0475602931 0.1140335798 0.0171021597 0.3241800000 0.0780630000 0.0650410000 0.0000000000 0.1779530000 0.0018180000 116832019 0 402718720 3.9187703133 4.1821203232 4.1279444695 661 1305031124.1827070713 0.0995763540 0.0476389860 0.1140335798 0.0170929667 0.5657090000 0.0773100000 0.0953030000 0.0298070000 0.1763880000 0.1856550000 116835747 0 402718720 3.9171414375 4.1753740311 4.1306977272 662 1305031124.2171790600 0.0935991108 0.0477084122 0.1140335798 0.0170970134 0.3190580000 0.0778760000 0.0616240000 0.0000000000 0.1765620000 0.0017350000 116839475 0 402718720 3.9047150612 4.1682577133 4.1286287308 663 1305031124.2493400574 0.0939125270 0.0477781017 0.1140335798 0.0170915287 0.3753520000 0.0774890000 0.0902630000 0.0297050000 0.1748990000 0.0017430000 116843091 0 402718720 3.9213514328 4.1602325439 4.1346745491 664 1305031124.2825551033 0.0885712057 0.0478395371 0.1140335798 0.0170794810 0.3672180000 0.1005940000 0.0894330000 0.0000010000 0.1741750000 0.0017220000 116846819 0 402718720 3.9200384617 4.1570611000 4.1355357170 665 1305031124.3167819977 0.0828805938 0.0478922304 0.1140335798 0.0170854625 0.5181640000 0.0768380000 0.0557600000 0.0302450000 0.1731470000 0.1808510000 116850547 0 402718720 3.9131662846 4.1485133171 4.1342263222 666 1305031124.3503708839 0.0802576467 0.0479408271 0.1140335798 0.0170779614 0.3374740000 0.0900930000 0.0686920000 0.0000000000 0.1756800000 0.0017520000 116854219 0 402718720 3.9156460762 4.1419053078 4.1360278130 667 1305031124.3824319839 0.0760476813 0.0479829663 0.1140335798 0.0170691361 0.3858180000 0.0888370000 0.0876070000 0.0296910000 0.1766770000 0.0017490000 116857947 0 402718720 3.9172942638 4.1356601715 4.1363735199 668 1305031124.4185550213 0.0709664822 0.0480173728 0.1140335798 0.0170717503 0.3168610000 0.0774420000 0.0588930000 0.0000010000 0.1774990000 0.0017420000 116861787 0 402718720 3.9211821556 4.1257939339 4.1367383003 669 1305031124.4502561092 0.0683728904 0.0480477996 0.1140335798 0.0170591492 0.5682920000 0.0895650000 0.0874470000 0.0296690000 0.1766140000 0.1837380000 116865347 0 402718720 3.9200408459 4.1166315079 4.1373438835 670 1305031124.4801259041 0.0639560968 0.0480715433 0.1140335798 0.0170472527 0.3490160000 0.0781160000 0.0924080000 0.0000010000 0.1754480000 0.0017650000 116869019 0 402718720 3.9212629795 4.1090216637 4.1371531487 671 1305031124.5167369843 0.0567346700 0.0480844541 0.1140335798 0.0170351483 0.3458250000 0.0784360000 0.0588520000 0.0300590000 0.1754260000 0.0017730000 116872803 0 402718720 3.9231617451 4.1011872292 4.1377491951 672 1305031124.5505030155 0.0526850000 0.0480913001 0.1140335798 0.0170226394 0.3091690000 0.0784770000 0.0515850000 0.0000010000 0.1760840000 0.0017580000 116876531 0 402718720 3.9218108654 4.0939979553 4.1391963959 673 1305031124.5846059322 0.0508148372 0.0480953470 0.1140335798 0.0170105134 0.5560060000 0.0784200000 0.0879170000 0.0300650000 0.1760970000 0.1822410000 116880259 0 402718720 3.9226434231 4.0840511322 4.1413230896 674 1305031124.6176528931 0.0452251434 0.0480910885 0.1140335798 0.0170124363 0.3627140000 0.0945500000 0.0886990000 0.0000010000 0.1764250000 0.0017600000 116883987 0 402718720 3.9231925011 4.0732827187 4.1437997818 675 1305031124.6513130665 0.0420672521 0.0480821643 0.1140335798 0.0170057002 0.3374650000 0.0780000000 0.0477020000 0.0296780000 0.1788750000 0.0018630000 116887659 0 402718720 3.9233343601 4.0648312569 4.1465415955 676 1305031124.6854729652 0.0408682674 0.0480714929 0.1140335798 0.0169976118 0.3695390000 0.0888190000 0.0939990000 0.0000000000 0.1836710000 0.0017680000 116891387 0 402718720 3.9246945381 4.0536322594 4.1496057510 677 1305031124.7157909870 0.0339284278 0.0480506021 0.1140335798 0.0169861807 0.5585870000 0.0911570000 0.0555530000 0.0296920000 0.1872230000 0.1936530000 116895059 0 402718720 3.9255840778 4.0447797775 4.1525564194 678 1305031124.7499411106 0.0318277217 0.0480266745 0.1140335798 0.0169744008 0.3400340000 0.0760650000 0.0701410000 0.0000010000 0.1907790000 0.0017560000 116898787 0 402718720 3.9245965481 4.0352888107 4.1562504768 679 1305031124.7851779461 0.0316218734 0.0480025143 0.1140335798 0.0169625189 0.4071850000 0.0899690000 0.0889700000 0.0301440000 0.1950280000 0.0017750000 116902515 0 402718720 3.9242572784 4.0237641335 4.1604957581 680 1305031124.8166410923 0.0256534908 0.0479696481 0.1140335798 0.0169511957 0.3327140000 0.0766090000 0.0548080000 0.0000010000 0.1980870000 0.0018560000 116906187 0 402718720 3.9228019714 4.0149059296 4.1651787758 681 1305031124.8505589962 0.0250650942 0.0479360144 0.1140335798 0.0169390391 0.5777960000 0.0770360000 0.0624900000 0.0297400000 0.2002650000 0.2069790000 116909915 0 402718720 3.9226543903 4.0045733452 4.1706976891 682 1305031124.8835940361 0.0251102131 0.0479025454 0.1140335798 0.0169373462 0.3623840000 0.0898380000 0.0664250000 0.0000000000 0.2030590000 0.0017660000 116913587 0 402718720 3.9246449471 3.9930019379 4.1763024330 683 1305031124.9187700748 0.0202860907 0.0478621114 0.1140335798 0.0169362795 0.3801130000 0.0761380000 0.0583140000 0.0295850000 0.2130030000 0.0017670000 116917371 0 402718720 3.9243922234 3.9854083061 4.1822233200 684 1305031124.9507479668 0.0212510061 0.0478232063 0.1140335798 0.0169254635 0.3820540000 0.0859600000 0.0907420000 0.0000000000 0.2021290000 0.0018530000 116920987 0 402718720 3.9220230579 3.9770705700 4.1884250641 685 1305031124.9864599705 0.0242625587 0.0477888112 0.1140335798 0.0169595292 0.5639530000 0.0756370000 0.0466820000 0.0296570000 0.2019800000 0.2086990000 116924771 0 402718720 3.9233353138 3.9608490467 4.1943454742 686 1305031125.0194671154 0.0274029449 0.0477590942 0.1140335798 0.0169500470 0.3711910000 0.0749820000 0.0864200000 0.0000010000 0.2067070000 0.0017750000 116928499 0 402718720 3.9216032028 3.9495711327 4.2002291679 687 1305031125.0507979393 0.0243891552 0.0477250768 0.1140335798 0.0169496461 0.3777880000 0.0751300000 0.0576190000 0.0301340000 0.2117940000 0.0017860000 116932115 0 402718720 3.9213945866 3.9458291531 4.2053833008 688 1305031125.0834798813 0.0237874761 0.0476902838 0.1140335798 0.0169390075 0.3484720000 0.0746510000 0.0573070000 0.0000000000 0.2134290000 0.0017660000 116935843 0 402718720 3.9218471050 3.9383444786 4.2106537819 689 1305031125.1190290451 0.0254538693 0.0476580103 0.1140335798 0.0169320702 0.5987990000 0.0743290000 0.0559960000 0.0300790000 0.2154650000 0.2216160000 116939627 0 402718720 3.9194741249 3.9270062447 4.2155632973 690 1305031125.1510369778 0.0252100751 0.0476254771 0.1140335798 0.0169237815 0.3797330000 0.0950950000 0.0604130000 0.0000010000 0.2211110000 0.0017840000 116943243 0 402718720 3.9200396538 3.9187424183 4.2194948196 691 1305031125.1870639324 0.0232977755 0.0475902705 0.1140335798 0.0169247348 0.3851150000 0.0722450000 0.0560060000 0.0299690000 0.2237980000 0.0017820000 116947083 0 402718720 3.9171104431 3.9156265259 4.2235894203 692 1305031125.2190179825 0.0252836905 0.0475580356 0.1140335798 0.0169165046 0.3543370000 0.0730610000 0.0563150000 0.0000010000 0.2218550000 0.0017850000 116950755 0 402718720 3.9147758484 3.9063413143 4.2271399498 693 1305031125.2506420612 0.0288935862 0.0475311028 0.1140335798 0.0169085533 0.6064240000 0.0731580000 0.0496940000 0.0300020000 0.2230060000 0.2292550000 116954371 0 402718720 3.9134781361 3.8934991360 4.2303290367 694 1305031125.2863960266 0.0294244643 0.0475050125 0.1140335798 0.0168985849 0.3875980000 0.1009490000 0.0562890000 0.0000010000 0.2272580000 0.0017780000 116958155 0 402718720 3.9102542400 3.8875248432 4.2334961891 695 1305031125.3191399574 0.0290911794 0.0474785178 0.1140335798 0.0168901657 0.4005820000 0.0730390000 0.0661610000 0.0295320000 0.2287370000 0.0017810000 116961883 0 402718720 3.9101440907 3.8814206123 4.2365236282 696 1305031125.3488988876 0.0332616940 0.0474580913 0.1140335798 0.0168797855 0.3740150000 0.0836070000 0.0558550000 0.0000000000 0.2314420000 0.0017740000 116965443 0 402718720 3.9055795670 3.8727698326 4.2391285896 697 1305031125.3867919445 0.0320432819 0.0474359754 0.1140335798 0.0168795342 0.6700120000 0.0895910000 0.0646980000 0.0358280000 0.2398620000 0.2387260000 116969339 0 402718720 3.9051134586 3.8708925247 4.2425756454 698 1305031125.4195740223 0.0332034193 0.0474155849 0.1140335798 0.0168690158 0.3698860000 0.0732280000 0.0627880000 0.0000000000 0.2307550000 0.0017790000 116973011 0 402718720 3.9054336548 3.8639349937 4.2456960678 699 1305031125.4512319565 0.0353512727 0.0473983255 0.1140335798 0.0168670194 0.4107340000 0.0849580000 0.0656300000 0.0299520000 0.2270790000 0.0017750000 116976683 0 402718720 3.9025988579 3.8596026897 4.2486615181 700 1305031125.4869990349 0.0377395824 0.0473845273 0.1140335798 0.0168672420 0.3557990000 0.0718720000 0.0549980000 0.0000010000 0.2258200000 0.0017700000 116980467 0 402718720 3.9042203426 3.8488178253 4.2506818771 701 1305031125.5193541050 0.0386733599 0.0473721005 0.1140335798 0.0168618944 0.6422990000 0.0720110000 0.0814680000 0.0298700000 0.2257210000 0.2318880000 116984195 0 402718720 3.9028570652 3.8458299637 4.2531995773 702 1305031125.5510499477 0.0381112732 0.0473589085 0.1140335798 0.0168520873 0.3659090000 0.0905490000 0.0479010000 0.0000010000 0.2243460000 0.0017690000 116987811 0 402718720 3.9042394161 3.8427507877 4.2546515465 703 1305031125.5853030682 0.0378093012 0.0473453244 0.1140335798 0.0168401974 0.3898250000 0.0703760000 0.0643410000 0.0297280000 0.2222730000 0.0017630000 116991539 0 402718720 3.9056956768 3.8399796486 4.2555770874 704 1305031125.6178700924 0.0413531549 0.0473368128 0.1140335798 0.0168493232 0.3752180000 0.0889220000 0.0612470000 0.0000010000 0.2219510000 0.0017440000 116995267 0 402718720 3.9043991566 3.8341965675 4.2551441193 705 1305031125.6505749226 0.0448798649 0.0473333278 0.1140335798 0.0168424213 0.6260890000 0.0843000000 0.0552480000 0.0298380000 0.2246110000 0.2307510000 116998939 0 402718720 3.9030361176 3.8303313255 4.2533521652 706 1305031125.6846020222 0.0432374701 0.0473275263 0.1140335798 0.0168413984 0.3603150000 0.0719770000 0.0558820000 0.0000010000 0.2293400000 0.0017680000 117002611 0 402718720 3.9028742313 3.8345482349 4.2512722015 707 1305031125.7156689167 0.0418001413 0.0473197082 0.1140335798 0.0168588275 0.3921130000 0.0717340000 0.0553870000 0.0294020000 0.2324680000 0.0017750000 117006283 0 402718720 3.9043183327 3.8374691010 4.2492074966 708 1305031125.7512919903 0.0390128046 0.0473079753 0.1140335798 0.0168580532 0.3597490000 0.0716910000 0.0486710000 0.0000010000 0.2362590000 0.0017740000 117010067 0 402718720 3.9068605900 3.8430809975 4.2460250854 709 1305031125.7868049145 0.0358070843 0.0472917540 0.1140335798 0.0168522401 0.6405190000 0.0819440000 0.0494180000 0.0299740000 0.2355490000 0.2422700000 117013851 0 402718720 3.9069926739 3.8526537418 4.2436780930 710 1305031125.8194499016 0.0343144014 0.0472734760 0.1140335798 0.0168438272 0.3955550000 0.0712700000 0.0859290000 0.0000000000 0.2352430000 0.0017530000 117017579 0 402718720 3.9088144302 3.8590180874 4.2402472496 711 1305031125.8547739983 0.0321402811 0.0472521916 0.1140335798 0.0168366754 0.4061660000 0.0721330000 0.0688370000 0.0299800000 0.2321030000 0.0017690000 117021251 0 402718720 3.9092559814 3.8681533337 4.2367191315 712 1305031125.8866450787 0.0368247554 0.0472375464 0.1140335798 0.0168396738 0.3606090000 0.0717520000 0.0549920000 0.0000010000 0.2307480000 0.0017560000 117024979 0 402718720 3.9044463634 3.8759405613 4.2317533493 713 1305031125.9193339348 0.0350327007 0.0472204288 0.1140335798 0.0168381139 0.6276290000 0.0845980000 0.0494280000 0.0299450000 0.2280780000 0.2342420000 117028707 0 402718720 3.9052963257 3.8852915764 4.2294292450 714 1305031125.9552519321 0.0384022184 0.0472080783 0.1140335798 0.0168369172 0.3874320000 0.1056650000 0.0531440000 0.0000010000 0.2254570000 0.0017900000 117032435 0 402718720 3.9044284821 3.8898382187 4.2255864143 715 1305031125.9870939255 0.0391187184 0.0471967645 0.1140335798 0.0168295552 0.3855520000 0.0750990000 0.0510610000 0.0294690000 0.2267770000 0.0017900000 117036107 0 402718720 3.9063801765 3.8990833759 4.2224626541 716 1305031126.0195720196 0.0364998765 0.0471818248 0.1140335798 0.0168219607 0.3918650000 0.0732370000 0.0892550000 0.0000000000 0.2260860000 0.0018550000 117039835 0 402718720 3.9072248936 3.9120690823 4.2201409340 717 1305031126.0550379753 0.0325496793 0.0471614173 0.1140335798 0.0168163668 0.6275870000 0.0751510000 0.0678670000 0.0296270000 0.2235900000 0.2299970000 117043563 0 402718720 3.9123213291 3.9240789413 4.2180953026 718 1305031126.0870759487 0.0343143530 0.0471435245 0.1140335798 0.0168067582 0.3584630000 0.0745100000 0.0638760000 0.0000000000 0.2169470000 0.0017670000 117047235 0 402718720 3.9157338142 3.9354536533 4.2156085968 719 1305031126.1194519997 0.0369108431 0.0471292926 0.1140335798 0.0167967227 0.3625110000 0.0752820000 0.0457520000 0.0301080000 0.2082180000 0.0017770000 117050963 0 402718720 3.9150252342 3.9446387291 4.2130479813 720 1305031126.1549999714 0.0357767344 0.0471135252 0.1140335798 0.0167888960 0.3667840000 0.0886070000 0.0716330000 0.0000000000 0.2033960000 0.0017650000 117054635 0 402718720 3.9185686111 3.9561078548 4.2107157707 721 1305031126.1871740818 0.0395957269 0.0471030983 0.1140335798 0.0167861616 0.5523400000 0.0761140000 0.0420450000 0.0300480000 0.1982790000 0.2044770000 117058363 0 402718720 3.9186480045 3.9687182903 4.2090873718 722 1305031126.2194728851 0.0431888476 0.0470976769 0.1140335798 0.0167896689 0.3286970000 0.0758930000 0.0558090000 0.0000000000 0.1938570000 0.0017560000 117062091 0 402718720 3.9205152988 3.9767904282 4.2066984177 723 1305031126.2552359104 0.0434643924 0.0470926516 0.1140335798 0.0167892536 0.3433410000 0.0762620000 0.0438400000 0.0300430000 0.1900570000 0.0017650000 117065875 0 402718720 3.9225387573 3.9884083271 4.2041363716 724 1305031126.2871050835 0.0478888638 0.0470937513 0.1140335798 0.0167803961 0.3284290000 0.0890060000 0.0512760000 0.0000010000 0.1850040000 0.0017530000 117069491 0 402718720 3.9231553078 3.9996118546 4.2013578415 725 1305031126.3197870255 0.0483226702 0.0470954464 0.1140335798 0.0167731199 0.5597160000 0.0777950000 0.0876010000 0.0294870000 0.1785900000 0.1848470000 117073219 0 402718720 3.9237151146 4.0115723610 4.1991996765 726 1305031126.3554151058 0.0509559996 0.0471007640 0.1140335798 0.0167643144 0.3186790000 0.0780670000 0.0659930000 0.0000010000 0.1714670000 0.0017590000 117076947 0 402718720 3.9234693050 4.0201201439 4.1967263222 727 1305031126.3874828815 0.0554618463 0.0471122648 0.1140335798 0.0167569885 0.3431440000 0.0917910000 0.0520410000 0.0299540000 0.1662120000 0.0017570000 117080675 0 402718720 3.9225134850 4.0297980309 4.1938705444 728 1305031126.4197928905 0.0568305552 0.0471256141 0.1140335798 0.0167467361 0.3387940000 0.0964420000 0.0778020000 0.0000000000 0.1614030000 0.0017430000 117084291 0 402718720 3.9205405712 4.0394430161 4.1914901733 729 1305031126.4553799629 0.0604653843 0.0471439128 0.1140335798 0.0167484015 0.4936540000 0.0958960000 0.0472970000 0.0299710000 0.1564640000 0.1626350000 117088019 0 402718720 3.9217817783 4.0457706451 4.1891899109 730 1305031126.4903860092 0.0664948523 0.0471704209 0.1140335798 0.0167457672 0.3253960000 0.0785150000 0.0895230000 0.0000000000 0.1542240000 0.0017300000 117091803 0 402718720 3.9214198589 4.0532298088 4.1862764359 731 1305031126.5223209858 0.0660569593 0.0471962575 0.1140335798 0.0167441774 0.3438100000 0.0788310000 0.0784980000 0.0299900000 0.1533570000 0.0017470000 117095475 0 402718720 3.9224343300 4.0638661385 4.1837267876 732 1305031126.5582089424 0.0695784837 0.0472268343 0.1140335798 0.0167411457 0.2930760000 0.0788090000 0.0546470000 0.0000010000 0.1564460000 0.0017620000 117099259 0 402718720 3.9238877296 4.0731515884 4.1819710732 733 1305031126.5901761055 0.0726241618 0.0472614828 0.1140335798 0.0167303295 0.5216630000 0.0770480000 0.0934330000 0.0298760000 0.1567350000 0.1631940000 117102931 0 402718720 3.9223046303 4.0792069435 4.1810956001 734 1305031126.6186869144 0.0737887770 0.0472976235 0.1140335798 0.0167194661 0.3381470000 0.0894330000 0.0884320000 0.0000000000 0.1571810000 0.0017350000 117106491 0 402718720 3.9223289490 4.0864892006 4.1795835495 735 1305031126.6544740200 0.0779049620 0.0473392661 0.1140335798 0.0167214032 0.3200900000 0.0777830000 0.0519350000 0.0295170000 0.1577390000 0.0017500000 117110331 0 402718720 3.9235801697 4.0893802643 4.1790952682 736 1305031126.6900219917 0.0824191794 0.0473869291 0.1140335798 0.0167113067 0.3273780000 0.0771130000 0.0889770000 0.0000010000 0.1581920000 0.0017240000 117114115 0 402718720 3.9235920906 4.0934052467 4.1773290634 737 1305031126.7157700062 0.0819806978 0.0474338677 0.1140335798 0.0167009073 0.5198230000 0.0755100000 0.0878890000 0.0297910000 0.1591430000 0.1661290000 117117563 0 402718720 3.9251921177 4.0997281075 4.1751627922 738 1305031126.7553739548 0.0846107826 0.0474842429 0.1140335798 0.0166911289 0.2983260000 0.0761950000 0.0589570000 0.0000010000 0.1600830000 0.0017280000 117121459 0 402718720 3.9240343571 4.1014418602 4.1729750633 739 1305031126.7875649929 0.0845047832 0.0475343384 0.1140335798 0.0166823094 0.3832190000 0.1009170000 0.0881410000 0.0299670000 0.1610810000 0.0017270000 117125131 0 402718720 3.9253125191 4.1068058014 4.1697950363 740 1305031126.8199288845 0.0841398239 0.0475838052 0.1140335798 0.0166740630 0.3092750000 0.0765070000 0.0678830000 0.0000010000 0.1617970000 0.0017280000 117128803 0 402718720 3.9266414642 4.1109733582 4.1674146652 741 1305031126.8583779335 0.0860873461 0.0476357668 0.1140335798 0.0166630695 0.5312400000 0.0769920000 0.0926420000 0.0300020000 0.1613280000 0.1688270000 117132699 0 402718720 3.9279768467 4.1132669449 4.1661791801 742 1305031126.8881540298 0.0867765099 0.0476885172 0.1140335798 0.0166523424 0.3157540000 0.0770810000 0.0733390000 0.0000000000 0.1622400000 0.0017120000 117136315 0 402718720 3.9280078411 4.1146383286 4.1643939018 743 1305031126.9194090366 0.0866018981 0.0477408905 0.1140335798 0.0166419000 0.3206860000 0.0747780000 0.0509650000 0.0292200000 0.1626260000 0.0017270000 117139931 0 402718720 3.9296956062 4.1156926155 4.1628403664 744 1305031126.9555010796 0.0859394372 0.0477922326 0.1140335798 0.0166339159 0.3521250000 0.0985950000 0.0878170000 0.0000010000 0.1626290000 0.0017110000 117143715 0 402718720 3.9296996593 4.1172871590 4.1612672806 745 1305031126.9873158932 0.0872254670 0.0478451631 0.1140335798 0.0166238643 0.5284800000 0.0762170000 0.0877950000 0.0300090000 0.1627260000 0.1703500000 117147443 0 402718720 3.9294500351 4.1160831451 4.1603517532 746 1305031127.0195240974 0.0870325491 0.0478976932 0.1140335798 0.0166134276 0.3267810000 0.0762360000 0.0845270000 0.0000010000 0.1627650000 0.0018190000 117151059 0 402718720 3.9295451641 4.1158342361 4.1594567299 747 1305031127.0533180237 0.0853101835 0.0479477768 0.1140335798 0.0166056358 0.3233780000 0.0761180000 0.0510640000 0.0295030000 0.1635950000 0.0017280000 117154787 0 402718720 3.9319882393 4.1170759201 4.1589841843 748 1305031127.0886490345 0.0835576952 0.0479953837 0.1140335798 0.0165977846 0.3293870000 0.0758660000 0.0867910000 0.0000010000 0.1636400000 0.0017080000 117158571 0 402718720 3.9321305752 4.1173124313 4.1590032578 749 1305031127.1209630966 0.0842014328 0.0480437228 0.1140335798 0.0165941932 0.5355330000 0.0767320000 0.0926560000 0.0301340000 0.1635360000 0.1710890000 117162187 0 402718720 3.9310166836 4.1147236824 4.1590833664 750 1305031127.1576919556 0.0823817402 0.0480895069 0.1140335798 0.0165836878 0.3304960000 0.0756520000 0.0876770000 0.0000000000 0.1640560000 0.0017220000 117166027 0 402718720 3.9285068512 4.1137437820 4.1581902504 751 1305031127.1875000000 0.0801042616 0.0481321364 0.1140335798 0.0165763130 0.3585220000 0.0769120000 0.0844610000 0.0301660000 0.1637160000 0.0018090000 117169643 0 402718720 3.9293394089 4.1142106056 4.1585378647 752 1305031127.2218310833 0.0774162710 0.0481710780 0.1140335798 0.0165680417 0.3345740000 0.0760010000 0.0909510000 0.0000000000 0.1645240000 0.0017120000 117173371 0 402718720 3.9281847477 4.1147842407 4.1581730843 753 1305031127.2597610950 0.0767844543 0.0482090772 0.1140335798 0.0165618801 0.5295920000 0.0765920000 0.0870370000 0.0296200000 0.1638930000 0.1710680000 117177211 0 402718720 3.9262704849 4.1114683151 4.1591773033 754 1305031127.2870380878 0.0745765194 0.0482440473 0.1140335798 0.0165589457 0.3279890000 0.0888700000 0.0726240000 0.0000000000 0.1633800000 0.0017230000 117180715 0 402718720 3.9260909557 4.1112251282 4.1597013474 755 1305031127.3204679489 0.0732035264 0.0482771062 0.1140335798 0.0165492574 0.3577520000 0.0757700000 0.0858330000 0.0300050000 0.1630090000 0.0017240000 117184443 0 402718720 3.9252715111 4.1101646423 4.1608738899 756 1305031127.3534069061 0.0753701255 0.0483129435 0.1140335798 0.0165444843 0.3113560000 0.0767750000 0.0689870000 0.0000010000 0.1623230000 0.0018180000 117188115 0 402718720 3.9259345531 4.1043252945 4.1628556252 757 1305031127.3837130070 0.0729656965 0.0483455099 0.1140335798 0.0165365699 0.5308720000 0.0773960000 0.0905190000 0.0300090000 0.1624210000 0.1691240000 117191787 0 402718720 3.9257898331 4.1044535637 4.1638655663 758 1305031127.4196500778 0.0704557449 0.0483746791 0.1140335798 0.0165270867 0.3063040000 0.0760350000 0.0649150000 0.0000010000 0.1622360000 0.0017190000 117195515 0 402718720 3.9265351295 4.1040701866 4.1654171944 759 1305031127.4542460442 0.0714434460 0.0484050727 0.1140335798 0.0165272761 0.3835560000 0.0974150000 0.0912000000 0.0300700000 0.1617380000 0.0017410000 117199299 0 402718720 3.9260821342 4.1001963615 4.1670870781 760 1305031127.4872000217 0.0692504197 0.0484325008 0.1140335798 0.0165291905 0.3261230000 0.0769360000 0.0724110000 0.0000010000 0.1736560000 0.0017250000 117202971 0 402718720 3.9269559383 4.1003308296 4.1685523987 761 1305031127.5218999386 0.0690559223 0.0484596012 0.1140335798 0.0165188457 0.5186190000 0.0749550000 0.0852480000 0.0292770000 0.1608390000 0.1668890000 117206755 0 402718720 3.9268643856 4.0999436378 4.1706180573 762 1305031127.5537250042 0.0713861808 0.0484896886 0.1140335798 0.0165178294 0.3253630000 0.0758880000 0.0858640000 0.0000010000 0.1604520000 0.0017290000 117210371 0 402718720 3.9258475304 4.0956640244 4.1725158691 763 1305031127.5866320133 0.0705894232 0.0485186529 0.1140335798 0.0165093679 0.3572720000 0.0775110000 0.0866570000 0.0300040000 0.1599430000 0.0017440000 117214099 0 402718720 3.9248595238 4.0952777863 4.1734480858 764 1305031127.6206569672 0.0695175678 0.0485461384 0.1140335798 0.0164992354 0.3133770000 0.0896540000 0.0608850000 0.0000010000 0.1596640000 0.0017240000 117217827 0 402718720 3.9271974564 4.0958509445 4.1750588417 765 1305031127.6546559334 0.0710168406 0.0485755118 0.1140335798 0.0164898573 0.4820320000 0.0749000000 0.0501840000 0.0298320000 0.1596700000 0.1660520000 117221499 0 402718720 3.9268705845 4.0934796333 4.1763005257 766 1305031127.6871099472 0.0710254684 0.0486048199 0.1140335798 0.0164791867 0.3060270000 0.0777300000 0.0653560000 0.0000000000 0.1597680000 0.0017500000 117225227 0 402718720 3.9283258915 4.0915646553 4.1767210960 767 1305031127.7232100964 0.0694876760 0.0486320465 0.1140335798 0.0164707567 0.3351400000 0.0770200000 0.0650310000 0.0299740000 0.1599420000 0.0017360000 117229011 0 402718720 3.9280073643 4.0929484367 4.1773319244 768 1305031127.7546939850 0.0706296042 0.0486606892 0.1140335798 0.0164609961 0.3367920000 0.0880830000 0.0858340000 0.0000010000 0.1597040000 0.0017390000 117232627 0 402718720 3.9271686077 4.0910134315 4.1783437729 769 1305031127.7876410484 0.0705469176 0.0486891498 0.1140335798 0.0164559924 0.5192340000 0.1087970000 0.0536560000 0.0300020000 0.1592830000 0.1660700000 117236411 0 402718720 3.9271655083 4.0890822411 4.1780490875 770 1305031127.8201279640 0.0690976232 0.0487156543 0.1140335798 0.0164473647 0.3072880000 0.0909630000 0.0533470000 0.0000010000 0.1598060000 0.0017350000 117240027 0 402718720 3.9261810780 4.0898294449 4.1778187752 771 1305031127.8551321030 0.0691104382 0.0487421067 0.1140335798 0.0164367025 0.3461230000 0.0748610000 0.0783300000 0.0299780000 0.1597630000 0.0017460000 117243755 0 402718720 3.9261364937 4.0892429352 4.1781797409 772 1305031127.8871219158 0.0694757625 0.0487689638 0.1140335798 0.0164272611 0.3239740000 0.0768450000 0.0841670000 0.0000010000 0.1598090000 0.0017280000 117247483 0 402718720 3.9253215790 4.0877509117 4.1782655716 773 1305031127.9225599766 0.0691253692 0.0487952981 0.1140335798 0.0164189399 0.5189130000 0.0764630000 0.0854310000 0.0299770000 0.1596910000 0.1659270000 117251267 0 402718720 3.9236776829 4.0880379677 4.1785993576 774 1305031127.9550879002 0.0685273409 0.0488207917 0.1140335798 0.0164096365 0.3506580000 0.0973000000 0.0903550000 0.0000010000 0.1596590000 0.0018320000 117254939 0 402718720 3.9250512123 4.0884160995 4.1797852516 775 1305031127.9870929718 0.0681075975 0.0488456779 0.1140335798 0.0163992122 0.3593690000 0.0771250000 0.0841510000 0.0297550000 0.1643690000 0.0023660000 117258611 0 402718720 3.9252212048 4.0878119469 4.1812443733 776 1305031128.0217759609 0.0678432733 0.0488701593 0.1140335798 0.0163916944 0.3602760000 0.0972550000 0.1008090000 0.0000010000 0.1590470000 0.0017250000 117262395 0 402718720 3.9250698090 4.0877308846 4.1830887794 777 1305031128.0557179451 0.0681008995 0.0488949093 0.1140335798 0.0163841632 0.5073940000 0.0756680000 0.0788820000 0.0298590000 0.1577870000 0.1637610000 117266067 0 402718720 3.9248106480 4.0864200592 4.1853709221 778 1305031128.0872058868 0.0700766370 0.0489221352 0.1140335798 0.0163756119 0.2878840000 0.0769610000 0.0508270000 0.0000010000 0.1569130000 0.0017420000 117269739 0 402718720 3.9248344898 4.0832037926 4.1872515678 779 1305031128.1247460842 0.0699172318 0.0489490865 0.1140335798 0.0163662770 0.3336960000 0.0912210000 0.0531260000 0.0299980000 0.1560120000 0.0018070000 117273579 0 402718720 3.9255325794 4.0825047493 4.1886224747 780 1305031128.1577820778 0.0699137896 0.0489759643 0.1140335798 0.0163572179 0.2893820000 0.0769010000 0.0533780000 0.0000010000 0.1559200000 0.0017270000 117277307 0 402718720 3.9272298813 4.0816130638 4.1905245781 781 1305031128.1872210503 0.0712617785 0.0490044993 0.1140335798 0.0163503096 0.5182020000 0.0776460000 0.0917020000 0.0299610000 0.1556000000 0.1618180000 117280867 0 402718720 3.9271712303 4.0788593292 4.1912531853 782 1305031128.2254419327 0.0701202527 0.0490315015 0.1140335798 0.0163450136 0.3268770000 0.0775850000 0.0911130000 0.0000000000 0.1548500000 0.0018120000 117284707 0 402718720 3.9270379543 4.0793905258 4.1914539337 783 1305031128.2560069561 0.0694148764 0.0490575339 0.1140335798 0.0163348250 0.3185480000 0.0771990000 0.0533200000 0.0300040000 0.1548250000 0.0017420000 117288323 0 402718720 3.9268381596 4.0797076225 4.1922168732 784 1305031128.2912750244 0.0704059303 0.0490847640 0.1140335798 0.0163279238 0.3536980000 0.1095390000 0.0859380000 0.0000010000 0.1550400000 0.0017200000 117292107 0 402718720 3.9266805649 4.0779972076 4.1925883293 785 1305031128.3241701126 0.0696256086 0.0491109307 0.1140335798 0.0163182726 0.5109870000 0.0772280000 0.0857940000 0.0299550000 0.1552020000 0.1613680000 117295779 0 402718720 3.9282822609 4.0780916214 4.1925263405 786 1305031128.3552060127 0.0691869855 0.0491364728 0.1140335798 0.0163087458 0.2994970000 0.0766490000 0.0644990000 0.0000010000 0.1551740000 0.0017210000 117299451 0 402718720 3.9273076057 4.0781946182 4.1925148964 787 1305031128.3913969994 0.0694027394 0.0491622241 0.1140335798 0.0162985469 0.3509190000 0.0768630000 0.0858590000 0.0299580000 0.1550390000 0.0017350000 117303235 0 402718720 3.9256482124 4.0772085190 4.1924242973 788 1305031128.4236090183 0.0698186085 0.0491884378 0.1140335798 0.0162883203 0.2795240000 0.0773190000 0.0441490000 0.0000010000 0.1546870000 0.0018380000 117306907 0 402718720 3.9250340462 4.0760073662 4.1923217773 789 1305031128.4554989338 0.0686261505 0.0492130736 0.1140335798 0.0162799707 0.5213490000 0.0878900000 0.0856700000 0.0299210000 0.1551120000 0.1612670000 117310579 0 402718720 3.9243071079 4.0765910149 4.1919131279 790 1305031128.4895229340 0.0691433772 0.0492383019 0.1140335798 0.0162702159 0.3256480000 0.0771130000 0.0904810000 0.0000000000 0.1548420000 0.0017470000 117314363 0 402718720 3.9240746498 4.0753388405 4.1921706200 791 1305031128.5236039162 0.0686732009 0.0492628719 0.1140335798 0.0162601457 0.3181310000 0.0770790000 0.0531870000 0.0299300000 0.1547220000 0.0017430000 117318035 0 402718720 3.9242238998 4.0747566223 4.1920008659 792 1305031128.5556390285 0.0683826506 0.0492870130 0.1140335798 0.0162515922 0.2789290000 0.0770820000 0.0436030000 0.0000010000 0.1550490000 0.0017390000 117321707 0 402718720 3.9255914688 4.0740766525 4.1919646263 793 1305031128.5914599895 0.0691971704 0.0493121204 0.1140335798 0.0162422091 0.5005680000 0.0888820000 0.0651410000 0.0299260000 0.1544860000 0.1606530000 117325491 0 402718720 3.9234426022 4.0724148750 4.1916723251 794 1305031128.6233680248 0.0690075085 0.0493369257 0.1140335798 0.0162326848 0.3125590000 0.0898710000 0.0648440000 0.0000010000 0.1546550000 0.0017280000 117329163 0 402718720 3.9246854782 4.0714697838 4.1913843155 795 1305031128.6555540562 0.0679959506 0.0493603962 0.1140335798 0.0162244636 0.3510010000 0.0766850000 0.0859880000 0.0299210000 0.1552010000 0.0017360000 117332835 0 402718720 3.9249556065 4.0718197823 4.1909351349 796 1305031128.6904489994 0.0677543879 0.0493835042 0.1140335798 0.0162151712 0.3258150000 0.0768840000 0.0898040000 0.0000010000 0.1559580000 0.0016820000 117336619 0 402718720 3.9246501923 4.0715823174 4.1906352043 797 1305031128.7229759693 0.0676164329 0.0494063812 0.1140335798 0.0162058990 0.5130260000 0.0772920000 0.0861530000 0.0299810000 0.1559820000 0.1621290000 117340291 0 402718720 3.9242591858 4.0710334778 4.1902012825 798 1305031128.7546460629 0.0666916445 0.0494280419 0.1140335798 0.0161972676 0.3223510000 0.0772170000 0.0860410000 0.0000000000 0.1558890000 0.0017250000 117343963 0 402718720 3.9236154556 4.0715537071 4.1895537376 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 11:36:38 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019025257 0.0019025257 0.0019025257 -nan 0.8445930000 0.1666560000 0.0218210000 0.0623100000 0.0000020000 0.5899660000 115298278 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 1311867718.6768438816 0.0021839470 0.0020432363 0.0021839470 0.0015734395 0.2143060000 0.1263560000 0.0205900000 0.0629400000 0.0000000000 0.0037170000 134574179 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 1311867718.7114279270 0.0026191149 0.0022351959 0.0026191149 0.0052681691 0.2145570000 0.1272640000 0.0199150000 0.0630460000 0.0000010000 0.0035440000 134578299 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 1311867718.7410299778 0.0032201277 0.0024814288 0.0032201277 0.0047920539 0.7627300000 0.1277160000 0.0199840000 0.0623330000 0.5485120000 0.0036080000 134582259 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 1311867718.7767970562 0.0102639766 0.0040379384 0.0102639766 0.0093924360 1.4589390000 0.1268600000 0.1791110000 0.0623790000 0.5378940000 0.5521310000 134586427 0 402718720 3.9892039299 3.9964058399 4.0032458305 6 1311867718.8094089031 0.0111242970 0.0052189982 0.0111242970 0.0088675249 0.5158650000 0.0738290000 0.0827450000 0.0000010000 0.3569820000 0.0017360000 134590899 0 402718720 3.9877562523 3.9977481365 4.0040669441 7 1311867718.8408079147 0.0115086315 0.0061175172 0.0115086315 0.0081085557 0.5459220000 0.0744050000 0.0834270000 0.0307330000 0.3550430000 0.0017400000 134594515 0 402718720 3.9869382381 3.9982514381 4.0042519569 8 1311867718.8767778873 0.0151464147 0.0072461294 0.0151464147 0.0077096137 0.4882350000 0.0745460000 0.0563120000 0.0000010000 0.3550620000 0.0017380000 134598299 0 402718720 3.9833035469 3.9974732399 4.0047264099 9 1311867718.9088680744 0.0145902839 0.0080621466 0.0151464147 0.0072426746 0.8963480000 0.0746190000 0.0880690000 0.0307790000 0.3485430000 0.3537570000 134602683 0 402718720 3.9835460186 3.9977257252 4.0048494339 10 1311867718.9438331127 0.0158703234 0.0088429642 0.0158703234 0.0068854998 0.5126740000 0.0746980000 0.0846700000 0.0000010000 0.3509770000 0.0017430000 134608067 0 402718720 3.9821383953 3.9979395866 4.0057196617 11 1311867718.9784109592 0.0144189782 0.0093498746 0.0158703234 0.0067737630 0.5366470000 0.0746830000 0.0832620000 0.0307610000 0.3456090000 0.0017470000 134611851 0 402718720 3.9839293957 3.9964618683 4.0056319237 12 1311867719.0091300011 0.0181727726 0.0100851161 0.0181727726 0.0067923139 0.5192020000 0.0875720000 0.0841020000 0.0000010000 0.3451910000 0.0017460000 134615411 0 402718720 3.9798362255 3.9964535236 4.0066075325 13 1311867719.0441620350 0.0168240909 0.0106034988 0.0181727726 0.0065191117 0.9036630000 0.1015190000 0.0810100000 0.0307600000 0.3410350000 0.3487320000 134619195 0 402718720 3.9809789658 3.9964716434 4.0068120956 14 1311867719.0776190758 0.0182064120 0.0111465640 0.0182064120 0.0063271655 0.5040740000 0.0748860000 0.0838430000 0.0000010000 0.3429920000 0.0017620000 134622923 0 402718720 3.9796545506 3.9957454205 4.0073685646 15 1311867719.1086950302 0.0170080140 0.0115373273 0.0182064120 0.0061317170 0.5325380000 0.0752300000 0.0841190000 0.0307390000 0.3401030000 0.0017510000 134626595 0 402718720 3.9809386730 3.9950768948 4.0075154305 16 1311867719.1437010765 0.0179978888 0.0119411124 0.0182064120 0.0059846240 0.4679470000 0.0750520000 0.0520730000 0.0000010000 0.3384780000 0.0017510000 134630323 0 402718720 3.9795103073 3.9950339794 4.0081734657 17 1311867719.1810290813 0.0160211939 0.0121811172 0.0182064120 0.0059238728 0.8627650000 0.0746830000 0.0766410000 0.0307240000 0.3370930000 0.3430270000 134635643 0 402718720 3.9816939831 3.9940829277 4.0082082748 18 1311867719.2127099037 0.0171610210 0.0124577786 0.0182064120 0.0057744203 0.5067070000 0.0841910000 0.0831010000 0.0000000000 0.3370770000 0.0017410000 134642515 0 402718720 3.9803969860 3.9934220314 4.0087184906 19 1311867719.2412090302 0.0176502392 0.0127310660 0.0182064120 0.0057001938 0.5126550000 0.0957940000 0.0520480000 0.0307220000 0.3317370000 0.0017450000 134646075 0 402718720 3.9793717861 3.9936635494 4.0092010498 20 1311867719.2779469490 0.0180034731 0.0129946863 0.0182064120 0.0058521951 0.4983010000 0.0751870000 0.0875560000 0.0000010000 0.3331990000 0.0017520000 134649803 0 402718720 3.9786224365 3.9924826622 4.0094289780 21 1311867719.3104898930 0.0165301897 0.0131630436 0.0182064120 0.0057629057 0.8469880000 0.0734710000 0.0696380000 0.0306770000 0.3330050000 0.3395960000 134653531 0 402718720 3.9797000885 3.9931693077 4.0097084045 22 1311867719.3413150311 0.0174493175 0.0133578742 0.0182064120 0.0056774080 0.4953860000 0.0753320000 0.0838180000 0.0000010000 0.3338760000 0.0017500000 134657203 0 402718720 3.9786593914 3.9920103550 4.0100641251 23 1311867719.3772718906 0.0165978912 0.0134987445 0.0182064120 0.0055641123 0.5218930000 0.0749570000 0.0832960000 0.0307620000 0.3305070000 0.0017590000 134660931 0 402718720 3.9793379307 3.9914212227 4.0097823143 24 1311867719.4105761051 0.0180064049 0.0136865637 0.0182064120 0.0055157017 0.4894350000 0.0734540000 0.0829400000 0.0000010000 0.3306800000 0.0017510000 134664659 0 402718720 3.9775962830 3.9909427166 4.0101928711 25 1311867719.4427709579 0.0165332146 0.0138004298 0.0182064120 0.0055245219 0.8542900000 0.0739550000 0.0830640000 0.0302190000 0.3294690000 0.3369740000 134668387 0 402718720 3.9794437885 3.9902670383 4.0101265907 26 1311867719.4787840843 0.0195068978 0.0140199093 0.0195068978 0.0054485308 0.4730190000 0.0723280000 0.0687210000 0.0000010000 0.3296130000 0.0017440000 134672115 0 402718720 3.9766035080 3.9880232811 4.0103125572 27 1311867719.5104370117 0.0193197690 0.0142162004 0.0195068978 0.0054800318 0.5208320000 0.0750290000 0.0880710000 0.0308670000 0.3244860000 0.0017630000 134675787 0 402718720 3.9766209126 3.9878787994 4.0101666451 28 1311867719.5449650288 0.0181261282 0.0143558407 0.0195068978 0.0054625452 0.4920300000 0.0854340000 0.0700710000 0.0000010000 0.3341390000 0.0017660000 134679515 0 402718720 3.9763913155 3.9887826443 4.0108199120 29 1311867719.5771939754 0.0192381255 0.0145241953 0.0195068978 0.0054267971 0.8322280000 0.0746700000 0.0735950000 0.0303570000 0.3220160000 0.3309700000 134683243 0 402718720 3.9755690098 3.9869921207 4.0107574463 30 1311867719.6112511158 0.0197062865 0.0146969317 0.0197062865 0.0053895018 0.4509580000 0.0747340000 0.0491310000 0.0000010000 0.3247040000 0.0017670000 134686971 0 402718720 3.9746561050 3.9866495132 4.0112013817 31 1311867719.6421909332 0.0170124900 0.0147716271 0.0197062865 0.0053120080 0.5138770000 0.0737150000 0.0829100000 0.0307640000 0.3241130000 0.0017530000 134690587 0 402718720 3.9768860340 3.9875824451 4.0113987923 32 1311867719.6770479679 0.0177945066 0.0148660921 0.0197062865 0.0052396531 0.4620050000 0.0722470000 0.0623800000 0.0000010000 0.3250030000 0.0017500000 134694371 0 402718720 3.9763786793 3.9864048958 4.0119233131 33 1311867719.7107939720 0.0181342177 0.0149651262 0.0197062865 0.0051753100 0.8610050000 0.0873950000 0.0870740000 0.0308800000 0.3222800000 0.3327570000 134701115 0 402718720 3.9754447937 3.9867062569 4.0126104355 34 1311867719.7442650795 0.0175035279 0.0150397851 0.0197062865 0.0051248168 0.4570870000 0.0725830000 0.0584780000 0.0000000000 0.3236480000 0.0017490000 134711187 0 402718720 3.9754066467 3.9876341820 4.0135173798 35 1311867719.7861878872 0.0185586382 0.0151403238 0.0197062865 0.0050561306 0.5164300000 0.0745520000 0.0832280000 0.0308020000 0.3254660000 0.0017520000 134715195 0 402718720 3.9745199680 3.9866864681 4.0141363144 36 1311867719.8099169731 0.0188596006 0.0152436370 0.0197062865 0.0049994949 0.4873600000 0.0748840000 0.0836890000 0.0000010000 0.3263960000 0.0017610000 134718587 0 402718720 3.9742028713 3.9862155914 4.0144858360 37 1311867719.8454990387 0.0192699078 0.0153524551 0.0197062865 0.0049778978 0.8409610000 0.0745210000 0.0832490000 0.0308750000 0.3210060000 0.3306740000 134722371 0 402718720 3.9744448662 3.9849376678 4.0145311356 38 1311867719.8771090508 0.0189867038 0.0154480933 0.0197062865 0.0049127426 0.5358610000 0.0946980000 0.1111260000 0.0000010000 0.3276420000 0.0017580000 134726043 0 402718720 3.9743826389 3.9848151207 4.0147142410 39 1311867719.9114089012 0.0185453407 0.0155275099 0.0197062865 0.0049253158 0.4863050000 0.0739550000 0.0588270000 0.0308790000 0.3201090000 0.0018420000 134729827 0 402718720 3.9736621380 3.9853322506 4.0152688026 40 1311867719.9461970329 0.0213935655 0.0156741613 0.0213935655 0.0049157944 0.4591330000 0.0747940000 0.0596620000 0.0000010000 0.3222670000 0.0017720000 134733555 0 402718720 3.9712667465 3.9833316803 4.0159001350 41 1311867719.9807810783 0.0209206399 0.0158021241 0.0213935655 0.0048699853 0.8186560000 0.0751020000 0.0594320000 0.0305090000 0.3202720000 0.3327120000 134737283 0 402718720 3.9723341465 3.9823818207 4.0158901215 42 1311867720.0117020607 0.0210047122 0.0159259953 0.0213935655 0.0048946576 0.4647420000 0.0753480000 0.0636790000 0.0000000000 0.3232950000 0.0017810000 134740955 0 402718720 3.9701304436 3.9838922024 4.0166597366 43 1311867720.0452380180 0.0216359477 0.0160587849 0.0216359477 0.0048704926 0.5311770000 0.0868550000 0.0892580000 0.0309750000 0.3216550000 0.0017900000 134744627 0 402718720 3.9691481590 3.9833133221 4.0169482231 44 1311867720.0772819519 0.0181093439 0.0161053885 0.0216359477 0.0048609162 0.4860840000 0.0750740000 0.0845480000 0.0000010000 0.3240380000 0.0017780000 134748355 0 402718720 3.9732904434 3.9842035770 4.0174307823 45 1311867720.1172130108 0.0164454896 0.0161129463 0.0216359477 0.0048379310 0.8469940000 0.0734130000 0.0829680000 0.0309430000 0.3229360000 0.3360990000 134752251 0 402718720 3.9763367176 3.9841914177 4.0178818703 46 1311867720.1451559067 0.0173381940 0.0161395821 0.0216359477 0.0047873637 0.4478690000 0.0732820000 0.0488600000 0.0000010000 0.3233190000 0.0017610000 134755755 0 402718720 3.9753630161 3.9837996960 4.0184249878 47 1311867720.1781630516 0.0153385485 0.0161225388 0.0216359477 0.0047449647 0.5085580000 0.0713310000 0.0814900000 0.0302800000 0.3230630000 0.0017440000 134759427 0 402718720 3.9773890972 3.9852161407 4.0188970566 48 1311867720.2094950676 0.0165937468 0.0161323557 0.0216359477 0.0047394391 0.4650100000 0.0843060000 0.0566670000 0.0000000000 0.3216360000 0.0017430000 134763099 0 402718720 3.9739885330 3.9859333038 4.0197954178 49 1311867720.2421469688 0.0136901392 0.0160825145 0.0216359477 0.0047384775 0.8677790000 0.0969680000 0.0830020000 0.0309940000 0.3211880000 0.3349720000 134766827 0 402718720 3.9783506393 3.9870285988 4.0200057030 50 1311867720.2770779133 0.0157336965 0.0160755382 0.0216359477 0.0047301456 0.4816100000 0.0736460000 0.0830600000 0.0000010000 0.3224980000 0.0017490000 134770555 0 402718720 3.9760117531 3.9861192703 4.0211911201 51 1311867720.3094570637 0.0124950744 0.0160053330 0.0216359477 0.0047060371 0.4996530000 0.0742270000 0.0741980000 0.0306140000 0.3181910000 0.0017610000 134774227 0 402718720 3.9798092842 3.9883577824 4.0219063759 52 1311867720.3430728912 0.0131311305 0.0159500599 0.0216359477 0.0047561825 0.4820970000 0.0748270000 0.0842760000 0.0000010000 0.3205700000 0.0017640000 134777955 0 402718720 3.9789657593 3.9888246059 4.0232038498 53 1311867720.3779859543 0.0137955090 0.0159094080 0.0216359477 0.0048139689 0.8458120000 0.0757210000 0.0894660000 0.0311310000 0.3170190000 0.3317590000 134781627 0 402718720 3.9817018509 3.9870052338 4.0234551430 54 1311867720.4096798897 0.0142790340 0.0158792159 0.0216359477 0.0048841922 0.4846000000 0.0763970000 0.0856180000 0.0000010000 0.3201350000 0.0017820000 134785299 0 402718720 3.9812800884 3.9865677357 4.0241260529 55 1311867720.4461109638 0.0135359317 0.0158366107 0.0216359477 0.0048474861 0.4971720000 0.0745150000 0.0700870000 0.0311530000 0.3189940000 0.0017560000 134789139 0 402718720 3.9823596478 3.9874341488 4.0244932175 56 1311867720.4799289703 0.0137455314 0.0157992700 0.0216359477 0.0048636026 0.4724500000 0.0740190000 0.0767320000 0.0000010000 0.3192830000 0.0017510000 134792867 0 402718720 3.9837777615 3.9872305393 4.0244631767 57 1311867720.5104389191 0.0135736410 0.0157602239 0.0216359477 0.0049154982 0.7926950000 0.0731390000 0.0352580000 0.0310410000 0.3183830000 0.3342190000 134796483 0 402718720 3.9824056625 3.9867978096 4.0242986679 58 1311867720.5467319489 0.0142166140 0.0157336099 0.0216359477 0.0050272079 0.4539110000 0.0748990000 0.0594060000 0.0000000000 0.3171880000 0.0017490000 134800323 0 402718720 3.9857499599 3.9875555038 4.0246038437 59 1311867720.5793280602 0.0140508655 0.0157050888 0.0216359477 0.0050732592 0.4983200000 0.0836760000 0.0630170000 0.0312790000 0.3179150000 0.0017550000 134803995 0 402718720 3.9837586880 3.9867560863 4.0251312256 60 1311867720.6121249199 0.0149729792 0.0156928870 0.0216359477 0.0050525477 0.4532760000 0.0748640000 0.0593760000 0.0000010000 0.3166160000 0.0017470000 134807667 0 402718720 3.9847555161 3.9862630367 4.0251531601 61 1311867720.6463210583 0.0151072014 0.0156832856 0.0216359477 0.0050389992 0.8347730000 0.0743540000 0.0768630000 0.0313270000 0.3170470000 0.3345210000 134811451 0 402718720 3.9846062660 3.9864475727 4.0256304741 62 1311867720.6798269749 0.0166617166 0.0156990667 0.0216359477 0.0050294622 0.4782670000 0.0742390000 0.0839510000 0.0000010000 0.3176510000 0.0017490000 134815067 0 402718720 3.9870893955 3.9862616062 4.0256276131 63 1311867720.7102439404 0.0169777386 0.0157193631 0.0216359477 0.0049944781 0.5120180000 0.0748530000 0.0883100000 0.0315360000 0.3147210000 0.0018600000 134818739 0 402718720 3.9856936932 3.9851374626 4.0256991386 64 1311867720.7451629639 0.0167082883 0.0157348151 0.0216359477 0.0049999560 0.4818440000 0.0737210000 0.0878530000 0.0000010000 0.3178480000 0.0017390000 134822467 0 402718720 3.9854934216 3.9857342243 4.0256805420 65 1311867720.7790179253 0.0581989288 0.0163881091 0.0581989288 0.0061941604 0.8468590000 0.0731720000 0.0830010000 0.0315030000 0.3181380000 0.3403680000 134832395 0 402718720 4.0315556526 3.9882464409 4.0336537361 66 1311867720.8115909100 0.0585793070 0.0170273697 0.0585793070 0.0061469823 0.4773940000 0.0723770000 0.0824900000 0.0000010000 0.3201030000 0.0017360000 134848867 0 402718720 4.0310993195 3.9874367714 4.0340332985 67 1311867720.8467299938 0.0618567094 0.0176964643 0.0618567094 0.0061143812 0.5217720000 0.0866470000 0.0823180000 0.0312050000 0.3191750000 0.0017390000 134852651 0 402718720 4.0341124535 3.9881896973 4.0344309807 68 1311867720.8813319206 0.0603026263 0.0183230255 0.0618567094 0.0061203353 0.4582170000 0.0855790000 0.0495620000 0.0000010000 0.3206590000 0.0017230000 134856379 0 402718720 4.0321674347 3.9887318611 4.0349125862 69 1311867720.9149661064 0.0613572076 0.0189467093 0.0618567094 0.0060825500 0.8542110000 0.0736360000 0.0826980000 0.0312100000 0.3210010000 0.3449880000 134860051 0 402718720 4.0324754715 3.9873766899 4.0352802277 70 1311867720.9500010014 0.0598262288 0.0195307025 0.0618567094 0.0060461517 0.4679790000 0.0736760000 0.0688320000 0.0000010000 0.3230560000 0.0017240000 134863779 0 402718720 4.0305304527 3.9878334999 4.0358734131 71 1311867720.9797990322 0.0623859949 0.0201342981 0.0623859949 0.0060187651 0.5244100000 0.0861120000 0.0819080000 0.0316910000 0.3222790000 0.0017240000 134867339 0 402718720 4.0330834389 3.9880812168 4.0357470512 72 1311867721.0093889236 0.0640341714 0.0207440186 0.0640341714 0.0059803902 0.4536640000 0.0732130000 0.0550390000 0.0000000000 0.3229940000 0.0017230000 134870955 0 402718720 4.0345811844 3.9879364967 4.0360088348 73 1311867721.0478379726 0.0626609921 0.0213182237 0.0640341714 0.0059469699 0.8693730000 0.0839660000 0.0821040000 0.0313230000 0.3232290000 0.3480670000 134874851 0 402718720 4.0328111649 3.9879713058 4.0359911919 74 1311867721.0794439316 0.0641731620 0.0218973445 0.0641731620 0.0059156357 0.4844940000 0.0728360000 0.0863720000 0.0000010000 0.3228640000 0.0017190000 134878467 0 402718720 4.0340189934 3.9873864651 4.0362267494 75 1311867721.1103579998 0.0598739833 0.0224036997 0.0641731620 0.0059072498 0.5142760000 0.0733250000 0.0818600000 0.0314060000 0.3252540000 0.0017280000 134882139 0 402718720 4.0289902687 3.9869568348 4.0363845825 76 1311867721.1467890739 0.0626415387 0.0229331449 0.0641731620 0.0059077328 0.5014270000 0.0863470000 0.0863500000 0.0000010000 0.3263050000 0.0017200000 134885923 0 402718720 4.0311250687 3.9866235256 4.0363626480 77 1311867721.1774179935 0.0625633523 0.0234478229 0.0641731620 0.0059530324 0.8538180000 0.0737600000 0.0687350000 0.0318990000 0.3262830000 0.3524560000 134889595 0 402718720 4.0309786797 3.9863207340 4.0365529060 78 1311867721.2112360001 0.0610255226 0.0239295883 0.0641731620 0.0059213972 0.4972060000 0.0842530000 0.0823340000 0.0000010000 0.3281900000 0.0017200000 134893267 0 402718720 4.0289111137 3.9862134457 4.0367598534 79 1311867721.2469010353 0.0646424964 0.0244449416 0.0646424964 0.0059063605 0.5433360000 0.0942500000 0.0865240000 0.0320840000 0.3280360000 0.0017300000 134897051 0 402718720 4.0325098038 3.9859762192 4.0366997719 80 1311867721.2800450325 0.0634045154 0.0249319363 0.0646424964 0.0058689720 0.4669740000 0.0720450000 0.0645470000 0.0000010000 0.3278260000 0.0017920000 134900723 0 402718720 4.0303478241 3.9849503040 4.0369000435 81 1311867721.3099579811 0.0681402683 0.0254653725 0.0681402683 0.0058739025 0.8794710000 0.0736690000 0.0862190000 0.0316750000 0.3278740000 0.3593490000 134904339 0 402718720 4.0351285934 3.9851276875 4.0370888710 82 1311867721.3483059406 0.0669542626 0.0259713345 0.0681402683 0.0058643924 0.4719120000 0.0844100000 0.0482620000 0.0000000000 0.3362290000 0.0022750000 134908179 0 402718720 4.0334548950 3.9852459431 4.0370163918 83 1311867721.3790040016 0.0673267171 0.0264695922 0.0681402683 0.0058320672 0.5533570000 0.0937200000 0.0919860000 0.0321300000 0.3330830000 0.0017270000 134911739 0 402718720 4.0332708359 3.9850890636 4.0371966362 84 1311867721.4092550278 0.0654952005 0.0269341827 0.0681402683 0.0058169153 0.4934740000 0.0737830000 0.0822730000 0.0000010000 0.3350190000 0.0016870000 134915355 0 402718720 4.0304937363 3.9845628738 4.0377545357 85 1311867721.4478130341 0.0686860085 0.0274253807 0.0686860085 0.0057914776 0.8868350000 0.0734210000 0.0817130000 0.0316420000 0.3350510000 0.3642980000 134919307 0 402718720 4.0331788063 3.9842457771 4.0381736755 86 1311867721.4768960476 0.0705027357 0.0279262802 0.0705027357 0.0057598039 0.4994590000 0.0741690000 0.0867710000 0.0000010000 0.3360800000 0.0017290000 134922867 0 402718720 4.0347113609 3.9845588207 4.0385270119 87 1311867721.5093359947 0.0708062872 0.0284191538 0.0708062872 0.0057359534 0.5282020000 0.0746110000 0.0818150000 0.0324140000 0.3369160000 0.0017270000 134926483 0 402718720 4.0346002579 3.9842684269 4.0384254456 88 1311867721.5451331139 0.0675341189 0.0288636420 0.0708062872 0.0057375261 0.4998480000 0.0874960000 0.0711910000 0.0000000000 0.3387410000 0.0016890000 134930211 0 402718720 4.0302090645 3.9832980633 4.0387530327 89 1311867721.5769670010 0.0675496310 0.0292983161 0.0708062872 0.0057149775 0.9167710000 0.0947920000 0.0816010000 0.0318710000 0.3388610000 0.3689270000 134933771 0 402718720 4.0300626755 3.9836139679 4.0386295319 90 1311867721.6129651070 0.0689675137 0.0297390849 0.0708062872 0.0057145826 0.4989620000 0.0730730000 0.0856660000 0.0000010000 0.3377810000 0.0017120000 134937499 0 402718720 4.0309715271 3.9833273888 4.0386948586 91 1311867721.6496050358 0.0691311434 0.0301719647 0.0708062872 0.0057207712 0.5342520000 0.0735350000 0.0859150000 0.0319800000 0.3403880000 0.0017160000 134941339 0 402718720 4.0303649902 3.9820299149 4.0385127068 92 1311867721.6800351143 0.0685424656 0.0305890354 0.0708062872 0.0057304508 0.5198290000 0.0856440000 0.0818060000 0.0000000000 0.3493600000 0.0022690000 134944955 0 402718720 4.0297741890 3.9836955070 4.0386853218 93 1311867721.7162289619 0.0684701651 0.0309963593 0.0708062872 0.0057247563 0.8920930000 0.0936040000 0.0533920000 0.0323830000 0.3409520000 0.3710520000 134948795 0 402718720 4.0294923782 3.9834852219 4.0388717651 94 1311867721.7467949390 0.0697930604 0.0314090902 0.0708062872 0.0057479864 0.5055520000 0.0744420000 0.0864480000 0.0000010000 0.3422040000 0.0017220000 134952411 0 402718720 4.0294537544 3.9810097218 4.0387749672 95 1311867721.7787001133 0.0727553144 0.0318443136 0.0727553144 0.0057320442 0.5256130000 0.0729200000 0.0749890000 0.0325560000 0.3426840000 0.0017240000 134956083 0 402718720 4.0327353477 3.9823002815 4.0392737389 96 1311867721.8154830933 0.0715582445 0.0322580004 0.0727553144 0.0057054800 0.4686980000 0.0737890000 0.0481170000 0.0000000000 0.3443400000 0.0017160000 134959867 0 402718720 4.0307598114 3.9818921089 4.0392913818 97 1311867721.8485159874 0.0723726079 0.0326715531 0.0727553144 0.0056810583 0.9036270000 0.0722460000 0.0804810000 0.0323180000 0.3442200000 0.3736410000 134963595 0 402718720 4.0307621956 3.9806585312 4.0391874313 98 1311867721.8778810501 0.0704092085 0.0330566312 0.0727553144 0.0056658638 0.5213960000 0.0885330000 0.0862170000 0.0000010000 0.3441950000 0.0017100000 134967211 0 402718720 4.0285758972 3.9817311764 4.0391111374 99 1311867721.9146931171 0.0703125522 0.0334329536 0.0727553144 0.0056407050 0.5012900000 0.0739840000 0.0479890000 0.0325840000 0.3442630000 0.0017250000 134970771 0 402718720 4.0278387070 3.9808745384 4.0388593674 100 1311867721.9467151165 0.0707983524 0.0338066076 0.0727553144 0.0056143268 0.5049110000 0.0740920000 0.0857280000 0.0000010000 0.3426460000 0.0017030000 134974443 0 402718720 4.0277066231 3.9801528454 4.0387492180 101 1311867721.9773728848 0.0695357695 0.0341603617 0.0727553144 0.0056167607 0.9133490000 0.0737600000 0.0855870000 0.0326960000 0.3446840000 0.3758940000 134978115 0 402718720 4.0262446404 3.9804461002 4.0386013985 102 1311867722.0166850090 0.0721758530 0.0345330626 0.0727553144 0.0056547660 0.4855160000 0.0739960000 0.0615820000 0.0000000000 0.3474850000 0.0017050000 134981843 0 402718720 4.0285978317 3.9799981117 4.0384569168 103 1311867722.0475180149 0.0718446821 0.0348953113 0.0727553144 0.0056651020 0.5079680000 0.0858090000 0.0434070000 0.0327000000 0.3435910000 0.0017100000 134985347 0 402718720 4.0280938148 3.9795286655 4.0381584167 104 1311867722.0800709724 0.0733958483 0.0352655088 0.0733958483 0.0056522864 0.4986240000 0.0733670000 0.0746330000 0.0000010000 0.3481770000 0.0016970000 134989075 0 402718720 4.0292978287 3.9790666103 4.0382075310 105 1311867722.1161251068 0.0743490607 0.0356377331 0.0743490607 0.0056320294 0.9199630000 0.0740480000 0.0858420000 0.0328010000 0.3475510000 0.3789870000 134992859 0 402718720 4.0293722153 3.9777681828 4.0381560326 106 1311867722.1479530334 0.0736166537 0.0359960248 0.0743490607 0.0056244825 0.5081870000 0.0739540000 0.0817090000 0.0000010000 0.3500630000 0.0017110000 134996475 0 402718720 4.0277843475 3.9772522449 4.0382041931 107 1311867722.1798410416 0.0716845170 0.0363295621 0.0743490607 0.0056154888 0.5410780000 0.0738830000 0.0811700000 0.0328380000 0.3507290000 0.0017100000 135000147 0 402718720 4.0257611275 3.9785532951 4.0379939079 108 1311867722.2146399021 0.0719716996 0.0366595819 0.0743490607 0.0056090094 0.5409460000 0.1090800000 0.0781840000 0.0000010000 0.3512180000 0.0017050000 135003931 0 402718720 4.0251989365 3.9768896103 4.0380778313 109 1311867722.2469589710 0.0735663772 0.0369981763 0.0743490607 0.0055863396 0.9215970000 0.0730110000 0.0803280000 0.0328070000 0.3517250000 0.3829890000 135007603 0 402718720 4.0267429352 3.9766960144 4.0380635262 110 1311867722.2780389786 0.0717215836 0.0373138437 0.0743490607 0.0055677108 0.5188020000 0.0837010000 0.0802100000 0.0000000000 0.3524340000 0.0017000000 135011275 0 402718720 4.0248918533 3.9778954983 4.0381197929 111 1311867722.3154170513 0.0733281374 0.0376382968 0.0743490607 0.0055507968 0.5463030000 0.0731350000 0.0847790000 0.0329920000 0.3529300000 0.0017040000 135015059 0 402718720 4.0259261131 3.9763560295 4.0382766724 112 1311867722.3488469124 0.0755851492 0.0379771079 0.0755851492 0.0055368694 0.4851810000 0.0736010000 0.0545160000 0.0000010000 0.3546020000 0.0017080000 135018731 0 402718720 4.0278515816 3.9755218029 4.0386199951 113 1311867722.3777940273 0.0725214928 0.0382828105 0.0755851492 0.0055390327 0.9348920000 0.0841950000 0.0845610000 0.0330010000 0.3495470000 0.3828360000 135022347 0 402718720 4.0250787735 3.9769146442 4.0380492210 114 1311867722.4150679111 0.0767886788 0.0386205812 0.0767886788 0.0055517457 0.4928240000 0.0720610000 0.0635240000 0.0000010000 0.3547780000 0.0017010000 135025963 0 402718720 4.0285539627 3.9747929573 4.0389194489 115 1311867722.4467909336 0.0743040740 0.0389308725 0.0767886788 0.0056175562 0.5455810000 0.0731530000 0.0806710000 0.0328630000 0.3564210000 0.0017060000 135029635 0 402718720 4.0251584053 3.9742147923 4.0388755798 116 1311867722.4777851105 0.0745281652 0.0392377457 0.0767886788 0.0056339494 0.5155080000 0.0736720000 0.0810380000 0.0000000000 0.3583340000 0.0017030000 135033251 0 402718720 4.0254573822 3.9751083851 4.0391516685 117 1311867722.5147399902 0.0784460083 0.0395728591 0.0784460083 0.0056199882 0.9652300000 0.0970370000 0.0848420000 0.0331750000 0.3584180000 0.3909980000 135036979 0 402718720 4.0292730331 3.9744145870 4.0399079323 118 1311867722.5469911098 0.0726754069 0.0398533891 0.0784460083 0.0056612573 0.5442130000 0.0978880000 0.0848290000 0.0000010000 0.3590300000 0.0016980000 135040651 0 402718720 4.0223970413 3.9740660191 4.0393037796 119 1311867722.5802359581 0.0763219148 0.0401598473 0.0784460083 0.0056569520 0.5482560000 0.0730410000 0.0840790000 0.0331470000 0.3553640000 0.0017960000 135044323 0 402718720 4.0261774063 3.9733877182 4.0398674011 120 1311867722.6146309376 0.0753286034 0.0404529203 0.0784460083 0.0056362276 0.5163840000 0.0706460000 0.0818950000 0.0000010000 0.3613880000 0.0016890000 135048051 0 402718720 4.0248942375 3.9729218483 4.0394845009 121 1311867722.6560258865 0.0755310357 0.0407428221 0.0784460083 0.0056167818 0.9167170000 0.0726160000 0.0534070000 0.0329420000 0.3619830000 0.3950040000 135052003 0 402718720 4.0246057510 3.9722170830 4.0396637917 122 1311867722.6778230667 0.0762367547 0.0410337559 0.0784460083 0.0056005766 0.5167020000 0.0712840000 0.0788800000 0.0000010000 0.3640690000 0.0016980000 135055451 0 402718720 4.0250196457 3.9717392921 4.0399308205 123 1311867722.7252709866 0.0732432306 0.0412956216 0.0784460083 0.0056000891 0.5614370000 0.0830140000 0.0791330000 0.0331270000 0.3636900000 0.0016890000 135059515 0 402718720 4.0214877129 3.9715967178 4.0391626358 124 1311867722.7449109554 0.0757240430 0.0415732701 0.0784460083 0.0055902011 0.5130840000 0.0722120000 0.0728600000 0.0000010000 0.3655530000 0.0016850000 135062795 0 402718720 4.0242042542 3.9711065292 4.0391330719 125 1311867722.7770080566 0.0742906854 0.0418350095 0.0784460083 0.0056305269 0.9527620000 0.0860090000 0.0668140000 0.0331710000 0.3660730000 0.3999240000 135066523 0 402718720 4.0220241547 3.9711656570 4.0391979218 126 1311867722.8162860870 0.0743420571 0.0420930019 0.0784460083 0.0056081450 0.5528000000 0.1013410000 0.0803480000 0.0000000000 0.3686270000 0.0016970000 135070307 0 402718720 4.0218205452 3.9711797237 4.0393657684 127 1311867722.8466939926 0.0790914446 0.0423843282 0.0790914446 0.0056341985 0.5389820000 0.0728460000 0.0630580000 0.0332850000 0.3673160000 0.0016980000 135073923 0 402718720 4.0254597664 3.9688370228 4.0407457352 128 1311867722.8819770813 0.0782341585 0.0426644050 0.0790914446 0.0056128997 0.5223160000 0.0731350000 0.0763190000 0.0000000000 0.3703980000 0.0016860000 135077707 0 402718720 4.0234322548 3.9681875706 4.0411596298 129 1311867722.9150629044 0.0793106556 0.0429484845 0.0793106556 0.0056128454 0.9611480000 0.0719400000 0.0782400000 0.0332740000 0.3710850000 0.4058380000 135093499 0 402718720 4.0249252319 3.9704840183 4.0418496132 130 1311867722.9485991001 0.0804489926 0.0432369499 0.0804489926 0.0056261620 0.5254970000 0.0718930000 0.0783450000 0.0000010000 0.3728080000 0.0016680000 135122883 0 402718720 4.0245771408 3.9676332474 4.0423064232 131 1311867722.9821140766 0.0830817223 0.0435411085 0.0830817223 0.0056062335 0.5406500000 0.0728380000 0.0594460000 0.0333930000 0.3725030000 0.0016850000 135126555 0 402718720 4.0260453224 3.9666864872 4.0442924500 132 1311867723.0147259235 0.0830559805 0.0438404636 0.0830817223 0.0055873386 0.5301620000 0.0733480000 0.0833920000 0.0000000000 0.3709550000 0.0016710000 135130227 0 402718720 4.0269498825 3.9689376354 4.0441684723 133 1311867723.0460629463 0.0865237638 0.0441613907 0.0865237638 0.0056039387 0.9576710000 0.0730780000 0.0626280000 0.0335150000 0.3708800000 0.4167870000 135133843 0 402718720 4.0286607742 3.9664781094 4.0459003448 134 1311867723.0845439434 0.0896397009 0.0445007810 0.0896397009 0.0056003224 0.5269600000 0.0717610000 0.0784130000 0.0000010000 0.3743210000 0.0016720000 135137683 0 402718720 4.0313777924 3.9655387402 4.0462536812 135 1311867723.1140980721 0.0907444060 0.0448433264 0.0907444060 0.0055816017 0.5606030000 0.0725040000 0.0785630000 0.0334180000 0.3736500000 0.0016770000 135141299 0 402718720 4.0318384171 3.9654674530 4.0470786095 136 1311867723.1505160332 0.0936199427 0.0452019780 0.0936199427 0.0055707289 0.4990200000 0.0732790000 0.0492480000 0.0000010000 0.3740200000 0.0016700000 135145083 0 402718720 4.0334014893 3.9636635780 4.0480732918 137 1311867723.1811029911 0.0946209282 0.0455627003 0.0946209282 0.0055522843 0.9531040000 0.0735870000 0.0630440000 0.0332590000 0.3727870000 0.4096490000 135148699 0 402718720 4.0333337784 3.9623692036 4.0483293533 138 1311867723.2201359272 0.0953498110 0.0459234764 0.0953498110 0.0055326575 0.5267230000 0.0948820000 0.0557090000 0.0000010000 0.3736500000 0.0016810000 135152539 0 402718720 4.0337209702 3.9623498917 4.0484924316 139 1311867723.2486810684 0.0993830115 0.0463080774 0.0993830115 0.0055302654 0.5626010000 0.0722860000 0.0779660000 0.0334680000 0.3764240000 0.0016640000 135156099 0 402718720 4.0374326706 3.9613885880 4.0491881371 140 1311867723.2846419811 0.0880771652 0.0466064280 0.0993830115 0.0055519082 0.4995570000 0.0724830000 0.0488540000 0.0000000000 0.3757500000 0.0016660000 135159883 0 402718720 4.0250625610 3.9617669582 4.0456242561 141 1311867723.3132460117 0.0898199081 0.0469129066 0.0993830115 0.0055362105 0.9620360000 0.0730310000 0.0644740000 0.0336220000 0.3776080000 0.4125130000 135163443 0 402718720 4.0262856483 3.9608070850 4.0460972786 142 1311867723.3499810696 0.0901664644 0.0472175091 0.0993830115 0.0055247945 0.5590610000 0.0861870000 0.0789880000 0.0000010000 0.3908530000 0.0021970000 135167283 0 402718720 4.0259747505 3.9608600140 4.0466895103 143 1311867723.3822429180 0.0917553231 0.0475289624 0.0993830115 0.0055123508 0.5663740000 0.0909430000 0.0528790000 0.0405700000 0.3795020000 0.0016800000 135171011 0 402718720 4.0275492668 3.9606335163 4.0468149185 144 1311867723.4193739891 0.0927517712 0.0478430097 0.0993830115 0.0055234723 0.4988660000 0.0699420000 0.0477130000 0.0000010000 0.3787410000 0.0016620000 135174795 0 402718720 4.0280575752 3.9598696232 4.0480542183 145 1311867723.4455900192 0.0915084705 0.0481441508 0.0993830115 0.0055110672 0.9651320000 0.0715570000 0.0652310000 0.0335730000 0.3794530000 0.4145240000 135178299 0 402718720 4.0269670486 3.9608089924 4.0473742485 146 1311867723.4825348854 0.0941275433 0.0484591055 0.0993830115 0.0055033891 0.5331610000 0.0722760000 0.0781310000 0.0000010000 0.3802790000 0.0016710000 135182139 0 402718720 4.0282630920 3.9599542618 4.0486721992 147 1311867723.5147960186 0.0963261276 0.0487847315 0.0993830115 0.0054867767 0.5543590000 0.0725320000 0.0651200000 0.0336300000 0.3805960000 0.0016730000 135185755 0 402718720 4.0299096107 3.9595541954 4.0495495796 148 1311867723.5451340675 0.0964968875 0.0491071109 0.0993830115 0.0054699325 0.5323460000 0.0954050000 0.0556500000 0.0000010000 0.3787980000 0.0016820000 135189427 0 402718720 4.0293817520 3.9594771862 4.0499124527 149 1311867723.5809938908 0.0990928560 0.0494425857 0.0993830115 0.0054602896 0.9604670000 0.0721260000 0.0553230000 0.0338510000 0.3814790000 0.4168920000 135193211 0 402718720 4.0312161446 3.9585578442 4.0506486893 150 1311867723.6132669449 0.1010076553 0.0497863529 0.1010076553 0.0054459012 0.5398410000 0.0727850000 0.0817330000 0.0000010000 0.3828370000 0.0016710000 135196939 0 402718720 4.0332279205 3.9589793682 4.0511407852 151 1311867723.6453940868 0.1000865474 0.0501194667 0.1010076553 0.0054285715 0.5789370000 0.0828410000 0.0772710000 0.0336740000 0.3826610000 0.0016730000 135200555 0 402718720 4.0327596664 3.9600849152 4.0503306389 152 1311867723.6809489727 0.1016360298 0.0504583915 0.1016360298 0.0054136250 0.5023760000 0.0708350000 0.0457400000 0.0000010000 0.3833180000 0.0016710000 135204339 0 402718720 4.0335326195 3.9587459564 4.0507779121 153 1311867723.7130429745 0.1043126881 0.0508103804 0.1043126881 0.0053976586 0.9855430000 0.1058990000 0.0481670000 0.0338800000 0.3784910000 0.4183020000 135208011 0 402718720 4.0355138779 3.9579782486 4.0520982742 154 1311867723.7471990585 0.1048087254 0.0511610190 0.1048087254 0.0053820992 0.5387760000 0.0716940000 0.0821640000 0.0000010000 0.3824260000 0.0016700000 135211739 0 402718720 4.0362429619 3.9584984779 4.0515031815 155 1311867723.7809250355 0.1063067093 0.0515167976 0.1063067093 0.0053695390 0.5330500000 0.0727840000 0.0397470000 0.0339050000 0.3841190000 0.0016740000 135215467 0 402718720 4.0368895531 3.9570136070 4.0513491631 156 1311867723.8157649040 0.1083554700 0.0518811481 0.1083554700 0.0053584769 0.5317430000 0.0724170000 0.0715160000 0.0000010000 0.3853060000 0.0016780000 135219195 0 402718720 4.0385131836 3.9564290047 4.0511641502 157 1311867723.8468959332 0.1091133058 0.0522456841 0.1091133058 0.0053431517 0.9615770000 0.0728770000 0.0483590000 0.0340670000 0.3840770000 0.4213900000 135222867 0 402718720 4.0401625633 3.9582440853 4.0506172180 158 1311867723.8826351166 0.1079640985 0.0525983323 0.1091133058 0.0053366047 0.5782090000 0.1089540000 0.0802880000 0.0000010000 0.3864620000 0.0016730000 135226595 0 402718720 4.0381770134 3.9570405483 4.0497603416 159 1311867723.9172909260 0.1089557856 0.0529527817 0.1091133058 0.0053297529 0.5420030000 0.0721830000 0.0474930000 0.0334770000 0.3863630000 0.0016680000 135230211 0 402718720 4.0393328667 3.9577896595 4.0498781204 160 1311867723.9490020275 0.1117710322 0.0533203958 0.1117710322 0.0053179003 0.5071310000 0.0717120000 0.0455910000 0.0000010000 0.3873330000 0.0016670000 135233827 0 402718720 4.0424423218 3.9586775303 4.0504922867 161 1311867723.9839010239 0.1136218235 0.0536949388 0.1136218235 0.0053156803 0.9623570000 0.0714630000 0.0456900000 0.0339960000 0.3871080000 0.4232870000 135237611 0 402718720 4.0433664322 3.9567539692 4.0507092476 162 1311867724.0132899284 0.1141743585 0.0540682686 0.1141743585 0.0053029684 0.5587220000 0.0922360000 0.0810330000 0.0000010000 0.3829590000 0.0016610000 135241171 0 402718720 4.0440173149 3.9571371078 4.0507774353 163 1311867724.0475380421 0.1167626157 0.0544528964 0.1167626157 0.0052916362 0.5465490000 0.0713460000 0.0544370000 0.0336840000 0.3845730000 0.0016750000 135244955 0 402718720 4.0467205048 3.9578907490 4.0517845154 164 1311867724.0824530125 0.1180818528 0.0548408779 0.1180818528 0.0052802919 0.5411540000 0.0968200000 0.0530640000 0.0000010000 0.3887610000 0.0016680000 135248683 0 402718720 4.0472393036 3.9567291737 4.0524358749 165 1311867724.1132431030 0.1164506823 0.0552142706 0.1180818528 0.0052655035 0.9751890000 0.0710860000 0.0611320000 0.0341260000 0.3830950000 0.4249280000 135252355 0 402718720 4.0460534096 3.9577848911 4.0511531830 166 1311867724.1547191143 0.1198962256 0.0556039210 0.1198962256 0.0052651962 0.5064800000 0.0707410000 0.0437660000 0.0000010000 0.3894670000 0.0016660000 135256307 0 402718720 4.0488185883 3.9572653770 4.0528974533 167 1311867724.1810541153 0.1215586439 0.0559988594 0.1215586439 0.0052544933 0.5664500000 0.0709340000 0.0701240000 0.0340130000 0.3888700000 0.0016680000 135259811 0 402718720 4.0498375893 3.9564986229 4.0539784431 168 1311867724.2139430046 0.1225485727 0.0563949887 0.1225485727 0.0052418332 0.5527940000 0.0839230000 0.0764330000 0.0000010000 0.3899270000 0.0016680000 135263539 0 402718720 4.0504541397 3.9560201168 4.0542950630 169 1311867724.2507870197 0.1217915565 0.0567819506 0.1225485727 0.0052312639 0.9729580000 0.0702820000 0.0542770000 0.0340320000 0.3878750000 0.4256680000 135267323 0 402718720 4.0499725342 3.9574153423 4.0537166595 170 1311867724.2855930328 0.1252330691 0.0571846043 0.1252330691 0.0052247711 0.5459890000 0.0826150000 0.0706440000 0.0000010000 0.3902160000 0.0016630000 135271051 0 402718720 4.0527172089 3.9563899040 4.0550742149 171 1311867724.3144888878 0.1285546869 0.0576019732 0.1285546869 0.0052153676 0.5602870000 0.0967780000 0.0409480000 0.0337720000 0.3862780000 0.0016610000 135274611 0 402718720 4.0552067757 3.9546144009 4.0559439659 172 1311867724.3517999649 0.1287255734 0.0580154825 0.1287255734 0.0052168682 0.5118390000 0.0714650000 0.0479310000 0.0000000000 0.3899170000 0.0016760000 135278507 0 402718720 4.0548896790 3.9547598362 4.0567107201 173 1311867724.3888330460 0.1284274906 0.0584224883 0.1287255734 0.0052082002 0.9895140000 0.0704500000 0.0742370000 0.0341720000 0.3843450000 0.4254760000 135282235 0 402718720 4.0550508499 3.9555752277 4.0557074547 174 1311867724.4160330296 0.1330348402 0.0588512949 0.1330348402 0.0052042594 0.5208080000 0.0700590000 0.0577820000 0.0000010000 0.3904520000 0.0016680000 135285795 0 402718720 4.0584874153 3.9534599781 4.0582399368 175 1311867724.4509639740 0.1341001689 0.0592812885 0.1341001689 0.0051910080 0.5371140000 0.0707050000 0.0392870000 0.0341350000 0.3904770000 0.0016680000 135289523 0 402718720 4.0592966080 3.9526944160 4.0577855110 176 1311867724.4830689430 0.1344126314 0.0597081711 0.1344126314 0.0051772206 0.5356340000 0.0828260000 0.0583280000 0.0000010000 0.3919840000 0.0016400000 135293195 0 402718720 4.0596175194 3.9526901245 4.0571584702 177 1311867724.5208630562 0.1348036528 0.0601324394 0.1348036528 0.0051638079 1.0007920000 0.0705850000 0.0769510000 0.0341490000 0.3909700000 0.4272960000 135296923 0 402718720 4.0592312813 3.9520387650 4.0575180054 178 1311867724.5523910522 0.1403675377 0.0605831983 0.1403675377 0.0051669422 0.5492680000 0.1025980000 0.0548390000 0.0000010000 0.3892850000 0.0016860000 135300651 0 402718720 4.0637726784 3.9498965740 4.0597448349 179 1311867724.5861799717 0.1412074268 0.0610336130 0.1412074268 0.0051631944 0.5739040000 0.0692850000 0.0766490000 0.0344060000 0.3910380000 0.0016740000 135304323 0 402718720 4.0634465218 3.9480080605 4.0603685379 180 1311867724.6193559170 0.1425234675 0.0614863344 0.1425234675 0.0051798033 0.5339910000 0.0908650000 0.0543880000 0.0000010000 0.3860460000 0.0017630000 135307995 0 402718720 4.0644974709 3.9478256702 4.0603623390 181 1311867724.6529819965 0.1442720890 0.0619437143 0.1442720890 0.0051687373 0.9690300000 0.0699430000 0.0459750000 0.0342130000 0.3897140000 0.4283420000 135311723 0 402718720 4.0661969185 3.9484193325 4.0605206490 182 1311867724.6818330288 0.1445900202 0.0623978149 0.1445900202 0.0051646218 0.5393340000 0.0866740000 0.0523100000 0.0000010000 0.3978190000 0.0016690000 135315283 0 402718720 4.0658450127 3.9470536709 4.0599150658 183 1311867724.7153129578 0.1452777684 0.0628507108 0.1452777684 0.0051621006 0.5595010000 0.0919820000 0.0414300000 0.0344270000 0.3891140000 0.0016790000 135319011 0 402718720 4.0659513474 3.9476315975 4.0607919693 184 1311867724.7518899441 0.1474152356 0.0633103006 0.1474152356 0.0051533101 0.5270450000 0.0724330000 0.0586660000 0.0000010000 0.3934060000 0.0016730000 135322795 0 402718720 4.0678625107 3.9487438202 4.0616645813 185 1311867724.7853860855 0.1502916217 0.0637804699 0.1502916217 0.0051441795 0.9846910000 0.0705350000 0.0578680000 0.0337350000 0.3924910000 0.4292040000 135326523 0 402718720 4.0691332817 3.9466118813 4.0635843277 186 1311867724.8179960251 0.1519014090 0.0642542384 0.1519014090 0.0051415900 0.5524130000 0.0702860000 0.0766780000 0.0000010000 0.4028840000 0.0016420000 135330195 0 402718720 4.0702991486 3.9462285042 4.0640444756 187 1311867724.8547580242 0.1514204144 0.0647203677 0.1519014090 0.0051461683 0.5474840000 0.0711810000 0.0460710000 0.0341240000 0.3935580000 0.0016750000 135333923 0 402718720 4.0699295998 3.9471495152 4.0632810593 188 1311867724.8830249310 0.1541203111 0.0651958993 0.1541203111 0.0051341615 0.5577600000 0.1015590000 0.0612390000 0.0000010000 0.3924190000 0.0016690000 135337483 0 402718720 4.0713887215 3.9458463192 4.0650730133 189 1311867724.9137279987 0.1574654430 0.0656840980 0.1574654430 0.0051479024 1.0169090000 0.1087740000 0.0547270000 0.0345350000 0.3882030000 0.4298060000 135341155 0 402718720 4.0733280182 3.9437613487 4.0667357445 190 1311867724.9535229206 0.1573655605 0.0661666320 0.1574654430 0.0051360389 0.5150460000 0.0706670000 0.0412760000 0.0000000000 0.4000230000 0.0021690000 135344995 0 402718720 4.0735054016 3.9446685314 4.0661883354 191 1311867724.9843940735 0.1583779752 0.0666494139 0.1583779752 0.0051230079 0.5896260000 0.0883140000 0.0682310000 0.0367840000 0.3937560000 0.0016640000 135348667 0 402718720 4.0740737915 3.9442710876 4.0668630600 192 1311867725.0159099102 0.1617295593 0.0671446230 0.1617295593 0.0051237890 0.5424110000 0.0701980000 0.0808850000 0.0000010000 0.3886320000 0.0017540000 135352283 0 402718720 4.0755414963 3.9413483143 4.0695319176 193 1311867725.0518310070 0.1595497578 0.0676234060 0.1617295593 0.0051115417 1.0048970000 0.0897630000 0.0544220000 0.0345450000 0.3941820000 0.4311180000 135356067 0 402718720 4.0740137100 3.9424705505 4.0676560402 194 1311867725.0813930035 0.1605774760 0.0681025507 0.1617295593 0.0050985452 0.5289140000 0.0708230000 0.0612350000 0.0000000000 0.3943160000 0.0016600000 135359683 0 402718720 4.0745215416 3.9423570633 4.0683841705 195 1311867725.1151220798 0.1625924557 0.0685871143 0.1625924557 0.0050893339 0.5480270000 0.0706260000 0.0454100000 0.0343830000 0.3950590000 0.0016660000 135363411 0 402718720 4.0756845474 3.9404892921 4.0689268112 196 1311867725.1557130814 0.1619133502 0.0690632686 0.1625924557 0.0050783378 0.5219610000 0.0713440000 0.0520630000 0.0000010000 0.3960070000 0.0016570000 135367307 0 402718720 4.0751581192 3.9413487911 4.0681881905 197 1311867725.1843969822 0.1668705195 0.0695597521 0.1668705195 0.0050780677 0.9924400000 0.0715050000 0.0583770000 0.0344410000 0.3952800000 0.4319650000 135370867 0 402718720 4.0777254105 3.9386751652 4.0722694397 198 1311867725.2150099277 0.1687136292 0.0700605293 0.1687136292 0.0050688631 0.5670560000 0.1003040000 0.0678270000 0.0000010000 0.3963620000 0.0016690000 135374539 0 402718720 4.0780162811 3.9362173080 4.0734033585 199 1311867725.2516539097 0.1658662111 0.0705419649 0.1687136292 0.0050573770 0.5817670000 0.0709220000 0.0772340000 0.0343430000 0.3966910000 0.0016660000 135378379 0 402718720 4.0769653320 3.9391252995 4.0702238083 200 1311867725.2816410065 0.1658433974 0.0710184720 0.1687136292 0.0050484402 0.5497520000 0.0708240000 0.0774290000 0.0000000000 0.3989420000 0.0016640000 135381995 0 402718720 4.0769133568 3.9390850067 4.0698161125 201 1311867725.3196239471 0.1717832834 0.0715197895 0.1717832834 0.0050481749 1.0034360000 0.0718840000 0.0648830000 0.0344820000 0.3973400000 0.4339680000 135385779 0 402718720 4.0798940659 3.9355320930 4.0744266510 202 1311867725.3517010212 0.1713870913 0.0720141821 0.1717832834 0.0050385301 0.5374750000 0.0718640000 0.0647310000 0.0000010000 0.3983230000 0.0016640000 135389395 0 402718720 4.0794186592 3.9361522198 4.0745549202 203 1311867725.3837459087 0.1789817661 0.0725411160 0.1789817661 0.0050761564 0.5931740000 0.0820940000 0.0772080000 0.0345560000 0.3967380000 0.0016740000 135392955 0 402718720 4.0830607414 3.9323241711 4.0821776390 204 1311867725.4178969860 0.1757043749 0.0730468182 0.1789817661 0.0050648838 0.5294910000 0.0715500000 0.0619710000 0.0000010000 0.3932330000 0.0017650000 135396739 0 402718720 4.0820221901 3.9346127510 4.0777359009 205 1311867725.4492449760 0.1730830967 0.0735348001 0.1789817661 0.0050598918 0.9911770000 0.0725050000 0.0489780000 0.0340800000 0.3990670000 0.4356520000 135400355 0 402718720 4.0800671577 3.9361681938 4.0755410194 206 1311867725.4836509228 0.1875833571 0.0740884339 0.1875833571 0.0051443537 0.5870090000 0.1084680000 0.0784270000 0.0000010000 0.3975320000 0.0016730000 135404083 0 402718720 4.0871062279 3.9289066792 4.0889000893 207 1311867725.5178139210 0.1967201084 0.0746808574 0.1967201084 0.0051552383 0.5531030000 0.0710820000 0.0480640000 0.0344500000 0.3969110000 0.0016870000 135407923 0 402718720 4.0907025337 3.9239099026 4.0977807045 208 1311867725.5497610569 0.2015437931 0.0752907754 0.2015437931 0.0051519309 0.5684310000 0.0889410000 0.0818830000 0.0000010000 0.3950270000 0.0016740000 135411539 0 402718720 4.0926613808 3.9213371277 4.1016983986 209 1311867725.5815479755 0.1943967193 0.0758606603 0.2015437931 0.0051808596 1.0199450000 0.0731720000 0.0785090000 0.0344700000 0.3986020000 0.4343050000 135415211 0 402718720 4.0904855728 3.9265718460 4.0929937363 210 1311867725.6194949150 0.2046260089 0.0764738286 0.2046260089 0.0051855617 0.5549330000 0.0735200000 0.0829420000 0.0000000000 0.3958920000 0.0016750000 135419051 0 402718720 4.0952982903 3.9210979939 4.1015682220 211 1311867725.6515610218 0.2175453156 0.0771424138 0.2175453156 0.0053201579 0.5635750000 0.0722670000 0.0589250000 0.0344200000 0.3953870000 0.0016710000 135422723 0 402718720 4.0988755226 3.9130775928 4.1150093079 212 1311867725.6834650040 0.2126061320 0.0777813936 0.2175453156 0.0053198635 0.5178800000 0.0716450000 0.0460760000 0.0000000000 0.3975720000 0.0016780000 135426395 0 402718720 4.0978283882 3.9175646305 4.1090154648 213 1311867725.7201809883 0.2166168392 0.0784332032 0.2175453156 0.0053125842 1.0198730000 0.0840360000 0.0717190000 0.0344860000 0.3968870000 0.4318420000 135430179 0 402718720 4.0995335579 3.9152462482 4.1116509438 214 1311867725.7515070438 0.2225106657 0.0791064624 0.2225106657 0.0053076793 0.5380350000 0.0733520000 0.0658840000 0.0000000000 0.3962120000 0.0016700000 135433851 0 402718720 4.1013970375 3.9114456177 4.1167654991 215 1311867725.7835409641 0.1846618205 0.0795974176 0.2225106657 0.0055393194 0.5957680000 0.0881190000 0.0734810000 0.0338840000 0.3976710000 0.0016830000 135437467 0 402718720 4.0744328499 3.9254016876 4.0915889740 216 1311867725.8211829662 0.1936567724 0.0801254701 0.2225106657 0.0055515335 0.5296450000 0.0715320000 0.0625340000 0.0000010000 0.3929800000 0.0016800000 135441363 0 402718720 4.0777750015 3.9198970795 4.0995130539 217 1311867725.8517971039 0.1933346093 0.0806471712 0.2225106657 0.0055445193 0.9904170000 0.0732170000 0.0533190000 0.0344030000 0.3969360000 0.4316380000 135445035 0 402718720 4.0772023201 3.9198067188 4.0987353325 218 1311867725.8837900162 0.1976762265 0.0811840018 0.2225106657 0.0055579797 0.5694880000 0.0909460000 0.0838020000 0.0000010000 0.3919640000 0.0017900000 135448595 0 402718720 4.0790896416 3.9190120697 4.1028428078 219 1311867725.9192690849 0.2012353987 0.0817321817 0.2225106657 0.0055536353 0.5727320000 0.0850650000 0.0534830000 0.0344230000 0.3971520000 0.0016800000 135452379 0 402718720 4.0811176300 3.9175422192 4.1044869423 220 1311867725.9511859417 0.2076977342 0.0823047524 0.2225106657 0.0055473844 0.5335950000 0.0720880000 0.0628350000 0.0000000000 0.3960730000 0.0016760000 135456051 0 402718720 4.0829496384 3.9131910801 4.1102681160 221 1311867725.9829630852 0.2093510628 0.0828796225 0.2225106657 0.0055373811 1.0182360000 0.0734700000 0.0838920000 0.0346450000 0.3949010000 0.4304210000 135459667 0 402718720 4.0841507912 3.9139490128 4.1113963127 222 1311867726.0219368935 0.2140143365 0.0834703194 0.2225106657 0.0055304536 0.5264430000 0.0735460000 0.0535500000 0.0000010000 0.3967360000 0.0016820000 135463563 0 402718720 4.0859479904 3.9114255905 4.1144733429 223 1311867726.0504179001 0.2102355212 0.0840387733 0.2225106657 0.0055301251 0.5966990000 0.0833330000 0.0796000000 0.0344450000 0.3967230000 0.0016700000 135467067 0 402718720 4.0841822624 3.9129619598 4.1099581718 224 1311867726.0845088959 0.2181767374 0.0846376035 0.2225106657 0.0055430640 0.5260000000 0.0738670000 0.0539540000 0.0000000000 0.3955710000 0.0016720000 135470851 0 402718720 4.0866775513 3.9089348316 4.1179847717 225 1311867726.1199669838 0.2178563476 0.0852296868 0.2225106657 0.0055322731 1.0142330000 0.0867430000 0.0665020000 0.0339590000 0.3966850000 0.4294270000 135474579 0 402718720 4.0863504410 3.9088821411 4.1169824600 226 1311867726.1506989002 0.2203763574 0.0858276809 0.2225106657 0.0055241261 0.5520810000 0.0741410000 0.0798300000 0.0000010000 0.3955070000 0.0016750000 135478251 0 402718720 4.0865468979 3.9067220688 4.1190814972 227 1311867726.1824700832 0.2162772864 0.0864023488 0.2225106657 0.0055132530 0.5793700000 0.0736860000 0.0771630000 0.0345890000 0.3911580000 0.0017730000 135481923 0 402718720 4.0847115517 3.9094626904 4.1152057648 228 1311867726.2198660374 0.2198680043 0.0869877244 0.2225106657 0.0055081398 0.5535350000 0.0731460000 0.0838030000 0.0000010000 0.3939670000 0.0016790000 135485707 0 402718720 4.0865845680 3.9079880714 4.1173982620 229 1311867726.2506690025 0.2277439088 0.0876023803 0.2277439088 0.0055102730 0.9894210000 0.0728930000 0.0494100000 0.0340670000 0.3999200000 0.4322090000 135489379 0 402718720 4.0887207985 3.9026465416 4.1245737076 230 1311867726.2845950127 0.2249289006 0.0881994521 0.2277439088 0.0055000662 0.5601690000 0.0841490000 0.0761050000 0.0000010000 0.3973020000 0.0016650000 135493051 0 402718720 4.0879063606 3.9044201374 4.1211051941 231 1311867726.3187239170 0.2313745320 0.0888192576 0.2313745320 0.0054971336 0.5866710000 0.0733330000 0.0796280000 0.0344580000 0.3966390000 0.0016720000 135496835 0 402718720 4.0905418396 3.9017629623 4.1267871857 232 1311867726.3524029255 0.2298026085 0.0894269445 0.2313745320 0.0054897605 0.5275890000 0.0729800000 0.0536030000 0.0000010000 0.3984000000 0.0016680000 135500563 0 402718720 4.0908117294 3.9036147594 4.1241822243 233 1311867726.3835608959 0.2323562205 0.0900403749 0.2323562205 0.0054790692 1.0125360000 0.1024710000 0.0467070000 0.0344150000 0.3973700000 0.4306410000 135504179 0 402718720 4.0911331177 3.9017446041 4.1261358261 234 1311867726.4218099117 0.2295842618 0.0906367163 0.2323562205 0.0054716069 0.5359060000 0.0740070000 0.0604130000 0.0000010000 0.3988700000 0.0016730000 135508075 0 402718720 4.0912427902 3.9049737453 4.1223516464 235 1311867726.4504199028 0.2314209938 0.0912357983 0.2323562205 0.0054601937 0.5472230000 0.0717710000 0.0399160000 0.0341310000 0.3987860000 0.0016670000 135511635 0 402718720 4.0914759636 3.9041354656 4.1241879463 236 1311867726.4843189716 0.2333260328 0.0918378756 0.2333260328 0.0054502243 0.5542670000 0.0741200000 0.0782450000 0.0000010000 0.3992670000 0.0016690000 135515363 0 402718720 4.0918416977 3.9029340744 4.1256670952 237 1311867726.5207901001 0.2390826792 0.0924591616 0.2390826792 0.0054448290 1.0250470000 0.0738140000 0.0798400000 0.0344600000 0.3978010000 0.4381470000 135519147 0 402718720 4.0929427147 3.8989746571 4.1314225197 238 1311867726.5524380207 0.2374822497 0.0930685023 0.2390826792 0.0054393581 0.5690040000 0.0914820000 0.0689450000 0.0000010000 0.4059390000 0.0016740000 135522819 0 402718720 4.0926351547 3.9006717205 4.1295776367 239 1311867726.5874860287 0.2342000008 0.0936590107 0.2390826792 0.0054356257 0.5887510000 0.0737160000 0.0797170000 0.0339340000 0.3987560000 0.0016680000 135526603 0 402718720 4.0916213989 3.9032664299 4.1261196136 240 1311867726.6204600334 0.2365411073 0.0942543528 0.2390826792 0.0054382495 0.5551920000 0.0737480000 0.0800980000 0.0000000000 0.3987180000 0.0016700000 135530275 0 402718720 4.0930609703 3.9023323059 4.1280798912 241 1311867726.6509370804 0.2332148403 0.0948309523 0.2390826792 0.0054423850 1.0176160000 0.0735640000 0.0802230000 0.0344860000 0.3979010000 0.4305040000 135533891 0 402718720 4.0921993256 3.9037113190 4.1236438751 242 1311867726.6916151047 0.2362776995 0.0954154430 0.2390826792 0.0054369625 0.5759020000 0.0930500000 0.0839790000 0.0000000000 0.3962290000 0.0016740000 135537843 0 402718720 4.0930080414 3.9019436836 4.1269373894 243 1311867726.7201170921 0.2357267439 0.0959928558 0.2390826792 0.0054276012 0.5772670000 0.0833820000 0.0606470000 0.0344020000 0.3961910000 0.0016710000 135541347 0 402718720 4.0937128067 3.9030566216 4.1259393692 244 1311867726.7513859272 0.2327254713 0.0965532353 0.2390826792 0.0054185215 0.5526680000 0.0734600000 0.0803500000 0.0000010000 0.3962180000 0.0016700000 135545019 0 402718720 4.0920119286 3.9035642147 4.1231994629 245 1311867726.7880010605 0.2280431092 0.0970899287 0.2390826792 0.0054136025 0.9899920000 0.0738340000 0.0565580000 0.0341750000 0.3963460000 0.4281290000 135548859 0 402718720 4.0901970863 3.9055893421 4.1188077927 246 1311867726.8198299408 0.2315225452 0.0976364027 0.2390826792 0.0054087897 0.5316260000 0.0735640000 0.0607030000 0.0000010000 0.3947210000 0.0016680000 135552475 0 402718720 4.0917401314 3.9038724899 4.1222877502 247 1311867726.8500390053 0.2322224677 0.0981812856 0.2390826792 0.0053981461 0.5517840000 0.0733320000 0.0474560000 0.0344160000 0.3939350000 0.0016760000 135556091 0 402718720 4.0920476913 3.9030857086 4.1228399277 248 1311867726.8927390575 0.2272617668 0.0987017714 0.2390826792 0.0053911930 0.5759630000 0.0957930000 0.0853880000 0.0000010000 0.3921140000 0.0016850000 135560099 0 402718720 4.0907001495 3.9058732986 4.1177525520 249 1311867726.9216780663 0.2292737216 0.0992261568 0.2390826792 0.0053826268 1.0097450000 0.0732100000 0.0803950000 0.0344550000 0.3939990000 0.4267240000 135563659 0 402718720 4.0910692215 3.9048726559 4.1206493378 250 1311867726.9543499947 0.2235274017 0.0997233617 0.2390826792 0.0054082956 0.5536820000 0.0743140000 0.0813920000 0.0000000000 0.3953170000 0.0016790000 135567331 0 402718720 4.0900192261 3.9085102081 4.1144318581 251 1311867726.9902989864 0.2238992304 0.1002180863 0.2390826792 0.0054024719 0.5867550000 0.0742960000 0.0852310000 0.0345830000 0.3898260000 0.0017820000 135571059 0 402718720 4.0895314217 3.9077405930 4.1155996323 252 1311867727.0208179951 0.2254297733 0.1007149581 0.2390826792 0.0053923968 0.5499610000 0.0726970000 0.0803230000 0.0000010000 0.3942900000 0.0016800000 135574731 0 402718720 4.0902085304 3.9066174030 4.1170220375 253 1311867727.0536949635 0.2222298682 0.1011952542 0.2390826792 0.0053879675 1.0140700000 0.0955230000 0.0611060000 0.0344550000 0.3944570000 0.4275600000 135578403 0 402718720 4.0895094872 3.9083366394 4.1138463020 254 1311867727.0911629200 0.2227320075 0.1016737453 0.2390826792 0.0053787019 0.5440220000 0.0732230000 0.0742420000 0.0000010000 0.3938790000 0.0016880000 135582243 0 402718720 4.0892710686 3.9076631069 4.1153073311 255 1311867727.1196689606 0.2188439071 0.1021332362 0.2390826792 0.0053708732 0.5626860000 0.0742900000 0.0576050000 0.0346950000 0.3934320000 0.0016850000 135585691 0 402718720 4.0877923965 3.9092962742 4.1115751266 256 1311867727.1514298916 0.2150447667 0.1025742968 0.2390826792 0.0053661881 0.5535100000 0.0748890000 0.0815910000 0.0000010000 0.3943850000 0.0016490000 135589419 0 402718720 4.0861225128 3.9111428261 4.1087684631 257 1311867727.1904149055 0.2159857452 0.1030155865 0.2390826792 0.0053753091 0.9849850000 0.0748660000 0.0648670000 0.0346520000 0.3872520000 0.4223610000 135617779 0 402718720 4.0865054131 3.9103338718 4.1103992462 258 1311867727.2208960056 0.2129856199 0.1034418269 0.2390826792 0.0053735248 0.5705690000 0.0947400000 0.0813010000 0.0000010000 0.3918440000 0.0016890000 135672651 0 402718720 4.0849657059 3.9123015404 4.1090836525 259 1311867727.2544560432 0.2080381513 0.1038456738 0.2390826792 0.0053786469 0.5577400000 0.0744430000 0.0548070000 0.0344150000 0.3913720000 0.0016930000 135676323 0 402718720 4.0832381248 3.9143502712 4.1038379669 260 1311867727.2870850563 0.2087342590 0.1042490914 0.2390826792 0.0053700928 0.5476200000 0.0731480000 0.0807760000 0.0000010000 0.3910100000 0.0016890000 135680051 0 402718720 4.0832033157 3.9134719372 4.1053590775 261 1311867727.3192501068 0.2091737539 0.1046511016 0.2390826792 0.0053600863 0.9855800000 0.0749650000 0.0614310000 0.0346250000 0.3903780000 0.4231950000 135683723 0 402718720 4.0838751793 3.9127337933 4.1056580544 262 1311867727.3502039909 0.2050454021 0.1050342859 0.2390826792 0.0053589869 0.5477430000 0.0730840000 0.0815350000 0.0000010000 0.3904410000 0.0016830000 135687339 0 402718720 4.0818896294 3.9136304855 4.1019749641 263 1311867727.3894629478 0.2038168907 0.1054098852 0.2390826792 0.0053501921 0.5642110000 0.0984250000 0.0434380000 0.0340610000 0.3855760000 0.0016970000 135691123 0 402718720 4.0812931061 3.9147672653 4.1026244164 264 1311867727.4182970524 0.2018567771 0.1057752143 0.2390826792 0.0053409001 0.5222470000 0.0744280000 0.0546560000 0.0000010000 0.3905150000 0.0016540000 135694739 0 402718720 4.0806226730 3.9153878689 4.1019430161 265 1311867727.4495580196 0.1980345100 0.1061233626 0.2390826792 0.0053359102 0.9694580000 0.0736230000 0.0479230000 0.0343570000 0.3898240000 0.4227380000 135698299 0 402718720 4.0789055824 3.9166924953 4.0989351273 266 1311867727.4858360291 0.1986812055 0.1064713244 0.2390826792 0.0053488777 0.5328140000 0.0731870000 0.0674830000 0.0000010000 0.3894490000 0.0016820000 135702139 0 402718720 4.0782361031 3.9165837765 4.1020183563 267 1311867727.5198891163 0.1947700977 0.1068020315 0.2390826792 0.0053541050 0.5496610000 0.0744140000 0.0482800000 0.0344330000 0.3898290000 0.0016940000 135705811 0 402718720 4.0774540901 3.9186003208 4.0975785255 268 1311867727.5494980812 0.1939752549 0.1071273047 0.2390826792 0.0053498830 0.5811120000 0.1051800000 0.0831910000 0.0000010000 0.3900370000 0.0016900000 135709427 0 402718720 4.0765161514 3.9175956249 4.0973157883 269 1311867727.5905909538 0.1913843006 0.1074405277 0.2390826792 0.0053476944 1.0077390000 0.0743400000 0.0846590000 0.0344710000 0.3901760000 0.4230920000 135713379 0 402718720 4.0758776665 3.9186370373 4.0950841904 270 1311867727.6176431179 0.1901268214 0.1077467732 0.2390826792 0.0053479094 0.5282960000 0.0744740000 0.0613400000 0.0000010000 0.3897840000 0.0016890000 135716883 0 402718720 4.0740380287 3.9180681705 4.0952248573 271 1311867727.6497650146 0.1880591214 0.1080431288 0.2390826792 0.0053433351 0.5923670000 0.0850470000 0.0809250000 0.0339040000 0.3897760000 0.0016890000 135720555 0 402718720 4.0730309486 3.9185945988 4.0934681892 272 1311867727.6884338856 0.1830627322 0.1083189361 0.2390826792 0.0053420966 0.5055920000 0.0717030000 0.0407220000 0.0000010000 0.3904640000 0.0016830000 135724227 0 402718720 4.0713787079 3.9215345383 4.0886173248 273 1311867727.7184689045 0.1808262765 0.1085845308 0.2390826792 0.0053335002 0.9762370000 0.0863920000 0.0414090000 0.0344230000 0.3900670000 0.4229360000 135727899 0 402718720 4.0700364113 3.9220237732 4.0862350464 274 1311867727.7523269653 0.1764353216 0.1088321614 0.2390826792 0.0053278111 0.5075470000 0.0738270000 0.0412990000 0.0000010000 0.3897060000 0.0016960000 135731627 0 402718720 4.0664668083 3.9223384857 4.0827207565 275 1311867727.7856590748 0.1754571944 0.1090744343 0.2390826792 0.0053220193 0.5752640000 0.0708540000 0.0831410000 0.0342560000 0.3843040000 0.0016850000 135735299 0 402718720 4.0653638840 3.9229824543 4.0828070641 276 1311867727.8181309700 0.1749062240 0.1093129552 0.2390826792 0.0053189950 0.5304880000 0.0721640000 0.0668340000 0.0000000000 0.3887780000 0.0016820000 135739027 0 402718720 4.0645699501 3.9233875275 4.0829029083 277 1311867727.8548729420 0.1743345857 0.1095476904 0.2390826792 0.0053110035 1.0173070000 0.0989990000 0.0733250000 0.0337890000 0.3888730000 0.4213010000 135742811 0 402718720 4.0643448830 3.9234752655 4.0821251869 278 1311867727.8882629871 0.1717629135 0.1097714861 0.2390826792 0.0053023225 0.5262400000 0.0946970000 0.0429520000 0.0000000000 0.3858810000 0.0016780000 135746539 0 402718720 4.0632729530 3.9249310493 4.0800538063 279 1311867727.9193139076 0.1709720045 0.1099908428 0.2390826792 0.0052955750 0.5576850000 0.0843040000 0.0474640000 0.0344000000 0.3887810000 0.0016930000 135750155 0 402718720 4.0623102188 3.9252064228 4.0804853439 280 1311867727.9556980133 0.1706979275 0.1102076538 0.2390826792 0.0052872691 0.5478770000 0.0730720000 0.0846250000 0.0000010000 0.3874900000 0.0016450000 135753939 0 402718720 4.0627970695 3.9251720905 4.0795531273 281 1311867727.9869389534 0.1704568714 0.1104220639 0.2390826792 0.0052785967 0.9711840000 0.0725150000 0.0537160000 0.0343540000 0.3884860000 0.4210880000 135757667 0 402718720 4.0626697540 3.9252631664 4.0795803070 282 1311867728.0179219246 0.1685993820 0.1106283664 0.2390826792 0.0052786575 0.5440000000 0.0724110000 0.0799150000 0.0000010000 0.3889750000 0.0016720000 135761227 0 402718720 4.0621662140 3.9264121056 4.0781273842 283 1311867728.0555219650 0.1660187989 0.1108240923 0.2390826792 0.0052724029 0.5592220000 0.0846420000 0.0499440000 0.0340680000 0.3878420000 0.0016740000 135765067 0 402718720 4.0603380203 3.9272086620 4.0770349503 284 1311867728.0892169476 0.1646756083 0.1110137103 0.2390826792 0.0052642854 0.5461350000 0.0723620000 0.0843720000 0.0000010000 0.3866900000 0.0016690000 135768795 0 402718720 4.0601119995 3.9283378124 4.0761404037 285 1311867728.1177880764 0.1621100157 0.1111929956 0.2390826792 0.0052616512 0.9770270000 0.0724980000 0.0423260000 0.0343460000 0.3884430000 0.4383220000 135772411 0 402718720 4.0588035583 3.9293167591 4.0741319656 286 1311867728.1556169987 0.1620911360 0.1113709612 0.2390826792 0.0052554003 0.5658080000 0.0914790000 0.0836670000 0.0000000000 0.3879420000 0.0016760000 135776195 0 402718720 4.0588660240 3.9290883541 4.0743126869 287 1311867728.1882989407 0.1605588794 0.1115423476 0.2390826792 0.0052465962 0.5308430000 0.0727710000 0.0325470000 0.0344340000 0.3883560000 0.0016820000 135779979 0 402718720 4.0585851669 3.9296562672 4.0723948479 288 1311867728.2182519436 0.1598300189 0.1117100132 0.2390826792 0.0052403525 0.5245570000 0.0930790000 0.0427600000 0.0000010000 0.3859770000 0.0016790000 135783595 0 402718720 4.0576848984 3.9295501709 4.0722999573 289 1311867728.2558999062 0.1578662544 0.1118697233 0.2390826792 0.0052320072 0.9968860000 0.0719240000 0.0799510000 0.0343830000 0.3884710000 0.4211110000 135787379 0 402718720 4.0568056107 3.9303250313 4.0706367493 290 1311867728.2875900269 0.1392019838 0.1119639725 0.2390826792 0.0053161805 0.5111760000 0.0732430000 0.0474500000 0.0000010000 0.3877400000 0.0016890000 135791051 0 402718720 4.0368723869 3.9323065281 4.0649857521 291 1311867728.3226509094 0.1387174726 0.1120559089 0.2390826792 0.0053215503 0.5550680000 0.0734690000 0.0539830000 0.0343700000 0.3899310000 0.0021970000 135794835 0 402718720 4.0374031067 3.9333226681 4.0646553040 292 1311867728.3597300053 0.1376253963 0.1121434757 0.2390826792 0.0053219295 0.5430430000 0.0911620000 0.0538830000 0.0000010000 0.3952630000 0.0016750000 135798563 0 402718720 4.0362844467 3.9326608181 4.0640101433 293 1311867728.3861401081 0.1379995793 0.1122317218 0.2390826792 0.0053130678 0.9913070000 0.0938880000 0.0567050000 0.0340320000 0.3855490000 0.4200810000 135802123 0 402718720 4.0369253159 3.9327311516 4.0640840530 294 1311867728.4175701141 0.1380097717 0.1123194022 0.2390826792 0.0053438055 0.5124840000 0.0721560000 0.0493360000 0.0000010000 0.3882550000 0.0016820000 135805795 0 402718720 4.0363588333 3.9320878983 4.0639195442 295 1311867728.4568250179 0.1359047592 0.1123993526 0.2390826792 0.0053365285 0.5399740000 0.0731450000 0.0429340000 0.0346520000 0.3864780000 0.0016950000 135809635 0 402718720 4.0352230072 3.9330615997 4.0621933937 296 1311867728.4875330925 0.1340978146 0.1124726582 0.2390826792 0.0053310953 0.5475260000 0.0827510000 0.0730200000 0.0000000000 0.3890110000 0.0016750000 135813251 0 402718720 4.0348176956 3.9345886707 4.0607185364 297 1311867728.5187420845 0.1338575631 0.1125446612 0.2390826792 0.0053250558 0.9572660000 0.0718010000 0.0403870000 0.0342680000 0.3888510000 0.4209020000 135816867 0 402718720 4.0347037315 3.9340896606 4.0599460602 298 1311867728.5550920963 0.1325221360 0.1126116997 0.2390826792 0.0053185341 0.5335410000 0.0934020000 0.0494730000 0.0000010000 0.3879070000 0.0016920000 135820707 0 402718720 4.0337629318 3.9348146915 4.0595541000 299 1311867728.5878560543 0.1330982298 0.1126802166 0.2390826792 0.0053121265 0.5779170000 0.0852810000 0.0666530000 0.0342970000 0.3889150000 0.0016940000 135824435 0 402718720 4.0349864960 3.9347274303 4.0589098930 300 1311867728.6187679768 0.1317928731 0.1127439254 0.2390826792 0.0053044877 0.5161500000 0.0708220000 0.0530530000 0.0000010000 0.3895270000 0.0016860000 135827995 0 402718720 4.0341839790 3.9352819920 4.0579061508 301 1311867728.6580820084 0.1324954629 0.1128095451 0.2390826792 0.0052966871 0.9470400000 0.0700600000 0.0334610000 0.0339440000 0.3882920000 0.4202190000 135831891 0 402718720 4.0345177650 3.9348497391 4.0584554672 302 1311867728.6893489361 0.1320027411 0.1128730988 0.2390826792 0.0052891233 0.5029100000 0.0717200000 0.0402530000 0.0000000000 0.3881770000 0.0016830000 135835563 0 402718720 4.0336542130 3.9343564510 4.0582304001 303 1311867728.7210168839 0.1313059181 0.1129339331 0.2390826792 0.0052857425 0.5886820000 0.0839170000 0.0800420000 0.0342420000 0.3877040000 0.0016920000 135839235 0 402718720 4.0336141586 3.9347057343 4.0575809479 304 1311867728.7584259510 0.1305803061 0.1129919804 0.2390826792 0.0052771502 0.5228780000 0.0851900000 0.0468940000 0.0000000000 0.3880210000 0.0016860000 135843019 0 402718720 4.0332794189 3.9347126484 4.0567941666 305 1311867728.7858450413 0.1297616363 0.1130469629 0.2390826792 0.0052693736 0.9589200000 0.0713700000 0.0558770000 0.0343700000 0.3823420000 0.4138910000 135846635 0 402718720 4.0321254730 3.9343504906 4.0563373566 306 1311867728.8203740120 0.1286770552 0.1130980416 0.2390826792 0.0052618782 0.5227500000 0.0721960000 0.0599180000 0.0000000000 0.3878750000 0.0016800000 135850307 0 402718720 4.0319986343 3.9348154068 4.0544838905 307 1311867728.8545160294 0.1248193160 0.1131362217 0.2390826792 0.0052556029 0.5506170000 0.0719260000 0.0532530000 0.0342570000 0.3884090000 0.0016840000 135854035 0 402718720 4.0301041603 3.9364764690 4.0510911942 308 1311867728.8860759735 0.1281329542 0.1131849124 0.2390826792 0.0052492095 0.5368660000 0.0948380000 0.0558810000 0.0000010000 0.3833890000 0.0016770000 135857763 0 402718720 4.0319871902 3.9350309372 4.0536012650 309 1311867728.9193949699 0.1278968900 0.1132325240 0.2390826792 0.0052412435 0.9661510000 0.0718310000 0.0530500000 0.0342730000 0.3868700000 0.4190480000 135861379 0 402718720 4.0314188004 3.9348449707 4.0541329384 310 1311867728.9585559368 0.1247904301 0.1132698075 0.2390826792 0.0052532355 0.5413260000 0.0716190000 0.0795060000 0.0000010000 0.3874280000 0.0016910000 135865387 0 402718720 4.0302042961 3.9367976189 4.0515956879 311 1311867728.9886839390 0.1263468713 0.1133118560 0.2390826792 0.0052491374 0.5753970000 0.0727980000 0.0842310000 0.0343720000 0.3810290000 0.0017960000 135868891 0 402718720 4.0305781364 3.9348800182 4.0529747009 312 1311867729.0231020451 0.1239029393 0.1133458017 0.2390826792 0.0052432459 0.5375150000 0.0726940000 0.0770510000 0.0000010000 0.3849950000 0.0016800000 135872675 0 402718720 4.0295243263 3.9364216328 4.0516328812 313 1311867729.0583839417 0.1216617227 0.1133723702 0.2390826792 0.0052425362 0.9833040000 0.0743600000 0.0701190000 0.0339460000 0.3847480000 0.4190560000 135876459 0 402718720 4.0276026726 3.9371917248 4.0512685776 314 1311867729.0882170200 0.1185289398 0.1133887924 0.2390826792 0.0052355380 0.5436710000 0.0720120000 0.0833550000 0.0000000000 0.3855100000 0.0016910000 135880075 0 402718720 4.0252871513 3.9382574558 4.0490365028 315 1311867729.1263229847 0.1192141995 0.1134072857 0.2390826792 0.0052489195 0.5436480000 0.0699010000 0.0506890000 0.0340470000 0.3862220000 0.0016830000 135883915 0 402718720 4.0254392624 3.9392309189 4.0508880615 316 1311867729.1556320190 0.1176370010 0.1134206709 0.2390826792 0.0052443452 0.5405770000 0.0720360000 0.0791030000 0.0000010000 0.3866570000 0.0016810000 135887475 0 402718720 4.0245757103 3.9405899048 4.0492677689 317 1311867729.1888830662 0.1181275398 0.1134355191 0.2390826792 0.0052712438 0.9780760000 0.0736840000 0.0648780000 0.0342910000 0.3860560000 0.4180670000 135891203 0 402718720 4.0241999626 3.9400277138 4.0495882034 318 1311867729.2240469456 0.1123078391 0.1134319729 0.2390826792 0.0052775398 0.5420410000 0.0724510000 0.0799120000 0.0000010000 0.3868800000 0.0016970000 135894931 0 402718720 4.0200839043 3.9421226978 4.0461907387 319 1311867729.2579979897 0.1137626842 0.1134330096 0.2390826792 0.0052694831 0.5598820000 0.0711390000 0.0659560000 0.0341360000 0.3858550000 0.0016900000 135898715 0 402718720 4.0193219185 3.9397835732 4.0483851433 320 1311867729.2880148888 0.1152928546 0.1134388216 0.2390826792 0.0052660215 0.5079890000 0.0733060000 0.0471240000 0.0000000000 0.3847540000 0.0016930000 135902331 0 402718720 4.0181679726 3.9376001358 4.0516066551 321 1311867729.3236539364 0.1102036387 0.1134287432 0.2390826792 0.0052654437 0.9703880000 0.0865280000 0.0500110000 0.0343440000 0.3816010000 0.4168000000 135906059 0 402718720 4.0142245293 3.9392983913 4.0501723289 322 1311867729.3580930233 0.1064593345 0.1134070991 0.2390826792 0.0052700752 0.5419370000 0.0733190000 0.0838470000 0.0000010000 0.3819710000 0.0016930000 135909843 0 402718720 4.0117759705 3.9394090176 4.0486388206 323 1311867729.3882780075 0.1081426144 0.1133908003 0.2390826792 0.0052714607 0.5424630000 0.0732280000 0.0475760000 0.0343670000 0.3844470000 0.0017070000 135913403 0 402718720 4.0114121437 3.9383966923 4.0517334938 324 1311867729.4253289700 0.1050922200 0.1133651874 0.2390826792 0.0052669255 0.5398370000 0.0728190000 0.0789920000 0.0000010000 0.3852520000 0.0016590000 135917243 0 402718720 4.0096521378 3.9398300648 4.0509567261 325 1311867729.4572670460 0.1053689793 0.1133405837 0.2390826792 0.0052608087 0.9750290000 0.0706330000 0.0533110000 0.0340110000 0.3922510000 0.4237110000 135920915 0 402718720 4.0097370148 3.9387981892 4.0515489578 326 1311867729.4887750149 0.1032397524 0.1133095996 0.2390826792 0.0052696694 0.5386080000 0.0722570000 0.0786580000 0.0000010000 0.3848870000 0.0016850000 135924643 0 402718720 4.0093750954 3.9391846657 4.0497765541 327 1311867729.5223650932 0.1036228761 0.1132799766 0.2390826792 0.0052630682 0.5706870000 0.0727960000 0.0768880000 0.0341270000 0.3840630000 0.0016860000 135928315 0 402718720 4.0088186264 3.9382832050 4.0512599945 328 1311867729.5603790283 0.1011527330 0.1132430033 0.2390826792 0.0052587233 0.5559130000 0.0871220000 0.0826970000 0.0000000000 0.3832850000 0.0016840000 135932155 0 402718720 4.0079584122 3.9388818741 4.0496854782 329 1311867729.5890150070 0.1024237350 0.1132101180 0.2390826792 0.0052508371 0.9876310000 0.0718330000 0.0806510000 0.0339820000 0.3838930000 0.4161620000 135935715 0 402718720 4.0092673302 3.9378671646 4.0504698753 330 1311867729.6254830360 0.0989431292 0.1131668847 0.2390826792 0.0052465264 0.5348070000 0.0705510000 0.0775830000 0.0000010000 0.3838800000 0.0016760000 135939499 0 402718720 4.0071959496 3.9390983582 4.0490393639 331 1311867729.6614611149 0.0982820466 0.1131219154 0.2390826792 0.0052403479 0.5869770000 0.0721530000 0.0786160000 0.0340470000 0.3987510000 0.0022050000 135943283 0 402718720 4.0076022148 3.9391336441 4.0488429070 332 1311867729.6888220310 0.0961345062 0.1130707485 0.2390826792 0.0052340494 0.5354190000 0.0713870000 0.0777530000 0.0000010000 0.3834750000 0.0016730000 135946731 0 402718720 4.0059790611 3.9392023087 4.0475902557 333 1311867729.7230739594 0.0942778289 0.1130143133 0.2390826792 0.0052276667 0.9855910000 0.0855860000 0.0589380000 0.0339600000 0.3829900000 0.4229280000 135950515 0 402718720 4.0044689178 3.9397680759 4.0473957062 334 1311867729.7570610046 0.0892309621 0.1129431056 0.2390826792 0.0052260184 0.5854920000 0.0937580000 0.0966970000 0.0000010000 0.3922240000 0.0016830000 135954075 0 402718720 4.0031638145 3.9423630238 4.0435285568 335 1311867729.7899730206 0.0857869908 0.1128620426 0.2390826792 0.0052203223 0.5589840000 0.0733810000 0.0695860000 0.0340470000 0.3789650000 0.0017810000 135957803 0 402718720 4.0009994507 3.9428832531 4.0409660339 336 1311867729.8264250755 0.0833993033 0.1127743559 0.2390826792 0.0052246445 0.5134790000 0.0734620000 0.0555590000 0.0000010000 0.3816290000 0.0016840000 135961531 0 402718720 3.9980704784 3.9432604313 4.0410523415 337 1311867729.8550031185 0.0795280486 0.1126757021 0.2390826792 0.0052191207 0.9879040000 0.0741130000 0.0786900000 0.0339870000 0.3837570000 0.4162140000 135965091 0 402718720 3.9959936142 3.9452662468 4.0392012596 338 1311867729.8881840706 0.0781057328 0.1125734241 0.2390826792 0.0052194076 0.5565430000 0.0896890000 0.0828930000 0.0000010000 0.3811370000 0.0016810000 135968875 0 402718720 3.9962854385 3.9453396797 4.0369281769 339 1311867729.9233629704 0.0712033734 0.1124513886 0.2390826792 0.0052191606 0.5986430000 0.0959330000 0.0817380000 0.0339140000 0.3842330000 0.0016810000 135972603 0 402718720 3.9910957813 3.9481792450 4.0332937241 340 1311867729.9569330215 0.0714411885 0.1123307703 0.2390826792 0.0052122424 0.5243420000 0.0728330000 0.0650760000 0.0000000000 0.3836050000 0.0016860000 135976331 0 402718720 3.9920027256 3.9485979080 4.0337972641 341 1311867729.9865698814 0.0687104240 0.1122028514 0.2390826792 0.0052092118 0.9869650000 0.0735840000 0.0782800000 0.0339290000 0.3837280000 0.4163170000 135979891 0 402718720 3.9894356728 3.9488613605 4.0319037437 342 1311867730.0230469704 0.0659895167 0.1120677247 0.2390826792 0.0052028217 0.5177990000 0.0718670000 0.0587170000 0.0000000000 0.3843980000 0.0016830000 135983675 0 402718720 3.9874022007 3.9498054981 4.0303211212 343 1311867730.0557899475 0.0640094280 0.1119276131 0.2390826792 0.0051976569 0.5541350000 0.0870240000 0.0458570000 0.0335960000 0.3848140000 0.0016900000 135987403 0 402718720 3.9858520031 3.9509241581 4.0296950340 344 1311867730.0871100426 0.0641199201 0.1117886372 0.2390826792 0.0051902220 0.5058010000 0.0730960000 0.0460630000 0.0000000000 0.3838220000 0.0016820000 135991075 0 402718720 3.9860866070 3.9507999420 4.0295596123 345 1311867730.1231229305 0.0642583966 0.1116508684 0.2390826792 0.0051828219 0.9847470000 0.0731000000 0.0773660000 0.0333190000 0.3835850000 0.4162440000 135994859 0 402718720 3.9860618114 3.9508328438 4.0298609734 346 1311867730.1568520069 0.0618216395 0.1115068533 0.2390826792 0.0051764710 0.5174890000 0.0719650000 0.0582170000 0.0000010000 0.3845030000 0.0016690000 135998587 0 402718720 3.9860546589 3.9528303146 4.0277576447 347 1311867730.1882419586 0.0597105585 0.1113575844 0.2390826792 0.0051719361 0.5725330000 0.0737220000 0.0782580000 0.0332810000 0.3844360000 0.0016880000 136002203 0 402718720 3.9860639572 3.9543447495 4.0258007050 348 1311867730.2224810123 0.0592659973 0.1112078960 0.2390826792 0.0051650786 0.5594560000 0.0996200000 0.0757770000 0.0000010000 0.3812150000 0.0016850000 136005987 0 402718720 3.9856722355 3.9547502995 4.0261850357 349 1311867730.2575879097 0.0591323823 0.1110586825 0.2390826792 0.0051593201 0.9840620000 0.0728870000 0.0787840000 0.0337420000 0.3826600000 0.4148670000 136009715 0 402718720 3.9877920151 3.9561698437 4.0253148079 350 1311867730.2914879322 0.0597716048 0.1109121480 0.2390826792 0.0051537175 0.5393890000 0.0749770000 0.0793690000 0.0000010000 0.3822040000 0.0016920000 136013443 0 402718720 3.9886524677 3.9568052292 4.0264525414 351 1311867730.3230810165 0.0607289746 0.1107691760 0.2390826792 0.0051524325 0.5607650000 0.0750580000 0.0702560000 0.0338860000 0.3787100000 0.0016990000 136017115 0 402718720 3.9911248684 3.9573478699 4.0259561539 352 1311867730.3554260731 0.0583936013 0.1106203817 0.2390826792 0.0051516405 0.5035620000 0.0740030000 0.0468150000 0.0000010000 0.3799040000 0.0016910000 136020787 0 402718720 3.9878151417 3.9572257996 4.0255274773 353 1311867730.3982920647 0.0598917268 0.1104766745 0.2390826792 0.0051453761 1.0017590000 0.1024760000 0.0767560000 0.0336940000 0.3780820000 0.4096100000 136024739 0 402718720 3.9907748699 3.9579732418 4.0259261131 354 1311867730.4225230217 0.0609986596 0.1103369061 0.2390826792 0.0051514190 0.5408540000 0.0756740000 0.0849180000 0.0000010000 0.3774180000 0.0017050000 136028243 0 402718720 3.9930129051 3.9592628479 4.0265302658 355 1311867730.4600110054 0.0620461479 0.1102008758 0.2390826792 0.0051445968 0.5668790000 0.0741380000 0.0800540000 0.0330840000 0.3767310000 0.0016980000 136032027 0 402718720 3.9936537743 3.9586477280 4.0261883736 356 1311867730.4948410988 0.0642806143 0.1100718863 0.2390826792 0.0051394090 0.5334290000 0.0741530000 0.0800070000 0.0000010000 0.3764110000 0.0016890000 136035755 0 402718720 3.9964809418 3.9585304260 4.0266723633 357 1311867730.5300729275 0.0621843971 0.1099377476 0.2390826792 0.0051342182 0.9712010000 0.0996650000 0.0544040000 0.0335980000 0.3758560000 0.4065160000 136039483 0 402718720 3.9942116737 3.9592194557 4.0262360573 358 1311867730.5597670078 0.0637819469 0.1098088208 0.2390826792 0.0051290324 0.5001430000 0.0748650000 0.0474650000 0.0000010000 0.3749630000 0.0016960000 136043099 0 402718720 3.9955790043 3.9587786198 4.0271844864 359 1311867730.5940020084 0.0619701147 0.1096755654 0.2390826792 0.0051259249 0.5271160000 0.0745900000 0.0408390000 0.0335560000 0.3752430000 0.0017100000 136046883 0 402718720 3.9928576946 3.9587428570 4.0268712044 360 1311867730.6230149269 0.0626974851 0.1095450707 0.2390826792 0.0051289116 0.5197240000 0.0746200000 0.0711760000 0.0000000000 0.3710180000 0.0017320000 136050387 0 402718720 3.9963257313 3.9605855942 4.0268020630 361 1311867730.6614060402 0.0611424446 0.1094109914 0.2390826792 0.0051230449 0.9813360000 0.0883600000 0.0810710000 0.0334470000 0.3734690000 0.4038390000 136054227 0 402718720 3.9947013855 3.9606583118 4.0262508392 362 1311867730.6922950745 0.0607034825 0.1092764403 0.2390826792 0.0051170114 0.5440330000 0.0874050000 0.0809140000 0.0000010000 0.3728330000 0.0016950000 136057899 0 402718720 3.9958100319 3.9617002010 4.0256366730 363 1311867730.7275629044 0.0610892363 0.1091436932 0.2390826792 0.0051195020 0.5759270000 0.0850180000 0.0856820000 0.0331530000 0.3691790000 0.0017060000 136061627 0 402718720 3.9980883598 3.9625430107 4.0246877670 364 1311867730.7572948933 0.0623856857 0.1090152371 0.2390826792 0.0051159808 0.5166040000 0.0753220000 0.0676940000 0.0000010000 0.3707180000 0.0016920000 136065243 0 402718720 4.0005283356 3.9630024433 4.0249619484 365 1311867730.7932779789 0.0592488870 0.1088788909 0.2390826792 0.0051104959 0.9624150000 0.0756500000 0.0815300000 0.0335350000 0.3702460000 0.4002930000 136069083 0 402718720 3.9980702400 3.9640228748 4.0232181549 366 1311867730.8240480423 0.0617346056 0.1087500814 0.2390826792 0.0051065080 0.5358380000 0.1016650000 0.0642080000 0.0000010000 0.3670850000 0.0016880000 136072643 0 402718720 4.0007243156 3.9626111984 4.0233116150 367 1311867730.8591129780 0.0592622720 0.1086152372 0.2390826792 0.0051027084 0.5597710000 0.0739220000 0.0806070000 0.0333210000 0.3690390000 0.0016950000 136076427 0 402718720 3.9995126724 3.9642927647 4.0224175453 368 1311867730.8922739029 0.0590373240 0.1084805146 0.2390826792 0.0050974649 0.5530340000 0.0960800000 0.0854430000 0.0000010000 0.3686190000 0.0017080000 136079987 0 402718720 3.9997460842 3.9648413658 4.0233111382 369 1311867730.9270720482 0.0599740967 0.1083490609 0.2390826792 0.0050934405 0.9535090000 0.0732420000 0.0803480000 0.0333230000 0.3678400000 0.3975940000 136083771 0 402718720 4.0025262833 3.9659621716 4.0238213539 370 1311867730.9611239433 0.0598916635 0.1082180950 0.2390826792 0.0050906768 0.5182170000 0.0762340000 0.0714300000 0.0000000000 0.3674280000 0.0017100000 136087443 0 402718720 4.0032043457 3.9668104649 4.0246806145 371 1311867730.9928169250 0.0613410585 0.1080917418 0.2390826792 0.0050901174 0.5597250000 0.0739190000 0.0844370000 0.0333460000 0.3651180000 0.0017050000 136091115 0 402718720 4.0062050819 3.9667220116 4.0242438316 372 1311867731.0221049786 0.0618088134 0.1079673253 0.2390826792 0.0050839595 0.5030110000 0.0737400000 0.0610140000 0.0000010000 0.3653820000 0.0016700000 136094731 0 402718720 4.0072016716 3.9664661884 4.0243835449 373 1311867731.0609729290 0.0596285164 0.1078377307 0.2390826792 0.0050801912 0.9731480000 0.0879920000 0.0821870000 0.0333460000 0.3629330000 0.4054190000 136098571 0 402718720 4.0060873032 3.9677088261 4.0243825912 374 1311867731.0900061131 0.0613686293 0.1077134817 0.2390826792 0.0050773806 0.5411170000 0.0939630000 0.0820000000 0.0000010000 0.3622440000 0.0017050000 136102131 0 402718720 4.0083432198 3.9667360783 4.0246496201 375 1311867731.1276559830 0.0630804226 0.1075944602 0.2390826792 0.0050732208 0.5755340000 0.0963190000 0.0815850000 0.0332800000 0.3614190000 0.0017140000 136105971 0 402718720 4.0114421844 3.9662928581 4.0243282318 376 1311867731.1551880836 0.0616418011 0.1074722457 0.2390826792 0.0050671838 0.5211190000 0.0749450000 0.0818130000 0.0000000000 0.3614390000 0.0017100000 136109531 0 402718720 4.0109720230 3.9679007530 4.0253124237 377 1311867731.1935870647 0.0614802726 0.1073502511 0.2390826792 0.0050620468 0.9411140000 0.0752650000 0.0819620000 0.0331950000 0.3604540000 0.3890340000 136113315 0 402718720 4.0118961334 3.9682364464 4.0253062248 378 1311867731.2235820293 0.0622444041 0.1072309235 0.2390826792 0.0050553742 0.5370480000 0.0912310000 0.0832010000 0.0000010000 0.3596880000 0.0017150000 136116987 0 402718720 4.0131540298 3.9679851532 4.0261693001 379 1311867731.2602028847 0.0607576817 0.1071083028 0.2390826792 0.0050496721 0.5556380000 0.0751030000 0.0860280000 0.0332830000 0.3582860000 0.0017190000 136120715 0 402718720 4.0130634308 3.9688682556 4.0257601738 380 1311867731.2900059223 0.0604733713 0.1069855793 0.2390826792 0.0050743406 0.5202050000 0.0765590000 0.0830370000 0.0000000000 0.3576760000 0.0017190000 136124331 0 402718720 4.0140895844 3.9691858292 4.0257072449 381 1311867731.3230779171 0.0607441105 0.1068642106 0.2390826792 0.0051020107 0.9355480000 0.0768750000 0.0835890000 0.0332340000 0.3563370000 0.3843110000 136128059 0 402718720 4.0156111717 3.9691624641 4.0251336098 382 1311867731.3570859432 0.0685032383 0.1067637892 0.2390826792 0.0051304311 0.5019320000 0.0764350000 0.0560310000 0.0000000000 0.3659000000 0.0022800000 136131843 0 402718720 4.0259575844 3.9686686993 4.0254020691 383 1311867731.3915760517 0.0631579533 0.1066499358 0.2390826792 0.0051298930 0.5837690000 0.0973940000 0.0840690000 0.0416060000 0.3577340000 0.0017350000 136135515 0 402718720 4.0208735466 3.9688928127 4.0241045952 384 1311867731.4279849529 0.0639068708 0.1065386258 0.2390826792 0.0051256067 0.4869330000 0.0769770000 0.0589350000 0.0000010000 0.3478870000 0.0018240000 136139355 0 402718720 4.0226030350 3.9683318138 4.0231304169 385 1311867731.4602010250 0.0591347255 0.1064154988 0.2390826792 0.0051314899 0.8834230000 0.0764840000 0.0445360000 0.0332600000 0.3494920000 0.3784370000 136143027 0 402718720 4.0176758766 3.9685285091 4.0221142769 386 1311867731.4926180840 0.0551072545 0.1062825758 0.2390826792 0.0051313112 0.4792370000 0.0762290000 0.0492850000 0.0000010000 0.3507720000 0.0017270000 136146699 0 402718720 4.0147681236 3.9702372551 4.0207104683 387 1311867731.5259540081 0.0570000149 0.1061552307 0.2390826792 0.0051271373 0.5460080000 0.0768790000 0.0840260000 0.0331600000 0.3489650000 0.0017350000 136150371 0 402718720 4.0188355446 3.9708421230 4.0205020905 388 1311867731.5589148998 0.0549436100 0.1060232420 0.2390826792 0.0051267488 0.4961160000 0.0880240000 0.0592940000 0.0000010000 0.3458160000 0.0017390000 136154043 0 402718720 4.0183157921 3.9720354080 4.0195512772 389 1311867731.5967359543 0.0517031252 0.1058836016 0.2390826792 0.0051362243 0.9058900000 0.0758950000 0.0766160000 0.0329720000 0.3465920000 0.3725830000 136157939 0 402718720 4.0151114464 3.9726717472 4.0191583633 390 1311867731.6247410774 0.0522962622 0.1057461982 0.2390826792 0.0051384000 0.4667490000 0.0759580000 0.0444930000 0.0000010000 0.3433350000 0.0017300000 136161443 0 402718720 4.0154747963 3.9722440243 4.0195865631 391 1311867731.6616659164 0.0508494042 0.1056057972 0.2390826792 0.0051458826 0.5124210000 0.0756050000 0.0558740000 0.0325310000 0.3454350000 0.0017280000 136165283 0 402718720 4.0142536163 3.9726819992 4.0196652412 392 1311867731.6925039291 0.0501520671 0.1054643336 0.2390826792 0.0051476645 0.4729610000 0.0752770000 0.0490110000 0.0000000000 0.3457110000 0.0017240000 136168899 0 402718720 4.0144534111 3.9731853008 4.0195107460 393 1311867731.7299311161 0.0481782034 0.1053185673 0.2390826792 0.0051427233 0.9051910000 0.0874040000 0.0698730000 0.0327790000 0.3443920000 0.3695240000 136172739 0 402718720 4.0120940208 3.9727807045 4.0198154449 394 1311867731.7615330219 0.0463391766 0.1051688734 0.2390826792 0.0051383156 0.5070390000 0.0762670000 0.0839710000 0.0000010000 0.3438250000 0.0017380000 136176411 0 402718720 4.0102806091 3.9727683067 4.0195908546 395 1311867731.7939310074 0.0445605405 0.1050154346 0.2390826792 0.0051333969 0.5364840000 0.0746760000 0.0834490000 0.0324380000 0.3429390000 0.0017250000 136180083 0 402718720 4.0087518692 3.9731590748 4.0196371078 396 1311867731.8252151012 0.0469500721 0.1048688049 0.2390826792 0.0051426953 0.5052920000 0.0760300000 0.0838120000 0.0000010000 0.3424480000 0.0017500000 136183699 0 402718720 4.0115747452 3.9716634750 4.0193495750 397 1311867731.8593230247 0.0444373861 0.1047165847 0.2390826792 0.0051570977 0.8879740000 0.0760420000 0.0700120000 0.0328820000 0.3415710000 0.3662290000 136187427 0 402718720 4.0092267990 3.9719808102 4.0187406540 398 1311867731.8910930157 0.0446804166 0.1045657401 0.2390826792 0.0051639883 0.4934960000 0.0935280000 0.0562720000 0.0000000000 0.3407150000 0.0017290000 136191155 0 402718720 4.0106730461 3.9721932411 4.0183062553 399 1311867731.9224479198 0.0456193462 0.1044180048 0.2390826792 0.0051585854 0.5373100000 0.0753990000 0.0864320000 0.0327490000 0.3397340000 0.0017250000 136194827 0 402718720 4.0126686096 3.9721105099 4.0177750587 400 1311867731.9598410130 0.0451604910 0.1042698610 0.2390826792 0.0051524653 0.5018030000 0.0756540000 0.0838180000 0.0000010000 0.3393640000 0.0017270000 136198555 0 402718720 4.0129833221 3.9722352028 4.0173306465 401 1311867731.9915709496 0.0409654453 0.1041119946 0.2390826792 0.0051525451 0.8954540000 0.0759320000 0.0838480000 0.0323740000 0.3386830000 0.3633760000 136202227 0 402718720 4.0091543198 3.9735517502 4.0165786743 402 1311867732.0239229202 0.0398976319 0.1039522574 0.2390826792 0.0051544267 0.5119100000 0.0869560000 0.0838710000 0.0000010000 0.3380970000 0.0017150000 136205899 0 402718720 4.0081310272 3.9722857475 4.0159339905 403 1311867732.0619950294 0.0403524041 0.1037944414 0.2390826792 0.0051495110 0.5670820000 0.1097050000 0.0835550000 0.0326880000 0.3381250000 0.0017310000 136209739 0 402718720 4.0089788437 3.9722526073 4.0150284767 404 1311867732.0918290615 0.0376938619 0.1036308261 0.2390826792 0.0051500355 0.5014150000 0.0751560000 0.0879420000 0.0000010000 0.3351580000 0.0018250000 136213355 0 402718720 4.0068044662 3.9732995033 4.0141458511 405 1311867732.1221950054 0.0379034318 0.1034685362 0.2390826792 0.0051488822 0.8712950000 0.0745500000 0.0624440000 0.0321270000 0.3382590000 0.3626600000 136217027 0 402718720 4.0070405006 3.9721634388 4.0132627487 406 1311867732.1605980396 0.0359127969 0.1033021428 0.2390826792 0.0051476685 0.5006900000 0.0751320000 0.0829500000 0.0000000000 0.3396230000 0.0017110000 136220811 0 402718720 4.0056114197 3.9729166031 4.0124258995 407 1311867732.1931400299 0.0352670699 0.1031349804 0.2390826792 0.0051554378 0.5182610000 0.0744430000 0.0688190000 0.0325400000 0.3394790000 0.0017080000 136224539 0 402718720 4.0069055557 3.9740855694 4.0116858482 408 1311867732.2232089043 0.0349089913 0.1029677599 0.2390826792 0.0051788142 0.5105280000 0.0852310000 0.0825240000 0.0000010000 0.3397720000 0.0017190000 136228099 0 402718720 4.0060343742 3.9731893539 4.0108504295 409 1311867732.2590498924 0.0336244181 0.1027982162 0.2390826792 0.0052466243 0.8878230000 0.0742620000 0.0754670000 0.0325440000 0.3397600000 0.3645310000 136231883 0 402718720 4.0060873032 3.9752674103 4.0103001595 410 1311867732.2903969288 0.0317291543 0.1026248771 0.2390826792 0.0052636429 0.4996890000 0.0740760000 0.0863270000 0.0000010000 0.3361340000 0.0018070000 136235555 0 402718720 4.0033988953 3.9747345448 4.0103588104 411 1311867732.3218240738 0.0316494368 0.1024521874 0.2390826792 0.0052605904 0.5000830000 0.0743860000 0.0511320000 0.0326620000 0.3388990000 0.0017270000 136239227 0 402718720 4.0032734871 3.9739525318 4.0096044540 412 1311867732.3607840538 0.0316070877 0.1022802333 0.2390826792 0.0052542494 0.5046390000 0.0739610000 0.0755130000 0.0000010000 0.3515060000 0.0022930000 136243067 0 402718720 4.0055956841 3.9750516415 4.0089869499 413 1311867732.3899528980 0.0301954430 0.1021056939 0.2390826792 0.0052489901 0.9181940000 0.0928210000 0.0906600000 0.0318250000 0.3387750000 0.3628380000 136246627 0 402718720 4.0045495033 3.9753205776 4.0084400177 414 1311867732.4218940735 0.0308338739 0.1019335397 0.2390826792 0.0052448484 0.5012630000 0.0738930000 0.0866950000 0.0000010000 0.3377090000 0.0016820000 136250355 0 402718720 4.0058073997 3.9741735458 4.0074973106 415 1311867732.4593050480 0.0289259423 0.1017576178 0.2390826792 0.0052428234 0.5299020000 0.0739310000 0.0819140000 0.0323750000 0.3386720000 0.0017170000 136254139 0 402718720 4.0053467751 3.9756922722 4.0069546700 416 1311867732.4918489456 0.0273321271 0.1015787104 0.2390826792 0.0052403601 0.5007100000 0.0731630000 0.0860130000 0.0000010000 0.3385210000 0.0017290000 136257867 0 402718720 4.0032010078 3.9754474163 4.0063996315 417 1311867732.5229809284 0.0287121125 0.1014039703 0.2390826792 0.0052426374 0.8900160000 0.0749130000 0.0827950000 0.0323840000 0.3375700000 0.3610810000 136261483 0 402718720 4.0078544617 3.9762015343 4.0053634644 418 1311867732.5698928833 0.0256873742 0.1012228301 0.2390826792 0.0052408155 0.4805750000 0.0845370000 0.0554120000 0.0000010000 0.3376250000 0.0017210000 136265547 0 402718720 4.0057654381 3.9780371189 4.0052285194 419 1311867732.5926280022 0.0238790661 0.1010382388 0.2390826792 0.0052379713 0.5303530000 0.0734110000 0.0864530000 0.0322840000 0.3351800000 0.0017310000 136268995 0 402718720 4.0028619766 3.9780380726 4.0048623085 420 1311867732.6242370605 0.0243979003 0.1008557618 0.2390826792 0.0052398872 0.4676440000 0.0736330000 0.0549300000 0.0000010000 0.3360820000 0.0017180000 136272667 0 402718720 4.0048503876 3.9778563976 4.0040712357 421 1311867732.6630299091 0.0223947596 0.1006693936 0.2390826792 0.0052369506 0.8869340000 0.0742950000 0.0874390000 0.0323380000 0.3340270000 0.3575520000 136276507 0 402718720 4.0028305054 3.9787302017 4.0042185783 422 1311867732.6922440529 0.0216775090 0.1004822091 0.2390826792 0.0052334204 0.4946680000 0.0745280000 0.0830630000 0.0000010000 0.3340500000 0.0017280000 136280123 0 402718720 4.0037794113 3.9802253246 4.0040826797 423 1311867732.7260940075 0.0219668597 0.1002965936 0.2390826792 0.0052278435 0.5234360000 0.1068580000 0.0519520000 0.0317530000 0.3296490000 0.0018390000 136283851 0 402718720 4.0032644272 3.9791650772 4.0034885406 424 1311867732.7601239681 0.0201872513 0.1001076565 0.2390826792 0.0052298864 0.4660350000 0.0736430000 0.0582220000 0.0000010000 0.3311480000 0.0017180000 136287523 0 402718720 3.9996683598 3.9796142578 4.0031466484 425 1311867732.7919039726 0.0200054944 0.0999191808 0.2390826792 0.0052257365 0.8685340000 0.0743800000 0.0556940000 0.0321160000 0.3387180000 0.3663360000 136291251 0 402718720 4.0021171570 3.9812941551 4.0030221939 426 1311867732.8280360699 0.0196235739 0.0997306934 0.2390826792 0.0052254290 0.4905930000 0.0739090000 0.0829570000 0.0000010000 0.3307120000 0.0017140000 136294979 0 402718720 3.9986526966 3.9801847935 4.0024743080 427 1311867732.8589270115 0.0187754817 0.0995411028 0.2390826792 0.0052216764 0.4933000000 0.0726940000 0.0550840000 0.0317960000 0.3306810000 0.0017340000 136298651 0 402718720 3.9986617565 3.9814264774 4.0023603439 428 1311867732.8912909031 0.0178745706 0.0993502931 0.2390826792 0.0052194470 0.5020570000 0.0856850000 0.0836580000 0.0000010000 0.3296780000 0.0017290000 136302323 0 402718720 3.9962928295 3.9821488857 4.0023422241 429 1311867732.9262781143 0.0174363591 0.0991593516 0.2390826792 0.0052136858 0.8660960000 0.0753430000 0.0840980000 0.0319160000 0.3271530000 0.3462880000 136306107 0 402718720 3.9974544048 3.9832234383 4.0026555061 430 1311867732.9602870941 0.0182893425 0.0989712818 0.2390826792 0.0052134479 0.5004780000 0.0878470000 0.0838420000 0.0000010000 0.3257450000 0.0017330000 136309779 0 402718720 3.9958214760 3.9815216064 4.0026688576 431 1311867732.9987640381 0.0179099366 0.0987832044 0.2390826792 0.0052095027 0.5302990000 0.0878770000 0.0832040000 0.0316910000 0.3244660000 0.0017410000 136313675 0 402718720 3.9978663921 3.9821045399 4.0026268959 432 1311867733.0276939869 0.0175248478 0.0985951064 0.2390826792 0.0052084543 0.4854710000 0.0746470000 0.0834570000 0.0000010000 0.3243620000 0.0016920000 136317291 0 402718720 3.9938120842 3.9825100899 4.0033159256 433 1311867733.0607628822 0.0189672690 0.0984112083 0.2390826792 0.0052251818 0.8889220000 0.1106610000 0.0840590000 0.0318170000 0.3218220000 0.3392390000 136320963 0 402718720 3.9946691990 3.9803791046 4.0032439232 434 1311867733.0977020264 0.0177815855 0.0982254258 0.2390826792 0.0052219757 0.4753260000 0.0752780000 0.0733760000 0.0000010000 0.3229470000 0.0023160000 136324747 0 402718720 3.9941987991 3.9817028046 4.0033130646 435 1311867733.1263020039 0.0173337664 0.0980394680 0.2390826792 0.0052201487 0.5852160000 0.0949520000 0.1120300000 0.0387260000 0.3357430000 0.0023230000 136328307 0 402718720 3.9907815456 3.9831357002 4.0038132668 436 1311867733.1625030041 0.0199601036 0.0978603869 0.2390826792 0.0052212048 0.4964590000 0.0883870000 0.0845700000 0.0000010000 0.3204270000 0.0017420000 136332091 0 402718720 3.9895946980 3.9799501896 4.0035562515 437 1311867733.1926651001 0.0195657574 0.0976812229 0.2390826792 0.0052192453 0.8511300000 0.0754280000 0.0844800000 0.0317530000 0.3209050000 0.3372550000 136335707 0 402718720 3.9883837700 3.9808731079 4.0035991669 438 1311867733.2259631157 0.0184836779 0.0975004066 0.2390826792 0.0052167994 0.4751370000 0.0858950000 0.0667740000 0.0000010000 0.3194060000 0.0017370000 136339435 0 402718720 3.9890930653 3.9825940132 4.0039443970 439 1311867733.2618060112 0.0201959182 0.0973243144 0.2390826792 0.0052151501 0.5131030000 0.0747130000 0.0846180000 0.0315650000 0.3191320000 0.0017470000 136343219 0 402718720 3.9862504005 3.9820268154 4.0040249825 440 1311867733.2919199467 0.0212747566 0.0971514745 0.2390826792 0.0052106522 0.4478550000 0.0758300000 0.0498950000 0.0000000000 0.3190530000 0.0017410000 136346779 0 402718720 3.9844651222 3.9815022945 4.0036931038 441 1311867733.3300418854 0.0201802272 0.0969769365 0.2390826792 0.0052180032 0.8474060000 0.0750340000 0.0887710000 0.0316190000 0.3173070000 0.3333620000 136350619 0 402718720 3.9861388206 3.9818148613 4.0036211014 442 1311867733.3602790833 0.0204226617 0.0968037368 0.2390826792 0.0052152639 0.5096790000 0.1005820000 0.0898670000 0.0000010000 0.3161250000 0.0017620000 136354291 0 402718720 3.9872753620 3.9805727005 4.0030703545 443 1311867733.3923840523 0.0226298366 0.0966363014 0.2390826792 0.0052172996 0.4783880000 0.0749930000 0.0524240000 0.0310790000 0.3167960000 0.0017600000 136357963 0 402718720 3.9836113453 3.9805779457 4.0029644966 444 1311867733.4289550781 0.0223851167 0.0964690690 0.2390826792 0.0052142755 0.4468540000 0.0744080000 0.0521640000 0.0000000000 0.3171860000 0.0017510000 136361747 0 402718720 3.9828910828 3.9823338985 4.0029459000 445 1311867733.4588150978 0.0220605861 0.0963018589 0.2390826792 0.0052115864 0.8441280000 0.0742720000 0.0863350000 0.0314310000 0.3181310000 0.3326250000 136365251 0 402718720 3.9837582111 3.9818053246 4.0024671555 446 1311867733.4956119061 0.0223213807 0.0961359834 0.2390826792 0.0052069239 0.4798690000 0.0745130000 0.0836790000 0.0000010000 0.3186010000 0.0017350000 136368923 0 402718720 3.9833450317 3.9820046425 4.0022554398 447 1311867733.5290400982 0.0225767735 0.0959714214 0.2390826792 0.0052046583 0.4748070000 0.0727910000 0.0492550000 0.0313970000 0.3182790000 0.0017450000 136372651 0 402718720 3.9821901321 3.9829828739 4.0023703575 448 1311867733.5630290508 0.0221537910 0.0958066499 0.2390826792 0.0051990514 0.4442270000 0.0876790000 0.0358010000 0.0000010000 0.3176560000 0.0017500000 136376379 0 402718720 3.9829947948 3.9829399586 4.0021710396 449 1311867733.5922229290 0.0253725294 0.0956497810 0.2390826792 0.0051979993 0.8400290000 0.0749950000 0.0843080000 0.0314320000 0.3173080000 0.3306600000 136379939 0 402718720 3.9799416065 3.9813861847 4.0018754005 450 1311867733.6283020973 0.0264656413 0.0954960385 0.2390826792 0.0051942778 0.4456970000 0.0749520000 0.0521960000 0.0000010000 0.3152760000 0.0018460000 136383723 0 402718720 3.9788002968 3.9815201759 4.0020976067 451 1311867733.6601879597 0.0259417091 0.0953418160 0.2390826792 0.0051889256 0.4841790000 0.0750050000 0.0595230000 0.0313840000 0.3151340000 0.0017650000 136387395 0 402718720 3.9791166782 3.9819757938 4.0017900467 452 1311867733.6917510033 0.0265616607 0.0951896476 0.2390826792 0.0051847457 0.4552490000 0.0862850000 0.0495220000 0.0000010000 0.3163250000 0.0017630000 136391067 0 402718720 3.9788067341 3.9814150333 4.0015282631 453 1311867733.7288239002 0.0281696990 0.0950417006 0.2390826792 0.0051816163 0.8677520000 0.1044700000 0.0887220000 0.0312470000 0.3142980000 0.3276560000 136394851 0 402718720 3.9779357910 3.9802360535 4.0014877319 454 1311867733.7597820759 0.0312222634 0.0949011292 0.2390826792 0.0051777785 0.4808740000 0.0744650000 0.0885560000 0.0000010000 0.3145560000 0.0018600000 136398411 0 402718720 3.9749066830 3.9796674252 4.0018544197 455 1311867733.7924160957 0.0301174205 0.0947587474 0.2390826792 0.0052022631 0.5081000000 0.0742420000 0.0834140000 0.0311520000 0.3161780000 0.0017540000 136402083 0 402718720 3.9761078358 3.9799263477 4.0019125938 456 1311867733.8282589912 0.0346680172 0.0946269695 0.2390826792 0.0052077180 0.4519260000 0.0749650000 0.0565650000 0.0000010000 0.3172720000 0.0017560000 136405867 0 402718720 3.9727032185 3.9778866768 4.0015277863 457 1311867733.8608579636 0.0318247117 0.0944895466 0.2390826792 0.0052047906 0.8351560000 0.0747190000 0.0835210000 0.0306770000 0.3168960000 0.3279930000 136409427 0 402718720 3.9756240845 3.9790861607 4.0009799004 458 1311867733.8918149471 0.0334235243 0.0943562147 0.2390826792 0.0052005810 0.4913680000 0.0867740000 0.0837790000 0.0000010000 0.3176920000 0.0017670000 136412987 0 402718720 3.9741587639 3.9793019295 4.0009012222 459 1311867733.9289460182 0.0349860340 0.0942268679 0.2390826792 0.0051956021 0.4779320000 0.0751860000 0.0522910000 0.0312100000 0.3160980000 0.0017720000 136416771 0 402718720 3.9735019207 3.9778656960 4.0003862381 460 1311867733.9595899582 0.0386527702 0.0941060546 0.2390826792 0.0052013701 0.4921180000 0.0874590000 0.0836410000 0.0000000000 0.3178950000 0.0017610000 136420443 0 402718720 3.9703683853 3.9761891365 4.0002775192 461 1311867733.9941790104 0.0385153145 0.0939854674 0.2390826792 0.0051983865 0.8188820000 0.0731920000 0.0685750000 0.0310160000 0.3173590000 0.3273700000 136424171 0 402718720 3.9711956978 3.9764025211 4.0004920959 462 1311867734.0275731087 0.0437980853 0.0938768367 0.2390826792 0.0052148207 0.4995320000 0.0951620000 0.0827440000 0.0000000000 0.3185080000 0.0017440000 136427955 0 402718720 3.9665832520 3.9735453129 4.0006060600 463 1311867734.0599920750 0.0425381660 0.0937659540 0.2390826792 0.0052095285 0.4816610000 0.0735310000 0.0583730000 0.0309680000 0.3156500000 0.0017540000 136431571 0 402718720 3.9682221413 3.9735388756 4.0003080368 464 1311867734.0956780910 0.0417957343 0.0936539492 0.2390826792 0.0052056621 0.4517320000 0.0743620000 0.0588360000 0.0000010000 0.3152090000 0.0018620000 136435355 0 402718720 3.9690716267 3.9741249084 4.0003118515 465 1311867734.1274170876 0.0445503332 0.0935483500 0.2390826792 0.0052034533 0.8338130000 0.0734610000 0.0856090000 0.0309090000 0.3167650000 0.3256880000 136439083 0 402718720 3.9674847126 3.9714431763 3.9998824596 466 1311867734.1618878841 0.0438889898 0.0934417849 0.2390826792 0.0052039291 0.4764750000 0.0738580000 0.0821950000 0.0000010000 0.3173500000 0.0017080000 136442755 0 402718720 3.9680256844 3.9727058411 3.9995286465 467 1311867734.1942350864 0.0431293398 0.0933340495 0.2390826792 0.0051999787 0.5070010000 0.0739990000 0.0823470000 0.0307700000 0.3167780000 0.0017180000 136446483 0 402718720 3.9687194824 3.9740922451 3.9995062351 468 1311867734.2291829586 0.0468022041 0.0932346224 0.2390826792 0.0052029896 0.4895230000 0.0863480000 0.0832760000 0.0000010000 0.3167670000 0.0017630000 136450155 0 402718720 3.9660077095 3.9713962078 3.9993450642 469 1311867734.2607750893 0.0452972427 0.0931324105 0.2390826792 0.0051995860 0.8078110000 0.0743230000 0.0624200000 0.0309570000 0.3154830000 0.3232380000 136453827 0 402718720 3.9673511982 3.9726884365 3.9992048740 470 1311867734.2941219807 0.0445371568 0.0930290164 0.2390826792 0.0051970005 0.4715130000 0.0720290000 0.0814900000 0.0000010000 0.3148660000 0.0017480000 136457499 0 402718720 3.9680273533 3.9737765789 3.9995896816 471 1311867734.3263280392 0.0437649228 0.0929244217 0.2390826792 0.0051946469 0.4768090000 0.0743330000 0.0557070000 0.0308970000 0.3127130000 0.0017570000 136461171 0 402718720 3.9692022800 3.9734961987 3.9994828701 472 1311867734.3610401154 0.0445784926 0.0928219939 0.2390826792 0.0051915576 0.4985930000 0.0975130000 0.0875010000 0.0000010000 0.3104190000 0.0017540000 136464899 0 402718720 3.9688682556 3.9727981091 3.9998037815 473 1311867734.3941841125 0.0457489565 0.0927224737 0.2390826792 0.0051954960 0.8233500000 0.0748390000 0.0880320000 0.0309210000 0.3099160000 0.3182730000 136468627 0 402718720 3.9674463272 3.9740264416 4.0005302429 474 1311867734.4276480675 0.0463017710 0.0926245398 0.2390826792 0.0051900515 0.4438580000 0.0745220000 0.0558810000 0.0000010000 0.3103150000 0.0017500000 136472355 0 402718720 3.9671282768 3.9737284184 4.0006923676 475 1311867734.4586091042 0.0462794378 0.0925269711 0.2390826792 0.0051864185 0.4966980000 0.0728460000 0.0805760000 0.0307010000 0.3094550000 0.0017190000 136475971 0 402718720 3.9674949646 3.9729645252 4.0010395050 476 1311867734.4938759804 0.0467919409 0.0924308891 0.2390826792 0.0051818993 0.4699400000 0.0750340000 0.0837450000 0.0000000000 0.3080140000 0.0017450000 136479755 0 402718720 3.9669470787 3.9741051197 4.0014815331 477 1311867734.5300569534 0.0478411391 0.0923374096 0.2390826792 0.0051773987 0.8065690000 0.0758370000 0.0843800000 0.0309250000 0.3037700000 0.3102740000 136483539 0 402718720 3.9662230015 3.9738411903 4.0020885468 478 1311867734.5595300198 0.0474722646 0.0922435494 0.2390826792 0.0051758332 0.4667640000 0.0744640000 0.0881720000 0.0000010000 0.3008070000 0.0018520000 136487099 0 402718720 3.9671955109 3.9734706879 4.0024356842 479 1311867734.5953910351 0.0494629256 0.0921542371 0.2390826792 0.0051735856 0.4989190000 0.0754790000 0.0889950000 0.0309210000 0.3003500000 0.0017630000 136490827 0 402718720 3.9648032188 3.9741821289 4.0034842491 480 1311867734.6285231113 0.0475087352 0.0920612256 0.2390826792 0.0051690732 0.4743140000 0.0732900000 0.0830430000 0.0000000000 0.3141200000 0.0023400000 136494555 0 402718720 3.9673056602 3.9743030071 4.0031175613 481 1311867734.6593229771 0.0487554073 0.0919711927 0.2390826792 0.0051640539 0.8532240000 0.0952910000 0.1118910000 0.0373970000 0.3010950000 0.3061570000 136498171 0 402718720 3.9661393166 3.9736847878 4.0030503273 482 1311867734.6947479248 0.0484747589 0.0918809511 0.2390826792 0.0051605596 0.4404220000 0.0938640000 0.0447600000 0.0000010000 0.2986320000 0.0017500000 136501899 0 402718720 3.9663827419 3.9734387398 4.0032734871 483 1311867734.7310240269 0.0484939143 0.0917911229 0.2390826792 0.0051596001 0.5151310000 0.0974630000 0.0845340000 0.0309010000 0.2990480000 0.0017640000 136505739 0 402718720 3.9668371677 3.9732627869 4.0032773018 484 1311867734.7607629299 0.0481088012 0.0917008702 0.2390826792 0.0051545764 0.4672810000 0.0766710000 0.0900260000 0.0000000000 0.2974020000 0.0017630000 136509299 0 402718720 3.9677481651 3.9731590748 4.0031628609 485 1311867734.7976419926 0.0494206473 0.0916136945 0.2390826792 0.0051517979 0.7969710000 0.0768250000 0.0854660000 0.0309310000 0.2983350000 0.3040160000 136513139 0 402718720 3.9664256573 3.9737069607 4.0035915375 486 1311867734.8298120499 0.0500962064 0.0915282675 0.2390826792 0.0051484239 0.4640570000 0.0766460000 0.0854520000 0.0000010000 0.2987790000 0.0017610000 136516811 0 402718720 3.9658854008 3.9742479324 4.0038866997 487 1311867734.8645250797 0.0516036786 0.0914462869 0.2390826792 0.0051450881 0.4930500000 0.0771190000 0.0858030000 0.0309090000 0.2960120000 0.0017780000 136520539 0 402718720 3.9643070698 3.9756782055 4.0046873093 488 1311867734.8943901062 0.0495625176 0.0913604595 0.2390826792 0.0051465199 0.4307630000 0.0869020000 0.0457130000 0.0000010000 0.2949570000 0.0017620000 136524211 0 402718720 3.9668679237 3.9747827053 4.0043048859 489 1311867734.9263660908 0.0492891446 0.0912744241 0.2390826792 0.0051414274 0.7510100000 0.0749470000 0.0498080000 0.0306670000 0.2942410000 0.2999270000 136527827 0 402718720 3.9676103592 3.9744050503 4.0045928955 490 1311867734.9631719589 0.0514017679 0.0911930513 0.2390826792 0.0051400458 0.4713790000 0.0770840000 0.0859930000 0.0000000000 0.3043850000 0.0023700000 136531387 0 402718720 3.9660234451 3.9742703438 4.0045576096 491 1311867734.9948470592 0.0503490902 0.0911098660 0.2390826792 0.0051427813 0.5555140000 0.0970670000 0.1134900000 0.0373960000 0.3043670000 0.0017660000 136535059 0 402718720 3.9666793346 3.9743988514 4.0042371750 492 1311867735.0292239189 0.0505314358 0.0910273895 0.2390826792 0.0051430284 0.4776080000 0.0927550000 0.0901260000 0.0000010000 0.2915320000 0.0017720000 136538899 0 402718720 3.9667642117 3.9748098850 4.0040955544 493 1311867735.0596508980 0.0529544018 0.0909501624 0.2390826792 0.0051398525 0.7809840000 0.0772320000 0.0832920000 0.0309240000 0.2906420000 0.2974780000 136542403 0 402718720 3.9640989304 3.9752035141 4.0045557022 494 1311867735.0952830315 0.0503146872 0.0908679043 0.2390826792 0.0051450253 0.4577140000 0.0770050000 0.0860030000 0.0000000000 0.2915120000 0.0017600000 136546187 0 402718720 3.9669241905 3.9748003483 4.0042881966 495 1311867735.1313030720 0.0508007221 0.0907869605 0.2390826792 0.0051433879 0.4618690000 0.0764810000 0.0602680000 0.0308650000 0.2910560000 0.0017600000 136549971 0 402718720 3.9663445950 3.9755005836 4.0045595169 496 1311867735.1603751183 0.0510540903 0.0907068540 0.2390826792 0.0051383263 0.4710510000 0.0904490000 0.0858040000 0.0000010000 0.2916020000 0.0017660000 136553531 0 402718720 3.9662656784 3.9753060341 4.0047507286 497 1311867735.1994349957 0.0525905192 0.0906301611 0.2390826792 0.0051364710 0.8022420000 0.0901000000 0.0906790000 0.0304000000 0.2917260000 0.2979070000 136557371 0 402718720 3.9651715755 3.9739463329 4.0051040649 498 1311867735.2263538837 0.0517199785 0.0905520282 0.2390826792 0.0051346047 0.4813230000 0.0941290000 0.0908200000 0.0000010000 0.2931520000 0.0017810000 136560987 0 402718720 3.9658508301 3.9753329754 4.0053324699 499 1311867735.2655019760 0.0512878560 0.0904733425 0.2390826792 0.0051298282 0.4558290000 0.0757940000 0.0503270000 0.0306630000 0.2958090000 0.0017740000 136564771 0 402718720 3.9662685394 3.9762017727 4.0056223869 500 1311867735.2961549759 0.0529534258 0.0903983027 0.2390826792 0.0051325203 0.4330210000 0.0758150000 0.0573560000 0.0000010000 0.2966690000 0.0017360000 136568443 0 402718720 3.9649119377 3.9749348164 4.0064201355 501 1311867735.3321089745 0.0517683253 0.0903211969 0.2390826792 0.0051309883 0.7603190000 0.0775610000 0.0511390000 0.0308860000 0.2968840000 0.3024050000 136572227 0 402718720 3.9659965038 3.9762372971 4.0067024231 502 1311867735.3666970730 0.0526000410 0.0902460552 0.2390826792 0.0051337735 0.4527560000 0.0992100000 0.0540220000 0.0000010000 0.2962970000 0.0017800000 136575843 0 402718720 3.9655241966 3.9754998684 4.0070862770 503 1311867735.3943350315 0.0531726032 0.0901723505 0.2390826792 0.0051467886 0.5191550000 0.0960710000 0.0925610000 0.0308910000 0.2963770000 0.0017940000 136579347 0 402718720 3.9651918411 3.9757411480 4.0073876381 504 1311867735.4322299957 0.0554688908 0.0901034944 0.2390826792 0.0051488207 0.4718590000 0.0789760000 0.0923680000 0.0000010000 0.2972760000 0.0017930000 136583243 0 402718720 3.9628388882 3.9766466618 4.0077877045 505 1311867735.4628560543 0.0537098646 0.0900314278 0.2390826792 0.0051457127 0.7982020000 0.0780550000 0.0865030000 0.0308050000 0.2977490000 0.3036500000 136586859 0 402718720 3.9653434753 3.9767823219 4.0077261925 506 1311867735.4973869324 0.0555948094 0.0899633713 0.2390826792 0.0051446150 0.4664720000 0.0782230000 0.0871160000 0.0000000000 0.2978960000 0.0017810000 136590643 0 402718720 3.9630501270 3.9770438671 4.0084142685 507 1311867735.5293200016 0.0555386320 0.0898954724 0.2390826792 0.0051401360 0.4544690000 0.0788190000 0.0441560000 0.0308500000 0.2973950000 0.0017870000 136594259 0 402718720 3.9633572102 3.9769876003 4.0087828636 508 1311867735.5632629395 0.0550655238 0.0898269095 0.2390826792 0.0051357763 0.4835930000 0.0952000000 0.0876600000 0.0000010000 0.2974780000 0.0017800000 136598043 0 402718720 3.9641721249 3.9764187336 4.0090122223 509 1311867735.5976569653 0.0559186600 0.0897602921 0.2390826792 0.0051312024 0.7567680000 0.0785490000 0.0442320000 0.0308530000 0.2975500000 0.3041410000 136601771 0 402718720 3.9635064602 3.9765784740 4.0092153549 510 1311867735.6363260746 0.0581963658 0.0896984021 0.2390826792 0.0051312547 0.4682020000 0.0788500000 0.0879050000 0.0000010000 0.2981950000 0.0017810000 136605555 0 402718720 3.9615597725 3.9758336544 4.0094432831 511 1311867735.6626520157 0.0574720688 0.0896353368 0.2390826792 0.0051308434 0.4636390000 0.0791530000 0.0518440000 0.0303720000 0.2990140000 0.0017970000 136609115 0 402718720 3.9626338482 3.9749710560 4.0092277527 512 1311867735.6952130795 0.0555147305 0.0895686950 0.2390826792 0.0051300081 0.4407600000 0.0787320000 0.0589180000 0.0000010000 0.2998670000 0.0017800000 136612787 0 402718720 3.9646594524 3.9749884605 4.0086822510 513 1311867735.7291250229 0.0556843169 0.0895026436 0.2390826792 0.0051291298 0.8324390000 0.1047600000 0.0921910000 0.0308830000 0.2978570000 0.3052910000 136665667 0 402718720 3.9646170139 3.9755079746 4.0084600449 514 1311867735.7631659508 0.0561041012 0.0894376659 0.2390826792 0.0051284613 0.4684960000 0.0784260000 0.0869920000 0.0000010000 0.2998310000 0.0017710000 136771851 0 402718720 3.9641325474 3.9769515991 4.0085349083 515 1311867735.7963778973 0.0557418317 0.0893722371 0.2390826792 0.0051299436 0.4982740000 0.0781780000 0.0867090000 0.0303660000 0.2997590000 0.0017690000 136775523 0 402718720 3.9647531509 3.9769051075 4.0084743500 516 1311867735.8277759552 0.0571215041 0.0893097357 0.2390826792 0.0051363056 0.4539960000 0.0776310000 0.0724930000 0.0000000000 0.3006240000 0.0017710000 136779139 0 402718720 3.9634969234 3.9778196812 4.0085821152 517 1311867735.8638889790 0.0574845038 0.0892481782 0.2390826792 0.0051326677 0.8040020000 0.0784220000 0.0864230000 0.0306470000 0.3001790000 0.3068580000 136782755 0 402718720 3.9632878304 3.9780423641 4.0089011192 518 1311867735.8951849937 0.0582210384 0.0891882802 0.2390826792 0.0051291895 0.4748090000 0.0790500000 0.0922160000 0.0000010000 0.3002910000 0.0017770000 136786427 0 402718720 3.9625818729 3.9786224365 4.0095725060 519 1311867735.9322230816 0.0584525391 0.0891290591 0.2390826792 0.0051252137 0.4638350000 0.0790560000 0.0514010000 0.0308660000 0.2992560000 0.0017740000 136790267 0 402718720 3.9623124599 3.9796648026 4.0101966858 520 1311867735.9623689651 0.0589149632 0.0890709551 0.2390826792 0.0051228128 0.4353510000 0.0788030000 0.0541600000 0.0000010000 0.2991350000 0.0017820000 136793883 0 402718720 3.9616143703 3.9800128937 4.0105409622 521 1311867735.9945859909 0.0581753142 0.0890116544 0.2390826792 0.0051195526 0.7604930000 0.0792360000 0.0443190000 0.0308360000 0.2985510000 0.3060680000 136797499 0 402718720 3.9622297287 3.9804017544 4.0108137131 522 1311867736.0290079117 0.0562138855 0.0889488235 0.2390826792 0.0051181889 0.4683470000 0.0780750000 0.0874440000 0.0000010000 0.2995540000 0.0017920000 136801283 0 402718720 3.9640862942 3.9810059071 4.0109601021 523 1311867736.0642199516 0.0559339970 0.0888856976 0.2390826792 0.0051157498 0.5164070000 0.0927920000 0.0897830000 0.0308740000 0.2996610000 0.0018010000 136805067 0 402718720 3.9644119740 3.9804160595 4.0110530853 524 1311867736.0946779251 0.0557495505 0.0888224607 0.2390826792 0.0051127401 0.4600350000 0.0803230000 0.0747020000 0.0000010000 0.3017470000 0.0017610000 136808627 0 402718720 3.9645071030 3.9809513092 4.0114474297 525 1311867736.1299190521 0.0562814325 0.0887604778 0.2390826792 0.0051167833 0.7927190000 0.0799460000 0.0806940000 0.0304010000 0.2960850000 0.3041090000 136812411 0 402718720 3.9638240337 3.9808397293 4.0115084648 526 1311867736.1631360054 0.0573271811 0.0887007187 0.2390826792 0.0051133141 0.4750230000 0.0803950000 0.0930100000 0.0000010000 0.2983240000 0.0017970000 136816195 0 402718720 3.9624216557 3.9807732105 4.0118799210 527 1311867736.1942429543 0.0591644421 0.0886446726 0.2390826792 0.0051179560 0.5122980000 0.0923880000 0.0875250000 0.0308970000 0.2981880000 0.0017890000 136819755 0 402718720 3.9604511261 3.9811186790 4.0119338036 528 1311867736.2298679352 0.0587062240 0.0885879710 0.2390826792 0.0051208168 0.4486050000 0.0946890000 0.0518250000 0.0000010000 0.2988030000 0.0017860000 136823539 0 402718720 3.9603028297 3.9814386368 4.0121912956 529 1311867736.2633900642 0.0565039888 0.0885273207 0.2390826792 0.0051255957 0.8166980000 0.0928990000 0.0880310000 0.0309870000 0.2972340000 0.3060440000 136827267 0 402718720 3.9623584747 3.9815974236 4.0121183395 530 1311867736.2995250225 0.0576095805 0.0884689854 0.2390826792 0.0051224558 0.4554660000 0.0801200000 0.0739020000 0.0000000000 0.2981430000 0.0017920000 136831051 0 402718720 3.9612896442 3.9795835018 4.0123267174 531 1311867736.3304500580 0.0577401817 0.0884111157 0.2390826792 0.0051229894 0.4981360000 0.0795170000 0.0880640000 0.0309190000 0.2963370000 0.0017870000 136834611 0 402718720 3.9609308243 3.9811508656 4.0127210617 532 1311867736.3637149334 0.0599619225 0.0883576398 0.2390826792 0.0051211952 0.4714620000 0.0803990000 0.0885880000 0.0000010000 0.2991760000 0.0017960000 136838339 0 402718720 3.9587352276 3.9803352356 4.0130362511 533 1311867736.3943159580 0.0625489205 0.0883092181 0.2390826792 0.0051174265 0.8044340000 0.0782330000 0.0876420000 0.0309590000 0.2982040000 0.3078970000 136841899 0 402718720 3.9562892914 3.9787669182 4.0131316185 534 1311867736.4313519001 0.0640614405 0.0882638103 0.2390826792 0.0051362729 0.4935700000 0.0988420000 0.0929100000 0.0000000000 0.2985110000 0.0017860000 136845795 0 402718720 3.9550185204 3.9799237251 4.0138111115 535 1311867736.4625089169 0.0660425648 0.0882222753 0.2390826792 0.0051328806 0.4809850000 0.0799480000 0.0702010000 0.0310100000 0.2963520000 0.0018780000 136849467 0 402718720 3.9528665543 3.9798519611 4.0139946938 536 1311867736.4987530708 0.0676423311 0.0881838799 0.2390826792 0.0051288439 0.4678110000 0.0801040000 0.0853030000 0.0000010000 0.2990910000 0.0018120000 136853195 0 402718720 3.9514877796 3.9784889221 4.0141472816 537 1311867736.5321619511 0.0711028725 0.0881520717 0.2390826792 0.0051448317 0.8005830000 0.0800760000 0.0547290000 0.0311050000 0.3083500000 0.3247000000 136856923 0 402718720 3.9479913712 3.9798889160 4.0145788193 538 1311867736.5634689331 0.0709907413 0.0881201733 0.2390826792 0.0051403756 0.4715460000 0.0855800000 0.0813230000 0.0000010000 0.3013410000 0.0017950000 136860595 0 402718720 3.9481241703 3.9792325497 4.0148472786 539 1311867736.5958600044 0.0730631799 0.0880922382 0.2390826792 0.0051366774 0.4912520000 0.0801020000 0.0778490000 0.0310910000 0.2987320000 0.0018810000 136864267 0 402718720 3.9460167885 3.9772591591 4.0148777962 540 1311867736.6320459843 0.0753001869 0.0880685492 0.2390826792 0.0051486447 0.4360770000 0.0794040000 0.0518010000 0.0000010000 0.3015830000 0.0017740000 136868051 0 402718720 3.9439799786 3.9785997868 4.0152544975 541 1311867736.6635379791 0.0742734447 0.0880430500 0.2390826792 0.0051648490 0.7827470000 0.0789160000 0.0592340000 0.0310570000 0.3002860000 0.3117430000 136871723 0 402718720 3.9445819855 3.9780151844 4.0149483681 542 1311867736.6945500374 0.0790006220 0.0880263665 0.2390826792 0.0051666643 0.4545240000 0.0784610000 0.0694690000 0.0000000000 0.3031490000 0.0018410000 136875283 0 402718720 3.9399690628 3.9757256508 4.0151004791 543 1311867736.7332150936 0.0799420476 0.0880114783 0.2390826792 0.0051642194 0.5213110000 0.0919400000 0.0922630000 0.0306530000 0.3031480000 0.0017840000 136879123 0 402718720 3.9389693737 3.9763853550 4.0150923729 544 1311867736.7636179924 0.0811870098 0.0879989333 0.2390826792 0.0051638752 0.4794990000 0.0790890000 0.0923630000 0.0000010000 0.3047470000 0.0017740000 136882795 0 402718720 3.9383404255 3.9768095016 4.0151891708 545 1311867736.7952749729 0.0842792764 0.0879921082 0.2390826792 0.0051625361 0.8255470000 0.1073300000 0.0621260000 0.0307080000 0.3051370000 0.3187420000 136886411 0 402718720 3.9351358414 3.9760129452 4.0153098106 546 1311867736.8325269222 0.0888896137 0.0879937520 0.2390826792 0.0051810274 0.4824300000 0.0786960000 0.0928480000 0.0000010000 0.3074050000 0.0018620000 136890195 0 402718720 3.9309267998 3.9766559601 4.0161533356 547 1311867736.8640279770 0.0913846791 0.0879999512 0.2390826792 0.0051880491 0.5203470000 0.0797630000 0.0878220000 0.0312290000 0.3182040000 0.0017920000 136893923 0 402718720 3.9286134243 3.9785981178 4.0165200233 548 1311867736.8945000172 0.0925484821 0.0880082514 0.2390826792 0.0051862679 0.4824570000 0.0944910000 0.0776310000 0.0000010000 0.3069970000 0.0017800000 136897483 0 402718720 3.9277262688 3.9770331383 4.0166530609 549 1311867736.9362800121 0.0960426852 0.0880228861 0.2390826792 0.0051892808 0.8045360000 0.0799350000 0.0591250000 0.0312370000 0.3091920000 0.3235050000 136901435 0 402718720 3.9245209694 3.9778411388 4.0167889595 550 1311867736.9632000923 0.0983991995 0.0880417521 0.2390826792 0.0051919939 0.4840090000 0.0799260000 0.0886800000 0.0000000000 0.3120810000 0.0017770000 136904995 0 402718720 3.9223141670 3.9795644283 4.0180320740 551 1311867736.9954400063 0.0996088386 0.0880627450 0.2390826792 0.0051920861 0.4837820000 0.0791100000 0.0617590000 0.0312800000 0.3083000000 0.0017940000 136908667 0 402718720 3.9213089943 3.9779672623 4.0180253983 552 1311867737.0307478905 0.1011332721 0.0880864235 0.2390826792 0.0051886231 0.4826500000 0.0807840000 0.0889960000 0.0000010000 0.3095370000 0.0017840000 136912395 0 402718720 3.9198594093 3.9775404930 4.0184388161 553 1311867737.0629029274 0.1017827094 0.0881111907 0.2390826792 0.0051859607 0.8461620000 0.0930950000 0.0890230000 0.0313650000 0.3078520000 0.3232930000 136916123 0 402718720 3.9194276333 3.9787178040 4.0190691948 554 1311867737.0977239609 0.1029623747 0.0881379979 0.2390826792 0.0051821157 0.4857110000 0.0808950000 0.0936340000 0.0000010000 0.3078330000 0.0017960000 136919851 0 402718720 3.9182488918 3.9780356884 4.0190114975 555 1311867737.1300530434 0.1047652140 0.0881679569 0.2390826792 0.0051785176 0.5228480000 0.0882680000 0.0933590000 0.0314490000 0.3064040000 0.0018010000 136923467 0 402718720 3.9164459705 3.9772813320 4.0190033913 556 1311867737.1655049324 0.1043974161 0.0881971465 0.2390826792 0.0051756802 0.4467070000 0.0804940000 0.0554820000 0.0000000000 0.3073920000 0.0017910000 136927251 0 402718720 3.9169607162 3.9788944721 4.0192489624 557 1311867737.1952710152 0.1062026992 0.0882294725 0.2390826792 0.0051720105 0.8445850000 0.0924850000 0.0892940000 0.0314220000 0.3068230000 0.3230330000 136930867 0 402718720 3.9152889252 3.9782817364 4.0191059113 558 1311867737.2333149910 0.1064448506 0.0882621165 0.2390826792 0.0051676161 0.5085650000 0.1045080000 0.0946970000 0.0000010000 0.3060110000 0.0017950000 136934763 0 402718720 3.9152717590 3.9776291847 4.0192747116 559 1311867737.2693018913 0.1073200926 0.0882962095 0.2390826792 0.0051686140 0.4826870000 0.0815620000 0.0603010000 0.0315160000 0.3059490000 0.0017960000 136938491 0 402718720 3.9149086475 3.9786124229 4.0191869736 560 1311867737.2957379818 0.1084680185 0.0883322306 0.2390826792 0.0051659341 0.4847930000 0.0818280000 0.0950070000 0.0000010000 0.3046030000 0.0017980000 136941995 0 402718720 3.9140431881 3.9789528847 4.0196862221 561 1311867737.3316531181 0.1088113040 0.0883687352 0.2390826792 0.0051619134 0.8165580000 0.0818600000 0.0754030000 0.0314790000 0.3047550000 0.3215210000 136945835 0 402718720 3.9139475822 3.9780862331 4.0198836327 562 1311867737.3659460545 0.1087163836 0.0884049410 0.2390826792 0.0051575485 0.4733730000 0.0818750000 0.0830320000 0.0000010000 0.3051050000 0.0017950000 136949507 0 402718720 3.9139454365 3.9783501625 4.0201210976 563 1311867737.3967239857 0.1098159924 0.0884429713 0.2390826792 0.0051540782 0.4807020000 0.0819940000 0.0639520000 0.0310920000 0.3000970000 0.0019070000 136953179 0 402718720 3.9130244255 3.9785108566 4.0204367638 564 1311867737.4355359077 0.1114050522 0.0884836842 0.2390826792 0.0051509555 0.4811050000 0.0947400000 0.0799100000 0.0000010000 0.3030750000 0.0018120000 136957019 0 402718720 3.9115655422 3.9787001610 4.0210990906 565 1311867737.4691100121 0.1124525443 0.0885261069 0.2390826792 0.0051467776 0.7970080000 0.0827440000 0.0640180000 0.0315340000 0.2998600000 0.3173050000 136960747 0 402718720 3.9106836319 3.9785060883 4.0217485428 566 1311867737.4959459305 0.1132183746 0.0885697328 0.2390826792 0.0051425842 0.4393770000 0.0824010000 0.0538460000 0.0000000000 0.2997480000 0.0018190000 136964251 0 402718720 3.9098103046 3.9785871506 4.0221085548 567 1311867737.5353999138 0.1156531572 0.0886174990 0.2390826792 0.0051410121 0.5216960000 0.0957570000 0.0960280000 0.0317120000 0.2947970000 0.0018210000 136968147 0 402718720 3.9077146053 3.9779076576 4.0231108665 568 1311867737.5654399395 0.1154765934 0.0886647862 0.2390826792 0.0051372476 0.4694840000 0.1089960000 0.0616430000 0.0000010000 0.2954470000 0.0018190000 136971707 0 402718720 3.9084291458 3.9781258106 4.0232930183 569 1311867737.5958089828 0.1163403019 0.0887134250 0.2390826792 0.0051331879 0.8172350000 0.0827020000 0.0966180000 0.0312500000 0.2931100000 0.3119960000 136975379 0 402718720 3.9079389572 3.9777746201 4.0238709450 570 1311867737.6330978870 0.1177175790 0.0887643095 0.2390826792 0.0051290854 0.4761570000 0.0830650000 0.0970440000 0.0000010000 0.2924640000 0.0019180000 136979219 0 402718720 3.9068629742 3.9778063297 4.0242905617 571 1311867737.6624519825 0.1186336800 0.0888166201 0.2390826792 0.0051250201 0.4669060000 0.0829960000 0.0558980000 0.0316810000 0.2929250000 0.0018170000 136982835 0 402718720 3.9061965942 3.9768307209 4.0246090889 572 1311867737.7032339573 0.1200065538 0.0888711480 0.2390826792 0.0051207176 0.4731780000 0.0833320000 0.0924970000 0.0000010000 0.2939520000 0.0018170000 136986675 0 402718720 3.9051725864 3.9760782719 4.0251326561 573 1311867737.7314720154 0.1201225072 0.0889256879 0.2390826792 0.0051164055 0.7801640000 0.0935750000 0.0489610000 0.0312680000 0.2931690000 0.3116110000 136990235 0 402718720 3.9053263664 3.9762897491 4.0253753662 574 1311867737.7658560276 0.1217058301 0.0889827961 0.2390826792 0.0051136064 0.4765340000 0.0829630000 0.0972380000 0.0000010000 0.2929300000 0.0018120000 136993963 0 402718720 3.9041354656 3.9760942459 4.0258078575 575 1311867737.8011269569 0.1215318739 0.0890394032 0.2390826792 0.0051104037 0.4965060000 0.1068030000 0.0618520000 0.0317180000 0.2927130000 0.0018180000 136997747 0 402718720 3.9044692516 3.9764096737 4.0258407593 576 1311867737.8323190212 0.1211299673 0.0890951160 0.2390826792 0.0051061312 0.4356500000 0.0830350000 0.0571770000 0.0000010000 0.2920470000 0.0018140000 137001419 0 402718720 3.9051129818 3.9763689041 4.0261383057 577 1311867737.8633110523 0.1226233914 0.0891532240 0.2390826792 0.0051117261 0.7902550000 0.0832680000 0.0695830000 0.0317740000 0.2925610000 0.3114880000 137005035 0 402718720 3.9043822289 3.9761953354 4.0271635056 578 1311867737.9004418850 0.1244005933 0.0892142056 0.2390826792 0.0051083444 0.4815820000 0.0981910000 0.0867850000 0.0000010000 0.2931950000 0.0018270000 137008763 0 402718720 3.9030246735 3.9756045341 4.0277752876 579 1311867737.9305500984 0.1244846657 0.0892751217 0.2390826792 0.0051080936 0.4794980000 0.0833010000 0.0700750000 0.0317470000 0.2909460000 0.0018240000 137012379 0 402718720 3.9032084942 3.9751291275 4.0283002853 580 1311867737.9630560875 0.1252671182 0.0893371769 0.2390826792 0.0051041744 0.4435850000 0.0831400000 0.0654150000 0.0000000000 0.2916200000 0.0018200000 137016107 0 402718720 3.9028921127 3.9750127792 4.0288343430 581 1311867737.9996941090 0.1266110092 0.0894013315 0.2390826792 0.0051005868 0.7757240000 0.0819020000 0.0618760000 0.0318400000 0.2894630000 0.3090570000 137019891 0 402718720 3.9020178318 3.9742927551 4.0296840668 582 1311867738.0315399170 0.1277691275 0.0894672556 0.2390826792 0.0050977661 0.4695310000 0.0831230000 0.0928380000 0.0000010000 0.2901490000 0.0018180000 137023563 0 402718720 3.9011802673 3.9750468731 4.0303730965 583 1311867738.0629770756 0.1266357005 0.0895310093 0.2390826792 0.0050947325 0.4853100000 0.0835350000 0.0778870000 0.0318530000 0.2885810000 0.0018260000 137027235 0 402718720 3.9029517174 3.9765818119 4.0314126015 584 1311867738.0998299122 0.1271984428 0.0895955084 0.2390826792 0.0050921565 0.4360880000 0.0820150000 0.0620200000 0.0000000000 0.2886290000 0.0018210000 137030963 0 402718720 3.9030086994 3.9750638008 4.0321750641 585 1311867738.1308510303 0.1286094487 0.0896621989 0.2390826792 0.0050901630 0.7865740000 0.0840690000 0.0738630000 0.0318860000 0.2863800000 0.3088040000 137034579 0 402718720 3.9021513462 3.9739255905 4.0329141617 586 1311867738.1635079384 0.1286842674 0.0897287894 0.2390826792 0.0050863104 0.4439350000 0.0933310000 0.0577810000 0.0000010000 0.2893880000 0.0018210000 137038307 0 402718720 3.9025466442 3.9735260010 4.0335268974 587 1311867738.1992070675 0.1312913150 0.0897995944 0.2390826792 0.0050842748 0.4722980000 0.0839150000 0.0659640000 0.0314680000 0.2875110000 0.0018310000 137042035 0 402718720 3.9007019997 3.9728782177 4.0347008705 588 1311867738.2306089401 0.1310070157 0.0898696750 0.2390826792 0.0050833851 0.4605280000 0.1014640000 0.0660840000 0.0000010000 0.2895230000 0.0018230000 137045707 0 402718720 3.9013822079 3.9713644981 4.0348219872 589 1311867738.2632689476 0.1326597035 0.0899423237 0.2390826792 0.0050818118 0.8139990000 0.0838800000 0.0986830000 0.0320250000 0.2882250000 0.3095950000 137049435 0 402718720 3.9002399445 3.9702374935 4.0351271629 590 1311867738.3008689880 0.1338366121 0.0900167207 0.2390826792 0.0050781176 0.4449770000 0.0821480000 0.0697840000 0.0000010000 0.2896510000 0.0017760000 137053219 0 402718720 3.8996522427 3.9698133469 4.0351901054 591 1311867738.3339769840 0.1347988099 0.0900924942 0.2390826792 0.0050754611 0.5012520000 0.0839790000 0.0936970000 0.0315410000 0.2885770000 0.0018320000 137056891 0 402718720 3.8992204666 3.9693474770 4.0353169441 592 1311867738.3651630878 0.1370057762 0.0901717396 0.2390826792 0.0050726925 0.4435780000 0.0961520000 0.0551480000 0.0000010000 0.2888220000 0.0018220000 137060563 0 402718720 3.8972132206 3.9694092274 4.0353140831 593 1311867738.3995900154 0.1394984722 0.0902549212 0.2390826792 0.0050712801 0.8144800000 0.0928140000 0.0930440000 0.0321080000 0.2864840000 0.3084110000 137064347 0 402718720 3.8952665329 3.9703261852 4.0356397629 594 1311867738.4334011078 0.1385147274 0.0903361667 0.2390826792 0.0050679759 0.4236390000 0.0834480000 0.0498400000 0.0000010000 0.2869090000 0.0018210000 137068075 0 402718720 3.8964087963 3.9711098671 4.0353269577 595 1311867738.4643430710 0.1424368322 0.0904237309 0.2390826792 0.0050657128 0.4610970000 0.0833800000 0.0547770000 0.0321700000 0.2872980000 0.0018250000 137071691 0 402718720 3.8933134079 3.9699735641 4.0356431007 596 1311867738.5000250340 0.1405994296 0.0905079183 0.2390826792 0.0050646563 0.4638420000 0.1076740000 0.0658780000 0.0000010000 0.2868000000 0.0018220000 137075475 0 402718720 3.8958404064 3.9715943336 4.0358910561 597 1311867738.5332009792 0.1417569369 0.0905937625 0.2390826792 0.0050612017 0.7745710000 0.0832150000 0.0624840000 0.0322420000 0.2877700000 0.3072240000 137079147 0 402718720 3.8954679966 3.9726758003 4.0361828804 598 1311867738.5634350777 0.1422412246 0.0906801295 0.2390826792 0.0050585597 0.4557230000 0.0925140000 0.0695660000 0.0000010000 0.2902120000 0.0017820000 137082819 0 402718720 3.8956940174 3.9709682465 4.0363941193 599 1311867738.6022439003 0.1420261413 0.0907658491 0.2390826792 0.0050566971 0.4470150000 0.0833830000 0.0393640000 0.0317420000 0.2890610000 0.0018200000 137086659 0 402718720 3.8968412876 3.9706950188 4.0363073349 600 1311867738.6328980923 0.1433976591 0.0908535688 0.2390826792 0.0050549046 0.4321050000 0.0834960000 0.0551500000 0.0000010000 0.2899960000 0.0018270000 137090275 0 402718720 3.8964312077 3.9720792770 4.0366353989 601 1311867738.6628730297 0.1436732262 0.0909414550 0.2390826792 0.0050538829 0.7708460000 0.0830720000 0.0546700000 0.0322180000 0.2898440000 0.3094150000 137093947 0 402718720 3.8969097137 3.9716341496 4.0363168716 602 1311867738.6996099949 0.1461057812 0.0910330901 0.2390826792 0.0050513375 0.4480170000 0.0833000000 0.0703870000 0.0000010000 0.2908490000 0.0018270000 137097731 0 402718720 3.8955101967 3.9703111649 4.0367145538 603 1311867738.7314729691 0.1464440674 0.0911249823 0.2390826792 0.0050604463 0.4776570000 0.0950820000 0.0549010000 0.0323490000 0.2918470000 0.0018230000 137101403 0 402718720 3.8960726261 3.9715297222 4.0369305611 604 1311867738.7626600266 0.1486643106 0.0912202461 0.2390826792 0.0050583936 0.4458350000 0.0830100000 0.0548600000 0.0000010000 0.3037170000 0.0024590000 137105019 0 402718720 3.8949050903 3.9713649750 4.0375204086 605 1311867738.8032259941 0.1494134963 0.0913164333 0.2390826792 0.0050614006 0.8712160000 0.1048970000 0.1035520000 0.0396830000 0.3075260000 0.3139410000 137108915 0 402718720 3.8952116966 3.9710562229 4.0376343727 606 1311867738.8306779861 0.1506591886 0.0914143586 0.2390826792 0.0050630172 0.4290790000 0.0829180000 0.0472070000 0.0000010000 0.2954610000 0.0018280000 137112475 0 402718720 3.8946373463 3.9714734554 4.0379085541 607 1311867738.8639259338 0.1496877968 0.0915103610 0.2390826792 0.0050598579 0.4709360000 0.0827770000 0.0574870000 0.0323910000 0.2947890000 0.0018240000 137116203 0 402718720 3.8964567184 3.9721744061 4.0380568504 608 1311867738.9000120163 0.1502472758 0.0916069678 0.2390826792 0.0050610023 0.5108990000 0.1121110000 0.0975120000 0.0000010000 0.2977480000 0.0018230000 137119987 0 402718720 3.8966925144 3.9718902111 4.0380039215 609 1311867738.9307610989 0.1535485387 0.0917086781 0.2390826792 0.0050628458 0.7864930000 0.0828800000 0.0573670000 0.0319730000 0.2964510000 0.3161870000 137123603 0 402718720 3.8940014839 3.9712460041 4.0385570526 610 1311867738.9664750099 0.1543271542 0.0918113313 0.2390826792 0.0050607729 0.4634760000 0.0828510000 0.0776670000 0.0000000000 0.2994700000 0.0018250000 137127387 0 402718720 3.8938050270 3.9723117352 4.0389533043 611 1311867738.9989941120 0.1559247822 0.0919162633 0.2390826792 0.0050570021 0.4956900000 0.0825440000 0.0765900000 0.0322460000 0.3008030000 0.0018300000 137131115 0 402718720 3.8927762508 3.9721958637 4.0391016006 612 1311867739.0329539776 0.1551078260 0.0920195175 0.2390826792 0.0050567343 0.4423420000 0.0825860000 0.0544290000 0.0000010000 0.3018260000 0.0018160000 137134843 0 402718720 3.8940351009 3.9707562923 4.0389308929 613 1311867739.0664470196 0.1543210894 0.0921211514 0.2390826792 0.0050544915 0.8104730000 0.0826410000 0.0698720000 0.0324160000 0.3026950000 0.3211880000 137138515 0 402718720 3.8953816891 3.9714646339 4.0391793251 614 1311867739.0997900963 0.1544006765 0.0922225838 0.2390826792 0.0050515352 0.4601260000 0.0820110000 0.0704000000 0.0000000000 0.3042280000 0.0018140000 137142075 0 402718720 3.8957793713 3.9727804661 4.0393905640 615 1311867739.1321549416 0.1549038589 0.0923245046 0.2390826792 0.0050494828 0.4969410000 0.0825730000 0.0731380000 0.0325410000 0.3051990000 0.0018190000 137145691 0 402718720 3.8957092762 3.9719557762 4.0398631096 616 1311867739.1687150002 0.1550639868 0.0924263544 0.2390826792 0.0050460639 0.5069080000 0.1075250000 0.0890660000 0.0000010000 0.3068220000 0.0018180000 137149475 0 402718720 3.8957748413 3.9719393253 4.0402073860 617 1311867739.1999289989 0.1549501121 0.0925276895 0.2390826792 0.0050457545 0.8119790000 0.0801620000 0.0625130000 0.0325410000 0.3080280000 0.3270810000 137153091 0 402718720 3.8961315155 3.9725005627 4.0410346985 618 1311867739.2313010693 0.1555828601 0.0926297205 0.2390826792 0.0050427468 0.4846990000 0.1028560000 0.0704070000 0.0000010000 0.3079270000 0.0018090000 137156707 0 402718720 3.8955695629 3.9718632698 4.0412478447 619 1311867739.2672259808 0.1563880444 0.0927327227 0.2390826792 0.0050390669 0.4940250000 0.0802800000 0.0680840000 0.0323130000 0.3098440000 0.0018110000 137160547 0 402718720 3.8945922852 3.9714243412 4.0413250923 620 1311867739.2996931076 0.1556697488 0.0928342340 0.2390826792 0.0050411746 0.4498700000 0.0813570000 0.0565740000 0.0000010000 0.3082550000 0.0019020000 137164219 0 402718720 3.8953168392 3.9709608555 4.0417318344 621 1311867739.3319859505 0.1558602303 0.0929357251 0.2390826792 0.0050402545 0.8506970000 0.0814670000 0.0953980000 0.0326550000 0.3093460000 0.3301530000 137167891 0 402718720 3.8952593803 3.9721007347 4.0422997475 622 1311867739.3670029640 0.1554952860 0.0930363032 0.2390826792 0.0050383134 0.4928220000 0.0939580000 0.0835110000 0.0000000000 0.3118480000 0.0018080000 137171619 0 402718720 3.8954179287 3.9716582298 4.0425810814 623 1311867739.3990058899 0.1554996222 0.0931365653 0.2390826792 0.0050344634 0.4962310000 0.0946910000 0.0538800000 0.0325890000 0.3115710000 0.0018050000 137175347 0 402718720 3.8951542377 3.9723072052 4.0428171158 624 1311867739.4311320782 0.1538188457 0.0932338126 0.2390826792 0.0050310237 0.4653700000 0.0814410000 0.0719780000 0.0000000000 0.3082620000 0.0019000000 137178963 0 402718720 3.8969092369 3.9726455212 4.0431251526 625 1311867739.4668490887 0.1558867693 0.0933340573 0.2390826792 0.0050282081 0.8358210000 0.0816010000 0.0786720000 0.0325820000 0.3114280000 0.3298490000 137182747 0 402718720 3.8948581219 3.9717442989 4.0438227654 626 1311867739.4988598824 0.1565952152 0.0934351135 0.2390826792 0.0050316898 0.5133890000 0.1029730000 0.0958210000 0.0000000000 0.3110880000 0.0017990000 137186419 0 402718720 3.8941738605 3.9709708691 4.0445628166 627 1311867739.5316400528 0.1558382511 0.0935346400 0.2390826792 0.0050281685 0.5228510000 0.0814990000 0.0957400000 0.0326700000 0.3092550000 0.0019060000 137190035 0 402718720 3.8950765133 3.9718933105 4.0445942879 628 1311867739.5670249462 0.1593000442 0.0936393620 0.2390826792 0.0050289426 0.4770580000 0.1039410000 0.0565480000 0.0000010000 0.3130580000 0.0018050000 137193819 0 402718720 3.8917956352 3.9721834660 4.0458436012 629 1311867739.5990490913 0.1615261585 0.0937472901 0.2390826792 0.0050258123 0.8317060000 0.0809610000 0.0709850000 0.0321530000 0.3135800000 0.3323600000 137197491 0 402718720 3.8894786835 3.9707660675 4.0465216637 630 1311867739.6325490475 0.1624759138 0.0938563832 0.2390826792 0.0050222226 0.4751800000 0.0812600000 0.0759880000 0.0000000000 0.3144340000 0.0018000000 137201219 0 402718720 3.8883824348 3.9717259407 4.0472412109 631 1311867739.6706740856 0.1640003473 0.0939675464 0.2390826792 0.0050196236 0.5003440000 0.0817720000 0.0684110000 0.0327040000 0.3139440000 0.0018040000 137205059 0 402718720 3.8865478039 3.9712207317 4.0478935242 632 1311867739.7001221180 0.1652191579 0.0940802863 0.2390826792 0.0050160324 0.4580200000 0.0808290000 0.0590400000 0.0000000000 0.3146390000 0.0017980000 137208675 0 402718720 3.8853139877 3.9712138176 4.0487594604 633 1311867739.7323939800 0.1658035517 0.0941935932 0.2390826792 0.0050134747 0.8235390000 0.0820420000 0.0613670000 0.0326950000 0.3134880000 0.3322740000 137212347 0 402718720 3.8846130371 3.9720802307 4.0495061874 634 1311867739.7662999630 0.1677950323 0.0943096838 0.2390826792 0.0050114950 0.4606020000 0.0815620000 0.0644420000 0.0000010000 0.3108930000 0.0019000000 137216075 0 402718720 3.8824622631 3.9709954262 4.0502610207 635 1311867739.8016180992 0.1687811315 0.0944269616 0.2390826792 0.0050097425 0.5258200000 0.0818230000 0.0941150000 0.0323090000 0.3140540000 0.0018070000 137219859 0 402718720 3.8811764717 3.9693901539 4.0507669449 636 1311867739.8325679302 0.1695210785 0.0945450341 0.2390826792 0.0050177410 0.4701780000 0.1051220000 0.0462260000 0.0000010000 0.3153060000 0.0017950000 137223475 0 402718720 3.8803665638 3.9715454578 4.0516147614 637 1311867739.8701560497 0.1699500680 0.0946634094 0.2390826792 0.0050146197 0.8327350000 0.0814560000 0.0685220000 0.0327450000 0.3147640000 0.3335560000 137227259 0 402718720 3.8794851303 3.9705407619 4.0522260666 638 1311867739.9036860466 0.1700170785 0.0947815186 0.2390826792 0.0050130546 0.5255660000 0.1106140000 0.0957570000 0.0000010000 0.3156730000 0.0017980000 137231043 0 402718720 3.8786292076 3.9690272808 4.0521569252 639 1311867739.9317240715 0.1715497375 0.0949016566 0.2390826792 0.0050109895 0.5009900000 0.0945310000 0.0533210000 0.0328100000 0.3168030000 0.0018010000 137234603 0 402718720 3.8767485619 3.9697520733 4.0527791977 640 1311867739.9668979645 0.1720001400 0.0950221230 0.2390826792 0.0050077378 0.4796140000 0.0947850000 0.0644510000 0.0000000000 0.3168550000 0.0017890000 137238331 0 402718720 3.8759500980 3.9705741405 4.0530996323 641 1311867739.9987080097 0.1746006310 0.0951462705 0.2390826792 0.0050056722 0.8623360000 0.0816480000 0.0954920000 0.0328740000 0.3149070000 0.3356860000 137242059 0 402718720 3.8726673126 3.9691998959 4.0537104607 642 1311867740.0328791142 0.1744957268 0.0952698677 0.2390826792 0.0050022129 0.4480010000 0.0796730000 0.0454810000 0.0000000000 0.3193300000 0.0017940000 137245787 0 402718720 3.8722164631 3.9692676067 4.0538883209 643 1311867740.0671849251 0.1740936190 0.0953924552 0.2390826792 0.0050024304 0.5237520000 0.0912460000 0.0795720000 0.0328860000 0.3165000000 0.0017950000 137249459 0 402718720 3.8724229336 3.9712603092 4.0543398857 644 1311867740.0992529392 0.1755709797 0.0955169560 0.2390826792 0.0050042595 0.4800060000 0.0816520000 0.0760590000 0.0000010000 0.3187650000 0.0017950000 137253187 0 402718720 3.8705899715 3.9691493511 4.0544939041 645 1311867740.1347720623 0.1781254709 0.0956450313 0.2390826792 0.0050033675 0.8676200000 0.0813190000 0.0953710000 0.0329650000 0.3175140000 0.3387170000 137256859 0 402718720 3.8672220707 3.9674420357 4.0546555519 646 1311867740.1666491032 0.1774277985 0.0957716300 0.2390826792 0.0050035473 0.4964080000 0.0815530000 0.0908680000 0.0000010000 0.3204700000 0.0017840000 137260587 0 402718720 3.8679111004 3.9695520401 4.0548224449 647 1311867740.1993310452 0.1788726151 0.0959000704 0.2390826792 0.0050000295 0.4986430000 0.0809590000 0.0609110000 0.0329530000 0.3202860000 0.0017990000 137264315 0 402718720 3.8661775589 3.9698154926 4.0552854538 648 1311867740.2383539677 0.1784286201 0.0960274293 0.2390826792 0.0049981398 0.4897310000 0.1020950000 0.0638380000 0.0000010000 0.3202770000 0.0017940000 137268211 0 402718720 3.8660919666 3.9684603214 4.0550918579 649 1311867740.2664349079 0.1790652871 0.0961553767 0.2390826792 0.0049980045 0.8848050000 0.0820550000 0.0833820000 0.0329930000 0.3281670000 0.3563360000 137271715 0 402718720 3.8652288914 3.9695215225 4.0553450584 650 1311867740.2981588840 0.1794073433 0.0962834567 0.2390826792 0.0049960226 0.4867080000 0.1025980000 0.0591900000 0.0000010000 0.3213850000 0.0017880000 137275387 0 402718720 3.8646492958 3.9701182842 4.0555992126 651 1311867740.3347120285 0.1787665635 0.0964101588 0.2390826792 0.0049935827 0.5297440000 0.0813390000 0.0906760000 0.0329800000 0.3212090000 0.0017950000 137279227 0 402718720 3.8647620678 3.9689073563 4.0551910400 652 1311867740.3665161133 0.1767777950 0.0965334221 0.2390826792 0.0049951675 0.4521220000 0.0813640000 0.0459160000 0.0000010000 0.3213200000 0.0017900000 137282843 0 402718720 3.8666436672 3.9705188274 4.0547680855 653 1311867740.3993780613 0.1775815487 0.0966575386 0.2390826792 0.0049934420 0.8469550000 0.0914380000 0.0639970000 0.0330090000 0.3176360000 0.3391290000 137286515 0 402718720 3.8657050133 3.9692714214 4.0546817780 654 1311867740.4346680641 0.1773636043 0.0967809424 0.2390826792 0.0049908039 0.4975850000 0.0813220000 0.0908740000 0.0000020000 0.3218620000 0.0017800000 137290299 0 402718720 3.8660249710 3.9697198868 4.0542159081 655 1311867740.4664289951 0.1785995066 0.0969058562 0.2390826792 0.0049876234 0.5529880000 0.1000660000 0.0951870000 0.0330550000 0.3211270000 0.0017980000 137293971 0 402718720 3.8646402359 3.9698486328 4.0538077354 656 1311867740.4993040562 0.1791707873 0.0970312601 0.2390826792 0.0049860608 0.4749640000 0.0810240000 0.0684210000 0.0000000000 0.3219900000 0.0017910000 137297643 0 402718720 3.8646190166 3.9698159695 4.0538458824 657 1311867740.5354259014 0.1804220229 0.0971581867 0.2390826792 0.0049875713 0.8260820000 0.0798340000 0.0478980000 0.0328470000 0.3219720000 0.3417800000 137301427 0 402718720 3.8637151718 3.9695112705 4.0535736084 658 1311867740.5666589737 0.1806916893 0.0972851373 0.2390826792 0.0049838359 0.4878210000 0.0914520000 0.0721660000 0.0000010000 0.3206660000 0.0017890000 137305099 0 402718720 3.8636031151 3.9701941013 4.0532650948 659 1311867740.6008880138 0.1833581477 0.0974157488 0.2390826792 0.0049833706 0.5068390000 0.0813650000 0.0533820000 0.0331020000 0.3346690000 0.0024130000 137308827 0 402718720 3.8611328602 3.9707453251 4.0534844398 660 1311867740.6346809864 0.1826942563 0.0975449587 0.2390826792 0.0049821933 0.5081370000 0.1026590000 0.0714480000 0.0000000000 0.3304690000 0.0017890000 137312555 0 402718720 3.8617796898 3.9707429409 4.0532307625 661 1311867740.6665890217 0.1831906587 0.0976745286 0.2390826792 0.0049787010 0.8487480000 0.0948160000 0.0531640000 0.0332010000 0.3227500000 0.3430670000 137316227 0 402718720 3.8610937595 3.9706454277 4.0528874397 662 1311867740.6994900703 0.1838216335 0.0978046602 0.2390826792 0.0049757830 0.4545720000 0.0815170000 0.0460080000 0.0000010000 0.3234990000 0.0017860000 137319899 0 402718720 3.8603622913 3.9702126980 4.0525274277 663 1311867740.7368240356 0.1840461344 0.0979347378 0.2390826792 0.0049743364 0.4947180000 0.0811420000 0.0561380000 0.0332450000 0.3204390000 0.0018840000 137323571 0 402718720 3.8600411415 3.9697620869 4.0522751808 664 1311867740.7668819427 0.1848546118 0.0980656412 0.2390826792 0.0049717080 0.4632510000 0.0812860000 0.0534230000 0.0000010000 0.3249750000 0.0017840000 137327187 0 402718720 3.8590221405 3.9699318409 4.0520834923 665 1311867740.7996399403 0.1878090501 0.0982005937 0.2390826792 0.0049692773 0.8747850000 0.1025720000 0.0715240000 0.0328030000 0.3210080000 0.3451410000 137330915 0 402718720 3.8558993340 3.9689888954 4.0526523590 666 1311867740.8349099159 0.1878305078 0.0983351732 0.2390826792 0.0049656207 0.4701890000 0.0810720000 0.0637550000 0.0000010000 0.3216150000 0.0018800000 137334587 0 402718720 3.8556525707 3.9694190025 4.0523719788 667 1311867740.8668210506 0.1892349571 0.0984714547 0.2390826792 0.0049627932 0.4985070000 0.0810040000 0.0559180000 0.0333750000 0.3246500000 0.0017870000 137338315 0 402718720 3.8539407253 3.9694674015 4.0524959564 668 1311867740.8993830681 0.1901783645 0.0986087405 0.2390826792 0.0049593421 0.4746770000 0.0921360000 0.0558410000 0.0000000000 0.3229580000 0.0018760000 137341987 0 402718720 3.8523449898 3.9684929848 4.0523266792 669 1311867740.9399120808 0.1888285875 0.0987435983 0.2390826792 0.0049629764 0.8516930000 0.0805530000 0.0631640000 0.0328070000 0.3257990000 0.3476010000 137345939 0 402718720 3.8533535004 3.9700577259 4.0523271561 670 1311867740.9665501118 0.1891845167 0.0988785847 0.2390826792 0.0049600467 0.4799350000 0.0806970000 0.0712040000 0.0000010000 0.3244800000 0.0017900000 137349443 0 402718720 3.8525364399 3.9698052406 4.0518393517 671 1311867741.0021579266 0.1898124367 0.0990141046 0.2390826792 0.0049572698 0.5053210000 0.0812070000 0.0604950000 0.0333160000 0.3267550000 0.0017780000 137353227 0 402718720 3.8514645100 3.9685149193 4.0516524315 672 1311867741.0367169380 0.1887134910 0.0991475859 0.2390826792 0.0049545611 0.4732750000 0.0807180000 0.0632960000 0.0000010000 0.3257100000 0.0017690000 137356955 0 402718720 3.8523337841 3.9694802761 4.0513200760 673 1311867741.0666699409 0.1888466775 0.0992808683 0.2390826792 0.0049530498 0.8535930000 0.0944230000 0.0479050000 0.0333780000 0.3269890000 0.3491260000 137360571 0 402718720 3.8520138264 3.9706261158 4.0512042046 674 1311867741.1009640694 0.1888560355 0.0994137692 0.2390826792 0.0049569275 0.4931530000 0.0792570000 0.0817710000 0.0000010000 0.3285830000 0.0017740000 137364299 0 402718720 3.8514292240 3.9685161114 4.0507121086 675 1311867741.1357901096 0.1886735260 0.0995460058 0.2390826792 0.0049541428 0.5308870000 0.1055130000 0.0632350000 0.0329080000 0.3256360000 0.0017840000 137368027 0 402718720 3.8510777950 3.9688935280 4.0500721931 676 1311867741.1675300598 0.1880402267 0.0996769144 0.2390826792 0.0049513984 0.4804870000 0.0804270000 0.0676960000 0.0000010000 0.3286410000 0.0018900000 137371755 0 402718720 3.8518302441 3.9688627720 4.0499863625 677 1311867741.2014830112 0.1890913993 0.0998089890 0.2390826792 0.0049530992 0.8693590000 0.0801790000 0.0747580000 0.0333280000 0.3289150000 0.3504180000 137375427 0 402718720 3.8508815765 3.9680809975 4.0495057106 678 1311867741.2411060333 0.1906462014 0.0999429672 0.2390826792 0.0049550710 0.4883550000 0.1017550000 0.0555920000 0.0000010000 0.3272360000 0.0018650000 137379323 0 402718720 3.8490390778 3.9667630196 4.0492334366 679 1311867741.2668209076 0.1925066113 0.1000792907 0.2390826792 0.0049569457 0.5230230000 0.0803850000 0.0745900000 0.0328520000 0.3316240000 0.0017640000 137382827 0 402718720 3.8474242687 3.9671931267 4.0492906570 680 1311867741.2997009754 0.1932245642 0.1002162690 0.2390826792 0.0049535519 0.4762960000 0.0796430000 0.0597380000 0.0000000000 0.3333360000 0.0017610000 137386499 0 402718720 3.8470127583 3.9677579403 4.0490837097 681 1311867741.3348419666 0.1937400103 0.1003536020 0.2390826792 0.0049500296 0.8701160000 0.0784120000 0.0668150000 0.0329740000 0.3340340000 0.3560990000 137390283 0 402718720 3.8467152119 3.9682641029 4.0489816666 682 1311867741.3701419830 0.1941678077 0.1004911595 0.2390826792 0.0049473510 0.4777410000 0.0795800000 0.0596690000 0.0000010000 0.3349230000 0.0017620000 137394011 0 402718720 3.8467140198 3.9698596001 4.0488920212 683 1311867741.4066278934 0.1947121471 0.1006291111 0.2390826792 0.0049453982 0.5297130000 0.0924290000 0.0649960000 0.0334420000 0.3352570000 0.0017660000 137397851 0 402718720 3.8465268612 3.9696362019 4.0486788750 684 1311867741.4393060207 0.1935778409 0.1007650011 0.2390826792 0.0049430473 0.4816130000 0.0798770000 0.0627190000 0.0000010000 0.3354330000 0.0017620000 137401579 0 402718720 3.8479948044 3.9704232216 4.0485572815 685 1311867741.4667329788 0.1942850053 0.1009015266 0.2390826792 0.0049394851 0.8749960000 0.0929680000 0.0522560000 0.0335170000 0.3361020000 0.3583750000 137405083 0 402718720 3.8478257656 3.9704952240 4.0487275124 686 1311867741.5025069714 0.1959882230 0.1010401370 0.2390826792 0.0049378747 0.4878710000 0.0799520000 0.0669420000 0.0000000000 0.3373810000 0.0017640000 137408867 0 402718720 3.8467273712 3.9710447788 4.0490450859 687 1311867741.5368049145 0.1957026720 0.1011779282 0.2390826792 0.0049357365 0.5060490000 0.0795700000 0.0519890000 0.0335440000 0.3373680000 0.0017660000 137412595 0 402718720 3.8475005627 3.9705412388 4.0490074158 688 1311867741.5688209534 0.1948498935 0.1013140793 0.2390826792 0.0049323574 0.5024360000 0.0941040000 0.0703400000 0.0000000000 0.3342240000 0.0018550000 137416267 0 402718720 3.8489978313 3.9711003304 4.0490469933 689 1311867741.6046030521 0.1954935342 0.1014507693 0.2390826792 0.0049389673 0.8593490000 0.0800180000 0.0472610000 0.0336610000 0.3362770000 0.3603420000 137419995 0 402718720 3.8489592075 3.9718999863 4.0492157936 690 1311867741.6355440617 0.1973955184 0.1015898197 0.2390826792 0.0049363174 0.4872420000 0.0800490000 0.0649190000 0.0000000000 0.3386730000 0.0017670000 137423667 0 402718720 3.8474991322 3.9713294506 4.0492634773 691 1311867741.6679561138 0.1969396919 0.1017278079 0.2390826792 0.0049329186 0.5443070000 0.0801280000 0.0886830000 0.0336490000 0.3382680000 0.0017690000 137427395 0 402718720 3.8486680984 3.9719653130 4.0492410660 692 1311867741.7048020363 0.1981345415 0.1018671240 0.2390826792 0.0049341110 0.4748880000 0.0801310000 0.0521870000 0.0000010000 0.3389850000 0.0017570000 137431179 0 402718720 3.8482685089 3.9721400738 4.0491337776 693 1311867741.7345991135 0.1977941692 0.1020055469 0.2390826792 0.0049320872 0.8844720000 0.0941810000 0.0623650000 0.0336910000 0.3348590000 0.3575650000 137434739 0 402718720 3.8491802216 3.9715237617 4.0488152504 694 1311867741.7702169418 0.1980997324 0.1021440111 0.2390826792 0.0049287124 0.5142040000 0.0796970000 0.0913730000 0.0000010000 0.3395230000 0.0017670000 137438523 0 402718720 3.8497438431 3.9716908932 4.0487699509 695 1311867741.8058650494 0.1987639964 0.1022830327 0.2390826792 0.0049252082 0.5232580000 0.1016700000 0.0470600000 0.0338530000 0.3370680000 0.0017690000 137442307 0 402718720 3.8499915600 3.9718296528 4.0485596657 696 1311867741.8388509750 0.1983504295 0.1024210606 0.2390826792 0.0049227483 0.4763680000 0.0799260000 0.0548200000 0.0000000000 0.3380160000 0.0017590000 137446091 0 402718720 3.8511393070 3.9719729424 4.0483732224 697 1311867741.8683021069 0.2007081211 0.1025620750 0.2390826792 0.0049195813 0.8700410000 0.0803870000 0.0521850000 0.0336600000 0.3397060000 0.3623000000 137449651 0 402718720 3.8493819237 3.9721472263 4.0484843254 698 1311867741.9065721035 0.1987603307 0.1026998948 0.2390826792 0.0049171304 0.4867050000 0.0914080000 0.0547830000 0.0000010000 0.3367130000 0.0018550000 137453491 0 402718720 3.8519361019 3.9719123840 4.0475168228 699 1311867741.9387769699 0.2009510547 0.1028404544 0.2390826792 0.0049148652 0.5464120000 0.0794170000 0.0888260000 0.0337290000 0.3408310000 0.0017630000 137457219 0 402718720 3.8507571220 3.9724802971 4.0478343964 700 1311867741.9665379524 0.2010069788 0.1029806923 0.2390826792 0.0049125426 0.5158450000 0.0800180000 0.0931710000 0.0000000000 0.3390680000 0.0017550000 137460723 0 402718720 3.8512716293 3.9719812870 4.0471653938 701 1311867742.0029959679 0.2022312135 0.1031222765 0.2390826792 0.0049092522 0.9014080000 0.0931260000 0.0665740000 0.0337110000 0.3418070000 0.3643740000 137464507 0 402718720 3.8511180878 3.9715080261 4.0474219322 702 1311867742.0344839096 0.2025866508 0.1032639637 0.2390826792 0.0049062046 0.5193050000 0.0798160000 0.0882360000 0.0000000000 0.3469110000 0.0023490000 137468123 0 402718720 3.8516392708 3.9726438522 4.0471491814 703 1311867742.0674400330 0.2032201886 0.1034061489 0.2390826792 0.0049040293 0.6181030000 0.1009080000 0.1177630000 0.0419200000 0.3538630000 0.0017620000 137471795 0 402718720 3.8519515991 3.9727435112 4.0473475456 704 1311867742.1030650139 0.2037003636 0.1035486123 0.2390826792 0.0049007034 0.5172660000 0.0805610000 0.0883940000 0.0000010000 0.3447160000 0.0017640000 137475523 0 402718720 3.8528370857 3.9732356071 4.0473141670 705 1311867742.1348879337 0.2058256269 0.1036936861 0.2390826792 0.0048992879 0.9075470000 0.0940420000 0.0682490000 0.0334710000 0.3425580000 0.3674020000 137479139 0 402718720 3.8517267704 3.9729101658 4.0473027229 706 1311867742.1672229767 0.2050755024 0.1038372864 0.2390826792 0.0048970580 0.4808270000 0.0801790000 0.0548620000 0.0000010000 0.3421850000 0.0017590000 137482867 0 402718720 3.8531591892 3.9738771915 4.0473699570 707 1311867742.2028279305 0.2052942216 0.1039807898 0.2390826792 0.0048939713 0.5332250000 0.0919070000 0.0573310000 0.0338020000 0.3465570000 0.0017550000 137486707 0 402718720 3.8539543152 3.9740314484 4.0473060608 708 1311867742.2362670898 0.2051875889 0.1041237373 0.2390826792 0.0048913739 0.5313830000 0.0899110000 0.0926580000 0.0000010000 0.3452100000 0.0017500000 137490379 0 402718720 3.8549633026 3.9744510651 4.0471601486 709 1311867742.2674059868 0.2068315893 0.1042686003 0.2390826792 0.0048884849 0.9361350000 0.0933430000 0.0879750000 0.0338870000 0.3480650000 0.3710420000 137494051 0 402718720 3.8541073799 3.9730627537 4.0477819443 710 1311867742.3028159142 0.2075504214 0.1044140676 0.2390826792 0.0048865706 0.4998950000 0.0789550000 0.0692240000 0.0000010000 0.3481220000 0.0017430000 137497835 0 402718720 3.8539671898 3.9736447334 4.0476493835 711 1311867742.3350739479 0.2075262666 0.1045590918 0.2390826792 0.0048833514 0.5566380000 0.0799660000 0.0919030000 0.0339660000 0.3471730000 0.0017520000 137501451 0 402718720 3.8543331623 3.9739034176 4.0471410751 712 1311867742.3694241047 0.2087923884 0.1047054869 0.2390826792 0.0048805629 0.5272020000 0.0870500000 0.0690190000 0.0000010000 0.3667870000 0.0023350000 137505235 0 402718720 3.8533070087 3.9732766151 4.0471811295 713 1311867742.4062991142 0.2098399252 0.1048529405 0.2390826792 0.0048772630 0.9341190000 0.1007140000 0.0590940000 0.0421630000 0.3558120000 0.3745010000 137509019 0 402718720 3.8525302410 3.9735040665 4.0467329025 714 1311867742.4346439838 0.2108515650 0.1050013980 0.2390826792 0.0048739398 0.5157920000 0.0804330000 0.0826440000 0.0000010000 0.3491080000 0.0017420000 137512579 0 402718720 3.8518507481 3.9729101658 4.0467557907 715 1311867742.4666969776 0.2102721035 0.1051486297 0.2390826792 0.0048707636 0.5136230000 0.0796960000 0.0443040000 0.0339510000 0.3519980000 0.0017480000 137516251 0 402718720 3.8527252674 3.9738166332 4.0460710526 716 1311867742.5047059059 0.2105825841 0.1052958838 0.2390826792 0.0048675638 0.4958280000 0.0803610000 0.0587960000 0.0000010000 0.3530410000 0.0017450000 137520035 0 402718720 3.8529288769 3.9741101265 4.0459909439 717 1311867742.5359389782 0.2100024372 0.1054419181 0.2390826792 0.0048656068 0.8961990000 0.0792550000 0.0513030000 0.0339540000 0.3531370000 0.3767120000 137523707 0 402718720 3.8539996147 3.9752895832 4.0460267067 718 1311867742.5678529739 0.2099393308 0.1055874577 0.2390826792 0.0048631334 0.5038520000 0.1017940000 0.0465400000 0.0000010000 0.3518930000 0.0017400000 137527435 0 402718720 3.8544788361 3.9754452705 4.0459833145 719 1311867742.6054639816 0.2113697529 0.1057345819 0.2390826792 0.0048605281 0.5594850000 0.0795360000 0.0918810000 0.0340490000 0.3503900000 0.0017450000 137531219 0 402718720 3.8534262180 3.9743118286 4.0461311340 720 1311867742.6347279549 0.2106246501 0.1058802625 0.2390826792 0.0048574258 0.5111780000 0.0801900000 0.0728830000 0.0000010000 0.3545300000 0.0017020000 137534779 0 402718720 3.8545076847 3.9751024246 4.0460901260 721 1311867742.6724960804 0.2109217048 0.1060259511 0.2390826792 0.0048546914 0.9377710000 0.0802090000 0.0916960000 0.0340810000 0.3521540000 0.3777830000 137538675 0 402718720 3.8544826508 3.9745545387 4.0462441444 722 1311867742.7046229839 0.2110094577 0.1061713576 0.2390826792 0.0048513359 0.4897560000 0.0800310000 0.0513240000 0.0000000000 0.3547970000 0.0017290000 137542291 0 402718720 3.8547103405 3.9740679264 4.0462536812 723 1311867742.7356119156 0.2108537853 0.1063161465 0.2390826792 0.0048479921 0.5754310000 0.0916480000 0.0913170000 0.0335490000 0.3553090000 0.0017380000 137545963 0 402718720 3.8552882671 3.9743711948 4.0461754799 724 1311867742.7726070881 0.2109936327 0.1064607287 0.2390826792 0.0048450441 0.5063140000 0.0794210000 0.0689330000 0.0000000000 0.3543460000 0.0017370000 137549803 0 402718720 3.8557205200 3.9736638069 4.0462069511 725 1311867742.8034689426 0.2117738277 0.1066059882 0.2390826792 0.0048447888 0.9023430000 0.0780790000 0.0508990000 0.0340450000 0.3568100000 0.3806640000 137553475 0 402718720 3.8549299240 3.9737579823 4.0461115837 726 1311867742.8352251053 0.2125699669 0.1067519441 0.2390826792 0.0048445220 0.5060190000 0.0793690000 0.0652570000 0.0000010000 0.3577710000 0.0017270000 137557091 0 402718720 3.8549315929 3.9738340378 4.0462732315 727 1311867742.8705639839 0.2128829807 0.1068979290 0.2390826792 0.0048414421 0.5186840000 0.0792780000 0.0439330000 0.0340700000 0.3577530000 0.0017600000 137560819 0 402718720 3.8548669815 3.9744019508 4.0461597443 728 1311867742.9046700001 0.2124130428 0.1070428673 0.2390826792 0.0048384667 0.5233460000 0.0933210000 0.0683630000 0.0000010000 0.3580450000 0.0017270000 137564547 0 402718720 3.8559613228 3.9740078449 4.0463957787 729 1311867742.9382069111 0.2128857821 0.1071880565 0.2390826792 0.0048543380 0.9246030000 0.0794470000 0.0610500000 0.0341210000 0.3615210000 0.3866030000 137568331 0 402718720 3.8553133011 3.9743795395 4.0461888313 730 1311867742.9707310200 0.2131093442 0.1073331542 0.2390826792 0.0048558482 0.4906000000 0.0784850000 0.0510340000 0.0000010000 0.3574510000 0.0017270000 137572003 0 402718720 3.8555912971 3.9743199348 4.0462431908 731 1311867743.0024189949 0.2138525099 0.1074788715 0.2390826792 0.0048570762 0.5269300000 0.0789140000 0.0507000000 0.0341340000 0.3595440000 0.0017390000 137575619 0 402718720 3.8550651073 3.9743223190 4.0463967323 732 1311867743.0345149040 0.2130788714 0.1076231338 0.2390826792 0.0048582153 0.4932880000 0.0783090000 0.0505040000 0.0000010000 0.3608890000 0.0016860000 137579291 0 402718720 3.8563485146 3.9748864174 4.0462832451 733 1311867743.0722420216 0.2136702836 0.1077678093 0.2390826792 0.0048572260 0.9286560000 0.0928800000 0.0608440000 0.0337280000 0.3558910000 0.3834440000 137583131 0 402718720 3.8561520576 3.9740266800 4.0459499359 734 1311867743.1045989990 0.2135079205 0.1079118694 0.2390826792 0.0048552656 0.5333090000 0.0794350000 0.0907750000 0.0000010000 0.3594990000 0.0017400000 137586803 0 402718720 3.8567698002 3.9746775627 4.0460720062 735 1311867743.1350400448 0.2138780206 0.1080560410 0.2390826792 0.0048532748 0.5220380000 0.0799220000 0.0460250000 0.0342570000 0.3582000000 0.0017410000 137590419 0 402718720 3.8571419716 3.9744017124 4.0461559296 736 1311867743.1704380512 0.2143538296 0.1082004673 0.2390826792 0.0048555821 0.5022530000 0.0790570000 0.0580160000 0.0000000000 0.3615420000 0.0017220000 137594147 0 402718720 3.8566956520 3.9738657475 4.0457801819 737 1311867743.2037980556 0.2138044685 0.1083437564 0.2390826792 0.0048535274 0.9066220000 0.0793370000 0.0461560000 0.0337690000 0.3595880000 0.3859060000 137597875 0 402718720 3.8576142788 3.9749042988 4.0452356339 738 1311867743.2358140945 0.2151930183 0.1084885386 0.2390826792 0.0048518463 0.5471390000 0.0925610000 0.0908520000 0.0000010000 0.3600710000 0.0017320000 137601491 0 402718720 3.8569388390 3.9742207527 4.0459222794 739 1311867743.2708129883 0.2151204497 0.1086328307 0.2390826792 0.0048525399 0.5212010000 0.0786870000 0.0455560000 0.0340520000 0.3591100000 0.0017940000 137605275 0 402718720 3.8571674824 3.9749979973 4.0460677147 740 1311867743.3032529354 0.2144598067 0.1087758401 0.2390826792 0.0048606531 0.4900380000 0.0798020000 0.0460000000 0.0000010000 0.3605690000 0.0017360000 137608947 0 402718720 3.8579330444 3.9755995274 4.0458765030 741 1311867743.3363931179 0.2134891599 0.1089171537 0.2390826792 0.0048574733 0.9474860000 0.0781070000 0.0851550000 0.0339490000 0.3623900000 0.3860020000 137612619 0 402718720 3.8591499329 3.9755203724 4.0461373329 742 1311867743.3707330227 0.2139699608 0.1090587343 0.2390826792 0.0048548327 0.5242240000 0.0972450000 0.0609700000 0.0000010000 0.3623330000 0.0017320000 137616347 0 402718720 3.8586802483 3.9765532017 4.0458979607 743 1311867743.4043838978 0.2145063877 0.1092006557 0.2390826792 0.0048516675 0.5382430000 0.0798650000 0.0610420000 0.0337990000 0.3598600000 0.0017360000 137620075 0 402718720 3.8584566116 3.9756727219 4.0466251373 744 1311867743.4352641106 0.2152527720 0.1093431989 0.2390826792 0.0048526798 0.4982480000 0.0803130000 0.0510510000 0.0000010000 0.3632240000 0.0017340000 137623747 0 402718720 3.8577394485 3.9749665260 4.0467724800 745 1311867743.4768960476 0.2155689746 0.1094857838 0.2390826792 0.0048518486 0.9425990000 0.0800340000 0.0533990000 0.0344250000 0.3692600000 0.4033950000 137627643 0 402718720 3.8577721119 3.9749124050 4.0471777916 746 1311867743.5035250187 0.2163494080 0.1096290327 0.2390826792 0.0048494797 0.5512600000 0.1009890000 0.0775400000 0.0000000000 0.3690580000 0.0017330000 137631203 0 402718720 3.8571209908 3.9759206772 4.0470066071 747 1311867743.5389750004 0.2162623107 0.1097717814 0.2390826792 0.0048489913 0.5247320000 0.0803100000 0.0438180000 0.0338780000 0.3630490000 0.0017380000 137634931 0 402718720 3.8569974899 3.9755282402 4.0468616486 748 1311867743.5749680996 0.2167838663 0.1099148457 0.2390826792 0.0048495167 0.5240960000 0.0898950000 0.0681460000 0.0000010000 0.3623930000 0.0017270000 137638715 0 402718720 3.8571581841 3.9756629467 4.0467491150 749 1311867743.6036109924 0.2168337554 0.1100575945 0.2390826792 0.0048539821 0.9136520000 0.0916400000 0.0367200000 0.0343700000 0.3631110000 0.3858990000 137642275 0 402718720 3.8566019535 3.9763123989 4.0467772484 750 1311867743.6354589462 0.2170019299 0.1102001870 0.2390826792 0.0048542284 0.5344860000 0.0805740000 0.0867560000 0.0000000000 0.3634810000 0.0017330000 137645947 0 402718720 3.8563497066 3.9753992558 4.0467333794 751 1311867743.6759150028 0.2168742418 0.1103422297 0.2390826792 0.0048511049 0.5714510000 0.0804500000 0.0905580000 0.0339210000 0.3628380000 0.0017350000 137649843 0 402718720 3.8563425541 3.9750797749 4.0464730263 752 1311867743.7034959793 0.2158199996 0.1104824927 0.2390826792 0.0048483433 0.5348080000 0.0806490000 0.0865000000 0.0000010000 0.3639960000 0.0017320000 137653403 0 402718720 3.8571882248 3.9758625031 4.0460109711 753 1311867743.7388861179 0.2162087411 0.1106228994 0.2390826792 0.0048463032 0.9413840000 0.0797880000 0.0524950000 0.0342980000 0.3686450000 0.4040780000 137657187 0 402718720 3.8566265106 3.9753277302 4.0457363129 754 1311867743.7733619213 0.2167844325 0.1107636971 0.2390826792 0.0048433222 0.5511870000 0.1004490000 0.0828620000 0.0000000000 0.3641960000 0.0017240000 137660971 0 402718720 3.8558804989 3.9741339684 4.0458364487 755 1311867743.8064749241 0.2174192071 0.1109049627 0.2390826792 0.0048411319 0.5265640000 0.0801130000 0.0437850000 0.0343930000 0.3646100000 0.0017360000 137664587 0 402718720 3.8550796509 3.9747891426 4.0455632210 756 1311867743.8391659260 0.2180335522 0.1110466672 0.2390826792 0.0048385484 0.4910490000 0.0786640000 0.0437110000 0.0000010000 0.3650130000 0.0017250000 137668259 0 402718720 3.8540039062 3.9739518166 4.0449905396 757 1311867743.8726658821 0.2169368714 0.1111865486 0.2390826792 0.0048360795 0.9259310000 0.0789630000 0.0574380000 0.0341720000 0.3654930000 0.3879450000 137672043 0 402718720 3.8550817966 3.9737777710 4.0449872017 758 1311867743.9031310081 0.2173539400 0.1113266111 0.2390826792 0.0048331078 0.5084940000 0.1047850000 0.0386390000 0.0000010000 0.3611690000 0.0018210000 137675659 0 402718720 3.8547635078 3.9742600918 4.0446443558 759 1311867743.9453630447 0.2192113549 0.1114687517 0.2390826792 0.0048305446 0.5370880000 0.0799420000 0.0529920000 0.0341730000 0.3662890000 0.0017370000 137679611 0 402718720 3.8527560234 3.9731657505 4.0448198318 760 1311867743.9741249084 0.2180884182 0.1116090408 0.2390826792 0.0048289973 0.5206410000 0.1011690000 0.0535370000 0.0000010000 0.3620500000 0.0018210000 137683171 0 402718720 3.8535535336 3.9747660160 4.0435786247 761 1311867744.0042529106 0.2177016586 0.1117484529 0.2390826792 0.0048305340 0.9583950000 0.0804710000 0.0863670000 0.0343920000 0.3659890000 0.3892350000 137686731 0 402718720 3.8541734219 3.9768838882 4.0435104370 762 1311867744.0407259464 0.2175003290 0.1118872349 0.2390826792 0.0048297772 0.5084790000 0.0806270000 0.0437980000 0.0000010000 0.3796450000 0.0022890000 137690571 0 402718720 3.8545084000 3.9749639034 4.0438604355 763 1311867744.0716118813 0.2166339159 0.1120245176 0.2390826792 0.0048277880 0.6009870000 0.1000080000 0.0748770000 0.0427810000 0.3796500000 0.0017250000 137694187 0 402718720 3.8553524017 3.9762442112 4.0437054634 764 1311867744.1111290455 0.2175542861 0.1121626455 0.2390826792 0.0048252716 0.5145260000 0.0807150000 0.0686630000 0.0000010000 0.3612480000 0.0018220000 137697915 0 402718720 3.8543632030 3.9753406048 4.0437803268 765 1311867744.1412119865 0.2172909230 0.1123000681 0.2390826792 0.0048226027 0.9201360000 0.0805840000 0.0537110000 0.0339210000 0.3620450000 0.3879550000 137701531 0 402718720 3.8545355797 3.9769518375 4.0431194305 766 1311867744.1734991074 0.2174954414 0.1124373989 0.2390826792 0.0048210492 0.5476460000 0.0918570000 0.0870640000 0.0000010000 0.3650360000 0.0017240000 137705259 0 402718720 3.8548204899 3.9782760143 4.0434641838 767 1311867744.2046771049 0.2184472680 0.1125756125 0.2390826792 0.0048249815 0.5481160000 0.0811910000 0.0654460000 0.0344290000 0.3633540000 0.0017430000 137708875 0 402718720 3.8537170887 3.9760808945 4.0435318947 768 1311867744.2400228977 0.2176719010 0.1127124567 0.2390826792 0.0048222734 0.5486870000 0.0920380000 0.0914810000 0.0000010000 0.3613890000 0.0017680000 137712715 0 402718720 3.8541591167 3.9756095409 4.0428161621 769 1311867744.2773048878 0.2180846483 0.1128494816 0.2390826792 0.0048210816 0.9449820000 0.1025930000 0.0581730000 0.0340870000 0.3634940000 0.3846830000 137716499 0 402718720 3.8539767265 3.9783577919 4.0429534912 770 1311867744.3032519817 0.2180460840 0.1129861006 0.2390826792 0.0048201360 0.5229950000 0.0814790000 0.0744760000 0.0000000000 0.3633910000 0.0017000000 137720003 0 402718720 3.8537912369 3.9764266014 4.0430884361 771 1311867744.3391230106 0.2172417194 0.1131213219 0.2390826792 0.0048234795 0.5534370000 0.0944600000 0.0588970000 0.0344270000 0.3619210000 0.0017470000 137723787 0 402718720 3.8544654846 3.9759259224 4.0424585342 772 1311867744.3707659245 0.2171160132 0.1132560300 0.2390826792 0.0048218109 0.5351110000 0.0810710000 0.0879700000 0.0000010000 0.3623710000 0.0017370000 137727403 0 402718720 3.8549611568 3.9776203632 4.0425624847 773 1311867744.4027431011 0.2179415375 0.1133914576 0.2390826792 0.0048195445 0.9310370000 0.0951060000 0.0541430000 0.0344300000 0.3617100000 0.3836790000 137731131 0 402718720 3.8544001579 3.9767179489 4.0430927277 774 1311867744.4383800030 0.2185536623 0.1135273261 0.2390826792 0.0048170044 0.4914410000 0.0809150000 0.0442770000 0.0000010000 0.3625250000 0.0017430000 137734859 0 402718720 3.8537442684 3.9763002396 4.0429291725 775 1311867744.4717690945 0.2192486823 0.1136637407 0.2390826792 0.0048141508 0.5560940000 0.0820290000 0.0734760000 0.0344200000 0.3624300000 0.0017430000 137738587 0 402718720 3.8530189991 3.9762749672 4.0426788330 776 1311867744.5026860237 0.2182125151 0.1137984685 0.2390826792 0.0048113816 0.4989610000 0.0809380000 0.0515450000 0.0000000000 0.3627600000 0.0017400000 137742259 0 402718720 3.8544309139 3.9774327278 4.0426697731 777 1311867744.5383169651 0.2185011655 0.1139332210 0.2390826792 0.0048115350 0.9205340000 0.0807610000 0.0568340000 0.0344350000 0.3624690000 0.3840770000 137746043 0 402718720 3.8541245461 3.9764986038 4.0422940254 778 1311867744.5726189613 0.2177004814 0.1140665980 0.2390826792 0.0048093177 0.5377450000 0.0848710000 0.0862340000 0.0000010000 0.3629210000 0.0017440000 137749771 0 402718720 3.8547742367 3.9763076305 4.0416493416 779 1311867744.6028740406 0.2192929834 0.1142016768 0.2390826792 0.0048120205 0.5659060000 0.0806250000 0.0764800000 0.0344670000 0.3705690000 0.0017510000 137753387 0 402718720 3.8539965153 3.9760408401 4.0425767899 780 1311867744.6386809349 0.2179508060 0.1143346885 0.2390826792 0.0048132208 0.4898330000 0.0806740000 0.0463360000 0.0000010000 0.3588730000 0.0018380000 137757171 0 402718720 3.8548305035 3.9767644405 4.0417923927 781 1311867744.6707758904 0.2173659056 0.1144666107 0.2390826792 0.0048103080 0.9229810000 0.0932300000 0.0463540000 0.0345210000 0.3627630000 0.3841480000 137760843 0 402718720 3.8553776741 3.9766604900 4.0415740013 782 1311867744.7029349804 0.2189080715 0.1146001675 0.2390826792 0.0048129169 0.5060270000 0.0808080000 0.0585550000 0.0000010000 0.3629460000 0.0017420000 137764515 0 402718720 3.8546242714 3.9765157700 4.0421643257 783 1311867744.7396171093 0.2173254788 0.1147313620 0.2390826792 0.0048160327 0.5667860000 0.0793630000 0.0863050000 0.0341460000 0.3632780000 0.0016970000 137768299 0 402718720 3.8556818962 3.9781188965 4.0415887833 784 1311867744.7705199718 0.2188022584 0.1148641055 0.2390826792 0.0048138076 0.4986520000 0.0807860000 0.0513950000 0.0000010000 0.3627500000 0.0017370000 137771915 0 402718720 3.8541979790 3.9766027927 4.0422053337 785 1311867744.8035891056 0.2190290242 0.1149967997 0.2390826792 0.0048142445 0.9013190000 0.0817150000 0.0371930000 0.0344330000 0.3622300000 0.3837580000 137775643 0 402718720 3.8541910648 3.9756910801 4.0418877602 786 1311867744.8424170017 0.2188573480 0.1151289378 0.2390826792 0.0048117775 0.5050020000 0.0942770000 0.0444920000 0.0000010000 0.3624770000 0.0017300000 137779483 0 402718720 3.8545300961 3.9764630795 4.0416378975 787 1311867744.8727390766 0.2181646824 0.1152598600 0.2390826792 0.0048124826 0.5689980000 0.0811210000 0.0872080000 0.0344260000 0.3625050000 0.0017310000 137783155 0 402718720 3.8548488617 3.9756898880 4.0419383049 788 1311867744.9029939175 0.2189722955 0.1153914747 0.2390826792 0.0048098150 0.5276060000 0.1035790000 0.0616530000 0.0000010000 0.3584130000 0.0018290000 137786771 0 402718720 3.8538441658 3.9748394489 4.0416088104 789 1311867744.9392940998 0.2181188315 0.1155216742 0.2390826792 0.0048090775 0.9519820000 0.0808150000 0.0890400000 0.0344510000 0.3623900000 0.3833140000 137790611 0 402718720 3.8553121090 3.9761097431 4.0409817696 790 1311867744.9708900452 0.2175404131 0.1156508118 0.2390826792 0.0048089989 0.4994730000 0.0939780000 0.0371140000 0.0000010000 0.3639100000 0.0022940000 137794171 0 402718720 3.8557076454 3.9762187004 4.0410618782 791 1311867745.0027489662 0.2184605598 0.1157807862 0.2390826792 0.0048148335 0.6079540000 0.1012190000 0.0781890000 0.0435750000 0.3804870000 0.0023030000 137797843 0 402718720 3.8550586700 3.9758031368 4.0401124954 792 1311867745.0384869576 0.2183133215 0.1159102465 0.2390826792 0.0048151530 0.4957090000 0.0902310000 0.0370230000 0.0000010000 0.3647200000 0.0017290000 137801627 0 402718720 3.8548901081 3.9755823612 4.0398511887 793 1311867745.0729780197 0.2189000100 0.1160401201 0.2390826792 0.0048148333 0.9252310000 0.0804320000 0.0613690000 0.0340230000 0.3611820000 0.3862270000 137805355 0 402718720 3.8544645309 3.9752318859 4.0398445129 794 1311867745.1118760109 0.2185000181 0.1161691628 0.2390826792 0.0048163700 0.5382310000 0.0810470000 0.0915660000 0.0000010000 0.3616620000 0.0018210000 137809195 0 402718720 3.8548233509 3.9760036469 4.0397434235 795 1311867745.1405589581 0.2184679657 0.1162978405 0.2390826792 0.0048135093 0.5268010000 0.0803890000 0.0422600000 0.0344900000 0.3658850000 0.0017340000 137812755 0 402718720 3.8551073074 3.9764485359 4.0398564339 796 1311867745.1729030609 0.2197420597 0.1164277956 0.2390826792 0.0048108862 0.5160350000 0.0804360000 0.0687010000 0.0000010000 0.3629300000 0.0018230000 137816427 0 402718720 3.8538992405 3.9749302864 4.0400218964 797 1311867745.2068369389 0.2206082642 0.1165585113 0.2390826792 0.0048079780 0.9292730000 0.0801260000 0.0578250000 0.0345280000 0.3669970000 0.3878250000 137820155 0 402718720 3.8530471325 3.9751856327 4.0401172638 798 1311867745.2430789471 0.2197510302 0.1166878253 0.2390826792 0.0048080325 0.5261610000 0.0888900000 0.0653280000 0.0000010000 0.3681930000 0.0017250000 137823939 0 402718720 3.8545758724 3.9767184258 4.0405836105 799 1311867745.2729060650 0.2203240693 0.1168175327 0.2390826792 0.0048050565 0.5290610000 0.0802190000 0.0457720000 0.0345680000 0.3647400000 0.0017350000 137827555 0 402718720 3.8540725708 3.9766221046 4.0404295921 800 1311867745.3112850189 0.2209947109 0.1169477542 0.2390826792 0.0048025010 0.5016930000 0.0786880000 0.0501590000 0.0000010000 0.3691060000 0.0017190000 137831339 0 402718720 3.8537743092 3.9754552841 4.0411567688 801 1311867745.3395059109 0.2207171768 0.1170773040 0.2390826792 0.0047995338 0.9395280000 0.0799500000 0.0647970000 0.0345610000 0.3686440000 0.3895660000 137834955 0 402718720 3.8542191982 3.9753260612 4.0408596992 802 1311867745.3733940125 0.2209091038 0.1172067701 0.2390826792 0.0047971970 0.5325870000 0.0804650000 0.0829560000 0.0000000000 0.3652030000 0.0018230000 137838683 0 402718720 3.8543655872 3.9747045040 4.0411300659 803 1311867745.4102098942 0.2216892540 0.1173368853 0.2390826792 0.0047947704 0.5885100000 0.0914550000 0.0716240000 0.0345890000 0.3863410000 0.0022810000 137842467 0 402718720 3.8543159962 3.9744312763 4.0420236588 804 1311867745.4433169365 0.2226919532 0.1174679239 0.2390826792 0.0047920500 0.5416790000 0.1002030000 0.0579460000 0.0000010000 0.3797840000 0.0017170000 137846195 0 402718720 3.8531706333 3.9749372005 4.0414023399 805 1311867745.4708619118 0.2210787833 0.1175966330 0.2390826792 0.0047894459 0.9417630000 0.0984820000 0.0439330000 0.0346320000 0.3709480000 0.3917400000 137849699 0 402718720 3.8548345566 3.9754357338 4.0408649445 806 1311867745.5099780560 0.2225176692 0.1177268080 0.2390826792 0.0047873152 0.5447080000 0.0802300000 0.0893660000 0.0000000000 0.3713700000 0.0017160000 137853595 0 402718720 3.8539302349 3.9753773212 4.0414280891 807 1311867745.5417380333 0.2228563279 0.1178570801 0.2390826792 0.0047865611 0.5777690000 0.0796650000 0.0899040000 0.0346280000 0.3697820000 0.0017200000 137857267 0 402718720 3.8540232182 3.9737126827 4.0416221619 808 1311867745.5704059601 0.2215180695 0.1179853734 0.2390826792 0.0047840960 0.5639600000 0.1014960000 0.0898140000 0.0000000000 0.3686820000 0.0018100000 137860827 0 402718720 3.8553359509 3.9730117321 4.0410804749 809 1311867745.6133821011 0.2221292853 0.1181141050 0.2390826792 0.0047814883 0.9731380000 0.0794580000 0.0890590000 0.0345770000 0.3733750000 0.3946460000 137864835 0 402718720 3.8550424576 3.9731700420 4.0411419868 810 1311867745.6438291073 0.2228262424 0.1182433793 0.2390826792 0.0047802060 0.5398050000 0.0788760000 0.0827450000 0.0000010000 0.3744200000 0.0017080000 137868507 0 402718720 3.8546719551 3.9731991291 4.0415372849 811 1311867745.6709001064 0.2235252410 0.1183731966 0.2390826792 0.0047854954 0.5492540000 0.0792850000 0.0568090000 0.0345620000 0.3748030000 0.0017200000 137871955 0 402718720 3.8543126583 3.9741106033 4.0416631699 812 1311867745.7088780403 0.2231279165 0.1185022049 0.2390826792 0.0047834317 0.5534220000 0.0782120000 0.0843630000 0.0000000000 0.3863570000 0.0022610000 137875851 0 402718720 3.8549957275 3.9742422104 4.0408854485 813 1311867745.7423269749 0.2238554806 0.1186317907 0.2390826792 0.0047813371 1.0416220000 0.0995180000 0.1124770000 0.0433330000 0.3867950000 0.3974660000 137879523 0 402718720 3.8542635441 3.9739737511 4.0413312912 814 1311867745.7760419846 0.2245735675 0.1187619403 0.2390826792 0.0047862957 0.5301180000 0.0979480000 0.0524030000 0.0000010000 0.3759800000 0.0017110000 137883251 0 402718720 3.8539197445 3.9728982449 4.0414829254 815 1311867745.8116889000 0.2246679068 0.1188918863 0.2390826792 0.0047912780 0.5819220000 0.0788190000 0.0884820000 0.0346840000 0.3761570000 0.0017240000 137887035 0 402718720 3.8542783260 3.9735729694 4.0420145988 816 1311867745.8389890194 0.2243931890 0.1190211771 0.2390826792 0.0047913079 0.5331530000 0.0798030000 0.0745100000 0.0000000000 0.3750790000 0.0017070000 137890595 0 402718720 3.8547599316 3.9728386402 4.0426926613 817 1311867745.8709759712 0.2265301496 0.1191527670 0.2390826792 0.0047895929 0.9777510000 0.0792500000 0.0841250000 0.0343370000 0.3781850000 0.3998100000 137894211 0 402718720 3.8526656628 3.9731006622 4.0431885719 818 1311867745.9108459949 0.2253722101 0.1192826196 0.2390826792 0.0047886222 0.5382630000 0.0990520000 0.0565480000 0.0000000000 0.3788900000 0.0017040000 137898107 0 402718720 3.8541040421 3.9746470451 4.0426263809 819 1311867745.9435789585 0.2260692120 0.1194130062 0.2390826792 0.0047893887 0.5788620000 0.0777200000 0.0834590000 0.0344670000 0.3794300000 0.0017070000 137901835 0 402718720 3.8534765244 3.9729621410 4.0425453186 820 1311867745.9732220173 0.2280497104 0.1195454900 0.2390826792 0.0047872928 0.5188270000 0.0793010000 0.0596460000 0.0000010000 0.3758880000 0.0018010000 137905395 0 402718720 3.8524472713 3.9703068733 4.0446896553 821 1311867746.0083909035 0.2287150025 0.1196784614 0.2390826792 0.0047850246 0.9648080000 0.0786300000 0.0667170000 0.0342910000 0.3807900000 0.4023250000 137909123 0 402718720 3.8522071838 3.9706368446 4.0449204445 822 1311867746.0391409397 0.2282861471 0.1198105875 0.2390826792 0.0047823449 0.5268630000 0.0780870000 0.0628660000 0.0000010000 0.3821410000 0.0016900000 137912851 0 402718720 3.8532049656 3.9703898430 4.0452485085 823 1311867746.0728518963 0.2280881405 0.1199421520 0.2390826792 0.0047797631 0.6098490000 0.1048020000 0.0877430000 0.0350000000 0.3785170000 0.0016940000 137916523 0 402718720 3.8535857201 3.9710650444 4.0446186066 824 1311867746.1113359928 0.2281378359 0.1200734574 0.2390826792 0.0047782175 0.5494000000 0.0783650000 0.0833450000 0.0000010000 0.3839390000 0.0016940000 137920307 0 402718720 3.8539433479 3.9707243443 4.0443625450 825 1311867746.1412689686 0.2308584750 0.1202077423 0.2390826792 0.0047768489 0.9884520000 0.0778280000 0.0827440000 0.0347380000 0.3845880000 0.4064770000 137923979 0 402718720 3.8519580364 3.9689745903 4.0458860397 826 1311867746.1721889973 0.2304833233 0.1203412478 0.2390826792 0.0047742590 0.5502820000 0.0779300000 0.0826050000 0.0000000000 0.3859930000 0.0016860000 137927595 0 402718720 3.8519988060 3.9701116085 4.0445528030 827 1311867746.2066209316 0.2287340164 0.1204723153 0.2390826792 0.0047723564 0.5977830000 0.0905140000 0.0824400000 0.0347880000 0.3863070000 0.0016870000 137931323 0 402718720 3.8537340164 3.9719955921 4.0431380272 828 1311867746.2386920452 0.2315314710 0.1206064447 0.2390826792 0.0047713756 0.5841670000 0.0989880000 0.0868030000 0.0000000000 0.3945910000 0.0016850000 137935051 0 402718720 3.8513164520 3.9684851170 4.0450987816 829 1311867746.2704648972 0.2320961505 0.1207409317 0.2390826792 0.0047685307 0.9663140000 0.0779560000 0.0582720000 0.0349900000 0.3834910000 0.4093440000 137938723 0 402718720 3.8510291576 3.9670162201 4.0459694862 830 1311867746.3068819046 0.2293659896 0.1208718052 0.2390826792 0.0047684615 0.6170320000 0.0968370000 0.1087900000 0.0000010000 0.4068950000 0.0022000000 137942451 0 402718720 3.8536427021 3.9688372612 4.0450596809 831 1311867746.3393440247 0.2307398170 0.1210040170 0.2390826792 0.0047705832 0.5956530000 0.0974560000 0.0697140000 0.0348940000 0.3898050000 0.0016800000 137946179 0 402718720 3.8525454998 3.9689352512 4.0451059341 832 1311867746.3797800541 0.2322225869 0.1211376932 0.2390826792 0.0047685424 0.5548210000 0.0777330000 0.0856490000 0.0000010000 0.3876310000 0.0016770000 137950075 0 402718720 3.8510906696 3.9670741558 4.0462074280 833 1311867746.4078478813 0.2312118858 0.1212698351 0.2390826792 0.0047679594 1.0050130000 0.0771720000 0.0856740000 0.0348990000 0.3907640000 0.4144320000 137953635 0 402718720 3.8523488045 3.9675600529 4.0461387634 834 1311867746.4389901161 0.2308143824 0.1214011835 0.2390826792 0.0047652669 0.5071170000 0.0769460000 0.0347190000 0.0000010000 0.3916640000 0.0016720000 137957251 0 402718720 3.8525063992 3.9688014984 4.0459704399 835 1311867746.4774639606 0.2297990620 0.1215310013 0.2390826792 0.0047649099 0.5538370000 0.0753520000 0.0474270000 0.0346010000 0.3926530000 0.0016760000 137961147 0 402718720 3.8530099392 3.9687559605 4.0450234413 836 1311867746.5066781044 0.2297724932 0.1216604767 0.2390826792 0.0047623645 0.5271260000 0.0893630000 0.0411260000 0.0000010000 0.3928510000 0.0016700000 137964707 0 402718720 3.8533213139 3.9683113098 4.0451765060 837 1311867746.5406761169 0.2301932871 0.1217901456 0.2390826792 0.0047625068 0.9770030000 0.0766150000 0.0543100000 0.0342780000 0.3931670000 0.4165300000 137968435 0 402718720 3.8528468609 3.9694309235 4.0455007553 838 1311867746.5748629570 0.2310022563 0.1219204703 0.2390826792 0.0047603965 0.5690410000 0.0883960000 0.0849430000 0.0000010000 0.3919050000 0.0016760000 137972219 0 402718720 3.8519725800 3.9687314034 4.0458021164 839 1311867746.6067559719 0.2288156599 0.1220478781 0.2390826792 0.0047603353 0.5896900000 0.0766120000 0.0807860000 0.0348620000 0.3935920000 0.0016730000 137975835 0 402718720 3.8534355164 3.9704196453 4.0439224243 840 1311867746.6396849155 0.2300878465 0.1221764972 0.2390826792 0.0047628596 0.5290920000 0.0767430000 0.0543440000 0.0000010000 0.3942030000 0.0016760000 137979619 0 402718720 3.8526389599 3.9694163799 4.0451555252 841 1311867746.6749529839 0.2298124582 0.1223044828 0.2390826792 0.0047644497 1.0142570000 0.1117390000 0.0570010000 0.0349220000 0.3908450000 0.4176300000 137983347 0 402718720 3.8526926041 3.9696502686 4.0442976952 842 1311867746.7095060349 0.2304461300 0.1224329171 0.2390826792 0.0047617535 0.5572960000 0.0771170000 0.0852650000 0.0000010000 0.3909470000 0.0017720000 137987075 0 402718720 3.8525505066 3.9683024883 4.0451855659 843 1311867746.7391049862 0.2307990044 0.1225614652 0.2390826792 0.0047595544 0.6126630000 0.0978600000 0.0804810000 0.0345150000 0.3960270000 0.0016750000 137990635 0 402718720 3.8523871899 3.9678051472 4.0454273224 844 1311867746.7751340866 0.2314217687 0.1226904467 0.2390826792 0.0047570204 0.5633210000 0.0890400000 0.0736150000 0.0000000000 0.3968890000 0.0016680000 137994475 0 402718720 3.8520205021 3.9674265385 4.0457820892 845 1311867746.8070099354 0.2309818417 0.1228186021 0.2390826792 0.0047552926 0.9838640000 0.0749710000 0.0539450000 0.0348840000 0.3971050000 0.4208680000 137998147 0 402718720 3.8523213863 3.9675841331 4.0449981689 846 1311867746.8401610851 0.2309640348 0.1229464336 0.2390826792 0.0047526327 0.5319350000 0.0764020000 0.0539310000 0.0000010000 0.3978030000 0.0016600000 138001819 0 402718720 3.8524570465 3.9667394161 4.0450944901 847 1311867746.8748359680 0.2282634377 0.1230707748 0.2390826792 0.0047505915 0.5909690000 0.0745450000 0.0790800000 0.0347190000 0.3988510000 0.0016310000 138005603 0 402718720 3.8544716835 3.9685769081 4.0424647331 848 1311867746.9086029530 0.2296956033 0.1231965117 0.2390826792 0.0047486515 0.5504390000 0.0885540000 0.0634780000 0.0000010000 0.3944320000 0.0017490000 138009275 0 402718720 3.8539817333 3.9694013596 4.0437703133 849 1311867746.9389610291 0.2297808975 0.1233220528 0.2390826792 0.0047462779 1.0264790000 0.0885200000 0.0803920000 0.0348460000 0.3984010000 0.4222170000 138012947 0 402718720 3.8542976379 3.9674503803 4.0443091393 850 1311867746.9748229980 0.2294648141 0.1234469266 0.2390826792 0.0047470998 0.5644760000 0.1048740000 0.0405480000 0.0000010000 0.4145560000 0.0021710000 138016731 0 402718720 3.8552920818 3.9677693844 4.0438771248 851 1311867747.0066559315 0.2288252711 0.1235707554 0.2390826792 0.0047496379 0.6542200000 0.0943500000 0.1056740000 0.0436840000 0.4067130000 0.0016600000 138020347 0 402718720 3.8549921513 3.9687185287 4.0429682732 852 1311867747.0389339924 0.2298619300 0.1236955103 0.2390826792 0.0047478430 0.5429180000 0.0863890000 0.0533410000 0.0000010000 0.3993870000 0.0016530000 138024019 0 402718720 3.8546092510 3.9665503502 4.0444650650 853 1311867747.0749640465 0.2296741754 0.1238197526 0.2390826792 0.0047462046 1.0021360000 0.0885600000 0.0534650000 0.0348940000 0.3995780000 0.4235130000 138027859 0 402718720 3.8552832603 3.9678511620 4.0441975594 854 1311867747.1066820621 0.2287462503 0.1239426174 0.2390826792 0.0047501408 0.5556430000 0.0764050000 0.0768020000 0.0000000000 0.3986300000 0.0016650000 138031475 0 402718720 3.8559415340 3.9678194523 4.0441908836 855 1311867747.1389479637 0.2286498398 0.1240650820 0.2390826792 0.0047479377 0.5531500000 0.0761830000 0.0427110000 0.0350420000 0.3951720000 0.0017640000 138035147 0 402718720 3.8564586639 3.9693489075 4.0443711281 856 1311867747.1744880676 0.2287773192 0.1241874093 0.2390826792 0.0047459539 0.5336560000 0.0760910000 0.0541270000 0.0000000000 0.3996470000 0.0016660000 138038931 0 402718720 3.8564524651 3.9686512947 4.0443205833 857 1311867747.2066030502 0.2287397385 0.1243094074 0.2390826792 0.0047442312 1.0139560000 0.0752100000 0.0792700000 0.0348120000 0.3993900000 0.4231380000 138042603 0 402718720 3.8565115929 3.9680273533 4.0442366600 858 1311867747.2385439873 0.2277435213 0.1244299600 0.2390826792 0.0047424487 0.5586530000 0.0755990000 0.0793320000 0.0000010000 0.3999280000 0.0016590000 138046331 0 402718720 3.8574633598 3.9689640999 4.0429983139 859 1311867747.2745490074 0.2287990302 0.1245514606 0.2390826792 0.0047536920 0.6675340000 0.0950790000 0.1059540000 0.0437310000 0.4182240000 0.0021720000 138050115 0 402718720 3.8571538925 3.9677395821 4.0441904068 860 1311867747.3064720631 0.2300312817 0.1246741116 0.2390826792 0.0047626598 0.6067690000 0.0938720000 0.1055110000 0.0000010000 0.4036000000 0.0016500000 138053675 0 402718720 3.8564004898 3.9665389061 4.0452842712 861 1311867747.3388469219 0.2267370224 0.1247926515 0.2390826792 0.0047884492 1.0158750000 0.0745550000 0.0790700000 0.0348100000 0.4007290000 0.4245910000 138057459 0 402718720 3.8588385582 3.9677729607 4.0428991318 862 1311867747.3758800030 0.2291321456 0.1249136950 0.2390826792 0.0047983754 0.5603560000 0.0756040000 0.0795040000 0.0000010000 0.4014390000 0.0016600000 138061187 0 402718720 3.8575844765 3.9666166306 4.0448579788 863 1311867747.4068729877 0.2278564721 0.1250329798 0.2390826792 0.0047986461 0.6210120000 0.1012700000 0.0794960000 0.0348740000 0.4015550000 0.0016580000 138064859 0 402718720 3.8586335182 3.9679114819 4.0440626144 864 1311867747.4396450520 0.2261141986 0.1251499720 0.2390826792 0.0047985848 0.5340290000 0.0752790000 0.0557980000 0.0000010000 0.3991410000 0.0016570000 138068475 0 402718720 3.8599796295 3.9693412781 4.0424880981 865 1311867747.4756069183 0.2272594869 0.1252680177 0.2390826792 0.0047999598 1.0551540000 0.0741050000 0.0779240000 0.0412160000 0.4209360000 0.4388270000 138072259 0 402718720 3.8591229916 3.9679348469 4.0434556007 866 1311867747.5095520020 0.2263353318 0.1253847236 0.2390826792 0.0047994259 0.5943550000 0.0902180000 0.0782440000 0.0000010000 0.4213800000 0.0021480000 138076043 0 402718720 3.8602712154 3.9693334103 4.0434184074 867 1311867747.5405330658 0.2250786424 0.1254997108 0.2390826792 0.0048054756 0.6286840000 0.0936930000 0.0790720000 0.0426560000 0.4087470000 0.0021440000 138079659 0 402718720 3.8608703613 3.9697513580 4.0414695740 868 1311867747.5766739845 0.2275393605 0.1256172680 0.2390826792 0.0048057729 0.6252180000 0.0938140000 0.1049720000 0.0000010000 0.4219320000 0.0021440000 138083443 0 402718720 3.8591501713 3.9678730965 4.0432982445 869 1311867747.6086390018 0.2193792611 0.1257251644 0.2390826792 0.0048388350 1.0265000000 0.0748160000 0.0820710000 0.0350850000 0.4037950000 0.4285750000 138087115 0 402718720 3.8640618324 3.9745850563 4.0348744392 870 1311867747.6432039738 0.2258254141 0.1258402222 0.2390826792 0.0048589944 0.5649300000 0.0744420000 0.0828470000 0.0000010000 0.4038200000 0.0016510000 138090899 0 402718720 3.8604412079 3.9701392651 4.0419650078 871 1311867747.6760280132 0.2251311392 0.1259542186 0.2390826792 0.0048621149 0.5972850000 0.0747430000 0.0821750000 0.0349980000 0.4015260000 0.0016480000 138094571 0 402718720 3.8610694408 3.9697759151 4.0418643951 872 1311867747.7068400383 0.2222369164 0.1260646346 0.2390826792 0.0048705993 0.5726740000 0.0861500000 0.0776880000 0.0000010000 0.4050190000 0.0016500000 138098187 0 402718720 3.8611936569 3.9743516445 4.0359673500 873 1311867747.7480750084 0.2277216017 0.1261810801 0.2390826792 0.0049113453 1.0511790000 0.1008050000 0.0799490000 0.0351090000 0.4044240000 0.4287430000 138102251 0 402718720 3.8581905365 3.9699468613 4.0427331924 874 1311867747.7826869488 0.2269827574 0.1262964139 0.2390826792 0.0049090295 0.5346540000 0.0747610000 0.0462280000 0.0000010000 0.4098540000 0.0016380000 138105979 0 402718720 3.8589940071 3.9692096710 4.0428376198 875 1311867747.8149020672 0.2249145359 0.1264091203 0.2390826792 0.0049087516 0.6110100000 0.0888720000 0.0820830000 0.0350420000 0.4011630000 0.0016460000 138109651 0 402718720 3.8597774506 3.9697031975 4.0407290459 876 1311867747.8466539383 0.2265549898 0.1265234420 0.2390826792 0.0049079843 0.5589600000 0.0749870000 0.0756840000 0.0000000000 0.4044770000 0.0016410000 138113267 0 402718720 3.8586335182 3.9703767300 4.0420780182 877 1311867747.8827810287 0.2295015156 0.1266408629 0.2390826792 0.0049157585 1.0234950000 0.0751810000 0.0780920000 0.0350190000 0.4041910000 0.4288530000 138117107 0 402718720 3.8563692570 3.9692053795 4.0444803238 878 1311867747.9150440693 0.2282556444 0.1267565973 0.2390826792 0.0049133520 0.5753540000 0.0891670000 0.0781460000 0.0000010000 0.4042510000 0.0016280000 138120835 0 402718720 3.8560111523 3.9702236652 4.0421090126 879 1311867747.9477820396 0.2303735763 0.1268744778 0.2390826792 0.0049120008 0.5947450000 0.0743080000 0.0780750000 0.0348840000 0.4036540000 0.0016420000 138124507 0 402718720 3.8546237946 3.9686396122 4.0447268486 880 1311867747.9826579094 0.2302978337 0.1269920043 0.2390826792 0.0049096603 0.5723920000 0.0867420000 0.0785800000 0.0000000000 0.4032480000 0.0016420000 138128235 0 402718720 3.8544895649 3.9683880806 4.0451984406 881 1311867748.0146598816 0.2320328355 0.1271112334 0.2390826792 0.0049108994 0.9887610000 0.0754570000 0.0463770000 0.0349490000 0.4025810000 0.4272260000 138131907 0 402718720 3.8527772427 3.9680318832 4.0468177795 882 1311867748.0469269753 0.2320121378 0.1272301687 0.2390826792 0.0049084503 0.5716200000 0.0866560000 0.0789960000 0.0000010000 0.4021380000 0.0016350000 138135579 0 402718720 3.8517768383 3.9688467979 4.0462570190 883 1311867748.0828750134 0.2334367782 0.1273504480 0.2390826792 0.0049065990 0.5881770000 0.0953600000 0.0527360000 0.0350160000 0.4012300000 0.0016530000 138139419 0 402718720 3.8501741886 3.9681203365 4.0475511551 884 1311867748.1150569916 0.2339103818 0.1274709909 0.2390826792 0.0049060001 0.5697830000 0.0980740000 0.0671320000 0.0000010000 0.4007480000 0.0016380000 138143035 0 402718720 3.8498976231 3.9675323963 4.0489482880 885 1311867748.1486010551 0.2349876016 0.1275924786 0.2390826792 0.0049050034 0.9980510000 0.0760430000 0.0606530000 0.0344800000 0.4001680000 0.4245460000 138146763 0 402718720 3.8479020596 3.9684925079 4.0482745171 886 1311867748.1831040382 0.2340571880 0.1277126419 0.2390826792 0.0049026001 0.5362380000 0.0746520000 0.0578260000 0.0000010000 0.3999270000 0.0016550000 138150435 0 402718720 3.8486139774 3.9680361748 4.0481681824 887 1311867748.2148320675 0.2368245125 0.1278356542 0.2390826792 0.0049036297 0.5553740000 0.0758630000 0.0425810000 0.0346270000 0.3984440000 0.0016580000 138154163 0 402718720 3.8464477062 3.9670705795 4.0505676270 888 1311867748.2466599941 0.2360324264 0.1279574974 0.2390826792 0.0049022512 0.5574520000 0.0751160000 0.0831280000 0.0000000000 0.3951290000 0.0017520000 138157779 0 402718720 3.8467404842 3.9678485394 4.0495657921 889 1311867748.2827599049 0.2351357639 0.1280780579 0.2390826792 0.0048999283 0.9770870000 0.0758210000 0.0425710000 0.0350470000 0.3986580000 0.4227990000 138161563 0 402718720 3.8472833633 3.9677953720 4.0490098000 890 1311867748.3148829937 0.2348959148 0.1281980779 0.2390826792 0.0049060966 0.5587300000 0.0764700000 0.0798160000 0.0000010000 0.3985980000 0.0016520000 138165235 0 402718720 3.8475992680 3.9673020840 4.0494818687 891 1311867748.3470869064 0.2353339344 0.1283183202 0.2390826792 0.0049094083 0.5525900000 0.0756160000 0.0404140000 0.0343990000 0.3982900000 0.0016540000 138168907 0 402718720 3.8467431068 3.9667072296 4.0490107536 892 1311867748.3826999664 0.2355950624 0.1284385856 0.2390826792 0.0049100916 0.5589040000 0.0765170000 0.0801860000 0.0000010000 0.3983390000 0.0016520000 138172691 0 402718720 3.8465642929 3.9672613144 4.0493645668 893 1311867748.4148259163 0.2353655100 0.1285583246 0.2390826792 0.0049077553 1.0083810000 0.1049680000 0.0495800000 0.0349620000 0.3950850000 0.4215890000 138176307 0 402718720 3.8461365700 3.9685208797 4.0483469963 894 1311867748.4520189762 0.2364532053 0.1286790124 0.2390826792 0.0049121378 0.5579650000 0.0761880000 0.0845970000 0.0000010000 0.3933120000 0.0016490000 138180147 0 402718720 3.8449044228 3.9671015739 4.0494675636 895 1311867748.4831318855 0.2359601408 0.1287988796 0.2390826792 0.0049096186 0.5906580000 0.0760170000 0.0843870000 0.0349630000 0.3912190000 0.0017470000 138183819 0 402718720 3.8448359966 3.9677984715 4.0486011505 896 1311867748.5149960518 0.2343901396 0.1289167269 0.2390826792 0.0049072705 0.5802300000 0.0891370000 0.0843420000 0.0000010000 0.4021560000 0.0021670000 138187491 0 402718720 3.8460395336 3.9685044289 4.0477209091 897 1311867748.5467929840 0.2361671180 0.1290362926 0.2390826792 0.0049053820 1.0154760000 0.0955830000 0.0636660000 0.0423450000 0.3938990000 0.4177930000 138191107 0 402718720 3.8444650173 3.9675233364 4.0493750572 898 1311867748.5827159882 0.2369040549 0.1291564126 0.2390826792 0.0049027211 0.5399420000 0.0886640000 0.0544180000 0.0000000000 0.3929720000 0.0016600000 138194891 0 402718720 3.8432943821 3.9678101540 4.0493092537 899 1311867748.6147999763 0.2351457775 0.1292743096 0.2390826792 0.0049009931 0.5883800000 0.0768070000 0.0808850000 0.0349040000 0.3919210000 0.0016600000 138198619 0 402718720 3.8447391987 3.9685788155 4.0489559174 900 1311867748.6470849514 0.2356935740 0.1293925532 0.2390826792 0.0049100771 0.5520720000 0.0774500000 0.0837670000 0.0000010000 0.3867200000 0.0017530000 138202235 0 402718720 3.8442342281 3.9683923721 4.0500373840 901 1311867748.6827559471 0.2346793115 0.1295094086 0.2390826792 0.0049078378 0.9840670000 0.0761070000 0.0673810000 0.0348140000 0.3899450000 0.4136280000 138206019 0 402718720 3.8450596333 3.9682025909 4.0498809814 902 1311867748.7147359848 0.2341784388 0.1296254497 0.2390826792 0.0049254124 0.5498200000 0.1015840000 0.0556240000 0.0000000000 0.3887060000 0.0016640000 138209691 0 402718720 3.8458132744 3.9668962955 4.0504994392 903 1311867748.7499361038 0.2355916798 0.1297427988 0.2390826792 0.0049233225 0.5775320000 0.0953700000 0.0574040000 0.0344820000 0.3863500000 0.0016730000 138213419 0 402718720 3.8441934586 3.9664890766 4.0511078835 904 1311867748.7828259468 0.2349601686 0.1298591897 0.2390826792 0.0049211959 0.5307210000 0.0767750000 0.0611510000 0.0000010000 0.3888890000 0.0016700000 138217203 0 402718720 3.8442637920 3.9669735432 4.0504593849 905 1311867748.8151619434 0.2348952889 0.1299752517 0.2390826792 0.0049187741 0.9777520000 0.0903190000 0.0505140000 0.0349620000 0.3875660000 0.4121300000 138220875 0 402718720 3.8441309929 3.9671394825 4.0507750511 906 1311867748.8466329575 0.2343926579 0.1300905027 0.2390826792 0.0049162053 0.5151760000 0.0757180000 0.0476600000 0.0000010000 0.3878950000 0.0016650000 138224435 0 402718720 3.8441083431 3.9673275948 4.0505619049 907 1311867748.8829579353 0.2340069711 0.1302050743 0.2390826792 0.0049141694 0.5846050000 0.0773710000 0.0815200000 0.0348710000 0.3869170000 0.0016760000 138228219 0 402718720 3.8436188698 3.9674785137 4.0501079559 908 1311867748.9149119854 0.2330762446 0.1303183685 0.2390826792 0.0049126700 0.5589090000 0.0870850000 0.0814910000 0.0000010000 0.3864450000 0.0016700000 138231947 0 402718720 3.8437561989 3.9685432911 4.0498237610 909 1311867748.9472498894 0.2346004844 0.1304330903 0.2390826792 0.0049101395 0.9538550000 0.0768480000 0.0508240000 0.0349110000 0.3808020000 0.4082730000 138235619 0 402718720 3.8418352604 3.9674959183 4.0505952835 910 1311867748.9829359055 0.2322159261 0.1305449396 0.2390826792 0.0049086731 0.5589850000 0.0888910000 0.0815460000 0.0000000000 0.3846380000 0.0016780000 138239403 0 402718720 3.8430233002 3.9683122635 4.0489830971 911 1311867749.0159859657 0.2313075662 0.1306555462 0.2390826792 0.0049059984 0.5540820000 0.0908660000 0.0413160000 0.0339690000 0.3840190000 0.0016730000 138243075 0 402718720 3.8432638645 3.9695012569 4.0482397079 912 1311867749.0467190742 0.2307064831 0.1307652512 0.2390826792 0.0049036973 0.5105020000 0.0768600000 0.0508170000 0.0000000000 0.3786610000 0.0017760000 138246691 0 402718720 3.8434391022 3.9693884850 4.0481958389 913 1311867749.0828969479 0.2304415703 0.1308744257 0.2390826792 0.0049011454 1.0007470000 0.0929190000 0.0820250000 0.0347120000 0.3822800000 0.4065620000 138250475 0 402718720 3.8432471752 3.9695558548 4.0480732918 914 1311867749.1158421040 0.2289317846 0.1309817095 0.2390826792 0.0048994706 0.5232950000 0.0773030000 0.0603390000 0.0000000000 0.3817280000 0.0016770000 138254203 0 402718720 3.8443684578 3.9705741405 4.0473599434 915 1311867749.1485249996 0.2289200276 0.1310887459 0.2390826792 0.0048968081 0.5373670000 0.0773770000 0.0441040000 0.0348410000 0.3770970000 0.0016870000 138257931 0 402718720 3.8440806866 3.9710412025 4.0474143028 916 1311867749.1829619408 0.2287933379 0.1311954103 0.2390826792 0.0048946379 0.5417250000 0.0758190000 0.0817930000 0.0000000000 0.3801640000 0.0016780000 138261659 0 402718720 3.8434484005 3.9711434841 4.0472025871 917 1311867749.2156000137 0.2277485877 0.1313007027 0.2390826792 0.0048923979 0.9481520000 0.0755860000 0.0531460000 0.0343430000 0.3796850000 0.4031420000 138265275 0 402718720 3.8442635536 3.9712481499 4.0467514992 918 1311867749.2468719482 0.2274885029 0.1314054825 0.2390826792 0.0048933284 0.5271220000 0.0902220000 0.0537480000 0.0000010000 0.3791900000 0.0016890000 138268891 0 402718720 3.8443033695 3.9706175327 4.0461230278 919 1311867749.2828478813 0.2281044126 0.1315107044 0.2390826792 0.0048948815 0.5874560000 0.1008850000 0.0727470000 0.0347840000 0.3748710000 0.0017920000 138272675 0 402718720 3.8438906670 3.9699296951 4.0473475456 920 1311867749.3148140907 0.2275087982 0.1316150501 0.2390826792 0.0048938008 0.5111710000 0.0776080000 0.0516210000 0.0000010000 0.3779940000 0.0016900000 138276403 0 402718720 3.8437449932 3.9717631340 4.0457601547 921 1311867749.3468968868 0.2268649191 0.1317184702 0.2390826792 0.0048917115 0.9638860000 0.0779720000 0.0694680000 0.0347090000 0.3778480000 0.4016480000 138280019 0 402718720 3.8437607288 3.9724195004 4.0453376770 922 1311867749.3828470707 0.2262222171 0.1318209688 0.2390826792 0.0048891252 0.5152160000 0.0781720000 0.0561920000 0.0000010000 0.3769000000 0.0016950000 138283803 0 402718720 3.8433995247 3.9731366634 4.0439972878 923 1311867749.4147930145 0.2238795608 0.1319207073 0.2390826792 0.0048874364 0.5375920000 0.0785530000 0.0447360000 0.0347230000 0.3756310000 0.0016900000 138287531 0 402718720 3.8449616432 3.9753072262 4.0426335335 924 1311867749.4467489719 0.2243571132 0.1320207467 0.2390826792 0.0048850763 0.5070960000 0.0790730000 0.0497800000 0.0000010000 0.3742890000 0.0016920000 138291147 0 402718720 3.8439531326 3.9760975838 4.0425553322 925 1311867749.4829080105 0.2227258980 0.1321188063 0.2390826792 0.0048850103 0.9570580000 0.0793950000 0.0744760000 0.0342250000 0.3715840000 0.3951180000 138294931 0 402718720 3.8443629742 3.9758555889 4.0417647362 926 1311867749.5159850121 0.2233577967 0.1322173365 0.2390826792 0.0048828102 0.5391540000 0.0792690000 0.0845080000 0.0000010000 0.3714070000 0.0017010000 138298603 0 402718720 3.8433253765 3.9743509293 4.0426168442 927 1311867749.5468530655 0.2241809517 0.1323165421 0.2390826792 0.0048802582 0.5709660000 0.0776100000 0.0838910000 0.0343440000 0.3711580000 0.0016630000 138302275 0 402718720 3.8413667679 3.9748330116 4.0418629646 928 1311867749.5830268860 0.2233270258 0.1324146138 0.2390826792 0.0048778266 0.5540660000 0.1095620000 0.0705920000 0.0000010000 0.3699310000 0.0016960000 138306059 0 402718720 3.8413636684 3.9747073650 4.0415673256 929 1311867749.6148250103 0.2224911898 0.1325115746 0.2390826792 0.0048754315 0.9272530000 0.0788490000 0.0524700000 0.0341740000 0.3670230000 0.3924660000 138309675 0 402718720 3.8412959576 3.9748954773 4.0410037041 930 1311867749.6469049454 0.2221546918 0.1326079650 0.2390826792 0.0048743738 0.5347140000 0.0790400000 0.0829460000 0.0000010000 0.3687510000 0.0017020000 138313403 0 402718720 3.8415474892 3.9743592739 4.0415229797 931 1311867749.6829149723 0.2221053541 0.1327040954 0.2390826792 0.0048722944 0.5434100000 0.0793330000 0.0572690000 0.0345980000 0.3682170000 0.0017080000 138317187 0 402718720 3.8402962685 3.9740004539 4.0407958031 932 1311867749.7160799503 0.2221275270 0.1328000433 0.2390826792 0.0048701202 0.5013940000 0.0791140000 0.0501830000 0.0000000000 0.3681210000 0.0017080000 138320859 0 402718720 3.8396432400 3.9740242958 4.0401301384 933 1311867749.7468609810 0.2216590941 0.1328952834 0.2390826792 0.0048716524 0.9681150000 0.0880390000 0.0847810000 0.0339700000 0.3675680000 0.3915130000 138324531 0 402718720 3.8400628567 3.9736628532 4.0401597023 934 1311867749.7828791142 0.2192912102 0.1329877844 0.2390826792 0.0048705439 0.5255330000 0.0899180000 0.0638260000 0.0000010000 0.3677630000 0.0017020000 138328315 0 402718720 3.8413381577 3.9732918739 4.0390882492 935 1311867749.8148949146 0.2182299644 0.1330789525 0.2390826792 0.0048718819 0.5276040000 0.0786690000 0.0430310000 0.0344740000 0.3674110000 0.0017080000 138331931 0 402718720 3.8417093754 3.9737160206 4.0386710167 936 1311867749.8469030857 0.2184098214 0.1331701180 0.2390826792 0.0048696703 0.5142790000 0.0770090000 0.0494930000 0.0000000000 0.3830040000 0.0022520000 138335659 0 402718720 3.8413376808 3.9743130207 4.0389699936 937 1311867749.8829030991 0.2192400545 0.1332619749 0.2390826792 0.0048851778 1.0197650000 0.0989170000 0.1129670000 0.0430240000 0.3721920000 0.3903750000 138339443 0 402718720 3.8403065205 3.9735059738 4.0388188362 938 1311867749.9149639606 0.2177012563 0.1333519955 0.2390826792 0.0049003663 0.5054150000 0.0779280000 0.0598640000 0.0000000000 0.3636180000 0.0017050000 138343059 0 402718720 3.8407306671 3.9739000797 4.0381174088 939 1311867749.9508709908 0.2169754207 0.1334410513 0.2390826792 0.0048985623 0.5475390000 0.0789370000 0.0654230000 0.0343830000 0.3647900000 0.0016970000 138346843 0 402718720 3.8411519527 3.9737408161 4.0382351875 940 1311867749.9827940464 0.2166227400 0.1335295425 0.2390826792 0.0048982978 0.4956040000 0.0787300000 0.0485610000 0.0000010000 0.3643230000 0.0017020000 138350571 0 402718720 3.8409531116 3.9741587639 4.0378289223 941 1311867750.0147750378 0.2147570401 0.1336158629 0.2390826792 0.0048964446 0.9282460000 0.0782330000 0.0626280000 0.0343050000 0.3634030000 0.3873710000 138354243 0 402718720 3.8424086571 3.9737362862 4.0376043320 942 1311867750.0470709801 0.2138675004 0.1337010557 0.2390826792 0.0048940327 0.5123880000 0.0801320000 0.0484120000 0.0000000000 0.3790550000 0.0022630000 138357915 0 402718720 3.8427555561 3.9735612869 4.0370221138 943 1311867750.0829339027 0.2142164409 0.1337864379 0.2390826792 0.0048922470 0.5709940000 0.0983690000 0.0579880000 0.0427040000 0.3679090000 0.0017050000 138361699 0 402718720 3.8419256210 3.9738225937 4.0368752480 944 1311867750.1156458855 0.2139251381 0.1338713305 0.2390826792 0.0048901602 0.5294520000 0.0785190000 0.0856780000 0.0000000000 0.3612400000 0.0017020000 138365371 0 402718720 3.8417468071 3.9738204479 4.0366282463 945 1311867750.1474790573 0.2136945724 0.1339557996 0.2390826792 0.0048881849 0.9446500000 0.0772440000 0.0834540000 0.0342580000 0.3634660000 0.3838980000 138369043 0 402718720 3.8416774273 3.9739460945 4.0366759300 946 1311867750.1828711033 0.2128899843 0.1340392395 0.2390826792 0.0048869556 0.5085910000 0.1018950000 0.0457330000 0.0000010000 0.3569370000 0.0017140000 138372827 0 402718720 3.8419928551 3.9739608765 4.0361566544 947 1311867750.2156589031 0.2126462460 0.1341222459 0.2390826792 0.0048848081 0.5158680000 0.0780430000 0.0457490000 0.0342140000 0.3535970000 0.0018040000 138376499 0 402718720 3.8418269157 3.9746656418 4.0360207558 948 1311867750.2469079494 0.2124050409 0.1342048227 0.2390826792 0.0048823072 0.5448910000 0.1018240000 0.0734350000 0.0000000000 0.3647830000 0.0022850000 138380115 0 402718720 3.8416366577 3.9746789932 4.0358757973 949 1311867750.2829968929 0.2116953135 0.1342864775 0.2390826792 0.0048817507 0.9937150000 0.0984850000 0.0960230000 0.0425510000 0.3719210000 0.3824340000 138383899 0 402718720 3.8420011997 3.9754731655 4.0361509323 950 1311867750.3150129318 0.2118102014 0.1343680815 0.2390826792 0.0048794625 0.4929310000 0.0781650000 0.0562960000 0.0000010000 0.3544300000 0.0017140000 138387627 0 402718720 3.8413376808 3.9759197235 4.0357480049 951 1311867750.3469090462 0.2099763006 0.1344475854 0.2390826792 0.0048788831 0.5500520000 0.0790780000 0.0798140000 0.0336860000 0.3534340000 0.0017190000 138391243 0 402718720 3.8429844379 3.9745864868 4.0356512070 952 1311867750.3828659058 0.2103963494 0.1345273635 0.2390826792 0.0048763879 0.4920630000 0.0784760000 0.0564030000 0.0000010000 0.3531600000 0.0017150000 138395027 0 402718720 3.8424072266 3.9755680561 4.0356411934 953 1311867750.4148640633 0.2103319466 0.1346069066 0.2390826792 0.0048739411 0.9170080000 0.0940580000 0.0593290000 0.0340850000 0.3522190000 0.3749950000 138398755 0 402718720 3.8420972824 3.9752960205 4.0356259346 954 1311867750.4469859600 0.2095398158 0.1346854526 0.2390826792 0.0048714440 0.5024680000 0.0786250000 0.0593690000 0.0000000000 0.3596130000 0.0022900000 138402371 0 402718720 3.8423943520 3.9749522209 4.0353846550 955 1311867750.4829618931 0.2091065198 0.1347633804 0.2390826792 0.0048694739 0.5816660000 0.0989010000 0.0682850000 0.0423450000 0.3672710000 0.0023040000 138406099 0 402718720 3.8423187733 3.9753396511 4.0344514847 956 1311867750.5148859024 0.2090289891 0.1348410641 0.2390826792 0.0048671068 0.5025700000 0.0987970000 0.0488230000 0.0000000000 0.3509090000 0.0017230000 138409715 0 402718720 3.8420259953 3.9754502773 4.0341401100 957 1311867750.5476069450 0.2079082578 0.1349174144 0.2390826792 0.0048652593 0.8815860000 0.0772160000 0.0436970000 0.0337620000 0.3510860000 0.3734710000 138413443 0 402718720 3.8429059982 3.9747209549 4.0337972641 958 1311867750.5827779770 0.2075894624 0.1349932725 0.2390826792 0.0048649848 0.4960260000 0.0904660000 0.0512670000 0.0000010000 0.3502230000 0.0017260000 138417227 0 402718720 3.8429112434 3.9757955074 4.0335736275 959 1311867750.6148829460 0.2068878114 0.1350682407 0.2390826792 0.0048634455 0.5171480000 0.0775960000 0.0535180000 0.0337790000 0.3481870000 0.0017290000 138420843 0 402718720 3.8431534767 3.9763536453 4.0330843925 960 1311867750.6469810009 0.2066427171 0.1351427975 0.2390826792 0.0048611810 0.4885420000 0.0785970000 0.0617260000 0.0000010000 0.3439190000 0.0018160000 138424571 0 402718720 3.8427410126 3.9761064053 4.0327444077 961 1311867750.6829319000 0.2063915133 0.1352169376 0.2390826792 0.0048611904 0.8949030000 0.0782140000 0.0442470000 0.0338270000 0.3558940000 0.3803910000 138428355 0 402718720 3.8425333500 3.9769792557 4.0329179764 962 1311867750.7149219513 0.2047163844 0.1352891824 0.2390826792 0.0048606946 0.5067680000 0.0916880000 0.0588890000 0.0000010000 0.3512940000 0.0023240000 138432083 0 402718720 3.8438975811 3.9768376350 4.0327062607 963 1311867750.7469151020 0.2045574486 0.1353611121 0.2390826792 0.0048584965 0.5952240000 0.0997880000 0.0878350000 0.0422020000 0.3603300000 0.0023810000 138435699 0 402718720 3.8437623978 3.9761116505 4.0327887535 964 1311867750.7832129002 0.2038083076 0.1354321154 0.2390826792 0.0048586304 0.4860080000 0.0928150000 0.0444870000 0.0000000000 0.3446060000 0.0017330000 138439427 0 402718720 3.8441441059 3.9765725136 4.0329809189 965 1311867750.8149549961 0.2025313824 0.1355016483 0.2390826792 0.0048562043 0.8908930000 0.0971840000 0.0544750000 0.0338390000 0.3393260000 0.3637500000 138442987 0 402718720 3.8453149796 3.9777877331 4.0331864357 966 1311867750.8468461037 0.2021637261 0.1355706566 0.2390826792 0.0048582763 0.4754800000 0.0786310000 0.0543410000 0.0000000000 0.3381780000 0.0018370000 138446659 0 402718720 3.8452665806 3.9775807858 4.0329627991 967 1311867750.8828840256 0.2015242279 0.1356388610 0.2390826792 0.0048559217 0.5025240000 0.0777490000 0.0463800000 0.0331140000 0.3411730000 0.0017410000 138450499 0 402718720 3.8456118107 3.9777097702 4.0328073502 968 1311867750.9147970676 0.2006377727 0.1357060086 0.2390826792 0.0048543835 0.4793100000 0.0986100000 0.0354490000 0.0000010000 0.3411530000 0.0017430000 138454115 0 402718720 3.8464553356 3.9779102802 4.0329332352 969 1311867750.9468770027 0.2007486522 0.1357731321 0.2390826792 0.0048528117 0.9073890000 0.0796770000 0.0884080000 0.0338390000 0.3404180000 0.3624320000 138457787 0 402718720 3.8460936546 3.9783658981 4.0329566002 970 1311867750.9830369949 0.2001259625 0.1358394752 0.2390826792 0.0048519954 0.4879030000 0.0788960000 0.0648430000 0.0000010000 0.3400560000 0.0017400000 138461627 0 402718720 3.8464961052 3.9773600101 4.0328264236 971 1311867751.0168409348 0.1986795813 0.1359041921 0.2390826792 0.0048512023 0.5949890000 0.0793580000 0.1134690000 0.0418760000 0.3553430000 0.0023390000 138465355 0 402718720 3.8475692272 3.9769623280 4.0324125290 972 1311867751.0470340252 0.1979373544 0.1359680122 0.2390826792 0.0048500635 0.5363360000 0.0997440000 0.0888640000 0.0000010000 0.3436380000 0.0017490000 138468971 0 402718720 3.8476421833 3.9779727459 4.0319037437 973 1311867751.0828599930 0.1961940080 0.1360299094 0.2390826792 0.0048477186 0.8657740000 0.0874800000 0.0470650000 0.0336920000 0.3351190000 0.3600670000 138472699 0 402718720 3.8489689827 3.9781448841 4.0311641693 974 1311867751.1174809933 0.1970257908 0.1360925335 0.2390826792 0.0048455958 0.5211210000 0.0931640000 0.0690860000 0.0000010000 0.3539340000 0.0023290000 138476483 0 402718720 3.8475644588 3.9769766331 4.0307769775 975 1311867751.1468789577 0.1962210089 0.1361542038 0.2390826792 0.0048457712 0.5752850000 0.0989940000 0.0883960000 0.0416300000 0.3421350000 0.0017450000 138480043 0 402718720 3.8483114243 3.9773707390 4.0304369926 976 1311867751.1835930347 0.1946841180 0.1362141730 0.2390826792 0.0048449328 0.4793680000 0.0787930000 0.0621690000 0.0000000000 0.3340570000 0.0018380000 138483883 0 402718720 3.8491587639 3.9781186581 4.0299477577 977 1311867751.2161049843 0.1954601705 0.1362748137 0.2390826792 0.0048427615 0.8565720000 0.0772860000 0.0464740000 0.0334200000 0.3373900000 0.3596450000 138487555 0 402718720 3.8480041027 3.9780821800 4.0297222137 978 1311867751.2468481064 0.1955891252 0.1363354623 0.2390826792 0.0048414823 0.4862030000 0.0928730000 0.0519430000 0.0000000000 0.3372460000 0.0017410000 138491171 0 402718720 3.8478341103 3.9776172638 4.0294485092 979 1311867751.2831909657 0.1955017745 0.1363958977 0.2390826792 0.0048435943 0.5365540000 0.0782270000 0.0842140000 0.0334930000 0.3365060000 0.0017420000 138495011 0 402718720 3.8476281166 3.9799492359 4.0294342041 980 1311867751.3149859905 0.1950456202 0.1364557444 0.2390826792 0.0048413109 0.4773630000 0.0788900000 0.0604010000 0.0000010000 0.3339610000 0.0017420000 138498627 0 402718720 3.8478782177 3.9802031517 4.0292057991 981 1311867751.3498640060 0.1958062351 0.1365162444 0.2390826792 0.0048402206 0.8589270000 0.0790750000 0.0522990000 0.0334960000 0.3346280000 0.3570540000 138502411 0 402718720 3.8465843201 3.9783968925 4.0288805962 982 1311867751.3834669590 0.1943774968 0.1365751662 0.2390826792 0.0048388547 0.4701390000 0.0792990000 0.0522150000 0.0000000000 0.3344720000 0.0017390000 138506139 0 402718720 3.8475518227 3.9799988270 4.0281362534 983 1311867751.4151160717 0.1929874867 0.1366325541 0.2390826792 0.0048384411 0.5087690000 0.0861580000 0.0546060000 0.0334100000 0.3304410000 0.0017490000 138509811 0 402718720 3.8490884304 3.9803850651 4.0274143219 984 1311867751.4513890743 0.1925720274 0.1366894032 0.2390826792 0.0048372409 0.4820380000 0.0781010000 0.0668110000 0.0000010000 0.3330290000 0.0017070000 138513539 0 402718720 3.8490712643 3.9783194065 4.0271749496 985 1311867751.4838130474 0.1929572672 0.1367465279 0.2390826792 0.0048348377 0.9137880000 0.1002650000 0.0931960000 0.0335080000 0.3294480000 0.3549940000 138517267 0 402718720 3.8486778736 3.9788146019 4.0266704559 986 1311867751.5149779320 0.1924865693 0.1368030594 0.2390826792 0.0048339203 0.5054830000 0.0788680000 0.0927310000 0.0000010000 0.3297480000 0.0017400000 138520939 0 402718720 3.8486597538 3.9801502228 4.0264763832 987 1311867751.5495769978 0.1922091097 0.1368591952 0.2390826792 0.0048317008 0.5007900000 0.0790390000 0.0522350000 0.0333700000 0.3320050000 0.0017530000 138524667 0 402718720 3.8486413956 3.9796950817 4.0263776779 988 1311867751.5829720497 0.1906984746 0.1369136884 0.2390826792 0.0048295422 0.4871090000 0.0986470000 0.0522180000 0.0000010000 0.3321150000 0.0017550000 138528339 0 402718720 3.8504123688 3.9798462391 4.0261988640 989 1311867751.6149520874 0.1905221045 0.1369678931 0.2390826792 0.0048280272 0.8438360000 0.0788640000 0.0449820000 0.0332190000 0.3314730000 0.3528950000 138532011 0 402718720 3.8503842354 3.9804472923 4.0260200500 990 1311867751.6501350403 0.1892897189 0.1370207434 0.2390826792 0.0048262187 0.4745020000 0.0793520000 0.0600200000 0.0000010000 0.3309670000 0.0017520000 138535739 0 402718720 3.8509964943 3.9799854755 4.0256686211 991 1311867751.6839730740 0.1889097840 0.1370731037 0.2390826792 0.0048238402 0.5150670000 0.0796040000 0.0673830000 0.0333650000 0.3305370000 0.0017570000 138539523 0 402718720 3.8511760235 3.9799563885 4.0254611969 992 1311867751.7150709629 0.1879640967 0.1371244051 0.2390826792 0.0048226904 0.5035370000 0.0798550000 0.0897430000 0.0000010000 0.3297720000 0.0017570000 138543083 0 402718720 3.8519418240 3.9794514179 4.0252528191 993 1311867751.7507519722 0.1870982945 0.1371747313 0.2390826792 0.0048205692 0.8524470000 0.0946070000 0.0474960000 0.0332780000 0.3256170000 0.3490330000 138546867 0 402718720 3.8523917198 3.9793896675 4.0249447823 994 1311867751.7830109596 0.1873557270 0.1372252152 0.2390826792 0.0048190683 0.4737090000 0.0797510000 0.0602430000 0.0000010000 0.3295440000 0.0017610000 138550539 0 402718720 3.8517670631 3.9791049957 4.0248398781 995 1311867751.8149600029 0.1864204407 0.1372746576 0.2390826792 0.0048178047 0.5236160000 0.1045820000 0.0556670000 0.0328170000 0.3263680000 0.0017690000 138554211 0 402718720 3.8524768353 3.9800307751 4.0247340202 996 1311867751.8509531021 0.1854721159 0.1373230486 0.2390826792 0.0048168609 0.4815110000 0.0798380000 0.0709620000 0.0000000000 0.3265160000 0.0017680000 138557995 0 402718720 3.8530931473 3.9796552658 4.0244121552 997 1311867751.8832330704 0.1852771640 0.1373711470 0.2390826792 0.0048147443 0.8800920000 0.0799870000 0.0691950000 0.0332060000 0.3321960000 0.3628500000 138561667 0 402718720 3.8528091908 3.9793589115 4.0243172646 998 1311867751.9149179459 0.1849213690 0.1374187926 0.2390826792 0.0048143673 0.5576550000 0.1009010000 0.1175280000 0.0000000000 0.3350320000 0.0017580000 138565283 0 402718720 3.8525729179 3.9801418781 4.0243034363 999 1311867751.9530611038 0.1822141856 0.1374636328 0.2390826792 0.0048130220 0.5321330000 0.0796570000 0.0898110000 0.0330480000 0.3254150000 0.0017720000 138569179 0 402718720 3.8549451828 3.9805741310 4.0240378380 1000 1311867751.9829521179 0.1814975590 0.1375076667 0.2390826792 0.0048112686 0.4547390000 0.0797460000 0.0478890000 0.0000010000 0.3229160000 0.0017740000 138572795 0 402718720 3.8552520275 3.9800863266 4.0239100456 1001 1311867752.0153670311 0.1813724786 0.1375514877 0.2390826792 0.0048114137 0.8813850000 0.0912000000 0.0902010000 0.0329610000 0.3228630000 0.3417440000 138576411 0 402718720 3.8548994064 3.9810712337 4.0239505768 1002 1311867752.0510330200 0.1792290211 0.1375930821 0.2390826792 0.0048096057 0.4730610000 0.0798130000 0.0680990000 0.0000010000 0.3209350000 0.0017740000 138580195 0 402718720 3.8569121361 3.9816961288 4.0234298706 1003 1311867752.0828928947 0.1784319878 0.1376337988 0.2390826792 0.0048076780 0.4984420000 0.0803780000 0.0639640000 0.0330060000 0.3168690000 0.0017850000 138583923 0 402718720 3.8571517467 3.9810700417 4.0231404305 1004 1311867752.1150529385 0.1751873046 0.1376712027 0.2390826792 0.0048060075 0.4765440000 0.0937890000 0.0611310000 0.0000010000 0.3174010000 0.0017880000 138587539 0 402718720 3.8602516651 3.9807465076 4.0225729942 1005 1311867752.1509859562 0.1726803035 0.1377060376 0.2390826792 0.0048050214 0.8438950000 0.1043040000 0.0557770000 0.0328470000 0.3157880000 0.3327700000 138591323 0 402718720 3.8618423939 3.9812653065 4.0221176147 1006 1311867752.1829679012 0.1726995707 0.1377408224 0.2390826792 0.0048039717 0.4463030000 0.0816480000 0.0464440000 0.0000010000 0.3139720000 0.0017860000 138595051 0 402718720 3.8612260818 3.9809820652 4.0219449997 1007 1311867752.2150039673 0.1722062528 0.1377750483 0.2390826792 0.0048016549 0.4865430000 0.0813170000 0.0464840000 0.0328490000 0.3207690000 0.0024360000 138598723 0 402718720 3.8610270023 3.9814345837 4.0215454102 1008 1311867752.2512340546 0.1706649959 0.1378076772 0.2390826792 0.0048014056 0.5031130000 0.1018700000 0.0717430000 0.0000010000 0.3244160000 0.0024110000 138602451 0 402718720 3.8622381687 3.9823670387 4.0211458206 1009 1311867752.2833271027 0.1713237315 0.1378408943 0.2390826792 0.0047999374 0.8892760000 0.1030800000 0.1197090000 0.0328140000 0.3079350000 0.3233170000 138606123 0 402718720 3.8613803387 3.9822969437 4.0213704109 1010 1311867752.3150799274 0.1684449017 0.1378711953 0.2390826792 0.0048022778 0.4646090000 0.0813370000 0.0725550000 0.0000010000 0.3064660000 0.0018010000 138609739 0 402718720 3.8638348579 3.9813916683 4.0208082199 1011 1311867752.3509979248 0.1682324558 0.1379012262 0.2390826792 0.0048026442 0.4715040000 0.0816530000 0.0463350000 0.0327770000 0.3064850000 0.0018070000 138613523 0 402718720 3.8642082214 3.9815433025 4.0209102631 1012 1311867752.3829851151 0.1688955873 0.1379318531 0.2390826792 0.0048004348 0.4381120000 0.0814550000 0.0464670000 0.0000010000 0.3059220000 0.0018010000 138617251 0 402718720 3.8634200096 3.9807906151 4.0207910538 1013 1311867752.4160280228 0.1671104282 0.1379606572 0.2390826792 0.0047985478 0.8040980000 0.0815020000 0.0613730000 0.0327100000 0.3055910000 0.3204880000 138620923 0 402718720 3.8650317192 3.9811637402 4.0202345848 1014 1311867752.4510710239 0.1679758877 0.1379902580 0.2390826792 0.0048020896 0.4718840000 0.0812130000 0.0686340000 0.0000010000 0.3169020000 0.0024260000 138624707 0 402718720 3.8637619019 3.9814574718 4.0202102661 1015 1311867752.4829080105 0.1669265926 0.1380187667 0.2390826792 0.0048006465 0.5896640000 0.1027010000 0.1216400000 0.0404100000 0.3197760000 0.0024340000 138628379 0 402718720 3.8649606705 3.9803025723 4.0197062492 1016 1311867752.5181159973 0.1668990999 0.1380471922 0.2390826792 0.0048010400 0.4458260000 0.0893740000 0.0464520000 0.0000010000 0.3057330000 0.0018030000 138632107 0 402718720 3.8646209240 3.9800009727 4.0192832947 1017 1311867752.5511059761 0.1658304036 0.1380745110 0.2390826792 0.0048004329 0.7959230000 0.0811690000 0.0535920000 0.0327060000 0.3055670000 0.3204240000 138635779 0 402718720 3.8657820225 3.9807648659 4.0187191963 1018 1311867752.5830090046 0.1653061956 0.1381012612 0.2390826792 0.0047982960 0.4504390000 0.0950160000 0.0482930000 0.0000010000 0.3025960000 0.0019090000 138639507 0 402718720 3.8660924435 3.9809510708 4.0185222626 1019 1311867752.6167891026 0.1654899269 0.1381281392 0.2390826792 0.0047960934 0.5184140000 0.0813460000 0.0961080000 0.0326710000 0.3040020000 0.0017990000 138643179 0 402718720 3.8659441471 3.9803652763 4.0180621147 1020 1311867752.6514921188 0.1660574079 0.1381555208 0.2390826792 0.0047952350 0.4446870000 0.0813750000 0.0534650000 0.0000000000 0.3055740000 0.0018050000 138646907 0 402718720 3.8654339314 3.9809067249 4.0179924965 1021 1311867752.6830079556 0.1647109985 0.1381815301 0.2390826792 0.0047956803 0.8087170000 0.0936340000 0.0386400000 0.0327020000 0.3060720000 0.3349750000 138650579 0 402718720 3.8668277264 3.9803898335 4.0174479485 1022 1311867752.7152869701 0.1639384925 0.1382067326 0.2390826792 0.0047968676 0.5094070000 0.1026610000 0.0814250000 0.0000010000 0.3201830000 0.0024350000 138654307 0 402718720 3.8677334785 3.9797258377 4.0170774460 1023 1311867752.7510609627 0.1643512100 0.1382322893 0.2390826792 0.0047945247 0.5147180000 0.0844920000 0.0868900000 0.0326440000 0.3064300000 0.0018000000 138657979 0 402718720 3.8672270775 3.9790391922 4.0165853500 1024 1311867752.7830440998 0.1643668115 0.1382578113 0.2390826792 0.0048036209 0.4461470000 0.0810270000 0.0535560000 0.0000010000 0.3073100000 0.0017980000 138661707 0 402718720 3.8672044277 3.9801831245 4.0162210464 1025 1311867752.8162839413 0.1619902104 0.1382809649 0.2390826792 0.0048017418 0.8245570000 0.0804620000 0.0514390000 0.0327210000 0.3202760000 0.3369240000 138763683 0 402718720 3.8695597649 3.9807829857 4.0153574944 1026 1311867752.8511059284 0.1611460298 0.1383032505 0.2390826792 0.0047995705 0.4847010000 0.1021630000 0.0711670000 0.0000000000 0.3070990000 0.0018010000 138972211 0 402718720 3.8705065250 3.9808402061 4.0148153305 1027 1311867752.8833000660 0.1619149894 0.1383262415 0.2390826792 0.0047975103 0.4825630000 0.0805640000 0.0620600000 0.0326250000 0.3027940000 0.0018820000 138975939 0 402718720 3.8696463108 3.9809532166 4.0147700310 1028 1311867752.9183809757 0.1601979285 0.1383475174 0.2390826792 0.0047953522 0.5178410000 0.1063860000 0.0907320000 0.0000010000 0.3155520000 0.0024260000 138979723 0 402718720 3.8717937469 3.9814796448 4.0142903328 1029 1311867752.9511129856 0.1596499234 0.1383682195 0.2390826792 0.0047993567 0.8784200000 0.1027710000 0.0910420000 0.0408300000 0.3184590000 0.3228430000 138983339 0 402718720 3.8722369671 3.9810798168 4.0140223503 1030 1311867752.9828579426 0.1601004303 0.1383893187 0.2390826792 0.0047972088 0.4486950000 0.0814530000 0.0592040000 0.0000010000 0.3037270000 0.0017990000 138987067 0 402718720 3.8717184067 3.9808452129 4.0137419701 1031 1311867753.0168170929 0.1576709896 0.1384080206 0.2390826792 0.0047951277 0.4897670000 0.0807520000 0.0683100000 0.0326100000 0.3037770000 0.0018090000 138990739 0 402718720 3.8744013309 3.9810266495 4.0132780075 1032 1311867753.0510199070 0.1593015939 0.1384282663 0.2390826792 0.0047930070 0.4412480000 0.0804350000 0.0532210000 0.0000010000 0.3032130000 0.0017910000 138994467 0 402718720 3.8727066517 3.9804646969 4.0130443573 1033 1311867753.0829060078 0.1595171839 0.1384486816 0.2390826792 0.0047915938 0.8072090000 0.0907510000 0.0609090000 0.0324920000 0.3030780000 0.3174630000 138998083 0 402718720 3.8722488880 3.9805397987 4.0124530792 1034 1311867753.1184310913 0.1582076997 0.1384677909 0.2390826792 0.0047894057 0.4784170000 0.0806390000 0.0907420000 0.0000010000 0.3027100000 0.0017950000 139001923 0 402718720 3.8735334873 3.9818973541 4.0119986534 1035 1311867753.1510760784 0.1571087688 0.1384858015 0.2390826792 0.0047872885 0.5082620000 0.0805420000 0.0889680000 0.0325290000 0.3018880000 0.0017990000 139005539 0 402718720 3.8746073246 3.9806468487 4.0118060112 1036 1311867753.1830070019 0.1574477106 0.1385041045 0.2390826792 0.0047852857 0.4566170000 0.1043470000 0.0482490000 0.0000010000 0.2994490000 0.0018910000 139009155 0 402718720 3.8738563061 3.9796829224 4.0114507675 1037 1311867753.2186999321 0.1560849100 0.1385210580 0.2390826792 0.0047854340 0.8109330000 0.0802730000 0.0769040000 0.0322180000 0.3025930000 0.3164480000 139012995 0 402718720 3.8751370907 3.9818224907 4.0113096237 1038 1311867753.2520470619 0.1556291282 0.1385375397 0.2390826792 0.0047831865 0.4536430000 0.1016250000 0.0464210000 0.0000000000 0.3012490000 0.0017830000 139016611 0 402718720 3.8754012585 3.9819653034 4.0111865997 1039 1311867753.2829909325 0.1542209387 0.1385526345 0.2390826792 0.0047816150 0.4787450000 0.0803860000 0.0638220000 0.0323740000 0.2976060000 0.0018980000 139020283 0 402718720 3.8762426376 3.9816842079 4.0108046532 1040 1311867753.3196740150 0.1499364525 0.1385635804 0.2390826792 0.0047837404 0.4607250000 0.0789990000 0.0786970000 0.0000000000 0.2987000000 0.0018010000 139024123 0 402718720 3.8798828125 3.9828734398 4.0100483894 1041 1311867753.3509368896 0.1486591697 0.1385732784 0.2390826792 0.0047817141 0.8163190000 0.0806040000 0.0904960000 0.0322680000 0.2985500000 0.3118840000 139027683 0 402718720 3.8809354305 3.9833412170 4.0099182129 1042 1311867753.3829340935 0.1500704139 0.1385843121 0.2390826792 0.0047811883 0.4482240000 0.0922320000 0.0534290000 0.0000010000 0.2982180000 0.0017810000 139031411 0 402718720 3.8791427612 3.9813728333 4.0101842880 1043 1311867753.4182109833 0.1513358504 0.1385965380 0.2390826792 0.0047795084 0.5178230000 0.0916850000 0.0904830000 0.0322730000 0.2990470000 0.0017890000 139035195 0 402718720 3.8773131371 3.9822478294 4.0097975731 1044 1311867753.4511721134 0.1500230730 0.1386074829 0.2390826792 0.0047774718 0.4445830000 0.0803460000 0.0606490000 0.0000010000 0.2992420000 0.0017760000 139038811 0 402718720 3.8780775070 3.9828367233 4.0092802048 1045 1311867753.4831509590 0.1484385133 0.1386168906 0.2390826792 0.0047759654 0.8205600000 0.0807170000 0.0906630000 0.0322070000 0.2994290000 0.3147740000 139042539 0 402718720 3.8789618015 3.9822032452 4.0085301399 1046 1311867753.5199849606 0.1475855261 0.1386254648 0.2390826792 0.0047737570 0.4920940000 0.1018830000 0.0710690000 0.0000000000 0.3139110000 0.0024150000 139046379 0 402718720 3.8789618015 3.9829683304 4.0077419281 1047 1311867753.5532789230 0.1463434398 0.1386328363 0.2390826792 0.0047716422 0.5654020000 0.1013550000 0.1198480000 0.0400110000 0.2998480000 0.0017940000 139050051 0 402718720 3.8795135021 3.9825510979 4.0074639320 1048 1311867753.5832290649 0.1449133158 0.1386388292 0.2390826792 0.0047696567 0.4418960000 0.0934590000 0.0480920000 0.0000010000 0.2957620000 0.0018860000 139053667 0 402718720 3.8802549839 3.9825129509 4.0068898201 1049 1311867753.6183180809 0.1435837746 0.1386435431 0.2390826792 0.0047677003 0.8034030000 0.0805270000 0.0605900000 0.0320390000 0.3038120000 0.3236480000 139057451 0 402718720 3.8806462288 3.9833648205 4.0063767433 1050 1311867753.6509299278 0.1438394785 0.1386484916 0.2390826792 0.0047657772 0.4664310000 0.1004470000 0.0660130000 0.0000000000 0.2956050000 0.0017920000 139061123 0 402718720 3.8797669411 3.9825770855 4.0062565804 1051 1311867753.6830120087 0.1418885142 0.1386515744 0.2390826792 0.0047653042 0.4719250000 0.0801830000 0.0604340000 0.0319590000 0.2950070000 0.0017850000 139064739 0 402718720 3.8811836243 3.9824213982 4.0056357384 1052 1311867753.7204821110 0.1403234601 0.1386531637 0.2390826792 0.0047632397 0.4472010000 0.0802200000 0.0676860000 0.0000010000 0.2949400000 0.0017790000 139068635 0 402718720 3.8822309971 3.9833657742 4.0054063797 1053 1311867753.7510209084 0.1401800215 0.1386546137 0.2390826792 0.0047616960 0.8465050000 0.0906860000 0.0897290000 0.0343790000 0.3081250000 0.3207720000 139072195 0 402718720 3.8815529346 3.9830439091 4.0053768158 1054 1311867753.7865459919 0.1383434683 0.1386543185 0.2390826792 0.0047612074 0.5185620000 0.1022690000 0.1174900000 0.0000000000 0.2944590000 0.0017900000 139075979 0 402718720 3.8824224472 3.9822607040 4.0049862862 1055 1311867753.8151860237 0.1356655806 0.1386514855 0.2390826792 0.0047598101 0.5035070000 0.0803990000 0.0942270000 0.0318760000 0.2926500000 0.0017830000 139079539 0 402718720 3.8850262165 3.9839661121 4.0048327446 1056 1311867753.8510670662 0.1353918761 0.1386483988 0.2390826792 0.0047589298 0.4591590000 0.1010490000 0.0477790000 0.0000010000 0.3050950000 0.0023980000 139083323 0 402718720 3.8843181133 3.9839203358 4.0047888756 1057 1311867753.8831698895 0.1341570169 0.1386441496 0.2390826792 0.0047675591 0.8811810000 0.1019900000 0.1201250000 0.0389070000 0.3080350000 0.3095620000 139087051 0 402718720 3.8849186897 3.9819710255 4.0045561790 1058 1311867753.9155960083 0.1325694025 0.1386384079 0.2390826792 0.0047660188 0.4420800000 0.0802960000 0.0631530000 0.0000010000 0.2940000000 0.0018830000 139090667 0 402718720 3.8858077526 3.9826934338 4.0042967796 1059 1311867753.9511620998 0.1313798726 0.1386315537 0.2390826792 0.0047669140 0.4595900000 0.0800870000 0.0476190000 0.0318080000 0.2956940000 0.0017810000 139094451 0 402718720 3.8863401413 3.9842705727 4.0045175552 1060 1311867753.9859020710 0.1312775165 0.1386246160 0.2390826792 0.0047667539 0.5102870000 0.0953660000 0.0999510000 0.0000000000 0.3097480000 0.0023850000 139098235 0 402718720 3.8856844902 3.9829216003 4.0045781136 1061 1311867754.0151760578 0.1309370399 0.1386173704 0.2390826792 0.0047652131 0.8421810000 0.1020450000 0.0902410000 0.0387780000 0.3005650000 0.3079560000 139101795 0 402718720 3.8848047256 3.9816510677 4.0047545433 1062 1311867754.0510439873 0.1271816641 0.1386066023 0.2390826792 0.0047716040 0.4728690000 0.0800930000 0.0892670000 0.0000010000 0.2982580000 0.0023960000 139105635 0 402718720 3.8878929615 3.9833571911 4.0047659874 1063 1311867754.0839149952 0.1252123266 0.1385940018 0.2390826792 0.0047702265 0.4740580000 0.0884930000 0.0525690000 0.0316330000 0.2970000000 0.0017840000 139109307 0 402718720 3.8891847134 3.9831559658 4.0045647621 1064 1311867754.1166028976 0.1235556677 0.1385798681 0.2390826792 0.0047688459 0.4735980000 0.0799810000 0.0936090000 0.0000010000 0.2953720000 0.0018700000 139112979 0 402718720 3.8899898529 3.9824056625 4.0048503876 1065 1311867754.1511039734 0.1214466617 0.1385637806 0.2390826792 0.0047694063 0.8069040000 0.0789890000 0.0887570000 0.0310460000 0.2973670000 0.3081450000 139116651 0 402718720 3.8912975788 3.9829416275 4.0045928955 1066 1311867754.1832261086 0.1204432324 0.1385467819 0.2390826792 0.0047674593 0.4651870000 0.0972240000 0.0665260000 0.0000010000 0.2970600000 0.0017600000 139120379 0 402718720 3.8916063309 3.9839015007 4.0051574707 1067 1311867754.2166349888 0.1193489283 0.1385287896 0.2390826792 0.0047671705 0.5114930000 0.0912330000 0.0886320000 0.0315360000 0.2957070000 0.0017710000 139124051 0 402718720 3.8912832737 3.9830656052 4.0048718452 1068 1311867754.2522869110 0.1183238104 0.1385098710 0.2390826792 0.0047713099 0.4925670000 0.1002860000 0.0930240000 0.0000000000 0.2948770000 0.0017730000 139127835 0 402718720 3.8911399841 3.9825446606 4.0050368309 1069 1311867754.2873370647 0.1142273247 0.1384871558 0.2390826792 0.0047766291 0.7840760000 0.0768950000 0.0727310000 0.0311780000 0.2953710000 0.3052970000 139131619 0 402718720 3.8940026760 3.9833154678 4.0048537254 1070 1311867754.3188319206 0.1165989637 0.1384666996 0.2390826792 0.0047747169 0.4367990000 0.0789620000 0.0589990000 0.0000010000 0.2944570000 0.0017740000 139135291 0 402718720 3.8904573917 3.9826290607 4.0054092407 1071 1311867754.3511719704 0.1157771647 0.1384455142 0.2390826792 0.0047766150 0.4703400000 0.0794620000 0.0622610000 0.0313940000 0.2926020000 0.0018730000 139138963 0 402718720 3.8903369904 3.9826216698 4.0055427551 1072 1311867754.3868899345 0.1137085631 0.1384224387 0.2390826792 0.0047776972 0.4492230000 0.0783320000 0.0725640000 0.0000010000 0.2939700000 0.0017070000 139142691 0 402718720 3.8912427425 3.9832508564 4.0051760674 1073 1311867754.4159760475 0.1133800745 0.1383991001 0.2390826792 0.0047755973 0.7939450000 0.0784560000 0.0874450000 0.0312940000 0.2921260000 0.3020350000 139146363 0 402718720 3.8910317421 3.9831402302 4.0051512718 1074 1311867754.4545960426 0.1106053069 0.1383732213 0.2390826792 0.0047891369 0.4450350000 0.0901570000 0.0588920000 0.0000000000 0.2913710000 0.0017560000 139150147 0 402718720 3.8927719593 3.9821362495 4.0054898262 1075 1311867754.4863700867 0.1089621335 0.1383458621 0.2390826792 0.0047962608 0.4710740000 0.0785270000 0.0659670000 0.0312600000 0.2909470000 0.0017680000 139153819 0 402718720 3.8939409256 3.9823279381 4.0055670738 1076 1311867754.5164580345 0.1082171127 0.1383178614 0.2390826792 0.0047946488 0.4329480000 0.0789140000 0.0588430000 0.0000000000 0.2907970000 0.0017650000 139157435 0 402718720 3.8941915035 3.9829359055 4.0057950020 1077 1311867754.5513699055 0.1074327901 0.1382891845 0.2390826792 0.0047941253 0.8114590000 0.0916370000 0.0915690000 0.0312880000 0.2902640000 0.3040770000 139161107 0 402718720 3.8944966793 3.9832577705 4.0060677528 1078 1311867754.5835940838 0.1047210470 0.1382580452 0.2390826792 0.0047954647 0.4808420000 0.0962920000 0.0923660000 0.0000000000 0.2875510000 0.0018580000 139164835 0 402718720 3.8967115879 3.9818649292 4.0057311058 1079 1311867754.6154909134 0.1051587760 0.1382273693 0.2390826792 0.0047948353 0.4917980000 0.0788910000 0.0885160000 0.0306890000 0.2893080000 0.0017670000 139168451 0 402718720 3.8957800865 3.9821267128 4.0061435699 1080 1311867754.6510920525 0.1044539586 0.1381960977 0.2390826792 0.0047929304 0.4588630000 0.0782060000 0.0870070000 0.0000010000 0.2892050000 0.0017530000 139172179 0 402718720 3.8960235119 3.9826450348 4.0062766075 1081 1311867754.6872758865 0.1026939750 0.1381632557 0.2390826792 0.0047937073 0.8119470000 0.0782440000 0.0873750000 0.0311020000 0.3006750000 0.3116460000 139175963 0 402718720 3.8971824646 3.9815258980 4.0062041283 1082 1311867754.7162959576 0.1027360484 0.1381305134 0.2390826792 0.0047915631 0.4580340000 0.1003780000 0.0596230000 0.0000010000 0.2936180000 0.0017640000 139179523 0 402718720 3.8966701031 3.9821250439 4.0064654350 1083 1311867754.7516000271 0.1016654596 0.1380968430 0.2390826792 0.0047908490 0.4952850000 0.0878830000 0.0847680000 0.0312060000 0.2867800000 0.0018630000 139183307 0 402718720 3.8972394466 3.9836997986 4.0067524910 1084 1311867754.7865269184 0.1003722623 0.1380620417 0.2390826792 0.0047909566 0.4368850000 0.0762940000 0.0683320000 0.0000010000 0.2870040000 0.0023710000 139187035 0 402718720 3.8979995251 3.9832649231 4.0067720413 1085 1311867754.8154470921 0.1010935009 0.1380279693 0.2390826792 0.0047900363 0.8644020000 0.1001490000 0.1175720000 0.0377370000 0.2986840000 0.3073680000 139190595 0 402718720 3.8967683315 3.9812545776 4.0069785118 1086 1311867754.8510210514 0.1004643813 0.1379933804 0.2390826792 0.0048038132 0.4647390000 0.0877930000 0.0879860000 0.0000010000 0.2845350000 0.0017670000 139194379 0 402718720 3.8965806961 3.9820361137 4.0073995590 1087 1311867754.8877389431 0.0976672471 0.1379562818 0.2390826792 0.0048035535 0.4708470000 0.0993220000 0.0546700000 0.0310190000 0.2814210000 0.0017760000 139198219 0 402718720 3.8985698223 3.9817943573 4.0070385933 1088 1311867754.9201259613 0.0957567170 0.1379174955 0.2390826792 0.0048022879 0.4873320000 0.0951980000 0.0919970000 0.0000010000 0.2947020000 0.0025240000 139201891 0 402718720 3.8997259140 3.9802865982 4.0069322586 1089 1311867754.9510319233 0.0951026082 0.1378781797 0.2390826792 0.0048015438 0.8141980000 0.1015480000 0.0895800000 0.0383360000 0.2934610000 0.2886220000 139205507 0 402718720 3.8995618820 3.9805235863 4.0068435669 1090 1311867754.9837870598 0.0938371941 0.1378377751 0.2390826792 0.0048006889 0.4145500000 0.0796010000 0.0524180000 0.0000000000 0.2780830000 0.0017870000 139209235 0 402718720 3.8996355534 3.9816718102 4.0074415207 1091 1311867755.0183880329 0.0928824246 0.1377965695 0.2390826792 0.0048024416 0.4498710000 0.0794670000 0.0595940000 0.0309980000 0.2753800000 0.0017770000 139212963 0 402718720 3.9000494480 3.9797759056 4.0077018738 1092 1311867755.0540831089 0.0936181620 0.1377561131 0.2390826792 0.0048031843 0.4506040000 0.0792440000 0.0932820000 0.0000010000 0.2733910000 0.0018650000 139216747 0 402718720 3.8988783360 3.9788446426 4.0083403587 1093 1311867755.0850980282 0.0940118209 0.1377160908 0.2390826792 0.0048032168 0.7621200000 0.0803720000 0.0934880000 0.0309600000 0.2735460000 0.2810770000 139220419 0 402718720 3.8980543613 3.9791829586 4.0088481903 1094 1311867755.1156959534 0.0939706266 0.1376761041 0.2390826792 0.0048050791 0.4431750000 0.0906400000 0.0743680000 0.0000010000 0.2737190000 0.0017680000 139223979 0 402718720 3.8975620270 3.9789640903 4.0090570450 1095 1311867755.1556220055 0.0930046663 0.1376353083 0.2390826792 0.0048033311 0.4813450000 0.0796680000 0.0819790000 0.0309160000 0.2834420000 0.0023910000 139227875 0 402718720 3.8979053497 3.9787278175 4.0092511177 1096 1311867755.1847031116 0.0937743708 0.1375952892 0.2390826792 0.0048017698 0.4588800000 0.0916330000 0.0890270000 0.0000010000 0.2737350000 0.0017460000 139231547 0 402718720 3.8966660500 3.9775362015 4.0095343590 1097 1311867755.2151238918 0.0919732451 0.1375537012 0.2390826792 0.0047996511 0.7327200000 0.0788050000 0.0668910000 0.0309040000 0.2733970000 0.2799830000 139235107 0 402718720 3.8979060650 3.9793198109 4.0094947815 1098 1311867755.2512340546 0.0921489596 0.1375123490 0.2390826792 0.0047987549 0.4375900000 0.0980160000 0.0627340000 0.0000010000 0.2723640000 0.0017790000 139238891 0 402718720 3.8972384930 3.9777295589 4.0098595619 1099 1311867755.2832889557 0.0917250142 0.1374706862 0.2390826792 0.0047989502 0.4787040000 0.0802250000 0.0893890000 0.0309650000 0.2736760000 0.0017980000 139242563 0 402718720 3.8971226215 3.9769654274 4.0094952583 1100 1311867755.3192110062 0.0905610099 0.1374280411 0.2390826792 0.0047973482 0.4201150000 0.0792020000 0.0624990000 0.0000010000 0.2737150000 0.0018620000 139246347 0 402718720 3.8978796005 3.9783992767 4.0091738701 1101 1311867755.3553090096 0.0915423036 0.1373863646 0.2390826792 0.0047951874 0.7564870000 0.0792400000 0.0884780000 0.0305050000 0.2745370000 0.2810590000 139250187 0 402718720 3.8965861797 3.9765467644 4.0090980530 1102 1311867755.3900220394 0.0930046290 0.1373460908 0.2390826792 0.0047933125 0.4165770000 0.0772170000 0.0588240000 0.0000010000 0.2760650000 0.0017740000 139253859 0 402718720 3.8947072029 3.9745590687 4.0088210106 1103 1311867755.4156589508 0.0924471244 0.1373053846 0.2390826792 0.0047940192 0.5255730000 0.1019830000 0.0879930000 0.0381380000 0.2921510000 0.0023800000 139257419 0 402718720 3.8947107792 3.9771091938 4.0085139275 1104 1311867755.4549160004 0.0921506882 0.1372644836 0.2390826792 0.0047926128 0.4793030000 0.0993650000 0.0881370000 0.0000010000 0.2873280000 0.0017650000 139261259 0 402718720 3.8943560123 3.9781868458 4.0086941719 1105 1311867755.4860870838 0.0922499448 0.1372237465 0.2390826792 0.0047915383 0.7642970000 0.0786610000 0.0881050000 0.0309320000 0.2786440000 0.2852640000 139264875 0 402718720 3.8939146996 3.9754118919 4.0085659027 1106 1311867755.5161950588 0.0942693800 0.1371849089 0.2390826792 0.0047936690 0.4523100000 0.0791290000 0.0883990000 0.0000010000 0.2802970000 0.0017710000 139268435 0 402718720 3.8916301727 3.9767804146 4.0090980530 1107 1311867755.5550999641 0.0926109254 0.1371446433 0.2390826792 0.0047915585 0.4665840000 0.0781690000 0.0731580000 0.0304530000 0.2803210000 0.0017710000 139272331 0 402718720 3.8929171562 3.9780206680 4.0089898109 1108 1311867755.5854589939 0.0933812186 0.1371051457 0.2390826792 0.0047894615 0.4309060000 0.0775660000 0.0689680000 0.0000010000 0.2799200000 0.0017630000 139276003 0 402718720 3.8919301033 3.9779324532 4.0088953972 1109 1311867755.6171119213 0.0922692865 0.1370647166 0.2390826792 0.0047877430 0.7510200000 0.1055220000 0.0467290000 0.0304700000 0.2791420000 0.2864580000 139279619 0 402718720 3.8928048611 3.9782571793 4.0087318420 1110 1311867755.6542940140 0.0918499455 0.1370239825 0.2390826792 0.0047856643 0.4840110000 0.0782090000 0.1065500000 0.0000000000 0.2938750000 0.0023800000 139283459 0 402718720 3.8931155205 3.9783368111 4.0087628365 1111 1311867755.6831719875 0.0934125930 0.1369847284 0.2390826792 0.0047841288 0.5500330000 0.0991930000 0.1168990000 0.0374730000 0.2919850000 0.0017730000 139287019 0 402718720 3.8914077282 3.9766831398 4.0086107254 1112 1311867755.7182741165 0.0924048871 0.1369446386 0.2390826792 0.0047823050 0.4222490000 0.0776580000 0.0585940000 0.0000010000 0.2815260000 0.0017670000 139290803 0 402718720 3.8919665813 3.9764142036 4.0079913139 1113 1311867755.7511448860 0.0931560323 0.1369052957 0.2390826792 0.0047819213 0.7964650000 0.0995360000 0.0920160000 0.0309610000 0.2820520000 0.2891980000 139294475 0 402718720 3.8908245564 3.9770090580 4.0077161789 1114 1311867755.7863750458 0.0941778049 0.1368669407 0.2390826792 0.0047800524 0.4490590000 0.0777880000 0.0840890000 0.0000010000 0.2826890000 0.0017720000 139298203 0 402718720 3.8895885944 3.9773991108 4.0077781677 1115 1311867755.8156878948 0.0905900896 0.1368254368 0.2390826792 0.0047823115 0.4855110000 0.0783410000 0.0875760000 0.0309210000 0.2841700000 0.0017780000 139301875 0 402718720 3.8929817677 3.9760670662 4.0066609383 1116 1311867755.8554079533 0.0893364996 0.1367828840 0.2390826792 0.0047816200 0.4570810000 0.0770910000 0.0913160000 0.0000010000 0.2839430000 0.0018640000 139305659 0 402718720 3.8938984871 3.9784913063 4.0067100525 1117 1311867755.8848359585 0.0903215781 0.1367412893 0.2390826792 0.0047796217 0.7762040000 0.0757720000 0.0735590000 0.0308950000 0.2881250000 0.3048640000 139309331 0 402718720 3.8926284313 3.9784319401 4.0069327354 1118 1311867755.9156229496 0.0892139897 0.1366987783 0.2390826792 0.0047812100 0.4992150000 0.0985220000 0.0974430000 0.0000010000 0.2979020000 0.0023650000 139313003 0 402718720 3.8935551643 3.9759426117 4.0064625740 1119 1311867755.9550359249 0.0886873230 0.1366558726 0.2390826792 0.0047813960 0.4869630000 0.0799200000 0.0869630000 0.0308690000 0.2847380000 0.0017590000 139316787 0 402718720 3.8936538696 3.9780571461 4.0066289902 1120 1311867755.9855198860 0.0896025747 0.1366138607 0.2390826792 0.0047797789 0.4457580000 0.0930900000 0.0615240000 0.0000010000 0.2858070000 0.0023650000 139320403 0 402718720 3.8926565647 3.9780178070 4.0069022179 1121 1311867756.0173881054 0.0896681026 0.1365719822 0.2390826792 0.0047780623 0.7822270000 0.0887690000 0.0874250000 0.0303750000 0.2833410000 0.2895960000 139324019 0 402718720 3.8924579620 3.9770622253 4.0068445206 1122 1311867756.0554430485 0.0869785398 0.1365277813 0.2390826792 0.0047765092 0.4531690000 0.0776730000 0.0872540000 0.0000000000 0.2837350000 0.0017620000 139327803 0 402718720 3.8949086666 3.9788126945 4.0066728592 1123 1311867756.0835959911 0.0880979523 0.1364846559 0.2390826792 0.0047750722 0.4823740000 0.0887270000 0.0773600000 0.0309340000 0.2806150000 0.0018780000 139331419 0 402718720 3.8937265873 3.9781968594 4.0068168640 1124 1311867756.1196908951 0.0905127749 0.1364437557 0.2390826792 0.0047754837 0.4532820000 0.0757510000 0.0883710000 0.0000000000 0.2837730000 0.0023730000 139335203 0 402718720 3.8915791512 3.9753317833 4.0070257187 1125 1311867756.1519339085 0.0880087763 0.1364007023 0.2390826792 0.0047743267 0.8079910000 0.0989650000 0.0689750000 0.0374430000 0.2964990000 0.3031340000 139338707 0 402718720 3.8938345909 3.9772410393 4.0065922737 1126 1311867756.1836869717 0.0896852612 0.1363592144 0.2390826792 0.0047746483 0.4630510000 0.0880640000 0.0881530000 0.0000010000 0.2823390000 0.0017600000 139342267 0 402718720 3.8921639919 3.9781146049 4.0072426796 1127 1311867756.2230648994 0.0903188512 0.1363183622 0.2390826792 0.0047791129 0.4798050000 0.0761290000 0.0867390000 0.0307090000 0.2817240000 0.0017680000 139345939 0 402718720 3.8918156624 3.9757492542 4.0072393417 1128 1311867756.2552509308 0.0895566791 0.1362769069 0.2390826792 0.0047796544 0.4277440000 0.0893920000 0.0516040000 0.0000000000 0.2822360000 0.0017690000 139349611 0 402718720 3.8925476074 3.9760870934 4.0072774887 1129 1311867756.2851591110 0.0895871744 0.1362355519 0.2390826792 0.0047782690 0.7333550000 0.0778600000 0.0544710000 0.0308450000 0.2802290000 0.2872010000 139353283 0 402718720 3.8925933838 3.9778015614 4.0075163841 1130 1311867756.3200058937 0.0905972421 0.1361951640 0.2390826792 0.0047763823 0.4245500000 0.0784820000 0.0620530000 0.0000010000 0.2792410000 0.0018650000 139357011 0 402718720 3.8917906284 3.9765264988 4.0076947212 1131 1311867756.3546419144 0.0891294628 0.1361535498 0.2390826792 0.0047753474 0.4840980000 0.0783220000 0.0902460000 0.0309040000 0.2801110000 0.0017750000 139360795 0 402718720 3.8933701515 3.9762446880 4.0073747635 1132 1311867756.3843090534 0.0900960565 0.1361128630 0.2390826792 0.0047749849 0.4224000000 0.0779160000 0.0588600000 0.0000010000 0.2810920000 0.0017700000 139364355 0 402718720 3.8923358917 3.9773371220 4.0077972412 1133 1311867756.4231688976 0.0896859095 0.1360718859 0.2390826792 0.0047733879 0.7570880000 0.0916380000 0.0678120000 0.0308840000 0.2784170000 0.2855850000 139368139 0 402718720 3.8929347992 3.9772398472 4.0079026222 1134 1311867756.4510979652 0.0909687206 0.1360321124 0.2390826792 0.0047717861 0.4385330000 0.0782880000 0.0772890000 0.0000010000 0.2781860000 0.0018770000 139371643 0 402718720 3.8918128014 3.9753277302 4.0080361366 1135 1311867756.4865350723 0.0902517140 0.1359917773 0.2390826792 0.0047761237 0.4812050000 0.0782510000 0.0881330000 0.0306950000 0.2796050000 0.0017720000 139375483 0 402718720 3.8925220966 3.9768159389 4.0084128380 1136 1311867756.5264549255 0.0898035169 0.1359511186 0.2390826792 0.0047745135 0.4503200000 0.0791520000 0.0887390000 0.0000010000 0.2778760000 0.0017690000 139379323 0 402718720 3.8931946754 3.9762527943 4.0084161758 1137 1311867756.5525779724 0.0904663578 0.1359111144 0.2390826792 0.0047729935 0.7620690000 0.0789290000 0.0888610000 0.0309860000 0.2772140000 0.2833130000 139382883 0 402718720 3.8927114010 3.9756431580 4.0086913109 1138 1311867756.5897810459 0.0892217606 0.1358700869 0.2390826792 0.0047713515 0.4255440000 0.0904630000 0.0552440000 0.0000010000 0.2752960000 0.0017760000 139386723 0 402718720 3.8940033913 3.9762966633 4.0085692406 1139 1311867756.6202929020 0.0913969725 0.1358310411 0.2390826792 0.0047701233 0.4604130000 0.0790010000 0.0596860000 0.0308800000 0.2854060000 0.0023930000 139390283 0 402718720 3.8921506405 3.9744412899 4.0091500282 1140 1311867756.6518390179 0.0915890336 0.1357922323 0.2390826792 0.0047680817 0.4543360000 0.1002280000 0.0601040000 0.0000010000 0.2885620000 0.0024060000 139393955 0 402718720 3.8920788765 3.9737396240 4.0094995499 1141 1311867756.6839349270 0.0900963917 0.1357521834 0.2390826792 0.0047672479 0.8133170000 0.1002730000 0.1184610000 0.0369130000 0.2744820000 0.2804250000 139397571 0 402718720 3.8932936192 3.9746649265 4.0093584061 1142 1311867756.7217059135 0.0903855935 0.1357124578 0.2390826792 0.0047677494 0.4513090000 0.0793800000 0.0940600000 0.0000010000 0.2733240000 0.0017810000 139401355 0 402718720 3.8930213451 3.9739699364 4.0097098351 1143 1311867756.7516939640 0.0907096416 0.1356730853 0.2390826792 0.0047659787 0.4898570000 0.0940100000 0.0875400000 0.0308690000 0.2728870000 0.0017900000 139404971 0 402718720 3.8926324844 3.9735193253 4.0098276138 1144 1311867756.7872660160 0.0914519727 0.1356344305 0.2390826792 0.0047642110 0.4438690000 0.0777800000 0.0883310000 0.0000000000 0.2732150000 0.0017400000 139408755 0 402718720 3.8919053078 3.9736287594 4.0100684166 1145 1311867756.8227219582 0.0902604014 0.1355948025 0.2390826792 0.0047622810 0.7295200000 0.0927200000 0.0528440000 0.0308910000 0.2721090000 0.2781810000 139412539 0 402718720 3.8930327892 3.9735047817 4.0101542473 1146 1311867756.8542120457 0.0908362865 0.1355557462 0.2390826792 0.0047686679 0.4010020000 0.0793110000 0.0434260000 0.0000000000 0.2727800000 0.0024050000 139416155 0 402718720 3.8924942017 3.9724419117 4.0103816986 1147 1311867756.8841960430 0.0922330618 0.1355179758 0.2390826792 0.0047802798 0.4996870000 0.1007380000 0.0703970000 0.0374530000 0.2856270000 0.0024100000 139419827 0 402718720 3.8909120560 3.9732160568 4.0110259056 1148 1311867756.9223539829 0.0915506408 0.1354796767 0.2390826792 0.0047791836 0.5004320000 0.1005800000 0.1190750000 0.0000010000 0.2762210000 0.0017750000 139423611 0 402718720 3.8914151192 3.9726827145 4.0110368729 1149 1311867756.9552440643 0.0902262554 0.1354402916 0.2390826792 0.0047787609 0.7149340000 0.0800010000 0.0530640000 0.0308760000 0.2710970000 0.2771060000 139427339 0 402718720 3.8927209377 3.9713878632 4.0105404854 1150 1311867756.9841780663 0.0908598751 0.1354015261 0.2390826792 0.0047782724 0.3989310000 0.0775540000 0.0449360000 0.0000000000 0.2719300000 0.0017310000 139430899 0 402718720 3.8918807507 3.9726879597 4.0109381676 1151 1311867757.0282740593 0.0897651389 0.1353618767 0.2390826792 0.0047821409 0.4715380000 0.0782120000 0.0873670000 0.0306620000 0.2707640000 0.0017540000 139434907 0 402718720 3.8928098679 3.9711706638 4.0108461380 1152 1311867757.0552940369 0.0893518552 0.1353219375 0.2390826792 0.0047805567 0.4768000000 0.1066550000 0.0948510000 0.0000010000 0.2707150000 0.0017880000 139438467 0 402718720 3.8933534622 3.9699671268 4.0105695724 1153 1311867757.0858569145 0.0885422900 0.1352813654 0.2390826792 0.0047800223 0.7347650000 0.0917210000 0.0602690000 0.0308720000 0.2716060000 0.2775070000 139442083 0 402718720 3.8938562870 3.9723808765 4.0107164383 1154 1311867757.1283040047 0.0881982744 0.1352405655 0.2390826792 0.0047906407 0.4838440000 0.0793960000 0.1138270000 0.0000000000 0.2851120000 0.0024200000 139445979 0 402718720 3.8946418762 3.9688279629 4.0106039047 1155 1311867757.1522068977 0.0864141658 0.1351982915 0.2390826792 0.0047899529 0.5394790000 0.1012150000 0.1098450000 0.0374430000 0.2863970000 0.0017980000 139449371 0 402718720 3.8964126110 3.9682662487 4.0097651482 1156 1311867757.1851921082 0.0904339403 0.1351595680 0.2390826792 0.0047934272 0.4490650000 0.0787190000 0.0892170000 0.0000010000 0.2765230000 0.0017670000 139453099 0 402718720 3.8923201561 3.9702770710 4.0106410980 1157 1311867757.2192370892 0.0890972465 0.1351197562 0.2390826792 0.0047924170 0.7307170000 0.0770650000 0.0589140000 0.0307230000 0.2777050000 0.2834860000 139456883 0 402718720 3.8940346241 3.9687128067 4.0099129677 1158 1311867757.2523930073 0.0879167095 0.1350789936 0.2390826792 0.0048126965 0.4341220000 0.0877740000 0.0625790000 0.0000010000 0.2789570000 0.0018740000 139460555 0 402718720 3.8954155445 3.9682579041 4.0090999603 1159 1311867757.2835690975 0.0882212073 0.1350385641 0.2390826792 0.0048161887 0.4859450000 0.0778530000 0.0903610000 0.0304180000 0.2827150000 0.0017780000 139464171 0 402718720 3.8949515820 3.9705750942 4.0088996887 1160 1311867757.3233768940 0.0906462818 0.1350002949 0.2390826792 0.0048258563 0.4243410000 0.0772240000 0.0584330000 0.0000010000 0.2841070000 0.0017670000 139468067 0 402718720 3.8932449818 3.9701256752 4.0089664459 1161 1311867757.3555359840 0.0898621306 0.1349614162 0.2390826792 0.0048241749 0.7605550000 0.0780780000 0.0585430000 0.0309210000 0.2857350000 0.3042310000 139471795 0 402718720 3.8940122128 3.9702603817 4.0086965561 1162 1311867757.3833439350 0.0896189809 0.1349223952 0.2390826792 0.0048239041 0.4513260000 0.0973670000 0.0584520000 0.0000010000 0.2909350000 0.0017610000 139475299 0 402718720 3.8943080902 3.9714791775 4.0090317726 1163 1311867757.4264349937 0.0898868218 0.1348836716 0.2390826792 0.0048241411 0.4719250000 0.0915040000 0.0581190000 0.0308990000 0.2868430000 0.0017700000 139479195 0 402718720 3.8942866325 3.9706470966 4.0089354515 1164 1311867757.4546940327 0.0896612555 0.1348448207 0.2390826792 0.0048227324 0.4588800000 0.0766040000 0.0908780000 0.0000000000 0.2867980000 0.0017600000 139482755 0 402718720 3.8945200443 3.9706904888 4.0088038445 1165 1311867757.4884710312 0.0897889659 0.1348061461 0.2390826792 0.0048207737 0.7467420000 0.0768920000 0.0536030000 0.0304910000 0.2876730000 0.2952950000 139486539 0 402718720 3.8945386410 3.9713613987 4.0090417862 1166 1311867757.5210690498 0.0895118564 0.1347673003 0.2390826792 0.0048231485 0.4568630000 0.0771420000 0.0864550000 0.0000000000 0.2886830000 0.0017480000 139490043 0 402718720 3.8950352669 3.9693667889 4.0089263916 1167 1311867757.5554831028 0.0893658474 0.1347283958 0.2390826792 0.0048215150 0.4877400000 0.0897080000 0.0719980000 0.0308690000 0.2902860000 0.0017510000 139493827 0 402718720 3.8951566219 3.9692869186 4.0088195801 1168 1311867757.5887749195 0.0897204876 0.1346898617 0.2390826792 0.0048206825 0.4390230000 0.0908490000 0.0531490000 0.0000010000 0.2904580000 0.0017460000 139497555 0 402718720 3.8948230743 3.9705567360 4.0091180801 1169 1311867757.6231749058 0.0909441113 0.1346524402 0.2390826792 0.0048205911 0.7729410000 0.0760860000 0.0714660000 0.0308990000 0.2924030000 0.2992370000 139501283 0 402718720 3.8934686184 3.9692249298 4.0092363358 1170 1311867757.6566219330 0.0906013995 0.1346147897 0.2390826792 0.0048187274 0.4588780000 0.0756190000 0.0850790000 0.0000010000 0.2936080000 0.0017370000 139504955 0 402718720 3.8938443661 3.9701271057 4.0094146729 1171 1311867757.6914329529 0.0914010331 0.1345778864 0.2390826792 0.0048171069 0.4488050000 0.0761890000 0.0433630000 0.0309350000 0.2937390000 0.0017540000 139508683 0 402718720 3.8929977417 3.9709625244 4.0098357201 1172 1311867757.7207450867 0.0904623866 0.1345402452 0.2390826792 0.0048157761 0.4722050000 0.0886400000 0.0851410000 0.0000010000 0.2938350000 0.0017470000 139512355 0 402718720 3.8938181400 3.9706938267 4.0097036362 1173 1311867757.7614738941 0.0905075520 0.1345027067 0.2390826792 0.0048142029 0.7879750000 0.1089280000 0.0527670000 0.0309050000 0.2926210000 0.2997710000 139516195 0 402718720 3.8937878609 3.9697983265 4.0098710060 1174 1311867757.7876570225 0.0914884731 0.1344660676 0.2390826792 0.0048124149 0.4187240000 0.0757860000 0.0431000000 0.0000000000 0.2952700000 0.0017500000 139519755 0 402718720 3.8928055763 3.9693858624 4.0098381042 1175 1311867757.8206570148 0.0913334861 0.1344293590 0.2390826792 0.0048108173 0.4909360000 0.0750750000 0.0846490000 0.0303650000 0.2962590000 0.0017440000 139523483 0 402718720 3.8929986954 3.9686415195 4.0095739365 1176 1311867757.8555610180 0.0928756669 0.1343940243 0.2390826792 0.0048094056 0.4779250000 0.0742530000 0.0879260000 0.0000010000 0.3102810000 0.0023240000 139527155 0 402718720 3.8912856579 3.9685459137 4.0094432831 1177 1311867757.8887560368 0.0938709527 0.1343595951 0.2390826792 0.0048084947 0.8676970000 0.0943350000 0.1116060000 0.0374080000 0.3123500000 0.3091340000 139530883 0 402718720 3.8903896809 3.9688513279 4.0095171928 1178 1311867757.9201729298 0.0942907035 0.1343255808 0.2390826792 0.0048065162 0.4765760000 0.0966170000 0.0775960000 0.0000000000 0.2975390000 0.0018320000 139534499 0 402718720 3.8898811340 3.9686584473 4.0092191696 1179 1311867757.9554479122 0.0942381695 0.1342915796 0.2390826792 0.0048050033 0.4557080000 0.0737040000 0.0421680000 0.0308590000 0.3043960000 0.0017230000 139538283 0 402718720 3.8899681568 3.9689044952 4.0088739395 1180 1311867757.9904439449 0.0950220525 0.1342583004 0.2390826792 0.0048081033 0.4632670000 0.0736830000 0.0830040000 0.0000010000 0.3020190000 0.0017070000 139542123 0 402718720 3.8892052174 3.9703342915 4.0086236000 1181 1311867758.0221159458 0.0944159403 0.1342245642 0.2390826792 0.0048076279 0.8020910000 0.0734280000 0.0855650000 0.0303970000 0.3000410000 0.3098110000 139545739 0 402718720 3.8899147511 3.9691863060 4.0081944466 1182 1311867758.0557579994 0.0935269445 0.1341901331 0.2390826792 0.0048062560 0.4759850000 0.0859320000 0.0824590000 0.0000010000 0.3030230000 0.0017150000 139549523 0 402718720 3.8907546997 3.9695806503 4.0078420639 1183 1311867758.0871500969 0.0954453126 0.1341573818 0.2390826792 0.0048046654 0.4929900000 0.0850190000 0.0487590000 0.0367250000 0.3169890000 0.0022900000 139553083 0 402718720 3.8887617588 3.9692552090 4.0076127052 1184 1311867758.1223280430 0.0948483348 0.1341241815 0.2390826792 0.0048030388 0.5246310000 0.0919980000 0.1092270000 0.0000010000 0.3179760000 0.0022890000 139556867 0 402718720 3.8894810677 3.9690902233 4.0073528290 1185 1311867758.1526539326 0.0943873897 0.1340906484 0.2390826792 0.0048037997 0.8136680000 0.0786980000 0.0824450000 0.0308610000 0.3054030000 0.3133860000 139560483 0 402718720 3.8898954391 3.9691452980 4.0069165230 1186 1311867758.1877539158 0.0950795040 0.1340577553 0.2390826792 0.0048021050 0.4671510000 0.0727140000 0.0851600000 0.0000000000 0.3047050000 0.0017030000 139564267 0 402718720 3.8892159462 3.9687082767 4.0065665245 1187 1311867758.2221779823 0.0947246850 0.1340246188 0.2390826792 0.0048022185 0.4973660000 0.0719870000 0.0819600000 0.0308310000 0.3079850000 0.0016970000 139567995 0 402718720 3.8895125389 3.9686481953 4.0059871674 1188 1311867758.2562980652 0.0944186375 0.1339912804 0.2390826792 0.0048007857 0.4262670000 0.0712920000 0.0435540000 0.0000010000 0.3068490000 0.0016970000 139571723 0 402718720 3.8896391392 3.9685800076 4.0055379868 1189 1311867758.2902839184 0.0932483897 0.1339570139 0.2390826792 0.0047992934 0.8129290000 0.0707830000 0.0840160000 0.0309050000 0.3074220000 0.3169400000 139575507 0 402718720 3.8906674385 3.9683289528 4.0049443245 1190 1311867758.3220090866 0.0932222009 0.1339227830 0.2390826792 0.0047992883 0.4765290000 0.0788240000 0.0787680000 0.0000010000 0.3143630000 0.0016980000 139579123 0 402718720 3.8905854225 3.9682919979 4.0044789314 1191 1311867758.3539829254 0.0926583707 0.1338881361 0.2390826792 0.0047976920 0.4587250000 0.0689260000 0.0405520000 0.0306740000 0.3140470000 0.0016680000 139582851 0 402718720 3.8908975124 3.9687097073 4.0040311813 1192 1311867758.3902978897 0.0935151428 0.1338542662 0.2390826792 0.0047960864 0.4820530000 0.0825310000 0.0803710000 0.0000010000 0.3145960000 0.0016790000 139586579 0 402718720 3.8898890018 3.9687981606 4.0041618347 1193 1311867758.4210340977 0.0928608105 0.1338199045 0.2390826792 0.0047950234 0.8392430000 0.0816490000 0.0853850000 0.0309100000 0.3133940000 0.3250320000 139590251 0 402718720 3.8903028965 3.9678201675 4.0034956932 1194 1311867758.4536960125 0.0940614864 0.1337866060 0.2390826792 0.0047946302 0.4729520000 0.0692550000 0.0843270000 0.0000000000 0.3145460000 0.0017800000 139593923 0 402718720 3.8890068531 3.9685392380 4.0037074089 1195 1311867758.4900159836 0.0954347104 0.1337545124 0.2390826792 0.0047952599 0.5219180000 0.0864090000 0.0823100000 0.0303330000 0.3182930000 0.0016850000 139597651 0 402718720 3.8875036240 3.9699187279 4.0039997101 1196 1311867758.5217890739 0.0936052054 0.1337209427 0.2390826792 0.0047966937 0.4694390000 0.0668330000 0.0827580000 0.0000010000 0.3153060000 0.0016670000 139601323 0 402718720 3.8892664909 3.9682831764 4.0035424232 1197 1311867758.5528969765 0.0934619978 0.1336873095 0.2390826792 0.0047951128 0.8577140000 0.0668380000 0.0831290000 0.0300790000 0.3313390000 0.3431590000 139604995 0 402718720 3.8892405033 3.9680609703 4.0034818649 1198 1311867758.5893049240 0.0930155367 0.1336533598 0.2390826792 0.0047935229 0.4691940000 0.0860610000 0.0529330000 0.0000010000 0.3256270000 0.0016660000 139608779 0 402718720 3.8895461559 3.9691884518 4.0035514832 1199 1311867758.6221299171 0.0923471451 0.1336189092 0.2390826792 0.0047935139 0.4764310000 0.0805320000 0.0399150000 0.0308000000 0.3206330000 0.0016710000 139612451 0 402718720 3.8900213242 3.9684326649 4.0033717155 1200 1311867758.6535029411 0.0944500193 0.1335862685 0.2390826792 0.0047915616 0.4455490000 0.0658890000 0.0527160000 0.0000000000 0.3223760000 0.0016580000 139616179 0 402718720 3.8879008293 3.9668703079 4.0036649704 1201 1311867758.6911680698 0.0942847654 0.1335535445 0.2390826792 0.0047919156 0.8311160000 0.0669660000 0.0806760000 0.0307310000 0.3197230000 0.3299940000 139619963 0 402718720 3.8880140781 3.9688334465 4.0038938522 1202 1311867758.7212190628 0.0935938060 0.1335203001 0.2390826792 0.0047920466 0.4403640000 0.0658080000 0.0466900000 0.0000000000 0.3233290000 0.0016580000 139623579 0 402718720 3.8887271881 3.9678294659 4.0038452148 1203 1311867758.7601859570 0.0920581818 0.1334858345 0.2390826792 0.0047904574 0.4922390000 0.0672210000 0.0690710000 0.0307490000 0.3206190000 0.0016640000 139627419 0 402718720 3.8900873661 3.9683365822 4.0036072731 1204 1311867758.7879199982 0.0926697031 0.1334519341 0.2390826792 0.0047889505 0.4656290000 0.0904450000 0.0457010000 0.0000000000 0.3248150000 0.0016640000 139630979 0 402718720 3.8894116879 3.9684588909 4.0039238930 1205 1311867758.8218998909 0.0927030295 0.1334181176 0.2390826792 0.0047884670 0.8011430000 0.0667320000 0.0395900000 0.0307150000 0.3254430000 0.3356680000 139634651 0 402718720 3.8893797398 3.9673082829 4.0041222572 1206 1311867758.8574860096 0.0958013758 0.1333869262 0.2390826792 0.0047909477 0.4695970000 0.0863360000 0.0550350000 0.0000010000 0.3234300000 0.0017530000 139638435 0 402718720 3.8863151073 3.9664750099 4.0047736168 1207 1311867758.8875849247 0.0956616551 0.1333556708 0.2390826792 0.0047889866 0.4748410000 0.0659390000 0.0454550000 0.0307540000 0.3281390000 0.0016580000 139642051 0 402718720 3.8865661621 3.9663953781 4.0047426224 1208 1311867758.9205179214 0.0956243947 0.1333244363 0.2390826792 0.0047874845 0.4748420000 0.0657140000 0.0752840000 0.0000010000 0.3292790000 0.0016570000 139645611 0 402718720 3.8866939545 3.9666917324 4.0047636032 1209 1311867758.9576990604 0.0955212712 0.1332931682 0.2390826792 0.0047890350 0.8186000000 0.0655780000 0.0454610000 0.0307430000 0.3312990000 0.3425930000 139649507 0 402718720 3.8869454861 3.9646911621 4.0046982765 1210 1311867758.9880809784 0.0982740521 0.1332642268 0.2390826792 0.0047885566 0.4801810000 0.0647830000 0.0763540000 0.0000000000 0.3344780000 0.0016450000 139653123 0 402718720 3.8842701912 3.9647438526 4.0049090385 1211 1311867759.0196750164 0.0966067314 0.1332339564 0.2390826792 0.0047870634 0.5110690000 0.0633980000 0.0755060000 0.0306370000 0.3369910000 0.0016190000 139656795 0 402718720 3.8858921528 3.9653360844 4.0044460297 1212 1311867759.0579299927 0.0971196368 0.1332041591 0.2390826792 0.0047862657 0.4805100000 0.0632600000 0.0786140000 0.0000000000 0.3338460000 0.0017260000 139660635 0 402718720 3.8853068352 3.9663140774 4.0047922134 1213 1311867759.0873589516 0.0974162742 0.1331746554 0.2390826792 0.0047847499 0.8635180000 0.0640560000 0.0756060000 0.0307580000 0.3386550000 0.3515510000 139664195 0 402718720 3.8848938942 3.9671964645 4.0050468445 1214 1311867759.1199090481 0.0978621095 0.1331455677 0.2390826792 0.0047831512 0.5026040000 0.0830330000 0.0768060000 0.0000000000 0.3381740000 0.0016310000 139667867 0 402718720 3.8843228817 3.9672126770 4.0050978661 1215 1311867759.1563479900 0.0959748104 0.1331149745 0.2390826792 0.0047836342 0.4922980000 0.0630900000 0.0590200000 0.0302440000 0.3350960000 0.0017280000 139671539 0 402718720 3.8861420155 3.9665875435 4.0046358109 1216 1311867759.1888740063 0.0972706005 0.1330854972 0.2390826792 0.0047818794 0.4683390000 0.0794600000 0.0439560000 0.0000010000 0.3403680000 0.0016320000 139675267 0 402718720 3.8848364353 3.9661087990 4.0050778389 1217 1311867759.2214748859 0.0971082896 0.1330559350 0.2390826792 0.0047804635 0.8726900000 0.0625740000 0.0779140000 0.0301840000 0.3371080000 0.3617110000 139678883 0 402718720 3.8849358559 3.9655592442 4.0050325394 1218 1311867759.2585420609 0.0957298800 0.1330252896 0.2390826792 0.0047794052 0.5229290000 0.0797810000 0.0814610000 0.0000010000 0.3563080000 0.0021220000 139682723 0 402718720 3.8862867355 3.9655642509 4.0046558380 1219 1311867759.2957389355 0.0970709845 0.1329957947 0.2390826792 0.0047774960 0.5615100000 0.0788350000 0.0947350000 0.0371750000 0.3462290000 0.0016190000 139686507 0 402718720 3.8849785328 3.9649345875 4.0048689842 1220 1311867759.3223690987 0.0985923335 0.1329675951 0.2390826792 0.0047760816 0.4847710000 0.0619480000 0.0729290000 0.0000010000 0.3453330000 0.0016170000 139690011 0 402718720 3.8834559917 3.9648034573 4.0050487518 1221 1311867759.3619010448 0.0985416397 0.1329394002 0.2390826792 0.0047744982 0.8911020000 0.0763670000 0.0766960000 0.0307030000 0.3445190000 0.3598630000 139693907 0 402718720 3.8838953972 3.9645788670 4.0050020218 1222 1311867759.3886260986 0.0990455374 0.1329116639 0.2390826792 0.0047748434 0.4671000000 0.0617040000 0.0580320000 0.0000000000 0.3428110000 0.0016170000 139697467 0 402718720 3.8833317757 3.9630868435 4.0051231384 1223 1311867759.4206190109 0.0992562622 0.1328841451 0.2390826792 0.0047744954 0.4868900000 0.0599640000 0.0423560000 0.0305130000 0.3495060000 0.0015910000 139701139 0 402718720 3.8832054138 3.9642202854 4.0052461624 1224 1311867759.4585750103 0.0988098979 0.1328563067 0.2390826792 0.0047727369 0.4908430000 0.0765040000 0.0601170000 0.0000000000 0.3496620000 0.0016220000 139704979 0 402718720 3.8837692738 3.9644613266 4.0053052902 1225 1311867759.4905979633 0.1001596525 0.1328296156 0.2390826792 0.0047709902 0.8803270000 0.0590440000 0.0709480000 0.0305270000 0.3508270000 0.3660790000 139708651 0 402718720 3.8823046684 3.9651730061 4.0054330826 1226 1311867759.5243968964 0.0987230241 0.1328017961 0.2390826792 0.0047695812 0.4737260000 0.0699400000 0.0480550000 0.0000010000 0.3511640000 0.0015960000 139712379 0 402718720 3.8841121197 3.9638202190 4.0054035187 1227 1311867759.5617649555 0.0993094817 0.1327745000 0.2390826792 0.0047677737 0.5222930000 0.0603150000 0.0752620000 0.0307070000 0.3514440000 0.0016130000 139716163 0 402718720 3.8835942745 3.9639301300 4.0054774284 1228 1311867759.5870699883 0.0990200490 0.1327470127 0.2390826792 0.0047659943 0.4725430000 0.0730010000 0.0420780000 0.0000010000 0.3528850000 0.0016060000 139719611 0 402718720 3.8840343952 3.9633922577 4.0056004524 1229 1311867759.6198399067 0.0994650722 0.1327199322 0.2390826792 0.0047640546 0.8869520000 0.0584520000 0.0701490000 0.0305230000 0.3547200000 0.3701660000 139723283 0 402718720 3.8837990761 3.9624886513 4.0057768822 1230 1311867759.6576719284 0.0997981802 0.1326931666 0.2390826792 0.0047623294 0.4711020000 0.0591790000 0.0564700000 0.0000000000 0.3509090000 0.0015890000 139727067 0 402718720 3.8838229179 3.9624471664 4.0058021545 1231 1311867759.6904048920 0.1014838368 0.1326678137 0.2390826792 0.0047608401 0.5355070000 0.0727030000 0.0712590000 0.0306320000 0.3563640000 0.0016010000 139730795 0 402718720 3.8823654652 3.9623451233 4.0059885979 1232 1311867759.7190918922 0.1005229577 0.1326417221 0.2390826792 0.0047602223 0.4905730000 0.0589630000 0.0738250000 0.0000000000 0.3529530000 0.0016900000 139734355 0 402718720 3.8835108280 3.9617643356 4.0055556297 1233 1311867759.7576398849 0.1002794653 0.1326154754 0.2390826792 0.0047588321 0.8617090000 0.0572680000 0.0355630000 0.0301950000 0.3590910000 0.3766300000 139738195 0 402718720 3.8838984966 3.9617292881 4.0054950714 1234 1311867759.7871410847 0.1015178412 0.1325902747 0.2390826792 0.0047609090 0.4850230000 0.0794460000 0.0410790000 0.0000000000 0.3599510000 0.0015890000 139741811 0 402718720 3.8827707767 3.9617750645 4.0056853294 1235 1311867759.8209869862 0.1022047997 0.1325656711 0.2390826792 0.0047684060 0.5011870000 0.0580590000 0.0466010000 0.0307160000 0.3612600000 0.0015890000 139745483 0 402718720 3.8819763660 3.9603350163 4.0055494308 1236 1311867759.8573861122 0.1033107638 0.1325420020 0.2390826792 0.0047755577 0.4972180000 0.0571930000 0.0724660000 0.0000010000 0.3630040000 0.0015600000 139749323 0 402718720 3.8812241554 3.9613757133 4.0054631233 1237 1311867759.8883268833 0.1018249094 0.1325171701 0.2390826792 0.0047805595 0.8769760000 0.0571970000 0.0403900000 0.0302500000 0.3636000000 0.3825820000 139752939 0 402718720 3.8826861382 3.9611096382 4.0050325394 1238 1311867759.9261589050 0.1007640287 0.1324915214 0.2390826792 0.0047817942 0.4942340000 0.0569290000 0.0671720000 0.0000010000 0.3656000000 0.0015710000 139756779 0 402718720 3.8837358952 3.9603321552 4.0043826103 1239 1311867759.9576280117 0.1026817933 0.1324674619 0.2390826792 0.0047822213 0.5106150000 0.0565570000 0.0511610000 0.0306740000 0.3676400000 0.0015770000 139760451 0 402718720 3.8818879128 3.9602105618 4.0045456886 1240 1311867759.9870700836 0.1036037728 0.1324441847 0.2390826792 0.0047818872 0.4954340000 0.0546340000 0.0663790000 0.0000010000 0.3698390000 0.0015730000 139764011 0 402718720 3.8809340000 3.9616720676 4.0043478012 1241 1311867760.0261199474 0.1044424623 0.1324216209 0.2390826792 0.0047828936 0.9134120000 0.0669550000 0.0536900000 0.0307130000 0.3677740000 0.3913180000 139767851 0 402718720 3.8798935413 3.9593183994 4.0036621094 1242 1311867760.0566520691 0.1034168079 0.1323982676 0.2390826792 0.0047822359 0.4988200000 0.0556320000 0.0706520000 0.0000010000 0.3679850000 0.0015630000 139771523 0 402718720 3.8809094429 3.9602124691 4.0036120415 1243 1311867760.0870590210 0.1044991538 0.1323758226 0.2390826792 0.0047807787 0.4971960000 0.0546610000 0.0336950000 0.0307170000 0.3735760000 0.0015610000 139775139 0 402718720 3.8797166348 3.9615049362 4.0038061142 1244 1311867760.1246991158 0.1041337028 0.1323531199 0.2390826792 0.0047805016 0.5198950000 0.0751740000 0.0660120000 0.0000010000 0.3741790000 0.0015610000 139778979 0 402718720 3.8798301220 3.9602069855 4.0034427643 1245 1311867760.1576859951 0.1047653332 0.1323309610 0.2390826792 0.0047801050 0.9002110000 0.0541190000 0.0388730000 0.0306620000 0.3756250000 0.3979240000 139782651 0 402718720 3.8792810440 3.9597856998 4.0034799576 1246 1311867760.1870229244 0.1046294868 0.1323087287 0.2390826792 0.0047786680 0.4785750000 0.0642450000 0.0331990000 0.0000010000 0.3765510000 0.0015410000 139786267 0 402718720 3.8792808056 3.9615621567 4.0033044815 1247 1311867760.2261290550 0.1047862098 0.1322866577 0.2390826792 0.0047786873 0.5062720000 0.0533400000 0.0400080000 0.0305390000 0.3778570000 0.0015470000 139790107 0 402718720 3.8789157867 3.9605021477 4.0031104088 1248 1311867760.2573459148 0.1051645279 0.1322649253 0.2390826792 0.0047768404 0.4968070000 0.0535840000 0.0597000000 0.0000010000 0.3789960000 0.0015510000 139793779 0 402718720 3.8784127235 3.9590139389 4.0026040077 1249 1311867760.2895119190 0.1052801013 0.1322433201 0.2390826792 0.0047757384 0.9357380000 0.0528090000 0.0640970000 0.0307570000 0.3804340000 0.4046340000 139797507 0 402718720 3.8782417774 3.9611201286 4.0025062561 1250 1311867760.3248739243 0.1048114598 0.1322213746 0.2390826792 0.0047740857 0.5026100000 0.0525690000 0.0638620000 0.0000000000 0.3816620000 0.0015330000 139801291 0 402718720 3.8786969185 3.9606397152 4.0023422241 1251 1311867760.3574841022 0.1059428900 0.1322003686 0.2390826792 0.0047838609 0.5609210000 0.0794690000 0.0674860000 0.0307430000 0.3784230000 0.0016360000 139804907 0 402718720 3.8774704933 3.9584715366 4.0020480156 1252 1311867760.3897368908 0.1059869900 0.1321794314 0.2390826792 0.0047823438 0.5062040000 0.0518000000 0.0635310000 0.0000000000 0.3863680000 0.0015260000 139808635 0 402718720 3.8772563934 3.9597907066 4.0013427734 1253 1311867760.4247770309 0.1053375751 0.1321580094 0.2390826792 0.0047833427 0.9191150000 0.0504310000 0.0318950000 0.0305820000 0.3887450000 0.4145150000 139812363 0 402718720 3.8776772022 3.9604611397 4.0009870529 1254 1311867760.4572839737 0.1068785116 0.1321378503 0.2390826792 0.0047818127 0.5073630000 0.0515100000 0.0614430000 0.0000000000 0.3899070000 0.0015160000 139815979 0 402718720 3.8764531612 3.9593288898 4.0006947517 1255 1311867760.4886090755 0.1078005508 0.1321184580 0.2390826792 0.0047802941 0.5093120000 0.0495970000 0.0315280000 0.0306080000 0.3930380000 0.0015190000 139819707 0 402718720 3.8755898476 3.9601972103 4.0005874634 1256 1311867760.5243430138 0.1073510274 0.1320987387 0.2390826792 0.0047786138 0.5116300000 0.0623330000 0.0513960000 0.0000010000 0.3933710000 0.0015080000 139823491 0 402718720 3.8763566017 3.9605095387 4.0004014969 1257 1311867760.5571060181 0.1066077352 0.1320784595 0.2390826792 0.0047772886 0.9617820000 0.0495340000 0.0600550000 0.0307740000 0.3945550000 0.4238470000 139827163 0 402718720 3.8772377968 3.9594216347 3.9997732639 1258 1311867760.5894339085 0.1067723632 0.1320583433 0.2390826792 0.0047755063 0.5116150000 0.0495160000 0.0609070000 0.0000010000 0.3965530000 0.0016050000 139830891 0 402718720 3.8772125244 3.9589335918 3.9995901585 1259 1311867760.6240029335 0.1075156480 0.1320388495 0.2390826792 0.0047741649 0.5190670000 0.0489790000 0.0429440000 0.0303330000 0.3920190000 0.0015920000 139834619 0 402718720 3.8767013550 3.9595572948 3.9993362427 1260 1311867760.6560370922 0.1058611274 0.1320180736 0.2390826792 0.0047732229 0.5119390000 0.0489140000 0.0602080000 0.0000010000 0.3983150000 0.0014910000 139838291 0 402718720 3.8785779476 3.9586293697 3.9986457825 1261 1311867760.6867549419 0.1092037931 0.1319999814 0.2390826792 0.0047720889 0.9856880000 0.0586030000 0.0602260000 0.0308140000 0.4006440000 0.4324110000 139841907 0 402718720 3.8750958443 3.9572160244 3.9987697601 1262 1311867760.7232599258 0.1085534543 0.1319814025 0.2390826792 0.0047709176 0.5182950000 0.0685370000 0.0475780000 0.0000000000 0.3974020000 0.0015850000 139845691 0 402718720 3.8759212494 3.9586894512 3.9985356331 1263 1311867760.7558701038 0.1091632172 0.1319633358 0.2390826792 0.0047692121 0.5569050000 0.0589570000 0.0589740000 0.0307860000 0.4036680000 0.0014950000 139849419 0 402718720 3.8753695488 3.9591863155 3.9983453751 1264 1311867760.7868170738 0.1090331152 0.1319451948 0.2390826792 0.0047684188 0.5146920000 0.0467990000 0.0619530000 0.0000010000 0.4012180000 0.0015600000 139853035 0 402718720 3.8755307198 3.9572141171 3.9977235794 1265 1311867760.8233850002 0.1054448485 0.1319242459 0.2390826792 0.0047668822 0.9913980000 0.0471860000 0.0617420000 0.0308660000 0.4068220000 0.4417920000 139856819 0 402718720 3.8794076443 3.9588122368 3.9972867966 1266 1311867760.8547210693 0.1067335606 0.1319043481 0.2390826792 0.0047653239 0.5293350000 0.0590450000 0.0579700000 0.0000010000 0.4076610000 0.0014760000 139860491 0 402718720 3.8783204556 3.9589843750 3.9973297119 1267 1311867760.8877849579 0.1086603031 0.1318860024 0.2390826792 0.0047642408 0.5481030000 0.0598190000 0.0441560000 0.0307710000 0.4088670000 0.0014760000 139864163 0 402718720 3.8763735294 3.9578545094 3.9974024296 1268 1311867760.9240860939 0.1086196601 0.1318676535 0.2390826792 0.0047680158 0.5186340000 0.0465880000 0.0575230000 0.0000010000 0.4100340000 0.0014770000 139868003 0 402718720 3.8764486313 3.9581899643 3.9970414639 1269 1311867760.9559810162 0.1060428545 0.1318473030 0.2390826792 0.0047665415 0.9946360000 0.0466750000 0.0575740000 0.0308510000 0.4102460000 0.4462460000 139871675 0 402718720 3.8790545464 3.9593763351 3.9966106415 1270 1311867760.9867389202 0.1075935438 0.1318282055 0.2390826792 0.0047647421 0.5001770000 0.0595300000 0.0249130000 0.0000010000 0.4112260000 0.0014640000 139875235 0 402718720 3.8773658276 3.9592490196 3.9965901375 1271 1311867761.0245900154 0.1069631130 0.1318086421 0.2390826792 0.0047634375 0.5266330000 0.0500090000 0.0293330000 0.0302600000 0.4125530000 0.0014710000 139879131 0 402718720 3.8779268265 3.9598989487 3.9964175224 1272 1311867761.0566051006 0.1076804101 0.1317896734 0.2390826792 0.0047618535 0.5182100000 0.0453180000 0.0555700000 0.0000010000 0.4128020000 0.0014660000 139882803 0 402718720 3.8771340847 3.9601774216 3.9961760044 1273 1311867761.0866270065 0.1048983634 0.1317685490 0.2390826792 0.0047642991 1.0013750000 0.0457750000 0.0568510000 0.0307730000 0.4136270000 0.4513420000 139886363 0 402718720 3.8798167706 3.9591271877 3.9955656528 1274 1311867761.1242640018 0.1079855412 0.1317498811 0.2390826792 0.0047678115 0.5209460000 0.0449200000 0.0562050000 0.0000000000 0.4153350000 0.0014580000 139890259 0 402718720 3.8765847683 3.9602532387 3.9957830906 1275 1311867761.1547141075 0.1081609130 0.1317313799 0.2390826792 0.0047662652 0.5242410000 0.0446550000 0.0287190000 0.0302860000 0.4160820000 0.0014600000 139893875 0 402718720 3.8764324188 3.9603943825 3.9956717491 1276 1311867761.1912519932 0.1054396182 0.1317107751 0.2390826792 0.0047685801 0.5338210000 0.0563770000 0.0559850000 0.0000000000 0.4169620000 0.0014600000 139897603 0 402718720 3.8790621758 3.9596524239 3.9952719212 1277 1311867761.2244689465 0.1067156047 0.1316912017 0.2390826792 0.0047670907 1.0240420000 0.0576970000 0.0591170000 0.0308520000 0.4138630000 0.4594450000 139901387 0 402718720 3.8776009083 3.9585456848 3.9950006008 1278 1311867761.2564349174 0.1075181216 0.1316722870 0.2390826792 0.0047688479 0.5229720000 0.0438740000 0.0549280000 0.0000010000 0.4196650000 0.0014350000 139905059 0 402718720 3.8768987656 3.9611573219 3.9950385094 1279 1311867761.2914810181 0.1082639396 0.1316539849 0.2390826792 0.0047673407 0.5315110000 0.0429980000 0.0325120000 0.0306790000 0.4208590000 0.0014280000 139908731 0 402718720 3.8759505749 3.9591801167 3.9946846962 1280 1311867761.3245120049 0.1093591377 0.1316365670 0.2390826792 0.0047659838 0.5278890000 0.0625320000 0.0442230000 0.0000010000 0.4166160000 0.0014420000 139912515 0 402718720 3.8748106956 3.9583721161 3.9950177670 1281 1311867761.3563210964 0.1067176238 0.1316171143 0.2390826792 0.0047643605 1.0143830000 0.0436180000 0.0575160000 0.0303380000 0.4161590000 0.4637270000 139916131 0 402718720 3.8774671555 3.9606077671 3.9946584702 1282 1311867761.3919639587 0.1069075316 0.1315978401 0.2390826792 0.0047628873 0.5229820000 0.0439720000 0.0579920000 0.0000000000 0.4162610000 0.0015330000 139919915 0 402718720 3.8769483566 3.9588608742 3.9941246510 1283 1311867761.4230949879 0.1071915105 0.1315788172 0.2390826792 0.0047615835 0.5303250000 0.0427390000 0.0293340000 0.0307280000 0.4230370000 0.0014350000 139923587 0 402718720 3.8763945103 3.9585070610 3.9935288429 1284 1311867761.4547801018 0.1070037931 0.1315596778 0.2390826792 0.0047611326 0.5309530000 0.0421980000 0.0568770000 0.0000010000 0.4267140000 0.0018040000 139927203 0 402718720 3.8767902851 3.9613299370 3.9935238361 1285 1311867761.4908668995 0.1072760522 0.1315407800 0.2390826792 0.0047593029 1.0489920000 0.0541680000 0.0702200000 0.0320120000 0.4231550000 0.4664050000 139931043 0 402718720 3.8764472008 3.9614138603 3.9930689335 1286 1311867761.5258040428 0.1081921533 0.1315226240 0.2390826792 0.0047577154 0.5341230000 0.0541490000 0.0498630000 0.0000010000 0.4256370000 0.0014240000 139934715 0 402718720 3.8753290176 3.9588019848 3.9925427437 1287 1311867761.5562748909 0.1082914844 0.1315045734 0.2390826792 0.0047558806 0.5597440000 0.0422060000 0.0568910000 0.0308330000 0.4253480000 0.0014300000 139938331 0 402718720 3.8753700256 3.9588592052 3.9923563004 1288 1311867761.5914149284 0.1065708250 0.1314852149 0.2390826792 0.0047552218 0.5253120000 0.0410420000 0.0526830000 0.0000000000 0.4271240000 0.0014100000 139942059 0 402718720 3.8771831989 3.9595885277 3.9914782047 1289 1311867761.6232030392 0.1079199240 0.1314669331 0.2390826792 0.0047543700 1.0697500000 0.0813390000 0.0572420000 0.0308840000 0.4250170000 0.4722060000 139945787 0 402718720 3.8758308887 3.9575123787 3.9912712574 1290 1311867761.6567790508 0.1082166955 0.1314489096 0.2390826792 0.0047556570 0.5057820000 0.0417570000 0.0334510000 0.0000010000 0.4260800000 0.0014270000 139949459 0 402718720 3.8757770061 3.9588489532 3.9912745953 1291 1311867761.6917459965 0.1084672287 0.1314311082 0.2390826792 0.0047546010 0.5409870000 0.0405100000 0.0417940000 0.0302980000 0.4238910000 0.0014170000 139953187 0 402718720 3.8756566048 3.9599058628 3.9908981323 1292 1311867761.7235610485 0.1074045673 0.1314125118 0.2390826792 0.0047536437 0.5311480000 0.0406980000 0.0554470000 0.0000010000 0.4305090000 0.0014180000 139956859 0 402718720 3.8767349720 3.9575080872 3.9905676842 1293 1311867761.7545659542 0.1077930704 0.1313942446 0.2390826792 0.0047520048 1.0379200000 0.0405430000 0.0552140000 0.0308100000 0.4274310000 0.4807820000 139960475 0 402718720 3.8764505386 3.9572670460 3.9904074669 1294 1311867761.7916970253 0.1108095422 0.1313783368 0.2390826792 0.0047512732 0.5126090000 0.0386220000 0.0342410000 0.0000000000 0.4352590000 0.0013780000 139964259 0 402718720 3.8737843037 3.9589171410 3.9907586575 1295 1311867761.8235230446 0.1105405688 0.1313622459 0.2390826792 0.0047495188 0.5591110000 0.0396330000 0.0499250000 0.0308240000 0.4342530000 0.0014070000 139967931 0 402718720 3.8741488457 3.9592251778 3.9905958176 1296 1311867761.8546519279 0.1087298468 0.1313447826 0.2390826792 0.0047480326 0.5478600000 0.0544200000 0.0543880000 0.0000010000 0.4345270000 0.0014000000 139971603 0 402718720 3.8760652542 3.9591586590 3.9902682304 1297 1311867761.8910980225 0.1111836061 0.1313292381 0.2390826792 0.0047478280 1.0441500000 0.0389200000 0.0504770000 0.0307790000 0.4355030000 0.4854090000 139975387 0 402718720 3.8738808632 3.9599304199 3.9907646179 1298 1311867761.9224560261 0.1094087958 0.1313123503 0.2390826792 0.0047484043 0.5130870000 0.0512010000 0.0275370000 0.0000010000 0.4295850000 0.0014930000 139979059 0 402718720 3.8758161068 3.9591259956 3.9902575016 1299 1311867761.9546790123 0.1095455587 0.1312955937 0.2390826792 0.0047485226 0.5643510000 0.0386250000 0.0537330000 0.0306770000 0.4368100000 0.0014030000 139982787 0 402718720 3.8757972717 3.9566650391 3.9898157120 1300 1311867761.9942779541 0.1125081927 0.1312811418 0.2390826792 0.0047473479 0.5434050000 0.0496650000 0.0502950000 0.0000000000 0.4388990000 0.0014010000 139986683 0 402718720 3.8731381893 3.9565320015 3.9897677898 1301 1311867762.0235669613 0.1105418503 0.1312652008 0.2390826792 0.0047468017 1.0487180000 0.0483530000 0.0334350000 0.0307100000 0.4403390000 0.4927080000 139990243 0 402718720 3.8753538132 3.9563813210 3.9890446663 1302 1311867762.0558550358 0.1136592478 0.1312516786 0.2390826792 0.0047461782 0.5143390000 0.0378220000 0.0312590000 0.0000010000 0.4407710000 0.0013880000 139993915 0 402718720 3.8724627495 3.9562184811 3.9892370701 1303 1311867762.0913889408 0.1128444374 0.1312375517 0.2390826792 0.0047656310 0.5356930000 0.0366760000 0.0269390000 0.0308200000 0.4364860000 0.0014740000 139997643 0 402718720 3.8732979298 3.9570455551 3.9891219139 1304 1311867762.1225299835 0.1133024320 0.1312237978 0.2390826792 0.0047642011 0.5267280000 0.0366660000 0.0432330000 0.0000010000 0.4423380000 0.0013800000 140001315 0 402718720 3.8731830120 3.9578967094 3.9894340038 1305 1311867762.1545391083 0.1128861830 0.1312097460 0.2390826792 0.0047779734 1.0424520000 0.0366290000 0.0290620000 0.0307520000 0.4439950000 0.4989010000 140005043 0 402718720 3.8740673065 3.9568951130 3.9890651703 1306 1311867762.1913030148 0.1143792123 0.1311968589 0.2390826792 0.0047766498 0.5451120000 0.0471200000 0.0483070000 0.0000010000 0.4451630000 0.0013780000 140008771 0 402718720 3.8729701042 3.9553246498 3.9894402027 1307 1311867762.2234869003 0.1160938665 0.1311853034 0.2390826792 0.0047751399 0.5659090000 0.0361950000 0.0478710000 0.0307450000 0.4466310000 0.0013780000 140012499 0 402718720 3.8716123104 3.9559075832 3.9896631241 1308 1311867762.2565600872 0.1162676662 0.1311738985 0.2390826792 0.0047733209 0.5350170000 0.0355830000 0.0475090000 0.0000010000 0.4474130000 0.0013730000 140016227 0 402718720 3.8717179298 3.9557750225 3.9895675182 1309 1311867762.2907900810 0.1177423745 0.1311636376 0.2390826792 0.0047716696 1.0727860000 0.0345060000 0.0471120000 0.0305950000 0.4496480000 0.5077690000 140019899 0 402718720 3.8704178333 3.9549517632 3.9898254871 1310 1311867762.3235380650 0.1155999526 0.1311517569 0.2390826792 0.0047997696 0.5285720000 0.0349700000 0.0395170000 0.0000000000 0.4495760000 0.0013640000 140023627 0 402718720 3.8726031780 3.9548068047 3.9893038273 1311 1311867762.3545570374 0.1160380915 0.1311402286 0.2390826792 0.0047983616 0.5605190000 0.0543850000 0.0204510000 0.0308680000 0.4503170000 0.0013670000 140027299 0 402718720 3.8724305630 3.9550960064 3.9893047810 1312 1311867762.3949799538 0.1156662703 0.1311284344 0.2390826792 0.0048110012 0.5141350000 0.0346230000 0.0241450000 0.0000010000 0.4508650000 0.0013630000 140031195 0 402718720 3.8729722500 3.9547903538 3.9889667034 1313 1311867762.4242470264 0.1165928170 0.1311173639 0.2390826792 0.0048091809 1.0909040000 0.0468960000 0.0453600000 0.0308210000 0.4520080000 0.5126900000 140034811 0 402718720 3.8721041679 3.9535913467 3.9888472557 1314 1311867762.4588010311 0.1167887673 0.1311064593 0.2390826792 0.0048083400 0.5134280000 0.0328590000 0.0235260000 0.0000000000 0.4525630000 0.0013570000 140038483 0 402718720 3.8722128868 3.9548923969 3.9890778065 1315 1311867762.4918160439 0.1181750074 0.1310966255 0.2390826792 0.0048069885 0.5812490000 0.0570110000 0.0408960000 0.0307900000 0.4480760000 0.0013550000 140042155 0 402718720 3.8705780506 3.9535634518 3.9887702465 1316 1311867762.5242910385 0.1187367886 0.1310872335 0.2390826792 0.0048060364 0.5157300000 0.0336380000 0.0236730000 0.0000010000 0.4539270000 0.0013530000 140045883 0 402718720 3.8701021671 3.9537560940 3.9891579151 1317 1311867762.5594940186 0.1161956564 0.1310759263 0.2390826792 0.0048046950 1.0853910000 0.0328710000 0.0480640000 0.0308150000 0.4539610000 0.5165590000 140049667 0 402718720 3.8725368977 3.9551422596 3.9888062477 1318 1311867762.5913679600 0.1180365533 0.1310660330 0.2390826792 0.0048030439 0.5105660000 0.0329310000 0.0247520000 0.0000000000 0.4483980000 0.0013460000 140053283 0 402718720 3.8704698086 3.9548988342 3.9891829491 1319 1311867762.6233699322 0.1179819480 0.1310561133 0.2390826792 0.0048013267 0.5682870000 0.0329100000 0.0452260000 0.0307330000 0.4549110000 0.0013480000 140056955 0 402718720 3.8705475330 3.9538562298 3.9894304276 1320 1311867762.6626110077 0.1199356839 0.1310476888 0.2390826792 0.0047996575 0.5375590000 0.0320910000 0.0445040000 0.0000010000 0.4564770000 0.0013460000 140060851 0 402718720 3.8683569431 3.9534811974 3.9894595146 1321 1311867762.6927230358 0.1191108823 0.1310386526 0.2390826792 0.0047978722 1.0693280000 0.0424420000 0.0243320000 0.0307720000 0.4503930000 0.5182290000 140064355 0 402718720 3.8691632748 3.9547481537 3.9893803596 1322 1311867762.7241640091 0.1176304221 0.1310285102 0.2390826792 0.0047986385 0.5393120000 0.0314790000 0.0470050000 0.0000010000 0.4563610000 0.0013370000 140068027 0 402718720 3.8704743385 3.9528310299 3.9888436794 1323 1311867762.7605299950 0.1198523864 0.1310200626 0.2390826792 0.0047979004 0.5699170000 0.0319690000 0.0434140000 0.0308000000 0.4591910000 0.0013490000 140071755 0 402718720 3.8678231239 3.9518592358 3.9888002872 1324 1311867762.7905199528 0.1257873178 0.1310161104 0.2390826792 0.0048018789 0.5577300000 0.0526050000 0.0465670000 0.0000010000 0.4540390000 0.0013380000 140075371 0 402718720 3.8618934155 3.9527702332 3.9897210598 1325 1311867762.8258841038 0.1220676526 0.1310093569 0.2390826792 0.0048004759 1.0896030000 0.0299980000 0.0455270000 0.0307190000 0.4537370000 0.5264560000 140079155 0 402718720 3.8657264709 3.9538097382 3.9895927906 1326 1311867762.8593358994 0.1235254779 0.1310037129 0.2390826792 0.0047999421 0.5518540000 0.0461230000 0.0462480000 0.0000010000 0.4547340000 0.0014250000 140082883 0 402718720 3.8643295765 3.9524674416 3.9901120663 1327 1311867762.8911890984 0.1249072477 0.1309991187 0.2390826792 0.0047986794 0.5706730000 0.0304970000 0.0460070000 0.0309020000 0.4587830000 0.0013300000 140086499 0 402718720 3.8629221916 3.9527163506 3.9903011322 1328 1311867762.9231870174 0.1211616695 0.1309917110 0.2390826792 0.0047974999 0.5209370000 0.0295600000 0.0306190000 0.0000010000 0.4563000000 0.0013190000 140090227 0 402718720 3.8667767048 3.9545469284 3.9904313087 1329 1311867762.9586219788 0.1219798625 0.1309849301 0.2390826792 0.0047959531 1.1031780000 0.0302470000 0.0453960000 0.0308310000 0.4622760000 0.5312550000 140094011 0 402718720 3.8657124043 3.9532289505 3.9902219772 1330 1311867762.9910819530 0.1237487793 0.1309794894 0.2390826792 0.0047942510 0.5524850000 0.0412240000 0.0424630000 0.0000000000 0.4643140000 0.0013240000 140097683 0 402718720 3.8638467789 3.9526178837 3.9904320240 1331 1311867763.0241999626 0.1250492036 0.1309750339 0.2390826792 0.0047931208 0.5901250000 0.0413450000 0.0418700000 0.0308680000 0.4715490000 0.0013220000 140101411 0 402718720 3.8628027439 3.9536263943 3.9908032417 1332 1311867763.0586409569 0.1250303984 0.1309705709 0.2390826792 0.0047930607 0.5389790000 0.0299360000 0.0448140000 0.0000000000 0.4594660000 0.0014130000 140105083 0 402718720 3.8629539013 3.9538283348 3.9907610416 1333 1311867763.0910348892 0.1284280270 0.1309686635 0.2390826792 0.0047915325 1.1152880000 0.0428180000 0.0374120000 0.0309210000 0.4618140000 0.5391450000 140108811 0 402718720 3.8596389294 3.9517166615 3.9910535812 1334 1311867763.1222279072 0.1286907345 0.1309669560 0.2390826792 0.0047905128 0.5408150000 0.0281860000 0.0407160000 0.0000010000 0.4674160000 0.0013060000 140112427 0 402718720 3.8596389294 3.9517166615 3.9910535812 1335 1311867763.1606709957 0.1288618147 0.1309653791 0.2390826792 0.0047889657 0.5382660000 0.0285010000 0.0437070000 0.0000010000 0.4612750000 0.0014010000 140116267 0 402718720 3.8596389294 3.9517166615 3.9910535812 1336 1311867763.1913530827 0.1290883273 0.1309639741 0.2390826792 0.0047913248 0.5726140000 0.0580150000 0.0428100000 0.0000010000 0.4673080000 0.0013110000 140119939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1337 1311867763.2239060402 0.1293349266 0.1309627557 0.2390826792 0.0047896709 1.0774350000 0.0273330000 0.0403460000 0.0000010000 0.4674000000 0.5391560000 140123611 0 402718720 3.8596389294 3.9517166615 3.9910535812 1338 1311867763.2619409561 0.1296575367 0.1309617802 0.2390826792 0.0047879164 0.5371420000 0.0277320000 0.0372550000 0.0000010000 0.4676630000 0.0012990000 140127339 0 402718720 3.8596389294 3.9517166615 3.9910535812 1339 1311867763.2997210026 0.1299395263 0.1309610167 0.2390826792 0.0047892230 0.5364440000 0.0275190000 0.0429640000 0.0000010000 0.4612150000 0.0013800000 140131235 0 402718720 3.8596389294 3.9517166615 3.9910535812 1340 1311867763.3283360004 0.1302842200 0.1309605116 0.2390826792 0.0047876816 0.5428710000 0.0277450000 0.0433360000 0.0000010000 0.4672850000 0.0012880000 140134795 0 402718720 3.8596389294 3.9517166615 3.9910535812 1341 1311867763.3595879078 0.1305673718 0.1309602185 0.2390826792 0.0047862711 1.1000270000 0.0618040000 0.0360160000 0.0000010000 0.4613020000 0.5377460000 140138355 0 402718720 3.8596389294 3.9517166615 3.9910535812 1342 1311867763.3930239677 0.1308537871 0.1309601392 0.2390826792 0.0047851746 0.5372290000 0.0276070000 0.0433730000 0.0000010000 0.4617750000 0.0013000000 140142083 0 402718720 3.8596389294 3.9517166615 3.9910535812 1343 1311867763.4231410027 0.1312543154 0.1309603582 0.2390826792 0.0047834644 0.5404190000 0.0273210000 0.0403770000 0.0000010000 0.4682630000 0.0012800000 140145699 0 402718720 3.8596389294 3.9517166615 3.9910535812 1344 1311867763.4599080086 0.1316377223 0.1309608622 0.2390826792 0.0047819866 0.5404050000 0.0277780000 0.0407290000 0.0000000000 0.4673760000 0.0013060000 140149539 0 402718720 3.8596389294 3.9517166615 3.9910535812 1345 1311867763.4920830727 0.1320759952 0.1309616913 0.2390826792 0.0047823919 1.0762040000 0.0274300000 0.0375170000 0.0000010000 0.4682910000 0.5397720000 140153155 0 402718720 3.8596389294 3.9517166615 3.9910535812 1346 1311867763.5240089893 0.1323828697 0.1309627471 0.2390826792 0.0047806654 0.5397240000 0.0274930000 0.0404080000 0.0000010000 0.4673420000 0.0012950000 140156883 0 402718720 3.8596389294 3.9517166615 3.9910535812 1347 1311867763.5586268902 0.1326159090 0.1309639744 0.2390826792 0.0047790522 0.5301860000 0.0274970000 0.0308890000 0.0000000000 0.4673110000 0.0012940000 140160555 0 402718720 3.8596389294 3.9517166615 3.9910535812 1348 1311867763.5911428928 0.1327827722 0.1309653237 0.2390826792 0.0047812422 0.5378670000 0.0278870000 0.0441150000 0.0000010000 0.4610710000 0.0013880000 140164283 0 402718720 3.8596389294 3.9517166615 3.9910535812 1349 1311867763.6315419674 0.1328776777 0.1309667413 0.2390826792 0.0047794935 1.0640910000 0.0268250000 0.0272330000 0.0000010000 0.4675420000 0.5392990000 140168123 0 402718720 3.8596389294 3.9517166615 3.9910535812 1350 1311867763.6613171101 0.1329726279 0.1309682271 0.2390826792 0.0047780549 0.5670640000 0.0539660000 0.0431410000 0.0000000000 0.4654330000 0.0012940000 140171627 0 402718720 3.8596389294 3.9517166615 3.9910535812 1351 1311867763.6906011105 0.1330276877 0.1309697515 0.2390826792 0.0047774963 0.5366460000 0.0271490000 0.0427960000 0.0000000000 0.4621750000 0.0012880000 140175299 0 402718720 3.8596389294 3.9517166615 3.9910535812 1352 1311867763.7281720638 0.1331795901 0.1309713860 0.2390826792 0.0047758198 0.5376650000 0.0263870000 0.0393960000 0.0000010000 0.4673670000 0.0012840000 140179139 0 402718720 3.8596389294 3.9517166615 3.9910535812 1353 1311867763.7617700100 0.1333123893 0.1309731163 0.2390826792 0.0047740772 1.0750810000 0.0260750000 0.0391520000 0.0000000000 0.4674330000 0.5391990000 140182811 0 402718720 3.8596389294 3.9517166615 3.9910535812 1354 1311867763.7929420471 0.1334257275 0.1309749277 0.2390826792 0.0047727927 0.5463920000 0.0380310000 0.0364870000 0.0000010000 0.4673010000 0.0012830000 140186483 0 402718720 3.8596389294 3.9517166615 3.9910535812 1355 1311867763.8308730125 0.1335403323 0.1309768209 0.2390826792 0.0047713678 0.5374780000 0.0261340000 0.0393740000 0.0000010000 0.4674650000 0.0012820000 140190323 0 402718720 3.8596389294 3.9517166615 3.9910535812 1356 1311867763.8622579575 0.1335986555 0.1309787544 0.2390826792 0.0047698973 0.5336180000 0.0260780000 0.0414970000 0.0000010000 0.4615380000 0.0012710000 140193939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1357 1311867763.8950018883 0.1336950660 0.1309807561 0.2390826792 0.0047686589 1.0731400000 0.0265620000 0.0429210000 0.0000000000 0.4611950000 0.5392490000 140197667 0 402718720 3.8596389294 3.9517166615 3.9910535812 1358 1311867763.9286549091 0.1338723451 0.1309828854 0.2390826792 0.0047701454 0.5364750000 0.0255790000 0.0389500000 0.0000010000 0.4674330000 0.0012740000 140201339 0 402718720 3.8596389294 3.9517166615 3.9910535812 1359 1311867763.9622230530 0.1340477616 0.1309851407 0.2390826792 0.0047683993 0.5351020000 0.0248410000 0.0383610000 0.0000000000 0.4674030000 0.0012620000 140205067 0 402718720 3.8596389294 3.9517166615 3.9910535812 1360 1311867763.9930698872 0.1340317577 0.1309873809 0.2390826792 0.0047669022 0.5360690000 0.0256350000 0.0414900000 0.0000010000 0.4644390000 0.0012720000 140208683 0 402718720 3.8596389294 3.9517166615 3.9910535812 1361 1311867764.0303530693 0.1341527849 0.1309897066 0.2390826792 0.0047698504 1.0889370000 0.0382700000 0.0409480000 0.0000010000 0.4673980000 0.5391040000 140212523 0 402718720 3.8596389294 3.9517166615 3.9910535812 1362 1311867764.0625600815 0.1344059110 0.1309922149 0.2390826792 0.0047687559 0.5373400000 0.0247570000 0.0407340000 0.0000010000 0.4673340000 0.0012650000 140216139 0 402718720 3.8596389294 3.9517166615 3.9910535812 1363 1311867764.0939369202 0.1345424205 0.1309948196 0.2390826792 0.0047674409 0.5372450000 0.0250200000 0.0408070000 0.0000000000 0.4669120000 0.0012630000 140219811 0 402718720 3.8596389294 3.9517166615 3.9910535812 1364 1311867764.1303229332 0.1346642822 0.1309975098 0.2390826792 0.0047683871 0.5461300000 0.0361640000 0.0380360000 0.0000010000 0.4674060000 0.0012660000 140223595 0 402718720 3.8596389294 3.9517166615 3.9910535812 1365 1311867764.1600530148 0.1347811073 0.1310002817 0.2390826792 0.0047671461 1.0728980000 0.0251070000 0.0380450000 0.0000010000 0.4673760000 0.5391390000 140227211 0 402718720 3.8596389294 3.9517166615 3.9910535812 1366 1311867764.1931879520 0.1348437220 0.1310030953 0.2390826792 0.0047655674 0.5518710000 0.0408770000 0.0405480000 0.0000010000 0.4659320000 0.0012660000 140230939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1367 1311867764.2289299965 0.1350094527 0.1310060261 0.2390826792 0.0047684064 0.5520900000 0.0455600000 0.0407210000 0.0000010000 0.4612880000 0.0012660000 140234667 0 402718720 3.8596389294 3.9517166615 3.9910535812 1368 1311867764.2623479366 0.1349776834 0.1310089293 0.2390826792 0.0047672607 0.5347320000 0.0242820000 0.0399530000 0.0000010000 0.4659540000 0.0012590000 140238395 0 402718720 3.8596389294 3.9517166615 3.9910535812 1369 1311867764.2925939560 0.1349361986 0.1310117980 0.2390826792 0.0047655600 1.0864050000 0.0373600000 0.0374250000 0.0000000000 0.4675010000 0.5408370000 140242011 0 402718720 3.8596389294 3.9517166615 3.9910535812 1370 1311867764.3292350769 0.1348427534 0.1310145944 0.2390826792 0.0047767701 0.5314830000 0.0246700000 0.0399710000 0.0000000000 0.4623280000 0.0012690000 140245851 0 402718720 3.8596389294 3.9517166615 3.9910535812 1371 1311867764.3632280827 0.1347398162 0.1310173115 0.2390826792 0.0047754479 0.5532740000 0.0438810000 0.0375240000 0.0000000000 0.4673930000 0.0012500000 140249579 0 402718720 3.8596389294 3.9517166615 3.9910535812 1372 1311867764.3937499523 0.1345486939 0.1310198854 0.2390826792 0.0047740694 0.5287190000 0.0238850000 0.0332300000 0.0000010000 0.4670800000 0.0012560000 140253195 0 402718720 3.8596389294 3.9517166615 3.9910535812 1373 1311867764.4299139977 0.1342951506 0.1310222709 0.2390826792 0.0047815651 1.0724120000 0.0248760000 0.0376100000 0.0000010000 0.4674870000 0.5392220000 140256979 0 402718720 3.8596389294 3.9517166615 3.9910535812 1374 1311867764.4600350857 0.1340782493 0.1310244950 0.2390826792 0.0047801822 0.5327170000 0.0238470000 0.0370100000 0.0000000000 0.4673700000 0.0012450000 140260539 0 402718720 3.8596389294 3.9517166615 3.9910535812 1375 1311867764.4931490421 0.1336747408 0.1310264225 0.2390826792 0.0047792600 0.5317250000 0.0235610000 0.0362920000 0.0000010000 0.4673750000 0.0012420000 140264211 0 402718720 3.8596389294 3.9517166615 3.9910535812 1376 1311867764.5289220810 0.1333598197 0.1310281183 0.2390826792 0.0047810972 0.5625400000 0.0570210000 0.0396240000 0.0000010000 0.4610970000 0.0013500000 140267995 0 402718720 3.8596389294 3.9517166615 3.9910535812 1377 1311867764.5604650974 0.1331707537 0.1310296743 0.2390826792 0.0047797100 1.0760100000 0.0226900000 0.0380770000 0.0000000000 0.4674580000 0.5442180000 140271611 0 402718720 3.8596389294 3.9517166615 3.9910535812 1378 1311867764.5906419754 0.1328416914 0.1310309893 0.2390826792 0.0047787057 0.5486560000 0.0294660000 0.0455620000 0.0000000000 0.4691360000 0.0012470000 140275227 0 402718720 3.8596389294 3.9517166615 3.9910535812 1379 1311867764.6277070045 0.1329774559 0.1310324008 0.2390826792 0.0047934296 0.5318590000 0.0235050000 0.0363920000 0.0000010000 0.4674490000 0.0012450000 140279011 0 402718720 3.8596389294 3.9517166615 3.9910535812 1380 1311867764.6609039307 0.1329371482 0.1310337810 0.2390826792 0.0047954979 0.5316660000 0.0230960000 0.0366660000 0.0000010000 0.4673950000 0.0012410000 140282795 0 402718720 3.8596389294 3.9517166615 3.9910535812 1381 1311867764.6907351017 0.1328234673 0.1310350769 0.2390826792 0.0047942102 1.0785630000 0.0335220000 0.0354000000 0.0000010000 0.4672320000 0.5391200000 140286355 0 402718720 3.8596389294 3.9517166615 3.9910535812 1382 1311867764.7274560928 0.1324338019 0.1310360890 0.2390826792 0.0047932524 0.5318340000 0.0236630000 0.0362780000 0.0000010000 0.4673830000 0.0012420000 140290139 0 402718720 3.8596389294 3.9517166615 3.9910535812 1383 1311867764.7591719627 0.1323499978 0.1310370391 0.2390826792 0.0047966141 0.5305750000 0.0226650000 0.0359160000 0.0000010000 0.4674830000 0.0012300000 140293867 0 402718720 3.8596389294 3.9517166615 3.9910535812 1384 1311867764.7921779156 0.1323081702 0.1310379575 0.2390826792 0.0047963748 0.5308080000 0.0230420000 0.0358250000 0.0000010000 0.4674200000 0.0012320000 140297483 0 402718720 3.8596389294 3.9517166615 3.9910535812 1385 1311867764.8278260231 0.1320842654 0.1310387130 0.2390826792 0.0047968636 1.0843550000 0.0427390000 0.0383180000 0.0000000000 0.4611760000 0.5388200000 140301267 0 402718720 3.8596389294 3.9517166615 3.9910535812 1386 1311867764.8610520363 0.1319052130 0.1310393382 0.2390826792 0.0047993997 0.5557640000 0.0478510000 0.0378940000 0.0000000000 0.4654880000 0.0012390000 140304939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1387 1311867764.8946199417 0.1316031963 0.1310397447 0.2390826792 0.0048008466 0.5315620000 0.0228020000 0.0367080000 0.0000010000 0.4674620000 0.0012360000 140308723 0 402718720 3.8596389294 3.9517166615 3.9910535812 1388 1311867764.9271790981 0.1312834471 0.1310399203 0.2390826792 0.0048019987 0.5302200000 0.0227090000 0.0355020000 0.0000010000 0.4674110000 0.0012370000 140312395 0 402718720 3.8596389294 3.9517166615 3.9910535812 1389 1311867764.9599800110 0.1309130937 0.1310398290 0.2390826792 0.0048002931 1.0712420000 0.0225360000 0.0364140000 0.0000010000 0.4688300000 0.5401580000 140316123 0 402718720 3.8596389294 3.9517166615 3.9910535812 1390 1311867764.9950439930 0.1305130422 0.1310394500 0.2390826792 0.0048039751 0.5316040000 0.0235400000 0.0361320000 0.0000000000 0.4673990000 0.0012440000 140319851 0 402718720 3.8596389294 3.9517166615 3.9910535812 1391 1311867765.0330669880 0.1300260574 0.1310387215 0.2390826792 0.0048032525 0.5424420000 0.0325450000 0.0380580000 0.0000010000 0.4673130000 0.0012340000 140323579 0 402718720 3.8596389294 3.9517166615 3.9910535812 1392 1311867765.0598719120 0.1297956407 0.1310378284 0.2390826792 0.0048022394 0.5284580000 0.0226540000 0.0390380000 0.0000010000 0.4621960000 0.0012420000 140327139 0 402718720 3.8596389294 3.9517166615 3.9910535812 1393 1311867765.0951199532 0.1296976358 0.1310368663 0.2390826792 0.0048015759 1.0698650000 0.0238250000 0.0387350000 0.0000010000 0.4649290000 0.5391040000 140330923 0 402718720 3.8596389294 3.9517166615 3.9910535812 1394 1311867765.1273620129 0.1293517947 0.1310356575 0.2390826792 0.0048007091 0.5415760000 0.0468180000 0.0231860000 0.0000010000 0.4670350000 0.0012440000 140334539 0 402718720 3.8596389294 3.9517166615 3.9910535812 1395 1311867765.1595649719 0.1291272491 0.1310342895 0.2390826792 0.0047990671 0.5294250000 0.0228780000 0.0383110000 0.0000000000 0.4637250000 0.0012400000 140338155 0 402718720 3.8596389294 3.9517166615 3.9910535812 1396 1311867765.1969060898 0.1290199757 0.1310328466 0.2390826792 0.0047973526 0.5398890000 0.0315450000 0.0362600000 0.0000010000 0.4674970000 0.0012510000 140341883 0 402718720 3.8596389294 3.9517166615 3.9910535812 1397 1311867765.2290871143 0.1289651096 0.1310313665 0.2390826792 0.0047984359 1.0660460000 0.0236770000 0.0389140000 0.0000010000 0.4613480000 0.5387910000 140345555 0 402718720 3.8596389294 3.9517166615 3.9910535812 1398 1311867765.2611060143 0.1288354248 0.1310297957 0.2390826792 0.0047968361 0.5327090000 0.0227590000 0.0382420000 0.0000000000 0.4671300000 0.0012390000 140349227 0 402718720 3.8596389294 3.9517166615 3.9910535812 1399 1311867765.2958459854 0.1288684011 0.1310282507 0.2390826792 0.0047951370 0.5438930000 0.0360050000 0.0359910000 0.0000000000 0.4672870000 0.0012400000 140352899 0 402718720 3.8596389294 3.9517166615 3.9910535812 1400 1311867765.3289039135 0.1289338320 0.1310267547 0.2390826792 0.0047941298 0.5316800000 0.0233510000 0.0361670000 0.0000000000 0.4675440000 0.0012340000 140356683 0 402718720 3.8596389294 3.9517166615 3.9910535812 1401 1311867765.3593490124 0.1289587617 0.1310252786 0.2390826792 0.0047924408 1.0914340000 0.0444600000 0.0368600000 0.0000000000 0.4675260000 0.5392790000 140360299 0 402718720 3.8596389294 3.9517166615 3.9910535812 1402 1311867765.3951449394 0.1289144903 0.1310237731 0.2390826792 0.0047908220 0.5280780000 0.0227380000 0.0382210000 0.0000000000 0.4622990000 0.0013160000 140364083 0 402718720 3.8596389294 3.9517166615 3.9910535812 1403 1311867765.4278709888 0.1290161610 0.1310223421 0.2390826792 0.0047933278 0.5309980000 0.0230300000 0.0391710000 0.0000000000 0.4642530000 0.0012330000 140367699 0 402718720 3.8596389294 3.9517166615 3.9910535812 1404 1311867765.4589679241 0.1289667487 0.1310208780 0.2390826792 0.0047922611 0.5312240000 0.0230610000 0.0361840000 0.0000010000 0.4673820000 0.0012390000 140371371 0 402718720 3.8596389294 3.9517166615 3.9910535812 1405 1311867765.4974000454 0.1287411600 0.1310192555 0.2390826792 0.0047920256 1.0828360000 0.0366280000 0.0363350000 0.0000020000 0.4674240000 0.5390940000 140375211 0 402718720 3.8596389294 3.9517166615 3.9910535812 1406 1311867765.5298929214 0.1285786331 0.1310175196 0.2390826792 0.0047908446 0.5485950000 0.0382540000 0.0385450000 0.0000010000 0.4672000000 0.0012420000 140378939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1407 1311867765.5625720024 0.1283993274 0.1310156588 0.2390826792 0.0047915483 0.5320580000 0.0232600000 0.0366640000 0.0000010000 0.4675010000 0.0012440000 140382611 0 402718720 3.8596389294 3.9517166615 3.9910535812 1408 1311867765.5947990417 0.1281159222 0.1310135993 0.2390826792 0.0047898593 0.5318130000 0.0231510000 0.0366370000 0.0000000000 0.4674220000 0.0012490000 140386283 0 402718720 3.8596389294 3.9517166615 3.9910535812 1409 1311867765.6310911179 0.1279805750 0.1310114467 0.2390826792 0.0047882424 1.0716810000 0.0233030000 0.0366780000 0.0000000000 0.4678040000 0.5405230000 140390011 0 402718720 3.8596389294 3.9517166615 3.9910535812 1410 1311867765.6618249416 0.1279294491 0.1310092609 0.2390826792 0.0047875893 0.5324980000 0.0234790000 0.0369440000 0.0000000000 0.4674540000 0.0012380000 140393683 0 402718720 3.8596389294 3.9517166615 3.9910535812 1411 1311867765.6966838837 0.1278745383 0.1310070392 0.2390826792 0.0047859578 0.5536560000 0.0479480000 0.0395960000 0.0000010000 0.4612450000 0.0013380000 140397411 0 402718720 3.8596389294 3.9517166615 3.9910535812 1412 1311867765.7292089462 0.1276411414 0.1310046555 0.2390826792 0.0047842906 0.5354470000 0.0230630000 0.0401140000 0.0000000000 0.4676740000 0.0012290000 140401195 0 402718720 3.8596389294 3.9517166615 3.9910535812 1413 1311867765.7602009773 0.1275231242 0.1310021915 0.2390826792 0.0047831040 1.0682330000 0.0237130000 0.0394010000 0.0000010000 0.4625460000 0.5392460000 140404811 0 402718720 3.8596389294 3.9517166615 3.9910535812 1414 1311867765.7960450649 0.1272910535 0.1309995670 0.2390826792 0.0047816143 0.5302210000 0.0231080000 0.0336910000 0.0000000000 0.4688160000 0.0012360000 140408595 0 402718720 3.8596389294 3.9517166615 3.9910535812 1415 1311867765.8298408985 0.1273240447 0.1309969694 0.2390826792 0.0047800993 0.5318410000 0.0230570000 0.0367940000 0.0000010000 0.4674180000 0.0012440000 140412267 0 402718720 3.8596389294 3.9517166615 3.9910535812 1416 1311867765.8610999584 0.1273695230 0.1309944077 0.2390826792 0.0047788078 0.5474220000 0.0335330000 0.0399160000 0.0000010000 0.4687760000 0.0014880000 140415939 0 402718720 3.8596389294 3.9517166615 3.9910535812 1417 1311867765.8960449696 0.1271561980 0.1309916990 0.2390826792 0.0047787947 1.0800600000 0.0300100000 0.0401160000 0.0000000000 0.4674400000 0.5391600000 140419667 0 402718720 3.8596389294 3.9517166615 3.9910535812 1418 1311867765.9303019047 0.1271139830 0.1309889643 0.2390826792 0.0047781604 0.5306220000 0.0242270000 0.0402450000 0.0000010000 0.4612930000 0.0013450000 140423451 0 402718720 3.8596389294 3.9517166615 3.9910535812 1419 1311867765.9612519741 0.1271447539 0.1309862552 0.2390826792 0.0047772914 0.5336600000 0.0239550000 0.0377290000 0.0000010000 0.4674150000 0.0012490000 140427011 0 402718720 3.8596389294 3.9517166615 3.9910535812 1420 1311867765.9962689877 0.1272415072 0.1309836181 0.2390826792 0.0047762253 0.5558650000 0.0494050000 0.0403530000 0.0000000000 0.4612470000 0.0013460000 140430739 0 402718720 3.8596389294 3.9517166615 3.9910535812 1421 1311867766.0289440155 0.1273389012 0.1309810532 0.2390826792 0.0047746292 1.0943770000 0.0459730000 0.0404150000 0.0000000000 0.4655290000 0.5390980000 140434523 0 402718720 3.8596389294 3.9517166615 3.9910535812 1422 1311867766.0606811047 0.1273828447 0.1309785228 0.2390826792 0.0047737012 0.5371800000 0.0246050000 0.0405990000 0.0000010000 0.4673320000 0.0012600000 140438195 0 402718720 3.8596389294 3.9517166615 3.9910535812 1423 1311867766.0968139172 0.1275372952 0.1309761045 0.2390826792 0.0047730149 0.5345150000 0.0244250000 0.0379910000 0.0000010000 0.4674770000 0.0012620000 140441979 0 402718720 3.8596389294 3.9517166615 3.9910535812 1424 1311867766.1277561188 0.1275413781 0.1309736925 0.2390826792 0.0047727663 0.5350150000 0.0246440000 0.0381550000 0.0000010000 0.4675420000 0.0012660000 140445539 0 402718720 3.8596389294 3.9517166615 3.9910535812 1425 1311867766.1625239849 0.1274137199 0.1309711943 0.2390826792 0.0047751613 1.0833290000 0.0250840000 0.0387720000 0.0000010000 0.4759840000 0.5401200000 140449323 0 402718720 3.8596389294 3.9517166615 3.9910535812 1426 1311867766.1968889236 0.1272326261 0.1309685726 0.2390826792 0.0047773254 0.5340830000 0.0260070000 0.0420620000 0.0000000000 0.4613330000 0.0012710000 140453051 0 402718720 3.8596389294 3.9517166615 3.9910535812 1427 1311867766.2298009396 0.1269660145 0.1309657677 0.2390826792 0.0047799320 0.5489760000 0.0373220000 0.0395390000 0.0000000000 0.4674320000 0.0012760000 140456779 0 402718720 3.8596389294 3.9517166615 3.9910535812 1428 1311867766.2654640675 0.1265358329 0.1309626655 0.2390826792 0.0047829656 0.5384690000 0.0262550000 0.0401430000 0.0000010000 0.4674100000 0.0012790000 140460507 0 402718720 3.8596389294 3.9517166615 3.9910535812 1429 1311867766.2981679440 0.1263417155 0.1309594318 0.2390826792 0.0047913256 1.0954930000 0.0532670000 0.0328020000 0.0000010000 0.4668870000 0.5391580000 140464179 0 402718720 3.8596389294 3.9517166615 3.9910535812 1430 1311867766.3291699886 0.1258846372 0.1309558830 0.2390826792 0.0047940768 0.5401200000 0.0269440000 0.0433250000 0.0000000000 0.4651470000 0.0012970000 140467851 0 402718720 3.8596389294 3.9517166615 3.9910535812 1431 1311867766.3653209209 0.1258917749 0.1309523441 0.2390826792 0.0048232922 0.5425010000 0.0273430000 0.0434930000 0.0000010000 0.4669920000 0.0013050000 140471579 0 402718720 3.8596389294 3.9517166615 3.9910535812 1432 1311867766.3979220390 0.1259576082 0.1309488562 0.2390826792 0.0048333122 0.5269770000 0.0275770000 0.0333670000 0.0000010000 0.4613150000 0.0013060000 140475307 0 402718720 3.8596389294 3.9517166615 3.9910535812 1433 1311867766.4302849770 0.1260159165 0.1309454138 0.2390826792 0.0048318829 1.0830250000 0.0279260000 0.0432900000 0.0000010000 0.4688410000 0.5395950000 140479035 0 402718720 3.8596389294 3.9517166615 3.9910535812 1434 1311867766.4642350674 0.1261734366 0.1309420861 0.2390826792 0.0048350088 0.5533610000 0.0403230000 0.0408160000 0.0000010000 0.4675080000 0.0013000000 140482707 0 402718720 3.8596389294 3.9517166615 3.9910535812 1435 1311867766.4967210293 0.1264784932 0.1309389755 0.2390826792 0.0048338557 0.5420270000 0.0283930000 0.0415250000 0.0000000000 0.4674360000 0.0013050000 140486379 0 402718720 3.8596389294 3.9517166615 3.9910535812 1436 1311867766.5302040577 0.1268201172 0.1309361073 0.2390826792 0.0048325817 0.5517670000 0.0379940000 0.0417130000 0.0000010000 0.4673370000 0.0013080000 140489995 0 402718720 3.8596389294 3.9517166615 3.9910535812 1437 1311867766.5639820099 0.1272232234 0.1309335235 0.2390826792 0.0048310041 1.0699720000 0.0282240000 0.0316670000 0.0000010000 0.4674280000 0.5392440000 140493723 0 402718720 3.8596389294 3.9517166615 3.9910535812 1438 1311867766.5953519344 0.1278084069 0.1309313502 0.2390826792 0.0048296486 0.5356830000 0.0274850000 0.0368750000 0.0000000000 0.4666100000 0.0013000000 140497395 0 402718720 3.8596389294 3.9517166615 3.9910535812 1439 1311867766.6287128925 0.1211242452 0.1309245350 0.2390826792 0.0048493746 0.5727040000 0.0285540000 0.0420410000 0.0303050000 0.4670730000 0.0013160000 140501123 0 402718720 3.8658952713 3.9559075832 3.9859876633 1440 1311867766.6636400223 0.1205139831 0.1309173055 0.2390826792 0.0048501484 0.5431230000 0.0290260000 0.0416020000 0.0000010000 0.4676740000 0.0013160000 140504851 0 402718720 3.8668720722 3.9522879124 3.9845707417 1441 1311867766.6964800358 0.1213797405 0.1309106868 0.2390826792 0.0048620566 1.1174550000 0.0289420000 0.0440590000 0.0303580000 0.4682030000 0.5424570000 140508467 0 402718720 3.8670272827 3.9520480633 3.9839086533 1442 1311867766.7300829887 0.1228974909 0.1309051298 0.2390826792 0.0048664294 0.5508670000 0.0418940000 0.0348790000 0.0000000000 0.4693840000 0.0013100000 140512251 0 402718720 3.8661065102 3.9511108398 3.9834253788 1443 1311867766.7628269196 0.1251356304 0.1309011315 0.2390826792 0.0048648971 0.5753670000 0.0287920000 0.0411750000 0.0307540000 0.4699280000 0.0013050000 140515923 0 402718720 3.8643779755 3.9506533146 3.9828240871 1444 1311867766.7970418930 0.1209857613 0.1308942649 0.2390826792 0.0048655934 0.5433930000 0.0284890000 0.0409980000 0.0000010000 0.4692090000 0.0013060000 140519595 0 402718720 3.8690447807 3.9496295452 3.9808769226 1445 1311867766.8299551010 0.1212578937 0.1308875961 0.2390826792 0.0048652925 1.1169210000 0.0280870000 0.0409610000 0.0308400000 0.4691640000 0.5443620000 140523267 0 402718720 3.8693714142 3.9511182308 3.9801282883 1446 1311867766.8662180901 0.1275088489 0.1308852595 0.2390826792 0.0048671797 0.5660590000 0.0544580000 0.0443390000 0.0000000000 0.4625050000 0.0013190000 140527107 0 402718720 3.8636364937 3.9499101639 3.9798157215 1447 1311867766.8958721161 0.1242404953 0.1308806674 0.2390826792 0.0048680646 0.5672190000 0.0292210000 0.0348060000 0.0308420000 0.4676590000 0.0013130000 140530611 0 402718720 3.8672771454 3.9494721889 3.9780733585 1448 1311867766.9286260605 0.1254515499 0.1308769180 0.2390826792 0.0048740377 0.5429700000 0.0293300000 0.0417920000 0.0000010000 0.4671270000 0.0013120000 140534339 0 402718720 3.8662807941 3.9501507282 3.9774107933 1449 1311867766.9661469460 0.1239422187 0.1308721322 0.2390826792 0.0048932332 1.0999720000 0.0299210000 0.0450290000 0.0303690000 0.4595040000 0.5317010000 140538179 0 402718720 3.8684468269 3.9508447647 3.9765779972 1450 1311867766.9956479073 0.1193860993 0.1308642108 0.2390826792 0.0048964166 0.5416950000 0.0302890000 0.0428400000 0.0000010000 0.4638070000 0.0013170000 140541739 0 402718720 3.8730864525 3.9507958889 3.9754261971 1451 1311867767.0294270515 0.1184272394 0.1308556395 0.2390826792 0.0048955202 0.5744390000 0.0306400000 0.0457640000 0.0303380000 0.4629340000 0.0013280000 140545523 0 402718720 3.8739547729 3.9484560490 3.9749076366 1452 1311867767.0660951138 0.1232868731 0.1308504268 0.2390826792 0.0049010877 0.5422280000 0.0305780000 0.0431320000 0.0000010000 0.4637380000 0.0013220000 140549251 0 402718720 3.8693132401 3.9487516880 3.9758999348 1453 1311867767.0968320370 0.1179243773 0.1308415307 0.2390826792 0.0049027744 1.0821450000 0.0320350000 0.0264700000 0.0307890000 0.4609330000 0.5284520000 140552923 0 402718720 3.8746674061 3.9484965801 3.9750142097 1454 1311867767.1276900768 0.1184019223 0.1308329753 0.2390826792 0.0049041517 0.5499990000 0.0410710000 0.0437990000 0.0000000000 0.4603590000 0.0013400000 140556539 0 402718720 3.8740248680 3.9464783669 3.9750292301 1455 1311867767.1632909775 0.1192804500 0.1308250354 0.2390826792 0.0049024976 0.5499930000 0.0312190000 0.0226640000 0.0307410000 0.4606110000 0.0013330000 140560323 0 402718720 3.8730456829 3.9461746216 3.9750077724 1456 1311867767.1955349445 0.1209454536 0.1308182499 0.2390826792 0.0049033009 0.5390150000 0.0486460000 0.0317760000 0.0000010000 0.4538010000 0.0013350000 140563995 0 402718720 3.8712339401 3.9470117092 3.9754207134 1457 1311867767.2308650017 0.1191831008 0.1308102643 0.2390826792 0.0049026238 1.0731350000 0.0311900000 0.0239510000 0.0307530000 0.4587800000 0.5250480000 140567835 0 402718720 3.8731377125 3.9465591908 3.9751274586 1458 1311867767.2658200264 0.1185820624 0.1308018773 0.2390826792 0.0049011683 0.5401420000 0.0319070000 0.0444980000 0.0000010000 0.4589350000 0.0013400000 140571563 0 402718720 3.8735775948 3.9475576878 3.9751000404 1459 1311867767.2981290817 0.1169584617 0.1307923890 0.2390826792 0.0048997414 0.5556820000 0.0323380000 0.0322210000 0.0302060000 0.4561320000 0.0013460000 140575235 0 402718720 3.8750469685 3.9482336044 3.9753668308 1460 1311867767.3362140656 0.1174081340 0.1307832217 0.2390826792 0.0049022321 0.5391260000 0.0325610000 0.0450650000 0.0000010000 0.4562530000 0.0013510000 140579075 0 402718720 3.8743498325 3.9474036694 3.9752032757 1461 1311867767.3633511066 0.1178433597 0.1307743648 0.2390826792 0.0049008463 1.0995510000 0.0499500000 0.0484890000 0.0308490000 0.4492380000 0.5175950000 140582635 0 402718720 3.8737411499 3.9464967251 3.9752187729 1462 1311867767.3987689018 0.1145666167 0.1307632788 0.2390826792 0.0048997999 0.5455490000 0.0341540000 0.0482610000 0.0000010000 0.4583530000 0.0013500000 140586419 0 402718720 3.8761348724 3.9478888512 3.9750072956 1463 1311867767.4331369400 0.1154622585 0.1307528202 0.2390826792 0.0048987341 0.5899090000 0.0578360000 0.0499070000 0.0307990000 0.4462660000 0.0014580000 140590147 0 402718720 3.8753325939 3.9492039680 3.9755599499 1464 1311867767.4638109207 0.1132431477 0.1307408600 0.2390826792 0.0048985474 0.5314120000 0.0346900000 0.0417370000 0.0000000000 0.4501790000 0.0013690000 140593763 0 402718720 3.8773598671 3.9485459328 3.9754195213 1465 1311867767.4974899292 0.1130116880 0.1307287582 0.2390826792 0.0048969873 1.0745460000 0.0350680000 0.0499280000 0.0308760000 0.4455210000 0.5096950000 140597491 0 402718720 3.8771069050 3.9483745098 3.9750869274 1466 1311867767.5351889133 0.1125705540 0.1307163720 0.2390826792 0.0049004064 0.5583100000 0.0554210000 0.0494240000 0.0000010000 0.4485930000 0.0013760000 140601331 0 402718720 3.8775305748 3.9496078491 3.9752008915 1467 1311867767.5664100647 0.1127619520 0.1307041331 0.2390826792 0.0049022664 0.5434770000 0.0356930000 0.0248930000 0.0308210000 0.4472330000 0.0013740000 140605003 0 402718720 3.8770956993 3.9496631622 3.9756462574 1468 1311867767.5953979492 0.1122509912 0.1306915628 0.2390826792 0.0049006180 0.5162960000 0.0351490000 0.0301510000 0.0000000000 0.4461840000 0.0013710000 140608563 0 402718720 3.8772196770 3.9495484829 3.9755880833 1469 1311867767.6338059902 0.1121834964 0.1306789637 0.2390826792 0.0048993250 1.0689220000 0.0365280000 0.0516390000 0.0307790000 0.4451230000 0.5013890000 140612403 0 402718720 3.8769302368 3.9495878220 3.9757955074 1470 1311867767.6632149220 0.1124016196 0.1306665302 0.2390826792 0.0048978520 0.5120590000 0.0373160000 0.0252940000 0.0000000000 0.4446320000 0.0013860000 140616019 0 402718720 3.8765232563 3.9483532906 3.9758310318 1471 1311867767.6991050243 0.1141647249 0.1306553121 0.2390826792 0.0048974266 0.5870030000 0.0489700000 0.0488040000 0.0308170000 0.4535620000 0.0013840000 140619803 0 402718720 3.8745484352 3.9477856159 3.9758648872 1472 1311867767.7346129417 0.1131754071 0.1306434372 0.2390826792 0.0048957963 0.5065890000 0.0368700000 0.0267550000 0.0000010000 0.4379080000 0.0014740000 140623531 0 402718720 3.8753523827 3.9484803677 3.9758343697 1473 1311867767.7651679516 0.1119750142 0.1306307634 0.2390826792 0.0048941938 1.0506490000 0.0373320000 0.0436270000 0.0308430000 0.4378670000 0.4975200000 140627203 0 402718720 3.8762848377 3.9481935501 3.9752693176 1474 1311867767.7999849319 0.1135356873 0.1306191657 0.2390826792 0.0048926333 0.5330620000 0.0367510000 0.0488590000 0.0000000000 0.4425080000 0.0013810000 140630931 0 402718720 3.8745629787 3.9473552704 3.9751210213 1475 1311867767.8344929218 0.1132234260 0.1306073719 0.2390826792 0.0048912394 0.5440030000 0.0367340000 0.0292670000 0.0308050000 0.4423420000 0.0013900000 140634603 0 402718720 3.8747158051 3.9467279911 3.9748897552 1476 1311867767.8673300743 0.1131621972 0.1305955527 0.2390826792 0.0048896059 0.5399800000 0.0483620000 0.0446860000 0.0000000000 0.4420140000 0.0013920000 140638275 0 402718720 3.8746547699 3.9465465546 3.9746706486 1477 1311867767.8966870308 0.1128311157 0.1305835253 0.2390826792 0.0048887919 1.0577210000 0.0375280000 0.0499040000 0.0307740000 0.4411660000 0.4948350000 140641835 0 402718720 3.8750607967 3.9491639137 3.9746885300 1478 1311867767.9358460903 0.1108279601 0.1305701589 0.2390826792 0.0048874209 0.5338620000 0.0386990000 0.0505880000 0.0000010000 0.4397030000 0.0013900000 140645731 0 402718720 3.8769609928 3.9492523670 3.9746012688 1479 1311867767.9646739960 0.1116123125 0.1305573409 0.2390826792 0.0048858390 0.5509940000 0.0385500000 0.0384160000 0.0308620000 0.4382730000 0.0014010000 140649347 0 402718720 3.8760650158 3.9488091469 3.9747779369 1480 1311867767.9988079071 0.1113634333 0.1305443721 0.2390826792 0.0048842798 0.5321260000 0.0386830000 0.0508430000 0.0000000000 0.4377180000 0.0013940000 140653075 0 402718720 3.8760697842 3.9496071339 3.9743938446 1481 1311867768.0346310139 0.1112830266 0.1305313664 0.2390826792 0.0048829530 1.0493350000 0.0437020000 0.0532440000 0.0309440000 0.4313320000 0.4866350000 140656859 0 402718720 3.8761272430 3.9498286247 3.9745039940 1482 1311867768.0639820099 0.1105393842 0.1305178766 0.2390826792 0.0048819246 0.5321290000 0.0398880000 0.0513910000 0.0000010000 0.4359600000 0.0014050000 140660419 0 402718720 3.8766889572 3.9492783546 3.9739048481 1483 1311867768.0985600948 0.1119198352 0.1305053357 0.2390826792 0.0048803361 0.5629360000 0.0399850000 0.0512440000 0.0308090000 0.4360260000 0.0014090000 140664203 0 402718720 3.8749234676 3.9492483139 3.9735465050 1484 1311867768.1352849007 0.1114723161 0.1304925102 0.2390826792 0.0048787177 0.5322920000 0.0401300000 0.0514400000 0.0000010000 0.4358030000 0.0014030000 140667987 0 402718720 3.8750970364 3.9494507313 3.9731550217 1485 1311867768.1651999950 0.1101917773 0.1304788397 0.2390826792 0.0048771471 1.0337880000 0.0405180000 0.0393620000 0.0308700000 0.4348810000 0.4846650000 140671603 0 402718720 3.8760905266 3.9504714012 3.9724667072 1486 1311867768.1962070465 0.1117503494 0.1304662364 0.2390826792 0.0048765059 0.5450040000 0.0542320000 0.0522170000 0.0000010000 0.4336780000 0.0014120000 140675219 0 402718720 3.8742179871 3.9508073330 3.9723274708 1487 1311867768.2323460579 0.1108875945 0.1304530699 0.2390826792 0.0048757899 0.5611720000 0.0408230000 0.0551470000 0.0307160000 0.4295660000 0.0014170000 140679003 0 402718720 3.8747360706 3.9500625134 3.9718096256 1488 1311867768.2749121189 0.1103588045 0.1304395657 0.2390826792 0.0048750344 0.5442850000 0.0547030000 0.0527360000 0.0000010000 0.4319290000 0.0014160000 140683011 0 402718720 3.8749516010 3.9514498711 3.9717350006 1489 1311867768.2962079048 0.1098630726 0.1304257467 0.2390826792 0.0048734587 1.0570190000 0.0623710000 0.0539170000 0.0308240000 0.4296450000 0.4767520000 140686347 0 402718720 3.8754248619 3.9530715942 3.9716193676 1490 1311867768.3351829052 0.1072343662 0.1304101820 0.2390826792 0.0048755514 0.5259280000 0.0424290000 0.0568810000 0.0000010000 0.4217000000 0.0014270000 140690243 0 402718720 3.8776586056 3.9525990486 3.9710321426 1491 1311867768.3693380356 0.1045264155 0.1303928220 0.2390826792 0.0048757080 0.5628120000 0.0627640000 0.0432130000 0.0308810000 0.4209850000 0.0014300000 140693859 0 402718720 3.8800401688 3.9522480965 3.9703118801 1492 1311867768.4011199474 0.1041317955 0.1303752208 0.2390826792 0.0048753096 0.5110590000 0.0432220000 0.0389940000 0.0000000000 0.4238940000 0.0014360000 140697475 0 402718720 3.8803234100 3.9535694122 3.9701263905 1493 1311867768.4324789047 0.1077215970 0.1303600475 0.2390826792 0.0048768942 1.0062420000 0.0437700000 0.0443790000 0.0304670000 0.4178350000 0.4662580000 140701035 0 402718720 3.8765923977 3.9544792175 3.9708135128 1494 1311867768.4655070305 0.1056921780 0.1303435362 0.2390826792 0.0048772838 0.5258230000 0.0438290000 0.0553250000 0.0000010000 0.4216860000 0.0014370000 140704707 0 402718720 3.8783354759 3.9533941746 3.9704525471 1495 1311867768.4980540276 0.1043092459 0.1303261220 0.2390826792 0.0048760079 0.5562360000 0.0440600000 0.0557040000 0.0308630000 0.4206890000 0.0014530000 140708435 0 402718720 3.8796584606 3.9550585747 3.9703764915 1496 1311867768.5367710590 0.1055575609 0.1303095655 0.2390826792 0.0048780346 0.5192350000 0.0556720000 0.0456150000 0.0000010000 0.4127080000 0.0015490000 140712219 0 402718720 3.8787455559 3.9560420513 3.9710404873 1497 1311867768.5648899078 0.1039693654 0.1302919702 0.2390826792 0.0048789683 1.0112900000 0.0454820000 0.0603480000 0.0308520000 0.4155740000 0.4554820000 140715835 0 402718720 3.8802177906 3.9544618130 3.9709582329 1498 1311867768.5998411179 0.1040141284 0.1302744282 0.2390826792 0.0048773580 0.5407770000 0.0635980000 0.0569660000 0.0000000000 0.4150160000 0.0014530000 140719563 0 402718720 3.8800222874 3.9539542198 3.9710757732 1499 1311867768.6319470406 0.1043753326 0.1302571506 0.2390826792 0.0048758446 0.5515510000 0.0462130000 0.0609160000 0.0309090000 0.4084880000 0.0014640000 140723235 0 402718720 3.8796701431 3.9542055130 3.9713237286 1500 1311867768.6643230915 0.1015743688 0.1302380288 0.2390826792 0.0048749762 0.5208910000 0.0460400000 0.0581920000 0.0000010000 0.4116270000 0.0014700000 140726963 0 402718720 3.8825871944 3.9556021690 3.9715018272 1501 1311867768.7014238834 0.1034312546 0.1302201695 0.2390826792 0.0048745175 1.0100490000 0.0613040000 0.0591490000 0.0308230000 0.4093410000 0.4458890000 140730691 0 402718720 3.8806309700 3.9543359280 3.9720747471 1502 1311867768.7344141006 0.1033839583 0.1302023025 0.2390826792 0.0048730524 0.5071550000 0.0472960000 0.0467490000 0.0000010000 0.4081040000 0.0014790000 140734475 0 402718720 3.8804337978 3.9531850815 3.9723315239 1503 1311867768.7646389008 0.1024768129 0.1301838557 0.2390826792 0.0048718574 0.5466570000 0.0464070000 0.0616130000 0.0307300000 0.4029030000 0.0014830000 140738091 0 402718720 3.8814451694 3.9538106918 3.9727213383 1504 1311867768.8039369583 0.1049253568 0.1301670615 0.2390826792 0.0048720724 0.4854460000 0.0470040000 0.0319080000 0.0000000000 0.4014960000 0.0014850000 140741931 0 402718720 3.8790588379 3.9541275501 3.9733276367 1505 1311867768.8365039825 0.1041205898 0.1301497549 0.2390826792 0.0048708344 0.9548370000 0.0474360000 0.0302820000 0.0307010000 0.4048960000 0.4380370000 140745659 0 402718720 3.8799881935 3.9541285038 3.9736087322 1506 1311867768.8651020527 0.1035377085 0.1301320842 0.2390826792 0.0048702412 0.5350300000 0.0687950000 0.0631950000 0.0000000000 0.3980630000 0.0014900000 140749219 0 402718720 3.8805360794 3.9525513649 3.9737465382 1507 1311867768.9001519680 0.1035019457 0.1301144133 0.2390826792 0.0048688213 0.5619000000 0.0619070000 0.0624330000 0.0308710000 0.4016820000 0.0014990000 140753003 0 402718720 3.8807218075 3.9539880753 3.9742319584 1508 1311867768.9330470562 0.1045783907 0.1300974796 0.2390826792 0.0048677149 0.5133200000 0.0490600000 0.0625930000 0.0000000000 0.3963280000 0.0015800000 140756619 0 402718720 3.8799660206 3.9525189400 3.9748177528 1509 1311867768.9639101028 0.1043251082 0.1300804005 0.2390826792 0.0048662821 0.9756660000 0.0490110000 0.0636560000 0.0308670000 0.3956900000 0.4328860000 140760235 0 402718720 3.8802073002 3.9526827335 3.9751210213 1510 1311867768.9992640018 0.1042663977 0.1300633051 0.2390826792 0.0048663841 0.4891730000 0.0494890000 0.0311310000 0.0000010000 0.4034720000 0.0014990000 140764019 0 402718720 3.8803646564 3.9534585476 3.9755074978 1511 1311867769.0331530571 0.1047213227 0.1300465334 0.2390826792 0.0048659802 0.5388660000 0.0716340000 0.0383420000 0.0308020000 0.3927690000 0.0015880000 140767635 0 402718720 3.8800599575 3.9539041519 3.9759993553 1512 1311867769.0641028881 0.1040266007 0.1300293245 0.2390826792 0.0048648195 0.5018460000 0.0616090000 0.0386130000 0.0000010000 0.3965570000 0.0015100000 140771307 0 402718720 3.8807253838 3.9533650875 3.9760193825 1513 1311867769.0999929905 0.1040153354 0.1300121308 0.2390826792 0.0048633319 0.9346460000 0.0503980000 0.0319260000 0.0309100000 0.3912800000 0.4266130000 140775091 0 402718720 3.8805599213 3.9522247314 3.9759564400 1514 1311867769.1327989101 0.1049190760 0.1299955568 0.2390826792 0.0048619328 0.4778870000 0.0505440000 0.0266760000 0.0000000000 0.3956090000 0.0015130000 140778707 0 402718720 3.8795788288 3.9528439045 3.9763379097 1515 1311867769.1643240452 0.1024227217 0.1299773569 0.2390826792 0.0048673487 0.5433360000 0.0510470000 0.0620070000 0.0308450000 0.3943860000 0.0015180000 140782379 0 402718720 3.8819484711 3.9531507492 3.9763693810 1516 1311867769.2002429962 0.1035523191 0.1299599262 0.2390826792 0.0048673852 0.5043630000 0.0820920000 0.0282640000 0.0000010000 0.3888960000 0.0015160000 140786107 0 402718720 3.8810131550 3.9526255131 3.9765729904 1517 1311867769.2324860096 0.1035756171 0.1299425337 0.2390826792 0.0048680141 0.9496500000 0.0517110000 0.0502760000 0.0309580000 0.3919340000 0.4212410000 140789779 0 402718720 3.8810110092 3.9541277885 3.9767835140 1518 1311867769.2636189461 0.1042081714 0.1299255809 0.2390826792 0.0048680511 0.4779820000 0.0502770000 0.0318000000 0.0000010000 0.3908030000 0.0015180000 140793451 0 402718720 3.8805496693 3.9527924061 3.9770812988 1519 1311867769.3002018929 0.1053105518 0.1299093762 0.2390826792 0.0048752666 0.5453860000 0.0520320000 0.0633370000 0.0308400000 0.3932540000 0.0019530000 140797179 0 402718720 3.8793435097 3.9536979198 3.9771611691 1520 1311867769.3330841064 0.1032137871 0.1298918133 0.2390826792 0.0048742851 0.5467670000 0.0664320000 0.0837870000 0.0000010000 0.3914530000 0.0015250000 140800851 0 402718720 3.8814804554 3.9551589489 3.9771118164 1521 1311867769.3653230667 0.1011122540 0.1298728918 0.2390826792 0.0048728207 0.9586190000 0.0647330000 0.0648160000 0.0307930000 0.3841760000 0.4105050000 140804635 0 402718720 3.8834946156 3.9563019276 3.9769752026 1522 1311867769.3995320797 0.1018144786 0.1298544566 0.2390826792 0.0048715549 0.4791250000 0.0538580000 0.0387230000 0.0000000000 0.3814260000 0.0015350000 140808363 0 402718720 3.8826031685 3.9562127590 3.9772231579 1523 1311867769.4340240955 0.1010393798 0.1298355366 0.2390826792 0.0048708141 0.5029480000 0.0543670000 0.0335710000 0.0308150000 0.3790780000 0.0015490000 140812035 0 402718720 3.8831932545 3.9552249908 3.9770417213 1524 1311867769.4644269943 0.1003745347 0.1298162053 0.2390826792 0.0048769761 0.5037720000 0.0550520000 0.0662610000 0.0000010000 0.3773280000 0.0015560000 140815707 0 402718720 3.8839077950 3.9556865692 3.9772908688 1525 1311867769.4999239445 0.1011822373 0.1297974289 0.2390826792 0.0048808924 0.9543520000 0.0798100000 0.0665170000 0.0303230000 0.3753560000 0.3987410000 140819491 0 402718720 3.8831567764 3.9561750889 3.9774415493 1526 1311867769.5317490101 0.1017212644 0.1297790304 0.2390826792 0.0048796151 0.4848980000 0.0567140000 0.0533760000 0.0000010000 0.3696510000 0.0015570000 140823107 0 402718720 3.8826107979 3.9551517963 3.9770660400 1527 1311867769.5660109520 0.1019407585 0.1297607997 0.2390826792 0.0048781848 0.5322930000 0.0559930000 0.0671440000 0.0307600000 0.3732670000 0.0015670000 140826723 0 402718720 3.8822059631 3.9546322823 3.9772272110 1528 1311867769.6002509594 0.1015722752 0.1297423517 0.2390826792 0.0048766536 0.4735830000 0.0565080000 0.0401570000 0.0000000000 0.3717810000 0.0015620000 140830451 0 402718720 3.8825106621 3.9552254677 3.9770867825 1529 1311867769.6330249310 0.1025790945 0.1297245863 0.2390826792 0.0048801545 0.9163790000 0.0568430000 0.0623400000 0.0308160000 0.3703520000 0.3924390000 140834179 0 402718720 3.8816397190 3.9544017315 3.9774525166 1530 1311867769.6637229919 0.1016220227 0.1297062186 0.2390826792 0.0048788183 0.4994690000 0.0571420000 0.0680880000 0.0000000000 0.3690810000 0.0015550000 140837795 0 402718720 3.8824884892 3.9549603462 3.9775168896 1531 1311867769.7014029026 0.1023290455 0.1296883367 0.2390826792 0.0048844037 0.5248430000 0.0687890000 0.0520910000 0.0308750000 0.3679060000 0.0015760000 140841691 0 402718720 3.8818106651 3.9559690952 3.9781949520 1532 1311867769.7340829372 0.1005745754 0.1296693330 0.2390826792 0.0048834626 0.4667180000 0.0580590000 0.0434460000 0.0000010000 0.3600190000 0.0015790000 140845307 0 402718720 3.8837299347 3.9563443661 3.9785034657 1533 1311867769.7641069889 0.1020240486 0.1296512995 0.2390826792 0.0048873599 0.8959930000 0.0593510000 0.0589070000 0.0308610000 0.3619500000 0.3813060000 140848979 0 402718720 3.8823556900 3.9570188522 3.9794898033 1534 1311867769.8003458977 0.1008630618 0.1296325327 0.2390826792 0.0049072917 0.4720840000 0.0599680000 0.0479470000 0.0000010000 0.3589790000 0.0015870000 140852707 0 402718720 3.8830370903 3.9569754601 3.9797480106 1535 1311867769.8341090679 0.1008715108 0.1296137959 0.2390826792 0.0049066604 0.5127310000 0.0796940000 0.0449890000 0.0309190000 0.3519200000 0.0016100000 140856435 0 402718720 3.8829779625 3.9560561180 3.9800500870 1536 1311867769.8692820072 0.1010235175 0.1295951824 0.2390826792 0.0049052642 0.4998840000 0.0862670000 0.0575140000 0.0000000000 0.3509120000 0.0015990000 140860219 0 402718720 3.8829419613 3.9558815956 3.9804985523 1537 1311867769.9001140594 0.1003832147 0.1295761766 0.2390826792 0.0049038919 0.8895580000 0.0622860000 0.0771620000 0.0305350000 0.3476100000 0.3683950000 140863891 0 402718720 3.8836758137 3.9575028419 3.9810326099 1538 1311867769.9321451187 0.0998001024 0.1295568164 0.2390826792 0.0049025782 0.4914970000 0.0629320000 0.0740640000 0.0000010000 0.3493420000 0.0015820000 140867507 0 402718720 3.8842563629 3.9583883286 3.9811706543 1539 1311867769.9684319496 0.0994114801 0.1295372287 0.2390826792 0.0049013080 0.5016950000 0.0757440000 0.0437000000 0.0308240000 0.3461760000 0.0016220000 140871291 0 402718720 3.8844494820 3.9575705528 3.9812812805 1540 1311867770.0010259151 0.0988222733 0.1295172840 0.2390826792 0.0048999484 0.4627210000 0.0635030000 0.0502140000 0.0000000000 0.3437650000 0.0016180000 140875075 0 402718720 3.8851525784 3.9582247734 3.9815700054 1541 1311867770.0330319405 0.0978553817 0.1294967376 0.2390826792 0.0048984684 0.8536040000 0.0745960000 0.0536930000 0.0309360000 0.3370670000 0.3536790000 140878691 0 402718720 3.8860473633 3.9589064121 3.9816355705 1542 1311867770.0690810680 0.0961154476 0.1294750896 0.2390826792 0.0048984084 0.4874320000 0.0650540000 0.0801550000 0.0000000000 0.3369770000 0.0016320000 140882475 0 402718720 3.8875353336 3.9579861164 3.9815542698 1543 1311867770.1002650261 0.0975241438 0.1294543826 0.2390826792 0.0049004434 0.5275590000 0.0779720000 0.0760340000 0.0309110000 0.3374180000 0.0016450000 140886147 0 402718720 3.8861167431 3.9576892853 3.9820997715 1544 1311867770.1335709095 0.0974655077 0.1294336644 0.2390826792 0.0048990527 0.4458310000 0.0656090000 0.0390180000 0.0000010000 0.3359550000 0.0016310000 140889819 0 402718720 3.8861365318 3.9582085609 3.9823119640 1545 1311867770.1684958935 0.0967506394 0.1294125103 0.2390826792 0.0048976992 0.8894360000 0.0930520000 0.0809710000 0.0309580000 0.3340520000 0.3467230000 140893603 0 402718720 3.8867208958 3.9580852985 3.9822609425 1546 1311867770.2001299858 0.0964094475 0.1293911629 0.2390826792 0.0048962353 0.5016520000 0.0862040000 0.0772980000 0.0000000000 0.3328790000 0.0016450000 140897275 0 402718720 3.8869450092 3.9576032162 3.9826123714 1547 1311867770.2336180210 0.0969844460 0.1293702148 0.2390826792 0.0048953790 0.4891790000 0.0671060000 0.0549650000 0.0309760000 0.3308670000 0.0016610000 140900947 0 402718720 3.8858497143 3.9578921795 3.9828782082 1548 1311867770.2679719925 0.0964475721 0.1293489470 0.2390826792 0.0048961675 0.4815260000 0.0671080000 0.0822830000 0.0000010000 0.3268500000 0.0016430000 140904675 0 402718720 3.8864433765 3.9570233822 3.9829947948 1549 1311867770.3009040356 0.0958430767 0.1293273163 0.2390826792 0.0048952529 0.8019510000 0.0665670000 0.0348820000 0.0304820000 0.3256160000 0.3407560000 140908347 0 402718720 3.8869755268 3.9566111565 3.9830222130 1550 1311867770.3339090347 0.0976082981 0.1293068524 0.2390826792 0.0048976976 0.4804390000 0.0673400000 0.0824520000 0.0000010000 0.3250780000 0.0017430000 140912075 0 402718720 3.8848927021 3.9566667080 3.9832680225 1551 1311867770.3681850433 0.0959843993 0.1292853679 0.2390826792 0.0049130983 0.4694620000 0.0668550000 0.0419040000 0.0308800000 0.3245170000 0.0016640000 140915803 0 402718720 3.8861751556 3.9572744370 3.9831428528 1552 1311867770.4014930725 0.0939327255 0.1292625892 0.2390826792 0.0049154275 0.4780420000 0.0677690000 0.0786680000 0.0000010000 0.3263100000 0.0016660000 140919475 0 402718720 3.8881442547 3.9580154419 3.9828152657 1553 1311867770.4333899021 0.0938295349 0.1292397733 0.2390826792 0.0049157146 0.7961100000 0.0680500000 0.0337230000 0.0309350000 0.3243090000 0.3354570000 140923203 0 402718720 3.8879988194 3.9582254887 3.9829897881 1554 1311867770.4684588909 0.0931423753 0.1292165446 0.2390826792 0.0049142916 0.4766270000 0.0685070000 0.0795130000 0.0000010000 0.3232950000 0.0016670000 140926931 0 402718720 3.8886513710 3.9573647976 3.9829957485 1555 1311867770.5046019554 0.0918943733 0.1291925432 0.2390826792 0.0049128034 0.4857570000 0.0873970000 0.0425430000 0.0309240000 0.3195580000 0.0016790000 140930715 0 402718720 3.8896143436 3.9572944641 3.9827589989 1556 1311867770.5338129997 0.0931690261 0.1291693918 0.2390826792 0.0049116956 0.4772350000 0.0686310000 0.0843200000 0.0000000000 0.3189190000 0.0016780000 140934275 0 402718720 3.8884003162 3.9573500156 3.9832842350 1557 1311867770.5683600903 0.0932472944 0.1291463205 0.2390826792 0.0049146876 0.8832140000 0.0838640000 0.1065250000 0.0376550000 0.3210250000 0.3304910000 140938003 0 402718720 3.8881525993 3.9577455521 3.9837391376 1558 1311867770.6027359962 0.0940979943 0.1291238248 0.2390826792 0.0049164869 0.4413660000 0.0698950000 0.0477830000 0.0000000000 0.3183810000 0.0016820000 140941731 0 402718720 3.8874676228 3.9588804245 3.9841334820 1559 1311867770.6331069469 0.0911836252 0.1290994885 0.2390826792 0.0049170072 0.5021190000 0.0696360000 0.0805810000 0.0308790000 0.3157060000 0.0016850000 140945347 0 402718720 3.8902144432 3.9585652351 3.9839766026 1560 1311867770.6699299812 0.0917654186 0.1290755564 0.2390826792 0.0049154764 0.4695640000 0.0692770000 0.0803270000 0.0000010000 0.3146060000 0.0016820000 140949187 0 402718720 3.8900735378 3.9578802586 3.9841854572 1561 1311867770.7014191151 0.0925971493 0.1290521878 0.2390826792 0.0049141859 0.8044910000 0.0819210000 0.0574200000 0.0305820000 0.3106100000 0.3200910000 140952859 0 402718720 3.8895409107 3.9572932720 3.9846863747 1562 1311867770.7347331047 0.0931911319 0.1290292294 0.2390826792 0.0049137609 0.4546350000 0.0713550000 0.0647950000 0.0000010000 0.3131650000 0.0016650000 140956587 0 402718720 3.8891100883 3.9583990574 3.9850466251 1563 1311867770.7684218884 0.0923530981 0.1290057642 0.2390826792 0.0049127198 0.4620060000 0.0717480000 0.0437250000 0.0310420000 0.3101280000 0.0016950000 140960259 0 402718720 3.8899936676 3.9577372074 3.9848444462 1564 1311867770.8017508984 0.0926566124 0.1289825230 0.2390826792 0.0049112793 0.4720240000 0.0827310000 0.0730850000 0.0000010000 0.3108560000 0.0016950000 140963931 0 402718720 3.8897604942 3.9573249817 3.9853360653 1565 1311867770.8396499157 0.0912374780 0.1289584048 0.2390826792 0.0049105581 0.8179460000 0.0995270000 0.0581190000 0.0310840000 0.3071340000 0.3183890000 140967827 0 402718720 3.8914146423 3.9584116936 3.9855768681 1566 1311867770.8699400425 0.0909808651 0.1289341535 0.2390826792 0.0049101878 0.4884230000 0.0916800000 0.0848740000 0.0000010000 0.3064410000 0.0017110000 140971443 0 402718720 3.8918731213 3.9569864273 3.9856984615 1567 1311867770.9027009010 0.0906853899 0.1289097446 0.2390826792 0.0049089700 0.4585150000 0.0719400000 0.0418570000 0.0310510000 0.3082980000 0.0017020000 140975115 0 402718720 3.8922505379 3.9566812515 3.9859199524 1568 1311867770.9355690479 0.0914767981 0.1288858715 0.2390826792 0.0049104760 0.4537240000 0.0716620000 0.0687040000 0.0000000000 0.3079740000 0.0016990000 140978843 0 402718720 3.8914616108 3.9583814144 3.9866654873 1569 1311867770.9692869186 0.0917778164 0.1288622208 0.2390826792 0.0049096943 0.8146140000 0.0727070000 0.0871190000 0.0310770000 0.3048050000 0.3152470000 140982571 0 402718720 3.8914554119 3.9572651386 3.9872081280 1570 1311867771.0021619797 0.0920962095 0.1288388029 0.2390826792 0.0049101036 0.4669080000 0.0722220000 0.0824080000 0.0000010000 0.3069070000 0.0017030000 140986243 0 402718720 3.8912389278 3.9569416046 3.9877800941 1571 1311867771.0365509987 0.0920626074 0.1288153935 0.2390826792 0.0049220363 0.5112610000 0.0854260000 0.0829210000 0.0307930000 0.3066810000 0.0017160000 140989915 0 402718720 3.8911488056 3.9584705830 3.9887406826 1572 1311867771.0685739517 0.0901347473 0.1287907875 0.2390826792 0.0049208391 0.4683140000 0.0736350000 0.0836620000 0.0000010000 0.3055240000 0.0017140000 140993643 0 402718720 3.8931276798 3.9589228630 3.9891736507 1573 1311867771.1014111042 0.0876263529 0.1287646181 0.2390826792 0.0049261371 0.7816900000 0.0743560000 0.0564290000 0.0310120000 0.3037020000 0.3120530000 140997371 0 402718720 3.8957822323 3.9581365585 3.9892659187 1574 1311867771.1381099224 0.0874461681 0.1287383675 0.2390826792 0.0049250417 0.5105280000 0.0943700000 0.1078070000 0.0000000000 0.3028620000 0.0017270000 141001155 0 402718720 3.8960692883 3.9580500126 3.9894351959 1575 1311867771.1686840057 0.0886127278 0.1287128909 0.2390826792 0.0049240941 0.4830910000 0.0946760000 0.0525060000 0.0305600000 0.2996340000 0.0018320000 141004771 0 402718720 3.8949363232 3.9583618641 3.9899845123 1576 1311867771.2019159794 0.0884239599 0.1286873269 0.2390826792 0.0049226970 0.4681720000 0.0748760000 0.0892800000 0.0000010000 0.2985950000 0.0017310000 141008443 0 402718720 3.8953390121 3.9573674202 3.9901516438 1577 1311867771.2363801003 0.0890646204 0.1286622015 0.2390826792 0.0049216115 0.7595430000 0.0746370000 0.0453670000 0.0310650000 0.2977550000 0.3070610000 141012171 0 402718720 3.8948955536 3.9577634335 3.9905669689 1578 1311867771.2705540657 0.0888968334 0.1286370017 0.2390826792 0.0049202337 0.4295390000 0.0756290000 0.0503290000 0.0000000000 0.2981460000 0.0017220000 141015955 0 402718720 3.8954031467 3.9585003853 3.9907350540 1579 1311867771.3016860485 0.0892089382 0.1286120314 0.2390826792 0.0049187998 0.4652220000 0.0749990000 0.0571750000 0.0310770000 0.2965240000 0.0017380000 141019571 0 402718720 3.8953769207 3.9580738544 3.9910638332 1580 1311867771.3360719681 0.0889436901 0.1285869248 0.2390826792 0.0049172778 0.4660790000 0.0755170000 0.0900530000 0.0000010000 0.2950520000 0.0017320000 141023299 0 402718720 3.8960597515 3.9575009346 3.9912590981 1581 1311867771.3679900169 0.0890942067 0.1285619453 0.2390826792 0.0049157277 0.8075280000 0.0887500000 0.0870820000 0.0311020000 0.2947650000 0.3021270000 141026971 0 402718720 3.8960225582 3.9584090710 3.9914104939 1582 1311867771.4030399323 0.0877063572 0.1285361200 0.2390826792 0.0049142693 0.4664930000 0.0771240000 0.0919030000 0.0000000000 0.2917300000 0.0018410000 141030699 0 402718720 3.8975448608 3.9599907398 3.9914147854 1583 1311867771.4361710548 0.0879041627 0.1285104523 0.2390826792 0.0049134204 0.4942740000 0.0764160000 0.0904370000 0.0305130000 0.2914680000 0.0017550000 141034427 0 402718720 3.8977055550 3.9582669735 3.9914417267 1584 1311867771.4682569504 0.0882448480 0.1284850321 0.2390826792 0.0049119817 0.4595150000 0.0762860000 0.0871800000 0.0000000000 0.2905880000 0.0017450000 141038099 0 402718720 3.8976025581 3.9592323303 3.9918003082 1585 1311867771.5008640289 0.0867982954 0.1284587313 0.2390826792 0.0049107369 0.7752730000 0.0769220000 0.0806850000 0.0310050000 0.2879630000 0.2950140000 141041771 0 402718720 3.8993520737 3.9607970715 3.9919064045 1586 1311867771.5365910530 0.0861648545 0.1284320643 0.2390826792 0.0049098142 0.4686500000 0.1083350000 0.0701790000 0.0000000000 0.2846640000 0.0017660000 141045555 0 402718720 3.9005432129 3.9591691494 3.9918007851 1587 1311867771.5686171055 0.0868411213 0.1284058570 0.2390826792 0.0049083059 0.4602480000 0.0776100000 0.0622550000 0.0310860000 0.2838300000 0.0017680000 141049283 0 402718720 3.9002151489 3.9583528042 3.9921181202 1588 1311867771.6077210903 0.0860798135 0.1283792033 0.2390826792 0.0049078904 0.4284820000 0.0778590000 0.0626870000 0.0000010000 0.2824560000 0.0017690000 141053123 0 402718720 3.9012730122 3.9600260258 3.9923770428 1589 1311867771.6366779804 0.0870506465 0.1283531942 0.2390826792 0.0049069530 0.7331440000 0.0785400000 0.0525140000 0.0305610000 0.2807110000 0.2871160000 141056683 0 402718720 3.9008588791 3.9579493999 3.9927561283 1590 1311867771.6715440750 0.0856898054 0.1283263619 0.2390826792 0.0049060777 0.4170470000 0.0787500000 0.0526360000 0.0000000000 0.2801640000 0.0017740000 141060467 0 402718720 3.9024286270 3.9574356079 3.9927086830 1591 1311867771.7024850845 0.0847620592 0.1282989801 0.2390826792 0.0049051939 0.5044790000 0.0983710000 0.0910050000 0.0310380000 0.2785570000 0.0017830000 141064139 0 402718720 3.9035725594 3.9593622684 3.9933001995 1592 1311867771.7367300987 0.0852152556 0.1282719175 0.2390826792 0.0049040983 0.4221400000 0.0794980000 0.0607080000 0.0000010000 0.2764320000 0.0017870000 141067811 0 402718720 3.9035742283 3.9594159126 3.9937369823 1593 1311867771.7697410583 0.0851925686 0.1282448746 0.2390826792 0.0049039083 0.7252290000 0.0795260000 0.0559850000 0.0310940000 0.2743490000 0.2805350000 141071539 0 402718720 3.9042222500 3.9577367306 3.9938497543 1594 1311867771.8023030758 0.0860350430 0.1282183941 0.2390826792 0.0049026129 0.4494360000 0.0795880000 0.0907840000 0.0000000000 0.2735530000 0.0017810000 141075211 0 402718720 3.9040629864 3.9578306675 3.9942255020 1595 1311867771.8386220932 0.0856516659 0.1281917065 0.2390826792 0.0049018010 0.4496760000 0.0800000000 0.0610560000 0.0310510000 0.2720470000 0.0017960000 141079051 0 402718720 3.9046421051 3.9585969448 3.9943809509 1596 1311867771.8711829185 0.0860592872 0.1281653078 0.2390826792 0.0049003993 0.4100760000 0.0796340000 0.0536320000 0.0000010000 0.2712530000 0.0017820000 141082667 0 402718720 3.9048235416 3.9573192596 3.9944815636 1597 1311867771.9016489983 0.0848981142 0.1281382150 0.2390826792 0.0048995472 0.7547320000 0.0797270000 0.0925440000 0.0310460000 0.2707250000 0.2769630000 141086339 0 402718720 3.9064471722 3.9563508034 3.9939725399 1598 1311867771.9377520084 0.0847919285 0.1281110897 0.2390826792 0.0048991020 0.4396500000 0.0796010000 0.0838970000 0.0000000000 0.2706040000 0.0017830000 141090123 0 402718720 3.9070012569 3.9571409225 3.9941761494 1599 1311867771.9696009159 0.0850263983 0.1280841449 0.2390826792 0.0048980566 0.4559830000 0.0795900000 0.0703490000 0.0305670000 0.2699820000 0.0017510000 141093795 0 402718720 3.9072232246 3.9567718506 3.9940297604 1600 1311867772.0018649101 0.0861238018 0.1280579197 0.2390826792 0.0048968069 0.4424300000 0.0781030000 0.0888500000 0.0000010000 0.2698980000 0.0017920000 141097523 0 402718720 3.9065978527 3.9560716152 3.9940044880 1601 1311867772.0375399590 0.0882987306 0.1280330857 0.2390826792 0.0048981509 0.7758990000 0.1087550000 0.0886330000 0.0310810000 0.2682560000 0.2754310000 141101251 0 402718720 3.9046108723 3.9570138454 3.9946484566 1602 1311867772.0696671009 0.0866045356 0.1280072252 0.2390826792 0.0048972115 0.4505220000 0.0795660000 0.0962600000 0.0000010000 0.2691520000 0.0017870000 141104979 0 402718720 3.9063920975 3.9571106434 3.9942779541 1603 1311867772.1012299061 0.0871884599 0.1279817612 0.2390826792 0.0048960099 0.4754940000 0.0802360000 0.0898810000 0.0310770000 0.2687740000 0.0018040000 141108595 0 402718720 3.9059958458 3.9565365314 3.9943711758 1604 1311867772.1369819641 0.0887228996 0.1279572856 0.2390826792 0.0048950137 0.4584460000 0.0925410000 0.0917910000 0.0000010000 0.2685590000 0.0017990000 141112267 0 402718720 3.9043893814 3.9572501183 3.9948568344 1605 1311867772.1690549850 0.0885616615 0.1279327400 0.2390826792 0.0048935013 0.7493700000 0.0805370000 0.0921730000 0.0310810000 0.2676490000 0.2741610000 141115995 0 402718720 3.9046416283 3.9576404095 3.9951450825 1606 1311867772.2016880512 0.0842001140 0.1279055093 0.2390826792 0.0048964891 0.4075060000 0.0809690000 0.0544300000 0.0000010000 0.2665750000 0.0018060000 141119723 0 402718720 3.9092988968 3.9572663307 3.9944758415 1607 1311867772.2370250225 0.0865611807 0.1278797816 0.2390826792 0.0048956394 0.4753160000 0.0805000000 0.0923000000 0.0310560000 0.2659130000 0.0017630000 141123395 0 402718720 3.9071755409 3.9562227726 3.9949777126 1608 1311867772.2710011005 0.0851312578 0.1278531967 0.2390826792 0.0048942164 0.4322490000 0.0963390000 0.0650680000 0.0000010000 0.2652760000 0.0017950000 141127179 0 402718720 3.9085650444 3.9570951462 3.9950218201 1609 1311867772.3046050072 0.0858281404 0.1278270780 0.2390826792 0.0048927565 0.7427000000 0.0806690000 0.0924990000 0.0310490000 0.2640220000 0.2707160000 141130907 0 402718720 3.9078874588 3.9571163654 3.9952418804 1610 1311867772.3366808891 0.0878541544 0.1278022501 0.2390826792 0.0048917738 0.4418210000 0.0804250000 0.0924420000 0.0000000000 0.2634070000 0.0017960000 141134523 0 402718720 3.9060640335 3.9553775787 3.9956529140 1611 1311867772.3689630032 0.0865722373 0.1277766573 0.2390826792 0.0048904075 0.5072670000 0.1105610000 0.0970200000 0.0310480000 0.2630510000 0.0018140000 141138251 0 402718720 3.9068768024 3.9565603733 3.9955344200 1612 1311867772.4054839611 0.0873109847 0.1277515545 0.2390826792 0.0048892558 0.3966320000 0.0804650000 0.0491590000 0.0000000000 0.2611390000 0.0019030000 141142091 0 402718720 3.9061923027 3.9562315941 3.9959211349 1613 1311867772.4385271072 0.0881174207 0.1277269828 0.2390826792 0.0048879436 0.7083410000 0.0807650000 0.0640950000 0.0308940000 0.2610630000 0.2678000000 141145763 0 402718720 3.9052641392 3.9552614689 3.9960498810 1614 1311867772.4697830677 0.0885008797 0.1277026791 0.2390826792 0.0048865304 0.4013790000 0.0806690000 0.0543820000 0.0000000000 0.2607570000 0.0017970000 141149379 0 402718720 3.9049823284 3.9539208412 3.9961810112 1615 1311867772.5049729347 0.0892948806 0.1276788972 0.2390826792 0.0048864514 0.4476700000 0.0806950000 0.0698260000 0.0310340000 0.2605160000 0.0017990000 141153163 0 402718720 3.9036953449 3.9543130398 3.9963126183 1616 1311867772.5382430553 0.0898513645 0.1276554891 0.2390826792 0.0048851204 0.4508230000 0.0922970000 0.0934800000 0.0000000000 0.2591870000 0.0018980000 141156835 0 402718720 3.9027323723 3.9547169209 3.9966201782 1617 1311867772.5713028908 0.0881904215 0.1276310827 0.2390826792 0.0048842822 0.7387060000 0.0812300000 0.0977160000 0.0310970000 0.2587630000 0.2659320000 141160563 0 402718720 3.9042172432 3.9545674324 3.9961411953 1618 1311867772.6077790260 0.0886694118 0.1276070026 0.2390826792 0.0048842281 0.4385500000 0.0810740000 0.0928820000 0.0000000000 0.2589820000 0.0017990000 141164291 0 402718720 3.9031867981 3.9549605846 3.9965996742 1619 1311867772.6382429600 0.0893792659 0.1275833907 0.2390826792 0.0048831753 0.4696730000 0.0814430000 0.0935570000 0.0310430000 0.2580540000 0.0018170000 141167907 0 402718720 3.9022104740 3.9549012184 3.9967932701 1620 1311867772.6695280075 0.0915823355 0.1275611678 0.2390826792 0.0048833060 0.3933470000 0.0811700000 0.0496940000 0.0000010000 0.2565770000 0.0019030000 141171579 0 402718720 3.9000735283 3.9528272152 3.9972190857 1621 1311867772.7066609859 0.0902643651 0.1275381593 0.2390826792 0.0048820518 0.7528770000 0.0997540000 0.0979280000 0.0310700000 0.2562490000 0.2640950000 141175363 0 402718720 3.9013197422 3.9528186321 3.9971716404 1622 1311867772.7385280132 0.0904279128 0.1275152800 0.2390826792 0.0048806108 0.4102070000 0.0816120000 0.0661720000 0.0000000000 0.2568390000 0.0018160000 141179035 0 402718720 3.9008941650 3.9533510208 3.9972498417 1623 1311867772.7712020874 0.0901201144 0.1274922392 0.2390826792 0.0048792782 0.5136790000 0.0891080000 0.1248200000 0.0378010000 0.2563710000 0.0018120000 141182763 0 402718720 3.9012463093 3.9528622627 3.9976727962 1624 1311867772.8056819439 0.0883032903 0.1274681081 0.2390826792 0.0048780090 0.4367090000 0.0817380000 0.0940160000 0.0000010000 0.2553470000 0.0018180000 141186547 0 402718720 3.9031226635 3.9523627758 3.9975926876 1625 1311867772.8384070396 0.0905630365 0.1274453972 0.2390826792 0.0048788431 0.7108860000 0.0807240000 0.0789150000 0.0310480000 0.2545800000 0.2618560000 141190163 0 402718720 3.9006695747 3.9531304836 3.9984164238 1626 1311867772.8747529984 0.0902298167 0.1274225094 0.2390826792 0.0048774788 0.4612270000 0.1066030000 0.0941240000 0.0000010000 0.2548980000 0.0018160000 141194003 0 402718720 3.9014146328 3.9522311687 3.9987900257 1627 1311867772.9054989815 0.0900574327 0.1273995438 0.2390826792 0.0048767824 0.4659650000 0.0819280000 0.0940550000 0.0310110000 0.2533700000 0.0018090000 141197619 0 402718720 3.9020810127 3.9507043362 3.9987883568 1628 1311867772.9415910244 0.0890157446 0.1273759665 0.2390826792 0.0048763900 0.4122630000 0.0820770000 0.0711250000 0.0000010000 0.2534510000 0.0018080000 141201347 0 402718720 3.9030771255 3.9519646168 3.9988586903 1629 1311867772.9716000557 0.0876816064 0.1273515992 0.2390826792 0.0048750553 0.7396690000 0.0946350000 0.0994720000 0.0310900000 0.2514040000 0.2592550000 141204963 0 402718720 3.9046173096 3.9523622990 3.9986543655 1630 1311867773.0115981102 0.0887424722 0.1273279126 0.2390826792 0.0048741815 0.4063410000 0.0822720000 0.0668350000 0.0000010000 0.2516150000 0.0018060000 141208803 0 402718720 3.9043390751 3.9506199360 3.9989686012 1631 1311867773.0406711102 0.0903669968 0.1273052511 0.2390826792 0.0048748752 0.4840900000 0.1025770000 0.0947900000 0.0310510000 0.2500930000 0.0018200000 141212419 0 402718720 3.9026448727 3.9513409138 3.9994635582 1632 1311867773.0706710815 0.0905307978 0.1272827178 0.2390826792 0.0048735398 0.4053030000 0.0824740000 0.0670300000 0.0000010000 0.2501480000 0.0018160000 141215979 0 402718720 3.9026405811 3.9516484737 3.9998545647 1633 1311867773.1044468880 0.0912267864 0.1272606382 0.2390826792 0.0048735888 0.6887730000 0.0823080000 0.0666270000 0.0310440000 0.2483310000 0.2567040000 141219707 0 402718720 3.9027795792 3.9493486881 4.0000405312 1634 1311867773.1367809772 0.0918421596 0.1272389623 0.2390826792 0.0048725551 0.4543970000 0.1005420000 0.0847130000 0.0000010000 0.2625130000 0.0024660000 141223379 0 402718720 3.9030237198 3.9476647377 4.0004501343 1635 1311867773.1702499390 0.0910120383 0.1272168051 0.2390826792 0.0048712440 0.4211500000 0.0821370000 0.0557520000 0.0310760000 0.2466280000 0.0018160000 141227107 0 402718720 3.9038980007 3.9483418465 4.0005865097 1636 1311867773.2047750950 0.0910527483 0.1271947000 0.2390826792 0.0048698071 0.3943380000 0.0923910000 0.0504740000 0.0000010000 0.2455990000 0.0019070000 141230835 0 402718720 3.9037702084 3.9487719536 4.0007410049 1637 1311867773.2366468906 0.0919312164 0.1271731584 0.2390826792 0.0048687370 0.6742760000 0.0821610000 0.0587310000 0.0311530000 0.2449940000 0.2534690000 141234507 0 402718720 3.9033300877 3.9484765530 4.0015177727 1638 1311867773.2714850903 0.0910217762 0.1271510880 0.2390826792 0.0048675858 0.4290380000 0.0826810000 0.0955150000 0.0000010000 0.2452880000 0.0018000000 141238291 0 402718720 3.9043452740 3.9487903118 4.0018429756 1639 1311867773.3104391098 0.0902472436 0.1271285719 0.2390826792 0.0048665325 0.4564280000 0.0823830000 0.0950930000 0.0310920000 0.2422940000 0.0018130000 141242131 0 402718720 3.9055442810 3.9488468170 4.0022420883 1640 1311867773.3365778923 0.0968602523 0.1271101156 0.2390826792 0.0048673940 0.3854120000 0.0809910000 0.0557430000 0.0000010000 0.2430870000 0.0018070000 141245579 0 402718720 3.8991622925 3.9473416805 4.0034770966 1641 1311867773.3720550537 0.0952477604 0.1270906992 0.2390826792 0.0048670378 0.7332940000 0.1160900000 0.0893790000 0.0310670000 0.2419150000 0.2510550000 141249363 0 402718720 3.9011220932 3.9470582008 4.0035772324 1642 1311867773.4075679779 0.0941860899 0.1270706598 0.2390826792 0.0048661744 0.4274150000 0.0827090000 0.0983480000 0.0000010000 0.2407770000 0.0018030000 141253091 0 402718720 3.9023914337 3.9474473000 4.0035853386 1643 1311867773.4431231022 0.0944210589 0.1270507879 0.2390826792 0.0048667375 0.4537260000 0.0827140000 0.0957320000 0.0306210000 0.2390960000 0.0018120000 141256875 0 402718720 3.9022641182 3.9480125904 4.0044126511 1644 1311867773.4752271175 0.0959272683 0.1270318563 0.2390826792 0.0048660397 0.4290330000 0.0828040000 0.1008990000 0.0000010000 0.2397670000 0.0018040000 141260547 0 402718720 3.9012234211 3.9467189312 4.0047469139 1645 1311867773.5056390762 0.0952838585 0.1270125566 0.2390826792 0.0048648146 0.6955230000 0.0810670000 0.0953010000 0.0310200000 0.2375070000 0.2469080000 141264163 0 402718720 3.9024026394 3.9466550350 4.0052561760 1646 1311867773.5412580967 0.0943095386 0.1269926884 0.2390826792 0.0048638136 0.3885320000 0.0941620000 0.0510110000 0.0000010000 0.2377630000 0.0018030000 141267947 0 402718720 3.9034259319 3.9478483200 4.0055489540 1647 1311867773.5752460957 0.0954358950 0.1269735283 0.2390826792 0.0048631581 0.4070910000 0.0813260000 0.0537350000 0.0309050000 0.2355680000 0.0017710000 141271675 0 402718720 3.9029662609 3.9459271431 4.0058507919 1648 1311867773.6103789806 0.0943145752 0.1269537110 0.2390826792 0.0048617644 0.4175750000 0.0811180000 0.0949330000 0.0000000000 0.2359200000 0.0018120000 141275459 0 402718720 3.9045169353 3.9459500313 4.0060348511 1649 1311867773.6384060383 0.0915547237 0.1269322440 0.2390826792 0.0048625365 0.6461770000 0.0827520000 0.0484830000 0.0311430000 0.2351610000 0.2448250000 141278963 0 402718720 3.9072673321 3.9477174282 4.0060162544 1650 1311867773.6767098904 0.0930518433 0.1269117104 0.2390826792 0.0048650651 0.4204370000 0.0828460000 0.0962890000 0.0000000000 0.2357180000 0.0018000000 141282803 0 402718720 3.9058008194 3.9475913048 4.0064525604 1651 1311867773.7092239857 0.0950959101 0.1268924398 0.2390826792 0.0048643256 0.4415150000 0.0913200000 0.0800720000 0.0311310000 0.2333760000 0.0018040000 141286475 0 402718720 3.9047911167 3.9453692436 4.0070958138 1652 1311867773.7367770672 0.0920363739 0.1268713405 0.2390826792 0.0048638839 0.3782400000 0.0811520000 0.0589470000 0.0000000000 0.2322930000 0.0018510000 141289979 0 402718720 3.9071106911 3.9481415749 4.0072264671 1653 1311867773.7767388821 0.0928783193 0.1268507761 0.2390826792 0.0048637253 0.6803280000 0.1030220000 0.0679020000 0.0306800000 0.2324080000 0.2425320000 141293875 0 402718720 3.9071307182 3.9470167160 4.0078907013 1654 1311867773.8052179813 0.0929085314 0.1268302548 0.2390826792 0.0048640050 0.4275330000 0.0815780000 0.0992970000 0.0000000000 0.2399890000 0.0024750000 141297435 0 402718720 3.9073295593 3.9461069107 4.0081191063 1655 1311867773.8394160271 0.0926201493 0.1268095840 0.2390826792 0.0048632862 0.4342480000 0.1056880000 0.0594790000 0.0310590000 0.2323760000 0.0018100000 141301163 0 402718720 3.9078710079 3.9449567795 4.0081329346 1656 1311867773.8739800453 0.0922482163 0.1267887136 0.2390826792 0.0048622568 0.3985030000 0.0957830000 0.0646100000 0.0000000000 0.2324980000 0.0017990000 141304891 0 402718720 3.9077847004 3.9453785419 4.0084939003 1657 1311867773.9096889496 0.0905799270 0.1267668616 0.2390826792 0.0048614236 0.6880950000 0.0830930000 0.0963790000 0.0311160000 0.2316740000 0.2419920000 141308675 0 402718720 3.9097318649 3.9451794624 4.0084910393 1658 1311867773.9369859695 0.0924760625 0.1267461796 0.2390826792 0.0048605401 0.4174510000 0.0830290000 0.0962380000 0.0000010000 0.2325850000 0.0018030000 141312179 0 402718720 3.9077074528 3.9446506500 4.0085268021 1659 1311867773.9740200043 0.0898302346 0.1267239276 0.2390826792 0.0048596758 0.4152280000 0.0830120000 0.0646820000 0.0311540000 0.2307730000 0.0018040000 141316019 0 402718720 3.9105598927 3.9450738430 4.0086350441 1660 1311867774.0073120594 0.0890213028 0.1267012152 0.2390826792 0.0048592656 0.4164430000 0.0829980000 0.0965920000 0.0000010000 0.2312360000 0.0018000000 141319691 0 402718720 3.9117543697 3.9449987411 4.0087451935 1661 1311867774.0389740467 0.0898835734 0.1266790493 0.2390826792 0.0048603474 0.6632420000 0.0832520000 0.0762000000 0.0306790000 0.2294240000 0.2398850000 141323419 0 402718720 3.9112110138 3.9439420700 4.0090208054 1662 1311867774.0735630989 0.0909952149 0.1266575788 0.2390826792 0.0048610292 0.4051880000 0.0831540000 0.0868240000 0.0000010000 0.2296060000 0.0018070000 141327147 0 402718720 3.9105966091 3.9439845085 4.0096335411 1663 1311867774.1093399525 0.0892670229 0.1266350950 0.2390826792 0.0048642302 0.4337130000 0.0830490000 0.0849090000 0.0311430000 0.2289980000 0.0018070000 141330931 0 402718720 3.9118831158 3.9454319477 4.0095329285 1664 1311867774.1424911022 0.0900548548 0.1266131117 0.2390826792 0.0048645673 0.3831670000 0.0829990000 0.0648560000 0.0000010000 0.2296570000 0.0017970000 141334659 0 402718720 3.9116141796 3.9443206787 4.0098991394 1665 1311867774.1754300594 0.0898968130 0.1265910599 0.2390826792 0.0048651863 0.6771800000 0.1021340000 0.0726900000 0.0311930000 0.2283190000 0.2390190000 141338331 0 402718720 3.9116559029 3.9446659088 4.0100812912 1666 1311867774.2059481144 0.0881159827 0.1265679656 0.2390826792 0.0048640999 0.3823930000 0.0829470000 0.0653550000 0.0000010000 0.2284800000 0.0017960000 141342003 0 402718720 3.9130768776 3.9467890263 4.0104088783 1667 1311867774.2384989262 0.0876939967 0.1265446459 0.2390826792 0.0048629772 0.4473240000 0.0830840000 0.1016010000 0.0307330000 0.2262880000 0.0018130000 141345619 0 402718720 3.9135913849 3.9468429089 4.0105504990 1668 1311867774.2744109631 0.0880454406 0.1265215648 0.2390826792 0.0048618221 0.4163990000 0.0833220000 0.1017190000 0.0000010000 0.2254830000 0.0019060000 141349459 0 402718720 3.9138906002 3.9454667568 4.0109000206 1669 1311867774.3046739101 0.0876930133 0.1264983003 0.2390826792 0.0048616423 0.6543050000 0.0827920000 0.0765320000 0.0311920000 0.2238240000 0.2361330000 141353075 0 402718720 3.9134879112 3.9476151466 4.0112347603 1670 1311867774.3375370502 0.0856238678 0.1264738246 0.2390826792 0.0048605872 0.3955640000 0.0829130000 0.0808810000 0.0000010000 0.2261620000 0.0017990000 141356747 0 402718720 3.9152364731 3.9493284225 4.0114541054 1671 1311867774.3727159500 0.0859751478 0.1264495884 0.2390826792 0.0048592671 0.4239530000 0.0973190000 0.0646460000 0.0311730000 0.2252140000 0.0018070000 141360475 0 402718720 3.9155151844 3.9481394291 4.0117349625 1672 1311867774.4051818848 0.0861596465 0.1264254915 0.2390826792 0.0048593259 0.4148400000 0.0830170000 0.1019620000 0.0000000000 0.2239620000 0.0018930000 141364203 0 402718720 3.9156522751 3.9480407238 4.0124306679 1673 1311867774.4376831055 0.0837586597 0.1263999883 0.2390826792 0.0048579602 0.6787290000 0.0829020000 0.1020060000 0.0312300000 0.2236590000 0.2351230000 141367875 0 402718720 3.9173874855 3.9502649307 4.0121684074 1674 1311867774.4740140438 0.0858419314 0.1263757601 0.2390826792 0.0048571183 0.3941140000 0.0832710000 0.0809120000 0.0000010000 0.2242800000 0.0017910000 141371659 0 402718720 3.9161646366 3.9480113983 4.0131802559 1675 1311867774.5066258907 0.0863260403 0.1263518498 0.2390826792 0.0048557277 0.4477840000 0.0942260000 0.0949010000 0.0311480000 0.2219020000 0.0017600000 141375387 0 402718720 3.9159164429 3.9469890594 4.0133962631 1676 1311867774.5394051075 0.0838474929 0.1263264892 0.2390826792 0.0048547918 0.4215920000 0.0930120000 0.1019860000 0.0000010000 0.2207350000 0.0018810000 141379059 0 402718720 3.9176437855 3.9489114285 4.0131573677 1677 1311867774.5727870464 0.0839384869 0.1263012131 0.2390826792 0.0048539276 0.6610510000 0.1052840000 0.0648900000 0.0311900000 0.2221030000 0.2337890000 141382731 0 402718720 3.9177320004 3.9489221573 4.0136260986 1678 1311867774.6076970100 0.0844640583 0.1262762804 0.2390826792 0.0048527662 0.3689770000 0.0813960000 0.0592640000 0.0000000000 0.2226600000 0.0017940000 141386515 0 402718720 3.9174757004 3.9487657547 4.0141677856 1679 1311867774.6373310089 0.0834108517 0.1262507501 0.2390826792 0.0048518178 0.4092120000 0.0828990000 0.0682990000 0.0312230000 0.2211770000 0.0017950000 141390131 0 402718720 3.9183545113 3.9498798847 4.0143804550 1680 1311867774.6731650829 0.0822322741 0.1262245486 0.2390826792 0.0048504435 0.4081340000 0.0829310000 0.0972080000 0.0000010000 0.2223290000 0.0017850000 141393859 0 402718720 3.9191660881 3.9507946968 4.0145449638 1681 1311867774.7048470974 0.0837518424 0.1261992823 0.2390826792 0.0048493889 0.6991820000 0.1098440000 0.1020930000 0.0308290000 0.2201140000 0.2324600000 141397587 0 402718720 3.9191153049 3.9489362240 4.0154547691 1682 1311867774.7448370457 0.0842927396 0.1261743675 0.2390826792 0.0048514224 0.3682580000 0.0831030000 0.0601370000 0.0000010000 0.2193440000 0.0017990000 141401483 0 402718720 3.9184699059 3.9502427578 4.0159182549 1683 1311867774.7731618881 0.0830446333 0.1261487408 0.2390826792 0.0048502463 0.4346300000 0.0814790000 0.0964150000 0.0310870000 0.2200130000 0.0018000000 141404987 0 402718720 3.9196920395 3.9511306286 4.0161218643 1684 1311867774.8052101135 0.0834519863 0.1261233865 0.2390826792 0.0048498780 0.4086300000 0.0831180000 0.0988110000 0.0000010000 0.2210470000 0.0017890000 141408715 0 402718720 3.9203689098 3.9495420456 4.0170111656 1685 1311867774.8443410397 0.0838191360 0.1260982801 0.2390826792 0.0048484461 0.6650860000 0.0830740000 0.0973460000 0.0313110000 0.2184100000 0.2311080000 141412555 0 402718720 3.9201846123 3.9496209621 4.0175175667 1686 1311867774.8735189438 0.0843929201 0.1260735438 0.2390826792 0.0048474886 0.4016170000 0.0953620000 0.0816250000 0.0000000000 0.2189960000 0.0017890000 141416171 0 402718720 3.9201920033 3.9491155148 4.0182137489 1687 1311867774.9063620567 0.0844482630 0.1260488697 0.2390826792 0.0048469088 0.4006520000 0.0947680000 0.0491700000 0.0312820000 0.2187610000 0.0024810000 141419843 0 402718720 3.9208736420 3.9481279850 4.0185265541 1688 1311867774.9433379173 0.0848464295 0.1260244606 0.2390826792 0.0048455454 0.4213250000 0.1059990000 0.0929090000 0.0000010000 0.2167010000 0.0018030000 141423683 0 402718720 3.9208576679 3.9482572079 4.0191254616 1689 1311867774.9730870724 0.0841523260 0.1259996696 0.2390826792 0.0048441750 0.6368320000 0.0983200000 0.0603430000 0.0313450000 0.2143130000 0.2286690000 141427243 0 402718720 3.9213871956 3.9490723610 4.0189623833 1690 1311867775.0104990005 0.0852340311 0.1259755479 0.2390826792 0.0048427826 0.4042130000 0.0829570000 0.0993590000 0.0000010000 0.2162380000 0.0018020000 141431139 0 402718720 3.9209692478 3.9482493401 4.0195846558 1691 1311867775.0417571068 0.0846313387 0.1259510983 0.2390826792 0.0048413686 0.3855950000 0.0838760000 0.0492610000 0.0308520000 0.2159280000 0.0017990000 141434755 0 402718720 3.9212296009 3.9491026402 4.0196504593 1692 1311867775.0737869740 0.0841315165 0.1259263823 0.2390826792 0.0048402801 0.4029210000 0.0831110000 0.0976880000 0.0000010000 0.2165030000 0.0017950000 141438427 0 402718720 3.9217219353 3.9499943256 4.0198912621 1693 1311867775.1060369015 0.0843731984 0.1259018381 0.2390826792 0.0048390072 0.6610320000 0.0832270000 0.1027360000 0.0313570000 0.2133550000 0.2263380000 141442099 0 402718720 3.9218380451 3.9496140480 4.0202465057 1694 1311867775.1426749229 0.0856703594 0.1258780887 0.2390826792 0.0048377841 0.3648770000 0.0833810000 0.0602520000 0.0000010000 0.2155440000 0.0017950000 141445883 0 402718720 3.9215416908 3.9479823112 4.0207619667 1695 1311867775.1733469963 0.0845876858 0.1258537286 0.2390826792 0.0048364534 0.3979940000 0.0813710000 0.0647680000 0.0311080000 0.2151030000 0.0017990000 141449499 0 402718720 3.9227452278 3.9485044479 4.0210742950 1696 1311867775.2047309875 0.0848915130 0.1258295764 0.2390826792 0.0048350556 0.3658640000 0.0951340000 0.0492580000 0.0000010000 0.2158030000 0.0017910000 141453227 0 402718720 3.9220550060 3.9487352371 4.0206837654 1697 1311867775.2407341003 0.0835981891 0.1258046905 0.2390826792 0.0048345509 0.6184000000 0.0830110000 0.0573440000 0.0313020000 0.2148290000 0.2280490000 141457011 0 402718720 3.9227311611 3.9502434731 4.0204286575 1698 1311867775.2726259232 0.0842720270 0.1257802307 0.2390826792 0.0048334222 0.3903050000 0.0958890000 0.0735600000 0.0000010000 0.2152260000 0.0018000000 141460627 0 402718720 3.9225590229 3.9498267174 4.0215044022 1699 1311867775.3058989048 0.0846792981 0.1257560395 0.2390826792 0.0048326074 0.3964940000 0.0959820000 0.0492620000 0.0313920000 0.2141810000 0.0018010000 141464355 0 402718720 3.9229774475 3.9484994411 4.0216727257 1700 1311867775.3405869007 0.0846478119 0.1257318582 0.2390826792 0.0048338741 0.4045480000 0.0826590000 0.0980120000 0.0000000000 0.2171210000 0.0024750000 141468139 0 402718720 3.9224362373 3.9500994682 4.0216341019 1701 1311867775.3728890419 0.0845937654 0.1257076735 0.2390826792 0.0048336076 0.7114060000 0.1052500000 0.1301650000 0.0314140000 0.2136300000 0.2270600000 141471867 0 402718720 3.9222698212 3.9504551888 4.0216741562 1702 1311867775.4055740833 0.0867412090 0.1256847790 0.2390826792 0.0048330570 0.3701360000 0.0830650000 0.0690210000 0.0000000000 0.2120890000 0.0018940000 141475539 0 402718720 3.9220523834 3.9479887486 4.0235166550 1703 1311867775.4408710003 0.0860432535 0.1256615015 0.2390826792 0.0048333314 0.4093080000 0.0827730000 0.0757770000 0.0314040000 0.2136740000 0.0017970000 141479323 0 402718720 3.9221844673 3.9493772984 4.0228757858 1704 1311867775.4725620747 0.0853734463 0.1256378583 0.2390826792 0.0048325032 0.3909120000 0.0810760000 0.0895700000 0.0000010000 0.2145370000 0.0017830000 141482939 0 402718720 3.9227325916 3.9498546124 4.0232148170 1705 1311867775.5057229996 0.0857606083 0.1256144699 0.2390826792 0.0048311959 0.6333080000 0.0826730000 0.0736900000 0.0315290000 0.2137060000 0.2278330000 141486723 0 402718720 3.9233274460 3.9491491318 4.0242319107 1706 1311867775.5413000584 0.0851260722 0.1255907369 0.2390826792 0.0048311249 0.4176800000 0.0956290000 0.1031750000 0.0000010000 0.2131960000 0.0017930000 141490507 0 402718720 3.9243717194 3.9488046169 4.0244293213 1707 1311867775.5736858845 0.0850019231 0.1255669591 0.2390826792 0.0048301649 0.4288300000 0.0810440000 0.0972130000 0.0312580000 0.2136230000 0.0017950000 141494123 0 402718720 3.9240567684 3.9498119354 4.0244174004 1708 1311867775.6086819172 0.0853405446 0.1255434073 0.2390826792 0.0048288641 0.4055970000 0.0824510000 0.1030410000 0.0000000000 0.2144100000 0.0017910000 141497851 0 402718720 3.9246566296 3.9492807388 4.0252399445 1709 1311867775.6414420605 0.0851516053 0.1255197726 0.2390826792 0.0048275835 0.6234140000 0.0819540000 0.0655010000 0.0314890000 0.2131060000 0.2274590000 141501635 0 402718720 3.9256963730 3.9487078190 4.0255484581 1710 1311867775.6726739407 0.0860232338 0.1254966752 0.2390826792 0.0048275061 0.3679370000 0.0821280000 0.0657830000 0.0000010000 0.2143270000 0.0017990000 141505195 0 402718720 3.9237332344 3.9499993324 4.0254106522 1711 1311867775.7051100731 0.0862307847 0.1254737261 0.2390826792 0.0048261864 0.4427550000 0.0950330000 0.0978470000 0.0314780000 0.2126840000 0.0017990000 141508923 0 402718720 3.9236328602 3.9500246048 4.0255498886 1712 1311867775.7416241169 0.0870576203 0.1254512868 0.2390826792 0.0048248546 0.4031430000 0.0821330000 0.1030700000 0.0000010000 0.2122240000 0.0017890000 141512707 0 402718720 3.9235761166 3.9492995739 4.0264225006 1713 1311867775.7742578983 0.0871558487 0.1254289310 0.2390826792 0.0048245498 0.6152800000 0.0820430000 0.0574270000 0.0315100000 0.2128090000 0.2276310000 141516379 0 402718720 3.9236791134 3.9495728016 4.0269808769 1714 1311867775.8062939644 0.0867135674 0.1254063433 0.2390826792 0.0048243406 0.3996260000 0.0817680000 0.0980010000 0.0000010000 0.2141690000 0.0017840000 141520051 0 402718720 3.9236414433 3.9508886337 4.0269532204 1715 1311867775.8408269882 0.0878134146 0.1253844232 0.2390826792 0.0048231580 0.4060340000 0.0818030000 0.0735520000 0.0315110000 0.2135320000 0.0017990000 141523835 0 402718720 3.9234724045 3.9499008656 4.0275592804 1716 1311867775.8729701042 0.0888748392 0.1253631472 0.2390826792 0.0048222217 0.3679800000 0.0818980000 0.0658590000 0.0000010000 0.2145180000 0.0017930000 141527451 0 402718720 3.9225947857 3.9499349594 4.0283541679 1717 1311867775.9066479206 0.0891990960 0.1253420849 0.2390826792 0.0048208515 0.6342410000 0.0817490000 0.0736650000 0.0315320000 0.2138930000 0.2294810000 141531235 0 402718720 3.9221544266 3.9499964714 4.0282993317 1718 1311867775.9435749054 0.0891484246 0.1253210175 0.2390826792 0.0048196415 0.4003100000 0.0818530000 0.0981750000 0.0000010000 0.2145780000 0.0017850000 141534963 0 402718720 3.9226028919 3.9499847889 4.0287733078 1719 1311867775.9730579853 0.0900909975 0.1253005230 0.2390826792 0.0048183306 0.3974770000 0.0815820000 0.0657620000 0.0316170000 0.2127860000 0.0018000000 141538579 0 402718720 3.9216783047 3.9503076077 4.0291333199 1720 1311867776.0135231018 0.0910652503 0.1252806188 0.2390826792 0.0048175157 0.3898850000 0.0805870000 0.0899290000 0.0000010000 0.2133880000 0.0017880000 141542475 0 402718720 3.9222624302 3.9483737946 4.0299129486 1721 1311867776.0423479080 0.0907899886 0.1252605778 0.2390826792 0.0048165703 0.6187020000 0.0819650000 0.0605880000 0.0316130000 0.2125530000 0.2281090000 141545979 0 402718720 3.9223897457 3.9488279819 4.0298075676 1722 1311867776.0782909393 0.0908754244 0.1252406096 0.2390826792 0.0048152228 0.4098210000 0.0929090000 0.0980250000 0.0000010000 0.2131910000 0.0017840000 141549819 0 402718720 3.9221866131 3.9492599964 4.0297465324 1723 1311867776.1090068817 0.0906051323 0.1252205078 0.2390826792 0.0048140107 0.3890420000 0.0814310000 0.0574500000 0.0310880000 0.2133410000 0.0017940000 141553491 0 402718720 3.9222996235 3.9500219822 4.0297541618 1724 1311867776.1410119534 0.0917270184 0.1252010800 0.2390826792 0.0048127384 0.3986910000 0.0816740000 0.0973210000 0.0000010000 0.2140660000 0.0017480000 141557163 0 402718720 3.9217720032 3.9493737221 4.0306024551 1725 1311867776.1773319244 0.0921273604 0.1251819068 0.2390826792 0.0048114432 0.6564720000 0.0818330000 0.0979100000 0.0316430000 0.2127070000 0.2284690000 141560947 0 402718720 3.9215412140 3.9491353035 4.0307469368 1726 1311867776.2094259262 0.0907515958 0.1251619588 0.2390826792 0.0048102392 0.3989550000 0.0818900000 0.0981040000 0.0000010000 0.2132260000 0.0017920000 141564619 0 402718720 3.9226384163 3.9503884315 4.0304794312 1727 1311867776.2407069206 0.0915822014 0.1251425148 0.2390826792 0.0048090375 0.3973660000 0.0814960000 0.0654720000 0.0316620000 0.2130280000 0.0017960000 141568291 0 402718720 3.9218273163 3.9502487183 4.0307855606 1728 1311867776.2753469944 0.0923081860 0.1251235135 0.2390826792 0.0048077579 0.3600650000 0.0816170000 0.0604140000 0.0000010000 0.2119750000 0.0018870000 141572075 0 402718720 3.9211142063 3.9503822327 4.0311107635 1729 1311867776.3120670319 0.0931965038 0.1251050479 0.2390826792 0.0048063988 0.6117960000 0.0816060000 0.0518900000 0.0316660000 0.2132190000 0.2295010000 141575803 0 402718720 3.9206526279 3.9498784542 4.0313596725 1730 1311867776.3407590389 0.0925901532 0.1250862531 0.2390826792 0.0048051946 0.3428810000 0.0813230000 0.0433730000 0.0000010000 0.2124800000 0.0017830000 141579475 0 402718720 3.9210686684 3.9505665302 4.0313944817 1731 1311867776.3730750084 0.0920614898 0.1250671747 0.2390826792 0.0048038416 0.4038060000 0.0923890000 0.0603020000 0.0317050000 0.2137050000 0.0017920000 141583147 0 402718720 3.9221403599 3.9504101276 4.0318078995 1732 1311867776.4097070694 0.0932427347 0.1250488003 0.2390826792 0.0048030708 0.3500550000 0.0797720000 0.0512430000 0.0000010000 0.2130600000 0.0018440000 141586987 0 402718720 3.9211628437 3.9501357079 4.0323071480 1733 1311867776.4422268867 0.0934256762 0.1250305527 0.2390826792 0.0048022422 0.6431710000 0.0797770000 0.0834270000 0.0317200000 0.2137400000 0.2305590000 141590659 0 402718720 3.9206418991 3.9508967400 4.0323042870 1734 1311867776.4727520943 0.0929025486 0.1250120244 0.2390826792 0.0048010203 0.3878690000 0.0812540000 0.0860090000 0.0000010000 0.2148740000 0.0017840000 141594275 0 402718720 3.9214863777 3.9508771896 4.0324940681 1735 1311867776.5105879307 0.0923154280 0.1249931791 0.2390826792 0.0047999816 0.3975890000 0.0810880000 0.0654240000 0.0317440000 0.2135820000 0.0017930000 141598115 0 402718720 3.9220004082 3.9515945911 4.0327339172 1736 1311867776.5415630341 0.0917755738 0.1249740446 0.2390826792 0.0047987567 0.3866880000 0.0986840000 0.0688040000 0.0000000000 0.2131110000 0.0018760000 141601731 0 402718720 3.9229295254 3.9516241550 4.0331311226 1737 1311867776.5743160248 0.0924088135 0.1249552966 0.2390826792 0.0047975896 0.6169110000 0.0809940000 0.0603350000 0.0317420000 0.2114400000 0.2284840000 141605459 0 402718720 3.9228725433 3.9512388706 4.0340003967 1738 1311867776.6094930172 0.0927670598 0.1249367763 0.2390826792 0.0047963858 0.4266690000 0.1051580000 0.1030560000 0.0000010000 0.2126860000 0.0017830000 141609243 0 402718720 3.9222292900 3.9518277645 4.0343241692 1739 1311867776.6413109303 0.0919570848 0.1249178116 0.2390826792 0.0047952782 0.4348380000 0.0809410000 0.1030140000 0.0317970000 0.2133430000 0.0018010000 141612915 0 402718720 3.9234709740 3.9518892765 4.0346169472 1740 1311867776.6763460636 0.0920841694 0.1248989417 0.2390826792 0.0047943066 0.3497560000 0.0807950000 0.0494210000 0.0000010000 0.2137930000 0.0017910000 141616755 0 402718720 3.9234340191 3.9523887634 4.0354213715 1741 1311867776.7134280205 0.0920404419 0.1248800683 0.2390826792 0.0047931623 0.6624970000 0.0903210000 0.0945420000 0.0317910000 0.2115940000 0.2303420000 141620539 0 402718720 3.9231138229 3.9533154964 4.0356740952 1742 1311867776.7423970699 0.0924489722 0.1248614512 0.2390826792 0.0047918661 0.3985430000 0.0801670000 0.0978640000 0.0000010000 0.2147620000 0.0017910000 141624099 0 402718720 3.9230303764 3.9532201290 4.0366220474 1743 1311867776.7739920616 0.0925709307 0.1248429253 0.2390826792 0.0047909717 0.3936280000 0.0930750000 0.0492340000 0.0318230000 0.2137200000 0.0017940000 141627883 0 402718720 3.9235205650 3.9529232979 4.0373125076 1744 1311867776.8117430210 0.0923886746 0.1248243162 0.2390826792 0.0047905690 0.3964860000 0.0800760000 0.0959010000 0.0000010000 0.2147320000 0.0017930000 141631779 0 402718720 3.9245762825 3.9528400898 4.0383410454 1745 1311867776.8449618816 0.0943697095 0.1248068637 0.2390826792 0.0047906639 0.6601760000 0.0800110000 0.0980830000 0.0318160000 0.2140960000 0.2322170000 141635563 0 402718720 3.9232511520 3.9521539211 4.0393385887 1746 1311867776.8748989105 0.0929123014 0.1247885965 0.2390826792 0.0047903306 0.4353050000 0.1155800000 0.0990230000 0.0000010000 0.2149020000 0.0018010000 141639179 0 402718720 3.9258849621 3.9518661499 4.0399494171 1747 1311867776.9104089737 0.0929537863 0.1247703740 0.2390826792 0.0047895795 0.4296150000 0.0798980000 0.0980800000 0.0318750000 0.2139950000 0.0017960000 141642963 0 402718720 3.9257116318 3.9523813725 4.0403189659 1748 1311867776.9465129375 0.0915241390 0.1247513544 0.2390826792 0.0047886831 0.4033510000 0.0796210000 0.1028660000 0.0000010000 0.2151190000 0.0017850000 141646803 0 402718720 3.9269964695 3.9531979561 4.0403237343 1749 1311867776.9780058861 0.0954488069 0.1247346005 0.2390826792 0.0047902527 0.6482130000 0.0784260000 0.0890420000 0.0317160000 0.2137480000 0.2312770000 141650475 0 402718720 3.9244713783 3.9510295391 4.0425786972 1750 1311867777.0103049278 0.0952742100 0.1247177660 0.2390826792 0.0047900507 0.3951570000 0.1070330000 0.0686530000 0.0000010000 0.2136640000 0.0017880000 141654259 0 402718720 3.9253799915 3.9508121014 4.0433464050 1751 1311867777.0430829525 0.0948300213 0.1247006970 0.2390826792 0.0047887292 0.4095960000 0.0909890000 0.0677410000 0.0319420000 0.2131430000 0.0017970000 141657987 0 402718720 3.9249377251 3.9515147209 4.0427136421 1752 1311867777.0763421059 0.0933572352 0.1246828069 0.2390826792 0.0047879885 0.4087020000 0.0914180000 0.0976980000 0.0000000000 0.2137880000 0.0017940000 141661715 0 402718720 3.9267792702 3.9516994953 4.0427289009 1753 1311867777.1087210178 0.0936850011 0.1246651242 0.2390826792 0.0047867023 0.6100560000 0.0802560000 0.0516090000 0.0319670000 0.2113540000 0.2309050000 141665443 0 402718720 3.9269177914 3.9513120651 4.0434036255 1754 1311867777.1435770988 0.0918554291 0.1246464186 0.2390826792 0.0047859621 0.3661120000 0.0798230000 0.0688200000 0.0000010000 0.2116290000 0.0017970000 141669283 0 402718720 3.9290907383 3.9518804550 4.0434460640 1755 1311867777.1783010960 0.0917851999 0.1246276942 0.2390826792 0.0047846036 0.4274150000 0.0795020000 0.0978580000 0.0319310000 0.2123700000 0.0017940000 141673067 0 402718720 3.9292550087 3.9523105621 4.0437307358 1756 1311867777.2115299702 0.0923464745 0.1246093108 0.2390826792 0.0047833401 0.4363260000 0.0803120000 0.1216620000 0.0000010000 0.2274950000 0.0024690000 141676907 0 402718720 3.9290821552 3.9520025253 4.0445327759 1757 1311867777.2420690060 0.0910235271 0.1245901954 0.2390826792 0.0047825347 0.6679380000 0.0924790000 0.0978800000 0.0314560000 0.2121310000 0.2300370000 141680467 0 402718720 3.9317836761 3.9516744614 4.0450987816 1758 1311867777.2766950130 0.0908701345 0.1245710145 0.2390826792 0.0047816599 0.3800410000 0.0797520000 0.0816900000 0.0000010000 0.2127540000 0.0017870000 141684251 0 402718720 3.9317455292 3.9519634247 4.0451564789 1759 1311867777.3093490601 0.0913526341 0.1245521297 0.2390826792 0.0047812931 0.4271610000 0.0794260000 0.0976470000 0.0319590000 0.2123370000 0.0017930000 141687979 0 402718720 3.9316546917 3.9516680241 4.0457272530 1760 1311867777.3419890404 0.0922322795 0.1245337661 0.2390826792 0.0047801289 0.4000610000 0.0794740000 0.1029530000 0.0000010000 0.2115550000 0.0018860000 141691707 0 402718720 3.9312205315 3.9507405758 4.0463843346 1761 1311867777.3780329227 0.0926343203 0.1245156518 0.2390826792 0.0047797914 0.6725770000 0.0911690000 0.1009700000 0.0319690000 0.2130510000 0.2314330000 141695603 0 402718720 3.9303691387 3.9509749413 4.0466465950 1762 1311867777.4108960629 0.0925684646 0.1244975205 0.2390826792 0.0047784411 0.4003800000 0.0794390000 0.1026880000 0.0000000000 0.2121540000 0.0018890000 141699331 0 402718720 3.9309325218 3.9507706165 4.0475034714 1763 1311867777.4411139488 0.0927029625 0.1244794862 0.2390826792 0.0047775946 0.3799010000 0.0795340000 0.0492780000 0.0320340000 0.2132450000 0.0017980000 141703003 0 402718720 3.9309406281 3.9502625465 4.0475826263 1764 1311867777.4770240784 0.0928652734 0.1244615643 0.2390826792 0.0047764641 0.3959330000 0.0793690000 0.0975930000 0.0000000000 0.2131580000 0.0018050000 141706899 0 402718720 3.9318957329 3.9496269226 4.0489788055 1765 1311867777.5098700523 0.0904447436 0.1244422913 0.2390826792 0.0047762254 0.6422170000 0.0791160000 0.0818440000 0.0320170000 0.2133680000 0.2318750000 141710627 0 402718720 3.9339997768 3.9505817890 4.0483140945 1766 1311867777.5421240330 0.0905547962 0.1244231025 0.2390826792 0.0047755103 0.4196680000 0.0965550000 0.1030430000 0.0000010000 0.2142730000 0.0017900000 141714299 0 402718720 3.9331774712 3.9512624741 4.0486783981 1767 1311867777.5777161121 0.0909121111 0.1244041376 0.2390826792 0.0047742805 0.4158090000 0.0792390000 0.0856780000 0.0320030000 0.2130620000 0.0017980000 141718195 0 402718720 3.9337413311 3.9505748749 4.0499806404 1768 1311867777.6086440086 0.0894102976 0.1243843447 0.2390826792 0.0047730162 0.4089230000 0.0788470000 0.1013560000 0.0000000000 0.2217540000 0.0024670000 141721867 0 402718720 3.9352405071 3.9510769844 4.0499567986 1769 1311867777.6407959461 0.0924189314 0.1243662749 0.2390826792 0.0047742088 0.7249950000 0.1007170000 0.1286190000 0.0396020000 0.2204790000 0.2315510000 141725651 0 402718720 3.9326503277 3.9497442245 4.0519351959 1770 1311867777.6765840054 0.0892445520 0.1243464321 0.2390826792 0.0047748759 0.3862210000 0.0919200000 0.0737410000 0.0000000000 0.2147230000 0.0017840000 141729491 0 402718720 3.9356818199 3.9507529736 4.0513720512 1771 1311867777.7086570263 0.0879917145 0.1243259043 0.2390826792 0.0047744305 0.4448360000 0.0908730000 0.1026580000 0.0320520000 0.2134290000 0.0017980000 141733163 0 402718720 3.9375283718 3.9507398605 4.0515751839 1772 1311867777.7411170006 0.0914558321 0.1243073546 0.2390826792 0.0047757858 0.3971980000 0.0789640000 0.0987720000 0.0000010000 0.2136560000 0.0017860000 141736891 0 402718720 3.9343962669 3.9492890835 4.0532994270 1773 1311867777.7797420025 0.0909299254 0.1242885292 0.2390826792 0.0047744904 0.6175920000 0.0792750000 0.0572950000 0.0320880000 0.2133870000 0.2314960000 141740843 0 402718720 3.9350035191 3.9493088722 4.0535259247 1774 1311867777.8103909492 0.0883972719 0.1242682974 0.2390826792 0.0047769063 0.3948350000 0.0775890000 0.0969700000 0.0000010000 0.2145150000 0.0017470000 141744571 0 402718720 3.9390094280 3.9495704174 4.0537867546 1775 1311867777.8421120644 0.0891461149 0.1242485103 0.2390826792 0.0047768053 0.4287390000 0.0787960000 0.0983700000 0.0320930000 0.2136550000 0.0017970000 141748243 0 402718720 3.9366593361 3.9505555630 4.0537967682 1776 1311867777.8771729469 0.0907353833 0.1242296403 0.2390826792 0.0047759517 0.4193020000 0.0951820000 0.1033590000 0.0000000000 0.2149130000 0.0017910000 141752083 0 402718720 3.9352633953 3.9498877525 4.0547800064 1777 1311867777.9091188908 0.0917823166 0.1242113807 0.2390826792 0.0047749206 0.6623910000 0.0785720000 0.1032340000 0.0321570000 0.2122760000 0.2321510000 141755811 0 402718720 3.9341268539 3.9493904114 4.0555477142 1778 1311867777.9424149990 0.0893822014 0.1241917917 0.2390826792 0.0047752136 0.3961660000 0.0785440000 0.0982850000 0.0000000000 0.2134770000 0.0017870000 141759539 0 402718720 3.9379291534 3.9497914314 4.0559358597 1779 1311867777.9770610332 0.0915746242 0.1241734571 0.2390826792 0.0047803566 0.4119140000 0.0779960000 0.0825920000 0.0320700000 0.2134120000 0.0017980000 141763435 0 402718720 3.9334673882 3.9505198002 4.0561513901 1780 1311867778.0100560188 0.0936602503 0.1241563149 0.2390826792 0.0047818180 0.4002720000 0.0785800000 0.1030000000 0.0000010000 0.2128580000 0.0017900000 141767163 0 402718720 3.9345777035 3.9478969574 4.0588250160 1781 1311867778.0413420200 0.0969284996 0.1241410270 0.2390826792 0.0047820873 0.6691700000 0.0948590000 0.0946550000 0.0321810000 0.2128250000 0.2306370000 141770835 0 402718720 3.9326510429 3.9456398487 4.0608325005 1782 1311867778.0773630142 0.0976763740 0.1241261759 0.2390826792 0.0047875680 0.3899880000 0.0782380000 0.0946130000 0.0000000000 0.2109820000 0.0018840000 141774675 0 402718720 3.9294056892 3.9471733570 4.0603013039 1783 1311867778.1094930172 0.1013884917 0.1241134234 0.2390826792 0.0047870650 0.4312500000 0.0785990000 0.1020080000 0.0322180000 0.2125900000 0.0017930000 141778403 0 402718720 3.9275653362 3.9447240829 4.0624537468 1784 1311867778.1418550014 0.1013561115 0.1241006670 0.2390826792 0.0047857289 0.3942380000 0.0786160000 0.0975000000 0.0000010000 0.2123250000 0.0017890000 141782187 0 402718720 3.9277186394 3.9447624683 4.0627098083 1785 1311867778.1826310158 0.0965614766 0.1240852389 0.2390826792 0.0047885142 0.6741700000 0.0961840000 0.0976420000 0.0321420000 0.2132240000 0.2309290000 141786083 0 402718720 3.9320335388 3.9465920925 4.0606651306 1786 1311867778.2094058990 0.0992016867 0.1240713064 0.2390826792 0.0047873604 0.3984080000 0.0785810000 0.1022790000 0.0000010000 0.2113360000 0.0018900000 141789699 0 402718720 3.9314906597 3.9443116188 4.0626659393 1787 1311867778.2432699203 0.0957795829 0.1240554744 0.2390826792 0.0047877822 0.4281520000 0.0774960000 0.1013310000 0.0314740000 0.2117330000 0.0018390000 141793483 0 402718720 3.9341576099 3.9456758499 4.0609273911 1788 1311867778.2796919346 0.1000463217 0.1240420465 0.2390826792 0.0047881411 0.3965440000 0.0787030000 0.1005410000 0.0000010000 0.2114260000 0.0017840000 141797323 0 402718720 3.9303598404 3.9437038898 4.0631084442 1789 1311867778.3125588894 0.1037336886 0.1240306947 0.2390826792 0.0047899463 0.6465400000 0.0781920000 0.0984160000 0.0322280000 0.2088810000 0.2247960000 141801051 0 402718720 3.9274051189 3.9416568279 4.0649476051 1790 1311867778.3414309025 0.0973625034 0.1240157962 0.2390826792 0.0047908962 0.3918540000 0.0787500000 0.0981940000 0.0000010000 0.2090680000 0.0017820000 141804723 0 402718720 3.9321177006 3.9446966648 4.0615882874 1791 1311867778.3782539368 0.1002506167 0.1240025270 0.2390826792 0.0047903633 0.4138420000 0.0899140000 0.0770690000 0.0319190000 0.2090350000 0.0017950000 141808619 0 402718720 3.9293048382 3.9431550503 4.0625023842 1792 1311867778.4093298912 0.0962366238 0.1239870326 0.2390826792 0.0047990486 0.3800130000 0.0787970000 0.0903240000 0.0000000000 0.2050280000 0.0017820000 141812291 0 402718720 3.9380507469 3.9427583218 4.0632443428 1793 1311867778.4445381165 0.1006313786 0.1239740066 0.2390826792 0.0048076028 0.6424960000 0.0792620000 0.1058360000 0.0315920000 0.2040510000 0.2176650000 141816131 0 402718720 3.9306554794 3.9422883987 4.0638070107 1794 1311867778.4812810421 0.0972955227 0.1239591357 0.2390826792 0.0048131697 0.3841080000 0.0774700000 0.0971300000 0.0000000000 0.2036550000 0.0017890000 141820027 0 402718720 3.9356861115 3.9427340031 4.0629429817 1795 1311867778.5097670555 0.0971688181 0.1239442107 0.2390826792 0.0048119586 0.3882740000 0.0784780000 0.0692310000 0.0320940000 0.2023550000 0.0018790000 141823643 0 402718720 3.9332327843 3.9433040619 4.0614871979 1796 1311867778.5484840870 0.0959312022 0.1239286133 0.2390826792 0.0048108087 0.4050180000 0.0948480000 0.1029080000 0.0000010000 0.2010880000 0.0018760000 141827539 0 402718720 3.9336173534 3.9439671040 4.0606832504 1797 1311867778.5830690861 0.0947410315 0.1239123709 0.2390826792 0.0048104952 0.6293570000 0.0789890000 0.0983670000 0.0321120000 0.2017520000 0.2140380000 141831379 0 402718720 3.9356601238 3.9437925816 4.0604238510 1798 1311867778.6150701046 0.0977359861 0.1238978123 0.2390826792 0.0048098878 0.3840750000 0.0786160000 0.0989640000 0.0000000000 0.2005980000 0.0017830000 141835107 0 402718720 3.9329950809 3.9421002865 4.0615711212 1799 1311867778.6452109814 0.1006009206 0.1238848623 0.2390826792 0.0048143266 0.3910750000 0.0774270000 0.0772370000 0.0318980000 0.1983810000 0.0018360000 141838779 0 402718720 3.9284007549 3.9417631626 4.0622553825 1800 1311867778.6781129837 0.0989168435 0.1238709912 0.2390826792 0.0048130816 0.3899780000 0.0902800000 0.0945000000 0.0000000000 0.1993310000 0.0017810000 141842507 0 402718720 3.9297962189 3.9425022602 4.0614914894 1801 1311867778.7125270367 0.0999097452 0.1238576868 0.2390826792 0.0048122262 0.6146010000 0.0926780000 0.0774530000 0.0316170000 0.1988920000 0.2099060000 141846291 0 402718720 3.9295716286 3.9414227009 4.0620837212 1802 1311867778.7490179539 0.0987681746 0.1238437637 0.2390826792 0.0048115080 0.3814110000 0.0786490000 0.0984410000 0.0000000000 0.1984800000 0.0017850000 141850187 0 402718720 3.9302160740 3.9421203136 4.0615272522 1803 1311867778.7815420628 0.0987110808 0.1238298243 0.2390826792 0.0048111628 0.4191780000 0.0793490000 0.1031510000 0.0320570000 0.1986990000 0.0017930000 141853971 0 402718720 3.9284834862 3.9430444241 4.0608172417 1804 1311867778.8090119362 0.0994504690 0.1238163102 0.2390826792 0.0048101086 0.3816160000 0.0786310000 0.0985090000 0.0000010000 0.1985630000 0.0017800000 141857531 0 402718720 3.9282088280 3.9419591427 4.0609216690 1805 1311867778.8465809822 0.1022324637 0.1238043524 0.2390826792 0.0048097747 0.6198820000 0.0784030000 0.0984630000 0.0314990000 0.1984360000 0.2089490000 141861427 0 402718720 3.9256196022 3.9404776096 4.0620489120 1806 1311867778.8808300495 0.1018882245 0.1237922172 0.2390826792 0.0048090886 0.4023780000 0.0996940000 0.0986730000 0.0000000000 0.1981160000 0.0017790000 141865211 0 402718720 3.9260921478 3.9405715466 4.0619235039 1807 1311867778.9117860794 0.1005876660 0.1237793758 0.2390826792 0.0048090994 0.3648970000 0.0788890000 0.0497120000 0.0319450000 0.1982320000 0.0019300000 141868883 0 402718720 3.9266138077 3.9409656525 4.0606904030 1808 1311867778.9482150078 0.1030414775 0.1237679057 0.2390826792 0.0048079796 0.3817240000 0.0787730000 0.0988730000 0.0000010000 0.1981810000 0.0017780000 141872779 0 402718720 3.9236764908 3.9396822453 4.0610580444 1809 1311867778.9777760506 0.1029786170 0.1237564135 0.2390826792 0.0048068067 0.6202480000 0.0789330000 0.0985380000 0.0319300000 0.1981730000 0.2085460000 141876451 0 402718720 3.9224038124 3.9400999546 4.0601944923 1810 1311867779.0105700493 0.1019562483 0.1237443693 0.2390826792 0.0048059357 0.3872730000 0.0794620000 0.1036860000 0.0000010000 0.1982190000 0.0017830000 141880179 0 402718720 3.9220447540 3.9413447380 4.0590462685 1811 1311867779.0471200943 0.1031382903 0.1237329910 0.2390826792 0.0048048382 0.4314970000 0.0937180000 0.1014160000 0.0319280000 0.1985420000 0.0017910000 141884075 0 402718720 3.9204707146 3.9408414364 4.0588722229 1812 1311867779.0780360699 0.1040632278 0.1237221357 0.2390826792 0.0048035929 0.3579070000 0.0793750000 0.0740730000 0.0000000000 0.1985930000 0.0017740000 141887691 0 402718720 3.9189550877 3.9406380653 4.0584974289 1813 1311867779.1124050617 0.1039694399 0.1237112407 0.2390826792 0.0048036647 0.6008260000 0.0796640000 0.0779680000 0.0314130000 0.1987800000 0.2089300000 141891475 0 402718720 3.9177310467 3.9416759014 4.0576233864 1814 1311867779.1473538876 0.1031424776 0.1236999018 0.2390826792 0.0048026157 0.3941150000 0.0910440000 0.0984800000 0.0000000000 0.1986750000 0.0017830000 141895147 0 402718720 3.9192214012 3.9416615963 4.0573606491 1815 1311867779.1777000427 0.1037679687 0.1236889200 0.2390826792 0.0048013228 0.3968090000 0.0784120000 0.0824090000 0.0313730000 0.1986960000 0.0017940000 141898763 0 402718720 3.9186456203 3.9412155151 4.0571999550 1816 1311867779.2123599052 0.1043151096 0.1236782516 0.2390826792 0.0048003881 0.3598280000 0.0943390000 0.0608960000 0.0000000000 0.1986080000 0.0017880000 141902491 0 402718720 3.9180231094 3.9411041737 4.0571312904 1817 1311867779.2447109222 0.1043573320 0.1236676182 0.2390826792 0.0047995730 0.5804960000 0.0797560000 0.0607910000 0.0317860000 0.1971770000 0.2068560000 141906219 0 402718720 3.9175159931 3.9413800240 4.0565619469 1818 1311867779.2782809734 0.1038571745 0.1236567213 0.2390826792 0.0048003295 0.3810180000 0.0786710000 0.0978250000 0.0000000000 0.1986460000 0.0017850000 141909891 0 402718720 3.9185793400 3.9411516190 4.0564036369 1819 1311867779.3104579449 0.1022124067 0.1236449323 0.2390826792 0.0047998333 0.4153900000 0.0801680000 0.0989070000 0.0317450000 0.1986870000 0.0017860000 141913619 0 402718720 3.9197902679 3.9418988228 4.0551486015 1820 1311867779.3468949795 0.1005605981 0.1236322486 0.2390826792 0.0047995254 0.3600260000 0.0804490000 0.0742080000 0.0000000000 0.1994340000 0.0017870000 141917459 0 402718720 3.9206733704 3.9434299469 4.0539784431 1821 1311867779.3772010803 0.1019941121 0.1236203660 0.2390826792 0.0047987213 0.6366650000 0.0904580000 0.1030590000 0.0317460000 0.1989530000 0.2082700000 141921075 0 402718720 3.9198415279 3.9421334267 4.0540981293 1822 1311867779.4088799953 0.1023311913 0.1236086815 0.2390826792 0.0047974621 0.3877570000 0.0802810000 0.1037640000 0.0000010000 0.1974830000 0.0018750000 141924747 0 402718720 3.9196467400 3.9417324066 4.0538020134 1823 1311867779.4446020126 0.1024267375 0.1235970622 0.2390826792 0.0047963245 0.4304250000 0.0933480000 0.1003190000 0.0317230000 0.1991360000 0.0017930000 141928531 0 402718720 3.9190309048 3.9419255257 4.0529079437 1824 1311867779.4768970013 0.1050487682 0.1235868932 0.2390826792 0.0047952984 0.3597910000 0.0803990000 0.0745400000 0.0000010000 0.1989140000 0.0017910000 141932259 0 402718720 3.9176087379 3.9396469593 4.0538301468 1825 1311867779.5098230839 0.1048251539 0.1235766128 0.2390826792 0.0047945537 0.6365520000 0.1017450000 0.0776540000 0.0389600000 0.2064300000 0.2076480000 141935931 0 402718720 3.9181880951 3.9390876293 4.0534744263 1826 1311867779.5450038910 0.1025977358 0.1235651238 0.2390826792 0.0047937033 0.4168060000 0.1076120000 0.1041630000 0.0000000000 0.1990120000 0.0017950000 141939715 0 402718720 3.9191951752 3.9405782223 4.0518097878 1827 1311867779.5777029991 0.1041077077 0.1235544739 0.2390826792 0.0047927327 0.4210330000 0.0808270000 0.1040740000 0.0311150000 0.1991000000 0.0017920000 141943387 0 402718720 3.9179151058 3.9395253658 4.0518431664 1828 1311867779.6092689037 0.1023317724 0.1235428641 0.2390826792 0.0047936835 0.3888680000 0.0809210000 0.1026930000 0.0000010000 0.1992890000 0.0017800000 141947059 0 402718720 3.9197320938 3.9398307800 4.0508866310 1829 1311867779.6482150555 0.1018776149 0.1235310187 0.2390826792 0.0047929495 0.6240120000 0.0810590000 0.0989890000 0.0315320000 0.1997790000 0.2084640000 141950899 0 402718720 3.9187326431 3.9411921501 4.0497107506 1830 1311867779.6796278954 0.0983559862 0.1235172618 0.2390826792 0.0047933329 0.3865560000 0.0812860000 0.0992560000 0.0000010000 0.2000220000 0.0017850000 141954571 0 402718720 3.9215738773 3.9430460930 4.0480308533 1831 1311867779.7129859924 0.0982385650 0.1235034559 0.2390826792 0.0047923901 0.4358120000 0.0941450000 0.1040930000 0.0315430000 0.2000870000 0.0017950000 141958243 0 402718720 3.9218363762 3.9429695606 4.0476679802 1832 1311867779.7461729050 0.0979567543 0.1234895112 0.2390826792 0.0047926196 0.3618820000 0.0813080000 0.0745810000 0.0000010000 0.2000730000 0.0017880000 141962027 0 402718720 3.9232182503 3.9419236183 4.0477261543 1833 1311867779.7771708965 0.0948990136 0.1234739135 0.2390826792 0.0047933208 0.6248100000 0.0815200000 0.0992140000 0.0314920000 0.2000620000 0.2083470000 141965643 0 402718720 3.9257955551 3.9430811405 4.0461812019 1834 1311867779.8130059242 0.0940638855 0.1234578775 0.2390826792 0.0047930384 0.3624760000 0.0965560000 0.0609730000 0.0000000000 0.1986770000 0.0018730000 141969371 0 402718720 3.9269514084 3.9430031776 4.0456824303 1835 1311867779.8454499245 0.0923407823 0.1234409200 0.2390826792 0.0047939295 0.4233900000 0.0817400000 0.1041230000 0.0314440000 0.2000760000 0.0017920000 141973099 0 402718720 3.9296913147 3.9422962666 4.0450634956 1836 1311867779.8771400452 0.0909113064 0.1234232023 0.2390826792 0.0047926705 0.4155600000 0.1091900000 0.0998330000 0.0000000000 0.2005630000 0.0017940000 141976715 0 402718720 3.9299697876 3.9433851242 4.0436391830 1837 1311867779.9128279686 0.0902730674 0.1234051565 0.2390826792 0.0047924070 0.6573350000 0.0820810000 0.0939500000 0.0384780000 0.2149480000 0.2232720000 141980555 0 402718720 3.9308216572 3.9432091713 4.0429201126 1838 1311867779.9448599815 0.0881211236 0.1233859596 0.2390826792 0.0047925057 0.3968810000 0.0905520000 0.0993010000 0.0000000000 0.2010470000 0.0017850000 141984227 0 402718720 3.9329261780 3.9437189102 4.0418496132 1839 1311867779.9769320488 0.0882832184 0.1233668716 0.2390826792 0.0047916015 0.4171510000 0.0806790000 0.0979990000 0.0311720000 0.2013780000 0.0017470000 141987899 0 402718720 3.9328255653 3.9434721470 4.0416336060 1840 1311867780.0130739212 0.0870878547 0.1233471547 0.2390826792 0.0047909239 0.3883840000 0.0821550000 0.0986620000 0.0000010000 0.2016000000 0.0017820000 141991683 0 402718720 3.9325628281 3.9449687004 4.0403318405 1841 1311867780.0448310375 0.0834718198 0.1233254951 0.2390826792 0.0047900620 0.6420750000 0.0957540000 0.0986080000 0.0313240000 0.2022700000 0.2099730000 141995355 0 402718720 3.9336802959 3.9476468563 4.0373587608 1842 1311867780.0771219730 0.0837895349 0.1233040315 0.2390826792 0.0047891914 0.3937040000 0.0825870000 0.1029030000 0.0000010000 0.2022620000 0.0017930000 141999027 0 402718720 3.9339218140 3.9471244812 4.0375928879 1843 1311867780.1143870354 0.0835515708 0.1232824621 0.2390826792 0.0047881307 0.3962450000 0.0825120000 0.0740170000 0.0312400000 0.2024560000 0.0017950000 142002867 0 402718720 3.9336552620 3.9471321106 4.0366587639 1844 1311867780.1448268890 0.0815441534 0.1232598274 0.2390826792 0.0047920879 0.3896030000 0.0824480000 0.0983680000 0.0000010000 0.2027980000 0.0017950000 142006483 0 402718720 3.9349699020 3.9471483231 4.0352911949 1845 1311867780.1773400307 0.0799182430 0.1232363361 0.2390826792 0.0047924747 0.6302810000 0.0825870000 0.0982050000 0.0312730000 0.2033040000 0.2107090000 142010155 0 402718720 3.9355657101 3.9483854771 4.0335154533 1846 1311867780.2158250809 0.0793030486 0.1232125369 0.2390826792 0.0047933319 0.4294820000 0.1169960000 0.1032260000 0.0000010000 0.2032890000 0.0017990000 142014051 0 402718720 3.9353473186 3.9488356113 4.0332407951 1847 1311867780.2454960346 0.0802375004 0.1231892694 0.2390826792 0.0047949940 0.4217610000 0.0826640000 0.0981350000 0.0312290000 0.2037740000 0.0017990000 142017667 0 402718720 3.9342677593 3.9484348297 4.0322508812 1848 1311867780.2815570831 0.0805227682 0.1231661815 0.2390826792 0.0047937322 0.3743270000 0.0824550000 0.0820160000 0.0000010000 0.2038740000 0.0017840000 142021451 0 402718720 3.9342608452 3.9479248524 4.0326123238 1849 1311867780.3140099049 0.0785968974 0.1231420769 0.2390826792 0.0047945087 0.6447650000 0.0939470000 0.0980170000 0.0312260000 0.2050350000 0.2123510000 142025123 0 402718720 3.9342350960 3.9486367702 4.0294017792 1850 1311867780.3464050293 0.0787443966 0.1231180782 0.2390826792 0.0047933253 0.3906750000 0.0811370000 0.0978600000 0.0000000000 0.2056530000 0.0017870000 142028795 0 402718720 3.9330651760 3.9487607479 4.0279254913 1851 1311867780.3772649765 0.0784209073 0.1230939306 0.2390826792 0.0047929099 0.4357990000 0.0949270000 0.0974140000 0.0312030000 0.2062590000 0.0017980000 142032411 0 402718720 3.9331791401 3.9476418495 4.0269207954 1852 1311867780.4132668972 0.0793955773 0.1230703354 0.2390826792 0.0047923606 0.3901450000 0.0809370000 0.0964170000 0.0000000000 0.2067510000 0.0017840000 142036251 0 402718720 3.9326260090 3.9470708370 4.0267558098 1853 1311867780.4451050758 0.0788696408 0.1230464818 0.2390826792 0.0047921156 0.6423990000 0.0827510000 0.1023230000 0.0312000000 0.2073970000 0.2144640000 142039923 0 402718720 3.9315474033 3.9487612247 4.0255794525 1854 1311867780.4791510105 0.0800424889 0.1230232866 0.2390826792 0.0047915218 0.3943600000 0.0825160000 0.0976300000 0.0000000000 0.2082300000 0.0017950000 142043651 0 402718720 3.9275217056 3.9501791000 4.0238585472 1855 1311867780.5153009892 0.0816645473 0.1230009907 0.2390826792 0.0047920357 0.4232880000 0.0809790000 0.0967020000 0.0311760000 0.2084030000 0.0018020000 142047491 0 402718720 3.9263010025 3.9496278763 4.0235991478 1856 1311867780.5455119610 0.0801359415 0.1229778953 0.2390826792 0.0047975814 0.3942250000 0.0824450000 0.0965410000 0.0000000000 0.2091450000 0.0017820000 142051107 0 402718720 3.9278066158 3.9487850666 4.0231828690 1857 1311867780.5798339844 0.0805422589 0.1229550436 0.2390826792 0.0047971604 0.6456940000 0.0824520000 0.1015080000 0.0311840000 0.2097670000 0.2165750000 142054835 0 402718720 3.9273405075 3.9484281540 4.0227775574 1858 1311867780.6136929989 0.0832843482 0.1229336923 0.2390826792 0.0048014829 0.4023780000 0.1008360000 0.0849190000 0.0000000000 0.2105820000 0.0017830000 142058507 0 402718720 3.9247972965 3.9479818344 4.0222463608 1859 1311867780.6459660530 0.0860539898 0.1229138539 0.2390826792 0.0048009052 0.4214090000 0.0808100000 0.0919220000 0.0309830000 0.2117170000 0.0017960000 142062235 0 402718720 3.9212737083 3.9477481842 4.0218477249 1860 1311867780.6793959141 0.0857076123 0.1228938505 0.2390826792 0.0048008447 0.3977660000 0.0827980000 0.0962870000 0.0000010000 0.2126340000 0.0017960000 142065963 0 402718720 3.9203522205 3.9498462677 4.0212664604 1861 1311867780.7156999111 0.0872804299 0.1228747138 0.2390826792 0.0048001990 0.6471380000 0.0829430000 0.0963600000 0.0311240000 0.2128550000 0.2194920000 142069747 0 402718720 3.9184472561 3.9497649670 4.0211291313 1862 1311867780.7469029427 0.0866762325 0.1228552732 0.2390826792 0.0047996397 0.3972260000 0.0823440000 0.0952290000 0.0000000000 0.2135170000 0.0017980000 142073363 0 402718720 3.9196817875 3.9484131336 4.0209250450 1863 1311867780.7774689198 0.0880998969 0.1228366176 0.2390826792 0.0047984186 0.4346070000 0.0826420000 0.1009200000 0.0311610000 0.2138680000 0.0017970000 142077035 0 402718720 3.9183022976 3.9474706650 4.0205874443 1864 1311867780.8164570332 0.0895278826 0.1228187481 0.2390826792 0.0047974979 0.3996370000 0.0827490000 0.0961110000 0.0000010000 0.2147480000 0.0018040000 142080931 0 402718720 3.9163219929 3.9477598667 4.0201873779 1865 1311867780.8460350037 0.0897667781 0.1228010258 0.2390826792 0.0047966216 0.6134830000 0.0826350000 0.0592470000 0.0311500000 0.2140240000 0.2221830000 142084491 0 402718720 3.9162609577 3.9462540150 4.0198874474 1866 1311867780.8791809082 0.0921422392 0.1227845956 0.2390826792 0.0047953643 0.4133560000 0.0949730000 0.0960600000 0.0000020000 0.2162530000 0.0018070000 142088219 0 402718720 3.9147276878 3.9438214302 4.0199937820 1867 1311867780.9152340889 0.0934732705 0.1227688959 0.2390826792 0.0047945760 0.4091830000 0.0828160000 0.0723380000 0.0311030000 0.2168550000 0.0018040000 142092003 0 402718720 3.9130632877 3.9439983368 4.0197181702 1868 1311867780.9457290173 0.0923708528 0.1227526229 0.2390826792 0.0047954232 0.3785220000 0.0827090000 0.0722470000 0.0000010000 0.2175060000 0.0017930000 142095619 0 402718720 3.9145483971 3.9431114197 4.0192432404 1869 1311867780.9838399887 0.0943652689 0.1227374344 0.2390826792 0.0047945521 0.6565160000 0.0824640000 0.0957280000 0.0310860000 0.2182290000 0.2247230000 142099459 0 402718720 3.9128091335 3.9417634010 4.0190720558 1870 1311867781.0137300491 0.0935192630 0.1227218097 0.2390826792 0.0047935619 0.4248170000 0.0989880000 0.1008750000 0.0000010000 0.2189090000 0.0018060000 142103075 0 402718720 3.9133658409 3.9424321651 4.0186777115 1871 1311867781.0463659763 0.0946651995 0.1227068142 0.2390826792 0.0047924895 0.4352320000 0.1050590000 0.0733640000 0.0310620000 0.2196560000 0.0018050000 142106747 0 402718720 3.9118905067 3.9422998428 4.0181665421 1872 1311867781.0821859837 0.0947686359 0.1226918899 0.2390826792 0.0047915767 0.4043380000 0.0813010000 0.0963230000 0.0000010000 0.2206160000 0.0017990000 142110531 0 402718720 3.9122881889 3.9405434132 4.0173301697 1873 1311867781.1157560349 0.0950517803 0.1226771328 0.2390826792 0.0047905087 0.6652930000 0.0827580000 0.1010180000 0.0306160000 0.2200210000 0.2264100000 142114259 0 402718720 3.9118089676 3.9404869080 4.0170421600 1874 1311867781.1459479332 0.0943493992 0.1226620166 0.2390826792 0.0047910802 0.4068680000 0.0825450000 0.0956870000 0.0000010000 0.2225580000 0.0018130000 142117875 0 402718720 3.9124286175 3.9394698143 4.0162701607 1875 1311867781.1839950085 0.0957374200 0.1226476568 0.2390826792 0.0047902489 0.4394790000 0.0826990000 0.0955910000 0.0310850000 0.2240370000 0.0018130000 142121715 0 402718720 3.9108395576 3.9391255379 4.0156888962 1876 1311867781.2133030891 0.0943586752 0.1226325774 0.2390826792 0.0047893249 0.4318790000 0.1052290000 0.0952440000 0.0000010000 0.2253210000 0.0018080000 142125275 0 402718720 3.9126296043 3.9384217262 4.0151114464 1877 1311867781.2467529774 0.0955612659 0.1226181548 0.2390826792 0.0047887046 0.6366710000 0.0829460000 0.0590580000 0.0311070000 0.2265190000 0.2327500000 142128947 0 402718720 3.9107830524 3.9397306442 4.0145125389 1878 1311867781.2855589390 0.0977983996 0.1226049387 0.2390826792 0.0047880193 0.4046540000 0.0827440000 0.0877140000 0.0000010000 0.2281010000 0.0018030000 142132843 0 402718720 3.9087142944 3.9390385151 4.0140466690 1879 1311867781.3133049011 0.0972713977 0.1225914562 0.2390826792 0.0047869893 0.4494320000 0.0957160000 0.0873570000 0.0305590000 0.2297210000 0.0018200000 142136347 0 402718720 3.9092073441 3.9397923946 4.0133686066 1880 1311867781.3465669155 0.0975633264 0.1225781434 0.2390826792 0.0047862370 0.3682910000 0.0827090000 0.0481260000 0.0000000000 0.2313560000 0.0018140000 142140131 0 402718720 3.9085216522 3.9404320717 4.0127954483 1881 1311867781.3809239864 0.0979380682 0.1225650439 0.2390826792 0.0047849735 0.6711970000 0.0971460000 0.0669620000 0.0310790000 0.2327120000 0.2389700000 142143859 0 402718720 3.9081680775 3.9399657249 4.0120868683 1882 1311867781.4144830704 0.0958695784 0.1225508593 0.2390826792 0.0047842943 0.4200110000 0.0828230000 0.0963360000 0.0000010000 0.2347280000 0.0018160000 142147531 0 402718720 3.9096851349 3.9416017532 4.0114030838 1883 1311867781.4457330704 0.0974851847 0.1225375478 0.2390826792 0.0047844117 0.4634830000 0.0958610000 0.0949250000 0.0305760000 0.2360440000 0.0018110000 142151203 0 402718720 3.9074995518 3.9408361912 4.0111784935 1884 1311867781.4812419415 0.0981236845 0.1225245892 0.2390826792 0.0047839723 0.3751500000 0.0812240000 0.0498380000 0.0000010000 0.2379730000 0.0018220000 142154987 0 402718720 3.9074234962 3.9405472279 4.0105648041 1885 1311867781.5131030083 0.0975514203 0.1225113409 0.2390826792 0.0047833853 0.6899280000 0.0823800000 0.0865950000 0.0309770000 0.2397500000 0.2459360000 142158603 0 402718720 3.9078693390 3.9410977364 4.0104207993 1886 1311867781.5451910496 0.0981634036 0.1224984310 0.2390826792 0.0047837073 0.4265090000 0.0822030000 0.0966760000 0.0000010000 0.2414970000 0.0018140000 142162331 0 402718720 3.9064655304 3.9425630569 4.0101332664 1887 1311867781.5813419819 0.0951829106 0.1224839554 0.2390826792 0.0047874461 0.4164400000 0.0818570000 0.0551830000 0.0310200000 0.2422690000 0.0018270000 142166115 0 402718720 3.9091513157 3.9426438808 4.0092449188 1888 1311867781.6135890484 0.0977921188 0.1224708771 0.2390826792 0.0047869553 0.4287990000 0.0820990000 0.0969100000 0.0000010000 0.2436480000 0.0018100000 142169731 0 402718720 3.9067716599 3.9413850307 4.0089883804 1889 1311867781.6467020512 0.0969712734 0.1224573781 0.2390826792 0.0047857913 0.6878510000 0.0931470000 0.0627690000 0.0310410000 0.2452120000 0.2513600000 142173459 0 402718720 3.9074726105 3.9416916370 4.0085134506 1890 1311867781.6832339764 0.0970970616 0.1224439599 0.2390826792 0.0047852976 0.4123960000 0.0817020000 0.0780290000 0.0000010000 0.2465500000 0.0018020000 142177243 0 402718720 3.9068896770 3.9423484802 4.0079355240 1891 1311867781.7131800652 0.0971290693 0.1224305729 0.2390826792 0.0047840768 0.4571410000 0.0884770000 0.0778740000 0.0310510000 0.2525240000 0.0024680000 142180859 0 402718720 3.9066970348 3.9421322346 4.0074424744 1892 1311867781.7453010082 0.0979878083 0.1224176539 0.2390826792 0.0047833163 0.4845870000 0.1036940000 0.1244380000 0.0000010000 0.2502970000 0.0018110000 142184587 0 402718720 3.9058380127 3.9415752888 4.0075397491 1893 1311867781.7820630074 0.0959372744 0.1224036653 0.2390826792 0.0047857115 0.6931380000 0.0814540000 0.0701690000 0.0310420000 0.2500850000 0.2560580000 142188371 0 402718720 3.9077987671 3.9413363934 4.0068054199 1894 1311867781.8145859241 0.0946851522 0.1223890304 0.2390826792 0.0047880548 0.3941380000 0.0814610000 0.0546580000 0.0000000000 0.2518410000 0.0018240000 142192043 0 402718720 3.9086375237 3.9411859512 4.0062775612 1895 1311867781.8453550339 0.0952456445 0.1223747067 0.2390826792 0.0047876961 0.4640410000 0.0813120000 0.0926580000 0.0305890000 0.2533720000 0.0018100000 142195715 0 402718720 3.9075207710 3.9424247742 4.0061483383 1896 1311867781.8827259541 0.0943926424 0.1223599483 0.2390826792 0.0047893093 0.4585860000 0.1013580000 0.0962470000 0.0000000000 0.2549270000 0.0017720000 142199499 0 402718720 3.9079260826 3.9423000813 4.0052952766 1897 1311867781.9138391018 0.0961742550 0.1223461445 0.2390826792 0.0047890230 0.7284850000 0.0810730000 0.0925490000 0.0310260000 0.2568010000 0.2626800000 142203171 0 402718720 3.9067449570 3.9399302006 4.0049571991 1898 1311867781.9470670223 0.0955529138 0.1223320280 0.2390826792 0.0047880731 0.4408570000 0.0812380000 0.0922100000 0.0000010000 0.2612740000 0.0018150000 142206899 0 402718720 3.9073059559 3.9392518997 4.0039687157 1899 1311867781.9856810570 0.0967498645 0.1223185566 0.2390826792 0.0047892181 0.4866140000 0.0920460000 0.0915820000 0.0310980000 0.2657750000 0.0018140000 142210683 0 402718720 3.9049222469 3.9413163662 4.0039572716 1900 1311867782.0139210224 0.0962598771 0.1223048415 0.2390826792 0.0047897263 0.4473030000 0.0807170000 0.0909110000 0.0000010000 0.2695760000 0.0017970000 142214243 0 402718720 3.9056229591 3.9397366047 4.0029821396 1901 1311867782.0464830399 0.0975426435 0.1222918156 0.2390826792 0.0047899193 0.7796460000 0.0965840000 0.0947300000 0.0310650000 0.2733800000 0.2795430000 142217971 0 402718720 3.9039013386 3.9403867722 4.0025844574 1902 1311867782.0839829445 0.0994132236 0.1222797869 0.2390826792 0.0047932546 0.4671540000 0.0799870000 0.0909270000 0.0000000000 0.2889930000 0.0024180000 142221699 0 402718720 3.9013023376 3.9424326420 4.0025873184 1903 1311867782.1135599613 0.0973259136 0.1222666740 0.2390826792 0.0047924798 0.4876450000 0.1011810000 0.0605750000 0.0378130000 0.2819450000 0.0017900000 142225315 0 402718720 3.9029932022 3.9437327385 4.0022745132 1904 1311867782.1472380161 0.0988115892 0.1222543551 0.2390826792 0.0047914574 0.4513690000 0.0775260000 0.0880740000 0.0000010000 0.2796890000 0.0017370000 142229043 0 402718720 3.9015588760 3.9431152344 4.0023617744 1905 1311867782.1819090843 0.0988819003 0.1222420861 0.2390826792 0.0047907544 0.7618160000 0.0980280000 0.0624400000 0.0307020000 0.2798410000 0.2864540000 142232827 0 402718720 3.9011409283 3.9445557594 4.0023603439 1906 1311867782.2144429684 0.0985123590 0.1222296361 0.2390826792 0.0047899268 0.4589750000 0.0794280000 0.0930680000 0.0000010000 0.2803470000 0.0017720000 142236499 0 402718720 3.9019589424 3.9444110394 4.0023274422 1907 1311867782.2494089603 0.0977182910 0.1222167828 0.2390826792 0.0047913210 0.4327360000 0.0768890000 0.0369430000 0.0311500000 0.2816390000 0.0017780000 142240227 0 402718720 3.9026491642 3.9437050819 4.0017795563 1908 1311867782.2860810757 0.0992415175 0.1222047412 0.2390826792 0.0047902338 0.4694390000 0.0920710000 0.0881510000 0.0000010000 0.2830390000 0.0017770000 142244067 0 402718720 3.9012155533 3.9437041283 4.0019474030 1909 1311867782.3144040108 0.0987706259 0.1221924656 0.2390826792 0.0047894209 0.7751060000 0.0783170000 0.0875800000 0.0310290000 0.2837110000 0.2901060000 142247571 0 402718720 3.9014844894 3.9446468353 4.0015277863 1910 1311867782.3526129723 0.0994448364 0.1221805559 0.2390826792 0.0047892645 0.4130230000 0.0780840000 0.0445860000 0.0000000000 0.2841960000 0.0017590000 142251467 0 402718720 3.9011008739 3.9435765743 4.0012731552 1911 1311867782.3825540543 0.1007624790 0.1221693481 0.2390826792 0.0047882065 0.5026980000 0.0886610000 0.0920980000 0.0311700000 0.2843410000 0.0018710000 142255027 0 402718720 3.8996832371 3.9436740875 4.0012793541 1912 1311867782.4147620201 0.1004421264 0.1221579845 0.2390826792 0.0047875671 0.4412490000 0.0777070000 0.0707890000 0.0000010000 0.2865790000 0.0017640000 142258587 0 402718720 3.9000093937 3.9449675083 4.0013489723 1913 1311867782.4514210224 0.0992591977 0.1221460144 0.2390826792 0.0047869492 0.7366270000 0.0769160000 0.0440940000 0.0310950000 0.2868640000 0.2932320000 142262371 0 402718720 3.9013407230 3.9441688061 4.0008344650 1914 1311867782.4812099934 0.0986875966 0.1221337581 0.2390826792 0.0047857224 0.4153740000 0.0774750000 0.0438380000 0.0000010000 0.2879360000 0.0017550000 142266043 0 402718720 3.9020900726 3.9443256855 4.0006337166 1915 1311867782.5149359703 0.1003836393 0.1221224004 0.2390826792 0.0047860643 0.4894510000 0.0773660000 0.0868450000 0.0310120000 0.2881370000 0.0017570000 142269715 0 402718720 3.9004142284 3.9453442097 4.0011062622 1916 1311867782.5516130924 0.0995811298 0.1221106356 0.2390826792 0.0047860473 0.4944340000 0.1097430000 0.0910340000 0.0000010000 0.2875260000 0.0017690000 142273499 0 402718720 3.9015538692 3.9445617199 4.0009646416 1917 1311867782.5828690529 0.1000619009 0.1220991339 0.2390826792 0.0047850972 0.7356900000 0.0772360000 0.0386840000 0.0311090000 0.2888690000 0.2954030000 142277115 0 402718720 3.9009497166 3.9453606606 4.0007562637 1918 1311867782.6142859459 0.1001231074 0.1220876762 0.2390826792 0.0047840474 0.4591970000 0.0772650000 0.0864250000 0.0000010000 0.2893480000 0.0017650000 142280843 0 402718720 3.9009797573 3.9459292889 4.0007185936 1919 1311867782.6501080990 0.1005709991 0.1220764637 0.2390826792 0.0047835943 0.4630180000 0.0778730000 0.0584400000 0.0310930000 0.2894070000 0.0017630000 142284627 0 402718720 3.9009330273 3.9447023869 4.0005488396 1920 1311867782.6862080097 0.1015454084 0.1220657705 0.2390826792 0.0047841460 0.4607150000 0.0775980000 0.0864270000 0.0000000000 0.2904860000 0.0017630000 142288411 0 402718720 3.9009048939 3.9444997311 4.0003585815 1921 1311867782.7131700516 0.1000344604 0.1220543018 0.2390826792 0.0047832398 0.7724980000 0.0772990000 0.0720740000 0.0309920000 0.2905650000 0.2972150000 142291915 0 402718720 3.9022135735 3.9457364082 3.9999413490 1922 1311867782.7489991188 0.1016219482 0.1220436710 0.2390826792 0.0047834935 0.4370700000 0.0889830000 0.0508680000 0.0000000000 0.2910860000 0.0017530000 142295699 0 402718720 3.9006466866 3.9447240829 3.9996228218 1923 1311867782.7844688892 0.1010653973 0.1220327619 0.2390826792 0.0047825446 0.4901270000 0.0773100000 0.0842510000 0.0305720000 0.2918310000 0.0017610000 142299483 0 402718720 3.9012422562 3.9440920353 3.9990336895 1924 1311867782.8159070015 0.1016165540 0.1220221505 0.2390826792 0.0047821518 0.4405350000 0.0769180000 0.0646480000 0.0000000000 0.2928150000 0.0017520000 142303155 0 402718720 3.8997657299 3.9455130100 3.9993324280 1925 1311867782.8522670269 0.1005948186 0.1220110195 0.2390826792 0.0047818970 0.7556200000 0.0771700000 0.0507740000 0.0309230000 0.2929670000 0.2993900000 142306883 0 402718720 3.9014840126 3.9438199997 3.9981400967 1926 1311867782.8824830055 0.1022799909 0.1220007749 0.2390826792 0.0047808589 0.4913420000 0.1007250000 0.0906890000 0.0000010000 0.2934790000 0.0018490000 142310555 0 402718720 3.8999590874 3.9423220158 3.9978270531 1927 1311867782.9145979881 0.1010814235 0.1219899190 0.2390826792 0.0047808871 0.4988620000 0.0762370000 0.0899800000 0.0310970000 0.2953840000 0.0017470000 142314227 0 402718720 3.9007952213 3.9443619251 3.9974169731 1928 1311867782.9517209530 0.1025425419 0.1219798322 0.2390826792 0.0047797962 0.4292160000 0.0761720000 0.0502020000 0.0000010000 0.2967080000 0.0017390000 142318067 0 402718720 3.8992481232 3.9440519810 3.9970829487 1929 1311867782.9812240601 0.1011751667 0.1219690470 0.2390826792 0.0047796346 0.7989070000 0.0758900000 0.0850660000 0.0310350000 0.2977140000 0.3047080000 142321627 0 402718720 3.9007177353 3.9421908855 3.9960021973 1930 1311867783.0143089294 0.1027988493 0.1219591142 0.2390826792 0.0047806426 0.4371190000 0.0747300000 0.0568150000 0.0000000000 0.2994420000 0.0017430000 142325355 0 402718720 3.8985733986 3.9439799786 3.9960346222 1931 1311867783.0528459549 0.1024609432 0.1219490168 0.2390826792 0.0047797659 0.4897580000 0.0959720000 0.0568860000 0.0310590000 0.2996980000 0.0017540000 142329139 0 402718720 3.8987004757 3.9442396164 3.9953899384 1932 1311867783.0829811096 0.1027562320 0.1219390826 0.2390826792 0.0047797368 0.4273620000 0.0758370000 0.0452610000 0.0000000000 0.3001270000 0.0017480000 142332811 0 402718720 3.8986387253 3.9425501823 3.9948356152 1933 1311867783.1137030125 0.1032414660 0.1219294098 0.2390826792 0.0047791141 0.8081150000 0.0751380000 0.0872610000 0.0310700000 0.3014700000 0.3087580000 142336427 0 402718720 3.8981218338 3.9432761669 3.9950451851 1934 1311867783.1539480686 0.1035122499 0.1219198869 0.2390826792 0.0047780137 0.4612300000 0.0755150000 0.0774180000 0.0000010000 0.3021660000 0.0017410000 142340323 0 402718720 3.8976583481 3.9435286522 3.9946928024 1935 1311867783.1857850552 0.1042073295 0.1219107332 0.2390826792 0.0047769462 0.4979480000 0.0749040000 0.0837470000 0.0306280000 0.3025270000 0.0017300000 142343995 0 402718720 3.8967525959 3.9434926510 3.9942946434 1936 1311867783.2169439793 0.1055389643 0.1219022767 0.2390826792 0.0047761011 0.4611680000 0.0863370000 0.0661790000 0.0000010000 0.3024230000 0.0017400000 142347611 0 402718720 3.8951108456 3.9438014030 3.9945602417 1937 1311867783.2548489571 0.1050500274 0.1218935765 0.2390826792 0.0047749108 0.8336080000 0.0979010000 0.0875220000 0.0311150000 0.3018920000 0.3107250000 142351507 0 402718720 3.8954300880 3.9443907738 3.9942119122 1938 1311867783.2816879749 0.1046838909 0.1218846964 0.2390826792 0.0047741539 0.4460510000 0.0747630000 0.0613940000 0.0000010000 0.3037430000 0.0017390000 142355067 0 402718720 3.8958044052 3.9437146187 3.9939196110 1939 1311867783.3132228851 0.1063564494 0.1218766880 0.2390826792 0.0047729979 0.4996390000 0.0749470000 0.0833840000 0.0309700000 0.3041990000 0.0017350000 142358627 0 402718720 3.8942873478 3.9429354668 3.9941592216 1940 1311867783.3503270149 0.1101926267 0.1218706653 0.2390826792 0.0047738509 0.4690560000 0.0744770000 0.0834160000 0.0000010000 0.3050180000 0.0017320000 142362467 0 402718720 3.8901951313 3.9438729286 3.9947319031 1941 1311867783.3855919838 0.1124547198 0.1218658142 0.2390826792 0.0047736011 0.8420770000 0.1032720000 0.0875530000 0.0311480000 0.3034410000 0.3121920000 142366251 0 402718720 3.8879580498 3.9430181980 3.9943418503 1942 1311867783.4198501110 0.1103281677 0.1218598731 0.2390826792 0.0047737041 0.4424660000 0.0744160000 0.0558860000 0.0000010000 0.3060210000 0.0017210000 142369979 0 402718720 3.8901617527 3.9425649643 3.9940266609 1943 1311867783.4503099918 0.1102613509 0.1218539037 0.2390826792 0.0047729063 0.4852640000 0.0741570000 0.0673700000 0.0310460000 0.3065720000 0.0017230000 142373595 0 402718720 3.8897097111 3.9440834522 3.9936780930 1944 1311867783.4863688946 0.1105009466 0.1218480637 0.2390826792 0.0047726686 0.4678850000 0.0722080000 0.0820600000 0.0000010000 0.3074910000 0.0017210000 142377379 0 402718720 3.8895645142 3.9430959225 3.9935207367 1945 1311867783.5186200142 0.1100583225 0.1218420021 0.2390826792 0.0047718631 0.7729760000 0.0723580000 0.0415710000 0.0308910000 0.3080840000 0.3156590000 142380995 0 402718720 3.8901178837 3.9424660206 3.9933764935 1946 1311867783.5488419533 0.1116317809 0.1218367553 0.2390826792 0.0047720816 0.4374090000 0.0731530000 0.0490490000 0.0000000000 0.3090960000 0.0016840000 142384611 0 402718720 3.8881382942 3.9437320232 3.9936382771 1947 1311867783.5823969841 0.1093292683 0.1218303314 0.2390826792 0.0047724629 0.5013750000 0.0732080000 0.0824740000 0.0311330000 0.3084400000 0.0017170000 142388395 0 402718720 3.8904340267 3.9429454803 3.9925460815 1948 1311867783.6168529987 0.1109052673 0.1218247230 0.2390826792 0.0047718117 0.4373710000 0.0732480000 0.0484850000 0.0000000000 0.3094840000 0.0016990000 142392067 0 402718720 3.8888735771 3.9427766800 3.9927196503 1949 1311867783.6515829563 0.1095642745 0.1218184324 0.2390826792 0.0047706234 0.8104080000 0.0710830000 0.0711160000 0.0308260000 0.3101750000 0.3222520000 142395795 0 402718720 3.8902878761 3.9432816505 3.9925436974 1950 1311867783.6816630363 0.1105465144 0.1218126519 0.2390826792 0.0047702051 0.5207160000 0.0927540000 0.1090290000 0.0000000000 0.3128280000 0.0017100000 142399467 0 402718720 3.8892679214 3.9434726238 3.9927444458 1951 1311867783.7179610729 0.1102514863 0.1218067261 0.2390826792 0.0047697106 0.4833970000 0.0941430000 0.0438040000 0.0306670000 0.3086370000 0.0017100000 142403251 0 402718720 3.8895392418 3.9433307648 3.9925241470 1952 1311867783.7488200665 0.1110782176 0.1218012300 0.2390826792 0.0047689730 0.4742300000 0.0729490000 0.0860310000 0.0000000000 0.3090830000 0.0016990000 142406867 0 402718720 3.8887662888 3.9444932938 3.9930045605 1953 1311867783.7808690071 0.1100405678 0.1217952081 0.2390826792 0.0047680079 0.7858730000 0.0731630000 0.0482510000 0.0308560000 0.3104120000 0.3187470000 142410539 0 402718720 3.8899912834 3.9448447227 3.9931576252 1954 1311867783.8168580532 0.1106480956 0.1217895034 0.2390826792 0.0047688840 0.4508020000 0.0860210000 0.0485080000 0.0000010000 0.3101240000 0.0017020000 142414267 0 402718720 3.8895590305 3.9434323311 3.9930355549 1955 1311867783.8489229679 0.1096128225 0.1217832749 0.2390826792 0.0047686644 0.5038450000 0.0737480000 0.0830570000 0.0311280000 0.3097420000 0.0017210000 142417939 0 402718720 3.8905680180 3.9460704327 3.9941124916 1956 1311867783.8808929920 0.1091240942 0.1217768029 0.2390826792 0.0047677327 0.4719100000 0.0741190000 0.0828370000 0.0000010000 0.3087880000 0.0017180000 142421611 0 402718720 3.8909351826 3.9459605217 3.9938135147 1957 1311867783.9168200493 0.1112426221 0.1217714201 0.2390826792 0.0047736160 0.8146270000 0.0877700000 0.0658030000 0.0311110000 0.3084380000 0.3169900000 142425395 0 402718720 3.8891298771 3.9450016022 3.9946117401 1958 1311867783.9508318901 0.1099154502 0.1217653650 0.2390826792 0.0047725841 0.4533640000 0.0745340000 0.0660760000 0.0000010000 0.3065810000 0.0017180000 142429123 0 402718720 3.8903601170 3.9456508160 3.9950451851 1959 1311867783.9816930294 0.1104982048 0.1217596135 0.2390826792 0.0047727883 0.4899300000 0.0736460000 0.0732130000 0.0311460000 0.3057700000 0.0017210000 142432739 0 402718720 3.8897585869 3.9458575249 3.9957361221 1960 1311867784.0175230503 0.1110015288 0.1217541247 0.2390826792 0.0047720330 0.4568950000 0.0742060000 0.0559100000 0.0000000000 0.3195880000 0.0022890000 142436579 0 402718720 3.8892340660 3.9440295696 3.9954843521 1961 1311867784.0505928993 0.1118029281 0.1217490501 0.2390826792 0.0047723376 0.8207890000 0.0950330000 0.0566130000 0.0384650000 0.3100340000 0.3161290000 142440307 0 402718720 3.8881225586 3.9452619553 3.9958033562 1962 1311867784.0830729008 0.1110846698 0.1217436146 0.2390826792 0.0047715744 0.4708150000 0.0743480000 0.0832160000 0.0000010000 0.3070460000 0.0017150000 142443923 0 402718720 3.8885810375 3.9458541870 3.9960026741 1963 1311867784.1187570095 0.1110448986 0.1217381644 0.2390826792 0.0047716752 0.5017100000 0.0746600000 0.0834740000 0.0306060000 0.3067530000 0.0017350000 142447707 0 402718720 3.8886322975 3.9439449310 3.9956889153 1964 1311867784.1503119469 0.1112156883 0.1217328068 0.2390826792 0.0047710970 0.4380240000 0.0751820000 0.0494120000 0.0000010000 0.3072650000 0.0017290000 142451379 0 402718720 3.8881270885 3.9438881874 3.9960069656 1965 1311867784.1823339462 0.1092173830 0.1217264376 0.2390826792 0.0047702031 0.7933850000 0.0744220000 0.0630230000 0.0305910000 0.3061770000 0.3147100000 142455107 0 402718720 3.8899419308 3.9444084167 3.9962496758 1966 1311867784.2173891068 0.1106336042 0.1217207953 0.2390826792 0.0047699577 0.4707060000 0.0724190000 0.0865800000 0.0000010000 0.3055070000 0.0017100000 142458779 0 402718720 3.8883757591 3.9423451424 3.9961488247 1967 1311867784.2502059937 0.1115724295 0.1217156360 0.2390826792 0.0047699581 0.4728770000 0.0729970000 0.0553530000 0.0310170000 0.3072900000 0.0017120000 142462507 0 402718720 3.8869814873 3.9426860809 3.9964931011 1968 1311867784.2819900513 0.1099123433 0.1217096383 0.2390826792 0.0047696178 0.4381440000 0.0744960000 0.0516860000 0.0000000000 0.3057410000 0.0016910000 142466123 0 402718720 3.8884677887 3.9441263676 3.9969348907 1969 1311867784.3176920414 0.1110731065 0.1217042363 0.2390826792 0.0047703392 0.7991590000 0.0736940000 0.0693260000 0.0305270000 0.3063320000 0.3147560000 142469963 0 402718720 3.8872931004 3.9421527386 3.9970669746 1970 1311867784.3490819931 0.1114269719 0.1216990195 0.2390826792 0.0047696973 0.4709070000 0.0742820000 0.0832980000 0.0000010000 0.3071110000 0.0017240000 142473579 0 402718720 3.8872203827 3.9413349628 3.9972128868 1971 1311867784.3815689087 0.1102469414 0.1216932092 0.2390826792 0.0047696789 0.4896490000 0.0937320000 0.0514720000 0.0311180000 0.3071420000 0.0017270000 142477307 0 402718720 3.8881869316 3.9426372051 3.9974687099 1972 1311867784.4190580845 0.1106070653 0.1216875874 0.2390826792 0.0047691575 0.4689870000 0.0727830000 0.0828450000 0.0000010000 0.3071560000 0.0017060000 142481091 0 402718720 3.8876636028 3.9418158531 3.9971899986 1973 1311867784.4496140480 0.1106984392 0.1216820176 0.2390826792 0.0047679847 0.8158490000 0.0743440000 0.0829030000 0.0310520000 0.3072680000 0.3157670000 142484763 0 402718720 3.8878161907 3.9413940907 3.9976222515 1974 1311867784.4828379154 0.1097501218 0.1216759731 0.2390826792 0.0047677920 0.4368630000 0.0738250000 0.0489130000 0.0000010000 0.3078860000 0.0017190000 142488491 0 402718720 3.8886182308 3.9428489208 3.9979863167 1975 1311867784.5185639858 0.1118775606 0.1216710119 0.2390826792 0.0047670902 0.5129350000 0.0857650000 0.0830280000 0.0306750000 0.3072560000 0.0017180000 142492163 0 402718720 3.8867101669 3.9417514801 3.9983882904 1976 1311867784.5499279499 0.1098281816 0.1216650185 0.2390826792 0.0047670880 0.4818860000 0.0895460000 0.0802200000 0.0000010000 0.3056420000 0.0018150000 142495835 0 402718720 3.8884613514 3.9407823086 3.9980549812 1977 1311867784.5848410130 0.1106222570 0.1216594329 0.2390826792 0.0047665463 0.7901000000 0.0737490000 0.0584100000 0.0310840000 0.3061840000 0.3161850000 142499619 0 402718720 3.8873159885 3.9417874813 3.9982042313 1978 1311867784.6179790497 0.1111805663 0.1216541352 0.2390826792 0.0047660602 0.4481840000 0.0718980000 0.0622660000 0.0000010000 0.3078660000 0.0017110000 142503291 0 402718720 3.8867068291 3.9402902126 3.9981470108 1979 1311867784.6492750645 0.1107839718 0.1216486425 0.2390826792 0.0047650487 0.5019090000 0.0736570000 0.0830020000 0.0310450000 0.3080090000 0.0017120000 142506963 0 402718720 3.8868753910 3.9403684139 3.9982306957 1980 1311867784.6878700256 0.1114067212 0.1216434698 0.2390826792 0.0047655132 0.4367170000 0.0728670000 0.0492290000 0.0000000000 0.3083640000 0.0017090000 142510803 0 402718720 3.8860371113 3.9419407845 3.9987211227 1981 1311867784.7168869972 0.1122014448 0.1216387035 0.2390826792 0.0047648900 0.7922340000 0.0839870000 0.0487300000 0.0305640000 0.3077200000 0.3166940000 142514363 0 402718720 3.8849589825 3.9407033920 3.9984929562 1982 1311867784.7578089237 0.1118571013 0.1216337683 0.2390826792 0.0047663493 0.4358050000 0.0730300000 0.0487030000 0.0000000000 0.3078510000 0.0017080000 142518371 0 402718720 3.8848147392 3.9406538010 3.9987480640 1983 1311867784.7870030403 0.1120977327 0.1216289594 0.2390826792 0.0047652123 0.4801640000 0.0732120000 0.0622480000 0.0310000000 0.3075240000 0.0017110000 142521931 0 402718720 3.8846719265 3.9414796829 3.9992136955 1984 1311867784.8199620247 0.1118260026 0.1216240184 0.2390826792 0.0047654162 0.4351580000 0.0727110000 0.0486350000 0.0000010000 0.3076300000 0.0016960000 142525491 0 402718720 3.8844313622 3.9398229122 3.9987640381 1985 1311867784.8550779819 0.1118506268 0.1216190947 0.2390826792 0.0047644756 0.7877910000 0.0726060000 0.0552770000 0.0309740000 0.3077810000 0.3166260000 142529219 0 402718720 3.8842613697 3.9397330284 3.9988868237 1986 1311867784.8873779774 0.1121890321 0.1216143465 0.2390826792 0.0047633644 0.4538580000 0.0974170000 0.0425470000 0.0000000000 0.3076680000 0.0017000000 142532891 0 402718720 3.8836615086 3.9406492710 3.9993529320 1987 1311867784.9173130989 0.1133546531 0.1216101896 0.2390826792 0.0047625885 0.4670700000 0.0724310000 0.0510510000 0.0310210000 0.3063900000 0.0017130000 142536563 0 402718720 3.8827474117 3.9391543865 3.9991326332 1988 1311867784.9491391182 0.1118431166 0.1216052766 0.2390826792 0.0047621753 0.4678220000 0.0886640000 0.0654800000 0.0000010000 0.3074680000 0.0017000000 142540179 0 402718720 3.8836913109 3.9394788742 3.9989085197 1989 1311867784.9848570824 0.1120005846 0.1216004477 0.2390826792 0.0047613501 0.7754490000 0.0729010000 0.0440450000 0.0310280000 0.3060780000 0.3167760000 142543963 0 402718720 3.8833701611 3.9393687248 3.9989941120 1990 1311867785.0184569359 0.1118904874 0.1215955683 0.2390826792 0.0047602871 0.4578340000 0.0728330000 0.0724550000 0.0000010000 0.3060780000 0.0017870000 142547635 0 402718720 3.8835091591 3.9381978512 3.9986143112 1991 1311867785.0500280857 0.1127091944 0.1215911050 0.2390826792 0.0047594140 0.4864840000 0.0845870000 0.0579990000 0.0310580000 0.3066090000 0.0017040000 142551363 0 402718720 3.8824183941 3.9388520718 3.9990031719 1992 1311867785.0871460438 0.1135663167 0.1215870765 0.2390826792 0.0047584822 0.4667560000 0.0733570000 0.0795850000 0.0000010000 0.3076110000 0.0017110000 142555147 0 402718720 3.8815648556 3.9389698505 3.9992468357 1993 1311867785.1168398857 0.1128596663 0.1215826975 0.2390826792 0.0047582622 0.7907900000 0.0720610000 0.0550590000 0.0305510000 0.3094670000 0.3190810000 142558819 0 402718720 3.8820402622 3.9390761852 3.9987404346 1994 1311867785.1499750614 0.1118472293 0.1215778151 0.2390826792 0.0047574944 0.4495500000 0.0719310000 0.0616860000 0.0000010000 0.3097030000 0.0016930000 142562435 0 402718720 3.8831443787 3.9386415482 3.9985811710 1995 1311867785.1850368977 0.1126569882 0.1215733435 0.2390826792 0.0047567809 0.5011180000 0.0718600000 0.0817490000 0.0310020000 0.3102240000 0.0016930000 142566219 0 402718720 3.8822293282 3.9400272369 3.9989218712 1996 1311867785.2169620991 0.1128643081 0.1215689803 0.2390826792 0.0047557160 0.4444430000 0.0790190000 0.0506920000 0.0000000000 0.3084990000 0.0016950000 142569835 0 402718720 3.8817832470 3.9401168823 3.9986624718 1997 1311867785.2491741180 0.1134722084 0.1215649258 0.2390826792 0.0047545393 0.7942020000 0.0719970000 0.0576970000 0.0310690000 0.3086040000 0.3202410000 142573507 0 402718720 3.8811819553 3.9398541451 3.9989893436 1998 1311867785.2858769894 0.1127837226 0.1215605308 0.2390826792 0.0047534152 0.4822590000 0.1098380000 0.0576640000 0.0000000000 0.3085040000 0.0017010000 142577347 0 402718720 3.8816993237 3.9403700829 3.9988000393 1999 1311867785.3214280605 0.1125489697 0.1215560228 0.2390826792 0.0047524772 0.4822890000 0.0704590000 0.0640860000 0.0309750000 0.3105450000 0.0016990000 142581243 0 402718720 3.8816225529 3.9402182102 3.9986331463 2000 1311867785.3573219776 0.1146893427 0.1215525894 0.2390826792 0.0047528254 0.4725600000 0.0715280000 0.0860930000 0.0000010000 0.3087280000 0.0016930000 142584971 0 402718720 3.8794684410 3.9395077229 3.9991765022 2001 1311867785.3893299103 0.1141049489 0.1215488675 0.2390826792 0.0047519586 0.8241820000 0.0724390000 0.0859680000 0.0310900000 0.3089760000 0.3210910000 142588643 0 402718720 3.8796010017 3.9409816265 3.9988920689 2002 1311867785.4211249352 0.1123331413 0.1215442642 0.2390826792 0.0047518465 0.4720830000 0.0727610000 0.0820620000 0.0000000000 0.3109960000 0.0017050000 142592315 0 402718720 3.8812518120 3.9405896664 3.9986193180 2003 1311867785.4570529461 0.1138596982 0.1215404277 0.2390826792 0.0047519522 0.5021220000 0.0718780000 0.0819260000 0.0310520000 0.3109770000 0.0017020000 142596099 0 402718720 3.8795263767 3.9397580624 3.9986433983 2004 1311867785.4900350571 0.1137017235 0.1215365162 0.2390826792 0.0047513487 0.4375330000 0.0716830000 0.0483230000 0.0000000000 0.3113040000 0.0017010000 142599827 0 402718720 3.8793888092 3.9419333935 3.9989714622 2005 1311867785.5211930275 0.1133012325 0.1215324088 0.2390826792 0.0047505431 0.7998300000 0.0728240000 0.0618600000 0.0310870000 0.3098920000 0.3195780000 142603443 0 402718720 3.8793742657 3.9419469833 3.9989976883 2006 1311867785.5571260452 0.1125547066 0.1215279334 0.2390826792 0.0047509690 0.4488090000 0.0824800000 0.0484700000 0.0000010000 0.3105520000 0.0022810000 142607227 0 402718720 3.8792731762 3.9407613277 3.9990122318 2007 1311867785.5891211033 0.1132857203 0.1215238266 0.2390826792 0.0047503960 0.5067200000 0.0919550000 0.0555550000 0.0377150000 0.3152300000 0.0017060000 142610899 0 402718720 3.8782281876 3.9412577152 3.9992899895 2008 1311867785.6211590767 0.1118458509 0.1215190069 0.2390826792 0.0047591445 0.4429550000 0.0862740000 0.0439680000 0.0000000000 0.3064640000 0.0017080000 142614627 0 402718720 3.8790502548 3.9419984818 3.9987998009 2009 1311867785.6570439339 0.1127843410 0.1215146592 0.2390826792 0.0047616907 0.7827050000 0.0725490000 0.0510550000 0.0310750000 0.3059280000 0.3175370000 142618411 0 402718720 3.8781011105 3.9403588772 3.9988965988 2010 1311867785.6892280579 0.1142385527 0.1215110392 0.2390826792 0.0047607948 0.4433750000 0.0728870000 0.0553430000 0.0000000000 0.3088230000 0.0017130000 142622027 0 402718720 3.8763675690 3.9406540394 3.9989743233 2011 1311867785.7214241028 0.1130979806 0.1215068557 0.2390826792 0.0047621448 0.5256400000 0.0939360000 0.0858320000 0.0310460000 0.3085570000 0.0017200000 142625699 0 402718720 3.8770384789 3.9417719841 3.9987459183 2012 1311867785.7573668957 0.1141404584 0.1215031945 0.2390826792 0.0047617457 0.4503010000 0.0721160000 0.0651280000 0.0000010000 0.3064830000 0.0017920000 142629483 0 402718720 3.8757274151 3.9399538040 3.9984574318 2013 1311867785.7892301083 0.1139144823 0.1214994246 0.2390826792 0.0047614761 0.8226780000 0.0720600000 0.0863370000 0.0311140000 0.3094180000 0.3191680000 142633155 0 402718720 3.8758611679 3.9395539761 3.9986457825 2014 1311867785.8210389614 0.1128823459 0.1214951460 0.2390826792 0.0047604056 0.4505100000 0.0722740000 0.0616680000 0.0000010000 0.3102540000 0.0017030000 142636827 0 402718720 3.8767304420 3.9405004978 3.9984834194 2015 1311867785.8574340343 0.1137853339 0.1214913198 0.2390826792 0.0047598842 0.5002420000 0.0710410000 0.0812980000 0.0310140000 0.3105900000 0.0017040000 142640611 0 402718720 3.8755319118 3.9405510426 3.9984221458 2016 1311867785.8893110752 0.1146254167 0.1214879141 0.2390826792 0.0047590498 0.4629960000 0.0836750000 0.0613580000 0.0000000000 0.3116280000 0.0016950000 142644339 0 402718720 3.8747355938 3.9395923615 3.9986650944 2017 1311867785.9211509228 0.1140776426 0.1214842402 0.2390826792 0.0047590875 0.8238880000 0.0712580000 0.0679490000 0.0310630000 0.3233510000 0.3256800000 142648011 0 402718720 3.8748588562 3.9409511089 3.9989099503 2018 1311867785.9588449001 0.1142271087 0.1214806440 0.2390826792 0.0047595836 0.4536660000 0.0799900000 0.0550470000 0.0000000000 0.3123370000 0.0016940000 142651795 0 402718720 3.8744223118 3.9412660599 3.9987692833 2019 1311867785.9892621040 0.1150774583 0.1214774725 0.2390826792 0.0047585427 0.4771200000 0.0721910000 0.0549710000 0.0311070000 0.3125540000 0.0017090000 142655467 0 402718720 3.8733813763 3.9402725697 3.9990291595 2020 1311867786.0210618973 0.1133668721 0.1214734574 0.2390826792 0.0047576111 0.4451460000 0.0714240000 0.0545870000 0.0000000000 0.3128670000 0.0016960000 142659139 0 402718720 3.8747129440 3.9412562847 3.9990186691 2021 1311867786.0572268963 0.1140797734 0.1214697990 0.2390826792 0.0047574310 0.8238820000 0.0907940000 0.0611780000 0.0310660000 0.3128920000 0.3233070000 142662867 0 402718720 3.8734595776 3.9405755997 3.9992423058 2022 1311867786.0892500877 0.1156414002 0.1214669165 0.2390826792 0.0047564958 0.4466450000 0.0715040000 0.0574680000 0.0000010000 0.3113890000 0.0017010000 142666595 0 402718720 3.8715527058 3.9394431114 3.9994907379 2023 1311867786.1211619377 0.1151602790 0.1214637990 0.2390826792 0.0047555554 0.5066600000 0.0713730000 0.0853560000 0.0312030000 0.3124400000 0.0017010000 142670323 0 402718720 3.8716161251 3.9396564960 3.9995093346 2024 1311867786.1570990086 0.1159325019 0.1214610661 0.2390826792 0.0047545459 0.4742750000 0.0712290000 0.0810450000 0.0000000000 0.3157000000 0.0017000000 142674051 0 402718720 3.8703284264 3.9405884743 3.9998035431 2025 1311867786.1891019344 0.1164043695 0.1214585690 0.2390826792 0.0047538287 0.8030670000 0.0825610000 0.0412050000 0.0311730000 0.3162320000 0.3273250000 142677667 0 402718720 3.8693876266 3.9392652512 3.9998257160 2026 1311867786.2216470242 0.1157151014 0.1214557341 0.2390826792 0.0047528897 0.4863630000 0.0823550000 0.0804000000 0.0000010000 0.3172990000 0.0016830000 142681339 0 402718720 3.8695445061 3.9394636154 3.9997603893 2027 1311867786.2570950985 0.1165312380 0.1214533047 0.2390826792 0.0047519364 0.4825250000 0.0709840000 0.0562730000 0.0311410000 0.3178010000 0.0017000000 142685179 0 402718720 3.8682785034 3.9398963451 3.9999907017 2028 1311867786.2895779610 0.1165952533 0.1214509092 0.2390826792 0.0047516736 0.4689560000 0.0705440000 0.0736640000 0.0000000000 0.3184500000 0.0016980000 142688795 0 402718720 3.8677599430 3.9391343594 3.9999170303 2029 1311867786.3211650848 0.1164493710 0.1214484442 0.2390826792 0.0047513100 0.8129930000 0.0701590000 0.0565560000 0.0311600000 0.3194820000 0.3309760000 142692411 0 402718720 3.8677916527 3.9390008450 4.0000801086 2030 1311867786.3572299480 0.1172291860 0.1214463657 0.2390826792 0.0047507491 0.4763630000 0.0702300000 0.0798700000 0.0000010000 0.3199580000 0.0016900000 142696251 0 402718720 3.8668248653 3.9393892288 4.0004730225 2031 1311867786.3891439438 0.1167868003 0.1214440715 0.2390826792 0.0047496736 0.4983260000 0.0870060000 0.0536280000 0.0311890000 0.3201810000 0.0016930000 142699867 0 402718720 3.8668739796 3.9387855530 4.0001368523 2032 1311867786.4213869572 0.1158694625 0.1214413281 0.2390826792 0.0047492442 0.4786170000 0.0697320000 0.0836650000 0.0000010000 0.3188750000 0.0016830000 142703595 0 402718720 3.8677284718 3.9377758503 4.0003123283 2033 1311867786.4573409557 0.1183791906 0.1214398219 0.2390826792 0.0047527974 0.8405930000 0.0696680000 0.0835200000 0.0311600000 0.3196000000 0.3317960000 142707379 0 402718720 3.8648946285 3.9394586086 4.0009393692 2034 1311867786.4891700745 0.1170017868 0.1214376399 0.2390826792 0.0047540746 0.4450420000 0.0694690000 0.0468450000 0.0000000000 0.3223980000 0.0016770000 142710995 0 402718720 3.8659834862 3.9382109642 4.0009117126 2035 1311867786.5218079090 0.1167317927 0.1214353275 0.2390826792 0.0047543665 0.4776940000 0.0696840000 0.0468830000 0.0311880000 0.3236170000 0.0016820000 142714723 0 402718720 3.8661410809 3.9366135597 4.0011749268 2036 1311867786.5572519302 0.1172879040 0.1214332904 0.2390826792 0.0047534264 0.4917050000 0.0807920000 0.0792900000 0.0000010000 0.3252800000 0.0016900000 142718507 0 402718720 3.8653724194 3.9371526241 4.0013604164 2037 1311867786.5895760059 0.1169814914 0.1214311050 0.2390826792 0.0047528567 0.8450850000 0.0916570000 0.0529310000 0.0311120000 0.3260020000 0.3387160000 142722179 0 402718720 3.8650991917 3.9371662140 4.0014176369 2038 1311867786.6211080551 0.1173583046 0.1214291065 0.2390826792 0.0047530486 0.4493550000 0.0691710000 0.0491310000 0.0000010000 0.3247180000 0.0016870000 142725851 0 402718720 3.8647174835 3.9355595112 4.0016398430 2039 1311867786.6573529243 0.1163708493 0.1214266258 0.2390826792 0.0047528695 0.4952640000 0.0689730000 0.0625450000 0.0312080000 0.3261770000 0.0016810000 142729635 0 402718720 3.8655290604 3.9357826710 4.0016584396 2040 1311867786.6891629696 0.1170173883 0.1214244644 0.2390826792 0.0047520569 0.4628210000 0.0679970000 0.0587630000 0.0000010000 0.3297650000 0.0016710000 142733251 0 402718720 3.8646409512 3.9361121655 4.0021324158 2041 1311867786.7210969925 0.1177781671 0.1214226779 0.2390826792 0.0047511273 0.8792530000 0.0883920000 0.0820450000 0.0311980000 0.3286620000 0.3443020000 142736923 0 402718720 3.8635973930 3.9358952045 4.0024685860 2042 1311867786.7570719719 0.1169260889 0.1214204758 0.2390826792 0.0047503324 0.4848910000 0.0687910000 0.0782640000 0.0000000000 0.3313080000 0.0017140000 142740651 0 402718720 3.8639733791 3.9371986389 4.0024247169 2043 1311867786.7892940044 0.1172655970 0.1214184421 0.2390826792 0.0047492285 0.4815060000 0.0674090000 0.0480710000 0.0310430000 0.3286590000 0.0016780000 142744379 0 402718720 3.8634748459 3.9380605221 4.0028576851 2044 1311867786.8211419582 0.1178323179 0.1214166876 0.2390826792 0.0047482251 0.4822850000 0.0667530000 0.0770220000 0.0000000000 0.3321790000 0.0016640000 142748051 0 402718720 3.8628001213 3.9358820915 4.0033679008 2045 1311867786.8575630188 0.1162498742 0.1214141611 0.2390826792 0.0047490894 0.8323680000 0.0670090000 0.0517970000 0.0311060000 0.3319640000 0.3458110000 142751779 0 402718720 3.8634774685 3.9377207756 4.0035772324 2046 1311867786.8893759251 0.1170581281 0.1214120320 0.2390826792 0.0047510724 0.5075920000 0.0923800000 0.0777700000 0.0000010000 0.3311190000 0.0016810000 142755507 0 402718720 3.8629369736 3.9387302399 4.0040845871 2047 1311867786.9211881161 0.1172827333 0.1214100148 0.2390826792 0.0047536372 0.5095290000 0.0952890000 0.0485530000 0.0312220000 0.3278330000 0.0017640000 142759179 0 402718720 3.8622429371 3.9366419315 4.0043025017 2048 1311867786.9576020241 0.1175414324 0.1214081258 0.2390826792 0.0047524869 0.4459330000 0.0685100000 0.0395130000 0.0000010000 0.3316020000 0.0016730000 142763019 0 402718720 3.8619539738 3.9369165897 4.0047016144 2049 1311867786.9892089367 0.1161799356 0.1214055742 0.2390826792 0.0047522947 0.8531180000 0.0684970000 0.0715980000 0.0311360000 0.3316550000 0.3455040000 142963187 0 402718720 3.8626723289 3.9384677410 4.0048680305 2050 1311867787.0211400986 0.1171730012 0.1214035096 0.2390826792 0.0047513139 0.4840880000 0.0679190000 0.0776880000 0.0000000000 0.3320420000 0.0016680000 143376515 0 402718720 3.8620727062 3.9364132881 4.0049524307 2051 1311867787.0571250916 0.1178365722 0.1214017705 0.2390826792 0.0047503926 0.5430740000 0.0904880000 0.0818380000 0.0311840000 0.3332040000 0.0016350000 143380355 0 402718720 3.8613321781 3.9357643127 4.0052776337 2052 1311867787.0895950794 0.1173986644 0.1213998196 0.2390826792 0.0047497176 0.4538540000 0.0675500000 0.0456320000 0.0000010000 0.3343080000 0.0016600000 143383971 0 402718720 3.8616232872 3.9372298717 4.0056691170 2053 1311867787.1239550114 0.1182645708 0.1213982925 0.2390826792 0.0047494015 0.8548440000 0.0676590000 0.0679670000 0.0312030000 0.3338210000 0.3494400000 143387699 0 402718720 3.8604824543 3.9355232716 4.0057415962 2054 1311867787.1573429108 0.1174757108 0.1213963827 0.2390826792 0.0047487919 0.4687270000 0.0681140000 0.0583200000 0.0000010000 0.3358960000 0.0016730000 143391427 0 402718720 3.8608477116 3.9367012978 4.0057468414 2055 1311867787.1892991066 0.1171575636 0.1213943201 0.2390826792 0.0047478788 0.4914990000 0.0790660000 0.0391570000 0.0309520000 0.3359080000 0.0016680000 143395099 0 402718720 3.8609378338 3.9379334450 4.0057578087 2056 1311867787.2230238914 0.1171933487 0.1213922768 0.2390826792 0.0047479483 0.4871290000 0.0805710000 0.0645300000 0.0000000000 0.3355620000 0.0016590000 143398827 0 402718720 3.8608510494 3.9348764420 4.0058026314 2057 1311867787.2571809292 0.1176766604 0.1213904705 0.2390826792 0.0047475475 0.8691950000 0.0673880000 0.0810970000 0.0307090000 0.3337880000 0.3513940000 143402555 0 402718720 3.8601205349 3.9353926182 4.0061845779 2058 1311867787.2893400192 0.1159562021 0.1213878299 0.2390826792 0.0047466005 0.4901870000 0.0675260000 0.0811330000 0.0000010000 0.3351030000 0.0016710000 143406227 0 402718720 3.8614542484 3.9367554188 4.0062203407 2059 1311867787.3217399120 0.1166815013 0.1213855442 0.2390826792 0.0047469137 0.5107280000 0.0659960000 0.0700380000 0.0309540000 0.3373360000 0.0016650000 143409899 0 402718720 3.8604881763 3.9342119694 4.0059933662 2060 1311867787.3572421074 0.1177242026 0.1213837668 0.2390826792 0.0047467223 0.4618460000 0.0658030000 0.0538070000 0.0000000000 0.3355400000 0.0017200000 143413683 0 402718720 3.8595681190 3.9342904091 4.0064325333 2061 1311867787.3892920017 0.1159666628 0.1213811384 0.2390826792 0.0047457185 0.8817690000 0.0763960000 0.0805720000 0.0311760000 0.3353540000 0.3535080000 143417355 0 402718720 3.8608133793 3.9357714653 4.0058302879 2062 1311867787.4245440960 0.1164958179 0.1213787692 0.2390826792 0.0047452444 0.5155690000 0.0654900000 0.1007360000 0.0000010000 0.3429220000 0.0016520000 143421083 0 402718720 3.8597614765 3.9342305660 4.0056552887 2063 1311867787.4572229385 0.1162257940 0.1213762714 0.2390826792 0.0047444606 0.5198130000 0.0654980000 0.0761840000 0.0311320000 0.3405610000 0.0016660000 143424811 0 402718720 3.8598535061 3.9348192215 4.0057611465 2064 1311867787.4892969131 0.1154321432 0.1213733915 0.2390826792 0.0047434259 0.5019750000 0.0786040000 0.0759900000 0.0000010000 0.3409290000 0.0016560000 143428427 0 402718720 3.8604123592 3.9360835552 4.0055351257 2065 1311867787.5220890045 0.1167033538 0.1213711300 0.2390826792 0.0047424521 0.8456140000 0.0668490000 0.0451520000 0.0311470000 0.3411270000 0.3565630000 143432099 0 402718720 3.8588356972 3.9345815182 4.0055065155 2066 1311867787.5581040382 0.1173170134 0.1213691677 0.2390826792 0.0047415227 0.5034560000 0.0781170000 0.0761550000 0.0000010000 0.3426930000 0.0016570000 143435883 0 402718720 3.8580999374 3.9335749149 4.0053806305 2067 1311867787.5897688866 0.1142037436 0.1213657011 0.2390826792 0.0047406316 0.5037680000 0.0659480000 0.0600790000 0.0311920000 0.3398390000 0.0017500000 143439611 0 402718720 3.8607020378 3.9356024265 4.0047450066 2068 1311867787.6235499382 0.1153151914 0.1213627753 0.2390826792 0.0047399549 0.4720620000 0.0645580000 0.0594930000 0.0000010000 0.3415860000 0.0016540000 143443283 0 402718720 3.8591437340 3.9343869686 4.0046896935 2069 1311867787.6574609280 0.1157124043 0.1213600443 0.2390826792 0.0047395541 0.8510640000 0.0658520000 0.0449020000 0.0311200000 0.3442440000 0.3601600000 143447011 0 402718720 3.8584551811 3.9330387115 4.0043001175 2070 1311867787.6898610592 0.1170377284 0.1213579563 0.2390826792 0.0047395337 0.4747610000 0.0781630000 0.0444360000 0.0000010000 0.3456840000 0.0016540000 143450739 0 402718720 3.8568685055 3.9336428642 4.0044288635 2071 1311867787.7212240696 0.1160047501 0.1213553714 0.2390826792 0.0047384191 0.5105310000 0.0762570000 0.0534510000 0.0307810000 0.3436070000 0.0016490000 143454411 0 402718720 3.8576712608 3.9350495338 4.0041389465 2072 1311867787.7579810619 0.1152883172 0.1213524433 0.2390826792 0.0047383475 0.5064940000 0.0655240000 0.0750880000 0.0000000000 0.3584180000 0.0021520000 143458195 0 402718720 3.8579766750 3.9347193241 4.0041389465 2073 1311867787.7901558876 0.1164341643 0.1213500708 0.2390826792 0.0047373932 0.9380080000 0.0839800000 0.0998180000 0.0380000000 0.3492450000 0.3621730000 143461867 0 402718720 3.8564038277 3.9348497391 4.0039925575 2074 1311867787.8218519688 0.1146631911 0.1213468466 0.2390826792 0.0047377473 0.5040270000 0.0766530000 0.0752240000 0.0000010000 0.3456870000 0.0016480000 143465595 0 402718720 3.8578081131 3.9342241287 4.0033173561 2075 1311867787.8573749065 0.1157998517 0.1213441734 0.2390826792 0.0047369879 0.5250380000 0.0655340000 0.0752450000 0.0311960000 0.3466380000 0.0016560000 143469267 0 402718720 3.8563704491 3.9333584309 4.0032372475 2076 1311867787.8894400597 0.1160956174 0.1213416452 0.2390826792 0.0047359140 0.5233180000 0.0927190000 0.0790880000 0.0000010000 0.3450340000 0.0016520000 143472995 0 402718720 3.8558738232 3.9330103397 4.0031476021 2077 1311867787.9214320183 0.1150864959 0.1213386335 0.2390826792 0.0047348936 0.8592720000 0.0655530000 0.0468240000 0.0312220000 0.3455450000 0.3653210000 143476723 0 402718720 3.8563225269 3.9344773293 4.0026631355 2078 1311867787.9577279091 0.1173769534 0.1213367271 0.2390826792 0.0047346268 0.4956720000 0.0652550000 0.0747710000 0.0000010000 0.3491980000 0.0016480000 143480451 0 402718720 3.8534355164 3.9332792759 4.0026965141 2079 1311867787.9892189503 0.1180609167 0.1213351514 0.2390826792 0.0047337108 0.5019900000 0.0650440000 0.0529830000 0.0307590000 0.3467790000 0.0016440000 143484067 0 402718720 3.8523359299 3.9334564209 4.0027303696 2080 1311867788.0211091042 0.1171836928 0.1213331555 0.2390826792 0.0047329160 0.4921630000 0.0784210000 0.0563620000 0.0000010000 0.3508720000 0.0016510000 143487795 0 402718720 3.8526601791 3.9346880913 4.0019135475 2081 1311867788.0577259064 0.1202541962 0.1213326370 0.2390826792 0.0047330443 0.9034320000 0.0771870000 0.0721900000 0.0312720000 0.3483010000 0.3696950000 143491635 0 402718720 3.8489055634 3.9343810081 4.0019350052 2082 1311867788.0892241001 0.1212314889 0.1213325884 0.2390826792 0.0047327901 0.4968150000 0.0640820000 0.0737920000 0.0000000000 0.3524550000 0.0016350000 143495251 0 402718720 3.8475594521 3.9344885349 4.0023007393 2083 1311867788.1307280064 0.1221307442 0.1213329716 0.2390826792 0.0047340785 0.5105710000 0.0646140000 0.0558870000 0.0311950000 0.3523810000 0.0016480000 143499203 0 402718720 3.8458049297 3.9356536865 4.0022749901 2084 1311867788.1572849751 0.1212333217 0.1213329238 0.2390826792 0.0047330826 0.4975200000 0.0648310000 0.0744250000 0.0000010000 0.3517980000 0.0016440000 143502763 0 402718720 3.8460695744 3.9357242584 4.0025105476 2085 1311867788.1904621124 0.1170298532 0.1213308600 0.2390826792 0.0047353987 0.8720870000 0.0653390000 0.0505060000 0.0311760000 0.3512680000 0.3689960000 143506435 0 402718720 3.8493990898 3.9360740185 4.0021944046 2086 1311867788.2247180939 0.1162365004 0.1213284178 0.2390826792 0.0047344846 0.5008320000 0.0995200000 0.0439360000 0.0000010000 0.3509210000 0.0016390000 143510163 0 402718720 3.8494601250 3.9373383522 4.0021882057 2087 1311867788.2583730221 0.1162040308 0.1213259624 0.2390826792 0.0047347993 0.5282900000 0.0649580000 0.0788180000 0.0312340000 0.3464390000 0.0017480000 143513835 0 402718720 3.8487284184 3.9371647835 4.0022730827 2088 1311867788.2893440723 0.1194898188 0.1213250830 0.2390826792 0.0047338678 0.4598760000 0.0647590000 0.0379580000 0.0000000000 0.3506820000 0.0016430000 143517507 0 402718720 3.8448367119 3.9360210896 4.0030431747 2089 1311867788.3251628876 0.1213760599 0.1213251074 0.2390826792 0.0047335749 0.8778220000 0.0642950000 0.0559610000 0.0311840000 0.3517000000 0.3698390000 143521291 0 402718720 3.8423466682 3.9361898899 4.0035638809 2090 1311867788.3571081161 0.1224489138 0.1213256451 0.2390826792 0.0047328522 0.4973760000 0.0642040000 0.0744510000 0.0000000000 0.3522270000 0.0016550000 143524963 0 402718720 3.8408436775 3.9365718365 4.0038633347 2091 1311867788.3910779953 0.1246730760 0.1213272460 0.2390826792 0.0047318124 0.5248280000 0.0888840000 0.0460860000 0.0312610000 0.3521170000 0.0016470000 143528691 0 402718720 3.8378994465 3.9364633560 4.0045647621 2092 1311867788.4251430035 0.1270089895 0.1213299620 0.2390826792 0.0047309866 0.5019240000 0.0647340000 0.0773040000 0.0000000000 0.3533560000 0.0016440000 143532419 0 402718720 3.8349857330 3.9359192848 4.0049362183 2093 1311867788.4573140144 0.1295493692 0.1213338891 0.2390826792 0.0047309364 0.8724550000 0.0637410000 0.0457130000 0.0307870000 0.3539230000 0.3734490000 143536091 0 402718720 3.8318262100 3.9361712933 4.0048999786 2094 1311867788.4924380779 0.1296229064 0.1213378475 0.2390826792 0.0047306257 0.5009500000 0.0642480000 0.0775540000 0.0000020000 0.3526730000 0.0016450000 143539819 0 402718720 3.8315050602 3.9351682663 4.0055217743 2095 1311867788.5262899399 0.1304456890 0.1213421949 0.2390826792 0.0047295628 0.5304400000 0.0636390000 0.0733170000 0.0312130000 0.3557310000 0.0016380000 143543547 0 402718720 3.8300817013 3.9348521233 4.0056705475 2096 1311867788.5573079586 0.1326807886 0.1213476046 0.2390826792 0.0047291103 0.5312790000 0.0930900000 0.0753830000 0.0000010000 0.3562810000 0.0016420000 143547219 0 402718720 3.8272166252 3.9355204105 4.0058517456 2097 1311867788.5915369987 0.1333169341 0.1213533124 0.2390826792 0.0047282990 0.9060320000 0.0621860000 0.0724140000 0.0312830000 0.3576140000 0.3776640000 143550947 0 402718720 3.8258657455 3.9357666969 4.0056877136 2098 1311867788.6251940727 0.1340345144 0.1213593568 0.2390826792 0.0047276891 0.4761960000 0.0627640000 0.0491400000 0.0000010000 0.3577370000 0.0016360000 143554619 0 402718720 3.8244173527 3.9350266457 4.0058336258 2099 1311867788.6593029499 0.1321917921 0.1213645176 0.2390826792 0.0047268861 0.4997680000 0.0614960000 0.0447760000 0.0306540000 0.3563590000 0.0016310000 143558347 0 402718720 3.8258681297 3.9355013371 4.0056157112 2100 1311867788.6898009777 0.1350624114 0.1213710404 0.2390826792 0.0047270979 0.4886640000 0.0621190000 0.0602310000 0.0000000000 0.3598050000 0.0016130000 143562019 0 402718720 3.8222107887 3.9359812737 4.0055289268 2101 1311867788.7262809277 0.1369909942 0.1213784749 0.2390826792 0.0047265902 0.8944660000 0.0750580000 0.0449980000 0.0313120000 0.3574220000 0.3808010000 143565859 0 402718720 3.8196587563 3.9348442554 4.0061407089 2102 1311867788.7571070194 0.1336178482 0.1213842977 0.2390826792 0.0047265622 0.5028600000 0.0625760000 0.0764880000 0.0000010000 0.3572130000 0.0016400000 143569531 0 402718720 3.8222820759 3.9350106716 4.0051898956 2103 1311867788.7899940014 0.1355764866 0.1213910462 0.2390826792 0.0047268087 0.5124610000 0.0604990000 0.0534470000 0.0310620000 0.3609340000 0.0016260000 143573147 0 402718720 3.8196363449 3.9358606339 4.0048427582 2104 1311867788.8253190517 0.1365989149 0.1213982743 0.2390826792 0.0047264815 0.5010430000 0.0616510000 0.0717230000 0.0000000000 0.3611310000 0.0016260000 143576987 0 402718720 3.8179223537 3.9341278076 4.0049619675 2105 1311867788.8572509289 0.1367312223 0.1214055583 0.2390826792 0.0047253849 0.8933690000 0.0619130000 0.0484160000 0.0313380000 0.3623650000 0.3844770000 143580659 0 402718720 3.8172080517 3.9337298870 4.0046262741 2106 1311867788.8892900944 0.1369585544 0.1214129434 0.2390826792 0.0047252072 0.5360510000 0.0915630000 0.0754460000 0.0000010000 0.3625140000 0.0016270000 143584275 0 402718720 3.8164024353 3.9354820251 4.0044512749 2107 1311867788.9253408909 0.1368941367 0.1214202909 0.2390826792 0.0047252750 0.5344130000 0.0612520000 0.0748640000 0.0314040000 0.3603970000 0.0016210000 143588115 0 402718720 3.8156256676 3.9340741634 4.0042243004 2108 1311867788.9572029114 0.1380652189 0.1214281870 0.2390826792 0.0047244548 0.5152180000 0.0727630000 0.0714340000 0.0000010000 0.3645260000 0.0016160000 143591787 0 402718720 3.8142096996 3.9332606792 4.0040841103 2109 1311867788.9914720058 0.1380917281 0.1214360882 0.2390826792 0.0047238908 0.9211620000 0.0608350000 0.0705680000 0.0313240000 0.3651580000 0.3883990000 143595515 0 402718720 3.8133177757 3.9340398312 4.0041790009 2110 1311867789.0253350735 0.1399935484 0.1214448832 0.2390826792 0.0047238428 0.5043930000 0.0615190000 0.0707720000 0.0000010000 0.3655720000 0.0016220000 143599187 0 402718720 3.8108153343 3.9347240925 4.0043525696 2111 1311867789.0572888851 0.1399700493 0.1214536587 0.2390826792 0.0047229411 0.5452590000 0.0716120000 0.0708180000 0.0309190000 0.3653820000 0.0016190000 143602859 0 402718720 3.8104503155 3.9349987507 4.0048160553 2112 1311867789.0921590328 0.1398829222 0.1214623847 0.2390826792 0.0047224672 0.4805950000 0.0613980000 0.0503130000 0.0000010000 0.3623400000 0.0016250000 143606643 0 402718720 3.8097105026 3.9348964691 4.0046319962 2113 1311867789.1266920567 0.1409451962 0.1214716051 0.2390826792 0.0047222875 0.9224100000 0.0607830000 0.0706610000 0.0313470000 0.3654680000 0.3892500000 143610427 0 402718720 3.8082206249 3.9346635342 4.0051717758 2114 1311867789.1574180126 0.1417696327 0.1214812069 0.2390826792 0.0047214828 0.5100140000 0.0610990000 0.0705910000 0.0000010000 0.3708470000 0.0021200000 143613987 0 402718720 3.8070263863 3.9342036247 4.0046529770 2115 1311867789.1895699501 0.1428785324 0.1214913238 0.2390826792 0.0047208176 0.5574620000 0.0775090000 0.0628050000 0.0384290000 0.3721690000 0.0016270000 143617715 0 402718720 3.8057420254 3.9344086647 4.0055513382 2116 1311867789.2251811028 0.1419209838 0.1215009786 0.2390826792 0.0047198821 0.5322660000 0.0927120000 0.0685120000 0.0000000000 0.3645000000 0.0016220000 143621499 0 402718720 3.8059704304 3.9352352619 4.0050730705 2117 1311867789.2573940754 0.1412706077 0.1215103171 0.2390826792 0.0047202094 0.8945790000 0.0611640000 0.0443430000 0.0315010000 0.3634520000 0.3892490000 143625115 0 402718720 3.8060302734 3.9351537228 4.0045294762 2118 1311867789.2926049232 0.1432236433 0.1215205690 0.2390826792 0.0047191085 0.5039790000 0.0609210000 0.0707330000 0.0000000000 0.3657660000 0.0016180000 143628899 0 402718720 3.8035094738 3.9337720871 4.0048122406 2119 1311867789.3252000809 0.1431223303 0.1215307633 0.2390826792 0.0047180399 0.5361030000 0.0610130000 0.0743420000 0.0310330000 0.3628670000 0.0017180000 143632627 0 402718720 3.8029663563 3.9338862896 4.0046682358 2120 1311867789.3589100838 0.1411565542 0.1215400207 0.2390826792 0.0047170440 0.5056700000 0.0608610000 0.0742380000 0.0000000000 0.3640850000 0.0015930000 143636299 0 402718720 3.8041880131 3.9346442223 4.0039486885 2121 1311867789.3897531033 0.1430370063 0.1215501560 0.2390826792 0.0047169618 0.9397410000 0.0740190000 0.0704820000 0.0314670000 0.3670780000 0.3917450000 143639971 0 402718720 3.8016686440 3.9346110821 4.0036964417 2122 1311867789.4252359867 0.1432904005 0.1215604012 0.2390826792 0.0047165228 0.4886180000 0.0608580000 0.0532700000 0.0000010000 0.3679220000 0.0016220000 143643755 0 402718720 3.8006269932 3.9340276718 4.0032734871 2123 1311867789.4577910900 0.1416719109 0.1215698744 0.2390826792 0.0047162009 0.5366020000 0.0599470000 0.0701890000 0.0315010000 0.3684360000 0.0016100000 143647371 0 402718720 3.8015339375 3.9344785213 4.0029735565 2124 1311867789.4892559052 0.1426816583 0.1215798140 0.2390826792 0.0047155270 0.4926660000 0.0600210000 0.0471010000 0.0000010000 0.3780170000 0.0020810000 143651099 0 402718720 3.7998635769 3.9349060059 4.0023813248 2125 1311867789.5256059170 0.1446397454 0.1215906657 0.2390826792 0.0047146509 0.9717940000 0.0749130000 0.0840070000 0.0383640000 0.3735690000 0.3960050000 143654827 0 402718720 3.7973556519 3.9343852997 4.0028066635 2126 1311867789.5572779179 0.1441653371 0.1216012841 0.2390826792 0.0047139571 0.4936370000 0.0754450000 0.0435500000 0.0000010000 0.3681230000 0.0016060000 143658499 0 402718720 3.7971053123 3.9336946011 4.0027241707 2127 1311867789.5892720222 0.1450459957 0.1216123065 0.2390826792 0.0047129401 0.5275930000 0.0601280000 0.0579690000 0.0310620000 0.3719030000 0.0016080000 143662115 0 402718720 3.7957289219 3.9334030151 4.0032548904 2128 1311867789.6253700256 0.1471620500 0.1216243130 0.2390826792 0.0047135731 0.5123050000 0.0703140000 0.0629610000 0.0000010000 0.3725170000 0.0015900000 143665955 0 402718720 3.7927653790 3.9343941212 4.0032110214 2129 1311867789.6574499607 0.1436857879 0.1216346754 0.2390826792 0.0047135032 0.9318540000 0.0726210000 0.0522700000 0.0314190000 0.3719130000 0.3987130000 143669627 0 402718720 3.7953982353 3.9350202084 4.0020484924 2130 1311867789.6894960403 0.1443897784 0.1216453585 0.2390826792 0.0047126245 0.5172350000 0.0593910000 0.0693070000 0.0000000000 0.3809880000 0.0020870000 143673243 0 402718720 3.7939655781 3.9355626106 4.0023288727 2131 1311867789.7253561020 0.1448506713 0.1216562479 0.2390826792 0.0047149242 0.5858540000 0.0745090000 0.0910070000 0.0384180000 0.3753440000 0.0016100000 143677027 0 402718720 3.7927548885 3.9372923374 4.0022625923 2132 1311867789.7572269440 0.1432425976 0.1216663728 0.2390826792 0.0047141374 0.5102290000 0.0600730000 0.0735240000 0.0000010000 0.3701070000 0.0016060000 143680699 0 402718720 3.7935543060 3.9382209778 4.0020604134 2133 1311867789.7893610001 0.1409720927 0.1216754238 0.2390826792 0.0047148806 0.9310190000 0.0610850000 0.0705090000 0.0314880000 0.3685590000 0.3944210000 143684371 0 402718720 3.7949533463 3.9383704662 4.0013580322 2134 1311867789.8253350258 0.1439744532 0.1216858732 0.2390826792 0.0047144716 0.5097330000 0.0808730000 0.0556930000 0.0000000000 0.3665930000 0.0016190000 143688155 0 402718720 3.7916247845 3.9378924370 4.0023183823 2135 1311867789.8573670387 0.1440580934 0.1216963520 0.2390826792 0.0047133937 0.5364240000 0.0605360000 0.0701190000 0.0314670000 0.3677500000 0.0016190000 143691883 0 402718720 3.7909028530 3.9381387234 4.0020842552 2136 1311867789.8893530369 0.1409964263 0.1217053876 0.2390826792 0.0047126791 0.4901940000 0.0735730000 0.0441160000 0.0000010000 0.3659330000 0.0016290000 143695499 0 402718720 3.7931067944 3.9387395382 4.0016846657 2137 1311867789.9253480434 0.1430432945 0.1217153726 0.2390826792 0.0047120217 0.9302100000 0.0613290000 0.0745950000 0.0315450000 0.3662840000 0.3914970000 143699283 0 402718720 3.7903068066 3.9385766983 4.0027713776 2138 1311867789.9573481083 0.1408651173 0.1217243294 0.2390826792 0.0047117906 0.5049350000 0.0616500000 0.0730770000 0.0000000000 0.3636360000 0.0016280000 143702899 0 402718720 3.7914769650 3.9387381077 4.0019507408 2139 1311867789.9892580509 0.1427265257 0.1217341481 0.2390826792 0.0047110066 0.5250050000 0.0744830000 0.0474670000 0.0314740000 0.3649980000 0.0016190000 143706571 0 402718720 3.7890162468 3.9393639565 4.0023407936 2140 1311867790.0253860950 0.1457553506 0.1217453730 0.2390826792 0.0047109852 0.4981540000 0.0613290000 0.0646860000 0.0000010000 0.3654560000 0.0016190000 143710411 0 402718720 3.7851557732 3.9392974377 4.0032291412 2141 1311867790.0572309494 0.1461997777 0.1217567950 0.2390826792 0.0047099219 0.9191520000 0.0734600000 0.0532540000 0.0315200000 0.3654570000 0.3904150000 143714027 0 402718720 3.7840902805 3.9396748543 4.0036954880 2142 1311867790.0896899700 0.1438436806 0.1217671063 0.2390826792 0.0047102343 0.4979790000 0.0611830000 0.0649170000 0.0000010000 0.3652940000 0.0016250000 143717755 0 402718720 3.7858703136 3.9397544861 4.0033621788 2143 1311867790.1257700920 0.1445677280 0.1217777459 0.2390826792 0.0047094905 0.5355600000 0.0613120000 0.0709150000 0.0315180000 0.3652250000 0.0016270000 143721539 0 402718720 3.7844011784 3.9402651787 4.0035843849 2144 1311867790.1572160721 0.1414708197 0.1217869311 0.2390826792 0.0047090847 0.5108120000 0.0841500000 0.0562190000 0.0000000000 0.3638430000 0.0016260000 143725155 0 402718720 3.7867982388 3.9408702850 4.0033278465 2145 1311867790.1894400120 0.1448894590 0.1217977015 0.2390826792 0.0047093433 0.9088940000 0.0611270000 0.0622570000 0.0316240000 0.3614220000 0.3874790000 143728883 0 402718720 3.7829949856 3.9405469894 4.0042877197 2146 1311867790.2254109383 0.1430296898 0.1218075952 0.2390826792 0.0047085839 0.5054830000 0.0613130000 0.0747720000 0.0000010000 0.3627530000 0.0016190000 143732667 0 402718720 3.7842531204 3.9413080215 4.0041069984 2147 1311867790.2576739788 0.1438017190 0.1218178394 0.2390826792 0.0047075254 0.5174530000 0.0616940000 0.0534030000 0.0315560000 0.3641950000 0.0016250000 143736395 0 402718720 3.7827668190 3.9415926933 4.0043225288 2148 1311867790.2894508839 0.1453538090 0.1218287965 0.2390826792 0.0047070781 0.4787040000 0.0603970000 0.0472990000 0.0000010000 0.3642940000 0.0016240000 143740011 0 402718720 3.7808790207 3.9408590794 4.0046930313 2149 1311867790.3254859447 0.1472890526 0.1218406440 0.2390826792 0.0047078312 0.9103160000 0.0615780000 0.0591860000 0.0315510000 0.3639770000 0.3890650000 143743795 0 402718720 3.7784340382 3.9413335323 4.0054268837 2150 1311867790.3573629856 0.1472776532 0.1218524752 0.2390826792 0.0047080146 0.5025540000 0.0612520000 0.0706840000 0.0000000000 0.3639650000 0.0016240000 143747467 0 402718720 3.7780048847 3.9411466122 4.0052328110 2151 1311867790.3896288872 0.1453578770 0.1218634028 0.2390826792 0.0047070474 0.5217720000 0.0727570000 0.0501440000 0.0316680000 0.3603110000 0.0017190000 143751139 0 402718720 3.7791795731 3.9415528774 4.0046629906 2152 1311867790.4259679317 0.1462434381 0.1218747318 0.2390826792 0.0047095893 0.4784600000 0.0603230000 0.0497090000 0.0000010000 0.3618080000 0.0016240000 143754979 0 402718720 3.7780215740 3.9419550896 4.0046863556 2153 1311867790.4603750706 0.1474317312 0.1218866023 0.2390826792 0.0047101455 0.9209250000 0.0605110000 0.0703060000 0.0310770000 0.3643510000 0.3897340000 143758707 0 402718720 3.7761607170 3.9417421818 4.0051398277 2154 1311867790.4893760681 0.1460977346 0.1218978423 0.2390826792 0.0047104756 0.5260070000 0.0826320000 0.0744960000 0.0000010000 0.3622110000 0.0016170000 143762267 0 402718720 3.7770035267 3.9420340061 4.0049490929 2155 1311867790.5260839462 0.1479574889 0.1219099350 0.2390826792 0.0047123437 0.5196910000 0.0617300000 0.0561140000 0.0317170000 0.3634980000 0.0016300000 143766051 0 402718720 3.7747602463 3.9427440166 4.0050296783 2156 1311867790.5578188896 0.1489747316 0.1219224882 0.2390826792 0.0047137210 0.5286570000 0.0836530000 0.0747600000 0.0000010000 0.3635970000 0.0016350000 143769667 0 402718720 3.7734920979 3.9432513714 4.0056362152 2157 1311867790.5941619873 0.1512818485 0.1219360994 0.2390826792 0.0047162994 0.9076460000 0.0613060000 0.0562270000 0.0316980000 0.3628550000 0.3905540000 143773451 0 402718720 3.7709577084 3.9428429604 4.0054802895 2158 1311867790.6255199909 0.1515130699 0.1219498052 0.2390826792 0.0047156106 0.4676370000 0.0611820000 0.0378540000 0.0000000000 0.3619730000 0.0016250000 143777179 0 402718720 3.7700664997 3.9429235458 4.0055823326 2159 1311867790.6573970318 0.1522375345 0.1219638338 0.2390826792 0.0047164203 0.5060470000 0.0609020000 0.0416330000 0.0316020000 0.3652950000 0.0016190000 143780739 0 402718720 3.7685105801 3.9431502819 4.0055017471 2160 1311867790.6901810169 0.1525656730 0.1219780013 0.2390826792 0.0047158876 0.4916940000 0.0603600000 0.0587340000 0.0000010000 0.3659430000 0.0016100000 143784467 0 402718720 3.7677233219 3.9431734085 4.0057768822 2161 1311867790.7253530025 0.1515894383 0.1219917039 0.2390826792 0.0047150289 0.9225320000 0.0730490000 0.0559960000 0.0317590000 0.3639090000 0.3928120000 143788195 0 402718720 3.7682456970 3.9430549145 4.0058164597 2162 1311867790.7575750351 0.1502890736 0.1220047924 0.2390826792 0.0047139698 0.4823700000 0.0597050000 0.0493170000 0.0000010000 0.3667330000 0.0016090000 143791867 0 402718720 3.7687191963 3.9443182945 4.0049672127 2163 1311867790.7912769318 0.1515084207 0.1220184326 0.2390826792 0.0047157214 0.5067790000 0.0615070000 0.0439170000 0.0318040000 0.3629320000 0.0016100000 143795595 0 402718720 3.7670912743 3.9461212158 4.0053448677 2164 1311867790.8261909485 0.1516142040 0.1220321090 0.2390826792 0.0047151517 0.5050220000 0.0847380000 0.0476340000 0.0000010000 0.3659610000 0.0016190000 143799379 0 402718720 3.7664196491 3.9458005428 4.0055465698 2165 1311867790.8573698997 0.1506469697 0.1220453260 0.2390826792 0.0047142151 0.9025210000 0.0612190000 0.0500940000 0.0317590000 0.3622990000 0.3921330000 143803051 0 402718720 3.7670576572 3.9457216263 4.0058507919 2166 1311867790.8950428963 0.1519698352 0.1220591416 0.2390826792 0.0047146628 0.4924140000 0.0613300000 0.0588990000 0.0000010000 0.3655250000 0.0016130000 143806835 0 402718720 3.7654554844 3.9470138550 4.0065107346 2167 1311867790.9258179665 0.1511771828 0.1220725786 0.2390826792 0.0047140891 0.5144710000 0.0752140000 0.0364030000 0.0317000000 0.3645290000 0.0016250000 143810507 0 402718720 3.7659263611 3.9482798576 4.0064167976 2168 1311867790.9607090950 0.1500179768 0.1220854686 0.2390826792 0.0047140572 0.5036860000 0.0619510000 0.0712750000 0.0000000000 0.3637840000 0.0016200000 143814235 0 402718720 3.7663331032 3.9486312866 4.0063056946 2169 1311867790.9944651127 0.1482074559 0.1220975119 0.2390826792 0.0047157900 0.9225050000 0.0621960000 0.0711830000 0.0317140000 0.3633500000 0.3890120000 143817963 0 402718720 3.7676739693 3.9484281540 4.0062603951 2170 1311867791.0299000740 0.1501135677 0.1221104225 0.2390826792 0.0047162238 0.5024310000 0.0613330000 0.0712890000 0.0000010000 0.3631800000 0.0016290000 143821747 0 402718720 3.7654063702 3.9493525028 4.0067501068 2171 1311867791.0577330589 0.1493033767 0.1221229481 0.2390826792 0.0047159122 0.5415090000 0.0741870000 0.0693150000 0.0317420000 0.3592260000 0.0017200000 143825195 0 402718720 3.7656450272 3.9501173496 4.0066123009 2172 1311867791.0913140774 0.1495867074 0.1221355925 0.2390826792 0.0047148632 0.4855020000 0.0623710000 0.0540510000 0.0000010000 0.3624200000 0.0016220000 143828979 0 402718720 3.7650218010 3.9505376816 4.0067567825 2173 1311867791.1254060268 0.1488887817 0.1221479042 0.2390826792 0.0047156176 0.9468210000 0.0780870000 0.0636260000 0.0393860000 0.3737890000 0.3869170000 143832707 0 402718720 3.7651600838 3.9503626823 4.0063972473 2174 1311867791.1664540768 0.1489568204 0.1221602358 0.2390826792 0.0047167504 0.5030030000 0.0627760000 0.0722540000 0.0000010000 0.3613200000 0.0016290000 143836659 0 402718720 3.7645897865 3.9511895180 4.0065093040 2175 1311867791.1905651093 0.1499405950 0.1221730083 0.2390826792 0.0047167149 0.5498880000 0.0742800000 0.0660160000 0.0316730000 0.3702280000 0.0021170000 143840107 0 402718720 3.7635464668 3.9503142834 4.0069990158 2176 1311867791.2257969379 0.1524137855 0.1221869058 0.2390826792 0.0047170824 0.5517440000 0.0777740000 0.0944330000 0.0000010000 0.3728760000 0.0016210000 143843891 0 402718720 3.7605035305 3.9494085312 4.0072302818 2177 1311867791.2579009533 0.1526982635 0.1222009211 0.2390826792 0.0047171747 0.9214840000 0.0621130000 0.0716370000 0.0316850000 0.3625880000 0.3883760000 143847507 0 402718720 3.7595205307 3.9487855434 4.0075531006 2178 1311867791.2920219898 0.1526050419 0.1222148807 0.2390826792 0.0047161434 0.5029000000 0.0615550000 0.0707520000 0.0000000000 0.3639130000 0.0016240000 143851235 0 402718720 3.7591955662 3.9492816925 4.0076823235 2179 1311867791.3277790546 0.1528341919 0.1222289327 0.2390826792 0.0047164312 0.5304630000 0.0621250000 0.0652550000 0.0318030000 0.3646270000 0.0016230000 143855019 0 402718720 3.7585508823 3.9492480755 4.0075531006 2180 1311867791.3597049713 0.1534486115 0.1222432537 0.2390826792 0.0047178124 0.5156720000 0.0728540000 0.0707680000 0.0000010000 0.3653340000 0.0016170000 143858747 0 402718720 3.7573850155 3.9497520924 4.0080904961 2181 1311867791.3896780014 0.1529591382 0.1222573371 0.2390826792 0.0047171203 0.9386190000 0.0717530000 0.0741980000 0.0318120000 0.3627460000 0.3930830000 143862363 0 402718720 3.7571430206 3.9501540661 4.0076394081 2182 1311867791.4270040989 0.1536251754 0.1222717128 0.2390826792 0.0047169157 0.5042850000 0.0846930000 0.0501070000 0.0000000000 0.3627930000 0.0016120000 143866203 0 402718720 3.7558372021 3.9500629902 4.0081477165 2183 1311867791.4574470520 0.1544722617 0.1222864634 0.2390826792 0.0047160955 0.5397880000 0.0616630000 0.0748240000 0.0318430000 0.3647650000 0.0016120000 143869819 0 402718720 3.7544622421 3.9495406151 4.0083756447 2184 1311867791.4916520119 0.1570197642 0.1223023669 0.2390826792 0.0047181130 0.5061750000 0.0605330000 0.0700080000 0.0000010000 0.3689440000 0.0016070000 143873547 0 402718720 3.7515058517 3.9491038322 4.0089545250 2185 1311867791.5275359154 0.1538817585 0.1223168197 0.2390826792 0.0047175185 0.9176450000 0.0611430000 0.0534120000 0.0317480000 0.3687260000 0.3975030000 143877331 0 402718720 3.7542455196 3.9500710964 4.0087161064 2186 1311867791.5593819618 0.1534571648 0.1223310651 0.2390826792 0.0047178121 0.5313940000 0.0848480000 0.0740350000 0.0000010000 0.3658000000 0.0016110000 143881003 0 402718720 3.7541961670 3.9511468410 4.0089311600 2187 1311867791.5894811153 0.1511089951 0.1223442237 0.2390826792 0.0047171556 0.5159980000 0.0615450000 0.0475920000 0.0317450000 0.3684330000 0.0016150000 143884619 0 402718720 3.7559580803 3.9520854950 4.0082569122 2188 1311867791.6275899410 0.1508549601 0.1223572542 0.2390826792 0.0047164052 0.4843490000 0.0620470000 0.0476060000 0.0000010000 0.3679840000 0.0016170000 143888459 0 402718720 3.7557609081 3.9515392780 4.0082063675 2189 1311867791.6574349403 0.1529430449 0.1223712267 0.2390826792 0.0047155682 0.9074510000 0.0606440000 0.0470110000 0.0316590000 0.3675270000 0.3955440000 143892131 0 402718720 3.7534959316 3.9514017105 4.0085978508 2190 1311867791.6894969940 0.1531738788 0.1223852919 0.2390826792 0.0047149056 0.5060490000 0.0611510000 0.0701860000 0.0000010000 0.3680240000 0.0016060000 143895747 0 402718720 3.7530677319 3.9510366917 4.0087695122 2191 1311867791.7263259888 0.1538079232 0.1223996335 0.2390826792 0.0047141552 0.5566490000 0.0801630000 0.0699980000 0.0317740000 0.3680550000 0.0016140000 143899587 0 402718720 3.7521903515 3.9513792992 4.0087809563 2192 1311867791.7602820396 0.1526955217 0.1224134547 0.2390826792 0.0047131538 0.5068210000 0.0612330000 0.0737220000 0.0000010000 0.3652030000 0.0016060000 143903315 0 402718720 3.7531065941 3.9523100853 4.0087461472 2193 1311867791.7897930145 0.1515222192 0.1224267282 0.2390826792 0.0047126876 0.9226970000 0.0609350000 0.0585860000 0.0317490000 0.3687150000 0.3976520000 143906931 0 402718720 3.7541029453 3.9520630836 4.0082802773 2194 1311867791.8265190125 0.1540414095 0.1224411378 0.2390826792 0.0047124293 0.5070330000 0.0609920000 0.0700790000 0.0000010000 0.3692700000 0.0016010000 143910715 0 402718720 3.7514402866 3.9518377781 4.0087370872 2195 1311867791.8574469090 0.1545420587 0.1224557623 0.2390826792 0.0047120911 0.5096270000 0.0601450000 0.0410180000 0.0316640000 0.3701160000 0.0016070000 143914387 0 402718720 3.7509951591 3.9521152973 4.0094299316 2196 1311867791.8895421028 0.1537343413 0.1224700058 0.2390826792 0.0047110212 0.5185570000 0.0725640000 0.0730190000 0.0000010000 0.3662640000 0.0015970000 143918003 0 402718720 3.7515451908 3.9531283379 4.0090403557 2197 1311867791.9276258945 0.1548825353 0.1224847588 0.2390826792 0.0047104957 0.9467620000 0.0801260000 0.0596480000 0.0317270000 0.3700480000 0.4000530000 143921843 0 402718720 3.7500751019 3.9530496597 4.0087780952 2198 1311867791.9574968815 0.1524180323 0.1224983773 0.2390826792 0.0047100132 0.4853980000 0.0610450000 0.0471700000 0.0000000000 0.3704100000 0.0015980000 143925459 0 402718720 3.7524063587 3.9538881779 4.0089063644 2199 1311867791.9918000698 0.1528864503 0.1225121963 0.2390826792 0.0047096129 0.5394700000 0.0607690000 0.0696790000 0.0313240000 0.3709330000 0.0016000000 143929075 0 402718720 3.7517530918 3.9529793262 4.0088014603 2200 1311867792.0277240276 0.1542791277 0.1225266358 0.2390826792 0.0047094184 0.5197660000 0.0727560000 0.0691570000 0.0000010000 0.3710600000 0.0015880000 143932803 0 402718720 3.7502338886 3.9533019066 4.0090270042 2201 1311867792.0615789890 0.1551979482 0.1225414797 0.2390826792 0.0047086975 0.9460800000 0.0947170000 0.0411630000 0.0312840000 0.3713610000 0.4024850000 143936643 0 402718720 3.7490231991 3.9532990456 4.0095615387 2202 1311867792.0946090221 0.1556241512 0.1225565036 0.2390826792 0.0047077566 0.5092440000 0.0605410000 0.0731600000 0.0000010000 0.3685030000 0.0016860000 143940259 0 402718720 3.7483747005 3.9535739422 4.0094003677 2203 1311867792.1256630421 0.1565643847 0.1225719407 0.2390826792 0.0047071491 0.5170820000 0.0601170000 0.0491960000 0.0318420000 0.3692320000 0.0015890000 143943931 0 402718720 3.7471446991 3.9537587166 4.0091571808 2204 1311867792.1595768929 0.1551066488 0.1225867023 0.2390826792 0.0047064036 0.5166400000 0.0730940000 0.0633850000 0.0000000000 0.3734500000 0.0015810000 143947659 0 402718720 3.7482528687 3.9543423653 4.0091276169 2205 1311867792.1948819160 0.1536746770 0.1226008012 0.2390826792 0.0047087856 0.9473450000 0.0599640000 0.0689210000 0.0317620000 0.3742620000 0.4073370000 143951443 0 402718720 3.7494423389 3.9544312954 4.0090985298 2206 1311867792.2253580093 0.1542208344 0.1226151348 0.2390826792 0.0047138571 0.5211990000 0.0710420000 0.0718610000 0.0000010000 0.3716060000 0.0015810000 143955059 0 402718720 3.7481102943 3.9554305077 4.0090036392 2207 1311867792.2575860023 0.1558383852 0.1226301884 0.2390826792 0.0047128564 0.5335840000 0.0585460000 0.0620530000 0.0316050000 0.3747410000 0.0015750000 143958731 0 402718720 3.7460696697 3.9558587074 4.0091710091 2208 1311867792.2995440960 0.1559624672 0.1226452846 0.2390826792 0.0047125966 0.5106430000 0.0598400000 0.0687370000 0.0000010000 0.3753250000 0.0015790000 143962683 0 402718720 3.7452666759 3.9546489716 4.0091004372 2209 1311867792.3314530849 0.1549493223 0.1226599084 0.2390826792 0.0047120421 0.9923120000 0.0591380000 0.0786880000 0.0396720000 0.3897680000 0.4199020000 143966355 0 402718720 3.7458999157 3.9552972317 4.0090465546 2210 1311867792.3589100838 0.1559281498 0.1226749619 0.2390826792 0.0047115617 0.5262440000 0.0728160000 0.0715100000 0.0000010000 0.3752010000 0.0015740000 143969859 0 402718720 3.7447178364 3.9551260471 4.0093646049 2211 1311867792.3954761028 0.1571790427 0.1226905675 0.2390826792 0.0047105820 0.5598480000 0.0851840000 0.0600120000 0.0319240000 0.3759580000 0.0015830000 143973699 0 402718720 3.7430214882 3.9553418159 4.0094113350 2212 1311867792.4281890392 0.1543340683 0.1227048729 0.2390826792 0.0047101325 0.5048540000 0.0584780000 0.0621520000 0.0000010000 0.3775290000 0.0015830000 143977371 0 402718720 3.7452182770 3.9556827545 4.0085654259 2213 1311867792.4589219093 0.1558956951 0.1227198710 0.2390826792 0.0047094604 0.9476520000 0.0576940000 0.0506680000 0.0315900000 0.3774780000 0.4245070000 143980987 0 402718720 3.7433300018 3.9555449486 4.0084614754 2214 1311867792.4948880672 0.1581631154 0.1227358797 0.2390826792 0.0047091668 0.5145310000 0.0733480000 0.0528300000 0.0000010000 0.3816540000 0.0015690000 143984771 0 402718720 3.7406940460 3.9548723698 4.0089535713 2215 1311867792.5256149769 0.1578360647 0.1227517263 0.2390826792 0.0047082576 0.5203910000 0.0577910000 0.0452970000 0.0316510000 0.3789580000 0.0015420000 143988443 0 402718720 3.7408506870 3.9546973705 4.0089764595 2216 1311867792.5579619408 0.1578092128 0.1227675465 0.2390826792 0.0047077587 0.5267720000 0.0712120000 0.0707970000 0.0000000000 0.3781080000 0.0015620000 143992059 0 402718720 3.7403013706 3.9552168846 4.0082941055 2217 1311867792.5937440395 0.1576521695 0.1227832815 0.2390826792 0.0047068390 0.9618550000 0.0577020000 0.0504670000 0.0342140000 0.3931160000 0.4212140000 143995787 0 402718720 3.7403144836 3.9544594288 4.0082149506 2218 1311867792.6254990101 0.1562173814 0.1227983555 0.2390826792 0.0047058398 0.5118530000 0.0581070000 0.0669420000 0.0000010000 0.3801730000 0.0015600000 143999403 0 402718720 3.7413892746 3.9550402164 4.0082011223 2219 1311867792.6587610245 0.1563061178 0.1228134559 0.2390826792 0.0047052131 0.5672600000 0.0832360000 0.0646170000 0.0313040000 0.3813850000 0.0015450000 144003131 0 402718720 3.7409853935 3.9550940990 4.0080966949 2220 1311867792.6947619915 0.1562971473 0.1228285386 0.2390826792 0.0047044514 0.4971330000 0.0705570000 0.0416260000 0.0000010000 0.3779500000 0.0016430000 144006915 0 402718720 3.7406108379 3.9540870190 4.0081181526 2221 1311867792.7254660130 0.1549522281 0.1228430023 0.2390826792 0.0047035215 0.9357390000 0.0579110000 0.0348250000 0.0317260000 0.3830930000 0.4231020000 144010587 0 402718720 3.7419385910 3.9547109604 4.0075845718 2222 1311867792.7574810982 0.1552231610 0.1228575748 0.2390826792 0.0047024704 0.5171440000 0.0575020000 0.0696110000 0.0000000000 0.3833360000 0.0015530000 144014259 0 402718720 3.7410941124 3.9545536041 4.0077419281 2223 1311867792.7968890667 0.1549258828 0.1228720005 0.2390826792 0.0047021649 0.5398270000 0.0569620000 0.0605320000 0.0316980000 0.3839670000 0.0015470000 144018155 0 402718720 3.7409222126 3.9548220634 4.0076069832 2224 1311867792.8254449368 0.1569762826 0.1228873351 0.2390826792 0.0047022221 0.5147440000 0.0574690000 0.0659160000 0.0000010000 0.3846750000 0.0015390000 144021659 0 402718720 3.7386791706 3.9544053078 4.0083727837 2225 1311867792.8578031063 0.1559572220 0.1229021980 0.2390826792 0.0047023852 0.9669120000 0.0559630000 0.0547470000 0.0316630000 0.3852530000 0.4336170000 144025331 0 402718720 3.7390019894 3.9548540115 4.0081148148 2226 1311867792.8974819183 0.1528615355 0.1229156568 0.2390826792 0.0047017855 0.5617450000 0.0695530000 0.0850600000 0.0000000000 0.3994570000 0.0019800000 144029283 0 402718720 3.7413394451 3.9555141926 4.0075292587 2227 1311867792.9254279137 0.1524193734 0.1229289050 0.2390826792 0.0047008173 0.5373400000 0.0584550000 0.0544840000 0.0316510000 0.3860390000 0.0015530000 144032787 0 402718720 3.7415101528 3.9552969933 4.0076074600 2228 1311867792.9580180645 0.1555883586 0.1229435637 0.2390826792 0.0047025499 0.5213050000 0.0799490000 0.0517900000 0.0000010000 0.3828590000 0.0015360000 144036515 0 402718720 3.7380237579 3.9557144642 4.0076923370 2229 1311867792.9958879948 0.1554404646 0.1229581428 0.2390826792 0.0047025495 0.9858320000 0.0671540000 0.0649480000 0.0316500000 0.3868540000 0.4300420000 144040355 0 402718720 3.7372562885 3.9554202557 4.0081458092 2230 1311867793.0254249573 0.1532427967 0.1229717234 0.2390826792 0.0047026865 0.4989940000 0.0555810000 0.0491090000 0.0000000000 0.3875790000 0.0015300000 144043915 0 402718720 3.7387828827 3.9556555748 4.0077548027 2231 1311867793.0575890541 0.1525495499 0.1229849810 0.2390826792 0.0047024014 0.5370060000 0.0727730000 0.0403410000 0.0317760000 0.3854300000 0.0015250000 144047587 0 402718720 3.7386131287 3.9559597969 4.0076684952 2232 1311867793.0956139565 0.1562801152 0.1229998982 0.2390826792 0.0047018271 0.5189890000 0.0686290000 0.0539450000 0.0000000000 0.3896950000 0.0015300000 144051483 0 402718720 3.7341010571 3.9556336403 4.0085611343 2233 1311867793.1253910065 0.1548986733 0.1230141834 0.2390826792 0.0047013284 0.9851500000 0.0549970000 0.0676590000 0.0317220000 0.3886310000 0.4369500000 144055043 0 402718720 3.7350502014 3.9561038017 4.0084443092 2234 1311867793.1573770046 0.1554517299 0.1230287033 0.2390826792 0.0047009374 0.5058720000 0.0546650000 0.0532200000 0.0000010000 0.3912820000 0.0015140000 144058715 0 402718720 3.7341136932 3.9572360516 4.0090680122 2235 1311867793.1934790611 0.1565209180 0.1230436886 0.2390826792 0.0047006128 0.5471260000 0.0540270000 0.0633330000 0.0316130000 0.3913420000 0.0015210000 144062499 0 402718720 3.7323973179 3.9555935860 4.0092463493 2236 1311867793.2255470753 0.1555442065 0.1230582237 0.2390826792 0.0046996153 0.5012360000 0.0649280000 0.0376340000 0.0000010000 0.3919010000 0.0015120000 144066171 0 402718720 3.7330968380 3.9562897682 4.0095458031 2237 1311867793.2574770451 0.1583933383 0.1230740195 0.2390826792 0.0046986318 1.0132060000 0.0768160000 0.0664250000 0.0316400000 0.3920550000 0.4410740000 144069787 0 402718720 3.7299058437 3.9558079243 4.0101571083 2238 1311867793.2951428890 0.1571161896 0.1230892305 0.2390826792 0.0046981685 0.5202120000 0.0538980000 0.0666930000 0.0000010000 0.3929590000 0.0015110000 144073683 0 402718720 3.7304217815 3.9560914040 4.0100603104 2239 1311867793.3254458904 0.1572366208 0.1231044817 0.2390826792 0.0046973808 0.5403510000 0.0537080000 0.0555960000 0.0317560000 0.3925890000 0.0015070000 144077299 0 402718720 3.7301297188 3.9554746151 4.0106596947 2240 1311867793.3620529175 0.1539207846 0.1231182389 0.2390826792 0.0046973904 0.4960660000 0.0528040000 0.0420020000 0.0000010000 0.3945700000 0.0014960000 144081139 0 402718720 3.7328591347 3.9567151070 4.0099654198 2241 1311867793.3934969902 0.1539806575 0.1231320107 0.2390826792 0.0046964549 1.0131740000 0.0700490000 0.0652040000 0.0316250000 0.3948250000 0.4462700000 144084755 0 402718720 3.7322497368 3.9568023682 4.0102186203 2242 1311867793.4254410267 0.1502318829 0.1231440980 0.2390826792 0.0046988366 0.4879590000 0.0527910000 0.0337400000 0.0000010000 0.3947020000 0.0015020000 144088427 0 402718720 3.7355523109 3.9579453468 4.0098190308 2243 1311867793.4615969658 0.1501608491 0.1231561429 0.2390826792 0.0046986611 0.5482870000 0.0521820000 0.0617280000 0.0315770000 0.3960860000 0.0014900000 144092211 0 402718720 3.7353184223 3.9573214054 4.0101838112 2244 1311867793.4961650372 0.1479639858 0.1231671981 0.2390826792 0.0046977388 0.5061460000 0.0514650000 0.0514410000 0.0000010000 0.3965090000 0.0014980000 144095827 0 402718720 3.7371308804 3.9587006569 4.0100417137 2245 1311867793.5258960724 0.1428971291 0.1231759865 0.2390826792 0.0046994889 1.0078530000 0.0631530000 0.0613830000 0.0315190000 0.3968390000 0.4498070000 144099443 0 402718720 3.7420713902 3.9585278034 4.0097980499 2246 1311867793.5653350353 0.1422543675 0.1231844809 0.2390826792 0.0046987683 0.4996790000 0.0566490000 0.0435500000 0.0000010000 0.3925320000 0.0015770000 144103339 0 402718720 3.7423310280 3.9591431618 4.0098476410 2247 1311867793.5951368809 0.1411245912 0.1231924649 0.2390826792 0.0046983644 0.5431170000 0.0517700000 0.0560590000 0.0315370000 0.3970500000 0.0014890000 144106843 0 402718720 3.7434637547 3.9595704079 4.0098471642 2248 1311867793.6255569458 0.1403622329 0.1232001027 0.2390826792 0.0046976955 0.4912160000 0.0511140000 0.0361830000 0.0000010000 0.3971730000 0.0014900000 144110515 0 402718720 3.7439653873 3.9598972797 4.0100097656 2249 1311867793.6641399860 0.1394164860 0.1232073132 0.2390826792 0.0046969750 0.9819860000 0.0517900000 0.0489080000 0.0316320000 0.3944700000 0.4499990000 144114299 0 402718720 3.7445614338 3.9601297379 4.0101113319 2250 1311867793.6930859089 0.1361523271 0.1232130665 0.2390826792 0.0047019889 0.5158710000 0.0514120000 0.0611930000 0.0000010000 0.3966010000 0.0014840000 144117915 0 402718720 3.7472574711 3.9604809284 4.0090851784 2251 1311867793.7268340588 0.1332947463 0.1232175453 0.2390826792 0.0047014563 0.5570520000 0.0612500000 0.0644330000 0.0315800000 0.3930540000 0.0014820000 144121699 0 402718720 3.7497882843 3.9612069130 4.0086779594 2252 1311867793.7666549683 0.1301767677 0.1232206355 0.2390826792 0.0047006670 0.4994620000 0.0519990000 0.0492120000 0.0000010000 0.3912020000 0.0015800000 144125539 0 402718720 3.7521772385 3.9620809555 4.0080347061 2253 1311867793.7944359779 0.1257770061 0.1232217702 0.2390826792 0.0047041641 1.0099150000 0.0639900000 0.0650610000 0.0310450000 0.3922000000 0.4518250000 144129043 0 402718720 3.7564158440 3.9629683495 4.0070800781 2254 1311867793.8265230656 0.1271092743 0.1232234949 0.2390826792 0.0047032851 0.5543760000 0.0648550000 0.0800720000 0.0000010000 0.4026360000 0.0014810000 144132771 0 402718720 3.7544269562 3.9631319046 4.0071196556 2255 1311867793.8667359352 0.1267968118 0.1232250795 0.2390826792 0.0047027785 0.5407970000 0.0598270000 0.0489740000 0.0315330000 0.3937380000 0.0014880000 144136723 0 402718720 3.7543807030 3.9626369476 4.0071926117 2256 1311867793.8930900097 0.1208412722 0.1232240229 0.2390826792 0.0047048099 0.5008150000 0.0524470000 0.0492790000 0.0000000000 0.3923570000 0.0014880000 144140227 0 402718720 3.7602424622 3.9637184143 4.0064897537 2257 1311867793.9269030094 0.1220559105 0.1232235053 0.2390826792 0.0047038588 0.9657280000 0.0517810000 0.0414800000 0.0313410000 0.3930000000 0.4428400000 144143955 0 402718720 3.7583281994 3.9631469250 4.0066289902 2258 1311867793.9623370171 0.1201846823 0.1232221595 0.2390826792 0.0047033623 0.4941780000 0.0529450000 0.0420140000 0.0000010000 0.3924820000 0.0014870000 144147627 0 402718720 3.7596662045 3.9638755322 4.0063691139 2259 1311867793.9955279827 0.1201376542 0.1232207941 0.2390826792 0.0047027515 0.5433190000 0.0518020000 0.0614540000 0.0313060000 0.3920750000 0.0014870000 144151411 0 402718720 3.7589602470 3.9645199776 4.0059690475 2260 1311867794.0277070999 0.1210490167 0.1232198331 0.2390826792 0.0047026911 0.5135030000 0.0526520000 0.0622800000 0.0000000000 0.3917930000 0.0014870000 144155083 0 402718720 3.7574574947 3.9647624493 4.0063643456 2261 1311867794.0608921051 0.1214309931 0.1232190420 0.2390826792 0.0047017221 0.9917740000 0.0665720000 0.0602460000 0.0308700000 0.3902400000 0.4386410000 144158755 0 402718720 3.7566757202 3.9652340412 4.0064620972 2262 1311867794.0951509476 0.1188655570 0.1232171173 0.2390826792 0.0047007693 0.5078270000 0.0518830000 0.0602070000 0.0000000000 0.3890040000 0.0014890000 144162483 0 402718720 3.7589933872 3.9670400620 4.0060024261 2263 1311867794.1269369125 0.1184038520 0.1232149904 0.2390826792 0.0047010797 0.5405510000 0.0668190000 0.0475720000 0.0312830000 0.3881820000 0.0014910000 144166211 0 402718720 3.7590916157 3.9670596123 4.0058917999 2264 1311867794.1632831097 0.1163200438 0.1232119449 0.2390826792 0.0047008956 0.5033910000 0.0539440000 0.0562280000 0.0000000000 0.3864290000 0.0015020000 144169995 0 402718720 3.7608094215 3.9693651199 4.0059552193 2265 1311867794.1936271191 0.1192956492 0.1232102159 0.2390826792 0.0047006764 0.9657570000 0.0540100000 0.0674220000 0.0312580000 0.3804630000 0.4273570000 144173555 0 402718720 3.7574577332 3.9695456028 4.0064725876 2266 1311867794.2258520126 0.1196777746 0.1232086570 0.2390826792 0.0046997001 0.5406760000 0.0867520000 0.0640650000 0.0000010000 0.3830740000 0.0015050000 144177227 0 402718720 3.7567582130 3.9701666832 4.0070810318 2267 1311867794.2619779110 0.1185433343 0.1232065991 0.2390826792 0.0046992811 0.5390770000 0.0539860000 0.0661210000 0.0307830000 0.3814450000 0.0015110000 144181011 0 402718720 3.7574429512 3.9702615738 4.0068655014 2268 1311867794.2955250740 0.1183528975 0.1232044590 0.2390826792 0.0046983886 0.5213560000 0.0692310000 0.0690230000 0.0000000000 0.3760330000 0.0016080000 144184683 0 402718720 3.7574164867 3.9715933800 4.0070376396 2269 1311867794.3254759312 0.1198205128 0.1232029676 0.2390826792 0.0046978238 0.9396180000 0.0560170000 0.0493880000 0.0312310000 0.3786290000 0.4191330000 144188299 0 402718720 3.7556648254 3.9723277092 4.0077710152 2270 1311867794.3628959656 0.1193403304 0.1232012660 0.2390826792 0.0046978502 0.4795390000 0.0564950000 0.0390830000 0.0000000000 0.3772030000 0.0015270000 144192139 0 402718720 3.7556974888 3.9733357430 4.0077781677 2271 1311867794.3958311081 0.1203504875 0.1232000107 0.2390826792 0.0046970114 0.5263610000 0.0690800000 0.0467620000 0.0313630000 0.3719900000 0.0016170000 144195867 0 402718720 3.7543654442 3.9733209610 4.0083031654 2272 1311867794.4267809391 0.1194938049 0.1231983794 0.2390826792 0.0046961997 0.5041770000 0.0566470000 0.0654400000 0.0000010000 0.3752930000 0.0015240000 144199539 0 402718720 3.7548627853 3.9745934010 4.0081167221 2273 1311867794.4620559216 0.1205009446 0.1231971927 0.2390826792 0.0046952536 0.9434590000 0.0757390000 0.0465770000 0.0313430000 0.3710490000 0.4134720000 144203323 0 402718720 3.7533562183 3.9749829769 4.0082874298 2274 1311867794.4987208843 0.1204651371 0.1231959913 0.2390826792 0.0046942930 0.5024010000 0.0560300000 0.0688240000 0.0000010000 0.3704220000 0.0016100000 144207051 0 402718720 3.7529461384 3.9759902954 4.0082364082 2275 1311867794.5290880203 0.1195860207 0.1231944045 0.2390826792 0.0046938470 0.5393270000 0.0562350000 0.0600620000 0.0307760000 0.3844860000 0.0019540000 144210667 0 402718720 3.7532653809 3.9763598442 4.0080075264 2276 1311867794.5637059212 0.1186616868 0.1231924130 0.2390826792 0.0046935378 0.5489000000 0.0698420000 0.0858620000 0.0000010000 0.3863930000 0.0015190000 144214395 0 402718720 3.7535979748 3.9763507843 4.0079269409 2277 1311867794.5940639973 0.1200187206 0.1231910192 0.2390826792 0.0046931374 0.9437660000 0.0563020000 0.0659470000 0.0311980000 0.3734090000 0.4116810000 144218067 0 402718720 3.7517104149 3.9762694836 4.0081233978 2278 1311867794.6319000721 0.1181313545 0.1231887981 0.2390826792 0.0046928891 0.5016810000 0.0561410000 0.0656720000 0.0000000000 0.3730530000 0.0015230000 144221851 0 402718720 3.7531692982 3.9774086475 4.0075411797 2279 1311867794.6658101082 0.1194591224 0.1231871615 0.2390826792 0.0046928582 0.5606000000 0.0835490000 0.0693700000 0.0312690000 0.3696320000 0.0015260000 144225579 0 402718720 3.7516152859 3.9778790474 4.0079436302 2280 1311867794.6949920654 0.1190515235 0.1231853476 0.2390826792 0.0046925354 0.4925820000 0.0567040000 0.0581740000 0.0000010000 0.3708780000 0.0015300000 144229195 0 402718720 3.7516481876 3.9780900478 4.0079588890 2281 1311867794.7305591106 0.1174236387 0.1231828217 0.2390826792 0.0046925761 0.9556430000 0.0698330000 0.0694500000 0.0312730000 0.3702080000 0.4096330000 144232979 0 402718720 3.7529373169 3.9788403511 4.0075521469 2282 1311867794.7625899315 0.1188001335 0.1231809011 0.2390826792 0.0046916300 0.4847230000 0.0556580000 0.0520220000 0.0000000000 0.3702400000 0.0015220000 144236595 0 402718720 3.7512874603 3.9793827534 4.0076746941 2283 1311867794.7959010601 0.1190939024 0.1231791109 0.2390826792 0.0046907055 0.5326960000 0.0564180000 0.0656910000 0.0311730000 0.3721920000 0.0015240000 144240323 0 402718720 3.7507400513 3.9796304703 4.0077762604 2284 1311867794.8306028843 0.1175737306 0.1231766568 0.2390826792 0.0046910679 0.4980620000 0.0694330000 0.0496520000 0.0000010000 0.3721890000 0.0015190000 144244051 0 402718720 3.7521221638 3.9797966480 4.0076208115 2285 1311867794.8631660938 0.1196946949 0.1231751329 0.2390826792 0.0046901954 0.9435270000 0.0562290000 0.0655710000 0.0311850000 0.3732600000 0.4120300000 144247611 0 402718720 3.7497577667 3.9807989597 4.0077996254 2286 1311867794.8947780132 0.1194017157 0.1231734823 0.2390826792 0.0046893834 0.4941170000 0.0566100000 0.0567250000 0.0000010000 0.3732200000 0.0015240000 144251283 0 402718720 3.7498843670 3.9808273315 4.0078134537 2287 1311867794.9343950748 0.1206314415 0.1231723707 0.2390826792 0.0046885886 0.5330850000 0.0556750000 0.0687200000 0.0312100000 0.3706700000 0.0015130000 144255179 0 402718720 3.7482178211 3.9810278416 4.0080800056 2288 1311867794.9646499157 0.1187626719 0.1231704434 0.2390826792 0.0046879338 0.4966610000 0.0669830000 0.0493080000 0.0000000000 0.3735390000 0.0015170000 144258795 0 402718720 3.7498567104 3.9818203449 4.0075612068 2289 1311867794.9988350868 0.1183232069 0.1231683258 0.2390826792 0.0046874625 0.9422980000 0.0747670000 0.0462790000 0.0307920000 0.3718070000 0.4133470000 144262579 0 402718720 3.7499768734 3.9825446606 4.0072994232 2290 1311867795.0307559967 0.1185479090 0.1231663081 0.2390826792 0.0046865809 0.5019370000 0.0553510000 0.0684350000 0.0000010000 0.3713310000 0.0015130000 144266195 0 402718720 3.7496101856 3.9832239151 4.0074410439 2291 1311867795.0651550293 0.1171017364 0.1231636610 0.2390826792 0.0046856823 0.5506340000 0.0791260000 0.0596730000 0.0310960000 0.3738870000 0.0015090000 144269923 0 402718720 3.7507030964 3.9841115475 4.0073165894 2292 1311867795.0993340015 0.1158535630 0.1231604716 0.2390826792 0.0046849520 0.4808050000 0.0560590000 0.0463900000 0.0000000000 0.3715490000 0.0015170000 144273651 0 402718720 3.7516410351 3.9849228859 4.0069780350 2293 1311867795.1310648918 0.1168111861 0.1231577026 0.2390826792 0.0046839468 0.9441490000 0.0540550000 0.0564780000 0.0380480000 0.3763330000 0.4138550000 144277379 0 402718720 3.7505333424 3.9855339527 4.0072875023 2294 1311867795.1630289555 0.1171832830 0.1231550983 0.2390826792 0.0046832672 0.4880580000 0.0673650000 0.0404850000 0.0000010000 0.3733470000 0.0015120000 144280995 0 402718720 3.7498521805 3.9855732918 4.0074234009 2295 1311867795.1945760250 0.1172771528 0.1231525371 0.2390826792 0.0046823173 0.5320400000 0.0550520000 0.0682230000 0.0306740000 0.3712850000 0.0015120000 144284723 0 402718720 3.7491858006 3.9852762222 4.0073413849 2296 1311867795.2313210964 0.1176250577 0.1231501296 0.2390826792 0.0046814018 0.5003720000 0.0549330000 0.0645650000 0.0000010000 0.3740690000 0.0015120000 144288507 0 402718720 3.7485175133 3.9863419533 4.0071334839 2297 1311867795.2631359100 0.1190741882 0.1231483552 0.2390826792 0.0046803973 0.9452420000 0.0541510000 0.0674630000 0.0306390000 0.3724780000 0.4151770000 144292179 0 402718720 3.7467265129 3.9856743813 4.0072669983 2298 1311867795.2958068848 0.1186392382 0.1231463930 0.2390826792 0.0046794579 0.5017830000 0.0555630000 0.0648910000 0.0000010000 0.3745610000 0.0015110000 144295907 0 402718720 3.7469308376 3.9853875637 4.0071344376 2299 1311867795.3314220905 0.1168886051 0.1231436710 0.2390826792 0.0046786750 0.5311570000 0.0679390000 0.0514490000 0.0311910000 0.3737760000 0.0015110000 144299635 0 402718720 3.7484209538 3.9867713451 4.0065641403 2300 1311867795.3670549393 0.1172456369 0.1231411067 0.2390826792 0.0046783676 0.5027140000 0.0549010000 0.0681830000 0.0000000000 0.3728180000 0.0015130000 144303531 0 402718720 3.7480471134 3.9870183468 4.0067749023 2301 1311867795.3950240612 0.1156332269 0.1231378438 0.2390826792 0.0046785332 0.9253520000 0.0548410000 0.0435140000 0.0310580000 0.3747170000 0.4159300000 144307035 0 402718720 3.7492454052 3.9877886772 4.0063734055 2302 1311867795.4294250011 0.1160791963 0.1231347775 0.2390826792 0.0046777384 0.4852440000 0.0549140000 0.0489060000 0.0000000000 0.3744910000 0.0015100000 144310819 0 402718720 3.7485766411 3.9880988598 4.0065550804 2303 1311867795.4614660740 0.1148573831 0.1231311833 0.2390826792 0.0046776882 0.5216210000 0.0554840000 0.0544940000 0.0306440000 0.3742000000 0.0015090000 144314603 0 402718720 3.7502338886 3.9891440868 4.0063252449 2304 1311867795.4961009026 0.1139861792 0.1231272141 0.2390826792 0.0046767593 0.4965580000 0.0650000000 0.0518220000 0.0000000000 0.3729010000 0.0015130000 144318387 0 402718720 3.7511289120 3.9896957874 4.0061645508 2305 1311867795.5292580128 0.1142610088 0.1231233676 0.2390826792 0.0046758337 0.9103890000 0.0553080000 0.0350780000 0.0306900000 0.3704220000 0.4135940000 144322115 0 402718720 3.7508263588 3.9903385639 4.0065073967 2306 1311867795.5632829666 0.1124659479 0.1231187460 0.2390826792 0.0046752112 0.4966270000 0.0561670000 0.0636790000 0.0000010000 0.3696600000 0.0016160000 144325955 0 402718720 3.7527322769 3.9917616844 4.0062108040 2307 1311867795.5938069820 0.1116918325 0.1231137928 0.2390826792 0.0046743577 0.5164440000 0.0564630000 0.0498090000 0.0311140000 0.3722200000 0.0015170000 144329627 0 402718720 3.7538931370 3.9920914173 4.0063185692 2308 1311867795.6295180321 0.1117943078 0.1231088884 0.2390826792 0.0046734652 0.4792800000 0.0565020000 0.0443350000 0.0000010000 0.3716250000 0.0015230000 144333467 0 402718720 3.7539236546 3.9935622215 4.0063977242 2309 1311867795.6619150639 0.1122475937 0.1231041845 0.2390826792 0.0046730332 0.9644010000 0.0720220000 0.0470970000 0.0312480000 0.3845120000 0.4235840000 144337195 0 402718720 3.7537498474 3.9938702583 4.0067892075 2310 1311867795.6935899258 0.1090476885 0.1230980994 0.2390826792 0.0046720980 0.5008320000 0.0572830000 0.0665800000 0.0000010000 0.3700920000 0.0015280000 144340867 0 402718720 3.7572312355 3.9964365959 4.0061969757 2311 1311867795.7300128937 0.1107429266 0.1230927532 0.2390826792 0.0046721293 0.5218180000 0.0571310000 0.0586730000 0.0307660000 0.3683780000 0.0015280000 144344763 0 402718720 3.7559459209 3.9972367287 4.0064268112 2312 1311867795.7627360821 0.1099353358 0.1230870623 0.2390826792 0.0046714156 0.4917960000 0.0714680000 0.0453720000 0.0000010000 0.3680580000 0.0015390000 144348547 0 402718720 3.7571253777 3.9980261326 4.0064482689 2313 1311867795.7993569374 0.1102351993 0.1230815059 0.2390826792 0.0046709558 0.9328180000 0.0579970000 0.0668740000 0.0311920000 0.3672790000 0.4041340000 144352387 0 402718720 3.7568466663 3.9993464947 4.0067896843 2314 1311867795.8297359943 0.1129379421 0.1230771223 0.2390826792 0.0046702146 0.4928870000 0.0690300000 0.0536390000 0.0000010000 0.3629920000 0.0016310000 144356059 0 402718720 3.7540559769 3.9995584488 4.0071740150 2315 1311867795.8630819321 0.1105856895 0.1230717265 0.2390826792 0.0046698618 0.5235640000 0.0577480000 0.0611790000 0.0310340000 0.3667530000 0.0015120000 144359843 0 402718720 3.7565486431 3.9998078346 4.0066337585 2316 1311867795.9011631012 0.1110478789 0.1230665348 0.2390826792 0.0046690066 0.4755520000 0.0583130000 0.0476090000 0.0000010000 0.3624860000 0.0016380000 144363739 0 402718720 3.7562093735 4.0009717941 4.0067048073 2317 1311867795.9300799370 0.1118661165 0.1230617008 0.2390826792 0.0046680233 0.9146850000 0.0584260000 0.0342190000 0.0312220000 0.3689660000 0.4159550000 144367355 0 402718720 3.7554829121 4.0009636879 4.0069198608 2318 1311867795.9624390602 0.1110482588 0.1230565181 0.2390826792 0.0046671964 0.4925930000 0.0732980000 0.0465920000 0.0000010000 0.3658270000 0.0015420000 144371083 0 402718720 3.7563748360 4.0013093948 4.0064845085 2319 1311867796.0000178814 0.1121536121 0.1230518166 0.2390826792 0.0046663021 0.5458420000 0.0741850000 0.0711690000 0.0313740000 0.3622190000 0.0015440000 144374979 0 402718720 3.7554743290 4.0008792877 4.0065202713 2320 1311867796.0296399593 0.1118489578 0.1230469878 0.2390826792 0.0046653468 0.5055230000 0.0834110000 0.0492310000 0.0000000000 0.3659910000 0.0015370000 144378595 0 402718720 3.7558565140 4.0006885529 4.0063543320 2321 1311867796.0617599487 0.1117869094 0.1230421364 0.2390826792 0.0046648648 0.9062090000 0.0580330000 0.0475120000 0.0308470000 0.3619840000 0.4024460000 144382379 0 402718720 3.7561480999 4.0013446808 4.0064516068 2322 1311867796.0984148979 0.1094828695 0.1230362969 0.2390826792 0.0046640919 0.4986920000 0.0583080000 0.0707030000 0.0000010000 0.3624880000 0.0016270000 144386163 0 402718720 3.7585155964 4.0024113655 4.0058035851 2323 1311867796.1296660900 0.1112554073 0.1230312255 0.2390826792 0.0046632556 0.5204240000 0.0594250000 0.0577580000 0.0308020000 0.3655350000 0.0015400000 144389723 0 402718720 3.7568714619 4.0024495125 4.0059862137 2324 1311867796.1618049145 0.1107255071 0.1230259304 0.2390826792 0.0046622960 0.5162830000 0.0818980000 0.0649040000 0.0000010000 0.3622460000 0.0016380000 144393451 0 402718720 3.7575347424 4.0021166801 4.0060243607 2325 1311867796.1990590096 0.1087912172 0.1230198080 0.2390826792 0.0046617891 0.9307680000 0.0588000000 0.0673130000 0.0311970000 0.3658470000 0.4022370000 144397347 0 402718720 3.7597992420 4.0035009384 4.0057783127 2326 1311867796.2292931080 0.1093013063 0.1230139101 0.2390826792 0.0046607952 0.4704010000 0.0586400000 0.0303550000 0.0000010000 0.3734880000 0.0019920000 144401019 0 402718720 3.7593193054 4.0033059120 4.0058817863 2327 1311867796.2631280422 0.1103522629 0.1230084689 0.2390826792 0.0046598303 0.5430720000 0.0727090000 0.0449850000 0.0381540000 0.3792690000 0.0019910000 144404747 0 402718720 3.7585165501 4.0033307076 4.0059704781 2328 1311867796.3010690212 0.1092751399 0.1230025697 0.2390826792 0.0046588777 0.4844210000 0.0719410000 0.0396010000 0.0000010000 0.3659720000 0.0015400000 144408587 0 402718720 3.7600352764 4.0041851997 4.0059099197 2329 1311867796.3299860954 0.1083664894 0.1229962854 0.2390826792 0.0046578825 0.9425090000 0.0702230000 0.0709350000 0.0313210000 0.3621380000 0.4025160000 144412203 0 402718720 3.7612857819 4.0044727325 4.0057134628 2330 1311867796.3619849682 0.1104108915 0.1229908839 0.2390826792 0.0046574464 0.4732850000 0.0589070000 0.0421930000 0.0000010000 0.3651880000 0.0015440000 144415987 0 402718720 3.7595174313 4.0042853355 4.0062394142 2331 1311867796.3998959064 0.1091009527 0.1229849252 0.2390826792 0.0046565534 0.5278170000 0.0574740000 0.0665220000 0.0311280000 0.3656460000 0.0015420000 144419715 0 402718720 3.7613472939 4.0049333572 4.0061769485 2332 1311867796.4297831059 0.1098968908 0.1229793128 0.2390826792 0.0046555746 0.4658340000 0.0591340000 0.0343420000 0.0000000000 0.3653660000 0.0015480000 144423387 0 402718720 3.7608251572 4.0045166016 4.0064077377 2333 1311867796.4618980885 0.1118371636 0.1229745369 0.2390826792 0.0046547508 0.9200480000 0.0574160000 0.0590340000 0.0311530000 0.3655110000 0.4015130000 144427171 0 402718720 3.7589793205 4.0042533875 4.0067772865 2334 1311867796.5018439293 0.1100457907 0.1229689976 0.2390826792 0.0046544206 0.5115770000 0.0724150000 0.0672010000 0.0000000000 0.3649780000 0.0015440000 144431123 0 402718720 3.7610952854 4.0045380592 4.0065655708 2335 1311867796.5301249027 0.1101928353 0.1229635260 0.2390826792 0.0046534617 0.5091720000 0.0716730000 0.0343960000 0.0312310000 0.3649250000 0.0015450000 144434739 0 402718720 3.7611675262 4.0047483444 4.0065579414 2336 1311867796.5621480942 0.1117393970 0.1229587212 0.2390826792 0.0046525933 0.4692720000 0.0577120000 0.0395920000 0.0000010000 0.3650270000 0.0015490000 144438467 0 402718720 3.7599525452 4.0045604706 4.0070824623 2337 1311867796.6018888950 0.1107393801 0.1229534925 0.2390826792 0.0046518273 0.9270150000 0.0574050000 0.0675330000 0.0306430000 0.3647750000 0.4012140000 144442419 0 402718720 3.7615284920 4.0051259995 4.0071620941 2338 1311867796.6323978901 0.1063880995 0.1229464072 0.2390826792 0.0046517412 0.4969190000 0.0577380000 0.0673110000 0.0000010000 0.3648720000 0.0015420000 144446091 0 402718720 3.7663211823 4.0060100555 4.0062780380 2339 1311867796.6659901142 0.1086494848 0.1229402948 0.2390826792 0.0046520665 0.5327270000 0.0818900000 0.0490200000 0.0313340000 0.3634290000 0.0015440000 144449875 0 402718720 3.7645735741 4.0062613487 4.0070195198 2340 1311867796.7025029659 0.1087370962 0.1229342251 0.2390826792 0.0046511568 0.4703750000 0.0593300000 0.0404800000 0.0000000000 0.3636110000 0.0015470000 144453603 0 402718720 3.7648763657 4.0062041283 4.0070495605 2341 1311867796.7335898876 0.1092760190 0.1229283907 0.2390826792 0.0046506595 0.9228030000 0.0593090000 0.0661720000 0.0313430000 0.3623790000 0.3981540000 144457275 0 402718720 3.7651929855 4.0061812401 4.0073542595 2342 1311867796.7634348869 0.1079617441 0.1229220002 0.2390826792 0.0046496814 0.5005440000 0.0593700000 0.0721190000 0.0000010000 0.3620930000 0.0015560000 144461003 0 402718720 3.7670335770 4.0068221092 4.0072808266 2343 1311867796.7990939617 0.1095818132 0.1229163066 0.2390826792 0.0046502112 0.5193750000 0.0582810000 0.0605050000 0.0312100000 0.3624020000 0.0015530000 144464787 0 402718720 3.7659173012 4.0076646805 4.0082468987 2344 1311867796.8303010464 0.1116347164 0.1229114936 0.2390826792 0.0046503668 0.5140770000 0.0722180000 0.0695110000 0.0000010000 0.3643430000 0.0020130000 144468515 0 402718720 3.7643153667 4.0074515343 4.0092024803 2345 1311867796.8626410961 0.1094208807 0.1229057407 0.2390826792 0.0046494814 0.9308520000 0.0751380000 0.0634620000 0.0313070000 0.3608630000 0.3946920000 144472187 0 402718720 3.7672185898 4.0084486008 4.0093617439 2346 1311867796.8988420963 0.1151806489 0.1229024478 0.2390826792 0.0046501240 0.4825290000 0.0738850000 0.0416130000 0.0000000000 0.3600650000 0.0015680000 144476027 0 402718720 3.7622032166 4.0082526207 4.0109329224 2347 1311867796.9308090210 0.1160353944 0.1228995219 0.2390826792 0.0046492783 0.5385110000 0.0715700000 0.0697550000 0.0312770000 0.3589140000 0.0015620000 144479755 0 402718720 3.7618687153 4.0079011917 4.0115098953 2348 1311867796.9623529911 0.1179037914 0.1228973942 0.2390826792 0.0046485622 0.4970330000 0.0612460000 0.0702530000 0.0000000000 0.3585300000 0.0015720000 144483483 0 402718720 3.7604587078 4.0080189705 4.0124583244 2349 1311867796.9994709492 0.1160479560 0.1228944784 0.2390826792 0.0046478241 0.9181080000 0.0911440000 0.0433490000 0.0309190000 0.3569790000 0.3902440000 144487323 0 402718720 3.7628624439 4.0078177452 4.0126438141 2350 1311867797.0328159332 0.1184216961 0.1228925750 0.2390826792 0.0046481544 0.4743630000 0.0613200000 0.0509200000 0.0000000000 0.3550940000 0.0015740000 144490995 0 402718720 3.7605733871 4.0080761909 4.0131769180 2351 1311867797.0733079910 0.1197113991 0.1228912219 0.2390826792 0.0046472681 0.4916150000 0.0611840000 0.0358760000 0.0313250000 0.3561960000 0.0015770000 144495059 0 402718720 3.7598543167 4.0072894096 4.0140800476 2352 1311867797.0992720127 0.1208474860 0.1228903530 0.2390826792 0.0046466224 0.4797540000 0.0752810000 0.0417350000 0.0000010000 0.3556760000 0.0015700000 144498563 0 402718720 3.7590191364 4.0073647499 4.0148448944 2353 1311867797.1336839199 0.1229140982 0.1228903631 0.2390826792 0.0046482368 0.8941050000 0.0624200000 0.0541020000 0.0314570000 0.3545640000 0.3861220000 144502403 0 402718720 3.7573766708 4.0074338913 4.0159115791 2354 1311867797.1708030701 0.1251469105 0.1228913217 0.2390826792 0.0046482291 0.5075110000 0.0754050000 0.0714750000 0.0000000000 0.3535380000 0.0015790000 144506243 0 402718720 3.7556426525 4.0074973106 4.0168032646 2355 1311867797.1996591091 0.1265749782 0.1228928859 0.2390826792 0.0046483176 0.5125950000 0.0621010000 0.0597250000 0.0313570000 0.3523610000 0.0015860000 144509859 0 402718720 3.7546420097 4.0081982613 4.0175256729 2356 1311867797.2372090816 0.1262951642 0.1228943300 0.2390826792 0.0046475407 0.4932350000 0.0632360000 0.0716770000 0.0000010000 0.3513000000 0.0015860000 144513811 0 402718720 3.7556023598 4.0085902214 4.0179562569 2357 1311867797.2708179951 0.1280398816 0.1228965131 0.2390826792 0.0046478364 0.8953300000 0.0745380000 0.0542740000 0.0313750000 0.3498650000 0.3798600000 144517539 0 402718720 3.7542374134 4.0091886520 4.0191779137 2358 1311867797.3019850254 0.1287034005 0.1228989757 0.2390826792 0.0046473256 0.4890210000 0.0615840000 0.0712220000 0.0000010000 0.3491750000 0.0015570000 144521267 0 402718720 3.7539823055 4.0093712807 4.0201673508 2359 1311867797.3296120167 0.1270428002 0.1229007323 0.2390826792 0.0046467303 0.5483990000 0.0907620000 0.0719050000 0.0313950000 0.3473020000 0.0016010000 144524827 0 402718720 3.7557644844 4.0094528198 4.0203499794 2360 1311867797.3703179359 0.1272795796 0.1229025877 0.2390826792 0.0046461529 0.4587410000 0.0637140000 0.0448290000 0.0000010000 0.3428300000 0.0016840000 144528779 0 402718720 3.7553613186 4.0101432800 4.0207762718 2361 1311867797.3999080658 0.1290591657 0.1229051953 0.2390826792 0.0046455106 0.8825540000 0.0765630000 0.0487160000 0.0314310000 0.3458420000 0.3744680000 144532451 0 402718720 3.7535309792 4.0100946426 4.0216517448 2362 1311867797.4322440624 0.1271471232 0.1229069912 0.2390826792 0.0046450040 0.4709280000 0.0638640000 0.0545190000 0.0000010000 0.3453460000 0.0016230000 144536235 0 402718720 3.7553455830 4.0103182793 4.0221514702 2363 1311867797.4688720703 0.1267398745 0.1229086133 0.2390826792 0.0046442213 0.4878580000 0.0639270000 0.0451240000 0.0310480000 0.3403600000 0.0016980000 144540019 0 402718720 3.7553398609 4.0096549988 4.0222811699 2364 1311867797.5000469685 0.1281585842 0.1229108341 0.2390826792 0.0046436213 0.4541410000 0.0642970000 0.0387670000 0.0000010000 0.3440070000 0.0016090000 144543747 0 402718720 3.7538728714 4.0101962090 4.0230035782 2365 1311867797.5296459198 0.1285621673 0.1229132237 0.2390826792 0.0046429482 0.8878530000 0.0638980000 0.0767100000 0.0315360000 0.3399000000 0.3703730000 144547419 0 402718720 3.7533421516 4.0104122162 4.0234699249 2366 1311867797.5718441010 0.1272416264 0.1229150531 0.2390826792 0.0046420558 0.4497640000 0.0624180000 0.0365030000 0.0000010000 0.3437630000 0.0016050000 144551371 0 402718720 3.7544519901 4.0107722282 4.0237946510 2367 1311867797.5997619629 0.1288787723 0.1229175726 0.2390826792 0.0046415986 0.4879340000 0.0639710000 0.0430630000 0.0309560000 0.3428760000 0.0016110000 144554987 0 402718720 3.7526583672 4.0097303391 4.0241527557 2368 1311867797.6303300858 0.1290597022 0.1229201664 0.2390826792 0.0046407693 0.4464250000 0.0651980000 0.0311090000 0.0000010000 0.3429590000 0.0016110000 144558659 0 402718720 3.7523279190 4.0093493462 4.0243725777 2369 1311867797.6706480980 0.1290606707 0.1229227584 0.2390826792 0.0046398322 0.9296280000 0.0964280000 0.0763770000 0.0310450000 0.3413670000 0.3782130000 144562611 0 402718720 3.7520828247 4.0083594322 4.0245857239 2370 1311867797.7010281086 0.1303703040 0.1229259009 0.2390826792 0.0046390923 0.5342030000 0.0793040000 0.0953380000 0.0000010000 0.3524080000 0.0016060000 144566283 0 402718720 3.7506484985 4.0085215569 4.0250163078 2371 1311867797.7299659252 0.1296645403 0.1229287430 0.2390826792 0.0046382118 0.4988890000 0.0632810000 0.0543620000 0.0313360000 0.3427570000 0.0016040000 144569899 0 402718720 3.7511465549 4.0076775551 4.0252366066 2372 1311867797.7678339481 0.1293848604 0.1229314648 0.2390826792 0.0046374364 0.4866640000 0.0643140000 0.0747010000 0.0000000000 0.3405620000 0.0016060000 144573795 0 402718720 3.7512438297 4.0072164536 4.0250992775 2373 1311867797.8001670837 0.1304176897 0.1229346195 0.2390826792 0.0046365600 0.8881260000 0.0637330000 0.0726410000 0.0314100000 0.3434540000 0.3713640000 144577579 0 402718720 3.7502102852 4.0069384575 4.0253109932 2374 1311867797.8302230835 0.1305672377 0.1229378346 0.2390826792 0.0046356378 0.4878610000 0.0759440000 0.0609680000 0.0000010000 0.3437850000 0.0016030000 144581251 0 402718720 3.7500610352 4.0067076683 4.0252580643 2375 1311867797.8681600094 0.1311859787 0.1229413075 0.2390826792 0.0046350935 0.5187820000 0.0638080000 0.0761850000 0.0315230000 0.3401200000 0.0016070000 144585147 0 402718720 3.7495372295 4.0069065094 4.0256209373 2376 1311867797.8986220360 0.1332260966 0.1229456361 0.2390826792 0.0046343956 0.4520690000 0.0638820000 0.0371070000 0.0000010000 0.3439690000 0.0016030000 144588763 0 402718720 3.7475597858 4.0060200691 4.0259151459 2377 1311867797.9362978935 0.1343142539 0.1229504189 0.2390826792 0.0046335071 0.8900160000 0.0637410000 0.0727260000 0.0314910000 0.3439580000 0.3725500000 144592659 0 402718720 3.7465362549 4.0059237480 4.0257525444 2378 1311867797.9696850777 0.1320772469 0.1229542569 0.2390826792 0.0046329134 0.4874950000 0.0641850000 0.0723160000 0.0000010000 0.3438600000 0.0016020000 144596331 0 402718720 3.7488353252 4.0053968430 4.0254950523 2379 1311867798.0026450157 0.1342167109 0.1229589910 0.2390826792 0.0046322010 0.5536570000 0.0961520000 0.0667690000 0.0314420000 0.3521230000 0.0016010000 144600059 0 402718720 3.7468061447 4.0049095154 4.0259165764 2380 1311867798.0362720490 0.1331472844 0.1229632718 0.2390826792 0.0046313144 0.4879710000 0.0641030000 0.0766190000 0.0000010000 0.3398360000 0.0016990000 144603787 0 402718720 3.7481701374 4.0044388771 4.0258989334 2381 1311867798.0708239079 0.1342510581 0.1229680126 0.2390826792 0.0046305883 0.8905910000 0.0642160000 0.0729240000 0.0315130000 0.3438370000 0.3725520000 144607515 0 402718720 3.7471151352 4.0043478012 4.0258498192 2382 1311867798.1006710529 0.1316901445 0.1229716743 0.2390826792 0.0046310381 0.4870120000 0.0635580000 0.0724160000 0.0000000000 0.3438860000 0.0015650000 144611131 0 402718720 3.7498939037 4.0032477379 4.0256028175 2383 1311867798.1315639019 0.1338999271 0.1229762602 0.2390826792 0.0046308415 0.5005840000 0.0630860000 0.0548320000 0.0309210000 0.3446260000 0.0015760000 144614747 0 402718720 3.7479822636 4.0030636787 4.0258698463 2384 1311867798.1681389809 0.1376229972 0.1229824040 0.2390826792 0.0046306111 0.4844710000 0.0871910000 0.0456650000 0.0000000000 0.3444070000 0.0016110000 144618531 0 402718720 3.7446286678 4.0020742416 4.0262417793 2385 1311867798.2041590214 0.1356273144 0.1229877058 0.2390826792 0.0046300165 0.8730180000 0.0639240000 0.0547720000 0.0315500000 0.3440680000 0.3731340000 144622371 0 402718720 3.7471897602 4.0025687218 4.0258674622 2386 1311867798.2401928902 0.1373479664 0.1229937244 0.2390826792 0.0046296593 0.4891950000 0.0643450000 0.0736650000 0.0000010000 0.3440050000 0.0016070000 144626155 0 402718720 3.7458636761 4.0021662712 4.0259251595 2387 1311867798.2742829323 0.1378057599 0.1229999297 0.2390826792 0.0046291699 0.5233570000 0.0643890000 0.0775950000 0.0317050000 0.3425540000 0.0016260000 144629883 0 402718720 3.7459962368 4.0022392273 4.0263099670 2388 1311867798.3000180721 0.1370920241 0.1230058309 0.2390826792 0.0046283238 0.4683510000 0.0625330000 0.0545520000 0.0000000000 0.3441320000 0.0015740000 144633387 0 402718720 3.7471938133 4.0024909973 4.0263271332 2389 1311867798.3389759064 0.1380588710 0.1230121319 0.2390826792 0.0046280446 0.8972110000 0.0943090000 0.0523540000 0.0316340000 0.3419940000 0.3713600000 144637283 0 402718720 3.7467527390 4.0027551651 4.0263061523 2390 1311867798.3689808846 0.1376278102 0.1230182472 0.2390826792 0.0046270865 0.4901500000 0.0649000000 0.0778590000 0.0000000000 0.3401550000 0.0015870000 144640843 0 402718720 3.7477638721 4.0029678345 4.0263619423 2391 1311867798.4016571045 0.1375559568 0.1230243274 0.2390826792 0.0046261962 0.5136710000 0.0778220000 0.0556320000 0.0313720000 0.3416950000 0.0015880000 144644571 0 402718720 3.7484877110 4.0031266212 4.0266728401 2392 1311867798.4377439022 0.1373969167 0.1230303360 0.2390826792 0.0046254380 0.4881410000 0.0646020000 0.0775100000 0.0000010000 0.3388550000 0.0016100000 144648355 0 402718720 3.7492666245 4.0027775764 4.0267982483 2393 1311867798.4722189903 0.1368698925 0.1230361193 0.2390826792 0.0046246598 0.8831270000 0.0646790000 0.0738020000 0.0316100000 0.3399750000 0.3675030000 144652083 0 402718720 3.7502751350 4.0028624535 4.0265245438 2394 1311867798.4979979992 0.1360163689 0.1230415413 0.2390826792 0.0046239207 0.4684560000 0.0790460000 0.0456050000 0.0000010000 0.3363220000 0.0016860000 144655587 0 402718720 3.7515645027 4.0029921532 4.0263409615 2395 1311867798.5371229649 0.1380082816 0.1230477905 0.2390826792 0.0046230208 0.4859290000 0.0649800000 0.0464870000 0.0316820000 0.3355870000 0.0016230000 144659427 0 402718720 3.7501885891 4.0024538040 4.0265507698 2396 1311867798.5710020065 0.1368041635 0.1230535319 0.2390826792 0.0046222115 0.4890100000 0.0658690000 0.0783410000 0.0000000000 0.3375770000 0.0016200000 144663155 0 402718720 3.7518136501 4.0024113655 4.0263791084 2397 1311867798.6058080196 0.1364136636 0.1230591056 0.2390826792 0.0046214436 0.8615470000 0.0649620000 0.0500810000 0.0315130000 0.3383820000 0.3710580000 144666883 0 402718720 3.7527718544 4.0027446747 4.0260624886 2398 1311867798.6374750137 0.1376058608 0.1230651718 0.2390826792 0.0046224878 0.4991470000 0.0786210000 0.0755300000 0.0000010000 0.3378180000 0.0016270000 144670499 0 402718720 3.7522883415 4.0030136108 4.0263876915 2399 1311867798.6689419746 0.1375199407 0.1230711971 0.2390826792 0.0046219953 0.5449200000 0.0940590000 0.0753890000 0.0316000000 0.3366570000 0.0016350000 144674171 0 402718720 3.7529325485 4.0039305687 4.0263175964 2400 1311867798.7046790123 0.1368534267 0.1230769397 0.2390826792 0.0046219010 0.4525020000 0.0659650000 0.0467750000 0.0000010000 0.3322450000 0.0017310000 144677955 0 402718720 3.7543663979 4.0042324066 4.0265851021 2401 1311867798.7372579575 0.1384519339 0.1230833433 0.2390826792 0.0046216950 0.8498750000 0.0667110000 0.0511580000 0.0312200000 0.3349070000 0.3602910000 144681683 0 402718720 3.7535681725 4.0043926239 4.0266580582 2402 1311867798.7684650421 0.1393124312 0.1230900998 0.2390826792 0.0046215168 0.4479600000 0.0667990000 0.0407390000 0.0000010000 0.3332220000 0.0016380000 144685299 0 402718720 3.7533791065 4.0052371025 4.0268340111 2403 1311867798.8009719849 0.1366481930 0.1230957419 0.2390826792 0.0046216609 0.4943220000 0.0652820000 0.0574150000 0.0316390000 0.3327220000 0.0016730000 144688971 0 402718720 3.7567570210 4.0060710907 4.0264949799 2404 1311867798.8353779316 0.1395199895 0.1231025740 0.2390826792 0.0046224161 0.4722780000 0.0788560000 0.0552280000 0.0000000000 0.3309850000 0.0016460000 144692699 0 402718720 3.7550942898 4.0070323944 4.0270919800 2405 1311867798.8719079494 0.1398177147 0.1231095241 0.2390826792 0.0046216508 0.8510000000 0.0670990000 0.0575900000 0.0317200000 0.3324080000 0.3565600000 144696483 0 402718720 3.7558553219 4.0075545311 4.0268831253 2406 1311867798.9030900002 0.1389340013 0.1231161012 0.2390826792 0.0046207970 0.4815240000 0.0708410000 0.0742550000 0.0000010000 0.3291270000 0.0016510000 144700099 0 402718720 3.7573616505 4.0082640648 4.0263204575 2407 1311867798.9344220161 0.1402008832 0.1231231992 0.2390826792 0.0046202021 0.4998750000 0.0678980000 0.0647230000 0.0317180000 0.3282930000 0.0016550000 144703771 0 402718720 3.7572560310 4.0090317726 4.0267109871 2408 1311867798.9702930450 0.1397470981 0.1231301028 0.2390826792 0.0046194621 0.4610510000 0.0681320000 0.0582950000 0.0000010000 0.3273580000 0.0016610000 144707555 0 402718720 3.7588443756 4.0093502998 4.0264158249 2409 1311867798.9996600151 0.1402101964 0.1231371929 0.2390826792 0.0046200179 0.8700100000 0.0977580000 0.0616760000 0.0317970000 0.3243110000 0.3488500000 144711171 0 402718720 3.7582514286 4.0100502968 4.0261540413 2410 1311867799.0381140709 0.1405526251 0.1231444192 0.2390826792 0.0046211463 0.4467590000 0.0685030000 0.0485280000 0.0000010000 0.3221610000 0.0017550000 144715067 0 402718720 3.7598519325 4.0111012459 4.0260720253 2411 1311867799.0688700676 0.1407360286 0.1231517156 0.2390826792 0.0046203203 0.4849840000 0.0692220000 0.0526600000 0.0317750000 0.3240880000 0.0016730000 144718683 0 402718720 3.7605514526 4.0112285614 4.0261440277 2412 1311867799.1011309624 0.1401881129 0.1231587788 0.2390826792 0.0046198819 0.4705290000 0.0685330000 0.0714340000 0.0000010000 0.3232730000 0.0016640000 144722355 0 402718720 3.7615919113 4.0113959312 4.0260148048 2413 1311867799.1368980408 0.1413486004 0.1231663171 0.2390826792 0.0046192547 0.8254880000 0.0687020000 0.0528610000 0.0315890000 0.3228650000 0.3438200000 144726139 0 402718720 3.7615027428 4.0118832588 4.0259242058 2414 1311867799.1699140072 0.1410445571 0.1231737231 0.2390826792 0.0046183763 0.4406860000 0.0691170000 0.0396230000 0.0000010000 0.3235340000 0.0021970000 144729811 0 402718720 3.7626464367 4.0127549171 4.0256762505 2415 1311867799.2040729523 0.1398701668 0.1231806368 0.2390826792 0.0046207604 0.5070060000 0.0686130000 0.0780770000 0.0317470000 0.3212820000 0.0016730000 144733539 0 402718720 3.7643377781 4.0121178627 4.0249104500 2416 1311867799.2358450890 0.1415359825 0.1231882342 0.2390826792 0.0046200850 0.4426060000 0.0674670000 0.0459080000 0.0000010000 0.3218940000 0.0016800000 144737211 0 402718720 3.7632496357 4.0123467445 4.0246071815 2417 1311867799.2801609039 0.1425439715 0.1231962424 0.2390826792 0.0046193072 0.8362460000 0.0690180000 0.0398010000 0.0313370000 0.3331810000 0.3567390000 144741219 0 402718720 3.7634019852 4.0127382278 4.0244050026 2418 1311867799.2992970943 0.1411234438 0.1232036564 0.2390826792 0.0046184497 0.4833360000 0.0777700000 0.0767190000 0.0000010000 0.3215380000 0.0016780000 144744499 0 402718720 3.7649805546 4.0121159554 4.0236458778 2419 1311867799.3363530636 0.1420654505 0.1232114538 0.2390826792 0.0046175636 0.4871080000 0.0675910000 0.0587840000 0.0310930000 0.3223430000 0.0016460000 144748339 0 402718720 3.7646210194 4.0120234489 4.0229182243 2420 1311867799.3682019711 0.1424483359 0.1232194029 0.2390826792 0.0046174209 0.4542800000 0.0680480000 0.0524000000 0.0000010000 0.3265120000 0.0016760000 144751955 0 402718720 3.7645883560 4.0132355690 4.0224814415 2421 1311867799.4002521038 0.1425691396 0.1232273953 0.2390826792 0.0046164882 0.8182900000 0.0692970000 0.0465520000 0.0318010000 0.3217890000 0.3431670000 144755683 0 402718720 3.7650804520 4.0137085915 4.0222630501 2422 1311867799.4359819889 0.1422329098 0.1232352424 0.2390826792 0.0046155551 0.4379560000 0.0691290000 0.0399720000 0.0000010000 0.3214920000 0.0016810000 144759467 0 402718720 3.7657501698 4.0142502785 4.0217823982 2423 1311867799.4694008827 0.1425828934 0.1232432274 0.2390826792 0.0046147343 0.4949590000 0.0884100000 0.0463820000 0.0318260000 0.3210270000 0.0016810000 144763139 0 402718720 3.7658658028 4.0145907402 4.0215940475 2424 1311867799.5055029392 0.1416064203 0.1232508030 0.2390826792 0.0046139518 0.4701360000 0.0809100000 0.0594210000 0.0000010000 0.3224950000 0.0016820000 144766923 0 402718720 3.7671763897 4.0155987740 4.0213251114 2425 1311867799.5358369350 0.1391301006 0.1232573511 0.2390826792 0.0046136927 0.8592970000 0.0812660000 0.0786380000 0.0318540000 0.3204820000 0.3414200000 144770539 0 402718720 3.7697873116 4.0168199539 4.0210790634 2426 1311867799.5718040466 0.1403410584 0.1232643930 0.2390826792 0.0046128485 0.4565290000 0.0692350000 0.0626500000 0.0000010000 0.3169660000 0.0017820000 144774323 0 402718720 3.7686362267 4.0168976784 4.0207724571 2427 1311867799.6046330929 0.1408122629 0.1232716233 0.2390826792 0.0046120610 0.4825580000 0.0698740000 0.0532900000 0.0318450000 0.3201690000 0.0016950000 144777939 0 402718720 3.7682194710 4.0172443390 4.0203089714 2428 1311867799.6362400055 0.1401132941 0.1232785597 0.2390826792 0.0046112261 0.4434860000 0.0698750000 0.0489310000 0.0000010000 0.3170440000 0.0017820000 144781667 0 402718720 3.7689301968 4.0179200172 4.0194997787 2429 1311867799.6706030369 0.1418882459 0.1232862212 0.2390826792 0.0046107919 0.8149860000 0.0700610000 0.0469970000 0.0318710000 0.3200380000 0.3403020000 144785395 0 402718720 3.7675509453 4.0174050331 4.0190892220 2430 1311867799.7089800835 0.1424024999 0.1232940880 0.2390826792 0.0046099341 0.4861370000 0.0961160000 0.0627970000 0.0000000000 0.3198620000 0.0016960000 144789235 0 402718720 3.7672967911 4.0176758766 4.0184555054 2431 1311867799.7397329807 0.1405525655 0.1233011873 0.2390826792 0.0046094511 0.4762020000 0.0696770000 0.0467810000 0.0318250000 0.3204930000 0.0016900000 144792851 0 402718720 3.7691590786 4.0186357498 4.0177688599 2432 1311867799.7721259594 0.1409868002 0.1233084594 0.2390826792 0.0046085317 0.4445000000 0.0697140000 0.0469000000 0.0000010000 0.3204170000 0.0016850000 144796579 0 402718720 3.7689323425 4.0185551643 4.0171999931 2433 1311867799.8072490692 0.1409698576 0.1233157185 0.2390826792 0.0046078505 0.8153530000 0.0698490000 0.0469620000 0.0318140000 0.3204710000 0.3403760000 144800307 0 402718720 3.7690262794 4.0195617676 4.0163364410 2434 1311867799.8393049240 0.1383450478 0.1233218932 0.2390826792 0.0046072524 0.4710900000 0.0698420000 0.0712300000 0.0000010000 0.3225580000 0.0016900000 144803979 0 402718720 3.7717494965 4.0201392174 4.0156702995 2435 1311867799.8678040504 0.1394361109 0.1233285110 0.2390826792 0.0046073941 0.4752780000 0.0688620000 0.0473340000 0.0317920000 0.3199240000 0.0016950000 144807595 0 402718720 3.7708110809 4.0202832222 4.0155673027 2436 1311867799.9071669579 0.1390585452 0.1233349683 0.2390826792 0.0046066481 0.4767500000 0.0696160000 0.0802120000 0.0000010000 0.3195540000 0.0016970000 144811491 0 402718720 3.7714600563 4.0212321281 4.0154232979 2437 1311867799.9347701073 0.1372762471 0.1233406890 0.2390826792 0.0046058165 0.8444110000 0.0705500000 0.0802790000 0.0317970000 0.3186280000 0.3375370000 144814939 0 402718720 3.7734413147 4.0219874382 4.0150613785 2438 1311867799.9675478935 0.1376423836 0.1233465551 0.2390826792 0.0046050568 0.4772690000 0.0711780000 0.0810280000 0.0000010000 0.3175870000 0.0017020000 144818667 0 402718720 3.7732839584 4.0219392776 4.0154643059 2439 1311867800.0074419975 0.1391127557 0.1233530193 0.2390826792 0.0046042866 0.4814060000 0.0712610000 0.0542220000 0.0318300000 0.3166830000 0.0017050000 144822563 0 402718720 3.7722713947 4.0224137306 4.0155520439 2440 1311867800.0354819298 0.1385777295 0.1233592590 0.2390826792 0.0046035196 0.4577300000 0.0924720000 0.0430620000 0.0000010000 0.3147250000 0.0017070000 144826123 0 402718720 3.7731456757 4.0226054192 4.0152239799 2441 1311867800.0715930462 0.1377678066 0.1233651617 0.2390826792 0.0046033593 0.8056760000 0.0711360000 0.0477290000 0.0318070000 0.3157100000 0.3335950000 144829907 0 402718720 3.7745852470 4.0232310295 4.0150628090 2442 1311867800.1054389477 0.1371647120 0.1233708126 0.2390826792 0.0046024315 0.4758820000 0.0715280000 0.0812140000 0.0000010000 0.3157080000 0.0017040000 144833635 0 402718720 3.7758059502 4.0244650841 4.0148544312 2443 1311867800.1350870132 0.1380547136 0.1233768232 0.2390826792 0.0046017593 0.4941720000 0.0850430000 0.0549840000 0.0318670000 0.3148380000 0.0017130000 144837195 0 402718720 3.7752153873 4.0239968300 4.0144810677 2444 1311867800.1694350243 0.1382903159 0.1233829253 0.2390826792 0.0046010111 0.4442720000 0.0721900000 0.0506510000 0.0000010000 0.3139410000 0.0017120000 144840923 0 402718720 3.7755386829 4.0245947838 4.0143775940 2445 1311867800.2077379227 0.1379150748 0.1233888689 0.2390826792 0.0046001090 0.8365230000 0.0719640000 0.0815160000 0.0318320000 0.3140880000 0.3313770000 144844819 0 402718720 3.7766313553 4.0247430801 4.0141935349 2446 1311867800.2413349152 0.1380071938 0.1233948453 0.2390826792 0.0045993278 0.4354650000 0.0723910000 0.0415990000 0.0000000000 0.3140140000 0.0017060000 144848547 0 402718720 3.7772872448 4.0258517265 4.0141243935 2447 1311867800.2718439102 0.1388062835 0.1234011434 0.2390826792 0.0045984125 0.4728940000 0.0721030000 0.0482400000 0.0317940000 0.3133210000 0.0017120000 144852163 0 402718720 3.7771859169 4.0257315636 4.0144786835 2448 1311867800.3038680553 0.1369586885 0.1234066816 0.2390826792 0.0045981353 0.4561400000 0.0943570000 0.0413840000 0.0000010000 0.3129000000 0.0017110000 144855779 0 402718720 3.7796721458 4.0263228416 4.0145268440 2449 1311867800.3359420300 0.1381527334 0.1234127029 0.2390826792 0.0045981029 0.7932040000 0.0722080000 0.0417200000 0.0318640000 0.3123890000 0.3293210000 144859507 0 402718720 3.7792756557 4.0269818306 4.0148158073 2450 1311867800.3712899685 0.1381439269 0.1234187156 0.2390826792 0.0045971841 0.4403850000 0.0726920000 0.0510010000 0.0000000000 0.3088960000 0.0018080000 144863179 0 402718720 3.7804973125 4.0275907516 4.0150170326 2451 1311867800.4036390781 0.1392461061 0.1234251732 0.2390826792 0.0045963417 0.4954290000 0.0728430000 0.0726310000 0.0318910000 0.3105880000 0.0017220000 144866907 0 402718720 3.7802429199 4.0273857117 4.0152039528 2452 1311867800.4360520840 0.1386571676 0.1234313852 0.2390826792 0.0045954992 0.4594860000 0.0724520000 0.0686290000 0.0000010000 0.3109220000 0.0017140000 144870523 0 402718720 3.7818098068 4.0272798538 4.0154252052 2453 1311867800.4683868885 0.1389378160 0.1234377066 0.2390826792 0.0045946933 0.8313000000 0.0941660000 0.0586350000 0.0319280000 0.3075130000 0.3332560000 144874195 0 402718720 3.7824239731 4.0275597572 4.0152959824 2454 1311867800.5043759346 0.1401543915 0.1234445187 0.2390826792 0.0045943386 0.4866540000 0.0857960000 0.0831990000 0.0000010000 0.3101470000 0.0017220000 144878035 0 402718720 3.7824277878 4.0279903412 4.0156044960 2455 1311867800.5355989933 0.1399576664 0.1234512450 0.2390826792 0.0045936762 0.4662050000 0.0733700000 0.0442860000 0.0314560000 0.3096310000 0.0017240000 144881707 0 402718720 3.7834882736 4.0280551910 4.0156869888 2456 1311867800.5714819431 0.1412700266 0.1234585002 0.2390826792 0.0045928218 0.4370040000 0.0727380000 0.0473360000 0.0000010000 0.3094280000 0.0017190000 144885547 0 402718720 3.7833371162 4.0283341408 4.0158991814 2457 1311867800.6043050289 0.1406906247 0.1234655137 0.2390826792 0.0045919351 0.8139410000 0.0864080000 0.0559240000 0.0317980000 0.3089800000 0.3251150000 144889219 0 402718720 3.7847588062 4.0286049843 4.0157117844 2458 1311867800.6356160641 0.1409921944 0.1234726441 0.2390826792 0.0045910236 0.4380230000 0.0731240000 0.0516350000 0.0000010000 0.3057270000 0.0017200000 144892891 0 402718720 3.7854282856 4.0283379555 4.0157213211 2459 1311867800.6704459190 0.1391507983 0.1234790200 0.2390826792 0.0045908164 0.4830620000 0.0728910000 0.0624690000 0.0317560000 0.3084750000 0.0017190000 144896619 0 402718720 3.7882952690 4.0288777351 4.0155768394 2460 1311867800.7034249306 0.1395949870 0.1234855712 0.2390826792 0.0045903303 0.4387960000 0.0736830000 0.0493710000 0.0000000000 0.3081970000 0.0017210000 144900291 0 402718720 3.7886996269 4.0289974213 4.0157423019 2461 1311867800.7352058887 0.1404627413 0.1234924697 0.2390826792 0.0045895808 0.8261270000 0.1012080000 0.0562660000 0.0317120000 0.3076480000 0.3235190000 144903963 0 402718720 3.7889759541 4.0289869308 4.0158891678 2462 1311867800.7744410038 0.1386516988 0.1234986269 0.2390826792 0.0045904039 0.4372970000 0.0736730000 0.0492690000 0.0000010000 0.3068260000 0.0017310000 144907803 0 402718720 3.7915301323 4.0283665657 4.0156435966 2463 1311867800.8084959984 0.1399066448 0.1235052887 0.2390826792 0.0045899913 0.4835410000 0.0888410000 0.0494040000 0.0313350000 0.3064370000 0.0017380000 144911531 0 402718720 3.7910370827 4.0281457901 4.0160088539 2464 1311867800.8347818851 0.1402590871 0.1235120882 0.2390826792 0.0045891723 0.4381730000 0.0741000000 0.0517840000 0.0000010000 0.3047400000 0.0017320000 144915035 0 402718720 3.7913424969 4.0287451744 4.0161995888 2465 1311867800.8741569519 0.1404982954 0.1235189791 0.2390826792 0.0045884942 0.7882860000 0.0736190000 0.0493780000 0.0317370000 0.3062150000 0.3215820000 144918931 0 402718720 3.7915620804 4.0285310745 4.0159940720 2466 1311867800.9060831070 0.1391563416 0.1235253203 0.2390826792 0.0045875936 0.4615490000 0.0853100000 0.0560400000 0.0000010000 0.3114220000 0.0023010000 144922547 0 402718720 3.7935154438 4.0288538933 4.0160140991 2467 1311867800.9397630692 0.1402421743 0.1235320965 0.2390826792 0.0045868074 0.4713650000 0.0771620000 0.0492040000 0.0317860000 0.3057220000 0.0017330000 144926275 0 402718720 3.7928423882 4.0283131599 4.0158815384 2468 1311867800.9754400253 0.1414307654 0.1235393488 0.2390826792 0.0045866733 0.4548750000 0.0841830000 0.0572900000 0.0000010000 0.3058580000 0.0017290000 144930059 0 402718720 3.7922346592 4.0274448395 4.0158400536 2469 1311867801.0043320656 0.1415857971 0.1235466580 0.2390826792 0.0045865995 0.8094470000 0.0737390000 0.0698190000 0.0317550000 0.3064210000 0.3218860000 144933619 0 402718720 3.7924449444 4.0273356438 4.0158753395 2470 1311867801.0391418934 0.1407027543 0.1235536038 0.2390826792 0.0045861022 0.4816160000 0.0739500000 0.0924260000 0.0000010000 0.3076740000 0.0017300000 144937403 0 402718720 3.7936599255 4.0264115334 4.0156660080 2471 1311867801.0742049217 0.1406166703 0.1235605091 0.2390826792 0.0045854482 0.4798860000 0.0737310000 0.0560060000 0.0317710000 0.3096720000 0.0023020000 144941075 0 402718720 3.7941589355 4.0272803307 4.0156822205 2472 1311867801.1095008850 0.1411416680 0.1235676212 0.2390826792 0.0045847807 0.5150000000 0.0916490000 0.1079240000 0.0000000000 0.3078480000 0.0017220000 144944859 0 402718720 3.7938821316 4.0267825127 4.0160322189 2473 1311867801.1356039047 0.1408281177 0.1235746008 0.2390826792 0.0045839470 0.8238420000 0.0931970000 0.0660090000 0.0318130000 0.3050290000 0.3219760000 144948363 0 402718720 3.7944927216 4.0265464783 4.0163516998 2474 1311867801.1731019020 0.1400676370 0.1235812674 0.2390826792 0.0045831513 0.4219470000 0.0724720000 0.0351360000 0.0000000000 0.3068230000 0.0016890000 144952203 0 402718720 3.7952625751 4.0265498161 4.0161194801 2475 1311867801.2059779167 0.1388035566 0.1235874178 0.2390826792 0.0045835441 0.4611350000 0.0737380000 0.0419560000 0.0315960000 0.3063070000 0.0017300000 144955875 0 402718720 3.7962994576 4.0253105164 4.0159230232 2476 1311867801.2351169586 0.1368017495 0.1235927548 0.2390826792 0.0045827377 0.4435150000 0.0736330000 0.0559660000 0.0000010000 0.3063370000 0.0017250000 144959323 0 402718720 3.7982399464 4.0250110626 4.0158929825 2477 1311867801.2740859985 0.1385694891 0.1235988011 0.2390826792 0.0045818844 0.8220820000 0.0722250000 0.0832470000 0.0317160000 0.3067440000 0.3223730000 144963275 0 402718720 3.7963318825 4.0246634483 4.0160293579 2478 1311867801.3080420494 0.1362301409 0.1236038985 0.2390826792 0.0045817186 0.4542460000 0.0836070000 0.0558110000 0.0000010000 0.3072560000 0.0017250000 144966947 0 402718720 3.7983858585 4.0248780251 4.0157952309 2479 1311867801.3364291191 0.1364412457 0.1236090769 0.2390826792 0.0045816540 0.4688110000 0.0732020000 0.0490170000 0.0316750000 0.3073610000 0.0017230000 144970507 0 402718720 3.7981352806 4.0252475739 4.0160055161 2480 1311867801.3723030090 0.1347914636 0.1236135859 0.2390826792 0.0045815049 0.4708900000 0.0732840000 0.0830510000 0.0000000000 0.3069390000 0.0017220000 144974291 0 402718720 3.7995305061 4.0251359940 4.0158395767 2481 1311867801.4048879147 0.1343014091 0.1236178938 0.2390826792 0.0045805943 0.8375860000 0.0735470000 0.0851190000 0.0316430000 0.3193610000 0.3220170000 144977963 0 402718720 3.7998275757 4.0253701210 4.0157375336 2482 1311867801.4369940758 0.1335656047 0.1236219017 0.2390826792 0.0045803471 0.4698070000 0.0738400000 0.0816690000 0.0000010000 0.3067100000 0.0017230000 144981691 0 402718720 3.8001515865 4.0254940987 4.0158171654 2483 1311867801.4725570679 0.1349328607 0.1236264571 0.2390826792 0.0045861702 0.4953160000 0.0980800000 0.0517740000 0.0317990000 0.3060890000 0.0017330000 144985419 0 402718720 3.7992649078 4.0261478424 4.0164599419 2484 1311867801.5049059391 0.1342435032 0.1236307313 0.2390826792 0.0045855894 0.4434470000 0.0739550000 0.0565220000 0.0000010000 0.3053810000 0.0017330000 144989035 0 402718720 3.7999534607 4.0265502930 4.0168447495 2485 1311867801.5366990566 0.1345079839 0.1236351084 0.2390826792 0.0045857532 0.7944230000 0.0744950000 0.0596170000 0.0317540000 0.3039340000 0.3187800000 144992763 0 402718720 3.8002200127 4.0269494057 4.0169339180 2486 1311867801.5724411011 0.1341764033 0.1236393487 0.2390826792 0.0045853959 0.4622590000 0.0746240000 0.0796820000 0.0000000000 0.3002980000 0.0017370000 144996547 0 402718720 3.8007972240 4.0265393257 4.0177550316 2487 1311867801.6040530205 0.1338521987 0.1236434552 0.2390826792 0.0045845781 0.4731040000 0.0747760000 0.0564780000 0.0316650000 0.3026270000 0.0017360000 145000163 0 402718720 3.8016717434 4.0267763138 4.0181517601 2488 1311867801.6371319294 0.1353268176 0.1236481511 0.2390826792 0.0045840950 0.4646850000 0.0873380000 0.0672750000 0.0000010000 0.3024770000 0.0017000000 145003891 0 402718720 3.8009126186 4.0267505646 4.0187535286 2489 1311867801.6713359356 0.1339541376 0.1236522917 0.2390826792 0.0045906075 0.7791830000 0.0752320000 0.0500890000 0.0312060000 0.3013700000 0.3154670000 145007619 0 402718720 3.8023412228 4.0277419090 4.0189003944 2490 1311867801.7047519684 0.1312072724 0.1236553258 0.2390826792 0.0045928040 0.4682540000 0.0749400000 0.0848960000 0.0000000000 0.3007680000 0.0017360000 145011347 0 402718720 3.8059532642 4.0263371468 4.0185866356 2491 1311867801.7362918854 0.1349133253 0.1236598453 0.2390826792 0.0045978942 0.4902080000 0.0866990000 0.0506740000 0.0316220000 0.3124200000 0.0023260000 145015019 0 402718720 3.8037605286 4.0258574486 4.0190858841 2492 1311867801.7739040852 0.1340147257 0.1236640005 0.2390826792 0.0045978404 0.4502230000 0.0907980000 0.0503880000 0.0000010000 0.3013750000 0.0017400000 145018859 0 402718720 3.8057060242 4.0257086754 4.0184674263 2493 1311867801.8057849407 0.1339572370 0.1236681294 0.2390826792 0.0045970343 0.8357470000 0.0921600000 0.0898160000 0.0316390000 0.3012980000 0.3149140000 145022475 0 402718720 3.8068468571 4.0250973701 4.0181403160 2494 1311867801.8389480114 0.1353033781 0.1236727947 0.2390826792 0.0045962002 0.4542100000 0.0883150000 0.0559640000 0.0000010000 0.3022560000 0.0017360000 145026147 0 402718720 3.8066601753 4.0241060257 4.0176668167 2495 1311867801.8715689182 0.1358476579 0.1236776744 0.2390826792 0.0045960670 0.4793670000 0.0753720000 0.0608580000 0.0317040000 0.3038160000 0.0017380000 145029931 0 402718720 3.8070914745 4.0234947205 4.0164132118 2496 1311867801.9050290585 0.1349744350 0.1236822004 0.2390826792 0.0045964484 0.4711430000 0.0732990000 0.0844520000 0.0000000000 0.3057380000 0.0017380000 145033603 0 402718720 3.8091645241 4.0231475830 4.0150551796 2497 1311867801.9403839111 0.1353663653 0.1236868796 0.2390826792 0.0045961662 0.7838160000 0.0745390000 0.0433170000 0.0316000000 0.3072100000 0.3212380000 145037387 0 402718720 3.8099460602 4.0230221748 4.0142121315 2498 1311867801.9724469185 0.1358755827 0.1236917590 0.2390826792 0.0045957100 0.4901340000 0.0879520000 0.0854340000 0.0000010000 0.3091490000 0.0016960000 145041059 0 402718720 3.8104739189 4.0237660408 4.0129027367 2499 1311867802.0031659603 0.1372134387 0.1236971699 0.2390826792 0.0046016379 0.4797550000 0.0740680000 0.0572140000 0.0315300000 0.3093370000 0.0017290000 145044675 0 402718720 3.8105013371 4.0243206024 4.0118422508 2500 1311867802.0413680077 0.1379368305 0.1237028657 0.2390826792 0.0046045949 0.4462680000 0.0728040000 0.0496170000 0.0000010000 0.3149870000 0.0023010000 145048571 0 402718720 3.8115959167 4.0246930122 4.0105934143 2501 1311867802.0717110634 0.1376309097 0.1237084347 0.2390826792 0.0046043043 0.8665270000 0.0927170000 0.0754080000 0.0385400000 0.3244230000 0.3295210000 145052187 0 402718720 3.8131494522 4.0252528191 4.0088963509 2502 1311867802.1040730476 0.1389771402 0.1237145373 0.2390826792 0.0046041427 0.4435290000 0.0741590000 0.0503660000 0.0000010000 0.3113810000 0.0017250000 145055803 0 402718720 3.8134517670 4.0264868736 4.0075106621 2503 1311867802.1390628815 0.1352033913 0.1237191273 0.2390826792 0.0046037838 0.4978930000 0.1032510000 0.0453800000 0.0315800000 0.3100220000 0.0017290000 145059531 0 402718720 3.8191781044 4.0265746117 4.0051050186 2504 1311867802.1724100113 0.1320481151 0.1237224536 0.2390826792 0.0046102184 0.4808040000 0.0750000000 0.0849140000 0.0000010000 0.3131620000 0.0017300000 145063259 0 402718720 3.8234782219 4.0263690948 4.0025606155 2505 1311867802.2056589127 0.1346383393 0.1237268113 0.2390826792 0.0046142789 0.8119730000 0.0747610000 0.0609000000 0.0311280000 0.3118920000 0.3273730000 145066931 0 402718720 3.8230128288 4.0268287659 4.0007858276 2506 1311867802.2409839630 0.1321453154 0.1237301706 0.2390826792 0.0046211658 0.4461760000 0.0746140000 0.0500160000 0.0000010000 0.3138820000 0.0017360000 145070715 0 402718720 3.8272182941 4.0266785622 3.9982969761 2507 1311867802.2706429958 0.1312445104 0.1237331679 0.2390826792 0.0046202869 0.4991470000 0.0747080000 0.0712820000 0.0315060000 0.3140180000 0.0017370000 145074331 0 402718720 3.8298211098 4.0254683495 3.9958434105 2508 1311867802.3064510822 0.1321333647 0.1237365173 0.2390826792 0.0046208811 0.4596150000 0.0862530000 0.0532320000 0.0000010000 0.3121830000 0.0018290000 145078059 0 402718720 3.8302485943 4.0242342949 3.9937791824 2509 1311867802.3400380611 0.1305091530 0.1237392166 0.2390826792 0.0046254210 0.8501870000 0.0739080000 0.0717380000 0.0314590000 0.3219110000 0.3446580000 145081787 0 402718720 3.8331184387 4.0242094994 3.9912867546 2510 1311867802.3742809296 0.1328619868 0.1237428512 0.2390826792 0.0046253191 0.4861980000 0.0923870000 0.0572330000 0.0000010000 0.3288830000 0.0017320000 145085403 0 402718720 3.8323335648 4.0226125717 3.9890513420 2511 1311867802.4052720070 0.1311765462 0.1237458117 0.2390826792 0.0046259128 0.5463320000 0.1020540000 0.0845620000 0.0314480000 0.3205840000 0.0017300000 145089075 0 402718720 3.8353688717 4.0217437744 3.9867434502 2512 1311867802.4389400482 0.1308507472 0.1237486401 0.2390826792 0.0046281387 0.4539340000 0.0738400000 0.0500200000 0.0000010000 0.3224200000 0.0017310000 145092747 0 402718720 3.8367459774 4.0225734711 3.9849665165 2513 1311867802.4714379311 0.1294187903 0.1237508964 0.2390826792 0.0046274713 0.8250920000 0.0737170000 0.0604850000 0.0311030000 0.3197680000 0.3341160000 145096475 0 402718720 3.8392171860 4.0217165947 3.9824326038 2514 1311867802.5060200691 0.1312440336 0.1237538769 0.2390826792 0.0046275050 0.4887530000 0.0730190000 0.0848830000 0.0000000000 0.3231450000 0.0017160000 145100203 0 402718720 3.8386163712 4.0215034485 3.9804806709 2515 1311867802.5389459133 0.1290577054 0.1237559858 0.2390826792 0.0046281482 0.5200960000 0.0733420000 0.0841330000 0.0313930000 0.3235500000 0.0017260000 145103819 0 402718720 3.8420424461 4.0211296082 3.9781813622 2516 1311867802.5715909004 0.1279076338 0.1237576359 0.2390826792 0.0046300639 0.4567210000 0.0725260000 0.0494720000 0.0000000000 0.3270790000 0.0017200000 145107603 0 402718720 3.8444635868 4.0221791267 3.9755332470 2517 1311867802.6031410694 0.1272877008 0.1237590384 0.2390826792 0.0046301633 0.8368260000 0.0726760000 0.0700300000 0.0313770000 0.3219020000 0.3349280000 145111219 0 402718720 3.8465256691 4.0223832130 3.9733743668 2518 1311867802.6396369934 0.1290567219 0.1237611423 0.2390826792 0.0046297152 0.4705920000 0.0846420000 0.0594070000 0.0000000000 0.3185400000 0.0018130000 145115003 0 402718720 3.8460695744 4.0207014084 3.9713554382 2519 1311867802.6727440357 0.1274260283 0.1237625972 0.2390826792 0.0046290359 0.4910160000 0.0731210000 0.0562820000 0.0314100000 0.3219820000 0.0017300000 145118675 0 402718720 3.8490557671 4.0210523605 3.9690120220 2520 1311867802.7073149681 0.1275103986 0.1237640845 0.2390826792 0.0046292267 0.4791280000 0.0725510000 0.0764330000 0.0000010000 0.3224580000 0.0017180000 145122403 0 402718720 3.8502297401 4.0227522850 3.9672920704 2521 1311867802.7416400909 0.1252763718 0.1237646843 0.2390826792 0.0046288902 0.8770210000 0.0998710000 0.0835260000 0.0313870000 0.3219390000 0.3343120000 145126131 0 402718720 3.8539302349 4.0228886604 3.9649579525 2522 1311867802.7708799839 0.1256859303 0.1237654461 0.2390826792 0.0046281338 0.4804800000 0.0713400000 0.0789850000 0.0000010000 0.3224680000 0.0017220000 145129747 0 402718720 3.8547835350 4.0227355957 3.9627442360 2523 1311867802.8048460484 0.1260383278 0.1237663470 0.2390826792 0.0046275471 0.5059880000 0.0736860000 0.0714230000 0.0314060000 0.3218020000 0.0017270000 145133363 0 402718720 3.8557310104 4.0228986740 3.9611840248 2524 1311867802.8393790722 0.1267073601 0.1237675122 0.2390826792 0.0046268679 0.4891910000 0.0731940000 0.0871540000 0.0000000000 0.3211480000 0.0017130000 145137147 0 402718720 3.8564758301 4.0230383873 3.9600529671 2525 1311867802.8706729412 0.1266438365 0.1237686513 0.2390826792 0.0046265856 0.8083340000 0.0723750000 0.0434290000 0.0309090000 0.3216260000 0.3340540000 145140819 0 402718720 3.8579070568 4.0223546028 3.9582219124 2526 1311867802.9066920280 0.1278777570 0.1237702781 0.2390826792 0.0046271175 0.4838920000 0.0716770000 0.0826100000 0.0000010000 0.3219080000 0.0017160000 145144603 0 402718720 3.8578019142 4.0223450661 3.9566586018 2527 1311867802.9404280186 0.1292076111 0.1237724298 0.2390826792 0.0046262781 0.5167950000 0.0728250000 0.0828700000 0.0314210000 0.3220380000 0.0017200000 145148275 0 402718720 3.8579320908 4.0223388672 3.9551627636 2528 1311867802.9723958969 0.1279408932 0.1237740787 0.2390826792 0.0046254748 0.4964750000 0.0833210000 0.0828510000 0.0000010000 0.3225690000 0.0017190000 145151947 0 402718720 3.8604650497 4.0223231316 3.9537620544 2529 1311867803.0042099953 0.1248995662 0.1237745237 0.2390826792 0.0046267211 0.8514760000 0.0728700000 0.0827590000 0.0314180000 0.3227880000 0.3356060000 145155619 0 402718720 3.8643047810 4.0233306885 3.9519896507 2530 1311867803.0404539108 0.1270454377 0.1237758166 0.2390826792 0.0046266271 0.4863520000 0.0727280000 0.0830880000 0.0000000000 0.3228260000 0.0017160000 145159403 0 402718720 3.8636817932 4.0228033066 3.9507944584 2531 1311867803.0710830688 0.1257639974 0.1237766021 0.2390826792 0.0046260794 0.5379310000 0.0931950000 0.0831130000 0.0309720000 0.3229890000 0.0017240000 145163019 0 402718720 3.8656020164 4.0218348503 3.9492166042 2532 1311867803.1049640179 0.1276115328 0.1237781167 0.2390826792 0.0046255588 0.4743210000 0.0731860000 0.0696930000 0.0000000000 0.3237360000 0.0017210000 145166691 0 402718720 3.8646237850 4.0217728615 3.9481558800 2533 1311867803.1399960518 0.1287242621 0.1237800694 0.2390826792 0.0046247718 0.8902640000 0.0916460000 0.0829610000 0.0328460000 0.3382540000 0.3385290000 145170475 0 402718720 3.8641920090 4.0224804878 3.9470188618 2534 1311867803.1724820137 0.1270778924 0.1237813708 0.2390826792 0.0046239146 0.4882130000 0.0717470000 0.0841960000 0.0000010000 0.3245910000 0.0017110000 145174147 0 402718720 3.8662037849 4.0220460892 3.9453504086 2535 1311867803.2086870670 0.1284016371 0.1237831934 0.2390826792 0.0046233043 0.5184090000 0.0720630000 0.0824860000 0.0313770000 0.3247960000 0.0017160000 145177987 0 402718720 3.8654053211 4.0224170685 3.9442756176 2536 1311867803.2400670052 0.1274367869 0.1237846341 0.2390826792 0.0046235550 0.5001800000 0.0721950000 0.0827450000 0.0000010000 0.3363440000 0.0022750000 145181603 0 402718720 3.8662228584 4.0222716331 3.9432759285 2537 1311867803.2704820633 0.1256024688 0.1237853506 0.2390826792 0.0046239541 0.8405060000 0.0850820000 0.0553570000 0.0314460000 0.3248590000 0.3376480000 145185219 0 402718720 3.8684871197 4.0213546753 3.9418115616 2538 1311867803.3084690571 0.1277904063 0.1237869286 0.2390826792 0.0046234029 0.5017700000 0.0835670000 0.0873730000 0.0000010000 0.3226960000 0.0018190000 145189115 0 402718720 3.8660445213 4.0200996399 3.9409489632 2539 1311867803.3390929699 0.1277556717 0.1237884918 0.2390826792 0.0046230220 0.5195400000 0.0721850000 0.0820880000 0.0314010000 0.3262030000 0.0017210000 145192619 0 402718720 3.8657386303 4.0203080177 3.9397869110 2540 1311867803.3732869625 0.1236775294 0.1237884481 0.2390826792 0.0046233452 0.4863230000 0.0708730000 0.0811750000 0.0000000000 0.3265490000 0.0016980000 145196403 0 402718720 3.8698413372 4.0205864906 3.9389224052 2541 1311867803.4067549706 0.1244594008 0.1237887121 0.2390826792 0.0046226138 0.8603500000 0.0716020000 0.0857460000 0.0314940000 0.3261130000 0.3393690000 145200131 0 402718720 3.8689346313 4.0207386017 3.9383606911 2542 1311867803.4397881031 0.1249886602 0.1237891842 0.2390826792 0.0046217641 0.4669560000 0.0706130000 0.0623990000 0.0000010000 0.3261930000 0.0016980000 145203803 0 402718720 3.8685059547 4.0209002495 3.9377675056 2543 1311867803.4707190990 0.1244399399 0.1237894401 0.2390826792 0.0046211114 0.5142960000 0.0811530000 0.0682370000 0.0309170000 0.3263490000 0.0017040000 145207475 0 402718720 3.8690264225 4.0204825401 3.9364075661 2544 1311867803.5065801144 0.1261890531 0.1237903833 0.2390826792 0.0046214174 0.4687940000 0.0709420000 0.0658530000 0.0000010000 0.3243010000 0.0017040000 145211259 0 402718720 3.8675684929 4.0212273598 3.9360959530 2545 1311867803.5397379398 0.1240596324 0.1237904891 0.2390826792 0.0046209603 0.8408000000 0.0818900000 0.0547820000 0.0313290000 0.3266130000 0.3401200000 145214931 0 402718720 3.8696200848 4.0213418007 3.9348394871 2546 1311867803.5702500343 0.1243679002 0.1237907159 0.2390826792 0.0046201265 0.5013540000 0.0711150000 0.0818930000 0.0000010000 0.3394810000 0.0022600000 145218547 0 402718720 3.8691191673 4.0211710930 3.9338102341 2547 1311867803.6121668816 0.1252146810 0.1237912750 0.2390826792 0.0046193548 0.5776560000 0.0893660000 0.1081640000 0.0383070000 0.3341820000 0.0017060000 145222555 0 402718720 3.8681371212 4.0213785172 3.9335298538 2548 1311867803.6394500732 0.1207262874 0.1237900721 0.2390826792 0.0046190724 0.4887590000 0.0710070000 0.0863980000 0.0000000000 0.3232450000 0.0017990000 145226059 0 402718720 3.8723304272 4.0225548744 3.9317896366 2549 1311867803.6726729870 0.1249959767 0.1237905452 0.2390826792 0.0046197668 0.8581350000 0.0715020000 0.0883640000 0.0314580000 0.3223740000 0.3383690000 145229731 0 402718720 3.8678209782 4.0227003098 3.9321212769 2550 1311867803.7105441093 0.1250647753 0.1237910449 0.2390826792 0.0046196472 0.4587430000 0.0713690000 0.0555280000 0.0000010000 0.3241130000 0.0017000000 145233627 0 402718720 3.8672447205 4.0233793259 3.9315371513 2551 1311867803.7378931046 0.1241987348 0.1237912047 0.2390826792 0.0046190780 0.5020470000 0.0846520000 0.0558830000 0.0313540000 0.3224380000 0.0017210000 145237131 0 402718720 3.8679416180 4.0248780251 3.9307999611 2552 1311867803.7722349167 0.1242209300 0.1237913731 0.2390826792 0.0046186283 0.4986990000 0.0848510000 0.0844740000 0.0000010000 0.3216290000 0.0016830000 145240915 0 402718720 3.8677182198 4.0249810219 3.9300847054 2553 1311867803.8064799309 0.1264544278 0.1237924162 0.2390826792 0.0046180550 0.8323480000 0.0854190000 0.0570270000 0.0314220000 0.3196710000 0.3327550000 145244643 0 402718720 3.8654282093 4.0246338844 3.9298543930 2554 1311867803.8385739326 0.1260596067 0.1237933039 0.2390826792 0.0046190126 0.4762420000 0.0733630000 0.0751370000 0.0000010000 0.3199820000 0.0017220000 145248259 0 402718720 3.8660290241 4.0269770622 3.9298560619 2555 1311867803.8737049103 0.1274799258 0.1237947468 0.2390826792 0.0046187094 0.4936770000 0.0865660000 0.0504170000 0.0313790000 0.3175400000 0.0017270000 145252099 0 402718720 3.8644766808 4.0280818939 3.9294686317 2556 1311867803.9077479839 0.1268032342 0.1237959238 0.2390826792 0.0046193313 0.4702230000 0.0740200000 0.0713540000 0.0000010000 0.3170710000 0.0017320000 145255827 0 402718720 3.8649940491 4.0278902054 3.9287312031 2557 1311867803.9400169849 0.1290129274 0.1237979641 0.2390826792 0.0046225840 0.8068260000 0.0736290000 0.0503870000 0.0313810000 0.3161840000 0.3292030000 145259443 0 402718720 3.8628008366 4.0282917023 3.9286792278 2558 1311867803.9723939896 0.1295460463 0.1238002112 0.2390826792 0.0046229264 0.4793980000 0.0834180000 0.0714390000 0.0000010000 0.3167880000 0.0016830000 145263171 0 402718720 3.8618233204 4.0302853584 3.9285736084 2559 1311867804.0064320564 0.1289275289 0.1238022148 0.2390826792 0.0046223594 0.5136130000 0.0741200000 0.0858230000 0.0314420000 0.3144550000 0.0017300000 145266843 0 402718720 3.8620648384 4.0293235779 3.9277148247 2560 1311867804.0387020111 0.1297979057 0.1238045569 0.2390826792 0.0046218409 0.4940530000 0.0857230000 0.0857140000 0.0000000000 0.3148280000 0.0017340000 145270515 0 402718720 3.8606381416 4.0297451019 3.9270646572 2561 1311867804.0722310543 0.1300934851 0.1238070126 0.2390826792 0.0046212122 0.8790430000 0.1122000000 0.0903220000 0.0314830000 0.3119870000 0.3270140000 145274243 0 402718720 3.8598299026 4.0311951637 3.9265627861 2562 1311867804.1084001064 0.1304068267 0.1238095886 0.2390826792 0.0046211099 0.4841740000 0.0747250000 0.0901600000 0.0000010000 0.3114850000 0.0017320000 145277971 0 402718720 3.8590075970 4.0300302505 3.9261984825 2563 1311867804.1399340630 0.1313431859 0.1238125280 0.2390826792 0.0046207437 0.5126790000 0.0744270000 0.0853580000 0.0314310000 0.3136490000 0.0017480000 145281643 0 402718720 3.8574707508 4.0301070213 3.9254198074 2564 1311867804.1736989021 0.1289867461 0.1238145460 0.2390826792 0.0046205616 0.4807050000 0.0726780000 0.0883880000 0.0000010000 0.3118250000 0.0017340000 145285371 0 402718720 3.8595001698 4.0303478241 3.9245018959 2565 1311867804.2092669010 0.1310786307 0.1238173780 0.2390826792 0.0046196931 0.8382350000 0.0746140000 0.0855980000 0.0312860000 0.3139420000 0.3267110000 145289099 0 402718720 3.8568646908 4.0286560059 3.9240779877 2566 1311867804.2408709526 0.1308929473 0.1238201354 0.2390826792 0.0046193904 0.4757470000 0.0745750000 0.0782940000 0.0000010000 0.3150510000 0.0017370000 145292715 0 402718720 3.8564660549 4.0295352936 3.9232068062 2567 1311867804.2707660198 0.1267599016 0.1238212806 0.2390826792 0.0046191362 0.4916130000 0.0740980000 0.0638140000 0.0315050000 0.3144020000 0.0017360000 145296331 0 402718720 3.8604252338 4.0306797028 3.9226450920 2568 1311867804.3078389168 0.1278514564 0.1238228500 0.2390826792 0.0046183992 0.4766690000 0.0947910000 0.0596820000 0.0000010000 0.3143530000 0.0017440000 145300059 0 402718720 3.8587923050 4.0305447578 3.9221520424 2569 1311867804.3404970169 0.1281535774 0.1238245358 0.2390826792 0.0046175188 0.8036630000 0.0744190000 0.0498350000 0.0310280000 0.3144060000 0.3279140000 145303787 0 402718720 3.8580651283 4.0305242538 3.9214005470 2570 1311867804.3725171089 0.1259095222 0.1238253471 0.2390826792 0.0046167173 0.4811090000 0.0740180000 0.0842140000 0.0000010000 0.3149600000 0.0017350000 145307459 0 402718720 3.8598744869 4.0317931175 3.9203000069 2571 1311867804.4121570587 0.1273617595 0.1238267226 0.2390826792 0.0046159149 0.5067900000 0.1022060000 0.0525850000 0.0315650000 0.3126190000 0.0017400000 145311355 0 402718720 3.8581089973 4.0313239098 3.9196345806 2572 1311867804.4434490204 0.1256474257 0.1238274305 0.2390826792 0.0046152648 0.4536110000 0.0738220000 0.0566360000 0.0000000000 0.3153390000 0.0017260000 145315027 0 402718720 3.8598365784 4.0321340561 3.9193239212 2573 1311867804.4745810032 0.1240611002 0.1238275213 0.2390826792 0.0046144479 0.8533530000 0.0841850000 0.0892140000 0.0315380000 0.3138440000 0.3284530000 145318643 0 402718720 3.8613708019 4.0327377319 3.9183108807 2574 1311867804.5092110634 0.1291176081 0.1238295765 0.2390826792 0.0046140003 0.4827260000 0.0741360000 0.0860570000 0.0000010000 0.3146840000 0.0017410000 145322371 0 402718720 3.8562905788 4.0311222076 3.9182405472 2575 1311867804.5393021107 0.1269498169 0.1238307882 0.2390826792 0.0046136993 0.5129430000 0.0736610000 0.0847490000 0.0315100000 0.3151720000 0.0017380000 145325987 0 402718720 3.8582506180 4.0324387550 3.9173190594 2576 1311867804.5744440556 0.1257890165 0.1238315484 0.2390826792 0.0046128551 0.4824250000 0.0739980000 0.0850590000 0.0000010000 0.3155090000 0.0017210000 145329715 0 402718720 3.8596200943 4.0334763527 3.9167943001 2577 1311867804.6065940857 0.1260630786 0.1238324143 0.2390826792 0.0046121194 0.8403260000 0.0743070000 0.0849460000 0.0314820000 0.3148320000 0.3285430000 145333443 0 402718720 3.8594932556 4.0323500633 3.9162120819 2578 1311867804.6414110661 0.1241110414 0.1238325224 0.2390826792 0.0046115353 0.4939920000 0.0856310000 0.0845680000 0.0000000000 0.3159300000 0.0017330000 145337171 0 402718720 3.8617269993 4.0338091850 3.9155025482 2579 1311867804.6758968830 0.1266693622 0.1238336224 0.2390826792 0.0046127466 0.4782300000 0.0740700000 0.0529390000 0.0310980000 0.3122980000 0.0017320000 145340955 0 402718720 3.8593101501 4.0351424217 3.9153165817 2580 1311867804.7094891071 0.1259153634 0.1238344293 0.2390826792 0.0046119249 0.4808420000 0.0740690000 0.0844690000 0.0000010000 0.3144490000 0.0017350000 145344627 0 402718720 3.8604125977 4.0345287323 3.9150249958 2581 1311867804.7431960106 0.1265007555 0.1238354623 0.2390826792 0.0046123655 0.8407550000 0.0741280000 0.0890010000 0.0315650000 0.3120370000 0.3279330000 145348355 0 402718720 3.8603537083 4.0360403061 3.9149363041 2582 1311867804.7739880085 0.1253859103 0.1238360628 0.2390826792 0.0046116817 0.4604340000 0.0729130000 0.0670300000 0.0000010000 0.3122770000 0.0017930000 145351915 0 402718720 3.8615310192 4.0378551483 3.9144756794 2583 1311867804.8113589287 0.1245798469 0.1238363508 0.2390826792 0.0046136654 0.5183870000 0.1005590000 0.0651130000 0.0314900000 0.3133690000 0.0017360000 145355755 0 402718720 3.8619863987 4.0363559723 3.9140784740 2584 1311867804.8407669067 0.1239934191 0.1238364116 0.2390826792 0.0046130466 0.4592720000 0.0734610000 0.0642930000 0.0000000000 0.3136210000 0.0017370000 145359371 0 402718720 3.8628041744 4.0381026268 3.9140665531 2585 1311867804.8758749962 0.1238606423 0.1238364209 0.2390826792 0.0046135543 0.8369560000 0.0749180000 0.0862890000 0.0315040000 0.3125110000 0.3256330000 145363099 0 402718720 3.8630800247 4.0390977859 3.9138188362 2586 1311867804.9093499184 0.1253410280 0.1238370028 0.2390826792 0.0046128909 0.4718540000 0.0863140000 0.0654080000 0.0000010000 0.3121990000 0.0017400000 145366827 0 402718720 3.8618755341 4.0376563072 3.9136812687 2587 1311867804.9418170452 0.1268849522 0.1238381809 0.2390826792 0.0046149405 0.5266310000 0.0749070000 0.0865400000 0.0314310000 0.3247010000 0.0023340000 145370499 0 402718720 3.8603141308 4.0392894745 3.9142029285 2588 1311867804.9785380363 0.1239900813 0.1238382396 0.2390826792 0.0046144939 0.5394310000 0.0955190000 0.1145880000 0.0000010000 0.3214660000 0.0017410000 145374227 0 402718720 3.8635368347 4.0399975777 3.9138414860 2589 1311867805.0090980530 0.1272241622 0.1238395474 0.2390826792 0.0046143151 0.7915490000 0.0753350000 0.0539360000 0.0316060000 0.3060170000 0.3183010000 145377843 0 402718720 3.8607454300 4.0381197929 3.9142763615 2590 1311867805.0401790142 0.1263664216 0.1238405231 0.2390826792 0.0046135566 0.4753300000 0.0753610000 0.0722780000 0.0000010000 0.3185350000 0.0023280000 145381515 0 402718720 3.8619327545 4.0383725166 3.9142889977 2591 1311867805.0801899433 0.1253817528 0.1238411179 0.2390826792 0.0046133224 0.5798080000 0.0955610000 0.1148430000 0.0390990000 0.3212060000 0.0023340000 145385411 0 402718720 3.8636636734 4.0390195847 3.9149010181 2592 1311867805.1079609394 0.1287222505 0.1238430011 0.2390826792 0.0046147564 0.4896340000 0.0878480000 0.0872320000 0.0000010000 0.3066310000 0.0017540000 145389027 0 402718720 3.8614866734 4.0375776291 3.9155845642 2593 1311867805.1444120407 0.1279179007 0.1238445726 0.2390826792 0.0046162567 0.8391870000 0.0873050000 0.0913350000 0.0315430000 0.3046190000 0.3182350000 145392811 0 402718720 3.8629770279 4.0376811028 3.9158601761 2594 1311867805.1750040054 0.1294492781 0.1238467332 0.2390826792 0.0046165314 0.4726430000 0.0757910000 0.0844630000 0.0000010000 0.3041800000 0.0018340000 145396371 0 402718720 3.8620445728 4.0383572578 3.9165990353 2595 1311867805.2100739479 0.1263682097 0.1238477049 0.2390826792 0.0046162850 0.5116690000 0.0758960000 0.0915070000 0.0315390000 0.3048600000 0.0017500000 145400155 0 402718720 3.8656628132 4.0383639336 3.9166476727 2596 1311867805.2393519878 0.1270404309 0.1238489347 0.2390826792 0.0046154436 0.4757000000 0.0755530000 0.0869510000 0.0000010000 0.3052340000 0.0017450000 145403771 0 402718720 3.8656117916 4.0377678871 3.9173357487 2597 1311867805.2741580009 0.1293644756 0.1238510585 0.2390826792 0.0046148948 0.8364710000 0.0889580000 0.0875930000 0.0314690000 0.3054660000 0.3168290000 145407499 0 402718720 3.8641092777 4.0373558998 3.9183402061 2598 1311867805.3108520508 0.1275786459 0.1238524933 0.2390826792 0.0046144142 0.4888720000 0.0858730000 0.0915660000 0.0000010000 0.3035480000 0.0017470000 145411283 0 402718720 3.8665916920 4.0375576019 3.9184253216 2599 1311867805.3395309448 0.1273827106 0.1238538516 0.2390826792 0.0046135533 0.4922990000 0.0744230000 0.0728690000 0.0314840000 0.3056530000 0.0017480000 145414899 0 402718720 3.8672101498 4.0372982025 3.9185087681 2600 1311867805.3745789528 0.1306067556 0.1238564489 0.2390826792 0.0046149969 0.4811800000 0.0758390000 0.0922810000 0.0000010000 0.3051030000 0.0017480000 145418627 0 402718720 3.8647165298 4.0368876457 3.9194054604 2601 1311867805.4084360600 0.1284809709 0.1238582269 0.2390826792 0.0046142811 0.8565810000 0.1066860000 0.0867260000 0.0310190000 0.3071170000 0.3188190000 145422411 0 402718720 3.8672418594 4.0378880501 3.9195287228 2602 1311867805.4401900768 0.1294036210 0.1238603581 0.2390826792 0.0046136139 0.4484390000 0.0752830000 0.0579900000 0.0000010000 0.3072630000 0.0017440000 145426027 0 402718720 3.8665590286 4.0391778946 3.9200360775 2603 1311867805.4747269154 0.1277458370 0.1238618508 0.2390826792 0.0046152997 0.4883120000 0.0752810000 0.0683990000 0.0315000000 0.3052070000 0.0017520000 145429755 0 402718720 3.8685519695 4.0383172035 3.9204299450 2604 1311867805.5079410076 0.1284821779 0.1238636251 0.2390826792 0.0046151627 0.4775590000 0.0751650000 0.0866450000 0.0000010000 0.3077710000 0.0017530000 145433483 0 402718720 3.8683831692 4.0382127762 3.9212803841 2605 1311867805.5406329632 0.1294377595 0.1238657649 0.2390826792 0.0046147452 0.8038910000 0.0751190000 0.0683450000 0.0309720000 0.3052070000 0.3180290000 145437211 0 402718720 3.8679475784 4.0387129784 3.9220876694 2606 1311867805.5750451088 0.1265614480 0.1238667993 0.2390826792 0.0046145101 0.4769410000 0.0748810000 0.0860030000 0.0000000000 0.3080700000 0.0017460000 145440883 0 402718720 3.8714163303 4.0368523598 3.9220578671 2607 1311867805.6078290939 0.1286915541 0.1238686500 0.2390826792 0.0046139541 0.5140200000 0.0751730000 0.0864990000 0.0314540000 0.3117750000 0.0023350000 145444611 0 402718720 3.8698806763 4.0350241661 3.9224970341 2608 1311867805.6431670189 0.1267184168 0.1238697427 0.2390826792 0.0046151797 0.5165590000 0.0942410000 0.1031270000 0.0000010000 0.3112090000 0.0017290000 145448395 0 402718720 3.8721032143 4.0365910530 3.9226977825 2609 1311867805.6750800610 0.1277550310 0.1238712319 0.2390826792 0.0046145167 0.8321580000 0.0870070000 0.0601070000 0.0314550000 0.3179260000 0.3294480000 145452067 0 402718720 3.8713591099 4.0363206863 3.9230079651 2610 1311867805.7071790695 0.1284074187 0.1238729699 0.2390826792 0.0046139566 0.4794730000 0.0735750000 0.0844250000 0.0000010000 0.3135140000 0.0017280000 145455795 0 402718720 3.8710584641 4.0355329514 3.9231731892 2611 1311867805.7425789833 0.1285045743 0.1238747438 0.2390826792 0.0046154554 0.5365690000 0.0971060000 0.0850040000 0.0313530000 0.3152170000 0.0017290000 145459579 0 402718720 3.8716468811 4.0359377861 3.9234254360 2612 1311867805.7748079300 0.1275576502 0.1238761538 0.2390826792 0.0046147038 0.4821880000 0.0722480000 0.0874420000 0.0000010000 0.3146000000 0.0017130000 145463195 0 402718720 3.8730187416 4.0360832214 3.9234974384 2613 1311867805.8089549541 0.1268314421 0.1238772848 0.2390826792 0.0046144420 0.8703420000 0.0988110000 0.0821260000 0.0313070000 0.3190960000 0.3327660000 145466923 0 402718720 3.8741552830 4.0362524986 3.9235272408 2614 1311867805.8436930180 0.1288976669 0.1238792053 0.2390826792 0.0046178294 0.4796950000 0.0702370000 0.0814590000 0.0000010000 0.3200830000 0.0017080000 145470595 0 402718720 3.8723680973 4.0368547440 3.9242975712 2615 1311867805.8754489422 0.1244080663 0.1238794076 0.2390826792 0.0046188658 0.5137180000 0.0715040000 0.0824760000 0.0309170000 0.3209170000 0.0017090000 145474267 0 402718720 3.8773107529 4.0368337631 3.9242734909 2616 1311867805.9129049778 0.1276486665 0.1238808484 0.2390826792 0.0046212292 0.4618760000 0.0835230000 0.0479020000 0.0000010000 0.3225150000 0.0016910000 145478107 0 402718720 3.8747522831 4.0360946655 3.9250628948 2617 1311867805.9434199333 0.1296768337 0.1238830632 0.2390826792 0.0046211926 0.8629520000 0.0705700000 0.0831900000 0.0312990000 0.3239170000 0.3471440000 145481779 0 402718720 3.8731448650 4.0355520248 3.9255180359 2618 1311867805.9747679234 0.1277244538 0.1238845305 0.2390826792 0.0046207144 0.5291210000 0.0882940000 0.1060850000 0.0000000000 0.3267930000 0.0016880000 145485395 0 402718720 3.8753459454 4.0370140076 3.9252307415 2619 1311867806.0099248886 0.1333003789 0.1238881257 0.2390826792 0.0046229965 0.5181680000 0.0695500000 0.0826950000 0.0313040000 0.3267290000 0.0016910000 145489123 0 402718720 3.8703002930 4.0369968414 3.9263064861 2620 1311867806.0427870750 0.1310161501 0.1238908463 0.2390826792 0.0046227294 0.4846550000 0.0690070000 0.0796710000 0.0000000000 0.3280480000 0.0016780000 145492907 0 402718720 3.8731813431 4.0370411873 3.9264261723 2621 1311867806.0743720531 0.1321993619 0.1238940163 0.2390826792 0.0046283210 0.8945180000 0.0870810000 0.0791600000 0.0312210000 0.3417640000 0.3490830000 145496467 0 402718720 3.8723990917 4.0381674767 3.9270548820 2622 1311867806.1078710556 0.1327155083 0.1238973807 0.2390826792 0.0046274437 0.4529010000 0.0689960000 0.0493170000 0.0000010000 0.3266540000 0.0016790000 145500195 0 402718720 3.8725931644 4.0376086235 3.9272515774 2623 1311867806.1461410522 0.1322434843 0.1239005626 0.2390826792 0.0046271641 0.5308190000 0.0822600000 0.0836060000 0.0313140000 0.3257590000 0.0016780000 145504035 0 402718720 3.8741469383 4.0385236740 3.9277894497 2624 1311867806.1751658916 0.1310962886 0.1239033048 0.2390826792 0.0046267331 0.4847290000 0.0683700000 0.0793150000 0.0000010000 0.3291690000 0.0016650000 145507595 0 402718720 3.8760623932 4.0397591591 3.9281859398 2625 1311867806.2106690407 0.1306791008 0.1239058861 0.2390826792 0.0046275053 0.8580290000 0.0684680000 0.0792540000 0.0312200000 0.3284330000 0.3444590000 145511379 0 402718720 3.8773970604 4.0387854576 3.9282407761 2626 1311867806.2435200214 0.1308704466 0.1239085383 0.2390826792 0.0046268655 0.4648490000 0.0685980000 0.0598620000 0.0000010000 0.3283870000 0.0016780000 145515107 0 402718720 3.8781430721 4.0385427475 3.9288520813 2627 1311867806.2773389816 0.1303334981 0.1239109840 0.2390826792 0.0046266276 0.5148350000 0.0683750000 0.0792350000 0.0312500000 0.3281190000 0.0016780000 145518835 0 402718720 3.8794105053 4.0405349731 3.9293141365 2628 1311867806.3098840714 0.1304461658 0.1239134707 0.2390826792 0.0046259719 0.4666520000 0.0785060000 0.0561120000 0.0000010000 0.3237950000 0.0017660000 145522451 0 402718720 3.8800961971 4.0392436981 3.9295058250 2629 1311867806.3459429741 0.1309711337 0.1239161553 0.2390826792 0.0046258151 0.8597680000 0.0686160000 0.0829240000 0.0307600000 0.3277500000 0.3435260000 145526291 0 402718720 3.8803436756 4.0401482582 3.9300534725 2630 1311867806.3760368824 0.1314382851 0.1239190154 0.2390826792 0.0046252591 0.4770250000 0.0687580000 0.0729450000 0.0000010000 0.3274150000 0.0016700000 145529907 0 402718720 3.8805313110 4.0411396027 3.9305505753 2631 1311867806.4090569019 0.1323789060 0.1239222309 0.2390826792 0.0046322783 0.5432220000 0.0974680000 0.0800440000 0.0312150000 0.3265630000 0.0016780000 145533579 0 402718720 3.8805861473 4.0394325256 3.9306800365 2632 1311867806.4434189796 0.1315173358 0.1239251166 0.2390826792 0.0046324290 0.4839190000 0.0688060000 0.0796200000 0.0000000000 0.3275610000 0.0016760000 145537307 0 402718720 3.8820607662 4.0393691063 3.9305381775 2633 1311867806.4748079777 0.1312288344 0.1239278905 0.2390826792 0.0046343045 0.8672160000 0.0797460000 0.0790560000 0.0311550000 0.3276840000 0.3433260000 145540979 0 402718720 3.8829855919 4.0401806831 3.9308969975 2634 1311867806.5103459358 0.1321714520 0.1239310202 0.2390826792 0.0046337212 0.4981440000 0.0690750000 0.0793570000 0.0000010000 0.3405220000 0.0022150000 145544763 0 402718720 3.8829910755 4.0384936333 3.9309542179 2635 1311867806.5426719189 0.1292106807 0.1239330238 0.2390826792 0.0046336508 0.5782650000 0.0864950000 0.1038420000 0.0385890000 0.3414510000 0.0016760000 145548435 0 402718720 3.8865888119 4.0391540527 3.9311525822 2636 1311867806.5787520409 0.1297849566 0.1239352438 0.2390826792 0.0046331865 0.4585030000 0.0684850000 0.0532920000 0.0000000000 0.3287580000 0.0016650000 145552163 0 402718720 3.8865077496 4.0410056114 3.9315431118 2637 1311867806.6116139889 0.1311502308 0.1239379799 0.2390826792 0.0046336720 0.8559350000 0.0680640000 0.0787270000 0.0312100000 0.3279420000 0.3437160000 145555947 0 402718720 3.8855805397 4.0398073196 3.9320473671 2638 1311867806.6448700428 0.1300032437 0.1239402791 0.2390826792 0.0046328678 0.4698040000 0.0807460000 0.0527190000 0.0000000000 0.3282810000 0.0016750000 145559619 0 402718720 3.8871588707 4.0402345657 3.9324965477 2639 1311867806.6744968891 0.1277611107 0.1239417269 0.2390826792 0.0046328215 0.5262240000 0.0806420000 0.0787440000 0.0306700000 0.3281970000 0.0016700000 145563235 0 402718720 3.8897390366 4.0423221588 3.9332308769 2640 1311867806.7064468861 0.1295245290 0.1239438416 0.2390826792 0.0046322389 0.4568720000 0.0688170000 0.0534230000 0.0000010000 0.3266040000 0.0016740000 145566907 0 402718720 3.8881969452 4.0417690277 3.9340326786 2641 1311867806.7427020073 0.1303861141 0.1239462809 0.2390826792 0.0046314922 0.8388520000 0.0808510000 0.0532080000 0.0311060000 0.3261930000 0.3412340000 145570691 0 402718720 3.8878209591 4.0413837433 3.9344084263 2642 1311867806.7790679932 0.1276641190 0.1239476881 0.2390826792 0.0046321101 0.4814710000 0.0682430000 0.0795050000 0.0000010000 0.3258000000 0.0016640000 145574419 0 402718720 3.8905260563 4.0427193642 3.9351491928 2643 1311867806.8067629337 0.1282518059 0.1239493166 0.2390826792 0.0046316870 0.5241470000 0.0806080000 0.0796240000 0.0311420000 0.3248330000 0.0016820000 145578035 0 402718720 3.8903293610 4.0421562195 3.9356257915 2644 1311867806.8439810276 0.1294593066 0.1239514006 0.2390826792 0.0046309959 0.4890290000 0.0688380000 0.0796520000 0.0000010000 0.3313500000 0.0022230000 145581819 0 402718720 3.8894922733 4.0406103134 3.9360175133 2645 1311867806.8763918877 0.1279932410 0.1239529287 0.2390826792 0.0046306357 0.8499680000 0.0684850000 0.0794920000 0.0306930000 0.3251770000 0.3398620000 145585491 0 402718720 3.8912329674 4.0426654816 3.9367318153 2646 1311867806.9124479294 0.1315247118 0.1239557903 0.2390826792 0.0046304881 0.4834090000 0.0689330000 0.0809200000 0.0000000000 0.3256120000 0.0016380000 145589275 0 402718720 3.8879120350 4.0419540405 3.9370112419 2647 1311867806.9446148872 0.1316733211 0.1239587059 0.2390826792 0.0046298817 0.5134500000 0.0692670000 0.0800890000 0.0311500000 0.3249570000 0.0016850000 145592891 0 402718720 3.8883202076 4.0406079292 3.9372456074 2648 1311867806.9770460129 0.1308982521 0.1239613265 0.2390826792 0.0046296498 0.4906040000 0.0779750000 0.0790120000 0.0000010000 0.3256470000 0.0016620000 145596675 0 402718720 3.8893301487 4.0424475670 3.9377334118 2649 1311867807.0138700008 0.1304545403 0.1239637777 0.2390826792 0.0046302458 0.8382270000 0.0688730000 0.0703140000 0.0311870000 0.3219000000 0.3395440000 145600403 0 402718720 3.8904211521 4.0409760475 3.9377825260 2650 1311867807.0428779125 0.1286449432 0.1239655442 0.2390826792 0.0046300550 0.4810330000 0.0681590000 0.0792460000 0.0000010000 0.3256340000 0.0016590000 145604075 0 402718720 3.8928756714 4.0398349762 3.9379217625 2651 1311867807.0794920921 0.1311822832 0.1239682665 0.2390826792 0.0046310223 0.5396380000 0.0942410000 0.0796990000 0.0311390000 0.3265590000 0.0016780000 145607803 0 402718720 3.8908433914 4.0393967628 3.9386405945 2652 1311867807.1121389866 0.1319946945 0.1239712930 0.2390826792 0.0046306147 0.4572320000 0.0684470000 0.0534530000 0.0000010000 0.3274010000 0.0016740000 145611531 0 402718720 3.8903064728 4.0407266617 3.9393305779 2653 1311867807.1428070068 0.1334461272 0.1239748644 0.2390826792 0.0046303433 0.8231260000 0.0684250000 0.0468240000 0.0311130000 0.3278230000 0.3426270000 145615203 0 402718720 3.8894531727 4.0391426086 3.9395701885 2654 1311867807.1802010536 0.1335252225 0.1239784629 0.2390826792 0.0046311206 0.4664710000 0.0679980000 0.0529860000 0.0000000000 0.3362850000 0.0021980000 145618875 0 402718720 3.8898882866 4.0403223038 3.9403476715 2655 1311867807.2105820179 0.1342255175 0.1239823224 0.2390826792 0.0046324406 0.5496030000 0.0849340000 0.0964740000 0.0310800000 0.3291920000 0.0016570000 145622491 0 402718720 3.8893299103 4.0428342819 3.9411759377 2656 1311867807.2429521084 0.1350672096 0.1239864959 0.2390826792 0.0046318251 0.4822600000 0.0669760000 0.0784160000 0.0000010000 0.3288730000 0.0016480000 145626163 0 402718720 3.8888881207 4.0412449837 3.9415526390 2657 1311867807.2808670998 0.1355874985 0.1239908622 0.2390826792 0.0046310201 0.8362710000 0.0794080000 0.0465350000 0.0306730000 0.3290230000 0.3443190000 145630003 0 402718720 3.8891277313 4.0395159721 3.9415364265 2658 1311867807.3107318878 0.1367865205 0.1239956762 0.2390826792 0.0046303883 0.4931510000 0.0724640000 0.0696450000 0.0000010000 0.3430250000 0.0016700000 145633619 0 402718720 3.8886761665 4.0397934914 3.9420292377 2659 1311867807.3434429169 0.1354611665 0.1239999881 0.2390826792 0.0046298950 0.5130080000 0.0668580000 0.0775590000 0.0310820000 0.3295060000 0.0016620000 145637291 0 402718720 3.8907687664 4.0395083427 3.9423673153 2660 1311867807.3776888847 0.1365188062 0.1240046944 0.2390826792 0.0046297532 0.4811190000 0.0656650000 0.0772960000 0.0000010000 0.3301540000 0.0016600000 145641019 0 402718720 3.8904078007 4.0380415916 3.9422643185 2661 1311867807.4111731052 0.1345532686 0.1240086586 0.2390826792 0.0046312732 0.8716570000 0.0817160000 0.0612330000 0.0306570000 0.3306310000 0.3603440000 145644747 0 402718720 3.8926808834 4.0390043259 3.9421718121 2662 1311867807.4426960945 0.1356020123 0.1240130137 0.2390826792 0.0046313473 0.4997410000 0.0840950000 0.0774420000 0.0000000000 0.3302040000 0.0016400000 145648419 0 402718720 3.8919990063 4.0399179459 3.9422440529 2663 1311867807.4781239033 0.1359916329 0.1240175119 0.2390826792 0.0046347929 0.5145090000 0.0670350000 0.0779580000 0.0311900000 0.3303930000 0.0016620000 145652147 0 402718720 3.8921523094 4.0379123688 3.9415354729 2664 1311867807.5104010105 0.1371371746 0.1240224367 0.2390826792 0.0046343703 0.4830110000 0.0660390000 0.0772520000 0.0000000000 0.3316540000 0.0016410000 145655763 0 402718720 3.8914277554 4.0371880531 3.9412562847 2665 1311867807.5430259705 0.1366610974 0.1240271791 0.2390826792 0.0046340792 0.8794140000 0.0654750000 0.0722030000 0.0378750000 0.3466680000 0.3508460000 145659435 0 402718720 3.8922469616 4.0378074646 3.9408738613 2666 1311867807.5746030807 0.1362052709 0.1240317471 0.2390826792 0.0046357165 0.4536530000 0.0658300000 0.0456030000 0.0000000000 0.3342300000 0.0016410000 145663107 0 402718720 3.8928005695 4.0357336998 3.9400517941 2667 1311867807.6121149063 0.1351740360 0.1240359249 0.2390826792 0.0046364801 0.5179120000 0.0654310000 0.0771180000 0.0310310000 0.3363830000 0.0016480000 145666947 0 402718720 3.8939533234 4.0351495743 3.9391429424 2668 1311867807.6434121132 0.1346166581 0.1240398907 0.2390826792 0.0046367358 0.4872920000 0.0644000000 0.0763900000 0.0000010000 0.3384880000 0.0016230000 145670619 0 402718720 3.8946483135 4.0352802277 3.9386909008 2669 1311867807.6772611141 0.1340892315 0.1240436559 0.2390826792 0.0046364797 0.8484030000 0.0634170000 0.0530990000 0.0310780000 0.3357820000 0.3586340000 145674347 0 402718720 3.8951244354 4.0346236229 3.9376785755 2670 1311867807.7112979889 0.1354196966 0.1240479166 0.2390826792 0.0046358284 0.4865310000 0.0753880000 0.0610750000 0.0000010000 0.3420310000 0.0016200000 145678075 0 402718720 3.8937280178 4.0327076912 3.9369845390 2671 1311867807.7441759109 0.1330766827 0.1240512969 0.2390826792 0.0046375774 0.5155090000 0.0830850000 0.0493260000 0.0310150000 0.3441520000 0.0016090000 145681803 0 402718720 3.8956432343 4.0350670815 3.9368445873 2672 1311867807.7760479450 0.1350647360 0.1240554187 0.2390826792 0.0046375691 0.4708740000 0.0626610000 0.0596940000 0.0000000000 0.3402110000 0.0017030000 145685419 0 402718720 3.8932852745 4.0357351303 3.9369735718 2673 1311867807.8105859756 0.1335163116 0.1240589581 0.2390826792 0.0046378582 0.8850020000 0.0786650000 0.0563180000 0.0310840000 0.3467950000 0.3657510000 145689147 0 402718720 3.8942475319 4.0351476669 3.9362394810 2674 1311867807.8429179192 0.1329765916 0.1240622931 0.2390826792 0.0046375439 0.4974870000 0.0611060000 0.0764830000 0.0000010000 0.3508020000 0.0021040000 145692819 0 402718720 3.8944871426 4.0356702805 3.9361414909 2675 1311867807.8800721169 0.1324089617 0.1240654133 0.2390826792 0.0046370099 0.5592950000 0.0778640000 0.0725530000 0.0383810000 0.3614010000 0.0020980000 145696547 0 402718720 3.8943965435 4.0371155739 3.9359574318 2676 1311867807.9118909836 0.1336048096 0.1240689781 0.2390826792 0.0046368384 0.5093710000 0.0777920000 0.0727810000 0.0000010000 0.3508180000 0.0016070000 145700275 0 402718720 3.8929245472 4.0353312492 3.9358127117 2677 1311867807.9477560520 0.1296492219 0.1240710626 0.2390826792 0.0046393509 0.8714570000 0.0611290000 0.0549570000 0.0309330000 0.3489290000 0.3691010000 145704003 0 402718720 3.8966987133 4.0343470573 3.9349169731 2678 1311867807.9757928848 0.1301625073 0.1240733372 0.2390826792 0.0046386231 0.5558970000 0.0873120000 0.0951780000 0.0000010000 0.3642020000 0.0021020000 145707563 0 402718720 3.8959896564 4.0349335670 3.9351015091 2679 1311867808.0103120804 0.1284525394 0.1240749719 0.2390826792 0.0046407293 0.5408580000 0.0770910000 0.0643720000 0.0377560000 0.3536090000 0.0016140000 145711291 0 402718720 3.8980569839 4.0358157158 3.9348244667 2680 1311867808.0437099934 0.1326587498 0.1240781748 0.2390826792 0.0046426175 0.4921260000 0.0601470000 0.0732350000 0.0000010000 0.3507810000 0.0015930000 145715019 0 402718720 3.8938705921 4.0367536545 3.9352390766 2681 1311867808.0799739361 0.1372328550 0.1240830814 0.2390826792 0.0046688613 0.9285950000 0.0813290000 0.0617180000 0.0305010000 0.3612920000 0.3866880000 145718803 0 402718720 3.8897202015 4.0360088348 3.9345426559 2682 1311867808.1118609905 0.1357729435 0.1240874401 0.2390826792 0.0046710080 0.5231920000 0.0777410000 0.0803050000 0.0000010000 0.3568140000 0.0017500000 145722475 0 402718720 3.8914067745 4.0355329514 3.9334011078 2683 1311867808.1470420361 0.1322474927 0.1240904814 0.2390826792 0.0046714654 0.5383390000 0.0725390000 0.0766700000 0.0310590000 0.3497290000 0.0017080000 145726203 0 402718720 3.8950684071 4.0345139503 3.9316632748 2684 1311867808.1792190075 0.1358781755 0.1240948733 0.2390826792 0.0046741624 0.4951150000 0.0597470000 0.0721450000 0.0000010000 0.3552220000 0.0015960000 145729819 0 402718720 3.8914623260 4.0356721878 3.9315629005 2685 1311867808.2112250328 0.1350460202 0.1240989519 0.2390826792 0.0046954529 0.9028580000 0.0595960000 0.0720280000 0.0309910000 0.3562340000 0.3776510000 145733547 0 402718720 3.8915393353 4.0332660675 3.9299705029 2686 1311867808.2432029247 0.1339921206 0.1241026352 0.2390826792 0.0046946343 0.4910750000 0.0590990000 0.0655260000 0.0000010000 0.3584570000 0.0016060000 145737275 0 402718720 3.8929777145 4.0324220657 3.9287302494 2687 1311867808.2811930180 0.1367687732 0.1241073490 0.2390826792 0.0046954752 0.5158010000 0.0695860000 0.0416520000 0.0310550000 0.3644460000 0.0020740000 145741059 0 402718720 3.8905353546 4.0327086449 3.9283151627 2688 1311867808.3112449646 0.1354352832 0.1241115633 0.2390826792 0.0046946681 0.5114770000 0.0776160000 0.0647300000 0.0000010000 0.3611130000 0.0015910000 145744675 0 402718720 3.8922259808 4.0326547623 3.9275140762 2689 1311867808.3454720974 0.1378389448 0.1241166683 0.2390826792 0.0046946062 0.8854190000 0.0579370000 0.0447320000 0.0305820000 0.3602710000 0.3855260000 145748403 0 402718720 3.8902766705 4.0325355530 3.9275269508 2690 1311867808.3792409897 0.1369280964 0.1241214309 0.2390826792 0.0046938433 0.4858480000 0.0561880000 0.0608070000 0.0000010000 0.3608640000 0.0015720000 145752075 0 402718720 3.8912863731 4.0326395035 3.9268925190 2691 1311867808.4111659527 0.1400910020 0.1241273653 0.2390826792 0.0046934177 0.5282000000 0.0567620000 0.0683310000 0.0308170000 0.3642980000 0.0015760000 145755803 0 402718720 3.8884084225 4.0320205688 3.9266099930 2692 1311867808.4447789192 0.1383373886 0.1241326440 0.2390826792 0.0046932859 0.4908050000 0.0672080000 0.0512320000 0.0000010000 0.3644390000 0.0015680000 145759475 0 402718720 3.8902347088 4.0335536003 3.9261770248 2693 1311867808.4827229977 0.1409764588 0.1241388986 0.2390826792 0.0046949931 0.9347900000 0.0737520000 0.0721680000 0.0310660000 0.3626030000 0.3887720000 145763371 0 402718720 3.8876848221 4.0326848030 3.9262514114 2694 1311867808.5103700161 0.1378891319 0.1241440026 0.2390826792 0.0047024122 0.4754440000 0.0562020000 0.0456830000 0.0000010000 0.3655860000 0.0015700000 145766875 0 402718720 3.8910176754 4.0315823555 3.9252095222 2695 1311867808.5431969166 0.1403351128 0.1241500105 0.2390826792 0.0047037752 0.4982710000 0.0556400000 0.0423420000 0.0310430000 0.3613580000 0.0015620000 145770659 0 402718720 3.8884887695 4.0337386131 3.9255247116 2696 1311867808.5788240433 0.1416504234 0.1241565017 0.2390826792 0.0047030014 0.4992300000 0.0565570000 0.0685100000 0.0000010000 0.3661730000 0.0015730000 145774387 0 402718720 3.8872654438 4.0320515633 3.9247825146 2697 1311867808.6111960411 0.1397654116 0.1241622892 0.2390826792 0.0047023420 0.9278090000 0.0562020000 0.0678700000 0.0310630000 0.3669720000 0.3993020000 145778059 0 402718720 3.8890647888 4.0320076942 3.9244349003 2698 1311867808.6424980164 0.1377882063 0.1241673396 0.2390826792 0.0047016963 0.5122030000 0.0683930000 0.0677130000 0.0000000000 0.3681150000 0.0015760000 145781731 0 402718720 3.8909392357 4.0318956375 3.9235389233 2699 1311867808.6796329021 0.1414302588 0.1241737357 0.2390826792 0.0047020465 0.5103260000 0.0561870000 0.0461050000 0.0310210000 0.3691420000 0.0015440000 145785459 0 402718720 3.8871901035 4.0322780609 3.9237062931 2700 1311867808.7121589184 0.1410414726 0.1241799830 0.2390826792 0.0047013423 0.5210650000 0.0817530000 0.0616690000 0.0000010000 0.3696080000 0.0015690000 145789243 0 402718720 3.8875751495 4.0325646400 3.9231987000 2701 1311867808.7424249649 0.1403797567 0.1241859807 0.2390826792 0.0047014111 0.9102750000 0.0558190000 0.0541580000 0.0310910000 0.3661780000 0.3966090000 145792859 0 402718720 3.8885285854 4.0312705040 3.9222543240 2702 1311867808.7797210217 0.1419607699 0.1241925590 0.2390826792 0.0047013596 0.5031530000 0.0556830000 0.0675770000 0.0000000000 0.3718630000 0.0015760000 145796643 0 402718720 3.8874044418 4.0298285484 3.9219002724 2703 1311867808.8102169037 0.1417350620 0.1241990490 0.2390826792 0.0047020327 0.5617360000 0.0837970000 0.0667280000 0.0309960000 0.3722660000 0.0015570000 145800259 0 402718720 3.8876900673 4.0314931870 3.9214580059 2704 1311867808.8426899910 0.1415972561 0.1242054833 0.2390826792 0.0047057657 0.5179880000 0.0644110000 0.0595650000 0.0000000000 0.3859570000 0.0015680000 145803931 0 402718720 3.8881335258 4.0296697617 3.9199099541 2705 1311867808.8811960220 0.1394535303 0.1242111203 0.2390826792 0.0047052526 0.9349580000 0.0550370000 0.0667510000 0.0306360000 0.3745110000 0.4016230000 145807827 0 402718720 3.8906459808 4.0300173759 3.9189171791 2706 1311867808.9101860523 0.1419988722 0.1242176937 0.2390826792 0.0047050111 0.4842290000 0.0537620000 0.0444350000 0.0000000000 0.3780980000 0.0015510000 145811387 0 402718720 3.8883428574 4.0298619270 3.9192123413 2707 1311867808.9424829483 0.1392673552 0.1242232533 0.2390826792 0.0047049832 0.5248510000 0.0546050000 0.0557810000 0.0311040000 0.3754060000 0.0015680000 145815115 0 402718720 3.8914043903 4.0279746056 3.9176950455 2708 1311867808.9811229706 0.1413142234 0.1242295646 0.2390826792 0.0047076971 0.5150480000 0.0638130000 0.0659820000 0.0000010000 0.3773380000 0.0015510000 145818955 0 402718720 3.8894727230 4.0288062096 3.9174094200 2709 1311867809.0102269650 0.1418341100 0.1242360631 0.2390826792 0.0047070424 0.9366480000 0.0534610000 0.0697150000 0.0306730000 0.3728880000 0.4034860000 145822515 0 402718720 3.8888418674 4.0295877457 3.9170391560 2710 1311867809.0425639153 0.1402321011 0.1242419657 0.2390826792 0.0047063455 0.5417710000 0.0542960000 0.0854540000 0.0000000000 0.3928890000 0.0020290000 145826243 0 402718720 3.8908240795 4.0277733803 3.9155194759 2711 1311867809.0782320499 0.1407347620 0.1242480494 0.2390826792 0.0047071446 0.5774090000 0.0674300000 0.0849540000 0.0369290000 0.3801470000 0.0015490000 145829971 0 402718720 3.8904638290 4.0286097527 3.9153563976 2712 1311867809.1110110283 0.1393061578 0.1242536018 0.2390826792 0.0047065797 0.5058620000 0.0524500000 0.0648580000 0.0000000000 0.3805990000 0.0015380000 145833699 0 402718720 3.8919067383 4.0295276642 3.9144375324 2713 1311867809.1425359249 0.1420326829 0.1242601550 0.2390826792 0.0047068037 0.9368330000 0.0678100000 0.0386550000 0.0309230000 0.3815800000 0.4114080000 145837371 0 402718720 3.8894212246 4.0286412239 3.9141919613 2714 1311867809.1801810265 0.1446468383 0.1242676667 0.2390826792 0.0047077588 0.5120040000 0.0518030000 0.0643750000 0.0000010000 0.3878760000 0.0015340000 145841155 0 402718720 3.8870067596 4.0295853615 3.9139704704 2715 1311867809.2120649815 0.1446061283 0.1242751579 0.2390826792 0.0047080650 0.5510010000 0.0657020000 0.0646260000 0.0310850000 0.3816210000 0.0015360000 145844827 0 402718720 3.8873431683 4.0311489105 3.9143011570 2716 1311867809.2422831059 0.1421201527 0.1242817282 0.2390826792 0.0047074373 0.5076690000 0.0520040000 0.0596500000 0.0000010000 0.3868960000 0.0019790000 145848499 0 402718720 3.8900332451 4.0316572189 3.9136481285 2717 1311867809.2790520191 0.1422062665 0.1242883254 0.2390826792 0.0047069868 1.0073380000 0.0674410000 0.0849230000 0.0380830000 0.3950830000 0.4153290000 145852171 0 402718720 3.8903236389 4.0301380157 3.9128954411 2718 1311867809.3103950024 0.1429545730 0.1242951930 0.2390826792 0.0047063068 0.5246260000 0.0718380000 0.0680280000 0.0000010000 0.3767400000 0.0015350000 145855843 0 402718720 3.8900203705 4.0309524536 3.9129583836 2719 1311867809.3436670303 0.1469074488 0.1243035094 0.2390826792 0.0047063125 0.5392750000 0.0531910000 0.0653280000 0.0311580000 0.3816220000 0.0015480000 145859571 0 402718720 3.8866980076 4.0306549072 3.9132528305 2720 1311867809.3787779808 0.1460009217 0.1243114864 0.2390826792 0.0047054718 0.4962210000 0.0525650000 0.0577750000 0.0000010000 0.3775840000 0.0016300000 145863243 0 402718720 3.8881938457 4.0308594704 3.9128403664 2721 1311867809.4101309776 0.1465973705 0.1243196767 0.2390826792 0.0047049104 0.9381910000 0.0517450000 0.0515030000 0.0311620000 0.3831150000 0.4141790000 145866915 0 402718720 3.8881947994 4.0305137634 3.9122226238 2722 1311867809.4475460052 0.1443444341 0.1243270333 0.2390826792 0.0047053934 0.5079140000 0.0524090000 0.0539290000 0.0000010000 0.3924460000 0.0019790000 145870755 0 402718720 3.8914151192 4.0308518410 3.9115850925 2723 1311867809.4785499573 0.1437088251 0.1243341512 0.2390826792 0.0047048571 0.5984000000 0.0669380000 0.0847810000 0.0388170000 0.3987620000 0.0019930000 145874483 0 402718720 3.8926327229 4.0305433273 3.9107925892 2724 1311867809.5100600719 0.1443110257 0.1243414848 0.2390826792 0.0047055036 0.5086200000 0.0620100000 0.0531670000 0.0000010000 0.3853520000 0.0015430000 145878043 0 402718720 3.8927037716 4.0315423012 3.9106800556 2725 1311867809.5460391045 0.1437772661 0.1243486172 0.2390826792 0.0047048968 0.9455200000 0.0512040000 0.0570400000 0.0312720000 0.3817480000 0.4177820000 145881883 0 402718720 3.8940134048 4.0327081680 3.9100193977 2726 1311867809.5791211128 0.1446134001 0.1243560511 0.2390826792 0.0047041113 0.5223760000 0.0646950000 0.0640970000 0.0000010000 0.3855440000 0.0015390000 145885555 0 402718720 3.8942387104 4.0324816704 3.9098689556 2727 1311867809.6122300625 0.1440318972 0.1243632663 0.2390826792 0.0047036179 0.5410930000 0.0519200000 0.0639300000 0.0312250000 0.3860090000 0.0015430000 145889283 0 402718720 3.8953061104 4.0346074104 3.9093263149 2728 1311867809.6463921070 0.1405053139 0.1243691835 0.2390826792 0.0047039878 0.5148400000 0.0732680000 0.0505240000 0.0000010000 0.3829770000 0.0015320000 145893011 0 402718720 3.8996675014 4.0345811844 3.9083409309 2729 1311867809.6796839237 0.1417086869 0.1243755373 0.2390826792 0.0047034488 0.9686420000 0.0509360000 0.0682220000 0.0381360000 0.3862170000 0.4185190000 145896683 0 402718720 3.8995430470 4.0354156494 3.9088785648 2730 1311867809.7111020088 0.1439437568 0.1243827051 0.2390826792 0.0047028717 0.5092710000 0.0519600000 0.0642100000 0.0000000000 0.3850180000 0.0015450000 145900355 0 402718720 3.8982524872 4.0348310471 3.9082918167 2731 1311867809.7464809418 0.1408699453 0.1243887422 0.2390826792 0.0047028623 0.5307730000 0.0516310000 0.0538660000 0.0312190000 0.3860410000 0.0015450000 145904139 0 402718720 3.9023578167 4.0340690613 3.9065499306 2732 1311867809.7800478935 0.1438752860 0.1243958749 0.2390826792 0.0047027646 0.5100750000 0.0512520000 0.0636310000 0.0000010000 0.3871370000 0.0015330000 145907811 0 402718720 3.9005658627 4.0346360207 3.9063446522 2733 1311867809.8107759953 0.1404463500 0.1244017477 0.2390826792 0.0047041682 0.9770250000 0.0653670000 0.0675330000 0.0313350000 0.3839320000 0.4222670000 145911483 0 402718720 3.9050140381 4.0344748497 3.9045562744 2734 1311867809.8470799923 0.1413669288 0.1244079530 0.2390826792 0.0047034152 0.5127600000 0.0513910000 0.0638550000 0.0000000000 0.3894440000 0.0015450000 145915267 0 402718720 3.9049849510 4.0338511467 3.9034399986 2735 1311867809.8791100979 0.1428246349 0.1244146867 0.2390826792 0.0047031690 0.5799260000 0.0567790000 0.0829930000 0.0382880000 0.3937210000 0.0015460000 145918939 0 402718720 3.9042131901 4.0335440636 3.9020452499 2736 1311867809.9124441147 0.1418700665 0.1244210666 0.2390826792 0.0047032235 0.5344430000 0.0689280000 0.0673290000 0.0000010000 0.3900780000 0.0015390000 145922611 0 402718720 3.9058902264 4.0337867737 3.9006161690 2737 1311867809.9469900131 0.1430238038 0.1244278633 0.2390826792 0.0047025797 0.9822210000 0.0498810000 0.0669790000 0.0313810000 0.3945690000 0.4329180000 145926339 0 402718720 3.9052152634 4.0329551697 3.8994555473 2738 1311867809.9805769920 0.1436934322 0.1244348997 0.2390826792 0.0047036441 0.5219100000 0.0504140000 0.0663020000 0.0000010000 0.3971580000 0.0015250000 145929955 0 402718720 3.9045312405 4.0345621109 3.8983466625 2739 1311867810.0119459629 0.1480039954 0.1244435047 0.2390826792 0.0047046390 0.5485570000 0.0488120000 0.0619500000 0.0312560000 0.3985160000 0.0015090000 145933571 0 402718720 3.9003102779 4.0340242386 3.8981764317 2740 1311867810.0470910072 0.1469669938 0.1244517250 0.2390826792 0.0047038137 0.5162800000 0.0479940000 0.0607430000 0.0000000000 0.3994590000 0.0015000000 145937299 0 402718720 3.9013447762 4.0332942009 3.8975093365 2741 1311867810.0808799267 0.1448143870 0.1244591539 0.2390826792 0.0047039267 1.0036740000 0.0484400000 0.0607230000 0.0313750000 0.4105130000 0.4459300000 145940971 0 402718720 3.9031162262 4.0349922180 3.8967556953 2742 1311867810.1118919849 0.1468299627 0.1244673124 0.2390826792 0.0047039779 0.5171240000 0.0483440000 0.0610820000 0.0000010000 0.3996640000 0.0015080000 145944643 0 402718720 3.9009964466 4.0357356071 3.8970487118 2743 1311867810.1474719048 0.1466961950 0.1244754163 0.2390826792 0.0047032071 0.5592770000 0.0567940000 0.0652070000 0.0313900000 0.3978830000 0.0015030000 145948427 0 402718720 3.9009838104 4.0357708931 3.8965127468 2744 1311867810.1817660332 0.1444909871 0.1244827106 0.2390826792 0.0047025571 0.5168960000 0.0479610000 0.0609360000 0.0000000000 0.3999300000 0.0015040000 145952099 0 402718720 3.9031281471 4.0345211029 3.8957664967 2745 1311867810.2106039524 0.1436278522 0.1244896852 0.2390826792 0.0047018077 0.9938940000 0.0661190000 0.0480470000 0.0313960000 0.4005990000 0.4411190000 145955715 0 402718720 3.9038183689 4.0364904404 3.8948881626 2746 1311867810.2471721172 0.1416635662 0.1244959393 0.2390826792 0.0047037344 0.5165330000 0.0476950000 0.0603050000 0.0000010000 0.4005020000 0.0014910000 145959499 0 402718720 3.9061653614 4.0367813110 3.8939743042 2747 1311867810.2785871029 0.1426199973 0.1245025371 0.2390826792 0.0047028912 0.5683070000 0.0485470000 0.0605700000 0.0359580000 0.4141490000 0.0019130000 145963115 0 402718720 3.9052412510 4.0363445282 3.8934440613 2748 1311867810.3111360073 0.1409695148 0.1245085294 0.2390826792 0.0047023097 0.5249770000 0.0567640000 0.0605100000 0.0000010000 0.3997110000 0.0015020000 145966843 0 402718720 3.9070527554 4.0360522270 3.8932015896 2749 1311867810.3463029861 0.1403456181 0.1245142905 0.2390826792 0.0047019030 0.9879530000 0.0480010000 0.0605970000 0.0313670000 0.3996070000 0.4410990000 145970627 0 402718720 3.9079036713 4.0352187157 3.8927533627 2750 1311867810.3784830570 0.1379177868 0.1245191645 0.2390826792 0.0047014681 0.5617350000 0.0604580000 0.0782860000 0.0000010000 0.4138960000 0.0019110000 145974355 0 402718720 3.9103033543 4.0350894928 3.8919863701 2751 1311867810.4100239277 0.1351984888 0.1245230464 0.2390826792 0.0047008905 0.5800860000 0.0599090000 0.0777880000 0.0346790000 0.3996580000 0.0014960000 145977915 0 402718720 3.9129691124 4.0342211723 3.8909640312 2752 1311867810.4462749958 0.1348402649 0.1245267954 0.2390826792 0.0047001228 0.5164780000 0.0479010000 0.0603700000 0.0000000000 0.4001570000 0.0014950000 145981699 0 402718720 3.9134078026 4.0342116356 3.8904905319 2753 1311867810.4781119823 0.1322069913 0.1245295852 0.2390826792 0.0047005483 1.0203170000 0.0565600000 0.0601640000 0.0313790000 0.4091430000 0.4557770000 145985315 0 402718720 3.9161825180 4.0352082253 3.8900341988 2754 1311867810.5101990700 0.1316848844 0.1245321833 0.2390826792 0.0046997735 0.5158730000 0.0485300000 0.0605510000 0.0000010000 0.3987250000 0.0014990000 145988987 0 402718720 3.9168081284 4.0359306335 3.8896067142 2755 1311867810.5459640026 0.1327839494 0.1245351785 0.2390826792 0.0046992723 0.5464630000 0.0487040000 0.0609870000 0.0313810000 0.3973440000 0.0015050000 145992771 0 402718720 3.9160428047 4.0354247093 3.8894553185 2756 1311867810.5791409016 0.1283681393 0.1245365693 0.2390826792 0.0046987390 0.5132980000 0.0481280000 0.0605260000 0.0000010000 0.3965440000 0.0014980000 145996443 0 402718720 3.9204769135 4.0367312431 3.8888132572 2757 1311867810.6141140461 0.1290080994 0.1245381912 0.2390826792 0.0046981507 0.9784190000 0.0489100000 0.0610150000 0.0309910000 0.3955340000 0.4353940000 146000227 0 402718720 3.9197251797 4.0374703407 3.8885807991 2758 1311867810.6471910477 0.1235613301 0.1245378370 0.2390826792 0.0046999464 0.5232540000 0.0588800000 0.0611420000 0.0000010000 0.3951510000 0.0015110000 146003955 0 402718720 3.9252665043 4.0365276337 3.8879265785 2759 1311867810.6781129837 0.1279002428 0.1245390557 0.2390826792 0.0047005845 0.5315270000 0.0491800000 0.0484370000 0.0314350000 0.3943970000 0.0015130000 146007571 0 402718720 3.9207444191 4.0378785133 3.8880131245 2760 1311867810.7146449089 0.1223810166 0.1245382738 0.2390826792 0.0047016567 0.5134000000 0.0496370000 0.0619230000 0.0000010000 0.3936640000 0.0015120000 146011355 0 402718720 3.9265489578 4.0381126404 3.8873221874 2761 1311867810.7468900681 0.1188705117 0.1245362210 0.2390826792 0.0047016272 0.9744650000 0.0496240000 0.0618100000 0.0313460000 0.3930840000 0.4319690000 146015083 0 402718720 3.9301941395 4.0377278328 3.8869128227 2762 1311867810.7789669037 0.1182317510 0.1245339384 0.2390826792 0.0047021497 0.5121460000 0.0492340000 0.0620150000 0.0000010000 0.3928240000 0.0015120000 146018755 0 402718720 3.9309010506 4.0381479263 3.8865652084 2763 1311867810.8146491051 0.1201754957 0.1245323610 0.2390826792 0.0047015055 0.5697890000 0.0860490000 0.0557520000 0.0315270000 0.3882620000 0.0015230000 146022483 0 402718720 3.9292154312 4.0379033089 3.8862886429 2764 1311867810.8460769653 0.1191615537 0.1245304179 0.2390826792 0.0047050745 0.5134280000 0.0496060000 0.0620590000 0.0000010000 0.3936770000 0.0014940000 146026155 0 402718720 3.9301140308 4.0388364792 3.8859341145 2765 1311867810.8793289661 0.1210944653 0.1245291752 0.2390826792 0.0047048628 0.9783950000 0.0493720000 0.0622880000 0.0313480000 0.3950410000 0.4337480000 146029883 0 402718720 3.9282879829 4.0405006409 3.8861939907 2766 1311867810.9141631126 0.1139793694 0.1245253611 0.2390826792 0.0047085774 0.5121340000 0.0491470000 0.0621840000 0.0000010000 0.3926850000 0.0015190000 146033667 0 402718720 3.9359979630 4.0406136513 3.8861796856 2767 1311867810.9458940029 0.1137949154 0.1245214831 0.2390826792 0.0047112790 0.5441920000 0.0501020000 0.0628740000 0.0313670000 0.3916980000 0.0015190000 146037283 0 402718720 3.9366204739 4.0403509140 3.8853914738 2768 1311867810.9796259403 0.1149866953 0.1245180384 0.2390826792 0.0047107587 0.5344860000 0.0620090000 0.0649210000 0.0000010000 0.3983440000 0.0019440000 146040955 0 402718720 3.9357330799 4.0407643318 3.8853168488 2769 1311867811.0151500702 0.1134300232 0.1245140341 0.2390826792 0.0047155506 0.9668320000 0.0531500000 0.0527210000 0.0314450000 0.3919140000 0.4309740000 146044739 0 402718720 3.9374797344 4.0410122871 3.8848092556 2770 1311867811.0469939709 0.1116880998 0.1245094038 0.2390826792 0.0047155215 0.5129470000 0.0500340000 0.0630110000 0.0000010000 0.3917680000 0.0015240000 146048411 0 402718720 3.9394729137 4.0429153442 3.8843548298 2771 1311867811.0785760880 0.1121507883 0.1245049438 0.2390826792 0.0047154887 0.5495380000 0.0500070000 0.0630550000 0.0314470000 0.3969260000 0.0015240000 146052083 0 402718720 3.9394063950 4.0429854393 3.8840394020 2772 1311867811.1144239902 0.1073704883 0.1244987626 0.2390826792 0.0047166497 0.5202990000 0.0714520000 0.0502720000 0.0000010000 0.3903970000 0.0015240000 146055867 0 402718720 3.9444947243 4.0442533493 3.8837072849 2773 1311867811.1461989880 0.1065466180 0.1244922886 0.2390826792 0.0047161614 0.9925090000 0.0712760000 0.0638610000 0.0309770000 0.3903400000 0.4294130000 146059539 0 402718720 3.9455940723 4.0447163582 3.8831729889 2774 1311867811.1786370277 0.1048921496 0.1244852230 0.2390826792 0.0047154758 0.5147980000 0.0505530000 0.0672840000 0.0000010000 0.3888470000 0.0015260000 146063267 0 402718720 3.9476180077 4.0459537506 3.8829264641 2775 1311867811.2142488956 0.1065533981 0.1244787611 0.2390826792 0.0047157668 0.5458020000 0.0503980000 0.0663220000 0.0314280000 0.3894790000 0.0015280000 146066939 0 402718720 3.9463856220 4.0448446274 3.8827898502 2776 1311867811.2464840412 0.1092069373 0.1244732597 0.2390826792 0.0047163315 0.5151170000 0.0500570000 0.0671570000 0.0000010000 0.3897930000 0.0015190000 146070667 0 402718720 3.9436039925 4.0468983650 3.8827867508 2777 1311867811.2798390388 0.1026858389 0.1244654140 0.2390826792 0.0047180090 0.9585330000 0.0501650000 0.0423000000 0.0314500000 0.3893560000 0.4379310000 146074395 0 402718720 3.9505605698 4.0473461151 3.8821258545 2778 1311867811.3147039413 0.1074781045 0.1244592991 0.2390826792 0.0047206162 0.5217150000 0.0607680000 0.0636530000 0.0000010000 0.3891550000 0.0015240000 146078123 0 402718720 3.9457750320 4.0480771065 3.8818752766 2779 1311867811.3470849991 0.1070232913 0.1244530249 0.2390826792 0.0047213413 0.5321760000 0.0505510000 0.0529540000 0.0314930000 0.3889620000 0.0015610000 146081795 0 402718720 3.9464201927 4.0473613739 3.8815493584 2780 1311867811.3799240589 0.1085785925 0.1244473147 0.2390826792 0.0047214437 0.5112510000 0.0506220000 0.0634560000 0.0000010000 0.3890010000 0.0015270000 146085467 0 402718720 3.9450805187 4.0495018959 3.8817505836 2781 1311867811.4141869545 0.1073847339 0.1244411792 0.2390826792 0.0047215485 0.9975840000 0.0804350000 0.0636560000 0.0315750000 0.3881240000 0.4270960000 146089195 0 402718720 3.9468412399 4.0493888855 3.8815665245 2782 1311867811.4464430809 0.1096991375 0.1244358802 0.2390826792 0.0047213041 0.5103120000 0.0505340000 0.0636820000 0.0000000000 0.3879380000 0.0015230000 146092923 0 402718720 3.9445612431 4.0504608154 3.8807778358 2783 1311867811.4788289070 0.1077404991 0.1244298811 0.2390826792 0.0047215546 0.5663760000 0.0736820000 0.0656500000 0.0314760000 0.3874480000 0.0015260000 146096651 0 402718720 3.9466626644 4.0522756577 3.8802752495 2784 1311867811.5141620636 0.1103919148 0.1244248387 0.2390826792 0.0047236154 0.5570410000 0.0647930000 0.0842810000 0.0000010000 0.3997760000 0.0015330000 146100323 0 402718720 3.9444365501 4.0535020828 3.8809237480 2785 1311867811.5465340614 0.1072151363 0.1244186593 0.2390826792 0.0047235527 0.9638830000 0.0516950000 0.0650310000 0.0314750000 0.3852260000 0.4238200000 146104051 0 402718720 3.9482545853 4.0538072586 3.8803789616 2786 1311867811.5787150860 0.1107820123 0.1244137646 0.2390826792 0.0047263276 0.5105170000 0.0516780000 0.0656350000 0.0000010000 0.3850360000 0.0015350000 146107723 0 402718720 3.9447584152 4.0559678078 3.8799273968 2787 1311867811.6143789291 0.1089976653 0.1244082332 0.2390826792 0.0047266884 0.5405960000 0.0517750000 0.0658000000 0.0310210000 0.3838240000 0.0015410000 146111451 0 402718720 3.9466063976 4.0577883720 3.8798692226 2788 1311867811.6465210915 0.1111455634 0.1244034761 0.2390826792 0.0047359341 0.4923040000 0.0622750000 0.0390880000 0.0000010000 0.3827140000 0.0015410000 146115179 0 402718720 3.9448077679 4.0556421280 3.8800203800 2789 1311867811.6790111065 0.1067014784 0.1243971290 0.2390826792 0.0047379864 0.9618790000 0.0526510000 0.0691340000 0.0315910000 0.3785020000 0.4226740000 146118795 0 402718720 3.9500417709 4.0551438332 3.8794605732 2790 1311867811.7141160965 0.1095201895 0.1243917968 0.2390826792 0.0047391558 0.5558300000 0.0652420000 0.0839920000 0.0000010000 0.3972910000 0.0019670000 146122579 0 402718720 3.9475104809 4.0569143295 3.8794121742 2791 1311867811.7471590042 0.1078498662 0.1243858699 0.2390826792 0.0047396835 0.5395340000 0.0653970000 0.0517840000 0.0315020000 0.3826220000 0.0015370000 146126307 0 402718720 3.9492745399 4.0578627586 3.8788971901 2792 1311867811.7787630558 0.1097217798 0.1243806177 0.2390826792 0.0047399641 0.4850580000 0.0518620000 0.0465520000 0.0000010000 0.3783340000 0.0016350000 146129979 0 402718720 3.9473657608 4.0568313599 3.8782498837 2793 1311867811.8140239716 0.1090457961 0.1243751273 0.2390826792 0.0047393507 0.9688090000 0.0621640000 0.0643120000 0.0315240000 0.3828590000 0.4212290000 146133763 0 402718720 3.9481725693 4.0574622154 3.8782718182 2794 1311867811.8467700481 0.1089167967 0.1243695946 0.2390826792 0.0047389538 0.5086500000 0.0513970000 0.0659430000 0.0000010000 0.3830900000 0.0015360000 146137435 0 402718720 3.9484627247 4.0571722984 3.8778352737 2795 1311867811.8873019218 0.1087476835 0.1243640054 0.2390826792 0.0047384754 0.5369610000 0.0503740000 0.0671250000 0.0313730000 0.3799120000 0.0015340000 146141331 0 402718720 3.9488103390 4.0575323105 3.8776412010 2796 1311867811.9162950516 0.1070809960 0.1243578240 0.2390826792 0.0047376987 0.5076780000 0.0513070000 0.0640990000 0.0000010000 0.3840650000 0.0015270000 146144835 0 402718720 3.9504308701 4.0574445724 3.8770973682 2797 1311867811.9480459690 0.1095546260 0.1243525315 0.2390826792 0.0047376361 0.9554910000 0.0507530000 0.0585990000 0.0314780000 0.3842050000 0.4237750000 146148451 0 402718720 3.9480071068 4.0570645332 3.8768665791 2798 1311867811.9825990200 0.1083040833 0.1243467958 0.2390826792 0.0047372502 0.5306180000 0.0742500000 0.0672920000 0.0000010000 0.3808680000 0.0015320000 146152235 0 402718720 3.9493892193 4.0572304726 3.8762755394 2799 1311867812.0155920982 0.1077162549 0.1243408542 0.2390826792 0.0047367083 0.5589880000 0.0668040000 0.0670420000 0.0314880000 0.3854620000 0.0015230000 146155907 0 402718720 3.9503948689 4.0566062927 3.8761460781 2800 1311867812.0471529961 0.1103167161 0.1243358456 0.2390826792 0.0047367929 0.4856080000 0.0505980000 0.0451600000 0.0000010000 0.3811910000 0.0016200000 146159579 0 402718720 3.9476935863 4.0579528809 3.8761420250 2801 1311867812.0860528946 0.1116539910 0.1243313180 0.2390826792 0.0047360690 0.9800480000 0.0634290000 0.0663030000 0.0315260000 0.3857970000 0.4263270000 146163475 0 402718720 3.9465856552 4.0582189560 3.8763239384 2802 1311867812.1176469326 0.1107767075 0.1243264805 0.2390826792 0.0047353734 0.5213310000 0.0634690000 0.0633120000 0.0000000000 0.3863260000 0.0015220000 146167147 0 402718720 3.9477021694 4.0578713417 3.8762075901 2803 1311867812.1501319408 0.1095629558 0.1243212135 0.2390826792 0.0047346159 0.5466670000 0.0697760000 0.0557880000 0.0311320000 0.3814420000 0.0016140000 146170763 0 402718720 3.9491019249 4.0581145287 3.8757171631 2804 1311867812.1841530800 0.1095380113 0.1243159413 0.2390826792 0.0047337977 0.5030800000 0.0506220000 0.0581720000 0.0000010000 0.3860560000 0.0015220000 146174547 0 402718720 3.9494402409 4.0581874847 3.8758490086 2805 1311867812.2161788940 0.1097594947 0.1243107518 0.2390826792 0.0047396523 0.9658740000 0.0494530000 0.0668150000 0.0313790000 0.3846280000 0.4267930000 146178219 0 402718720 3.9499561787 4.0580039024 3.8762326241 2806 1311867812.2469139099 0.1105997264 0.1243058655 0.2390826792 0.0047393837 0.5078370000 0.0503070000 0.0632700000 0.0000010000 0.3861220000 0.0015140000 146181835 0 402718720 3.9490768909 4.0590190887 3.8759095669 2807 1311867812.2830879688 0.1081981361 0.1243001271 0.2390826792 0.0047497769 0.5392170000 0.0505260000 0.0631510000 0.0315090000 0.3858180000 0.0015220000 146185675 0 402718720 3.9515681267 4.0597610474 3.8761854172 2808 1311867812.3143959045 0.1097010896 0.1242949280 0.2390826792 0.0047585586 0.4967730000 0.0521050000 0.0508570000 0.0000010000 0.3847860000 0.0015220000 146189235 0 402718720 3.9506626129 4.0601143837 3.8762652874 2809 1311867812.3466560841 0.1098553017 0.1242897875 0.2390826792 0.0047577784 1.0112040000 0.0707470000 0.0819410000 0.0386110000 0.3857330000 0.4275220000 146192963 0 402718720 3.9510219097 4.0602302551 3.8766589165 2810 1311867812.3833289146 0.1088357195 0.1242842878 0.2390826792 0.0047574051 0.4918330000 0.0500050000 0.0475840000 0.0000010000 0.3860630000 0.0015180000 146196803 0 402718720 3.9525165558 4.0596585274 3.8767547607 2811 1311867812.4177269936 0.1097809151 0.1242791283 0.2390826792 0.0047568241 0.5284700000 0.0499390000 0.0529560000 0.0314590000 0.3858960000 0.0015120000 146200531 0 402718720 3.9520895481 4.0604066849 3.8767211437 2812 1311867812.4586019516 0.1104052663 0.1242741945 0.2390826792 0.0047560506 0.5002160000 0.0506120000 0.0560900000 0.0000010000 0.3852940000 0.0015180000 146204427 0 402718720 3.9520337582 4.0608730316 3.8770329952 2813 1311867812.4830911160 0.1124155447 0.1242699789 0.2390826792 0.0047558052 0.9782830000 0.0604110000 0.0667900000 0.0315430000 0.3832880000 0.4295460000 146207763 0 402718720 3.9500334263 4.0606627464 3.8768925667 2814 1311867812.5157220364 0.1105751842 0.1242651122 0.2390826792 0.0047591700 0.4943140000 0.0497830000 0.0503500000 0.0000000000 0.3858670000 0.0015100000 146211379 0 402718720 3.9518170357 4.0612611771 3.8767418861 2815 1311867812.5469310284 0.1098560244 0.1242599935 0.2390826792 0.0047585708 0.5394670000 0.0498500000 0.0625720000 0.0314470000 0.3874080000 0.0015090000 146215051 0 402718720 3.9528594017 4.0617146492 3.8764078617 2816 1311867812.5857439041 0.1081103981 0.1242542586 0.2390826792 0.0047578066 0.4877860000 0.0494050000 0.0420320000 0.0000010000 0.3881720000 0.0015000000 146218891 0 402718720 3.9549930096 4.0619454384 3.8761274815 2817 1311867812.6147639751 0.1091775969 0.1242489065 0.2390826792 0.0047571239 0.9911010000 0.0663480000 0.0659760000 0.0315180000 0.3871830000 0.4333620000 146222451 0 402718720 3.9541375637 4.0618996620 3.8762538433 2818 1311867812.6462490559 0.1083008498 0.1242432472 0.2390826792 0.0047567067 0.5307430000 0.0694040000 0.0657010000 0.0000010000 0.3874510000 0.0014960000 146226179 0 402718720 3.9551274776 4.0620341301 3.8757693768 2819 1311867812.6821310520 0.1081206575 0.1242375279 0.2390826792 0.0047560793 0.5254850000 0.0487110000 0.0491590000 0.0314780000 0.3879860000 0.0014690000 146229963 0 402718720 3.9553613663 4.0620560646 3.8755245209 2820 1311867812.7141439915 0.1056172326 0.1242309250 0.2390826792 0.0047559290 0.4889430000 0.0488820000 0.0414190000 0.0000000000 0.3904200000 0.0014950000 146233579 0 402718720 3.9576921463 4.0627584457 3.8750677109 2821 1311867812.7468860149 0.1073260233 0.1242249325 0.2390826792 0.0047556587 0.9961960000 0.0486900000 0.0618130000 0.0314550000 0.3985510000 0.4489440000 146237307 0 402718720 3.9557886124 4.0631175041 3.8751022816 2822 1311867812.7839629650 0.1091291904 0.1242195832 0.2390826792 0.0047550666 0.5228790000 0.0615640000 0.0615100000 0.0000010000 0.3916010000 0.0014900000 146241147 0 402718720 3.9538176060 4.0633835793 3.8751146793 2823 1311867812.8143351078 0.1076031700 0.1242136971 0.2390826792 0.0047568366 0.5526390000 0.0600660000 0.0611310000 0.0314620000 0.3918470000 0.0014900000 146244707 0 402718720 3.9552860260 4.0631017685 3.8750016689 2824 1311867812.8463029861 0.1080958173 0.1242079896 0.2390826792 0.0047565211 0.4967210000 0.0485120000 0.0489350000 0.0000010000 0.3910820000 0.0014900000 146248435 0 402718720 3.9544439316 4.0640759468 3.8748345375 2825 1311867812.8841478825 0.1082669646 0.1242023468 0.2390826792 0.0047605578 0.9802760000 0.0482320000 0.0607070000 0.0314710000 0.3926700000 0.4404630000 146252275 0 402718720 3.9537212849 4.0656104088 3.8749799728 2826 1311867812.9142088890 0.1065779030 0.1241961102 0.2390826792 0.0047599348 0.5088670000 0.0620480000 0.0461780000 0.0000000000 0.3924160000 0.0014890000 146255835 0 402718720 3.9551277161 4.0655226707 3.8750174046 2827 1311867812.9470400810 0.1099401265 0.1241910674 0.2390826792 0.0047605594 0.5235580000 0.0480070000 0.0439310000 0.0315100000 0.3917880000 0.0014900000 146259563 0 402718720 3.9512927532 4.0652103424 3.8751454353 2828 1311867812.9833469391 0.1077463925 0.1241852525 0.2390826792 0.0047607199 0.5196360000 0.0585160000 0.0601650000 0.0000000000 0.3927530000 0.0014800000 146263291 0 402718720 3.9531044960 4.0664734840 3.8751852512 2829 1311867813.0143780708 0.1103300527 0.1241803549 0.2390826792 0.0047684810 0.9819820000 0.0470700000 0.0636910000 0.0314390000 0.3924250000 0.4405880000 146266963 0 402718720 3.9504272938 4.0666751862 3.8757944107 2830 1311867813.0462698936 0.1090551242 0.1241750103 0.2390826792 0.0047757722 0.5252880000 0.0607680000 0.0638960000 0.0000010000 0.3923870000 0.0014830000 146270635 0 402718720 3.9509842396 4.0674767494 3.8757665157 2831 1311867813.0825068951 0.1078576073 0.1241692465 0.2390826792 0.0047806236 0.5286980000 0.0609160000 0.0359910000 0.0314520000 0.3921310000 0.0014810000 146274475 0 402718720 3.9517147541 4.0685133934 3.8754751682 2832 1311867813.1142160892 0.1080890968 0.1241635685 0.2390826792 0.0047843143 0.5103700000 0.0483710000 0.0619650000 0.0000010000 0.3918750000 0.0014820000 146278147 0 402718720 3.9508597851 4.0686726570 3.8757402897 2833 1311867813.1504809856 0.1099505052 0.1241585515 0.2390826792 0.0047844640 1.0079760000 0.0603840000 0.0653790000 0.0315210000 0.3901520000 0.4530610000 146281875 0 402718720 3.9488151073 4.0680603981 3.8757858276 2834 1311867813.1829130650 0.1065848023 0.1241523505 0.2390826792 0.0047849809 0.5153290000 0.0601450000 0.0465920000 0.0000010000 0.4003970000 0.0014830000 146285603 0 402718720 3.9516148567 4.0693178177 3.8752722740 2835 1311867813.2166841030 0.1080862284 0.1241466834 0.2390826792 0.0047854441 0.5611900000 0.0688310000 0.0611370000 0.0314400000 0.3915700000 0.0014870000 146289275 0 402718720 3.9496190548 4.0701818466 3.8754417896 2836 1311867813.2536849976 0.1073791161 0.1241407710 0.2390826792 0.0047859859 0.5143970000 0.0486560000 0.0659640000 0.0000000000 0.3915750000 0.0014940000 146293059 0 402718720 3.9498217106 4.0693073273 3.8752639294 2837 1311867813.2831010818 0.1080582514 0.1241351022 0.2390826792 0.0047928244 0.9777590000 0.0612120000 0.0536450000 0.0310930000 0.3868140000 0.4382310000 146296675 0 402718720 3.9491081238 4.0706033707 3.8753590584 2838 1311867813.3142321110 0.1107254848 0.1241303771 0.2390826792 0.0047951666 0.5330630000 0.0725610000 0.0653690000 0.0000010000 0.3865690000 0.0015800000 146300347 0 402718720 3.9459815025 4.0720534325 3.8757615089 2839 1311867813.3517169952 0.1090215966 0.1241250553 0.2390826792 0.0048137688 0.5289890000 0.0490310000 0.0493670000 0.0314780000 0.3909570000 0.0014830000 146304131 0 402718720 3.9468953609 4.0712976456 3.8756401539 2840 1311867813.3851261139 0.1084209979 0.1241195257 0.2390826792 0.0048131235 0.5085710000 0.0482410000 0.0606200000 0.0000010000 0.3914900000 0.0014790000 146307859 0 402718720 3.9474112988 4.0713629723 3.8756916523 2841 1311867813.4148280621 0.1091900617 0.1241142707 0.2390826792 0.0048310844 0.9554640000 0.0485240000 0.0361210000 0.0314280000 0.3913950000 0.4412090000 146311419 0 402718720 3.9469485283 4.0725421906 3.8762130737 2842 1311867813.4501829147 0.1084002256 0.1241087415 0.2390826792 0.0048428552 0.4862630000 0.0481020000 0.0377980000 0.0000010000 0.3921550000 0.0014780000 146315147 0 402718720 3.9472749233 4.0727438927 3.8759069443 2843 1311867813.4843769073 0.1092879027 0.1241035284 0.2390826792 0.0048428414 0.5502710000 0.0581490000 0.0609990000 0.0313720000 0.3915380000 0.0014810000 146318931 0 402718720 3.9465317726 4.0740146637 3.8762342930 2844 1311867813.5152790546 0.1117427647 0.1240991821 0.2390826792 0.0048490143 0.5174170000 0.0564560000 0.0607810000 0.0000000000 0.3919250000 0.0014770000 146322547 0 402718720 3.9438064098 4.0744247437 3.8767023087 2845 1311867813.5519089699 0.1122958213 0.1240950333 0.2390826792 0.0048524749 0.9808710000 0.0480780000 0.0606580000 0.0314090000 0.3915360000 0.4424100000 146326331 0 402718720 3.9430899620 4.0764265060 3.8769743443 2846 1311867813.5863409042 0.1124864817 0.1240909544 0.2390826792 0.0048518073 0.5209610000 0.0608860000 0.0610500000 0.0000000000 0.3908060000 0.0014780000 146330059 0 402718720 3.9425880909 4.0777192116 3.8769798279 2847 1311867813.6168019772 0.1148255393 0.1240876999 0.2390826792 0.0048630285 0.5391980000 0.0480630000 0.0612790000 0.0313430000 0.3902590000 0.0014730000 146333675 0 402718720 3.9396426678 4.0789885521 3.8774192333 2848 1311867813.6515810490 0.1159372926 0.1240848381 0.2390826792 0.0048628269 0.5169500000 0.0571690000 0.0651370000 0.0000010000 0.3863880000 0.0014810000 146337403 0 402718720 3.9387180805 4.0788788795 3.8774633408 2849 1311867813.6860060692 0.1147271767 0.1240815536 0.2390826792 0.0048623534 0.9644000000 0.0487460000 0.0462510000 0.0313500000 0.3902060000 0.4410330000 146341131 0 402718720 3.9401283264 4.0794115067 3.8769822121 2850 1311867813.7184169292 0.1137424111 0.1240779258 0.2390826792 0.0048615828 0.4932410000 0.0485730000 0.0458780000 0.0000010000 0.3905480000 0.0014770000 146344803 0 402718720 3.9411263466 4.0803418159 3.8766307831 2851 1311867813.7506020069 0.1161344722 0.1240751396 0.2390826792 0.0048616234 0.5402370000 0.0484330000 0.0609240000 0.0313830000 0.3912480000 0.0014720000 146348475 0 402718720 3.9385046959 4.0813689232 3.8764853477 2852 1311867813.7827889919 0.1177346334 0.1240729164 0.2390826792 0.0048611877 0.5193840000 0.0660090000 0.0541770000 0.0000010000 0.3909680000 0.0014780000 146352203 0 402718720 3.9369056225 4.0829281807 3.8760414124 2853 1311867813.8147668839 0.1180190444 0.1240707945 0.2390826792 0.0048603477 0.9936520000 0.0589790000 0.0609620000 0.0313420000 0.3917210000 0.4438470000 146355763 0 402718720 3.9369375706 4.0833096504 3.8761825562 2854 1311867813.8517930508 0.1182836518 0.1240687668 0.2390826792 0.0048596816 0.4825460000 0.0483460000 0.0320790000 0.0000010000 0.3927650000 0.0018840000 146359659 0 402718720 3.9368531704 4.0844125748 3.8758676052 2855 1311867813.8838069439 0.1183034107 0.1240667474 0.2390826792 0.0048596221 0.5617980000 0.0599390000 0.0655420000 0.0353090000 0.3927110000 0.0014680000 146363275 0 402718720 3.9373688698 4.0852365494 3.8753762245 2856 1311867813.9144020081 0.1212650910 0.1240657664 0.2390826792 0.0048592434 0.4958120000 0.0482550000 0.0459140000 0.0000010000 0.3933670000 0.0014730000 146366891 0 402718720 3.9343447685 4.0860414505 3.8753490448 2857 1311867813.9523379803 0.1236673966 0.1240656270 0.2390826792 0.0048596604 0.9905900000 0.0490110000 0.0614610000 0.0314550000 0.3939650000 0.4479220000 146370787 0 402718720 3.9322564602 4.0867743492 3.8756554127 2858 1311867813.9825320244 0.1241981760 0.1240656734 0.2390826792 0.0048589972 0.4886220000 0.0481660000 0.0373540000 0.0000010000 0.3948670000 0.0014710000 146374403 0 402718720 3.9322352409 4.0895380974 3.8755836487 2859 1311867814.0155770779 0.1219164282 0.1240649216 0.2390826792 0.0048638877 0.5185590000 0.0483820000 0.0357780000 0.0313870000 0.3947150000 0.0014710000 146378075 0 402718720 3.9356746674 4.0893974304 3.8753423691 2860 1311867814.0528070927 0.1209373698 0.1240638281 0.2390826792 0.0048632518 0.4932910000 0.0476980000 0.0407200000 0.0000000000 0.3966280000 0.0014380000 146381971 0 402718720 3.9366686344 4.0905537605 3.8753871918 2861 1311867814.0849530697 0.1214892119 0.1240629282 0.2390826792 0.0048630148 0.9886820000 0.0661850000 0.0354280000 0.0313720000 0.3964340000 0.4521260000 146385587 0 402718720 3.9362359047 4.0917720795 3.8747527599 2862 1311867814.1153879166 0.1253314316 0.1240633714 0.2390826792 0.0048632362 0.5148090000 0.0470000000 0.0639670000 0.0000000000 0.3955860000 0.0014620000 146389203 0 402718720 3.9327867031 4.0922455788 3.8750729561 2863 1311867814.1526429653 0.1254426986 0.1240638532 0.2390826792 0.0048626991 0.5572370000 0.0596350000 0.0599260000 0.0314540000 0.3979300000 0.0014590000 146393099 0 402718720 3.9334573746 4.0921444893 3.8749911785 2864 1311867814.1845281124 0.1237302199 0.1240637367 0.2390826792 0.0048623965 0.4999750000 0.0470200000 0.0448380000 0.0000010000 0.3992640000 0.0014560000 146396771 0 402718720 3.9357147217 4.0926613808 3.8746109009 2865 1311867814.2153480053 0.1278328300 0.1240650522 0.2390826792 0.0048628451 0.9838300000 0.0462250000 0.0401680000 0.0313490000 0.4001730000 0.4590330000 146400331 0 402718720 3.9316349030 4.0937485695 3.8747563362 2866 1311867814.2520170212 0.1319537163 0.1240678047 0.2390826792 0.0048624479 0.5000620000 0.0460910000 0.0446940000 0.0000010000 0.4010270000 0.0014490000 146404171 0 402718720 3.9277422428 4.0931520462 3.8748788834 2867 1311867814.2834239006 0.1367065012 0.1240722131 0.2390826792 0.0048629666 0.5324850000 0.0461930000 0.0447830000 0.0314940000 0.4016980000 0.0014450000 146407899 0 402718720 3.9234254360 4.0935492516 3.8753633499 2868 1311867814.3181779385 0.1376816034 0.1240769583 0.2390826792 0.0048622573 0.5092800000 0.0584370000 0.0395580000 0.0000000000 0.4030270000 0.0014420000 146411627 0 402718720 3.9226894379 4.0952553749 3.8750631809 2869 1311867814.3510050774 0.1367070079 0.1240813606 0.2390826792 0.0048639329 0.9865660000 0.0455000000 0.0345130000 0.0315000000 0.4034260000 0.4648020000 146415243 0 402718720 3.9240193367 4.0954985619 3.8745472431 2870 1311867814.3861339092 0.1373656392 0.1240859892 0.2390826792 0.0048631487 0.5418430000 0.0692820000 0.0604060000 0.0000000000 0.4039100000 0.0014380000 146419027 0 402718720 3.9234824181 4.0949678421 3.8741929531 2871 1311867814.4182898998 0.1380886436 0.1240908665 0.2390826792 0.0048631757 0.5470590000 0.0455260000 0.0618780000 0.0310420000 0.3999530000 0.0015350000 146422699 0 402718720 3.9229345322 4.0958194733 3.8738667965 2872 1311867814.4512650967 0.1355815232 0.1240948674 0.2390826792 0.0048632693 0.4885510000 0.0451220000 0.0311330000 0.0000000000 0.4040260000 0.0014380000 146426427 0 402718720 3.9254708290 4.0970201492 3.8731091022 2873 1311867814.4847788811 0.1361808181 0.1240990742 0.2390826792 0.0048625204 1.0119350000 0.0451460000 0.0611300000 0.0309030000 0.4002340000 0.4676920000 146430099 0 402718720 3.9249861240 4.0974416733 3.8730168343 2874 1311867814.5201790333 0.1363956034 0.1241033527 0.2390826792 0.0048685627 0.4956870000 0.0453770000 0.0413570000 0.0000000000 0.4003050000 0.0015340000 146433883 0 402718720 3.9244694710 4.0977554321 3.8728218079 2875 1311867814.5517210960 0.1366311163 0.1241077102 0.2390826792 0.0048678927 0.5484710000 0.0573770000 0.0461450000 0.0314680000 0.4051830000 0.0014080000 146437555 0 402718720 3.9239897728 4.0970339775 3.8729388714 2876 1311867814.5848219395 0.1390581280 0.1241129085 0.2390826792 0.0048675006 0.4971750000 0.0447130000 0.0391950000 0.0000000000 0.4049200000 0.0014390000 146441171 0 402718720 3.9210498333 4.0980820656 3.8729381561 2877 1311867814.6200098991 0.1385798156 0.1241179370 0.2390826792 0.0048671042 1.0131810000 0.0446710000 0.0576500000 0.0313400000 0.4046740000 0.4680200000 146444899 0 402718720 3.9207286835 4.0981683731 3.8726518154 2878 1311867814.6503028870 0.1362210214 0.1241221424 0.2390826792 0.0048666231 0.5288920000 0.0559760000 0.0609950000 0.0000010000 0.4036630000 0.0014310000 146448571 0 402718720 3.9223792553 4.1000137329 3.8726727962 2879 1311867814.6833140850 0.1396189183 0.1241275251 0.2390826792 0.0048664713 0.5477670000 0.0451610000 0.0617880000 0.0314130000 0.4010930000 0.0014310000 146452243 0 402718720 3.9184997082 4.0997991562 3.8733334541 2880 1311867814.7211821079 0.1377276927 0.1241322474 0.2390826792 0.0048662305 0.4907310000 0.0450340000 0.0343640000 0.0000010000 0.4030130000 0.0014350000 146456083 0 402718720 3.9197220802 4.1004810333 3.8735077381 2881 1311867814.7502319813 0.1389344335 0.1241373852 0.2390826792 0.0048655745 1.0067570000 0.0454060000 0.0618140000 0.0309750000 0.3976990000 0.4639670000 146459699 0 402718720 3.9181656837 4.1014380455 3.8741929531 2882 1311867814.7828900814 0.1407550275 0.1241431512 0.2390826792 0.0048661374 0.5096180000 0.0457150000 0.0543550000 0.0000010000 0.4012570000 0.0014460000 146463371 0 402718720 3.9160554409 4.1025481224 3.8746986389 2883 1311867814.8186480999 0.1427517086 0.1241496058 0.2390826792 0.0048659122 0.5554570000 0.0558290000 0.0593590000 0.0313490000 0.4005750000 0.0014450000 146467155 0 402718720 3.9141850471 4.1023578644 3.8756239414 2884 1311867814.8526010513 0.1388926804 0.1241547178 0.2390826792 0.0048658591 0.5124480000 0.0459000000 0.0624480000 0.0000010000 0.3958070000 0.0014410000 146470883 0 402718720 3.9181458950 4.1026535034 3.8757133484 2885 1311867814.8852329254 0.1436691433 0.1241614819 0.2390826792 0.0048668592 1.0036420000 0.0461230000 0.0595720000 0.0313370000 0.3995730000 0.4601510000 146474555 0 402718720 3.9131810665 4.1032361984 3.8764302731 2886 1311867814.9202771187 0.1453426182 0.1241688212 0.2390826792 0.0048662504 0.4932670000 0.0461800000 0.0401660000 0.0000000000 0.3986890000 0.0014430000 146478339 0 402718720 3.9114096165 4.1035676003 3.8771204948 2887 1311867814.9503459930 0.1437031180 0.1241755875 0.2390826792 0.0048656144 0.5433740000 0.0467190000 0.0593740000 0.0313210000 0.3976490000 0.0014540000 146481955 0 402718720 3.9132354259 4.1047229767 3.8772921562 2888 1311867814.9839959145 0.1441502571 0.1241825039 0.2390826792 0.0048668309 0.5167280000 0.0635780000 0.0475990000 0.0000010000 0.3972110000 0.0014570000 146485683 0 402718720 3.9129147530 4.1057810783 3.8776545525 2889 1311867815.0193099976 0.1443606764 0.1241894884 0.2390826792 0.0048691121 0.9800770000 0.0470120000 0.0416070000 0.0312490000 0.3970510000 0.4562240000 146489355 0 402718720 3.9130783081 4.1064343452 3.8779573441 2890 1311867815.0509970188 0.1446015239 0.1241965514 0.2390826792 0.0048683382 0.5261270000 0.0606150000 0.0635660000 0.0000010000 0.3936660000 0.0014340000 146492971 0 402718720 3.9133207798 4.1077818871 3.8784546852 2891 1311867815.0835149288 0.1456477344 0.1242039714 0.2390826792 0.0048691316 0.5428920000 0.0476770000 0.0608790000 0.0313370000 0.3946090000 0.0014600000 146496643 0 402718720 3.9130024910 4.1069293022 3.8788156509 2892 1311867815.1192519665 0.1517259777 0.1242134880 0.2390826792 0.0048701459 0.5113700000 0.0476510000 0.0611610000 0.0000000000 0.3942490000 0.0014660000 146500427 0 402718720 3.9076714516 4.1080589294 3.8794820309 2893 1311867815.1505639553 0.1539199501 0.1242237564 0.2390826792 0.0048708995 1.0033960000 0.0651140000 0.0564270000 0.0313430000 0.3928450000 0.4507900000 146504043 0 402718720 3.9061861038 4.1077337265 3.8796036243 2894 1311867815.1827230453 0.1593464762 0.1242358928 0.2390826792 0.0048730362 0.4972740000 0.0482220000 0.0493030000 0.0000010000 0.3914420000 0.0014620000 146507771 0 402718720 3.9017050266 4.1080236435 3.8800194263 2895 1311867815.2192549706 0.1673503071 0.1242507855 0.2390826792 0.0048777454 0.5232290000 0.0472590000 0.0435620000 0.0313670000 0.3926930000 0.0014610000 146511555 0 402718720 3.8946392536 4.1086401939 3.8807802200 2896 1311867815.2503280640 0.1672896892 0.1242656470 0.2390826792 0.0048771427 0.4919090000 0.0488880000 0.0413410000 0.0000010000 0.3933620000 0.0014630000 146515171 0 402718720 3.8955445290 4.1083970070 3.8809266090 2897 1311867815.2826719284 0.1669537127 0.1242803823 0.2390826792 0.0048764172 1.0040710000 0.0620780000 0.0614840000 0.0314350000 0.3926200000 0.4495800000 146518899 0 402718720 3.8967533112 4.1095743179 3.8812406063 2898 1311867815.3188140392 0.1703319550 0.1242962731 0.2390826792 0.0048760729 0.5117430000 0.0676810000 0.0444440000 0.0000010000 0.3912180000 0.0014810000 146522683 0 402718720 3.8938519955 4.1093144417 3.8817327023 2899 1311867815.3506569862 0.1712385565 0.1243124657 0.2390826792 0.0048753413 0.5470880000 0.0499560000 0.0660280000 0.0315010000 0.3912660000 0.0014790000 146526299 0 402718720 3.8934812546 4.1107082367 3.8819384575 2900 1311867815.3841490746 0.1700651497 0.1243282425 0.2390826792 0.0048749984 0.4983690000 0.0498640000 0.0500390000 0.0000010000 0.3901040000 0.0014780000 146530027 0 402718720 3.8952078819 4.1102504730 3.8817918301 2901 1311867815.4187209606 0.1707502007 0.1243442445 0.2390826792 0.0048754249 0.9978930000 0.0632630000 0.0614640000 0.0314960000 0.3900880000 0.4447640000 146533811 0 402718720 3.8946828842 4.1109957695 3.8822927475 2902 1311867815.4505259991 0.1709701568 0.1243603113 0.2390826792 0.0048747344 0.4908600000 0.0506850000 0.0424960000 0.0000000000 0.3893360000 0.0014830000 146537427 0 402718720 3.8946423531 4.1119737625 3.8826777935 2903 1311867815.4827210903 0.1714233756 0.1243765232 0.2390826792 0.0048744056 0.5603250000 0.0663110000 0.0657010000 0.0314600000 0.3884620000 0.0014900000 146541155 0 402718720 3.8942859173 4.1123018265 3.8831830025 2904 1311867815.5188379288 0.1693490893 0.1243920096 0.2390826792 0.0048736705 0.5183960000 0.0507910000 0.0670930000 0.0000010000 0.3910340000 0.0019110000 146544939 0 402718720 3.8964004517 4.1121187210 3.8831615448 2905 1311867815.5508639812 0.1688084751 0.1244072993 0.2390826792 0.0048730134 0.9668870000 0.0597250000 0.0430100000 0.0314280000 0.3866640000 0.4392090000 146548555 0 402718720 3.8969497681 4.1131258011 3.8833260536 2906 1311867815.5879790783 0.1636091769 0.1244207893 0.2390826792 0.0048746035 0.5111440000 0.0515190000 0.0643630000 0.0000010000 0.3869600000 0.0014650000 146552395 0 402718720 3.9025118351 4.1134128571 3.8834140301 2907 1311867815.6201279163 0.1644075066 0.1244345446 0.2390826792 0.0048751172 0.5295710000 0.0510750000 0.0532190000 0.0313330000 0.3855680000 0.0014910000 146556067 0 402718720 3.9018883705 4.1136927605 3.8841784000 2908 1311867815.6522359848 0.1601098478 0.1244468126 0.2390826792 0.0048745802 0.5225670000 0.0653710000 0.0637720000 0.0000010000 0.3849890000 0.0014890000 146559795 0 402718720 3.9065279961 4.1141109467 3.8837881088 2909 1311867815.6869289875 0.1606489718 0.1244592574 0.2390826792 0.0048752739 0.9745210000 0.0515340000 0.0640930000 0.0314400000 0.3845180000 0.4359980000 146563523 0 402718720 3.9064743519 4.1135120392 3.8843946457 2910 1311867815.7186810970 0.1605753154 0.1244716685 0.2390826792 0.0048781694 0.5230020000 0.0642250000 0.0637420000 0.0000010000 0.3866370000 0.0014960000 146567251 0 402718720 3.9067306519 4.1150655746 3.8846936226 2911 1311867815.7527859211 0.1620568633 0.1244845799 0.2390826792 0.0048910141 0.5395050000 0.0517620000 0.0680380000 0.0313800000 0.3796000000 0.0015820000 146570923 0 402718720 3.9057734013 4.1149377823 3.8851735592 2912 1311867815.7881309986 0.1597078890 0.1244966758 0.2390826792 0.0048904919 0.5020340000 0.0519170000 0.0568270000 0.0000000000 0.3848850000 0.0014990000 146574707 0 402718720 3.9083049297 4.1152615547 3.8848109245 2913 1311867815.8185119629 0.1626978070 0.1245097898 0.2390826792 0.0049028899 0.9835120000 0.0649170000 0.0678780000 0.0315230000 0.3789830000 0.4332920000 146578267 0 402718720 3.9055547714 4.1155505180 3.8855149746 2914 1311867815.8516321182 0.1608545631 0.1245222623 0.2390826792 0.0049021369 0.5090490000 0.0528940000 0.0685280000 0.0000000000 0.3788540000 0.0015970000 146581995 0 402718720 3.9077527523 4.1154041290 3.8857033253 2915 1311867815.8881559372 0.1629831940 0.1245354564 0.2390826792 0.0049018612 0.5410960000 0.0519350000 0.0678180000 0.0313800000 0.3814870000 0.0015030000 146585835 0 402718720 3.9060206413 4.1158676147 3.8862521648 2916 1311867815.9183700085 0.1656801403 0.1245495664 0.2390826792 0.0049015458 0.5079460000 0.0517680000 0.0679790000 0.0000010000 0.3789470000 0.0015910000 146589395 0 402718720 3.9037363529 4.1168618202 3.8869762421 2917 1311867815.9544029236 0.1646670550 0.1245633194 0.2390826792 0.0049011077 0.9720440000 0.0523410000 0.0646510000 0.0314030000 0.3843220000 0.4323760000 146593179 0 402718720 3.9051878452 4.1166977882 3.8870720863 2918 1311867815.9880459309 0.1632720083 0.1245765849 0.2390826792 0.0049042437 0.5248400000 0.0678960000 0.0686990000 0.0000010000 0.3798390000 0.0015070000 146596907 0 402718720 3.9068355560 4.1167440414 3.8872423172 2919 1311867816.0232369900 0.1579371840 0.1245880137 0.2390826792 0.0049056323 0.5276000000 0.0528180000 0.0576080000 0.0309480000 0.3773150000 0.0015000000 146600691 0 402718720 3.9128704071 4.1176400185 3.8868253231 2920 1311867816.0513160229 0.1584086120 0.1245995961 0.2390826792 0.0049049934 0.4864830000 0.0526780000 0.0462320000 0.0000000000 0.3791230000 0.0015010000 146604195 0 402718720 3.9131584167 4.1181159019 3.8875558376 2921 1311867816.0872139931 0.1663438380 0.1246138872 0.2390826792 0.0049093166 0.9705690000 0.0527590000 0.0657600000 0.0311310000 0.3823390000 0.4315550000 146608035 0 402718720 3.9057919979 4.1187958717 3.8884439468 2922 1311867816.1192660332 0.1662088335 0.1246281222 0.2390826792 0.0049084952 0.4920230000 0.0529730000 0.0493230000 0.0000010000 0.3812120000 0.0015110000 146611651 0 402718720 3.9066808224 4.1186847687 3.8887684345 2923 1311867816.1530499458 0.1664228588 0.1246424208 0.2390826792 0.0049080162 0.5597400000 0.0822900000 0.0573580000 0.0314660000 0.3801490000 0.0015120000 146615267 0 402718720 3.9071347713 4.1193742752 3.8892083168 2924 1311867816.1877670288 0.1619569063 0.1246551823 0.2390826792 0.0049102732 0.4794270000 0.0531890000 0.0409030000 0.0000000000 0.3764800000 0.0016090000 146619051 0 402718720 3.9121069908 4.1204137802 3.8891749382 2925 1311867816.2185130119 0.1631680578 0.1246683491 0.2390826792 0.0049099014 0.9575090000 0.0531260000 0.0576510000 0.0313570000 0.3788830000 0.4294230000 146622723 0 402718720 3.9113435745 4.1205124855 3.8893306255 2926 1311867816.2509930134 0.1631336808 0.1246814951 0.2390826792 0.0049121540 0.5076730000 0.0533380000 0.0653170000 0.0000000000 0.3805260000 0.0015150000 146626339 0 402718720 3.9116954803 4.1213731766 3.8896448612 2927 1311867816.2875878811 0.1601434052 0.1246936106 0.2390826792 0.0049124716 0.5163990000 0.0528330000 0.0440490000 0.0312640000 0.3797830000 0.0015120000 146630123 0 402718720 3.9151532650 4.1208915710 3.8892650604 2928 1311867816.3221759796 0.1575143784 0.1247048198 0.2390826792 0.0049117065 0.4988830000 0.0644540000 0.0468870000 0.0000010000 0.3790190000 0.0015160000 146633907 0 402718720 3.9182252884 4.1219720840 3.8890991211 2929 1311867816.3515660763 0.1639102846 0.1247182051 0.2390826792 0.0049134016 0.9680720000 0.0532820000 0.0657930000 0.0313950000 0.3805930000 0.4299830000 146637467 0 402718720 3.9123606682 4.1214246750 3.8896303177 2930 1311867816.3902490139 0.1661899835 0.1247323593 0.2390826792 0.0049131743 0.5078910000 0.0531570000 0.0651800000 0.0000000000 0.3810520000 0.0015060000 146641307 0 402718720 3.9103903770 4.1208410263 3.8892624378 2931 1311867816.4188189507 0.1672347486 0.1247468603 0.2390826792 0.0049125457 0.5188380000 0.0644410000 0.0331650000 0.0314750000 0.3812110000 0.0015130000 146644923 0 402718720 3.9094390869 4.1196565628 3.8888368607 2932 1311867816.4527490139 0.1687043160 0.1247618526 0.2390826792 0.0049121440 0.5307690000 0.0748330000 0.0684110000 0.0000010000 0.3790110000 0.0015020000 146648651 0 402718720 3.9081034660 4.1207985878 3.8888034821 2933 1311867816.4875969887 0.1705902368 0.1247774777 0.2390826792 0.0049139598 0.9683990000 0.0642700000 0.0515590000 0.0314320000 0.3816160000 0.4325340000 146652379 0 402718720 3.9059824944 4.1195144653 3.8883714676 2934 1311867816.5199189186 0.1733462214 0.1247940315 0.2390826792 0.0049138106 0.4990150000 0.0528900000 0.0558030000 0.0000000000 0.3818770000 0.0015060000 146655995 0 402718720 3.9030179977 4.1195611954 3.8880944252 2935 1311867816.5529119968 0.1735903919 0.1248106571 0.2390826792 0.0049155055 0.5437420000 0.0532420000 0.0684610000 0.0315690000 0.3819820000 0.0015060000 146659779 0 402718720 3.9027149677 4.1193528175 3.8882193565 2936 1311867816.5888628960 0.1714022905 0.1248265262 0.2390826792 0.0049153012 0.4826590000 0.0530180000 0.0384820000 0.0000010000 0.3826670000 0.0014770000 146663563 0 402718720 3.9048211575 4.1185374260 3.8875961304 2937 1311867816.6194050312 0.1723512858 0.1248427076 0.2390826792 0.0049145370 0.9738720000 0.0527680000 0.0677850000 0.0313730000 0.3819080000 0.4329640000 146667179 0 402718720 3.9034223557 4.1182808876 3.8875274658 2938 1311867816.6509261131 0.1730301231 0.1248591090 0.2390826792 0.0049140096 0.5050570000 0.0625850000 0.0515230000 0.0000010000 0.3824230000 0.0015080000 146670795 0 402718720 3.9022655487 4.1178174019 3.8873195648 2939 1311867816.6893680096 0.1722309589 0.1248752274 0.2390826792 0.0049134424 0.5390670000 0.0526440000 0.0647710000 0.0314870000 0.3816260000 0.0015040000 146674691 0 402718720 3.9022665024 4.1170277596 3.8868951797 2940 1311867816.7204029560 0.1736557782 0.1248918194 0.2390826792 0.0049144800 0.4812820000 0.0527080000 0.0384440000 0.0000010000 0.3815250000 0.0015060000 146678251 0 402718720 3.8998022079 4.1163735390 3.8867599964 2941 1311867816.7523219585 0.1737830192 0.1249084434 0.2390826792 0.0049136483 0.9682800000 0.0529490000 0.0647750000 0.0313410000 0.3811330000 0.4309690000 146681923 0 402718720 3.8986568451 4.1164035797 3.8865938187 2942 1311867816.7867000103 0.1727813333 0.1249247157 0.2390826792 0.0049130442 0.5072110000 0.0528550000 0.0647280000 0.0000010000 0.3811010000 0.0015050000 146685651 0 402718720 3.8991386890 4.1166496277 3.8861629963 2943 1311867816.8192241192 0.1734732538 0.1249412119 0.2390826792 0.0049126810 0.5305320000 0.0658420000 0.0460510000 0.0313310000 0.3787330000 0.0015060000 146689323 0 402718720 3.8978190422 4.1149578094 3.8860223293 2944 1311867816.8584229946 0.1741099656 0.1249579133 0.2390826792 0.0049125212 0.4861290000 0.0528860000 0.0437660000 0.0000010000 0.3809230000 0.0015050000 146693219 0 402718720 3.8965561390 4.1144366264 3.8855004311 2945 1311867816.8891038895 0.1724982262 0.1249740560 0.2390826792 0.0049119053 0.9408730000 0.0530540000 0.0385780000 0.0314210000 0.3807590000 0.4300500000 146696779 0 402718720 3.8979091644 4.1129455566 3.8848013878 2946 1311867816.9194529057 0.1737713069 0.1249906199 0.2390826792 0.0049203541 0.4811210000 0.0529770000 0.0386520000 0.0000000000 0.3809380000 0.0015130000 146700451 0 402718720 3.8965420723 4.1129860878 3.8847692013 2947 1311867816.9566609859 0.1744005382 0.1250073861 0.2390826792 0.0049214013 0.5194700000 0.0531300000 0.0459110000 0.0311890000 0.3806860000 0.0015140000 146704123 0 402718720 3.8949747086 4.1119194031 3.8844881058 2948 1311867816.9880828857 0.1719186306 0.1250232990 0.2390826792 0.0049356577 0.5087640000 0.0530340000 0.0687890000 0.0000000000 0.3784170000 0.0015150000 146707795 0 402718720 3.8967313766 4.1118850708 3.8837752342 2949 1311867817.0196158886 0.1723797917 0.1250393575 0.2390826792 0.0049353819 0.9662770000 0.0534590000 0.0653740000 0.0314060000 0.3805870000 0.4284200000 146711467 0 402718720 3.8960556984 4.1104154587 3.8835794926 2950 1311867817.0547220707 0.1728336215 0.1250555589 0.2390826792 0.0049351861 0.4801940000 0.0523830000 0.0384030000 0.0000010000 0.3808390000 0.0015140000 146715195 0 402718720 3.8949742317 4.1096854210 3.8832316399 2951 1311867817.0868639946 0.1735193282 0.1250719817 0.2390826792 0.0049344944 0.5633360000 0.0762220000 0.0686680000 0.0314820000 0.3783730000 0.0015150000 146718867 0 402718720 3.8940644264 4.1101899147 3.8832859993 2952 1311867817.1189420223 0.1727213264 0.1250881231 0.2390826792 0.0049341287 0.5132870000 0.0545180000 0.0697870000 0.0000000000 0.3803350000 0.0015190000 146722595 0 402718720 3.8944981098 4.1095604897 3.8826258183 2953 1311867817.1549699306 0.1736349016 0.1251045629 0.2390826792 0.0049333947 0.9799350000 0.0678430000 0.0690260000 0.0315380000 0.3773050000 0.4271430000 146726379 0 402718720 3.8930799961 4.1094799042 3.8826625347 2954 1311867817.1863970757 0.1712392271 0.1251201806 0.2390826792 0.0049342992 0.5159250000 0.0532650000 0.0692530000 0.0000010000 0.3836330000 0.0019560000 146729995 0 402718720 3.8953409195 4.1090021133 3.8820338249 2955 1311867817.2202200890 0.1727834344 0.1251363103 0.2390826792 0.0049339922 0.5354320000 0.0606740000 0.0547800000 0.0313880000 0.3799830000 0.0015140000 146733723 0 402718720 3.8937723637 4.1077065468 3.8821930885 2956 1311867817.2567460537 0.1738624573 0.1251527941 0.2390826792 0.0049346464 0.5089340000 0.0535080000 0.0691020000 0.0000010000 0.3776920000 0.0015180000 146737507 0 402718720 3.8927755356 4.1062698364 3.8817994595 2957 1311867817.2865970135 0.1707651615 0.1251682194 0.2390826792 0.0049350856 0.9778600000 0.0641930000 0.0653700000 0.0314160000 0.3809780000 0.4280870000 146741123 0 402718720 3.8955900669 4.1060342789 3.8811955452 2958 1311867817.3192870617 0.1710209697 0.1251837206 0.2390826792 0.0049344379 0.4902260000 0.0611680000 0.0386250000 0.0000010000 0.3818440000 0.0015150000 146744851 0 402718720 3.8949015141 4.1048903465 3.8804917336 2959 1311867817.3578689098 0.1729812026 0.1251998739 0.2390826792 0.0049355161 0.5295410000 0.0531220000 0.0577030000 0.0315580000 0.3785870000 0.0015100000 146748691 0 402718720 3.8925704956 4.1037178040 3.8804848194 2960 1311867817.3868360519 0.1734624356 0.1252161788 0.2390826792 0.0049358656 0.4953910000 0.0657310000 0.0386290000 0.0000010000 0.3824150000 0.0015200000 146752251 0 402718720 3.8917689323 4.1025185585 3.8803024292 2961 1311867817.4206850529 0.1725007892 0.1252321479 0.2390826792 0.0049352769 0.9420180000 0.0529070000 0.0394650000 0.0314590000 0.3823410000 0.4286670000 146755979 0 402718720 3.8923203945 4.1011672020 3.8796286583 2962 1311867817.4551830292 0.1710479409 0.1252476158 0.2390826792 0.0049347472 0.4861240000 0.0526120000 0.0462170000 0.0000010000 0.3787070000 0.0015130000 146759707 0 402718720 3.8933134079 4.1006412506 3.8796467781 2963 1311867817.4888920784 0.1705116183 0.1252628922 0.2390826792 0.0049351161 0.5513030000 0.0744090000 0.0543430000 0.0315150000 0.3824410000 0.0015180000 146763491 0 402718720 3.8935070038 4.0978202820 3.8790154457 2964 1311867817.5194959641 0.1704411358 0.1252781345 0.2390826792 0.0049349061 0.4827640000 0.0525950000 0.0385260000 0.0000010000 0.3830150000 0.0015130000 146767051 0 402718720 3.8932023048 4.0981583595 3.8786602020 2965 1311867817.5576219559 0.1727266163 0.1252941374 0.2390826792 0.0049345153 0.9514670000 0.0525260000 0.0490140000 0.0314340000 0.3826770000 0.4287190000 146770947 0 402718720 3.8903670311 4.0963287354 3.8785142899 2966 1311867817.5864789486 0.1704291254 0.1253093548 0.2390826792 0.0049344776 0.4928660000 0.0522950000 0.0490180000 0.0000010000 0.3828970000 0.0015210000 146774507 0 402718720 3.8920989037 4.0952749252 3.8778874874 2967 1311867817.6205849648 0.1706922352 0.1253246507 0.2390826792 0.0049336515 0.5401470000 0.0525070000 0.0646370000 0.0314560000 0.3829640000 0.0015180000 146778235 0 402718720 3.8911914825 4.0947785378 3.8776931763 2968 1311867817.6566040516 0.1668373197 0.1253386375 0.2390826792 0.0049335287 0.5149770000 0.0774230000 0.0462870000 0.0000010000 0.3826610000 0.0014960000 146782019 0 402718720 3.8944413662 4.0935320854 3.8774263859 2969 1311867817.6880049706 0.1661822945 0.1253523942 0.2390826792 0.0049332763 0.9393220000 0.0528980000 0.0406030000 0.0315060000 0.3793140000 0.4278600000 146785691 0 402718720 3.8944501877 4.0923686028 3.8767933846 2970 1311867817.7194509506 0.1664406210 0.1253662286 0.2390826792 0.0049325791 0.4888240000 0.0525820000 0.0445620000 0.0000000000 0.3824740000 0.0015200000 146789419 0 402718720 3.8938100338 4.0913357735 3.8765857220 2971 1311867817.7552740574 0.1648589820 0.1253795213 0.2390826792 0.0049333987 0.5352960000 0.0632730000 0.0488880000 0.0314830000 0.3830310000 0.0015160000 146793091 0 402718720 3.8951244354 4.0893602371 3.8758769035 2972 1311867817.7872710228 0.1623751521 0.1253919694 0.2390826792 0.0049343844 0.4833180000 0.0527570000 0.0386130000 0.0000010000 0.3832990000 0.0015250000 146796819 0 402718720 3.8973426819 4.0876145363 3.8752131462 2973 1311867817.8201289177 0.1589119583 0.1254032442 0.2390826792 0.0049375329 0.9925900000 0.0756680000 0.0690350000 0.0311530000 0.3824590000 0.4271660000 146800547 0 402718720 3.9004476070 4.0874285698 3.8747446537 2974 1311867817.8596370220 0.1589146107 0.1254145123 0.2390826792 0.0049393357 0.4896340000 0.0532240000 0.0464780000 0.0000010000 0.3812810000 0.0015250000 146804443 0 402718720 3.9000463486 4.0857658386 3.8745872974 2975 1311867817.8866479397 0.1585391462 0.1254256467 0.2390826792 0.0049392832 0.5188070000 0.0536750000 0.0468310000 0.0316110000 0.3780740000 0.0015310000 146807947 0 402718720 3.9003860950 4.0838513374 3.8747081757 2976 1311867817.9203889370 0.1549601853 0.1254355709 0.2390826792 0.0049409710 0.4874080000 0.0532540000 0.0443970000 0.0000010000 0.3810680000 0.0015310000 146811675 0 402718720 3.9036142826 4.0831608772 3.8743546009 2977 1311867817.9569509029 0.1503159851 0.1254439284 0.2390826792 0.0049412604 0.9605220000 0.0535330000 0.0658870000 0.0315650000 0.3801600000 0.4222320000 146815459 0 402718720 3.9078125954 4.0829410553 3.8737449646 2978 1311867817.9865961075 0.1481619775 0.1254515571 0.2390826792 0.0049421712 0.5237830000 0.0846400000 0.0528520000 0.0000010000 0.3775540000 0.0015410000 146819075 0 402718720 3.9098739624 4.0809240341 3.8732881546 2979 1311867818.0255188942 0.1482426375 0.1254592076 0.2390826792 0.0049424237 0.5119490000 0.0538230000 0.0391800000 0.0311740000 0.3790940000 0.0015460000 146822915 0 402718720 3.9096622467 4.0807776451 3.8732731342 2980 1311867818.0579230785 0.1490731239 0.1254671318 0.2390826792 0.0049425661 0.5077700000 0.0538040000 0.0661320000 0.0000000000 0.3791110000 0.0015450000 146826643 0 402718720 3.9089989662 4.0798826218 3.8733856678 2981 1311867818.0892961025 0.1445288658 0.1254735262 0.2390826792 0.0049435297 0.9296620000 0.0536240000 0.0391790000 0.0315750000 0.3787970000 0.4193410000 146830203 0 402718720 3.9132401943 4.0790767670 3.8723444939 2982 1311867818.1228859425 0.1461801976 0.1254804701 0.2390826792 0.0049460678 0.4993190000 0.0670790000 0.0447570000 0.0000010000 0.3787750000 0.0015500000 146833987 0 402718720 3.9114139080 4.0783796310 3.8722350597 2983 1311867818.1594460011 0.1440426260 0.1254866927 0.2390826792 0.0049455129 0.5392130000 0.0541720000 0.0666170000 0.0315500000 0.3781780000 0.0015530000 146837715 0 402718720 3.9136383533 4.0772590637 3.8718545437 2984 1311867818.1912620068 0.1427004337 0.1254924614 0.2390826792 0.0049576416 0.4807560000 0.0542190000 0.0394010000 0.0000010000 0.3784020000 0.0015440000 146841443 0 402718720 3.9148759842 4.0766425133 3.8714234829 2985 1311867818.2233390808 0.1409258544 0.1254976317 0.2390826792 0.0049641148 0.9277570000 0.0543650000 0.0395960000 0.0311390000 0.3780010000 0.4174910000 146845171 0 402718720 3.9164109230 4.0765929222 3.8707370758 2986 1311867818.2556240559 0.1421322972 0.1255032026 0.2390826792 0.0049653065 0.4847790000 0.0538390000 0.0445940000 0.0000000000 0.3776160000 0.0015510000 146848787 0 402718720 3.9152848721 4.0749039650 3.8704543114 2987 1311867818.2891340256 0.1402386129 0.1255081358 0.2390826792 0.0049654365 0.5226550000 0.0542460000 0.0504430000 0.0315600000 0.3777030000 0.0015540000 146852515 0 402718720 3.9170172215 4.0738282204 3.8698358536 2988 1311867818.3256890774 0.1397712827 0.1255129093 0.2390826792 0.0049648469 0.5048160000 0.0787820000 0.0397050000 0.0000010000 0.3774790000 0.0015560000 146856299 0 402718720 3.9174883366 4.0736389160 3.8695862293 2989 1311867818.3582971096 0.1398743242 0.1255177140 0.2390826792 0.0049640686 0.9524530000 0.0546500000 0.0704690000 0.0317940000 0.3728580000 0.4154050000 146860027 0 402718720 3.9171447754 4.0729980469 3.8689925671 2990 1311867818.3892099857 0.1400868595 0.1255225866 0.2390826792 0.0049639384 0.5064580000 0.0542790000 0.0702950000 0.0000000000 0.3728270000 0.0016450000 146863699 0 402718720 3.9171392918 4.0722832680 3.8688225746 2991 1311867818.4233601093 0.1390413493 0.1255271065 0.2390826792 0.0049647886 0.5232620000 0.0545010000 0.0508370000 0.0316200000 0.3776280000 0.0015310000 146867427 0 402718720 3.9179103374 4.0714945793 3.8683373928 2992 1311867818.4555370808 0.1365306526 0.1255307841 0.2390826792 0.0049646567 0.4852650000 0.0542610000 0.0450450000 0.0000010000 0.3771760000 0.0015610000 146871043 0 402718720 3.9202020168 4.0706205368 3.8677458763 2993 1311867818.4896349907 0.1361730248 0.1255343398 0.2390826792 0.0049645323 0.9646910000 0.0664790000 0.0667950000 0.0315810000 0.3773360000 0.4152690000 146874827 0 402718720 3.9202482700 4.0694637299 3.8673586845 2994 1311867818.5246019363 0.1355946809 0.1255377000 0.2390826792 0.0049652831 0.5100040000 0.0546750000 0.0710000000 0.0000010000 0.3755740000 0.0015660000 146878555 0 402718720 3.9205522537 4.0691580772 3.8673815727 2995 1311867818.5566370487 0.1365118474 0.1255413641 0.2390826792 0.0049653013 0.5162530000 0.0550090000 0.0478290000 0.0317850000 0.3725630000 0.0016640000 146882227 0 402718720 3.9186484814 4.0684533119 3.8669562340 2996 1311867818.5892300606 0.1328875571 0.1255438161 0.2390826792 0.0049688387 0.5206800000 0.0660370000 0.0673510000 0.0000010000 0.3785330000 0.0015690000 146885899 0 402718720 3.9216871262 4.0677185059 3.8664741516 2997 1311867818.6233239174 0.1331560165 0.1255463561 0.2390826792 0.0049685511 0.9664380000 0.0734110000 0.0711830000 0.0317180000 0.3716030000 0.4113120000 146889627 0 402718720 3.9206826687 4.0671768188 3.8667745590 2998 1311867818.6555750370 0.1303917915 0.1255479723 0.2390826792 0.0049713035 0.4782270000 0.0558240000 0.0424710000 0.0000010000 0.3710560000 0.0015820000 146893243 0 402718720 3.9223034382 4.0657444000 3.8665263653 2999 1311867818.6877410412 0.1304598004 0.1255496101 0.2390826792 0.0049706901 0.5380310000 0.0553700000 0.0677000000 0.0316360000 0.3745530000 0.0015720000 146896971 0 402718720 3.9214508533 4.0655670166 3.8664774895 3000 1311867818.7238090038 0.1286173463 0.1255506327 0.2390826792 0.0049701734 0.5066780000 0.0557640000 0.0718750000 0.0000010000 0.3698650000 0.0016750000 146900699 0 402718720 3.9225051403 4.0643329620 3.8664717674 3001 1311867818.7561779022 0.1255805492 0.1255506427 0.2390826792 0.0049697650 0.9568890000 0.0667670000 0.0718110000 0.0312350000 0.3712860000 0.4085730000 146904427 0 402718720 3.9252350330 4.0633878708 3.8662071228 3002 1311867818.7870090008 0.1264666915 0.1255509478 0.2390826792 0.0049699634 0.4782630000 0.0557450000 0.0403420000 0.0000010000 0.3733440000 0.0015800000 146908043 0 402718720 3.9235658646 4.0629663467 3.8662838936 3003 1311867818.8250839710 0.1244519353 0.1255505819 0.2390826792 0.0049699467 0.5361850000 0.0657170000 0.0569990000 0.0316110000 0.3730730000 0.0015790000 146911827 0 402718720 3.9247767925 4.0625820160 3.8662757874 3004 1311867818.8546340466 0.1245847866 0.1255502603 0.2390826792 0.0049696699 0.4886160000 0.0557940000 0.0515270000 0.0000010000 0.3724510000 0.0015830000 146915443 0 402718720 3.9239840508 4.0615911484 3.8662567139 3005 1311867818.8872439861 0.1226199493 0.1255492852 0.2390826792 0.0049800868 0.9331020000 0.0560160000 0.0516450000 0.0316150000 0.3720360000 0.4145190000 146919227 0 402718720 3.9251360893 4.0601835251 3.8659696579 3006 1311867818.9249579906 0.1230977625 0.1255484697 0.2390826792 0.0049802650 0.4887860000 0.0560900000 0.0518340000 0.0000000000 0.3719570000 0.0015940000 146923067 0 402718720 3.9238514900 4.0585241318 3.8660209179 3007 1311867818.9544699192 0.1192503646 0.1255463752 0.2390826792 0.0049853793 0.5595500000 0.0771130000 0.0725690000 0.0316760000 0.3693960000 0.0015900000 146926627 0 402718720 3.9272518158 4.0576572418 3.8654413223 3008 1311867818.9864790440 0.1228965446 0.1255454943 0.2390826792 0.0049859298 0.4892000000 0.0569640000 0.0522110000 0.0000010000 0.3711360000 0.0015950000 146930299 0 402718720 3.9230165482 4.0559210777 3.8660507202 3009 1311867819.0252439976 0.1221108511 0.1255443528 0.2390826792 0.0049865392 0.9405490000 0.0561560000 0.0727350000 0.0316540000 0.3693750000 0.4033300000 146934195 0 402718720 3.9231491089 4.0541915894 3.8657195568 3010 1311867819.0550930500 0.1222102270 0.1255432451 0.2390826792 0.0049990874 0.4876540000 0.0557730000 0.0516600000 0.0000010000 0.3713650000 0.0015830000 146937811 0 402718720 3.9223041534 4.0518107414 3.8656055927 3011 1311867819.0875039101 0.1227059290 0.1255423028 0.2390826792 0.0049996381 0.5115910000 0.0558020000 0.0429250000 0.0317170000 0.3723420000 0.0015860000 146941483 0 402718720 3.9214441776 4.0505962372 3.8658764362 3012 1311867819.1251850128 0.1237537414 0.1255417090 0.2390826792 0.0050091237 0.5069900000 0.0566500000 0.0687370000 0.0000010000 0.3727160000 0.0015930000 146945267 0 402718720 3.9195880890 4.0498766899 3.8657155037 3013 1311867819.1578950882 0.1252476424 0.1255416114 0.2390826792 0.0050089335 0.9306890000 0.0659150000 0.0468270000 0.0315710000 0.3730410000 0.4060630000 146948995 0 402718720 3.9172129631 4.0475449562 3.8656771183 3014 1311867819.1891999245 0.1241682991 0.1255411557 0.2390826792 0.0050104147 0.4849810000 0.0561430000 0.0459380000 0.0000000000 0.3740130000 0.0015870000 146952667 0 402718720 3.9183657169 4.0452475548 3.8658754826 3015 1311867819.2251279354 0.1216354296 0.1255398603 0.2390826792 0.0050132410 0.5386680000 0.0553970000 0.0679070000 0.0315990000 0.3749870000 0.0015850000 146956395 0 402718720 3.9204618931 4.0445251465 3.8657379150 3016 1311867819.2586779594 0.1166368127 0.1255369084 0.2390826792 0.0050163073 0.4794790000 0.0547930000 0.0398750000 0.0000010000 0.3758800000 0.0015770000 146960123 0 402718720 3.9255475998 4.0431890488 3.8649454117 3017 1311867819.2937591076 0.1182656661 0.1255344983 0.2390826792 0.0050154797 0.9559080000 0.0777310000 0.0531770000 0.0316260000 0.3755960000 0.4105420000 146963851 0 402718720 3.9234325886 4.0420832634 3.8648540974 3018 1311867819.3250200748 0.1213969439 0.1255331273 0.2390826792 0.0050147769 0.5105420000 0.0552920000 0.0707860000 0.0000010000 0.3755420000 0.0015790000 146967523 0 402718720 3.9201645851 4.0410070419 3.8652799129 3019 1311867819.3568780422 0.1222922727 0.1255320538 0.2390826792 0.0050142940 0.5196570000 0.0544130000 0.0474200000 0.0312670000 0.3776940000 0.0015670000 146971195 0 402718720 3.9190645218 4.0411710739 3.8652560711 3020 1311867819.3930859566 0.1215610653 0.1255307389 0.2390826792 0.0050186527 0.5076150000 0.0540170000 0.0698420000 0.0000010000 0.3748730000 0.0015610000 146974979 0 402718720 3.9194478989 4.0401911736 3.8649771214 3021 1311867819.4237139225 0.1228606775 0.1255298551 0.2390826792 0.0050184239 0.9398190000 0.0542750000 0.0558030000 0.0315300000 0.3782620000 0.4126640000 146978651 0 402718720 3.9177627563 4.0410776138 3.8654990196 3022 1311867819.4571580887 0.1237710714 0.1255292731 0.2390826792 0.0050177847 0.5188120000 0.0655960000 0.0664710000 0.0000000000 0.3778940000 0.0015720000 146982323 0 402718720 3.9166727066 4.0400347710 3.8656482697 3023 1311867819.4921460152 0.1231845170 0.1255284975 0.2390826792 0.0050181686 0.5516480000 0.0664160000 0.0667170000 0.0315730000 0.3780830000 0.0015750000 146986051 0 402718720 3.9177312851 4.0382266045 3.8659005165 3024 1311867819.5226500034 0.1228376999 0.1255276077 0.2390826792 0.0050182597 0.4864770000 0.0544150000 0.0449190000 0.0000010000 0.3782160000 0.0015780000 146989723 0 402718720 3.9179081917 4.0393099785 3.8661258221 3025 1311867819.5550689697 0.1229795218 0.1255267653 0.2390826792 0.0050176050 0.9499690000 0.0546170000 0.0665230000 0.0316810000 0.3783250000 0.4114570000 146993339 0 402718720 3.9173345566 4.0393495560 3.8657779694 3026 1311867819.5923891068 0.1220645383 0.1255256212 0.2390826792 0.0050185226 0.5121680000 0.0749850000 0.0534370000 0.0000010000 0.3748290000 0.0015810000 146997235 0 402718720 3.9185252190 4.0373558998 3.8659801483 3027 1311867819.6253750324 0.1200311929 0.1255238060 0.2390826792 0.0050191681 0.5188620000 0.0549160000 0.0453500000 0.0316010000 0.3780900000 0.0015790000 147000907 0 402718720 3.9206390381 4.0383710861 3.8664233685 3028 1311867819.6557610035 0.1261062026 0.1255239984 0.2390826792 0.0050191332 0.5412490000 0.0839690000 0.0705960000 0.0000000000 0.3777570000 0.0015490000 147004523 0 402718720 3.9143459797 4.0382084846 3.8670811653 3029 1311867819.6919729710 0.1200380251 0.1255221872 0.2390826792 0.0050212762 0.9472530000 0.0545970000 0.0663620000 0.0315170000 0.3774420000 0.4099600000 147008307 0 402718720 3.9201829433 4.0370178223 3.8656578064 3030 1311867819.7227339745 0.1218915805 0.1255209890 0.2390826792 0.0050206535 0.5082360000 0.0546420000 0.0665340000 0.0000010000 0.3781970000 0.0015760000 147011979 0 402718720 3.9185893536 4.0355434418 3.8660490513 3031 1311867819.7567169666 0.1224261522 0.1255199679 0.2390826792 0.0050215157 0.5187110000 0.0551170000 0.0451290000 0.0315910000 0.3779960000 0.0015860000 147015707 0 402718720 3.9180998802 4.0365128517 3.8665699959 3032 1311867819.7913908958 0.1237638816 0.1255193887 0.2390826792 0.0050212731 0.5082200000 0.0550860000 0.0664770000 0.0000010000 0.3777210000 0.0015760000 147019435 0 402718720 3.9166755676 4.0356578827 3.8664155006 3033 1311867819.8285260201 0.1227666661 0.1255184811 0.2390826792 0.0050208549 0.9285000000 0.0656320000 0.0359770000 0.0315500000 0.3769660000 0.4110060000 147023219 0 402718720 3.9177563190 4.0339384079 3.8661668301 3034 1311867819.8552229404 0.1234954000 0.1255178143 0.2390826792 0.0050238285 0.4878110000 0.0548520000 0.0472370000 0.0000000000 0.3768780000 0.0015700000 147026723 0 402718720 3.9168107510 4.0353665352 3.8663625717 3035 1311867819.8941109180 0.1210068688 0.1255163280 0.2390826792 0.0050239745 0.5287450000 0.0705430000 0.0416800000 0.0315530000 0.3761500000 0.0015740000 147030675 0 402718720 3.9193785191 4.0355343819 3.8663113117 3036 1311867819.9237871170 0.1214501113 0.1255149887 0.2390826792 0.0050241712 0.5066970000 0.0544920000 0.0651920000 0.0000000000 0.3779960000 0.0015690000 147034235 0 402718720 3.9191014767 4.0331597328 3.8660619259 3037 1311867819.9576539993 0.1215635017 0.1255136876 0.2390826792 0.0050233658 0.9467250000 0.0537150000 0.0657100000 0.0313220000 0.3781770000 0.4104830000 147037963 0 402718720 3.9190762043 4.0337724686 3.8667860031 3038 1311867819.9939079285 0.1220178008 0.1255125369 0.2390826792 0.0050227412 0.5033620000 0.0660010000 0.0529570000 0.0000010000 0.3754960000 0.0015730000 147041803 0 402718720 3.9184138775 4.0345048904 3.8665990829 3039 1311867820.0229809284 0.1219597682 0.1255113678 0.2390826792 0.0050225161 0.5384270000 0.0543790000 0.0682060000 0.0315070000 0.3753890000 0.0015710000 147045363 0 402718720 3.9185471535 4.0335845947 3.8665769100 3040 1311867820.0577530861 0.1236150339 0.1255107440 0.2390826792 0.0050218559 0.5071630000 0.0547570000 0.0663300000 0.0000010000 0.3772120000 0.0015720000 147049091 0 402718720 3.9171400070 4.0330991745 3.8672425747 3041 1311867820.0944790840 0.1201234609 0.1255089725 0.2390826792 0.0050217072 0.9264070000 0.0551440000 0.0474290000 0.0315480000 0.3766270000 0.4082970000 147052875 0 402718720 3.9207720757 4.0338287354 3.8673167229 3042 1311867820.1251690388 0.1227767617 0.1255080743 0.2390826792 0.0050215854 0.5039910000 0.0548020000 0.0641950000 0.0000010000 0.3760680000 0.0015750000 147056491 0 402718720 3.9182288647 4.0320863724 3.8675761223 3043 1311867820.1551020145 0.1200477481 0.1255062799 0.2390826792 0.0050210657 0.5503070000 0.0670230000 0.0662620000 0.0314360000 0.3766930000 0.0015710000 147060163 0 402718720 3.9211280346 4.0321822166 3.8679161072 3044 1311867820.1938860416 0.1202132627 0.1255045411 0.2390826792 0.0050204265 0.5316250000 0.0866140000 0.0588000000 0.0000010000 0.3772820000 0.0015720000 147064003 0 402718720 3.9209251404 4.0330095291 3.8680977821 3045 1311867820.2262499332 0.1195202991 0.1255025758 0.2390826792 0.0050202258 0.9273390000 0.0551130000 0.0531310000 0.0315330000 0.3729410000 0.4071580000 147067675 0 402718720 3.9219441414 4.0318007469 3.8683798313 3046 1311867820.2557370663 0.1212921292 0.1255011935 0.2390826792 0.0050197515 0.4824520000 0.0548210000 0.0457780000 0.0000010000 0.3729410000 0.0015630000 147071235 0 402718720 3.9201908112 4.0306820869 3.8687062263 3047 1311867820.2941820621 0.1232316568 0.1255004487 0.2390826792 0.0050195535 0.5516410000 0.0605810000 0.0658360000 0.0385550000 0.3777560000 0.0015750000 147075187 0 402718720 3.9181816578 4.0314683914 3.8693616390 3048 1311867820.3227488995 0.1192075238 0.1254983841 0.2390826792 0.0050205525 0.5016570000 0.0670080000 0.0530990000 0.0000000000 0.3726590000 0.0015730000 147078747 0 402718720 3.9223785400 4.0296497345 3.8686201572 3049 1311867820.3565030098 0.1186579987 0.1254961406 0.2390826792 0.0050197495 0.9437000000 0.0546810000 0.0662860000 0.0314580000 0.3763880000 0.4075230000 147082419 0 402718720 3.9230306149 4.0291175842 3.8687126637 3050 1311867820.3936169147 0.1190312281 0.1254940209 0.2390826792 0.0050189840 0.5075600000 0.0551990000 0.0667670000 0.0000000000 0.3766420000 0.0015850000 147086259 0 402718720 3.9228773117 4.0288333893 3.8694491386 3051 1311867820.4230690002 0.1199857593 0.1254922155 0.2390826792 0.0050185325 0.5055390000 0.0544910000 0.0338400000 0.0314540000 0.3768150000 0.0015660000 147089819 0 402718720 3.9218702316 4.0280447006 3.8693737984 3052 1311867820.4605870247 0.1198830754 0.1254903777 0.2390826792 0.0050177338 0.5020150000 0.0545740000 0.0611840000 0.0000000000 0.3772860000 0.0015660000 147093603 0 402718720 3.9219212532 4.0271210670 3.8697605133 3053 1311867820.4940779209 0.1176685318 0.1254878157 0.2390826792 0.0050175846 0.9591540000 0.0657240000 0.0701670000 0.0315110000 0.3756580000 0.4087390000 147097331 0 402718720 3.9239540100 4.0271439552 3.8694498539 3054 1311867820.5266289711 0.1187242121 0.1254856010 0.2390826792 0.0050168980 0.5067750000 0.0543060000 0.0699660000 0.0000010000 0.3731950000 0.0016560000 147101059 0 402718720 3.9227986336 4.0261244774 3.8700003624 3055 1311867820.5596110821 0.1179501340 0.1254831344 0.2390826792 0.0050166723 0.5403140000 0.0552400000 0.0669870000 0.0314880000 0.3776460000 0.0015800000 147104731 0 402718720 3.9234735966 4.0260968208 3.8703210354 3056 1311867820.5906820297 0.1185665280 0.1254808711 0.2390826792 0.0050158949 0.5169800000 0.0547110000 0.0664220000 0.0000000000 0.3856560000 0.0020310000 147108347 0 402718720 3.9225134850 4.0264582634 3.8705151081 3057 1311867820.6261150837 0.1177538112 0.1254783434 0.2390826792 0.0050155411 0.9461440000 0.0548360000 0.0666250000 0.0314390000 0.3774570000 0.4084210000 147112131 0 402718720 3.9225845337 4.0255784988 3.8706812859 3058 1311867820.6602840424 0.1162634566 0.1254753301 0.2390826792 0.0050148966 0.5115360000 0.0552100000 0.0702280000 0.0000010000 0.3770760000 0.0015750000 147115803 0 402718720 3.9239034653 4.0246353149 3.8708982468 3059 1311867820.6933140755 0.1164574847 0.1254723821 0.2390826792 0.0050142449 0.5130780000 0.0549830000 0.0416120000 0.0314900000 0.3760580000 0.0015750000 147119587 0 402718720 3.9234323502 4.0247592926 3.8714587688 3060 1311867820.7232019901 0.1200113967 0.1254705975 0.2390826792 0.0050138058 0.5080170000 0.0547560000 0.0664650000 0.0000010000 0.3778380000 0.0015740000 147123203 0 402718720 3.9195866585 4.0241665840 3.8719062805 3061 1311867820.7605569363 0.1182015762 0.1254682227 0.2390826792 0.0050144310 0.9470550000 0.0545720000 0.0665600000 0.0314520000 0.3780220000 0.4090970000 147126987 0 402718720 3.9212930202 4.0225276947 3.8719108105 3062 1311867820.7916440964 0.1169927791 0.1254654548 0.2390826792 0.0050142047 0.5135590000 0.0864110000 0.0414060000 0.0000000000 0.3767650000 0.0015660000 147130603 0 402718720 3.9221177101 4.0232157707 3.8719923496 3063 1311867820.8228490353 0.1171318442 0.1254627341 0.2390826792 0.0050136030 0.5534850000 0.0688150000 0.0662700000 0.0314000000 0.3779840000 0.0015710000 147134331 0 402718720 3.9216842651 4.0225014687 3.8721327782 3064 1311867820.8588171005 0.1173366979 0.1254600820 0.2390826792 0.0050135915 0.4845390000 0.0541070000 0.0470080000 0.0000010000 0.3744560000 0.0015600000 147138115 0 402718720 3.9211225510 4.0212755203 3.8721528053 3065 1311867820.8911399841 0.1214075387 0.1254587598 0.2390826792 0.0050131344 0.9474580000 0.0543620000 0.0659980000 0.0309470000 0.3788030000 0.4099220000 147141731 0 402718720 3.9166736603 4.0201001167 3.8727760315 3066 1311867820.9231750965 0.1221691594 0.1254576868 0.2390826792 0.0050129884 0.4810720000 0.0542140000 0.0390230000 0.0000010000 0.3788550000 0.0015620000 147145403 0 402718720 3.9155235291 4.0213894844 3.8732981682 3067 1311867820.9593999386 0.1225265488 0.1254567311 0.2390826792 0.0050121880 0.5396840000 0.0543660000 0.0662850000 0.0314220000 0.3786480000 0.0015620000 147149243 0 402718720 3.9147174358 4.0203175545 3.8735060692 3068 1311867820.9930229187 0.1203487366 0.1254550662 0.2390826792 0.0050116238 0.5079940000 0.0542140000 0.0658420000 0.0000000000 0.3789120000 0.0015580000 147152971 0 402718720 3.9167802334 4.0203037262 3.8738873005 3069 1311867821.0258319378 0.1228048354 0.1254542027 0.2390826792 0.0050134327 0.9497040000 0.0548160000 0.0684480000 0.0314410000 0.3782760000 0.4093290000 147156531 0 402718720 3.9139075279 4.0212860107 3.8744156361 3070 1311867821.0608170033 0.1235317141 0.1254535764 0.2390826792 0.0050134979 0.5073460000 0.0542490000 0.0660450000 0.0000010000 0.3780400000 0.0015660000 147160315 0 402718720 3.9127545357 4.0197696686 3.8743808270 3071 1311867821.0909409523 0.1211567447 0.1254521773 0.2390826792 0.0050132599 0.5592020000 0.0750380000 0.0661630000 0.0309010000 0.3780760000 0.0015650000 147163931 0 402718720 3.9148037434 4.0204238892 3.8747298717 3072 1311867821.1260650158 0.1242644936 0.1254517907 0.2390826792 0.0050147824 0.5084960000 0.0551620000 0.0671220000 0.0000010000 0.3771990000 0.0015730000 147167659 0 402718720 3.9110667706 4.0216498375 3.8754913807 3073 1311867821.1620008945 0.1218780577 0.1254506277 0.2390826792 0.0050171967 0.9490140000 0.0716400000 0.0536230000 0.0314550000 0.3744570000 0.4102860000 147171387 0 402718720 3.9130811691 4.0191607475 3.8750219345 3074 1311867821.1925799847 0.1203763410 0.1254489770 0.2390826792 0.0050176909 0.4799870000 0.0547060000 0.0396240000 0.0000010000 0.3766410000 0.0015690000 147175059 0 402718720 3.9144675732 4.0169653893 3.8751721382 3075 1311867821.2257659435 0.1226507798 0.1254480670 0.2390826792 0.0050170639 0.5378910000 0.0544220000 0.0666130000 0.0313410000 0.3765030000 0.0015650000 147178731 0 402718720 3.9114568233 4.0178704262 3.8755841255 3076 1311867821.2620539665 0.1225096360 0.1254471117 0.2390826792 0.0050164755 0.5068330000 0.0547620000 0.0665750000 0.0000000000 0.3764250000 0.0015630000 147182515 0 402718720 3.9112589359 4.0171818733 3.8758728504 3077 1311867821.2933909893 0.1229867935 0.1254463122 0.2390826792 0.0050158302 0.9426550000 0.0540160000 0.0663370000 0.0312750000 0.3767440000 0.4068190000 147186187 0 402718720 3.9106440544 4.0149288177 3.8760650158 3078 1311867821.3235690594 0.1244916990 0.1254460020 0.2390826792 0.0050157257 0.5211430000 0.0682870000 0.0668870000 0.0000010000 0.3770080000 0.0015730000 147189859 0 402718720 3.9088697433 4.0157208443 3.8772838116 3079 1311867821.3590209484 0.1245157346 0.1254456999 0.2390826792 0.0050152685 0.5094000000 0.0548280000 0.0416050000 0.0313890000 0.3725610000 0.0015680000 147193643 0 402718720 3.9084527493 4.0147223473 3.8774225712 3080 1311867821.3907248974 0.1240105480 0.1254452339 0.2390826792 0.0050155655 0.5092180000 0.0549640000 0.0708190000 0.0000010000 0.3743990000 0.0015660000 147197203 0 402718720 3.9090015888 4.0112719536 3.8771057129 3081 1311867821.4246149063 0.1272069961 0.1254458057 0.2390826792 0.0050159322 0.9557870000 0.0546170000 0.0699990000 0.0314220000 0.3746220000 0.4176360000 147200931 0 402718720 3.9051942825 4.0128426552 3.8777875900 3082 1311867821.4626159668 0.1274777949 0.1254464651 0.2390826792 0.0050152411 0.5085120000 0.0542480000 0.0699950000 0.0000000000 0.3749420000 0.0016520000 147204827 0 402718720 3.9044823647 4.0128607750 3.8777818680 3083 1311867821.4939169884 0.1269409060 0.1254469498 0.2390826792 0.0050147493 0.5446590000 0.0541540000 0.0697980000 0.0313640000 0.3802560000 0.0015590000 147208443 0 402718720 3.9048016071 4.0112390518 3.8773186207 3084 1311867821.5273780823 0.1286132187 0.1254479765 0.2390826792 0.0050146042 0.5090690000 0.0534300000 0.0655260000 0.0000000000 0.3810750000 0.0015530000 147212171 0 402718720 3.9026458263 4.0114860535 3.8779015541 3085 1311867821.5590820312 0.1300179958 0.1254494578 0.2390826792 0.0050143066 0.9219950000 0.0539490000 0.0340980000 0.0314190000 0.3809930000 0.4139640000 147215843 0 402718720 3.9004142284 4.0127129555 3.8782019615 3086 1311867821.5928409100 0.1283220947 0.1254503887 0.2390826792 0.0050148438 0.5151220000 0.0644540000 0.0600320000 0.0000010000 0.3815550000 0.0015510000 147219459 0 402718720 3.9015941620 4.0112214088 3.8780100346 3087 1311867821.6260631084 0.1269080639 0.1254508609 0.2390826792 0.0050142998 0.5418370000 0.0539140000 0.0656470000 0.0313050000 0.3819380000 0.0015560000 147223131 0 402718720 3.9025955200 4.0116200447 3.8787455559 3088 1311867821.6634659767 0.1291176528 0.1254520483 0.2390826792 0.0050137932 0.5169930000 0.0676040000 0.0549320000 0.0000010000 0.3853960000 0.0015520000 147227139 0 402718720 3.8993747234 4.0128927231 3.8790130615 3089 1311867821.6953229904 0.1292632371 0.1254532821 0.2390826792 0.0050137762 0.9589740000 0.0669300000 0.0630830000 0.0309420000 0.3765940000 0.4139720000 147230755 0 402718720 3.8986492157 4.0111579895 3.8793156147 3090 1311867821.7313649654 0.1287957877 0.1254543638 0.2390826792 0.0050134086 0.4746010000 0.0533690000 0.0352420000 0.0000000000 0.3769950000 0.0015440000 147234539 0 402718720 3.8984239101 4.0104660988 3.8797745705 3091 1311867821.7634460926 0.1280995309 0.1254552196 0.2390826792 0.0050128354 0.5423520000 0.0537440000 0.0697070000 0.0313400000 0.3784720000 0.0015580000 147238267 0 402718720 3.8985371590 4.0109472275 3.8801996708 3092 1311867821.7956120968 0.1297936141 0.1254566227 0.2390826792 0.0050121563 0.4824550000 0.0533820000 0.0386280000 0.0000010000 0.3813900000 0.0015440000 147241827 0 402718720 3.8961591721 4.0095872879 3.8806104660 3093 1311867821.8313920498 0.1292264462 0.1254578415 0.2390826792 0.0050115685 0.9747690000 0.0729900000 0.0649420000 0.0313450000 0.3824980000 0.4154910000 147245611 0 402718720 3.8960540295 4.0088195801 3.8807244301 3094 1311867821.8633379936 0.1311316788 0.1254596754 0.2390826792 0.0050118100 0.4889000000 0.0534550000 0.0465570000 0.0000010000 0.3798520000 0.0015470000 147249227 0 402718720 3.8943338394 4.0095419884 3.8812987804 3095 1311867821.8956110477 0.1306032091 0.1254613372 0.2390826792 0.0050114286 0.5401110000 0.0528230000 0.0648590000 0.0312380000 0.3821260000 0.0015370000 147252955 0 402718720 3.8943905830 4.0086355209 3.8809564114 3096 1311867821.9314410686 0.1311523616 0.1254631754 0.2390826792 0.0050109948 0.5109860000 0.0524510000 0.0683340000 0.0000010000 0.3811330000 0.0015360000 147256739 0 402718720 3.8933966160 4.0069007874 3.8806269169 3097 1311867821.9633870125 0.1315020025 0.1254651253 0.2390826792 0.0050103807 0.9498850000 0.0643760000 0.0435660000 0.0312620000 0.3842590000 0.4188900000 147260467 0 402718720 3.8928081989 4.0068221092 3.8807277679 3098 1311867821.9954171181 0.1312327683 0.1254669870 0.2390826792 0.0050099151 0.5411870000 0.0835430000 0.0679530000 0.0000010000 0.3802610000 0.0016280000 147264139 0 402718720 3.8926453590 4.0057954788 3.8805744648 3099 1311867822.0314009190 0.1303680390 0.1254685685 0.2390826792 0.0050101436 0.5466140000 0.0525820000 0.0674150000 0.0312820000 0.3862200000 0.0015360000 147267867 0 402718720 3.8929653168 4.0036559105 3.8802862167 3100 1311867822.0633769035 0.1333124638 0.1254710988 0.2390826792 0.0050106387 0.4849090000 0.0511140000 0.0375630000 0.0000010000 0.3870710000 0.0015230000 147271595 0 402718720 3.8894705772 4.0051865578 3.8809726238 3101 1311867822.0962209702 0.1337998807 0.1254737847 0.2390826792 0.0050099708 0.9436830000 0.0516700000 0.0426660000 0.0310390000 0.3875330000 0.4232740000 147275211 0 402718720 3.8885896206 4.0052747726 3.8812718391 3102 1311867822.1315379143 0.1343413591 0.1254766433 0.2390826792 0.0050102016 0.4772230000 0.0511690000 0.0341180000 0.0000000000 0.3828420000 0.0015270000 147278995 0 402718720 3.8877277374 4.0056605339 3.8812661171 3103 1311867822.1634409428 0.1358933598 0.1254800003 0.2390826792 0.0050096882 0.5543490000 0.0633700000 0.0638980000 0.0311740000 0.3868990000 0.0015260000 147282723 0 402718720 3.8860042095 4.0060830116 3.8820648193 3104 1311867822.1960899830 0.1370216608 0.1254837186 0.2390826792 0.0050091240 0.5146730000 0.0519140000 0.0674000000 0.0000010000 0.3862650000 0.0015360000 147286339 0 402718720 3.8845286369 4.0065946579 3.8827612400 3105 1311867822.2317450047 0.1353878528 0.1254869084 0.2390826792 0.0050089758 0.9624780000 0.0522180000 0.0641810000 0.0312900000 0.3859130000 0.4213470000 147290123 0 402718720 3.8860843182 4.0048770905 3.8829956055 3106 1311867822.2634150982 0.1345271766 0.1254898190 0.2390826792 0.0050098485 0.5174190000 0.0516560000 0.0636760000 0.0000010000 0.3917740000 0.0019610000 147293851 0 402718720 3.8874354362 4.0043463707 3.8823363781 3107 1311867822.2954349518 0.1347913891 0.1254928127 0.2390826792 0.0050095856 0.5836960000 0.0652080000 0.0828200000 0.0388810000 0.3877230000 0.0015300000 147297467 0 402718720 3.8865089417 4.0040774345 3.8824777603 3108 1311867822.3315870762 0.1328550577 0.1254951815 0.2390826792 0.0050092679 0.5057480000 0.0626300000 0.0511650000 0.0000000000 0.3820400000 0.0016310000 147301251 0 402718720 3.8883323669 4.0033202171 3.8826508522 3109 1311867822.3635189533 0.1348735690 0.1254981980 0.2390826792 0.0050086740 0.9666110000 0.0519600000 0.0663620000 0.0308700000 0.3869010000 0.4229160000 147304979 0 402718720 3.8859620094 4.0026845932 3.8827991486 3110 1311867822.3960089684 0.1350521147 0.1255012700 0.2390826792 0.0050080887 0.5111380000 0.0514630000 0.0634710000 0.0000000000 0.3870380000 0.0015260000 147308595 0 402718720 3.8852331638 4.0031933784 3.8827450275 3111 1311867822.4314260483 0.1347266734 0.1255042354 0.2390826792 0.0050074314 0.5276270000 0.0628680000 0.0377730000 0.0312830000 0.3865580000 0.0015290000 147312379 0 402718720 3.8849201202 4.0021877289 3.8828861713 3112 1311867822.4634740353 0.1359347403 0.1255075872 0.2390826792 0.0050071722 0.4864440000 0.0524510000 0.0380950000 0.0000010000 0.3867150000 0.0015320000 147316051 0 402718720 3.8836245537 4.0010051727 3.8831646442 3113 1311867822.4957718849 0.1376532912 0.1255114888 0.2390826792 0.0050068688 0.9770920000 0.0653290000 0.0640620000 0.0312300000 0.3864740000 0.4223100000 147319667 0 402718720 3.8814339638 4.0009455681 3.8837070465 3114 1311867822.5315260887 0.1386961043 0.1255157227 0.2390826792 0.0050069334 0.5126230000 0.0515540000 0.0647480000 0.0000010000 0.3872430000 0.0015170000 147323507 0 402718720 3.8801755905 3.9991674423 3.8833906651 3115 1311867822.5634500980 0.1376162022 0.1255196073 0.2390826792 0.0050068041 0.5252240000 0.0511300000 0.0450500000 0.0311840000 0.3887700000 0.0015280000 147327179 0 402718720 3.8814325333 3.9974308014 3.8835365772 3116 1311867822.5955328941 0.1385408044 0.1255237861 0.2390826792 0.0050067893 0.4948090000 0.0517050000 0.0428800000 0.0000010000 0.3910290000 0.0015280000 147330851 0 402718720 3.8803012371 3.9948806763 3.8834638596 3117 1311867822.6315131187 0.1416867375 0.1255289716 0.2390826792 0.0050072689 0.9727980000 0.0504170000 0.0576550000 0.0312830000 0.3934130000 0.4323710000 147334635 0 402718720 3.8771986961 3.9940376282 3.8834123611 3118 1311867822.6634640694 0.1400945038 0.1255336430 0.2390826792 0.0050073927 0.4854690000 0.0492500000 0.0318350000 0.0000010000 0.3953010000 0.0015120000 147338307 0 402718720 3.8786492348 3.9926598072 3.8829686642 3119 1311867822.6954870224 0.1418708265 0.1255388810 0.2390826792 0.0050068339 0.5234910000 0.0494670000 0.0367350000 0.0312850000 0.3968870000 0.0015110000 147341979 0 402718720 3.8765151501 3.9922270775 3.8830611706 3120 1311867822.7317390442 0.1441576928 0.1255448485 0.2390826792 0.0050077239 0.5028000000 0.0494740000 0.0465390000 0.0000010000 0.3977140000 0.0015030000 147345707 0 402718720 3.8737726212 3.9928495884 3.8835170269 3121 1311867822.7634871006 0.1457718909 0.1255513295 0.2390826792 0.0050070497 0.9595910000 0.0492670000 0.0365730000 0.0307670000 0.3970550000 0.4382660000 147349379 0 402718720 3.8715531826 3.9942045212 3.8838136196 3122 1311867822.7954308987 0.1462864429 0.1255579711 0.2390826792 0.0050067586 0.5286850000 0.0616160000 0.0616510000 0.0000010000 0.3962920000 0.0015020000 147353051 0 402718720 3.8708713055 3.9920196533 3.8841214180 3123 1311867822.8314750195 0.1444571018 0.1255640227 0.2390826792 0.0050069598 0.5380630000 0.0602870000 0.0420180000 0.0313090000 0.3952800000 0.0015100000 147356835 0 402718720 3.8716564178 3.9929943085 3.8841848373 3124 1311867822.8634629250 0.1448254436 0.1255701883 0.2390826792 0.0050090766 0.5003140000 0.0501650000 0.0473600000 0.0000010000 0.3937170000 0.0015070000 147360507 0 402718720 3.8709816933 3.9952015877 3.8847212791 3125 1311867822.8955349922 0.1431431174 0.1255758116 0.2390826792 0.0050085258 0.9791810000 0.0713040000 0.0449390000 0.0313210000 0.3867290000 0.4372730000 147364067 0 402718720 3.8721859455 3.9945471287 3.8848965168 3126 1311867822.9318330288 0.1426654011 0.1255812786 0.2390826792 0.0050079442 0.5130690000 0.0515770000 0.0671490000 0.0000010000 0.3848280000 0.0016080000 147367907 0 402718720 3.8720133305 3.9945991039 3.8851842880 3127 1311867822.9635109901 0.1416295022 0.1255864107 0.2390826792 0.0050076217 0.5478670000 0.0518010000 0.0674530000 0.0313520000 0.3880980000 0.0015270000 147371579 0 402718720 3.8722043037 3.9958465099 3.8854062557 3128 1311867822.9979970455 0.1401291043 0.1255910599 0.2390826792 0.0050076002 0.5294700000 0.0705940000 0.0677790000 0.0000010000 0.3819530000 0.0015310000 147375363 0 402718720 3.8731451035 3.9956314564 3.8856697083 3129 1311867823.0344979763 0.1403097510 0.1255957639 0.2390826792 0.0050070687 0.9395250000 0.0526080000 0.0382380000 0.0312550000 0.3888320000 0.4209600000 147379035 0 402718720 3.8722217083 3.9952204227 3.8856768608 3130 1311867823.0634639263 0.1411831826 0.1256007439 0.2390826792 0.0050068160 0.5025440000 0.0649440000 0.0436190000 0.0000010000 0.3848190000 0.0015300000 147382595 0 402718720 3.8706717491 3.9953515530 3.8861277103 3131 1311867823.0971090794 0.1423819214 0.1256061036 0.2390826792 0.0050061377 0.5407270000 0.0528980000 0.0681710000 0.0313160000 0.3792410000 0.0015320000 147386323 0 402718720 3.8687474728 3.9957482815 3.8864910603 3132 1311867823.1313869953 0.1409183145 0.1256109925 0.2390826792 0.0050072923 0.4788080000 0.0525620000 0.0330890000 0.0000000000 0.3838830000 0.0015320000 147390051 0 402718720 3.8693807125 3.9941618443 3.8864309788 3133 1311867823.1635200977 0.1412895024 0.1256159968 0.2390826792 0.0050079161 0.9477690000 0.0629730000 0.0436270000 0.0312810000 0.3837500000 0.4185480000 147393723 0 402718720 3.8683075905 3.9935662746 3.8865177631 3134 1311867823.1954131126 0.1430010051 0.1256215441 0.2390826792 0.0050099990 0.4874100000 0.0532340000 0.0461660000 0.0000000000 0.3788330000 0.0015350000 147397395 0 402718720 3.8658707142 3.9944422245 3.8872950077 3135 1311867823.2316908836 0.1425407529 0.1256269409 0.2390826792 0.0050093956 0.5258330000 0.0528600000 0.0491470000 0.0312480000 0.3834220000 0.0015280000 147401235 0 402718720 3.8655700684 3.9936845303 3.8872370720 3136 1311867823.2635869980 0.1442108601 0.1256328669 0.2390826792 0.0050142745 0.4888670000 0.0520360000 0.0435260000 0.0000010000 0.3841070000 0.0015240000 147404907 0 402718720 3.8637127876 3.9932227135 3.8876259327 3137 1311867823.2955200672 0.1440883279 0.1256387501 0.2390826792 0.0050135707 0.9333930000 0.0526280000 0.0384500000 0.0312330000 0.3840880000 0.4193690000 147408523 0 402718720 3.8631746769 3.9951901436 3.8881630898 3138 1311867823.3330919743 0.1457820237 0.1256451692 0.2390826792 0.0050129643 0.5000250000 0.0641080000 0.0462410000 0.0000010000 0.3804790000 0.0015270000 147412363 0 402718720 3.8608138561 3.9951345921 3.8882865906 3139 1311867823.3635790348 0.1462273002 0.1256517261 0.2390826792 0.0050123702 0.5140690000 0.0526770000 0.0383190000 0.0307390000 0.3832070000 0.0015320000 147416035 0 402718720 3.8598673344 3.9942488670 3.8884680271 3140 1311867823.3954129219 0.1482599080 0.1256589262 0.2390826792 0.0050123956 0.4956000000 0.0649860000 0.0384480000 0.0000010000 0.3829660000 0.0015310000 147419651 0 402718720 3.8571143150 3.9961478710 3.8889601231 3141 1311867823.4318161011 0.1494152695 0.1256664895 0.2390826792 0.0050123073 0.9559720000 0.0532930000 0.0652480000 0.0312840000 0.3818190000 0.4166340000 147423491 0 402718720 3.8553874493 3.9954793453 3.8891820908 3142 1311867823.4634220600 0.1505996138 0.1256744249 0.2390826792 0.0050151629 0.5089850000 0.0533730000 0.0649970000 0.0000010000 0.3813850000 0.0015300000 147427163 0 402718720 3.8540470600 3.9961669445 3.8895103931 3143 1311867823.4969789982 0.1505210698 0.1256823303 0.2390826792 0.0050154038 0.5191980000 0.0649560000 0.0332790000 0.0312080000 0.3805430000 0.0015350000 147430891 0 402718720 3.8533053398 3.9973249435 3.8896002769 3144 1311867823.5356218815 0.1494003087 0.1256898742 0.2390826792 0.0050151588 0.4893540000 0.0533450000 0.0521900000 0.0000010000 0.3745450000 0.0015350000 147434675 0 402718720 3.8539135456 3.9981007576 3.8896517754 3145 1311867823.5636498928 0.1480223984 0.1256969752 0.2390826792 0.0050175463 0.9296620000 0.0540350000 0.0468330000 0.0312990000 0.3778140000 0.4118810000 147438291 0 402718720 3.8551282883 3.9961814880 3.8894870281 3146 1311867823.5974569321 0.1510245800 0.1257050259 0.2390826792 0.0050175509 0.5063050000 0.0539340000 0.0693130000 0.0000010000 0.3738160000 0.0015370000 147442019 0 402718720 3.8515543938 3.9970433712 3.8903846741 3147 1311867823.6316640377 0.1496665180 0.1257126400 0.2390826792 0.0050350158 0.5376600000 0.0540490000 0.0660140000 0.0311770000 0.3772780000 0.0015360000 147445747 0 402718720 3.8521423340 3.9991621971 3.8905711174 3148 1311867823.6636750698 0.1478233039 0.1257196637 0.2390826792 0.0050385718 0.5095030000 0.0703600000 0.0482430000 0.0000010000 0.3816600000 0.0015460000 147449419 0 402718720 3.8534305096 4.0000467300 3.8907432556 3149 1311867823.6956110001 0.1464941800 0.1257262609 0.2390826792 0.0050393853 0.9269800000 0.0549310000 0.0533350000 0.0312680000 0.3743030000 0.4054220000 147453035 0 402718720 3.8544092178 3.9983327389 3.8907110691 3150 1311867823.7316160202 0.1474581212 0.1257331599 0.2390826792 0.0050389896 0.4817300000 0.0551900000 0.0475790000 0.0000010000 0.3697100000 0.0015500000 147456875 0 402718720 3.8529331684 3.9993355274 3.8913547993 3151 1311867823.7635159492 0.1462624967 0.1257396751 0.2390826792 0.0050384059 0.5076540000 0.0556480000 0.0399940000 0.0312500000 0.3715590000 0.0015510000 147460547 0 402718720 3.8535103798 3.9999847412 3.8912169933 3152 1311867823.7964189053 0.1468529999 0.1257463734 0.2390826792 0.0050379577 0.4705720000 0.0562090000 0.0346210000 0.0000010000 0.3705090000 0.0015560000 147464219 0 402718720 3.8525366783 3.9984109402 3.8915114403 3153 1311867823.8316709995 0.1465409696 0.1257529686 0.2390826792 0.0050372602 0.9203470000 0.0671660000 0.0479570000 0.0313030000 0.3654550000 0.4007320000 147468003 0 402718720 3.8524174690 3.9991617203 3.8922123909 3154 1311867823.8635869026 0.1467786282 0.1257596350 0.2390826792 0.0050375408 0.4644820000 0.0562120000 0.0290610000 0.0000000000 0.3699050000 0.0015290000 147471675 0 402718720 3.8517947197 4.0003099442 3.8928191662 3155 1311867823.8993299007 0.1462349743 0.1257661248 0.2390826792 0.0050373500 0.5002810000 0.0566090000 0.0348310000 0.0312020000 0.3683220000 0.0015610000 147475403 0 402718720 3.8519797325 4.0004682541 3.8930284977 3156 1311867823.9316000938 0.1460650563 0.1257725566 0.2390826792 0.0050491897 0.4693750000 0.0568940000 0.0350290000 0.0000000000 0.3680160000 0.0015550000 147479131 0 402718720 3.8520164490 3.9994380474 3.8935189247 3157 1311867823.9639530182 0.1469042599 0.1257792502 0.2390826792 0.0050592064 0.9290580000 0.0573210000 0.0575620000 0.0312350000 0.3674610000 0.4069760000 147482859 0 402718720 3.8509624004 3.9998953342 3.8940489292 3158 1311867823.9956440926 0.1472328454 0.1257860436 0.2390826792 0.0050597895 0.4947420000 0.0727640000 0.0459950000 0.0000000000 0.3667380000 0.0015640000 147486419 0 402718720 3.8501603603 4.0009741783 3.8944690228 3159 1311867824.0315599442 0.1465410888 0.1257926138 0.2390826792 0.0050594100 0.5059120000 0.0573330000 0.0422290000 0.0312430000 0.3657710000 0.0015740000 147490259 0 402718720 3.8503661156 4.0005283356 3.8945996761 3160 1311867824.0634789467 0.1482175738 0.1257997103 0.2390826792 0.0050606339 0.5033930000 0.0706780000 0.0577190000 0.0000010000 0.3656920000 0.0015680000 147493931 0 402718720 3.8487040997 4.0001945496 3.8954379559 3161 1311867824.0966339111 0.1495943666 0.1258072379 0.2390826792 0.0050601048 0.8906490000 0.0577730000 0.0359910000 0.0307820000 0.3646620000 0.3936950000 147497603 0 402718720 3.8468599319 4.0013041496 3.8957347870 3162 1311867824.1315801144 0.1474563479 0.1258140845 0.2390826792 0.0050598742 0.4723400000 0.0576720000 0.0410310000 0.0000000000 0.3644010000 0.0015630000 147501387 0 402718720 3.8482863903 4.0004806519 3.8955192566 3163 1311867824.1636250019 0.1490851641 0.1258214418 0.2390826792 0.0050591287 0.5249160000 0.0673530000 0.0524630000 0.0312630000 0.3645150000 0.0015720000 147505059 0 402718720 3.8464870453 3.9999182224 3.8961300850 3164 1311867824.1974411011 0.1491788477 0.1258288240 0.2390826792 0.0050589279 0.4912330000 0.0579080000 0.0554220000 0.0000010000 0.3673380000 0.0020430000 147508787 0 402718720 3.8460919857 4.0024919510 3.8968734741 3165 1311867824.2314341068 0.1517547667 0.1258370155 0.2390826792 0.0050610640 0.9555870000 0.0743710000 0.0880430000 0.0312910000 0.3626740000 0.3914000000 147512459 0 402718720 3.8430056572 4.0020771027 3.8974330425 3166 1311867824.2667160034 0.1501694769 0.1258447010 0.2390826792 0.0050608048 0.5067350000 0.0624360000 0.0700480000 0.0000000000 0.3648770000 0.0015720000 147516243 0 402718720 3.8443844318 4.0016508102 3.8974847794 3167 1311867824.3015260696 0.1503176242 0.1258524285 0.2390826792 0.0050624242 0.5031060000 0.0588120000 0.0378430000 0.0309020000 0.3650040000 0.0020490000 147519971 0 402718720 3.8438618183 4.0040888786 3.8979830742 3168 1311867824.3329520226 0.1507014185 0.1258602723 0.2390826792 0.0050617829 0.4924100000 0.0751900000 0.0476310000 0.0000010000 0.3602140000 0.0015760000 147523699 0 402718720 3.8431060314 4.0049829483 3.8983051777 3169 1311867824.3655378819 0.1496692300 0.1258677853 0.2390826792 0.0050623681 0.8773070000 0.0593580000 0.0379740000 0.0313100000 0.3547350000 0.3862150000 147527371 0 402718720 3.8437545300 4.0057215691 3.8987386227 3170 1311867824.3960471153 0.1486176401 0.1258749619 0.2390826792 0.0050616833 0.4689070000 0.0597430000 0.0422250000 0.0000010000 0.3575070000 0.0015810000 147530931 0 402718720 3.8445684910 4.0077695847 3.8989317417 3171 1311867824.4315910339 0.1482379586 0.1258820143 0.2390826792 0.0050610134 0.4862530000 0.0602740000 0.0307420000 0.0308120000 0.3551110000 0.0015920000 147534715 0 402718720 3.8448541164 4.0092048645 3.8994829655 3172 1311867824.4656479359 0.1477471441 0.1258889075 0.2390826792 0.0050602389 0.4714940000 0.0608170000 0.0487120000 0.0000010000 0.3526800000 0.0015880000 147538499 0 402718720 3.8451385498 4.0111508369 3.9003167152 3173 1311867824.4978680611 0.1454447359 0.1258950707 0.2390826792 0.0050627141 0.8827210000 0.0735640000 0.0453150000 0.0314550000 0.3499400000 0.3747130000 147542171 0 402718720 3.8471407890 4.0114994049 3.9004757404 3174 1311867824.5316801071 0.1444995552 0.1259009322 0.2390826792 0.0050619515 0.4940150000 0.0621430000 0.0759610000 0.0000010000 0.3465250000 0.0016060000 147545843 0 402718720 3.8480858803 4.0129094124 3.9013857841 3175 1311867824.5658340454 0.1442144960 0.1259067002 0.2390826792 0.0050612076 0.4991090000 0.0627150000 0.0495560000 0.0312730000 0.3461480000 0.0016140000 147549627 0 402718720 3.8483390808 4.0139608383 3.9020104408 3176 1311867824.5956490040 0.1450206190 0.1259127185 0.2390826792 0.0050606286 0.4912200000 0.0631570000 0.0738030000 0.0000010000 0.3448920000 0.0016190000 147553187 0 402718720 3.8475432396 4.0140280724 3.9026277065 3177 1311867824.6318910122 0.1424840987 0.1259179345 0.2390826792 0.0050601119 0.8550340000 0.0621330000 0.0433810000 0.0311170000 0.3443720000 0.3662820000 147557027 0 402718720 3.8502843380 4.0141119957 3.9031648636 3178 1311867824.6661880016 0.1434672028 0.1259234566 0.2390826792 0.0050595356 0.4858940000 0.0889480000 0.0440970000 0.0000000000 0.3434370000 0.0016150000 147560699 0 402718720 3.8494496346 4.0148444176 3.9042801857 3179 1311867824.6979959011 0.1437108815 0.1259290519 0.2390826792 0.0050661305 0.4843810000 0.0645640000 0.0402160000 0.0314150000 0.3387150000 0.0016330000 147564371 0 402718720 3.8492465019 4.0143818855 3.9052138329 3180 1311867824.7314980030 0.1423652470 0.1259342205 0.2390826792 0.0050725137 0.4916310000 0.0646360000 0.0750930000 0.0000010000 0.3424820000 0.0016230000 147567987 0 402718720 3.8502244949 4.0147662163 3.9058544636 3181 1311867824.7639760971 0.1406996548 0.1259388623 0.2390826792 0.0050721477 0.8822070000 0.0648150000 0.0736410000 0.0313500000 0.3418360000 0.3627920000 147571771 0 402718720 3.8518767357 4.0152564049 3.9065155983 3182 1311867824.7997510433 0.1417897791 0.1259438437 0.2390826792 0.0050748803 0.4889220000 0.0635350000 0.0735310000 0.0000000000 0.3424610000 0.0016250000 147575443 0 402718720 3.8507521152 4.0164651871 3.9069621563 3183 1311867824.8315179348 0.1413055360 0.1259486699 0.2390826792 0.0050791928 0.5254720000 0.0656100000 0.0780000000 0.0313470000 0.3410700000 0.0016430000 147579171 0 402718720 3.8510806561 4.0153050423 3.9076707363 3184 1311867824.8635060787 0.1413873583 0.1259535187 0.2390826792 0.0050786823 0.4540700000 0.0649900000 0.0384980000 0.0000000000 0.3411230000 0.0016350000 147582843 0 402718720 3.8508954048 4.0151610374 3.9081280231 3185 1311867824.8995370865 0.1415693164 0.1259584216 0.2390826792 0.0050832132 0.8465990000 0.0657740000 0.0408770000 0.0314390000 0.3404300000 0.3602780000 147586571 0 402718720 3.8505785465 4.0158896446 3.9089741707 3186 1311867824.9316530228 0.1397649497 0.1259627551 0.2390826792 0.0050825920 0.4609290000 0.0661730000 0.0452670000 0.0000010000 0.3400870000 0.0016440000 147590299 0 402718720 3.8520147800 4.0153279305 3.9095449448 3187 1311867824.9636321068 0.1414130330 0.1259676031 0.2390826792 0.0050833350 0.5355820000 0.0785530000 0.0764280000 0.0314370000 0.3397150000 0.0016580000 147593971 0 402718720 3.8499138355 4.0152449608 3.9104235172 3188 1311867824.9996089935 0.1402614713 0.1259720867 0.2390826792 0.0050835585 0.4666360000 0.0786100000 0.0390380000 0.0000010000 0.3395400000 0.0016490000 147597811 0 402718720 3.8505275249 4.0151939392 3.9110589027 3189 1311867825.0316529274 0.1404747367 0.1259766344 0.2390826792 0.0050830316 0.8422640000 0.0665100000 0.0390910000 0.0314410000 0.3391430000 0.3582330000 147601427 0 402718720 3.8497638702 4.0147457123 3.9114272594 3190 1311867825.0644180775 0.1402641982 0.1259811133 0.2390826792 0.0050825384 0.4906210000 0.0659020000 0.0761970000 0.0000000000 0.3390990000 0.0016430000 147605043 0 402718720 3.8494317532 4.0143399239 3.9115068913 3191 1311867825.0997018814 0.1389416456 0.1259851749 0.2390826792 0.0050820410 0.4898190000 0.0653990000 0.0449060000 0.0313400000 0.3388220000 0.0016340000 147608827 0 402718720 3.8502433300 4.0149445534 3.9118502140 3192 1311867825.1316909790 0.1408703625 0.1259898381 0.2390826792 0.0050813006 0.4791650000 0.0667380000 0.0644480000 0.0000010000 0.3384710000 0.0016540000 147612555 0 402718720 3.8477680683 4.0143737793 3.9121370316 3193 1311867825.1636679173 0.1391736120 0.1259939671 0.2390826792 0.0050812167 0.9075620000 0.0968170000 0.0765310000 0.0308400000 0.3383770000 0.3571660000 147616227 0 402718720 3.8490161896 4.0119214058 3.9116752148 3194 1311867825.1996359825 0.1397292167 0.1259982674 0.2390826792 0.0050810345 0.4520970000 0.0651440000 0.0387170000 0.0000000000 0.3387850000 0.0016460000 147619955 0 402718720 3.8477206230 4.0126070976 3.9124822617 3195 1311867825.2316811085 0.1383183002 0.1260021235 0.2390826792 0.0050820380 0.4842850000 0.0660820000 0.0392520000 0.0313200000 0.3381630000 0.0016540000 147623683 0 402718720 3.8470737934 4.0146355629 3.9121520519 3196 1311867825.2670049667 0.1360932887 0.1260052809 0.2390826792 0.0050835096 0.4794610000 0.0668420000 0.0649620000 0.0000010000 0.3378610000 0.0016540000 147627467 0 402718720 3.8483538628 4.0125007629 3.9117743969 3197 1311867825.2996079922 0.1372222751 0.1260087895 0.2390826792 0.0050827352 0.8462210000 0.0665000000 0.0471080000 0.0308850000 0.3375150000 0.3563080000 147631195 0 402718720 3.8462736607 4.0131769180 3.9123158455 3198 1311867825.3316459656 0.1365151107 0.1260120748 0.2390826792 0.0050838377 0.4592700000 0.0668530000 0.0458430000 0.0000000000 0.3370960000 0.0016610000 147634811 0 402718720 3.8459153175 4.0143895149 3.9127781391 3199 1311867825.3635549545 0.1377107948 0.1260157318 0.2390826792 0.0050833075 0.4903320000 0.0671760000 0.0460310000 0.0314670000 0.3362590000 0.0016640000 147638483 0 402718720 3.8437502384 4.0133576393 3.9131741524 3200 1311867825.3995220661 0.1373335868 0.1260192686 0.2390826792 0.0050829059 0.4909400000 0.0670420000 0.0818970000 0.0000000000 0.3325890000 0.0016700000 147642323 0 402718720 3.8435049057 4.0120286942 3.9137482643 3201 1311867825.4329199791 0.1361038983 0.1260224191 0.2390826792 0.0050826078 0.8806160000 0.0679480000 0.0787050000 0.0314700000 0.3352870000 0.3593820000 147645995 0 402718720 3.8439376354 4.0129795074 3.9139282703 3202 1311867825.4655759335 0.1382079571 0.1260262247 0.2390826792 0.0050818728 0.4889500000 0.0662810000 0.0772460000 0.0000010000 0.3358550000 0.0016700000 147649611 0 402718720 3.8411912918 4.0121588707 3.9139394760 3203 1311867825.4996039867 0.1381971836 0.1260300245 0.2390826792 0.0050810888 0.5421210000 0.0992700000 0.0664360000 0.0312820000 0.3355600000 0.0016710000 147653283 0 402718720 3.8406453133 4.0124363899 3.9140865803 3204 1311867825.5338120461 0.1379520595 0.1260337455 0.2390826792 0.0050803232 0.4571990000 0.0674490000 0.0485210000 0.0000000000 0.3316880000 0.0016720000 147657067 0 402718720 3.8406188488 4.0131363869 3.9145791531 3205 1311867825.5637319088 0.1389460415 0.1260377743 0.2390826792 0.0050797114 0.8339800000 0.0674350000 0.0396870000 0.0313980000 0.3347820000 0.3528450000 147660683 0 402718720 3.8393599987 4.0134973526 3.9145441055 3206 1311867825.5995988846 0.1408463120 0.1260423933 0.2390826792 0.0050789956 0.4776930000 0.0679900000 0.0654660000 0.0000010000 0.3346630000 0.0016710000 147664411 0 402718720 3.8367066383 4.0132870674 3.9148950577 3207 1311867825.6372098923 0.1392221451 0.1260465030 0.2390826792 0.0050785467 0.5201960000 0.0671030000 0.0777810000 0.0314320000 0.3344580000 0.0016640000 147668251 0 402718720 3.8377976418 4.0135970116 3.9149034023 3208 1311867825.6636829376 0.1380651891 0.1260502495 0.2390826792 0.0050778638 0.4999800000 0.0797690000 0.0655490000 0.0000010000 0.3437540000 0.0022110000 147671755 0 402718720 3.8390491009 4.0141024590 3.9149179459 3209 1311867825.6997060776 0.1395898163 0.1260544687 0.2390826792 0.0050782732 0.8745020000 0.0689620000 0.0787340000 0.0312850000 0.3349960000 0.3525570000 147675539 0 402718720 3.8370265961 4.0129132271 3.9150657654 3210 1311867825.7345299721 0.1410635263 0.1260591444 0.2390826792 0.0050776103 0.4902040000 0.0677120000 0.0783340000 0.0000010000 0.3346400000 0.0016730000 147679267 0 402718720 3.8350365162 4.0131807327 3.9155282974 3211 1311867825.7654349804 0.1374248117 0.1260626840 0.2390826792 0.0050769662 0.4919740000 0.0678250000 0.0463940000 0.0314650000 0.3367600000 0.0016730000 147682883 0 402718720 3.8386688232 4.0145006180 3.9149613380 3212 1311867825.7998030186 0.1399608552 0.1260670110 0.2390826792 0.0050768932 0.4895010000 0.0674840000 0.0781860000 0.0000000000 0.3342570000 0.0016610000 147686723 0 402718720 3.8359432220 4.0114574432 3.9149665833 3213 1311867825.8355960846 0.1408853829 0.1260716230 0.2390826792 0.0050763532 0.9089760000 0.1014290000 0.0825220000 0.0315560000 0.3323310000 0.3530950000 147690507 0 402718720 3.8345477581 4.0128684044 3.9152932167 3214 1311867825.8656499386 0.1394332796 0.1260757803 0.2390826792 0.0050757285 0.4964490000 0.0681360000 0.0828610000 0.0000000000 0.3345540000 0.0022050000 147694067 0 402718720 3.8357985020 4.0143923759 3.9147675037 3215 1311867825.8996019363 0.1369443536 0.1260791609 0.2390826792 0.0050756490 0.5498710000 0.0866080000 0.0868860000 0.0324500000 0.3344350000 0.0016730000 147697851 0 402718720 3.8383371830 4.0129241943 3.9144585133 3216 1311867825.9338490963 0.1376232952 0.1260827505 0.2390826792 0.0050752674 0.4516470000 0.0674140000 0.0396750000 0.0000010000 0.3350350000 0.0016680000 147701579 0 402718720 3.8372592926 4.0131058693 3.9146504402 3217 1311867825.9640550613 0.1375181526 0.1260863052 0.2390826792 0.0050747683 0.8746520000 0.0683120000 0.0787560000 0.0315130000 0.3347270000 0.3528300000 147705195 0 402718720 3.8374984264 4.0146627426 3.9143333435 3218 1311867825.9996759892 0.1378947645 0.1260899747 0.2390826792 0.0050743984 0.4833140000 0.0801760000 0.0587140000 0.0000000000 0.3348450000 0.0016740000 147708923 0 402718720 3.8368353844 4.0129418373 3.9142003059 3219 1311867826.0327920914 0.1377757043 0.1260936049 0.2390826792 0.0050740326 0.5217610000 0.0676130000 0.0823470000 0.0310370000 0.3312780000 0.0016740000 147712651 0 402718720 3.8368728161 4.0148124695 3.9141955376 3220 1311867826.0636880398 0.1381140798 0.1260973380 0.2390826792 0.0050737440 0.5042860000 0.0813000000 0.0788350000 0.0000010000 0.3346140000 0.0016710000 147716323 0 402718720 3.8362877369 4.0160603523 3.9143650532 3221 1311867826.1009249687 0.1397484243 0.1261015761 0.2390826792 0.0050737699 0.8720410000 0.0680490000 0.0785320000 0.0314810000 0.3337200000 0.3515370000 147720107 0 402718720 3.8344132900 4.0140986443 3.9143867493 3222 1311867826.1333520412 0.1400587857 0.1261059080 0.2390826792 0.0050730962 0.4621580000 0.0674820000 0.0509250000 0.0000010000 0.3341790000 0.0016690000 147723835 0 402718720 3.8340542316 4.0138807297 3.9148411751 3223 1311867826.1658940315 0.1397383660 0.1261101377 0.2390826792 0.0050723998 0.5427860000 0.0856610000 0.0825260000 0.0310370000 0.3340740000 0.0016740000 147727507 0 402718720 3.8341159821 4.0153374672 3.9147367477 3224 1311867826.1998670101 0.1379235387 0.1261138019 0.2390826792 0.0050725908 0.4717800000 0.0688880000 0.0594960000 0.0000010000 0.3337980000 0.0016840000 147731235 0 402718720 3.8357729912 4.0146994591 3.9142091274 3225 1311867826.2345190048 0.1387925893 0.1261177333 0.2390826792 0.0050718269 0.8710930000 0.0687310000 0.0773550000 0.0309040000 0.3343490000 0.3519050000 147734963 0 402718720 3.8348913193 4.0135507584 3.9142358303 3226 1311867826.2638120651 0.1382957399 0.1261215083 0.2390826792 0.0050716673 0.4447450000 0.0686300000 0.0318700000 0.0000010000 0.3346120000 0.0016770000 147738579 0 402718720 3.8347496986 4.0136017799 3.9140639305 3227 1311867826.3011031151 0.1411687732 0.1261261712 0.2390826792 0.0050723871 0.4963620000 0.0679400000 0.0527010000 0.0315340000 0.3347000000 0.0016680000 147742307 0 402718720 3.8319633007 4.0125937462 3.9141390324 3228 1311867826.3321969509 0.1399832964 0.1261304640 0.2390826792 0.0050728371 0.4645590000 0.0797450000 0.0398410000 0.0000000000 0.3354120000 0.0016710000 147745811 0 402718720 3.8324096203 4.0126938820 3.9138522148 3229 1311867826.3637990952 0.1415292621 0.1261352329 0.2390826792 0.0050732143 0.8656760000 0.0664960000 0.0699980000 0.0315520000 0.3356440000 0.3540510000 147749483 0 402718720 3.8310880661 4.0133242607 3.9140403271 3230 1311867826.3997180462 0.1417620629 0.1261400710 0.2390826792 0.0050725167 0.4906120000 0.0684990000 0.0768330000 0.0000000000 0.3356820000 0.0016760000 147753211 0 402718720 3.8305675983 4.0132708549 3.9139919281 3231 1311867826.4321830273 0.1415977329 0.1261448551 0.2390826792 0.0050720089 0.5219170000 0.0795950000 0.0655550000 0.0316250000 0.3356140000 0.0016740000 147756939 0 402718720 3.8306050301 4.0128655434 3.9140603542 3232 1311867826.4641919136 0.1416601092 0.1261496556 0.2390826792 0.0050715815 0.4907680000 0.1051160000 0.0402430000 0.0000010000 0.3358330000 0.0016690000 147760667 0 402718720 3.8303058147 4.0147638321 3.9141390324 3233 1311867826.5007300377 0.1410985291 0.1261542795 0.2390826792 0.0050708943 0.8253550000 0.0682050000 0.0351780000 0.0311270000 0.3318430000 0.3510860000 147764395 0 402718720 3.8306005001 4.0145425797 3.9137558937 3234 1311867826.5320169926 0.1410944462 0.1261588992 0.2390826792 0.0050701413 0.4541640000 0.0682490000 0.0403790000 0.0000010000 0.3359440000 0.0016650000 147768067 0 402718720 3.8303351402 4.0139656067 3.9138329029 3235 1311867826.5638980865 0.1429681927 0.1261640953 0.2390826792 0.0050694884 0.4852260000 0.0684970000 0.0398810000 0.0314150000 0.3359530000 0.0016720000 147771795 0 402718720 3.8284788132 4.0145282745 3.9139795303 3236 1311867826.6006839275 0.1421220005 0.1261690266 0.2390826792 0.0050688034 0.4530870000 0.0680510000 0.0397450000 0.0000010000 0.3357360000 0.0016720000 147775523 0 402718720 3.8291337490 4.0142226219 3.9138686657 3237 1311867826.6315999031 0.1401536614 0.1261733469 0.2390826792 0.0050685274 0.8435330000 0.0681140000 0.0462370000 0.0315340000 0.3355600000 0.3541930000 147779139 0 402718720 3.8305642605 4.0144743919 3.9133515358 3238 1311867826.6638810635 0.1418958157 0.1261782025 0.2390826792 0.0050683796 0.4685280000 0.0779710000 0.0484980000 0.0000010000 0.3324390000 0.0016740000 147782811 0 402718720 3.8285584450 4.0159854889 3.9139137268 3239 1311867826.6997959614 0.1412577927 0.1261828581 0.2390826792 0.0050676831 0.4975310000 0.0683650000 0.0527600000 0.0315790000 0.3353160000 0.0016760000 147786539 0 402718720 3.8285231590 4.0158176422 3.9137964249 3240 1311867826.7349510193 0.1424454898 0.1261878775 0.2390826792 0.0050670707 0.4894830000 0.0671640000 0.0803750000 0.0000010000 0.3319950000 0.0017330000 147790323 0 402718720 3.8271095753 4.0138921738 3.9136898518 3241 1311867826.7678439617 0.1405054033 0.1261922951 0.2390826792 0.0050665564 0.8350030000 0.0683100000 0.0382630000 0.0315750000 0.3351230000 0.3537460000 147793939 0 402718720 3.8286249638 4.0146708488 3.9133610725 3242 1311867826.8019490242 0.1403500289 0.1261966621 0.2390826792 0.0050663433 0.4593110000 0.0682150000 0.0463630000 0.0000010000 0.3351270000 0.0016720000 147797723 0 402718720 3.8285782337 4.0143952370 3.9129254818 3243 1311867826.8324790001 0.1424671113 0.1262016792 0.2390826792 0.0050691878 0.5126160000 0.0791940000 0.0575010000 0.0310970000 0.3353000000 0.0016730000 147801339 0 402718720 3.8262240887 4.0124955177 3.9130659103 3244 1311867826.8646159172 0.1421790123 0.1262066043 0.2390826792 0.0050685381 0.5042930000 0.0808770000 0.0780100000 0.0000010000 0.3357640000 0.0016590000 147804955 0 402718720 3.8262867928 4.0126128197 3.9130666256 3245 1311867826.9008219242 0.1415305585 0.1262113267 0.2390826792 0.0050687040 0.8366340000 0.0680580000 0.0384760000 0.0316740000 0.3354380000 0.3550360000 147808739 0 402718720 3.8261926174 4.0130977631 3.9126958847 3246 1311867826.9319140911 0.1434145570 0.1262166265 0.2390826792 0.0050717883 0.4907510000 0.0672680000 0.0778060000 0.0000010000 0.3360630000 0.0016690000 147812299 0 402718720 3.8246819973 4.0134372711 3.9128804207 3247 1311867826.9639439583 0.1418689638 0.1262214471 0.2390826792 0.0050723407 0.4970870000 0.0673660000 0.0523360000 0.0315590000 0.3362560000 0.0016740000 147815859 0 402718720 3.8258712292 4.0134320259 3.9125306606 3248 1311867827.0083661079 0.1435142308 0.1262267712 0.2390826792 0.0050738434 0.4632360000 0.0789650000 0.0417540000 0.0000000000 0.3328510000 0.0016710000 147819811 0 402718720 3.8239986897 4.0137481689 3.9127347469 3249 1311867827.0334970951 0.1426869333 0.1262318374 0.2390826792 0.0050732569 0.8389180000 0.0672850000 0.0416390000 0.0315710000 0.3350280000 0.3554470000 147823259 0 402718720 3.8246872425 4.0132308006 3.9124119282 3250 1311867827.0653018951 0.1433936656 0.1262371180 0.2390826792 0.0050740901 0.4578560000 0.0658710000 0.0459380000 0.0000010000 0.3364630000 0.0016610000 147826763 0 402718720 3.8235936165 4.0129384995 3.9122552872 3251 1311867827.0995759964 0.1435283422 0.1262424367 0.2390826792 0.0050751841 0.5402740000 0.0856270000 0.0776110000 0.0310830000 0.3363440000 0.0016740000 147830379 0 402718720 3.8238370419 4.0134491920 3.9118893147 3252 1311867827.1319890022 0.1430342793 0.1262476003 0.2390826792 0.0050746518 0.4911430000 0.0673700000 0.0777180000 0.0000000000 0.3364850000 0.0016560000 147833883 0 402718720 3.8243982792 4.0137205124 3.9117381573 3253 1311867827.1636219025 0.1414975822 0.1262522882 0.2390826792 0.0050749107 0.8581200000 0.0861660000 0.0397240000 0.0315380000 0.3367370000 0.3560150000 147837611 0 402718720 3.8260035515 4.0136737823 3.9113368988 3254 1311867827.2006959915 0.1444859356 0.1262578917 0.2390826792 0.0050775327 0.4765130000 0.0679880000 0.0622690000 0.0000010000 0.3365630000 0.0016770000 147841395 0 402718720 3.8231666088 4.0124235153 3.9110484123 3255 1311867827.2315700054 0.1432934254 0.1262631253 0.2390826792 0.0050768209 0.5411330000 0.0783830000 0.0773570000 0.0315540000 0.3428800000 0.0021910000 147844955 0 402718720 3.8245742321 4.0136690140 3.9106833935 3256 1311867827.2656030655 0.1433872730 0.1262683846 0.2390826792 0.0050762029 0.4753830000 0.0848950000 0.0432150000 0.0000010000 0.3376830000 0.0016570000 147848515 0 402718720 3.8246347904 4.0135536194 3.9102544785 3257 1311867827.2999110222 0.1446565539 0.1262740303 0.2390826792 0.0050762511 0.8395150000 0.0671410000 0.0413730000 0.0311650000 0.3343520000 0.3574880000 147852299 0 402718720 3.8232154846 4.0131087303 3.9106152058 3258 1311867827.3331999779 0.1437775940 0.1262794028 0.2390826792 0.0050757281 0.4777150000 0.0912530000 0.0417640000 0.0000010000 0.3350170000 0.0016650000 147855915 0 402718720 3.8239085674 4.0153698921 3.9107365608 3259 1311867827.3665180206 0.1435522884 0.1262847029 0.2390826792 0.0050750353 0.5227390000 0.0668980000 0.0772790000 0.0315320000 0.3373110000 0.0016590000 147859587 0 402718720 3.8240518570 4.0148615837 3.9105100632 3260 1311867827.4023349285 0.1425480545 0.1262896916 0.2390826792 0.0050757790 0.4924920000 0.0672590000 0.0816910000 0.0000000000 0.3338490000 0.0017250000 147863427 0 402718720 3.8252348900 4.0144152641 3.9104218483 3261 1311867827.4316511154 0.1435081363 0.1262949718 0.2390826792 0.0050756665 0.8420650000 0.0672810000 0.0415350000 0.0315820000 0.3367830000 0.3567970000 147866987 0 402718720 3.8241956234 4.0156927109 3.9108428955 3262 1311867827.4660930634 0.1426728219 0.1262999926 0.2390826792 0.0050750005 0.4950320000 0.0671660000 0.0818150000 0.0000010000 0.3362970000 0.0016580000 147870715 0 402718720 3.8248093128 4.0152459145 3.9103019238 3263 1311867827.5022308826 0.1419166476 0.1263047785 0.2390826792 0.0050760169 0.5081680000 0.0777960000 0.0551990000 0.0316040000 0.3335660000 0.0017610000 147874555 0 402718720 3.8256161213 4.0135059357 3.9098272324 3264 1311867827.5346870422 0.1428893209 0.1263098596 0.2390826792 0.0050765592 0.4930530000 0.0673940000 0.0782680000 0.0000010000 0.3377230000 0.0016550000 147878171 0 402718720 3.8244965076 4.0152440071 3.9102220535 3265 1311867827.5639040470 0.1425764412 0.1263148417 0.2390826792 0.0050760622 0.8517280000 0.0672000000 0.0416120000 0.0316070000 0.3353730000 0.3678890000 147881843 0 402718720 3.8246204853 4.0146274567 3.9098107815 3266 1311867827.6014358997 0.1434621811 0.1263200919 0.2390826792 0.0050761420 0.4920150000 0.0670030000 0.0776080000 0.0000000000 0.3377170000 0.0016560000 147885627 0 402718720 3.8238503933 4.0129899979 3.9096410275 3267 1311867827.6328499317 0.1419631094 0.1263248801 0.2390826792 0.0050764406 0.5239960000 0.0671500000 0.0776520000 0.0315820000 0.3378920000 0.0016710000 147889299 0 402718720 3.8250958920 4.0149536133 3.9097969532 3268 1311867827.6636641026 0.1433532536 0.1263300908 0.2390826792 0.0050757575 0.4628680000 0.0772780000 0.0413430000 0.0000000000 0.3345440000 0.0016680000 147892971 0 402718720 3.8234257698 4.0153131485 3.9100620747 3269 1311867827.7023649216 0.1430861950 0.1263352165 0.2390826792 0.0050753794 0.8781620000 0.0676210000 0.0762150000 0.0315860000 0.3375780000 0.3571230000 147896811 0 402718720 3.8240182400 4.0140891075 3.9101939201 3270 1311867827.7343521118 0.1421839744 0.1263400632 0.2390826792 0.0050754155 0.4473020000 0.0670330000 0.0331460000 0.0000010000 0.3374440000 0.0016630000 147900483 0 402718720 3.8248541355 4.0148882866 3.9103093147 3271 1311867827.7669301033 0.1405647397 0.1263444120 0.2390826792 0.0050777903 0.5460740000 0.0866580000 0.0810690000 0.0316290000 0.3370210000 0.0016730000 147904099 0 402718720 3.8261973858 4.0154156685 3.9101569653 3272 1311867827.8077390194 0.1421425641 0.1263492403 0.2390826792 0.0050780968 0.4801070000 0.0679910000 0.0652330000 0.0000010000 0.3371370000 0.0016670000 147908051 0 402718720 3.8246037960 4.0140395164 3.9105675220 3273 1311867827.8316879272 0.1423728466 0.1263541360 0.2390826792 0.0050781006 0.8726370000 0.0802460000 0.0590940000 0.0315010000 0.3371520000 0.3565950000 147911443 0 402718720 3.8244125843 4.0144176483 3.9107248783 3274 1311867827.8644089699 0.1409239471 0.1263585861 0.2390826792 0.0050775981 0.4930600000 0.0675180000 0.0818690000 0.0000000000 0.3340080000 0.0016680000 147915227 0 402718720 3.8258793354 4.0144839287 3.9104731083 3275 1311867827.9007999897 0.1426354051 0.1263635561 0.2390826792 0.0050790313 0.5201960000 0.0673620000 0.0745680000 0.0315490000 0.3369860000 0.0016670000 147918899 0 402718720 3.8243937492 4.0131673813 3.9105880260 3276 1311867827.9316790104 0.1418213397 0.1263682746 0.2390826792 0.0050802436 0.4904880000 0.0673210000 0.0761260000 0.0000000000 0.3373790000 0.0016600000 147922571 0 402718720 3.8247990608 4.0139794350 3.9106910229 3277 1311867827.9717168808 0.1435725689 0.1263735246 0.2390826792 0.0050836156 0.8706500000 0.0675280000 0.0698440000 0.0315880000 0.3370890000 0.3565190000 147926411 0 402718720 3.8232800961 4.0137119293 3.9110066891 3278 1311867827.9999699593 0.1418404579 0.1263782430 0.2390826792 0.0050837906 0.4831360000 0.0814960000 0.0549670000 0.0000010000 0.3369960000 0.0016560000 147930083 0 402718720 3.8249111176 4.0125603676 3.9103066921 3279 1311867828.0320069790 0.1431064457 0.1263833447 0.2390826792 0.0050840140 0.4921700000 0.0672290000 0.0457190000 0.0316040000 0.3377420000 0.0016620000 147933699 0 402718720 3.8236787319 4.0140905380 3.9106783867 3280 1311867828.0711700916 0.1425498128 0.1263882735 0.2390826792 0.0050856394 0.4541850000 0.0673500000 0.0394380000 0.0000000000 0.3376930000 0.0016650000 147937539 0 402718720 3.8239960670 4.0137972832 3.9106941223 3281 1311867828.1003229618 0.1425740123 0.1263932066 0.2390826792 0.0050849867 0.8517960000 0.0669420000 0.0504860000 0.0315260000 0.3375240000 0.3571990000 147941211 0 402718720 3.8240618706 4.0128674507 3.9106736183 3282 1311867828.1317639351 0.1428434402 0.1263982189 0.2390826792 0.0050865158 0.4920900000 0.0669500000 0.0774710000 0.0000010000 0.3379560000 0.0016510000 147944827 0 402718720 3.8240900040 4.0134081841 3.9111068249 3283 1311867828.1714239120 0.1449169517 0.1264038597 0.2390826792 0.0050869069 0.5207400000 0.0770120000 0.0648080000 0.0315880000 0.3376080000 0.0016730000 147948723 0 402718720 3.8217589855 4.0139365196 3.9111175537 3284 1311867828.2080869675 0.1428571939 0.1264088698 0.2390826792 0.0050913806 0.4539420000 0.0672420000 0.0393740000 0.0000000000 0.3376290000 0.0016530000 147952563 0 402718720 3.8243236542 4.0137147903 3.9109890461 3285 1311867828.2316999435 0.1427834630 0.1264138545 0.2390826792 0.0050918406 0.8658850000 0.0667580000 0.0584560000 0.0314800000 0.3373090000 0.3628610000 147955955 0 402718720 3.8243567944 4.0140166283 3.9114558697 3286 1311867828.2725389004 0.1416774690 0.1264184995 0.2390826792 0.0050912011 0.4854010000 0.0850660000 0.0524090000 0.0000010000 0.3382140000 0.0016580000 147959851 0 402718720 3.8255977631 4.0150456429 3.9115421772 3287 1311867828.3008439541 0.1427197754 0.1264234589 0.2390826792 0.0050908321 0.5217050000 0.0673280000 0.0761100000 0.0315340000 0.3370380000 0.0016650000 147963467 0 402718720 3.8250031471 4.0126881599 3.9117484093 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 12:09:46 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520030 0.0582520030 0.0582520030 -nan 0.7671610000 0.1361400000 0.0225400000 0.0622050000 0.0000020000 0.5424510000 115668534 0 402718720 4.0000000000 4.0000000000 4.0000000000 2 1311867170.4941389561 0.0599970818 0.0591245424 0.0599970818 0.0035989983 0.2415170000 0.1545000000 0.0202990000 0.0621940000 0.0000000000 0.0036720000 134944323 0 402718720 4.0000000000 4.0000000000 4.0000000000 3 1311867170.5264289379 0.0615839623 0.0599443490 0.0615839623 0.0081929692 0.2358010000 0.1488750000 0.0203870000 0.0622540000 0.0000000000 0.0036360000 134948443 0 402718720 4.0000000000 4.0000000000 4.0000000000 4 1311867170.5623490810 0.0628964603 0.0606823768 0.0628964603 0.0105670472 0.7285100000 0.1294480000 0.0202240000 0.0622600000 0.5123120000 0.0036340000 134952627 0 402718720 4.0000000000 4.0000000000 4.0000000000 5 1311867170.5942170620 0.0609254539 0.0607309923 0.0628964603 0.0111247626 1.3290760000 0.1285090000 0.1051670000 0.0631140000 0.5076940000 0.5239610000 134956627 0 402718720 4.0031237602 3.9974741936 3.9970712662 6 1311867170.6260869503 0.0606057271 0.0607101147 0.0628964603 0.0110246615 0.4987190000 0.0753250000 0.0829770000 0.0000010000 0.3380460000 0.0017350000 134961099 0 402718720 4.0016193390 3.9956707954 3.9953823090 7 1311867170.6621398926 0.0602240376 0.0606406751 0.0628964603 0.0105575191 0.4949010000 0.0747070000 0.0558670000 0.0306620000 0.3312930000 0.0017340000 134964939 0 402718720 4.0018353462 3.9940981865 3.9936187267 8 1311867170.6942050457 0.0600374378 0.0605652705 0.0628964603 0.0100582606 0.5063580000 0.0871030000 0.0836970000 0.0000010000 0.3331880000 0.0017270000 134968555 0 402718720 4.0011496544 3.9931437969 3.9919633865 9 1311867170.7263879776 0.0608408414 0.0605958895 0.0628964603 0.0100333745 0.8354920000 0.0731840000 0.0656840000 0.0305480000 0.3293460000 0.3360870000 134972995 0 402718720 4.0015754700 3.9936788082 3.9908602238 10 1311867170.7620189190 0.0603598244 0.0605722830 0.0628964603 0.0098643122 0.4947570000 0.0747610000 0.0835380000 0.0000000000 0.3340860000 0.0017290000 134978435 0 402718720 3.9995038509 3.9909117222 3.9892885685 11 1311867170.7941920757 0.0607234947 0.0605860295 0.0628964603 0.0096817732 0.5029160000 0.0875650000 0.0515980000 0.0304890000 0.3308760000 0.0017400000 134981995 0 402718720 4.0003848076 3.9889507294 3.9876785278 12 1311867170.8262820244 0.0612697341 0.0606430049 0.0628964603 0.0096081845 0.4772540000 0.0743180000 0.0702420000 0.0000010000 0.3303200000 0.0017260000 134985723 0 402718720 4.0014481544 3.9856200218 3.9859521389 13 1311867170.8622210026 0.0614301339 0.0607035533 0.0628964603 0.0096879169 0.8481100000 0.0736080000 0.0830120000 0.0306670000 0.3263510000 0.3338260000 134989507 0 402718720 4.0042462349 3.9817702770 3.9834048748 14 1311867170.8943779469 0.0618294664 0.0607839756 0.0628964603 0.0094070636 0.4485530000 0.0730560000 0.0476330000 0.0000010000 0.3254920000 0.0017200000 134993123 0 402718720 4.0020446777 3.9801132679 3.9812369347 15 1311867170.9263520241 0.0620392002 0.0608676573 0.0628964603 0.0093892339 0.4831690000 0.0721740000 0.0552190000 0.0306840000 0.3227310000 0.0017070000 134996851 0 402718720 4.0027909279 3.9772715569 3.9783899784 16 1311867170.9621469975 0.0615631305 0.0609111243 0.0628964603 0.0091747880 0.4551220000 0.0716010000 0.0552060000 0.0000010000 0.3259580000 0.0017020000 135000635 0 402718720 4.0006065369 3.9752995968 3.9754085541 17 1311867170.9942629337 0.0615480766 0.0609485921 0.0628964603 0.0090199975 0.8348440000 0.0833710000 0.0549390000 0.0307510000 0.3283080000 0.3368170000 135005787 0 402718720 3.9983270168 3.9747209549 3.9725210667 18 1311867171.0262739658 0.0615851060 0.0609839540 0.0628964603 0.0087685231 0.4987230000 0.0837890000 0.0811680000 0.0000010000 0.3314190000 0.0016870000 135012715 0 402718720 3.9982266426 3.9730975628 3.9697549343 19 1311867171.0623519421 0.0607634597 0.0609723490 0.0628964603 0.0091383784 0.4854120000 0.0700080000 0.0476870000 0.0307850000 0.3345750000 0.0016920000 135016499 0 402718720 3.9972686768 3.9699757099 3.9667017460 20 1311867171.0942349434 0.0605198704 0.0609497251 0.0628964603 0.0090707242 0.4629390000 0.0691830000 0.0567340000 0.0000000000 0.3346690000 0.0016900000 135020115 0 402718720 3.9972779751 3.9690647125 3.9645526409 21 1311867171.1262509823 0.0605362430 0.0609300355 0.0628964603 0.0089262250 0.8877770000 0.0880150000 0.0769960000 0.0308290000 0.3353350000 0.3559400000 135023843 0 402718720 3.9977841377 3.9692537785 3.9624035358 22 1311867171.1622469425 0.0602449514 0.0608988953 0.0628964603 0.0088230217 0.4730630000 0.0688210000 0.0606470000 0.0000010000 0.3411940000 0.0016820000 135027627 0 402718720 3.9996716976 3.9667243958 3.9608962536 23 1311867171.1942689419 0.0591667853 0.0608235862 0.0628964603 0.0090509939 0.4947030000 0.0666460000 0.0555840000 0.0305890000 0.3395400000 0.0016750000 135031243 0 402718720 4.0014810562 3.9671690464 3.9596321583 24 1311867171.2262530327 0.0610351041 0.0608323994 0.0628964603 0.0090323727 0.4659400000 0.0675740000 0.0528690000 0.0000010000 0.3431580000 0.0016690000 135034971 0 402718720 4.0051183701 3.9670653343 3.9591295719 25 1311867171.2622439861 0.0604288056 0.0608162557 0.0628964603 0.0090271019 0.8412310000 0.0677820000 0.0465410000 0.0307050000 0.3423500000 0.3531840000 135038755 0 402718720 4.0062818527 3.9663743973 3.9580392838 26 1311867171.2943410873 0.0607743300 0.0608146431 0.0628964603 0.0090315593 0.4790800000 0.0683720000 0.0667860000 0.0000010000 0.3415690000 0.0016790000 135042315 0 402718720 4.0050153732 3.9689991474 3.9576382637 27 1311867171.3263869286 0.0610768870 0.0608243559 0.0628964603 0.0092675705 0.4882840000 0.0677190000 0.0471850000 0.0306260000 0.3403900000 0.0016880000 135046043 0 402718720 4.0013971329 3.9707107544 3.9562118053 28 1311867171.3622460365 0.0606455319 0.0608179693 0.0628964603 0.0091349784 0.5032230000 0.0919570000 0.0713160000 0.0000000000 0.3375700000 0.0016940000 135049827 0 402718720 3.9982872009 3.9719960690 3.9549028873 29 1311867171.3941431046 0.0616783872 0.0608476389 0.0628964603 0.0093291279 0.8305410000 0.0705400000 0.0545180000 0.0308980000 0.3324500000 0.3414520000 135053443 0 402718720 3.9963989258 3.9747509956 3.9538214207 30 1311867171.4262878895 0.0624619760 0.0609014501 0.0628964603 0.0092872366 0.4581050000 0.0706500000 0.0547070000 0.0000010000 0.3303720000 0.0016940000 135057171 0 402718720 3.9952247143 3.9750373363 3.9522821903 31 1311867171.4622440338 0.0615452044 0.0609222164 0.0628964603 0.0092250545 0.5180860000 0.0944950000 0.0547320000 0.0308410000 0.3350560000 0.0022670000 135060955 0 402718720 3.9949316978 3.9722235203 3.9500675201 32 1311867171.4944040775 0.0617169328 0.0609470513 0.0628964603 0.0091430777 0.4849830000 0.0890350000 0.0547430000 0.0000010000 0.3388340000 0.0016870000 135064571 0 402718720 3.9956281185 3.9733457565 3.9481205940 33 1311867171.5261778831 0.0612874143 0.0609573653 0.0628964603 0.0090020855 0.8704140000 0.0840450000 0.0808080000 0.0309010000 0.3325400000 0.3414290000 135071371 0 402718720 3.9946570396 3.9734251499 3.9461150169 34 1311867171.5622971058 0.0606258214 0.0609476140 0.0628964603 0.0088675766 0.4548800000 0.0700280000 0.0477940000 0.0000010000 0.3346750000 0.0016960000 135081555 0 402718720 3.9948871136 3.9731507301 3.9447321892 35 1311867171.5942931175 0.0608296581 0.0609442438 0.0628964603 0.0088019152 0.5148230000 0.0702170000 0.0783390000 0.0309800000 0.3329010000 0.0016970000 135085171 0 402718720 3.9961781502 3.9744794369 3.9438004494 36 1311867171.6263399124 0.0606495552 0.0609360580 0.0628964603 0.0087050660 0.4880910000 0.0820180000 0.0681100000 0.0000000000 0.3355690000 0.0017040000 135088899 0 402718720 3.9952914715 3.9733269215 3.9432115555 37 1311867171.6622560024 0.0605875328 0.0609266384 0.0628964603 0.0086047873 0.8364100000 0.0700560000 0.0546400000 0.0307810000 0.3355410000 0.3447010000 135092683 0 402718720 3.9916207790 3.9727840424 3.9424440861 38 1311867171.6943440437 0.0612240024 0.0609344638 0.0628964603 0.0087752029 0.4765200000 0.0828020000 0.0544780000 0.0000010000 0.3368510000 0.0016920000 135096299 0 402718720 3.9922981262 3.9735455513 3.9422595501 39 1311867171.7262439728 0.0611811914 0.0609407902 0.0628964603 0.0086879500 0.5107350000 0.0699920000 0.0713700000 0.0309910000 0.3359940000 0.0016940000 135100027 0 402718720 3.9922752380 3.9729049206 3.9418625832 40 1311867171.7621190548 0.0614369810 0.0609531949 0.0628964603 0.0086003313 0.4592950000 0.0698530000 0.0478520000 0.0000000000 0.3392060000 0.0016890000 135103811 0 402718720 3.9937415123 3.9712727070 3.9414770603 41 1311867171.7941710949 0.0609953254 0.0609542225 0.0628964603 0.0085939177 0.8918060000 0.0836570000 0.0852620000 0.0309730000 0.3397530000 0.3514670000 135107427 0 402718720 3.9931578636 3.9692935944 3.9404470921 42 1311867171.8262550831 0.0613957383 0.0609647348 0.0628964603 0.0085136184 0.4917640000 0.0677640000 0.0791800000 0.0000010000 0.3424500000 0.0016680000 135111155 0 402718720 3.9929246902 3.9690442085 3.9393177032 43 1311867171.8623590469 0.0609215237 0.0609637299 0.0628964603 0.0084172947 0.5152630000 0.0857250000 0.0533020000 0.0310260000 0.3428310000 0.0016710000 135114939 0 402718720 3.9888491631 3.9687507153 3.9379613400 44 1311867171.8944430351 0.0605714731 0.0609548149 0.0628964603 0.0085269904 0.4739380000 0.0682590000 0.0631810000 0.0000000000 0.3401160000 0.0016760000 135118611 0 402718720 3.9858469963 3.9683239460 3.9371433258 45 1311867171.9262220860 0.0615002029 0.0609669347 0.0628964603 0.0084617330 0.8505570000 0.0665270000 0.0485240000 0.0308010000 0.3396960000 0.3643120000 135122283 0 402718720 3.9849133492 3.9696893692 3.9368989468 46 1311867171.9624669552 0.0616448484 0.0609816719 0.0628964603 0.0084032177 0.4911280000 0.0680990000 0.0792110000 0.0000010000 0.3414360000 0.0016770000 135126067 0 402718720 3.9828624725 3.9694271088 3.9368638992 47 1311867171.9946711063 0.0619914383 0.0610031563 0.0628964603 0.0084647418 0.4918240000 0.0683150000 0.0531430000 0.0305530000 0.3374170000 0.0016890000 135129739 0 402718720 3.9826257229 3.9692704678 3.9370517731 48 1311867172.0262680054 0.0626867786 0.0610382318 0.0628964603 0.0085242849 0.4770440000 0.0785940000 0.0597460000 0.0000010000 0.3362980000 0.0016910000 135133411 0 402718720 3.9832251072 3.9691407681 3.9375021458 49 1311867172.0622880459 0.0630711839 0.0610797206 0.0630711839 0.0084654600 0.8596750000 0.0685770000 0.0790520000 0.0305360000 0.3348020000 0.3460000000 135137195 0 402718720 3.9815528393 3.9699547291 3.9382374287 50 1311867172.0941960812 0.0632806867 0.0611237399 0.0632806867 0.0084488614 0.4599540000 0.0693910000 0.0534620000 0.0000010000 0.3346880000 0.0016940000 135140867 0 402718720 3.9808065891 3.9696650505 3.9387931824 51 1311867172.1263689995 0.0637469441 0.0611751753 0.0637469441 0.0084526812 0.5109900000 0.0900950000 0.0565480000 0.0305380000 0.3313780000 0.0017050000 135144539 0 402718720 3.9779822826 3.9700479507 3.9398071766 52 1311867172.1623349190 0.0626347587 0.0612032442 0.0637469441 0.0084113241 0.4792740000 0.0820210000 0.0605520000 0.0000010000 0.3342800000 0.0017000000 135148323 0 402718720 3.9731318951 3.9699699879 3.9401979446 53 1311867172.1944270134 0.0616226606 0.0612111577 0.0637469441 0.0083616701 0.8656140000 0.0936340000 0.0693350000 0.0308870000 0.3300960000 0.3409450000 135151995 0 402718720 3.9676198959 3.9710314274 3.9405732155 54 1311867172.2264409065 0.0615652874 0.0612177157 0.0637469441 0.0085122650 0.4838600000 0.0698420000 0.0798930000 0.0000000000 0.3316950000 0.0017050000 135155667 0 402718720 3.9636113644 3.9709122181 3.9409599304 55 1311867172.2622280121 0.0611544251 0.0612165650 0.0637469441 0.0084435239 0.5088400000 0.0699570000 0.0795000000 0.0304820000 0.3264710000 0.0017020000 135159451 0 402718720 3.9609465599 3.9717447758 3.9413595200 56 1311867172.2944829464 0.0612875074 0.0612178318 0.0637469441 0.0083824087 0.4607010000 0.0700800000 0.0600910000 0.0000010000 0.3281030000 0.0016990000 135163123 0 402718720 3.9581696987 3.9725751877 3.9417634010 57 1311867172.3263380527 0.0609406643 0.0612129692 0.0637469441 0.0083566107 0.8459760000 0.0705900000 0.0799320000 0.0310090000 0.3266810000 0.3370440000 135166795 0 402718720 3.9552729130 3.9723401070 3.9422793388 58 1311867172.3624010086 0.0610912852 0.0612108712 0.0637469441 0.0083044261 0.4693240000 0.0832970000 0.0571390000 0.0000010000 0.3264480000 0.0017130000 135170579 0 402718720 3.9515480995 3.9734477997 3.9424512386 59 1311867172.3942890167 0.0597912669 0.0611868101 0.0637469441 0.0082449281 0.5059800000 0.0704590000 0.0738230000 0.0309200000 0.3283480000 0.0017030000 135174251 0 402718720 3.9468121529 3.9733533859 3.9422540665 60 1311867172.4265220165 0.0596389249 0.0611610120 0.0637469441 0.0082958194 0.4879890000 0.0707900000 0.0854460000 0.0000010000 0.3291100000 0.0018470000 135177923 0 402718720 3.9417486191 3.9735667706 3.9417977333 61 1311867172.4623498917 0.0590962954 0.0611271642 0.0637469441 0.0082724948 0.8527600000 0.0712490000 0.0852760000 0.0310440000 0.3269420000 0.3375230000 135181707 0 402718720 3.9383955002 3.9728329182 3.9413549900 62 1311867172.4952669144 0.0595682748 0.0611020208 0.0637469441 0.0083123657 0.4501340000 0.0708980000 0.0502200000 0.0000010000 0.3265640000 0.0017140000 135185323 0 402718720 3.9374089241 3.9733476639 3.9412446022 63 1311867172.5263059139 0.0592369586 0.0610724167 0.0637469441 0.0082594688 0.5013780000 0.0869760000 0.0543490000 0.0310050000 0.3265920000 0.0017180000 135188995 0 402718720 3.9349281788 3.9717228413 3.9406466484 64 1311867172.5624930859 0.0588575192 0.0610378089 0.0637469441 0.0082091426 0.4621840000 0.0717750000 0.0611620000 0.0000010000 0.3267850000 0.0017230000 135192779 0 402718720 3.9306592941 3.9709348679 3.9400806427 65 1311867172.5945439339 0.0596703328 0.0610167708 0.0637469441 0.0082139278 0.8508800000 0.0707910000 0.0805990000 0.0310130000 0.3284180000 0.3393260000 135202539 0 402718720 3.9334509373 3.9711201191 3.9393548965 66 1311867172.6263699532 0.0593938157 0.0609921806 0.0637469441 0.0081871783 0.4801300000 0.0697220000 0.0781160000 0.0000010000 0.3298320000 0.0017190000 135219067 0 402718720 3.9304628372 3.9711413383 3.9385628700 67 1311867172.6624419689 0.0592249595 0.0609658041 0.0637469441 0.0081290461 0.4837370000 0.0712830000 0.0476150000 0.0310200000 0.3313610000 0.0017170000 135222851 0 402718720 3.9275436401 3.9713344574 3.9379849434 68 1311867172.6945450306 0.0590749383 0.0609379973 0.0637469441 0.0081937832 0.5016160000 0.0848130000 0.0809950000 0.0000010000 0.3333490000 0.0017110000 135226523 0 402718720 3.9258878231 3.9711589813 3.9375181198 69 1311867172.7263929844 0.0594225004 0.0609160336 0.0637469441 0.0081660281 0.8582010000 0.0712880000 0.0854810000 0.0311020000 0.3290500000 0.3405550000 135230195 0 402718720 3.9233992100 3.9712169170 3.9371740818 70 1311867172.7623739243 0.0597462542 0.0608993224 0.0637469441 0.0081238212 0.4876370000 0.0719100000 0.0818330000 0.0000010000 0.3314230000 0.0017200000 135233979 0 402718720 3.9207248688 3.9725005627 3.9369585514 71 1311867172.7944509983 0.0589746125 0.0608722138 0.0637469441 0.0080715074 0.5372380000 0.0983970000 0.0755010000 0.0310740000 0.3297750000 0.0017350000 135237595 0 402718720 3.9160556793 3.9716851711 3.9363920689 72 1311867172.8263089657 0.0594248176 0.0608521111 0.0637469441 0.0080356065 0.4698380000 0.0728080000 0.0621830000 0.0000010000 0.3323660000 0.0017290000 135241323 0 402718720 3.9132173061 3.9718499184 3.9354975224 73 1311867172.8632309437 0.0593112186 0.0608310030 0.0637469441 0.0080000219 0.8716070000 0.0962240000 0.0824000000 0.0310930000 0.3253860000 0.3357640000 135245163 0 402718720 3.9104607105 3.9712779522 3.9346868992 74 1311867172.8944649696 0.0586127415 0.0608010265 0.0637469441 0.0079460149 0.4862950000 0.0723070000 0.0867140000 0.0000010000 0.3246240000 0.0018340000 135248723 0 402718720 3.9072182178 3.9710354805 3.9340174198 75 1311867172.9263219833 0.0582556129 0.0607670876 0.0637469441 0.0078930918 0.4735660000 0.0727630000 0.0418080000 0.0310910000 0.3254030000 0.0017360000 135252451 0 402718720 3.9041082859 3.9702184200 3.9334328175 76 1311867172.9623310566 0.0580810681 0.0607317453 0.0637469441 0.0078415702 0.4708540000 0.0727480000 0.0553600000 0.0000000000 0.3396530000 0.0023200000 135256235 0 402718720 3.9026079178 3.9699063301 3.9327480793 77 1311867172.9945271015 0.0584517792 0.0607021353 0.0637469441 0.0078180995 0.8671370000 0.0891810000 0.0814660000 0.0311220000 0.3268300000 0.3377880000 135259851 0 402718720 3.9039728642 3.9697577953 3.9322259426 78 1311867173.0262629986 0.0575001538 0.0606610843 0.0637469441 0.0077803305 0.4585490000 0.0798690000 0.0486120000 0.0000010000 0.3275890000 0.0017180000 135263523 0 402718720 3.8992040157 3.9692907333 3.9320387840 79 1311867173.0624630451 0.0575767159 0.0606220416 0.0637469441 0.0077347405 0.5142870000 0.0723090000 0.0824020000 0.0311030000 0.3259720000 0.0017340000 135267307 0 402718720 3.8990514278 3.9688019753 3.9317142963 80 1311867173.0945179462 0.0580034256 0.0605893089 0.0637469441 0.0077177453 0.4557190000 0.0718440000 0.0550730000 0.0000010000 0.3263180000 0.0017200000 135270979 0 402718720 3.8984487057 3.9687492847 3.9317653179 81 1311867173.1267819405 0.0577783994 0.0605546064 0.0637469441 0.0076897959 0.8658040000 0.0934600000 0.0823900000 0.0306410000 0.3239090000 0.3346410000 135274707 0 402718720 3.8967065811 3.9687879086 3.9315228462 82 1311867173.1622309685 0.0581945777 0.0605258255 0.0637469441 0.0076775798 0.4573060000 0.0724910000 0.0582570000 0.0000010000 0.3240530000 0.0017420000 135278491 0 402718720 3.8968060017 3.9698088169 3.9316098690 83 1311867173.1943008900 0.0585979111 0.0605025976 0.0637469441 0.0076315094 0.5226570000 0.0844300000 0.0822200000 0.0306630000 0.3228500000 0.0017250000 135282107 0 402718720 3.8961322308 3.9703478813 3.9316933155 84 1311867173.2264449596 0.0575894937 0.0604679178 0.0637469441 0.0075919314 0.4766370000 0.0714910000 0.0792890000 0.0000010000 0.3233540000 0.0017350000 135285779 0 402718720 3.8910257816 3.9698305130 3.9317324162 85 1311867173.2622020245 0.0588815510 0.0604492547 0.0637469441 0.0075516066 0.8434130000 0.0726680000 0.0824140000 0.0310810000 0.3226680000 0.3338110000 135289563 0 402718720 3.8930788040 3.9705748558 3.9319703579 86 1311867173.2942678928 0.0589430779 0.0604317410 0.0637469441 0.0075077236 0.5326190000 0.0824550000 0.1098500000 0.0000010000 0.3371950000 0.0023290000 135293179 0 402718720 3.8907363415 3.9703912735 3.9320094585 87 1311867173.3262879848 0.0585477203 0.0604100856 0.0637469441 0.0075122697 0.5122150000 0.0745860000 0.0830290000 0.0312450000 0.3208310000 0.0017500000 135296851 0 402718720 3.8876938820 3.9691035748 3.9320142269 88 1311867173.3623280525 0.0585131869 0.0603885299 0.0637469441 0.0074696069 0.4759120000 0.0890080000 0.0629480000 0.0000000000 0.3214080000 0.0017680000 135300691 0 402718720 3.8852221966 3.9691100121 3.9319067001 89 1311867173.3942871094 0.0580506921 0.0603622621 0.0637469441 0.0074377844 0.8368170000 0.0722710000 0.0827960000 0.0309440000 0.3197540000 0.3302800000 135304307 0 402718720 3.8819086552 3.9692668915 3.9317800999 90 1311867173.4262790680 0.0577734485 0.0603334975 0.0637469441 0.0074210083 0.4454350000 0.0737460000 0.0493210000 0.0000000000 0.3198460000 0.0017420000 135307979 0 402718720 3.8796904087 3.9691488743 3.9314885139 91 1311867173.4622900486 0.0571745597 0.0602987839 0.0637469441 0.0074081655 0.5382510000 0.0973460000 0.0883490000 0.0311700000 0.3188460000 0.0017510000 135311763 0 402718720 3.8768019676 3.9686441422 3.9310550690 92 1311867173.4943389893 0.0578968525 0.0602726759 0.0637469441 0.0074702971 0.4792090000 0.0732380000 0.0834820000 0.0000010000 0.3199730000 0.0017410000 135315435 0 402718720 3.8756136894 3.9682314396 3.9305777550 93 1311867173.5263900757 0.0576131456 0.0602440788 0.0637469441 0.0074321525 0.8614170000 0.0850070000 0.0829750000 0.0311780000 0.3289380000 0.3325430000 135319163 0 402718720 3.8733634949 3.9677751064 3.9301297665 94 1311867173.5624370575 0.0574038588 0.0602138637 0.0637469441 0.0074115336 0.4788880000 0.0734220000 0.0807300000 0.0000010000 0.3216150000 0.0023210000 135322947 0 402718720 3.8714349270 3.9680187702 3.9299719334 95 1311867173.5943109989 0.0575281680 0.0601855932 0.0637469441 0.0073974161 0.5203040000 0.0935670000 0.0654140000 0.0379430000 0.3208260000 0.0017520000 135326563 0 402718720 3.8692054749 3.9681923389 3.9296619892 96 1311867173.6263959408 0.0565075912 0.0601472807 0.0637469441 0.0073703373 0.4581550000 0.0738770000 0.0632680000 0.0000010000 0.3184790000 0.0017450000 135330235 0 402718720 3.8650805950 3.9674692154 3.9291522503 97 1311867173.6623299122 0.0573230945 0.0601181654 0.0637469441 0.0073375033 0.8449070000 0.0807610000 0.0832270000 0.0306730000 0.3189840000 0.3304800000 135334019 0 402718720 3.8655457497 3.9680950642 3.9287490845 98 1311867173.6943540573 0.0578699373 0.0600952243 0.0637469441 0.0073032488 0.4451620000 0.0831770000 0.0402660000 0.0000000000 0.3191890000 0.0017310000 135337691 0 402718720 3.8649833202 3.9680914879 3.9283356667 99 1311867173.7267971039 0.0568722114 0.0600626686 0.0637469441 0.0073024940 0.4858250000 0.0725650000 0.0625130000 0.0307020000 0.3175130000 0.0017440000 135341419 0 402718720 3.8597850800 3.9674172401 3.9273881912 100 1311867173.7623970509 0.0573922023 0.0600359640 0.0637469441 0.0072788012 0.4756020000 0.0726980000 0.0828720000 0.0000010000 0.3175030000 0.0017370000 135345203 0 402718720 3.8597826958 3.9679677486 3.9268703461 101 1311867173.7943561077 0.0578552634 0.0600143729 0.0637469441 0.0072462507 0.8536720000 0.0954930000 0.0829310000 0.0311840000 0.3159760000 0.3272960000 135348763 0 402718720 3.8591933250 3.9682595730 3.9263722897 102 1311867173.8265669346 0.0571391396 0.0599861843 0.0637469441 0.0072132337 0.4781410000 0.0726910000 0.0873510000 0.0000010000 0.3155610000 0.0017410000 135352491 0 402718720 3.8561995029 3.9667584896 3.9253540039 103 1311867173.8635799885 0.0576803908 0.0599637980 0.0637469441 0.0072110686 0.4963390000 0.0726110000 0.0757840000 0.0306890000 0.3147240000 0.0017390000 135356219 0 402718720 3.8541653156 3.9677753448 3.9248914719 104 1311867173.8946080208 0.0578880198 0.0599438385 0.0637469441 0.0071797457 0.4783350000 0.0728670000 0.0874840000 0.0000010000 0.3154400000 0.0017490000 135359891 0 402718720 3.8540165424 3.9673633575 3.9240953922 105 1311867173.9266970158 0.0567989387 0.0599138871 0.0637469441 0.0071529542 0.8165530000 0.0733570000 0.0701470000 0.0311730000 0.3149350000 0.3261530000 135363619 0 402718720 3.8499324322 3.9669039249 3.9229736328 106 1311867173.9625461102 0.0570386276 0.0598867620 0.0637469441 0.0071554246 0.4690650000 0.0732450000 0.0770120000 0.0000010000 0.3162620000 0.0017520000 135367403 0 402718720 3.8479146957 3.9680995941 3.9225738049 107 1311867173.9944310188 0.0576345064 0.0598657129 0.0637469441 0.0071407514 0.4849480000 0.0720500000 0.0622660000 0.0311520000 0.3169420000 0.0017370000 135371019 0 402718720 3.8491160870 3.9683060646 3.9220285416 108 1311867174.0264260769 0.0566554628 0.0598359884 0.0637469441 0.0072271322 0.4878740000 0.0826230000 0.0838240000 0.0000010000 0.3188670000 0.0017560000 135374691 0 402718720 3.8442797661 3.9667825699 3.9209291935 109 1311867174.0624630451 0.0573337227 0.0598130318 0.0637469441 0.0072002739 0.8231660000 0.0722820000 0.0727400000 0.0307480000 0.3165970000 0.3299940000 135378475 0 402718720 3.8458333015 3.9672751427 3.9204685688 110 1311867174.0945188999 0.0590763576 0.0598063348 0.0637469441 0.0071768062 0.4518650000 0.0729700000 0.0590310000 0.0000010000 0.3173030000 0.0017510000 135382147 0 402718720 3.8470559120 3.9684283733 3.9209206104 111 1311867174.1264541149 0.0584154166 0.0597938040 0.0637469441 0.0071597878 0.5258700000 0.0907730000 0.0824490000 0.0311660000 0.3189290000 0.0017410000 135385819 0 402718720 3.8438532352 3.9667170048 3.9200561047 112 1311867174.1624329090 0.0586539023 0.0597836263 0.0637469441 0.0071570470 0.4453060000 0.0733670000 0.0492110000 0.0000010000 0.3201790000 0.0017460000 135389603 0 402718720 3.8412170410 3.9674198627 3.9199416637 113 1311867174.1943979263 0.0595636964 0.0597816800 0.0637469441 0.0071445279 0.8522070000 0.0936210000 0.0842870000 0.0312730000 0.3152380000 0.3269710000 135393275 0 402718720 3.8418834209 3.9687528610 3.9202685356 114 1311867174.2267580032 0.0586755835 0.0597719774 0.0637469441 0.0071227716 0.4831810000 0.0743280000 0.0891250000 0.0000000000 0.3171540000 0.0017580000 135397003 0 402718720 3.8373532295 3.9668769836 3.9199261665 115 1311867174.2626769543 0.0587194562 0.0597628250 0.0637469441 0.0070918354 0.4743100000 0.0749500000 0.0501040000 0.0312770000 0.3153960000 0.0017690000 135400731 0 402718720 3.8347499371 3.9667646885 3.9197182655 116 1311867174.2945280075 0.0599219128 0.0597641965 0.0637469441 0.0070730831 0.4690420000 0.0749190000 0.0749870000 0.0000000000 0.3165230000 0.0017910000 135404403 0 402718720 3.8353037834 3.9675126076 3.9196155071 117 1311867174.3265740871 0.0585656464 0.0597539525 0.0637469441 0.0070455419 0.7876680000 0.0739210000 0.0426510000 0.0312240000 0.3138410000 0.3252320000 135408075 0 402718720 3.8305478096 3.9666688442 3.9187252522 118 1311867174.3624329567 0.0584296137 0.0597427293 0.0637469441 0.0070235446 0.4511010000 0.0849530000 0.0498820000 0.0000010000 0.3136850000 0.0017590000 135411915 0 402718720 3.8275368214 3.9675934315 3.9188864231 119 1311867174.3946359158 0.0590965301 0.0597372990 0.0637469441 0.0070232506 0.5080210000 0.0747230000 0.0847990000 0.0312500000 0.3146630000 0.0017680000 135415531 0 402718720 3.8267724514 3.9688401222 3.9190206528 120 1311867174.4266788960 0.0587156340 0.0597287851 0.0637469441 0.0070004000 0.4502700000 0.0745590000 0.0572220000 0.0000010000 0.3159020000 0.0017660000 135419259 0 402718720 3.8230996132 3.9683222771 3.9189841747 121 1311867174.4630160332 0.0581694059 0.0597158977 0.0637469441 0.0069886615 0.8387510000 0.0968590000 0.0761920000 0.0312920000 0.3105870000 0.3229980000 135422987 0 402718720 3.8201529980 3.9676673412 3.9187917709 122 1311867174.4945669174 0.0592743419 0.0597122784 0.0637469441 0.0069606645 0.4744790000 0.0745570000 0.0847950000 0.0000010000 0.3125350000 0.0017710000 135426659 0 402718720 3.8216099739 3.9686233997 3.9189510345 123 1311867174.5267519951 0.0586916581 0.0597039807 0.0637469441 0.0069454847 0.5111830000 0.0877660000 0.0776250000 0.0312530000 0.3119530000 0.0017640000 135430387 0 402718720 3.8183279037 3.9680209160 3.9187564850 124 1311867174.5623500347 0.0582921840 0.0596925952 0.0637469441 0.0069581803 0.4748900000 0.0747550000 0.0852910000 0.0000010000 0.3122430000 0.0017720000 135434171 0 402718720 3.8149938583 3.9674832821 3.9187805653 125 1311867174.5944879055 0.0586783886 0.0596844816 0.0637469441 0.0069513695 0.7957560000 0.0742870000 0.0526750000 0.0308490000 0.3124930000 0.3245830000 135437787 0 402718720 3.8146152496 3.9690151215 3.9190547466 126 1311867174.6265459061 0.0587642714 0.0596771783 0.0637469441 0.0069304994 0.4741100000 0.0741250000 0.0847970000 0.0000010000 0.3125980000 0.0017650000 135441459 0 402718720 3.8112998009 3.9694724083 3.9196131229 127 1311867174.6624910831 0.0581306182 0.0596650007 0.0637469441 0.0069094710 0.4792110000 0.0756930000 0.0575840000 0.0307790000 0.3125350000 0.0017920000 135445243 0 402718720 3.8074610233 3.9683790207 3.9196703434 128 1311867174.6945910454 0.0588043630 0.0596582769 0.0637469441 0.0069077061 0.4834190000 0.0823590000 0.0859540000 0.0000010000 0.3125040000 0.0017710000 135448915 0 402718720 3.8071885109 3.9702436924 3.9203341007 129 1311867174.7265629768 0.0591002330 0.0596539510 0.0637469441 0.0069138943 0.8090640000 0.0871220000 0.0573760000 0.0312340000 0.3101770000 0.3223290000 135464819 0 402718720 3.8038625717 3.9701852798 3.9207332134 130 1311867174.7623760700 0.0585926287 0.0596457870 0.0637469441 0.0069145667 0.4819730000 0.0894230000 0.0792370000 0.0000000000 0.3106820000 0.0017960000 135494259 0 402718720 3.7997357845 3.9672908783 3.9206657410 131 1311867174.7944738865 0.0588034131 0.0596393567 0.0637469441 0.0068901667 0.5275310000 0.0977110000 0.0776540000 0.0313220000 0.3176070000 0.0023720000 135497819 0 402718720 3.8008372784 3.9683418274 3.9202134609 132 1311867174.8273398876 0.0587678403 0.0596327543 0.0637469441 0.0068652773 0.4998830000 0.0937360000 0.0952700000 0.0000000000 0.3082830000 0.0017520000 135501547 0 402718720 3.7979822159 3.9676189423 3.9202287197 133 1311867174.8624229431 0.0576049127 0.0596175073 0.0637469441 0.0068437813 0.8105030000 0.0938000000 0.0569080000 0.0309300000 0.3080330000 0.3199950000 135505331 0 402718720 3.7948145866 3.9673080444 3.9190917015 134 1311867174.8944199085 0.0568429008 0.0595968013 0.0637469441 0.0068362296 0.4775250000 0.0743050000 0.0879640000 0.0000010000 0.3120120000 0.0023750000 135508947 0 402718720 3.7914805412 3.9691390991 3.9182188511 135 1311867174.9270179272 0.0568618700 0.0595765426 0.0637469441 0.0068292300 0.5567380000 0.0941100000 0.1116270000 0.0380980000 0.3102810000 0.0017660000 135512675 0 402718720 3.7907371521 3.9684138298 3.9177150726 136 1311867174.9626429081 0.0571472757 0.0595586803 0.0637469441 0.0068124163 0.4439850000 0.0741440000 0.0597270000 0.0000000000 0.3075070000 0.0017610000 135516459 0 402718720 3.7910611629 3.9681448936 3.9168725014 137 1311867174.9943349361 0.0565122776 0.0595364438 0.0637469441 0.0068228786 0.8091130000 0.0743290000 0.0821020000 0.0312830000 0.3039240000 0.3166300000 135520075 0 402718720 3.7862491608 3.9690179825 3.9163429737 138 1311867175.0265510082 0.0573625863 0.0595206912 0.0637469441 0.0068551480 0.4880270000 0.0873080000 0.0780850000 0.0000000000 0.3193880000 0.0023720000 135523803 0 402718720 3.7854006290 3.9726252556 3.9166324139 139 1311867175.0633120537 0.0569187775 0.0595019724 0.0637469441 0.0068317294 0.4878470000 0.0757770000 0.0713920000 0.0308380000 0.3071940000 0.0017830000 135527587 0 402718720 3.7811198235 3.9713499546 3.9166936874 140 1311867175.0947189331 0.0555999279 0.0594741007 0.0637469441 0.0068266929 0.4733410000 0.0751510000 0.0851680000 0.0000010000 0.3103840000 0.0017810000 135531259 0 402718720 3.7696895599 3.9731488228 3.9162039757 141 1311867175.1265308857 0.0559538417 0.0594491343 0.0637469441 0.0068139196 0.8460120000 0.0948220000 0.0845690000 0.0312780000 0.3085130000 0.3259720000 135534931 0 402718720 3.7717533112 3.9735226631 3.9168691635 142 1311867175.1625180244 0.0562344044 0.0594264953 0.0637469441 0.0068234020 0.4596070000 0.0745630000 0.0748950000 0.0000010000 0.3075210000 0.0017730000 135538715 0 402718720 3.7707953453 3.9732398987 3.9173135757 143 1311867175.1946399212 0.0561439320 0.0594035403 0.0637469441 0.0068032892 0.4798120000 0.0955540000 0.0429120000 0.0313420000 0.3073710000 0.0017780000 135542331 0 402718720 3.7686543465 3.9729697704 3.9174613953 144 1311867175.2270050049 0.0558291823 0.0593787184 0.0637469441 0.0068536993 0.4737410000 0.0744770000 0.0894880000 0.0000000000 0.3071420000 0.0017790000 135546059 0 402718720 3.7659621239 3.9745018482 3.9180850983 145 1311867175.2624669075 0.0559821427 0.0593552938 0.0637469441 0.0068615865 0.7952280000 0.0754900000 0.0647320000 0.0313450000 0.3052460000 0.3175640000 135549787 0 402718720 3.7664887905 3.9758243561 3.9181604385 146 1311867175.2944509983 0.0558710136 0.0593314288 0.0637469441 0.0068633287 0.4647310000 0.0758220000 0.0796560000 0.0000010000 0.3066010000 0.0017940000 135553459 0 402718720 3.7595198154 3.9758102894 3.9188106060 147 1311867175.3267059326 0.0557375811 0.0593069809 0.0637469441 0.0068416028 0.4990720000 0.0760540000 0.0861680000 0.0312760000 0.3029140000 0.0018010000 135557187 0 402718720 3.7616486549 3.9775395393 3.9195890427 148 1311867175.3625650406 0.0566606447 0.0592891002 0.0637469441 0.0068647150 0.4890930000 0.0917280000 0.0916930000 0.0000000000 0.3029930000 0.0018070000 135560915 0 402718720 3.7566633224 3.9765942097 3.9203991890 149 1311867175.3945989609 0.0564363748 0.0592699544 0.0637469441 0.0068565167 0.7716030000 0.0763160000 0.0505980000 0.0313160000 0.3002050000 0.3123080000 135564587 0 402718720 3.7568757534 3.9759213924 3.9204053879 150 1311867175.4266059399 0.0568197817 0.0592536199 0.0637469441 0.0068441726 0.4622710000 0.0762490000 0.0832660000 0.0000010000 0.3000930000 0.0017990000 135568259 0 402718720 3.7502298355 3.9772095680 3.9211091995 151 1311867175.4625999928 0.0565573983 0.0592357642 0.0637469441 0.0068382947 0.4934560000 0.0760110000 0.0859700000 0.0307800000 0.2980300000 0.0017960000 135572099 0 402718720 3.7487869263 3.9770541191 3.9212689400 152 1311867175.4945731163 0.0569831021 0.0592209440 0.0637469441 0.0068236235 0.4530180000 0.0996420000 0.0514160000 0.0000000000 0.2992440000 0.0018250000 135575771 0 402718720 3.7432720661 3.9771842957 3.9217331409 153 1311867175.5264270306 0.0577575006 0.0592113790 0.0637469441 0.0068262431 0.8157220000 0.0898720000 0.0864390000 0.0313010000 0.2977780000 0.3094580000 135579387 0 402718720 3.7387068272 3.9779558182 3.9220237732 154 1311867175.5625700951 0.0572501756 0.0591986439 0.0637469441 0.0068496900 0.4485040000 0.0759710000 0.0719450000 0.0000000000 0.2979160000 0.0017980000 135583227 0 402718720 3.7368700504 3.9784934521 3.9221723080 155 1311867175.5946640968 0.0581482723 0.0591918673 0.0637469441 0.0068826381 0.4973610000 0.0767370000 0.0916070000 0.0308580000 0.2954780000 0.0018080000 135586843 0 402718720 3.7348093987 3.9798743725 3.9225397110 156 1311867175.6264801025 0.0577096529 0.0591823660 0.0637469441 0.0068907726 0.4627790000 0.0766820000 0.0870460000 0.0000010000 0.2963610000 0.0018080000 135590515 0 402718720 3.7308800220 3.9798567295 3.9226903915 157 1311867175.6624929905 0.0585060567 0.0591780583 0.0637469441 0.0069476427 0.7621660000 0.0770080000 0.0540130000 0.0313540000 0.2937200000 0.3051310000 135594299 0 402718720 3.7309732437 3.9813976288 3.9231436253 158 1311867175.6947000027 0.0583286062 0.0591726820 0.0637469441 0.0069506380 0.4404480000 0.0875240000 0.0547780000 0.0000010000 0.2954400000 0.0018200000 135597971 0 402718720 3.7280888557 3.9804711342 3.9232318401 159 1311867175.7273120880 0.0588133857 0.0591704223 0.0637469441 0.0069399553 0.4740740000 0.0780680000 0.0678100000 0.0313530000 0.2941400000 0.0018290000 135601699 0 402718720 3.7256200314 3.9800281525 3.9235305786 160 1311867175.7624969482 0.0590040796 0.0591693826 0.0637469441 0.0069406406 0.4605020000 0.0767120000 0.0862130000 0.0000010000 0.2948820000 0.0018140000 135605483 0 402718720 3.7216143608 3.9807894230 3.9235124588 161 1311867175.7948620319 0.0592004135 0.0591695754 0.0637469441 0.0069478178 0.7569140000 0.0766460000 0.0508130000 0.0313710000 0.2926440000 0.3045640000 135609099 0 402718720 3.7188255787 3.9798407555 3.9235587120 162 1311867175.8287971020 0.0593977049 0.0591709836 0.0637469441 0.0069376349 0.4469770000 0.0992960000 0.0512690000 0.0000010000 0.2936960000 0.0018160000 135612883 0 402718720 3.7145514488 3.9786863327 3.9233806133 163 1311867175.8625519276 0.0595583431 0.0591733600 0.0637469441 0.0069568996 0.4807360000 0.0976080000 0.0541810000 0.0313730000 0.2948560000 0.0018130000 135616611 0 402718720 3.7130894661 3.9804177284 3.9233472347 164 1311867175.8946080208 0.0598618723 0.0591775583 0.0637469441 0.0069432207 0.4626840000 0.0771190000 0.0871390000 0.0000010000 0.2957260000 0.0018080000 135620227 0 402718720 3.7105700970 3.9806554317 3.9228963852 165 1311867175.9282429218 0.0596128963 0.0591801967 0.0637469441 0.0069439351 0.7618990000 0.0775910000 0.0541560000 0.0313920000 0.2923600000 0.3055150000 135623955 0 402718720 3.7058000565 3.9795978069 3.9223468304 166 1311867175.9629371166 0.0601754300 0.0591861920 0.0637469441 0.0069248672 0.4609850000 0.0769190000 0.0867540000 0.0000000000 0.2946070000 0.0018080000 135627683 0 402718720 3.7027435303 3.9799282551 3.9225409031 167 1311867175.9983000755 0.0602324679 0.0591924572 0.0637469441 0.0069385730 0.4690520000 0.0760170000 0.0647350000 0.0313440000 0.2942530000 0.0018030000 135631411 0 402718720 3.7023167610 3.9811711311 3.9223356247 168 1311867176.0268509388 0.0608657748 0.0592024174 0.0637469441 0.0069245360 0.4704300000 0.1001070000 0.0724460000 0.0000010000 0.2951740000 0.0018080000 135634971 0 402718720 3.6977293491 3.9791479111 3.9221067429 169 1311867176.0627059937 0.0605327860 0.0592102894 0.0637469441 0.0069422789 0.7829420000 0.0768100000 0.0729670000 0.0313570000 0.2944730000 0.3064480000 135638755 0 402718720 3.6931974888 3.9796524048 3.9215946198 170 1311867176.0946600437 0.0614836626 0.0592236622 0.0637469441 0.0069886755 0.4463470000 0.0763620000 0.0724190000 0.0000000000 0.2948600000 0.0018070000 135642371 0 402718720 3.6905181408 3.9805889130 3.9213140011 171 1311867176.1268119812 0.0614961870 0.0592369518 0.0637469441 0.0069709533 0.4828960000 0.0764890000 0.0795970000 0.0309100000 0.2931830000 0.0018140000 135646099 0 402718720 3.6916985512 3.9803984165 3.9204974174 172 1311867176.1625900269 0.0611293688 0.0592479542 0.0637469441 0.0070345353 0.4497240000 0.0873090000 0.0649370000 0.0000000000 0.2947590000 0.0018100000 135649883 0 402718720 3.6887769699 3.9809176922 3.9198899269 173 1311867176.1946918964 0.0615727045 0.0592613921 0.0637469441 0.0070727314 0.8180200000 0.1029870000 0.0821900000 0.0313710000 0.2944160000 0.3061550000 135653555 0 402718720 3.6878697872 3.9812695980 3.9191436768 174 1311867176.2265360355 0.0616399013 0.0592750617 0.0637469441 0.0070534466 0.4372320000 0.0754230000 0.0641980000 0.0000000000 0.2949000000 0.0018040000 135657227 0 402718720 3.6853377819 3.9816682339 3.9187281132 175 1311867176.2625019550 0.0616961569 0.0592888965 0.0637469441 0.0070406205 0.4602340000 0.0749550000 0.0571710000 0.0308870000 0.2945290000 0.0017880000 135661011 0 402718720 3.6817855835 3.9821724892 3.9178583622 176 1311867176.2946109772 0.0621509291 0.0593051581 0.0637469441 0.0070358699 0.4438270000 0.0875080000 0.0567940000 0.0000010000 0.2968680000 0.0017490000 135664627 0 402718720 3.6787960529 3.9842100143 3.9174749851 177 1311867176.3266019821 0.0628819615 0.0593253660 0.0637469441 0.0070260792 0.7847750000 0.0753180000 0.0781190000 0.0308540000 0.2944490000 0.3051220000 135668299 0 402718720 3.6761536598 3.9866142273 3.9171712399 178 1311867176.3624560833 0.0630711392 0.0593464097 0.0637469441 0.0070082596 0.4624080000 0.1043910000 0.0605200000 0.0000010000 0.2947710000 0.0018010000 135672139 0 402718720 3.6751525402 3.9853093624 3.9163465500 179 1311867176.3952438831 0.0631934553 0.0593679015 0.0637469441 0.0069903271 0.4950990000 0.0746790000 0.0871590000 0.0313300000 0.2992260000 0.0017910000 135675755 0 402718720 3.6743783951 3.9867355824 3.9158840179 180 1311867176.4268360138 0.0629530549 0.0593878191 0.0637469441 0.0069765632 0.4578990000 0.0744750000 0.0844410000 0.0000010000 0.2962880000 0.0017820000 135679427 0 402718720 3.6736028194 3.9876742363 3.9151949883 181 1311867176.4629659653 0.0626445413 0.0594058120 0.0637469441 0.0070432871 0.7922350000 0.0726270000 0.0696920000 0.0311840000 0.2968290000 0.3209650000 135683211 0 402718720 3.6711006165 3.9875197411 3.9143996239 182 1311867176.4945809841 0.0635055900 0.0594283382 0.0637469441 0.0070393513 0.4539300000 0.0768690000 0.0776380000 0.0000000000 0.2967180000 0.0017860000 135686827 0 402718720 3.6689324379 3.9874634743 3.9135267735 183 1311867176.5266211033 0.0639208406 0.0594528874 0.0639208406 0.0070965119 0.4725090000 0.0849270000 0.0562950000 0.0311570000 0.2974630000 0.0017430000 135690555 0 402718720 3.6666059494 3.9897930622 3.9128038883 184 1311867176.5636389256 0.0639844164 0.0594775153 0.0639844164 0.0070904655 0.4458760000 0.0745340000 0.0710560000 0.0000010000 0.2975760000 0.0017910000 135694395 0 402718720 3.6648724079 3.9891333580 3.9120464325 185 1311867176.5946090221 0.0640708432 0.0595023441 0.0640708432 0.0070804622 0.7892870000 0.0756350000 0.0714350000 0.0313890000 0.2991450000 0.3107650000 135698011 0 402718720 3.6607072353 3.9890654087 3.9111118317 186 1311867176.6283841133 0.0636888295 0.0595248521 0.0640708432 0.0070703863 0.4411390000 0.0741910000 0.0635920000 0.0000010000 0.3006350000 0.0017920000 135701739 0 402718720 3.6599330902 3.9896202087 3.9103558064 187 1311867176.6625781059 0.0637878999 0.0595476491 0.0640708432 0.0070551743 0.4739080000 0.0739670000 0.0665580000 0.0309630000 0.2997000000 0.0017860000 135705467 0 402718720 3.6567895412 3.9905354977 3.9097113609 188 1311867176.6945180893 0.0632484108 0.0595673341 0.0640708432 0.0070385708 0.4801580000 0.0884180000 0.0881090000 0.0000010000 0.3009210000 0.0017800000 135709083 0 402718720 3.6559352875 3.9907543659 3.9086799622 189 1311867176.7265889645 0.0637436658 0.0595894310 0.0640708432 0.0070216364 0.7983690000 0.0739150000 0.0771120000 0.0313580000 0.3014280000 0.3136380000 135712811 0 402718720 3.6517717838 3.9915883541 3.9083528519 190 1311867176.7632329464 0.0635438785 0.0596102439 0.0640708432 0.0070170360 0.4640770000 0.0743160000 0.0841940000 0.0000010000 0.3028590000 0.0017820000 135716595 0 402718720 3.6510965824 3.9922924042 3.9079921246 191 1311867176.7947680950 0.0634979829 0.0596305986 0.0640708432 0.0070156491 0.4807700000 0.0743020000 0.0702370000 0.0313370000 0.3021390000 0.0017940000 135720211 0 402718720 3.6487348080 3.9922127724 3.9075019360 192 1311867176.8266770840 0.0638490170 0.0596525695 0.0640708432 0.0069980359 0.4432610000 0.0737660000 0.0630390000 0.0000000000 0.3037560000 0.0017700000 135723939 0 402718720 3.6454682350 3.9919891357 3.9071829319 193 1311867176.8627309799 0.0637005046 0.0596735433 0.0640708432 0.0069834494 0.7850960000 0.0847190000 0.0489970000 0.0313160000 0.3032790000 0.3158520000 135727723 0 402718720 3.6436026096 3.9932110310 3.9066474438 194 1311867176.8949549198 0.0640231669 0.0596959640 0.0640708432 0.0069664930 0.4596530000 0.0967710000 0.0565970000 0.0000010000 0.3035780000 0.0017710000 135731395 0 402718720 3.6391220093 3.9932997227 3.9064030647 195 1311867176.9268178940 0.0634631887 0.0597152831 0.0640708432 0.0069684578 0.4966830000 0.0743480000 0.0839270000 0.0309670000 0.3047060000 0.0017960000 135735067 0 402718720 3.6380724907 3.9932353497 3.9060454369 196 1311867176.9650609493 0.0637645200 0.0597359425 0.0640708432 0.0069809297 0.4650330000 0.0731560000 0.0829930000 0.0000010000 0.3061680000 0.0017770000 135738851 0 402718720 3.6360151768 3.9945235252 3.9060282707 197 1311867176.9947481155 0.0638148338 0.0597566475 0.0640708432 0.0069654699 0.8233390000 0.0856280000 0.0830210000 0.0313860000 0.3047450000 0.3176350000 135742467 0 402718720 3.6341257095 3.9948751926 3.9057316780 198 1311867177.0267279148 0.0641783103 0.0597789791 0.0641783103 0.0069507834 0.4588970000 0.0940410000 0.0559250000 0.0000010000 0.3061860000 0.0017810000 135746139 0 402718720 3.6304371357 3.9935657978 3.9054884911 199 1311867177.0626339912 0.0640714541 0.0598005494 0.0641783103 0.0069378346 0.5493840000 0.0794100000 0.1094310000 0.0382670000 0.3189300000 0.0023650000 135749923 0 402718720 3.6303658485 3.9948408604 3.9052236080 200 1311867177.0946850777 0.0638770014 0.0598209316 0.0641783103 0.0069232487 0.4477180000 0.0772190000 0.0620960000 0.0000010000 0.3056780000 0.0017800000 135753595 0 402718720 3.6280403137 3.9950442314 3.9046437740 201 1311867177.1266150475 0.0641250908 0.0598423454 0.0641783103 0.0069075545 0.8121470000 0.0729750000 0.0828320000 0.0313950000 0.3055290000 0.3184740000 135757267 0 402718720 3.6263828278 3.9943847656 3.9046056271 202 1311867177.1627299786 0.0643870831 0.0598648441 0.0643870831 0.0068926271 0.4785200000 0.0854550000 0.0832610000 0.0000010000 0.3070880000 0.0017740000 135761051 0 402718720 3.6234977245 3.9950628281 3.9046406746 203 1311867177.1946458817 0.0645086840 0.0598877201 0.0645086840 0.0068782278 0.4801250000 0.0844890000 0.0552790000 0.0314270000 0.3061960000 0.0017710000 135764723 0 402718720 3.6197783947 3.9958646297 3.9043812752 204 1311867177.2264730930 0.0648206845 0.0599119013 0.0648206845 0.0068623898 0.4530770000 0.0859160000 0.0586890000 0.0000010000 0.3057700000 0.0017420000 135768395 0 402718720 3.6177582741 3.9950795174 3.9040238857 205 1311867177.2638640404 0.0654352307 0.0599388444 0.0654352307 0.0068461385 0.8172930000 0.0724200000 0.0872140000 0.0314320000 0.3057920000 0.3194830000 135772235 0 402718720 3.6150116920 3.9954550266 3.9039120674 206 1311867177.2946178913 0.0648287684 0.0599625819 0.0654352307 0.0068470733 0.4366000000 0.0718870000 0.0551490000 0.0000010000 0.3068450000 0.0017650000 135775851 0 402718720 3.6134479046 3.9953365326 3.9033670425 207 1311867177.3276090622 0.0649304390 0.0599865812 0.0654352307 0.0068310419 0.4954420000 0.0729220000 0.0825520000 0.0309370000 0.3062950000 0.0017770000 135779579 0 402718720 3.6097259521 3.9959840775 3.9029862881 208 1311867177.3627710342 0.0651514083 0.0600114121 0.0654352307 0.0068185702 0.4453090000 0.0804910000 0.0554250000 0.0000010000 0.3066670000 0.0017680000 135783307 0 402718720 3.6089856625 3.9967529774 3.9026987553 209 1311867177.3946089745 0.0656531230 0.0600384059 0.0656531230 0.0068242902 0.7880130000 0.0721050000 0.0581460000 0.0313910000 0.3054050000 0.3199650000 135786979 0 402718720 3.6054868698 3.9963462353 3.9024152756 210 1311867177.4312860966 0.0656951591 0.0600653428 0.0656951591 0.0068111669 0.4718630000 0.0922810000 0.0647240000 0.0000010000 0.3121180000 0.0017780000 135790819 0 402718720 3.6044282913 3.9973940849 3.9021666050 211 1311867177.4626040459 0.0659890547 0.0600934173 0.0659890547 0.0067969779 0.4948220000 0.0726510000 0.0825150000 0.0314700000 0.3054510000 0.0017750000 135794491 0 402718720 3.6013309956 3.9977555275 3.9018816948 212 1311867177.4946429729 0.0657456443 0.0601200788 0.0659890547 0.0067831859 0.4629400000 0.0721520000 0.0823160000 0.0000010000 0.3057410000 0.0017660000 135798163 0 402718720 3.6006932259 3.9982397556 3.9013791084 213 1311867177.5276319981 0.0656402484 0.0601459950 0.0659890547 0.0067705099 0.7955630000 0.0854220000 0.0552680000 0.0314280000 0.3046040000 0.3178700000 135801835 0 402718720 3.5998473167 3.9990258217 3.9009072781 214 1311867177.5626399517 0.0665214658 0.0601757870 0.0665214658 0.0067643761 0.4220710000 0.0724790000 0.0420140000 0.0000010000 0.3048340000 0.0017740000 135805563 0 402718720 3.5980134010 3.9994931221 3.9009289742 215 1311867177.5947310925 0.0662775859 0.0602041674 0.0665214658 0.0067563228 0.4818550000 0.0731440000 0.0695460000 0.0314720000 0.3049430000 0.0017830000 135809235 0 402718720 3.5908687115 3.9986803532 3.8996784687 216 1311867177.6311450005 0.0660978928 0.0602314532 0.0665214658 0.0067413540 0.4157730000 0.0724380000 0.0350730000 0.0000000000 0.3055210000 0.0017690000 135813075 0 402718720 3.5893943310 3.9998712540 3.8990359306 217 1311867177.6624829769 0.0657235980 0.0602567626 0.0665214658 0.0067300982 0.7771020000 0.0729740000 0.0489330000 0.0315170000 0.3047000000 0.3180130000 135816747 0 402718720 3.5891013145 4.0009350777 3.8984160423 218 1311867177.6945610046 0.0663742274 0.0602848244 0.0665214658 0.0067396542 0.4803060000 0.0817830000 0.0827720000 0.0000010000 0.3123740000 0.0023590000 135820419 0 402718720 3.5842792988 4.0008335114 3.8982679844 219 1311867177.7305839062 0.0659587607 0.0603107328 0.0665214658 0.0067304489 0.4744570000 0.0801320000 0.0556750000 0.0310810000 0.3047990000 0.0017760000 135824147 0 402718720 3.5848779678 4.0025777817 3.8975169659 220 1311867177.7625379562 0.0661084950 0.0603370862 0.0665214658 0.0067218347 0.4168780000 0.0730510000 0.0372200000 0.0000010000 0.3038480000 0.0017790000 135827819 0 402718720 3.5854592323 4.0026054382 3.8971123695 221 1311867177.7945590019 0.0663699433 0.0603643842 0.0665214658 0.0067086506 0.7722960000 0.0724250000 0.0486220000 0.0310460000 0.3031230000 0.3160980000 135831491 0 402718720 3.5822658539 4.0026540756 3.8963317871 222 1311867177.8309149742 0.0668347478 0.0603935300 0.0668347478 0.0066990940 0.4330200000 0.0711720000 0.0548950000 0.0000010000 0.3041910000 0.0017790000 135835275 0 402718720 3.5797889233 4.0027003288 3.8955929279 223 1311867177.8625319004 0.0663909465 0.0604204242 0.0668347478 0.0066883151 0.5041460000 0.0831340000 0.0826750000 0.0315210000 0.3040470000 0.0017830000 135838947 0 402718720 3.5812926292 4.0029120445 3.8948013783 224 1311867177.8946919441 0.0671705082 0.0604505586 0.0671705082 0.0066749426 0.4448800000 0.0720080000 0.0652590000 0.0000010000 0.3048560000 0.0017710000 135842563 0 402718720 3.5775771141 4.0037846565 3.8946328163 225 1311867177.9317860603 0.0673481375 0.0604812145 0.0673481375 0.0066611377 0.8067960000 0.0959050000 0.0582380000 0.0315000000 0.3031810000 0.3169820000 135846459 0 402718720 3.5758960247 4.0039081573 3.8938870430 226 1311867177.9627909660 0.0671649277 0.0605107884 0.0673481375 0.0066511548 0.4288440000 0.0727360000 0.0488510000 0.0000000000 0.3044910000 0.0017750000 135850075 0 402718720 3.5763170719 4.0040235519 3.8927981853 227 1311867177.9947769642 0.0671684965 0.0605401175 0.0673481375 0.0066432348 0.4946310000 0.0720390000 0.0840970000 0.0314770000 0.3042530000 0.0017720000 135853635 0 402718720 3.5749084949 4.0059409142 3.8920049667 228 1311867178.0306100845 0.0675345212 0.0605707947 0.0675345212 0.0066293753 0.4478000000 0.0885420000 0.0516750000 0.0000010000 0.3048100000 0.0017760000 135857419 0 402718720 3.5720748901 4.0055170059 3.8913834095 229 1311867178.0634479523 0.0674101561 0.0606006609 0.0675345212 0.0066163594 0.7793520000 0.0730400000 0.0491770000 0.0315560000 0.3056650000 0.3189250000 135861091 0 402718720 3.5727736950 4.0047035217 3.8906576633 230 1311867178.0951139927 0.0672177300 0.0606294308 0.0675345212 0.0066031897 0.4650740000 0.0725110000 0.0824540000 0.0000010000 0.3073270000 0.0017780000 135864763 0 402718720 3.5704543591 4.0066013336 3.8900477886 231 1311867178.1307909489 0.0682786405 0.0606625443 0.0682786405 0.0065973391 0.4782100000 0.0722220000 0.0659180000 0.0310790000 0.3062180000 0.0017730000 135868547 0 402718720 3.5650703907 4.0054492950 3.8899149895 232 1311867178.1627469063 0.0686248392 0.0606968645 0.0686248392 0.0066110230 0.4657050000 0.0717610000 0.0825410000 0.0000000000 0.3085590000 0.0017860000 135872219 0 402718720 3.5632073879 4.0051217079 3.8894767761 233 1311867178.1950459480 0.0680494681 0.0607284207 0.0686248392 0.0066121151 0.8237960000 0.0839230000 0.0764030000 0.0311140000 0.3088530000 0.3224340000 135875835 0 402718720 3.5645542145 4.0070991516 3.8889718056 234 1311867178.2307190895 0.0686356798 0.0607622124 0.0686356798 0.0065995718 0.4678670000 0.0847890000 0.0703700000 0.0000010000 0.3099210000 0.0017710000 135879619 0 402718720 3.5599508286 4.0057907104 3.8884835243 235 1311867178.2628939152 0.0681002364 0.0607934381 0.0686356798 0.0065876943 0.4745790000 0.0731140000 0.0558270000 0.0315360000 0.3112960000 0.0018030000 135883347 0 402718720 3.5595085621 4.0057339668 3.8878986835 236 1311867178.2954900265 0.0680567846 0.0608242150 0.0686356798 0.0065765871 0.4585420000 0.0921860000 0.0506130000 0.0000010000 0.3129530000 0.0017700000 135887019 0 402718720 3.5567870140 4.0072479248 3.8877005577 237 1311867178.3306670189 0.0683929771 0.0608561507 0.0686356798 0.0065694406 0.8269730000 0.0722550000 0.0827310000 0.0315260000 0.3127350000 0.3267170000 135890747 0 402718720 3.5540766716 4.0054349899 3.8875889778 238 1311867178.3627231121 0.0674541369 0.0608838733 0.0686356798 0.0065583626 0.4618660000 0.0885090000 0.0557370000 0.0000010000 0.3148130000 0.0017920000 135894475 0 402718720 3.5550639629 4.0064435005 3.8870851994 239 1311867178.3949439526 0.0675188228 0.0609116346 0.0686356798 0.0065465266 0.5060010000 0.0719880000 0.0849960000 0.0315460000 0.3146790000 0.0017740000 135898091 0 402718720 3.5519704819 4.0069103241 3.8868539333 240 1311867178.4306581020 0.0680190176 0.0609412487 0.0686356798 0.0065486461 0.4456040000 0.0721260000 0.0552060000 0.0000000000 0.3154720000 0.0017870000 135901875 0 402718720 3.5488338470 4.0072102547 3.8871679306 241 1311867178.4628739357 0.0684648231 0.0609724668 0.0686356798 0.0065354525 0.8327910000 0.0720500000 0.0822470000 0.0316920000 0.3156940000 0.3300980000 135905547 0 402718720 3.5461392403 4.0077404976 3.8874258995 242 1311867178.4946439266 0.0685597211 0.0610038191 0.0686356798 0.0065238366 0.4531640000 0.0721280000 0.0619320000 0.0000010000 0.3163130000 0.0017690000 135909219 0 402718720 3.5440111160 4.0067553520 3.8874216080 243 1311867178.5306270123 0.0680590868 0.0610328532 0.0686356798 0.0065261930 0.5157700000 0.0840350000 0.0819710000 0.0315900000 0.3153800000 0.0017700000 135913003 0 402718720 3.5442035198 4.0083293915 3.8871550560 244 1311867178.5626420975 0.0688749030 0.0610649927 0.0688749030 0.0065139563 0.4782550000 0.0726680000 0.0876030000 0.0000010000 0.3151870000 0.0017800000 135916731 0 402718720 3.5405340195 4.0083012581 3.8876559734 245 1311867178.5947000980 0.0687773973 0.0610964719 0.0688749030 0.0065121019 0.8409710000 0.0729120000 0.0830290000 0.0316680000 0.3155110000 0.3367860000 135920403 0 402718720 3.5399317741 4.0073633194 3.8874347210 246 1311867178.6306900978 0.0690887272 0.0611289608 0.0690887272 0.0065098437 0.5192490000 0.0912020000 0.1082260000 0.0000010000 0.3170140000 0.0017760000 135924131 0 402718720 3.5374095440 4.0081634521 3.8873298168 247 1311867178.6626410484 0.0686897635 0.0611595713 0.0690887272 0.0065190068 0.4780390000 0.0726590000 0.0556170000 0.0312540000 0.3157100000 0.0017810000 135927859 0 402718720 3.5371375084 4.0093150139 3.8871481419 248 1311867178.6946120262 0.0694932193 0.0611931747 0.0694932193 0.0065094485 0.4889790000 0.0833730000 0.0869710000 0.0000010000 0.3158170000 0.0017810000 135931475 0 402718720 3.5337893963 4.0074510574 3.8872084618 249 1311867178.7307450771 0.0692925155 0.0612257022 0.0694932193 0.0065063851 0.8121450000 0.0716590000 0.0618740000 0.0312040000 0.3160620000 0.3303260000 135935259 0 402718720 3.5330572128 4.0090298653 3.8867964745 250 1311867178.7632350922 0.0690594316 0.0612570371 0.0694932193 0.0064997613 0.4449720000 0.0719680000 0.0550490000 0.0000010000 0.3151500000 0.0017780000 135938987 0 402718720 3.5327200890 4.0094461441 3.8864564896 251 1311867178.8006799221 0.0694596693 0.0612897169 0.0694932193 0.0064951401 0.4728860000 0.0723320000 0.0516760000 0.0316840000 0.3143710000 0.0017800000 135942771 0 402718720 3.5302357674 4.0075898170 3.8862586021 252 1311867178.8309500217 0.0694057420 0.0613219234 0.0694932193 0.0064914185 0.4726400000 0.0715430000 0.0819820000 0.0000020000 0.3163150000 0.0017650000 135946387 0 402718720 3.5292282104 4.0099191666 3.8861234188 253 1311867178.8627939224 0.0692712814 0.0613533437 0.0694932193 0.0064898130 0.8443770000 0.0848500000 0.0837380000 0.0317290000 0.3145070000 0.3285190000 135950115 0 402718720 3.5290646553 4.0097508430 3.8858470917 254 1311867178.8952279091 0.0700417757 0.0613875502 0.0700417757 0.0064905248 0.4722630000 0.0724030000 0.0826650000 0.0000000000 0.3143910000 0.0017710000 135953787 0 402718720 3.5274009705 4.0066246986 3.8856189251 255 1311867178.9306209087 0.0694987848 0.0614193589 0.0700417757 0.0064878943 0.5052300000 0.0738730000 0.0843560000 0.0311820000 0.3129820000 0.0017950000 135957515 0 402718720 3.5292632580 4.0092210770 3.8845567703 256 1311867178.9627609253 0.0692652762 0.0614500071 0.0700417757 0.0064851415 0.5184430000 0.1075710000 0.0842190000 0.0000000000 0.3231740000 0.0023870000 135961243 0 402718720 3.5293657780 4.0094785690 3.8837380409 257 1311867178.9946830273 0.0698018894 0.0614825046 0.0700417757 0.0064834517 0.8134790000 0.0912380000 0.0635270000 0.0315440000 0.3074500000 0.3186650000 135989491 0 402718720 3.5236725807 4.0086278915 3.8831412792 258 1311867179.0309159756 0.0699689537 0.0615153979 0.0700417757 0.0065207995 0.4476910000 0.0812670000 0.0552080000 0.0000010000 0.3084160000 0.0017560000 136044475 0 402718720 3.5216741562 4.0100989342 3.8826522827 259 1311867179.0628120899 0.0695759580 0.0615465197 0.0700417757 0.0065157115 0.4791840000 0.0727440000 0.0635060000 0.0316270000 0.3084610000 0.0017910000 136048203 0 402718720 3.5225234032 4.0088920593 3.8817603588 260 1311867179.0968201160 0.0709704906 0.0615827658 0.0709704906 0.0066133079 0.4753920000 0.0729320000 0.0885970000 0.0000010000 0.3110260000 0.0017860000 136051875 0 402718720 3.5177078247 4.0058007240 3.8812670708 261 1311867179.1310369968 0.0697956160 0.0616142326 0.0709704906 0.0066019268 0.7987280000 0.0723040000 0.0557830000 0.0316450000 0.3128140000 0.3251320000 136055547 0 402718720 3.5214912891 4.0081958771 3.8799211979 262 1311867179.1627540588 0.0705186948 0.0616482191 0.0709704906 0.0066074538 0.4362630000 0.0724780000 0.0488650000 0.0000010000 0.3120910000 0.0017700000 136059219 0 402718720 3.5195846558 4.0069069862 3.8787393570 263 1311867179.1957008839 0.0706850886 0.0616825798 0.0709704906 0.0066002592 0.4920210000 0.0836440000 0.0616270000 0.0315520000 0.3123590000 0.0017680000 136062891 0 402718720 3.5146682262 4.0059251785 3.8772051334 264 1311867179.2307469845 0.0708635971 0.0617173564 0.0709704906 0.0066620508 0.4572400000 0.0701510000 0.0710400000 0.0000010000 0.3132280000 0.0017530000 136066619 0 402718720 3.5123827457 4.0098648071 3.8764214516 265 1311867179.2634611130 0.0707680061 0.0617515098 0.0709704906 0.0066613601 0.8382590000 0.0705160000 0.0756220000 0.0311180000 0.3283270000 0.3316240000 136070403 0 402718720 3.5105540752 4.0080933571 3.8755092621 266 1311867179.2959330082 0.0705400631 0.0617845495 0.0709704906 0.0066529683 0.4972230000 0.0912590000 0.0837420000 0.0000000000 0.3193600000 0.0017960000 136074019 0 402718720 3.5092210770 4.0076622963 3.8746626377 267 1311867179.3307149410 0.0698297471 0.0618146813 0.0709704906 0.0066425976 0.5116350000 0.0711430000 0.0860570000 0.0317280000 0.3198610000 0.0017690000 136077747 0 402718720 3.5115833282 4.0090894699 3.8739376068 268 1311867179.3629300594 0.0700277463 0.0618453271 0.0709704906 0.0066328570 0.4659790000 0.0784110000 0.0634230000 0.0000010000 0.3213340000 0.0017420000 136081531 0 402718720 3.5092959404 4.0091075897 3.8736286163 269 1311867179.3948490620 0.0700098872 0.0618756786 0.0709704906 0.0066258940 0.8437090000 0.0705140000 0.0851960000 0.0312580000 0.3204700000 0.3351990000 136085091 0 402718720 3.5079128742 4.0077948570 3.8731694221 270 1311867179.4308040142 0.0698082820 0.0619050586 0.0709704906 0.0066397560 0.4461730000 0.0708230000 0.0482880000 0.0000010000 0.3242220000 0.0017620000 136088931 0 402718720 3.5060081482 4.0100636482 3.8730914593 271 1311867179.4637460709 0.0702115968 0.0619357100 0.0709704906 0.0066348621 0.4912790000 0.0834560000 0.0485740000 0.0316100000 0.3247810000 0.0017730000 136092659 0 402718720 3.5042440891 4.0107021332 3.8735332489 272 1311867179.4949469566 0.0700163245 0.0619654182 0.0709704906 0.0066447002 0.4837640000 0.0716780000 0.0832940000 0.0000000000 0.3259480000 0.0017710000 136096275 0 402718720 3.5043017864 4.0098304749 3.8731513023 273 1311867179.5307800770 0.0696735978 0.0619936533 0.0709704906 0.0066425805 0.8242620000 0.0704410000 0.0544870000 0.0316580000 0.3257390000 0.3408610000 136100059 0 402718720 3.5044255257 4.0127563477 3.8731601238 274 1311867179.5627610683 0.0698832124 0.0620224473 0.0709704906 0.0066545005 0.4839550000 0.0708660000 0.0856320000 0.0000010000 0.3246140000 0.0017640000 136103731 0 402718720 3.5027775764 4.0125727654 3.8733103275 275 1311867179.5946741104 0.0701982304 0.0620521774 0.0709704906 0.0066464567 0.5168370000 0.0820760000 0.0744830000 0.0316810000 0.3257540000 0.0017600000 136107403 0 402718720 3.5009558201 4.0130634308 3.8734703064 276 1311867179.6306900978 0.0700007975 0.0620809768 0.0709704906 0.0066600237 0.5094000000 0.0948440000 0.0857640000 0.0000010000 0.3259500000 0.0017610000 136111131 0 402718720 3.5013103485 4.0146932602 3.8734359741 277 1311867179.6625750065 0.0703889132 0.0621109693 0.0709704906 0.0066560878 0.8315010000 0.0711920000 0.0617210000 0.0312580000 0.3254690000 0.3407770000 136114859 0 402718720 3.5009551048 4.0135812759 3.8736443520 278 1311867179.6946051121 0.0705763474 0.0621414203 0.0709704906 0.0066587550 0.4569330000 0.0844430000 0.0437710000 0.0000010000 0.3258740000 0.0017600000 136118475 0 402718720 3.4993660450 4.0149321556 3.8738636971 279 1311867179.7309470177 0.0708456784 0.0621726184 0.0709704906 0.0066496630 0.5166390000 0.0712380000 0.0857060000 0.0317830000 0.3251000000 0.0017300000 136122315 0 402718720 3.4995694160 4.0147566795 3.8740935326 280 1311867179.7627270222 0.0706017539 0.0622027224 0.0709704906 0.0066674293 0.4816980000 0.0712650000 0.0812750000 0.0000010000 0.3263060000 0.0017660000 136125987 0 402718720 3.4986956120 4.0136656761 3.8738737106 281 1311867179.7948911190 0.0700446218 0.0622306295 0.0709704906 0.0066829951 0.8551330000 0.0710790000 0.0814640000 0.0317130000 0.3270550000 0.3427440000 136129603 0 402718720 3.4987785816 4.0156826973 3.8736815453 282 1311867179.8307530880 0.0700094178 0.0622582139 0.0709704906 0.0066735145 0.4691910000 0.0708920000 0.0683200000 0.0000010000 0.3271180000 0.0017650000 136133443 0 402718720 3.4990642071 4.0164513588 3.8739230633 283 1311867179.8627979755 0.0706292987 0.0622877937 0.0709704906 0.0066669573 0.5160670000 0.0997510000 0.0552010000 0.0317310000 0.3265140000 0.0017640000 136137115 0 402718720 3.4966073036 4.0143318176 3.8743047714 284 1311867179.8948040009 0.0704571307 0.0623165590 0.0709704906 0.0066571910 0.5155540000 0.1022890000 0.0808940000 0.0000000000 0.3295200000 0.0017610000 136140787 0 402718720 3.4976184368 4.0144195557 3.8744072914 285 1311867179.9309051037 0.0706578791 0.0623458268 0.0709704906 0.0066831536 0.8372440000 0.0710150000 0.0651720000 0.0313120000 0.3258760000 0.3427820000 136144571 0 402718720 3.4962191582 4.0177326202 3.8750045300 286 1311867179.9635379314 0.0707586855 0.0623752423 0.0709704906 0.0066837509 0.4806180000 0.0894440000 0.0616630000 0.0000010000 0.3266460000 0.0017640000 136148299 0 402718720 3.4951994419 4.0160250664 3.8751320839 287 1311867179.9958879948 0.0708071142 0.0624046217 0.0709704906 0.0066766227 0.5134230000 0.0711670000 0.0810390000 0.0317440000 0.3266100000 0.0017510000 136151915 0 402718720 3.4935107231 4.0161290169 3.8753738403 288 1311867180.0309770107 0.0707231611 0.0624335055 0.0709704906 0.0066741929 0.4870350000 0.0957230000 0.0617630000 0.0000010000 0.3266860000 0.0017650000 136155699 0 402718720 3.4942085743 4.0187034607 3.8759326935 289 1311867180.0626471043 0.0711084455 0.0624635226 0.0711084455 0.0066641322 0.8418060000 0.0720780000 0.0688340000 0.0313960000 0.3262740000 0.3421340000 136159371 0 402718720 3.4931328297 4.0174970627 3.8761048317 290 1311867180.0947730541 0.0712009072 0.0624936515 0.0712009072 0.0066537498 0.4765960000 0.0716590000 0.0751330000 0.0000010000 0.3269590000 0.0017500000 136162987 0 402718720 3.4899675846 4.0181927681 3.8759267330 291 1311867180.1307730675 0.0713495538 0.0625240842 0.0713495538 0.0066506276 0.4688890000 0.0718270000 0.0367950000 0.0318440000 0.3255460000 0.0017660000 136166771 0 402718720 3.4926013947 4.0177059174 3.8758826256 292 1311867180.1636900902 0.0711540505 0.0625536388 0.0713495538 0.0066661057 0.4560270000 0.0722050000 0.0555160000 0.0000010000 0.3254350000 0.0017650000 136170555 0 402718720 3.4947619438 4.0178909302 3.8756923676 293 1311867180.1949090958 0.0708730891 0.0625820329 0.0713495538 0.0066558656 0.8321800000 0.0731230000 0.0628510000 0.0318400000 0.3240960000 0.3391740000 136174115 0 402718720 3.4946997166 4.0176024437 3.8749761581 294 1311867180.2308139801 0.0702900887 0.0626082508 0.0713495538 0.0066520706 0.4540060000 0.0726600000 0.0557040000 0.0000010000 0.3227560000 0.0017770000 136177843 0 402718720 3.4960184097 4.0179247856 3.8739390373 295 1311867180.2637619972 0.0696899518 0.0626322565 0.0713495538 0.0066700064 0.5024590000 0.0716770000 0.0751240000 0.0312680000 0.3215160000 0.0017600000 136181571 0 402718720 3.4970118999 4.0184240341 3.8730413914 296 1311867180.2947549820 0.0702613443 0.0626580305 0.0713495538 0.0066591433 0.4730170000 0.0937220000 0.0546820000 0.0000000000 0.3217250000 0.0017660000 136185187 0 402718720 3.4951066971 4.0176181793 3.8730087280 297 1311867180.3308670521 0.0701183304 0.0626831493 0.0713495538 0.0066501018 0.8297520000 0.0707010000 0.0678540000 0.0317120000 0.3221260000 0.3362510000 136188971 0 402718720 3.4951159954 4.0186944008 3.8725080490 298 1311867180.3658289909 0.0701479688 0.0627081990 0.0713495538 0.0066490052 0.4988070000 0.0975580000 0.0763480000 0.0000010000 0.3220250000 0.0017530000 136192699 0 402718720 3.4948019981 4.0190315247 3.8720386028 299 1311867180.3964109421 0.0704138502 0.0627339705 0.0713495538 0.0066387328 0.4836310000 0.0719210000 0.0585030000 0.0317850000 0.3183660000 0.0018580000 136196371 0 402718720 3.4964911938 4.0194349289 3.8720233440 300 1311867180.4309151173 0.0711624920 0.0627620655 0.0713495538 0.0066284194 0.4774610000 0.0712600000 0.0840140000 0.0000010000 0.3193050000 0.0017580000 136200099 0 402718720 3.4935023785 4.0181007385 3.8717267513 301 1311867180.4670670033 0.0708467364 0.0627889249 0.0713495538 0.0066231855 0.8404510000 0.0713310000 0.0684080000 0.0313310000 0.3307540000 0.3375130000 136203883 0 402718720 3.4947848320 4.0195546150 3.8713493347 302 1311867180.4947559834 0.0710972175 0.0628164358 0.0713495538 0.0066227213 0.4733010000 0.0711400000 0.0812050000 0.0000010000 0.3180670000 0.0017540000 136207387 0 402718720 3.4959607124 4.0190072060 3.8712408543 303 1311867180.5308880806 0.0704978630 0.0628417870 0.0713495538 0.0066119791 0.5004350000 0.0806120000 0.0677460000 0.0314970000 0.3176870000 0.0017590000 136211227 0 402718720 3.4982225895 4.0194082260 3.8709321022 304 1311867180.5629510880 0.0711540878 0.0628691301 0.0713495538 0.0066016583 0.4660700000 0.0714340000 0.0751460000 0.0000010000 0.3166070000 0.0017590000 136214899 0 402718720 3.4970948696 4.0197391510 3.8713929653 305 1311867180.5946910381 0.0712624416 0.0628966492 0.0713495538 0.0065929341 0.8299500000 0.0713710000 0.0817580000 0.0317430000 0.3158110000 0.3281490000 136218571 0 402718720 3.4969649315 4.0201168060 3.8715841770 306 1311867180.6308128834 0.0710181072 0.0629231899 0.0713495538 0.0065836226 0.4709930000 0.0714600000 0.0817340000 0.0000010000 0.3149130000 0.0017550000 136222355 0 402718720 3.4984648228 4.0193862915 3.8717198372 307 1311867180.6640911102 0.0707243085 0.0629486007 0.0713495538 0.0065880841 0.5012640000 0.0699110000 0.0817290000 0.0317040000 0.3150240000 0.0017610000 136226027 0 402718720 3.4989731312 4.0203719139 3.8718898296 308 1311867180.6957859993 0.0709128976 0.0629744588 0.0713495538 0.0065779396 0.4815080000 0.0854900000 0.0638990000 0.0000010000 0.3285760000 0.0023380000 136229699 0 402718720 3.4999296665 4.0191054344 3.8722598553 309 1311867180.7309739590 0.0705640242 0.0629990205 0.0713495538 0.0065724404 0.8408090000 0.0840160000 0.0822370000 0.0317740000 0.3147110000 0.3269370000 136233483 0 402718720 3.5009303093 4.0203123093 3.8722083569 310 1311867180.7650830746 0.0707977042 0.0630241776 0.0713495538 0.0065727254 0.4712250000 0.0716980000 0.0819640000 0.0000010000 0.3146620000 0.0017570000 136237211 0 402718720 3.5024406910 4.0198941231 3.8722894192 311 1311867180.7949280739 0.0710849166 0.0630500963 0.0713495538 0.0065623385 0.4748600000 0.0717370000 0.0417100000 0.0318120000 0.3260550000 0.0023420000 136240771 0 402718720 3.5025858879 4.0198040009 3.8726725578 312 1311867180.8309240341 0.0712926909 0.0630765149 0.0713495538 0.0065527000 0.4753350000 0.0904160000 0.0639860000 0.0000000000 0.3180320000 0.0017620000 136244611 0 402718720 3.5032241344 4.0210609436 3.8731095791 313 1311867180.8652698994 0.0712042153 0.0631024820 0.0713495538 0.0065507783 0.8041740000 0.0838210000 0.0440560000 0.0318590000 0.3152540000 0.3280310000 136248339 0 402718720 3.5037155151 4.0196828842 3.8732008934 314 1311867180.8966469765 0.0707974732 0.0631269884 0.0713495538 0.0065409712 0.4330400000 0.0717150000 0.0440520000 0.0000010000 0.3143740000 0.0017590000 136252011 0 402718720 3.5059404373 4.0206952095 3.8730099201 315 1311867180.9306049347 0.0712638572 0.0631528197 0.0713495538 0.0065495656 0.4818740000 0.0913420000 0.0415740000 0.0312970000 0.3147410000 0.0017620000 136255739 0 402718720 3.5052261353 4.0203042030 3.8733301163 316 1311867180.9631829262 0.0713947117 0.0631789016 0.0713947117 0.0065493588 0.4381390000 0.0714520000 0.0483630000 0.0000010000 0.3154130000 0.0017670000 136259411 0 402718720 3.5057020187 4.0206294060 3.8732531071 317 1311867180.9948179722 0.0709126070 0.0632032982 0.0713947117 0.0065432893 0.8038980000 0.0715370000 0.0553500000 0.0317050000 0.3156230000 0.3285400000 136263027 0 402718720 3.5097661018 4.0211224556 3.8735833168 318 1311867181.0308310986 0.0712241530 0.0632285210 0.0713947117 0.0065340272 0.4574680000 0.0960640000 0.0443530000 0.0000010000 0.3141340000 0.0017680000 136266811 0 402718720 3.5109622478 4.0195674896 3.8737807274 319 1311867181.0627830029 0.0717802644 0.0632553290 0.0717802644 0.0065312513 0.4647420000 0.0720440000 0.0441500000 0.0317720000 0.3138520000 0.0017630000 136270539 0 402718720 3.5128741264 4.0192213058 3.8740515709 320 1311867181.0948719978 0.0709409490 0.0632793465 0.0717802644 0.0065289702 0.4485770000 0.0728030000 0.0588090000 0.0000010000 0.3140350000 0.0017680000 136274211 0 402718720 3.5156698227 4.0196676254 3.8740158081 321 1311867181.1311910152 0.0695146248 0.0632987711 0.0717802644 0.0065248510 0.8310780000 0.0730210000 0.0834820000 0.0318290000 0.3140500000 0.3275430000 136277995 0 402718720 3.5210282803 4.0207343102 3.8733949661 322 1311867181.1629528999 0.0706594065 0.0633216302 0.0717802644 0.0065322899 0.4581000000 0.0727260000 0.0696580000 0.0000010000 0.3127860000 0.0017670000 136281667 0 402718720 3.5205478668 4.0192708969 3.8737673759 323 1311867181.1972830296 0.0704039559 0.0633435569 0.0717802644 0.0065228754 0.4819620000 0.0853120000 0.0492940000 0.0317860000 0.3126240000 0.0017740000 136285395 0 402718720 3.5219125748 4.0196304321 3.8735253811 324 1311867181.2342460155 0.0703238547 0.0633651010 0.0717802644 0.0065140432 0.4569030000 0.0721490000 0.0692100000 0.0000010000 0.3126210000 0.0017580000 136289235 0 402718720 3.5248229504 4.0186247826 3.8732564449 325 1311867181.2629361153 0.0709510967 0.0633884425 0.0717802644 0.0065054331 0.8036590000 0.0706130000 0.0617540000 0.0317870000 0.3126370000 0.3257080000 136292795 0 402718720 3.5251061916 4.0185694695 3.8736114502 326 1311867181.2948091030 0.0700540617 0.0634088892 0.0717802644 0.0064963601 0.4368950000 0.0721010000 0.0489480000 0.0000000000 0.3129130000 0.0017590000 136296411 0 402718720 3.5288975239 4.0199036598 3.8733465672 327 1311867181.3317139149 0.0704165250 0.0634303193 0.0717802644 0.0064926400 0.4547490000 0.0722580000 0.0352820000 0.0317340000 0.3125320000 0.0017680000 136300251 0 402718720 3.5285143852 4.0193996429 3.8733248711 328 1311867181.3626708984 0.0698654875 0.0634499387 0.0717802644 0.0064947810 0.4766360000 0.0950080000 0.0664370000 0.0000000000 0.3122360000 0.0017620000 136303867 0 402718720 3.5319478512 4.0219364166 3.8736770153 329 1311867181.3948218822 0.0699801445 0.0634697874 0.0717802644 0.0064864854 0.8094320000 0.0724960000 0.0695120000 0.0313710000 0.3109230000 0.3239740000 136307539 0 402718720 3.5320010185 4.0200996399 3.8735263348 330 1311867181.4308950901 0.0702180117 0.0634902365 0.0717802644 0.0064776682 0.4694750000 0.0721560000 0.0830630000 0.0000000000 0.3113130000 0.0017620000 136311211 0 402718720 3.5329072475 4.0197882652 3.8736867905 331 1311867181.4628310204 0.0701873228 0.0635104694 0.0717802644 0.0064718895 0.4730560000 0.0721580000 0.0558920000 0.0313030000 0.3107610000 0.0017620000 136314883 0 402718720 3.5358290672 4.0197653770 3.8742334843 332 1311867181.4963610172 0.0693444833 0.0635280417 0.0717802644 0.0064800178 0.4424690000 0.0729450000 0.0565450000 0.0000000000 0.3100300000 0.0017700000 136318611 0 402718720 3.5391869545 4.0199623108 3.8741831779 333 1311867181.5359110832 0.0695783198 0.0635462108 0.0717802644 0.0064735824 0.8072300000 0.0954280000 0.0492240000 0.0317320000 0.3083410000 0.3213240000 136322451 0 402718720 3.5406537056 4.0191445351 3.8741486073 334 1311867181.5671720505 0.0695735291 0.0635642566 0.0717802644 0.0064687798 0.4665660000 0.0721160000 0.0830270000 0.0000010000 0.3084830000 0.0017550000 136326067 0 402718720 3.5413670540 4.0182766914 3.8736071587 335 1311867181.5948610306 0.0697789565 0.0635828080 0.0717802644 0.0064654515 0.4666300000 0.0727200000 0.0518920000 0.0318150000 0.3072500000 0.0017710000 136329571 0 402718720 3.5423171520 4.0196728706 3.8738348484 336 1311867181.6313591003 0.0696289092 0.0636008023 0.0717802644 0.0064653110 0.4681200000 0.0920780000 0.0663800000 0.0000010000 0.3067020000 0.0017710000 136333411 0 402718720 3.5449001789 4.0186939240 3.8735864162 337 1311867181.6628570557 0.0704076737 0.0636210007 0.0717802644 0.0064626810 0.7886060000 0.0725390000 0.0562480000 0.0317220000 0.3072350000 0.3196300000 136337083 0 402718720 3.5447778702 4.0164489746 3.8732821941 338 1311867181.6949229240 0.0695348606 0.0636384974 0.0717802644 0.0064583382 0.4567650000 0.0869180000 0.0592790000 0.0000000000 0.3076040000 0.0017710000 136340699 0 402718720 3.5474207401 4.0184941292 3.8727989197 339 1311867181.7310829163 0.0701641515 0.0636577471 0.0717802644 0.0064600276 0.4979820000 0.0727110000 0.0834590000 0.0318430000 0.3070070000 0.0017720000 136344483 0 402718720 3.5502407551 4.0167932510 3.8725664616 340 1311867181.7634840012 0.0705202594 0.0636779309 0.0717802644 0.0064505594 0.4652310000 0.0724600000 0.0833390000 0.0000000000 0.3064750000 0.0017640000 136348211 0 402718720 3.5492403507 4.0150642395 3.8720791340 341 1311867181.7948980331 0.0695251524 0.0636950782 0.0717802644 0.0064473519 0.7874660000 0.0721550000 0.0556700000 0.0318410000 0.3071130000 0.3195070000 136351771 0 402718720 3.5534322262 4.0164265633 3.8713932037 342 1311867181.8308010101 0.0697695166 0.0637128397 0.0717802644 0.0064424129 0.4376860000 0.0718420000 0.0560140000 0.0000000000 0.3068730000 0.0017560000 136355555 0 402718720 3.5544531345 4.0149321556 3.8713924885 343 1311867181.8627979755 0.0687956214 0.0637276583 0.0717802644 0.0064359002 0.4761080000 0.0851620000 0.0489770000 0.0312870000 0.3077020000 0.0017780000 136359283 0 402718720 3.5573182106 4.0146222115 3.8711040020 344 1311867181.8949289322 0.0686334521 0.0637419194 0.0717802644 0.0064290230 0.4666090000 0.0726400000 0.0834040000 0.0000010000 0.3075970000 0.0017710000 136362899 0 402718720 3.5599067211 4.0155711174 3.8712692261 345 1311867181.9307990074 0.0685510188 0.0637558588 0.0717802644 0.0064242565 0.8141660000 0.0727220000 0.0834280000 0.0317660000 0.3064070000 0.3186460000 136366739 0 402718720 3.5610263348 4.0142488480 3.8708522320 346 1311867181.9629189968 0.0695014000 0.0637724644 0.0717802644 0.0064234848 0.4535000000 0.0858800000 0.0588620000 0.0000010000 0.3057790000 0.0017660000 136370411 0 402718720 3.5600149632 4.0141940117 3.8714499474 347 1311867181.9955599308 0.0693584979 0.0637885625 0.0717802644 0.0064412460 0.5087820000 0.0849850000 0.0832080000 0.0317180000 0.3058920000 0.0017620000 136374083 0 402718720 3.5621659756 4.0132598877 3.8721780777 348 1311867182.0320639610 0.0688556135 0.0638031230 0.0717802644 0.0064334169 0.4907570000 0.0942930000 0.0872740000 0.0000010000 0.3062030000 0.0017640000 136377867 0 402718720 3.5643680096 4.0124983788 3.8721961975 349 1311867182.0629000664 0.0683344454 0.0638161067 0.0717802644 0.0064282127 0.8490990000 0.0809670000 0.0822490000 0.0393130000 0.3205680000 0.3247960000 136381539 0 402718720 3.5669620037 4.0129108429 3.8723385334 350 1311867182.0948839188 0.0684464201 0.0638293362 0.0717802644 0.0064301361 0.4440700000 0.0843400000 0.0488860000 0.0000000000 0.3078680000 0.0017560000 136385155 0 402718720 3.5687954426 4.0125336647 3.8725094795 351 1311867182.1314840317 0.0686083883 0.0638429517 0.0717802644 0.0064215049 0.4998600000 0.0712210000 0.0866090000 0.0317220000 0.3073390000 0.0017560000 136388995 0 402718720 3.5709636211 4.0123934746 3.8730580807 352 1311867182.1629920006 0.0683703721 0.0638558137 0.0717802644 0.0064136747 0.4427510000 0.0696130000 0.0618960000 0.0000000000 0.3083040000 0.0017110000 136392667 0 402718720 3.5722434521 4.0127520561 3.8731687069 353 1311867182.1994500160 0.0690160915 0.0638704320 0.0717802644 0.0064080914 0.7990750000 0.0822310000 0.0580520000 0.0312390000 0.3062660000 0.3200660000 136396395 0 402718720 3.5726532936 4.0119900703 3.8736670017 354 1311867182.2307739258 0.0689740553 0.0638848491 0.0717802644 0.0064023915 0.4293750000 0.0709720000 0.0483260000 0.0000000000 0.3071120000 0.0017380000 136400011 0 402718720 3.5745916367 4.0112037659 3.8741023540 355 1311867182.2629120350 0.0686897486 0.0638983840 0.0717802644 0.0064030716 0.4953610000 0.0717400000 0.0828510000 0.0316640000 0.3061220000 0.0017530000 136403739 0 402718720 3.5775437355 4.0113506317 3.8744015694 356 1311867182.2973539829 0.0695111528 0.0639141502 0.0717802644 0.0063982898 0.4527120000 0.0956980000 0.0486070000 0.0000010000 0.3054080000 0.0017600000 136407467 0 402718720 3.5771582127 4.0097970963 3.8747882843 357 1311867182.3308460712 0.0702874810 0.0639320027 0.0717802644 0.0064160279 0.8123910000 0.0712370000 0.0795800000 0.0312330000 0.3046910000 0.3243570000 136411139 0 402718720 3.5769608021 4.0097622871 3.8754317760 358 1311867182.3629670143 0.0702897534 0.0639497617 0.0717802644 0.0064365760 0.5142510000 0.0903230000 0.1087030000 0.0000010000 0.3122270000 0.0017520000 136414867 0 402718720 3.5782868862 4.0092058182 3.8758430481 359 1311867182.3990368843 0.0701534972 0.0639670423 0.0717802644 0.0064325138 0.4659450000 0.0713760000 0.0555270000 0.0316420000 0.3044190000 0.0017520000 136418595 0 402718720 3.5801057816 4.0082221031 3.8760209084 360 1311867182.4308118820 0.0713772327 0.0639876262 0.0717802644 0.0064296478 0.4267640000 0.0711270000 0.0484370000 0.0000000000 0.3042050000 0.0017500000 136422267 0 402718720 3.5793032646 4.0059466362 3.8763401508 361 1311867182.4629440308 0.0716549456 0.0640088653 0.0717802644 0.0064263831 0.8122080000 0.0831080000 0.0617090000 0.0316590000 0.3046370000 0.3297860000 136425995 0 402718720 3.5796399117 4.0066027641 3.8761427402 362 1311867182.4969599247 0.0719219074 0.0640307245 0.0719219074 0.0064227432 0.5005400000 0.0904180000 0.1027790000 0.0000010000 0.3043440000 0.0017560000 136429667 0 402718720 3.5825247765 4.0048890114 3.8761813641 363 1311867182.5309500694 0.0726884976 0.0640545752 0.0726884976 0.0064143622 0.4712050000 0.0832870000 0.0490280000 0.0316030000 0.3042720000 0.0017690000 136433395 0 402718720 3.5823531151 4.0031027794 3.8756642342 364 1311867182.5629699230 0.0738078207 0.0640813698 0.0738078207 0.0064091871 0.4277930000 0.0703740000 0.0497400000 0.0000010000 0.3046980000 0.0017410000 136437067 0 402718720 3.5817866325 4.0032300949 3.8752772808 365 1311867182.6036369801 0.0742371231 0.0641091938 0.0742371231 0.0064069471 0.7909180000 0.0704170000 0.0681470000 0.0310980000 0.3045210000 0.3155010000 136440963 0 402718720 3.5809097290 4.0028734207 3.8738811016 366 1311867182.6308450699 0.0746735781 0.0641380582 0.0746735781 0.0064172426 0.4759910000 0.0838320000 0.0857440000 0.0000010000 0.3034240000 0.0017300000 136444467 0 402718720 3.5815231800 4.0018301010 3.8733396530 367 1311867182.6635921001 0.0745866150 0.0641665284 0.0746735781 0.0064105942 0.4827700000 0.0693690000 0.0737870000 0.0315570000 0.3050780000 0.0017350000 136448195 0 402718720 3.5829067230 4.0023794174 3.8732955456 368 1311867182.6970019341 0.0741861910 0.0641937557 0.0746735781 0.0064054551 0.4737160000 0.0697150000 0.0850350000 0.0000000000 0.3153280000 0.0023070000 136451867 0 402718720 3.5864670277 4.0017580986 3.8726549149 369 1311867182.7330639362 0.0747750849 0.0642224314 0.0747750849 0.0064018581 0.7918530000 0.0829680000 0.0543610000 0.0315720000 0.3054250000 0.3162790000 136455651 0 402718720 3.5871245861 4.0003843307 3.8719370365 370 1311867182.7631130219 0.0749794096 0.0642515043 0.0749794096 0.0063960302 0.4325560000 0.0683490000 0.0565540000 0.0000010000 0.3046710000 0.0017310000 136459155 0 402718720 3.5897214413 4.0007939339 3.8720941544 371 1311867182.7970550060 0.0756235123 0.0642821566 0.0756235123 0.0063881439 0.4601130000 0.0704780000 0.0505370000 0.0315550000 0.3045840000 0.0017130000 136462939 0 402718720 3.5904157162 3.9993948936 3.8717038631 372 1311867182.8306989670 0.0766279399 0.0643153442 0.0766279399 0.0063820730 0.4324740000 0.0693730000 0.0538430000 0.0000000000 0.3062540000 0.0017410000 136466611 0 402718720 3.5905284882 3.9991526604 3.8714640141 373 1311867182.8641169071 0.0766397864 0.0643483856 0.0766397864 0.0063792201 0.7849080000 0.0812550000 0.0471940000 0.0313960000 0.3067460000 0.3170510000 136470283 0 402718720 3.5917367935 3.9993343353 3.8713185787 374 1311867182.8969969749 0.0754208863 0.0643779913 0.0766397864 0.0063720306 0.4580400000 0.0689780000 0.0801470000 0.0000000000 0.3059200000 0.0017270000 136474011 0 402718720 3.5956768990 3.9988160133 3.8712482452 375 1311867182.9318990707 0.0759720877 0.0644089088 0.0766397864 0.0063636938 0.4832540000 0.0693990000 0.0740040000 0.0315080000 0.3053400000 0.0017420000 136477739 0 402718720 3.5970470905 3.9998536110 3.8715620041 376 1311867182.9630720615 0.0748762488 0.0644367475 0.0766397864 0.0063559070 0.4577600000 0.0699170000 0.0808130000 0.0000010000 0.3040300000 0.0017370000 136481411 0 402718720 3.6009645462 3.9996786118 3.8716878891 377 1311867182.9983949661 0.0757901594 0.0644668627 0.0766397864 0.0063644389 0.8018950000 0.0973460000 0.0552640000 0.0310690000 0.3032480000 0.3137070000 136485139 0 402718720 3.6014664173 3.9990046024 3.8719882965 378 1311867183.0308830738 0.0759397969 0.0644972143 0.0766397864 0.0063563019 0.4309310000 0.0835170000 0.0412270000 0.0000000000 0.3031670000 0.0017470000 136488811 0 402718720 3.6030826569 3.9985437393 3.8723554611 379 1311867183.0628600121 0.0760476813 0.0645276905 0.0766397864 0.0063488816 0.4890500000 0.0703780000 0.0814930000 0.0314870000 0.3026950000 0.0017390000 136492539 0 402718720 3.6053285599 3.9996380806 3.8729076385 380 1311867183.1000499725 0.0763830915 0.0645588889 0.0766397864 0.0063697545 0.4282680000 0.0689040000 0.0539660000 0.0000010000 0.3023990000 0.0017390000 136496267 0 402718720 3.6062285900 3.9978766441 3.8731873035 381 1311867183.1344780922 0.0763166398 0.0645897492 0.0766397864 0.0063638456 0.7906560000 0.0821910000 0.0612100000 0.0314340000 0.3021110000 0.3124220000 136500051 0 402718720 3.6079266071 3.9984292984 3.8735568523 382 1311867183.1673240662 0.0760653615 0.0646197900 0.0766397864 0.0063575149 0.4495270000 0.0704090000 0.0747890000 0.0000010000 0.3013280000 0.0017360000 136503779 0 402718720 3.6098918915 3.9994366169 3.8738684654 383 1311867183.2004919052 0.0772939026 0.0646528817 0.0772939026 0.0063528178 0.4751050000 0.0819210000 0.0580750000 0.0315540000 0.3005210000 0.0017530000 136507451 0 402718720 3.6098213196 3.9975216389 3.8746223450 384 1311867183.2311279774 0.0765976161 0.0646839878 0.0772939026 0.0063451545 0.4606930000 0.0712030000 0.0862700000 0.0000010000 0.3001790000 0.0017490000 136511067 0 402718720 3.6126849651 3.9972553253 3.8748500347 385 1311867183.2633349895 0.0758842826 0.0647130795 0.0772939026 0.0063386057 0.7973350000 0.0706970000 0.0861480000 0.0315230000 0.2985400000 0.3091470000 136514795 0 402718720 3.6151406765 3.9977149963 3.8748917580 386 1311867183.2991099358 0.0760900825 0.0647425536 0.0772939026 0.0063339313 0.4586410000 0.0701900000 0.0851650000 0.0000010000 0.3002620000 0.0017380000 136518523 0 402718720 3.6158893108 3.9955031872 3.8748652935 387 1311867183.3320920467 0.0757209286 0.0647709215 0.0772939026 0.0063336866 0.4869650000 0.0703870000 0.0812140000 0.0315050000 0.3008290000 0.0017370000 136522251 0 402718720 3.6178398132 3.9963755608 3.8748457432 388 1311867183.3695240021 0.0765530691 0.0648012878 0.0772939026 0.0063257224 0.4830120000 0.0953540000 0.0853220000 0.0000010000 0.2993330000 0.0017040000 136526091 0 402718720 3.6182038784 3.9960002899 3.8751218319 389 1311867183.3986210823 0.0767371207 0.0648319712 0.0772939026 0.0063194633 0.7678570000 0.0685070000 0.0566830000 0.0308390000 0.2995050000 0.3110240000 136529651 0 402718720 3.6186361313 3.9944710732 3.8747975826 390 1311867183.4311549664 0.0764511898 0.0648617641 0.0772939026 0.0063251591 0.4562910000 0.0703770000 0.0811410000 0.0000010000 0.3017440000 0.0017320000 136533323 0 402718720 3.6206572056 3.9951453209 3.8747856617 391 1311867183.4667448997 0.0770355910 0.0648928992 0.0772939026 0.0063231783 0.4849950000 0.0691080000 0.0805630000 0.0312990000 0.3009720000 0.0017420000 136537107 0 402718720 3.6221454144 3.9957396984 3.8751573563 392 1311867183.4988338947 0.0766105354 0.0649227911 0.0772939026 0.0063498752 0.4482150000 0.0687040000 0.0775060000 0.0000000000 0.2988450000 0.0017910000 136540835 0 402718720 3.6240606308 3.9937775135 3.8750956059 393 1311867183.5321829319 0.0760980472 0.0649512269 0.0772939026 0.0063428160 0.8232590000 0.0969290000 0.0834790000 0.0315350000 0.2994590000 0.3105570000 136544507 0 402718720 3.6260306835 3.9934089184 3.8752567768 394 1311867183.5661609173 0.0761976093 0.0649797710 0.0772939026 0.0063355448 0.4232090000 0.0709710000 0.0509030000 0.0000010000 0.2981180000 0.0018430000 136548235 0 402718720 3.6280088425 3.9944944382 3.8756172657 395 1311867183.5985479355 0.0769185796 0.0650099958 0.0772939026 0.0063321951 0.4722610000 0.0706930000 0.0679940000 0.0314420000 0.2990960000 0.0017430000 136551907 0 402718720 3.6284589767 3.9927115440 3.8755705357 396 1311867183.6310880184 0.0766254663 0.0650393278 0.0772939026 0.0063437537 0.4514740000 0.0699930000 0.0792640000 0.0000010000 0.2991720000 0.0017250000 136555579 0 402718720 3.6307263374 3.9925177097 3.8758897781 397 1311867183.6649260521 0.0773343816 0.0650702977 0.0773343816 0.0063387399 0.7914040000 0.0703330000 0.0811750000 0.0314540000 0.2986200000 0.3085360000 136559307 0 402718720 3.6323060989 3.9929974079 3.8767571449 398 1311867183.6993949413 0.0765556991 0.0650991555 0.0773343816 0.0063323401 0.4627520000 0.1044950000 0.0579320000 0.0000000000 0.2972360000 0.0017420000 136563091 0 402718720 3.6356067657 3.9912250042 3.8770473003 399 1311867183.7308928967 0.0787639618 0.0651334032 0.0787639618 0.0063356273 0.4870200000 0.0702460000 0.0855050000 0.0314410000 0.2966050000 0.0018390000 136566651 0 402718720 3.6343085766 3.9912936687 3.8776612282 400 1311867183.7676479816 0.0765530318 0.0651619522 0.0787639618 0.0063466143 0.4216770000 0.0710020000 0.0508770000 0.0000010000 0.2967450000 0.0017490000 136570491 0 402718720 3.6398205757 3.9906330109 3.8779444695 401 1311867183.7971870899 0.0765342787 0.0651903121 0.0787639618 0.0063391163 0.7926640000 0.0709790000 0.0814370000 0.0314500000 0.3002140000 0.3072610000 136574051 0 402718720 3.6414334774 3.9896054268 3.8782832623 402 1311867183.8309071064 0.0786491483 0.0652237918 0.0787639618 0.0063332885 0.4384380000 0.0702770000 0.0678230000 0.0000000000 0.2972640000 0.0017400000 136577723 0 402718720 3.6402099133 3.9890022278 3.8791317940 403 1311867183.8655049801 0.0764975101 0.0652517663 0.0787639618 0.0063315347 0.4940680000 0.0814390000 0.0810580000 0.0314400000 0.2970830000 0.0017430000 136581451 0 402718720 3.6450810432 3.9870448112 3.8789510727 404 1311867183.8970971107 0.0771604776 0.0652812433 0.0787639618 0.0063239509 0.4539950000 0.0702890000 0.0832960000 0.0000000000 0.2973660000 0.0017360000 136585067 0 402718720 3.6453688145 3.9869420528 3.8792862892 405 1311867183.9314939976 0.0789048076 0.0653148818 0.0789048076 0.0063183939 0.7750070000 0.0834670000 0.0544730000 0.0314080000 0.2972720000 0.3068120000 136588851 0 402718720 3.6443562508 3.9871973991 3.8799507618 406 1311867183.9658319950 0.0772566795 0.0653442951 0.0789048076 0.0063216750 0.4553610000 0.0703180000 0.0855860000 0.0000010000 0.2963900000 0.0017320000 136592523 0 402718720 3.6478326321 3.9856545925 3.8799395561 407 1311867183.9966781139 0.0769914985 0.0653729123 0.0789048076 0.0063149504 0.4804820000 0.0686610000 0.0798840000 0.0312690000 0.2975980000 0.0017350000 136596195 0 402718720 3.6496450901 3.9852011204 3.8801589012 408 1311867184.0309689045 0.0781297013 0.0654041789 0.0789048076 0.0063396836 0.4242330000 0.0831090000 0.0409860000 0.0000010000 0.2970790000 0.0017300000 136599923 0 402718720 3.6499607563 3.9848873615 3.8808312416 409 1311867184.0647850037 0.0768627077 0.0654321949 0.0789048076 0.0063375693 0.7813560000 0.0900780000 0.0571040000 0.0314730000 0.2950870000 0.3062840000 136603651 0 402718720 3.6527676582 3.9844384193 3.8810205460 410 1311867184.0968890190 0.0768808424 0.0654601184 0.0789048076 0.0063299902 0.4380170000 0.0702990000 0.0677090000 0.0000000000 0.2969420000 0.0017350000 136607267 0 402718720 3.6540071964 3.9841804504 3.8814418316 411 1311867184.1312260628 0.0777608380 0.0654900472 0.0789048076 0.0063242061 0.4825890000 0.0703760000 0.0810820000 0.0314280000 0.2966310000 0.0017380000 136610995 0 402718720 3.6543819904 3.9836864471 3.8820548058 412 1311867184.1650640965 0.0781301111 0.0655207269 0.0789048076 0.0063166896 0.4417170000 0.0687660000 0.0733580000 0.0000010000 0.2965270000 0.0017290000 136614667 0 402718720 3.6553425789 3.9830253124 3.8823938370 413 1311867184.1969559193 0.0777751058 0.0655503985 0.0789048076 0.0063109000 0.8066290000 0.0860170000 0.0856080000 0.0314910000 0.2957480000 0.3064320000 136618395 0 402718720 3.6577708721 3.9842247963 3.8827207088 414 1311867184.2309360504 0.0759248957 0.0655754577 0.0789048076 0.0063058089 0.4257280000 0.0711040000 0.0557130000 0.0000000000 0.2958290000 0.0017350000 136622123 0 402718720 3.6630558968 3.9841797352 3.8832175732 415 1311867184.2681369781 0.0771354660 0.0656033132 0.0789048076 0.0063063104 0.4830780000 0.0709920000 0.0819400000 0.0314590000 0.2955930000 0.0017450000 136625963 0 402718720 3.6626749039 3.9817905426 3.8831462860 416 1311867184.2983899117 0.0780195445 0.0656331599 0.0789048076 0.0063001266 0.4844940000 0.0838630000 0.1018650000 0.0000000000 0.2956780000 0.0017310000 136629579 0 402718720 3.6635818481 3.9828627110 3.8838953972 417 1311867184.3314700127 0.0773390085 0.0656612314 0.0789048076 0.0062925836 0.7846450000 0.0712800000 0.0819650000 0.0309940000 0.2949160000 0.3041590000 136633251 0 402718720 3.6666605473 3.9834604263 3.8842096329 418 1311867184.3697841167 0.0776374862 0.0656898828 0.0789048076 0.0062952084 0.4494450000 0.0949560000 0.0579850000 0.0000000000 0.2933930000 0.0017410000 136637091 0 402718720 3.6681735516 3.9819068909 3.8840818405 419 1311867184.4000220299 0.0776032582 0.0657183156 0.0789048076 0.0063292771 0.4635100000 0.0704140000 0.0649140000 0.0314690000 0.2936340000 0.0017390000 136640707 0 402718720 3.6717379093 3.9827816486 3.8846797943 420 1311867184.4310610294 0.0770765468 0.0657453591 0.0789048076 0.0063249008 0.4202410000 0.0720370000 0.0513720000 0.0000010000 0.2937240000 0.0017580000 136644379 0 402718720 3.6752276421 3.9832646847 3.8853125572 421 1311867184.4655809402 0.0790154338 0.0657768794 0.0790154338 0.0063234764 0.7798730000 0.0696950000 0.0812350000 0.0312740000 0.2937400000 0.3025940000 136648107 0 402718720 3.6742434502 3.9808471203 3.8850865364 422 1311867184.5037670135 0.0783860385 0.0658067589 0.0790154338 0.0063645328 0.4163910000 0.0710830000 0.0480980000 0.0000010000 0.2940880000 0.0017450000 136651947 0 402718720 3.6773374081 3.9799571037 3.8842680454 423 1311867184.5310881138 0.0779695734 0.0658355126 0.0790154338 0.0063840677 0.4729110000 0.0719990000 0.0729480000 0.0315280000 0.2933160000 0.0017570000 136655507 0 402718720 3.6804876328 3.9803962708 3.8837497234 424 1311867184.5682930946 0.0773985684 0.0658627840 0.0790154338 0.0063778881 0.4437910000 0.0717250000 0.0755090000 0.0000010000 0.2934530000 0.0017500000 136659347 0 402718720 3.6839814186 3.9805731773 3.8831875324 425 1311867184.6018071175 0.0774864629 0.0658901338 0.0790154338 0.0063709094 0.7785290000 0.0695910000 0.0808100000 0.0308140000 0.2935240000 0.3024270000 136663019 0 402718720 3.6850273609 3.9791617393 3.8824834824 426 1311867184.6367399693 0.0799160451 0.0659230585 0.0799160451 0.0063675718 0.4170050000 0.0705510000 0.0411560000 0.0000010000 0.3015060000 0.0023180000 136666803 0 402718720 3.6846470833 3.9797923565 3.8833382130 427 1311867184.6662440300 0.0770368427 0.0659490861 0.0799160451 0.0063854432 0.5354840000 0.0896600000 0.1075920000 0.0383570000 0.2967780000 0.0017370000 136670363 0 402718720 3.6905806065 3.9787061214 3.8830945492 428 1311867184.6994929314 0.0779765919 0.0659771878 0.0799160451 0.0063805974 0.4402040000 0.0818210000 0.0615910000 0.0000010000 0.2936770000 0.0017480000 136674147 0 402718720 3.6912002563 3.9772636890 3.8832945824 429 1311867184.7359158993 0.0775244534 0.0660041045 0.0799160451 0.0063801873 0.7638780000 0.0706490000 0.0648340000 0.0314730000 0.2925520000 0.3030040000 136677819 0 402718720 3.6949858665 3.9782495499 3.8837246895 430 1311867184.7690689564 0.0789875612 0.0660342985 0.0799160451 0.0063825606 0.4659660000 0.0918510000 0.0788460000 0.0000010000 0.2921560000 0.0017380000 136681603 0 402718720 3.6954450607 3.9759979248 3.8846335411 431 1311867184.8001279831 0.0784447789 0.0660630932 0.0799160451 0.0063823533 0.4553870000 0.0704570000 0.0577870000 0.0314320000 0.2926010000 0.0017370000 136685219 0 402718720 3.6986234188 3.9758343697 3.8851132393 432 1311867184.8348441124 0.0787332803 0.0660924223 0.0799160451 0.0063755817 0.4607270000 0.0830000000 0.0811890000 0.0000010000 0.2934240000 0.0017260000 136688891 0 402718720 3.7012476921 3.9759583473 3.8861875534 433 1311867184.8690660000 0.0763345659 0.0661160762 0.0799160451 0.0063703590 0.8031380000 0.0916490000 0.0860500000 0.0310000000 0.2913650000 0.3017030000 136692619 0 402718720 3.7067377567 3.9748475552 3.8866205215 434 1311867184.9055209160 0.0760290474 0.0661389172 0.0799160451 0.0063648333 0.4487010000 0.0711060000 0.0816570000 0.0000000000 0.2927920000 0.0017400000 136696291 0 402718720 3.7101211548 3.9746079445 3.8876125813 435 1311867184.9332280159 0.0756560341 0.0661607956 0.0799160451 0.0063604249 0.4599610000 0.0699800000 0.0639100000 0.0314470000 0.2914880000 0.0017540000 136699795 0 402718720 3.7140181065 3.9752829075 3.8892352581 436 1311867184.9656410217 0.0761049539 0.0661836033 0.0799160451 0.0063590749 0.4394500000 0.0841690000 0.0617430000 0.0000010000 0.2904120000 0.0017350000 136703467 0 402718720 3.7154607773 3.9738271236 3.8904712200 437 1311867184.9983251095 0.0755663589 0.0662050741 0.0799160451 0.0063556989 0.7790730000 0.0710700000 0.0862520000 0.0314840000 0.2898250000 0.2990620000 136707195 0 402718720 3.7187099457 3.9727518559 3.8914442062 438 1311867185.0360550880 0.0741535202 0.0662232213 0.0799160451 0.0063485923 0.4483850000 0.0706590000 0.0858180000 0.0000010000 0.2887890000 0.0017270000 136710979 0 402718720 3.7242169380 3.9727530479 3.8928775787 439 1311867185.0652348995 0.0722080171 0.0662368541 0.0799160451 0.0063465962 0.4642640000 0.0715960000 0.0687990000 0.0310010000 0.2897410000 0.0017450000 136714595 0 402718720 3.7293872833 3.9708018303 3.8939116001 440 1311867185.0991280079 0.0737535805 0.0662539375 0.0799160451 0.0063434208 0.4462310000 0.0713390000 0.0821330000 0.0000010000 0.2896140000 0.0017420000 136718323 0 402718720 3.7301313877 3.9720678329 3.8955245018 441 1311867185.1360778809 0.0742046982 0.0662719665 0.0799160451 0.0063397472 0.7927280000 0.0871090000 0.0865090000 0.0310130000 0.2890300000 0.2976880000 136722107 0 402718720 3.7326059341 3.9717237949 3.8973066807 442 1311867185.1648709774 0.0732241496 0.0662876954 0.0799160451 0.0063348380 0.4467990000 0.0707820000 0.0860660000 0.0000010000 0.2868210000 0.0017300000 136725723 0 402718720 3.7368092537 3.9709234238 3.8988480568 443 1311867185.2000720501 0.0734141469 0.0663037822 0.0799160451 0.0063296668 0.4799730000 0.0859590000 0.0722920000 0.0313620000 0.2872210000 0.0017420000 136729395 0 402718720 3.7403342724 3.9708991051 3.9005618095 444 1311867185.2342920303 0.0733624995 0.0663196802 0.0799160451 0.0063283324 0.4191460000 0.0721250000 0.0585630000 0.0000010000 0.2851370000 0.0018480000 136733179 0 402718720 3.7443261147 3.9708666801 3.9025275707 445 1311867185.2663950920 0.0717878938 0.0663319683 0.0799160451 0.0063227882 0.7410030000 0.0720540000 0.0555940000 0.0313770000 0.2860520000 0.2944780000 136736907 0 402718720 3.7488844395 3.9679541588 3.9035630226 446 1311867185.2970550060 0.0718679801 0.0663443809 0.0799160451 0.0063342572 0.4027840000 0.0715050000 0.0416100000 0.0000010000 0.2864760000 0.0017370000 136740523 0 402718720 3.7517490387 3.9690608978 3.9051868916 447 1311867185.3360140324 0.0719397068 0.0663568984 0.0799160451 0.0063271680 0.4542140000 0.0719000000 0.0624420000 0.0313350000 0.2853340000 0.0017440000 136744363 0 402718720 3.7550685406 3.9683327675 3.9068927765 448 1311867185.3681778908 0.0715219527 0.0663684275 0.0799160451 0.0063205014 0.4353560000 0.0831510000 0.0657310000 0.0000000000 0.2833080000 0.0017470000 136748091 0 402718720 3.7582733631 3.9668762684 3.9079666138 449 1311867185.4036509991 0.0713208169 0.0663794574 0.0799160451 0.0063161762 0.7759910000 0.0831040000 0.0822380000 0.0309060000 0.2850280000 0.2933180000 136751819 0 402718720 3.7613413334 3.9669008255 3.9090013504 450 1311867185.4386389256 0.0727221221 0.0663935522 0.0799160451 0.0063119777 0.4408070000 0.0712950000 0.0822630000 0.0000010000 0.2841040000 0.0017390000 136755547 0 402718720 3.7626440525 3.9676342010 3.9105677605 451 1311867185.4655449390 0.0712626651 0.0664043484 0.0799160451 0.0063065045 0.4891590000 0.0963140000 0.0761640000 0.0308760000 0.2826340000 0.0017480000 136759051 0 402718720 3.7673308849 3.9656293392 3.9113695621 452 1311867185.5013909340 0.0694880858 0.0664111709 0.0799160451 0.0063248508 0.4372540000 0.0719660000 0.0799690000 0.0000010000 0.2821660000 0.0017340000 136762835 0 402718720 3.7721269131 3.9645700455 3.9115531445 453 1311867185.5336329937 0.0711730719 0.0664216828 0.0799160451 0.0063497003 0.8282490000 0.0844170000 0.1023020000 0.0381780000 0.2966550000 0.3051920000 136766507 0 402718720 3.7730906010 3.9659781456 3.9127018452 454 1311867185.5666799545 0.0709219649 0.0664315953 0.0799160451 0.0063431825 0.4826590000 0.0917600000 0.1058180000 0.0000000000 0.2819080000 0.0017390000 136770235 0 402718720 3.7766542435 3.9646546841 3.9135158062 455 1311867185.5970540047 0.0698851869 0.0664391856 0.0799160451 0.0063416899 0.4744910000 0.0721950000 0.0874180000 0.0308830000 0.2808320000 0.0017480000 136773851 0 402718720 3.7801632881 3.9632492065 3.9137310982 456 1311867185.6329469681 0.0715947151 0.0664504916 0.0799160451 0.0063657296 0.4173300000 0.0699820000 0.0616720000 0.0000010000 0.2825280000 0.0017190000 136777635 0 402718720 3.7820589542 3.9652082920 3.9146423340 457 1311867185.6664180756 0.0697689131 0.0664577529 0.0799160451 0.0063728762 0.7580280000 0.0722880000 0.0831340000 0.0307720000 0.2811570000 0.2892540000 136781307 0 402718720 3.7878015041 3.9635715485 3.9153735638 458 1311867185.6973390579 0.0695342496 0.0664644702 0.0799160451 0.0063660680 0.4503910000 0.0833670000 0.0830410000 0.0000000000 0.2808180000 0.0017320000 136784979 0 402718720 3.7903871536 3.9625532627 3.9160354137 459 1311867185.7351899147 0.0697420985 0.0664716110 0.0799160451 0.0063646913 0.4445930000 0.0722910000 0.0590030000 0.0313080000 0.2788330000 0.0017400000 136788763 0 402718720 3.7944345474 3.9645664692 3.9176638126 460 1311867185.7649769783 0.0701230168 0.0664795488 0.0799160451 0.0063614925 0.4372410000 0.0722820000 0.0834700000 0.0000010000 0.2783160000 0.0017270000 136792435 0 402718720 3.7964463234 3.9620740414 3.9188895226 461 1311867185.7989649773 0.0705285668 0.0664883319 0.0799160451 0.0063689635 0.7523150000 0.0723410000 0.0832410000 0.0312260000 0.2780850000 0.2859990000 136796107 0 402718720 3.7989134789 3.9610590935 3.9197249413 462 1311867185.8327999115 0.0695590526 0.0664949785 0.0799160451 0.0063630904 0.4223010000 0.0853140000 0.0560540000 0.0000010000 0.2777620000 0.0017280000 136799891 0 402718720 3.8032417297 3.9614677429 3.9206130505 463 1311867185.8649098873 0.0694535077 0.0665013684 0.0799160451 0.0063570716 0.4703700000 0.0861020000 0.0735470000 0.0313170000 0.2762190000 0.0017380000 136803563 0 402718720 3.8057160378 3.9600007534 3.9216451645 464 1311867185.9030420780 0.0689712763 0.0665066915 0.0799160451 0.0063523271 0.4368050000 0.0730480000 0.0834580000 0.0000010000 0.2771330000 0.0017050000 136807347 0 402718720 3.8085696697 3.9596037865 3.9223403931 465 1311867185.9396789074 0.0704403222 0.0665151509 0.0799160451 0.0063503992 0.7239850000 0.0731930000 0.0594490000 0.0308540000 0.2749650000 0.2840750000 136811187 0 402718720 3.8090400696 3.9595334530 3.9241292477 466 1311867185.9650609493 0.0694146752 0.0665213731 0.0799160451 0.0063619151 0.4157660000 0.0736230000 0.0634080000 0.0000010000 0.2755460000 0.0017310000 136814579 0 402718720 3.8117830753 3.9571204185 3.9249684811 467 1311867186.0039470196 0.0687270090 0.0665260961 0.0799160451 0.0063572161 0.4533750000 0.0732720000 0.0702730000 0.0312980000 0.2753460000 0.0017410000 136818475 0 402718720 3.8147985935 3.9551401138 3.9259476662 468 1311867186.0396919250 0.0704103410 0.0665343957 0.0799160451 0.0063699940 0.4219090000 0.0868610000 0.0567260000 0.0000010000 0.2751250000 0.0017400000 136822259 0 402718720 3.8149032593 3.9570345879 3.9273679256 469 1311867186.0653240681 0.0693589821 0.0665404183 0.0799160451 0.0063742379 0.7106140000 0.0737680000 0.0496550000 0.0313140000 0.2733880000 0.2810450000 136825819 0 402718720 3.8168425560 3.9542179108 3.9280421734 470 1311867186.1047339439 0.0697257444 0.0665471956 0.0799160451 0.0063675745 0.4110140000 0.0715790000 0.0625280000 0.0000000000 0.2737180000 0.0017350000 136829659 0 402718720 3.8172314167 3.9527740479 3.9286029339 471 1311867186.1361179352 0.0691252798 0.0665526692 0.0799160451 0.0063628554 0.4655490000 0.0734870000 0.0842050000 0.0312700000 0.2733960000 0.0017440000 136833275 0 402718720 3.8198566437 3.9524047375 3.9291713238 472 1311867186.1649448872 0.0696729049 0.0665592799 0.0799160451 0.0063565947 0.4056930000 0.0732310000 0.0561810000 0.0000010000 0.2730810000 0.0017330000 136836891 0 402718720 3.8204448223 3.9513092041 3.9296886921 473 1311867186.2044749260 0.0684725046 0.0665633248 0.0799160451 0.0063509784 0.7734470000 0.0994280000 0.0887090000 0.0314400000 0.2722740000 0.2800670000 136840787 0 402718720 3.8236620426 3.9500789642 3.9297606945 474 1311867186.2359659672 0.0690461472 0.0665685628 0.0799160451 0.0063477200 0.4365510000 0.0733820000 0.0869500000 0.0000010000 0.2730240000 0.0017350000 136844403 0 402718720 3.8245697021 3.9501359463 3.9305257797 475 1311867186.2674899101 0.0698060915 0.0665753786 0.0799160451 0.0063417713 0.4729760000 0.0739020000 0.0845460000 0.0313110000 0.2793160000 0.0023400000 136848075 0 402718720 3.8256151676 3.9483051300 3.9312243462 476 1311867186.3030838966 0.0690871030 0.0665806554 0.0799160451 0.0063362646 0.4360140000 0.0939990000 0.0661490000 0.0000010000 0.2726450000 0.0017490000 136851859 0 402718720 3.8287153244 3.9482452869 3.9318368435 477 1311867186.3349270821 0.0693911165 0.0665865473 0.0799160451 0.0063307470 0.7403670000 0.0747220000 0.0855800000 0.0313110000 0.2698800000 0.2774250000 136855475 0 402718720 3.8306884766 3.9486720562 3.9329831600 478 1311867186.3670160770 0.0681487918 0.0665898156 0.0799160451 0.0063356350 0.4094240000 0.0874210000 0.0501170000 0.0000020000 0.2686790000 0.0017470000 136859091 0 402718720 3.8338141441 3.9458324909 3.9334533215 479 1311867186.4019849300 0.0688259453 0.0665944839 0.0799160451 0.0063398603 0.4339310000 0.0742280000 0.0569070000 0.0308490000 0.2687360000 0.0017390000 136862819 0 402718720 3.8348078728 3.9465022087 3.9345226288 480 1311867186.4360210896 0.0688551739 0.0665991937 0.0799160451 0.0063388035 0.4422620000 0.0863510000 0.0856870000 0.0000010000 0.2669840000 0.0017590000 136866547 0 402718720 3.8377151489 3.9470541477 3.9362752438 481 1311867186.4659481049 0.0681339726 0.0666023845 0.0799160451 0.0063365657 0.7016360000 0.0751350000 0.0574680000 0.0308940000 0.2647140000 0.2719480000 136870163 0 402718720 3.8400166035 3.9445791245 3.9371666908 482 1311867186.5031139851 0.0683154613 0.0666059386 0.0799160451 0.0063315933 0.4059170000 0.0877880000 0.0502390000 0.0000000000 0.2646710000 0.0017510000 136874003 0 402718720 3.8411641121 3.9430632591 3.9379825592 483 1311867186.5363171101 0.0683168992 0.0666094810 0.0799160451 0.0063283431 0.4622170000 0.0890270000 0.0759870000 0.0313650000 0.2625990000 0.0017590000 136877675 0 402718720 3.8440449238 3.9448454380 3.9395449162 484 1311867186.5651130676 0.0689271912 0.0666142696 0.0799160451 0.0063269437 0.4310460000 0.0911260000 0.0758790000 0.0000010000 0.2607960000 0.0017560000 136881291 0 402718720 3.8445904255 3.9425284863 3.9402611256 485 1311867186.6014220715 0.0692869425 0.0666197803 0.0799160451 0.0063212232 0.7115170000 0.0747980000 0.0751110000 0.0308380000 0.2607800000 0.2685090000 136885075 0 402718720 3.8461558819 3.9417448044 3.9404590130 486 1311867186.6362628937 0.0699184909 0.0666265678 0.0799160451 0.0063148878 0.4246590000 0.0738030000 0.0849930000 0.0000000000 0.2619150000 0.0023560000 136888803 0 402718720 3.8474061489 3.9417076111 3.9407007694 487 1311867186.6650478840 0.0699660033 0.0666334249 0.0799160451 0.0063105603 0.5262320000 0.0956280000 0.1137950000 0.0381310000 0.2747450000 0.0023540000 136892363 0 402718720 3.8494148254 3.9421212673 3.9408431053 488 1311867186.7043809891 0.0694134161 0.0666391216 0.0799160451 0.0063291356 0.4685340000 0.0954540000 0.1089140000 0.0000010000 0.2609320000 0.0017440000 136896315 0 402718720 3.8520014286 3.9417998791 3.9404389858 489 1311867186.7337749004 0.0700422004 0.0666460809 0.0799160451 0.0063360278 0.7252900000 0.0753620000 0.0907880000 0.0309170000 0.2597120000 0.2669600000 136899875 0 402718720 3.8529264927 3.9432456493 3.9404015541 490 1311867186.7673180103 0.0705679208 0.0666540847 0.0799160451 0.0063310112 0.4005290000 0.0765730000 0.0611650000 0.0000010000 0.2595340000 0.0017650000 136903603 0 402718720 3.8543763161 3.9442663193 3.9406208992 491 1311867186.8047299385 0.0695932284 0.0666600707 0.0799160451 0.0063340245 0.4553000000 0.0750320000 0.0865020000 0.0308390000 0.2596640000 0.0017680000 136907443 0 402718720 3.8568227291 3.9426023960 3.9397094250 492 1311867186.8340749741 0.0709384754 0.0666687666 0.0799160451 0.0063359382 0.3906410000 0.0761940000 0.0512640000 0.0000010000 0.2599220000 0.0017630000 136911003 0 402718720 3.8570976257 3.9453721046 3.9397125244 493 1311867186.8775999546 0.0710792765 0.0666777129 0.0799160451 0.0063298618 0.7387760000 0.0903810000 0.0902490000 0.0314590000 0.2590850000 0.2661270000 136915011 0 402718720 3.8600044250 3.9455757141 3.9398117065 494 1311867186.9052100182 0.0705284476 0.0666855079 0.0799160451 0.0063280086 0.4265480000 0.0753800000 0.0889050000 0.0000000000 0.2589970000 0.0017750000 136918515 0 402718720 3.8629114628 3.9464926720 3.9397864342 495 1311867186.9334239960 0.0710642785 0.0666943539 0.0799160451 0.0063221536 0.4825720000 0.1009760000 0.0886100000 0.0308610000 0.2588390000 0.0017750000 136922187 0 402718720 3.8643517494 3.9474267960 3.9396147728 496 1311867186.9663379192 0.0715450421 0.0667041335 0.0799160451 0.0063223429 0.4362420000 0.0780670000 0.0946800000 0.0000000000 0.2594710000 0.0024080000 136925803 0 402718720 3.8670022488 3.9493739605 3.9399158955 497 1311867187.0017139912 0.0722722858 0.0667153371 0.0799160451 0.0063254389 0.8031050000 0.0999580000 0.1191150000 0.0381350000 0.2712570000 0.2731350000 136929419 0 402718720 3.8685700893 3.9490275383 3.9395995140 498 1311867187.0336461067 0.0711777806 0.0667242978 0.0799160451 0.0063215166 0.4106200000 0.0787940000 0.0706980000 0.0000010000 0.2578270000 0.0018030000 136933091 0 402718720 3.8728733063 3.9495613575 3.9390842915 499 1311867187.0749349594 0.0733322650 0.0667375402 0.0799160451 0.0063248765 0.4649570000 0.0789080000 0.0947810000 0.0313360000 0.2564690000 0.0018940000 136937043 0 402718720 3.8740010262 3.9526343346 3.9395864010 500 1311867187.1016030312 0.0731786713 0.0667504225 0.0799160451 0.0063201518 0.4130800000 0.0801300000 0.0720980000 0.0000010000 0.2575290000 0.0018090000 136940603 0 402718720 3.8766906261 3.9529731274 3.9397354126 501 1311867187.1342070103 0.0737687349 0.0667644311 0.0799160451 0.0063210917 0.7109070000 0.0926690000 0.0604930000 0.0313480000 0.2589890000 0.2659120000 136944275 0 402718720 3.8779537678 3.9501488209 3.9392857552 502 1311867187.1710209846 0.0740233213 0.0667788910 0.0799160451 0.0063264830 0.4301870000 0.0787030000 0.0893970000 0.0000000000 0.2587660000 0.0017900000 136948059 0 402718720 3.8813722134 3.9522306919 3.9394690990 503 1311867187.2041370869 0.0741700158 0.0667935851 0.0799160451 0.0063252575 0.4970020000 0.1077610000 0.0947660000 0.0313170000 0.2596640000 0.0018870000 136951787 0 402718720 3.8852617741 3.9539928436 3.9393436909 504 1311867187.2331659794 0.0737615824 0.0668074105 0.0799160451 0.0063240232 0.4254240000 0.0798390000 0.0792420000 0.0000010000 0.2630160000 0.0018000000 136955403 0 402718720 3.8865973949 3.9511160851 3.9384844303 505 1311867187.2707629204 0.0728816316 0.0668194386 0.0799160451 0.0063301057 0.7381840000 0.0791720000 0.0924960000 0.0312770000 0.2631130000 0.2706320000 136959187 0 402718720 3.8904812336 3.9541106224 3.9380788803 506 1311867187.3015060425 0.0719756708 0.0668296288 0.0799160451 0.0063326680 0.4139820000 0.0790750000 0.0672200000 0.0000010000 0.2643620000 0.0017900000 136962859 0 402718720 3.8926768303 3.9534745216 3.9376618862 507 1311867187.3336570263 0.0724368095 0.0668406884 0.0799160451 0.0063278821 0.4295510000 0.0795050000 0.0527310000 0.0308570000 0.2631360000 0.0018080000 136966475 0 402718720 3.8922536373 3.9513845444 3.9369056225 508 1311867187.3707590103 0.0717886686 0.0668504285 0.0799160451 0.0063227147 0.4480820000 0.0919880000 0.0894850000 0.0000000000 0.2632930000 0.0017960000 136970315 0 402718720 3.8945903778 3.9517784119 3.9364295006 509 1311867187.4033529758 0.0718319714 0.0668602154 0.0799160451 0.0063209438 0.7319220000 0.0781950000 0.0892820000 0.0311390000 0.2621540000 0.2696460000 136974043 0 402718720 3.8956079483 3.9522678852 3.9357378483 510 1311867187.4335899353 0.0701977238 0.0668667595 0.0799160451 0.0063223459 0.4316410000 0.0795120000 0.0868880000 0.0000010000 0.2619000000 0.0018090000 136977659 0 402718720 3.8991138935 3.9512445927 3.9350309372 511 1311867187.4763159752 0.0723027512 0.0668773975 0.0799160451 0.0063257758 0.4398490000 0.0926050000 0.0529510000 0.0308820000 0.2600820000 0.0018050000 136981611 0 402718720 3.8993251324 3.9518554211 3.9345190525 512 1311867187.5056400299 0.0726256743 0.0668886246 0.0799160451 0.0063228971 0.4338570000 0.0797190000 0.0902320000 0.0000010000 0.2605890000 0.0018010000 136985171 0 402718720 3.9013283253 3.9503476620 3.9336335659 513 1311867187.5342190266 0.0719368160 0.0668984651 0.0799160451 0.0063186909 0.7173990000 0.0977210000 0.0600310000 0.0313150000 0.2594660000 0.2673370000 137037939 0 402718720 3.9055311680 3.9503598213 3.9327797890 514 1311867187.5709679127 0.0721516907 0.0669086854 0.0799160451 0.0063129160 0.4051390000 0.0792110000 0.0626830000 0.0000010000 0.2599020000 0.0018010000 137144123 0 402718720 3.9089922905 3.9506471157 3.9317955971 515 1311867187.6045789719 0.0731939077 0.0669208897 0.0799160451 0.0063334531 0.4410890000 0.0790660000 0.0674740000 0.0313360000 0.2598800000 0.0017920000 137147907 0 402718720 3.9099209309 3.9513926506 3.9304206371 516 1311867187.6353919506 0.0727782473 0.0669322412 0.0799160451 0.0063287726 0.4336380000 0.0794280000 0.0897870000 0.0000010000 0.2610780000 0.0017920000 137151523 0 402718720 3.9127032757 3.9497880936 3.9289529324 517 1311867187.6707689762 0.0726495534 0.0669432998 0.0799160451 0.0063342563 0.7549690000 0.0978780000 0.0944030000 0.0314090000 0.2608180000 0.2689250000 137155251 0 402718720 3.9162642956 3.9515850544 3.9280025959 518 1311867187.7035770416 0.0715552345 0.0669522032 0.0799160451 0.0063311431 0.4349850000 0.0796850000 0.0901450000 0.0000010000 0.2617990000 0.0018030000 137158979 0 402718720 3.9210133553 3.9519984722 3.9272332191 519 1311867187.7345480919 0.0720923170 0.0669621070 0.0799160451 0.0063375277 0.4712780000 0.0800830000 0.0948820000 0.0314630000 0.2613400000 0.0019090000 137162371 0 402718720 3.9206728935 3.9492824078 3.9257640839 520 1311867187.7707819939 0.0720495284 0.0669718905 0.0799160451 0.0063414324 0.4396450000 0.0793560000 0.0948220000 0.0000010000 0.2621110000 0.0017960000 137166155 0 402718720 3.9230952263 3.9524273872 3.9250075817 521 1311867187.8017508984 0.0714667588 0.0669805179 0.0799160451 0.0063388075 0.6982810000 0.0781190000 0.0525070000 0.0307900000 0.2635160000 0.2718050000 137169827 0 402718720 3.9265186787 3.9525063038 3.9240598679 522 1311867187.8339610100 0.0720984265 0.0669903224 0.0799160451 0.0063345781 0.4361460000 0.0791210000 0.0896150000 0.0000010000 0.2640340000 0.0017980000 137173499 0 402718720 3.9272799492 3.9522750378 3.9231317043 523 1311867187.8708090782 0.0717473105 0.0669994179 0.0799160451 0.0063346539 0.4852920000 0.0922020000 0.0947960000 0.0314510000 0.2634770000 0.0018050000 137177283 0 402718720 3.9302580357 3.9538590908 3.9225172997 524 1311867187.9038810730 0.0725632384 0.0670100359 0.0799160451 0.0063356147 0.4173070000 0.0789130000 0.0709770000 0.0000010000 0.2640540000 0.0017880000 137181067 0 402718720 3.9312884808 3.9541652203 3.9218358994 525 1311867187.9363000393 0.0702873021 0.0670162783 0.0799160451 0.0063314779 0.7351140000 0.0791000000 0.0890310000 0.0307670000 0.2632180000 0.2714430000 137184683 0 402718720 3.9370551109 3.9543848038 3.9209527969 526 1311867187.9713420868 0.0705653802 0.0670230257 0.0799160451 0.0063316351 0.4361270000 0.0792890000 0.0898100000 0.0000010000 0.2636610000 0.0017960000 137188467 0 402718720 3.9392099380 3.9530556202 3.9195919037 527 1311867188.0047569275 0.0710183978 0.0670306070 0.0799160451 0.0063500855 0.4671420000 0.0790890000 0.0896900000 0.0310150000 0.2639770000 0.0018000000 137192195 0 402718720 3.9422340393 3.9543530941 3.9185357094 528 1311867188.0333108902 0.0713684782 0.0670388227 0.0799160451 0.0063556711 0.4107880000 0.0797230000 0.0631840000 0.0000000000 0.2645130000 0.0017950000 137195755 0 402718720 3.9449923038 3.9553029537 3.9177553654 529 1311867188.0698699951 0.0696617886 0.0670437810 0.0799160451 0.0063516930 0.7122860000 0.0797240000 0.0602790000 0.0315050000 0.2653010000 0.2739330000 137199483 0 402718720 3.9504687786 3.9529287815 3.9163873196 530 1311867188.1088800430 0.0709565803 0.0670511637 0.0799160451 0.0063502411 0.4202760000 0.0918730000 0.0602370000 0.0000010000 0.2647870000 0.0018000000 137203435 0 402718720 3.9517467022 3.9532775879 3.9147713184 531 1311867188.1359970570 0.0694201961 0.0670556251 0.0799160451 0.0063556922 0.4661320000 0.0786410000 0.0893220000 0.0310200000 0.2637880000 0.0017920000 137206939 0 402718720 3.9552285671 3.9556322098 3.9136660099 532 1311867188.1703350544 0.0707388595 0.0670625485 0.0799160451 0.0063536083 0.4201660000 0.0786320000 0.0744780000 0.0000010000 0.2636840000 0.0017910000 137210667 0 402718720 3.9577784538 3.9539747238 3.9123384953 533 1311867188.2026720047 0.0709312111 0.0670698068 0.0799160451 0.0063540248 0.7562890000 0.0978940000 0.0945890000 0.0315470000 0.2615960000 0.2690950000 137214395 0 402718720 3.9597041607 3.9534294605 3.9107992649 534 1311867188.2352449894 0.0690271631 0.0670734722 0.0799160451 0.0063619275 0.4362670000 0.0785090000 0.0909660000 0.0000000000 0.2634060000 0.0017820000 137218011 0 402718720 3.9654016495 3.9550189972 3.9098706245 535 1311867188.2706460953 0.0704141408 0.0670797165 0.0799160451 0.0063601277 0.4659960000 0.0783260000 0.0885350000 0.0310590000 0.2647140000 0.0017910000 137221795 0 402718720 3.9675850868 3.9549920559 3.9087786674 536 1311867188.3047339916 0.0708481520 0.0670867471 0.0799160451 0.0063545845 0.4141950000 0.0776690000 0.0663300000 0.0000010000 0.2668340000 0.0017800000 137225579 0 402718720 3.9705975056 3.9553549290 3.9075853825 537 1311867188.3398799896 0.0720362589 0.0670959641 0.0799160451 0.0063494664 0.7692890000 0.0770380000 0.0871420000 0.0312900000 0.2819660000 0.2901390000 137229363 0 402718720 3.9723474979 3.9561290741 3.9064910412 538 1311867188.3718800545 0.0731473640 0.0671072121 0.0799160451 0.0063547806 0.4391640000 0.0786290000 0.0873540000 0.0000010000 0.2698000000 0.0017730000 137232979 0 402718720 3.9740211964 3.9589488506 3.9060852528 539 1311867188.4054470062 0.0717852414 0.0671158912 0.0799160451 0.0063596573 0.4673390000 0.1025470000 0.0612800000 0.0310760000 0.2689200000 0.0018550000 137236651 0 402718720 3.9787075520 3.9587931633 3.9055023193 540 1311867188.4398789406 0.0715009570 0.0671240116 0.0799160451 0.0063580252 0.4276450000 0.0768390000 0.0766430000 0.0000010000 0.2707780000 0.0017750000 137240435 0 402718720 3.9818208218 3.9582245350 3.9046952724 541 1311867188.4724500179 0.0727569088 0.0671344237 0.0799160451 0.0063634407 0.7314520000 0.0883290000 0.0586710000 0.0314920000 0.2718170000 0.2795440000 137244107 0 402718720 3.9837126732 3.9615898132 3.9043369293 542 1311867188.5049159527 0.0720952749 0.0671435765 0.0799160451 0.0063654050 0.4402160000 0.0769470000 0.0889020000 0.0000010000 0.2709990000 0.0017750000 137247779 0 402718720 3.9876518250 3.9618849754 3.9040522575 543 1311867188.5389990807 0.0719753057 0.0671524747 0.0799160451 0.0063658067 0.4638250000 0.1039530000 0.0541980000 0.0315380000 0.2706050000 0.0018660000 137251563 0 402718720 3.9897785187 3.9610292912 3.9032468796 544 1311867188.5723888874 0.0738137141 0.0671647197 0.0799160451 0.0063861036 0.4401180000 0.0769250000 0.0872530000 0.0000000000 0.2725600000 0.0017770000 137255235 0 402718720 3.9912376404 3.9655411243 3.9031362534 545 1311867188.6045958996 0.0731111914 0.0671756306 0.0799160451 0.0063808633 0.7491420000 0.0776250000 0.0926170000 0.0315310000 0.2688670000 0.2769150000 137258907 0 402718720 3.9951660633 3.9653496742 3.9031276703 546 1311867188.6398339272 0.0727018490 0.0671857519 0.0799160451 0.0063799113 0.4391490000 0.0773830000 0.0876520000 0.0000010000 0.2707280000 0.0017810000 137262579 0 402718720 3.9980845451 3.9635527134 3.9027922153 547 1311867188.6715080738 0.0743587166 0.0671988652 0.0799160451 0.0063848357 0.4598090000 0.0876360000 0.0655090000 0.0314460000 0.2718390000 0.0017710000 137266307 0 402718720 3.9988195896 3.9658131599 3.9021272659 548 1311867188.7038300037 0.0744774267 0.0672121472 0.0799160451 0.0063870997 0.4321340000 0.0891830000 0.0660290000 0.0000010000 0.2735120000 0.0017740000 137269979 0 402718720 4.0009751320 3.9643101692 3.9013342857 549 1311867188.7393829823 0.0744077563 0.0672252540 0.0799160451 0.0063981046 0.7571220000 0.0776260000 0.0876860000 0.0310480000 0.2757920000 0.2833800000 137273707 0 402718720 4.0038905144 3.9636874199 3.9002842903 550 1311867188.7721049786 0.0774163082 0.0672437832 0.0799160451 0.0063951426 0.4465440000 0.0757230000 0.0873410000 0.0000010000 0.2800850000 0.0017710000 137277435 0 402718720 4.0039315224 3.9660556316 3.8991465569 551 1311867188.8045220375 0.0772602931 0.0672619619 0.0799160451 0.0063898841 0.4679550000 0.0767180000 0.0764880000 0.0309910000 0.2803830000 0.0017750000 137281163 0 402718720 4.0087676048 3.9674732685 3.8983070850 552 1311867188.8402431011 0.0782033727 0.0672817833 0.0799160451 0.0063850765 0.4502600000 0.0766850000 0.0869800000 0.0000000000 0.2832150000 0.0017660000 137284891 0 402718720 4.0119199753 3.9661791325 3.8974096775 553 1311867188.8705990314 0.0810393244 0.0673066614 0.0810393244 0.0063867917 0.7893500000 0.1059000000 0.0688220000 0.0314440000 0.2865760000 0.2950090000 137288507 0 402718720 4.0118370056 3.9675047398 3.8963112831 554 1311867188.9016311169 0.0818387344 0.0673328925 0.0818387344 0.0063843779 0.4367370000 0.0759510000 0.0647760000 0.0000000000 0.2926400000 0.0017510000 137292179 0 402718720 4.0150489807 3.9701471329 3.8952004910 555 1311867188.9401769638 0.0823159292 0.0673598890 0.0823159292 0.0063832846 0.4784240000 0.0755240000 0.0729150000 0.0313510000 0.2952580000 0.0017600000 137296075 0 402718720 4.0188746452 3.9689204693 3.8941078186 556 1311867188.9709990025 0.0831215307 0.0673882373 0.0831215307 0.0063833948 0.4603550000 0.0731350000 0.0843610000 0.0000010000 0.2995150000 0.0017100000 137299635 0 402718720 4.0208206177 3.9684689045 3.8932940960 557 1311867189.0052258968 0.0831894949 0.0674166058 0.0831894949 0.0063789615 0.7738270000 0.0740020000 0.0566840000 0.0313050000 0.3009500000 0.3092910000 137303419 0 402718720 4.0249767303 3.9698288441 3.8927223682 558 1311867189.0400099754 0.0825619847 0.0674437480 0.0831894949 0.0063791877 0.4504470000 0.0857830000 0.0597470000 0.0000010000 0.3015440000 0.0017510000 137307091 0 402718720 4.0302734375 3.9690005779 3.8926858902 559 1311867189.0724329948 0.0814092308 0.0674687310 0.0831894949 0.0063765495 0.5017800000 0.0743080000 0.0886020000 0.0313510000 0.3041610000 0.0017400000 137310875 0 402718720 4.0345153809 3.9680888653 3.8928072453 560 1311867189.1026360989 0.0804205686 0.0674918593 0.0831894949 0.0063723484 0.4940860000 0.1001720000 0.0834290000 0.0000010000 0.3071400000 0.0017210000 137314491 0 402718720 4.0390930176 3.9689307213 3.8934469223 561 1311867189.1417639256 0.0795071200 0.0675132769 0.0831894949 0.0063667787 0.8191980000 0.0733270000 0.0877480000 0.0309480000 0.3085870000 0.3169580000 137318387 0 402718720 4.0438594818 3.9691603184 3.8942615986 562 1311867189.1717920303 0.0803844631 0.0675361793 0.0831894949 0.0063631649 0.4474670000 0.0860820000 0.0490390000 0.0000000000 0.3089890000 0.0017200000 137322003 0 402718720 4.0439410210 3.9686582088 3.8949296474 563 1311867189.2019069195 0.0794461295 0.0675573338 0.0831894949 0.0063598792 0.5151240000 0.0856750000 0.0853470000 0.0308590000 0.3098860000 0.0017260000 137325619 0 402718720 4.0479259491 3.9689807892 3.8961493969 564 1311867189.2390630245 0.0795489177 0.0675785954 0.0831894949 0.0063549689 0.4376320000 0.0736800000 0.0518820000 0.0000000000 0.3085030000 0.0018290000 137329403 0 402718720 4.0501084328 3.9686353207 3.8970758915 565 1311867189.2722640038 0.0790614933 0.0675989192 0.0831894949 0.0063512161 0.7865760000 0.0735870000 0.0517500000 0.0313480000 0.3096990000 0.3185700000 137333075 0 402718720 4.0526375771 3.9676165581 3.8978924751 566 1311867189.3046789169 0.0796555653 0.0676202207 0.0831894949 0.0063460613 0.4372660000 0.0733460000 0.0422770000 0.0000010000 0.3182620000 0.0017310000 137336803 0 402718720 4.0542597771 3.9668257236 3.8987953663 567 1311867189.3397970200 0.0778768957 0.0676383100 0.0831894949 0.0063554124 0.4647120000 0.0717020000 0.0485430000 0.0312780000 0.3098400000 0.0017200000 137340531 0 402718720 4.0583629608 3.9652512074 3.8994445801 568 1311867189.3720359802 0.0781634971 0.0676568403 0.0831894949 0.0063840834 0.4804850000 0.0837350000 0.0830880000 0.0000000000 0.3103000000 0.0017140000 137344203 0 402718720 4.0613780022 3.9647874832 3.8998796940 569 1311867189.4056949615 0.0785508156 0.0676759861 0.0831894949 0.0063820005 0.7967610000 0.0712560000 0.0650440000 0.0306340000 0.3094570000 0.3187570000 137347931 0 402718720 4.0641374588 3.9653403759 3.9011988640 570 1311867189.4405019283 0.0779180229 0.0676939546 0.0831894949 0.0063861633 0.4618090000 0.0917300000 0.0582310000 0.0000010000 0.3084870000 0.0017240000 137351659 0 402718720 4.0680041313 3.9631788731 3.9017691612 571 1311867189.4729130268 0.0776152164 0.0677113298 0.0831894949 0.0063812164 0.4920170000 0.0724540000 0.0759880000 0.0312470000 0.3089760000 0.0017120000 137355387 0 402718720 4.0722022057 3.9611511230 3.9020864964 572 1311867189.5060400963 0.0783559456 0.0677299393 0.0831894949 0.0063791051 0.4717360000 0.0725690000 0.0874280000 0.0000000000 0.3083760000 0.0017100000 137359059 0 402718720 4.0749382973 3.9617142677 3.9024252892 573 1311867189.5394289494 0.0769804567 0.0677460833 0.0831894949 0.0063738821 0.8129350000 0.0864920000 0.0639080000 0.0313430000 0.3101590000 0.3193900000 137362731 0 402718720 4.0799865723 3.9592225552 3.9022281170 574 1311867189.5720269680 0.0775594488 0.0677631798 0.0831894949 0.0063705292 0.4571820000 0.0722630000 0.0700220000 0.0000010000 0.3115450000 0.0017090000 137366459 0 402718720 4.0820126534 3.9567341805 3.9013051987 575 1311867189.6112909317 0.0782088563 0.0677813462 0.0831894949 0.0063670083 0.5001550000 0.0706880000 0.0814750000 0.0305560000 0.3140870000 0.0017110000 137370299 0 402718720 4.0868310928 3.9568943977 3.9011058807 576 1311867189.6424219608 0.0792020932 0.0678011739 0.0831894949 0.0063636627 0.4644530000 0.0838980000 0.0623640000 0.0000010000 0.3148380000 0.0017070000 137373971 0 402718720 4.0893712044 3.9564888477 3.9009799957 577 1311867189.6728401184 0.0787512809 0.0678201515 0.0831894949 0.0063584184 0.7973920000 0.0729130000 0.0556200000 0.0312820000 0.3134730000 0.3224670000 137377643 0 402718720 4.0932202339 3.9546406269 3.9006962776 578 1311867189.7065870762 0.0804433376 0.0678419909 0.0831894949 0.0063571637 0.4871660000 0.0861870000 0.0828100000 0.0000010000 0.3147920000 0.0017070000 137381315 0 402718720 4.0957794189 3.9542405605 3.9009101391 579 1311867189.7401719093 0.0803155154 0.0678635342 0.0831894949 0.0063526768 0.4741850000 0.0728260000 0.0587850000 0.0308130000 0.3082230000 0.0018170000 137385043 0 402718720 4.1008629799 3.9546411037 3.9020009041 580 1311867189.7729759216 0.0823512673 0.0678885130 0.0831894949 0.0063490554 0.4515780000 0.0950650000 0.0429930000 0.0000010000 0.3101350000 0.0017330000 137388715 0 402718720 4.1019010544 3.9544239044 3.9027123451 581 1311867189.8073968887 0.0808824152 0.0679108777 0.0831894949 0.0063470292 0.8209380000 0.0747260000 0.0892830000 0.0309210000 0.3076550000 0.3167160000 137392443 0 402718720 4.1066613197 3.9526045322 3.9034225941 582 1311867189.8405311108 0.0823494419 0.0679356863 0.0831894949 0.0063448594 0.4425100000 0.0731950000 0.0564590000 0.0000010000 0.3094560000 0.0017360000 137396115 0 402718720 4.1086549759 3.9529016018 3.9042747021 583 1311867189.8713529110 0.0814424753 0.0679588540 0.0831894949 0.0063410665 0.4786830000 0.0911710000 0.0451680000 0.0313220000 0.3076200000 0.0017350000 137399787 0 402718720 4.1130976677 3.9519712925 3.9051134586 584 1311867189.9102680683 0.0818095505 0.0679825709 0.0831894949 0.0063411301 0.4447720000 0.0749490000 0.0567590000 0.0000010000 0.3096680000 0.0017360000 137403627 0 402718720 4.1155276299 3.9501287937 3.9050238132 585 1311867189.9402260780 0.0817515254 0.0680061076 0.0831894949 0.0063368599 0.7948460000 0.0729040000 0.0663140000 0.0311430000 0.3069250000 0.3159280000 137407299 0 402718720 4.1187353134 3.9503922462 3.9051845074 586 1311867189.9727621078 0.0810252652 0.0680283246 0.0831894949 0.0063315047 0.4588160000 0.0747750000 0.0745040000 0.0000010000 0.3059670000 0.0018310000 137410971 0 402718720 4.1234636307 3.9508090019 3.9055974483 587 1311867190.0107009411 0.0812036172 0.0680507697 0.0831894949 0.0063295225 0.4975590000 0.0749110000 0.0818800000 0.0313560000 0.3060210000 0.0017360000 137414755 0 402718720 4.1268854141 3.9494535923 3.9055652618 588 1311867190.0402929783 0.0813413933 0.0680733728 0.0831894949 0.0063251135 0.4844410000 0.0887350000 0.0850690000 0.0000000000 0.3072010000 0.0017430000 137418371 0 402718720 4.1299839020 3.9492177963 3.9056229591 589 1311867190.0719039440 0.0813206434 0.0680958640 0.0831894949 0.0063202663 0.7983200000 0.0747740000 0.0707870000 0.0313560000 0.3059770000 0.3137640000 137422043 0 402718720 4.1330714226 3.9485251904 3.9054996967 590 1311867190.1096539497 0.0890794173 0.0681314293 0.0890794173 0.0063338698 0.4685290000 0.0979770000 0.0603400000 0.0000010000 0.3067880000 0.0017410000 137425883 0 402718720 4.1254167557 3.9478447437 3.9038050175 591 1311867190.1396369934 0.0897229314 0.0681679631 0.0897229314 0.0063308940 0.4825050000 0.0745550000 0.0501430000 0.0313590000 0.3222990000 0.0023310000 137429555 0 402718720 4.1277327538 3.9484724998 3.9032437801 592 1311867190.1706380844 0.0897184461 0.0682043660 0.0897229314 0.0063385573 0.5353000000 0.0950770000 0.1128670000 0.0000010000 0.3232170000 0.0023230000 137433115 0 402718720 4.1304726601 3.9473397732 3.9030609131 593 1311867190.2096021175 0.0901058689 0.0682412994 0.0901058689 0.0063334313 0.8383980000 0.0863290000 0.0849620000 0.0313400000 0.3129140000 0.3211680000 137437011 0 402718720 4.1322379112 3.9457690716 3.9015858173 594 1311867190.2394330502 0.0898262486 0.0682776377 0.0901058689 0.0063355854 0.4460770000 0.0738740000 0.0496170000 0.0000000000 0.3191680000 0.0017330000 137440571 0 402718720 4.1359038353 3.9472410679 3.9009633064 595 1311867190.2714810371 0.0892437175 0.0683128748 0.0901058689 0.0063382742 0.5084820000 0.0736080000 0.0863140000 0.0313140000 0.3136680000 0.0018110000 137444299 0 402718720 4.1394710541 3.9467799664 3.9005415440 596 1311867190.3072700500 0.0902480558 0.0683496788 0.0902480558 0.0063338948 0.4447030000 0.0738760000 0.0520920000 0.0000010000 0.3153350000 0.0017230000 137448083 0 402718720 4.1410179138 3.9463415146 3.8999731541 597 1311867190.3414731026 0.0902872309 0.0683864251 0.0902872309 0.0063316652 0.8037030000 0.0733410000 0.0559370000 0.0313710000 0.3162630000 0.3251150000 137451811 0 402718720 4.1443624496 3.9469337463 3.9001910686 598 1311867190.3716828823 0.0894054025 0.0684215739 0.0902872309 0.0063319483 0.4535050000 0.0845410000 0.0493260000 0.0000010000 0.3162380000 0.0017140000 137455427 0 402718720 4.1486597061 3.9481141567 3.9006137848 599 1311867190.4101090431 0.0909059495 0.0684591104 0.0909059495 0.0063314328 0.4658620000 0.0733360000 0.0424010000 0.0313100000 0.3154150000 0.0017210000 137459211 0 402718720 4.1494059563 3.9470884800 3.9004032612 600 1311867190.4394960403 0.0913597047 0.0684972781 0.0913597047 0.0063288238 0.4549690000 0.0916430000 0.0447750000 0.0000010000 0.3151450000 0.0017220000 137462939 0 402718720 4.1522212029 3.9487411976 3.9013171196 601 1311867190.4708199501 0.0915772691 0.0685356807 0.0915772691 0.0063248903 0.7867130000 0.0737110000 0.0426720000 0.0308780000 0.3145580000 0.3232030000 137466499 0 402718720 4.1547179222 3.9481055737 3.9020545483 602 1311867190.5097529888 0.0915986300 0.0685739913 0.0915986300 0.0063203144 0.4491530000 0.0732560000 0.0593100000 0.0000000000 0.3129860000 0.0018140000 137470451 0 402718720 4.1567978859 3.9467415810 3.9021680355 603 1311867190.5405189991 0.0926570445 0.0686139300 0.0926570445 0.0063229277 0.5240910000 0.0874520000 0.0888620000 0.0313080000 0.3130540000 0.0017250000 137474011 0 402718720 4.1589045525 3.9478931427 3.9027287960 604 1311867190.5708439350 0.0928660557 0.0686540825 0.0928660557 0.0063188015 0.4457940000 0.0745030000 0.0526450000 0.0000000000 0.3152080000 0.0017330000 137477627 0 402718720 4.1611304283 3.9471707344 3.9034571648 605 1311867190.6067750454 0.0928852409 0.0686941340 0.0928852409 0.0063139605 0.8357180000 0.0742560000 0.0708540000 0.0312760000 0.3281540000 0.3294870000 137481411 0 402718720 4.1634597778 3.9460322857 3.9035606384 606 1311867190.6389939785 0.0930142775 0.0687342663 0.0930142775 0.0063099987 0.4457150000 0.0748850000 0.0501640000 0.0000010000 0.3172150000 0.0017390000 137485139 0 402718720 4.1662817001 3.9468085766 3.9042944908 607 1311867190.6723659039 0.0923285112 0.0687731365 0.0930142775 0.0063059878 0.4850090000 0.0748230000 0.0572960000 0.0312940000 0.3181480000 0.0017330000 137488811 0 402718720 4.1698999405 3.9451394081 3.9050600529 608 1311867190.7114980221 0.0926995948 0.0688124893 0.0930142775 0.0063031124 0.4607020000 0.0880120000 0.0503620000 0.0000010000 0.3188790000 0.0017360000 137492651 0 402718720 4.1724863052 3.9452555180 3.9057681561 609 1311867190.7392649651 0.0924115032 0.0688512397 0.0930142775 0.0062982418 0.8090900000 0.0752630000 0.0573400000 0.0313130000 0.3176370000 0.3258400000 137496155 0 402718720 4.1747817993 3.9449875355 3.9062364101 610 1311867190.7751801014 0.0926198959 0.0688902047 0.0930142775 0.0062938059 0.4633420000 0.0907920000 0.0531110000 0.0000000000 0.3159770000 0.0017360000 137499939 0 402718720 4.1770610809 3.9452347755 3.9067738056 611 1311867190.8070900440 0.0931621715 0.0689299297 0.0931621715 0.0062899807 0.5122780000 0.0751800000 0.0856080000 0.0312410000 0.3167970000 0.0017380000 137503667 0 402718720 4.1788787842 3.9447185993 3.9075412750 612 1311867190.8414280415 0.0918397382 0.0689673640 0.0931621715 0.0062921775 0.4465910000 0.0756790000 0.0506200000 0.0000010000 0.3168220000 0.0017430000 137507395 0 402718720 4.1825399399 3.9431793690 3.9083025455 613 1311867190.8739249706 0.0936202779 0.0690075808 0.0936202779 0.0062886287 0.8235870000 0.0957530000 0.0577910000 0.0313280000 0.3145140000 0.3225000000 137511067 0 402718720 4.1827821732 3.9424684048 3.9088439941 614 1311867190.9076139927 0.0938060805 0.0690479693 0.0938060805 0.0062839059 0.4446370000 0.0754060000 0.0532660000 0.0000010000 0.3123100000 0.0018360000 137514795 0 402718720 4.1851243973 3.9425756931 3.9096267223 615 1311867190.9393599033 0.0923481435 0.0690858557 0.0938060805 0.0062808757 0.4676120000 0.0758020000 0.0437220000 0.0313450000 0.3132860000 0.0017530000 137518411 0 402718720 4.1887373924 3.9404485226 3.9103758335 616 1311867190.9741609097 0.0919978172 0.0691230505 0.0938060805 0.0062766029 0.4363330000 0.0751260000 0.0435420000 0.0000010000 0.3142000000 0.0017350000 137522195 0 402718720 4.1914429665 3.9395258427 3.9104974270 617 1311867191.0085949898 0.0930227488 0.0691617858 0.0938060805 0.0062812020 0.8092610000 0.0752220000 0.0647620000 0.0313500000 0.3140470000 0.3221740000 137525923 0 402718720 4.1938171387 3.9414763451 3.9115440845 618 1311867191.0396919250 0.0930152088 0.0692003836 0.0938060805 0.0062772231 0.4497330000 0.0886710000 0.0435770000 0.0000000000 0.3140190000 0.0017390000 137529595 0 402718720 4.1961832047 3.9412987232 3.9124789238 619 1311867191.0764329433 0.0926356465 0.0692382435 0.0938060805 0.0062746669 0.4782160000 0.0754260000 0.0527750000 0.0308460000 0.3156830000 0.0017470000 137533379 0 402718720 4.1979975700 3.9376552105 3.9126276970 620 1311867191.1103041172 0.0937261209 0.0692777400 0.0938060805 0.0062806680 0.4538650000 0.0761330000 0.0580200000 0.0000010000 0.3162430000 0.0017490000 137537107 0 402718720 4.2007575035 3.9387505054 3.9138367176 621 1311867191.1388139725 0.0928152353 0.0693156426 0.0938060805 0.0062887356 0.8252580000 0.0918440000 0.0611760000 0.0308940000 0.3151170000 0.3245060000 137540723 0 402718720 4.2043523788 3.9383890629 3.9148669243 622 1311867191.1742820740 0.0936746076 0.0693548049 0.0938060805 0.0062848666 0.4636780000 0.0763350000 0.0661610000 0.0000010000 0.3176900000 0.0017530000 137544451 0 402718720 4.2056932449 3.9370205402 3.9152040482 623 1311867191.2077920437 0.0935757533 0.0693936828 0.0938060805 0.0062800262 0.4872430000 0.0894900000 0.0462290000 0.0313340000 0.3167210000 0.0017160000 137548179 0 402718720 4.2094292641 3.9378156662 3.9162790775 624 1311867191.2408421040 0.0944572836 0.0694338489 0.0944572836 0.0062759383 0.4500790000 0.0769650000 0.0539400000 0.0000010000 0.3156960000 0.0017570000 137551907 0 402718720 4.2112998962 3.9376585484 3.9169936180 625 1311867191.2769579887 0.0951988026 0.0694750728 0.0951988026 0.0062727012 0.8262590000 0.0891620000 0.0586760000 0.0382130000 0.3154950000 0.3229730000 137555635 0 402718720 4.2133622169 3.9369194508 3.9175298214 626 1311867191.3085029125 0.0953146219 0.0695163500 0.0953146219 0.0062729345 0.4470900000 0.0757170000 0.0512350000 0.0000010000 0.3166720000 0.0017060000 137559139 0 402718720 4.2164764404 3.9381384850 3.9183921814 627 1311867191.3404779434 0.0955973342 0.0695579465 0.0955973342 0.0062688372 0.4851700000 0.0764640000 0.0582830000 0.0312640000 0.3156710000 0.0017550000 137562811 0 402718720 4.2187767029 3.9378271103 3.9191436768 628 1311867191.3794629574 0.0956853181 0.0695995506 0.0956853181 0.0062651493 0.4681350000 0.0902400000 0.0587510000 0.0000010000 0.3156410000 0.0017660000 137566707 0 402718720 4.2203373909 3.9353401661 3.9195337296 629 1311867191.4091579914 0.0952940062 0.0696404003 0.0956853181 0.0062616011 0.8144030000 0.0768070000 0.0655110000 0.0309000000 0.3160210000 0.3234500000 137570267 0 402718720 4.2231841087 3.9349946976 3.9202053547 630 1311867191.4415969849 0.0946111530 0.0696800364 0.0956853181 0.0062573113 0.4408180000 0.0767760000 0.0441750000 0.0000010000 0.3163760000 0.0017580000 137573939 0 402718720 4.2273173332 3.9361171722 3.9213318825 631 1311867191.4775309563 0.0953267962 0.0697206810 0.0956853181 0.0062576961 0.4866640000 0.0755330000 0.0580980000 0.0311040000 0.3184200000 0.0017590000 137577667 0 402718720 4.2278976440 3.9342262745 3.9214758873 632 1311867191.5075590611 0.0953316540 0.0697612047 0.0956853181 0.0062536248 0.4611460000 0.0882050000 0.0514150000 0.0000010000 0.3180240000 0.0017550000 137581227 0 402718720 4.2301945686 3.9353177547 3.9222345352 633 1311867191.5390620232 0.0951095000 0.0698012494 0.0956853181 0.0062487145 0.8381630000 0.0950480000 0.0617790000 0.0314000000 0.3157150000 0.3323170000 137584899 0 402718720 4.2321281433 3.9344182014 3.9227600098 634 1311867191.5764698982 0.0951091945 0.0698411673 0.0956853181 0.0062449684 0.5211240000 0.0983000000 0.0875910000 0.0000010000 0.3309400000 0.0023740000 137588683 0 402718720 4.2346210480 3.9339442253 3.9237318039 635 1311867191.6118669510 0.0959282890 0.0698822494 0.0959282890 0.0062718226 0.5444650000 0.0981710000 0.0876890000 0.0382030000 0.3168850000 0.0017640000 137592467 0 402718720 4.2367739677 3.9359915257 3.9246094227 636 1311867191.6451880932 0.0954897329 0.0699225127 0.0959282890 0.0062679722 0.4488630000 0.0771910000 0.0515550000 0.0000010000 0.3165790000 0.0017600000 137596139 0 402718720 4.2389006615 3.9353370667 3.9256224632 637 1311867191.6827919483 0.0937591791 0.0699599329 0.0959282890 0.0062712904 0.8573220000 0.0776790000 0.0878190000 0.0313350000 0.3229360000 0.3356380000 137600035 0 402718720 4.2422590256 3.9339621067 3.9266896248 638 1311867191.7119400501 0.0942344069 0.0699979807 0.0959282890 0.0062700003 0.5388380000 0.0995700000 0.1176680000 0.0000000000 0.3180610000 0.0017700000 137603595 0 402718720 4.2438788414 3.9353888035 3.9276010990 639 1311867191.7457199097 0.0939509347 0.0700354658 0.0959282890 0.0062887456 0.4985410000 0.0908790000 0.0590870000 0.0312600000 0.3137830000 0.0017760000 137607211 0 402718720 4.2446827888 3.9340169430 3.9281017780 640 1311867191.7763800621 0.0948276743 0.0700742036 0.0959282890 0.0062939904 0.4819820000 0.0784210000 0.0810910000 0.0000000000 0.3181510000 0.0023800000 137610827 0 402718720 4.2455196381 3.9347157478 3.9289946556 641 1311867191.8097250462 0.0933817774 0.0701105649 0.0959282890 0.0062909131 0.8214540000 0.0809450000 0.0739610000 0.0312890000 0.3131720000 0.3203190000 137614555 0 402718720 4.2490181923 3.9348585606 3.9306216240 642 1311867191.8395779133 0.0922769010 0.0701450919 0.0959282890 0.0062955363 0.4415300000 0.0786000000 0.0470770000 0.0000010000 0.3122740000 0.0017880000 137618171 0 402718720 4.2507629395 3.9337615967 3.9310266972 643 1311867191.8745219707 0.0928172469 0.0701803518 0.0959282890 0.0062979060 0.4898920000 0.0891380000 0.0549460000 0.0313860000 0.3108640000 0.0017820000 137621899 0 402718720 4.2519779205 3.9344301224 3.9322826862 644 1311867191.9077119827 0.0915529802 0.0702135391 0.0959282890 0.0062942219 0.4836450000 0.0781560000 0.0914710000 0.0000010000 0.3104700000 0.0017720000 137625627 0 402718720 4.2548327446 3.9345028400 3.9336640835 645 1311867191.9391601086 0.0921741575 0.0702475866 0.0959282890 0.0062917310 0.8273680000 0.0789490000 0.0889660000 0.0312710000 0.3096660000 0.3167510000 137629299 0 402718720 4.2544932365 3.9323766232 3.9340744019 646 1311867191.9755239487 0.0914220288 0.0702803644 0.0959282890 0.0062910947 0.4741670000 0.0792130000 0.0817980000 0.0000000000 0.3095960000 0.0017710000 137633027 0 402718720 4.2571649551 3.9331758022 3.9354441166 647 1311867192.0076289177 0.0917133465 0.0703134911 0.0959282890 0.0062867101 0.5239990000 0.0912360000 0.0894130000 0.0313260000 0.3084430000 0.0017860000 137636699 0 402718720 4.2582268715 3.9332671165 3.9361650944 648 1311867192.0447950363 0.0913021564 0.0703458810 0.0959282890 0.0062963908 0.4447800000 0.0793190000 0.0525490000 0.0000000000 0.3093230000 0.0017770000 137640539 0 402718720 4.2588281631 3.9308533669 3.9364058971 649 1311867192.0751929283 0.0932235718 0.0703811317 0.0959282890 0.0062977948 0.8049490000 0.0775550000 0.0698820000 0.0306670000 0.3087160000 0.3163500000 137644099 0 402718720 4.2580461502 3.9318759441 3.9368715286 650 1311867192.1073920727 0.0919667557 0.0704143403 0.0959282890 0.0062947870 0.4517600000 0.0794210000 0.0600120000 0.0000000000 0.3087490000 0.0017770000 137647827 0 402718720 4.2622003555 3.9331912994 3.9385557175 651 1311867192.1433029175 0.0929969773 0.0704490295 0.0959282890 0.0062988975 0.5412200000 0.1062320000 0.0800680000 0.0381080000 0.3132280000 0.0017910000 137651611 0 402718720 4.2610692978 3.9305927753 3.9383726120 652 1311867192.1754670143 0.0936476812 0.0704846102 0.0959282890 0.0063041750 0.4382160000 0.0793540000 0.0450670000 0.0000000000 0.3102140000 0.0017820000 137655283 0 402718720 4.2623720169 3.9317219257 3.9392328262 653 1311867192.2077538967 0.0937809870 0.0705202862 0.0959282890 0.0063007538 0.8183750000 0.0999800000 0.0599190000 0.0312810000 0.3093220000 0.3160990000 137659011 0 402718720 4.2645359039 3.9325416088 3.9405152798 654 1311867192.2451250553 0.0930908993 0.0705547978 0.0959282890 0.0063102034 0.4435740000 0.0796180000 0.0507420000 0.0000010000 0.3096130000 0.0017800000 137662851 0 402718720 4.2657980919 3.9295942783 3.9412648678 655 1311867192.2744629383 0.0935248584 0.0705898666 0.0959282890 0.0063083467 0.4689590000 0.0790460000 0.0451100000 0.0312810000 0.3099500000 0.0017890000 137666411 0 402718720 4.2677607536 3.9317343235 3.9419724941 656 1311867192.3067719936 0.0936738178 0.0706250555 0.0959282890 0.0063061890 0.4821250000 0.0794010000 0.0892080000 0.0000000000 0.3099210000 0.0017800000 137670083 0 402718720 4.2695093155 3.9307439327 3.9431648254 657 1311867192.3427391052 0.0936227366 0.0706600596 0.0959282890 0.0063032189 0.8024970000 0.0795010000 0.0623210000 0.0312370000 0.3104480000 0.3172190000 137673867 0 402718720 4.2708835602 3.9289700985 3.9435811043 658 1311867192.3755910397 0.0944061875 0.0706961480 0.0959282890 0.0063049162 0.4673250000 0.0929220000 0.0597270000 0.0000010000 0.3110640000 0.0017800000 137677595 0 402718720 4.2725453377 3.9295768738 3.9441380501 659 1311867192.4059340954 0.0935062096 0.0707307611 0.0959282890 0.0063006990 0.5068450000 0.0799130000 0.0820080000 0.0312310000 0.3101120000 0.0017890000 137681155 0 402718720 4.2757143974 3.9290893078 3.9448492527 660 1311867192.4447100163 0.0953917280 0.0707681262 0.0959282890 0.0062971995 0.4538070000 0.0793490000 0.0595870000 0.0000000000 0.3112720000 0.0017740000 137685051 0 402718720 4.2757101059 3.9274933338 3.9448862076 661 1311867192.4748210907 0.0963533595 0.0708068331 0.0963533595 0.0062946056 0.8040380000 0.0793390000 0.0449960000 0.0312540000 0.3154250000 0.3310820000 137688667 0 402718720 4.2771706581 3.9279668331 3.9454271793 662 1311867192.5077190399 0.0972255319 0.0708467405 0.0972255319 0.0062906161 0.4965140000 0.1003980000 0.0793560000 0.0000000000 0.3131680000 0.0017880000 137692339 0 402718720 4.2782287598 3.9272627831 3.9459433556 663 1311867192.5427820683 0.0963023752 0.0708851351 0.0972255319 0.0062915304 0.5181860000 0.1032790000 0.0705120000 0.0312910000 0.3093140000 0.0018660000 137696123 0 402718720 4.2802176476 3.9251222610 3.9456768036 664 1311867192.5787169933 0.0978922769 0.0709258085 0.0978922769 0.0062928632 0.4562630000 0.0790210000 0.0628360000 0.0000010000 0.3107690000 0.0017850000 137699851 0 402718720 4.2812919617 3.9265396595 3.9457392693 665 1311867192.6109929085 0.1019397005 0.0709724459 0.1019397005 0.0062902973 0.8055080000 0.0920880000 0.0524020000 0.0308150000 0.3109030000 0.3175030000 137703523 0 402718720 4.2783260345 3.9269351959 3.9455900192 666 1311867192.6435210705 0.1033292264 0.0710210297 0.1033292264 0.0062908317 0.4823320000 0.0923830000 0.0744610000 0.0000010000 0.3118800000 0.0017820000 137707251 0 402718720 4.2778515816 3.9254796505 3.9451367855 667 1311867192.6790139675 0.1035784930 0.0710698415 0.1035784930 0.0062883985 0.4696180000 0.0787890000 0.0448280000 0.0312220000 0.3111730000 0.0017840000 137711035 0 402718720 4.2799582481 3.9264316559 3.9457108974 668 1311867192.7113289833 0.1043384597 0.0711196448 0.1043384597 0.0062854910 0.4655580000 0.0903180000 0.0598050000 0.0000010000 0.3118240000 0.0017920000 137714651 0 402718720 4.2805194855 3.9261422157 3.9459352493 669 1311867192.7439620495 0.1052400768 0.0711706469 0.1052400768 0.0062844771 0.7924660000 0.0793030000 0.0525030000 0.0307760000 0.3109090000 0.3171500000 137718379 0 402718720 4.2803430557 3.9248468876 3.9457881451 670 1311867192.7760629654 0.1046672016 0.0712206418 0.1052400768 0.0062817406 0.4803590000 0.0774760000 0.0883860000 0.0000000000 0.3108740000 0.0017760000 137722051 0 402718720 4.2830052376 3.9260590076 3.9464578629 671 1311867192.8091869354 0.1050270200 0.0712710239 0.1052400768 0.0062772036 0.5155570000 0.0794400000 0.0915350000 0.0308100000 0.3101710000 0.0017880000 137725779 0 402718720 4.2839708328 3.9255588055 3.9468638897 672 1311867192.8422288895 0.1033896729 0.0713188195 0.1052400768 0.0062738746 0.4465400000 0.0795420000 0.0524810000 0.0000000000 0.3109160000 0.0017850000 137729451 0 402718720 4.2866048813 3.9240343571 3.9472243786 673 1311867192.8792889118 0.1055175364 0.0713696348 0.1055175364 0.0062766310 0.8162510000 0.0891280000 0.0704110000 0.0312460000 0.3081720000 0.3154830000 137733291 0 402718720 4.2861247063 3.9257507324 3.9477920532 674 1311867192.9092190266 0.1049773395 0.0714194979 0.1055175364 0.0062721243 0.4845510000 0.0792100000 0.0938180000 0.0000010000 0.3077210000 0.0018770000 137736851 0 402718720 4.2878146172 3.9250137806 3.9487748146 675 1311867192.9434111118 0.1046645865 0.0714687499 0.1055175364 0.0062699009 0.5143690000 0.0797390000 0.0913920000 0.0312530000 0.3083570000 0.0017940000 137740635 0 402718720 4.2886838913 3.9230172634 3.9486904144 676 1311867192.9776289463 0.1043563932 0.0715174002 0.1055175364 0.0062703787 0.4439440000 0.0793180000 0.0526340000 0.0000010000 0.3083490000 0.0017830000 137744307 0 402718720 4.2912254333 3.9243617058 3.9494857788 677 1311867193.0086810589 0.1051071435 0.0715670158 0.1055175364 0.0062675952 0.8252940000 0.0800280000 0.0896310000 0.0307990000 0.3083930000 0.3146180000 137747979 0 402718720 4.2912826538 3.9241068363 3.9498302937 678 1311867193.0430600643 0.1043100655 0.0716153094 0.1055175364 0.0062659665 0.5012290000 0.0952460000 0.0943750000 0.0000010000 0.3079570000 0.0017890000 137751707 0 402718720 4.2926135063 3.9214522839 3.9498860836 679 1311867193.0767369270 0.1051977873 0.0716647681 0.1055175364 0.0062724079 0.4873100000 0.0913220000 0.0527180000 0.0312090000 0.3084290000 0.0017840000 137755379 0 402718720 4.2939963341 3.9236195087 3.9501285553 680 1311867193.1105849743 0.1044820026 0.0717130287 0.1055175364 0.0062689881 0.4547130000 0.0801680000 0.0635560000 0.0000000000 0.3073500000 0.0017930000 137759107 0 402718720 4.2964844704 3.9237744808 3.9507479668 681 1311867193.1429219246 0.1028415859 0.0717587388 0.1055175364 0.0062699574 0.8171060000 0.0988950000 0.0603570000 0.0313000000 0.3092240000 0.3154950000 137762835 0 402718720 4.2981553078 3.9211547375 3.9506793022 682 1311867193.1767370701 0.1046612635 0.0718069830 0.1055175364 0.0062862482 0.4832630000 0.0801750000 0.0903050000 0.0000010000 0.3091430000 0.0017980000 137766507 0 402718720 4.2994394302 3.9247419834 3.9508640766 683 1311867193.2122681141 0.1048958302 0.0718554293 0.1055175364 0.0062865214 0.4767440000 0.0801490000 0.0560470000 0.0307680000 0.3059630000 0.0018980000 137770291 0 402718720 4.3002390862 3.9233250618 3.9512553215 684 1311867193.2432429790 0.1038472056 0.0719022009 0.1055175364 0.0062856989 0.4867460000 0.0805880000 0.0950900000 0.0000010000 0.3073760000 0.0018020000 137773963 0 402718720 4.3022742271 3.9220044613 3.9512712955 685 1311867193.2773900032 0.1049334407 0.0719504217 0.1055175364 0.0062844938 0.7970460000 0.0804290000 0.0639540000 0.0313270000 0.3061790000 0.3133300000 137777691 0 402718720 4.3032884598 3.9243652821 3.9513719082 686 1311867193.3139379025 0.1055215448 0.0719993592 0.1055215448 0.0062860452 0.4835480000 0.0877310000 0.0838730000 0.0000010000 0.3083270000 0.0017610000 137781475 0 402718720 4.3035154343 3.9222540855 3.9510414600 687 1311867193.3426671028 0.1058104560 0.0720485748 0.1058104560 0.0062854671 0.5131530000 0.0805370000 0.0900020000 0.0313680000 0.3076030000 0.0018080000 137785035 0 402718720 4.3045840263 3.9228777885 3.9512441158 688 1311867193.3788230419 0.1047652066 0.0720961280 0.1058104560 0.0062817575 0.4854130000 0.1055500000 0.0681530000 0.0000010000 0.3080380000 0.0018000000 137788819 0 402718720 4.3080482483 3.9242262840 3.9516115189 689 1311867193.4126739502 0.1053198576 0.0721443482 0.1058104560 0.0062903895 0.8289520000 0.0807000000 0.0951860000 0.0308670000 0.3070020000 0.3133610000 137792491 0 402718720 4.3081707954 3.9221444130 3.9514050484 690 1311867193.4440810680 0.1054708809 0.0721926476 0.1058104560 0.0062896743 0.4539120000 0.0798420000 0.0634320000 0.0000000000 0.3067770000 0.0018950000 137796219 0 402718720 4.3096280098 3.9224126339 3.9512765408 691 1311867193.4782969952 0.1051953062 0.0722404083 0.1058104560 0.0062858004 0.5378560000 0.1004620000 0.0955220000 0.0313060000 0.3068830000 0.0018120000 137799947 0 402718720 4.3121347427 3.9235026836 3.9516043663 692 1311867193.5199069977 0.1060000062 0.0722891938 0.1060000062 0.0062828228 0.4482000000 0.0810340000 0.0560570000 0.0000010000 0.3073830000 0.0018030000 137803787 0 402718720 4.3127832413 3.9218537807 3.9514949322 693 1311867193.5431120396 0.1062387526 0.0723381831 0.1062387526 0.0062794962 0.8399900000 0.0903920000 0.0949750000 0.0308370000 0.3078540000 0.3140730000 137807291 0 402718720 4.3137755394 3.9224209785 3.9515273571 694 1311867193.5765709877 0.1062344387 0.0723870250 0.1062387526 0.0062753922 0.4827150000 0.0802340000 0.0904330000 0.0000010000 0.3083740000 0.0018050000 137810963 0 402718720 4.3159437180 3.9234991074 3.9516623020 695 1311867193.6127800941 0.1074704826 0.0724375048 0.1074704826 0.0062713547 0.5148470000 0.0812130000 0.0907570000 0.0314290000 0.3077620000 0.0018170000 137814803 0 402718720 4.3153181076 3.9216992855 3.9510219097 696 1311867193.6461451054 0.1074740663 0.0724878446 0.1074740663 0.0062674077 0.4829170000 0.0804710000 0.0901040000 0.0000010000 0.3086560000 0.0018030000 137818475 0 402718720 4.3168969154 3.9217791557 3.9509541988 697 1311867193.6757860184 0.1076525971 0.0725382962 0.1076525971 0.0062641076 0.8267450000 0.0807470000 0.0907430000 0.0313940000 0.3078900000 0.3141230000 137822091 0 402718720 4.3191637993 3.9237761497 3.9514126778 698 1311867193.7122890949 0.1086280048 0.0725900007 0.1086280048 0.0062603265 0.4846630000 0.0940260000 0.0797000000 0.0000010000 0.3072290000 0.0018100000 137825875 0 402718720 4.3186903000 3.9218342304 3.9510993958 699 1311867193.7430191040 0.1097574607 0.0726431730 0.1097574607 0.0062571938 0.4794500000 0.0806220000 0.0559920000 0.0313210000 0.3078380000 0.0018110000 137829491 0 402718720 4.3191742897 3.9227600098 3.9510374069 700 1311867193.7760169506 0.1113934368 0.0726985305 0.1113934368 0.0062550340 0.4387270000 0.0807160000 0.0459390000 0.0000010000 0.3083890000 0.0018080000 137833163 0 402718720 4.3192968369 3.9243104458 3.9505774975 701 1311867193.8139710426 0.1117332876 0.0727542149 0.1117332876 0.0062532311 0.8196990000 0.0959280000 0.0715600000 0.0308280000 0.3061340000 0.3133850000 137837059 0 402718720 4.3202314377 3.9225211143 3.9508414268 702 1311867193.8436760902 0.1122160181 0.0728104283 0.1122160181 0.0062501962 0.4457800000 0.0804570000 0.0531140000 0.0000000000 0.3085500000 0.0017590000 137840619 0 402718720 4.3210573196 3.9226431847 3.9507503510 703 1311867193.8771181107 0.1123496145 0.0728666718 0.1123496145 0.0062466415 0.4988160000 0.1008370000 0.0560090000 0.0313210000 0.3069530000 0.0018100000 137844347 0 402718720 4.3228073120 3.9235415459 3.9505159855 704 1311867193.9151229858 0.1130687371 0.0729237770 0.1130687371 0.0062430639 0.4629940000 0.0808460000 0.0697630000 0.0000000000 0.3086790000 0.0018110000 137848131 0 402718720 4.3232617378 3.9222850800 3.9504523277 705 1311867193.9425311089 0.1145415753 0.0729828094 0.1145415753 0.0062403080 0.8281440000 0.0809460000 0.0948920000 0.0313330000 0.3062090000 0.3128870000 137851747 0 402718720 4.3230876923 3.9235441685 3.9502403736 706 1311867193.9781770706 0.1146719530 0.0730418591 0.1146719530 0.0062363965 0.4454360000 0.0806620000 0.0533590000 0.0000000000 0.3077140000 0.0018120000 137855531 0 402718720 4.3246741295 3.9237072468 3.9502367973 707 1311867194.0148570538 0.1171340272 0.0731042243 0.1171340272 0.0062346858 0.5438030000 0.0886950000 0.0912610000 0.0381760000 0.3211590000 0.0024410000 137859259 0 402718720 4.3231205940 3.9227867126 3.9495360851 708 1311867194.0433440208 0.1181400493 0.0731678342 0.1181400493 0.0062341241 0.4609620000 0.0805550000 0.0681780000 0.0000010000 0.3085150000 0.0018110000 137862875 0 402718720 4.3236446381 3.9235320091 3.9496133327 709 1311867194.0746119022 0.1165354326 0.0732290015 0.1181400493 0.0062304620 0.8156850000 0.0809740000 0.0798040000 0.0313280000 0.3072840000 0.3144170000 137866491 0 402718720 4.3269896507 3.9243478775 3.9500961304 710 1311867194.1131060123 0.1173407435 0.0732911307 0.1181400493 0.0062271455 0.4767900000 0.0810460000 0.0832230000 0.0000000000 0.3088200000 0.0018130000 137870387 0 402718720 4.3266644478 3.9230005741 3.9497377872 711 1311867194.1428558826 0.1202298999 0.0733571487 0.1202298999 0.0062274124 0.5406760000 0.1012820000 0.0956270000 0.0313790000 0.3086490000 0.0018220000 137874003 0 402718720 4.3246526718 3.9244184494 3.9495265484 712 1311867194.1758549213 0.1187638491 0.0734209221 0.1202298999 0.0062288967 0.4406830000 0.0809310000 0.0485830000 0.0000010000 0.3072430000 0.0019050000 137877675 0 402718720 4.3274483681 3.9255747795 3.9500381947 713 1311867194.2138450146 0.1206218600 0.0734871226 0.1206218600 0.0062264583 0.8245500000 0.0944860000 0.0755520000 0.0312630000 0.3076800000 0.3136700000 137881515 0 402718720 4.3255524635 3.9238390923 3.9496307373 714 1311867194.2451140881 0.1198784336 0.0735520964 0.1206218600 0.0062249093 0.4867430000 0.0806090000 0.0953270000 0.0000010000 0.3068800000 0.0019140000 137885075 0 402718720 4.3276648521 3.9255759716 3.9499058723 715 1311867194.2760241032 0.1201051101 0.0736172055 0.1206218600 0.0062213813 0.5143900000 0.0811180000 0.0914310000 0.0312870000 0.3068330000 0.0018190000 137888691 0 402718720 4.3279790878 3.9252991676 3.9504637718 716 1311867194.3139200211 0.1207897216 0.0736830889 0.1207897216 0.0062179892 0.4528910000 0.0811580000 0.0609380000 0.0000000000 0.3070720000 0.0018160000 137892531 0 402718720 4.3274960518 3.9240024090 3.9500510693 717 1311867194.3447821140 0.1193714887 0.0737468106 0.1207897216 0.0062218151 0.8467430000 0.0936450000 0.0759750000 0.0312840000 0.3164390000 0.3273230000 137896203 0 402718720 4.3301143646 3.9256813526 3.9506995678 718 1311867194.3802230358 0.1187766567 0.0738095262 0.1207897216 0.0062185341 0.5250340000 0.1031760000 0.1112240000 0.0000000000 0.3069040000 0.0018150000 137899931 0 402718720 4.3311810493 3.9253187180 3.9511806965 719 1311867194.4124519825 0.1186434329 0.0738718821 0.1207897216 0.0062169488 0.4933530000 0.0810780000 0.0721820000 0.0313210000 0.3048530000 0.0019030000 137903547 0 402718720 4.3312191963 3.9231815338 3.9516489506 720 1311867194.4447510242 0.1199255735 0.0739358456 0.1207897216 0.0062134835 0.4393820000 0.0810020000 0.0483870000 0.0000010000 0.3062550000 0.0018230000 137907275 0 402718720 4.3307657242 3.9238317013 3.9516398907 721 1311867194.4805839062 0.1192141026 0.0739986449 0.1207897216 0.0062099974 0.8243780000 0.0810970000 0.0910210000 0.0312710000 0.3064950000 0.3125920000 137910947 0 402718720 4.3324651718 3.9246227741 3.9519236088 722 1311867194.5174930096 0.1202356592 0.0740626850 0.1207897216 0.0062078746 0.4574710000 0.0791440000 0.0680380000 0.0000010000 0.3065600000 0.0018100000 137914843 0 402718720 4.3313312531 3.9231441021 3.9516797066 723 1311867194.5439500809 0.1191319600 0.0741250215 0.1207897216 0.0062066656 0.5151760000 0.1023490000 0.0719600000 0.0309490000 0.3061620000 0.0018170000 137918291 0 402718720 4.3331465721 3.9239900112 3.9517083168 724 1311867194.5795979500 0.1197792292 0.0741880798 0.1207897216 0.0062024096 0.4463490000 0.0811220000 0.0552180000 0.0000010000 0.3062530000 0.0018280000 137922019 0 402718720 4.3328962326 3.9239394665 3.9522593021 725 1311867194.6129479408 0.1181748733 0.0742487513 0.1207897216 0.0061987387 0.8082450000 0.0942890000 0.0640800000 0.0313620000 0.3049750000 0.3116470000 137925747 0 402718720 4.3347992897 3.9227023125 3.9527945518 726 1311867194.6493880749 0.1176090017 0.0743084761 0.1207897216 0.0062096481 0.4514190000 0.0806850000 0.0610490000 0.0000000000 0.3059460000 0.0018110000 137929587 0 402718720 4.3359780312 3.9238595963 3.9535648823 727 1311867194.6784319878 0.1166012809 0.0743666505 0.1207897216 0.0062094942 0.5149010000 0.0808340000 0.0908590000 0.0312760000 0.3074160000 0.0024380000 137933147 0 402718720 4.3372144699 3.9233133793 3.9538397789 728 1311867194.7133309841 0.1177070215 0.0744261840 0.1207897216 0.0062065465 0.5277990000 0.1029810000 0.1012310000 0.0000010000 0.3190230000 0.0024550000 137936875 0 402718720 4.3362803459 3.9233908653 3.9537487030 729 1311867194.7475099564 0.1171597391 0.0744848034 0.1207897216 0.0062024916 0.8243510000 0.1024920000 0.0614810000 0.0380740000 0.3091590000 0.3112380000 137940603 0 402718720 4.3377470970 3.9240348339 3.9543251991 730 1311867194.7784450054 0.1171904802 0.0745433044 0.1207897216 0.0061986477 0.4435990000 0.0811760000 0.0535320000 0.0000000000 0.3051300000 0.0018200000 137944275 0 402718720 4.3380908966 3.9238750935 3.9547243118 731 1311867194.8130390644 0.1184162498 0.0746033221 0.1207897216 0.0061947243 0.5385430000 0.1092260000 0.0896530000 0.0313130000 0.3045910000 0.0018270000 137948003 0 402718720 4.3367781639 3.9237184525 3.9548664093 732 1311867194.8476719856 0.1190864369 0.0746640914 0.1207897216 0.0061909016 0.4430310000 0.0794730000 0.0557790000 0.0000010000 0.3038770000 0.0018630000 137951731 0 402718720 4.3362812996 3.9245550632 3.9546175003 733 1311867194.8814148903 0.1195749566 0.0747253613 0.1207897216 0.0061870740 0.7781450000 0.0817220000 0.0486010000 0.0308640000 0.3041710000 0.3108770000 137955459 0 402718720 4.3355793953 3.9250221252 3.9548146725 734 1311867194.9104089737 0.1198941544 0.0747868992 0.1207897216 0.0061932781 0.4357990000 0.0797530000 0.0482060000 0.0000010000 0.3040230000 0.0018470000 137959019 0 402718720 4.3352274895 3.9257783890 3.9549725056 735 1311867194.9451448917 0.1188466102 0.0748468443 0.1207897216 0.0061905655 0.4741670000 0.0814450000 0.0538410000 0.0312540000 0.3038720000 0.0018180000 137962803 0 402718720 4.3353314400 3.9245524406 3.9554657936 736 1311867194.9787399769 0.1158431694 0.0749025459 0.1207897216 0.0061898284 0.4427470000 0.0813190000 0.0539230000 0.0000010000 0.3037710000 0.0018120000 137966531 0 402718720 4.3378171921 3.9233419895 3.9560363293 737 1311867195.0132799149 0.1155722141 0.0749577286 0.1207897216 0.0061876390 0.7818100000 0.0819520000 0.0539070000 0.0308440000 0.3035440000 0.3096320000 137970259 0 402718720 4.3374443054 3.9245176315 3.9563930035 738 1311867195.0464940071 0.1151208505 0.0750121502 0.1207897216 0.0061848942 0.4413080000 0.0797880000 0.0546770000 0.0000010000 0.3031000000 0.0018090000 137973931 0 402718720 4.3367877007 3.9225909710 3.9566493034 739 1311867195.0781710148 0.1139462814 0.0750648351 0.1207897216 0.0061819740 0.4849610000 0.0795870000 0.0681910000 0.0305780000 0.3029070000 0.0017640000 137977603 0 402718720 4.3375916481 3.9232945442 3.9569504261 740 1311867195.1115310192 0.1139294729 0.0751173548 0.1207897216 0.0061781573 0.4668370000 0.0813400000 0.0806330000 0.0000010000 0.3010980000 0.0018110000 137981275 0 402718720 4.3371415138 3.9241247177 3.9573285580 741 1311867195.1458311081 0.1142898202 0.0751702192 0.1207897216 0.0061739995 0.7696940000 0.0795260000 0.0462320000 0.0312600000 0.3023160000 0.3084320000 137985059 0 402718720 4.3354487419 3.9233045578 3.9569740295 742 1311867195.1780319214 0.1140050888 0.0752225573 0.1207897216 0.0061721036 0.4903140000 0.0928340000 0.0918640000 0.0000000000 0.3018510000 0.0018070000 137988731 0 402718720 4.3353939056 3.9248905182 3.9572165012 743 1311867195.2114748955 0.1123744026 0.0752725597 0.1207897216 0.0061683334 0.4563500000 0.0817290000 0.0389390000 0.0307650000 0.3011480000 0.0018150000 137992403 0 402718720 4.3355321884 3.9245505333 3.9572818279 744 1311867195.2436800003 0.1118390188 0.0753217082 0.1207897216 0.0061667758 0.4614470000 0.1093040000 0.0487390000 0.0000000000 0.2996340000 0.0018140000 137996131 0 402718720 4.3351678848 3.9232909679 3.9575755596 745 1311867195.2780399323 0.1117145866 0.0753705577 0.1207897216 0.0061631910 0.7810220000 0.0806140000 0.0611250000 0.0307700000 0.3002780000 0.3062770000 137999859 0 402718720 4.3343400955 3.9238059521 3.9576075077 746 1311867195.3123180866 0.1116696671 0.0754192160 0.1207897216 0.0061592054 0.4746320000 0.0813710000 0.0889350000 0.0000000000 0.3005800000 0.0017680000 138003587 0 402718720 4.3333225250 3.9234910011 3.9577124119 747 1311867195.3425979614 0.1127173007 0.0754691465 0.1207897216 0.0061595556 0.4679130000 0.0811440000 0.0519240000 0.0308190000 0.3002520000 0.0018090000 138007203 0 402718720 4.3302445412 3.9217431545 3.9568862915 748 1311867195.3782711029 0.1108364686 0.0755164291 0.1207897216 0.0061570119 0.4446820000 0.0795750000 0.0611050000 0.0000010000 0.3002350000 0.0018040000 138010987 0 402718720 4.3313584328 3.9225990772 3.9567975998 749 1311867195.4119830132 0.1103632823 0.0755629536 0.1207897216 0.0061552793 0.7834840000 0.0909290000 0.0537280000 0.0307780000 0.3000600000 0.3059950000 138014659 0 402718720 4.3305368423 3.9227225780 3.9566833973 750 1311867195.4435520172 0.1111133993 0.0756103542 0.1207897216 0.0061533351 0.4541560000 0.0812010000 0.0691250000 0.0000000000 0.3000060000 0.0017990000 138018387 0 402718720 4.3274402618 3.9217052460 3.9558684826 751 1311867195.4788239002 0.1097794920 0.0756558523 0.1207897216 0.0061495122 0.4772450000 0.0813980000 0.0616200000 0.0308380000 0.2996000000 0.0018060000 138022115 0 402718720 4.3280205727 3.9235854149 3.9557018280 752 1311867195.5113179684 0.1100870743 0.0757016385 0.1207897216 0.0061455271 0.4730330000 0.1080730000 0.0617480000 0.0000000000 0.2994120000 0.0018090000 138025787 0 402718720 4.3262486458 3.9236180782 3.9557034969 753 1311867195.5439620018 0.1098663434 0.0757470100 0.1207897216 0.0061414949 0.7810890000 0.0819000000 0.0617920000 0.0313290000 0.2990750000 0.3050170000 138029515 0 402718720 4.3238182068 3.9220356941 3.9554665089 754 1311867195.5782160759 0.1078389362 0.0757895722 0.1207897216 0.0061391800 0.4968890000 0.1030970000 0.0914400000 0.0000010000 0.2985570000 0.0018030000 138033243 0 402718720 4.3248834610 3.9226632118 3.9559171200 755 1311867195.6119859219 0.1082245633 0.0758325325 0.1207897216 0.0061365388 0.4924520000 0.0808030000 0.0784690000 0.0312080000 0.2981960000 0.0018070000 138036971 0 402718720 4.3226909637 3.9227151871 3.9558010101 756 1311867195.6430909634 0.1092342883 0.0758767147 0.1207897216 0.0061329310 0.4499620000 0.0792540000 0.0683610000 0.0000000000 0.2985430000 0.0018030000 138040587 0 402718720 4.3191761971 3.9221019745 3.9551382065 757 1311867195.6779129505 0.1084201559 0.0759197047 0.1207897216 0.0061295323 0.7877890000 0.0815680000 0.0724430000 0.0312890000 0.2968790000 0.3036510000 138044371 0 402718720 4.3183875084 3.9226341248 3.9551689625 758 1311867195.7107300758 0.1088931039 0.0759632052 0.1207897216 0.0061292355 0.4410040000 0.0792020000 0.0605230000 0.0000000000 0.2975340000 0.0017590000 138047987 0 402718720 4.3156523705 3.9226260185 3.9552011490 759 1311867195.7458300591 0.1079785079 0.0760053861 0.1207897216 0.0061261592 0.4877100000 0.0944900000 0.0613420000 0.0312460000 0.2968470000 0.0018070000 138051771 0 402718720 4.3143644333 3.9216094017 3.9551286697 760 1311867195.7821879387 0.1068746746 0.0760460036 0.1207897216 0.0061226430 0.4754780000 0.0914300000 0.0692150000 0.0000000000 0.3102110000 0.0024350000 138055499 0 402718720 4.3139333725 3.9218227863 3.9555826187 761 1311867195.8100500107 0.1074950844 0.0760873296 0.1207897216 0.0061191024 0.8160210000 0.1029300000 0.0691900000 0.0387400000 0.3009070000 0.3022800000 138059059 0 402718720 4.3113746643 3.9216730595 3.9554197788 762 1311867195.8458549976 0.1068456918 0.0761276949 0.1207897216 0.0061152815 0.4365590000 0.0808960000 0.0565410000 0.0000010000 0.2953060000 0.0017890000 138062843 0 402718720 4.3097276688 3.9210710526 3.9553420544 763 1311867195.8778660297 0.1063429415 0.0761672955 0.1207897216 0.0061137228 0.5090330000 0.0811650000 0.0840960000 0.0312490000 0.3079270000 0.0024230000 138066571 0 402718720 4.3089580536 3.9229500294 3.9554207325 764 1311867195.9098269939 0.1065186858 0.0762070225 0.1207897216 0.0061113191 0.5366690000 0.1024630000 0.1211350000 0.0000010000 0.3084560000 0.0024210000 138070243 0 402718720 4.3069128990 3.9223856926 3.9555761814 765 1311867195.9458460808 0.1063304618 0.0762463995 0.1207897216 0.0061075687 0.7825330000 0.0849140000 0.0689280000 0.0313230000 0.2947030000 0.3006950000 138073971 0 402718720 4.3048019409 3.9216785431 3.9553928375 766 1311867195.9778430462 0.1068232134 0.0762863170 0.1207897216 0.0061065010 0.4287140000 0.0791010000 0.0514050000 0.0000000000 0.2944060000 0.0017980000 138077699 0 402718720 4.3034472466 3.9236831665 3.9556150436 767 1311867196.0100569725 0.1057961211 0.0763247913 0.1207897216 0.0061043395 0.4580210000 0.0812550000 0.0487330000 0.0313350000 0.2926980000 0.0018950000 138081371 0 402718720 4.3027534485 3.9227366447 3.9558708668 768 1311867196.0498790741 0.1049498990 0.0763620636 0.1207897216 0.0061009300 0.4666090000 0.0810160000 0.0884170000 0.0000000000 0.2933670000 0.0017950000 138085267 0 402718720 4.3017296791 3.9220211506 3.9555852413 769 1311867196.0793108940 0.1060465127 0.0764006650 0.1207897216 0.0061034126 0.7636930000 0.0911640000 0.0463800000 0.0307770000 0.2936400000 0.2997330000 138088939 0 402718720 4.2998223305 3.9241983891 3.9558584690 770 1311867196.1113979816 0.1058136076 0.0764388636 0.1207897216 0.0061005375 0.4318210000 0.0808370000 0.0536920000 0.0000000000 0.2934710000 0.0017950000 138092499 0 402718720 4.2978525162 3.9228587151 3.9558529854 771 1311867196.1473290920 0.1044752970 0.0764752273 0.1207897216 0.0060971682 0.4552110000 0.0817440000 0.0462770000 0.0308390000 0.2925570000 0.0018050000 138096339 0 402718720 4.2973093987 3.9219779968 3.9560441971 772 1311867196.1811769009 0.1045832261 0.0765116367 0.1207897216 0.0060987252 0.4311680000 0.0811300000 0.0540290000 0.0000010000 0.2921940000 0.0017950000 138100067 0 402718720 4.2959828377 3.9237067699 3.9559583664 773 1311867196.2114949226 0.1057151183 0.0765494161 0.1207897216 0.0060966901 0.8295070000 0.1067030000 0.0960200000 0.0312850000 0.2912940000 0.3020050000 138103627 0 402718720 4.2928204536 3.9225287437 3.9557507038 774 1311867196.2462599277 0.1053702608 0.0765866523 0.1207897216 0.0060937644 0.4838270000 0.0981150000 0.0896530000 0.0000010000 0.2922480000 0.0018010000 138107411 0 402718720 4.2914214134 3.9223055840 3.9558427334 775 1311867196.2800569534 0.1054907218 0.0766239479 0.1207897216 0.0060900414 0.4554250000 0.0807440000 0.0484950000 0.0312620000 0.2909110000 0.0018870000 138111139 0 402718720 4.2897644043 3.9232196808 3.9557108879 776 1311867196.3111600876 0.1052032560 0.0766607769 0.1207897216 0.0060866556 0.4401370000 0.0809450000 0.0637470000 0.0000010000 0.2916200000 0.0018030000 138114755 0 402718720 4.2880277634 3.9222450256 3.9557673931 777 1311867196.3484730721 0.1053230539 0.0766976653 0.1207897216 0.0060833184 0.8000760000 0.0816180000 0.0965380000 0.0313320000 0.2909270000 0.2976540000 138118595 0 402718720 4.2862153053 3.9226155281 3.9555797577 778 1311867196.3842670918 0.1048760638 0.0767338843 0.1207897216 0.0060801919 0.4673860000 0.0793580000 0.0925290000 0.0000010000 0.2916440000 0.0017970000 138122323 0 402718720 4.2852263451 3.9238300323 3.9558427334 779 1311867196.4107549191 0.1051497906 0.0767703617 0.1207897216 0.0060779798 0.4790610000 0.0909210000 0.0625800000 0.0312440000 0.2904720000 0.0017960000 138125827 0 402718720 4.2828764915 3.9222035408 3.9560046196 780 1311867196.4463150501 0.1047774032 0.0768062682 0.1207897216 0.0060774804 0.4620340000 0.0813520000 0.0864500000 0.0000000000 0.2903780000 0.0018020000 138129611 0 402718720 4.2819423676 3.9232037067 3.9561488628 781 1311867196.4798319340 0.1040037051 0.0768410920 0.1207897216 0.0060736568 0.7534570000 0.0809590000 0.0537990000 0.0312240000 0.2899650000 0.2955030000 138133339 0 402718720 4.2814116478 3.9236755371 3.9566872120 782 1311867196.5113470554 0.1044449285 0.0768763910 0.1207897216 0.0060700833 0.4203600000 0.0806420000 0.0463240000 0.0000010000 0.2895620000 0.0018020000 138136955 0 402718720 4.2787270546 3.9230301380 3.9565677643 783 1311867196.5468420982 0.1040904298 0.0769111472 0.1207897216 0.0060671751 0.4891770000 0.1088340000 0.0565980000 0.0312560000 0.2886590000 0.0018020000 138140739 0 402718720 4.2768201828 3.9237458706 3.9567952156 784 1311867196.5795550346 0.1038130745 0.0769454608 0.1207897216 0.0060650244 0.4386550000 0.0909310000 0.0567310000 0.0000010000 0.2869310000 0.0018880000 138144467 0 402718720 4.2763719559 3.9249074459 3.9573373795 785 1311867196.6108930111 0.1028488576 0.0769784588 0.1207897216 0.0060643663 0.7524130000 0.0813230000 0.0576940000 0.0307730000 0.2872260000 0.2933810000 138148083 0 402718720 4.2750511169 3.9235553741 3.9576945305 786 1311867196.6521809101 0.1031637862 0.0770117735 0.1207897216 0.0060674402 0.4234010000 0.0936330000 0.0386900000 0.0000010000 0.2872290000 0.0017940000 138152035 0 402718720 4.2722926140 3.9247815609 3.9575557709 787 1311867196.6805100441 0.1019999385 0.0770435246 0.1207897216 0.0060750237 0.4616170000 0.0794020000 0.0609820000 0.0310240000 0.2863850000 0.0017960000 138155595 0 402718720 4.2716703415 3.9256763458 3.9581782818 788 1311867196.7112100124 0.1012214348 0.0770742073 0.1207897216 0.0060720554 0.4168150000 0.0813260000 0.0464070000 0.0000000000 0.2852080000 0.0017930000 138159211 0 402718720 4.2705645561 3.9244041443 3.9588794708 789 1311867196.7464900017 0.1023799479 0.0771062804 0.1207897216 0.0060686907 0.7346510000 0.0797120000 0.0460680000 0.0310270000 0.2848870000 0.2909440000 138162995 0 402718720 4.2673459053 3.9258201122 3.9590697289 790 1311867196.7783749104 0.1008667424 0.0771363570 0.1207897216 0.0060652177 0.4081490000 0.0812770000 0.0389730000 0.0000010000 0.2840520000 0.0017950000 138166723 0 402718720 4.2666463852 3.9255123138 3.9594669342 791 1311867196.8109180927 0.1009568647 0.0771664714 0.1207897216 0.0060630296 0.4568510000 0.0819510000 0.0569120000 0.0312930000 0.2826420000 0.0018860000 138170283 0 402718720 4.2640609741 3.9250795841 3.9596781731 792 1311867196.8488750458 0.1007394716 0.0771962353 0.1207897216 0.0060606240 0.4233760000 0.0816550000 0.0541870000 0.0000000000 0.2836880000 0.0017990000 138174179 0 402718720 4.2618861198 3.9251971245 3.9599087238 793 1311867196.8821749687 0.1003883630 0.0772254814 0.1207897216 0.0060570544 0.7379730000 0.0814870000 0.0521200000 0.0307580000 0.2827320000 0.2888150000 138177851 0 402718720 4.2603588104 3.9259402752 3.9602689743 794 1311867196.9115700722 0.0996870026 0.0772537704 0.1207897216 0.0060547652 0.4573150000 0.1066650000 0.0648570000 0.0000010000 0.2819150000 0.0018030000 138181411 0 402718720 4.2585320473 3.9241919518 3.9603834152 795 1311867196.9482440948 0.0994219184 0.0772816549 0.1207897216 0.0060514700 0.4446490000 0.0811710000 0.0459260000 0.0311720000 0.2825060000 0.0018030000 138185251 0 402718720 4.2564787865 3.9248046875 3.9604601860 796 1311867196.9809880257 0.0987665355 0.0773086459 0.1207897216 0.0060488688 0.4195440000 0.0796480000 0.0535420000 0.0000000000 0.2824750000 0.0018060000 138188979 0 402718720 4.2550482750 3.9245228767 3.9606163502 797 1311867197.0154891014 0.0986356437 0.0773354050 0.1207897216 0.0060455711 0.7569740000 0.0925020000 0.0614070000 0.0307470000 0.2820810000 0.2882050000 138192651 0 402718720 4.2531094551 3.9240581989 3.9606215954 798 1311867197.0490679741 0.0987313986 0.0773622171 0.1207897216 0.0060424188 0.4378550000 0.0818470000 0.0708290000 0.0000010000 0.2810940000 0.0018950000 138196379 0 402718720 4.2507009506 3.9240329266 3.9604678154 799 1311867197.0806479454 0.0970761850 0.0773868904 0.1207897216 0.0060395934 0.4499400000 0.0936120000 0.0408240000 0.0307870000 0.2806650000 0.0018840000 138199939 0 402718720 4.2504510880 3.9234993458 3.9604587555 800 1311867197.1148109436 0.0976196080 0.0774121813 0.1207897216 0.0060359082 0.4587700000 0.0814030000 0.0917350000 0.0000010000 0.2817800000 0.0017920000 138203723 0 402718720 4.2472748756 3.9233698845 3.9599287510 801 1311867197.1468429565 0.0979535282 0.0774378259 0.1207897216 0.0060334432 0.7207260000 0.0810410000 0.0388510000 0.0312710000 0.2804510000 0.2870740000 138207395 0 402718720 4.2450699806 3.9243941307 3.9598345757 802 1311867197.1792430878 0.0979964510 0.0774634601 0.1207897216 0.0060307072 0.4124910000 0.0810240000 0.0463610000 0.0000010000 0.2812290000 0.0017960000 138211123 0 402718720 4.2425866127 3.9238305092 3.9596989155 803 1311867197.2143619061 0.0980754048 0.0774891288 0.1207897216 0.0060299406 0.4517140000 0.0814790000 0.0539570000 0.0312220000 0.2811760000 0.0018060000 138214851 0 402718720 4.2401871681 3.9243319035 3.9596066475 804 1311867197.2459290028 0.0976012573 0.0775141438 0.1207897216 0.0060265041 0.4268400000 0.0809770000 0.0613910000 0.0000010000 0.2805870000 0.0017960000 138218523 0 402718720 4.2390022278 3.9248213768 3.9598252773 805 1311867197.2799959183 0.0972549617 0.0775386666 0.1207897216 0.0060235827 0.7555340000 0.1088990000 0.0483210000 0.0312290000 0.2789860000 0.2860300000 138222307 0 402718720 4.2369446754 3.9243624210 3.9600009918 806 1311867197.3157260418 0.0971160606 0.0775629562 0.1207897216 0.0060205275 0.4361340000 0.0816280000 0.0707770000 0.0000010000 0.2798550000 0.0017970000 138225979 0 402718720 4.2345919609 3.9246513844 3.9598472118 807 1311867197.3468708992 0.0964600518 0.0775863726 0.1207897216 0.0060173615 0.4565060000 0.0817730000 0.0598980000 0.0312150000 0.2797270000 0.0017990000 138229651 0 402718720 4.2331867218 3.9247601032 3.9600510597 808 1311867197.3784019947 0.0967509374 0.0776100912 0.1207897216 0.0060148811 0.4264170000 0.0813050000 0.0616770000 0.0000000000 0.2795470000 0.0017890000 138233267 0 402718720 4.2305145264 3.9241094589 3.9598379135 809 1311867197.4155099392 0.0969380736 0.0776339824 0.1207897216 0.0060115859 0.7391100000 0.0962440000 0.0462250000 0.0307800000 0.2785960000 0.2851800000 138237051 0 402718720 4.2278547287 3.9240057468 3.9594621658 810 1311867197.4478878975 0.0959084854 0.0776565435 0.1207897216 0.0060081735 0.4219770000 0.0939160000 0.0446010000 0.0000010000 0.2795710000 0.0017900000 138240723 0 402718720 4.2274618149 3.9241015911 3.9594779015 811 1311867197.4793179035 0.0968517810 0.0776802121 0.1207897216 0.0060046878 0.4923460000 0.0810790000 0.0963990000 0.0312800000 0.2796930000 0.0017990000 138244283 0 402718720 4.2239861488 3.9238083363 3.9584558010 812 1311867197.5150759220 0.0973702893 0.0777044609 0.1207897216 0.0060027290 0.4102350000 0.0794970000 0.0463100000 0.0000000000 0.2805320000 0.0018000000 138248067 0 402718720 4.2214446068 3.9247190952 3.9577088356 813 1311867197.5469260216 0.0970288813 0.0777282302 0.1207897216 0.0059994871 0.7464770000 0.0795170000 0.0664600000 0.0310550000 0.2807900000 0.2865710000 138251683 0 402718720 4.2202563286 3.9253818989 3.9574029446 814 1311867197.5802750587 0.0970470458 0.0777519634 0.1207897216 0.0059983235 0.4701240000 0.0978360000 0.0885730000 0.0000000000 0.2796150000 0.0018950000 138255411 0 402718720 4.2176966667 3.9239723682 3.9565973282 815 1311867197.6152749062 0.0991069004 0.0777781658 0.1207897216 0.0059990918 0.4618710000 0.0809450000 0.0644600000 0.0312500000 0.2813360000 0.0017960000 138259139 0 402718720 4.2134470940 3.9255523682 3.9552221298 816 1311867197.6470439434 0.0982950926 0.0778033091 0.1207897216 0.0059966206 0.4440780000 0.0952490000 0.0648230000 0.0000010000 0.2798900000 0.0018830000 138262811 0 402718720 4.2131595612 3.9273498058 3.9549832344 817 1311867197.6800849438 0.0981854051 0.0778282566 0.1207897216 0.0059960630 0.7463810000 0.0811160000 0.0647050000 0.0312890000 0.2801920000 0.2869740000 138266539 0 402718720 4.2103881836 3.9254395962 3.9542233944 818 1311867197.7143290043 0.0985792801 0.0778536246 0.1207897216 0.0059966034 0.4691160000 0.0922880000 0.0917260000 0.0000000000 0.2812200000 0.0017860000 138270267 0 402718720 4.2087244987 3.9277915955 3.9535748959 819 1311867197.7463419437 0.0985288098 0.0778788690 0.1207897216 0.0059946213 0.5044860000 0.0925700000 0.0968490000 0.0312810000 0.2798840000 0.0017960000 138273939 0 402718720 4.2068123817 3.9277687073 3.9529621601 820 1311867197.7793009281 0.0992840603 0.0779049729 0.1207897216 0.0059919787 0.4192030000 0.0791520000 0.0561080000 0.0000010000 0.2798860000 0.0018410000 138277667 0 402718720 4.2032036781 3.9263989925 3.9517736435 821 1311867197.8146750927 0.0990954936 0.0779307835 0.1207897216 0.0059938347 0.7278490000 0.0795380000 0.0482330000 0.0306380000 0.2803940000 0.2869550000 138281451 0 402718720 4.2024960518 3.9288368225 3.9511737823 822 1311867197.8467919827 0.0985194296 0.0779558305 0.1207897216 0.0059928226 0.4202360000 0.0815040000 0.0542810000 0.0000010000 0.2804890000 0.0017940000 138285067 0 402718720 4.2011590004 3.9274237156 3.9505755901 823 1311867197.8802978992 0.0995862335 0.0779821129 0.1207897216 0.0059913534 0.4656350000 0.0922850000 0.0487360000 0.0387620000 0.2819460000 0.0017910000 138288739 0 402718720 4.1975250244 3.9281835556 3.9492547512 824 1311867197.9148609638 0.0991334468 0.0780077820 0.1207897216 0.0059924541 0.4352560000 0.0944610000 0.0567780000 0.0000010000 0.2798660000 0.0018920000 138292523 0 402718720 4.1969985962 3.9297473431 3.9488308430 825 1311867197.9470140934 0.0982398689 0.0780323057 0.1207897216 0.0059958146 0.7302930000 0.0813250000 0.0488510000 0.0313070000 0.2800600000 0.2866350000 138296195 0 402718720 4.1954460144 3.9290199280 3.9481835365 826 1311867197.9812700748 0.0983771011 0.0780569362 0.1207897216 0.0059922195 0.4102940000 0.0793750000 0.0458840000 0.0000000000 0.2810950000 0.0017890000 138299923 0 402718720 4.1932697296 3.9292583466 3.9474496841 827 1311867198.0145471096 0.0983072519 0.0780814227 0.1207897216 0.0059899123 0.4412810000 0.0811050000 0.0444980000 0.0313460000 0.2804070000 0.0017990000 138303707 0 402718720 4.1919765472 3.9305622578 3.9473066330 828 1311867198.0463368893 0.0975518674 0.0781049377 0.1207897216 0.0059876064 0.4132120000 0.0812270000 0.0487840000 0.0000000000 0.2790420000 0.0018930000 138307323 0 402718720 4.1905522346 3.9297485352 3.9466969967 829 1311867198.0787069798 0.0979340151 0.0781288570 0.1207897216 0.0059872986 0.7629690000 0.0996990000 0.0645210000 0.0313320000 0.2791030000 0.2861810000 138311051 0 402718720 4.1883654594 3.9305317402 3.9461543560 830 1311867198.1143770218 0.0957096517 0.0781500387 0.1207897216 0.0059848439 0.4270680000 0.0808610000 0.0627950000 0.0000010000 0.2794690000 0.0017960000 138314779 0 402718720 4.1890249252 3.9309802055 3.9459819794 831 1311867198.1463611126 0.0971922874 0.0781729536 0.1207897216 0.0059813614 0.4420770000 0.0809230000 0.0464160000 0.0313240000 0.2794880000 0.0018010000 138318451 0 402718720 4.1851825714 3.9313869476 3.9451787472 832 1311867198.1822519302 0.0962603763 0.0781946933 0.1207897216 0.0059780518 0.4123720000 0.0809610000 0.0488930000 0.0000010000 0.2783820000 0.0018870000 138322235 0 402718720 4.1839718819 3.9319028854 3.9444494247 833 1311867198.2144989967 0.0963645279 0.0782165058 0.1207897216 0.0059812100 0.7685300000 0.0794010000 0.0908640000 0.0310470000 0.2796900000 0.2854300000 138325907 0 402718720 4.1819095612 3.9320914745 3.9439244270 834 1311867198.2464120388 0.0957737714 0.0782375577 0.1207897216 0.0059791040 0.4322120000 0.0897720000 0.0464820000 0.0000000000 0.2911780000 0.0024260000 138329579 0 402718720 4.1803731918 3.9317147732 3.9430837631 835 1311867198.2821578979 0.0954834521 0.0782582114 0.1207897216 0.0059762390 0.5088600000 0.1028480000 0.0914400000 0.0313170000 0.2793270000 0.0018020000 138333363 0 402718720 4.1784410477 3.9326195717 3.9424860477 836 1311867198.3159120083 0.0948001072 0.0782779984 0.1207897216 0.0059756532 0.4115200000 0.0805810000 0.0487600000 0.0000000000 0.2780520000 0.0018830000 138337035 0 402718720 4.1769847870 3.9333996773 3.9415566921 837 1311867198.3481218815 0.0934853777 0.0782961673 0.1207897216 0.0059732790 0.7943920000 0.0995810000 0.0964540000 0.0313130000 0.2792250000 0.2857060000 138340707 0 402718720 4.1759386063 3.9326534271 3.9409720898 838 1311867198.3828320503 0.0939124674 0.0783148025 0.1207897216 0.0059746729 0.4600470000 0.0804980000 0.0962980000 0.0000000000 0.2793200000 0.0017830000 138344491 0 402718720 4.1731204987 3.9343221188 3.9399750233 839 1311867198.4242680073 0.0927598774 0.0783320195 0.1207897216 0.0059772557 0.4561350000 0.0923440000 0.0486530000 0.0313790000 0.2797980000 0.0017960000 138348219 0 402718720 4.1712207794 3.9348340034 3.9389114380 840 1311867198.4497859478 0.0921776444 0.0783485024 0.1207897216 0.0059742020 0.4222720000 0.0918750000 0.0461830000 0.0000010000 0.2802780000 0.0017920000 138351611 0 402718720 4.1693921089 3.9328877926 3.9379928112 841 1311867198.4856219292 0.0938531756 0.0783669384 0.1207897216 0.0059802954 0.7724770000 0.0800580000 0.0908460000 0.0313160000 0.2809460000 0.2871770000 138355283 0 402718720 4.1649088860 3.9345326424 3.9368565083 842 1311867198.5190339088 0.0935712755 0.0783849958 0.1207897216 0.0059780102 0.4095160000 0.0786340000 0.0459340000 0.0000000000 0.2810310000 0.0017780000 138359011 0 402718720 4.1627635956 3.9358661175 3.9360258579 843 1311867198.5499279499 0.0921060294 0.0784012722 0.1207897216 0.0059785914 0.4877660000 0.0800240000 0.0914950000 0.0313670000 0.2809640000 0.0017850000 138362683 0 402718720 4.1613802910 3.9346272945 3.9349946976 844 1311867198.5824239254 0.0910343602 0.0784162403 0.1207897216 0.0059760715 0.4306090000 0.0944130000 0.0511310000 0.0000010000 0.2811270000 0.0017750000 138366355 0 402718720 4.1603393555 3.9366636276 3.9341714382 845 1311867198.6147489548 0.0899792910 0.0784299244 0.1207897216 0.0059777911 0.7442140000 0.0794650000 0.0636020000 0.0314290000 0.2806380000 0.2869540000 138370027 0 402718720 4.1589064598 3.9363565445 3.9334318638 846 1311867198.6482009888 0.0900694057 0.0784436827 0.1207897216 0.0059753537 0.4546740000 0.0794040000 0.0899860000 0.0000000000 0.2813480000 0.0017830000 138373699 0 402718720 4.1563229561 3.9373357296 3.9325261116 847 1311867198.6827540398 0.0906176195 0.0784580557 0.1207897216 0.0059731398 0.4488180000 0.0792120000 0.0529090000 0.0313890000 0.2813580000 0.0017870000 138377427 0 402718720 4.1530652046 3.9382960796 3.9315447807 848 1311867198.7146520615 0.0903257281 0.0784720506 0.1207897216 0.0059696318 0.4361460000 0.0984470000 0.0528380000 0.0000000000 0.2809040000 0.0017720000 138381043 0 402718720 4.1514782906 3.9389679432 3.9310867786 849 1311867198.7467699051 0.0905796438 0.0784863116 0.1207897216 0.0059671975 0.7911730000 0.1001580000 0.0897230000 0.0313330000 0.2807150000 0.2870920000 138384659 0 402718720 4.1489510536 3.9386157990 3.9302823544 850 1311867198.7842700481 0.0896227509 0.0784994133 0.1207897216 0.0059639896 0.4266500000 0.0792190000 0.0636270000 0.0000000000 0.2796360000 0.0018660000 138388443 0 402718720 4.1480627060 3.9400520325 3.9298286438 851 1311867198.8149418831 0.0920696780 0.0785153595 0.1207897216 0.0059612667 0.4499250000 0.0797910000 0.0532210000 0.0314120000 0.2815770000 0.0017880000 138392059 0 402718720 4.1424612999 3.9405541420 3.9284620285 852 1311867198.8464009762 0.0925509259 0.0785318332 0.1207897216 0.0059585370 0.4257030000 0.0795070000 0.0604730000 0.0000000000 0.2817610000 0.0017740000 138395731 0 402718720 4.1400103569 3.9413294792 3.9277088642 853 1311867198.8845369816 0.0921264812 0.0785477707 0.1207897216 0.0059559438 0.7374460000 0.0772440000 0.0451360000 0.0308380000 0.2818020000 0.3000700000 138399459 0 402718720 4.1389727592 3.9422593117 3.9271490574 854 1311867198.9147930145 0.0928873792 0.0785645618 0.1207897216 0.0059525168 0.4646800000 0.1010960000 0.0709190000 0.0000010000 0.2887100000 0.0017770000 138403075 0 402718720 4.1365475655 3.9431109428 3.9263331890 855 1311867198.9465179443 0.0937371328 0.0785823075 0.1207897216 0.0059492054 0.4834960000 0.0797740000 0.0782540000 0.0382650000 0.2832580000 0.0017850000 138406747 0 402718720 4.1339354515 3.9443445206 3.9252798557 856 1311867198.9839329720 0.0940954909 0.0786004303 0.1207897216 0.0059460292 0.4198950000 0.0797780000 0.0532800000 0.0000000000 0.2828830000 0.0017850000 138410643 0 402718720 4.1316366196 3.9450531006 3.9244492054 857 1311867199.0148730278 0.0952530652 0.0786198617 0.1207897216 0.0059471491 0.7708080000 0.0795100000 0.0608300000 0.0313840000 0.2929300000 0.3037870000 138414259 0 402718720 4.1285748482 3.9462025166 3.9233834743 858 1311867199.0468010902 0.0969173461 0.0786411874 0.1207897216 0.0059485019 0.4594680000 0.1006670000 0.0612950000 0.0000000000 0.2935450000 0.0017790000 138417931 0 402718720 4.1262316704 3.9473586082 3.9225208759 859 1311867199.0849320889 0.0965258405 0.0786620077 0.1207897216 0.0059487788 0.4752370000 0.0942340000 0.0608400000 0.0313840000 0.2848210000 0.0017810000 138421827 0 402718720 4.1255154610 3.9485766888 3.9216992855 860 1311867199.1149818897 0.0977847502 0.0786842435 0.1207897216 0.0059461331 0.4251520000 0.0802730000 0.0564350000 0.0000010000 0.2844630000 0.0017760000 138425387 0 402718720 4.1228089333 3.9490392208 3.9205553532 861 1311867199.1465420723 0.0991582498 0.0787080228 0.1207897216 0.0059435756 0.7637300000 0.0793250000 0.0459790000 0.0308840000 0.2989790000 0.3061890000 138429059 0 402718720 4.1204705238 3.9505059719 3.9192872047 862 1311867199.1823658943 0.1005059257 0.0787333104 0.1207897216 0.0059422028 0.4732250000 0.1001870000 0.0807470000 0.0000000000 0.2883340000 0.0017690000 138432843 0 402718720 4.1182694435 3.9527704716 3.9180819988 863 1311867199.2146680355 0.1016055495 0.0787598136 0.1207897216 0.0059389680 0.4602740000 0.0776170000 0.0600220000 0.0311520000 0.2875480000 0.0017410000 138436571 0 402718720 4.1155409813 3.9528806210 3.9168217182 864 1311867199.2467749119 0.1017509401 0.0787864237 0.1207897216 0.0059357195 0.4189680000 0.0792070000 0.0480330000 0.0000010000 0.2877520000 0.0017830000 138440187 0 402718720 4.1144313812 3.9542644024 3.9159221649 865 1311867199.2833590508 0.1018608287 0.0788130993 0.1207897216 0.0059323035 0.7386530000 0.0786730000 0.0437190000 0.0312710000 0.2882580000 0.2945510000 138444027 0 402718720 4.1128640175 3.9551134109 3.9148178101 866 1311867199.3159129620 0.1024523601 0.0788403963 0.1207897216 0.0059323907 0.4415650000 0.0785050000 0.0703190000 0.0000000000 0.2887440000 0.0017760000 138447587 0 402718720 4.1108851433 3.9555242062 3.9135499001 867 1311867199.3465209007 0.1031255275 0.0788684069 0.1207897216 0.0059292111 0.5050830000 0.0901490000 0.0900080000 0.0313530000 0.2895880000 0.0017770000 138451203 0 402718720 4.1087760925 3.9561588764 3.9123141766 868 1311867199.3829050064 0.1032128781 0.0788964535 0.1207897216 0.0059261702 0.4331210000 0.0784470000 0.0602690000 0.0000010000 0.2904280000 0.0017670000 138455043 0 402718720 4.1068387032 3.9567959309 3.9111900330 869 1311867199.4147589207 0.1030519530 0.0789242504 0.1207897216 0.0059228012 0.8157950000 0.1035550000 0.0900390000 0.0313410000 0.2910940000 0.2975920000 138458659 0 402718720 4.1049809456 3.9564726353 3.9100055695 870 1311867199.4512910843 0.1033156440 0.0789522865 0.1207897216 0.0059199907 0.4124820000 0.0783740000 0.0378750000 0.0000000000 0.2922780000 0.0017340000 138462499 0 402718720 4.1025738716 3.9576566219 3.9086191654 871 1311867199.4837360382 0.1020882577 0.0789788490 0.1207897216 0.0059175648 0.4977070000 0.0781380000 0.0936000000 0.0309350000 0.2910410000 0.0017710000 138466171 0 402718720 4.1021232605 3.9578731060 3.9078974724 872 1311867199.5150198936 0.1018864140 0.0790051192 0.1207897216 0.0059143277 0.4750130000 0.0895390000 0.0891320000 0.0000000000 0.2923550000 0.0017560000 138469843 0 402718720 4.1003589630 3.9579095840 3.9070641994 873 1311867199.5544059277 0.1020122692 0.0790314733 0.1207897216 0.0059130232 0.7477120000 0.0777850000 0.0450020000 0.0308700000 0.2926310000 0.2992310000 138473739 0 402718720 4.0976428986 3.9589490891 3.9061107635 874 1311867199.5835030079 0.1023175716 0.0790581164 0.1207897216 0.0059097214 0.4338220000 0.0914140000 0.0474170000 0.0000010000 0.2907900000 0.0018560000 138477355 0 402718720 4.0950837135 3.9595322609 3.9053945541 875 1311867199.6158308983 0.1019851342 0.0790843187 0.1207897216 0.0059072397 0.4966710000 0.0783850000 0.0916050000 0.0309120000 0.2917750000 0.0017770000 138480915 0 402718720 4.0925903320 3.9594225883 3.9047546387 876 1311867199.6538460255 0.1003490686 0.0791085936 0.1207897216 0.0059050235 0.4238970000 0.0779330000 0.0504620000 0.0000000000 0.2915210000 0.0017650000 138484811 0 402718720 4.0916595459 3.9596407413 3.9044294357 877 1311867199.6824479103 0.1005822420 0.0791330789 0.1207897216 0.0059018673 0.7663770000 0.0785040000 0.0652510000 0.0313870000 0.2911590000 0.2978850000 138488371 0 402718720 4.0890164375 3.9593763351 3.9038777351 878 1311867199.7146759033 0.0995815620 0.0791563687 0.1207897216 0.0058994050 0.4180090000 0.0780780000 0.0450980000 0.0000000000 0.2908240000 0.0017670000 138492099 0 402718720 4.0875844955 3.9596416950 3.9033980370 879 1311867199.7511539459 0.0994103923 0.0791794109 0.1207897216 0.0058969886 0.4687030000 0.0904800000 0.0525380000 0.0314500000 0.2902330000 0.0017710000 138495827 0 402718720 4.0852432251 3.9605729580 3.9031274319 880 1311867199.7826020718 0.0997890681 0.0792028309 0.1207897216 0.0058949771 0.4165650000 0.0779110000 0.0448990000 0.0000010000 0.2897650000 0.0017560000 138499499 0 402718720 4.0820951462 3.9598519802 3.9025912285 881 1311867199.8150150776 0.0986192599 0.0792248700 0.1207897216 0.0058973103 0.7855080000 0.0777640000 0.0888040000 0.0313600000 0.2893620000 0.2959720000 138503171 0 402718720 4.0803756714 3.9594011307 3.9020390511 882 1311867199.8519051075 0.0983343050 0.0792465360 0.1207897216 0.0058943515 0.4229690000 0.0781240000 0.0518350000 0.0000010000 0.2890020000 0.0017570000 138506955 0 402718720 4.0784859657 3.9606018066 3.9017748833 883 1311867199.8839609623 0.0979959518 0.0792677698 0.1207897216 0.0058947051 0.5009250000 0.0779530000 0.0842560000 0.0383210000 0.2963790000 0.0017720000 138510683 0 402718720 4.0760016441 3.9595334530 3.9014017582 884 1311867199.9148159027 0.0977599546 0.0792886886 0.1207897216 0.0058926783 0.4274350000 0.0968950000 0.0395050000 0.0000000000 0.2867970000 0.0018580000 138514355 0 402718720 4.0737104416 3.9593310356 3.9010887146 885 1311867199.9520709515 0.0970048010 0.0793087068 0.1207897216 0.0058895940 0.7387140000 0.0771710000 0.0470240000 0.0309370000 0.2870630000 0.2943060000 138518139 0 402718720 4.0727391243 3.9601943493 3.9009006023 886 1311867199.9828410149 0.0957716629 0.0793272880 0.1207897216 0.0058879931 0.4214350000 0.0777820000 0.0521690000 0.0000000000 0.2874450000 0.0017730000 138521755 0 402718720 4.0714173317 3.9589972496 3.9004952908 887 1311867200.0144031048 0.0950116888 0.0793449705 0.1207897216 0.0058857605 0.4499600000 0.0774330000 0.0501640000 0.0309560000 0.2874210000 0.0017670000 138525427 0 402718720 4.0699906349 3.9593963623 3.9001893997 888 1311867200.0539638996 0.0946940780 0.0793622555 0.1207897216 0.0058846967 0.4206070000 0.0775950000 0.0519820000 0.0000010000 0.2870000000 0.0017620000 138529323 0 402718720 4.0682115555 3.9612562656 3.9001402855 889 1311867200.0830330849 0.0944394693 0.0793792153 0.1207897216 0.0058821209 0.7294380000 0.0756570000 0.0427720000 0.0312240000 0.2853510000 0.2922140000 138532883 0 402718720 4.0660204887 3.9598226547 3.9001615047 890 1311867200.1174468994 0.0947096720 0.0793964405 0.1207897216 0.0058810921 0.4539500000 0.0757080000 0.0875780000 0.0000010000 0.2866610000 0.0017580000 138536611 0 402718720 4.0629410744 3.9609603882 3.9000027180 891 1311867200.1517000198 0.0927980989 0.0794114817 0.1207897216 0.0058811155 0.4845690000 0.0760110000 0.0874080000 0.0307310000 0.2863940000 0.0017630000 138540339 0 402718720 4.0632009506 3.9612419605 3.9003126621 892 1311867200.1853220463 0.0933300555 0.0794270854 0.1207897216 0.0058812752 0.4112330000 0.0768390000 0.0444980000 0.0000000000 0.2859060000 0.0017540000 138544123 0 402718720 4.0599718094 3.9600291252 3.9002943039 893 1311867200.2179059982 0.0919943601 0.0794411585 0.1207897216 0.0058806581 0.7410390000 0.0769190000 0.0518180000 0.0313590000 0.2859670000 0.2927260000 138547795 0 402718720 4.0598645210 3.9618124962 3.9004769325 894 1311867200.2522649765 0.0917141587 0.0794548867 0.1207897216 0.0058774249 0.4735530000 0.0982510000 0.0741110000 0.0000010000 0.2963060000 0.0023730000 138551523 0 402718720 4.0577535629 3.9617249966 3.9009847641 895 1311867200.2825429440 0.0902682170 0.0794669687 0.1207897216 0.0058764478 0.4854070000 0.0847680000 0.0807240000 0.0309580000 0.2849330000 0.0017590000 138555139 0 402718720 4.0566787720 3.9607079029 3.9013261795 896 1311867200.3148880005 0.0901375338 0.0794788778 0.1207897216 0.0058733684 0.4394920000 0.0774020000 0.0735060000 0.0000000000 0.2845250000 0.0017560000 138558867 0 402718720 4.0548677444 3.9621438980 3.9018039703 897 1311867200.3514990807 0.0883969218 0.0794888198 0.1207897216 0.0058733699 0.7353640000 0.0755940000 0.0539080000 0.0312460000 0.2827180000 0.2896410000 138562595 0 402718720 4.0539159775 3.9602925777 3.9024457932 898 1311867200.3837759495 0.0878168344 0.0794980938 0.1207897216 0.0058794164 0.4248320000 0.0774310000 0.0589700000 0.0000010000 0.2843880000 0.0017530000 138566323 0 402718720 4.0522203445 3.9611921310 3.9028556347 899 1311867200.4162800312 0.0876097828 0.0795071168 0.1207897216 0.0058768885 0.4529520000 0.0756210000 0.0583130000 0.0311840000 0.2838120000 0.0017590000 138569939 0 402718720 4.0499372482 3.9610145092 3.9031918049 900 1311867200.4522490501 0.0871766657 0.0795156385 0.1207897216 0.0058746212 0.4155560000 0.0765550000 0.0515940000 0.0000010000 0.2833720000 0.0017510000 138573723 0 402718720 4.0470867157 3.9601759911 3.9033334255 901 1311867200.4850699902 0.0870224088 0.0795239701 0.1207897216 0.0058752169 0.7900800000 0.0926300000 0.0922280000 0.0314690000 0.2816770000 0.2897950000 138577395 0 402718720 4.0445055962 3.9606909752 3.9036786556 902 1311867200.5143918991 0.0865532756 0.0795317632 0.1207897216 0.0058731633 0.4505960000 0.0765220000 0.0873900000 0.0000000000 0.2826690000 0.0017520000 138581067 0 402718720 4.0423302650 3.9596705437 3.9043610096 903 1311867200.5505030155 0.0865279287 0.0795395109 0.1207897216 0.0058765410 0.4820200000 0.0771150000 0.0875130000 0.0309530000 0.2824130000 0.0017560000 138584851 0 402718720 4.0392179489 3.9602057934 3.9047510624 904 1311867200.5832219124 0.0875393525 0.0795483602 0.1207897216 0.0058813482 0.4795560000 0.1032850000 0.0920530000 0.0000010000 0.2799710000 0.0018450000 138588523 0 402718720 4.0358777046 3.9609189034 3.9053010941 905 1311867200.6145610809 0.0875699520 0.0795572239 0.1207897216 0.0058802518 0.7693710000 0.0883900000 0.0694700000 0.0313910000 0.2799570000 0.2976940000 138592139 0 402718720 4.0326099396 3.9600191116 3.9058864117 906 1311867200.6504778862 0.0862430260 0.0795646033 0.1207897216 0.0058796001 0.5135320000 0.0981790000 0.1165240000 0.0000000000 0.2939590000 0.0023580000 138595923 0 402718720 4.0312042236 3.9602489471 3.9064297676 907 1311867200.6851279736 0.0859975144 0.0795716959 0.1207897216 0.0058768499 0.4731660000 0.0985520000 0.0592980000 0.0317860000 0.2794770000 0.0017630000 138599707 0 402718720 4.0284643173 3.9600837231 3.9067666531 908 1311867200.7189719677 0.0868241936 0.0795796832 0.1207897216 0.0058749232 0.4479280000 0.0772070000 0.0875650000 0.0000010000 0.2790870000 0.0017550000 138603435 0 402718720 4.0243101120 3.9599227905 3.9070913792 909 1311867200.7503669262 0.0877701268 0.0795886936 0.1207897216 0.0058724603 0.7974670000 0.0883810000 0.0873180000 0.0308850000 0.2893990000 0.2990100000 138607051 0 402718720 4.0206456184 3.9607441425 3.9075078964 910 1311867200.7832930088 0.0872465298 0.0795971088 0.1207897216 0.0058768992 0.4685860000 0.0978060000 0.0781920000 0.0000000000 0.2885100000 0.0017450000 138610779 0 402718720 4.0187010765 3.9607999325 3.9080626965 911 1311867200.8181068897 0.0870489627 0.0796052886 0.1207897216 0.0058748476 0.4779600000 0.0776830000 0.0879210000 0.0314230000 0.2768990000 0.0017720000 138614507 0 402718720 4.0153803825 3.9605376720 3.9084105492 912 1311867200.8501501083 0.0877263620 0.0796141933 0.1207897216 0.0058721782 0.4408010000 0.1068770000 0.0542820000 0.0000010000 0.2755430000 0.0017570000 138618123 0 402718720 4.0123009682 3.9612140656 3.9089145660 913 1311867200.8845369816 0.0876798034 0.0796230275 0.1207897216 0.0058716903 0.7621690000 0.0773180000 0.0593520000 0.0383000000 0.2889630000 0.2957480000 138621963 0 402718720 4.0095095634 3.9609050751 3.9095866680 914 1311867200.9194929600 0.0889942795 0.0796332805 0.1207897216 0.0058712409 0.4571380000 0.0983400000 0.0785400000 0.0000010000 0.2762090000 0.0017600000 138625691 0 402718720 4.0053281784 3.9600584507 3.9100875854 915 1311867200.9512679577 0.0884927660 0.0796429630 0.1207897216 0.0058701891 0.4632100000 0.0768460000 0.0769700000 0.0308910000 0.2742150000 0.0018600000 138629307 0 402718720 4.0033226013 3.9601264000 3.9105641842 916 1311867200.9856009483 0.0887923762 0.0796529515 0.1207897216 0.0058715632 0.4461090000 0.0778920000 0.0881080000 0.0000010000 0.2760250000 0.0017680000 138633091 0 402718720 4.0017800331 3.9594058990 3.9107751846 917 1311867201.0184400082 0.0891403779 0.0796632976 0.1207897216 0.0058683732 0.7371020000 0.0773900000 0.0659370000 0.0309170000 0.2770620000 0.2835030000 138636763 0 402718720 3.9998714924 3.9594917297 3.9108181000 918 1311867201.0555179119 0.0892293975 0.0796737182 0.1207897216 0.0058668951 0.4452180000 0.0765920000 0.0867850000 0.0000010000 0.2777790000 0.0017600000 138640603 0 402718720 3.9982523918 3.9597818851 3.9106993675 919 1311867201.0825428963 0.0900798291 0.0796850415 0.1207897216 0.0058668506 0.4780830000 0.0767740000 0.0872680000 0.0313540000 0.2786310000 0.0017570000 138644107 0 402718720 3.9958593845 3.9591453075 3.9107494354 920 1311867201.1193449497 0.0905617028 0.0796968640 0.1207897216 0.0058645528 0.4472700000 0.0769450000 0.0868780000 0.0000000000 0.2793790000 0.0017580000 138647947 0 402718720 3.9940061569 3.9591095448 3.9108204842 921 1311867201.1506710052 0.0905768424 0.0797086772 0.1207897216 0.0058614860 0.7276460000 0.0768340000 0.0511900000 0.0313740000 0.2797200000 0.2862460000 138651507 0 402718720 3.9929444790 3.9593195915 3.9107506275 922 1311867201.1830160618 0.0902139321 0.0797200712 0.1207897216 0.0058599042 0.4198360000 0.0859730000 0.0492440000 0.0000010000 0.2805400000 0.0017630000 138655179 0 402718720 3.9921329021 3.9587500095 3.9108572006 923 1311867201.2196528912 0.0915629044 0.0797329020 0.1207897216 0.0058580702 0.4517490000 0.0764090000 0.0581620000 0.0313120000 0.2817720000 0.0017590000 138658907 0 402718720 3.9888694286 3.9597630501 3.9106578827 924 1311867201.2503149509 0.0911830589 0.0797452939 0.1207897216 0.0058549017 0.4669150000 0.0919630000 0.0886470000 0.0000000000 0.2821600000 0.0017480000 138662579 0 402718720 3.9880826473 3.9599838257 3.9108591080 925 1311867201.2824099064 0.0904240608 0.0797568385 0.1207897216 0.0058524125 0.7654870000 0.0755920000 0.0856060000 0.0308750000 0.2822260000 0.2888860000 138666251 0 402718720 3.9874422550 3.9604771137 3.9106025696 926 1311867201.3180539608 0.0904155672 0.0797683490 0.1207897216 0.0058505442 0.4132750000 0.0758540000 0.0505640000 0.0000010000 0.2827830000 0.0017350000 138670035 0 402718720 3.9851138592 3.9590425491 3.9105839729 927 1311867201.3522200584 0.0914060846 0.0797809032 0.1207897216 0.0058501308 0.4556510000 0.0763830000 0.0610680000 0.0314340000 0.2827030000 0.0017610000 138673763 0 402718720 3.9820814133 3.9606058598 3.9103443623 928 1311867201.3842790127 0.0908502787 0.0797928314 0.1207897216 0.0058501013 0.4214040000 0.0761330000 0.0579820000 0.0000010000 0.2831910000 0.0017440000 138677435 0 402718720 3.9806153774 3.9622082710 3.9103331566 929 1311867201.4198760986 0.0903413370 0.0798041861 0.1207897216 0.0058690804 0.7444260000 0.0895650000 0.0520420000 0.0314150000 0.2809530000 0.2881230000 138681107 0 402718720 3.9772672653 3.9605371952 3.9099111557 930 1311867201.4558579922 0.0907640085 0.0798159709 0.1207897216 0.0058712786 0.4124980000 0.0747360000 0.0505490000 0.0000000000 0.2830870000 0.0017490000 138684779 0 402718720 3.9737884998 3.9617593288 3.9097301960 931 1311867201.4853110313 0.0911302418 0.0798281237 0.1207897216 0.0058706200 0.4454090000 0.0765580000 0.0510120000 0.0312660000 0.2824800000 0.0017620000 138688395 0 402718720 3.9713814259 3.9643783569 3.9096779823 932 1311867201.5198690891 0.0906786472 0.0798397659 0.1207897216 0.0058692384 0.4128880000 0.0767570000 0.0512400000 0.0000010000 0.2807690000 0.0017630000 138692179 0 402718720 3.9684841633 3.9633533955 3.9097623825 933 1311867201.5527739525 0.0917149112 0.0798524938 0.1207897216 0.0058677853 0.7592800000 0.0763850000 0.0835910000 0.0314190000 0.2788880000 0.2866340000 138695795 0 402718720 3.9640767574 3.9638268948 3.9094495773 934 1311867201.5840220451 0.0910476893 0.0798644801 0.1207897216 0.0058647368 0.4666030000 0.0983400000 0.0848560000 0.0000000000 0.2793040000 0.0017590000 138699467 0 402718720 3.9626224041 3.9640569687 3.9093773365 935 1311867201.6197049618 0.0905798003 0.0798759403 0.1207897216 0.0058619443 0.4411270000 0.0763280000 0.0509920000 0.0313540000 0.2783340000 0.0017620000 138703251 0 402718720 3.9608747959 3.9642651081 3.9089896679 936 1311867201.6515579224 0.0893488750 0.0798860610 0.1207897216 0.0058611083 0.4312870000 0.0749480000 0.0755160000 0.0000010000 0.2767200000 0.0017580000 138706867 0 402718720 3.9599080086 3.9638977051 3.9087843895 937 1311867201.6839449406 0.0899506435 0.0798968023 0.1207897216 0.0058580282 0.7420220000 0.0889170000 0.0580320000 0.0313730000 0.2773590000 0.2839630000 138710595 0 402718720 3.9569079876 3.9648272991 3.9083130360 938 1311867201.7189009190 0.0905420482 0.0799081512 0.1207897216 0.0058578198 0.4415280000 0.0881550000 0.0723360000 0.0000010000 0.2769100000 0.0017560000 138714379 0 402718720 3.9547657967 3.9663190842 3.9083070755 939 1311867201.7507290840 0.0898983553 0.0799187904 0.1207897216 0.0058561291 0.5055150000 0.1041800000 0.0905010000 0.0309160000 0.2757750000 0.0017700000 138718051 0 402718720 3.9529862404 3.9655547142 3.9079356194 940 1311867201.7858049870 0.0898565352 0.0799293624 0.1207897216 0.0058595349 0.4470200000 0.0765290000 0.0910200000 0.0000010000 0.2753120000 0.0017660000 138721723 0 402718720 3.9505081177 3.9659693241 3.9076993465 941 1311867201.8190178871 0.0897583961 0.0799398077 0.1207897216 0.0058660931 0.7284090000 0.0765480000 0.0614330000 0.0314850000 0.2742270000 0.2823370000 138725507 0 402718720 3.9500582218 3.9689133167 3.9078979492 942 1311867201.8505740166 0.0893360898 0.0799497825 0.1207897216 0.0058686344 0.4056730000 0.0763550000 0.0509340000 0.0000010000 0.2742360000 0.0017510000 138729123 0 402718720 3.9486088753 3.9678351879 3.9076092243 943 1311867201.8862850666 0.0888578370 0.0799592291 0.1207897216 0.0058658247 0.5044980000 0.0760230000 0.0970200000 0.0382540000 0.2882660000 0.0023690000 138732851 0 402718720 3.9479663372 3.9677505493 3.9075260162 944 1311867201.9195730686 0.0898503140 0.0799697069 0.1207897216 0.0058652282 0.4533490000 0.0881080000 0.0864080000 0.0000010000 0.2747100000 0.0017490000 138736635 0 402718720 3.9459342957 3.9690897465 3.9073653221 945 1311867201.9516520500 0.0896658376 0.0799799674 0.1207897216 0.0058632344 0.7486710000 0.0757950000 0.0842350000 0.0313480000 0.2741270000 0.2808060000 138740195 0 402718720 3.9446835518 3.9685983658 3.9068329334 946 1311867201.9894599915 0.0885869265 0.0799890656 0.1207897216 0.0058606687 0.4198900000 0.0761300000 0.0650510000 0.0000010000 0.2745400000 0.0017530000 138744091 0 402718720 3.9449448586 3.9686832428 3.9062452316 947 1311867202.0184879303 0.0891584381 0.0799987482 0.1207897216 0.0058581104 0.4563480000 0.0884720000 0.0578900000 0.0309120000 0.2749100000 0.0017690000 138747651 0 402718720 3.9432475567 3.9692223072 3.9057493210 948 1311867202.0507359505 0.0883323252 0.0800075389 0.1207897216 0.0058558708 0.4411940000 0.0759130000 0.0862320000 0.0000010000 0.2748860000 0.0017650000 138751323 0 402718720 3.9436297417 3.9698765278 3.9052450657 949 1311867202.0866351128 0.0888590142 0.0800168660 0.1207897216 0.0058530647 0.7518910000 0.0753730000 0.0860540000 0.0313510000 0.2749580000 0.2818160000 138755107 0 402718720 3.9420382977 3.9702329636 3.9048447609 950 1311867202.1185920238 0.0897436440 0.0800271047 0.1207897216 0.0058512953 0.4146440000 0.0755960000 0.0608740000 0.0000010000 0.2740220000 0.0017520000 138758779 0 402718720 3.9394195080 3.9706158638 3.9045882225 951 1311867202.1516621113 0.0895989537 0.0800371698 0.1207897216 0.0058493703 0.4473630000 0.0744530000 0.0625900000 0.0312420000 0.2749840000 0.0017170000 138762507 0 402718720 3.9386541843 3.9718186855 3.9046473503 952 1311867202.1866259575 0.0878986716 0.0800454276 0.1207897216 0.0058472878 0.4391970000 0.0750680000 0.0861450000 0.0000010000 0.2738170000 0.0017500000 138766235 0 402718720 3.9395406246 3.9718139172 3.9046242237 953 1311867202.2191269398 0.0892078504 0.0800550419 0.1207897216 0.0058452152 0.7540440000 0.0761730000 0.0865590000 0.0309250000 0.2738500000 0.2839460000 138769907 0 402718720 3.9364731312 3.9721939564 3.9044556618 954 1311867202.2513220310 0.0887503102 0.0800641565 0.1207897216 0.0058424514 0.4225250000 0.0864440000 0.0579810000 0.0000000000 0.2739130000 0.0017540000 138773523 0 402718720 3.9358215332 3.9729692936 3.9045987129 955 1311867202.2868280411 0.0880495012 0.0800725181 0.1207897216 0.0058405383 0.4382470000 0.0769370000 0.0541690000 0.0314740000 0.2712990000 0.0018620000 138777307 0 402718720 3.9353766441 3.9738984108 3.9045922756 956 1311867202.3199880123 0.0887083262 0.0800815514 0.1207897216 0.0058390237 0.4206430000 0.0758710000 0.0686220000 0.0000010000 0.2719620000 0.0017580000 138780979 0 402718720 3.9327969551 3.9723684788 3.9045424461 957 1311867202.3523900509 0.0881682932 0.0800900015 0.1207897216 0.0058365103 0.7466740000 0.0745380000 0.0855370000 0.0312240000 0.2732910000 0.2796710000 138784651 0 402718720 3.9318706989 3.9727256298 3.9043879509 958 1311867202.3883628845 0.0876901522 0.0800979348 0.1207897216 0.0058336588 0.4804250000 0.0769810000 0.1119250000 0.0000010000 0.2864920000 0.0023830000 138788435 0 402718720 3.9310777187 3.9742066860 3.9043867588 959 1311867202.4196391106 0.0882292986 0.0801064138 0.1207897216 0.0058324020 0.5183320000 0.0964230000 0.0956190000 0.0389290000 0.2832060000 0.0017660000 138792107 0 402718720 3.9293878078 3.9738843441 3.9043602943 960 1311867202.4529430866 0.0881638974 0.0801148070 0.1207897216 0.0058297788 0.4406870000 0.0767160000 0.0865690000 0.0000010000 0.2732360000 0.0017540000 138795779 0 402718720 3.9284811020 3.9728984833 3.9044270515 961 1311867202.4875710011 0.0888000354 0.0801238447 0.1207897216 0.0058294055 0.7542800000 0.0760830000 0.0911810000 0.0309960000 0.2729750000 0.2806540000 138799507 0 402718720 3.9274370670 3.9739620686 3.9048044682 962 1311867202.5206449032 0.0889625922 0.0801330326 0.1207897216 0.0058435445 0.4394240000 0.0741450000 0.0875680000 0.0000000000 0.2733890000 0.0018050000 138803179 0 402718720 3.9261732101 3.9747486115 3.9045910835 963 1311867202.5508940220 0.0895828456 0.0801428455 0.1207897216 0.0058405875 0.4446040000 0.0888970000 0.0462190000 0.0314330000 0.2738530000 0.0017620000 138806795 0 402718720 3.9246091843 3.9743299484 3.9047613144 964 1311867202.5864949226 0.0902839303 0.0801533653 0.1207897216 0.0058499217 0.4119690000 0.0885120000 0.0436280000 0.0000000000 0.2756470000 0.0017590000 138810635 0 402718720 3.9230997562 3.9735634327 3.9047451019 965 1311867202.6185030937 0.0904214904 0.0801640059 0.1207897216 0.0058511135 0.7582130000 0.0765240000 0.0866510000 0.0309460000 0.2773930000 0.2842970000 138814307 0 402718720 3.9215686321 3.9735255241 3.9041435719 966 1311867202.6514449120 0.0914815068 0.0801757217 0.1207897216 0.0058558750 0.4728720000 0.0999710000 0.0908410000 0.0000010000 0.2776180000 0.0018450000 138817979 0 402718720 3.9185760021 3.9745571613 3.9034063816 967 1311867202.6866559982 0.0910953805 0.0801870140 0.1207897216 0.0058534533 0.4821520000 0.0759040000 0.0911660000 0.0314520000 0.2794270000 0.0017630000 138821763 0 402718720 3.9177913666 3.9752845764 3.9027414322 968 1311867202.7185359001 0.0913295075 0.0801985248 0.1207897216 0.0058509203 0.4198630000 0.0755870000 0.0606070000 0.0000000000 0.2792430000 0.0018590000 138825435 0 402718720 3.9154343605 3.9738886356 3.9016067982 969 1311867202.7507350445 0.0911566094 0.0802098335 0.1207897216 0.0058488966 0.7475460000 0.0899870000 0.0501150000 0.0313740000 0.2831410000 0.2905070000 138829107 0 402718720 3.9135646820 3.9728529453 3.9002940655 970 1311867202.7897169590 0.0915459767 0.0802215202 0.1207897216 0.0058462861 0.4474090000 0.0736950000 0.0842120000 0.0000000000 0.2853050000 0.0017390000 138833003 0 402718720 3.9120018482 3.9738717079 3.8994152546 971 1311867202.8190000057 0.0918363854 0.0802334820 0.1207897216 0.0058449401 0.4460830000 0.0739940000 0.0495830000 0.0314210000 0.2868890000 0.0017470000 138836619 0 402718720 3.9101345539 3.9740898609 3.8983778954 972 1311867202.8527579308 0.0909985751 0.0802445572 0.1207897216 0.0058420084 0.4652990000 0.0875360000 0.0848220000 0.0000010000 0.2887300000 0.0017480000 138840291 0 402718720 3.9091358185 3.9738466740 3.8973762989 973 1311867202.8873219490 0.0904710293 0.0802550674 0.1207897216 0.0058412217 0.7924500000 0.0866100000 0.0842310000 0.0309260000 0.2900810000 0.2981900000 138844019 0 402718720 3.9088239670 3.9755423069 3.8969531059 974 1311867202.9199879169 0.0901391953 0.0802652154 0.1207897216 0.0058388633 0.4563510000 0.0849160000 0.0772930000 0.0000010000 0.2899710000 0.0017280000 138847691 0 402718720 3.9089701176 3.9760525227 3.8972146511 975 1311867202.9525690079 0.0908496380 0.0802760712 0.1207897216 0.0058426514 0.4625680000 0.0729560000 0.0664630000 0.0314130000 0.2875680000 0.0017400000 138851419 0 402718720 3.9078674316 3.9752070904 3.8972604275 976 1311867202.9868710041 0.0889999196 0.0802850096 0.1207897216 0.0058480122 0.4499190000 0.0732670000 0.0840840000 0.0000010000 0.2883990000 0.0017360000 138855147 0 402718720 3.9098732471 3.9756360054 3.8978042603 977 1311867203.0202019215 0.0894536376 0.0802943941 0.1207897216 0.0058450504 0.8024310000 0.1007960000 0.0892640000 0.0309750000 0.2848540000 0.2940960000 138858819 0 402718720 3.9094803333 3.9759862423 3.8981790543 978 1311867203.0560851097 0.0900645033 0.0803043840 0.1207897216 0.0058484426 0.4134970000 0.0742450000 0.0527720000 0.0000010000 0.2820600000 0.0018480000 138862603 0 402718720 3.9091219902 3.9732642174 3.8986577988 979 1311867203.0865778923 0.0904877037 0.0803147857 0.1207897216 0.0058469054 0.4801700000 0.0901470000 0.0714300000 0.0314120000 0.2829570000 0.0017580000 138866219 0 402718720 3.9100167751 3.9734966755 3.8991818428 980 1311867203.1189930439 0.0899727046 0.0803246407 0.1207897216 0.0058536373 0.4477040000 0.0756590000 0.0864210000 0.0000010000 0.2814190000 0.0017490000 138869891 0 402718720 3.9112174511 3.9715578556 3.8994965553 981 1311867203.1549820900 0.0906832889 0.0803352000 0.1207897216 0.0058588646 0.7680490000 0.0754690000 0.0899550000 0.0314780000 0.2807320000 0.2879720000 138873675 0 402718720 3.9106929302 3.9696707726 3.8995857239 982 1311867203.1877939701 0.0926325917 0.0803477228 0.1207897216 0.0058923676 0.4475430000 0.0757040000 0.0857940000 0.0000000000 0.2818220000 0.0017470000 138877347 0 402718720 3.9088397026 3.9679758549 3.8993742466 983 1311867203.2185909748 0.0929530933 0.0803605462 0.1207897216 0.0058923537 0.4768910000 0.0741020000 0.0849130000 0.0313620000 0.2823120000 0.0017430000 138881019 0 402718720 3.9100925922 3.9696161747 3.8993241787 984 1311867203.2552030087 0.0932114050 0.0803736060 0.1207897216 0.0058906761 0.4432990000 0.0858650000 0.0714280000 0.0000010000 0.2818070000 0.0017390000 138884803 0 402718720 3.9099793434 3.9674980640 3.8991122246 985 1311867203.2864799500 0.0936222225 0.0803870564 0.1207897216 0.0058901678 0.7660650000 0.0748420000 0.0852950000 0.0314670000 0.2824320000 0.2896120000 138888419 0 402718720 3.9092984200 3.9662797451 3.8984463215 986 1311867203.3194670677 0.0928521678 0.0803996985 0.1207897216 0.0058876134 0.4470030000 0.0748800000 0.0851610000 0.0000010000 0.2827650000 0.0017470000 138892203 0 402718720 3.9107186794 3.9661912918 3.8980295658 987 1311867203.3547461033 0.0925239995 0.0804119825 0.1207897216 0.0058858050 0.4426280000 0.0749110000 0.0502960000 0.0310120000 0.2821990000 0.0017480000 138895875 0 402718720 3.9116954803 3.9663467407 3.8978157043 988 1311867203.3865599632 0.0917748213 0.0804234833 0.1207897216 0.0058887541 0.4198680000 0.0754000000 0.0607890000 0.0000010000 0.2792490000 0.0018490000 138899547 0 402718720 3.9123644829 3.9646701813 3.8975646496 989 1311867203.4183609486 0.0914593041 0.0804346419 0.1207897216 0.0058948649 0.7842560000 0.0961430000 0.0858230000 0.0313640000 0.2806690000 0.2877990000 138903275 0 402718720 3.9117867947 3.9606807232 3.8967752457 990 1311867203.4545118809 0.0922411382 0.0804465676 0.1207897216 0.0058929701 0.4492280000 0.0746750000 0.0895360000 0.0000000000 0.2807740000 0.0017520000 138907059 0 402718720 3.9112131596 3.9604494572 3.8965940475 991 1311867203.4864439964 0.0911694020 0.0804573878 0.1207897216 0.0058914366 0.4432550000 0.0747670000 0.0529700000 0.0310490000 0.2802220000 0.0017520000 138910675 0 402718720 3.9121894836 3.9584784508 3.8964765072 992 1311867203.5185539722 0.0917315036 0.0804687529 0.1207897216 0.0058929045 0.4502570000 0.0755760000 0.0902930000 0.0000010000 0.2801510000 0.0017570000 138914403 0 402718720 3.9111351967 3.9553315639 3.8957338333 993 1311867203.5560259819 0.0923078209 0.0804806754 0.1207897216 0.0058903445 0.7665080000 0.0750010000 0.0857810000 0.0314540000 0.2823170000 0.2894930000 138918187 0 402718720 3.9105091095 3.9531118870 3.8951063156 994 1311867203.5876550674 0.0922724009 0.0804925383 0.1207897216 0.0058879947 0.4476400000 0.0751850000 0.0857700000 0.0000010000 0.2824450000 0.0017530000 138921859 0 402718720 3.9108026028 3.9522473812 3.8947715759 995 1311867203.6191980839 0.0921902806 0.0805042948 0.1207897216 0.0058862613 0.4776560000 0.0746320000 0.0855440000 0.0314560000 0.2817930000 0.0017470000 138925531 0 402718720 3.9106307030 3.9496200085 3.8944573402 996 1311867203.6557719707 0.0909444913 0.0805147770 0.1207897216 0.0058836910 0.4469810000 0.0750510000 0.0853860000 0.0000010000 0.2822980000 0.0017550000 138929259 0 402718720 3.9119920731 3.9469385147 3.8938012123 997 1311867203.6866750717 0.0924690887 0.0805267672 0.1207897216 0.0058821985 0.7634750000 0.0727910000 0.0840470000 0.0313090000 0.2828140000 0.2900540000 138932931 0 402718720 3.9097135067 3.9455347061 3.8933000565 998 1311867203.7195260525 0.0913383737 0.0805376005 0.1207897216 0.0058803544 0.4677770000 0.0944860000 0.0857330000 0.0000010000 0.2833020000 0.0017530000 138936603 0 402718720 3.9115250111 3.9437699318 3.8930661678 999 1311867203.7566421032 0.0918440446 0.0805489183 0.1207897216 0.0058777645 0.4991200000 0.0916430000 0.0896220000 0.0315370000 0.2818510000 0.0018510000 138940443 0 402718720 3.9115607738 3.9425556660 3.8930189610 1000 1311867203.7867228985 0.0919644609 0.0805603338 0.1207897216 0.0058748465 0.4355680000 0.0739810000 0.0746060000 0.0000010000 0.2827180000 0.0017460000 138944059 0 402718720 3.9113242626 3.9405374527 3.8926904202 1001 1311867203.8193860054 0.0915887058 0.0805713512 0.1207897216 0.0058720884 0.7325590000 0.0745360000 0.0500800000 0.0310720000 0.2836240000 0.2907800000 138947731 0 402718720 3.9120192528 3.9391624928 3.8921649456 1002 1311867203.8572859764 0.0921362266 0.0805828930 0.1207897216 0.0058706132 0.4295660000 0.0870120000 0.0432970000 0.0000010000 0.2941660000 0.0023370000 138951571 0 402718720 3.9115018845 3.9379951954 3.8914666176 1003 1311867203.8891890049 0.0922115818 0.0805944869 0.1207897216 0.0058684018 0.5125350000 0.0941350000 0.0758500000 0.0390390000 0.2984490000 0.0023400000 138955243 0 402718720 3.9110100269 3.9360840321 3.8905205727 1004 1311867203.9188020229 0.0923377573 0.0806061834 0.1207897216 0.0058659202 0.4994480000 0.0946670000 0.1127690000 0.0000010000 0.2877550000 0.0017470000 138958859 0 402718720 3.9105780125 3.9346411228 3.8896982670 1005 1311867203.9553489685 0.0928698182 0.0806183860 0.1207897216 0.0058633458 0.7749650000 0.0739030000 0.0842680000 0.0315200000 0.2876740000 0.2950900000 138962643 0 402718720 3.9102995396 3.9357061386 3.8886892796 1006 1311867203.9866371155 0.0921049342 0.0806298040 0.1207897216 0.0058639363 0.4512240000 0.0736660000 0.0845870000 0.0000010000 0.2887510000 0.0017260000 138966315 0 402718720 3.9106330872 3.9325270653 3.8876881599 1007 1311867204.0199849606 0.0918356404 0.0806409320 0.1207897216 0.0058624111 0.4878500000 0.0740850000 0.0889510000 0.0315700000 0.2887910000 0.0018430000 138969987 0 402718720 3.9110796452 3.9324069023 3.8864419460 1008 1311867204.0551509857 0.0931771398 0.0806533687 0.1207897216 0.0058598510 0.4323160000 0.0730650000 0.0635360000 0.0000000000 0.2914700000 0.0017410000 138973771 0 402718720 3.9092221260 3.9311256409 3.8853607178 1009 1311867204.0867509842 0.0917822570 0.0806643983 0.1207897216 0.0058599778 0.7941930000 0.0795740000 0.0884730000 0.0315610000 0.2915680000 0.3005420000 138977443 0 402718720 3.9103965759 3.9291472435 3.8841681480 1010 1311867204.1191530228 0.0923153833 0.0806759339 0.1207897216 0.0058572312 0.4346620000 0.0727600000 0.0631730000 0.0000000000 0.2944860000 0.0017260000 138981115 0 402718720 3.9099254608 3.9280581474 3.8831577301 1011 1311867204.1555769444 0.0921640024 0.0806872970 0.1207897216 0.0058546814 0.4666540000 0.0716580000 0.0628370000 0.0313480000 0.2965630000 0.0017350000 138984843 0 402718720 3.9101126194 3.9263596535 3.8823790550 1012 1311867204.1876530647 0.0914958343 0.0806979774 0.1207897216 0.0058537266 0.4376530000 0.0721490000 0.0628110000 0.0000000000 0.2984380000 0.0017160000 138988515 0 402718720 3.9107372761 3.9246785641 3.8816854954 1013 1311867204.2187769413 0.0926620066 0.0807097879 0.1207897216 0.0058522458 0.8116270000 0.0700130000 0.0822240000 0.0315100000 0.3129390000 0.3121660000 138992187 0 402718720 3.9094965458 3.9241352081 3.8812444210 1014 1311867204.2566440105 0.0919850618 0.0807209075 0.1207897216 0.0058498489 0.4636220000 0.0715460000 0.0869810000 0.0000000000 0.3006090000 0.0018170000 138996027 0 402718720 3.9106359482 3.9224321842 3.8808193207 1015 1311867204.2867140770 0.0919031501 0.0807319245 0.1207897216 0.0058473269 0.4678640000 0.0708750000 0.0581520000 0.0315560000 0.3030460000 0.0017170000 138999643 0 402718720 3.9102675915 3.9200520515 3.8800618649 1016 1311867204.3204538822 0.0925910771 0.0807435968 0.1207897216 0.0058447291 0.4511210000 0.0708920000 0.0683590000 0.0000010000 0.3076290000 0.0017130000 139003315 0 402718720 3.9098291397 3.9195256233 3.8797247410 1017 1311867204.3625741005 0.0932977796 0.0807559412 0.1207897216 0.0058419492 0.8178480000 0.0813640000 0.0746850000 0.0315160000 0.3093100000 0.3184260000 139007323 0 402718720 3.9091215134 3.9179873466 3.8796544075 1018 1311867204.3869600296 0.0941211879 0.0807690701 0.1207897216 0.0058393644 0.4391250000 0.0824300000 0.0410610000 0.0000000000 0.3114240000 0.0016960000 139010771 0 402718720 3.9077353477 3.9167120457 3.8791823387 1019 1311867204.4240970612 0.0943981856 0.0807824451 0.1207897216 0.0058366721 0.5191360000 0.0879950000 0.0818970000 0.0314980000 0.3135260000 0.0016990000 139014611 0 402718720 3.9075920582 3.9152748585 3.8789191246 1020 1311867204.4549949169 0.0948066264 0.0807961943 0.1207897216 0.0058349196 0.4558760000 0.0894620000 0.0470970000 0.0000010000 0.3150770000 0.0016900000 139018227 0 402718720 3.9074378014 3.9147818089 3.8787858486 1021 1311867204.4872748852 0.0945027620 0.0808096189 0.1207897216 0.0058334434 0.7947650000 0.0687040000 0.0486030000 0.0314600000 0.3167540000 0.3266980000 139021899 0 402718720 3.9074668884 3.9126191139 3.8783416748 1022 1311867204.5237219334 0.0960367620 0.0808245183 0.1207897216 0.0058309986 0.4650290000 0.0684610000 0.0732060000 0.0000000000 0.3191260000 0.0016810000 139025739 0 402718720 3.9055325985 3.9112279415 3.8780930042 1023 1311867204.5581860542 0.0963738859 0.0808397181 0.1207897216 0.0058301629 0.4641770000 0.0673450000 0.0400920000 0.0314760000 0.3210360000 0.0016820000 139029467 0 402718720 3.9054839611 3.9112160206 3.8779232502 1024 1311867204.5878469944 0.0961139351 0.0808546343 0.1207897216 0.0058280639 0.4880120000 0.0796380000 0.0830390000 0.0000000000 0.3211110000 0.0016640000 139033083 0 402718720 3.9050400257 3.9086227417 3.8778576851 1025 1311867204.6241528988 0.0965955257 0.0808699913 0.1207897216 0.0058254106 0.8224690000 0.0672350000 0.0614290000 0.0314320000 0.3243880000 0.3353990000 139135171 0 402718720 3.9037921429 3.9081211090 3.8778879642 1026 1311867204.6541819572 0.0965545923 0.0808852784 0.1207897216 0.0058229319 0.4742140000 0.0663460000 0.0777990000 0.0000000000 0.3258530000 0.0016570000 139343587 0 402718720 3.9036960602 3.9060645103 3.8781094551 1027 1311867204.6871540546 0.0965244099 0.0809005064 0.1207897216 0.0058204455 0.5081530000 0.0668250000 0.0779830000 0.0314620000 0.3276420000 0.0016710000 139347259 0 402718720 3.9035732746 3.9050505161 3.8781399727 1028 1311867204.7225689888 0.0977450386 0.0809168921 0.1207897216 0.0058200570 0.4644600000 0.0665420000 0.0651030000 0.0000010000 0.3285740000 0.0016590000 139351043 0 402718720 3.9024460316 3.9052250385 3.8785078526 1029 1311867204.7539510727 0.0986052826 0.0809340820 0.1207897216 0.0058175097 0.8453290000 0.0658600000 0.0817760000 0.0314920000 0.3259360000 0.3377250000 139354715 0 402718720 3.9003512859 3.9034411907 3.8788738251 1030 1311867204.7878720760 0.0981626511 0.0809508088 0.1207897216 0.0058157147 0.5040310000 0.0921570000 0.0776960000 0.0000000000 0.3298090000 0.0017820000 139358443 0 402718720 3.8997871876 3.9016506672 3.8796041012 1031 1311867204.8227200508 0.0980415344 0.0809673856 0.1207897216 0.0058135767 0.4886130000 0.0651440000 0.0577770000 0.0314470000 0.3300340000 0.0016600000 139362171 0 402718720 3.8998959064 3.9015817642 3.8810875416 1032 1311867204.8542668819 0.0969197452 0.0809828433 0.1207897216 0.0058132847 0.4891360000 0.0783210000 0.0771870000 0.0000000000 0.3293830000 0.0016520000 139365843 0 402718720 3.9002153873 3.8993320465 3.8820986748 1033 1311867204.8864960670 0.0970505998 0.0809983978 0.1207897216 0.0058111040 0.8481140000 0.0661320000 0.0774960000 0.0310000000 0.3298270000 0.3411190000 139369515 0 402718720 3.8992531300 3.8963320255 3.8831901550 1034 1311867204.9220221043 0.0983975753 0.0810152248 0.1207897216 0.0058085383 0.4947890000 0.0797490000 0.0800320000 0.0000000000 0.3307760000 0.0016590000 139373299 0 402718720 3.8973143101 3.8949980736 3.8844194412 1035 1311867204.9542920589 0.0990187377 0.0810326195 0.1207897216 0.0058058880 0.5114790000 0.0655030000 0.0812020000 0.0314150000 0.3291260000 0.0016610000 139376971 0 402718720 3.8961744308 3.8937423229 3.8854060173 1036 1311867204.9865999222 0.0973686203 0.0810483879 0.1207897216 0.0058047716 0.4798130000 0.0653380000 0.0812710000 0.0000000000 0.3287380000 0.0017490000 139380643 0 402718720 3.8977353573 3.8903651237 3.8861374855 1037 1311867205.0227239132 0.0974841490 0.0810642372 0.1207897216 0.0058060515 0.8427600000 0.0653320000 0.0678000000 0.0314240000 0.3310460000 0.3445830000 139384427 0 402718720 3.8976113796 3.8886256218 3.8868963718 1038 1311867205.0550808907 0.0969611555 0.0810795522 0.1207897216 0.0058198330 0.4777310000 0.0635780000 0.0755500000 0.0000010000 0.3343540000 0.0016510000 139388155 0 402718720 3.8979773521 3.8884394169 3.8877305984 1039 1311867205.0880999565 0.0972538218 0.0810951193 0.1207897216 0.0058173477 0.4888620000 0.0646770000 0.0540860000 0.0313840000 0.3344610000 0.0016610000 139391715 0 402718720 3.8971223831 3.8856296539 3.8885619640 1040 1311867205.1232450008 0.0992728695 0.0811125979 0.1207897216 0.0058173490 0.4862600000 0.0884990000 0.0609360000 0.0000000000 0.3323630000 0.0017430000 139395499 0 402718720 3.8952853680 3.8845486641 3.8892667294 1041 1311867205.1545319557 0.0982724130 0.0811290819 0.1207897216 0.0058233201 0.8265560000 0.0645340000 0.0448900000 0.0313920000 0.3358020000 0.3473410000 139399115 0 402718720 3.8978404999 3.8835947514 3.8900182247 1042 1311867205.1863510609 0.0980696231 0.0811453396 0.1207897216 0.0058301627 0.4820960000 0.0652090000 0.0763750000 0.0000000000 0.3362820000 0.0016490000 139402787 0 402718720 3.8977549076 3.8808383942 3.8907370567 1043 1311867205.2223129272 0.0987684131 0.0811622361 0.1207897216 0.0058292460 0.5146660000 0.0645750000 0.0803890000 0.0309440000 0.3342920000 0.0017500000 139406571 0 402718720 3.8966853619 3.8789932728 3.8912768364 1044 1311867205.2541849613 0.0973950997 0.0811777848 0.1207897216 0.0058275774 0.4989370000 0.0770960000 0.0796390000 0.0000010000 0.3379360000 0.0016430000 139410243 0 402718720 3.8981859684 3.8773479462 3.8919410706 1045 1311867205.2880499363 0.0979183689 0.0811938045 0.1207897216 0.0058251849 0.8261820000 0.0642900000 0.0436560000 0.0309350000 0.3362790000 0.3484100000 139413971 0 402718720 3.8976171017 3.8754570484 3.8928709030 1046 1311867205.3218879700 0.0981404483 0.0812100059 0.1207897216 0.0058237230 0.4959710000 0.0765220000 0.0746690000 0.0000010000 0.3405370000 0.0016320000 139417643 0 402718720 3.8970081806 3.8730516434 3.8935821056 1047 1311867205.3542900085 0.0980445817 0.0812260848 0.1207897216 0.0058285847 0.5269610000 0.0756870000 0.0742750000 0.0312850000 0.3415110000 0.0016430000 139421371 0 402718720 3.8970301151 3.8714494705 3.8945195675 1048 1311867205.3862779140 0.0987450480 0.0812428014 0.1207897216 0.0058357031 0.4954450000 0.0745810000 0.0745390000 0.0000010000 0.3420650000 0.0016320000 139425043 0 402718720 3.8957724571 3.8702085018 3.8955616951 1049 1311867205.4225649834 0.0985553861 0.0812593053 0.1207897216 0.0058390187 0.8678430000 0.0933070000 0.0463160000 0.0309300000 0.3397330000 0.3549470000 139428827 0 402718720 3.8949997425 3.8681576252 3.8960714340 1050 1311867205.4540419579 0.0981695876 0.0812754103 0.1207897216 0.0058409060 0.4591630000 0.0622850000 0.0521540000 0.0000000000 0.3404870000 0.0016260000 139432499 0 402718720 3.8954553604 3.8674900532 3.8969910145 1051 1311867205.4865119457 0.0978420451 0.0812911730 0.1207897216 0.0058417761 0.5182830000 0.0626130000 0.0779540000 0.0313340000 0.3421340000 0.0016420000 139436171 0 402718720 3.8942091465 3.8655035496 3.8981330395 1052 1311867205.5230340958 0.0972833633 0.0813063747 0.1207897216 0.0058521190 0.4870480000 0.0630460000 0.0784920000 0.0000010000 0.3410090000 0.0017320000 139439955 0 402718720 3.8938348293 3.8634078503 3.8988902569 1053 1311867205.5542900562 0.0984238163 0.0813226306 0.1207897216 0.0058739067 0.8504830000 0.0627860000 0.0524070000 0.0313540000 0.3439550000 0.3573660000 139443627 0 402718720 3.8919789791 3.8639886379 3.8998746872 1054 1311867205.5866839886 0.0979834199 0.0813384378 0.1207897216 0.0058711623 0.4969280000 0.0734270000 0.0738980000 0.0000010000 0.3453370000 0.0016310000 139447299 0 402718720 3.8915390968 3.8627793789 3.9011206627 1055 1311867205.6226179600 0.0982042849 0.0813544244 0.1207897216 0.0058734761 0.4806260000 0.0627560000 0.0399570000 0.0309190000 0.3425100000 0.0017390000 139451083 0 402718720 3.8890666962 3.8592841625 3.9020011425 1056 1311867205.6555979252 0.0995290875 0.0813716352 0.1207897216 0.0058718241 0.4627650000 0.0625100000 0.0522300000 0.0000010000 0.3437570000 0.0016310000 139454755 0 402718720 3.8862943649 3.8576986790 3.9028546810 1057 1311867205.6902959347 0.0985132977 0.0813878525 0.1207897216 0.0058693145 0.8405540000 0.0622690000 0.0373190000 0.0308540000 0.3476910000 0.3598010000 139458539 0 402718720 3.8869414330 3.8559653759 3.9036114216 1058 1311867205.7222061157 0.0981185362 0.0814036660 0.1207897216 0.0058665707 0.5150270000 0.0636440000 0.0964380000 0.0000010000 0.3506790000 0.0016240000 139462211 0 402718720 3.8861329556 3.8529613018 3.9041204453 1059 1311867205.7548348904 0.0978633240 0.0814192087 0.1207897216 0.0058641026 0.5348580000 0.0748690000 0.0770860000 0.0313400000 0.3473290000 0.0016350000 139465939 0 402718720 3.8853895664 3.8508195877 3.9043781757 1060 1311867205.7906379700 0.0987375677 0.0814355467 0.1207897216 0.0058621796 0.4932440000 0.0612040000 0.0763500000 0.0000010000 0.3514270000 0.0016260000 139469667 0 402718720 3.8838059902 3.8494105339 3.9052755833 1061 1311867205.8232109547 0.0976837501 0.0814508608 0.1207897216 0.0058730418 0.8834430000 0.0602940000 0.0721310000 0.0312410000 0.3523750000 0.3647520000 139473395 0 402718720 3.8839151859 3.8461165428 3.9056348801 1062 1311867205.8554759026 0.0983484611 0.0814667719 0.1207897216 0.0058754725 0.4779940000 0.0598870000 0.0595930000 0.0000000000 0.3543000000 0.0015820000 139477123 0 402718720 3.8824198246 3.8452093601 3.9062240124 1063 1311867205.8905880451 0.0993574709 0.0814836023 0.1207897216 0.0058753280 0.5158320000 0.0606620000 0.0656930000 0.0312680000 0.3539570000 0.0016200000 139480795 0 402718720 3.8806052208 3.8445224762 3.9065325260 1064 1311867205.9223020077 0.0981440544 0.0814992606 0.1207897216 0.0058838320 0.5028680000 0.0712900000 0.0757540000 0.0000010000 0.3515660000 0.0016170000 139484467 0 402718720 3.8813567162 3.8427288532 3.9068930149 1065 1311867205.9544939995 0.0981503054 0.0815148954 0.1207897216 0.0058815243 0.8825310000 0.0623890000 0.0558010000 0.0381040000 0.3565120000 0.3670910000 139488139 0 402718720 3.8805041313 3.8406519890 3.9072241783 1066 1311867205.9905850887 0.1001906171 0.0815324148 0.1207897216 0.0058906423 0.4906490000 0.0600360000 0.0711410000 0.0000010000 0.3552350000 0.0015980000 139491979 0 402718720 3.8780519962 3.8407046795 3.9077913761 1067 1311867206.0259850025 0.0996216312 0.0815493682 0.1207897216 0.0058912982 0.5216470000 0.0609300000 0.0663370000 0.0312290000 0.3581350000 0.0021110000 139495707 0 402718720 3.8786628246 3.8407070637 3.9078514576 1068 1311867206.0604250431 0.0998267606 0.0815664818 0.1207897216 0.0058979838 0.5295360000 0.0773610000 0.0798980000 0.0000010000 0.3672450000 0.0021120000 139499379 0 402718720 3.8768613338 3.8365745544 3.9080061913 1069 1311867206.0903289318 0.0992656350 0.0815830386 0.1207897216 0.0058954890 0.8966900000 0.0693600000 0.0721990000 0.0312920000 0.3545680000 0.3666010000 139502995 0 402718720 3.8768947124 3.8339929581 3.9080028534 1070 1311867206.1227540970 0.0983304605 0.0815986904 0.1207897216 0.0058929990 0.4929020000 0.0606640000 0.0732600000 0.0000000000 0.3546940000 0.0016110000 139506667 0 402718720 3.8783795834 3.8327093124 3.9084124565 1071 1311867206.1546130180 0.0988142416 0.0816147646 0.1207897216 0.0058904590 0.5244020000 0.0614250000 0.0722760000 0.0313160000 0.3551110000 0.0016270000 139510339 0 402718720 3.8773434162 3.8298690319 3.9080379009 1072 1311867206.1903800964 0.0992457792 0.0816312115 0.1207897216 0.0058917045 0.4574280000 0.0598760000 0.0370020000 0.0000000000 0.3562930000 0.0016160000 139514179 0 402718720 3.8762533665 3.8275637627 3.9081242085 1073 1311867206.2239561081 0.0995843634 0.0816479432 0.1207897216 0.0058897019 0.8800060000 0.0614170000 0.0586570000 0.0313310000 0.3569010000 0.3690720000 139517907 0 402718720 3.8758766651 3.8268229961 3.9079458714 1074 1311867206.2553579807 0.0994867384 0.0816645529 0.1207897216 0.0058884017 0.4952370000 0.0736320000 0.0606520000 0.0000000000 0.3566420000 0.0016220000 139521523 0 402718720 3.8752696514 3.8245618343 3.9075477123 1075 1311867206.2904770374 0.0999400616 0.0816815534 0.1207897216 0.0058856949 0.5275560000 0.0619240000 0.0763070000 0.0314140000 0.3536340000 0.0016290000 139525251 0 402718720 3.8738353252 3.8219809532 3.9072308540 1076 1311867206.3222041130 0.1008648053 0.0816993817 0.1207897216 0.0058831979 0.4952770000 0.0616640000 0.0722850000 0.0000010000 0.3570320000 0.0016170000 139528867 0 402718720 3.8724982738 3.8216211796 3.9067180157 1077 1311867206.3542530537 0.1014088839 0.0817176820 0.1207897216 0.0058816456 0.8759650000 0.0615380000 0.0547280000 0.0313280000 0.3569500000 0.3687600000 139532595 0 402718720 3.8709847927 3.8197820187 3.9063630104 1078 1311867206.3900070190 0.1001472771 0.0817347781 0.1207897216 0.0058811762 0.4656670000 0.0616110000 0.0427320000 0.0000010000 0.3570360000 0.0016200000 139536323 0 402718720 3.8720390797 3.8171732426 3.9063284397 1079 1311867206.4220259190 0.1004544497 0.0817521272 0.1207897216 0.0058802125 0.5605480000 0.0962480000 0.0720720000 0.0309460000 0.3569870000 0.0016320000 139539995 0 402718720 3.8716757298 3.8163876534 3.9061748981 1080 1311867206.4542310238 0.0994351208 0.0817685004 0.1207897216 0.0058776933 0.4709220000 0.0612110000 0.0485380000 0.0000000000 0.3568830000 0.0016170000 139543723 0 402718720 3.8724904060 3.8146114349 3.9061744213 1081 1311867206.4905378819 0.1000173837 0.0817853819 0.1207897216 0.0058830456 0.8639070000 0.0616550000 0.0428040000 0.0308880000 0.3572380000 0.3686520000 139547451 0 402718720 3.8709039688 3.8117885590 3.9061098099 1082 1311867206.5250329971 0.1007315516 0.0818028922 0.1207897216 0.0058844991 0.4665710000 0.0603160000 0.0438930000 0.0000010000 0.3580440000 0.0016290000 139551235 0 402718720 3.8696489334 3.8093461990 3.9060146809 1083 1311867206.5539300442 0.0992591083 0.0818190106 0.1207897216 0.0058890527 0.5051820000 0.0618680000 0.0486310000 0.0313640000 0.3590090000 0.0016300000 139554851 0 402718720 3.8714299202 3.8068635464 3.9059445858 1084 1311867206.5921130180 0.0987999514 0.0818346756 0.1207897216 0.0058882988 0.4549270000 0.0601470000 0.0305090000 0.0000010000 0.3599810000 0.0016280000 139558635 0 402718720 3.8721637726 3.8055672646 3.9055426121 1085 1311867206.6226360798 0.1015093625 0.0818528090 0.1207897216 0.0059018919 0.8708860000 0.0612410000 0.0426860000 0.0313010000 0.3606590000 0.3723290000 139562251 0 402718720 3.8691871166 3.8035197258 3.9054489136 1086 1311867206.6566751003 0.1001465246 0.0818696540 0.1207897216 0.0059002320 0.4992040000 0.0611020000 0.0719110000 0.0000010000 0.3618910000 0.0016150000 139565979 0 402718720 3.8701648712 3.8014988899 3.9052798748 1087 1311867206.6945209503 0.1003908142 0.0818866928 0.1207897216 0.0058980361 0.5305050000 0.0603500000 0.0749480000 0.0313230000 0.3596250000 0.0016180000 139569819 0 402718720 3.8701336384 3.8011429310 3.9048545361 1088 1311867206.7248480320 0.0989916474 0.0819024143 0.1207897216 0.0059064474 0.4645240000 0.0605430000 0.0363940000 0.0000010000 0.3632780000 0.0016160000 139573435 0 402718720 3.8706617355 3.7979342937 3.9045677185 1089 1311867206.7587969303 0.1017254815 0.0819206173 0.1207897216 0.0059520565 0.9019710000 0.0914210000 0.0381180000 0.0313520000 0.3614140000 0.3769610000 139577219 0 402718720 3.8687877655 3.7973883152 3.9041779041 1090 1311867206.7902839184 0.1002252772 0.0819374106 0.1207897216 0.0059705319 0.4827790000 0.0600870000 0.0564170000 0.0000010000 0.3619850000 0.0016020000 139580891 0 402718720 3.8690776825 3.7957861423 3.9034590721 1091 1311867206.8229770660 0.1006441936 0.0819545570 0.1207897216 0.0059684208 0.5039220000 0.0600820000 0.0419330000 0.0313770000 0.3662380000 0.0016130000 139584563 0 402718720 3.8681035042 3.7940604687 3.9028658867 1092 1311867206.8605449200 0.0999231040 0.0819710117 0.1207897216 0.0059658248 0.5009140000 0.0587340000 0.0698740000 0.0000000000 0.3680140000 0.0015860000 139588347 0 402718720 3.8680818081 3.7910046577 3.9022071362 1093 1311867206.8907771111 0.0989651531 0.0819865599 0.1207897216 0.0059643350 0.9121620000 0.0593490000 0.0699690000 0.0313080000 0.3679840000 0.3808580000 139591963 0 402718720 3.8693633080 3.7906813622 3.9015250206 1094 1311867206.9225020409 0.1005755365 0.0820035516 0.1207897216 0.0059617390 0.5236870000 0.0808140000 0.0700280000 0.0000010000 0.3685510000 0.0016040000 139595635 0 402718720 3.8670408726 3.7884306908 3.9010405540 1095 1311867206.9592480659 0.1011913046 0.0820210747 0.1207897216 0.0059599485 0.5045870000 0.0583850000 0.0435510000 0.0307590000 0.3674040000 0.0016720000 139599475 0 402718720 3.8662290573 3.7852749825 3.9005413055 1096 1311867206.9948680401 0.1010581329 0.0820384443 0.1207897216 0.0059706797 0.5050750000 0.0579090000 0.0732270000 0.0000000000 0.3696010000 0.0016070000 139603203 0 402718720 3.8664746284 3.7834486961 3.9001290798 1097 1311867207.0247550011 0.1016494781 0.0820563213 0.1207897216 0.0059731068 0.8887340000 0.0583830000 0.0352770000 0.0313220000 0.3735340000 0.3875560000 139606875 0 402718720 3.8667783737 3.7824068069 3.8999629021 1098 1311867207.0597259998 0.1019191146 0.0820744112 0.1207897216 0.0059706006 0.5094370000 0.0719810000 0.0583830000 0.0000000000 0.3747650000 0.0016030000 139610659 0 402718720 3.8659408092 3.7799162865 3.8997240067 1099 1311867207.0942800045 0.1009358838 0.0820915736 0.1207897216 0.0059756824 0.5491960000 0.0902250000 0.0498040000 0.0313870000 0.3734730000 0.0016100000 139614331 0 402718720 3.8669934273 3.7771120071 3.8995366096 1100 1311867207.1229140759 0.1000192687 0.0821078715 0.1207897216 0.0059783338 0.4960800000 0.0578290000 0.0605970000 0.0000010000 0.3733520000 0.0015970000 139617891 0 402718720 3.8687360287 3.7766911983 3.8992567062 1101 1311867207.1583549976 0.1024292558 0.0821263287 0.1207897216 0.0059842177 0.9287220000 0.0580120000 0.0687020000 0.0313690000 0.3770300000 0.3909470000 139621675 0 402718720 3.8662207127 3.7740328312 3.8993253708 1102 1311867207.1904919147 0.1008491740 0.0821433186 0.1207897216 0.0059838447 0.4992050000 0.0582680000 0.0584770000 0.0000010000 0.3781800000 0.0015750000 139625291 0 402718720 3.8675761223 3.7724938393 3.8989973068 1103 1311867207.2226181030 0.1016102210 0.0821609677 0.1207897216 0.0059824972 0.5174190000 0.0577540000 0.0462230000 0.0314180000 0.3777110000 0.0015990000 139629019 0 402718720 3.8667349815 3.7714197636 3.8991646767 1104 1311867207.2604830265 0.1009160727 0.0821779560 0.1207897216 0.0059812238 0.4728400000 0.0574110000 0.0368050000 0.0000010000 0.3743180000 0.0015900000 139632859 0 402718720 3.8671743870 3.7697083950 3.8992507458 1105 1311867207.2926900387 0.0999672040 0.0821940548 0.1207897216 0.0059815792 0.9300340000 0.0584750000 0.0687690000 0.0314430000 0.3774660000 0.3912000000 139636531 0 402718720 3.8675580025 3.7667357922 3.8996186256 1106 1311867207.3235239983 0.1006302163 0.0822107241 0.1207897216 0.0059853834 0.4865680000 0.0580330000 0.0462060000 0.0000000000 0.3780080000 0.0016030000 139640147 0 402718720 3.8666281700 3.7651371956 3.9001526833 1107 1311867207.3597478867 0.1006237343 0.0822273573 0.1207897216 0.0059830812 0.5067580000 0.0581170000 0.0349450000 0.0313930000 0.3779790000 0.0015970000 139643987 0 402718720 3.8662061691 3.7647981644 3.9006247520 1108 1311867207.3901309967 0.1002782062 0.0822436487 0.1207897216 0.0059839845 0.4805360000 0.0577800000 0.0407050000 0.0000000000 0.3777160000 0.0015910000 139647603 0 402718720 3.8656156063 3.7620160580 3.9010956287 1109 1311867207.4227840900 0.1001356393 0.0822597821 0.1207897216 0.0059813910 0.9175100000 0.0825640000 0.0340060000 0.0313960000 0.3751020000 0.3917220000 139651275 0 402718720 3.8644132614 3.7608590126 3.9010889530 1110 1311867207.4586789608 0.1001856849 0.0822759316 0.1207897216 0.0059809472 0.4886210000 0.0578250000 0.0425880000 0.0000000000 0.3831250000 0.0020570000 139655059 0 402718720 3.8640723228 3.7603118420 3.9017567635 1111 1311867207.4927639961 0.1003578231 0.0822922069 0.1207897216 0.0059790245 0.5656630000 0.0730320000 0.0681400000 0.0383120000 0.3818650000 0.0016050000 139658787 0 402718720 3.8623473644 3.7571089268 3.9019372463 1112 1311867207.5237300396 0.1010766402 0.0823090994 0.1207897216 0.0059808792 0.5103750000 0.0574720000 0.0723950000 0.0000000000 0.3761880000 0.0015970000 139662459 0 402718720 3.8604207039 3.7543065548 3.9023666382 1113 1311867207.5598409176 0.0997541621 0.0823247733 0.1207897216 0.0059785651 0.8995260000 0.0567200000 0.0348140000 0.0311940000 0.3804850000 0.3936210000 139666187 0 402718720 3.8614633083 3.7535827160 3.9027163982 1114 1311867207.5944800377 0.1008705869 0.0823414213 0.1207897216 0.0059780147 0.4953460000 0.0694820000 0.0406050000 0.0000010000 0.3809200000 0.0015900000 139669971 0 402718720 3.8591029644 3.7516944408 3.9028797150 1115 1311867207.6259219646 0.0982726961 0.0823557094 0.1207897216 0.0059762037 0.5449650000 0.0585540000 0.0689520000 0.0309790000 0.3821960000 0.0015960000 139673587 0 402718720 3.8604726791 3.7477333546 3.9033885002 1116 1311867207.6592938900 0.0982303545 0.0823699340 0.1207897216 0.0059744679 0.5144230000 0.0580650000 0.0684750000 0.0000000000 0.3835360000 0.0015940000 139677371 0 402718720 3.8599035740 3.7470779419 3.9033098221 1117 1311867207.6923089027 0.0985594988 0.0823844278 0.1207897216 0.0059729492 0.9544490000 0.0701660000 0.0679900000 0.0313780000 0.3841920000 0.3980180000 139681043 0 402718720 3.8591194153 3.7451591492 3.9034769535 1118 1311867207.7238640785 0.0983934402 0.0823987471 0.1207897216 0.0059720330 0.5194110000 0.0837130000 0.0459160000 0.0000000000 0.3854140000 0.0015950000 139684715 0 402718720 3.8582093716 3.7416501045 3.9038121700 1119 1311867207.7588050365 0.0989388749 0.0824135283 0.1207897216 0.0059704003 0.5235140000 0.0566930000 0.0481080000 0.0309530000 0.3834380000 0.0015830000 139688331 0 402718720 3.8566930294 3.7396271229 3.9036405087 1120 1311867207.7921919823 0.1005581543 0.0824297289 0.1207897216 0.0059681875 0.5071490000 0.0576600000 0.0457770000 0.0000010000 0.3986340000 0.0020470000 139692059 0 402718720 3.8542406559 3.7382197380 3.9038879871 1121 1311867207.8237760067 0.0988563821 0.0824443824 0.1207897216 0.0059672047 0.9699910000 0.0714250000 0.0595700000 0.0382950000 0.3945320000 0.4034310000 139695731 0 402718720 3.8555662632 3.7353787422 3.9039080143 1122 1311867207.8608479500 0.0983543694 0.0824585625 0.1207897216 0.0059656689 0.5291470000 0.0678150000 0.0666340000 0.0000010000 0.3903710000 0.0015770000 139699515 0 402718720 3.8564016819 3.7341771126 3.9042155743 1123 1311867207.8937089443 0.0979613215 0.0824723672 0.1207897216 0.0059631188 0.5464400000 0.0551310000 0.0645060000 0.0312260000 0.3912360000 0.0015830000 139703243 0 402718720 3.8569293022 3.7330224514 3.9041368961 1124 1311867207.9244139194 0.0997279063 0.0824877191 0.1207897216 0.0059612792 0.5194910000 0.0557230000 0.0704440000 0.0000010000 0.3889620000 0.0015890000 139706859 0 402718720 3.8541376591 3.7305426598 3.9045789242 1125 1311867207.9614970684 0.0970622376 0.0825006743 0.1207897216 0.0059636017 0.9291790000 0.0557820000 0.0392060000 0.0313920000 0.3925980000 0.4074540000 139710531 0 402718720 3.8568840027 3.7295718193 3.9046156406 1126 1311867207.9914131165 0.0970896035 0.0825136307 0.1207897216 0.0059779723 0.5095160000 0.0560810000 0.0448060000 0.0000010000 0.4035740000 0.0020260000 139714147 0 402718720 3.8572864532 3.7283794880 3.9049851894 1127 1311867208.0248498917 0.0967170596 0.0825262335 0.1207897216 0.0059929453 0.5654980000 0.0706050000 0.0448000000 0.0382810000 0.4067770000 0.0020250000 139717931 0 402718720 3.8565554619 3.7246174812 3.9052817822 1128 1311867208.0618500710 0.0979363620 0.0825398950 0.1207897216 0.0059926811 0.5113080000 0.0569810000 0.0555830000 0.0000010000 0.3943700000 0.0015790000 139721547 0 402718720 3.8553040028 3.7232375145 3.9055528641 1129 1311867208.0924620628 0.0971169397 0.0825528065 0.1207897216 0.0059903294 0.9717210000 0.0553640000 0.0696900000 0.0314350000 0.3912190000 0.4210040000 139725163 0 402718720 3.8566014767 3.7229311466 3.9054899216 1130 1311867208.1276559830 0.0973675251 0.0825659168 0.1207897216 0.0059887059 0.5646190000 0.0697450000 0.0865050000 0.0000010000 0.4040500000 0.0015700000 139728891 0 402718720 3.8556015491 3.7205681801 3.9054200649 1131 1311867208.1596069336 0.0958820283 0.0825776906 0.1207897216 0.0059861909 0.5497940000 0.0547790000 0.0629340000 0.0313930000 0.3963590000 0.0015750000 139732563 0 402718720 3.8573937416 3.7198476791 3.9052000046 1132 1311867208.1905009747 0.0981314853 0.0825914307 0.1207897216 0.0059843157 0.5253130000 0.0548130000 0.0652700000 0.0000000000 0.4001640000 0.0020110000 139736123 0 402718720 3.8544666767 3.7185347080 3.9048883915 1133 1311867208.2280850410 0.0983825624 0.0826053681 0.1207897216 0.0059822891 0.9429500000 0.0632210000 0.0335190000 0.0314260000 0.3982190000 0.4137840000 139740019 0 402718720 3.8542470932 3.7171888351 3.9047236443 1134 1311867208.2581789494 0.0976213664 0.0826186098 0.1207897216 0.0059803122 0.5135330000 0.0646770000 0.0450300000 0.0000010000 0.3994780000 0.0015560000 139743635 0 402718720 3.8545007706 3.7150378227 3.9044778347 1135 1311867208.2901990414 0.0974012837 0.0826316341 0.1207897216 0.0059778682 0.5528140000 0.0527220000 0.0637300000 0.0311390000 0.4008730000 0.0015580000 139747251 0 402718720 3.8547289371 3.7141909599 3.9040398598 1136 1311867208.3270208836 0.0981531143 0.0826452974 0.1207897216 0.0059804313 0.5432550000 0.0728460000 0.0646040000 0.0000010000 0.4014320000 0.0015590000 139751091 0 402718720 3.8542118073 3.7130870819 3.9039595127 1137 1311867208.3580970764 0.0981843621 0.0826589641 0.1207897216 0.0059821312 0.9717770000 0.0533200000 0.0639720000 0.0312940000 0.4023820000 0.4180420000 139754763 0 402718720 3.8538148403 3.7113642693 3.9040358067 1138 1311867208.3910560608 0.0973850042 0.0826719044 0.1207897216 0.0059801605 0.4919980000 0.0527340000 0.0325750000 0.0000010000 0.4023520000 0.0015540000 139758379 0 402718720 3.8547718525 3.7105572224 3.9038712978 1139 1311867208.4260230064 0.0979892239 0.0826853525 0.1207897216 0.0059779332 0.5251220000 0.0546510000 0.0350690000 0.0314250000 0.3993800000 0.0016590000 139762163 0 402718720 3.8532872200 3.7079989910 3.9036309719 1140 1311867208.4577419758 0.0982642993 0.0826990182 0.1207897216 0.0059790576 0.5264230000 0.0532570000 0.0675680000 0.0000000000 0.4012650000 0.0015610000 139765835 0 402718720 3.8535163403 3.7068538666 3.9037754536 1141 1311867208.4907650948 0.0966397896 0.0827112362 0.1207897216 0.0059780100 0.9774320000 0.0536790000 0.0646030000 0.0309330000 0.4045460000 0.4209090000 139769563 0 402718720 3.8553719521 3.7055943012 3.9037990570 1142 1311867208.5257411003 0.0968473032 0.0827236146 0.1207897216 0.0059763232 0.5103950000 0.0667630000 0.0345190000 0.0000000000 0.4047290000 0.0015600000 139773347 0 402718720 3.8544216156 3.7042915821 3.9038543701 1143 1311867208.5583798885 0.0989021212 0.0827377690 0.1207897216 0.0059744574 0.5582700000 0.0536920000 0.0641840000 0.0309220000 0.4051230000 0.0015640000 139777019 0 402718720 3.8516504765 3.7030880451 3.9045450687 1144 1311867208.5904500484 0.0997681022 0.0827526557 0.1207897216 0.0059730590 0.5070690000 0.0648240000 0.0327450000 0.0000000000 0.4051160000 0.0015590000 139780747 0 402718720 3.8508994579 3.7028551102 3.9050817490 1145 1311867208.6259779930 0.0966201723 0.0827647670 0.1207897216 0.0059726919 0.9931390000 0.0643000000 0.0677770000 0.0313930000 0.4057380000 0.4211320000 139784419 0 402718720 3.8537793159 3.7012946606 3.9053540230 1146 1311867208.6582078934 0.0965163782 0.0827767667 0.1207897216 0.0059701108 0.5276720000 0.0540870000 0.0679020000 0.0000010000 0.4013130000 0.0015600000 139788147 0 402718720 3.8532145023 3.6996345520 3.9059772491 1147 1311867208.6910300255 0.0953484178 0.0827877271 0.1207897216 0.0059723659 0.5479140000 0.0539310000 0.0568690000 0.0314090000 0.4013580000 0.0015680000 139791819 0 402718720 3.8533494473 3.6991302967 3.9065897465 1148 1311867208.7262260914 0.0963937715 0.0827995791 0.1207897216 0.0059743477 0.5017140000 0.0541880000 0.0382430000 0.0000010000 0.4048920000 0.0015740000 139795603 0 402718720 3.8521881104 3.6979095936 3.9069473743 1149 1311867208.7591009140 0.0981013551 0.0828128966 0.1207897216 0.0059723129 0.9717180000 0.0713450000 0.0399520000 0.0314530000 0.4051350000 0.4210410000 139799275 0 402718720 3.8497748375 3.6980085373 3.9074120522 1150 1311867208.7909750938 0.0957870632 0.0828241785 0.1207897216 0.0059717848 0.4974640000 0.0542630000 0.0348270000 0.0000010000 0.4039650000 0.0015730000 139802891 0 402718720 3.8515698910 3.6962203979 3.9078614712 1151 1311867208.8259930611 0.0964197442 0.0828359904 0.1207897216 0.0059706759 0.5701640000 0.0657820000 0.0631580000 0.0307840000 0.4060770000 0.0015640000 139806675 0 402718720 3.8500669003 3.6935880184 3.9084041119 1152 1311867208.8588190079 0.0977409035 0.0828489287 0.1207897216 0.0059752073 0.5282090000 0.0535110000 0.0638380000 0.0000010000 0.4064870000 0.0015570000 139810403 0 402718720 3.8486783504 3.6940867901 3.9086747169 1153 1311867208.8916258812 0.0970361903 0.0828612334 0.1207897216 0.0059865537 0.9999830000 0.0738410000 0.0674090000 0.0309250000 0.4027730000 0.4222480000 139814019 0 402718720 3.8478875160 3.6938509941 3.9091761112 1154 1311867208.9275119305 0.0978435576 0.0828742163 0.1207897216 0.0059888907 0.5362280000 0.0706650000 0.0542770000 0.0000000000 0.4069030000 0.0015670000 139817747 0 402718720 3.8466818333 3.6909158230 3.9094491005 1155 1311867208.9577760696 0.0980236307 0.0828873327 0.1207897216 0.0059867127 0.5623620000 0.0536850000 0.0680780000 0.0314370000 0.4047640000 0.0015730000 139821363 0 402718720 3.8457045555 3.6882171631 3.9094388485 1156 1311867208.9911639690 0.0962463096 0.0828988889 0.1207897216 0.0059841632 0.5102050000 0.0535190000 0.0429140000 0.0000010000 0.4094080000 0.0015600000 139825091 0 402718720 3.8481421471 3.6884858608 3.9090118408 1157 1311867209.0270779133 0.0960369036 0.0829102441 0.1207897216 0.0059833759 0.9889210000 0.0538740000 0.0641730000 0.0313830000 0.4101480000 0.4265150000 139828875 0 402718720 3.8479845524 3.6857421398 3.9091045856 1158 1311867209.0579569340 0.0978695527 0.0829231624 0.1207897216 0.0059813884 0.5118400000 0.0530790000 0.0426770000 0.0000010000 0.4116890000 0.0015520000 139832491 0 402718720 3.8455822468 3.6850416660 3.9082925320 1159 1311867209.0906980038 0.0985638872 0.0829366574 0.1207897216 0.0059797318 0.5809760000 0.0706900000 0.0661970000 0.0313460000 0.4083750000 0.0015530000 139836219 0 402718720 3.8448185921 3.6854817867 3.9078173637 1160 1311867209.1260778904 0.0981560946 0.0829497776 0.1207897216 0.0059775025 0.5227890000 0.0526810000 0.0448420000 0.0000010000 0.4201510000 0.0019860000 139839891 0 402718720 3.8448858261 3.6845316887 3.9071645737 1161 1311867209.1600620747 0.0991623178 0.0829637419 0.1207897216 0.0059758717 1.0318870000 0.0653080000 0.0749640000 0.0381780000 0.4191800000 0.4311700000 139843675 0 402718720 3.8432846069 3.6820459366 3.9069631100 1162 1311867209.1917839050 0.0998032466 0.0829782337 0.1207897216 0.0059741395 0.5681470000 0.0867590000 0.0660060000 0.0000000000 0.4109840000 0.0015520000 139847347 0 402718720 3.8429634571 3.6828169823 3.9064862728 1163 1311867209.2259531021 0.0996521488 0.0829925707 0.1207897216 0.0059716300 0.5700920000 0.0564950000 0.0417110000 0.0381480000 0.4286420000 0.0019780000 139851019 0 402718720 3.8425602913 3.6813130379 3.9059028625 1164 1311867209.2580060959 0.1002072394 0.0830073599 0.1207897216 0.0059694551 0.5300090000 0.0657730000 0.0419880000 0.0000010000 0.4178620000 0.0015510000 139854747 0 402718720 3.8415791988 3.6802558899 3.9056534767 1165 1311867209.2903130054 0.0996631905 0.0830216568 0.1207897216 0.0059671950 0.9698630000 0.0519600000 0.0390700000 0.0314210000 0.4123820000 0.4319220000 139858419 0 402718720 3.8420453072 3.6806521416 3.9047696590 1166 1311867209.3274219036 0.0992820486 0.0830356022 0.1207897216 0.0059671168 0.5436580000 0.0656320000 0.0419150000 0.0000000000 0.4310090000 0.0019740000 139862203 0 402718720 3.8412282467 3.6774425507 3.9043061733 1167 1311867209.3581039906 0.0998478457 0.0830500086 0.1207897216 0.0059645943 0.6101670000 0.0647420000 0.0806110000 0.0389280000 0.4214930000 0.0015550000 139865819 0 402718720 3.8398280144 3.6756186485 3.9036962986 1168 1311867209.3937969208 0.0992211774 0.0830638538 0.1207897216 0.0059631684 0.5124410000 0.0520250000 0.0367150000 0.0000010000 0.4192620000 0.0015580000 139869603 0 402718720 3.8404138088 3.6756482124 3.9034152031 1169 1311867209.4258151054 0.0988068283 0.0830773208 0.1207897216 0.0059614483 1.0321530000 0.0719690000 0.0473570000 0.0378970000 0.4314790000 0.4406040000 139873331 0 402718720 3.8399188519 3.6738042831 3.9028449059 1170 1311867209.4581329823 0.0980354622 0.0830901056 0.1207897216 0.0059596931 0.5173340000 0.0507880000 0.0412500000 0.0000010000 0.4209100000 0.0015470000 139876947 0 402718720 3.8402028084 3.6720514297 3.9027664661 1171 1311867209.4940650463 0.0987674370 0.0831034935 0.1207897216 0.0059593180 0.5866340000 0.0691010000 0.0644560000 0.0314170000 0.4172580000 0.0015390000 139880787 0 402718720 3.8394370079 3.6731579304 3.9024384022 1172 1311867209.5258729458 0.0996949226 0.0831176501 0.1207897216 0.0059568985 0.5388090000 0.0503370000 0.0610830000 0.0000000000 0.4230020000 0.0015390000 139884403 0 402718720 3.8370766640 3.6714727879 3.9020471573 1173 1311867209.5580699444 0.0990901291 0.0831312668 0.1207897216 0.0059559451 0.9948380000 0.0627360000 0.0365550000 0.0313840000 0.4215040000 0.4398360000 139888075 0 402718720 3.8362634182 3.6686737537 3.9019494057 1174 1311867209.5939540863 0.1009387374 0.0831464350 0.1207897216 0.0059545140 0.5263390000 0.0627040000 0.0392020000 0.0000010000 0.4193090000 0.0019660000 139891859 0 402718720 3.8330948353 3.6674377918 3.9017648697 1175 1311867209.6262791157 0.1003957465 0.0831611153 0.1207897216 0.0059521089 0.5591580000 0.0634290000 0.0343830000 0.0335390000 0.4234340000 0.0015330000 139895475 0 402718720 3.8326900005 3.6658084393 3.9014911652 1176 1311867209.6582019329 0.0989416316 0.0831745341 0.1207897216 0.0059515750 0.5388450000 0.0496840000 0.0603990000 0.0000010000 0.4243690000 0.0015130000 139899091 0 402718720 3.8335564137 3.6637101173 3.9012849331 1177 1311867209.6967020035 0.0979803801 0.0831871134 0.1207897216 0.0059559882 0.9943100000 0.0505380000 0.0408570000 0.0313800000 0.4248780000 0.4438040000 139902875 0 402718720 3.8339486122 3.6612994671 3.9013426304 1178 1311867209.7262639999 0.0986230373 0.0832002169 0.1207897216 0.0059642857 0.5547690000 0.0639240000 0.0605460000 0.0000010000 0.4258920000 0.0015450000 139906491 0 402718720 3.8329317570 3.6608476639 3.9007160664 1179 1311867209.7583460808 0.1004917920 0.0832148832 0.1207897216 0.0059642595 0.5799810000 0.0781760000 0.0427550000 0.0313760000 0.4232650000 0.0015270000 139910219 0 402718720 3.8300166130 3.6590247154 3.9002561569 1180 1311867209.7959320545 0.1003461331 0.0832294012 0.1207897216 0.0059618480 0.5126590000 0.0494090000 0.0307800000 0.0000010000 0.4280590000 0.0015260000 139914059 0 402718720 3.8297109604 3.6570599079 3.8996484280 1181 1311867209.8262419701 0.0996219143 0.0832432814 0.1207897216 0.0059605028 1.0199720000 0.0490600000 0.0595250000 0.0308650000 0.4289050000 0.4487340000 139917675 0 402718720 3.8302478790 3.6559293270 3.8990361691 1182 1311867209.8588960171 0.1009254456 0.0832582410 0.1207897216 0.0059593639 0.5431270000 0.0496650000 0.0638870000 0.0000000000 0.4251500000 0.0015290000 139921347 0 402718720 3.8291890621 3.6576347351 3.8982825279 1183 1311867209.8946969509 0.0997729003 0.0832722009 0.1207897216 0.0059582057 0.5744630000 0.0491790000 0.0595910000 0.0313370000 0.4299460000 0.0015330000 139925131 0 402718720 3.8302683830 3.6555318832 3.8980336189 1184 1311867209.9268450737 0.1010324433 0.0832872011 0.1207897216 0.0059564356 0.5305130000 0.0495270000 0.0458460000 0.0000010000 0.4306920000 0.0015250000 139928747 0 402718720 3.8289289474 3.6552684307 3.8978388309 1185 1311867209.9588210583 0.1027174294 0.0833035980 0.1207897216 0.0059541606 1.0231110000 0.0489560000 0.0578990000 0.0309060000 0.4310230000 0.4514310000 139932475 0 402718720 3.8270390034 3.6555716991 3.8973910809 1186 1311867209.9942541122 0.1010172069 0.0833185336 0.1207897216 0.0059549888 0.5590120000 0.0633740000 0.0596770000 0.0000010000 0.4315280000 0.0015270000 139936259 0 402718720 3.8287677765 3.6534926891 3.8969595432 1187 1311867210.0261061192 0.1014646813 0.0833338210 0.1207897216 0.0059535591 0.5748860000 0.0484250000 0.0589590000 0.0308180000 0.4322600000 0.0015170000 139939875 0 402718720 3.8280408382 3.6522383690 3.8968145847 1188 1311867210.0603590012 0.1008300930 0.0833485485 0.1207897216 0.0059545326 0.5254560000 0.0612600000 0.0319820000 0.0000000000 0.4275410000 0.0016220000 139943715 0 402718720 3.8294463158 3.6531450748 3.8963119984 1189 1311867210.0942480564 0.1007907689 0.0833632181 0.1207897216 0.0059554512 1.0361470000 0.0493040000 0.0626790000 0.0310100000 0.4285670000 0.4617170000 139947387 0 402718720 3.8293654919 3.6513557434 3.8962633610 1190 1311867210.1280341148 0.0993850529 0.0833766818 0.1207897216 0.0059546705 0.5474140000 0.0488900000 0.0612060000 0.0000010000 0.4329220000 0.0015200000 139951115 0 402718720 3.8310530186 3.6488304138 3.8967278004 1191 1311867210.1578240395 0.0996059701 0.0833903084 0.1207897216 0.0059536269 0.5428210000 0.0490450000 0.0257410000 0.0313590000 0.4322690000 0.0015220000 139954731 0 402718720 3.8315725327 3.6501181126 3.8966736794 1192 1311867210.1943209171 0.1018855870 0.0834058246 0.1207897216 0.0059541368 0.5302260000 0.0485830000 0.0473160000 0.0000010000 0.4298860000 0.0015230000 139958571 0 402718720 3.8286819458 3.6490886211 3.8965561390 1193 1311867210.2258129120 0.1014411375 0.0834209422 0.1207897216 0.0059523901 1.0160780000 0.0499400000 0.0399980000 0.0377190000 0.4325840000 0.4529710000 139962187 0 402718720 3.8285570145 3.6472363472 3.8957121372 1194 1311867210.2579770088 0.1008774564 0.0834355624 0.1207897216 0.0059502839 0.5398800000 0.0640050000 0.0424880000 0.0000000000 0.4287480000 0.0016240000 139965859 0 402718720 3.8295872211 3.6480858326 3.8950340748 1195 1311867210.2953989506 0.1005697325 0.0834499006 0.1207897216 0.0059479156 0.5481950000 0.0487720000 0.0304330000 0.0313910000 0.4331540000 0.0015200000 139969699 0 402718720 3.8298473358 3.6479790211 3.8943977356 1196 1311867210.3271369934 0.1009092852 0.0834644988 0.1207897216 0.0059498609 0.5580610000 0.0620580000 0.0579910000 0.0000010000 0.4335980000 0.0015220000 139973315 0 402718720 3.8293690681 3.6478908062 3.8942844868 1197 1311867210.3582420349 0.1002573669 0.0834785279 0.1207897216 0.0059527417 1.0304570000 0.0762440000 0.0319000000 0.0313120000 0.4340320000 0.4540600000 139976987 0 402718720 3.8301150799 3.6475021839 3.8939042091 1198 1311867210.3937919140 0.1018544734 0.0834938668 0.1207897216 0.0059504892 0.5461810000 0.0489970000 0.0594570000 0.0000000000 0.4332590000 0.0015260000 139980771 0 402718720 3.8279831409 3.6466875076 3.8938527107 1199 1311867210.4260039330 0.1016213596 0.0835089856 0.1207897216 0.0059518634 0.5775670000 0.0492110000 0.0629370000 0.0314600000 0.4295210000 0.0015290000 139984387 0 402718720 3.8275098801 3.6459991932 3.8932623863 1200 1311867210.4581708908 0.1005357206 0.0835231746 0.1207897216 0.0059500542 0.5473530000 0.0492480000 0.0592400000 0.0000010000 0.4343890000 0.0015320000 139988115 0 402718720 3.8291468620 3.6465640068 3.8931319714 1201 1311867210.4943509102 0.1012670696 0.0835379488 0.1207897216 0.0059651982 1.0296060000 0.0493090000 0.0632850000 0.0314870000 0.4289470000 0.4536730000 139991843 0 402718720 3.8285441399 3.6483025551 3.8925123215 1202 1311867210.5261299610 0.1002475545 0.0835518503 0.1207897216 0.0059654984 0.5459100000 0.0494550000 0.0594850000 0.0000010000 0.4325150000 0.0015250000 139995515 0 402718720 3.8287615776 3.6464915276 3.8919887543 1203 1311867210.5634729862 0.1020912379 0.0835672613 0.1207897216 0.0059651644 0.5485280000 0.0494180000 0.0306720000 0.0313500000 0.4326590000 0.0015270000 139999355 0 402718720 3.8263630867 3.6469550133 3.8915860653 1204 1311867210.5943870544 0.1008915752 0.0835816503 0.1207897216 0.0059633007 0.5470220000 0.0605960000 0.0532490000 0.0000010000 0.4287490000 0.0015230000 140003027 0 402718720 3.8279962540 3.6489017010 3.8905880451 1205 1311867210.6260209084 0.0991890430 0.0835946025 0.1207897216 0.0059717572 1.0109530000 0.0498420000 0.0454750000 0.0314780000 0.4306010000 0.4506210000 140006587 0 402718720 3.8284680843 3.6447563171 3.8900363445 1206 1311867210.6675710678 0.0984595120 0.0836069283 0.1207897216 0.0059751562 0.5407330000 0.0686410000 0.0357100000 0.0000000000 0.4319160000 0.0015190000 140010595 0 402718720 3.8293950558 3.6436390877 3.8897867203 1207 1311867210.6952280998 0.0999662578 0.0836204820 0.1207897216 0.0059788536 0.5563070000 0.0488700000 0.0303940000 0.0312640000 0.4406350000 0.0019250000 140014211 0 402718720 3.8286972046 3.6460604668 3.8890919685 1208 1311867210.7260899544 0.0994210467 0.0836335619 0.1207897216 0.0059777823 0.5717530000 0.0620340000 0.0587280000 0.0000010000 0.4458350000 0.0019170000 140017715 0 402718720 3.8287069798 3.6447331905 3.8885331154 1209 1311867210.7620921135 0.1000674441 0.0836471549 0.1207897216 0.0059758399 1.0300320000 0.0616540000 0.0398320000 0.0389470000 0.4331220000 0.4535500000 140021555 0 402718720 3.8277816772 3.6437816620 3.8884913921 1210 1311867210.7943489552 0.1012238339 0.0836616810 0.1207897216 0.0059812600 0.5478990000 0.0489970000 0.0619650000 0.0000010000 0.4324390000 0.0015280000 140025003 0 402718720 3.8274698257 3.6474165916 3.8879387379 1211 1311867210.8263258934 0.1010172218 0.0836760126 0.1207897216 0.0059808569 0.5761650000 0.0496940000 0.0634220000 0.0314610000 0.4269010000 0.0016240000 140028675 0 402718720 3.8270072937 3.6457407475 3.8878705502 1212 1311867210.8623979092 0.1013124138 0.0836905641 0.1207897216 0.0059787818 0.5089980000 0.0490020000 0.0270550000 0.0000010000 0.4284670000 0.0015240000 140032459 0 402718720 3.8269155025 3.6463205814 3.8879792690 1213 1311867210.8942279816 0.0994414315 0.0837035492 0.1207897216 0.0059768666 1.0012520000 0.0496760000 0.0355520000 0.0314410000 0.4307440000 0.4509040000 140036187 0 402718720 3.8294267654 3.6467618942 3.8877322674 1214 1311867210.9288311005 0.0994176343 0.0837164932 0.1207897216 0.0059744662 0.5216050000 0.0581580000 0.0324820000 0.0000010000 0.4264790000 0.0015240000 140039915 0 402718720 3.8295531273 3.6463921070 3.8882606030 1215 1311867210.9653480053 0.0985668525 0.0837287157 0.1207897216 0.0059829119 0.5948080000 0.0770540000 0.0529890000 0.0314170000 0.4288330000 0.0015390000 140043699 0 402718720 3.8317954540 3.6505441666 3.8882241249 1216 1311867210.9945580959 0.0982801840 0.0837406824 0.1207897216 0.0059918413 0.5337460000 0.0506810000 0.0410720000 0.0000010000 0.4374980000 0.0015400000 140047315 0 402718720 3.8306436539 3.6473889351 3.8882138729 1217 1311867211.0263500214 0.0966983289 0.0837513296 0.1207897216 0.0059912589 1.0207540000 0.0507900000 0.0598560000 0.0314570000 0.4281290000 0.4475740000 140050987 0 402718720 3.8319838047 3.6460888386 3.8883516788 1218 1311867211.0651569366 0.0980128050 0.0837630385 0.1207897216 0.0060001371 0.5554400000 0.0631400000 0.0605710000 0.0000010000 0.4272590000 0.0015370000 140054827 0 402718720 3.8319795132 3.6510071754 3.8880167007 1219 1311867211.0940821171 0.0994263142 0.0837758878 0.1207897216 0.0060016414 0.5785340000 0.0615200000 0.0437450000 0.0314310000 0.4371770000 0.0016750000 140058387 0 402718720 3.8290824890 3.6483268738 3.8878870010 1220 1311867211.1266880035 0.0971817151 0.0837868762 0.1207897216 0.0060027883 0.5316340000 0.0634540000 0.0362720000 0.0000010000 0.4274260000 0.0015340000 140062059 0 402718720 3.8306837082 3.6454355717 3.8877460957 1221 1311867211.1646990776 0.0981826112 0.0837986663 0.1207897216 0.0060019606 1.0215730000 0.0502620000 0.0605230000 0.0313800000 0.4281800000 0.4482700000 140065955 0 402718720 3.8304936886 3.6485469341 3.8872406483 1222 1311867211.1946630478 0.0981594399 0.0838104182 0.1207897216 0.0059995858 0.5551680000 0.0620890000 0.0609620000 0.0000010000 0.4276000000 0.0015310000 140069571 0 402718720 3.8306622505 3.6488623619 3.8870358467 1223 1311867211.2270209789 0.0978420898 0.0838218913 0.1207897216 0.0060056483 0.5576060000 0.0619880000 0.0316090000 0.0314440000 0.4280740000 0.0015390000 140073243 0 402718720 3.8300142288 3.6465804577 3.8871848583 1224 1311867211.2645599842 0.0963667929 0.0838321404 0.1207897216 0.0060038859 0.5412770000 0.0685050000 0.0431080000 0.0000010000 0.4251470000 0.0015300000 140077083 0 402718720 3.8318629265 3.6478536129 3.8866806030 1225 1311867211.2953100204 0.0965181291 0.0838424963 0.1207897216 0.0060016313 1.0219270000 0.0505830000 0.0606980000 0.0309770000 0.4283900000 0.4483570000 140080755 0 402718720 3.8325345516 3.6499195099 3.8866789341 1226 1311867211.3262948990 0.0989264026 0.0838547997 0.1207897216 0.0059998563 0.5414050000 0.0498970000 0.0626900000 0.0000000000 0.4243190000 0.0015300000 140084371 0 402718720 3.8291764259 3.6489989758 3.8866779804 1227 1311867211.3653290272 0.0983814374 0.0838666388 0.1207897216 0.0059975356 0.5453790000 0.0494530000 0.0307920000 0.0312500000 0.4293640000 0.0015420000 140088267 0 402718720 3.8297498226 3.6490411758 3.8868627548 1228 1311867211.3949019909 0.0982805192 0.0838783765 0.1207897216 0.0059960063 0.5328840000 0.0636380000 0.0363170000 0.0000010000 0.4283940000 0.0015370000 140091883 0 402718720 3.8304603100 3.6514172554 3.8867306709 1229 1311867211.4295680523 0.0984059051 0.0838901971 0.1207897216 0.0060013914 1.0068720000 0.0620730000 0.0362640000 0.0309790000 0.4274840000 0.4471070000 140095555 0 402718720 3.8305394650 3.6526176929 3.8869543076 1230 1311867211.4645059109 0.0991072729 0.0839025687 0.1207897216 0.0060002156 0.5129310000 0.0494280000 0.0308740000 0.0000000000 0.4281000000 0.0015460000 140099283 0 402718720 3.8287899494 3.6511363983 3.8870494366 1231 1311867211.4942829609 0.0999470428 0.0839156024 0.1207897216 0.0059985025 0.5385060000 0.0506240000 0.0277670000 0.0310180000 0.4246200000 0.0015150000 140102899 0 402718720 3.8282823563 3.6528401375 3.8871164322 1232 1311867211.5279569626 0.0985288695 0.0839274639 0.1207897216 0.0059988915 0.5715610000 0.0774420000 0.0645930000 0.0000010000 0.4249840000 0.0015440000 140106571 0 402718720 3.8296906948 3.6537685394 3.8872747421 1233 1311867211.5646700859 0.0980570316 0.0839389234 0.1207897216 0.0059985170 1.0169780000 0.0503880000 0.0596200000 0.0314260000 0.4266120000 0.4459830000 140110411 0 402718720 3.8310999870 3.6534228325 3.8875114918 1234 1311867211.5967590809 0.0993393734 0.0839514035 0.1207897216 0.0059989103 0.5693620000 0.0795370000 0.0622520000 0.0000010000 0.4228040000 0.0016340000 140114083 0 402718720 3.8295404911 3.6536655426 3.8878946304 1235 1311867211.6269431114 0.0993941054 0.0839639077 0.1207897216 0.0060024596 0.5755100000 0.0502800000 0.0643330000 0.0310540000 0.4253050000 0.0015390000 140117699 0 402718720 3.8300757408 3.6548173428 3.8881766796 1236 1311867211.6620280743 0.0990897566 0.0839761454 0.1207897216 0.0060099540 0.5117210000 0.0515010000 0.0331850000 0.0000010000 0.4222650000 0.0016420000 140121483 0 402718720 3.8301167488 3.6559050083 3.8879821301 1237 1311867211.6944348812 0.0998506993 0.0839889785 0.1207897216 0.0060122615 1.0202010000 0.0502320000 0.0610510000 0.0314000000 0.4274970000 0.4470150000 140125155 0 402718720 3.8285119534 3.6536843777 3.8878536224 1238 1311867211.7267570496 0.1000534073 0.0840019546 0.1207897216 0.0060122700 0.5193260000 0.0504300000 0.0362440000 0.0000010000 0.4281130000 0.0015370000 140128771 0 402718720 3.8292112350 3.6568982601 3.8875327110 1239 1311867211.7642099857 0.0999887735 0.0840148576 0.1207897216 0.0060103526 0.5857540000 0.0604110000 0.0605250000 0.0313640000 0.4289260000 0.0015300000 140132667 0 402718720 3.8293139935 3.6557881832 3.8873126507 1240 1311867211.7948160172 0.1000133231 0.0840277596 0.1207897216 0.0060084223 0.5142400000 0.0493870000 0.0308010000 0.0000010000 0.4295350000 0.0015210000 140136171 0 402718720 3.8297321796 3.6568071842 3.8867545128 1241 1311867211.8337268829 0.0997575670 0.0840404347 0.1207897216 0.0060063919 1.0479430000 0.0733100000 0.0634700000 0.0314570000 0.4260110000 0.4506850000 140140011 0 402718720 3.8302044868 3.6564984322 3.8863768578 1242 1311867211.8630928993 0.1002746597 0.0840535058 0.1207897216 0.0060049288 0.5444230000 0.0495190000 0.0635110000 0.0000010000 0.4269020000 0.0015250000 140143627 0 402718720 3.8304376602 3.6584281921 3.8862891197 1243 1311867211.8967690468 0.0993978530 0.0840658504 0.1207897216 0.0060025281 0.5747240000 0.0487350000 0.0595820000 0.0313940000 0.4304570000 0.0015240000 140147299 0 402718720 3.8316032887 3.6599862576 3.8857247829 1244 1311867211.9324300289 0.1011433750 0.0840795783 0.1207897216 0.0060018841 0.5495290000 0.0651960000 0.0530100000 0.0000010000 0.4267710000 0.0015230000 140151083 0 402718720 3.8291678429 3.6594738960 3.8852500916 1245 1311867211.9653239250 0.0998433232 0.0840922399 0.1207897216 0.0060001995 0.9993540000 0.0496790000 0.0375950000 0.0314770000 0.4266790000 0.4509370000 140154811 0 402718720 3.8313043118 3.6604545116 3.8849735260 1246 1311867211.9972860813 0.1004918441 0.0841054017 0.1207897216 0.0059981086 0.5082960000 0.0494380000 0.0274230000 0.0000000000 0.4266340000 0.0016130000 140158427 0 402718720 3.8314363956 3.6631648540 3.8843929768 1247 1311867212.0317659378 0.0999026969 0.0841180700 0.1207897216 0.0059959089 0.5565150000 0.0495400000 0.0427590000 0.0315130000 0.4281710000 0.0015290000 140162211 0 402718720 3.8325822353 3.6643302441 3.8840222359 1248 1311867212.0621519089 0.1003159285 0.0841310490 0.1207897216 0.0059935369 0.5433000000 0.0491460000 0.0583560000 0.0000010000 0.4312610000 0.0015230000 140165827 0 402718720 3.8319561481 3.6643526554 3.8837518692 1249 1311867212.0954549313 0.1002871022 0.0841439842 0.1207897216 0.0059939953 1.0256070000 0.0624800000 0.0456240000 0.0314340000 0.4307570000 0.4523360000 140169499 0 402718720 3.8330795765 3.6676704884 3.8835544586 1250 1311867212.1331028938 0.1013388336 0.0841577401 0.1207897216 0.0059949460 0.5596490000 0.0699180000 0.0584080000 0.0000010000 0.4267750000 0.0015200000 140173339 0 402718720 3.8317077160 3.6686401367 3.8830673695 1251 1311867212.1668488979 0.1020064130 0.0841720076 0.1207897216 0.0059934471 0.5640170000 0.0496570000 0.0533280000 0.0314440000 0.4250560000 0.0015290000 140177011 0 402718720 3.8302016258 3.6673417091 3.8828094006 1252 1311867212.1945068836 0.1006441936 0.0841851643 0.1207897216 0.0059929351 0.5345130000 0.0493900000 0.0512100000 0.0000010000 0.4293480000 0.0015260000 140180571 0 402718720 3.8328084946 3.6694161892 3.8826038837 1253 1311867212.2301759720 0.1017352268 0.0841991708 0.1207897216 0.0059958557 1.0067460000 0.0499430000 0.0524420000 0.0310200000 0.4240660000 0.4462290000 140184299 0 402718720 3.8322484493 3.6718618870 3.8817110062 1254 1311867212.2647190094 0.1006675288 0.0842123034 0.1207897216 0.0059977333 0.5655410000 0.0699960000 0.0635670000 0.0000010000 0.4267310000 0.0019210000 140188083 0 402718720 3.8332638741 3.6706228256 3.8810753822 1255 1311867212.2944819927 0.1024428308 0.0842268297 0.1207897216 0.0059956416 0.5761370000 0.0615570000 0.0464370000 0.0340540000 0.4295260000 0.0015200000 140191699 0 402718720 3.8317477703 3.6727018356 3.8801319599 1256 1311867212.3326430321 0.1024475172 0.0842413367 0.1207897216 0.0059944884 0.5432570000 0.0489280000 0.0597970000 0.0000000000 0.4299920000 0.0015130000 140195539 0 402718720 3.8323771954 3.6750385761 3.8794221878 1257 1311867212.3653640747 0.1013396308 0.0842549391 0.1207897216 0.0059925423 1.0002810000 0.0494310000 0.0357300000 0.0309680000 0.4294640000 0.4516540000 140199211 0 402718720 3.8344900608 3.6784298420 3.8782804012 1258 1311867212.3955509663 0.1028633043 0.0842697311 0.1207897216 0.0060049374 0.5258150000 0.0610980000 0.0307780000 0.0000000000 0.4294000000 0.0015170000 140202827 0 402718720 3.8328433037 3.6783103943 3.8778386116 1259 1311867212.4329519272 0.1015776768 0.0842834785 0.1207897216 0.0060221565 0.6055880000 0.0816950000 0.0630710000 0.0314730000 0.4245430000 0.0016130000 140206667 0 402718720 3.8345921040 3.6801455021 3.8773975372 1260 1311867212.4622640610 0.1031609774 0.0842984607 0.1207897216 0.0060310769 0.5224800000 0.0486270000 0.0403680000 0.0000010000 0.4289050000 0.0015150000 140210283 0 402718720 3.8336544037 3.6827068329 3.8770356178 1261 1311867212.4944300652 0.1032260582 0.0843134706 0.1207897216 0.0060344602 1.0043340000 0.0500300000 0.0407220000 0.0314860000 0.4284740000 0.4505690000 140213955 0 402718720 3.8338146210 3.6829936504 3.8765108585 1262 1311867212.5300269127 0.1028086320 0.0843281261 0.1207897216 0.0060330911 0.5446660000 0.0493800000 0.0617580000 0.0000010000 0.4289510000 0.0015220000 140217739 0 402718720 3.8345925808 3.6830286980 3.8757920265 1263 1311867212.5625970364 0.1024160162 0.0843424474 0.1207897216 0.0060404318 0.5529750000 0.0486790000 0.0374870000 0.0314910000 0.4300600000 0.0019110000 140221411 0 402718720 3.8363642693 3.6847908497 3.8749527931 1264 1311867212.5948359966 0.1021558419 0.0843565403 0.1207897216 0.0060391865 0.5765960000 0.0603970000 0.0768700000 0.0000010000 0.4347400000 0.0015160000 140225083 0 402718720 3.8371434212 3.6852998734 3.8738749027 1265 1311867212.6323919296 0.1004949212 0.0843692979 0.1207897216 0.0060384051 1.0037540000 0.0489740000 0.0356380000 0.0309370000 0.4309160000 0.4542300000 140228811 0 402718720 3.8398134708 3.6852750778 3.8730862141 1266 1311867212.6629829407 0.1010190398 0.0843824494 0.1207897216 0.0060416454 0.5286050000 0.0478290000 0.0443740000 0.0000010000 0.4318160000 0.0015130000 140232427 0 402718720 3.8401820660 3.6874632835 3.8721992970 1267 1311867212.6944150925 0.1003186256 0.0843950273 0.1207897216 0.0060395244 0.5458480000 0.0473620000 0.0300560000 0.0313040000 0.4325720000 0.0015070000 140236155 0 402718720 3.8420603275 3.6890041828 3.8714141846 1268 1311867212.7323219776 0.1016698331 0.0844086509 0.1207897216 0.0060387137 0.5571460000 0.0672320000 0.0574660000 0.0000000000 0.4278630000 0.0015150000 140239939 0 402718720 3.8410253525 3.6897587776 3.8706340790 1269 1311867212.7618949413 0.1017973572 0.0844223536 0.1207897216 0.0060377627 0.9943440000 0.0484430000 0.0267770000 0.0314580000 0.4279360000 0.4566550000 140243499 0 402718720 3.8408074379 3.6900441647 3.8698463440 1270 1311867212.7951610088 0.1023107544 0.0844364390 0.1207897216 0.0060361165 0.5124280000 0.0481580000 0.0320130000 0.0000000000 0.4277020000 0.0015070000 140247227 0 402718720 3.8413639069 3.6937067509 3.8690378666 1271 1311867212.8303771019 0.1017873585 0.0844500904 0.1207897216 0.0060339755 0.5742490000 0.0477690000 0.0586000000 0.0313640000 0.4319540000 0.0015050000 140251067 0 402718720 3.8421170712 3.6932775974 3.8684489727 1272 1311867212.8625240326 0.1028644964 0.0844645671 0.1207897216 0.0060340505 0.5441490000 0.0480040000 0.0588600000 0.0000010000 0.4327070000 0.0014990000 140254683 0 402718720 3.8407459259 3.6926507950 3.8674738407 1273 1311867212.8941800594 0.1032528132 0.0844793261 0.1207897216 0.0060416661 1.0327800000 0.0477170000 0.0584250000 0.0313570000 0.4335030000 0.4587260000 140258355 0 402718720 3.8411366940 3.6954324245 3.8665533066 1274 1311867212.9306590557 0.1010426208 0.0844923272 0.1207897216 0.0060505197 0.5322670000 0.0592230000 0.0347020000 0.0000010000 0.4337560000 0.0015010000 140262139 0 402718720 3.8441071510 3.6980543137 3.8657190800 1275 1311867212.9621579647 0.1021896228 0.0845062074 0.1207897216 0.0060660898 0.5481050000 0.0478260000 0.0300390000 0.0314500000 0.4342340000 0.0014780000 140265811 0 402718720 3.8433640003 3.6983509064 3.8648381233 1276 1311867212.9971981049 0.1020222306 0.0845199347 0.1207897216 0.0060682649 0.5443070000 0.0474810000 0.0582590000 0.0000010000 0.4339960000 0.0015040000 140269539 0 402718720 3.8453941345 3.7018854618 3.8640255928 1277 1311867213.0305559635 0.1022962630 0.0845338551 0.1207897216 0.0060701884 1.0271340000 0.0629680000 0.0365620000 0.0315550000 0.4332710000 0.4596850000 140273323 0 402718720 3.8448536396 3.7014503479 3.8637261391 1278 1311867213.0622329712 0.1022443250 0.0845477130 0.1207897216 0.0060691047 0.5536830000 0.0472990000 0.0582420000 0.0000010000 0.4428680000 0.0018900000 140276939 0 402718720 3.8453783989 3.7017965317 3.8634023666 1279 1311867213.0985310078 0.1015260890 0.0845609877 0.1207897216 0.0060671501 0.5610170000 0.0505170000 0.0394100000 0.0309930000 0.4355430000 0.0014990000 140280723 0 402718720 3.8470106125 3.7039086819 3.8624823093 1280 1311867213.1321671009 0.1009770781 0.0845738128 0.1207897216 0.0060648010 0.5115400000 0.0472650000 0.0250860000 0.0000000000 0.4346050000 0.0015000000 140284451 0 402718720 3.8487854004 3.7051165104 3.8619015217 1281 1311867213.1642329693 0.1020599902 0.0845874632 0.1207897216 0.0060629635 1.0294170000 0.0467640000 0.0564570000 0.0314690000 0.4299870000 0.4616780000 140288123 0 402718720 3.8484263420 3.7062289715 3.8613977432 1282 1311867213.1981649399 0.1011570096 0.0846003880 0.1207897216 0.0060645688 0.5140680000 0.0474990000 0.0315310000 0.0000010000 0.4302100000 0.0015940000 140291851 0 402718720 3.8497364521 3.7063941956 3.8603684902 1283 1311867213.2303979397 0.1032960042 0.0846149598 0.1207897216 0.0060632997 0.5796640000 0.0471750000 0.0600400000 0.0315370000 0.4363130000 0.0014960000 140295523 0 402718720 3.8484091759 3.7078294754 3.8601243496 1284 1311867213.2621340752 0.1037536412 0.0846298653 0.1207897216 0.0060613198 0.5442740000 0.0466540000 0.0609580000 0.0000000000 0.4320680000 0.0014940000 140299195 0 402718720 3.8489763737 3.7103462219 3.8588850498 1285 1311867213.2983639240 0.1025499776 0.0846438109 0.1207897216 0.0060609037 1.0411890000 0.0465190000 0.0573710000 0.0313160000 0.4376500000 0.4652290000 140302979 0 402718720 3.8504726887 3.7093772888 3.8582890034 1286 1311867213.3312969208 0.1043254212 0.0846591154 0.1207897216 0.0060632198 0.5494040000 0.0623380000 0.0509270000 0.0000000000 0.4313300000 0.0015750000 140306707 0 402718720 3.8498618603 3.7138421535 3.8578433990 1287 1311867213.3622069359 0.1040153503 0.0846741552 0.1207897216 0.0060615441 0.5493240000 0.0472410000 0.0296660000 0.0314640000 0.4363780000 0.0014940000 140310323 0 402718720 3.8503060341 3.7150979042 3.8569159508 1288 1311867213.3980619907 0.1051217243 0.0846900307 0.1207897216 0.0060595190 0.5179360000 0.0471630000 0.0296210000 0.0000010000 0.4365800000 0.0014900000 140314107 0 402718720 3.8499572277 3.7166988850 3.8568727970 1289 1311867213.4303960800 0.1046117842 0.0847054859 0.1207897216 0.0060579154 1.0588680000 0.0672850000 0.0608970000 0.0315320000 0.4313590000 0.4647210000 140317835 0 402718720 3.8514938354 3.7185735703 3.8566079140 1290 1311867213.4620630741 0.1053755358 0.0847215092 0.1207897216 0.0060561571 0.5143730000 0.0467480000 0.0312930000 0.0000010000 0.4317290000 0.0014860000 140321451 0 402718720 3.8514492512 3.7210552692 3.8562407494 1291 1311867213.4981389046 0.1046581194 0.0847369519 0.1207897216 0.0060587035 0.5749400000 0.0455830000 0.0568840000 0.0312230000 0.4366710000 0.0014660000 140325235 0 402718720 3.8524444103 3.7227022648 3.8558664322 1292 1311867213.5318338871 0.1041913852 0.0847520096 0.1207897216 0.0060580845 0.5546770000 0.0576960000 0.0576650000 0.0000010000 0.4346950000 0.0014800000 140328963 0 402718720 3.8533654213 3.7253036499 3.8555228710 1293 1311867213.5621318817 0.1025281996 0.0847657576 0.1207897216 0.0060560886 1.0257080000 0.0469460000 0.0485100000 0.0314410000 0.4337690000 0.4619370000 140332579 0 402718720 3.8560483456 3.7275433540 3.8555400372 1294 1311867213.5989580154 0.1018272862 0.0847789427 0.1207897216 0.0060573987 0.5567570000 0.0612490000 0.0580590000 0.0000000000 0.4328510000 0.0014910000 140336419 0 402718720 3.8568081856 3.7283115387 3.8554921150 1295 1311867213.6327760220 0.1014617160 0.0847918251 0.1207897216 0.0060556344 0.5772610000 0.0670310000 0.0422070000 0.0314900000 0.4319180000 0.0015000000 140340091 0 402718720 3.8577136993 3.7300014496 3.8554959297 1296 1311867213.6623249054 0.1032088399 0.0848060358 0.1207897216 0.0060564639 0.5140330000 0.0480970000 0.0302840000 0.0000010000 0.4310340000 0.0014920000 140343707 0 402718720 3.8569252491 3.7331800461 3.8555626869 1297 1311867213.6987268925 0.1022176594 0.0848194603 0.1207897216 0.0060545799 1.0274080000 0.0476780000 0.0592170000 0.0313480000 0.4295250000 0.4565300000 140347491 0 402718720 3.8593916893 3.7356636524 3.8558137417 1298 1311867213.7312800884 0.1025516838 0.0848331215 0.1207897216 0.0060591635 0.5404660000 0.0483410000 0.0592750000 0.0000010000 0.4282160000 0.0015020000 140351219 0 402718720 3.8599743843 3.7371878624 3.8561980724 1299 1311867213.7623159885 0.1016691476 0.0848460823 0.1207897216 0.0060682559 0.5539890000 0.0617190000 0.0323090000 0.0314090000 0.4239340000 0.0015040000 140354835 0 402718720 3.8613467216 3.7384088039 3.8564417362 1300 1311867213.7984969616 0.1023641974 0.0848595577 0.1207897216 0.0060665352 0.5411650000 0.0489630000 0.0621560000 0.0000010000 0.4253930000 0.0015060000 140358507 0 402718720 3.8615844250 3.7406923771 3.8568437099 1301 1311867213.8303530216 0.1017038971 0.0848725050 0.1207897216 0.0060644128 1.0151470000 0.0491290000 0.0638950000 0.0314410000 0.4186400000 0.4489120000 140362179 0 402718720 3.8633890152 3.7419230938 3.8575544357 1302 1311867213.8669381142 0.1012411937 0.0848850769 0.1207897216 0.0060671222 0.5481040000 0.0488020000 0.0604490000 0.0000000000 0.4342280000 0.0014970000 140365963 0 402718720 3.8639051914 3.7408058643 3.8578112125 1303 1311867213.8988749981 0.1029925942 0.0848989737 0.1207897216 0.0060650318 0.5672070000 0.0486190000 0.0601100000 0.0307110000 0.4231410000 0.0015080000 140369635 0 402718720 3.8629889488 3.7430229187 3.8579318523 1304 1311867213.9324591160 0.1035461798 0.0849132737 0.1207897216 0.0060648279 0.5391820000 0.0843120000 0.0327680000 0.0000000000 0.4172190000 0.0016020000 140373307 0 402718720 3.8638675213 3.7472033501 3.8578894138 1305 1311867213.9625511169 0.1041955724 0.0849280494 0.1207897216 0.0060634509 0.9931100000 0.0494220000 0.0408320000 0.0309240000 0.4219330000 0.4468840000 140376923 0 402718720 3.8628973961 3.7463629246 3.8575603962 1306 1311867214.0014989376 0.1038960814 0.0849425732 0.1207897216 0.0060618736 0.5170130000 0.0491500000 0.0406800000 0.0000010000 0.4225440000 0.0015030000 140380875 0 402718720 3.8641536236 3.7478885651 3.8569815159 1307 1311867214.0316550732 0.1036441401 0.0849568820 0.1207897216 0.0060623378 0.5602310000 0.0487890000 0.0583480000 0.0309260000 0.4175590000 0.0015060000 140384435 0 402718720 3.8649427891 3.7504723072 3.8564591408 1308 1311867214.0640029907 0.1030541882 0.0849707178 0.1207897216 0.0060609251 0.5349420000 0.0629890000 0.0363400000 0.0000010000 0.4301990000 0.0019250000 140388163 0 402718720 3.8666875362 3.7521364689 3.8564596176 1309 1311867214.0984749794 0.1045390964 0.0849856669 0.1207897216 0.0060587614 1.0565290000 0.0629010000 0.0792720000 0.0390010000 0.4256340000 0.4465880000 140391891 0 402718720 3.8659083843 3.7545204163 3.8560979366 1310 1311867214.1326990128 0.1050148010 0.0850009563 0.1207897216 0.0060579047 0.5367400000 0.0503750000 0.0647120000 0.0000000000 0.4169760000 0.0015150000 140395563 0 402718720 3.8660724163 3.7561948299 3.8560256958 1311 1311867214.1643800735 0.1053205505 0.0850164557 0.1207897216 0.0060576807 0.5456360000 0.0500280000 0.0263030000 0.0308970000 0.4330330000 0.0019210000 140399291 0 402718720 3.8662717342 3.7578775883 3.8560678959 1312 1311867214.2013020515 0.1052774340 0.0850318985 0.1207897216 0.0060558968 0.5296570000 0.0631650000 0.0344440000 0.0000010000 0.4273840000 0.0015180000 140403019 0 402718720 3.8664088249 3.7581348419 3.8561050892 1313 1311867214.2338430882 0.1057610735 0.0850476861 0.1207897216 0.0060537376 1.0094500000 0.0507450000 0.0614240000 0.0313850000 0.4188470000 0.4439200000 140406747 0 402718720 3.8661403656 3.7595033646 3.8559870720 1314 1311867214.2674899101 0.1050810218 0.0850629322 0.1207897216 0.0060518362 0.5615460000 0.0496020000 0.0741330000 0.0000010000 0.4324160000 0.0019160000 140410475 0 402718720 3.8674616814 3.7613306046 3.8558676243 1315 1311867214.3004720211 0.1057592407 0.0850786708 0.1207897216 0.0060498000 0.5891270000 0.0634400000 0.0605380000 0.0389900000 0.4214720000 0.0015160000 140414147 0 402718720 3.8669960499 3.7635495663 3.8558058739 1316 1311867214.3310549259 0.1044714078 0.0850934069 0.1207897216 0.0060479788 0.5281930000 0.0492270000 0.0554650000 0.0000010000 0.4188240000 0.0014920000 140417763 0 402718720 3.8683929443 3.7642054558 3.8553614616 1317 1311867214.3663671017 0.1048857272 0.0851084353 0.1207897216 0.0060473469 1.0050220000 0.0502540000 0.0362950000 0.0313540000 0.4267650000 0.4568660000 140421547 0 402718720 3.8687398434 3.7662379742 3.8553123474 1318 1311867214.3980031013 0.1045005992 0.0851231486 0.1207897216 0.0060453813 0.5669500000 0.0627350000 0.0793830000 0.0000010000 0.4201660000 0.0015120000 140425219 0 402718720 3.8692111969 3.7659773827 3.8548471928 1319 1311867214.4332211018 0.1044747680 0.0851378200 0.1207897216 0.0060441347 0.5726880000 0.0616540000 0.0619600000 0.0314440000 0.4129370000 0.0015240000 140428947 0 402718720 3.8694403172 3.7668266296 3.8542199135 1320 1311867214.4698181152 0.1050956026 0.0851529396 0.1207897216 0.0060463008 0.5146970000 0.0503170000 0.0413060000 0.0000010000 0.4183800000 0.0015120000 140432899 0 402718720 3.8689973354 3.7681436539 3.8534839153 1321 1311867214.5059390068 0.1057231128 0.0851685112 0.1207897216 0.0060474860 0.9830640000 0.0504680000 0.0437680000 0.0314610000 0.4129540000 0.4412390000 140436683 0 402718720 3.8695459366 3.7706849575 3.8532142639 1322 1311867214.5373690128 0.1053550765 0.0851837810 0.1207897216 0.0060466667 0.5315160000 0.0486530000 0.0601980000 0.0000010000 0.4179820000 0.0015040000 140440355 0 402718720 3.8708932400 3.7725260258 3.8530333042 1323 1311867214.5691421032 0.1054272577 0.0851990822 0.1207897216 0.0060453574 0.5388160000 0.0502080000 0.0364160000 0.0309250000 0.4165920000 0.0015080000 140444027 0 402718720 3.8716225624 3.7752103806 3.8528294563 1324 1311867214.6048638821 0.1046819836 0.0852137973 0.1207897216 0.0060431698 0.5304990000 0.0503830000 0.0647200000 0.0000000000 0.4104840000 0.0015900000 140447811 0 402718720 3.8728559017 3.7762215137 3.8526024818 1325 1311867214.6369891167 0.1055778414 0.0852291664 0.1207897216 0.0060423043 1.0013520000 0.0503400000 0.0612260000 0.0313370000 0.4150770000 0.4401910000 140451427 0 402718720 3.8718667030 3.7763450146 3.8526124954 1326 1311867214.6691009998 0.1056079715 0.0852445351 0.1207897216 0.0060405372 0.5067500000 0.0507170000 0.0367600000 0.0000000000 0.4145900000 0.0015180000 140455155 0 402718720 3.8730113506 3.7791657448 3.8524136543 1327 1311867214.7048900127 0.1065948755 0.0852606242 0.1207897216 0.0060391849 0.5590930000 0.0507550000 0.0625180000 0.0315180000 0.4096080000 0.0015190000 140458883 0 402718720 3.8726925850 3.7789113522 3.8524711132 1328 1311867214.7369639874 0.1055385321 0.0852758937 0.1207897216 0.0060435548 0.5161640000 0.0506550000 0.0465100000 0.0000010000 0.4142940000 0.0015080000 140462555 0 402718720 3.8745346069 3.7810456753 3.8522200584 1329 1311867214.7695059776 0.1059779897 0.0852914709 0.1207897216 0.0060452370 0.9742100000 0.0504970000 0.0365370000 0.0314230000 0.4137040000 0.4388620000 140466283 0 402718720 3.8746917248 3.7830798626 3.8518626690 1330 1311867214.8049929142 0.1060475186 0.0853070770 0.1207897216 0.0060442337 0.5072870000 0.0502520000 0.0438730000 0.0000000000 0.4082220000 0.0016130000 140470067 0 402718720 3.8749418259 3.7839672565 3.8511857986 1331 1311867214.8369181156 0.1051588058 0.0853219919 0.1207897216 0.0060451997 0.5651860000 0.0502100000 0.0649320000 0.0314830000 0.4138820000 0.0015070000 140473683 0 402718720 3.8756670952 3.7837336063 3.8506641388 1332 1311867214.8699979782 0.1061684564 0.0853376424 0.1207897216 0.0060440695 0.5057960000 0.0505930000 0.0366080000 0.0000010000 0.4138890000 0.0015130000 140477411 0 402718720 3.8755550385 3.7865865231 3.8505492210 1333 1311867214.9049839973 0.1066313609 0.0853536167 0.1207897216 0.0060429329 0.9972770000 0.0500420000 0.0620480000 0.0309840000 0.4127380000 0.4382690000 140481195 0 402718720 3.8755068779 3.7890200615 3.8502316475 1334 1311867214.9372529984 0.1054117978 0.0853686528 0.1207897216 0.0060444919 0.5359210000 0.0617670000 0.0566950000 0.0000010000 0.4127420000 0.0015230000 140484867 0 402718720 3.8768813610 3.7886259556 3.8497681618 1335 1311867214.9693040848 0.1058404520 0.0853839875 0.1207897216 0.0060434844 0.5356030000 0.0505550000 0.0366830000 0.0309380000 0.4127210000 0.0015080000 140488539 0 402718720 3.8770689964 3.7914552689 3.8495752811 1336 1311867215.0050640106 0.1063636020 0.0853996908 0.1207897216 0.0060418401 0.5074460000 0.0496150000 0.0414360000 0.0000010000 0.4116490000 0.0015090000 140492379 0 402718720 3.8774726391 3.7955310345 3.8496024609 1337 1311867215.0371069908 0.1059202179 0.0854150390 0.1207897216 0.0060415715 0.9941590000 0.0511550000 0.0620890000 0.0314360000 0.4105290000 0.4357600000 140495939 0 402718720 3.8772435188 3.7950868607 3.8492169380 1338 1311867215.0692911148 0.1060041413 0.0854304269 0.1207897216 0.0060402433 0.5401180000 0.0511400000 0.0625830000 0.0000010000 0.4209420000 0.0019330000 140499667 0 402718720 3.8780369759 3.7984755039 3.8494944572 1339 1311867215.1050040722 0.1048440859 0.0854449256 0.1207897216 0.0060393567 0.5594220000 0.0649450000 0.0497900000 0.0313500000 0.4086200000 0.0015210000 140503451 0 402718720 3.8797926903 3.8011989594 3.8496236801 1340 1311867215.1369140148 0.1053446829 0.0854597761 0.1207897216 0.0060372960 0.5266780000 0.0521220000 0.0632860000 0.0000010000 0.4065180000 0.0015390000 140507067 0 402718720 3.8789699078 3.8014049530 3.8504517078 1341 1311867215.1694459915 0.1039751992 0.0854735833 0.1207897216 0.0060359255 0.9552760000 0.0507800000 0.0391120000 0.0307490000 0.4021330000 0.4292870000 140510851 0 402718720 3.8808755875 3.8016877174 3.8509235382 1342 1311867215.2049460411 0.1031932384 0.0854867872 0.1207897216 0.0060348664 0.5013570000 0.0523950000 0.0325950000 0.0000000000 0.4108630000 0.0019530000 140514579 0 402718720 3.8821945190 3.8051898479 3.8510777950 1343 1311867215.2369511127 0.1038980186 0.0855004962 0.1207897216 0.0060327440 0.5814500000 0.0657730000 0.0767340000 0.0313810000 0.4027960000 0.0015360000 140518195 0 402718720 3.8814954758 3.8056769371 3.8514976501 1344 1311867215.2690820694 0.1050017774 0.0855150061 0.1207897216 0.0060307430 0.5241650000 0.0661400000 0.0508280000 0.0000010000 0.4024600000 0.0015390000 140521923 0 402718720 3.8800258636 3.8070836067 3.8516538143 1345 1311867215.3049569130 0.1054613069 0.0855298361 0.1207897216 0.0060299086 0.9889420000 0.0632060000 0.0638950000 0.0314570000 0.4018940000 0.4252810000 140525707 0 402718720 3.8804929256 3.8090157509 3.8516941071 1346 1311867215.3369619846 0.1045902297 0.0855439969 0.1207897216 0.0060295100 0.5137390000 0.0644510000 0.0428940000 0.0000000000 0.4016520000 0.0015380000 140529379 0 402718720 3.8818240166 3.8099348545 3.8515088558 1347 1311867215.3691840172 0.1049358174 0.0855583932 0.1207897216 0.0060291024 0.5242600000 0.0525640000 0.0334010000 0.0313240000 0.4021910000 0.0015440000 140533051 0 402718720 3.8808729649 3.8106052876 3.8514401913 1348 1311867215.4049520493 0.1051093861 0.0855728969 0.1207897216 0.0060277452 0.5214580000 0.0746650000 0.0456570000 0.0000010000 0.3961150000 0.0016300000 140536835 0 402718720 3.8816764355 3.8130531311 3.8512530327 1349 1311867215.4370350838 0.1046686098 0.0855870523 0.1207897216 0.0060260861 0.9486640000 0.0529760000 0.0380150000 0.0308960000 0.4001420000 0.4234080000 140540451 0 402718720 3.8832178116 3.8151431084 3.8509438038 1350 1311867215.4690899849 0.1047311872 0.0856012332 0.1207897216 0.0060266323 0.5326700000 0.0537040000 0.0644140000 0.0000010000 0.4090100000 0.0019870000 140544179 0 402718720 3.8838171959 3.8151397705 3.8509285450 1351 1311867215.5049800873 0.1046034992 0.0856152985 0.1207897216 0.0060267076 0.5806230000 0.0668650000 0.0569520000 0.0382670000 0.4129480000 0.0019790000 140547963 0 402718720 3.8845303059 3.8171858788 3.8507237434 1352 1311867215.5371229649 0.1041729748 0.0856290246 0.1207897216 0.0060247417 0.5235320000 0.0672240000 0.0530120000 0.0000010000 0.3985280000 0.0015430000 140551579 0 402718720 3.8856909275 3.8198506832 3.8502328396 1353 1311867215.5690340996 0.1032462791 0.0856420455 0.1207897216 0.0060232657 0.9591260000 0.0518710000 0.0427690000 0.0307840000 0.3989640000 0.4311550000 140555307 0 402718720 3.8872497082 3.8205013275 3.8499701023 1354 1311867215.6050848961 0.1045297012 0.0856559950 0.1207897216 0.0060226348 0.5695850000 0.0678540000 0.0844050000 0.0000010000 0.4117800000 0.0019830000 140559091 0 402718720 3.8866646290 3.8227307796 3.8500618935 1355 1311867215.6370549202 0.1039433852 0.0856694912 0.1207897216 0.0060213027 0.5279080000 0.0620890000 0.0332300000 0.0313180000 0.3964800000 0.0015440000 140562763 0 402718720 3.8881888390 3.8264074326 3.8503060341 1356 1311867215.6689219475 0.1032691747 0.0856824703 0.1207897216 0.0060198221 0.4934460000 0.0655260000 0.0278560000 0.0000010000 0.3952800000 0.0015480000 140566435 0 402718720 3.8885202408 3.8265397549 3.8501031399 1357 1311867215.7049510479 0.1042338684 0.0856961412 0.1207897216 0.0060192074 0.9957390000 0.0540390000 0.0645430000 0.0341130000 0.4088340000 0.4309610000 140570219 0 402718720 3.8876323700 3.8276700974 3.8500049114 1358 1311867215.7388830185 0.1038692668 0.0857095235 0.1207897216 0.0060172959 0.5180000000 0.0535980000 0.0650510000 0.0000000000 0.3945780000 0.0015410000 140573947 0 402718720 3.8893816471 3.8317313194 3.8502295017 1359 1311867215.7691988945 0.1025597528 0.0857219225 0.1207897216 0.0060154032 0.5486430000 0.0542730000 0.0651520000 0.0314070000 0.3929910000 0.0015530000 140577451 0 402718720 3.8908345699 3.8322472572 3.8501379490 1360 1311867215.8048830032 0.1024468020 0.0857342202 0.1207897216 0.0060163137 0.5055050000 0.0643420000 0.0434930000 0.0000010000 0.3928670000 0.0015560000 140581235 0 402718720 3.8907568455 3.8328390121 3.8500657082 1361 1311867215.8373351097 0.1032716408 0.0857471059 0.1207897216 0.0060150373 0.9423800000 0.0710010000 0.0349190000 0.0314600000 0.3880130000 0.4137340000 140584907 0 402718720 3.8901519775 3.8340020180 3.8500604630 1362 1311867215.8691670895 0.1029061005 0.0857597043 0.1207897216 0.0060130627 0.4823390000 0.0542560000 0.0352890000 0.0000010000 0.3879770000 0.0015530000 140588635 0 402718720 3.8915224075 3.8352103233 3.8497467041 1363 1311867215.9052760601 0.1030949801 0.0857724227 0.1207897216 0.0060112026 0.5284510000 0.0536560000 0.0460310000 0.0313330000 0.3926190000 0.0015500000 140592419 0 402718720 3.8908927441 3.8344142437 3.8492753506 1364 1311867215.9370880127 0.1033501551 0.0857853096 0.1207897216 0.0060092709 0.4902590000 0.0537060000 0.0384840000 0.0000010000 0.3932590000 0.0015460000 140596035 0 402718720 3.8912951946 3.8362474442 3.8488926888 1365 1311867215.9702870846 0.1029133126 0.0857978576 0.1207897216 0.0060070881 0.9389810000 0.0537050000 0.0424290000 0.0314480000 0.3927010000 0.4154190000 140599763 0 402718720 3.8924131393 3.8378081322 3.8486227989 1366 1311867216.0050790310 0.1039360613 0.0858111360 0.1207897216 0.0060056410 0.5266460000 0.0856720000 0.0437220000 0.0000000000 0.3924640000 0.0015300000 140603547 0 402718720 3.8912565708 3.8381204605 3.8482887745 1367 1311867216.0369679928 0.1021320820 0.0858230752 0.1207897216 0.0060036514 0.5461980000 0.0541690000 0.0687530000 0.0309690000 0.3874440000 0.0015590000 140607163 0 402718720 3.8940265179 3.8392541409 3.8478550911 1368 1311867216.0694830418 0.1027903855 0.0858354782 0.1207897216 0.0060033593 0.4873690000 0.0542120000 0.0411360000 0.0000000000 0.3871940000 0.0015470000 140610891 0 402718720 3.8935182095 3.8407697678 3.8476431370 1369 1311867216.1050429344 0.1033606902 0.0858482797 0.1207897216 0.0060018549 0.9645190000 0.0539780000 0.0654650000 0.0309070000 0.3928550000 0.4180370000 140614675 0 402718720 3.8938374519 3.8433907032 3.8479955196 1370 1311867216.1392951012 0.1037978828 0.0858613816 0.1207897216 0.0059996992 0.5138320000 0.0535920000 0.0650320000 0.0000000000 0.3903810000 0.0015640000 140618403 0 402718720 3.8932464123 3.8441112041 3.8479716778 1371 1311867216.1692190170 0.1032205224 0.0858740432 0.1207897216 0.0059988199 0.5543070000 0.0634030000 0.0695430000 0.0314330000 0.3850840000 0.0015510000 140622019 0 402718720 3.8942489624 3.8453142643 3.8483507633 1372 1311867216.2049610615 0.1028372943 0.0858864071 0.1207897216 0.0059966690 0.5141310000 0.0553520000 0.0665980000 0.0000010000 0.3873480000 0.0015550000 140625803 0 402718720 3.8954455853 3.8483455181 3.8484849930 1373 1311867216.2370231152 0.1025103480 0.0858985149 0.1207897216 0.0059956949 0.9223590000 0.0554010000 0.0393920000 0.0314130000 0.3857810000 0.4070810000 140629419 0 402718720 3.8953120708 3.8483426571 3.8490662575 1374 1311867216.2706630230 0.1024152488 0.0859105358 0.1207897216 0.0059954444 0.4801190000 0.0558300000 0.0341540000 0.0000000000 0.3848340000 0.0015580000 140633203 0 402718720 3.8959035873 3.8504223824 3.8498339653 1375 1311867216.3050479889 0.1027937531 0.0859228145 0.1207897216 0.0059936057 0.5319220000 0.0781770000 0.0362160000 0.0314000000 0.3812750000 0.0015660000 140636931 0 402718720 3.8959982395 3.8527235985 3.8505363464 1376 1311867216.3395419121 0.1006101891 0.0859334885 0.1207897216 0.0059943831 0.5105370000 0.0568090000 0.0716980000 0.0000000000 0.3771550000 0.0015730000 140640715 0 402718720 3.8986778259 3.8545534611 3.8509206772 1377 1311867216.3694689274 0.1009575799 0.0859443992 0.1207897216 0.0059923162 0.9059400000 0.0564140000 0.0345550000 0.0313510000 0.3801340000 0.4001830000 140644275 0 402718720 3.8982183933 3.8549594879 3.8515903950 1378 1311867216.4055120945 0.1004511192 0.0859549266 0.1207897216 0.0059902131 0.4952740000 0.0562100000 0.0552890000 0.0000010000 0.3788960000 0.0015690000 140648115 0 402718720 3.8993625641 3.8566987514 3.8521018028 1379 1311867216.4373409748 0.1006620601 0.0859655916 0.1207897216 0.0059880882 0.5390680000 0.0566070000 0.0683250000 0.0313450000 0.3778950000 0.0015840000 140651675 0 402718720 3.8990461826 3.8577144146 3.8524124622 1380 1311867216.4697530270 0.1009923071 0.0859764806 0.1207897216 0.0059861839 0.4792730000 0.0568220000 0.0406020000 0.0000010000 0.3769750000 0.0015740000 140655459 0 402718720 3.8988308907 3.8600914478 3.8525047302 1381 1311867216.5049800873 0.0995403081 0.0859863023 0.1207897216 0.0059852381 0.9314950000 0.0570990000 0.0727450000 0.0314410000 0.3717210000 0.3951910000 140659187 0 402718720 3.9010674953 3.8609449863 3.8528974056 1382 1311867216.5372259617 0.1000891030 0.0859965069 0.1207897216 0.0059832384 0.5059930000 0.0572050000 0.0685390000 0.0000010000 0.3753730000 0.0015730000 140662859 0 402718720 3.9006836414 3.8609030247 3.8535254002 1383 1311867216.5693330765 0.1006896049 0.0860071310 0.1207897216 0.0059813940 0.4984100000 0.0574380000 0.0294150000 0.0313610000 0.3753160000 0.0015810000 140666531 0 402718720 3.9002666473 3.8622069359 3.8537046909 1384 1311867216.6050319672 0.1005595624 0.0860176458 0.1207897216 0.0059808165 0.4890150000 0.0699110000 0.0393770000 0.0000000000 0.3748150000 0.0015740000 140670315 0 402718720 3.9017190933 3.8638918400 3.8543949127 1385 1311867216.6373488903 0.1004031450 0.0860280324 0.1207897216 0.0059790091 0.9162770000 0.0709980000 0.0309960000 0.0314190000 0.3725240000 0.4066880000 140673987 0 402718720 3.9020481110 3.8638732433 3.8545262814 1386 1311867216.6691188812 0.1007754430 0.0860386727 0.1207897216 0.0059770427 0.5447590000 0.0731680000 0.0902620000 0.0000010000 0.3764390000 0.0015820000 140677659 0 402718720 3.9019863605 3.8637633324 3.8545858860 1387 1311867216.7052359581 0.1002320349 0.0860489058 0.1207897216 0.0059755754 0.5033400000 0.0585750000 0.0353230000 0.0309670000 0.3735660000 0.0015850000 140681443 0 402718720 3.9029996395 3.8658819199 3.8546624184 1388 1311867216.7372078896 0.1004048511 0.0860592487 0.1207897216 0.0059739560 0.4766440000 0.0578810000 0.0410120000 0.0000010000 0.3728580000 0.0015840000 140685059 0 402718720 3.9031538963 3.8668408394 3.8545365334 1389 1311867216.7691950798 0.1002595648 0.0860694721 0.1207897216 0.0059719760 0.9239810000 0.0580950000 0.0677730000 0.0309520000 0.3726050000 0.3912490000 140688787 0 402718720 3.9033269882 3.8668150902 3.8542721272 1390 1311867216.8050019741 0.1008407846 0.0860800990 0.1207897216 0.0059704934 0.5033590000 0.0581660000 0.0676770000 0.0000010000 0.3726140000 0.0015830000 140692571 0 402718720 3.9038476944 3.8681359291 3.8541905880 1391 1311867216.8379631042 0.0998408347 0.0860899917 0.1207897216 0.0059688653 0.5363430000 0.0584450000 0.0734940000 0.0310190000 0.3684640000 0.0015930000 140696243 0 402718720 3.9056367874 3.8685019016 3.8545296192 1392 1311867216.8703401089 0.0995536000 0.0860996638 0.1207897216 0.0059686719 0.4707630000 0.0583000000 0.0353590000 0.0000010000 0.3721650000 0.0015810000 140699915 0 402718720 3.9057481289 3.8692288399 3.8542039394 1393 1311867216.9049589634 0.0999083221 0.0861095767 0.1207897216 0.0059669687 0.9239400000 0.0576210000 0.0727130000 0.0314300000 0.3680080000 0.3908500000 140703699 0 402718720 3.9057390690 3.8701567650 3.8539943695 1394 1311867216.9374070168 0.0992705822 0.0861190179 0.1207897216 0.0059648772 0.5045670000 0.0582510000 0.0695390000 0.0000010000 0.3718530000 0.0015930000 140707315 0 402718720 3.9077901840 3.8710207939 3.8539543152 1395 1311867216.9691729546 0.0998468399 0.0861288586 0.1207897216 0.0059632693 0.5487550000 0.0577630000 0.0690720000 0.0313500000 0.3848320000 0.0020540000 140710987 0 402718720 3.9072074890 3.8722014427 3.8541274071 1396 1311867217.0053269863 0.0996183306 0.0861385216 0.1207897216 0.0059625837 0.5145830000 0.0733450000 0.0539690000 0.0000000000 0.3823340000 0.0015860000 140714827 0 402718720 3.9080910683 3.8736631870 3.8542866707 1397 1311867217.0373110771 0.0992444530 0.0861479030 0.1207897216 0.0059616488 0.9040520000 0.0579050000 0.0524000000 0.0313160000 0.3703370000 0.3887510000 140718443 0 402718720 3.9086353779 3.8734226227 3.8541588783 1398 1311867217.0691289902 0.0994596928 0.0861574251 0.1207897216 0.0059604924 0.5026700000 0.0581230000 0.0694170000 0.0000000000 0.3701920000 0.0015850000 140722115 0 402718720 3.9093449116 3.8741452694 3.8542449474 1399 1311867217.1052579880 0.1005764902 0.0861677318 0.1207897216 0.0059594056 0.5159620000 0.0584360000 0.0556520000 0.0314110000 0.3652930000 0.0016760000 140725955 0 402718720 3.9086859226 3.8760266304 3.8544261456 1400 1311867217.1370849609 0.0992977098 0.0861771103 0.1207897216 0.0059582705 0.4739560000 0.0583730000 0.0411330000 0.0000000000 0.3694920000 0.0015830000 140729571 0 402718720 3.9102368355 3.8758270741 3.8542411327 1401 1311867217.1691889763 0.0999995396 0.0861869764 0.1207897216 0.0059565185 0.9314250000 0.0672750000 0.0737440000 0.0314700000 0.3657290000 0.3898480000 140733299 0 402718720 3.9098861217 3.8762378693 3.8543350697 1402 1311867217.2057919502 0.1001284197 0.0861969204 0.1207897216 0.0059547824 0.4683250000 0.0584100000 0.0356530000 0.0000000000 0.3692930000 0.0015830000 140737083 0 402718720 3.9103763103 3.8783149719 3.8540852070 1403 1311867217.2371680737 0.0994492620 0.0862063661 0.1207897216 0.0059534406 0.4989490000 0.0580690000 0.0354500000 0.0312250000 0.3692440000 0.0015930000 140740755 0 402718720 3.9103600979 3.8782217503 3.8534967899 1404 1311867217.2692279816 0.0998229161 0.0862160645 0.1207897216 0.0059518761 0.4669380000 0.0595220000 0.0375820000 0.0000000000 0.3648900000 0.0015930000 140744427 0 402718720 3.9101676941 3.8791007996 3.8533117771 1405 1311867217.3051640987 0.0998871922 0.0862257949 0.1207897216 0.0059500175 0.9023920000 0.0709420000 0.0414310000 0.0309040000 0.3686150000 0.3871190000 140748211 0 402718720 3.9109897614 3.8816838264 3.8533773422 1406 1311867217.3374049664 0.1001935750 0.0862357293 0.1207897216 0.0059481282 0.4817620000 0.0731480000 0.0359090000 0.0000010000 0.3677020000 0.0015930000 140751883 0 402718720 3.9102144241 3.8831412792 3.8531534672 1407 1311867217.3695969582 0.1002781764 0.0862457097 0.1207897216 0.0059462919 0.5334290000 0.0594800000 0.0709060000 0.0314070000 0.3666440000 0.0015950000 140755555 0 402718720 3.9097981453 3.8847165108 3.8533403873 1408 1311867217.4120450020 0.0998312831 0.0862553585 0.1207897216 0.0059456561 0.5007210000 0.0596830000 0.0709270000 0.0000010000 0.3651440000 0.0015960000 140759395 0 402718720 3.9102656841 3.8854773045 3.8534939289 1409 1311867217.4372820854 0.0991763100 0.0862645288 0.1207897216 0.0059442634 0.8768060000 0.0596840000 0.0363700000 0.0314250000 0.3641470000 0.3818320000 140762843 0 402718720 3.9110000134 3.8856377602 3.8535082340 1410 1311867217.4694299698 0.0995924398 0.0862739813 0.1207897216 0.0059434602 0.5130670000 0.0732780000 0.0710970000 0.0000010000 0.3637250000 0.0015940000 140766571 0 402718720 3.9108843803 3.8874070644 3.8536517620 1411 1311867217.5050430298 0.0998311192 0.0862835894 0.1207897216 0.0059420761 0.5561880000 0.0715600000 0.0713620000 0.0313800000 0.3760620000 0.0020820000 140770355 0 402718720 3.9104187489 3.8883740902 3.8534026146 1412 1311867217.5370678902 0.0991867930 0.0862927277 0.1207897216 0.0059404034 0.5254020000 0.0756440000 0.0821250000 0.0000010000 0.3621800000 0.0015950000 140773971 0 402718720 3.9112889767 3.8891179562 3.8530607224 1413 1311867217.5691540241 0.1000364721 0.0863024543 0.1207897216 0.0059385128 0.8655430000 0.0599280000 0.0383880000 0.0313950000 0.3571450000 0.3753120000 140777643 0 402718720 3.9109551907 3.8909766674 3.8533303738 1414 1311867217.6050539017 0.0993304402 0.0863116679 0.1207897216 0.0059368953 0.5208280000 0.0851790000 0.0705320000 0.0000010000 0.3601430000 0.0016030000 140781483 0 402718720 3.9116091728 3.8921730518 3.8530733585 1415 1311867217.6370990276 0.0996440500 0.0863210901 0.1207897216 0.0059359214 0.5051360000 0.0607540000 0.0489370000 0.0314520000 0.3589740000 0.0016100000 140785099 0 402718720 3.9108488560 3.8939225674 3.8530168533 1416 1311867217.6691000462 0.0983247012 0.0863295672 0.1207897216 0.0059351874 0.5014380000 0.0847960000 0.0581200000 0.0000010000 0.3534930000 0.0016150000 140788827 0 402718720 3.9123020172 3.8947534561 3.8530607224 1417 1311867217.7050631046 0.0978376642 0.0863376886 0.1207897216 0.0059345302 0.8938400000 0.0612130000 0.0643320000 0.0315440000 0.3554950000 0.3774990000 140792611 0 402718720 3.9130098820 3.8948261738 3.8529863358 1418 1311867217.7371540070 0.0986365080 0.0863463620 0.1207897216 0.0059325129 0.5236410000 0.0776960000 0.0779300000 0.0000010000 0.3629990000 0.0016150000 140796227 0 402718720 3.9122467041 3.8950414658 3.8531239033 1419 1311867217.7694880962 0.0977827907 0.0863544215 0.1207897216 0.0059308005 0.4955300000 0.0617640000 0.0429730000 0.0314830000 0.3542670000 0.0016110000 140799955 0 402718720 3.9139666557 3.8964400291 3.8529672623 1420 1311867217.8051838875 0.0981356800 0.0863627182 0.1207897216 0.0059287328 0.4508650000 0.0602940000 0.0308310000 0.0000010000 0.3547050000 0.0016140000 140803739 0 402718720 3.9139566422 3.8967597485 3.8530125618 1421 1311867217.8372271061 0.0981284752 0.0863709981 0.1207897216 0.0059269370 0.8599710000 0.0621000000 0.0390940000 0.0314980000 0.3539250000 0.3699610000 140807355 0 402718720 3.9142420292 3.8968925476 3.8527431488 1422 1311867217.8690850735 0.0973882079 0.0863787458 0.1207897216 0.0059257318 0.4930320000 0.0611580000 0.0728170000 0.0000010000 0.3540370000 0.0016170000 140811083 0 402718720 3.9158580303 3.8990085125 3.8526580334 1423 1311867217.9056351185 0.0985935926 0.0863873296 0.1207897216 0.0059244746 0.4952400000 0.0622170000 0.0434850000 0.0314270000 0.3530730000 0.0016170000 140814923 0 402718720 3.9146275520 3.9005260468 3.8527350426 1424 1311867217.9372580051 0.0978896543 0.0863954071 0.1207897216 0.0059230621 0.4805160000 0.0855760000 0.0370660000 0.0000000000 0.3528730000 0.0015900000 140818483 0 402718720 3.9152612686 3.9012258053 3.8525495529 1425 1311867217.9711000919 0.0973101780 0.0864030666 0.1207897216 0.0059211255 0.8683810000 0.0619570000 0.0585300000 0.0314310000 0.3478930000 0.3651320000 140822267 0 402718720 3.9163501263 3.9036960602 3.8526470661 1426 1311867218.0052239895 0.0968541503 0.0864103955 0.1207897216 0.0059192955 0.4916820000 0.0621090000 0.0776210000 0.0000010000 0.3466560000 0.0017190000 140825995 0 402718720 3.9170091152 3.9047577381 3.8529117107 1427 1311867218.0371439457 0.0969304070 0.0864177677 0.1207897216 0.0059174184 0.5212060000 0.0622760000 0.0759230000 0.0314920000 0.3464870000 0.0016210000 140829611 0 402718720 3.9169001579 3.9051847458 3.8533682823 1428 1311867218.0710949898 0.0967690870 0.0864250165 0.1207897216 0.0059153648 0.4551890000 0.0627930000 0.0398930000 0.0000000000 0.3474420000 0.0016260000 140833227 0 402718720 3.9177036285 3.9073162079 3.8536272049 1429 1311867218.1050980091 0.0965589061 0.0864321081 0.1207897216 0.0059133458 0.8435550000 0.0610080000 0.0312520000 0.0307400000 0.3496160000 0.3675310000 140837011 0 402718720 3.9176950455 3.9084091187 3.8536190987 1430 1311867218.1371181011 0.0959919393 0.0864387933 0.1207897216 0.0059112784 0.4897440000 0.0626170000 0.0737450000 0.0000000000 0.3483160000 0.0016290000 140840683 0 402718720 3.9186244011 3.9102861881 3.8538653851 1431 1311867218.1712090969 0.0966841355 0.0864459528 0.1207897216 0.0059115553 0.4972220000 0.0757730000 0.0377110000 0.0313840000 0.3473050000 0.0016290000 140844411 0 402718720 3.9173965454 3.9117555618 3.8542838097 1432 1311867218.2050349712 0.0973971710 0.0864536003 0.1207897216 0.0059095281 0.4867350000 0.0627380000 0.0728470000 0.0000000000 0.3460990000 0.0016270000 140848139 0 402718720 3.9165391922 3.9134101868 3.8546240330 1433 1311867218.2372438908 0.0965105295 0.0864606184 0.1207897216 0.0059080814 0.8657700000 0.0630450000 0.0624750000 0.0314520000 0.3452590000 0.3601290000 140851755 0 402718720 3.9173336029 3.9138207436 3.8548820019 1434 1311867218.2715640068 0.0969438702 0.0864679289 0.1207897216 0.0059066143 0.5117860000 0.0798620000 0.0786520000 0.0000010000 0.3473510000 0.0021390000 140855539 0 402718720 3.9170212746 3.9160897732 3.8551580906 1435 1311867218.3051331043 0.0960792825 0.0864746267 0.1207897216 0.0059059494 0.5400860000 0.0802680000 0.0584290000 0.0384070000 0.3570810000 0.0021440000 140859267 0 402718720 3.9174740314 3.9154911041 3.8547613621 1436 1311867218.3373649120 0.0965385363 0.0864816350 0.1207897216 0.0059039333 0.5154390000 0.0805250000 0.0826650000 0.0000010000 0.3470380000 0.0016670000 140862883 0 402718720 3.9167175293 3.9163582325 3.8544230461 1437 1311867218.3734769821 0.0973883122 0.0864892249 0.1207897216 0.0059035381 0.8735630000 0.0621930000 0.0782370000 0.0312970000 0.3406790000 0.3577430000 140866723 0 402718720 3.9160943031 3.9190411568 3.8540992737 1438 1311867218.4052689075 0.0968341753 0.0864964189 0.1207897216 0.0059024703 0.4870830000 0.0638070000 0.0750460000 0.0000000000 0.3431660000 0.0016350000 140870395 0 402718720 3.9166660309 3.9204008579 3.8534924984 1439 1311867218.4372320175 0.0969865844 0.0865037088 0.1207897216 0.0059023553 0.5055260000 0.0634390000 0.0626720000 0.0310030000 0.3433740000 0.0016330000 140874067 0 402718720 3.9158103466 3.9192852974 3.8526895046 1440 1311867218.4729750156 0.0962098017 0.0865104492 0.1207897216 0.0059021175 0.4573060000 0.0625410000 0.0439770000 0.0000010000 0.3457250000 0.0016080000 140877795 0 402718720 3.9169125557 3.9206001759 3.8522844315 1441 1311867218.5051169395 0.0979878008 0.0865184140 0.1207897216 0.0059063060 0.8802660000 0.0755800000 0.0503330000 0.0314070000 0.3454770000 0.3736660000 140881523 0 402718720 3.9152092934 3.9238567352 3.8522381783 1442 1311867218.5372729301 0.0973569602 0.0865259303 0.1207897216 0.0059044956 0.5179980000 0.0798670000 0.0740110000 0.0000010000 0.3582220000 0.0021360000 140885139 0 402718720 3.9156229496 3.9249861240 3.8519887924 1443 1311867218.5714759827 0.0971325412 0.0865332807 0.1207897216 0.0059024810 0.4895830000 0.0714210000 0.0379920000 0.0314030000 0.3437220000 0.0016360000 140888923 0 402718720 3.9158191681 3.9259767532 3.8520464897 1444 1311867218.6059319973 0.0974635333 0.0865408501 0.1207897216 0.0059010669 0.5122860000 0.0881030000 0.0794600000 0.0000010000 0.3396470000 0.0016290000 140892707 0 402718720 3.9156491756 3.9273436069 3.8528347015 1445 1311867218.6372020245 0.0974828154 0.0865484224 0.1207897216 0.0058999012 0.8452510000 0.0752660000 0.0383240000 0.0314370000 0.3410300000 0.3557420000 140896267 0 402718720 3.9154922962 3.9280824661 3.8533506393 1446 1311867218.6710820198 0.0972624943 0.0865558319 0.1207897216 0.0058987399 0.4965660000 0.0759510000 0.0752320000 0.0000000000 0.3402920000 0.0016400000 140900051 0 402718720 3.9157338142 3.9288542271 3.8537652493 1447 1311867218.7058999538 0.0976444632 0.0865634951 0.1207897216 0.0058980676 0.5019000000 0.0648340000 0.0655720000 0.0310640000 0.3353390000 0.0016550000 140903667 0 402718720 3.9153995514 3.9296376705 3.8541784286 1448 1311867218.7378489971 0.0963900313 0.0865702814 0.1207897216 0.0058984312 0.4835880000 0.0650060000 0.0763270000 0.0000010000 0.3371290000 0.0016480000 140907339 0 402718720 3.9162638187 3.9294559956 3.8547313213 1449 1311867218.7715899944 0.0976557806 0.0865779318 0.1207897216 0.0058979376 0.8591060000 0.0645510000 0.0728360000 0.0309750000 0.3366030000 0.3505540000 140911067 0 402718720 3.9152297974 3.9297344685 3.8552055359 1450 1311867218.8052420616 0.0973581746 0.0865853665 0.1207897216 0.0058976359 0.4816470000 0.0644740000 0.0762500000 0.0000000000 0.3358130000 0.0016490000 140914851 0 402718720 3.9156885147 3.9316735268 3.8557286263 1451 1311867218.8379960060 0.0975211188 0.0865929032 0.1207897216 0.0058957804 0.5309690000 0.0767620000 0.0752080000 0.0314770000 0.3424150000 0.0016520000 140918467 0 402718720 3.9152810574 3.9323065281 3.8563420773 1452 1311867218.8727340698 0.0981738195 0.0866008790 0.1207897216 0.0058985559 0.4495980000 0.0649610000 0.0476530000 0.0000010000 0.3318720000 0.0016540000 140922195 0 402718720 3.9139111042 3.9310209751 3.8564784527 1453 1311867218.9054861069 0.0972250849 0.0866081909 0.1207897216 0.0059000806 0.8568830000 0.0653260000 0.0772180000 0.0314430000 0.3330730000 0.3463610000 140925811 0 402718720 3.9146561623 3.9336853027 3.8570973873 1454 1311867218.9372200966 0.0961865783 0.0866147785 0.1207897216 0.0059009203 0.4752620000 0.0854380000 0.0547270000 0.0000000000 0.3298960000 0.0016620000 140929539 0 402718720 3.9147846699 3.9335391521 3.8569309711 1455 1311867218.9731678963 0.0967038646 0.0866217126 0.1207897216 0.0058994033 0.5557990000 0.0761770000 0.1021010000 0.0384340000 0.3339470000 0.0016610000 140933323 0 402718720 3.9142711163 3.9344174862 3.8575727940 1456 1311867219.0051829815 0.0967465863 0.0866286665 0.1207897216 0.0058974211 0.4910850000 0.0769970000 0.0819460000 0.0000000000 0.3270190000 0.0016600000 140937051 0 402718720 3.9143595695 3.9357340336 3.8580665588 1457 1311867219.0371239185 0.0963638797 0.0866353482 0.1207897216 0.0058955288 0.8376920000 0.0666560000 0.0691520000 0.0314790000 0.3258330000 0.3410670000 140940723 0 402718720 3.9140450954 3.9363610744 3.8579940796 1458 1311867219.0738430023 0.0945491716 0.0866407760 0.1207897216 0.0058961571 0.4762510000 0.0655430000 0.0784170000 0.0000010000 0.3271520000 0.0016640000 140944507 0 402718720 3.9162540436 3.9373366833 3.8583743572 1459 1311867219.1050798893 0.0950722024 0.0866465550 0.1207897216 0.0058990677 0.4749070000 0.0664310000 0.0486510000 0.0314990000 0.3229250000 0.0017580000 140948123 0 402718720 3.9153554440 3.9370861053 3.8587756157 1460 1311867219.1383259296 0.0940490291 0.0866516251 0.1207897216 0.0058971403 0.4639420000 0.0670830000 0.0692670000 0.0000010000 0.3221790000 0.0017700000 140951795 0 402718720 3.9170746803 3.9384739399 3.8591821194 1461 1311867219.1708459854 0.0954776779 0.0866576662 0.1207897216 0.0058953625 0.8188360000 0.0773240000 0.0464300000 0.0313840000 0.3241180000 0.3360630000 140955523 0 402718720 3.9156277180 3.9400467873 3.8596613407 1462 1311867219.2052450180 0.0945637375 0.0866630740 0.1207897216 0.0058944977 0.4762010000 0.0674740000 0.0832750000 0.0000010000 0.3203470000 0.0016730000 140959307 0 402718720 3.9168682098 3.9407455921 3.8601422310 1463 1311867219.2391340733 0.0944841281 0.0866684199 0.1207897216 0.0058963377 0.4795960000 0.0681250000 0.0537110000 0.0310300000 0.3215720000 0.0016770000 140962979 0 402718720 3.9169397354 3.9422192574 3.8604211807 1464 1311867219.2709059715 0.0947033018 0.0866739082 0.1207897216 0.0058951185 0.4615060000 0.0956950000 0.0428730000 0.0000000000 0.3177370000 0.0016770000 140966651 0 402718720 3.9167959690 3.9430747032 3.8605527878 1465 1311867219.3052430153 0.0941768587 0.0866790296 0.1207897216 0.0059004546 0.8210340000 0.0683490000 0.0405040000 0.0314830000 0.3319690000 0.3448490000 140970379 0 402718720 3.9175186157 3.9432432652 3.8606624603 1466 1311867219.3401598930 0.0937251747 0.0866838360 0.1207897216 0.0058986636 0.4925220000 0.0861380000 0.0818410000 0.0000000000 0.3193620000 0.0016760000 140974107 0 402718720 3.9191236496 3.9444217682 3.8612051010 1467 1311867219.3715050220 0.0936063007 0.0866885548 0.1207897216 0.0058969170 0.5027610000 0.0685640000 0.0800780000 0.0310510000 0.3178850000 0.0016830000 140977723 0 402718720 3.9202036858 3.9459621906 3.8614418507 1468 1311867219.4051969051 0.0949111506 0.0866941560 0.1207897216 0.0058951610 0.4514630000 0.0686060000 0.0606490000 0.0000010000 0.3170480000 0.0016710000 140981507 0 402718720 3.9182128906 3.9463615417 3.8614859581 1469 1311867219.4394860268 0.0945602879 0.0866995108 0.1207897216 0.0058933264 0.8037660000 0.0693110000 0.0438270000 0.0385410000 0.3209250000 0.3276810000 140985235 0 402718720 3.9191079140 3.9473583698 3.8616991043 1470 1311867219.4717299938 0.0951519459 0.0867052607 0.1207897216 0.0058914854 0.4711520000 0.0697290000 0.0807890000 0.0000010000 0.3154470000 0.0016880000 140988907 0 402718720 3.9188702106 3.9486694336 3.8621215820 1471 1311867219.5051560402 0.0947274044 0.0867107143 0.1207897216 0.0058902550 0.5024680000 0.0701560000 0.0810410000 0.0314800000 0.3146070000 0.0017010000 140992635 0 402718720 3.9195547104 3.9487161636 3.8624334335 1472 1311867219.5391950607 0.0954003930 0.0867166176 0.1207897216 0.0058895569 0.4429490000 0.0824180000 0.0409790000 0.0000000000 0.3143060000 0.0016880000 140996307 0 402718720 3.9194009304 3.9507381916 3.8626673222 1473 1311867219.5743470192 0.0955610871 0.0867226220 0.1207897216 0.0058881856 0.7916280000 0.0698280000 0.0479300000 0.0310470000 0.3132480000 0.3257070000 141000091 0 402718720 3.9197106361 3.9526693821 3.8629019260 1474 1311867219.6086258888 0.0951717943 0.0867283541 0.1207897216 0.0058867808 0.4755910000 0.0890010000 0.0546560000 0.0000010000 0.3258360000 0.0022500000 141003763 0 402718720 3.9202380180 3.9517707825 3.8633627892 1475 1311867219.6425020695 0.0960152522 0.0867346503 0.1207897216 0.0058963567 0.5017550000 0.0896250000 0.0549570000 0.0385400000 0.3134100000 0.0017020000 141007491 0 402718720 3.9203615189 3.9533927441 3.8634641171 1476 1311867219.6711170673 0.0953776985 0.0867405060 0.1207897216 0.0059130303 0.4485650000 0.0843130000 0.0479420000 0.0000000000 0.3111110000 0.0016900000 141011051 0 402718720 3.9218289852 3.9536190033 3.8637096882 1477 1311867219.7052869797 0.0964716375 0.0867470945 0.1207897216 0.0059119203 0.7962580000 0.0684200000 0.0638370000 0.0308370000 0.3087870000 0.3208630000 141014779 0 402718720 3.9207155704 3.9531617165 3.8634243011 1478 1311867219.7395179272 0.0951045156 0.0867527490 0.1207897216 0.0059121503 0.4681240000 0.0704030000 0.0815270000 0.0000010000 0.3109830000 0.0016870000 141018507 0 402718720 3.9232399464 3.9538743496 3.8636651039 1479 1311867219.7772109509 0.0956185982 0.0867587435 0.1207897216 0.0059240001 0.4980320000 0.0702070000 0.0811440000 0.0310120000 0.3104330000 0.0016950000 141022291 0 402718720 3.9239442348 3.9553325176 3.8636560440 1480 1311867219.8051769733 0.0951111540 0.0867643870 0.1207897216 0.0059229536 0.4669020000 0.0703660000 0.0811530000 0.0000010000 0.3102200000 0.0016950000 141025907 0 402718720 3.9250948429 3.9555306435 3.8634347916 1481 1311867219.8397340775 0.0960801765 0.0867706772 0.1207897216 0.0059230323 0.8309280000 0.0815640000 0.0858290000 0.0315360000 0.3080920000 0.3204070000 141029691 0 402718720 3.9244019985 3.9569022655 3.8633961678 1482 1311867219.8753221035 0.0954813361 0.0867765549 0.1207897216 0.0059309033 0.4478780000 0.0700610000 0.0646670000 0.0000010000 0.3079510000 0.0016900000 141033419 0 402718720 3.9263617992 3.9583966732 3.8637084961 1483 1311867219.9108390808 0.0953717157 0.0867823507 0.1207897216 0.0059470526 0.4566050000 0.0698100000 0.0410900000 0.0313850000 0.3090720000 0.0016930000 141037091 0 402718720 3.9267351627 3.9593079090 3.8638434410 1484 1311867219.9417819977 0.0946886465 0.0867876784 0.1207897216 0.0059474955 0.4946400000 0.0969380000 0.0861300000 0.0000010000 0.3063350000 0.0017000000 141040763 0 402718720 3.9276316166 3.9604415894 3.8639609814 1485 1311867219.9732298851 0.0951857269 0.0867933336 0.1207897216 0.0059472371 0.7936020000 0.0715250000 0.0618340000 0.0315250000 0.3076930000 0.3175000000 141044323 0 402718720 3.9274511337 3.9611163139 3.8640697002 1486 1311867220.0068678856 0.0945372507 0.0867985449 0.1207897216 0.0059473850 0.4927720000 0.0958070000 0.0840920000 0.0000010000 0.3076710000 0.0016800000 141048107 0 402718720 3.9288203716 3.9612216949 3.8643212318 1487 1311867220.0422430038 0.0942118540 0.0868035303 0.1207897216 0.0059471399 0.4963030000 0.0710000000 0.0818170000 0.0314350000 0.3068690000 0.0017040000 141051835 0 402718720 3.9294469357 3.9633383751 3.8645865917 1488 1311867220.0743820667 0.0951679051 0.0868091515 0.1207897216 0.0059455170 0.4653460000 0.0696990000 0.0855890000 0.0000000000 0.3049010000 0.0017040000 141055507 0 402718720 3.9290153980 3.9643011093 3.8646948338 1489 1311867220.1052761078 0.0946295708 0.0868144036 0.1207897216 0.0059501124 0.8089090000 0.0713510000 0.0825870000 0.0314460000 0.3053910000 0.3146740000 141059179 0 402718720 3.9298889637 3.9653468132 3.8648848534 1490 1311867220.1421229839 0.0951603800 0.0868200049 0.1207897216 0.0059487365 0.4745690000 0.0831760000 0.0811760000 0.0000010000 0.3050600000 0.0017150000 141062907 0 402718720 3.9295403957 3.9672682285 3.8651163578 1491 1311867220.1714730263 0.0949639231 0.0868254670 0.1207897216 0.0059522491 0.4736420000 0.0836790000 0.0489980000 0.0315120000 0.3042590000 0.0017220000 141066579 0 402718720 3.9292259216 3.9691276550 3.8651325703 1492 1311867220.2061989307 0.0957394913 0.0868314415 0.1207897216 0.0059559411 0.4683700000 0.0723320000 0.0875620000 0.0000010000 0.3032780000 0.0017230000 141070363 0 402718720 3.9285881519 3.9698734283 3.8651614189 1493 1311867220.2422249317 0.0955093428 0.0868372539 0.1207897216 0.0059589096 0.8077040000 0.0719790000 0.0873790000 0.0310700000 0.3022300000 0.3115530000 141074147 0 402718720 3.9286844730 3.9695994854 3.8649642467 1494 1311867220.2741279602 0.0958217308 0.0868432676 0.1207897216 0.0059573045 0.4871260000 0.0936020000 0.0878110000 0.0000000000 0.3002420000 0.0018160000 141077763 0 402718720 3.9284646511 3.9708788395 3.8650021553 1495 1311867220.3064579964 0.0957937911 0.0868492546 0.1207897216 0.0059667862 0.4467150000 0.0726600000 0.0373680000 0.0315320000 0.2999720000 0.0017250000 141081435 0 402718720 3.9289159775 3.9717307091 3.8650851250 1496 1311867220.3420999050 0.0957253501 0.0868551878 0.1207897216 0.0059695463 0.4496670000 0.0930850000 0.0518120000 0.0000000000 0.2995490000 0.0017280000 141085107 0 402718720 3.9288012981 3.9727063179 3.8648819923 1497 1311867220.3714869022 0.0945897028 0.0868603545 0.1207897216 0.0060146831 0.7612700000 0.0728690000 0.0447310000 0.0310920000 0.2993660000 0.3097240000 141088723 0 402718720 3.9293177128 3.9733943939 3.8647651672 1498 1311867220.4063799381 0.0941486582 0.0868652199 0.1207897216 0.0060152072 0.4289720000 0.0733330000 0.0495430000 0.0000010000 0.3008850000 0.0017300000 141092563 0 402718720 3.9307193756 3.9760749340 3.8649785519 1499 1311867220.4408841133 0.0949175507 0.0868705917 0.1207897216 0.0060139334 0.4576820000 0.0719110000 0.0495390000 0.0314570000 0.2995160000 0.0017340000 141096291 0 402718720 3.9291172028 3.9774463177 3.8651425838 1500 1311867220.4728751183 0.0959156156 0.0868766217 0.1207897216 0.0060175286 0.4620150000 0.0736190000 0.0844950000 0.0000000000 0.2986650000 0.0017280000 141099907 0 402718720 3.9279263020 3.9790022373 3.8650584221 1501 1311867220.5091059208 0.0957825035 0.0868825550 0.1207897216 0.0060163164 0.7807170000 0.0848680000 0.0566980000 0.0314720000 0.2978630000 0.3063370000 141103747 0 402718720 3.9291145802 3.9788222313 3.8654367924 1502 1311867220.5419850349 0.0954699069 0.0868882723 0.1207897216 0.0060143280 0.4652640000 0.0740760000 0.0887360000 0.0000000000 0.2972300000 0.0017350000 141107363 0 402718720 3.9296877384 3.9800968170 3.8656425476 1503 1311867220.5716400146 0.0950040072 0.0868936720 0.1207897216 0.0060134164 0.4524910000 0.0745400000 0.0454800000 0.0316020000 0.2956210000 0.0017400000 141110923 0 402718720 3.9304616451 3.9802393913 3.8653564453 1504 1311867220.6104249954 0.0958821103 0.0868996483 0.1207897216 0.0060138626 0.4752990000 0.0862750000 0.0841200000 0.0000010000 0.2987080000 0.0023170000 141114763 0 402718720 3.9296312332 3.9805846214 3.8650894165 1505 1311867220.6415500641 0.0962559581 0.0869058651 0.1207897216 0.0060121689 0.7901010000 0.0934900000 0.0478420000 0.0390750000 0.3004840000 0.3057480000 141118323 0 402718720 3.9298431873 3.9814682007 3.8648273945 1506 1311867220.6713089943 0.0960219502 0.0869119183 0.1207897216 0.0060102196 0.4351790000 0.0912260000 0.0410120000 0.0000000000 0.2977020000 0.0017300000 141121995 0 402718720 3.9306099415 3.9821524620 3.8643383980 1507 1311867220.7073359489 0.0964838043 0.0869182699 0.1207897216 0.0060113931 0.4926770000 0.0735600000 0.0843360000 0.0314820000 0.2980570000 0.0017400000 141125779 0 402718720 3.9316093922 3.9830701351 3.8639974594 1508 1311867220.7393438816 0.0951203927 0.0869237090 0.1207897216 0.0060105464 0.4659150000 0.0737240000 0.0881110000 0.0000010000 0.2988530000 0.0017010000 141129451 0 402718720 3.9328587055 3.9824137688 3.8633406162 1509 1311867220.7719850540 0.0947413519 0.0869288897 0.1207897216 0.0060090178 0.7999280000 0.0739200000 0.0842970000 0.0315500000 0.2990350000 0.3076310000 141133067 0 402718720 3.9345960617 3.9840967655 3.8629827499 1510 1311867220.8097529411 0.0956379622 0.0869346573 0.1207897216 0.0060096988 0.4609000000 0.0736690000 0.0825640000 0.0000010000 0.2994520000 0.0017260000 141136963 0 402718720 3.9341919422 3.9849154949 3.8626170158 1511 1311867220.8415019512 0.0954811350 0.0869403134 0.1207897216 0.0060085753 0.5101830000 0.0849910000 0.0840870000 0.0310640000 0.3038640000 0.0023160000 141140579 0 402718720 3.9354913235 3.9867026806 3.8625605106 1512 1311867220.8712480068 0.0954768881 0.0869459593 0.1207897216 0.0060112818 0.4703900000 0.0939890000 0.0570200000 0.0000010000 0.3131880000 0.0023290000 141144251 0 402718720 3.9364132881 3.9879903793 3.8628058434 1513 1311867220.9075961113 0.0949220210 0.0869512310 0.1207897216 0.0060119938 0.7635450000 0.0794480000 0.0425970000 0.0315090000 0.2989360000 0.3075460000 141148035 0 402718720 3.9374158382 3.9874746799 3.8628184795 1514 1311867220.9392969608 0.0953932256 0.0869568070 0.1207897216 0.0060102844 0.4740450000 0.0867420000 0.0826570000 0.0000010000 0.2993920000 0.0017350000 141151707 0 402718720 3.9373867512 3.9885118008 3.8628215790 1515 1311867220.9713189602 0.0964778289 0.0869630915 0.1207897216 0.0060178174 0.4654720000 0.0732600000 0.0563910000 0.0310530000 0.2995230000 0.0017330000 141155379 0 402718720 3.9364826679 3.9892854691 3.8628909588 1516 1311867221.0090179443 0.0959488451 0.0869690187 0.1207897216 0.0060158472 0.4972920000 0.1054470000 0.0881330000 0.0000000000 0.2984290000 0.0017370000 141159219 0 402718720 3.9376606941 3.9902410507 3.8631091118 1517 1311867221.0392940044 0.0960412547 0.0869749991 0.1207897216 0.0060138779 0.8014570000 0.0729570000 0.0852800000 0.0314420000 0.2997380000 0.3084910000 141162835 0 402718720 3.9377892017 3.9901690483 3.8632514477 1518 1311867221.0720989704 0.0967829600 0.0869814602 0.1207897216 0.0060123067 0.4289000000 0.0736810000 0.0496490000 0.0000010000 0.3003140000 0.0017310000 141166507 0 402718720 3.9371335506 3.9911158085 3.8633406162 1519 1311867221.1077580452 0.0966023207 0.0869877939 0.1207897216 0.0060111295 0.4668840000 0.0733140000 0.0595390000 0.0310590000 0.2974490000 0.0018270000 141170291 0 402718720 3.9379432201 3.9933335781 3.8634192944 1520 1311867221.1397790909 0.0967235640 0.0869941990 0.1207897216 0.0060099407 0.4632370000 0.0721140000 0.0879550000 0.0000000000 0.2979200000 0.0017430000 141174019 0 402718720 3.9386713505 3.9926784039 3.8635790348 1521 1311867221.1716909409 0.0977916420 0.0870012979 0.1207897216 0.0060117060 0.7719590000 0.0876790000 0.0449880000 0.0316090000 0.2974390000 0.3067100000 141177579 0 402718720 3.9380445480 3.9938981533 3.8633170128 1522 1311867221.2083969116 0.0974761397 0.0870081802 0.1207897216 0.0060127067 0.4763380000 0.0865880000 0.0849390000 0.0000000000 0.2995140000 0.0017450000 141181363 0 402718720 3.9393436909 3.9966683388 3.8634350300 1523 1311867221.2398130894 0.0964902565 0.0870144061 0.1207897216 0.0060125924 0.4569700000 0.0719550000 0.0519720000 0.0313470000 0.2962090000 0.0017940000 141185091 0 402718720 3.9408318996 3.9965884686 3.8631896973 1524 1311867221.2721240520 0.0967270732 0.0870207793 0.1207897216 0.0060111877 0.4197880000 0.0735680000 0.0428470000 0.0000010000 0.2980940000 0.0017370000 141188763 0 402718720 3.9406068325 3.9964282513 3.8628334999 1525 1311867221.3075931072 0.0981278494 0.0870280626 0.1207897216 0.0060129696 0.8004650000 0.0736750000 0.0891600000 0.0315440000 0.2962560000 0.3062930000 141192491 0 402718720 3.9398846626 3.9993720055 3.8623979092 1526 1311867221.3393449783 0.0970570669 0.0870346347 0.1207897216 0.0060115545 0.4344910000 0.0811970000 0.0499400000 0.0000000000 0.2980640000 0.0017370000 141196163 0 402718720 3.9423246384 4.0005450249 3.8621218204 1527 1311867221.3714220524 0.0964927673 0.0870408286 0.1207897216 0.0060107129 0.4954450000 0.0735090000 0.0890650000 0.0310790000 0.2962180000 0.0018290000 141199891 0 402718720 3.9431135654 3.9999744892 3.8612353802 1528 1311867221.4073879719 0.0965302661 0.0870470390 0.1207897216 0.0060091005 0.4562900000 0.0737200000 0.0777720000 0.0000010000 0.2995190000 0.0017290000 141203563 0 402718720 3.9444289207 4.0032873154 3.8606388569 1529 1311867221.4400680065 0.0960828587 0.0870529486 0.1207897216 0.0060081020 0.8003380000 0.0737200000 0.0850210000 0.0314670000 0.2988870000 0.3077110000 141207291 0 402718720 3.9458808899 4.0039901733 3.8602240086 1530 1311867221.4712409973 0.0960008577 0.0870587969 0.1207897216 0.0060072019 0.4633900000 0.0741820000 0.0853370000 0.0000010000 0.2985820000 0.0017360000 141210907 0 402718720 3.9469430447 4.0059456825 3.8598539829 1531 1311867221.5081720352 0.0962998420 0.0870648329 0.1207897216 0.0060058292 0.4572520000 0.0724220000 0.0498760000 0.0313100000 0.2983500000 0.0017430000 141214691 0 402718720 3.9467833042 4.0063457489 3.8594372272 1532 1311867221.5396909714 0.0968327150 0.0870712088 0.1207897216 0.0060040727 0.4278690000 0.0732320000 0.0529090000 0.0000010000 0.2961580000 0.0018250000 141218419 0 402718720 3.9468400478 4.0083074570 3.8590419292 1533 1311867221.5712790489 0.0971663818 0.0870777940 0.1207897216 0.0060038633 0.8014340000 0.0742940000 0.0873520000 0.0315600000 0.2978780000 0.3067550000 141222091 0 402718720 3.9467909336 4.0097494125 3.8584964275 1534 1311867221.6073110104 0.0967584103 0.0870841047 0.1207897216 0.0060029915 0.4655130000 0.0745190000 0.0896390000 0.0000010000 0.2957980000 0.0018270000 141225819 0 402718720 3.9471662045 4.0093617439 3.8576273918 1535 1311867221.6403770447 0.0971412510 0.0870906566 0.1207897216 0.0060021819 0.4957470000 0.0734370000 0.0866890000 0.0315340000 0.2987770000 0.0017340000 141229603 0 402718720 3.9468719959 4.0128326416 3.8568830490 1536 1311867221.6771481037 0.0971225202 0.0870971878 0.1207897216 0.0060016448 0.4381040000 0.0903730000 0.0454160000 0.0000010000 0.2969850000 0.0017480000 141233387 0 402718720 3.9473669529 4.0153017044 3.8560237885 1537 1311867221.7072019577 0.0970341414 0.0871036529 0.1207897216 0.0060027012 0.7797240000 0.0739460000 0.0639890000 0.0314270000 0.2990300000 0.3077730000 141236947 0 402718720 3.9471030235 4.0173816681 3.8549752235 1538 1311867221.7423930168 0.0960913226 0.0871094967 0.1207897216 0.0060011423 0.4602350000 0.0717110000 0.0841240000 0.0000010000 0.2991440000 0.0017180000 141240731 0 402718720 3.9482083321 4.0195760727 3.8539843559 1539 1311867221.7773499489 0.0958533883 0.0871151782 0.1207897216 0.0060003004 0.4593670000 0.0742990000 0.0504970000 0.0311360000 0.2981080000 0.0017420000 141244403 0 402718720 3.9489922523 4.0220885277 3.8533685207 1540 1311867221.8074541092 0.0960274041 0.0871209654 0.1207897216 0.0059985495 0.4471340000 0.0729160000 0.0712990000 0.0000010000 0.2976310000 0.0017420000 141248019 0 402718720 3.9488763809 4.0242333412 3.8524444103 1541 1311867221.8396520615 0.0955888405 0.0871264604 0.1207897216 0.0060057730 0.8817530000 0.0930980000 0.1136160000 0.0391770000 0.3113520000 0.3205530000 141251747 0 402718720 3.9485352039 4.0227956772 3.8507819176 1542 1311867221.8777329922 0.0956352949 0.0871319785 0.1207897216 0.0060076751 0.4838420000 0.0943130000 0.0856840000 0.0000010000 0.2985310000 0.0017460000 141255587 0 402718720 3.9490425587 4.0243039131 3.8494184017 1543 1311867221.9077489376 0.0954603776 0.0871373760 0.1207897216 0.0060079726 0.4953310000 0.0725320000 0.0886010000 0.0313390000 0.2975490000 0.0017400000 141259203 0 402718720 3.9495689869 4.0269312859 3.8480498791 1544 1311867221.9424629211 0.0950219631 0.0871424826 0.1207897216 0.0060080064 0.4637210000 0.0740510000 0.0851600000 0.0000010000 0.2992480000 0.0017380000 141262931 0 402718720 3.9492037296 4.0271353722 3.8468043804 1545 1311867221.9775359631 0.0951172113 0.0871476442 0.1207897216 0.0060071535 0.7677360000 0.0746780000 0.0507500000 0.0315420000 0.2990030000 0.3081750000 141266715 0 402718720 3.9489130974 4.0289030075 3.8455989361 1546 1311867222.0090060234 0.0956098363 0.0871531178 0.1207897216 0.0060053036 0.4997020000 0.1071040000 0.0904990000 0.0000010000 0.2964260000 0.0018460000 141270387 0 402718720 3.9482059479 4.0309457779 3.8447847366 1547 1311867222.0428760052 0.0958854035 0.0871587625 0.1207897216 0.0060063464 0.4936180000 0.0737410000 0.0852290000 0.0310390000 0.2982690000 0.0017400000 141273947 0 402718720 3.9472324848 4.0315880775 3.8438298702 1548 1311867222.0782530308 0.0965599343 0.0871648356 0.1207897216 0.0060099955 0.4668300000 0.0746960000 0.0903360000 0.0000010000 0.2962000000 0.0018490000 141277619 0 402718720 3.9461867809 4.0346212387 3.8432006836 1549 1311867222.1110939980 0.0957021788 0.0871703471 0.1207897216 0.0060083979 0.8159120000 0.0876130000 0.0906130000 0.0316230000 0.2958640000 0.3065980000 141281291 0 402718720 3.9470393658 4.0378718376 3.8429174423 1550 1311867222.1406900883 0.0956794247 0.0871758369 0.1207897216 0.0060227186 0.4638320000 0.0754250000 0.0863710000 0.0000010000 0.2967300000 0.0017480000 141284907 0 402718720 3.9455614090 4.0395345688 3.8427689075 1551 1311867222.1797990799 0.0959335268 0.0871814833 0.1207897216 0.0060352683 0.5142990000 0.0949770000 0.0865670000 0.0311260000 0.2962680000 0.0017550000 141288803 0 402718720 3.9448487759 4.0405583382 3.8424236774 1552 1311867222.2081730366 0.0962707847 0.0871873398 0.1207897216 0.0060374395 0.4229980000 0.0761510000 0.0465320000 0.0000000000 0.2946320000 0.0018630000 141292363 0 402718720 3.9448654652 4.0453615189 3.8429291248 1553 1311867222.2400839329 0.0969451144 0.0871936230 0.1207897216 0.0060379679 0.8033540000 0.0742940000 0.0905930000 0.0313900000 0.2968550000 0.3066170000 141296035 0 402718720 3.9433205128 4.0475807190 3.8432309628 1554 1311867222.2760300636 0.0962175131 0.0871994299 0.1207897216 0.0060371279 0.4683380000 0.0762780000 0.0870490000 0.0000000000 0.2996690000 0.0017650000 141299819 0 402718720 3.9427495003 4.0470747948 3.8432960510 1555 1311867222.3077421188 0.0970058516 0.0872057363 0.1207897216 0.0060353473 0.4638390000 0.0755230000 0.0515000000 0.0316090000 0.2998750000 0.0017660000 141303491 0 402718720 3.9414608479 4.0508866310 3.8440442085 1556 1311867222.3396389484 0.0977353454 0.0872125034 0.1207897216 0.0060364160 0.4819310000 0.0883580000 0.0880010000 0.0000000000 0.3001990000 0.0017630000 141307163 0 402718720 3.9396688938 4.0524806976 3.8443329334 1557 1311867222.3792359829 0.0958028808 0.0872180206 0.1207897216 0.0060375728 0.8087960000 0.0938110000 0.0772350000 0.0316470000 0.2958060000 0.3067090000 141311003 0 402718720 3.9417769909 4.0524797440 3.8446083069 1558 1311867222.4102001190 0.0959344283 0.0872236153 0.1207897216 0.0060366877 0.4701320000 0.0778690000 0.0885540000 0.0000010000 0.2983570000 0.0017640000 141314675 0 402718720 3.9412717819 4.0545606613 3.8452529907 1559 1311867222.4436430931 0.0951434076 0.0872286953 0.1207897216 0.0060357720 0.5037780000 0.0783470000 0.0939130000 0.0316250000 0.2945000000 0.0017880000 141318347 0 402718720 3.9427976608 4.0571756363 3.8463914394 1560 1311867222.4781119823 0.0945243537 0.0872333720 0.1207897216 0.0060343509 0.4515700000 0.0762750000 0.0735150000 0.0000010000 0.2964550000 0.0017350000 141322131 0 402718720 3.9423334599 4.0584750175 3.8470001221 1561 1311867222.5087089539 0.0939776227 0.0872376925 0.1207897216 0.0060326192 0.7615960000 0.0785980000 0.0552550000 0.0316510000 0.2913960000 0.3011090000 141325747 0 402718720 3.9437973499 4.0602521896 3.8481223583 1562 1311867222.5401790142 0.0937406048 0.0872418557 0.1207897216 0.0060312249 0.4670320000 0.0791490000 0.0901220000 0.0000010000 0.2923650000 0.0017840000 141329419 0 402718720 3.9446303844 4.0616555214 3.8489096165 1563 1311867222.5774040222 0.0932217464 0.0872456816 0.1207897216 0.0060300246 0.4569270000 0.0786910000 0.0527560000 0.0311250000 0.2889760000 0.0017850000 141333203 0 402718720 3.9449882507 4.0616073608 3.8495926857 1564 1311867222.6084389687 0.0921437070 0.0872488133 0.1207897216 0.0060290861 0.4404450000 0.0789890000 0.0679740000 0.0000000000 0.2881270000 0.0017760000 141336875 0 402718720 3.9459543228 4.0617327690 3.8504791260 1565 1311867222.6433119774 0.0939463004 0.0872530929 0.1207897216 0.0060278137 0.7545610000 0.0917800000 0.0457270000 0.0315810000 0.2865530000 0.2953570000 141340603 0 402718720 3.9436275959 4.0642251968 3.8510272503 1566 1311867222.6796491146 0.0942787305 0.0872575792 0.1207897216 0.0060281898 0.4759440000 0.0908940000 0.0954530000 0.0000010000 0.2839860000 0.0018720000 141344443 0 402718720 3.9436352253 4.0650138855 3.8516869545 1567 1311867222.7080249786 0.0934824571 0.0872615517 0.1207897216 0.0060285748 0.5059290000 0.0908100000 0.0952480000 0.0316080000 0.2825680000 0.0018930000 141347947 0 402718720 3.9446539879 4.0664186478 3.8523297310 1568 1311867222.7400081158 0.0934429988 0.0872654939 0.1207897216 0.0060303925 0.4828250000 0.0990330000 0.0953650000 0.0000000000 0.2830800000 0.0017890000 141351675 0 402718720 3.9450902939 4.0678806305 3.8532376289 1569 1311867222.7793939114 0.0926111639 0.0872689010 0.1207897216 0.0060334208 0.7416310000 0.0789070000 0.0547440000 0.0315290000 0.2820930000 0.2907730000 141355403 0 402718720 3.9460134506 4.0674085617 3.8537411690 1570 1311867222.8093209267 0.0921788961 0.0872720284 0.1207897216 0.0060325431 0.4606380000 0.0791170000 0.0952970000 0.0000010000 0.2808600000 0.0017930000 141358963 0 402718720 3.9467012882 4.0673251152 3.8542351723 1571 1311867222.8402760029 0.0918328166 0.0872749315 0.1207897216 0.0060309484 0.4829890000 0.1028730000 0.0638250000 0.0311710000 0.2794170000 0.0018760000 141362635 0 402718720 3.9475829601 4.0694818497 3.8548674583 1572 1311867222.8812980652 0.0907408521 0.0872771363 0.1207897216 0.0060296814 0.4297670000 0.0793690000 0.0641740000 0.0000010000 0.2808380000 0.0017900000 141366475 0 402718720 3.9485020638 4.0693368912 3.8553795815 1573 1311867222.9082360268 0.0912591591 0.0872796678 0.1207897216 0.0060285748 0.7675830000 0.0800550000 0.0836020000 0.0315980000 0.2800860000 0.2886300000 141370035 0 402718720 3.9475214481 4.0689315796 3.8556690216 1574 1311867222.9470820427 0.0914424658 0.0872823125 0.1207897216 0.0060273754 0.4475640000 0.0775960000 0.0861330000 0.0000010000 0.2781840000 0.0018400000 141373931 0 402718720 3.9475867748 4.0712037086 3.8564684391 1575 1311867222.9831020832 0.0908117071 0.0872845534 0.1207897216 0.0060256016 0.4708130000 0.0774770000 0.0785050000 0.0313880000 0.2777870000 0.0018400000 141377715 0 402718720 3.9479691982 4.0711607933 3.8568882942 1576 1311867223.0078310966 0.0908065736 0.0872867882 0.1207897216 0.0060264796 0.4355560000 0.0917290000 0.0534950000 0.0000010000 0.2839210000 0.0024290000 141381163 0 402718720 3.9477591515 4.0701093674 3.8572485447 1577 1311867223.0454061031 0.0909096301 0.0872890855 0.1207897216 0.0060253203 0.7700680000 0.1006100000 0.0685020000 0.0315140000 0.2787620000 0.2870740000 141385003 0 402718720 3.9473650455 4.0719332695 3.8576965332 1578 1311867223.0808250904 0.0902157426 0.0872909401 0.1207897216 0.0060252306 0.4238490000 0.0793560000 0.0606310000 0.0000000000 0.2784760000 0.0017960000 141388787 0 402718720 3.9481060505 4.0725226402 3.8580505848 1579 1311867223.1094229221 0.0909229293 0.0872932403 0.1207897216 0.0060249122 0.4472660000 0.0791110000 0.0531420000 0.0314990000 0.2781080000 0.0017880000 141392347 0 402718720 3.9466757774 4.0736708641 3.8584425449 1580 1311867223.1473770142 0.0910477936 0.0872956166 0.1207897216 0.0060240495 0.4958140000 0.0972010000 0.1004800000 0.0000000000 0.2917220000 0.0024130000 141396187 0 402718720 3.9468007088 4.0758123398 3.8590164185 1581 1311867223.1758580208 0.0914496705 0.0872982441 0.1207897216 0.0060235858 0.8564420000 0.1011660000 0.1206990000 0.0385460000 0.2916300000 0.3003700000 141399747 0 402718720 3.9455347061 4.0759997368 3.8592815399 1582 1311867223.2080020905 0.0905943289 0.0873003276 0.1207897216 0.0060219876 0.4532880000 0.0950050000 0.0752380000 0.0000020000 0.2776150000 0.0017750000 141403363 0 402718720 3.9457643032 4.0765190125 3.8595821857 1583 1311867223.2450079918 0.0900318697 0.0873020531 0.1207897216 0.0060214356 0.4544070000 0.0800340000 0.0610030000 0.0310840000 0.2767680000 0.0017990000 141407203 0 402718720 3.9460053444 4.0782928467 3.8601963520 1584 1311867223.2779359818 0.0902229026 0.0873038971 0.1207897216 0.0060204367 0.4652990000 0.0920010000 0.0906690000 0.0000010000 0.2771000000 0.0017910000 141410931 0 402718720 3.9458115101 4.0801405907 3.8609011173 1585 1311867223.3085999489 0.0907866284 0.0873060944 0.1207897216 0.0060190691 0.7291670000 0.0803900000 0.0535140000 0.0315240000 0.2757010000 0.2843090000 141414547 0 402718720 3.9443578720 4.0806446075 3.8613314629 1586 1311867223.3452420235 0.0900930837 0.0873078517 0.1207897216 0.0060190844 0.4717410000 0.0951410000 0.0958190000 0.0000000000 0.2752560000 0.0017880000 141418387 0 402718720 3.9451119900 4.0833144188 3.8620560169 1587 1311867223.3794689178 0.0887528509 0.0873087622 0.1207897216 0.0060220060 0.4874670000 0.0802820000 0.0960610000 0.0310730000 0.2745220000 0.0018000000 141422059 0 402718720 3.9449224472 4.0855460167 3.8624236584 1588 1311867223.4074239731 0.0906210393 0.0873108480 0.1207897216 0.0060229431 0.4507060000 0.0790120000 0.0908460000 0.0000010000 0.2753530000 0.0017590000 141425563 0 402718720 3.9434573650 4.0847415924 3.8625600338 1589 1311867223.4458000660 0.0905051380 0.0873128582 0.1207897216 0.0060214604 0.7512360000 0.0807490000 0.0801210000 0.0310880000 0.2733890000 0.2822000000 141429403 0 402718720 3.9428987503 4.0844016075 3.8625886440 1590 1311867223.4758329391 0.0902326107 0.0873146946 0.1207897216 0.0060197284 0.4206240000 0.0801850000 0.0611500000 0.0000000000 0.2737620000 0.0017950000 141433075 0 402718720 3.9430735111 4.0858178139 3.8624637127 1591 1311867223.5077428818 0.0921302363 0.0873177213 0.1207897216 0.0060195899 0.4958400000 0.0937660000 0.0914190000 0.0314570000 0.2736740000 0.0018000000 141436747 0 402718720 3.9396238327 4.0877509117 3.8620586395 1592 1311867223.5466530323 0.0901688859 0.0873195122 0.1207897216 0.0060281767 0.4493320000 0.0805090000 0.0892160000 0.0000010000 0.2740690000 0.0017960000 141440587 0 402718720 3.9411225319 4.0873141289 3.8616104126 1593 1311867223.5759539604 0.0912695602 0.0873219919 0.1207897216 0.0060319003 0.7410680000 0.0802960000 0.0687640000 0.0315160000 0.2740260000 0.2827500000 141444259 0 402718720 3.9397737980 4.0894832611 3.8611395359 1594 1311867223.6078069210 0.0913037360 0.0873244898 0.1207897216 0.0060300234 0.4168720000 0.0791520000 0.0536630000 0.0000010000 0.2774780000 0.0024320000 141447819 0 402718720 3.9391613007 4.0894765854 3.8607823849 1595 1311867223.6502039433 0.0904548690 0.0873264524 0.1207897216 0.0060331409 0.4952720000 0.1013330000 0.0613670000 0.0384510000 0.2875770000 0.0024180000 141451827 0 402718720 3.9393146038 4.0900511742 3.8600804806 1596 1311867223.6753880978 0.0903678983 0.0873283581 0.1207897216 0.0060314774 0.4668230000 0.1011820000 0.0711990000 0.0000010000 0.2878820000 0.0024150000 141455275 0 402718720 3.9394745827 4.0918531418 3.8597640991 1597 1311867223.7088580132 0.0905611143 0.0873303824 0.1207897216 0.0060298743 0.8407330000 0.1017040000 0.1213290000 0.0391060000 0.2879370000 0.2869490000 141459003 0 402718720 3.9389383793 4.0938682556 3.8596744537 1598 1311867223.7452809811 0.0910287648 0.0873326968 0.1207897216 0.0060290677 0.4401790000 0.0804210000 0.0799580000 0.0000010000 0.2742890000 0.0017970000 141462843 0 402718720 3.9380474091 4.0951576233 3.8592998981 1599 1311867223.7760720253 0.0908309743 0.0873348846 0.1207897216 0.0060290941 0.4360240000 0.0805830000 0.0463130000 0.0310630000 0.2725340000 0.0017960000 141466459 0 402718720 3.9391045570 4.0978579521 3.8592379093 1600 1311867223.8077559471 0.0913551524 0.0873373972 0.1207897216 0.0060272155 0.4488800000 0.0935750000 0.0765810000 0.0000010000 0.2731880000 0.0017940000 141470075 0 402718720 3.9386711121 4.0997042656 3.8591167927 1601 1311867223.8438520432 0.0922466218 0.0873404636 0.1207897216 0.0060286721 0.7529390000 0.0952420000 0.0729690000 0.0315890000 0.2700010000 0.2794100000 141473915 0 402718720 3.9382686615 4.1014966965 3.8589005470 1602 1311867223.8760919571 0.0927309319 0.0873438284 0.1207897216 0.0060280427 0.4270460000 0.0810350000 0.0691840000 0.0000000000 0.2712870000 0.0017950000 141477587 0 402718720 3.9376256466 4.1020550728 3.8586735725 1603 1311867223.9078280926 0.0927819163 0.0873472209 0.1207897216 0.0060263997 0.4842650000 0.0813010000 0.0970210000 0.0315630000 0.2685430000 0.0019000000 141481203 0 402718720 3.9382598400 4.1039223671 3.8585660458 1604 1311867223.9491670132 0.0935198665 0.0873510691 0.1207897216 0.0060248881 0.4538430000 0.0813090000 0.0972950000 0.0000010000 0.2694220000 0.0018970000 141485155 0 402718720 3.9375953674 4.1052484512 3.8582816124 1605 1311867223.9760739803 0.0926467106 0.0873543686 0.1207897216 0.0060272524 0.7215310000 0.0813730000 0.0571140000 0.0315120000 0.2692950000 0.2784720000 141488715 0 402718720 3.9392056465 4.1068162918 3.8579082489 1606 1311867224.0093441010 0.0940390602 0.0873585309 0.1207897216 0.0060301465 0.4618760000 0.0928960000 0.0926210000 0.0000010000 0.2707450000 0.0018130000 141492387 0 402718720 3.9379370213 4.1087660789 3.8573257923 1607 1311867224.0470440388 0.0939991176 0.0873626632 0.1207897216 0.0060285150 0.4423810000 0.0816740000 0.0544170000 0.0310350000 0.2697080000 0.0018050000 141496283 0 402718720 3.9389207363 4.1100797653 3.8572254181 1608 1311867224.0761411190 0.0940499455 0.0873668220 0.1207897216 0.0060266699 0.4275380000 0.0819630000 0.0698290000 0.0000000000 0.2702290000 0.0018090000 141499843 0 402718720 3.9391710758 4.1110739708 3.8568205833 1609 1311867224.1081349850 0.0940526724 0.0873709773 0.1207897216 0.0060251682 0.7742870000 0.0998330000 0.0894120000 0.0315080000 0.2705610000 0.2792420000 141503515 0 402718720 3.9399330616 4.1130070686 3.8561403751 1610 1311867224.1458990574 0.0948950201 0.0873756506 0.1207897216 0.0060262914 0.4220110000 0.0813980000 0.0654620000 0.0000010000 0.2692940000 0.0019030000 141507299 0 402718720 3.9397890568 4.1153206825 3.8558456898 1611 1311867224.1768929958 0.0947636142 0.0873802365 0.1207897216 0.0060287833 0.5039090000 0.1003100000 0.0954330000 0.0316030000 0.2709750000 0.0018060000 141510971 0 402718720 3.9411880970 4.1170310974 3.8554921150 1612 1311867224.2143769264 0.0940004215 0.0873843433 0.1207897216 0.0060272935 0.4459800000 0.0814890000 0.0891570000 0.0000000000 0.2695260000 0.0018940000 141514643 0 402718720 3.9426295757 4.1187005043 3.8548173904 1613 1311867224.2470428944 0.0952450261 0.0873892167 0.1207897216 0.0060257025 0.7827670000 0.0818210000 0.0929350000 0.0314710000 0.2785880000 0.2938190000 141518315 0 402718720 3.9412419796 4.1207790375 3.8542022705 1614 1311867224.2768630981 0.0975467414 0.0873955100 0.1207897216 0.0060279470 0.5207810000 0.1043160000 0.1241850000 0.0000000000 0.2861460000 0.0023740000 141521875 0 402718720 3.9389500618 4.1239295006 3.8538992405 1615 1311867224.3146169186 0.0965092927 0.0874011533 0.1207897216 0.0060293748 0.4965100000 0.0946770000 0.0928090000 0.0314840000 0.2719460000 0.0018000000 141525771 0 402718720 3.9410378933 4.1236968040 3.8531658649 1616 1311867224.3456730843 0.0969915241 0.0874070879 0.1207897216 0.0060276275 0.4764740000 0.1062840000 0.0925100000 0.0000010000 0.2720780000 0.0017930000 141529443 0 402718720 3.9401049614 4.1257390976 3.8523364067 1617 1311867224.3769209385 0.0972878560 0.0874131984 0.1207897216 0.0060261224 0.7232660000 0.0815560000 0.0546000000 0.0310480000 0.2720080000 0.2802550000 141533003 0 402718720 3.9400515556 4.1288437843 3.8518166542 1618 1311867224.4141020775 0.0983369127 0.0874199498 0.1207897216 0.0060268344 0.4296700000 0.0815020000 0.0702530000 0.0000010000 0.2723180000 0.0018020000 141536843 0 402718720 3.9388785362 4.1289863586 3.8509905338 1619 1311867224.4464271069 0.0985706970 0.0874268372 0.1207897216 0.0060261273 0.4823160000 0.0817180000 0.0931950000 0.0310440000 0.2707120000 0.0017970000 141540515 0 402718720 3.9383602142 4.1307086945 3.8501174450 1620 1311867224.4776859283 0.0984787270 0.0874336594 0.1207897216 0.0060278378 0.4695970000 0.1019680000 0.0924890000 0.0000010000 0.2694840000 0.0018000000 141544131 0 402718720 3.9394543171 4.1346502304 3.8497936726 1621 1311867224.5181219578 0.0992543325 0.0874409516 0.1207897216 0.0060337527 0.7198560000 0.0808370000 0.0631750000 0.0314950000 0.2664260000 0.2739500000 141548027 0 402718720 3.9387850761 4.1342215538 3.8489477634 1622 1311867224.5470569134 0.0988477394 0.0874479842 0.1207897216 0.0060323928 0.4105900000 0.0811460000 0.0557020000 0.0000000000 0.2678920000 0.0019260000 141551643 0 402718720 3.9396333694 4.1343307495 3.8481974602 1623 1311867224.5859119892 0.1010775119 0.0874563819 0.1207897216 0.0060428519 0.4588230000 0.0806020000 0.0731160000 0.0310790000 0.2683680000 0.0018030000 141555539 0 402718720 3.9374496937 4.1410112381 3.8479373455 1624 1311867224.6181120872 0.1012323871 0.0874648647 0.1207897216 0.0060411933 0.4230570000 0.0804600000 0.0673320000 0.0000010000 0.2696190000 0.0017900000 141559155 0 402718720 3.9367744923 4.1430521011 3.8473010063 1625 1311867224.6502161026 0.0998445973 0.0874724830 0.1207897216 0.0060397725 0.7243430000 0.0807990000 0.0619950000 0.0310460000 0.2695940000 0.2770390000 141562883 0 402718720 3.9378015995 4.1417965889 3.8466622829 1626 1311867224.6785190105 0.1005188674 0.0874805066 0.1207897216 0.0060398469 0.4333280000 0.1023280000 0.0568030000 0.0000010000 0.2682610000 0.0018840000 141566387 0 402718720 3.9364645481 4.1441674232 3.8464019299 1627 1311867224.7173650265 0.1002856568 0.0874883770 0.1207897216 0.0060410967 0.4748740000 0.0798810000 0.0888370000 0.0315430000 0.2689760000 0.0017950000 141570283 0 402718720 3.9375536442 4.1477494240 3.8465213776 1628 1311867224.7520918846 0.1003742665 0.0874962921 0.1207897216 0.0060395495 0.4472130000 0.0801040000 0.0917410000 0.0000000000 0.2697390000 0.0017890000 141574067 0 402718720 3.9369468689 4.1482033730 3.8463606834 1629 1311867224.7866261005 0.0996930450 0.0875037794 0.1207897216 0.0060391981 0.7445030000 0.0783230000 0.0834640000 0.0313140000 0.2701810000 0.2773310000 141577739 0 402718720 3.9374325275 4.1484823227 3.8460624218 1630 1311867224.8123459816 0.1007535309 0.0875119081 0.1207897216 0.0060414401 0.4027150000 0.0803750000 0.0465350000 0.0000000000 0.2701440000 0.0017940000 141581299 0 402718720 3.9362292290 4.1515231133 3.8461647034 1631 1311867224.8458189964 0.1006278098 0.0875199497 0.1207897216 0.0060658878 0.5038910000 0.1005810000 0.0968280000 0.0314840000 0.2693550000 0.0017970000 141584915 0 402718720 3.9366991520 4.1539435387 3.8465669155 1632 1311867224.8779430389 0.1011933237 0.0875283280 0.1207897216 0.0060710134 0.4072100000 0.0785030000 0.0534840000 0.0000010000 0.2696200000 0.0017500000 141588531 0 402718720 3.9354372025 4.1554503441 3.8465545177 1633 1311867224.9142448902 0.1001718417 0.0875360705 0.1207897216 0.0060752847 0.7304640000 0.0802100000 0.0730650000 0.0315010000 0.2670670000 0.2745740000 141592371 0 402718720 3.9377543926 4.1582961082 3.8473255634 1634 1311867224.9471449852 0.1013154835 0.0875445034 0.1207897216 0.0060780820 0.4354350000 0.0806470000 0.0814140000 0.0000000000 0.2674630000 0.0018830000 141595931 0 402718720 3.9364693165 4.1599283218 3.8475408554 1635 1311867224.9800488949 0.0987167582 0.0875513366 0.1207897216 0.0060775802 0.4587080000 0.0807670000 0.0716440000 0.0314930000 0.2691790000 0.0017960000 141599715 0 402718720 3.9390282631 4.1593461037 3.8475944996 1636 1311867225.0142920017 0.0997470468 0.0875587912 0.1207897216 0.0060785190 0.4791470000 0.1084390000 0.0972300000 0.0000010000 0.2675440000 0.0018940000 141603275 0 402718720 3.9380028248 4.1641407013 3.8479793072 1637 1311867225.0493879318 0.0999853313 0.0875663823 0.1207897216 0.0060778874 0.7179840000 0.0804240000 0.0571340000 0.0310120000 0.2681220000 0.2774810000 141606947 0 402718720 3.9372286797 4.1677565575 3.8485376835 1638 1311867225.0798690319 0.1002608538 0.0875741322 0.1207897216 0.0060791391 0.4314780000 0.0790340000 0.0758760000 0.0000010000 0.2708720000 0.0017920000 141610619 0 402718720 3.9373970032 4.1673521996 3.8491311073 1639 1311867225.1138188839 0.1009069309 0.0875822670 0.1207897216 0.0060789456 0.4635860000 0.0805860000 0.0627330000 0.0313760000 0.2821950000 0.0024350000 141614291 0 402718720 3.9370832443 4.1704535484 3.8497679234 1640 1311867225.1472380161 0.1013330817 0.0875906516 0.1207897216 0.0060772129 0.4780780000 0.1031500000 0.0924280000 0.0000000000 0.2768680000 0.0017880000 141617963 0 402718720 3.9363663197 4.1730656624 3.8502092361 1641 1311867225.1810939312 0.1016532630 0.0875992211 0.1207897216 0.0060753860 0.7644100000 0.1119980000 0.0648650000 0.0314610000 0.2719280000 0.2801270000 141621747 0 402718720 3.9357202053 4.1749739647 3.8503959179 1642 1311867225.2153220177 0.1017052755 0.0876078119 0.1207897216 0.0060736694 0.4571320000 0.0810470000 0.0966450000 0.0000010000 0.2738270000 0.0017880000 141625475 0 402718720 3.9357898235 4.1755962372 3.8507988453 1643 1311867225.2483470440 0.1020087600 0.0876165769 0.1207897216 0.0060727885 0.4523600000 0.0810940000 0.0598390000 0.0314450000 0.2743820000 0.0017950000 141629147 0 402718720 3.9351170063 4.1775660515 3.8508412838 1644 1311867225.2792909145 0.1010643318 0.0876247568 0.1207897216 0.0060724854 0.4388860000 0.0814980000 0.0770530000 0.0000000000 0.2746660000 0.0017880000 141632819 0 402718720 3.9363620281 4.1796832085 3.8510472775 1645 1311867225.3207540512 0.0997315571 0.0876321166 0.1207897216 0.0060714198 0.7257520000 0.0791610000 0.0533570000 0.0312750000 0.2749410000 0.2832510000 141636771 0 402718720 3.9381890297 4.1798381805 3.8509736061 1646 1311867225.3462350368 0.0994994193 0.0876393264 0.1207897216 0.0060701679 0.4402020000 0.0913460000 0.0693770000 0.0000010000 0.2738440000 0.0017840000 141640275 0 402718720 3.9385766983 4.1814904213 3.8509488106 1647 1311867225.3852069378 0.1004134491 0.0876470824 0.1207897216 0.0060684471 0.4602120000 0.0807170000 0.0690480000 0.0314270000 0.2733890000 0.0017920000 141644115 0 402718720 3.9369053841 4.1839389801 3.8509347439 1648 1311867225.4130129814 0.1001439393 0.0876546654 0.1207897216 0.0060666190 0.4461190000 0.0806970000 0.0886980000 0.0000010000 0.2708180000 0.0018860000 141647619 0 402718720 3.9370880127 4.1848263741 3.8509449959 1649 1311867225.4504270554 0.0996938199 0.0876619663 0.1207897216 0.0060650022 0.7724280000 0.0935240000 0.0917450000 0.0309850000 0.2722520000 0.2800730000 141651515 0 402718720 3.9370496273 4.1858220100 3.8504765034 1650 1311867225.4842948914 0.1002595350 0.0876696012 0.1207897216 0.0060638976 0.4700010000 0.0915830000 0.0913700000 0.0000010000 0.2803050000 0.0024240000 141655187 0 402718720 3.9358108044 4.1875958443 3.8501679897 1651 1311867225.5163919926 0.0995524079 0.0876767985 0.1207897216 0.0060627872 0.5555000000 0.1023450000 0.1221160000 0.0383680000 0.2859420000 0.0024190000 141658915 0 402718720 3.9365775585 4.1873397827 3.8498518467 1652 1311867225.5493750572 0.0993947983 0.0876838918 0.1207897216 0.0060644070 0.4532550000 0.1019820000 0.0717380000 0.0000010000 0.2739050000 0.0017870000 141662531 0 402718720 3.9365549088 4.1902599335 3.8493838310 1653 1311867225.5882349014 0.1006386355 0.0876917289 0.1207897216 0.0060631808 0.7153620000 0.0797860000 0.0462950000 0.0314620000 0.2730430000 0.2808830000 141666371 0 402718720 3.9330732822 4.1931385994 3.8483841419 1654 1311867225.6179010868 0.1007149965 0.0876996027 0.1207897216 0.0060625074 0.4054550000 0.0797470000 0.0463380000 0.0000010000 0.2737290000 0.0017910000 141669987 0 402718720 3.9323287010 4.1919212341 3.8474462032 1655 1311867225.6461288929 0.1006056443 0.0877074009 0.1207897216 0.0060611118 0.4834220000 0.0797090000 0.0915520000 0.0314680000 0.2750400000 0.0017890000 141673547 0 402718720 3.9312283993 4.1923375130 3.8458735943 1656 1311867225.6847119331 0.1017509252 0.0877158813 0.1207897216 0.0060595173 0.4430020000 0.0913290000 0.0717870000 0.0000010000 0.2739300000 0.0018630000 141677443 0 402718720 3.9286808968 4.1951894760 3.8450887203 1657 1311867225.7160770893 0.1006026044 0.0877236584 0.1207897216 0.0060590250 0.7208740000 0.0768970000 0.0477300000 0.0308480000 0.2756230000 0.2859170000 141681115 0 402718720 3.9297604561 4.1960763931 3.8439831734 1658 1311867225.7506299019 0.1019139737 0.0877322171 0.1207897216 0.0060616719 0.4242960000 0.0789080000 0.0606350000 0.0000010000 0.2791070000 0.0017760000 141684843 0 402718720 3.9274919033 4.1975460052 3.8428435326 1659 1311867225.7872900963 0.1023850963 0.0877410495 0.1207897216 0.0060634719 0.4405650000 0.0781100000 0.0453820000 0.0314440000 0.2799750000 0.0017710000 141688571 0 402718720 3.9275689125 4.2027616501 3.8422348499 1660 1311867225.8170781136 0.1027321965 0.0877500803 0.1207897216 0.0060649504 0.4096040000 0.0784880000 0.0455230000 0.0000010000 0.2799380000 0.0017740000 141692131 0 402718720 3.9247045517 4.2019410133 3.8407292366 1661 1311867225.8520019054 0.1035034209 0.0877595645 0.1207897216 0.0060684463 0.7397410000 0.0882650000 0.0476490000 0.0314360000 0.2787730000 0.2897470000 141695971 0 402718720 3.9230709076 4.2028923035 3.8399598598 1662 1311867225.8862910271 0.1044131219 0.0877695847 0.1207897216 0.0060706081 0.4563510000 0.0781330000 0.0941660000 0.0000000000 0.2781250000 0.0018460000 141699699 0 402718720 3.9222180843 4.2053461075 3.8397226334 1663 1311867225.9177930355 0.1043065041 0.0877795287 0.1207897216 0.0060688823 0.4568570000 0.0782440000 0.0636770000 0.0310490000 0.2779760000 0.0018610000 141703315 0 402718720 3.9219682217 4.2064571381 3.8391630650 1664 1311867225.9504909515 0.1021767184 0.0877881809 0.1207897216 0.0060703413 0.4343420000 0.0787950000 0.0715720000 0.0000000000 0.2780030000 0.0018790000 141707043 0 402718720 3.9236829281 4.2058787346 3.8382167816 1665 1311867225.9852480888 0.1023984924 0.0877969559 0.1207897216 0.0060696390 0.7523200000 0.0782650000 0.0709080000 0.0311160000 0.2788320000 0.2892780000 141710827 0 402718720 3.9238889217 4.2076492310 3.8381373882 1666 1311867226.0173718929 0.1021849066 0.0878055921 0.1207897216 0.0060681418 0.4345840000 0.0950260000 0.0554590000 0.0000010000 0.2781240000 0.0018730000 141714499 0 402718720 3.9235715866 4.2079057693 3.8372030258 1667 1311867226.0511479378 0.1032754406 0.0878148721 0.1207897216 0.0060676191 0.4877640000 0.0777330000 0.0939550000 0.0310570000 0.2793400000 0.0017750000 141718171 0 402718720 3.9214575291 4.2103548050 3.8365285397 1668 1311867226.0877819061 0.1045450717 0.0878249022 0.1207897216 0.0060707972 0.4104610000 0.0782830000 0.0479770000 0.0000000000 0.2782650000 0.0018720000 141721955 0 402718720 3.9198372364 4.2142663002 3.8364450932 1669 1311867226.1182270050 0.1025222987 0.0878337083 0.1207897216 0.0060813117 0.7806120000 0.0782700000 0.0928180000 0.0314780000 0.2830100000 0.2911460000 141725627 0 402718720 3.9213755131 4.2121706009 3.8356070518 1670 1311867226.1477489471 0.1011753976 0.0878416974 0.1207897216 0.0060797723 0.4539820000 0.0783500000 0.0898100000 0.0000010000 0.2801320000 0.0017790000 141729187 0 402718720 3.9233214855 4.2139482498 3.8351740837 1671 1311867226.1833140850 0.1022991613 0.0878503494 0.1207897216 0.0060783362 0.4483190000 0.0779470000 0.0557330000 0.0310680000 0.2776140000 0.0018560000 141732971 0 402718720 3.9225013256 4.2175960541 3.8355388641 1672 1311867226.2166810036 0.1014109030 0.0878584597 0.1207897216 0.0060770830 0.4227600000 0.0764340000 0.0624950000 0.0000000000 0.2779280000 0.0018280000 141736643 0 402718720 3.9232656956 4.2170252800 3.8349783421 1673 1311867226.2487111092 0.1015773788 0.0878666599 0.1207897216 0.0060765992 0.7557380000 0.0969500000 0.0553810000 0.0315830000 0.2785480000 0.2893850000 141740371 0 402718720 3.9230780602 4.2194309235 3.8345527649 1674 1311867226.2829930782 0.1023784950 0.0878753289 0.1207897216 0.0060755512 0.4522040000 0.0780940000 0.0879060000 0.0000010000 0.2804730000 0.0017750000 141744099 0 402718720 3.9227106571 4.2211041451 3.8341667652 1675 1311867226.3211309910 0.1024768054 0.0878840462 0.1207897216 0.0060737495 0.4563290000 0.0780300000 0.0602450000 0.0314590000 0.2809030000 0.0017810000 141747995 0 402718720 3.9228835106 4.2224578857 3.8335554600 1676 1311867226.3455820084 0.1043227240 0.0878938545 0.1207897216 0.0060750241 0.4692190000 0.0894640000 0.0943650000 0.0000000000 0.2797050000 0.0017630000 141751387 0 402718720 3.9209337234 4.2264552116 3.8336646557 1677 1311867226.3873078823 0.1026370004 0.0879026459 0.1207897216 0.0060741973 0.7730910000 0.0779220000 0.0894890000 0.0314700000 0.2804600000 0.2898220000 141755395 0 402718720 3.9233145714 4.2275433540 3.8333601952 1678 1311867226.4188749790 0.1024177298 0.0879112961 0.1207897216 0.0060725439 0.4096020000 0.0780590000 0.0454650000 0.0000010000 0.2804080000 0.0017650000 141759011 0 402718720 3.9233486652 4.2296648026 3.8329665661 1679 1311867226.4472739697 0.1020954177 0.0879197440 0.1207897216 0.0060710599 0.4766960000 0.0781070000 0.0829090000 0.0314660000 0.2785490000 0.0017720000 141762627 0 402718720 3.9239327908 4.2308845520 3.8328263760 1680 1311867226.4849569798 0.1030182466 0.0879287312 0.1207897216 0.0060701877 0.4068710000 0.0767740000 0.0450440000 0.0000010000 0.2793820000 0.0017780000 141766411 0 402718720 3.9225466251 4.2323164940 3.8323221207 1681 1311867226.5167839527 0.1035063341 0.0879379981 0.1207897216 0.0060691767 0.7342550000 0.0791820000 0.0528750000 0.0314760000 0.2787790000 0.2880580000 141770027 0 402718720 3.9223427773 4.2343869209 3.8319907188 1682 1311867226.5462191105 0.1032313183 0.0879470905 0.1207897216 0.0060684335 0.4527210000 0.0785460000 0.0896920000 0.0000000000 0.2788080000 0.0017770000 141773643 0 402718720 3.9213066101 4.2335624695 3.8309218884 1683 1311867226.5842289925 0.1025175080 0.0879557479 0.1207897216 0.0060677076 0.4560410000 0.0785180000 0.0635570000 0.0315280000 0.2764680000 0.0018540000 141777483 0 402718720 3.9231448174 4.2367911339 3.8310551643 1684 1311867226.6149599552 0.1035807356 0.0879650264 0.1207897216 0.0060659661 0.4429860000 0.0979970000 0.0605430000 0.0000000000 0.2787410000 0.0017770000 141781099 0 402718720 3.9213776588 4.2379684448 3.8307754993 1685 1311867226.6545290947 0.1030891016 0.0879740021 0.1207897216 0.0060644984 0.7722200000 0.0788990000 0.0946830000 0.0315240000 0.2769570000 0.2860230000 141784995 0 402718720 3.9217724800 4.2380251884 3.8301913738 1686 1311867226.6802148819 0.1026132032 0.0879826849 0.1207897216 0.0060634931 0.4276850000 0.0886790000 0.0556470000 0.0000010000 0.2773100000 0.0018620000 141788499 0 402718720 3.9222009182 4.2392625809 3.8300099373 1687 1311867226.7142350674 0.1029912904 0.0879915815 0.1207897216 0.0060628196 0.4591790000 0.0792120000 0.0637210000 0.0315390000 0.2790060000 0.0017810000 141792227 0 402718720 3.9226326942 4.2402682304 3.8295738697 1688 1311867226.7506589890 0.1032809243 0.0880006392 0.1207897216 0.0060645044 0.4553980000 0.0788820000 0.0902480000 0.0000000000 0.2805430000 0.0017830000 141796011 0 402718720 3.9215214252 4.2393255234 3.8289470673 1689 1311867226.7818078995 0.1023460627 0.0880091326 0.1207897216 0.0060637675 0.7496900000 0.0768510000 0.0681440000 0.0315080000 0.2800340000 0.2891740000 141799683 0 402718720 3.9235551357 4.2419500351 3.8287789822 1690 1311867226.8133080006 0.1026369929 0.0880177881 0.1207897216 0.0060639299 0.4570300000 0.0791100000 0.0903700000 0.0000010000 0.2818220000 0.0017780000 141803299 0 402718720 3.9234037399 4.2448201180 3.8287391663 1691 1311867226.8513610363 0.1014201790 0.0880257139 0.1207897216 0.0060626882 0.5085600000 0.0929130000 0.0951200000 0.0315160000 0.2832630000 0.0017780000 141807139 0 402718720 3.9244015217 4.2439589500 3.8280344009 1692 1311867226.8838679790 0.1020612940 0.0880340091 0.1207897216 0.0060661643 0.4201470000 0.0775500000 0.0550620000 0.0000000000 0.2815890000 0.0018410000 141810811 0 402718720 3.9228825569 4.2441654205 3.8275439739 1693 1311867226.9181559086 0.1017928049 0.0880421360 0.1207897216 0.0060647794 0.7521300000 0.0785780000 0.0635240000 0.0314990000 0.2823410000 0.2919410000 141814539 0 402718720 3.9236025810 4.2460536957 3.8273448944 1694 1311867226.9514899254 0.1028273106 0.0880508640 0.1207897216 0.0060633863 0.4791400000 0.0951450000 0.0946670000 0.0000000000 0.2833090000 0.0018750000 141818267 0 402718720 3.9214103222 4.2454366684 3.8266794682 1695 1311867226.9810149670 0.1021940634 0.0880592080 0.1207897216 0.0060617269 0.4551480000 0.0789910000 0.0528860000 0.0315230000 0.2857920000 0.0019090000 141821939 0 402718720 3.9225151539 4.2472581863 3.8263754845 1696 1311867227.0125620365 0.1011597216 0.0880669324 0.1207897216 0.0060605505 0.4463490000 0.0912720000 0.0637450000 0.0000010000 0.2853030000 0.0018760000 141825499 0 402718720 3.9242038727 4.2495779991 3.8260886669 1697 1311867227.0480670929 0.1014688462 0.0880748298 0.1207897216 0.0060620771 0.7625400000 0.0793920000 0.0634340000 0.0311680000 0.2866760000 0.2978970000 141829339 0 402718720 3.9230146408 4.2500247955 3.8254868984 1698 1311867227.0861930847 0.1025407985 0.0880833492 0.1207897216 0.0060642488 0.4788780000 0.0922980000 0.0901250000 0.0000010000 0.2896880000 0.0024080000 141833011 0 402718720 3.9211838245 4.2518329620 3.8256871700 1699 1311867227.1158189774 0.1019576937 0.0880915154 0.1207897216 0.0060639409 0.5218780000 0.1023720000 0.0714500000 0.0385940000 0.3026550000 0.0024260000 141836571 0 402718720 3.9229438305 4.2546601295 3.8260872364 1700 1311867227.1503999233 0.1026438251 0.0881000756 0.1207897216 0.0060659319 0.4830910000 0.1019790000 0.0712050000 0.0000010000 0.3030990000 0.0024180000 141840355 0 402718720 3.9216551781 4.2547087669 3.8263792992 1701 1311867227.1841590405 0.1027368754 0.0881086804 0.1207897216 0.0060644137 0.8289150000 0.1017350000 0.0710140000 0.0385670000 0.3016360000 0.3116020000 141844083 0 402718720 3.9215288162 4.2576031685 3.8265938759 1702 1311867227.2148449421 0.1035123914 0.0881177308 0.1207897216 0.0060629659 0.4682650000 0.0803140000 0.0956960000 0.0000010000 0.2864820000 0.0017850000 141847643 0 402718720 3.9208383560 4.2591066360 3.8269412518 1703 1311867227.2480258942 0.1032865345 0.0881266379 0.1207897216 0.0060630006 0.4583860000 0.0804970000 0.0534620000 0.0315230000 0.2871250000 0.0017960000 141851371 0 402718720 3.9205446243 4.2584147453 3.8268206120 1704 1311867227.2819800377 0.1035416275 0.0881356842 0.1207897216 0.0060651077 0.4416680000 0.0805010000 0.0684060000 0.0000000000 0.2869810000 0.0017990000 141855099 0 402718720 3.9205574989 4.2609872818 3.8272986412 1705 1311867227.3152499199 0.1028918177 0.0881443389 0.1207897216 0.0060644982 0.7909440000 0.0801730000 0.0953810000 0.0315310000 0.2846630000 0.2952960000 141858827 0 402718720 3.9207475185 4.2606840134 3.8272020817 1706 1311867227.3479840755 0.1038659289 0.0881535543 0.1207897216 0.0060633351 0.4396320000 0.0933990000 0.0534360000 0.0000010000 0.2871120000 0.0017880000 141862499 0 402718720 3.9194073677 4.2635583878 3.8276255131 1707 1311867227.3841071129 0.1030766889 0.0881622966 0.1207897216 0.0060662799 0.4946810000 0.0799170000 0.0934330000 0.0315880000 0.2837950000 0.0018740000 141866283 0 402718720 3.9196248055 4.2631769180 3.8276088238 1708 1311867227.4141440392 0.1031750292 0.0881710863 0.1207897216 0.0060688464 0.4334660000 0.0803230000 0.0610260000 0.0000010000 0.2864320000 0.0017840000 141869899 0 402718720 3.9190366268 4.2642822266 3.8275735378 1709 1311867227.4479200840 0.1036764458 0.0881801591 0.1207897216 0.0060706030 0.8007820000 0.0919460000 0.0908490000 0.0315070000 0.2865610000 0.2960140000 141873627 0 402718720 3.9184308052 4.2665276527 3.8278484344 1710 1311867227.4818758965 0.1032219008 0.0881889554 0.1207897216 0.0060695633 0.4331540000 0.0798150000 0.0607950000 0.0000010000 0.2868350000 0.0017870000 141877411 0 402718720 3.9186375141 4.2655181885 3.8276231289 1711 1311867227.5169329643 0.1036946252 0.0881980177 0.1207897216 0.0060684328 0.5074850000 0.0899190000 0.0952790000 0.0315070000 0.2850740000 0.0017890000 141881083 0 402718720 3.9173810482 4.2659950256 3.8273012638 1712 1311867227.5501220226 0.1046453714 0.0882076248 0.1207897216 0.0060671746 0.4324890000 0.0797620000 0.0604470000 0.0000000000 0.2866130000 0.0017850000 141884811 0 402718720 3.9155168533 4.2668900490 3.8271660805 1713 1311867227.5819540024 0.1045049429 0.0882171387 0.1207897216 0.0060655620 0.7455860000 0.0800440000 0.0481180000 0.0315560000 0.2859090000 0.2960760000 141888539 0 402718720 3.9158432484 4.2679195404 3.8272554874 1714 1311867227.6162750721 0.1041569412 0.0882264385 0.1207897216 0.0060670366 0.4623970000 0.0798860000 0.0902140000 0.0000010000 0.2866250000 0.0017830000 141892211 0 402718720 3.9165115356 4.2692203522 3.8275401592 1715 1311867227.6503078938 0.1043911055 0.0882358640 0.1207897216 0.0060802489 0.4491240000 0.0796790000 0.0456790000 0.0315050000 0.2865900000 0.0017850000 141895995 0 402718720 3.9157676697 4.2698569298 3.8276033401 1716 1311867227.6823980808 0.1049374640 0.0882455968 0.1207897216 0.0060785880 0.4522930000 0.1062950000 0.0561010000 0.0000010000 0.2838960000 0.0018800000 141899667 0 402718720 3.9142901897 4.2686300278 3.8274707794 1717 1311867227.7135930061 0.1045707241 0.0882551048 0.1207897216 0.0060790191 0.7870280000 0.0797820000 0.0905810000 0.0314950000 0.2858140000 0.2954530000 141903227 0 402718720 3.9156343937 4.2714667320 3.8280732632 1718 1311867227.7496368885 0.1041117162 0.0882643345 0.1207897216 0.0060773294 0.4269950000 0.0801480000 0.0562780000 0.0000000000 0.2848210000 0.0017880000 141907067 0 402718720 3.9164440632 4.2725095749 3.8285760880 1719 1311867227.7827620506 0.1043069214 0.0882736670 0.1207897216 0.0060757703 0.4614690000 0.0917000000 0.0458160000 0.0311060000 0.2871270000 0.0017950000 141910795 0 402718720 3.9155528545 4.2729954720 3.8284404278 1720 1311867227.8141551018 0.1041250303 0.0882828829 0.1207897216 0.0060756805 0.4644600000 0.0805350000 0.0910380000 0.0000010000 0.2871710000 0.0017900000 141914411 0 402718720 3.9169063568 4.2749552727 3.8292582035 1721 1311867227.8497691154 0.1041550413 0.0882921055 0.1207897216 0.0060771250 0.7597720000 0.0942360000 0.0462510000 0.0314730000 0.2871530000 0.2967200000 141918195 0 402718720 3.9172728062 4.2761564255 3.8298995495 1722 1311867227.8832869530 0.1029046476 0.0883005913 0.1207897216 0.0060756913 0.4690720000 0.0813270000 0.0963310000 0.0000010000 0.2853970000 0.0018970000 141921867 0 402718720 3.9200627804 4.2770504951 3.8305420876 1723 1311867227.9196939468 0.1030470654 0.0883091499 0.1207897216 0.0060740625 0.4905620000 0.0811070000 0.0877310000 0.0311690000 0.2845010000 0.0018940000 141925707 0 402718720 3.9204690456 4.2777156830 3.8307843208 1724 1311867227.9516780376 0.1030503437 0.0883177005 0.1207897216 0.0060732240 0.4304080000 0.0812580000 0.0566270000 0.0000000000 0.2868090000 0.0017960000 141929379 0 402718720 3.9212269783 4.2796320915 3.8308198452 1725 1311867227.9828588963 0.1049560159 0.0883273459 0.1207897216 0.0060719740 0.7885360000 0.0815940000 0.0919910000 0.0315360000 0.2850780000 0.2944270000 141933051 0 402718720 3.9190535545 4.2808070183 3.8313744068 1726 1311867228.0181910992 0.1060348898 0.0883376052 0.1207897216 0.0060705591 0.5045490000 0.1213460000 0.0919770000 0.0000000000 0.2854740000 0.0017960000 141936779 0 402718720 3.9178929329 4.2823009491 3.8316545486 1727 1311867228.0516328812 0.1057149097 0.0883476673 0.1207897216 0.0060689866 0.5040960000 0.0946940000 0.0888680000 0.0314800000 0.2833060000 0.0017960000 141940507 0 402718720 3.9193723202 4.2841634750 3.8320076466 1728 1311867228.0825328827 0.1054778397 0.0883575806 0.1207897216 0.0060675436 0.4350020000 0.0824380000 0.0621980000 0.0000010000 0.2846440000 0.0018020000 141944123 0 402718720 3.9203581810 4.2851848602 3.8323974609 1729 1311867228.1179840565 0.1050204858 0.0883672179 0.1207897216 0.0060665723 0.7878370000 0.0821780000 0.0971300000 0.0315170000 0.2817380000 0.2911390000 141947851 0 402718720 3.9214179516 4.2860507965 3.8323554993 1730 1311867228.1511390209 0.1052954122 0.0883770030 0.1207897216 0.0060662005 0.4193190000 0.0819780000 0.0491650000 0.0000010000 0.2820960000 0.0018980000 141951635 0 402718720 3.9225635529 4.2879261971 3.8329343796 1731 1311867228.1828610897 0.1050469801 0.0883866333 0.1207897216 0.0060645515 0.5072090000 0.0946960000 0.0919150000 0.0313230000 0.2835310000 0.0017620000 141955307 0 402718720 3.9236466885 4.2890944481 3.8328964710 1732 1311867228.2179419994 0.1051723212 0.0883963248 0.1207897216 0.0060696983 0.4195300000 0.0821110000 0.0491810000 0.0000010000 0.2824850000 0.0018020000 141958979 0 402718720 3.9243924618 4.2896580696 3.8330104351 1733 1311867228.2541251183 0.1057099849 0.0884063154 0.1207897216 0.0060757359 0.7505770000 0.0931770000 0.0466330000 0.0314470000 0.2831290000 0.2922430000 141962819 0 402718720 3.9237897396 4.2906322479 3.8325984478 1734 1311867228.2826519012 0.1063374206 0.0884166562 0.1207897216 0.0060740725 0.4631580000 0.0817990000 0.0921610000 0.0000000000 0.2834300000 0.0017880000 141966379 0 402718720 3.9228317738 4.2919774055 3.8325273991 1735 1311867228.3181738853 0.1068886593 0.0884273029 0.1207897216 0.0060728490 0.4492710000 0.0822030000 0.0467160000 0.0310620000 0.2834810000 0.0018070000 141970163 0 402718720 3.9221453667 4.2922873497 3.8325104713 1736 1311867228.3504519463 0.1074660793 0.0884382700 0.1207897216 0.0060712950 0.4406240000 0.0966470000 0.0567580000 0.0000000000 0.2811390000 0.0018980000 141973835 0 402718720 3.9218349457 4.2940807343 3.8326306343 1737 1311867228.3824779987 0.1070788130 0.0884490014 0.1207897216 0.0060697150 0.7430490000 0.0824520000 0.0493130000 0.0314760000 0.2833270000 0.2925250000 141977563 0 402718720 3.9229471684 4.2954506874 3.8327212334 1738 1311867228.4176759720 0.1067265645 0.0884595179 0.1207897216 0.0060681311 0.4337470000 0.0821690000 0.0618640000 0.0000000000 0.2839430000 0.0018050000 141981235 0 402718720 3.9234364033 4.2954425812 3.8326530457 1739 1311867228.4483039379 0.1062031984 0.0884697212 0.1207897216 0.0060674271 0.4992120000 0.0822180000 0.0967290000 0.0314760000 0.2830010000 0.0018080000 141984907 0 402718720 3.9242286682 4.2962021828 3.8326025009 1740 1311867228.4835319519 0.1061664894 0.0884798918 0.1207897216 0.0060658990 0.4313750000 0.0953800000 0.0466230000 0.0000010000 0.2836080000 0.0018000000 141988635 0 402718720 3.9243197441 4.2959580421 3.8324832916 1741 1311867228.5177900791 0.1072060838 0.0884906478 0.1207897216 0.0060667675 0.8001730000 0.0934860000 0.0964260000 0.0315000000 0.2827780000 0.2920000000 141992363 0 402718720 3.9231674671 4.2957563400 3.8325958252 1742 1311867228.5529639721 0.1074455678 0.0885015289 0.1207897216 0.0060651857 0.4288330000 0.0936530000 0.0467540000 0.0000010000 0.2826640000 0.0017990000 141996147 0 402718720 3.9221639633 4.2946467400 3.8319385052 1743 1311867228.5834119320 0.1078910455 0.0885126531 0.1207897216 0.0060634688 0.4493280000 0.0824410000 0.0493550000 0.0315670000 0.2798980000 0.0018980000 141999763 0 402718720 3.9215261936 4.2943944931 3.8316314220 1744 1311867228.6168839931 0.1079431772 0.0885237945 0.1207897216 0.0060622586 0.4325590000 0.0820870000 0.0656370000 0.0000000000 0.2787440000 0.0018930000 142003547 0 402718720 3.9211328030 4.2927289009 3.8311545849 1745 1311867228.6513540745 0.1072204709 0.0885345089 0.1207897216 0.0060609751 0.7459610000 0.0815750000 0.0653850000 0.0315070000 0.2771270000 0.2862160000 142007219 0 402718720 3.9215221405 4.2912259102 3.8302593231 1746 1311867228.6960909367 0.1074915007 0.0885453663 0.1207897216 0.0060592848 0.4391410000 0.0943840000 0.0624110000 0.0000010000 0.2765580000 0.0017930000 142011283 0 402718720 3.9209940434 4.2895317078 3.8295903206 1747 1311867228.7251129150 0.1083208770 0.0885566860 0.1207897216 0.0060581557 0.4388770000 0.0805350000 0.0468570000 0.0310400000 0.2746450000 0.0018020000 142014787 0 402718720 3.9177320004 4.2885084152 3.8285121918 1748 1311867228.7533209324 0.1083095819 0.0885679863 0.1207897216 0.0060566148 0.4560140000 0.1043930000 0.0729400000 0.0000010000 0.2728620000 0.0017980000 142018235 0 402718720 3.9177660942 4.2888221741 3.8281862736 1749 1311867228.7872729301 0.1075306013 0.0885788283 0.1207897216 0.0060627510 0.7352650000 0.0806060000 0.0649190000 0.0315140000 0.2724580000 0.2817490000 142021683 0 402718720 3.9182026386 4.2866921425 3.8276379108 1750 1311867228.8184990883 0.1085910797 0.0885902638 0.1207897216 0.0060666954 0.4203120000 0.0926050000 0.0467810000 0.0000010000 0.2751050000 0.0018020000 142025299 0 402718720 3.9163253307 4.2855834961 3.8268439770 1751 1311867228.8512189388 0.1081216708 0.0886014183 0.1207897216 0.0060652301 0.4529450000 0.0936560000 0.0467010000 0.0315250000 0.2752780000 0.0017980000 142029027 0 402718720 3.9160728455 4.2861447334 3.8264765739 1752 1311867228.8835051060 0.1082588807 0.0886126383 0.1207897216 0.0060638739 0.4096240000 0.0811120000 0.0492230000 0.0000010000 0.2731530000 0.0018950000 142032643 0 402718720 3.9156596661 4.2835268974 3.8259954453 1753 1311867228.9181449413 0.1080020443 0.0886236990 0.1207897216 0.0060621883 0.7531560000 0.0794920000 0.0806000000 0.0313550000 0.2742500000 0.2834670000 142036427 0 402718720 3.9157221317 4.2814288139 3.8251755238 1754 1311867228.9496490955 0.1081516370 0.0886348324 0.1207897216 0.0060607860 0.4539540000 0.0800580000 0.0914040000 0.0000010000 0.2766610000 0.0017850000 142040099 0 402718720 3.9150171280 4.2821674347 3.8244712353 1755 1311867228.9844760895 0.1082247347 0.0886459947 0.1207897216 0.0060594359 0.4481770000 0.0803200000 0.0541010000 0.0315000000 0.2764530000 0.0017950000 142043827 0 402718720 3.9145197868 4.2793841362 3.8240807056 1756 1311867229.0238449574 0.1078820825 0.0886569492 0.1207897216 0.0060580664 0.4697430000 0.0893410000 0.0973480000 0.0000010000 0.2772590000 0.0017890000 142047723 0 402718720 3.9146718979 4.2761516571 3.8233580589 1757 1311867229.0509281158 0.1087033525 0.0886683586 0.1207897216 0.0060570711 0.7844640000 0.0802250000 0.0917330000 0.0310760000 0.2780050000 0.2989880000 142051283 0 402718720 3.9131097794 4.2766685486 3.8228387833 1758 1311867229.0874319077 0.1086679175 0.0886797350 0.1207897216 0.0060560956 0.4722400000 0.1015270000 0.0717060000 0.0000010000 0.2921500000 0.0024140000 142055011 0 402718720 3.9130997658 4.2754330635 3.8226850033 1759 1311867229.1218080521 0.1082871929 0.0886908819 0.1207897216 0.0060547235 0.5617530000 0.1018750000 0.1220200000 0.0385820000 0.2924120000 0.0024190000 142058795 0 402718720 3.9135541916 4.2731223106 3.8224213123 1760 1311867229.1517140865 0.1087470651 0.0887022774 0.1207897216 0.0060547878 0.5239090000 0.1020830000 0.1218600000 0.0000010000 0.2931070000 0.0024130000 142062467 0 402718720 3.9123320580 4.2707171440 3.8219425678 1761 1311867229.1890540123 0.1090422496 0.0887138277 0.1207897216 0.0060539331 0.7446610000 0.0883770000 0.0536110000 0.0315440000 0.2789670000 0.2881890000 142066251 0 402718720 3.9121181965 4.2701210976 3.8217298985 1762 1311867229.2214341164 0.1097430587 0.0887257625 0.1207897216 0.0060527112 0.4276240000 0.0797310000 0.0647100000 0.0000010000 0.2771140000 0.0018780000 142069923 0 402718720 3.9110624790 4.2677259445 3.8218536377 1763 1311867229.2532980442 0.1092022210 0.0887373771 0.1207897216 0.0060539869 0.4614990000 0.0797680000 0.0642890000 0.0314600000 0.2802200000 0.0017980000 142073595 0 402718720 3.9115850925 4.2654027939 3.8211710453 1764 1311867229.2841351032 0.1082339659 0.0887484296 0.1207897216 0.0060524483 0.4539040000 0.0772290000 0.0895780000 0.0000010000 0.2812590000 0.0017850000 142077211 0 402718720 3.9131419659 4.2645587921 3.8208293915 1765 1311867229.3193020821 0.1091605425 0.0887599945 0.1207897216 0.0060536702 0.7419750000 0.0896920000 0.0455490000 0.0310780000 0.2810460000 0.2905940000 142080995 0 402718720 3.9110798836 4.2626123428 3.8202421665 1766 1311867229.3502240181 0.1086637527 0.0887712651 0.1207897216 0.0060537513 0.4521940000 0.0885130000 0.0761460000 0.0000000000 0.2817580000 0.0017710000 142084611 0 402718720 3.9117474556 4.2598481178 3.8196308613 1767 1311867229.3850710392 0.1083278880 0.0887823328 0.1207897216 0.0060525999 0.4922580000 0.0788640000 0.0957350000 0.0315460000 0.2799670000 0.0018740000 142088339 0 402718720 3.9119818211 4.2582268715 3.8188846111 1768 1311867229.4180469513 0.1089697033 0.0887937510 0.1207897216 0.0060523921 0.4295000000 0.0787910000 0.0639940000 0.0000010000 0.2808780000 0.0017810000 142092011 0 402718720 3.9113562107 4.2571754456 3.8186709881 1769 1311867229.4483740330 0.1076800078 0.0888044272 0.1207897216 0.0060513258 0.7786890000 0.0784840000 0.0905130000 0.0315220000 0.2822020000 0.2919170000 142095627 0 402718720 3.9125018120 4.2539949417 3.8179609776 1770 1311867229.4843358994 0.1070029587 0.0888147088 0.1207897216 0.0060555685 0.4498210000 0.0986650000 0.0638250000 0.0000000000 0.2814480000 0.0017810000 142099411 0 402718720 3.9131145477 4.2512812614 3.8171765804 1771 1311867229.5189929008 0.1074823961 0.0888252496 0.1207897216 0.0060543804 0.4920690000 0.0785020000 0.0951290000 0.0315580000 0.2807530000 0.0018720000 142103083 0 402718720 3.9117839336 4.2490444183 3.8162155151 1772 1311867229.5504579544 0.1084939018 0.0888363493 0.1207897216 0.0060528834 0.4145620000 0.0786730000 0.0458190000 0.0000010000 0.2842460000 0.0017860000 142106755 0 402718720 3.9093720913 4.2462058067 3.8154244423 1773 1311867229.5853381157 0.1077145413 0.0888469969 0.1207897216 0.0060521728 0.7592200000 0.0774870000 0.0709810000 0.0311230000 0.2826610000 0.2927230000 142110483 0 402718720 3.9101378918 4.2458763123 3.8147799969 1774 1311867229.6182799339 0.1078178734 0.0888576907 0.1207897216 0.0060505406 0.4608910000 0.0775480000 0.0942680000 0.0000000000 0.2829480000 0.0018600000 142114155 0 402718720 3.9094922543 4.2435193062 3.8143587112 1775 1311867229.6503160000 0.1073792577 0.0888681254 0.1207897216 0.0060488664 0.4699670000 0.0774770000 0.0710650000 0.0315690000 0.2840360000 0.0017680000 142117883 0 402718720 3.9101135731 4.2418270111 3.8141090870 1776 1311867229.6876978874 0.1085834205 0.0888792264 0.1207897216 0.0060476124 0.4775110000 0.0923870000 0.0935990000 0.0000010000 0.2856950000 0.0017700000 142121667 0 402718720 3.9083793163 4.2415776253 3.8139317036 1777 1311867229.7184219360 0.1087404341 0.0888904032 0.1207897216 0.0060476139 0.7870440000 0.0770690000 0.0935470000 0.0311140000 0.2846630000 0.2965820000 142125283 0 402718720 3.9078774452 4.2410769463 3.8134453297 1778 1311867229.7500000000 0.1071569249 0.0889006768 0.1207897216 0.0060465420 0.4492260000 0.0891100000 0.0670330000 0.0000010000 0.2872450000 0.0017640000 142128955 0 402718720 3.9091510773 4.2376022339 3.8129944801 1779 1311867229.7854330540 0.1077398434 0.0889112666 0.1207897216 0.0060450483 0.4741840000 0.0753090000 0.0734200000 0.0315960000 0.2880320000 0.0017720000 142132739 0 402718720 3.9085364342 4.2372546196 3.8124618530 1780 1311867229.8184831142 0.1078687683 0.0889219169 0.1207897216 0.0060433740 0.4226180000 0.0764430000 0.0520060000 0.0000000000 0.2883110000 0.0017590000 142136411 0 402718720 3.9083399773 4.2355699539 3.8121275902 1781 1311867229.8494279385 0.1086149439 0.0889329741 0.1207897216 0.0060419749 0.8170330000 0.1033150000 0.0933980000 0.0311590000 0.2870580000 0.2978830000 142140083 0 402718720 3.9065005779 4.2334151268 3.8115296364 1782 1311867229.8853340149 0.1079779640 0.0889436616 0.1207897216 0.0060404493 0.4501440000 0.0765320000 0.0780230000 0.0000010000 0.2897470000 0.0017610000 142143867 0 402718720 3.9071061611 4.2314462662 3.8109519482 1783 1311867229.9183139801 0.1084084287 0.0889545784 0.1207897216 0.0060394858 0.4588180000 0.0762210000 0.0518100000 0.0315620000 0.2933590000 0.0017660000 142147539 0 402718720 3.9059698582 4.2308778763 3.8100206852 1784 1311867229.9534161091 0.1083583385 0.0889654550 0.1207897216 0.0060404097 0.4259450000 0.0747550000 0.0514490000 0.0000000000 0.2939460000 0.0017220000 142151323 0 402718720 3.9056818485 4.2279467583 3.8095304966 1785 1311867229.9877750874 0.1093425155 0.0889768707 0.1207897216 0.0060389430 0.7686670000 0.0759310000 0.0518720000 0.0315080000 0.2968570000 0.3083870000 142155107 0 402718720 3.9038600922 4.2265067101 3.8089406490 1786 1311867230.0194880962 0.1103195027 0.0889888207 0.1207897216 0.0060376543 0.4412470000 0.0852680000 0.0524710000 0.0000000000 0.2976620000 0.0017550000 142158723 0 402718720 3.9025259018 4.2257637978 3.8083283901 1787 1311867230.0512609482 0.1097010970 0.0890004112 0.1207897216 0.0060361622 0.5009340000 0.0755760000 0.0873560000 0.0315900000 0.3005550000 0.0017640000 142162451 0 402718720 3.9035382271 4.2243413925 3.8080375195 1788 1311867230.0876040459 0.1102403924 0.0890122904 0.1207897216 0.0060345992 0.4735040000 0.0755860000 0.0923720000 0.0000010000 0.2994310000 0.0018610000 142166123 0 402718720 3.9016525745 4.2216477394 3.8069844246 1789 1311867230.1212029457 0.1097135469 0.0890238618 0.1207897216 0.0060329515 0.7921350000 0.0885540000 0.0540580000 0.0311800000 0.3007190000 0.3133620000 142169963 0 402718720 3.9016687870 4.2195496559 3.8061037064 1790 1311867230.1508131027 0.1083139256 0.0890346384 0.1207897216 0.0060315422 0.4706560000 0.0742810000 0.0866020000 0.0000000000 0.3039500000 0.0017390000 142173523 0 402718720 3.9042425156 4.2186651230 3.8058428764 1791 1311867230.1872301102 0.1090399548 0.0890458083 0.1207897216 0.0060340448 0.4719530000 0.0868060000 0.0440110000 0.0310990000 0.3041650000 0.0017570000 142177307 0 402718720 3.9021658897 4.2175736427 3.8051810265 1792 1311867230.2194790840 0.1098453924 0.0890574152 0.1207897216 0.0060402443 0.4369260000 0.0746870000 0.0534630000 0.0000010000 0.3029050000 0.0017490000 142180979 0 402718720 3.9017002583 4.2155728340 3.8046562672 1793 1311867230.2494208813 0.1090461314 0.0890685634 0.1207897216 0.0060447762 0.8201860000 0.0740710000 0.0905650000 0.0315840000 0.3029200000 0.3169570000 142184595 0 402718720 3.9021532536 4.2153010368 3.8039338589 1794 1311867230.2894790173 0.1114731133 0.0890810520 0.1207897216 0.0060502393 0.4552710000 0.0853700000 0.0579170000 0.0000000000 0.3061040000 0.0017510000 142188491 0 402718720 3.8990168571 4.2141857147 3.8030664921 1795 1311867230.3189430237 0.1117240414 0.0890936665 0.1207897216 0.0060486007 0.5069560000 0.0743660000 0.0907520000 0.0316860000 0.3042850000 0.0017570000 142192051 0 402718720 3.8983759880 4.2123975754 3.8023452759 1796 1311867230.3552010059 0.1102876514 0.0891054671 0.1207897216 0.0060475223 0.4675400000 0.0891440000 0.0679600000 0.0000010000 0.3043110000 0.0018310000 142195891 0 402718720 3.9002025127 4.2104988098 3.8015005589 1797 1311867230.3913140297 0.1108237579 0.0891175530 0.1207897216 0.0060460547 0.7903770000 0.0742980000 0.0458500000 0.0312080000 0.3052840000 0.3292040000 142199619 0 402718720 3.8996357918 4.2099070549 3.8011660576 1798 1311867230.4169929028 0.1117855161 0.0891301603 0.1207897216 0.0060447355 0.4688470000 0.0895630000 0.0647620000 0.0000000000 0.3085450000 0.0017510000 142203123 0 402718720 3.8977308273 4.2084026337 3.8003885746 1799 1311867230.4538938999 0.1115904003 0.0891426452 0.1207897216 0.0060431460 0.4612060000 0.0716820000 0.0426590000 0.0315130000 0.3094290000 0.0017430000 142206963 0 402718720 3.8972947598 4.2065629959 3.7994842529 1800 1311867230.4892110825 0.1111630127 0.0891548787 0.1207897216 0.0060517176 0.4299990000 0.0713780000 0.0425860000 0.0000010000 0.3101340000 0.0017120000 142210691 0 402718720 3.8966784477 4.2049341202 3.7988636494 1801 1311867230.5216429234 0.1105061695 0.0891667339 0.1207897216 0.0060506642 0.8426300000 0.0853610000 0.0867330000 0.0315580000 0.3104840000 0.3243630000 142214419 0 402718720 3.8976287842 4.2045383453 3.7986798286 1802 1311867230.5564150810 0.1122790650 0.0891795599 0.1207897216 0.0060621486 0.4923340000 0.0887110000 0.0892240000 0.0000010000 0.3082010000 0.0018380000 142218203 0 402718720 3.8956637383 4.2042665482 3.7982192039 1803 1311867230.5930590630 0.1110544056 0.0891916923 0.1207897216 0.0060609055 0.4706540000 0.0724830000 0.0523280000 0.0315850000 0.3080870000 0.0018100000 142221931 0 402718720 3.8975980282 4.2029132843 3.7979872227 1804 1311867230.6184151173 0.1110998467 0.0892038365 0.1207897216 0.0060594465 0.4401590000 0.0726350000 0.0524400000 0.0000000000 0.3091810000 0.0017370000 142225379 0 402718720 3.8963809013 4.2001409531 3.7970981598 1805 1311867230.6534399986 0.1125599518 0.0892167762 0.1207897216 0.0060579207 0.8330670000 0.0728250000 0.0567430000 0.0315800000 0.3261610000 0.3411830000 142229163 0 402718720 3.8939909935 4.1993680000 3.7968316078 1806 1311867230.6920781136 0.1115302965 0.0892291314 0.1207897216 0.0060572215 0.5075070000 0.0922140000 0.0934210000 0.0000010000 0.3160010000 0.0017400000 142233059 0 402718720 3.8956384659 4.1986007690 3.7967634201 1807 1311867230.7185189724 0.1117320508 0.0892415846 0.1207897216 0.0060556212 0.5099200000 0.0722480000 0.0884920000 0.0315840000 0.3117700000 0.0017410000 142236507 0 402718720 3.8946681023 4.1974482536 3.7961966991 1808 1311867230.7529120445 0.1112962067 0.0892537830 0.1207897216 0.0060544556 0.4478690000 0.0706560000 0.0559460000 0.0000000000 0.3153980000 0.0017230000 142240291 0 402718720 3.8950715065 4.1974263191 3.7959852219 1809 1311867230.7871611118 0.1113646924 0.0892660057 0.1207897216 0.0060614094 0.7958170000 0.0723960000 0.0428960000 0.0316690000 0.3150000000 0.3297540000 142244075 0 402718720 3.8927173615 4.1950125694 3.7954311371 1810 1311867230.8195741177 0.1107424423 0.0892778711 0.1207897216 0.0060668770 0.4755520000 0.0718580000 0.0818970000 0.0000000000 0.3158920000 0.0017240000 142247691 0 402718720 3.8947548866 4.1953234673 3.7957041264 1811 1311867230.8534181118 0.1108610556 0.0892897890 0.1207897216 0.0060654295 0.4603830000 0.0718820000 0.0373770000 0.0316390000 0.3135970000 0.0017350000 142251419 0 402718720 3.8946104050 4.1956734657 3.7958488464 1812 1311867230.8890159130 0.1106855869 0.0893015968 0.1207897216 0.0060639366 0.4629720000 0.0924070000 0.0493440000 0.0000010000 0.3153150000 0.0017250000 142255203 0 402718720 3.8942997456 4.1946921349 3.7956745625 1813 1311867230.9176509380 0.1107393503 0.0893134213 0.1207897216 0.0060623888 0.8003090000 0.0706120000 0.0490950000 0.0309780000 0.3155850000 0.3299200000 142258819 0 402718720 3.8939373493 4.1946139336 3.7955775261 1814 1311867230.9559168816 0.1107190102 0.0893252215 0.1207897216 0.0060609606 0.4721030000 0.0895950000 0.0650880000 0.0000010000 0.3115230000 0.0017260000 142262603 0 402718720 3.8935236931 4.1929039955 3.7955255508 1815 1311867230.9881010056 0.1115411147 0.0893374616 0.1207897216 0.0060598824 0.5087430000 0.0722470000 0.0847940000 0.0315870000 0.3137660000 0.0017340000 142266275 0 402718720 3.8923509121 4.1932067871 3.7952771187 1816 1311867231.0166280270 0.1115847379 0.0893497123 0.1207897216 0.0060585238 0.4756440000 0.0724280000 0.0843970000 0.0000010000 0.3129570000 0.0017290000 142269891 0 402718720 3.8917779922 4.1916046143 3.7949163914 1817 1311867231.0603969097 0.1103385687 0.0893612637 0.1207897216 0.0060578930 0.8128280000 0.0725410000 0.0635680000 0.0311880000 0.3135530000 0.3277990000 142273787 0 402718720 3.8935773373 4.1916031837 3.7946794033 1818 1311867231.0868620872 0.1116491854 0.0893735233 0.1207897216 0.0060567716 0.4803430000 0.0723810000 0.0886140000 0.0000000000 0.3134370000 0.0017300000 142277235 0 402718720 3.8906648159 4.1902055740 3.7938437462 1819 1311867231.1221020222 0.1114936993 0.0893856839 0.1207897216 0.0060555168 0.4869370000 0.0721070000 0.0643750000 0.0315260000 0.3130450000 0.0017300000 142281075 0 402718720 3.8906781673 4.1887860298 3.7935822010 1820 1311867231.1523799896 0.1121378541 0.0893981851 0.1207897216 0.0060586798 0.4568080000 0.0873120000 0.0526670000 0.0000000000 0.3109490000 0.0017230000 142284635 0 402718720 3.8884801865 4.1852097511 3.7925889492 1821 1311867231.1860070229 0.1117850170 0.0894104788 0.1207897216 0.0060573240 0.7994110000 0.0718170000 0.0519730000 0.0316010000 0.3123580000 0.3275370000 142288363 0 402718720 3.8891918659 4.1861090660 3.7921710014 1822 1311867231.2188270092 0.1121236980 0.0894229449 0.1207897216 0.0060565610 0.4774030000 0.0718620000 0.0836760000 0.0000000000 0.3159720000 0.0017170000 142292035 0 402718720 3.8883001804 4.1839380264 3.7917952538 1823 1311867231.2522621155 0.1122712269 0.0894354783 0.1207897216 0.0060569189 0.5253210000 0.0859610000 0.0841080000 0.0316450000 0.3177040000 0.0017310000 142295763 0 402718720 3.8873162270 4.1819391251 3.7911210060 1824 1311867231.2864110470 0.1137450337 0.0894488059 0.1207897216 0.0060568472 0.4528680000 0.0714930000 0.0557970000 0.0000000000 0.3196630000 0.0017220000 142299491 0 402718720 3.8849544525 4.1814742088 3.7901804447 1825 1311867231.3215939999 0.1140779778 0.0894623013 0.1207897216 0.0060555807 0.8699280000 0.0930240000 0.0871820000 0.0316330000 0.3176570000 0.3362730000 142303275 0 402718720 3.8842425346 4.1805491447 3.7900085449 1826 1311867231.3525509834 0.1134706065 0.0894754493 0.1207897216 0.0060540591 0.4834810000 0.0710920000 0.0875510000 0.0000010000 0.3186320000 0.0018110000 142306891 0 402718720 3.8843913078 4.1788463593 3.7895748615 1827 1311867231.3874650002 0.1129487604 0.0894882973 0.1207897216 0.0060524422 0.4720580000 0.0706450000 0.0439500000 0.0316270000 0.3199600000 0.0017180000 142310619 0 402718720 3.8847081661 4.1784362793 3.7891669273 1828 1311867231.4187040329 0.1132092923 0.0895012738 0.1207897216 0.0060508938 0.4790370000 0.0703490000 0.0826050000 0.0000010000 0.3198910000 0.0018050000 142314291 0 402718720 3.8839333057 4.1779503822 3.7890195847 1829 1311867231.4542400837 0.1129913107 0.0895141169 0.1207897216 0.0060493674 0.8520140000 0.0704950000 0.0823030000 0.0316450000 0.3234720000 0.3398850000 142318075 0 402718720 3.8836081028 4.1767892838 3.7890565395 1830 1311867231.4867990017 0.1134002358 0.0895271694 0.1207897216 0.0060477970 0.4758320000 0.0843950000 0.0644720000 0.0000010000 0.3207640000 0.0017770000 142321747 0 402718720 3.8823053837 4.1761693954 3.7890567780 1831 1311867231.5193030834 0.1130522937 0.0895400177 0.1207897216 0.0060462857 0.5140060000 0.0704490000 0.0865880000 0.0311260000 0.3195870000 0.0018020000 142325419 0 402718720 3.8826289177 4.1757793427 3.7892665863 1832 1311867231.5524148941 0.1126331761 0.0895526231 0.1207897216 0.0060452860 0.5081440000 0.0931760000 0.0864460000 0.0000010000 0.3225820000 0.0017120000 142329091 0 402718720 3.8826477528 4.1737947464 3.7891204357 1833 1311867231.5855851173 0.1120930314 0.0895649201 0.1207897216 0.0060488678 0.9265980000 0.0834430000 0.1084640000 0.0386910000 0.3373860000 0.3540180000 142332875 0 402718720 3.8826446533 4.1732993126 3.7892379761 1834 1311867231.6210820675 0.1119013950 0.0895770992 0.1207897216 0.0060565062 0.4814720000 0.0705380000 0.0822480000 0.0000010000 0.3227710000 0.0017080000 142336603 0 402718720 3.8837842941 4.1729846001 3.7891228199 1835 1311867231.6522169113 0.1129101142 0.0895898148 0.1207897216 0.0060549865 0.5034620000 0.0687720000 0.0748000000 0.0313680000 0.3225350000 0.0017130000 142340275 0 402718720 3.8816251755 4.1709294319 3.7886357307 1836 1311867231.6880500317 0.1130927205 0.0896026159 0.1207897216 0.0060534257 0.5419260000 0.0889600000 0.1089070000 0.0000000000 0.3371550000 0.0022790000 142344059 0 402718720 3.8815264702 4.1709175110 3.7885439396 1837 1311867231.7208089828 0.1128806248 0.0896152877 0.1207897216 0.0060521714 0.9231660000 0.0895840000 0.0999370000 0.0386860000 0.3370140000 0.3533110000 142347787 0 402718720 3.8818628788 4.1703300476 3.7882189751 1838 1311867231.7523078918 0.1122132987 0.0896275826 0.1207897216 0.0060533662 0.5259510000 0.0895380000 0.1066130000 0.0000010000 0.3239020000 0.0017060000 142351347 0 402718720 3.8826963902 4.1691303253 3.7876777649 1839 1311867231.7860589027 0.1122700945 0.0896398950 0.1207897216 0.0060518228 0.5252540000 0.0826710000 0.0822400000 0.0316100000 0.3228300000 0.0017160000 142355131 0 402718720 3.8823208809 4.1659874916 3.7872867584 1840 1311867231.8202130795 0.1128146872 0.0896524900 0.1207897216 0.0060514190 0.4697300000 0.0947560000 0.0491800000 0.0000010000 0.3198800000 0.0017060000 142358859 0 402718720 3.8818972111 4.1657891273 3.7868139744 1841 1311867231.8521840572 0.1130495667 0.0896651989 0.1207897216 0.0060503885 0.8480160000 0.0701490000 0.0860220000 0.0315940000 0.3197470000 0.3363220000 142362475 0 402718720 3.8817603588 4.1650428772 3.7861795425 1842 1311867231.8857500553 0.1127128378 0.0896777111 0.1207897216 0.0060494959 0.4820980000 0.0703890000 0.0820170000 0.0000010000 0.3237780000 0.0017020000 142366259 0 402718720 3.8814051151 4.1622018814 3.7855858803 1843 1311867231.9208559990 0.1118828207 0.0896897595 0.1207897216 0.0060479101 0.5138900000 0.0698300000 0.0857480000 0.0311300000 0.3209430000 0.0017940000 142370043 0 402718720 3.8826265335 4.1615262032 3.7846705914 1844 1311867231.9533181190 0.1128459722 0.0897023171 0.1207897216 0.0060470004 0.4732590000 0.0882160000 0.0576900000 0.0000000000 0.3211750000 0.0018060000 142373659 0 402718720 3.8816215992 4.1604056358 3.7843794823 1845 1311867231.9870491028 0.1130719557 0.0897149836 0.1207897216 0.0060454651 0.8127450000 0.0696180000 0.0434210000 0.0316050000 0.3221770000 0.3417650000 142377387 0 402718720 3.8813846111 4.1591382027 3.7837991714 1846 1311867232.0202860832 0.1142476946 0.0897282732 0.1207897216 0.0060441449 0.4549210000 0.0698680000 0.0529720000 0.0000000000 0.3261490000 0.0017040000 142381115 0 402718720 3.8794448376 4.1569013596 3.7831678391 1847 1311867232.0522420406 0.1136840954 0.0897412434 0.1207897216 0.0060426960 0.5127510000 0.0682380000 0.0801550000 0.0314540000 0.3269750000 0.0017090000 142384787 0 402718720 3.8804211617 4.1566128731 3.7828707695 1848 1311867232.0878489017 0.1141240224 0.0897544375 0.1207897216 0.0060410988 0.4633930000 0.0826860000 0.0477870000 0.0000010000 0.3269680000 0.0017040000 142388571 0 402718720 3.8795599937 4.1550874710 3.7822229862 1849 1311867232.1203238964 0.1141798273 0.0897676475 0.1207897216 0.0060405601 0.8938250000 0.0797720000 0.0808620000 0.0316030000 0.3378280000 0.3591220000 142392243 0 402718720 3.8795108795 4.1533226967 3.7814879417 1850 1311867232.1545510292 0.1131721511 0.0897802986 0.1207897216 0.0060396383 0.5181660000 0.0883200000 0.0810460000 0.0000000000 0.3418800000 0.0022590000 142395971 0 402718720 3.8811948299 4.1543283463 3.7814197540 1851 1311867232.1846179962 0.1142696291 0.0897935290 0.1207897216 0.0060388345 0.5300120000 0.0884570000 0.0545720000 0.0387690000 0.3412150000 0.0022640000 142399587 0 402718720 3.8788945675 4.1517581940 3.7806971073 1852 1311867232.2209780216 0.1148593947 0.0898070634 0.1207897216 0.0060374355 0.4689410000 0.0870980000 0.0476720000 0.0000010000 0.3282030000 0.0017050000 142403371 0 402718720 3.8775608540 4.1495022774 3.7799959183 1853 1311867232.2531120777 0.1147901416 0.0898205459 0.1207897216 0.0060361702 0.8323880000 0.0688710000 0.0538170000 0.0312180000 0.3285480000 0.3456930000 142406987 0 402718720 3.8780281544 4.1500167847 3.7797865868 1854 1311867232.2844479084 0.1152866930 0.0898342817 0.1207897216 0.0060350125 0.4991010000 0.0836260000 0.0804370000 0.0000010000 0.3290820000 0.0016890000 142410715 0 402718720 3.8763983250 4.1472859383 3.7789683342 1855 1311867232.3209791183 0.1149249449 0.0898478077 0.1207897216 0.0060335748 0.4956000000 0.0812620000 0.0496990000 0.0312400000 0.3274380000 0.0017010000 142414499 0 402718720 3.8767607212 4.1467442513 3.7785034180 1856 1311867232.3544659615 0.1144309491 0.0898610529 0.1207897216 0.0060322031 0.4828290000 0.0674860000 0.0792670000 0.0000010000 0.3301540000 0.0016920000 142418171 0 402718720 3.8775436878 4.1466040611 3.7780201435 1857 1311867232.3858909607 0.1166010723 0.0898754525 0.1207897216 0.0060310784 0.8340310000 0.0664010000 0.0530590000 0.0314700000 0.3308350000 0.3480450000 142421843 0 402718720 3.8748550415 4.1452317238 3.7777154446 1858 1311867232.4203910828 0.1155436561 0.0898892675 0.1207897216 0.0060300532 0.4846390000 0.0679790000 0.0795820000 0.0000000000 0.3311580000 0.0016890000 142425571 0 402718720 3.8759913445 4.1441073418 3.7770900726 1859 1311867232.4544560909 0.1151058078 0.0899028320 0.1207897216 0.0060286095 0.5108920000 0.0791220000 0.0630230000 0.0316030000 0.3311660000 0.0016920000 142429299 0 402718720 3.8772237301 4.1445808411 3.7770609856 1860 1311867232.4846010208 0.1141647175 0.0899158761 0.1207897216 0.0060318621 0.5018430000 0.0851210000 0.0832940000 0.0000010000 0.3271570000 0.0017850000 142432915 0 402718720 3.8771421909 4.1428055763 3.7766706944 1861 1311867232.5203030109 0.1143956035 0.0899290301 0.1207897216 0.0060311040 0.8787900000 0.0800420000 0.0826320000 0.0316420000 0.3312500000 0.3489640000 142436699 0 402718720 3.8777520657 4.1426396370 3.7764670849 1862 1311867232.5550050735 0.1140393913 0.0899419788 0.1207897216 0.0060311796 0.4646590000 0.0676710000 0.0599110000 0.0000010000 0.3311810000 0.0016610000 142440427 0 402718720 3.8774523735 4.1427402496 3.7765498161 1863 1311867232.5844318867 0.1149294153 0.0899553912 0.1207897216 0.0060330010 0.4873380000 0.0683220000 0.0548870000 0.0312310000 0.3265970000 0.0017860000 142443987 0 402718720 3.8770585060 4.1398644447 3.7760312557 1864 1311867232.6201601028 0.1146597490 0.0899686447 0.1207897216 0.0060315092 0.4961840000 0.0790610000 0.0838440000 0.0000010000 0.3270080000 0.0017950000 142447771 0 402718720 3.8777430058 4.1386871338 3.7759189606 1865 1311867232.6554861069 0.1132990122 0.0899811542 0.1207897216 0.0060313469 0.8332090000 0.0678510000 0.0563090000 0.0312500000 0.3268690000 0.3466680000 142451387 0 402718720 3.8810737133 4.1402688026 3.7763261795 1866 1311867232.6850490570 0.1133530363 0.0899936794 0.1207897216 0.0060306037 0.5409990000 0.0841790000 0.1053770000 0.0000010000 0.3444860000 0.0022510000 142455003 0 402718720 3.8798787594 4.1363191605 3.7754056454 1867 1311867232.7210319042 0.1133393124 0.0900061837 0.1207897216 0.0060289924 0.5747590000 0.0875180000 0.1062190000 0.0388080000 0.3362280000 0.0017050000 142458787 0 402718720 3.8799724579 4.1344518661 3.7752540112 1868 1311867232.7539520264 0.1145496666 0.0900193226 0.1207897216 0.0060287341 0.4798320000 0.0662800000 0.0752640000 0.0000000000 0.3323410000 0.0016660000 142462403 0 402718720 3.8789894581 4.1348242760 3.7752244473 1869 1311867232.7885808945 0.1142159030 0.0900322689 0.1207897216 0.0060273326 0.8924110000 0.0678750000 0.0792940000 0.0317590000 0.3453150000 0.3634380000 142466131 0 402718720 3.8795213699 4.1327738762 3.7749705315 1870 1311867232.8206169605 0.1154199243 0.0900458452 0.1207897216 0.0060259262 0.5464340000 0.0870600000 0.1060590000 0.0000000000 0.3463200000 0.0022590000 142469859 0 402718720 3.8771345615 4.1277828217 3.7746300697 1871 1311867232.8539369106 0.1143068895 0.0900588121 0.1207897216 0.0060247646 0.5833610000 0.0854860000 0.1040150000 0.0387300000 0.3481600000 0.0022360000 142473531 0 402718720 3.8793332577 4.1290769577 3.7744131088 1872 1311867232.8882710934 0.1138513610 0.0900715218 0.1207897216 0.0060232769 0.4448570000 0.0710320000 0.0334000000 0.0000000000 0.3344940000 0.0016840000 142477259 0 402718720 3.8797204494 4.1267075539 3.7740116119 1873 1311867232.9203770161 0.1142200306 0.0900844147 0.1207897216 0.0060223787 0.8708550000 0.0672910000 0.0785910000 0.0311760000 0.3354970000 0.3540520000 142480987 0 402718720 3.8789176941 4.1240296364 3.7736682892 1874 1311867232.9559900761 0.1128831431 0.0900965805 0.1207897216 0.0060218028 0.4980270000 0.0761630000 0.0825200000 0.0000010000 0.3330760000 0.0017740000 142484771 0 402718720 3.8804042339 4.1222195625 3.7731134892 1875 1311867232.9890038967 0.1154014841 0.0901100765 0.1207897216 0.0060235717 0.4963130000 0.0661390000 0.0548080000 0.0316950000 0.3376750000 0.0016810000 142488387 0 402718720 3.8780267239 4.1240649223 3.7730243206 1876 1311867233.0212259293 0.1134740412 0.0901225306 0.1207897216 0.0060233712 0.4613020000 0.0655620000 0.0518050000 0.0000000000 0.3379790000 0.0016720000 142492115 0 402718720 3.8804342747 4.1211023331 3.7730073929 1877 1311867233.0569291115 0.1146412194 0.0901355933 0.1207897216 0.0060222138 0.8754300000 0.0658410000 0.0813810000 0.0316730000 0.3345680000 0.3576880000 142495843 0 402718720 3.8784432411 4.1195116043 3.7725844383 1878 1311867233.0943200588 0.1145183593 0.0901485767 0.1207897216 0.0060215983 0.4550910000 0.0655620000 0.0455150000 0.0000000000 0.3380340000 0.0016710000 142499683 0 402718720 3.8795688152 4.1204142570 3.7729892731 1879 1311867233.1241600513 0.1146434173 0.0901616128 0.1207897216 0.0060206385 0.5344430000 0.0771720000 0.0818150000 0.0317060000 0.3377980000 0.0016830000 142503187 0 402718720 3.8789420128 4.1182022095 3.7727384567 1880 1311867233.1530799866 0.1138183698 0.0901741962 0.1207897216 0.0060206284 0.5057910000 0.0900890000 0.0751280000 0.0000010000 0.3342930000 0.0017750000 142506747 0 402718720 3.8792209625 4.1161727905 3.7728869915 1881 1311867233.1887679100 0.1133499444 0.0901865171 0.1207897216 0.0060193529 0.8556280000 0.0656330000 0.0585560000 0.0311780000 0.3383360000 0.3576350000 142510531 0 402718720 3.8807382584 4.1155538559 3.7727813721 1882 1311867233.2210481167 0.1136037260 0.0901989599 0.1207897216 0.0060178551 0.4911750000 0.0660690000 0.0811790000 0.0000010000 0.3379460000 0.0016790000 142514203 0 402718720 3.8794598579 4.1124830246 3.7725679874 1883 1311867233.2590179443 0.1140208617 0.0902116109 0.1207897216 0.0060163466 0.5008290000 0.0660940000 0.0583310000 0.0316310000 0.3387510000 0.0016780000 142518043 0 402718720 3.8794126511 4.1111946106 3.7725288868 1884 1311867233.2899589539 0.1137024686 0.0902240795 0.1207897216 0.0060147994 0.5091630000 0.0863710000 0.0810690000 0.0000010000 0.3354140000 0.0017730000 142521715 0 402718720 3.8801229000 4.1119942665 3.7726860046 1885 1311867233.3212211132 0.1130013466 0.0902361629 0.1207897216 0.0060144582 0.8758110000 0.0654590000 0.0809140000 0.0312160000 0.3354350000 0.3584930000 142525387 0 402718720 3.8801882267 4.1099181175 3.7725150585 1886 1311867233.3533849716 0.1162059978 0.0902499327 0.1207897216 0.0060151334 0.4626570000 0.0647190000 0.0514880000 0.0000010000 0.3405380000 0.0016450000 142529003 0 402718720 3.8764896393 4.1071410179 3.7726426125 1887 1311867233.3884561062 0.1155381799 0.0902633340 0.1207897216 0.0060159270 0.5180090000 0.0639800000 0.0758050000 0.0314230000 0.3407900000 0.0016680000 142532787 0 402718720 3.8774576187 4.1063375473 3.7726078033 1888 1311867233.4236669540 0.1152066886 0.0902765456 0.1207897216 0.0060202412 0.4850810000 0.0634450000 0.0738850000 0.0000010000 0.3418330000 0.0016300000 142536515 0 402718720 3.8774347305 4.1049251556 3.7725245953 1889 1311867233.4522700310 0.1133942306 0.0902887836 0.1207897216 0.0060240954 0.8668560000 0.0756070000 0.0511290000 0.0314400000 0.3423280000 0.3620410000 142540187 0 402718720 3.8793110847 4.1011261940 3.7716612816 1890 1311867233.4881610870 0.1141811013 0.0903014251 0.1207897216 0.0060278588 0.4795830000 0.0872030000 0.0473010000 0.0000000000 0.3387980000 0.0017610000 142543859 0 402718720 3.8781676292 4.1002588272 3.7713670731 1891 1311867233.5201199055 0.1139395460 0.0903139254 0.1207897216 0.0060277340 0.5209880000 0.0644140000 0.0793540000 0.0316560000 0.3392860000 0.0017570000 142547587 0 402718720 3.8789048195 4.1002097130 3.7713367939 1892 1311867233.5526270866 0.1136037260 0.0903262350 0.1207897216 0.0060270336 0.4879740000 0.0643990000 0.0728610000 0.0000000000 0.3447450000 0.0016330000 142551259 0 402718720 3.8786787987 4.0980529785 3.7709474564 1893 1311867233.5890851021 0.1141906902 0.0903388417 0.1207897216 0.0060260027 0.8619810000 0.0636860000 0.0516210000 0.0316510000 0.3447220000 0.3659700000 142555043 0 402718720 3.8781750202 4.0986771584 3.7709715366 1894 1311867233.6202619076 0.1136503220 0.0903511498 0.1207897216 0.0060244940 0.5160920000 0.0904860000 0.0746670000 0.0000000000 0.3449890000 0.0016430000 142558715 0 402718720 3.8792328835 4.0977706909 3.7712717056 1895 1311867233.6539080143 0.1154016703 0.0903643690 0.1207897216 0.0060239148 0.5004350000 0.0617680000 0.0557770000 0.0314110000 0.3454960000 0.0016410000 142562387 0 402718720 3.8768999577 4.0970044136 3.7712051868 1896 1311867233.6879289150 0.1164282709 0.0903781158 0.1207897216 0.0060224378 0.4889260000 0.0638740000 0.0772650000 0.0000010000 0.3414860000 0.0017530000 142566115 0 402718720 3.8751900196 4.0960512161 3.7711188793 1897 1311867233.7197790146 0.1148489788 0.0903910156 0.1207897216 0.0060208993 0.8826940000 0.0638320000 0.0788890000 0.0317030000 0.3412580000 0.3625090000 142569843 0 402718720 3.8772363663 4.0954818726 3.7710626125 1898 1311867233.7577540874 0.1150127798 0.0904039881 0.1207897216 0.0060196313 0.4513200000 0.0637660000 0.0400710000 0.0000010000 0.3415040000 0.0016530000 142573683 0 402718720 3.8765313625 4.0944252014 3.7710008621 1899 1311867233.7896089554 0.1150709316 0.0904169775 0.1207897216 0.0060193482 0.5229910000 0.0638610000 0.0753570000 0.0315910000 0.3460990000 0.0016540000 142577355 0 402718720 3.8758249283 4.0934686661 3.7708346844 1900 1311867233.8221189976 0.1147081703 0.0904297623 0.1207897216 0.0060191259 0.4772870000 0.0831770000 0.0463550000 0.0000000000 0.3414520000 0.0017490000 142581083 0 402718720 3.8761012554 4.0923404694 3.7710976601 1901 1311867233.8562450409 0.1147041172 0.0904425316 0.1207897216 0.0060176380 0.8786050000 0.0635330000 0.0656420000 0.0315950000 0.3460190000 0.3674750000 142584755 0 402718720 3.8758041859 4.0913686752 3.7711701393 1902 1311867233.8885691166 0.1143045425 0.0904550773 0.1207897216 0.0060160911 0.4915000000 0.0635010000 0.0788160000 0.0000010000 0.3431700000 0.0016550000 142588427 0 402718720 3.8758106232 4.0898022652 3.7710609436 1903 1311867233.9203450680 0.1127406880 0.0904667881 0.1207897216 0.0060155190 0.5211740000 0.0630790000 0.0783710000 0.0311990000 0.3421910000 0.0017490000 142592099 0 402718720 3.8774962425 4.0890045166 3.7711739540 1904 1311867233.9552910328 0.1124963239 0.0904783583 0.1207897216 0.0060140657 0.5060700000 0.0925340000 0.0607020000 0.0000010000 0.3468010000 0.0016530000 142595883 0 402718720 3.8771724701 4.0878167152 3.7709333897 1905 1311867233.9885900021 0.1133019105 0.0904903391 0.1207897216 0.0060125427 0.8646060000 0.0623800000 0.0494830000 0.0315440000 0.3474770000 0.3693940000 142599555 0 402718720 3.8759045601 4.0871787071 3.7710111141 1906 1311867234.0205829144 0.1133564636 0.0905023360 0.1207897216 0.0060110467 0.4522820000 0.0609420000 0.0370780000 0.0000010000 0.3483140000 0.0016110000 142603227 0 402718720 3.8756408691 4.0872197151 3.7707641125 1907 1311867234.0566239357 0.1137897074 0.0905145476 0.1207897216 0.0060096892 0.5193000000 0.0612150000 0.0730180000 0.0309460000 0.3481060000 0.0016370000 142607067 0 402718720 3.8746547699 4.0847835541 3.7708535194 1908 1311867234.0907170773 0.1128934547 0.0905262765 0.1207897216 0.0060083002 0.4713920000 0.0613440000 0.0551580000 0.0000000000 0.3489180000 0.0016150000 142610739 0 402718720 3.8749074936 4.0825004578 3.7703564167 1909 1311867234.1214520931 0.1137922108 0.0905384640 0.1207897216 0.0060074168 0.9030300000 0.0739070000 0.0731710000 0.0315720000 0.3488700000 0.3711690000 142614411 0 402718720 3.8737187386 4.0826926231 3.7703027725 1910 1311867234.1561689377 0.1139847487 0.0905507396 0.1207897216 0.0060060112 0.4844880000 0.0750960000 0.0583240000 0.0000010000 0.3447500000 0.0017400000 142618139 0 402718720 3.8731851578 4.0804967880 3.7703487873 1911 1311867234.1892559528 0.1157902181 0.0905639471 0.1207897216 0.0060046966 0.5024880000 0.0607380000 0.0576430000 0.0314560000 0.3463390000 0.0016950000 142621811 0 402718720 3.8702778816 4.0792627335 3.7704017162 1912 1311867234.2203600407 0.1150430962 0.0905767500 0.1207897216 0.0060037518 0.4734830000 0.0604230000 0.0571530000 0.0000010000 0.3499110000 0.0016260000 142625483 0 402718720 3.8711204529 4.0780324936 3.7700853348 1913 1311867234.2588930130 0.1157448366 0.0905899063 0.1207897216 0.0060024521 0.8659370000 0.0611950000 0.0425510000 0.0315140000 0.3515060000 0.3748110000 142629323 0 402718720 3.8696730137 4.0781316757 3.7701823711 1914 1311867234.2895319462 0.1148968935 0.0906026059 0.1207897216 0.0060009694 0.4924990000 0.0618440000 0.0727870000 0.0000000000 0.3519180000 0.0016320000 142632995 0 402718720 3.8696660995 4.0766606331 3.7700793743 1915 1311867234.3213200569 0.1148508936 0.0906152682 0.1207897216 0.0060030334 0.5053630000 0.0612970000 0.0544870000 0.0315990000 0.3519800000 0.0016290000 142636667 0 402718720 3.8691992760 4.0762085915 3.7704164982 1916 1311867234.3570129871 0.1151464358 0.0906280715 0.1207897216 0.0060015818 0.4677680000 0.0612050000 0.0484170000 0.0000010000 0.3521520000 0.0016280000 142640395 0 402718720 3.8683407307 4.0761914253 3.7707846165 1917 1311867234.3885769844 0.1116562188 0.0906390408 0.1207897216 0.0060024342 0.8968220000 0.0613360000 0.0723040000 0.0316190000 0.3518890000 0.3753130000 142644067 0 402718720 3.8716843128 4.0741825104 3.7707951069 1918 1311867234.4204909801 0.1120451689 0.0906502014 0.1207897216 0.0060009257 0.4794040000 0.0725980000 0.0484440000 0.0000000000 0.3523460000 0.0016260000 142647795 0 402718720 3.8703973293 4.0723690987 3.7710523605 1919 1311867234.4579920769 0.1123769432 0.0906615234 0.1207897216 0.0060002065 0.4862420000 0.0598300000 0.0363210000 0.0313660000 0.3527080000 0.0016270000 142651523 0 402718720 3.8700537682 4.0730662346 3.7713966370 1920 1311867234.4878959656 0.1119057089 0.0906725880 0.1207897216 0.0060020091 0.4832850000 0.0611180000 0.0681810000 0.0000010000 0.3476500000 0.0017140000 142655195 0 402718720 3.8703396320 4.0717129707 3.7716026306 1921 1311867234.5201239586 0.1113834977 0.0906833693 0.1207897216 0.0060005935 0.9146870000 0.0745730000 0.0765440000 0.0316460000 0.3517050000 0.3758030000 142658867 0 402718720 3.8706116676 4.0693764687 3.7719340324 1922 1311867234.5594279766 0.1130331829 0.0906949978 0.1207897216 0.0060016332 0.4829070000 0.0612050000 0.0484410000 0.0000010000 0.3662650000 0.0021330000 142662763 0 402718720 3.8690199852 4.0697255135 3.7725706100 1923 1311867234.5882380009 0.1123782024 0.0907062735 0.1207897216 0.0060008780 0.5855280000 0.0778560000 0.0950420000 0.0393400000 0.3662770000 0.0021310000 142666379 0 402718720 3.8695702553 4.0689096451 3.7728800774 1924 1311867234.6204199791 0.1135062277 0.0907181238 0.1207897216 0.0059994056 0.5241610000 0.0784390000 0.0721970000 0.0000010000 0.3665080000 0.0021360000 142670051 0 402718720 3.8677723408 4.0664577484 3.7731590271 1925 1311867234.6590909958 0.1134653687 0.0907299405 0.1207897216 0.0059985284 0.9200970000 0.0772720000 0.0641460000 0.0392390000 0.3583370000 0.3767000000 142673891 0 402718720 3.8681561947 4.0686836243 3.7738537788 1926 1311867234.6880459785 0.1124430224 0.0907412142 0.1207897216 0.0059971714 0.4925230000 0.0617190000 0.0766200000 0.0000010000 0.3478630000 0.0017260000 142677451 0 402718720 3.8689267635 4.0671663284 3.7739717960 1927 1311867234.7198779583 0.1133251786 0.0907529339 0.1207897216 0.0059973830 0.4988030000 0.0610780000 0.0513640000 0.0316020000 0.3487090000 0.0016280000 142681123 0 402718720 3.8682024479 4.0661697388 3.7745628357 1928 1311867234.7586181164 0.1121649742 0.0907640398 0.1207897216 0.0059958658 0.4919880000 0.0612300000 0.0723050000 0.0000000000 0.3524050000 0.0016310000 142684907 0 402718720 3.8697307110 4.0657548904 3.7754452229 1929 1311867234.7882609367 0.1122579575 0.0907751823 0.1207897216 0.0060016638 0.8916300000 0.0731600000 0.0580040000 0.0315890000 0.3492800000 0.3752000000 142688579 0 402718720 3.8698081970 4.0666122437 3.7765765190 1930 1311867234.8206560612 0.1123850122 0.0907863791 0.1207897216 0.0060001560 0.4927620000 0.0621800000 0.0767140000 0.0000010000 0.3478010000 0.0016350000 142692251 0 402718720 3.8689002991 4.0646376610 3.7773172855 1931 1311867234.8590250015 0.1113751829 0.0907970413 0.1207897216 0.0059987000 0.4990360000 0.0615630000 0.0487740000 0.0311030000 0.3515880000 0.0016350000 142696035 0 402718720 3.8709471226 4.0654096603 3.7783803940 1932 1311867234.8881230354 0.1119923592 0.0908080120 0.1207897216 0.0059975580 0.5003160000 0.0616750000 0.0730370000 0.0000010000 0.3585680000 0.0021340000 142699651 0 402718720 3.8705756664 4.0651707649 3.7794017792 1933 1311867234.9204928875 0.1124167666 0.0908191909 0.1207897216 0.0059965583 0.9589020000 0.0778920000 0.0954290000 0.0385400000 0.3641340000 0.3784420000 142703379 0 402718720 3.8702931404 4.0640692711 3.7801623344 1934 1311867234.9566090107 0.1134958789 0.0908309161 0.1207897216 0.0059956781 0.4884730000 0.0721340000 0.0641670000 0.0000010000 0.3458350000 0.0017260000 142707163 0 402718720 3.8694009781 4.0640020370 3.7807438374 1935 1311867234.9904088974 0.1135425642 0.0908426534 0.1207897216 0.0059941880 0.5224750000 0.0620230000 0.0727070000 0.0315250000 0.3501990000 0.0016300000 142710891 0 402718720 3.8695728779 4.0635585785 3.7810482979 1936 1311867235.0205988884 0.1125219539 0.0908538514 0.1207897216 0.0059933977 0.4909920000 0.0619860000 0.0727080000 0.0000010000 0.3502990000 0.0016300000 142714507 0 402718720 3.8706288338 4.0611433983 3.7808399200 1937 1311867235.0563809872 0.1153668240 0.0908665065 0.1207897216 0.0059923809 0.8704100000 0.0614780000 0.0576380000 0.0315360000 0.3462260000 0.3689050000 142718291 0 402718720 3.8667666912 4.0609049797 3.7810084820 1938 1311867235.0911149979 0.1143161654 0.0908786065 0.1207897216 0.0059914535 0.4917110000 0.0603150000 0.0749790000 0.0000010000 0.3504040000 0.0016070000 142722019 0 402718720 3.8677098751 4.0601205826 3.7808973789 1939 1311867235.1208140850 0.1124930084 0.0908897537 0.1207897216 0.0059911907 0.5312300000 0.0710080000 0.0710610000 0.0314960000 0.3516130000 0.0016110000 142725691 0 402718720 3.8696205616 4.0587620735 3.7809159756 1940 1311867235.1564071178 0.1115799844 0.0909004187 0.1207897216 0.0059912001 0.4769830000 0.0604120000 0.0624850000 0.0000010000 0.3480840000 0.0016080000 142729419 0 402718720 3.8702383041 4.0590219498 3.7817516327 1941 1311867235.1885681152 0.1107883751 0.0909106650 0.1207897216 0.0059910226 0.8882690000 0.0596600000 0.0748200000 0.0310280000 0.3469970000 0.3712720000 142733091 0 402718720 3.8703346252 4.0586819649 3.7817122936 1942 1311867235.2202088833 0.1115368679 0.0909212861 0.1207897216 0.0059897345 0.4837680000 0.0606010000 0.0653140000 0.0000000000 0.3518010000 0.0016020000 142736763 0 402718720 3.8680732250 4.0571599007 3.7816522121 1943 1311867235.2576260567 0.1124204919 0.0909323510 0.1207897216 0.0059892498 0.4954080000 0.0601200000 0.0504470000 0.0314710000 0.3470540000 0.0017040000 142740435 0 402718720 3.8673343658 4.0578203201 3.7821347713 1944 1311867235.2899661064 0.1124596819 0.0909434248 0.1207897216 0.0059899705 0.4995040000 0.0711210000 0.0750860000 0.0000010000 0.3469100000 0.0017080000 142744163 0 402718720 3.8659107685 4.0565314293 3.7824311256 1945 1311867235.3247830868 0.1113324612 0.0909539076 0.1207897216 0.0059885629 0.8960210000 0.0607460000 0.0754230000 0.0311080000 0.3494660000 0.3748110000 142747947 0 402718720 3.8665003777 4.0561513901 3.7822556496 1946 1311867235.3567800522 0.1110930666 0.0909642566 0.1207897216 0.0059982651 0.4875860000 0.0602800000 0.0694910000 0.0000010000 0.3517830000 0.0016060000 142751619 0 402718720 3.8659667969 4.0564227104 3.7825486660 1947 1311867235.3886280060 0.1113614738 0.0909747328 0.1207897216 0.0060074720 0.5035580000 0.0604390000 0.0538320000 0.0314960000 0.3517070000 0.0016160000 142755291 0 402718720 3.8659024239 4.0562357903 3.7829630375 1948 1311867235.4246189594 0.1117075235 0.0909853759 0.1207897216 0.0060067386 0.4665680000 0.0608580000 0.0480230000 0.0000010000 0.3516480000 0.0016170000 142759075 0 402718720 3.8643667698 4.0556764603 3.7836816311 1949 1311867235.4564850330 0.1120996028 0.0909962093 0.1207897216 0.0060063960 0.8756580000 0.0711100000 0.0421780000 0.0314840000 0.3515730000 0.3748590000 142762747 0 402718720 3.8645999432 4.0572347641 3.7845716476 1950 1311867235.4897930622 0.1119831353 0.0910069718 0.1207897216 0.0060060061 0.4866720000 0.0605360000 0.0739050000 0.0000010000 0.3461540000 0.0016060000 142766419 0 402718720 3.8640341759 4.0570769310 3.7854118347 1951 1311867235.5240719318 0.1117499098 0.0910176038 0.1207897216 0.0060047909 0.5188770000 0.0603850000 0.0712160000 0.0310100000 0.3501860000 0.0016090000 142770147 0 402718720 3.8640062809 4.0562486649 3.7859666348 1952 1311867235.5577290058 0.1128502339 0.0910287885 0.1207897216 0.0060044630 0.4578920000 0.0598490000 0.0419800000 0.0000010000 0.3499520000 0.0016060000 142773819 0 402718720 3.8631885052 4.0576314926 3.7871620655 1953 1311867235.5880639553 0.1129682139 0.0910400222 0.1207897216 0.0060029941 0.8531390000 0.0601190000 0.0364620000 0.0310330000 0.3493680000 0.3717180000 142777491 0 402718720 3.8628485203 4.0566473007 3.7877681255 1954 1311867235.6249940395 0.1127811670 0.0910511487 0.1207897216 0.0060020318 0.4920280000 0.0832520000 0.0573830000 0.0000010000 0.3450180000 0.0017060000 142781331 0 402718720 3.8623740673 4.0543842316 3.7877905369 1955 1311867235.6563270092 0.1128732339 0.0910623109 0.1207897216 0.0060013996 0.5100550000 0.0611410000 0.0612060000 0.0315080000 0.3501070000 0.0016190000 142784947 0 402718720 3.8627953529 4.0559024811 3.7883772850 1956 1311867235.6885619164 0.1131040230 0.0910735796 0.1207897216 0.0060001746 0.4885540000 0.0608920000 0.0716720000 0.0000010000 0.3499020000 0.0016160000 142788619 0 402718720 3.8621752262 4.0548386574 3.7885942459 1957 1311867235.7241950035 0.1135977283 0.0910850892 0.1207897216 0.0059988384 0.8917050000 0.0609910000 0.0717370000 0.0314500000 0.3500780000 0.3729370000 142792403 0 402718720 3.8611452579 4.0545220375 3.7888629436 1958 1311867235.7561719418 0.1128237322 0.0910961917 0.1207897216 0.0059974357 0.4596040000 0.0609560000 0.0425360000 0.0000010000 0.3499240000 0.0016100000 142796131 0 402718720 3.8622081280 4.0547471046 3.7896854877 1959 1311867235.7903280258 0.1131276265 0.0911074379 0.1207897216 0.0059965845 0.5288570000 0.0693280000 0.0723430000 0.0314400000 0.3496230000 0.0016210000 142799803 0 402718720 3.8616175652 4.0543794632 3.7902314663 1960 1311867235.8249480724 0.1136663705 0.0911189476 0.1207897216 0.0059952535 0.4877000000 0.0605580000 0.0715690000 0.0000010000 0.3494700000 0.0016030000 142803531 0 402718720 3.8610703945 4.0542907715 3.7912516594 1961 1311867235.8562169075 0.1141306385 0.0911306822 0.1207897216 0.0059958856 0.8894720000 0.0609190000 0.0756960000 0.0314710000 0.3447650000 0.3721360000 142807259 0 402718720 3.8612492085 4.0562138557 3.7926127911 1962 1311867235.8881049156 0.1161799356 0.0911434495 0.1207897216 0.0059949020 0.4689790000 0.0599590000 0.0541950000 0.0000010000 0.3487220000 0.0016060000 142810819 0 402718720 3.8577065468 4.0548148155 3.7931909561 1963 1311867235.9239900112 0.1140020564 0.0911550942 0.1207897216 0.0059940790 0.5016120000 0.0610210000 0.0541700000 0.0314600000 0.3488410000 0.0016090000 142814659 0 402718720 3.8600654602 4.0538458824 3.7938964367 1964 1311867235.9563760757 0.1144250929 0.0911669425 0.1207897216 0.0059937165 0.4918790000 0.0844850000 0.0571830000 0.0000000000 0.3437520000 0.0017020000 142818387 0 402718720 3.8602252007 4.0547585487 3.7949502468 1965 1311867235.9890949726 0.1133437008 0.0911782283 0.1207897216 0.0059937551 0.8617400000 0.0613360000 0.0496090000 0.0314830000 0.3441070000 0.3706950000 142822003 0 402718720 3.8605055809 4.0540251732 3.7951142788 1966 1311867236.0250449181 0.1139843091 0.0911898286 0.1207897216 0.0059923113 0.4695690000 0.0610720000 0.0542540000 0.0000000000 0.3480760000 0.0016050000 142825787 0 402718720 3.8591380119 4.0536642075 3.7956354618 1967 1311867236.0599400997 0.1134432033 0.0912011419 0.1207897216 0.0059908071 0.4825440000 0.0606280000 0.0364330000 0.0314400000 0.3478710000 0.0016000000 142829515 0 402718720 3.8594329357 4.0543813705 3.7964141369 1968 1311867236.0884859562 0.1136343703 0.0912125409 0.1207897216 0.0059894754 0.4850100000 0.0607640000 0.0703660000 0.0000010000 0.3477130000 0.0016060000 142833075 0 402718720 3.8585293293 4.0537061691 3.7971289158 1969 1311867236.1247038841 0.1130088568 0.0912236107 0.1207897216 0.0059880106 0.8961910000 0.0752020000 0.0692780000 0.0314390000 0.3459700000 0.3697240000 142836915 0 402718720 3.8588023186 4.0532793999 3.7982008457 1970 1311867236.1581289768 0.1127688140 0.0912345473 0.1207897216 0.0059867792 0.4731690000 0.0596480000 0.0597380000 0.0000010000 0.3476760000 0.0015740000 142840587 0 402718720 3.8588945866 4.0528740883 3.7992873192 1971 1311867236.1901528835 0.1127576008 0.0912454672 0.1207897216 0.0059855225 0.5160230000 0.0608200000 0.0754720000 0.0314410000 0.3418020000 0.0016990000 142844203 0 402718720 3.8582100868 4.0538454056 3.8005244732 1972 1311867236.2242329121 0.1118511856 0.0912559163 0.1207897216 0.0059841879 0.4609160000 0.0601170000 0.0483110000 0.0000010000 0.3463410000 0.0016050000 142847931 0 402718720 3.8582196236 4.0532326698 3.8015122414 1973 1311867236.2599489689 0.1122517884 0.0912665579 0.1207897216 0.0059828209 0.8775800000 0.0611120000 0.0758190000 0.0314180000 0.3412980000 0.3634020000 142851715 0 402718720 3.8572871685 4.0539035797 3.8029615879 1974 1311867236.2890419960 0.1120645180 0.0912770939 0.1207897216 0.0059813425 0.4994800000 0.0759860000 0.0761070000 0.0000010000 0.3409120000 0.0016970000 142855275 0 402718720 3.8570444584 4.0532436371 3.8040852547 1975 1311867236.3262441158 0.1129616573 0.0912880734 0.1207897216 0.0059799222 0.5291810000 0.0603780000 0.0740200000 0.0313730000 0.3562590000 0.0021210000 142859115 0 402718720 3.8556163311 4.0533051491 3.8055546284 1976 1311867236.3568809032 0.1130821034 0.0912991028 0.1207897216 0.0059790882 0.5383540000 0.0775490000 0.0950440000 0.0000010000 0.3586050000 0.0021150000 142862787 0 402718720 3.8549506664 4.0523281097 3.8066933155 1977 1311867236.3897418976 0.1135028526 0.0913103338 0.1207897216 0.0059776263 0.9520000000 0.0773590000 0.0929890000 0.0383740000 0.3581230000 0.3800940000 142866459 0 402718720 3.8537259102 4.0521650314 3.8076934814 1978 1311867236.4243390560 0.1122999266 0.0913209453 0.1207897216 0.0059783607 0.5098620000 0.0775070000 0.0825710000 0.0000000000 0.3436280000 0.0016050000 142870187 0 402718720 3.8545677662 4.0519413948 3.8093883991 1979 1311867236.4566040039 0.1116812006 0.0913312335 0.1207897216 0.0059774705 0.4900980000 0.0613660000 0.0486480000 0.0309190000 0.3429600000 0.0016080000 142873915 0 402718720 3.8552451134 4.0520596504 3.8106982708 1980 1311867236.4936130047 0.1134859398 0.0913424227 0.1207897216 0.0059820742 0.4809960000 0.0610890000 0.0760700000 0.0000010000 0.3376680000 0.0016110000 142877699 0 402718720 3.8531403542 4.0514225960 3.8122706413 1981 1311867236.5246999264 0.1126501188 0.0913531788 0.1207897216 0.0059806322 0.8381650000 0.0615620000 0.0452990000 0.0313970000 0.3369470000 0.3584290000 142881371 0 402718720 3.8547096252 4.0522937775 3.8141920567 1982 1311867236.5602099895 0.1131135076 0.0913641577 0.1207897216 0.0059803753 0.4814930000 0.0620370000 0.0730790000 0.0000000000 0.3402290000 0.0016160000 142885155 0 402718720 3.8536822796 4.0519032478 3.8158416748 1983 1311867236.5972909927 0.1127383187 0.0913749364 0.1207897216 0.0059790594 0.4872730000 0.0611000000 0.0488600000 0.0311680000 0.3400050000 0.0015980000 142888939 0 402718720 3.8541035652 4.0513944626 3.8175275326 1984 1311867236.6246581078 0.1135831773 0.0913861301 0.1207897216 0.0059776583 0.5004020000 0.0823800000 0.0730110000 0.0000000000 0.3388390000 0.0016170000 142892443 0 402718720 3.8530814648 4.0507225990 3.8192427158 1985 1311867236.6600480080 0.1139495969 0.0913974971 0.1207897216 0.0059761768 0.8448860000 0.0627880000 0.0495270000 0.0309170000 0.3385250000 0.3586020000 142896227 0 402718720 3.8532173634 4.0517530441 3.8216667175 1986 1311867236.6956660748 0.1137412935 0.0914087477 0.1207897216 0.0059756219 0.4812110000 0.0633250000 0.0740200000 0.0000010000 0.3377280000 0.0016210000 142900011 0 402718720 3.8535990715 4.0524206161 3.8238794804 1987 1311867236.7276370525 0.1135759130 0.0914199038 0.1207897216 0.0059744576 0.4989860000 0.0628170000 0.0616940000 0.0313090000 0.3369720000 0.0016290000 142903627 0 402718720 3.8535511494 4.0515918732 3.8258516788 1988 1311867236.7619268894 0.1131696254 0.0914308443 0.1207897216 0.0059738816 0.5006420000 0.0845080000 0.0780340000 0.0000000000 0.3319030000 0.0016310000 142907355 0 402718720 3.8541016579 4.0508608818 3.8280267715 1989 1311867236.7923469543 0.1144595668 0.0914424224 0.1207897216 0.0059748159 0.8794350000 0.0798760000 0.0745750000 0.0313550000 0.3352320000 0.3538340000 142910971 0 402718720 3.8529980183 4.0508618355 3.8302431107 1990 1311867236.8255391121 0.1142792180 0.0914538982 0.1207897216 0.0059740087 0.4788260000 0.0633440000 0.0747660000 0.0000000000 0.3345100000 0.0016280000 142914755 0 402718720 3.8527433872 4.0504875183 3.8321034908 1991 1311867236.8583440781 0.1140781865 0.0914652614 0.1207897216 0.0059732745 0.5090450000 0.0633500000 0.0784750000 0.0313250000 0.3293980000 0.0017300000 142918371 0 402718720 3.8531084061 4.0505256653 3.8341200352 1992 1311867236.8928480148 0.1132257134 0.0914761854 0.1207897216 0.0059727579 0.4767820000 0.0633390000 0.0743120000 0.0000000000 0.3329540000 0.0016300000 142922099 0 402718720 3.8534848690 4.0491762161 3.8358762264 1993 1311867236.9255330563 0.1124731973 0.0914867207 0.1207897216 0.0059714525 0.8560230000 0.0638660000 0.0745720000 0.0313870000 0.3319870000 0.3496560000 142925771 0 402718720 3.8541343212 4.0487713814 3.8377878666 1994 1311867236.9581959248 0.1134393513 0.0914977301 0.1207897216 0.0059701005 0.4791380000 0.0636450000 0.0781140000 0.0000000000 0.3312090000 0.0016320000 142929443 0 402718720 3.8532099724 4.0488910675 3.8402903080 1995 1311867236.9937291145 0.1121502668 0.0915080822 0.1207897216 0.0059728077 0.4762000000 0.0641640000 0.0443360000 0.0308230000 0.3306530000 0.0016390000 142933227 0 402718720 3.8541934490 4.0504975319 3.8425755501 1996 1311867237.0244200230 0.1126001254 0.0915186494 0.1207897216 0.0059715918 0.4762240000 0.0646290000 0.0755850000 0.0000000000 0.3298340000 0.0016370000 142936843 0 402718720 3.8529746532 4.0498051643 3.8448252678 1997 1311867237.0603060722 0.1117660478 0.0915287883 0.1207897216 0.0059747713 0.8496880000 0.0625470000 0.0743490000 0.0310640000 0.3302680000 0.3469000000 142940627 0 402718720 3.8529429436 4.0500979424 3.8467671871 1998 1311867237.0927588940 0.1111272797 0.0915385973 0.1207897216 0.0059854624 0.4910270000 0.0864340000 0.0734190000 0.0000000000 0.3249760000 0.0016480000 142944355 0 402718720 3.8542220592 4.0512514114 3.8489933014 1999 1311867237.1276650429 0.1106280833 0.0915481469 0.1207897216 0.0059849173 0.5180540000 0.0766450000 0.0759240000 0.0313360000 0.3277980000 0.0016490000 142948083 0 402718720 3.8536899090 4.0496335030 3.8506355286 2000 1311867237.1566579342 0.1126058474 0.0915586757 0.1207897216 0.0059837222 0.4738550000 0.0644720000 0.0794690000 0.0000010000 0.3234130000 0.0017340000 142951643 0 402718720 3.8502871990 4.0497369766 3.8522684574 2001 1311867237.1925950050 0.1117353663 0.0915687590 0.1207897216 0.0059829020 0.8265020000 0.0646990000 0.0568660000 0.0312820000 0.3267310000 0.3423740000 142955427 0 402718720 3.8507790565 4.0496129990 3.8539929390 2002 1311867237.2254281044 0.1109329090 0.0915784314 0.1207897216 0.0059815687 0.4732960000 0.0651010000 0.0756190000 0.0000000000 0.3263340000 0.0016410000 142959155 0 402718720 3.8514130116 4.0481991768 3.8554272652 2003 1311867237.2569580078 0.1119147316 0.0915885843 0.1207897216 0.0059809087 0.5051790000 0.0656160000 0.0760520000 0.0308290000 0.3264260000 0.0016500000 142962827 0 402718720 3.8489220142 4.0471014977 3.8568713665 2004 1311867237.2944281101 0.1119732559 0.0915987563 0.1207897216 0.0059795996 0.4845830000 0.0758370000 0.0797730000 0.0000010000 0.3223110000 0.0018000000 142966611 0 402718720 3.8485813141 4.0486636162 3.8585250378 2005 1311867237.3250501156 0.1105049402 0.0916081859 0.1207897216 0.0059783436 0.8238630000 0.0656490000 0.0603890000 0.0308460000 0.3217980000 0.3405340000 142970283 0 402718720 3.8501555920 4.0483670235 3.8600120544 2006 1311867237.3565309048 0.1115890071 0.0916181464 0.1207897216 0.0059790546 0.4726460000 0.0652260000 0.0758350000 0.0000010000 0.3253490000 0.0016420000 142973955 0 402718720 3.8485336304 4.0472736359 3.8617680073 2007 1311867237.3934979439 0.1105707288 0.0916275896 0.1207897216 0.0059782192 0.5032260000 0.0652120000 0.0758830000 0.0312680000 0.3246580000 0.0016450000 142977683 0 402718720 3.8493053913 4.0488176346 3.8635668755 2008 1311867237.4248709679 0.1107006073 0.0916370881 0.1207897216 0.0059770099 0.4671370000 0.0865970000 0.0543160000 0.0000010000 0.3196900000 0.0017570000 142981411 0 402718720 3.8485321999 4.0473971367 3.8653297424 2009 1311867237.4579510689 0.1100057811 0.0916462313 0.1207897216 0.0059757737 0.8301500000 0.0801550000 0.0542960000 0.0308940000 0.3227940000 0.3373770000 142985083 0 402718720 3.8487195969 4.0457339287 3.8668663502 2010 1311867237.4933559895 0.1114088595 0.0916560635 0.1207897216 0.0059762296 0.4449440000 0.0658720000 0.0544770000 0.0000010000 0.3179980000 0.0017560000 142988867 0 402718720 3.8470623493 4.0475945473 3.8691909313 2011 1311867237.5253219604 0.1085265577 0.0916644526 0.1207897216 0.0059786994 0.5005520000 0.0659520000 0.0763890000 0.0312470000 0.3206940000 0.0016550000 142992539 0 402718720 3.8499269485 4.0461111069 3.8708865643 2012 1311867237.5581231117 0.1091446653 0.0916731406 0.1207897216 0.0059776099 0.4688890000 0.0658430000 0.0766410000 0.0000010000 0.3201420000 0.0016590000 142996267 0 402718720 3.8488872051 4.0447421074 3.8726000786 2013 1311867237.5925350189 0.1106902957 0.0916825877 0.1207897216 0.0059798915 0.8303330000 0.0661820000 0.0770190000 0.0307230000 0.3190320000 0.3327440000 142999939 0 402718720 3.8475141525 4.0458979607 3.8750808239 2014 1311867237.6261129379 0.1105646789 0.0916919632 0.1207897216 0.0059785405 0.4708880000 0.0815290000 0.0682480000 0.0000000000 0.3148440000 0.0016650000 143003723 0 402718720 3.8472599983 4.0451140404 3.8770258427 2015 1311867237.6569290161 0.1107598394 0.0917014261 0.1207897216 0.0059777850 0.4985990000 0.0654530000 0.0807870000 0.0311410000 0.3146340000 0.0017250000 143007339 0 402718720 3.8464174271 4.0435795784 3.8788821697 2016 1311867237.6925010681 0.1101973504 0.0917106007 0.1207897216 0.0059763956 0.4416010000 0.0657690000 0.0522550000 0.0000000000 0.3172690000 0.0016670000 143011067 0 402718720 3.8472685814 4.0441040993 3.8810267448 2017 1311867237.7243609428 0.1108177602 0.0917200738 0.1207897216 0.0059750160 0.8145460000 0.0675680000 0.0651890000 0.0312330000 0.3163730000 0.3295190000 143014739 0 402718720 3.8468425274 4.0440683365 3.8832800388 2018 1311867237.7617940903 0.1097204685 0.0917289937 0.1207897216 0.0059736899 0.4667080000 0.0672000000 0.0776290000 0.0000010000 0.3155860000 0.0016600000 143018635 0 402718720 3.8473043442 4.0422930717 3.8852210045 2019 1311867237.7926809788 0.1096600220 0.0917378748 0.1207897216 0.0059726796 0.4879080000 0.0773680000 0.0616540000 0.0312390000 0.3113820000 0.0016630000 143022195 0 402718720 3.8473448753 4.0433769226 3.8877618313 2020 1311867237.8255820274 0.1098908186 0.0917468614 0.1207897216 0.0059716861 0.4801410000 0.0675170000 0.0782600000 0.0000010000 0.3270670000 0.0022100000 143025923 0 402718720 3.8468127251 4.0436129570 3.8901281357 2021 1311867237.8612699509 0.1087586433 0.0917552789 0.1207897216 0.0059708713 0.8526550000 0.0860530000 0.0695710000 0.0379800000 0.3263730000 0.3280500000 143029763 0 402718720 3.8476376534 4.0428900719 3.8920495510 2022 1311867237.8926060200 0.1096125618 0.0917641104 0.1207897216 0.0059707922 0.4515770000 0.0681070000 0.0658450000 0.0000010000 0.3113310000 0.0016740000 143033379 0 402718720 3.8463988304 4.0434827805 3.8948485851 2023 1311867237.9253590107 0.1089241579 0.0917725929 0.1207897216 0.0059703182 0.4943590000 0.0683130000 0.0788290000 0.0311550000 0.3097330000 0.0016830000 143036995 0 402718720 3.8475325108 4.0427885056 3.8970949650 2024 1311867237.9613509178 0.1088937074 0.0917810520 0.1207897216 0.0059695438 0.4728910000 0.0794360000 0.0786900000 0.0000010000 0.3084980000 0.0016740000 143040779 0 402718720 3.8467919827 4.0418653488 3.8990528584 2025 1311867237.9928910732 0.1080352962 0.0917890787 0.1207897216 0.0059684873 0.8081510000 0.0684570000 0.0830260000 0.0312740000 0.3043870000 0.3161510000 143044451 0 402718720 3.8483493328 4.0420117378 3.9013068676 2026 1311867238.0245919228 0.1084688976 0.0917973116 0.1207897216 0.0059680961 0.4622380000 0.0687450000 0.0836610000 0.0000000000 0.3035330000 0.0016840000 143048067 0 402718720 3.8481595516 4.0426297188 3.9036469460 2027 1311867238.0607950687 0.1087311879 0.0918056658 0.1207897216 0.0059670980 0.4802940000 0.0909700000 0.0469510000 0.0311560000 0.3048470000 0.0016960000 143051851 0 402718720 3.8477337360 4.0411739349 3.9058208466 2028 1311867238.0932629108 0.1081233472 0.0918137120 0.1207897216 0.0059661650 0.4570610000 0.0671250000 0.0786190000 0.0000010000 0.3050480000 0.0016380000 143055523 0 402718720 3.8475544453 4.0388803482 3.9074435234 2029 1311867238.1251931190 0.1101662964 0.0918227571 0.1207897216 0.0059675708 0.7888630000 0.0802110000 0.0533720000 0.0306780000 0.3043180000 0.3156310000 143059195 0 402718720 3.8465211391 4.0409927368 3.9100618362 2030 1311867238.1608469486 0.1088624746 0.0918311511 0.1207897216 0.0059713611 0.4770190000 0.0691320000 0.0828940000 0.0000000000 0.3176110000 0.0022460000 143062979 0 402718720 3.8488690853 4.0414810181 3.9126231670 2031 1311867238.1928510666 0.1086861864 0.0918394499 0.1207897216 0.0059758990 0.5208070000 0.0876100000 0.0709950000 0.0378700000 0.3169860000 0.0022400000 143066651 0 402718720 3.8487908840 4.0407109261 3.9146347046 2032 1311867238.2246770859 0.1089932323 0.0918478918 0.1207897216 0.0059749226 0.5174260000 0.0878520000 0.1059370000 0.0000010000 0.3162100000 0.0022380000 143070323 0 402718720 3.8492853642 4.0414881706 3.9170911312 2033 1311867238.2605938911 0.1086534932 0.0918561582 0.1207897216 0.0059750139 0.8623250000 0.0902790000 0.1074160000 0.0385320000 0.3097090000 0.3117040000 143074107 0 402718720 3.8503940105 4.0408802032 3.9193375111 2034 1311867238.2926790714 0.1080182865 0.0918641042 0.1207897216 0.0059798480 0.4715280000 0.0840680000 0.0807160000 0.0000000000 0.3004030000 0.0016850000 143077723 0 402718720 3.8513464928 4.0384149551 3.9213700294 2035 1311867238.3257811069 0.1092564613 0.0918726508 0.1207897216 0.0059905126 0.4750750000 0.0701220000 0.0673350000 0.0311190000 0.3001480000 0.0017000000 143081507 0 402718720 3.8506436348 4.0394992828 3.9239046574 2036 1311867238.3604390621 0.1079550982 0.0918805498 0.1207897216 0.0059893555 0.4563640000 0.0703400000 0.0803230000 0.0000010000 0.2993640000 0.0016950000 143085235 0 402718720 3.8535068035 4.0390396118 3.9261596203 2037 1311867238.3936378956 0.1070958152 0.0918880193 0.1207897216 0.0059913453 0.7746460000 0.0895610000 0.0419740000 0.0311470000 0.2986000000 0.3087530000 143088963 0 402718720 3.8544011116 4.0374193192 3.9280588627 2038 1311867238.4264049530 0.1080713719 0.0918959601 0.1207897216 0.0059937491 0.4543230000 0.0683770000 0.0840000000 0.0000010000 0.2953370000 0.0017470000 143092635 0 402718720 3.8537092209 4.0361266136 3.9300158024 2039 1311867238.4616210461 0.1092042327 0.0919044487 0.1207897216 0.0059926414 0.4902370000 0.0708490000 0.0851740000 0.0311130000 0.2967530000 0.0017060000 143096419 0 402718720 3.8532779217 4.0367403030 3.9325528145 2040 1311867238.4932549000 0.1079116315 0.0919122953 0.1207897216 0.0059962584 0.4193060000 0.0702790000 0.0499840000 0.0000010000 0.2923550000 0.0017900000 143099979 0 402718720 3.8547534943 4.0357651711 3.9345703125 2041 1311867238.5248661041 0.1070864573 0.0919197300 0.1207897216 0.0059952785 0.7857650000 0.0709280000 0.0808380000 0.0311240000 0.2942600000 0.3038880000 143103707 0 402718720 3.8562457561 4.0338883400 3.9366257191 2042 1311867238.5605928898 0.1056965142 0.0919264767 0.1207897216 0.0060007968 0.4455430000 0.0708450000 0.0743810000 0.0000010000 0.2939500000 0.0016920000 143107491 0 402718720 3.8586146832 4.0340218544 3.9391815662 2043 1311867238.5929119587 0.1061974913 0.0919334620 0.1207897216 0.0060050953 0.4805070000 0.0701910000 0.0805730000 0.0305480000 0.2928330000 0.0016880000 143111107 0 402718720 3.8582413197 4.0326862335 3.9416532516 2044 1311867238.6249868870 0.1046010852 0.0919396595 0.1207897216 0.0060041138 0.4665900000 0.0856060000 0.0850260000 0.0000010000 0.2895880000 0.0016930000 143114835 0 402718720 3.8602728844 4.0319471359 3.9439821243 2045 1311867238.6608479023 0.1050455794 0.0919460683 0.1207897216 0.0060032009 0.7787190000 0.0707410000 0.0814140000 0.0310490000 0.2908620000 0.2999660000 143118619 0 402718720 3.8603484631 4.0321550369 3.9469082355 2046 1311867238.6929359436 0.1045573056 0.0919522321 0.1207897216 0.0060024155 0.4485510000 0.0711270000 0.0815280000 0.0000010000 0.2895260000 0.0016940000 143122291 0 402718720 3.8606340885 4.0314464569 3.9496879578 2047 1311867238.7246360779 0.1050401330 0.0919586258 0.1207897216 0.0060028626 0.4795100000 0.0707690000 0.0855020000 0.0310590000 0.2854710000 0.0017890000 143125907 0 402718720 3.8608162403 4.0307550430 3.9526531696 2048 1311867238.7627971172 0.1037829816 0.0919643994 0.1207897216 0.0060016078 0.4443660000 0.0956890000 0.0547570000 0.0000010000 0.2875500000 0.0016990000 143129747 0 402718720 3.8616685867 4.0312023163 3.9556751251 2049 1311867238.7949919701 0.1032965705 0.0919699300 0.1207897216 0.0060003089 0.7715980000 0.0717780000 0.0864700000 0.0305500000 0.2834530000 0.2945080000 143330083 0 402718720 3.8630778790 4.0309653282 3.9588148594 2050 1311867238.8246819973 0.1033890843 0.0919755003 0.1207897216 0.0060031034 0.4181590000 0.0720060000 0.0550350000 0.0000010000 0.2847270000 0.0017050000 143743243 0 402718720 3.8628435135 4.0292601585 3.9616708755 2051 1311867238.8630580902 0.1038314700 0.0919812809 0.1207897216 0.0060020048 0.4407600000 0.0718460000 0.0510530000 0.0309570000 0.2803870000 0.0017100000 143747139 0 402718720 3.8621146679 4.0298609734 3.9649548531 2052 1311867238.8933889866 0.1034996659 0.0919868942 0.1207897216 0.0060007434 0.4276570000 0.0720550000 0.0552570000 0.0000010000 0.2928520000 0.0022780000 143750755 0 402718720 3.8629605770 4.0300569534 3.9681820869 2053 1311867238.9278979301 0.1017959490 0.0919916721 0.1207897216 0.0060003171 0.8384570000 0.0924360000 0.1095490000 0.0376450000 0.2927560000 0.3008150000 143754539 0 402718720 3.8655109406 4.0286245346 3.9712433815 2054 1311867238.9628050327 0.1026300043 0.0919968514 0.1207897216 0.0060005331 0.5015380000 0.0926310000 0.1099820000 0.0000010000 0.2913990000 0.0022930000 143758323 0 402718720 3.8633620739 4.0265851021 3.9739940166 2055 1311867238.9937820435 0.1029595137 0.0920021860 0.1207897216 0.0060004385 0.4586560000 0.0922540000 0.0510320000 0.0309370000 0.2777380000 0.0017020000 143761883 0 402718720 3.8639774323 4.0272583961 3.9774942398 2056 1311867239.0287299156 0.1020494699 0.0920070728 0.1207897216 0.0060039549 0.4193590000 0.0719340000 0.0638470000 0.0000010000 0.2771910000 0.0016620000 143765667 0 402718720 3.8656775951 4.0271997452 3.9804689884 2057 1311867239.0619978905 0.1014433429 0.0920116602 0.1207897216 0.0060056517 0.7310350000 0.0718200000 0.0622820000 0.0308760000 0.2768170000 0.2845080000 143769451 0 402718720 3.8653986454 4.0250821114 3.9835069180 2058 1311867239.0939240456 0.1025403216 0.0920167762 0.1207897216 0.0060058592 0.4420510000 0.0951950000 0.0657400000 0.0000010000 0.2746760000 0.0016910000 143773011 0 402718720 3.8647320271 4.0258002281 3.9870424271 2059 1311867239.1358110905 0.1012833789 0.0920212767 0.1207897216 0.0060049102 0.4600620000 0.0836710000 0.0625070000 0.0309210000 0.2764890000 0.0017100000 143776963 0 402718720 3.8661522865 4.0251889229 3.9903688431 2060 1311867239.1620550156 0.1012413427 0.0920257525 0.1207897216 0.0060044881 0.4393280000 0.0721960000 0.0871690000 0.0000010000 0.2732110000 0.0018030000 143780467 0 402718720 3.8665325642 4.0239963531 3.9934217930 2061 1311867239.1936569214 0.1018012166 0.0920304956 0.1207897216 0.0060035014 0.7270730000 0.0723920000 0.0659640000 0.0308840000 0.2727040000 0.2801270000 143784083 0 402718720 3.8667712212 4.0234613419 3.9968976974 2062 1311867239.2294950485 0.1015869007 0.0920351301 0.1207897216 0.0060024360 0.4303860000 0.0720090000 0.0803240000 0.0000000000 0.2716100000 0.0016970000 143787867 0 402718720 3.8675243855 4.0230994225 4.0004510880 2063 1311867239.2609150410 0.1009655371 0.0920394589 0.1207897216 0.0060019314 0.4637820000 0.0707740000 0.0823550000 0.0306550000 0.2735750000 0.0016620000 143791539 0 402718720 3.8689961433 4.0212540627 4.0037288666 2064 1311867239.2928791046 0.1021495610 0.0920443572 0.1207897216 0.0060006805 0.4451350000 0.0812450000 0.0837320000 0.0000000000 0.2736750000 0.0017120000 143795155 0 402718720 3.8682003021 4.0196256638 4.0072183609 2065 1311867239.3295290470 0.1016956791 0.0920490310 0.1207897216 0.0059993339 0.7417520000 0.0708410000 0.0824020000 0.0301390000 0.2735200000 0.2800580000 143798995 0 402718720 3.8695256710 4.0195698738 4.0107660294 2066 1311867239.3615000248 0.1012628004 0.0920534907 0.1207897216 0.0059989042 0.4352360000 0.0722540000 0.0833890000 0.0000010000 0.2731560000 0.0017130000 143802667 0 402718720 3.8709905148 4.0181541443 4.0140385628 2067 1311867239.3928411007 0.1013874114 0.0920580064 0.1207897216 0.0059986291 0.4675060000 0.0726510000 0.0835360000 0.0308500000 0.2740150000 0.0017100000 143806339 0 402718720 3.8714048862 4.0158557892 4.0170655251 2068 1311867239.4293289185 0.1009566709 0.0920623094 0.1207897216 0.0060015594 0.4421670000 0.0848430000 0.0759200000 0.0000000000 0.2749220000 0.0016920000 143810067 0 402718720 3.8728368282 4.0152873993 4.0202937126 2069 1311867239.4619059563 0.1009238139 0.0920665924 0.1207897216 0.0060038864 0.7771990000 0.1039360000 0.0827570000 0.0307120000 0.2741520000 0.2808380000 143813851 0 402718720 3.8735616207 4.0133304596 4.0232992172 2070 1311867239.4938249588 0.1005068794 0.0920706699 0.1207897216 0.0060028687 0.4401610000 0.0720290000 0.0837820000 0.0000000000 0.2767560000 0.0022890000 143817467 0 402718720 3.8749372959 4.0113778114 4.0260710716 2071 1311867239.5295019150 0.1005245671 0.0920747519 0.1207897216 0.0060044035 0.4899210000 0.0917570000 0.0647410000 0.0371570000 0.2886590000 0.0022910000 143821251 0 402718720 3.8756775856 4.0099768639 4.0288019180 2072 1311867239.5617070198 0.1010634303 0.0920790901 0.1207897216 0.0060098547 0.4568910000 0.0910590000 0.0735910000 0.0000010000 0.2857960000 0.0016930000 143824923 0 402718720 3.8757719994 4.0102009773 4.0319352150 2073 1311867239.5944910049 0.1000468880 0.0920829337 0.1207897216 0.0060087816 0.7167360000 0.0718780000 0.0555190000 0.0307560000 0.2736650000 0.2800940000 143828595 0 402718720 3.8783361912 4.0082592964 4.0348348618 2074 1311867239.6284430027 0.0998219773 0.0920866651 0.1207897216 0.0060151104 0.4470020000 0.0809170000 0.0874230000 0.0000010000 0.2721930000 0.0016920000 143832323 0 402718720 3.8785262108 4.0059700012 4.0374078751 2075 1311867239.6623089314 0.0999438837 0.0920904517 0.1207897216 0.0060141162 0.4481100000 0.0724860000 0.0660600000 0.0307290000 0.2720130000 0.0018040000 143836107 0 402718720 3.8796904087 4.0062355995 4.0404644012 2076 1311867239.6931240559 0.0999360904 0.0920942309 0.1207897216 0.0060245860 0.4011560000 0.0720820000 0.0514800000 0.0000010000 0.2707770000 0.0018070000 143839667 0 402718720 3.8811149597 4.0064902306 4.0434803963 2077 1311867239.7284948826 0.0999466553 0.0920980116 0.1207897216 0.0060246043 0.7382470000 0.0709240000 0.0866930000 0.0300320000 0.2697440000 0.2760480000 143843451 0 402718720 3.8816483021 4.0056514740 4.0462241173 2078 1311867239.7614610195 0.0992590338 0.0921014577 0.1207897216 0.0060237755 0.4204320000 0.0720910000 0.0557880000 0.0000000000 0.2849460000 0.0022980000 143847235 0 402718720 3.8829231262 4.0048880577 4.0489087105 2079 1311867239.7926149368 0.0989072025 0.0921047313 0.1207897216 0.0060225939 0.4947780000 0.0927820000 0.0743480000 0.0370610000 0.2829620000 0.0022920000 143850795 0 402718720 3.8840858936 4.0062956810 4.0519981384 2080 1311867239.8308320045 0.0982378423 0.0921076799 0.1207897216 0.0060224500 0.4619340000 0.0940970000 0.0934480000 0.0000010000 0.2679210000 0.0017090000 143854691 0 402718720 3.8846981525 4.0050983429 4.0547428131 2081 1311867239.8608438969 0.0971639827 0.0921101096 0.1207897216 0.0060297121 0.7278360000 0.0735410000 0.0839520000 0.0306380000 0.2644490000 0.2704260000 143858307 0 402718720 3.8859395981 4.0043368340 4.0575928688 2082 1311867239.8929069042 0.0973181650 0.0921126111 0.1207897216 0.0060316935 0.4274980000 0.0734860000 0.0841850000 0.0000000000 0.2633600000 0.0017030000 143861979 0 402718720 3.8861498833 4.0042705536 4.0607118607 2083 1311867239.9306600094 0.0968274623 0.0921148746 0.1207897216 0.0060321344 0.4234970000 0.0739380000 0.0525310000 0.0306220000 0.2596030000 0.0018050000 143865819 0 402718720 3.8863062859 4.0033164024 4.0634603500 2084 1311867239.9613699913 0.0969473273 0.0921171934 0.1207897216 0.0060335455 0.4440090000 0.0896040000 0.0890040000 0.0000010000 0.2585910000 0.0018000000 143869491 0 402718720 3.8866920471 4.0035943985 4.0664610863 2085 1311867239.9948220253 0.0961513147 0.0921191283 0.1207897216 0.0060322466 0.6875700000 0.0723380000 0.0562240000 0.0303890000 0.2591790000 0.2646190000 143873163 0 402718720 3.8876545429 4.0026454926 4.0692677498 2086 1311867240.0292289257 0.0960715637 0.0921210230 0.1207897216 0.0060319676 0.3881250000 0.0739840000 0.0497530000 0.0000010000 0.2578470000 0.0017100000 143876891 0 402718720 3.8873386383 4.0015854836 4.0719776154 2087 1311867240.0618810654 0.0956217423 0.0921227004 0.1207897216 0.0060310499 0.4533310000 0.0742110000 0.0849200000 0.0305770000 0.2571140000 0.0017160000 143880619 0 402718720 3.8887815475 4.0020484924 4.0747265816 2088 1311867240.0945510864 0.0957349017 0.0921244304 0.1207897216 0.0060302405 0.3854450000 0.0730530000 0.0496790000 0.0000010000 0.2562050000 0.0017140000 143884235 0 402718720 3.8883478642 4.0019321442 4.0774426460 2089 1311867240.1297509670 0.0953893438 0.0921259933 0.1207897216 0.0060290955 0.7303460000 0.0881330000 0.0854950000 0.0300890000 0.2550650000 0.2667690000 143888019 0 402718720 3.8895592690 4.0014843941 4.0804882050 2090 1311867240.1617240906 0.0960123539 0.0921278528 0.1207897216 0.0060286835 0.4058940000 0.0944480000 0.0506810000 0.0000010000 0.2542360000 0.0017200000 143891691 0 402718720 3.8894166946 4.0019445419 4.0837531090 2091 1311867240.1963129044 0.0964609459 0.0921299250 0.1207897216 0.0060277750 0.4510560000 0.0748200000 0.0855070000 0.0304760000 0.2537100000 0.0017270000 143895475 0 402718720 3.8889472485 4.0011091232 4.0863347054 2092 1311867240.2291030884 0.0960759968 0.0921318113 0.1207897216 0.0060263674 0.3862370000 0.0751450000 0.0530180000 0.0000010000 0.2512290000 0.0018100000 143899147 0 402718720 3.8905637264 4.0008325577 4.0890564919 2093 1311867240.2612760067 0.0945191979 0.0921329520 0.1207897216 0.0060263922 0.6693160000 0.0756190000 0.0514740000 0.0300410000 0.2508310000 0.2565170000 143902875 0 402718720 3.8936221600 4.0012297630 4.0917644501 2094 1311867240.2981250286 0.0951684564 0.0921344016 0.1207897216 0.0060250826 0.4000520000 0.0751310000 0.0678910000 0.0000000000 0.2504910000 0.0017310000 143906491 0 402718720 3.8932232857 4.0005884171 4.0944666862 2095 1311867240.3289160728 0.0956933424 0.0921361004 0.1207897216 0.0060259139 0.4479010000 0.0741690000 0.0850830000 0.0303260000 0.2518210000 0.0017040000 143910163 0 402718720 3.8924031258 3.9994933605 4.0969576836 2096 1311867240.3609399796 0.0951158479 0.0921375220 0.1207897216 0.0060250813 0.4186340000 0.0753050000 0.0855690000 0.0000000000 0.2512450000 0.0017140000 143913891 0 402718720 3.8934974670 3.9984831810 4.0994796753 2097 1311867240.3967890739 0.0946481451 0.0921387192 0.1207897216 0.0060242600 0.7014380000 0.0748380000 0.0855100000 0.0299190000 0.2505180000 0.2558420000 143917563 0 402718720 3.8949041367 3.9979512691 4.1019010544 2098 1311867240.4286890030 0.0937289596 0.0921394772 0.1207897216 0.0060233693 0.3827460000 0.0754070000 0.0505720000 0.0000010000 0.2502110000 0.0017190000 143921123 0 402718720 3.8959255219 3.9957892895 4.1039633751 2099 1311867240.4650850296 0.0934392065 0.0921400964 0.1207897216 0.0060264500 0.4570810000 0.0874140000 0.0828620000 0.0300620000 0.2501920000 0.0017320000 143924963 0 402718720 3.8960642815 3.9943764210 4.1060924530 2100 1311867240.4972898960 0.0938809887 0.0921409254 0.1207897216 0.0060304243 0.3985640000 0.0751360000 0.0681470000 0.0000000000 0.2487330000 0.0017220000 143928635 0 402718720 3.8958811760 3.9940907955 4.1082439423 2101 1311867240.5309979916 0.0929605439 0.0921413155 0.1207897216 0.0060334248 0.6707170000 0.0739490000 0.0571170000 0.0297850000 0.2498780000 0.2551100000 143932363 0 402718720 3.8973829746 3.9924759865 4.1100254059 2102 1311867240.5608210564 0.0921156555 0.0921413033 0.1207897216 0.0060320691 0.3927630000 0.0864340000 0.0504010000 0.0000010000 0.2493650000 0.0017220000 143935979 0 402718720 3.8983016014 3.9922046661 4.1117911339 2103 1311867240.5965991020 0.0916456431 0.0921410676 0.1207897216 0.0060310561 0.4385150000 0.0887590000 0.0648190000 0.0305060000 0.2478660000 0.0017320000 143939763 0 402718720 3.8995206356 3.9913046360 4.1134161949 2104 1311867240.6290791035 0.0918138027 0.0921409121 0.1207897216 0.0060318248 0.4285660000 0.0859340000 0.0902350000 0.0000010000 0.2458510000 0.0017320000 143943435 0 402718720 3.8992559910 3.9892981052 4.1147603989 2105 1311867240.6622560024 0.0907865912 0.0921402687 0.1207897216 0.0060349289 0.6974260000 0.0750280000 0.0898870000 0.0304370000 0.2458300000 0.2513810000 143947107 0 402718720 3.9003245831 3.9886798859 4.1161026955 2106 1311867240.6968801022 0.0915465727 0.0921399868 0.1207897216 0.0060335408 0.3806270000 0.0757970000 0.0504360000 0.0000010000 0.2478150000 0.0017410000 143950835 0 402718720 3.8984673023 3.9883153439 4.1173930168 2107 1311867240.7291979790 0.0909399614 0.0921394173 0.1207897216 0.0060347232 0.4167610000 0.0753600000 0.0571900000 0.0304840000 0.2471350000 0.0017310000 143954507 0 402718720 3.8989748955 3.9886770248 4.1185879707 2108 1311867240.7625629902 0.0907739252 0.0921387695 0.1207897216 0.0060340688 0.4128650000 0.0750580000 0.0855490000 0.0000010000 0.2456630000 0.0017170000 143958179 0 402718720 3.8992447853 3.9887890816 4.1201791763 2109 1311867240.7965719700 0.0896103680 0.0921375706 0.1207897216 0.0060333372 0.6899650000 0.0885250000 0.0757270000 0.0304720000 0.2423900000 0.2479630000 143961963 0 402718720 3.8999588490 3.9884030819 4.1214756966 2110 1311867240.8293309212 0.0894724205 0.0921363075 0.1207897216 0.0060321855 0.3952960000 0.0746310000 0.0646600000 0.0000010000 0.2482980000 0.0023430000 143965635 0 402718720 3.8990232944 3.9889752865 4.1232624054 2111 1311867240.8621098995 0.0886824578 0.0921346714 0.1207897216 0.0060311285 0.4329150000 0.0971050000 0.0583610000 0.0303740000 0.2403710000 0.0017420000 143969363 0 402718720 3.8995203972 3.9893488884 4.1250400543 2112 1311867240.8973500729 0.0881154910 0.0921327684 0.1207897216 0.0060301796 0.4092150000 0.0770000000 0.0867210000 0.0000010000 0.2387640000 0.0017510000 143973147 0 402718720 3.8994357586 3.9898555279 4.1271429062 2113 1311867240.9290270805 0.0875994116 0.0921306229 0.1207897216 0.0060289927 0.6678620000 0.1029730000 0.0513980000 0.0299400000 0.2365260000 0.2420030000 143976763 0 402718720 3.8993892670 3.9906618595 4.1293559074 2114 1311867240.9614369869 0.0875676498 0.0921284645 0.1207897216 0.0060276119 0.3739800000 0.0889120000 0.0443210000 0.0000010000 0.2341400000 0.0017370000 143980435 0 402718720 3.8991146088 3.9912827015 4.1315760612 2115 1311867240.9968450069 0.0870527402 0.0921260646 0.1207897216 0.0060264760 0.4383850000 0.0776410000 0.0921560000 0.0304440000 0.2312080000 0.0018370000 143984275 0 402718720 3.8989467621 3.9913008213 4.1338958740 2116 1311867241.0315620899 0.0870251805 0.0921236540 0.1207897216 0.0060273986 0.3877930000 0.0906020000 0.0599490000 0.0000000000 0.2303050000 0.0018470000 143988003 0 402718720 3.8974201679 3.9921536446 4.1365213394 2117 1311867241.0633668900 0.0872598961 0.0921213565 0.1207897216 0.0060342777 0.6577050000 0.0765710000 0.0843610000 0.0302400000 0.2280760000 0.2333620000 143991563 0 402718720 3.8976397514 3.9941897392 4.1395649910 2118 1311867241.0990099907 0.0862351432 0.0921185774 0.1207897216 0.0060371350 0.4022420000 0.0782340000 0.0908130000 0.0000010000 0.2266100000 0.0016980000 143995403 0 402718720 3.8970692158 3.9926142693 4.1418375969 2119 1311867241.1285290718 0.0873404816 0.0921163225 0.1207897216 0.0060375611 0.4436080000 0.0904600000 0.0902670000 0.0298290000 0.2264370000 0.0017460000 143998963 0 402718720 3.8956532478 3.9923882484 4.1441311836 2120 1311867241.1641499996 0.0862194449 0.0921135409 0.1207897216 0.0060402182 0.3993160000 0.0782130000 0.0880460000 0.0000010000 0.2264400000 0.0017420000 144002803 0 402718720 3.8957805634 3.9933180809 4.1466226578 2121 1311867241.1980121136 0.0868007317 0.0921110361 0.1207897216 0.0060396318 0.6626000000 0.0792090000 0.0889050000 0.0298810000 0.2270920000 0.2326010000 144006475 0 402718720 3.8943171501 3.9926671982 4.1490592957 2122 1311867241.2313330173 0.0880596265 0.0921091268 0.1207897216 0.0060402540 0.3807780000 0.0785900000 0.0667010000 0.0000010000 0.2288130000 0.0017550000 144010259 0 402718720 3.8927178383 3.9937152863 4.1516551971 2123 1311867241.2640700340 0.0883078426 0.0921073363 0.1207897216 0.0060389252 0.4320030000 0.0782550000 0.0883690000 0.0303070000 0.2283880000 0.0017470000 144013875 0 402718720 3.8924410343 3.9948024750 4.1540174484 2124 1311867241.3000609875 0.0879683569 0.0921053876 0.1207897216 0.0060442221 0.4200320000 0.0929700000 0.0929600000 0.0000010000 0.2271670000 0.0018460000 144017715 0 402718720 3.8910601139 3.9932589531 4.1555233002 2125 1311867241.3294849396 0.0883854404 0.0921036371 0.1207897216 0.0060451932 0.6656120000 0.0782170000 0.0922240000 0.0302920000 0.2271880000 0.2325650000 144021275 0 402718720 3.8900437355 3.9938333035 4.1573810577 2126 1311867241.3612549305 0.0885501951 0.0921019657 0.1207897216 0.0060440957 0.4042080000 0.0781210000 0.0926670000 0.0000010000 0.2267830000 0.0017540000 144025003 0 402718720 3.8891105652 3.9934847355 4.1593151093 2127 1311867241.3981139660 0.0891118869 0.0921005599 0.1207897216 0.0060458219 0.3938810000 0.0778340000 0.0517200000 0.0297850000 0.2278790000 0.0017590000 144028731 0 402718720 3.8869922161 3.9922170639 4.1609678268 2128 1311867241.4300589561 0.0888855904 0.0920990491 0.1207897216 0.0060577447 0.3649120000 0.0777840000 0.0516610000 0.0000000000 0.2288780000 0.0017400000 144032459 0 402718720 3.8866670132 3.9928240776 4.1628351212 2129 1311867241.4652009010 0.0892065689 0.0920976905 0.1207897216 0.0060589307 0.6905900000 0.1009900000 0.0924050000 0.0302890000 0.2281860000 0.2337620000 144036187 0 402718720 3.8854520321 3.9933540821 4.1648421288 2130 1311867241.4969789982 0.0884118378 0.0920959600 0.1207897216 0.0060632344 0.3802030000 0.0777090000 0.0695010000 0.0000010000 0.2263060000 0.0017410000 144039803 0 402718720 3.8847625256 3.9926416874 4.1665682793 2131 1311867241.5331718922 0.0888435915 0.0920944338 0.1207897216 0.0060647195 0.4396320000 0.0760250000 0.0868310000 0.0297700000 0.2392160000 0.0023720000 144043643 0 402718720 3.8837618828 3.9930088520 4.1682538986 2132 1311867241.5656960011 0.0882487968 0.0920926300 0.1207897216 0.0060647062 0.4641330000 0.0999130000 0.1170750000 0.0000010000 0.2393480000 0.0023740000 144047315 0 402718720 3.8832452297 3.9929103851 4.1697640419 2133 1311867241.6002480984 0.0886347368 0.0920910089 0.1207897216 0.0060648174 0.6833600000 0.0994430000 0.0593880000 0.0363320000 0.2385460000 0.2441380000 144051043 0 402718720 3.8818969727 3.9913408756 4.1708483696 2134 1311867241.6291201115 0.0887717232 0.0920894535 0.1207897216 0.0060637567 0.4345820000 0.0988850000 0.0970080000 0.0000010000 0.2320090000 0.0017590000 144054659 0 402718720 3.8819439411 3.9919824600 4.1720070839 2135 1311867241.6646790504 0.0879308954 0.0920875057 0.1207897216 0.0060686608 0.3913310000 0.0778720000 0.0516350000 0.0302370000 0.2248780000 0.0017470000 144058387 0 402718720 3.8819241524 3.9928331375 4.1730747223 2136 1311867241.6999258995 0.0877350792 0.0920854680 0.1207897216 0.0060691128 0.3922820000 0.0781990000 0.0852070000 0.0000010000 0.2219280000 0.0018470000 144062171 0 402718720 3.8811151981 3.9919359684 4.1738820076 2137 1311867241.7297649384 0.0888073891 0.0920839341 0.1207897216 0.0060800323 0.6453990000 0.0941640000 0.0678300000 0.0297350000 0.2211260000 0.2275900000 144065731 0 402718720 3.8809089661 3.9924180508 4.1747417450 2138 1311867241.7676639557 0.0880524144 0.0920820484 0.1207897216 0.0060789552 0.3828190000 0.0783040000 0.0777010000 0.0000010000 0.2198010000 0.0018500000 144069627 0 402718720 3.8805561066 3.9931721687 4.1756820679 2139 1311867241.7974851131 0.0881272554 0.0920801995 0.1207897216 0.0060784738 0.3987310000 0.0976790000 0.0446510000 0.0302080000 0.2195020000 0.0017550000 144073187 0 402718720 3.8798561096 3.9924111366 4.1765303612 2140 1311867241.8296549320 0.0883631036 0.0920784625 0.1207897216 0.0060780209 0.3588450000 0.0787710000 0.0547590000 0.0000010000 0.2183270000 0.0018490000 144076859 0 402718720 3.8781509399 3.9923100471 4.1774058342 2141 1311867241.8668920994 0.0875342488 0.0920763401 0.1207897216 0.0060774807 0.6607480000 0.0913120000 0.0928340000 0.0301700000 0.2178530000 0.2233990000 144080699 0 402718720 3.8783817291 3.9927256107 4.1786503792 2142 1311867241.8979690075 0.0883338675 0.0920745929 0.1207897216 0.0060765414 0.3953560000 0.0782960000 0.0926860000 0.0000010000 0.2174110000 0.0018500000 144084315 0 402718720 3.8772923946 3.9925808907 4.1802167892 2143 1311867241.9292619228 0.0880722776 0.0920727253 0.1207897216 0.0060756625 0.4249280000 0.0783160000 0.0926400000 0.0297070000 0.2175830000 0.0017510000 144087987 0 402718720 3.8770883083 3.9932506084 4.1821689606 2144 1311867241.9654040337 0.0872854814 0.0920704924 0.1207897216 0.0060743726 0.3993530000 0.0883480000 0.0887900000 0.0000010000 0.2155190000 0.0017580000 144091771 0 402718720 3.8767480850 3.9938621521 4.1843242645 2145 1311867241.9974029064 0.0876022801 0.0920684093 0.1207897216 0.0060745135 0.5888410000 0.0789430000 0.0447970000 0.0301450000 0.2123090000 0.2177110000 144095443 0 402718720 3.8758668900 3.9931395054 4.1862311363 2146 1311867242.0296339989 0.0875167474 0.0920662883 0.1207897216 0.0060745618 0.3858700000 0.0788630000 0.0887340000 0.0000010000 0.2114120000 0.0017470000 144099115 0 402718720 3.8760743141 3.9934225082 4.1881709099 2147 1311867242.0670061111 0.0872413367 0.0920640410 0.1207897216 0.0060734385 0.4144070000 0.0796150000 0.0893960000 0.0301420000 0.2085370000 0.0017610000 144102955 0 402718720 3.8756623268 3.9948723316 4.1902008057 2148 1311867242.0972509384 0.0870207474 0.0920616931 0.1207897216 0.0060742848 0.3344400000 0.0775740000 0.0446610000 0.0000010000 0.2054890000 0.0017510000 144106571 0 402718720 3.8754706383 3.9935481548 4.1917214394 2149 1311867242.1308040619 0.0872839913 0.0920594699 0.1207897216 0.0060764218 0.5912980000 0.0898660000 0.0525730000 0.0301650000 0.2041220000 0.2096010000 144110243 0 402718720 3.8752717972 3.9948136806 4.1933450699 2150 1311867242.1670179367 0.0867561400 0.0920570032 0.1207897216 0.0060772561 0.3710310000 0.1018220000 0.0613700000 0.0000010000 0.2008090000 0.0018720000 144113971 0 402718720 3.8752782345 3.9943487644 4.1946587563 2151 1311867242.1982409954 0.0867441297 0.0920545333 0.1207897216 0.0060776316 0.3723100000 0.0795590000 0.0552400000 0.0301720000 0.2002720000 0.0018450000 144117587 0 402718720 3.8745672703 3.9936351776 4.1959686279 2152 1311867242.2334370613 0.0871836320 0.0920522699 0.1207897216 0.0060800874 0.3930580000 0.0920860000 0.0940010000 0.0000010000 0.2002920000 0.0017620000 144121371 0 402718720 3.8733050823 3.9949805737 4.1977472305 2153 1311867242.2696599960 0.0864999741 0.0920496910 0.1207897216 0.0060787162 0.6388430000 0.0799650000 0.0895180000 0.0335400000 0.2123210000 0.2180250000 144125155 0 402718720 3.8740289211 3.9948329926 4.1994681358 2154 1311867242.2982430458 0.0871036202 0.0920473948 0.1207897216 0.0060774752 0.3830590000 0.1024160000 0.0606590000 0.0000000000 0.2120620000 0.0023990000 144128715 0 402718720 3.8729617596 3.9941618443 4.2011532784 2155 1311867242.3293490410 0.0872524008 0.0920451697 0.1207897216 0.0060765405 0.3801560000 0.0990240000 0.0454700000 0.0300910000 0.1988360000 0.0017620000 144132387 0 402718720 3.8723936081 3.9945199490 4.2030906677 2156 1311867242.3659460545 0.0872602910 0.0920429504 0.1207897216 0.0060772784 0.3401880000 0.0801050000 0.0554090000 0.0000010000 0.1976730000 0.0018560000 144136171 0 402718720 3.8721535206 3.9942948818 4.2048039436 2157 1311867242.3974800110 0.0876666456 0.0920409215 0.1207897216 0.0060767059 0.6017280000 0.0799290000 0.0673450000 0.0300830000 0.2016310000 0.2171970000 144139843 0 402718720 3.8721411228 3.9940254688 4.2065582275 2158 1311867242.4322769642 0.0880611986 0.0920390773 0.1207897216 0.0060753268 0.4409710000 0.1026070000 0.1194470000 0.0000010000 0.2109770000 0.0023960000 144143627 0 402718720 3.8711850643 3.9934942722 4.2082052231 2159 1311867242.4648990631 0.0883196294 0.0920373546 0.1207897216 0.0060749714 0.4389570000 0.1030910000 0.0805070000 0.0367430000 0.2106600000 0.0024090000 144147243 0 402718720 3.8707201481 3.9927456379 4.2095913887 2160 1311867242.4975609779 0.0882971659 0.0920356230 0.1207897216 0.0060736518 0.3924490000 0.1026750000 0.0704810000 0.0000010000 0.2113890000 0.0024060000 144150915 0 402718720 3.8702986240 3.9925529957 4.2108435631 2161 1311867242.5292570591 0.0881048962 0.0920338040 0.1207897216 0.0060724270 0.6279120000 0.1020730000 0.0875410000 0.0300820000 0.1988710000 0.2043380000 144154587 0 402718720 3.8705019951 3.9927387238 4.2122950554 2162 1311867242.5650939941 0.0879868716 0.0920319322 0.1207897216 0.0060713238 0.3474840000 0.0804920000 0.0613760000 0.0000000000 0.1985250000 0.0018650000 144158427 0 402718720 3.8699359894 3.9914269447 4.2135229111 2163 1311867242.5985031128 0.0884405449 0.0920302718 0.1207897216 0.0060700232 0.3634520000 0.0796890000 0.0475950000 0.0296110000 0.1995220000 0.0018390000 144162155 0 402718720 3.8691511154 3.9914512634 4.2150869370 2164 1311867242.6305589676 0.0884675011 0.0920286254 0.1207897216 0.0060687209 0.3721370000 0.1038350000 0.0605170000 0.0000000000 0.2010320000 0.0017550000 144165771 0 402718720 3.8695971966 3.9907798767 4.2166299820 2165 1311867242.6692740917 0.0882042870 0.0920268590 0.1207897216 0.0060677479 0.6193430000 0.0802880000 0.0947470000 0.0300790000 0.2013890000 0.2078220000 144169667 0 402718720 3.8683667183 3.9904789925 4.2182426453 2166 1311867242.6981039047 0.0879247412 0.0920249651 0.1207897216 0.0060667516 0.3789990000 0.0799240000 0.0894780000 0.0000010000 0.2028640000 0.0017610000 144173227 0 402718720 3.8693068027 3.9914565086 4.2202243805 2167 1311867242.7372829914 0.0877137855 0.0920229757 0.1207897216 0.0060663688 0.4039090000 0.0803670000 0.0867930000 0.0300870000 0.1995730000 0.0018480000 144177067 0 402718720 3.8697657585 3.9916579723 4.2224178314 2168 1311867242.7656900883 0.0876752809 0.0920209703 0.1207897216 0.0060663739 0.3659860000 0.0806950000 0.0793850000 0.0000010000 0.1991250000 0.0017740000 144180683 0 402718720 3.8695285320 3.9895350933 4.2240715027 2169 1311867242.7994089127 0.0883345380 0.0920192707 0.1207897216 0.0060691688 0.5753390000 0.0806120000 0.0530840000 0.0300340000 0.2005780000 0.2060240000 144184355 0 402718720 3.8688328266 3.9907343388 4.2261147499 2170 1311867242.8355538845 0.0876090750 0.0920172383 0.1207897216 0.0060699306 0.3772490000 0.0804300000 0.0901560000 0.0000010000 0.1999010000 0.0017470000 144188195 0 402718720 3.8693611622 3.9912383556 4.2281613350 2171 1311867242.8666720390 0.0874296203 0.0920151252 0.1207897216 0.0060700377 0.3627460000 0.0808500000 0.0455660000 0.0300110000 0.1995050000 0.0017620000 144191867 0 402718720 3.8700284958 3.9902260303 4.2300066948 2172 1311867242.8980929852 0.0890079513 0.0920137407 0.1207897216 0.0060940464 0.3404510000 0.0810870000 0.0532010000 0.0000010000 0.1993850000 0.0017560000 144195483 0 402718720 3.8690030575 3.9911360741 4.2321066856 2173 1311867242.9335498810 0.0881191120 0.0920119484 0.1207897216 0.0061210715 0.6080250000 0.0810720000 0.0903890000 0.0300170000 0.1980260000 0.2034870000 144199267 0 402718720 3.8689849377 3.9908616543 4.2340769768 2174 1311867242.9649999142 0.0887331516 0.0920104402 0.1207897216 0.0061234891 0.3706050000 0.0960110000 0.0715670000 0.0000000000 0.1961730000 0.0017980000 144202939 0 402718720 3.8682672977 3.9904668331 4.2359580994 2175 1311867242.9970819950 0.0885904059 0.0920088678 0.1207897216 0.0061224196 0.3687380000 0.0806490000 0.0552040000 0.0298960000 0.1961970000 0.0017590000 144206555 0 402718720 3.8684704304 3.9898982048 4.2377195358 2176 1311867243.0332529545 0.0895516947 0.0920077386 0.1207897216 0.0061212187 0.3473250000 0.0920940000 0.0530710000 0.0000010000 0.1953100000 0.0017480000 144210339 0 402718720 3.8681526184 3.9899694920 4.2396974564 2177 1311867243.0648689270 0.0883707479 0.0920060679 0.1207897216 0.0061200024 0.6034430000 0.0809340000 0.0950790000 0.0299770000 0.1932760000 0.1989380000 144214011 0 402718720 3.8680610657 3.9896564484 4.2415132523 2178 1311867243.0972158909 0.0882704034 0.0920043527 0.1207897216 0.0061187441 0.3735940000 0.0810870000 0.0933000000 0.0000010000 0.1921130000 0.0018500000 144217683 0 402718720 3.8678824902 3.9893357754 4.2434282303 2179 1311867243.1357100010 0.0870952979 0.0920020998 0.1207897216 0.0061250939 0.4297750000 0.1073410000 0.0944550000 0.0294060000 0.1917230000 0.0017700000 144221523 0 402718720 3.8673858643 3.9883410931 4.2452583313 2180 1311867243.1655960083 0.0888503268 0.0920006541 0.1207897216 0.0061337249 0.3339900000 0.0813740000 0.0545990000 0.0000010000 0.1912210000 0.0017710000 144225139 0 402718720 3.8656854630 3.9885103703 4.2472558022 2181 1311867243.1977169514 0.0891401023 0.0919993425 0.1207897216 0.0061336153 0.5708100000 0.0815750000 0.0683360000 0.0299210000 0.1902070000 0.1956790000 144228755 0 402718720 3.8651826382 3.9883153439 4.2491655350 2182 1311867243.2358860970 0.0887633711 0.0919978595 0.1207897216 0.0061342024 0.3791810000 0.0924890000 0.0904370000 0.0000010000 0.1894380000 0.0017530000 144232651 0 402718720 3.8643329144 3.9869513512 4.2509918213 2183 1311867243.2649240494 0.0891731605 0.0919965655 0.1207897216 0.0061329958 0.3673820000 0.0813070000 0.0605660000 0.0294280000 0.1892530000 0.0017630000 144236155 0 402718720 3.8638613224 3.9864323139 4.2528495789 2184 1311867243.2970221043 0.0887235925 0.0919950669 0.1207897216 0.0061317611 0.3706950000 0.1063210000 0.0682780000 0.0000010000 0.1892870000 0.0017600000 144239883 0 402718720 3.8638594151 3.9860720634 4.2546176910 2185 1311867243.3327538967 0.0887785852 0.0919935948 0.1207897216 0.0061314122 0.5577940000 0.0798730000 0.0603770000 0.0297600000 0.1887550000 0.1939110000 144243611 0 402718720 3.8630046844 3.9850363731 4.2564005852 2186 1311867243.3681559563 0.0893938914 0.0919924056 0.1207897216 0.0061302845 0.3480710000 0.0815920000 0.0718380000 0.0000010000 0.1874950000 0.0018720000 144247395 0 402718720 3.8618624210 3.9849402905 4.2583546638 2187 1311867243.4021821022 0.0894072577 0.0919912235 0.1207897216 0.0061289397 0.3832150000 0.1032690000 0.0562200000 0.0299100000 0.1866650000 0.0018760000 144251123 0 402718720 3.8618550301 3.9844729900 4.2600817680 2188 1311867243.4344329834 0.0896671936 0.0919901614 0.1207897216 0.0061287531 0.3553290000 0.0818520000 0.0799670000 0.0000010000 0.1863810000 0.0018460000 144254795 0 402718720 3.8615450859 3.9841587543 4.2618412971 2189 1311867243.4665510654 0.0891831443 0.0919888790 0.1207897216 0.0061275675 0.5558190000 0.0821510000 0.0612220000 0.0298920000 0.1860170000 0.1914960000 144258467 0 402718720 3.8613982201 3.9847276211 4.2638230324 2190 1311867243.4982140064 0.0896449387 0.0919878087 0.1207897216 0.0061266135 0.3386670000 0.0933160000 0.0536430000 0.0000010000 0.1848680000 0.0017670000 144262083 0 402718720 3.8607664108 3.9842712879 4.2657523155 2191 1311867243.5339779854 0.0898482800 0.0919868322 0.1207897216 0.0061253568 0.3718260000 0.0823840000 0.0686860000 0.0298580000 0.1840730000 0.0017750000 144265923 0 402718720 3.8604359627 3.9841179848 4.2675070763 2192 1311867243.5669720173 0.0891922563 0.0919855573 0.1207897216 0.0061244112 0.3415140000 0.0826010000 0.0689340000 0.0000010000 0.1831710000 0.0017570000 144269651 0 402718720 3.8608438969 3.9837973118 4.2692551613 2193 1311867243.5978341103 0.0893853307 0.0919843716 0.1207897216 0.0061231496 0.5488920000 0.0823560000 0.0612650000 0.0298090000 0.1824120000 0.1879640000 144273267 0 402718720 3.8604335785 3.9829154015 4.2707972527 2194 1311867243.6333720684 0.0897566155 0.0919833562 0.1207897216 0.0061245646 0.3382370000 0.0953480000 0.0536500000 0.0000000000 0.1823810000 0.0017720000 144276995 0 402718720 3.8606452942 3.9832937717 4.2725348473 2195 1311867243.6661529541 0.0903101638 0.0919825940 0.1207897216 0.0061232701 0.3578760000 0.0830150000 0.0568770000 0.0298590000 0.1809670000 0.0018590000 144280723 0 402718720 3.8602759838 3.9831702709 4.2742276192 2196 1311867243.6981849670 0.0900266021 0.0919817033 0.1207897216 0.0061228790 0.3351330000 0.0828230000 0.0644870000 0.0000010000 0.1806380000 0.0018790000 144284339 0 402718720 3.8609981537 3.9820916653 4.2756562233 2197 1311867243.7344710827 0.0898480117 0.0919807321 0.1207897216 0.0061219660 0.5336790000 0.0827260000 0.0489350000 0.0298010000 0.1806060000 0.1863140000 144288179 0 402718720 3.8607456684 3.9827799797 4.2774081230 2198 1311867243.7666299343 0.0900273174 0.0919798434 0.1207897216 0.0061213869 0.3430250000 0.0830950000 0.0728480000 0.0000010000 0.1801890000 0.0017620000 144291907 0 402718720 3.8612625599 3.9825041294 4.2791895866 2199 1311867243.7979769707 0.0897708088 0.0919788388 0.1207897216 0.0061203274 0.3593180000 0.0955560000 0.0465400000 0.0297940000 0.1805870000 0.0017850000 144295523 0 402718720 3.8623590469 3.9821696281 4.2809853554 2200 1311867243.8330240250 0.0898385495 0.0919778659 0.1207897216 0.0061190140 0.3252430000 0.0833430000 0.0543780000 0.0000000000 0.1804210000 0.0019270000 144299251 0 402718720 3.8620703220 3.9827001095 4.2828979492 2201 1311867243.8647689819 0.0905418918 0.0919772135 0.1207897216 0.0061184700 0.5664750000 0.1028080000 0.0651460000 0.0292940000 0.1790800000 0.1850600000 144302923 0 402718720 3.8624629974 3.9820117950 4.2848291397 2202 1311867243.8968739510 0.0910030603 0.0919767711 0.1207897216 0.0061173328 0.3262740000 0.0830950000 0.0568010000 0.0000010000 0.1792430000 0.0018740000 144306651 0 402718720 3.8621883392 3.9816100597 4.2864346504 2203 1311867243.9329960346 0.0911128223 0.0919763790 0.1207897216 0.0061165030 0.3965800000 0.0832560000 0.0969020000 0.0297810000 0.1798000000 0.0017760000 144310379 0 402718720 3.8627278805 3.9816992283 4.2881321907 2204 1311867243.9660589695 0.0913137123 0.0919760783 0.1207897216 0.0061153111 0.3361780000 0.0989000000 0.0502960000 0.0000000000 0.1800460000 0.0017750000 144314107 0 402718720 3.8626275063 3.9811153412 4.2895641327 2205 1311867244.0016739368 0.0908973739 0.0919755891 0.1207897216 0.0061147485 0.5410710000 0.0835470000 0.0580660000 0.0298090000 0.1792710000 0.1851050000 144317891 0 402718720 3.8634455204 3.9807219505 4.2911386490 2206 1311867244.0341379642 0.0905048624 0.0919749224 0.1207897216 0.0061136629 0.3628040000 0.0837900000 0.0924890000 0.0000010000 0.1796580000 0.0017790000 144321563 0 402718720 3.8641812801 3.9806509018 4.2926597595 2207 1311867244.0655789375 0.0909339264 0.0919744507 0.1207897216 0.0061125030 0.3913950000 0.0835520000 0.0920490000 0.0297600000 0.1791530000 0.0017740000 144325235 0 402718720 3.8639509678 3.9802100658 4.2942810059 2208 1311867244.1010930538 0.0907297805 0.0919738870 0.1207897216 0.0061112772 0.3154010000 0.0833680000 0.0464740000 0.0000000000 0.1787060000 0.0017780000 144329019 0 402718720 3.8641371727 3.9797492027 4.2960262299 2209 1311867244.1353089809 0.0904660150 0.0919732044 0.1207897216 0.0061102626 0.5516590000 0.0938260000 0.0617920000 0.0297470000 0.1777750000 0.1834090000 144332747 0 402718720 3.8649690151 3.9791905880 4.2978281975 2210 1311867244.1648418903 0.0906860083 0.0919726220 0.1207897216 0.0061089734 0.3576690000 0.0820210000 0.0916550000 0.0000000000 0.1771640000 0.0017230000 144336307 0 402718720 3.8648650646 3.9786057472 4.2996101379 2211 1311867244.2024741173 0.0897963420 0.0919716377 0.1207897216 0.0061076510 0.3661090000 0.0839820000 0.0696620000 0.0291850000 0.1764320000 0.0017930000 144340203 0 402718720 3.8655204773 3.9787724018 4.3015890121 2212 1311867244.2330279350 0.0898426026 0.0919706752 0.1207897216 0.0061063673 0.3182200000 0.0820930000 0.0539780000 0.0000000000 0.1753120000 0.0017490000 144343819 0 402718720 3.8665227890 3.9787011147 4.3037223816 2213 1311867244.2649021149 0.0895331427 0.0919695737 0.1207897216 0.0061055479 0.5357880000 0.0844470000 0.0621290000 0.0297200000 0.1743800000 0.1799610000 144347435 0 402718720 3.8675160408 3.9776639938 4.3057398796 2214 1311867244.3010311127 0.0896222368 0.0919685135 0.1207897216 0.0061049681 0.3100030000 0.0822120000 0.0464970000 0.0000010000 0.1744660000 0.0017320000 144351275 0 402718720 3.8675510883 3.9782989025 4.3080058098 2215 1311867244.3355190754 0.0890735537 0.0919672065 0.1207897216 0.0061038893 0.4072620000 0.1024200000 0.0958420000 0.0291910000 0.1725530000 0.0018710000 144355003 0 402718720 3.8688676357 3.9785685539 4.3101401329 2216 1311867244.3649079800 0.0895949900 0.0919661360 0.1207897216 0.0061031550 0.3608120000 0.0842300000 0.0974300000 0.0000010000 0.1719490000 0.0018630000 144358563 0 402718720 3.8693082333 3.9778051376 4.3121075630 2217 1311867244.4008760452 0.0899087861 0.0919652080 0.1207897216 0.0061026455 0.5303280000 0.0838420000 0.0633120000 0.0296250000 0.1712420000 0.1769840000 144362347 0 402718720 3.8693604469 3.9783909321 4.3142700195 2218 1311867244.4329938889 0.0894223005 0.0919640615 0.1207897216 0.0061029768 0.3538510000 0.0831720000 0.0928260000 0.0000010000 0.1709770000 0.0017630000 144366019 0 402718720 3.8703966141 3.9782726765 4.3163394928 2219 1311867244.4654510021 0.0891348794 0.0919627865 0.1207897216 0.0061023590 0.3662410000 0.0968140000 0.0621790000 0.0296610000 0.1706620000 0.0017730000 144369747 0 402718720 3.8714511395 3.9783020020 4.3183798790 2220 1311867244.5052490234 0.0883934200 0.0919611787 0.1207897216 0.0061016071 0.3170480000 0.0845540000 0.0547330000 0.0000010000 0.1708300000 0.0017830000 144373643 0 402718720 3.8728380203 3.9792110920 4.3206148148 2221 1311867244.5330989361 0.0885949954 0.0919596631 0.1207897216 0.0061005131 0.5429220000 0.0845710000 0.0776200000 0.0296270000 0.1701900000 0.1757920000 144377147 0 402718720 3.8734655380 3.9796557426 4.3229584694 2222 1311867244.5669400692 0.0888815299 0.0919582778 0.1207897216 0.0060992074 0.3312650000 0.0845100000 0.0699390000 0.0000000000 0.1698780000 0.0017840000 144380819 0 402718720 3.8733890057 3.9799320698 4.3251729012 2223 1311867244.6027030945 0.0889198929 0.0919569110 0.1207897216 0.0061033421 0.3378070000 0.0847540000 0.0471830000 0.0296650000 0.1692750000 0.0017920000 144384491 0 402718720 3.8743345737 3.9814503193 4.3277606964 2224 1311867244.6328020096 0.0890450776 0.0919556017 0.1207897216 0.0061036394 0.3611310000 0.0936980000 0.0932110000 0.0000010000 0.1673480000 0.0017830000 144388051 0 402718720 3.8749895096 3.9812023640 4.3301854134 2225 1311867244.6672449112 0.0894237012 0.0919544638 0.1207897216 0.0061027125 0.5234170000 0.0961790000 0.0550020000 0.0290620000 0.1661970000 0.1718280000 144391835 0 402718720 3.8751845360 3.9808814526 4.3325452805 2226 1311867244.7012600899 0.0893415660 0.0919532900 0.1207897216 0.0061016144 0.3506990000 0.0848260000 0.0933960000 0.0000010000 0.1655810000 0.0017670000 144395563 0 402718720 3.8762309551 3.9807963371 4.3348827362 2227 1311867244.7346320152 0.0895934999 0.0919522304 0.1207897216 0.0061006236 0.3332230000 0.0846740000 0.0469720000 0.0295710000 0.1649680000 0.0017960000 144399235 0 402718720 3.8766415119 3.9809291363 4.3371086121 2228 1311867244.7650001049 0.0896450281 0.0919511948 0.1207897216 0.0060993779 0.3160730000 0.0827860000 0.0620710000 0.0000000000 0.1643020000 0.0017760000 144402851 0 402718720 3.8774318695 3.9814608097 4.3393859863 2229 1311867244.8015320301 0.0893676654 0.0919500358 0.1207897216 0.0060982619 0.5473160000 0.0856600000 0.0952150000 0.0295340000 0.1630800000 0.1686600000 144406691 0 402718720 3.8786108494 3.9813458920 4.3416814804 2230 1311867244.8331909180 0.0894376636 0.0919489091 0.1207897216 0.0060973574 0.3529560000 0.0850490000 0.0984680000 0.0000010000 0.1621650000 0.0018700000 144410307 0 402718720 3.8788151741 3.9805381298 4.3435702324 2231 1311867244.8651568890 0.0894357562 0.0919477827 0.1207897216 0.0060961010 0.3811170000 0.0848680000 0.0973070000 0.0295380000 0.1624700000 0.0017780000 144414035 0 402718720 3.8795626163 3.9812402725 4.3459043503 2232 1311867244.9013550282 0.0893794894 0.0919466320 0.1207897216 0.0060948122 0.3400310000 0.0855400000 0.0861000000 0.0000010000 0.1614180000 0.0017750000 144417819 0 402718720 3.8797090054 3.9811980724 4.3479313850 2233 1311867244.9328739643 0.0891385227 0.0919453745 0.1207897216 0.0060935295 0.5638060000 0.0851960000 0.0934510000 0.0295800000 0.1708600000 0.1790620000 144421379 0 402718720 3.8802924156 3.9808666706 4.3499045372 2234 1311867244.9652509689 0.0890204906 0.0919440652 0.1207897216 0.0060923479 0.3519940000 0.1084820000 0.0633960000 0.0000010000 0.1719300000 0.0024290000 144425107 0 402718720 3.8802466393 3.9816801548 4.3521933556 2235 1311867245.0022718906 0.0892408639 0.0919428557 0.1207897216 0.0060919811 0.3864820000 0.1085230000 0.0632630000 0.0358140000 0.1707660000 0.0024400000 144429003 0 402718720 3.8802282810 3.9807670116 4.3542928696 2236 1311867245.0349979401 0.0894701257 0.0919417498 0.1207897216 0.0060920362 0.3820560000 0.1091090000 0.0941250000 0.0000000000 0.1706190000 0.0024510000 144432619 0 402718720 3.8803040981 3.9810576439 4.3563275337 2237 1311867245.0664730072 0.0893446058 0.0919405888 0.1207897216 0.0060907164 0.6071220000 0.1086420000 0.1247320000 0.0350780000 0.1697300000 0.1637560000 144436291 0 402718720 3.8803207874 3.9815969467 4.3585848808 2238 1311867245.1041638851 0.0890618414 0.0919393025 0.1207897216 0.0060900781 0.3009840000 0.0830840000 0.0544770000 0.0000000000 0.1564490000 0.0017860000 144440075 0 402718720 3.8803069592 3.9812235832 4.3603549004 2239 1311867245.1338050365 0.0895827636 0.0919382500 0.1207897216 0.0060890833 0.3365560000 0.0950500000 0.0496890000 0.0289910000 0.1555140000 0.0018660000 144443691 0 402718720 3.8802914619 3.9808218479 4.3623518944 2240 1311867245.1749250889 0.0889215320 0.0919369033 0.1207897216 0.0060878621 0.3381350000 0.0853450000 0.0905740000 0.0000000000 0.1549730000 0.0018630000 144447699 0 402718720 3.8799691200 3.9815068245 4.3643708229 2241 1311867245.2108979225 0.0885221586 0.0919353795 0.1207897216 0.0060865444 0.4988710000 0.0853780000 0.0636560000 0.0295060000 0.1547290000 0.1603610000 144451483 0 402718720 3.8795728683 3.9812574387 4.3662633896 2242 1311867245.2429010868 0.0890022069 0.0919340713 0.1207897216 0.0060863034 0.2995180000 0.0851250000 0.0529220000 0.0000000000 0.1544770000 0.0017760000 144455211 0 402718720 3.8792150021 3.9811878204 4.3684039116 2243 1311867245.2755670547 0.0888924226 0.0919327152 0.1207897216 0.0060862039 0.3329240000 0.0955920000 0.0472470000 0.0294550000 0.1536530000 0.0017840000 144458883 0 402718720 3.8792517185 3.9811611176 4.3707833290 2244 1311867245.3120090961 0.0884937719 0.0919311827 0.1207897216 0.0060849072 0.3190300000 0.0851280000 0.0739450000 0.0000010000 0.1526510000 0.0018670000 144462667 0 402718720 3.8789062500 3.9808316231 4.3729276657 2245 1311867245.3430099487 0.0883322805 0.0919295796 0.1207897216 0.0060836757 0.4794800000 0.0851290000 0.0496010000 0.0289360000 0.1523710000 0.1580980000 144466339 0 402718720 3.8787610531 3.9803378582 4.3750581741 2246 1311867245.3749370575 0.0883203521 0.0919279726 0.1207897216 0.0060835340 0.2982620000 0.0830830000 0.0555020000 0.0000000000 0.1527140000 0.0017760000 144469955 0 402718720 3.8787274361 3.9803354740 4.3774085045 2247 1311867245.4122350216 0.0878398865 0.0919261533 0.1207897216 0.0060823372 0.3314880000 0.0853960000 0.0577920000 0.0294380000 0.1515520000 0.0018820000 144473851 0 402718720 3.8774878979 3.9806485176 4.3798909187 2248 1311867245.4428830147 0.0886671171 0.0919247035 0.1207897216 0.0060846681 0.3134830000 0.0977080000 0.0577400000 0.0000010000 0.1510250000 0.0017900000 144477355 0 402718720 3.8769869804 3.9801046848 4.3820881844 2249 1311867245.4751451015 0.0886557400 0.0919232500 0.1207897216 0.0060839761 0.4903410000 0.0856300000 0.0455090000 0.0288700000 0.1606290000 0.1644330000 144481083 0 402718720 3.8770000935 3.9813203812 4.3845448494 2250 1311867245.5108819008 0.0883822963 0.0919216763 0.1207897216 0.0060831360 0.2963290000 0.0854720000 0.0550010000 0.0000010000 0.1487940000 0.0017820000 144484867 0 402718720 3.8762838840 3.9811239243 4.3869419098 2251 1311867245.5429608822 0.0880696997 0.0919199650 0.1207897216 0.0060819490 0.3167320000 0.0855860000 0.0473940000 0.0288460000 0.1478430000 0.0017790000 144488539 0 402718720 3.8764042854 3.9810471535 4.3892917633 2252 1311867245.5749409199 0.0884763300 0.0919184359 0.1207897216 0.0060806767 0.3032100000 0.0863440000 0.0635480000 0.0000000000 0.1463530000 0.0017730000 144492211 0 402718720 3.8757004738 3.9819259644 4.3919863701 2253 1311867245.6109130383 0.0889962763 0.0919171389 0.1207897216 0.0060798948 0.5208950000 0.0975950000 0.0942400000 0.0293190000 0.1444330000 0.1500560000 144495995 0 402718720 3.8752408028 3.9803302288 4.3941397667 2254 1311867245.6428189278 0.0880718380 0.0919154329 0.1207897216 0.0060848199 0.3367030000 0.0862050000 0.0991720000 0.0000000000 0.1443290000 0.0017780000 144499611 0 402718720 3.8742439747 3.9801902771 4.3963432312 2255 1311867245.6751749516 0.0886651203 0.0919139915 0.1207897216 0.0060842719 0.3209060000 0.0859040000 0.0554830000 0.0288010000 0.1437180000 0.0017790000 144503339 0 402718720 3.8743116856 3.9808065891 4.3987731934 2256 1311867245.7109169960 0.0888342336 0.0919126264 0.1207897216 0.0060830666 0.2912090000 0.0861720000 0.0553040000 0.0000000000 0.1427120000 0.0017760000 144507123 0 402718720 3.8735136986 3.9795846939 4.4007334709 2257 1311867245.7429819107 0.0884502456 0.0919110923 0.1207897216 0.0060824957 0.5142160000 0.1075290000 0.0824090000 0.0288000000 0.1421770000 0.1478570000 144510739 0 402718720 3.8736209869 3.9800539017 4.4028377533 2258 1311867245.7752521038 0.0884850100 0.0919095750 0.1207897216 0.0060840218 0.2919210000 0.0856610000 0.0579840000 0.0000010000 0.1409680000 0.0018620000 144514467 0 402718720 3.8730733395 3.9798197746 4.4050431252 2259 1311867245.8110349178 0.0885515884 0.0919080885 0.1207897216 0.0060831324 0.3587110000 0.0859610000 0.0959790000 0.0292980000 0.1404910000 0.0017810000 144518251 0 402718720 3.8733539581 3.9785990715 4.4068279266 2260 1311867245.8428230286 0.0887151733 0.0919066757 0.1207897216 0.0060826039 0.2880000000 0.0855800000 0.0549510000 0.0000000000 0.1405100000 0.0017770000 144521979 0 402718720 3.8726437092 3.9784071445 4.4086799622 2261 1311867245.8757770061 0.0892734081 0.0919055111 0.1207897216 0.0060812856 0.4638840000 0.0860470000 0.0581270000 0.0293120000 0.1395820000 0.1453350000 144525595 0 402718720 3.8718729019 3.9785225391 4.4106092453 2262 1311867245.9110751152 0.0887786746 0.0919041287 0.1207897216 0.0060810897 0.2966500000 0.0856300000 0.0644690000 0.0000000000 0.1395360000 0.0017740000 144529379 0 402718720 3.8716926575 3.9777390957 4.4120850563 2263 1311867245.9428870678 0.0886701569 0.0919026997 0.1207897216 0.0060811590 0.3321280000 0.0859510000 0.0706870000 0.0293010000 0.1391870000 0.0017820000 144533051 0 402718720 3.8714663982 3.9781084061 4.4138913155 2264 1311867245.9751350880 0.0887761042 0.0919013187 0.1207897216 0.0060799785 0.3268770000 0.0838680000 0.0977030000 0.0000010000 0.1380240000 0.0018270000 144536723 0 402718720 3.8707370758 3.9781820774 4.4155998230 2265 1311867246.0112419128 0.0882190317 0.0918996929 0.1207897216 0.0060786596 0.4489230000 0.0862640000 0.0477250000 0.0292740000 0.1373610000 0.1430570000 144540507 0 402718720 3.8699357510 3.9787235260 4.4176793098 2266 1311867246.0429229736 0.0883860141 0.0918981423 0.1207897216 0.0060773774 0.3043220000 0.0864540000 0.0746500000 0.0000000000 0.1358790000 0.0018660000 144544123 0 402718720 3.8690233231 3.9787957668 4.4198746681 2267 1311867246.0752329826 0.0884509832 0.0918966217 0.1207897216 0.0060761159 0.3137590000 0.0860280000 0.0563430000 0.0292880000 0.1347090000 0.0018640000 144547795 0 402718720 3.8685574532 3.9792897701 4.4221234322 2268 1311867246.1109249592 0.0882486776 0.0918950133 0.1207897216 0.0060753211 0.3199440000 0.0959310000 0.0832760000 0.0000010000 0.1333980000 0.0018730000 144551579 0 402718720 3.8683288097 3.9800810814 4.4244079590 2269 1311867246.1430890560 0.0888842344 0.0918936864 0.1207897216 0.0060741917 0.4644350000 0.0859490000 0.0743430000 0.0292880000 0.1317840000 0.1375830000 144555307 0 402718720 3.8672218323 3.9799942970 4.4264864922 2270 1311867246.1749811172 0.0886849836 0.0918922729 0.1207897216 0.0060732412 0.3185890000 0.0839940000 0.0967030000 0.0000010000 0.1309060000 0.0017820000 144558923 0 402718720 3.8669335842 3.9810822010 4.4287190437 2271 1311867246.2109639645 0.0886022300 0.0918908241 0.1207897216 0.0060722612 0.3466880000 0.0864160000 0.0947160000 0.0292930000 0.1292560000 0.0017860000 144562707 0 402718720 3.8661446571 3.9817564487 4.4309425354 2272 1311867246.2429399490 0.0887401029 0.0918894374 0.1207897216 0.0060710303 0.3034350000 0.0845260000 0.0842890000 0.0000010000 0.1276000000 0.0017250000 144566379 0 402718720 3.8663802147 3.9822034836 4.4330964088 2273 1311867246.2750649452 0.0888355523 0.0918880938 0.1207897216 0.0060702820 0.4631960000 0.1206480000 0.0502120000 0.0293090000 0.1259210000 0.1317620000 144570051 0 402718720 3.8664770126 3.9835138321 4.4353089333 2274 1311867246.3108720779 0.0884899870 0.0918865995 0.1207897216 0.0060702375 0.3013650000 0.0865560000 0.0831910000 0.0000000000 0.1242360000 0.0018640000 144573835 0 402718720 3.8665580750 3.9841973782 4.4373373985 2275 1311867246.3429319859 0.0886068791 0.0918851579 0.1207897216 0.0060694421 0.3363320000 0.0863380000 0.0912920000 0.0287330000 0.1228120000 0.0018630000 144577507 0 402718720 3.8661825657 3.9842498302 4.4393329620 2276 1311867246.3752970695 0.0888621956 0.0918838297 0.1207897216 0.0060683173 0.2794420000 0.0865360000 0.0635150000 0.0000010000 0.1223380000 0.0017730000 144581179 0 402718720 3.8659718037 3.9852705002 4.4413104057 2277 1311867246.4109311104 0.0889002904 0.0918825194 0.1207897216 0.0060672260 0.4256140000 0.0870070000 0.0558150000 0.0287000000 0.1215350000 0.1273200000 144584963 0 402718720 3.8657023907 3.9855840206 4.4432706833 2278 1311867246.4430770874 0.0889516547 0.0918812328 0.1207897216 0.0060660588 0.3097360000 0.0983380000 0.0834550000 0.0000000000 0.1205900000 0.0018790000 144588635 0 402718720 3.8657112122 3.9864187241 4.4451994896 2279 1311867246.4751329422 0.0895038098 0.0918801896 0.1207897216 0.0060647609 0.3007520000 0.0861980000 0.0581420000 0.0292720000 0.1198060000 0.0018550000 144592307 0 402718720 3.8650138378 3.9865572453 4.4469685555 2280 1311867246.5109679699 0.0894317552 0.0918791157 0.1207897216 0.0060643430 0.3084710000 0.0867780000 0.0954790000 0.0000000000 0.1192020000 0.0017680000 144596091 0 402718720 3.8653976917 3.9875209332 4.4486484528 2281 1311867246.5431129932 0.0897793099 0.0918781952 0.1207897216 0.0060634858 0.4383390000 0.0987950000 0.0633510000 0.0292400000 0.1178740000 0.1237230000 144599707 0 402718720 3.8653075695 3.9873540401 4.4500551224 2282 1311867246.5752038956 0.0895242989 0.0918771637 0.1207897216 0.0060626079 0.3058190000 0.0867600000 0.0946880000 0.0000010000 0.1173250000 0.0017670000 144603435 0 402718720 3.8663363457 3.9874594212 4.4513158798 2283 1311867246.6111249924 0.0900202915 0.0918763503 0.1207897216 0.0060625567 0.3064060000 0.0943260000 0.0584950000 0.0292660000 0.1169250000 0.0018710000 144607219 0 402718720 3.8653204441 3.9870395660 4.4525613785 2284 1311867246.6431870461 0.0894459039 0.0918752862 0.1207897216 0.0060625298 0.3044370000 0.0842760000 0.0960020000 0.0000010000 0.1168050000 0.0018370000 144610891 0 402718720 3.8653426170 3.9875857830 4.4535613060 2285 1311867246.6751689911 0.0896442086 0.0918743098 0.1207897216 0.0060619060 0.4187620000 0.0866490000 0.0585460000 0.0292280000 0.1165200000 0.1225640000 144614563 0 402718720 3.8648674488 3.9868290424 4.4543347359 2286 1311867246.7110559940 0.0896798298 0.0918733498 0.1207897216 0.0060606062 0.2842540000 0.0974100000 0.0628310000 0.0000000000 0.1169620000 0.0017720000 144618347 0 402718720 3.8648641109 3.9867067337 4.4552221298 2287 1311867246.7433049679 0.0897749737 0.0918724323 0.1207897216 0.0060593207 0.2862820000 0.0841380000 0.0493320000 0.0290420000 0.1166600000 0.0017860000 144622075 0 402718720 3.8646223545 3.9863064289 4.4559597969 2288 1311867246.7749860287 0.0902311876 0.0918717150 0.1207897216 0.0060583398 0.2771540000 0.0978620000 0.0551410000 0.0000000000 0.1170600000 0.0017710000 144625691 0 402718720 3.8644516468 3.9859077930 4.4567565918 2289 1311867246.8111929893 0.0905384645 0.0918711325 0.1207897216 0.0060574341 0.4058700000 0.0859210000 0.0452990000 0.0292240000 0.1171490000 0.1230070000 144629475 0 402718720 3.8640224934 3.9860701561 4.4573717117 2290 1311867246.8430919647 0.0906302929 0.0918705907 0.1207897216 0.0060561499 0.3099480000 0.0867160000 0.0988080000 0.0000010000 0.1169870000 0.0018700000 144633203 0 402718720 3.8640615940 3.9855139256 4.4580001831 2291 1311867246.8750779629 0.0906832963 0.0918700724 0.1207897216 0.0060552109 0.3334700000 0.0860220000 0.0936430000 0.0292240000 0.1175040000 0.0017960000 144636819 0 402718720 3.8638808727 3.9853219986 4.4584770203 2292 1311867246.9111549854 0.0908050388 0.0918696077 0.1207897216 0.0060539710 0.2589960000 0.0861810000 0.0474840000 0.0000000000 0.1174950000 0.0017730000 144640603 0 402718720 3.8634161949 3.9853436947 4.4590144157 2293 1311867246.9430611134 0.0905180052 0.0918690183 0.1207897216 0.0060531913 0.4112960000 0.0867430000 0.0500850000 0.0286040000 0.1172790000 0.1232840000 144644219 0 402718720 3.8637325764 3.9844415188 4.4593214989 2294 1311867246.9751238823 0.0905241445 0.0918684320 0.1207897216 0.0060521132 0.2660870000 0.0860840000 0.0550560000 0.0000010000 0.1178800000 0.0017700000 144647947 0 402718720 3.8627176285 3.9845674038 4.4597330093 2295 1311867247.0109090805 0.0902339518 0.0918677198 0.1207897216 0.0060511552 0.2936090000 0.0861530000 0.0534040000 0.0292090000 0.1176950000 0.0018090000 144651731 0 402718720 3.8632080555 3.9843220711 4.4602279663 2296 1311867247.0440731049 0.0900353864 0.0918669218 0.1207897216 0.0060498509 0.3043360000 0.0859030000 0.0936580000 0.0000010000 0.1176910000 0.0017890000 144655459 0 402718720 3.8633430004 3.9838554859 4.4606852531 2297 1311867247.0751919746 0.0902867094 0.0918662338 0.1207897216 0.0060488624 0.4674680000 0.0977390000 0.0943040000 0.0292010000 0.1175270000 0.1233590000 144659075 0 402718720 3.8631219864 3.9843692780 4.4613852501 2298 1311867247.1112151146 0.0906358957 0.0918656985 0.1207897216 0.0060477028 0.3119530000 0.0960240000 0.0917090000 0.0000010000 0.1171130000 0.0017940000 144662859 0 402718720 3.8625619411 3.9842596054 4.4619998932 2299 1311867247.1430439949 0.0906193405 0.0918651563 0.1207897216 0.0060470364 0.2801820000 0.0860320000 0.0416830000 0.0286850000 0.1166990000 0.0017820000 144666531 0 402718720 3.8628075123 3.9844295979 4.4625148773 2300 1311867247.1751630306 0.0905364677 0.0918645786 0.1207897216 0.0060459557 0.2726070000 0.0857090000 0.0631160000 0.0000010000 0.1166650000 0.0017700000 144670203 0 402718720 3.8629858494 3.9847652912 4.4628958702 2301 1311867247.2113189697 0.0905957967 0.0918640272 0.1207897216 0.0060448443 0.4131530000 0.0866990000 0.0539780000 0.0286390000 0.1162900000 0.1221660000 144673987 0 402718720 3.8633151054 3.9838950634 4.4631032944 2302 1311867247.2437279224 0.0912119970 0.0918637440 0.1207897216 0.0060449577 0.2855030000 0.0846110000 0.0768400000 0.0000010000 0.1170180000 0.0017320000 144677659 0 402718720 3.8620188236 3.9825797081 4.4630150795 2303 1311867247.2777190208 0.0915509015 0.0918636081 0.1207897216 0.0060445897 0.3021140000 0.0933680000 0.0551080000 0.0286680000 0.1178840000 0.0017970000 144681443 0 402718720 3.8613018990 3.9824202061 4.4628071785 2304 1311867247.3109691143 0.0917925835 0.0918635773 0.1207897216 0.0060435848 0.2949060000 0.0986000000 0.0710370000 0.0000010000 0.1181530000 0.0017720000 144685059 0 402718720 3.8603613377 3.9817736149 4.4621081352 2305 1311867247.3432049751 0.0918964669 0.0918635916 0.1207897216 0.0060434361 0.4588580000 0.0863890000 0.0947000000 0.0286470000 0.1189930000 0.1247990000 144688731 0 402718720 3.8599455357 3.9810917377 4.4613823891 2306 1311867247.3753070831 0.0918736383 0.0918635959 0.1207897216 0.0060422130 0.3327540000 0.1120240000 0.0943150000 0.0000000000 0.1193230000 0.0017390000 144692403 0 402718720 3.8594362736 3.9812076092 4.4605407715 2307 1311867247.4116749763 0.0920310318 0.0918636685 0.1207897216 0.0060428715 0.3288400000 0.0864030000 0.0867550000 0.0291810000 0.1193630000 0.0017760000 144696243 0 402718720 3.8592793941 3.9794361591 4.4594087601 2308 1311867247.4440929890 0.0923575461 0.0918638825 0.1207897216 0.0060420901 0.2714930000 0.0988110000 0.0450940000 0.0000010000 0.1204440000 0.0017710000 144699859 0 402718720 3.8587889671 3.9788141251 4.4582433701 2309 1311867247.4751029015 0.0925913230 0.0918641975 0.1207897216 0.0060408289 0.4623620000 0.0858980000 0.0938250000 0.0291980000 0.1211310000 0.1269620000 144703531 0 402718720 3.8582231998 3.9780941010 4.4569463730 2310 1311867247.5110449791 0.0925861150 0.0918645101 0.1207897216 0.0060443666 0.2866060000 0.0863140000 0.0711110000 0.0000010000 0.1221040000 0.0017660000 144707315 0 402718720 3.8585174084 3.9761137962 4.4553632736 2311 1311867247.5430850983 0.0928965807 0.0918649567 0.1207897216 0.0060482644 0.3397650000 0.0858110000 0.0935780000 0.0292060000 0.1240490000 0.0017760000 144710987 0 402718720 3.8580422401 3.9763319492 4.4536294937 2312 1311867247.5751209259 0.0922340602 0.0918651163 0.1207897216 0.0060525423 0.3115110000 0.0857270000 0.0937540000 0.0000000000 0.1249080000 0.0017810000 144714603 0 402718720 3.8584716320 3.9755997658 4.4519190788 2313 1311867247.6114599705 0.0931650549 0.0918656783 0.1207897216 0.0060540432 0.4446000000 0.1023440000 0.0500880000 0.0287320000 0.1260070000 0.1318600000 144718443 0 402718720 3.8589673042 3.9744060040 4.4499831200 2314 1311867247.6431109905 0.0932617858 0.0918662816 0.1207897216 0.0060529303 0.2792020000 0.0858990000 0.0580640000 0.0000010000 0.1275940000 0.0018640000 144722059 0 402718720 3.8590638638 3.9739363194 4.4478979111 2315 1311867247.6750760078 0.0926148072 0.0918666050 0.1207897216 0.0060572774 0.3091220000 0.0864060000 0.0584910000 0.0286660000 0.1281360000 0.0018610000 144725731 0 402718720 3.8609728813 3.9716982841 4.4455971718 2316 1311867247.7112369537 0.0939199403 0.0918674916 0.1207897216 0.0060565675 0.2824330000 0.0863640000 0.0585560000 0.0000010000 0.1300540000 0.0018670000 144729571 0 402718720 3.8604519367 3.9696447849 4.4427595139 2317 1311867247.7431221008 0.0937395766 0.0918682995 0.1207897216 0.0060559250 0.4477940000 0.0861810000 0.0564700000 0.0292680000 0.1324360000 0.1380810000 144733187 0 402718720 3.8607723713 3.9695715904 4.4398870468 2318 1311867247.7750411034 0.0931902230 0.0918688698 0.1207897216 0.0060550861 0.3238600000 0.0964180000 0.0866050000 0.0000010000 0.1336960000 0.0017640000 144736859 0 402718720 3.8610923290 3.9693942070 4.4371323586 2319 1311867247.8111629486 0.0933960751 0.0918695284 0.1207897216 0.0060540099 0.3516720000 0.0862840000 0.0943230000 0.0292840000 0.1346460000 0.0017940000 144740643 0 402718720 3.8610143661 3.9689750671 4.4342832565 2320 1311867247.8438889980 0.0936336666 0.0918702888 0.1207897216 0.0060547778 0.2840390000 0.0859650000 0.0553380000 0.0000010000 0.1355840000 0.0017870000 144744371 0 402718720 3.8608429432 3.9691359997 4.4319224358 2321 1311867247.8752439022 0.0930270925 0.0918707872 0.1207897216 0.0060538268 0.4613840000 0.0860650000 0.0630310000 0.0292790000 0.1359910000 0.1416400000 144747987 0 402718720 3.8619425297 3.9698061943 4.4298005104 2322 1311867247.9113290310 0.0936841741 0.0918715682 0.1207897216 0.0060532452 0.3609540000 0.1123490000 0.0970680000 0.0000010000 0.1431630000 0.0024550000 144751771 0 402718720 3.8618330956 3.9688632488 4.4276490211 2323 1311867247.9430620670 0.0933235288 0.0918721932 0.1207897216 0.0060522463 0.4274760000 0.1093150000 0.1251690000 0.0347480000 0.1498560000 0.0024560000 144755499 0 402718720 3.8628816605 3.9687173367 4.4255647659 2324 1311867247.9769830704 0.0932950452 0.0918728054 0.1207897216 0.0060510278 0.3418320000 0.1093200000 0.0737230000 0.0000010000 0.1504030000 0.0024480000 144759227 0 402718720 3.8636014462 3.9692203999 4.4237565994 2325 1311867248.0109910965 0.0934032574 0.0918734637 0.1207897216 0.0060515389 0.5227270000 0.1097050000 0.0638110000 0.0355050000 0.1508680000 0.1569560000 144762899 0 402718720 3.8642225266 3.9671640396 4.4215035439 2326 1311867248.0431969166 0.0936591551 0.0918742314 0.1207897216 0.0060508570 0.3338140000 0.1091920000 0.0634270000 0.0000010000 0.1527970000 0.0024550000 144766627 0 402718720 3.8635964394 3.9672074318 4.4191923141 2327 1311867248.0751419067 0.0937051252 0.0918750182 0.1207897216 0.0060498044 0.3556360000 0.1089790000 0.0686740000 0.0293290000 0.1414950000 0.0017870000 144770243 0 402718720 3.8638584614 3.9674804211 4.4168848991 2328 1311867248.1121830940 0.0935977623 0.0918757582 0.1207897216 0.0060487802 0.3451880000 0.0965710000 0.0990170000 0.0000010000 0.1424640000 0.0017910000 144774083 0 402718720 3.8646144867 3.9665560722 4.4142804146 2329 1311867248.1431720257 0.0939592272 0.0918766528 0.1207897216 0.0060482888 0.4703030000 0.0861320000 0.0553180000 0.0293770000 0.1442230000 0.1498620000 144777699 0 402718720 3.8638789654 3.9668679237 4.4117546082 2330 1311867248.1757500172 0.0941860303 0.0918776440 0.1207897216 0.0060469939 0.3293420000 0.0838090000 0.0930050000 0.0000010000 0.1453530000 0.0017720000 144781315 0 402718720 3.8640661240 3.9667189121 4.4094076157 2331 1311867248.2111859322 0.0937603265 0.0918784516 0.1207897216 0.0060458898 0.3235870000 0.0859690000 0.0551450000 0.0289000000 0.1464120000 0.0017890000 144785155 0 402718720 3.8644874096 3.9666635990 4.4069623947 2332 1311867248.2431430817 0.0941118747 0.0918794094 0.1207897216 0.0060447483 0.3341750000 0.0857410000 0.0937130000 0.0000000000 0.1475420000 0.0017720000 144788827 0 402718720 3.8644948006 3.9669730663 4.4047126770 2333 1311867248.2755289078 0.0940379873 0.0918803346 0.1207897216 0.0060434708 0.5270480000 0.0928420000 0.0968470000 0.0293790000 0.1484940000 0.1540470000 144792499 0 402718720 3.8649358749 3.9669079781 4.4022259712 2334 1311867248.3112230301 0.0936615542 0.0918810978 0.1207897216 0.0060436391 0.3404960000 0.0850490000 0.0982220000 0.0000000000 0.1496880000 0.0018790000 144796227 0 402718720 3.8650887012 3.9670453072 4.3995580673 2335 1311867248.3434588909 0.0939054713 0.0918819647 0.1207897216 0.0060438928 0.3390310000 0.0852420000 0.0658200000 0.0294300000 0.1513500000 0.0017860000 144799787 0 402718720 3.8656165600 3.9676802158 4.3972783089 2336 1311867248.3752219677 0.0940279290 0.0918828834 0.1207897216 0.0060455509 0.3688870000 0.1111330000 0.0982630000 0.0000000000 0.1519960000 0.0018620000 144803459 0 402718720 3.8661530018 3.9691483974 4.3951163292 2337 1311867248.4115560055 0.0938336030 0.0918837181 0.1207897216 0.0060462459 0.5395130000 0.0965840000 0.0985740000 0.0294900000 0.1516910000 0.1577410000 144807299 0 402718720 3.8663733006 3.9691522121 4.3928542137 2338 1311867248.4431369305 0.0938364565 0.0918845533 0.1207897216 0.0060449772 0.3125210000 0.0981280000 0.0548140000 0.0000000000 0.1523900000 0.0017820000 144810915 0 402718720 3.8674535751 3.9691679478 4.3904356956 2339 1311867248.4759230614 0.0943108723 0.0918855906 0.1207897216 0.0060440932 0.3398810000 0.0852110000 0.0658730000 0.0289340000 0.1523740000 0.0018590000 144814643 0 402718720 3.8670463562 3.9694478512 4.3881278038 2340 1311867248.5111510754 0.0936987475 0.0918863655 0.1207897216 0.0060435869 0.3039350000 0.0857130000 0.0579340000 0.0000010000 0.1527920000 0.0018700000 144818371 0 402718720 3.8679821491 3.9701142311 4.3858194351 2341 1311867248.5431890488 0.0941715464 0.0918873416 0.1207897216 0.0060424906 0.5256970000 0.0855880000 0.0929540000 0.0293220000 0.1534990000 0.1588100000 144822099 0 402718720 3.8683068752 3.9702265263 4.3834633827 2342 1311867248.5751869678 0.0938107148 0.0918881629 0.1207897216 0.0060414893 0.3519230000 0.0969120000 0.0939060000 0.0000010000 0.1538800000 0.0017780000 144825715 0 402718720 3.8689749241 3.9699943066 4.3811101913 2343 1311867248.6114389896 0.0934849009 0.0918888444 0.1207897216 0.0060404643 0.3546230000 0.0932380000 0.0706170000 0.0294700000 0.1541260000 0.0017810000 144829555 0 402718720 3.8699495792 3.9704947472 4.3787779808 2344 1311867248.6432449818 0.0940353274 0.0918897601 0.1207897216 0.0060391971 0.3442380000 0.0860120000 0.0968830000 0.0000000000 0.1538220000 0.0018740000 144833171 0 402718720 3.8699278831 3.9701471329 4.3763380051 2345 1311867248.6753089428 0.0938032344 0.0918905761 0.1207897216 0.0060379480 0.5328040000 0.0850870000 0.0984510000 0.0289630000 0.1544730000 0.1601450000 144836787 0 402718720 3.8698039055 3.9706077576 4.3737702370 2346 1311867248.7112829685 0.0942996442 0.0918916030 0.1207897216 0.0060376666 0.3475100000 0.0859660000 0.0991130000 0.0000010000 0.1549100000 0.0018640000 144840627 0 402718720 3.8700838089 3.9716546535 4.3713274002 2347 1311867248.7433049679 0.0942079946 0.0918925899 0.1207897216 0.0060377134 0.3759460000 0.0855010000 0.0989160000 0.0295270000 0.1548130000 0.0017810000 144844243 0 402718720 3.8705604076 3.9717626572 4.3686227798 2348 1311867248.7762219906 0.0938215181 0.0918934115 0.1207897216 0.0060364752 0.3374210000 0.0958910000 0.0783020000 0.0000010000 0.1560030000 0.0017750000 144847971 0 402718720 3.8711628914 3.9722168446 4.3658084869 2349 1311867248.8111898899 0.0942524001 0.0918944157 0.1207897216 0.0060386654 0.5314540000 0.0857760000 0.0923270000 0.0295380000 0.1563630000 0.1619910000 144851699 0 402718720 3.8711826801 3.9735078812 4.3632984161 2350 1311867248.8433189392 0.0939101428 0.0918952735 0.1207897216 0.0060457033 0.3308040000 0.1097840000 0.0573660000 0.0000010000 0.1563350000 0.0017830000 144855371 0 402718720 3.8715815544 3.9727559090 4.3603091240 2351 1311867248.8755309582 0.0942610502 0.0918962798 0.1207897216 0.0060454269 0.3459970000 0.0856870000 0.0662730000 0.0295710000 0.1568960000 0.0018630000 144859099 0 402718720 3.8720164299 3.9722034931 4.3573598862 2352 1311867248.9111700058 0.0945894644 0.0918974248 0.1207897216 0.0060449102 0.3471750000 0.0852910000 0.0964750000 0.0000010000 0.1582000000 0.0017690000 144862883 0 402718720 3.8727605343 3.9737582207 4.3546080589 2353 1311867248.9430971146 0.0947469249 0.0918986358 0.1207897216 0.0060437284 0.5664700000 0.1100690000 0.0987020000 0.0289780000 0.1587780000 0.1644530000 144866499 0 402718720 3.8729748726 3.9734234810 4.3515014648 2354 1311867248.9766070843 0.0951112509 0.0919000006 0.1207897216 0.0060432920 0.3516130000 0.0854960000 0.0989560000 0.0000010000 0.1595620000 0.0018810000 144870283 0 402718720 3.8734393120 3.9728415012 4.3483319283 2355 1311867249.0112600327 0.0952638015 0.0919014289 0.1207897216 0.0060426032 0.3822420000 0.0856230000 0.0987290000 0.0296190000 0.1607030000 0.0018820000 144873955 0 402718720 3.8744430542 3.9740591049 4.3453874588 2356 1311867249.0432310104 0.0951432660 0.0919028049 0.1207897216 0.0060417232 0.3208680000 0.0856140000 0.0663270000 0.0000000000 0.1613560000 0.0018800000 144877627 0 402718720 3.8764698505 3.9744803905 4.3424401283 2357 1311867249.0799250603 0.0955581218 0.0919043558 0.1207897216 0.0060406674 0.5176860000 0.0854760000 0.0661610000 0.0296620000 0.1623620000 0.1685290000 144881467 0 402718720 3.8765640259 3.9746429920 4.3393268585 2358 1311867249.1120550632 0.0955174118 0.0919058880 0.1207897216 0.0060403825 0.3229120000 0.0964400000 0.0552490000 0.0000010000 0.1639660000 0.0017930000 144885139 0 402718720 3.8779044151 3.9759347439 4.3365788460 2359 1311867249.1435980797 0.0953600705 0.0919073523 0.1207897216 0.0060402842 0.3494700000 0.0855390000 0.0631040000 0.0296360000 0.1639730000 0.0017810000 144888811 0 402718720 3.8794467449 3.9767026901 4.3337969780 2360 1311867249.1785130501 0.0948209614 0.0919085869 0.1207897216 0.0060406806 0.3255070000 0.0982540000 0.0553340000 0.0000010000 0.1646450000 0.0017690000 144892483 0 402718720 3.8814764023 3.9754741192 4.3306140900 2361 1311867249.2113580704 0.0950906947 0.0919099346 0.1207897216 0.0060402738 0.5532350000 0.0856690000 0.0939060000 0.0291640000 0.1666880000 0.1723030000 144896211 0 402718720 3.8820831776 3.9768166542 4.3277444839 2362 1311867249.2432780266 0.0957797021 0.0919115730 0.1207897216 0.0060401558 0.3314620000 0.0857760000 0.0709420000 0.0000010000 0.1675340000 0.0017710000 144899939 0 402718720 3.8827245235 3.9778964520 4.3250288963 2363 1311867249.2773559093 0.0957918167 0.0919132151 0.1207897216 0.0060421573 0.3730750000 0.1103140000 0.0573390000 0.0296900000 0.1684850000 0.0017880000 144903667 0 402718720 3.8834745884 3.9760150909 4.3218436241 2364 1311867249.3112919331 0.0956723392 0.0919148052 0.1207897216 0.0060435737 0.3542360000 0.0853330000 0.0903720000 0.0000010000 0.1709620000 0.0018700000 144907339 0 402718720 3.8845922947 3.9773676395 4.3190250397 2365 1311867249.3437249660 0.0958400294 0.0919164649 0.1207897216 0.0060428856 0.5686760000 0.0856980000 0.0988520000 0.0298010000 0.1713980000 0.1772620000 144911067 0 402718720 3.8857362270 3.9787216187 4.3163905144 2366 1311867249.3768579960 0.0954786912 0.0919179705 0.1207897216 0.0060447427 0.3599100000 0.0828630000 0.0975050000 0.0000010000 0.1720430000 0.0018280000 144914795 0 402718720 3.8868286610 3.9776732922 4.3134503365 2367 1311867249.4112169743 0.0958696306 0.0919196400 0.1207897216 0.0060442113 0.3952400000 0.0855780000 0.0986000000 0.0297060000 0.1741320000 0.0017960000 144918523 0 402718720 3.8873593807 3.9775466919 4.3105778694 2368 1311867249.4432210922 0.0956442058 0.0919212129 0.1207897216 0.0060438124 0.3614090000 0.0970480000 0.0822700000 0.0000000000 0.1748300000 0.0017980000 144922139 0 402718720 3.8885805607 3.9787247181 4.3080534935 2369 1311867249.4764440060 0.0959754735 0.0919229243 0.1207897216 0.0060425809 0.5709610000 0.0829160000 0.0971930000 0.0295930000 0.1750880000 0.1804020000 144925867 0 402718720 3.8887426853 3.9781060219 4.3052525520 2370 1311867249.5111339092 0.0957736596 0.0919245490 0.1207897216 0.0060420400 0.3625270000 0.0834440000 0.0948240000 0.0000010000 0.1769810000 0.0017790000 144929595 0 402718720 3.8892683983 3.9772107601 4.3022689819 2371 1311867249.5432300568 0.0957268104 0.0919261527 0.1207897216 0.0060416080 0.3978470000 0.0849150000 0.0982660000 0.0298110000 0.1772900000 0.0018810000 144933267 0 402718720 3.8897695541 3.9784255028 4.2997083664 2372 1311867249.5759820938 0.0956113040 0.0919277063 0.1207897216 0.0060403494 0.3636940000 0.0851500000 0.0934500000 0.0000010000 0.1778560000 0.0017820000 144936995 0 402718720 3.8906338215 3.9783582687 4.2969012260 2373 1311867249.6112229824 0.0954709575 0.0919291995 0.1207897216 0.0060394400 0.5494100000 0.0959010000 0.0550720000 0.0298020000 0.1788100000 0.1843850000 144940723 0 402718720 3.8908140659 3.9773187637 4.2939453125 2374 1311867249.6433780193 0.0957288295 0.0919308000 0.1207897216 0.0060414377 0.3463670000 0.0963090000 0.0629060000 0.0000010000 0.1798900000 0.0017770000 144944395 0 402718720 3.8909716606 3.9788916111 4.2917323112 2375 1311867249.6751029491 0.0947556198 0.0919319894 0.1207897216 0.0060464655 0.3559380000 0.0849230000 0.0549660000 0.0297990000 0.1789700000 0.0017840000 144948067 0 402718720 3.8920075893 3.9786272049 4.2891116142 2376 1311867249.7111389637 0.0953549221 0.0919334300 0.1207897216 0.0060459594 0.3577920000 0.0850040000 0.0860290000 0.0000010000 0.1795240000 0.0017790000 144951795 0 402718720 3.8921322823 3.9774396420 4.2862863541 2377 1311867249.7432470322 0.0954415426 0.0919349059 0.1207897216 0.0060477750 0.5910550000 0.1029060000 0.0859520000 0.0298740000 0.1805720000 0.1862380000 144955523 0 402718720 3.8921010494 3.9791517258 4.2837538719 2378 1311867249.7751579285 0.0948257595 0.0919361215 0.1207897216 0.0060489881 0.3385610000 0.0852300000 0.0662010000 0.0000010000 0.1795470000 0.0018740000 144959139 0 402718720 3.8922913074 3.9804985523 4.2815723419 2379 1311867249.8111488819 0.0951536223 0.0919374740 0.1207897216 0.0060479422 0.3666410000 0.0850670000 0.0659900000 0.0294210000 0.1788340000 0.0018140000 144962979 0 402718720 3.8930468559 3.9798939228 4.2790055275 2380 1311867249.8433248997 0.0949556604 0.0919387421 0.1207897216 0.0060466961 0.3611920000 0.0832480000 0.0909380000 0.0000010000 0.1797440000 0.0017330000 144966595 0 402718720 3.8936829567 3.9815473557 4.2766561508 2381 1311867249.8784089088 0.0954708755 0.0919402256 0.1207897216 0.0060456003 0.5305920000 0.0833930000 0.0494500000 0.0297760000 0.1783210000 0.1841470000 144970379 0 402718720 3.8935906887 3.9824519157 4.2744054794 2382 1311867249.9112401009 0.0954776779 0.0919417107 0.1207897216 0.0060444543 0.4103150000 0.0860690000 0.1248500000 0.0000010000 0.1908400000 0.0024650000 144974051 0 402718720 3.8946330547 3.9830431938 4.2717251778 2383 1311867249.9432768822 0.0950431526 0.0919430122 0.1207897216 0.0060441449 0.4589910000 0.1088070000 0.1147770000 0.0357590000 0.1911280000 0.0024540000 144977779 0 402718720 3.8952805996 3.9829833508 4.2689323425 2384 1311867249.9751698971 0.0953131244 0.0919444258 0.1207897216 0.0060438790 0.4331720000 0.1080920000 0.1246550000 0.0000010000 0.1919210000 0.0024480000 144981395 0 402718720 3.8954520226 3.9837992191 4.2661476135 2385 1311867250.0117108822 0.0951407999 0.0919457660 0.1207897216 0.0060431933 0.6520640000 0.1078440000 0.1243330000 0.0357750000 0.1920830000 0.1865010000 144985235 0 402718720 3.8959152699 3.9843397141 4.2632122040 2386 1311867250.0434269905 0.0957101285 0.0919473437 0.1207897216 0.0060425821 0.3651980000 0.0844530000 0.0934320000 0.0000000000 0.1800260000 0.0017850000 144988907 0 402718720 3.8957870007 3.9846806526 4.2602081299 2387 1311867250.0767190456 0.0955775306 0.0919488645 0.1207897216 0.0060427924 0.3965970000 0.0850720000 0.0939630000 0.0294350000 0.1808290000 0.0017970000 144992635 0 402718720 3.8958582878 3.9840736389 4.2570562363 2388 1311867250.1116099358 0.0961453393 0.0919506218 0.1207897216 0.0060420706 0.3873800000 0.1001120000 0.0982270000 0.0000010000 0.1817060000 0.0017800000 144996363 0 402718720 3.8958263397 3.9849388599 4.2543239594 2389 1311867250.1432220936 0.0962358192 0.0919524155 0.1207897216 0.0060408431 0.5691550000 0.0846660000 0.0779670000 0.0299420000 0.1827900000 0.1882740000 144999979 0 402718720 3.8964118958 3.9848790169 4.2513294220 2390 1311867250.1758980751 0.0962752327 0.0919542242 0.1207897216 0.0060396137 0.3720800000 0.1025370000 0.0781080000 0.0000000000 0.1841730000 0.0017920000 145003707 0 402718720 3.8966979980 3.9844067097 4.2482190132 2391 1311867250.2133369446 0.0963629633 0.0919560681 0.1207897216 0.0060384321 0.3775630000 0.0842130000 0.0700460000 0.0299650000 0.1860420000 0.0017880000 145007491 0 402718720 3.8976941109 3.9854462147 4.2452950478 2392 1311867250.2457129955 0.0964168310 0.0919579330 0.1207897216 0.0060378103 0.3760770000 0.0841900000 0.0980020000 0.0000000000 0.1862440000 0.0018870000 145011219 0 402718720 3.8977553844 3.9861679077 4.2425098419 2393 1311867250.2751679420 0.0970289409 0.0919600521 0.1207897216 0.0060385013 0.5562760000 0.0843630000 0.0577200000 0.0300430000 0.1863570000 0.1920210000 145014779 0 402718720 3.8968374729 3.9866557121 4.2397155762 2394 1311867250.3114409447 0.0967745334 0.0919620632 0.1207897216 0.0060380699 0.3766120000 0.0845310000 0.0983930000 0.0000010000 0.1863520000 0.0017820000 145018619 0 402718720 3.8983113766 3.9867830276 4.2371487617 2395 1311867250.3431971073 0.0970407948 0.0919641837 0.1207897216 0.0060375449 0.4002400000 0.0842200000 0.0914130000 0.0299630000 0.1872910000 0.0017860000 145022235 0 402718720 3.8983554840 3.9877512455 4.2348155975 2396 1311867250.3780639172 0.0969326943 0.0919662574 0.1207897216 0.0060365151 0.3702790000 0.0842220000 0.0915360000 0.0000010000 0.1871780000 0.0017780000 145026019 0 402718720 3.8985311985 3.9880387783 4.2322654724 2397 1311867250.4116489887 0.0971353725 0.0919684139 0.1207897216 0.0060360867 0.5786150000 0.0846650000 0.0782950000 0.0295270000 0.1875100000 0.1929990000 145029747 0 402718720 3.8990490437 3.9877383709 4.2296056747 2398 1311867250.4441781044 0.0968513042 0.0919704501 0.1207897216 0.0060348729 0.3898600000 0.0980310000 0.0963390000 0.0000000000 0.1878120000 0.0018880000 145033363 0 402718720 3.8992254734 3.9880254269 4.2270660400 2399 1311867250.4793250561 0.0968497619 0.0919724840 0.1207897216 0.0060338126 0.3842150000 0.0843170000 0.0659680000 0.0296030000 0.1957550000 0.0024460000 145037147 0 402718720 3.9004988670 3.9895055294 4.2247242928 2400 1311867250.5113220215 0.0969341993 0.0919745514 0.1207897216 0.0060333027 0.4007870000 0.1077000000 0.0835150000 0.0000010000 0.2009810000 0.0024490000 145040819 0 402718720 3.9006216526 3.9890491962 4.2222623825 2401 1311867250.5443398952 0.0968299508 0.0919765736 0.1207897216 0.0060321446 0.6533780000 0.1075340000 0.0937590000 0.0360640000 0.2020060000 0.2079300000 145044491 0 402718720 3.9013893604 3.9890885353 4.2198696136 2402 1311867250.5793490410 0.0977212191 0.0919789652 0.1207897216 0.0060315294 0.4424180000 0.1069220000 0.1240860000 0.0000010000 0.2028720000 0.0024190000 145048275 0 402718720 3.9009759426 3.9909911156 4.2179188728 2403 1311867250.6114881039 0.0976685435 0.0919813329 0.1207897216 0.0060304970 0.4151390000 0.1073780000 0.0733460000 0.0360670000 0.1910260000 0.0017940000 145052003 0 402718720 3.9019129276 3.9907417297 4.2156744003 2404 1311867250.6433761120 0.0975277349 0.0919836401 0.1207897216 0.0060302180 0.3769410000 0.0845770000 0.0938740000 0.0000010000 0.1911210000 0.0017780000 145055675 0 402718720 3.9021141529 3.9898636341 4.2130837440 2405 1311867250.6795539856 0.0983935669 0.0919863053 0.1207897216 0.0060305247 0.5800220000 0.0841240000 0.0704530000 0.0296290000 0.1923200000 0.1978900000 145059403 0 402718720 3.9021613598 3.9912340641 4.2108654976 2406 1311867250.7112920284 0.0978013501 0.0919887222 0.1207897216 0.0060296020 0.3385860000 0.0840410000 0.0547220000 0.0000010000 0.1924000000 0.0017920000 145063075 0 402718720 3.9032833576 3.9917194843 4.2084732056 2407 1311867250.7445890903 0.0985614061 0.0919914529 0.1207897216 0.0060313040 0.3692390000 0.0837840000 0.0549640000 0.0301360000 0.1929390000 0.0017860000 145066803 0 402718720 3.9018728733 3.9907133579 4.2059340477 2408 1311867250.7792830467 0.0985601991 0.0919941808 0.1207897216 0.0060309326 0.3523340000 0.0947430000 0.0563250000 0.0000010000 0.1939170000 0.0017880000 145070475 0 402718720 3.9026894569 3.9909050465 4.2037172318 2409 1311867250.8145580292 0.0986156911 0.0919969294 0.1207897216 0.0060302782 0.5822390000 0.0824860000 0.0700190000 0.0300980000 0.1942550000 0.1997800000 145074259 0 402718720 3.9028549194 3.9917724133 4.2017273903 2410 1311867250.8433599472 0.0984377190 0.0919996020 0.1207897216 0.0060293193 0.3346360000 0.0838120000 0.0494540000 0.0000000000 0.1937150000 0.0018770000 145077819 0 402718720 3.9029207230 3.9905204773 4.1996340752 2411 1311867250.8792760372 0.0980760679 0.0920021223 0.1207897216 0.0060306817 0.3947970000 0.0839700000 0.0781480000 0.0297070000 0.1956680000 0.0017920000 145081603 0 402718720 3.9029462337 3.9899632931 4.1975598335 2412 1311867250.9116361141 0.0983961374 0.0920047732 0.1207897216 0.0060301173 0.3469940000 0.0814200000 0.0614900000 0.0000010000 0.1967700000 0.0017460000 145085331 0 402718720 3.9026436806 3.9902522564 4.1955289841 2413 1311867250.9433720112 0.0979230031 0.0920072258 0.1207897216 0.0060292451 0.5662580000 0.0839790000 0.0467950000 0.0295270000 0.1975290000 0.2028460000 145088947 0 402718720 3.9035534859 3.9895904064 4.1935386658 2414 1311867250.9793050289 0.0984725878 0.0920099041 0.1207897216 0.0060287646 0.3514320000 0.0834450000 0.0622420000 0.0000010000 0.1983680000 0.0017750000 145092731 0 402718720 3.9028728008 3.9903337955 4.1916542053 2415 1311867251.0112459660 0.0979417935 0.0920123604 0.1207897216 0.0060279830 0.3923250000 0.0949040000 0.0621650000 0.0296910000 0.1982310000 0.0017900000 145096403 0 402718720 3.9035363197 3.9906487465 4.1898808479 2416 1311867251.0437910557 0.0984290242 0.0920150163 0.1207897216 0.0060274656 0.4059530000 0.1074110000 0.0928020000 0.0000010000 0.1983770000 0.0017730000 145100075 0 402718720 3.9028975964 3.9893300533 4.1876730919 2417 1311867251.0793159008 0.0985661820 0.0920177267 0.1207897216 0.0060269229 0.5780740000 0.0831620000 0.0543150000 0.0301880000 0.1997090000 0.2050840000 145103859 0 402718720 3.9027836323 3.9895396233 4.1856317520 2418 1311867251.1115839481 0.0981701240 0.0920202711 0.1207897216 0.0060259148 0.4049200000 0.1047320000 0.0926060000 0.0000010000 0.2002370000 0.0017790000 145107587 0 402718720 3.9029514790 3.9903504848 4.1839790344 2419 1311867251.1432809830 0.0987955928 0.0920230720 0.1207897216 0.0060255907 0.4174870000 0.0831130000 0.0972860000 0.0303110000 0.1990840000 0.0018950000 145111259 0 402718720 3.9022669792 3.9899575710 4.1818675995 2420 1311867251.1794250011 0.0981633291 0.0920256093 0.1207897216 0.0060273310 0.3883480000 0.0833200000 0.0974860000 0.0000010000 0.1998700000 0.0018920000 145115043 0 402718720 3.9027237892 3.9888865948 4.1797246933 2421 1311867251.2113831043 0.0988479927 0.0920284273 0.1207897216 0.0060331224 0.5984480000 0.0828930000 0.0731580000 0.0297680000 0.2007470000 0.2063060000 145118715 0 402718720 3.9020905495 3.9905154705 4.1779594421 2422 1311867251.2472319603 0.0985053182 0.0920311015 0.1207897216 0.0060339029 0.3818650000 0.0814930000 0.0918980000 0.0000000000 0.2010760000 0.0017700000 145122499 0 402718720 3.9022026062 3.9902372360 4.1759672165 2423 1311867251.2793700695 0.0983533189 0.0920337108 0.1207897216 0.0060328112 0.4060710000 0.0966910000 0.0701530000 0.0302600000 0.2015600000 0.0017840000 145126115 0 402718720 3.9021089077 3.9883809090 4.1736130714 2424 1311867251.3133869171 0.0985324383 0.0920363918 0.1207897216 0.0060328329 0.3979300000 0.0954190000 0.0924620000 0.0000010000 0.2026660000 0.0017760000 145129899 0 402718720 3.9019730091 3.9890968800 4.1717538834 2425 1311867251.3432419300 0.0980082527 0.0920388544 0.1207897216 0.0060352691 0.5934500000 0.0827400000 0.0653280000 0.0302810000 0.2017950000 0.2074450000 145133459 0 402718720 3.9011032581 3.9887959957 4.1696538925 2426 1311867251.3801820278 0.0982106775 0.0920413984 0.1207897216 0.0060341516 0.3404270000 0.0827270000 0.0468610000 0.0000000000 0.2034810000 0.0017730000 145137299 0 402718720 3.9011709690 3.9881501198 4.1675138474 2427 1311867251.4113550186 0.0978583544 0.0920437952 0.1207897216 0.0060330937 0.4161680000 0.0824330000 0.0921950000 0.0297690000 0.2043840000 0.0017950000 145140971 0 402718720 3.9013333321 3.9886922836 4.1655654907 2428 1311867251.4433960915 0.0986442193 0.0920465136 0.1207897216 0.0060324946 0.4231010000 0.1147170000 0.0968270000 0.0000010000 0.2038330000 0.0018840000 145144587 0 402718720 3.9004554749 3.9886629581 4.1637258530 2429 1311867251.4793379307 0.0982541293 0.0920490693 0.1207897216 0.0060313041 0.6250520000 0.0802310000 0.0953990000 0.0296760000 0.2043060000 0.2094930000 145148371 0 402718720 3.9009234905 3.9882400036 4.1618289948 2430 1311867251.5175099373 0.0982534587 0.0920516225 0.1207897216 0.0060303291 0.3917790000 0.0825460000 0.0967540000 0.0000010000 0.2050700000 0.0017860000 145152267 0 402718720 3.9007508755 3.9882035255 4.1599769592 2431 1311867251.5431749821 0.0989275649 0.0920544510 0.1207897216 0.0060296396 0.4189600000 0.0803050000 0.0954250000 0.0301550000 0.2057060000 0.0017780000 145155715 0 402718720 3.9004096985 3.9883687496 4.1582717896 2432 1311867251.5795340538 0.0993054137 0.0920574324 0.1207897216 0.0060285081 0.3430440000 0.0823770000 0.0465210000 0.0000010000 0.2067830000 0.0017660000 145159555 0 402718720 3.9004342556 3.9883928299 4.1563649178 2433 1311867251.6119680405 0.0990642682 0.0920603124 0.1207897216 0.0060272717 0.6036360000 0.0921710000 0.0569290000 0.0303630000 0.2061420000 0.2124170000 145163283 0 402718720 3.9008636475 3.9885075092 4.1544976234 2434 1311867251.6432960033 0.0985600203 0.0920629827 0.1207897216 0.0060264823 0.3509540000 0.0822600000 0.0539660000 0.0000010000 0.2072810000 0.0017680000 145166899 0 402718720 3.9014060497 3.9880239964 4.1524910927 2435 1311867251.6797280312 0.0993881300 0.0920659910 0.1207897216 0.0060270810 0.4199990000 0.0822070000 0.0919690000 0.0303540000 0.2080960000 0.0017840000 145170683 0 402718720 3.9005064964 3.9876673222 4.1505246162 2436 1311867251.7123379707 0.0992348790 0.0920689339 0.1207897216 0.0060269067 0.3676250000 0.0820960000 0.0691430000 0.0000010000 0.2089900000 0.0017800000 145174411 0 402718720 3.9007680416 3.9886982441 4.1485924721 2437 1311867251.7434990406 0.0985031277 0.0920715741 0.1207897216 0.0060260616 0.6321520000 0.0819400000 0.0920830000 0.0303150000 0.2083940000 0.2137820000 145177971 0 402718720 3.9019942284 3.9895479679 4.1467595100 2438 1311867251.7797439098 0.0986522511 0.0920742733 0.1207897216 0.0060255349 0.3644280000 0.0925890000 0.0570240000 0.0000010000 0.2071070000 0.0018610000 145181811 0 402718720 3.9016799927 3.9875488281 4.1444654465 2439 1311867251.8112530708 0.0988774449 0.0920770627 0.1207897216 0.0060253017 0.3843600000 0.0825260000 0.0549650000 0.0304500000 0.2089980000 0.0017750000 145185483 0 402718720 3.9009525776 3.9881038666 4.1423697472 2440 1311867251.8433279991 0.0984143242 0.0920796599 0.1207897216 0.0060241753 0.3528220000 0.0815700000 0.0540300000 0.0000010000 0.2098310000 0.0017630000 145189155 0 402718720 3.9016091824 3.9892525673 4.1407275200 2441 1311867251.8805420399 0.0979062393 0.0920820469 0.1207897216 0.0060237464 0.6146900000 0.0934040000 0.0615550000 0.0303800000 0.2090850000 0.2146170000 145192883 0 402718720 3.9017653465 3.9885516167 4.1387691498 2442 1311867251.9112489223 0.0978665873 0.0920844156 0.1207897216 0.0060225249 0.3452110000 0.0816760000 0.0462860000 0.0000010000 0.2098540000 0.0017650000 145196555 0 402718720 3.9018001556 3.9889814854 4.1370763779 2443 1311867251.9432179928 0.0986196548 0.0920870907 0.1207897216 0.0060226789 0.4208970000 0.1014250000 0.0729080000 0.0303990000 0.2084590000 0.0018660000 145200171 0 402718720 3.9014761448 3.9902660847 4.1356267929 2444 1311867251.9800109863 0.0983916000 0.0920896703 0.1207897216 0.0060225990 0.3776230000 0.0929740000 0.0689460000 0.0000010000 0.2082860000 0.0017750000 145204011 0 402718720 3.9018518925 3.9895792007 4.1338877678 2445 1311867252.0119040012 0.0978512540 0.0920920268 0.1207897216 0.0060217920 0.6292850000 0.0949760000 0.0787640000 0.0299080000 0.2071000000 0.2126740000 145207739 0 402718720 3.9024493694 3.9898645878 4.1321015358 2446 1311867252.0441029072 0.0983619243 0.0920945901 0.1207897216 0.0060209005 0.3453230000 0.0817100000 0.0488850000 0.0000010000 0.2072980000 0.0017600000 145211411 0 402718720 3.9022877216 3.9894289970 4.1302180290 2447 1311867252.0794539452 0.0991835222 0.0920974871 0.1207897216 0.0060198500 0.3760170000 0.0819950000 0.0489920000 0.0299710000 0.2073160000 0.0018560000 145215083 0 402718720 3.9018435478 3.9893043041 4.1280450821 2448 1311867252.1122460365 0.0991633460 0.0921003735 0.1207897216 0.0060191120 0.4155040000 0.1037090000 0.0965330000 0.0000010000 0.2078750000 0.0017220000 145218867 0 402718720 3.9014828205 3.9890801907 4.1254019737 2449 1311867252.1432950497 0.0988872871 0.0921031448 0.1207897216 0.0060198186 0.6532760000 0.0816300000 0.0843950000 0.0304630000 0.2217510000 0.2287910000 145222427 0 402718720 3.9015877247 3.9876291752 4.1225790977 2450 1311867252.1794359684 0.0996172577 0.0921062118 0.1207897216 0.0060187502 0.4594790000 0.1039310000 0.1218150000 0.0000010000 0.2250880000 0.0024060000 145226211 0 402718720 3.9008748531 3.9872758389 4.1196660995 2451 1311867252.2113459110 0.0989211649 0.0921089922 0.1207897216 0.0060194095 0.4160350000 0.0962100000 0.0690430000 0.0304790000 0.2128590000 0.0017790000 145229939 0 402718720 3.9019618034 3.9876079559 4.1168560982 2452 1311867252.2432808876 0.0997747332 0.0921121186 0.1207897216 0.0060191504 0.3925200000 0.0798760000 0.0911060000 0.0000010000 0.2141300000 0.0017700000 145233611 0 402718720 3.9003548622 3.9859526157 4.1137619019 2453 1311867252.2794110775 0.0991899222 0.0921150039 0.1207897216 0.0060201141 0.6153820000 0.0931520000 0.0464780000 0.0304950000 0.2170930000 0.2224600000 145237395 0 402718720 3.9012076855 3.9844651222 4.1108365059 2454 1311867252.3112668991 0.0988302901 0.0921177404 0.1207897216 0.0060199745 0.3817840000 0.0819620000 0.0725220000 0.0000010000 0.2194960000 0.0018760000 145241067 0 402718720 3.9015331268 3.9843108654 4.1079325676 2455 1311867252.3450291157 0.0986382812 0.0921203964 0.1207897216 0.0060189087 0.4013550000 0.0788780000 0.0634960000 0.0303440000 0.2209340000 0.0018090000 145244739 0 402718720 3.9016523361 3.9839842319 4.1050128937 2456 1311867252.3794589043 0.0982378125 0.0921228872 0.1207897216 0.0060184566 0.3609250000 0.0814230000 0.0489350000 0.0000000000 0.2227820000 0.0018710000 145248523 0 402718720 3.9014246464 3.9806823730 4.1018142700 2457 1311867252.4111969471 0.0987606719 0.0921255888 0.1207897216 0.0060180708 0.6353820000 0.0815760000 0.0571820000 0.0306000000 0.2274210000 0.2329390000 145252195 0 402718720 3.9007108212 3.9795384407 4.0987443924 2458 1311867252.4456050396 0.1001690179 0.0921288611 0.1207897216 0.0060279358 0.4272620000 0.0950280000 0.0957310000 0.0000010000 0.2287340000 0.0018520000 145255923 0 402718720 3.8999583721 3.9798388481 4.0959491730 2459 1311867252.4792900085 0.0990845859 0.0921316898 0.1207897216 0.0060367134 0.4040580000 0.0803350000 0.0562210000 0.0306140000 0.2294600000 0.0017640000 145259595 0 402718720 3.8997814655 3.9782731533 4.0927796364 2460 1311867252.5112249851 0.0987079814 0.0921343631 0.1207897216 0.0060356891 0.4120790000 0.0807610000 0.0908720000 0.0000000000 0.2330010000 0.0017580000 145263323 0 402718720 3.8998813629 3.9766423702 4.0893688202 2461 1311867252.5432820320 0.0987070277 0.0921370338 0.1207897216 0.0060350610 0.6823930000 0.0800460000 0.0903240000 0.0306180000 0.2351100000 0.2405870000 145266995 0 402718720 3.9004945755 3.9770271778 4.0864729881 2462 1311867252.5791800022 0.0993860364 0.0921399782 0.1207897216 0.0060339147 0.3831920000 0.0797810000 0.0602750000 0.0000000000 0.2356910000 0.0017610000 145270779 0 402718720 3.8994004726 3.9765510559 4.0835886002 2463 1311867252.6112799644 0.0990764424 0.0921427945 0.1207897216 0.0060327413 0.4556970000 0.0890730000 0.0928400000 0.0301560000 0.2358640000 0.0018470000 145274451 0 402718720 3.8995728493 3.9749999046 4.0804829597 2464 1311867252.6432769299 0.0995355994 0.0921457948 0.1207897216 0.0060316987 0.4214900000 0.0803940000 0.0954040000 0.0000000000 0.2378410000 0.0018540000 145278179 0 402718720 3.8991928101 3.9746179581 4.0772938728 2465 1311867252.6792490482 0.1005003974 0.0921491841 0.1207897216 0.0060313286 0.6937960000 0.0789810000 0.0942430000 0.0306530000 0.2389780000 0.2452340000 145281851 0 402718720 3.8983781338 3.9744043350 4.0746011734 2466 1311867252.7112491131 0.1005806997 0.0921526032 0.1207897216 0.0060307991 0.3967450000 0.1013700000 0.0478540000 0.0000010000 0.2397300000 0.0018600000 145285579 0 402718720 3.8977727890 3.9732866287 4.0714969635 2467 1311867252.7432410717 0.1004503891 0.0921559667 0.1207897216 0.0060297840 0.4542530000 0.0797290000 0.0949620000 0.0307640000 0.2413100000 0.0017930000 145289195 0 402718720 3.8980243206 3.9713697433 4.0680899620 2468 1311867252.7792730331 0.1010670960 0.0921595774 0.1207897216 0.0060286328 0.3973020000 0.0909830000 0.0554630000 0.0000010000 0.2430740000 0.0018480000 145292979 0 402718720 3.8978745937 3.9713485241 4.0650253296 2469 1311867252.8112781048 0.1011887491 0.0921632344 0.1207897216 0.0060280818 0.7174060000 0.0778780000 0.0936450000 0.0307640000 0.2475250000 0.2612960000 145296707 0 402718720 3.8982110023 3.9717853069 4.0620079041 2470 1311867252.8433189392 0.1008756682 0.0921667617 0.1207897216 0.0060274066 0.4567120000 0.1004980000 0.0893520000 0.0000010000 0.2581800000 0.0023830000 145300379 0 402718720 3.8985311985 3.9702527523 4.0586395264 2471 1311867252.8792660236 0.1014789939 0.0921705303 0.1207897216 0.0060283220 0.5239530000 0.1001680000 0.1178790000 0.0378430000 0.2594030000 0.0023720000 145304107 0 402718720 3.8987395763 3.9705932140 4.0556464195 2472 1311867252.9112188816 0.1010245085 0.0921741120 0.1207897216 0.0060271919 0.4848630000 0.0997520000 0.1179850000 0.0000010000 0.2584680000 0.0023620000 145307835 0 402718720 3.8991613388 3.9710631371 4.0528793335 2473 1311867252.9446918964 0.1005515531 0.0921774996 0.1207897216 0.0060267451 0.7125870000 0.0929180000 0.0892640000 0.0307070000 0.2442650000 0.2496680000 145311507 0 402718720 3.8994851112 3.9698815346 4.0497393608 2474 1311867252.9806020260 0.1010702252 0.0921810940 0.1207897216 0.0060264240 0.3941920000 0.0791230000 0.0630840000 0.0000010000 0.2441570000 0.0018520000 145315291 0 402718720 3.8995246887 3.9685173035 4.0468010902 2475 1311867253.0113809109 0.0995853171 0.0921840856 0.1207897216 0.0060255480 0.4448270000 0.0782590000 0.0782740000 0.0307890000 0.2488350000 0.0023750000 145318963 0 402718720 3.9018146992 3.9705739021 4.0441031456 2476 1311867253.0434310436 0.0999979004 0.0921872415 0.1207897216 0.0060250727 0.4831510000 0.0995530000 0.1178580000 0.0000010000 0.2570460000 0.0023690000 145322635 0 402718720 3.9017736912 3.9688076973 4.0412354469 2477 1311867253.0799300671 0.0997488946 0.0921902942 0.1207897216 0.0060320591 0.6997820000 0.0784840000 0.0890430000 0.0307940000 0.2450800000 0.2505980000 145326419 0 402718720 3.9019117355 3.9671254158 4.0379567146 2478 1311867253.1113030910 0.1000013351 0.0921934464 0.1207897216 0.0060347402 0.4019660000 0.0890290000 0.0591810000 0.0000000000 0.2462790000 0.0017480000 145330091 0 402718720 3.9027416706 3.9686942101 4.0352430344 2479 1311867253.1440761089 0.1001369134 0.0921966507 0.1207897216 0.0060339669 0.4487920000 0.0766650000 0.0882070000 0.0308580000 0.2456320000 0.0017520000 145333763 0 402718720 3.9030239582 3.9680063725 4.0321950912 2480 1311867253.1794049740 0.1000666395 0.0921998241 0.1207897216 0.0060329539 0.3848080000 0.0785520000 0.0522530000 0.0000010000 0.2465170000 0.0017580000 145337491 0 402718720 3.9030873775 3.9673089981 4.0290131569 2481 1311867253.2112159729 0.1000276953 0.0922029792 0.1207897216 0.0060323005 0.6680320000 0.0788790000 0.0522160000 0.0309350000 0.2473410000 0.2529410000 145341219 0 402718720 3.9033601284 3.9667563438 4.0262241364 2482 1311867253.2458410263 0.0998744443 0.0922060700 0.1207897216 0.0060311369 0.3854810000 0.0781710000 0.0520540000 0.0000000000 0.2477190000 0.0017590000 145344947 0 402718720 3.9036633968 3.9671928883 4.0235409737 2483 1311867253.2793951035 0.1005339921 0.0922094240 0.1207897216 0.0060302722 0.4702680000 0.0916020000 0.0930890000 0.0308960000 0.2472200000 0.0017590000 145348619 0 402718720 3.9039485455 3.9667761326 4.0209593773 2484 1311867253.3114080429 0.0997591540 0.0922124633 0.1207897216 0.0060291184 0.3930210000 0.0781920000 0.0591790000 0.0000000000 0.2481420000 0.0017510000 145352347 0 402718720 3.9052286148 3.9667549133 4.0184154510 2485 1311867253.3445611000 0.0999702513 0.0922155852 0.1207897216 0.0060337742 0.7053770000 0.0779870000 0.0883810000 0.0304980000 0.2484760000 0.2542060000 145356075 0 402718720 3.9055356979 3.9664304256 4.0158495903 2486 1311867253.3794078827 0.0994089320 0.0922184787 0.1207897216 0.0060356061 0.3813500000 0.0781980000 0.0478470000 0.0000010000 0.2474890000 0.0018440000 145359747 0 402718720 3.9073357582 3.9664504528 4.0133562088 2487 1311867253.4129528999 0.0988742411 0.0922211550 0.1207897216 0.0060364584 0.4777390000 0.0983010000 0.0927020000 0.0310230000 0.2479080000 0.0018650000 145363531 0 402718720 3.9090201855 3.9660315514 4.0109062195 2488 1311867253.4444990158 0.1002411246 0.0922243784 0.1207897216 0.0060371544 0.4400830000 0.0913150000 0.0923470000 0.0000000000 0.2486100000 0.0018470000 145367147 0 402718720 3.9078528881 3.9660403728 4.0086665154 2489 1311867253.4804859161 0.0999698341 0.0922274903 0.1207897216 0.0060371229 0.6964600000 0.0783470000 0.0591210000 0.0309630000 0.2523520000 0.2693230000 145370931 0 402718720 3.9099087715 3.9667253494 4.0065360069 2490 1311867253.5113739967 0.1003052667 0.0922307344 0.1207897216 0.0060365245 0.4613010000 0.1000660000 0.0887670000 0.0000010000 0.2636990000 0.0023810000 145374603 0 402718720 3.9101407528 3.9652252197 4.0042099953 2491 1311867253.5441629887 0.1003535688 0.0922339952 0.1207897216 0.0060364706 0.4679050000 0.0992180000 0.0795100000 0.0304930000 0.2512120000 0.0017590000 145378219 0 402718720 3.9109935760 3.9639759064 4.0017137527 2492 1311867253.5794069767 0.1010251790 0.0922375230 0.1207897216 0.0060354103 0.4263440000 0.0784700000 0.0882420000 0.0000010000 0.2521570000 0.0017320000 145382003 0 402718720 3.9111266136 3.9637875557 3.9996113777 2493 1311867253.6118021011 0.1009016484 0.0922409984 0.1207897216 0.0060342474 0.7049740000 0.0867920000 0.0700240000 0.0310540000 0.2524650000 0.2588130000 145385731 0 402718720 3.9117310047 3.9623861313 3.9970963001 2494 1311867253.6447649002 0.1015305072 0.0922447231 0.1207897216 0.0060333305 0.4005610000 0.0775980000 0.0619300000 0.0000000000 0.2532060000 0.0018500000 145389403 0 402718720 3.9117474556 3.9615948200 3.9945783615 2495 1311867253.6799790859 0.1021197960 0.0922486811 0.1207897216 0.0060323183 0.4245980000 0.0784420000 0.0528940000 0.0310520000 0.2543840000 0.0018680000 145393187 0 402718720 3.9115638733 3.9612412453 3.9921152592 2496 1311867253.7115769386 0.1031190604 0.0922530362 0.1207897216 0.0060324689 0.4454330000 0.0898330000 0.0931450000 0.0000010000 0.2549400000 0.0017480000 145396859 0 402718720 3.9100966454 3.9595694542 3.9892013073 2497 1311867253.7435369492 0.1023030505 0.0922570610 0.1207897216 0.0060340687 0.7242020000 0.0791870000 0.0886910000 0.0311200000 0.2567760000 0.2626810000 145400475 0 402718720 3.9100899696 3.9570212364 3.9854171276 2498 1311867253.7806150913 0.1028583273 0.0922613049 0.1207897216 0.0060341816 0.4320000000 0.1043200000 0.0624270000 0.0000010000 0.2573560000 0.0018660000 145404259 0 402718720 3.9091234207 3.9561600685 3.9818797112 2499 1311867253.8113009930 0.1028343216 0.0922655358 0.1207897216 0.0060330404 0.4649470000 0.0787490000 0.0885050000 0.0311580000 0.2589970000 0.0017640000 145407931 0 402718720 3.9079542160 3.9549524784 3.9783911705 2500 1311867253.8469560146 0.1019850671 0.0922694236 0.1207897216 0.0060329900 0.4356760000 0.0789180000 0.0887360000 0.0000000000 0.2604470000 0.0017610000 145411715 0 402718720 3.9078867435 3.9539685249 3.9745361805 2501 1311867253.8792059422 0.1016497985 0.0922731743 0.1207897216 0.0060321918 0.7365780000 0.0787170000 0.0909570000 0.0312090000 0.2618150000 0.2680780000 145415331 0 402718720 3.9065649509 3.9514880180 3.9704875946 2502 1311867253.9114460945 0.1019309312 0.0922770343 0.1207897216 0.0060310245 0.4263310000 0.0781890000 0.0776730000 0.0000010000 0.2626120000 0.0018590000 145419003 0 402718720 3.9046058655 3.9502835274 3.9665167332 2503 1311867253.9461600780 0.1015626267 0.0922807441 0.1207897216 0.0060301681 0.4570440000 0.0922400000 0.0618200000 0.0307340000 0.2643870000 0.0018480000 145422787 0 402718720 3.9039399624 3.9512159824 3.9627528191 2504 1311867253.9794149399 0.1005032957 0.0922840279 0.1207897216 0.0060292539 0.3979780000 0.0770190000 0.0465150000 0.0000010000 0.2669620000 0.0017140000 145426403 0 402718720 3.9037041664 3.9504952431 3.9590594769 2505 1311867254.0119979382 0.1019016728 0.0922878672 0.1207897216 0.0060301669 0.7278810000 0.0776240000 0.0697140000 0.0312490000 0.2680000000 0.2754890000 145430131 0 402718720 3.8998539448 3.9486091137 3.9552371502 2506 1311867254.0457749367 0.1010780856 0.0922913749 0.1207897216 0.0060290895 0.4422140000 0.0770550000 0.0872580000 0.0000010000 0.2703070000 0.0017530000 145433859 0 402718720 3.8993124962 3.9479782581 3.9518063068 2507 1311867254.0793740749 0.1003074795 0.0922945724 0.1207897216 0.0060338209 0.4388070000 0.0770830000 0.0512120000 0.0312850000 0.2716250000 0.0017610000 145437531 0 402718720 3.8996820450 3.9474210739 3.9485030174 2508 1311867254.1113519669 0.0994351655 0.0922974195 0.1207897216 0.0060327119 0.4565890000 0.0890550000 0.0865220000 0.0000000000 0.2734620000 0.0017460000 145441203 0 402718720 3.8996706009 3.9463336468 3.9451506138 2509 1311867254.1476950645 0.1009505913 0.0923008684 0.1207897216 0.0060321045 0.7594160000 0.0761150000 0.0905580000 0.0313430000 0.2741390000 0.2812620000 145445043 0 402718720 3.8973953724 3.9474902153 3.9422612190 2510 1311867254.1795129776 0.1016380116 0.0923045884 0.1207897216 0.0060311477 0.4105520000 0.0751840000 0.0502800000 0.0000010000 0.2775530000 0.0017380000 145448659 0 402718720 3.8960356712 3.9478523731 3.9393479824 2511 1311867254.2114939690 0.1000340506 0.0923076666 0.1207897216 0.0060378108 0.4575800000 0.0749240000 0.0643330000 0.0312630000 0.2795380000 0.0017390000 145452387 0 402718720 3.8960125446 3.9466269016 3.9362027645 2512 1311867254.2469160557 0.1010487303 0.0923111463 0.1207897216 0.0060380188 0.4065180000 0.0731010000 0.0432020000 0.0000010000 0.2826740000 0.0017240000 145456171 0 402718720 3.8949620724 3.9471039772 3.9332613945 2513 1311867254.2798569202 0.1022849679 0.0923151152 0.1207897216 0.0060380296 0.7902870000 0.0972860000 0.0822850000 0.0313340000 0.2829580000 0.2903750000 145459787 0 402718720 3.8944211006 3.9496512413 3.9305980206 2514 1311867254.3114631176 0.1041346192 0.0923198167 0.1207897216 0.0060439301 0.4188940000 0.0749470000 0.0517990000 0.0000010000 0.2846050000 0.0017290000 145463459 0 402718720 3.8919308186 3.9516038895 3.9277722836 2515 1311867254.3475589752 0.1057538390 0.0923251582 0.1207897216 0.0060449440 0.4839710000 0.0748870000 0.0851860000 0.0313430000 0.2850760000 0.0017400000 145467299 0 402718720 3.8894965649 3.9496760368 3.9241306782 2516 1311867254.3794488907 0.1064704508 0.0923307804 0.1207897216 0.0060441428 0.4590550000 0.0749940000 0.0900080000 0.0000010000 0.2864890000 0.0017290000 145470915 0 402718720 3.8878197670 3.9480543137 3.9202399254 2517 1311867254.4115350246 0.1071476117 0.0923366671 0.1207897216 0.0060483343 0.7823560000 0.0740010000 0.0845580000 0.0313670000 0.2895910000 0.2970550000 145474643 0 402718720 3.8870387077 3.9496190548 3.9165370464 2518 1311867254.4483439922 0.1084983572 0.0923430855 0.1207897216 0.0060474127 0.4157740000 0.0739340000 0.0427920000 0.0000010000 0.2914520000 0.0017180000 145478427 0 402718720 3.8859870434 3.9502363205 3.9125425816 2519 1311867254.4794480801 0.1079489365 0.0923492808 0.1207897216 0.0060466566 0.4708890000 0.0751430000 0.0644620000 0.0314240000 0.2923240000 0.0017470000 145482043 0 402718720 3.8851346970 3.9492938519 3.9082400799 2520 1311867254.5114428997 0.1071780175 0.0923551652 0.1207897216 0.0060454592 0.4589680000 0.0988460000 0.0601740000 0.0000000000 0.2923580000 0.0017460000 145485715 0 402718720 3.8848373890 3.9496505260 3.9041030407 2521 1311867254.5500459671 0.1065251902 0.0923607860 0.1207897216 0.0060459789 0.7749170000 0.0747360000 0.0642450000 0.0314410000 0.2952690000 0.3033820000 145489555 0 402718720 3.8850855827 3.9506049156 3.8996143341 2522 1311867254.5794870853 0.1057152897 0.0923660812 0.1207897216 0.0060494264 0.4604230000 0.0722440000 0.0833560000 0.0000000000 0.2972850000 0.0016990000 145493171 0 402718720 3.8848409653 3.9508070946 3.8953747749 2523 1311867254.6114809513 0.1061993614 0.0923715641 0.1207897216 0.0060483984 0.4715720000 0.0918740000 0.0423300000 0.0314710000 0.2983770000 0.0017230000 145496843 0 402718720 3.8830666542 3.9523909092 3.8915164471 2524 1311867254.6452929974 0.1059782505 0.0923769550 0.1207897216 0.0060492046 0.4293570000 0.0731800000 0.0492300000 0.0000000000 0.2994580000 0.0017180000 145500571 0 402718720 3.8834664822 3.9542453289 3.8877658844 2525 1311867254.6794900894 0.1071334034 0.0923827992 0.1207897216 0.0060492549 0.7695820000 0.0731620000 0.0492580000 0.0310090000 0.3008300000 0.3094640000 145504355 0 402718720 3.8814971447 3.9541738033 3.8836920261 2526 1311867254.7113230228 0.1062244102 0.0923882788 0.1207897216 0.0060480949 0.4239530000 0.0714900000 0.0418570000 0.0000000000 0.3030440000 0.0017240000 145508027 0 402718720 3.8815038204 3.9542489052 3.8795809746 2527 1311867254.7453329563 0.1063415408 0.0923938005 0.1207897216 0.0060494185 0.5073570000 0.0719550000 0.0827570000 0.0314810000 0.3135630000 0.0017160000 145511699 0 402718720 3.8820321560 3.9558570385 3.8761186600 2528 1311867254.7794649601 0.1086501554 0.0924002310 0.1207897216 0.0060532353 0.4805890000 0.0846290000 0.0826940000 0.0000010000 0.3056380000 0.0017180000 145515427 0 402718720 3.8796739578 3.9569284916 3.8727841377 2529 1311867254.8115739822 0.1077647358 0.0924063063 0.1207897216 0.0060521553 0.8255840000 0.0830880000 0.0822030000 0.0310680000 0.3068700000 0.3164370000 145519099 0 402718720 3.8810703754 3.9571726322 3.8695657253 2530 1311867254.8482780457 0.1080318838 0.0924124824 0.1207897216 0.0060524353 0.4698010000 0.0954490000 0.0483180000 0.0000010000 0.3173160000 0.0022750000 145522995 0 402718720 3.8805665970 3.9577069283 3.8663666248 2531 1311867254.8794910908 0.1095157489 0.0924192400 0.1207897216 0.0060513332 0.5697600000 0.0906790000 0.1083720000 0.0391770000 0.3228250000 0.0022780000 145526555 0 402718720 3.8792676926 3.9586203098 3.8634607792 2532 1311867254.9138929844 0.1086573377 0.0924256531 0.1207897216 0.0060511658 0.4785840000 0.0903570000 0.0550430000 0.0000010000 0.3244650000 0.0022700000 145530283 0 402718720 3.8801345825 3.9585170746 3.8601505756 2533 1311867254.9490759373 0.1095156074 0.0924324000 0.1207897216 0.0060505948 0.8366470000 0.0902380000 0.0549700000 0.0385730000 0.3244560000 0.3225400000 145534067 0 402718720 3.8789596558 3.9588611126 3.8570990562 2534 1311867254.9819579124 0.1101501435 0.0924393920 0.1207897216 0.0060499833 0.4461960000 0.0705440000 0.0545030000 0.0000000000 0.3135710000 0.0017030000 145537795 0 402718720 3.8787398338 3.9606029987 3.8545413017 2535 1311867255.0154359341 0.1099946573 0.0924463172 0.1207897216 0.0060512074 0.4988340000 0.0711590000 0.0747650000 0.0311840000 0.3142060000 0.0017100000 145541467 0 402718720 3.8790588379 3.9603140354 3.8518371582 2536 1311867255.0494379997 0.1111280099 0.0924536838 0.1207897216 0.0060503863 0.4738970000 0.0702150000 0.0807860000 0.0000010000 0.3152960000 0.0016940000 145545195 0 402718720 3.8778824806 3.9604256153 3.8491508961 2537 1311867255.0822079182 0.1127861962 0.0924616982 0.1207897216 0.0060493802 0.8443520000 0.0826460000 0.0804570000 0.0315590000 0.3162560000 0.3275390000 145548867 0 402718720 3.8758704662 3.9619371891 3.8468325138 2538 1311867255.1176838875 0.1125788912 0.0924696246 0.1207897216 0.0060483462 0.4533520000 0.0810610000 0.0474900000 0.0000010000 0.3172390000 0.0016970000 145552539 0 402718720 3.8770217896 3.9623548985 3.8443911076 2539 1311867255.1510150433 0.1120502204 0.0924773365 0.1207897216 0.0060487112 0.4817940000 0.0704010000 0.0542790000 0.0311930000 0.3182920000 0.0017080000 145556211 0 402718720 3.8773894310 3.9614968300 3.8416004181 2540 1311867255.1838800907 0.1129848361 0.0924854103 0.1207897216 0.0060483083 0.4444740000 0.0700100000 0.0499680000 0.0000000000 0.3169290000 0.0016900000 145559771 0 402718720 3.8765897751 3.9628098011 3.8391003609 2541 1311867255.2169129848 0.1131868437 0.0924935573 0.1207897216 0.0060486488 0.8212280000 0.0694660000 0.0603410000 0.0315840000 0.3208710000 0.3330870000 145563443 0 402718720 3.8769638538 3.9654722214 3.8368253708 2542 1311867255.2459371090 0.1142980531 0.0925021350 0.1207897216 0.0060479872 0.4790810000 0.0696830000 0.0800760000 0.0000000000 0.3217540000 0.0016850000 145567059 0 402718720 3.8752570152 3.9653935432 3.8342273235 2543 1311867255.2793660164 0.1144352108 0.0925107599 0.1207897216 0.0060564175 0.5138400000 0.0697650000 0.0843990000 0.0316770000 0.3200500000 0.0017930000 145570731 0 402718720 3.8749120235 3.9649426937 3.8316774368 2544 1311867255.3138630390 0.1136236563 0.0925190590 0.1207897216 0.0060555567 0.4595660000 0.0809500000 0.0466670000 0.0000010000 0.3243720000 0.0016810000 145574459 0 402718720 3.8765189648 3.9657430649 3.8288426399 2545 1311867255.3468410969 0.1141153723 0.0925275447 0.1207897216 0.0060550457 0.8484290000 0.0693450000 0.0783060000 0.0316710000 0.3250700000 0.3381430000 145578187 0 402718720 3.8762674332 3.9650964737 3.8260710239 2546 1311867255.3794751167 0.1144235134 0.0925361449 0.1207897216 0.0060539135 0.4800300000 0.0672820000 0.0786710000 0.0000010000 0.3265250000 0.0016450000 145581859 0 402718720 3.8762674332 3.9649159908 3.8231146336 2547 1311867255.4137639999 0.1156257689 0.0925452103 0.1207897216 0.0060568607 0.4945750000 0.0686400000 0.0596720000 0.0316530000 0.3270110000 0.0016930000 145585587 0 402718720 3.8754031658 3.9656991959 3.8201320171 2548 1311867255.4455530643 0.1156194210 0.0925542661 0.1207897216 0.0060558808 0.4928460000 0.0787100000 0.0785020000 0.0000010000 0.3280590000 0.0016710000 145589259 0 402718720 3.8756797314 3.9667503834 3.8170828819 2549 1311867255.4794819355 0.1167497933 0.0925637583 0.1207897216 0.0060560798 0.8244830000 0.0689610000 0.0492030000 0.0317340000 0.3256630000 0.3430100000 145592987 0 402718720 3.8753244877 3.9666345119 3.8143434525 2550 1311867255.5156099796 0.1184916571 0.0925739261 0.1207897216 0.0060578472 0.4580580000 0.0684050000 0.0557370000 0.0000000000 0.3263350000 0.0016710000 145596771 0 402718720 3.8747117519 3.9678421021 3.8117387295 2551 1311867255.5457780361 0.1174395010 0.0925836735 0.1207897216 0.0060601261 0.5035030000 0.0682160000 0.0658030000 0.0316780000 0.3302680000 0.0016820000 145600387 0 402718720 3.8758366108 3.9678952694 3.8088729382 2552 1311867255.5794420242 0.1181653664 0.0925936976 0.1207897216 0.0060589436 0.4593220000 0.0679020000 0.0530070000 0.0000000000 0.3308260000 0.0016700000 145604059 0 402718720 3.8760547638 3.9672822952 3.8059587479 2553 1311867255.6153330803 0.1178506613 0.0926035907 0.1207897216 0.0060591292 0.8556860000 0.0832660000 0.0621750000 0.0317250000 0.3285190000 0.3437910000 145607843 0 402718720 3.8766999245 3.9675970078 3.8030514717 2554 1311867255.6456480026 0.1187456027 0.0926138264 0.1207897216 0.0060583909 0.4883740000 0.0668560000 0.0811060000 0.0000010000 0.3328450000 0.0016590000 145611515 0 402718720 3.8765864372 3.9700474739 3.8007740974 2555 1311867255.6801021099 0.1185772941 0.0926239882 0.1207897216 0.0060575966 0.5185150000 0.0676650000 0.0782130000 0.0317360000 0.3333370000 0.0016710000 145615243 0 402718720 3.8776607513 3.9698548317 3.7982442379 2556 1311867255.7182919979 0.1204628497 0.0926348798 0.1207897216 0.0060591308 0.4984780000 0.0785340000 0.0783010000 0.0000010000 0.3340920000 0.0016670000 145619083 0 402718720 3.8749148846 3.9677858353 3.7949256897 2557 1311867255.7457749844 0.1212396473 0.0926460667 0.1212396473 0.0060589920 0.8487770000 0.0658600000 0.0583790000 0.0311080000 0.3356930000 0.3511350000 145622643 0 402718720 3.8743293285 3.9693143368 3.7924127579 2558 1311867255.7810928822 0.1195340455 0.0926565780 0.1212396473 0.0060625324 0.4689040000 0.0791210000 0.0465160000 0.0000000000 0.3356760000 0.0016790000 145626371 0 402718720 3.8780982494 3.9719269276 3.7897996902 2559 1311867255.8176100254 0.1207555309 0.0926675584 0.1212396473 0.0060664938 0.4944690000 0.0673500000 0.0556860000 0.0312540000 0.3322950000 0.0017710000 145630155 0 402718720 3.8763461113 3.9701085091 3.7868559361 2560 1311867255.8457250595 0.1205194145 0.0926784381 0.1212396473 0.0060659883 0.4835980000 0.0874620000 0.0560880000 0.0000000000 0.3320590000 0.0017900000 145633715 0 402718720 3.8763017654 3.9698164463 3.7839593887 2561 1311867255.8793790340 0.1206651926 0.0926893661 0.1212396473 0.0060649500 0.8609170000 0.0686470000 0.0701950000 0.0319230000 0.3330130000 0.3511800000 145637443 0 402718720 3.8762199879 3.9714646339 3.7810828686 2562 1311867255.9140310287 0.1204757020 0.0927002117 0.1212396473 0.0060638445 0.4910740000 0.0689380000 0.0796450000 0.0000000000 0.3348880000 0.0016840000 145641227 0 402718720 3.8763761520 3.9708626270 3.7782135010 2563 1311867255.9459080696 0.1197388619 0.0927107613 0.1212396473 0.0060632495 0.5484300000 0.0908170000 0.0833800000 0.0313720000 0.3352660000 0.0016970000 145644899 0 402718720 3.8762559891 3.9686839581 3.7748684883 2564 1311867255.9794859886 0.1201160997 0.0927214498 0.1212396473 0.0060621922 0.4591410000 0.0685900000 0.0491880000 0.0000010000 0.3337540000 0.0016890000 145648571 0 402718720 3.8757824898 3.9685924053 3.7718183994 2565 1311867256.0177969933 0.1193084493 0.0927318151 0.1212396473 0.0060610668 0.8492680000 0.0685960000 0.0532330000 0.0319390000 0.3369330000 0.3526460000 145652467 0 402718720 3.8764731884 3.9692070484 3.7689652443 2566 1311867256.0460140705 0.1206656247 0.0927427012 0.1212396473 0.0060602255 0.4958080000 0.0686660000 0.0820470000 0.0000000000 0.3374840000 0.0016910000 145656027 0 402718720 3.8737003803 3.9682800770 3.7658588886 2567 1311867256.0856881142 0.1185324788 0.0927527479 0.1212396473 0.0060653238 0.4862000000 0.0669940000 0.0399110000 0.0317390000 0.3399680000 0.0016600000 145659867 0 402718720 3.8759515285 3.9680807590 3.7628242970 2568 1311867256.1167299747 0.1189041138 0.0927629314 0.1212396473 0.0060658700 0.4880260000 0.0806240000 0.0593680000 0.0000010000 0.3403960000 0.0016900000 145663539 0 402718720 3.8755984306 3.9685845375 3.7600951195 2569 1311867256.1452269554 0.1182663143 0.0927728588 0.1212396473 0.0060659055 0.8816470000 0.0681800000 0.0832510000 0.0319880000 0.3377900000 0.3545050000 145667099 0 402718720 3.8758101463 3.9692382812 3.7573325634 2570 1311867256.1795060635 0.1192473397 0.0927831602 0.1212396473 0.0060664212 0.4979160000 0.0687790000 0.0797750000 0.0000000000 0.3417280000 0.0016930000 145670883 0 402718720 3.8737523556 3.9679262638 3.7541000843 2571 1311867256.2177491188 0.1185698211 0.0927931900 0.1212396473 0.0060668536 0.5320130000 0.0684510000 0.0798730000 0.0321000000 0.3439170000 0.0017060000 145674723 0 402718720 3.8737993240 3.9667427540 3.7512521744 2572 1311867256.2454690933 0.1183817908 0.0928031389 0.1212396473 0.0060666130 0.4714370000 0.0657910000 0.0521560000 0.0000010000 0.3458940000 0.0016560000 145678227 0 402718720 3.8734726906 3.9663689137 3.7482872009 2573 1311867256.2847039700 0.1176620796 0.0928128004 0.1212396473 0.0060664955 0.8824060000 0.0886210000 0.0465640000 0.0320420000 0.3459650000 0.3632640000 145682123 0 402718720 3.8741354942 3.9666242599 3.7449543476 2574 1311867256.3143420219 0.1168640032 0.0928221443 0.1212396473 0.0060669890 0.5057990000 0.0687920000 0.0840220000 0.0000010000 0.3453280000 0.0017110000 145685683 0 402718720 3.8732054234 3.9637134075 3.7410287857 2575 1311867256.3471789360 0.1166296974 0.0928313899 0.1212396473 0.0060666746 0.5016740000 0.0670200000 0.0459410000 0.0320440000 0.3490130000 0.0016850000 145689411 0 402718720 3.8728709221 3.9643030167 3.7374622822 2576 1311867256.3848650455 0.1162417382 0.0928404778 0.1212396473 0.0060656042 0.4764690000 0.0665340000 0.0518610000 0.0000010000 0.3504170000 0.0016800000 145693195 0 402718720 3.8728981018 3.9632616043 3.7337996960 2577 1311867256.4158649445 0.1159357429 0.0928494398 0.1212396473 0.0060646311 0.8915280000 0.0660810000 0.0643500000 0.0320650000 0.3521100000 0.3709700000 145696811 0 402718720 3.8721215725 3.9618058205 3.7299389839 2578 1311867256.4452838898 0.1158599183 0.0928583656 0.1212396473 0.0060650428 0.5064830000 0.0871320000 0.0580690000 0.0000000000 0.3536090000 0.0016690000 145700427 0 402718720 3.8717942238 3.9612045288 3.7264378071 2579 1311867256.4844601154 0.1149793938 0.0928669429 0.1212396473 0.0060671536 0.4995210000 0.0671520000 0.0415980000 0.0318070000 0.3509980000 0.0017760000 145704267 0 402718720 3.8720705509 3.9624607563 3.7226994038 2580 1311867256.5135829449 0.1150940880 0.0928755581 0.1212396473 0.0060669711 0.5091150000 0.0668960000 0.0825410000 0.0000010000 0.3516500000 0.0017870000 145707939 0 402718720 3.8701162338 3.9601476192 3.7187247276 2581 1311867256.5478789806 0.1137831733 0.0928836587 0.1212396473 0.0060856269 0.9048610000 0.0672620000 0.0685140000 0.0323060000 0.3544320000 0.3762390000 145711667 0 402718720 3.8699419498 3.9578218460 3.7149016857 2582 1311867256.5836489201 0.1129393578 0.0928914262 0.1212396473 0.0060938381 0.4746830000 0.0649070000 0.0474160000 0.0000010000 0.3543590000 0.0017610000 145715507 0 402718720 3.8718349934 3.9579365253 3.7115328312 2583 1311867256.6160368919 0.1122883931 0.0928989357 0.1212396473 0.0060926956 0.5343950000 0.0758100000 0.0599580000 0.0320860000 0.3589240000 0.0016460000 145719123 0 402718720 3.8726923466 3.9579992294 3.7083296776 2584 1311867256.6452310085 0.1147718802 0.0929074004 0.1212396473 0.0060920026 0.4969300000 0.0655340000 0.0613580000 0.0000010000 0.3612870000 0.0022020000 145722739 0 402718720 3.8688387871 3.9566912651 3.7048802376 2585 1311867256.6832759380 0.1150365770 0.0929159610 0.1212396473 0.0060910928 1.0015140000 0.0827540000 0.1007920000 0.0396780000 0.3751270000 0.3965290000 145726635 0 402718720 3.8689558506 3.9567687511 3.7014646530 2586 1311867256.7140300274 0.1152509674 0.0929245979 0.1212396473 0.0060915014 0.5270570000 0.0826840000 0.0594910000 0.0000010000 0.3761190000 0.0021880000 145730195 0 402718720 3.8691916466 3.9583041668 3.6988739967 2587 1311867256.7463369370 0.1145500094 0.0929329572 0.1212396473 0.0060908202 0.5926200000 0.0814640000 0.1000090000 0.0397780000 0.3637150000 0.0016750000 145733867 0 402718720 3.8698000908 3.9576795101 3.6958396435 2588 1311867256.7827401161 0.1150108129 0.0929414880 0.1212396473 0.0060899881 0.5106730000 0.0946860000 0.0448650000 0.0000000000 0.3634640000 0.0016610000 145737707 0 402718720 3.8702063560 3.9576992989 3.6930580139 2589 1311867256.8140430450 0.1141217053 0.0929496689 0.1212396473 0.0060897873 0.9032170000 0.0645170000 0.0513580000 0.0322430000 0.3636690000 0.3853980000 145741323 0 402718720 3.8723645210 3.9587459564 3.6903281212 2590 1311867256.8477399349 0.1158309951 0.0929585034 0.1212396473 0.0060899141 0.5005800000 0.0651200000 0.0628720000 0.0000000000 0.3648600000 0.0016720000 145745051 0 402718720 3.8700706959 3.9544045925 3.6871349812 2591 1311867256.8838980198 0.1153949276 0.0929671627 0.1212396473 0.0060903244 0.5497100000 0.0655910000 0.0767150000 0.0322960000 0.3674650000 0.0016860000 145748779 0 402718720 3.8700573444 3.9527964592 3.6835951805 2592 1311867256.9148108959 0.1138065532 0.0929752026 0.1212396473 0.0060897088 0.5153870000 0.0635490000 0.0746270000 0.0000010000 0.3695630000 0.0016510000 145752451 0 402718720 3.8724133968 3.9525856972 3.6800706387 2593 1311867256.9465379715 0.1148991510 0.0929836577 0.1212396473 0.0060887297 0.9495090000 0.0741050000 0.0780770000 0.0323160000 0.3668800000 0.3917840000 145756123 0 402718720 3.8717358112 3.9527010918 3.6763908863 2594 1311867256.9814610481 0.1156367362 0.0929923906 0.1212396473 0.0060878485 0.5572830000 0.0805860000 0.0820860000 0.0000000000 0.3858510000 0.0021610000 145759851 0 402718720 3.8709847927 3.9516699314 3.6725664139 2595 1311867257.0129959583 0.1152181998 0.0930009554 0.1212396473 0.0060876552 0.5858870000 0.0790610000 0.0812030000 0.0405130000 0.3774710000 0.0016540000 145763579 0 402718720 3.8715887070 3.9501848221 3.6688239574 2596 1311867257.0451910496 0.1173631772 0.0930103399 0.1212396473 0.0060897406 0.5045830000 0.0616110000 0.0610630000 0.0000010000 0.3742240000 0.0016360000 145767195 0 402718720 3.8696081638 3.9509530067 3.6657974720 2597 1311867257.0841369629 0.1161620319 0.0930192547 0.1212396473 0.0060889223 0.9698510000 0.0822120000 0.0777550000 0.0323450000 0.3718910000 0.3995970000 145771035 0 402718720 3.8725056648 3.9539210796 3.6626107693 2598 1311867257.1134428978 0.1169419661 0.0930284629 0.1212396473 0.0060878730 0.5404330000 0.0843060000 0.0778240000 0.0000000000 0.3702940000 0.0017450000 145774707 0 402718720 3.8715100288 3.9530866146 3.6599938869 2599 1311867257.1474308968 0.1169520617 0.0930376678 0.1212396473 0.0060868620 0.5268300000 0.0631020000 0.0525220000 0.0325280000 0.3709940000 0.0016540000 145778435 0 402718720 3.8714904785 3.9532387257 3.6567833424 2600 1311867257.1821229458 0.1150409207 0.0930461306 0.1212396473 0.0060863375 0.4941270000 0.0624170000 0.0498230000 0.0000010000 0.3742310000 0.0016530000 145782163 0 402718720 3.8738729954 3.9547414780 3.6533458233 2601 1311867257.2147839069 0.1139141545 0.0930541536 0.1212396473 0.0060898567 0.9497200000 0.0625520000 0.0786340000 0.0324690000 0.3708700000 0.3991020000 145785835 0 402718720 3.8745880127 3.9541585445 3.6500601768 2602 1311867257.2457039356 0.1154065505 0.0930627441 0.1212396473 0.0060913457 0.5204790000 0.0626620000 0.0780690000 0.0000000000 0.3720810000 0.0016510000 145789451 0 402718720 3.8726809025 3.9529097080 3.6468789577 2603 1311867257.2824490070 0.1162637845 0.0930716573 0.1212396473 0.0060903094 0.5561480000 0.0758870000 0.0652030000 0.0320600000 0.3753500000 0.0016460000 145793291 0 402718720 3.8722472191 3.9546892643 3.6440694332 2604 1311867257.3133430481 0.1168489978 0.0930807884 0.1212396473 0.0060894563 0.4915750000 0.0636040000 0.0470420000 0.0000010000 0.3728740000 0.0017650000 145796907 0 402718720 3.8725883961 3.9570715427 3.6412963867 2605 1311867257.3452849388 0.1176671833 0.0930902265 0.1212396473 0.0060884214 0.9528030000 0.0637330000 0.0794640000 0.0325620000 0.3726000000 0.3984270000 145800523 0 402718720 3.8711800575 3.9557859898 3.6381652355 2606 1311867257.3839631081 0.1198810190 0.0931005070 0.1212396473 0.0060877373 0.5318310000 0.0840110000 0.0658370000 0.0000010000 0.3742820000 0.0016620000 145804363 0 402718720 3.8696551323 3.9579653740 3.6353461742 2607 1311867257.4198129177 0.1221001521 0.0931116307 0.1221001521 0.0060903743 0.5502400000 0.0639180000 0.0727920000 0.0321590000 0.3733950000 0.0017650000 145808147 0 402718720 3.8690989017 3.9594902992 3.6331894398 2608 1311867257.4458611012 0.1225555018 0.0931229206 0.1225555018 0.0060895424 0.5285030000 0.0879960000 0.0566440000 0.0000010000 0.3761920000 0.0016630000 145811651 0 402718720 3.8689939976 3.9607717991 3.6310575008 2609 1311867257.4851269722 0.1235202402 0.0931345715 0.1235202402 0.0060894645 0.9322790000 0.0627690000 0.0400620000 0.0325280000 0.3737470000 0.4164370000 145815547 0 402718720 3.8683156967 3.9599680901 3.6283347607 2610 1311867257.5166249275 0.1256261468 0.0931470204 0.1256261468 0.0060898791 0.5614830000 0.0797850000 0.0821850000 0.0000010000 0.3906590000 0.0021510000 145819219 0 402718720 3.8674368858 3.9634277821 3.6262252331 2611 1311867257.5537879467 0.1249342710 0.0931591947 0.1256261468 0.0060889146 0.5806450000 0.0816840000 0.0590030000 0.0408300000 0.3902410000 0.0021790000 145823003 0 402718720 3.8703525066 3.9644458294 3.6242785454 2612 1311867257.5836200714 0.1221368834 0.0931702888 0.1256261468 0.0061009061 0.5567880000 0.0806620000 0.0925040000 0.0000000000 0.3759160000 0.0016600000 145826619 0 402718720 3.8741953373 3.9639661312 3.6219055653 2613 1311867257.6154460907 0.1239092574 0.0931820527 0.1256261468 0.0061062003 0.9660580000 0.0740920000 0.0745200000 0.0320600000 0.3765460000 0.4027840000 145830235 0 402718720 3.8728837967 3.9658210278 3.6194620132 2614 1311867257.6519720554 0.1215032861 0.0931928871 0.1256261468 0.0061054049 0.4843650000 0.0635240000 0.0404290000 0.0000010000 0.3723230000 0.0017480000 145834075 0 402718720 3.8771572113 3.9668955803 3.6176612377 2615 1311867257.6842958927 0.1262474358 0.0932055275 0.1262474358 0.0061061364 0.5593650000 0.0867220000 0.0569880000 0.0325020000 0.3754960000 0.0016660000 145837747 0 402718720 3.8720414639 3.9691324234 3.6150443554 2616 1311867257.7187778950 0.1256234348 0.0932179196 0.1262474358 0.0061050173 0.5221780000 0.0633230000 0.0793800000 0.0000010000 0.3714440000 0.0017460000 145841531 0 402718720 3.8738205433 3.9690980911 3.6130714417 2617 1311867257.7527809143 0.1239859685 0.0932296766 0.1262474358 0.0061064898 0.9447910000 0.0639140000 0.0662670000 0.0325500000 0.3751770000 0.4007730000 145845259 0 402718720 3.8766415119 3.9672098160 3.6115102768 2618 1311867257.7838430405 0.1212072521 0.0932403633 0.1262474358 0.0061060544 0.5437360000 0.0844890000 0.0761560000 0.0000010000 0.3753260000 0.0016700000 145848931 0 402718720 3.8815584183 3.9674589634 3.6101558208 2619 1311867257.8181409836 0.1204772443 0.0932507630 0.1262474358 0.0061056273 0.5366030000 0.0641210000 0.0604720000 0.0322140000 0.3717040000 0.0017660000 145852659 0 402718720 3.8832249641 3.9673700333 3.6084477901 2620 1311867257.8530700207 0.1226214021 0.0932619731 0.1262474358 0.0061140735 0.4853930000 0.0638950000 0.0404910000 0.0000010000 0.3732780000 0.0016560000 145856387 0 402718720 3.8821709156 3.9690403938 3.6063647270 2621 1311867257.8854579926 0.1221070811 0.0932729785 0.1262474358 0.0061155844 0.9254680000 0.0637120000 0.0468390000 0.0322650000 0.3734990000 0.4030300000 145860003 0 402718720 3.8834683895 3.9689502716 3.6045501232 2622 1311867257.9152529240 0.1209117174 0.0932835196 0.1262474358 0.0061162308 0.5246260000 0.0640890000 0.0756560000 0.0000010000 0.3770920000 0.0016630000 145863619 0 402718720 3.8859627247 3.9681041241 3.6034319401 2623 1311867257.9559030533 0.1201654077 0.0932937681 0.1262474358 0.0061157630 0.5429090000 0.0757790000 0.0533510000 0.0322240000 0.3734220000 0.0017520000 145867571 0 402718720 3.8880589008 3.9676947594 3.6021759510 2624 1311867257.9850780964 0.1184915677 0.0933033710 0.1262474358 0.0061152223 0.4996760000 0.0638920000 0.0534660000 0.0000010000 0.3744970000 0.0016670000 145871131 0 402718720 3.8905179501 3.9663217068 3.6009979248 2625 1311867258.0135710239 0.1198862717 0.0933134978 0.1262474358 0.0061146617 0.9246350000 0.0635430000 0.0382000000 0.0326310000 0.3789050000 0.4052090000 145874747 0 402718720 3.8887300491 3.9659507275 3.5988917351 2626 1311867258.0526609421 0.1198196188 0.0933235915 0.1262474358 0.0061141146 0.5268140000 0.0639780000 0.0757030000 0.0000000000 0.3792600000 0.0016670000 145878587 0 402718720 3.8897037506 3.9646458626 3.5974912643 2627 1311867258.0836610794 0.1212526038 0.0933342230 0.1262474358 0.0061148725 0.5388980000 0.0632810000 0.0550360000 0.0326150000 0.3802120000 0.0016570000 145882203 0 402718720 3.8881285191 3.9642241001 3.5961039066 2628 1311867258.1137859821 0.1196966693 0.0933442544 0.1262474358 0.0061145354 0.5498690000 0.0813900000 0.0791350000 0.0000010000 0.3814900000 0.0016680000 145885875 0 402718720 3.8902504444 3.9631142616 3.5946562290 2629 1311867258.1501069069 0.1219631284 0.0933551402 0.1262474358 0.0061165038 0.9319310000 0.0623580000 0.0459150000 0.0326580000 0.3781960000 0.4063910000 145889603 0 402718720 3.8878660202 3.9643497467 3.5923006535 2630 1311867258.1848480701 0.1216786578 0.0933659096 0.1262474358 0.0061154091 0.4952640000 0.0624600000 0.0459410000 0.0000010000 0.3790620000 0.0016520000 145893331 0 402718720 3.8893027306 3.9631259441 3.5915100574 2631 1311867258.2162730694 0.1205546036 0.0933762436 0.1262474358 0.0061145107 0.5276470000 0.0612380000 0.0431300000 0.0324470000 0.3830220000 0.0016540000 145897059 0 402718720 3.8910577297 3.9623055458 3.5901234150 2632 1311867258.2524979115 0.1206080988 0.0933865901 0.1262474358 0.0061149516 0.5282840000 0.0627850000 0.0743650000 0.0000000000 0.3832920000 0.0016550000 145900843 0 402718720 3.8914344311 3.9622130394 3.5889356136 2633 1311867258.2857830524 0.1204680726 0.0933968755 0.1262474358 0.0061141571 0.9872400000 0.0922060000 0.0557130000 0.0322160000 0.3836710000 0.4165980000 145904515 0 402718720 3.8915705681 3.9612529278 3.5877928734 2634 1311867258.3132910728 0.1191023439 0.0934066346 0.1262474358 0.0061135600 0.5838760000 0.0793160000 0.0975000000 0.0000010000 0.3980770000 0.0021520000 145908131 0 402718720 3.8931496143 3.9586501122 3.5870220661 2635 1311867258.3510708809 0.1191315800 0.0934163974 0.1262474358 0.0061147487 0.6158010000 0.0792630000 0.0887140000 0.0405690000 0.3982920000 0.0021520000 145911915 0 402718720 3.8943796158 3.9592390060 3.5863120556 2636 1311867258.3812119961 0.1192312464 0.0934261906 0.1262474358 0.0061137114 0.5796470000 0.0778860000 0.0942500000 0.0000000000 0.3985400000 0.0021380000 145915475 0 402718720 3.8944456577 3.9597480297 3.5855712891 2637 1311867258.4142711163 0.1191611663 0.0934359497 0.1262474358 0.0061126470 0.9754370000 0.0644630000 0.0737870000 0.0326740000 0.3844700000 0.4137480000 145919147 0 402718720 3.8943395615 3.9594769478 3.5844817162 2638 1311867258.4507009983 0.1212463975 0.0934464920 0.1262474358 0.0061133268 0.5475790000 0.0803220000 0.0780700000 0.0000010000 0.3813250000 0.0016490000 145922987 0 402718720 3.8918590546 3.9605298042 3.5833830833 2639 1311867258.4826059341 0.1210173294 0.0934569395 0.1262474358 0.0061127291 0.5316940000 0.0628140000 0.0438480000 0.0327280000 0.3844780000 0.0016490000 145926715 0 402718720 3.8917179108 3.9588885307 3.5825359821 2640 1311867258.5139899254 0.1218853518 0.0934677078 0.1262474358 0.0061125166 0.5277500000 0.0616830000 0.0736260000 0.0000010000 0.3844890000 0.0016370000 145930331 0 402718720 3.8909397125 3.9570851326 3.5815682411 2641 1311867258.5500509739 0.1217092499 0.0934784013 0.1262474358 0.0061225745 0.9625860000 0.0624280000 0.0619500000 0.0327310000 0.3850680000 0.4141620000 145934115 0 402718720 3.8905401230 3.9559414387 3.5802106857 2642 1311867258.5836040974 0.1223957166 0.0934893465 0.1262474358 0.0061287569 0.5485990000 0.0806770000 0.0775350000 0.0000000000 0.3825420000 0.0016440000 145937787 0 402718720 3.8908104897 3.9559168816 3.5787096024 2643 1311867258.6141679287 0.1230502427 0.0935005311 0.1262474358 0.0061289874 0.5661540000 0.0617210000 0.0772620000 0.0327760000 0.3865610000 0.0016450000 145941403 0 402718720 3.8900716305 3.9548978806 3.5770211220 2644 1311867258.6506860256 0.1244064644 0.0935122202 0.1262474358 0.0061289201 0.5311570000 0.0620870000 0.0773760000 0.0000010000 0.3835020000 0.0017300000 145945187 0 402718720 3.8896987438 3.9555776119 3.5751938820 2645 1311867258.6856470108 0.1241556853 0.0935238056 0.1262474358 0.0061288704 0.9515940000 0.0621670000 0.0433680000 0.0327780000 0.3885120000 0.4186000000 145948971 0 402718720 3.8905825615 3.9533402920 3.5733375549 2646 1311867258.7134239674 0.1239978373 0.0935353227 0.1262474358 0.0061279315 0.5437860000 0.0725430000 0.0733520000 0.0000010000 0.3900390000 0.0016410000 145952475 0 402718720 3.8906612396 3.9496309757 3.5712039471 2647 1311867258.7543559074 0.1258683205 0.0935475376 0.1262474358 0.0061289119 0.5648220000 0.0605130000 0.0764660000 0.0323080000 0.3873490000 0.0017170000 145956371 0 402718720 3.8905322552 3.9508717060 3.5690398216 2648 1311867258.7843589783 0.1249573529 0.0935593993 0.1262474358 0.0061291295 0.5327340000 0.0607880000 0.0760630000 0.0000000000 0.3876960000 0.0017280000 145959987 0 402718720 3.8920903206 3.9519941807 3.5675039291 2649 1311867258.8193690777 0.1239630505 0.0935708767 0.1262474358 0.0061284230 0.9664340000 0.0608890000 0.0503260000 0.0324900000 0.3927520000 0.4236980000 145963771 0 402718720 3.8934090137 3.9505352974 3.5654935837 2650 1311867258.8514409065 0.1264243275 0.0935832743 0.1264243275 0.0061278864 0.5049280000 0.0612820000 0.0427840000 0.0000010000 0.3928430000 0.0016320000 145967499 0 402718720 3.8901500702 3.9490220547 3.5633630753 2651 1311867258.8846011162 0.1253271848 0.0935952486 0.1264243275 0.0061270379 0.5639590000 0.0766550000 0.0577440000 0.0324610000 0.3887980000 0.0017290000 145971115 0 402718720 3.8928682804 3.9488773346 3.5619976521 2652 1311867258.9178969860 0.1249150410 0.0936070585 0.1264243275 0.0061258968 0.5039800000 0.0605800000 0.0425300000 0.0000010000 0.3929510000 0.0016180000 145974843 0 402718720 3.8940002918 3.9480211735 3.5600087643 2653 1311867258.9506199360 0.1256234199 0.0936191264 0.1264243275 0.0061255882 1.0028570000 0.0767080000 0.0756660000 0.0327400000 0.3895550000 0.4216760000 145978515 0 402718720 3.8934762478 3.9468364716 3.5580182076 2654 1311867258.9841670990 0.1262091547 0.0936314060 0.1264243275 0.0061262930 0.5352380000 0.0605800000 0.0760760000 0.0000010000 0.3906920000 0.0016290000 145982299 0 402718720 3.8942463398 3.9471387863 3.5561630726 2655 1311867259.0194389820 0.1260994375 0.0936436350 0.1264243275 0.0061254488 0.5409170000 0.0607910000 0.0450900000 0.0329360000 0.3942900000 0.0016320000 145985971 0 402718720 3.8952803612 3.9458439350 3.5535910130 2656 1311867259.0497961044 0.1264349222 0.0936559812 0.1264349222 0.0061275976 0.5368470000 0.0609620000 0.0722560000 0.0000000000 0.3958300000 0.0016290000 145989643 0 402718720 3.8961076736 3.9434955120 3.5515468121 2657 1311867259.0845470428 0.1265561134 0.0936683636 0.1265561134 0.0061275063 0.9692220000 0.0601400000 0.0424410000 0.0328520000 0.3969860000 0.4306040000 145993315 0 402718720 3.8980116844 3.9446706772 3.5490844250 2658 1311867259.1189930439 0.1272689253 0.0936810049 0.1272689253 0.0061269865 0.5404540000 0.0726330000 0.0635290000 0.0000010000 0.3964740000 0.0016290000 145997099 0 402718720 3.8989074230 3.9459702969 3.5467877388 2659 1311867259.1506030560 0.1283930987 0.0936940595 0.1283930987 0.0061286554 0.5395630000 0.0602850000 0.0447270000 0.0328960000 0.3934860000 0.0017140000 146000771 0 402718720 3.8988008499 3.9442281723 3.5447692871 2660 1311867259.1837821007 0.1274928153 0.0937067658 0.1283930987 0.0061285151 0.5393140000 0.0611610000 0.0759120000 0.0000000000 0.3940820000 0.0017110000 146004443 0 402718720 3.9019212723 3.9435925484 3.5428938866 2661 1311867259.2191979885 0.1266535372 0.0937191471 0.1283930987 0.0061274249 0.9843180000 0.0600160000 0.0567670000 0.0329110000 0.3957170000 0.4326330000 146008283 0 402718720 3.9049093723 3.9438812733 3.5407140255 2662 1311867259.2532899380 0.1255601943 0.0937311084 0.1283930987 0.0061273042 0.5096380000 0.0603300000 0.0424550000 0.0000000000 0.3990040000 0.0016280000 146012011 0 402718720 3.9090702534 3.9417254925 3.5381863117 2663 1311867259.2815980911 0.1260582507 0.0937432478 0.1283930987 0.0061263545 0.5630780000 0.0739240000 0.0483060000 0.0329590000 0.4000680000 0.0016240000 146015571 0 402718720 3.9093642235 3.9414660931 3.5359606743 2664 1311867259.3212718964 0.1273546815 0.0937558647 0.1283930987 0.0061262737 0.5393260000 0.0592980000 0.0707400000 0.0000000000 0.4014070000 0.0016060000 146019467 0 402718720 3.9101715088 3.9424796104 3.5333454609 2665 1311867259.3519039154 0.1251339763 0.0937676389 0.1283930987 0.0061252393 1.0105250000 0.0590590000 0.0703740000 0.0328640000 0.4026700000 0.4393090000 146023139 0 402718720 3.9140343666 3.9424288273 3.5300621986 2666 1311867259.3840188980 0.1269107163 0.0937800706 0.1283930987 0.0061243331 0.5412530000 0.0587520000 0.0704670000 0.0000000000 0.4041620000 0.0016080000 146026755 0 402718720 3.9127073288 3.9414873123 3.5266027451 2667 1311867259.4204289913 0.1290151775 0.0937932821 0.1290151775 0.0061253385 0.5744860000 0.0582340000 0.0694450000 0.0328930000 0.4060970000 0.0016010000 146030539 0 402718720 3.9115588665 3.9407024384 3.5237154961 2668 1311867259.4579179287 0.1288547963 0.0938064236 0.1290151775 0.0061243425 0.5652160000 0.0871360000 0.0669110000 0.0000010000 0.4029230000 0.0016870000 146034379 0 402718720 3.9139568806 3.9424088001 3.5207457542 2669 1311867259.4850549698 0.1290467978 0.0938196272 0.1290467978 0.0061248030 1.0251020000 0.0573900000 0.0727580000 0.0328810000 0.4080780000 0.4477240000 146037827 0 402718720 3.9140803814 3.9411346912 3.5180110931 2670 1311867259.5189819336 0.1272520721 0.0938321487 0.1290467978 0.0061241507 0.5319170000 0.0694250000 0.0458140000 0.0000010000 0.4088970000 0.0015860000 146041555 0 402718720 3.9170639515 3.9385299683 3.5151209831 2671 1311867259.5505928993 0.1286725253 0.0938451927 0.1290467978 0.0061231564 0.5573280000 0.0563730000 0.0541780000 0.0329300000 0.4056770000 0.0016730000 146045227 0 402718720 3.9162578583 3.9381406307 3.5117223263 2672 1311867259.5823240280 0.1275983453 0.0938578248 0.1290467978 0.0061226014 0.5323200000 0.0571010000 0.0600910000 0.0000000000 0.4070140000 0.0016760000 146048955 0 402718720 3.9186513424 3.9372105598 3.5088853836 2673 1311867259.6192719936 0.1271739602 0.0938702888 0.1290467978 0.0061226985 1.0592500000 0.0865200000 0.0652730000 0.0325790000 0.4127750000 0.4557900000 146052683 0 402718720 3.9211652279 3.9381036758 3.5055375099 2674 1311867259.6494839191 0.1274000257 0.0938828280 0.1290467978 0.0061220164 0.5210980000 0.0559320000 0.0479190000 0.0000010000 0.4094410000 0.0015730000 146056243 0 402718720 3.9217624664 3.9397115707 3.5024785995 2675 1311867259.6828589439 0.1279613823 0.0938955676 0.1290467978 0.0061224455 0.5654660000 0.0554020000 0.0593410000 0.0330360000 0.4098620000 0.0015680000 146059971 0 402718720 3.9220211506 3.9413461685 3.4992256165 2676 1311867259.7201991081 0.1279432178 0.0939082909 0.1290467978 0.0061216746 0.5119640000 0.0552950000 0.0341820000 0.0000010000 0.4146800000 0.0015600000 146063811 0 402718720 3.9227311611 3.9423010349 3.4959082603 2677 1311867259.7557690144 0.1261340678 0.0939203290 0.1290467978 0.0061206858 1.0510380000 0.0776970000 0.0713300000 0.0330390000 0.4097890000 0.4527210000 146067595 0 402718720 3.9251279831 3.9407432079 3.4934034348 2678 1311867259.7817859650 0.1291526407 0.0939334852 0.1291526407 0.0061197533 0.5606740000 0.0716780000 0.0710940000 0.0000010000 0.4100870000 0.0015780000 146071099 0 402718720 3.9215168953 3.9414913654 3.4910538197 2679 1311867259.8177011013 0.1276081204 0.0939460550 0.1291526407 0.0061187622 0.5694730000 0.0562970000 0.0568770000 0.0329650000 0.4154770000 0.0015620000 146074883 0 402718720 3.9239985943 3.9420280457 3.4885296822 2680 1311867259.8548939228 0.1265973449 0.0939582383 0.1291526407 0.0061180108 0.5252550000 0.0570820000 0.0462210000 0.0000010000 0.4141440000 0.0015870000 146078667 0 402718720 3.9263937473 3.9418361187 3.4867346287 2681 1311867259.8818409443 0.1284648478 0.0939711091 0.1291526407 0.0061174265 1.0454290000 0.0576100000 0.0687320000 0.0330990000 0.4141080000 0.4649140000 146082227 0 402718720 3.9237575531 3.9410219193 3.4842343330 2682 1311867259.9219179153 0.1271469444 0.0939834789 0.1291526407 0.0061170432 0.5704190000 0.0723750000 0.0606630000 0.0000010000 0.4284210000 0.0020460000 146086123 0 402718720 3.9264147282 3.9426503181 3.4818844795 2683 1311867259.9520130157 0.1269067824 0.0939957500 0.1291526407 0.0061159953 0.6419850000 0.0727540000 0.0901890000 0.0418150000 0.4281780000 0.0020600000 146089739 0 402718720 3.9272987843 3.9446654320 3.4792108536 2684 1311867259.9923639297 0.1275114864 0.0940082373 0.1291526407 0.0061158655 0.5840800000 0.0724540000 0.0828120000 0.0000000000 0.4208570000 0.0015950000 146093635 0 402718720 3.9271383286 3.9432442188 3.4769032001 2685 1311867260.0219469070 0.1288117468 0.0940211995 0.1291526407 0.0061155690 1.0138670000 0.0574620000 0.0461800000 0.0331860000 0.4142330000 0.4564180000 146097195 0 402718720 3.9266319275 3.9437921047 3.4753394127 2686 1311867260.0493209362 0.1253762543 0.0940328730 0.1291526407 0.0061154233 0.5844920000 0.0939400000 0.0682830000 0.0000010000 0.4143710000 0.0015840000 146100699 0 402718720 3.9317777157 3.9453878403 3.4730057716 2687 1311867260.0888080597 0.1261546910 0.0940448275 0.1291526407 0.0061149968 0.5556390000 0.0576520000 0.0433960000 0.0328590000 0.4138670000 0.0016110000 146104595 0 402718720 3.9314639568 3.9451808929 3.4703311920 2688 1311867260.1210498810 0.1268703341 0.0940570394 0.1291526407 0.0061175322 0.5194610000 0.0578800000 0.0434550000 0.0000010000 0.4098810000 0.0016800000 146108267 0 402718720 3.9323990345 3.9455852509 3.4677546024 2689 1311867260.1513869762 0.1247338131 0.0940684476 0.1291526407 0.0061198725 1.0385700000 0.0574040000 0.0726380000 0.0331810000 0.4114500000 0.4576140000 146111883 0 402718720 3.9355847836 3.9460780621 3.4651944637 2690 1311867260.1908860207 0.1249831840 0.0940799401 0.1291526407 0.0061188469 0.5503430000 0.0577950000 0.0688100000 0.0000010000 0.4158860000 0.0015940000 146115723 0 402718720 3.9371390343 3.9466366768 3.4622647762 2691 1311867260.2204439640 0.1275534183 0.0940923791 0.1291526407 0.0061182124 0.5727820000 0.0685280000 0.0463680000 0.0331940000 0.4167990000 0.0015970000 146119339 0 402718720 3.9343593121 3.9480159283 3.4588253498 2692 1311867260.2496669292 0.1280816197 0.0941050052 0.1291526407 0.0061171663 0.5482720000 0.0703660000 0.0521670000 0.0000000000 0.4178420000 0.0016040000 146123011 0 402718720 3.9340791702 3.9469375610 3.4557631016 2693 1311867260.2869880199 0.1294941306 0.0941181463 0.1294941306 0.0061172375 1.0223900000 0.0564900000 0.0481790000 0.0331780000 0.4149450000 0.4632730000 146126795 0 402718720 3.9344868660 3.9496333599 3.4528465271 2694 1311867260.3195590973 0.1288350374 0.0941310331 0.1294941306 0.0061164661 0.5516950000 0.0566480000 0.0724050000 0.0000000000 0.4144250000 0.0016860000 146130467 0 402718720 3.9359502792 3.9510893822 3.4495618343 2695 1311867260.3505260944 0.1314184666 0.0941448688 0.1314184666 0.0061164281 0.5669460000 0.0563770000 0.0545700000 0.0331970000 0.4145700000 0.0016730000 146134139 0 402718720 3.9330677986 3.9508614540 3.4464399815 2696 1311867260.3868899345 0.1343159080 0.0941597691 0.1343159080 0.0061195123 0.5250400000 0.0565450000 0.0426590000 0.0000010000 0.4179280000 0.0015940000 146137923 0 402718720 3.9312262535 3.9537942410 3.4437274933 2697 1311867260.4211299419 0.1339688897 0.0941745296 0.1343159080 0.0061187293 1.0328880000 0.0566810000 0.0517300000 0.0331970000 0.4200920000 0.4648210000 146141595 0 402718720 3.9328238964 3.9571170807 3.4407098293 2698 1311867260.4521770477 0.1325668693 0.0941887595 0.1343159080 0.0061179015 0.5627450000 0.0718010000 0.0676050000 0.0000000000 0.4153930000 0.0016080000 146145211 0 402718720 3.9348137379 3.9569303989 3.4382286072 2699 1311867260.4867470264 0.1347475797 0.0942037869 0.1347475797 0.0061189990 0.5953220000 0.0564880000 0.0666260000 0.0332690000 0.4299510000 0.0020550000 146148939 0 402718720 3.9328107834 3.9581007957 3.4352660179 2700 1311867260.5192930698 0.1338275969 0.0942184624 0.1347475797 0.0061207314 0.5766020000 0.0723760000 0.0612320000 0.0000000000 0.4339620000 0.0020630000 146152499 0 402718720 3.9355044365 3.9610502720 3.4324660301 2701 1311867260.5527870655 0.1348484010 0.0942335049 0.1348484010 0.0061203776 1.0770020000 0.0743430000 0.0549500000 0.0418040000 0.4328560000 0.4667090000 146156283 0 402718720 3.9350600243 3.9613292217 3.4302089214 2702 1311867260.5880448818 0.1369813234 0.0942493257 0.1369813234 0.0061203410 0.5381480000 0.0704180000 0.0414310000 0.0000000000 0.4183260000 0.0016130000 146160067 0 402718720 3.9330136776 3.9612605572 3.4269373417 2703 1311867260.6196188927 0.1363498122 0.0942649012 0.1369813234 0.0061197731 0.5927210000 0.0875490000 0.0496250000 0.0333720000 0.4142530000 0.0016150000 146163739 0 402718720 3.9342651367 3.9609780312 3.4239420891 2704 1311867260.6493411064 0.1342252940 0.0942796794 0.1369813234 0.0061189221 0.5302280000 0.0576920000 0.0495150000 0.0000000000 0.4141630000 0.0017100000 146167299 0 402718720 3.9374184608 3.9598801136 3.4215362072 2705 1311867260.6865339279 0.1343121380 0.0942944789 0.1369813234 0.0061188873 1.0207940000 0.0581320000 0.0416040000 0.0333890000 0.4190280000 0.4622720000 146171139 0 402718720 3.9396491051 3.9578204155 3.4186360836 2706 1311867260.7188229561 0.1380394846 0.0943106448 0.1380394846 0.0061180722 0.5559350000 0.0576490000 0.0700530000 0.0000010000 0.4202790000 0.0016100000 146174811 0 402718720 3.9356510639 3.9570543766 3.4157369137 2707 1311867260.7493369579 0.1363993734 0.0943261929 0.1380394846 0.0061190241 0.5900620000 0.0579800000 0.0697380000 0.0334710000 0.4209580000 0.0016060000 146178371 0 402718720 3.9388728142 3.9580218792 3.4132404327 2708 1311867260.7859649658 0.1349287480 0.0943411865 0.1380394846 0.0061208484 0.5505090000 0.0690630000 0.0560830000 0.0000010000 0.4174300000 0.0016200000 146182211 0 402718720 3.9411954880 3.9561517239 3.4104573727 2709 1311867260.8179080486 0.1371169239 0.0943569767 0.1380394846 0.0061224747 1.0350980000 0.0580860000 0.0470350000 0.0334660000 0.4225670000 0.4675460000 146185939 0 402718720 3.9395205975 3.9551353455 3.4068262577 2710 1311867260.8514599800 0.1359112412 0.0943723104 0.1380394846 0.0061265166 0.5570500000 0.0562630000 0.0724850000 0.0000010000 0.4203980000 0.0016110000 146189611 0 402718720 3.9411211014 3.9536716938 3.4037945271 2711 1311867260.8867430687 0.1360209733 0.0943876732 0.1380394846 0.0061261314 0.5698810000 0.0574270000 0.0466330000 0.0330940000 0.4248140000 0.0015990000 146193283 0 402718720 3.9418802261 3.9522681236 3.4001646042 2712 1311867260.9177849293 0.1375407279 0.0944035851 0.1380394846 0.0061254504 0.5301800000 0.0570280000 0.0427830000 0.0000010000 0.4224400000 0.0015990000 146196955 0 402718720 3.9410412312 3.9535517693 3.3971483707 2713 1311867260.9494459629 0.1371632367 0.0944193461 0.1380394846 0.0061378338 1.0883220000 0.0828100000 0.0604240000 0.0331990000 0.4221440000 0.4833770000 146200627 0 402718720 3.9407484531 3.9527468681 3.3936774731 2714 1311867260.9869680405 0.1389026046 0.0944357364 0.1389026046 0.0061475707 0.5277950000 0.0565510000 0.0357360000 0.0000010000 0.4275750000 0.0016030000 146204467 0 402718720 3.9404096603 3.9508421421 3.3905820847 2715 1311867261.0202260017 0.1416086406 0.0944531113 0.1416086406 0.0061475011 0.5841050000 0.0562960000 0.0574670000 0.0334730000 0.4289040000 0.0015970000 146208139 0 402718720 3.9371297359 3.9495325089 3.3871417046 2716 1311867261.0519640446 0.1400253028 0.0944698905 0.1416086406 0.0061484709 0.5609860000 0.0556870000 0.0668980000 0.0000010000 0.4304260000 0.0015910000 146211811 0 402718720 3.9391767979 3.9477872849 3.3845722675 2717 1311867261.0871579647 0.1411121190 0.0944870573 0.1416086406 0.0061474401 1.0556080000 0.0552670000 0.0455250000 0.0334900000 0.4319860000 0.4829660000 146215595 0 402718720 3.9375023842 3.9441442490 3.3811273575 2718 1311867261.1197659969 0.1430294514 0.0945049169 0.1430294514 0.0061475021 0.5427850000 0.0555170000 0.0453890000 0.0000010000 0.4339440000 0.0015890000 146219267 0 402718720 3.9352092743 3.9417471886 3.3778023720 2719 1311867261.1530790329 0.1421927363 0.0945224556 0.1430294514 0.0061502161 0.5705540000 0.0545710000 0.0392240000 0.0332580000 0.4355840000 0.0015780000 146222995 0 402718720 3.9365203381 3.9413361549 3.3747580051 2720 1311867261.1872630119 0.1443275511 0.0945407663 0.1443275511 0.0061527360 0.5645260000 0.0541040000 0.0656720000 0.0000010000 0.4368110000 0.0015750000 146226723 0 402718720 3.9336612225 3.9397239685 3.3715474606 2721 1311867261.2191090584 0.1449464560 0.0945592910 0.1449464560 0.0061577622 1.0773770000 0.0544520000 0.0496670000 0.0335600000 0.4383580000 0.4949060000 146230395 0 402718720 3.9319646358 3.9370689392 3.3685216904 2722 1311867261.2548229694 0.1470546871 0.0945785766 0.1470546871 0.0061570740 0.5413900000 0.0511970000 0.0426590000 0.0000000000 0.4396270000 0.0015340000 146234123 0 402718720 3.9303543568 3.9377682209 3.3659458160 2723 1311867261.2879600525 0.1469526440 0.0945978106 0.1470546871 0.0061565395 0.6002080000 0.0780120000 0.0452700000 0.0334940000 0.4351210000 0.0016390000 146237907 0 402718720 3.9305648804 3.9386229515 3.3630800247 2724 1311867261.3185029030 0.1495416909 0.0946179809 0.1495416909 0.0061627737 0.5628990000 0.0520110000 0.0669550000 0.0000000000 0.4357390000 0.0016370000 146241579 0 402718720 3.9273033142 3.9396951199 3.3605656624 2725 1311867261.3546299934 0.1522089094 0.0946391152 0.1522089094 0.0061632020 1.0957140000 0.0518240000 0.0610320000 0.0335110000 0.4413090000 0.5015950000 146245307 0 402718720 3.9234035015 3.9405574799 3.3578023911 2726 1311867261.3858330250 0.1527429074 0.0946604298 0.1527429074 0.0061622500 0.5589780000 0.0513210000 0.0578110000 0.0000000000 0.4419540000 0.0015320000 146248923 0 402718720 3.9223353863 3.9417924881 3.3555951118 2727 1311867261.4186379910 0.1533207297 0.0946819408 0.1533207297 0.0061613658 0.5721260000 0.0512840000 0.0377970000 0.0334440000 0.4416770000 0.0015460000 146252595 0 402718720 3.9214708805 3.9434161186 3.3541529179 2728 1311867261.4558680058 0.1517881006 0.0947028741 0.1533207297 0.0061632564 0.5359640000 0.0531460000 0.0332850000 0.0000000000 0.4416070000 0.0015390000 146256435 0 402718720 3.9210014343 3.9409160614 3.3522429466 2729 1311867261.4862189293 0.1519365013 0.0947238465 0.1533207297 0.0061650623 1.0934410000 0.0629520000 0.0478090000 0.0334950000 0.4418780000 0.5009190000 146260051 0 402718720 3.9204213619 3.9406301975 3.3503198624 2730 1311867261.5178630352 0.1547254324 0.0947458251 0.1547254324 0.0061644461 0.5341580000 0.0515760000 0.0326200000 0.0000000000 0.4420240000 0.0015490000 146263779 0 402718720 3.9165408611 3.9411213398 3.3491549492 2731 1311867261.5556519032 0.1517748982 0.0947667072 0.1547254324 0.0061635458 0.6001840000 0.0523550000 0.0643290000 0.0336170000 0.4419280000 0.0015550000 146267563 0 402718720 3.9195437431 3.9413540363 3.3476045132 2732 1311867261.5857899189 0.1540352106 0.0947884014 0.1547254324 0.0061664341 0.5670430000 0.0526620000 0.0643520000 0.0000000000 0.4421040000 0.0015580000 146271179 0 402718720 3.9161756039 3.9399828911 3.3460071087 2733 1311867261.6174640656 0.1535579860 0.0948099051 0.1547254324 0.0061658409 1.0826000000 0.0694130000 0.0347150000 0.0332940000 0.4374940000 0.5012660000 146274907 0 402718720 3.9164612293 3.9421095848 3.3441455364 2734 1311867261.6652009487 0.1532464921 0.0948312791 0.1547254324 0.0061663340 0.5792000000 0.0654910000 0.0678300000 0.0000000000 0.4376160000 0.0016530000 146278971 0 402718720 3.9158153534 3.9413585663 3.3415005207 2735 1311867261.6889929771 0.1554942131 0.0948534593 0.1554942131 0.0061657840 0.5816710000 0.0527600000 0.0437540000 0.0336880000 0.4435020000 0.0015650000 146282419 0 402718720 3.9123356342 3.9414067268 3.3388512135 2736 1311867261.7193109989 0.1612931341 0.0948777428 0.1612931341 0.0061668222 0.5903420000 0.0739760000 0.0674780000 0.0000000000 0.4409170000 0.0015560000 146285979 0 402718720 3.9050567150 3.9434885979 3.3353948593 2737 1311867261.7601549625 0.1581826359 0.0949008721 0.1612931341 0.0061683824 1.0658690000 0.0507980000 0.0338720000 0.0330780000 0.4406080000 0.5010640000 146289819 0 402718720 3.9090852737 3.9445250034 3.3325355053 2738 1311867261.7876880169 0.1590271741 0.0949242930 0.1612931341 0.0061698289 0.5767990000 0.0616010000 0.0670110000 0.0000000000 0.4402100000 0.0015500000 146293379 0 402718720 3.9079420567 3.9474167824 3.3294513226 2739 1311867261.8213939667 0.1602079272 0.0949481278 0.1612931341 0.0061763233 0.5726700000 0.0521260000 0.0328800000 0.0337020000 0.4459200000 0.0015570000 146297107 0 402718720 3.9068872929 3.9505009651 3.3261973858 2740 1311867261.8598148823 0.1616480201 0.0949724709 0.1616480201 0.0061756933 0.5388880000 0.0519740000 0.0328590000 0.0000010000 0.4460410000 0.0015550000 146300891 0 402718720 3.9047627449 3.9495720863 3.3235406876 2741 1311867261.8885459900 0.1588851959 0.0949957882 0.1616480201 0.0061807459 1.0953070000 0.0637270000 0.0381820000 0.0333620000 0.4461120000 0.5074720000 146304507 0 402718720 3.9080505371 3.9516437054 3.3212692738 2742 1311867261.9212360382 0.1578783542 0.0950187213 0.1616480201 0.0061845124 0.6012250000 0.0519310000 0.0800110000 0.0000010000 0.4602300000 0.0019900000 146308179 0 402718720 3.9096693993 3.9538505077 3.3180582523 2743 1311867261.9592299461 0.1594564766 0.0950422130 0.1616480201 0.0061838088 0.6176240000 0.0658770000 0.0498040000 0.0424690000 0.4515500000 0.0015690000 146312075 0 402718720 3.9079563618 3.9546017647 3.3146429062 2744 1311867261.9886140823 0.1579165161 0.0950651264 0.1616480201 0.0061835749 0.5427740000 0.0525850000 0.0407910000 0.0000010000 0.4413650000 0.0015650000 146315635 0 402718720 3.9102053642 3.9546449184 3.3125691414 2745 1311867262.0219531059 0.1581418812 0.0950881051 0.1616480201 0.0061831348 1.1105920000 0.0530090000 0.0649500000 0.0333840000 0.4463370000 0.5064780000 146319363 0 402718720 3.9106907845 3.9566779137 3.3095798492 2746 1311867262.0576629639 0.1607251614 0.0951120079 0.1616480201 0.0061823322 0.5506380000 0.0524920000 0.0437410000 0.0000010000 0.4464210000 0.0015760000 146323147 0 402718720 3.9080750942 3.9574456215 3.3063960075 2747 1311867262.0944681168 0.1589125097 0.0951352334 0.1616480201 0.0061815601 0.6063420000 0.0526830000 0.0650470000 0.0337760000 0.4468520000 0.0015790000 146326875 0 402718720 3.9112894535 3.9580678940 3.3037319183 2748 1311867262.1180479527 0.1580621898 0.0951581326 0.1616480201 0.0061805888 0.5809270000 0.0658260000 0.0599470000 0.0000000000 0.4471750000 0.0015670000 146330323 0 402718720 3.9124755859 3.9597783089 3.3008995056 2749 1311867262.1539878845 0.1569345742 0.0951806050 0.1616480201 0.0061812021 1.0903680000 0.0531900000 0.0466290000 0.0338400000 0.4427630000 0.5075010000 146334107 0 402718720 3.9141719341 3.9603996277 3.2978048325 2750 1311867262.1906540394 0.1576646119 0.0952033264 0.1616480201 0.0061802657 0.5666850000 0.0514550000 0.0591360000 0.0000000000 0.4481170000 0.0015690000 146337835 0 402718720 3.9139170647 3.9608430862 3.2942795753 2751 1311867262.2200620174 0.1610362828 0.0952272570 0.1616480201 0.0061800238 0.5924090000 0.0529130000 0.0493540000 0.0338210000 0.4483730000 0.0015740000 146341507 0 402718720 3.9098415375 3.9608302116 3.2907373905 2752 1311867262.2557590008 0.1582971662 0.0952501748 0.1616480201 0.0061792959 0.5978960000 0.0767080000 0.0687990000 0.0000010000 0.4439610000 0.0016690000 146345235 0 402718720 3.9141416550 3.9623727798 3.2877449989 2753 1311867262.2893559933 0.1618658006 0.0952743723 0.1618658006 0.0061811961 1.1005840000 0.0525440000 0.0462840000 0.0335210000 0.4497020000 0.5120450000 146348963 0 402718720 3.9103105068 3.9643085003 3.2840204239 2754 1311867262.3192830086 0.1643973589 0.0952994714 0.1643973589 0.0061802344 0.5750760000 0.0526710000 0.0684540000 0.0000010000 0.4459620000 0.0015740000 146352635 0 402718720 3.9068622589 3.9658651352 3.2794234753 2755 1311867262.3543510437 0.1650929004 0.0953248048 0.1650929004 0.0061833103 0.6096210000 0.0525880000 0.0685040000 0.0339920000 0.4464570000 0.0015770000 146356363 0 402718720 3.9067895412 3.9675390720 3.2750704288 2756 1311867262.3862760067 0.1662307531 0.0953505326 0.1662307531 0.0061822700 0.5767240000 0.0520290000 0.0644640000 0.0000010000 0.4522320000 0.0015690000 146359979 0 402718720 3.9057474136 3.9699354172 3.2710423470 2757 1311867262.4192481041 0.1705567390 0.0953778109 0.1705567390 0.0061814342 1.0990790000 0.0524920000 0.0404890000 0.0339920000 0.4481200000 0.5174760000 146363707 0 402718720 3.9003884792 3.9715118408 3.2657756805 2758 1311867262.4579370022 0.1713050157 0.0954053407 0.1713050157 0.0061806164 0.5824350000 0.0807100000 0.0403370000 0.0000010000 0.4534030000 0.0015590000 146367547 0 402718720 3.9004311562 3.9726824760 3.2614810467 2759 1311867262.4882910252 0.1735964417 0.0954336811 0.1735964417 0.0061830523 0.5908140000 0.0516320000 0.0431950000 0.0335930000 0.4543650000 0.0015590000 146371219 0 402718720 3.8972115517 3.9754436016 3.2562153339 2760 1311867262.5228719711 0.1767578870 0.0954631464 0.1767578870 0.0061825682 0.5884700000 0.0787560000 0.0461590000 0.0000000000 0.4555510000 0.0015730000 146374947 0 402718720 3.8937263489 3.9756724834 3.2516875267 2761 1311867262.5554070473 0.1790917963 0.0954934356 0.1790917963 0.0061830602 1.1196850000 0.0520630000 0.0432450000 0.0340330000 0.4574590000 0.5262970000 146378619 0 402718720 3.8915345669 3.9786932468 3.2471435070 2762 1311867262.5873200893 0.1788026094 0.0955235983 0.1790917963 0.0061919793 0.5618410000 0.0511140000 0.0494050000 0.0000000000 0.4530000000 0.0016550000 146382347 0 402718720 3.8920035362 3.9799332619 3.2430214882 2763 1311867262.6235508919 0.1802778840 0.0955542730 0.1802778840 0.0061944358 0.6373370000 0.0801400000 0.0616460000 0.0340380000 0.4534660000 0.0015630000 146386131 0 402718720 3.8901088238 3.9821376801 3.2388844490 2764 1311867262.6548008919 0.1791932583 0.0955845331 0.1802778840 0.0061942669 0.5825640000 0.0509510000 0.0673180000 0.0000010000 0.4563250000 0.0015670000 146389747 0 402718720 3.8912897110 3.9837107658 3.2353205681 2765 1311867262.6901140213 0.1822252423 0.0956158679 0.1822252423 0.0061952395 1.1253600000 0.0509790000 0.0380440000 0.0339770000 0.4595490000 0.5328050000 146393475 0 402718720 3.8877110481 3.9842989445 3.2315082550 2766 1311867262.7234799862 0.1785258353 0.0956458426 0.1822252423 0.0061943134 0.5573270000 0.0517390000 0.0382050000 0.0000010000 0.4593640000 0.0015710000 146397203 0 402718720 3.8921191692 3.9850463867 3.2278025150 2767 1311867262.7550880909 0.1770355999 0.0956752570 0.1822252423 0.0061998952 0.5904130000 0.0510910000 0.0376990000 0.0340280000 0.4595630000 0.0015570000 146400875 0 402718720 3.8937606812 3.9832167625 3.2249538898 2768 1311867262.7890789509 0.1791989505 0.0957054318 0.1822252423 0.0062009959 0.5996380000 0.0800770000 0.0563840000 0.0000010000 0.4548000000 0.0016530000 146404547 0 402718720 3.8920211792 3.9834918976 3.2210419178 2769 1311867262.8232269287 0.1787950546 0.0957354389 0.1822252423 0.0062006835 1.1264690000 0.0512620000 0.0344900000 0.0341850000 0.4561130000 0.5431730000 146408387 0 402718720 3.8948338032 3.9828412533 3.2188198566 2770 1311867262.8561139107 0.1822911948 0.0957666864 0.1822911948 0.0062008575 0.5986950000 0.0642480000 0.0491050000 0.0000010000 0.4761680000 0.0019990000 146412003 0 402718720 3.8909156322 3.9836342335 3.2157623768 2771 1311867262.8878281116 0.1820579171 0.0957978273 0.1822911948 0.0062003179 0.6055020000 0.0633700000 0.0374450000 0.0341660000 0.4624440000 0.0015580000 146415675 0 402718720 3.8924701214 3.9841022491 3.2128326893 2772 1311867262.9221930504 0.1852904260 0.0958301117 0.1852904260 0.0062009560 0.5722150000 0.0512550000 0.0377970000 0.0000010000 0.4739770000 0.0019910000 146419459 0 402718720 3.8903543949 3.9852128029 3.2108175755 2773 1311867262.9539968967 0.1869748533 0.0958629804 0.1869748533 0.0062013435 1.2070900000 0.0639130000 0.0621770000 0.0433090000 0.4776200000 0.5528770000 146423131 0 402718720 3.8905866146 3.9851188660 3.2088470459 2774 1311867262.9877319336 0.1880346239 0.0958962074 0.1880346239 0.0062019444 0.5885360000 0.0632390000 0.0484300000 0.0000010000 0.4688370000 0.0015570000 146426859 0 402718720 3.8893027306 3.9847056866 3.2064988613 2775 1311867263.0238440037 0.1902953088 0.0959302251 0.1902953088 0.0062009113 0.5958280000 0.0499220000 0.0390620000 0.0342360000 0.4645180000 0.0015470000 146430643 0 402718720 3.8877069950 3.9846477509 3.2040722370 2776 1311867263.0552799702 0.1915991753 0.0959646879 0.1915991753 0.0061999066 0.6087970000 0.0742220000 0.0658780000 0.0000010000 0.4606150000 0.0015450000 146434259 0 402718720 3.8868238926 3.9843084812 3.2020478249 2777 1311867263.0870039463 0.1935087740 0.0959998136 0.1935087740 0.0061988862 1.1651000000 0.0503290000 0.0622620000 0.0343390000 0.4667020000 0.5449620000 146437931 0 402718720 3.8850219250 3.9848921299 3.1995739937 2778 1311867263.1226899624 0.1951782405 0.0960355150 0.1951782405 0.0061980516 0.5722970000 0.0634190000 0.0386380000 0.0000010000 0.4621810000 0.0015370000 146441715 0 402718720 3.8831110001 3.9853310585 3.1970748901 2779 1311867263.1537079811 0.1941272467 0.0960708125 0.1951782405 0.0062015571 0.6171320000 0.0480490000 0.0639810000 0.0342100000 0.4625050000 0.0016220000 146445331 0 402718720 3.8839359283 3.9855444431 3.1940872669 2780 1311867263.1884229183 0.1940898597 0.0961060712 0.1951782405 0.0062008993 0.5742070000 0.0486510000 0.0485170000 0.0000010000 0.4689630000 0.0015360000 146449059 0 402718720 3.8840391636 3.9873752594 3.1919515133 2781 1311867263.2225809097 0.1914872825 0.0961403686 0.1951782405 0.0062002083 1.1403800000 0.0482710000 0.0432940000 0.0342830000 0.4632290000 0.5447440000 146452843 0 402718720 3.8867890835 3.9884605408 3.1894850731 2782 1311867263.2536139488 0.1893758774 0.0961738825 0.1951782405 0.0061999876 0.5822570000 0.0594430000 0.0455140000 0.0000000000 0.4692540000 0.0015290000 146456459 0 402718720 3.8888401985 3.9905011654 3.1865806580 2783 1311867263.2884469032 0.1917075962 0.0962082101 0.1951782405 0.0061997640 0.6350290000 0.0620680000 0.0603430000 0.0342420000 0.4696230000 0.0015290000 146460187 0 402718720 3.8856825829 3.9880266190 3.1845865250 2784 1311867263.3236269951 0.1915932000 0.0962424719 0.1951782405 0.0062179729 0.5642320000 0.0485720000 0.0429920000 0.0000010000 0.4642800000 0.0016220000 146463971 0 402718720 3.8860659599 3.9884588718 3.1828529835 2785 1311867263.3539469242 0.1889113635 0.0962757462 0.1951782405 0.0062187961 1.1718490000 0.0486740000 0.0635880000 0.0344310000 0.4651770000 0.5534440000 146467587 0 402718720 3.8883981705 3.9866905212 3.1803007126 2786 1311867263.3856530190 0.1908378303 0.0963096881 0.1951782405 0.0062178708 0.5774490000 0.0608220000 0.0428310000 0.0000010000 0.4657140000 0.0015200000 146471259 0 402718720 3.8862886429 3.9872226715 3.1779186726 2787 1311867263.4221460819 0.1926586032 0.0963442589 0.1951782405 0.0062168863 0.6025430000 0.0473410000 0.0407840000 0.0343930000 0.4719870000 0.0015100000 146475043 0 402718720 3.8848905563 3.9882309437 3.1755962372 2788 1311867263.4549560547 0.1946082562 0.0963795043 0.1951782405 0.0062162909 0.5774410000 0.0616970000 0.0351300000 0.0000010000 0.4725490000 0.0015120000 146478659 0 402718720 3.8836455345 3.9884409904 3.1734323502 2789 1311867263.4876389503 0.1936296970 0.0964143735 0.1951782405 0.0062161512 1.1432250000 0.0471090000 0.0372410000 0.0341080000 0.4670430000 0.5509320000 146482443 0 402718720 3.8852248192 3.9863331318 3.1710169315 2790 1311867263.5235950947 0.1926468164 0.0964488654 0.1951782405 0.0062202842 0.5756920000 0.0470360000 0.0472530000 0.0000010000 0.4733780000 0.0015100000 146486283 0 402718720 3.8871085644 3.9880170822 3.1676666737 2791 1311867263.5535099506 0.1963633597 0.0964846642 0.1963633597 0.0062214453 0.6216960000 0.0467900000 0.0589510000 0.0344160000 0.4735220000 0.0015080000 146489843 0 402718720 3.8842005730 3.9870455265 3.1651766300 2792 1311867263.5855040550 0.1943104267 0.0965197021 0.1963633597 0.0062211735 0.5960720000 0.0698330000 0.0445440000 0.0000010000 0.4736480000 0.0015090000 146493459 0 402718720 3.8881294727 3.9885585308 3.1625516415 2793 1311867263.6236140728 0.1958824843 0.0965552777 0.1963633597 0.0062234126 1.1552330000 0.0473650000 0.0368790000 0.0341020000 0.4693580000 0.5609130000 146497355 0 402718720 3.8884820938 3.9890213013 3.1590600014 2794 1311867263.6543920040 0.1958198398 0.0965908055 0.1963633597 0.0062231296 0.5860620000 0.0472670000 0.0620800000 0.0000000000 0.4682170000 0.0016090000 146500915 0 402718720 3.8903014660 3.9885432720 3.1569292545 2795 1311867263.6903779507 0.1976772249 0.0966269723 0.1976772249 0.0062222472 0.6007890000 0.0469890000 0.0368770000 0.0344310000 0.4744430000 0.0015070000 146504755 0 402718720 3.8899016380 3.9897136688 3.1533062458 2796 1311867263.7227630615 0.1957354099 0.0966624189 0.1976772249 0.0062231114 0.5873750000 0.0464090000 0.0616460000 0.0000010000 0.4713250000 0.0015080000 146508427 0 402718720 3.8933348656 3.9905529022 3.1496307850 2797 1311867263.7559669018 0.1987442821 0.0966989158 0.1987442821 0.0062225988 1.1851060000 0.0463440000 0.0573980000 0.0344620000 0.4760010000 0.5642670000 146512099 0 402718720 3.8908038139 3.9904100895 3.1461451054 2798 1311867263.7911560535 0.1945144534 0.0967338749 0.1987442821 0.0062230335 0.5983140000 0.0568770000 0.0623500000 0.0000010000 0.4710540000 0.0015060000 146515827 0 402718720 3.8977825642 3.9923925400 3.1428973675 2799 1311867263.8235189915 0.1948583424 0.0967689318 0.1987442821 0.0062220548 0.6100330000 0.0463770000 0.0442880000 0.0344650000 0.4768360000 0.0015030000 146519555 0 402718720 3.8983149529 3.9915542603 3.1392619610 2800 1311867263.8555519581 0.1934381574 0.0968034566 0.1987442821 0.0062215604 0.5945420000 0.0675090000 0.0469270000 0.0000010000 0.4720710000 0.0015120000 146523171 0 402718720 3.9017438889 3.9932372570 3.1363217831 2801 1311867263.8925390244 0.1959924549 0.0968388686 0.1987442821 0.0062205102 1.1638150000 0.0463510000 0.0367710000 0.0342640000 0.4728200000 0.5670380000 146527011 0 402718720 3.8999924660 3.9921214581 3.1328029633 2802 1311867263.9255890846 0.1965644956 0.0968744594 0.1987442821 0.0062194469 0.5835340000 0.0456540000 0.0561950000 0.0000010000 0.4733210000 0.0015790000 146530683 0 402718720 3.9011523724 3.9936475754 3.1305263042 2803 1311867263.9557209015 0.1984343380 0.0969106920 0.1987442821 0.0062186564 0.6503460000 0.0702770000 0.0595430000 0.0341770000 0.4782380000 0.0015090000 146534299 0 402718720 3.9004347324 3.9943535328 3.1281592846 2804 1311867263.9913449287 0.1968959272 0.0969463501 0.1987442821 0.0062179791 0.5691200000 0.0469220000 0.0369430000 0.0000010000 0.4772000000 0.0015160000 146538083 0 402718720 3.9034690857 3.9966511726 3.1247055531 2805 1311867264.0265080929 0.1971946657 0.0969820892 0.1987442821 0.0062171140 1.1791460000 0.0458940000 0.0443030000 0.0345000000 0.4787050000 0.5691420000 146541867 0 402718720 3.9045917988 3.9951684475 3.1227271557 2806 1311867264.0539839268 0.1992349476 0.0970185300 0.1992349476 0.0062168964 0.5643660000 0.0461190000 0.0367930000 0.0000000000 0.4734210000 0.0015090000 146545427 0 402718720 3.9032580853 3.9954140186 3.1209337711 2807 1311867264.0935840607 0.2030706406 0.0970563113 0.2030706406 0.0062162534 0.6130760000 0.0468740000 0.0448040000 0.0345680000 0.4787930000 0.0015120000 146549323 0 402718720 3.9008405209 3.9974770546 3.1189157963 2808 1311867264.1232929230 0.2019080669 0.0970936517 0.2030706406 0.0062156201 0.6042170000 0.0755990000 0.0471470000 0.0000000000 0.4734080000 0.0015160000 146552939 0 402718720 3.9029648304 3.9967358112 3.1167969704 2809 1311867264.1547811031 0.2006012946 0.0971305002 0.2030706406 0.0062160698 1.1800040000 0.0469820000 0.0372040000 0.0346850000 0.4745930000 0.5792640000 146556499 0 402718720 3.9048745632 3.9971292019 3.1145882607 2810 1311867264.1908740997 0.1990048289 0.0971667545 0.2030706406 0.0062163186 0.6400700000 0.0599790000 0.0774800000 0.0000010000 0.4934540000 0.0019180000 146560283 0 402718720 3.9082200527 3.9988243580 3.1118996143 2811 1311867264.2230439186 0.1989580095 0.0972029662 0.2030706406 0.0062173716 0.6786030000 0.0599940000 0.0710300000 0.0446650000 0.4937320000 0.0019210000 146564011 0 402718720 3.9085228443 3.9981429577 3.1094410419 2812 1311867264.2549281120 0.1998942345 0.0972394852 0.2030706406 0.0062191685 0.5908290000 0.0578190000 0.0449250000 0.0000000000 0.4799450000 0.0015170000 146567627 0 402718720 3.9085116386 3.9990730286 3.1069409847 2813 1311867264.2910940647 0.1983365119 0.0972754244 0.2030706406 0.0062242861 1.1889930000 0.0686320000 0.0369240000 0.0344070000 0.4745200000 0.5678120000 146571411 0 402718720 3.9112854004 3.9994149208 3.1040675640 2814 1311867264.3223540783 0.1997335702 0.0973118345 0.2030706406 0.0062277275 0.5792560000 0.0465050000 0.0350910000 0.0000010000 0.4885130000 0.0019040000 146575083 0 402718720 3.9106183052 3.9987843037 3.1013724804 2815 1311867264.3539710045 0.1987656653 0.0973478750 0.2030706406 0.0062332271 0.6541520000 0.0593120000 0.0458980000 0.0442570000 0.4954600000 0.0019160000 146578699 0 402718720 3.9114897251 3.9987101555 3.0990033150 2816 1311867264.3903570175 0.1950635463 0.0973825751 0.2030706406 0.0062351931 0.6408130000 0.0591550000 0.0768490000 0.0000010000 0.4955960000 0.0019200000 146582483 0 402718720 3.9167098999 3.9997107983 3.0964126587 2817 1311867264.4247128963 0.1943695545 0.0974170043 0.2030706406 0.0062391340 1.2459930000 0.0583570000 0.0763170000 0.0446910000 0.4855170000 0.5743990000 146586267 0 402718720 3.9166605473 3.9984381199 3.0933763981 2818 1311867264.4536709785 0.1912200898 0.0974502914 0.2030706406 0.0062408571 0.5786770000 0.0463500000 0.0470330000 0.0000010000 0.4772150000 0.0014850000 146589827 0 402718720 3.9198205471 3.9979410172 3.0911114216 2819 1311867264.4911220074 0.1896826476 0.0974830095 0.2030706406 0.0062401933 0.6309070000 0.0591710000 0.0518840000 0.0347940000 0.4769200000 0.0015070000 146593667 0 402718720 3.9218051434 4.0008730888 3.0888595581 2820 1311867264.5220930576 0.1874185801 0.0975149016 0.2030706406 0.0062405504 0.5707120000 0.0455720000 0.0346100000 0.0000010000 0.4823970000 0.0014990000 146597283 0 402718720 3.9239306450 3.9994750023 3.0862560272 2821 1311867264.5544660091 0.1857209057 0.0975461692 0.2030706406 0.0062413063 1.1955730000 0.0459790000 0.0488090000 0.0348670000 0.4823310000 0.5769030000 146600955 0 402718720 3.9266233444 3.9999241829 3.0849261284 2822 1311867264.5919189453 0.1816388965 0.0975759682 0.2030706406 0.0062416819 0.5909680000 0.0456910000 0.0455660000 0.0000010000 0.4895880000 0.0018820000 146604795 0 402718720 3.9314818382 3.9988996983 3.0825817585 2823 1311867264.6239540577 0.1814272702 0.0976056711 0.2030706406 0.0062422944 0.6525290000 0.0573910000 0.0447010000 0.0444040000 0.4968790000 0.0018750000 146608467 0 402718720 3.9320213795 3.9993548393 3.0809440613 2824 1311867264.6537890434 0.1802537590 0.0976349374 0.2030706406 0.0062419511 0.5984550000 0.0574760000 0.0497620000 0.0000010000 0.4830360000 0.0014910000 146612139 0 402718720 3.9328846931 3.9975900650 3.0788083076 2825 1311867264.6908979416 0.1777276099 0.0976632888 0.2030706406 0.0062417811 1.2074800000 0.0452690000 0.0481680000 0.0345190000 0.4890380000 0.5837680000 146615867 0 402718720 3.9362251759 3.9989309311 3.0768685341 2826 1311867264.7228040695 0.1769023389 0.0976913281 0.2030706406 0.0062419538 0.5917060000 0.0448840000 0.0603410000 0.0000010000 0.4780530000 0.0015850000 146619595 0 402718720 3.9371590614 3.9982240200 3.0753896236 2827 1311867264.7547140121 0.1738061011 0.0977182523 0.2030706406 0.0062410025 0.6118790000 0.0445510000 0.0454170000 0.0345430000 0.4792340000 0.0014780000 146623211 0 402718720 3.9408597946 3.9964191914 3.0736908913 2828 1311867264.7909140587 0.1750099510 0.0977455832 0.2030706406 0.0062408801 0.6153390000 0.0650200000 0.0565430000 0.0000010000 0.4857270000 0.0014580000 146626995 0 402718720 3.9402883053 3.9983549118 3.0725231171 2829 1311867264.8233439922 0.1740159243 0.0977725434 0.2030706406 0.0062402989 1.1838110000 0.0449670000 0.0292560000 0.0349400000 0.4846160000 0.5833280000 146630723 0 402718720 3.9415998459 3.9995660782 3.0707347393 2830 1311867264.8540790081 0.1736614853 0.0977993592 0.2030706406 0.0062395308 0.6080740000 0.0577380000 0.0602020000 0.0000010000 0.4820200000 0.0014680000 146634339 0 402718720 3.9423277378 4.0019392967 3.0689251423 2831 1311867264.8904409409 0.1761478633 0.0978270345 0.2030706406 0.0062385412 0.6270890000 0.0643490000 0.0402880000 0.0350160000 0.4789520000 0.0015800000 146638123 0 402718720 3.9395585060 4.0016551018 3.0674579144 2832 1311867264.9235579967 0.1740179807 0.0978539380 0.2030706406 0.0062375326 0.5717550000 0.0440140000 0.0402060000 0.0000010000 0.4794230000 0.0014840000 146641851 0 402718720 3.9426841736 4.0016736984 3.0666153431 2833 1311867264.9598839283 0.1745655388 0.0978810159 0.2030706406 0.0062368062 1.2093250000 0.0589550000 0.0406510000 0.0349840000 0.4848080000 0.5832520000 146645635 0 402718720 3.9420957565 3.9998149872 3.0652577877 2834 1311867264.9916839600 0.1771918833 0.0979090014 0.2030706406 0.0062362214 0.5761680000 0.0448530000 0.0383680000 0.0000010000 0.4848760000 0.0014880000 146649307 0 402718720 3.9404768944 4.0027971268 3.0649428368 2835 1311867265.0220029354 0.1776630431 0.0979371333 0.2030706406 0.0062351694 0.6075870000 0.0441750000 0.0336620000 0.0345570000 0.4860170000 0.0018640000 146652923 0 402718720 3.9397988319 4.0004796982 3.0639457703 2836 1311867265.0581490993 0.1805413663 0.0979662603 0.2030706406 0.0062343699 0.6083630000 0.0559860000 0.0438590000 0.0000010000 0.4993610000 0.0018730000 146656707 0 402718720 3.9370949268 4.0011291504 3.0633659363 2837 1311867265.0911719799 0.1780568808 0.0979944911 0.2030706406 0.0062336788 1.2506240000 0.0563140000 0.0495490000 0.0446820000 0.4995590000 0.5938190000 146660323 0 402718720 3.9401652813 4.0015878677 3.0619964600 2838 1311867265.1217110157 0.1826895028 0.0980243343 0.2030706406 0.0062350238 0.6081810000 0.0742390000 0.0453850000 0.0000010000 0.4804120000 0.0014900000 146663939 0 402718720 3.9356977940 4.0031690598 3.0610208511 2839 1311867265.1582090855 0.1814586371 0.0980537229 0.2030706406 0.0062340133 0.6212520000 0.0623690000 0.0356460000 0.0346350000 0.4804750000 0.0014890000 146667723 0 402718720 3.9373421669 4.0011167526 3.0595710278 2840 1311867265.1899518967 0.1814056933 0.0980830722 0.2030706406 0.0062341019 0.5936900000 0.0446600000 0.0601090000 0.0000000000 0.4808220000 0.0014860000 146671339 0 402718720 3.9372925758 4.0030512810 3.0577340126 2841 1311867265.2225220203 0.1883877218 0.0981148584 0.2030706406 0.0062351330 1.2171100000 0.0442220000 0.0572440000 0.0349370000 0.4866830000 0.5873060000 146675067 0 402718720 3.9294643402 4.0019311905 3.0567889214 2842 1311867265.2581849098 0.1905825436 0.0981473946 0.2030706406 0.0062371010 0.5941270000 0.0441490000 0.0597180000 0.0000000000 0.4821120000 0.0014760000 146678739 0 402718720 3.9276983738 4.0011930466 3.0547838211 2843 1311867265.2915129662 0.1936760396 0.0981809959 0.2030706406 0.0062375371 0.6437610000 0.0563530000 0.0558230000 0.0348390000 0.4881760000 0.0014680000 146682467 0 402718720 3.9254012108 4.0017724037 3.0532310009 2844 1311867265.3220860958 0.1983932704 0.0982162323 0.2030706406 0.0062371011 0.6018970000 0.0518200000 0.0586040000 0.0000010000 0.4828690000 0.0015670000 146686139 0 402718720 3.9199013710 4.0024986267 3.0516226292 2845 1311867265.3585588932 0.1991735250 0.0982517182 0.2030706406 0.0062360252 1.2021970000 0.0439580000 0.0303900000 0.0349760000 0.4906360000 0.5955550000 146689923 0 402718720 3.9195239544 4.0017514229 3.0501203537 2846 1311867265.3912470341 0.2017746270 0.0982880930 0.2030706406 0.0062354819 0.5965830000 0.0434220000 0.0551750000 0.0000010000 0.4898030000 0.0014700000 146693595 0 402718720 3.9171514511 4.0036454201 3.0485558510 2847 1311867265.4244530201 0.2039999068 0.0983252240 0.2039999068 0.0062346617 0.6271860000 0.0433880000 0.0508940000 0.0345740000 0.4901690000 0.0014730000 146697379 0 402718720 3.9146494865 4.0036606789 3.0464851856 2848 1311867265.4604411125 0.2058632523 0.0983629831 0.2058632523 0.0062337982 0.5930530000 0.0433650000 0.0508820000 0.0000010000 0.4906340000 0.0014680000 146701051 0 402718720 3.9127981663 4.0039367676 3.0445113182 2849 1311867265.4902420044 0.2015198618 0.0983991912 0.2058632523 0.0062328643 1.2422760000 0.0550140000 0.0549560000 0.0350280000 0.4908120000 0.5997010000 146704723 0 402718720 3.9177160263 4.0054860115 3.0422656536 2850 1311867265.5230569839 0.2034152895 0.0984360390 0.2058632523 0.0062322582 0.5971980000 0.0431990000 0.0547930000 0.0000010000 0.4910700000 0.0014730000 146708451 0 402718720 3.9154305458 4.0048317909 3.0405240059 2851 1311867265.5594520569 0.2075556070 0.0984743131 0.2075556070 0.0062315855 0.6318300000 0.0539400000 0.0443940000 0.0351340000 0.4902020000 0.0014770000 146712179 0 402718720 3.9111547470 4.0063791275 3.0386426449 2852 1311867265.5932300091 0.2039709985 0.0985113035 0.2075556070 0.0062315158 0.5767860000 0.0431340000 0.0392730000 0.0000010000 0.4858510000 0.0015720000 146715963 0 402718720 3.9152472019 4.0058040619 3.0365169048 2853 1311867265.6250700951 0.2089227736 0.0985500037 0.2089227736 0.0062311622 1.2538650000 0.0651140000 0.0572130000 0.0350750000 0.4864770000 0.6032220000 146719523 0 402718720 3.9099621773 4.0063900948 3.0349433422 2854 1311867265.6610729694 0.2105165422 0.0985892351 0.2105165422 0.0062303436 0.5953460000 0.0659020000 0.0340150000 0.0000000000 0.4868840000 0.0015540000 146723307 0 402718720 3.9081494808 4.0053830147 3.0326728821 2855 1311867265.6956009865 0.2093774229 0.0986280401 0.2105165422 0.0062292949 0.6213610000 0.0420510000 0.0429830000 0.0349950000 0.4931140000 0.0014650000 146727035 0 402718720 3.9103386402 4.0082330704 3.0316510201 2856 1311867265.7221889496 0.2106332481 0.0986672576 0.2106332481 0.0062283364 0.5955960000 0.0420920000 0.0432800000 0.0000010000 0.5010500000 0.0018210000 146730595 0 402718720 3.9088344574 4.0104761124 3.0295376778 2857 1311867265.7626268864 0.2062500864 0.0987049135 0.2106332481 0.0062287667 1.3052430000 0.0527210000 0.0697730000 0.0447960000 0.5078890000 0.6225520000 146734491 0 402718720 3.9137763977 4.0097150803 3.0287022591 2858 1311867265.7925920486 0.2066233009 0.0987426736 0.2106332481 0.0062281520 0.6069890000 0.0533420000 0.0479610000 0.0000010000 0.4974900000 0.0014750000 146738107 0 402718720 3.9132916927 4.0111117363 3.0273911953 2859 1311867265.8224210739 0.2078574747 0.0987808389 0.2106332481 0.0062272492 0.6167540000 0.0423470000 0.0376730000 0.0350460000 0.4935120000 0.0014750000 146741723 0 402718720 3.9120864868 4.0129122734 3.0262532234 2860 1311867265.8593389988 0.2065433711 0.0988185182 0.2106332481 0.0062263987 0.5690770000 0.0424740000 0.0297460000 0.0000000000 0.4887120000 0.0014500000 146745507 0 402718720 3.9137210846 4.0118632317 3.0259709358 2861 1311867265.8943600655 0.2098364085 0.0988573220 0.2106332481 0.0062256533 1.2394190000 0.0433530000 0.0443490000 0.0348120000 0.4916860000 0.6177210000 146749235 0 402718720 3.9100012779 4.0137939453 3.0244150162 2862 1311867265.9256451130 0.2074684948 0.0988952714 0.2106332481 0.0062249158 0.6074020000 0.0537250000 0.0365730000 0.0000010000 0.5078750000 0.0018310000 146752907 0 402718720 3.9130911827 4.0132870674 3.0241069794 2863 1311867265.9620978832 0.2089230865 0.0989337024 0.2106332481 0.0062241004 0.6815560000 0.0540350000 0.0713090000 0.0448190000 0.5032160000 0.0014700000 146756691 0 402718720 3.9114303589 4.0119390488 3.0230889320 2864 1311867265.9908990860 0.2101897001 0.0989725487 0.2106332481 0.0062245747 0.5991730000 0.0421690000 0.0547130000 0.0000010000 0.4941020000 0.0014700000 146760251 0 402718720 3.9100012779 4.0125722885 3.0210871696 2865 1311867266.0233469009 0.2086045593 0.0990108147 0.2106332481 0.0062235094 1.2385830000 0.0425140000 0.0545340000 0.0349820000 0.4940910000 0.6057020000 146763979 0 402718720 3.9123392105 4.0117092133 3.0209422112 2866 1311867266.0634260178 0.2141960561 0.0990510050 0.2141960561 0.0062227101 0.5777300000 0.0424440000 0.0325830000 0.0000010000 0.4945090000 0.0014640000 146767875 0 402718720 3.9057989120 4.0117182732 3.0188548565 2867 1311867266.0954639912 0.2132962644 0.0990908533 0.2141960561 0.0062217181 0.6342110000 0.0426550000 0.0536950000 0.0350690000 0.4945960000 0.0014700000 146771491 0 402718720 3.9068424702 4.0128674507 3.0174155235 2868 1311867266.1241600513 0.2122991681 0.0991303262 0.2141960561 0.0062209288 0.6129340000 0.0549710000 0.0548900000 0.0000010000 0.4948580000 0.0014640000 146775107 0 402718720 3.9079787731 4.0119848251 3.0162055492 2869 1311867266.1634809971 0.2082803249 0.0991683709 0.2141960561 0.0062213415 1.2250500000 0.0421200000 0.0387430000 0.0351140000 0.4938640000 0.6084510000 146779003 0 402718720 3.9126765728 4.0123968124 3.0153110027 2870 1311867266.1922690868 0.2095052153 0.0992068157 0.2141960561 0.0062204151 0.6264070000 0.0692010000 0.0540410000 0.0000000000 0.4949390000 0.0014520000 146782563 0 402718720 3.9111475945 4.0136928558 3.0145378113 2871 1311867266.2255198956 0.2093750238 0.0992451885 0.2141960561 0.0062196355 0.6147040000 0.0418530000 0.0389520000 0.0350420000 0.4906670000 0.0014550000 146786291 0 402718720 3.9105782509 4.0142078400 3.0127003193 2872 1311867266.2597849369 0.2084780037 0.0992832222 0.2141960561 0.0062185704 0.5777730000 0.0420240000 0.0322540000 0.0000000000 0.4953060000 0.0014560000 146789963 0 402718720 3.9116954803 4.0140323639 3.0119554996 2873 1311867266.2915120125 0.2099675089 0.0993217479 0.2141960561 0.0062176707 1.2437320000 0.0415130000 0.0541320000 0.0346800000 0.4955110000 0.6111020000 146793635 0 402718720 3.9092175961 4.0111036301 3.0108265877 2874 1311867266.3258039951 0.2137553543 0.0993615647 0.2141960561 0.0062171047 0.5947050000 0.0413080000 0.0491930000 0.0000010000 0.4959970000 0.0014500000 146797307 0 402718720 3.9048264027 4.0140595436 3.0089161396 2875 1311867266.3601551056 0.2114089876 0.0994005378 0.2141960561 0.0062166697 0.6509620000 0.0668410000 0.0447590000 0.0350570000 0.4960470000 0.0014490000 146801035 0 402718720 3.9071531296 4.0142703056 3.0071351528 2876 1311867266.3913159370 0.2123604417 0.0994398145 0.2141960561 0.0062156584 0.5878470000 0.0424140000 0.0408640000 0.0000000000 0.4963570000 0.0014490000 146804707 0 402718720 3.9057161808 4.0136489868 3.0056850910 2877 1311867266.4254870415 0.2134847343 0.0994794547 0.2141960561 0.0062159728 1.2232120000 0.0411430000 0.0274210000 0.0348970000 0.4969910000 0.6159430000 146808435 0 402718720 3.9040873051 4.0124011040 3.0048732758 2878 1311867266.4612910748 0.2112952620 0.0995183066 0.2141960561 0.0062153281 0.5868460000 0.0542470000 0.0276070000 0.0000010000 0.4967950000 0.0014460000 146812219 0 402718720 3.9060544968 4.0116009712 3.0032982826 2879 1311867266.4912600517 0.2122441083 0.0995574611 0.2141960561 0.0062144397 0.6352190000 0.0414900000 0.0531520000 0.0352840000 0.4971040000 0.0014420000 146815779 0 402718720 3.9046289921 4.0116343498 3.0018835068 2880 1311867266.5284929276 0.2100488842 0.0995958262 0.2141960561 0.0062138108 0.6036100000 0.0623120000 0.0359420000 0.0000010000 0.4971710000 0.0014310000 146819675 0 402718720 3.9062428474 4.0105628967 2.9994425774 2881 1311867266.5587360859 0.2091983706 0.0996338694 0.2141960561 0.0062140333 1.2525100000 0.0409680000 0.0514250000 0.0348960000 0.4967840000 0.6216190000 146823235 0 402718720 3.9069418907 4.0127201080 2.9974231720 2882 1311867266.5906820297 0.2096291035 0.0996720357 0.2141960561 0.0062129880 0.5681190000 0.0399890000 0.0283530000 0.0000010000 0.4911290000 0.0015250000 146826907 0 402718720 3.9060401917 4.0116667747 2.9961276054 2883 1311867266.6256470680 0.2115304917 0.0997108351 0.2141960561 0.0062131303 0.6038010000 0.0401990000 0.0227520000 0.0351470000 0.4974990000 0.0014290000 146830635 0 402718720 3.9030563831 4.0100154877 2.9937100410 2884 1311867266.6596419811 0.2089444697 0.0997487108 0.2141960561 0.0062123739 0.5843670000 0.0395600000 0.0390480000 0.0000010000 0.4976000000 0.0014270000 146834363 0 402718720 3.9060866833 4.0097446442 2.9937140942 2885 1311867266.6914939880 0.2136720121 0.0997881989 0.2141960561 0.0062120349 1.2733550000 0.0672140000 0.0414680000 0.0352010000 0.4976470000 0.6250350000 146838035 0 402718720 3.9008498192 4.0124607086 2.9933037758 2886 1311867266.7260789871 0.2143849134 0.0998279067 0.2143849134 0.0062111149 0.5946710000 0.0395620000 0.0549160000 0.0000000000 0.4920110000 0.0014250000 146841763 0 402718720 3.8992910385 4.0094623566 2.9922516346 2887 1311867266.7576239109 0.2163588256 0.0998682708 0.2163588256 0.0062103856 0.6441460000 0.0388660000 0.0510700000 0.0351080000 0.5099030000 0.0017620000 146845491 0 402718720 3.8973126411 4.0130395889 2.9913578033 2888 1311867266.7898240089 0.2142207921 0.0999078665 0.2163588256 0.0062100802 0.6361390000 0.0488630000 0.0655270000 0.0000010000 0.5125050000 0.0017540000 146849163 0 402718720 3.8993096352 4.0119805336 2.9912626743 2889 1311867266.8257129192 0.2112324089 0.0999464004 0.2163588256 0.0062093327 1.3065570000 0.0494540000 0.0660100000 0.0455850000 0.5115360000 0.6270860000 146852947 0 402718720 3.9024407864 4.0109229088 2.9914016724 2890 1311867266.8575000763 0.2164787799 0.0999867231 0.2164787799 0.0062087238 0.6065960000 0.0529360000 0.0530180000 0.0000010000 0.4921220000 0.0015160000 146856619 0 402718720 3.8968627453 4.0121054649 2.9922549725 2891 1311867266.8898739815 0.2172944695 0.1000272999 0.2172944695 0.0062082894 0.6021630000 0.0394180000 0.0270590000 0.0352610000 0.4917140000 0.0015260000 146860291 0 402718720 3.8955745697 4.0107822418 2.9931790829 2892 1311867266.9266190529 0.2139473408 0.1000666914 0.2172944695 0.0062079821 0.5988540000 0.0394690000 0.0534020000 0.0000010000 0.4977750000 0.0014210000 146864075 0 402718720 3.8989188671 4.0118646622 2.9934902191 2893 1311867266.9576549530 0.2145772576 0.1001062733 0.2172944695 0.0062070614 1.2721710000 0.0604130000 0.0548020000 0.0348600000 0.4916700000 0.6235140000 146867747 0 402718720 3.8985543251 4.0117177963 2.9959833622 2894 1311867266.9920771122 0.2161559016 0.1001463734 0.2172944695 0.0062091431 0.5831860000 0.0411490000 0.0359940000 0.0000000000 0.4977910000 0.0014370000 146871475 0 402718720 3.8967378139 4.0139665604 2.9972183704 2895 1311867267.0259480476 0.2138079405 0.1001856347 0.2172944695 0.0062096271 0.6307520000 0.0574720000 0.0380530000 0.0350670000 0.4914650000 0.0015310000 146875147 0 402718720 3.8988420963 4.0130257607 2.9989569187 2896 1311867267.0603609085 0.2146397084 0.1002251562 0.2172944695 0.0062096720 0.5814390000 0.0417170000 0.0386330000 0.0000010000 0.4928510000 0.0014480000 146878819 0 402718720 3.8978266716 4.0133681297 3.0006847382 2897 1311867267.0929799080 0.2170427889 0.1002654798 0.2172944695 0.0062087038 1.2649030000 0.0414530000 0.0508750000 0.0352070000 0.4971370000 0.6326720000 146882379 0 402718720 3.8945720196 4.0124096870 3.0011668205 2898 1311867267.1266899109 0.2176659852 0.1003059907 0.2176659852 0.0062116679 0.6070710000 0.0520890000 0.0343510000 0.0000010000 0.5113360000 0.0018000000 146886051 0 402718720 3.8937859535 4.0130085945 3.0025153160 2899 1311867267.1586909294 0.2178676277 0.1003465432 0.2178676277 0.0062110370 0.6514520000 0.0526740000 0.0401330000 0.0450770000 0.5052760000 0.0014640000 146889779 0 402718720 3.8934462070 4.0145626068 3.0032801628 2900 1311867267.1916129589 0.2142721564 0.1003858279 0.2178676277 0.0062114671 0.5913000000 0.0541830000 0.0320030000 0.0000010000 0.4968290000 0.0014440000 146893451 0 402718720 3.8962175846 4.0101552010 3.0036621094 2901 1311867267.2262039185 0.2146234363 0.1004252066 0.2178676277 0.0062106357 1.2180260000 0.0416100000 0.0232840000 0.0351500000 0.4967880000 0.6142680000 146897123 0 402718720 3.8954751492 4.0100502968 3.0043885708 2902 1311867267.2587449551 0.2150862664 0.1004647176 0.2178676277 0.0062099176 0.5820790000 0.0417880000 0.0354430000 0.0000010000 0.4965490000 0.0014530000 146900795 0 402718720 3.8945434093 4.0112037659 3.0047416687 2903 1311867267.2920761108 0.2183247358 0.1005053170 0.2183247358 0.0062096325 0.6351880000 0.0419300000 0.0535730000 0.0351220000 0.4963140000 0.0014520000 146904523 0 402718720 3.8906505108 4.0121607780 3.0053317547 2904 1311867267.3265810013 0.2174441218 0.1005455852 0.2183247358 0.0062087440 0.6004920000 0.0418910000 0.0540850000 0.0000000000 0.4962800000 0.0014550000 146908307 0 402718720 3.8910415173 4.0102806091 3.0063469410 2905 1311867267.3609950542 0.2164108008 0.1005854700 0.2183247358 0.0062082581 1.2564660000 0.0519710000 0.0552170000 0.0352470000 0.4956990000 0.6114930000 146911979 0 402718720 3.8923254013 4.0107584000 3.0081143379 2906 1311867267.3945980072 0.2148892134 0.1006248037 0.2183247358 0.0062074986 0.5996890000 0.0418450000 0.0537680000 0.0000000000 0.4957990000 0.0014540000 146915651 0 402718720 3.8934636116 4.0096979141 3.0086114407 2907 1311867267.4286189079 0.2204431146 0.1006660208 0.2204431146 0.0062076213 0.6289450000 0.0553140000 0.0392850000 0.0352330000 0.4908110000 0.0014680000 146919435 0 402718720 3.8870141506 4.0090103149 3.0091850758 2908 1311867267.4595789909 0.2189599425 0.1007066996 0.2204431146 0.0062068304 0.5759680000 0.0429550000 0.0346050000 0.0000010000 0.4897170000 0.0015660000 146923051 0 402718720 3.8888361454 4.0101881027 3.0098423958 2909 1311867267.4935429096 0.2164899409 0.1007465013 0.2204431146 0.0062061468 1.2199060000 0.0422360000 0.0436340000 0.0352090000 0.4895880000 0.6023190000 146926779 0 402718720 3.8915317059 4.0107984543 3.0109009743 2910 1311867267.5264101028 0.2178201675 0.1007867328 0.2204431146 0.0062059569 0.6004790000 0.0545750000 0.0421640000 0.0000010000 0.4954280000 0.0014610000 146930451 0 402718720 3.8903543949 4.0128469467 3.0117394924 2911 1311867267.5577969551 0.2221582383 0.1008284269 0.2221582383 0.0062098365 0.6170470000 0.0437060000 0.0401120000 0.0352750000 0.4896510000 0.0014790000 146934179 0 402718720 3.8862447739 4.0121774673 3.0130920410 2912 1311867267.5954480171 0.2224369198 0.1008701881 0.2224369198 0.0062104457 0.6010800000 0.0425950000 0.0551560000 0.0000010000 0.4949630000 0.0014660000 146937963 0 402718720 3.8850057125 4.0108118057 3.0148227215 2913 1311867267.6272020340 0.2189815640 0.1009107344 0.2224369198 0.0062102127 1.2579560000 0.0559950000 0.0332400000 0.0350970000 0.5046210000 0.6213800000 146941635 0 402718720 3.8886754513 4.0109128952 3.0163607597 2914 1311867267.6608970165 0.2192466259 0.1009513438 0.2224369198 0.0062093698 0.6429340000 0.0542650000 0.0706040000 0.0000010000 0.5086280000 0.0018540000 146945307 0 402718720 3.8877842426 4.0104269981 3.0172598362 2915 1311867267.6955730915 0.2218113095 0.1009928052 0.2224369198 0.0062084284 0.6523660000 0.0549230000 0.0599600000 0.0348250000 0.4943010000 0.0014880000 146949091 0 402718720 3.8849096298 4.0108079910 3.0189092159 2916 1311867267.7264549732 0.2208866030 0.1010339211 0.2224369198 0.0062165320 0.5703430000 0.0433220000 0.0304750000 0.0000000000 0.4882090000 0.0014790000 146952707 0 402718720 3.8858132362 4.0127897263 3.0198993683 2917 1311867267.7624979019 0.2191275060 0.1010744057 0.2224369198 0.0062225112 1.2391980000 0.0711940000 0.0297730000 0.0349630000 0.4937690000 0.6026020000 146956547 0 402718720 3.8871574402 4.0102009773 3.0218977928 2918 1311867267.7957980633 0.2177324444 0.1011143844 0.2224369198 0.0062217108 0.5801100000 0.0434740000 0.0400550000 0.0000010000 0.4878690000 0.0015770000 146960219 0 402718720 3.8876760006 4.0086736679 3.0228030682 2919 1311867267.8323969841 0.2166545391 0.1011539665 0.2224369198 0.0062210262 0.6055910000 0.0435550000 0.0303780000 0.0350540000 0.4878890000 0.0015740000 146964059 0 402718720 3.8885223866 4.0075345039 3.0248310566 2920 1311867267.8601078987 0.2151564807 0.1011930085 0.2224369198 0.0062203376 0.5999300000 0.0437550000 0.0597100000 0.0000010000 0.4880260000 0.0014900000 146967563 0 402718720 3.8899295330 4.0106282234 3.0257744789 2921 1311867267.8989579678 0.2113964707 0.1012307365 0.2224369198 0.0062239793 1.2174950000 0.0437550000 0.0378560000 0.0350210000 0.4933020000 0.6005070000 146971459 0 402718720 3.8923323154 4.0086894035 3.0267975330 2922 1311867267.9282948971 0.2161348611 0.1012700603 0.2224369198 0.0062236107 0.5877840000 0.0437060000 0.0423870000 0.0000010000 0.4932820000 0.0014870000 146975019 0 402718720 3.8871376514 4.0080757141 3.0291786194 2923 1311867267.9643011093 0.2104356736 0.1013074074 0.2224369198 0.0062235479 0.6234680000 0.0442460000 0.0427660000 0.0351550000 0.4929560000 0.0014950000 146978803 0 402718720 3.8931348324 4.0079360008 3.0309605598 2924 1311867267.9947459698 0.2096603513 0.1013444638 0.2224369198 0.0062225794 0.5768000000 0.0433850000 0.0321660000 0.0000000000 0.4928500000 0.0014860000 146982475 0 402718720 3.8933842182 4.0072021484 3.0318405628 2925 1311867268.0287120342 0.2115701586 0.1013821478 0.2224369198 0.0062219826 1.2280450000 0.0587730000 0.0354680000 0.0351110000 0.4869140000 0.6041200000 146986147 0 402718720 3.8905119896 4.0053100586 3.0334651470 2926 1311867268.0588328838 0.2108640522 0.1014195647 0.2224369198 0.0062218913 0.6090340000 0.0553650000 0.0373600000 0.0000010000 0.5068610000 0.0018590000 146989819 0 402718720 3.8915584087 4.0069818497 3.0359618664 2927 1311867268.0946080685 0.2103123069 0.1014567676 0.2224369198 0.0062212558 0.6382290000 0.0551900000 0.0374210000 0.0451270000 0.4921230000 0.0014930000 146993603 0 402718720 3.8912866116 4.0043478012 3.0384030342 2928 1311867268.1253910065 0.2102982253 0.1014939402 0.2224369198 0.0062208251 0.5990930000 0.0437490000 0.0582620000 0.0000010000 0.4887480000 0.0014910000 146997219 0 402718720 3.8908209801 4.0037393570 3.0402092934 2929 1311867268.1606659889 0.2122452110 0.1015317522 0.2224369198 0.0062228260 1.2126120000 0.0441580000 0.0381730000 0.0349340000 0.4915380000 0.5967790000 147000947 0 402718720 3.8884913921 4.0040292740 3.0429840088 2930 1311867268.1981959343 0.2134538442 0.1015699508 0.2224369198 0.0062222054 0.5923500000 0.0628630000 0.0357040000 0.0000010000 0.4853600000 0.0014900000 147004787 0 402718720 3.8864433765 4.0046396255 3.0453243256 2931 1311867268.2290298939 0.2146081626 0.1016085173 0.2224369198 0.0062213481 0.6351370000 0.0444410000 0.0568570000 0.0349350000 0.4905760000 0.0014660000 147008459 0 402718720 3.8844552040 4.0044608116 3.0470974445 2932 1311867268.2579200268 0.2136946619 0.1016467458 0.2224369198 0.0062211512 0.5975020000 0.0443990000 0.0601030000 0.0000010000 0.4845940000 0.0015040000 147012019 0 402718720 3.8845837116 4.0023646355 3.0495629311 2933 1311867268.2951550484 0.2139985412 0.1016850519 0.2224369198 0.0062225417 1.1975130000 0.0442710000 0.0292230000 0.0347740000 0.4900050000 0.5922760000 147015803 0 402718720 3.8837101460 4.0014891624 3.0528554916 2934 1311867268.3274168968 0.2133366019 0.1017231063 0.2224369198 0.0062225677 0.5846550000 0.0572860000 0.0292120000 0.0000000000 0.4897060000 0.0014910000 147019475 0 402718720 3.8836960793 4.0011377335 3.0551865101 2935 1311867268.3586890697 0.2134677321 0.1017611794 0.2224369198 0.0062219899 0.6484650000 0.0606390000 0.0603740000 0.0350400000 0.4836210000 0.0015960000 147023203 0 402718720 3.8829081059 3.9991157055 3.0573630333 2936 1311867268.3934800625 0.2144955397 0.1017995767 0.2224369198 0.0062210955 0.5925760000 0.0450070000 0.0498950000 0.0000010000 0.4893020000 0.0014940000 147026931 0 402718720 3.8804817200 3.9993805885 3.0599260330 2937 1311867268.4261479378 0.2140992880 0.1018378129 0.2224369198 0.0062200718 1.2220840000 0.0450470000 0.0573500000 0.0345460000 0.4887300000 0.5894490000 147030603 0 402718720 3.8801307678 3.9988276958 3.0625138283 2938 1311867268.4581170082 0.2140752673 0.1018760149 0.2224369198 0.0062204151 0.5860310000 0.0448780000 0.0385340000 0.0000000000 0.4931130000 0.0018770000 147034275 0 402718720 3.8791685104 3.9990165234 3.0647885799 2939 1311867268.4943540096 0.2129029036 0.1019137920 0.2224369198 0.0062196729 0.6876770000 0.0569290000 0.0745900000 0.0445260000 0.5021740000 0.0018680000 147038059 0 402718720 3.8790538311 3.9956774712 3.0679283142 2940 1311867268.5280330181 0.2104535699 0.1019507103 0.2224369198 0.0062187327 0.6436680000 0.0573520000 0.0749230000 0.0000010000 0.5017760000 0.0018810000 147041787 0 402718720 3.8803346157 3.9955546856 3.0695235729 2941 1311867268.5616149902 0.2135087252 0.1019886423 0.2224369198 0.0062186575 1.2231450000 0.0563380000 0.0382090000 0.0448330000 0.4908960000 0.5859190000 147045515 0 402718720 3.8761172295 3.9972145557 3.0720310211 2942 1311867268.5949339867 0.2106342018 0.1020255714 0.2224369198 0.0062190975 0.5978380000 0.0451440000 0.0576500000 0.0000010000 0.4865640000 0.0014920000 147049187 0 402718720 3.8782172203 3.9972844124 3.0738658905 2943 1311867268.6294579506 0.2099378109 0.1020622389 0.2224369198 0.0062221124 0.6305710000 0.0451170000 0.0608810000 0.0349640000 0.4812070000 0.0014920000 147052971 0 402718720 3.8776423931 3.9967288971 3.0759475231 2944 1311867268.6639370918 0.2097616494 0.1020988215 0.2224369198 0.0062227729 0.5645610000 0.0451150000 0.0248510000 0.0000010000 0.4861320000 0.0014990000 147056755 0 402718720 3.8764786720 3.9959957600 3.0783324242 2945 1311867268.6937808990 0.2115638703 0.1021359913 0.2224369198 0.0062221741 1.1893890000 0.0536470000 0.0313120000 0.0346150000 0.4800140000 0.5827920000 147060315 0 402718720 3.8734183311 3.9956796169 3.0806574821 2946 1311867268.7282569408 0.2113296837 0.1021730564 0.2224369198 0.0062211548 0.5828080000 0.0451230000 0.0435300000 0.0000000000 0.4857310000 0.0014930000 147064043 0 402718720 3.8723778725 3.9958820343 3.0822668076 2947 1311867268.7629311085 0.2108878344 0.1022099464 0.2224369198 0.0062211621 0.6281410000 0.0451680000 0.0598170000 0.0344390000 0.4798580000 0.0015960000 147067827 0 402718720 3.8723368645 3.9951715469 3.0850195885 2948 1311867268.7951219082 0.2121834755 0.1022472508 0.2224369198 0.0062207156 0.6000000000 0.0452460000 0.0608100000 0.0000000000 0.4855130000 0.0015030000 147071443 0 402718720 3.8703863621 3.9960484505 3.0874526501 2949 1311867268.8264629841 0.2107599378 0.1022840473 0.2224369198 0.0062201856 1.2326620000 0.0728080000 0.0512730000 0.0344930000 0.4854820000 0.5816010000 147075115 0 402718720 3.8704133034 3.9949393272 3.0903842449 2950 1311867268.8615820408 0.2096720338 0.1023204500 0.2224369198 0.0062199852 0.5764350000 0.0580380000 0.0249890000 0.0000010000 0.4849030000 0.0015020000 147078843 0 402718720 3.8699216843 3.9932854176 3.0929739475 2951 1311867268.8947710991 0.2073533386 0.1023560423 0.2224369198 0.0062272439 0.6276580000 0.0455130000 0.0602890000 0.0343500000 0.4790630000 0.0014970000 147082515 0 402718720 3.8710224628 3.9946618080 3.0959029198 2952 1311867268.9271900654 0.2114493698 0.1023929980 0.2224369198 0.0062359225 0.5995130000 0.0461080000 0.0610790000 0.0000010000 0.4838330000 0.0015120000 147086243 0 402718720 3.8657877445 3.9946713448 3.0991876125 2953 1311867268.9633738995 0.2080434710 0.1024287754 0.2224369198 0.0062354567 1.1920800000 0.0462030000 0.0443320000 0.0346880000 0.4831010000 0.5767350000 147090083 0 402718720 3.8679871559 3.9926073551 3.1028194427 2954 1311867268.9942259789 0.2104015797 0.1024653268 0.2224369198 0.0062358784 0.5956670000 0.0460890000 0.0587150000 0.0000010000 0.4824140000 0.0015100000 147093643 0 402718720 3.8645315170 3.9933953285 3.1058077812 2955 1311867269.0293419361 0.2080639452 0.1025010623 0.2224369198 0.0062357542 0.6360260000 0.0545140000 0.0621370000 0.0346060000 0.4759500000 0.0016040000 147097483 0 402718720 3.8658013344 3.9903364182 3.1097326279 2956 1311867269.0628340244 0.2075654566 0.1025366051 0.2224369198 0.0062347822 0.5774750000 0.0454930000 0.0463880000 0.0000010000 0.4766850000 0.0015830000 147101211 0 402718720 3.8651256561 3.9902172089 3.1126689911 2957 1311867269.0942130089 0.2084875703 0.1025724356 0.2224369198 0.0062337836 1.1790780000 0.0469430000 0.0369770000 0.0347220000 0.4814260000 0.5720580000 147104715 0 402718720 3.8629143238 3.9895505905 3.1158909798 2958 1311867269.1263980865 0.2122981846 0.1026095302 0.2224369198 0.0062329840 0.5931360000 0.0592480000 0.0442130000 0.0000010000 0.4812220000 0.0015030000 147108387 0 402718720 3.8577885628 3.9891328812 3.1192786694 2959 1311867269.1618270874 0.2090648562 0.1026455070 0.2224369198 0.0062321068 0.5999880000 0.0463000000 0.0301600000 0.0342760000 0.4807110000 0.0015090000 147112115 0 402718720 3.8594632149 3.9890978336 3.1215484142 2960 1311867269.1941618919 0.2075529099 0.1026809487 0.2224369198 0.0062317036 0.6147420000 0.0685490000 0.0627540000 0.0000010000 0.4745700000 0.0016100000 147115787 0 402718720 3.8594501019 3.9880852699 3.1249103546 2961 1311867269.2266249657 0.2096511573 0.1027170751 0.2224369198 0.0062341344 1.1511110000 0.0467630000 0.0270080000 0.0345940000 0.4740210000 0.5617080000 147119459 0 402718720 3.8561971188 3.9888820648 3.1275131702 2962 1311867269.2623720169 0.2054675967 0.1027517647 0.2224369198 0.0062347960 0.5704080000 0.0472000000 0.0353910000 0.0000010000 0.4792430000 0.0015200000 147123243 0 402718720 3.8587691784 3.9880375862 3.1302084923 2963 1311867269.2948200703 0.2043551505 0.1027860554 0.2224369198 0.0062631976 0.6226460000 0.0604310000 0.0404280000 0.0346230000 0.4786640000 0.0015280000 147126971 0 402718720 3.8579010963 3.9870905876 3.1330049038 2964 1311867269.3261830807 0.2040026337 0.1028202040 0.2224369198 0.0062700045 0.5951970000 0.0477840000 0.0601430000 0.0000000000 0.4787270000 0.0015050000 147130587 0 402718720 3.8576872349 3.9891428947 3.1364078522 2965 1311867269.3641560078 0.2052661031 0.1028547557 0.2224369198 0.0062715201 1.2306310000 0.0613220000 0.0619160000 0.0344640000 0.4864130000 0.5786820000 147134427 0 402718720 3.8548030853 3.9910452366 3.1391932964 2966 1311867269.3967740536 0.2031536847 0.1028885720 0.2224369198 0.0062729387 0.6154710000 0.0612340000 0.0538030000 0.0000010000 0.4907990000 0.0019390000 147138099 0 402718720 3.8551459312 3.9866063595 3.1434683800 2967 1311867269.4275820255 0.2008563727 0.1029215911 0.2224369198 0.0062741631 0.6690890000 0.0611180000 0.0781090000 0.0438300000 0.4775150000 0.0015300000 147141771 0 402718720 3.8570690155 3.9883110523 3.1462366581 2968 1311867269.4626441002 0.2013299167 0.1029547476 0.2224369198 0.0062733720 0.5739190000 0.0486250000 0.0418100000 0.0000010000 0.4749500000 0.0015340000 147145499 0 402718720 3.8556230068 3.9885144234 3.1494870186 2969 1311867269.4938280582 0.1999135017 0.1029874046 0.2224369198 0.0062894942 1.1673670000 0.0601050000 0.0368020000 0.0344400000 0.4740600000 0.5548970000 147149115 0 402718720 3.8568253517 3.9893751144 3.1533558369 2970 1311867269.5278589725 0.1975028962 0.1030192280 0.2224369198 0.0063088091 0.6069840000 0.0613080000 0.0632660000 0.0000010000 0.4738530000 0.0015430000 147152899 0 402718720 3.8586313725 3.9904010296 3.1570217609 2971 1311867269.5634589195 0.1953661442 0.1030503108 0.2224369198 0.0063082651 0.6267850000 0.0500080000 0.0667240000 0.0345450000 0.4665390000 0.0016460000 147156683 0 402718720 3.8592679501 3.9905266762 3.1599638462 2972 1311867269.5962390900 0.1950460076 0.1030812649 0.2224369198 0.0063077625 0.5642670000 0.0511600000 0.0385690000 0.0000010000 0.4659760000 0.0015520000 147160355 0 402718720 3.8587796688 3.9903995991 3.1624450684 2973 1311867269.6306080818 0.1940431893 0.1031118609 0.2224369198 0.0063068060 1.1939360000 0.0506300000 0.0613850000 0.0345500000 0.4777620000 0.5617390000 147164083 0 402718720 3.8583679199 3.9896612167 3.1653416157 2974 1311867269.6631560326 0.1938951910 0.1031423866 0.2224369198 0.0063057793 0.5986720000 0.0640060000 0.0558510000 0.0000000000 0.4702290000 0.0015270000 147167811 0 402718720 3.8578214645 3.9903037548 3.1683781147 2975 1311867269.6964600086 0.1909829378 0.1031719128 0.2224369198 0.0063104763 0.6387170000 0.0702300000 0.0571490000 0.0342120000 0.4685740000 0.0015730000 147171427 0 402718720 3.8604147434 3.9918572903 3.1712303162 2976 1311867269.7280869484 0.1900112629 0.1032010927 0.2224369198 0.0063101503 0.5615880000 0.0520610000 0.0329880000 0.0000010000 0.4679110000 0.0015730000 147175155 0 402718720 3.8597824574 3.9914495945 3.1723601818 2977 1311867269.7622261047 0.1898893118 0.1032302120 0.2224369198 0.0063097396 1.1281750000 0.0510800000 0.0401090000 0.0341060000 0.4619600000 0.5338480000 147178883 0 402718720 3.8590040207 3.9900448322 3.1752800941 2978 1311867269.7974090576 0.1859642565 0.1032579938 0.2224369198 0.0063089379 0.5743400000 0.0518350000 0.0330080000 0.0000000000 0.4797360000 0.0020000000 147182611 0 402718720 3.8619902134 3.9895212650 3.1768882275 2979 1311867269.8295869827 0.1865836978 0.1032859648 0.2224369198 0.0063194970 0.6371900000 0.0657520000 0.0433460000 0.0436550000 0.4758790000 0.0015730000 147186283 0 402718720 3.8604316711 3.9895551205 3.1793305874 2980 1311867269.8676230907 0.1878387779 0.1033143382 0.2224369198 0.0063191617 0.5794940000 0.0639460000 0.0460970000 0.0000010000 0.4608290000 0.0015690000 147190067 0 402718720 3.8570687771 3.9870090485 3.1811308861 2981 1311867269.8953619003 0.1876211166 0.1033426196 0.2224369198 0.0063182176 1.1730000000 0.0514650000 0.0513950000 0.0343710000 0.4768220000 0.5510800000 147193627 0 402718720 3.8572547436 3.9875111580 3.1831004620 2982 1311867269.9344720840 0.1846851557 0.1033698975 0.2224369198 0.0063173049 0.6033940000 0.0654310000 0.0485320000 0.0000010000 0.4796580000 0.0020100000 147197467 0 402718720 3.8597550392 3.9879748821 3.1850469112 2983 1311867269.9627900124 0.1876131594 0.1033981386 0.2224369198 0.0063230690 0.6411510000 0.0653720000 0.0570060000 0.0436040000 0.4665470000 0.0015700000 147201083 0 402718720 3.8560359478 3.9873547554 3.1869337559 2984 1311867269.9987258911 0.1895076782 0.1034269957 0.2224369198 0.0063225250 0.5891560000 0.0521110000 0.0635870000 0.0000010000 0.4648640000 0.0015750000 147204867 0 402718720 3.8534226418 3.9863085747 3.1888322830 2985 1311867270.0306990147 0.1878166944 0.1034552669 0.2224369198 0.0063230709 1.1650790000 0.0621940000 0.0641300000 0.0344730000 0.4644500000 0.5327370000 147208483 0 402718720 3.8546423912 3.9844815731 3.1911778450 2986 1311867270.0660951138 0.1901749074 0.1034843090 0.2224369198 0.0063225235 0.5903680000 0.0524020000 0.0652830000 0.0000000000 0.4640540000 0.0015780000 147212267 0 402718720 3.8520951271 3.9849550724 3.1938517094 2987 1311867270.0948200226 0.1900403053 0.1035132866 0.2224369198 0.0063216295 0.5951080000 0.0522580000 0.0409780000 0.0343420000 0.4589070000 0.0015570000 147215771 0 402718720 3.8524706364 3.9863100052 3.1958816051 2988 1311867270.1336340904 0.1896589100 0.1035421171 0.2224369198 0.0063205825 0.5689810000 0.0528600000 0.0445320000 0.0000000000 0.4629320000 0.0015890000 147219723 0 402718720 3.8525199890 3.9864180088 3.1985194683 2989 1311867270.1624090672 0.1907391697 0.1035712897 0.2224369198 0.0063195984 1.1311440000 0.0530530000 0.0445900000 0.0343860000 0.4624600000 0.5295840000 147223283 0 402718720 3.8515326977 3.9867892265 3.2012670040 2990 1311867270.1943540573 0.1893201023 0.1035999683 0.2224369198 0.0063188245 0.5817140000 0.0663830000 0.0449780000 0.0000010000 0.4617050000 0.0015880000 147226955 0 402718720 3.8527781963 3.9847199917 3.2043447495 2991 1311867270.2323369980 0.1877488345 0.1036281023 0.2224369198 0.0063203400 0.5936660000 0.0535090000 0.0402410000 0.0344910000 0.4567970000 0.0016040000 147230795 0 402718720 3.8540887833 3.9852735996 3.2063758373 2992 1311867270.2655749321 0.1869410723 0.1036559475 0.2224369198 0.0063215645 0.5895270000 0.0536140000 0.0666630000 0.0000000000 0.4605340000 0.0016040000 147234467 0 402718720 3.8541224003 3.9825882912 3.2090632915 2993 1311867270.2960460186 0.1845299751 0.1036829686 0.2224369198 0.0063206371 1.1101920000 0.0535800000 0.0415090000 0.0343680000 0.4547000000 0.5189080000 147238083 0 402718720 3.8569593430 3.9816043377 3.2119657993 2994 1311867270.3346099854 0.1823514551 0.1037092440 0.2224369198 0.0063203626 0.5590830000 0.0537150000 0.0418840000 0.0000010000 0.4547710000 0.0015990000 147241979 0 402718720 3.8587443829 3.9812808037 3.2142684460 2995 1311867270.3624660969 0.1851177812 0.1037364255 0.2224369198 0.0063194392 0.6457320000 0.0827300000 0.0657520000 0.0344660000 0.4540650000 0.0016110000 147245539 0 402718720 3.8554611206 3.9813568592 3.2163767815 2996 1311867270.3957469463 0.1864426136 0.1037640310 0.2224369198 0.0063197227 0.5657150000 0.0539000000 0.0449780000 0.0000010000 0.4581050000 0.0015940000 147249211 0 402718720 3.8541407585 3.9805812836 3.2195913792 2997 1311867270.4334359169 0.1850965619 0.1037911690 0.2224369198 0.0063260881 1.1253880000 0.0658560000 0.0399570000 0.0339330000 0.4574840000 0.5210220000 147253107 0 402718720 3.8555552959 3.9808578491 3.2230749130 2998 1311867270.4641909599 0.1839020103 0.1038178904 0.2224369198 0.0063252748 0.5518230000 0.0545390000 0.0363940000 0.0000000000 0.4521180000 0.0016140000 147256779 0 402718720 3.8566377163 3.9792706966 3.2257425785 2999 1311867270.4954609871 0.1827123612 0.1038441973 0.2224369198 0.0063248308 0.6208620000 0.0545600000 0.0675780000 0.0339680000 0.4561120000 0.0016140000 147260339 0 402718720 3.8576278687 3.9771385193 3.2287616730 3000 1311867270.5331869125 0.1844924092 0.1038710801 0.2224369198 0.0063242050 0.6037010000 0.0819980000 0.0571330000 0.0000000000 0.4558420000 0.0016110000 147264235 0 402718720 3.8560183048 3.9771738052 3.2317149639 3001 1311867270.5629880428 0.1832606494 0.1038975344 0.2224369198 0.0063235639 1.1019030000 0.0551190000 0.0347800000 0.0343240000 0.4551730000 0.5153750000 147267851 0 402718720 3.8570139408 3.9733428955 3.2345786095 3002 1311867270.5944859982 0.1808216572 0.1039231587 0.2224369198 0.0063227573 0.5595910000 0.0555390000 0.0403860000 0.0000010000 0.4549890000 0.0016080000 147271411 0 402718720 3.8593206406 3.9703457355 3.2367730141 3003 1311867270.6312110424 0.1814355701 0.1039489704 0.2224369198 0.0063232019 0.6068580000 0.0543880000 0.0596200000 0.0342360000 0.4495120000 0.0017040000 147275195 0 402718720 3.8596487045 3.9718775749 3.2396767139 3004 1311867270.6644439697 0.1826264113 0.1039751613 0.2224369198 0.0063248068 0.5855610000 0.0552330000 0.0721070000 0.0000010000 0.4491440000 0.0017080000 147278867 0 402718720 3.8587949276 3.9710578918 3.2414436340 3005 1311867270.6950180531 0.1807668060 0.1040007159 0.2224369198 0.0063247191 1.1226670000 0.0701830000 0.0482630000 0.0342430000 0.4497220000 0.5130820000 147282483 0 402718720 3.8603484631 3.9698143005 3.2435472012 3006 1311867270.7318449020 0.1808453500 0.1040262797 0.2224369198 0.0063241520 0.5852020000 0.0556170000 0.0719160000 0.0000010000 0.4489550000 0.0016140000 147286323 0 402718720 3.8606760502 3.9681944847 3.2459077835 3007 1311867270.7623898983 0.1804450452 0.1040516933 0.2224369198 0.0063232397 0.5933020000 0.0551370000 0.0470430000 0.0342850000 0.4481680000 0.0016110000 147289939 0 402718720 3.8613662720 3.9696733952 3.2476453781 3008 1311867270.7960500717 0.1814837754 0.1040774353 0.2224369198 0.0063227569 0.5843170000 0.0563470000 0.0661090000 0.0000010000 0.4532160000 0.0015970000 147293667 0 402718720 3.8601987362 3.9679291248 3.2492487431 3009 1311867270.8322730064 0.1817388833 0.1041032451 0.2224369198 0.0063254039 1.1049950000 0.0552620000 0.0459280000 0.0341960000 0.4522160000 0.5101330000 147297451 0 402718720 3.8602688313 3.9686932564 3.2516694069 3010 1311867270.8635489941 0.1799527109 0.1041284442 0.2224369198 0.0063257388 0.5610280000 0.0676630000 0.0372770000 0.0000000000 0.4472910000 0.0016260000 147301123 0 402718720 3.8628242016 3.9684166908 3.2541425228 3011 1311867270.8945889473 0.1818650067 0.1041542617 0.2224369198 0.0063256049 0.6195370000 0.0563730000 0.0689860000 0.0342570000 0.4511780000 0.0016180000 147304739 0 402718720 3.8601145744 3.9660174847 3.2555553913 3012 1311867270.9326179028 0.1810669601 0.1041797972 0.2224369198 0.0063287979 0.5617100000 0.0558810000 0.0462470000 0.0000010000 0.4507880000 0.0016130000 147308579 0 402718720 3.8622224331 3.9663825035 3.2580406666 3013 1311867270.9624550343 0.1788235307 0.1042045710 0.2224369198 0.0063319555 1.0955140000 0.0568390000 0.0414400000 0.0338020000 0.4499670000 0.5062510000 147312195 0 402718720 3.8663198948 3.9689145088 3.2606065273 3014 1311867270.9944560528 0.1776659340 0.1042289444 0.2224369198 0.0063317200 0.5790770000 0.0815920000 0.0438000000 0.0000000000 0.4445080000 0.0017260000 147315867 0 402718720 3.8671658039 3.9660239220 3.2617321014 3015 1311867271.0306649208 0.1758968085 0.1042527149 0.2224369198 0.0063308839 0.6292470000 0.0797200000 0.0619960000 0.0339660000 0.4444020000 0.0017210000 147319595 0 402718720 3.8691093922 3.9627606869 3.2636044025 3016 1311867271.0623910427 0.1747686565 0.1042760955 0.2224369198 0.0063305390 0.5613900000 0.0568450000 0.0494550000 0.0000000000 0.4462000000 0.0016210000 147323267 0 402718720 3.8713693619 3.9616310596 3.2658917904 3017 1311867271.0983459949 0.1766390353 0.1043000805 0.2224369198 0.0063325766 1.0865390000 0.0571960000 0.0364320000 0.0338150000 0.4486390000 0.5032650000 147327051 0 402718720 3.8698289394 3.9610724449 3.2669959068 3018 1311867271.1322019100 0.1793746054 0.1043249561 0.2224369198 0.0063316056 0.5847920000 0.0572100000 0.0698580000 0.0000010000 0.4488810000 0.0016210000 147330723 0 402718720 3.8666925430 3.9587070942 3.2684016228 3019 1311867271.1643741131 0.1790733933 0.1043497155 0.2224369198 0.0063310112 0.6186550000 0.0571110000 0.0696420000 0.0342070000 0.4488770000 0.0016350000 147334395 0 402718720 3.8682594299 3.9595928192 3.2701454163 3020 1311867271.1988029480 0.1811712831 0.1043751531 0.2224369198 0.0063307388 0.5953300000 0.0680610000 0.0697350000 0.0000010000 0.4487440000 0.0016250000 147338179 0 402718720 3.8661646843 3.9580748081 3.2716505527 3021 1311867271.2320818901 0.1792713255 0.1043999449 0.2224369198 0.0063316930 1.0921810000 0.0572860000 0.0413620000 0.0338740000 0.4487380000 0.5036580000 147341795 0 402718720 3.8685388565 3.9561369419 3.2735109329 3022 1311867271.2645740509 0.1813046634 0.1044253932 0.2224369198 0.0063345953 0.5835160000 0.0569720000 0.0733980000 0.0000010000 0.4440030000 0.0017130000 147345467 0 402718720 3.8676843643 3.9580657482 3.2761657238 3023 1311867271.2998549938 0.1794215441 0.1044502017 0.2224369198 0.0063355176 0.5814670000 0.0568200000 0.0374910000 0.0338160000 0.4444580000 0.0016280000 147349251 0 402718720 3.8703479767 3.9564108849 3.2789149284 3024 1311867271.3354289532 0.1789582670 0.1044748406 0.2224369198 0.0063369373 0.5762640000 0.0579530000 0.0620560000 0.0000010000 0.4461390000 0.0020980000 147352979 0 402718720 3.8701150417 3.9515051842 3.2815818787 3025 1311867271.3673670292 0.1762500703 0.1044985680 0.2224369198 0.0063365514 1.1456030000 0.0723680000 0.0449760000 0.0431030000 0.4611860000 0.5159900000 147356707 0 402718720 3.8737652302 3.9519779682 3.2843139172 3026 1311867271.3988809586 0.1755484343 0.1045220478 0.2224369198 0.0063359906 0.5959660000 0.0715290000 0.0537600000 0.0000000000 0.4606050000 0.0020790000 147360379 0 402718720 3.8751237392 3.9501571655 3.2869322300 3027 1311867271.4355340004 0.1754425317 0.1045454771 0.2224369198 0.0063351673 0.6073140000 0.0658810000 0.0525970000 0.0341850000 0.4458540000 0.0016220000 147364163 0 402718720 3.8747365475 3.9470560551 3.2894558907 3028 1311867271.4657170773 0.1749648005 0.1045687331 0.2224369198 0.0063374644 0.5564910000 0.0573700000 0.0494100000 0.0000010000 0.4404920000 0.0017140000 147367723 0 402718720 3.8752474785 3.9441831112 3.2924144268 3029 1311867271.4997088909 0.1747477204 0.1045919022 0.2224369198 0.0063400330 1.0778800000 0.0566600000 0.0371480000 0.0340950000 0.4443040000 0.4984260000 147371507 0 402718720 3.8753917217 3.9434003830 3.2947256565 3030 1311867271.5323960781 0.1738061756 0.1046147452 0.2224369198 0.0063396959 0.6775450000 0.0878710000 0.0387150000 0.0000010000 0.5351590000 0.0049610000 147375179 0 402718720 3.8765697479 3.9415800571 3.2980084419 3031 1311867271.5676190853 0.1731799543 0.1046373665 0.2224369198 0.0063388890 0.6121830000 0.0563120000 0.0686830000 0.0339490000 0.4444930000 0.0016040000 147378907 0 402718720 3.8768591881 3.9384815693 3.3013582230 3032 1311867271.5991230011 0.1725875884 0.1046597775 0.2224369198 0.0063379676 0.5475290000 0.0560940000 0.0427340000 0.0000010000 0.4398710000 0.0016080000 147382579 0 402718720 3.8777959347 3.9384002686 3.3045861721 3033 1311867271.6349890232 0.1717116684 0.1046818849 0.2224369198 0.0063374438 1.0956320000 0.0557780000 0.0536860000 0.0339320000 0.4493150000 0.4956820000 147386307 0 402718720 3.8780953884 3.9358398914 3.3084115982 3034 1311867271.6658320427 0.1707468927 0.1047036598 0.2224369198 0.0063366634 0.5587980000 0.0669640000 0.0404780000 0.0000010000 0.4425110000 0.0016020000 147389979 0 402718720 3.8794560432 3.9355905056 3.3126029968 3035 1311867271.7005228996 0.1703502536 0.1047252897 0.2224369198 0.0063393630 0.6058900000 0.0757400000 0.0462200000 0.0334540000 0.4416540000 0.0016030000 147393707 0 402718720 3.8793215752 3.9349842072 3.3167872429 3036 1311867271.7349541187 0.1703442931 0.1047469033 0.2224369198 0.0063389316 0.5524720000 0.0566880000 0.0463720000 0.0000010000 0.4405660000 0.0016100000 147397491 0 402718720 3.8778157234 3.9336094856 3.3211462498 3037 1311867271.7661850452 0.1662404686 0.1047671514 0.2224369198 0.0063412542 1.0824740000 0.0564860000 0.0668080000 0.0339750000 0.4345590000 0.4832900000 147401107 0 402718720 3.8806385994 3.9299547672 3.3256368637 3038 1311867271.7994530201 0.1672510952 0.1047877189 0.2224369198 0.0063449481 0.5996590000 0.0835310000 0.0725840000 0.0000010000 0.4346620000 0.0016110000 147404891 0 402718720 3.8792197704 3.9300584793 3.3298904896 3039 1311867271.8341000080 0.1628834158 0.1048068356 0.2224369198 0.0063445185 0.5822460000 0.0569040000 0.0491140000 0.0338770000 0.4334740000 0.0016110000 147408563 0 402718720 3.8827505112 3.9283010960 3.3342881203 3040 1311867271.8629150391 0.1622406542 0.1048257283 0.2224369198 0.0063443475 0.5629190000 0.0698220000 0.0467170000 0.0000010000 0.4374960000 0.0016090000 147412179 0 402718720 3.8825795650 3.9233131409 3.3395228386 3041 1311867271.9009630680 0.1600086093 0.1048438746 0.2224369198 0.0063434167 1.0557210000 0.0568740000 0.0351970000 0.0338150000 0.4370700000 0.4854600000 147416019 0 402718720 3.8840923309 3.9220111370 3.3443837166 3042 1311867271.9304800034 0.1609008610 0.1048623023 0.2224369198 0.0063428415 0.5543380000 0.0571010000 0.0521060000 0.0000010000 0.4363180000 0.0016130000 147419635 0 402718720 3.8831472397 3.9225564003 3.3493635654 3043 1311867271.9669768810 0.1592784673 0.1048801847 0.2224369198 0.0063423184 0.5698310000 0.0568130000 0.0351280000 0.0337240000 0.4352790000 0.0016040000 147423363 0 402718720 3.8848810196 3.9202911854 3.3550403118 3044 1311867271.9994390011 0.1582363248 0.1048977130 0.2224369198 0.0063413721 0.5585850000 0.0570790000 0.0579610000 0.0000010000 0.4346460000 0.0016080000 147427035 0 402718720 3.8861227036 3.9190640450 3.3604929447 3045 1311867272.0337600708 0.1566008925 0.1049146927 0.2224369198 0.0063407346 1.0680100000 0.0719240000 0.0498630000 0.0338170000 0.4287860000 0.4763220000 147430763 0 402718720 3.8880367279 3.9199213982 3.3658189774 3046 1311867272.0626399517 0.1563780010 0.1049315881 0.2224369198 0.0063407791 0.5404250000 0.0589840000 0.0440070000 0.0000010000 0.4284740000 0.0016190000 147434379 0 402718720 3.8880703449 3.9166724682 3.3699572086 3047 1311867272.0988030434 0.1567706466 0.1049486012 0.2224369198 0.0063402626 0.5891930000 0.0574060000 0.0583430000 0.0336180000 0.4309580000 0.0016160000 147438163 0 402718720 3.8877928257 3.9140701294 3.3749816418 3048 1311867272.1336209774 0.1558662057 0.1049653065 0.2224369198 0.0063392534 0.5426690000 0.0582670000 0.0496860000 0.0000010000 0.4254840000 0.0017200000 147441947 0 402718720 3.8897120953 3.9127361774 3.3796851635 3049 1311867272.1659350395 0.1578618586 0.1049826553 0.2224369198 0.0063398211 1.0383210000 0.0579720000 0.0435090000 0.0337080000 0.4247240000 0.4710660000 147445619 0 402718720 3.8876626492 3.9101550579 3.3834006786 3050 1311867272.1987910271 0.1578310132 0.1049999826 0.2224369198 0.0063395169 0.5550270000 0.0751240000 0.0421440000 0.0000000000 0.4288300000 0.0016240000 147449347 0 402718720 3.8883960247 3.9084198475 3.3870215416 3051 1311867272.2319760323 0.1577676088 0.1050172778 0.2224369198 0.0063392694 0.5631900000 0.0580290000 0.0376000000 0.0336300000 0.4250990000 0.0016120000 147453019 0 402718720 3.8895285130 3.9057738781 3.3912920952 3052 1311867272.2655110359 0.1577545553 0.1050345574 0.2224369198 0.0063420836 0.5540030000 0.0583890000 0.0581730000 0.0000010000 0.4284880000 0.0016130000 147456747 0 402718720 3.8905770779 3.9065775871 3.3947820663 3053 1311867272.2982270718 0.1590922028 0.1050522638 0.2224369198 0.0063412205 1.0330860000 0.0580810000 0.0355680000 0.0335570000 0.4276730000 0.4709160000 147460475 0 402718720 3.8898725510 3.9061729908 3.3976340294 3054 1311867272.3315019608 0.1579841822 0.1050695958 0.2224369198 0.0063459361 0.5359620000 0.0583580000 0.0413810000 0.0000010000 0.4273270000 0.0016100000 147464147 0 402718720 3.8909745216 3.9033553600 3.4004907608 3055 1311867272.3696749210 0.1585309654 0.1050870954 0.2224369198 0.0063467970 0.6348660000 0.0926940000 0.0740120000 0.0337080000 0.4249100000 0.0016350000 147467987 0 402718720 3.8907780647 3.9024336338 3.4036686420 3056 1311867272.3987050056 0.1588989645 0.1051047040 0.2224369198 0.0063462458 0.5519450000 0.0589060000 0.0620320000 0.0000010000 0.4217280000 0.0017090000 147471547 0 402718720 3.8907601833 3.9011421204 3.4071326256 3057 1311867272.4335730076 0.1538478285 0.1051206488 0.2224369198 0.0063458452 1.0460430000 0.0587800000 0.0559160000 0.0336450000 0.4223950000 0.4680030000 147475331 0 402718720 3.8965418339 3.8986647129 3.4101133347 3058 1311867272.4686141014 0.1517769843 0.1051359059 0.2224369198 0.0063452958 0.5449130000 0.0692630000 0.0412590000 0.0000010000 0.4255050000 0.0016170000 147479059 0 402718720 3.8991572857 3.8963418007 3.4135768414 3059 1311867272.5011420250 0.1511486918 0.1051509477 0.2224369198 0.0063444029 0.6054600000 0.0686360000 0.0693480000 0.0333740000 0.4252180000 0.0016120000 147482731 0 402718720 3.9001193047 3.8952138424 3.4169898033 3060 1311867272.5325479507 0.1483298242 0.1051650584 0.2224369198 0.0063437257 0.5501540000 0.0704910000 0.0496180000 0.0000010000 0.4206720000 0.0017160000 147486403 0 402718720 3.9035396576 3.8932840824 3.4198253155 3061 1311867272.5676600933 0.1465265155 0.1051785708 0.2224369198 0.0063431032 1.0252230000 0.0590530000 0.0377080000 0.0335680000 0.4212700000 0.4663190000 147490131 0 402718720 3.9060854912 3.8928046227 3.4226431847 3062 1311867272.5996229649 0.1483319104 0.1051926640 0.2224369198 0.0063422302 0.5499990000 0.0586920000 0.0585810000 0.0000010000 0.4237690000 0.0016140000 147493859 0 402718720 3.9045886993 3.8934316635 3.4252302647 3063 1311867272.6315360069 0.1475143582 0.1052064811 0.2224369198 0.0063416025 0.5702810000 0.0579860000 0.0470080000 0.0329640000 0.4234710000 0.0016170000 147497475 0 402718720 3.9054846764 3.8921654224 3.4273889065 3064 1311867272.6661291122 0.1481934786 0.1052205108 0.2224369198 0.0063407332 0.5621620000 0.0828380000 0.0472730000 0.0000010000 0.4231030000 0.0016160000 147501203 0 402718720 3.9049410820 3.8927650452 3.4298591614 3065 1311867272.6987280846 0.1474686861 0.1052342949 0.2224369198 0.0063399188 1.0222180000 0.0595870000 0.0440880000 0.0335040000 0.4184880000 0.4590440000 147504931 0 402718720 3.9064562321 3.8922708035 3.4328284264 3066 1311867272.7307109833 0.1450363249 0.1052472766 0.2224369198 0.0063393289 0.5617260000 0.0591530000 0.0746900000 0.0000000000 0.4189530000 0.0016180000 147508603 0 402718720 3.9094579220 3.8893005848 3.4355144501 3067 1311867272.7686150074 0.1459932774 0.1052605619 0.2224369198 0.0063415427 0.5777970000 0.0593370000 0.0561810000 0.0334930000 0.4199010000 0.0016160000 147512387 0 402718720 3.9093451500 3.8904621601 3.4380209446 3068 1311867272.7996079922 0.1477567405 0.1052744133 0.2224369198 0.0063406123 0.5261120000 0.0591410000 0.0357440000 0.0000000000 0.4222880000 0.0016230000 147516003 0 402718720 3.9086661339 3.8900291920 3.4408926964 3069 1311867272.8310160637 0.1477957815 0.1052882684 0.2224369198 0.0063401822 1.0694710000 0.0719490000 0.0645040000 0.0333880000 0.4218090000 0.4697680000 147519675 0 402718720 3.9096505642 3.8907592297 3.4435961246 3070 1311867272.8674850464 0.1486271173 0.1053023853 0.2224369198 0.0063395866 0.6121670000 0.0743290000 0.0919950000 0.0000010000 0.4357050000 0.0020750000 147523515 0 402718720 3.9103164673 3.8902165890 3.4461350441 3071 1311867272.8996291161 0.1447442025 0.1053152286 0.2224369198 0.0063395316 0.6532870000 0.0739680000 0.0915400000 0.0422450000 0.4354170000 0.0021160000 147527131 0 402718720 3.9163429737 3.8898677826 3.4484429359 3072 1311867272.9314110279 0.1455256194 0.1053283180 0.2224369198 0.0063393614 0.5719430000 0.0738520000 0.0617630000 0.0000000000 0.4273320000 0.0016020000 147530803 0 402718720 3.9174063206 3.8889050484 3.4505438805 3073 1311867272.9664669037 0.1464198530 0.1053416898 0.2224369198 0.0063384918 1.0517030000 0.0584200000 0.0695200000 0.0332680000 0.4212410000 0.4618210000 147534587 0 402718720 3.9178681374 3.8900425434 3.4519424438 3074 1311867272.9987599850 0.1468049735 0.1053551781 0.2224369198 0.0063378714 0.5354840000 0.0586010000 0.0469560000 0.0000010000 0.4209880000 0.0016050000 147538259 0 402718720 3.9189283848 3.8895852566 3.4535422325 3075 1311867273.0328490734 0.1451524347 0.1053681203 0.2224369198 0.0063370066 0.6010280000 0.0717870000 0.0614490000 0.0329450000 0.4247250000 0.0020760000 147542043 0 402718720 3.9223604202 3.8884582520 3.4547765255 3076 1311867273.0662739277 0.1460288465 0.1053813390 0.2224369198 0.0063360107 0.5951340000 0.0734340000 0.0759900000 0.0000010000 0.4354990000 0.0020670000 147545715 0 402718720 3.9230930805 3.8883993626 3.4561696053 3077 1311867273.0999150276 0.1473207325 0.1053949690 0.2224369198 0.0063350938 1.1185570000 0.0728050000 0.0887190000 0.0415920000 0.4355230000 0.4725460000 147549387 0 402718720 3.9235541821 3.8903555870 3.4575181007 3078 1311867273.1310710907 0.1468845010 0.1054084484 0.2224369198 0.0063342327 0.5234960000 0.0579640000 0.0353250000 0.0000000000 0.4212810000 0.0015930000 147553059 0 402718720 3.9251461029 3.8910050392 3.4584152699 3079 1311867273.1665740013 0.1452762038 0.1054213967 0.2224369198 0.0063334850 0.6023560000 0.0696390000 0.0698820000 0.0328870000 0.4210130000 0.0016070000 147556843 0 402718720 3.9274251461 3.8917279243 3.4591476917 3080 1311867273.1997520924 0.1437943727 0.1054338554 0.2224369198 0.0063325665 0.5737120000 0.0921600000 0.0554270000 0.0000010000 0.4168160000 0.0017000000 147560515 0 402718720 3.9302773476 3.8922009468 3.4609911442 3081 1311867273.2331819534 0.1437652111 0.1054462966 0.2224369198 0.0063323537 1.0634840000 0.0694980000 0.0715550000 0.0332790000 0.4205290000 0.4612930000 147564299 0 402718720 3.9301669598 3.8895862103 3.4622290134 3082 1311867273.2668380737 0.1410231590 0.1054578401 0.2224369198 0.0063329158 0.5574730000 0.0582990000 0.0694180000 0.0000010000 0.4208320000 0.0016000000 147567971 0 402718720 3.9335317612 3.8886492252 3.4638578892 3083 1311867273.2985589504 0.1405063570 0.1054692084 0.2224369198 0.0063319900 0.5626630000 0.0587580000 0.0412320000 0.0332880000 0.4205040000 0.0016050000 147571699 0 402718720 3.9354264736 3.8900728226 3.4661707878 3084 1311867273.3308010101 0.1403592378 0.1054805216 0.2224369198 0.0063320942 0.5557660000 0.0579010000 0.0688320000 0.0000010000 0.4200610000 0.0015970000 147575315 0 402718720 3.9358918667 3.8896567822 3.4680907726 3085 1311867273.3663508892 0.1406002790 0.1054919057 0.2224369198 0.0063311260 1.0601190000 0.0704520000 0.0728540000 0.0332950000 0.4161420000 0.4599540000 147579099 0 402718720 3.9360332489 3.8894114494 3.4700016975 3086 1311867273.3992459774 0.1416920871 0.1055036361 0.2224369198 0.0063311501 0.5383440000 0.0581840000 0.0551400000 0.0000000000 0.4161010000 0.0016080000 147582771 0 402718720 3.9359774590 3.8901793957 3.4731631279 3087 1311867273.4308409691 0.1400604546 0.1055148304 0.2224369198 0.0063307060 0.5886420000 0.0585990000 0.0700370000 0.0327970000 0.4181770000 0.0016150000 147586499 0 402718720 3.9384152889 3.8915746212 3.4762704372 3088 1311867273.4663250446 0.1373508126 0.1055251400 0.2224369198 0.0063306032 0.5566330000 0.0601090000 0.0708980000 0.0000010000 0.4166410000 0.0016190000 147590227 0 402718720 3.9425857067 3.8903200626 3.4792165756 3089 1311867273.4997849464 0.1398241967 0.1055362436 0.2224369198 0.0063301602 0.9997420000 0.0596520000 0.0382670000 0.0332500000 0.4107260000 0.4505160000 147593899 0 402718720 3.9400925636 3.8907573223 3.4823262691 3090 1311867273.5318419933 0.1378095448 0.1055466880 0.2224369198 0.0063304212 0.5957180000 0.1019730000 0.0562910000 0.0000010000 0.4271500000 0.0021030000 147597627 0 402718720 3.9426267147 3.8903932571 3.4859204292 3091 1311867273.5687909126 0.1374491602 0.1055570091 0.2224369198 0.0063300474 0.6051100000 0.0771250000 0.0643220000 0.0414750000 0.4127900000 0.0016320000 147601467 0 402718720 3.9437260628 3.8923637867 3.4890639782 3092 1311867273.6000390053 0.1380921304 0.1055675315 0.2224369198 0.0063296914 0.5228050000 0.0610660000 0.0431960000 0.0000010000 0.4095470000 0.0016320000 147605027 0 402718720 3.9428570271 3.8893699646 3.4921615124 3093 1311867273.6349599361 0.1385321170 0.1055781893 0.2224369198 0.0063289953 1.0056220000 0.0630420000 0.0495800000 0.0330260000 0.4087500000 0.4437780000 147608811 0 402718720 3.9434742928 3.8888602257 3.4960429668 3094 1311867273.6673769951 0.1415249705 0.1055898075 0.2224369198 0.0063281632 0.5324140000 0.0724850000 0.0431700000 0.0000010000 0.4077490000 0.0016350000 147612539 0 402718720 3.9414916039 3.8893628120 3.5005645752 3095 1311867273.6987860203 0.1429692358 0.1056018849 0.2224369198 0.0063284534 0.5730730000 0.0746050000 0.0519860000 0.0332720000 0.4042820000 0.0016360000 147616155 0 402718720 3.9400451183 3.8884389400 3.5037846565 3096 1311867273.7346739769 0.1404747367 0.1056131487 0.2224369198 0.0063300719 0.5444640000 0.0617600000 0.0670930000 0.0000000000 0.4064520000 0.0016280000 147619939 0 402718720 3.9441001415 3.8905389309 3.5083270073 3097 1311867273.7665960789 0.1397445649 0.1056241695 0.2224369198 0.0063314431 1.0075020000 0.0752800000 0.0528550000 0.0328400000 0.4016910000 0.4374870000 147623611 0 402718720 3.9471206665 3.8907711506 3.5117838383 3098 1311867273.7990698814 0.1401678175 0.1056353198 0.2224369198 0.0063313509 0.5286970000 0.0637110000 0.0529010000 0.0000010000 0.4030300000 0.0016520000 147627339 0 402718720 3.9464437962 3.8886020184 3.5144035816 3099 1311867273.8358130455 0.1412475407 0.1056468113 0.2224369198 0.0063312161 0.5836870000 0.0646600000 0.0753270000 0.0332890000 0.4014020000 0.0016620000 147631123 0 402718720 3.9456083775 3.8875615597 3.5172626972 3100 1311867273.8668060303 0.1423695385 0.1056586574 0.2224369198 0.0063318217 0.5691350000 0.0850610000 0.0746930000 0.0000010000 0.4003470000 0.0016620000 147634795 0 402718720 3.9443004131 3.8877546787 3.5199363232 3101 1311867273.8990719318 0.1456386447 0.1056715500 0.2224369198 0.0063349732 0.9703300000 0.0636830000 0.0400360000 0.0331610000 0.3965170000 0.4295220000 147638523 0 402718720 3.9402937889 3.8870158195 3.5222921371 3102 1311867273.9384820461 0.1453448087 0.1056843396 0.2224369198 0.0063340171 0.5213280000 0.0634850000 0.0529870000 0.0000000000 0.3954790000 0.0017500000 147642363 0 402718720 3.9404644966 3.8874745369 3.5252966881 3103 1311867273.9669051170 0.1439772993 0.1056966802 0.2224369198 0.0063336149 0.5837490000 0.0641830000 0.0791380000 0.0331880000 0.3981190000 0.0016620000 147645923 0 402718720 3.9410698414 3.8882827759 3.5278031826 3104 1311867273.9996581078 0.1438423097 0.1057089694 0.2224369198 0.0063326157 0.5153100000 0.0639940000 0.0444400000 0.0000000000 0.3977770000 0.0016580000 147649651 0 402718720 3.9398148060 3.8871378899 3.5305328369 3105 1311867274.0348489285 0.1421328634 0.1057207001 0.2224369198 0.0063319435 0.9859760000 0.0768760000 0.0446550000 0.0331400000 0.3971740000 0.4267370000 147653323 0 402718720 3.9408214092 3.8883831501 3.5343785286 3106 1311867274.0670020580 0.1389682293 0.1057314044 0.2224369198 0.0063342247 0.5388530000 0.0639050000 0.0731110000 0.0000010000 0.3924730000 0.0017530000 147657051 0 402718720 3.9429135323 3.8871743679 3.5381312370 3107 1311867274.1025679111 0.1380057335 0.1057417920 0.2224369198 0.0063342208 0.5465720000 0.0647140000 0.0471330000 0.0331870000 0.3925240000 0.0016630000 147660835 0 402718720 3.9419066906 3.8852648735 3.5419156551 3108 1311867274.1350569725 0.1358131319 0.1057514675 0.2224369198 0.0063333234 0.5244400000 0.0644250000 0.0571710000 0.0000010000 0.3938130000 0.0016630000 147664563 0 402718720 3.9439167976 3.8849265575 3.5469074249 3109 1311867274.1667969227 0.1338938773 0.1057605194 0.2224369198 0.0063329955 0.9920200000 0.0752890000 0.0631400000 0.0330740000 0.3926030000 0.4204300000 147668179 0 402718720 3.9442343712 3.8836348057 3.5504133701 3110 1311867274.2008550167 0.1307365149 0.1057685503 0.2224369198 0.0063385452 0.5297360000 0.0821080000 0.0471400000 0.0000000000 0.3913890000 0.0016630000 147671851 0 402718720 3.9450712204 3.8814427853 3.5541820526 3111 1311867274.2389180660 0.1322952062 0.1057770770 0.2224369198 0.0063393778 0.5429230000 0.0649840000 0.0471650000 0.0330730000 0.3882370000 0.0017650000 147675747 0 402718720 3.9412212372 3.8797681332 3.5586624146 3112 1311867274.2668540478 0.1347901374 0.1057863999 0.2224369198 0.0063386652 0.5019310000 0.0645800000 0.0401800000 0.0000000000 0.3878150000 0.0017470000 147679307 0 402718720 3.9383883476 3.8808469772 3.5636346340 3113 1311867274.3018939495 0.1332133561 0.1057952104 0.2224369198 0.0063392034 0.9939340000 0.0756460000 0.0723720000 0.0330010000 0.3876150000 0.4178810000 147683035 0 402718720 3.9378819466 3.8788664341 3.5676860809 3114 1311867274.3358139992 0.1326971352 0.1058038494 0.2224369198 0.0063398362 0.5478930000 0.0846700000 0.0662490000 0.0000010000 0.3875200000 0.0017580000 147686763 0 402718720 3.9369072914 3.8770775795 3.5718183517 3115 1311867274.3679759502 0.1319879889 0.1058122553 0.2224369198 0.0063390307 0.5847240000 0.0750840000 0.0787020000 0.0329770000 0.3888980000 0.0016550000 147690491 0 402718720 3.9366831779 3.8768601418 3.5763776302 3116 1311867274.4007549286 0.1339925975 0.1058212990 0.2224369198 0.0063382951 0.5155760000 0.0639540000 0.0529560000 0.0000010000 0.3882900000 0.0021630000 147694107 0 402718720 3.9330708981 3.8764266968 3.5803248882 3117 1311867274.4357678890 0.1341471374 0.1058303865 0.2224369198 0.0063405623 1.0345930000 0.0818350000 0.0664470000 0.0409320000 0.4045940000 0.4324620000 147697891 0 402718720 3.9318921566 3.8746030331 3.5845224857 3118 1311867274.4689209461 0.1361054331 0.1058400963 0.2224369198 0.0063423312 0.5545730000 0.0814660000 0.0582330000 0.0000010000 0.4045200000 0.0021600000 147701619 0 402718720 3.9285507202 3.8744044304 3.5881762505 3119 1311867274.4997699261 0.1343564093 0.1058492391 0.2224369198 0.0063416057 0.6198810000 0.0811410000 0.0975990000 0.0408810000 0.3912250000 0.0016500000 147705179 0 402718720 3.9297583103 3.8721475601 3.5919575691 3120 1311867274.5345981121 0.1354673207 0.1058587321 0.2224369198 0.0063414366 0.5131450000 0.0759550000 0.0379150000 0.0000010000 0.3901700000 0.0016510000 147708907 0 402718720 3.9271786213 3.8703622818 3.5952091217 3121 1311867274.5686841011 0.1361190826 0.1058684278 0.2224369198 0.0063406132 0.9689440000 0.0766510000 0.0438150000 0.0328290000 0.3901750000 0.4179040000 147712579 0 402718720 3.9256389141 3.8680520058 3.5994026661 3122 1311867274.6001191139 0.1363136768 0.1058781796 0.2224369198 0.0063405359 0.5358990000 0.0632500000 0.0736310000 0.0000000000 0.3899890000 0.0016380000 147716251 0 402718720 3.9252989292 3.8689236641 3.6022524834 3123 1311867274.6349270344 0.1360939741 0.1058878549 0.2224369198 0.0063409036 0.5448320000 0.0639830000 0.0524240000 0.0328540000 0.3860960000 0.0017290000 147720035 0 402718720 3.9239032269 3.8661382198 3.6051678658 3124 1311867274.6665649414 0.1369243711 0.1058977897 0.2224369198 0.0063422907 0.5121390000 0.0644250000 0.0525370000 0.0000010000 0.3860420000 0.0016410000 147723651 0 402718720 3.9229822159 3.8654041290 3.6086671352 3125 1311867274.6988699436 0.1378781497 0.1059080234 0.2224369198 0.0063415686 0.9551730000 0.0736230000 0.0393370000 0.0327700000 0.3851680000 0.4167170000 147727379 0 402718720 3.9212059975 3.8662843704 3.6116745472 3126 1311867274.7355759144 0.1366519630 0.1059178584 0.2224369198 0.0063449154 0.4954760000 0.0623750000 0.0392030000 0.0000010000 0.3844770000 0.0017240000 147731107 0 402718720 3.9211218357 3.8646650314 3.6146245003 3127 1311867274.7669000626 0.1375040114 0.1059279595 0.2224369198 0.0063440236 0.5410010000 0.0629230000 0.0520490000 0.0323260000 0.3846380000 0.0016250000 147734779 0 402718720 3.9196226597 3.8635430336 3.6183669567 3128 1311867274.8040020466 0.1378254145 0.1059381569 0.2224369198 0.0063437157 0.5303510000 0.0613050000 0.0722060000 0.0000000000 0.3877590000 0.0016140000 147738619 0 402718720 3.9178202152 3.8640549183 3.6213552952 3129 1311867274.8350889683 0.1384713054 0.1059485542 0.2224369198 0.0063436982 0.9612470000 0.0740530000 0.0428210000 0.0326120000 0.3879380000 0.4162890000 147742291 0 402718720 3.9162721634 3.8633770943 3.6248936653 3130 1311867274.8671360016 0.1391226500 0.1059591529 0.2224369198 0.0063429042 0.5565470000 0.0868860000 0.0725420000 0.0000010000 0.3879770000 0.0016140000 147745963 0 402718720 3.9144370556 3.8633935452 3.6284244061 3131 1311867274.9044289589 0.1398158371 0.1059699663 0.2224369198 0.0063419357 0.5329190000 0.0614620000 0.0451790000 0.0326170000 0.3845350000 0.0016170000 147749747 0 402718720 3.9128923416 3.8637592793 3.6323642731 3132 1311867274.9350550175 0.1405091882 0.1059809941 0.2224369198 0.0063414425 0.5155700000 0.0780130000 0.0433220000 0.0000000000 0.3850930000 0.0016120000 147753419 0 402718720 3.9114067554 3.8646888733 3.6361629963 3133 1311867274.9666490555 0.1388348192 0.1059914805 0.2224369198 0.0063408277 0.9702360000 0.0620540000 0.0700150000 0.0321670000 0.3836960000 0.4147830000 147757035 0 402718720 3.9122781754 3.8634009361 3.6396446228 3134 1311867275.0030829906 0.1403723955 0.1060024508 0.2224369198 0.0063413895 0.5078590000 0.0619770000 0.0488190000 0.0000010000 0.3878150000 0.0016210000 147760875 0 402718720 3.9093437195 3.8612484932 3.6442108154 3135 1311867275.0368080139 0.1415913552 0.1060138029 0.2224369198 0.0063461173 0.5342330000 0.0619390000 0.0426230000 0.0325170000 0.3881090000 0.0016190000 147764547 0 402718720 3.9072740078 3.8633203506 3.6482028961 3136 1311867275.0664451122 0.1407235116 0.1060248711 0.2224369198 0.0063475478 0.5126440000 0.0731040000 0.0426530000 0.0000010000 0.3877120000 0.0016130000 147768163 0 402718720 3.9075305462 3.8624413013 3.6522040367 3137 1311867275.1023271084 0.1402280629 0.1060357742 0.2224369198 0.0063476753 0.9411990000 0.0616460000 0.0368670000 0.0324540000 0.3875680000 0.4150870000 147771947 0 402718720 3.9065685272 3.8599381447 3.6561598778 3138 1311867275.1351230145 0.1408677846 0.1060468743 0.2224369198 0.0063469654 0.5317460000 0.0615760000 0.0759850000 0.0000000000 0.3849940000 0.0016140000 147775619 0 402718720 3.9050617218 3.8592278957 3.6600241661 3139 1311867275.1667180061 0.1411239505 0.1060580489 0.2224369198 0.0063459762 0.5286020000 0.0620130000 0.0366410000 0.0324890000 0.3884110000 0.0016140000 147779291 0 402718720 3.9042279720 3.8588283062 3.6640985012 3140 1311867275.2041749954 0.1421090364 0.1060695301 0.2224369198 0.0063463516 0.5125120000 0.0613920000 0.0539650000 0.0000010000 0.3879460000 0.0016140000 147783131 0 402718720 3.9016156197 3.8586196899 3.6678364277 3141 1311867275.2371780872 0.1424815655 0.1060811226 0.2224369198 0.0063455569 0.9663100000 0.0744690000 0.0510270000 0.0324650000 0.3860080000 0.4147940000 147786859 0 402718720 3.9006729126 3.8577971458 3.6714918613 3142 1311867275.2668180466 0.1429103613 0.1060928442 0.2224369198 0.0063470897 0.5303270000 0.0615720000 0.0759990000 0.0000010000 0.3832470000 0.0017070000 147790419 0 402718720 3.9003949165 3.8593990803 3.6752200127 3143 1311867275.3026800156 0.1420756727 0.1061042928 0.2224369198 0.0063485502 0.5311870000 0.0623770000 0.0453250000 0.0324260000 0.3815710000 0.0017110000 147794203 0 402718720 3.9000799656 3.8592767715 3.6787548065 3144 1311867275.3351879120 0.1418423802 0.1061156598 0.2224369198 0.0063482728 0.5123360000 0.0629420000 0.0580070000 0.0000010000 0.3822550000 0.0016210000 147797875 0 402718720 3.8995602131 3.8591167927 3.6833055019 3145 1311867275.3669109344 0.1402113736 0.1061265011 0.2224369198 0.0063502446 0.9911630000 0.0837400000 0.0768710000 0.0324080000 0.3828320000 0.4077690000 147801547 0 402718720 3.9000329971 3.8571867943 3.6874227524 3146 1311867275.4038369656 0.1406037658 0.1061374602 0.2224369198 0.0063506470 0.5148060000 0.0629350000 0.0648330000 0.0000000000 0.3774750000 0.0017270000 147805275 0 402718720 3.8986239433 3.8584318161 3.6916465759 3147 1311867275.4349598885 0.1397740394 0.1061481486 0.2224369198 0.0063511350 0.5479920000 0.0643000000 0.0635310000 0.0319780000 0.3790440000 0.0016340000 147808947 0 402718720 3.8986063004 3.8562483788 3.6952188015 3148 1311867275.4669399261 0.1403072476 0.1061589997 0.2224369198 0.0063502536 0.5239770000 0.0634310000 0.0734160000 0.0000010000 0.3779720000 0.0016250000 147812563 0 402718720 3.8963277340 3.8557255268 3.6991264820 3149 1311867275.5037291050 0.1396194398 0.1061696254 0.2224369198 0.0063495942 0.9290910000 0.0637600000 0.0497520000 0.0323950000 0.3764680000 0.3991540000 147816403 0 402718720 3.8953664303 3.8566625118 3.7029674053 3150 1311867275.5353329182 0.1373304129 0.1061795177 0.2224369198 0.0063503032 0.5394310000 0.0956970000 0.0500070000 0.0000010000 0.3832070000 0.0021210000 147820075 0 402718720 3.8967504501 3.8551783562 3.7069013119 3151 1311867275.5668909550 0.1384384185 0.1061897554 0.2224369198 0.0063524459 0.5789000000 0.0815540000 0.0580080000 0.0405060000 0.3884090000 0.0021250000 147823691 0 402718720 3.8938474655 3.8539767265 3.7101254463 3152 1311867275.6028299332 0.1371081173 0.1061995645 0.2224369198 0.0063529134 0.5165140000 0.0813880000 0.0499340000 0.0000010000 0.3760570000 0.0016320000 147827531 0 402718720 3.8934600353 3.8534591198 3.7139868736 3153 1311867275.6383280754 0.1365357935 0.1062091859 0.2224369198 0.0063529440 0.9171110000 0.0650390000 0.0466220000 0.0323940000 0.3705960000 0.3948010000 147831315 0 402718720 3.8923261166 3.8528296947 3.7175557613 3154 1311867275.6682209969 0.1367862672 0.1062188806 0.2224369198 0.0063524464 0.4842140000 0.0640270000 0.0378060000 0.0000010000 0.3731030000 0.0016260000 147834875 0 402718720 3.8903234005 3.8510832787 3.7208137512 3155 1311867275.7045888901 0.1379767060 0.1062289465 0.2224369198 0.0063515435 0.5352070000 0.0770330000 0.0463070000 0.0322970000 0.3701030000 0.0017320000 147838659 0 402718720 3.8872678280 3.8506848812 3.7239930630 3156 1311867275.7349820137 0.1368918419 0.1062386622 0.2224369198 0.0063507451 0.5198360000 0.0638970000 0.0764810000 0.0000010000 0.3702550000 0.0016220000 147842219 0 402718720 3.8873054981 3.8505945206 3.7271924019 3157 1311867275.7792279720 0.1356974542 0.1062479935 0.2224369198 0.0063508771 0.9387840000 0.0645250000 0.0679230000 0.0318390000 0.3730980000 0.3938120000 147846339 0 402718720 3.8858649731 3.8494729996 3.7301549911 3158 1311867275.8028490543 0.1369265318 0.1062577080 0.2224369198 0.0063507774 0.5201700000 0.0642000000 0.0737610000 0.0000010000 0.3730210000 0.0016280000 147849731 0 402718720 3.8837215900 3.8490459919 3.7335062027 3159 1311867275.8355960846 0.1357062012 0.1062670301 0.2224369198 0.0063509800 0.5227680000 0.0651010000 0.0464100000 0.0323170000 0.3692900000 0.0016380000 147853347 0 402718720 3.8837659359 3.8499214649 3.7367784977 3160 1311867275.8701560497 0.1350806803 0.1062761484 0.2224369198 0.0063500809 0.5093600000 0.0793670000 0.0529240000 0.0000010000 0.3675280000 0.0017260000 147857131 0 402718720 3.8827040195 3.8496875763 3.7401218414 3161 1311867275.9032120705 0.1358188838 0.1062854944 0.2224369198 0.0063492277 0.9107720000 0.0647700000 0.0530400000 0.0322100000 0.3666500000 0.3863120000 147860859 0 402718720 3.8797261715 3.8482601643 3.7433304787 3162 1311867275.9371318817 0.1352590621 0.1062946574 0.2224369198 0.0063483072 0.4932740000 0.0646050000 0.0527980000 0.0000000000 0.3666520000 0.0016300000 147864587 0 402718720 3.8783316612 3.8478140831 3.7465567589 3163 1311867275.9683859348 0.1338376105 0.1063033653 0.2224369198 0.0063477751 0.5514590000 0.0646170000 0.0788080000 0.0321990000 0.3666280000 0.0016390000 147868259 0 402718720 3.8788568974 3.8490617275 3.7498252392 3164 1311867276.0048470497 0.1332988739 0.1063118974 0.2224369198 0.0063493275 0.4816410000 0.0663010000 0.0384950000 0.0000010000 0.3676010000 0.0016330000 147872043 0 402718720 3.8771774769 3.8486146927 3.7527077198 3165 1311867276.0387539864 0.1324138194 0.1063201444 0.2224369198 0.0063498242 0.9566710000 0.0897800000 0.0751800000 0.0321690000 0.3668650000 0.3850510000 147875771 0 402718720 3.8760161400 3.8467543125 3.7562689781 3166 1311867276.0739030838 0.1323822588 0.1063283763 0.2224369198 0.0063511347 0.5361630000 0.0692640000 0.0917450000 0.0000000000 0.3658670000 0.0016440000 147879555 0 402718720 3.8752629757 3.8477549553 3.7595796585 3167 1311867276.1051371098 0.1312468648 0.1063362445 0.2224369198 0.0063523365 0.5221780000 0.0659870000 0.0536550000 0.0317370000 0.3612470000 0.0017390000 147883227 0 402718720 3.8754274845 3.8471536636 3.7626619339 3168 1311867276.1382379532 0.1319870055 0.1063443413 0.2224369198 0.0063533678 0.5029300000 0.0854790000 0.0472480000 0.0000010000 0.3606570000 0.0017270000 147886843 0 402718720 3.8733379841 3.8447868824 3.7659847736 3169 1311867276.1709389687 0.1315090507 0.1063522822 0.2224369198 0.0063551995 0.8888540000 0.0661270000 0.0405130000 0.0321280000 0.3613180000 0.3811780000 147890515 0 402718720 3.8731219769 3.8448898792 3.7693562508 3170 1311867276.2042279243 0.1326487362 0.1063605776 0.2224369198 0.0063546138 0.5438590000 0.0930530000 0.0802480000 0.0000010000 0.3609440000 0.0017390000 147894299 0 402718720 3.8714044094 3.8460528851 3.7725331783 3171 1311867276.2357859612 0.1320828050 0.1063686893 0.2224369198 0.0063537043 0.5317460000 0.0663260000 0.0605570000 0.0321370000 0.3635310000 0.0016500000 147897915 0 402718720 3.8717544079 3.8461539745 3.7759213448 3172 1311867276.2747719288 0.1325075924 0.1063769298 0.2224369198 0.0063531192 0.4838210000 0.0667720000 0.0452750000 0.0000010000 0.3625200000 0.0016390000 147901811 0 402718720 3.8700437546 3.8465030193 3.7789108753 3173 1311867276.3027520180 0.1321711987 0.1063850591 0.2224369198 0.0063531548 0.8937470000 0.0672920000 0.0479950000 0.0321450000 0.3612630000 0.3774260000 147905315 0 402718720 3.8709380627 3.8455524445 3.7818045616 3174 1311867276.3387188911 0.1309444755 0.1063927968 0.2224369198 0.0063528874 0.4957250000 0.0668020000 0.0612700000 0.0000010000 0.3584170000 0.0016460000 147909099 0 402718720 3.8708257675 3.8448686600 3.7842760086 3175 1311867276.3729600906 0.1327766925 0.1064011067 0.2224369198 0.0063519292 0.5574430000 0.0779250000 0.0814630000 0.0320330000 0.3567710000 0.0016540000 147912827 0 402718720 3.8675141335 3.8437314034 3.7869472504 3176 1311867276.4031929970 0.1321898103 0.1064092266 0.2224369198 0.0063526579 0.5161690000 0.0678410000 0.0815820000 0.0000010000 0.3574930000 0.0016560000 147916443 0 402718720 3.8672933578 3.8429913521 3.7888178825 3177 1311867276.4360129833 0.1324688196 0.1064174291 0.2224369198 0.0063528225 0.9003170000 0.0855640000 0.0463120000 0.0320720000 0.3561590000 0.3725700000 147920115 0 402718720 3.8655171394 3.8419122696 3.7913255692 3178 1311867276.4737091064 0.1314996630 0.1064253216 0.2224369198 0.0063537387 0.5019220000 0.0680360000 0.0680670000 0.0000000000 0.3564910000 0.0016500000 147924011 0 402718720 3.8655679226 3.8409140110 3.7938988209 3179 1311867276.5048420429 0.1320705712 0.1064333887 0.2224369198 0.0063531110 0.5444220000 0.0673260000 0.0767130000 0.0319960000 0.3591610000 0.0016430000 147927627 0 402718720 3.8642394543 3.8420686722 3.7962369919 3180 1311867276.5387470722 0.1308153123 0.1064410560 0.2224369198 0.0063523630 0.5180030000 0.0845710000 0.0681660000 0.0000010000 0.3556800000 0.0017540000 147931355 0 402718720 3.8654251099 3.8418471813 3.7983179092 3181 1311867276.5746779442 0.1313470900 0.1064488856 0.2224369198 0.0063514589 0.9121040000 0.0674890000 0.0798560000 0.0316150000 0.3550390000 0.3704480000 147935139 0 402718720 3.8639039993 3.8421654701 3.8010730743 3182 1311867276.6041920185 0.1317242086 0.1064568288 0.2224369198 0.0063505114 0.5069560000 0.0678510000 0.0613890000 0.0000010000 0.3670880000 0.0021830000 147938643 0 402718720 3.8629715443 3.8434133530 3.8034255505 3183 1311867276.6361470222 0.1314000636 0.1064646652 0.2224369198 0.0063495941 0.5740390000 0.0860390000 0.0692100000 0.0393590000 0.3688550000 0.0021790000 147942259 0 402718720 3.8626525402 3.8420500755 3.8058359623 3184 1311867276.6710920334 0.1315591186 0.1064725466 0.2224369198 0.0063491191 0.5135000000 0.0860600000 0.0636520000 0.0000010000 0.3544880000 0.0016490000 147946043 0 402718720 3.8612997532 3.8416094780 3.8087148666 3185 1311867276.7029719353 0.1315430999 0.1064804181 0.2224369198 0.0063503610 0.9170600000 0.0905150000 0.0689560000 0.0320550000 0.3513540000 0.3664560000 147949715 0 402718720 3.8619036674 3.8415579796 3.8114235401 3186 1311867276.7360780239 0.1314334124 0.1064882501 0.2224369198 0.0063495797 0.4770960000 0.0691210000 0.0486730000 0.0000000000 0.3495970000 0.0017660000 147953387 0 402718720 3.8600246906 3.8399512768 3.8136205673 3187 1311867276.7721960545 0.1291618198 0.1064953645 0.2224369198 0.0063544726 0.5420150000 0.0685630000 0.0821310000 0.0319240000 0.3497430000 0.0017410000 147957227 0 402718720 3.8607847691 3.8388931751 3.8159706593 3188 1311867276.8029088974 0.1318735927 0.1065033251 0.2224369198 0.0063632311 0.4766360000 0.0690690000 0.0481620000 0.0000010000 0.3500490000 0.0016620000 147960843 0 402718720 3.8576445580 3.8398005962 3.8178608418 3189 1311867276.8375699520 0.1306540072 0.1065108982 0.2224369198 0.0063646486 0.9030990000 0.0690120000 0.0780130000 0.0319620000 0.3518940000 0.3645320000 147964571 0 402718720 3.8575878143 3.8388648033 3.8194818497 3190 1311867276.8740971088 0.1301441789 0.1065183067 0.2224369198 0.0063643222 0.4970130000 0.0811120000 0.0555390000 0.0000010000 0.3510730000 0.0016720000 147968411 0 402718720 3.8571476936 3.8376238346 3.8214964867 3191 1311867276.9029750824 0.1308338046 0.1065259268 0.2224369198 0.0063653932 0.5076920000 0.0695620000 0.0470100000 0.0315920000 0.3502390000 0.0016670000 147971971 0 402718720 3.8561823368 3.8390333652 3.8235447407 3192 1311867276.9374980927 0.1299486160 0.1065332647 0.2224369198 0.0063676221 0.5016300000 0.0688500000 0.0715820000 0.0000010000 0.3518630000 0.0016620000 147975699 0 402718720 3.8552389145 3.8379983902 3.8254821301 3193 1311867276.9726910591 0.1284367889 0.1065401246 0.2224369198 0.0063673725 0.8889330000 0.0689820000 0.0636860000 0.0319140000 0.3522070000 0.3644460000 147979483 0 402718720 3.8560414314 3.8367669582 3.8281764984 3194 1311867277.0050029755 0.1288079768 0.1065470963 0.2224369198 0.0063676972 0.4946350000 0.0806450000 0.0526420000 0.0000000000 0.3519700000 0.0016640000 147983211 0 402718720 3.8548417091 3.8383405209 3.8307664394 3195 1311867277.0356070995 0.1284214854 0.1065539428 0.2224369198 0.0063667101 0.5294360000 0.0841740000 0.0556440000 0.0320130000 0.3479460000 0.0017570000 147986827 0 402718720 3.8551788330 3.8396310806 3.8338680267 3196 1311867277.0711610317 0.1266884655 0.1065602427 0.2224369198 0.0063659402 0.4893960000 0.0844340000 0.0488240000 0.0000010000 0.3464770000 0.0017690000 147990555 0 402718720 3.8560540676 3.8388216496 3.8364129066 3197 1311867277.1039769650 0.1268226057 0.1065665806 0.2224369198 0.0063656622 0.8989130000 0.0692840000 0.0824570000 0.0319350000 0.3474290000 0.3600750000 147994283 0 402718720 3.8550415039 3.8371193409 3.8396406174 3198 1311867277.1350269318 0.1262098700 0.1065727230 0.2224369198 0.0063662695 0.4866190000 0.0700720000 0.0597270000 0.0000010000 0.3474150000 0.0016740000 147997843 0 402718720 3.8557329178 3.8386728764 3.8428068161 3199 1311867277.1708490849 0.1258934736 0.1065787626 0.2224369198 0.0063660842 0.5385040000 0.0704580000 0.0839650000 0.0318970000 0.3424720000 0.0017770000 148001627 0 402718720 3.8553037643 3.8401386738 3.8460226059 3200 1311867277.2029759884 0.1252268255 0.1065845901 0.2224369198 0.0063656082 0.5220220000 0.0904250000 0.0797530000 0.0000000000 0.3424160000 0.0016840000 148005355 0 402718720 3.8552536964 3.8394513130 3.8490371704 3201 1311867277.2351000309 0.1249471977 0.1065903267 0.2224369198 0.0063649037 0.8576220000 0.0707120000 0.0565100000 0.0318650000 0.3392640000 0.3515540000 148009027 0 402718720 3.8549137115 3.8378014565 3.8519334793 3202 1311867277.2733149529 0.1244423613 0.1065959019 0.2224369198 0.0063643281 0.5028320000 0.0704540000 0.0840650000 0.0000010000 0.3386190000 0.0017670000 148012923 0 402718720 3.8543758392 3.8385109901 3.8550109863 3203 1311867277.3063778877 0.1239873767 0.1066013317 0.2224369198 0.0063633700 0.5074940000 0.0713470000 0.0567560000 0.0318950000 0.3382240000 0.0016850000 148016595 0 402718720 3.8545680046 3.8391144276 3.8580303192 3204 1311867277.3396029472 0.1238122284 0.1066067034 0.2224369198 0.0063625297 0.4809440000 0.0714210000 0.0608820000 0.0000010000 0.3392370000 0.0016900000 148020323 0 402718720 3.8543760777 3.8401262760 3.8608410358 3205 1311867277.3773889542 0.1225884855 0.1066116899 0.2224369198 0.0063624662 0.8570260000 0.0841660000 0.0475420000 0.0317800000 0.3382310000 0.3476060000 148024107 0 402718720 3.8549997807 3.8390076160 3.8637654781 3206 1311867277.4055531025 0.1249902099 0.1066174224 0.2224369198 0.0063616320 0.4752340000 0.0715050000 0.0572880000 0.0000010000 0.3367190000 0.0017880000 148027611 0 402718720 3.8520915508 3.8381676674 3.8666560650 3207 1311867277.4425079823 0.1256642640 0.1066233616 0.2224369198 0.0063617513 0.5079710000 0.0715380000 0.0570820000 0.0318680000 0.3377330000 0.0017940000 148031395 0 402718720 3.8505141735 3.8394751549 3.8695588112 3208 1311867277.4723749161 0.1259520352 0.1066293867 0.2224369198 0.0063691944 0.5167740000 0.0835140000 0.0847700000 0.0000010000 0.3390320000 0.0017000000 148035011 0 402718720 3.8514807224 3.8415269852 3.8726146221 3209 1311867277.5057780743 0.1246740744 0.1066350099 0.2224369198 0.0063719985 0.8560460000 0.0707670000 0.0604400000 0.0313050000 0.3383430000 0.3473640000 148038627 0 402718720 3.8511695862 3.8402724266 3.8751115799 3210 1311867277.5401940346 0.1240449771 0.1066404335 0.2224369198 0.0063781889 0.4937150000 0.0911830000 0.0542370000 0.0000010000 0.3388690000 0.0016880000 148042411 0 402718720 3.8502228260 3.8381090164 3.8779172897 3211 1311867277.5715351105 0.1242760345 0.1066459258 0.2224369198 0.0063815783 0.5242200000 0.0837520000 0.0600750000 0.0317400000 0.3392980000 0.0016900000 148046083 0 402718720 3.8503077030 3.8389332294 3.8801193237 3212 1311867277.6027710438 0.1242250577 0.1066513987 0.2224369198 0.0063811008 0.4854920000 0.0705180000 0.0665800000 0.0000010000 0.3389280000 0.0016850000 148049699 0 402718720 3.8507564068 3.8386754990 3.8825314045 3213 1311867277.6416130066 0.1234955564 0.1066566412 0.2224369198 0.0063835028 0.8639800000 0.0836310000 0.0536720000 0.0316810000 0.3392800000 0.3479250000 148053539 0 402718720 3.8504931927 3.8357889652 3.8845536709 3214 1311867277.6713008881 0.1237290129 0.1066619531 0.2224369198 0.0063829571 0.5015510000 0.0712220000 0.0796780000 0.0000010000 0.3412680000 0.0016780000 148057211 0 402718720 3.8506624699 3.8353083134 3.8868608475 3215 1311867277.7063589096 0.1283865720 0.1066687104 0.2224369198 0.0063858918 0.5153290000 0.0854340000 0.0404170000 0.0316600000 0.3484390000 0.0016900000 148060883 0 402718720 3.8451552391 3.8387877941 3.8888905048 3216 1311867277.7401409149 0.1276778132 0.1066752431 0.2224369198 0.0063851776 0.4606440000 0.0708340000 0.0425880000 0.0000000000 0.3378010000 0.0016850000 148064611 0 402718720 3.8457896709 3.8395965099 3.8915328979 3217 1311867277.7720079422 0.1275746673 0.1066817396 0.2224369198 0.0063842047 0.8764260000 0.0710960000 0.0796100000 0.0316560000 0.3389210000 0.3473400000 148068283 0 402718720 3.8460469246 3.8392250538 3.8943977356 3218 1311867277.8036880493 0.1271057576 0.1066880864 0.2224369198 0.0063837585 0.4841940000 0.0711310000 0.0537510000 0.0000000000 0.3485690000 0.0022230000 148071955 0 402718720 3.8469676971 3.8397176266 3.8976075649 3219 1311867277.8400499821 0.1263148785 0.1066941836 0.2224369198 0.0063828038 0.5619640000 0.0902220000 0.0718390000 0.0392320000 0.3499050000 0.0022410000 148075739 0 402718720 3.8483240604 3.8400037289 3.9009866714 3220 1311867277.8711171150 0.1264413595 0.1067003163 0.2224369198 0.0063830208 0.5389470000 0.0896060000 0.0886530000 0.0000010000 0.3499130000 0.0022380000 148079411 0 402718720 3.8478937149 3.8376369476 3.9045557976 3221 1311867277.9031610489 0.1266214550 0.1067065010 0.2224369198 0.0063820723 0.9024360000 0.0899580000 0.0800720000 0.0386500000 0.3408790000 0.3451350000 148083083 0 402718720 3.8481175900 3.8372592926 3.9078352451 3222 1311867277.9393019676 0.1267544925 0.1067127232 0.2224369198 0.0063827947 0.4731950000 0.0718760000 0.0543490000 0.0000010000 0.3375290000 0.0016900000 148086867 0 402718720 3.8491113186 3.8388416767 3.9118044376 3223 1311867277.9714229107 0.1273196787 0.1067191170 0.2224369198 0.0063836497 0.4978530000 0.0723380000 0.0477550000 0.0311250000 0.3371910000 0.0017100000 148090539 0 402718720 3.8488605022 3.8382179737 3.9150421619 3224 1311867278.0041360855 0.1270392239 0.1067254197 0.2224369198 0.0063827831 0.4674130000 0.0716420000 0.0501420000 0.0000010000 0.3358980000 0.0018010000 148094211 0 402718720 3.8500537872 3.8366148472 3.9184200764 3225 1311867278.0394210815 0.1276132762 0.1067318966 0.2224369198 0.0063832196 0.8897960000 0.0837550000 0.0804240000 0.0311320000 0.3393870000 0.3473270000 148097939 0 402718720 3.8503801823 3.8359920979 3.9216732979 3226 1311867278.0712630749 0.1281174272 0.1067385257 0.2224369198 0.0063829827 0.5034550000 0.0712750000 0.0838450000 0.0000010000 0.3388230000 0.0016900000 148101611 0 402718720 3.8510680199 3.8372585773 3.9251246452 3227 1311867278.1056289673 0.1289618760 0.1067454124 0.2224369198 0.0063820618 0.5064520000 0.0705780000 0.0533000000 0.0314950000 0.3416180000 0.0016880000 148105395 0 402718720 3.8510351181 3.8375940323 3.9286191463 3228 1311867278.1391980648 0.1284164637 0.1067521258 0.2224369198 0.0063811376 0.4694840000 0.0695610000 0.0472100000 0.0000010000 0.3433270000 0.0016780000 148109067 0 402718720 3.8523404598 3.8363296986 3.9323592186 3229 1311867278.1710369587 0.1283465773 0.1067588135 0.2224369198 0.0063802509 0.8506930000 0.0697790000 0.0462230000 0.0314560000 0.3436770000 0.3517680000 148112739 0 402718720 3.8532176018 3.8369946480 3.9363868237 3230 1311867278.2038609982 0.1282669008 0.1067654724 0.2224369198 0.0063814483 0.4884610000 0.0947130000 0.0399340000 0.0000010000 0.3442900000 0.0016760000 148116467 0 402718720 3.8545496464 3.8379559517 3.9399490356 3231 1311867278.2388060093 0.1283390969 0.1067721494 0.2224369198 0.0063852672 0.5353310000 0.0692900000 0.0819490000 0.0314380000 0.3432560000 0.0016750000 148120251 0 402718720 3.8538713455 3.8373699188 3.9433488846 3232 1311867278.2707629204 0.1283815950 0.1067788355 0.2224369198 0.0063863813 0.5042960000 0.0692790000 0.0818360000 0.0000010000 0.3433770000 0.0017610000 148123867 0 402718720 3.8547182083 3.8374519348 3.9467241764 3233 1311867278.3027629852 0.1271652579 0.1067851413 0.2224369198 0.0063859914 0.8849340000 0.0686600000 0.0809570000 0.0313750000 0.3436610000 0.3522870000 148127539 0 402718720 3.8570089340 3.8389422894 3.9500062466 3234 1311867278.3421599865 0.1274108142 0.1067915190 0.2224369198 0.0063854684 0.4904230000 0.0685090000 0.0679480000 0.0000010000 0.3445420000 0.0016550000 148131435 0 402718720 3.8565089703 3.8377463818 3.9531288147 3235 1311867278.3714361191 0.1276239604 0.1067979587 0.2224369198 0.0063845259 0.5466320000 0.0798690000 0.0772690000 0.0313590000 0.3486320000 0.0016720000 148134995 0 402718720 3.8564915657 3.8362600803 3.9561235905 3236 1311867278.4035348892 0.1272323728 0.1068042734 0.2224369198 0.0063837487 0.4731630000 0.0687720000 0.0479080000 0.0000000000 0.3470210000 0.0016700000 148138723 0 402718720 3.8580348492 3.8382284641 3.9594876766 3237 1311867278.4391169548 0.1263278723 0.1068103048 0.2224369198 0.0063830474 0.8665500000 0.0674790000 0.0511400000 0.0308210000 0.3504270000 0.3588360000 148142451 0 402718720 3.8590893745 3.8385670185 3.9624423981 3238 1311867278.4713339806 0.1249446273 0.1068159053 0.2224369198 0.0063830214 0.4738610000 0.0677190000 0.0449750000 0.0000010000 0.3516960000 0.0016490000 148146179 0 402718720 3.8603024483 3.8363738060 3.9650273323 3239 1311867278.5041239262 0.1238660440 0.1068211693 0.2224369198 0.0063826475 0.5382880000 0.0676740000 0.0784590000 0.0313090000 0.3510790000 0.0017570000 148149851 0 402718720 3.8612689972 3.8349218369 3.9678492546 3240 1311867278.5423910618 0.1229708418 0.1068261538 0.2224369198 0.0063817971 0.5052920000 0.0890430000 0.0528980000 0.0000010000 0.3535850000 0.0017430000 148153691 0 402718720 3.8625164032 3.8353519440 3.9711239338 3241 1311867278.5710260868 0.1222004145 0.1068308974 0.2224369198 0.0063812150 0.8853870000 0.0655050000 0.0587940000 0.0312800000 0.3548270000 0.3670340000 148157251 0 402718720 3.8645043373 3.8371860981 3.9743814468 3242 1311867278.6069030762 0.1221623570 0.1068356265 0.2224369198 0.0063804634 0.5068730000 0.0648210000 0.0732820000 0.0000010000 0.3592680000 0.0016220000 148161035 0 402718720 3.8642368317 3.8363208771 3.9775245190 3243 1311867278.6393239498 0.1225841716 0.1068404826 0.2224369198 0.0063797658 0.5155050000 0.0653360000 0.0495560000 0.0306850000 0.3604790000 0.0016340000 148164707 0 402718720 3.8637561798 3.8357360363 3.9807946682 3244 1311867278.6709709167 0.1230424270 0.1068454771 0.2224369198 0.0063828923 0.4775400000 0.0643560000 0.0430530000 0.0000010000 0.3607130000 0.0016290000 148168435 0 402718720 3.8637974262 3.8373384476 3.9841718674 3245 1311867278.7069129944 0.1203560010 0.1068496405 0.2224369198 0.0063824589 0.9211070000 0.0773780000 0.0773310000 0.0312250000 0.3594400000 0.3677660000 148172163 0 402718720 3.8678748608 3.8372528553 3.9875721931 3246 1311867278.7390680313 0.1208142489 0.1068539426 0.2224369198 0.0063821320 0.4741320000 0.0647090000 0.0440880000 0.0000010000 0.3555650000 0.0017200000 148175835 0 402718720 3.8670289516 3.8357419968 3.9905674458 3247 1311867278.7718300819 0.1215539873 0.1068584699 0.2224369198 0.0063819579 0.5242450000 0.0763000000 0.0503330000 0.0311670000 0.3570790000 0.0016270000 148179507 0 402718720 3.8663892746 3.8349664211 3.9935300350 3248 1311867278.8068239689 0.1210940480 0.1068628528 0.2224369198 0.0063812239 0.4960700000 0.0647370000 0.0612110000 0.0000000000 0.3606650000 0.0016200000 148183291 0 402718720 3.8680663109 3.8377766609 3.9967327118 3249 1311867278.8386530876 0.1200584918 0.1068669142 0.2224369198 0.0063817611 0.8786840000 0.0642620000 0.0491260000 0.0310880000 0.3593380000 0.3669540000 148187019 0 402718720 3.8697907925 3.8355247974 3.9996550083 3250 1311867278.8741700649 0.1201964468 0.1068710156 0.2224369198 0.0063811761 0.5237630000 0.0801370000 0.0774700000 0.0000010000 0.3566240000 0.0016260000 148190747 0 402718720 3.8690569401 3.8335142136 4.0024542809 3251 1311867278.9090650082 0.1210597157 0.1068753800 0.2224369198 0.0063816596 0.5031520000 0.0642950000 0.0370910000 0.0310410000 0.3612020000 0.0016280000 148194475 0 402718720 3.8690452576 3.8365657330 4.0057497025 3252 1311867278.9392769337 0.1206735373 0.1068796230 0.2224369198 0.0063818786 0.5063270000 0.0648770000 0.0735220000 0.0000000000 0.3584460000 0.0016220000 148198147 0 402718720 3.8703465462 3.8390548229 4.0086698532 3253 1311867278.9711430073 0.1203963310 0.1068837782 0.2224369198 0.0063813325 0.8919970000 0.0655080000 0.0678220000 0.0310320000 0.3565020000 0.3632070000 148201819 0 402718720 3.8698041439 3.8360602856 4.0113496780 3254 1311867279.0073111057 0.1194197983 0.1068876307 0.2224369198 0.0063825683 0.5066730000 0.0660350000 0.0736850000 0.0000010000 0.3574390000 0.0016220000 148205603 0 402718720 3.8702569008 3.8344914913 4.0142655373 3255 1311867279.0397729874 0.1178154126 0.1068909879 0.2224369198 0.0063828080 0.5356490000 0.0895080000 0.0525690000 0.0305480000 0.3531670000 0.0017300000 148209275 0 402718720 3.8732349873 3.8366405964 4.0175609589 3256 1311867279.0738539696 0.1186372638 0.1068945955 0.2224369198 0.0063820266 0.4873120000 0.0795680000 0.0463530000 0.0000010000 0.3518540000 0.0016340000 148213003 0 402718720 3.8718173504 3.8370990753 4.0205492973 3257 1311867279.1068439484 0.1185575724 0.1068981764 0.2224369198 0.0063813710 0.8641840000 0.0661110000 0.0437890000 0.0309970000 0.3546610000 0.3607220000 148216675 0 402718720 3.8716499805 3.8350634575 4.0233373642 3258 1311867279.1392490864 0.1183059290 0.1069016778 0.2224369198 0.0063808342 0.4916960000 0.0659240000 0.0617830000 0.0000010000 0.3544530000 0.0016250000 148220403 0 402718720 3.8716621399 3.8361296654 4.0263819695 3259 1311867279.1712040901 0.1168849319 0.1069047411 0.2224369198 0.0063861483 0.5160040000 0.0664920000 0.0562960000 0.0305560000 0.3531970000 0.0016390000 148224019 0 402718720 3.8747031689 3.8387243748 4.0292859077 3260 1311867279.2070438862 0.1171942651 0.1069078974 0.2224369198 0.0063867185 0.4947450000 0.0775530000 0.0595880000 0.0000010000 0.3478130000 0.0017330000 148227803 0 402718720 3.8730723858 3.8377020359 4.0321397781 3261 1311867279.2411210537 0.1173093691 0.1069110871 0.2224369198 0.0063863614 0.8905510000 0.0666950000 0.0779840000 0.0309430000 0.3506400000 0.3563330000 148231531 0 402718720 3.8722200394 3.8367571831 4.0349493027 3262 1311867279.2717759609 0.1155520231 0.1069137360 0.2224369198 0.0063859173 0.4698890000 0.0666100000 0.0442800000 0.0000010000 0.3494790000 0.0016400000 148235147 0 402718720 3.8745548725 3.8381443024 4.0381202698 3263 1311867279.3067219257 0.1161146089 0.1069165558 0.2224369198 0.0063858693 0.5123590000 0.0680300000 0.0570890000 0.0305280000 0.3472530000 0.0016570000 148238931 0 402718720 3.8741755486 3.8390438557 4.0408506393 3264 1311867279.3388090134 0.1158821583 0.1069193026 0.2224369198 0.0063861988 0.4671200000 0.0674350000 0.0445970000 0.0000010000 0.3454920000 0.0016520000 148242603 0 402718720 3.8741300106 3.8378183842 4.0438861847 3265 1311867279.3804929256 0.1147819012 0.1069217108 0.2224369198 0.0063868659 0.8898260000 0.0997610000 0.0574300000 0.0310380000 0.3442040000 0.3493890000 148246555 0 402718720 3.8745298386 3.8392431736 4.0468235016 3266 1311867279.4089910984 0.1142299324 0.1069239484 0.2224369198 0.0063868715 0.4816130000 0.0679410000 0.0655640000 0.0000010000 0.3382340000 0.0017480000 148250003 0 402718720 3.8760604858 3.8404684067 4.0497970581 3267 1311867279.4410970211 0.1151179448 0.1069264565 0.2224369198 0.0063866771 0.5134470000 0.0695820000 0.0679720000 0.0306120000 0.3357970000 0.0016730000 148253675 0 402718720 3.8739790916 3.8401207924 4.0525856018 3268 1311867279.4725570679 0.1137712076 0.1069285510 0.2224369198 0.0063861656 0.4972780000 0.0691850000 0.0812410000 0.0000010000 0.3373050000 0.0016620000 148257347 0 402718720 3.8756771088 3.8378407955 4.0556459427 3269 1311867279.5095710754 0.1141994074 0.1069307752 0.2224369198 0.0063861278 0.8751230000 0.0822400000 0.0755650000 0.0305000000 0.3370000000 0.3418210000 148261187 0 402718720 3.8752574921 3.8405129910 4.0586304665 3270 1311867279.5407390594 0.1140185520 0.1069329427 0.2224369198 0.0063864311 0.4930310000 0.0766720000 0.0751160000 0.0000010000 0.3317040000 0.0016620000 148264691 0 402718720 3.8748800755 3.8404226303 4.0612697601 3271 1311867279.5734229088 0.1150033399 0.1069354100 0.2224369198 0.0063858035 0.5701890000 0.0726410000 0.1025650000 0.0374180000 0.3466670000 0.0021990000 148268475 0 402718720 3.8735783100 3.8385126591 4.0639390945 3272 1311867279.6121640205 0.1136424541 0.1069374598 0.2224369198 0.0063859781 0.5462710000 0.0867900000 0.1018400000 0.0000000000 0.3465630000 0.0021880000 148272315 0 402718720 3.8745236397 3.8386228085 4.0665874481 3273 1311867279.6389439106 0.1133360639 0.1069394148 0.2224369198 0.0063878068 0.8907110000 0.0870360000 0.0692820000 0.0373130000 0.3446770000 0.3444800000 148275819 0 402718720 3.8758282661 3.8402760029 4.0691308975 3274 1311867279.6749770641 0.1126265153 0.1069411518 0.2224369198 0.0063903108 0.4554050000 0.0696670000 0.0456810000 0.0000010000 0.3304410000 0.0016830000 148279659 0 402718720 3.8758273125 3.8381211758 4.0713858604 3275 1311867279.7107980251 0.1126570925 0.1069428971 0.2224369198 0.0063901607 0.4924140000 0.0697220000 0.0549780000 0.0309120000 0.3268690000 0.0017830000 148283331 0 402718720 3.8758697510 3.8391551971 4.0741415024 3276 1311867279.7410199642 0.1129168943 0.1069447207 0.2224369198 0.0063895009 0.4625270000 0.0712550000 0.0559840000 0.0000010000 0.3257010000 0.0016820000 148286947 0 402718720 3.8760294914 3.8406827450 4.0767183304 3277 1311867279.7777059078 0.1119337529 0.1069462431 0.2224369198 0.0063891113 0.8176280000 0.0706190000 0.0559970000 0.0308790000 0.3224520000 0.3296940000 148290787 0 402718720 3.8768649101 3.8396811485 4.0794548988 3278 1311867279.8118851185 0.1124726608 0.1069479291 0.2224369198 0.0063885580 0.4441190000 0.0706800000 0.0399980000 0.0000010000 0.3237680000 0.0016870000 148294515 0 402718720 3.8768377304 3.8380293846 4.0824565887 3279 1311867279.8438251019 0.1110674813 0.1069491854 0.2224369198 0.0063878601 0.5138290000 0.0842520000 0.0663710000 0.0304360000 0.3232010000 0.0016960000 148298187 0 402718720 3.8789687157 3.8396847248 4.0853953362 3280 1311867279.8808829784 0.1100290269 0.1069501244 0.2224369198 0.0063897581 0.4630330000 0.0725480000 0.0620810000 0.0000000000 0.3183920000 0.0017950000 148301971 0 402718720 3.8802454472 3.8401396275 4.0882964134 3281 1311867279.9088180065 0.1101936772 0.1069511130 0.2224369198 0.0063900095 0.8531510000 0.0725450000 0.0842210000 0.0303980000 0.3196380000 0.3374700000 148305587 0 402718720 3.8805110455 3.8379838467 4.0910634995 3282 1311867279.9440410137 0.1104919910 0.1069521918 0.2224369198 0.0063895794 0.5158420000 0.0912880000 0.0802040000 0.0000010000 0.3333500000 0.0022540000 148309371 0 402718720 3.8811867237 3.8382215500 4.0944175720 3283 1311867279.9795188904 0.1098977402 0.1069530890 0.2224369198 0.0063926117 0.5298470000 0.0911630000 0.0807840000 0.0302990000 0.3180140000 0.0017070000 148313099 0 402718720 3.8826880455 3.8402349949 4.0974211693 3284 1311867280.0113790035 0.1090071872 0.1069537145 0.2224369198 0.0063947588 0.4901520000 0.0847870000 0.0803010000 0.0000010000 0.3154400000 0.0016980000 148316715 0 402718720 3.8839256763 3.8388969898 4.1003313065 3285 1311867280.0401859283 0.1100054458 0.1069546435 0.2224369198 0.0063943220 0.8285600000 0.1022390000 0.0542860000 0.0308080000 0.3141210000 0.3190270000 148320275 0 402718720 3.8838002682 3.8398211002 4.1036729813 3286 1311867280.0785079002 0.1091465876 0.1069553106 0.2224369198 0.0063947070 0.4435620000 0.0743220000 0.0509940000 0.0000000000 0.3082870000 0.0018110000 148324115 0 402718720 3.8860740662 3.8413558006 4.1070628166 3287 1311867280.1111929417 0.1085003540 0.1069557806 0.2224369198 0.0063941701 0.4942060000 0.0751070000 0.0726260000 0.0308650000 0.3059760000 0.0017330000 148327787 0 402718720 3.8876178265 3.8388559818 4.1099581718 3288 1311867280.1450068951 0.1099713668 0.1069566978 0.2224369198 0.0063933874 0.4742750000 0.0747120000 0.0819910000 0.0000010000 0.3079220000 0.0017250000 148331571 0 402718720 3.8863592148 3.8388683796 4.1130180359 3289 1311867280.1753098965 0.1106388494 0.1069578173 0.2224369198 0.0063948355 0.7922940000 0.0748150000 0.0621950000 0.0307600000 0.3057470000 0.3108100000 148335131 0 402718720 3.8867619038 3.8408038616 4.1160597801 3290 1311867280.2123339176 0.1103026494 0.1069588340 0.2224369198 0.0063958907 0.4901450000 0.0913450000 0.0880930000 0.0000010000 0.3006680000 0.0018190000 148338971 0 402718720 3.8871583939 3.8395121098 4.1186752319 3291 1311867280.2422859669 0.1099522859 0.1069597436 0.2224369198 0.0063954869 0.4684020000 0.0752310000 0.0513820000 0.0307890000 0.3013740000 0.0017310000 148342587 0 402718720 3.8879055977 3.8375375271 4.1216273308 3292 1311867280.2794580460 0.1107422113 0.1069608926 0.2224369198 0.0064008957 0.4426990000 0.0761970000 0.0595460000 0.0000010000 0.2969510000 0.0018340000 148346427 0 402718720 3.8882267475 3.8408751488 4.1245193481 3293 1311867280.3114728928 0.1106374413 0.1069620090 0.2224369198 0.0064020935 0.7665350000 0.0773170000 0.0598260000 0.0308060000 0.2924990000 0.2977750000 148350099 0 402718720 3.8882606030 3.8384866714 4.1270289421 3294 1311867280.3445079327 0.1115214452 0.1069633932 0.2224369198 0.0064034538 0.4307270000 0.0768810000 0.0523970000 0.0000000000 0.2913970000 0.0018440000 148353715 0 402718720 3.8878347874 3.8386788368 4.1299076080 3295 1311867280.3755340576 0.1123245656 0.1069650203 0.2224369198 0.0064026884 0.4835530000 0.0900110000 0.0642490000 0.0301920000 0.2894470000 0.0017490000 148357387 0 402718720 3.8878974915 3.8405354023 4.1327204704 3296 1311867280.4071900845 0.1123850048 0.1069666647 0.2224369198 0.0064028219 0.4403950000 0.0915900000 0.0531040000 0.0000010000 0.2855950000 0.0018380000 148361003 0 402718720 3.8878340721 3.8384211063 4.1351637840 3297 1311867280.4424109459 0.1121176928 0.1069682270 0.2224369198 0.0064038340 0.7366810000 0.0778120000 0.0458170000 0.0307100000 0.2840440000 0.2903180000 148364787 0 402718720 3.8887217045 3.8393914700 4.1378893852 3298 1311867280.4782869816 0.1114654094 0.1069695906 0.2224369198 0.0064035448 0.4313440000 0.0788960000 0.0611630000 0.0000010000 0.2815880000 0.0017580000 148368571 0 402718720 3.8893568516 3.8402373791 4.1404643059 3299 1311867280.5091259480 0.1119309366 0.1069710945 0.2224369198 0.0064026158 0.4573200000 0.0787920000 0.0580690000 0.0306500000 0.2800870000 0.0017530000 148372243 0 402718720 3.8889560699 3.8398337364 4.1430358887 3300 1311867280.5455989838 0.1114232317 0.1069724436 0.2224369198 0.0064017872 0.4429870000 0.0793670000 0.0765820000 0.0000010000 0.2769780000 0.0018510000 148375971 0 402718720 3.8894443512 3.8400018215 4.1456823349 3301 1311867280.5782079697 0.1118535995 0.1069739223 0.2224369198 0.0064021502 0.7267990000 0.0802230000 0.0543280000 0.0306750000 0.2739310000 0.2793930000 148379643 0 402718720 3.8894426823 3.8413004875 4.1483597755 3302 1311867280.6130499840 0.1119063199 0.1069754161 0.2224369198 0.0064024682 0.4381440000 0.0798070000 0.0770640000 0.0000010000 0.2715650000 0.0017600000 148383371 0 402718720 3.8891842365 3.8403825760 4.1507778168 3303 1311867280.6422739029 0.1116458401 0.1069768301 0.2224369198 0.0064026231 0.4562130000 0.0791560000 0.0657020000 0.0305760000 0.2709740000 0.0017710000 148386987 0 402718720 3.8899247646 3.8394689560 4.1532278061 3304 1311867280.6755290031 0.1112098843 0.1069781113 0.2224369198 0.0064020761 0.4615150000 0.0936730000 0.0882010000 0.0000000000 0.2697910000 0.0017640000 148390715 0 402718720 3.8908650875 3.8401353359 4.1557679176 3305 1311867280.7094879150 0.1118358597 0.1069795811 0.2224369198 0.0064014179 0.7630780000 0.0926920000 0.0898810000 0.0305370000 0.2683170000 0.2735230000 148394443 0 402718720 3.8904001713 3.8402101994 4.1580662727 3306 1311867280.7411808968 0.1120593399 0.1069811176 0.2224369198 0.0064020021 0.4167620000 0.0798050000 0.0589500000 0.0000010000 0.2681480000 0.0017690000 148398059 0 402718720 3.8895149231 3.8394610882 4.1604356766 3307 1311867280.7752668858 0.1125783175 0.1069828102 0.2224369198 0.0064029102 0.4491080000 0.0797510000 0.0621500000 0.0306290000 0.2664080000 0.0018680000 148401787 0 402718720 3.8895998001 3.8405737877 4.1626348495 3308 1311867280.8076250553 0.1119307727 0.1069843059 0.2224369198 0.0064020090 0.4109130000 0.0810390000 0.0549440000 0.0000010000 0.2650270000 0.0017840000 148405459 0 402718720 3.8905446529 3.8404817581 4.1649975777 3309 1311867280.8401010036 0.1119875684 0.1069858179 0.2224369198 0.0064010994 0.7411820000 0.0810870000 0.0887180000 0.0301870000 0.2638740000 0.2691570000 148409187 0 402718720 3.8909392357 3.8403630257 4.1675596237 3310 1311867280.8754839897 0.1121287867 0.1069873717 0.2224369198 0.0064001466 0.4605260000 0.0997830000 0.0888300000 0.0000000000 0.2620330000 0.0017880000 148412915 0 402718720 3.8902857304 3.8403372765 4.1697597504 3311 1311867280.9079110622 0.1114436835 0.1069887176 0.2224369198 0.0063991933 0.4715640000 0.0815130000 0.0891720000 0.0305990000 0.2603980000 0.0017950000 148416587 0 402718720 3.8911514282 3.8408646584 4.1721587181 3312 1311867280.9394528866 0.1119717211 0.1069902221 0.2224369198 0.0063982653 0.4394730000 0.0816760000 0.0893980000 0.0000000000 0.2585360000 0.0017810000 148420315 0 402718720 3.8904991150 3.8406493664 4.1747488976 3313 1311867280.9766991138 0.1109178290 0.1069914076 0.2224369198 0.0063973452 0.6991810000 0.0821650000 0.0603240000 0.0300480000 0.2566220000 0.2619210000 148423987 0 402718720 3.8916943073 3.8412270546 4.1773858070 3314 1311867281.0075190067 0.1114047915 0.1069927394 0.2224369198 0.0063965557 0.4364140000 0.0820560000 0.0899880000 0.0000010000 0.2544640000 0.0017800000 148427659 0 402718720 3.8912305832 3.8407287598 4.1798882484 3315 1311867281.0433430672 0.1107334197 0.1069938678 0.2224369198 0.0063957439 0.4553010000 0.0988590000 0.0637810000 0.0305850000 0.2518720000 0.0018860000 148431443 0 402718720 3.8919880390 3.8402299881 4.1824502945 3316 1311867281.0752780437 0.1107051149 0.1069949870 0.2224369198 0.0063948816 0.4217600000 0.0818120000 0.0792990000 0.0000010000 0.2504500000 0.0018760000 148435059 0 402718720 3.8922255039 3.8404510021 4.1850438118 3317 1311867281.1074900627 0.1105282754 0.1069960522 0.2224369198 0.0063945323 0.7134110000 0.1005020000 0.0722170000 0.0305520000 0.2481680000 0.2539260000 148438787 0 402718720 3.8929738998 3.8405272961 4.1877450943 3318 1311867281.1451520920 0.1112380996 0.1069973307 0.2224369198 0.0063944054 0.4306110000 0.0824520000 0.0914670000 0.0000010000 0.2466930000 0.0017930000 148442571 0 402718720 3.8921210766 3.8402597904 4.1901211739 3319 1311867281.1786689758 0.1099795923 0.1069982292 0.2224369198 0.0063941156 0.4364210000 0.0826070000 0.0687520000 0.0304350000 0.2447090000 0.0017970000 148446355 0 402718720 3.8945426941 3.8400843143 4.1924047470 3320 1311867281.2083299160 0.1098504290 0.1069990883 0.2224369198 0.0063932162 0.4574250000 0.1091610000 0.0966660000 0.0000010000 0.2417030000 0.0017990000 148449971 0 402718720 3.8957812786 3.8409416676 4.1947174072 3321 1311867281.2457950115 0.1088360101 0.1069996415 0.2224369198 0.0063946804 0.7016810000 0.0828800000 0.0967040000 0.0304210000 0.2386970000 0.2447450000 148453755 0 402718720 3.8970046043 3.8390119076 4.1969456673 3322 1311867281.2754399776 0.1094336063 0.1070003741 0.2224369198 0.0063939795 0.4240260000 0.0835110000 0.0922550000 0.0000010000 0.2382360000 0.0018030000 148457315 0 402718720 3.8971810341 3.8394837379 4.1992154121 3323 1311867281.3072988987 0.1096143052 0.1070011608 0.2224369198 0.0063957285 0.4522160000 0.0836570000 0.0924870000 0.0304440000 0.2357330000 0.0018140000 148461043 0 402718720 3.8978495598 3.8402483463 4.2017068863 3324 1311867281.3465099335 0.1087339297 0.1070016820 0.2224369198 0.0063982503 0.3916370000 0.0838040000 0.0655500000 0.0000010000 0.2318880000 0.0019130000 148464883 0 402718720 3.8995506763 3.8387551308 4.2041015625 3325 1311867281.3751530647 0.1088616475 0.1070022414 0.2224369198 0.0063973035 0.6982950000 0.0946230000 0.0974340000 0.0299630000 0.2310580000 0.2370730000 148468443 0 402718720 3.8998875618 3.8378303051 4.2062444687 3326 1311867281.4080700874 0.1091237143 0.1070028793 0.2224369198 0.0063968316 0.4200690000 0.0840660000 0.0951210000 0.0000010000 0.2303590000 0.0018020000 148472171 0 402718720 3.9003667831 3.8389329910 4.2086515427 3327 1311867281.4434111118 0.1083072200 0.1070032713 0.2224369198 0.0063968370 0.4454000000 0.0842090000 0.0933680000 0.0304000000 0.2275140000 0.0018140000 148475955 0 402718720 3.9016795158 3.8380584717 4.2108888626 3328 1311867281.4753720760 0.1093391702 0.1070039732 0.2224369198 0.0063962164 0.4312150000 0.0956190000 0.0986760000 0.0000010000 0.2270170000 0.0018180000 148479571 0 402718720 3.9005300999 3.8368494511 4.2130336761 3329 1311867281.5101969242 0.1088876352 0.1070045390 0.2224369198 0.0063956423 0.7131940000 0.1086130000 0.0982770000 0.0299210000 0.2259030000 0.2415300000 148483355 0 402718720 3.9016594887 3.8384685516 4.2153306007 3330 1311867281.5435659885 0.1079705730 0.1070048291 0.2224369198 0.0063956206 0.4390660000 0.1064390000 0.0837790000 0.0000010000 0.2373630000 0.0024850000 148487083 0 402718720 3.9030551910 3.8379712105 4.2174992561 3331 1311867281.5754749775 0.1077875793 0.1070050641 0.2224369198 0.0063948588 0.5171630000 0.1067130000 0.1248480000 0.0371970000 0.2369530000 0.0024830000 148490755 0 402718720 3.9039664268 3.8364591599 4.2196593285 3332 1311867281.6111190319 0.1077782512 0.1070052962 0.2224369198 0.0063949671 0.4799350000 0.1068590000 0.1246870000 0.0000010000 0.2369460000 0.0024730000 148494483 0 402718720 3.9044842720 3.8374359608 4.2218313217 3333 1311867281.6435608864 0.1080773696 0.1070056178 0.2224369198 0.0063947718 0.7277450000 0.1068010000 0.1254960000 0.0371360000 0.2223970000 0.2277400000 148498211 0 402718720 3.9045481682 3.8371427059 4.2237200737 3334 1311867281.6755120754 0.1070469618 0.1070056302 0.2224369198 0.0063949523 0.3789730000 0.0842360000 0.0627870000 0.0000010000 0.2219450000 0.0018070000 148501883 0 402718720 3.9064784050 3.8358371258 4.2255806923 3335 1311867281.7089190483 0.1067912877 0.1070055660 0.2224369198 0.0063941490 0.4348400000 0.0948490000 0.0779280000 0.0297980000 0.2222920000 0.0018270000 148505555 0 402718720 3.9077837467 3.8357913494 4.2275290489 3336 1311867281.7452239990 0.1072898209 0.1070056512 0.2224369198 0.0063936596 0.3862460000 0.0842350000 0.0708030000 0.0000010000 0.2212490000 0.0018180000 148509395 0 402718720 3.9079873562 3.8361954689 4.2292604446 3337 1311867281.7755289078 0.1075283438 0.1070058078 0.2224369198 0.0063931531 0.6399520000 0.0841600000 0.0664250000 0.0297970000 0.2204780000 0.2299650000 148512955 0 402718720 3.9083089828 3.8347575665 4.2307176590 3338 1311867281.8075580597 0.1072494909 0.1070058808 0.2224369198 0.0063923873 0.4244970000 0.1070090000 0.0710590000 0.0000010000 0.2348680000 0.0024790000 148516627 0 402718720 3.9094581604 3.8350555897 4.2321796417 3339 1311867281.8447821140 0.1070106402 0.1070058822 0.2224369198 0.0063914337 0.5134120000 0.1065560000 0.1245740000 0.0363950000 0.2344570000 0.0024890000 148520467 0 402718720 3.9105982780 3.8351423740 4.2336359024 3340 1311867281.8756659031 0.1068120673 0.1070058242 0.2224369198 0.0063905598 0.4772360000 0.1065960000 0.1246880000 0.0000010000 0.2344800000 0.0024690000 148524139 0 402718720 3.9119212627 3.8341543674 4.2350263596 3341 1311867281.9077229500 0.1067133024 0.1070057367 0.2224369198 0.0063901680 0.6962880000 0.1064740000 0.1029840000 0.0297590000 0.2217060000 0.2272190000 148527811 0 402718720 3.9131665230 3.8346536160 4.2365927696 3342 1311867281.9444870949 0.1068018004 0.1070056756 0.2224369198 0.0063908018 0.4258220000 0.0967990000 0.0990680000 0.0000010000 0.2196820000 0.0019070000 148531539 0 402718720 3.9138305187 3.8355290890 4.2379169464 3343 1311867281.9785399437 0.1057277173 0.1070052934 0.2224369198 0.0063923964 0.4286970000 0.0958240000 0.0745160000 0.0297240000 0.2186550000 0.0018160000 148535267 0 402718720 3.9162609577 3.8337006569 4.2390947342 3344 1311867282.0098121166 0.1055656895 0.1070048629 0.2224369198 0.0063915272 0.3801210000 0.0845340000 0.0662350000 0.0000000000 0.2190420000 0.0019080000 148538939 0 402718720 3.9174449444 3.8335812092 4.2405123711 3345 1311867282.0436799526 0.1062097475 0.1070046252 0.2224369198 0.0063912202 0.6353760000 0.0962150000 0.0582320000 0.0302690000 0.2183360000 0.2240800000 148542611 0 402718720 3.9175238609 3.8348534107 4.2420215607 3346 1311867282.0755469799 0.1055950969 0.1070042039 0.2224369198 0.0063904060 0.3673620000 0.0841450000 0.0561550000 0.0000010000 0.2167430000 0.0019000000 148546283 0 402718720 3.9189569950 3.8341419697 4.2434282303 3347 1311867282.1077909470 0.1054876372 0.1070037508 0.2224369198 0.0063895401 0.4402720000 0.0843580000 0.0985980000 0.0302310000 0.2168280000 0.0019110000 148549955 0 402718720 3.9201922417 3.8341009617 4.2450127602 3348 1311867282.1464140415 0.1051169708 0.1070031872 0.2224369198 0.0063886707 0.4095570000 0.0842040000 0.0989450000 0.0000010000 0.2160750000 0.0019140000 148553795 0 402718720 3.9212648869 3.8353388309 4.2468585968 3349 1311867282.1797480583 0.1048254222 0.1070025370 0.2224369198 0.0063877693 0.6692710000 0.0972420000 0.0992350000 0.0302280000 0.2141880000 0.2201410000 148557523 0 402718720 3.9221811295 3.8351116180 4.2486257553 3350 1311867282.2136330605 0.1048482060 0.1070018939 0.2224369198 0.0063868429 0.4172450000 0.0994200000 0.0936600000 0.0000010000 0.2141440000 0.0018120000 148561251 0 402718720 3.9228339195 3.8345539570 4.2504258156 3351 1311867282.2453169823 0.1046013683 0.1070011775 0.2224369198 0.0063861645 0.4312360000 0.0841220000 0.0938150000 0.0296350000 0.2136180000 0.0018180000 148564923 0 402718720 3.9241392612 3.8349785805 4.2522754669 3352 1311867282.2844099998 0.1040066108 0.1070002841 0.2224369198 0.0063856569 0.3616230000 0.0843300000 0.0552180000 0.0000010000 0.2120540000 0.0018180000 148568707 0 402718720 3.9255599976 3.8346064091 4.2538919449 3353 1311867282.3187301159 0.1035630852 0.1069992590 0.2224369198 0.0063854886 0.6298440000 0.0972070000 0.0660600000 0.0296710000 0.2112780000 0.2173620000 148572435 0 402718720 3.9266226292 3.8342094421 4.2555589676 3354 1311867282.3445549011 0.1035000086 0.1069982157 0.2224369198 0.0063846624 0.3610470000 0.0842660000 0.0552060000 0.0000010000 0.2115670000 0.0018090000 148575939 0 402718720 3.9275889397 3.8343193531 4.2571821213 3355 1311867282.3837130070 0.1040242165 0.1069973293 0.2224369198 0.0063846494 0.4434240000 0.0941660000 0.0990380000 0.0301500000 0.2097270000 0.0019000000 148579555 0 402718720 3.9279034138 3.8338820934 4.2589182854 3356 1311867282.4114849567 0.1033905670 0.1069962546 0.2224369198 0.0063845380 0.4022840000 0.0842430000 0.0987670000 0.0000010000 0.2089530000 0.0019010000 148583059 0 402718720 3.9295029640 3.8334727287 4.2606148720 3357 1311867282.4437038898 0.1031382382 0.1069951053 0.2224369198 0.0063838046 0.5949860000 0.0844040000 0.0499460000 0.0296680000 0.2085000000 0.2142450000 148586787 0 402718720 3.9303529263 3.8333628178 4.2623710632 3358 1311867282.4754569530 0.1032248437 0.1069939826 0.2224369198 0.0063833357 0.3962300000 0.0841820000 0.0942850000 0.0000010000 0.2077590000 0.0018110000 148590403 0 402718720 3.9306437969 3.8336522579 4.2639608383 3359 1311867282.5128560066 0.1035359055 0.1069929531 0.2224369198 0.0063828210 0.4173970000 0.0843250000 0.0864980000 0.0295920000 0.2068900000 0.0018060000 148594243 0 402718720 3.9311544895 3.8321828842 4.2655491829 3360 1311867282.5435400009 0.1034813225 0.1069919079 0.2224369198 0.0063819298 0.3893460000 0.0987770000 0.0725510000 0.0000000000 0.2076360000 0.0019130000 148597915 0 402718720 3.9319665432 3.8320002556 4.2670831680 3361 1311867282.5755639076 0.1033865362 0.1069908352 0.2224369198 0.0063811721 0.5913360000 0.0845070000 0.0476510000 0.0300880000 0.2076460000 0.2132130000 148601587 0 402718720 3.9324641228 3.8326919079 4.2685890198 3362 1311867282.6112899780 0.1032939628 0.1069897356 0.2224369198 0.0063804423 0.3970900000 0.0842690000 0.0951660000 0.0000010000 0.2076310000 0.0018020000 148605315 0 402718720 3.9327061176 3.8314819336 4.2698092461 3363 1311867282.6437261105 0.1033301353 0.1069886474 0.2224369198 0.0063796755 0.4573870000 0.1229080000 0.0860950000 0.0300760000 0.2082810000 0.0018140000 148608987 0 402718720 3.9330697060 3.8311154842 4.2710475922 3364 1311867282.6766591072 0.1033773646 0.1069875739 0.2224369198 0.0063789527 0.3416210000 0.0842010000 0.0397430000 0.0000000000 0.2076550000 0.0017960000 148612659 0 402718720 3.9334344864 3.8321359158 4.2720808983 3365 1311867282.7147250175 0.1035503149 0.1069865524 0.2224369198 0.0063783144 0.6523050000 0.0959390000 0.0987230000 0.0300730000 0.2067310000 0.2124410000 148616499 0 402718720 3.9327354431 3.8306143284 4.2727808952 3366 1311867282.7462520599 0.1033037454 0.1069854583 0.2224369198 0.0063775014 0.3854220000 0.0845040000 0.0826260000 0.0000010000 0.2082800000 0.0018040000 148620171 0 402718720 3.9331977367 3.8299214840 4.2735309601 3367 1311867282.7754290104 0.1038805842 0.1069845362 0.2224369198 0.0063768159 0.3883790000 0.0842280000 0.0551920000 0.0300420000 0.2088460000 0.0018040000 148623619 0 402718720 3.9320099354 3.8306422234 4.2741193771 3368 1311867282.8116350174 0.1035133824 0.1069835055 0.2224369198 0.0063759239 0.3780190000 0.0842710000 0.0744140000 0.0000010000 0.2089030000 0.0018960000 148627347 0 402718720 3.9317185879 3.8298711777 4.2749209404 3369 1311867282.8475370407 0.1034488603 0.1069824564 0.2224369198 0.0063759535 0.6585110000 0.0964010000 0.0988330000 0.0301410000 0.2095670000 0.2153530000 148631131 0 402718720 3.9306714535 3.8308298588 4.2760624886 3370 1311867282.8757910728 0.1028316990 0.1069812247 0.2224369198 0.0063750291 0.3592650000 0.0915890000 0.0501210000 0.0000000000 0.2075550000 0.0018150000 148634747 0 402718720 3.9310710430 3.8318412304 4.2774467468 3371 1311867282.9114630222 0.1023627147 0.1069798546 0.2224369198 0.0063741902 0.3921500000 0.0842560000 0.0628150000 0.0295250000 0.2055210000 0.0018130000 148638475 0 402718720 3.9311885834 3.8313622475 4.2788176537 3372 1311867282.9456479549 0.1022154689 0.1069784417 0.2224369198 0.0063735160 0.3649450000 0.0843860000 0.0663240000 0.0000010000 0.2039300000 0.0019010000 148642203 0 402718720 3.9313054085 3.8313791752 4.2805380821 3373 1311867282.9811890125 0.1020286679 0.1069769742 0.2224369198 0.0063735271 0.5995790000 0.0846200000 0.0668800000 0.0300750000 0.2019030000 0.2078870000 148645931 0 402718720 3.9305701256 3.8326787949 4.2818670273 3374 1311867283.0114879608 0.1022277921 0.1069755666 0.2224369198 0.0063729071 0.3693560000 0.0848440000 0.0748840000 0.0000010000 0.1992320000 0.0018970000 148649603 0 402718720 3.9302673340 3.8317971230 4.2833251953 3375 1311867283.0462460518 0.1024648398 0.1069742301 0.2224369198 0.0063726806 0.3841520000 0.0946280000 0.0501470000 0.0300790000 0.1991640000 0.0018100000 148653331 0 402718720 3.9295578003 3.8308427334 4.2844052315 3376 1311867283.0752930641 0.1025773510 0.1069729277 0.2224369198 0.0063723227 0.3881750000 0.0841330000 0.0942450000 0.0000000000 0.1997230000 0.0018010000 148656947 0 402718720 3.9290285110 3.8320145607 4.2855887413 3377 1311867283.1116878986 0.1011871025 0.1069712144 0.2224369198 0.0063737068 0.6175030000 0.0844950000 0.0946750000 0.0295180000 0.1974460000 0.2030480000 148660787 0 402718720 3.9292721748 3.8321716785 4.2865753174 3378 1311867283.1435511112 0.1014403850 0.1069695771 0.2224369198 0.0063735726 0.3479540000 0.0847160000 0.0553570000 0.0000000000 0.1978700000 0.0017650000 148664459 0 402718720 3.9289944172 3.8301103115 4.2872076035 3379 1311867283.1788220406 0.1019883007 0.1069681029 0.2224369198 0.0063750021 0.4223280000 0.0841780000 0.0990540000 0.0300940000 0.1986360000 0.0019160000 148668131 0 402718720 3.9289669991 3.8312611580 4.2880630493 3380 1311867283.2158269882 0.1022926345 0.1069667197 0.2224369198 0.0063744542 0.4139920000 0.1012100000 0.0944550000 0.0000000000 0.2067050000 0.0024640000 148671971 0 402718720 3.9293735027 3.8314044476 4.2888312340 3381 1311867283.2441749573 0.1024863273 0.1069653945 0.2224369198 0.0063742993 0.7059200000 0.1070230000 0.1260380000 0.0359620000 0.2108230000 0.2168230000 148675531 0 402718720 3.9291100502 3.8294076920 4.2893686295 3382 1311867283.2776839733 0.1026665941 0.1069641234 0.2224369198 0.0063740305 0.4260890000 0.1069510000 0.0945090000 0.0000000000 0.2129860000 0.0024760000 148679259 0 402718720 3.9291210175 3.8299539089 4.2904028893 3383 1311867283.3134660721 0.1019483283 0.1069626408 0.2224369198 0.0063735335 0.4890370000 0.1072650000 0.1254480000 0.0359620000 0.2103060000 0.0018210000 148683043 0 402718720 3.9299736023 3.8307042122 4.2912755013 3384 1311867283.3498029709 0.1019901186 0.1069611713 0.2224369198 0.0063735556 0.4144980000 0.0973430000 0.0926940000 0.0000010000 0.2128710000 0.0024810000 148686939 0 402718720 3.9300615788 3.8294131756 4.2922854424 3385 1311867283.3852219582 0.1024806425 0.1069598477 0.2224369198 0.0063731585 0.6704040000 0.1069840000 0.0842420000 0.0359450000 0.2139870000 0.2199750000 148690723 0 402718720 3.9295365810 3.8292710781 4.2933030128 3386 1311867283.4173080921 0.1026758626 0.1069585825 0.2224369198 0.0063729607 0.4090940000 0.1035010000 0.0938440000 0.0000000000 0.2016550000 0.0018100000 148694339 0 402718720 3.9298677444 3.8303289413 4.2943334579 3387 1311867283.4492650032 0.1024928316 0.1069572640 0.2224369198 0.0063720611 0.3834240000 0.0845770000 0.0579370000 0.0300030000 0.2005100000 0.0018980000 148698011 0 402718720 3.9304568768 3.8300695419 4.2950439453 3388 1311867283.4853370190 0.1025897264 0.1069559749 0.2224369198 0.0063716190 0.3946910000 0.0841150000 0.0989290000 0.0000010000 0.2015380000 0.0018080000 148701795 0 402718720 3.9305429459 3.8286137581 4.2956380844 3389 1311867283.5172159672 0.1029257551 0.1069547857 0.2224369198 0.0063708643 0.6413800000 0.0956080000 0.0938200000 0.0300040000 0.2040560000 0.2096190000 148705467 0 402718720 3.9302198887 3.8291912079 4.2961711884 3390 1311867283.5495610237 0.1030714959 0.1069536402 0.2224369198 0.0063702965 0.3460380000 0.0839380000 0.0474470000 0.0000010000 0.2044620000 0.0017970000 148709139 0 402718720 3.9303019047 3.8301203251 4.2968482971 3391 1311867283.5853879452 0.1028621271 0.1069524336 0.2224369198 0.0063699537 0.4120940000 0.1092340000 0.0580040000 0.0300250000 0.2043880000 0.0018850000 148712867 0 402718720 3.9307675362 3.8289184570 4.2973809242 3392 1311867283.6173179150 0.1030353531 0.1069512788 0.2224369198 0.0063695445 0.3934620000 0.0954610000 0.0820550000 0.0000010000 0.2058320000 0.0018010000 148716539 0 402718720 3.9306693077 3.8296689987 4.2981624603 3393 1311867283.6493821144 0.1027342752 0.1069500359 0.2224369198 0.0063686903 0.5845700000 0.0843320000 0.0474210000 0.0294550000 0.2047090000 0.2102990000 148720267 0 402718720 3.9310536385 3.8300950527 4.2987761497 3394 1311867283.6852879524 0.1028073132 0.1069488153 0.2224369198 0.0063683288 0.3807990000 0.0963300000 0.0707320000 0.0000010000 0.2035530000 0.0018050000 148724051 0 402718720 3.9306373596 3.8302829266 4.2993144989 3395 1311867283.7179150581 0.1022388786 0.1069474280 0.2224369198 0.0063675756 0.3981560000 0.0845540000 0.0708840000 0.0299310000 0.2026590000 0.0018060000 148727667 0 402718720 3.9316356182 3.8306119442 4.3002700806 3396 1311867283.7492079735 0.1026623249 0.1069461662 0.2224369198 0.0063669329 0.3625570000 0.0961950000 0.0554720000 0.0000010000 0.2007400000 0.0018040000 148731339 0 402718720 3.9310684204 3.8315854073 4.3009486198 3397 1311867283.7853169441 0.1026217565 0.1069448932 0.2224369198 0.0063664100 0.6467600000 0.0849890000 0.0943170000 0.0299490000 0.2098240000 0.2185120000 148735123 0 402718720 3.9309129715 3.8309061527 4.3015666008 3398 1311867283.8174130917 0.1029690951 0.1069437232 0.2224369198 0.0063658119 0.4369890000 0.1072250000 0.1049480000 0.0000010000 0.2130660000 0.0024770000 148738739 0 402718720 3.9301483631 3.8312239647 4.3021597862 3399 1311867283.8494520187 0.1026101112 0.1069424482 0.2224369198 0.0063653348 0.4308110000 0.1069840000 0.0636180000 0.0358910000 0.2126710000 0.0024790000 148742467 0 402718720 3.9303755760 3.8323800564 4.3027677536 3400 1311867283.8853459358 0.1026172042 0.1069411761 0.2224369198 0.0063646105 0.4564400000 0.1075340000 0.1256600000 0.0000000000 0.2114910000 0.0024730000 148746195 0 402718720 3.9298822880 3.8320600986 4.3032383919 3401 1311867283.9175400734 0.1024073809 0.1069398430 0.2224369198 0.0063637133 0.6258400000 0.0844120000 0.0991190000 0.0299600000 0.1992570000 0.2048370000 148749867 0 402718720 3.9296131134 3.8315465450 4.3035216331 3402 1311867283.9498898983 0.1024171486 0.1069385136 0.2224369198 0.0063628274 0.3935730000 0.0847340000 0.0989700000 0.0000010000 0.1994130000 0.0018900000 148753539 0 402718720 3.9291594028 3.8324601650 4.3039631844 3403 1311867283.9856629372 0.1024475992 0.1069371939 0.2224369198 0.0063622258 0.3988780000 0.0846730000 0.0744750000 0.0299450000 0.1996470000 0.0018090000 148757379 0 402718720 3.9283759594 3.8320484161 4.3042597771 3404 1311867284.0172998905 0.1026513651 0.1069359348 0.2224369198 0.0063614622 0.3436180000 0.0846260000 0.0475490000 0.0000010000 0.2013010000 0.0017950000 148760995 0 402718720 3.9276769161 3.8311738968 4.3044862747 3405 1311867284.0497789383 0.1029891521 0.1069347757 0.2224369198 0.0063621393 0.6287590000 0.0844610000 0.0938840000 0.0300020000 0.2032380000 0.2088130000 148764723 0 402718720 3.9265699387 3.8324961662 4.3048896790 3406 1311867284.0853729248 0.1025333554 0.1069334834 0.2224369198 0.0063613367 0.4038920000 0.0975250000 0.0940280000 0.0000000000 0.2021930000 0.0018070000 148768451 0 402718720 3.9264795780 3.8335127831 4.3053731918 3407 1311867284.1175038815 0.1027758420 0.1069322631 0.2224369198 0.0063614087 0.4234080000 0.0843260000 0.0987010000 0.0294960000 0.2007870000 0.0018130000 148772123 0 402718720 3.9252836704 3.8326227665 4.3055758476 3408 1311867284.1494109631 0.1020001546 0.1069308159 0.2224369198 0.0063607247 0.3893650000 0.0842400000 0.0939000000 0.0000000000 0.2010890000 0.0017890000 148775795 0 402718720 3.9258501530 3.8333234787 4.3062343597 3409 1311867284.1874890327 0.1019986272 0.1069293691 0.2224369198 0.0063599556 0.5883540000 0.0843710000 0.0631550000 0.0299650000 0.1984970000 0.2040410000 148779635 0 402718720 3.9255189896 3.8349080086 4.3069925308 3410 1311867284.2173368931 0.1023495942 0.1069280260 0.2224369198 0.0063596402 0.3578160000 0.1037080000 0.0474670000 0.0000010000 0.1965060000 0.0017990000 148783251 0 402718720 3.9247605801 3.8334012032 4.3073205948 3411 1311867284.2494308949 0.1027812436 0.1069268103 0.2224369198 0.0063588869 0.3990450000 0.1047800000 0.0583010000 0.0299650000 0.1954910000 0.0018840000 148786923 0 402718720 3.9243438244 3.8341326714 4.3078236580 3412 1311867284.2853159904 0.1027094424 0.1069255743 0.2224369198 0.0063579895 0.3882390000 0.0849640000 0.0993970000 0.0000010000 0.1936840000 0.0017960000 148790651 0 402718720 3.9245922565 3.8348584175 4.3082237244 3413 1311867284.3178350925 0.1031465381 0.1069244671 0.2224369198 0.0063571490 0.5633580000 0.0848280000 0.0501400000 0.0294600000 0.1923840000 0.1982050000 148794379 0 402718720 3.9239871502 3.8346545696 4.3082909584 3414 1311867284.3494238853 0.1028198004 0.1069232647 0.2224369198 0.0063565013 0.3339490000 0.0843790000 0.0477640000 0.0000010000 0.1916450000 0.0017990000 148798051 0 402718720 3.9247756004 3.8362462521 4.3087582588 3415 1311867284.3854329586 0.1023528203 0.1069219264 0.2224369198 0.0063559794 0.3894290000 0.0969080000 0.0633940000 0.0299350000 0.1890450000 0.0018090000 148801835 0 402718720 3.9257202148 3.8362970352 4.3091554642 3416 1311867284.4175798893 0.1026985943 0.1069206901 0.2224369198 0.0063553194 0.3335050000 0.0848760000 0.0502860000 0.0000010000 0.1878150000 0.0018920000 148805507 0 402718720 3.9255292416 3.8363499641 4.3093814850 3417 1311867284.4495139122 0.1023496687 0.1069193523 0.2224369198 0.0063545978 0.6022190000 0.0849480000 0.0998290000 0.0294120000 0.1868190000 0.1926480000 148809179 0 402718720 3.9265263081 3.8372509480 4.3098464012 3418 1311867284.4854190350 0.1030026451 0.1069182064 0.2224369198 0.0063538784 0.3316130000 0.0850170000 0.0504400000 0.0000010000 0.1859940000 0.0018050000 148812907 0 402718720 3.9259490967 3.8367152214 4.3101754189 3419 1311867284.5177299976 0.1026196629 0.1069169492 0.2224369198 0.0063531601 0.4065260000 0.0850850000 0.0948830000 0.0299780000 0.1864290000 0.0017990000 148816635 0 402718720 3.9269263744 3.8363819122 4.3105330467 3420 1311867284.5494539738 0.1023822054 0.1069156232 0.2224369198 0.0063529254 0.3459220000 0.0852690000 0.0636290000 0.0000000000 0.1868290000 0.0018100000 148820307 0 402718720 3.9278485775 3.8372964859 4.3109617233 3421 1311867284.5854179859 0.1026771143 0.1069143843 0.2224369198 0.0063521498 0.5839450000 0.0849700000 0.0835380000 0.0294580000 0.1858160000 0.1917930000 148824035 0 402718720 3.9280459881 3.8379120827 4.3112416267 3422 1311867284.6174941063 0.1027856618 0.1069131777 0.2224369198 0.0063515394 0.3610330000 0.0852930000 0.0797950000 0.0000000000 0.1856930000 0.0017950000 148827707 0 402718720 3.9282259941 3.8369700909 4.3114814758 3423 1311867284.6495230198 0.1025427505 0.1069119010 0.2224369198 0.0063515377 0.4342290000 0.1091280000 0.0988020000 0.0299130000 0.1861250000 0.0018090000 148831435 0 402718720 3.9289674759 3.8380405903 4.3118677139 3424 1311867284.6853780746 0.1023823693 0.1069105781 0.2224369198 0.0063515153 0.3448140000 0.0851180000 0.0641200000 0.0000010000 0.1853460000 0.0017960000 148835163 0 402718720 3.9296224117 3.8390395641 4.3122873306 3425 1311867284.7174859047 0.1019334272 0.1069091249 0.2224369198 0.0063523623 0.5738110000 0.0851940000 0.0753520000 0.0299440000 0.1844150000 0.1901630000 148838835 0 402718720 3.9307408333 3.8372011185 4.3125734329 3426 1311867284.7498660088 0.1026413664 0.1069078792 0.2224369198 0.0063542525 0.3804700000 0.0849790000 0.0997100000 0.0000000000 0.1852180000 0.0019100000 148842563 0 402718720 3.9299151897 3.8387372494 4.3130469322 3427 1311867284.7854089737 0.1025343016 0.1069066030 0.2224369198 0.0063534740 0.4101130000 0.0852640000 0.1001990000 0.0299490000 0.1841170000 0.0019140000 148846291 0 402718720 3.9302556515 3.8398880959 4.3135514259 3428 1311867284.8186919689 0.1022688374 0.1069052501 0.2224369198 0.0063540156 0.3667120000 0.0851290000 0.0873360000 0.0000010000 0.1840230000 0.0018040000 148850019 0 402718720 3.9311294556 3.8383426666 4.3139162064 3429 1311867284.8492770195 0.1023330167 0.1069039167 0.2224369198 0.0063541451 0.5813870000 0.0972560000 0.0714570000 0.0294180000 0.1845770000 0.1902680000 148853635 0 402718720 3.9314019680 3.8396420479 4.3142852783 3430 1311867284.8853850365 0.1023848206 0.1069025992 0.2224369198 0.0063533256 0.3423240000 0.0851290000 0.0637590000 0.0000010000 0.1831230000 0.0017950000 148857363 0 402718720 3.9316806793 3.8401784897 4.3146824837 3431 1311867284.9174609184 0.1024223417 0.1069012933 0.2224369198 0.0063530794 0.3843250000 0.0944960000 0.0669330000 0.0299240000 0.1824680000 0.0019080000 148861091 0 402718720 3.9316275120 3.8384740353 4.3146252632 3432 1311867284.9492468834 0.1022554263 0.1068999396 0.2224369198 0.0063526923 0.3782180000 0.0851350000 0.0997550000 0.0000010000 0.1831640000 0.0018060000 148864763 0 402718720 3.9319190979 3.8397526741 4.3146624565 3433 1311867284.9852581024 0.1028763056 0.1068987676 0.2224369198 0.0063519517 0.5422390000 0.0853560000 0.0479310000 0.0293890000 0.1827220000 0.1884000000 148868603 0 402718720 3.9309308529 3.8395473957 4.3144054413 3434 1311867285.0175390244 0.1026260778 0.1068975234 0.2224369198 0.0063520521 0.3655870000 0.0849070000 0.0872540000 0.0000010000 0.1831260000 0.0017880000 148872219 0 402718720 3.9310564995 3.8378775120 4.3140296936 3435 1311867285.0493679047 0.1027856991 0.1068963263 0.2224369198 0.0063514606 0.3892340000 0.0852860000 0.0792990000 0.0299160000 0.1844940000 0.0018060000 148875891 0 402718720 3.9304146767 3.8384671211 4.3134794235 3436 1311867285.0853259563 0.1027359962 0.1068951155 0.2224369198 0.0063505411 0.3552950000 0.1100630000 0.0503310000 0.0000010000 0.1842980000 0.0018970000 148879675 0 402718720 3.9303514957 3.8383998871 4.3130426407 3437 1311867285.1177120209 0.1031114236 0.1068940147 0.2224369198 0.0063502872 0.5991370000 0.0851450000 0.1001600000 0.0294290000 0.1851020000 0.1907740000 148883347 0 402718720 3.9299056530 3.8361685276 4.3122878075 3438 1311867285.1502749920 0.1032521054 0.1068929553 0.2224369198 0.0063503943 0.3575100000 0.0849920000 0.0750150000 0.0000010000 0.1872560000 0.0018000000 148887075 0 402718720 3.9292030334 3.8365399837 4.3114347458 3439 1311867285.1855800152 0.1028679907 0.1068917850 0.2224369198 0.0063496218 0.3767990000 0.0853890000 0.0632990000 0.0299120000 0.1879570000 0.0018130000 148890747 0 402718720 3.9295175076 3.8369405270 4.3105812073 3440 1311867285.2187609673 0.1029865965 0.1068906497 0.2224369198 0.0063490357 0.3396430000 0.0849080000 0.0557850000 0.0000000000 0.1887130000 0.0017910000 148894531 0 402718720 3.9289965630 3.8354163170 4.3096332550 3441 1311867285.2493660450 0.1032837108 0.1068896015 0.2224369198 0.0063481607 0.6046120000 0.0845020000 0.0943810000 0.0299810000 0.1908050000 0.1964530000 148898147 0 402718720 3.9284927845 3.8345489502 4.3088870049 3442 1311867285.2853620052 0.1034618914 0.1068886057 0.2224369198 0.0063476957 0.3817480000 0.0849910000 0.0941900000 0.0000010000 0.1923400000 0.0018050000 148901931 0 402718720 3.9280035496 3.8352911472 4.3081159592 3443 1311867285.3175029755 0.1034194008 0.1068875980 0.2224369198 0.0063469304 0.3650570000 0.0848380000 0.0476200000 0.0294570000 0.1928010000 0.0018180000 148905603 0 402718720 3.9277670383 3.8350040913 4.3074150085 3444 1311867285.3493449688 0.1029473916 0.1068864540 0.2224369198 0.0063461298 0.3295860000 0.0847630000 0.0398250000 0.0000010000 0.1947230000 0.0017950000 148909275 0 402718720 3.9281282425 3.8342506886 4.3069210052 3445 1311867285.3855409622 0.1024991497 0.1068851804 0.2224369198 0.0063460975 0.6173080000 0.0844760000 0.0989490000 0.0293800000 0.1950400000 0.2007970000 148913115 0 402718720 3.9282751083 3.8356881142 4.3066177368 3446 1311867285.4175810814 0.1024744213 0.1068839005 0.2224369198 0.0063455681 0.3887080000 0.0846550000 0.0992480000 0.0000010000 0.1945670000 0.0018000000 148916731 0 402718720 3.9277484417 3.8356108665 4.3064408302 3447 1311867285.4492840767 0.1026532277 0.1068826731 0.2224369198 0.0063446639 0.3776180000 0.0847530000 0.0401980000 0.0358360000 0.2064860000 0.0018160000 148920403 0 402718720 3.9273231030 3.8352053165 4.3066296577 3448 1311867285.4853799343 0.1023220643 0.1068813504 0.2224369198 0.0063446181 0.3843910000 0.0849020000 0.0945540000 0.0000010000 0.1946500000 0.0017990000 148924131 0 402718720 3.9275763035 3.8367495537 4.3070964813 3449 1311867285.5176479816 0.1021028534 0.1068799650 0.2224369198 0.0063444314 0.6332290000 0.1073320000 0.0974640000 0.0294290000 0.1923430000 0.1981480000 148927859 0 402718720 3.9275360107 3.8363077641 4.3075575829 3450 1311867285.5494589806 0.1024645045 0.1068786851 0.2224369198 0.0063440120 0.3868840000 0.0847200000 0.0993130000 0.0000010000 0.1925410000 0.0018120000 148931531 0 402718720 3.9264802933 3.8356540203 4.3079376221 3451 1311867285.5855739117 0.1018811315 0.1068772370 0.2224369198 0.0063438766 0.3894320000 0.0991300000 0.0585260000 0.0294680000 0.1920620000 0.0018140000 148935315 0 402718720 3.9273426533 3.8372006416 4.3087735176 3452 1311867285.6175510883 0.1018751115 0.1068757879 0.2224369198 0.0063436865 0.3848910000 0.0848060000 0.0994570000 0.0000010000 0.1899790000 0.0018960000 148938987 0 402718720 3.9268949032 3.8365142345 4.3092246056 3453 1311867285.6494030952 0.1022181734 0.1068744391 0.2224369198 0.0063428338 0.6072240000 0.0848830000 0.0972610000 0.0299730000 0.1903230000 0.1961070000 148942659 0 402718720 3.9261331558 3.8359019756 4.3098053932 3454 1311867285.6856529713 0.1021225378 0.1068730633 0.2224369198 0.0063423561 0.3849120000 0.0847690000 0.0997780000 0.0000010000 0.1897350000 0.0018880000 148946443 0 402718720 3.9261958599 3.8381772041 4.3106064796 3455 1311867285.7177190781 0.1023498029 0.1068717541 0.2224369198 0.0063427505 0.3882570000 0.0850950000 0.0749000000 0.0294580000 0.1885750000 0.0018120000 148950115 0 402718720 3.9256505966 3.8367254734 4.3109745979 3456 1311867285.7497379780 0.1024961844 0.1068704880 0.2224369198 0.0063421167 0.3593620000 0.0963520000 0.0632310000 0.0000010000 0.1894830000 0.0017900000 148953787 0 402718720 3.9252300262 3.8365955353 4.3112688065 3457 1311867285.7854781151 0.1022625640 0.1068691551 0.2224369198 0.0063412107 0.5552240000 0.0848850000 0.0477530000 0.0299350000 0.1892390000 0.1948870000 148957627 0 402718720 3.9254066944 3.8372442722 4.3116359711 3458 1311867285.8179709911 0.1025286838 0.1068678999 0.2224369198 0.0063405880 0.3789580000 0.0846680000 0.0945290000 0.0000010000 0.1894160000 0.0018040000 148961243 0 402718720 3.9246397018 3.8361630440 4.3117041588 3459 1311867285.8496279716 0.1028356105 0.1068667342 0.2224369198 0.0063400959 0.3752390000 0.0850820000 0.0584390000 0.0299520000 0.1903970000 0.0018870000 148964915 0 402718720 3.9238307476 3.8362598419 4.3118224144 3460 1311867285.8852860928 0.1022845507 0.1068654098 0.2224369198 0.0063392540 0.3928430000 0.0967860000 0.0943080000 0.0000010000 0.1912690000 0.0017930000 148968755 0 402718720 3.9243550301 3.8362340927 4.3119401932 3461 1311867285.9187369347 0.1024557352 0.1068641357 0.2224369198 0.0063393016 0.6221180000 0.0956020000 0.0992110000 0.0294360000 0.1916860000 0.1975250000 148972427 0 402718720 3.9235134125 3.8347089291 4.3118047714 3462 1311867285.9496929646 0.1024745107 0.1068628678 0.2224369198 0.0063387481 0.4124280000 0.1074630000 0.0994640000 0.0000010000 0.1948280000 0.0018990000 148976099 0 402718720 3.9231855869 3.8341028690 4.3118863106 3463 1311867285.9858360291 0.1020353362 0.1068614738 0.2224369198 0.0063390203 0.3873470000 0.0847580000 0.0663930000 0.0299610000 0.1955830000 0.0018920000 148979827 0 402718720 3.9233319759 3.8358263969 4.3121538162 3464 1311867286.0184700489 0.1027574167 0.1068602890 0.2224369198 0.0063386931 0.3405300000 0.0847440000 0.0502170000 0.0000000000 0.1952860000 0.0018070000 148983499 0 402718720 3.9217338562 3.8347203732 4.3121809959 3465 1311867286.0494220257 0.1027019098 0.1068590889 0.2224369198 0.0063379196 0.5922790000 0.0846510000 0.0708200000 0.0298990000 0.1964360000 0.2020000000 148987171 0 402718720 3.9219400883 3.8343098164 4.3126888275 3466 1311867286.0854020119 0.1027051806 0.1068578904 0.2224369198 0.0063394338 0.3993170000 0.0990430000 0.0943410000 0.0000000000 0.1955830000 0.0018050000 148990899 0 402718720 3.9222605228 3.8355698586 4.3132610321 3467 1311867286.1240980625 0.1029547602 0.1068567646 0.2224369198 0.0063403513 0.3751200000 0.0845890000 0.0553530000 0.0299140000 0.1940300000 0.0018020000 148994683 0 402718720 3.9214007854 3.8347356319 4.3134989738 3468 1311867286.1506319046 0.1031672508 0.1068557007 0.2224369198 0.0063406052 0.3476060000 0.0849400000 0.0580910000 0.0000010000 0.1939610000 0.0018960000 148998187 0 402718720 3.9213542938 3.8353471756 4.3137993813 3469 1311867286.1857590675 0.1026784554 0.1068544966 0.2224369198 0.0063397128 0.6287920000 0.0848620000 0.0957650000 0.0299390000 0.1971520000 0.2116220000 149001915 0 402718720 3.9219069481 3.8359875679 4.3142027855 3470 1311867286.2179830074 0.1024209559 0.1068532189 0.2224369198 0.0063399322 0.4489740000 0.1072130000 0.1253010000 0.0000010000 0.2045720000 0.0024600000 149005587 0 402718720 3.9218873978 3.8355748653 4.3144912720 3471 1311867286.2525210381 0.1022560298 0.1068518944 0.2224369198 0.0063391279 0.4803350000 0.1073750000 0.1204900000 0.0358110000 0.2047780000 0.0024740000 149009259 0 402718720 3.9219722748 3.8357748985 4.3148612976 3472 1311867286.2861630917 0.1025682017 0.1068506607 0.2224369198 0.0063383927 0.4078730000 0.1074110000 0.0843890000 0.0000000000 0.2042590000 0.0024580000 149012931 0 402718720 3.9213871956 3.8369255066 4.3150305748 3473 1311867286.3203520775 0.1026867703 0.1068494617 0.2224369198 0.0063375133 0.6165650000 0.1071510000 0.0839980000 0.0299140000 0.1906400000 0.1962820000 149016603 0 402718720 3.9210162163 3.8368499279 4.3149909973 3474 1311867286.3524320126 0.1026645675 0.1068482571 0.2224369198 0.0063368861 0.3629500000 0.1024510000 0.0581420000 0.0000000000 0.1917150000 0.0019030000 149020275 0 402718720 3.9204075336 3.8369026184 4.3147287369 3475 1311867286.3855628967 0.1022206023 0.1068469254 0.2224369198 0.0063364351 0.3856280000 0.0849380000 0.0662720000 0.0299810000 0.1937790000 0.0019120000 149023947 0 402718720 3.9203879833 3.8387200832 4.3142499924 3476 1311867286.4177770615 0.1012741551 0.1068453222 0.2224369198 0.0063364098 0.3958430000 0.0965180000 0.0939690000 0.0000000000 0.1950170000 0.0018000000 149027675 0 402718720 3.9212274551 3.8401534557 4.3138203621 3477 1311867286.4494199753 0.1005355120 0.1068435074 0.2224369198 0.0063356553 0.5799060000 0.0850980000 0.0585080000 0.0299470000 0.1959800000 0.2018890000 149031347 0 402718720 3.9217433929 3.8401179314 4.3133258820 3478 1311867286.4855709076 0.1002451628 0.1068416103 0.2224369198 0.0063363816 0.3486440000 0.0844150000 0.0552150000 0.0000000000 0.1986800000 0.0018070000 149035075 0 402718720 3.9218909740 3.8411393166 4.3130826950 3479 1311867286.5190370083 0.0991290733 0.1068393934 0.2224369198 0.0063358135 0.3936960000 0.0840220000 0.0701630000 0.0299460000 0.1992500000 0.0018000000 149038859 0 402718720 3.9237384796 3.8422269821 4.3130407333 3480 1311867286.5512158871 0.0992569104 0.1068372145 0.2224369198 0.0063350433 0.3576420000 0.0844250000 0.0628790000 0.0000000000 0.2000030000 0.0018040000 149042475 0 402718720 3.9233539104 3.8417932987 4.3127279282 3481 1311867286.5855200291 0.0986985490 0.1068348765 0.2224369198 0.0063344280 0.6345570000 0.0924410000 0.0933660000 0.0299340000 0.2023330000 0.2078860000 149046315 0 402718720 3.9244127274 3.8423619270 4.3127660751 3482 1311867286.6190819740 0.0985898450 0.1068325086 0.2224369198 0.0063342116 0.3545270000 0.0843560000 0.0576830000 0.0000000000 0.2020570000 0.0018150000 149049987 0 402718720 3.9247460365 3.8433129787 4.3130431175 3483 1311867286.6500060558 0.0989429355 0.1068302434 0.2224369198 0.0063339048 0.3866310000 0.0841180000 0.0606900000 0.0299700000 0.2015210000 0.0018170000 149053603 0 402718720 3.9244349003 3.8424685001 4.3128833771 3484 1311867286.6856429577 0.0982941911 0.1068277934 0.2224369198 0.0063338969 0.3685830000 0.0842650000 0.0702950000 0.0000010000 0.2037110000 0.0017960000 149057331 0 402718720 3.9254496098 3.8410446644 4.3127460480 3485 1311867286.7176160812 0.0981525704 0.1068253041 0.2224369198 0.0063336676 0.6333870000 0.0839680000 0.0927630000 0.0299300000 0.2063260000 0.2118510000 149061003 0 402718720 3.9260241985 3.8420851231 4.3127961159 3486 1311867286.7495489120 0.0988536775 0.1068230173 0.2224369198 0.0063332078 0.3673790000 0.0956600000 0.0547550000 0.0000000000 0.2065730000 0.0018010000 149064731 0 402718720 3.9248809814 3.8424570560 4.3127007484 3487 1311867286.7856459618 0.0988669321 0.1068207357 0.2224369198 0.0063330068 0.3777470000 0.0840390000 0.0466090000 0.0297750000 0.2068810000 0.0017690000 149068459 0 402718720 3.9253311157 3.8419437408 4.3129134178 3488 1311867286.8176259995 0.0981502086 0.1068182498 0.2224369198 0.0063321899 0.3784740000 0.0840690000 0.0776250000 0.0000000000 0.2063470000 0.0018070000 149072187 0 402718720 3.9271857738 3.8421540260 4.3133006096 3489 1311867286.8535819054 0.0985186547 0.1068158711 0.2224369198 0.0063314244 0.6103900000 0.0842990000 0.0737110000 0.0294550000 0.2042610000 0.2098340000 149075971 0 402718720 3.9269599915 3.8419609070 4.3134355545 3490 1311867286.8868150711 0.0989444181 0.1068136156 0.2224369198 0.0063305740 0.3655430000 0.0842070000 0.0657280000 0.0000010000 0.2042420000 0.0019010000 149079643 0 402718720 3.9261066914 3.8413856030 4.3132734299 3491 1311867286.9174380302 0.0978278443 0.1068110416 0.2224369198 0.0063297245 0.4129050000 0.1041350000 0.0623230000 0.0298910000 0.2050030000 0.0021070000 149083259 0 402718720 3.9280662537 3.8415591717 4.3135600090 3492 1311867286.9543609619 0.0971787795 0.1068082833 0.2224369198 0.0063294513 0.4082950000 0.1067300000 0.0732650000 0.0000000000 0.2163850000 0.0024550000 149087099 0 402718720 3.9294555187 3.8436632156 4.3138470650 3493 1311867286.9854118824 0.0973479822 0.1068055749 0.2224369198 0.0063293483 0.6667520000 0.1067910000 0.0934610000 0.0357680000 0.2139030000 0.2082630000 149090715 0 402718720 3.9292004108 3.8427515030 4.3139047623 3494 1311867287.0174310207 0.0975204408 0.1068029174 0.2224369198 0.0063286957 0.3895560000 0.0840850000 0.0933460000 0.0000000000 0.2016760000 0.0017990000 149094387 0 402718720 3.9292075634 3.8415584564 4.3138718605 3495 1311867287.0547020435 0.0982836336 0.1068004799 0.2224369198 0.0063316561 0.4201290000 0.0843170000 0.0933460000 0.0298870000 0.2021850000 0.0018010000 149098227 0 402718720 3.9292378426 3.8431305885 4.3139128685 3496 1311867287.0856859684 0.0978450775 0.1067979183 0.2224369198 0.0063309693 0.3528230000 0.0950840000 0.0472370000 0.0000000000 0.2000730000 0.0017960000 149101899 0 402718720 3.9296760559 3.8437047005 4.3138160706 3497 1311867287.1178219318 0.0982391387 0.1067954708 0.2224369198 0.0063311806 0.5997920000 0.0967970000 0.0626420000 0.0298840000 0.1981530000 0.2037220000 149105515 0 402718720 3.9292628765 3.8429145813 4.3136067390 3498 1311867287.1537048817 0.0978349373 0.1067929092 0.2224369198 0.0063303154 0.4053530000 0.0981740000 0.0982150000 0.0000010000 0.1982050000 0.0019060000 149109299 0 402718720 3.9302392006 3.8431994915 4.3135914803 3499 1311867287.1874449253 0.0980483145 0.1067904100 0.2224369198 0.0063301165 0.3717210000 0.0846550000 0.0498210000 0.0294700000 0.1974230000 0.0018130000 149113027 0 402718720 3.9302322865 3.8443131447 4.3136081696 3500 1311867287.2175579071 0.0980719030 0.1067879190 0.2224369198 0.0063311174 0.3498720000 0.0846570000 0.0580470000 0.0000010000 0.1964870000 0.0018980000 149116643 0 402718720 3.9303243160 3.8429877758 4.3135547638 3501 1311867287.2536680698 0.0984617397 0.1067855408 0.2224369198 0.0063304784 0.6278590000 0.0949370000 0.0935860000 0.0294230000 0.1978820000 0.2034370000 149120427 0 402718720 3.9299261570 3.8429129124 4.3134779930 3502 1311867287.2870221138 0.0982867554 0.1067831140 0.2224369198 0.0063298924 0.3402110000 0.0845990000 0.0472580000 0.0000010000 0.1979340000 0.0018000000 149124155 0 402718720 3.9303817749 3.8437228203 4.3133964539 3503 1311867287.3175630569 0.0985458866 0.1067807625 0.2224369198 0.0063296163 0.4124490000 0.0840040000 0.0913310000 0.0293990000 0.1972770000 0.0017960000 149127771 0 402718720 3.9298760891 3.8427605629 4.3131442070 3504 1311867287.3540940285 0.0987007245 0.1067784565 0.2224369198 0.0063287811 0.3568770000 0.0845450000 0.0630540000 0.0000010000 0.1989080000 0.0018060000 149131611 0 402718720 3.9297516346 3.8424949646 4.3129448891 3505 1311867287.3855540752 0.0983637199 0.1067760557 0.2224369198 0.0063279507 0.5816000000 0.0844190000 0.0548560000 0.0294390000 0.1993660000 0.2048680000 149135283 0 402718720 3.9303326607 3.8430168629 4.3128442764 3506 1311867287.4175760746 0.0981220528 0.1067735874 0.2224369198 0.0063271533 0.3928000000 0.0973190000 0.0858470000 0.0000000000 0.1991680000 0.0018140000 149138899 0 402718720 3.9308671951 3.8422687054 4.3126926422 3507 1311867287.4535288811 0.0983694047 0.1067711910 0.2224369198 0.0063263419 0.3880520000 0.0844490000 0.0626950000 0.0299740000 0.2005060000 0.0018130000 149142683 0 402718720 3.9307525158 3.8413271904 4.3125023842 3508 1311867287.4867310524 0.0974816829 0.1067685429 0.2224369198 0.0063272903 0.3894600000 0.0841810000 0.0928510000 0.0000010000 0.2019740000 0.0018030000 149146355 0 402718720 3.9310240746 3.8425278664 4.3124289513 3509 1311867287.5174999237 0.0986335427 0.1067662246 0.2224369198 0.0063310843 0.5853710000 0.0843200000 0.0548060000 0.0294240000 0.2012790000 0.2068490000 149150027 0 402718720 3.9303297997 3.8426077366 4.3122792244 3510 1311867287.5534870625 0.0975824296 0.1067636081 0.2224369198 0.0063307692 0.3547830000 0.0963270000 0.0470820000 0.0000000000 0.2009140000 0.0018150000 149153811 0 402718720 3.9318838120 3.8426134586 4.3124337196 3511 1311867287.5869519711 0.0980225429 0.1067611185 0.2224369198 0.0063300411 0.4372700000 0.0989470000 0.0986690000 0.0294200000 0.1998070000 0.0018120000 149157539 0 402718720 3.9313447475 3.8429517746 4.3125791550 3512 1311867287.6176569462 0.0978042260 0.1067585681 0.2224369198 0.0063307545 0.3686100000 0.0843620000 0.0740900000 0.0000010000 0.1994180000 0.0018990000 149161155 0 402718720 3.9314825535 3.8417894840 4.3125271797 3513 1311867287.6539158821 0.0974827707 0.1067559277 0.2224369198 0.0063299140 0.6316510000 0.0843520000 0.0902560000 0.0299510000 0.2012770000 0.2162780000 149164995 0 402718720 3.9319956303 3.8420774937 4.3123984337 3514 1311867287.6875660419 0.0977912843 0.1067533766 0.2224369198 0.0063311186 0.3964660000 0.1065460000 0.0630200000 0.0000010000 0.2149160000 0.0024660000 149168667 0 402718720 3.9308719635 3.8435978889 4.3123898506 3515 1311867287.7176280022 0.0980125219 0.1067508899 0.2224369198 0.0063305540 0.4922040000 0.1068800000 0.1242840000 0.0357710000 0.2132750000 0.0024770000 149172283 0 402718720 3.9304339886 3.8433892727 4.3125128746 3516 1311867287.7553908825 0.0977432281 0.1067483280 0.2224369198 0.0063304550 0.4149810000 0.1068040000 0.0833800000 0.0000010000 0.2127600000 0.0024620000 149176123 0 402718720 3.9310243130 3.8426475525 4.3126301765 3517 1311867287.7872428894 0.0978259891 0.1067457910 0.2224369198 0.0063296392 0.6213630000 0.1070640000 0.0630920000 0.0358240000 0.2014380000 0.2051820000 149179739 0 402718720 3.9311773777 3.8432943821 4.3128013611 3518 1311867287.8260099888 0.0981021523 0.1067433341 0.2224369198 0.0063288622 0.3756820000 0.0846310000 0.0825660000 0.0000000000 0.1976720000 0.0018990000 149183579 0 402718720 3.9311213493 3.8439321518 4.3131632805 3519 1311867287.8536510468 0.0984907523 0.1067409889 0.2224369198 0.0063284541 0.4198850000 0.0843000000 0.0982570000 0.0299950000 0.1965420000 0.0019020000 149187139 0 402718720 3.9311413765 3.8429026604 4.3133716583 3520 1311867287.8931109905 0.0992216095 0.1067388527 0.2224369198 0.0063281292 0.3500640000 0.0845400000 0.0563880000 0.0000010000 0.1987050000 0.0017600000 149190923 0 402718720 3.9309022427 3.8432381153 4.3137350082 3521 1311867287.9175710678 0.0988144577 0.1067366021 0.2224369198 0.0063282028 0.6095270000 0.1129470000 0.0580770000 0.0299490000 0.1969730000 0.2029080000 149194371 0 402718720 3.9327907562 3.8449656963 4.3143525124 3522 1311867287.9535610676 0.0987985879 0.1067343483 0.2224369198 0.0063343106 0.3453000000 0.0845650000 0.0551690000 0.0000000000 0.1951180000 0.0018080000 149198099 0 402718720 3.9327836037 3.8429841995 4.3143935204 3523 1311867287.9868519306 0.0993764773 0.1067322598 0.2224369198 0.0063342473 0.4430060000 0.1058020000 0.0989850000 0.0299250000 0.1978070000 0.0018210000 149201771 0 402718720 3.9335129261 3.8408243656 4.3142013550 3524 1311867288.0178821087 0.0992008001 0.1067301226 0.2224369198 0.0063350161 0.3772600000 0.0842720000 0.0822710000 0.0000000000 0.1998610000 0.0018930000 149205443 0 402718720 3.9349043369 3.8423335552 4.3142452240 3525 1311867288.0536389351 0.0995419472 0.1067280834 0.2224369198 0.0063348191 0.5862450000 0.0849240000 0.0580790000 0.0299890000 0.1989100000 0.2045080000 149209227 0 402718720 3.9342367649 3.8425393105 4.3141541481 3526 1311867288.0854179859 0.0992731452 0.1067259691 0.2224369198 0.0063349815 0.3636290000 0.0973440000 0.0551370000 0.0000010000 0.2006530000 0.0017920000 149212843 0 402718720 3.9348292351 3.8400454521 4.3139882088 3527 1311867288.1175940037 0.0995548666 0.1067239359 0.2224369198 0.0063348645 0.4196190000 0.0827010000 0.0925940000 0.0297840000 0.2032370000 0.0017590000 149216571 0 402718720 3.9349031448 3.8406693935 4.3140797615 3528 1311867288.1540820599 0.0990166664 0.1067217513 0.2224369198 0.0063350552 0.3524750000 0.0843760000 0.0549480000 0.0000010000 0.2026290000 0.0017970000 149220355 0 402718720 3.9358220100 3.8403887749 4.3140134811 3529 1311867288.1854550838 0.0998448208 0.1067198026 0.2224369198 0.0063343244 0.6316630000 0.0845730000 0.0936460000 0.0294140000 0.2048820000 0.2103940000 149224027 0 402718720 3.9347810745 3.8378472328 4.3136930466 3530 1311867288.2175340652 0.0993323699 0.1067177098 0.2224369198 0.0063357140 0.3876070000 0.0841690000 0.0851950000 0.0000010000 0.2077950000 0.0018110000 149227587 0 402718720 3.9354870319 3.8391525745 4.3134784698 3531 1311867288.2535810471 0.0989814177 0.1067155189 0.2224369198 0.0063351867 0.4049770000 0.0948500000 0.0633570000 0.0297680000 0.2065360000 0.0017750000 149231427 0 402718720 3.9357497692 3.8399238586 4.3132047653 3532 1311867288.2854719162 0.0995462835 0.1067134891 0.2224369198 0.0063356786 0.3988170000 0.0841850000 0.0980650000 0.0000010000 0.2058160000 0.0018930000 149235043 0 402718720 3.9344739914 3.8379771709 4.3125896454 3533 1311867288.3175830841 0.0991591513 0.1067113509 0.2224369198 0.0063353234 0.5938990000 0.0842180000 0.0493850000 0.0299060000 0.2079270000 0.2134890000 149238771 0 402718720 3.9342374802 3.8385903835 4.3124141693 3534 1311867288.3535211086 0.0987991691 0.1067091120 0.2224369198 0.0063344796 0.3593500000 0.0836530000 0.0573520000 0.0000010000 0.2075820000 0.0018910000 149242555 0 402718720 3.9343972206 3.8392627239 4.3125534058 3535 1311867288.3858890533 0.0988976359 0.1067069022 0.2224369198 0.0063342648 0.3783770000 0.0840060000 0.0468790000 0.0293810000 0.2075860000 0.0018070000 149246227 0 402718720 3.9335904121 3.8382670879 4.3125100136 3536 1311867288.4177610874 0.0988263637 0.1067046736 0.2224369198 0.0063335631 0.3859620000 0.1095610000 0.0573530000 0.0000000000 0.2082150000 0.0018950000 149249899 0 402718720 3.9329345226 3.8385720253 4.3125028610 3537 1311867288.4560298920 0.0986823738 0.1067024055 0.2224369198 0.0063329572 0.6001760000 0.0839480000 0.0576400000 0.0298990000 0.2071780000 0.2128040000 149253739 0 402718720 3.9323692322 3.8393554688 4.3127789497 3538 1311867288.4854650497 0.0986604169 0.1067001324 0.2224369198 0.0063322783 0.3582880000 0.0839760000 0.0574790000 0.0000010000 0.2060170000 0.0018990000 149257411 0 402718720 3.9315550327 3.8391029835 4.3127851486 3539 1311867288.5176889896 0.0986180454 0.1066978487 0.2224369198 0.0063316890 0.3882570000 0.0840670000 0.0575110000 0.0299330000 0.2062410000 0.0018080000 149261027 0 402718720 3.9312298298 3.8382539749 4.3130931854 3540 1311867288.5544929504 0.0984329581 0.1066955140 0.2224369198 0.0063312511 0.4280720000 0.0967170000 0.0998280000 0.0000010000 0.2193780000 0.0024580000 149264811 0 402718720 3.9308660030 3.8392786980 4.3131484985 3541 1311867288.5874340534 0.0988523364 0.1066932990 0.2224369198 0.0063304368 0.7170480000 0.1063890000 0.1215260000 0.0357850000 0.2188890000 0.2248070000 149268483 0 402718720 3.9294316769 3.8391907215 4.3129944801 3542 1311867288.6175410748 0.0990505368 0.1066911413 0.2224369198 0.0063296126 0.4607910000 0.1058490000 0.1235070000 0.0000010000 0.2193650000 0.0024580000 149272099 0 402718720 3.9288909435 3.8386592865 4.3129882812 3543 1311867288.6551198959 0.0991996974 0.1066890268 0.2224369198 0.0063289795 0.4137400000 0.1064690000 0.0528610000 0.0358080000 0.2081670000 0.0018110000 149275939 0 402718720 3.9283826351 3.8395335674 4.3128924370 3544 1311867288.6874110699 0.0995211974 0.1066870043 0.2224369198 0.0063281026 0.3932110000 0.0840570000 0.0929030000 0.0000000000 0.2057610000 0.0018040000 149279611 0 402718720 3.9275283813 3.8393199444 4.3127574921 3545 1311867288.7177178860 0.0998754203 0.1066850829 0.2224369198 0.0063272445 0.6317220000 0.0841890000 0.0911490000 0.0299910000 0.2059800000 0.2114470000 149283227 0 402718720 3.9267714024 3.8391907215 4.3125295639 3546 1311867288.7560660839 0.0995836779 0.1066830802 0.2224369198 0.0063263922 0.3461600000 0.0825100000 0.0470680000 0.0000010000 0.2060120000 0.0017960000 149287067 0 402718720 3.9269573689 3.8401174545 4.3122735023 3547 1311867288.7855091095 0.0997342318 0.1066811211 0.2224369198 0.0063255599 0.3761080000 0.0840500000 0.0470410000 0.0294070000 0.2051570000 0.0018040000 149290683 0 402718720 3.9268815517 3.8394105434 4.3121013641 3548 1311867288.8192400932 0.1002731174 0.1066793150 0.2224369198 0.0063247639 0.4198680000 0.1091910000 0.0932260000 0.0000000000 0.2060290000 0.0018040000 149294467 0 402718720 3.9260051250 3.8392860889 4.3118777275 3549 1311867288.8543450832 0.0999970064 0.1066774322 0.2224369198 0.0063242217 0.5976630000 0.0846920000 0.0576720000 0.0299790000 0.2053290000 0.2110360000 149298195 0 402718720 3.9266386032 3.8401281834 4.3116173744 3550 1311867288.8855559826 0.1000013798 0.1066755516 0.2224369198 0.0063235029 0.3411800000 0.0846740000 0.0415280000 0.0000010000 0.2044660000 0.0017980000 149301867 0 402718720 3.9264743328 3.8396043777 4.3113718033 3551 1311867288.9176120758 0.1001521125 0.1066737145 0.2224369198 0.0063227173 0.4273880000 0.0845500000 0.0978300000 0.0299420000 0.2041840000 0.0019110000 149305483 0 402718720 3.9265305996 3.8395936489 4.3112654686 3552 1311867288.9599480629 0.1007090956 0.1066720353 0.2224369198 0.0063223731 0.3649720000 0.0842090000 0.0657570000 0.0000010000 0.2043850000 0.0018180000 149309491 0 402718720 3.9257965088 3.8406891823 4.3111267090 3553 1311867288.9855918884 0.1004951820 0.1066702968 0.2224369198 0.0063217419 0.5825600000 0.0844230000 0.0471230000 0.0300030000 0.2033810000 0.2089000000 149312995 0 402718720 3.9263455868 3.8402905464 4.3111157417 3554 1311867289.0176560879 0.1004855037 0.1066685566 0.2224369198 0.0063211363 0.3528320000 0.0842930000 0.0550770000 0.0000010000 0.2028940000 0.0017960000 149316611 0 402718720 3.9265663624 3.8401572704 4.3109965324 3555 1311867289.0535120964 0.1003272980 0.1066667728 0.2224369198 0.0063215169 0.4212600000 0.0845620000 0.0934980000 0.0299730000 0.2027260000 0.0018030000 149320451 0 402718720 3.9270052910 3.8397254944 4.3110651970 3556 1311867289.0855109692 0.1006153971 0.1066650711 0.2224369198 0.0063207647 0.4085550000 0.0967420000 0.0982590000 0.0000010000 0.2027300000 0.0018990000 149324067 0 402718720 3.9267463684 3.8397381306 4.3111462593 3557 1311867289.1175429821 0.1004369408 0.1066633201 0.2224369198 0.0063201498 0.6256860000 0.0837240000 0.0924610000 0.0292290000 0.2031000000 0.2084120000 149327739 0 402718720 3.9272570610 3.8400239944 4.3111982346 3558 1311867289.1545929909 0.1006483212 0.1066616296 0.2224369198 0.0063192707 0.3918530000 0.0847560000 0.0935190000 0.0000000000 0.2030100000 0.0017960000 149331635 0 402718720 3.9270322323 3.8400466442 4.3111515045 3559 1311867289.1856400967 0.1008535326 0.1066599976 0.2224369198 0.0063184621 0.3754800000 0.0848180000 0.0472940000 0.0294800000 0.2033900000 0.0018140000 149335195 0 402718720 3.9266071320 3.8392701149 4.3110766411 3560 1311867289.2185060978 0.1005116403 0.1066582706 0.2224369198 0.0063180062 0.3384830000 0.0844920000 0.0395260000 0.0000000000 0.2038530000 0.0018090000 149338923 0 402718720 3.9268991947 3.8397502899 4.3111286163 3561 1311867289.2550480366 0.1005492285 0.1066565550 0.2224369198 0.0063183794 0.6119430000 0.1194880000 0.0415150000 0.0299640000 0.2032300000 0.2090070000 149342763 0 402718720 3.9268374443 3.8392069340 4.3111371994 3562 1311867289.2853870392 0.1004929170 0.1066548246 0.2224369198 0.0063178198 0.3527380000 0.0844820000 0.0531000000 0.0000010000 0.2045730000 0.0018050000 149346435 0 402718720 3.9269149303 3.8383359909 4.3110847473 3563 1311867289.3176290989 0.0999944359 0.1066529553 0.2224369198 0.0063171484 0.3788710000 0.0842470000 0.0495100000 0.0294530000 0.2048160000 0.0018920000 149350051 0 402718720 3.9273328781 3.8388762474 4.3109159470 3564 1311867289.3539168835 0.0999818519 0.1066510835 0.2224369198 0.0063163927 0.3934640000 0.0842810000 0.0936350000 0.0000010000 0.2049480000 0.0017920000 149353835 0 402718720 3.9269800186 3.8390176296 4.3109140396 3565 1311867289.3861899376 0.1000990421 0.1066492456 0.2224369198 0.0063155698 0.6203880000 0.0843240000 0.0822880000 0.0299690000 0.2046130000 0.2103910000 149357563 0 402718720 3.9261813164 3.8386452198 4.3108515739 3566 1311867289.4177041054 0.0995598435 0.1066472576 0.2224369198 0.0063154876 0.3675930000 0.0942160000 0.0573110000 0.0000010000 0.2054560000 0.0018000000 149361179 0 402718720 3.9269185066 3.8394777775 4.3110756874 3567 1311867289.4536058903 0.0995287970 0.1066452619 0.2224369198 0.0063147474 0.4267400000 0.0844860000 0.0983250000 0.0299480000 0.2031310000 0.0019070000 149364963 0 402718720 3.9267306328 3.8398950100 4.3114705086 3568 1311867289.4859669209 0.0996371880 0.1066432978 0.2224369198 0.0063145878 0.3471910000 0.0844690000 0.0496480000 0.0000000000 0.2021730000 0.0019130000 149368691 0 402718720 3.9261062145 3.8387076855 4.3115544319 3569 1311867289.5183238983 0.0997047797 0.1066413537 0.2224369198 0.0063144680 0.6001580000 0.0842840000 0.0657410000 0.0300080000 0.2027640000 0.2083810000 149372307 0 402718720 3.9259142876 3.8401086330 4.3119778633 3570 1311867289.5548820496 0.0996524990 0.1066393960 0.2224369198 0.0063136188 0.3833560000 0.0955880000 0.0762780000 0.0000000000 0.2008980000 0.0018000000 149376147 0 402718720 3.9254870415 3.8408074379 4.3123302460 3571 1311867289.5856130123 0.1001633257 0.1066375825 0.2224369198 0.0063146462 0.3944340000 0.0916190000 0.0629810000 0.0294420000 0.1997740000 0.0017980000 149379819 0 402718720 3.9244322777 3.8387577534 4.3122506142 3572 1311867289.6176490784 0.1001526862 0.1066357670 0.2224369198 0.0063141876 0.3544950000 0.0845000000 0.0577850000 0.0000000000 0.2012140000 0.0018900000 149383435 0 402718720 3.9241321087 3.8395516872 4.3125157356 3573 1311867289.6536390781 0.0996351689 0.1066338077 0.2224369198 0.0063135865 0.5785330000 0.0844000000 0.0499460000 0.0299430000 0.1997400000 0.2055400000 149387219 0 402718720 3.9243280888 3.8413560390 4.3130106926 3574 1311867289.6856849194 0.0994094238 0.1066317863 0.2224369198 0.0063132573 0.3632520000 0.0977260000 0.0580190000 0.0000010000 0.1967690000 0.0017980000 149390891 0 402718720 3.9236915112 3.8408415318 4.3134441376 3575 1311867289.7204349041 0.0998483971 0.1066298889 0.2224369198 0.0063128757 0.4033380000 0.0959830000 0.0708550000 0.0299350000 0.1959490000 0.0018120000 149394675 0 402718720 3.9225292206 3.8411841393 4.3142395020 3576 1311867289.7564179897 0.0998342708 0.1066279885 0.2224369198 0.0063126751 0.3578570000 0.0984130000 0.0555450000 0.0000010000 0.1931690000 0.0018090000 149398403 0 402718720 3.9222958088 3.8419337273 4.3150343895 3577 1311867289.7855679989 0.1004037037 0.1066262485 0.2224369198 0.0063123163 0.6076780000 0.0850250000 0.0991630000 0.0294940000 0.1895660000 0.1952650000 149402019 0 402718720 3.9212226868 3.8410627842 4.3155603409 3578 1311867289.8240370750 0.1002320498 0.1066244614 0.2224369198 0.0063117981 0.3445580000 0.0849310000 0.0584010000 0.0000010000 0.1902150000 0.0019060000 149405859 0 402718720 3.9209706783 3.8395383358 4.3159432411 3579 1311867289.8541870117 0.1000323668 0.1066226195 0.2224369198 0.0063121075 0.3743570000 0.0847830000 0.0583350000 0.0299400000 0.1906120000 0.0018210000 149409531 0 402718720 3.9210557938 3.8415768147 4.3165574074 3580 1311867289.8855679035 0.1004886255 0.1066209061 0.2224369198 0.0063120851 0.3788390000 0.0849210000 0.0945310000 0.0000010000 0.1887040000 0.0017980000 149413147 0 402718720 3.9202733040 3.8408644199 4.3169441223 3581 1311867289.9200530052 0.1013260335 0.1066194275 0.2224369198 0.0063126843 0.5996450000 0.1065900000 0.0708500000 0.0298960000 0.1888550000 0.1944640000 149416875 0 402718720 3.9192609787 3.8396980762 4.3173098564 3582 1311867289.9536409378 0.1007013842 0.1066177753 0.2224369198 0.0063124709 0.3462880000 0.0849310000 0.0612130000 0.0000010000 0.1893300000 0.0017980000 149420603 0 402718720 3.9191279411 3.8402523994 4.3177199364 3583 1311867289.9855279922 0.1003368422 0.1066160223 0.2224369198 0.0063116093 0.4109770000 0.0848730000 0.0972010000 0.0299470000 0.1879350000 0.0018860000 149424219 0 402718720 3.9191427231 3.8399989605 4.3180155754 3584 1311867290.0232169628 0.1006127968 0.1066143473 0.2224369198 0.0063129183 0.3795070000 0.0848490000 0.0945440000 0.0000000000 0.1893950000 0.0017970000 149428115 0 402718720 3.9185545444 3.8375129700 4.3181772232 3585 1311867290.0535910130 0.1002456397 0.1066125708 0.2224369198 0.0063128149 0.5875790000 0.0969180000 0.0630220000 0.0293270000 0.1919020000 0.1974810000 149431731 0 402718720 3.9190690517 3.8386044502 4.3185954094 3586 1311867290.0854740143 0.1004045233 0.1066108396 0.2224369198 0.0063124092 0.3542140000 0.0956680000 0.0561680000 0.0000010000 0.1916150000 0.0018130000 149435459 0 402718720 3.9186687469 3.8385522366 4.3189911842 3587 1311867290.1248800755 0.1003967896 0.1066091073 0.2224369198 0.0063122720 0.3836250000 0.1088660000 0.0418800000 0.0299810000 0.1921880000 0.0018200000 149439243 0 402718720 3.9187047482 3.8373401165 4.3193316460 3588 1311867290.1536118984 0.1003002003 0.1066073489 0.2224369198 0.0063118133 0.3390200000 0.0849480000 0.0502360000 0.0000000000 0.1931320000 0.0018000000 149442859 0 402718720 3.9190714359 3.8387036324 4.3198251724 3589 1311867290.1856379509 0.1001172215 0.1066055406 0.2224369198 0.0063111571 0.5763460000 0.0847880000 0.0634080000 0.0299460000 0.1918150000 0.1974810000 149446587 0 402718720 3.9197454453 3.8391082287 4.3202199936 3590 1311867290.2225489616 0.1004399732 0.1066038232 0.2224369198 0.0063104952 0.3941430000 0.0975610000 0.0945580000 0.0000010000 0.1913070000 0.0018060000 149450315 0 402718720 3.9192209244 3.8387358189 4.3204832077 3591 1311867290.2540318966 0.0998159498 0.1066019329 0.2224369198 0.0063106093 0.3915630000 0.1020560000 0.0581120000 0.0298900000 0.1907230000 0.0018050000 149453987 0 402718720 3.9206829071 3.8399984837 4.3210139275 3592 1311867290.2892379761 0.1003538147 0.1066001935 0.2224369198 0.0063102490 0.3508250000 0.0848170000 0.0664170000 0.0000010000 0.1888470000 0.0018210000 149457771 0 402718720 3.9197766781 3.8393728733 4.3214159012 3593 1311867290.3220748901 0.1007180139 0.1065985563 0.2224369198 0.0063100778 0.5747120000 0.0847320000 0.0665470000 0.0299240000 0.1894260000 0.1951430000 149461443 0 402718720 3.9193005562 3.8384239674 4.3214445114 3594 1311867290.3587789536 0.1002601832 0.1065967927 0.2224369198 0.0063097906 0.3804740000 0.0847190000 0.0939640000 0.0000010000 0.1910380000 0.0018020000 149465227 0 402718720 3.9199585915 3.8392214775 4.3215260506 3595 1311867290.3864240646 0.1000156403 0.1065949621 0.2224369198 0.0063089590 0.4084690000 0.0845310000 0.0939230000 0.0294250000 0.1898540000 0.0017990000 149468731 0 402718720 3.9201045036 3.8389568329 4.3214979172 3596 1311867290.4216320515 0.0998496935 0.1065930863 0.2224369198 0.0063082839 0.3900500000 0.0948190000 0.0935780000 0.0000010000 0.1909090000 0.0017970000 149472571 0 402718720 3.9193651676 3.8379898071 4.3212165833 3597 1311867290.4578390121 0.1000909507 0.1065912787 0.2224369198 0.0063078647 0.6072940000 0.0846240000 0.0939220000 0.0299150000 0.1920940000 0.1977720000 149476131 0 402718720 3.9181907177 3.8392436504 4.3212661743 3598 1311867290.4859950542 0.1000406444 0.1065894580 0.2224369198 0.0063072250 0.3406240000 0.0848770000 0.0397890000 0.0000010000 0.2035150000 0.0024880000 149479691 0 402718720 3.9181306362 3.8391489983 4.3211092949 3599 1311867290.5223400593 0.1001439840 0.1065876671 0.2224369198 0.0063073053 0.4854380000 0.1069990000 0.1252900000 0.0357530000 0.2050070000 0.0024660000 149483475 0 402718720 3.9176144600 3.8374426365 4.3209414482 3600 1311867290.5537059307 0.1004088670 0.1065859508 0.2224369198 0.0063075742 0.4376640000 0.1070890000 0.1252040000 0.0000010000 0.1945720000 0.0018030000 149487147 0 402718720 3.9172122478 3.8387432098 4.3208637238 3601 1311867290.5855538845 0.1006369889 0.1065842988 0.2224369198 0.0063073810 0.6024120000 0.0978440000 0.0747250000 0.0299420000 0.1925860000 0.1983060000 149490875 0 402718720 3.9163157940 3.8392391205 4.3205280304 3602 1311867290.6221020222 0.1002897099 0.1065825513 0.2224369198 0.0063069960 0.3843270000 0.0843950000 0.0956860000 0.0000000000 0.1934340000 0.0018100000 149494603 0 402718720 3.9167318344 3.8384034634 4.3202481270 3603 1311867290.6536018848 0.1006109565 0.1065808939 0.2224369198 0.0063080169 0.3657840000 0.0842160000 0.0474930000 0.0294280000 0.1938660000 0.0018120000 149498275 0 402718720 3.9164865017 3.8398733139 4.3200488091 3604 1311867290.6857531071 0.1008192450 0.1065792952 0.2224369198 0.0063071629 0.3353380000 0.0846420000 0.0475570000 0.0000010000 0.1922960000 0.0018050000 149501891 0 402718720 3.9165441990 3.8401584625 4.3199300766 3605 1311867290.7256150246 0.1007698998 0.1065776837 0.2224369198 0.0063080195 0.6180920000 0.0953160000 0.0941210000 0.0293550000 0.1923030000 0.1979450000 149505843 0 402718720 3.9170429707 3.8383347988 4.3195800781 3606 1311867290.7539739609 0.1011603773 0.1065761814 0.2224369198 0.0063077999 0.3939450000 0.0952530000 0.0938860000 0.0000010000 0.1940210000 0.0018100000 149509403 0 402718720 3.9166438580 3.8390042782 4.3193798065 3607 1311867290.7866060734 0.1009995937 0.1065746353 0.2224369198 0.0063069706 0.3586340000 0.0845730000 0.0398000000 0.0299280000 0.1934410000 0.0018060000 149513019 0 402718720 3.9172344208 3.8395853043 4.3190269470 3608 1311867290.8231720924 0.1010211483 0.1065730961 0.2224369198 0.0063067501 0.3831630000 0.0844130000 0.0938490000 0.0000000000 0.1941540000 0.0018140000 149516859 0 402718720 3.9173476696 3.8382041454 4.3184227943 3609 1311867290.8556039333 0.1011589542 0.1065715959 0.2224369198 0.0063061602 0.5601300000 0.0845660000 0.0396110000 0.0299460000 0.1957180000 0.2013240000 149520531 0 402718720 3.9175765514 3.8382861614 4.3181290627 3610 1311867290.8876988888 0.1015165076 0.1065701956 0.2224369198 0.0063083808 0.3308560000 0.0846420000 0.0395970000 0.0000010000 0.1958100000 0.0018010000 149524203 0 402718720 3.9181592464 3.8383650780 4.3177604675 3611 1311867290.9227120876 0.1015316769 0.1065688003 0.2224369198 0.0063075827 0.4375690000 0.0926690000 0.0945400000 0.0299140000 0.2080480000 0.0024740000 149527931 0 402718720 3.9184606075 3.8377437592 4.3172149658 3612 1311867290.9537110329 0.1010211334 0.1065672644 0.2224369198 0.0063086642 0.4535550000 0.1068160000 0.1244540000 0.0000010000 0.2099810000 0.0024650000 149531603 0 402718720 3.9187171459 3.8377177715 4.3168363571 3613 1311867290.9906909466 0.1010771841 0.1065657449 0.2224369198 0.0063080479 0.7055440000 0.1068940000 0.1245770000 0.0364610000 0.2108680000 0.2168980000 149535443 0 402718720 3.9192893505 3.8379564285 4.3165369034 3614 1311867291.0239291191 0.1012927592 0.1065642858 0.2224369198 0.0063075546 0.4540980000 0.1067010000 0.1244560000 0.0000010000 0.2106230000 0.0024620000 149539171 0 402718720 3.9195568562 3.8374826908 4.3162493706 3615 1311867291.0558199883 0.1009547114 0.1065627341 0.2224369198 0.0063068815 0.3878090000 0.0931420000 0.0549790000 0.0299150000 0.1990310000 0.0018060000 149542843 0 402718720 3.9206926823 3.8367075920 4.3158960342 3616 1311867291.0934820175 0.1007404923 0.1065611240 0.2224369198 0.0063068566 0.3757370000 0.0949430000 0.0705710000 0.0000000000 0.1994830000 0.0017990000 149546627 0 402718720 3.9217240810 3.8380625248 4.3156561852 3617 1311867291.1203110218 0.1002983451 0.1065593925 0.2224369198 0.0063067480 0.5805280000 0.0840990000 0.0549470000 0.0299040000 0.1985150000 0.2040520000 149550187 0 402718720 3.9226586819 3.8371913433 4.3152427673 3618 1311867291.1541891098 0.1014595553 0.1065579829 0.2224369198 0.0063078446 0.3932720000 0.0843780000 0.0983760000 0.0000010000 0.1994770000 0.0019070000 149553803 0 402718720 3.9220325947 3.8368835449 4.3146667480 3619 1311867291.1891989708 0.1007272527 0.1065563718 0.2224369198 0.0063080546 0.3988170000 0.0843910000 0.0739330000 0.0299570000 0.1997720000 0.0018100000 149557587 0 402718720 3.9229292870 3.8382000923 4.3143520355 3620 1311867291.2211010456 0.1008112878 0.1065547847 0.2224369198 0.0063077251 0.3495350000 0.0841690000 0.0549600000 0.0000000000 0.1996700000 0.0017960000 149561259 0 402718720 3.9233560562 3.8370494843 4.3139858246 3621 1311867291.2543909550 0.1008318290 0.1065532042 0.2224369198 0.0063070416 0.6414890000 0.0994690000 0.0964030000 0.0299850000 0.2003800000 0.2060810000 149564987 0 402718720 3.9235954285 3.8374552727 4.3136148453 3622 1311867291.2877960205 0.1003568769 0.1065514935 0.2224369198 0.0063061916 0.3737490000 0.0843210000 0.0782460000 0.0000010000 0.2004450000 0.0017990000 149568659 0 402718720 3.9246959686 3.8381576538 4.3132290840 3623 1311867291.3210899830 0.1010156497 0.1065499655 0.2224369198 0.0063060229 0.3724730000 0.0841780000 0.0473160000 0.0298700000 0.2003600000 0.0018070000 149572331 0 402718720 3.9240999222 3.8371491432 4.3126797676 3624 1311867291.3547959328 0.1010924280 0.1065484596 0.2224369198 0.0063052018 0.3786780000 0.1111380000 0.0548860000 0.0000000000 0.2018950000 0.0018020000 149576115 0 402718720 3.9242336750 3.8370373249 4.3122167587 3625 1311867291.3878760338 0.1009168476 0.1065469060 0.2224369198 0.0063048239 0.6709960000 0.1050480000 0.0835110000 0.0358460000 0.2153230000 0.2212890000 149579787 0 402718720 3.9246239662 3.8376729488 4.3118934631 3626 1311867291.4223349094 0.1008802652 0.1065453432 0.2224369198 0.0063042113 0.3859370000 0.1062330000 0.0629980000 0.0000010000 0.2059280000 0.0018110000 149583515 0 402718720 3.9248316288 3.8370764256 4.3115696907 3627 1311867291.4536559582 0.1006065309 0.1065437058 0.2224369198 0.0063034266 0.4268090000 0.0841310000 0.0981910000 0.0299800000 0.2037830000 0.0018130000 149587187 0 402718720 3.9252851009 3.8368484974 4.3110203743 3628 1311867291.4883999825 0.1005009860 0.1065420403 0.2224369198 0.0063033528 0.3466710000 0.0840680000 0.0471540000 0.0000000000 0.2046740000 0.0017990000 149590915 0 402718720 3.9253599644 3.8382010460 4.3106956482 3629 1311867291.5201730728 0.1002508774 0.1065403067 0.2224369198 0.0063026945 0.6294130000 0.0842460000 0.0932060000 0.0298830000 0.2037830000 0.2092900000 149594643 0 402718720 3.9256858826 3.8377568722 4.3105216026 3630 1311867291.5536448956 0.1010261625 0.1065387876 0.2224369198 0.0063020868 0.3769700000 0.0840690000 0.0777540000 0.0000010000 0.2043310000 0.0017960000 149598315 0 402718720 3.9244592190 3.8374736309 4.3102045059 3631 1311867291.5895080566 0.1002648920 0.1065370598 0.2224369198 0.0063016570 0.4079860000 0.1137390000 0.0495300000 0.0299700000 0.2035850000 0.0019060000 149602099 0 402718720 3.9260585308 3.8380520344 4.3100786209 3632 1311867291.6206870079 0.1003192663 0.1065353478 0.2224369198 0.0063015330 0.3483350000 0.0842760000 0.0494880000 0.0000000000 0.2034960000 0.0018970000 149605715 0 402718720 3.9252572060 3.8375763893 4.3096079826 3633 1311867291.6539781094 0.1002053842 0.1065336055 0.2224369198 0.0063009287 0.6012910000 0.0842990000 0.0624860000 0.0299540000 0.2050240000 0.2105650000 149609443 0 402718720 3.9251806736 3.8370027542 4.3094100952 3634 1311867291.6896810532 0.1000073478 0.1065318096 0.2224369198 0.0063002020 0.3932040000 0.0842350000 0.0929240000 0.0000010000 0.2053090000 0.0018120000 149613227 0 402718720 3.9256639481 3.8380177021 4.3091349602 3635 1311867291.7202739716 0.0996166617 0.1065299072 0.2224369198 0.0062996737 0.4222950000 0.0840540000 0.0925280000 0.0292850000 0.2056210000 0.0018140000 149616843 0 402718720 3.9261291027 3.8369340897 4.3089265823 3636 1311867291.7537178993 0.1002767161 0.1065281874 0.2224369198 0.0062992303 0.3697200000 0.1025290000 0.0495310000 0.0000010000 0.2064670000 0.0018920000 149620571 0 402718720 3.9246647358 3.8371317387 4.3085231781 3637 1311867291.7890019417 0.0997167975 0.1065263146 0.2224369198 0.0062987117 0.6007560000 0.0841630000 0.0573930000 0.0300340000 0.2069110000 0.2124130000 149624355 0 402718720 3.9256889820 3.8378989697 4.3084440231 3638 1311867291.8217189312 0.0996729881 0.1065244308 0.2224369198 0.0062987425 0.3571250000 0.0842750000 0.0553440000 0.0000000000 0.2063790000 0.0018970000 149627971 0 402718720 3.9256732464 3.8366589546 4.3083748817 3639 1311867291.8538639545 0.0999197364 0.1065226158 0.2224369198 0.0062982101 0.3816570000 0.0842390000 0.0493820000 0.0294910000 0.2074380000 0.0018820000 149631699 0 402718720 3.9256236553 3.8371672630 4.3084602356 3640 1311867291.8879489899 0.1001034230 0.1065208523 0.2224369198 0.0062981220 0.3497040000 0.0839330000 0.0472650000 0.0000010000 0.2073930000 0.0019010000 149635371 0 402718720 3.9261450768 3.8373198509 4.3086166382 3641 1311867291.9206929207 0.0999433473 0.1065190458 0.2224369198 0.0062976488 0.5956700000 0.0945680000 0.0412650000 0.0299680000 0.2074520000 0.2132540000 149639155 0 402718720 3.9264428616 3.8368756771 4.3085985184 3642 1311867291.9537200928 0.1002048180 0.1065173121 0.2224369198 0.0062975239 0.4000340000 0.0841140000 0.0974610000 0.0000010000 0.2076670000 0.0018110000 149642771 0 402718720 3.9268794060 3.8370165825 4.3088684082 3643 1311867291.9902889729 0.0998367816 0.1065154783 0.2224369198 0.0062981360 0.3977820000 0.0839050000 0.0653860000 0.0299780000 0.2073440000 0.0019040000 149646611 0 402718720 3.9274570942 3.8366968632 4.3090758324 3644 1311867292.0225260258 0.1007484421 0.1065138956 0.2224369198 0.0063002240 0.3598860000 0.0839450000 0.0572690000 0.0000010000 0.2078690000 0.0018040000 149650283 0 402718720 3.9272756577 3.8366699219 4.3092784882 3645 1311867292.0536830425 0.1005833372 0.1065122686 0.2224369198 0.0062994385 0.5991810000 0.0837980000 0.0552450000 0.0299900000 0.2076240000 0.2133350000 149653899 0 402718720 3.9281241894 3.8367905617 4.3095273972 3646 1311867292.0922849178 0.0998857990 0.1065104511 0.2224369198 0.0063010500 0.3547610000 0.0966420000 0.0392550000 0.0000010000 0.2080370000 0.0017990000 149657739 0 402718720 3.9283835888 3.8368008137 4.3097438812 3647 1311867292.1243879795 0.1002415866 0.1065087322 0.2224369198 0.0063003745 0.3867640000 0.0840850000 0.0545800000 0.0294120000 0.2078100000 0.0018020000 149661355 0 402718720 3.9279186726 3.8373024464 4.3099479675 3648 1311867292.1602649689 0.1002022550 0.1065070035 0.2224369198 0.0062995149 0.3949600000 0.0839470000 0.0930170000 0.0000010000 0.2071770000 0.0017940000 149665139 0 402718720 3.9280564785 3.8376154900 4.3102531433 3649 1311867292.1899850368 0.0999883637 0.1065052171 0.2224369198 0.0062987891 0.5993450000 0.0952720000 0.0470120000 0.0299700000 0.2062650000 0.2117820000 149668755 0 402718720 3.9283685684 3.8372571468 4.3105258942 3650 1311867292.2207419872 0.1005481035 0.1065035850 0.2224369198 0.0062979521 0.3408150000 0.0839050000 0.0391410000 0.0000010000 0.2060750000 0.0017980000 149672315 0 402718720 3.9275639057 3.8370399475 4.3107652664 3651 1311867292.2576909065 0.1002386436 0.1065018690 0.2224369198 0.0062972017 0.4609700000 0.1164830000 0.0977630000 0.0299630000 0.2055900000 0.0019040000 149676155 0 402718720 3.9277703762 3.8372061253 4.3109879494 3652 1311867292.2878270149 0.1002756283 0.1065001641 0.2224369198 0.0062963701 0.3555080000 0.0841560000 0.0546210000 0.0000000000 0.2058500000 0.0018090000 149679771 0 402718720 3.9275524616 3.8369011879 4.3111958504 3653 1311867292.3217270374 0.0995504707 0.1064982617 0.2224369198 0.0062976703 0.6349840000 0.0835970000 0.0952640000 0.0299110000 0.2055600000 0.2115700000 149683443 0 402718720 3.9274520874 3.8367643356 4.3113441467 3654 1311867292.3621709347 0.1005607843 0.1064966368 0.2224369198 0.0062999833 0.3665050000 0.0839920000 0.0654920000 0.0000010000 0.2058840000 0.0018970000 149687395 0 402718720 3.9263410568 3.8370506763 4.3114323616 3655 1311867292.3953619003 0.1005166322 0.1064950006 0.2224369198 0.0062992087 0.3774600000 0.0837620000 0.0468570000 0.0299240000 0.2060650000 0.0018030000 149691123 0 402718720 3.9261672497 3.8362395763 4.3115200996 3656 1311867292.4259300232 0.1005333513 0.1064933700 0.2224369198 0.0062984122 0.3499720000 0.0952670000 0.0374240000 0.0000010000 0.2064010000 0.0018110000 149694739 0 402718720 3.9260115623 3.8360762596 4.3115777969 3657 1311867292.4565210342 0.1005563587 0.1064917465 0.2224369198 0.0062975594 0.5814550000 0.0841160000 0.0392990000 0.0299590000 0.2067470000 0.2122300000 149698299 0 402718720 3.9257097244 3.8360347748 4.3115234375 3658 1311867292.4883699417 0.1001507267 0.1064900131 0.2224369198 0.0062969184 0.3953460000 0.0838240000 0.0929520000 0.0000000000 0.2070450000 0.0017980000 149702027 0 402718720 3.9261183739 3.8353049755 4.3115162849 3659 1311867292.5229649544 0.1003073305 0.1064883233 0.2224369198 0.0062960713 0.4255020000 0.0841150000 0.0933900000 0.0299570000 0.2071580000 0.0018130000 149705755 0 402718720 3.9256656170 3.8353712559 4.3114652634 3660 1311867292.5581150055 0.1002839729 0.1064866282 0.2224369198 0.0062954396 0.3949750000 0.0837170000 0.0928010000 0.0000000000 0.2075900000 0.0017970000 149709483 0 402718720 3.9255528450 3.8362126350 4.3117518425 3661 1311867292.5882439613 0.1006767154 0.1064850412 0.2224369198 0.0062947066 0.6708090000 0.1160700000 0.0977390000 0.0294600000 0.2062960000 0.2119290000 149713155 0 402718720 3.9246344566 3.8364520073 4.3118000031 3662 1311867292.6230869293 0.1001601741 0.1064833140 0.2224369198 0.0062938912 0.3483610000 0.0840080000 0.0469130000 0.0000010000 0.2065780000 0.0017980000 149716883 0 402718720 3.9254798889 3.8364920616 4.3121123314 3663 1311867292.6595211029 0.0999891981 0.1064815411 0.2224369198 0.0062930335 0.4279710000 0.0841590000 0.0980030000 0.0294350000 0.2052000000 0.0018910000 149720723 0 402718720 3.9259212017 3.8369591236 4.3123927116 3664 1311867292.6880218983 0.1003580913 0.1064798699 0.2224369198 0.0062925055 0.3622370000 0.0836960000 0.0622250000 0.0000010000 0.2054230000 0.0017960000 149724227 0 402718720 3.9253492355 3.8358759880 4.3124155998 3665 1311867292.7206969261 0.0999258533 0.1064780816 0.2224369198 0.0062917775 0.6070760000 0.0960400000 0.0545610000 0.0294380000 0.2061820000 0.2117170000 149727955 0 402718720 3.9263513088 3.8357141018 4.3126807213 3666 1311867292.7561879158 0.1002985835 0.1064763960 0.2224369198 0.0062912056 0.4103190000 0.0954450000 0.0982650000 0.0000000000 0.2054290000 0.0019160000 149731739 0 402718720 3.9259867668 3.8361458778 4.3127985001 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:22:06 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000001192 0.0000001192 0.0000001192 -nan 0.0084830000 0.0007670000 0.0006460000 0.0000230000 0.0000030000 0.0065420000 12691069 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0071111759 0.0035556476 0.0071111759 0.0073250057 0.0024930000 0.0006480000 0.0005970000 0.0000160000 0.0000010000 0.0011030000 13087421 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0160688832 0.0077267261 0.0160688832 0.0105653904 0.0025590000 0.0006590000 0.0006370000 0.0000150000 0.0000020000 0.0011060000 13090589 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0069097765 0.0075224887 0.0160688832 0.0105835547 0.0032380000 0.0006610000 0.0006180000 0.0000160000 0.0000220000 0.0017780000 13093765 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0087672304 0.0077714371 0.0160688832 0.0110947769 0.0068380000 0.0006800000 0.0031290000 0.0000160000 0.0000140000 0.0028440000 13096925 96830484 509673472 4.0003604889 4.0041589737 3.9997618198 6 0.2000000000 0.0087729022 0.0079383479 0.0160688832 0.0099842573 0.0052310000 0.0006870000 0.0027780000 0.0000020000 0.0000160000 0.0015910000 13100501 96830484 509673472 4.0005397797 3.9986739159 4.0006165504 7 0.2400000000 0.0089619178 0.0080845722 0.0160688832 0.0091709159 0.0058100000 0.0006410000 0.0030900000 0.0000150000 0.0000140000 0.0018980000 13103277 96830484 509673472 4.0003643036 3.9985852242 4.0004940033 8 0.2800000000 0.0086609768 0.0081566228 0.0160688832 0.0085533520 0.0049970000 0.0006590000 0.0025490000 0.0000020000 0.0000170000 0.0016020000 13106053 96830484 509673472 4.0010018349 4.0011548996 4.0005350113 9 0.3200000000 0.0086934324 0.0082162683 0.0160688832 0.0080191422 0.0066340000 0.0006580000 0.0029280000 0.0000180000 0.0000150000 0.0028300000 13109597 96830484 509673472 4.0009446144 4.0011129379 4.0001001358 10 0.3600000000 0.0088480115 0.0082794426 0.0160688832 0.0075715801 0.0056870000 0.0006460000 0.0032620000 0.0000010000 0.0000160000 0.0015900000 13113973 96830484 509673472 4.0023875237 3.9998791218 4.0002794266 11 0.4000000000 0.0089143980 0.0083371658 0.0160688832 0.0072054835 0.0052840000 0.0005550000 0.0029260000 0.0000100000 0.0000090000 0.0016640000 13116749 96830484 509673472 4.0022621155 3.9993748665 4.0004630089 12 0.4400000000 0.0089349160 0.0083869783 0.0160688832 0.0068920107 0.0060440000 0.0006590000 0.0035590000 0.0000020000 0.0000160000 0.0016120000 13119525 96830484 509673472 4.0025334358 3.9998528957 3.9999468327 13 0.4800000000 0.0089761754 0.0084323012 0.0160688832 0.0067033955 0.0070160000 0.0006630000 0.0032610000 0.0000160000 0.0000140000 0.0028590000 13122301 96830484 509673472 4.0026526451 4.0015053749 3.9993929863 14 0.5200000000 0.0089722145 0.0084708664 0.0160688832 0.0065182570 0.0057410000 0.0006570000 0.0032540000 0.0000020000 0.0000160000 0.0016030000 13125077 96830484 509673472 4.0027189255 4.0024609566 3.9992070198 15 0.5600000000 0.0089669544 0.0085039390 0.0160688832 0.0062908492 0.0063620000 0.0006420000 0.0035600000 0.0000160000 0.0000140000 0.0019180000 13127853 96830484 509673472 4.0029129982 4.0031347275 3.9986879826 16 0.6000000000 0.0090229688 0.0085363783 0.0160688832 0.0060791975 0.0050150000 0.0005570000 0.0029310000 0.0000010000 0.0000100000 0.0013760000 13130629 96830484 509673472 4.0029554367 4.0030107498 3.9984185696 17 0.6400000000 0.0090527842 0.0085667551 0.0160688832 0.0058997725 0.0068410000 0.0006380000 0.0030960000 0.0000150000 0.0000150000 0.0028510000 13134941 96830484 509673472 4.0021624565 4.0036859512 3.9978315830 18 0.6800000000 0.0092091998 0.0086024465 0.0160688832 0.0057496339 0.0051050000 0.0006400000 0.0026190000 0.0000020000 0.0000150000 0.0016060000 13140917 96830484 509673472 4.0025978088 4.0049710274 3.9975540638 19 0.7200000000 0.0092688277 0.0086375192 0.0160688832 0.0057176881 0.0053510000 0.0005550000 0.0029490000 0.0000100000 0.0000100000 0.0016760000 13143693 96830484 509673472 4.0038008690 4.0054731369 3.9974598885 20 0.7600000000 0.0093655260 0.0086739196 0.0160688832 0.0055670053 0.0045860000 0.0005550000 0.0024870000 0.0000020000 0.0000100000 0.0013780000 13146469 96830484 509673472 4.0043582916 4.0055823326 3.9969880581 21 0.8000000000 0.0094021130 0.0087085954 0.0160688832 0.0054260836 0.0073580000 0.0006410000 0.0035780000 0.0000150000 0.0000140000 0.0028740000 13149245 96830484 509673472 4.0034465790 4.0064196587 3.9972102642 22 0.8400000000 0.0096052364 0.0087493518 0.0160688832 0.0052954996 0.0053590000 0.0006420000 0.0028030000 0.0000020000 0.0000160000 0.0016590000 13152021 96830484 509673472 4.0031509399 4.0063815117 3.9969267845 23 0.8800000000 0.0094864415 0.0087813992 0.0160688832 0.0051738093 0.0053830000 0.0005530000 0.0029430000 0.0000100000 0.0000090000 0.0017000000 13154797 96830484 509673472 4.0037240982 4.0054364204 3.9970669746 24 0.9200000000 0.0096070161 0.0088157999 0.0160688832 0.0050637212 0.0046000000 0.0005540000 0.0024880000 0.0000010000 0.0000100000 0.0013790000 13157573 96830484 509673472 4.0044245720 4.0051822662 3.9973948002 25 0.9600000000 0.0096701179 0.0088499726 0.0160688832 0.0049637494 0.0066020000 0.0006370000 0.0028030000 0.0000140000 0.0000150000 0.0028740000 13160349 96830484 509673472 4.0056781769 4.0050964355 3.9977095127 26 1.0000000000 0.0096045723 0.0088789957 0.0160688832 0.0048655868 0.0053340000 0.0006390000 0.0028010000 0.0000020000 0.0000170000 0.0016100000 13163125 96830484 509673472 4.0052924156 4.0045461655 3.9974348545 27 1.0400000000 0.0095489519 0.0089038089 0.0160688832 0.0047759756 0.0065970000 0.0006890000 0.0037320000 0.0000160000 0.0000140000 0.0018830000 13165901 96830484 509673472 4.0054478645 4.0051455498 3.9975297451 28 1.0800000000 0.0094876885 0.0089246617 0.0160688832 0.0047055126 0.0052600000 0.0006050000 0.0031070000 0.0000010000 0.0000110000 0.0013640000 13168677 96830484 509673472 4.0072197914 4.0039138794 3.9976329803 29 1.1200000000 0.0094599277 0.0089431192 0.0160688832 0.0047738596 0.0073280000 0.0006420000 0.0035640000 0.0000170000 0.0000140000 0.0028310000 13171453 96830484 509673472 4.0084533691 4.0044536591 3.9976909161 30 1.1600000000 0.0095202159 0.0089623557 0.0160688832 0.0049254574 0.0050730000 0.0005790000 0.0029400000 0.0000020000 0.0000100000 0.0013650000 13174229 96830484 509673472 4.0077738762 4.0029931068 3.9979410172 31 1.2000000000 0.0095997611 0.0089829172 0.0160688832 0.0050156973 0.0060760000 0.0006430000 0.0032630000 0.0000150000 0.0000140000 0.0018740000 13177005 96830484 509673472 4.0100092888 4.0033454895 3.9981107712 32 1.2400000000 0.0096526761 0.0090038472 0.0160688832 0.0052975211 0.0057580000 0.0006400000 0.0032470000 0.0000020000 0.0000150000 0.0015810000 13179781 96830484 509673472 4.0117549896 4.0045742989 3.9984755516 33 1.2800000000 0.0096760010 0.0090242155 0.0160688832 0.0055436504 0.0070580000 0.0006410000 0.0032480000 0.0000180000 0.0000140000 0.0028470000 13185629 96830484 509673472 4.0115580559 4.0040292740 3.9992871284 34 1.3200000000 0.0097352564 0.0090451284 0.0160688832 0.0056844625 0.0053050000 0.0006380000 0.0030990000 0.0000010000 0.0000110000 0.0013600000 13194805 96830484 509673472 4.0111384392 4.0038509369 4.0000424385 35 1.3600000000 0.0098008718 0.0090667211 0.0160688832 0.0060333415 0.0059170000 0.0006470000 0.0030720000 0.0000150000 0.0000130000 0.0018720000 13197581 96830484 509673472 4.0113835335 4.0045242310 4.0006899834 36 1.4000000000 0.0098719718 0.0090890892 0.0160688832 0.0063440724 0.0056530000 0.0006430000 0.0030920000 0.0000020000 0.0000160000 0.0015980000 13200357 96830484 509673472 4.0127730370 4.0029511452 4.0015988350 37 1.4400000000 0.0099633113 0.0091127168 0.0160688832 0.0067327562 0.0062650000 0.0005730000 0.0029290000 0.0000110000 0.0000100000 0.0025360000 13203133 96830484 509673472 4.0137982368 4.0030975342 4.0021114349 38 1.4800000000 0.0099631185 0.0091350958 0.0160688832 0.0085641670 0.0056840000 0.0006410000 0.0031080000 0.0000020000 0.0000160000 0.0016060000 13205909 96830484 509673472 4.0152721405 4.0021991730 4.0038647652 39 1.5200000000 0.0100138085 0.0091576269 0.0160688832 0.0088497814 0.0057620000 0.0006400000 0.0030660000 0.0000160000 0.0000150000 0.0018090000 13208685 96830484 509673472 4.0168061256 4.0024724007 4.0048856735 40 1.5600000000 0.0100025982 0.0091787512 0.0160688832 0.0089655115 0.0056580000 0.0006410000 0.0030770000 0.0000020000 0.0000160000 0.0016070000 13211461 96830484 509673472 4.0181446075 4.0022878647 4.0052504539 41 1.6000000000 0.0099809235 0.0091983164 0.0160688832 0.0091048962 0.0071180000 0.0006400000 0.0032600000 0.0000160000 0.0000140000 0.0028640000 13214237 96830484 509673472 4.0197396278 3.9987454414 4.0067358017 42 1.6400000000 0.0101154288 0.0092201524 0.0160688832 0.0092251026 0.0050820000 0.0005560000 0.0029220000 0.0000010000 0.0000110000 0.0013750000 13217013 96830484 509673472 4.0215520859 3.9990439415 4.0070896149 43 1.6800000000 0.0100315250 0.0092390215 0.0160688832 0.0094690052 0.0059450000 0.0006370000 0.0030470000 0.0000170000 0.0000140000 0.0018950000 13219789 96830484 509673472 4.0233941078 4.0012521744 4.0076265335 44 1.7200000000 0.0100642983 0.0092577778 0.0160688832 0.0097024184 0.0058770000 0.0006360000 0.0032620000 0.0000020000 0.0000140000 0.0016230000 13222565 96830484 509673472 4.0247106552 4.0028104782 4.0085988045 45 1.7600000000 0.0100791156 0.0092760297 0.0160688832 0.0100015832 0.0072420000 0.0006600000 0.0032130000 0.0000150000 0.0000140000 0.0029160000 13225341 96830484 509673472 4.0267496109 4.0007357597 4.0096945763 46 1.8000000000 0.0101573067 0.0092951879 0.0160688832 0.0112165157 0.0057940000 0.0006600000 0.0030940000 0.0000020000 0.0000160000 0.0016290000 13228117 96830484 509673472 4.0545892715 4.0003552437 4.0058865547 47 1.8400000000 0.0102251591 0.0093149746 0.0160688832 0.0111223213 0.0060840000 0.0006400000 0.0030960000 0.0000150000 0.0000150000 0.0019280000 13230893 96830484 509673472 4.1148557663 3.9970898628 3.9948434830 48 1.8800000000 0.0101774288 0.0093329423 0.0160688832 0.0112461860 0.0053090000 0.0005540000 0.0030890000 0.0000010000 0.0000100000 0.0013930000 13233669 96830484 509673472 4.1175332069 3.9967885017 3.9951965809 49 1.9200000000 0.0102161048 0.0093509661 0.0160688832 0.0113782666 0.0072480000 0.0006570000 0.0032540000 0.0000160000 0.0000140000 0.0029010000 13236445 96830484 509673472 4.1197648048 3.9957673550 3.9954762459 50 1.9600000000 0.0102209048 0.0093683648 0.0160688832 0.0114550551 0.0059720000 0.0006610000 0.0032500000 0.0000020000 0.0000170000 0.0016250000 13239221 96830484 509673472 4.1223011017 3.9955277443 3.9957170486 51 2.0000000000 0.0102302218 0.0093852640 0.0160688832 0.0115135346 0.0062420000 0.0006410000 0.0032460000 0.0000160000 0.0000130000 0.0019110000 13241997 96830484 509673472 4.1251683235 3.9945280552 3.9955189228 52 2.0400000000 0.0102256872 0.0094014260 0.0160688832 0.0115620665 0.0057710000 0.0006910000 0.0030800000 0.0000020000 0.0000150000 0.0015900000 13244773 96830484 509673472 4.1282305717 3.9936099052 3.9955554008 53 2.0800000000 0.0102711264 0.0094178354 0.0160688832 0.0115841251 0.0071890000 0.0006390000 0.0032510000 0.0000150000 0.0000140000 0.0028590000 13247549 96830484 509673472 4.1295490265 3.9927649498 3.9956364632 54 2.1200000000 0.0102788340 0.0094337798 0.0160688832 0.0116052337 0.0050380000 0.0005570000 0.0029320000 0.0000010000 0.0000110000 0.0013320000 13250325 96830484 509673472 4.1327815056 3.9931225777 3.9951825142 55 2.1600000000 0.0103171673 0.0094498414 0.0160688832 0.0116349487 0.0067660000 0.0006950000 0.0037220000 0.0000150000 0.0000150000 0.0018820000 13253101 96830484 509673472 4.1360096931 3.9953265190 3.9942369461 56 2.2000000000 0.0103939297 0.0094667002 0.0160688832 0.0116980190 0.0055330000 0.0006890000 0.0031950000 0.0000010000 0.0000090000 0.0013540000 13255877 96830484 509673472 4.1373171806 3.9938936234 3.9940738678 57 2.2400000000 0.0104833990 0.0094845370 0.0160688832 0.0118348949 0.0069370000 0.0006410000 0.0030010000 0.0000170000 0.0000130000 0.0028480000 13258653 96830484 509673472 4.1365599632 3.9913039207 3.9946730137 58 2.2800000000 0.0104921293 0.0095019093 0.0160688832 0.0119863682 0.0052090000 0.0005550000 0.0030080000 0.0000010000 0.0000100000 0.0013540000 13261429 96830484 509673472 4.1383833885 3.9901580811 3.9942932129 59 2.3200000000 0.0108217802 0.0095242800 0.0160688832 0.0122082372 0.0052180000 0.0005240000 0.0028860000 0.0000090000 0.0000070000 0.0015510000 13264205 96830484 509673472 4.1397390366 3.9898939133 3.9937951565 60 2.3600000000 0.0107741989 0.0095451119 0.0160688832 0.0123713313 0.0058670000 0.0006570000 0.0031260000 0.0000030000 0.0000180000 0.0015830000 13266981 96830484 509673472 4.1426548958 3.9890105724 3.9926307201 61 2.4000000000 0.0105018243 0.0095607957 0.0160688832 0.0126428075 0.0071000000 0.0006420000 0.0031010000 0.0000140000 0.0000140000 0.0028560000 13269757 96830484 509673472 4.1450047493 3.9885711670 3.9923591614 62 2.4400000000 0.0103500625 0.0095735259 0.0160688832 0.0128742319 0.0051820000 0.0005540000 0.0029440000 0.0000010000 0.0000110000 0.0013520000 13272533 96830484 509673472 4.1489114761 3.9883522987 3.9910602570 63 2.4800000000 0.0102496594 0.0095842581 0.0160688832 0.0130853175 0.0059780000 0.0006400000 0.0029360000 0.0000150000 0.0000140000 0.0018540000 13275309 96830484 509673472 4.1525759697 3.9888381958 3.9899277687 64 2.5200000000 0.0101979999 0.0095938478 0.0160688832 0.0132262591 0.0055890000 0.0006400000 0.0029060000 0.0000020000 0.0000150000 0.0015420000 13278085 96830484 509673472 4.1565647125 3.9868690968 3.9882478714 65 2.5600000000 0.0100999428 0.0096016339 0.0160688832 0.0133261477 0.0068920000 0.0006360000 0.0029160000 0.0000160000 0.0000140000 0.0027990000 13287005 96830484 509673472 4.1606831551 3.9870502949 3.9863681793 66 2.6000000000 0.0101264818 0.0096095862 0.0160688832 0.0134094040 0.0050690000 0.0006170000 0.0027580000 0.0000010000 0.0000110000 0.0013330000 13302581 96830484 509673472 4.1652383804 3.9861567020 3.9840834141 67 2.6400000000 0.0101822820 0.0096181339 0.0160688832 0.0135127076 0.0051490000 0.0005270000 0.0027990000 0.0000080000 0.0000070000 0.0015430000 13305357 96830484 509673472 4.1685061455 3.9857223034 3.9820845127 68 2.6800000000 0.0101906843 0.0096265537 0.0160688832 0.0136252304 0.0047000000 0.0005260000 0.0026590000 0.0000010000 0.0000080000 0.0012360000 13308133 96830484 509673472 4.1731653214 3.9860148430 3.9793002605 69 2.7200000000 0.0101915887 0.0096347426 0.0160688832 0.0137350960 0.0058420000 0.0005230000 0.0026360000 0.0000080000 0.0000080000 0.0023850000 13310909 96830484 509673472 4.1765580177 3.9839990139 3.9774475098 70 2.7600000000 0.0102232341 0.0096431497 0.0160688832 0.0139070067 0.0047230000 0.0005270000 0.0026700000 0.0000010000 0.0000090000 0.0012430000 13313685 96830484 509673472 4.1788158417 3.9826354980 3.9764966965 71 2.8000000000 0.0102680763 0.0096519514 0.0160688832 0.0140159073 0.0050220000 0.0005240000 0.0026500000 0.0000080000 0.0000070000 0.0015560000 13316461 96830484 509673472 4.1828513145 3.9832248688 3.9742226601 72 2.8400000000 0.0103078671 0.0096610614 0.0160688832 0.0141742455 0.0047110000 0.0005250000 0.0026490000 0.0000010000 0.0000080000 0.0012470000 13319237 96830484 509673472 4.1856102943 3.9831962585 3.9727451801 73 2.8800000000 0.0103276819 0.0096701932 0.0160688832 0.0142979086 0.0058500000 0.0005240000 0.0026430000 0.0000080000 0.0000070000 0.0023850000 13322013 96830484 509673472 4.1878991127 3.9826543331 3.9714846611 74 2.9200000000 0.0103370138 0.0096792043 0.0160688832 0.0143765091 0.0047160000 0.0005270000 0.0026440000 0.0000010000 0.0000080000 0.0012510000 13324789 96830484 509673472 4.1923127174 3.9823122025 3.9687254429 75 2.9600000000 0.0103676207 0.0096883831 0.0160688832 0.0145131512 0.0050370000 0.0005270000 0.0026510000 0.0000090000 0.0000070000 0.0015550000 13327565 96830484 509673472 4.1938738823 3.9824349880 3.9678502083 76 3.0000000000 0.0103893420 0.0096976063 0.0160688832 0.0145456090 0.0046210000 0.0005260000 0.0026500000 0.0000010000 0.0000090000 0.0011880000 13330341 96830484 509673472 4.1988859177 3.9799427986 3.9647479057 77 3.0400000000 0.0103750508 0.0097064043 0.0160688832 0.0146123056 0.0053050000 0.0004840000 0.0024100000 0.0000050000 0.0000040000 0.0022440000 13333117 96830484 509673472 4.2018356323 3.9786624908 3.9626848698 78 3.0800000000 0.0103812041 0.0097150555 0.0160688832 0.0146270101 0.0042370000 0.0004540000 0.0025230000 0.0000000000 0.0000040000 0.0011270000 13335893 96830484 509673472 4.2063822746 3.9777350426 3.9592599869 79 3.1200000000 0.0103509743 0.0097231051 0.0160688832 0.0146752884 0.0045290000 0.0004540000 0.0025070000 0.0000040000 0.0000040000 0.0014300000 13338669 96830484 509673472 4.2104387283 3.9773430824 3.9567136765 80 3.1600000000 0.0103976605 0.0097315371 0.0160688832 0.0150960221 0.0038430000 0.0004540000 0.0021190000 0.0000000000 0.0000040000 0.0011330000 13341445 96830484 509673472 4.2190308571 3.9762580395 3.9505658150 81 3.2000000000 0.0103499480 0.0097391718 0.0160688832 0.0151199150 0.0053070000 0.0004540000 0.0025030000 0.0000040000 0.0000030000 0.0022100000 13344221 96830484 509673472 4.2230148315 3.9758667946 3.9480760098 82 3.2400000000 0.0103191528 0.0097462447 0.0160688832 0.0151228440 0.0042480000 0.0004540000 0.0025230000 0.0000010000 0.0000040000 0.0011340000 13346997 96830484 509673472 4.2263255119 3.9729228020 3.9457497597 83 3.2800000000 0.0103265010 0.0097532358 0.0160688832 0.0151688247 0.0049520000 0.0004550000 0.0029160000 0.0000040000 0.0000040000 0.0014380000 13349773 96830484 509673472 4.2295055389 3.9726026058 3.9436583519 84 3.3200000000 0.0103249019 0.0097600413 0.0160688832 0.0151588553 0.0042470000 0.0004560000 0.0025170000 0.0000000000 0.0000040000 0.0011340000 13352549 96830484 509673472 4.2317705154 3.9696855545 3.9422757626 85 3.3600000000 0.0103254439 0.0097666931 0.0160688832 0.0151688122 0.0053600000 0.0004560000 0.0025030000 0.0000040000 0.0000030000 0.0022510000 13355325 96830484 509673472 4.2351121902 3.9683182240 3.9400300980 86 3.4000000000 0.0103322500 0.0097732694 0.0160688832 0.0152082663 0.0042540000 0.0004540000 0.0025140000 0.0000000000 0.0000040000 0.0011410000 13358101 96830484 509673472 4.2371687889 3.9671533108 3.9388184547 87 3.4400000000 0.0103250118 0.0097796112 0.0160688832 0.0152310311 0.0048430000 0.0004540000 0.0027760000 0.0000040000 0.0000040000 0.0014650000 13360877 96830484 509673472 4.2408342361 3.9666521549 3.9364805222 88 3.4800000000 0.0102732889 0.0097852212 0.0160688832 0.0152505926 0.0042570000 0.0004540000 0.0025140000 0.0000000000 0.0000050000 0.0011430000 13363653 96830484 509673472 4.2444701195 3.9674160480 3.9339151382 89 3.5200000000 0.0103039015 0.0097910491 0.0160688832 0.0152536397 0.0049400000 0.0004540000 0.0021020000 0.0000050000 0.0000040000 0.0022320000 13366429 96830484 509673472 4.2472791672 3.9669251442 3.9318690300 90 3.5600000000 0.0103620170 0.0097973932 0.0160688832 0.0152603103 0.0042620000 0.0004570000 0.0025070000 0.0000000000 0.0000040000 0.0011480000 13369205 96830484 509673472 4.2495160103 3.9649038315 3.9303009510 91 3.6000000000 0.0103199519 0.0098031356 0.0160688832 0.0152758524 0.0045780000 0.0004550000 0.0025040000 0.0000040000 0.0000040000 0.0014660000 13371981 96830484 509673472 4.2519755363 3.9640889168 3.9287378788 92 3.6400000000 0.0103423875 0.0098089970 0.0160688832 0.0152703232 0.0038760000 0.0004530000 0.0021170000 0.0000000000 0.0000040000 0.0011540000 13374757 96830484 509673472 4.2550215721 3.9649455547 3.9266762733 93 3.6800000000 0.0103411479 0.0098147190 0.0160688832 0.0152334247 0.0053840000 0.0004530000 0.0025140000 0.0000040000 0.0000030000 0.0022590000 13377533 96830484 509673472 4.2571725845 3.9636151791 3.9248077869 94 3.7200000000 0.0103859734 0.0098207962 0.0160688832 0.0151954077 0.0050960000 0.0004580000 0.0033290000 0.0000000000 0.0000040000 0.0011550000 13380309 96830484 509673472 4.2596883774 3.9631006718 3.9234580994 95 3.7600000000 0.0104042497 0.0098269378 0.0160688832 0.0151533745 0.0046020000 0.0004570000 0.0025110000 0.0000050000 0.0000040000 0.0014760000 13383085 96830484 509673472 4.2628889084 3.9634349346 3.9213225842 96 3.8000000000 0.0103056561 0.0098319245 0.0160688832 0.0151081860 0.0042930000 0.0004540000 0.0025190000 0.0000000000 0.0000040000 0.0011660000 13385861 96830484 509673472 4.2654695511 3.9630036354 3.9189665318 97 3.8400000000 0.0103487214 0.0098372523 0.0160688832 0.0150713585 0.0053980000 0.0004570000 0.0025080000 0.0000040000 0.0000040000 0.0022720000 13388637 96830484 509673472 4.2677979469 3.9627666473 3.9169483185 98 3.8800000000 0.0103090564 0.0098420666 0.0160688832 0.0150277525 0.0042950000 0.0004550000 0.0025170000 0.0000000000 0.0000040000 0.0011640000 13391413 96830484 509673472 4.2687516212 3.9616184235 3.9162867069 99 3.9200000000 0.0103916572 0.0098476180 0.0160688832 0.0149737824 0.0047460000 0.0004550000 0.0026480000 0.0000040000 0.0000040000 0.0014800000 13394189 96830484 509673472 4.2714767456 3.9610753059 3.9140703678 100 3.9600000000 0.0104520861 0.0098536627 0.0160688832 0.0149209710 0.0044250000 0.0004530000 0.0026410000 0.0000010000 0.0000040000 0.0011680000 13396965 96830484 509673472 4.2730154991 3.9597296715 3.9127948284 101 4.0000000000 0.0105038490 0.0098601002 0.0160688832 0.0148718145 0.0055530000 0.0004540000 0.0026480000 0.0000050000 0.0000040000 0.0022830000 13399741 96830484 509673472 4.2754898071 3.9615824223 3.9113044739 102 4.0400000000 0.0103971977 0.0098653659 0.0160688832 0.0148261131 0.0043030000 0.0004530000 0.0025110000 0.0000000000 0.0000040000 0.0011720000 13402517 96830484 509673472 4.2776231766 3.9620976448 3.9096796513 103 4.0800000000 0.0104695382 0.0098712316 0.0160688832 0.0147804814 0.0046200000 0.0004530000 0.0025160000 0.0000040000 0.0000040000 0.0014790000 13405293 96830484 509673472 4.2799229622 3.9626626968 3.9084060192 104 4.1200000000 0.0104734041 0.0098770217 0.0160688832 0.0147269811 0.0043220000 0.0004550000 0.0025170000 0.0000010000 0.0000040000 0.0011800000 13408069 96830484 509673472 4.2815995216 3.9636347294 3.9070832729 105 4.1600000000 0.0105674425 0.0098835972 0.0160688832 0.0146801667 0.0054320000 0.0004540000 0.0025130000 0.0000040000 0.0000040000 0.0022890000 13410845 96830484 509673472 4.2843117714 3.9649920464 3.9051740170 106 4.2000000000 0.0105215944 0.0098896160 0.0160688832 0.0146233971 0.0043170000 0.0004560000 0.0025110000 0.0000010000 0.0000040000 0.0011800000 13413621 96830484 509673472 4.2858724594 3.9654228687 3.9039485455 107 4.2400000000 0.0105438475 0.0098957303 0.0160688832 0.0145603681 0.0046510000 0.0004540000 0.0025110000 0.0000040000 0.0000030000 0.0015040000 13416397 96830484 509673472 4.2867202759 3.9654345512 3.9032220840 108 4.2800000000 0.0105699971 0.0099019735 0.0160688832 0.0144964940 0.0043430000 0.0004550000 0.0025270000 0.0000010000 0.0000040000 0.0011870000 13419173 96830484 509673472 4.2903637886 3.9677829742 3.9002752304 109 4.3200000000 0.0106258513 0.0099086146 0.0160688832 0.0144297081 0.0054140000 0.0004540000 0.0024860000 0.0000040000 0.0000030000 0.0022920000 13421949 96830484 509673472 4.2919621468 3.9684903622 3.8990147114 110 4.3600000000 0.0107187647 0.0099159796 0.0160688832 0.0143656528 0.0044690000 0.0004550000 0.0026500000 0.0000010000 0.0000040000 0.0011860000 13424725 96830484 509673472 4.2927913666 3.9696741104 3.8979597092 111 4.4000000000 0.0107258018 0.0099232753 0.0160688832 0.0143023993 0.0046580000 0.0004540000 0.0025150000 0.0000040000 0.0000040000 0.0015060000 13427501 96830484 509673472 4.2940049171 3.9718124866 3.8966078758 112 4.4400000000 0.0107975453 0.0099310813 0.0160688832 0.0142454382 0.0040520000 0.0004550000 0.0022230000 0.0000000000 0.0000040000 0.0011910000 13430277 96830484 509673472 4.2964630127 3.9745388031 3.8943352699 113 4.4800000000 0.0108773299 0.0099394552 0.0160688832 0.0141827349 0.0054600000 0.0004560000 0.0022250000 0.0000040000 0.0000030000 0.0025850000 13433053 96830484 509673472 4.2977805138 3.9770510197 3.8932988644 114 4.5200000000 0.0108565185 0.0099474996 0.0160688832 0.0141199684 0.0051880000 0.0006190000 0.0028250000 0.0000010000 0.0000080000 0.0013180000 13435829 96830484 509673472 4.2986459732 3.9785664082 3.8922727108 115 4.5600000000 0.0109284129 0.0099560293 0.0160688832 0.0140598967 0.0049580000 0.0005550000 0.0022820000 0.0000100000 0.0000090000 0.0016960000 13438605 96830484 509673472 4.2999563217 3.9811234474 3.8907394409 116 4.6000000000 0.0108696232 0.0099639051 0.0160688832 0.0140034128 0.0053590000 0.0005540000 0.0028230000 0.0000020000 0.0000110000 0.0014340000 13441381 96830484 509673472 4.3003921509 3.9825298786 3.8897004128 117 4.6400000000 0.0110397693 0.0099731005 0.0160688832 0.0139603148 0.0077420000 0.0006370000 0.0034040000 0.0000150000 0.0000150000 0.0029430000 13444157 96830484 509673472 4.3012685776 3.9852619171 3.8883364201 118 4.6800000000 0.0109957419 0.0099817670 0.0160688832 0.0139268710 0.0055660000 0.0006370000 0.0028230000 0.0000020000 0.0000150000 0.0015370000 13446933 96830484 509673472 4.3017992973 3.9857397079 3.8877720833 119 4.7200000000 0.0109773427 0.0099901331 0.0160688832 0.0138870069 0.0062240000 0.0006410000 0.0029700000 0.0000140000 0.0000140000 0.0019600000 13449709 96830484 509673472 4.3020262718 3.9884240627 3.8874022961 120 4.7600000000 0.0110489838 0.0099989569 0.0160688832 0.0138408760 0.0052360000 0.0005530000 0.0026840000 0.0000010000 0.0000110000 0.0014370000 13452485 96830484 509673472 4.3019447327 3.9894938469 3.8864295483 121 4.8000000000 0.0110569801 0.0100077009 0.0160688832 0.0137973017 0.0072810000 0.0006390000 0.0028450000 0.0000170000 0.0000140000 0.0029310000 13455261 96830484 509673472 4.3011627197 3.9908239841 3.8868815899 122 4.8400000000 0.0110884132 0.0100165592 0.0160688832 0.0137687779 0.0054100000 0.0005540000 0.0028410000 0.0000010000 0.0000090000 0.0014450000 13458037 96830484 509673472 4.3003110886 3.9955949783 3.8862059116 123 4.8800000000 0.0111526288 0.0100257955 0.0160688832 0.0137227116 0.0052030000 0.0005170000 0.0026070000 0.0000080000 0.0000070000 0.0016440000 13460813 96830484 509673472 4.2994098663 3.9979162216 3.8865082264 124 4.9200000000 0.0112698805 0.0100358285 0.0160688832 0.0136821878 0.0061290000 0.0006380000 0.0029820000 0.0000020000 0.0000150000 0.0016280000 13463589 96830484 509673472 4.2986755371 3.9990422726 3.8864195347 125 4.9600000000 0.0112429978 0.0100454858 0.0160688832 0.0136407128 0.0071310000 0.0006380000 0.0028240000 0.0000150000 0.0000140000 0.0029280000 13466365 96830484 509673472 4.2979979515 4.0019454956 3.8870129585 126 5.0000000000 0.0113316039 0.0100556931 0.0160688832 0.0136014570 0.0061270000 0.0006390000 0.0029800000 0.0000020000 0.0000160000 0.0016270000 13469141 96830484 509673472 4.2978496552 4.0039153099 3.8868830204 127 5.0400000000 0.0113358311 0.0100657729 0.0160688832 0.0135729563 0.0054680000 0.0005540000 0.0026780000 0.0000100000 0.0000090000 0.0017420000 13471917 96830484 509673472 4.2965893745 4.0054621696 3.8875727654 128 5.0800000000 0.0113877412 0.0100761008 0.0160688832 0.0135442751 0.0068730000 0.0006420000 0.0037030000 0.0000010000 0.0000150000 0.0016330000 13474693 96830484 509673472 4.2955923080 4.0070614815 3.8879902363 129 5.1200000000 0.0113862855 0.0100862573 0.0160688832 0.0135157869 0.0073110000 0.0006440000 0.0028240000 0.0000180000 0.0000140000 0.0029140000 13489757 96830484 509673472 4.2956113815 4.0097804070 3.8878154755 130 5.1600000000 0.0113505144 0.0100959823 0.0160688832 0.0134965187 0.0048150000 0.0005520000 0.0024930000 0.0000010000 0.0000080000 0.0013100000 13518133 96830484 509673472 4.2937369347 4.0105419159 3.8892035484 131 5.2000000000 0.0113723027 0.0101057252 0.0160688832 0.0134766722 0.0050320000 0.0004980000 0.0025870000 0.0000060000 0.0000050000 0.0015740000 13520909 96830484 509673472 4.2917876244 4.0106854439 3.8904278278 132 5.2400000000 0.0114370035 0.0101158107 0.0160688832 0.0134569202 0.0061490000 0.0006350000 0.0029720000 0.0000020000 0.0000170000 0.0016230000 13523685 96830484 509673472 4.2898612022 4.0110411644 3.8916096687 133 5.2800000000 0.0114659406 0.0101259620 0.0160688832 0.0134256075 0.0079290000 0.0006390000 0.0034270000 0.0000150000 0.0000140000 0.0029150000 13526461 96830484 509673472 4.2885379791 4.0118908882 3.8933253288 134 5.3200000000 0.0114395730 0.0101357651 0.0160688832 0.0133890625 0.0056880000 0.0005520000 0.0031020000 0.0000010000 0.0000100000 0.0014040000 13529237 96830484 509673472 4.2866744995 4.0135540962 3.8948168755 135 5.3600000000 0.0114075774 0.0101451859 0.0160688832 0.0133531490 0.0052400000 0.0005240000 0.0026090000 0.0000070000 0.0000080000 0.0016210000 13532013 96830484 509673472 4.2841138840 4.0138030052 3.8970172405 136 5.4000000000 0.0114984931 0.0101551367 0.0160688832 0.0133196474 0.0062150000 0.0006450000 0.0029890000 0.0000020000 0.0000160000 0.0016200000 13534789 96830484 509673472 4.2826814651 4.0155038834 3.8983616829 137 5.4400000000 0.0114642698 0.0101646924 0.0160688832 0.0132876043 0.0075320000 0.0006380000 0.0030130000 0.0000170000 0.0000140000 0.0028990000 13537565 96830484 509673472 4.2817173004 4.0180730820 3.8996107578 138 5.4800000000 0.0114729935 0.0101741729 0.0160688832 0.0133454738 0.0061890000 0.0006410000 0.0029690000 0.0000020000 0.0000170000 0.0015960000 13540341 96830484 509673472 4.2781567574 4.0180101395 3.9027550220 139 5.5200000000 0.0114727123 0.0101835149 0.0160688832 0.0133144109 0.0065640000 0.0006550000 0.0029930000 0.0000170000 0.0000140000 0.0019060000 13543117 96830484 509673472 4.2758321762 4.0187888145 3.9046545029 140 5.5600000000 0.0115374252 0.0101931857 0.0160688832 0.0132947808 0.0061490000 0.0006570000 0.0028850000 0.0000020000 0.0000150000 0.0016030000 13545893 96830484 509673472 4.2747645378 4.0207238197 3.9059760571 141 5.6000000000 0.0116528179 0.0102035377 0.0160688832 0.0132714766 0.0077250000 0.0007080000 0.0031060000 0.0000150000 0.0000140000 0.0028660000 13548669 96830484 509673472 4.2729268074 4.0225787163 3.9076235294 142 5.6400000000 0.0116451150 0.0102136896 0.0160688832 0.0132452707 0.0055560000 0.0006430000 0.0028720000 0.0000020000 0.0000150000 0.0013830000 13551445 96830484 509673472 4.2715659142 4.0250916481 3.9090242386 143 5.6800000000 0.0115888184 0.0102233059 0.0160688832 0.0132274229 0.0056490000 0.0005180000 0.0030380000 0.0000100000 0.0000070000 0.0015970000 13554221 96830484 509673472 4.2691860199 4.0254826546 3.9106431007 144 5.7200000000 0.0116824517 0.0102334389 0.0160688832 0.0131976715 0.0063080000 0.0006600000 0.0030160000 0.0000020000 0.0000150000 0.0016040000 13556997 96830484 509673472 4.2665948868 4.0258278847 3.9120545387 145 5.7600000000 0.0116828056 0.0102434345 0.0160688832 0.0131673377 0.0068470000 0.0006410000 0.0028690000 0.0000110000 0.0000090000 0.0026380000 13559773 96830484 509673472 4.2646627426 4.0293154716 3.9138431549 146 5.8000000000 0.0116939265 0.0102533694 0.0160688832 0.0131391207 0.0055800000 0.0006410000 0.0028690000 0.0000020000 0.0000150000 0.0013850000 13562549 96830484 509673472 4.2625341415 4.0300078392 3.9152073860 147 5.8400000000 0.0117326360 0.0102634324 0.0160688832 0.0131166570 0.0052680000 0.0005160000 0.0026450000 0.0000070000 0.0000110000 0.0015830000 13565325 96830484 509673472 4.2595677376 4.0310177803 3.9175286293 148 5.8800000000 0.0117343161 0.0102733708 0.0160688832 0.0130963511 0.0063000000 0.0006600000 0.0030000000 0.0000020000 0.0000170000 0.0015950000 13568101 96830484 509673472 4.2579340935 4.0322360992 3.9182732105 149 5.9200000000 0.0117683550 0.0102834043 0.0160688832 0.0130754673 0.0074180000 0.0006420000 0.0028410000 0.0000150000 0.0000140000 0.0028860000 13570877 96830484 509673472 4.2546920776 4.0322709084 3.9203615189 150 5.9600000000 0.0116659990 0.0102926216 0.0160688832 0.0130564504 0.0055730000 0.0006390000 0.0028550000 0.0000020000 0.0000160000 0.0013750000 13573653 96830484 509673472 4.2509312630 4.0309019089 3.9226229191 151 6.0000000000 0.0118182432 0.0103027250 0.0160688832 0.0130335922 0.0052610000 0.0005190000 0.0026330000 0.0000080000 0.0000070000 0.0015760000 13576429 96830484 509673472 4.2472686768 4.0313382149 3.9248065948 152 6.0400000000 0.0116260741 0.0103114313 0.0160688832 0.0130164009 0.0047270000 0.0004930000 0.0026020000 0.0000010000 0.0000060000 0.0012050000 13579205 96830484 509673472 4.2438683510 4.0298275948 3.9271111488 153 6.0800000000 0.0118357558 0.0103213942 0.0160688832 0.0130000210 0.0074290000 0.0006400000 0.0028540000 0.0000180000 0.0000150000 0.0028490000 13581981 96830484 509673472 4.2396378517 4.0321946144 3.9297137260 154 6.1200000000 0.0117420340 0.0103306191 0.0160688832 0.0129928985 0.0058660000 0.0006400000 0.0028920000 0.0000020000 0.0000140000 0.0015860000 13584757 96830484 509673472 4.2366337776 4.0337648392 3.9314138889 155 6.1600000000 0.0118621774 0.0103405001 0.0160688832 0.0129868880 0.0064670000 0.0006390000 0.0028640000 0.0000150000 0.0000130000 0.0018790000 13587533 96830484 509673472 4.2323698997 4.0331664085 3.9339208603 156 6.2000000000 0.0118870325 0.0103504138 0.0160688832 0.0129841691 0.0066040000 0.0006400000 0.0033100000 0.0000020000 0.0000150000 0.0015810000 13590309 96830484 509673472 4.2277922630 4.0340304375 3.9366281033 157 6.2400000000 0.0116949650 0.0103589778 0.0160688832 0.0129859173 0.0076630000 0.0006420000 0.0030400000 0.0000140000 0.0000130000 0.0028840000 13593085 96830484 509673472 4.2234869003 4.0358061790 3.9383416176 158 6.2800000000 0.0117861433 0.0103680105 0.0160688832 0.0130007881 0.0051520000 0.0005490000 0.0027950000 0.0000010000 0.0000080000 0.0012580000 13595861 96830484 509673472 4.2207012177 4.0370821953 3.9399311543 159 6.3200000000 0.0116897076 0.0103763231 0.0160688832 0.0130074839 0.0065290000 0.0006400000 0.0029090000 0.0000160000 0.0000130000 0.0018760000 13598637 96830484 509673472 4.2167892456 4.0371174812 3.9417076111 160 6.3600000000 0.0117334528 0.0103848051 0.0160688832 0.0130075237 0.0061770000 0.0006410000 0.0028630000 0.0000020000 0.0000160000 0.0015770000 13601413 96830484 509673472 4.2136697769 4.0383677483 3.9433205128 161 6.4000000000 0.0116949184 0.0103929425 0.0160688832 0.0130087103 0.0067010000 0.0005550000 0.0031560000 0.0000100000 0.0000090000 0.0024130000 13604189 96830484 509673472 4.2107295990 4.0394811630 3.9446539879 162 6.4400000000 0.0116745438 0.0104008536 0.0160688832 0.0130211630 0.0047620000 0.0004940000 0.0026210000 0.0000010000 0.0000060000 0.0011940000 13606965 96830484 509673472 4.2062497139 4.0388154984 3.9462771416 163 6.4800000000 0.0116940672 0.0104087874 0.0160688832 0.0130192628 0.0066800000 0.0006400000 0.0030540000 0.0000150000 0.0000140000 0.0018590000 13609741 96830484 509673472 4.2021532059 4.0381922722 3.9482131004 164 6.5200000000 0.0116713513 0.0104164860 0.0160688832 0.0130123798 0.0059650000 0.0006400000 0.0026220000 0.0000020000 0.0000160000 0.0015650000 13612517 96830484 509673472 4.1990146637 4.0369725227 3.9498836994 165 6.5600000000 0.0115759065 0.0104235128 0.0160688832 0.0130009686 0.0075330000 0.0006400000 0.0028980000 0.0000150000 0.0000160000 0.0028500000 13615293 96830484 509673472 4.1946964264 4.0400876999 3.9517099857 166 6.6000000000 0.0115214540 0.0104301269 0.0160688832 0.0130112492 0.0055590000 0.0005540000 0.0029010000 0.0000010000 0.0000110000 0.0013550000 13618069 96830484 509673472 4.1891279221 4.0387039185 3.9543244839 167 6.6400000000 0.0115315160 0.0104367220 0.0160688832 0.0130286810 0.0066980000 0.0006420000 0.0030270000 0.0000160000 0.0000160000 0.0018680000 13620845 96830484 509673472 4.1849646568 4.0384716988 3.9564552307 168 6.6800000000 0.0115816323 0.0104435370 0.0160688832 0.0130288862 0.0064230000 0.0006400000 0.0030660000 0.0000020000 0.0000150000 0.0015600000 13623621 96830484 509673472 4.1812028885 4.0408926010 3.9582824707 169 6.7200000000 0.0116372323 0.0104506003 0.0160688832 0.0130724696 0.0072870000 0.0006380000 0.0029270000 0.0000160000 0.0000140000 0.0028480000 13626397 96830484 509673472 4.1770462990 4.0397033691 3.9600036144 170 6.7600000000 0.0116150314 0.0104574499 0.0160688832 0.0130888505 0.0064400000 0.0006440000 0.0031170000 0.0000020000 0.0000150000 0.0015300000 13629173 96830484 509673472 4.1733431816 4.0386414528 3.9614465237 171 6.8000000000 0.0117521854 0.0104650214 0.0160688832 0.0131028443 0.0064450000 0.0006430000 0.0033770000 0.0000150000 0.0000140000 0.0016340000 13631949 96830484 509673472 4.1702237129 4.0412840843 3.9623920918 172 6.8400000000 0.0118812369 0.0104732552 0.0160688832 0.0131235355 0.0064340000 0.0006410000 0.0030910000 0.0000010000 0.0000150000 0.0015550000 13634725 96830484 509673472 4.1676201820 4.0422782898 3.9634299278 173 6.8800000000 0.0121325701 0.0104828466 0.0160688832 0.0131499051 0.0063610000 0.0005530000 0.0025040000 0.0000110000 0.0000100000 0.0025220000 13637501 96830484 509673472 4.1663808823 4.0419535637 3.9638209343 174 6.9200000000 0.0121229133 0.0104922723 0.0160688832 0.0131792303 0.0052210000 0.0005160000 0.0028810000 0.0000010000 0.0000080000 0.0012440000 13640277 96830484 509673472 4.1649384499 4.0400490761 3.9652528763 175 6.9600000000 0.0121590430 0.0105017967 0.0160688832 0.0132192951 0.0066530000 0.0006400000 0.0029790000 0.0000170000 0.0000160000 0.0018630000 13643053 96830484 509673472 4.1648783684 4.0410509109 3.9655885696 176 7.0000000000 0.0118981143 0.0105097303 0.0160688832 0.0132258749 0.0064340000 0.0006380000 0.0031510000 0.0000040000 0.0000170000 0.0015660000 13645829 96830484 509673472 4.1653122902 4.0422964096 3.9654922485 177 7.0400000000 0.0117951175 0.0105169924 0.0160688832 0.0132658122 0.0074000000 0.0006410000 0.0030110000 0.0000160000 0.0000140000 0.0028770000 13648605 96830484 509673472 4.1632003784 4.0442295074 3.9663479328 178 7.0800000000 0.0116542503 0.0105233815 0.0160688832 0.0133047192 0.0052710000 0.0005560000 0.0028730000 0.0000010000 0.0000100000 0.0012460000 13651381 96830484 509673472 4.1613087654 4.0444998741 3.9668340683 179 7.1200000000 0.0115920119 0.0105293515 0.0160688832 0.0133609251 0.0069560000 0.0006370000 0.0032310000 0.0000150000 0.0000130000 0.0018920000 13654157 96830484 509673472 4.1599836349 4.0428600311 3.9675326347 180 7.1600000000 0.0115941614 0.0105352671 0.0160688832 0.0133910802 0.0058070000 0.0005520000 0.0030960000 0.0000010000 0.0000100000 0.0013650000 13656933 96830484 509673472 4.1590299606 4.0444564819 3.9677834511 181 7.2000000000 0.0115336068 0.0105407828 0.0160688832 0.0133803492 0.0069670000 0.0005170000 0.0034570000 0.0000080000 0.0000070000 0.0023820000 13659709 96830484 509673472 4.1564440727 4.0446534157 3.9684538841 182 7.2400000000 0.0115826614 0.0105465074 0.0160688832 0.0133737754 0.0053980000 0.0005170000 0.0030120000 0.0000010000 0.0000070000 0.0012640000 13662485 96830484 509673472 4.1560988426 4.0459251404 3.9684069157 183 7.2800000000 0.0116052469 0.0105522929 0.0160688832 0.0133593326 0.0070290000 0.0006290000 0.0032430000 0.0000150000 0.0000140000 0.0019280000 13665261 96830484 509673472 4.1517033577 4.0466742516 3.9696104527 184 7.3200000000 0.0115758935 0.0105578559 0.0160688832 0.0133611029 0.0064760000 0.0006430000 0.0030940000 0.0000020000 0.0000150000 0.0016300000 13668037 96830484 509673472 4.1499590874 4.0453791618 3.9699103832 185 7.3600000000 0.0116379540 0.0105636943 0.0160688832 0.0133487917 0.0080880000 0.0006380000 0.0032580000 0.0000160000 0.0000140000 0.0029120000 13670813 96830484 509673472 4.1450138092 4.0458960533 3.9703209400 186 7.4000000000 0.0116548650 0.0105695608 0.0160688832 0.0133614287 0.0047000000 0.0005230000 0.0024120000 0.0000010000 0.0000070000 0.0012420000 13673589 96830484 509673472 4.1449003220 4.0455937386 3.9707939625 187 7.4400000000 0.0116595691 0.0105753897 0.0160688832 0.0133787320 0.0070100000 0.0006580000 0.0030920000 0.0000170000 0.0000140000 0.0019640000 13676365 96830484 509673472 4.1424884796 4.0439262390 3.9710266590 188 7.4800000000 0.0117093921 0.0105814216 0.0160688832 0.0133939288 0.0057600000 0.0005550000 0.0029500000 0.0000010000 0.0000120000 0.0013960000 13679141 96830484 509673472 4.1395864487 4.0431423187 3.9719722271 189 7.5200000000 0.0116102677 0.0105868653 0.0160688832 0.0134276538 0.0080070000 0.0006650000 0.0031130000 0.0000160000 0.0000140000 0.0029290000 13681917 96830484 509673472 4.1372241974 4.0444159508 3.9727182388 190 7.5600000000 0.0116227074 0.0105923171 0.0160688832 0.0134802292 0.0058690000 0.0006410000 0.0029360000 0.0000020000 0.0000150000 0.0014070000 13684693 96830484 509673472 4.1345310211 4.0428118706 3.9734582901 191 7.6000000000 0.0117209302 0.0105982260 0.0160688832 0.0135193334 0.0056470000 0.0005160000 0.0028790000 0.0000080000 0.0000080000 0.0015920000 13687469 96830484 509673472 4.1329994202 4.0449962616 3.9736545086 192 7.6400000000 0.0117069371 0.0106040006 0.0160688832 0.0135407815 0.0068850000 0.0006580000 0.0032510000 0.0000020000 0.0000170000 0.0016560000 13690245 96830484 509673472 4.1303176880 4.0446257591 3.9739472866 193 7.6800000000 0.0115790442 0.0106090526 0.0160688832 0.0135749721 0.0069890000 0.0005620000 0.0029510000 0.0000100000 0.0000090000 0.0025820000 13693021 96830484 509673472 4.1289153099 4.0451693535 3.9744145870 194 7.7200000000 0.0116360262 0.0106143463 0.0160688832 0.0135791794 0.0053040000 0.0005210000 0.0028700000 0.0000000000 0.0000080000 0.0012690000 13695797 96830484 509673472 4.1264662743 4.0436534882 3.9741585255 195 7.7600000000 0.0117199644 0.0106200161 0.0160688832 0.0135758506 0.0072380000 0.0006560000 0.0032710000 0.0000160000 0.0000140000 0.0019390000 13698573 96830484 509673472 4.1270208359 4.0458102226 3.9741997719 196 7.8000000000 0.0116302185 0.0106251702 0.0160688832 0.0135625823 0.0069270000 0.0006560000 0.0032960000 0.0000020000 0.0000160000 0.0016250000 13701349 96830484 509673472 4.1233110428 4.0450711250 3.9741001129 197 7.8400000000 0.0116260406 0.0106302508 0.0160688832 0.0135739347 0.0067040000 0.0005560000 0.0029420000 0.0000100000 0.0000110000 0.0025100000 13704125 96830484 509673472 4.1271891594 4.0456624031 3.9743757248 198 7.8800000000 0.0116700390 0.0106355022 0.0160688832 0.0135796177 0.0067430000 0.0006410000 0.0030970000 0.0000020000 0.0000150000 0.0016410000 13706901 96830484 509673472 4.1250023842 4.0462226868 3.9744000435 199 7.9200000000 0.0116127152 0.0106404129 0.0160688832 0.0136031886 0.0072040000 0.0007200000 0.0031090000 0.0000170000 0.0000150000 0.0018990000 13709677 96830484 509673472 4.1297426224 4.0473942757 3.9747843742 200 7.9600000000 0.0116069363 0.0106452455 0.0160688832 0.0136177285 0.0067210000 0.0006510000 0.0030950000 0.0000010000 0.0000160000 0.0016070000 13712453 96830484 509673472 4.1285138130 4.0486545563 3.9746496677 201 8.0000000000 0.0116120391 0.0106500554 0.0160688832 0.0136318572 0.0080410000 0.0006410000 0.0032900000 0.0000170000 0.0000140000 0.0028830000 13715229 96830484 509673472 4.1307344437 4.0491271019 3.9749534130 202 8.0400000000 0.0116138048 0.0106548264 0.0160688832 0.0136289569 0.0059870000 0.0005670000 0.0034080000 0.0000010000 0.0000100000 0.0013140000 13718005 96830484 509673472 4.1294364929 4.0488495827 3.9750237465 203 8.0800000000 0.0116115715 0.0106595395 0.0160688832 0.0136116827 0.0061940000 0.0005550000 0.0030960000 0.0000120000 0.0000090000 0.0016700000 13720781 96830484 509673472 4.1265015602 4.0501451492 3.9753510952 204 8.1200000000 0.0116585875 0.0106644368 0.0160688832 0.0135828787 0.0055510000 0.0005200000 0.0030400000 0.0000010000 0.0000090000 0.0012800000 13723557 96830484 509673472 4.1254248619 4.0523872375 3.9759654999 205 8.1600000000 0.0116838263 0.0106694094 0.0160688832 0.0135581597 0.0064290000 0.0005230000 0.0028320000 0.0000070000 0.0000070000 0.0023680000 13726333 96830484 509673472 4.1232066154 4.0507121086 3.9765880108 206 8.1999999990 0.0117156729 0.0106744883 0.0160688832 0.0135417312 0.0054000000 0.0005260000 0.0028750000 0.0000000000 0.0000080000 0.0012840000 13729109 96830484 509673472 4.1206374168 4.0482864380 3.9780845642 207 8.2400000000 0.0115755619 0.0106788414 0.0160688832 0.0135364721 0.0065700000 0.0005280000 0.0037500000 0.0000080000 0.0000070000 0.0015690000 13731885 96830484 509673472 4.1189060211 4.0497241020 3.9789192677 208 8.2799999990 0.0117152603 0.0106838241 0.0160688832 0.0135544107 0.0053720000 0.0005210000 0.0028500000 0.0000010000 0.0000070000 0.0012870000 13734661 96830484 509673472 4.1192083359 4.0470905304 3.9807801247 209 8.3200000000 0.0117737437 0.0106890391 0.0160688832 0.0135663292 0.0079860000 0.0006420000 0.0030550000 0.0000170000 0.0000140000 0.0028350000 13737437 96830484 509673472 4.1173577309 4.0491070747 3.9813501835 210 8.3599999990 0.0117114391 0.0106939076 0.0160688832 0.0135809382 0.0060700000 0.0006420000 0.0030600000 0.0000020000 0.0000150000 0.0013960000 13740213 96830484 509673472 4.1144614220 4.0526261330 3.9819629192 211 8.4000000000 0.0118208164 0.0106992484 0.0160688832 0.0136140192 0.0055870000 0.0005180000 0.0028460000 0.0000080000 0.0000070000 0.0015570000 13742989 96830484 509673472 4.1122641563 4.0532169342 3.9828681946 212 8.4399999990 0.0117843691 0.0107043669 0.0160688832 0.0136392276 0.0068170000 0.0006420000 0.0030720000 0.0000020000 0.0000170000 0.0016270000 13745765 96830484 509673472 4.1128053665 4.0502676964 3.9848477840 213 8.4800000000 0.0118178185 0.0107095944 0.0160688832 0.0136509799 0.0072560000 0.0006470000 0.0030880000 0.0000150000 0.0000160000 0.0025030000 13748541 96830484 509673472 4.1087660789 4.0516605377 3.9856498241 214 8.5200000000 0.0117556704 0.0107144826 0.0160688832 0.0136666599 0.0054100000 0.0005270000 0.0028540000 0.0000020000 0.0000080000 0.0012780000 13751317 96830484 509673472 4.1077041626 4.0515513420 3.9871094227 215 8.5600000000 0.0118572721 0.0107197979 0.0160688832 0.0137002227 0.0054040000 0.0005100000 0.0028050000 0.0000060000 0.0000050000 0.0014980000 13754093 96830484 509673472 4.1060776711 4.0499148369 3.9883601665 216 8.6000000000 0.0118775824 0.0107251580 0.0160688832 0.0137168042 0.0067750000 0.0006400000 0.0030840000 0.0000020000 0.0000140000 0.0016100000 13756869 96830484 509673472 4.1088337898 4.0540084839 3.9906806946 217 8.6400000000 0.0119291386 0.0107307063 0.0160688832 0.0137190736 0.0076170000 0.0006410000 0.0032440000 0.0000170000 0.0000130000 0.0027500000 13759645 96830484 509673472 4.1085910797 4.0555891991 3.9921059608 218 8.6800000000 0.0119597372 0.0107363441 0.0160688832 0.0137276417 0.0051620000 0.0005330000 0.0028570000 0.0000010000 0.0000080000 0.0011870000 13762421 96830484 509673472 4.1110949516 4.0548601151 3.9943966866 219 8.7200000000 0.0119779333 0.0107420134 0.0160688832 0.0137533439 0.0070920000 0.0006430000 0.0030780000 0.0000150000 0.0000140000 0.0018990000 13765197 96830484 509673472 4.1132030487 4.0541253090 3.9978857040 220 8.7600000000 0.0120643340 0.0107480240 0.0160688832 0.0137669201 0.0058710000 0.0005570000 0.0029490000 0.0000010000 0.0000100000 0.0013880000 13767973 96830484 509673472 4.1134219170 4.0522065163 4.0012884140 221 8.8000000000 0.0119110467 0.0107532865 0.0160688832 0.0137922136 0.0064710000 0.0005260000 0.0028450000 0.0000080000 0.0000080000 0.0023340000 13770749 96830484 509673472 4.1150159836 4.0525093079 4.0035743713 222 8.8400000000 0.0119638517 0.0107587395 0.0160688832 0.0138204151 0.0051560000 0.0005150000 0.0028140000 0.0000010000 0.0000060000 0.0012170000 13773525 96830484 509673472 4.1137318611 4.0546455383 4.0052337646 223 8.8800000000 0.0119575448 0.0107641153 0.0160688832 0.0138590941 0.0071920000 0.0006600000 0.0030650000 0.0000150000 0.0000140000 0.0019050000 13776301 96830484 509673472 4.1125259399 4.0534796715 4.0072221756 224 8.9200000000 0.0119394641 0.0107693624 0.0160688832 0.0138783238 0.0061130000 0.0006460000 0.0030480000 0.0000020000 0.0000100000 0.0013960000 13779077 96830484 509673472 4.1087183952 4.0531816483 4.0082912445 225 8.9600000000 0.0119410073 0.0107745697 0.0160688832 0.0140224392 0.0064170000 0.0005180000 0.0029840000 0.0000090000 0.0000070000 0.0022960000 13781853 96830484 509673472 4.0668554306 4.0475258827 3.9936120510 226 9.0000000000 0.0119322129 0.0107796920 0.0160688832 0.0140292332 0.0052680000 0.0004930000 0.0029640000 0.0000000000 0.0000060000 0.0011950000 13784629 96830484 509673472 4.0616412163 4.0507512093 3.9927377701 227 9.0400000000 0.0119649796 0.0107849136 0.0160688832 0.0140363294 0.0073840000 0.0005010000 0.0047590000 0.0000070000 0.0000060000 0.0014910000 13787405 96830484 509673472 4.0582571030 4.0495471954 3.9932801723 228 9.0800000000 0.0118830102 0.0107897298 0.0160688832 0.0140441193 0.0052690000 0.0004970000 0.0029550000 0.0000000000 0.0000070000 0.0011900000 13790181 96830484 509673472 4.0544843674 4.0495352745 3.9934213161 229 9.1200000000 0.0119984904 0.0107950082 0.0160688832 0.0140502645 0.0064420000 0.0005670000 0.0029500000 0.0000060000 0.0000070000 0.0021990000 13792957 96830484 509673472 4.0500550270 4.0491719246 3.9931252003 230 9.1600000000 0.0119134858 0.0107998712 0.0160688832 0.0140598307 0.0070840000 0.0006470000 0.0032840000 0.0000020000 0.0000160000 0.0016160000 13795733 96830484 509673472 4.0452485085 4.0494308472 3.9931881428 231 9.2000000000 0.0119501483 0.0108048507 0.0160688832 0.0140644640 0.0078430000 0.0006560000 0.0036930000 0.0000160000 0.0000140000 0.0018810000 13798509 96830484 509673472 4.0414218903 4.0490555763 3.9926583767 232 9.2400000000 0.0120531609 0.0108102314 0.0160688832 0.0140708172 0.0067450000 0.0006410000 0.0036670000 0.0000020000 0.0000100000 0.0013760000 13801285 96830484 509673472 4.0377044678 4.0484943390 3.9929616451 233 9.2800000000 0.0120260334 0.0108154494 0.0160688832 0.0140828378 0.0062840000 0.0005190000 0.0029620000 0.0000060000 0.0000050000 0.0022060000 13804061 96830484 509673472 4.0350041389 4.0494179726 3.9921481609 234 9.3200000000 0.0120217334 0.0108206045 0.0160688832 0.0140861559 0.0050150000 0.0004880000 0.0029380000 0.0000010000 0.0000050000 0.0011330000 13806837 96830484 509673472 4.0307021141 4.0494585037 3.9914469719 235 9.3600000000 0.0121159237 0.0108261165 0.0160688832 0.0141059848 0.0063810000 0.0005750000 0.0030650000 0.0000110000 0.0000100000 0.0016530000 13809613 96830484 509673472 4.0281796455 4.0488562584 3.9913547039 236 9.4000000000 0.0120345419 0.0108312369 0.0160688832 0.0141431008 0.0061160000 0.0005730000 0.0030990000 0.0000010000 0.0000110000 0.0013740000 13812389 96830484 509673472 4.0254273415 4.0476431847 3.9910676479 237 9.4400000000 0.0119886957 0.0108361207 0.0160688832 0.0141720838 0.0070670000 0.0005530000 0.0030700000 0.0000110000 0.0000090000 0.0024380000 13815165 96830484 509673472 4.0226006508 4.0448002815 3.9906272888 238 9.4800000000 0.0120102298 0.0108410539 0.0160688832 0.0141971120 0.0069280000 0.0006420000 0.0030730000 0.0000020000 0.0000160000 0.0015980000 13817941 96830484 509673472 4.0189938545 4.0408153534 3.9903376102 239 9.5200000000 0.0119573232 0.0108457245 0.0160688832 0.0142099915 0.0064220000 0.0005520000 0.0035130000 0.0000100000 0.0000090000 0.0015320000 13820717 96830484 509673472 4.0166926384 4.0411233902 3.9899044037 240 9.5600000000 0.0121046007 0.0108509698 0.0160688832 0.0143569834 0.0069200000 0.0006420000 0.0030650000 0.0000010000 0.0000140000 0.0015930000 13823493 96830484 509673472 4.0139017105 4.0350637436 3.9909949303 241 9.6000000000 0.0120631848 0.0108559998 0.0160688832 0.0143556018 0.0073540000 0.0006400000 0.0031930000 0.0000110000 0.0000100000 0.0024180000 13826269 96830484 509673472 4.0113363266 4.0350699425 3.9900908470 242 9.6400000000 0.0121525871 0.0108613576 0.0160688832 0.0143684178 0.0054460000 0.0005180000 0.0028550000 0.0000010000 0.0000080000 0.0012330000 13829045 96830484 509673472 4.0102138519 4.0327820778 3.9905996323 243 9.6800000000 0.0121802483 0.0108667851 0.0160688832 0.0143833021 0.0054240000 0.0004950000 0.0027870000 0.0000060000 0.0000050000 0.0014650000 13831821 96830484 509673472 4.0083212852 4.0301580429 3.9902913570 244 9.7200000000 0.0121362675 0.0108719879 0.0160688832 0.0143926178 0.0052990000 0.0005020000 0.0029610000 0.0000010000 0.0000060000 0.0011650000 13834597 96830484 509673472 4.0066981316 4.0294318199 3.9906635284 245 9.7600000000 0.0121222306 0.0108770909 0.0160688832 0.0143908502 0.0082710000 0.0006410000 0.0032170000 0.0000160000 0.0000140000 0.0027460000 13837373 96830484 509673472 4.0048422813 4.0302319527 3.9904367924 246 9.8000000000 0.0122245094 0.0108825682 0.0160688832 0.0143943324 0.0071510000 0.0006640000 0.0032480000 0.0000020000 0.0000140000 0.0015930000 13840149 96830484 509673472 4.0029058456 4.0289692879 3.9904227257 247 9.8400000000 0.0122953560 0.0108882880 0.0160688832 0.0144014852 0.0064150000 0.0005540000 0.0035190000 0.0000110000 0.0000090000 0.0014940000 13842925 96830484 509673472 3.9997186661 4.0285434723 3.9895806313 248 9.8800000000 0.0124175660 0.0108944545 0.0160688832 0.0143984694 0.0057260000 0.0004930000 0.0034080000 0.0000010000 0.0000060000 0.0011480000 13845701 96830484 509673472 3.9964387417 4.0253024101 3.9891471863 249 9.9200000000 0.0124385655 0.0109006557 0.0160688832 0.0143998972 0.0080480000 0.0006410000 0.0032270000 0.0000150000 0.0000140000 0.0026980000 13848477 96830484 509673472 3.9924435616 4.0222187042 3.9873445034 250 9.9600000000 0.0124001121 0.0109066535 0.0160688832 0.0143932905 0.0057960000 0.0005570000 0.0030690000 0.0000020000 0.0000100000 0.0013120000 13851253 96830484 509673472 3.9895975590 4.0222506523 3.9865720272 251 10.0000000000 0.0124295615 0.0109127209 0.0160688832 0.0143939242 0.0061940000 0.0005570000 0.0028920000 0.0000110000 0.0000100000 0.0016050000 13854029 96830484 509673472 3.9863150120 4.0198907852 3.9855372906 252 10.0400000000 0.0125617366 0.0109192646 0.0160688832 0.0144000737 0.0071490000 0.0006410000 0.0032650000 0.0000020000 0.0000150000 0.0015460000 13856805 96830484 509673472 3.9826872349 4.0179252625 3.9842252731 253 10.0800000000 0.0125310039 0.0109256351 0.0160688832 0.0143968325 0.0071970000 0.0005550000 0.0035170000 0.0000100000 0.0000090000 0.0022550000 13859581 96830484 509673472 3.9798996449 4.0172915459 3.9833703041 254 10.1200000000 0.0124261715 0.0109315428 0.0160688832 0.0143937528 0.0065110000 0.0005540000 0.0035170000 0.0000010000 0.0000100000 0.0013120000 13862357 96830484 509673472 3.9772419930 4.0153064728 3.9828827381 255 10.1600000000 0.0124056749 0.0109373237 0.0160688832 0.0143873983 0.0054760000 0.0005180000 0.0028250000 0.0000080000 0.0000070000 0.0014330000 13865133 96830484 509673472 3.9745330811 4.0142436028 3.9816989899 256 10.2000000000 0.0122643774 0.0109425075 0.0160688832 0.0143861596 0.0069050000 0.0006380000 0.0035230000 0.0000020000 0.0000150000 0.0015320000 13867909 96830484 509673472 3.9720866680 4.0129404068 3.9812889099 257 10.2400000000 0.0122017888 0.0109474074 0.0160688832 0.0144946351 0.0078820000 0.0006360000 0.0032430000 0.0000160000 0.0000140000 0.0026210000 13895261 96830484 509673472 3.9675180912 4.0092406273 3.9801466465 258 10.2800000000 0.0121746389 0.0109521641 0.0160688832 0.0144971546 0.0053440000 0.0005180000 0.0029870000 0.0000010000 0.0000080000 0.0011290000 13949237 96830484 509673472 3.9649574757 4.0083513260 3.9787087440 259 10.3200000000 0.0120441699 0.0109563803 0.0160688832 0.0144883634 0.0079060000 0.0006660000 0.0036710000 0.0000160000 0.0000130000 0.0017940000 13952013 96830484 509673472 3.9630773067 4.0071306229 3.9777951241 260 10.3600000000 0.0120118828 0.0109604400 0.0160688832 0.0144772374 0.0076310000 0.0006410000 0.0036850000 0.0000020000 0.0000150000 0.0015170000 13954789 96830484 509673472 3.9611382484 4.0052981377 3.9770269394 261 10.4000000000 0.0120138591 0.0109644761 0.0160688832 0.0144590393 0.0064680000 0.0005530000 0.0028620000 0.0000080000 0.0000070000 0.0021520000 13957565 96830484 509673472 3.9593005180 4.0040378571 3.9760355949 262 10.4400000000 0.0120066311 0.0109684538 0.0160688832 0.0144412679 0.0073350000 0.0006730000 0.0035250000 0.0000020000 0.0000160000 0.0015100000 13960341 96830484 509673472 3.9570848942 4.0022821426 3.9750616550 263 10.4800000000 0.0120562520 0.0109725899 0.0160688832 0.0144237585 0.0079190000 0.0006400000 0.0036830000 0.0000150000 0.0000130000 0.0017720000 13963117 96830484 509673472 3.9549739361 4.0011577606 3.9739418030 264 10.5200000000 0.0120295659 0.0109765936 0.0160688832 0.0144075587 0.0061190000 0.0005550000 0.0035030000 0.0000010000 0.0000080000 0.0011620000 13965893 96830484 509673472 3.9533216953 3.9998438358 3.9734835625 265 10.5600000000 0.0120313177 0.0109805737 0.0160688832 0.0143928785 0.0084500000 0.0006430000 0.0036770000 0.0000180000 0.0000140000 0.0025910000 13968669 96830484 509673472 3.9502968788 3.9978029728 3.9711713791 266 10.6000000000 0.0120846368 0.0109847243 0.0160688832 0.0143840833 0.0052940000 0.0005150000 0.0028330000 0.0000010000 0.0000080000 0.0011530000 13971445 96830484 509673472 3.9474806786 3.9957513809 3.9695274830 267 10.6400000000 0.0119294059 0.0109882624 0.0160688832 0.0143860973 0.0074410000 0.0006400000 0.0031930000 0.0000150000 0.0000140000 0.0017900000 13974221 96830484 509673472 3.9451508522 3.9948296547 3.9680604935 268 10.6800000000 0.0119257336 0.0109917604 0.0160688832 0.0143919656 0.0055180000 0.0005560000 0.0028970000 0.0000010000 0.0000080000 0.0011510000 13976997 96830484 509673472 3.9425895214 3.9930498600 3.9663734436 269 10.7200000000 0.0119389053 0.0109952814 0.0160688832 0.0144031031 0.0087110000 0.0006400000 0.0036600000 0.0000150000 0.0000140000 0.0025730000 13979773 96830484 509673472 3.9402730465 3.9911727905 3.9647593498 270 10.7600000000 0.0119658075 0.0109988760 0.0160688832 0.0144095120 0.0063060000 0.0006360000 0.0030620000 0.0000020000 0.0000140000 0.0013730000 13982549 96830484 509673472 3.9375250340 3.9894006252 3.9622817039 271 10.8000000000 0.0120147243 0.0110026245 0.0160688832 0.0144144726 0.0062110000 0.0005510000 0.0028850000 0.0000100000 0.0000090000 0.0015330000 13985325 96830484 509673472 3.9352228642 3.9876315594 3.9605224133 272 10.8400000000 0.0117359105 0.0110053204 0.0160688832 0.0144318677 0.0075380000 0.0006440000 0.0036960000 0.0000020000 0.0000150000 0.0014670000 13988101 96830484 509673472 3.9327678680 3.9856266975 3.9584655762 273 10.8800000000 0.0117304837 0.0110079767 0.0160688832 0.0144477655 0.0071740000 0.0006360000 0.0030630000 0.0000170000 0.0000130000 0.0022130000 13990877 96830484 509673472 3.9301698208 3.9837779999 3.9561913013 274 10.9200000000 0.0116463834 0.0110103066 0.0160688832 0.0144580893 0.0061980000 0.0006380000 0.0028880000 0.0000020000 0.0000150000 0.0014230000 13993653 96830484 509673472 3.9282910824 3.9821786880 3.9547772408 275 10.9600000000 0.0116953338 0.0110127976 0.0160688832 0.0144668242 0.0064260000 0.0005580000 0.0030600000 0.0000100000 0.0000090000 0.0015450000 13996429 96830484 509673472 3.9261560440 3.9801597595 3.9530804157 276 11.0000000000 0.0116245393 0.0110150141 0.0160688832 0.0144665070 0.0060090000 0.0005160000 0.0034420000 0.0000010000 0.0000070000 0.0011170000 13999205 96830484 509673472 3.9242277145 3.9795618057 3.9512965679 277 11.0400000000 0.0117558278 0.0110176885 0.0160688832 0.0147822957 0.0086290000 0.0006440000 0.0036460000 0.0000160000 0.0000160000 0.0024680000 14001981 96830484 509673472 3.9162716866 3.9722597599 3.9443686008 278 11.0800000000 0.0115797352 0.0110197102 0.0160688832 0.0147756387 0.0055840000 0.0005550000 0.0030060000 0.0000010000 0.0000080000 0.0010990000 14004757 96830484 509673472 3.9143695831 3.9699630737 3.9426515102 279 11.1200000000 0.0115655540 0.0110216667 0.0160688832 0.0147625122 0.0072210000 0.0006350000 0.0032070000 0.0000150000 0.0000150000 0.0017230000 14007533 96830484 509673472 3.9129459858 3.9675540924 3.9418022633 280 11.1600000000 0.0113013508 0.0110226655 0.0160688832 0.0147536757 0.0059360000 0.0005540000 0.0033620000 0.0000010000 0.0000080000 0.0010870000 14010309 96830484 509673472 3.9118974209 3.9663498402 3.9412100315 281 11.2000000000 0.0112645198 0.0110235262 0.0160688832 0.0147523007 0.0104880000 0.0006390000 0.0060570000 0.0000160000 0.0000140000 0.0024770000 14013085 96830484 509673472 3.9106421471 3.9640531540 3.9402334690 282 11.2400000000 0.0110966070 0.0110237854 0.0160688832 0.0147508518 0.0057870000 0.0005340000 0.0034310000 0.0000000000 0.0000080000 0.0010380000 14015861 96830484 509673472 3.9093265533 3.9630529881 3.9388813972 283 11.2800000000 0.0108504929 0.0110231730 0.0160688832 0.0147426479 0.0056390000 0.0004810000 0.0033370000 0.0000050000 0.0000040000 0.0012560000 14018637 96830484 509673472 3.9084038734 3.9605188370 3.9380054474 284 11.3200000000 0.0105146132 0.0110213823 0.0160688832 0.0147487550 0.0048250000 0.0004640000 0.0028940000 0.0000000000 0.0000040000 0.0009750000 14021413 96830484 509673472 3.9072015285 3.9588119984 3.9368870258 285 11.3600000000 0.0104379430 0.0110193352 0.0160688832 0.0147454608 0.0082590000 0.0006430000 0.0032150000 0.0000170000 0.0000140000 0.0024320000 14024189 96830484 509673472 3.9061286449 3.9568264484 3.9356727600 286 11.4000000000 0.0102029350 0.0110164806 0.0160688832 0.0147332685 0.0069160000 0.0006440000 0.0032570000 0.0000020000 0.0000150000 0.0014120000 14026965 96830484 509673472 3.9053127766 3.9542326927 3.9347257614 287 11.4400000000 0.0101194298 0.0110133550 0.0160688832 0.0147172471 0.0065670000 0.0005570000 0.0035550000 0.0000090000 0.0000070000 0.0013950000 14029741 96830484 509673472 3.9046258926 3.9526815414 3.9339933395 288 11.4800000000 0.0099943252 0.0110098167 0.0160688832 0.0146967871 0.0060370000 0.0005030000 0.0037120000 0.0000010000 0.0000060000 0.0010060000 14032517 96830484 509673472 3.9035081863 3.9502880573 3.9326581955 289 11.5200000000 0.0097573837 0.0110054830 0.0160688832 0.0146814740 0.0069270000 0.0005050000 0.0037010000 0.0000060000 0.0000060000 0.0019080000 14035293 96830484 509673472 3.9031894207 3.9477007389 3.9321224689 290 11.5600000000 0.0095481565 0.0110004578 0.0160688832 0.0146672803 0.0052720000 0.0005010000 0.0029490000 0.0000010000 0.0000080000 0.0010120000 14038069 96830484 509673472 3.9025628567 3.9465286732 3.9315209389 291 11.6000000000 0.0096532023 0.0109958280 0.0160688832 0.0146452661 0.0060190000 0.0005050000 0.0033990000 0.0000080000 0.0000050000 0.0013020000 14040845 96830484 509673472 3.9022538662 3.9449093342 3.9312252998 292 11.6400000000 0.0094360579 0.0109904864 0.0160688832 0.0146208378 0.0052670000 0.0005020000 0.0029520000 0.0000010000 0.0000070000 0.0009980000 14043621 96830484 509673472 3.9014799595 3.9425194263 3.9298787117 293 11.6800000000 0.0092904875 0.0109846843 0.0160688832 0.0145958151 0.0088050000 0.0005010000 0.0056330000 0.0000070000 0.0000050000 0.0018480000 14046397 96830484 509673472 3.9012444019 3.9405083656 3.9294981956 294 11.7200000000 0.0092231436 0.0109786927 0.0160688832 0.0145722039 0.0078000000 0.0004990000 0.0054980000 0.0000010000 0.0000070000 0.0009920000 14049173 96830484 509673472 3.9010734558 3.9394452572 3.9287834167 295 11.7600000000 0.0087708831 0.0109712086 0.0160688832 0.0145545031 0.0060780000 0.0004870000 0.0036540000 0.0000050000 0.0000060000 0.0012440000 14051949 96830484 509673472 3.9009716511 3.9339942932 3.9283373356 296 11.8000000000 0.0085651483 0.0109630800 0.0160688832 0.0145347127 0.0068320000 0.0004860000 0.0047080000 0.0000010000 0.0000050000 0.0009540000 14054725 96830484 509673472 3.9010004997 3.9316513538 3.9281263351 297 11.8400000000 0.0083470931 0.0109542720 0.0160688832 0.0145214660 0.0061880000 0.0004810000 0.0032230000 0.0000050000 0.0000050000 0.0017960000 14057501 96830484 509673472 3.9005901814 3.9304494858 3.9272019863 298 11.8800000000 0.0082065761 0.0109450515 0.0160688832 0.0145563729 0.0054920000 0.0004860000 0.0033590000 0.0000010000 0.0000060000 0.0009620000 14060277 96830484 509673472 3.8993875980 3.9264707565 3.9250762463 299 11.9200000000 0.0080888616 0.0109354990 0.0160688832 0.0145594732 0.0076090000 0.0006970000 0.0032230000 0.0000170000 0.0000140000 0.0016450000 14063053 96830484 509673472 3.8986701965 3.9247670174 3.9237415791 300 11.9600000000 0.0077533433 0.0109248918 0.0160688832 0.0145717839 0.0073420000 0.0006400000 0.0037320000 0.0000020000 0.0000160000 0.0013500000 14065829 96830484 509673472 3.8983719349 3.9225375652 3.9230763912 301 12.0000000000 0.0076666642 0.0109140672 0.0160688832 0.0145784155 0.0078770000 0.0006390000 0.0032120000 0.0000150000 0.0000140000 0.0023350000 14068605 96830484 509673472 3.8976280689 3.9204955101 3.9218592644 302 12.0400000000 0.0073506846 0.0109022679 0.0160688832 0.0146169565 0.0053190000 0.0005190000 0.0029890000 0.0000010000 0.0000070000 0.0009890000 14071381 96830484 509673472 3.8954520226 3.9168007374 3.9182760715 303 12.0800000000 0.0073328693 0.0108904877 0.0160688832 0.0146022013 0.0090030000 0.0005730000 0.0056040000 0.0000110000 0.0000100000 0.0014200000 14074157 96830484 509673472 3.8941364288 3.9151141644 3.9162027836 304 12.1200000000 0.0071610780 0.0108782199 0.0160688832 0.0145898365 0.0053090000 0.0005280000 0.0029770000 0.0000010000 0.0000070000 0.0009720000 14076933 96830484 509673472 3.8926615715 3.9130625725 3.9136860371 305 12.1600000000 0.0071476456 0.0108659885 0.0160688832 0.0145831768 0.0058550000 0.0004850000 0.0029160000 0.0000050000 0.0000050000 0.0017460000 14079709 96830484 509673472 3.8913786411 3.9119272232 3.9117038250 306 12.2000000000 0.0068284990 0.0108527941 0.0160688832 0.0145826342 0.0072740000 0.0006450000 0.0032440000 0.0000020000 0.0000150000 0.0013020000 14082485 96830484 509673472 3.8906404972 3.9093313217 3.9099543095 307 12.2400000000 0.0068635880 0.0108397999 0.0160688832 0.0145967166 0.0064950000 0.0005550000 0.0033520000 0.0000110000 0.0000090000 0.0013680000 14085261 96830484 509673472 3.8892195225 3.9076378345 3.9077844620 308 12.2800000000 0.0067613735 0.0108265583 0.0160688832 0.0146137657 0.0070450000 0.0006410000 0.0032430000 0.0000020000 0.0000160000 0.0012920000 14088037 96830484 509673472 3.8875830173 3.9058256149 3.9050323963 309 12.3200000000 0.0067258878 0.0108132875 0.0160688832 0.0146125654 0.0072470000 0.0006400000 0.0032020000 0.0000110000 0.0000090000 0.0019810000 14090813 96830484 509673472 3.8859126568 3.9039957523 3.9019513130 310 12.3600000000 0.0066718897 0.0107999282 0.0160688832 0.0146125897 0.0068490000 0.0006630000 0.0036920000 0.0000010000 0.0000110000 0.0010900000 14093589 96830484 509673472 3.8842632771 3.9022243023 3.8986308575 311 12.4000000000 0.0066079488 0.0107864491 0.0160688832 0.0146121931 0.0061340000 0.0005160000 0.0032850000 0.0000080000 0.0000070000 0.0012650000 14096365 96830484 509673472 3.8830118179 3.9010250568 3.8958022594 312 12.4400000000 0.0065174177 0.0107727663 0.0160688832 0.0146050496 0.0052380000 0.0004960000 0.0029560000 0.0000000000 0.0000060000 0.0009310000 14099141 96830484 509673472 3.8817522526 3.8995838165 3.8927803040 313 12.4800000000 0.0065342542 0.0107592248 0.0160688832 0.0145969867 0.0060440000 0.0004960000 0.0029480000 0.0000060000 0.0000050000 0.0017430000 14101917 96830484 509673472 3.8804786205 3.8981928825 3.8902080059 314 12.5200000000 0.0065375515 0.0107457800 0.0160688832 0.0145955664 0.0052380000 0.0004950000 0.0029580000 0.0000010000 0.0000060000 0.0009270000 14104693 96830484 509673472 3.8794524670 3.8968980312 3.8880496025 315 12.5600000000 0.0066072429 0.0107326417 0.0160688832 0.0145984270 0.0080600000 0.0006690000 0.0036750000 0.0000150000 0.0000140000 0.0015560000 14107469 96830484 509673472 3.8780860901 3.8959250450 3.8853049278 316 12.6000000000 0.0065947319 0.0107195471 0.0160688832 0.0145961541 0.0069910000 0.0007010000 0.0036710000 0.0000020000 0.0000100000 0.0010650000 14110245 96830484 509673472 3.8768477440 3.8946466446 3.8826255798 317 12.6400000000 0.0065927082 0.0107065287 0.0160688832 0.0145859207 0.0066390000 0.0005230000 0.0035300000 0.0000060000 0.0000070000 0.0017120000 14113021 96830484 509673472 3.8756101131 3.8938174248 3.8799400330 318 12.6800000000 0.0066102734 0.0106936474 0.0160688832 0.0145716305 0.0054450000 0.0004800000 0.0033750000 0.0000010000 0.0000060000 0.0008780000 14115797 96830484 509673472 3.8743157387 3.8929221630 3.8773038387 319 12.7200000000 0.0068261414 0.0106815235 0.0160688832 0.0145888617 0.0089190000 0.0006390000 0.0046270000 0.0000160000 0.0000160000 0.0015230000 14118573 96830484 509673472 3.8720390797 3.8914713860 3.8721182346 320 12.7600000000 0.0068897796 0.0106696743 0.0160688832 0.0145769185 0.0065030000 0.0005530000 0.0039430000 0.0000010000 0.0000070000 0.0009420000 14121349 96830484 509673472 3.8711776733 3.8905706406 3.8698911667 321 12.8000000000 0.0070127784 0.0106582821 0.0160688832 0.0145654188 0.0076580000 0.0006400000 0.0036800000 0.0000110000 0.0000090000 0.0019120000 14124125 96830484 509673472 3.8698868752 3.8904154301 3.8673374653 322 12.8400000000 0.0073211156 0.0106479183 0.0160688832 0.0145512801 0.0066540000 0.0005190000 0.0043520000 0.0000010000 0.0000080000 0.0009270000 14126901 96830484 509673472 3.8685336113 3.8895967007 3.8645904064 323 12.8800000000 0.0072749970 0.0106374758 0.0160688832 0.0145376967 0.0059090000 0.0005530000 0.0026070000 0.0000120000 0.0000090000 0.0013180000 14129677 96830484 509673472 3.8675127029 3.8892724514 3.8628420830 324 12.9200000000 0.0074321022 0.0106275826 0.0160688832 0.0145248351 0.0081470000 0.0006390000 0.0041950000 0.0000020000 0.0000150000 0.0012340000 14132453 96830484 509673472 3.8661825657 3.8893144131 3.8603205681 325 12.9600000000 0.0074241948 0.0106177261 0.0160688832 0.0145054264 0.0082890000 0.0005740000 0.0048820000 0.0000080000 0.0000070000 0.0017470000 14135229 96830484 509673472 3.8650095463 3.8896703720 3.8583710194 326 13.0000000000 0.0076831440 0.0106087243 0.0160688832 0.0144856715 0.0064080000 0.0004990000 0.0042960000 0.0000010000 0.0000060000 0.0008840000 14138005 96830484 509673472 3.8635940552 3.8896739483 3.8557903767 327 13.0400000000 0.0082723713 0.0106015795 0.0160688832 0.0144656340 0.0084420000 0.0006430000 0.0046210000 0.0000160000 0.0000170000 0.0014940000 14140781 96830484 509673472 3.8623547554 3.8906655312 3.8530156612 328 13.0800000000 0.0080039054 0.0105936597 0.0160688832 0.0144460160 0.0057060000 0.0005190000 0.0034510000 0.0000010000 0.0000060000 0.0008670000 14143557 96830484 509673472 3.8609781265 3.8916864395 3.8511812687 329 13.1200000000 0.0081019746 0.0105860862 0.0160688832 0.0144284456 0.0083200000 0.0004800000 0.0056150000 0.0000040000 0.0000040000 0.0015920000 14146333 96830484 509673472 3.8597896099 3.8930552006 3.8490772247 330 13.1600000000 0.0090501718 0.0105814319 0.0160688832 0.0144103733 0.0073450000 0.0004630000 0.0055490000 0.0000000000 0.0000040000 0.0008210000 14149109 96830484 509673472 3.8585019112 3.8944342136 3.8461971283 331 13.2000000000 0.0086515825 0.0105756016 0.0160688832 0.0143956773 0.0078600000 0.0006350000 0.0037060000 0.0000160000 0.0000140000 0.0014920000 14151885 96830484 509673472 3.8573725224 3.8961062431 3.8448803425 332 13.2400000000 0.0087839132 0.0105702049 0.0160688832 0.0143787610 0.0077820000 0.0005170000 0.0055350000 0.0000000000 0.0000060000 0.0008540000 14154661 96830484 509673472 3.8561532497 3.8981883526 3.8434629440 333 13.2800000000 0.0082075233 0.0105631098 0.0160688832 0.0143674221 0.0065340000 0.0004790000 0.0038080000 0.0000050000 0.0000050000 0.0016010000 14157437 96830484 509673472 3.8548569679 3.9004433155 3.8425810337 334 13.3200000000 0.0085440418 0.0105570647 0.0160688832 0.0143913498 0.0081340000 0.0006430000 0.0046410000 0.0000020000 0.0000160000 0.0012180000 14160213 96830484 509673472 3.8526093960 3.9051730633 3.8399057388 335 13.3600000000 0.0080264853 0.0105495107 0.0160688832 0.0143805432 0.0059820000 0.0005190000 0.0034290000 0.0000060000 0.0000060000 0.0011380000 14162989 96830484 509673472 3.8516943455 3.9076581001 3.8396790028 336 13.4000000000 0.0087826764 0.0105442523 0.0160688832 0.0143686592 0.0058780000 0.0004820000 0.0038220000 0.0000000000 0.0000050000 0.0008240000 14165765 96830484 509673472 3.8507056236 3.9100883007 3.8382592201 337 13.4400000000 0.0086967824 0.0105387702 0.0160688832 0.0143586629 0.0091780000 0.0006280000 0.0041780000 0.0000160000 0.0000140000 0.0021200000 14168541 96830484 509673472 3.8498063087 3.9123258591 3.8379051685 338 13.4800000000 0.0087212417 0.0105333929 0.0160688832 0.0143609535 0.0056400000 0.0005560000 0.0030510000 0.0000010000 0.0000070000 0.0009000000 14171317 96830484 509673472 3.8489830494 3.9138343334 3.8375234604 339 13.5200000000 0.0088068843 0.0105282999 0.0160688832 0.0143724365 0.0071470000 0.0006440000 0.0036990000 0.0000120000 0.0000090000 0.0013000000 14174093 96830484 509673472 3.8479313850 3.9164409637 3.8370103836 340 13.5600000000 0.0090694539 0.0105240092 0.0160688832 0.0143747325 0.0066560000 0.0005200000 0.0043760000 0.0000010000 0.0000060000 0.0008500000 14176869 96830484 509673472 3.8471455574 3.9185214043 3.8368730545 341 13.6000000000 0.0090940548 0.0105198158 0.0160688832 0.0143711170 0.0072160000 0.0004950000 0.0043170000 0.0000070000 0.0000050000 0.0016180000 14179645 96830484 509673472 3.8463137150 3.9211657047 3.8368513584 342 13.6400000000 0.0093771052 0.0105164745 0.0160688832 0.0143654348 0.0085690000 0.0006450000 0.0051420000 0.0000020000 0.0000150000 0.0012140000 14182421 96830484 509673472 3.8450891972 3.9240946770 3.8360345364 343 13.6800000000 0.0094284099 0.0105133023 0.0160688832 0.0143745241 0.0064830000 0.0005570000 0.0035610000 0.0000080000 0.0000070000 0.0012040000 14185197 96830484 509673472 3.8442206383 3.9265480042 3.8358447552 344 13.7200000000 0.0092823487 0.0105097240 0.0160688832 0.0143882358 0.0078190000 0.0006420000 0.0046390000 0.0000010000 0.0000100000 0.0010090000 14187973 96830484 509673472 3.8434720039 3.9290032387 3.8359010220 345 13.7600000000 0.0094372137 0.0105066152 0.0160688832 0.0145382487 0.0064840000 0.0005180000 0.0034300000 0.0000060000 0.0000060000 0.0016080000 14190749 96830484 509673472 3.8418691158 3.9344575405 3.8357462883 346 13.8000000000 0.0099329585 0.0105049573 0.0160688832 0.0145470722 0.0068470000 0.0006400000 0.0036620000 0.0000020000 0.0000100000 0.0010070000 14193525 96830484 509673472 3.8412344456 3.9367129803 3.8351716995 347 13.8400000000 0.0101650674 0.0105039778 0.0160688832 0.0145456689 0.0090850000 0.0006370000 0.0046530000 0.0000150000 0.0000140000 0.0015150000 14196301 96830484 509673472 3.8403391838 3.9393703938 3.8347821236 348 13.8800000000 0.0098919207 0.0105022190 0.0160688832 0.0145324745 0.0059350000 0.0005470000 0.0034540000 0.0000010000 0.0000080000 0.0009100000 14199077 96830484 509673472 3.8395118713 3.9422919750 3.8349521160 349 13.9200000000 0.0094526578 0.0104992116 0.0160688832 0.0145129250 0.0083560000 0.0004820000 0.0056260000 0.0000050000 0.0000040000 0.0015740000 14201853 96830484 509673472 3.8386790752 3.9460825920 3.8352558613 350 13.9600000000 0.0101168426 0.0104981191 0.0160688832 0.0144963990 0.0084390000 0.0005560000 0.0058050000 0.0000010000 0.0000080000 0.0009090000 14204629 96830484 509673472 3.8378934860 3.9480204582 3.8346366882 351 14.0000000000 0.0100209760 0.0104967598 0.0160688832 0.0144941070 0.0094320000 0.0006760000 0.0059740000 0.0000110000 0.0000090000 0.0013110000 14207405 96830484 509673472 3.8372046947 3.9516324997 3.8347604275 352 14.0400000000 0.0099298358 0.0104951492 0.0160688832 0.0144922987 0.0064420000 0.0005200000 0.0043020000 0.0000010000 0.0000060000 0.0008410000 14210181 96830484 509673472 3.8364589214 3.9544422626 3.8350799084 353 14.0800000000 0.0098506147 0.0104933233 0.0160688832 0.0145021281 0.0068450000 0.0004710000 0.0042150000 0.0000030000 0.0000030000 0.0015610000 14212957 96830484 509673472 3.8357977867 3.9581394196 3.8354582787 354 14.1200000000 0.0103660692 0.0104929638 0.0160688832 0.0145255203 0.0096600000 0.0006420000 0.0060470000 0.0000020000 0.0000150000 0.0012080000 14215733 96830484 509673472 3.8353126049 3.9608418941 3.8354375362 355 14.1600000000 0.0101499101 0.0104919975 0.0160688832 0.0145486481 0.0065260000 0.0005270000 0.0038880000 0.0000060000 0.0000060000 0.0011610000 14218509 96830484 509673472 3.8347864151 3.9638390541 3.8360824585 356 14.2000000000 0.0099051632 0.0104903491 0.0160688832 0.0145584108 0.0076270000 0.0004880000 0.0056210000 0.0000000000 0.0000050000 0.0008150000 14221285 96830484 509673472 3.8342382908 3.9673082829 3.8365263939 357 14.2400000000 0.0099639082 0.0104888745 0.0160688832 0.0145605572 0.0059260000 0.0004660000 0.0033270000 0.0000030000 0.0000030000 0.0015760000 14224061 96830484 509673472 3.8337790966 3.9700660706 3.8371372223 358 14.2800000000 0.0099920584 0.0104874867 0.0160688832 0.0145651766 0.0084380000 0.0006450000 0.0041880000 0.0000020000 0.0000160000 0.0012160000 14226837 96830484 509673472 3.8333761692 3.9724264145 3.8378911018 359 14.3200000000 0.0094641531 0.0104846362 0.0160688832 0.0145708509 0.0092590000 0.0006560000 0.0046170000 0.0000160000 0.0000150000 0.0015320000 14229613 96830484 509673472 3.8330492973 3.9756906033 3.8390817642 360 14.3600000000 0.0100289518 0.0104833704 0.0160688832 0.0145687416 0.0075570000 0.0006340000 0.0032490000 0.0000020000 0.0000150000 0.0012500000 14232389 96830484 509673472 3.8328757286 3.9780638218 3.8392302990 361 14.4000000000 0.0100525962 0.0104821771 0.0160688832 0.0145646684 0.0065930000 0.0005550000 0.0030550000 0.0000080000 0.0000070000 0.0017560000 14235165 96830484 509673472 3.8327310085 3.9811403751 3.8400990963 362 14.4400000000 0.0096191941 0.0104797932 0.0160688832 0.0145693289 0.0078440000 0.0005020000 0.0056590000 0.0000000000 0.0000050000 0.0008500000 14237941 96830484 509673472 3.8326828480 3.9837949276 3.8413844109 363 14.4800000000 0.0096798865 0.0104775896 0.0160688832 0.0145710115 0.0060450000 0.0004750000 0.0037860000 0.0000040000 0.0000040000 0.0011490000 14240717 96830484 509673472 3.8327178955 3.9856462479 3.8422150612 364 14.5200000000 0.0100698173 0.0104764693 0.0160688832 0.0145726569 0.0056910000 0.0004680000 0.0037760000 0.0000000000 0.0000040000 0.0008300000 14243493 96830484 509673472 3.8326396942 3.9879300594 3.8426461220 365 14.5600000000 0.0098145427 0.0104746558 0.0160688832 0.0145782618 0.0069330000 0.0004690000 0.0042000000 0.0000050000 0.0000040000 0.0016190000 14246269 96830484 509673472 3.8327162266 3.9896626472 3.8438556194 366 14.6000000000 0.0093347281 0.0104715413 0.0160688832 0.0146701394 0.0057110000 0.0004680000 0.0037610000 0.0000010000 0.0000050000 0.0008440000 14249045 96830484 509673472 3.8334360123 3.9960052967 3.8463597298 367 14.6400000000 0.0088197971 0.0104670406 0.0160688832 0.0146854790 0.0059930000 0.0004680000 0.0037320000 0.0000050000 0.0000040000 0.0011520000 14251821 96830484 509673472 3.8338692188 3.9990882874 3.8478066921 368 14.6800000000 0.0084700091 0.0104616139 0.0160688832 0.0146966682 0.0057120000 0.0004660000 0.0037560000 0.0000000000 0.0000040000 0.0008500000 14254597 96830484 509673472 3.8347167969 4.0024847984 3.8498001099 369 14.7200000000 0.0080162827 0.0104549870 0.0160688832 0.0147183902 0.0086640000 0.0006590000 0.0031970000 0.0000150000 0.0000150000 0.0022770000 14257373 96830484 509673472 3.8362872601 4.0099387169 3.8531877995 370 14.7600000000 0.0073338528 0.0104465515 0.0160688832 0.0147253215 0.0085380000 0.0006490000 0.0041050000 0.0000020000 0.0000150000 0.0012970000 14260149 96830484 509673472 3.8377187252 4.0134663582 3.8562800884 371 14.8000000000 0.0061457166 0.0104349589 0.0160688832 0.0147291807 0.0075130000 0.0005560000 0.0043890000 0.0000090000 0.0000070000 0.0012940000 14262925 96830484 509673472 3.8389234543 4.0172128677 3.8597002029 372 14.8400000000 0.0054147774 0.0104214638 0.0160688832 0.0147296187 0.0051750000 0.0005010000 0.0029340000 0.0000010000 0.0000070000 0.0008960000 14265701 96830484 509673472 3.8399796486 4.0206995010 3.8631620407 373 14.8800000000 0.0052428935 0.0104075803 0.0160688832 0.0147266976 0.0069290000 0.0005390000 0.0037660000 0.0000050000 0.0000050000 0.0017260000 14268477 96830484 509673472 3.8414487839 4.0250697136 3.8667352200 374 14.9200000000 0.0054690032 0.0103943755 0.0160688832 0.0147193488 0.0048740000 0.0004680000 0.0028670000 0.0000000000 0.0000040000 0.0008870000 14271253 96830484 509673472 3.8428997993 4.0294251442 3.8698153496 375 14.9600000000 0.0062209601 0.0103832464 0.0160688832 0.0147144912 0.0056550000 0.0004690000 0.0033160000 0.0000040000 0.0000040000 0.0012170000 14274029 96830484 509673472 3.8444538116 4.0337471962 3.8733863831 376 15.0000000000 0.0067874962 0.0103736832 0.0160688832 0.0147238069 0.0053280000 0.0004650000 0.0033070000 0.0000000000 0.0000040000 0.0009040000 14276805 96830484 509673472 3.8460507393 4.0369129181 3.8764700890 377 15.0400000000 0.0072339713 0.0103653551 0.0160688832 0.0147449235 0.0066340000 0.0004680000 0.0037480000 0.0000040000 0.0000040000 0.0017600000 14279581 96830484 509673472 3.8479781151 4.0398287773 3.8795239925 378 15.0800000000 0.0078566112 0.0103587182 0.0160688832 0.0147565941 0.0077940000 0.0006480000 0.0032280000 0.0000020000 0.0000150000 0.0013780000 14282357 96830484 509673472 3.8498749733 4.0434474945 3.8820621967 379 15.1200000000 0.0082253451 0.0103530892 0.0160688832 0.0147533118 0.0087770000 0.0006430000 0.0041410000 0.0000160000 0.0000150000 0.0016980000 14285133 96830484 509673472 3.8520839214 4.0463714600 3.8847112656 380 15.1600000000 0.0087108808 0.0103487676 0.0160688832 0.0147585198 0.0056910000 0.0005260000 0.0029900000 0.0000010000 0.0000070000 0.0010710000 14287909 96830484 509673472 3.8542566299 4.0488576889 3.8872840405 381 15.2000000000 0.0091205621 0.0103455440 0.0160688832 0.0147637211 0.0060740000 0.0004860000 0.0029120000 0.0000050000 0.0000050000 0.0018150000 14290685 96830484 509673472 3.8563165665 4.0509815216 3.8893764019 382 15.2400000000 0.0091771455 0.0103424854 0.0160688832 0.0147600781 0.0059380000 0.0004740000 0.0037820000 0.0000000000 0.0000040000 0.0009500000 14293461 96830484 509673472 3.8585913181 4.0526614189 3.8913855553 383 15.2800000000 0.0092766583 0.0103397025 0.0160688832 0.0147565819 0.0081580000 0.0006420000 0.0032150000 0.0000150000 0.0000140000 0.0017520000 14296237 96830484 509673472 3.8606531620 4.0543832779 3.8933765888 384 15.3200000000 0.0092705665 0.0103369183 0.0160688832 0.0147748150 0.0059790000 0.0005540000 0.0030590000 0.0000010000 0.0000070000 0.0010840000 14299013 96830484 509673472 3.8627982140 4.0556411743 3.8953311443 385 15.3600000000 0.0093197552 0.0103342763 0.0160688832 0.0147785864 0.0077990000 0.0006490000 0.0032460000 0.0000170000 0.0000140000 0.0021680000 14301789 96830484 509673472 3.8653228283 4.0562481880 3.8974707127 386 15.4000000000 0.0094259912 0.0103319233 0.0160688832 0.0147784893 0.0058260000 0.0005190000 0.0032730000 0.0000010000 0.0000060000 0.0010040000 14304565 96830484 509673472 3.8675847054 4.0584707260 3.8993499279 387 15.4400000000 0.0096505722 0.0103301627 0.0160688832 0.0147792833 0.0055910000 0.0004820000 0.0029300000 0.0000060000 0.0000050000 0.0013080000 14307341 96830484 509673472 3.8703346252 4.0595049858 3.9019987583 388 15.4800000000 0.0095734941 0.0103282125 0.0160688832 0.0147887355 0.0078180000 0.0006610000 0.0030640000 0.0000020000 0.0000150000 0.0014480000 14310117 96830484 509673472 3.8732724190 4.0601420403 3.9044108391 389 15.5200000000 0.0095386999 0.0103261829 0.0160688832 0.0147932382 0.0071860000 0.0005640000 0.0030750000 0.0000100000 0.0000100000 0.0021890000 14312893 96830484 509673472 3.8754832745 4.0617046356 3.9061520100 390 15.5600000000 0.0097894538 0.0103248067 0.0160688832 0.0147861923 0.0051720000 0.0004960000 0.0027950000 0.0000010000 0.0000060000 0.0009980000 14315669 96830484 509673472 3.8786149025 4.0622339249 3.9092977047 391 15.6000000000 0.0098270196 0.0103235336 0.0160688832 0.0147846469 0.0058780000 0.0004800000 0.0033330000 0.0000050000 0.0000040000 0.0012940000 14318445 96830484 509673472 3.8809752464 4.0629720688 3.9114704132 392 15.6400000000 0.0098499842 0.0103223255 0.0160688832 0.0147849021 0.0079610000 0.0006510000 0.0032170000 0.0000020000 0.0000150000 0.0014520000 14321221 96830484 509673472 3.8841178417 4.0627579689 3.9141843319 393 15.6800000000 0.0098679140 0.0103211693 0.0160688832 0.0147842039 0.0070250000 0.0005680000 0.0030900000 0.0000080000 0.0000070000 0.0020310000 14323997 96830484 509673472 3.8866353035 4.0632061958 3.9162073135 394 15.7200000000 0.0099345595 0.0103201880 0.0160688832 0.0147883221 0.0049400000 0.0004980000 0.0023480000 0.0000010000 0.0000060000 0.0010510000 14326773 96830484 509673472 3.8894863129 4.0646915436 3.9180696011 395 15.7600000000 0.0101120593 0.0103196611 0.0160688832 0.0147933647 0.0078620000 0.0006440000 0.0032610000 0.0000170000 0.0000130000 0.0017520000 14329549 96830484 509673472 3.8922533989 4.0648684502 3.9199931622 396 15.8000000000 0.0101178791 0.0103191516 0.0160688832 0.0147877181 0.0060880000 0.0005530000 0.0030780000 0.0000010000 0.0000110000 0.0011110000 14332325 96830484 509673472 3.8953037262 4.0656909943 3.9217429161 397 15.8400000000 0.0101517905 0.0103187300 0.0160688832 0.0147788006 0.0062190000 0.0004980000 0.0028180000 0.0000060000 0.0000060000 0.0019940000 14335101 96830484 509673472 3.8986947536 4.0672178268 3.9240489006 398 15.8800000000 0.0102193877 0.0103184804 0.0160688832 0.0147733034 0.0078630000 0.0006440000 0.0032530000 0.0000020000 0.0000160000 0.0014710000 14337877 96830484 509673472 3.9000051022 4.0679702759 3.9239041805 399 15.9200000000 0.0101812007 0.0103181363 0.0160688832 0.0147689000 0.0062780000 0.0005200000 0.0032920000 0.0000060000 0.0000050000 0.0013740000 14340653 96830484 509673472 3.9035274982 4.0688495636 3.9259755611 400 15.9600000000 0.0102380086 0.0103179360 0.0160688832 0.0147643876 0.0051960000 0.0004830000 0.0027680000 0.0000010000 0.0000050000 0.0010320000 14343429 96830484 509673472 3.9051814079 4.0681276321 3.9266788960 401 16.0000000000 0.0102648828 0.0103178037 0.0160688832 0.0147528146 0.0061070000 0.0004790000 0.0029030000 0.0000050000 0.0000040000 0.0019410000 14346205 96830484 509673472 3.9071443081 4.0675063133 3.9280164242 402 16.0400000000 0.0103282509 0.0103178297 0.0160688832 0.0147446774 0.0080860000 0.0006450000 0.0032260000 0.0000010000 0.0000150000 0.0014940000 14348981 96830484 509673472 3.9092574120 4.0678024292 3.9291565418 403 16.0800000000 0.0104146004 0.0103180698 0.0160688832 0.0147446205 0.0075490000 0.0007350000 0.0030930000 0.0000170000 0.0000140000 0.0017420000 14351757 96830484 509673472 3.9108133316 4.0661525726 3.9299147129 404 16.1200000000 0.0104604447 0.0103184222 0.0160688832 0.0147515047 0.0063090000 0.0005380000 0.0036010000 0.0000010000 0.0000060000 0.0010700000 14354533 96830484 509673472 3.9126732349 4.0662436485 3.9305546284 405 16.1600000000 0.0105461236 0.0103189845 0.0160688832 0.0147536089 0.0060430000 0.0004800000 0.0027840000 0.0000060000 0.0000060000 0.0019890000 14357309 96830484 509673472 3.9151709080 4.0677299500 3.9314408302 406 16.2000000000 0.0106952433 0.0103199112 0.0160688832 0.0147504995 0.0075290000 0.0006440000 0.0030880000 0.0000020000 0.0000160000 0.0014990000 14360085 96830484 509673472 3.9175379276 4.0681242943 3.9328017235 407 16.2400000000 0.0107752103 0.0103210299 0.0160688832 0.0147570493 0.0061660000 0.0005200000 0.0028550000 0.0000080000 0.0000060000 0.0014350000 14362861 96830484 509673472 3.9205293655 4.0682768822 3.9341502190 408 16.2800000000 0.0109035186 0.0103224576 0.0160688832 0.0147614822 0.0055320000 0.0004950000 0.0029700000 0.0000010000 0.0000070000 0.0010740000 14365637 96830484 509673472 3.9232351780 4.0687770844 3.9351372719 409 16.3200000000 0.0108722076 0.0103238017 0.0160688832 0.0147535013 0.0088960000 0.0006390000 0.0037330000 0.0000160000 0.0000140000 0.0026350000 14368413 96830484 509673472 3.9264624119 4.0689334869 3.9368839264 410 16.3600000000 0.0109030204 0.0103252144 0.0160688832 0.0147561142 0.0057050000 0.0005180000 0.0030140000 0.0000010000 0.0000060000 0.0010830000 14371189 96830484 509673472 3.9296014309 4.0683612823 3.9386723042 411 16.3999999990 0.0109596821 0.0103267581 0.0160688832 0.0147662523 0.0055800000 0.0004830000 0.0028040000 0.0000060000 0.0000050000 0.0013760000 14373965 96830484 509673472 3.9327685833 4.0667796135 3.9404547215 412 16.4400000000 0.0109342644 0.0103282327 0.0160688832 0.0147698559 0.0052220000 0.0004700000 0.0029280000 0.0000010000 0.0000040000 0.0010380000 14376741 96830484 509673472 3.9346444607 4.0666456223 3.9415218830 413 16.4800000000 0.0110258730 0.0103299219 0.0160688832 0.0147752139 0.0092860000 0.0006400000 0.0032460000 0.0000160000 0.0000130000 0.0026360000 14379517 96830484 509673472 3.9376308918 4.0651836395 3.9435217381 414 16.5200000000 0.0110535687 0.0103316698 0.0160688832 0.0147690184 0.0079190000 0.0006470000 0.0032560000 0.0000010000 0.0000150000 0.0015400000 14382293 96830484 509673472 3.9396600723 4.0653390884 3.9444298744 415 16.5599999990 0.0111168744 0.0103335619 0.0160688832 0.0147596162 0.0059910000 0.0005260000 0.0028730000 0.0000070000 0.0000080000 0.0014760000 14385069 96830484 509673472 3.9417986870 4.0659790039 3.9452798367 416 16.6000000000 0.0110914344 0.0103353837 0.0160688832 0.0147474552 0.0066590000 0.0005540000 0.0035550000 0.0000010000 0.0000090000 0.0011640000 14387845 96830484 509673472 3.9431297779 4.0661563873 3.9458577633 417 16.6400000000 0.0111190323 0.0103372629 0.0160688832 0.0147390429 0.0077000000 0.0005540000 0.0035670000 0.0000080000 0.0000070000 0.0021830000 14390621 96830484 509673472 3.9455490112 4.0667548180 3.9469094276 418 16.6800000000 0.0111362869 0.0103391745 0.0160688832 0.0147297855 0.0053210000 0.0004980000 0.0028200000 0.0000000000 0.0000050000 0.0010670000 14393397 96830484 509673472 3.9461174011 4.0656828880 3.9471211433 419 16.7199999990 0.0111905783 0.0103412065 0.0160688832 0.0147236034 0.0082490000 0.0006450000 0.0035800000 0.0000160000 0.0000130000 0.0018090000 14396173 96830484 509673472 3.9487183094 4.0650677681 3.9481997490 420 16.7600000000 0.0112478919 0.0103433652 0.0160688832 0.0147214928 0.0060680000 0.0005210000 0.0033250000 0.0000010000 0.0000090000 0.0010980000 14398949 96830484 509673472 3.9504311085 4.0635561943 3.9496848583 421 16.8000000000 0.0112453615 0.0103455077 0.0160688832 0.0147213449 0.0075620000 0.0005560000 0.0031180000 0.0000110000 0.0000100000 0.0023420000 14401725 96830484 509673472 3.9526388645 4.0618553162 3.9513285160 422 16.8400000000 0.0112940995 0.0103477556 0.0160688832 0.0147159145 0.0066680000 0.0005550000 0.0029630000 0.0000010000 0.0000100000 0.0012900000 14404501 96830484 509673472 3.9542229176 4.0625057220 3.9520504475 423 16.8799999990 0.0114069199 0.0103502595 0.0160688832 0.0147120195 0.0077000000 0.0006430000 0.0035770000 0.0000150000 0.0000130000 0.0015910000 14407277 96830484 509673472 3.9563643932 4.0616021156 3.9531404972 424 16.9200000000 0.0114218537 0.0103527869 0.0160688832 0.0147030642 0.0063500000 0.0005190000 0.0033450000 0.0000010000 0.0000080000 0.0011780000 14410053 96830484 509673472 3.9591281414 4.0604047775 3.9543352127 425 16.9600000000 0.0114953602 0.0103554753 0.0160688832 0.0147091596 0.0065970000 0.0005010000 0.0028490000 0.0000060000 0.0000050000 0.0021050000 14412829 96830484 509673472 3.9615714550 4.0603742599 3.9564909935 426 17.0000000000 0.0115220407 0.0103582137 0.0160688832 0.0147044705 0.0054680000 0.0004820000 0.0029630000 0.0000010000 0.0000060000 0.0010770000 14415605 96830484 509673472 3.9639668465 4.0564508438 3.9580640793 427 17.0400000000 0.0114782201 0.0103608367 0.0160688832 0.0146999926 0.0085560000 0.0006380000 0.0032620000 0.0000150000 0.0000130000 0.0018270000 14418381 96830484 509673472 3.9670290947 4.0554242134 3.9589540958 428 17.0800000000 0.0115632275 0.0103636460 0.0160688832 0.0146944828 0.0061670000 0.0005650000 0.0029520000 0.0000010000 0.0000090000 0.0011890000 14421157 96830484 509673472 3.9698836803 4.0553421974 3.9603090286 429 17.1200000000 0.0115428297 0.0103663947 0.0160688832 0.0146884748 0.0082770000 0.0006580000 0.0032670000 0.0000160000 0.0000160000 0.0023750000 14423933 96830484 509673472 3.9722948074 4.0547218323 3.9614317417 430 17.1600000000 0.0116499215 0.0103693796 0.0160688832 0.0146800365 0.0058640000 0.0005270000 0.0030350000 0.0000000000 0.0000070000 0.0011230000 14426709 96830484 509673472 3.9747505188 4.0572566986 3.9619786739 431 17.2000000000 0.0116165662 0.0103722733 0.0160688832 0.0146739786 0.0075200000 0.0006430000 0.0033010000 0.0000150000 0.0000170000 0.0016140000 14429485 96830484 509673472 3.9772469997 4.0570249557 3.9623534679 432 17.2400000000 0.0115796011 0.0103750680 0.0160688832 0.0146747823 0.0058690000 0.0005190000 0.0028650000 0.0000000000 0.0000090000 0.0011960000 14432261 96830484 509673472 3.9798221588 4.0522093773 3.9636976719 433 17.2800000000 0.0116227521 0.0103779495 0.0160688832 0.0146870333 0.0088270000 0.0006470000 0.0032570000 0.0000160000 0.0000130000 0.0027320000 14435037 96830484 509673472 3.9810485840 4.0481829643 3.9655253887 434 17.3200000000 0.0116375089 0.0103808517 0.0160688832 0.0146912747 0.0068110000 0.0005580000 0.0035840000 0.0000010000 0.0000070000 0.0011970000 14437813 96830484 509673472 3.9837310314 4.0460000038 3.9671359062 435 17.3600000000 0.0117057431 0.0103838975 0.0160688832 0.0146958124 0.0057110000 0.0004970000 0.0028270000 0.0000050000 0.0000040000 0.0014010000 14440589 96830484 509673472 3.9860320091 4.0426421165 3.9681534767 436 17.4000000000 0.0117029231 0.0103869228 0.0160688832 0.0146945951 0.0051700000 0.0004700000 0.0027900000 0.0000010000 0.0000050000 0.0010800000 14443365 96830484 509673472 3.9872546196 4.0409107208 3.9692950249 437 17.4400000000 0.0116985058 0.0103899241 0.0160688832 0.0146901733 0.0100300000 0.0006560000 0.0035910000 0.0000150000 0.0000140000 0.0027570000 14446141 96830484 509673472 3.9878239632 4.0401830673 3.9696762562 438 17.4800000000 0.0117572621 0.0103930459 0.0160688832 0.0147052211 0.0064140000 0.0005680000 0.0031250000 0.0000010000 0.0000080000 0.0012120000 14448917 96830484 509673472 3.9879732132 4.0398654938 3.9709339142 439 17.5200000000 0.0117751285 0.0103961941 0.0160688832 0.0147141715 0.0057590000 0.0005040000 0.0028290000 0.0000050000 0.0000050000 0.0014160000 14451693 96830484 509673472 3.9875993729 4.0388255119 3.9716861248 440 17.5600000000 0.0118160564 0.0103994211 0.0160688832 0.0147177752 0.0052970000 0.0004760000 0.0029260000 0.0000000000 0.0000050000 0.0011170000 14454469 96830484 509673472 3.9860229492 4.0383782387 3.9720563889 441 17.6000000000 0.0118313730 0.0104026681 0.0160688832 0.0147301271 0.0061270000 0.0004690000 0.0027860000 0.0000040000 0.0000030000 0.0020950000 14457245 96830484 509673472 3.9846684933 4.0377264023 3.9731683731 442 17.6400000000 0.0118444180 0.0104059300 0.0160688832 0.0148207382 0.0051000000 0.0004680000 0.0027610000 0.0000000000 0.0000040000 0.0010970000 14460021 96830484 509673472 3.9752995968 4.0344986916 3.9733505249 443 17.6800000000 0.0118056899 0.0104090897 0.0160688832 0.0148296853 0.0054410000 0.0004690000 0.0027710000 0.0000050000 0.0000040000 0.0014190000 14462797 96830484 509673472 3.9712626934 4.0349493027 3.9731733799 444 17.7200000000 0.0118277343 0.0104122849 0.0160688832 0.0148350391 0.0052490000 0.0004690000 0.0029210000 0.0000000000 0.0000040000 0.0010720000 14465573 96830484 509673472 3.9688422680 4.0348157883 3.9738681316 445 17.7600000000 0.0118511226 0.0104155182 0.0160688832 0.0148412196 0.0062530000 0.0004700000 0.0029200000 0.0000040000 0.0000040000 0.0020750000 14468349 96830484 509673472 3.9670975208 4.0306901932 3.9746398926 446 17.8000000000 0.0116793877 0.0104183520 0.0160688832 0.0148499126 0.0052670000 0.0004700000 0.0029380000 0.0000000000 0.0000040000 0.0010760000 14471125 96830484 509673472 3.9654042721 4.0284919739 3.9754762650 447 17.8400000000 0.0118132960 0.0104214727 0.0160688832 0.0148491625 0.0054200000 0.0004680000 0.0027890000 0.0000050000 0.0000040000 0.0013750000 14473901 96830484 509673472 3.9664778709 4.0242323875 3.9771423340 448 17.8800000000 0.0117231980 0.0104243783 0.0160688832 0.0148407831 0.0083630000 0.0006580000 0.0031090000 0.0000020000 0.0000160000 0.0015510000 14476677 96830484 509673472 3.9673547745 4.0213232040 3.9783301353 449 17.9200000000 0.0117513435 0.0104273337 0.0160688832 0.0148316672 0.0091000000 0.0006610000 0.0030880000 0.0000170000 0.0000140000 0.0027790000 14479453 96830484 509673472 3.9654629230 4.0184721947 3.9805159569 450 17.9600000000 0.0117174936 0.0104302007 0.0160688832 0.0148192522 0.0059560000 0.0005290000 0.0030210000 0.0000010000 0.0000080000 0.0011770000 14482229 96830484 509673472 3.9663176537 4.0151710510 3.9821259975 451 18.0000000000 0.0117774131 0.0104331879 0.0160688832 0.0148116985 0.0070390000 0.0005560000 0.0029710000 0.0000100000 0.0000090000 0.0016510000 14485005 96830484 509673472 3.9665694237 4.0145092010 3.9851617813 452 18.0400000000 0.0115952343 0.0104357588 0.0160688832 0.0148063214 0.0055660000 0.0004980000 0.0026910000 0.0000000000 0.0000070000 0.0011470000 14487781 96830484 509673472 3.9669229984 4.0120310783 3.9882254601 453 18.0800000000 0.0115811843 0.0104382873 0.0160688832 0.0147962325 0.0069600000 0.0004870000 0.0032520000 0.0000050000 0.0000040000 0.0021700000 14490557 96830484 509673472 3.9679055214 4.0105376244 3.9914474487 454 18.1200000000 0.0115791140 0.0104408002 0.0160688832 0.0147842362 0.0068140000 0.0004870000 0.0041600000 0.0000010000 0.0000050000 0.0011290000 14493333 96830484 509673472 3.9683618546 4.0099544525 3.9954326153 455 18.1600000000 0.0116321975 0.0104434186 0.0160688832 0.0147694428 0.0057990000 0.0004920000 0.0028050000 0.0000050000 0.0000050000 0.0014490000 14496109 96830484 509673472 3.9699425697 4.0083913803 3.9993295670 456 18.2000000000 0.0115416041 0.0104458269 0.0160688832 0.0147606306 0.0086190000 0.0006500000 0.0032910000 0.0000020000 0.0000150000 0.0015860000 14498885 96830484 509673472 3.9710745811 4.0071768761 4.0043125153 457 18.2400000000 0.0115083400 0.0104481519 0.0160688832 0.0147536114 0.0084760000 0.0006290000 0.0032900000 0.0000150000 0.0000140000 0.0024510000 14501661 96830484 509673472 3.9711613655 4.0101265907 4.0090065002 458 18.2800000000 0.0114498781 0.0104503391 0.0160688832 0.0147427234 0.0057820000 0.0005200000 0.0028710000 0.0000010000 0.0000070000 0.0011220000 14504437 96830484 509673472 3.9722800255 4.0108070374 4.0152287483 459 18.3200000000 0.0114530921 0.0104525237 0.0160688832 0.0147280038 0.0055950000 0.0004890000 0.0028160000 0.0000050000 0.0000050000 0.0013780000 14507213 96830484 509673472 3.9746365547 4.0109729767 4.0213241577 460 18.3600000000 0.0113364188 0.0104544452 0.0160688832 0.0147137499 0.0052810000 0.0004780000 0.0028210000 0.0000010000 0.0000040000 0.0010680000 14509989 96830484 509673472 3.9760744572 4.0145459175 4.0278363228 461 18.4000000000 0.0114404541 0.0104565841 0.0160688832 0.0146990395 0.0096800000 0.0006510000 0.0031440000 0.0000160000 0.0000130000 0.0027290000 14512765 96830484 509673472 3.9768588543 4.0144410133 4.0350799561 462 18.4400000000 0.0113307731 0.0104584763 0.0160688832 0.0146836886 0.0065550000 0.0005590000 0.0024850000 0.0000020000 0.0000100000 0.0014760000 14515541 96830484 509673472 3.9802188873 4.0148959160 4.0427818298 463 18.4800000000 0.0113465916 0.0104603944 0.0160688832 0.0146710001 0.0067200000 0.0006270000 0.0029820000 0.0000080000 0.0000070000 0.0014890000 14518317 96830484 509673472 3.9808168411 4.0171909332 4.0508451462 464 18.5200000000 0.0113424379 0.0104622954 0.0160688832 0.0146580345 0.0056990000 0.0005480000 0.0028440000 0.0000010000 0.0000060000 0.0011100000 14521093 96830484 509673472 3.9814963341 4.0192251205 4.0599632263 465 18.5600000000 0.0112632550 0.0104640179 0.0160688832 0.0146466443 0.0096620000 0.0006610000 0.0031070000 0.0000150000 0.0000150000 0.0027050000 14523869 96830484 509673472 3.9854962826 4.0256810188 4.0794978142 466 18.6000000000 0.0112392455 0.0104656815 0.0160688832 0.0146320254 0.0061830000 0.0005620000 0.0029000000 0.0000010000 0.0000090000 0.0011730000 14526645 96830484 509673472 3.9882071018 4.0295782089 4.0898714066 467 18.6400000000 0.0113478629 0.0104675705 0.0160688832 0.0146171717 0.0065890000 0.0005610000 0.0029590000 0.0000080000 0.0000070000 0.0014680000 14529421 96830484 509673472 3.9909582138 4.0306639671 4.1008629799 468 18.6800000000 0.0113144815 0.0104693802 0.0160688832 0.0146040224 0.0057030000 0.0004980000 0.0028610000 0.0000000000 0.0000070000 0.0011160000 14532197 96830484 509673472 3.9929709435 4.0354390144 4.1119570732 469 18.7200000000 0.0112825073 0.0104711139 0.0160688832 0.0145931198 0.0064870000 0.0004870000 0.0028180000 0.0000060000 0.0000050000 0.0020910000 14534973 96830484 509673472 3.9944548607 4.0387063026 4.1235170364 470 18.7600000000 0.0113808922 0.0104730496 0.0160688832 0.0145866431 0.0054720000 0.0004880000 0.0028140000 0.0000010000 0.0000050000 0.0010910000 14537749 96830484 509673472 3.9964985847 4.0439548492 4.1353182793 471 18.8000000000 0.0113391960 0.0104748886 0.0160688832 0.0145798245 0.0087730000 0.0006470000 0.0031140000 0.0000180000 0.0000150000 0.0018000000 14540525 96830484 509673472 3.9978828430 4.0497212410 4.1477289200 472 18.8400000000 0.0112484377 0.0104765274 0.0160688832 0.0145652150 0.0071890000 0.0006540000 0.0030940000 0.0000020000 0.0000150000 0.0012870000 14543301 96830484 509673472 4.0011124611 4.0558638573 4.1595721245 473 18.8800000000 0.0113297086 0.0104783312 0.0160688832 0.0145499843 0.0069950000 0.0005250000 0.0030400000 0.0000060000 0.0000060000 0.0021320000 14546077 96830484 509673472 4.0037755966 4.0634732246 4.1714792252 474 18.9200000000 0.0113835027 0.0104802408 0.0160688832 0.0145385164 0.0051350000 0.0004850000 0.0024960000 0.0000010000 0.0000060000 0.0010730000 14548853 96830484 509673472 4.0070829391 4.0697937012 4.1827063560 475 18.9600000000 0.0112984544 0.0104819634 0.0160688832 0.0145304527 0.0087780000 0.0006510000 0.0031160000 0.0000160000 0.0000130000 0.0017850000 14551629 96830484 509673472 4.0107421875 4.0745692253 4.1953916550 476 19.0000000000 0.0114003755 0.0104838928 0.0160688832 0.0145208001 0.0062880000 0.0005720000 0.0024850000 0.0000020000 0.0000100000 0.0013050000 14554405 96830484 509673472 4.0141196251 4.0774497986 4.2073917389 477 19.0400000000 0.0115288366 0.0104860835 0.0160688832 0.0145079509 0.0084210000 0.0005620000 0.0035960000 0.0000110000 0.0000110000 0.0024290000 14557181 96830484 509673472 4.0156135559 4.0842990875 4.2192230225 478 19.0800000000 0.0114092231 0.0104880147 0.0160688832 0.0144951586 0.0055180000 0.0004990000 0.0028460000 0.0000010000 0.0000060000 0.0010900000 14559957 96830484 509673472 4.0193371773 4.0915656090 4.2303681374 479 19.1200000000 0.0116302660 0.0104903994 0.0160688832 0.0144849673 0.0087840000 0.0006440000 0.0030820000 0.0000150000 0.0000140000 0.0018030000 14562733 96830484 509673472 4.0228228569 4.0950865746 4.2422719002 480 19.1600000000 0.0116060404 0.0104927237 0.0160688832 0.0144760471 0.0061590000 0.0005600000 0.0028940000 0.0000010000 0.0000080000 0.0011830000 14565509 96830484 509673472 4.0266003609 4.0998845100 4.2534127235 481 19.2000000000 0.0115147568 0.0104948485 0.0160688832 0.0144624922 0.0079510000 0.0005600000 0.0029680000 0.0000100000 0.0000090000 0.0023860000 14568285 96830484 509673472 4.0277781487 4.1099061966 4.2636861801 482 19.2400000000 0.0115463026 0.0104970299 0.0160688832 0.0144606381 0.0063760000 0.0005580000 0.0029740000 0.0000010000 0.0000110000 0.0012120000 14571061 96830484 509673472 4.0316510201 4.1142878532 4.2752771378 483 19.2800000000 0.0115707386 0.0104992529 0.0160688832 0.0144622665 0.0056900000 0.0005010000 0.0025570000 0.0000060000 0.0000050000 0.0014060000 14573837 96830484 509673472 4.0341825485 4.1149787903 4.2867884636 484 19.3200000000 0.0115808994 0.0105014877 0.0160688832 0.0144602690 0.0080270000 0.0006450000 0.0031080000 0.0000020000 0.0000160000 0.0015340000 14576613 96830484 509673472 4.0377535820 4.1162924767 4.2979598045 485 19.3600000000 0.0114919646 0.0105035299 0.0160688832 0.0144479240 0.0084470000 0.0005550000 0.0035940000 0.0000100000 0.0000090000 0.0023690000 14579389 96830484 509673472 4.0397820473 4.1198058128 4.3091254234 486 19.4000000000 0.0115431268 0.0105056690 0.0160688832 0.0144330229 0.0061430000 0.0004980000 0.0034610000 0.0000000000 0.0000070000 0.0010810000 14582165 96830484 509673472 4.0427660942 4.1267371178 4.3192543983 487 19.4400000000 0.0115076611 0.0105077265 0.0160688832 0.0144183628 0.0070140000 0.0005580000 0.0029550000 0.0000100000 0.0000090000 0.0015450000 14584941 96830484 509673472 4.0431280136 4.1307606697 4.3309974670 488 19.4800000000 0.0115314592 0.0105098243 0.0160688832 0.0144038784 0.0078790000 0.0006800000 0.0029290000 0.0000020000 0.0000150000 0.0014800000 14587717 96830484 509673472 4.0452370644 4.1335053444 4.3420372009 489 19.5200000000 0.0115958899 0.0105120453 0.0160688832 0.0143897305 0.0068370000 0.0005240000 0.0028990000 0.0000080000 0.0000070000 0.0020810000 14590493 96830484 509673472 4.0459017754 4.1412529945 4.3526468277 490 19.5600000000 0.0116929850 0.0105144554 0.0160688832 0.0143756746 0.0054730000 0.0004870000 0.0029690000 0.0000010000 0.0000060000 0.0010660000 14593269 96830484 509673472 4.0462522507 4.1467070580 4.3634099960 491 19.6000000000 0.0115137938 0.0105164907 0.0160688832 0.0143613438 0.0094470000 0.0007300000 0.0033230000 0.0000160000 0.0000150000 0.0017260000 14596045 96830484 509673472 4.0491433144 4.1527075768 4.3736925125 492 19.6400000000 0.0117610479 0.0105190203 0.0160688832 0.0143467725 0.0079740000 0.0007120000 0.0029350000 0.0000020000 0.0000160000 0.0014790000 14598821 96830484 509673472 4.0492963791 4.1573166847 4.3839898109 493 19.6800000000 0.0116545418 0.0105213236 0.0160688832 0.0143325600 0.0070280000 0.0005310000 0.0030570000 0.0000070000 0.0000080000 0.0020580000 14601597 96830484 509673472 4.0498790741 4.1597948074 4.3948855400 494 19.7200000000 0.0115788523 0.0105234643 0.0160688832 0.0143180334 0.0054530000 0.0004840000 0.0029530000 0.0000000000 0.0000040000 0.0010340000 14604373 96830484 509673472 4.0500493050 4.1608352661 4.4061126709 495 19.7600000000 0.0116472794 0.0105257346 0.0160688832 0.0143047009 0.0089560000 0.0006610000 0.0031280000 0.0000150000 0.0000140000 0.0017620000 14607149 96830484 509673472 4.0507397652 4.1657304764 4.4172601700 496 19.8000000000 0.0116528235 0.0105280070 0.0160688832 0.0142920461 0.0086860000 0.0006700000 0.0030980000 0.0000020000 0.0000160000 0.0015040000 14609925 96830484 509673472 4.0507893562 4.1724662781 4.4277644157 497 19.8400000000 0.0116179092 0.0105302000 0.0160688832 0.0142799604 0.0070750000 0.0005530000 0.0030480000 0.0000080000 0.0000070000 0.0020960000 14612701 96830484 509673472 4.0506720543 4.1786131859 4.4387602806 498 19.8800000000 0.0116989585 0.0105325469 0.0160688832 0.0142710725 0.0059000000 0.0005610000 0.0024910000 0.0000010000 0.0000080000 0.0011410000 14615477 96830484 509673472 4.0493526459 4.1855554581 4.4495196342 499 19.9200000000 0.0117221074 0.0105349308 0.0160688832 0.0142629874 0.0072300000 0.0006370000 0.0026260000 0.0000160000 0.0000140000 0.0016760000 14618253 96830484 509673472 4.0484251976 4.1918420792 4.4611830711 500 19.9600000000 0.0116386926 0.0105371383 0.0160688832 0.0142530781 0.0061520000 0.0005200000 0.0028940000 0.0000010000 0.0000070000 0.0011360000 14621029 96830484 509673472 4.0473585129 4.1936359406 4.4723401070 501 20.0000000000 0.0115379374 0.0105391359 0.0160688832 0.0142441416 0.0091210000 0.0006460000 0.0032920000 0.0000150000 0.0000140000 0.0025830000 14623805 96830484 509673472 4.0458598137 4.1964936256 4.4831709862 502 20.0400000000 0.0116051324 0.0105412594 0.0160688832 0.0142347563 0.0082870000 0.0006640000 0.0026740000 0.0000020000 0.0000160000 0.0014800000 14626581 96830484 509673472 4.0444321632 4.2013034821 4.4942393303 503 20.0800000000 0.0116911642 0.0105435455 0.0160688832 0.0142228553 0.0089580000 0.0006480000 0.0031220000 0.0000160000 0.0000160000 0.0017410000 14629357 96830484 509673472 4.0422220230 4.2078986168 4.5050420761 504 20.1200000000 0.0115910200 0.0105456238 0.0160688832 0.0142087512 0.0087400000 0.0006470000 0.0031670000 0.0000020000 0.0000150000 0.0014690000 14632133 96830484 509673472 4.0395736694 4.2128391266 4.5159239769 505 20.1600000000 0.0116974171 0.0105479046 0.0160688832 0.0141949037 0.0092210000 0.0006600000 0.0031450000 0.0000150000 0.0000150000 0.0025720000 14634909 96830484 509673472 4.0380287170 4.2193365097 4.5265488625 506 20.2000000000 0.0116172694 0.0105500180 0.0160688832 0.0141841185 0.0061030000 0.0005320000 0.0030810000 0.0000010000 0.0000080000 0.0010730000 14637685 96830484 509673472 4.0360445976 4.2284073830 4.5365180969 507 20.2400000000 0.0115533788 0.0105519970 0.0160688832 0.0141807842 0.0056580000 0.0004890000 0.0026830000 0.0000050000 0.0000050000 0.0013090000 14640461 96830484 509673472 4.0331788063 4.2334356308 4.5469989777 508 20.2800000000 0.0115636140 0.0105539883 0.0160688832 0.0141793610 0.0053360000 0.0004790000 0.0028270000 0.0000000000 0.0000040000 0.0010160000 14643237 96830484 509673472 4.0309581757 4.2380795479 4.5571150780 509 20.3200000000 0.0115765817 0.0105559974 0.0160688832 0.0141907995 0.0064090000 0.0004800000 0.0029580000 0.0000050000 0.0000040000 0.0019440000 14646013 96830484 509673472 4.0283327103 4.2447218895 4.5666651726 510 20.3600000000 0.0116529232 0.0105581482 0.0160688832 0.0141921358 0.0051750000 0.0004770000 0.0026540000 0.0000000000 0.0000050000 0.0010160000 14648789 96830484 509673472 4.0244030952 4.2493896484 4.5761156082 511 20.4000000000 0.0116349394 0.0105602554 0.0160688832 0.0141904635 0.0056150000 0.0004800000 0.0028170000 0.0000040000 0.0000040000 0.0012850000 14651565 96830484 509673472 4.0223493576 4.2542004585 4.5848402977 512 20.4400000000 0.0116468957 0.0105623778 0.0160688832 0.0141959759 0.0054930000 0.0004770000 0.0029580000 0.0000010000 0.0000050000 0.0010250000 14654341 96830484 509673472 4.0220012665 4.2607669830 4.5928330421 513 20.4800000000 0.0116472663 0.0105644926 0.0160688832 0.0141967699 0.0064570000 0.0004790000 0.0029610000 0.0000050000 0.0000040000 0.0019470000 14706269 96830484 509673472 4.0203528404 4.2649984360 4.6011090279 514 20.5200000000 0.0116774449 0.0105666578 0.0160688832 0.0142001921 0.0090270000 0.0006660000 0.0033350000 0.0000020000 0.0000160000 0.0014700000 14811445 96830484 509673472 4.0189800262 4.2672052383 4.6095976830 515 20.5600000000 0.0115983626 0.0105686611 0.0160688832 0.0142062296 0.0086280000 0.0006390000 0.0032780000 0.0000160000 0.0000140000 0.0017220000 14814221 96830484 509673472 4.0186138153 4.2690033913 4.6166753769 516 20.6000000000 0.0116216475 0.0105707018 0.0160688832 0.0142212112 0.0059750000 0.0005330000 0.0029190000 0.0000010000 0.0000070000 0.0010880000 14816997 96830484 509673472 4.0186500549 4.2746257782 4.6238765717 517 20.6400000000 0.0116889765 0.0105728648 0.0160688832 0.0142353519 0.0073990000 0.0005600000 0.0029550000 0.0000080000 0.0000080000 0.0020920000 14819773 96830484 509673472 4.0188641548 4.2782969475 4.6304440498 518 20.6800000000 0.0116844317 0.0105750107 0.0160688832 0.0142537861 0.0053430000 0.0004860000 0.0028110000 0.0000010000 0.0000050000 0.0010180000 14822549 96830484 509673472 4.0189709663 4.2813692093 4.6369194984 519 20.7200000000 0.0117047746 0.0105771875 0.0160688832 0.0142728365 0.0080060000 0.0006600000 0.0031160000 0.0000160000 0.0000150000 0.0017120000 14825325 96830484 509673472 4.0208992958 4.2851328850 4.6426196098 520 20.7600000000 0.0116740447 0.0105792969 0.0160688832 0.0143010875 0.0054460000 0.0005240000 0.0024290000 0.0000010000 0.0000070000 0.0010570000 14828101 96830484 509673472 4.0221114159 4.2880692482 4.6481471062 521 20.8000000000 0.0116284136 0.0105813105 0.0160688832 0.0143260170 0.0066210000 0.0004920000 0.0029700000 0.0000050000 0.0000050000 0.0019420000 14830877 96830484 509673472 4.0240092278 4.2886948586 4.6534838676 522 20.8400000000 0.0116899749 0.0105834344 0.0160688832 0.0143537925 0.0055220000 0.0004870000 0.0028100000 0.0000000000 0.0000050000 0.0010240000 14833653 96830484 509673472 4.0253939629 4.2889828682 4.6586828232 523 20.8800000000 0.0116544859 0.0105854823 0.0160688832 0.0143831227 0.0091350000 0.0006640000 0.0031440000 0.0000170000 0.0000140000 0.0017040000 14836429 96830484 509673472 4.0274944305 4.2887330055 4.6632099152 524 20.9200000000 0.0116600385 0.0105875330 0.0160688832 0.0144173758 0.0082440000 0.0006370000 0.0031070000 0.0000020000 0.0000170000 0.0014460000 14839205 96830484 509673472 4.0299410820 4.2922148705 4.6673717499 525 20.9600000000 0.0117181223 0.0105896865 0.0160688832 0.0144345579 0.0069820000 0.0005810000 0.0024830000 0.0000100000 0.0000090000 0.0020970000 14841981 96830484 509673472 4.0326161385 4.2938542366 4.6712775230 526 21.0000000000 0.0117377015 0.0105918690 0.0160688832 0.0144460282 0.0055940000 0.0005010000 0.0028500000 0.0000010000 0.0000050000 0.0010240000 14844757 96830484 509673472 4.0355672836 4.2933001518 4.6749935150 527 21.0400000000 0.0117833065 0.0105941298 0.0160688832 0.0144629804 0.0057860000 0.0004760000 0.0029440000 0.0000050000 0.0000040000 0.0012770000 14847533 96830484 509673472 4.0383114815 4.2948617935 4.6784920692 528 21.0800000000 0.0118596824 0.0105965267 0.0160688832 0.0144733357 0.0059480000 0.0004870000 0.0033970000 0.0000010000 0.0000050000 0.0010040000 14850309 96830484 509673472 4.0417990685 4.2965245247 4.6814894676 529 21.1200000000 0.0118673090 0.0105989289 0.0160688832 0.0144756123 0.0099570000 0.0006460000 0.0031090000 0.0000180000 0.0000140000 0.0025470000 14853085 96830484 509673472 4.0443773270 4.2965822220 4.6844568253 530 21.1600000000 0.0119081680 0.0106013992 0.0160688832 0.0144809808 0.0058950000 0.0005620000 0.0024250000 0.0000000000 0.0000080000 0.0011100000 14855861 96830484 509673472 4.0476918221 4.2977795601 4.6871824265 531 21.2000000000 0.0119613465 0.0106039603 0.0160688832 0.0144912219 0.0076510000 0.0006460000 0.0030990000 0.0000110000 0.0000090000 0.0014610000 14858637 96830484 509673472 4.0513830185 4.2980284691 4.6897764206 532 21.2400000000 0.0119264359 0.0106064461 0.0160688832 0.0145067325 0.0099120000 0.0006430000 0.0059570000 0.0000010000 0.0000100000 0.0012020000 14861413 96830484 509673472 4.0550317764 4.2973513603 4.6920614243 533 21.2800000000 0.0119367829 0.0106089421 0.0160688832 0.0145252642 0.0069970000 0.0005060000 0.0032920000 0.0000060000 0.0000050000 0.0019510000 14864189 96830484 509673472 4.0591440201 4.2976603508 4.6942758560 534 21.3200000000 0.0119583113 0.0106114690 0.0160688832 0.0145422443 0.0057810000 0.0004750000 0.0033930000 0.0000010000 0.0000040000 0.0009810000 14866965 96830484 509673472 4.0631918907 4.2976646423 4.6964936256 535 21.3600000000 0.0119610103 0.0106139915 0.0160688832 0.0145596362 0.0054600000 0.0004660000 0.0029130000 0.0000040000 0.0000030000 0.0012480000 14869741 96830484 509673472 4.0669898987 4.2981414795 4.6988172531 536 21.4000000000 0.0119786970 0.0106165376 0.0160688832 0.0145771558 0.0050410000 0.0004570000 0.0027650000 0.0000010000 0.0000040000 0.0009830000 14872517 96830484 509673472 4.0708522797 4.2987093925 4.7009558678 537 21.4400000000 0.0120301638 0.0106191700 0.0160688832 0.0145963743 0.0096460000 0.0006420000 0.0028110000 0.0000160000 0.0000140000 0.0025120000 14875293 96830484 509673472 4.0753297806 4.2993488312 4.7032055855 538 21.4800000000 0.0120142708 0.0106217632 0.0160688832 0.0146054896 0.0080850000 0.0006470000 0.0035700000 0.0000020000 0.0000150000 0.0013880000 14878069 96830484 509673472 4.0800886154 4.3002805710 4.7051415443 539 21.5200000000 0.0120973121 0.0106245007 0.0160688832 0.0146157833 0.0062120000 0.0005250000 0.0028730000 0.0000060000 0.0000060000 0.0013080000 14880845 96830484 509673472 4.0850734711 4.3015527725 4.7067790031 540 21.5600000000 0.0119826198 0.0106270158 0.0160688832 0.0146176958 0.0055360000 0.0004820000 0.0028270000 0.0000000000 0.0000050000 0.0010130000 14883621 96830484 509673472 4.0889372826 4.3017978668 4.7090120316 541 21.6000000000 0.0121120261 0.0106297607 0.0160688832 0.0146213849 0.0107540000 0.0006400000 0.0032970000 0.0000150000 0.0000140000 0.0028430000 14886397 96830484 509673472 4.0933823586 4.3020057678 4.7108407021 542 21.6400000000 0.0121487631 0.0106325633 0.0160688832 0.0146290780 0.0063360000 0.0006240000 0.0027370000 0.0000010000 0.0000090000 0.0012830000 14889173 96830484 509673472 4.0971255302 4.3034286499 4.7127790451 543 21.6800000000 0.0120694777 0.0106352095 0.0160688832 0.0146456128 0.0053110000 0.0004810000 0.0023700000 0.0000060000 0.0000050000 0.0013070000 14891949 96830484 509673472 4.1010928154 4.3041114807 4.7148814201 544 21.7200000000 0.0120920986 0.0106378877 0.0160688832 0.0146602012 0.0071950000 0.0005550000 0.0029700000 0.0000020000 0.0000100000 0.0012100000 14894725 96830484 509673472 4.1041474342 4.3046975136 4.7170557976 545 21.7600000000 0.0121336989 0.0106406323 0.0160688832 0.0146746166 0.0077160000 0.0005240000 0.0033500000 0.0000090000 0.0000070000 0.0021010000 14897501 96830484 509673472 4.1083898544 4.3065524101 4.7192177773 546 21.8000000000 0.0122112650 0.0106435089 0.0160688832 0.0147506163 0.0083950000 0.0006410000 0.0029460000 0.0000020000 0.0000160000 0.0014030000 14900277 96830484 509673472 4.1140713692 4.3078289032 4.7236514091 547 21.8400000000 0.0122052282 0.0106463639 0.0160688832 0.0147587287 0.0064090000 0.0005210000 0.0030330000 0.0000080000 0.0000070000 0.0013600000 14903053 96830484 509673472 4.1176900864 4.3086614609 4.7259058952 548 21.8800000000 0.0121666212 0.0106491381 0.0160688832 0.0147717714 0.0067710000 0.0005570000 0.0029650000 0.0000010000 0.0000110000 0.0012180000 14905829 96830484 509673472 4.1218347549 4.3104872704 4.7277173996 549 21.9200000000 0.0121861426 0.0106519378 0.0160688832 0.0147926002 0.0076520000 0.0005550000 0.0024900000 0.0000110000 0.0000100000 0.0022490000 14908605 96830484 509673472 4.1253290176 4.3122358322 4.7299408913 550 21.9600000000 0.0121491756 0.0106546600 0.0160688832 0.0148096451 0.0082340000 0.0006480000 0.0026360000 0.0000020000 0.0000160000 0.0014100000 14911381 96830484 509673472 4.1306748390 4.3132119179 4.7314743996 551 22.0000000000 0.0120368935 0.0106571686 0.0160688832 0.0148366816 0.0063090000 0.0005220000 0.0028890000 0.0000080000 0.0000080000 0.0013890000 14914157 96830484 509673472 4.1338710785 4.3155517578 4.7331252098 552 22.0400000000 0.0120737087 0.0106597348 0.0160688832 0.0148478032 0.0070840000 0.0005550000 0.0029630000 0.0000010000 0.0000100000 0.0012190000 14916933 96830484 509673472 4.1385664940 4.3180513382 4.7345309258 553 22.0800000000 0.0120486123 0.0106622463 0.0160688832 0.0148445271 0.0087300000 0.0006430000 0.0024330000 0.0000150000 0.0000140000 0.0025580000 14919709 96830484 509673472 4.1431574821 4.3179211617 4.7360258102 554 22.1200000000 0.0120710088 0.0106647892 0.0160688832 0.0148379900 0.0061040000 0.0005530000 0.0024740000 0.0000010000 0.0000100000 0.0011780000 14922485 96830484 509673472 4.1464190483 4.3171153069 4.7381072044 555 22.1600000000 0.0120177362 0.0106672270 0.0160688832 0.0148304560 0.0074590000 0.0006420000 0.0026200000 0.0000170000 0.0000140000 0.0016470000 14925261 96830484 509673472 4.1525573730 4.3189549446 4.7391719818 556 22.2000000000 0.0119099757 0.0106694621 0.0160688832 0.0148292840 0.0053510000 0.0005190000 0.0022520000 0.0000010000 0.0000070000 0.0010720000 14928037 96830484 509673472 4.1577239037 4.3218302727 4.7405247688 557 22.2400000000 0.0119667416 0.0106717912 0.0160688832 0.0148255586 0.0059430000 0.0004820000 0.0021920000 0.0000050000 0.0000040000 0.0020020000 14930813 96830484 509673472 4.1623139381 4.3236269951 4.7420630455 558 22.2800000000 0.0118770422 0.0106739511 0.0160688832 0.0148250888 0.0084950000 0.0006410000 0.0026320000 0.0000020000 0.0000150000 0.0014270000 14933589 96830484 509673472 4.1676177979 4.3264379501 4.7435960770 559 22.3200000000 0.0118846670 0.0106761170 0.0160688832 0.0148221111 0.0067770000 0.0005530000 0.0024830000 0.0000100000 0.0000090000 0.0015100000 14936365 96830484 509673472 4.1731181145 4.3290677071 4.7450351715 560 22.3600000000 0.0118575813 0.0106782268 0.0160688832 0.0148180214 0.0067940000 0.0005540000 0.0024660000 0.0000020000 0.0000110000 0.0012340000 14939141 96830484 509673472 4.1770296097 4.3298859596 4.7475976944 561 22.4000000000 0.0118803121 0.0106803695 0.0160688832 0.0148148421 0.0065710000 0.0005200000 0.0024150000 0.0000090000 0.0000070000 0.0020840000 14941917 96830484 509673472 4.1813158989 4.3322420120 4.7492942810 562 22.4400000000 0.0118420441 0.0106824365 0.0160688832 0.0148129154 0.0083270000 0.0006440000 0.0023870000 0.0000020000 0.0000140000 0.0014360000 14944693 96830484 509673472 4.1866836548 4.3355212212 4.7504730225 563 22.4800000000 0.0118373819 0.0106844880 0.0160688832 0.0148061519 0.0062370000 0.0005570000 0.0023920000 0.0000070000 0.0000080000 0.0014220000 14947469 96830484 509673472 4.1928782463 4.3390765190 4.7510790825 564 22.5200000000 0.0118285986 0.0106865165 0.0160688832 0.0147966530 0.0066830000 0.0005770000 0.0023190000 0.0000020000 0.0000100000 0.0012510000 14950245 96830484 509673472 4.1971144676 4.3407702446 4.7527751923 565 22.5600000000 0.0118559469 0.0106885863 0.0160688832 0.0147869716 0.0068790000 0.0005200000 0.0022650000 0.0000080000 0.0000070000 0.0021550000 14953021 96830484 509673472 4.2007317543 4.3417949677 4.7543964386 566 22.6000000000 0.0118564628 0.0106906497 0.0160688832 0.0147780460 0.0053690000 0.0004990000 0.0022310000 0.0000010000 0.0000070000 0.0010960000 14955797 96830484 509673472 4.2058548927 4.3449878693 4.7557139397 567 22.6400000000 0.0118621346 0.0106927158 0.0160688832 0.0147669536 0.0088050000 0.0006450000 0.0026210000 0.0000160000 0.0000140000 0.0016960000 14958573 96830484 509673472 4.2105345726 4.3471097946 4.7567801476 568 22.6800000000 0.0119256908 0.0106948865 0.0160688832 0.0147573687 0.0060180000 0.0005560000 0.0023900000 0.0000010000 0.0000070000 0.0011490000 14961349 96830484 509673472 4.2147746086 4.3489794731 4.7582640648 569 22.7200000000 0.0119384658 0.0106970721 0.0160688832 0.0147463810 0.0068180000 0.0005000000 0.0026640000 0.0000070000 0.0000060000 0.0021010000 14964125 96830484 509673472 4.2202916145 4.3504910469 4.7585482597 570 22.7600000000 0.0119341342 0.0106992424 0.0160688832 0.0147357429 0.0054940000 0.0004820000 0.0026420000 0.0000010000 0.0000050000 0.0010790000 14966901 96830484 509673472 4.2244095802 4.3532781601 4.7594642639 571 22.8000000000 0.0120027270 0.0107015252 0.0160688832 0.0147238133 0.0058370000 0.0005370000 0.0026330000 0.0000050000 0.0000050000 0.0013520000 14969677 96830484 509673472 4.2295084000 4.3560414314 4.7602372169 572 22.8400000000 0.0119376061 0.0107036862 0.0160688832 0.0147114735 0.0051030000 0.0005270000 0.0023140000 0.0000010000 0.0000050000 0.0010870000 14972453 96830484 509673472 4.2353692055 4.3589210510 4.7598528862 573 22.8800000000 0.0119831096 0.0107059190 0.0160688832 0.0147000291 0.0058910000 0.0004800000 0.0021690000 0.0000060000 0.0000040000 0.0020630000 14975229 96830484 509673472 4.2395219803 4.3611550331 4.7606086731 574 22.9200000000 0.0120020108 0.0107081770 0.0160688832 0.0146889920 0.0086860000 0.0006550000 0.0026220000 0.0000020000 0.0000160000 0.0014710000 14978005 96830484 509673472 4.2439103127 4.3643040657 4.7608060837 575 22.9600000000 0.0119920811 0.0107104099 0.0160688832 0.0146763749 0.0083360000 0.0006500000 0.0028810000 0.0000160000 0.0000150000 0.0017260000 14980781 96830484 509673472 4.2479085922 4.3671140671 4.7614502907 576 23.0000000000 0.0120117040 0.0107126691 0.0160688832 0.0146637008 0.0056230000 0.0005190000 0.0023880000 0.0000010000 0.0000080000 0.0011220000 14983557 96830484 509673472 4.2516646385 4.3705291748 4.7619810104 577 23.0400000000 0.0120698931 0.0107150213 0.0160688832 0.0146509890 0.0063680000 0.0004810000 0.0026260000 0.0000060000 0.0000050000 0.0021050000 14986333 96830484 509673472 4.2554793358 4.3741393089 4.7623934746 578 23.0800000000 0.0120944437 0.0107174078 0.0160688832 0.0146384649 0.0085470000 0.0006610000 0.0024490000 0.0000010000 0.0000160000 0.0014790000 14989109 96830484 509673472 4.2584090233 4.3759474754 4.7627820969 579 23.1200000000 0.0120343929 0.0107196824 0.0160688832 0.0146263324 0.0063410000 0.0006050000 0.0022720000 0.0000100000 0.0000070000 0.0014460000 14991885 96830484 509673472 4.2622861862 4.3794813156 4.7623944283 580 23.1600000000 0.0121387104 0.0107221290 0.0160688832 0.0146142852 0.0051740000 0.0004860000 0.0023210000 0.0000010000 0.0000060000 0.0010990000 14994661 96830484 509673472 4.2666702271 4.3853597641 4.7623209953 581 23.2000000000 0.0121114431 0.0107245203 0.0160688832 0.0146017761 0.0107020000 0.0006590000 0.0036800000 0.0000160000 0.0000140000 0.0026290000 14997437 96830484 509673472 4.2703099251 4.3899364471 4.7621145248 582 23.2400000000 0.0121623464 0.0107269908 0.0160688832 0.0145892829 0.0060820000 0.0005280000 0.0026840000 0.0000010000 0.0000080000 0.0011900000 15000213 96830484 509673472 4.2728261948 4.3934330940 4.7621450424 583 23.2800000000 0.0121922139 0.0107295040 0.0160688832 0.0145768718 0.0053170000 0.0004830000 0.0023130000 0.0000050000 0.0000040000 0.0013540000 15002989 96830484 509673472 4.2759280205 4.3984956741 4.7622580528 584 23.3200000000 0.0121624535 0.0107319577 0.0160688832 0.0145655326 0.0052680000 0.0004670000 0.0027010000 0.0000010000 0.0000060000 0.0010800000 15005765 96830484 509673472 4.2784314156 4.4013667107 4.7615737915 585 23.3600000000 0.0121960565 0.0107344604 0.0160688832 0.0145537019 0.0096950000 0.0006440000 0.0024020000 0.0000150000 0.0000140000 0.0026350000 15008541 96830484 509673472 4.2810473442 4.4034886360 4.7611641884 586 23.4000000000 0.0122148367 0.0107369867 0.0160688832 0.0145417283 0.0066160000 0.0005560000 0.0024170000 0.0000010000 0.0000120000 0.0012860000 15011317 96830484 509673472 4.2833170891 4.4064345360 4.7611937523 587 23.4400000000 0.0122133950 0.0107395018 0.0160688832 0.0145293573 0.0053850000 0.0004970000 0.0021760000 0.0000060000 0.0000050000 0.0013580000 15014093 96830484 509673472 4.2856001854 4.4096860886 4.7609395981 588 23.4800000000 0.0122119570 0.0107420060 0.0160688832 0.0145170843 0.0050150000 0.0004730000 0.0022750000 0.0000000000 0.0000040000 0.0010970000 15016869 96830484 509673472 4.2877941132 4.4124536514 4.7609276772 589 23.5200000000 0.0121854302 0.0107444566 0.0160688832 0.0145048293 0.0104040000 0.0006440000 0.0030400000 0.0000160000 0.0000140000 0.0026690000 15019645 96830484 509673472 4.2906360626 4.4152216911 4.7607798576 590 23.5600000000 0.0122225862 0.0107469620 0.0160688832 0.0144925436 0.0065050000 0.0005580000 0.0028400000 0.0000000000 0.0000080000 0.0012040000 15022421 96830484 509673472 4.2923436165 4.4170289040 4.7612094879 591 23.6000000000 0.0122066531 0.0107494318 0.0160688832 0.0144803550 0.0069570000 0.0005550000 0.0028690000 0.0000110000 0.0000100000 0.0014780000 15025197 96830484 509673472 4.2943344116 4.4197659492 4.7616882324 592 23.6400000000 0.0121598383 0.0107518143 0.0160688832 0.0144689231 0.0081650000 0.0006440000 0.0034830000 0.0000020000 0.0000150000 0.0013160000 15027973 96830484 509673472 4.2972207069 4.4224538803 4.7611255646 593 23.6800000000 0.0120487856 0.0107540014 0.0160688832 0.0144602918 0.0069080000 0.0005190000 0.0026440000 0.0000060000 0.0000060000 0.0021400000 15030749 96830484 509673472 4.3010764122 4.4257259369 4.7615776062 594 23.7200000000 0.0119619621 0.0107560350 0.0160688832 0.0144481132 0.0072430000 0.0005570000 0.0027140000 0.0000020000 0.0000100000 0.0012960000 15033525 96830484 509673472 4.3021874428 4.4262409210 4.7623462677 595 23.7600000000 0.0119288806 0.0107580062 0.0160688832 0.0144361941 0.0076390000 0.0006430000 0.0027410000 0.0000160000 0.0000130000 0.0015500000 15036301 96830484 509673472 4.3036966324 4.4281616211 4.7626185417 596 23.8000000000 0.0118820844 0.0107598922 0.0160688832 0.0144241327 0.0056230000 0.0005220000 0.0023350000 0.0000010000 0.0000070000 0.0011450000 15039077 96830484 509673472 4.3049235344 4.4304814339 4.7634449005 597 23.8400000000 0.0119717615 0.0107619221 0.0160688832 0.0144123131 0.0089450000 0.0006410000 0.0027250000 0.0000160000 0.0000140000 0.0026930000 15041853 96830484 509673472 4.3061318398 4.4326667786 4.7639546394 598 23.8800000000 0.0119493864 0.0107639079 0.0160688832 0.0144011907 0.0060810000 0.0005290000 0.0027930000 0.0000000000 0.0000060000 0.0011480000 15044629 96830484 509673472 4.3067488670 4.4336919785 4.7648334503 599 23.9200000000 0.0118549643 0.0107657293 0.0160688832 0.0143911916 0.0075300000 0.0006440000 0.0025970000 0.0000150000 0.0000160000 0.0015700000 15047405 96830484 509673472 4.3076806068 4.4354763031 4.7656846046 600 23.9600000000 0.0118661784 0.0107675634 0.0160688832 0.0143815511 0.0064840000 0.0005210000 0.0028040000 0.0000010000 0.0000080000 0.0012070000 15050181 96830484 509673472 4.3077793121 4.4372272491 4.7665791512 601 24.0000000000 0.0117764277 0.0107692421 0.0160688832 0.0143728414 0.0065750000 0.0004980000 0.0023130000 0.0000070000 0.0000060000 0.0021280000 15052957 96830484 509673472 4.3087153435 4.4407610893 4.7682104111 602 24.0400000000 0.0117437532 0.0107708608 0.0160688832 0.0143623151 0.0052460000 0.0004850000 0.0022830000 0.0000000000 0.0000050000 0.0011190000 15055733 96830484 509673472 4.3093409538 4.4411273003 4.7688274384 603 24.0800000000 0.0116835143 0.0107723744 0.0160688832 0.0143520400 0.0093330000 0.0006490000 0.0028430000 0.0000170000 0.0000130000 0.0017960000 15058509 96830484 509673472 4.3099508286 4.4422488213 4.7696290016 604 24.1200000000 0.0117321312 0.0107739634 0.0160688832 0.0143403519 0.0065590000 0.0005680000 0.0028440000 0.0000010000 0.0000080000 0.0012150000 15061285 96830484 509673472 4.3107824326 4.4435844421 4.7703762054 605 24.1600000000 0.0117094805 0.0107755097 0.0160688832 0.0143286150 0.0060840000 0.0004840000 0.0022900000 0.0000060000 0.0000050000 0.0021080000 15064061 96830484 509673472 4.3120560646 4.4479827881 4.7715826035 606 24.2000000000 0.0116636576 0.0107769753 0.0160688832 0.0143167704 0.0053570000 0.0004680000 0.0026900000 0.0000000000 0.0000050000 0.0011180000 15066837 96830484 509673472 4.3126773834 4.4495725632 4.7725262642 607 24.2400000000 0.0116147725 0.0107783555 0.0160688832 0.0143052457 0.0096190000 0.0006460000 0.0030560000 0.0000150000 0.0000140000 0.0018100000 15069613 96830484 509673472 4.3137688637 4.4511985779 4.7727413177 608 24.2800000000 0.0116917854 0.0107798578 0.0160688832 0.0142936291 0.0066890000 0.0005560000 0.0024130000 0.0000020000 0.0000110000 0.0013260000 15072389 96830484 509673472 4.3142881393 4.4522838593 4.7736325264 609 24.3200000000 0.0116460156 0.0107812801 0.0160688832 0.0142821110 0.0079590000 0.0005570000 0.0030480000 0.0000090000 0.0000070000 0.0022780000 15075165 96830484 509673472 4.3148288727 4.4535408020 4.7741060257 610 24.3600000000 0.0116079850 0.0107826354 0.0160688832 0.0142704582 0.0069980000 0.0005540000 0.0030180000 0.0000020000 0.0000100000 0.0013480000 15077941 96830484 509673472 4.3153643608 4.4562644958 4.7744941711 611 24.4000000000 0.0115930261 0.0107839617 0.0160688832 0.0142587760 0.0062840000 0.0004990000 0.0027660000 0.0000070000 0.0000060000 0.0014660000 15080717 96830484 509673472 4.3163337708 4.4586682320 4.7746882439 612 24.4400000000 0.0115984948 0.0107852926 0.0160688832 0.0142471231 0.0085080000 0.0006440000 0.0027420000 0.0000020000 0.0000150000 0.0015460000 15083493 96830484 509673472 4.3159322739 4.4604692459 4.7758207321 613 24.4800000000 0.0116247796 0.0107866621 0.0160688832 0.0142357034 0.0073690000 0.0005560000 0.0024130000 0.0000100000 0.0000100000 0.0022960000 15086269 96830484 509673472 4.3167676926 4.4630274773 4.7761487961 614 24.5200000000 0.0116310166 0.0107880373 0.0160688832 0.0142247062 0.0059450000 0.0004990000 0.0027600000 0.0000010000 0.0000060000 0.0011790000 15089045 96830484 509673472 4.3164319992 4.4648194313 4.7771167755 615 24.5600000000 0.0115812961 0.0107893271 0.0160688832 0.0142140050 0.0073850000 0.0005580000 0.0024120000 0.0000100000 0.0000100000 0.0016290000 15091821 96830484 509673472 4.3155632019 4.4674983025 4.7782711983 616 24.6000000000 0.0116319899 0.0107906951 0.0160688832 0.0142030989 0.0061670000 0.0005190000 0.0027940000 0.0000010000 0.0000060000 0.0011770000 15094597 96830484 509673472 4.3147702217 4.4694566727 4.7796006203 617 24.6400000000 0.0115902554 0.0107919910 0.0160688832 0.0141917898 0.0067470000 0.0004820000 0.0027320000 0.0000050000 0.0000040000 0.0021300000 15097373 96830484 509673472 4.3138756752 4.4713978767 4.7808008194 618 24.6800000000 0.0115895020 0.0107932814 0.0160688832 0.0141824311 0.0057500000 0.0004840000 0.0027310000 0.0000000000 0.0000050000 0.0011400000 15100149 96830484 509673472 4.3130316734 4.4732813835 4.7822113037 619 24.7200000000 0.0115445461 0.0107944951 0.0160688832 0.0141732861 0.0098120000 0.0006430000 0.0031910000 0.0000170000 0.0000140000 0.0018220000 15102925 96830484 509673472 4.3114171028 4.4760618210 4.7837257385 620 24.7600000000 0.0115744649 0.0107957531 0.0160688832 0.0141647493 0.0067130000 0.0005590000 0.0028650000 0.0000010000 0.0000080000 0.0012280000 15105701 96830484 509673472 4.3100180626 4.4776716232 4.7850079536 621 24.8000000000 0.0115694748 0.0107969991 0.0160688832 0.0141568988 0.0077960000 0.0005590000 0.0028680000 0.0000110000 0.0000090000 0.0022460000 15108477 96830484 509673472 4.3079690933 4.4794778824 4.7869248390 622 24.8400000000 0.0115599129 0.0107982256 0.0160688832 0.0141497968 0.0078080000 0.0006470000 0.0030080000 0.0000020000 0.0000150000 0.0013610000 15111253 96830484 509673472 4.3060803413 4.4814491272 4.7891368866 623 24.8800000000 0.0116131958 0.0107995337 0.0160688832 0.0141454553 0.0064120000 0.0005220000 0.0027930000 0.0000070000 0.0000060000 0.0014160000 15114029 96830484 509673472 4.3044810295 4.4848513603 4.7910451889 624 24.9200000000 0.0115452465 0.0108007288 0.0160688832 0.0141390422 0.0066180000 0.0005600000 0.0027150000 0.0000010000 0.0000110000 0.0012280000 15116805 96830484 509673472 4.3033380508 4.4858021736 4.7927770615 625 24.9600000000 0.0115177566 0.0108018760 0.0160688832 0.0141322478 0.0064520000 0.0004970000 0.0023220000 0.0000070000 0.0000050000 0.0021680000 15119581 96830484 509673472 4.3010473251 4.4882593155 4.7949810028 626 25.0000000000 0.0115789147 0.0108031173 0.0160688832 0.0141256547 0.0058290000 0.0004880000 0.0027460000 0.0000010000 0.0000050000 0.0011220000 15122357 96830484 509673472 4.2988171577 4.4918107986 4.7970514297 627 25.0400000000 0.0115893465 0.0108043713 0.0160688832 0.0141231448 0.0058830000 0.0004800000 0.0027290000 0.0000050000 0.0000040000 0.0014010000 15125133 96830484 509673472 4.2976489067 4.4952707291 4.7981457710 628 25.0800000000 0.0116158789 0.0108056635 0.0160688832 0.0141218251 0.0055730000 0.0004730000 0.0027450000 0.0000010000 0.0000050000 0.0010990000 15127909 96830484 509673472 4.2957305908 4.4977736473 4.7997922897 629 25.1200000000 0.0115414746 0.0108068333 0.0160688832 0.0141239998 0.0060780000 0.0004720000 0.0022850000 0.0000040000 0.0000040000 0.0020590000 15130685 96830484 509673472 4.2942919731 4.4998526573 4.8009676933 630 25.1600000000 0.0115554482 0.0108080216 0.0160688832 0.0141187170 0.0058220000 0.0005350000 0.0027470000 0.0000000000 0.0000050000 0.0010970000 15133461 96830484 509673472 4.2905416489 4.5014061928 4.8035182953 631 25.2000000000 0.0116366046 0.0108093347 0.0160688832 0.0141131504 0.0097490000 0.0006970000 0.0030450000 0.0000150000 0.0000140000 0.0017430000 15136237 96830484 509673472 4.2881774902 4.5038218498 4.8051304817 632 25.2400000000 0.0115833208 0.0108105594 0.0160688832 0.0141067242 0.0068480000 0.0005560000 0.0024360000 0.0000010000 0.0000110000 0.0012720000 15139013 96830484 509673472 4.2848052979 4.5038795471 4.8078551292 633 25.2800000000 0.0115286205 0.0108116937 0.0160688832 0.0140983144 0.0066590000 0.0005060000 0.0025110000 0.0000060000 0.0000060000 0.0021170000 15141789 96830484 509673472 4.2809953690 4.5053887367 4.8100585938 634 25.3200000000 0.0115815373 0.0108129080 0.0160688832 0.0140900096 0.0054150000 0.0004740000 0.0027490000 0.0000010000 0.0000040000 0.0010710000 15144565 96830484 509673472 4.2773575783 4.5081930161 4.8126635551 635 25.3600000000 0.0115961498 0.0108141415 0.0160688832 0.0140825593 0.0054680000 0.0004590000 0.0026700000 0.0000030000 0.0000030000 0.0013380000 15147341 96830484 509673472 4.2735319138 4.5104494095 4.8155016899 636 25.4000000000 0.0115881190 0.0108153584 0.0160688832 0.0140761703 0.0095460000 0.0006450000 0.0030510000 0.0000010000 0.0000160000 0.0014790000 15150117 96830484 509673472 4.2699556351 4.5116233826 4.8178167343 637 25.4400000000 0.0114945406 0.0108164246 0.0160688832 0.0140696041 0.0075310000 0.0005610000 0.0024510000 0.0000100000 0.0000090000 0.0023140000 15152893 96830484 509673472 4.2656741142 4.5126523972 4.8207306862 638 25.4800000000 0.0114941187 0.0108174868 0.0160688832 0.0140624298 0.0054220000 0.0005070000 0.0023710000 0.0000010000 0.0000060000 0.0010690000 15155669 96830484 509673472 4.2605309486 4.5137457848 4.8242206573 639 25.5200000000 0.0114629492 0.0108184969 0.0160688832 0.0140552886 0.0055290000 0.0004730000 0.0024660000 0.0000050000 0.0000050000 0.0013240000 15158445 96830484 509673472 4.2559452057 4.5140314102 4.8274774551 640 25.5600000000 0.0114609068 0.0108195007 0.0160688832 0.0140470049 0.0049310000 0.0004640000 0.0023060000 0.0000010000 0.0000040000 0.0010410000 15161221 96830484 509673472 4.2510352135 4.5132975578 4.8310713768 641 25.6000000000 0.0114768622 0.0108205262 0.0160688832 0.0140390233 0.0062750000 0.0004660000 0.0027010000 0.0000050000 0.0000030000 0.0019780000 15163997 96830484 509673472 4.2461094856 4.5134468079 4.8343024254 642 25.6400000000 0.0115635851 0.0108216837 0.0160688832 0.0140350932 0.0052350000 0.0004640000 0.0026150000 0.0000000000 0.0000040000 0.0010370000 15166773 96830484 509673472 4.2419381142 4.5160069466 4.8372206688 643 25.6800000000 0.0115255732 0.0108227783 0.0160688832 0.0140325800 0.0092560000 0.0006400000 0.0025290000 0.0000160000 0.0000150000 0.0016880000 15169549 96830484 509673472 4.2371945381 4.5171108246 4.8403229713 644 25.7200000000 0.0115042944 0.0108238366 0.0160688832 0.0140291030 0.0087630000 0.0006500000 0.0030670000 0.0000020000 0.0000160000 0.0014400000 15172325 96830484 509673472 4.2328038216 4.5170245171 4.8431725502 645 25.7600000000 0.0115219522 0.0108249190 0.0160688832 0.0140232456 0.0069230000 0.0005280000 0.0025630000 0.0000080000 0.0000070000 0.0020190000 15175101 96830484 509673472 4.2286524773 4.5188999176 4.8456974030 646 25.8000000000 0.0115019698 0.0108259670 0.0160688832 0.0140176187 0.0056110000 0.0004870000 0.0027990000 0.0000010000 0.0000050000 0.0010230000 15177877 96830484 509673472 4.2243423462 4.5204586983 4.8485646248 647 25.8400000000 0.0115263462 0.0108270495 0.0160688832 0.0140115550 0.0082070000 0.0006480000 0.0030980000 0.0000160000 0.0000140000 0.0014760000 15180653 96830484 509673472 4.2194867134 4.5207118988 4.8517136574 648 25.8800000000 0.0114828758 0.0108280616 0.0160688832 0.0140040206 0.0057750000 0.0005260000 0.0023790000 0.0000010000 0.0000060000 0.0010690000 15183429 96830484 509673472 4.2150888443 4.5226354599 4.8543767929 649 25.9200000000 0.0114525631 0.0108290239 0.0160688832 0.0139962331 0.0067700000 0.0004820000 0.0028060000 0.0000050000 0.0000050000 0.0019750000 15186205 96830484 509673472 4.2106933594 4.5244226456 4.8570928574 650 25.9600000000 0.0115292165 0.0108301011 0.0160688832 0.0139895595 0.0054910000 0.0004720000 0.0027770000 0.0000000000 0.0000040000 0.0009920000 15188981 96830484 509673472 4.2064204216 4.5279941559 4.8595695496 651 26.0000000000 0.0114981029 0.0108311272 0.0160688832 0.0139884446 0.0098610000 0.0006480000 0.0031000000 0.0000170000 0.0000130000 0.0016440000 15191757 96830484 509673472 4.2032151222 4.5298924446 4.8618168831 652 26.0400000000 0.0114792464 0.0108321212 0.0160688832 0.0139852874 0.0066280000 0.0005570000 0.0028990000 0.0000020000 0.0000080000 0.0010830000 15194533 96830484 509673472 4.1994199753 4.5320353508 4.8637261391 653 26.0800000000 0.0114995940 0.0108331434 0.0160688832 0.0139839611 0.0077720000 0.0005660000 0.0029550000 0.0000100000 0.0000100000 0.0020380000 15197309 96830484 509673472 4.1946620941 4.5336074829 4.8660407066 654 26.1200000000 0.0114952652 0.0108341558 0.0160688832 0.0139839288 0.0058610000 0.0005060000 0.0028200000 0.0000010000 0.0000060000 0.0009980000 15200085 96830484 509673472 4.1902155876 4.5347957611 4.8684091568 655 26.1600000000 0.0114654163 0.0108351196 0.0160688832 0.0139796539 0.0065190000 0.0004770000 0.0036880000 0.0000050000 0.0000040000 0.0011920000 15202861 96830484 509673472 4.1875548363 4.5381975174 4.8700971603 656 26.2000000000 0.0115264682 0.0108361735 0.0160688832 0.0139756404 0.0057790000 0.0004620000 0.0033490000 0.0000000000 0.0000030000 0.0009240000 15205637 96830484 509673472 4.1776332855 4.5415129662 4.8739190102 657 26.2400000000 0.0114851110 0.0108371612 0.0160688832 0.0139732970 0.0096850000 0.0006620000 0.0033340000 0.0000170000 0.0000150000 0.0023860000 15208413 96830484 509673472 4.1749095917 4.5418272018 4.8756265640 658 26.2800000000 0.0113917422 0.0108380040 0.0160688832 0.0139662775 0.0086960000 0.0005270000 0.0055940000 0.0000010000 0.0000060000 0.0009780000 15211189 96830484 509673472 4.1714153290 4.5437102318 4.8772268295 659 26.3200000000 0.0114762355 0.0108389725 0.0160688832 0.0139619643 0.0057600000 0.0004770000 0.0029170000 0.0000050000 0.0000040000 0.0011940000 15213965 96830484 509673472 4.1680536270 4.5475296974 4.8786077499 660 26.3600000000 0.0115305698 0.0108400204 0.0160688832 0.0139596030 0.0084250000 0.0005600000 0.0044740000 0.0000020000 0.0000090000 0.0010240000 15216741 96830484 509673472 4.1640801430 4.5485053062 4.8801274300 661 26.4000000000 0.0114370957 0.0108409237 0.0160688832 0.0139579896 0.0065720000 0.0005390000 0.0029500000 0.0000060000 0.0000060000 0.0017400000 15219517 96830484 509673472 4.1615548134 4.5522880554 4.8808898926 662 26.4400000000 0.0114610568 0.0108418604 0.0160688832 0.0139523495 0.0057290000 0.0004670000 0.0032130000 0.0000010000 0.0000050000 0.0009010000 15222293 96830484 509673472 4.1590085030 4.5551948547 4.8817043304 663 26.4800000000 0.0112387128 0.0108424590 0.0160688832 0.0139490849 0.0055520000 0.0004610000 0.0029060000 0.0000040000 0.0000030000 0.0011510000 15225069 96830484 509673472 4.1552529335 4.5547580719 4.8831963539 664 26.5200000000 0.0113037722 0.0108431537 0.0160688832 0.0139478884 0.0057610000 0.0004640000 0.0033430000 0.0000010000 0.0000040000 0.0008970000 15227845 96830484 509673472 4.1528711319 4.5563516617 4.8841729164 665 26.5600000000 0.0113020130 0.0108438438 0.0160688832 0.0139461421 0.0113170000 0.0006590000 0.0037470000 0.0000160000 0.0000140000 0.0023360000 15230621 96830484 509673472 4.1495718956 4.5585818291 4.8853125572 666 26.6000000000 0.0112277316 0.0108444202 0.0160688832 0.0139413875 0.0069240000 0.0005520000 0.0034900000 0.0000010000 0.0000080000 0.0010070000 15233397 96830484 509673472 4.1468520164 4.5597248077 4.8863124847 667 26.6400000000 0.0113299256 0.0108451481 0.0160688832 0.0139363419 0.0072030000 0.0005600000 0.0030950000 0.0000100000 0.0000090000 0.0012480000 15236173 96830484 509673472 4.1425442696 4.5616598129 4.8873085976 668 26.6800000000 0.0113681396 0.0108459310 0.0160688832 0.0139311370 0.0068320000 0.0004990000 0.0038780000 0.0000010000 0.0000060000 0.0009120000 15238949 96830484 509673472 4.1384134293 4.5636277199 4.8883666992 669 26.7200000000 0.0112666506 0.0108465599 0.0160688832 0.0139273054 0.0074840000 0.0004640000 0.0042580000 0.0000030000 0.0000030000 0.0017040000 15241725 96830484 509673472 4.1345772743 4.5653724670 4.8893389702 670 26.7600000000 0.0113597745 0.0108473258 0.0160688832 0.0139207571 0.0055470000 0.0004570000 0.0032060000 0.0000000000 0.0000040000 0.0008830000 15244501 96830484 509673472 4.1300735474 4.5645551682 4.8905506134 671 26.8000000000 0.0113635072 0.0108480951 0.0160688832 0.0139158416 0.0100550000 0.0006430000 0.0032620000 0.0000150000 0.0000140000 0.0015450000 15247277 96830484 509673472 4.1267628670 4.5638194084 4.8921170235 672 26.8400000000 0.0112570776 0.0108487037 0.0160688832 0.0139082245 0.0071100000 0.0005570000 0.0035130000 0.0000010000 0.0000070000 0.0009950000 15250053 96830484 509673472 4.1227145195 4.5637097359 4.8935356140 673 26.8800000000 0.0113226194 0.0108494079 0.0160688832 0.0138990840 0.0064090000 0.0004910000 0.0028080000 0.0000050000 0.0000050000 0.0017320000 15252829 96830484 509673472 4.1190128326 4.5637831688 4.8948588371 674 26.9200000000 0.0114411842 0.0108502859 0.0160688832 0.0138954119 0.0069660000 0.0005790000 0.0030840000 0.0000010000 0.0000070000 0.0009960000 15255605 96830484 509673472 4.1147813797 4.5632586479 4.8964004517 675 26.9600000000 0.0113513414 0.0108510282 0.0160688832 0.0138915230 0.0065710000 0.0004980000 0.0034310000 0.0000050000 0.0000050000 0.0011410000 15258381 96830484 509673472 4.1107583046 4.5631685257 4.8974742889 676 27.0000000000 0.0112349242 0.0108515961 0.0160688832 0.0138838699 0.0105250000 0.0005670000 0.0058980000 0.0000020000 0.0000100000 0.0010920000 15261157 96830484 509673472 4.1064968109 4.5633478165 4.8983139992 677 27.0400000000 0.0113450717 0.0108523250 0.0160688832 0.0138770210 0.0072640000 0.0005340000 0.0034370000 0.0000060000 0.0000060000 0.0017150000 15263933 96830484 509673472 4.1015691757 4.5635194778 4.8990793228 678 27.0800000000 0.0113195358 0.0108530141 0.0160688832 0.0138695918 0.0059310000 0.0004810000 0.0033880000 0.0000010000 0.0000040000 0.0008740000 15266709 96830484 509673472 4.0969843864 4.5631785393 4.9000797272 679 27.1200000000 0.0120704891 0.0108548072 0.0160688832 0.0138616653 0.0078310000 0.0005540000 0.0035520000 0.0000100000 0.0000110000 0.0013260000 15269485 96830484 509673472 4.0897178650 4.5619835854 4.9011940956 680 27.1600000000 0.0128715718 0.0108577730 0.0160688832 0.0138571526 0.0071450000 0.0004990000 0.0041680000 0.0000010000 0.0000050000 0.0009000000 15272261 96830484 509673472 4.0835070610 4.5614438057 4.9026851654 681 27.2000000000 0.0129342014 0.0108608221 0.0160688832 0.0138523646 0.0093580000 0.0006450000 0.0037000000 0.0000100000 0.0000090000 0.0020040000 15275037 96830484 509673472 4.0807824135 4.5611319542 4.9033908844 682 27.2400000000 0.0130416183 0.0108640197 0.0160688832 0.0138474341 0.0068750000 0.0005060000 0.0038720000 0.0000000000 0.0000060000 0.0009200000 15277813 96830484 509673472 4.0769982338 4.5605635643 4.9041457176 683 27.2800000000 0.0131060751 0.0108673024 0.0160688832 0.0138422466 0.0077120000 0.0005570000 0.0035600000 0.0000080000 0.0000070000 0.0012380000 15280589 96830484 509673472 4.0742750168 4.5594449043 4.9050788879 684 27.3200000000 0.0131596159 0.0108706537 0.0160688832 0.0138330555 0.0097000000 0.0005570000 0.0058410000 0.0000010000 0.0000080000 0.0010070000 15283365 96830484 509673472 4.0684409142 4.5600023270 4.9061598778 685 27.3600000000 0.0119132521 0.0108721758 0.0160688832 0.0138258363 0.0069820000 0.0005040000 0.0033990000 0.0000050000 0.0000050000 0.0017070000 15286141 96830484 509673472 4.0679798126 4.5609655380 4.9070501328 686 27.4000000000 0.0116003398 0.0108732372 0.0160688832 0.0138206430 0.0075020000 0.0005580000 0.0035630000 0.0000010000 0.0000080000 0.0010220000 15288917 96830484 509673472 4.0646357536 4.5600943565 4.9081921577 687 27.4400000000 0.0114509156 0.0108740781 0.0160688832 0.0138168818 0.0078110000 0.0005890000 0.0035670000 0.0000100000 0.0000090000 0.0012540000 15291693 96830484 509673472 4.0611758232 4.5607519150 4.9095492363 688 27.4800000000 0.0114099262 0.0108748570 0.0160688832 0.0138139314 0.0064430000 0.0004980000 0.0034370000 0.0000010000 0.0000060000 0.0009060000 15294469 96830484 509673472 4.0593123436 4.5612545013 4.9106373787 689 27.5200000000 0.0113251265 0.0108755105 0.0160688832 0.0138098358 0.0082290000 0.0005570000 0.0034050000 0.0000080000 0.0000060000 0.0018830000 15297245 96830484 509673472 4.0555887222 4.5619902611 4.9114174843 690 27.5600000000 0.0113942157 0.0108762622 0.0160688832 0.0138036370 0.0063210000 0.0004960000 0.0033840000 0.0000000000 0.0000050000 0.0009360000 15300021 96830484 509673472 4.0520949364 4.5629744530 4.9124970436 691 27.6000000000 0.0113066379 0.0108768850 0.0160688832 0.0137980164 0.0084500000 0.0005580000 0.0044360000 0.0000080000 0.0000070000 0.0012420000 15302797 96830484 509673472 4.0490760803 4.5631170273 4.9134964943 692 27.6400000000 0.0112356087 0.0108774034 0.0160688832 0.0137922075 0.0057100000 0.0004850000 0.0029410000 0.0000000000 0.0000050000 0.0009050000 15305573 96830484 509673472 4.0457825661 4.5641083717 4.9147243500 693 27.6800000000 0.0112279756 0.0108779093 0.0160688832 0.0137864459 0.0081350000 0.0005570000 0.0030910000 0.0000100000 0.0000090000 0.0020160000 15308349 96830484 509673472 4.0413765907 4.5634570122 4.9157438278 694 27.7200000000 0.0112089999 0.0108783864 0.0160688832 0.0137790698 0.0063700000 0.0005020000 0.0029810000 0.0000000000 0.0000070000 0.0009630000 15311125 96830484 509673472 4.0389795303 4.5637259483 4.9169898033 695 27.7600000000 0.0112630688 0.0108789399 0.0160688832 0.0137734600 0.0083430000 0.0006430000 0.0030870000 0.0000150000 0.0000150000 0.0013990000 15313901 96830484 509673472 4.0361518860 4.5639925003 4.9180583954 696 27.8000000000 0.0113076987 0.0108795559 0.0160688832 0.0137681163 0.0063940000 0.0005270000 0.0029950000 0.0000010000 0.0000060000 0.0009740000 15316677 96830484 509673472 4.0322914124 4.5625467300 4.9193463326 697 27.8400000000 0.0113889296 0.0108802867 0.0160688832 0.0137647952 0.0084440000 0.0005560000 0.0029380000 0.0000100000 0.0000100000 0.0020530000 15319453 96830484 509673472 4.0286211967 4.5632452965 4.9203433990 698 27.8800000000 0.0113534154 0.0108809646 0.0160688832 0.0137608629 0.0061400000 0.0005070000 0.0029830000 0.0000010000 0.0000060000 0.0010030000 15322229 96830484 509673472 4.0259771347 4.5633015633 4.9214181900 699 27.9200000000 0.0113372747 0.0108816174 0.0160688832 0.0137558503 0.0092050000 0.0005560000 0.0049300000 0.0000100000 0.0000090000 0.0012950000 15325005 96830484 509673472 4.0221881866 4.5640468597 4.9224605560 700 27.9600000000 0.0114962654 0.0108824954 0.0160688832 0.0137537116 0.0059280000 0.0005060000 0.0028070000 0.0000010000 0.0000050000 0.0009640000 15327781 96830484 509673472 4.0180969238 4.5642251968 4.9235777855 701 28.0000000000 0.0115596643 0.0108834614 0.0160688832 0.0137504303 0.0064440000 0.0004750000 0.0029110000 0.0000050000 0.0000040000 0.0017810000 15330557 96830484 509673472 4.0149779320 4.5650706291 4.9245176315 702 28.0400000000 0.0115038604 0.0108843452 0.0160688832 0.0137464756 0.0072850000 0.0005570000 0.0026400000 0.0000020000 0.0000100000 0.0012120000 15333333 96830484 509673472 4.0103797913 4.5671339035 4.9250731468 703 28.0800000000 0.0115220072 0.0108852523 0.0160688832 0.0137420541 0.0070190000 0.0005200000 0.0032860000 0.0000070000 0.0000050000 0.0012610000 15336109 96830484 509673472 4.0076923370 4.5676422119 4.9263038635 704 28.1200000000 0.0116528515 0.0108863426 0.0160688832 0.0137372419 0.0059940000 0.0004820000 0.0029320000 0.0000000000 0.0000050000 0.0009820000 15338885 96830484 509673472 4.0046463013 4.5676527023 4.9273943901 705 28.1600000000 0.0116830654 0.0108874727 0.0160688832 0.0137325480 0.0096030000 0.0006430000 0.0030730000 0.0000150000 0.0000140000 0.0024610000 15341661 96830484 509673472 4.0017213821 4.5674772263 4.9288611412 706 28.2000000000 0.0118209235 0.0108887949 0.0160688832 0.0137274016 0.0072380000 0.0005300000 0.0037400000 0.0000010000 0.0000060000 0.0010210000 15344437 96830484 509673472 4.0000128746 4.5666999817 4.9300236702 707 28.2400000000 0.0117870346 0.0108900654 0.0160688832 0.0137227195 0.0058850000 0.0004880000 0.0029040000 0.0000060000 0.0000050000 0.0011820000 15347213 96830484 509673472 3.9958016872 4.5662469864 4.9311766624 708 28.2800000000 0.0118116047 0.0108913670 0.0160688832 0.0137169884 0.0079040000 0.0005560000 0.0031000000 0.0000020000 0.0000110000 0.0012060000 15349989 96830484 509673472 3.9934604168 4.5657749176 4.9323458672 709 28.3200000000 0.0117725311 0.0108926098 0.0160688832 0.0137099076 0.0069510000 0.0004970000 0.0029590000 0.0000070000 0.0000070000 0.0018360000 15352765 96830484 509673472 3.9901025295 4.5670986176 4.9333662987 710 28.3600000000 0.0118256854 0.0108939240 0.0160688832 0.0137036313 0.0057400000 0.0004710000 0.0029060000 0.0000000000 0.0000050000 0.0009750000 15355541 96830484 509673472 3.9860303402 4.5672678947 4.9343438148 711 28.4000000000 0.0117834099 0.0108951750 0.0160688832 0.0136986691 0.0093810000 0.0006480000 0.0030710000 0.0000160000 0.0000140000 0.0016890000 15358317 96830484 509673472 3.9823002815 4.5669403076 4.9356060028 712 28.4400000000 0.0118129598 0.0108964640 0.0160688832 0.0136923120 0.0065150000 0.0005290000 0.0030080000 0.0000010000 0.0000060000 0.0010160000 15361093 96830484 509673472 3.9772851467 4.5669889450 4.9365119934 713 28.4800000000 0.0117946854 0.0108977238 0.0160688832 0.0136857819 0.0065820000 0.0004850000 0.0027910000 0.0000050000 0.0000040000 0.0018060000 15363869 96830484 509673472 3.9731812477 4.5677752495 4.9374914169 714 28.5200000000 0.0118517196 0.0108990600 0.0160688832 0.0136795819 0.0092170000 0.0006500000 0.0032260000 0.0000020000 0.0000150000 0.0014610000 15366645 96830484 509673472 3.9693520069 4.5670971870 4.9389166832 715 28.5600000000 0.0118242735 0.0109003540 0.0160688832 0.0136718783 0.0066060000 0.0005220000 0.0028490000 0.0000070000 0.0000050000 0.0012570000 15369421 96830484 509673472 3.9647455215 4.5674276352 4.9401965141 716 28.6000000000 0.0118637709 0.0109016995 0.0160688832 0.0136665161 0.0058340000 0.0004910000 0.0027920000 0.0000000000 0.0000060000 0.0009970000 15372197 96830484 509673472 3.9602661133 4.5663557053 4.9413499832 717 28.6400000000 0.0119430460 0.0109031519 0.0160688832 0.0136597557 0.0109450000 0.0006790000 0.0030640000 0.0000150000 0.0000150000 0.0024650000 15374973 96830484 509673472 3.9559457302 4.5667572021 4.9421672821 718 28.6800000000 0.0120317554 0.0109047237 0.0160688832 0.0136534276 0.0066740000 0.0005320000 0.0030200000 0.0000020000 0.0000080000 0.0010990000 15377749 96830484 509673472 3.9511642456 4.5675902367 4.9429998398 719 28.7200000000 0.0120504899 0.0109063173 0.0160688832 0.0136502732 0.0065470000 0.0004850000 0.0033890000 0.0000050000 0.0000050000 0.0012250000 15380525 96830484 509673472 3.9469182491 4.5661892891 4.9438772202 720 28.7600000000 0.0120257521 0.0109078721 0.0160688832 0.0136515466 0.0090500000 0.0006780000 0.0032360000 0.0000020000 0.0000160000 0.0016300000 15383301 96830484 509673472 3.9434931278 4.5664758682 4.9447131157 721 28.8000000000 0.0120702581 0.0109094843 0.0160688832 0.0136480061 0.0070500000 0.0005910000 0.0026850000 0.0000070000 0.0000060000 0.0018560000 15386077 96830484 509673472 3.9399178028 4.5654459000 4.9459543228 722 28.8400000000 0.0121082989 0.0109111447 0.0160688832 0.0136433271 0.0076500000 0.0005720000 0.0035290000 0.0000010000 0.0000080000 0.0010920000 15388853 96830484 509673472 3.9342048168 4.5643277168 4.9468650818 723 28.8800000000 0.0122057572 0.0109129353 0.0160688832 0.0136372272 0.0069480000 0.0005620000 0.0024900000 0.0000100000 0.0000090000 0.0014180000 15391629 96830484 509673472 3.9304428101 4.5646886826 4.9477419853 724 28.9200000000 0.0122405924 0.0109147691 0.0160688832 0.0136303864 0.0066480000 0.0005020000 0.0034370000 0.0000000000 0.0000070000 0.0010280000 15394405 96830484 509673472 3.9248869419 4.5641012192 4.9484539032 725 28.9600000000 0.0122340769 0.0109165888 0.0160688832 0.0136231206 0.0086150000 0.0005850000 0.0030830000 0.0000100000 0.0000100000 0.0021440000 15397181 96830484 509673472 3.9212698936 4.5632958412 4.9496965408 726 29.0000000000 0.0122660166 0.0109184475 0.0160688832 0.0136167464 0.0069110000 0.0005020000 0.0037220000 0.0000000000 0.0000050000 0.0009950000 15399957 96830484 509673472 3.9176747799 4.5634036064 4.9504284859 727 29.0400000000 0.0122417249 0.0109202677 0.0160688832 0.0136126895 0.0059340000 0.0004770000 0.0029170000 0.0000050000 0.0000040000 0.0012220000 15402733 96830484 509673472 3.9142358303 4.5633416176 4.9512495995 728 29.0800000000 0.0123282811 0.0109222018 0.0160688832 0.0136092642 0.0090270000 0.0006480000 0.0032680000 0.0000010000 0.0000150000 0.0014690000 15405509 96830484 509673472 3.9117195606 4.5624370575 4.9520030022 729 29.1200000000 0.0122624664 0.0109240403 0.0160688832 0.0136089270 0.0072380000 0.0005200000 0.0028460000 0.0000060000 0.0000060000 0.0018920000 15408285 96830484 509673472 3.9087927341 4.5623116493 4.9526462555 730 29.1600000000 0.0122999204 0.0109259250 0.0160688832 0.0136067065 0.0054980000 0.0004820000 0.0027650000 0.0000000000 0.0000040000 0.0009700000 15411061 96830484 509673472 3.9065015316 4.5612616539 4.9535751343 731 29.2000000000 0.0123016089 0.0109278070 0.0160688832 0.0136043590 0.0083740000 0.0005590000 0.0029470000 0.0000100000 0.0000100000 0.0014740000 15413837 96830484 509673472 3.9015543461 4.5601501465 4.9538431168 732 29.2400000000 0.0122616515 0.0109296292 0.0160688832 0.0136009751 0.0064160000 0.0005280000 0.0028500000 0.0000000000 0.0000070000 0.0010370000 15416613 96830484 509673472 3.8983235359 4.5603199005 4.9542241096 733 29.2800000000 0.0122485356 0.0109314285 0.0160688832 0.0135965324 0.0067220000 0.0004800000 0.0029260000 0.0000040000 0.0000050000 0.0018220000 15419389 96830484 509673472 3.8958361149 4.5587058067 4.9549183846 734 29.3200000000 0.0122495973 0.0109332244 0.0160688832 0.0135899160 0.0060980000 0.0004710000 0.0033480000 0.0000000000 0.0000050000 0.0009680000 15422165 96830484 509673472 3.8932056427 4.5581498146 4.9552950859 735 29.3600000000 0.0122618787 0.0109350321 0.0160688832 0.0135827003 0.0063520000 0.0004700000 0.0033430000 0.0000050000 0.0000040000 0.0012280000 15424941 96830484 509673472 3.8896477222 4.5579490662 4.9554324150 736 29.4000000000 0.0123314410 0.0109369293 0.0160688832 0.0135772965 0.0055330000 0.0004730000 0.0027610000 0.0000000000 0.0000040000 0.0009800000 15427717 96830484 509673472 3.8867161274 4.5565276146 4.9555740356 737 29.4400000000 0.0122091463 0.0109386556 0.0160688832 0.0135720473 0.0063480000 0.0004700000 0.0027630000 0.0000040000 0.0000040000 0.0017970000 15430493 96830484 509673472 3.8839602470 4.5546092987 4.9557127953 738 29.4800000000 0.0123673901 0.0109405915 0.0160688832 0.0135650670 0.0059620000 0.0004690000 0.0032010000 0.0000010000 0.0000040000 0.0009680000 15433269 96830484 509673472 3.8826956749 4.5532174110 4.9563350677 739 29.5200000000 0.0123641044 0.0109425178 0.0160688832 0.0135592420 0.0063640000 0.0004710000 0.0033470000 0.0000040000 0.0000030000 0.0012210000 15436045 96830484 509673472 3.8813424110 4.5511684418 4.9567508698 740 29.5600000000 0.0123274289 0.0109443893 0.0160688832 0.0135564756 0.0061050000 0.0004690000 0.0033460000 0.0000000000 0.0000040000 0.0009690000 15438821 96830484 509673472 3.8800096512 4.5494666100 4.9568820000 741 29.6000000000 0.0123163313 0.0109462408 0.0160688832 0.0135546337 0.0068320000 0.0004730000 0.0032210000 0.0000040000 0.0000030000 0.0017800000 15441597 96830484 509673472 3.8778295517 4.5481486320 4.9573221207 742 29.6400000000 0.0123704318 0.0109481602 0.0160688832 0.0135508154 0.0098540000 0.0006480000 0.0026120000 0.0000010000 0.0000170000 0.0014650000 15444373 96830484 509673472 3.8762705326 4.5469298363 4.9577865601 743 29.6800000000 0.0122822095 0.0109499556 0.0160688832 0.0135482713 0.0074090000 0.0005620000 0.0029130000 0.0000080000 0.0000070000 0.0013520000 15447149 96830484 509673472 3.8749141693 4.5453505516 4.9578795433 744 29.7200000000 0.0122818500 0.0109517458 0.0160688832 0.0135492413 0.0061870000 0.0005060000 0.0029550000 0.0000010000 0.0000060000 0.0009940000 15449925 96830484 509673472 3.8717849255 4.5415754318 4.9586215019 745 29.7600000000 0.0122493366 0.0109534876 0.0160688832 0.0135421893 0.0069470000 0.0004710000 0.0033610000 0.0000040000 0.0000040000 0.0017940000 15452701 96830484 509673472 3.8713405132 4.5392460823 4.9591712952 746 29.8000000000 0.0123639731 0.0109553783 0.0160688832 0.0135346482 0.0100670000 0.0005610000 0.0058170000 0.0000010000 0.0000080000 0.0011140000 15455477 96830484 509673472 3.8697304726 4.5387353897 4.9595146179 747 29.8400000000 0.0123846252 0.0109572916 0.0160688832 0.0135269417 0.0069940000 0.0005050000 0.0036960000 0.0000050000 0.0000040000 0.0012670000 15458253 96830484 509673472 3.8685450554 4.5371017456 4.9600605965 748 29.8800000000 0.0123575749 0.0109591636 0.0160688832 0.0135179466 0.0053630000 0.0004670000 0.0027560000 0.0000010000 0.0000040000 0.0009680000 15461029 96830484 509673472 3.8677852154 4.5356254578 4.9604129791 749 29.9200000000 0.0124474820 0.0109611507 0.0160688832 0.0135090793 0.0089890000 0.0005730000 0.0029440000 0.0000100000 0.0000090000 0.0021800000 15463805 96830484 509673472 3.8660917282 4.5344500542 4.9607939720 750 29.9600000000 0.0124482606 0.0109631335 0.0160688832 0.0135001370 0.0075020000 0.0005880000 0.0034620000 0.0000020000 0.0000080000 0.0010730000 15466581 96830484 509673472 3.8648643494 4.5339894295 4.9611191750 751 30.0000000000 0.0124698980 0.0109651399 0.0160688832 0.0134914107 0.0061690000 0.0004900000 0.0029480000 0.0000040000 0.0000040000 0.0012310000 15469357 96830484 509673472 3.8650188446 4.5306224823 4.9618711472 752 30.0400000000 0.0124669084 0.0109671369 0.0160688832 0.0134827903 0.0055100000 0.0004690000 0.0027640000 0.0000000000 0.0000040000 0.0009420000 15472133 96830484 509673472 3.8646888733 4.5288939476 4.9626708031 753 30.0800000000 0.0125235440 0.0109692038 0.0160688832 0.0134762248 0.0063660000 0.0004670000 0.0027710000 0.0000050000 0.0000030000 0.0017740000 15474909 96830484 509673472 3.8635740280 4.5278277397 4.9634561539 754 30.1200000000 0.0125420261 0.0109712898 0.0160688832 0.0134698552 0.0103770000 0.0006460000 0.0031120000 0.0000020000 0.0000170000 0.0014380000 15477685 96830484 509673472 3.8643829823 4.5260453224 4.9644203186 755 30.1600000000 0.0125368927 0.0109733635 0.0160688832 0.0134635403 0.0077470000 0.0005590000 0.0031000000 0.0000110000 0.0000090000 0.0014330000 15480461 96830484 509673472 3.8644819260 4.5246753693 4.9655852318 756 30.2000000000 0.0125458622 0.0109754435 0.0160688832 0.0134554443 0.0077160000 0.0005020000 0.0044780000 0.0000010000 0.0000050000 0.0009740000 15483237 96830484 509673472 3.8640508652 4.5236868858 4.9664230347 757 30.2400000000 0.0125135323 0.0109774753 0.0160688832 0.0134483969 0.0084300000 0.0005610000 0.0032560000 0.0000110000 0.0000110000 0.0019750000 15486013 96830484 509673472 3.8643467426 4.5219287872 4.9675421715 758 30.2800000000 0.0125107979 0.0109794982 0.0160688832 0.0134434340 0.0060530000 0.0005020000 0.0028270000 0.0000010000 0.0000050000 0.0009710000 15488789 96830484 509673472 3.8640918732 4.5231790543 4.9686517715 759 30.3200000000 0.0124955643 0.0109814956 0.0160688832 0.0134390356 0.0082980000 0.0005750000 0.0031070000 0.0000120000 0.0000100000 0.0014340000 15491565 96830484 509673472 3.8646879196 4.5220465660 4.9698476791 760 30.3600000000 0.0125906961 0.0109836130 0.0160688832 0.0134381098 0.0063840000 0.0005010000 0.0031320000 0.0000000000 0.0000060000 0.0009800000 15494341 96830484 509673472 3.8661565781 4.5198273659 4.9710731506 761 30.4000000000 0.0127371084 0.0109859172 0.0160688832 0.0134328266 0.0094260000 0.0006610000 0.0031000000 0.0000170000 0.0000150000 0.0021520000 15497117 96830484 509673472 3.8665795326 4.5197105408 4.9726371765 762 30.4400000000 0.0126919979 0.0109881561 0.0160688832 0.0134242053 0.0087040000 0.0005320000 0.0054350000 0.0000010000 0.0000050000 0.0009660000 15499893 96830484 509673472 3.8673193455 4.5190439224 4.9740591049 763 30.4800000000 0.0127768312 0.0109905004 0.0160688832 0.0134154999 0.0075010000 0.0005590000 0.0029390000 0.0000080000 0.0000070000 0.0013150000 15502669 96830484 509673472 3.8691532612 4.5165863037 4.9757590294 764 30.5200000000 0.0127922194 0.0109928587 0.0160688832 0.0134078876 0.0072890000 0.0005680000 0.0029350000 0.0000010000 0.0000110000 0.0011130000 15505445 96830484 509673472 3.8717319965 4.5147867203 4.9773354530 765 30.5600000000 0.0128158089 0.0109952416 0.0160688832 0.0134006839 0.0069310000 0.0005030000 0.0029640000 0.0000060000 0.0000040000 0.0017910000 15508221 96830484 509673472 3.8740055561 4.5133748055 4.9791779518 766 30.6000000000 0.0128333755 0.0109976413 0.0160688832 0.0133978484 0.0078480000 0.0005590000 0.0029550000 0.0000010000 0.0000110000 0.0011880000 15510997 96830484 509673472 3.8760983944 4.5117239952 4.9807653427 767 30.6400000000 0.0130180335 0.0110002754 0.0160688832 0.0134022237 0.0063070000 0.0004990000 0.0028380000 0.0000060000 0.0000070000 0.0011960000 15513773 96830484 509673472 3.8790714741 4.5088539124 4.9825816154 768 30.6800000000 0.0130972471 0.0110030058 0.0160688832 0.0134093863 0.0100840000 0.0006500000 0.0030980000 0.0000030000 0.0000160000 0.0014160000 15516549 96830484 509673472 3.8822848797 4.5080695152 4.9844250679 769 30.7200000000 0.0131288674 0.0110057703 0.0160688832 0.0134629806 0.0074040000 0.0005290000 0.0028760000 0.0000080000 0.0000070000 0.0018460000 15519325 96830484 509673472 3.8890082836 4.5058631897 4.9881629944 770 30.7600000000 0.0132104298 0.0110086335 0.0160688832 0.0134917723 0.0053120000 0.0004840000 0.0023430000 0.0000010000 0.0000050000 0.0009390000 15522101 96830484 509673472 3.8932757378 4.5012316704 4.9896926880 771 30.8000000000 0.0133083379 0.0110116162 0.0160688832 0.0135128886 0.0059340000 0.0004650000 0.0029220000 0.0000040000 0.0000030000 0.0011850000 15524877 96830484 509673472 3.8968622684 4.4990048409 4.9910387993 772 30.8400000000 0.0133683123 0.0110146690 0.0160688832 0.0135341841 0.0101970000 0.0006420000 0.0032730000 0.0000020000 0.0000150000 0.0013820000 15527653 96830484 509673472 3.8990941048 4.4979429245 4.9919867516 773 30.8800000000 0.0134184286 0.0110177786 0.0160688832 0.0135576265 0.0074200000 0.0005280000 0.0028820000 0.0000080000 0.0000080000 0.0018460000 15530429 96830484 509673472 3.9029901028 4.4947409630 4.9936556816 774 30.9200000000 0.0134197492 0.0110208819 0.0160688832 0.0135778109 0.0057530000 0.0004920000 0.0028190000 0.0000010000 0.0000050000 0.0009220000 15533205 96830484 509673472 3.9066994190 4.4909038544 4.9948468208 775 30.9600000000 0.0134734511 0.0110240465 0.0160688832 0.0135966691 0.0054560000 0.0004670000 0.0024700000 0.0000040000 0.0000040000 0.0011650000 15535981 96830484 509673472 3.9098670483 4.4889645576 4.9958615303 776 31.0000000000 0.0135806054 0.0110273411 0.0160688832 0.0136187169 0.0104000000 0.0006440000 0.0031140000 0.0000020000 0.0000480000 0.0013450000 15538757 96830484 509673472 3.9139952660 4.4862837791 4.9975380898 777 31.0400000000 0.0134804565 0.0110304982 0.0160688832 0.0136296324 0.0075980000 0.0005530000 0.0030470000 0.0000080000 0.0000070000 0.0018620000 15541533 96830484 509673472 3.9174511433 4.4841356277 4.9991145134 778 31.0800000000 0.0137178963 0.0110339525 0.0160688832 0.0136352339 0.0058890000 0.0004830000 0.0029720000 0.0000010000 0.0000040000 0.0008940000 15544309 96830484 509673472 3.9203686714 4.4807662964 5.0006909370 779 31.1200000000 0.0134693393 0.0110370788 0.0160688832 0.0136342806 0.0100500000 0.0006500000 0.0031170000 0.0000150000 0.0000140000 0.0015750000 15547085 96830484 509673472 3.9237241745 4.4771323204 5.0027718544 780 31.1600000000 0.0136719486 0.0110404568 0.0160688832 0.0136308749 0.0071710000 0.0005630000 0.0029630000 0.0000010000 0.0000120000 0.0009950000 15549861 96830484 509673472 3.9265537262 4.4744367599 5.0046939850 781 31.2000000000 0.0137232421 0.0110438919 0.0160688832 0.0136262076 0.0070100000 0.0005070000 0.0029890000 0.0000050000 0.0000050000 0.0017150000 15552637 96830484 509673472 3.9286203384 4.4707784653 5.0063767433 782 31.2400000000 0.0136501240 0.0110472246 0.0160688832 0.0136229765 0.0072300000 0.0005610000 0.0029700000 0.0000010000 0.0000080000 0.0009950000 15555413 96830484 509673472 3.9317357540 4.4666419029 5.0086941719 783 31.2800000000 0.0136431614 0.0110505400 0.0160688832 0.0136179866 0.0064590000 0.0005030000 0.0028450000 0.0000070000 0.0000060000 0.0011950000 15558189 96830484 509673472 3.9342834949 4.4625725746 5.0107412338 784 31.3200000000 0.0135136619 0.0110536818 0.0160688832 0.0136133386 0.0075950000 0.0005580000 0.0029820000 0.0000010000 0.0000110000 0.0010990000 15560965 96830484 509673472 3.9366559982 4.4574346542 5.0127034187 785 31.3600000000 0.0135780852 0.0110568976 0.0160688832 0.0136081252 0.0073540000 0.0004990000 0.0033170000 0.0000060000 0.0000050000 0.0017210000 15563741 96830484 509673472 3.9385759830 4.4530081749 5.0144705772 786 31.4000000000 0.0136595415 0.0110602088 0.0160688832 0.0136013088 0.0101620000 0.0006490000 0.0037890000 0.0000010000 0.0000160000 0.0013100000 15566517 96830484 509673472 3.9401776791 4.4495778084 5.0159301758 787 31.4400000000 0.0137451626 0.0110636204 0.0160688832 0.0135939811 0.0069080000 0.0005270000 0.0030560000 0.0000070000 0.0000060000 0.0011720000 15569293 96830484 509673472 3.9416506290 4.4433078766 5.0173926353 788 31.4800000000 0.0137098487 0.0110669786 0.0160688832 0.0135907001 0.0057630000 0.0004850000 0.0028240000 0.0000000000 0.0000050000 0.0008910000 15572069 96830484 509673472 3.9437763691 4.4384284019 5.0193796158 789 31.5200000000 0.0135691250 0.0110701499 0.0160688832 0.0135893590 0.0103000000 0.0006460000 0.0032930000 0.0000160000 0.0000160000 0.0022780000 15574845 96830484 509673472 3.9452257156 4.4336700439 5.0210170746 790 31.5600000000 0.0136026628 0.0110733556 0.0160688832 0.0135883041 0.0066410000 0.0005230000 0.0030300000 0.0000010000 0.0000070000 0.0009350000 15577621 96830484 509673472 3.9466359615 4.4269518852 5.0227274895 791 31.6000000000 0.0135557223 0.0110764939 0.0160688832 0.0136130398 0.0060320000 0.0004840000 0.0029360000 0.0000050000 0.0000050000 0.0011360000 15580397 96830484 509673472 3.9478409290 4.4181771278 5.0255045891 792 31.6400000000 0.0136932004 0.0110797978 0.0160688832 0.0136104323 0.0080600000 0.0005590000 0.0031380000 0.0000010000 0.0000100000 0.0010850000 15583173 96830484 509673472 3.9483733177 4.4141278267 5.0274944305 793 31.6800000000 0.0134214507 0.0110827507 0.0160688832 0.0136066309 0.0070870000 0.0005070000 0.0030060000 0.0000060000 0.0000050000 0.0016900000 15585949 96830484 509673472 3.9492499828 4.4072179794 5.0293951035 794 31.7200000000 0.0135402521 0.0110858458 0.0160688832 0.0136016351 0.0057810000 0.0004780000 0.0029470000 0.0000000000 0.0000040000 0.0008890000 15588725 96830484 509673472 3.9494619370 4.4059596062 5.0310010910 795 31.7600000000 0.0134038981 0.0110887616 0.0160688832 0.0135965905 0.0094440000 0.0006350000 0.0032800000 0.0000170000 0.0000140000 0.0015500000 15591501 96830484 509673472 3.9492352009 4.4043750763 5.0325818062 796 31.8000000000 0.0133431852 0.0110915938 0.0160688832 0.0135935786 0.0066840000 0.0005220000 0.0030470000 0.0000010000 0.0000060000 0.0009170000 15594277 96830484 509673472 3.9496545792 4.3990445137 5.0347838402 797 31.8400000000 0.0131440982 0.0110941690 0.0160688832 0.0135942117 0.0094220000 0.0006480000 0.0032890000 0.0000150000 0.0000300000 0.0019500000 15597053 96830484 509673472 3.9497449398 4.3930754662 5.0373482704 798 31.8800000000 0.0130525306 0.0110966231 0.0160688832 0.0136616443 0.0059360000 0.0005000000 0.0025470000 0.0000010000 0.0000060000 0.0009260000 15599829 96830484 509673472 3.9510581493 4.3748669624 5.0435724258 799 31.9200000000 0.0130439112 0.0110990603 0.0160688832 0.0136766404 0.0081420000 0.0005610000 0.0031240000 0.0000100000 0.0000090000 0.0013360000 15602605 96830484 509673472 3.9512765408 4.3665404320 5.0462417603 800 31.9600000000 0.0129062822 0.0111013193 0.0160688832 0.0136828817 0.0072030000 0.0005070000 0.0038880000 0.0000010000 0.0000050000 0.0009110000 15605381 96830484 509673472 3.9507451057 4.3620829582 5.0484843254 801 32.0000000000 0.0128278658 0.0111034748 0.0160688832 0.0136775741 0.0098550000 0.0006630000 0.0037300000 0.0000120000 0.0000090000 0.0019970000 15608157 96830484 509673472 3.9503710270 4.3580722809 5.0514645576 802 32.0400000000 0.0128498906 0.0111056524 0.0160688832 0.0136691241 0.0067820000 0.0005130000 0.0034600000 0.0000000000 0.0000060000 0.0009390000 15610933 96830484 509673472 3.9493167400 4.3501257896 5.0540404320 803 32.0800000000 0.0129327942 0.0111079278 0.0160688832 0.0136608031 0.0059410000 0.0004720000 0.0029220000 0.0000040000 0.0000040000 0.0011220000 15613709 96830484 509673472 3.9486460686 4.3408713341 5.0571513176 804 32.1199999990 0.0130081140 0.0111102912 0.0160688832 0.0136549357 0.0106260000 0.0006460000 0.0042110000 0.0000020000 0.0000150000 0.0013050000 15616485 96830484 509673472 3.9470150471 4.3258099556 5.0639228821 805 32.1600000000 0.0139407953 0.0111138073 0.0160688832 0.0136475297 0.0073330000 0.0005280000 0.0028670000 0.0000060000 0.0000060000 0.0016860000 15619261 96830484 509673472 3.9461019039 4.3226652145 5.0670289993 806 32.2000000000 0.0139652975 0.0111173452 0.0160688832 0.0136390607 0.0063880000 0.0004900000 0.0033960000 0.0000000000 0.0000040000 0.0008770000 15622037 96830484 509673472 3.9445507526 4.3174591064 5.0703310966 807 32.2400000000 0.0135230413 0.0111203262 0.0160688832 0.0136310659 0.0066940000 0.0004620000 0.0038260000 0.0000030000 0.0000030000 0.0011130000 15624813 96830484 509673472 3.9431927204 4.3085818291 5.0738449097 808 32.2800000000 0.0140228951 0.0111239185 0.0160688832 0.0136233141 0.0066820000 0.0004660000 0.0038140000 0.0000000000 0.0000030000 0.0008770000 15627589 96830484 509673472 3.9413826466 4.3030405045 5.0774817467 809 32.3200000000 0.0140550397 0.0111275416 0.0160688832 0.0136152967 0.0073620000 0.0005310000 0.0038200000 0.0000040000 0.0000030000 0.0016260000 15630365 96830484 509673472 3.9403324127 4.2892842293 5.0822353363 810 32.3600000000 0.0154301524 0.0111328535 0.0160688832 0.0136070666 0.0081630000 0.0004660000 0.0055760000 0.0000000000 0.0000030000 0.0008640000 15633141 96830484 509673472 3.9393105507 4.2789216042 5.0864505768 811 32.4000000000 0.0158879980 0.0111387168 0.0160688832 0.0135994967 0.0071040000 0.0004610000 0.0042550000 0.0000030000 0.0000030000 0.0011070000 15635917 96830484 509673472 3.9372770786 4.2759313583 5.0902390480 812 32.4399999990 0.0163435973 0.0111451268 0.0163435973 0.0135932100 0.0050360000 0.0004610000 0.0024730000 0.0000010000 0.0000040000 0.0008560000 15638693 96830484 509673472 3.9354424477 4.2699704170 5.0945611000 813 32.4800000000 0.0164686441 0.0111516748 0.0164686441 0.0135860358 0.0089080000 0.0004580000 0.0056030000 0.0000030000 0.0000030000 0.0016020000 15641469 96830484 509673472 3.9340181351 4.2605481148 5.0993838310 814 32.5200000000 0.0162827615 0.0111579783 0.0164686441 0.0135781857 0.0080100000 0.0004580000 0.0054620000 0.0000000000 0.0000040000 0.0008530000 15644245 96830484 509673472 3.9329333305 4.2492117882 5.1043744087 815 32.5600000000 0.0169916190 0.0111651362 0.0169916190 0.0135710716 0.0083930000 0.0004590000 0.0056100000 0.0000040000 0.0000030000 0.0011100000 15647021 96830484 509673472 3.9317390919 4.2400984764 5.1092195511 816 32.6000000000 0.0168654639 0.0111721218 0.0169916190 0.0135630522 0.0058500000 0.0004540000 0.0033420000 0.0000000000 0.0000030000 0.0008520000 15649797 96830484 509673472 3.9305107594 4.2329268456 5.1143169403 817 32.6400000000 0.0159652736 0.0111779886 0.0169916190 0.0135573792 0.0066450000 0.0004620000 0.0033600000 0.0000030000 0.0000030000 0.0016010000 15652573 96830484 509673472 3.9296455383 4.2190999985 5.1211891174 818 32.6800000000 0.0165108722 0.0111845080 0.0169916190 0.0135490971 0.0124510000 0.0006470000 0.0061370000 0.0000020000 0.0000150000 0.0012650000 15655349 96830484 509673472 3.9286861420 4.2032332420 5.1277847290 819 32.7200000000 0.0172595717 0.0111919257 0.0172595717 0.0135421023 0.0074140000 0.0005220000 0.0034700000 0.0000060000 0.0000060000 0.0011470000 15658125 96830484 509673472 3.9271321297 4.1936826706 5.1327476501 820 32.7599999990 0.0167983398 0.0111987628 0.0172595717 0.0135339112 0.0109500000 0.0005750000 0.0058890000 0.0000010000 0.0000100000 0.0010570000 15660901 96830484 509673472 3.9254362583 4.1870603561 5.1369581223 821 32.7999999990 0.0166935641 0.0112054556 0.0172595717 0.0135258479 0.0079480000 0.0005010000 0.0038990000 0.0000060000 0.0000060000 0.0016070000 15663677 96830484 509673472 3.9245772362 4.1783623695 5.1417274475 822 32.8400000000 0.0167035721 0.0112121443 0.0172595717 0.0135187622 0.0061910000 0.0004830000 0.0033860000 0.0000010000 0.0000040000 0.0008550000 15666453 96830484 509673472 3.9246101379 4.1666789055 5.1471734047 823 32.8800000000 0.0165960547 0.0112186861 0.0172595717 0.0135123999 0.0057310000 0.0004590000 0.0029050000 0.0000040000 0.0000030000 0.0011070000 15669229 96830484 509673472 3.9246835709 4.1546001434 5.1527504921 824 32.9200000000 0.0163667593 0.0112249338 0.0172595717 0.0135050280 0.0099990000 0.0006610000 0.0035590000 0.0000030000 0.0000160000 0.0012610000 15672005 96830484 509673472 3.9248712063 4.1434841156 5.1583042145 825 32.9600000000 0.0157076512 0.0112303674 0.0172595717 0.0134973245 0.0079270000 0.0005280000 0.0034700000 0.0000060000 0.0000060000 0.0016670000 15674781 96830484 509673472 3.9245414734 4.1331758499 5.1629571915 826 33.0000000000 0.0152068837 0.0112351816 0.0172595717 0.0134909002 0.0084440000 0.0004890000 0.0056510000 0.0000010000 0.0000040000 0.0008470000 15677557 96830484 509673472 3.9244012833 4.1239233017 5.1678013802 827 33.0400000000 0.0153230289 0.0112401245 0.0172595717 0.0134837350 0.0054770000 0.0004590000 0.0027040000 0.0000170000 0.0000030000 0.0010790000 15680333 96830484 509673472 3.9244115353 4.1139678955 5.1723084450 828 33.0800000000 0.0152018573 0.0112449092 0.0172595717 0.0134773668 0.0053020000 0.0004580000 0.0027530000 0.0000010000 0.0000030000 0.0008400000 15683109 96830484 509673472 3.9243333340 4.1061573029 5.1759052277 829 33.1199999990 0.0150130354 0.0112494546 0.0172595717 0.0134744111 0.0119820000 0.0006490000 0.0037250000 0.0000160000 0.0000140000 0.0021830000 15685885 96830484 509673472 3.9245040417 4.0950388908 5.1801075935 830 33.1600000000 0.0149626527 0.0112539284 0.0172595717 0.0134706345 0.0068260000 0.0005290000 0.0030190000 0.0000000000 0.0000080000 0.0009450000 15688661 96830484 509673472 3.9249708652 4.0817956924 5.1850862503 831 33.2000000000 0.0138904713 0.0112571011 0.0172595717 0.0134645744 0.0061980000 0.0004880000 0.0029520000 0.0000050000 0.0000040000 0.0010860000 15691437 96830484 509673472 3.9255082607 4.0691304207 5.1893100739 832 33.2400000000 0.0147567047 0.0112613074 0.0172595717 0.0134607087 0.0059990000 0.0004640000 0.0033740000 0.0000000000 0.0000030000 0.0008430000 15694213 96830484 509673472 3.9253764153 4.0615310669 5.1922369003 833 33.2800000000 0.0148354536 0.0112655980 0.0172595717 0.0134558820 0.0066690000 0.0004570000 0.0033570000 0.0000030000 0.0000030000 0.0015940000 15696989 96830484 509673472 3.9257659912 4.0517058372 5.1957330704 834 33.3200000000 0.0146570904 0.0112696646 0.0172595717 0.0134484351 0.0054650000 0.0004580000 0.0029120000 0.0000000000 0.0000040000 0.0008440000 15699765 96830484 509673472 3.9260852337 4.0424656868 5.1986055374 835 33.3600000000 0.0145572200 0.0112736018 0.0172595717 0.0134408448 0.0111360000 0.0006460000 0.0032730000 0.0000160000 0.0000140000 0.0014580000 15702541 96830484 509673472 3.9270396233 4.0351519585 5.2009835243 836 33.4000000000 0.0144749740 0.0112774312 0.0172595717 0.0134372143 0.0078230000 0.0005550000 0.0039510000 0.0000010000 0.0000080000 0.0009310000 15705317 96830484 509673472 3.9286701679 4.0267438889 5.2040734291 837 33.4399999990 0.0148633318 0.0112817154 0.0172595717 0.0134359398 0.0076690000 0.0004900000 0.0038690000 0.0000050000 0.0000040000 0.0015960000 15708093 96830484 509673472 3.9296650887 4.0163598061 5.2074046135 838 33.4800000000 0.0148564288 0.0112859812 0.0172595717 0.0134312427 0.0068590000 0.0005250000 0.0037250000 0.0000000000 0.0000040000 0.0009790000 15710869 96830484 509673472 3.9305808544 4.0062608719 5.2101325989 839 33.5200000000 0.0146128843 0.0112899465 0.0172595717 0.0134235042 0.0077910000 0.0005810000 0.0031170000 0.0000100000 0.0000090000 0.0011520000 15713645 96830484 509673472 3.9313404560 3.9974923134 5.2121343613 840 33.5600000000 0.0148259001 0.0112941560 0.0172595717 0.0134158897 0.0055740000 0.0005020000 0.0023530000 0.0000000000 0.0000050000 0.0008460000 15716421 96830484 509673472 3.9325981140 3.9913961887 5.2135729790 841 33.6000000000 0.0144787775 0.0112979427 0.0172595717 0.0134128788 0.0109160000 0.0006500000 0.0042530000 0.0000160000 0.0000140000 0.0021250000 15719197 96830484 509673472 3.9338793755 3.9785144329 5.2169432640 842 33.6400000000 0.0144133978 0.0113016427 0.0172595717 0.0134054273 0.0080700000 0.0005330000 0.0046460000 0.0000000000 0.0000060000 0.0008730000 15721973 96830484 509673472 3.9355018139 3.9652988911 5.2209248543 843 33.6800000000 0.0143740401 0.0113052873 0.0172595717 0.0133987410 0.0063160000 0.0005040000 0.0028300000 0.0000060000 0.0000050000 0.0010820000 15724749 96830484 509673472 3.9360713959 3.9593451023 5.2213258743 844 33.7200000000 0.0138856927 0.0113083447 0.0172595717 0.0133974389 0.0079440000 0.0005570000 0.0035690000 0.0000010000 0.0000090000 0.0009280000 15727525 96830484 509673472 3.9374372959 3.9519758224 5.2222776413 845 33.7599999990 0.0137615008 0.0113112478 0.0172595717 0.0134010455 0.0082300000 0.0005720000 0.0029540000 0.0000110000 0.0000100000 0.0017740000 15730301 96830484 509673472 3.9380416870 3.9410924911 5.2239937782 846 33.7999999990 0.0135362232 0.0113138778 0.0172595717 0.0133987256 0.0065070000 0.0005010000 0.0032830000 0.0000010000 0.0000050000 0.0008330000 15733077 96830484 509673472 3.9392843246 3.9356572628 5.2245512009 847 33.8400000000 0.0135060782 0.0113164660 0.0172595717 0.0133989861 0.0057850000 0.0004650000 0.0029250000 0.0000040000 0.0000040000 0.0010670000 15735853 96830484 509673472 3.9398136139 3.9304506779 5.2246203423 848 33.8800000000 0.0134181017 0.0113189444 0.0172595717 0.0133960498 0.0102100000 0.0006460000 0.0031030000 0.0000010000 0.0000170000 0.0012040000 15738629 96830484 509673472 3.9407968521 3.9187231064 5.2275314331 849 33.9200000000 0.0134415682 0.0113214445 0.0172595717 0.0133890141 0.0074010000 0.0005350000 0.0028760000 0.0000090000 0.0000070000 0.0016080000 15741405 96830484 509673472 3.9401714802 3.9114248753 5.2282752991 850 33.9600000000 0.0131144850 0.0113235540 0.0172595717 0.0133831201 0.0059980000 0.0004950000 0.0029590000 0.0000010000 0.0000050000 0.0008250000 15744181 96830484 509673472 3.9390313625 3.9072930813 5.2272601128 851 34.0000000000 0.0129565001 0.0113254728 0.0172595717 0.0133768415 0.0089810000 0.0006530000 0.0030930000 0.0000150000 0.0000140000 0.0013100000 15746957 96830484 509673472 3.9382154942 3.9001007080 5.2277326584 852 34.0400000000 0.0128143150 0.0113272203 0.0172595717 0.0133698217 0.0066700000 0.0005320000 0.0030220000 0.0000000000 0.0000060000 0.0008610000 15749733 96830484 509673472 3.9376285076 3.8954086304 5.2272777557 853 34.0800000000 0.0127210831 0.0113288544 0.0172595717 0.0133672929 0.0082560000 0.0005590000 0.0030930000 0.0000080000 0.0000070000 0.0016920000 15752509 96830484 509673472 3.9374117851 3.8909657001 5.2268137932 854 34.1199999990 0.0126851834 0.0113304426 0.0172595717 0.0133670950 0.0060170000 0.0004970000 0.0028120000 0.0000000000 0.0000050000 0.0008360000 15755285 96830484 509673472 3.9371273518 3.8834183216 5.2271537781 855 34.1600000000 0.0127579533 0.0113321122 0.0172595717 0.0133607660 0.0077210000 0.0005600000 0.0031070000 0.0000090000 0.0000070000 0.0011480000 15758061 96830484 509673472 3.9375550747 3.8783280849 5.2275724411 856 34.2000000000 0.0126270335 0.0113336249 0.0172595717 0.0133545638 0.0086080000 0.0006460000 0.0030670000 0.0000010000 0.0000110000 0.0010100000 15760837 96830484 509673472 3.9379098415 3.8764097691 5.2263612747 857 34.2400000000 0.0125141209 0.0113350024 0.0172595717 0.0133522569 0.0072170000 0.0005270000 0.0029940000 0.0000080000 0.0000050000 0.0016020000 15763613 96830484 509673472 3.9389247894 3.8740358353 5.2252678871 858 34.2800000000 0.0124128954 0.0113362587 0.0172595717 0.0133533330 0.0072960000 0.0005740000 0.0029500000 0.0000010000 0.0000080000 0.0009080000 15766389 96830484 509673472 3.9401280880 3.8707478046 5.2245922089 859 34.3200000000 0.0124477288 0.0113375526 0.0172595717 0.0133563095 0.0076540000 0.0005640000 0.0029770000 0.0000110000 0.0000090000 0.0011350000 15769165 96830484 509673472 3.9402153492 3.8687527180 5.2227740288 860 34.3600000000 0.0124155739 0.0113388061 0.0172595717 0.0133548401 0.0061640000 0.0005020000 0.0028360000 0.0000000000 0.0000050000 0.0008380000 15771941 96830484 509673472 3.9411678314 3.8663477898 5.2214999199 861 34.4000000000 0.0125554716 0.0113402192 0.0172595717 0.0133516652 0.0088250000 0.0005600000 0.0029590000 0.0000110000 0.0000110000 0.0018230000 15774717 96830484 509673472 3.9432022572 3.8653094769 5.2208399773 862 34.4400000000 0.0125373779 0.0113416080 0.0172595717 0.0133612691 0.0070370000 0.0005620000 0.0024960000 0.0000010000 0.0000110000 0.0009930000 15777493 96830484 509673472 3.9447541237 3.8621275425 5.2202739716 863 34.4800000000 0.0126147354 0.0113430832 0.0172595717 0.0133709551 0.0064750000 0.0005050000 0.0028510000 0.0000050000 0.0000050000 0.0010680000 15780269 96830484 509673472 3.9461734295 3.8584070206 5.2199273109 864 34.5200000000 0.0126556372 0.0113446024 0.0172595717 0.0133761295 0.0052000000 0.0004680000 0.0023380000 0.0000000000 0.0000040000 0.0008290000 15783045 96830484 509673472 3.9463064671 3.8587925434 5.2175345421 865 34.5600000000 0.0126355169 0.0113460948 0.0172595717 0.0133813222 0.0113540000 0.0006490000 0.0032710000 0.0000160000 0.0000140000 0.0021320000 15785821 96830484 509673472 3.9476752281 3.8575732708 5.2161502838 866 34.6000000000 0.0126706352 0.0113476243 0.0172595717 0.0133813261 0.0072580000 0.0005610000 0.0027890000 0.0000000000 0.0000110000 0.0009130000 15788597 96830484 509673472 3.9487733841 3.8534259796 5.2156224251 867 34.6400000000 0.0129309436 0.0113494505 0.0172595717 0.0133759513 0.0064470000 0.0005070000 0.0028480000 0.0000060000 0.0000040000 0.0010630000 15791373 96830484 509673472 3.9494268894 3.8519077301 5.2146148682 868 34.6800000000 0.0129072266 0.0113512452 0.0172595717 0.0133700294 0.0057850000 0.0004770000 0.0029420000 0.0000000000 0.0000040000 0.0008310000 15794149 96830484 509673472 3.9504718781 3.8509607315 5.2130351067 869 34.7200000000 0.0129203731 0.0113530508 0.0172595717 0.0133642892 0.0086900000 0.0005620000 0.0029690000 0.0000110000 0.0000090000 0.0018410000 15796925 96830484 509673472 3.9514164925 3.8484790325 5.2123298645 870 34.7600000000 0.0128690088 0.0113547933 0.0172595717 0.0133579369 0.0090330000 0.0005080000 0.0057400000 0.0000000000 0.0000060000 0.0008410000 15799701 96830484 509673472 3.9526638985 3.8458640575 5.2117137909 871 34.8000000000 0.0128538366 0.0113565144 0.0172595717 0.0133534269 0.0078170000 0.0005640000 0.0029740000 0.0000110000 0.0000090000 0.0012460000 15802477 96830484 509673472 3.9533238411 3.8424236774 5.2109379768 872 34.8400000000 0.0128136063 0.0113581853 0.0172595717 0.0133483216 0.0112120000 0.0006740000 0.0031020000 0.0000020000 0.0000160000 0.0012170000 15805253 96830484 509673472 3.9535465240 3.8384141922 5.2109045982 873 34.8800000000 0.0127678309 0.0113598001 0.0172595717 0.0133411382 0.0119500000 0.0006540000 0.0030940000 0.0000180000 0.0000150000 0.0021400000 15808029 96830484 509673472 3.9542081356 3.8358347416 5.2104520798 874 34.9200000000 0.0126479752 0.0113612739 0.0172595717 0.0133343800 0.0080880000 0.0006690000 0.0025880000 0.0000010000 0.0000100000 0.0010240000 15810805 96830484 509673472 3.9544520378 3.8338904381 5.2093019485 875 34.9600000000 0.0125486124 0.0113626309 0.0172595717 0.0133281048 0.0074600000 0.0005080000 0.0037620000 0.0000080000 0.0000070000 0.0010720000 15813581 96830484 509673472 3.9541921616 3.8305583000 5.2086586952 876 35.0000000000 0.0125197368 0.0113639518 0.0172595717 0.0133206621 0.0053210000 0.0004830000 0.0023460000 0.0000010000 0.0000050000 0.0008370000 15816357 96830484 509673472 3.9552206993 3.8278799057 5.2086076736 877 35.0400000000 0.0123714041 0.0113651006 0.0172595717 0.0133131807 0.0088290000 0.0004680000 0.0053450000 0.0000040000 0.0000030000 0.0015600000 15819133 96830484 509673472 3.9548718929 3.8254511356 5.2073307037 878 35.0800000000 0.0123348609 0.0113662051 0.0172595717 0.0133059364 0.0055140000 0.0004650000 0.0027790000 0.0000010000 0.0000050000 0.0008280000 15821909 96830484 509673472 3.9547157288 3.8217189312 5.2064275742 879 35.1200000000 0.0124016637 0.0113673831 0.0172595717 0.0132984062 0.0052760000 0.0004640000 0.0023090000 0.0000040000 0.0000030000 0.0010520000 15824685 96830484 509673472 3.9552309513 3.8187091351 5.2059245110 880 35.1600000000 0.0123498114 0.0113684995 0.0172595717 0.0132918854 0.0050740000 0.0004640000 0.0023100000 0.0000010000 0.0000040000 0.0008360000 15827461 96830484 509673472 3.9549694061 3.8139979839 5.2034811974 881 35.2000000000 0.0121043380 0.0113693347 0.0172595717 0.0132849102 0.0064200000 0.0004670000 0.0029230000 0.0000040000 0.0000030000 0.0015610000 15830237 96830484 509673472 3.9548606873 3.8124170303 5.2017941475 882 35.2400000000 0.0120902071 0.0113701520 0.0172595717 0.0132792536 0.0048880000 0.0004640000 0.0021240000 0.0000000000 0.0000030000 0.0008290000 15833013 96830484 509673472 3.9548163414 3.8096487522 5.2005758286 883 35.2800000000 0.0121889450 0.0113710793 0.0172595717 0.0132755352 0.0052200000 0.0004670000 0.0022600000 0.0000040000 0.0000040000 0.0010540000 15835789 96830484 509673472 3.9542894363 3.8070304394 5.1991162300 884 35.3200000000 0.0120754298 0.0113718761 0.0172595717 0.0132749498 0.0111350000 0.0006560000 0.0031180000 0.0000020000 0.0000150000 0.0012140000 15838565 96830484 509673472 3.9538078308 3.8048326969 5.1971955299 885 35.3600000000 0.0119951190 0.0113725803 0.0172595717 0.0132763057 0.0091320000 0.0006500000 0.0029880000 0.0000110000 0.0000100000 0.0018480000 15841341 96830484 509673472 3.9535033703 3.8026921749 5.1956992149 886 35.4000000000 0.0119333901 0.0113732133 0.0172595717 0.0132788753 0.0073060000 0.0005580000 0.0026660000 0.0000010000 0.0000120000 0.0009750000 15844117 96830484 509673472 3.9524722099 3.8008947372 5.1940736771 887 35.4400000000 0.0119094532 0.0113738178 0.0172595717 0.0132820212 0.0069740000 0.0005060000 0.0032990000 0.0000060000 0.0000060000 0.0010650000 15846893 96830484 509673472 3.9520351887 3.7999837399 5.1924548149 888 35.4800000000 0.0118545229 0.0113743591 0.0172595717 0.0132840557 0.0057260000 0.0004740000 0.0027980000 0.0000010000 0.0000040000 0.0008260000 15849669 96830484 509673472 3.9505367279 3.7976799011 5.1906418800 889 35.5200000000 0.0117927343 0.0113748298 0.0172595717 0.0132924740 0.0061170000 0.0005300000 0.0023140000 0.0000050000 0.0000030000 0.0015770000 15852445 96830484 509673472 3.9500443935 3.7961890697 5.1891059875 890 35.5600000000 0.0117353620 0.0113752349 0.0172595717 0.0132987200 0.0048480000 0.0004650000 0.0021770000 0.0000010000 0.0000040000 0.0008200000 15855221 96830484 509673472 3.9491231441 3.7958054543 5.1874337196 891 35.6000000000 0.0116417874 0.0113755340 0.0172595717 0.0133029945 0.0087160000 0.0005810000 0.0029840000 0.0000120000 0.0000100000 0.0012390000 15857997 96830484 509673472 3.9473912716 3.7925097942 5.1860918999 892 35.6400000000 0.0116648395 0.0113758583 0.0172595717 0.0133143174 0.0085330000 0.0006790000 0.0026480000 0.0000030000 0.0000160000 0.0010320000 15860773 96830484 509673472 3.9461202621 3.7914941311 5.1842598915 893 35.6800000000 0.0116224037 0.0113761344 0.0172595717 0.0133253014 0.0067200000 0.0005290000 0.0022410000 0.0000070000 0.0000060000 0.0016110000 15863549 96830484 509673472 3.9444632530 3.7909238338 5.1824674606 894 35.7200000000 0.0114902016 0.0113762620 0.0172595717 0.0133362104 0.0075110000 0.0005610000 0.0029670000 0.0000010000 0.0000080000 0.0009190000 15866325 96830484 509673472 3.9429166317 3.7884132862 5.1812787056 895 35.7600000000 0.0114809824 0.0113763790 0.0172595717 0.0133525050 0.0073660000 0.0005600000 0.0023460000 0.0000100000 0.0000100000 0.0012410000 15869101 96830484 509673472 3.9413361549 3.7861785889 5.1801853180 896 35.8000000000 0.0114252707 0.0113764336 0.0172595717 0.0133755165 0.0059560000 0.0005030000 0.0023730000 0.0000010000 0.0000060000 0.0008340000 15871877 96830484 509673472 3.9404277802 3.7860920429 5.1787090302 897 35.8400000000 0.0114020715 0.0113764622 0.0172595717 0.0133905978 0.0062480000 0.0004750000 0.0023510000 0.0000050000 0.0000040000 0.0015580000 15874653 96830484 509673472 3.9399912357 3.7863004208 5.1780028343 898 35.8800000000 0.0114340009 0.0113765263 0.0172595717 0.0133996336 0.0104470000 0.0006450000 0.0026450000 0.0000020000 0.0000150000 0.0011980000 15877429 96830484 509673472 3.9386687279 3.7855801582 5.1767792702 899 35.9200000000 0.0114124250 0.0113765662 0.0172595717 0.0134076918 0.0070740000 0.0005290000 0.0028970000 0.0000090000 0.0000080000 0.0011020000 15880205 96830484 509673472 3.9386594296 3.7851943970 5.1769146919 900 35.9600000000 0.0114176096 0.0113766118 0.0172595717 0.0134117476 0.0055210000 0.0004900000 0.0023880000 0.0000010000 0.0000050000 0.0008210000 15882981 96830484 509673472 3.9378225803 3.7847497463 5.1762108803 901 36.0000000000 0.0113834012 0.0113766193 0.0172595717 0.0134180272 0.0058540000 0.0004670000 0.0023490000 0.0000050000 0.0000040000 0.0015300000 15885757 96830484 509673472 3.9369781017 3.7840485573 5.1752991676 902 36.0400000000 0.0113860825 0.0113766298 0.0172595717 0.0134276627 0.0106750000 0.0006450000 0.0026450000 0.0000010000 0.0000160000 0.0011930000 15888533 96830484 509673472 3.9359173775 3.7837104797 5.1746459007 903 36.0800000000 0.0114064701 0.0113766629 0.0172595717 0.0134378710 0.0066880000 0.0005330000 0.0022890000 0.0000080000 0.0000080000 0.0011280000 15891309 96830484 509673472 3.9341528416 3.7834057808 5.1731243134 904 36.1200000000 0.0114260884 0.0113767175 0.0172595717 0.0134542447 0.0055500000 0.0004870000 0.0023870000 0.0000010000 0.0000050000 0.0008180000 15894085 96830484 509673472 3.9332396984 3.7823352814 5.1726369858 905 36.1600000000 0.0114618586 0.0113768116 0.0172595717 0.0134770578 0.0058800000 0.0004700000 0.0023490000 0.0000040000 0.0000040000 0.0015210000 15896861 96830484 509673472 3.9318575859 3.7820279598 5.1714968681 906 36.2000000000 0.0114309033 0.0113768713 0.0172595717 0.0135002519 0.0093820000 0.0006480000 0.0026380000 0.0000020000 0.0000150000 0.0011880000 15899637 96830484 509673472 3.9307465553 3.7820537090 5.1707277298 907 36.2400000000 0.0114246327 0.0113769240 0.0172595717 0.0135209066 0.0065980000 0.0005200000 0.0024300000 0.0000070000 0.0000060000 0.0010870000 15902413 96830484 509673472 3.9296016693 3.7806167603 5.1702971458 908 36.2800000000 0.0114662005 0.0113770223 0.0172595717 0.0135379246 0.0089910000 0.0006450000 0.0031280000 0.0000020000 0.0000170000 0.0010000000 15905189 96830484 509673472 3.9281499386 3.7809910774 5.1696357727 909 36.3200000000 0.0113938749 0.0113770408 0.0172595717 0.0135470292 0.0065810000 0.0005000000 0.0022410000 0.0000070000 0.0000060000 0.0015790000 15907965 96830484 509673472 3.9266488552 3.7806448936 5.1689815521 910 36.3600000000 0.0113892891 0.0113770543 0.0172595717 0.0135543673 0.0070840000 0.0005590000 0.0025030000 0.0000010000 0.0000080000 0.0009010000 15910741 96830484 509673472 3.9249541759 3.7801113129 5.1683974266 911 36.4000000000 0.0113977129 0.0113770770 0.0172595717 0.0135609947 0.0063780000 0.0004860000 0.0026740000 0.0000060000 0.0000050000 0.0010590000 15913517 96830484 509673472 3.9238831997 3.7790045738 5.1681556702 912 36.4400000000 0.0114492681 0.0113771561 0.0172595717 0.0135672410 0.0105940000 0.0006450000 0.0030940000 0.0000020000 0.0000160000 0.0011840000 15916293 96830484 509673472 3.9221992493 3.7777292728 5.1679806709 913 36.4800000000 0.0115409438 0.0113773355 0.0172595717 0.0136444493 0.0071110000 0.0005290000 0.0024160000 0.0000090000 0.0000070000 0.0015680000 15919069 96830484 509673472 3.9188604355 3.7776648998 5.1666274071 914 36.5200000000 0.0113872597 0.0113773464 0.0172595717 0.0136630646 0.0058060000 0.0004830000 0.0026700000 0.0000000000 0.0000050000 0.0008030000 15921845 96830484 509673472 3.9178195000 3.7770226002 5.1665577888 915 36.5600000000 0.0114053013 0.0113773769 0.0172595717 0.0136804134 0.0059480000 0.0004750000 0.0029430000 0.0000050000 0.0000040000 0.0010400000 15924621 96830484 509673472 3.9160535336 3.7768123150 5.1664514542 916 36.6000000000 0.0113954050 0.0113773966 0.0172595717 0.0136966655 0.0054430000 0.0004620000 0.0027770000 0.0000010000 0.0000040000 0.0007920000 15927397 96830484 509673472 3.9143304825 3.7767155170 5.1660985947 917 36.6400000000 0.0113897165 0.0113774101 0.0172595717 0.0137083163 0.0117640000 0.0006490000 0.0031080000 0.0000160000 0.0000140000 0.0020270000 15930173 96830484 509673472 3.9124915600 3.7763402462 5.1658368111 918 36.6800000000 0.0114222281 0.0113774589 0.0172595717 0.0137206371 0.0073920000 0.0005920000 0.0029340000 0.0000010000 0.0000080000 0.0008820000 15932949 96830484 509673472 3.9109792709 3.7758533955 5.1657342911 919 36.7200000000 0.0113910399 0.0113774737 0.0172595717 0.0137372433 0.0057860000 0.0005040000 0.0023610000 0.0000050000 0.0000050000 0.0010270000 15935725 96830484 509673472 3.9094395638 3.7753047943 5.1657142639 920 36.7600000000 0.0114227906 0.0113775229 0.0172595717 0.0137549756 0.0056940000 0.0004730000 0.0027930000 0.0000000000 0.0000040000 0.0007870000 15938501 96830484 509673472 3.9078052044 3.7755875587 5.1652855873 921 36.8000000000 0.0113695608 0.0113775143 0.0172595717 0.0137641928 0.0114970000 0.0006510000 0.0026280000 0.0000150000 0.0000140000 0.0020120000 15941277 96830484 509673472 3.9062216282 3.7748703957 5.1655015945 922 36.8400000000 0.0114391148 0.0113775811 0.0172595717 0.0137716792 0.0070100000 0.0005320000 0.0029210000 0.0000010000 0.0000080000 0.0008760000 15944053 96830484 509673472 3.9045143127 3.7741887569 5.1659846306 923 36.8800000000 0.0114693027 0.0113776805 0.0172595717 0.0137774230 0.0062320000 0.0004910000 0.0028280000 0.0000060000 0.0000050000 0.0010230000 15946829 96830484 509673472 3.9026930332 3.7738339901 5.1667122841 924 36.9200000000 0.0114978636 0.0113778105 0.0172595717 0.0137801840 0.0056650000 0.0004690000 0.0027830000 0.0000010000 0.0000040000 0.0007800000 15949605 96830484 509673472 3.9008846283 3.7733430862 5.1668777466 925 36.9600000000 0.0114842709 0.0113779256 0.0172595717 0.0137835046 0.0118730000 0.0006580000 0.0030910000 0.0000150000 0.0000150000 0.0020350000 15952381 96830484 509673472 3.8991460800 3.7732865810 5.1670656204 926 37.0000000000 0.0114355078 0.0113779878 0.0172595717 0.0137876140 0.0068620000 0.0005260000 0.0028860000 0.0000010000 0.0000090000 0.0008720000 15955157 96830484 509673472 3.8975737095 3.7731029987 5.1670479774 927 37.0400000000 0.0112969885 0.0113779004 0.0172595717 0.0137936445 0.0057810000 0.0004920000 0.0023740000 0.0000050000 0.0000050000 0.0010200000 15957933 96830484 509673472 3.8963048458 3.7722365856 5.1674432755 928 37.0800000000 0.0111159347 0.0113776181 0.0172595717 0.0138051067 0.0059250000 0.0004750000 0.0029410000 0.0000010000 0.0000040000 0.0007800000 15960709 96830484 509673472 3.8946027756 3.7725276947 5.1674661636 929 37.1200000000 0.0109449066 0.0113771523 0.0172595717 0.0138161083 0.0106710000 0.0006530000 0.0030900000 0.0000180000 0.0000140000 0.0019880000 15963485 96830484 509673472 3.8929889202 3.7731151581 5.1668748856 930 37.1600000000 0.0108168693 0.0113765499 0.0172595717 0.0138244359 0.0068300000 0.0005320000 0.0028860000 0.0000010000 0.0000070000 0.0008010000 15966261 96830484 509673472 3.8912122250 3.7734029293 5.1662201881 931 37.2000000000 0.0106838392 0.0113758058 0.0172595717 0.0138316241 0.0060760000 0.0004860000 0.0028120000 0.0000050000 0.0000040000 0.0009980000 15969037 96830484 509673472 3.8895599842 3.7729070187 5.1659679413 932 37.2400000000 0.0105691236 0.0113749403 0.0172595717 0.0138483238 0.0080260000 0.0005640000 0.0029500000 0.0000010000 0.0000100000 0.0009360000 15971813 96830484 509673472 3.8877100945 3.7725455761 5.1651248932 933 37.2800000000 0.0103482753 0.0113738399 0.0172595717 0.0138747727 0.0069720000 0.0004990000 0.0028500000 0.0000060000 0.0000060000 0.0014410000 15974589 96830484 509673472 3.8858892918 3.7729146481 5.1636300087 934 37.3200000000 0.0102339638 0.0113726195 0.0172595717 0.0139003699 0.0059110000 0.0004740000 0.0028020000 0.0000010000 0.0000050000 0.0007550000 15977365 96830484 509673472 3.8838846684 3.7741348743 5.1628308296 935 37.3600000000 0.0101382434 0.0113712993 0.0172595717 0.0139152908 0.0061720000 0.0004760000 0.0027960000 0.0000050000 0.0000040000 0.0010100000 15980141 96830484 509673472 3.8820765018 3.7745494843 5.1612906456 936 37.4000000000 0.0101511478 0.0113699957 0.0172595717 0.0139266520 0.0114260000 0.0006480000 0.0032600000 0.0000010000 0.0000160000 0.0011040000 15982917 96830484 509673472 3.8805320263 3.7748093605 5.1606674194 937 37.4400000000 0.0101375617 0.0113686804 0.0172595717 0.0139344390 0.0077140000 0.0005580000 0.0028910000 0.0000090000 0.0000080000 0.0015260000 15985693 96830484 509673472 3.8789784908 3.7763588428 5.1600103378 938 37.4800000000 0.0101679424 0.0113674003 0.0172595717 0.0139379015 0.0059560000 0.0004910000 0.0028190000 0.0000010000 0.0000060000 0.0007470000 15988469 96830484 509673472 3.8776340485 3.7765161991 5.1596026421 939 37.5200000000 0.0102226101 0.0113661812 0.0172595717 0.0139421838 0.0058760000 0.0004700000 0.0027960000 0.0000040000 0.0000030000 0.0009810000 15991245 96830484 509673472 3.8762671947 3.7766468525 5.1591410637 940 37.5600000000 0.0102235377 0.0113649656 0.0172595717 0.0139441573 0.0096000000 0.0006520000 0.0026410000 0.0000020000 0.0000170000 0.0010980000 15994021 96830484 509673472 3.8748791218 3.7768809795 5.1586866379 941 37.6000000000 0.0102267209 0.0113637560 0.0172595717 0.0139455454 0.0074880000 0.0005300000 0.0028700000 0.0000060000 0.0000060000 0.0014360000 15996797 96830484 509673472 3.8734939098 3.7774007320 5.1573362350 942 37.6400000000 0.0102799088 0.0113626054 0.0172595717 0.0139470426 0.0059560000 0.0004830000 0.0027980000 0.0000010000 0.0000040000 0.0007820000 15999573 96830484 509673472 3.8721468449 3.7776761055 5.1560244560 943 37.6800000000 0.0102934334 0.0113614716 0.0172595717 0.0139481827 0.0085260000 0.0005610000 0.0029740000 0.0000110000 0.0000100000 0.0012220000 16002349 96830484 509673472 3.8710284233 3.7772810459 5.1551971436 944 37.7200000000 0.0103064980 0.0113603540 0.0172595717 0.0139504624 0.0065240000 0.0005000000 0.0030030000 0.0000010000 0.0000050000 0.0007840000 16005125 96830484 509673472 3.8698430061 3.7769227028 5.1548895836 945 37.7600000000 0.0103086252 0.0113592411 0.0172595717 0.0139535526 0.0098540000 0.0006510000 0.0033000000 0.0000300000 0.0000100000 0.0017210000 16007901 96830484 509673472 3.8683836460 3.7772252560 5.1561512947 946 37.8000000000 0.0103667369 0.0113581919 0.0172595717 0.0139566697 0.0066060000 0.0005070000 0.0030050000 0.0000010000 0.0000070000 0.0008100000 16010677 96830484 509673472 3.8671257496 3.7768406868 5.1556091309 947 37.8400000000 0.0103250807 0.0113571010 0.0172595717 0.0139584931 0.0060090000 0.0004760000 0.0028120000 0.0000040000 0.0000040000 0.0010150000 16013453 96830484 509673472 3.8655853271 3.7771637440 5.1552014351 948 37.8800000000 0.0104300203 0.0113561231 0.0172595717 0.0139582044 0.0100790000 0.0006520000 0.0031310000 0.0000010000 0.0000150000 0.0011150000 16016229 96830484 509673472 3.8642382622 3.7772541046 5.1567916870 949 37.9200000000 0.0105332974 0.0113552560 0.0172595717 0.0139594115 0.0076090000 0.0005310000 0.0029010000 0.0000070000 0.0000060000 0.0015350000 16019005 96830484 509673472 3.8628776073 3.7831602097 5.1656737328 950 37.9600000000 0.0107699176 0.0113546399 0.0172595717 0.0139600637 0.0059200000 0.0004850000 0.0028160000 0.0000000000 0.0000050000 0.0007580000 16021781 96830484 509673472 3.8610670567 3.7878046036 5.1752038002 951 38.0000000000 0.0107927192 0.0113540490 0.0172595717 0.0139624856 0.0090800000 0.0005820000 0.0036070000 0.0000110000 0.0000100000 0.0012150000 16024557 96830484 509673472 3.8597574234 3.7896049023 5.1785149574 952 38.0400000000 0.0108774509 0.0113535484 0.0172595717 0.0139634600 0.0069890000 0.0005220000 0.0034610000 0.0000000000 0.0000050000 0.0007680000 16027333 96830484 509673472 3.8586871624 3.7905533314 5.1786303520 953 38.0800000000 0.0109186834 0.0113530921 0.0172595717 0.0139604265 0.0102200000 0.0006490000 0.0037610000 0.0000120000 0.0000090000 0.0017030000 16030109 96830484 509673472 3.8575420380 3.7906265259 5.1784324646 954 38.1200000000 0.0108060483 0.0113525186 0.0172595717 0.0139591152 0.0070160000 0.0005110000 0.0034590000 0.0000010000 0.0000070000 0.0007890000 16032885 96830484 509673472 3.8564836979 3.7908997536 5.1797819138 955 38.1600000000 0.0107647125 0.0113519031 0.0172595717 0.0139608015 0.0066610000 0.0004790000 0.0034000000 0.0000050000 0.0000040000 0.0010100000 16035661 96830484 509673472 3.8556823730 3.7902874947 5.1777920723 956 38.2000000000 0.0106558157 0.0113511750 0.0172595717 0.0139620802 0.0103050000 0.0005630000 0.0059150000 0.0000010000 0.0000080000 0.0008390000 16038437 96830484 509673472 3.8543906212 3.7908308506 5.1776804924 957 38.2400000000 0.0104753142 0.0113502598 0.0172595717 0.0139604622 0.0090320000 0.0005620000 0.0035770000 0.0000090000 0.0000070000 0.0015630000 16041213 96830484 509673472 3.8530716896 3.7911479473 5.1762833595 958 38.2800000000 0.0103432778 0.0113492087 0.0172595717 0.0139578006 0.0084390000 0.0005070000 0.0052410000 0.0000010000 0.0000060000 0.0007470000 16043989 96830484 509673472 3.8522357941 3.7892479897 5.1723170280 959 38.3200000000 0.0101199141 0.0113479268 0.0172595717 0.0139569483 0.0103720000 0.0005730000 0.0059100000 0.0000080000 0.0000070000 0.0011010000 16046765 96830484 509673472 3.8510296345 3.7889196873 5.1721286774 960 38.3600000000 0.0093370341 0.0113458321 0.0172595717 0.0139564842 0.0066430000 0.0004930000 0.0034460000 0.0000010000 0.0000050000 0.0007400000 16049541 96830484 509673472 3.8495626450 3.7903265953 5.1759924889 961 38.4000000000 0.0096566901 0.0113440744 0.0172595717 0.0139552063 0.0105920000 0.0005630000 0.0058310000 0.0000070000 0.0000050000 0.0014690000 16052317 96830484 509673472 3.8484525681 3.7898609638 5.1785635948 962 38.4400000000 0.0162156299 0.0113491384 0.0172595717 0.0139576357 0.0081830000 0.0004940000 0.0052650000 0.0000010000 0.0000040000 0.0006830000 16055093 96830484 509673472 3.8469839096 3.7897469997 5.1882729530 963 38.4800000000 0.0414216667 0.0113803664 0.0414216667 0.0139869993 0.0085310000 0.0004620000 0.0056770000 0.0000030000 0.0000030000 0.0009530000 16057869 96830484 509673472 3.8453831673 3.7886676788 5.2123956680 964 38.5200000000 0.0721528530 0.0114434084 0.0721528530 0.0140373391 0.0103120000 0.0005960000 0.0059270000 0.0000010000 0.0000080000 0.0007720000 16060645 96830484 509673472 3.8433895111 3.7903339863 5.2444639206 965 38.5600000000 0.1043329164 0.0115396670 0.1043329164 0.0140853046 0.0085320000 0.0005610000 0.0031360000 0.0000100000 0.0000100000 0.0014430000 16063421 96830484 509673472 3.8416709900 3.7906947136 5.2751359940 966 38.6000000000 0.1261360943 0.0116582968 0.1261360943 0.0141090654 0.0089410000 0.0005340000 0.0057630000 0.0000010000 0.0000050000 0.0006790000 16066197 96830484 509673472 3.8401899338 3.7910788059 5.2963519096 967 38.6400000000 0.1309161484 0.0117816245 0.1309161484 0.0141082610 0.0059110000 0.0004680000 0.0029440000 0.0000040000 0.0000030000 0.0009520000 16068973 96830484 509673472 3.8388035297 3.7920150757 5.3034324646 968 38.6800000000 0.1532768756 0.0119277972 0.1532768756 0.0141339210 0.0054380000 0.0004630000 0.0027810000 0.0000010000 0.0000030000 0.0006670000 16071749 96830484 509673472 3.8371953964 3.7908802032 5.3233928680 969 38.7200000000 0.2008054852 0.0121227175 0.2008054852 0.0142460765 0.0118240000 0.0006560000 0.0031040000 0.0000180000 0.0000140000 0.0018300000 16074525 96830484 509673472 3.8348250389 3.7924196720 5.3713512421 970 38.7600000000 0.2521639466 0.0123701826 0.2521639466 0.0143695670 0.0068840000 0.0005350000 0.0028880000 0.0000010000 0.0000090000 0.0007080000 16077301 96830484 509673472 3.8327505589 3.7929165363 5.4212236404 971 38.8000000000 0.3055055141 0.0126720728 0.3055055141 0.0145036171 0.0061800000 0.0004960000 0.0027520000 0.0000050000 0.0000050000 0.0009360000 16080077 96830484 509673472 3.8303730488 3.7925000191 5.4724020958 972 38.8400000000 0.3579495847 0.0130272966 0.3579495847 0.0146229409 0.0071400000 0.0005490000 0.0028860000 0.0000010000 0.0000090000 0.0007570000 16082853 96830484 509673472 3.8279228210 3.7935514450 5.5243744850 973 38.8800000000 0.4103031754 0.0134355965 0.4103031754 0.0147439158 0.0065270000 0.0004910000 0.0027550000 0.0000050000 0.0000050000 0.0012760000 16085629 96830484 509673472 3.8259520531 3.7935874462 5.5755138397 974 38.9200000000 0.4594154656 0.0138934814 0.4594154656 0.0148445946 0.0102790000 0.0006580000 0.0031190000 0.0000020000 0.0000150000 0.0010210000 16088405 96830484 509673472 3.8238344193 3.7945473194 5.6247992516 975 38.9600000000 0.5109578371 0.0144032910 0.5109578371 0.0149565777 0.0070070000 0.0005480000 0.0027250000 0.0000060000 0.0000060000 0.0009700000 16091181 96830484 509673472 3.8216941357 3.7954850197 5.6757826805 976 39.0000000000 0.5584700108 0.0149607364 0.5584700108 0.0150516701 0.0058850000 0.0004970000 0.0028070000 0.0000000000 0.0000040000 0.0006610000 16093957 96830484 509673472 3.8196480274 3.7947838306 5.7216429710 977 39.0400000000 0.6048418283 0.0155645042 0.6048418283 0.0151321680 0.0096310000 0.0006270000 0.0033710000 0.0000120000 0.0000100000 0.0015070000 16096733 96830484 509673472 3.8176777363 3.7957470417 5.7674927711 978 39.0800000000 0.6520205736 0.0162152773 0.6520205736 0.0152238006 0.0060270000 0.0005160000 0.0025220000 0.0000010000 0.0000050000 0.0006640000 16099509 96830484 509673472 3.8158717155 3.7958774567 5.8127064705 979 39.1200000000 0.7027806640 0.0169165698 0.7027806640 0.0153303836 0.0075290000 0.0005710000 0.0022620000 0.0000100000 0.0000090000 0.0011240000 16102285 96830484 509673472 3.8140501976 3.7948985100 5.8606514931 980 39.1600000000 0.7499216199 0.0176645341 0.7499216199 0.0154180004 0.0058780000 0.0005160000 0.0023830000 0.0000010000 0.0000070000 0.0006620000 16105061 96830484 509673472 3.8120956421 3.7954401970 5.9060459137 981 39.2000000000 0.7953104377 0.0184572415 0.7953104377 0.0155025091 0.0105520000 0.0006530000 0.0030240000 0.0000160000 0.0000150000 0.0017740000 16107837 96830484 509673472 3.8103945255 3.7954103947 5.9508180618 982 39.2400000000 0.8415718675 0.0192954437 0.8415718675 0.0155813596 0.0068710000 0.0005410000 0.0028900000 0.0000010000 0.0000060000 0.0006850000 16110613 96830484 509673472 3.8085956573 3.7957007885 5.9953227043 983 39.2800000000 0.8901376128 0.0201813462 0.8901376128 0.0156719089 0.0060740000 0.0004840000 0.0028000000 0.0000050000 0.0000040000 0.0009080000 16113389 96830484 509673472 3.8068997860 3.7963857651 6.0423598289 984 39.3200000000 0.8958982229 0.0210713024 0.8958982229 0.0156663977 0.0077850000 0.0005790000 0.0022650000 0.0000010000 0.0000110000 0.0008230000 16116165 96830484 509673472 3.8063256741 3.7967040539 6.0471906662 985 39.3600000000 0.9462540746 0.0220105743 0.9462540746 0.0157683161 0.0073330000 0.0005100000 0.0027800000 0.0000060000 0.0000060000 0.0012930000 16118941 96830484 509673472 3.8046514988 3.7972564697 6.0948901176 986 39.4000000000 0.9487032890 0.0229504249 0.9487032890 0.0157618254 0.0091180000 0.0006580000 0.0031120000 0.0000020000 0.0000160000 0.0008310000 16121717 96830484 509673472 3.8046426773 3.7976377010 6.0957322121 987 39.4400000000 0.9952431321 0.0239355239 0.9952431321 0.0158580681 0.0079660000 0.0005670000 0.0028320000 0.0000110000 0.0000100000 0.0010690000 16124493 96830484 509673472 3.8032932281 3.7977960110 6.1405706406 988 39.4800000000 1.0434871912 0.0249674588 1.0434871912 0.0159548156 0.0062410000 0.0005070000 0.0027730000 0.0000000000 0.0000060000 0.0006540000 16127269 96830484 509673472 3.8020896912 3.7979309559 6.1873226166 989 39.5200000000 1.0394769907 0.0259932520 1.0434871912 0.0159481681 0.0077100000 0.0005670000 0.0023280000 0.0000110000 0.0000100000 0.0013740000 16130045 96830484 509673472 3.8022158146 3.7979264259 6.1807179451 990 39.5600000000 1.0911593437 0.0270691774 1.0911593437 0.0160550946 0.0091930000 0.0006530000 0.0031320000 0.0000020000 0.0000160000 0.0008190000 16132821 96830484 509673472 3.8005647659 3.7989540100 6.2311463356 991 39.6000000000 1.0893138647 0.0281410691 1.0911593437 0.0160481023 0.0069730000 0.0005360000 0.0029960000 0.0000070000 0.0000060000 0.0009380000 16135597 96830484 509673472 3.8006241322 3.7990136147 6.2266263962 992 39.6400000000 1.1338769197 0.0292557222 1.1338769197 0.0161278595 0.0071340000 0.0005740000 0.0024640000 0.0000010000 0.0000080000 0.0007260000 16138373 96830484 509673472 3.7989618778 3.7999174595 6.2691383362 993 39.6800000000 1.1267907619 0.0303609941 1.1338769197 0.0161222256 0.0076740000 0.0005690000 0.0022600000 0.0000110000 0.0000090000 0.0013570000 16141149 96830484 509673472 3.7990286350 3.7998723984 6.2601785660 994 39.7200000000 1.1687214375 0.0315062259 1.1687214375 0.0161874741 0.0088520000 0.0006570000 0.0026340000 0.0000020000 0.0000160000 0.0009490000 16143925 96830484 509673472 3.7975633144 3.7999083996 6.2985486984 995 39.7600000000 1.1478080750 0.0326281373 1.1687214375 0.0162016988 0.0062920000 0.0005090000 0.0023490000 0.0000070000 0.0000060000 0.0009470000 16146701 96830484 509673472 3.7977399826 3.8014583588 6.2745156288 996 39.8000000000 1.1864478588 0.0337865909 1.1864478588 0.0162668496 0.0075860000 0.0005710000 0.0029570000 0.0000010000 0.0000080000 0.0007300000 16149477 96830484 509673472 3.7958464622 3.8037741184 6.3106775284 997 39.8400000000 1.2189277411 0.0349752981 1.2189277411 0.0163116487 0.0082870000 0.0005680000 0.0029650000 0.0000090000 0.0000070000 0.0013560000 16152253 96830484 509673472 3.7945876122 3.8052537441 6.3415689468 998 39.8800000000 1.2502720356 0.0361930304 1.2502720356 0.0163506174 0.0062070000 0.0005200000 0.0028400000 0.0000000000 0.0000050000 0.0006520000 16155029 96830484 509673472 3.7934412956 3.8067657948 6.3708162308 999 39.9200000000 1.2490960360 0.0374071475 1.2502720356 0.0163537057 0.0079700000 0.0005830000 0.0023260000 0.0000110000 0.0000090000 0.0010790000 16157805 96830484 509673472 3.7930152416 3.8096926212 6.3649640083 1000 39.9600000000 1.2797011137 0.0386494414 1.2797011137 0.0163923807 0.0063650000 0.0005070000 0.0028510000 0.0000010000 0.0000060000 0.0006510000 16160581 96830484 509673472 3.7911789417 3.8125097752 6.3936696053 1001 40.0000000000 1.3068192005 0.0399163443 1.3068192005 0.0164237781 0.0065470000 0.0004890000 0.0028150000 0.0000050000 0.0000040000 0.0012460000 16163357 96830484 509673472 3.7899200916 3.8144853115 6.4183621407 1002 40.0400000000 1.2491867542 0.0411232010 1.3068192005 0.0165465041 0.0096210000 0.0006710000 0.0024060000 0.0000030000 0.0000180000 0.0010060000 16166133 96830484 509673472 3.7918643951 3.8152217865 6.3585925102 1003 40.0800000000 1.2793914080 0.0423577655 1.3068192005 0.0165906089 0.0073160000 0.0005430000 0.0030410000 0.0000070000 0.0000060000 0.0009390000 16168909 96830484 509673472 3.7895259857 3.8198609352 6.3870105743 1004 40.1200000000 1.3071194887 0.0436174883 1.3071194887 0.0166228372 0.0059380000 0.0005010000 0.0028180000 0.0000010000 0.0000050000 0.0006450000 16171685 96830484 509673472 3.7886130810 3.8212366104 6.4112877846 1005 40.1600000000 1.3347710371 0.0449022182 1.3347710371 0.0166555804 0.0078620000 0.0005680000 0.0024840000 0.0000080000 0.0000070000 0.0013640000 16174461 96830484 509673472 3.7875823975 3.8232700825 6.4381070137 1006 40.2000000000 1.3660856485 0.0462155218 1.3660856485 0.0166996554 0.0079980000 0.0005720000 0.0029830000 0.0000020000 0.0000100000 0.0008030000 16177237 96830484 509673472 3.7863714695 3.8252093792 6.4667396545 1007 40.2400000000 1.4020606279 0.0475619420 1.4020606279 0.0167543694 0.0066840000 0.0005730000 0.0026710000 0.0000050000 0.0000050000 0.0009450000 16180013 96830484 509673472 3.7853159904 3.8269586563 6.4991993904 1008 40.2800000000 1.2867568731 0.0487913021 1.4020606279 0.0172680933 0.0066890000 0.0006300000 0.0027980000 0.0000010000 0.0000110000 0.0008590000 16182789 96830484 509673472 3.7900409698 3.8236300945 6.3817539215 1009 40.3200000000 1.3344032764 0.0500654467 1.4020606279 0.0173674891 0.0122580000 0.0006770000 0.0026230000 0.0000180000 0.0000150000 0.0017710000 16185565 96830484 509673472 3.7862067223 3.8326439857 6.4261713028 1010 40.3600000000 1.3711042404 0.0513734059 1.4020606279 0.0174205943 0.0101230000 0.0006610000 0.0030790000 0.0000010000 0.0000150000 0.0010100000 16188341 96830484 509673472 3.7851698399 3.8349826336 6.4592843056 1011 40.4000000000 1.3988169432 0.0527061889 1.4020606279 0.0174549335 0.0070440000 0.0005350000 0.0027140000 0.0000080000 0.0000060000 0.0009790000 16191117 96830484 509673472 3.7841911316 3.8376207352 6.4831156731 1012 40.4400000000 1.4242875576 0.0540615064 1.4242875576 0.0174842093 0.0058530000 0.0004950000 0.0026540000 0.0000010000 0.0000040000 0.0006530000 16193893 96830484 509673472 3.7832021713 3.8408577442 6.5056018829 1013 40.4800000000 1.4508081675 0.0554403284 1.4508081675 0.0175126979 0.0061320000 0.0004730000 0.0027650000 0.0000040000 0.0000040000 0.0012400000 16196669 96830484 509673472 3.7822339535 3.8438208103 6.5294761658 1014 40.5200000000 1.4758025408 0.0568410801 1.4758025408 0.0175376717 0.0077050000 0.0005660000 0.0027860000 0.0000020000 0.0000100000 0.0007480000 16199445 96830484 509673472 3.7810633183 3.8473186493 6.5521593094 1015 40.5600000000 1.5003516674 0.0582632580 1.5003516674 0.0175625262 0.0068160000 0.0004850000 0.0032530000 0.0000060000 0.0000050000 0.0009690000 16202221 96830484 509673472 3.7795677185 3.8521630764 6.5743713379 1016 40.6000000000 1.5225816965 0.0597045163 1.5225816965 0.0175843704 0.0056950000 0.0004730000 0.0029030000 0.0000010000 0.0000040000 0.0006520000 16204997 96830484 509673472 3.7780838013 3.8566112518 6.5947914124 1017 40.6400000000 1.5445159674 0.0611645079 1.5445159674 0.0176021232 0.0115390000 0.0006870000 0.0036890000 0.0000170000 0.0000140000 0.0018100000 16207773 96830484 509673472 3.7766380310 3.8606293201 6.6139378548 1018 40.6800000000 1.5669836998 0.0626437016 1.5669836998 0.0176255898 0.0077500000 0.0005350000 0.0038320000 0.0000010000 0.0000060000 0.0006990000 16210549 96830484 509673472 3.7749509811 3.8654849529 6.6341977119 1019 40.7200000000 1.3401000500 0.0638973388 1.5669836998 0.0194312553 0.0078870000 0.0005680000 0.0026400000 0.0000120000 0.0000100000 0.0010130000 16213325 96830484 509673472 3.7856233120 3.8545451164 6.4057998657 1020 40.7600000000 1.3585002422 0.0651665574 1.5669836998 0.0194738849 0.0062810000 0.0005060000 0.0026570000 0.0000010000 0.0000070000 0.0006630000 16216101 96830484 509673472 3.7800526619 3.8738727570 6.4219384193 1021 40.8000000000 1.3657755852 0.0664404154 1.5669836998 0.0194715361 0.0069070000 0.0004830000 0.0033820000 0.0000050000 0.0000040000 0.0012500000 16218877 96830484 509673472 3.7794497013 3.8776299953 6.4270153046 1022 40.8400000000 1.3733834028 0.0677192246 1.5669836998 0.0194685536 0.0068950000 0.0004660000 0.0041350000 0.0000000000 0.0000030000 0.0006490000 16221653 96830484 509673472 3.7784101963 3.8814620972 6.4333920479 1023 40.8800000000 1.3809525967 0.0690029327 1.5669836998 0.0194660834 0.0095500000 0.0006590000 0.0031450000 0.0000150000 0.0000110000 0.0011000000 16224429 96830484 509673472 3.7774527073 3.8855857849 6.4397621155 1024 40.9200000000 1.3859572411 0.0702890209 1.5669836998 0.0194661412 0.0067320000 0.0005180000 0.0029720000 0.0000000000 0.0000070000 0.0006930000 16227205 96830484 509673472 3.7767391205 3.8895678520 6.4430546761 1025 40.9600000000 1.3904771805 0.0715770093 1.5669836998 0.0194682981 0.0066030000 0.0004850000 0.0029270000 0.0000050000 0.0000040000 0.0012450000 16328285 96830484 509673472 3.7761230469 3.8938605785 6.4461693764 1026 41.0000000000 1.4005949497 0.0728723484 1.5669836998 0.0194714783 0.0096740000 0.0006710000 0.0032660000 0.0000020000 0.0000160000 0.0008690000 16535861 96830484 509673472 3.7749350071 3.8999707699 6.4535474777 1027 41.0400000000 1.4104911089 0.0741748010 1.5669836998 0.0194773171 0.0077510000 0.0005370000 0.0037450000 0.0000070000 0.0000060000 0.0009690000 16538637 96830484 509673472 3.7740564346 3.9043681622 6.4612455368 1028 41.0800000000 1.4173326492 0.0754813747 1.5669836998 0.0194792394 0.0057870000 0.0004850000 0.0027700000 0.0000010000 0.0000050000 0.0006510000 16541413 96830484 509673472 3.7734050751 3.9095332623 6.4666452408 1029 41.1200000000 1.4255932570 0.0767934368 1.5669836998 0.0194783313 0.0105830000 0.0006530000 0.0037100000 0.0000150000 0.0000150000 0.0015230000 16544189 96830484 509673472 3.7726178169 3.9138572216 6.4727869034 1030 41.1600000000 1.4306080341 0.0781078199 1.5669836998 0.0194755740 0.0067280000 0.0005070000 0.0029670000 0.0000000000 0.0000070000 0.0006940000 16546965 96830484 509673472 3.7721002102 3.9163358212 6.4758348465 1031 41.2000000000 1.4371768236 0.0794260246 1.5669836998 0.0194750237 0.0062480000 0.0004810000 0.0029310000 0.0000050000 0.0000040000 0.0009310000 16549741 96830484 509673472 3.7713260651 3.9209306240 6.4801192284 1032 41.2400000000 1.4458844662 0.0807501122 1.5669836998 0.0194731840 0.0069730000 0.0004660000 0.0042380000 0.0000010000 0.0000040000 0.0006480000 16552517 96830484 509673472 3.7706897259 3.9244325161 6.4869656563 1033 41.2800000000 1.4509278536 0.0820765186 1.5669836998 0.0194676368 0.0115440000 0.0005780000 0.0058800000 0.0000100000 0.0000080000 0.0013960000 16555293 96830484 509673472 3.7702496052 3.9262778759 6.4906802177 1034 41.3200000000 1.4580961466 0.0834072919 1.5669836998 0.0194805062 0.0089890000 0.0005070000 0.0056500000 0.0000010000 0.0000050000 0.0006550000 16558069 96830484 509673472 3.7694246769 3.9309074879 6.4946470261 1035 41.3600000000 1.4547027349 0.0847322150 1.5669836998 0.0194718643 0.0087590000 0.0004820000 0.0056340000 0.0000040000 0.0000030000 0.0009520000 16560845 96830484 509673472 3.7692832947 3.9313986301 6.4902801514 1036 41.4000000000 1.4513468742 0.0860513412 1.5669836998 0.0194657621 0.0082670000 0.0004660000 0.0055590000 0.0000000000 0.0000040000 0.0006470000 16563621 96830484 509673472 3.7686643600 3.9331219196 6.4851875305 1037 41.4400000000 1.4298617840 0.0873472046 1.5669836998 0.0194738666 0.0088630000 0.0004640000 0.0055350000 0.0000040000 0.0000040000 0.0012440000 16566397 96830484 509673472 3.7685532570 3.9626910686 6.4606680870 1038 41.4800000000 1.4730753899 0.0886822029 1.5669836998 0.0197450051 0.0081680000 0.0004650000 0.0054630000 0.0000000000 0.0000030000 0.0006480000 16569173 96830484 509673472 3.7670381069 3.8850562572 6.5060968399 1039 41.5200000000 1.4287201166 0.0899719410 1.5669836998 0.0198499347 0.0084220000 0.0004630000 0.0054320000 0.0000050000 0.0000030000 0.0009280000 16571949 96830484 509673472 3.7681720257 3.9484093189 6.4576025009 1040 41.5600000000 1.4279744625 0.0912584819 1.5669836998 0.0198453071 0.0080800000 0.0004670000 0.0053830000 0.0000000000 0.0000030000 0.0006430000 16574725 96830484 509673472 3.7674205303 3.9492855072 6.4556307793 1041 41.6000000000 1.4359608889 0.0925502229 1.5669836998 0.0198565825 0.0086970000 0.0004650000 0.0053910000 0.0000040000 0.0000030000 0.0012420000 16577501 96830484 509673472 3.7670631409 3.9325387478 6.4637522697 1042 41.6400000000 1.9107800722 0.0942951652 1.9107800722 0.0302437698 0.0070650000 0.0004640000 0.0043990000 0.0000000000 0.0000040000 0.0006140000 16580277 96830484 509673472 3.7676832676 3.2916071415 6.8517036438 1043 41.6800000000 1.9844042063 0.0961073503 1.9844042063 0.0310179770 0.0101500000 0.0005690000 0.0051000000 0.0000080000 0.0000070000 0.0009930000 16583053 96830484 509673472 3.7581543922 3.2049365044 6.8979783058 1044 41.7200000000 1.9788529873 0.0979107465 1.9844042063 0.0310095250 0.0081790000 0.0004970000 0.0048670000 0.0000010000 0.0000050000 0.0006220000 16585829 96830484 509673472 3.7579567432 3.2093610764 6.8921241760 1045 41.7600000000 1.9745360613 0.0997065602 1.9844042063 0.0309991743 0.0081590000 0.0004750000 0.0048220000 0.0000040000 0.0000030000 0.0011860000 16588605 96830484 509673472 3.7578008175 3.2142763138 6.8884334564 1046 41.8000000000 1.9647587538 0.1014895929 1.9844042063 0.0309900065 0.0074970000 0.0004630000 0.0048230000 0.0000000000 0.0000030000 0.0006140000 16591381 96830484 509673472 3.7579145432 3.2214031219 6.8789410591 1047 41.8400000000 1.9629312754 0.1032674741 1.9844042063 0.0309789368 0.0078380000 0.0004660000 0.0048410000 0.0000040000 0.0000030000 0.0008990000 16594157 96830484 509673472 3.7579925060 3.2232341766 6.8771128654 1048 41.8800000000 1.9609178305 0.1050400413 1.9844042063 0.0309666899 0.0093220000 0.0005160000 0.0047050000 0.0000010000 0.0000080000 0.0006890000 16596933 96830484 509673472 3.7579743862 3.2248778343 6.8737568855 1049 41.9200000000 1.9602553844 0.1068085974 1.9844042063 0.0309560487 0.0083400000 0.0004390000 0.0045350000 0.0000050000 0.0000040000 0.0011140000 16599709 96830484 509673472 3.7578999996 3.2266635895 6.8718438148 1050 41.9600000000 1.9591628313 0.1085727443 1.9844042063 0.0309459501 0.0090650000 0.0005170000 0.0046860000 0.0000010000 0.0000080000 0.0006880000 16602485 96830484 509673472 3.7579298019 3.2283592224 6.8696246147 1051 42.0000000000 1.9589288235 0.1103333114 1.9844042063 0.0309351846 0.0080450000 0.0004410000 0.0045600000 0.0000050000 0.0000050000 0.0008390000 16605261 96830484 509673472 3.7581028938 3.2290635109 6.8683247566 1052 42.0400000000 1.9583879709 0.1120900174 1.9844042063 0.0309235202 0.0071560000 0.0004220000 0.0044930000 0.0000010000 0.0000040000 0.0005930000 16608037 96830484 509673472 3.7580158710 3.2299640179 6.8671789169 1053 42.0800000000 1.9571428299 0.1138422043 1.9844042063 0.0309119190 0.0095160000 0.0005120000 0.0047170000 0.0000080000 0.0000070000 0.0012440000 16610813 96830484 509673472 3.7579646111 3.2323791981 6.8650121689 1054 42.1200000000 1.9537302256 0.1155878286 1.9844042063 0.0309004879 0.0078150000 0.0004530000 0.0045650000 0.0000010000 0.0000050000 0.0005950000 16613589 96830484 509673472 3.7580695152 3.2344598770 6.8611474037 1055 42.1600000000 1.9526785612 0.1173291468 1.9844042063 0.0308880699 0.0073870000 0.0004180000 0.0045170000 0.0000040000 0.0000030000 0.0008310000 16616365 96830484 509673472 3.7577965260 3.2365384102 6.8597192764 1056 42.2000000000 1.9493304491 0.1190639965 1.9844042063 0.0308784476 0.0072030000 0.0004240000 0.0045060000 0.0000000000 0.0000040000 0.0005900000 16619141 96830484 509673472 3.7577118874 3.2399585247 6.8565053940 1057 42.2400000000 1.9452251196 0.1207916797 1.9844042063 0.0308686800 0.0101500000 0.0005130000 0.0047810000 0.0000080000 0.0000070000 0.0012460000 16621917 96830484 509673472 3.7578153610 3.2418243885 6.8520374298 1058 42.2800000000 1.9409650564 0.1225120704 1.9844042063 0.0308559640 0.0078540000 0.0004470000 0.0046020000 0.0000010000 0.0000050000 0.0006020000 16624693 96830484 509673472 3.7577800751 3.2446908951 6.8482685089 1059 42.3200000000 1.9392542839 0.1242275966 1.9844042063 0.0308440476 0.0075460000 0.0004250000 0.0045430000 0.0000040000 0.0000040000 0.0008280000 16627469 96830484 509673472 3.7576589584 3.2447340488 6.8465480804 1060 42.3600000000 1.9359699488 0.1259367875 1.9844042063 0.0308316391 0.0094730000 0.0005410000 0.0044520000 0.0000010000 0.0000080000 0.0006920000 16630245 96830484 509673472 3.7575378418 3.2457578182 6.8433303833 1061 42.4000000000 1.9328356981 0.1276398025 1.9844042063 0.0308187893 0.0081380000 0.0004680000 0.0042820000 0.0000060000 0.0000050000 0.0011350000 16633021 96830484 509673472 3.7573971748 3.2477576733 6.8406834602 1062 42.4400000000 1.9289301634 0.1293359328 1.9844042063 0.0308121210 0.0073810000 0.0004260000 0.0045450000 0.0000000000 0.0000040000 0.0005960000 16635797 96830484 509673472 3.7570633888 3.2507250309 6.8392133713 1063 42.4800000000 1.9224979877 0.1310228209 1.9844042063 0.0308027322 0.0067770000 0.0004160000 0.0038430000 0.0000030000 0.0000030000 0.0008340000 16638573 96830484 509673472 3.7574403286 3.2522685528 6.8335118294 1064 42.5200000000 1.9206837416 0.1327048330 1.9844042063 0.0307897337 0.0100330000 0.0005150000 0.0048480000 0.0000010000 0.0000110000 0.0007910000 16641349 96830484 509673472 3.7575342655 3.2535147667 6.8325896263 1065 42.5600000000 1.9189521074 0.1343820605 1.9844042063 0.0307762968 0.0085720000 0.0004760000 0.0046630000 0.0000060000 0.0000050000 0.0011230000 16644125 96830484 509673472 3.7577185631 3.2553684711 6.8322939873 1066 42.6000000000 1.9149460793 0.1360523832 1.9844042063 0.0307633750 0.0096780000 0.0005130000 0.0048390000 0.0000010000 0.0000070000 0.0006920000 16646901 96830484 509673472 3.7580015659 3.2579002380 6.8289227486 1067 42.6400000000 1.9140154123 0.1377187028 1.9844042063 0.0307513093 0.0090340000 0.0005020000 0.0050250000 0.0000050000 0.0000040000 0.0008380000 16649677 96830484 509673472 3.7581934929 3.2592384815 6.8289141655 1068 42.6800000000 1.9118071795 0.1393798344 1.9844042063 0.0307396406 0.0075170000 0.0004410000 0.0047180000 0.0000000000 0.0000040000 0.0005900000 16652453 96830484 509673472 3.7585871220 3.2619130611 6.8283495903 1069 42.7200000000 1.9115028381 0.1410375734 1.9844042063 0.0307285259 0.0077750000 0.0004200000 0.0045790000 0.0000030000 0.0000040000 0.0010920000 16655229 96830484 509673472 3.7589521408 3.2651307583 6.8295021057 1070 42.7600000000 1.9090725183 0.1426899425 1.9844042063 0.0307165323 0.0072770000 0.0004160000 0.0045900000 0.0000000000 0.0000040000 0.0005900000 16658005 96830484 509673472 3.7592582703 3.2691676617 6.8282022476 1071 42.8000000000 1.9092698097 0.1443394102 1.9844042063 0.0307038722 0.0075220000 0.0004180000 0.0045950000 0.0000040000 0.0000040000 0.0008280000 16660781 96830484 509673472 3.7592084408 3.2726318836 6.8310213089 1072 42.8400000000 1.9065747261 0.1459832864 1.9844042063 0.0306911844 0.0072870000 0.0004160000 0.0046170000 0.0000000000 0.0000030000 0.0005880000 16663557 96830484 509673472 3.7591776848 3.2757079601 6.8306798935 1073 42.8800000000 1.9042859077 0.1476219654 1.9844042063 0.0306780856 0.0078820000 0.0004200000 0.0046200000 0.0000040000 0.0000040000 0.0011150000 16666333 96830484 509673472 3.7591865063 3.2785069942 6.8290758133 1074 42.9200000000 1.9002647400 0.1492538488 1.9844042063 0.0306650297 0.0073340000 0.0004180000 0.0046330000 0.0000010000 0.0000030000 0.0005900000 16669109 96830484 509673472 3.7590157986 3.2816143036 6.8261446953 1075 42.9600000000 1.8943644762 0.1508772076 1.9844042063 0.0306534722 0.0075590000 0.0004180000 0.0046480000 0.0000030000 0.0000030000 0.0008190000 16671885 96830484 509673472 3.7590951920 3.2823934555 6.8200263977 1076 43.0000000000 1.8887916803 0.1524923697 1.9844042063 0.0306414807 0.0096980000 0.0005320000 0.0049060000 0.0000010000 0.0000080000 0.0006800000 16674661 96830484 509673472 3.7591955662 3.2819440365 6.8156476021 1077 43.0400000000 1.8845870495 0.1541006285 1.9844042063 0.0306283324 0.0085830000 0.0004530000 0.0047250000 0.0000050000 0.0000040000 0.0011050000 16677437 96830484 509673472 3.7592291832 3.2835893631 6.8144111633 1078 43.0800000000 1.8788996935 0.1557006276 1.9844042063 0.0306168979 0.0074220000 0.0004260000 0.0046630000 0.0000010000 0.0000040000 0.0005920000 16680213 96830484 509673472 3.7595150471 3.2846739292 6.8104939461 1079 43.1200000000 1.8763023615 0.1572952539 1.9844042063 0.0306040362 0.0075950000 0.0004310000 0.0046450000 0.0000040000 0.0000030000 0.0008220000 16682989 96830484 509673472 3.7596490383 3.2866961956 6.8110284805 1080 43.1600000000 1.8701021671 0.1588811862 1.9844042063 0.0305919286 0.0073700000 0.0004170000 0.0046560000 0.0000000000 0.0000040000 0.0005940000 16685765 96830484 509673472 3.7599117756 3.2885870934 6.8069524765 1081 43.2000000000 1.8694421053 0.1604635737 1.9844042063 0.0305792006 0.0079310000 0.0004210000 0.0046580000 0.0000030000 0.0000030000 0.0011020000 16688541 96830484 509673472 3.7600214481 3.2912783623 6.8099503517 1082 43.2400000000 1.8675490618 0.1620412867 1.9844042063 0.0305665288 0.0096860000 0.0005420000 0.0049060000 0.0000010000 0.0000080000 0.0006960000 16691317 96830484 509673472 3.7601163387 3.2939891815 6.8106465340 1083 43.2800000000 1.8716025352 0.1636198290 1.9844042063 0.0305577873 0.0078860000 0.0004470000 0.0043630000 0.0000050000 0.0000050000 0.0008260000 16694093 96830484 509673472 3.7603042126 3.2909996510 6.8160166740 1084 43.3200000000 1.8705470562 0.1651944851 1.9844042063 0.0305438870 0.0074130000 0.0004290000 0.0046700000 0.0000010000 0.0000040000 0.0005950000 16696869 96830484 509673472 3.7606627941 3.2954187393 6.8175592422 1085 43.3600000000 1.8718727827 0.1667674605 1.9844042063 0.0305307182 0.0079170000 0.0004160000 0.0046900000 0.0000040000 0.0000030000 0.0010990000 16699645 96830484 509673472 3.7609736919 3.2932016850 6.8191304207 1086 43.4000000000 1.8688200712 0.1683347281 1.9844042063 0.0305168017 0.0091710000 0.0005200000 0.0048670000 0.0000010000 0.0000080000 0.0006690000 16702421 96830484 509673472 3.7613694668 3.2992007732 6.8190250397 1087 43.4400000000 1.8691127300 0.1698993813 1.9844042063 0.0305031721 0.0081870000 0.0004490000 0.0047290000 0.0000050000 0.0000040000 0.0008480000 16705197 96830484 509673472 3.7617383003 3.3020467758 6.8219885826 1088 43.4800000000 1.8643521070 0.1714567827 1.9844042063 0.0304905355 0.0073960000 0.0004200000 0.0046610000 0.0000010000 0.0000040000 0.0006010000 16707973 96830484 509673472 3.7621994019 3.3039903641 6.8184671402 1089 43.5200000000 1.8576996326 0.1730052150 1.9844042063 0.0304781912 0.0117610000 0.0006130000 0.0051330000 0.0000120000 0.0000090000 0.0014020000 16710749 96830484 509673472 3.7629132271 3.3070311546 6.8142147064 1090 43.5600000000 1.8564354181 0.1745496464 1.9844042063 0.0304650825 0.0084610000 0.0004660000 0.0047610000 0.0000000000 0.0000050000 0.0006160000 16713525 96830484 509673472 3.7636945248 3.3085854053 6.8146739006 1091 43.6000000000 1.8634320498 0.1760976596 1.9844042063 0.0304554081 0.0063660000 0.0004370000 0.0031900000 0.0000050000 0.0000040000 0.0008300000 16716301 96830484 509673472 3.7644255161 3.2995157242 6.8204002380 1092 43.6400000000 1.8681681156 0.1776471747 1.9844042063 0.0304424487 0.0073630000 0.0004170000 0.0046320000 0.0000000000 0.0000040000 0.0005980000 16719077 96830484 509673472 3.7650694847 3.3113231659 6.8320522308 1093 43.6800000000 1.8740690947 0.1791992533 1.9844042063 0.0304354217 0.0067520000 0.0004160000 0.0035250000 0.0000040000 0.0000030000 0.0010960000 16721853 96830484 509673472 3.7658045292 3.3015890121 6.8374118805 1094 43.7200000000 1.8725146055 0.1807470735 1.9844042063 0.0304216783 0.0099250000 0.0005190000 0.0045310000 0.0000020000 0.0000100000 0.0007870000 16724629 96830484 509673472 3.7663908005 3.3129169941 6.8417167664 1095 43.7600000000 1.8706935644 0.1822904037 1.9844042063 0.0304090562 0.0084740000 0.0004670000 0.0047170000 0.0000060000 0.0000060000 0.0008420000 16727405 96830484 509673472 3.7669649124 3.3143901825 6.8429641724 1096 43.8000000000 1.8661482334 0.1838267703 1.9844042063 0.0303961821 0.0063910000 0.0004240000 0.0035310000 0.0000000000 0.0000040000 0.0006010000 16730181 96830484 509673472 3.7676019669 3.3167831898 6.8413109779 1097 43.8400000000 1.8646845818 0.1853590017 1.9844042063 0.0303867112 0.0077120000 0.0004140000 0.0041000000 0.0000040000 0.0000040000 0.0011040000 16732957 96830484 509673472 3.7682688236 3.3069345951 6.8385190964 1098 43.8800000000 1.8579787016 0.1868823347 1.9844042063 0.0303745180 0.0074790000 0.0004320000 0.0046880000 0.0000000000 0.0000030000 0.0006020000 16735733 96830484 509673472 3.7688391209 3.3186771870 6.8373708725 1099 43.9200000000 1.8516335487 0.1883971220 1.9844042063 0.0303624243 0.0125250000 0.0006080000 0.0050960000 0.0000160000 0.0000150000 0.0011930000 16738509 96830484 509673472 3.7695510387 3.3220636845 6.8329601288 1100 43.9600000000 1.8463834524 0.1899043823 1.9844042063 0.0303499867 0.0082100000 0.0004900000 0.0043550000 0.0000010000 0.0000070000 0.0006430000 16741285 96830484 509673472 3.7702958584 3.3251550198 6.8305053711 1101 44.0000000000 1.8418999910 0.1914048324 1.9844042063 0.0303378516 0.0082870000 0.0004380000 0.0047240000 0.0000050000 0.0000050000 0.0010940000 16744061 96830484 509673472 3.7709536552 3.3279542923 6.8283863068 1102 44.0400000000 1.8324409723 0.1928939759 1.9844042063 0.0303279141 0.0074840000 0.0004310000 0.0045950000 0.0000000000 0.0000040000 0.0006140000 16746837 96830484 509673472 3.7716510296 3.3314783573 6.8219375610 1103 44.0800000000 1.8234958649 0.1943723095 1.9844042063 0.0303168166 0.0076320000 0.0004180000 0.0045940000 0.0000060000 0.0000040000 0.0008330000 16749613 96830484 509673472 3.7724404335 3.3378517628 6.8167481422 1104 44.1200000000 1.7845001221 0.1958126426 1.9844042063 0.0303363339 0.0073910000 0.0004260000 0.0045690000 0.0000000000 0.0000040000 0.0006140000 16752389 96830484 509673472 3.7734868526 3.3468613625 6.7804312706 1105 44.1600000000 1.7844302654 0.1972503057 1.9844042063 0.0303474759 0.0079020000 0.0004200000 0.0046140000 0.0000040000 0.0000030000 0.0011080000 16755165 96830484 509673472 3.7741627693 3.3151531219 6.7710695267 1106 44.2000000000 1.8096802235 0.1987081989 1.9844042063 0.0303568863 0.0074230000 0.0004190000 0.0046030000 0.0000010000 0.0000030000 0.0006110000 16757941 96830484 509673472 3.7743878365 3.3355183601 6.8072552681 1107 44.2400000000 1.7593687773 0.2001180097 1.9844042063 0.0304028239 0.0075130000 0.0004120000 0.0045390000 0.0000040000 0.0000030000 0.0008340000 16760717 96830484 509673472 3.7752807140 3.3367743492 6.7560400963 1108 44.2800000000 1.7716611624 0.2015363700 1.9844042063 0.0303957275 0.0073880000 0.0004140000 0.0046150000 0.0000000000 0.0000040000 0.0006180000 16763493 96830484 509673472 3.7760744095 3.3206059933 6.7649893761 1109 44.3200000000 1.7580972910 0.2029399416 1.9844042063 0.0303876748 0.0078780000 0.0004100000 0.0045660000 0.0000030000 0.0000030000 0.0011280000 16766269 96830484 509673472 3.7767858505 3.3363935947 6.7581944466 1110 44.3600000000 1.7419388294 0.2043264271 1.9844042063 0.0303832781 0.0074410000 0.0004180000 0.0046110000 0.0000010000 0.0000040000 0.0006100000 16769045 96830484 509673472 3.7775814533 3.3330104351 6.7409334183 1111 44.4000000000 1.7323858738 0.2057018181 1.9844042063 0.0303731341 0.0114840000 0.0006020000 0.0050980000 0.0000100000 0.0000100000 0.0010220000 16771821 96830484 509673472 3.7783787251 3.3305890560 6.7318592072 1112 44.4400000000 1.7373601198 0.2070792087 1.9844042063 0.0303602279 0.0085400000 0.0004640000 0.0047140000 0.0000000000 0.0000050000 0.0006310000 16774597 96830484 509673472 3.7788949013 3.3336250782 6.7399005890 1113 44.4800000000 1.7389732599 0.2084555735 1.9844042063 0.0303469968 0.0080400000 0.0004360000 0.0046350000 0.0000040000 0.0000040000 0.0011260000 16777373 96830484 509673472 3.7795650959 3.3350667953 6.7439270020 1114 44.5200000000 1.7371758223 0.2098278538 1.9844042063 0.0303343039 0.0098600000 0.0005140000 0.0048530000 0.0000010000 0.0000080000 0.0007100000 16780149 96830484 509673472 3.7803018093 3.3347699642 6.7441225052 1115 44.5600000000 1.7436871529 0.2112035123 1.9844042063 0.0303249322 0.0082810000 0.0004450000 0.0046610000 0.0000050000 0.0000050000 0.0008460000 16782925 96830484 509673472 3.7809751034 3.3213827610 6.7476348877 1116 44.6000000000 1.7440428734 0.2125770243 1.9844042063 0.0303136018 0.0074600000 0.0004250000 0.0045540000 0.0000000000 0.0000040000 0.0006160000 16785701 96830484 509673472 3.7815375328 3.3351933956 6.7550611496 1117 44.6400000000 1.7443912029 0.2139483888 1.9844042063 0.0303008197 0.0099820000 0.0005180000 0.0047790000 0.0000080000 0.0000070000 0.0012740000 16788477 96830484 509673472 3.7822577953 3.3364410400 6.7575845718 1118 44.6800000000 1.7492635250 0.2153216582 1.9844042063 0.0302927628 0.0080500000 0.0004490000 0.0046000000 0.0000010000 0.0000060000 0.0006230000 16791253 96830484 509673472 3.7830665112 3.3199715614 6.7594242096 1119 44.7200000000 1.7417459488 0.2166857550 1.9844042063 0.0302877073 0.0102460000 0.0005170000 0.0047710000 0.0000080000 0.0000080000 0.0009180000 16794029 96830484 509673472 3.7836720943 3.3348050117 6.7596521378 1120 44.7600000000 1.7487525940 0.2180536718 1.9844042063 0.0302782219 0.0080340000 0.0004610000 0.0045940000 0.0000000000 0.0000050000 0.0006220000 16796805 96830484 509673472 3.7842745781 3.3211460114 6.7650694847 1121 44.8000000000 1.7469109297 0.2194175052 1.9844042063 0.0302687285 0.0079270000 0.0004210000 0.0044940000 0.0000030000 0.0000030000 0.0011220000 16799581 96830484 509673472 3.7849829197 3.3380084038 6.7716760635 1122 44.8400000000 1.7558327913 0.2207868593 1.9844042063 0.0302588692 0.0099140000 0.0005260000 0.0047520000 0.0000010000 0.0000080000 0.0007130000 16802357 96830484 509673472 3.7857296467 3.3250536919 6.7791867256 1123 44.8800000000 1.7516151667 0.2221500190 1.9844042063 0.0302500139 0.0081790000 0.0004460000 0.0045080000 0.0000060000 0.0000050000 0.0008460000 16805133 96830484 509673472 3.7864995003 3.3446080685 6.7852635384 1124 44.9200000000 1.7613474131 0.2235194117 1.9844042063 0.0302419486 0.0073760000 0.0004240000 0.0044770000 0.0000010000 0.0000040000 0.0006180000 16807909 96830484 509673472 3.7873330116 3.3284118176 6.7919349670 1125 44.9600000000 1.7592018843 0.2248844627 1.9844042063 0.0302330528 0.0077600000 0.0004160000 0.0044230000 0.0000030000 0.0000030000 0.0011260000 16810685 96830484 509673472 3.7880392075 3.3498299122 6.7995929718 1126 45.0000000000 1.7619037628 0.2262494888 1.9844042063 0.0302202412 0.0106080000 0.0006040000 0.0041920000 0.0000010000 0.0000100000 0.0008060000 16813461 96830484 509673472 3.7888770103 3.3519899845 6.8059606552 1127 45.0400000000 1.7732946873 0.2276221997 1.9844042063 0.0302141933 0.0086180000 0.0004620000 0.0045480000 0.0000060000 0.0000040000 0.0008470000 16816237 96830484 509673472 3.7896487713 3.3337249756 6.8135371208 1128 45.0800000000 1.7827395201 0.2290008498 1.9844042063 0.0302084287 0.0074650000 0.0004360000 0.0044380000 0.0000010000 0.0000040000 0.0006140000 16819013 96830484 509673472 3.7901253700 3.3528954983 6.8329968452 1129 45.1200000000 1.8081367016 0.2303995529 1.9844042063 0.0302070487 0.0077680000 0.0004170000 0.0043910000 0.0000030000 0.0000030000 0.0011160000 16821789 96830484 509673472 3.7904231548 3.3386011124 6.8572859764 1130 45.1600000000 1.8257316351 0.2318113512 1.9844042063 0.0302038906 0.0072000000 0.0004240000 0.0043620000 0.0000010000 0.0000040000 0.0006090000 16824565 96830484 509673472 3.7907223701 3.3569376469 6.8839349747 1131 45.2000000000 1.8324692249 0.2332266102 1.9844042063 0.0301978004 0.0103270000 0.0005140000 0.0046580000 0.0000100000 0.0000090000 0.0010060000 16827341 96830484 509673472 3.7917783260 3.3409733772 6.8880991936 1132 45.2400000000 1.8304934502 0.2346376233 1.9844042063 0.0301889144 0.0074540000 0.0004630000 0.0037430000 0.0000010000 0.0000060000 0.0006260000 16830117 96830484 509673472 3.7925097942 3.3571758270 6.8932933807 1133 45.2800000000 1.8361603022 0.2360511473 1.9844042063 0.0301821619 0.0074680000 0.0004230000 0.0040310000 0.0000050000 0.0000030000 0.0011140000 16832893 96830484 509673472 3.7935643196 3.3440077305 6.8960728645 1134 45.3200000000 1.8343337774 0.2374605676 1.9844042063 0.0301703744 0.0071480000 0.0004130000 0.0043360000 0.0000000000 0.0000040000 0.0006070000 16835669 96830484 509673472 3.7945663929 3.3566842079 6.8999228477 1135 45.3600000000 1.8387652636 0.2388714087 1.9844042063 0.0301614076 0.0095910000 0.0005180000 0.0045590000 0.0000080000 0.0000070000 0.0009060000 16838445 96830484 509673472 3.7959206104 3.3455698490 6.9040303230 1136 45.4000000000 1.8368673325 0.2402780953 1.9844042063 0.0301495146 0.0078180000 0.0004390000 0.0043690000 0.0000000000 0.0000040000 0.0006150000 16841221 96830484 509673472 3.7968997955 3.3562660217 6.9075002670 1137 45.4400000000 1.8403422832 0.2416853637 1.9844042063 0.0301412161 0.0073130000 0.0004230000 0.0039630000 0.0000040000 0.0000040000 0.0011040000 16843997 96830484 509673472 3.7982740402 3.3463172913 6.9116687775 1138 45.4800000000 1.8376568556 0.2430877991 1.9844042063 0.0301291821 0.0071030000 0.0004160000 0.0042690000 0.0000000000 0.0000040000 0.0006050000 16846773 96830484 509673472 3.8000073433 3.3528795242 6.9123396873 1139 45.5200000000 1.8403577805 0.2444901433 1.9844042063 0.0301219748 0.0119730000 0.0006050000 0.0040470000 0.0000150000 0.0000140000 0.0011800000 16849549 96830484 509673472 3.8014612198 3.3518760204 6.9142336845 1140 45.5600000000 1.8408889771 0.2458904931 1.9844042063 0.0301118829 0.0083780000 0.0004860000 0.0043910000 0.0000010000 0.0000060000 0.0006510000 16852325 96830484 509673472 3.8034002781 3.3499169350 6.9156684875 1141 45.6000000000 1.8434239626 0.2472906101 1.9844042063 0.0301040959 0.0079990000 0.0004340000 0.0042870000 0.0000040000 0.0000030000 0.0010770000 16855101 96830484 509673472 3.8052742481 3.3484246731 6.9176917076 1142 45.6400000000 1.8451422453 0.2486897796 1.9844042063 0.0300943410 0.0072080000 0.0004180000 0.0042790000 0.0000000000 0.0000030000 0.0006120000 16857877 96830484 509673472 3.8070826530 3.3470358849 6.9198536873 1143 45.6800000000 1.8458116055 0.2500870866 1.9844042063 0.0300853446 0.0096210000 0.0005140000 0.0044820000 0.0000080000 0.0000070000 0.0009000000 16860653 96830484 509673472 3.8084876537 3.3508076668 6.9195280075 1144 45.7200000000 1.8478380442 0.2514837220 1.9844042063 0.0300752720 0.0078150000 0.0004580000 0.0042940000 0.0000010000 0.0000040000 0.0006150000 16863429 96830484 509673472 3.8100743294 3.3530125618 6.9212555885 1145 45.7600000000 1.8487145901 0.2528786835 1.9844042063 0.0300643495 0.0076020000 0.0004240000 0.0042310000 0.0000040000 0.0000040000 0.0010710000 16866205 96830484 509673472 3.8120572567 3.3487823009 6.9243502617 1146 45.8000000000 1.8515295982 0.2542736668 1.9844042063 0.0300582607 0.0070800000 0.0004160000 0.0042180000 0.0000000000 0.0000040000 0.0006070000 16868981 96830484 509673472 3.8134477139 3.3505918980 6.9240760803 1147 45.8400000000 1.8561410904 0.2556702383 1.9844042063 0.0300508783 0.0105940000 0.0005270000 0.0044840000 0.0000110000 0.0000100000 0.0009990000 16871757 96830484 509673472 3.8153226376 3.3469896317 6.9272646904 1148 45.8800000000 1.8587061167 0.2570666110 1.9844042063 0.0300420121 0.0081420000 0.0004600000 0.0043280000 0.0000010000 0.0000060000 0.0006250000 16874533 96830484 509673472 3.8174436092 3.3428342342 6.9287834167 1149 45.9200000000 1.8648655415 0.2584659138 1.9844042063 0.0300377263 0.0076430000 0.0004320000 0.0042160000 0.0000040000 0.0000030000 0.0010680000 16877309 96830484 509673472 3.8194072247 3.3364310265 6.9314346313 1150 45.9600000000 1.8740626574 0.2598707805 1.9844042063 0.0300366942 0.0070790000 0.0004150000 0.0042030000 0.0000010000 0.0000040000 0.0006060000 16880085 96830484 509673472 3.8216829300 3.3169891834 6.9361228943 1151 46.0000000000 1.9173840284 0.2613108442 1.9844042063 0.0301408358 0.0098590000 0.0005110000 0.0044640000 0.0000080000 0.0000070000 0.0008990000 16882861 96830484 509673472 3.8240301609 3.2310535908 6.9464330673 1152 46.0400000000 1.8916586637 0.2627260766 1.9844042063 0.0301550656 0.0077210000 0.0004390000 0.0042120000 0.0000010000 0.0000060000 0.0006150000 16885637 96830484 509673472 3.8254079819 3.2856736183 6.9446702003 1153 46.0800000000 1.9530357122 0.2641920867 1.9844042063 0.0303364887 0.0075710000 0.0004190000 0.0041860000 0.0000040000 0.0000030000 0.0010580000 16888413 96830484 509673472 3.8285889626 3.1702547073 6.9592189789 1154 46.1200000000 1.9329229593 0.2656381273 1.9844042063 0.0303404155 0.0092810000 0.0005120000 0.0043340000 0.0000010000 0.0000070000 0.0007030000 16891189 96830484 509673472 3.8297028542 3.2109322548 6.9586629868 1155 46.1600000000 1.9512387514 0.2670975218 1.9844042063 0.0303497297 0.0078830000 0.0004420000 0.0041910000 0.0000050000 0.0000040000 0.0007960000 16893965 96830484 509673472 3.8324182034 3.1751253605 6.9642901421 1156 46.2000000000 1.9551918507 0.2685578110 1.9844042063 0.0303382885 0.0103390000 0.0006140000 0.0044150000 0.0000010000 0.0000080000 0.0006870000 16896741 96830484 509673472 3.8348574638 3.1692183018 6.9677925110 1157 46.2400000000 1.9623359442 0.2700217507 1.9844042063 0.0303284815 0.0075830000 0.0005110000 0.0035460000 0.0000060000 0.0000050000 0.0010570000 16899517 96830484 509673472 3.8379251957 3.1559445858 6.9715852737 1158 46.2800000000 1.9714419842 0.2714910255 1.9844042063 0.0303216382 0.0070970000 0.0004310000 0.0041230000 0.0000010000 0.0000040000 0.0005930000 16902293 96830484 509673472 3.8406813145 3.1412763596 6.9760198593 1159 46.3200000000 1.9815593958 0.2729664943 1.9844042063 0.0303176900 0.0097880000 0.0005160000 0.0043870000 0.0000080000 0.0000070000 0.0008550000 16905069 96830484 509673472 3.8436524868 3.1257081032 6.9799604416 1160 46.3600000000 1.9870603085 0.2744441614 1.9870603085 0.0303082055 0.0076920000 0.0004630000 0.0041430000 0.0000000000 0.0000050000 0.0006070000 16907845 96830484 509673472 3.8470206261 3.1184062958 6.9837226868 1161 46.4000000000 1.9872120619 0.2759194137 1.9872120619 0.0302969278 0.0058490000 0.0004220000 0.0024720000 0.0000040000 0.0000040000 0.0010160000 16910621 96830484 509673472 3.8503572941 3.1186416149 6.9872913361 1162 46.4400000000 1.9649028778 0.2773729278 1.9872120619 0.0303059666 0.0094570000 0.0005140000 0.0042960000 0.0000010000 0.0000080000 0.0006810000 16913397 96830484 509673472 3.8553495407 3.1663944721 6.9873781204 1163 46.4800000000 1.9747513533 0.2788324106 1.9872120619 0.0303035919 0.0078000000 0.0004430000 0.0041370000 0.0000050000 0.0000050000 0.0007700000 16916173 96830484 509673472 3.8552312851 3.1458175182 6.9898438454 1164 46.5200000000 1.8518041372 0.2801837608 1.9872120619 0.0305545329 0.0069730000 0.0004250000 0.0040220000 0.0000000000 0.0000030000 0.0006070000 16918949 96830484 509673472 3.8667509556 3.2827970982 6.9210705757 1165 46.5600000000 1.7151079178 0.2814154554 1.9872120619 0.0310402409 0.0074650000 0.0004170000 0.0040920000 0.0000030000 0.0000030000 0.0010970000 16921725 96830484 509673472 3.8685736656 3.2567024231 6.7581725121 1166 46.6000000000 1.5462465286 0.2825002162 1.9872120619 0.0317530620 0.0070160000 0.0004260000 0.0040820000 0.0000010000 0.0000030000 0.0006490000 16924501 96830484 509673472 3.8760085106 3.2267332077 6.5482835770 1167 46.6400000000 1.2544645071 0.2833330905 1.9872120619 0.0340524307 0.0072290000 0.0004120000 0.0040850000 0.0000040000 0.0000030000 0.0008920000 16927277 96830484 509673472 3.8848187923 3.2028071880 6.1732330322 1168 46.6800000000 1.0355759859 0.2839771340 1.9872120619 0.0358335071 0.0116740000 0.0006050000 0.0046830000 0.0000020000 0.0000160000 0.0010150000 16930053 96830484 509673472 3.8959524632 3.2054178715 5.8598351479 1169 46.7200000000 1.0091094971 0.2845974355 1.9872120619 0.0358281711 0.0089780000 0.0004640000 0.0042710000 0.0000070000 0.0000050000 0.0013350000 16932829 96830484 509673472 3.9002497196 3.2401616573 5.8633952141 1170 46.7600000000 1.0103229284 0.2852177137 1.9872120619 0.0358164480 0.0078900000 0.0004420000 0.0045860000 0.0000000000 0.0000040000 0.0007270000 16935605 96830484 509673472 3.9023413658 3.2368535995 5.8637261391 1171 46.8000000000 1.0169764757 0.2858426144 1.9872120619 0.0358062700 0.0076500000 0.0004120000 0.0043850000 0.0000040000 0.0000040000 0.0009550000 16938381 96830484 509673472 3.9042398930 3.2264244556 5.8663344383 1172 46.8400000000 1.0118514299 0.2864620758 1.9872120619 0.0357918717 0.0061140000 0.0004140000 0.0030870000 0.0000000000 0.0000040000 0.0007260000 16941157 96830484 509673472 3.9056928158 3.2302119732 5.8669018745 1173 46.8800000000 1.0146547556 0.2870828710 1.9872120619 0.0357803897 0.0113600000 0.0006010000 0.0045620000 0.0000100000 0.0000100000 0.0016070000 16943933 96830484 509673472 3.9073238373 3.2260594368 5.8665947914 1174 46.9200000000 1.0226006508 0.2877093767 1.9872120619 0.0357702954 0.0084500000 0.0004600000 0.0045880000 0.0000010000 0.0000050000 0.0007470000 16946709 96830484 509673472 3.9089152813 3.2149956226 5.8687701225 1175 46.9600000000 1.0198400021 0.2883324666 1.9872120619 0.0357576891 0.0060840000 0.0004210000 0.0027200000 0.0000040000 0.0000050000 0.0009420000 16949485 96830484 509673472 3.9099814892 3.2171711922 5.8686394691 1176 47.0000000000 1.0235220194 0.2889576278 1.9872120619 0.0357464025 0.0085240000 0.0005130000 0.0031240000 0.0000010000 0.0000080000 0.0008310000 16952261 96830484 509673472 3.9112994671 3.2109289169 5.8699431419 1177 47.0400000000 1.0254201889 0.2895833394 1.9872120619 0.0357343829 0.0084620000 0.0004420000 0.0041610000 0.0000050000 0.0000040000 0.0013400000 16955037 96830484 509673472 3.9126801491 3.2084367275 5.8713603020 1178 47.0800000000 1.0281208754 0.2902102813 1.9872120619 0.0357222146 0.0075810000 0.0004440000 0.0044710000 0.0000010000 0.0000040000 0.0007340000 16957813 96830484 509673472 3.9140248299 3.2057626247 5.8718857765 1179 47.1200000000 1.0291393995 0.2908370236 1.9872120619 0.0357083012 0.0069880000 0.0004130000 0.0037250000 0.0000040000 0.0000030000 0.0009390000 16960589 96830484 509673472 3.9155652523 3.2048339844 5.8731088638 1180 47.1600000000 1.0303132534 0.2914636983 1.9872120619 0.0356945707 0.0075150000 0.0004180000 0.0044240000 0.0000000000 0.0000030000 0.0007340000 16963365 96830484 509673472 3.9170327187 3.2026109695 5.8735613823 1181 47.2000000000 1.0306005478 0.2920895551 1.9872120619 0.0356805459 0.0080650000 0.0004140000 0.0044000000 0.0000040000 0.0000030000 0.0013440000 16966141 96830484 509673472 3.9187660217 3.2026784420 5.8747177124 1182 47.2400000000 1.0336486101 0.2927169316 1.9872120619 0.0356686245 0.0074690000 0.0004100000 0.0044230000 0.0000000000 0.0000040000 0.0007400000 16968917 96830484 509673472 3.9200437069 3.1987304688 5.8755726814 1183 47.2800000000 1.0306490660 0.2933407120 1.9872120619 0.0356536895 0.0077670000 0.0004190000 0.0043970000 0.0000040000 0.0000030000 0.0009430000 16971693 96830484 509673472 3.9215230942 3.2018198967 5.8769207001 1184 47.3200000000 1.0322566032 0.2939647963 1.9872120619 0.0356391452 0.0075210000 0.0004150000 0.0044140000 0.0000010000 0.0000030000 0.0007390000 16974469 96830484 509673472 3.9225363731 3.1985120773 5.8765153885 1185 47.3600000000 1.0338451862 0.2945891680 1.9872120619 0.0356254907 0.0090090000 0.0004140000 0.0049510000 0.0000040000 0.0000040000 0.0013430000 16977245 96830484 509673472 3.9236652851 3.1954543591 5.8774013519 1186 47.4000000000 1.0384830236 0.2952163972 1.9872120619 0.0356139051 0.0076110000 0.0004330000 0.0045130000 0.0000010000 0.0000030000 0.0007390000 16980021 96830484 509673472 3.9245727062 3.1910109520 5.8773822784 1187 47.4400000000 1.0388908386 0.2958429132 1.9872120619 0.0355999071 0.0098700000 0.0005240000 0.0046630000 0.0000080000 0.0000070000 0.0010370000 16982797 96830484 509673472 3.9257199764 3.1910119057 5.8779926300 1188 47.4800000000 1.0390915871 0.2964685434 1.9872120619 0.0355854553 0.0064110000 0.0004470000 0.0027000000 0.0000000000 0.0000040000 0.0007470000 16985573 96830484 509673472 3.9265797138 3.1890974045 5.8788251877 1189 47.5200000000 1.0368689299 0.2970912518 1.9872120619 0.0355704824 0.0067440000 0.0004250000 0.0029940000 0.0000040000 0.0000040000 0.0013380000 16988349 96830484 509673472 3.9274077415 3.1887383461 5.8799366951 1190 47.5600000000 1.0409966707 0.2977163824 1.9872120619 0.0355574554 0.0098000000 0.0005220000 0.0046060000 0.0000010000 0.0000080000 0.0008470000 16991125 96830484 509673472 3.9284436703 3.1841740608 5.8806514740 1191 47.6000000000 1.0413596630 0.2983407681 1.9872120619 0.0355434635 0.0083270000 0.0004420000 0.0044150000 0.0000050000 0.0000040000 0.0009410000 16993901 96830484 509673472 3.9289402962 3.1838994026 5.8815116882 1192 47.6400000000 1.0412940979 0.2989640511 1.9872120619 0.0355291929 0.0074480000 0.0004240000 0.0043440000 0.0000010000 0.0000040000 0.0007440000 16996677 96830484 509673472 3.9290885925 3.1827213764 5.8815107346 1193 47.6800000000 1.0462946892 0.2995904808 1.9872120619 0.0355171367 0.0079970000 0.0004090000 0.0043280000 0.0000040000 0.0000040000 0.0013430000 16999453 96830484 509673472 3.9291603565 3.1783490181 5.8825731277 1194 47.7200000000 1.0473124981 0.3002167136 1.9872120619 0.0355044020 0.0086380000 0.0005090000 0.0028500000 0.0000010000 0.0000100000 0.0009110000 17002229 96830484 509673472 3.9293549061 3.1765332222 5.8825583458 1195 47.7600000000 1.0473858118 0.3008419597 1.9872120619 0.0354917000 0.0080860000 0.0004590000 0.0040420000 0.0000050000 0.0000050000 0.0009530000 17005005 96830484 509673472 3.9296555519 3.1766247749 5.8833703995 1196 47.8000000000 1.0465101004 0.3014654281 1.9872120619 0.0354797242 0.0075960000 0.0004270000 0.0043320000 0.0000000000 0.0000040000 0.0007530000 17007781 96830484 509673472 3.9295334816 3.1774971485 5.8826661110 1197 47.8400000000 1.0485925674 0.3020895944 1.9872120619 0.0354673923 0.0080160000 0.0004120000 0.0042940000 0.0000040000 0.0000030000 0.0013590000 17010557 96830484 509673472 3.9296805859 3.1734850407 5.8838238716 1198 47.8800000000 1.0488264561 0.3027129140 1.9872120619 0.0354532138 0.0073950000 0.0004120000 0.0042880000 0.0000000000 0.0000040000 0.0007530000 17013333 96830484 509673472 3.9299180508 3.1706957817 5.8846001625 1199 47.9200000000 1.0545696020 0.3033399838 1.9872120619 0.0354435187 0.0102290000 0.0005200000 0.0045340000 0.0000080000 0.0000070000 0.0010520000 17016109 96830484 509673472 3.9297211170 3.1655800343 5.8857989311 1200 47.9600000000 1.0559241772 0.3039671373 1.9872120619 0.0354341580 0.0080730000 0.0004440000 0.0043140000 0.0000010000 0.0000050000 0.0007640000 17018885 96830484 509673472 3.9293587208 3.1632955074 5.8860058784 1201 48.0000000000 1.0616323948 0.3045979993 1.9872120619 0.0354246154 0.0080930000 0.0004180000 0.0043120000 0.0000040000 0.0000030000 0.0013730000 17021661 96830484 509673472 3.9300737381 3.1575746536 5.8879818916 1202 48.0400000000 1.0631252527 0.3052290536 1.9872120619 0.0354116249 0.0099140000 0.0005100000 0.0045040000 0.0000010000 0.0000080000 0.0008520000 17024437 96830484 509673472 3.9304149151 3.1548035145 5.8885278702 1203 48.0800000000 1.0673747063 0.3058625911 1.9872120619 0.0353997613 0.0102360000 0.0005140000 0.0045440000 0.0000080000 0.0000070000 0.0010620000 17027213 96830484 509673472 3.9305999279 3.1503806114 5.8891305923 1204 48.1200000000 1.0632184744 0.3064916242 1.9872120619 0.0353861190 0.0100450000 0.0005120000 0.0045250000 0.0000010000 0.0000070000 0.0008550000 17029989 96830484 509673472 3.9313349724 3.1543512344 5.8883795738 1205 48.1600000000 1.0597531796 0.3071167376 1.9872120619 0.0353724870 0.0087130000 0.0004440000 0.0043240000 0.0000050000 0.0000050000 0.0013870000 17032765 96830484 509673472 3.9316968918 3.1570289135 5.8870663643 1206 48.2000000000 1.0540962219 0.3077361235 1.9872120619 0.0353600236 0.0074810000 0.0004260000 0.0042590000 0.0000010000 0.0000040000 0.0007640000 17035541 96830484 509673472 3.9318404198 3.1617414951 5.8852939606 1207 48.2400000000 1.0817095041 0.3083773608 1.9872120619 0.0353927137 0.0075760000 0.0004110000 0.0042580000 0.0000040000 0.0000040000 0.0009760000 17038317 96830484 509673472 3.9333310127 3.1314518452 5.8923134804 1208 48.2800000000 1.1037590504 0.3090357894 1.9872120619 0.0354053167 0.0074060000 0.0004140000 0.0042640000 0.0000010000 0.0000040000 0.0007890000 17041093 96830484 509673472 3.9343523979 3.1075971127 5.8981261253 1209 48.3200000000 1.1359328032 0.3097197406 1.9872120619 0.0354327956 0.0074150000 0.0004100000 0.0036080000 0.0000030000 0.0000040000 0.0014530000 17043869 96830484 509673472 3.9359028339 3.0745971203 5.9069261551 1210 48.3600000000 1.1456480026 0.3104105904 1.9872120619 0.0354263373 0.0098330000 0.0005260000 0.0045290000 0.0000010000 0.0000080000 0.0008780000 17046645 96830484 509673472 3.9374940395 3.0640354156 5.9095206261 1211 48.4000000000 1.1385345459 0.3110944252 1.9872120619 0.0354143163 0.0083230000 0.0004470000 0.0043200000 0.0000050000 0.0000050000 0.0009910000 17049421 96830484 509673472 3.9397361279 3.0703363419 5.9090719223 1212 48.4400000000 1.1391875744 0.3117776704 1.9872120619 0.0354107244 0.0074650000 0.0004280000 0.0042540000 0.0000010000 0.0000040000 0.0007970000 17052197 96830484 509673472 3.9429020882 3.0686149597 5.9098091125 1213 48.4800000000 1.1379057169 0.3124587322 1.9872120619 0.0353974136 0.0104660000 0.0005150000 0.0045180000 0.0000080000 0.0000070000 0.0015840000 17054973 96830484 509673472 3.9448852539 3.0700910091 5.9098801613 1214 48.5200000000 1.1397342682 0.3131401783 1.9872120619 0.0353855743 0.0081500000 0.0004490000 0.0043100000 0.0000000000 0.0000050000 0.0008010000 17057749 96830484 509673472 3.9471628666 3.0679490566 5.9102935791 1215 48.5600000000 1.1394096613 0.3138202355 1.9872120619 0.0353761413 0.0077210000 0.0004300000 0.0042450000 0.0000040000 0.0000030000 0.0010170000 17060525 96830484 509673472 3.9487707615 3.0674526691 5.9106860161 1216 48.6000000000 1.1381148100 0.3144981093 1.9872120619 0.0353680683 0.0100300000 0.0005290000 0.0045020000 0.0000010000 0.0000070000 0.0008850000 17063301 96830484 509673472 3.9515705109 3.0671844482 5.9111323357 1217 48.6400000000 1.1423629522 0.3151783598 1.9872120619 0.0353602711 0.0106310000 0.0005150000 0.0044880000 0.0000090000 0.0000070000 0.0015860000 17066077 96830484 509673472 3.9537439346 3.0636484623 5.9117512703 1218 48.6800000000 1.1476525068 0.3158618361 1.9872120619 0.0353545284 0.0100010000 0.0005200000 0.0044680000 0.0000010000 0.0000080000 0.0008860000 17068853 96830484 509673472 3.9562032223 3.0582077503 5.9137682915 1219 48.7200000000 1.1486753225 0.3165450301 1.9872120619 0.0353446027 0.0082840000 0.0004440000 0.0042640000 0.0000050000 0.0000050000 0.0010030000 17071629 96830484 509673472 3.9585447311 3.0566017628 5.9149718285 1220 48.7600000000 1.1320167780 0.3172134496 1.9872120619 0.0353352733 0.0074620000 0.0004300000 0.0041880000 0.0000010000 0.0000040000 0.0008020000 17074405 96830484 509673472 3.9614305496 3.0729765892 5.9111800194 1221 48.8000000000 1.1085726023 0.3178615734 1.9872120619 0.0353302689 0.0080170000 0.0004180000 0.0041780000 0.0000030000 0.0000030000 0.0014650000 17077181 96830484 509673472 3.9642453194 3.0953109264 5.9067645073 1222 48.8400000000 1.0972750187 0.3184993913 1.9872120619 0.0353209720 0.0063740000 0.0004160000 0.0031940000 0.0000000000 0.0000030000 0.0008010000 17079957 96830484 509673472 3.9674382210 3.1074564457 5.9033203125 1223 48.8800000000 1.1117248535 0.3191479812 1.9872120619 0.0353225176 0.0076190000 0.0004210000 0.0041890000 0.0000040000 0.0000040000 0.0009940000 17082733 96830484 509673472 3.9691770077 3.0923664570 5.9073004723 1224 48.9200000000 1.0938020945 0.3197808685 1.9872120619 0.0353127857 0.0073650000 0.0004170000 0.0041740000 0.0000010000 0.0000040000 0.0008030000 17085509 96830484 509673472 3.9718506336 3.1111965179 5.9024310112 1225 48.9600000000 1.0907325745 0.3204102168 1.9872120619 0.0353039472 0.0119490000 0.0006030000 0.0046510000 0.0000100000 0.0000090000 0.0017490000 17088285 96830484 509673472 3.9749016762 3.1138253212 5.9025044441 1226 49.0000000000 1.1022200584 0.3210479084 1.9872120619 0.0353004130 0.0084440000 0.0004650000 0.0043060000 0.0000000000 0.0000050000 0.0008130000 17091061 96830484 509673472 3.9774529934 3.1019611359 5.9054632187 1227 49.0400000000 1.0992426872 0.3216821340 1.9872120619 0.0352902438 0.0076820000 0.0004290000 0.0042010000 0.0000040000 0.0000030000 0.0009930000 17093837 96830484 509673472 3.9807333946 3.1053793430 5.9058008194 1228 49.0800000000 1.1056736708 0.3223205636 1.9872120619 0.0352829214 0.0074470000 0.0004160000 0.0041850000 0.0000010000 0.0000030000 0.0008100000 17096613 96830484 509673472 3.9832682610 3.0983853340 5.9077868462 1229 49.1200000000 1.1069761515 0.3229590140 1.9872120619 0.0352726567 0.0080440000 0.0004180000 0.0041680000 0.0000030000 0.0000030000 0.0014700000 17099389 96830484 509673472 3.9861893654 3.0973231792 5.9089550972 1230 49.1600000000 1.1084711552 0.3235976418 1.9872120619 0.0352636213 0.0073920000 0.0004180000 0.0041730000 0.0000000000 0.0000040000 0.0008120000 17102165 96830484 509673472 3.9880378246 3.0950512886 5.9090647697 1231 49.2000000000 1.1105813980 0.3242369462 1.9872120619 0.0352524656 0.0065530000 0.0004170000 0.0031740000 0.0000040000 0.0000040000 0.0009960000 17104941 96830484 509673472 3.9900159836 3.0940406322 5.9091143608 1232 49.2400000000 1.1128404140 0.3248770464 1.9872120619 0.0352421221 0.0091860000 0.0005190000 0.0037470000 0.0000010000 0.0000070000 0.0009050000 17107717 96830484 509673472 3.9922184944 3.0921542645 5.9098052979 1233 49.2800000000 1.1141353846 0.3255171586 1.9872120619 0.0352300259 0.0087140000 0.0004410000 0.0042170000 0.0000050000 0.0000050000 0.0014840000 17110493 96830484 509673472 3.9944007397 3.0913107395 5.9107799530 1234 49.3200000000 1.1150473356 0.3261569724 1.9872120619 0.0352183672 0.0074360000 0.0004250000 0.0041580000 0.0000000000 0.0000040000 0.0008280000 17113269 96830484 509673472 3.9964227676 3.0897514820 5.9114084244 1235 49.3600000000 1.1162501574 0.3267967239 1.9872120619 0.0352095568 0.0099990000 0.0005270000 0.0044120000 0.0000090000 0.0000070000 0.0010880000 17116045 96830484 509673472 3.9988112450 3.0888354778 5.9123582840 1236 49.4000000000 1.1490758657 0.3274619983 1.9872120619 0.0352337342 0.0082130000 0.0004530000 0.0042200000 0.0000000000 0.0000040000 0.0008290000 17118821 96830484 509673472 4.0008916855 3.0552473068 5.9222340584 1237 49.4400000000 1.1443312168 0.3281223615 1.9872120619 0.0352257021 0.0081170000 0.0004250000 0.0041680000 0.0000040000 0.0000040000 0.0014910000 17121597 96830484 509673472 4.0027847290 3.0612318516 5.9202556610 1238 49.4800000000 1.1451238394 0.3287822980 1.9872120619 0.0352224067 0.0096770000 0.0005190000 0.0043770000 0.0000010000 0.0000080000 0.0009140000 17124373 96830484 509673472 4.0042338371 3.0615286827 5.9193058014 1239 49.5200000000 1.1464538574 0.3294422428 1.9872120619 0.0352212990 0.0069660000 0.0004480000 0.0028810000 0.0000050000 0.0000040000 0.0010110000 17127149 96830484 509673472 4.0062747002 3.0605032444 5.9197087288 1240 49.5600000000 1.1447623968 0.3300997591 1.9872120619 0.0352166500 0.0074620000 0.0004250000 0.0041500000 0.0000010000 0.0000040000 0.0008210000 17129925 96830484 509673472 4.0077910423 3.0606620312 5.9200000763 1241 49.6000000000 1.1470866203 0.3307580885 1.9872120619 0.0352077025 0.0092880000 0.0005260000 0.0030270000 0.0000080000 0.0000070000 0.0016390000 17132701 96830484 509673472 4.0110578537 3.0586678982 5.9199728966 1242 49.6400000000 1.1454508305 0.3314140408 1.9872120619 0.0351958891 0.0100670000 0.0005190000 0.0044040000 0.0000010000 0.0000080000 0.0009190000 17135477 96830484 509673472 4.0112605095 3.0614910126 5.9191069603 1243 49.6800000000 1.1451584101 0.3320687024 1.9872120619 0.0351829726 0.0088730000 0.0005300000 0.0027050000 0.0000100000 0.0000100000 0.0011350000 17138253 96830484 509673472 4.0134081841 3.0613067150 5.9190468788 1244 49.7200000000 1.1387058496 0.3327171245 1.9872120619 0.0351689648 0.0163980000 0.0006850000 0.0046240000 0.0000020000 0.0000160000 0.0012540000 17141029 96830484 509673472 4.0144701004 3.0689382553 5.9163646698 1245 49.7600000000 1.1361720562 0.3333624699 1.9872120619 0.0351548572 0.0150960000 0.0006240000 0.0046180000 0.0000150000 0.0000150000 0.0021310000 17143805 96830484 509673472 4.0155644417 3.0727674961 5.9141860008 1246 49.8000000000 1.0761302710 0.3339585917 1.9872120619 0.0351875826 0.0090370000 0.0004860000 0.0042560000 0.0000010000 0.0000070000 0.0008830000 17146581 96830484 509673472 4.0132460594 3.1336474419 5.8964147568 1247 49.8400000000 1.0714486837 0.3345500032 1.9872120619 0.0351739980 0.0080060000 0.0004310000 0.0041400000 0.0000040000 0.0000030000 0.0010250000 17149357 96830484 509673472 4.0148429871 3.1395652294 5.8943157196 1248 49.8800000000 1.0665599108 0.3351365496 1.9872120619 0.0351608397 0.0074420000 0.0004240000 0.0040950000 0.0000000000 0.0000030000 0.0008440000 17152133 96830484 509673472 4.0142064095 3.1447975636 5.8919634819 1249 49.9200000000 1.0602108240 0.3357170734 1.9872120619 0.0351469649 0.0144080000 0.0006080000 0.0046410000 0.0000170000 0.0000140000 0.0021440000 17154909 96830484 509673472 4.0155353546 3.1502614021 5.8895115852 1250 49.9600000000 0.9000309110 0.3361685245 1.9872120619 0.0355385638 0.0088410000 0.0004810000 0.0042170000 0.0000010000 0.0000070000 0.0008930000 17157685 96830484 509673472 4.0231018066 3.3299484253 5.8584284782 1251 50.0000000000 0.8934047818 0.3366139571 1.9872120619 0.0355245023 0.0080130000 0.0004370000 0.0041480000 0.0000050000 0.0000040000 0.0010260000 17160461 96830484 509673472 4.0251607895 3.3373765945 5.8533692360 1252 50.0400000000 0.8972613811 0.3370617586 1.9872120619 0.0355121046 0.0067780000 0.0004220000 0.0034640000 0.0000000000 0.0000040000 0.0008500000 17163237 96830484 509673472 4.0267553329 3.3368003368 5.8568072319 1253 50.0800000000 0.8961792588 0.3375079817 1.9872120619 0.0354982376 0.0080770000 0.0004140000 0.0040860000 0.0000040000 0.0000030000 0.0015470000 17166013 96830484 509673472 4.0283985138 3.3382863998 5.8553552628 1254 50.1200000000 0.9218081236 0.3379739307 1.9872120619 0.0354976865 0.0073970000 0.0004150000 0.0040890000 0.0000010000 0.0000040000 0.0008510000 17168789 96830484 509673472 4.0330343246 3.3194940090 5.8720812798 1255 50.1600000000 0.9329164028 0.3384479885 1.9872120619 0.0354873165 0.0075630000 0.0004120000 0.0040890000 0.0000040000 0.0000040000 0.0010430000 17171565 96830484 509673472 4.0363473892 3.3113305569 5.8789544106 1256 50.2000000000 0.9615674615 0.3389441027 1.9872120619 0.0354881548 0.0098570000 0.0005260000 0.0043580000 0.0000010000 0.0000080000 0.0009610000 17174341 96830484 509673472 4.0449924469 3.2900650501 5.8975834846 1257 50.2400000000 0.9774829149 0.3394520890 1.9872120619 0.0354794401 0.0088310000 0.0004460000 0.0041860000 0.0000050000 0.0000040000 0.0015910000 17177117 96830484 509673472 4.0519447327 3.2767903805 5.9072418213 1258 50.2800000000 0.9836601615 0.3399641781 1.9872120619 0.0354665802 0.0074150000 0.0004200000 0.0040850000 0.0000010000 0.0000040000 0.0008720000 17179893 96830484 509673472 4.0532732010 3.2733411789 5.9092407227 1259 50.3200000000 0.9915664792 0.3404817336 1.9872120619 0.0354548168 0.0075810000 0.0004150000 0.0040750000 0.0000030000 0.0000030000 0.0010600000 17182669 96830484 509673472 4.0599927902 3.2674601078 5.9135785103 1260 50.3600000000 0.9894753695 0.3409968079 1.9872120619 0.0354416917 0.0073840000 0.0004120000 0.0040460000 0.0000000000 0.0000030000 0.0008670000 17185445 96830484 509673472 4.0594277382 3.2700014114 5.9092311859 1261 50.4000000000 0.9955651760 0.3415158946 1.9872120619 0.0354287783 0.0074590000 0.0004160000 0.0034070000 0.0000030000 0.0000030000 0.0016030000 17188221 96830484 509673472 4.0658874512 3.2658741474 5.9128203392 1262 50.4400000000 0.9915623665 0.3420309869 1.9872120619 0.0354147571 0.0100490000 0.0005170000 0.0043200000 0.0000010000 0.0000080000 0.0009790000 17190997 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1263 50.4800000000 0.9940953255 0.3425472690 1.9872120619 0.0354033844 0.0102010000 0.0005200000 0.0043270000 0.0000010000 0.0000080000 0.0009820000 17193773 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1264 50.5200000000 0.9954560995 0.3430638108 1.9872120619 0.0353920913 0.0081970000 0.0004460000 0.0041020000 0.0000000000 0.0000050000 0.0008900000 17196549 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1265 50.5600000000 0.9949201941 0.3435791123 1.9872120619 0.0353798156 0.0089810000 0.0004280000 0.0046060000 0.0000000000 0.0000040000 0.0014310000 17199325 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1266 50.6000000000 0.9963772297 0.3440947506 1.9872120619 0.0353672877 0.0074560000 0.0004730000 0.0040190000 0.0000000000 0.0000040000 0.0008770000 17202101 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1267 50.6400000000 0.9992084503 0.3446118096 1.9872120619 0.0353550077 0.0073620000 0.0004200000 0.0040240000 0.0000010000 0.0000030000 0.0008750000 17204877 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1268 50.6800000000 1.0008624792 0.3451293574 1.9872120619 0.0353487350 0.0101940000 0.0005190000 0.0042950000 0.0000010000 0.0000080000 0.0009610000 17207653 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1269 50.7200000000 1.0017328262 0.3456467755 1.9872120619 0.0353359015 0.0106160000 0.0005210000 0.0042340000 0.0000010000 0.0000090000 0.0015330000 17210429 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1270 50.7600000000 1.0029652119 0.3461643490 1.9872120619 0.0353234117 0.0080380000 0.0004500000 0.0039940000 0.0000000000 0.0000050000 0.0008720000 17213205 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1271 50.8000000000 1.0059274435 0.3466834388 1.9872120619 0.0353127228 0.0074130000 0.0004330000 0.0039360000 0.0000000000 0.0000030000 0.0008670000 17215981 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1272 50.8400000000 1.0072150230 0.3472027246 1.9872120619 0.0353017199 0.0072800000 0.0004170000 0.0039230000 0.0000010000 0.0000030000 0.0008640000 17218757 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1273 50.8800000000 1.0090820789 0.3477226613 1.9872120619 0.0352902933 0.0078100000 0.0004170000 0.0039200000 0.0000000000 0.0000040000 0.0013970000 17221533 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1274 50.9200000000 1.0117199421 0.3482438523 1.9872120619 0.0352793361 0.0101140000 0.0005440000 0.0041890000 0.0000010000 0.0000080000 0.0009600000 17224309 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1275 50.9600000000 1.0120798349 0.3487645079 1.9872120619 0.0352680228 0.0080240000 0.0004480000 0.0039750000 0.0000000000 0.0000050000 0.0008810000 17227085 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1276 51.0000000000 1.0127363205 0.3492848620 1.9872120619 0.0352563255 0.0074000000 0.0004340000 0.0039330000 0.0000000000 0.0000040000 0.0008670000 17229861 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1277 51.0400000000 1.0125035048 0.3498042188 1.9872120619 0.0352446718 0.0078370000 0.0004210000 0.0038870000 0.0000010000 0.0000040000 0.0014070000 17232637 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1278 51.0800000000 1.0124303102 0.3503227056 1.9872120619 0.0352328008 0.0072740000 0.0004230000 0.0038980000 0.0000010000 0.0000040000 0.0008670000 17235413 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1279 51.1200000000 1.0121798515 0.3508401858 1.9872120619 0.0352205902 0.0106000000 0.0005240000 0.0042130000 0.0000010000 0.0000110000 0.0010580000 17238189 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1280 51.1600000000 1.0121223927 0.3513568125 1.9872120619 0.0352077746 0.0083160000 0.0004690000 0.0040020000 0.0000010000 0.0000060000 0.0008820000 17240965 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1281 51.2000000000 1.0156553984 0.3518753906 1.9872120619 0.0351947310 0.0080610000 0.0004320000 0.0040100000 0.0000000000 0.0000030000 0.0014050000 17243741 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1282 51.2400000000 1.0169498920 0.3523941695 1.9872120619 0.0351815903 0.0073750000 0.0004170000 0.0039960000 0.0000010000 0.0000030000 0.0008660000 17246517 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1283 51.2800000000 1.0166376829 0.3529118963 1.9872120619 0.0351684267 0.0099200000 0.0005190000 0.0042970000 0.0000010000 0.0000080000 0.0009640000 17249293 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1284 51.3200000000 1.0172278881 0.3534292764 1.9872120619 0.0351552161 0.0081950000 0.0004430000 0.0041010000 0.0000010000 0.0000050000 0.0008780000 17252069 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1285 51.3600000000 1.0181902647 0.3539466001 1.9872120619 0.0351421020 0.0079450000 0.0004230000 0.0040050000 0.0000000000 0.0000040000 0.0014150000 17254845 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1286 51.4000000000 1.0182963610 0.3544632018 1.9872120619 0.0351293842 0.0073980000 0.0004190000 0.0039960000 0.0000000000 0.0000040000 0.0008800000 17257621 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1287 51.4400000000 1.0179713964 0.3549787481 1.9872120619 0.0351161933 0.0099120000 0.0005510000 0.0042540000 0.0000010000 0.0000080000 0.0009590000 17260397 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1288 51.4800000000 1.0165601969 0.3554923983 1.9872120619 0.0351032308 0.0100490000 0.0005170000 0.0043120000 0.0000010000 0.0000080000 0.0009700000 17263173 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1289 51.5200000000 1.0185914040 0.3560068274 1.9872120619 0.0350901884 0.0087870000 0.0004490000 0.0040810000 0.0000010000 0.0000050000 0.0014170000 17265949 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1290 51.5600000000 1.0192693472 0.3565209844 1.9872120619 0.0350769977 0.0076220000 0.0004350000 0.0040430000 0.0000010000 0.0000040000 0.0008720000 17268725 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1291 51.6000000000 1.0195264816 0.3570345440 1.9872120619 0.0350639590 0.0074810000 0.0004150000 0.0040590000 0.0000010000 0.0000040000 0.0008700000 17271501 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1292 51.6400000000 1.0202662945 0.3575478813 1.9872120619 0.0350508889 0.0074780000 0.0004220000 0.0040480000 0.0000010000 0.0000040000 0.0008700000 17274277 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1293 51.6800000000 1.0213177204 0.3580612377 1.9872120619 0.0350377714 0.0080010000 0.0004140000 0.0040580000 0.0000000000 0.0000040000 0.0014130000 17277053 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1294 51.7200000000 1.0210269690 0.3585735760 1.9872120619 0.0350248781 0.0074520000 0.0004140000 0.0040390000 0.0000000000 0.0000030000 0.0008740000 17279829 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1295 51.7600000000 1.0208121538 0.3590849571 1.9872120619 0.0350118928 0.0112960000 0.0005240000 0.0043600000 0.0000010000 0.0000100000 0.0010630000 17282605 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1296 51.8000000000 1.0230506659 0.3595972763 1.9872120619 0.0350000181 0.0085310000 0.0004710000 0.0041400000 0.0000010000 0.0000060000 0.0008830000 17285381 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1297 51.8400000000 1.0225311518 0.3601084050 1.9872120619 0.0349866386 0.0108280000 0.0005160000 0.0043350000 0.0000010000 0.0000080000 0.0015410000 17288157 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1298 51.8800000000 1.0253170729 0.3606208924 1.9872120619 0.0349733405 0.0082710000 0.0004550000 0.0041320000 0.0000010000 0.0000050000 0.0008720000 17290933 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1299 51.9200000000 1.0269275904 0.3611338306 1.9872120619 0.0349600574 0.0076180000 0.0004300000 0.0040920000 0.0000000000 0.0000040000 0.0008730000 17293709 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1300 51.9600000000 1.0281865597 0.3616469481 1.9872120619 0.0349467812 0.0104160000 0.0005170000 0.0043520000 0.0000010000 0.0000080000 0.0009610000 17296485 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1301 52.0000000000 1.0301120281 0.3621607567 1.9872120619 0.0349334759 0.0088170000 0.0004490000 0.0041320000 0.0000010000 0.0000060000 0.0014090000 17299261 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1302 52.0400000000 1.0337098837 0.3626765395 1.9872120619 0.0349210119 0.0075800000 0.0004300000 0.0040790000 0.0000000000 0.0000030000 0.0008680000 17302037 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1303 52.0800000000 1.0382682085 0.3631950289 1.9872120619 0.0349092995 0.0075060000 0.0004220000 0.0040520000 0.0000010000 0.0000040000 0.0008670000 17304813 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1304 52.1200000000 1.0403287411 0.3637143032 1.9872120619 0.0348965239 0.0104980000 0.0005330000 0.0043910000 0.0000010000 0.0000090000 0.0009570000 17307589 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1305 52.1600000000 1.0433406830 0.3642350897 1.9872120619 0.0348835150 0.0088810000 0.0004520000 0.0041900000 0.0000010000 0.0000050000 0.0014140000 17310365 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1306 52.2000000000 1.0476477146 0.3647583765 1.9872120619 0.0348704881 0.0076390000 0.0004310000 0.0041300000 0.0000000000 0.0000040000 0.0008650000 17313141 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1307 52.2400000000 1.0509803295 0.3652834124 1.9872120619 0.0348575779 0.0103800000 0.0005190000 0.0044040000 0.0000010000 0.0000080000 0.0009560000 17315917 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1308 52.2800000000 1.0537202358 0.3658097403 1.9872120619 0.0348445169 0.0083360000 0.0004500000 0.0041910000 0.0000010000 0.0000050000 0.0008700000 17318693 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1309 52.3200000000 1.0565713644 0.3663374421 1.9872120619 0.0348312812 0.0082210000 0.0004300000 0.0042060000 0.0000000000 0.0000030000 0.0014010000 17321469 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1310 52.3600000000 1.0591170788 0.3668662815 1.9872120619 0.0348185075 0.0076050000 0.0004180000 0.0041740000 0.0000000000 0.0000030000 0.0008700000 17324245 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1311 52.4000000000 1.0639003515 0.3673979627 1.9872120619 0.0348060438 0.0104500000 0.0005210000 0.0044700000 0.0000010000 0.0000080000 0.0009530000 17327021 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1312 52.4400000000 1.0699366331 0.3679334342 1.9872120619 0.0347933605 0.0085740000 0.0004480000 0.0043180000 0.0000000000 0.0000050000 0.0008820000 17329797 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1313 52.4800000000 1.0753822327 0.3684722376 1.9872120619 0.0347805559 0.0081100000 0.0004290000 0.0040530000 0.0000000000 0.0000030000 0.0014110000 17332573 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1314 52.5200000000 1.0824034214 0.3690155642 1.9872120619 0.0347681719 0.0074910000 0.0004140000 0.0040390000 0.0000010000 0.0000030000 0.0008740000 17335349 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1315 52.5600000000 1.0893149376 0.3695633204 1.9872120619 0.0347555705 0.0074590000 0.0004150000 0.0040330000 0.0000000000 0.0000030000 0.0008680000 17338125 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1316 52.6000000000 1.0954624414 0.3701149155 1.9872120619 0.0347427020 0.0074840000 0.0004170000 0.0040310000 0.0000000000 0.0000040000 0.0008710000 17340901 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1317 52.6400000000 1.1030738354 0.3706714522 1.9872120619 0.0347301187 0.0085060000 0.0004160000 0.0044390000 0.0000000000 0.0000040000 0.0014150000 17343677 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1318 52.6800000000 1.1113044024 0.3712333892 1.9872120619 0.0347176964 0.0106010000 0.0005160000 0.0046500000 0.0000010000 0.0000090000 0.0009690000 17346453 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1319 52.7200000000 1.1193113327 0.3718005446 1.9872120619 0.0347050508 0.0087590000 0.0004520000 0.0045210000 0.0000010000 0.0000060000 0.0008770000 17349229 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1320 52.7600000000 1.1281242371 0.3723735171 1.9872120619 0.0346925303 0.0080190000 0.0004290000 0.0044690000 0.0000010000 0.0000040000 0.0008840000 17352005 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1321 52.8000000000 1.1389032602 0.3729537819 1.9872120619 0.0346807133 0.0082900000 0.0004180000 0.0042420000 0.0000010000 0.0000030000 0.0014200000 17354781 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1322 52.8400000000 1.1478427649 0.3735399309 1.9872120619 0.0346681703 0.0079940000 0.0004170000 0.0044870000 0.0000000000 0.0000040000 0.0008740000 17357557 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1323 52.8800000000 1.1565730572 0.3741317926 1.9872120619 0.0346556482 0.0077400000 0.0004220000 0.0042370000 0.0000010000 0.0000040000 0.0008700000 17360333 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1324 52.9200000000 1.1680401564 0.3747314213 1.9872120619 0.0346440887 0.0087350000 0.0004200000 0.0047710000 0.0000010000 0.0000040000 0.0008810000 17363109 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1325 52.9600000000 1.1787555218 0.3753382319 1.9872120619 0.0346323964 0.0083440000 0.0004720000 0.0041980000 0.0000000000 0.0000040000 0.0014120000 17365885 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1326 53.0000000000 1.1891007423 0.3759519292 1.9872120619 0.0346206049 0.0077420000 0.0004240000 0.0041970000 0.0000000000 0.0000040000 0.0008730000 17368661 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1327 53.0400000000 1.1993544102 0.3765724284 1.9872120619 0.0346085732 0.0076650000 0.0004240000 0.0041570000 0.0000000000 0.0000030000 0.0008680000 17371437 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1328 53.0800000000 1.2112007141 0.3772009136 1.9872120619 0.0345975403 0.0077150000 0.0004340000 0.0041820000 0.0000010000 0.0000040000 0.0008690000 17374213 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1329 53.1200000000 1.2199494839 0.3778350359 1.9872120619 0.0345852737 0.0081830000 0.0004210000 0.0041650000 0.0000010000 0.0000030000 0.0014020000 17376989 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1330 53.1600000000 1.2281343937 0.3784743587 1.9872120619 0.0345728817 0.0077160000 0.0004240000 0.0041030000 0.0000000000 0.0000030000 0.0008760000 17379765 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1331 53.2000000000 1.2403303385 0.3791218839 1.9872120619 0.0345626049 0.0075450000 0.0004220000 0.0040270000 0.0000000000 0.0000030000 0.0008730000 17382541 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1332 53.2400000000 1.2534945011 0.3797783198 1.9872120619 0.0345525467 0.0131540000 0.0006080000 0.0045850000 0.0000020000 0.0000160000 0.0012500000 17385317 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1333 53.2800000000 1.2640203238 0.3804416671 1.9872120619 0.0345405792 0.0093900000 0.0004700000 0.0041500000 0.0000000000 0.0000060000 0.0014240000 17388093 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1334 53.3200000000 1.2743897438 0.3811117931 1.9872120619 0.0345290820 0.0077260000 0.0004420000 0.0040390000 0.0000010000 0.0000050000 0.0008660000 17390869 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1335 53.3600000000 1.2848036289 0.3817887158 1.9872120619 0.0345175860 0.0075070000 0.0004280000 0.0040210000 0.0000000000 0.0000040000 0.0008660000 17393645 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1336 53.4000000000 1.2940695286 0.3824715607 1.9872120619 0.0345054902 0.0075200000 0.0004260000 0.0040210000 0.0000010000 0.0000040000 0.0008740000 17396421 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1337 53.4400000000 1.3018615246 0.3831592122 1.9872120619 0.0344929155 0.0080620000 0.0004210000 0.0040270000 0.0000000000 0.0000030000 0.0014130000 17399197 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1338 53.4800000000 1.3117525578 0.3838532281 1.9872120619 0.0344808675 0.0075190000 0.0004220000 0.0040200000 0.0000010000 0.0000030000 0.0008680000 17401973 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1339 53.5200000000 1.3240084648 0.3845553605 1.9872120619 0.0344707538 0.0100300000 0.0005240000 0.0043130000 0.0000000000 0.0000080000 0.0009520000 17404749 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1340 53.5600000000 1.3425782919 0.3852703030 1.9872120619 0.0344643261 0.0082780000 0.0004530000 0.0040960000 0.0000000000 0.0000040000 0.0008750000 17407525 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1341 53.6000000000 1.3535200357 0.3859923386 1.9872120619 0.0344540670 0.0110030000 0.0005200000 0.0043290000 0.0000010000 0.0000080000 0.0015360000 17410301 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1342 53.6400000000 1.3626778126 0.3867201221 1.9872120619 0.0344428223 0.0083460000 0.0004500000 0.0041190000 0.0000000000 0.0000040000 0.0008740000 17413077 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1343 53.6800000000 1.3676445484 0.3874505200 1.9872120619 0.0344301633 0.0076460000 0.0004330000 0.0040610000 0.0000010000 0.0000040000 0.0008670000 17415853 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1344 53.7200000000 1.3731838465 0.3881839525 1.9872120619 0.0344178979 0.0105030000 0.0005330000 0.0043310000 0.0000010000 0.0000080000 0.0009550000 17418629 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1345 53.7600000000 1.3796436787 0.3889210973 1.9872120619 0.0344061680 0.0089450000 0.0004460000 0.0041310000 0.0000000000 0.0000050000 0.0014150000 17421405 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1346 53.8000000000 1.3835062981 0.3896600165 1.9872120619 0.0343943845 0.0074590000 0.0004320000 0.0038770000 0.0000000000 0.0000040000 0.0008660000 17424181 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1347 53.8400000000 1.3975435495 0.3904082596 1.9872120619 0.0343924681 0.0102220000 0.0005170000 0.0041870000 0.0000010000 0.0000080000 0.0009670000 17426957 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1348 53.8800000000 1.4053996801 0.3911612206 1.9872120619 0.0343815111 0.0082530000 0.0004590000 0.0039680000 0.0000000000 0.0000050000 0.0008760000 17429733 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1349 53.9200000000 1.4095737934 0.3919161595 1.9872120619 0.0343688556 0.0082160000 0.0004310000 0.0041130000 0.0000010000 0.0000040000 0.0014250000 17432509 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1350 53.9600000000 1.4136743546 0.3926730175 1.9872120619 0.0343562469 0.0100430000 0.0005240000 0.0041200000 0.0000000000 0.0000090000 0.0009520000 17435285 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1351 54.0000000000 1.4156453609 0.3934302139 1.9872120619 0.0343435833 0.0081840000 0.0004510000 0.0039370000 0.0000010000 0.0000050000 0.0008760000 17438061 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1352 54.0400000000 1.4175130129 0.3941876716 1.9872120619 0.0343308805 0.0074520000 0.0004270000 0.0038840000 0.0000010000 0.0000040000 0.0008730000 17440837 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1353 54.0800000000 1.4220827818 0.3949473871 1.9872120619 0.0343190095 0.0107490000 0.0005230000 0.0042490000 0.0000010000 0.0000070000 0.0015280000 17443613 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1354 54.1200000000 1.4251523018 0.3957082474 1.9872120619 0.0343071697 0.0082990000 0.0005090000 0.0041300000 0.0000010000 0.0000050000 0.0008780000 17446389 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1355 54.1600000000 1.4278711081 0.3964699912 1.9872120619 0.0342954250 0.0074020000 0.0004280000 0.0038700000 0.0000000000 0.0000040000 0.0008660000 17449165 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1356 54.2000000000 1.4312771559 0.3972331234 1.9872120619 0.0342841332 0.0076000000 0.0004220000 0.0040580000 0.0000000000 0.0000030000 0.0008720000 17451941 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1357 54.2400000000 1.4339028597 0.3979970657 1.9872120619 0.0342728442 0.0079350000 0.0004250000 0.0038040000 0.0000000000 0.0000030000 0.0014020000 17454717 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1358 54.2800000000 1.4345006943 0.3987603232 1.9872120619 0.0342607396 0.0076820000 0.0004260000 0.0041170000 0.0000000000 0.0000040000 0.0008740000 17457493 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1359 54.3200000000 1.4357162714 0.3995233518 1.9872120619 0.0342482660 0.0122080000 0.0006080000 0.0046790000 0.0000010000 0.0000110000 0.0010770000 17460269 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1360 54.3600000000 1.4408737421 0.4002890506 1.9872120619 0.0342367382 0.0087730000 0.0004720000 0.0041210000 0.0000010000 0.0000060000 0.0008890000 17463045 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1361 54.4000000000 1.4416450262 0.4010541910 1.9872120619 0.0342250870 0.0086420000 0.0004410000 0.0044340000 0.0000010000 0.0000040000 0.0014110000 17465821 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1362 54.4400000000 1.4434925318 0.4018195642 1.9872120619 0.0342133299 0.0081110000 0.0004200000 0.0045270000 0.0000000000 0.0000040000 0.0008810000 17468597 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1363 54.4800000000 1.4462968111 0.4025858718 1.9872120619 0.0342021347 0.0105690000 0.0005320000 0.0041570000 0.0000010000 0.0000110000 0.0009560000 17471373 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1364 54.5200000000 1.4467326403 0.4033513753 1.9872120619 0.0341910554 0.0082990000 0.0004530000 0.0040040000 0.0000010000 0.0000050000 0.0008690000 17474149 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1365 54.5600000000 1.4454920292 0.4041148483 1.9872120619 0.0341793305 0.0081220000 0.0004300000 0.0039510000 0.0000010000 0.0000040000 0.0014100000 17476925 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1366 54.6000000000 1.4460675716 0.4048776248 1.9872120619 0.0341674261 0.0105900000 0.0005400000 0.0042090000 0.0000010000 0.0000080000 0.0009780000 17479701 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1367 54.6400000000 1.4498311281 0.4056420385 1.9872120619 0.0341572671 0.0082680000 0.0004470000 0.0039380000 0.0000000000 0.0000040000 0.0008800000 17482477 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1368 54.6800000000 1.4499720335 0.4064054376 1.9872120619 0.0341461730 0.0076320000 0.0004230000 0.0039270000 0.0000000000 0.0000030000 0.0008740000 17485253 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1369 54.7200000000 1.4519459009 0.4071691633 1.9872120619 0.0341351219 0.0104400000 0.0005310000 0.0040080000 0.0000010000 0.0000080000 0.0015340000 17488029 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1370 54.7600000000 1.4561352730 0.4079348320 1.9872120619 0.0341247049 0.0081450000 0.0004590000 0.0038090000 0.0000000000 0.0000050000 0.0008800000 17490805 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1371 54.8000000000 1.4584928751 0.4087011033 1.9872120619 0.0341137315 0.0103740000 0.0005190000 0.0042180000 0.0000010000 0.0000080000 0.0009500000 17493581 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1372 54.8400000000 1.4633206129 0.4094697765 1.9872120619 0.0341036738 0.0104290000 0.0005190000 0.0042310000 0.0000000000 0.0000080000 0.0009530000 17496357 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1373 54.8800000000 1.4662423134 0.4102394578 1.9872120619 0.0340942710 0.0088600000 0.0004550000 0.0040110000 0.0000010000 0.0000050000 0.0014140000 17499133 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1374 54.9200000000 1.4673593044 0.4110088318 1.9872120619 0.0340844854 0.0074040000 0.0004330000 0.0037840000 0.0000010000 0.0000040000 0.0008660000 17501909 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1375 54.9600000000 1.4698052406 0.4117788656 1.9872120619 0.0340748797 0.0075390000 0.0004220000 0.0039960000 0.0000010000 0.0000030000 0.0008640000 17504685 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1376 55.0000000000 1.4727175236 0.4125498966 1.9872120619 0.0340657862 0.0073220000 0.0004180000 0.0037750000 0.0000010000 0.0000040000 0.0008620000 17507461 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1377 55.0400000000 1.4751785994 0.4133215950 1.9872120619 0.0340571159 0.0111120000 0.0005320000 0.0042690000 0.0000000000 0.0000080000 0.0015490000 17510237 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1378 55.0800000000 1.4767149687 0.4140932883 1.9872120619 0.0340484143 0.0104690000 0.0005230000 0.0042980000 0.0000000000 0.0000080000 0.0009610000 17513013 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1379 55.1200000000 1.4790129662 0.4148655288 1.9872120619 0.0340390899 0.0104330000 0.0005180000 0.0042690000 0.0000000000 0.0000080000 0.0009620000 17515789 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1380 55.1600000000 1.4827270508 0.4156393415 1.9872120619 0.0340312391 0.0083720000 0.0004490000 0.0040020000 0.0000000000 0.0000050000 0.0008780000 17518565 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1381 55.2000000000 1.4850631952 0.4164137252 1.9872120619 0.0340238007 0.0081730000 0.0004340000 0.0039960000 0.0000000000 0.0000040000 0.0014070000 17521341 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1382 55.2400000000 1.4866058826 0.4171881044 1.9872120619 0.0340160174 0.0073830000 0.0004250000 0.0037870000 0.0000010000 0.0000040000 0.0008670000 17524117 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1383 55.2800000000 1.4906302691 0.4179642738 1.9872120619 0.0340090017 0.0073600000 0.0004240000 0.0037630000 0.0000010000 0.0000030000 0.0008680000 17526893 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1384 55.3200000000 1.4932402372 0.4187412073 1.9872120619 0.0340024709 0.0076670000 0.0004310000 0.0039830000 0.0000010000 0.0000040000 0.0008750000 17529669 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1385 55.3600000000 1.4961341619 0.4195191083 1.9872120619 0.0339962162 0.0081340000 0.0004210000 0.0040040000 0.0000000000 0.0000030000 0.0014030000 17532445 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1386 55.4000000000 1.4991286993 0.4202980474 1.9872120619 0.0339898410 0.0099560000 0.0005180000 0.0041990000 0.0000010000 0.0000080000 0.0009570000 17535221 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1387 55.4400000000 1.5002249479 0.4210766537 1.9872120619 0.0339843194 0.0082660000 0.0004500000 0.0040480000 0.0000000000 0.0000050000 0.0008820000 17537997 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1388 55.4800000000 1.5005441904 0.4218543680 1.9872120619 0.0339770252 0.0076210000 0.0004270000 0.0039750000 0.0000000000 0.0000040000 0.0008720000 17540773 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1389 55.5200000000 1.5018545389 0.4226319060 1.9872120619 0.0339682116 0.0080850000 0.0004150000 0.0039710000 0.0000000000 0.0000040000 0.0014060000 17543549 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1390 55.5600000000 1.5036125183 0.4234095899 1.9872120619 0.0339599153 0.0075820000 0.0004150000 0.0039870000 0.0000000000 0.0000040000 0.0008730000 17546325 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1391 55.6000000000 1.5062968731 0.4241880854 1.9872120619 0.0339509394 0.0075400000 0.0004130000 0.0039690000 0.0000000000 0.0000040000 0.0008700000 17549101 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1392 55.6400000000 1.5074810982 0.4249663131 1.9872120619 0.0339415177 0.0075940000 0.0004160000 0.0039870000 0.0000000000 0.0000040000 0.0008720000 17551877 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1393 55.6800000000 1.5088280439 0.4257443905 1.9872120619 0.0339321566 0.0108850000 0.0005140000 0.0042400000 0.0000000000 0.0000130000 0.0015680000 17554653 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1394 55.7200000000 1.5093631744 0.4265217354 1.9872120619 0.0339235444 0.0082390000 0.0004480000 0.0038990000 0.0000010000 0.0000050000 0.0008970000 17557429 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1395 55.7600000000 1.5095924139 0.4272981301 1.9872120619 0.0339151964 0.0074360000 0.0004260000 0.0037620000 0.0000000000 0.0000030000 0.0008760000 17560205 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1396 55.8000000000 1.5121566057 0.4280752494 1.9872120619 0.0339083239 0.0073590000 0.0004140000 0.0037080000 0.0000000000 0.0000040000 0.0008770000 17562981 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1397 55.8400000000 1.5121029615 0.4288512177 1.9872120619 0.0339026789 0.0081570000 0.0004230000 0.0038160000 0.0000010000 0.0000040000 0.0014300000 17565757 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1398 55.8800000000 1.5117796659 0.4296258446 1.9872120619 0.0338945714 0.0073930000 0.0004210000 0.0036700000 0.0000000000 0.0000030000 0.0008690000 17568533 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1399 55.9200000000 1.5128507614 0.4304001297 1.9872120619 0.0338851802 0.0106120000 0.0005190000 0.0041900000 0.0000010000 0.0000080000 0.0009710000 17571309 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1400 55.9600000000 1.5154466629 0.4311751630 1.9872120619 0.0338756458 0.0084250000 0.0004420000 0.0039930000 0.0000010000 0.0000050000 0.0008770000 17574085 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1401 56.0000000000 1.5163348913 0.4319497238 1.9872120619 0.0338658291 0.0081570000 0.0004250000 0.0039290000 0.0000000000 0.0000040000 0.0014140000 17576861 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1402 56.0400000000 1.5161360502 0.4327230379 1.9872120619 0.0338558795 0.0075210000 0.0004220000 0.0038380000 0.0000000000 0.0000040000 0.0008740000 17579637 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1403 56.0800000000 1.5162633657 0.4334953403 1.9872120619 0.0338456269 0.0075170000 0.0004150000 0.0038750000 0.0000010000 0.0000040000 0.0008670000 17582413 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1404 56.1200000000 1.5184597969 0.4342681070 1.9872120619 0.0338363532 0.0075420000 0.0004150000 0.0038880000 0.0000000000 0.0000040000 0.0008720000 17585189 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1405 56.1600000000 1.5195777416 0.4350405694 1.9872120619 0.0338279107 0.0081260000 0.0004190000 0.0039290000 0.0000010000 0.0000040000 0.0014110000 17587965 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1406 56.2000000000 1.5235418081 0.4358147524 1.9872120619 0.0338314045 0.0077860000 0.0004160000 0.0041460000 0.0000010000 0.0000040000 0.0008720000 17590741 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1407 56.2400000000 1.5266256332 0.4365900266 1.9872120619 0.0338242057 0.0104190000 0.0005240000 0.0044070000 0.0000000000 0.0000080000 0.0009770000 17593517 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1408 56.2800000000 1.5267610550 0.4373642958 1.9872120619 0.0338162102 0.0085980000 0.0004470000 0.0042990000 0.0000010000 0.0000050000 0.0008800000 17596293 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1409 56.3200000000 1.5265138149 0.4381372905 1.9872120619 0.0338072852 0.0084090000 0.0004220000 0.0042340000 0.0000000000 0.0000030000 0.0014130000 17599069 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1410 56.3600000000 1.5302885771 0.4389118659 1.9872120619 0.0338010437 0.0078640000 0.0004170000 0.0042270000 0.0000000000 0.0000040000 0.0008710000 17601845 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1411 56.4000000000 1.5320887566 0.4396866192 1.9872120619 0.0337945896 0.0079190000 0.0004190000 0.0042030000 0.0000000000 0.0000030000 0.0008770000 17604621 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1412 56.4400000000 1.5313948393 0.4404597836 1.9872120619 0.0337858375 0.0078950000 0.0004150000 0.0042150000 0.0000010000 0.0000030000 0.0008790000 17607397 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1413 56.4800000000 1.5343891382 0.4412339728 1.9872120619 0.0337772165 0.0118370000 0.0005130000 0.0044580000 0.0000010000 0.0000080000 0.0018380000 17610173 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1414 56.5200000000 1.5386611223 0.4420100882 1.9872120619 0.0337685325 0.0086230000 0.0005090000 0.0042770000 0.0000010000 0.0000060000 0.0008800000 17612949 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1415 56.5600000000 1.5411981344 0.4427868996 1.9872120619 0.0337585256 0.0078680000 0.0004270000 0.0041890000 0.0000000000 0.0000030000 0.0008700000 17615725 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1416 56.6000000000 1.5455038548 0.4435656545 1.9872120619 0.0337496122 0.0078570000 0.0004260000 0.0041700000 0.0000000000 0.0000030000 0.0008740000 17618501 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1417 56.6400000000 1.5490992069 0.4443458475 1.9872120619 0.0337418245 0.0083460000 0.0004200000 0.0041590000 0.0000010000 0.0000040000 0.0014070000 17621277 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1418 56.6800000000 1.5519039631 0.4451269181 1.9872120619 0.0337345654 0.0078140000 0.0004220000 0.0041330000 0.0000000000 0.0000040000 0.0008730000 17624053 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1419 56.7200000000 1.5542172194 0.4459085181 1.9872120619 0.0337276318 0.0108000000 0.0005200000 0.0044090000 0.0000010000 0.0000090000 0.0009590000 17626829 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1420 56.7600000000 1.5574777126 0.4466913133 1.9872120619 0.0337204357 0.0106930000 0.0005160000 0.0043620000 0.0000010000 0.0000080000 0.0009520000 17629605 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1421 56.8000000000 1.5594627857 0.4474744037 1.9872120619 0.0337126520 0.0091380000 0.0004510000 0.0041620000 0.0000000000 0.0000040000 0.0014110000 17632381 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1422 56.8400000000 1.5621345043 0.4482582715 1.9872120619 0.0337045105 0.0077650000 0.0004330000 0.0040660000 0.0000000000 0.0000030000 0.0008800000 17635157 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1423 56.8800000000 1.5659022331 0.4490436854 1.9872120619 0.0336963013 0.0077400000 0.0004250000 0.0040560000 0.0000010000 0.0000040000 0.0008760000 17637933 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1424 56.9200000000 1.5694190264 0.4498304659 1.9872120619 0.0336880816 0.0103260000 0.0005300000 0.0042650000 0.0000000000 0.0000090000 0.0009550000 17640709 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1425 56.9600000000 1.5691351891 0.4506159429 1.9872120619 0.0336787237 0.0088140000 0.0004530000 0.0039940000 0.0000000000 0.0000050000 0.0014220000 17643485 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1426 57.0000000000 1.5713641644 0.4514018813 1.9872120619 0.0336692093 0.0105350000 0.0005210000 0.0041330000 0.0000010000 0.0000080000 0.0009530000 17646261 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1427 57.0400000000 1.5747394562 0.4521890835 1.9872120619 0.0336604447 0.0083550000 0.0004520000 0.0039070000 0.0000000000 0.0000040000 0.0008720000 17649037 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1428 57.0800000000 1.5766804218 0.4529765425 1.9872120619 0.0336516134 0.0080180000 0.0004350000 0.0042290000 0.0000010000 0.0000040000 0.0008760000 17651813 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1429 57.1200000000 1.5794533491 0.4537648397 1.9872120619 0.0336425842 0.0084410000 0.0004290000 0.0042030000 0.0000000000 0.0000050000 0.0014070000 17654589 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1430 57.1600000000 1.5822168589 0.4545539670 1.9872120619 0.0336342362 0.0078530000 0.0004250000 0.0041510000 0.0000000000 0.0000030000 0.0008690000 17657365 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1431 57.2000000000 1.5833880901 0.4553428099 1.9872120619 0.0336260293 0.0077670000 0.0004200000 0.0040970000 0.0000010000 0.0000030000 0.0008670000 17660141 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1432 57.2400000000 1.5853271484 0.4561319051 1.9872120619 0.0336175681 0.0079080000 0.0004210000 0.0041560000 0.0000000000 0.0000030000 0.0008690000 17662917 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1433 57.2800000000 1.5881730318 0.4569218849 1.9872120619 0.0336092924 0.0111790000 0.0005200000 0.0043870000 0.0000000000 0.0000080000 0.0015470000 17665693 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1434 57.3200000000 1.5901474953 0.4577121399 1.9872120619 0.0336022523 0.0084550000 0.0004540000 0.0040310000 0.0000000000 0.0000050000 0.0008750000 17668469 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1435 57.3600000000 1.5923897028 0.4585028560 1.9872120619 0.0335955494 0.0079490000 0.0004450000 0.0042250000 0.0000000000 0.0000030000 0.0008670000 17671245 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1436 57.4000000000 1.5950511694 0.4592943241 1.9872120619 0.0335885613 0.0076130000 0.0004270000 0.0039140000 0.0000000000 0.0000030000 0.0008670000 17674021 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1437 57.4400000000 1.5974985361 0.4600863939 1.9872120619 0.0335817093 0.0081440000 0.0004220000 0.0038550000 0.0000000000 0.0000030000 0.0014150000 17676797 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1438 57.4800000000 1.6024351120 0.4608807949 1.9872120619 0.0335743888 0.0076950000 0.0004250000 0.0039220000 0.0000010000 0.0000040000 0.0008740000 17679573 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1439 57.5200000000 1.6085932255 0.4616783713 1.9872120619 0.0335686246 0.0076200000 0.0004330000 0.0038950000 0.0000000000 0.0000040000 0.0008740000 17682349 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1440 57.5600000000 1.6120040417 0.4624772086 1.9872120619 0.0335620549 0.0075200000 0.0004200000 0.0038090000 0.0000000000 0.0000040000 0.0008690000 17685125 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1441 57.6000000000 1.6146572828 0.4632767784 1.9872120619 0.0335549331 0.0110050000 0.0005310000 0.0042850000 0.0000010000 0.0000080000 0.0015300000 17687901 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1442 57.6400000000 1.6194245815 0.4640785453 1.9872120619 0.0335470230 0.0084830000 0.0004530000 0.0040900000 0.0000000000 0.0000050000 0.0008760000 17690677 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1443 57.6800000000 1.6227633953 0.4648815147 1.9872120619 0.0335389755 0.0076190000 0.0004290000 0.0038470000 0.0000010000 0.0000040000 0.0008690000 17693453 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1444 57.7200000000 1.6236487627 0.4656839851 1.9872120619 0.0335294736 0.0084210000 0.0004850000 0.0040890000 0.0000010000 0.0000040000 0.0008760000 17696229 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1445 57.7600000000 1.6263986826 0.4664872478 1.9872120619 0.0335207260 0.0082870000 0.0004260000 0.0039870000 0.0000000000 0.0000040000 0.0014030000 17699005 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1446 57.8000000000 1.6311606169 0.4672926927 1.9872120619 0.0335116792 0.0075880000 0.0004260000 0.0038240000 0.0000010000 0.0000040000 0.0008770000 17701781 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1447 57.8400000000 1.6320168972 0.4680976162 1.9872120619 0.0335015469 0.0075680000 0.0004210000 0.0038280000 0.0000000000 0.0000030000 0.0008660000 17704557 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1448 57.8800000000 1.6327615976 0.4689019421 1.9872120619 0.0334913209 0.0077840000 0.0004260000 0.0039860000 0.0000000000 0.0000030000 0.0008710000 17707333 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1449 57.9200000000 1.6352819204 0.4697068973 1.9872120619 0.0334816756 0.0107290000 0.0005330000 0.0040750000 0.0000010000 0.0000080000 0.0015380000 17710109 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1450 57.9600000000 1.6377905607 0.4705124722 1.9872120619 0.0334735614 0.0101770000 0.0005460000 0.0040520000 0.0000010000 0.0000080000 0.0009630000 17712885 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1451 58.0000000000 1.6395773888 0.4713181682 1.9872120619 0.0334655497 0.0083670000 0.0004560000 0.0039150000 0.0000000000 0.0000050000 0.0008720000 17715661 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1452 58.0400000000 1.6417530775 0.4721242529 1.9872120619 0.0334571072 0.0108700000 0.0005200000 0.0042880000 0.0000010000 0.0000080000 0.0009570000 17718437 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1453 58.0800000000 1.6437926292 0.4729306316 1.9872120619 0.0334484448 0.0111920000 0.0005220000 0.0042030000 0.0000010000 0.0000080000 0.0015460000 17721213 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1454 58.1200000000 1.6440609694 0.4737360858 1.9872120619 0.0334382406 0.0085180000 0.0004530000 0.0040010000 0.0000010000 0.0000050000 0.0008730000 17723989 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1455 58.1600000000 1.6445379257 0.4745407606 1.9872120619 0.0334276909 0.0076970000 0.0004280000 0.0039360000 0.0000000000 0.0000040000 0.0008700000 17726765 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1456 58.2000000000 1.6448252201 0.4753445274 1.9872120619 0.0334173567 0.0172130000 0.0006330000 0.0044120000 0.0000020000 0.0000180000 0.0012560000 17729541 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1457 58.2400000000 1.6466716528 0.4761484582 1.9872120619 0.0334074968 0.0146340000 0.0006070000 0.0044160000 0.0000020000 0.0000160000 0.0020070000 17732317 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1458 58.2800000000 1.6488207579 0.4769527602 1.9872120619 0.0333979390 0.0091720000 0.0004640000 0.0040170000 0.0000010000 0.0000060000 0.0008910000 17735093 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1459 58.3200000000 1.6493979692 0.4777563552 1.9872120619 0.0333880883 0.0078370000 0.0004370000 0.0039160000 0.0000010000 0.0000040000 0.0008720000 17737869 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1460 58.3600000000 1.6493941545 0.4785588469 1.9872120619 0.0333781078 0.0076770000 0.0004170000 0.0039240000 0.0000010000 0.0000040000 0.0008720000 17740645 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1461 58.4000000000 1.6502277851 0.4793608106 1.9872120619 0.0333679761 0.0112430000 0.0005150000 0.0041350000 0.0000010000 0.0000080000 0.0015660000 17743421 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1462 58.4400000000 1.6503940821 0.4801617909 1.9872120619 0.0333572971 0.0089530000 0.0004480000 0.0044030000 0.0000000000 0.0000050000 0.0008930000 17746197 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1463 58.4800000000 1.6511471272 0.4809621910 1.9872120619 0.0333465007 0.0079030000 0.0004300000 0.0041180000 0.0000000000 0.0000030000 0.0008690000 17748973 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1464 58.5200000000 1.6516813040 0.4817618625 1.9872120619 0.0333357213 0.0072880000 0.0004240000 0.0034610000 0.0000010000 0.0000040000 0.0008730000 17751749 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1465 58.5600000000 1.6519497633 0.4825606256 1.9872120619 0.0333249740 0.0107770000 0.0005160000 0.0040310000 0.0000010000 0.0000080000 0.0015580000 17754525 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1466 58.6000000000 1.6516793966 0.4833581145 1.9872120619 0.0333144124 0.0080020000 0.0004640000 0.0035250000 0.0000010000 0.0000040000 0.0008770000 17757301 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1467 58.6400000000 1.6526283026 0.4841551631 1.9872120619 0.0333040524 0.0045140000 0.0004290000 0.0005560000 0.0000000000 0.0000040000 0.0008670000 17760077 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1468 58.6800000000 1.6529388428 0.4849513372 1.9872120619 0.0332936208 0.0088140000 0.0005330000 0.0006580000 0.0000010000 0.0000110000 0.0010590000 17762853 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1469 58.7200000000 1.6533043385 0.4857466762 1.9872120619 0.0332831649 0.0063650000 0.0004680000 0.0006040000 0.0000000000 0.0000060000 0.0014760000 17765629 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1470 58.7600000000 1.6559777260 0.4865427518 1.9872120619 0.0332734576 0.0048440000 0.0004320000 0.0006260000 0.0000000000 0.0000050000 0.0008780000 17768405 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1471 58.8000000000 1.6580282450 0.4873391389 1.9872120619 0.0332638261 0.0112570000 0.0006060000 0.0007150000 0.0000020000 0.0000200000 0.0012410000 17771181 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1472 58.8400000000 1.6597065926 0.4881355842 1.9872120619 0.0332537446 0.0064100000 0.0004900000 0.0006500000 0.0000000000 0.0000060000 0.0009220000 17773957 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1473 58.8800000000 1.6617491245 0.4889323347 1.9872120619 0.0332438553 0.0056610000 0.0004390000 0.0006570000 0.0000000000 0.0000050000 0.0014110000 17776733 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1474 58.9200000000 1.6636517048 0.4897292950 1.9872120619 0.0332346321 0.0077610000 0.0005140000 0.0006800000 0.0000010000 0.0000110000 0.0010540000 17779509 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1475 58.9600000000 1.6657485962 0.4905265962 1.9872120619 0.0332254336 0.0088870000 0.0004400000 0.0043200000 0.0000010000 0.0000050000 0.0008740000 17782285 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1476 59.0000000000 1.6686813831 0.4913248040 1.9872120619 0.0332159250 0.0081480000 0.0004210000 0.0043450000 0.0000010000 0.0000040000 0.0008750000 17785061 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1477 59.0400000000 1.6707513332 0.4921233325 1.9872120619 0.0332058656 0.0087340000 0.0004220000 0.0043360000 0.0000000000 0.0000040000 0.0014170000 17787837 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1478 59.0800000000 1.6730259657 0.4929223194 1.9872120619 0.0331952493 0.0111720000 0.0005280000 0.0045990000 0.0000010000 0.0000070000 0.0009680000 17790613 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1479 59.1200000000 1.6777069569 0.4937233908 1.9872120619 0.0331858853 0.0089600000 0.0004470000 0.0044280000 0.0000000000 0.0000040000 0.0008850000 17793389 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1480 59.1600000000 1.6805197001 0.4945252802 1.9872120619 0.0331752161 0.0081790000 0.0004260000 0.0043780000 0.0000010000 0.0000040000 0.0008730000 17796165 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1481 59.2000000000 1.6818475723 0.4953269833 1.9872120619 0.0331644860 0.0086820000 0.0004160000 0.0043550000 0.0000010000 0.0000030000 0.0014070000 17798941 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1482 59.2400000000 1.6843074560 0.4961292643 1.9872120619 0.0331536786 0.0081660000 0.0004170000 0.0043530000 0.0000010000 0.0000040000 0.0008760000 17801717 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1483 59.2800000000 1.6870275736 0.4969322976 1.9872120619 0.0331430275 0.0081480000 0.0004240000 0.0043740000 0.0000010000 0.0000040000 0.0008730000 17804493 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1484 59.3200000000 1.6891435385 0.4977356744 1.9872120619 0.0331324908 0.0113240000 0.0005250000 0.0045580000 0.0000010000 0.0000080000 0.0009820000 17807269 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1485 59.3600000000 1.6906559467 0.4985389877 1.9872120619 0.0331221855 0.0116930000 0.0005200000 0.0046470000 0.0000010000 0.0000080000 0.0015680000 17810045 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1486 59.4000000000 1.6918870211 0.4993420483 1.9872120619 0.0331116799 0.0089330000 0.0004490000 0.0044550000 0.0000010000 0.0000050000 0.0008810000 17812821 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1487 59.4400000000 1.6935003996 0.5001451138 1.9872120619 0.0331012371 0.0080770000 0.0004190000 0.0042920000 0.0000000000 0.0000030000 0.0008720000 17815597 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1488 59.4800000000 1.6959903240 0.5009487732 1.9872120619 0.0330912087 0.0081570000 0.0004190000 0.0043060000 0.0000000000 0.0000040000 0.0008770000 17818373 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1489 59.5200000000 1.6975078583 0.5017523723 1.9872120619 0.0330808945 0.0086230000 0.0004150000 0.0043100000 0.0000000000 0.0000030000 0.0014090000 17821149 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1490 59.5600000000 1.6999936104 0.5025565611 1.9872120619 0.0330704754 0.0081130000 0.0004150000 0.0043140000 0.0000010000 0.0000040000 0.0008740000 17823925 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1491 59.6000000000 1.7022566795 0.5033611889 1.9872120619 0.0330599093 0.0112700000 0.0005200000 0.0045760000 0.0000010000 0.0000080000 0.0009690000 17826701 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1492 59.6400000000 1.7038966417 0.5041658373 1.9872120619 0.0330490867 0.0089860000 0.0004580000 0.0043740000 0.0000000000 0.0000050000 0.0008850000 17829477 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1493 59.6800000000 1.7074332237 0.5049717767 1.9872120619 0.0330384920 0.0087670000 0.0004450000 0.0043280000 0.0000010000 0.0000040000 0.0014070000 17832253 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1494 59.7200000000 1.7091976404 0.5057778181 1.9872120619 0.0330277149 0.0082120000 0.0004320000 0.0043110000 0.0000000000 0.0000040000 0.0008840000 17835029 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1495 59.7600000000 1.7108435631 0.5065838821 1.9872120619 0.0330170662 0.0112440000 0.0005210000 0.0046190000 0.0000010000 0.0000080000 0.0009730000 17837805 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1496 59.8000000000 1.7122610807 0.5073898161 1.9872120619 0.0330065589 0.0090160000 0.0004490000 0.0043930000 0.0000010000 0.0000050000 0.0008790000 17840581 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1497 59.8400000000 1.7145267725 0.5081961868 1.9872120619 0.0329962392 0.0098220000 0.0004830000 0.0047230000 0.0000000000 0.0000030000 0.0015880000 17843357 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1498 59.8800000000 1.7177795172 0.5090036523 1.9872120619 0.0329859631 0.0082330000 0.0004360000 0.0043210000 0.0000010000 0.0000040000 0.0008720000 17846133 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1499 59.9200000000 1.7194324732 0.5098111432 1.9872120619 0.0329752946 0.0112620000 0.0005220000 0.0046360000 0.0000010000 0.0000080000 0.0009570000 17848909 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1500 59.9600000000 1.7202198505 0.5106180823 1.9872120619 0.0329646146 0.0089750000 0.0004540000 0.0043750000 0.0000000000 0.0000050000 0.0008750000 17851685 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1501 60.0000000000 1.7211872339 0.5114245907 1.9872120619 0.0329540743 0.0088210000 0.0004300000 0.0043950000 0.0000000000 0.0000040000 0.0014050000 17854461 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1502 60.0400000000 1.7220360041 0.5122305903 1.9872120619 0.0329435041 0.0083080000 0.0004300000 0.0043810000 0.0000010000 0.0000040000 0.0008730000 17857237 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1503 60.0800000000 1.7223331928 0.5130357152 1.9872120619 0.0329330067 0.0081760000 0.0004180000 0.0043020000 0.0000010000 0.0000040000 0.0008740000 17860013 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1504 60.1200000000 1.7234866619 0.5138405363 1.9872120619 0.0329226848 0.0082950000 0.0004210000 0.0043020000 0.0000000000 0.0000040000 0.0008890000 17862789 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1505 60.1600000000 1.7239781618 0.5146446144 1.9872120619 0.0329126879 0.0087480000 0.0004220000 0.0043250000 0.0000010000 0.0000040000 0.0014050000 17865565 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1506 60.2000000000 1.7245945930 0.5154480341 1.9872120619 0.0329029778 0.0114970000 0.0005170000 0.0046090000 0.0000010000 0.0000090000 0.0009760000 17868341 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1507 60.2400000000 1.7237619162 0.5162498349 1.9872120619 0.0328935260 0.0090900000 0.0004540000 0.0044160000 0.0000000000 0.0000050000 0.0008770000 17871117 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1508 60.2800000000 1.7236784697 0.5170505170 1.9872120619 0.0328834504 0.0082590000 0.0004300000 0.0043370000 0.0000000000 0.0000040000 0.0008910000 17873893 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1509 60.3200000000 1.7237211466 0.5178501662 1.9872120619 0.0328733320 0.0115760000 0.0005280000 0.0045750000 0.0000020000 0.0000080000 0.0015620000 17876669 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 1510 60.3600000000 1.7226669788 0.5186480581 1.9872120619 0.0328625597 0.0089020000 0.0004450000 0.0043660000 0.0000000000 0.0000050000 0.0008900000 17879445 96830484 509673472 4.0657682419 3.2700335979 5.9081759453 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:22:27 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002853 0.0000002853 0.0000002853 -nan 0.0058500000 0.0005850000 0.0005630000 0.0000140000 0.0000020000 0.0044470000 12540621 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0004263568 0.0002133210 0.0004263568 0.0040680543 0.0022960000 0.0005940000 0.0005610000 0.0000160000 0.0000020000 0.0010200000 12740365 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0024013643 0.0009426688 0.0024013643 0.0044545561 0.0023570000 0.0005860000 0.0005620000 0.0000140000 0.0000020000 0.0010840000 12743533 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0017003767 0.0011320958 0.0024013643 0.0049657320 0.0027930000 0.0006430000 0.0005640000 0.0000140000 0.0000220000 0.0014430000 12746709 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0008905209 0.0010837808 0.0024013643 0.0044341422 0.0068420000 0.0005830000 0.0038750000 0.0000150000 0.0000150000 0.0022430000 12749869 96830484 509673472 4.0000133514 3.9995694160 4.0000009537 6 0.2000000000 0.0008925555 0.0010519099 0.0024013643 0.0040874857 0.0060930000 0.0005850000 0.0041050000 0.0000010000 0.0000150000 0.0012780000 12753445 96830484 509673472 4.0000443459 3.9984669685 3.9996931553 7 0.2400000000 0.0009212737 0.0010332476 0.0024013643 0.0037767942 0.0054400000 0.0005810000 0.0032160000 0.0000140000 0.0000140000 0.0015000000 12756221 96830484 509673472 4.0000247955 3.9983057976 3.9996023178 8 0.2800000000 0.0010177245 0.0010313072 0.0024013643 0.0035593415 0.0049500000 0.0005800000 0.0029780000 0.0000010000 0.0000160000 0.0012540000 12758997 96830484 509673472 4.0002617836 3.9996204376 4.0000276566 9 0.3200000000 0.0010306418 0.0010312333 0.0024013643 0.0033325978 0.0059080000 0.0005850000 0.0029680000 0.0000150000 0.0000140000 0.0021900000 12762541 96830484 509673472 4.0004601479 3.9996554852 4.0000720024 10 0.3600000000 0.0011195267 0.0010400626 0.0024013643 0.0031526510 0.0049470000 0.0005870000 0.0029530000 0.0000010000 0.0000150000 0.0012560000 12766917 96830484 509673472 4.0005083084 3.9990284443 3.9999022484 11 0.4000000000 0.0010719971 0.0010429658 0.0024013643 0.0029938753 0.0048380000 0.0005900000 0.0025550000 0.0000140000 0.0000150000 0.0014980000 12769693 96830484 509673472 4.0003881454 3.9995760918 4.0000905991 12 0.4400000000 0.0010249168 0.0010414617 0.0024013643 0.0028622442 0.0056930000 0.0006060000 0.0036360000 0.0000020000 0.0000150000 0.0012620000 12772469 96830484 509673472 4.0004501343 4.0003008842 4.0003972054 13 0.4800000000 0.0011125762 0.0010469320 0.0024013643 0.0027522012 0.0085060000 0.0005900000 0.0055080000 0.0000150000 0.0000140000 0.0022110000 12775245 96830484 509673472 4.0002908707 4.0009546280 4.0007076263 14 0.5200000000 0.0010822896 0.0010494576 0.0024013643 0.0027276101 0.0052140000 0.0005010000 0.0036020000 0.0000010000 0.0000110000 0.0010110000 12778021 96830484 509673472 4.0004348755 4.0009870529 4.0007882118 15 0.5600000000 0.0010702026 0.0010508406 0.0024013643 0.0027168827 0.0056630000 0.0005800000 0.0033820000 0.0000150000 0.0000140000 0.0014960000 12780797 96830484 509673472 4.0004868507 4.0010123253 4.0008840561 16 0.6000000000 0.0011199052 0.0010551571 0.0024013643 0.0026456645 0.0045620000 0.0005850000 0.0025240000 0.0000020000 0.0000150000 0.0012530000 12783573 96830484 509673472 4.0009765625 4.0009317398 4.0008077621 17 0.6400000000 0.0012319526 0.0010655568 0.0024013643 0.0025687162 0.0055600000 0.0005850000 0.0025400000 0.0000150000 0.0000130000 0.0022120000 12787885 96830484 509673472 4.0008697510 4.0009245872 4.0008525848 18 0.6800000000 0.0012718930 0.0010770200 0.0024013643 0.0025020911 0.0050100000 0.0005860000 0.0029630000 0.0000020000 0.0000150000 0.0012480000 12793861 96830484 509673472 4.0009841919 4.0001983643 4.0006084442 19 0.7200000000 0.0011871908 0.0010828184 0.0024013643 0.0025408235 0.0052080000 0.0005240000 0.0032140000 0.0000110000 0.0000090000 0.0013090000 12796637 96830484 509673472 4.0009002686 4.0001873970 4.0005221367 20 0.7600000000 0.0011708777 0.0010872214 0.0024013643 0.0026357444 0.0050950000 0.0006060000 0.0029770000 0.0000020000 0.0000160000 0.0012730000 12799413 96830484 509673472 4.0006680489 3.9999325275 4.0004420280 21 0.8000000000 0.0012415576 0.0010945707 0.0024013643 0.0027461987 0.0060310000 0.0005880000 0.0029730000 0.0000170000 0.0000130000 0.0022250000 12802189 96830484 509673472 4.0006694794 3.9998669624 4.0002851486 22 0.8400000000 0.0012328282 0.0011008552 0.0024013643 0.0027264513 0.0050820000 0.0005900000 0.0029980000 0.0000020000 0.0000150000 0.0012590000 12804965 96830484 509673472 4.0007185936 4.0000534058 4.0004005432 23 0.8800000000 0.0012368672 0.0011067687 0.0024013643 0.0027024888 0.0057720000 0.0005890000 0.0034290000 0.0000150000 0.0000130000 0.0015040000 12807741 96830484 509673472 4.0004849434 3.9998300076 4.0003304482 24 0.9200000000 0.0013181245 0.0011155752 0.0024013643 0.0026498581 0.0057270000 0.0005860000 0.0036420000 0.0000020000 0.0000160000 0.0012570000 12810517 96830484 509673472 4.0005636215 4.0000429153 4.0003299713 25 0.9600000000 0.0013126627 0.0011234587 0.0024013643 0.0025963924 0.0054520000 0.0005890000 0.0023890000 0.0000150000 0.0000140000 0.0022100000 12813293 96830484 509673472 4.0003504753 3.9999787807 4.0003352165 26 1.0000000000 0.0013838731 0.0011334747 0.0024013643 0.0025455669 0.0073900000 0.0005850000 0.0055090000 0.0000020000 0.0000150000 0.0011180000 12816069 96830484 509673472 4.0005517006 4.0003004074 4.0003790855 27 1.0400000000 0.0014678285 0.0011458581 0.0024013643 0.0025021747 0.0049070000 0.0005850000 0.0025450000 0.0000150000 0.0000140000 0.0015050000 12818845 96830484 509673472 4.0003247261 4.0003523827 4.0003652573 28 1.0800000000 0.0014613050 0.0011571241 0.0024013643 0.0024758671 0.0041340000 0.0005060000 0.0023810000 0.0000010000 0.0000120000 0.0010680000 12821621 96830484 509673472 4.0002403259 4.0002021790 4.0003981590 29 1.1200000000 0.0013489033 0.0011637372 0.0024013643 0.0024414107 0.0053020000 0.0005740000 0.0022220000 0.0000150000 0.0000140000 0.0022190000 12824397 96830484 509673472 3.9998302460 4.0003528595 4.0005002022 30 1.1600000000 0.0014576978 0.0011735359 0.0024013643 0.0024129590 0.0046890000 0.0005890000 0.0025310000 0.0000010000 0.0000160000 0.0012880000 12827173 96830484 509673472 4.0000953674 4.0008740425 4.0004773140 31 1.2000000000 0.0013885713 0.0011804725 0.0024013643 0.0023908722 0.0057770000 0.0005900000 0.0033950000 0.0000160000 0.0000130000 0.0014960000 12829949 96830484 509673472 3.9998571873 4.0005626678 4.0004510880 32 1.2400000000 0.0013831268 0.0011868054 0.0024013643 0.0023574945 0.0046790000 0.0005850000 0.0025520000 0.0000020000 0.0000150000 0.0012580000 12832725 96830484 509673472 3.9996078014 4.0001573563 4.0004110336 33 1.2800000000 0.0013971203 0.0011931786 0.0024013643 0.0023526233 0.0056430000 0.0005890000 0.0025290000 0.0000150000 0.0000140000 0.0022130000 12838573 96830484 509673472 3.9994225502 4.0002517700 4.0005779266 34 1.3200000000 0.0015338081 0.0012031971 0.0024013643 0.0023415331 0.0046760000 0.0005870000 0.0025250000 0.0000010000 0.0000150000 0.0012630000 12847749 96830484 509673472 3.9990346432 4.0000853539 4.0006413460 35 1.3600000000 0.0013563003 0.0012075715 0.0024013643 0.0023246787 0.0056560000 0.0005900000 0.0032310000 0.0000150000 0.0000130000 0.0015050000 12850525 96830484 509673472 3.9986054897 3.9990754128 4.0003924370 36 1.4000000000 0.0014289237 0.0012137202 0.0024013643 0.0022980579 0.0077040000 0.0005860000 0.0055470000 0.0000020000 0.0000150000 0.0012590000 12853301 96830484 509673472 3.9982209206 3.9990472794 4.0003805161 37 1.4400000000 0.0012873560 0.0012157103 0.0024013643 0.0022666373 0.0057580000 0.0005020000 0.0031970000 0.0000090000 0.0000100000 0.0018890000 12856077 96830484 509673472 3.9978511333 3.9995613098 4.0005798340 38 1.4800000000 0.0011970763 0.0012152200 0.0024013643 0.0022358431 0.0055590000 0.0005870000 0.0033950000 0.0000020000 0.0000160000 0.0012580000 12858853 96830484 509673472 3.9974410534 3.9990322590 4.0006051064 39 1.5200000000 0.0011732621 0.0012141441 0.0024013643 0.0022164826 0.0052290000 0.0005830000 0.0029750000 0.0000140000 0.0000140000 0.0014300000 12861629 96830484 509673472 3.9967067242 3.9975492954 4.0002336502 40 1.5600000000 0.0010581139 0.0012102434 0.0024013643 0.0022940407 0.0059930000 0.0005870000 0.0037970000 0.0000020000 0.0000150000 0.0012750000 12864405 96830484 509673472 3.9962744713 3.9979035854 4.0006465912 41 1.6000000000 0.0010631033 0.0012066546 0.0024013643 0.0024324691 0.0059780000 0.0004960000 0.0037720000 0.0000030000 0.0000040000 0.0016290000 12867181 96830484 509673472 3.9959051609 3.9991247654 4.0013785362 42 1.6400000000 0.0011627487 0.0012056092 0.0024013643 0.0025073513 0.0060130000 0.0005890000 0.0038140000 0.0000020000 0.0000150000 0.0012630000 12869957 96830484 509673472 3.9952697754 3.9989511967 4.0017290115 43 1.6800000000 0.0012294155 0.0012061628 0.0024013643 0.0025127170 0.0058240000 0.0005870000 0.0033790000 0.0000180000 0.0000130000 0.0014910000 12872733 96830484 509673472 3.9949569702 3.9988992214 4.0022754669 44 1.7200000000 0.0012588424 0.0012073601 0.0024013643 0.0024944850 0.0058480000 0.0005010000 0.0040530000 0.0000010000 0.0000110000 0.0010540000 12875509 96830484 509673472 3.9945423603 3.9993019104 4.0029430389 45 1.7600000000 0.0012221107 0.0012076879 0.0024013643 0.0024891929 0.0070090000 0.0005020000 0.0043300000 0.0000100000 0.0000090000 0.0019260000 12878285 96830484 509673472 3.9943320751 3.9987688065 4.0034580231 46 1.8000000000 0.0012848658 0.0012093657 0.0024013643 0.0026050669 0.0048870000 0.0005050000 0.0030710000 0.0000010000 0.0000100000 0.0010660000 12881061 96830484 509673472 3.9941358566 3.9977045059 4.0039982796 47 1.8400000000 0.0012403937 0.0012100258 0.0024013643 0.0027733452 0.0054400000 0.0005710000 0.0029720000 0.0000150000 0.0000130000 0.0015090000 12883837 96830484 509673472 3.9941878319 3.9972214699 4.0049424171 48 1.8800000000 0.0011585370 0.0012089532 0.0024013643 0.0029400499 0.0052460000 0.0005850000 0.0030140000 0.0000030000 0.0000150000 0.0012680000 12886613 96830484 509673472 3.9939668179 3.9970421791 4.0063562393 49 1.9200000000 0.0011806221 0.0012083750 0.0024013643 0.0032209912 0.0066520000 0.0005860000 0.0034320000 0.0000150000 0.0000150000 0.0022330000 12889389 96830484 509673472 3.9939467907 3.9956655502 4.0073823929 50 1.9600000000 0.0011968248 0.0012081440 0.0024013643 0.0035129184 0.0055160000 0.0005850000 0.0032700000 0.0000010000 0.0000160000 0.0012690000 12892165 96830484 509673472 3.9939007759 3.9951612949 4.0089011192 51 2.0000000000 0.0012256256 0.0012084868 0.0024013643 0.0036898036 0.0051560000 0.0005030000 0.0030680000 0.0000100000 0.0000090000 0.0013120000 12894941 96830484 509673472 3.9940013885 3.9953758717 4.0108098984 52 2.0400000000 0.0012703071 0.0012096756 0.0024013643 0.0038263200 0.0043590000 0.0004700000 0.0027220000 0.0000010000 0.0000070000 0.0009660000 12897717 96830484 509673472 3.9946224689 3.9952771664 4.0127320290 53 2.0800000000 0.0013039646 0.0012114546 0.0024013643 0.0038931817 0.0064670000 0.0005900000 0.0032390000 0.0000160000 0.0000130000 0.0022150000 12900493 96830484 509673472 3.9949827194 3.9940834045 4.0143833160 54 2.1200000000 0.0013381320 0.0012138005 0.0024013643 0.0039584565 0.0056760000 0.0005920000 0.0034150000 0.0000020000 0.0000160000 0.0012510000 12903269 96830484 509673472 3.9960281849 3.9933795929 4.0161623955 55 2.1600000000 0.0013013497 0.0012153923 0.0024013643 0.0039625354 0.0057560000 0.0005910000 0.0032350000 0.0000140000 0.0000140000 0.0014940000 12906045 96830484 509673472 3.9962968826 3.9936258793 4.0186738968 56 2.2000000000 0.0012280261 0.0012156179 0.0024013643 0.0039411769 0.0067070000 0.0005040000 0.0048860000 0.0000010000 0.0000100000 0.0010280000 12908821 96830484 509673472 3.9967117310 3.9938156605 4.0211815834 57 2.2400000000 0.0012766335 0.0012166884 0.0024013643 0.0039562104 0.0050310000 0.0004740000 0.0025920000 0.0000080000 0.0000070000 0.0017340000 12911597 96830484 509673472 3.9978797436 3.9937651157 4.0235886574 58 2.2800000000 0.0013238764 0.0012185364 0.0024013643 0.0040153014 0.0044810000 0.0004550000 0.0029650000 0.0000010000 0.0000060000 0.0008770000 12914373 96830484 509673472 3.9985771179 3.9948425293 4.0264348984 59 2.3200000000 0.0013906093 0.0012214529 0.0024013643 0.0041141997 0.0055450000 0.0006120000 0.0029840000 0.0000150000 0.0000140000 0.0014800000 12917149 96830484 509673472 3.9998769760 3.9946322441 4.0290813446 60 2.3600000000 0.0014004608 0.0012244364 0.0024013643 0.0044158295 0.0051260000 0.0005940000 0.0028390000 0.0000020000 0.0000150000 0.0012410000 12919925 96830484 509673472 4.0008149147 3.9933304787 4.0314807892 61 2.4000000000 0.0014368054 0.0012279179 0.0024013643 0.0046786316 0.0066460000 0.0005850000 0.0034120000 0.0000150000 0.0000130000 0.0021720000 12922701 96830484 509673472 4.0022435188 3.9933092594 4.0344047546 62 2.4400000000 0.0014467937 0.0012314481 0.0024013643 0.0049279217 0.0046830000 0.0005100000 0.0028310000 0.0000020000 0.0000100000 0.0010350000 12925477 96830484 509673472 4.0035204887 3.9932484627 4.0373091698 63 2.4800000000 0.0015674848 0.0012367820 0.0024013643 0.0051105856 0.0059610000 0.0005870000 0.0034150000 0.0000160000 0.0000140000 0.0014730000 12928253 96830484 509673472 4.0050287247 3.9926962852 4.0400238037 64 2.5200000000 0.0015486005 0.0012416542 0.0024013643 0.0052491333 0.0060540000 0.0005870000 0.0036970000 0.0000020000 0.0000230000 0.0012760000 12931029 96830484 509673472 4.0066504478 3.9929883480 4.0431861877 65 2.5600000000 0.0015359905 0.0012461824 0.0024013643 0.0054904193 0.0054730000 0.0005260000 0.0026800000 0.0000100000 0.0000100000 0.0019000000 12939949 96830484 509673472 4.0079741478 3.9925365448 4.0460400581 66 2.6000000000 0.0013402728 0.0012476081 0.0024013643 0.0058367298 0.0053520000 0.0005900000 0.0029920000 0.0000020000 0.0000180000 0.0012610000 12955525 96830484 509673472 4.0095305443 3.9914584160 4.0485444069 67 2.6400000000 0.0012951200 0.0012483172 0.0024013643 0.0061143396 0.0048070000 0.0005050000 0.0026590000 0.0000120000 0.0000090000 0.0012940000 12958301 96830484 509673472 4.0115532875 3.9929039478 4.0518617630 68 2.6800000000 0.0013064535 0.0012491721 0.0024013643 0.0065270307 0.0054120000 0.0005900000 0.0030350000 0.0000020000 0.0000170000 0.0012700000 12961077 96830484 509673472 4.0118255615 3.9931578636 4.0547132492 69 2.7200000000 0.0013385747 0.0012504678 0.0024013643 0.0067401093 0.0061440000 0.0006070000 0.0028130000 0.0000150000 0.0000140000 0.0021990000 12963853 96830484 509673472 4.0137863159 3.9922809601 4.0573825836 70 2.7600000000 0.0013635393 0.0012520831 0.0024013643 0.0068656346 0.0045760000 0.0005000000 0.0026700000 0.0000010000 0.0000100000 0.0010560000 12966629 96830484 509673472 4.0153465271 3.9915504456 4.0598611832 71 2.8000000000 0.0013757856 0.0012538254 0.0024013643 0.0068892636 0.0060360000 0.0005860000 0.0034060000 0.0000140000 0.0000130000 0.0015040000 12969405 96830484 509673472 4.0166678429 3.9922478199 4.0629000664 72 2.8400000000 0.0013539615 0.0012552162 0.0024013643 0.0068805412 0.0053600000 0.0005910000 0.0029800000 0.0000020000 0.0000150000 0.0012610000 12972181 96830484 509673472 4.0180330276 3.9920053482 4.0655674934 73 2.8800000000 0.0012585336 0.0012552616 0.0024013643 0.0068673320 0.0065860000 0.0005900000 0.0032560000 0.0000150000 0.0000140000 0.0021810000 12974957 96830484 509673472 4.0192089081 3.9914388657 4.0680289268 74 2.9200000000 0.0012516783 0.0012552132 0.0024013643 0.0068798209 0.0047220000 0.0005020000 0.0028130000 0.0000010000 0.0000100000 0.0010500000 12977733 96830484 509673472 4.0207333565 3.9922780991 4.0709118843 75 2.9600000000 0.0013584342 0.0012565895 0.0024013643 0.0069512487 0.0056140000 0.0005910000 0.0029790000 0.0000150000 0.0000130000 0.0014850000 12980509 96830484 509673472 4.0221438408 3.9927170277 4.0736103058 76 3.0000000000 0.0013385297 0.0012576677 0.0024013643 0.0071192888 0.0053880000 0.0005900000 0.0029850000 0.0000010000 0.0000150000 0.0012530000 12983285 96830484 509673472 4.0236101151 3.9914755821 4.0757899284 77 3.0400000000 0.0013308822 0.0012586185 0.0024013643 0.0072809438 0.0061240000 0.0005880000 0.0027900000 0.0000150000 0.0000130000 0.0021780000 12986061 96830484 509673472 4.0247716904 3.9902963638 4.0779023170 78 3.0800000000 0.0012355674 0.0012583230 0.0024013643 0.0075055379 0.0053840000 0.0005890000 0.0029780000 0.0000020000 0.0000150000 0.0012500000 12988837 96830484 509673472 4.0259866714 3.9909839630 4.0807237625 79 3.1200000000 0.0012295084 0.0012579582 0.0024013643 0.0077087389 0.0054340000 0.0005860000 0.0027900000 0.0000160000 0.0000150000 0.0014730000 12991613 96830484 509673472 4.0267004967 3.9912049770 4.0834498405 80 3.1600000000 0.0012715757 0.0012581284 0.0024013643 0.0078497026 0.0052070000 0.0005880000 0.0028010000 0.0000020000 0.0000150000 0.0012440000 12994389 96830484 509673472 4.0278964043 3.9901621342 4.0856747627 81 3.2000000000 0.0013447531 0.0012591979 0.0024013643 0.0079961849 0.0063440000 0.0005940000 0.0029710000 0.0000140000 0.0000130000 0.0021830000 12997165 96830484 509673472 4.0293869972 3.9899585247 4.0881953239 82 3.2400000000 0.0013740427 0.0012605984 0.0024013643 0.0081719077 0.0052020000 0.0005170000 0.0032240000 0.0000020000 0.0000100000 0.0010700000 12999941 96830484 509673472 4.0297861099 3.9897863865 4.0907039642 83 3.2800000000 0.0013300498 0.0012614352 0.0024013643 0.0083564945 0.0050700000 0.0004640000 0.0031170000 0.0000100000 0.0000070000 0.0011840000 13002717 96830484 509673472 4.0308141708 3.9888341427 4.0930986404 84 3.3200000000 0.0013377274 0.0012623434 0.0024013643 0.0084581518 0.0048770000 0.0004670000 0.0031530000 0.0000010000 0.0000070000 0.0009570000 13005493 96830484 509673472 4.0314311981 3.9886610508 4.0956320763 85 3.3600000000 0.0013315254 0.0012631573 0.0024013643 0.0085290880 0.0072160000 0.0006160000 0.0037940000 0.0000150000 0.0000140000 0.0021930000 13008269 96830484 509673472 4.0319399834 3.9890487194 4.0983986855 86 3.4000000000 0.0014452330 0.0012652745 0.0024013643 0.0085876456 0.0058690000 0.0005840000 0.0034240000 0.0000020000 0.0000180000 0.0012460000 13011045 96830484 509673472 4.0329546928 3.9890015125 4.1009740829 87 3.4400000000 0.0013987144 0.0012668083 0.0024013643 0.0086604065 0.0060960000 0.0005920000 0.0033890000 0.0000140000 0.0000130000 0.0014630000 13013821 96830484 509673472 4.0337567329 3.9890124798 4.1038222313 88 3.4800000000 0.0014665357 0.0012690779 0.0024013643 0.0087455273 0.0058720000 0.0005920000 0.0033910000 0.0000020000 0.0000150000 0.0012500000 13016597 96830484 509673472 4.0344710350 3.9887485504 4.1065797806 89 3.5200000000 0.0014287990 0.0012708725 0.0024013643 0.0088273971 0.0068350000 0.0006070000 0.0029930000 0.0000150000 0.0000140000 0.0025190000 13019373 96830484 509673472 4.0353178978 3.9887394905 4.1094851494 90 3.5600000000 0.0014397985 0.0012727495 0.0024013643 0.0089451978 0.0055190000 0.0006430000 0.0029980000 0.0000010000 0.0000150000 0.0012410000 13022149 96830484 509673472 4.0355997086 3.9887714386 4.1124486923 91 3.6000000000 0.0014365724 0.0012745497 0.0024013643 0.0090830555 0.0057930000 0.0006450000 0.0029900000 0.0000150000 0.0000140000 0.0014710000 13024925 96830484 509673472 4.0369486809 3.9882032871 4.1154460907 92 3.6400000000 0.0014718786 0.0012766946 0.0024013643 0.0091708969 0.0054040000 0.0006100000 0.0028530000 0.0000010000 0.0000170000 0.0012570000 13027701 96830484 509673472 4.0373892784 3.9879977703 4.1186227798 93 3.6800000000 0.0014340671 0.0012783868 0.0024013643 0.0091729896 0.0061020000 0.0005240000 0.0032210000 0.0000110000 0.0000100000 0.0019000000 13030477 96830484 509673472 4.0377364159 3.9874403477 4.1215581894 94 3.7200000000 0.0015649518 0.0012814354 0.0024013643 0.0091509233 0.0069640000 0.0004760000 0.0051840000 0.0000010000 0.0000090000 0.0009600000 13033253 96830484 509673472 4.0387701988 3.9877843857 4.1247420311 95 3.7600000000 0.0014686860 0.0012834064 0.0024013643 0.0091393615 0.0070530000 0.0004700000 0.0051640000 0.0000080000 0.0000070000 0.0011350000 13036029 96830484 509673472 4.0395607948 3.9874806404 4.1277985573 96 3.8000000000 0.0015279996 0.0012859543 0.0024013643 0.0091591661 0.0049760000 0.0004480000 0.0033490000 0.0000010000 0.0000060000 0.0009070000 13038805 96830484 509673472 4.0404353142 3.9876904488 4.1310429573 97 3.8400000000 0.0014441775 0.0012875854 0.0024013643 0.0092727409 0.0049390000 0.0004530000 0.0025340000 0.0000070000 0.0000050000 0.0016570000 13041581 96830484 509673472 4.0409927368 3.9890556335 4.1346778870 98 3.8800000000 0.0015747155 0.0012905153 0.0024013643 0.0093982549 0.0043360000 0.0004510000 0.0026930000 0.0000000000 0.0000070000 0.0009090000 13044357 96830484 509673472 4.0415396690 3.9890546799 4.1378207207 99 3.9200000000 0.0015627525 0.0012932652 0.0024013643 0.0095285830 0.0045830000 0.0004510000 0.0027080000 0.0000070000 0.0000050000 0.0011330000 13047133 96830484 509673472 4.0424909592 3.9890418053 4.1410422325 100 3.9600000000 0.0015766473 0.0012960990 0.0024013643 0.0096402307 0.0043590000 0.0004540000 0.0026920000 0.0000000000 0.0000070000 0.0009180000 13049909 96830484 509673472 4.0426750183 3.9906740189 4.1446571350 101 4.0000000000 0.0016526827 0.0012996296 0.0024013643 0.0096919279 0.0065140000 0.0005890000 0.0030100000 0.0000140000 0.0000150000 0.0021820000 13052685 96830484 509673472 4.0432038307 3.9913082123 4.1480345726 102 4.0400000000 0.0016596590 0.0013031593 0.0024013643 0.0097054442 0.0055670000 0.0005920000 0.0029930000 0.0000020000 0.0000170000 0.0012680000 13055461 96830484 509673472 4.0438318253 3.9909951687 4.1509761810 103 4.0800000000 0.0016054928 0.0013060945 0.0024013643 0.0097171825 0.0057550000 0.0005890000 0.0029610000 0.0000140000 0.0000150000 0.0014700000 13058237 96830484 509673472 4.0442280769 3.9921636581 4.1543774605 104 4.1200000000 0.0016006902 0.0013089272 0.0024013643 0.0097226348 0.0058280000 0.0005820000 0.0032440000 0.0000020000 0.0000140000 0.0012640000 13061013 96830484 509673472 4.0450739861 3.9921965599 4.1575131416 105 4.1600000000 0.0016823177 0.0013124833 0.0024013643 0.0097313287 0.0069300000 0.0005930000 0.0033940000 0.0000170000 0.0000140000 0.0021970000 13063789 96830484 509673472 4.0454783440 3.9924008846 4.1602492332 106 4.2000000000 0.0017372860 0.0013164909 0.0024013643 0.0097228670 0.0047360000 0.0005020000 0.0026670000 0.0000010000 0.0000100000 0.0010750000 13066565 96830484 509673472 4.0450892448 3.9930024147 4.1630744934 107 4.2400000000 0.0016457656 0.0013195682 0.0024013643 0.0096979746 0.0057890000 0.0005840000 0.0029590000 0.0000150000 0.0000130000 0.0014870000 13069341 96830484 509673472 4.0459647179 3.9923710823 4.1655430794 108 4.2800000000 0.0018956974 0.0013249027 0.0024013643 0.0096906192 0.0047510000 0.0004990000 0.0026680000 0.0000020000 0.0000100000 0.0010850000 13072117 96830484 509673472 4.0455546379 3.9932878017 4.1682972908 109 4.3200000000 0.0019811892 0.0013309237 0.0024013643 0.0096749087 0.0056520000 0.0005030000 0.0026560000 0.0000100000 0.0000080000 0.0019460000 13074893 96830484 509673472 4.0455889702 3.9941465855 4.1709666252 110 4.3600000000 0.0022050806 0.0013388706 0.0024013643 0.0096389719 0.0056090000 0.0005870000 0.0029620000 0.0000020000 0.0000140000 0.0013030000 13077669 96830484 509673472 4.0455446243 3.9943706989 4.1735162735 111 4.4000000000 0.0022980429 0.0013475118 0.0024013643 0.0096067891 0.0058830000 0.0005870000 0.0029660000 0.0000150000 0.0000130000 0.0015350000 13080445 96830484 509673472 4.0458812714 3.9945158958 4.1760654449 112 4.4400000000 0.0026373770 0.0013590284 0.0026373770 0.0095755163 0.0054290000 0.0005900000 0.0027840000 0.0000010000 0.0000140000 0.0013070000 13083221 96830484 509673472 4.0459899902 3.9948041439 4.1784644127 113 4.4800000000 0.0022380271 0.0013668072 0.0026373770 0.0095417764 0.0073890000 0.0005830000 0.0038010000 0.0000150000 0.0000140000 0.0022390000 13085997 96830484 509673472 4.0459733009 3.9952740669 4.1809129715 114 4.5200000000 0.0025542083 0.0013772230 0.0026373770 0.0095108149 0.0049560000 0.0005010000 0.0028380000 0.0000010000 0.0000100000 0.0011050000 13088773 96830484 509673472 4.0460414886 3.9952266216 4.1833195686 115 4.5600000000 0.0022746453 0.0013850267 0.0026373770 0.0094806181 0.0061110000 0.0005860000 0.0032180000 0.0000140000 0.0000140000 0.0015340000 13091549 96830484 509673472 4.0466880798 3.9950509071 4.1856923103 116 4.6000000000 0.0025525840 0.0013950918 0.0026373770 0.0094619205 0.0056500000 0.0005850000 0.0029830000 0.0000020000 0.0000150000 0.0013090000 13094325 96830484 509673472 4.0462698936 3.9958219528 4.1882600784 117 4.6400000000 0.0024523437 0.0014041281 0.0026373770 0.0094305975 0.0064470000 0.0005850000 0.0028110000 0.0000160000 0.0000160000 0.0022550000 13097101 96830484 509673472 4.0465583801 3.9954569340 4.1907110214 118 4.6800000000 0.0023228922 0.0014119143 0.0026373770 0.0094029611 0.0053400000 0.0005020000 0.0032040000 0.0000010000 0.0000090000 0.0011120000 13099877 96830484 509673472 4.0467896461 3.9956855774 4.1934094429 119 4.7200000000 0.0026395533 0.0014222306 0.0026395533 0.0093781859 0.0048060000 0.0004660000 0.0027050000 0.0000070000 0.0000060000 0.0012340000 13102653 96830484 509673472 4.0469269753 3.9958074093 4.1963567734 120 4.7600000000 0.0024068167 0.0014304355 0.0026395533 0.0093519909 0.0056650000 0.0005860000 0.0029490000 0.0000020000 0.0000160000 0.0013310000 13105429 96830484 509673472 4.0472388268 3.9953954220 4.1991329193 121 4.8000000000 0.0026309362 0.0014403569 0.0026395533 0.0093406405 0.0064890000 0.0005840000 0.0027760000 0.0000150000 0.0000140000 0.0023220000 13108205 96830484 509673472 4.0473160744 3.9957549572 4.2021780014 122 4.8400000000 0.0027074905 0.0014507433 0.0027074905 0.0093458564 0.0056540000 0.0005840000 0.0029370000 0.0000010000 0.0000160000 0.0013290000 13110981 96830484 509673472 4.0472497940 3.9957699776 4.2052569389 123 4.8800000000 0.0025180073 0.0014594202 0.0027074905 0.0093300311 0.0055630000 0.0005000000 0.0031710000 0.0000110000 0.0000090000 0.0013440000 13113757 96830484 509673472 4.0475683212 3.9959414005 4.2084345818 124 4.9200000000 0.0025937723 0.0014685682 0.0027074905 0.0093073962 0.0056910000 0.0005850000 0.0029490000 0.0000020000 0.0000170000 0.0013360000 13116533 96830484 509673472 4.0475597382 3.9963078499 4.2114982605 125 4.9600000000 0.0025697476 0.0014773777 0.0027074905 0.0092860483 0.0069440000 0.0005880000 0.0032160000 0.0000150000 0.0000150000 0.0022830000 13119309 96830484 509673472 4.0478844643 3.9966328144 4.2147960663 126 5.0000000000 0.0025078184 0.0014855558 0.0027074905 0.0092721434 0.0054270000 0.0005890000 0.0026600000 0.0000010000 0.0000150000 0.0013420000 13122085 96830484 509673472 4.0482301712 3.9965810776 4.2179389000 127 5.0400000000 0.0025101376 0.0014936233 0.0027074905 0.0092727037 0.0050650000 0.0005030000 0.0026300000 0.0000090000 0.0000090000 0.0013650000 13124861 96830484 509673472 4.0486493111 3.9965429306 4.2212057114 128 5.0800000000 0.0025822807 0.0015021285 0.0027074905 0.0092889023 0.0056060000 0.0005840000 0.0028050000 0.0000010000 0.0000150000 0.0013350000 13127637 96830484 509673472 4.0490536690 3.9970846176 4.2243757248 129 5.1200000000 0.0026003562 0.0015106419 0.0027074905 0.0092735994 0.0067010000 0.0005870000 0.0029310000 0.0000150000 0.0000130000 0.0023100000 13142701 96830484 509673472 4.0496296883 3.9972081184 4.2274985313 130 5.1600000000 0.0026385058 0.0015193177 0.0027074905 0.0092614509 0.0055710000 0.0005880000 0.0027750000 0.0000020000 0.0000140000 0.0013480000 13171077 96830484 509673472 4.0502281189 3.9965281487 4.2301139832 131 5.2000000000 0.0025494469 0.0015271813 0.0027074905 0.0092508272 0.0051430000 0.0005270000 0.0026200000 0.0000100000 0.0000090000 0.0013850000 13173853 96830484 509673472 4.0508890152 3.9966807365 4.2329149246 132 5.2400000000 0.0026068601 0.0015353607 0.0027074905 0.0092303447 0.0053940000 0.0005920000 0.0025190000 0.0000020000 0.0000170000 0.0013760000 13176629 96830484 509673472 4.0511617661 3.9972319603 4.2358608246 133 5.2800000000 0.0026766809 0.0015439421 0.0027074905 0.0092241205 0.0061720000 0.0005870000 0.0023600000 0.0000140000 0.0000140000 0.0023270000 13179405 96830484 509673472 4.0518360138 3.9967811108 4.2383947372 134 5.3200000000 0.0027790670 0.0015531594 0.0027790670 0.0092512116 0.0041340000 0.0005700000 0.0024440000 0.0000000000 0.0000030000 0.0009210000 13182181 96830484 509673472 4.0523610115 3.9975194931 4.2414240837 135 5.3600000000 0.0027011794 0.0015616633 0.0027790670 0.0092515361 0.0059950000 0.0005870000 0.0029090000 0.0000140000 0.0000130000 0.0015810000 13184957 96830484 509673472 4.0528926849 3.9970746040 4.2437062263 136 5.4000000000 0.0026250184 0.0015694821 0.0027790670 0.0092565073 0.0056530000 0.0005900000 0.0027980000 0.0000020000 0.0000150000 0.0013650000 13187733 96830484 509673472 4.0536670685 3.9962670803 4.2459979057 137 5.4400000000 0.0026527706 0.0015773893 0.0027790670 0.0092550534 0.0061620000 0.0005850000 0.0023440000 0.0000140000 0.0000130000 0.0023120000 13190509 96830484 509673472 4.0544557571 3.9961113930 4.2485051155 138 5.4800000000 0.0027017563 0.0015855369 0.0027790670 0.0092366128 0.0049780000 0.0005150000 0.0026530000 0.0000010000 0.0000100000 0.0011600000 13193285 96830484 509673472 4.0548639297 3.9962310791 4.2508163452 139 5.5200000000 0.0026123379 0.0015929239 0.0027790670 0.0092262287 0.0051630000 0.0005050000 0.0026260000 0.0000100000 0.0000090000 0.0013970000 13196061 96830484 509673472 4.0552668571 3.9959194660 4.2530770302 140 5.5600000000 0.0026207643 0.0016002656 0.0027790670 0.0092194884 0.0052860000 0.0005870000 0.0023750000 0.0000010000 0.0000150000 0.0013720000 13198837 96830484 509673472 4.0555200577 3.9954349995 4.2553353310 141 5.6000000000 0.0027086379 0.0016081264 0.0027790670 0.0092727883 0.0060870000 0.0005880000 0.0021680000 0.0000150000 0.0000130000 0.0023670000 13201613 96830484 509673472 4.0556020737 3.9952132702 4.2596111298 142 5.6400000000 0.0026882929 0.0016157332 0.0027790670 0.0092803251 0.0057270000 0.0005870000 0.0027970000 0.0000010000 0.0000150000 0.0013800000 13204389 96830484 509673472 4.0554919243 3.9946734905 4.2616519928 143 5.6800000000 0.0026507401 0.0016229710 0.0027790670 0.0092841770 0.0055350000 0.0005880000 0.0023330000 0.0000160000 0.0000140000 0.0016110000 13207165 96830484 509673472 4.0553412437 3.9941809177 4.2635564804 144 5.7200000000 0.0026901485 0.0016303820 0.0027790670 0.0092819298 0.0057250000 0.0005760000 0.0027870000 0.0000020000 0.0000150000 0.0013870000 13209941 96830484 509673472 4.0548605919 3.9943182468 4.2655358315 145 5.7600000000 0.0026842225 0.0016376499 0.0027790670 0.0092720767 0.0058720000 0.0005020000 0.0026260000 0.0000110000 0.0000090000 0.0020690000 13212717 96830484 509673472 4.0542359352 3.9943068027 4.2673034668 146 5.8000000000 0.0027342024 0.0016451605 0.0027790670 0.0092746852 0.0045980000 0.0005060000 0.0022330000 0.0000010000 0.0000100000 0.0011830000 13215493 96830484 509673472 4.0536212921 3.9946041107 4.2692456245 147 5.8400000000 0.0027268704 0.0016525191 0.0027790670 0.0092667655 0.0055980000 0.0006030000 0.0023540000 0.0000160000 0.0000130000 0.0016300000 13218269 96830484 509673472 4.0529546738 3.9936959743 4.2707872391 148 5.8800000000 0.0028273258 0.0016604570 0.0028273258 0.0092492145 0.0062560000 0.0006090000 0.0027090000 0.0000010000 0.0000160000 0.0018980000 13221045 96830484 509673472 4.0520453453 3.9930982590 4.2721800804 149 5.9200000000 0.0028394484 0.0016683697 0.0028394484 0.0092328801 0.0069250000 0.0005970000 0.0027920000 0.0000160000 0.0000140000 0.0025080000 13223821 96830484 509673472 4.0510907173 3.9930119514 4.2739353180 150 5.9600000000 0.0029217142 0.0016767253 0.0029217142 0.0092170943 0.0049220000 0.0005020000 0.0026590000 0.0000020000 0.0000110000 0.0011750000 13226597 96830484 509673472 4.0501675606 3.9928779602 4.2759709358 151 6.0000000000 0.0028760396 0.0016846678 0.0029217142 0.0091985374 0.0060000000 0.0005870000 0.0027730000 0.0000150000 0.0000140000 0.0016380000 13229373 96830484 509673472 4.0490431786 3.9926292896 4.2777280807 152 6.0400000000 0.0029203738 0.0016927974 0.0029217142 0.0091842946 0.0053400000 0.0005870000 0.0023530000 0.0000010000 0.0000160000 0.0014000000 13232149 96830484 509673472 4.0479283333 3.9924600124 4.2796235085 153 6.0800000000 0.0029471393 0.0017009957 0.0029471393 0.0091727044 0.0067870000 0.0006160000 0.0027660000 0.0000140000 0.0000130000 0.0023870000 13234925 96830484 509673472 4.0468540192 3.9922471046 4.2819437981 154 6.1200000000 0.0029963672 0.0017094072 0.0029963672 0.0091575008 0.0050130000 0.0005030000 0.0026490000 0.0000010000 0.0000100000 0.0011910000 13237701 96830484 509673472 4.0456061363 3.9918813705 4.2839293480 155 6.1600000000 0.0029472411 0.0017173932 0.0029963672 0.0091386851 0.0056500000 0.0005910000 0.0023610000 0.0000170000 0.0000140000 0.0016540000 13240477 96830484 509673472 4.0441861153 3.9916045666 4.2859539986 156 6.2000000000 0.0030372113 0.0017258536 0.0030372113 0.0091495843 0.0057960000 0.0005880000 0.0027770000 0.0000020000 0.0000150000 0.0014080000 13243253 96830484 509673472 4.0412917137 3.9907751083 4.2901277542 157 6.2400000000 0.0031061145 0.0017346451 0.0031061145 0.0091329051 0.0068230000 0.0005900000 0.0027430000 0.0000150000 0.0000130000 0.0024510000 13246029 96830484 509673472 4.0398831367 3.9907488823 4.2924456596 158 6.2800000000 0.0032278374 0.0017440957 0.0032278374 0.0091161976 0.0057830000 0.0005890000 0.0032100000 0.0000020000 0.0000150000 0.0012830000 13248805 96830484 509673472 4.0383777618 3.9904327393 4.2944211960 159 6.3200000000 0.0033080014 0.0017539316 0.0033080014 0.0091032641 0.0053450000 0.0005240000 0.0026200000 0.0000100000 0.0000090000 0.0014690000 13251581 96830484 509673472 4.0367360115 3.9903140068 4.2964577675 160 6.3600000000 0.0033703656 0.0017640343 0.0033703656 0.0090873700 0.0046800000 0.0004700000 0.0025650000 0.0000000000 0.0000080000 0.0011000000 13254357 96830484 509673472 4.0351758003 3.9904613495 4.2985873222 161 6.4000000000 0.0033867375 0.0017741132 0.0033867375 0.0090778577 0.0069370000 0.0005900000 0.0027900000 0.0000150000 0.0000140000 0.0024450000 13257133 96830484 509673472 4.0334997177 3.9904034138 4.3004841805 162 6.4400000000 0.0035173795 0.0017848741 0.0035173795 0.0090855782 0.0058930000 0.0005880000 0.0027900000 0.0000020000 0.0000150000 0.0014190000 13259909 96830484 509673472 4.0317091942 3.9903159142 4.3023028374 163 6.4800000000 0.0035981922 0.0017959987 0.0035981922 0.0090779339 0.0048920000 0.0005010000 0.0022090000 0.0000100000 0.0000090000 0.0014510000 13262685 96830484 509673472 4.0301489830 3.9903907776 4.3040056229 164 6.5200000000 0.0037347283 0.0018078202 0.0037347283 0.0090639945 0.0046900000 0.0005040000 0.0022480000 0.0000010000 0.0000100000 0.0012090000 13265461 96830484 509673472 4.0286273956 3.9905543327 4.3060436249 165 6.5600000000 0.0038031009 0.0018199129 0.0038031009 0.0090559594 0.0073490000 0.0005880000 0.0032010000 0.0000150000 0.0000150000 0.0024180000 13268237 96830484 509673472 4.0270471573 3.9904084206 4.3081221581 166 6.6000000000 0.0040341048 0.0018332514 0.0040341048 0.0090421355 0.0061080000 0.0006030000 0.0029570000 0.0000020000 0.0000150000 0.0014290000 13271013 96830484 509673472 4.0255885124 3.9905695915 4.3100233078 167 6.6400000000 0.0040423027 0.0018464792 0.0040423027 0.0090324613 0.0047020000 0.0005150000 0.0022280000 0.0000100000 0.0000090000 0.0013780000 13273789 96830484 509673472 4.0241007805 3.9909176826 4.3123097420 168 6.6800000000 0.0041523851 0.0018602048 0.0041523851 0.0090169017 0.0047500000 0.0004750000 0.0025840000 0.0000010000 0.0000080000 0.0011200000 13276565 96830484 509673472 4.0226163864 3.9904329777 4.3138241768 169 6.7200000000 0.0042872354 0.0018745660 0.0042872354 0.0090028511 0.0052150000 0.0004740000 0.0021700000 0.0000080000 0.0000070000 0.0019920000 13279341 96830484 509673472 4.0211300850 3.9903712273 4.3152999878 170 6.7600000000 0.0043158932 0.0018889267 0.0043158932 0.0089886463 0.0044900000 0.0004760000 0.0023160000 0.0000010000 0.0000080000 0.0011230000 13282117 96830484 509673472 4.0199980736 3.9902172089 4.3170700073 171 6.8000000000 0.0043291491 0.0019031970 0.0043291491 0.0089760305 0.0051520000 0.0004760000 0.0027140000 0.0000080000 0.0000070000 0.0013760000 13284893 96830484 509673472 4.0189700127 3.9894580841 4.3185772896 172 6.8400000000 0.0044604558 0.0019180648 0.0044604558 0.0089600142 0.0047730000 0.0004790000 0.0025690000 0.0000000000 0.0000080000 0.0011300000 13287669 96830484 509673472 4.0177950859 3.9890344143 4.3197078705 173 6.8800000000 0.0044054147 0.0019324426 0.0044604558 0.0089455698 0.0056550000 0.0004770000 0.0025780000 0.0000080000 0.0000080000 0.0020060000 13290445 96830484 509673472 4.0168457031 3.9884724617 4.3206877708 174 6.9200000000 0.0044445544 0.0019468800 0.0044604558 0.0089551510 0.0045530000 0.0004560000 0.0027480000 0.0000000000 0.0000030000 0.0010920000 13293221 96830484 509673472 4.0160040855 3.9880008698 4.3217501640 175 6.9600000000 0.0044252803 0.0019610423 0.0044604558 0.0089734899 0.0054390000 0.0004570000 0.0033220000 0.0000040000 0.0000040000 0.0014070000 13295997 96830484 509673472 4.0151667595 3.9873969555 4.3228931427 176 7.0000000000 0.0044223750 0.0019750271 0.0044604558 0.0089824977 0.0064750000 0.0006550000 0.0030890000 0.0000020000 0.0000160000 0.0015310000 13298773 96830484 509673472 4.0143203735 3.9869015217 4.3235483170 177 7.0400000000 0.0044739754 0.0019891455 0.0044739754 0.0090089346 0.0081220000 0.0006870000 0.0032260000 0.0000160000 0.0000140000 0.0029990000 13301549 96830484 509673472 4.0137257576 3.9863379002 4.3244576454 178 7.0800000000 0.0044917329 0.0020032049 0.0044917329 0.0090156075 0.0058610000 0.0006910000 0.0030410000 0.0000010000 0.0000110000 0.0013120000 13304325 96830484 509673472 4.0131449699 3.9857678413 4.3252038956 179 7.1200000000 0.0044535310 0.0020168939 0.0044917329 0.0090229488 0.0055090000 0.0005610000 0.0028550000 0.0000090000 0.0000070000 0.0014970000 13307101 96830484 509673472 4.0126614571 3.9853398800 4.3259801865 180 7.1600000000 0.0044591865 0.0020304622 0.0044917329 0.0090514880 0.0052120000 0.0005250000 0.0028660000 0.0000000000 0.0000080000 0.0012100000 13309877 96830484 509673472 4.0122537613 3.9848232269 4.3269414902 181 7.2000000000 0.0044791284 0.0020439908 0.0044917329 0.0090709932 0.0076290000 0.0006390000 0.0030570000 0.0000150000 0.0000140000 0.0026790000 13312653 96830484 509673472 4.0117330551 3.9844810963 4.3274574280 182 7.2400000000 0.0045803026 0.0020579265 0.0045803026 0.0090902974 0.0062470000 0.0006850000 0.0028100000 0.0000020000 0.0000150000 0.0015320000 13315429 96830484 509673472 4.0112504959 3.9843504429 4.3279895782 183 7.2800000000 0.0046219463 0.0020719376 0.0046219463 0.0091170763 0.0074150000 0.0005550000 0.0047210000 0.0000080000 0.0000070000 0.0015090000 13318205 96830484 509673472 4.0108628273 3.9840252399 4.3283376694 184 7.3200000000 0.0048459196 0.0020870136 0.0048459196 0.0092612379 0.0049500000 0.0004980000 0.0028130000 0.0000000000 0.0000060000 0.0011440000 13320981 96830484 509673472 4.0101265907 3.9836301804 4.3291649818 185 7.3600000000 0.0050448151 0.0021030017 0.0050448151 0.0092857867 0.0076020000 0.0006430000 0.0030220000 0.0000160000 0.0000140000 0.0026790000 13323757 96830484 509673472 4.0098128319 3.9834516048 4.3297066689 186 7.4000000000 0.0052239383 0.0021197809 0.0052239383 0.0092883298 0.0064660000 0.0006440000 0.0030660000 0.0000020000 0.0000150000 0.0015200000 13326533 96830484 509673472 4.0092906952 3.9831469059 4.3310360909 187 7.4400000000 0.0052583292 0.0021365646 0.0052583292 0.0092755245 0.0057380000 0.0005570000 0.0030520000 0.0000110000 0.0000090000 0.0014880000 13329309 96830484 509673472 4.0089678764 3.9828729630 4.3325810432 188 7.4800000000 0.0053320434 0.0021535618 0.0053320434 0.0092621598 0.0064690000 0.0006260000 0.0030660000 0.0000020000 0.0000150000 0.0015010000 13332085 96830484 509673472 4.0087590218 3.9826273918 4.3340625763 189 7.5200000000 0.0053793998 0.0021706297 0.0053793998 0.0092563376 0.0072720000 0.0006420000 0.0032110000 0.0000160000 0.0000140000 0.0025580000 13334861 96830484 509673472 4.0086002350 3.9823341370 4.3355641365 190 7.5600000000 0.0054339124 0.0021878049 0.0054339124 0.0092658972 0.0050030000 0.0005200000 0.0028670000 0.0000010000 0.0000070000 0.0011090000 13337637 96830484 509673472 4.0086078644 3.9824433327 4.3372297287 191 7.6000000000 0.0055660168 0.0022054919 0.0055660168 0.0092553440 0.0067520000 0.0006420000 0.0030630000 0.0000150000 0.0000140000 0.0017660000 13340413 96830484 509673472 4.0089015961 3.9823164940 4.3388433456 192 7.6400000000 0.0059074839 0.0022247731 0.0059074839 0.0092445205 0.0064650000 0.0006660000 0.0030710000 0.0000010000 0.0000150000 0.0014540000 13343189 96830484 509673472 4.0089616776 3.9820904732 4.3410859108 193 7.6800000000 0.0064883977 0.0022468644 0.0064883977 0.0092340744 0.0068750000 0.0005580000 0.0035250000 0.0000090000 0.0000070000 0.0021410000 13345965 96830484 509673472 4.0089559555 3.9820270538 4.3434281349 194 7.7200000000 0.0070971800 0.0022718660 0.0070971800 0.0092219463 0.0058920000 0.0004990000 0.0038810000 0.0000010000 0.0000070000 0.0010810000 13348741 96830484 509673472 4.0090866089 3.9820144176 4.3455820084 195 7.7600000000 0.0076627466 0.0022995116 0.0076627466 0.0092095080 0.0073260000 0.0006670000 0.0037050000 0.0000150000 0.0000140000 0.0017750000 13351517 96830484 509673472 4.0092744827 3.9818673134 4.3474564552 196 7.8000000000 0.0083944369 0.0023306081 0.0083944369 0.0091984854 0.0087450000 0.0006380000 0.0056650000 0.0000020000 0.0000160000 0.0014560000 13354293 96830484 509673472 4.0094032288 3.9816327095 4.3493361473 197 7.8400000000 0.0100104213 0.0023695920 0.0100104213 0.0091914905 0.0088610000 0.0005250000 0.0057080000 0.0000060000 0.0000050000 0.0020960000 13357069 96830484 509673472 4.0095539093 3.9813776016 4.3520798683 198 7.8800000000 0.0101037417 0.0024086533 0.0101037417 0.0091769133 0.0048810000 0.0004920000 0.0029430000 0.0000000000 0.0000040000 0.0010650000 13359845 96830484 509673472 4.0097775459 3.9812626839 4.3531956673 199 7.9200000000 0.0103678629 0.0024486494 0.0103678629 0.0091666441 0.0077350000 0.0004650000 0.0055480000 0.0000040000 0.0000040000 0.0013850000 13362621 96830484 509673472 4.0100455284 3.9810295105 4.3539452553 200 7.9600000000 0.0097359782 0.0024850860 0.0103678629 0.0091583027 0.0051600000 0.0004540000 0.0033460000 0.0000000000 0.0000030000 0.0010590000 13365397 96830484 509673472 4.0102772713 3.9807288647 4.3540635109 201 8.0000000000 0.0093933484 0.0025194555 0.0103678629 0.0091452005 0.0078610000 0.0006390000 0.0032510000 0.0000170000 0.0000140000 0.0026160000 13368173 96830484 509673472 4.0104045868 3.9805450439 4.3545126915 202 8.0400000000 0.0101743834 0.0025573511 0.0103678629 0.0091390466 0.0058810000 0.0006270000 0.0030810000 0.0000020000 0.0000170000 0.0012620000 13370949 96830484 509673472 4.0106425285 3.9804811478 4.3557591438 203 8.0800000000 0.0094877006 0.0025914908 0.0103678629 0.0091292277 0.0065660000 0.0005170000 0.0039070000 0.0000070000 0.0000070000 0.0014980000 13373725 96830484 509673472 4.0107579231 3.9805355072 4.3553566933 204 8.1200000000 0.0096726939 0.0026262026 0.0103678629 0.0091293115 0.0076060000 0.0006390000 0.0042370000 0.0000020000 0.0000150000 0.0014540000 13376501 96830484 509673472 4.0108613968 3.9805948734 4.3561210632 205 8.1600000000 0.0104474202 0.0026643549 0.0104474202 0.0091346549 0.0077240000 0.0005530000 0.0042850000 0.0000080000 0.0000070000 0.0021960000 13379277 96830484 509673472 4.0109143257 3.9806978703 4.3575611115 206 8.1999999990 0.0099510653 0.0026997272 0.0104474202 0.0091333631 0.0076760000 0.0004970000 0.0057110000 0.0000010000 0.0000050000 0.0010740000 13382053 96830484 509673472 4.0109086037 3.9810183048 4.3571453094 207 8.2400000000 0.0098463278 0.0027342519 0.0104474202 0.0091619196 0.0055020000 0.0004640000 0.0033280000 0.0000030000 0.0000040000 0.0013970000 13384829 96830484 509673472 4.0110111237 3.9810945988 4.3573908806 208 8.2799999990 0.0099393725 0.0027688919 0.0104474202 0.0091962167 0.0058680000 0.0005570000 0.0031230000 0.0000010000 0.0000100000 0.0012610000 13387605 96830484 509673472 4.0110049248 3.9812037945 4.3575954437 209 8.3200000000 0.0095000574 0.0028010984 0.0104474202 0.0092210471 0.0079140000 0.0006370000 0.0032490000 0.0000140000 0.0000130000 0.0026150000 13390381 96830484 509673472 4.0109834671 3.9810662270 4.3570899963 210 8.3599999990 0.0093327621 0.0028322016 0.0104474202 0.0092184751 0.0060190000 0.0005540000 0.0036050000 0.0000010000 0.0000080000 0.0011560000 13393157 96830484 509673472 4.0108537674 3.9811615944 4.3570723534 211 8.4000000000 0.0090196356 0.0028615259 0.0104474202 0.0092086794 0.0080660000 0.0004960000 0.0056870000 0.0000050000 0.0000050000 0.0014190000 13395933 96830484 509673472 4.0108566284 3.9812991619 4.3565745354 212 8.4399999990 0.0093570994 0.0028921654 0.0104474202 0.0092074052 0.0048590000 0.0004710000 0.0029320000 0.0000010000 0.0000050000 0.0010600000 13398709 96830484 509673472 4.0108404160 3.9815938473 4.3564491272 213 8.4800000000 0.0091421828 0.0029215082 0.0104474202 0.0092168392 0.0088990000 0.0006400000 0.0042210000 0.0000140000 0.0000160000 0.0026300000 13401485 96830484 509673472 4.0108604431 3.9815759659 4.3559088707 214 8.5200000000 0.0087858299 0.0029489116 0.0104474202 0.0092118912 0.0060120000 0.0005550000 0.0035730000 0.0000010000 0.0000100000 0.0011790000 13404261 96830484 509673472 4.0109009743 3.9816484451 4.3549818993 215 8.5600000000 0.0092473542 0.0029782067 0.0104474202 0.0092047535 0.0070660000 0.0006400000 0.0032380000 0.0000160000 0.0000140000 0.0017810000 13407037 96830484 509673472 4.0107975006 3.9820768833 4.3550796509 216 8.6000000000 0.0091188876 0.0030066357 0.0104474202 0.0092090340 0.0054360000 0.0005540000 0.0029860000 0.0000010000 0.0000100000 0.0011900000 13409813 96830484 509673472 4.0107293129 3.9823811054 4.3544077873 217 8.6400000000 0.0085780527 0.0030323105 0.0104474202 0.0092159110 0.0091720000 0.0006390000 0.0044870000 0.0000160000 0.0000140000 0.0026120000 13412589 96830484 509673472 4.0105900764 3.9826376438 4.3533692360 218 8.6800000000 0.0085879760 0.0030577952 0.0104474202 0.0092305441 0.0063960000 0.0005520000 0.0039690000 0.0000000000 0.0000080000 0.0011550000 13415365 96830484 509673472 4.0104789734 3.9830193520 4.3528542519 219 8.7200000000 0.0087802671 0.0030839252 0.0104474202 0.0092450797 0.0058410000 0.0005550000 0.0030670000 0.0000100000 0.0000090000 0.0014930000 13418141 96830484 509673472 4.0103459358 3.9834182262 4.3526701927 220 8.7600000000 0.0081671104 0.0031070306 0.0104474202 0.0092519170 0.0049890000 0.0004950000 0.0028070000 0.0000000000 0.0000060000 0.0011110000 13420917 96830484 509673472 4.0102891922 3.9837274551 4.3514075279 221 8.8000000000 0.0083552981 0.0031307784 0.0104474202 0.0092683829 0.0080080000 0.0006380000 0.0032150000 0.0000150000 0.0000130000 0.0026960000 13423693 96830484 509673472 4.0101971626 3.9838819504 4.3512544632 222 8.8400000000 0.0079384921 0.0031524348 0.0104474202 0.0092708044 0.0074110000 0.0006420000 0.0044950000 0.0000010000 0.0000110000 0.0012920000 13426469 96830484 509673472 4.0100774765 3.9841656685 4.3502821922 223 8.8800000000 0.0077960142 0.0031732580 0.0104474202 0.0092820175 0.0053810000 0.0005150000 0.0028140000 0.0000060000 0.0000050000 0.0014660000 13429245 96830484 509673472 4.0097708702 3.9846215248 4.3494644165 224 8.9200000000 0.0077517307 0.0031936976 0.0104474202 0.0093073481 0.0048500000 0.0004800000 0.0027690000 0.0000010000 0.0000050000 0.0011160000 13432021 96830484 509673472 4.0094776154 3.9849691391 4.3486957550 225 8.9600000000 0.0076680109 0.0032135834 0.0104474202 0.0093264084 0.0083760000 0.0006350000 0.0035220000 0.0000150000 0.0000130000 0.0027270000 13434797 96830484 509673472 4.0091376305 3.9855437279 4.3477711678 226 9.0000000000 0.0071449238 0.0032309787 0.0104474202 0.0093514782 0.0068980000 0.0006240000 0.0035510000 0.0000010000 0.0000150000 0.0015750000 13437573 96830484 509673472 4.0088920593 3.9858422279 4.3463711739 227 9.0400000000 0.0073298141 0.0032490353 0.0104474202 0.0093709264 0.0056170000 0.0005190000 0.0029900000 0.0000060000 0.0000050000 0.0015050000 13440349 96830484 509673472 4.0085000992 3.9863262177 4.3457522392 228 9.0800000000 0.0077574388 0.0032688090 0.0104474202 0.0094021979 0.0066010000 0.0004820000 0.0045530000 0.0000010000 0.0000060000 0.0011330000 13443125 96830484 509673472 4.0080971718 3.9868245125 4.3454227448 229 9.1200000000 0.0076751164 0.0032880505 0.0104474202 0.0094319756 0.0081610000 0.0006400000 0.0034940000 0.0000150000 0.0000150000 0.0028370000 13445901 96830484 509673472 4.0076885223 3.9869151115 4.3443636894 230 9.1600000000 0.0073677520 0.0033057883 0.0104474202 0.0094383139 0.0058100000 0.0006440000 0.0027630000 0.0000020000 0.0000150000 0.0013930000 13448677 96830484 509673472 4.0072302818 3.9876627922 4.3427062035 231 9.2000000000 0.0071659684 0.0033224991 0.0104474202 0.0094540623 0.0082010000 0.0005170000 0.0055190000 0.0000060000 0.0000060000 0.0015560000 13451453 96830484 509673472 4.0066800117 3.9880549908 4.3415141106 232 9.2400000000 0.0073025580 0.0033396545 0.0104474202 0.0094734729 0.0050820000 0.0004810000 0.0029130000 0.0000000000 0.0000050000 0.0011860000 13454229 96830484 509673472 4.0061664581 3.9887406826 4.3406000137 233 9.2800000000 0.0076677054 0.0033582298 0.0104474202 0.0095031922 0.0085720000 0.0006400000 0.0035010000 0.0000140000 0.0000140000 0.0029110000 13457005 96830484 509673472 4.0055632591 3.9893617630 4.3402099609 234 9.3200000000 0.0074659991 0.0033757844 0.0104474202 0.0095291522 0.0060120000 0.0005530000 0.0030660000 0.0000020000 0.0000100000 0.0014430000 13459781 96830484 509673472 4.0049338341 3.9900264740 4.3384838104 235 9.3600000000 0.0074535352 0.0033931365 0.0104474202 0.0095412989 0.0068490000 0.0005280000 0.0038740000 0.0000080000 0.0000070000 0.0016540000 13462557 96830484 509673472 4.0043087006 3.9902791977 4.3375473022 236 9.4000000000 0.0074760844 0.0034104372 0.0104474202 0.0095448467 0.0051290000 0.0005020000 0.0028150000 0.0000000000 0.0000070000 0.0012790000 13465333 96830484 509673472 4.0035848618 3.9908864498 4.3364090919 237 9.4400000000 0.0074458299 0.0034274641 0.0104474202 0.0095540989 0.0083980000 0.0006720000 0.0030540000 0.0000150000 0.0000130000 0.0029640000 13468109 96830484 509673472 4.0028185844 3.9913065434 4.3353381157 238 9.4800000000 0.0075751161 0.0034448912 0.0104474202 0.0096263884 0.0057080000 0.0006170000 0.0028960000 0.0000010000 0.0000070000 0.0013300000 13470885 96830484 509673472 4.0010070801 3.9935417175 4.3327903748 239 9.5200000000 0.0074875811 0.0034618063 0.0104474202 0.0096549416 0.0054910000 0.0005410000 0.0027800000 0.0000060000 0.0000050000 0.0016040000 13473661 96830484 509673472 4.0000514984 3.9942486286 4.3315863609 240 9.5600000000 0.0076234955 0.0034791466 0.0104474202 0.0096807139 0.0070630000 0.0006440000 0.0030930000 0.0000020000 0.0000150000 0.0017640000 13476437 96830484 509673472 3.9989740849 3.9958837032 4.3301410675 241 9.6000000000 0.0076313168 0.0034963756 0.0104474202 0.0097478420 0.0073580000 0.0006420000 0.0030230000 0.0000100000 0.0000100000 0.0026360000 13479213 96830484 509673472 3.9979183674 3.9967250824 4.3291263580 242 9.6400000000 0.0078584636 0.0035144007 0.0104474202 0.0098188713 0.0052080000 0.0005180000 0.0027840000 0.0000000000 0.0000070000 0.0012770000 13481989 96830484 509673472 3.9969003201 3.9977717400 4.3280768394 243 9.6800000000 0.0079494929 0.0035326521 0.0104474202 0.0098745292 0.0055370000 0.0004850000 0.0029010000 0.0000050000 0.0000050000 0.0015950000 13484765 96830484 509673472 3.9958236217 3.9987645149 4.3264889717 244 9.7200000000 0.0080841407 0.0035513058 0.0104474202 0.0099285083 0.0050660000 0.0004850000 0.0027710000 0.0000010000 0.0000060000 0.0012580000 13487541 96830484 509673472 3.9947097301 3.9998354912 4.3253035545 245 9.7600000000 0.0079419054 0.0035692266 0.0104474202 0.0099720347 0.0061210000 0.0004840000 0.0027560000 0.0000050000 0.0000050000 0.0023240000 13490317 96830484 509673472 3.9937393665 4.0003471375 4.3237586021 246 9.8000000000 0.0081236530 0.0035877405 0.0104474202 0.0099986366 0.0059500000 0.0004860000 0.0036430000 0.0000010000 0.0000060000 0.0012630000 13493093 96830484 509673472 3.9925475121 4.0014157295 4.3223347664 247 9.8400000000 0.0080912495 0.0036059733 0.0104474202 0.0100366688 0.0053940000 0.0004850000 0.0027480000 0.0000050000 0.0000050000 0.0015950000 13495869 96830484 509673472 3.9915382862 4.0025768280 4.3208422661 248 9.8800000000 0.0080965348 0.0036240804 0.0104474202 0.0100863131 0.0054760000 0.0004850000 0.0031890000 0.0000010000 0.0000050000 0.0012450000 13498645 96830484 509673472 3.9904477596 4.0036439896 4.3190588951 249 9.9200000000 0.0082139820 0.0036425138 0.0104474202 0.0101389363 0.0061160000 0.0004880000 0.0027410000 0.0000050000 0.0000040000 0.0023210000 13501421 96830484 509673472 3.9894444942 4.0044584274 4.3175001144 250 9.9600000000 0.0082025733 0.0036607540 0.0104474202 0.0101826817 0.0044670000 0.0004870000 0.0021580000 0.0000010000 0.0000050000 0.0012560000 13504197 96830484 509673472 3.9884352684 4.0053396225 4.3160448074 251 10.0000000000 0.0082003195 0.0036788399 0.0104474202 0.0102255231 0.0053820000 0.0004860000 0.0027350000 0.0000050000 0.0000050000 0.0015910000 13506973 96830484 509673472 3.9873466492 4.0067238808 4.3144016266 252 10.0400000000 0.0083805118 0.0036974974 0.0104474202 0.0102859393 0.0050510000 0.0004840000 0.0027410000 0.0000010000 0.0000050000 0.0012590000 13509749 96830484 509673472 3.9863622189 4.0078868866 4.3128724098 253 10.0800000000 0.0083912984 0.0037160499 0.0104474202 0.0103215827 0.0058030000 0.0004830000 0.0024200000 0.0000050000 0.0000050000 0.0023270000 13512525 96830484 509673472 3.9854915142 4.0089273453 4.3111243248 254 10.1200000000 0.0084946332 0.0037348633 0.0104474202 0.0103571095 0.0051930000 0.0004980000 0.0028690000 0.0000000000 0.0000050000 0.0012510000 13515301 96830484 509673472 3.9845380783 4.0101799965 4.3095536232 255 10.1600000000 0.0085506858 0.0037537488 0.0104474202 0.0104054363 0.0053460000 0.0004880000 0.0027030000 0.0000050000 0.0000050000 0.0015800000 13518077 96830484 509673472 3.9835050106 4.0112915039 4.3078804016 256 10.2000000000 0.0084009627 0.0037719020 0.0104474202 0.0104468738 0.0050510000 0.0004860000 0.0027170000 0.0000000000 0.0000050000 0.0012730000 13520853 96830484 509673472 3.9826779366 4.0121917725 4.3060555458 257 10.2400000000 0.0084649855 0.0037901630 0.0104474202 0.0104899703 0.0084930000 0.0006570000 0.0030060000 0.0000160000 0.0000130000 0.0030490000 13548205 96830484 509673472 3.9817016125 4.0132126808 4.3046846390 258 10.2800000000 0.0083096474 0.0038076804 0.0104474202 0.0105014348 0.0071700000 0.0006400000 0.0030160000 0.0000020000 0.0000150000 0.0017920000 13602181 96830484 509673472 3.9809315205 4.0141053200 4.3027672768 259 10.3200000000 0.0082892794 0.0038249839 0.0104474202 0.0105031096 0.0061440000 0.0005580000 0.0028620000 0.0000100000 0.0000090000 0.0018420000 13604957 96830484 509673472 3.9800252914 4.0149559975 4.3011431694 260 10.3600000000 0.0083651114 0.0038424459 0.0104474202 0.0105207268 0.0061300000 0.0005550000 0.0028670000 0.0000010000 0.0000110000 0.0015410000 13607733 96830484 509673472 3.9790070057 4.0162878036 4.2994856834 261 10.4000000000 0.0083733071 0.0038598055 0.0104474202 0.0105539431 0.0067110000 0.0005270000 0.0027660000 0.0000100000 0.0000070000 0.0025350000 13610509 96830484 509673472 3.9782278538 4.0169663429 4.2979764938 262 10.4400000000 0.0082186805 0.0038764425 0.0104474202 0.0105653626 0.0053790000 0.0004980000 0.0028860000 0.0000010000 0.0000060000 0.0013030000 13613285 96830484 509673472 3.9773817062 4.0175733566 4.2961611748 263 10.4800000000 0.0082422914 0.0038930426 0.0104474202 0.0105652026 0.0053840000 0.0004870000 0.0026940000 0.0000050000 0.0000050000 0.0016070000 13616061 96830484 509673472 3.9765222073 4.0184845924 4.2946333885 264 10.5200000000 0.0081973970 0.0039093470 0.0104474202 0.0105684658 0.0051980000 0.0004810000 0.0028510000 0.0000010000 0.0000050000 0.0012750000 13618837 96830484 509673472 3.9755916595 4.0193452835 4.2928915024 265 10.5600000000 0.0082948729 0.0039258962 0.0104474202 0.0105939266 0.0080680000 0.0006420000 0.0025230000 0.0000160000 0.0000140000 0.0030980000 13621613 96830484 509673472 3.9747025967 4.0196080208 4.2916679382 266 10.6000000000 0.0083155129 0.0039423985 0.0104474202 0.0105921416 0.0071820000 0.0006410000 0.0029780000 0.0000020000 0.0000160000 0.0018000000 13624389 96830484 509673472 3.9739615917 4.0201311111 4.2899041176 267 10.6400000000 0.0083521465 0.0039589144 0.0104474202 0.0105759519 0.0060450000 0.0005760000 0.0028280000 0.0000100000 0.0000090000 0.0017350000 13627165 96830484 509673472 3.9731011391 4.0208563805 4.2883372307 268 10.6800000000 0.0082716839 0.0039750068 0.0104474202 0.0105663583 0.0064230000 0.0006020000 0.0033040000 0.0000010000 0.0000110000 0.0015190000 13629941 96830484 509673472 3.9722785950 4.0212922096 4.2864379883 269 10.7200000000 0.0083407434 0.0039912363 0.0104474202 0.0105647266 0.0085260000 0.0006910000 0.0034270000 0.0000150000 0.0000150000 0.0030470000 13632717 96830484 509673472 3.9714086056 4.0216097832 4.2850737572 270 10.7600000000 0.0084729455 0.0040078353 0.0104474202 0.0105695707 0.0054920000 0.0005250000 0.0028990000 0.0000010000 0.0000080000 0.0013530000 13635493 96830484 509673472 3.9705975056 4.0220804214 4.2834405899 271 10.8000000000 0.0084549459 0.0040242453 0.0104474202 0.0105634851 0.0064830000 0.0005740000 0.0029820000 0.0000100000 0.0000100000 0.0018710000 13638269 96830484 509673472 3.9698877335 4.0227007866 4.2812347412 272 10.8400000000 0.0084559722 0.0040405384 0.0104474202 0.0105497717 0.0079250000 0.0006400000 0.0036160000 0.0000020000 0.0000140000 0.0018130000 13641045 96830484 509673472 3.9689769745 4.0233101845 4.2795529366 273 10.8800000000 0.0084013864 0.0040565122 0.0104474202 0.0105545102 0.0077140000 0.0006390000 0.0031560000 0.0000160000 0.0000140000 0.0026880000 13643821 96830484 509673472 3.9682135582 4.0237793922 4.2776021957 274 10.9200000000 0.0084627494 0.0040725933 0.0104474202 0.0105534024 0.0058760000 0.0005170000 0.0033110000 0.0000000000 0.0000060000 0.0013120000 13646597 96830484 509673472 3.9673178196 4.0240283012 4.2759976387 275 10.9600000000 0.0085697351 0.0040889466 0.0104474202 0.0105400939 0.0067360000 0.0004810000 0.0041160000 0.0000050000 0.0000040000 0.0016060000 13649373 96830484 509673472 3.9667379856 4.0241246223 4.2741022110 276 11.0000000000 0.0085802097 0.0041052193 0.0104474202 0.0105250779 0.0057880000 0.0004620000 0.0036330000 0.0000000000 0.0000040000 0.0012290000 13652149 96830484 509673472 3.9661104679 4.0243339539 4.2722992897 277 11.0400000000 0.0084565319 0.0041209280 0.0104474202 0.0105159591 0.0090160000 0.0006380000 0.0034170000 0.0000160000 0.0000130000 0.0030970000 13654925 96830484 509673472 3.9651787281 4.0243501663 4.2706551552 278 11.0800000000 0.0084904535 0.0041366457 0.0104474202 0.0105089524 0.0058450000 0.0005540000 0.0029560000 0.0000010000 0.0000070000 0.0013940000 13657701 96830484 509673472 3.9644494057 4.0244865417 4.2690205574 279 11.1200000000 0.0084777419 0.0041522052 0.0104474202 0.0104941354 0.0055150000 0.0004960000 0.0026870000 0.0000070000 0.0000060000 0.0016280000 13660477 96830484 509673472 3.9638471603 4.0244646072 4.2673048973 280 11.1600000000 0.0084462622 0.0041675411 0.0104474202 0.0104761715 0.0073850000 0.0006640000 0.0031170000 0.0000020000 0.0000150000 0.0017810000 13663253 96830484 509673472 3.9631016254 4.0249257088 4.2655110359 281 11.2000000000 0.0085313050 0.0041830705 0.0104474202 0.0104602484 0.0078950000 0.0005510000 0.0033860000 0.0000110000 0.0000090000 0.0027230000 13666029 96830484 509673472 3.9622721672 4.0251955986 4.2640514374 282 11.2400000000 0.0085037313 0.0041983920 0.0104474202 0.0104439754 0.0064840000 0.0006410000 0.0029490000 0.0000020000 0.0000140000 0.0016580000 13668805 96830484 509673472 3.9615557194 4.0255756378 4.2622976303 283 11.2800000000 0.0083806114 0.0042131702 0.0104474202 0.0104265872 0.0066610000 0.0005550000 0.0033670000 0.0000100000 0.0000090000 0.0017930000 13671581 96830484 509673472 3.9602816105 4.0256452560 4.2607326508 284 11.3200000000 0.0084664514 0.0042281465 0.0104474202 0.0104086073 0.0072340000 0.0006410000 0.0029780000 0.0000020000 0.0000170000 0.0017690000 13674357 96830484 509673472 3.9596126080 4.0259356499 4.2592110634 285 11.3600000000 0.0085835513 0.0042434286 0.0104474202 0.0103906355 0.0076690000 0.0006400000 0.0030620000 0.0000150000 0.0000150000 0.0026930000 13677133 96830484 509673472 3.9585754871 4.0262241364 4.2575139999 286 11.4000000000 0.0085560968 0.0042585079 0.0104474202 0.0103729473 0.0054280000 0.0005200000 0.0026900000 0.0000010000 0.0000070000 0.0013730000 13679909 96830484 509673472 3.9577865601 4.0263476372 4.2554030418 287 11.4400000000 0.0086137820 0.0042736831 0.0104474202 0.0103551464 0.0055640000 0.0004970000 0.0026430000 0.0000060000 0.0000050000 0.0016580000 13682685 96830484 509673472 3.9567599297 4.0262794495 4.2538442612 288 11.4800000000 0.0085293939 0.0042884598 0.0104474202 0.0103376139 0.0072700000 0.0006390000 0.0029170000 0.0000020000 0.0000140000 0.0018060000 13685461 96830484 509673472 3.9558427334 4.0262856483 4.2514491081 289 11.5200000000 0.0086094029 0.0043034112 0.0104474202 0.0103205290 0.0076880000 0.0006370000 0.0030600000 0.0000170000 0.0000130000 0.0027070000 13688237 96830484 509673472 3.9540741444 4.0260448456 4.2502374649 290 11.5600000000 0.0085354643 0.0043180045 0.0104474202 0.0103033785 0.0054460000 0.0005160000 0.0026790000 0.0000010000 0.0000070000 0.0013980000 13691013 96830484 509673472 3.9529075623 4.0259666443 4.2478971481 291 11.6000000000 0.0085238246 0.0043324575 0.0104474202 0.0102900801 0.0083570000 0.0006370000 0.0043880000 0.0000160000 0.0000130000 0.0020410000 13693789 96830484 509673472 3.9514331818 4.0256743431 4.2462053299 292 11.6400000000 0.0084832814 0.0043466726 0.0104474202 0.0102728302 0.0054090000 0.0005580000 0.0024850000 0.0000010000 0.0000100000 0.0014100000 13696565 96830484 509673472 3.9498915672 4.0250353813 4.2444782257 293 11.6800000000 0.0084644966 0.0043607266 0.0104474202 0.0102617011 0.0074530000 0.0005510000 0.0028870000 0.0000110000 0.0000090000 0.0027320000 13699341 96830484 509673472 3.9481618404 4.0244574547 4.2428565025 294 11.7200000000 0.0084479535 0.0043746288 0.0104474202 0.0102448955 0.0055850000 0.0005180000 0.0026850000 0.0000010000 0.0000090000 0.0014090000 13702117 96830484 509673472 3.9462952614 4.0244336128 4.2408070564 295 11.7600000000 0.0084152650 0.0043883258 0.0104474202 0.0102294711 0.0076790000 0.0006410000 0.0029160000 0.0000150000 0.0000140000 0.0021640000 13704893 96830484 509673472 3.9441955090 4.0243196487 4.2392430305 296 11.8000000000 0.0083656153 0.0044017626 0.0104474202 0.0102128544 0.0063670000 0.0006380000 0.0028720000 0.0000020000 0.0000150000 0.0015480000 13707669 96830484 509673472 3.9421436787 4.0241084099 4.2376155853 297 11.8400000000 0.0085355267 0.0044156810 0.0104474202 0.0101958512 0.0066230000 0.0005160000 0.0028280000 0.0000090000 0.0000070000 0.0024840000 13710445 96830484 509673472 3.9399499893 4.0240778923 4.2362604141 298 11.8800000000 0.0084772045 0.0044293103 0.0104474202 0.0101836601 0.0053980000 0.0004990000 0.0027710000 0.0000010000 0.0000060000 0.0013420000 13713221 96830484 509673472 3.9379241467 4.0238981247 4.2345190048 299 11.9200000000 0.0084817577 0.0044428636 0.0104474202 0.0101741766 0.0078150000 0.0006260000 0.0030510000 0.0000170000 0.0000140000 0.0021820000 13715997 96830484 509673472 3.9354519844 4.0240383148 4.2331409454 300 11.9600000000 0.0084415581 0.0044561926 0.0104474202 0.0101600875 0.0073770000 0.0006410000 0.0029050000 0.0000020000 0.0000160000 0.0018530000 13718773 96830484 509673472 3.9331145287 4.0237860680 4.2315073013 301 12.0000000000 0.0085426737 0.0044697690 0.0104474202 0.0101495897 0.0070110000 0.0005550000 0.0027210000 0.0000100000 0.0000090000 0.0027380000 13721549 96830484 509673472 3.9306883812 4.0240292549 4.2300109863 302 12.0400000000 0.0084128221 0.0044828254 0.0104474202 0.0101376159 0.0061570000 0.0005550000 0.0027260000 0.0000010000 0.0000110000 0.0015610000 13724325 96830484 509673472 3.9281919003 4.0242929459 4.2282814980 303 12.0800000000 0.0084352251 0.0044958696 0.0104474202 0.0101237176 0.0078930000 0.0006470000 0.0030390000 0.0000150000 0.0000130000 0.0021990000 13727101 96830484 509673472 3.9257733822 4.0242705345 4.2267684937 304 12.1200000000 0.0084945746 0.0045090233 0.0104474202 0.0101128603 0.0064820000 0.0006380000 0.0029180000 0.0000020000 0.0000170000 0.0015910000 13729877 96830484 509673472 3.9233424664 4.0241513252 4.2253603935 305 12.1600000000 0.0084925294 0.0045220840 0.0104474202 0.0101047413 0.0066110000 0.0005170000 0.0026500000 0.0000070000 0.0000070000 0.0026130000 13732653 96830484 509673472 3.9208054543 4.0245270729 4.2237849236 306 12.2000000000 0.0084954211 0.0045350687 0.0104474202 0.0100911624 0.0073530000 0.0006260000 0.0028630000 0.0000020000 0.0000150000 0.0018720000 13735429 96830484 509673472 3.9182350636 4.0249123573 4.2222027779 307 12.2400000000 0.0085113393 0.0045480207 0.0104474202 0.0100749475 0.0071600000 0.0006380000 0.0032690000 0.0000100000 0.0000100000 0.0018770000 13738205 96830484 509673472 3.9157466888 4.0250315666 4.2205452919 308 12.2800000000 0.0084459493 0.0045606763 0.0104474202 0.0100591364 0.0055410000 0.0005160000 0.0026270000 0.0000010000 0.0000080000 0.0014560000 13740981 96830484 509673472 3.9134204388 4.0244021416 4.2193317413 309 12.3200000000 0.0084764613 0.0045733488 0.0104474202 0.0100493721 0.0059850000 0.0004940000 0.0021720000 0.0000060000 0.0000060000 0.0025060000 13743757 96830484 509673472 3.9109220505 4.0241298676 4.2180233002 310 12.3600000000 0.0084642563 0.0045859001 0.0104474202 0.0100406364 0.0050290000 0.0004940000 0.0023420000 0.0000000000 0.0000060000 0.0013770000 13746533 96830484 509673472 3.9083957672 4.0243215561 4.2165722847 311 12.4000000000 0.0084183877 0.0045982232 0.0104474202 0.0100248667 0.0078440000 0.0006360000 0.0030250000 0.0000150000 0.0000140000 0.0021460000 13749309 96830484 509673472 3.9056699276 4.0243263245 4.2154898643 312 12.4400000000 0.0084605608 0.0046106025 0.0104474202 0.0100090898 0.0068820000 0.0006590000 0.0030600000 0.0000010000 0.0000160000 0.0017610000 13752085 96830484 509673472 3.9032633305 4.0239453316 4.2142572403 313 12.4800000000 0.0085687377 0.0046232483 0.0104474202 0.0099944493 0.0071360000 0.0005550000 0.0027530000 0.0000100000 0.0000090000 0.0027690000 13754861 96830484 509673472 3.9008312225 4.0237746239 4.2131800652 314 12.5200000000 0.0085401041 0.0046357224 0.0104474202 0.0099788426 0.0057380000 0.0004950000 0.0030400000 0.0000010000 0.0000070000 0.0013680000 13757637 96830484 509673472 3.8980045319 4.0233750343 4.2124261856 315 12.5600000000 0.0084526017 0.0046478394 0.0104474202 0.0099646136 0.0071480000 0.0005530000 0.0032870000 0.0000120000 0.0000090000 0.0019010000 13760413 96830484 509673472 3.8957271576 4.0222854614 4.2115316391 316 12.6000000000 0.0085462211 0.0046601761 0.0104474202 0.0099536850 0.0056090000 0.0005190000 0.0026510000 0.0000000000 0.0000080000 0.0014420000 13763189 96830484 509673472 3.8933212757 4.0216693878 4.2107067108 317 12.6400000000 0.0084982850 0.0046722837 0.0104474202 0.0099433286 0.0088930000 0.0006410000 0.0037460000 0.0000150000 0.0000150000 0.0030890000 13765965 96830484 509673472 3.8912801743 4.0206804276 4.2097511292 318 12.6800000000 0.0085926130 0.0046846118 0.0104474202 0.0099455453 0.0059520000 0.0005190000 0.0032240000 0.0000010000 0.0000060000 0.0013630000 13768741 96830484 509673472 3.8891396523 4.0200119019 4.2089519501 319 12.7200000000 0.0086196372 0.0046969473 0.0104474202 0.0099416124 0.0080300000 0.0004850000 0.0051890000 0.0000050000 0.0000040000 0.0016330000 13771517 96830484 509673472 3.8870503902 4.0197510719 4.2078204155 320 12.7600000000 0.0086338213 0.0047092500 0.0104474202 0.0099275796 0.0058710000 0.0004750000 0.0035450000 0.0000010000 0.0000050000 0.0012820000 13774293 96830484 509673472 3.8851675987 4.0196032524 4.2065825462 321 12.8000000000 0.0086484673 0.0047215217 0.0104474202 0.0099124751 0.0084280000 0.0006430000 0.0030560000 0.0000170000 0.0000140000 0.0031740000 13777069 96830484 509673472 3.8835182190 4.0188994408 4.2052555084 322 12.8400000000 0.0087368302 0.0047339916 0.0104474202 0.0098999831 0.0063940000 0.0005550000 0.0033200000 0.0000010000 0.0000100000 0.0014520000 13779845 96830484 509673472 3.8820548058 4.0177397728 4.2041320801 323 12.8800000000 0.0087785972 0.0047465136 0.0104474202 0.0098939135 0.0078930000 0.0006390000 0.0039290000 0.0000160000 0.0000130000 0.0018830000 13782621 96830484 509673472 3.8803381920 4.0175046921 4.2028651237 324 12.9200000000 0.0088426098 0.0047591559 0.0104474202 0.0098825129 0.0059860000 0.0005170000 0.0032320000 0.0000010000 0.0000070000 0.0013770000 13785397 96830484 509673472 3.8784828186 4.0170989037 4.2013406754 325 12.9600000000 0.0089084646 0.0047719230 0.0104474202 0.0098699420 0.0087740000 0.0006420000 0.0034870000 0.0000150000 0.0000140000 0.0031910000 13788173 96830484 509673472 3.8770363331 4.0163283348 4.1999340057 326 13.0000000000 0.0086539397 0.0047838310 0.0104474202 0.0098602014 0.0063810000 0.0005520000 0.0032880000 0.0000010000 0.0000110000 0.0014610000 13790949 96830484 509673472 3.8756020069 4.0151863098 4.1983995438 327 13.0400000000 0.0087397452 0.0047959286 0.0104474202 0.0098514986 0.0065510000 0.0005380000 0.0035640000 0.0000060000 0.0000050000 0.0016310000 13793725 96830484 509673472 3.8738718033 4.0147619247 4.1967644691 328 13.0800000000 0.0088588186 0.0048083155 0.0104474202 0.0098395538 0.0077430000 0.0006930000 0.0034850000 0.0000020000 0.0000150000 0.0019030000 13796501 96830484 509673472 3.8724107742 4.0142736435 4.1953883171 329 13.1200000000 0.0089302612 0.0048208442 0.0104474202 0.0098296302 0.0074680000 0.0005170000 0.0035630000 0.0000070000 0.0000050000 0.0025130000 13799277 96830484 509673472 3.8708889484 4.0136485100 4.1936917305 330 13.1600000000 0.0090816971 0.0048337559 0.0104474202 0.0098195377 0.0070100000 0.0006410000 0.0033220000 0.0000020000 0.0000150000 0.0015990000 13802053 96830484 509673472 3.8695321083 4.0130739212 4.1918740273 331 13.2000000000 0.0090235732 0.0048464139 0.0104474202 0.0098096439 0.0065160000 0.0005180000 0.0032110000 0.0000070000 0.0000070000 0.0017760000 13804829 96830484 509673472 3.8681123257 4.0125494003 4.1899337769 332 13.2400000000 0.0090522235 0.0048590820 0.0104474202 0.0098009352 0.0080410000 0.0006400000 0.0039450000 0.0000010000 0.0000160000 0.0018970000 13807605 96830484 509673472 3.8666393757 4.0118179321 4.1879634857 333 13.2800000000 0.0090527628 0.0048716757 0.0104474202 0.0097961336 0.0066930000 0.0005170000 0.0027950000 0.0000080000 0.0000070000 0.0025030000 13810381 96830484 509673472 3.8654561043 4.0117053986 4.1854748726 334 13.3200000000 0.0089330832 0.0048838356 0.0104474202 0.0097860721 0.0082410000 0.0006430000 0.0035250000 0.0000020000 0.0000170000 0.0018930000 13813157 96830484 509673472 3.8641252518 4.0113124847 4.1831674576 335 13.3600000000 0.0091652321 0.0048966158 0.0104474202 0.0097772723 0.0079090000 0.0005630000 0.0047910000 0.0000080000 0.0000070000 0.0016670000 13815933 96830484 509673472 3.8627986908 4.0099015236 4.1812386513 336 13.4000000000 0.0092130844 0.0049094625 0.0104474202 0.0098035446 0.0059580000 0.0004800000 0.0035590000 0.0000000000 0.0000050000 0.0012890000 13818709 96830484 509673472 3.8616740704 4.0099678040 4.1786031723 337 13.4400000000 0.0093237143 0.0049225611 0.0104474202 0.0098131220 0.0077530000 0.0004630000 0.0043340000 0.0000040000 0.0000030000 0.0023980000 13821485 96830484 509673472 3.8602707386 4.0106110573 4.1752419472 338 13.4800000000 0.0092052659 0.0049352319 0.0104474202 0.0098102276 0.0049000000 0.0004590000 0.0026780000 0.0000000000 0.0000030000 0.0012670000 13824261 96830484 509673472 3.8589625359 4.0102295876 4.1728568077 339 13.5200000000 0.0091794189 0.0049477516 0.0104474202 0.0098088827 0.0101110000 0.0006400000 0.0050420000 0.0000160000 0.0000140000 0.0021960000 13827037 96830484 509673472 3.8575508595 4.0106339455 4.1702079773 340 13.5600000000 0.0093280971 0.0049606350 0.0104474202 0.0097969047 0.0074240000 0.0005530000 0.0041670000 0.0000020000 0.0000110000 0.0015860000 13829813 96830484 509673472 3.8561062813 4.0113210678 4.1673827171 341 13.6000000000 0.0093597630 0.0049735356 0.0104474202 0.0097825053 0.0088050000 0.0004950000 0.0051190000 0.0000060000 0.0000050000 0.0024440000 13832589 96830484 509673472 3.8547971249 4.0115303993 4.1649246216 342 13.6400000000 0.0094958292 0.0049867587 0.0104474202 0.0097681846 0.0074430000 0.0004720000 0.0051930000 0.0000010000 0.0000040000 0.0012780000 13835365 96830484 509673472 3.8534090519 4.0114026070 4.1622357368 343 13.6800000000 0.0097773932 0.0050007256 0.0104474202 0.0097544752 0.0076070000 0.0005520000 0.0040200000 0.0000100000 0.0000090000 0.0018960000 13838141 96830484 509673472 3.8525154591 4.0110712051 4.1596360207 344 13.7200000000 0.0098041445 0.0050146890 0.0104474202 0.0097484333 0.0084890000 0.0005490000 0.0054090000 0.0000010000 0.0000080000 0.0014510000 13840917 96830484 509673472 3.8516473770 4.0111989975 4.1563372612 345 13.7600000000 0.0095575359 0.0050278567 0.0104474202 0.0097398777 0.0075400000 0.0004940000 0.0039740000 0.0000050000 0.0000050000 0.0024200000 13843693 96830484 509673472 3.8506093025 4.0113172531 4.1532449722 346 13.8000000000 0.0095273424 0.0050408610 0.0104474202 0.0097261952 0.0050130000 0.0004630000 0.0026970000 0.0000000000 0.0000040000 0.0012880000 13846469 96830484 509673472 3.8497087955 4.0113630295 4.1504535675 347 13.8400000000 0.0097778263 0.0050545122 0.0104474202 0.0097121727 0.0056240000 0.0006400000 0.0029010000 0.0000170000 0.0000140000 0.0015690000 13849245 96830484 509673472 3.8486835957 4.0113883018 4.1475858688 348 13.8800000000 0.0097379480 0.0050679703 0.0104474202 0.0096986583 0.0101760000 0.0006400000 0.0053870000 0.0000010000 0.0000170000 0.0018920000 13852021 96830484 509673472 3.8476049900 4.0109543800 4.1449337006 349 13.9200000000 0.0096407710 0.0050810729 0.0104474202 0.0096864687 0.0080910000 0.0005670000 0.0037370000 0.0000080000 0.0000070000 0.0026330000 13854797 96830484 509673472 3.8467438221 4.0104751587 4.1421422958 350 13.9600000000 0.0095934188 0.0050939653 0.0104474202 0.0096764042 0.0057720000 0.0005070000 0.0031680000 0.0000010000 0.0000050000 0.0013350000 13857573 96830484 509673472 3.8459079266 4.0100984573 4.1389145851 351 14.0000000000 0.0096797952 0.0051070304 0.0104474202 0.0096658261 0.0068140000 0.0005550000 0.0033120000 0.0000070000 0.0000080000 0.0017790000 13860349 96830484 509673472 3.8451220989 4.0096249580 4.1361126900 352 14.0400000000 0.0098839458 0.0051206011 0.0104474202 0.0096592534 0.0068860000 0.0004980000 0.0042970000 0.0000010000 0.0000050000 0.0013150000 13863125 96830484 509673472 3.8443298340 4.0094990730 4.1330313683 353 14.0800000000 0.0097415820 0.0051336917 0.0104474202 0.0096509986 0.0070830000 0.0004690000 0.0035420000 0.0000050000 0.0000040000 0.0023770000 13865901 96830484 509673472 3.8436541557 4.0090870857 4.1302514076 354 14.1200000000 0.0096170092 0.0051463565 0.0104474202 0.0096398384 0.0076550000 0.0006410000 0.0030620000 0.0000020000 0.0000150000 0.0019020000 13868677 96830484 509673472 3.8425571918 4.0092291832 4.1272974014 355 14.1600000000 0.0098403292 0.0051595789 0.0104474202 0.0096263749 0.0089850000 0.0006370000 0.0043590000 0.0000150000 0.0000130000 0.0022280000 13871453 96830484 509673472 3.8417165279 4.0093131065 4.1248993874 356 14.2000000000 0.0097859325 0.0051725743 0.0104474202 0.0096129211 0.0053300000 0.0005260000 0.0023840000 0.0000010000 0.0000070000 0.0014420000 13874229 96830484 509673472 3.8408548832 4.0091080666 4.1221556664 357 14.2400000000 0.0097617675 0.0051854292 0.0104474202 0.0095996267 0.0071100000 0.0005490000 0.0032860000 0.0000060000 0.0000050000 0.0024380000 13877005 96830484 509673472 3.8401794434 4.0093507767 4.1195425987 358 14.2800000000 0.0100665456 0.0051990636 0.0104474202 0.0095901635 0.0085970000 0.0006570000 0.0043560000 0.0000020000 0.0000150000 0.0019110000 13879781 96830484 509673472 3.8394939899 4.0097818375 4.1175274849 359 14.3200000000 0.0100231422 0.0052125011 0.0104474202 0.0095833346 0.0064020000 0.0005640000 0.0028600000 0.0000100000 0.0000100000 0.0017560000 13882557 96830484 509673472 3.8390531540 4.0087752342 4.1149291992 360 14.3600000000 0.0100120828 0.0052258333 0.0104474202 0.0095710775 0.0054690000 0.0004960000 0.0027540000 0.0000000000 0.0000060000 0.0013860000 13885333 96830484 509673472 3.8388788700 4.0077958107 4.1126308441 361 14.4000000000 0.0099549424 0.0052389333 0.0104474202 0.0095678500 0.0088870000 0.0006410000 0.0034630000 0.0000150000 0.0000140000 0.0031430000 13888109 96830484 509673472 3.8381905556 4.0076079369 4.1103601456 362 14.4400000000 0.0100249732 0.0052521544 0.0104474202 0.0095569323 0.0056630000 0.0005180000 0.0028140000 0.0000010000 0.0000060000 0.0013630000 13890885 96830484 509673472 3.8377921581 4.0076842308 4.1075530052 363 14.4800000000 0.0098744947 0.0052648882 0.0104474202 0.0095441891 0.0090480000 0.0006440000 0.0037670000 0.0000140000 0.0000140000 0.0022030000 13893661 96830484 509673472 3.8373107910 4.0067877769 4.1054725647 364 14.5200000000 0.0100154784 0.0052779392 0.0104474202 0.0095359949 0.0073960000 0.0006430000 0.0035090000 0.0000020000 0.0000170000 0.0016160000 13896437 96830484 509673472 3.8369872570 4.0065250397 4.1030850410 365 14.5600000000 0.0102746384 0.0052916288 0.0104474202 0.0095255674 0.0068310000 0.0005190000 0.0028110000 0.0000070000 0.0000060000 0.0025390000 13899213 96830484 509673472 3.8363130093 4.0072937012 4.1005854607 366 14.6000000000 0.0101173930 0.0053048140 0.0104474202 0.0095164230 0.0070050000 0.0005540000 0.0037630000 0.0000010000 0.0000070000 0.0014630000 13901989 96830484 509673472 3.8364033699 4.0072488785 4.0982470512 367 14.6400000000 0.0100713260 0.0053178017 0.0104474202 0.0095076865 0.0079600000 0.0006440000 0.0037690000 0.0000100000 0.0000090000 0.0018980000 13904765 96830484 509673472 3.8361520767 4.0059413910 4.0958480835 368 14.6800000000 0.0100412993 0.0053306373 0.0104474202 0.0094983424 0.0068020000 0.0005210000 0.0040650000 0.0000010000 0.0000060000 0.0013680000 13907541 96830484 509673472 3.8357553482 4.0053396225 4.0934815407 369 14.7200000000 0.0101198060 0.0053436161 0.0104474202 0.0094891878 0.0079510000 0.0005540000 0.0033080000 0.0000100000 0.0000090000 0.0028550000 13910317 96830484 509673472 3.8350136280 4.0053715706 4.0910949707 370 14.7600000000 0.0100676073 0.0053563837 0.0104474202 0.0094770955 0.0054350000 0.0004960000 0.0027760000 0.0000010000 0.0000070000 0.0013380000 13913093 96830484 509673472 3.8347573280 4.0056414604 4.0889725685 371 14.8000000000 0.0099909538 0.0053688758 0.0104474202 0.0094646189 0.0104130000 0.0006420000 0.0056640000 0.0000160000 0.0000130000 0.0022200000 13915869 96830484 509673472 3.8339991570 4.0061359406 4.0862874985 372 14.8400000000 0.0102765439 0.0053820684 0.0104474202 0.0094579216 0.0060380000 0.0005230000 0.0031000000 0.0000010000 0.0000090000 0.0014130000 13918645 96830484 509673472 3.8334290981 4.0063662529 4.0833525658 373 14.8800000000 0.0101557989 0.0053948666 0.0104474202 0.0094513236 0.0081830000 0.0005550000 0.0036080000 0.0000100000 0.0000090000 0.0027670000 13921421 96830484 509673472 3.8332793713 4.0066709518 4.0806279182 374 14.9200000000 0.0102274837 0.0054077881 0.0104474202 0.0094558503 0.0054540000 0.0004980000 0.0027750000 0.0000010000 0.0000060000 0.0013390000 13924197 96830484 509673472 3.8325200081 4.0071163177 4.0783066750 375 14.9600000000 0.0103514753 0.0054209712 0.0104474202 0.0094691259 0.0055250000 0.0004720000 0.0027000000 0.0000050000 0.0000040000 0.0016290000 13926973 96830484 509673472 3.8315975666 4.0060329437 4.0762963295 376 15.0000000000 0.0102842264 0.0054339054 0.0104474202 0.0094597079 0.0085710000 0.0006430000 0.0034900000 0.0000020000 0.0000160000 0.0019490000 13929749 96830484 509673472 3.8314485550 4.0054464340 4.0740036964 377 15.0400000000 0.0102019096 0.0054465526 0.0104474202 0.0094476353 0.0088630000 0.0006300000 0.0035100000 0.0000150000 0.0000130000 0.0030370000 13932525 96830484 509673472 3.8301610947 4.0064058304 4.0715556145 378 15.0800000000 0.0103157852 0.0054594342 0.0104474202 0.0094574613 0.0060010000 0.0005280000 0.0030770000 0.0000010000 0.0000060000 0.0013920000 13935301 96830484 509673472 3.8299798965 4.0060577393 4.0687961578 379 15.1200000000 0.0107103987 0.0054732890 0.0107103987 0.0094530737 0.0052870000 0.0004820000 0.0023080000 0.0000050000 0.0000050000 0.0016530000 13938077 96830484 509673472 3.8297657967 4.0054345131 4.0663967133 380 15.1600000000 0.0104647549 0.0054864244 0.0107103987 0.0094406318 0.0087800000 0.0006370000 0.0041860000 0.0000020000 0.0000140000 0.0020110000 13940853 96830484 509673472 3.8290121555 4.0053834915 4.0635409355 381 15.2000000000 0.0107447533 0.0055002258 0.0107447533 0.0094294118 0.0072850000 0.0005170000 0.0032290000 0.0000060000 0.0000060000 0.0025190000 13943629 96830484 509673472 3.8280179501 4.0056557655 4.0613441467 382 15.2400000000 0.0108239213 0.0055141622 0.0108239213 0.0094182413 0.0056730000 0.0004820000 0.0031360000 0.0000010000 0.0000050000 0.0013290000 13946405 96830484 509673472 3.8276858330 4.0053496361 4.0584139824 383 15.2800000000 0.0105342939 0.0055272696 0.0108239213 0.0094060459 0.0086260000 0.0006280000 0.0034700000 0.0000160000 0.0000140000 0.0022190000 13949181 96830484 509673472 3.8268313408 4.0052032471 4.0562829971 384 15.3200000000 0.0106521221 0.0055406156 0.0108239213 0.0093945050 0.0070820000 0.0005550000 0.0037480000 0.0000010000 0.0000070000 0.0015080000 13951957 96830484 509673472 3.8255190849 4.0055809021 4.0536108017 385 15.3600000000 0.0105325179 0.0055535815 0.0108239213 0.0093848427 0.0072440000 0.0004960000 0.0035570000 0.0000050000 0.0000050000 0.0024550000 13954733 96830484 509673472 3.8243625164 4.0058140755 4.0513586998 386 15.4000000000 0.0106273526 0.0055667260 0.0108239213 0.0093742307 0.0067640000 0.0005560000 0.0028730000 0.0000020000 0.0000110000 0.0016320000 13957509 96830484 509673472 3.8235466480 4.0060243607 4.0484142303 387 15.4400000000 0.0107632596 0.0055801538 0.0108239213 0.0093624398 0.0075950000 0.0005270000 0.0043230000 0.0000070000 0.0000050000 0.0016940000 13960285 96830484 509673472 3.8223350048 4.0066833496 4.0456767082 388 15.4800000000 0.0106763197 0.0055932882 0.0108239213 0.0093545309 0.0076210000 0.0004810000 0.0051400000 0.0000010000 0.0000050000 0.0013440000 13963061 96830484 509673472 3.8209538460 4.0073328018 4.0437054634 389 15.5200000000 0.0105691710 0.0056060797 0.0108239213 0.0093513964 0.0060250000 0.0004550000 0.0026210000 0.0000030000 0.0000030000 0.0023940000 13965837 96830484 509673472 3.8200526237 4.0076217651 4.0409669876 390 15.5600000000 0.0107669625 0.0056193127 0.0108239213 0.0093448996 0.0073450000 0.0004540000 0.0050470000 0.0000010000 0.0000030000 0.0012910000 13968613 96830484 509673472 3.8183424473 4.0081181526 4.0386934280 391 15.6000000000 0.0104424097 0.0056316480 0.0108239213 0.0093358108 0.0077080000 0.0006380000 0.0030190000 0.0000140000 0.0000150000 0.0021820000 13971389 96830484 509673472 3.8169565201 4.0088763237 4.0361709595 392 15.6400000000 0.0105170915 0.0056441109 0.0108239213 0.0093363128 0.0066510000 0.0005750000 0.0032930000 0.0000010000 0.0000070000 0.0014800000 13974165 96830484 509673472 3.8154597282 4.0095338821 4.0337634087 393 15.6800000000 0.0106019760 0.0056567263 0.0108239213 0.0093341599 0.0066340000 0.0004970000 0.0027500000 0.0000070000 0.0000050000 0.0025100000 13976941 96830484 509673472 3.8147282600 4.0099372864 4.0312986374 394 15.7200000000 0.0105506573 0.0056691474 0.0108239213 0.0093295273 0.0079210000 0.0006580000 0.0033400000 0.0000020000 0.0000160000 0.0019170000 13979717 96830484 509673472 3.8134610653 4.0104179382 4.0289583206 395 15.7600000000 0.0105706705 0.0056815564 0.0108239213 0.0093227807 0.0081290000 0.0005190000 0.0048640000 0.0000060000 0.0000060000 0.0016860000 13982493 96830484 509673472 3.8112864494 4.0113058090 4.0262889862 396 15.8000000000 0.0105378637 0.0056938198 0.0108239213 0.0093184119 0.0077580000 0.0004810000 0.0052000000 0.0000010000 0.0000040000 0.0013180000 13985269 96830484 509673472 3.8105983734 4.0122041702 4.0234060287 397 15.8400000000 0.0105646746 0.0057060889 0.0108239213 0.0093227475 0.0061310000 0.0004630000 0.0026780000 0.0000030000 0.0000030000 0.0023820000 13988045 96830484 509673472 3.8090696335 4.0128860474 4.0213937759 398 15.8800000000 0.0106451390 0.0057184986 0.0108239213 0.0093320679 0.0056770000 0.0004450000 0.0034130000 0.0000000000 0.0000040000 0.0012500000 13990821 96830484 509673472 3.8079061508 4.0124902725 4.0187754631 399 15.9200000000 0.0105645293 0.0057306440 0.0108239213 0.0093246640 0.0063160000 0.0004420000 0.0037960000 0.0000040000 0.0000030000 0.0015210000 13993597 96830484 509673472 3.8067038059 4.0122995377 4.0166015625 400 15.9600000000 0.0105807679 0.0057427693 0.0108239213 0.0093139225 0.0081570000 0.0006260000 0.0029810000 0.0000020000 0.0000140000 0.0018910000 13996373 96830484 509673472 3.8052196503 4.0135502815 4.0140614510 401 16.0000000000 0.0104238046 0.0057544427 0.0108239213 0.0093187287 0.0063420000 0.0006300000 0.0028340000 0.0000030000 0.0000030000 0.0023040000 13999149 96830484 509673472 3.8045058250 4.0135726929 4.0117268562 402 16.0400000000 0.0104135107 0.0057660325 0.0108239213 0.0093150385 0.0072320000 0.0004430000 0.0049590000 0.0000000000 0.0000030000 0.0012560000 14001925 96830484 509673472 3.8030312061 4.0139126778 4.0095129013 403 16.0800000000 0.0103364643 0.0057773735 0.0108239213 0.0093169767 0.0086680000 0.0006290000 0.0033780000 0.0000150000 0.0000140000 0.0021660000 14004701 96830484 509673472 3.8017399311 4.0145578384 4.0072379112 404 16.1200000000 0.0104827331 0.0057890204 0.0108239213 0.0093326203 0.0057510000 0.0005140000 0.0027240000 0.0000010000 0.0000080000 0.0014150000 14007477 96830484 509673472 3.8016405106 4.0152492523 4.0046916008 405 16.1600000000 0.0105067389 0.0058006691 0.0108239213 0.0093535704 0.0089820000 0.0005480000 0.0044080000 0.0000100000 0.0000100000 0.0026580000 14010253 96830484 509673472 3.8002867699 4.0149278641 4.0029115677 406 16.2000000000 0.0104936212 0.0058122281 0.0108239213 0.0093486394 0.0065970000 0.0004870000 0.0038740000 0.0000010000 0.0000050000 0.0013370000 14013029 96830484 509673472 3.7998125553 4.0164427757 4.0004982948 407 16.2400000000 0.0105744274 0.0058239288 0.0108239213 0.0093643561 0.0097580000 0.0006330000 0.0054230000 0.0000110000 0.0000090000 0.0018870000 14015805 96830484 509673472 3.7989048958 4.0166563988 3.9987077713 408 16.2800000000 0.0105224354 0.0058354448 0.0108239213 0.0093693121 0.0078080000 0.0005160000 0.0050780000 0.0000010000 0.0000070000 0.0013150000 14018581 96830484 509673472 3.7983705997 4.0167555809 3.9965457916 409 16.3200000000 0.0106218942 0.0058471476 0.0108239213 0.0093625101 0.0080410000 0.0005420000 0.0035680000 0.0000080000 0.0000060000 0.0025700000 14021357 96830484 509673472 3.7973594666 4.0168824196 3.9945185184 410 16.3600000000 0.0105141755 0.0058585306 0.0108239213 0.0093530363 0.0067800000 0.0004830000 0.0042360000 0.0000010000 0.0000050000 0.0012870000 14024133 96830484 509673472 3.7969396114 4.0179877281 3.9923079014 411 16.3999999990 0.0104927551 0.0058698061 0.0108239213 0.0093599475 0.0051880000 0.0004520000 0.0026060000 0.0000030000 0.0000030000 0.0015240000 14026909 96830484 509673472 3.7966859341 4.0184803009 3.9902884960 412 16.4400000000 0.0104034441 0.0058808100 0.0108239213 0.0093654743 0.0072240000 0.0004460000 0.0049470000 0.0000000000 0.0000030000 0.0012520000 14029685 96830484 509673472 3.7965009212 4.0190834999 3.9880731106 413 16.4800000000 0.0102869123 0.0058914786 0.0108239213 0.0093640399 0.0058860000 0.0004450000 0.0025870000 0.0000030000 0.0000030000 0.0022780000 14032461 96830484 509673472 3.7956826687 4.0190916061 3.9860396385 414 16.5200000000 0.0104455827 0.0059024788 0.0108239213 0.0093562317 0.0072560000 0.0004430000 0.0049870000 0.0000000000 0.0000030000 0.0012350000 14035237 96830484 509673472 3.7955946922 4.0194811821 3.9838807583 415 16.5599999990 0.0105869267 0.0059137667 0.0108239213 0.0093454482 0.0098200000 0.0006280000 0.0046600000 0.0000150000 0.0000130000 0.0021500000 14038013 96830484 509673472 3.7951350212 4.0205416679 3.9814100266 416 16.6000000000 0.0104132304 0.0059245827 0.0108239213 0.0093389784 0.0072250000 0.0005050000 0.0041500000 0.0000010000 0.0000070000 0.0013420000 14040789 96830484 509673472 3.7948203087 4.0205159187 3.9792423248 417 16.6400000000 0.0104516977 0.0059354391 0.0108239213 0.0093333948 0.0083330000 0.0006050000 0.0040440000 0.0000070000 0.0000070000 0.0025240000 14043565 96830484 509673472 3.7939567566 4.0211887360 3.9768702984 418 16.6800000000 0.0105601773 0.0059465030 0.0108239213 0.0093327386 0.0067990000 0.0004700000 0.0042670000 0.0000000000 0.0000040000 0.0012690000 14046341 96830484 509673472 3.7930469513 4.0223178864 3.9744384289 419 16.7199999990 0.0105017889 0.0059573748 0.0108239213 0.0093448666 0.0052870000 0.0004510000 0.0026130000 0.0000040000 0.0000040000 0.0015280000 14049117 96830484 509673472 3.7924523354 4.0235137939 3.9717068672 420 16.7600000000 0.0107592065 0.0059688078 0.0108239213 0.0093671070 0.0072850000 0.0004460000 0.0049760000 0.0000000000 0.0000040000 0.0012470000 14051893 96830484 509673472 3.7927789688 4.0236864090 3.9692327976 421 16.8000000000 0.0108466940 0.0059803942 0.0108466940 0.0093635207 0.0063120000 0.0004430000 0.0029880000 0.0000030000 0.0000030000 0.0022870000 14054669 96830484 509673472 3.7919661999 4.0244011879 3.9664556980 422 16.8400000000 0.0109916683 0.0059922693 0.0109916683 0.0093584759 0.0085870000 0.0006310000 0.0034120000 0.0000020000 0.0000150000 0.0018120000 14057445 96830484 509673472 3.7925968170 4.0253410339 3.9636211395 423 16.8799999990 0.0110241687 0.0060041650 0.0110241687 0.0093534628 0.0067030000 0.0005380000 0.0031120000 0.0000070000 0.0000070000 0.0016200000 14060221 96830484 509673472 3.7917568684 4.0259833336 3.9610328674 424 16.9200000000 0.0108546875 0.0060156049 0.0110241687 0.0093482723 0.0072590000 0.0004690000 0.0047590000 0.0000010000 0.0000050000 0.0012130000 14062997 96830484 509673472 3.7916917801 4.0269055367 3.9579746723 425 16.9600000000 0.0108538587 0.0060269890 0.0110241687 0.0093650428 0.0088400000 0.0005280000 0.0043250000 0.0000100000 0.0000090000 0.0025600000 14065773 96830484 509673472 3.7916715145 4.0271468163 3.9549310207 426 17.0000000000 0.0110608116 0.0060388055 0.0110608116 0.0093638717 0.0068250000 0.0004740000 0.0041750000 0.0000010000 0.0000050000 0.0012230000 14068549 96830484 509673472 3.7919905186 4.0274457932 3.9520628452 427 17.0400000000 0.0110493675 0.0060505399 0.0110608116 0.0093537503 0.0056100000 0.0004460000 0.0029500000 0.0000050000 0.0000040000 0.0014750000 14071325 96830484 509673472 3.7918825150 4.0270867348 3.9492180347 428 17.0800000000 0.0114032310 0.0060630461 0.0114032310 0.0093429598 0.0083780000 0.0006290000 0.0037280000 0.0000020000 0.0000160000 0.0017950000 14074101 96830484 509673472 3.7935175896 4.0281252861 3.9458587170 429 17.1200000000 0.0112453708 0.0060751262 0.0114032310 0.0093332494 0.0073890000 0.0005010000 0.0034420000 0.0000080000 0.0000070000 0.0022830000 14076877 96830484 509673472 3.7939219475 4.0281052589 3.9426770210 430 17.1600000000 0.0112889009 0.0060872512 0.0114032310 0.0093226194 0.0062580000 0.0004550000 0.0037760000 0.0000010000 0.0000050000 0.0012200000 14079653 96830484 509673472 3.7936468124 4.0284471512 3.9397027493 431 17.2000000000 0.0112118619 0.0060991413 0.0114032310 0.0093119227 0.0081280000 0.0006140000 0.0029120000 0.0000150000 0.0000130000 0.0020360000 14082429 96830484 509673472 3.7937331200 4.0292019844 3.9361877441 432 17.2400000000 0.0112704961 0.0061111120 0.0114032310 0.0093062643 0.0082820000 0.0005260000 0.0050000000 0.0000010000 0.0000080000 0.0013460000 14085205 96830484 509673472 3.7935836315 4.0296587944 3.9332456589 433 17.2800000000 0.0112356972 0.0061229471 0.0114032310 0.0093039001 0.0084340000 0.0004700000 0.0049430000 0.0000060000 0.0000050000 0.0022000000 14087981 96830484 509673472 3.7933280468 4.0299272537 3.9298722744 434 17.3200000000 0.0112070153 0.0061346615 0.0114032310 0.0092969235 0.0047890000 0.0004370000 0.0025540000 0.0000010000 0.0000040000 0.0011590000 14090757 96830484 509673472 3.7939302921 4.0303177834 3.9268817902 435 17.3600000000 0.0111717703 0.0061462411 0.0114032310 0.0092873998 0.0065970000 0.0004320000 0.0040990000 0.0000030000 0.0000030000 0.0014330000 14093533 96830484 509673472 3.7940161228 4.0317373276 3.9234054089 436 17.4000000000 0.0112502044 0.0061579474 0.0114032310 0.0092955337 0.0070890000 0.0004300000 0.0048730000 0.0000000000 0.0000030000 0.0011610000 14096309 96830484 509673472 3.7950174809 4.0322523117 3.9202132225 437 17.4400000000 0.0112905325 0.0061696924 0.0114032310 0.0093115736 0.0061120000 0.0004290000 0.0029110000 0.0000030000 0.0000040000 0.0021420000 14099085 96830484 509673472 3.7956748009 4.0325245857 3.9174642563 438 17.4800000000 0.0110333487 0.0061807967 0.0114032310 0.0093091686 0.0054930000 0.0004280000 0.0033020000 0.0000000000 0.0000030000 0.0011420000 14101861 96830484 509673472 3.7966423035 4.0325655937 3.9141688347 439 17.5200000000 0.0110004973 0.0061917755 0.0114032310 0.0093077864 0.0096690000 0.0006150000 0.0041150000 0.0000150000 0.0000140000 0.0020120000 14104637 96830484 509673472 3.7989289761 4.0329871178 3.9110715389 440 17.5600000000 0.0110841170 0.0062028945 0.0114032310 0.0093120463 0.0085250000 0.0005250000 0.0051380000 0.0000010000 0.0000100000 0.0013910000 14107413 96830484 509673472 3.7996413708 4.0333232880 3.9083964825 441 17.6000000000 0.0110358587 0.0062138536 0.0114032310 0.0093163328 0.0070650000 0.0004780000 0.0033990000 0.0000070000 0.0000050000 0.0021850000 14110189 96830484 509673472 3.8001880646 4.0338153839 3.9057345390 442 17.6400000000 0.0110015869 0.0062246855 0.0114032310 0.0093274202 0.0056730000 0.0004440000 0.0033370000 0.0000000000 0.0000040000 0.0011530000 14112965 96830484 509673472 3.8002588749 4.0334210396 3.9030015469 443 17.6800000000 0.0110331671 0.0062355399 0.0114032310 0.0093300040 0.0095560000 0.0006160000 0.0045560000 0.0000160000 0.0000140000 0.0019830000 14115741 96830484 509673472 3.8004064560 4.0328707695 3.9006617069 444 17.7200000000 0.0111819236 0.0062466804 0.0114032310 0.0093229649 0.0079420000 0.0005000000 0.0050100000 0.0000010000 0.0000070000 0.0012330000 14118517 96830484 509673472 3.8001651764 4.0329122543 3.8980822563 445 17.7600000000 0.0108633814 0.0062570550 0.0114032310 0.0093124809 0.0064240000 0.0004530000 0.0029730000 0.0000040000 0.0000040000 0.0021440000 14121293 96830484 509673472 3.8010528088 4.0335407257 3.8952529430 446 17.8000000000 0.0111238463 0.0062679671 0.0114032310 0.0093029180 0.0085320000 0.0005250000 0.0051360000 0.0000020000 0.0000080000 0.0013280000 14124069 96830484 509673472 3.8002412319 4.0338406563 3.8924958706 447 17.8400000000 0.0109271370 0.0062783903 0.0114032310 0.0092962538 0.0062660000 0.0005310000 0.0031480000 0.0000050000 0.0000050000 0.0014560000 14126845 96830484 509673472 3.8008542061 4.0342998505 3.8900356293 448 17.8800000000 0.0112926196 0.0062895828 0.0114032310 0.0092873291 0.0085450000 0.0005300000 0.0050030000 0.0000010000 0.0000100000 0.0014690000 14129621 96830484 509673472 3.8004126549 4.0345911980 3.8875420094 449 17.9200000000 0.0111878356 0.0063004920 0.0114032310 0.0092802559 0.0085990000 0.0004690000 0.0049490000 0.0000050000 0.0000040000 0.0021890000 14132397 96830484 509673472 3.8014464378 4.0335226059 3.8853080273 450 17.9600000000 0.0112280315 0.0063114421 0.0114032310 0.0092702136 0.0053000000 0.0004450000 0.0029480000 0.0000010000 0.0000040000 0.0011630000 14135173 96830484 509673472 3.8011410236 4.0346112251 3.8801832199 451 18.0000000000 0.0112546748 0.0063224027 0.0114032310 0.0092769177 0.0098850000 0.0006170000 0.0053770000 0.0000150000 0.0000140000 0.0019080000 14137949 96830484 509673472 3.8014318943 4.0343732834 3.8776869774 452 18.0400000000 0.0111716539 0.0063331311 0.0114032310 0.0092842595 0.0079310000 0.0004900000 0.0050160000 0.0000010000 0.0000060000 0.0012310000 14140725 96830484 509673472 3.8012130260 4.0330657959 3.8755602837 453 18.0800000000 0.0113337543 0.0063441701 0.0114032310 0.0092890762 0.0082180000 0.0004540000 0.0048810000 0.0000040000 0.0000040000 0.0021260000 14143501 96830484 509673472 3.8005392551 4.0325193405 3.8732702732 454 18.1200000000 0.0112541802 0.0063549851 0.0114032310 0.0092838685 0.0056640000 0.0005280000 0.0023200000 0.0000010000 0.0000120000 0.0013120000 14146277 96830484 509673472 3.8004131317 4.0330557823 3.8704111576 455 18.1600000000 0.0110849226 0.0063653805 0.0114032310 0.0092738149 0.0076460000 0.0006140000 0.0033170000 0.0000150000 0.0000130000 0.0016940000 14149053 96830484 509673472 3.8001067638 4.0341467857 3.8674185276 456 18.2000000000 0.0114167091 0.0063764580 0.0114167091 0.0092643048 0.0077440000 0.0004940000 0.0050110000 0.0000000000 0.0000070000 0.0012300000 14151829 96830484 509673472 3.7989480495 4.0353770256 3.8646566868 457 18.2400000000 0.0112693328 0.0063871645 0.0114167091 0.0092673540 0.0082590000 0.0004460000 0.0049070000 0.0000040000 0.0000030000 0.0021510000 14154605 96830484 509673472 3.7989599705 4.0350055695 3.8622100353 458 18.2800000000 0.0114131756 0.0063981383 0.0114167091 0.0092639379 0.0093980000 0.0006120000 0.0053240000 0.0000010000 0.0000110000 0.0014610000 14157381 96830484 509673472 3.7977905273 4.0358605385 3.8593840599 459 18.3200000000 0.0112353098 0.0064086768 0.0114167091 0.0092808294 0.0058380000 0.0004990000 0.0026340000 0.0000060000 0.0000050000 0.0014910000 14160157 96830484 509673472 3.7972714901 4.0358829498 3.8568210602 460 18.3600000000 0.0112815406 0.0064192700 0.0114167091 0.0092864113 0.0087940000 0.0006360000 0.0033340000 0.0000020000 0.0000160000 0.0017400000 14162933 96830484 509673472 3.7968440056 4.0360541344 3.8538646698 461 18.4000000000 0.0112873102 0.0064298297 0.0114167091 0.0092833646 0.0099060000 0.0006180000 0.0032960000 0.0000160000 0.0000160000 0.0028970000 14165709 96830484 509673472 3.7960104942 4.0363531113 3.8511016369 462 18.4400000000 0.0112911193 0.0064403520 0.0114167091 0.0093053858 0.0103280000 0.0006610000 0.0052400000 0.0000010000 0.0000160000 0.0017420000 14168485 96830484 509673472 3.7957017422 4.0355277061 3.8486104012 463 18.4800000000 0.0112840412 0.0064508136 0.0114167091 0.0093110808 0.0078710000 0.0004980000 0.0046300000 0.0000060000 0.0000060000 0.0014950000 14171261 96830484 509673472 3.7951724529 4.0356884003 3.8456449509 464 18.5200000000 0.0113165220 0.0064613000 0.0114167091 0.0093118533 0.0054820000 0.0004620000 0.0029760000 0.0000010000 0.0000050000 0.0011520000 14174037 96830484 509673472 3.7942559719 4.0350747108 3.8431067467 465 18.5600000000 0.0112905763 0.0064716855 0.0114167091 0.0093092063 0.0066650000 0.0004410000 0.0033350000 0.0000040000 0.0000030000 0.0020950000 14176813 96830484 509673472 3.7935965061 4.0355019569 3.8400406837 466 18.6000000000 0.0112280725 0.0064818924 0.0114167091 0.0093000787 0.0061010000 0.0004400000 0.0037360000 0.0000000000 0.0000040000 0.0011340000 14179589 96830484 509673472 3.7923204899 4.0367622375 3.8367466927 467 18.6400000000 0.0112567032 0.0064921168 0.0114167091 0.0092901999 0.0052180000 0.0004400000 0.0025740000 0.0000040000 0.0000040000 0.0014120000 14182365 96830484 509673472 3.7909588814 4.0379834175 3.8336243629 468 18.6800000000 0.0113918427 0.0065025863 0.0114167091 0.0092809814 0.0073220000 0.0004450000 0.0049230000 0.0000010000 0.0000040000 0.0011430000 14185141 96830484 509673472 3.7893283367 4.0392265320 3.8304274082 469 18.7200000000 0.0113319922 0.0065128835 0.0114167091 0.0092808198 0.0082600000 0.0004380000 0.0049170000 0.0000040000 0.0000040000 0.0021010000 14187917 96830484 509673472 3.7888398170 4.0396137238 3.8275771141 470 18.7600000000 0.0113922432 0.0065232652 0.0114167091 0.0092713114 0.0103810000 0.0006170000 0.0054350000 0.0000020000 0.0000160000 0.0017280000 14190693 96830484 509673472 3.7867882252 4.0423507690 3.8241505623 471 18.8000000000 0.0113717709 0.0065335592 0.0114167091 0.0093031080 0.0067420000 0.0005010000 0.0034670000 0.0000080000 0.0000070000 0.0015050000 14193469 96830484 509673472 3.7869107723 4.0421009064 3.8215086460 472 18.8400000000 0.0113564907 0.0065437773 0.0114167091 0.0093921966 0.0054950000 0.0004550000 0.0029970000 0.0000010000 0.0000040000 0.0011410000 14196245 96830484 509673472 3.7860708237 4.0432591438 3.8184726238 473 18.8800000000 0.0113210864 0.0065538773 0.0114167091 0.0094585583 0.0062640000 0.0004390000 0.0029440000 0.0000040000 0.0000030000 0.0020750000 14199021 96830484 509673472 3.7850935459 4.0428543091 3.8154635429 474 18.9200000000 0.0113662742 0.0065640301 0.0114167091 0.0094584573 0.0053540000 0.0004400000 0.0029760000 0.0000010000 0.0000040000 0.0011320000 14201797 96830484 509673472 3.7833166122 4.0434050560 3.8126966953 475 18.9600000000 0.0113498727 0.0065741055 0.0114167091 0.0094540835 0.0095420000 0.0006320000 0.0037700000 0.0000150000 0.0000140000 0.0019580000 14204573 96830484 509673472 3.7821431160 4.0447597504 3.8099062443 476 19.0000000000 0.0114277825 0.0065843023 0.0114277825 0.0094697553 0.0076030000 0.0006040000 0.0033360000 0.0000020000 0.0000170000 0.0015270000 14207349 96830484 509673472 3.7807848454 4.0464782715 3.8070116043 477 19.0400000000 0.0113579761 0.0065943100 0.0114277825 0.0094684535 0.0070200000 0.0004930000 0.0030880000 0.0000060000 0.0000060000 0.0021520000 14210125 96830484 509673472 3.7800245285 4.0483865738 3.8039581776 478 19.0800000000 0.0113694193 0.0066042998 0.0114277825 0.0094598443 0.0065950000 0.0005480000 0.0031820000 0.0000020000 0.0000100000 0.0012720000 14212901 96830484 509673472 3.7789647579 4.0505528450 3.8014132977 479 19.1200000000 0.0112961028 0.0066140948 0.0114277825 0.0094583193 0.0058640000 0.0004700000 0.0026550000 0.0000070000 0.0000050000 0.0014490000 14215677 96830484 509673472 3.7775976658 4.0514612198 3.7987964153 480 19.1600000000 0.0114520602 0.0066241739 0.0114520602 0.0094603182 0.0077220000 0.0004560000 0.0050190000 0.0000000000 0.0000050000 0.0011650000 14218453 96830484 509673472 3.7764718533 4.0525135994 3.7962543964 481 19.2000000000 0.0113594029 0.0066340184 0.0114520602 0.0094572215 0.0066490000 0.0004560000 0.0030210000 0.0000070000 0.0000050000 0.0020800000 14221229 96830484 509673472 3.7755403519 4.0531821251 3.7937481403 482 19.2400000000 0.0114004416 0.0066439073 0.0114520602 0.0094547621 0.0055060000 0.0004450000 0.0030070000 0.0000010000 0.0000040000 0.0011230000 14224005 96830484 509673472 3.7747652531 4.0543131828 3.7911942005 483 19.2800000000 0.0114314705 0.0066538194 0.0114520602 0.0094758938 0.0053840000 0.0004460000 0.0026030000 0.0000040000 0.0000050000 0.0014000000 14226781 96830484 509673472 3.7737255096 4.0535998344 3.7891652584 484 19.3200000000 0.0114457291 0.0066637201 0.0114520602 0.0094734446 0.0074990000 0.0004460000 0.0050020000 0.0000010000 0.0000050000 0.0011220000 14229557 96830484 509673472 3.7733042240 4.0540485382 3.7870748043 485 19.3600000000 0.0114103509 0.0066735069 0.0114520602 0.0094653152 0.0064630000 0.0004430000 0.0030200000 0.0000040000 0.0000040000 0.0020650000 14232333 96830484 509673472 3.7730364799 4.0542564392 3.7853696346 486 19.4000000000 0.0114102941 0.0066832534 0.0114520602 0.0094567024 0.0055190000 0.0004430000 0.0030300000 0.0000010000 0.0000050000 0.0011140000 14235109 96830484 509673472 3.7729227543 4.0549354553 3.7832546234 487 19.4400000000 0.0115061896 0.0066931568 0.0115061896 0.0094502718 0.0112920000 0.0006120000 0.0054880000 0.0000160000 0.0000140000 0.0019190000 14237885 96830484 509673472 3.7723493576 4.0560808182 3.7812798023 488 19.4800000000 0.0115594082 0.0067031286 0.0115594082 0.0094465261 0.0064370000 0.0005260000 0.0027860000 0.0000010000 0.0000100000 0.0013730000 14240661 96830484 509673472 3.7717351913 4.0568161011 3.7791426182 489 19.5200000000 0.0114762178 0.0067128895 0.0115594082 0.0094511344 0.0070880000 0.0004720000 0.0034540000 0.0000060000 0.0000050000 0.0020610000 14243437 96830484 509673472 3.7720687389 4.0564374924 3.7772397995 490 19.5600000000 0.0114758713 0.0067226099 0.0115594082 0.0094460737 0.0051080000 0.0004560000 0.0026140000 0.0000000000 0.0000040000 0.0010960000 14246213 96830484 509673472 3.7719378471 4.0571718216 3.7752385139 491 19.6000000000 0.0115875034 0.0067325180 0.0115875034 0.0094379370 0.0089000000 0.0006000000 0.0037930000 0.0000150000 0.0000130000 0.0018850000 14248989 96830484 509673472 3.7706997395 4.0575218201 3.7733063698 492 19.6400000000 0.0116116134 0.0067424349 0.0116116134 0.0094296023 0.0070120000 0.0005290000 0.0036200000 0.0000010000 0.0000080000 0.0012280000 14251765 96830484 509673472 3.7710449696 4.0584526062 3.7713868618 493 19.6800000000 0.0116230333 0.0067523347 0.0116230333 0.0094248713 0.0086700000 0.0004700000 0.0050620000 0.0000050000 0.0000040000 0.0020270000 14254541 96830484 509673472 3.7707805634 4.0585923195 3.7694623470 494 19.7200000000 0.0116536170 0.0067622563 0.0116536170 0.0094171783 0.0051390000 0.0004460000 0.0026330000 0.0000000000 0.0000040000 0.0010930000 14257317 96830484 509673472 3.7709760666 4.0595617294 3.7674825191 495 19.7600000000 0.0116698910 0.0067721707 0.0116698910 0.0094195622 0.0093060000 0.0006190000 0.0041960000 0.0000150000 0.0000140000 0.0018760000 14260093 96830484 509673472 3.7699623108 4.0591502190 3.7653529644 496 19.8000000000 0.0116562778 0.0067820177 0.0116698910 0.0094201799 0.0067410000 0.0005510000 0.0035630000 0.0000010000 0.0000070000 0.0011200000 14262869 96830484 509673472 3.7687046528 4.0592656136 3.7629592419 497 19.8400000000 0.0117384670 0.0067919904 0.0117384670 0.0094172207 0.0076350000 0.0005310000 0.0032150000 0.0000100000 0.0000090000 0.0022220000 14265645 96830484 509673472 3.7684018612 4.0587620735 3.7610974312 498 19.8800000000 0.0118155759 0.0068020779 0.0118155759 0.0094125801 0.0077220000 0.0004700000 0.0050640000 0.0000010000 0.0000070000 0.0010710000 14268421 96830484 509673472 3.7693319321 4.0569543839 3.7598206997 499 19.9200000000 0.0117806457 0.0068120550 0.0118155759 0.0094039104 0.0071830000 0.0004460000 0.0045880000 0.0000040000 0.0000040000 0.0013090000 14271197 96830484 509673472 3.7702751160 4.0571594238 3.7576749325 500 19.9600000000 0.0117645040 0.0068219599 0.0118155759 0.0093949664 0.0048060000 0.0004320000 0.0025960000 0.0000010000 0.0000040000 0.0010300000 14273973 96830484 509673472 3.7715864182 4.0577416420 3.7553486824 501 20.0000000000 0.0117978100 0.0068318918 0.0118155759 0.0094093548 0.0099140000 0.0006170000 0.0033730000 0.0000150000 0.0000130000 0.0026210000 14276749 96830484 509673472 3.7702908516 4.0556707382 3.7529015541 502 20.0400000000 0.0118181771 0.0068418246 0.0118181771 0.0094263670 0.0065090000 0.0005300000 0.0028040000 0.0000020000 0.0000110000 0.0012870000 14279525 96830484 509673472 3.7694950104 4.0549311638 3.7500452995 503 20.0800000000 0.0119566098 0.0068519932 0.0119566098 0.0094182617 0.0086460000 0.0005280000 0.0052220000 0.0000080000 0.0000060000 0.0014370000 14282301 96830484 509673472 3.7695019245 4.0560603142 3.7473280430 504 20.1200000000 0.0119056692 0.0068620203 0.0119566098 0.0094097050 0.0055450000 0.0004530000 0.0030370000 0.0000000000 0.0000050000 0.0010630000 14285077 96830484 509673472 3.7704036236 4.0566525459 3.7450265884 505 20.1600000000 0.0118361730 0.0068718701 0.0119566098 0.0094016332 0.0078560000 0.0005290000 0.0028050000 0.0000100000 0.0000100000 0.0022870000 14287853 96830484 509673472 3.7709884644 4.0578174591 3.7422609329 506 20.2000000000 0.0118614640 0.0068817310 0.0119566098 0.0093933501 0.0060410000 0.0004920000 0.0031140000 0.0000010000 0.0000060000 0.0010910000 14290629 96830484 509673472 3.7707602978 4.0588512421 3.7398710251 507 20.2400000000 0.0118649537 0.0068915598 0.0119566098 0.0093888359 0.0091120000 0.0006170000 0.0033610000 0.0000150000 0.0000140000 0.0017890000 14293405 96830484 509673472 3.7700803280 4.0577130318 3.7373011112 508 20.2800000000 0.0119191827 0.0069014567 0.0119566098 0.0093824145 0.0063240000 0.0005290000 0.0028010000 0.0000010000 0.0000100000 0.0012850000 14296181 96830484 509673472 3.7703745365 4.0577206612 3.7345676422 509 20.3200000000 0.0118973153 0.0069112718 0.0119566098 0.0093799315 0.0075230000 0.0005280000 0.0027890000 0.0000110000 0.0000090000 0.0022510000 14298957 96830484 509673472 3.7715837955 4.0571613312 3.7325074673 510 20.3600000000 0.0119338837 0.0069211200 0.0119566098 0.0093812014 0.0059880000 0.0004730000 0.0030680000 0.0000010000 0.0000070000 0.0010810000 14301733 96830484 509673472 3.7718167305 4.0582404137 3.7301363945 511 20.4000000000 0.0120094977 0.0069310777 0.0120094977 0.0093740408 0.0087070000 0.0006160000 0.0029420000 0.0000150000 0.0000160000 0.0017500000 14304509 96830484 509673472 3.7716534138 4.0588555336 3.7275097370 512 20.4400000000 0.0119910194 0.0069409604 0.0120094977 0.0093657631 0.0072540000 0.0006160000 0.0029540000 0.0000010000 0.0000170000 0.0014300000 14307285 96830484 509673472 3.7719390392 4.0594696999 3.7246646881 513 20.4800000000 0.0120129529 0.0069508473 0.0120129529 0.0093581894 0.0069710000 0.0004940000 0.0031310000 0.0000070000 0.0000050000 0.0020000000 14359213 96830484 509673472 3.7747497559 4.0609116554 3.7218320370 514 20.5200000000 0.0120004369 0.0069606714 0.0120129529 0.0093528732 0.0070350000 0.0005300000 0.0036390000 0.0000010000 0.0000070000 0.0011600000 14464389 96830484 509673472 3.7753462791 4.0608983040 3.7186684608 515 20.5600000000 0.0120939063 0.0069706389 0.0120939063 0.0093465614 0.0078390000 0.0006210000 0.0033940000 0.0000150000 0.0000140000 0.0015130000 14467165 96830484 509673472 3.7767426968 4.0603585243 3.7159636021 516 20.6000000000 0.0120746316 0.0069805303 0.0120939063 0.0093433879 0.0060800000 0.0004920000 0.0031250000 0.0000010000 0.0000070000 0.0010730000 14469941 96830484 509673472 3.7793145180 4.0598001480 3.7133224010 517 20.6400000000 0.0121515663 0.0069905323 0.0121515663 0.0093358921 0.0069910000 0.0004530000 0.0034640000 0.0000050000 0.0000050000 0.0019430000 14472717 96830484 509673472 3.7814569473 4.0601892471 3.7109005451 518 20.6800000000 0.0121264569 0.0070004472 0.0121515663 0.0093305058 0.0055090000 0.0004460000 0.0030530000 0.0000000000 0.0000040000 0.0010270000 14475493 96830484 509673472 3.7833125591 4.0609488487 3.7083568573 519 20.7200000000 0.0121402023 0.0070103504 0.0121515663 0.0093257234 0.0094650000 0.0006140000 0.0036530000 0.0000160000 0.0000150000 0.0017410000 14478269 96830484 509673472 3.7846438885 4.0615949631 3.7057192326 520 20.7600000000 0.0122174509 0.0070203641 0.0122174509 0.0093211164 0.0096120000 0.0006000000 0.0055280000 0.0000020000 0.0000100000 0.0012610000 14481045 96830484 509673472 3.7854695320 4.0613207817 3.7033376694 521 20.8000000000 0.0122304289 0.0070303642 0.0122304289 0.0093128298 0.0071980000 0.0005000000 0.0035260000 0.0000060000 0.0000050000 0.0019760000 14483821 96830484 509673472 3.7862977982 4.0624370575 3.7011549473 522 20.8400000000 0.0122262854 0.0070403181 0.0122304289 0.0093046368 0.0058070000 0.0004460000 0.0034700000 0.0000010000 0.0000040000 0.0010130000 14486597 96830484 509673472 3.7869396210 4.0645208359 3.6987557411 523 20.8800000000 0.0122443382 0.0070502684 0.0122443382 0.0092964451 0.0089980000 0.0005290000 0.0053140000 0.0000080000 0.0000070000 0.0014190000 14489373 96830484 509673472 3.7878124714 4.0650100708 3.6965157986 524 20.9200000000 0.0123031791 0.0070602931 0.0123031791 0.0092886164 0.0061890000 0.0004680000 0.0035130000 0.0000010000 0.0000050000 0.0010400000 14492149 96830484 509673472 3.7877595425 4.0650491714 3.6940340996 525 20.9600000000 0.0122878868 0.0070702504 0.0123031791 0.0092829099 0.0096460000 0.0009470000 0.0042830000 0.0000100000 0.0000100000 0.0022980000 14494925 96830484 509673472 3.7883937359 4.0652432442 3.6917235851 526 21.0000000000 0.0123354523 0.0070802603 0.0123354523 0.0092790470 0.0071260000 0.0005380000 0.0036620000 0.0000010000 0.0000070000 0.0011420000 14497701 96830484 509673472 3.7891831398 4.0659074783 3.6895651817 527 21.0400000000 0.0123733263 0.0070903040 0.0123733263 0.0092741738 0.0060070000 0.0004680000 0.0030860000 0.0000060000 0.0000050000 0.0013110000 14500477 96830484 509673472 3.7896568775 4.0661320686 3.6877164841 528 21.0800000000 0.0123678083 0.0071002993 0.0123733263 0.0092759982 0.0078300000 0.0006130000 0.0030040000 0.0000020000 0.0000150000 0.0014990000 14503253 96830484 509673472 3.7908344269 4.0664043427 3.6859059334 529 21.1200000000 0.0124050714 0.0071103272 0.0124050714 0.0092748242 0.0067130000 0.0005000000 0.0027590000 0.0000060000 0.0000060000 0.0019960000 14506029 96830484 509673472 3.7914919853 4.0655498505 3.6840393543 530 21.1600000000 0.0124669615 0.0071204341 0.0124669615 0.0092761004 0.0053430000 0.0004560000 0.0026730000 0.0000010000 0.0000050000 0.0010480000 14508805 96830484 509673472 3.7912034988 4.0655341148 3.6821885109 531 21.2000000000 0.0125359735 0.0071306328 0.0125359735 0.0092828368 0.0093590000 0.0006170000 0.0034140000 0.0000150000 0.0000130000 0.0017330000 14511581 96830484 509673472 3.7917201519 4.0658516884 3.6803863049 532 21.2400000000 0.0125020286 0.0071407294 0.0125359735 0.0092924373 0.0069080000 0.0005320000 0.0036100000 0.0000010000 0.0000080000 0.0011490000 14514357 96830484 509673472 3.7925415039 4.0643892288 3.6787548065 533 21.2800000000 0.0125238420 0.0071508291 0.0125359735 0.0093009201 0.0072380000 0.0005280000 0.0028210000 0.0000080000 0.0000080000 0.0020710000 14517133 96830484 509673472 3.7931218147 4.0640954971 3.6771564484 534 21.3200000000 0.0126207676 0.0071610724 0.0126207676 0.0092949488 0.0062980000 0.0004700000 0.0035040000 0.0000000000 0.0000070000 0.0010880000 14519909 96830484 509673472 3.7935726643 4.0632944107 3.6757719517 535 21.3600000000 0.0126065407 0.0071712509 0.0126207676 0.0092920611 0.0072190000 0.0005270000 0.0032240000 0.0000110000 0.0000090000 0.0015210000 14522685 96830484 509673472 3.7937884331 4.0623035431 3.6743905544 536 21.4000000000 0.0127170784 0.0071815976 0.0127170784 0.0092913300 0.0070330000 0.0004990000 0.0035710000 0.0000010000 0.0000090000 0.0011450000 14525461 96830484 509673472 3.7939476967 4.0625977516 3.6728293896 537 21.4400000000 0.0126992231 0.0071918725 0.0127170784 0.0092894143 0.0087820000 0.0004750000 0.0051040000 0.0000050000 0.0000050000 0.0019600000 14528237 96830484 509673472 3.7940609455 4.0616168976 3.6715946198 538 21.4800000000 0.0127065703 0.0072021228 0.0127170784 0.0093004231 0.0051980000 0.0004480000 0.0026490000 0.0000000000 0.0000040000 0.0010330000 14531013 96830484 509673472 3.7944540977 4.0614452362 3.6704416275 539 21.5200000000 0.0126724532 0.0072122719 0.0127170784 0.0093171443 0.0056800000 0.0004420000 0.0030200000 0.0000040000 0.0000040000 0.0012800000 14533789 96830484 509673472 3.7950787544 4.0604605675 3.6691429615 540 21.5600000000 0.0128536401 0.0072227189 0.0128536401 0.0093245264 0.0050540000 0.0004410000 0.0026510000 0.0000010000 0.0000040000 0.0010270000 14536565 96830484 509673472 3.7945182323 4.0602746010 3.6679036617 541 21.6000000000 0.0127914082 0.0072330122 0.0128536401 0.0093290544 0.0059600000 0.0004420000 0.0026240000 0.0000030000 0.0000040000 0.0019440000 14539341 96830484 509673472 3.7945134640 4.0600047112 3.6665530205 542 21.6400000000 0.0127875684 0.0072432604 0.0128536401 0.0093298221 0.0062430000 0.0004400000 0.0038280000 0.0000010000 0.0000040000 0.0010350000 14542117 96830484 509673472 3.7949566841 4.0586833954 3.6653904915 543 21.6800000000 0.0128559507 0.0072535969 0.0128559507 0.0093320153 0.0076930000 0.0004390000 0.0050040000 0.0000040000 0.0000040000 0.0013080000 14544893 96830484 509673472 3.7939403057 4.0577697754 3.6642050743 544 21.7200000000 0.0127883693 0.0072637711 0.0128559507 0.0093291563 0.0054480000 0.0004370000 0.0030220000 0.0000000000 0.0000040000 0.0010480000 14547669 96830484 509673472 3.7938990593 4.0566692352 3.6630160809 545 21.7600000000 0.0128419343 0.0072740063 0.0128559507 0.0093241850 0.0067780000 0.0004400000 0.0034160000 0.0000040000 0.0000040000 0.0019720000 14550445 96830484 509673472 3.7934963703 4.0553479195 3.6619915962 546 21.8000000000 0.0128325112 0.0072841867 0.0128559507 0.0093303665 0.0088790000 0.0006450000 0.0029720000 0.0000020000 0.0000150000 0.0015650000 14553221 96830484 509673472 3.7932898998 4.0544419289 3.6610355377 547 21.8400000000 0.0127756186 0.0072942259 0.0128559507 0.0093536634 0.0066570000 0.0005300000 0.0027820000 0.0000080000 0.0000070000 0.0014700000 14555997 96830484 509673472 3.7933962345 4.0529236794 3.6600165367 548 21.8800000000 0.0127638644 0.0073042069 0.0128559507 0.0093671343 0.0073480000 0.0006180000 0.0029640000 0.0000020000 0.0000150000 0.0013330000 14558773 96830484 509673472 3.7930397987 4.0519056320 3.6587829590 549 21.9200000000 0.0127226822 0.0073140767 0.0128559507 0.0093773598 0.0072270000 0.0004940000 0.0031280000 0.0000080000 0.0000070000 0.0021150000 14561549 96830484 509673472 3.7924287319 4.0483841896 3.6577310562 550 21.9600000000 0.0127452910 0.0073239516 0.0128559507 0.0093863071 0.0070310000 0.0004560000 0.0042990000 0.0000000000 0.0000050000 0.0011130000 14564325 96830484 509673472 3.7916142941 4.0476193428 3.6566259861 551 22.0000000000 0.0127986241 0.0073338875 0.0128559507 0.0093838036 0.0059000000 0.0004440000 0.0030420000 0.0000050000 0.0000050000 0.0013500000 14567101 96830484 509673472 3.7910606861 4.0478882790 3.6554841995 552 22.0400000000 0.0125914626 0.0073434121 0.0128559507 0.0093802630 0.0053090000 0.0004490000 0.0026650000 0.0000000000 0.0000040000 0.0011090000 14569877 96830484 509673472 3.7903568745 4.0467786789 3.6544966698 553 22.0800000000 0.0126719382 0.0073530477 0.0128559507 0.0093803802 0.0105440000 0.0006430000 0.0034210000 0.0000170000 0.0000140000 0.0027180000 14572653 96830484 509673472 3.7893705368 4.0448837280 3.6535830498 554 22.1200000000 0.0127245085 0.0073627435 0.0128559507 0.0093884222 0.0071470000 0.0005310000 0.0032560000 0.0000020000 0.0000090000 0.0013610000 14575429 96830484 509673472 3.7886612415 4.0447320938 3.6527397633 555 22.1600000000 0.0126509108 0.0073722718 0.0128559507 0.0093915622 0.0071430000 0.0005260000 0.0032280000 0.0000080000 0.0000080000 0.0015030000 14578205 96830484 509673472 3.7883296013 4.0460247993 3.6516070366 556 22.2000000000 0.0126941297 0.0073818434 0.0128559507 0.0093854276 0.0079430000 0.0006170000 0.0034470000 0.0000010000 0.0000110000 0.0013680000 14580981 96830484 509673472 3.7884783745 4.0458073616 3.6506924629 557 22.2400000000 0.0127534689 0.0073914873 0.0128559507 0.0093781690 0.0070880000 0.0004910000 0.0031490000 0.0000070000 0.0000070000 0.0021240000 14583757 96830484 509673472 3.7882430553 4.0442242622 3.6499600410 558 22.2800000000 0.0127511872 0.0074010925 0.0128559507 0.0093765481 0.0057120000 0.0004430000 0.0030640000 0.0000000000 0.0000050000 0.0011110000 14586533 96830484 509673472 3.7884621620 4.0437784195 3.6493954659 559 22.3200000000 0.0127619337 0.0074106825 0.0128559507 0.0093799952 0.0064930000 0.0004370000 0.0037160000 0.0000040000 0.0000040000 0.0013710000 14589309 96830484 509673472 3.7881696224 4.0434603691 3.6483993530 560 22.3600000000 0.0127255330 0.0074201734 0.0128559507 0.0093774261 0.0051570000 0.0004360000 0.0026650000 0.0000000000 0.0000040000 0.0010970000 14592085 96830484 509673472 3.7878243923 4.0435767174 3.6476116180 561 22.4000000000 0.0127617931 0.0074296950 0.0128559507 0.0093749610 0.0120970000 0.0006330000 0.0054210000 0.0000150000 0.0000140000 0.0027410000 14594861 96830484 509673472 3.7879464626 4.0429673195 3.6469266415 562 22.4400000000 0.0127450312 0.0074391529 0.0128559507 0.0093716607 0.0065580000 0.0005300000 0.0028650000 0.0000010000 0.0000100000 0.0012480000 14597637 96830484 509673472 3.7874920368 4.0423283577 3.6461851597 563 22.4800000000 0.0127597973 0.0074486034 0.0128559507 0.0093688989 0.0058630000 0.0004710000 0.0027370000 0.0000050000 0.0000040000 0.0013720000 14600413 96830484 509673472 3.7874279022 4.0418744087 3.6456179619 564 22.5200000000 0.0128030451 0.0074580971 0.0128559507 0.0093690411 0.0053490000 0.0004430000 0.0027000000 0.0000000000 0.0000040000 0.0011060000 14603189 96830484 509673472 3.7872865200 4.0418214798 3.6450216770 565 22.5600000000 0.0127754034 0.0074675082 0.0128559507 0.0093716577 0.0106210000 0.0006420000 0.0034380000 0.0000150000 0.0000160000 0.0027200000 14605965 96830484 509673472 3.7865707874 4.0409398079 3.6441838741 566 22.6000000000 0.0128014451 0.0074769321 0.0128559507 0.0093712264 0.0065960000 0.0005300000 0.0031060000 0.0000010000 0.0000090000 0.0012350000 14608741 96830484 509673472 3.7867743969 4.0406994820 3.6437718868 567 22.6400000000 0.0128289238 0.0074863713 0.0128559507 0.0093694840 0.0080700000 0.0005320000 0.0041370000 0.0000100000 0.0000100000 0.0014710000 14611517 96830484 509673472 3.7863647938 4.0403518677 3.6429076195 568 22.6800000000 0.0128501486 0.0074958146 0.0128559507 0.0093688628 0.0062470000 0.0004690000 0.0034390000 0.0000010000 0.0000060000 0.0011140000 14614293 96830484 509673472 3.7861077785 4.0397262573 3.6425511837 569 22.7200000000 0.0129633788 0.0075054236 0.0129633788 0.0093754550 0.0072430000 0.0004370000 0.0039250000 0.0000040000 0.0000030000 0.0020120000 14617069 96830484 509673472 3.7857916355 4.0395388603 3.6419301033 570 22.7600000000 0.0129533028 0.0075149813 0.0129633788 0.0093782291 0.0062280000 0.0004290000 0.0039120000 0.0000010000 0.0000030000 0.0010800000 14619845 96830484 509673472 3.7853293419 4.0391702652 3.6413178444 571 22.8000000000 0.0129522029 0.0075245036 0.0129633788 0.0093834642 0.0085740000 0.0006190000 0.0034810000 0.0000170000 0.0000130000 0.0018300000 14622621 96830484 509673472 3.7851698399 4.0381464958 3.6406114101 572 22.8400000000 0.0129592903 0.0075340050 0.0129633788 0.0093937356 0.0068480000 0.0004980000 0.0036620000 0.0000010000 0.0000070000 0.0011430000 14625397 96830484 509673472 3.7850584984 4.0384564400 3.6398563385 573 22.8800000000 0.0129825044 0.0075435137 0.0129825044 0.0093930674 0.0090080000 0.0006170000 0.0034690000 0.0000140000 0.0000140000 0.0023680000 14628173 96830484 509673472 3.7847015858 4.0379977226 3.6390154362 574 22.9200000000 0.0130134141 0.0075530431 0.0130134141 0.0093949401 0.0063830000 0.0005040000 0.0032240000 0.0000010000 0.0000060000 0.0011480000 14630949 96830484 509673472 3.7850117683 4.0371794701 3.6380121708 575 22.9600000000 0.0130387712 0.0075625835 0.0130387712 0.0093993497 0.0072440000 0.0005300000 0.0033190000 0.0000110000 0.0000100000 0.0014670000 14633725 96830484 509673472 3.7850267887 4.0365443230 3.6371710300 576 23.0000000000 0.0130278040 0.0075720718 0.0130387712 0.0094066136 0.0061720000 0.0004700000 0.0032090000 0.0000010000 0.0000070000 0.0011470000 14636501 96830484 509673472 3.7846674919 4.0356621742 3.6361207962 577 23.0400000000 0.0131529337 0.0075817440 0.0131529337 0.0094143906 0.0095510000 0.0006150000 0.0035140000 0.0000170000 0.0000140000 0.0026940000 14639277 96830484 509673472 3.7850472927 4.0347366333 3.6353261471 578 23.0800000000 0.0132392803 0.0075915321 0.0132392803 0.0094229614 0.0060210000 0.0005020000 0.0028480000 0.0000010000 0.0000060000 0.0011280000 14642053 96830484 509673472 3.7851383686 4.0337381363 3.6345624924 579 23.1200000000 0.0132364463 0.0076012815 0.0132392803 0.0094286777 0.0062020000 0.0004560000 0.0031750000 0.0000050000 0.0000050000 0.0013600000 14644829 96830484 509673472 3.7851204872 4.0328435898 3.6337120533 580 23.1600000000 0.0132653834 0.0076110472 0.0132653834 0.0094350795 0.0066070000 0.0004450000 0.0039660000 0.0000010000 0.0000050000 0.0010840000 14647605 96830484 509673472 3.7849605083 4.0322179794 3.6329731941 581 23.2000000000 0.0131462039 0.0076205742 0.0132653834 0.0094375445 0.0069600000 0.0004380000 0.0035180000 0.0000040000 0.0000040000 0.0020180000 14650381 96830484 509673472 3.7847881317 4.0311307907 3.6324112415 582 23.2400000000 0.0131137418 0.0076300126 0.0132653834 0.0094390039 0.0084130000 0.0006190000 0.0035170000 0.0000020000 0.0000150000 0.0015820000 14653157 96830484 509673472 3.7854714394 4.0306496620 3.6318356991 583 23.2800000000 0.0131633738 0.0076395038 0.0132653834 0.0094460591 0.0066940000 0.0004980000 0.0032280000 0.0000060000 0.0000060000 0.0014080000 14655933 96830484 509673472 3.7862854004 4.0307936668 3.6312222481 584 23.3200000000 0.0132549554 0.0076491193 0.0132653834 0.0094466408 0.0081700000 0.0006480000 0.0033510000 0.0000020000 0.0000160000 0.0013500000 14658709 96830484 509673472 3.7858307362 4.0294728279 3.6306612492 585 23.3600000000 0.0132187568 0.0076586400 0.0132653834 0.0094571606 0.0073170000 0.0005530000 0.0032120000 0.0000080000 0.0000060000 0.0020950000 14661485 96830484 509673472 3.7864778042 4.0289859772 3.6304609776 586 23.4000000000 0.0132675981 0.0076682116 0.0132675981 0.0094731519 0.0056610000 0.0004470000 0.0031430000 0.0000000000 0.0000040000 0.0010880000 14664261 96830484 509673472 3.7866601944 4.0292611122 3.6299459934 587 23.4400000000 0.0131661585 0.0076775778 0.0132675981 0.0094775606 0.0098920000 0.0006430000 0.0034820000 0.0000150000 0.0000130000 0.0018440000 14667037 96830484 509673472 3.7866225243 4.0286793709 3.6293954849 588 23.4800000000 0.0132240597 0.0076870106 0.0132675981 0.0094830886 0.0066250000 0.0005340000 0.0032530000 0.0000010000 0.0000070000 0.0012150000 14669813 96830484 509673472 3.7872385979 4.0281419754 3.6295433044 589 23.5200000000 0.0132363243 0.0076964322 0.0132675981 0.0094899253 0.0063740000 0.0004560000 0.0027430000 0.0000050000 0.0000050000 0.0020340000 14672589 96830484 509673472 3.7872266769 4.0279932022 3.6291184425 590 23.5600000000 0.0132511938 0.0077058470 0.0132675981 0.0094941889 0.0052470000 0.0004360000 0.0027180000 0.0000000000 0.0000040000 0.0010900000 14675365 96830484 509673472 3.7873580456 4.0277318954 3.6289069653 591 23.6000000000 0.0132253468 0.0077151863 0.0132675981 0.0094936478 0.0098730000 0.0006140000 0.0034900000 0.0000140000 0.0000160000 0.0018370000 14678141 96830484 509673472 3.7871806622 4.0262336731 3.6288323402 592 23.6400000000 0.0132609848 0.0077245542 0.0132675981 0.0095041746 0.0068850000 0.0005480000 0.0032840000 0.0000010000 0.0000070000 0.0012220000 14680917 96830484 509673472 3.7870986462 4.0256323814 3.6285710335 593 23.6800000000 0.0132876728 0.0077339355 0.0132876728 0.0095093287 0.0068610000 0.0004740000 0.0031530000 0.0000050000 0.0000050000 0.0020910000 14683693 96830484 509673472 3.7870020866 4.0253105164 3.6283504963 594 23.7200000000 0.0131558934 0.0077430634 0.0132876728 0.0095077896 0.0053760000 0.0004380000 0.0029830000 0.0000010000 0.0000040000 0.0010680000 14686469 96830484 509673472 3.7869298458 4.0247807503 3.6277935505 595 23.7600000000 0.0132258842 0.0077522782 0.0132876728 0.0095089631 0.0096740000 0.0006170000 0.0034780000 0.0000160000 0.0000140000 0.0018800000 14689245 96830484 509673472 3.7869267464 4.0239605904 3.6276926994 596 23.8000000000 0.0132906344 0.0077615707 0.0132906344 0.0095131752 0.0058320000 0.0005030000 0.0024080000 0.0000010000 0.0000080000 0.0012150000 14692021 96830484 509673472 3.7864041328 4.0235528946 3.6275420189 597 23.8400000000 0.0132880900 0.0077708279 0.0132906344 0.0095129191 0.0074520000 0.0005270000 0.0027190000 0.0000080000 0.0000080000 0.0022100000 14694797 96830484 509673472 3.7865681648 4.0233731270 3.6277434826 598 23.8800000000 0.0132829873 0.0077800455 0.0132906344 0.0095100290 0.0054470000 0.0004700000 0.0023790000 0.0000010000 0.0000060000 0.0011460000 14697573 96830484 509673472 3.7864680290 4.0228137970 3.6275718212 599 23.9200000000 0.0132173412 0.0077891228 0.0132906344 0.0095041662 0.0093800000 0.0006130000 0.0029060000 0.0000150000 0.0000130000 0.0018770000 14700349 96830484 509673472 3.7864818573 4.0215253830 3.6276023388 600 23.9600000000 0.0133005986 0.0077983086 0.0133005986 0.0094990121 0.0067750000 0.0005320000 0.0031500000 0.0000010000 0.0000080000 0.0012170000 14703125 96830484 509673472 3.7867100239 4.0206165314 3.6276109219 601 24.0000000000 0.0133778406 0.0078075924 0.0133778406 0.0094962289 0.0068970000 0.0004670000 0.0031520000 0.0000050000 0.0000040000 0.0021110000 14705901 96830484 509673472 3.7865183353 4.0199594498 3.6274497509 602 24.0400000000 0.0133799911 0.0078168489 0.0133799911 0.0094961854 0.0070560000 0.0005290000 0.0027680000 0.0000020000 0.0000100000 0.0013520000 14708677 96830484 509673472 3.7867398262 4.0188794136 3.6276130676 603 24.0800000000 0.0134332413 0.0078261629 0.0134332413 0.0095040321 0.0067530000 0.0005270000 0.0026920000 0.0000100000 0.0000090000 0.0014900000 14711453 96830484 509673472 3.7868418694 4.0182108879 3.6278071404 604 24.1200000000 0.0133134304 0.0078352478 0.0134332413 0.0095070472 0.0057980000 0.0004690000 0.0028060000 0.0000010000 0.0000060000 0.0011570000 14714229 96830484 509673472 3.7870426178 4.0175542831 3.6282134056 605 24.1600000000 0.0133743072 0.0078444033 0.0134332413 0.0095046399 0.0070450000 0.0004610000 0.0031530000 0.0000050000 0.0000060000 0.0020770000 14717005 96830484 509673472 3.7866671085 4.0175228119 3.6280324459 606 24.2000000000 0.0134034790 0.0078535767 0.0134332413 0.0094982762 0.0057780000 0.0004520000 0.0030200000 0.0000010000 0.0000050000 0.0011210000 14719781 96830484 509673472 3.7868928909 4.0169177055 3.6280999184 607 24.2400000000 0.0134239011 0.0078627535 0.0134332413 0.0094916558 0.0094880000 0.0006180000 0.0029100000 0.0000150000 0.0000140000 0.0018630000 14722557 96830484 509673472 3.7873260975 4.0165147781 3.6282858849 608 24.2800000000 0.0134743638 0.0078719831 0.0134743638 0.0094848174 0.0064610000 0.0005280000 0.0028480000 0.0000000000 0.0000080000 0.0012300000 14725333 96830484 509673472 3.7878198624 4.0161156654 3.6284029484 609 24.3200000000 0.0135329068 0.0078812786 0.0135329068 0.0094779916 0.0064830000 0.0004560000 0.0027380000 0.0000050000 0.0000050000 0.0021030000 14728109 96830484 509673472 3.7870261669 4.0148653984 3.6282455921 610 24.3600000000 0.0136036500 0.0078906595 0.0136036500 0.0094777136 0.0073690000 0.0005280000 0.0033390000 0.0000010000 0.0000100000 0.0013730000 14730885 96830484 509673472 3.7872748375 4.0148358345 3.6280305386 611 24.4000000000 0.0135577144 0.0078999345 0.0136036500 0.0094723362 0.0064940000 0.0004690000 0.0032120000 0.0000060000 0.0000050000 0.0014330000 14733661 96830484 509673472 3.7875037193 4.0137958527 3.6282401085 612 24.4400000000 0.0136006223 0.0079092494 0.0136036500 0.0094696015 0.0055700000 0.0004460000 0.0028180000 0.0000010000 0.0000050000 0.0011150000 14736437 96830484 509673472 3.7876214981 4.0136480331 3.6278691292 613 24.4800000000 0.0136528993 0.0079186191 0.0136528993 0.0094646810 0.0110440000 0.0006300000 0.0035440000 0.0000160000 0.0000130000 0.0027520000 14739213 96830484 509673472 3.7886145115 4.0146741867 3.6281461716 614 24.5200000000 0.0138089322 0.0079282125 0.0138089322 0.0094570532 0.0063330000 0.0005030000 0.0026810000 0.0000010000 0.0000080000 0.0012430000 14741989 96830484 509673472 3.7886765003 4.0146989822 3.6280870438 615 24.5600000000 0.0138453944 0.0079378339 0.0138453944 0.0094498360 0.0062450000 0.0005180000 0.0030200000 0.0000060000 0.0000060000 0.0013960000 14744765 96830484 509673472 3.7880790234 4.0132141113 3.6278197765 616 24.6000000000 0.0138186309 0.0079473807 0.0138453944 0.0094477587 0.0069760000 0.0005290000 0.0032920000 0.0000010000 0.0000080000 0.0012260000 14747541 96830484 509673472 3.7878401279 4.0114126205 3.6274883747 617 24.6400000000 0.0138796614 0.0079569954 0.0138796614 0.0094495365 0.0095420000 0.0006140000 0.0030930000 0.0000170000 0.0000130000 0.0027390000 14750317 96830484 509673472 3.7882730961 4.0111403465 3.6275846958 618 24.6800000000 0.0139795225 0.0079667406 0.0139795225 0.0094498727 0.0065680000 0.0004990000 0.0032360000 0.0000010000 0.0000070000 0.0011840000 14753093 96830484 509673472 3.7888281345 4.0105538368 3.6274337769 619 24.7200000000 0.0139878122 0.0079764677 0.0139878122 0.0094624856 0.0053710000 0.0004580000 0.0023060000 0.0000040000 0.0000040000 0.0014190000 14755869 96830484 509673472 3.7893729210 4.0104508400 3.6271731853 620 24.7600000000 0.0141162612 0.0079863705 0.0141162612 0.0094676316 0.0052970000 0.0004370000 0.0026960000 0.0000010000 0.0000050000 0.0011240000 14758645 96830484 509673472 3.7895519733 4.0112333298 3.6261911392 621 24.8000000000 0.0141282510 0.0079962609 0.0141282510 0.0094607354 0.0109200000 0.0006160000 0.0037340000 0.0000150000 0.0000140000 0.0027850000 14761421 96830484 509673472 3.7902345657 4.0111570358 3.6259377003 622 24.8400000000 0.0143419690 0.0080064630 0.0143419690 0.0094531398 0.0062540000 0.0004990000 0.0028220000 0.0000010000 0.0000080000 0.0012490000 14764197 96830484 509673472 3.7913894653 4.0107517242 3.6259617805 623 24.8800000000 0.0143046817 0.0080165725 0.0143419690 0.0094457650 0.0062090000 0.0004540000 0.0031430000 0.0000040000 0.0000040000 0.0014110000 14766973 96830484 509673472 3.7922778130 4.0103034973 3.6260583401 624 24.9200000000 0.0143658221 0.0080267475 0.0143658221 0.0094385587 0.0053360000 0.0004390000 0.0027150000 0.0000000000 0.0000040000 0.0011280000 14769749 96830484 509673472 3.7927713394 4.0095171928 3.6256351471 625 24.9600000000 0.0144506870 0.0080370258 0.0144506870 0.0094330252 0.0109810000 0.0006160000 0.0034770000 0.0000150000 0.0000130000 0.0027500000 14772525 96830484 509673472 3.7941846848 4.0097980499 3.6259076595 626 25.0000000000 0.0145447999 0.0080474216 0.0145447999 0.0094256790 0.0064240000 0.0005280000 0.0026830000 0.0000010000 0.0000070000 0.0012530000 14775301 96830484 509673472 3.7954294682 4.0102458000 3.6259236336 627 25.0400000000 0.0145398341 0.0080577764 0.0145447999 0.0094181966 0.0063080000 0.0004790000 0.0031510000 0.0000050000 0.0000050000 0.0014280000 14778077 96830484 509673472 3.7965455055 4.0093817711 3.6258580685 628 25.0800000000 0.0146732479 0.0080683106 0.0146732479 0.0094138863 0.0070710000 0.0005310000 0.0031680000 0.0000010000 0.0000070000 0.0012510000 14780853 96830484 509673472 3.7979745865 4.0099120140 3.6257960796 629 25.1200000000 0.0146822585 0.0080788256 0.0146822585 0.0094075184 0.0067160000 0.0004710000 0.0026250000 0.0000060000 0.0000050000 0.0021970000 14783629 96830484 509673472 3.7997128963 4.0113568306 3.6253938675 630 25.1600000000 0.0147871003 0.0080894736 0.0147871003 0.0094043132 0.0057900000 0.0004450000 0.0030040000 0.0000000000 0.0000050000 0.0011350000 14786405 96830484 509673472 3.8008201122 4.0110673904 3.6255996227 631 25.2000000000 0.0148385093 0.0081001694 0.0148385093 0.0093981510 0.0054810000 0.0004390000 0.0025590000 0.0000040000 0.0000040000 0.0014160000 14789181 96830484 509673472 3.8026139736 4.0104598999 3.6259899139 632 25.2400000000 0.0148733780 0.0081108865 0.0148733780 0.0093907153 0.0099870000 0.0006410000 0.0035060000 0.0000020000 0.0000150000 0.0016210000 14791957 96830484 509673472 3.8041639328 4.0105128288 3.6259267330 633 25.2800000000 0.0149340415 0.0081216656 0.0149340415 0.0093833087 0.0078230000 0.0005280000 0.0029080000 0.0000120000 0.0000090000 0.0022650000 14794733 96830484 509673472 3.8057537079 4.0116786957 3.6259920597 634 25.3200000000 0.0150437905 0.0081325838 0.0150437905 0.0093777548 0.0058190000 0.0004770000 0.0027680000 0.0000010000 0.0000050000 0.0011610000 14797509 96830484 509673472 3.8076946735 4.0116395950 3.6266181469 635 25.3600000000 0.0151105691 0.0081435727 0.0151105691 0.0093724590 0.0081700000 0.0006140000 0.0030710000 0.0000170000 0.0000130000 0.0016470000 14800285 96830484 509673472 3.8097591400 4.0113582611 3.6273779869 636 25.4000000000 0.0151634263 0.0081546102 0.0151634263 0.0093660533 0.0060360000 0.0004920000 0.0026580000 0.0000010000 0.0000060000 0.0012000000 14803061 96830484 509673472 3.8115205765 4.0115666389 3.6271371841 637 25.4400000000 0.0152469100 0.0081657441 0.0152469100 0.0093602905 0.0068030000 0.0004500000 0.0031260000 0.0000040000 0.0000050000 0.0021140000 14805837 96830484 509673472 3.8137483597 4.0118913651 3.6275432110 638 25.4800000000 0.0152903078 0.0081769112 0.0152903078 0.0093564763 0.0079610000 0.0006170000 0.0029190000 0.0000020000 0.0000150000 0.0015430000 14808613 96830484 509673472 3.8154547215 4.0108761787 3.6280786991 639 25.5200000000 0.0152368871 0.0081879596 0.0152903078 0.0093491853 0.0063780000 0.0004930000 0.0026540000 0.0000060000 0.0000060000 0.0014870000 14811389 96830484 509673472 3.8177413940 4.0109181404 3.6281580925 640 25.5600000000 0.0153528219 0.0081991547 0.0153528219 0.0093422187 0.0093260000 0.0006170000 0.0033250000 0.0000020000 0.0000140000 0.0016340000 14814165 96830484 509673472 3.8201842308 4.0114259720 3.6287486553 641 25.6000000000 0.0153734824 0.0082103471 0.0153734824 0.0093354804 0.0077890000 0.0005300000 0.0027490000 0.0000110000 0.0000100000 0.0022910000 14816941 96830484 509673472 3.8230142593 4.0119137764 3.6294262409 642 25.6400000000 0.0154950153 0.0082216940 0.0154950153 0.0093301805 0.0065470000 0.0004770000 0.0034510000 0.0000000000 0.0000050000 0.0011600000 14819717 96830484 509673472 3.8250775337 4.0114917755 3.6295664310 643 25.6800000000 0.0154514965 0.0082329378 0.0154950153 0.0093229189 0.0059150000 0.0004370000 0.0030990000 0.0000050000 0.0000030000 0.0014050000 14822493 96830484 509673472 3.8275990486 4.0121240616 3.6297852993 644 25.7200000000 0.0155466842 0.0082442946 0.0155466842 0.0093164665 0.0076140000 0.0005480000 0.0033210000 0.0000010000 0.0000100000 0.0013950000 14825269 96830484 509673472 3.8301548958 4.0119838715 3.6306042671 645 25.7600000000 0.0155269196 0.0082555855 0.0155466842 0.0093093339 0.0074050000 0.0004760000 0.0030470000 0.0000060000 0.0000050000 0.0021890000 14828045 96830484 509673472 3.8327240944 4.0112910271 3.6313302517 646 25.8000000000 0.0155783845 0.0082669211 0.0155783845 0.0093040639 0.0079920000 0.0006180000 0.0030620000 0.0000010000 0.0000150000 0.0013910000 14830821 96830484 509673472 3.8351988792 4.0118198395 3.6316664219 647 25.8400000000 0.0155384028 0.0082781598 0.0155783845 0.0092968696 0.0065000000 0.0004940000 0.0027860000 0.0000070000 0.0000050000 0.0014650000 14833597 96830484 509673472 3.8379375935 4.0122227669 3.6326274872 648 25.8800000000 0.0155635811 0.0082894028 0.0155783845 0.0092906785 0.0078470000 0.0005290000 0.0031720000 0.0000010000 0.0000100000 0.0013610000 14836373 96830484 509673472 3.8401138783 4.0116219521 3.6334450245 649 25.9200000000 0.0156078637 0.0083006793 0.0156078637 0.0092835176 0.0069300000 0.0004840000 0.0027770000 0.0000060000 0.0000060000 0.0021850000 14839149 96830484 509673472 3.8426628113 4.0112671852 3.6337857246 650 25.9600000000 0.0156552270 0.0083119940 0.0156552270 0.0092769052 0.0055530000 0.0004470000 0.0027220000 0.0000010000 0.0000040000 0.0011230000 14841925 96830484 509673472 3.8454108238 4.0117840767 3.6345632076 651 26.0000000000 0.0156194782 0.0083232190 0.0156552270 0.0092697803 0.0055290000 0.0004390000 0.0025710000 0.0000040000 0.0000040000 0.0014090000 14844701 96830484 509673472 3.8478736877 4.0122890472 3.6350023746 652 26.0400000000 0.0156706553 0.0083344881 0.0156706553 0.0092628552 0.0101320000 0.0006160000 0.0035300000 0.0000020000 0.0000150000 0.0015880000 14847477 96830484 509673472 3.8502249718 4.0124530792 3.6349391937 653 26.0800000000 0.0156941451 0.0083457586 0.0156941451 0.0092558804 0.0078880000 0.0005320000 0.0027310000 0.0000110000 0.0000140000 0.0023670000 14850253 96830484 509673472 3.8524494171 4.0122742653 3.6350941658 654 26.1200000000 0.0157734491 0.0083571159 0.0157734491 0.0092493468 0.0062980000 0.0004750000 0.0032060000 0.0000000000 0.0000050000 0.0011250000 14853029 96830484 509673472 3.8581812382 4.0131425858 3.6371054649 655 26.1600000000 0.0158333592 0.0083685300 0.0158333592 0.0092423676 0.0071850000 0.0005270000 0.0032610000 0.0000080000 0.0000070000 0.0015250000 14855805 96830484 509673472 3.8604347706 4.0125603676 3.6374981403 656 26.2000000000 0.0157724079 0.0083798164 0.0158333592 0.0092356880 0.0070560000 0.0005300000 0.0031590000 0.0000000000 0.0000090000 0.0012300000 14858581 96830484 509673472 3.8633534908 4.0129590034 3.6385252476 657 26.2400000000 0.0158385728 0.0083911692 0.0158385728 0.0092286844 0.0085340000 0.0006210000 0.0026270000 0.0000110000 0.0000090000 0.0024120000 14861357 96830484 509673472 3.8660042286 4.0129389763 3.6396667957 658 26.2800000000 0.0158748701 0.0084025426 0.0158748701 0.0092217824 0.0065100000 0.0005300000 0.0024740000 0.0000020000 0.0000100000 0.0012820000 14864133 96830484 509673472 3.8685946465 4.0127587318 3.6403064728 659 26.3200000000 0.0158784073 0.0084138868 0.0158784073 0.0092157725 0.0062790000 0.0004710000 0.0026460000 0.0000070000 0.0000060000 0.0014450000 14866909 96830484 509673472 3.8711502552 4.0132474899 3.6404359341 660 26.3600000000 0.0159071926 0.0084252403 0.0159071926 0.0092087820 0.0054030000 0.0004540000 0.0023330000 0.0000010000 0.0000050000 0.0011190000 14869685 96830484 509673472 3.8737256527 4.0128040314 3.6412777901 661 26.4000000000 0.0158843454 0.0084365249 0.0159071926 0.0092022876 0.0111510000 0.0006160000 0.0033630000 0.0000160000 0.0000140000 0.0027010000 14872461 96830484 509673472 3.8766860962 4.0124950409 3.6425945759 662 26.4400000000 0.0159462970 0.0084478690 0.0159462970 0.0091967618 0.0075100000 0.0005290000 0.0037220000 0.0000010000 0.0000090000 0.0012140000 14875237 96830484 509673472 3.8793816566 4.0127062798 3.6432461739 663 26.4800000000 0.0158643574 0.0084590552 0.0159462970 0.0091898432 0.0062250000 0.0004610000 0.0030350000 0.0000060000 0.0000060000 0.0013940000 14878013 96830484 509673472 3.8818502426 4.0120153427 3.6437849998 664 26.5200000000 0.0159961022 0.0084704062 0.0159961022 0.0091832621 0.0052480000 0.0004370000 0.0027150000 0.0000010000 0.0000040000 0.0010860000 14880789 96830484 509673472 3.8842239380 4.0110030174 3.6445667744 665 26.5600000000 0.0160394665 0.0084817883 0.0160394665 0.0091785546 0.0102880000 0.0006530000 0.0033430000 0.0000150000 0.0000140000 0.0027290000 14883565 96830484 509673472 3.8862645626 4.0094213486 3.6447055340 666 26.6000000000 0.0160844773 0.0084932037 0.0160844773 0.0091786459 0.0062900000 0.0005020000 0.0028300000 0.0000010000 0.0000070000 0.0011480000 14886341 96830484 509673472 3.8887872696 4.0088829994 3.6451537609 667 26.6400000000 0.0160055105 0.0085044665 0.0160844773 0.0091769116 0.0063760000 0.0004570000 0.0030110000 0.0000050000 0.0000040000 0.0014140000 14889117 96830484 509673472 3.8911771774 4.0080866814 3.6453042030 668 26.6800000000 0.0161166769 0.0085158621 0.0161166769 0.0091727758 0.0059820000 0.0004470000 0.0031460000 0.0000000000 0.0000140000 0.0010840000 14891893 96830484 509673472 3.8936004639 4.0075354576 3.6458182335 669 26.7200000000 0.0161483604 0.0085272709 0.0161483604 0.0091678667 0.0062090000 0.0004380000 0.0025660000 0.0000040000 0.0000040000 0.0020620000 14894669 96830484 509673472 3.8958582878 4.0064353943 3.6457901001 670 26.7600000000 0.0162294619 0.0085387667 0.0162294619 0.0091672654 0.0097470000 0.0006420000 0.0030730000 0.0000020000 0.0000150000 0.0015610000 14897445 96830484 509673472 3.8982191086 4.0061292648 3.6456155777 671 26.8000000000 0.0162816085 0.0085503059 0.0162816085 0.0091639528 0.0073450000 0.0005260000 0.0027610000 0.0000100000 0.0000090000 0.0016150000 14900221 96830484 509673472 3.9007954597 4.0064964294 3.6451978683 672 26.8400000000 0.0162693001 0.0085617925 0.0162816085 0.0091574016 0.0057420000 0.0004690000 0.0026550000 0.0000010000 0.0000050000 0.0011110000 14902997 96830484 509673472 3.9030208588 4.0051245689 3.6449878216 673 26.8800000000 0.0162841845 0.0085732671 0.0162841845 0.0091592749 0.0091000000 0.0006140000 0.0030460000 0.0000190000 0.0000140000 0.0024140000 14905773 96830484 509673472 3.9055225849 4.0043592453 3.6448345184 674 26.9200000000 0.0163738988 0.0085848408 0.0163738988 0.0091667571 0.0063500000 0.0004880000 0.0030380000 0.0000000000 0.0000060000 0.0011600000 14908549 96830484 509673472 3.9082708359 4.0051822662 3.6444673538 675 26.9600000000 0.0164746158 0.0085965293 0.0164746158 0.0091623806 0.0078020000 0.0006310000 0.0023450000 0.0000100000 0.0000090000 0.0016200000 14911325 96830484 509673472 3.9108574390 4.0052380562 3.6434798241 676 27.0000000000 0.0164079443 0.0086080847 0.0164746158 0.0091560443 0.0057210000 0.0005130000 0.0025010000 0.0000010000 0.0000070000 0.0011660000 14914101 96830484 509673472 3.9133288860 4.0038194656 3.6434247494 677 27.0400000000 0.0164818056 0.0086197150 0.0164818056 0.0091529364 0.0105810000 0.0006330000 0.0030530000 0.0000150000 0.0000160000 0.0027210000 14916877 96830484 509673472 3.9160349369 4.0038280487 3.6423349380 678 27.0800000000 0.0165487193 0.0086314097 0.0165487193 0.0091483635 0.0065400000 0.0005300000 0.0023320000 0.0000010000 0.0000100000 0.0013390000 14919653 96830484 509673472 3.9187850952 4.0035624504 3.6417520046 679 27.1200000000 0.0165347960 0.0086430494 0.0165487193 0.0091454425 0.0061890000 0.0004700000 0.0027630000 0.0000050000 0.0000050000 0.0014140000 14922429 96830484 509673472 3.9210298061 4.0030646324 3.6405317783 680 27.1600000000 0.0166453365 0.0086548175 0.0166453365 0.0091442961 0.0079340000 0.0006170000 0.0028980000 0.0000020000 0.0000150000 0.0013320000 14925205 96830484 509673472 3.9237952232 4.0036063194 3.6392002106 681 27.2000000000 0.0165913962 0.0086664718 0.0166453365 0.0091379569 0.0090820000 0.0006190000 0.0028870000 0.0000160000 0.0000140000 0.0024950000 14927981 96830484 509673472 3.9264323711 4.0034146309 3.6380779743 682 27.2400000000 0.0165776964 0.0086780718 0.0166453365 0.0091318787 0.0061990000 0.0005040000 0.0026520000 0.0000010000 0.0000070000 0.0011690000 14930757 96830484 509673472 3.9289863110 4.0030837059 3.6364638805 683 27.2800000000 0.0167214144 0.0086898483 0.0167214144 0.0091268707 0.0056210000 0.0004480000 0.0025850000 0.0000040000 0.0000030000 0.0014070000 14933533 96830484 509673472 3.9318430424 4.0032463074 3.6352069378 684 27.3200000000 0.0167899225 0.0087016905 0.0167899225 0.0091203633 0.0097090000 0.0006160000 0.0030850000 0.0000020000 0.0000150000 0.0016060000 14936309 96830484 509673472 3.9346659184 4.0031604767 3.6334941387 685 27.3600000000 0.0168480631 0.0087135830 0.0168480631 0.0091137680 0.0076620000 0.0004990000 0.0031110000 0.0000080000 0.0000070000 0.0021680000 14939085 96830484 509673472 3.9372920990 4.0013499260 3.6323838234 686 27.4000000000 0.0167596359 0.0087253120 0.0168480631 0.0091127052 0.0099690000 0.0006310000 0.0030900000 0.0000020000 0.0000150000 0.0015920000 14941861 96830484 509673472 3.9400277138 4.0003681183 3.6308779716 687 27.4400000000 0.0168160424 0.0087370889 0.0168480631 0.0091146041 0.0103090000 0.0006340000 0.0030520000 0.0000160000 0.0000140000 0.0018880000 14944637 96830484 509673472 3.9430689812 4.0005593300 3.6289010048 688 27.4800000000 0.0167756937 0.0087487729 0.0168480631 0.0091150900 0.0081900000 0.0006350000 0.0024650000 0.0000020000 0.0000170000 0.0016020000 14947413 96830484 509673472 3.9461212158 4.0004825592 3.6269652843 689 27.5200000000 0.0167928152 0.0087604479 0.0168480631 0.0091157125 0.0073490000 0.0004950000 0.0028120000 0.0000070000 0.0000050000 0.0021490000 14950189 96830484 509673472 3.9488456249 4.0001254082 3.6248118877 690 27.5600000000 0.0168799609 0.0087722153 0.0168799609 0.0091199245 0.0103370000 0.0006300000 0.0033820000 0.0000020000 0.0000160000 0.0015850000 14952965 96830484 509673472 3.9521305561 4.0010261536 3.6225483418 691 27.6000000000 0.0168792680 0.0087839476 0.0168799609 0.0091134454 0.0096990000 0.0006370000 0.0026630000 0.0000160000 0.0000140000 0.0018770000 14955741 96830484 509673472 3.9554092884 4.0019860268 3.6200997829 692 27.6400000000 0.0169462748 0.0087957429 0.0169462748 0.0091101690 0.0067620000 0.0005030000 0.0031250000 0.0000010000 0.0000080000 0.0012260000 14958517 96830484 509673472 3.9584820271 4.0021681786 3.6175932884 693 27.6800000000 0.0169418436 0.0088074977 0.0169462748 0.0091065963 0.0079530000 0.0005330000 0.0027670000 0.0000100000 0.0000100000 0.0022310000 14961293 96830484 509673472 3.9614777565 4.0013718605 3.6157867908 694 27.7200000000 0.0169833489 0.0088192785 0.0169833489 0.0091000253 0.0057780000 0.0004770000 0.0026070000 0.0000010000 0.0000060000 0.0011090000 14964069 96830484 509673472 3.9644739628 4.0011210442 3.6134922504 695 27.7600000000 0.0169903003 0.0088310353 0.0169903003 0.0090936789 0.0059020000 0.0004400000 0.0030100000 0.0000040000 0.0000040000 0.0013720000 14966845 96830484 509673472 3.9674949646 4.0006041527 3.6116149426 696 27.8000000000 0.0169022530 0.0088426319 0.0169903003 0.0090891371 0.0078580000 0.0005300000 0.0027790000 0.0000020000 0.0000110000 0.0013260000 14969621 96830484 509673472 3.9703443050 4.0001282692 3.6099948883 697 27.8400000000 0.0168316457 0.0088540939 0.0169903003 0.0090864132 0.0075480000 0.0005560000 0.0026940000 0.0000060000 0.0000060000 0.0021130000 14972397 96830484 509673472 3.9761075974 4.0009999275 3.6051857471 698 27.8800000000 0.0169543866 0.0088656989 0.0169903003 0.0090798984 0.0057980000 0.0004890000 0.0030060000 0.0000000000 0.0000050000 0.0010920000 14975173 96830484 509673472 3.9786114693 4.0000205040 3.6035563946 699 27.9200000000 0.0169219431 0.0088772243 0.0169903003 0.0090972542 0.0080150000 0.0005300000 0.0027710000 0.0000100000 0.0000090000 0.0015720000 14977949 96830484 509673472 3.9831759930 3.9997327328 3.5995025635 700 27.9600000000 0.0168548636 0.0088886209 0.0169903003 0.0090918269 0.0059230000 0.0004950000 0.0024190000 0.0000010000 0.0000060000 0.0011150000 14980725 96830484 509673472 3.9852631092 3.9990079403 3.5974504948 701 28.0000000000 0.0168973096 0.0089000456 0.0169903003 0.0090885476 0.0065250000 0.0004570000 0.0026160000 0.0000050000 0.0000060000 0.0020780000 14983501 96830484 509673472 3.9874324799 3.9980278015 3.5961964130 702 28.0400000000 0.0168592688 0.0089113835 0.0169903003 0.0090936066 0.0085330000 0.0006160000 0.0029080000 0.0000020000 0.0000150000 0.0015110000 14986277 96830484 509673472 3.9893696308 3.9970741272 3.5946447849 703 28.0800000000 0.0166851897 0.0089224416 0.0169903003 0.0091120267 0.0084630000 0.0005030000 0.0047790000 0.0000060000 0.0000060000 0.0013840000 14989053 96830484 509673472 3.9915194511 3.9971630573 3.5926487446 704 28.1200000000 0.0166506991 0.0089334192 0.0169903003 0.0091181390 0.0071350000 0.0005300000 0.0030420000 0.0000010000 0.0000100000 0.0011850000 14991829 96830484 509673472 3.9939184189 3.9972243309 3.5911402702 705 28.1600000000 0.0167326108 0.0089444819 0.0169903003 0.0091183714 0.0065350000 0.0004730000 0.0022100000 0.0000060000 0.0000050000 0.0021090000 14994605 96830484 509673472 3.9958596230 3.9964265823 3.5897872448 706 28.2000000000 0.0166614186 0.0089554124 0.0169903003 0.0091240321 0.0074760000 0.0005310000 0.0028940000 0.0000010000 0.0000100000 0.0013130000 14997381 96830484 509673472 3.9979922771 3.9959099293 3.5884470940 707 28.2400000000 0.0166965686 0.0089663617 0.0169903003 0.0091287950 0.0066270000 0.0004780000 0.0030740000 0.0000060000 0.0000050000 0.0013990000 15000157 96830484 509673472 4.0003838539 3.9967594147 3.5868268013 708 28.2800000000 0.0166876353 0.0089772675 0.0169903003 0.0091225053 0.0053840000 0.0004490000 0.0024660000 0.0000010000 0.0000040000 0.0010770000 15002933 96830484 509673472 4.0029077530 3.9969685078 3.5852739811 709 28.3200000000 0.0167241432 0.0089881939 0.0169903003 0.0091161800 0.0063090000 0.0004440000 0.0025810000 0.0000040000 0.0000040000 0.0020330000 15005709 96830484 509673472 4.0050687790 3.9959683418 3.5844762325 710 28.3600000000 0.0167455729 0.0089991198 0.0169903003 0.0091139033 0.0052120000 0.0004360000 0.0025740000 0.0000010000 0.0000040000 0.0010590000 15008485 96830484 509673472 4.0074887276 3.9955897331 3.5838191509 711 28.4000000000 0.0167928282 0.0090100814 0.0169903003 0.0091119755 0.0053560000 0.0004300000 0.0024280000 0.0000040000 0.0000040000 0.0013600000 15011261 96830484 509673472 4.0100722313 3.9962811470 3.5824830532 712 28.4400000000 0.0167506300 0.0090209530 0.0169903003 0.0091055795 0.0051960000 0.0004290000 0.0025700000 0.0000010000 0.0000040000 0.0010590000 15014037 96830484 509673472 4.0124597549 3.9953775406 3.5821871758 713 28.4800000000 0.0167033747 0.0090317278 0.0169903003 0.0091001493 0.0060250000 0.0004320000 0.0024310000 0.0000040000 0.0000040000 0.0020160000 15016813 96830484 509673472 4.0147824287 3.9945023060 3.5818357468 714 28.5200000000 0.0166439749 0.0090423892 0.0169903003 0.0090984130 0.0049480000 0.0004330000 0.0022950000 0.0000000000 0.0000050000 0.0010590000 15019589 96830484 509673472 4.0173902512 3.9948959351 3.5810341835 715 28.5600000000 0.0166603960 0.0090530437 0.0169903003 0.0090929621 0.0053750000 0.0004330000 0.0024460000 0.0000040000 0.0000040000 0.0013450000 15022365 96830484 509673472 4.0204181671 3.9959123135 3.5804514885 716 28.6000000000 0.0166616514 0.0090636703 0.0169903003 0.0090880400 0.0046540000 0.0004330000 0.0020210000 0.0000000000 0.0000030000 0.0010540000 15025141 96830484 509673472 4.0233078003 3.9963426590 3.5802481174 717 28.6400000000 0.0166614093 0.0090742669 0.0169903003 0.0090848249 0.0061550000 0.0004330000 0.0025750000 0.0000040000 0.0000040000 0.0019850000 15027917 96830484 509673472 4.0261440277 3.9960441589 3.5801043510 718 28.6800000000 0.0166684706 0.0090848437 0.0169903003 0.0090788307 0.0047810000 0.0004320000 0.0021570000 0.0000000000 0.0000040000 0.0010480000 15030693 96830484 509673472 4.0288929939 3.9959104061 3.5801808834 719 28.7200000000 0.0166097060 0.0090953095 0.0169903003 0.0090725364 0.0053610000 0.0004330000 0.0024460000 0.0000040000 0.0000030000 0.0013250000 15033469 96830484 509673472 4.0317854881 3.9954802990 3.5805978775 720 28.7600000000 0.0165477246 0.0091056601 0.0169903003 0.0090689772 0.0048160000 0.0004320000 0.0021570000 0.0000000000 0.0000040000 0.0010570000 15036245 96830484 509673472 4.0349979401 3.9951460361 3.5813167095 721 28.8000000000 0.0165125523 0.0091159331 0.0169903003 0.0090705066 0.0057430000 0.0004310000 0.0021650000 0.0000040000 0.0000030000 0.0019850000 15039021 96830484 509673472 4.0383090973 3.9963750839 3.5813117027 722 28.8400000000 0.0165402591 0.0091262161 0.0169903003 0.0090643123 0.0052090000 0.0004330000 0.0025780000 0.0000000000 0.0000050000 0.0010440000 15041797 96830484 509673472 4.0418839455 3.9967625141 3.5820121765 723 28.8800000000 0.0165148564 0.0091364356 0.0169903003 0.0090583731 0.0052240000 0.0004330000 0.0023000000 0.0000040000 0.0000040000 0.0013270000 15044573 96830484 509673472 4.0452747345 3.9969067574 3.5827121735 724 28.9200000000 0.0165289044 0.0091466462 0.0169903003 0.0090522044 0.0052210000 0.0004320000 0.0025840000 0.0000000000 0.0000040000 0.0010400000 15047349 96830484 509673472 4.0487174988 3.9970920086 3.5836174488 725 28.9600000000 0.0164402574 0.0091567063 0.0169903003 0.0090460601 0.0055760000 0.0004300000 0.0020200000 0.0000040000 0.0000040000 0.0019660000 15050125 96830484 509673472 4.0523982048 3.9969925880 3.5847866535 726 29.0000000000 0.0164069403 0.0091666929 0.0169903003 0.0090410676 0.0051340000 0.0004310000 0.0024510000 0.0000000000 0.0000040000 0.0010530000 15052901 96830484 509673472 4.0556130409 3.9968621731 3.5855660439 727 29.0400000000 0.0164136086 0.0091766611 0.0169903003 0.0090416106 0.0055040000 0.0004360000 0.0025820000 0.0000040000 0.0000040000 0.0013090000 15055677 96830484 509673472 4.0596084595 3.9978387356 3.5867516994 728 29.0800000000 0.0163569972 0.0091865242 0.0169903003 0.0090359364 0.0049440000 0.0004320000 0.0023100000 0.0000000000 0.0000040000 0.0010310000 15058453 96830484 509673472 4.0634560585 3.9985129833 3.5878422260 729 29.1200000000 0.0163225029 0.0091963129 0.0169903003 0.0090298158 0.0061720000 0.0004330000 0.0025800000 0.0000040000 0.0000030000 0.0019820000 15061229 96830484 509673472 4.0669512749 3.9978497028 3.5893151760 730 29.1600000000 0.0162575822 0.0092059859 0.0169903003 0.0090329195 0.0046970000 0.0004320000 0.0020300000 0.0000010000 0.0000040000 0.0010450000 15064005 96830484 509673472 4.0702633858 3.9976873398 3.5904924870 731 29.2000000000 0.0163526312 0.0092157624 0.0169903003 0.0090374290 0.0050600000 0.0004320000 0.0021480000 0.0000050000 0.0000040000 0.0013040000 15066781 96830484 509673472 4.0742068291 3.9983365536 3.5920209885 732 29.2400000000 0.0163545124 0.0092255148 0.0169903003 0.0090352416 0.0049580000 0.0004350000 0.0022850000 0.0000000000 0.0000040000 0.0010370000 15069557 96830484 509673472 4.0777616501 3.9985752106 3.5932965279 733 29.2800000000 0.0163170584 0.0092351895 0.0169903003 0.0090322980 0.0055900000 0.0004310000 0.0020110000 0.0000040000 0.0000040000 0.0019660000 15072333 96830484 509673472 4.0811915398 3.9989113808 3.5941073895 734 29.3200000000 0.0162094459 0.0092446912 0.0169903003 0.0090274916 0.0053570000 0.0004290000 0.0027130000 0.0000000000 0.0000040000 0.0010320000 15075109 96830484 509673472 4.0847206116 3.9990291595 3.5953485966 735 29.3600000000 0.0162765738 0.0092542584 0.0169903003 0.0090215112 0.0054870000 0.0004290000 0.0025730000 0.0000040000 0.0000030000 0.0012970000 15077885 96830484 509673472 4.0878863335 3.9989535809 3.5964484215 736 29.4000000000 0.0161985923 0.0092636936 0.0169903003 0.0090154815 0.0046700000 0.0004310000 0.0020230000 0.0000010000 0.0000040000 0.0010350000 15080661 96830484 509673472 4.0908927917 3.9984714985 3.5977473259 737 29.4400000000 0.0162367672 0.0092731551 0.0169903003 0.0090111745 0.0070190000 0.0004320000 0.0034140000 0.0000040000 0.0000040000 0.0019690000 15083437 96830484 509673472 4.0938096046 3.9984633923 3.5987279415 738 29.4800000000 0.0161605775 0.0092824876 0.0169903003 0.0090066764 0.0048140000 0.0004290000 0.0021640000 0.0000010000 0.0000050000 0.0010260000 15086213 96830484 509673472 4.0968647003 3.9987108707 3.5998208523 739 29.5200000000 0.0161306597 0.0092917544 0.0169903003 0.0090007133 0.0050610000 0.0004300000 0.0021530000 0.0000040000 0.0000040000 0.0012860000 15088989 96830484 509673472 4.0995078087 3.9981131554 3.6009962559 740 29.5600000000 0.0160528924 0.0093008911 0.0169903003 0.0089981471 0.0052200000 0.0004300000 0.0025730000 0.0000000000 0.0000040000 0.0010330000 15091765 96830484 509673472 4.1018810272 3.9971942902 3.6021871567 741 29.6000000000 0.0160336625 0.0093099772 0.0169903003 0.0090056641 0.0061540000 0.0004330000 0.0025740000 0.0000040000 0.0000040000 0.0019280000 15094541 96830484 509673472 4.1041231155 3.9970271587 3.6031417847 742 29.6400000000 0.0159987230 0.0093189916 0.0169903003 0.0090079038 0.0052340000 0.0004350000 0.0025750000 0.0000000000 0.0000050000 0.0010170000 15097317 96830484 509673472 4.1068592072 3.9972946644 3.6041314602 743 29.6800000000 0.0159366708 0.0093278983 0.0169903003 0.0090048178 0.0055130000 0.0004320000 0.0025870000 0.0000040000 0.0000040000 0.0012790000 15100093 96830484 509673472 4.1091766357 3.9973835945 3.6049175262 744 29.7200000000 0.0159675423 0.0093368226 0.0169903003 0.0089997535 0.0048350000 0.0004300000 0.0021730000 0.0000010000 0.0000040000 0.0010210000 15102869 96830484 509673472 4.1113619804 3.9972014427 3.6057868004 745 29.7600000000 0.0159581248 0.0093457103 0.0169903003 0.0089959976 0.0057710000 0.0004300000 0.0021840000 0.0000040000 0.0000030000 0.0019500000 15105645 96830484 509673472 4.1136898994 3.9979612827 3.6064364910 746 29.8000000000 0.0159792434 0.0093546024 0.0169903003 0.0089919821 0.0052380000 0.0004340000 0.0025850000 0.0000000000 0.0000040000 0.0010200000 15108421 96830484 509673472 4.1156768799 3.9985971451 3.6067073345 747 29.8400000000 0.0159925688 0.0093634886 0.0169903003 0.0089923925 0.0049290000 0.0004320000 0.0020220000 0.0000040000 0.0000040000 0.0012770000 15111197 96830484 509673472 4.1173191071 3.9975457191 3.6076755524 748 29.8800000000 0.0158561040 0.0093721685 0.0169903003 0.0089999591 0.0053730000 0.0004290000 0.0027270000 0.0000000000 0.0000040000 0.0010070000 15113973 96830484 509673472 4.1212244034 3.9976298809 3.6095087528 749 29.9200000000 0.0159507375 0.0093809517 0.0169903003 0.0089939802 0.0061850000 0.0004340000 0.0025870000 0.0000050000 0.0000040000 0.0019090000 15116749 96830484 509673472 4.1233825684 3.9981536865 3.6102311611 750 29.9600000000 0.0158811472 0.0093896186 0.0169903003 0.0089883999 0.0052440000 0.0004330000 0.0025830000 0.0000010000 0.0000040000 0.0010110000 15119525 96830484 509673472 4.1249599457 3.9980945587 3.6107819080 751 30.0000000000 0.0158611313 0.0093982358 0.0169903003 0.0089824326 0.0054440000 0.0004300000 0.0025270000 0.0000040000 0.0000040000 0.0012760000 15122301 96830484 509673472 4.1269149780 3.9986436367 3.6113040447 752 30.0400000000 0.0159220323 0.0094069110 0.0169903003 0.0089789249 0.0048140000 0.0004300000 0.0021640000 0.0000000000 0.0000040000 0.0010040000 15125077 96830484 509673472 4.1289467812 3.9992005825 3.6118242741 753 30.0800000000 0.0158955529 0.0094155281 0.0169903003 0.0089761996 0.0057120000 0.0004330000 0.0021590000 0.0000040000 0.0000030000 0.0019030000 15127853 96830484 509673472 4.1307454109 3.9987738132 3.6124880314 754 30.1200000000 0.0159011483 0.0094241297 0.0169903003 0.0089703109 0.0057020000 0.0004300000 0.0030220000 0.0000010000 0.0000040000 0.0010140000 15130629 96830484 509673472 4.1327414513 3.9990758896 3.6129260063 755 30.1600000000 0.0158150289 0.0094325945 0.0169903003 0.0089651425 0.0056350000 0.0004340000 0.0027190000 0.0000040000 0.0000040000 0.0012600000 15133405 96830484 509673472 4.1345181465 3.9989380836 3.6134374142 756 30.2000000000 0.0158286225 0.0094410548 0.0169903003 0.0089593724 0.0055730000 0.0004950000 0.0025890000 0.0000010000 0.0000040000 0.0010220000 15136181 96830484 509673472 4.1360673904 3.9980158806 3.6142153740 757 30.2400000000 0.0157714654 0.0094494173 0.0169903003 0.0089598859 0.0074590000 0.0005440000 0.0026890000 0.0000080000 0.0000080000 0.0020810000 15138957 96830484 509673472 4.1379103661 3.9971349239 3.6150729656 758 30.2800000000 0.0157906655 0.0094577831 0.0169903003 0.0089775967 0.0052120000 0.0004620000 0.0022050000 0.0000010000 0.0000050000 0.0010250000 15141733 96830484 509673472 4.1398220062 3.9973390102 3.6152744293 759 30.3200000000 0.0157272257 0.0094660432 0.0169903003 0.0089900938 0.0056580000 0.0004410000 0.0025890000 0.0000040000 0.0000040000 0.0012740000 15144509 96830484 509673472 4.1422495842 3.9976363182 3.6156766415 760 30.3600000000 0.0156821571 0.0094742223 0.0169903003 0.0089937293 0.0050170000 0.0004440000 0.0021730000 0.0000010000 0.0000040000 0.0010130000 15147285 96830484 509673472 4.1443300247 3.9973049164 3.6162600517 761 30.4000000000 0.0156475753 0.0094823345 0.0169903003 0.0090026449 0.0063150000 0.0004430000 0.0025850000 0.0000040000 0.0000040000 0.0019050000 15150061 96830484 509673472 4.1463174820 3.9969334602 3.6164901257 762 30.4400000000 0.0156663023 0.0094904499 0.0169903003 0.0090183984 0.0048290000 0.0004400000 0.0020280000 0.0000000000 0.0000040000 0.0010090000 15152837 96830484 509673472 4.1487693787 3.9970455170 3.6171584129 763 30.4800000000 0.0155923758 0.0094984472 0.0169903003 0.0090286743 0.0057890000 0.0004410000 0.0027190000 0.0000040000 0.0000040000 0.0012590000 15155613 96830484 509673472 4.1513648033 3.9972026348 3.6174004078 764 30.5200000000 0.0156350918 0.0095064795 0.0169903003 0.0090367381 0.0054170000 0.0004440000 0.0025900000 0.0000010000 0.0000040000 0.0010120000 15158389 96830484 509673472 4.1538362503 3.9969065189 3.6178445816 765 30.5600000000 0.0156443361 0.0095145028 0.0169903003 0.0090540866 0.0057340000 0.0004440000 0.0020240000 0.0000050000 0.0000030000 0.0018990000 15161165 96830484 509673472 4.1561641693 3.9967706203 3.6181838512 766 30.6000000000 0.0155744683 0.0095224140 0.0169903003 0.0090691315 0.0049980000 0.0004420000 0.0021730000 0.0000010000 0.0000050000 0.0010050000 15163941 96830484 509673472 4.1586418152 3.9974119663 3.6181190014 767 30.6400000000 0.0155210244 0.0095302349 0.0169903003 0.0090695187 0.0057830000 0.0004410000 0.0027270000 0.0000040000 0.0000050000 0.0012530000 15166717 96830484 509673472 4.1612501144 3.9978361130 3.6180377007 768 30.6800000000 0.0155911054 0.0095381266 0.0169903003 0.0090676197 0.0104550000 0.0006330000 0.0030800000 0.0000020000 0.0000150000 0.0014500000 15169493 96830484 509673472 4.1633381844 3.9976294041 3.6180634499 769 30.7200000000 0.0156378895 0.0095460587 0.0169903003 0.0090695665 0.0093440000 0.0006070000 0.0029230000 0.0000140000 0.0000130000 0.0022610000 15172269 96830484 509673472 4.1656694412 3.9981911182 3.6179127693 770 30.7600000000 0.0155408764 0.0095538442 0.0169903003 0.0090655146 0.0062370000 0.0004920000 0.0026720000 0.0000010000 0.0000060000 0.0010510000 15175045 96830484 509673472 4.1678705215 3.9986195564 3.6176595688 771 30.8000000000 0.0154169537 0.0095614487 0.0169903003 0.0090597877 0.0074980000 0.0005300000 0.0029470000 0.0000100000 0.0000090000 0.0013450000 15177821 96830484 509673472 4.1697010994 3.9977688789 3.6175527573 772 30.8400000000 0.0154023133 0.0095690146 0.0169903003 0.0090632667 0.0060540000 0.0004710000 0.0027940000 0.0000010000 0.0000050000 0.0010220000 15180597 96830484 509673472 4.1712937355 3.9976685047 3.6172537804 773 30.8800000000 0.0154174184 0.0095765805 0.0169903003 0.0090632945 0.0065270000 0.0004460000 0.0026190000 0.0000050000 0.0000050000 0.0019100000 15183373 96830484 509673472 4.1734800339 3.9982471466 3.6169912815 774 30.9200000000 0.0154362824 0.0095841511 0.0169903003 0.0090578242 0.0097500000 0.0006180000 0.0031250000 0.0000020000 0.0000170000 0.0014360000 15186149 96830484 509673472 4.1753573418 3.9982953072 3.6168065071 775 30.9600000000 0.0154524585 0.0095917231 0.0169903003 0.0090521333 0.0079250000 0.0005000000 0.0040000000 0.0000070000 0.0000060000 0.0012940000 15188925 96830484 509673472 4.1769680977 3.9986500740 3.6164612770 776 31.0000000000 0.0155718680 0.0095994295 0.0169903003 0.0090494013 0.0055680000 0.0004570000 0.0025720000 0.0000010000 0.0000040000 0.0010060000 15191701 96830484 509673472 4.1788268089 3.9988303185 3.6164202690 777 31.0400000000 0.0155286817 0.0096070605 0.0169903003 0.0090454850 0.0103060000 0.0006210000 0.0031120000 0.0000150000 0.0000140000 0.0025200000 15194477 96830484 509673472 4.1803407669 3.9986376762 3.6163258553 778 31.0800000000 0.0155780576 0.0096147353 0.0169903003 0.0090401666 0.0065190000 0.0005010000 0.0027990000 0.0000010000 0.0000060000 0.0010510000 15197253 96830484 509673472 4.1818637848 3.9997744560 3.6156117916 779 31.1200000000 0.0156867430 0.0096225299 0.0169903003 0.0090511057 0.0063600000 0.0004540000 0.0032130000 0.0000040000 0.0000040000 0.0012770000 15200029 96830484 509673472 4.1830878258 4.0006713867 3.6149191856 780 31.1600000000 0.0157690179 0.0096304100 0.0169903003 0.0090857929 0.0075690000 0.0005320000 0.0027800000 0.0000010000 0.0000100000 0.0012250000 15202805 96830484 509673472 4.1840834618 4.0009980202 3.6146025658 781 31.2000000000 0.0157293808 0.0096382192 0.0169903003 0.0091206280 0.0081380000 0.0005280000 0.0029370000 0.0000070000 0.0000070000 0.0020510000 15205581 96830484 509673472 4.1848211288 4.0010776520 3.6140453815 782 31.2400000000 0.0157102589 0.0096459839 0.0169903003 0.0091526913 0.0058800000 0.0004550000 0.0027830000 0.0000010000 0.0000050000 0.0010160000 15208357 96830484 509673472 4.1856827736 4.0014009476 3.6136643887 783 31.2800000000 0.0157331061 0.0096537580 0.0169903003 0.0091832726 0.0088840000 0.0005700000 0.0032270000 0.0000100000 0.0000100000 0.0014740000 15211133 96830484 509673472 4.1864972115 4.0014228821 3.6133408546 784 31.3200000000 0.0156309530 0.0096613820 0.0169903003 0.0091987811 0.0064390000 0.0004980000 0.0027080000 0.0000010000 0.0000060000 0.0010550000 15213909 96830484 509673472 4.1871047020 4.0010824203 3.6131210327 785 31.3600000000 0.0156819150 0.0096690515 0.0169903003 0.0091968671 0.0076270000 0.0005110000 0.0030840000 0.0000060000 0.0000050000 0.0019350000 15216685 96830484 509673472 4.1878504753 4.0008606911 3.6130797863 786 31.4000000000 0.0156706590 0.0096766871 0.0169903003 0.0091911907 0.0082110000 0.0006650000 0.0025040000 0.0000020000 0.0000150000 0.0014420000 15219461 96830484 509673472 4.1888799667 4.0016269684 3.6127150059 787 31.4400000000 0.0157086849 0.0096843517 0.0169903003 0.0091915498 0.0065910000 0.0004970000 0.0022980000 0.0000080000 0.0000070000 0.0013610000 15222237 96830484 509673472 4.1898121834 4.0023021698 3.6124892235 788 31.4800000000 0.0156663209 0.0096919430 0.0169903003 0.0091945063 0.0071230000 0.0005480000 0.0027830000 0.0000010000 0.0000070000 0.0011150000 15225013 96830484 509673472 4.1907324791 4.0027246475 3.6124317646 789 31.5200000000 0.0156441387 0.0096994870 0.0169903003 0.0091986132 0.0070590000 0.0004700000 0.0028130000 0.0000070000 0.0000050000 0.0019370000 15227789 96830484 509673472 4.1917510033 4.0037722588 3.6121416092 790 31.5600000000 0.0156354140 0.0097070008 0.0169903003 0.0092285130 0.0082330000 0.0006460000 0.0024760000 0.0000020000 0.0000150000 0.0014800000 15230565 96830484 509673472 4.1925983429 4.0045433044 3.6120555401 791 31.6000000000 0.0157395005 0.0097146272 0.0169903003 0.0092630041 0.0065090000 0.0004920000 0.0025520000 0.0000060000 0.0000050000 0.0013120000 15233341 96830484 509673472 4.1936140060 4.0048646927 3.6120412350 792 31.6400000000 0.0157471541 0.0097222441 0.0169903003 0.0092744946 0.0092790000 0.0006160000 0.0028080000 0.0000020000 0.0000150000 0.0014760000 15236117 96830484 509673472 4.1947121620 4.0053706169 3.6122016907 793 31.6800000000 0.0157881863 0.0097298934 0.0169903003 0.0092840469 0.0075020000 0.0005000000 0.0028640000 0.0000080000 0.0000060000 0.0019830000 15238893 96830484 509673472 4.1954832077 4.0061883926 3.6121244431 794 31.7200000000 0.0157453902 0.0097374696 0.0169903003 0.0093060918 0.0073390000 0.0005280000 0.0027790000 0.0000010000 0.0000100000 0.0012270000 15241669 96830484 509673472 4.1964182854 4.0071444511 3.6121900082 795 31.7600000000 0.0156973377 0.0097449663 0.0169903003 0.0093351208 0.0063920000 0.0004700000 0.0028140000 0.0000050000 0.0000040000 0.0012870000 15244445 96830484 509673472 4.1971507072 4.0076355934 3.6125578880 796 31.8000000000 0.0157665685 0.0097525311 0.0169903003 0.0093680523 0.0056700000 0.0004480000 0.0026270000 0.0000010000 0.0000050000 0.0010220000 15247221 96830484 509673472 4.1978025436 4.0085649490 3.6127574444 797 31.8400000000 0.0156926773 0.0097599843 0.0169903003 0.0094485085 0.0107770000 0.0006210000 0.0029510000 0.0000150000 0.0000140000 0.0025380000 15249997 96830484 509673472 4.1985812187 4.0094118118 3.6130940914 798 31.8800000000 0.0158680454 0.0097676385 0.0169903003 0.0095481983 0.0060740000 0.0005020000 0.0022770000 0.0000010000 0.0000070000 0.0011000000 15252773 96830484 509673472 4.1987667084 4.0098724365 3.6132066250 799 31.9200000000 0.0158529002 0.0097752546 0.0169903003 0.0096027294 0.0060410000 0.0004560000 0.0024870000 0.0000050000 0.0000050000 0.0012980000 15255549 96830484 509673472 4.1993236542 4.0101466179 3.6135554314 800 31.9600000000 0.0157573745 0.0097827322 0.0169903003 0.0096222666 0.0057840000 0.0004470000 0.0027580000 0.0000000000 0.0000050000 0.0010200000 15258325 96830484 509673472 4.1998567581 4.0102934837 3.6137888432 801 32.0000000000 0.0157536883 0.0097901866 0.0169903003 0.0096254082 0.0106650000 0.0006160000 0.0029110000 0.0000150000 0.0000130000 0.0025340000 15261101 96830484 509673472 4.2006192207 4.0105156898 3.6143636703 802 32.0400000000 0.0157842450 0.0097976605 0.0169903003 0.0096277156 0.0063820000 0.0005040000 0.0025530000 0.0000010000 0.0000080000 0.0010850000 15263877 96830484 509673472 4.2013912201 4.0107650757 3.6147758961 803 32.0800000000 0.0157903302 0.0098051233 0.0169903003 0.0096261484 0.0057350000 0.0004610000 0.0023470000 0.0000060000 0.0000050000 0.0013300000 15266653 96830484 509673472 4.2022290230 4.0111441612 3.6152093410 804 32.1199999990 0.0158738289 0.0098126715 0.0169903003 0.0096250297 0.0053800000 0.0004390000 0.0026030000 0.0000000000 0.0000040000 0.0010210000 15269429 96830484 509673472 4.2029447556 4.0114541054 3.6158754826 805 32.1600000000 0.0158085227 0.0098201197 0.0169903003 0.0096258920 0.0111280000 0.0006190000 0.0024840000 0.0000150000 0.0000140000 0.0025730000 15272205 96830484 509673472 4.2035741806 4.0116257668 3.6163678169 806 32.2000000000 0.0158483684 0.0098275990 0.0169903003 0.0096250706 0.0069230000 0.0005380000 0.0028540000 0.0000010000 0.0000080000 0.0011300000 15274981 96830484 509673472 4.2041664124 4.0116176605 3.6170144081 807 32.2400000000 0.0158813912 0.0098351006 0.0169903003 0.0096200500 0.0056440000 0.0004630000 0.0022220000 0.0000050000 0.0000050000 0.0012940000 15277757 96830484 509673472 4.2050442696 4.0118179321 3.6175787449 808 32.2800000000 0.0159378201 0.0098426534 0.0169903003 0.0096148932 0.0073410000 0.0005300000 0.0029300000 0.0000000000 0.0000080000 0.0011060000 15280533 96830484 509673472 4.2055883408 4.0120744705 3.6181430817 809 32.3200000000 0.0158913229 0.0098501301 0.0169903003 0.0096110699 0.0081730000 0.0005330000 0.0027900000 0.0000080000 0.0000070000 0.0020740000 15283309 96830484 509673472 4.2063288689 4.0121665001 3.6187741756 810 32.3600000000 0.0159261003 0.0098576313 0.0169903003 0.0096076659 0.0060870000 0.0004710000 0.0027890000 0.0000000000 0.0000050000 0.0010460000 15286085 96830484 509673472 4.2069358826 4.0120267868 3.6196029186 811 32.4000000000 0.0159870982 0.0098651893 0.0169903003 0.0096019706 0.0057620000 0.0004380000 0.0026140000 0.0000050000 0.0000040000 0.0012900000 15288861 96830484 509673472 4.2077002525 4.0119857788 3.6203908920 812 32.4399999990 0.0160080418 0.0098727543 0.0169903003 0.0095963019 0.0053140000 0.0004330000 0.0026030000 0.0000010000 0.0000040000 0.0010220000 15291637 96830484 509673472 4.2084736824 4.0118441582 3.6212878227 813 32.4800000000 0.0160618331 0.0098803670 0.0169903003 0.0095912170 0.0114120000 0.0006150000 0.0029340000 0.0000150000 0.0000130000 0.0025350000 15294413 96830484 509673472 4.2094049454 4.0120425224 3.6220352650 814 32.5200000000 0.0161190815 0.0098880313 0.0169903003 0.0095883302 0.0070730000 0.0005050000 0.0031260000 0.0000010000 0.0000230000 0.0011400000 15297189 96830484 509673472 4.2101454735 4.0118994713 3.6230397224 815 32.5600000000 0.0162018798 0.0098957783 0.0169903003 0.0095903112 0.0060090000 0.0004630000 0.0026300000 0.0000050000 0.0000050000 0.0012860000 15299965 96830484 509673472 4.2109308243 4.0118904114 3.6240491867 816 32.6000000000 0.0161982719 0.0099035020 0.0169903003 0.0095928746 0.0053030000 0.0004490000 0.0025860000 0.0000000000 0.0000030000 0.0009990000 15302741 96830484 509673472 4.2117071152 4.0120863914 3.6248600483 817 32.6400000000 0.0162200388 0.0099112333 0.0169903003 0.0095950319 0.0108770000 0.0006170000 0.0038310000 0.0000160000 0.0000140000 0.0025250000 15305517 96830484 509673472 4.2123727798 4.0119895935 3.6258442402 818 32.6800000000 0.0163009576 0.0099190447 0.0169903003 0.0095985671 0.0060460000 0.0005010000 0.0022590000 0.0000010000 0.0000060000 0.0010590000 15308293 96830484 509673472 4.2130494118 4.0120539665 3.6267864704 819 32.7200000000 0.0162820071 0.0099268139 0.0169903003 0.0096002689 0.0059930000 0.0004580000 0.0026230000 0.0000040000 0.0000040000 0.0012780000 15311069 96830484 509673472 4.2135791779 4.0119571686 3.6278717518 820 32.7599999990 0.0163568724 0.0099346555 0.0169903003 0.0096034036 0.0054710000 0.0004390000 0.0025940000 0.0000010000 0.0000050000 0.0010150000 15313845 96830484 509673472 4.2137522697 4.0118045807 3.6287579536 821 32.7999999990 0.0162820686 0.0099423868 0.0169903003 0.0096067588 0.0059620000 0.0004380000 0.0021730000 0.0000040000 0.0000040000 0.0019190000 15316621 96830484 509673472 4.2139391899 4.0116453171 3.6295211315 822 32.8400000000 0.0163353011 0.0099501640 0.0169903003 0.0096100630 0.0107750000 0.0006430000 0.0029290000 0.0000020000 0.0000150000 0.0014800000 15319397 96830484 509673472 4.2138576508 4.0111589432 3.6304428577 823 32.8800000000 0.0162733011 0.0099578471 0.0169903003 0.0096212653 0.0110190000 0.0006380000 0.0029100000 0.0000160000 0.0000160000 0.0017270000 15322173 96830484 509673472 4.2141532898 4.0107641220 3.6316940784 824 32.9200000000 0.0162571650 0.0099654919 0.0169903003 0.0096300820 0.0062970000 0.0006730000 0.0029090000 0.0000010000 0.0000040000 0.0010360000 15324949 96830484 509673472 4.2140426636 4.0102381706 3.6326153278 825 32.9600000000 0.0161794685 0.0099730240 0.0169903003 0.0096412461 0.0057850000 0.0004480000 0.0021560000 0.0000040000 0.0000030000 0.0019320000 15327725 96830484 509673472 4.2140278816 4.0098257065 3.6336069107 826 33.0000000000 0.0161475576 0.0099804992 0.0169903003 0.0096521923 0.0052220000 0.0004330000 0.0025230000 0.0000000000 0.0000030000 0.0010220000 15330501 96830484 509673472 4.2137975693 4.0097675323 3.6342086792 827 33.0400000000 0.0161485933 0.0099879576 0.0169903003 0.0096568611 0.0054230000 0.0004510000 0.0021850000 0.0000040000 0.0000040000 0.0013040000 15333277 96830484 509673472 4.2136120796 4.0093722343 3.6351051331 828 33.0800000000 0.0161132365 0.0099953553 0.0169903003 0.0096648293 0.0051330000 0.0004430000 0.0021780000 0.0000000000 0.0000040000 0.0010230000 15336053 96830484 509673472 4.2131247520 4.0088176727 3.6357083321 829 33.1199999990 0.0161481164 0.0100027772 0.0169903003 0.0096736625 0.0064590000 0.0004430000 0.0025880000 0.0000040000 0.0000040000 0.0019480000 15338829 96830484 509673472 4.2126746178 4.0089497566 3.6362786293 830 33.1600000000 0.0162095279 0.0100102552 0.0169903003 0.0096736514 0.0107050000 0.0006180000 0.0030720000 0.0000020000 0.0000150000 0.0014540000 15341605 96830484 509673472 4.2124333382 4.0089397430 3.6374733448 831 33.2000000000 0.0162277352 0.0100177371 0.0169903003 0.0096771222 0.0082560000 0.0006210000 0.0023250000 0.0000150000 0.0000130000 0.0015720000 15344381 96830484 509673472 4.2110042572 4.0090384483 3.6386339664 832 33.2400000000 0.0163136367 0.0100253043 0.0169903003 0.0096717600 0.0059220000 0.0005010000 0.0021150000 0.0000010000 0.0000060000 0.0010490000 15347157 96830484 509673472 4.2107610703 4.0089235306 3.6398017406 833 33.2800000000 0.0163213555 0.0100328626 0.0169903003 0.0096673736 0.0066020000 0.0004590000 0.0026260000 0.0000050000 0.0000050000 0.0019240000 15349933 96830484 509673472 4.2099132538 4.0086908340 3.6405525208 834 33.3200000000 0.0163404476 0.0100404256 0.0169903003 0.0096633381 0.0066610000 0.0005310000 0.0021860000 0.0000020000 0.0000100000 0.0011240000 15352709 96830484 509673472 4.2091970444 4.0089187622 3.6414453983 835 33.3600000000 0.0164230652 0.0100480695 0.0169903003 0.0096576783 0.0060970000 0.0004780000 0.0022380000 0.0000070000 0.0000050000 0.0013620000 15355485 96830484 509673472 4.2087025642 4.0090613365 3.6425583363 836 33.4000000000 0.0164388325 0.0100557140 0.0169903003 0.0096520485 0.0093690000 0.0006180000 0.0029370000 0.0000010000 0.0000170000 0.0014540000 15358261 96830484 509673472 4.2076992989 4.0086779594 3.6434683800 837 33.4399999990 0.0165018402 0.0100634154 0.0169903003 0.0096472604 0.0080430000 0.0005050000 0.0024850000 0.0000060000 0.0000060000 0.0025860000 15361037 96830484 509673472 4.2066955566 4.0084414482 3.6442768574 838 33.4800000000 0.0164624713 0.0100710515 0.0169903003 0.0096424194 0.0053180000 0.0004570000 0.0022020000 0.0000010000 0.0000040000 0.0010220000 15363813 96830484 509673472 4.2057008743 4.0083713531 3.6449749470 839 33.5200000000 0.0165138058 0.0100787306 0.0169903003 0.0096368976 0.0079860000 0.0005990000 0.0023420000 0.0000100000 0.0000100000 0.0014980000 15366589 96830484 509673472 4.2045335770 4.0082731247 3.6453826427 840 33.5600000000 0.0165462960 0.0100864301 0.0169903003 0.0096315796 0.0064870000 0.0004710000 0.0030830000 0.0000000000 0.0000050000 0.0010280000 15369365 96830484 509673472 4.2033758163 4.0075469017 3.6461746693 841 33.6000000000 0.0165321678 0.0100940945 0.0169903003 0.0096290031 0.0065330000 0.0004500000 0.0026020000 0.0000050000 0.0000040000 0.0019210000 15372141 96830484 509673472 4.2020387650 4.0065531731 3.6474256516 842 33.6400000000 0.0165839866 0.0101018022 0.0169903003 0.0096346316 0.0051070000 0.0004410000 0.0021700000 0.0000010000 0.0000040000 0.0010220000 15374917 96830484 509673472 4.2008080482 4.0061759949 3.6481158733 843 33.6800000000 0.0166311096 0.0101095475 0.0169903003 0.0096359869 0.0058120000 0.0004420000 0.0025740000 0.0000040000 0.0000040000 0.0013060000 15377693 96830484 509673472 4.1996397972 4.0061922073 3.6488234997 844 33.7200000000 0.0167089794 0.0101173668 0.0169903003 0.0096333117 0.0109620000 0.0006280000 0.0031180000 0.0000020000 0.0000160000 0.0014500000 15380469 96830484 509673472 4.1983404160 4.0057520866 3.6498057842 845 33.7599999990 0.0167357475 0.0101251992 0.0169903003 0.0096343641 0.0083820000 0.0005300000 0.0027380000 0.0000100000 0.0000100000 0.0021950000 15383245 96830484 509673472 4.1969289780 4.0056180954 3.6499695778 846 33.7999999990 0.0167675558 0.0101330506 0.0169903003 0.0096343032 0.0057030000 0.0004780000 0.0022430000 0.0000000000 0.0000060000 0.0010330000 15386021 96830484 509673472 4.1957464218 4.0059003830 3.6506087780 847 33.8400000000 0.0168370306 0.0101409656 0.0169903003 0.0096303936 0.0074860000 0.0005300000 0.0028790000 0.0000080000 0.0000080000 0.0014120000 15388797 96830484 509673472 4.1946573257 4.0060691833 3.6516036987 848 33.8800000000 0.0169456396 0.0101489900 0.0169903003 0.0096249262 0.0073030000 0.0005300000 0.0027570000 0.0000010000 0.0000070000 0.0011320000 15391573 96830484 509673472 4.1933021545 4.0062508583 3.6521034241 849 33.9200000000 0.0169923585 0.0101570505 0.0169923585 0.0096194356 0.0084160000 0.0005310000 0.0027760000 0.0000100000 0.0000090000 0.0021930000 15394349 96830484 509673472 4.1921291351 4.0065064430 3.6525795460 850 33.9600000000 0.0169658083 0.0101650608 0.0169923585 0.0096145910 0.0060770000 0.0004740000 0.0026550000 0.0000010000 0.0000050000 0.0010330000 15397125 96830484 509673472 4.1909060478 4.0064082146 3.6538205147 851 34.0000000000 0.0169872716 0.0101730775 0.0169923585 0.0096109838 0.0056620000 0.0004390000 0.0025970000 0.0000040000 0.0000030000 0.0012910000 15399901 96830484 509673472 4.1895351410 4.0062499046 3.6539442539 852 34.0400000000 0.0169768129 0.0101810631 0.0169923585 0.0096075692 0.0047400000 0.0004320000 0.0020160000 0.0000010000 0.0000040000 0.0010040000 15402677 96830484 509673472 4.1877889633 4.0060768127 3.6536576748 853 34.0800000000 0.0169908982 0.0101890465 0.0169923585 0.0096037670 0.0116100000 0.0006200000 0.0028380000 0.0000160000 0.0000140000 0.0025250000 15405453 96830484 509673472 4.1863999367 4.0057020187 3.6540670395 854 34.1199999990 0.0170091018 0.0101970325 0.0170091018 0.0095994012 0.0072270000 0.0005320000 0.0024760000 0.0000020000 0.0000100000 0.0012180000 15408229 96830484 509673472 4.1851301193 4.0051393509 3.6549756527 855 34.1600000000 0.0169686358 0.0102049525 0.0170091018 0.0095944729 0.0059700000 0.0004800000 0.0022140000 0.0000060000 0.0000060000 0.0013130000 15411005 96830484 509673472 4.1838250160 4.0037531853 3.6562862396 856 34.2000000000 0.0171043426 0.0102130125 0.0171043426 0.0095925256 0.0059600000 0.0004470000 0.0030070000 0.0000000000 0.0000040000 0.0010270000 15413781 96830484 509673472 4.1827039719 4.0030226707 3.6579515934 857 34.2400000000 0.0170666520 0.0102210098 0.0171043426 0.0095933422 0.0091010000 0.0006190000 0.0024360000 0.0000180000 0.0000140000 0.0022320000 15416557 96830484 509673472 4.1816630363 4.0030841827 3.6589674950 858 34.2800000000 0.0171618331 0.0102290993 0.0171618331 0.0095889812 0.0062960000 0.0004920000 0.0026320000 0.0000010000 0.0000060000 0.0010820000 15419333 96830484 509673472 4.1804141998 4.0025539398 3.6603507996 859 34.3200000000 0.0172048602 0.0102372201 0.0172048602 0.0095862787 0.0071400000 0.0005290000 0.0022910000 0.0000080000 0.0000060000 0.0014170000 15422109 96830484 509673472 4.1790242195 4.0021066666 3.6619820595 860 34.3600000000 0.0172603242 0.0102453865 0.0172603242 0.0095824596 0.0058300000 0.0004740000 0.0022140000 0.0000000000 0.0000070000 0.0010690000 15424885 96830484 509673472 4.1776447296 4.0023336411 3.6632449627 861 34.4000000000 0.0172712207 0.0102535466 0.0172712207 0.0095770643 0.0093990000 0.0005430000 0.0027420000 0.0000100000 0.0000100000 0.0022600000 15427661 96830484 509673472 4.1761708260 4.0021281242 3.6646630764 862 34.4400000000 0.0174149759 0.0102618545 0.0174149759 0.0095715941 0.0069310000 0.0005050000 0.0031100000 0.0000000000 0.0000060000 0.0010730000 15430437 96830484 509673472 4.1747126579 4.0021123886 3.6664094925 863 34.4800000000 0.0173646118 0.0102700848 0.0174149759 0.0095660950 0.0076580000 0.0005300000 0.0027660000 0.0000100000 0.0000090000 0.0014270000 15433213 96830484 509673472 4.1732215881 4.0023379326 3.6680204868 864 34.5200000000 0.0173833538 0.0102783178 0.0174149759 0.0095611020 0.0064950000 0.0004740000 0.0030640000 0.0000010000 0.0000050000 0.0010390000 15435989 96830484 509673472 4.1713328362 4.0026059151 3.6700029373 865 34.5600000000 0.0175256785 0.0102866962 0.0175256785 0.0095573299 0.0078970000 0.0005520000 0.0023330000 0.0000100000 0.0000090000 0.0020890000 15438765 96830484 509673472 4.1694583893 4.0023784637 3.6721174717 866 34.6000000000 0.0174990464 0.0102950246 0.0175256785 0.0095518779 0.0087260000 0.0006160000 0.0029260000 0.0000020000 0.0000150000 0.0012480000 15441541 96830484 509673472 4.1673498154 4.0020527840 3.6744480133 867 34.6400000000 0.0175024830 0.0103033377 0.0175256785 0.0095467354 0.0067640000 0.0005030000 0.0026530000 0.0000070000 0.0000060000 0.0013630000 15444317 96830484 509673472 4.1652059555 4.0026164055 3.6761491299 868 34.6800000000 0.0175634753 0.0103117019 0.0175634753 0.0095428782 0.0055980000 0.0005110000 0.0021820000 0.0000010000 0.0000040000 0.0010410000 15447093 96830484 509673472 4.1629338264 4.0031757355 3.6782495975 869 34.7200000000 0.0175421648 0.0103200223 0.0175634753 0.0095405082 0.0084830000 0.0005720000 0.0027450000 0.0000100000 0.0000100000 0.0021920000 15449869 96830484 509673472 4.1606307030 4.0038747787 3.6802749634 870 34.7600000000 0.0175604783 0.0103283447 0.0175634753 0.0095433365 0.0072540000 0.0005300000 0.0027440000 0.0000010000 0.0000090000 0.0011200000 15452645 96830484 509673472 4.1580286026 4.0043029785 3.6827318668 871 34.8000000000 0.0175695643 0.0103366584 0.0175695643 0.0095465856 0.0076490000 0.0005410000 0.0027520000 0.0000080000 0.0000070000 0.0013990000 15455421 96830484 509673472 4.1552858353 4.0037117004 3.6851954460 872 34.8400000000 0.0175837949 0.0103449693 0.0175837949 0.0095411274 0.0061510000 0.0004690000 0.0027620000 0.0000000000 0.0000060000 0.0010420000 15458197 96830484 509673472 4.1523847580 4.0032124519 3.6880652905 873 34.8800000000 0.0175477490 0.0103532199 0.0175837949 0.0095400986 0.0087080000 0.0005330000 0.0027720000 0.0000100000 0.0000100000 0.0022400000 15460973 96830484 509673472 4.1496629715 4.0044965744 3.6902661324 874 34.9200000000 0.0176990964 0.0103616248 0.0176990964 0.0095353564 0.0061700000 0.0004940000 0.0026470000 0.0000010000 0.0000060000 0.0010420000 15463749 96830484 509673472 4.1468920708 4.0059080124 3.6923074722 875 34.9600000000 0.0177090503 0.0103700219 0.0177090503 0.0095388788 0.0061910000 0.0004470000 0.0027470000 0.0000050000 0.0000040000 0.0013190000 15466525 96830484 509673472 4.1438999176 4.0062475204 3.6945769787 876 35.0000000000 0.0177657753 0.0103784645 0.0177657753 0.0095421554 0.0055750000 0.0004400000 0.0025970000 0.0000000000 0.0000040000 0.0010240000 15469301 96830484 509673472 4.1409063339 4.0065717697 3.6968672276 877 35.0400000000 0.0177192166 0.0103868348 0.0177657753 0.0095431470 0.0110640000 0.0006150000 0.0029370000 0.0000150000 0.0000130000 0.0025270000 15472077 96830484 509673472 4.1378898621 4.0071530342 3.6991906166 878 35.0800000000 0.0178432595 0.0103953273 0.0178432595 0.0095479510 0.0066690000 0.0005020000 0.0027000000 0.0000000000 0.0000060000 0.0010680000 15474853 96830484 509673472 4.1347699165 4.0070624352 3.7015330791 879 35.1200000000 0.0176988076 0.0104036362 0.0178432595 0.0095462999 0.0057560000 0.0004670000 0.0022050000 0.0000050000 0.0000040000 0.0013230000 15477629 96830484 509673472 4.1317038536 4.0074863434 3.7035322189 880 35.1600000000 0.0178315621 0.0104120770 0.0178432595 0.0095526031 0.0075610000 0.0005300000 0.0027610000 0.0000010000 0.0000100000 0.0012350000 15480405 96830484 509673472 4.1287755966 4.0085630417 3.7060310841 881 35.2000000000 0.0178229939 0.0104204890 0.0178432595 0.0095694574 0.0073890000 0.0004720000 0.0027890000 0.0000060000 0.0000050000 0.0020250000 15483181 96830484 509673472 4.1256875992 4.0084185600 3.7079858780 882 35.2400000000 0.0178353116 0.0104288958 0.0178432595 0.0095705054 0.0053200000 0.0004480000 0.0023240000 0.0000010000 0.0000040000 0.0010240000 15485957 96830484 509673472 4.1226854324 4.0083742142 3.7104663849 883 35.2800000000 0.0177363213 0.0104371715 0.0178432595 0.0095668490 0.0089700000 0.0005310000 0.0029080000 0.0000110000 0.0000090000 0.0015070000 15488733 96830484 509673472 4.1195135117 4.0084118843 3.7127785683 884 35.3200000000 0.0177808180 0.0104454788 0.0178432595 0.0095624732 0.0065740000 0.0005120000 0.0026680000 0.0000010000 0.0000060000 0.0010600000 15491509 96830484 509673472 4.1167440414 4.0093655586 3.7148239613 885 35.3600000000 0.0177357662 0.0104537164 0.0178432595 0.0095592267 0.0084990000 0.0005300000 0.0029120000 0.0000090000 0.0000070000 0.0020600000 15494285 96830484 509673472 4.1138048172 4.0097827911 3.7168657780 886 35.4000000000 0.0177710839 0.0104619752 0.0178432595 0.0095548367 0.0055400000 0.0004550000 0.0022020000 0.0000000000 0.0000050000 0.0010280000 15497061 96830484 509673472 4.1108183861 4.0097398758 3.7190403938 887 35.4400000000 0.0177846868 0.0104702308 0.0178432595 0.0095496117 0.0058700000 0.0004370000 0.0025820000 0.0000050000 0.0000040000 0.0013100000 15499837 96830484 509673472 4.1078910828 4.0098056793 3.7208905220 888 35.4800000000 0.0179220904 0.0104786226 0.0179220904 0.0095443324 0.0096950000 0.0005890000 0.0028460000 0.0000020000 0.0000130000 0.0013450000 15502613 96830484 509673472 4.1050992012 4.0099706650 3.7228453159 889 35.5200000000 0.0179205295 0.0104869937 0.0179220904 0.0095406823 0.0076390000 0.0004950000 0.0028060000 0.0000070000 0.0000060000 0.0020200000 15505389 96830484 509673472 4.1024742126 4.0104956627 3.7244317532 890 35.5600000000 0.0178833548 0.0104953042 0.0179220904 0.0095359055 0.0054900000 0.0004600000 0.0023240000 0.0000010000 0.0000040000 0.0010180000 15508165 96830484 509673472 4.0998516083 4.0110783577 3.7261118889 891 35.6000000000 0.0178695526 0.0105035806 0.0179220904 0.0095306435 0.0100530000 0.0006220000 0.0029040000 0.0000170000 0.0000140000 0.0016870000 15510941 96830484 509673472 4.0972509384 4.0118474960 3.7279059887 892 35.6400000000 0.0179213230 0.0105118964 0.0179220904 0.0095253582 0.0070970000 0.0005010000 0.0031040000 0.0000010000 0.0000070000 0.0010710000 15513717 96830484 509673472 4.0947041512 4.0123386383 3.7296519279 893 35.6800000000 0.0178927947 0.0105201617 0.0179220904 0.0095200842 0.0067710000 0.0004610000 0.0026060000 0.0000040000 0.0000040000 0.0019430000 15516493 96830484 509673472 4.0921378136 4.0127878189 3.7311592102 894 35.7200000000 0.0180380382 0.0105285710 0.0180380382 0.0095149387 0.0083390000 0.0005350000 0.0029100000 0.0000010000 0.0000100000 0.0012030000 15519269 96830484 509673472 4.0896534920 4.0134158134 3.7327468395 895 35.7600000000 0.0179634113 0.0105368780 0.0180380382 0.0095101687 0.0069440000 0.0004770000 0.0030520000 0.0000070000 0.0000060000 0.0013160000 15522045 96830484 509673472 4.0871548653 4.0136966705 3.7340788841 896 35.8000000000 0.0180960707 0.0105453146 0.0180960707 0.0095051005 0.0057290000 0.0004470000 0.0025930000 0.0000000000 0.0000050000 0.0010240000 15524821 96830484 509673472 4.0847358704 4.0139517784 3.7354841232 897 35.8400000000 0.0180875789 0.0105537230 0.0180960707 0.0094999249 0.0104510000 0.0006160000 0.0030650000 0.0000150000 0.0000140000 0.0025080000 15527597 96830484 509673472 4.0823426247 4.0144324303 3.7366492748 898 35.8800000000 0.0182279777 0.0105622689 0.0182279777 0.0094949194 0.0066080000 0.0005080000 0.0026500000 0.0000010000 0.0000060000 0.0010550000 15530373 96830484 509673472 4.0798964500 4.0152435303 3.7378253937 899 35.9200000000 0.0181846973 0.0105707477 0.0182279777 0.0094903035 0.0077400000 0.0005320000 0.0027450000 0.0000100000 0.0000090000 0.0013890000 15533149 96830484 509673472 4.0773034096 4.0153851509 3.7385098934 900 35.9600000000 0.0181957353 0.0105792199 0.0182279777 0.0094850811 0.0061590000 0.0004710000 0.0026280000 0.0000000000 0.0000050000 0.0010250000 15535925 96830484 509673472 4.0747575760 4.0150599480 3.7391602993 901 36.0000000000 0.0181018580 0.0105875691 0.0182279777 0.0094814867 0.0103710000 0.0006190000 0.0030520000 0.0000150000 0.0000130000 0.0024880000 15538701 96830484 509673472 4.0723757744 4.0151424408 3.7392716408 902 36.0400000000 0.0182265248 0.0105960380 0.0182279777 0.0094763283 0.0067840000 0.0005010000 0.0027970000 0.0000010000 0.0000080000 0.0010650000 15541477 96830484 509673472 4.0700201988 4.0156078339 3.7393627167 903 36.0800000000 0.0182447899 0.0106045084 0.0182447899 0.0094711887 0.0086610000 0.0005340000 0.0035790000 0.0000100000 0.0000100000 0.0014040000 15544253 96830484 509673472 4.0674443245 4.0155229568 3.7399041653 904 36.1200000000 0.0183236506 0.0106130473 0.0183236506 0.0094660216 0.0059590000 0.0004720000 0.0023460000 0.0000000000 0.0000050000 0.0010360000 15547029 96830484 509673472 4.0650081635 4.0156617165 3.7400300503 905 36.1600000000 0.0182460714 0.0106214816 0.0183236506 0.0094612995 0.0069160000 0.0004390000 0.0029710000 0.0000040000 0.0000030000 0.0019310000 15549805 96830484 509673472 4.0625224113 4.0160169601 3.7407257557 906 36.2000000000 0.0183278304 0.0106299875 0.0183278304 0.0094577738 0.0102580000 0.0006180000 0.0028900000 0.0000020000 0.0000150000 0.0014090000 15552581 96830484 509673472 4.0599188805 4.0160927773 3.7407360077 907 36.2400000000 0.0183553528 0.0106385050 0.0183553528 0.0094542634 0.0074360000 0.0005020000 0.0030730000 0.0000060000 0.0000060000 0.0013390000 15555357 96830484 509673472 4.0573067665 4.0158772469 3.7401812077 908 36.2800000000 0.0183274597 0.0106469730 0.0183553528 0.0094491476 0.0054840000 0.0004590000 0.0021850000 0.0000010000 0.0000050000 0.0010320000 15558133 96830484 509673472 4.0546441078 4.0156974792 3.7396285534 909 36.3200000000 0.0182957184 0.0106553874 0.0183553528 0.0094439629 0.0066750000 0.0004410000 0.0026880000 0.0000040000 0.0000030000 0.0019360000 15560909 96830484 509673472 4.0520091057 4.0156960487 3.7395234108 910 36.3600000000 0.0183094330 0.0106637985 0.0183553528 0.0094388295 0.0059960000 0.0004350000 0.0031130000 0.0000010000 0.0000040000 0.0010230000 15563685 96830484 509673472 4.0493936539 4.0159406662 3.7395267487 911 36.4000000000 0.0183715783 0.0106722593 0.0183715783 0.0094340475 0.0057140000 0.0004320000 0.0025580000 0.0000040000 0.0000040000 0.0013030000 15566461 96830484 509673472 4.0467424393 4.0156965256 3.7392239571 912 36.4400000000 0.0183737054 0.0106807038 0.0183737054 0.0094288825 0.0112280000 0.0006190000 0.0030480000 0.0000010000 0.0000150000 0.0014140000 15569237 96830484 509673472 4.0442442894 4.0159020424 3.7393755913 913 36.4800000000 0.0183751266 0.0106891314 0.0183751266 0.0094240279 0.0090340000 0.0005310000 0.0031560000 0.0000110000 0.0000090000 0.0021810000 15572013 96830484 509673472 4.0417575836 4.0161938667 3.7397587299 914 36.5200000000 0.0183688328 0.0106975337 0.0183751266 0.0094204917 0.0059980000 0.0004780000 0.0023410000 0.0000010000 0.0000060000 0.0010570000 15574789 96830484 509673472 4.0391097069 4.0160150528 3.7395977974 915 36.5600000000 0.0184093788 0.0107059620 0.0184093788 0.0094166299 0.0055430000 0.0004460000 0.0021600000 0.0000040000 0.0000040000 0.0013330000 15577565 96830484 509673472 4.0366749763 4.0158548355 3.7390756607 916 36.6000000000 0.0183672458 0.0107143258 0.0184093788 0.0094117679 0.0100560000 0.0006170000 0.0030580000 0.0000010000 0.0000150000 0.0014140000 15580341 96830484 509673472 4.0342702866 4.0156693459 3.7392413616 917 36.6400000000 0.0183927268 0.0107226992 0.0184093788 0.0094066395 0.0085220000 0.0005010000 0.0036390000 0.0000060000 0.0000060000 0.0020310000 15583117 96830484 509673472 4.0318412781 4.0150036812 3.7392199039 918 36.6800000000 0.0184077974 0.0107310708 0.0184093788 0.0094018044 0.0057860000 0.0004520000 0.0026010000 0.0000000000 0.0000050000 0.0010400000 15585893 96830484 509673472 4.0295839310 4.0149717331 3.7394983768 919 36.7200000000 0.0184122324 0.0107394290 0.0184122324 0.0093967422 0.0058230000 0.0004400000 0.0025530000 0.0000040000 0.0000030000 0.0013400000 15588669 96830484 509673472 4.0275464058 4.0153017044 3.7390882969 920 36.7600000000 0.0184362456 0.0107477951 0.0184362456 0.0093919431 0.0100270000 0.0006340000 0.0028830000 0.0000020000 0.0000170000 0.0014290000 15591445 96830484 509673472 4.0254993439 4.0150985718 3.7393796444 921 36.8000000000 0.0184358675 0.0107561426 0.0184362456 0.0093868750 0.0078600000 0.0005020000 0.0028120000 0.0000070000 0.0000050000 0.0020480000 15594221 96830484 509673472 4.0236806870 4.0152840614 3.7396109104 922 36.8400000000 0.0185095333 0.0107645519 0.0185095333 0.0093822699 0.0070880000 0.0004460000 0.0039810000 0.0000010000 0.0000050000 0.0010410000 15596997 96830484 509673472 4.0220451355 4.0158462524 3.7403621674 923 36.8800000000 0.0185333211 0.0107729688 0.0185333211 0.0093784196 0.0078060000 0.0005310000 0.0028830000 0.0000080000 0.0000070000 0.0014460000 15599773 96830484 509673472 4.0204730034 4.0159993172 3.7404630184 924 36.9200000000 0.0185273103 0.0107813609 0.0185333211 0.0093756859 0.0059760000 0.0004570000 0.0026230000 0.0000010000 0.0000040000 0.0010410000 15602549 96830484 509673472 4.0190367699 4.0157842636 3.7397487164 925 36.9600000000 0.0185556822 0.0107897656 0.0185556822 0.0093714252 0.0079070000 0.0004430000 0.0038370000 0.0000040000 0.0000040000 0.0019650000 15605325 96830484 509673472 4.0174975395 4.0155763626 3.7401041985 926 37.0000000000 0.0185184162 0.0107981119 0.0185556822 0.0093664187 0.0056500000 0.0004400000 0.0027150000 0.0000000000 0.0000040000 0.0010350000 15608101 96830484 509673472 4.0162224770 4.0158562660 3.7396614552 927 37.0400000000 0.0185238272 0.0108064460 0.0185556822 0.0093619140 0.0109020000 0.0009890000 0.0028470000 0.0000400000 0.0000250000 0.0022500000 15610877 96830484 509673472 4.0150995255 4.0159935951 3.7397348881 928 37.0800000000 0.0185586493 0.0108147997 0.0185586493 0.0093586325 0.0068810000 0.0005460000 0.0028150000 0.0000010000 0.0000060000 0.0010840000 15613653 96830484 509673472 4.0140886307 4.0168190002 3.7401504517 929 37.1200000000 0.0185220428 0.0108230959 0.0185586493 0.0093578752 0.0068470000 0.0004500000 0.0027380000 0.0000050000 0.0000040000 0.0020020000 15616429 96830484 509673472 4.0130748749 4.0169672966 3.7405824661 930 37.1600000000 0.0185467731 0.0108314010 0.0185586493 0.0093569094 0.0059010000 0.0004360000 0.0029860000 0.0000000000 0.0000040000 0.0010350000 15619205 96830484 509673472 4.0122494698 4.0172195435 3.7406904697 931 37.2000000000 0.0185502768 0.0108396919 0.0185586493 0.0093551577 0.0100590000 0.0006220000 0.0029400000 0.0000150000 0.0000140000 0.0017270000 15621981 96830484 509673472 4.0114650726 4.0175476074 3.7410187721 932 37.2400000000 0.0185584649 0.0108479739 0.0185586493 0.0093521808 0.0065290000 0.0005060000 0.0024100000 0.0000010000 0.0000070000 0.0010730000 15624757 96830484 509673472 4.0108246803 4.0177454948 3.7410600185 933 37.2800000000 0.0185442083 0.0108562228 0.0185586493 0.0093490973 0.0065850000 0.0004610000 0.0022050000 0.0000050000 0.0000050000 0.0020180000 15627533 96830484 509673472 4.0101332664 4.0181617737 3.7414770126 934 37.3200000000 0.0185855739 0.0108644983 0.0185855739 0.0093466366 0.0081920000 0.0004460000 0.0052220000 0.0000010000 0.0000050000 0.0010480000 15630309 96830484 509673472 4.0096063614 4.0189208984 3.7418208122 935 37.3600000000 0.0184807666 0.0108726440 0.0185855739 0.0093462647 0.0061700000 0.0004430000 0.0029910000 0.0000030000 0.0000040000 0.0013410000 15633085 96830484 509673472 4.0092210770 4.0191960335 3.7418923378 936 37.4000000000 0.0185678601 0.0108808654 0.0185855739 0.0093444528 0.0104900000 0.0006170000 0.0029280000 0.0000010000 0.0000150000 0.0014320000 15635861 96830484 509673472 4.0088000298 4.0194287300 3.7418711185 937 37.4400000000 0.0185706560 0.0108890723 0.0185855739 0.0093409932 0.0080060000 0.0005070000 0.0028610000 0.0000060000 0.0000050000 0.0020530000 15638637 96830484 509673472 4.0085291862 4.0194191933 3.7418880463 938 37.4800000000 0.0186312180 0.0108973261 0.0186312180 0.0093376218 0.0082510000 0.0004650000 0.0051120000 0.0000000000 0.0000040000 0.0010320000 15641413 96830484 509673472 4.0082454681 4.0194654465 3.7418153286 939 37.5200000000 0.0185833946 0.0109055115 0.0186312180 0.0093333240 0.0076680000 0.0005380000 0.0024940000 0.0000100000 0.0000090000 0.0014340000 15644189 96830484 509673472 4.0082416534 4.0196380615 3.7415804863 940 37.5600000000 0.0185495000 0.0109136434 0.0186312180 0.0093291246 0.0072970000 0.0005350000 0.0023500000 0.0000010000 0.0000100000 0.0012020000 15646965 96830484 509673472 4.0082426071 4.0199007988 3.7415471077 941 37.6000000000 0.0185887404 0.0109217997 0.0186312180 0.0093254541 0.0071040000 0.0004750000 0.0026580000 0.0000050000 0.0000050000 0.0019910000 15649741 96830484 509673472 4.0081849098 4.0204715729 3.7416224480 942 37.6400000000 0.0185712613 0.0109299202 0.0186312180 0.0093221954 0.0066950000 0.0004430000 0.0035990000 0.0000010000 0.0000050000 0.0010170000 15652517 96830484 509673472 4.0083484650 4.0209326744 3.7414402962 943 37.6800000000 0.0185055230 0.0109379537 0.0186312180 0.0093206368 0.0103030000 0.0006210000 0.0025200000 0.0000150000 0.0000130000 0.0016950000 15655293 96830484 509673472 4.0084409714 4.0210866928 3.7412347794 944 37.7200000000 0.0185062457 0.0109459710 0.0186312180 0.0093183196 0.0068670000 0.0005040000 0.0027140000 0.0000010000 0.0000070000 0.0010520000 15658069 96830484 509673472 4.0085558891 4.0215811729 3.7410602570 945 37.7600000000 0.0185058564 0.0109539708 0.0186312180 0.0093159127 0.0069510000 0.0004620000 0.0027770000 0.0000050000 0.0000040000 0.0019580000 15660845 96830484 509673472 4.0086879730 4.0218744278 3.7408664227 946 37.8000000000 0.0185157452 0.0109619643 0.0186312180 0.0093134686 0.0050780000 0.0004420000 0.0021850000 0.0000010000 0.0000040000 0.0010110000 15663621 96830484 509673472 4.0086975098 4.0220389366 3.7406542301 947 37.8400000000 0.0185968764 0.0109700265 0.0186312180 0.0093100094 0.0094410000 0.0005410000 0.0033610000 0.0000100000 0.0000090000 0.0015240000 15666397 96830484 509673472 4.0088477135 4.0224108696 3.7406492233 948 37.8800000000 0.0185150299 0.0109779853 0.0186312180 0.0093073076 0.0077390000 0.0005070000 0.0035700000 0.0000010000 0.0000090000 0.0010540000 15669173 96830484 509673472 4.0089516640 4.0225305557 3.7405147552 949 37.9200000000 0.0185173713 0.0109859299 0.0186312180 0.0093043487 0.0067040000 0.0004630000 0.0022020000 0.0000050000 0.0000050000 0.0019490000 15671949 96830484 509673472 4.0091595650 4.0228233337 3.7403259277 950 37.9600000000 0.0185496416 0.0109938917 0.0186312180 0.0093004513 0.0059770000 0.0004510000 0.0026220000 0.0000000000 0.0000040000 0.0010140000 15674725 96830484 509673472 4.0094118118 4.0232667923 3.7401010990 951 38.0000000000 0.0185074341 0.0110017924 0.0186312180 0.0092962383 0.0104630000 0.0006230000 0.0026320000 0.0000150000 0.0000160000 0.0016890000 15677501 96830484 509673472 4.0096111298 4.0234951973 3.7399942875 952 38.0400000000 0.0185025521 0.0110096713 0.0186312180 0.0092938313 0.0077320000 0.0005210000 0.0035490000 0.0000010000 0.0000060000 0.0010470000 15680277 96830484 509673472 4.0097603798 4.0237298012 3.7400813103 953 38.0800000000 0.0185132008 0.0110175449 0.0186312180 0.0092897363 0.0066350000 0.0004620000 0.0023450000 0.0000040000 0.0000040000 0.0019650000 15683053 96830484 509673472 4.0101099014 4.0240011215 3.7397773266 954 38.1200000000 0.0185443256 0.0110254346 0.0186312180 0.0092849424 0.0053100000 0.0004380000 0.0024550000 0.0000010000 0.0000040000 0.0010060000 15685829 96830484 509673472 4.0103945732 4.0243902206 3.7394602299 955 38.1600000000 0.0185253657 0.0110332879 0.0186312180 0.0092804958 0.0119190000 0.0006200000 0.0039640000 0.0000150000 0.0000140000 0.0017170000 15688605 96830484 509673472 4.0105280876 4.0243825912 3.7396843433 956 38.2000000000 0.0185878035 0.0110411902 0.0186312180 0.0092756534 0.0076130000 0.0005060000 0.0026450000 0.0000010000 0.0000170000 0.0014830000 15691381 96830484 509673472 4.0108685493 4.0248250961 3.7391545773 957 38.2400000000 0.0185911283 0.0110490793 0.0186312180 0.0092709235 0.0067440000 0.0006900000 0.0022030000 0.0000050000 0.0000050000 0.0019560000 15694157 96830484 509673472 4.0109944344 4.0246887207 3.7389075756 958 38.2800000000 0.0185830854 0.0110569436 0.0186312180 0.0092662454 0.0076790000 0.0005350000 0.0027740000 0.0000010000 0.0000080000 0.0010930000 15696933 96830484 509673472 4.0111384392 4.0249133110 3.7389416695 959 38.3200000000 0.0186042078 0.0110648136 0.0186312180 0.0092615768 0.0081130000 0.0005360000 0.0027800000 0.0000100000 0.0000090000 0.0014770000 15699709 96830484 509673472 4.0114340782 4.0249319077 3.7385699749 960 38.3600000000 0.0186325647 0.0110726966 0.0186325647 0.0092570560 0.0075690000 0.0004780000 0.0039280000 0.0000010000 0.0000050000 0.0010120000 15702485 96830484 509673472 4.0116043091 4.0251002312 3.7386536598 961 38.4000000000 0.0186216421 0.0110805519 0.0186325647 0.0092525683 0.0084660000 0.0005300000 0.0027900000 0.0000090000 0.0000070000 0.0020700000 15705261 96830484 509673472 4.0119113922 4.0252175331 3.7383224964 962 38.4400000000 0.0186419878 0.0110884121 0.0186419878 0.0092479621 0.0057030000 0.0004600000 0.0022130000 0.0000000000 0.0000050000 0.0010190000 15708037 96830484 509673472 4.0121726990 4.0253372192 3.7380745411 963 38.4800000000 0.0186491385 0.0110962633 0.0186491385 0.0092432633 0.0082630000 0.0005340000 0.0029320000 0.0000120000 0.0000090000 0.0015140000 15710813 96830484 509673472 4.0124473572 4.0252046585 3.7379634380 964 38.5200000000 0.0186671484 0.0111041169 0.0186671484 0.0092385437 0.0065040000 0.0004750000 0.0027970000 0.0000010000 0.0000060000 0.0010170000 15713589 96830484 509673472 4.0127782822 4.0254311562 3.7377953529 965 38.5600000000 0.0186582077 0.0111119450 0.0186671484 0.0092338180 0.0066490000 0.0004500000 0.0023390000 0.0000040000 0.0000040000 0.0019370000 15716365 96830484 509673472 4.0130720139 4.0255007744 3.7377886772 966 38.6000000000 0.0186475553 0.0111197458 0.0186671484 0.0092292293 0.0105780000 0.0006250000 0.0026370000 0.0000020000 0.0000160000 0.0013930000 15719141 96830484 509673472 4.0133404732 4.0254697800 3.7376320362 967 38.6400000000 0.0186180696 0.0111275000 0.0186671484 0.0092244792 0.0073510000 0.0004960000 0.0028430000 0.0000080000 0.0000070000 0.0013370000 15721917 96830484 509673472 4.0136189461 4.0254745483 3.7376434803 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:22:41 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 -nan 0.0033090000 0.0004690000 0.0005300000 0.0000060000 0.0000010000 0.0022340000 12532445 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378911 0.0016670000 0.0004280000 0.0005150000 0.0000040000 0.0000000000 0.0007030000 12732189 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728699 0.0016580000 0.0004250000 0.0005170000 0.0000040000 0.0000010000 0.0006940000 12735357 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723129 0.0022980000 0.0004250000 0.0005140000 0.0000030000 0.0000050000 0.0013310000 12738533 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276867 0.0024566393 0.0055015511 0.0048987302 0.0055110000 0.0004250000 0.0029650000 0.0000040000 0.0000030000 0.0020920000 12741693 96830484 509673472 3.9957129955 4.0020370483 4.0009112358 6 0.2000000000 0.0021193668 0.0024004272 0.0055015511 0.0043897879 0.0042190000 0.0004250000 0.0026810000 0.0000000000 0.0000040000 0.0010870000 12745269 96830484 509673472 3.9965579510 4.0017552376 4.0000634193 7 0.2400000000 0.0020520808 0.0023506635 0.0055015511 0.0040162830 0.0039630000 0.0004230000 0.0021390000 0.0000030000 0.0000030000 0.0013720000 12748045 96830484 509673472 3.9963893890 4.0014748573 4.0003581047 8 0.2800000000 0.0021309818 0.0023232032 0.0055015511 0.0037226256 0.0038220000 0.0004240000 0.0022750000 0.0000010000 0.0000030000 0.0010960000 12750821 96830484 509673472 3.9949610233 4.0019330978 4.0002708435 9 0.3200000000 0.0021698186 0.0023061605 0.0055015511 0.0035285755 0.0046980000 0.0004230000 0.0021340000 0.0000030000 0.0000020000 0.0021070000 12754365 96830484 509673472 3.9930253029 4.0012869835 4.0003128052 10 0.3600000000 0.0022089549 0.0022964399 0.0055015511 0.0033889312 0.0036900000 0.0004250000 0.0021400000 0.0000010000 0.0000030000 0.0010950000 12758741 96830484 509673472 3.9929094315 4.0026316643 4.0009026527 11 0.4000000000 0.0022601751 0.0022931431 0.0055015511 0.0033576804 0.0043820000 0.0004260000 0.0025450000 0.0000030000 0.0000030000 0.0013760000 12761517 96830484 509673472 3.9919466972 4.0017867088 4.0016007423 12 0.4400000000 0.0022672073 0.0022909818 0.0055015511 0.0034304144 0.0036800000 0.0004230000 0.0021410000 0.0000000000 0.0000030000 0.0010840000 12764293 96830484 509673472 3.9918613434 4.0017361641 4.0008234978 13 0.4800000000 0.0022819978 0.0022902907 0.0055015511 0.0034359352 0.0046970000 0.0004240000 0.0021470000 0.0000040000 0.0000030000 0.0020890000 12767069 96830484 509673472 3.9894280434 4.0015416145 4.0013961792 14 0.5200000000 0.0023268927 0.0022929052 0.0055015511 0.0033242452 0.0065710000 0.0004230000 0.0050250000 0.0000000000 0.0000030000 0.0010890000 12769845 96830484 509673472 3.9894309044 4.0028085709 4.0008172989 15 0.5600000000 0.0023079070 0.0022939053 0.0055015511 0.0032120938 0.0042450000 0.0004230000 0.0024190000 0.0000030000 0.0000030000 0.0013630000 12772621 96830484 509673472 3.9863359928 4.0038881302 4.0015878677 16 0.6000000000 0.0023973526 0.0023003707 0.0055015511 0.0031278743 0.0046470000 0.0004270000 0.0031030000 0.0000000000 0.0000040000 0.0010810000 12775397 96830484 509673472 3.9871206284 4.0023245811 4.0005326271 17 0.6400000000 0.0024036658 0.0023064469 0.0055015511 0.0030498162 0.0049810000 0.0004220000 0.0024290000 0.0000030000 0.0000020000 0.0020890000 12779709 96830484 509673472 3.9851038456 4.0008935928 3.9991035461 18 0.6800000000 0.0024461173 0.0023142064 0.0055015511 0.0029599922 0.0042260000 0.0004230000 0.0026880000 0.0000000000 0.0000030000 0.0010760000 12785685 96830484 509673472 3.9835441113 4.0011601448 4.0000782013 19 0.7200000000 0.0024378977 0.0023207165 0.0055015511 0.0029192022 0.0042580000 0.0004240000 0.0024190000 0.0000030000 0.0000020000 0.0013720000 12788461 96830484 509673472 3.9820592403 4.0014061928 3.9996428490 20 0.7600000000 0.0025582798 0.0023325946 0.0055015511 0.0029371945 0.0041120000 0.0004220000 0.0025750000 0.0000010000 0.0000030000 0.0010750000 12791237 96830484 509673472 3.9790954590 4.0002269745 3.9993181229 21 0.8000000000 0.0026400634 0.0023472360 0.0055015511 0.0028722664 0.0051290000 0.0004250000 0.0025710000 0.0000030000 0.0000030000 0.0020870000 12794013 96830484 509673472 3.9762642384 4.0010976791 3.9996490479 22 0.8400000000 0.0029139980 0.0023729979 0.0055015511 0.0028126401 0.0037070000 0.0004220000 0.0021580000 0.0000000000 0.0000040000 0.0010850000 12796789 96830484 509673472 3.9707870483 4.0004653931 3.9992003441 23 0.8800000000 0.0029073921 0.0023962324 0.0055015511 0.0027480098 0.0045460000 0.0004250000 0.0027030000 0.0000030000 0.0000030000 0.0013690000 12799565 96830484 509673472 3.9713716507 3.9995737076 3.9975576401 24 0.9200000000 0.0028074081 0.0024133648 0.0055015511 0.0026877869 0.0041160000 0.0004240000 0.0025580000 0.0000000000 0.0000030000 0.0010890000 12802341 96830484 509673472 3.9628982544 4.0010151863 3.9969213009 25 0.9600000000 0.0027890853 0.0024283936 0.0055015511 0.0026594899 0.0047230000 0.0004250000 0.0021480000 0.0000030000 0.0000030000 0.0021020000 12805117 96830484 509673472 3.9617063999 4.0022802353 3.9961562157 26 1.0000000000 0.0028312423 0.0024438878 0.0055015511 0.0026071527 0.0041070000 0.0004250000 0.0025500000 0.0000010000 0.0000030000 0.0010850000 12807893 96830484 509673472 3.9554359913 4.0008039474 3.9970479012 27 1.0400000000 0.0026908601 0.0024530349 0.0055015511 0.0026328908 0.0043780000 0.0004240000 0.0025400000 0.0000030000 0.0000030000 0.0013640000 12810669 96830484 509673472 3.9496476650 4.0000371933 3.9948542118 28 1.0800000000 0.0027713049 0.0024644017 0.0055015511 0.0027076861 0.0041250000 0.0004270000 0.0025560000 0.0000000000 0.0000030000 0.0010940000 12813445 96830484 509673472 3.9448781013 4.0019001961 3.9945559502 29 1.1200000000 0.0027278329 0.0024734855 0.0055015511 0.0027861364 0.0053960000 0.0004230000 0.0028220000 0.0000030000 0.0000030000 0.0020970000 12816221 96830484 509673472 3.9388289452 4.0020222664 3.9917790890 30 1.1600000000 0.0030030743 0.0024911385 0.0055015511 0.0027896121 0.0041130000 0.0004250000 0.0025570000 0.0000010000 0.0000040000 0.0010790000 12818997 96830484 509673472 3.9293975830 4.0014457703 3.9938297272 31 1.2000000000 0.0029134697 0.0025047620 0.0055015511 0.0027658133 0.0048050000 0.0004240000 0.0029680000 0.0000030000 0.0000030000 0.0013580000 12821773 96830484 509673472 3.9228034019 4.0022144318 3.9920370579 32 1.2400000000 0.0029502921 0.0025186849 0.0055015511 0.0027655082 0.0041050000 0.0004250000 0.0025490000 0.0000000000 0.0000030000 0.0010780000 12824549 96830484 509673472 3.9160883427 4.0025353432 3.9897420406 33 1.2800000000 0.0029388322 0.0025314166 0.0055015511 0.0028074236 0.0051340000 0.0004260000 0.0025630000 0.0000030000 0.0000030000 0.0020860000 12830397 96830484 509673472 3.9104778767 4.0022206306 3.9895055294 34 1.3200000000 0.0028928840 0.0025420480 0.0055015511 0.0027808541 0.0041300000 0.0004230000 0.0025620000 0.0000000000 0.0000040000 0.0010870000 12839573 96830484 509673472 3.8820109367 4.0016808510 3.9892072678 35 1.3600000000 0.0030740034 0.0025572467 0.0055015511 0.0030478220 0.0044100000 0.0004230000 0.0025610000 0.0000030000 0.0000030000 0.0013640000 12842349 96830484 509673472 3.8787236214 4.0025434494 3.9865612984 36 1.4000000000 0.0030465741 0.0025708391 0.0055015511 0.0035590300 0.0037210000 0.0004250000 0.0021490000 0.0000000000 0.0000030000 0.0010870000 12845125 96830484 509673472 3.8730773926 4.0032992363 3.9847621918 37 1.4400000000 0.0030497839 0.0025837836 0.0055015511 0.0035973852 0.0055540000 0.0004230000 0.0029730000 0.0000030000 0.0000030000 0.0020950000 12847901 96830484 509673472 3.8621592522 4.0013198853 3.9860253334 38 1.4800000000 0.0032347857 0.0026009152 0.0055015511 0.0035571079 0.0042260000 0.0004260000 0.0026960000 0.0000000000 0.0000060000 0.0010360000 12850677 96830484 509673472 3.8505938053 4.0007586479 3.9867534637 39 1.5200000000 0.0032996268 0.0026188309 0.0055015511 0.0035142520 0.0037630000 0.0003960000 0.0020260000 0.0000030000 0.0000030000 0.0012730000 12853453 96830484 509673472 3.8474643230 4.0001368523 3.9834077358 40 1.5600000000 0.0033595394 0.0026373486 0.0055015511 0.0034974516 0.0035090000 0.0003940000 0.0020330000 0.0000000000 0.0000030000 0.0010180000 12856229 96830484 509673472 3.8375627995 3.9985218048 3.9840941429 41 1.6000000000 0.0033771237 0.0026553919 0.0055015511 0.0035179954 0.0049780000 0.0003940000 0.0025530000 0.0000040000 0.0000030000 0.0019630000 12859005 96830484 509673472 3.8271627426 3.9974079132 3.9858467579 42 1.6400000000 0.0033799068 0.0026726423 0.0055015511 0.0034791447 0.0035290000 0.0003960000 0.0020380000 0.0000000000 0.0000030000 0.0010280000 12861781 96830484 509673472 3.8137965202 3.9989016056 3.9880623817 43 1.6800000000 0.0033599804 0.0026886269 0.0055015511 0.0034583165 0.0040450000 0.0003950000 0.0022990000 0.0000030000 0.0000030000 0.0012820000 12864557 96830484 509673472 3.8069851398 3.9993276596 3.9914343357 44 1.7200000000 0.0033661884 0.0027040260 0.0055015511 0.0034889453 0.0036690000 0.0003960000 0.0021680000 0.0000000000 0.0000030000 0.0010380000 12867333 96830484 509673472 3.8006703854 3.9986772537 3.9893207550 45 1.7600000000 0.0033918242 0.0027193104 0.0055015511 0.0035075278 0.0050010000 0.0003940000 0.0025610000 0.0000040000 0.0000030000 0.0019740000 12870109 96830484 509673472 3.7923028469 4.0006680489 3.9930343628 46 1.8000000000 0.0034432332 0.0027350479 0.0055015511 0.0035142342 0.0040410000 0.0003950000 0.0025570000 0.0000000000 0.0000030000 0.0010180000 12872885 96830484 509673472 3.7863345146 4.0012741089 3.9931325912 47 1.8400000000 0.0034609591 0.0027504928 0.0055015511 0.0036200770 0.0037900000 0.0003960000 0.0020390000 0.0000030000 0.0000020000 0.0012800000 12875661 96830484 509673472 3.7833206654 3.9994668961 3.9928333759 48 1.8800000000 0.0034226219 0.0027644955 0.0055015511 0.0036631838 0.0039310000 0.0003950000 0.0024340000 0.0000000000 0.0000030000 0.0010270000 12878437 96830484 509673472 3.7787642479 3.9991862774 3.9939386845 49 1.9200000000 0.0036193100 0.0027819407 0.0055015511 0.0036249447 0.0048760000 0.0003960000 0.0024430000 0.0000030000 0.0000030000 0.0019600000 12881213 96830484 509673472 3.7716324329 4.0004019737 3.9947488308 50 1.9600000000 0.0036020253 0.0027983424 0.0055015511 0.0036102777 0.0039330000 0.0003970000 0.0024390000 0.0000010000 0.0000030000 0.0010210000 12883989 96830484 509673472 3.7573082447 4.0000443459 3.9996886253 51 2.0000000000 0.0035140107 0.0028123751 0.0055015511 0.0035844030 0.0040630000 0.0003950000 0.0023100000 0.0000030000 0.0000030000 0.0012790000 12886765 96830484 509673472 3.7588646412 3.9998886585 3.9966924191 52 2.0400000000 0.0035647256 0.0028268434 0.0055015511 0.0035492286 0.0040650000 0.0003960000 0.0025660000 0.0000000000 0.0000030000 0.0010260000 12889541 96830484 509673472 3.7549414635 4.0002875328 3.9959812164 53 2.0800000000 0.0034589334 0.0028387696 0.0055015511 0.0035930305 0.0052790000 0.0003930000 0.0028260000 0.0000030000 0.0000030000 0.0019780000 12892317 96830484 509673472 3.7529308796 3.9978303909 3.9927303791 54 2.1200000000 0.0036061904 0.0028529811 0.0055015511 0.0036678873 0.0039470000 0.0003950000 0.0024410000 0.0000000000 0.0000030000 0.0010300000 12895093 96830484 509673472 3.7399079800 3.9963834286 3.9985299110 55 2.1600000000 0.0035217302 0.0028651402 0.0055015511 0.0037628748 0.0042160000 0.0003950000 0.0024370000 0.0000030000 0.0000030000 0.0012990000 12897869 96830484 509673472 3.7375404835 3.9971230030 3.9982161522 56 2.2000000000 0.0036147384 0.0028785258 0.0055015511 0.0037702022 0.0039580000 0.0003960000 0.0024510000 0.0000000000 0.0000030000 0.0010280000 12900645 96830484 509673472 3.7177095413 3.9974887371 4.0073981285 57 2.2400000000 0.0037543508 0.0028938912 0.0055015511 0.0037490664 0.0047520000 0.0003950000 0.0023030000 0.0000030000 0.0000030000 0.0019660000 12903421 96830484 509673472 3.7129154205 3.9949150085 4.0079960823 58 2.2800000000 0.0036991327 0.0029077747 0.0055015511 0.0037578658 0.0036820000 0.0003950000 0.0021680000 0.0000000000 0.0000030000 0.0010310000 12906197 96830484 509673472 3.7035665512 3.9941790104 4.0107655525 59 2.3200000000 0.0038119289 0.0029230993 0.0055015511 0.0038959011 0.0038130000 0.0003950000 0.0020450000 0.0000040000 0.0000030000 0.0012840000 12908973 96830484 509673472 3.6894257069 3.9966034889 4.0165252686 60 2.3600000000 0.0037969921 0.0029376642 0.0055015511 0.0040111584 0.0036870000 0.0003950000 0.0021790000 0.0000000000 0.0000030000 0.0010250000 12911749 96830484 509673472 3.6862921715 3.9948878288 4.0145845413 61 2.4000000000 0.0038415659 0.0029524822 0.0055015511 0.0041276680 0.0048800000 0.0003930000 0.0024330000 0.0000030000 0.0000030000 0.0019620000 12914525 96830484 509673472 3.6795256138 3.9934599400 4.0143737793 62 2.4400000000 0.0038519476 0.0029669898 0.0055015511 0.0042929610 0.0040120000 0.0003960000 0.0024630000 0.0000000000 0.0000050000 0.0010220000 12917301 96830484 509673472 3.6558568478 3.9938809872 4.0246863365 63 2.4800000000 0.0038875362 0.0029816016 0.0055015511 0.0044370717 0.0043850000 0.0004060000 0.0025890000 0.0000040000 0.0000030000 0.0012900000 12920077 96830484 509673472 3.6471881866 3.9928195477 4.0258588791 64 2.5200000000 0.0038809592 0.0029956541 0.0055015511 0.0047966559 0.0039610000 0.0004000000 0.0024380000 0.0000000000 0.0000040000 0.0010270000 12922853 96830484 509673472 3.6346523762 3.9939305782 4.0304188728 65 2.5600000000 0.0038915584 0.0030094372 0.0055015511 0.0051044626 0.0049050000 0.0003980000 0.0024300000 0.0000030000 0.0000030000 0.0019750000 12931773 96830484 509673472 3.6208136082 3.9938168526 4.0341477394 66 2.6000000000 0.0040776967 0.0030256230 0.0055015511 0.0051955859 0.0035660000 0.0003980000 0.0020400000 0.0000010000 0.0000030000 0.0010310000 12947349 96830484 509673472 3.6103196144 3.9951491356 4.0361337662 67 2.6400000000 0.0040973444 0.0030416188 0.0055015511 0.0052467188 0.0043700000 0.0003980000 0.0025720000 0.0000040000 0.0000030000 0.0012980000 12950125 96830484 509673472 3.6001150608 3.9975602627 4.0384063721 68 2.6800000000 0.0043203449 0.0030604236 0.0055015511 0.0052299886 0.0041040000 0.0003990000 0.0025780000 0.0000000000 0.0000030000 0.0010260000 12952901 96830484 509673472 3.5891768932 3.9974370003 4.0377373695 69 2.7200000000 0.0043210322 0.0030786933 0.0055015511 0.0051934229 0.0049040000 0.0003970000 0.0024330000 0.0000030000 0.0000030000 0.0019690000 12955677 96830484 509673472 3.5796027184 3.9976992607 4.0422320366 70 2.7600000000 0.0044691442 0.0030985569 0.0055015511 0.0051655168 0.0039610000 0.0003980000 0.0024340000 0.0000000000 0.0000040000 0.0010250000 12958453 96830484 509673472 3.5707461834 3.9996323586 4.0418829918 71 2.8000000000 0.0045009977 0.0031183096 0.0055015511 0.0052159664 0.0041990000 0.0003980000 0.0024170000 0.0000040000 0.0000030000 0.0012780000 12961229 96830484 509673472 3.5635983944 4.0002312660 4.0388054848 72 2.8400000000 0.0048466693 0.0031423146 0.0055015511 0.0058973494 0.0040820000 0.0003970000 0.0025470000 0.0000010000 0.0000030000 0.0010340000 12964005 96830484 509673472 3.5478830338 4.0054097176 4.0417704582 73 2.8800000000 0.0048706639 0.0031659906 0.0055015511 0.0059701013 0.0050040000 0.0003980000 0.0025220000 0.0000030000 0.0000020000 0.0019740000 12966781 96830484 509673472 3.5378990173 4.0068225861 4.0434460640 74 2.9200000000 0.0049523395 0.0031901304 0.0055015511 0.0060608448 0.0036660000 0.0003990000 0.0021300000 0.0000000000 0.0000040000 0.0010290000 12969557 96830484 509673472 3.5358510017 4.0085158348 4.0402979851 75 2.9600000000 0.0050944239 0.0032155210 0.0055015511 0.0061155866 0.0043080000 0.0003990000 0.0025200000 0.0000030000 0.0000030000 0.0012780000 12972333 96830484 509673472 3.5346469879 4.0121555328 4.0375261307 76 3.0000000000 0.0050744712 0.0032399809 0.0055015511 0.0061499892 0.0039210000 0.0003980000 0.0023830000 0.0000000000 0.0000030000 0.0010300000 12975109 96830484 509673472 3.5366408825 4.0152044296 4.0294275284 77 3.0400000000 0.0047418405 0.0032594855 0.0055015511 0.0061733062 0.0044940000 0.0003990000 0.0019780000 0.0000040000 0.0000030000 0.0020020000 12977885 96830484 509673472 3.5357542038 4.0155291557 4.0226597786 78 3.0800000000 0.0043574874 0.0032735625 0.0055015511 0.0061424400 0.0040170000 0.0003970000 0.0024720000 0.0000000000 0.0000040000 0.0010360000 12980661 96830484 509673472 3.5369186401 4.0168824196 4.0154695511 79 3.1200000000 0.0042994614 0.0032865486 0.0055015511 0.0061043442 0.0038960000 0.0003970000 0.0020860000 0.0000030000 0.0000030000 0.0012970000 12983437 96830484 509673472 3.5298628807 4.0200643539 4.0133037567 80 3.1600000000 0.0040653758 0.0032962839 0.0055015511 0.0060686978 0.0043540000 0.0003980000 0.0028110000 0.0000000000 0.0000030000 0.0010320000 12986213 96830484 509673472 3.5259101391 4.0230660439 4.0096011162 81 3.2000000000 0.0041703563 0.0033070749 0.0055015511 0.0060408276 0.0070640000 0.0003990000 0.0045520000 0.0000030000 0.0000030000 0.0019980000 12988989 96830484 509673472 3.5140922070 4.0221219063 4.0126113892 82 3.2400000000 0.0043994314 0.0033203963 0.0055015511 0.0060490054 0.0043670000 0.0003980000 0.0028120000 0.0000010000 0.0000030000 0.0010420000 12991765 96830484 509673472 3.5058872700 4.0222706795 4.0121884346 83 3.2800000000 0.0043160873 0.0033323926 0.0055015511 0.0060868350 0.0038960000 0.0003980000 0.0020720000 0.0000030000 0.0000030000 0.0013050000 12994541 96830484 509673472 3.4979910851 4.0243487358 4.0090532303 84 3.3200000000 0.0043093422 0.0033440230 0.0055015511 0.0060778719 0.0039890000 0.0003990000 0.0024310000 0.0000000000 0.0000030000 0.0010380000 12997317 96830484 509673472 3.4852666855 4.0233683586 4.0093283653 85 3.3600000000 0.0045079975 0.0033577168 0.0055015511 0.0060685334 0.0056610000 0.0003970000 0.0031490000 0.0000040000 0.0000030000 0.0019920000 13000093 96830484 509673472 3.4720723629 4.0242362022 4.0097374916 86 3.4000000000 0.0044961269 0.0033709541 0.0055015511 0.0061071517 0.0043320000 0.0003990000 0.0027730000 0.0000000000 0.0000030000 0.0010410000 13002869 96830484 509673472 3.4570422173 4.0251412392 4.0137987137 87 3.4400000000 0.0041861450 0.0033803241 0.0055015511 0.0062325877 0.0042180000 0.0003970000 0.0024010000 0.0000030000 0.0000020000 0.0012940000 13005645 96830484 509673472 3.4469790459 4.0238537788 4.0134687424 88 3.4800000000 0.0038641291 0.0033858219 0.0055015511 0.0063830288 0.0035930000 0.0003980000 0.0020340000 0.0000010000 0.0000030000 0.0010380000 13008421 96830484 509673472 3.4335215092 4.0241298676 4.0137062073 89 3.5200000000 0.0040299422 0.0033930592 0.0055015511 0.0065297679 0.0052730000 0.0003970000 0.0027430000 0.0000040000 0.0000030000 0.0020050000 13011197 96830484 509673472 3.4245271683 4.0243425369 4.0138106346 90 3.5600000000 0.0044025057 0.0034042753 0.0055015511 0.0066381371 0.0036910000 0.0003990000 0.0021320000 0.0000000000 0.0000040000 0.0010340000 13013973 96830484 509673472 3.4175684452 4.0225906372 4.0125837326 91 3.6000000000 0.0041462174 0.0034124285 0.0055015511 0.0066785265 0.0040880000 0.0003980000 0.0022380000 0.0000030000 0.0000020000 0.0013230000 13016749 96830484 509673472 3.4026930332 4.0212779045 4.0156178474 92 3.6400000000 0.0042098621 0.0034210962 0.0055015511 0.0066904798 0.0038040000 0.0003990000 0.0022450000 0.0000000000 0.0000030000 0.0010330000 13019525 96830484 509673472 3.3876020908 4.0233888626 4.0208144188 93 3.6800000000 0.0041152774 0.0034285606 0.0055015511 0.0066699094 0.0047570000 0.0003970000 0.0022270000 0.0000030000 0.0000030000 0.0020000000 13022301 96830484 509673472 3.3826243877 4.0225024223 4.0174145699 94 3.7200000000 0.0040466669 0.0034351362 0.0055015511 0.0066420579 0.0041560000 0.0003980000 0.0025930000 0.0000000000 0.0000040000 0.0010310000 13025077 96830484 509673472 3.3753571510 4.0200653076 4.0169701576 95 3.7600000000 0.0041561369 0.0034427256 0.0055015511 0.0066274875 0.0041700000 0.0003960000 0.0023500000 0.0000030000 0.0000030000 0.0012900000 13027853 96830484 509673472 3.3624589443 4.0213980675 4.0235280991 96 3.8000000000 0.0040898337 0.0034494663 0.0055015511 0.0065997872 0.0041470000 0.0003970000 0.0025870000 0.0000010000 0.0000030000 0.0010300000 13030629 96830484 509673472 3.3521382809 4.0208730698 4.0231080055 97 3.8400000000 0.0042554373 0.0034577753 0.0055015511 0.0065660211 0.0048850000 0.0003980000 0.0023500000 0.0000030000 0.0000020000 0.0019990000 13033405 96830484 509673472 3.3468508720 4.0181565285 4.0250062943 98 3.8800000000 0.0042275456 0.0034656301 0.0055015511 0.0065406138 0.0037940000 0.0004000000 0.0022270000 0.0000010000 0.0000030000 0.0010320000 13036181 96830484 509673472 3.3322305679 4.0175251961 4.0290789604 99 3.9200000000 0.0043088249 0.0034741472 0.0055015511 0.0065134503 0.0041760000 0.0003950000 0.0023300000 0.0000030000 0.0000030000 0.0013120000 13038957 96830484 509673472 3.3268020153 4.0189337730 4.0322198868 100 3.9600000000 0.0044690496 0.0034840963 0.0055015511 0.0064807935 0.0037980000 0.0003980000 0.0022230000 0.0000010000 0.0000030000 0.0010380000 13041733 96830484 509673472 3.3189003468 4.0183334351 4.0362596512 101 4.0000000000 0.0041833599 0.0034910197 0.0055015511 0.0064511219 0.0054920000 0.0004000000 0.0029310000 0.0000030000 0.0000030000 0.0020180000 13044509 96830484 509673472 3.3098387718 4.0166215897 4.0422787666 102 4.0400000000 0.0041824323 0.0034977982 0.0055015511 0.0064307220 0.0038250000 0.0003970000 0.0022530000 0.0000000000 0.0000030000 0.0010340000 13047285 96830484 509673472 3.3061685562 4.0152349472 4.0438976288 103 4.0800000000 0.0041300105 0.0035039362 0.0055015511 0.0064001433 0.0040730000 0.0003980000 0.0022250000 0.0000030000 0.0000020000 0.0013040000 13050061 96830484 509673472 3.2954182625 4.0147414207 4.0505309105 104 4.1200000000 0.0043187356 0.0035117708 0.0055015511 0.0063752011 0.0042720000 0.0004420000 0.0026040000 0.0000010000 0.0000040000 0.0010540000 13052837 96830484 509673472 3.2830889225 4.0128827095 4.0633401871 105 4.1600000000 0.0042486768 0.0035187890 0.0055015511 0.0063732640 0.0048200000 0.0004040000 0.0022240000 0.0000040000 0.0000030000 0.0020380000 13055613 96830484 509673472 3.2800836563 4.0127511024 4.0651054382 106 4.2000000000 0.0043454953 0.0035265881 0.0055015511 0.0063829235 0.0042960000 0.0003990000 0.0027140000 0.0000000000 0.0000030000 0.0010360000 13058389 96830484 509673472 3.2739670277 4.0132446289 4.0701570511 107 4.2400000000 0.0044658165 0.0035353659 0.0055015511 0.0063664244 0.0040980000 0.0003990000 0.0022330000 0.0000040000 0.0000030000 0.0013150000 13061165 96830484 509673472 3.2737631798 4.0100226402 4.0664796829 108 4.2800000000 0.0041308873 0.0035408800 0.0055015511 0.0063377503 0.0039300000 0.0003970000 0.0023520000 0.0000000000 0.0000040000 0.0010300000 13063941 96830484 509673472 3.2635629177 4.0090346336 4.0749340057 109 4.3200000000 0.0042456407 0.0035473457 0.0055015511 0.0063187262 0.0051940000 0.0003980000 0.0025990000 0.0000030000 0.0000030000 0.0020430000 13066717 96830484 509673472 3.2618083954 4.0092091560 4.0760202408 110 4.3600000000 0.0047162338 0.0035579720 0.0055015511 0.0063306059 0.0038530000 0.0004000000 0.0022620000 0.0000000000 0.0000030000 0.0010400000 13069493 96830484 509673472 3.2547655106 4.0085163116 4.0843892097 111 4.4000000000 0.0043509034 0.0035651155 0.0055015511 0.0063284376 0.0041240000 0.0003990000 0.0022470000 0.0000030000 0.0000030000 0.0013230000 13072269 96830484 509673472 3.2477705479 4.0073041916 4.0910844803 112 4.4400000000 0.0043603014 0.0035722154 0.0055015511 0.0063294915 0.0039730000 0.0003970000 0.0023820000 0.0000000000 0.0000040000 0.0010380000 13075045 96830484 509673472 3.2398099899 4.0079455376 4.0989503860 113 4.4800000000 0.0044167275 0.0035796889 0.0055015511 0.0063361432 0.0048580000 0.0003980000 0.0022530000 0.0000040000 0.0000030000 0.0020470000 13077821 96830484 509673472 3.2356553078 4.0078215599 4.1031556129 114 4.5200000000 0.0044326698 0.0035871712 0.0055015511 0.0063829178 0.0042140000 0.0003960000 0.0026260000 0.0000010000 0.0000030000 0.0010340000 13080597 96830484 509673472 3.2248802185 4.0076951981 4.1154427528 115 4.5600000000 0.0044092713 0.0035943199 0.0055015511 0.0064050644 0.0041180000 0.0003970000 0.0022480000 0.0000030000 0.0000030000 0.0013120000 13083373 96830484 509673472 3.2241582870 4.0075912476 4.1172785759 116 4.6000000000 0.0044552204 0.0036017415 0.0055015511 0.0064461014 0.0039790000 0.0003970000 0.0023830000 0.0000000000 0.0000030000 0.0010420000 13086149 96830484 509673472 3.2137994766 4.0102262497 4.1293282509 117 4.6400000000 0.0045301323 0.0036096764 0.0055015511 0.0064536201 0.0044630000 0.0003970000 0.0018780000 0.0000030000 0.0000030000 0.0020240000 13088925 96830484 509673472 3.2062170506 4.0131716728 4.1397786140 118 4.6800000000 0.0044905161 0.0036171412 0.0055015511 0.0064264189 0.0039610000 0.0003980000 0.0023580000 0.0000000000 0.0000030000 0.0010430000 13091701 96830484 509673472 3.2005338669 4.0115981102 4.1439752579 119 4.7200000000 0.0043853414 0.0036235966 0.0055015511 0.0064043524 0.0041200000 0.0003980000 0.0022400000 0.0000040000 0.0000030000 0.0013170000 13094477 96830484 509673472 3.1941065788 4.0111169815 4.1509766579 120 4.7600000000 0.0043745786 0.0036298548 0.0055015511 0.0063796496 0.0060220000 0.0003980000 0.0044180000 0.0000010000 0.0000030000 0.0010410000 13097253 96830484 509673472 3.1872184277 4.0124707222 4.1592063904 121 4.8000000000 0.0042411303 0.0036349067 0.0055015511 0.0063623810 0.0055450000 0.0003970000 0.0029560000 0.0000040000 0.0000030000 0.0020250000 13100029 96830484 509673472 3.1777899265 4.0119318962 4.1769351959 122 4.8400000000 0.0043888805 0.0036410868 0.0055015511 0.0063399567 0.0038360000 0.0003980000 0.0022290000 0.0000010000 0.0000030000 0.0010420000 13102805 96830484 509673472 3.1763195992 4.0134382248 4.1777811050 123 4.8800000000 0.0044055404 0.0036473019 0.0055015511 0.0063178094 0.0045870000 0.0003980000 0.0027000000 0.0000030000 0.0000030000 0.0013200000 13105581 96830484 509673472 3.1706607342 4.0176057816 4.1841592789 124 4.9200000000 0.0046009091 0.0036549922 0.0055015511 0.0062978287 0.0043100000 0.0003980000 0.0027030000 0.0000000000 0.0000030000 0.0010380000 13108357 96830484 509673472 3.1615464687 4.0185523033 4.2000665665 125 4.9600000000 0.0045762532 0.0036623623 0.0055015511 0.0062877022 0.0049150000 0.0003980000 0.0023450000 0.0000030000 0.0000030000 0.0020020000 13111133 96830484 509673472 3.1571626663 4.0183296204 4.2050652504 126 5.0000000000 0.0043872287 0.0036681152 0.0055015511 0.0062683559 0.0042010000 0.0003990000 0.0025940000 0.0000010000 0.0000030000 0.0010380000 13113909 96830484 509673472 3.1521556377 4.0194320679 4.2123508453 127 5.0400000000 0.0045894142 0.0036753696 0.0055015511 0.0062440999 0.0041200000 0.0003970000 0.0022330000 0.0000030000 0.0000030000 0.0013180000 13116685 96830484 509673472 3.1428625584 4.0204434395 4.2293457985 128 5.0800000000 0.0045449371 0.0036821631 0.0055015511 0.0062215730 0.0039680000 0.0003990000 0.0023500000 0.0000000000 0.0000030000 0.0010450000 13119461 96830484 509673472 3.1373460293 4.0202531815 4.2351269722 129 5.1200000000 0.0045419862 0.0036888284 0.0055015511 0.0061986321 0.0049350000 0.0003980000 0.0023430000 0.0000030000 0.0000030000 0.0020120000 13134525 96830484 509673472 3.1333973408 4.0206022263 4.2417912483 130 5.1600000000 0.0044211829 0.0036944619 0.0055015511 0.0061938690 0.0042140000 0.0003990000 0.0025890000 0.0000000000 0.0000030000 0.0010490000 13162901 96830484 509673472 3.1246552467 4.0203957558 4.2597913742 131 5.2000000000 0.0045658811 0.0037011139 0.0055015511 0.0062249239 0.0042370000 0.0003980000 0.0023440000 0.0000040000 0.0000030000 0.0013130000 13165677 96830484 509673472 3.1212174892 4.0209646225 4.2639012337 132 5.2400000000 0.0045076851 0.0037072243 0.0055015511 0.0062369436 0.0039600000 0.0003960000 0.0023400000 0.0000000000 0.0000040000 0.0010420000 13168453 96830484 509673472 3.1207387447 4.0206923485 4.2615709305 133 5.2800000000 0.0044369483 0.0037127109 0.0055015511 0.0062368092 0.0049450000 0.0003970000 0.0023420000 0.0000030000 0.0000030000 0.0020220000 13171229 96830484 509673472 3.1103410721 4.0208978653 4.2806963921 134 5.3200000000 0.0049509592 0.0037219516 0.0055015511 0.0062691717 0.0038500000 0.0004010000 0.0022200000 0.0000000000 0.0000030000 0.0010470000 13174005 96830484 509673472 3.1018047333 4.0237231255 4.2973408699 135 5.3600000000 0.0050950567 0.0037321227 0.0055015511 0.0062898416 0.0041250000 0.0003980000 0.0022110000 0.0000040000 0.0000030000 0.0013310000 13176781 96830484 509673472 3.0986595154 4.0242085457 4.3013195992 136 5.4000000000 0.0052635367 0.0037433831 0.0055015511 0.0063267739 0.0039670000 0.0003980000 0.0023350000 0.0000000000 0.0000030000 0.0010480000 13179557 96830484 509673472 3.0919308662 4.0243411064 4.3133587837 137 5.4400000000 0.0052027917 0.0037540358 0.0055015511 0.0063797597 0.0049580000 0.0003960000 0.0023450000 0.0000030000 0.0000030000 0.0020310000 13182333 96830484 509673472 3.0865361691 4.0247192383 4.3225984573 138 5.4800000000 0.0052038999 0.0037645420 0.0055015511 0.0064223031 0.0038460000 0.0003960000 0.0022230000 0.0000010000 0.0000030000 0.0010410000 13185109 96830484 509673472 3.0809524059 4.0238685608 4.3272933960 139 5.5200000000 0.0050571710 0.0037738415 0.0055015511 0.0064647493 0.0041330000 0.0003970000 0.0022200000 0.0000030000 0.0000030000 0.0013250000 13187885 96830484 509673472 3.0748412609 4.0217156410 4.3324899673 140 5.5600000000 0.0050816773 0.0037831832 0.0055015511 0.0065367526 0.0039890000 0.0003980000 0.0023480000 0.0000000000 0.0000030000 0.0010510000 13190661 96830484 509673472 3.0655717850 4.0224575996 4.3467669487 141 5.6000000000 0.0050855028 0.0037924195 0.0055015511 0.0065705596 0.0048370000 0.0003980000 0.0022220000 0.0000030000 0.0000030000 0.0020220000 13193437 96830484 509673472 3.0601952076 4.0236697197 4.3522353172 142 5.6400000000 0.0051267003 0.0038018159 0.0055015511 0.0066051338 0.0036250000 0.0003980000 0.0019890000 0.0000010000 0.0000030000 0.0010480000 13196213 96830484 509673472 3.0509710312 4.0237722397 4.3669514656 143 5.6800000000 0.0051577762 0.0038112981 0.0055015511 0.0066816661 0.0041730000 0.0003970000 0.0022370000 0.0000040000 0.0000030000 0.0013420000 13198989 96830484 509673472 3.0457365513 4.0260252953 4.3769559860 144 5.7200000000 0.0052310433 0.0038211574 0.0055015511 0.0067255132 0.0039070000 0.0003980000 0.0022560000 0.0000000000 0.0000040000 0.0010570000 13201765 96830484 509673472 3.0395276546 4.0277652740 4.3848271370 145 5.7600000000 0.0052077551 0.0038307202 0.0055015511 0.0067255252 0.0048610000 0.0003970000 0.0022460000 0.0000030000 0.0000020000 0.0020210000 13204541 96830484 509673472 3.0339641571 4.0268282890 4.3915762901 146 5.8000000000 0.0052451137 0.0038404078 0.0055015511 0.0067167888 0.0040100000 0.0003960000 0.0023630000 0.0000000000 0.0000030000 0.0010550000 13207317 96830484 509673472 3.0281231403 4.0269808769 4.4010467529 147 5.8400000000 0.0052808914 0.0038502070 0.0055015511 0.0067002993 0.0041850000 0.0003980000 0.0022420000 0.0000040000 0.0000030000 0.0013430000 13210093 96830484 509673472 3.0179359913 4.0262284279 4.4219789505 148 5.8800000000 0.0053074518 0.0038600533 0.0055015511 0.0066797245 0.0040270000 0.0003960000 0.0023590000 0.0000000000 0.0000030000 0.0010700000 13212869 96830484 509673472 3.0165126324 4.0261392593 4.4253592491 149 5.9200000000 0.0052760998 0.0038695569 0.0055015511 0.0066631086 0.0048940000 0.0003960000 0.0022350000 0.0000030000 0.0000030000 0.0020580000 13215645 96830484 509673472 3.0121576786 4.0268230438 4.4364209175 150 5.9600000000 0.0053268955 0.0038792725 0.0055015511 0.0066447321 0.0040270000 0.0003990000 0.0023600000 0.0000010000 0.0000030000 0.0010670000 13218421 96830484 509673472 3.0085952282 4.0266041756 4.4451346397 151 6.0000000000 0.0053692479 0.0038891399 0.0055015511 0.0066261101 0.0042120000 0.0003980000 0.0022540000 0.0000040000 0.0000030000 0.0013540000 13221197 96830484 509673472 3.0052974224 4.0271205902 4.4548664093 152 6.0400000000 0.0053455778 0.0038987217 0.0055015511 0.0066126065 0.0039140000 0.0003970000 0.0022430000 0.0000000000 0.0000030000 0.0010670000 13223973 96830484 509673472 3.0021955967 4.0284247398 4.4656457901 153 6.0800000000 0.0054274574 0.0039087135 0.0055015511 0.0066018790 0.0047910000 0.0003970000 0.0021280000 0.0000030000 0.0000020000 0.0020590000 13226749 96830484 509673472 2.9985527992 4.0274677277 4.4742336273 154 6.1200000000 0.0053975401 0.0039183812 0.0055015511 0.0066206748 0.0036580000 0.0003970000 0.0019860000 0.0000000000 0.0000030000 0.0010660000 13229525 96830484 509673472 2.9940743446 4.0267791748 4.4865503311 155 6.1600000000 0.0053812792 0.0039278192 0.0055015511 0.0066840132 0.0043220000 0.0003960000 0.0023520000 0.0000030000 0.0000030000 0.0013630000 13232301 96830484 509673472 2.9924228191 4.0258522034 4.4941554070 156 6.2000000000 0.0053935330 0.0039372148 0.0055015511 0.0067957865 0.0042900000 0.0003970000 0.0026060000 0.0000000000 0.0000040000 0.0010760000 13235077 96830484 509673472 2.9877269268 4.0269794464 4.5091171265 157 6.2400000000 0.0054101413 0.0039465965 0.0055015511 0.0068866472 0.0050200000 0.0003970000 0.0023460000 0.0000030000 0.0000020000 0.0020630000 13237853 96830484 509673472 2.9854710102 4.0275936127 4.5200409889 158 6.2800000000 0.0054019168 0.0039558074 0.0055015511 0.0069635139 0.0040530000 0.0003970000 0.0023610000 0.0000000000 0.0000030000 0.0010790000 13240629 96830484 509673472 2.9824733734 4.0278787613 4.5365486145 159 6.3200000000 0.0054337368 0.0039651026 0.0055015511 0.0069939671 0.0041130000 0.0003980000 0.0021180000 0.0000030000 0.0000030000 0.0013820000 13243405 96830484 509673472 2.9819092751 4.0272893906 4.5442638397 160 6.3600000000 0.0054282551 0.0039742473 0.0055015511 0.0070316601 0.0039300000 0.0003960000 0.0022400000 0.0000010000 0.0000030000 0.0010810000 13246181 96830484 509673472 2.9807803631 4.0286645889 4.5597090721 161 6.4000000000 0.0055286461 0.0039839019 0.0055286461 0.0070169335 0.0048960000 0.0003980000 0.0022230000 0.0000040000 0.0000030000 0.0020560000 13248957 96830484 509673472 2.9809012413 4.0291776657 4.5705718994 162 6.4400000000 0.0056188568 0.0039939942 0.0056188568 0.0069973589 0.0040520000 0.0003980000 0.0023540000 0.0000000000 0.0000040000 0.0010810000 13251733 96830484 509673472 2.9807972908 4.0274944305 4.5817489624 163 6.4800000000 0.0055624577 0.0040036167 0.0056188568 0.0069805798 0.0042380000 0.0003980000 0.0022260000 0.0000030000 0.0000020000 0.0013930000 13254509 96830484 509673472 2.9798259735 4.0287628174 4.5947461128 164 6.5200000000 0.0055745235 0.0040131954 0.0056188568 0.0069641183 0.0041910000 0.0003960000 0.0024860000 0.0000010000 0.0000030000 0.0010910000 13257285 96830484 509673472 2.9797205925 4.0301423073 4.6065702438 165 6.5600000000 0.0056312690 0.0040230019 0.0056312690 0.0069546300 0.0049340000 0.0003970000 0.0022350000 0.0000030000 0.0000020000 0.0020780000 13260061 96830484 509673472 2.9786863327 4.0314221382 4.6245646477 166 6.6000000000 0.0056379130 0.0040327303 0.0056379130 0.0069716502 0.0039500000 0.0003970000 0.0022390000 0.0000000000 0.0000040000 0.0010920000 13262837 96830484 509673472 2.9794631004 4.0321283340 4.6358709335 167 6.6400000000 0.0056015439 0.0040421244 0.0056379130 0.0069789813 0.0042800000 0.0003980000 0.0022370000 0.0000030000 0.0000020000 0.0014200000 13265613 96830484 509673472 2.9805140495 4.0339975357 4.6462459564 168 6.6800000000 0.0056427028 0.0040516516 0.0056427028 0.0069812043 0.0039340000 0.0003970000 0.0022180000 0.0000000000 0.0000030000 0.0010960000 13268389 96830484 509673472 2.9810287952 4.0342435837 4.6586809158 169 6.7200000000 0.0056608310 0.0040611734 0.0056608310 0.0069677157 0.0054330000 0.0003970000 0.0027160000 0.0000030000 0.0000030000 0.0020910000 13271165 96830484 509673472 2.9810914993 4.0320711136 4.6730828285 170 6.7600000000 0.0056843879 0.0040707217 0.0056843879 0.0069597897 0.0039560000 0.0003990000 0.0022320000 0.0000000000 0.0000040000 0.0010970000 13273941 96830484 509673472 2.9791998863 4.0341596603 4.6901674271 171 6.8000000000 0.0056571336 0.0040799990 0.0056843879 0.0069530611 0.0042700000 0.0003990000 0.0022320000 0.0000030000 0.0000030000 0.0014070000 13276717 96830484 509673472 2.9802639484 4.0368928909 4.6993741989 172 6.8400000000 0.0057266806 0.0040895727 0.0057266806 0.0069348196 0.0039750000 0.0003970000 0.0022490000 0.0000010000 0.0000030000 0.0010960000 13279493 96830484 509673472 2.9807951450 4.0381984711 4.7123975754 173 6.8800000000 0.0057206945 0.0040990012 0.0057266806 0.0069156234 0.0054340000 0.0003970000 0.0027080000 0.0000030000 0.0000030000 0.0020960000 13282269 96830484 509673472 2.9804234505 4.0398039818 4.7263231277 174 6.9200000000 0.0057963300 0.0041087559 0.0057963300 0.0068962113 0.0039560000 0.0003980000 0.0022270000 0.0000010000 0.0000030000 0.0010970000 13285045 96830484 509673472 2.9793746471 4.0416250229 4.7389674187 175 6.9600000000 0.0057795374 0.0041183033 0.0057963300 0.0068764325 0.0042980000 0.0003980000 0.0022290000 0.0000030000 0.0000020000 0.0014000000 13287821 96830484 509673472 2.9798502922 4.0425524712 4.7507953644 176 7.0000000000 0.0058102859 0.0041279168 0.0058102859 0.0068606964 0.0037700000 0.0004000000 0.0020050000 0.0000000000 0.0000040000 0.0010950000 13290597 96830484 509673472 2.9785783291 4.0429191589 4.7653398514 177 7.0400000000 0.0058318935 0.0041375438 0.0058318935 0.0068712717 0.0050100000 0.0004010000 0.0022510000 0.0000040000 0.0000030000 0.0020830000 13293373 96830484 509673472 2.9796292782 4.0405187607 4.7724251747 178 7.0800000000 0.0058777933 0.0041473205 0.0058777933 0.0068570921 0.0036410000 0.0003990000 0.0018780000 0.0000000000 0.0000030000 0.0010930000 13296149 96830484 509673472 2.9808826447 4.0401020050 4.7797036171 179 7.1200000000 0.0057799108 0.0041564411 0.0058777933 0.0068430768 0.0043510000 0.0003990000 0.0022660000 0.0000040000 0.0000030000 0.0014050000 13298925 96830484 509673472 2.9810791016 4.0424814224 4.7933559418 180 7.1600000000 0.0058091911 0.0041656230 0.0058777933 0.0068247817 0.0040200000 0.0004000000 0.0022470000 0.0000000000 0.0000030000 0.0010970000 13301701 96830484 509673472 2.9818780422 4.0449323654 4.8063964844 181 7.2000000000 0.0058111027 0.0041747141 0.0058777933 0.0068100599 0.0046460000 0.0003990000 0.0018800000 0.0000040000 0.0000030000 0.0020870000 13304477 96830484 509673472 2.9840197563 4.0455880165 4.8172211647 182 7.2400000000 0.0058332621 0.0041838270 0.0058777933 0.0067932005 0.0037930000 0.0004000000 0.0020160000 0.0000000000 0.0000050000 0.0011000000 13307253 96830484 509673472 2.9836959839 4.0458641052 4.8311939240 183 7.2800000000 0.0058430680 0.0041928939 0.0058777933 0.0067780830 0.0044540000 0.0004000000 0.0023650000 0.0000040000 0.0000040000 0.0014050000 13310029 96830484 509673472 2.9820084572 4.0464444160 4.8473682404 184 7.3200000000 0.0058487826 0.0042018933 0.0058777933 0.0067601524 0.0041350000 0.0004000000 0.0023640000 0.0000000000 0.0000040000 0.0010920000 13312805 96830484 509673472 2.9841961861 4.0460104942 4.8579773903 185 7.3600000000 0.0058368095 0.0042107307 0.0058777933 0.0067444853 0.0050440000 0.0004010000 0.0022590000 0.0000030000 0.0000030000 0.0020950000 13315581 96830484 509673472 2.9857387543 4.0463008881 4.8733549118 186 7.4000000000 0.0057915095 0.0042192295 0.0058777933 0.0067320655 0.0040370000 0.0004010000 0.0022550000 0.0000000000 0.0000040000 0.0010960000 13318357 96830484 509673472 2.9855985641 4.0459337234 4.8914747238 187 7.4400000000 0.0057636858 0.0042274886 0.0058777933 0.0067256439 0.0048430000 0.0004000000 0.0027140000 0.0000030000 0.0000030000 0.0014380000 13321133 96830484 509673472 2.9887242317 4.0459308624 4.8998761177 188 7.4800000000 0.0057792170 0.0042357425 0.0058777933 0.0067341239 0.0044910000 0.0004500000 0.0026090000 0.0000000000 0.0000030000 0.0011240000 13323909 96830484 509673472 2.9911038876 4.0494847298 4.9153175354 189 7.5200000000 0.0057374379 0.0042436879 0.0058777933 0.0067179987 0.0048220000 0.0004030000 0.0018710000 0.0000030000 0.0000030000 0.0022790000 13326685 96830484 509673472 2.9932599068 4.0521392822 4.9329338074 190 7.5600000000 0.0058082659 0.0042519226 0.0058777933 0.0067079569 0.0040060000 0.0004000000 0.0022360000 0.0000000000 0.0000030000 0.0011100000 13329461 96830484 509673472 2.9955294132 4.0511288643 4.9477066994 191 7.6000000000 0.0058088265 0.0042600739 0.0058777933 0.0066962684 0.0043140000 0.0003970000 0.0022370000 0.0000030000 0.0000030000 0.0014170000 13332237 96830484 509673472 2.9968359470 4.0533871651 4.9640116692 192 7.6400000000 0.0059125400 0.0042686805 0.0059125400 0.0066890655 0.0040020000 0.0003980000 0.0022320000 0.0000010000 0.0000030000 0.0011130000 13335013 96830484 509673472 3.0005047321 4.0595703125 4.9790940285 193 7.6800000000 0.0059914929 0.0042776070 0.0059914929 0.0066904874 0.0053830000 0.0003970000 0.0026090000 0.0000030000 0.0000030000 0.0021130000 13337789 96830484 509673472 3.0005235672 4.0601081848 4.9973883629 194 7.7200000000 0.0061021987 0.0042870121 0.0061021987 0.0066878278 0.0040200000 0.0004040000 0.0022330000 0.0000000000 0.0000040000 0.0011220000 13340565 96830484 509673472 3.0002632141 4.0561037064 5.0136933327 195 7.7600000000 0.0060857469 0.0042962364 0.0061021987 0.0066909870 0.0039530000 0.0003980000 0.0018700000 0.0000030000 0.0000020000 0.0014180000 13343341 96830484 509673472 3.0014877319 4.0556716919 5.0267190933 196 7.8000000000 0.0060643093 0.0043052571 0.0061021987 0.0067278308 0.0040250000 0.0003990000 0.0022370000 0.0000010000 0.0000030000 0.0011260000 13346117 96830484 509673472 3.0033607483 4.0593199730 5.0434827805 197 7.8400000000 0.0061500561 0.0043146216 0.0061500561 0.0067534488 0.0051460000 0.0003980000 0.0023470000 0.0000030000 0.0000030000 0.0021320000 13348893 96830484 509673472 3.0052099228 4.0627899170 5.0555558205 198 7.8800000000 0.0060171690 0.0043232203 0.0061500561 0.0067713834 0.0039170000 0.0004010000 0.0021220000 0.0000000000 0.0000030000 0.0011270000 13351669 96830484 509673472 3.0063338280 4.0664367676 5.0721011162 199 7.9200000000 0.0060552228 0.0043319239 0.0061500561 0.0067645900 0.0043340000 0.0003980000 0.0022220000 0.0000030000 0.0000030000 0.0014440000 13354445 96830484 509673472 3.0084040165 4.0674023628 5.0879073143 200 7.9600000000 0.0062433127 0.0043414808 0.0062433127 0.0067552328 0.0040420000 0.0003980000 0.0022340000 0.0000010000 0.0000030000 0.0011420000 13357221 96830484 509673472 3.0085837841 4.0659961700 5.1019749641 201 8.0000000000 0.0061993464 0.0043507239 0.0062433127 0.0067705383 0.0050390000 0.0003990000 0.0022240000 0.0000030000 0.0000030000 0.0021440000 13359997 96830484 509673472 3.0092198849 4.0664038658 5.1206936836 202 8.0400000000 0.0061744615 0.0043597523 0.0062433127 0.0067876655 0.0041630000 0.0003970000 0.0023510000 0.0000000000 0.0000030000 0.0011430000 13362773 96830484 509673472 3.0120339394 4.0673012733 5.1309661865 203 8.0800000000 0.0062667690 0.0043691465 0.0062667690 0.0067971930 0.0043670000 0.0003970000 0.0022290000 0.0000030000 0.0000030000 0.0014620000 13365549 96830484 509673472 3.0143363476 4.0690822601 5.1484045982 204 8.1200000000 0.0061378600 0.0043778167 0.0062667690 0.0067893842 0.0040510000 0.0003980000 0.0022330000 0.0000010000 0.0000030000 0.0011470000 13368325 96830484 509673472 3.0162239075 4.0684924126 5.1606812477 205 8.1600000000 0.0062076291 0.0043867426 0.0062667690 0.0067815234 0.0050810000 0.0003980000 0.0022240000 0.0000030000 0.0000030000 0.0021790000 13371101 96830484 509673472 3.0191428661 4.0674738884 5.1724519730 206 8.1999999990 0.0062210215 0.0043956468 0.0062667690 0.0067722635 0.0044090000 0.0003980000 0.0025840000 0.0000000000 0.0000030000 0.0011480000 13373877 96830484 509673472 3.0225040913 4.0675692558 5.1859960556 207 8.2400000000 0.0062034870 0.0044043804 0.0062667690 0.0067650326 0.0043790000 0.0003990000 0.0022300000 0.0000040000 0.0000030000 0.0014680000 13376653 96830484 509673472 3.0270359516 4.0703945160 5.1995906830 208 8.2799999990 0.0061653703 0.0044128467 0.0062667690 0.0067523339 0.0040510000 0.0003990000 0.0022240000 0.0000000000 0.0000030000 0.0011480000 13379429 96830484 509673472 3.0312514305 4.0725197792 5.2121906281 209 8.3200000000 0.0062722573 0.0044217434 0.0062722573 0.0067497083 0.0047210000 0.0003990000 0.0018700000 0.0000030000 0.0000030000 0.0021660000 13382205 96830484 509673472 3.0358080864 4.0743994713 5.2252998352 210 8.3599999990 0.0062816082 0.0044305999 0.0062816082 0.0067736492 0.0041770000 0.0003960000 0.0023490000 0.0000000000 0.0000030000 0.0011480000 13384981 96830484 509673472 3.0414373875 4.0752453804 5.2363162041 211 8.4000000000 0.0063410904 0.0044396543 0.0063410904 0.0067933879 0.0043990000 0.0003990000 0.0022280000 0.0000040000 0.0000030000 0.0014830000 13387757 96830484 509673472 3.0464916229 4.0734281540 5.2500743866 212 8.4399999990 0.0063801347 0.0044488075 0.0063801347 0.0067795258 0.0038230000 0.0003980000 0.0019910000 0.0000000000 0.0000030000 0.0011490000 13390533 96830484 509673472 3.0537750721 4.0763788223 5.2616963387 213 8.4800000000 0.0064225332 0.0044580739 0.0064225332 0.0067811308 0.0052110000 0.0003990000 0.0023380000 0.0000030000 0.0000030000 0.0021830000 13393309 96830484 509673472 3.0602052212 4.0803074837 5.2761926651 214 8.5200000000 0.0064715529 0.0044674826 0.0064715529 0.0068439794 0.0040690000 0.0004000000 0.0022090000 0.0000000000 0.0000030000 0.0011540000 13396085 96830484 509673472 3.0672638416 4.0806159973 5.2883310318 215 8.5600000000 0.0064998376 0.0044769354 0.0064998376 0.0068534144 0.0045010000 0.0004000000 0.0023210000 0.0000030000 0.0000030000 0.0014880000 13398861 96830484 509673472 3.0751450062 4.0799407959 5.2988371849 216 8.6000000000 0.0065783253 0.0044866641 0.0065783253 0.0068386360 0.0040540000 0.0003970000 0.0022080000 0.0000010000 0.0000030000 0.0011560000 13401637 96830484 509673472 3.0844509602 4.0844588280 5.3104386330 217 8.6400000000 0.0067020943 0.0044968735 0.0067020943 0.0068625340 0.0051080000 0.0003970000 0.0022070000 0.0000040000 0.0000030000 0.0022070000 13404413 96830484 509673472 3.0934443474 4.0874881744 5.3273048401 218 8.6800000000 0.0065605817 0.0045063400 0.0067020943 0.0069131246 0.0040670000 0.0004000000 0.0022020000 0.0000010000 0.0000030000 0.0011700000 13407189 96830484 509673472 3.1018726826 4.0872259140 5.3363728523 219 8.7200000000 0.0067113610 0.0045164086 0.0067113610 0.0069131941 0.0043590000 0.0003980000 0.0021920000 0.0000030000 0.0000030000 0.0014710000 13409965 96830484 509673472 3.1120402813 4.0900874138 5.3467040062 220 8.7600000000 0.0068521942 0.0045270258 0.0068521942 0.0069164090 0.0040590000 0.0003980000 0.0021910000 0.0000000000 0.0000040000 0.0011730000 13412741 96830484 509673472 3.1226286888 4.0950989723 5.3584675789 221 8.8000000000 0.0067516076 0.0045370918 0.0068521942 0.0069538586 0.0051330000 0.0003980000 0.0021880000 0.0000030000 0.0000030000 0.0022460000 13415517 96830484 509673472 3.1322836876 4.0962281227 5.3702397346 222 8.8400000000 0.0069169519 0.0045478119 0.0069169519 0.0069623779 0.0037200000 0.0004000000 0.0018380000 0.0000010000 0.0000030000 0.0011820000 13418293 96830484 509673472 3.1415848732 4.0980639458 5.3847823143 223 8.8800000000 0.0069196904 0.0045584481 0.0069196904 0.0069631454 0.0044050000 0.0003970000 0.0021910000 0.0000030000 0.0000030000 0.0015150000 13421069 96830484 509673472 3.1522419453 4.1012020111 5.3941621780 224 8.9200000000 0.0068647834 0.0045687442 0.0069196904 0.0069690171 0.0040800000 0.0004000000 0.0021930000 0.0000000000 0.0000030000 0.0011870000 13423845 96830484 509673472 3.1629633904 4.1042346954 5.4047870636 225 8.9600000000 0.0068980544 0.0045790967 0.0069196904 0.0069663535 0.0051100000 0.0003980000 0.0021800000 0.0000030000 0.0000030000 0.0022250000 13426621 96830484 509673472 3.1734352112 4.1069211960 5.4128260612 226 9.0000000000 0.0072254403 0.0045908062 0.0072254403 0.0069527532 0.0040770000 0.0003970000 0.0021850000 0.0000000000 0.0000030000 0.0011920000 13429397 96830484 509673472 3.1838812828 4.1111669540 5.4244599342 227 9.0400000000 0.0070937173 0.0046018323 0.0072254403 0.0069389750 0.0041760000 0.0004000000 0.0019440000 0.0000030000 0.0000020000 0.0015210000 13432173 96830484 509673472 3.1958563328 4.1170096397 5.4328417778 228 9.0800000000 0.0072643943 0.0046135102 0.0072643943 0.0069502678 0.0040950000 0.0004000000 0.0021870000 0.0000010000 0.0000030000 0.0012000000 13434949 96830484 509673472 3.2074055672 4.1230902672 5.4463391304 229 9.1200000000 0.0072253821 0.0046249157 0.0072643943 0.0070096127 0.0052500000 0.0003960000 0.0022870000 0.0000030000 0.0000020000 0.0022540000 13437725 96830484 509673472 3.2179820538 4.1271700859 5.4537768364 230 9.1600000000 0.0072599859 0.0046363725 0.0072643943 0.0071109560 0.0042100000 0.0003990000 0.0023010000 0.0000000000 0.0000030000 0.0012020000 13440501 96830484 509673472 3.2288749218 4.1312575340 5.4606409073 231 9.2000000000 0.0071143950 0.0046470999 0.0072643943 0.0073238445 0.0040800000 0.0004000000 0.0018390000 0.0000030000 0.0000030000 0.0015270000 13443277 96830484 509673472 3.2381241322 4.1320676804 5.4680809975 232 9.2400000000 0.0072366716 0.0046582619 0.0072643943 0.0074886121 0.0041230000 0.0003990000 0.0022120000 0.0000010000 0.0000030000 0.0011970000 13446053 96830484 509673472 3.2476441860 4.1351461411 5.4764394760 233 9.2800000000 0.0071883346 0.0046691205 0.0072643943 0.0076323315 0.0051940000 0.0004000000 0.0022120000 0.0000030000 0.0000030000 0.0022670000 13448829 96830484 509673472 3.2572534084 4.1378970146 5.4837450981 234 9.3200000000 0.0072323345 0.0046800744 0.0072643943 0.0077362816 0.0041180000 0.0003980000 0.0022180000 0.0000010000 0.0000030000 0.0011910000 13451605 96830484 509673472 3.2672071457 4.1416530609 5.4906444550 235 9.3600000000 0.0071960459 0.0046907807 0.0072643943 0.0078134357 0.0044290000 0.0003970000 0.0022130000 0.0000030000 0.0000030000 0.0015030000 13454381 96830484 509673472 3.2773098946 4.1448554993 5.4979395866 236 9.4000000000 0.0073503372 0.0047020500 0.0073503372 0.0078744968 0.0041450000 0.0003990000 0.0022420000 0.0000000000 0.0000030000 0.0011910000 13457157 96830484 509673472 3.2867805958 4.1478281021 5.5063047409 237 9.4400000000 0.0072635226 0.0047128579 0.0073503372 0.0079028136 0.0048340000 0.0003980000 0.0018800000 0.0000030000 0.0000040000 0.0022370000 13459933 96830484 509673472 3.2967557907 4.1517910957 5.5127701759 238 9.4800000000 0.0074485955 0.0047243526 0.0074485955 0.0079248186 0.0041520000 0.0003990000 0.0022460000 0.0000000000 0.0000030000 0.0011880000 13462709 96830484 509673472 3.3076429367 4.1580104828 5.5205726624 239 9.5200000000 0.0073743653 0.0047354405 0.0074485955 0.0079685660 0.0044760000 0.0003980000 0.0022440000 0.0000030000 0.0000030000 0.0015110000 13465485 96830484 509673472 3.3183660507 4.1630940437 5.5281019211 240 9.5600000000 0.0074186162 0.0047466204 0.0074485955 0.0080226047 0.0038190000 0.0003980000 0.0019110000 0.0000010000 0.0000030000 0.0011860000 13468261 96830484 509673472 3.3285760880 4.1679182053 5.5366687775 241 9.6000000000 0.0073739910 0.0047575224 0.0074485955 0.0080773449 0.0054370000 0.0004000000 0.0024340000 0.0000030000 0.0000020000 0.0022760000 13471037 96830484 509673472 3.3378717899 4.1686444283 5.5453929901 242 9.6400000000 0.0072604534 0.0047678651 0.0074485955 0.0080981347 0.0044000000 0.0004000000 0.0024790000 0.0000000000 0.0000030000 0.0011940000 13473813 96830484 509673472 3.3476212025 4.1710424423 5.5539355278 243 9.6800000000 0.0072607538 0.0047781239 0.0074485955 0.0081124943 0.0050380000 0.0003970000 0.0027650000 0.0000030000 0.0000030000 0.0015460000 13476589 96830484 509673472 3.3586022854 4.1770153046 5.5616979599 244 9.7200000000 0.0072714370 0.0047883424 0.0074485955 0.0081594785 0.0044750000 0.0003980000 0.0025430000 0.0000010000 0.0000030000 0.0012000000 13479365 96830484 509673472 3.3698980808 4.1834440231 5.5698738098 245 9.7600000000 0.0071215229 0.0047978656 0.0074485955 0.0082226926 0.0055350000 0.0003990000 0.0025520000 0.0000030000 0.0000030000 0.0022500000 13482141 96830484 509673472 3.3801255226 4.1858167648 5.5777177811 246 9.8000000000 0.0071205953 0.0048073075 0.0074485955 0.0082425213 0.0040670000 0.0003990000 0.0021530000 0.0000000000 0.0000030000 0.0011840000 13484917 96830484 509673472 3.3904662132 4.1886811256 5.5866932869 247 9.8400000000 0.0072004125 0.0048169962 0.0074485955 0.0082476598 0.0047700000 0.0003970000 0.0025360000 0.0000030000 0.0000030000 0.0015020000 13487693 96830484 509673472 3.3999838829 4.1890230179 5.5966734886 248 9.8800000000 0.0072000292 0.0048266052 0.0074485955 0.0082328635 0.0044670000 0.0004000000 0.0025490000 0.0000000000 0.0000040000 0.0011840000 13490469 96830484 509673472 3.4093174934 4.1907835007 5.6051855087 249 9.9200000000 0.0071771718 0.0048360453 0.0074485955 0.0082174428 0.0053670000 0.0003980000 0.0024130000 0.0000030000 0.0000030000 0.0022160000 13493245 96830484 509673472 3.4193496704 4.1930518150 5.6128292084 250 9.9600000000 0.0071918867 0.0048454686 0.0074485955 0.0082012656 0.0039490000 0.0003970000 0.0020240000 0.0000000000 0.0000040000 0.0011900000 13496021 96830484 509673472 3.4290330410 4.1952629089 5.6217751503 251 10.0000000000 0.0072807050 0.0048551708 0.0074485955 0.0081851099 0.0047880000 0.0003990000 0.0025420000 0.0000030000 0.0000030000 0.0015060000 13498797 96830484 509673472 3.4391508102 4.1984252930 5.6305847168 252 10.0400000000 0.0072272238 0.0048645837 0.0074485955 0.0081719316 0.0044830000 0.0003990000 0.0025510000 0.0000000000 0.0000030000 0.0011930000 13501573 96830484 509673472 3.4476833344 4.1974649429 5.6410279274 253 10.0800000000 0.0071757156 0.0048737186 0.0074485955 0.0081566534 0.0073770000 0.0003970000 0.0043630000 0.0000050000 0.0000030000 0.0022690000 13504349 96830484 509673472 3.4552299976 4.1943354607 5.6508445740 254 10.1200000000 0.0072520515 0.0048830821 0.0074485955 0.0081769322 0.0044960000 0.0003990000 0.0025620000 0.0000000000 0.0000040000 0.0011930000 13507125 96830484 509673472 3.4650208950 4.1982078552 5.6597423553 255 10.1600000000 0.0072530629 0.0048923761 0.0074485955 0.0081921115 0.0048150000 0.0003970000 0.0025590000 0.0000030000 0.0000030000 0.0015100000 13509901 96830484 509673472 3.4759025574 4.2050762177 5.6686515808 256 10.2000000000 0.0072717825 0.0049016707 0.0074485955 0.0081795804 0.0039730000 0.0003980000 0.0020410000 0.0000000000 0.0000030000 0.0011920000 13512677 96830484 509673472 3.4870977402 4.2099943161 5.6771063805 257 10.2400000000 0.0072231293 0.0049107036 0.0074485955 0.0081652963 0.0055830000 0.0003980000 0.0025540000 0.0000030000 0.0000030000 0.0022750000 13540029 96830484 509673472 3.4964659214 4.2096490860 5.6859159470 258 10.2800000000 0.0072380486 0.0049197243 0.0074485955 0.0081494397 0.0048910000 0.0003980000 0.0029620000 0.0000000000 0.0000030000 0.0011800000 13594005 96830484 509673472 3.5068166256 4.2147345543 5.6947417259 259 10.3200000000 0.0072607100 0.0049287629 0.0074485955 0.0081436190 0.0048340000 0.0004000000 0.0025570000 0.0000040000 0.0000030000 0.0015230000 13596781 96830484 509673472 3.5172986984 4.2186360359 5.7011475563 260 10.3600000000 0.0072670924 0.0049377565 0.0074485955 0.0081496626 0.0043610000 0.0003970000 0.0024300000 0.0000000000 0.0000030000 0.0011800000 13599557 96830484 509673472 3.5272772312 4.2202401161 5.7093830109 261 10.4000000000 0.0072087119 0.0049464574 0.0074485955 0.0081493713 0.0053870000 0.0003970000 0.0024020000 0.0000030000 0.0000030000 0.0022270000 13602333 96830484 509673472 3.5368404388 4.2197041512 5.7162175179 262 10.4400000000 0.0072257542 0.0049551570 0.0074485955 0.0081369972 0.0044810000 0.0004000000 0.0025420000 0.0000000000 0.0000030000 0.0011810000 13605109 96830484 509673472 3.5463674068 4.2199916840 5.7234263420 263 10.4800000000 0.0071984548 0.0049636867 0.0074485955 0.0081235241 0.0047830000 0.0003970000 0.0025300000 0.0000030000 0.0000020000 0.0014970000 13607885 96830484 509673472 3.5571599007 4.2214097977 5.7290377617 264 10.5200000000 0.0071901456 0.0049721202 0.0074485955 0.0081132666 0.0060200000 0.0003960000 0.0040960000 0.0000000000 0.0000030000 0.0011700000 13610661 96830484 509673472 3.5674726963 4.2210483551 5.7350444794 265 10.5600000000 0.0072379960 0.0049806707 0.0074485955 0.0080981381 0.0054830000 0.0003980000 0.0025190000 0.0000030000 0.0000020000 0.0022030000 13613437 96830484 509673472 3.5787215233 4.2229795456 5.7412075996 266 10.6000000000 0.0071544908 0.0049888430 0.0074485955 0.0080873292 0.0047250000 0.0004010000 0.0028010000 0.0000000000 0.0000030000 0.0011630000 13616213 96830484 509673472 3.5907096863 4.2252111435 5.7455229759 267 10.6400000000 0.0071788444 0.0049970452 0.0074485955 0.0080836528 0.0047830000 0.0003970000 0.0025360000 0.0000030000 0.0000030000 0.0014810000 13618989 96830484 509673472 3.6019752026 4.2243146896 5.7495560646 268 10.6800000000 0.0072043259 0.0050052814 0.0074485955 0.0080768860 0.0048380000 0.0003970000 0.0029260000 0.0000000000 0.0000030000 0.0011540000 13621765 96830484 509673472 3.6133160591 4.2237768173 5.7556066513 269 10.7200000000 0.0071599754 0.0050132914 0.0074485955 0.0080659244 0.0053960000 0.0003990000 0.0024090000 0.0000030000 0.0000030000 0.0022190000 13624541 96830484 509673472 3.6252140999 4.2235774994 5.7579569817 270 10.7600000000 0.0071546678 0.0050212224 0.0074485955 0.0080566415 0.0043330000 0.0004000000 0.0024070000 0.0000010000 0.0000040000 0.0011550000 13627317 96830484 509673472 3.6506152153 4.2283115387 5.7682752609 271 10.8000000000 0.0071445885 0.0050290577 0.0074485955 0.0080736532 0.0046630000 0.0004000000 0.0024040000 0.0000030000 0.0000020000 0.0014870000 13630093 96830484 509673472 3.6649413109 4.2320513725 5.7716107368 272 10.8400000000 0.0071649109 0.0050369101 0.0074485955 0.0081357878 0.0044650000 0.0003980000 0.0025470000 0.0000010000 0.0000050000 0.0011470000 13632869 96830484 509673472 3.6768913269 4.2302012444 5.7751269341 273 10.8800000000 0.0071709296 0.0050447270 0.0074485955 0.0081441858 0.0055110000 0.0004000000 0.0025450000 0.0000030000 0.0000030000 0.0021880000 13635645 96830484 509673472 3.6895010471 4.2309336662 5.7796788216 274 10.9200000000 0.0072003426 0.0050525942 0.0074485955 0.0081530218 0.0044480000 0.0003980000 0.0025370000 0.0000000000 0.0000040000 0.0011380000 13638421 96830484 509673472 3.7027790546 4.2321758270 5.7833552361 275 10.9600000000 0.0071804002 0.0050603317 0.0074485955 0.0081586503 0.0048010000 0.0003990000 0.0025510000 0.0000040000 0.0000030000 0.0014740000 13641197 96830484 509673472 3.7156677246 4.2321162224 5.7861166000 276 11.0000000000 0.0072026625 0.0050680938 0.0074485955 0.0081558471 0.0043240000 0.0004000000 0.0024240000 0.0000000000 0.0000030000 0.0011270000 13643973 96830484 509673472 3.7291328907 4.2340221405 5.7898879051 277 11.0400000000 0.0072200582 0.0050758626 0.0074485955 0.0081614233 0.0053410000 0.0004010000 0.0024300000 0.0000030000 0.0000030000 0.0021280000 13646749 96830484 509673472 3.7427012920 4.2355189323 5.7932348251 278 11.0800000000 0.0072439029 0.0050836613 0.0074485955 0.0081672659 0.0043180000 0.0003990000 0.0024240000 0.0000010000 0.0000030000 0.0011160000 13649525 96830484 509673472 3.7562873363 4.2372832298 5.7966055870 279 11.1200000000 0.0072256303 0.0050913386 0.0074485955 0.0081766005 0.0047580000 0.0003980000 0.0025470000 0.0000030000 0.0000020000 0.0014330000 13652301 96830484 509673472 3.7702391148 4.2390341759 5.8006019592 280 11.1600000000 0.0072257449 0.0050989615 0.0074485955 0.0081848622 0.0044310000 0.0003970000 0.0025510000 0.0000010000 0.0000030000 0.0011030000 13655077 96830484 509673472 3.7842402458 4.2415351868 5.8037648201 281 11.2000000000 0.0072633964 0.0051066641 0.0074485955 0.0081912237 0.0054550000 0.0003990000 0.0025650000 0.0000040000 0.0000030000 0.0021030000 13657853 96830484 509673472 3.7973935604 4.2424201965 5.8063678741 282 11.2400000000 0.0072317682 0.0051141999 0.0074485955 0.0081865919 0.0044610000 0.0004030000 0.0025810000 0.0000000000 0.0000030000 0.0010940000 13660629 96830484 509673472 3.8092379570 4.2414031029 5.8109903336 283 11.2800000000 0.0072237048 0.0051216540 0.0074485955 0.0081722833 0.0048020000 0.0004010000 0.0025780000 0.0000030000 0.0000030000 0.0014220000 13663405 96830484 509673472 3.8215346336 4.2427086830 5.8134732246 284 11.3200000000 0.0072532925 0.0051291598 0.0074485955 0.0081614013 0.0043140000 0.0004000000 0.0024400000 0.0000000000 0.0000040000 0.0010870000 13666181 96830484 509673472 3.8341231346 4.2448267937 5.8188343048 285 11.3600000000 0.0073550236 0.0051369698 0.0074485955 0.0081586280 0.0058160000 0.0003970000 0.0029560000 0.0000030000 0.0000020000 0.0020710000 13668957 96830484 509673472 3.8457341194 4.2460331917 5.8229637146 286 11.4000000000 0.0072565689 0.0051443810 0.0074485955 0.0081505211 0.0048410000 0.0004000000 0.0029630000 0.0000000000 0.0000030000 0.0010870000 13671733 96830484 509673472 3.8562357426 4.2458915710 5.8269667625 287 11.4400000000 0.0073007662 0.0051518946 0.0074485955 0.0081363427 0.0051280000 0.0003990000 0.0029230000 0.0000030000 0.0000030000 0.0014120000 13674509 96830484 509673472 3.8657681942 4.2455487251 5.8311662674 288 11.4800000000 0.0072297128 0.0051591092 0.0074485955 0.0081230492 0.0044550000 0.0003970000 0.0025880000 0.0000010000 0.0000030000 0.0010770000 13677285 96830484 509673472 3.8746147156 4.2453570366 5.8351063728 289 11.5200000000 0.0072868117 0.0051664715 0.0074485955 0.0081103440 0.0054590000 0.0004000000 0.0025890000 0.0000040000 0.0000030000 0.0020700000 13680061 96830484 509673472 3.8831646442 4.2452907562 5.8416728973 290 11.5600000000 0.0072940481 0.0051738080 0.0074485955 0.0081020862 0.0068190000 0.0003970000 0.0049560000 0.0000010000 0.0000030000 0.0010700000 13682837 96830484 509673472 3.8914830685 4.2456989288 5.8474278450 291 11.6000000000 0.0073340884 0.0051812316 0.0074485955 0.0080918929 0.0070320000 0.0003980000 0.0048320000 0.0000030000 0.0000030000 0.0014000000 13685613 96830484 509673472 3.8990385532 4.2448382378 5.8545546532 292 11.6400000000 0.0073332400 0.0051886015 0.0074485955 0.0080797795 0.0051870000 0.0003980000 0.0033210000 0.0000000000 0.0000030000 0.0010680000 13688389 96830484 509673472 3.9070794582 4.2458267212 5.8603177071 293 11.6800000000 0.0073266509 0.0051958986 0.0074485955 0.0080660535 0.0053070000 0.0003970000 0.0024530000 0.0000030000 0.0000030000 0.0020540000 13691165 96830484 509673472 3.9140496254 4.2460818291 5.8671760559 294 11.7200000000 0.0073637995 0.0052032724 0.0074485955 0.0080537503 0.0044590000 0.0004030000 0.0025890000 0.0000010000 0.0000030000 0.0010630000 13693941 96830484 509673472 3.9201757908 4.2453894615 5.8745245934 295 11.7600000000 0.0073572029 0.0052105739 0.0074485955 0.0080458683 0.0046280000 0.0004000000 0.0024280000 0.0000030000 0.0000030000 0.0013970000 13696717 96830484 509673472 3.9258635044 4.2453398705 5.8814735413 296 11.8000000000 0.0073395078 0.0052177662 0.0074485955 0.0080368135 0.0043090000 0.0003980000 0.0024440000 0.0000000000 0.0000040000 0.0010650000 13699493 96830484 509673472 3.9317138195 4.2455096245 5.8880057335 297 11.8400000000 0.0073793987 0.0052250444 0.0074485955 0.0080283096 0.0052960000 0.0003980000 0.0024520000 0.0000030000 0.0000030000 0.0020410000 13702269 96830484 509673472 3.9366185665 4.2450776100 5.8955593109 298 11.8800000000 0.0073999725 0.0052323429 0.0074485955 0.0080238081 0.0039270000 0.0003980000 0.0020490000 0.0000000000 0.0000030000 0.0010690000 13705045 96830484 509673472 3.9415140152 4.2444567680 5.9035243988 299 11.9200000000 0.0073813270 0.0052395301 0.0074485955 0.0080148115 0.0047920000 0.0003990000 0.0025780000 0.0000030000 0.0000030000 0.0014060000 13707821 96830484 509673472 3.9465563297 4.2444572449 5.9116525650 300 11.9600000000 0.0073854090 0.0052466830 0.0074485955 0.0080022774 0.0039430000 0.0003990000 0.0020640000 0.0000000000 0.0000040000 0.0010700000 13710597 96830484 509673472 3.9515702724 4.2452769279 5.9199399948 301 12.0000000000 0.0073838877 0.0052537834 0.0074485955 0.0079891987 0.0051970000 0.0003980000 0.0023100000 0.0000030000 0.0000030000 0.0020750000 13713373 96830484 509673472 3.9562072754 4.2455592155 5.9291758537 302 12.0400000000 0.0074367658 0.0052610118 0.0074485955 0.0079785828 0.0044620000 0.0003980000 0.0025760000 0.0000000000 0.0000030000 0.0010720000 13716149 96830484 509673472 3.9601831436 4.2454562187 5.9390702248 303 12.0800000000 0.0073895343 0.0052680366 0.0074485955 0.0079726561 0.0046730000 0.0003980000 0.0024390000 0.0000040000 0.0000030000 0.0014190000 13718925 96830484 509673472 3.9643700123 4.2457022667 5.9490251541 304 12.1200000000 0.0074990336 0.0052753754 0.0074990336 0.0079716506 0.0055160000 0.0004010000 0.0036270000 0.0000010000 0.0000030000 0.0010740000 13721701 96830484 509673472 3.9683089256 4.2460722923 5.9592866898 305 12.1600000000 0.0074478355 0.0052824982 0.0074990336 0.0079687090 0.0053140000 0.0003970000 0.0024370000 0.0000030000 0.0000030000 0.0020640000 13724477 96830484 509673472 3.9719648361 4.2458791733 5.9705724716 306 12.2000000000 0.0074819364 0.0052896859 0.0074990336 0.0079621110 0.0044650000 0.0003990000 0.0025780000 0.0000010000 0.0000030000 0.0010730000 13727253 96830484 509673472 3.9755818844 4.2458806038 5.9820895195 307 12.2400000000 0.0075255302 0.0052969688 0.0075255302 0.0079639680 0.0045750000 0.0003990000 0.0023840000 0.0000040000 0.0000030000 0.0013740000 13730029 96830484 509673472 3.9788665771 4.2466516495 5.9937334061 308 12.2800000000 0.0075551816 0.0053043007 0.0075551816 0.0079680097 0.0039350000 0.0003980000 0.0020430000 0.0000000000 0.0000030000 0.0010770000 13732805 96830484 509673472 3.9815020561 4.2467846870 6.0053009987 309 12.3200000000 0.0075220112 0.0053114777 0.0075551816 0.0079793921 0.0052960000 0.0003970000 0.0023820000 0.0000030000 0.0000030000 0.0020980000 13735581 96830484 509673472 3.9834141731 4.2463593483 6.0162405968 310 12.3600000000 0.0075694961 0.0053187617 0.0075694961 0.0079983576 0.0046810000 0.0004000000 0.0027810000 0.0000000000 0.0000030000 0.0010810000 13738357 96830484 509673472 3.9850912094 4.2458829880 6.0281934738 311 12.4000000000 0.0075954697 0.0053260823 0.0075954697 0.0080122303 0.0050830000 0.0004000000 0.0028320000 0.0000030000 0.0000030000 0.0014270000 13741133 96830484 509673472 3.9873123169 4.2467226982 6.0389842987 312 12.4400000000 0.0076361587 0.0053334864 0.0076361587 0.0080494223 0.0043430000 0.0003970000 0.0024400000 0.0000010000 0.0000030000 0.0010850000 13743909 96830484 509673472 3.9896705151 4.2464714050 6.0628237724 313 12.4800000000 0.0076379045 0.0053408487 0.0076379045 0.0080432508 0.0053590000 0.0003980000 0.0024380000 0.0000030000 0.0000020000 0.0020970000 13746685 96830484 509673472 3.9902601242 4.2462687492 6.0735831261 314 12.5200000000 0.0076865163 0.0053483190 0.0076865163 0.0080355880 0.0043550000 0.0004000000 0.0024430000 0.0000000000 0.0000030000 0.0010870000 13749461 96830484 509673472 3.9903218746 4.2451815605 6.0861415863 315 12.5600000000 0.0077175442 0.0053558404 0.0077175442 0.0080359125 0.0046890000 0.0003970000 0.0024290000 0.0000040000 0.0000030000 0.0014350000 13752237 96830484 509673472 3.9907758236 4.2454409599 6.0974960327 316 12.6000000000 0.0077124364 0.0053632979 0.0077175442 0.0080256965 0.0043550000 0.0003990000 0.0024450000 0.0000000000 0.0000040000 0.0010800000 13755013 96830484 509673472 3.9909594059 4.2456798553 6.1096587181 317 12.6400000000 0.0076553384 0.0053705283 0.0077175442 0.0080131394 0.0053660000 0.0003970000 0.0024380000 0.0000030000 0.0000040000 0.0020950000 13757789 96830484 509673472 3.9906392097 4.2449569702 6.1213068962 318 12.6800000000 0.0076575852 0.0053777204 0.0077175442 0.0080004922 0.0043580000 0.0004010000 0.0024380000 0.0000000000 0.0000040000 0.0010800000 13760565 96830484 509673472 3.9899997711 4.2444348335 6.1326689720 319 12.7200000000 0.0076138591 0.0053847302 0.0077175442 0.0079879161 0.0050940000 0.0003980000 0.0028370000 0.0000030000 0.0000030000 0.0014220000 13763341 96830484 509673472 3.9892706871 4.2445020676 6.1427092552 320 12.7600000000 0.0075689089 0.0053915557 0.0077175442 0.0079753922 0.0067230000 0.0003990000 0.0048110000 0.0000010000 0.0000030000 0.0010780000 13766117 96830484 509673472 3.9880726337 4.2445864677 6.1529402733 321 12.8000000000 0.0075131026 0.0053981649 0.0077175442 0.0079653306 0.0058420000 0.0003990000 0.0029630000 0.0000030000 0.0000030000 0.0020350000 13768893 96830484 509673472 3.9859287739 4.2434425354 6.1637492180 322 12.8400000000 0.0074351886 0.0054044911 0.0077175442 0.0079550935 0.0048690000 0.0003980000 0.0029560000 0.0000000000 0.0000030000 0.0010730000 13771669 96830484 509673472 3.9842870235 4.2437133789 6.1732449532 323 12.8800000000 0.0073882723 0.0054106328 0.0077175442 0.0079462473 0.0047600000 0.0004000000 0.0025570000 0.0000030000 0.0000030000 0.0013570000 13774445 96830484 509673472 3.9823307991 4.2425599098 6.1819763184 324 12.9200000000 0.0073316176 0.0054165618 0.0077175442 0.0079349283 0.0046890000 0.0003980000 0.0028080000 0.0000000000 0.0000030000 0.0010410000 13777221 96830484 509673472 3.9803481102 4.2418599129 6.1911954880 325 12.9600000000 0.0072255661 0.0054221280 0.0077175442 0.0079228846 0.0056530000 0.0004020000 0.0028140000 0.0000030000 0.0000030000 0.0019970000 13779997 96830484 509673472 3.9789474010 4.2425870895 6.2003059387 326 13.0000000000 0.0071915463 0.0054275556 0.0077175442 0.0079112751 0.0042870000 0.0003990000 0.0024180000 0.0000000000 0.0000040000 0.0010260000 13782773 96830484 509673472 3.9769923687 4.2422051430 6.2075762749 327 13.0400000000 0.0072087157 0.0054330026 0.0077175442 0.0079005208 0.0049870000 0.0004010000 0.0028090000 0.0000030000 0.0000030000 0.0013300000 13785549 96830484 509673472 3.9750576019 4.2425994873 6.2173290253 328 13.0800000000 0.0072088344 0.0054384167 0.0077175442 0.0078896279 0.0041650000 0.0003980000 0.0022970000 0.0000000000 0.0000030000 0.0010180000 13788325 96830484 509673472 3.9745416641 4.2453007698 6.2239003181 329 13.1200000000 0.0071731433 0.0054436894 0.0077175442 0.0078781945 0.0053420000 0.0003970000 0.0025540000 0.0000040000 0.0000030000 0.0019350000 13791101 96830484 509673472 3.9729366302 4.2460446358 6.2329826355 330 13.1600000000 0.0071350350 0.0054488147 0.0077175442 0.0078673726 0.0042870000 0.0003980000 0.0024400000 0.0000000000 0.0000030000 0.0010030000 13793877 96830484 509673472 3.9710316658 4.2462692261 6.2410383224 331 13.2000000000 0.0071886992 0.0054540712 0.0077175442 0.0078558752 0.0045670000 0.0004000000 0.0024390000 0.0000030000 0.0000020000 0.0012760000 13796653 96830484 509673472 3.9693367481 4.2468905449 6.2510919571 332 13.2400000000 0.0073234844 0.0054597019 0.0077175442 0.0078461543 0.0041370000 0.0004020000 0.0022910000 0.0000010000 0.0000030000 0.0009890000 13799429 96830484 509673472 3.9675891399 4.2474899292 6.2596859932 333 13.2800000000 0.0072819269 0.0054651741 0.0077175442 0.0078353863 0.0050780000 0.0004000000 0.0024290000 0.0000030000 0.0000030000 0.0017930000 13802205 96830484 509673472 3.9654877186 4.2476987839 6.2690157890 334 13.3200000000 0.0073059071 0.0054706853 0.0077175442 0.0078241629 0.0047490000 0.0003980000 0.0029670000 0.0000000000 0.0000030000 0.0009290000 13804981 96830484 509673472 3.9632742405 4.2476205826 6.2769842148 335 13.3600000000 0.0072845127 0.0054760997 0.0077175442 0.0078126222 0.0041280000 0.0003970000 0.0020390000 0.0000040000 0.0000030000 0.0012370000 13807757 96830484 509673472 3.9612259865 4.2485785484 6.2855792046 336 13.4000000000 0.0072893389 0.0054814962 0.0077175442 0.0078010280 0.0043380000 0.0004000000 0.0025640000 0.0000000000 0.0000030000 0.0009190000 13810533 96830484 509673472 3.9597787857 4.2504639626 6.2933950424 337 13.4400000000 0.0072844592 0.0054868463 0.0077175442 0.0077996942 0.0047580000 0.0003980000 0.0021730000 0.0000030000 0.0000020000 0.0017250000 13813309 96830484 509673472 3.9581034184 4.2528572083 6.3008241653 338 13.4800000000 0.0073104640 0.0054922416 0.0077175442 0.0078057727 0.0038100000 0.0004020000 0.0020370000 0.0000000000 0.0000030000 0.0009120000 13816085 96830484 509673472 3.9563405514 4.2544832230 6.3070259094 339 13.5200000000 0.0073159602 0.0054976213 0.0077175442 0.0078217249 0.0044590000 0.0003990000 0.0024240000 0.0000030000 0.0000030000 0.0011710000 13818861 96830484 509673472 3.9539377689 4.2544822693 6.3124794960 340 13.5600000000 0.0073213466 0.0055029852 0.0077175442 0.0078181760 0.0042050000 0.0003990000 0.0024290000 0.0000000000 0.0000030000 0.0009140000 13821637 96830484 509673472 3.9515523911 4.2548332214 6.3176312447 341 13.6000000000 0.0073563186 0.0055084202 0.0077175442 0.0078115339 0.0049730000 0.0003990000 0.0024330000 0.0000030000 0.0000030000 0.0016710000 13824413 96830484 509673472 3.9494173527 4.2552204132 6.3224840164 342 13.6400000000 0.0073263133 0.0055137357 0.0077175442 0.0078031797 0.0042180000 0.0003980000 0.0024400000 0.0000010000 0.0000030000 0.0009180000 13827189 96830484 509673472 3.9473016262 4.2555336952 6.3279967308 343 13.6800000000 0.0073950682 0.0055192206 0.0077175442 0.0077921818 0.0049470000 0.0003990000 0.0028170000 0.0000050000 0.0000030000 0.0011610000 13829965 96830484 509673472 3.9454154968 4.2558588982 6.3327326775 344 13.7200000000 0.0074189375 0.0055247430 0.0077175442 0.0077809613 0.0045280000 0.0004110000 0.0025730000 0.0000010000 0.0000030000 0.0010500000 13832741 96830484 509673472 3.9443650246 4.2575039864 6.3382663727 345 13.7600000000 0.0074402853 0.0055302953 0.0077175442 0.0077730332 0.0050560000 0.0004020000 0.0025530000 0.0000040000 0.0000030000 0.0016210000 13835517 96830484 509673472 3.9424917698 4.2573852539 6.3436841965 346 13.8000000000 0.0074306629 0.0055357877 0.0077175442 0.0077672303 0.0041450000 0.0003980000 0.0024280000 0.0000010000 0.0000030000 0.0008460000 13838293 96830484 509673472 3.9408526421 4.2572388649 6.3486800194 347 13.8400000000 0.0073828329 0.0055411106 0.0077175442 0.0077564550 0.0044070000 0.0003970000 0.0024260000 0.0000040000 0.0000030000 0.0011040000 13841069 96830484 509673472 3.9384818077 4.2558178902 6.3532772064 348 13.8800000000 0.0073452918 0.0055462950 0.0077175442 0.0077459141 0.0041470000 0.0003980000 0.0024390000 0.0000010000 0.0000030000 0.0008340000 13843845 96830484 509673472 3.9379153252 4.2579889297 6.3590674400 349 13.9200000000 0.0073330654 0.0055514147 0.0077175442 0.0077430024 0.0043470000 0.0003980000 0.0019040000 0.0000030000 0.0000020000 0.0015680000 13846621 96830484 509673472 3.9362776279 4.2576274872 6.3647785187 350 13.9600000000 0.0073157237 0.0055564556 0.0077175442 0.0077348942 0.0045070000 0.0004010000 0.0028120000 0.0000010000 0.0000030000 0.0008160000 13849397 96830484 509673472 3.9342591763 4.2562332153 6.3736109734 351 14.0000000000 0.0071669128 0.0055610438 0.0077175442 0.0077247219 0.0049230000 0.0003990000 0.0029570000 0.0000030000 0.0000030000 0.0010800000 13852173 96830484 509673472 3.9340078831 4.2567772865 6.3782548904 352 14.0400000000 0.0071672988 0.0055656070 0.0077175442 0.0077164797 0.0041440000 0.0004010000 0.0024440000 0.0000000000 0.0000030000 0.0008160000 13854949 96830484 509673472 3.9334282875 4.2563681602 6.3830265999 353 14.0800000000 0.0071675782 0.0055701452 0.0077175442 0.0077055541 0.0056240000 0.0004000000 0.0032280000 0.0000040000 0.0000030000 0.0015110000 13857725 96830484 509673472 3.9330935478 4.2553591728 6.3873205185 354 14.1200000000 0.0071858093 0.0055747092 0.0077175442 0.0076946802 0.0042710000 0.0003990000 0.0025780000 0.0000000000 0.0000040000 0.0008110000 13860501 96830484 509673472 3.9334216118 4.2559065819 6.3921518326 355 14.1600000000 0.0072022416 0.0055792938 0.0077175442 0.0076841876 0.0045170000 0.0004010000 0.0025840000 0.0000030000 0.0000030000 0.0010460000 13863277 96830484 509673472 3.9329156876 4.2544879913 6.3968858719 356 14.2000000000 0.0071529676 0.0055837142 0.0077175442 0.0076756036 0.0045130000 0.0003980000 0.0028280000 0.0000000000 0.0000030000 0.0008010000 13866053 96830484 509673472 3.9331886768 4.2542719841 6.4015374184 357 14.2400000000 0.0070721786 0.0055878836 0.0077175442 0.0076652868 0.0048180000 0.0003990000 0.0024410000 0.0000040000 0.0000030000 0.0014860000 13868829 96830484 509673472 3.9334709644 4.2547068596 6.4071516991 358 14.2800000000 0.0070929276 0.0055920876 0.0077175442 0.0076553076 0.0041290000 0.0003990000 0.0024460000 0.0000010000 0.0000030000 0.0007990000 13871605 96830484 509673472 3.9331927299 4.2533307076 6.4125308990 359 14.3200000000 0.0070806812 0.0055962341 0.0077175442 0.0076461278 0.0043790000 0.0004000000 0.0024450000 0.0000030000 0.0000020000 0.0010410000 13874381 96830484 509673472 3.9325654507 4.2515134811 6.4179716110 360 14.3600000000 0.0070396364 0.0056002436 0.0077175442 0.0076377582 0.0046620000 0.0003990000 0.0029730000 0.0000010000 0.0000030000 0.0007980000 13877157 96830484 509673472 3.9323945045 4.2501807213 6.4240846634 361 14.4000000000 0.0070467503 0.0056042505 0.0077175442 0.0076342943 0.0049590000 0.0003980000 0.0025720000 0.0000040000 0.0000030000 0.0014940000 13879933 96830484 509673472 3.9322919846 4.2499990463 6.4305696487 362 14.4400000000 0.0070522795 0.0056082506 0.0077175442 0.0076281508 0.0042540000 0.0003990000 0.0025690000 0.0000000000 0.0000030000 0.0007960000 13882709 96830484 509673472 3.9322953224 4.2502036095 6.4370794296 363 14.4800000000 0.0070546451 0.0056122352 0.0077175442 0.0076179797 0.0048870000 0.0003970000 0.0029590000 0.0000040000 0.0000030000 0.0010280000 13885485 96830484 509673472 3.9324471951 4.2510905266 6.4442420006 364 14.5200000000 0.0070528449 0.0056161929 0.0077175442 0.0076083497 0.0049160000 0.0004000000 0.0032300000 0.0000000000 0.0000040000 0.0007900000 13888261 96830484 509673472 3.9320948124 4.2504220009 6.4514389038 365 14.5600000000 0.0070742336 0.0056201875 0.0077175442 0.0075982313 0.0055980000 0.0004000000 0.0032210000 0.0000040000 0.0000030000 0.0014770000 13891037 96830484 509673472 3.9315402508 4.2495083809 6.4584417343 366 14.6000000000 0.0070843156 0.0056241879 0.0077175442 0.0075878513 0.0046310000 0.0004000000 0.0029470000 0.0000010000 0.0000030000 0.0007860000 13893813 96830484 509673472 3.9314532280 4.2504177094 6.4662661552 367 14.6400000000 0.0071531790 0.0056283541 0.0077175442 0.0075776546 0.0047160000 0.0003970000 0.0027940000 0.0000030000 0.0000030000 0.0010230000 13896589 96830484 509673472 3.9315357208 4.2513799667 6.4734916687 368 14.6800000000 0.0072001526 0.0056326253 0.0077175442 0.0075699479 0.0042140000 0.0004000000 0.0025270000 0.0000010000 0.0000030000 0.0007840000 13899365 96830484 509673472 3.9313642979 4.2518968582 6.4812393188 369 14.7200000000 0.0072063543 0.0056368901 0.0077175442 0.0075697260 0.0063130000 0.0004000000 0.0039280000 0.0000040000 0.0000030000 0.0014780000 13902141 96830484 509673472 3.9305913448 4.2516274452 6.4886651039 370 14.7600000000 0.0072334534 0.0056412051 0.0077175442 0.0075678426 0.0049670000 0.0004000000 0.0032720000 0.0000010000 0.0000030000 0.0007910000 13904917 96830484 509673472 3.9304080009 4.2519974709 6.4965972900 371 14.8000000000 0.0072602257 0.0056455691 0.0077175442 0.0075621546 0.0044400000 0.0004010000 0.0024880000 0.0000030000 0.0000030000 0.0010420000 13907693 96830484 509673472 3.9303929806 4.2516899109 6.5037355423 372 14.8400000000 0.0072689569 0.0056499330 0.0077175442 0.0075584505 0.0045720000 0.0004010000 0.0028660000 0.0000000000 0.0000030000 0.0007970000 13910469 96830484 509673472 3.9301886559 4.2511601448 6.5107669830 373 14.8800000000 0.0072786645 0.0056542996 0.0077175442 0.0075591627 0.0047500000 0.0004000000 0.0023590000 0.0000040000 0.0000030000 0.0014810000 13913245 96830484 509673472 3.9300799370 4.2509202957 6.5180263519 374 14.9200000000 0.0073253801 0.0056587677 0.0077175442 0.0075559103 0.0045640000 0.0004010000 0.0028510000 0.0000010000 0.0000030000 0.0008000000 13916021 96830484 509673472 3.9299650192 4.2502450943 6.5252223015 375 14.9600000000 0.0073676561 0.0056633248 0.0077175442 0.0075586737 0.0048100000 0.0004010000 0.0028380000 0.0000030000 0.0000030000 0.0010550000 13918797 96830484 509673472 3.9302554131 4.2498779297 6.5321621895 376 15.0000000000 0.0073912381 0.0056679203 0.0077175442 0.0075582144 0.0063110000 0.0003990000 0.0045910000 0.0000000000 0.0000030000 0.0008100000 13921573 96830484 509673472 3.9312670231 4.2512407303 6.5395827293 377 15.0400000000 0.0074287974 0.0056725910 0.0077175442 0.0075511159 0.0047920000 0.0004000000 0.0023290000 0.0000040000 0.0000030000 0.0015420000 13924349 96830484 509673472 3.9336028099 4.2523298264 6.5526747704 378 15.0800000000 0.0075418511 0.0056775362 0.0077175442 0.0075411757 0.0040750000 0.0003990000 0.0023420000 0.0000000000 0.0000040000 0.0008200000 13927125 96830484 509673472 3.9356451035 4.2535877228 6.5589742661 379 15.1200000000 0.0075285495 0.0056824201 0.0077175442 0.0075312585 0.0043410000 0.0003990000 0.0023400000 0.0000040000 0.0000030000 0.0010830000 13929901 96830484 509673472 3.9374945164 4.2540154457 6.5646619797 380 15.1600000000 0.0075819204 0.0056874188 0.0077175442 0.0075224801 0.0040910000 0.0003990000 0.0023450000 0.0000000000 0.0000040000 0.0008310000 13932677 96830484 509673472 3.9402890205 4.2551121712 6.5700855255 381 15.2000000000 0.0076034279 0.0056924477 0.0077175442 0.0075127202 0.0072390000 0.0003990000 0.0047380000 0.0000030000 0.0000030000 0.0015690000 13935453 96830484 509673472 3.9426708221 4.2560839653 6.5751633644 382 15.2400000000 0.0076282993 0.0056975154 0.0077175442 0.0075040560 0.0041190000 0.0003990000 0.0023510000 0.0000010000 0.0000030000 0.0008450000 13938229 96830484 509673472 3.9449152946 4.2564477921 6.5799775124 383 15.2800000000 0.0076737213 0.0057026752 0.0077175442 0.0074948517 0.0044050000 0.0003980000 0.0023590000 0.0000040000 0.0000030000 0.0011140000 13941005 96830484 509673472 3.9476091862 4.2574386597 6.5845546722 384 15.3200000000 0.0076853232 0.0057078383 0.0077175442 0.0074851538 0.0041450000 0.0003980000 0.0023640000 0.0000010000 0.0000030000 0.0008520000 13943781 96830484 509673472 3.9504272938 4.2580885887 6.5883827209 385 15.3600000000 0.0077628260 0.0057131759 0.0077628260 0.0074763914 0.0049130000 0.0003970000 0.0023690000 0.0000040000 0.0000030000 0.0016160000 13946557 96830484 509673472 3.9529907703 4.2577357292 6.5909218788 386 15.4000000000 0.0077601224 0.0057184789 0.0077628260 0.0074740164 0.0041630000 0.0003980000 0.0023750000 0.0000000000 0.0000030000 0.0008630000 13949333 96830484 509673472 3.9560241699 4.2582926750 6.5931081772 387 15.4400000000 0.0077929907 0.0057238394 0.0077929907 0.0074759281 0.0049730000 0.0003990000 0.0028960000 0.0000030000 0.0000030000 0.0011440000 13952109 96830484 509673472 3.9597334862 4.2604236603 6.5953216553 388 15.4800000000 0.0077772569 0.0057291317 0.0077929907 0.0074669456 0.0042190000 0.0004000000 0.0024050000 0.0000000000 0.0000030000 0.0008790000 13954885 96830484 509673472 3.9627382755 4.2615790367 6.5963692665 389 15.5200000000 0.0077770837 0.0057343964 0.0077929907 0.0074581379 0.0050460000 0.0004000000 0.0024220000 0.0000040000 0.0000030000 0.0016850000 13957661 96830484 509673472 3.9653537273 4.2616858482 6.5973720551 390 15.5600000000 0.0077607809 0.0057395922 0.0077929907 0.0074486703 0.0042560000 0.0003980000 0.0024330000 0.0000000000 0.0000030000 0.0008920000 13960437 96830484 509673472 3.9692211151 4.2647280693 6.5986142159 391 15.6000000000 0.0077087246 0.0057446284 0.0077929907 0.0074560459 0.0044160000 0.0003990000 0.0023050000 0.0000030000 0.0000030000 0.0011770000 13963213 96830484 509673472 3.9723589420 4.2649397850 6.5999598503 392 15.6400000000 0.0077269007 0.0057496852 0.0077929907 0.0074474710 0.0042750000 0.0004000000 0.0024320000 0.0000000000 0.0000030000 0.0009030000 13965989 96830484 509673472 3.9752094746 4.2647452354 6.6003494263 393 15.6800000000 0.0076640551 0.0057545564 0.0077929907 0.0074382384 0.0051400000 0.0003980000 0.0024470000 0.0000030000 0.0000020000 0.0017500000 13968765 96830484 509673472 3.9772744179 4.2631621361 6.6010055542 394 15.7200000000 0.0077087372 0.0057595162 0.0077929907 0.0074301429 0.0042930000 0.0003980000 0.0024260000 0.0000000000 0.0000030000 0.0009290000 13971541 96830484 509673472 3.9793279171 4.2614059448 6.6020131111 395 15.7600000000 0.0077465060 0.0057645466 0.0077929907 0.0074322632 0.0047480000 0.0003980000 0.0025630000 0.0000030000 0.0000030000 0.0012400000 13974317 96830484 509673472 3.9826650620 4.2618608475 6.6026096344 396 15.8000000000 0.0077646100 0.0057695972 0.0077929907 0.0074268163 0.0044800000 0.0003980000 0.0025710000 0.0000010000 0.0000030000 0.0009690000 13977093 96830484 509673472 3.9864375591 4.2621340752 6.6028308868 397 15.8400000000 0.0077309567 0.0057745377 0.0077929907 0.0074297900 0.0052950000 0.0004000000 0.0024290000 0.0000040000 0.0000030000 0.0019170000 13979869 96830484 509673472 3.9892997742 4.2613101006 6.6027908325 398 15.8800000000 0.0077135116 0.0057794095 0.0077929907 0.0074246859 0.0042700000 0.0004010000 0.0023050000 0.0000000000 0.0000030000 0.0010190000 13982645 96830484 509673472 3.9922194481 4.2594923973 6.6021018028 399 15.9200000000 0.0076740026 0.0057841578 0.0077929907 0.0074168292 0.0044650000 0.0004000000 0.0021600000 0.0000030000 0.0000030000 0.0013570000 13985421 96830484 509673472 3.9967370033 4.2611165047 6.6006484032 400 15.9600000000 0.0076503023 0.0057888232 0.0077929907 0.0074097925 0.0042850000 0.0004000000 0.0023010000 0.0000000000 0.0000030000 0.0010400000 13988197 96830484 509673472 4.0010619164 4.2621221542 6.6008315086 401 16.0000000000 0.0076102433 0.0057933654 0.0077929907 0.0074043839 0.0053720000 0.0004000000 0.0024260000 0.0000040000 0.0000030000 0.0019930000 13990973 96830484 509673472 4.0053973198 4.2624897957 6.6012177467 402 16.0400000000 0.0076247579 0.0057979211 0.0077929907 0.0073959809 0.0040030000 0.0003990000 0.0020310000 0.0000000000 0.0000030000 0.0010250000 13993749 96830484 509673472 4.0109300613 4.2631044388 6.6009101868 403 16.0800000000 0.0076576588 0.0058025358 0.0077929907 0.0073904864 0.0047410000 0.0003980000 0.0024120000 0.0000030000 0.0000020000 0.0013790000 13996525 96830484 509673472 4.0155510902 4.2625999451 6.6021823883 404 16.1200000000 0.0077604498 0.0058073822 0.0077929907 0.0073819973 0.0044030000 0.0003980000 0.0024000000 0.0000000000 0.0000040000 0.0010550000 13999301 96830484 509673472 4.0205311775 4.2631030083 6.6009111404 405 16.1600000000 0.0079377787 0.0058126424 0.0079377787 0.0073733774 0.0053700000 0.0004010000 0.0023570000 0.0000040000 0.0000030000 0.0020520000 14002077 96830484 509673472 4.0259776115 4.2636036873 6.6018218994 406 16.2000000000 0.0081362789 0.0058183656 0.0081362789 0.0073647444 0.0045040000 0.0004320000 0.0024630000 0.0000000000 0.0000030000 0.0010530000 14004853 96830484 509673472 4.0319223404 4.2653036118 6.6039910316 407 16.2400000000 0.0081807654 0.0058241701 0.0081807654 0.0073570018 0.0043070000 0.0003970000 0.0019450000 0.0000040000 0.0000030000 0.0014050000 14007629 96830484 509673472 4.0371022224 4.2662134171 6.6058945656 408 16.2800000000 0.0082343314 0.0058300773 0.0082343314 0.0073598106 0.0043180000 0.0003970000 0.0022900000 0.0000000000 0.0000030000 0.0010730000 14010405 96830484 509673472 4.0424003601 4.2668251991 6.6086230278 409 16.3200000000 0.0081886621 0.0058358440 0.0082343314 0.0073628881 0.0054520000 0.0003980000 0.0024010000 0.0000040000 0.0000030000 0.0020850000 14013181 96830484 509673472 4.0490622520 4.2703733444 6.6114535332 410 16.3600000000 0.0082857823 0.0058418195 0.0082857823 0.0073541395 0.0042750000 0.0004010000 0.0022430000 0.0000000000 0.0000030000 0.0010680000 14015957 96830484 509673472 4.0552625656 4.2735033035 6.6156740189 411 16.3999999990 0.0083229775 0.0058478564 0.0083229775 0.0073481888 0.0046260000 0.0003980000 0.0022270000 0.0000030000 0.0000030000 0.0014330000 14018733 96830484 509673472 4.0587940216 4.2723112106 6.6174273491 412 16.4400000000 0.0082874354 0.0058537777 0.0083229775 0.0073641000 0.0042750000 0.0003990000 0.0022220000 0.0000000000 0.0000030000 0.0010900000 14021509 96830484 509673472 4.0640063286 4.2721576691 6.6238965988 413 16.4800000000 0.0083450871 0.0058598099 0.0083450871 0.0073784371 0.0053270000 0.0004000000 0.0022120000 0.0000030000 0.0000030000 0.0021410000 14024285 96830484 509673472 4.0703563690 4.2736282349 6.6309795380 414 16.5200000000 0.0083817057 0.0058659014 0.0083817057 0.0073747035 0.0042880000 0.0003980000 0.0022300000 0.0000000000 0.0000040000 0.0010910000 14027061 96830484 509673472 4.0751905441 4.2715601921 6.6345133781 415 16.5599999990 0.0084778704 0.0058721953 0.0084778704 0.0073894770 0.0046520000 0.0003980000 0.0022130000 0.0000030000 0.0000030000 0.0014720000 14029837 96830484 509673472 4.0783972740 4.2658677101 6.6400699615 416 16.6000000000 0.0085358229 0.0058785983 0.0085358229 0.0074722957 0.0042810000 0.0003980000 0.0022160000 0.0000000000 0.0000030000 0.0010910000 14032613 96830484 509673472 4.0847339630 4.2659163475 6.6457824707 417 16.6400000000 0.0085819019 0.0058850810 0.0085819019 0.0075057139 0.0054800000 0.0003990000 0.0023280000 0.0000040000 0.0000030000 0.0021750000 14035389 96830484 509673472 4.0910511017 4.2675933838 6.6474013329 418 16.6800000000 0.0086514475 0.0058916991 0.0086514475 0.0075103910 0.0044150000 0.0003980000 0.0023400000 0.0000010000 0.0000030000 0.0010960000 14038165 96830484 509673472 4.0932707787 4.2644901276 6.6467247009 419 16.7199999990 0.0087731397 0.0058985761 0.0087731397 0.0075425205 0.0051410000 0.0003980000 0.0026940000 0.0000030000 0.0000030000 0.0014680000 14040941 96830484 509673472 4.1011242867 4.2675762177 6.6524443626 420 16.7600000000 0.0087657440 0.0059054027 0.0087731397 0.0075338974 0.0044690000 0.0003980000 0.0023550000 0.0000010000 0.0000030000 0.0011110000 14043717 96830484 509673472 4.1084718704 4.2703027725 6.6523809433 421 16.8000000000 0.0088522006 0.0059124022 0.0088522006 0.0075450980 0.0057500000 0.0004930000 0.0023610000 0.0000040000 0.0000030000 0.0021880000 14046493 96830484 509673472 4.1124119759 4.2658700943 6.6533012390 422 16.8400000000 0.0089683440 0.0059196438 0.0089683440 0.0075425747 0.0043650000 0.0004420000 0.0022240000 0.0000010000 0.0000040000 0.0011050000 14049269 96830484 509673472 4.1213064194 4.2593297958 6.6553187370 423 16.8799999990 0.0089398352 0.0059267837 0.0089683440 0.0075389108 0.0048210000 0.0004000000 0.0023380000 0.0000040000 0.0000030000 0.0014900000 14052045 96830484 509673472 4.1283588409 4.2582559586 6.6552710533 424 16.9200000000 0.0087863971 0.0059335281 0.0089683440 0.0075305336 0.0044160000 0.0003970000 0.0023360000 0.0000010000 0.0000030000 0.0010960000 14054821 96830484 509673472 4.1336355209 4.2552499771 6.6530051231 425 16.9600000000 0.0086668991 0.0059399595 0.0089683440 0.0075301205 0.0058860000 0.0004000000 0.0027060000 0.0000040000 0.0000030000 0.0021880000 14057597 96830484 509673472 4.1413555145 4.2557187080 6.6503477097 426 17.0000000000 0.0086779827 0.0059463868 0.0089683440 0.0075224694 0.0044160000 0.0004000000 0.0023310000 0.0000010000 0.0000030000 0.0010900000 14060373 96830484 509673472 4.1502323151 4.2558245659 6.6496558189 427 17.0400000000 0.0086731836 0.0059527727 0.0089683440 0.0075205407 0.0057390000 0.0004000000 0.0032760000 0.0000030000 0.0000030000 0.0014690000 14063149 96830484 509673472 4.1561083794 4.2520556450 6.6451964378 428 17.0800000000 0.0087062456 0.0059592061 0.0089683440 0.0075123517 0.0051140000 0.0003990000 0.0030390000 0.0000010000 0.0000040000 0.0010870000 14065925 96830484 509673472 4.1658697128 4.2503232956 6.6418919563 429 17.1200000000 0.0085174125 0.0059651693 0.0089683440 0.0075055435 0.0064380000 0.0004000000 0.0032400000 0.0000030000 0.0000030000 0.0021770000 14068701 96830484 509673472 4.1762199402 4.2491555214 6.6403279305 430 17.1600000000 0.0088024130 0.0059717675 0.0089683440 0.0075030671 0.0061630000 0.0004000000 0.0040780000 0.0000000000 0.0000040000 0.0010880000 14071477 96830484 509673472 4.1846570969 4.2454786301 6.6335592270 431 17.2000000000 0.0089793056 0.0059787456 0.0089793056 0.0074944372 0.0054920000 0.0003990000 0.0030040000 0.0000040000 0.0000030000 0.0014850000 14074253 96830484 509673472 4.1942462921 4.2411890030 6.6301403046 432 17.2400000000 0.0091351802 0.0059860521 0.0091351802 0.0074932025 0.0064920000 0.0003980000 0.0044080000 0.0000010000 0.0000040000 0.0010880000 14077029 96830484 509673472 4.2063670158 4.2399039268 6.6254305840 433 17.2800000000 0.0088987369 0.0059927789 0.0091351802 0.0074860071 0.0075890000 0.0004000000 0.0043950000 0.0000040000 0.0000030000 0.0021890000 14079805 96830484 509673472 4.2175412178 4.2383670807 6.6197524071 434 17.3200000000 0.0088293897 0.0059993149 0.0091351802 0.0074774338 0.0058190000 0.0003980000 0.0037390000 0.0000000000 0.0000030000 0.0010840000 14082581 96830484 509673472 4.2272930145 4.2337594032 6.6112394333 435 17.3600000000 0.0087972004 0.0060057468 0.0091351802 0.0074888749 0.0065860000 0.0003990000 0.0041050000 0.0000030000 0.0000030000 0.0014760000 14085357 96830484 509673472 4.2402200699 4.2329463959 6.6058607101 436 17.4000000000 0.0087523190 0.0060120463 0.0091351802 0.0074941100 0.0051200000 0.0004010000 0.0030370000 0.0000000000 0.0000040000 0.0010780000 14088133 96830484 509673472 4.2561111450 4.2366771698 6.5988545418 437 17.4400000000 0.0088253776 0.0060184841 0.0091351802 0.0074916458 0.0065840000 0.0003980000 0.0033800000 0.0000030000 0.0000030000 0.0021950000 14090909 96830484 509673472 4.2734794617 4.2422299385 6.5902395248 438 17.4800000000 0.0087700067 0.0060247661 0.0091351802 0.0075961711 0.0058150000 0.0004010000 0.0037300000 0.0000010000 0.0000030000 0.0010730000 14093685 96830484 509673472 4.2868208885 4.2434558868 6.5821967125 439 17.5200000000 0.0086374208 0.0060307175 0.0091351802 0.0077374701 0.0069340000 0.0004010000 0.0044240000 0.0000040000 0.0000040000 0.0014950000 14096461 96830484 509673472 4.2942752838 4.2379856110 6.5713262558 440 17.5600000000 0.0085926550 0.0060365401 0.0091351802 0.0077669115 0.0058180000 0.0004000000 0.0037330000 0.0000010000 0.0000030000 0.0010740000 14099237 96830484 509673472 4.3002514839 4.2293653488 6.5628676414 441 17.6000000000 0.0086851101 0.0060425459 0.0091351802 0.0077633666 0.0075460000 0.0003990000 0.0043910000 0.0000030000 0.0000030000 0.0021420000 14102013 96830484 509673472 4.3081564903 4.2225627899 6.5553159714 442 17.6400000000 0.0085355854 0.0060481862 0.0091351802 0.0078229197 0.0054400000 0.0004000000 0.0033650000 0.0000010000 0.0000030000 0.0010630000 14104789 96830484 509673472 4.3215737343 4.2234468460 6.5462479591 443 17.6800000000 0.0083706332 0.0060534288 0.0091351802 0.0078455149 0.0055190000 0.0004000000 0.0030270000 0.0000040000 0.0000030000 0.0014790000 14107565 96830484 509673472 4.3470187187 4.2275171280 6.5287795067 444 17.7200000000 0.0079312539 0.0060576581 0.0091351802 0.0078406241 0.0062050000 0.0004010000 0.0041050000 0.0000010000 0.0000030000 0.0010860000 14110341 96830484 509673472 4.3558998108 4.2267451286 6.5169005394 445 17.7600000000 0.0079429168 0.0060618947 0.0091351802 0.0078367850 0.0059130000 0.0003990000 0.0026710000 0.0000030000 0.0000030000 0.0022220000 14113117 96830484 509673472 4.3660683632 4.2239298820 6.5087947845 446 17.8000000000 0.0080221100 0.0060662898 0.0091351802 0.0078279912 0.0065660000 0.0004020000 0.0044700000 0.0000000000 0.0000030000 0.0010810000 14115893 96830484 509673472 4.3761963844 4.2241234779 6.4996829033 447 17.8400000000 0.0077645662 0.0060700890 0.0091351802 0.0078236018 0.0068380000 0.0004000000 0.0043330000 0.0000030000 0.0000030000 0.0014860000 14118669 96830484 509673472 4.3836765289 4.2211017609 6.4918394089 448 17.8800000000 0.0079199476 0.0060742182 0.0091351802 0.0078149197 0.0044410000 0.0004010000 0.0023270000 0.0000000000 0.0000030000 0.0010910000 14121445 96830484 509673472 4.3914966583 4.2191653252 6.4843926430 449 17.9200000000 0.0080029164 0.0060785137 0.0091351802 0.0078064169 0.0076990000 0.0003990000 0.0044400000 0.0000040000 0.0000030000 0.0022320000 14124221 96830484 509673472 4.3996429443 4.2173199654 6.4763746262 450 17.9600000000 0.0079508293 0.0060826744 0.0091351802 0.0077989529 0.0065610000 0.0004000000 0.0044520000 0.0000010000 0.0000030000 0.0010860000 14126997 96830484 509673472 4.4062380791 4.2131223679 6.4705810547 451 18.0000000000 0.0077521862 0.0060863762 0.0091351802 0.0078022423 0.0069960000 0.0004010000 0.0044530000 0.0000030000 0.0000030000 0.0015140000 14129773 96830484 509673472 4.4154338837 4.2126736641 6.4646272659 452 18.0400000000 0.0078977384 0.0060903837 0.0091351802 0.0077961823 0.0058650000 0.0004000000 0.0037580000 0.0000010000 0.0000030000 0.0010850000 14132549 96830484 509673472 4.4255423546 4.2127766609 6.4580779076 453 18.0800000000 0.0078627691 0.0060942962 0.0091351802 0.0077875609 0.0066450000 0.0003990000 0.0033840000 0.0000030000 0.0000030000 0.0022290000 14135325 96830484 509673472 4.4330635071 4.2094402313 6.4514865875 454 18.1200000000 0.0077575836 0.0060979598 0.0091351802 0.0077867958 0.0062050000 0.0004000000 0.0040930000 0.0000000000 0.0000030000 0.0010850000 14138101 96830484 509673472 4.4429168701 4.2086572647 6.4458513260 455 18.1600000000 0.0077107255 0.0061015044 0.0091351802 0.0077794257 0.0069680000 0.0003990000 0.0044460000 0.0000030000 0.0000020000 0.0014900000 14140877 96830484 509673472 4.4531550407 4.2076830864 6.4406008720 456 18.2000000000 0.0078229466 0.0061052795 0.0091351802 0.0077724978 0.0043990000 0.0003990000 0.0022790000 0.0000000000 0.0000030000 0.0010860000 14143653 96830484 509673472 4.4619107246 4.2045464516 6.4340710640 457 18.2400000000 0.0077467612 0.0061088713 0.0091351802 0.0077736151 0.0069220000 0.0003980000 0.0036570000 0.0000030000 0.0000030000 0.0022350000 14146429 96830484 509673472 4.4709420204 4.2017283440 6.4290819168 458 18.2800000000 0.0077503971 0.0061124555 0.0091351802 0.0077881595 0.0064760000 0.0003990000 0.0043560000 0.0000000000 0.0000030000 0.0010890000 14149205 96830484 509673472 4.4827232361 4.2029695511 6.4261312485 459 18.3200000000 0.0079559600 0.0061164718 0.0091351802 0.0077816548 0.0068850000 0.0003990000 0.0043620000 0.0000030000 0.0000030000 0.0014880000 14151981 96830484 509673472 4.4961409569 4.2053523064 6.4198803902 460 18.3600000000 0.0077024545 0.0061199196 0.0091351802 0.0077814317 0.0054480000 0.0003990000 0.0033270000 0.0000000000 0.0000040000 0.0010880000 14154757 96830484 509673472 4.5040397644 4.2013778687 6.4160194397 461 18.4000000000 0.0076168058 0.0061231666 0.0091351802 0.0077739524 0.0065910000 0.0003980000 0.0033130000 0.0000030000 0.0000020000 0.0022430000 14157533 96830484 509673472 4.5150842667 4.1995186806 6.4130368233 462 18.4400000000 0.0075979745 0.0061263589 0.0091351802 0.0077665776 0.0050960000 0.0004010000 0.0029730000 0.0000000000 0.0000040000 0.0010900000 14160309 96830484 509673472 4.5262737274 4.2004065514 6.4073219299 463 18.4800000000 0.0075927302 0.0061295260 0.0091351802 0.0077608877 0.0058450000 0.0003980000 0.0033240000 0.0000040000 0.0000030000 0.0014820000 14163085 96830484 509673472 4.5355434418 4.1983575821 6.4011416435 464 18.5200000000 0.0076373452 0.0061327756 0.0091351802 0.0077546218 0.0055060000 0.0003980000 0.0033650000 0.0000000000 0.0000030000 0.0011040000 14165861 96830484 509673472 4.5433955193 4.1948413849 6.3981666565 465 18.5600000000 0.0076478859 0.0061360339 0.0091351802 0.0077504926 0.0059540000 0.0003990000 0.0026430000 0.0000030000 0.0000030000 0.0022670000 14168637 96830484 509673472 4.5513367653 4.1907601357 6.3950834274 466 18.6000000000 0.0074602794 0.0061388756 0.0091351802 0.0077670942 0.0048170000 0.0003980000 0.0026710000 0.0000000000 0.0000030000 0.0011060000 14171413 96830484 509673472 4.5628476143 4.1917138100 6.3919367790 467 18.6400000000 0.0073102303 0.0061413839 0.0091351802 0.0077622145 0.0055740000 0.0003980000 0.0030230000 0.0000040000 0.0000030000 0.0015070000 14174189 96830484 509673472 4.5738010406 4.1900820732 6.3892912865 468 18.6800000000 0.0074310768 0.0061441396 0.0091351802 0.0077638383 0.0062410000 0.0004000000 0.0040920000 0.0000010000 0.0000030000 0.0011030000 14176965 96830484 509673472 4.5838475227 4.1866078377 6.3884840012 469 18.7200000000 0.0074154534 0.0061468503 0.0091351802 0.0077859713 0.0066650000 0.0004000000 0.0033360000 0.0000030000 0.0000030000 0.0022830000 14179741 96830484 509673472 4.5931591988 4.1850676537 6.3871607780 470 18.7600000000 0.0074397265 0.0061496011 0.0091351802 0.0078044867 0.0044700000 0.0003990000 0.0023050000 0.0000010000 0.0000030000 0.0011200000 14182517 96830484 509673472 4.6016001701 4.1816930771 6.3867478371 471 18.8000000000 0.0073985984 0.0061522529 0.0091351802 0.0078560872 0.0052190000 0.0004020000 0.0026520000 0.0000030000 0.0000030000 0.0015130000 14185293 96830484 509673472 4.6128129959 4.1799640656 6.3846597672 472 18.8400000000 0.0073946007 0.0061548850 0.0091351802 0.0078999017 0.0051870000 0.0003970000 0.0030130000 0.0000000000 0.0000030000 0.0011250000 14188069 96830484 509673472 4.6234240532 4.1802377701 6.3815937042 473 18.8800000000 0.0074693197 0.0061576639 0.0091351802 0.0079087399 0.0059690000 0.0004000000 0.0026120000 0.0000040000 0.0000030000 0.0023050000 14190845 96830484 509673472 4.6330971718 4.1803116798 6.3775429726 474 18.9200000000 0.0074319080 0.0061603522 0.0091351802 0.0079063582 0.0048380000 0.0003990000 0.0026500000 0.0000000000 0.0000030000 0.0011370000 14193621 96830484 509673472 4.6384119987 4.1788721085 6.3699936867 475 18.9600000000 0.0074722944 0.0061631142 0.0091351802 0.0079050956 0.0048640000 0.0003990000 0.0022680000 0.0000040000 0.0000030000 0.0015390000 14196397 96830484 509673472 4.6472187042 4.1769437790 6.3678359985 476 19.0000000000 0.0075043095 0.0061659318 0.0091351802 0.0079108938 0.0048360000 0.0004010000 0.0026260000 0.0000010000 0.0000030000 0.0011520000 14199173 96830484 509673472 4.6564579010 4.1767673492 6.3651156425 477 19.0400000000 0.0074581881 0.0061686410 0.0091351802 0.0079090810 0.0059910000 0.0004010000 0.0026190000 0.0000030000 0.0000040000 0.0023050000 14201949 96830484 509673472 4.6648988724 4.1767644882 6.3571753502 478 19.0800000000 0.0075200340 0.0061714682 0.0091351802 0.0079029919 0.0052220000 0.0003990000 0.0029890000 0.0000010000 0.0000030000 0.0011720000 14204725 96830484 509673472 4.6776580811 4.1761507988 6.3602948189 479 19.1200000000 0.0075669531 0.0061743815 0.0091351802 0.0078959213 0.0049010000 0.0004000000 0.0022910000 0.0000040000 0.0000030000 0.0015490000 14207501 96830484 509673472 4.6849417686 4.1733856201 6.3590211868 480 19.1600000000 0.0077109174 0.0061775826 0.0091351802 0.0079012486 0.0052740000 0.0003990000 0.0030230000 0.0000010000 0.0000030000 0.0011850000 14210277 96830484 509673472 4.6955070496 4.1714773178 6.3608751297 481 19.2000000000 0.0080176434 0.0061814081 0.0091351802 0.0079168017 0.0067720000 0.0003970000 0.0033600000 0.0000030000 0.0000030000 0.0023450000 14213053 96830484 509673472 4.7033867836 4.1736750603 6.3549947739 482 19.2400000000 0.0079697566 0.0061851184 0.0091351802 0.0079091110 0.0067160000 0.0003990000 0.0044630000 0.0000010000 0.0000030000 0.0011910000 14215829 96830484 509673472 4.7131662369 4.1732430458 6.3561902046 483 19.2800000000 0.0078590689 0.0061885841 0.0091351802 0.0079011295 0.0052080000 0.0003980000 0.0025710000 0.0000040000 0.0000030000 0.0015710000 14218605 96830484 509673472 4.7217345238 4.1709036827 6.3549637794 484 19.3200000000 0.0080566360 0.0061924437 0.0091351802 0.0078977676 0.0067740000 0.0004010000 0.0045280000 0.0000000000 0.0000040000 0.0011750000 14221381 96830484 509673472 4.7269506454 4.1707863808 6.3504276276 485 19.3600000000 0.0082232198 0.0061966309 0.0091351802 0.0078948609 0.0064850000 0.0003990000 0.0030780000 0.0000040000 0.0000030000 0.0023390000 14224157 96830484 509673472 4.7365651131 4.1739192009 6.3460178375 486 19.4000000000 0.0079949908 0.0062003312 0.0091351802 0.0078976986 0.0049670000 0.0004000000 0.0027280000 0.0000010000 0.0000030000 0.0011710000 14226933 96830484 509673472 4.7453379631 4.1768369675 6.3436427116 487 19.4400000000 0.0081571871 0.0062043494 0.0091351802 0.0079399672 0.0053580000 0.0003980000 0.0027270000 0.0000040000 0.0000030000 0.0015570000 14229709 96830484 509673472 4.7514152527 4.1737446785 6.3407478333 488 19.4800000000 0.0080855321 0.0062082043 0.0091351802 0.0079393455 0.0048580000 0.0003990000 0.0026100000 0.0000010000 0.0000030000 0.0011740000 14232485 96830484 509673472 4.7512836456 4.1710939407 6.3332109451 489 19.5200000000 0.0081153046 0.0062121043 0.0091351802 0.0079313627 0.0060230000 0.0004010000 0.0026110000 0.0000030000 0.0000030000 0.0023330000 14235261 96830484 509673472 4.7562661171 4.1705727577 6.3288855553 490 19.5600000000 0.0081001110 0.0062159573 0.0091351802 0.0079235359 0.0046060000 0.0003980000 0.0023680000 0.0000010000 0.0000030000 0.0011640000 14238037 96830484 509673472 4.7603125572 4.1698632240 6.3205952644 491 19.6000000000 0.0080622975 0.0062197177 0.0091351802 0.0079156667 0.0060410000 0.0003990000 0.0034090000 0.0000030000 0.0000030000 0.0015550000 14240813 96830484 509673472 4.7660760880 4.1690659523 6.3162446022 492 19.6400000000 0.0082244007 0.0062237923 0.0091351802 0.0079076931 0.0049590000 0.0003990000 0.0027230000 0.0000000000 0.0000030000 0.0011540000 14243589 96830484 509673472 4.7663931847 4.1695818901 6.3045768738 493 19.6800000000 0.0081568705 0.0062277133 0.0091351802 0.0079049844 0.0061030000 0.0003990000 0.0027170000 0.0000030000 0.0000030000 0.0023010000 14246365 96830484 509673472 4.7684059143 4.1687517166 6.2935690880 494 19.7200000000 0.0080229510 0.0062313474 0.0091351802 0.0079064319 0.0045830000 0.0003990000 0.0023590000 0.0000000000 0.0000030000 0.0011460000 14249141 96830484 509673472 4.7697520256 4.1637191772 6.2863411903 495 19.7600000000 0.0080633191 0.0062350484 0.0091351802 0.0078998208 0.0057070000 0.0004000000 0.0030860000 0.0000030000 0.0000040000 0.0015370000 14251917 96830484 509673472 4.7695498466 4.1607875824 6.2757277489 496 19.8000000000 0.0081157507 0.0062388401 0.0091351802 0.0078959368 0.0046070000 0.0004000000 0.0023780000 0.0000000000 0.0000030000 0.0011470000 14254693 96830484 509673472 4.7682056427 4.1609678268 6.2684803009 497 19.8400000000 0.0080524385 0.0062424892 0.0091351802 0.0078884346 0.0057470000 0.0004030000 0.0023620000 0.0000030000 0.0000030000 0.0022950000 14257469 96830484 509673472 4.7715363503 4.1578588486 6.2621955872 498 19.8800000000 0.0080937240 0.0062462065 0.0091351802 0.0078817247 0.0048570000 0.0004000000 0.0026250000 0.0000000000 0.0000030000 0.0011420000 14260245 96830484 509673472 4.7698354721 4.1567740440 6.2512321472 499 19.9200000000 0.0081861103 0.0062500941 0.0091351802 0.0078738821 0.0052080000 0.0003980000 0.0025940000 0.0000040000 0.0000030000 0.0015250000 14263021 96830484 509673472 4.7707886696 4.1555590630 6.2446579933 500 19.9600000000 0.0081768297 0.0062539476 0.0091351802 0.0078662410 0.0049470000 0.0003990000 0.0027180000 0.0000000000 0.0000040000 0.0011390000 14265797 96830484 509673472 4.7706351280 4.1541814804 6.2343664169 501 20.0000000000 0.0082747182 0.0062579811 0.0091351802 0.0078590819 0.0064120000 0.0003970000 0.0030590000 0.0000030000 0.0000030000 0.0022630000 14268573 96830484 509673472 4.7714900970 4.1525149345 6.2237076759 502 20.0400000000 0.0081732366 0.0062617963 0.0091351802 0.0078513418 0.0044750000 0.0003980000 0.0022370000 0.0000000000 0.0000040000 0.0011460000 14271349 96830484 509673472 4.7748017311 4.1500830650 6.2177195549 503 20.0800000000 0.0081220027 0.0062654945 0.0091351802 0.0078446553 0.0055650000 0.0003990000 0.0029570000 0.0000030000 0.0000030000 0.0015130000 14274125 96830484 509673472 4.7768664360 4.1501765251 6.2048945427 504 20.1200000000 0.0082678292 0.0062694674 0.0091351802 0.0078377818 0.0060370000 0.0004000000 0.0038290000 0.0000000000 0.0000030000 0.0011130000 14276901 96830484 509673472 4.7755236626 4.1470670700 6.1943273544 505 20.1600000000 0.0082223369 0.0062733345 0.0091351802 0.0078334719 0.0064540000 0.0003990000 0.0031140000 0.0000030000 0.0000030000 0.0022430000 14279677 96830484 509673472 4.7714524269 4.1451625824 6.1814012527 506 20.2000000000 0.0084591173 0.0062776542 0.0091351802 0.0078301477 0.0053180000 0.0004010000 0.0031090000 0.0000000000 0.0000030000 0.0011080000 14282453 96830484 509673472 4.7707886696 4.1479835510 6.1724123955 507 20.2400000000 0.0084900158 0.0062820178 0.0091351802 0.0078287712 0.0055930000 0.0003980000 0.0029850000 0.0000030000 0.0000030000 0.0015080000 14285229 96830484 509673472 4.7709856033 4.1490192413 6.1610789299 508 20.2800000000 0.0083995694 0.0062861863 0.0091351802 0.0078340411 0.0049660000 0.0004000000 0.0027440000 0.0000000000 0.0000040000 0.0011190000 14288005 96830484 509673472 4.7636222839 4.1464247704 6.1515045166 509 20.3200000000 0.0083845006 0.0062903087 0.0091351802 0.0078279726 0.0060540000 0.0004000000 0.0027490000 0.0000030000 0.0000040000 0.0022000000 14290781 96830484 509673472 4.7673354149 4.1452345848 6.1419286728 510 20.3600000000 0.0084520821 0.0062945474 0.0091351802 0.0078205729 0.0049820000 0.0004010000 0.0027670000 0.0000000000 0.0000030000 0.0011100000 14293557 96830484 509673472 4.7717137337 4.1464204788 6.1270575523 511 20.4000000000 0.0084441761 0.0062987542 0.0091351802 0.0078140358 0.0050010000 0.0003980000 0.0023990000 0.0000030000 0.0000030000 0.0014900000 14296333 96830484 509673472 4.7746062279 4.1502981186 6.1147265434 512 20.4400000000 0.0085134516 0.0063030797 0.0091351802 0.0078253559 0.0053490000 0.0004000000 0.0031330000 0.0000000000 0.0000030000 0.0011120000 14299109 96830484 509673472 4.7712345123 4.1509475708 6.1017856598 513 20.4800000000 0.0086237658 0.0063076035 0.0091351802 0.0078320443 0.0060860000 0.0004000000 0.0027430000 0.0000030000 0.0000030000 0.0022200000 14351037 96830484 509673472 4.7759599686 4.1494607925 6.0905556679 514 20.5200000000 0.0086605484 0.0063121812 0.0091351802 0.0078261438 0.0049940000 0.0003990000 0.0027620000 0.0000010000 0.0000030000 0.0011140000 14456213 96830484 509673472 4.7774095535 4.1509890556 6.0789632797 515 20.5600000000 0.0087015498 0.0063168208 0.0091351802 0.0078259680 0.0053690000 0.0004000000 0.0027630000 0.0000030000 0.0000030000 0.0014830000 14458989 96830484 509673472 4.7826809883 4.1531939507 6.0665922165 516 20.6000000000 0.0087606786 0.0063215569 0.0091351802 0.0078358264 0.0050220000 0.0004000000 0.0027820000 0.0000000000 0.0000040000 0.0011210000 14461765 96830484 509673472 4.7855682373 4.1523876190 6.0530118942 517 20.6400000000 0.0088112196 0.0063263725 0.0091351802 0.0078390466 0.0060960000 0.0004010000 0.0027720000 0.0000040000 0.0000030000 0.0022000000 14464541 96830484 509673472 4.7812833786 4.1500720978 6.0541625023 518 20.6800000000 0.0086953649 0.0063309459 0.0091351802 0.0078317391 0.0057850000 0.0003980000 0.0035500000 0.0000010000 0.0000030000 0.0011150000 14467317 96830484 509673472 4.7955279350 4.1502113342 6.0333614349 519 20.7200000000 0.0087861931 0.0063356766 0.0091351802 0.0078253981 0.0053930000 0.0003980000 0.0027740000 0.0000030000 0.0000030000 0.0014920000 14470093 96830484 509673472 4.7864437103 4.1529822350 6.0374698639 520 20.7600000000 0.0088223740 0.0063404587 0.0091351802 0.0078297346 0.0068450000 0.0003990000 0.0046160000 0.0000000000 0.0000030000 0.0011040000 14472869 96830484 509673472 4.7793974876 4.1547803879 6.0376439095 521 20.8000000000 0.0087168086 0.0063450198 0.0091351802 0.0078436947 0.0060750000 0.0004010000 0.0027460000 0.0000030000 0.0000020000 0.0021990000 14475645 96830484 509673472 4.7771024704 4.1525921822 6.0300731659 522 20.8400000000 0.0088139474 0.0063497496 0.0091351802 0.0078406754 0.0046410000 0.0004010000 0.0024110000 0.0000000000 0.0000030000 0.0011020000 14478421 96830484 509673472 4.7787184715 4.1489777565 6.0234999657 523 20.8800000000 0.0087479251 0.0063543350 0.0091351802 0.0078337849 0.0050040000 0.0004000000 0.0023980000 0.0000030000 0.0000020000 0.0014750000 14481197 96830484 509673472 4.7683458328 4.1477532387 6.0292539597 524 20.9200000000 0.0087871654 0.0063589778 0.0091351802 0.0078296915 0.0050260000 0.0004000000 0.0027870000 0.0000000000 0.0000040000 0.0011080000 14483973 96830484 509673472 4.7851586342 4.1480789185 6.0077056885 525 20.9600000000 0.0087143574 0.0063634642 0.0091351802 0.0078222397 0.0057160000 0.0003980000 0.0024000000 0.0000030000 0.0000030000 0.0021860000 14486749 96830484 509673472 4.7849178314 4.1473507881 6.0027265549 526 21.0000000000 0.0086346474 0.0063677821 0.0091351802 0.0078152247 0.0049780000 0.0003990000 0.0027510000 0.0000000000 0.0000040000 0.0010980000 14489525 96830484 509673472 4.7928900719 4.1437883377 5.9897370338 527 21.0400000000 0.0086461613 0.0063721054 0.0091351802 0.0078157156 0.0057360000 0.0003990000 0.0031130000 0.0000030000 0.0000030000 0.0014810000 14492301 96830484 509673472 4.7939610481 4.1442942619 5.9806342125 528 21.0800000000 0.0087738801 0.0063766542 0.0091351802 0.0078085082 0.0049920000 0.0003990000 0.0027570000 0.0000010000 0.0000030000 0.0011010000 14495077 96830484 509673472 4.7966365814 4.1438608170 5.9758238792 529 21.1200000000 0.0086536994 0.0063809586 0.0091351802 0.0078020471 0.0060830000 0.0003980000 0.0027400000 0.0000030000 0.0000030000 0.0022050000 14497853 96830484 509673472 4.8098773956 4.1417360306 5.9552726746 530 21.1600000000 0.0086644525 0.0063852671 0.0091351802 0.0077974001 0.0057250000 0.0003990000 0.0034850000 0.0000000000 0.0000030000 0.0011030000 14500629 96830484 509673472 4.8064451218 4.1419634819 5.9534840584 531 21.2000000000 0.0087460103 0.0063897129 0.0091351802 0.0077907523 0.0053780000 0.0003990000 0.0027400000 0.0000030000 0.0000030000 0.0014930000 14503405 96830484 509673472 4.8145236969 4.1408677101 5.9383187294 532 21.2400000000 0.0087307543 0.0063941134 0.0091351802 0.0077846682 0.0053790000 0.0003980000 0.0031250000 0.0000010000 0.0000040000 0.0011110000 14506181 96830484 509673472 4.8149604797 4.1395015717 5.9302625656 533 21.2800000000 0.0086800000 0.0063984021 0.0091351802 0.0077786222 0.0061170000 0.0004000000 0.0027630000 0.0000030000 0.0000030000 0.0022080000 14508957 96830484 509673472 4.8135461807 4.1384544373 5.9251823425 534 21.3200000000 0.0088042160 0.0064029074 0.0091351802 0.0077738455 0.0050290000 0.0003980000 0.0027710000 0.0000010000 0.0000030000 0.0011150000 14511733 96830484 509673472 4.8208456039 4.1369023323 5.9098229408 535 21.3600000000 0.0087679354 0.0064073280 0.0091351802 0.0077697227 0.0050510000 0.0004000000 0.0024100000 0.0000030000 0.0000030000 0.0014870000 14514509 96830484 509673472 4.8265252113 4.1390552521 5.8949570656 536 21.4000000000 0.0087472247 0.0064116935 0.0091351802 0.0077633765 0.0050460000 0.0003990000 0.0027840000 0.0000010000 0.0000030000 0.0011170000 14517285 96830484 509673472 4.8240976334 4.1382117271 5.8910775185 537 21.4400000000 0.0089932000 0.0064165008 0.0091351802 0.0077562390 0.0064950000 0.0004000000 0.0031480000 0.0000030000 0.0000020000 0.0021950000 14520061 96830484 509673472 4.8318705559 4.1367402077 5.8738317490 538 21.4800000000 0.0089997808 0.0064213024 0.0091351802 0.0077492383 0.0046920000 0.0003980000 0.0024120000 0.0000010000 0.0000030000 0.0011320000 14522837 96830484 509673472 4.8319997787 4.1366953850 5.8655910492 539 21.5200000000 0.0092123142 0.0064264805 0.0092123142 0.0077421782 0.0072960000 0.0004010000 0.0046550000 0.0000030000 0.0000030000 0.0014850000 14525613 96830484 509673472 4.8303093910 4.1364326477 5.8575897217 540 21.5600000000 0.0094159255 0.0064320165 0.0094159255 0.0077361022 0.0054420000 0.0004010000 0.0031590000 0.0000000000 0.0000040000 0.0011240000 14528389 96830484 509673472 4.8334541321 4.1376519203 5.8429317474 541 21.6000000000 0.0092303716 0.0064371891 0.0094159255 0.0077293595 0.0061620000 0.0004010000 0.0027680000 0.0000040000 0.0000030000 0.0022330000 14531165 96830484 509673472 4.8339939117 4.1392941475 5.8336634636 542 21.6400000000 0.0091242511 0.0064421468 0.0094159255 0.0077270981 0.0054420000 0.0004010000 0.0031570000 0.0000000000 0.0000030000 0.0011280000 14533941 96830484 509673472 4.8363695145 4.1373543739 5.8208608627 543 21.6800000000 0.0091312993 0.0064470992 0.0094159255 0.0077200777 0.0054330000 0.0003990000 0.0027960000 0.0000030000 0.0000040000 0.0014810000 14536717 96830484 509673472 4.8373289108 4.1347770691 5.8155841827 544 21.7200000000 0.0092237750 0.0064522034 0.0094159255 0.0077198805 0.0050830000 0.0003990000 0.0027860000 0.0000000000 0.0000030000 0.0011350000 14539493 96830484 509673472 4.8379201889 4.1355881691 5.8053398132 545 21.7600000000 0.0094288066 0.0064576650 0.0094288066 0.0077164967 0.0061570000 0.0003980000 0.0027820000 0.0000030000 0.0000030000 0.0022080000 14542269 96830484 509673472 4.8407568932 4.1342000961 5.7931709290 546 21.8000000000 0.0094837183 0.0064632072 0.0094837183 0.0077209119 0.0051110000 0.0003980000 0.0028020000 0.0000000000 0.0000030000 0.0011390000 14545045 96830484 509673472 4.8422369957 4.1348857880 5.7865090370 547 21.8400000000 0.0095994147 0.0064689407 0.0095994147 0.0077189207 0.0054610000 0.0004010000 0.0027880000 0.0000030000 0.0000030000 0.0015020000 14547821 96830484 509673472 4.8442368507 4.1367926598 5.7747502327 548 21.8800000000 0.0095542790 0.0064745709 0.0095994147 0.0077120103 0.0050950000 0.0003990000 0.0027910000 0.0000010000 0.0000040000 0.0011430000 14550597 96830484 509673472 4.8409194946 4.1370506287 5.7714562416 549 21.9200000000 0.0091554038 0.0064794540 0.0095994147 0.0077054213 0.0061850000 0.0004000000 0.0028000000 0.0000040000 0.0000030000 0.0022200000 14553373 96830484 509673472 4.8420424461 4.1360449791 5.7651491165 550 21.9600000000 0.0092881676 0.0064845608 0.0095994147 0.0076990704 0.0054540000 0.0003990000 0.0025710000 0.0000010000 0.0000040000 0.0015160000 14556149 96830484 509673472 4.8415980339 4.1383247375 5.7582468987 551 22.0000000000 0.0094120018 0.0064898737 0.0095994147 0.0076933933 0.0060610000 0.0004160000 0.0032840000 0.0000040000 0.0000030000 0.0015520000 14558925 96830484 509673472 4.8420891762 4.1383814812 5.7502007484 552 22.0400000000 0.0097538820 0.0064957868 0.0097538820 0.0076866198 0.0048000000 0.0004050000 0.0024150000 0.0000010000 0.0000040000 0.0011590000 14561701 96830484 509673472 4.8453960419 4.1400194168 5.7418670654 553 22.0800000000 0.0097908294 0.0065017453 0.0097908294 0.0076831417 0.0062160000 0.0004020000 0.0027740000 0.0000040000 0.0000030000 0.0022280000 14564477 96830484 509673472 4.8439669609 4.1400570869 5.7394895554 554 22.1200000000 0.0095561575 0.0065072586 0.0097908294 0.0076772028 0.0051480000 0.0004010000 0.0027820000 0.0000000000 0.0000030000 0.0011530000 14567253 96830484 509673472 4.8443470001 4.1382074356 5.7326140404 555 22.1600000000 0.0095349252 0.0065127139 0.0097908294 0.0076708930 0.0053850000 0.0003990000 0.0026510000 0.0000030000 0.0000030000 0.0015180000 14570029 96830484 509673472 4.8450918198 4.1407017708 5.7244520187 556 22.2000000000 0.0100431945 0.0065190637 0.0100431945 0.0076671176 0.0051380000 0.0004010000 0.0027660000 0.0000000000 0.0000030000 0.0011610000 14572805 96830484 509673472 4.8449101448 4.1436681747 5.7155885696 557 22.2400000000 0.0101697007 0.0065256178 0.0101697007 0.0076747355 0.0056770000 0.0003990000 0.0022650000 0.0000030000 0.0000030000 0.0022320000 14575581 96830484 509673472 4.8444256783 4.1410546303 5.7114071846 558 22.2800000000 0.0102632223 0.0065323160 0.0102632223 0.0076679940 0.0047490000 0.0003980000 0.0023950000 0.0000000000 0.0000040000 0.0011760000 14578357 96830484 509673472 4.8423857689 4.1385750771 5.7053842545 559 22.3200000000 0.0100698434 0.0065386443 0.0102632223 0.0076632657 0.0051080000 0.0003980000 0.0023870000 0.0000030000 0.0000030000 0.0015440000 14581133 96830484 509673472 4.8418793678 4.1407890320 5.7001104355 560 22.3600000000 0.0102633834 0.0065452956 0.0102633834 0.0076576424 0.0049840000 0.0003970000 0.0026370000 0.0000000000 0.0000030000 0.0011650000 14583909 96830484 509673472 4.8406429291 4.1408562660 5.6966810226 561 22.4000000000 0.0104557294 0.0065522661 0.0104557294 0.0076517710 0.0058400000 0.0004000000 0.0023770000 0.0000040000 0.0000030000 0.0022770000 14586685 96830484 509673472 4.8440642357 4.1399374008 5.6882143021 562 22.4400000000 0.0109123262 0.0065600242 0.0109123262 0.0076451726 0.0051080000 0.0004010000 0.0027570000 0.0000000000 0.0000040000 0.0011720000 14589461 96830484 509673472 4.8425641060 4.1417021751 5.6849908829 563 22.4800000000 0.0110126510 0.0065679330 0.0110126510 0.0076408308 0.0055080000 0.0003980000 0.0027780000 0.0000030000 0.0000030000 0.0015450000 14592237 96830484 509673472 4.8447556496 4.1417579651 5.6756491661 564 22.5200000000 0.0108684907 0.0065755581 0.0110126510 0.0076375898 0.0047680000 0.0003980000 0.0024130000 0.0000000000 0.0000030000 0.0011720000 14595013 96830484 509673472 4.8449726105 4.1396164894 5.6699624062 565 22.5600000000 0.0108590955 0.0065831396 0.0110126510 0.0076309152 0.0058380000 0.0004000000 0.0024130000 0.0000030000 0.0000030000 0.0022300000 14597789 96830484 509673472 4.8483200073 4.1370558739 5.6584997177 566 22.6000000000 0.0111116702 0.0065911405 0.0111116702 0.0076257688 0.0070090000 0.0004010000 0.0046520000 0.0000010000 0.0000030000 0.0011650000 14600565 96830484 509673472 4.8491406441 4.1363415718 5.6516509056 567 22.6400000000 0.0110893371 0.0065990738 0.0111116702 0.0076198479 0.0047660000 0.0004000000 0.0020430000 0.0000030000 0.0000030000 0.0015340000 14603341 96830484 509673472 4.8505125046 4.1357746124 5.6452493668 568 22.6800000000 0.0113046737 0.0066073583 0.0113046737 0.0076134181 0.0055310000 0.0004000000 0.0031740000 0.0000000000 0.0000030000 0.0011670000 14606117 96830484 509673472 4.8527808189 4.1337919235 5.6363058090 569 22.7200000000 0.0115973949 0.0066161282 0.0115973949 0.0076090205 0.0061130000 0.0004010000 0.0026780000 0.0000030000 0.0000030000 0.0022390000 14608893 96830484 509673472 4.8549261093 4.1324467659 5.6257057190 570 22.7600000000 0.0117686950 0.0066251677 0.0117686950 0.0076053461 0.0048120000 0.0003990000 0.0024490000 0.0000010000 0.0000030000 0.0011660000 14611669 96830484 509673472 4.8538236618 4.1351041794 5.6157836914 571 22.8000000000 0.0118130222 0.0066342533 0.0118130222 0.0076001483 0.0055360000 0.0004010000 0.0028130000 0.0000040000 0.0000030000 0.0015250000 14614445 96830484 509673472 4.8525524139 4.1364321709 5.6072950363 572 22.8400000000 0.0120342951 0.0066436939 0.0120342951 0.0075982320 0.0046810000 0.0004000000 0.0023200000 0.0000010000 0.0000030000 0.0011610000 14617221 96830484 509673472 4.8525023460 4.1326227188 5.5987510681 573 22.8800000000 0.0115045346 0.0066521771 0.0120342951 0.0075937309 0.0057200000 0.0003990000 0.0023110000 0.0000040000 0.0000030000 0.0022110000 14619997 96830484 509673472 4.8515973091 4.1319556236 5.5901150703 574 22.9200000000 0.0111208642 0.0066599623 0.0120342951 0.0075871903 0.0050330000 0.0004000000 0.0026800000 0.0000000000 0.0000030000 0.0011550000 14622773 96830484 509673472 4.8487176895 4.1332230568 5.5836987495 575 22.9600000000 0.0106530795 0.0066669068 0.0120342951 0.0075823879 0.0054880000 0.0004000000 0.0027830000 0.0000050000 0.0000030000 0.0014970000 14625549 96830484 509673472 4.8473682404 4.1297512054 5.5744118690 576 23.0000000000 0.0107001122 0.0066739089 0.0120342951 0.0075776165 0.0051390000 0.0004020000 0.0027960000 0.0000000000 0.0000030000 0.0011370000 14628325 96830484 509673472 4.8464407921 4.1262869835 5.5671391487 577 23.0400000000 0.0107696690 0.0066810073 0.0120342951 0.0075788370 0.0057190000 0.0004000000 0.0023050000 0.0000030000 0.0000030000 0.0021750000 14631101 96830484 509673472 4.8450922966 4.1279721260 5.5575985909 578 23.0800000000 0.0109205823 0.0066883422 0.0120342951 0.0075722905 0.0045570000 0.0004010000 0.0021870000 0.0000000000 0.0000030000 0.0011340000 14633877 96830484 509673472 4.8441567421 4.1274585724 5.5480265617 579 23.1200000000 0.0108794160 0.0066955806 0.0120342951 0.0075658412 0.0050660000 0.0003990000 0.0023220000 0.0000030000 0.0000030000 0.0015030000 14636653 96830484 509673472 4.8435950279 4.1246747971 5.5389022827 580 23.1600000000 0.0111180758 0.0067032056 0.0120342951 0.0075609640 0.0054490000 0.0003980000 0.0030680000 0.0000000000 0.0000030000 0.0011380000 14639429 96830484 509673472 4.8429803848 4.1238832474 5.5285511017 581 23.2000000000 0.0109911775 0.0067105860 0.0120342951 0.0075547725 0.0061180000 0.0004020000 0.0027000000 0.0000030000 0.0000040000 0.0021700000 14642205 96830484 509673472 4.8414020538 4.1239733696 5.5192728043 582 23.2400000000 0.0109506771 0.0067178713 0.0120342951 0.0075487456 0.0050860000 0.0004020000 0.0027090000 0.0000010000 0.0000040000 0.0011290000 14644981 96830484 509673472 4.8400030136 4.1217627525 5.5082063675 583 23.2800000000 0.0111306114 0.0067254404 0.0120342951 0.0075427168 0.0050620000 0.0004000000 0.0023240000 0.0000040000 0.0000030000 0.0014890000 14647757 96830484 509673472 4.8399524689 4.1185994148 5.4986672401 584 23.3200000000 0.0113337059 0.0067333312 0.0120342951 0.0075431799 0.0051810000 0.0003990000 0.0028260000 0.0000000000 0.0000030000 0.0011370000 14650533 96830484 509673472 4.8379011154 4.1192336082 5.4873290062 585 23.3600000000 0.0114487484 0.0067413918 0.0120342951 0.0075381104 0.0061130000 0.0003990000 0.0027130000 0.0000030000 0.0000030000 0.0021810000 14653309 96830484 509673472 4.8366246223 4.1185526848 5.4758863449 586 23.4000000000 0.0115260100 0.0067495567 0.0120342951 0.0075339081 0.0046900000 0.0003990000 0.0023310000 0.0000010000 0.0000030000 0.0011380000 14656085 96830484 509673472 4.8362579346 4.1153268814 5.4647402763 587 23.4400000000 0.0116041200 0.0067578268 0.0120342951 0.0075380802 0.0051620000 0.0004010000 0.0024620000 0.0000030000 0.0000030000 0.0014770000 14658861 96830484 509673472 4.8348450661 4.1148467064 5.4551668167 588 23.4800000000 0.0118472483 0.0067664823 0.0120342951 0.0075459083 0.0047130000 0.0004000000 0.0023600000 0.0000000000 0.0000030000 0.0011360000 14661637 96830484 509673472 4.8321719170 4.1171193123 5.4275417328 589 23.5200000000 0.0119001968 0.0067751982 0.0120342951 0.0075401524 0.0059240000 0.0004020000 0.0024910000 0.0000040000 0.0000030000 0.0022010000 14664413 96830484 509673472 4.8303041458 4.1186089516 5.4176573753 590 23.5600000000 0.0120675182 0.0067841683 0.0120675182 0.0075376807 0.0047140000 0.0004000000 0.0023630000 0.0000000000 0.0000030000 0.0011300000 14667189 96830484 509673472 4.8279943466 4.1204395294 5.4060559273 591 23.6000000000 0.0120852003 0.0067931379 0.0120852003 0.0075418690 0.0047980000 0.0003990000 0.0021180000 0.0000030000 0.0000020000 0.0014550000 14669965 96830484 509673472 4.8267893791 4.1181726456 5.3948230743 592 23.6400000000 0.0121728946 0.0068022253 0.0121728946 0.0075357705 0.0048580000 0.0003970000 0.0024950000 0.0000010000 0.0000030000 0.0011390000 14672741 96830484 509673472 4.8256993294 4.1156506538 5.3806986809 593 23.6800000000 0.0122769726 0.0068114576 0.0122769726 0.0075314623 0.0059110000 0.0004000000 0.0025040000 0.0000040000 0.0000030000 0.0021740000 14675517 96830484 509673472 4.8238930702 4.1156377792 5.3681144714 594 23.7200000000 0.0124368705 0.0068209280 0.0124368705 0.0075272643 0.0072050000 0.0003990000 0.0048350000 0.0000010000 0.0000030000 0.0011390000 14678293 96830484 509673472 4.8224229813 4.1156444550 5.3561639786 595 23.7600000000 0.0122824078 0.0068301069 0.0124368705 0.0075240728 0.0050920000 0.0004010000 0.0023890000 0.0000040000 0.0000030000 0.0014720000 14681069 96830484 509673472 4.8198084831 4.1146140099 5.3472223282 596 23.8000000000 0.0122773331 0.0068392466 0.0124368705 0.0075233343 0.0047740000 0.0003990000 0.0024100000 0.0000000000 0.0000030000 0.0011370000 14683845 96830484 509673472 4.8180212975 4.1159453392 5.3342428207 597 23.8400000000 0.0123880198 0.0068485410 0.0124368705 0.0075172961 0.0058880000 0.0004000000 0.0025230000 0.0000030000 0.0000030000 0.0021330000 14686621 96830484 509673472 4.8152675629 4.1177196503 5.3236265182 598 23.8800000000 0.0125186639 0.0068580228 0.0125186639 0.0075118824 0.0049000000 0.0004010000 0.0025370000 0.0000000000 0.0000040000 0.0011310000 14689397 96830484 509673472 4.8135895729 4.1176290512 5.3098649979 599 23.9200000000 0.0124669783 0.0068673867 0.0125186639 0.0075060302 0.0055050000 0.0004000000 0.0027860000 0.0000030000 0.0000030000 0.0014830000 14692173 96830484 509673472 4.8105592728 4.1196289062 5.2996826172 600 23.9600000000 0.0127330087 0.0068771627 0.0127330087 0.0075031041 0.0051490000 0.0003990000 0.0027900000 0.0000000000 0.0000040000 0.0011280000 14694949 96830484 509673472 4.8085412979 4.1199779510 5.2882843018 601 24.0000000000 0.0127027510 0.0068868559 0.0127330087 0.0074975038 0.0057570000 0.0003990000 0.0024010000 0.0000040000 0.0000030000 0.0021090000 14697725 96830484 509673472 4.8055014610 4.1200909615 5.2779889107 602 24.0400000000 0.0127688302 0.0068966266 0.0127688302 0.0074913590 0.0048860000 0.0004010000 0.0025400000 0.0000000000 0.0000030000 0.0011090000 14700501 96830484 509673472 4.8034987450 4.1201338768 5.2653679848 603 24.0800000000 0.0127280932 0.0069062974 0.0127688302 0.0074851852 0.0051100000 0.0004010000 0.0024100000 0.0000030000 0.0000030000 0.0014440000 14703277 96830484 509673472 4.8000731468 4.1204562187 5.2564530373 604 24.1200000000 0.0126338508 0.0069157801 0.0127688302 0.0074789862 0.0043760000 0.0003990000 0.0020130000 0.0000000000 0.0000030000 0.0011240000 14706053 96830484 509673472 4.7967000008 4.1212320328 5.2485322952 605 24.1600000000 0.0124688102 0.0069249586 0.0127688302 0.0074731705 0.0057690000 0.0003980000 0.0023980000 0.0000040000 0.0000030000 0.0021200000 14708829 96830484 509673472 4.7938299179 4.1201434135 5.2399082184 606 24.2000000000 0.0124222841 0.0069340301 0.0127688302 0.0074672063 0.0045180000 0.0004020000 0.0021530000 0.0000010000 0.0000030000 0.0011080000 14711605 96830484 509673472 4.7913403511 4.1176991463 5.2323770523 607 24.2400000000 0.0124074165 0.0069430472 0.0127688302 0.0074614807 0.0048310000 0.0004000000 0.0021510000 0.0000040000 0.0000030000 0.0014270000 14714381 96830484 509673472 4.7891664505 4.1170983315 5.2196526527 608 24.2800000000 0.0124505330 0.0069521056 0.0127688302 0.0074557126 0.0055310000 0.0003990000 0.0031800000 0.0000010000 0.0000030000 0.0010930000 14717157 96830484 509673472 4.7860822678 4.1186332703 5.2108988762 609 24.3200000000 0.0124281896 0.0069610975 0.0127688302 0.0074514513 0.0057270000 0.0004020000 0.0024050000 0.0000030000 0.0000030000 0.0020600000 14719933 96830484 509673472 4.7844333649 4.1158390045 5.2018589973 610 24.3600000000 0.0127072660 0.0069705175 0.0127688302 0.0074456369 0.0068530000 0.0003990000 0.0045030000 0.0000000000 0.0000030000 0.0010960000 14722709 96830484 509673472 4.7824144363 4.1120681763 5.1933956146 611 24.4000000000 0.0127462596 0.0069799704 0.0127688302 0.0074441566 0.0050980000 0.0003990000 0.0024050000 0.0000030000 0.0000030000 0.0014390000 14725485 96830484 509673472 4.7810440063 4.1113514900 5.1798267365 612 24.4400000000 0.0127553549 0.0069894073 0.0127688302 0.0074392505 0.0051650000 0.0004000000 0.0028150000 0.0000000000 0.0000040000 0.0010770000 14728261 96830484 509673472 4.7781581879 4.1117401123 5.1705746651 613 24.4800000000 0.0127998758 0.0069988860 0.0127998758 0.0074338918 0.0057170000 0.0004010000 0.0024150000 0.0000030000 0.0000030000 0.0020330000 14731037 96830484 509673472 4.7759962082 4.1098179817 5.1632061005 614 24.5200000000 0.0129273906 0.0070085416 0.0129273906 0.0074279345 0.0049050000 0.0004000000 0.0025580000 0.0000000000 0.0000030000 0.0010800000 14733813 96830484 509673472 4.7741498947 4.1074929237 5.1499552727 615 24.5600000000 0.0129558891 0.0070182121 0.0129558891 0.0074222711 0.0051040000 0.0003990000 0.0024290000 0.0000040000 0.0000030000 0.0014160000 14736589 96830484 509673472 4.7727651596 4.1061968803 5.1416163445 616 24.6000000000 0.0130465915 0.0070279984 0.0130465915 0.0074171042 0.0049110000 0.0003980000 0.0025600000 0.0000010000 0.0000030000 0.0010910000 14739365 96830484 509673472 4.7712521553 4.1034126282 5.1304769516 617 24.6400000000 0.0130602419 0.0070377751 0.0130602419 0.0074161180 0.0058620000 0.0004000000 0.0025580000 0.0000040000 0.0000030000 0.0020400000 14742141 96830484 509673472 4.7693395615 4.1018471718 5.1195974350 618 24.6800000000 0.0132361418 0.0070478049 0.0132361418 0.0074163777 0.0052050000 0.0004000000 0.0024410000 0.0000010000 0.0000030000 0.0013230000 14744917 96830484 509673472 4.7682433128 4.1001553535 5.1066617966 619 24.7200000000 0.0130848624 0.0070575578 0.0132361418 0.0074178035 0.0053990000 0.0004630000 0.0024510000 0.0000040000 0.0000030000 0.0015620000 14747693 96830484 509673472 4.7670559883 4.0992617607 5.0915164948 620 24.7600000000 0.0132214520 0.0070674995 0.0132361418 0.0074150570 0.0048040000 0.0004030000 0.0024500000 0.0000000000 0.0000030000 0.0010660000 14750469 96830484 509673472 4.7641448975 4.1002244949 5.0825090408 621 24.8000000000 0.0132581200 0.0070774683 0.0132581200 0.0074092108 0.0058430000 0.0004010000 0.0025750000 0.0000030000 0.0000030000 0.0019920000 14753245 96830484 509673472 4.7624368668 4.0997071266 5.0721735954 622 24.8400000000 0.0131494971 0.0070872304 0.0132581200 0.0074034850 0.0053150000 0.0004010000 0.0029810000 0.0000000000 0.0000040000 0.0010520000 14756021 96830484 509673472 4.7605323792 4.0975799561 5.0613417625 623 24.8800000000 0.0134962201 0.0070975177 0.0134962201 0.0074008772 0.0050690000 0.0004050000 0.0024320000 0.0000030000 0.0000030000 0.0013380000 14758797 96830484 509673472 4.7582101822 4.0983471870 5.0503473282 624 24.9200000000 0.0136615811 0.0071080371 0.0136615811 0.0073955549 0.0049210000 0.0004040000 0.0025940000 0.0000000000 0.0000040000 0.0010350000 14761573 96830484 509673472 4.7552547455 4.0992379189 5.0390462875 625 24.9600000000 0.0138031645 0.0071187493 0.0138031645 0.0073897695 0.0062260000 0.0004040000 0.0029770000 0.0000030000 0.0000030000 0.0019630000 14764349 96830484 509673472 4.7524714470 4.0976605415 5.0289955139 626 25.0000000000 0.0138438828 0.0071294923 0.0138438828 0.0073847030 0.0048730000 0.0004040000 0.0025700000 0.0000000000 0.0000040000 0.0010180000 14767125 96830484 509673472 4.7505235672 4.0956740379 5.0196852684 627 25.0400000000 0.0139378747 0.0071403510 0.0139378747 0.0073815432 0.0051690000 0.0004010000 0.0025570000 0.0000030000 0.0000030000 0.0013240000 14769901 96830484 509673472 4.7477278709 4.0953378677 5.0092663765 628 25.0800000000 0.0138593419 0.0071510500 0.0139378747 0.0073759369 0.0048670000 0.0004030000 0.0025720000 0.0000000000 0.0000030000 0.0010110000 14772677 96830484 509673472 4.7439041138 4.0972361565 4.9998474121 629 25.1200000000 0.0138628390 0.0071617206 0.0139378747 0.0073726184 0.0057540000 0.0004020000 0.0025490000 0.0000040000 0.0000030000 0.0019140000 14775453 96830484 509673472 4.7413039207 4.0965409279 4.9936046600 630 25.1600000000 0.0139985895 0.0071725727 0.0139985895 0.0073675128 0.0052400000 0.0004010000 0.0029610000 0.0000000000 0.0000030000 0.0009960000 14778229 96830484 509673472 4.7374000549 4.0965948105 4.9841237068 631 25.2000000000 0.0139078964 0.0071832468 0.0139985895 0.0073639774 0.0053870000 0.0004030000 0.0028280000 0.0000030000 0.0000040000 0.0012640000 14781005 96830484 509673472 4.7334299088 4.0974078178 4.9755311012 632 25.2400000000 0.0140409768 0.0071940976 0.0140409768 0.0073629465 0.0048250000 0.0004010000 0.0025690000 0.0000010000 0.0000030000 0.0009680000 14783781 96830484 509673472 4.7296419144 4.0965313911 4.9698543549 633 25.2800000000 0.0136087937 0.0072042314 0.0140409768 0.0073589448 0.0057040000 0.0004060000 0.0025630000 0.0000040000 0.0000030000 0.0018390000 14786557 96830484 509673472 4.7255892754 4.0975079536 4.9600434303 634 25.3200000000 0.0145192165 0.0072157693 0.0145192165 0.0073556712 0.0070920000 0.0004040000 0.0048380000 0.0000000000 0.0000030000 0.0009580000 14789333 96830484 509673472 4.7204122543 4.0991845131 4.9509291649 635 25.3600000000 0.0144749107 0.0072272010 0.0145192165 0.0073582980 0.0071120000 0.0004020000 0.0045490000 0.0000040000 0.0000030000 0.0012640000 14792109 96830484 509673472 4.7163820267 4.0990452766 4.9454393387 636 25.4000000000 0.0144271674 0.0072385217 0.0145192165 0.0073583720 0.0052230000 0.0004030000 0.0029690000 0.0000000000 0.0000030000 0.0009550000 14794885 96830484 509673472 4.7129201889 4.0973811150 4.9363303185 637 25.4400000000 0.0145302964 0.0072499687 0.0145302964 0.0073532512 0.0063470000 0.0004020000 0.0032180000 0.0000030000 0.0000030000 0.0018190000 14797661 96830484 509673472 4.7084317207 4.0978603363 4.9292750359 638 25.4800000000 0.0145493150 0.0072614097 0.0145493150 0.0073489172 0.0044330000 0.0004050000 0.0021830000 0.0000000000 0.0000030000 0.0009460000 14800437 96830484 509673472 4.7051048279 4.0961890221 4.9212951660 639 25.5200000000 0.0147157423 0.0072730753 0.0147157423 0.0073433254 0.0058920000 0.0004060000 0.0033570000 0.0000030000 0.0000030000 0.0012260000 14803213 96830484 509673472 4.6999773979 4.0941472054 4.9153556824 640 25.5600000000 0.0148627125 0.0072849341 0.0148627125 0.0073383254 0.0048410000 0.0004050000 0.0025930000 0.0000000000 0.0000030000 0.0009420000 14805989 96830484 509673472 4.6958665848 4.0927677155 4.9091076851 641 25.6000000000 0.0148075856 0.0072966700 0.0148627125 0.0073332641 0.0056760000 0.0004060000 0.0025760000 0.0000030000 0.0000030000 0.0017910000 14808765 96830484 509673472 4.6907815933 4.0916914940 4.9027371407 642 25.6400000000 0.0151452245 0.0073088951 0.0151452245 0.0073286596 0.0056270000 0.0004010000 0.0033860000 0.0000000000 0.0000030000 0.0009370000 14811541 96830484 509673472 4.6854000092 4.0906162262 4.8975005150 643 25.6800000000 0.0150738815 0.0073209713 0.0151452245 0.0073232541 0.0053780000 0.0004030000 0.0028420000 0.0000030000 0.0000030000 0.0012210000 14814317 96830484 509673472 4.6807308197 4.0889797211 4.8910636902 644 25.7200000000 0.0154477619 0.0073335905 0.0154477619 0.0073176725 0.0048380000 0.0004020000 0.0025900000 0.0000010000 0.0000030000 0.0009370000 14817093 96830484 509673472 4.6750264168 4.0880861282 4.8857259750 645 25.7600000000 0.0155672422 0.0073463559 0.0155672422 0.0073122310 0.0064890000 0.0004030000 0.0033780000 0.0000030000 0.0000030000 0.0017900000 14819869 96830484 509673472 4.6700472832 4.0861186981 4.8793778419 646 25.8000000000 0.0158549733 0.0073595271 0.0158549733 0.0073066168 0.0052230000 0.0004050000 0.0029730000 0.0000010000 0.0000040000 0.0009350000 14822645 96830484 509673472 4.6636219025 4.0845289230 4.8751134872 647 25.8400000000 0.0159167517 0.0073727531 0.0159167517 0.0073010288 0.0055240000 0.0004070000 0.0029830000 0.0000040000 0.0000030000 0.0012200000 14825421 96830484 509673472 4.6562800407 4.0850205421 4.8694477081 648 25.8800000000 0.0160860512 0.0073861996 0.0160860512 0.0072987939 0.0052320000 0.0004050000 0.0029980000 0.0000000000 0.0000030000 0.0009170000 14828197 96830484 509673472 4.6495552063 4.0844216347 4.8649697304 649 25.9200000000 0.0161070619 0.0073996370 0.0161070619 0.0072976110 0.0060850000 0.0004010000 0.0029840000 0.0000030000 0.0000030000 0.0017810000 14830973 96830484 509673472 4.6424446106 4.0814356804 4.8599233627 650 25.9600000000 0.0166042857 0.0074137980 0.0166042857 0.0072935505 0.0056230000 0.0004050000 0.0033750000 0.0000000000 0.0000040000 0.0009240000 14833749 96830484 509673472 4.6283740997 4.0748095512 4.8508181572 651 26.0000000000 0.0171406697 0.0074287394 0.0171406697 0.0072946456 0.0050990000 0.0004050000 0.0025630000 0.0000040000 0.0000030000 0.0012160000 14836525 96830484 509673472 4.6109142303 4.0750250816 4.8401579857 652 26.0400000000 0.0175599512 0.0074442781 0.0175599512 0.0072891902 0.0052400000 0.0004050000 0.0030080000 0.0000000000 0.0000030000 0.0009080000 14839301 96830484 509673472 4.6015214920 4.0758838654 4.8340215683 653 26.0800000000 0.0176423900 0.0074598954 0.0176423900 0.0072861654 0.0060410000 0.0004060000 0.0029780000 0.0000040000 0.0000030000 0.0017290000 14842077 96830484 509673472 4.5913109779 4.0786933899 4.8293256760 654 26.1200000000 0.0182823073 0.0074764434 0.0182823073 0.0072926475 0.0052220000 0.0004050000 0.0030010000 0.0000000000 0.0000040000 0.0008970000 14844853 96830484 509673472 4.5809755325 4.0786938667 4.8252468109 655 26.1600000000 0.0188157707 0.0074937554 0.0188157707 0.0072882195 0.0075190000 0.0004050000 0.0049860000 0.0000040000 0.0000030000 0.0012040000 14847629 96830484 509673472 4.5715146065 4.0763697624 4.8187680244 656 26.2000000000 0.0182756018 0.0075101911 0.0188157707 0.0072869157 0.0056270000 0.0004070000 0.0034020000 0.0000010000 0.0000030000 0.0008920000 14850405 96830484 509673472 4.5606956482 4.0769371986 4.8153853416 657 26.2400000000 0.0184660237 0.0075268666 0.0188157707 0.0072869312 0.0078850000 0.0004050000 0.0048450000 0.0000030000 0.0000030000 0.0017060000 14853181 96830484 509673472 4.5500826836 4.0773477554 4.8116416931 658 26.2800000000 0.0182001442 0.0075430874 0.0188157707 0.0072884199 0.0052190000 0.0004070000 0.0029950000 0.0000000000 0.0000040000 0.0008880000 14855957 96830484 509673472 4.5388903618 4.0786266327 4.8073658943 659 26.3200000000 0.0186549984 0.0075599492 0.0188157707 0.0072859150 0.0070960000 0.0004070000 0.0045920000 0.0000040000 0.0000030000 0.0011600000 14858733 96830484 509673472 4.5270843506 4.0814666748 4.8036928177 660 26.3600000000 0.0182414781 0.0075761333 0.0188157707 0.0072809090 0.0048170000 0.0004040000 0.0026000000 0.0000010000 0.0000040000 0.0008840000 14861509 96830484 509673472 4.5162539482 4.0826005936 4.8006510735 661 26.4000000000 0.0184318852 0.0075925566 0.0188157707 0.0072757960 0.0059790000 0.0004040000 0.0029710000 0.0000030000 0.0000030000 0.0016730000 14864285 96830484 509673472 4.5041785240 4.0851893425 4.7965970039 662 26.4400000000 0.0184355658 0.0076089357 0.0188157707 0.0072746865 0.0072020000 0.0004070000 0.0049840000 0.0000010000 0.0000030000 0.0008790000 14867061 96830484 509673472 4.4923281670 4.0885586739 4.7951173782 663 26.4800000000 0.0185722671 0.0076254717 0.0188157707 0.0072920685 0.0054660000 0.0004050000 0.0029790000 0.0000030000 0.0000030000 0.0011530000 14869837 96830484 509673472 4.4816451073 4.0880179405 4.7914156914 664 26.5200000000 0.0188396089 0.0076423604 0.0188396089 0.0072997765 0.0048140000 0.0004040000 0.0025970000 0.0000000000 0.0000030000 0.0008790000 14872613 96830484 509673472 4.4714684486 4.0850706100 4.7854332924 665 26.5600000000 0.0188915748 0.0076592766 0.0188915748 0.0072948737 0.0080290000 0.0004040000 0.0049980000 0.0000030000 0.0000030000 0.0016860000 14875389 96830484 509673472 4.4608998299 4.0856022835 4.7824554443 666 26.6000000000 0.0184334330 0.0076754540 0.0188915748 0.0072910354 0.0055990000 0.0004020000 0.0033800000 0.0000000000 0.0000030000 0.0008790000 14878165 96830484 509673472 4.4497799873 4.0878257751 4.7795467377 667 26.6400000000 0.0189777184 0.0076923989 0.0189777184 0.0072948387 0.0050910000 0.0004040000 0.0025900000 0.0000040000 0.0000030000 0.0011540000 14880941 96830484 509673472 4.4391245842 4.0908422470 4.7774491310 668 26.6800000000 0.0186366066 0.0077087824 0.0189777184 0.0073168935 0.0052060000 0.0004050000 0.0029830000 0.0000000000 0.0000030000 0.0008730000 14883717 96830484 509673472 4.4280734062 4.0949816704 4.7747464180 669 26.7200000000 0.0190239940 0.0077256961 0.0190239940 0.0073597274 0.0060160000 0.0004050000 0.0029880000 0.0000030000 0.0000030000 0.0016700000 14886493 96830484 509673472 4.4171400070 4.0963673592 4.7713794708 670 26.7600000000 0.0183927137 0.0077416170 0.0190239940 0.0073966367 0.0064060000 0.0004050000 0.0041840000 0.0000000000 0.0000030000 0.0008780000 14889269 96830484 509673472 4.4074878693 4.0959382057 4.7691979408 671 26.8000000000 0.0185530428 0.0077577294 0.0190239940 0.0074035228 0.0054780000 0.0004050000 0.0029860000 0.0000030000 0.0000030000 0.0011290000 14892045 96830484 509673472 4.3979711533 4.0963654518 4.7653350830 672 26.8400000000 0.0186602976 0.0077739534 0.0190239940 0.0073994481 0.0060150000 0.0004070000 0.0037950000 0.0000000000 0.0000030000 0.0008660000 14894821 96830484 509673472 4.3883881569 4.0989480019 4.7610898018 673 26.8800000000 0.0179473571 0.0077890699 0.0190239940 0.0073954887 0.0080410000 0.0004040000 0.0050080000 0.0000030000 0.0000030000 0.0016730000 14897597 96830484 509673472 4.3793811798 4.0994863510 4.7584347725 674 26.9200000000 0.0183673408 0.0078047647 0.0190239940 0.0073900765 0.0048180000 0.0004000000 0.0026030000 0.0000000000 0.0000030000 0.0008670000 14900373 96830484 509673472 4.3706278801 4.1005201340 4.7540445328 675 26.9600000000 0.0180137549 0.0078198891 0.0190239940 0.0073846428 0.0074940000 0.0004040000 0.0049790000 0.0000040000 0.0000030000 0.0011590000 14903149 96830484 509673472 4.3618893623 4.1024894714 4.7518110275 676 27.0000000000 0.0184165780 0.0078355647 0.0190239940 0.0073802693 0.0056250000 0.0004060000 0.0033900000 0.0000000000 0.0000040000 0.0008680000 14905925 96830484 509673472 4.3528356552 4.1068115234 4.7478041649 677 27.0400000000 0.0183915142 0.0078511570 0.0190239940 0.0073890366 0.0071780000 0.0004020000 0.0041550000 0.0000040000 0.0000030000 0.0016580000 14908701 96830484 509673472 4.3441052437 4.1099376678 4.7460837364 678 27.0800000000 0.0179057885 0.0078659868 0.0190239940 0.0074023168 0.0068010000 0.0004040000 0.0045720000 0.0000000000 0.0000040000 0.0008650000 14911477 96830484 509673472 4.3358798027 4.1118788719 4.7435584068 679 27.1200000000 0.0183472689 0.0078814232 0.0190239940 0.0074119989 0.0054560000 0.0004040000 0.0029710000 0.0000030000 0.0000030000 0.0011130000 14914253 96830484 509673472 4.3270125389 4.1140146255 4.7391824722 680 27.1600000000 0.0175291393 0.0078956110 0.0190239940 0.0074143706 0.0055830000 0.0004060000 0.0033800000 0.0000000000 0.0000040000 0.0008450000 14917029 96830484 509673472 4.3191728592 4.1139292717 4.7355742455 681 27.2000000000 0.0185623113 0.0079112743 0.0190239940 0.0074091702 0.0063800000 0.0004050000 0.0033770000 0.0000040000 0.0000030000 0.0016350000 14919805 96830484 509673472 4.3112168312 4.1151609421 4.7305817604 682 27.2400000000 0.0185895059 0.0079269315 0.0190239940 0.0074039949 0.0051990000 0.0004040000 0.0029750000 0.0000010000 0.0000030000 0.0008520000 14922581 96830484 509673472 4.3029704094 4.1188039780 4.7265062332 683 27.2800000000 0.0193738099 0.0079436912 0.0193738099 0.0074031493 0.0054550000 0.0004050000 0.0029640000 0.0000040000 0.0000030000 0.0011180000 14925357 96830484 509673472 4.2950787544 4.1216716766 4.7211666107 684 27.3200000000 0.0189231858 0.0079597431 0.0193738099 0.0074083773 0.0052080000 0.0004060000 0.0029760000 0.0000000000 0.0000040000 0.0008550000 14928133 96830484 509673472 4.2867345810 4.1227545738 4.7175092697 685 27.3600000000 0.0196967367 0.0079768774 0.0196967367 0.0074076583 0.0079310000 0.0004040000 0.0049490000 0.0000040000 0.0000030000 0.0016080000 14930909 96830484 509673472 4.2790703773 4.1235804558 4.7110409737 686 27.4000000000 0.0195958037 0.0079938146 0.0196967367 0.0074044294 0.0071940000 0.0004030000 0.0049760000 0.0000010000 0.0000030000 0.0008460000 14933685 96830484 509673472 4.2705340385 4.1270923615 4.7057127953 687 27.4400000000 0.0192687362 0.0080102264 0.0196967367 0.0074113525 0.0058610000 0.0004070000 0.0033700000 0.0000030000 0.0000030000 0.0011080000 14936461 96830484 509673472 4.2623229027 4.1306700706 4.7006297112 688 27.4800000000 0.0197024774 0.0080272210 0.0197024774 0.0074270020 0.0051970000 0.0004030000 0.0029750000 0.0000000000 0.0000030000 0.0008480000 14939237 96830484 509673472 4.2540416718 4.1323618889 4.6946358681 689 27.5200000000 0.0196065027 0.0080440269 0.0197024774 0.0074367452 0.0063610000 0.0004020000 0.0033610000 0.0000030000 0.0000030000 0.0016190000 14942013 96830484 509673472 4.2456631660 4.1340050697 4.6891360283 690 27.5600000000 0.0193907581 0.0080604714 0.0197024774 0.0074378822 0.0063880000 0.0004030000 0.0041660000 0.0000010000 0.0000030000 0.0008420000 14944789 96830484 509673472 4.2377271652 4.1353974342 4.6826896667 691 27.6000000000 0.0197560452 0.0080773970 0.0197560452 0.0074380189 0.0074260000 0.0004030000 0.0049370000 0.0000030000 0.0000030000 0.0011070000 14947565 96830484 509673472 4.2288699150 4.1397180557 4.6760253906 692 27.6400000000 0.0202161297 0.0080949385 0.0202161297 0.0074525724 0.0047880000 0.0004020000 0.0025700000 0.0000000000 0.0000030000 0.0008400000 14950341 96830484 509673472 4.2202010155 4.1435413361 4.6691570282 693 27.6800000000 0.0205720142 0.0081129430 0.0205720142 0.0074829766 0.0059750000 0.0004050000 0.0029720000 0.0000040000 0.0000030000 0.0016110000 14953117 96830484 509673472 4.2123632431 4.1439952850 4.6614403725 694 27.7200000000 0.0213790704 0.0081320584 0.0213790704 0.0074975096 0.0052020000 0.0004050000 0.0029710000 0.0000000000 0.0000030000 0.0008430000 14955893 96830484 509673472 4.2048873901 4.1433763504 4.6523489952 695 27.7600000000 0.0216896664 0.0081515658 0.0216896664 0.0074973733 0.0062770000 0.0004020000 0.0037690000 0.0000030000 0.0000020000 0.0011140000 14958669 96830484 509673472 4.1977801323 4.1426100731 4.6446723938 696 27.8000000000 0.0223372970 0.0081719476 0.0223372970 0.0074933386 0.0052090000 0.0004030000 0.0029760000 0.0000010000 0.0000030000 0.0008470000 14961445 96830484 509673472 4.1900315285 4.1451239586 4.6365594864 697 27.8400000000 0.0230155960 0.0081932441 0.0230155960 0.0074904728 0.0071750000 0.0004010000 0.0041540000 0.0000030000 0.0000030000 0.0016250000 14964221 96830484 509673472 4.1819105148 4.1485934258 4.6288003922 698 27.8800000000 0.0233675893 0.0082149838 0.0233675893 0.0074926509 0.0048260000 0.0004050000 0.0025840000 0.0000000000 0.0000040000 0.0008450000 14966997 96830484 509673472 4.1729054451 4.1531491280 4.6219830513 699 27.9200000000 0.0234038215 0.0082367132 0.0234038215 0.0075035145 0.0053490000 0.0004020000 0.0028460000 0.0000030000 0.0000030000 0.0011040000 14969773 96830484 509673472 4.1645145416 4.1572523117 4.6158800125 700 27.9600000000 0.0232906528 0.0082582188 0.0234038215 0.0075204560 0.0048350000 0.0004030000 0.0025850000 0.0000000000 0.0000030000 0.0008510000 14972549 96830484 509673472 4.1558179855 4.1604542732 4.6093115807 701 28.0000000000 0.0229872782 0.0082792303 0.0234038215 0.0075395534 0.0056070000 0.0004030000 0.0025740000 0.0000030000 0.0000030000 0.0016360000 14975325 96830484 509673472 4.1475811005 4.1627621651 4.6035728455 702 28.0400000000 0.0222847369 0.0082991812 0.0234038215 0.0075547573 0.0048200000 0.0004010000 0.0025690000 0.0000000000 0.0000030000 0.0008550000 14978101 96830484 509673472 4.1395258904 4.1639180183 4.5982050896 703 28.0800000000 0.0213247780 0.0083177098 0.0234038215 0.0075632448 0.0050800000 0.0004050000 0.0025610000 0.0000030000 0.0000030000 0.0011190000 14980877 96830484 509673472 4.1322994232 4.1649799347 4.5947065353 704 28.1200000000 0.0201817174 0.0083345620 0.0234038215 0.0075704942 0.0046950000 0.0004010000 0.0024420000 0.0000000000 0.0000030000 0.0008570000 14983653 96830484 509673472 4.1233811378 4.1712923050 4.5919981003 705 28.1600000000 0.0193199888 0.0083501442 0.0234038215 0.0075948571 0.0060000000 0.0004010000 0.0029640000 0.0000040000 0.0000030000 0.0016350000 14986429 96830484 509673472 4.1149239540 4.1755385399 4.5889549255 706 28.2000000000 0.0186680425 0.0083647588 0.0234038215 0.0076160293 0.0048180000 0.0004010000 0.0025590000 0.0000000000 0.0000040000 0.0008650000 14989205 96830484 509673472 4.1076536179 4.1756038666 4.5860023499 707 28.2400000000 0.0181885883 0.0083786539 0.0234038215 0.0076185210 0.0057590000 0.0003990000 0.0032270000 0.0000030000 0.0000030000 0.0011290000 14991981 96830484 509673472 4.0998244286 4.1790533066 4.5827636719 708 28.2800000000 0.0175692290 0.0083916349 0.0234038215 0.0076159654 0.0052180000 0.0004020000 0.0029530000 0.0000010000 0.0000030000 0.0008660000 14994757 96830484 509673472 4.0915465355 4.1834869385 4.5809168816 709 28.3200000000 0.0164757017 0.0084030370 0.0234038215 0.0076116495 0.0055980000 0.0003990000 0.0025550000 0.0000030000 0.0000030000 0.0016360000 14997533 96830484 509673472 4.0851912498 4.1805114746 4.5793886185 710 28.3600000000 0.0156619996 0.0084132609 0.0234038215 0.0076080622 0.0052360000 0.0004000000 0.0029590000 0.0000010000 0.0000040000 0.0008730000 15000309 96830484 509673472 4.0783090591 4.1814818382 4.5772953033 711 28.4000000000 0.0152898319 0.0084229326 0.0234038215 0.0076030827 0.0055170000 0.0004020000 0.0029610000 0.0000040000 0.0000030000 0.0011450000 15003085 96830484 509673472 4.0697560310 4.1893715858 4.5762839317 712 28.4400000000 0.0149738537 0.0084321333 0.0234038215 0.0076001690 0.0048430000 0.0004000000 0.0025680000 0.0000010000 0.0000030000 0.0008690000 15005861 96830484 509673472 4.0618724823 4.1916384697 4.5741963387 713 28.4800000000 0.0147928558 0.0084410544 0.0234038215 0.0075971167 0.0056240000 0.0003990000 0.0025900000 0.0000040000 0.0000030000 0.0016210000 15008637 96830484 509673472 4.0568604469 4.1881833076 4.5736846924 714 28.5200000000 0.0148073835 0.0084499708 0.0234038215 0.0076159000 0.0049050000 0.0004010000 0.0025950000 0.0000000000 0.0000030000 0.0008710000 15011413 96830484 509673472 4.0485134125 4.1957001686 4.5732026100 715 28.5600000000 0.0146850990 0.0084586913 0.0234038215 0.0076111319 0.0055270000 0.0004020000 0.0029750000 0.0000040000 0.0000030000 0.0011210000 15014189 96830484 509673472 4.0397443771 4.2025403976 4.5731811523 716 28.6000000000 0.0146524683 0.0084673418 0.0234038215 0.0076117249 0.0048580000 0.0004020000 0.0025590000 0.0000000000 0.0000040000 0.0008690000 15016965 96830484 509673472 4.0329961777 4.2042908669 4.5752968788 717 28.6400000000 0.0146053219 0.0084759024 0.0234038215 0.0076090890 0.0060280000 0.0004000000 0.0029620000 0.0000030000 0.0000030000 0.0016220000 15019741 96830484 509673472 4.0265450478 4.2058696747 4.5780787468 718 28.6800000000 0.0146620348 0.0084845182 0.0234038215 0.0076043619 0.0049990000 0.0004030000 0.0027030000 0.0000010000 0.0000030000 0.0008620000 15022517 96830484 509673472 4.0192084312 4.2105760574 4.5807962418 719 28.7200000000 0.0146476142 0.0084930900 0.0234038215 0.0076032193 0.0049740000 0.0004030000 0.0024250000 0.0000030000 0.0000030000 0.0011120000 15025293 96830484 509673472 4.0114727020 4.2138457298 4.5830001831 720 28.7600000000 0.0146649797 0.0085016620 0.0234038215 0.0076010893 0.0048550000 0.0004000000 0.0025530000 0.0000010000 0.0000030000 0.0008730000 15028069 96830484 509673472 4.0040192604 4.2162003517 4.5866451263 721 28.8000000000 0.0147095276 0.0085102721 0.0234038215 0.0075962872 0.0055000000 0.0004030000 0.0024400000 0.0000030000 0.0000020000 0.0016260000 15030845 96830484 509673472 3.9971327782 4.2171154022 4.5912480354 722 28.8400000000 0.0147220893 0.0085188757 0.0234038215 0.0075910414 0.0047220000 0.0004040000 0.0024280000 0.0000010000 0.0000030000 0.0008630000 15033621 96830484 509673472 3.9892899990 4.2195806503 4.5956292152 723 28.8800000000 0.0147159547 0.0085274471 0.0234038215 0.0075858384 0.0051180000 0.0004030000 0.0025610000 0.0000040000 0.0000030000 0.0011240000 15036397 96830484 509673472 3.9816026688 4.2208595276 4.6011595726 724 28.9200000000 0.0146630285 0.0085359216 0.0234038215 0.0075806293 0.0048550000 0.0004000000 0.0025630000 0.0000010000 0.0000040000 0.0008580000 15039173 96830484 509673472 3.9733309746 4.2232136726 4.6065478325 725 28.9600000000 0.0146289999 0.0085443259 0.0234038215 0.0075779641 0.0063920000 0.0004010000 0.0033480000 0.0000030000 0.0000030000 0.0016090000 15041949 96830484 509673472 3.9646775723 4.2258548737 4.6122894287 726 29.0000000000 0.0146746207 0.0085527698 0.0234038215 0.0075830036 0.0051240000 0.0004010000 0.0028280000 0.0000010000 0.0000030000 0.0008650000 15044725 96830484 509673472 3.9565711021 4.2272825241 4.6183643341 727 29.0400000000 0.0146144405 0.0085611077 0.0234038215 0.0075873728 0.0049830000 0.0004000000 0.0024280000 0.0000030000 0.0000030000 0.0011110000 15047501 96830484 509673472 3.9473941326 4.2293381691 4.6242823601 728 29.0800000000 0.0146900993 0.0085695267 0.0234038215 0.0075910993 0.0047270000 0.0004010000 0.0024330000 0.0000000000 0.0000030000 0.0008570000 15050277 96830484 509673472 3.9386262894 4.2318096161 4.6308646202 729 29.1200000000 0.0146648576 0.0085778879 0.0234038215 0.0075907189 0.0055860000 0.0004010000 0.0025650000 0.0000040000 0.0000030000 0.0015750000 15053053 96830484 509673472 3.9298596382 4.2344160080 4.6378707886 730 29.1600000000 0.0148015339 0.0085864135 0.0234038215 0.0075872152 0.0060560000 0.0004010000 0.0037460000 0.0000010000 0.0000030000 0.0008570000 15055829 96830484 509673472 3.9211103916 4.2357645035 4.6446847916 731 29.2000000000 0.0148281408 0.0085949521 0.0234038215 0.0075826629 0.0049910000 0.0004010000 0.0024450000 0.0000030000 0.0000030000 0.0010960000 15058605 96830484 509673472 3.9117431641 4.2384061813 4.6511168480 732 29.2400000000 0.0149860708 0.0086036831 0.0234038215 0.0075785290 0.0044830000 0.0004010000 0.0021780000 0.0000010000 0.0000030000 0.0008550000 15061381 96830484 509673472 3.9016389847 4.2427988052 4.6576485634 733 29.2800000000 0.0149071356 0.0086122826 0.0234038215 0.0075738345 0.0055920000 0.0004030000 0.0025580000 0.0000030000 0.0000030000 0.0015730000 15064157 96830484 509673472 3.8918917179 4.2460560799 4.6660380363 734 29.3200000000 0.0148262670 0.0086207486 0.0234038215 0.0075694223 0.0044820000 0.0004020000 0.0021770000 0.0000000000 0.0000030000 0.0008530000 15066933 96830484 509673472 3.8827767372 4.2497072220 4.6752905846 735 29.3600000000 0.0146844657 0.0086289985 0.0234038215 0.0075663919 0.0051180000 0.0004030000 0.0025610000 0.0000030000 0.0000030000 0.0011030000 15069709 96830484 509673472 3.8739030361 4.2531218529 4.6840653419 736 29.4000000000 0.0145357111 0.0086370239 0.0234038215 0.0075631914 0.0048580000 0.0004020000 0.0025570000 0.0000010000 0.0000030000 0.0008540000 15072485 96830484 509673472 3.8653006554 4.2573456764 4.6932592392 737 29.4400000000 0.0143338200 0.0086447536 0.0234038215 0.0075584906 0.0058550000 0.0004000000 0.0028030000 0.0000040000 0.0000030000 0.0015870000 15075261 96830484 509673472 3.8570153713 4.2604908943 4.7020478249 738 29.4800000000 0.0142052537 0.0086522882 0.0234038215 0.0075571335 0.0047260000 0.0004030000 0.0024150000 0.0000000000 0.0000030000 0.0008540000 15078037 96830484 509673472 3.8485097885 4.2639656067 4.7108135223 739 29.5200000000 0.0140976608 0.0086596568 0.0234038215 0.0075722214 0.0049580000 0.0004020000 0.0024060000 0.0000030000 0.0000030000 0.0010870000 15080813 96830484 509673472 3.8406710625 4.2668504715 4.7196755409 740 29.5600000000 0.0141408248 0.0086670637 0.0234038215 0.0075917171 0.0048640000 0.0003990000 0.0025540000 0.0000010000 0.0000030000 0.0008590000 15083589 96830484 509673472 3.8335928917 4.2695608139 4.7282662392 741 29.6000000000 0.0141964583 0.0086745258 0.0234038215 0.0076159308 0.0055550000 0.0004010000 0.0025270000 0.0000040000 0.0000030000 0.0015590000 15086365 96830484 509673472 3.8263485432 4.2739381790 4.7367458344 742 29.6400000000 0.0142480517 0.0086820373 0.0234038215 0.0076343793 0.0051090000 0.0004010000 0.0027950000 0.0000000000 0.0000040000 0.0008570000 15089141 96830484 509673472 3.8201489449 4.2776322365 4.7457246780 743 29.6800000000 0.0141865173 0.0086894458 0.0234038215 0.0076340018 0.0050950000 0.0004000000 0.0025290000 0.0000030000 0.0000030000 0.0011080000 15091917 96830484 509673472 3.8153162003 4.2786369324 4.7539196014 744 29.7200000000 0.0141959880 0.0086968470 0.0234038215 0.0076293715 0.0052590000 0.0004000000 0.0029390000 0.0000000000 0.0000030000 0.0008490000 15094693 96830484 509673472 3.8103458881 4.2806229591 4.7609181404 745 29.7600000000 0.0142010776 0.0087042353 0.0234038215 0.0076271610 0.0054520000 0.0004020000 0.0024210000 0.0000040000 0.0000030000 0.0015630000 15097469 96830484 509673472 3.8051693439 4.2833333015 4.7673606873 746 29.8000000000 0.0141980182 0.0087115996 0.0234038215 0.0076231897 0.0047610000 0.0004030000 0.0024370000 0.0000000000 0.0000030000 0.0008490000 15100245 96830484 509673472 3.8003442287 4.2852001190 4.7736997604 747 29.8400000000 0.0141940117 0.0087189388 0.0234038215 0.0076182764 0.0050960000 0.0004000000 0.0025530000 0.0000030000 0.0000020000 0.0010770000 15103021 96830484 509673472 3.7950968742 4.2882914543 4.7794380188 748 29.8800000000 0.0141583513 0.0087262108 0.0234038215 0.0076154705 0.0051190000 0.0004000000 0.0028070000 0.0000010000 0.0000030000 0.0008450000 15105797 96830484 509673472 3.7901055813 4.2918062210 4.7853803635 749 29.9200000000 0.0141648687 0.0087334720 0.0234038215 0.0076120125 0.0063370000 0.0004010000 0.0025250000 0.0000040000 0.0000030000 0.0020090000 15108573 96830484 509673472 3.7858099937 4.2947058678 4.7910299301 750 29.9600000000 0.0141791273 0.0087407329 0.0234038215 0.0076089527 0.0049630000 0.0004560000 0.0025420000 0.0000000000 0.0000040000 0.0008490000 15111349 96830484 509673472 3.7817609310 4.2975273132 4.7962603569 751 30.0000000000 0.0142160412 0.0087480235 0.0234038215 0.0076059401 0.0049730000 0.0004050000 0.0024040000 0.0000040000 0.0000030000 0.0010750000 15114125 96830484 509673472 3.7779874802 4.2997059822 4.8008751869 752 30.0400000000 0.0142573137 0.0087553497 0.0234038215 0.0076030747 0.0052470000 0.0004010000 0.0029330000 0.0000000000 0.0000040000 0.0008340000 15116901 96830484 509673472 3.7744195461 4.3024230003 4.8051824570 753 30.0800000000 0.0142574776 0.0087626567 0.0234038215 0.0076022862 0.0054350000 0.0004030000 0.0024040000 0.0000030000 0.0000030000 0.0015410000 15119677 96830484 509673472 3.7707173824 4.3043723106 4.8089079857 754 30.1200000000 0.0142907547 0.0087699884 0.0234038215 0.0076078324 0.0051240000 0.0004030000 0.0028000000 0.0000000000 0.0000040000 0.0008300000 15122453 96830484 509673472 3.7671651840 4.3065071106 4.8124728203 755 30.1600000000 0.0143503798 0.0087773796 0.0234038215 0.0076191280 0.0049470000 0.0004000000 0.0023950000 0.0000030000 0.0000030000 0.0010650000 15125229 96830484 509673472 3.7631106377 4.3079886436 4.8157191277 756 30.2000000000 0.0143578649 0.0087847612 0.0234038215 0.0076305173 0.0052180000 0.0004000000 0.0029190000 0.0000010000 0.0000030000 0.0008230000 15128005 96830484 509673472 3.7588417530 4.3107352257 4.8192877769 757 30.2400000000 0.0143215647 0.0087920754 0.0234038215 0.0076321991 0.0054040000 0.0004010000 0.0023890000 0.0000030000 0.0000040000 0.0015290000 15130781 96830484 509673472 3.7540323734 4.3137836456 4.8223166466 758 30.2800000000 0.0143272150 0.0087993776 0.0234038215 0.0076353019 0.0052310000 0.0004030000 0.0029200000 0.0000000000 0.0000040000 0.0008260000 15133557 96830484 509673472 3.7491452694 4.3155264854 4.8257660866 759 30.3200000000 0.0143730063 0.0088067210 0.0234038215 0.0076522847 0.0049420000 0.0004010000 0.0023870000 0.0000030000 0.0000040000 0.0010700000 15136333 96830484 509673472 3.7436273098 4.3185868263 4.8292517662 760 30.3600000000 0.0143878590 0.0088140646 0.0234038215 0.0076651681 0.0052110000 0.0004000000 0.0029050000 0.0000000000 0.0000030000 0.0008160000 15139109 96830484 509673472 3.7373211384 4.3234467506 4.8322610855 761 30.4000000000 0.0143975662 0.0088214017 0.0234038215 0.0076742134 0.0054880000 0.0004020000 0.0025050000 0.0000030000 0.0000030000 0.0014870000 15141885 96830484 509673472 3.7309877872 4.3269224167 4.8349933624 762 30.4400000000 0.0144075323 0.0088287326 0.0234038215 0.0076754993 0.0050950000 0.0004010000 0.0027780000 0.0000000000 0.0000030000 0.0008230000 15144661 96830484 509673472 3.7242169380 4.3305659294 4.8371901512 763 30.4800000000 0.0144663164 0.0088361213 0.0234038215 0.0076743347 0.0050710000 0.0004020000 0.0025240000 0.0000040000 0.0000030000 0.0010480000 15147437 96830484 509673472 3.7170135975 4.3346457481 4.8393964767 764 30.5200000000 0.0145217404 0.0088435632 0.0234038215 0.0076740856 0.0050890000 0.0004010000 0.0027880000 0.0000000000 0.0000030000 0.0008060000 15150213 96830484 509673472 3.7092709541 4.3385281563 4.8415856361 765 30.5600000000 0.0145005118 0.0088509579 0.0234038215 0.0076718403 0.0054930000 0.0004010000 0.0025230000 0.0000030000 0.0000040000 0.0014640000 15152989 96830484 509673472 3.7015848160 4.3425374031 4.8438706398 766 30.6000000000 0.0145804090 0.0088584376 0.0234038215 0.0076708753 0.0048350000 0.0004000000 0.0025470000 0.0000010000 0.0000040000 0.0007930000 15155765 96830484 509673472 3.6938910484 4.3461709023 4.8461494446 767 30.6400000000 0.0145623703 0.0088658743 0.0234038215 0.0076695273 0.0050610000 0.0003990000 0.0025350000 0.0000030000 0.0000040000 0.0010300000 15158541 96830484 509673472 3.6853933334 4.3501658440 4.8479857445 768 30.6800000000 0.0146076605 0.0088733506 0.0234038215 0.0076706589 0.0048300000 0.0004010000 0.0025380000 0.0000000000 0.0000040000 0.0007870000 15161317 96830484 509673472 3.6770789623 4.3538455963 4.8500652313 769 30.7200000000 0.0146278478 0.0088808336 0.0234038215 0.0076713102 0.0054690000 0.0004000000 0.0025260000 0.0000030000 0.0000030000 0.0014320000 15164093 96830484 509673472 3.6687047482 4.3581080437 4.8521847725 770 30.7600000000 0.0146342190 0.0088883056 0.0234038215 0.0076684984 0.0048220000 0.0004010000 0.0025310000 0.0000010000 0.0000030000 0.0007860000 15166869 96830484 509673472 3.6603212357 4.3623938560 4.8542804718 771 30.8000000000 0.0146410884 0.0088957670 0.0234038215 0.0076648205 0.0054770000 0.0004020000 0.0029190000 0.0000040000 0.0000030000 0.0010460000 15169645 96830484 509673472 3.6518585682 4.3661909103 4.8559808731 772 30.8400000000 0.0147050209 0.0089032920 0.0234038215 0.0076624479 0.0048200000 0.0004000000 0.0025360000 0.0000010000 0.0000030000 0.0007800000 15172421 96830484 509673472 3.6435592175 4.3688035011 4.8577666283 773 30.8800000000 0.0147016849 0.0089107931 0.0234038215 0.0076610624 0.0055170000 0.0004010000 0.0025480000 0.0000030000 0.0000030000 0.0014560000 15175197 96830484 509673472 3.6350376606 4.3718733788 4.8596067429 774 30.9200000000 0.0147453239 0.0089183313 0.0234038215 0.0076644198 0.0052020000 0.0004020000 0.0029230000 0.0000010000 0.0000030000 0.0007690000 15177973 96830484 509673472 3.6269762516 4.3743290901 4.8616347313 775 30.9600000000 0.0147887189 0.0089259060 0.0234038215 0.0076697027 0.0049160000 0.0004010000 0.0024020000 0.0000030000 0.0000030000 0.0010010000 15180749 96830484 509673472 3.6186838150 4.3759083748 4.8631105423 776 31.0000000000 0.0147937443 0.0089334676 0.0234038215 0.0076773653 0.0046660000 0.0004020000 0.0023900000 0.0000000000 0.0000030000 0.0007680000 15183525 96830484 509673472 3.6101126671 4.3778591156 4.8646345139 777 31.0400000000 0.0148291588 0.0089410554 0.0234038215 0.0076881364 0.0050460000 0.0004000000 0.0021300000 0.0000040000 0.0000030000 0.0014040000 15186301 96830484 509673472 3.6016428471 4.3810915947 4.8659210205 778 31.0800000000 0.0148525201 0.0089486537 0.0234038215 0.0076891708 0.0046650000 0.0004000000 0.0023930000 0.0000000000 0.0000040000 0.0007610000 15189077 96830484 509673472 3.5933084488 4.3844466209 4.8670721054 779 31.1200000000 0.0148736443 0.0089562596 0.0234038215 0.0076876577 0.0050750000 0.0003990000 0.0025270000 0.0000040000 0.0000030000 0.0010310000 15191853 96830484 509673472 3.5854470730 4.3867053986 4.8686099052 780 31.1600000000 0.0148852095 0.0089638608 0.0234038215 0.0076866663 0.0048150000 0.0004030000 0.0025350000 0.0000000000 0.0000030000 0.0007590000 15194629 96830484 509673472 3.5777349472 4.3893294334 4.8701419830 781 31.2000000000 0.0149344746 0.0089715056 0.0234038215 0.0076844537 0.0057130000 0.0004010000 0.0027840000 0.0000030000 0.0000040000 0.0014060000 15197405 96830484 509673472 3.5700395107 4.3917531967 4.8709049225 782 31.2400000000 0.0149240717 0.0089791176 0.0234038215 0.0076804010 0.0050920000 0.0004020000 0.0028050000 0.0000000000 0.0000040000 0.0007540000 15200181 96830484 509673472 3.5627417564 4.3930764198 4.8721742630 783 31.2800000000 0.0149170831 0.0089867012 0.0234038215 0.0076758677 0.0053190000 0.0004020000 0.0028130000 0.0000030000 0.0000030000 0.0009780000 15202957 96830484 509673472 3.5555405617 4.3947482109 4.8735418320 784 31.3200000000 0.0149604809 0.0089943208 0.0234038215 0.0076711231 0.0050790000 0.0004000000 0.0028050000 0.0000000000 0.0000030000 0.0007460000 15205733 96830484 509673472 3.5489115715 4.3960537910 4.8749604225 785 31.3600000000 0.0149550876 0.0090019141 0.0234038215 0.0076663915 0.0054580000 0.0004000000 0.0025430000 0.0000030000 0.0000030000 0.0013790000 15208509 96830484 509673472 3.5425050259 4.3966536522 4.8760895729 786 31.4000000000 0.0149752861 0.0090095139 0.0234038215 0.0076632068 0.0046910000 0.0004040000 0.0024110000 0.0000010000 0.0000030000 0.0007430000 15211285 96830484 509673472 3.5360922813 4.3975763321 4.8773274422 787 31.4400000000 0.0149635542 0.0090170793 0.0234038215 0.0076598771 0.0051000000 0.0004030000 0.0025650000 0.0000040000 0.0000030000 0.0010100000 15214061 96830484 509673472 3.5303144455 4.3995294571 4.8785009384 788 31.4800000000 0.0149913626 0.0090246609 0.0234038215 0.0076580218 0.0048410000 0.0004030000 0.0025630000 0.0000010000 0.0000030000 0.0007400000 15216837 96830484 509673472 3.5250968933 4.4004378319 4.8801174164 789 31.5200000000 0.0150151923 0.0090322535 0.0234038215 0.0076565380 0.0052450000 0.0004020000 0.0024370000 0.0000040000 0.0000030000 0.0012690000 15219613 96830484 509673472 3.5197999477 4.4005088806 4.8811955452 790 31.5600000000 0.0150071792 0.0090398167 0.0234038215 0.0076528342 0.0050500000 0.0004020000 0.0028270000 0.0000000000 0.0000040000 0.0006830000 15222389 96830484 509673472 3.5146903992 4.4006853104 4.8826565742 791 31.6000000000 0.0149963107 0.0090473470 0.0234038215 0.0076481470 0.0049810000 0.0004020000 0.0024360000 0.0000030000 0.0000040000 0.0009980000 15225165 96830484 509673472 3.5098438263 4.4009284973 4.8838677406 792 31.6400000000 0.0149962008 0.0090548582 0.0234038215 0.0076433546 0.0048490000 0.0004020000 0.0025770000 0.0000010000 0.0000040000 0.0007430000 15227941 96830484 509673472 3.5055809021 4.4005460739 4.8852591515 793 31.6800000000 0.0149992974 0.0090623543 0.0234038215 0.0076401909 0.0054970000 0.0004010000 0.0025730000 0.0000030000 0.0000030000 0.0013820000 15230717 96830484 509673472 3.5017232895 4.3997616768 4.8864722252 794 31.7200000000 0.0149983019 0.0090698303 0.0234038215 0.0076428345 0.0048630000 0.0004030000 0.0025740000 0.0000010000 0.0000030000 0.0007470000 15233493 96830484 509673472 3.4984242916 4.3986692429 4.8878889084 795 31.7600000000 0.0149943735 0.0090772826 0.0234038215 0.0076520739 0.0049670000 0.0004030000 0.0024360000 0.0000030000 0.0000040000 0.0009830000 15236269 96830484 509673472 3.4951646328 4.3976435661 4.8891816139 796 31.8000000000 0.0149849607 0.0090847043 0.0234038215 0.0076694970 0.0047270000 0.0004030000 0.0024450000 0.0000010000 0.0000030000 0.0007380000 15239045 96830484 509673472 3.4919991493 4.3965382576 4.8908505440 797 31.8400000000 0.0150258634 0.0090921587 0.0234038215 0.0076891858 0.0054840000 0.0004000000 0.0025640000 0.0000030000 0.0000030000 0.0013780000 15241821 96830484 509673472 3.4896328449 4.3954634666 4.8924660683 798 31.8800000000 0.0150147416 0.0090995805 0.0234038215 0.0077073493 0.0047370000 0.0004020000 0.0024420000 0.0000000000 0.0000030000 0.0007470000 15244597 96830484 509673472 3.4867827892 4.3939709663 4.8937740326 799 31.9200000000 0.0150366705 0.0091070111 0.0234038215 0.0077177064 0.0045660000 0.0004010000 0.0020490000 0.0000040000 0.0000030000 0.0009640000 15247373 96830484 509673472 3.4841732979 4.3922038078 4.8951792717 800 31.9600000000 0.0149989724 0.0091143761 0.0234038215 0.0077254184 0.0043490000 0.0004010000 0.0020520000 0.0000000000 0.0000030000 0.0007520000 15250149 96830484 509673472 3.4817991257 4.3901815414 4.8967022896 801 32.0000000000 0.0149894739 0.0091217108 0.0234038215 0.0077384051 0.0050170000 0.0004030000 0.0020380000 0.0000030000 0.0000030000 0.0014250000 15252925 96830484 509673472 3.4798204899 4.3884849548 4.8987469673 802 32.0400000000 0.0150138540 0.0091290576 0.0234038215 0.0077442980 0.0047450000 0.0004000000 0.0024400000 0.0000000000 0.0000030000 0.0007570000 15255701 96830484 509673472 3.4777314663 4.3864250183 4.9005551338 803 32.0800000000 0.0149964243 0.0091363644 0.0234038215 0.0077554980 0.0045980000 0.0004020000 0.0020510000 0.0000030000 0.0000030000 0.0009880000 15258477 96830484 509673472 3.4768621922 4.3860807419 4.9031410217 804 32.1199999990 0.0150234560 0.0091436867 0.0234038215 0.0077719745 0.0048900000 0.0004020000 0.0025720000 0.0000000000 0.0000040000 0.0007630000 15261253 96830484 509673472 3.4757497311 4.3853344917 4.9051532745 805 32.1600000000 0.0149897840 0.0091509489 0.0234038215 0.0077880582 0.0055330000 0.0004020000 0.0025620000 0.0000040000 0.0000030000 0.0014110000 15264029 96830484 509673472 3.4747533798 4.3836150169 4.9073553085 806 32.2000000000 0.0150057552 0.0091582129 0.0234038215 0.0078047376 0.0047730000 0.0004030000 0.0024430000 0.0000000000 0.0000040000 0.0007670000 15266805 96830484 509673472 3.4735121727 4.3820662498 4.9090790749 807 32.2400000000 0.0150147658 0.0091654701 0.0234038215 0.0078221430 0.0046000000 0.0004020000 0.0020450000 0.0000030000 0.0000020000 0.0009920000 15269581 96830484 509673472 3.4729151726 4.3790049553 4.9110703468 808 32.2800000000 0.0150223300 0.0091727187 0.0234038215 0.0078312309 0.0047840000 0.0004040000 0.0024400000 0.0000000000 0.0000030000 0.0007760000 15272357 96830484 509673472 3.4717168808 4.3765935898 4.9133419991 809 32.3200000000 0.0150084719 0.0091799322 0.0234038215 0.0078372734 0.0054220000 0.0004020000 0.0024440000 0.0000040000 0.0000030000 0.0014100000 15275133 96830484 509673472 3.4715015888 4.3728895187 4.9157671928 810 32.3600000000 0.0150340265 0.0091871595 0.0234038215 0.0078440666 0.0047710000 0.0004000000 0.0024390000 0.0000010000 0.0000030000 0.0007770000 15277909 96830484 509673472 3.4707136154 4.3705410957 4.9178771973 811 32.4000000000 0.0150299212 0.0091943639 0.0234038215 0.0078426344 0.0072530000 0.0004030000 0.0046480000 0.0000030000 0.0000020000 0.0010150000 15280685 96830484 509673472 3.4696333408 4.3667325974 4.9199676514 812 32.4399999990 0.0150403017 0.0092015633 0.0234038215 0.0078416743 0.0071530000 0.0004040000 0.0047940000 0.0000000000 0.0000040000 0.0007900000 15283461 96830484 509673472 3.4688682556 4.3632202148 4.9221758842 813 32.4800000000 0.0150019135 0.0092086979 0.0234038215 0.0078418240 0.0055740000 0.0004010000 0.0025770000 0.0000030000 0.0000030000 0.0014210000 15286237 96830484 509673472 3.4686572552 4.3606390953 4.9252305031 814 32.5200000000 0.0150171882 0.0092158336 0.0234038215 0.0078423261 0.0047990000 0.0004000000 0.0024470000 0.0000000000 0.0000040000 0.0007820000 15289013 96830484 509673472 3.4680800438 4.3578152657 4.9280681610 815 32.5600000000 0.0149815753 0.0092229081 0.0234038215 0.0078399244 0.0050340000 0.0004030000 0.0024370000 0.0000030000 0.0000030000 0.0010230000 15291789 96830484 509673472 3.4672636986 4.3547873497 4.9308013916 816 32.6000000000 0.0150015475 0.0092299898 0.0234038215 0.0078379638 0.0049220000 0.0004030000 0.0025700000 0.0000010000 0.0000030000 0.0007800000 15294565 96830484 509673472 3.4670178890 4.3505215645 4.9341163635 817 32.6400000000 0.0149596957 0.0092370029 0.0234038215 0.0078342217 0.0054690000 0.0004010000 0.0024430000 0.0000040000 0.0000030000 0.0014420000 15297341 96830484 509673472 3.4662525654 4.3470702171 4.9370064735 818 32.6800000000 0.0149487955 0.0092439855 0.0234038215 0.0078296761 0.0049330000 0.0004040000 0.0025690000 0.0000000000 0.0000040000 0.0007850000 15300117 96830484 509673472 3.4656007290 4.3434238434 4.9407124519 819 32.7200000000 0.0149640050 0.0092509697 0.0234038215 0.0078263331 0.0052350000 0.0004000000 0.0025760000 0.0000040000 0.0000030000 0.0010270000 15302893 96830484 509673472 3.4653968811 4.3415002823 4.9449739456 820 32.7599999990 0.0149468733 0.0092579159 0.0234038215 0.0078235158 0.0054220000 0.0004770000 0.0026910000 0.0000010000 0.0000040000 0.0008060000 15305669 96830484 509673472 3.4648013115 4.3390760422 4.9492430687 821 32.7999999990 0.0148618445 0.0092647416 0.0234038215 0.0078275125 0.0055040000 0.0004040000 0.0024580000 0.0000040000 0.0000030000 0.0014390000 15308445 96830484 509673472 3.4653165340 4.3370056152 4.9547982216 822 32.8400000000 0.0149076404 0.0092716065 0.0234038215 0.0078511378 0.0048370000 0.0004020000 0.0024540000 0.0000000000 0.0000040000 0.0007980000 15311221 96830484 509673472 3.4650454521 4.3344697952 4.9596862793 823 32.8800000000 0.0148421377 0.0092783750 0.0234038215 0.0078610684 0.0055810000 0.0004010000 0.0029690000 0.0000040000 0.0000030000 0.0010180000 15313997 96830484 509673472 3.4644279480 4.3323874474 4.9646911621 824 32.9200000000 0.0149065256 0.0092852053 0.0234038215 0.0078654649 0.0056220000 0.0004020000 0.0032220000 0.0000000000 0.0000040000 0.0008010000 15316773 96830484 509673472 3.4640736580 4.3315801620 4.9705429077 825 32.9600000000 0.0148100210 0.0092919021 0.0234038215 0.0078781183 0.0057100000 0.0004030000 0.0025800000 0.0000040000 0.0000030000 0.0014640000 15319549 96830484 509673472 3.4637763500 4.3291244507 4.9765634537 826 33.0000000000 0.0147065921 0.0092984574 0.0234038215 0.0078860333 0.0048990000 0.0004050000 0.0024490000 0.0000000000 0.0000030000 0.0008050000 15322325 96830484 509673472 3.4633414745 4.3277649879 4.9827437401 827 33.0400000000 0.0146322101 0.0093049069 0.0234038215 0.0079026439 0.0050990000 0.0004010000 0.0024500000 0.0000030000 0.0000030000 0.0010030000 15325101 96830484 509673472 3.4627931118 4.3245472908 4.9885945320 828 33.0800000000 0.0145911099 0.0093112912 0.0234038215 0.0079296179 0.0050250000 0.0004030000 0.0025680000 0.0000010000 0.0000030000 0.0008000000 15327877 96830484 509673472 3.4624831676 4.3207349777 4.9941558838 829 33.1199999990 0.0145420199 0.0093176009 0.0234038215 0.0079507607 0.0055360000 0.0004040000 0.0024220000 0.0000030000 0.0000030000 0.0014550000 15330653 96830484 509673472 3.4617583752 4.3175115585 5.0003685951 830 33.1600000000 0.0144277010 0.0093237576 0.0234038215 0.0079664885 0.0048910000 0.0004040000 0.0024290000 0.0000000000 0.0000040000 0.0008090000 15333429 96830484 509673472 3.4611141682 4.3140044212 5.0062336922 831 33.2000000000 0.0142812971 0.0093297234 0.0234038215 0.0079841133 0.0050780000 0.0004010000 0.0024200000 0.0000040000 0.0000030000 0.0010150000 15336205 96830484 509673472 3.4612455368 4.3089199066 5.0130391121 832 33.2400000000 0.0141255362 0.0093354876 0.0234038215 0.0079938944 0.0050180000 0.0004030000 0.0025580000 0.0000000000 0.0000030000 0.0008040000 15338981 96830484 509673472 3.4605348110 4.3047127724 5.0195188522 833 33.2800000000 0.0139739746 0.0093410560 0.0234038215 0.0079968648 0.0059040000 0.0004000000 0.0028380000 0.0000030000 0.0000020000 0.0014570000 15341757 96830484 509673472 3.4595835209 4.3012294769 5.0264039040 834 33.3200000000 0.0139111169 0.0093465357 0.0234038215 0.0080009258 0.0053730000 0.0004000000 0.0029600000 0.0000010000 0.0000030000 0.0008110000 15344533 96830484 509673472 3.4587943554 4.2960877419 5.0329232216 835 33.3600000000 0.0137430755 0.0093518010 0.0234038215 0.0080074548 0.0051810000 0.0004010000 0.0025620000 0.0000030000 0.0000030000 0.0010160000 15347309 96830484 509673472 3.4574675560 4.2932944298 5.0391044617 836 33.4000000000 0.0136487354 0.0093569409 0.0234038215 0.0080166667 0.0053940000 0.0004040000 0.0029580000 0.0000000000 0.0000030000 0.0008190000 15350085 96830484 509673472 3.4565820694 4.2896146774 5.0458016396 837 33.4399999990 0.0135026518 0.0093618939 0.0234038215 0.0080320662 0.0055230000 0.0004030000 0.0024320000 0.0000030000 0.0000030000 0.0014750000 15352861 96830484 509673472 3.4554309845 4.2869272232 5.0521941185 838 33.4800000000 0.0134273805 0.0093667453 0.0234038215 0.0080612833 0.0044520000 0.0004010000 0.0020340000 0.0000000000 0.0000030000 0.0008120000 15355637 96830484 509673472 3.4550287724 4.2820277214 5.0581789017 839 33.5200000000 0.0132829575 0.0093714131 0.0234038215 0.0080922814 0.0050630000 0.0004010000 0.0024170000 0.0000030000 0.0000030000 0.0010380000 15358413 96830484 509673472 3.4544811249 4.2794241905 5.0646243095 840 33.5600000000 0.0130839972 0.0093758328 0.0234038215 0.0081134058 0.0048540000 0.0004030000 0.0024220000 0.0000000000 0.0000040000 0.0008180000 15361189 96830484 509673472 3.4522542953 4.2767581940 5.0692820549 841 33.6000000000 0.0128807984 0.0093800004 0.0234038215 0.0081159737 0.0056730000 0.0003990000 0.0025630000 0.0000030000 0.0000030000 0.0014890000 15363965 96830484 509673472 3.4508469105 4.2745561600 5.0747604370 842 33.6400000000 0.0127107929 0.0093839562 0.0234038215 0.0081144377 0.0050000000 0.0004020000 0.0025710000 0.0000000000 0.0000030000 0.0008150000 15366741 96830484 509673472 3.4494299889 4.2722659111 5.0798292160 843 33.6800000000 0.0125204064 0.0093876768 0.0234038215 0.0081143317 0.0052050000 0.0004020000 0.0025780000 0.0000030000 0.0000030000 0.0010120000 15369517 96830484 509673472 3.4483847618 4.2687005997 5.0850777626 844 33.7200000000 0.0123535581 0.0093911909 0.0234038215 0.0081194450 0.0049900000 0.0004000000 0.0025530000 0.0000000000 0.0000030000 0.0008200000 15372293 96830484 509673472 3.4476621151 4.2636570930 5.0899558067 845 33.7599999990 0.0121643851 0.0093944728 0.0234038215 0.0081303330 0.0055260000 0.0004010000 0.0024260000 0.0000030000 0.0000040000 0.0014770000 15375069 96830484 509673472 3.4475893974 4.2603254318 5.0951514244 846 33.7999999990 0.0117588863 0.0093972676 0.0234038215 0.0081374079 0.0048620000 0.0004040000 0.0024140000 0.0000000000 0.0000040000 0.0008240000 15377845 96830484 509673472 3.4463891983 4.2576665878 5.0997309685 847 33.8400000000 0.0114403600 0.0093996797 0.0234038215 0.0081362422 0.0051750000 0.0004020000 0.0025560000 0.0000040000 0.0000030000 0.0010020000 15380621 96830484 509673472 3.4455940723 4.2526540756 5.1033678055 848 33.8800000000 0.0111546181 0.0094017492 0.0234038215 0.0081317902 0.0048540000 0.0004030000 0.0024290000 0.0000000000 0.0000040000 0.0007980000 15383397 96830484 509673472 3.4447321892 4.2489714622 5.1074504852 849 33.9200000000 0.0107861375 0.0094033799 0.0234038215 0.0081270285 0.0056410000 0.0004000000 0.0025680000 0.0000040000 0.0000030000 0.0014400000 15386173 96830484 509673472 3.4439406395 4.2432360649 5.1110167503 850 33.9600000000 0.0105255116 0.0094047000 0.0234038215 0.0081225779 0.0048740000 0.0004030000 0.0024210000 0.0000000000 0.0000040000 0.0008250000 15388949 96830484 509673472 3.4431729317 4.2393426895 5.1146869659 851 34.0000000000 0.0103141144 0.0094057687 0.0234038215 0.0081178278 0.0052400000 0.0004040000 0.0025460000 0.0000040000 0.0000030000 0.0010570000 15391725 96830484 509673472 3.4422764778 4.2363071442 5.1186285019 852 34.0400000000 0.0101502649 0.0094066425 0.0234038215 0.0081130808 0.0049570000 0.0004030000 0.0024300000 0.0000000000 0.0000040000 0.0008380000 15394501 96830484 509673472 3.4425928593 4.2309861183 5.1224913597 853 34.0800000000 0.0098332893 0.0094071427 0.0234038215 0.0081106310 0.0053850000 0.0004050000 0.0021630000 0.0000040000 0.0000030000 0.0015200000 15397277 96830484 509673472 3.4416449070 4.2268524170 5.1254868507 854 34.1199999990 0.0095127430 0.0094072663 0.0234038215 0.0081089793 0.0051040000 0.0004040000 0.0025620000 0.0000000000 0.0000030000 0.0008470000 15400053 96830484 509673472 3.4414086342 4.2240428925 5.1290354729 855 34.1600000000 0.0090810983 0.0094068848 0.0234038215 0.0081098355 0.0051750000 0.0004040000 0.0024290000 0.0000040000 0.0000030000 0.0010500000 15402829 96830484 509673472 3.4416799545 4.2203278542 5.1325449944 856 34.2000000000 0.0087116081 0.0094060726 0.0234038215 0.0081097666 0.0073230000 0.0004030000 0.0047780000 0.0000010000 0.0000030000 0.0008520000 15405605 96830484 509673472 3.4411818981 4.2171387672 5.1353721619 857 34.2400000000 0.0083655538 0.0094048584 0.0234038215 0.0081056666 0.0058240000 0.0004040000 0.0025730000 0.0000040000 0.0000030000 0.0015470000 15408381 96830484 509673472 3.4401326180 4.2157945633 5.1382365227 858 34.2800000000 0.0080824783 0.0094033172 0.0234038215 0.0081010940 0.0054480000 0.0004030000 0.0029500000 0.0000010000 0.0000030000 0.0008510000 15411157 96830484 509673472 3.4389710426 4.2132945061 5.1406230927 859 34.3200000000 0.0079321610 0.0094016046 0.0234038215 0.0080966681 0.0052580000 0.0004020000 0.0025630000 0.0000040000 0.0000030000 0.0010510000 15413933 96830484 509673472 3.4392890930 4.2071509361 5.1425662041 860 34.3600000000 0.0075821541 0.0093994889 0.0234038215 0.0080922342 0.0049230000 0.0004060000 0.0024230000 0.0000010000 0.0000030000 0.0008500000 15416709 96830484 509673472 3.4386522770 4.2019801140 5.1440320015 861 34.4000000000 0.0072099068 0.0093969459 0.0234038215 0.0080879184 0.0055940000 0.0004030000 0.0024130000 0.0000030000 0.0000030000 0.0015390000 15419485 96830484 509673472 3.4383196831 4.1982827187 5.1465249062 862 34.4400000000 0.0068567432 0.0093939990 0.0234038215 0.0080832468 0.0050550000 0.0004010000 0.0025560000 0.0000000000 0.0000040000 0.0008520000 15422261 96830484 509673472 3.4381964207 4.1939525604 5.1484742165 863 34.4800000000 0.0065161064 0.0093906642 0.0234038215 0.0080788861 0.0056520000 0.0004020000 0.0029600000 0.0000040000 0.0000030000 0.0010450000 15425037 96830484 509673472 3.4380509853 4.1873650551 5.1496829987 864 34.5200000000 0.0060912753 0.0093868455 0.0234038215 0.0080745463 0.0045430000 0.0004000000 0.0020380000 0.0000000000 0.0000030000 0.0008630000 15427813 96830484 509673472 3.4382395744 4.1836380959 5.1514482498 865 34.5600000000 0.0058906805 0.0093828037 0.0234038215 0.0080698768 0.0065200000 0.0004050000 0.0033410000 0.0000030000 0.0000030000 0.0015140000 15430589 96830484 509673472 3.4372994900 4.1823873520 5.1531543732 866 34.6000000000 0.0058179144 0.0093786872 0.0234038215 0.0080673931 0.0045280000 0.0004040000 0.0020400000 0.0000000000 0.0000040000 0.0008410000 15433365 96830484 509673472 3.4360690117 4.1808862686 5.1542773247 867 34.6400000000 0.0056784176 0.0093744193 0.0234038215 0.0080641238 0.0052810000 0.0004030000 0.0025700000 0.0000040000 0.0000030000 0.0010610000 15436141 96830484 509673472 3.4362993240 4.1780986786 5.1559038162 868 34.6800000000 0.0056740870 0.0093701562 0.0234038215 0.0080600066 0.0046200000 0.0004040000 0.0021290000 0.0000010000 0.0000040000 0.0008430000 15438917 96830484 509673472 3.4356739521 4.1743216515 5.1566581726 869 34.7200000000 0.0054815426 0.0093656814 0.0234038215 0.0080557657 0.0055170000 0.0004030000 0.0023200000 0.0000030000 0.0000030000 0.0015340000 15441693 96830484 509673472 3.4362785816 4.1708250046 5.1577100754 870 34.7600000000 0.0053936755 0.0093611159 0.0234038215 0.0080514077 0.0048960000 0.0004040000 0.0024260000 0.0000000000 0.0000040000 0.0008070000 15444469 96830484 509673472 3.4353151321 4.1681756973 5.1581826210 871 34.8000000000 0.0053738221 0.0093565381 0.0234038215 0.0080467804 0.0047220000 0.0004000000 0.0020340000 0.0000030000 0.0000030000 0.0010240000 15447245 96830484 509673472 3.4343438148 4.1663365364 5.1589169502 872 34.8400000000 0.0052798879 0.0093518630 0.0234038215 0.0080425245 0.0049370000 0.0004030000 0.0024370000 0.0000000000 0.0000040000 0.0008160000 15450021 96830484 509673472 3.4332633018 4.1631307602 5.1595444679 873 34.8800000000 0.0051564449 0.0093470573 0.0234038215 0.0080380716 0.0055970000 0.0004040000 0.0024440000 0.0000040000 0.0000030000 0.0014740000 15452797 96830484 509673472 3.4328534603 4.1610312462 5.1609210968 874 34.9200000000 0.0052125254 0.0093423267 0.0234038215 0.0080341799 0.0049120000 0.0004030000 0.0024300000 0.0000010000 0.0000030000 0.0008140000 15455573 96830484 509673472 3.4321591854 4.1598286629 5.1621079445 875 34.9600000000 0.0050856448 0.0093374619 0.0234038215 0.0080306660 0.0052540000 0.0004020000 0.0025590000 0.0000040000 0.0000030000 0.0010240000 15458349 96830484 509673472 3.4306297302 4.1598424911 5.1635861397 876 35.0000000000 0.0051528737 0.0093326850 0.0234038215 0.0080269296 0.0043900000 0.0004040000 0.0019100000 0.0000000000 0.0000040000 0.0008100000 15461125 96830484 509673472 3.4298586845 4.1590299606 5.1649312973 877 35.0400000000 0.0050936262 0.0093278514 0.0234038215 0.0080223647 0.0053410000 0.0004050000 0.0021780000 0.0000030000 0.0000020000 0.0014700000 15463901 96830484 509673472 3.4289684296 4.1586933136 5.1663298607 878 35.0800000000 0.0052036420 0.0093231541 0.0234038215 0.0080179370 0.0046640000 0.0004050000 0.0021690000 0.0000000000 0.0000030000 0.0008130000 15466677 96830484 509673472 3.4279501438 4.1590414047 5.1674847603 879 35.1200000000 0.0051756208 0.0093184356 0.0234038215 0.0080133963 0.0048780000 0.0004030000 0.0021790000 0.0000030000 0.0000030000 0.0010170000 15469453 96830484 509673472 3.4270985126 4.1579713821 5.1685752869 880 35.1600000000 0.0051332046 0.0093136797 0.0234038215 0.0080092046 0.0049190000 0.0004010000 0.0024380000 0.0000000000 0.0000030000 0.0008100000 15472229 96830484 509673472 3.4264726639 4.1588721275 5.1699171066 881 35.2000000000 0.0051965336 0.0093090064 0.0234038215 0.0080053442 0.0050510000 0.0004010000 0.0019060000 0.0000040000 0.0000030000 0.0014660000 15475005 96830484 509673472 3.4254279137 4.1587538719 5.1712212563 882 35.2400000000 0.0050967298 0.0093042306 0.0234038215 0.0080019516 0.0050390000 0.0004010000 0.0025610000 0.0000000000 0.0000040000 0.0008110000 15477781 96830484 509673472 3.4259686470 4.1547031403 5.1718530655 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 01:22:46 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002920 0.0000002920 0.0000002920 -nan 0.0032300000 0.0004470000 0.0005070000 0.0000060000 0.0000010000 0.0021300000 12665325 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0040127714 0.0020065317 0.0040127714 0.0032323198 0.0023780000 0.0006080000 0.0005650000 0.0000170000 0.0000020000 0.0010660000 13061677 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0039232424 0.0026454353 0.0040127714 0.0045263772 0.0023420000 0.0005890000 0.0005560000 0.0000170000 0.0000020000 0.0010570000 13064845 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0033563883 0.0028231735 0.0040127714 0.0050261389 0.0029510000 0.0006040000 0.0005610000 0.0000170000 0.0000220000 0.0016190000 13068021 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0020585158 0.0026702420 0.0040127714 0.0052622180 0.0063010000 0.0006020000 0.0029990000 0.0000150000 0.0000140000 0.0025220000 13071181 96830484 509673472 4.0005679131 4.0062379837 4.0028867722 6 0.2000000000 0.0022282717 0.0025965803 0.0040127714 0.0049478834 0.0054890000 0.0006090000 0.0032380000 0.0000020000 0.0000170000 0.0014750000 13074757 96830484 509673472 4.0035142899 3.9963679314 4.0019836426 7 0.2400000000 0.0023014175 0.0025544142 0.0040127714 0.0047218328 0.0059270000 0.0006040000 0.0034090000 0.0000150000 0.0000140000 0.0017310000 13077533 96830484 509673472 4.0037331581 3.9863786697 3.9988594055 8 0.2800000000 0.0024058358 0.0025358419 0.0040127714 0.0043783305 0.0052140000 0.0006040000 0.0029620000 0.0000020000 0.0000160000 0.0014700000 13080309 96830484 509673472 4.0014529228 3.9884290695 3.9979808331 9 0.3200000000 0.0023829828 0.0025188575 0.0040127714 0.0050589391 0.0061930000 0.0006040000 0.0029550000 0.0000160000 0.0000140000 0.0024820000 13083853 96830484 509673472 4.0003533363 3.9923250675 4.0009713173 10 0.3600000000 0.0024716596 0.0025141377 0.0040127714 0.0047846787 0.0046660000 0.0005040000 0.0027810000 0.0000010000 0.0000100000 0.0012590000 13088229 96830484 509673472 3.9983103275 3.9848964214 3.9990835190 11 0.4000000000 0.0026018682 0.0025221132 0.0040127714 0.0045829778 0.0061710000 0.0005260000 0.0040020000 0.0000100000 0.0000090000 0.0015000000 13091005 96830484 509673472 3.9982979298 3.9888906479 3.9978284836 12 0.4400000000 0.0026440807 0.0025322772 0.0040127714 0.0046231387 0.0045050000 0.0005060000 0.0026230000 0.0000010000 0.0000100000 0.0012460000 13093781 96830484 509673472 3.9992866516 3.9987823963 4.0008063316 13 0.4800000000 0.0025945576 0.0025370680 0.0040127714 0.0044304165 0.0056660000 0.0005340000 0.0027690000 0.0000100000 0.0000090000 0.0022170000 13096557 96830484 509673472 4.0012993813 3.9965374470 4.0008153915 14 0.5200000000 0.0027364714 0.0025513111 0.0040127714 0.0043605006 0.0049600000 0.0005240000 0.0030620000 0.0000010000 0.0000100000 0.0012290000 13099333 96830484 509673472 4.0040860176 3.9890964031 3.9980857372 15 0.5600000000 0.0027256652 0.0025629347 0.0040127714 0.0042916505 0.0065790000 0.0006040000 0.0040630000 0.0000150000 0.0000140000 0.0016800000 13102109 96830484 509673472 4.0069060326 3.9907071590 3.9979019165 16 0.6000000000 0.0027488372 0.0025745536 0.0040127714 0.0041499514 0.0052410000 0.0006040000 0.0029580000 0.0000020000 0.0000170000 0.0014510000 13104885 96830484 509673472 4.0079045296 3.9920747280 3.9981870651 17 0.6400000000 0.0027897872 0.0025872144 0.0040127714 0.0040353301 0.0062950000 0.0005920000 0.0029490000 0.0000150000 0.0000130000 0.0025140000 13109197 96830484 509673472 4.0076575279 3.9883246422 3.9963276386 18 0.6800000000 0.0028621149 0.0026024867 0.0040127714 0.0039159697 0.0054930000 0.0005920000 0.0032150000 0.0000020000 0.0000150000 0.0014610000 13115173 96830484 509673472 4.0069389343 3.9894137383 3.9949533939 19 0.7200000000 0.0028721986 0.0026166820 0.0040127714 0.0039411313 0.0065050000 0.0005770000 0.0033920000 0.0000270000 0.0000190000 0.0022290000 13117949 96830484 509673472 4.0073785782 3.9935979843 3.9951670170 20 0.7600000000 0.0029137817 0.0026315370 0.0040127714 0.0042001314 0.0045740000 0.0005570000 0.0027920000 0.0000020000 0.0000100000 0.0011010000 13120725 96830484 509673472 4.0069322586 3.9923043251 3.9925444126 21 0.8000000000 0.0028845142 0.0026435835 0.0040127714 0.0043462357 0.0053880000 0.0005130000 0.0026990000 0.0000080000 0.0000070000 0.0020380000 13123501 96830484 509673472 4.0093746185 3.9954643250 3.9927823544 22 0.8400000000 0.0029369202 0.0026569170 0.0040127714 0.0042702313 0.0059680000 0.0006090000 0.0036390000 0.0000020000 0.0000170000 0.0014540000 13126277 96830484 509673472 4.0094804764 3.9983515739 3.9931848049 23 0.8800000000 0.0030857818 0.0026755633 0.0040127714 0.0042423367 0.0053770000 0.0005880000 0.0028050000 0.0000160000 0.0000140000 0.0017200000 13129053 96830484 509673472 4.0121827126 3.9920938015 3.9892163277 24 0.9200000000 0.0033512472 0.0027037168 0.0040127714 0.0042385300 0.0051820000 0.0006000000 0.0028010000 0.0000020000 0.0000150000 0.0015240000 13131829 96830484 509673472 4.0144157410 3.9935758114 3.9894180298 25 0.9600000000 0.0033457018 0.0027293962 0.0040127714 0.0041508411 0.0062140000 0.0005840000 0.0027890000 0.0000340000 0.0000150000 0.0025440000 13134605 96830484 509673472 4.0146059990 3.9905099869 3.9862883091 26 1.0000000000 0.0033623539 0.0027537407 0.0040127714 0.0040675994 0.0047230000 0.0005010000 0.0027960000 0.0000010000 0.0000110000 0.0012440000 13137381 96830484 509673472 4.0128607750 3.9902780056 3.9853050709 27 1.0400000000 0.0033408066 0.0027754839 0.0040127714 0.0040008730 0.0060620000 0.0005900000 0.0034590000 0.0000180000 0.0000130000 0.0017270000 13140157 96830484 509673472 4.0138993263 3.9860901833 3.9828314781 28 1.0800000000 0.0033535664 0.0027961297 0.0040127714 0.0039308158 0.0052790000 0.0005880000 0.0029580000 0.0000020000 0.0000170000 0.0014540000 13142933 96830484 509673472 4.0126342773 3.9840531349 3.9814426899 29 1.1200000000 0.0033603078 0.0028155841 0.0040127714 0.0039420728 0.0055550000 0.0005020000 0.0026320000 0.0000090000 0.0000090000 0.0022260000 13145709 96830484 509673472 4.0137376785 3.9820570946 3.9802513123 30 1.1600000000 0.0034488849 0.0028366942 0.0040127714 0.0039077985 0.0053040000 0.0005880000 0.0029430000 0.0000010000 0.0000140000 0.0014750000 13148485 96830484 509673472 4.0170412064 3.9830811024 3.9798831940 31 1.2000000000 0.0036165956 0.0028618523 0.0040127714 0.0039116283 0.0051310000 0.0005900000 0.0025100000 0.0000160000 0.0000130000 0.0017260000 13151261 96830484 509673472 4.0219888687 3.9843547344 3.9785184860 32 1.2400000000 0.0036410992 0.0028862037 0.0040127714 0.0039563979 0.0051580000 0.0005830000 0.0028020000 0.0000020000 0.0000150000 0.0014720000 13154037 96830484 509673472 4.0223841667 3.9876070023 3.9773900509 33 1.2800000000 0.0037009139 0.0029108919 0.0040127714 0.0041801619 0.0062320000 0.0005880000 0.0027940000 0.0000150000 0.0000140000 0.0025220000 13159885 96830484 509673472 4.0237050056 3.9915728569 3.9773089886 34 1.3200000000 0.0036787381 0.0029334756 0.0040127714 0.0043685224 0.0051390000 0.0005890000 0.0027700000 0.0000010000 0.0000160000 0.0014700000 13169061 96830484 509673472 4.0318694115 3.9940252304 3.9749875069 35 1.3600000000 0.0036429816 0.0029537472 0.0040127714 0.0043065475 0.0048160000 0.0005070000 0.0026190000 0.0000110000 0.0000100000 0.0014640000 13171837 96830484 509673472 4.0311307907 3.9926419258 3.9733846188 36 1.4000000000 0.0037401686 0.0029755923 0.0040127714 0.0042538661 0.0049420000 0.0005880000 0.0025750000 0.0000020000 0.0000160000 0.0014570000 13174613 96830484 509673472 4.0315456390 3.9903738499 3.9700045586 37 1.4400000000 0.0036499649 0.0029938186 0.0040127714 0.0041956559 0.0062560000 0.0005870000 0.0027850000 0.0000140000 0.0000140000 0.0025430000 13177389 96830484 509673472 4.0340623856 3.9892785549 3.9676873684 38 1.4800000000 0.0039306507 0.0030184720 0.0040127714 0.0041389314 0.0053000000 0.0005720000 0.0029490000 0.0000010000 0.0000160000 0.0014430000 13180165 96830484 509673472 4.0342350006 3.9894709587 3.9674448967 39 1.5200000000 0.0038185569 0.0030389870 0.0040127714 0.0041049721 0.0051490000 0.0005840000 0.0025250000 0.0000160000 0.0000130000 0.0016880000 13182941 96830484 509673472 4.0348224640 3.9902076721 3.9665126801 40 1.5600000000 0.0039645229 0.0030621254 0.0040127714 0.0043004428 0.0053280000 0.0005890000 0.0029450000 0.0000020000 0.0000160000 0.0014490000 13185717 96830484 509673472 4.0379071236 3.9906182289 3.9656765461 41 1.6000000000 0.0039860331 0.0030846598 0.0040127714 0.0045464570 0.0058310000 0.0005850000 0.0023550000 0.0000160000 0.0000140000 0.0025220000 13188493 96830484 509673472 4.0435156822 3.9923305511 3.9650821686 42 1.6400000000 0.0044836272 0.0031179685 0.0044836272 0.0045172182 0.0053210000 0.0005900000 0.0029520000 0.0000020000 0.0000150000 0.0014290000 13191269 96830484 509673472 4.0445218086 3.9924111366 3.9638333321 43 1.6800000000 0.0042965584 0.0031453776 0.0044836272 0.0044987052 0.0054140000 0.0005870000 0.0027610000 0.0000150000 0.0000140000 0.0016830000 13194045 96830484 509673472 4.0461373329 3.9921369553 3.9622647762 44 1.7200000000 0.0045094192 0.0031763785 0.0045094192 0.0044681613 0.0053230000 0.0005870000 0.0029380000 0.0000010000 0.0000160000 0.0014280000 13196821 96830484 509673472 4.0483326912 3.9931683540 3.9621014595 45 1.7600000000 0.0046877982 0.0032099656 0.0046877982 0.0046643236 0.0064240000 0.0005850000 0.0029410000 0.0000150000 0.0000130000 0.0025160000 13199597 96830484 509673472 4.0504131317 3.9947969913 3.9609920979 46 1.8000000000 0.0046759821 0.0032418356 0.0046877982 0.0047503420 0.0051580000 0.0005010000 0.0031950000 0.0000010000 0.0000100000 0.0012120000 13202373 96830484 509673472 4.0517616272 3.9956567287 3.9602890015 47 1.8400000000 0.0043487782 0.0032653875 0.0046877982 0.0047455140 0.0056360000 0.0006020000 0.0029330000 0.0000150000 0.0000140000 0.0016890000 13205149 96830484 509673472 4.0531158447 3.9980447292 3.9598867893 48 1.8800000000 0.0045068711 0.0032912518 0.0046877982 0.0047317963 0.0054150000 0.0006030000 0.0029570000 0.0000020000 0.0000150000 0.0014500000 13207925 96830484 509673472 4.0551476479 3.9993107319 3.9601128101 49 1.9200000000 0.0044835359 0.0033155841 0.0046877982 0.0047579741 0.0062720000 0.0005260000 0.0030170000 0.0000280000 0.0000170000 0.0023910000 13210701 96830484 509673472 4.0561594963 3.9968862534 3.9582457542 50 1.9600000000 0.0046146279 0.0033415650 0.0046877982 0.0047315328 0.0050910000 0.0005550000 0.0030610000 0.0000020000 0.0000120000 0.0012040000 13213477 96830484 509673472 4.0514888763 3.9993236065 3.9562673569 51 2.0000000000 0.0044674757 0.0033636417 0.0046877982 0.0047247067 0.0050520000 0.0005420000 0.0027860000 0.0000110000 0.0000090000 0.0014550000 13216253 96830484 509673472 4.0505309105 4.0037322044 3.9571309090 52 2.0400000000 0.0047116843 0.0033895655 0.0047116843 0.0047005248 0.0053710000 0.0005910000 0.0029670000 0.0000020000 0.0000150000 0.0014140000 13219029 96830484 509673472 4.0510134697 4.0015029907 3.9568879604 53 2.0800000000 0.0046361652 0.0034130863 0.0047116843 0.0046650446 0.0070780000 0.0005870000 0.0036260000 0.0000150000 0.0000130000 0.0024470000 13221805 96830484 509673472 4.0512080193 3.9970610142 3.9545483589 54 2.1200000000 0.0045986716 0.0034350416 0.0047116843 0.0046825857 0.0055960000 0.0005930000 0.0032210000 0.0000030000 0.0000150000 0.0013620000 13224581 96830484 509673472 4.0513687134 3.9984388351 3.9549844265 55 2.1600000000 0.0045131212 0.0034546430 0.0047116843 0.0046722466 0.0049920000 0.0005030000 0.0027790000 0.0000100000 0.0000090000 0.0014280000 13227357 96830484 509673472 4.0520820618 4.0007295609 3.9550132751 56 2.2000000000 0.0044305963 0.0034720708 0.0047116843 0.0046748499 0.0057240000 0.0005760000 0.0033630000 0.0000020000 0.0000160000 0.0013660000 13230133 96830484 509673472 4.0534024239 3.9998846054 3.9541101456 57 2.2400000000 0.0045567388 0.0034911000 0.0047116843 0.0046955361 0.0066860000 0.0005890000 0.0032260000 0.0000160000 0.0000140000 0.0024260000 13232909 96830484 509673472 4.0539326668 3.9971559048 3.9518053532 58 2.2800000000 0.0045839846 0.0035099429 0.0047116843 0.0048528593 0.0045900000 0.0005010000 0.0026430000 0.0000010000 0.0000100000 0.0011590000 13235685 96830484 509673472 4.0575251579 3.9987654686 3.9523797035 59 2.3200000000 0.0047956128 0.0035317339 0.0047956128 0.0050189124 0.0055780000 0.0005870000 0.0029260000 0.0000150000 0.0000140000 0.0016160000 13238461 96830484 509673472 4.0615358353 4.0016217232 3.9516859055 60 2.3600000000 0.0049531879 0.0035554248 0.0049531879 0.0050703270 0.0051910000 0.0005900000 0.0027880000 0.0000020000 0.0000150000 0.0013710000 13241237 96830484 509673472 4.0651321411 3.9972314835 3.9490835667 61 2.4000000000 0.0049847728 0.0035788567 0.0049847728 0.0050607619 0.0064370000 0.0005840000 0.0029570000 0.0000170000 0.0000130000 0.0024310000 13244013 96830484 509673472 4.0649266243 3.9946384430 3.9476435184 62 2.4400000000 0.0047013788 0.0035969619 0.0049847728 0.0050970929 0.0053820000 0.0005870000 0.0029610000 0.0000020000 0.0000150000 0.0013750000 13246789 96830484 509673472 4.0665764809 3.9957628250 3.9481954575 63 2.4800000000 0.0050493903 0.0036200163 0.0050493903 0.0051360609 0.0054950000 0.0005870000 0.0028000000 0.0000160000 0.0000150000 0.0016230000 13249565 96830484 509673472 4.0733838081 3.9973392487 3.9481508732 64 2.5200000000 0.0049292170 0.0036404726 0.0050493903 0.0051098685 0.0049890000 0.0005580000 0.0027240000 0.0000020000 0.0000140000 0.0012980000 13252341 96830484 509673472 4.0755033493 3.9932091236 3.9442253113 65 2.5600000000 0.0049939137 0.0036612948 0.0050493903 0.0051007981 0.0079020000 0.0005640000 0.0045460000 0.0000150000 0.0000120000 0.0023520000 13261261 96830484 509673472 4.0765795708 3.9943478107 3.9443881512 66 2.6000000000 0.0051035760 0.0036831475 0.0051035760 0.0050627179 0.0043120000 0.0004910000 0.0023750000 0.0000010000 0.0000090000 0.0011410000 13276837 96830484 509673472 4.0738892555 3.9897964001 3.9425399303 67 2.6400000000 0.0051671360 0.0037052966 0.0051671360 0.0050949660 0.0048100000 0.0004900000 0.0026140000 0.0000120000 0.0000080000 0.0013940000 13279613 96830484 509673472 4.0741295815 3.9883854389 3.9407281876 68 2.6800000000 0.0052277381 0.0037276854 0.0052277381 0.0051670844 0.0056560000 0.0005850000 0.0032120000 0.0000020000 0.0000180000 0.0013660000 13282389 96830484 509673472 4.0792155266 3.9859161377 3.9403665066 69 2.7200000000 0.0050206436 0.0037464240 0.0052277381 0.0051839836 0.0064750000 0.0005850000 0.0029310000 0.0000170000 0.0000160000 0.0024450000 13285165 96830484 509673472 4.0803699493 3.9865522385 3.9391837120 70 2.7600000000 0.0051333038 0.0037662365 0.0052277381 0.0052326334 0.0051020000 0.0005820000 0.0026590000 0.0000020000 0.0000170000 0.0013620000 13287941 96830484 509673472 4.0830988884 3.9880127907 3.9385142326 71 2.8000000000 0.0052606803 0.0037872850 0.0052606803 0.0052792010 0.0055110000 0.0005830000 0.0027920000 0.0000150000 0.0000130000 0.0016180000 13290717 96830484 509673472 4.0858702660 3.9886751175 3.9367780685 72 2.8400000000 0.0051934486 0.0038068151 0.0052606803 0.0052985963 0.0048510000 0.0005820000 0.0023840000 0.0000020000 0.0000160000 0.0013720000 13293493 96830484 509673472 4.0874023438 3.9884274006 3.9358823299 73 2.8800000000 0.0051582404 0.0038253278 0.0052606803 0.0053403569 0.0054630000 0.0006320000 0.0023630000 0.0000170000 0.0000130000 0.0023110000 13296269 96830484 509673472 4.0898318291 3.9910426140 3.9336357117 74 2.9200000000 0.0052090851 0.0038440272 0.0052606803 0.0054580156 0.0035530000 0.0004070000 0.0020500000 0.0000000000 0.0000030000 0.0009780000 13299045 96830484 509673472 4.0917782784 3.9908561707 3.9306099415 75 2.9600000000 0.0053008753 0.0038634518 0.0053008753 0.0054998264 0.0042740000 0.0004120000 0.0024460000 0.0000040000 0.0000040000 0.0012590000 13301821 96830484 509673472 4.0974750519 3.9908180237 3.9291653633 76 3.0000000000 0.0052517937 0.0038817195 0.0053008753 0.0055203589 0.0037460000 0.0004360000 0.0020940000 0.0000010000 0.0000060000 0.0010210000 13304597 96830484 509673472 4.1008777618 3.9922816753 3.9274406433 77 3.0400000000 0.0051390142 0.0038980480 0.0053008753 0.0055429440 0.0049620000 0.0004440000 0.0022380000 0.0000070000 0.0000070000 0.0020080000 13307373 96830484 509673472 4.1035513878 3.9928734303 3.9264075756 78 3.0800000000 0.0050561829 0.0039128959 0.0053008753 0.0055142763 0.0043370000 0.0004620000 0.0025320000 0.0000010000 0.0000070000 0.0010760000 13310149 96830484 509673472 4.1065850258 3.9903488159 3.9228329659 79 3.1200000000 0.0049948804 0.0039265919 0.0053008753 0.0055356006 0.0041780000 0.0004620000 0.0021180000 0.0000070000 0.0000070000 0.0013200000 13312925 96830484 509673472 4.1102414131 3.9917397499 3.9223651886 80 3.1600000000 0.0050242441 0.0039403125 0.0053008753 0.0055195377 0.0043150000 0.0004610000 0.0025250000 0.0000010000 0.0000070000 0.0010570000 13315701 96830484 509673472 4.1140975952 3.9913780689 3.9194912910 81 3.2000000000 0.0050360658 0.0039538403 0.0053008753 0.0054983738 0.0056220000 0.0005110000 0.0021670000 0.0000130000 0.0000130000 0.0023930000 13318477 96830484 509673472 4.1197085381 3.9899454117 3.9178786278 82 3.2400000000 0.0050028237 0.0039666328 0.0053008753 0.0054713280 0.0050090000 0.0005720000 0.0025440000 0.0000010000 0.0000150000 0.0013240000 13321253 96830484 509673472 4.1236987114 3.9884841442 3.9155647755 83 3.2800000000 0.0050502997 0.0039796890 0.0053008753 0.0054582576 0.0053410000 0.0005770000 0.0026120000 0.0000140000 0.0000130000 0.0015840000 13324029 96830484 509673472 4.1256051064 3.9883275032 3.9134366512 84 3.3200000000 0.0050523491 0.0039924588 0.0053008753 0.0054344707 0.0047430000 0.0005760000 0.0022660000 0.0000020000 0.0000190000 0.0013330000 13326805 96830484 509673472 4.1318578720 3.9879920483 3.9106464386 85 3.3600000000 0.0050740265 0.0040051831 0.0053008753 0.0054048743 0.0060110000 0.0005990000 0.0024310000 0.0000140000 0.0000120000 0.0024000000 13329581 96830484 509673472 4.1423320770 3.9913799763 3.9105865955 86 3.4000000000 0.0051032361 0.0040179512 0.0053008753 0.0054186802 0.0051330000 0.0005640000 0.0026830000 0.0000010000 0.0000160000 0.0013260000 13332357 96830484 509673472 4.1449313164 3.9936683178 3.9082798958 87 3.4400000000 0.0051443763 0.0040308986 0.0053008753 0.0054135055 0.0054710000 0.0005840000 0.0026740000 0.0000130000 0.0000120000 0.0016240000 13335133 96830484 509673472 4.1471161842 3.9930384159 3.9054017067 88 3.4800000000 0.0051199845 0.0040432746 0.0053008753 0.0053885394 0.0048880000 0.0005640000 0.0024200000 0.0000020000 0.0000130000 0.0013340000 13337909 96830484 509673472 4.1525030136 3.9958424568 3.9047262669 89 3.5200000000 0.0051189894 0.0040553613 0.0053008753 0.0053714316 0.0062420000 0.0005760000 0.0026700000 0.0000150000 0.0000130000 0.0024030000 13340685 96830484 509673472 4.1555552483 3.9961588383 3.9035227299 90 3.5600000000 0.0053625298 0.0040698854 0.0053625298 0.0053447240 0.0053040000 0.0005640000 0.0028210000 0.0000020000 0.0000140000 0.0013390000 13343461 96830484 509673472 4.1587176323 3.9964623451 3.9019393921 91 3.6000000000 0.0054236664 0.0040847621 0.0054236664 0.0053805997 0.0055740000 0.0005620000 0.0028270000 0.0000140000 0.0000120000 0.0015840000 13346237 96830484 509673472 4.1651821136 3.9967248440 3.9009671211 92 3.6400000000 0.0053567928 0.0040985885 0.0054236664 0.0054535320 0.0050150000 0.0006050000 0.0023140000 0.0000020000 0.0000170000 0.0014080000 13349013 96830484 509673472 4.1743907928 3.9995663166 3.9010133743 93 3.6800000000 0.0053323833 0.0041118551 0.0054236664 0.0054676972 0.0061250000 0.0005890000 0.0023210000 0.0000160000 0.0000140000 0.0025310000 13351789 96830484 509673472 4.1824698448 4.0035905838 3.8995635509 94 3.7200000000 0.0052995379 0.0041244900 0.0054236664 0.0054446322 0.0043110000 0.0005030000 0.0021740000 0.0000010000 0.0000110000 0.0012000000 13354565 96830484 509673472 4.1907620430 4.0028114319 3.8969957829 95 3.7600000000 0.0052821054 0.0041366755 0.0054236664 0.0054173659 0.0046250000 0.0004670000 0.0024780000 0.0000070000 0.0000070000 0.0013460000 13357341 96830484 509673472 4.1968259811 4.0028252602 3.8945267200 96 3.8000000000 0.0053377687 0.0041491868 0.0054236664 0.0054022193 0.0040280000 0.0004690000 0.0020980000 0.0000010000 0.0000080000 0.0011080000 13360117 96830484 509673472 4.2043557167 4.0015521049 3.8925278187 97 3.8400000000 0.0053137112 0.0041611923 0.0054236664 0.0053763017 0.0050460000 0.0004730000 0.0021160000 0.0000080000 0.0000060000 0.0020950000 13362893 96830484 509673472 4.2122292519 4.0030913353 3.8894286156 98 3.8800000000 0.0053425021 0.0041732464 0.0054236664 0.0053495524 0.0044510000 0.0004720000 0.0025010000 0.0000010000 0.0000080000 0.0011190000 13365669 96830484 509673472 4.2207150459 4.0032205582 3.8886051178 99 3.9200000000 0.0053415089 0.0041850471 0.0054236664 0.0053596428 0.0053670000 0.0006000000 0.0023410000 0.0000160000 0.0000140000 0.0016940000 13368445 96830484 509673472 4.2289261818 4.0025749207 3.8866939545 100 3.9600000000 0.0053954637 0.0041971512 0.0054236664 0.0053345593 0.0054250000 0.0005890000 0.0027050000 0.0000020000 0.0000160000 0.0014220000 13371221 96830484 509673472 4.2365455627 4.0030832291 3.8862667084 101 4.0000000000 0.0053851311 0.0042089134 0.0054236664 0.0053239582 0.0066250000 0.0006000000 0.0027220000 0.0000150000 0.0000150000 0.0025600000 13373997 96830484 509673472 4.2451529503 4.0052204132 3.8849551678 102 4.0400000000 0.0055172932 0.0042217407 0.0055172932 0.0053347330 0.0054600000 0.0005930000 0.0027350000 0.0000010000 0.0000170000 0.0014150000 13376773 96830484 509673472 4.2498660088 4.0046539307 3.8828969002 103 4.0800000000 0.0055208160 0.0042343530 0.0055208160 0.0053094165 0.0050200000 0.0005020000 0.0025640000 0.0000100000 0.0000090000 0.0014640000 13379549 96830484 509673472 4.2579040527 4.0080900192 3.8836779594 104 4.1200000000 0.0055600191 0.0042470998 0.0055600191 0.0052847475 0.0054720000 0.0005910000 0.0027210000 0.0000010000 0.0000150000 0.0014230000 13382325 96830484 509673472 4.2683663368 4.0107359886 3.8829417229 105 4.1600000000 0.0055907466 0.0042598965 0.0055907466 0.0052770237 0.0061980000 0.0005880000 0.0023020000 0.0000150000 0.0000130000 0.0025410000 13385101 96830484 509673472 4.2749242783 4.0120902061 3.8827190399 106 4.2000000000 0.0056613046 0.0042731173 0.0056613046 0.0052891478 0.0055180000 0.0005860000 0.0027320000 0.0000020000 0.0000150000 0.0014210000 13387877 96830484 509673472 4.2819828987 4.0102591515 3.8801579475 107 4.2400000000 0.0055983281 0.0042855024 0.0056613046 0.0052665558 0.0050580000 0.0005010000 0.0025610000 0.0000100000 0.0000090000 0.0014850000 13390653 96830484 509673472 4.2898201942 4.0093169212 3.8789508343 108 4.2800000000 0.0056293453 0.0042979454 0.0056613046 0.0052505335 0.0065150000 0.0006140000 0.0033110000 0.0000030000 0.0000360000 0.0017820000 13393429 96830484 509673472 4.2985038757 4.0095157623 3.8771841526 109 4.3200000000 0.0055564600 0.0043094914 0.0056613046 0.0052305485 0.0067760000 0.0006370000 0.0027000000 0.0000150000 0.0000160000 0.0026740000 13396205 96830484 509673472 4.3155388832 4.0091133118 3.8746383190 110 4.3600000000 0.0057231062 0.0043223425 0.0057231062 0.0052279696 0.0042570000 0.0005040000 0.0020480000 0.0000010000 0.0000100000 0.0012040000 13398981 96830484 509673472 4.3276715279 4.0103607178 3.8738620281 111 4.4000000000 0.0057100547 0.0043348444 0.0057231062 0.0052045242 0.0057340000 0.0005900000 0.0027140000 0.0000150000 0.0000150000 0.0016580000 13401757 96830484 509673472 4.3374915123 4.0095014572 3.8721601963 112 4.4400000000 0.0056957221 0.0043469951 0.0057231062 0.0051894485 0.0050820000 0.0005860000 0.0023160000 0.0000020000 0.0000150000 0.0014180000 13404533 96830484 509673472 4.3432831764 4.0053067207 3.8694331646 113 4.4800000000 0.0056697726 0.0043587011 0.0057231062 0.0051662401 0.0066280000 0.0005890000 0.0027490000 0.0000170000 0.0000130000 0.0025140000 13407309 96830484 509673472 4.3522987366 4.0045900345 3.8687884808 114 4.5200000000 0.0057457257 0.0043708680 0.0057457257 0.0051499316 0.0054910000 0.0005840000 0.0027350000 0.0000020000 0.0000160000 0.0014070000 13410085 96830484 509673472 4.3631591797 4.0046868324 3.8679230213 115 4.5600000000 0.0056853173 0.0043822980 0.0057457257 0.0051369011 0.0055550000 0.0005840000 0.0025940000 0.0000150000 0.0000130000 0.0016500000 13412861 96830484 509673472 4.3731212616 4.0027031898 3.8666181564 116 4.6000000000 0.0056581139 0.0043932964 0.0057457257 0.0051167956 0.0054830000 0.0005860000 0.0027230000 0.0000020000 0.0000170000 0.0014010000 13415637 96830484 509673472 4.3810019493 3.9996702671 3.8650109768 117 4.6400000000 0.0056711594 0.0044042183 0.0057457257 0.0051209313 0.0055630000 0.0005100000 0.0023080000 0.0000100000 0.0000090000 0.0022190000 13418413 96830484 509673472 4.3884568214 3.9971811771 3.8638668060 118 4.6800000000 0.0056926785 0.0044151374 0.0057457257 0.0051342586 0.0051010000 0.0005890000 0.0023150000 0.0000020000 0.0000150000 0.0013900000 13421189 96830484 509673472 4.3975987434 3.9972615242 3.8635232449 119 4.7200000000 0.0056394818 0.0044254260 0.0057457257 0.0051730794 0.0057720000 0.0005850000 0.0027220000 0.0000150000 0.0000150000 0.0016620000 13423965 96830484 509673472 4.4117240906 3.9979023933 3.8653900623 120 4.7600000000 0.0057481648 0.0044364489 0.0057481648 0.0051516670 0.0055150000 0.0005830000 0.0027150000 0.0000010000 0.0000150000 0.0014120000 13426741 96830484 509673472 4.4229965210 3.9998998642 3.8668017387 121 4.8000000000 0.0057021701 0.0044469094 0.0057481648 0.0051474452 0.0066390000 0.0005860000 0.0027420000 0.0000150000 0.0000130000 0.0025000000 13429517 96830484 509673472 4.4315028191 3.9984936714 3.8652749062 122 4.8400000000 0.0057756132 0.0044578004 0.0057756132 0.0051462426 0.0049380000 0.0005890000 0.0023110000 0.0000020000 0.0000150000 0.0013980000 13432293 96830484 509673472 4.4405755997 3.9990479946 3.8647367954 123 4.8800000000 0.0057306448 0.0044681487 0.0057756132 0.0051260402 0.0058150000 0.0005730000 0.0027410000 0.0000150000 0.0000130000 0.0016750000 13435069 96830484 509673472 4.4518437386 4.0015034676 3.8667614460 124 4.9200000000 0.0058429851 0.0044792361 0.0058429851 0.0051068286 0.0055660000 0.0005890000 0.0027460000 0.0000020000 0.0000150000 0.0014030000 13437845 96830484 509673472 4.4582505226 4.0030860901 3.8700125217 125 4.9600000000 0.0057804715 0.0044896460 0.0058429851 0.0050988183 0.0067020000 0.0005860000 0.0027570000 0.0000150000 0.0000150000 0.0025160000 13440621 96830484 509673472 4.4617042542 4.0026488304 3.8714387417 126 5.0000000000 0.0059292894 0.0045010717 0.0059292894 0.0050851563 0.0044600000 0.0005010000 0.0022020000 0.0000020000 0.0000110000 0.0012030000 13443397 96830484 509673472 4.4711313248 4.0028533936 3.8731281757 127 5.0400000000 0.0059257317 0.0045122895 0.0059292894 0.0050678512 0.0060030000 0.0005880000 0.0028850000 0.0000150000 0.0000130000 0.0016640000 13446173 96830484 509673472 4.4813003540 4.0027108192 3.8752965927 128 5.0800000000 0.0059485226 0.0045235101 0.0059485226 0.0050619122 0.0055520000 0.0005830000 0.0027150000 0.0000010000 0.0000160000 0.0014100000 13448949 96830484 509673472 4.4930901527 4.0041360855 3.8786749840 129 5.1200000000 0.0059163547 0.0045343073 0.0059485226 0.0050541966 0.0071340000 0.0005850000 0.0031500000 0.0000160000 0.0000140000 0.0025110000 13464013 96830484 509673472 4.5041437149 4.0054841042 3.8822398186 130 5.1600000000 0.0060301078 0.0045458135 0.0060301078 0.0050363775 0.0056090000 0.0005880000 0.0027510000 0.0000020000 0.0000150000 0.0014000000 13492389 96830484 509673472 4.5108394623 4.0064253807 3.8846948147 131 5.2000000000 0.0060351416 0.0045571824 0.0060351416 0.0050720316 0.0051800000 0.0005020000 0.0026170000 0.0000100000 0.0000090000 0.0014640000 13495165 96830484 509673472 4.5175070763 4.0055236816 3.8878247738 132 5.2400000000 0.0059441612 0.0045676898 0.0060351416 0.0050576404 0.0057960000 0.0005860000 0.0029150000 0.0000020000 0.0000150000 0.0013960000 13497941 96830484 509673472 4.5282158852 4.0059981346 3.8916349411 133 5.2800000000 0.0058937715 0.0045776604 0.0060351416 0.0050385839 0.0067250000 0.0005860000 0.0027390000 0.0000150000 0.0000140000 0.0024940000 13500717 96830484 509673472 4.5387835503 4.0069069862 3.8960566521 134 5.3200000000 0.0059468551 0.0045878782 0.0060351416 0.0050857909 0.0049160000 0.0005010000 0.0026080000 0.0000010000 0.0000110000 0.0012110000 13503493 96830484 509673472 4.5474786758 4.0064592361 3.8986999989 135 5.3600000000 0.0060005723 0.0045983426 0.0060351416 0.0050998566 0.0055020000 0.0005860000 0.0023290000 0.0000150000 0.0000140000 0.0016700000 13506269 96830484 509673472 4.5572004318 4.0076398849 3.9021449089 136 5.4000000000 0.0060031754 0.0046086723 0.0060351416 0.0051264354 0.0058190000 0.0006020000 0.0027790000 0.0000020000 0.0000150000 0.0014300000 13509045 96830484 509673472 4.5713090897 4.0152654648 3.9084048271 137 5.4400000000 0.0059785573 0.0046186715 0.0060351416 0.0051227195 0.0065550000 0.0006580000 0.0023470000 0.0000150000 0.0000140000 0.0025160000 13511821 96830484 509673472 4.5764145851 4.0192475319 3.9122540951 138 5.4800000000 0.0060741981 0.0046292188 0.0060741981 0.0051682085 0.0058670000 0.0006260000 0.0028870000 0.0000010000 0.0000150000 0.0014260000 13514597 96830484 509673472 4.5801630020 4.0180754662 3.9150266647 139 5.5200000000 0.0060774717 0.0046396378 0.0060774717 0.0051496757 0.0052130000 0.0005030000 0.0026160000 0.0000100000 0.0000090000 0.0014630000 13517373 96830484 509673472 4.5890240669 4.0188131332 3.9199883938 140 5.5600000000 0.0061399625 0.0046503544 0.0061399625 0.0051333019 0.0056980000 0.0005850000 0.0027590000 0.0000020000 0.0000170000 0.0014170000 13520149 96830484 509673472 4.5973982811 4.0202012062 3.9251387119 141 5.6000000000 0.0061036120 0.0046606612 0.0061399625 0.0051152475 0.0059760000 0.0005000000 0.0026170000 0.0000100000 0.0000090000 0.0022180000 13522925 96830484 509673472 4.6060738564 4.0210466385 3.9299621582 142 5.6400000000 0.0060702055 0.0046705876 0.0061399625 0.0051004597 0.0049520000 0.0005020000 0.0026230000 0.0000010000 0.0000100000 0.0011970000 13525701 96830484 509673472 4.6169919968 4.0214347839 3.9351372719 143 5.6800000000 0.0060755364 0.0046804124 0.0061399625 0.0050906348 0.0052260000 0.0005000000 0.0026250000 0.0000100000 0.0000090000 0.0014580000 13528477 96830484 509673472 4.6259331703 4.0235409737 3.9404466152 144 5.7200000000 0.0060903504 0.0046902037 0.0061399625 0.0051097187 0.0049500000 0.0004980000 0.0026240000 0.0000010000 0.0000120000 0.0011920000 13531253 96830484 509673472 4.6319580078 4.0235047340 3.9448897839 145 5.7600000000 0.0060698800 0.0046997187 0.0061399625 0.0050969557 0.0063970000 0.0005850000 0.0023510000 0.0000150000 0.0000140000 0.0024680000 13534029 96830484 509673472 4.6399068832 4.0239834785 3.9501924515 146 5.8000000000 0.0061015612 0.0047093203 0.0061399625 0.0050819629 0.0054390000 0.0005870000 0.0025030000 0.0000010000 0.0000150000 0.0013820000 13536805 96830484 509673472 4.6496663094 4.0256071091 3.9563727379 147 5.8400000000 0.0060024480 0.0047181171 0.0061399625 0.0050647372 0.0056700000 0.0006030000 0.0023710000 0.0000170000 0.0000130000 0.0016510000 13539581 96830484 509673472 4.6589894295 4.0294914246 3.9624927044 148 5.8800000000 0.0061068530 0.0047275005 0.0061399625 0.0050881850 0.0050620000 0.0005110000 0.0026480000 0.0000010000 0.0000100000 0.0012050000 13542357 96830484 509673472 4.6632938385 4.0291781425 3.9671697617 149 5.9200000000 0.0061568213 0.0047370932 0.0061568213 0.0050732408 0.0064850000 0.0005910000 0.0023620000 0.0000150000 0.0000140000 0.0024910000 13545133 96830484 509673472 4.6691074371 4.0286145210 3.9715301991 150 5.9600000000 0.0061067333 0.0047462242 0.0061568213 0.0050793721 0.0049600000 0.0004980000 0.0025780000 0.0000010000 0.0000120000 0.0011960000 13547909 96830484 509673472 4.6770424843 4.0318398476 3.9775445461 151 6.0000000000 0.0060392744 0.0047547874 0.0061568213 0.0050762045 0.0060860000 0.0005820000 0.0028100000 0.0000150000 0.0000160000 0.0016480000 13550685 96830484 509673472 4.6848597527 4.0338845253 3.9822423458 152 6.0400000000 0.0060456088 0.0047632796 0.0061568213 0.0050834153 0.0053840000 0.0005860000 0.0023720000 0.0000020000 0.0000150000 0.0014240000 13553461 96830484 509673472 4.6980733871 4.0334734917 3.9913339615 153 6.0800000000 0.0060496419 0.0047716872 0.0061568213 0.0051024568 0.0061550000 0.0005000000 0.0027940000 0.0000100000 0.0000090000 0.0021620000 13556237 96830484 509673472 4.7058396339 4.0345540047 3.9967098236 154 6.1200000000 0.0060308068 0.0047798633 0.0061568213 0.0050861196 0.0062520000 0.0005850000 0.0032690000 0.0000010000 0.0000150000 0.0013780000 13559013 96830484 509673472 4.7120251656 4.0361852646 4.0017490387 155 6.1600000000 0.0060126614 0.0047878169 0.0061568213 0.0050857326 0.0050110000 0.0004990000 0.0023750000 0.0000110000 0.0000090000 0.0014520000 13561789 96830484 509673472 4.7163062096 4.0360522270 4.0059556961 156 6.2000000000 0.0060215620 0.0047957255 0.0061568213 0.0050983575 0.0045230000 0.0004670000 0.0024570000 0.0000010000 0.0000070000 0.0010820000 13564565 96830484 509673472 4.7250094414 4.0375323296 4.0115647316 157 6.2400000000 0.0060290159 0.0048035809 0.0061568213 0.0051088336 0.0060460000 0.0004710000 0.0029930000 0.0000070000 0.0000070000 0.0020330000 13567341 96830484 509673472 4.7316803932 4.0387496948 4.0176057816 158 6.2800000000 0.0060451948 0.0048114392 0.0061568213 0.0051183279 0.0058920000 0.0006030000 0.0027960000 0.0000010000 0.0000160000 0.0014060000 13570117 96830484 509673472 4.7362785339 4.0396814346 4.0233764648 159 6.3200000000 0.0060289092 0.0048190962 0.0061568213 0.0051478166 0.0061630000 0.0005880000 0.0028210000 0.0000150000 0.0000150000 0.0016400000 13572893 96830484 509673472 4.7436199188 4.0417766571 4.0302033424 160 6.3600000000 0.0059624910 0.0048262424 0.0061568213 0.0052033920 0.0055750000 0.0005720000 0.0028290000 0.0000010000 0.0000150000 0.0013840000 13575669 96830484 509673472 4.7569532394 4.0455675125 4.0445909500 161 6.4000000000 0.0060306131 0.0048337230 0.0061568213 0.0052265624 0.0071280000 0.0005880000 0.0029590000 0.0000150000 0.0000140000 0.0024600000 13578445 96830484 509673472 4.7611370087 4.0478291512 4.0513181686 162 6.4400000000 0.0059305062 0.0048404933 0.0061568213 0.0052164635 0.0060440000 0.0005030000 0.0038790000 0.0000010000 0.0000070000 0.0010920000 13581221 96830484 509673472 4.7662162781 4.0501766205 4.0590505600 163 6.4800000000 0.0058885235 0.0048469229 0.0061568213 0.0052251223 0.0043200000 0.0004430000 0.0021540000 0.0000060000 0.0000050000 0.0012700000 13583997 96830484 509673472 4.7727484703 4.0508718491 4.0670790672 164 6.5200000000 0.0058238208 0.0048528796 0.0061568213 0.0052356355 0.0059450000 0.0006070000 0.0028350000 0.0000020000 0.0000150000 0.0013730000 13586773 96830484 509673472 4.7805190086 4.0506696701 4.0751361847 165 6.5600000000 0.0058313785 0.0048588099 0.0061568213 0.0052419714 0.0071800000 0.0006030000 0.0032510000 0.0000150000 0.0000140000 0.0024390000 13589549 96830484 509673472 4.7891559601 4.0535712242 4.0839734077 166 6.6000000000 0.0058083343 0.0048645299 0.0061568213 0.0052641220 0.0049810000 0.0005100000 0.0028110000 0.0000010000 0.0000100000 0.0010990000 13592325 96830484 509673472 4.7971386909 4.0574984550 4.0930414200 167 6.6400000000 0.0057805753 0.0048700152 0.0061568213 0.0053156350 0.0058200000 0.0006010000 0.0024210000 0.0000170000 0.0000140000 0.0016390000 13595101 96830484 509673472 4.8014883995 4.0593223572 4.1012320518 168 6.6800000000 0.0057390872 0.0048751883 0.0061568213 0.0053192715 0.0051670000 0.0005100000 0.0026960000 0.0000010000 0.0000100000 0.0011820000 13597877 96830484 509673472 4.8085737228 4.0617160797 4.1099843979 169 6.7200000000 0.0057138256 0.0048801506 0.0061568213 0.0053131303 0.0061200000 0.0005220000 0.0026680000 0.0000120000 0.0000090000 0.0021500000 13600653 96830484 509673472 4.8173165321 4.0663099289 4.1206231117 170 6.7600000000 0.0057234843 0.0048851114 0.0061568213 0.0053266801 0.0061070000 0.0005910000 0.0029650000 0.0000020000 0.0000150000 0.0013770000 13603429 96830484 509673472 4.8230280876 4.0676450729 4.1288962364 171 6.8000000000 0.0056701880 0.0048897025 0.0061568213 0.0053111776 0.0063870000 0.0005860000 0.0030150000 0.0000170000 0.0000140000 0.0016220000 13606205 96830484 509673472 4.8323884010 4.0704751015 4.1391472816 172 6.8400000000 0.0056632604 0.0048941999 0.0061568213 0.0052957344 0.0049450000 0.0006100000 0.0022300000 0.0000020000 0.0000150000 0.0013180000 13608981 96830484 509673472 4.8404426575 4.0731782913 4.1494398117 173 6.8800000000 0.0056481659 0.0048985581 0.0061568213 0.0052809181 0.0070670000 0.0006040000 0.0028140000 0.0000160000 0.0000160000 0.0024180000 13611757 96830484 509673472 4.8442869186 4.0731334686 4.1566572189 174 6.9200000000 0.0056729857 0.0049030088 0.0061568213 0.0052740755 0.0051580000 0.0005060000 0.0026880000 0.0000010000 0.0000100000 0.0011720000 13614533 96830484 509673472 4.8527302742 4.0753993988 4.1664061546 175 6.9600000000 0.0056423256 0.0049072335 0.0061568213 0.0052618838 0.0051160000 0.0004660000 0.0027240000 0.0000080000 0.0000070000 0.0013280000 13617309 96830484 509673472 4.8624191284 4.0791654587 4.1769003868 176 7.0000000000 0.0056823636 0.0049116377 0.0061568213 0.0052470233 0.0045780000 0.0004670000 0.0024470000 0.0000010000 0.0000070000 0.0010680000 13620085 96830484 509673472 4.8692708015 4.0817103386 4.1868515015 177 7.0400000000 0.0056027072 0.0049155420 0.0061568213 0.0052878175 0.0069880000 0.0005730000 0.0028140000 0.0000160000 0.0000140000 0.0023940000 13622861 96830484 509673472 4.8739581108 4.0814642906 4.1950302124 178 7.0800000000 0.0055418434 0.0049190605 0.0061568213 0.0053154560 0.0059450000 0.0005910000 0.0027920000 0.0000020000 0.0000150000 0.0013490000 13625637 96830484 509673472 4.8782382011 4.0814371109 4.2028570175 179 7.1200000000 0.0055289320 0.0049224677 0.0061568213 0.0053010423 0.0063920000 0.0005880000 0.0029830000 0.0000150000 0.0000140000 0.0016030000 13628413 96830484 509673472 4.8843026161 4.0839509964 4.2120461464 180 7.1600000000 0.0055056321 0.0049257075 0.0061568213 0.0052913883 0.0059890000 0.0005870000 0.0028240000 0.0000020000 0.0000150000 0.0013660000 13631189 96830484 509673472 4.8906316757 4.0852222443 4.2211475372 181 7.2000000000 0.0055047660 0.0049289067 0.0061568213 0.0052769548 0.0059880000 0.0005000000 0.0026610000 0.0000100000 0.0000100000 0.0020560000 13633965 96830484 509673472 4.8944182396 4.0859928131 4.2299909592 182 7.2400000000 0.0055230460 0.0049321712 0.0061568213 0.0052633292 0.0059730000 0.0005860000 0.0028180000 0.0000020000 0.0000150000 0.0013390000 13636741 96830484 509673472 4.9002633095 4.0878529549 4.2386074066 183 7.2800000000 0.0054398915 0.0049349456 0.0061568213 0.0052490929 0.0062120000 0.0005880000 0.0028000000 0.0000140000 0.0000140000 0.0015770000 13639517 96830484 509673472 4.9055233002 4.0899486542 4.2479658127 184 7.3200000000 0.0053970716 0.0049374572 0.0061568213 0.0052415103 0.0059860000 0.0005900000 0.0028200000 0.0000020000 0.0000150000 0.0013390000 13642293 96830484 509673472 4.9109892845 4.0905742645 4.2555203438 185 7.3600000000 0.0054233349 0.0049400835 0.0061568213 0.0052320774 0.0061130000 0.0005010000 0.0028120000 0.0000120000 0.0000090000 0.0020780000 13645069 96830484 509673472 4.9147005081 4.0901789665 4.2616567612 186 7.4000000000 0.0054242057 0.0049426863 0.0061568213 0.0052189155 0.0057430000 0.0005880000 0.0025520000 0.0000020000 0.0000150000 0.0013380000 13647845 96830484 509673472 4.9201254845 4.0918126106 4.2710456848 187 7.4400000000 0.0053489101 0.0049448587 0.0061568213 0.0052187645 0.0053210000 0.0005040000 0.0026120000 0.0000100000 0.0000090000 0.0013550000 13650621 96830484 509673472 4.9250741005 4.0927567482 4.2783312798 188 7.4800000000 0.0053272285 0.0049468925 0.0061568213 0.0052054803 0.0057010000 0.0005020000 0.0032200000 0.0000010000 0.0000110000 0.0011260000 13653397 96830484 509673472 4.9292163849 4.0936374664 4.2850275040 189 7.5200000000 0.0053219730 0.0049488771 0.0061568213 0.0051924764 0.0070290000 0.0005840000 0.0028200000 0.0000150000 0.0000130000 0.0023160000 13656173 96830484 509673472 4.9323048592 4.0935063362 4.2914452553 190 7.5600000000 0.0052836197 0.0049506389 0.0061568213 0.0051839765 0.0060400000 0.0005840000 0.0028350000 0.0000020000 0.0000170000 0.0013260000 13658949 96830484 509673472 4.9374561310 4.0942311287 4.2994856834 191 7.6000000000 0.0052189911 0.0049520439 0.0061568213 0.0051748493 0.0064090000 0.0005890000 0.0029790000 0.0000150000 0.0000150000 0.0015380000 13661725 96830484 509673472 4.9411687851 4.0960941315 4.3077344894 192 7.6400000000 0.0052528535 0.0049536106 0.0061568213 0.0051618631 0.0060870000 0.0005920000 0.0033910000 0.0000020000 0.0000160000 0.0012200000 13664501 96830484 509673472 4.9439325333 4.0977220535 4.3161888123 193 7.6800000000 0.0051764259 0.0049547651 0.0061568213 0.0051497532 0.0061950000 0.0005020000 0.0028250000 0.0000110000 0.0000090000 0.0019860000 13667277 96830484 509673472 4.9493484497 4.0995397568 4.3316073418 194 7.7200000000 0.0052070981 0.0049560658 0.0061568213 0.0051364200 0.0061400000 0.0005870000 0.0029600000 0.0000020000 0.0000150000 0.0012940000 13670053 96830484 509673472 4.9530463219 4.1020278931 4.3403635025 195 7.7600000000 0.0050952937 0.0049567797 0.0061568213 0.0051233772 0.0064200000 0.0005870000 0.0029710000 0.0000170000 0.0000130000 0.0015210000 13672829 96830484 509673472 4.9578208923 4.1034336090 4.3589267731 196 7.8000000000 0.0052108061 0.0049580758 0.0061568213 0.0051170834 0.0051370000 0.0005590000 0.0026670000 0.0000020000 0.0000110000 0.0010750000 13675605 96830484 509673472 4.9581122398 4.1025881767 4.3676319122 197 7.8400000000 0.0051971823 0.0049592895 0.0061568213 0.0051052797 0.0060760000 0.0005430000 0.0026510000 0.0000100000 0.0000090000 0.0019890000 13678381 96830484 509673472 4.9607620239 4.1033349037 4.3778362274 198 7.8800000000 0.0050707450 0.0049598524 0.0061568213 0.0050924974 0.0060090000 0.0005950000 0.0028120000 0.0000020000 0.0000160000 0.0012630000 13681157 96830484 509673472 4.9627189636 4.1039161682 4.3887743950 199 7.9200000000 0.0051643429 0.0049608800 0.0061568213 0.0050872989 0.0066170000 0.0005840000 0.0032220000 0.0000150000 0.0000130000 0.0014800000 13683933 96830484 509673472 4.9628829956 4.1031384468 4.3988299370 200 7.9600000000 0.0051625203 0.0049618882 0.0061568213 0.0050765413 0.0064190000 0.0005830000 0.0032490000 0.0000020000 0.0000170000 0.0012650000 13686709 96830484 509673472 4.9650702477 4.1039562225 4.4098033905 201 8.0000000000 0.0050499458 0.0049623263 0.0061568213 0.0050646795 0.0061120000 0.0005000000 0.0028020000 0.0000110000 0.0000100000 0.0019200000 13689485 96830484 509673472 4.9673681259 4.1037187576 4.4213147163 202 8.0400000000 0.0050647617 0.0049628334 0.0061568213 0.0050527639 0.0059690000 0.0005850000 0.0027950000 0.0000010000 0.0000150000 0.0012600000 13692261 96830484 509673472 4.9671077728 4.1040964127 4.4316306114 203 8.0800000000 0.0050757341 0.0049633896 0.0061568213 0.0050405678 0.0061870000 0.0005900000 0.0027880000 0.0000160000 0.0000140000 0.0014670000 13695037 96830484 509673472 4.9669981003 4.1043624878 4.4422888756 204 8.1200000000 0.0051359506 0.0049642355 0.0061568213 0.0050315638 0.0052710000 0.0005030000 0.0028060000 0.0000020000 0.0000100000 0.0010620000 13697813 96830484 509673472 4.9671969414 4.1058206558 4.4529976845 205 8.1600000000 0.0052336426 0.0049655497 0.0061568213 0.0050437327 0.0071310000 0.0005870000 0.0029820000 0.0000170000 0.0000130000 0.0022050000 13700589 96830484 509673472 4.9684801102 4.1076216698 4.4646973610 206 8.1999999990 0.0051850323 0.0049666151 0.0061568213 0.0050510482 0.0055050000 0.0005880000 0.0029540000 0.0000020000 0.0000100000 0.0010600000 13703365 96830484 509673472 4.9691433907 4.1096730232 4.4768490791 207 8.2400000000 0.0051173810 0.0049673435 0.0061568213 0.0050462354 0.0066440000 0.0005870000 0.0032350000 0.0000150000 0.0000140000 0.0014570000 13706141 96830484 509673472 4.9699001312 4.1120605469 4.4897031784 208 8.2799999990 0.0051594502 0.0049682670 0.0061568213 0.0050472493 0.0051100000 0.0005030000 0.0026550000 0.0000020000 0.0000110000 0.0010480000 13708917 96830484 509673472 4.9695887566 4.1151719093 4.5014500618 209 8.3200000000 0.0052337651 0.0049695374 0.0061568213 0.0050413636 0.0069580000 0.0005730000 0.0028440000 0.0000150000 0.0000140000 0.0021590000 13711693 96830484 509673472 4.9698185921 4.1167240143 4.5130949020 210 8.3599999990 0.0051047611 0.0049701813 0.0061568213 0.0050301895 0.0061320000 0.0006030000 0.0028150000 0.0000030000 0.0000160000 0.0012500000 13714469 96830484 509673472 4.9704208374 4.1181478500 4.5251731873 211 8.4000000000 0.0051343990 0.0049709596 0.0061568213 0.0050264616 0.0059130000 0.0006050000 0.0023810000 0.0000170000 0.0000140000 0.0014670000 13717245 96830484 509673472 4.9708418846 4.1203451157 4.5375833511 212 8.4399999990 0.0050894739 0.0049715186 0.0061568213 0.0050190294 0.0060930000 0.0005900000 0.0028160000 0.0000020000 0.0000150000 0.0012640000 13720021 96830484 509673472 4.9698095322 4.1221055984 4.5499749184 213 8.4800000000 0.0051316773 0.0049722705 0.0061568213 0.0050112140 0.0069660000 0.0005910000 0.0028040000 0.0000150000 0.0000140000 0.0021710000 13722797 96830484 509673472 4.9686203003 4.1240663528 4.5614809990 214 8.5200000000 0.0052519762 0.0049735776 0.0061568213 0.0050078932 0.0060390000 0.0005900000 0.0028100000 0.0000020000 0.0000150000 0.0012430000 13725573 96830484 509673472 4.9680514336 4.1262903214 4.5727910995 215 8.5600000000 0.0052545448 0.0049748844 0.0061568213 0.0049988730 0.0062270000 0.0005020000 0.0035080000 0.0000100000 0.0000100000 0.0012580000 13728349 96830484 509673472 4.9682369232 4.1294765472 4.5849390030 216 8.6000000000 0.0050322511 0.0049751500 0.0061568213 0.0049909416 0.0062110000 0.0005890000 0.0029660000 0.0000020000 0.0000170000 0.0012360000 13731125 96830484 509673472 4.9686799049 4.1316208839 4.5973057747 217 8.6400000000 0.0050842641 0.0049756528 0.0061568213 0.0049841532 0.0071510000 0.0005870000 0.0029760000 0.0000140000 0.0000130000 0.0021450000 13733901 96830484 509673472 4.9675607681 4.1332802773 4.6082091331 218 8.6800000000 0.0051133153 0.0049762843 0.0061568213 0.0049785319 0.0055810000 0.0005050000 0.0030810000 0.0000010000 0.0000100000 0.0010350000 13736597 96830484 509673472 4.9659609795 4.1347451210 4.6188659668 219 8.7200000000 0.0051957574 0.0049772864 0.0061568213 0.0049718305 0.0066800000 0.0005880000 0.0032520000 0.0000150000 0.0000130000 0.0014390000 13739373 96830484 509673472 4.9632697105 4.1358246803 4.6292138100 220 8.7600000000 0.0052111270 0.0049783494 0.0061568213 0.0049622261 0.0052280000 0.0005120000 0.0026620000 0.0000010000 0.0000110000 0.0010520000 13742149 96830484 509673472 4.9599685669 4.1361312866 4.6387791634 221 8.8000000000 0.0051866090 0.0049792917 0.0061568213 0.0049514850 0.0055750000 0.0004740000 0.0025890000 0.0000080000 0.0000070000 0.0017460000 13744925 96830484 509673472 4.9603199959 4.1384315491 4.6508617401 222 8.8400000000 0.0050666304 0.0049796851 0.0061568213 0.0049427668 0.0078910000 0.0005900000 0.0045050000 0.0000020000 0.0000140000 0.0012460000 13747701 96830484 509673472 4.9586420059 4.1390399933 4.6615967751 223 8.8800000000 0.0050455569 0.0049799805 0.0061568213 0.0049316597 0.0052050000 0.0005730000 0.0026440000 0.0000080000 0.0000080000 0.0011470000 13750477 96830484 509673472 4.9558796883 4.1389951706 4.6711897850 224 8.9200000000 0.0049588266 0.0049798861 0.0061568213 0.0049216808 0.0060670000 0.0006300000 0.0027540000 0.0000010000 0.0000160000 0.0012090000 13753253 96830484 509673472 4.9541454315 4.1395349503 4.6816139221 225 8.9600000000 0.0048469836 0.0049792954 0.0061568213 0.0049138925 0.0054310000 0.0004590000 0.0030330000 0.0000040000 0.0000040000 0.0015990000 13756109 96830484 509673472 4.9538526535 4.1410932541 4.6929483414 226 9.0000000000 0.0049809492 0.0049793027 0.0061568213 0.0049037350 0.0060780000 0.0005970000 0.0028270000 0.0000020000 0.0000150000 0.0012310000 13758885 96830484 509673472 4.9550690651 4.1433954239 4.7148227692 227 9.0400000000 0.0048238500 0.0049786179 0.0061568213 0.0048929651 0.0062770000 0.0005880000 0.0028180000 0.0000160000 0.0000140000 0.0014300000 13761661 96830484 509673472 4.9551715851 4.1454553604 4.7255783081 228 9.0800000000 0.0049536647 0.0049785085 0.0061568213 0.0048842394 0.0056050000 0.0005880000 0.0023650000 0.0000020000 0.0000140000 0.0012200000 13764437 96830484 509673472 4.9529194832 4.1470074654 4.7345767021 229 9.1200000000 0.0048602149 0.0049779919 0.0061568213 0.0048952783 0.0057450000 0.0005010000 0.0026570000 0.0000100000 0.0000090000 0.0018570000 13767213 96830484 509673472 4.9530963898 4.1487202644 4.7457385063 230 9.1600000000 0.0047461768 0.0049769840 0.0061568213 0.0048920475 0.0058230000 0.0005850000 0.0025440000 0.0000010000 0.0000160000 0.0012520000 13769989 96830484 509673472 4.9536833763 4.1500377655 4.7559862137 231 9.2000000000 0.0046593100 0.0049756088 0.0061568213 0.0048869298 0.0068760000 0.0006020000 0.0034040000 0.0000150000 0.0000140000 0.0014140000 13772765 96830484 509673472 4.9529786110 4.1512827873 4.7746334076 232 9.2400000000 0.0046853125 0.0049743575 0.0061568213 0.0048799683 0.0060740000 0.0005890000 0.0028180000 0.0000010000 0.0000170000 0.0012170000 13775541 96830484 509673472 4.9537668228 4.1536684036 4.7866196632 233 9.2800000000 0.0045911544 0.0049727129 0.0061568213 0.0048814516 0.0075990000 0.0006000000 0.0034070000 0.0000160000 0.0000130000 0.0021120000 13778317 96830484 509673472 4.9543766975 4.1562628746 4.7987074852 234 9.3200000000 0.0047239978 0.0049716500 0.0061568213 0.0048798862 0.0063870000 0.0005970000 0.0030930000 0.0000020000 0.0000160000 0.0012200000 13781093 96830484 509673472 4.9536404610 4.1589183807 4.8094420433 235 9.3600000000 0.0045477897 0.0049698463 0.0061568213 0.0048782891 0.0059670000 0.0005180000 0.0032210000 0.0000110000 0.0000100000 0.0012270000 13783869 96830484 509673472 4.9533538818 4.1601018906 4.8202762604 236 9.4000000000 0.0046789697 0.0049686138 0.0061568213 0.0048726270 0.0051390000 0.0004700000 0.0030080000 0.0000010000 0.0000080000 0.0009100000 13786645 96830484 509673472 4.9549756050 4.1608595848 4.8297848701 237 9.4400000000 0.0046691587 0.0049673503 0.0061568213 0.0048806888 0.0056160000 0.0004720000 0.0027280000 0.0000080000 0.0000080000 0.0016550000 13789421 96830484 509673472 4.9556875229 4.1634902954 4.8408379555 238 9.4800000000 0.0046164813 0.0049658760 0.0061568213 0.0048786050 0.0048730000 0.0004730000 0.0027370000 0.0000010000 0.0000080000 0.0009040000 13792197 96830484 509673472 4.9564762115 4.1650266647 4.8516426086 239 9.5200000000 0.0046848543 0.0049647002 0.0061568213 0.0048844772 0.0067460000 0.0005910000 0.0032350000 0.0000150000 0.0000150000 0.0014020000 13794973 96830484 509673472 4.9583868980 4.1672606468 4.8623967171 240 9.5600000000 0.0045694984 0.0049630535 0.0061568213 0.0048828300 0.0056720000 0.0005860000 0.0023870000 0.0000020000 0.0000140000 0.0012030000 13797749 96830484 509673472 4.9580144882 4.1680598259 4.8719301224 241 9.6000000000 0.0045336755 0.0049612719 0.0061568213 0.0048726901 0.0077740000 0.0005840000 0.0036070000 0.0000150000 0.0000140000 0.0020600000 13800525 96830484 509673472 4.9562830925 4.1695141792 4.8816843033 242 9.6400000000 0.0044498020 0.0049591584 0.0061568213 0.0048759728 0.0056420000 0.0005830000 0.0029560000 0.0000020000 0.0000140000 0.0010870000 13803301 96830484 509673472 4.9574756622 4.1718831062 4.8938455582 243 9.6800000000 0.0044997297 0.0049572677 0.0061568213 0.0048667167 0.0053690000 0.0005020000 0.0026510000 0.0000110000 0.0000090000 0.0011920000 13806077 96830484 509673472 4.9604816437 4.1743707657 4.9075245857 244 9.7200000000 0.0043569133 0.0049548072 0.0061568213 0.0048567089 0.0048520000 0.0004620000 0.0027300000 0.0000010000 0.0000090000 0.0008970000 13808853 96830484 509673472 4.9617609978 4.1779823303 4.9195818901 245 9.7600000000 0.0044651898 0.0049528088 0.0061568213 0.0048485457 0.0054360000 0.0004640000 0.0025820000 0.0000070000 0.0000060000 0.0016210000 13811629 96830484 509673472 4.9618325233 4.1787681580 4.9291963577 246 9.8000000000 0.0042485194 0.0049499458 0.0061568213 0.0048386741 0.0059760000 0.0005830000 0.0027370000 0.0000010000 0.0000150000 0.0011640000 13814405 96830484 509673472 4.9632921219 4.1814455986 4.9409284592 247 9.8400000000 0.0042999312 0.0049473142 0.0061568213 0.0048290526 0.0067020000 0.0005830000 0.0032330000 0.0000150000 0.0000130000 0.0013720000 13817181 96830484 509673472 4.9635925293 4.1840600967 4.9526166916 248 9.8800000000 0.0043993494 0.0049451047 0.0061568213 0.0048240842 0.0057940000 0.0005830000 0.0025340000 0.0000010000 0.0000150000 0.0011620000 13819957 96830484 509673472 4.9636201859 4.1872291565 4.9626722336 249 9.9200000000 0.0041791941 0.0049420287 0.0061568213 0.0048144787 0.0060360000 0.0004990000 0.0027950000 0.0000100000 0.0000090000 0.0017210000 13822733 96830484 509673472 4.9648604393 4.1882309914 4.9734330177 250 9.9600000000 0.0042670514 0.0049393288 0.0061568213 0.0048051958 0.0044080000 0.0004650000 0.0023200000 0.0000010000 0.0000070000 0.0008670000 13825509 96830484 509673472 4.9655241966 4.1900911331 4.9843182564 251 10.0000000000 0.0041738809 0.0049362792 0.0061568213 0.0047974582 0.0068690000 0.0005880000 0.0033800000 0.0000150000 0.0000130000 0.0013690000 13828285 96830484 509673472 4.9649610519 4.1908488274 4.9934377670 252 10.0400000000 0.0040987828 0.0049329558 0.0061568213 0.0047879097 0.0061130000 0.0005870000 0.0028150000 0.0000020000 0.0000150000 0.0011670000 13831061 96830484 509673472 4.9653792381 4.1924934387 5.0030355453 253 10.0800000000 0.0042334655 0.0049301910 0.0061568213 0.0047789010 0.0075540000 0.0005840000 0.0034060000 0.0000150000 0.0000130000 0.0019970000 13833837 96830484 509673472 4.9657874107 4.1942272186 5.0124506950 254 10.1200000000 0.0041687759 0.0049271933 0.0061568213 0.0047732710 0.0056150000 0.0005020000 0.0032190000 0.0000010000 0.0000110000 0.0009600000 13836613 96830484 509673472 4.9660186768 4.1962485313 5.0217771530 255 10.1600000000 0.0041846167 0.0049242813 0.0061568213 0.0047641533 0.0082530000 0.0005730000 0.0053680000 0.0000140000 0.0000140000 0.0012520000 13839389 96830484 509673472 4.9654026031 4.1979475021 5.0309453011 256 10.2000000000 0.0040171295 0.0049207377 0.0061568213 0.0047658919 0.0048770000 0.0004640000 0.0029910000 0.0000000000 0.0000060000 0.0007940000 13842165 96830484 509673472 4.9641470909 4.1987199783 5.0385828018 257 10.2400000000 0.0039691916 0.0049170352 0.0061568213 0.0047764956 0.0059450000 0.0004980000 0.0026750000 0.0000100000 0.0000080000 0.0016910000 13869517 96830484 509673472 4.9632439613 4.2003941536 5.0474085808 258 10.2800000000 0.0040481659 0.0049136675 0.0061568213 0.0047778320 0.0061480000 0.0005890000 0.0028230000 0.0000010000 0.0000150000 0.0011440000 13923493 96830484 509673472 4.9637031555 4.2020387650 5.0570383072 259 10.3200000000 0.0041792151 0.0049108318 0.0061568213 0.0047883749 0.0065820000 0.0005890000 0.0034070000 0.0000150000 0.0000130000 0.0013360000 13926269 96830484 509673472 4.9632630348 4.2029094696 5.0650534630 260 10.3600000000 0.0043876125 0.0049088194 0.0061568213 0.0047906250 0.0056470000 0.0005010000 0.0031540000 0.0000020000 0.0000090000 0.0009260000 13929045 96830484 509673472 4.9611177444 4.2043590546 5.0726041794 261 10.4000000000 0.0043146396 0.0049065428 0.0061568213 0.0047825677 0.0054820000 0.0004620000 0.0027290000 0.0000070000 0.0000070000 0.0014870000 13931821 96830484 509673472 4.9598779678 4.2061295509 5.0822253227 262 10.4400000000 0.0045534796 0.0049051953 0.0061568213 0.0047735244 0.0062940000 0.0005820000 0.0029800000 0.0000020000 0.0000150000 0.0011190000 13934597 96830484 509673472 4.9610118866 4.2074809074 5.0913586617 263 10.4800000000 0.0044052005 0.0049032941 0.0061568213 0.0047644455 0.0071500000 0.0005800000 0.0038040000 0.0000150000 0.0000130000 0.0012920000 13937373 96830484 509673472 4.9604048729 4.2089767456 5.1009650230 264 10.5200000000 0.0043566558 0.0049012235 0.0061568213 0.0047585212 0.0066420000 0.0005840000 0.0040430000 0.0000010000 0.0000100000 0.0009250000 13940149 96830484 509673472 4.9586696625 4.2095112801 5.1088767052 265 10.5600000000 0.0045409538 0.0048998640 0.0061568213 0.0047507376 0.0063290000 0.0005850000 0.0027990000 0.0000150000 0.0000130000 0.0018460000 13942925 96830484 509673472 4.9575362206 4.2096991539 5.1163525581 266 10.6000000000 0.0044656293 0.0048982316 0.0061568213 0.0047419517 0.0055690000 0.0004990000 0.0030630000 0.0000010000 0.0000100000 0.0009240000 13945701 96830484 509673472 4.9581565857 4.2107892036 5.1249818802 267 10.6400000000 0.0044547450 0.0048965706 0.0061568213 0.0047348149 0.0077530000 0.0005820000 0.0042210000 0.0000170000 0.0000130000 0.0013130000 13948477 96830484 509673472 4.9573073387 4.2121853828 5.1336388588 268 10.6800000000 0.0043727490 0.0048946160 0.0061568213 0.0047287738 0.0054470000 0.0005210000 0.0030590000 0.0000000000 0.0000100000 0.0009280000 13951253 96830484 509673472 4.9561057091 4.2142138481 5.1430382729 269 10.7200000000 0.0043378966 0.0048925464 0.0061568213 0.0047244733 0.0069430000 0.0005880000 0.0027910000 0.0000170000 0.0000130000 0.0018950000 13954029 96830484 509673472 4.9543457031 4.2150063515 5.1522483826 270 10.7600000000 0.0044305641 0.0048908354 0.0061568213 0.0047182034 0.0063570000 0.0005840000 0.0029840000 0.0000020000 0.0000150000 0.0011220000 13956805 96830484 509673472 4.9524588585 4.2172780037 5.1613411903 271 10.8000000000 0.0043372624 0.0048887927 0.0061568213 0.0047111851 0.0063900000 0.0005130000 0.0040230000 0.0000100000 0.0000080000 0.0010090000 13959581 96830484 509673472 4.9502682686 4.2191562653 5.1712827682 272 10.8400000000 0.0042636138 0.0048864942 0.0061568213 0.0047024896 0.0055680000 0.0004990000 0.0030460000 0.0000010000 0.0000110000 0.0009150000 13962357 96830484 509673472 4.9473857880 4.2209877968 5.1805119514 273 10.8800000000 0.0040715444 0.0048835091 0.0061568213 0.0046940708 0.0057450000 0.0004610000 0.0029680000 0.0000070000 0.0000060000 0.0014690000 13965133 96830484 509673472 4.9434037209 4.2213993073 5.1894869804 274 10.9200000000 0.0039160089 0.0048799780 0.0061568213 0.0046865417 0.0052310000 0.0004640000 0.0031130000 0.0000000000 0.0000070000 0.0008170000 13967909 96830484 509673472 4.9417362213 4.2234554291 5.1999192238 275 10.9600000000 0.0039076712 0.0048764424 0.0061568213 0.0046803080 0.0065460000 0.0005850000 0.0029420000 0.0000150000 0.0000130000 0.0013000000 13970685 96830484 509673472 4.9391274452 4.2271461487 5.2095394135 276 11.0000000000 0.0039023843 0.0048729132 0.0061568213 0.0046735107 0.0062210000 0.0007180000 0.0033520000 0.0000020000 0.0000100000 0.0009100000 13973461 96830484 509673472 4.9354763031 4.2263612747 5.2173790932 277 11.0400000000 0.0038406032 0.0048691864 0.0061568213 0.0046692344 0.0072640000 0.0006290000 0.0029500000 0.0000140000 0.0000140000 0.0018840000 13976237 96830484 509673472 4.9350624084 4.2285780907 5.2286372185 278 11.0800000000 0.0038861255 0.0048656502 0.0061568213 0.0046608011 0.0066430000 0.0005940000 0.0033700000 0.0000020000 0.0000150000 0.0011230000 13979013 96830484 509673472 4.9300131798 4.2296905518 5.2375631332 279 11.1200000000 0.0038055831 0.0048618507 0.0061568213 0.0046536349 0.0065880000 0.0005840000 0.0029390000 0.0000170000 0.0000130000 0.0013040000 13981789 96830484 509673472 4.9252028465 4.2296824455 5.2468070984 280 11.1600000000 0.0037905751 0.0048580247 0.0061568213 0.0046453151 0.0056040000 0.0005840000 0.0027970000 0.0000020000 0.0000140000 0.0010400000 13984565 96830484 509673472 4.9227170944 4.2321882248 5.2576136589 281 11.2000000000 0.0038244214 0.0048543464 0.0061568213 0.0046373280 0.0075930000 0.0006020000 0.0033680000 0.0000160000 0.0000140000 0.0018540000 13987341 96830484 509673472 4.9206395149 4.2360043526 5.2670774460 282 11.2400000000 0.0037635751 0.0048504784 0.0061568213 0.0046296549 0.0063690000 0.0006030000 0.0029340000 0.0000010000 0.0000150000 0.0010990000 13990117 96830484 509673472 4.9171481133 4.2370305061 5.2757697105 283 11.2800000000 0.0036746981 0.0048463237 0.0061568213 0.0046222262 0.0058180000 0.0005260000 0.0031920000 0.0000090000 0.0000090000 0.0010910000 13992893 96830484 509673472 4.9139375687 4.2400665283 5.2853240967 284 11.3200000000 0.0037094804 0.0048423208 0.0061568213 0.0046150511 0.0068210000 0.0005880000 0.0034030000 0.0000010000 0.0000170000 0.0010880000 13995669 96830484 509673472 4.9089593887 4.2428016663 5.2963514328 285 11.3600000000 0.0037136616 0.0048383606 0.0061568213 0.0046074225 0.0064170000 0.0004990000 0.0031970000 0.0000100000 0.0000090000 0.0015400000 13998445 96830484 509673472 4.9041938782 4.2434678078 5.3052072525 286 11.4000000000 0.0037426872 0.0048345295 0.0061568213 0.0046119791 0.0051170000 0.0004620000 0.0029870000 0.0000010000 0.0000080000 0.0007840000 14001221 96830484 509673472 4.9055399895 4.2467775345 5.3157620430 287 11.4400000000 0.0037291949 0.0048306782 0.0061568213 0.0046049297 0.0061400000 0.0005850000 0.0025170000 0.0000140000 0.0000150000 0.0012720000 14003997 96830484 509673472 4.9029779434 4.2502517700 5.3247342110 288 11.4800000000 0.0037183994 0.0048268161 0.0061568213 0.0045970323 0.0068970000 0.0006000000 0.0033500000 0.0000020000 0.0000150000 0.0011020000 14006773 96830484 509673472 4.8959093094 4.2511940002 5.3314857483 289 11.5200000000 0.0036089746 0.0048226021 0.0061568213 0.0045895948 0.0062580000 0.0005100000 0.0032070000 0.0000100000 0.0000090000 0.0015520000 14009549 96830484 509673472 4.8902258873 4.2497305870 5.3387613297 290 11.5600000000 0.0035172582 0.0048181010 0.0061568213 0.0045824426 0.0075220000 0.0005890000 0.0046270000 0.0000020000 0.0000150000 0.0010750000 14012325 96830484 509673472 4.8872365952 4.2507257462 5.3476448059 291 11.6000000000 0.0034838584 0.0048135159 0.0061568213 0.0045748788 0.0069510000 0.0004640000 0.0046000000 0.0000070000 0.0000070000 0.0009660000 14015101 96830484 509673472 4.8847856522 4.2532382011 5.3560409546 292 11.6400000000 0.0034105254 0.0048087112 0.0061568213 0.0045673096 0.0081300000 0.0005850000 0.0054220000 0.0000020000 0.0000090000 0.0008880000 14017877 96830484 509673472 4.8816542625 4.2538027763 5.3637828827 293 11.6800000000 0.0032546062 0.0048034070 0.0061568213 0.0045595306 0.0066260000 0.0004630000 0.0041610000 0.0000050000 0.0000050000 0.0012920000 14020653 96830484 509673472 4.8797721863 4.2559642792 5.3703012466 294 11.7200000000 0.0031287158 0.0047977108 0.0061568213 0.0045580065 0.0071310000 0.0005890000 0.0036400000 0.0000030000 0.0000140000 0.0010730000 14023429 96830484 509673472 4.8756165504 4.2551894188 5.3768167496 295 11.7600000000 0.0030654452 0.0047918387 0.0061568213 0.0045581869 0.0049430000 0.0004730000 0.0027040000 0.0000070000 0.0000070000 0.0009610000 14026205 96830484 509673472 4.8742246628 4.2559328079 5.3846187592 296 11.8000000000 0.0030309730 0.0047858899 0.0061568213 0.0045768550 0.0063690000 0.0006210000 0.0027970000 0.0000020000 0.0000150000 0.0010820000 14028981 96830484 509673472 4.8717646599 4.2563071251 5.3923950195 297 11.8400000000 0.0029693770 0.0047797737 0.0061568213 0.0046044763 0.0056290000 0.0005190000 0.0027740000 0.0000070000 0.0000070000 0.0013800000 14031757 96830484 509673472 4.8674030304 4.2561979294 5.3996634483 298 11.8800000000 0.0028174177 0.0047731886 0.0061568213 0.0046171942 0.0047850000 0.0004470000 0.0029280000 0.0000010000 0.0000070000 0.0007220000 14034533 96830484 509673472 4.8644247055 4.2557301521 5.4084916115 299 11.9200000000 0.0027426297 0.0047663974 0.0061568213 0.0046156587 0.0048340000 0.0004330000 0.0028960000 0.0000050000 0.0000050000 0.0008700000 14037309 96830484 509673472 4.8625035286 4.2553939819 5.4166154861 300 11.9600000000 0.0026291353 0.0047592732 0.0061568213 0.0046145259 0.0043940000 0.0004330000 0.0026380000 0.0000010000 0.0000050000 0.0006910000 14040085 96830484 509673472 4.8606333733 4.2548089027 5.4242625237 301 12.0000000000 0.0025685385 0.0047519950 0.0061568213 0.0046099111 0.0053400000 0.0004330000 0.0030250000 0.0000060000 0.0000040000 0.0012450000 14042861 96830484 509673472 4.8596019745 4.2555966377 5.4338469505 302 12.0400000000 0.0024732358 0.0047444494 0.0061568213 0.0046034349 0.0047980000 0.0004350000 0.0030390000 0.0000010000 0.0000050000 0.0006850000 14045637 96830484 509673472 4.8588724136 4.2558946609 5.4424800873 303 12.0800000000 0.0024620618 0.0047369168 0.0061568213 0.0045975010 0.0048320000 0.0004310000 0.0028960000 0.0000050000 0.0000040000 0.0008580000 14048413 96830484 509673472 4.8568820953 4.2551364899 5.4500436783 304 12.1200000000 0.0023855688 0.0047291821 0.0061568213 0.0045914202 0.0044290000 0.0004340000 0.0026290000 0.0000010000 0.0000110000 0.0006840000 14051189 96830484 509673472 4.8556928635 4.2560210228 5.4596481323 305 12.1600000000 0.0022728783 0.0047211287 0.0061568213 0.0045839567 0.0056090000 0.0004870000 0.0031430000 0.0000050000 0.0000050000 0.0012300000 14053965 96830484 509673472 4.8545217514 4.2570648193 5.4693069458 306 12.2000000000 0.0022917006 0.0047131894 0.0061568213 0.0045765675 0.0069600000 0.0005990000 0.0033740000 0.0000020000 0.0000150000 0.0010690000 14056741 96830484 509673472 4.8518891335 4.2580747604 5.4781460762 307 12.2400000000 0.0021781682 0.0047049320 0.0061568213 0.0045706953 0.0063750000 0.0005870000 0.0026380000 0.0000150000 0.0000130000 0.0012380000 14059517 96830484 509673472 4.8497462273 4.2598910332 5.4877319336 308 12.2800000000 0.0020680351 0.0046963706 0.0061568213 0.0045689804 0.0054550000 0.0005050000 0.0028080000 0.0000010000 0.0000100000 0.0008570000 14062293 96830484 509673472 4.8486347198 4.2605662346 5.4974699020 309 12.3200000000 0.0020822256 0.0046879106 0.0061568213 0.0045670687 0.0072720000 0.0006050000 0.0029500000 0.0000150000 0.0000140000 0.0017380000 14065069 96830484 509673472 4.8472642899 4.2612042427 5.5065951347 310 12.3600000000 0.0021225561 0.0046796353 0.0061568213 0.0045744586 0.0065280000 0.0005940000 0.0029550000 0.0000020000 0.0000150000 0.0010520000 14067845 96830484 509673472 4.8462324142 4.2638802528 5.5165872574 311 12.4000000000 0.0021078237 0.0046713658 0.0061568213 0.0045944729 0.0076510000 0.0005920000 0.0046630000 0.0000150000 0.0000140000 0.0010780000 14070621 96830484 509673472 4.8449778557 4.2660784721 5.5268073082 312 12.4400000000 0.0020935591 0.0046631036 0.0061568213 0.0046012812 0.0047530000 0.0004650000 0.0025730000 0.0000010000 0.0000080000 0.0007430000 14073397 96830484 509673472 4.8439469337 4.2649779320 5.5344948769 313 12.4800000000 0.0019359112 0.0046543905 0.0061568213 0.0046023891 0.0055570000 0.0004510000 0.0030750000 0.0000060000 0.0000060000 0.0012140000 14076173 96830484 509673472 4.8426833153 4.2660293579 5.5441317558 314 12.5200000000 0.0018119566 0.0046453381 0.0061568213 0.0046009970 0.0049960000 0.0004480000 0.0030760000 0.0000010000 0.0000060000 0.0006900000 14078949 96830484 509673472 4.8409333229 4.2671604156 5.5533900261 315 12.5600000000 0.0017757907 0.0046362285 0.0061568213 0.0045960657 0.0066800000 0.0005880000 0.0029410000 0.0000150000 0.0000140000 0.0011890000 14081725 96830484 509673472 4.8395223618 4.2681770325 5.5615444183 316 12.6000000000 0.0018510374 0.0046274146 0.0061568213 0.0045890295 0.0085950000 0.0005880000 0.0054710000 0.0000020000 0.0000160000 0.0010310000 14084501 96830484 509673472 4.8401408195 4.2678260803 5.5694742203 317 12.6400000000 0.0017786721 0.0046184280 0.0061568213 0.0045821455 0.0055720000 0.0005010000 0.0027910000 0.0000090000 0.0000100000 0.0012680000 14087277 96830484 509673472 4.8393573761 4.2689757347 5.5784196854 318 12.6800000000 0.0019374382 0.0046099972 0.0061568213 0.0045777556 0.0045990000 0.0004440000 0.0026830000 0.0000010000 0.0000070000 0.0006770000 14090053 96830484 509673472 4.8390951157 4.2707648277 5.5874056816 319 12.7200000000 0.0020570010 0.0046019941 0.0061568213 0.0045717482 0.0062880000 0.0005840000 0.0025280000 0.0000140000 0.0000130000 0.0011700000 14092829 96830484 509673472 4.8364720345 4.2735757828 5.5978217125 320 12.7600000000 0.0020664043 0.0045940704 0.0061568213 0.0045714657 0.0073560000 0.0005800000 0.0037960000 0.0000020000 0.0000150000 0.0010080000 14095605 96830484 509673472 4.8343319893 4.2746357918 5.6068391800 321 12.8000000000 0.0020918173 0.0045862752 0.0061568213 0.0045826295 0.0068090000 0.0005000000 0.0040430000 0.0000070000 0.0000070000 0.0012540000 14098381 96830484 509673472 4.8327603340 4.2766575813 5.6161532402 322 12.8400000000 0.0021210536 0.0045786192 0.0061568213 0.0045878886 0.0056810000 0.0004480000 0.0038840000 0.0000000000 0.0000080000 0.0006580000 14101157 96830484 509673472 4.8316836357 4.2789711952 5.6251153946 323 12.8800000000 0.0021238967 0.0045710195 0.0061568213 0.0046000262 0.0071650000 0.0005930000 0.0033810000 0.0000150000 0.0000140000 0.0011700000 14103933 96830484 509673472 4.8304629326 4.2804422379 5.6330204010 324 12.9200000000 0.0020520343 0.0045632448 0.0061568213 0.0046121716 0.0073650000 0.0005870000 0.0038150000 0.0000010000 0.0000150000 0.0009870000 14106709 96830484 509673472 4.8292999268 4.2805852890 5.6399950981 325 12.9600000000 0.0020589151 0.0045555392 0.0061568213 0.0046244678 0.0059810000 0.0004990000 0.0032100000 0.0000110000 0.0000090000 0.0012640000 14109485 96830484 509673472 4.8289155960 4.2810454369 5.6471600533 326 13.0000000000 0.0021794359 0.0045482505 0.0061568213 0.0046331762 0.0062530000 0.0005040000 0.0036240000 0.0000010000 0.0000110000 0.0007940000 14112261 96830484 509673472 4.8277416229 4.2818989754 5.6553177834 327 13.0400000000 0.0021274239 0.0045408474 0.0061568213 0.0047405445 0.0069880000 0.0005870000 0.0033740000 0.0000160000 0.0000130000 0.0011320000 14115037 96830484 509673472 4.8240628242 4.2864341736 5.6748557091 328 13.0800000000 0.0021794266 0.0045336479 0.0061568213 0.0047591093 0.0054110000 0.0005030000 0.0027900000 0.0000010000 0.0000100000 0.0007910000 14117813 96830484 509673472 4.8221888542 4.2871489525 5.6826982498 329 13.1200000000 0.0021818283 0.0045264996 0.0061568213 0.0047643940 0.0071800000 0.0005900000 0.0029630000 0.0000160000 0.0000130000 0.0016090000 14120589 96830484 509673472 4.8200693130 4.2881379128 5.6906609535 330 13.1600000000 0.0022601844 0.0045196319 0.0061568213 0.0047635928 0.0058600000 0.0005020000 0.0032260000 0.0000010000 0.0000100000 0.0007860000 14123365 96830484 509673472 4.8186340332 4.2885260582 5.6978793144 331 13.2000000000 0.0022557785 0.0045127925 0.0061568213 0.0047633341 0.0072770000 0.0005900000 0.0038170000 0.0000150000 0.0000130000 0.0011300000 14126141 96830484 509673472 4.8178844452 4.2884688377 5.7046184540 332 13.2400000000 0.0023243942 0.0045062009 0.0061568213 0.0047602647 0.0062270000 0.0005030000 0.0040250000 0.0000010000 0.0000070000 0.0006870000 14128917 96830484 509673472 4.8168654442 4.2899818420 5.7123031616 333 13.2800000000 0.0023002976 0.0044995766 0.0061568213 0.0047553758 0.0084700000 0.0005890000 0.0042240000 0.0000150000 0.0000130000 0.0016070000 14131693 96830484 509673472 4.8158307076 4.2914195061 5.7197952271 334 13.3200000000 0.0022538933 0.0044928530 0.0061568213 0.0047576106 0.0050080000 0.0005380000 0.0027580000 0.0000000000 0.0000080000 0.0006830000 14134469 96830484 509673472 4.8154187202 4.2914948463 5.7258677483 335 13.3600000000 0.0022122725 0.0044860453 0.0061568213 0.0047633455 0.0051210000 0.0004450000 0.0030650000 0.0000060000 0.0000050000 0.0007880000 14137245 96830484 509673472 4.8132758141 4.2942910194 5.7345819473 336 13.4000000000 0.0021694251 0.0044791506 0.0061568213 0.0047771013 0.0066220000 0.0005910000 0.0029940000 0.0000010000 0.0000150000 0.0009680000 14140021 96830484 509673472 4.8112478256 4.2950539589 5.7407913208 337 13.4400000000 0.0020220133 0.0044718594 0.0061568213 0.0048017392 0.0065580000 0.0005890000 0.0029570000 0.0000170000 0.0000130000 0.0015740000 14142797 96830484 509673472 4.8099198341 4.2940864563 5.7459931374 338 13.4800000000 0.0019992914 0.0044645441 0.0061568213 0.0048294646 0.0066400000 0.0005890000 0.0033770000 0.0000010000 0.0000150000 0.0009600000 14145573 96830484 509673472 4.8064718246 4.2941398621 5.7514433861 339 13.5200000000 0.0020242955 0.0044573457 0.0061568213 0.0048511193 0.0060250000 0.0005080000 0.0032010000 0.0000100000 0.0000090000 0.0009270000 14148349 96830484 509673472 4.8045234680 4.2958559990 5.7590141296 340 13.5600000000 0.0020253605 0.0044501928 0.0061568213 0.0048755149 0.0066200000 0.0005880000 0.0029890000 0.0000020000 0.0000150000 0.0009610000 14151125 96830484 509673472 4.7999272346 4.2961168289 5.7647190094 341 13.6000000000 0.0019575560 0.0044428830 0.0061568213 0.0048848976 0.0061300000 0.0005060000 0.0032080000 0.0000110000 0.0000100000 0.0013000000 14153901 96830484 509673472 4.7961974144 4.2970924377 5.7719807625 342 13.6400000000 0.0021181721 0.0044360856 0.0061568213 0.0048980536 0.0066360000 0.0005880000 0.0029690000 0.0000020000 0.0000160000 0.0009690000 14156677 96830484 509673472 4.7925724983 4.2994747162 5.7800755501 343 13.6800000000 0.0022292472 0.0044296517 0.0061568213 0.0049167015 0.0067990000 0.0005850000 0.0030020000 0.0000150000 0.0000150000 0.0011040000 14159453 96830484 509673472 4.7883567810 4.3029665947 5.7885141373 344 13.7200000000 0.0022741708 0.0044233858 0.0061568213 0.0049209695 0.0058610000 0.0005030000 0.0031910000 0.0000010000 0.0000100000 0.0007680000 14162229 96830484 509673472 4.7844119072 4.3049449921 5.7943654060 345 13.7600000000 0.0023174270 0.0044172815 0.0061568213 0.0049231875 0.0057010000 0.0004680000 0.0031400000 0.0000070000 0.0000060000 0.0011360000 14165005 96830484 509673472 4.7826566696 4.3040661812 5.7990121841 346 13.8000000000 0.0024078349 0.0044114739 0.0061568213 0.0049239087 0.0084500000 0.0006130000 0.0054950000 0.0000010000 0.0000140000 0.0009190000 14167781 96830484 509673472 4.7801308632 4.3044953346 5.8029813766 347 13.8400000000 0.0024703192 0.0044058798 0.0061568213 0.0049319473 0.0056470000 0.0005050000 0.0028090000 0.0000100000 0.0000080000 0.0009130000 14170557 96830484 509673472 4.7762861252 4.3038926125 5.8087129593 348 13.8800000000 0.0025768899 0.0044006241 0.0061568213 0.0049451530 0.0053690000 0.0004670000 0.0031450000 0.0000000000 0.0000080000 0.0006690000 14173333 96830484 509673472 4.7717676163 4.3044419289 5.8153648376 349 13.9200000000 0.0026391570 0.0043955769 0.0061568213 0.0049537284 0.0057000000 0.0004710000 0.0030110000 0.0000080000 0.0000070000 0.0011310000 14176109 96830484 509673472 4.7657051086 4.3049035072 5.8227133751 350 13.9600000000 0.0028386000 0.0043911284 0.0061568213 0.0049630297 0.0067050000 0.0005880000 0.0029970000 0.0000010000 0.0000160000 0.0009680000 14178885 96830484 509673472 4.7601013184 4.3061947823 5.8303089142 351 14.0000000000 0.0028325128 0.0043866879 0.0061568213 0.0049632320 0.0072610000 0.0005850000 0.0034100000 0.0000150000 0.0000140000 0.0010990000 14181661 96830484 509673472 4.7548260689 4.3076844215 5.8367772102 352 14.0400000000 0.0028936788 0.0043824464 0.0061568213 0.0049638213 0.0062390000 0.0005860000 0.0034090000 0.0000020000 0.0000140000 0.0007850000 14184437 96830484 509673472 4.7492218018 4.3073792458 5.8404994011 353 14.0800000000 0.0028884141 0.0043782140 0.0061568213 0.0049620875 0.0058330000 0.0004720000 0.0031400000 0.0000080000 0.0000060000 0.0011320000 14187213 96830484 509673472 4.7448596954 4.3063902855 5.8459010124 354 14.1200000000 0.0029565056 0.0043741979 0.0061568213 0.0049633780 0.0067100000 0.0005900000 0.0029790000 0.0000020000 0.0000150000 0.0009560000 14189989 96830484 509673472 4.7388315201 4.3087563515 5.8549766541 355 14.1600000000 0.0031144158 0.0043706492 0.0061568213 0.0049599963 0.0062140000 0.0005900000 0.0032520000 0.0000100000 0.0000090000 0.0009100000 14192765 96830484 509673472 4.7331080437 4.3096685410 5.8600616455 356 14.2000000000 0.0032640181 0.0043675407 0.0061568213 0.0049569720 0.0079710000 0.0005910000 0.0042420000 0.0000020000 0.0000140000 0.0009540000 14195541 96830484 509673472 4.7271456718 4.3096709251 5.8644566536 357 14.2400000000 0.0033689863 0.0043647436 0.0061568213 0.0049538073 0.0058790000 0.0005030000 0.0031600000 0.0000080000 0.0000060000 0.0011140000 14198317 96830484 509673472 4.7197804451 4.3109145164 5.8708014488 358 14.2800000000 0.0034552340 0.0043622031 0.0061568213 0.0049475156 0.0045800000 0.0004480000 0.0026440000 0.0000010000 0.0000060000 0.0006040000 14201093 96830484 509673472 4.7144527435 4.3111047745 5.8763108253 359 14.3200000000 0.0034885104 0.0043597694 0.0061568213 0.0049410450 0.0051220000 0.0004500000 0.0030210000 0.0000060000 0.0000060000 0.0007600000 14203869 96830484 509673472 4.7054905891 4.3147120476 5.8838500977 360 14.3600000000 0.0036955900 0.0043579244 0.0061568213 0.0049423873 0.0066290000 0.0005880000 0.0028910000 0.0000020000 0.0000170000 0.0009450000 14206645 96830484 509673472 4.6897888184 4.3179430962 5.8957290649 361 14.4000000000 0.0041223811 0.0043572720 0.0061568213 0.0049356450 0.0067640000 0.0005890000 0.0024360000 0.0000150000 0.0000140000 0.0015190000 14209421 96830484 509673472 4.6807203293 4.3224539757 5.9043188095 362 14.4400000000 0.0041849599 0.0043567960 0.0061568213 0.0049308885 0.0069130000 0.0006120000 0.0039210000 0.0000020000 0.0000200000 0.0007550000 14212197 96830484 509673472 4.6639437675 4.3216719627 5.9105687141 363 14.4800000000 0.0041115414 0.0043561203 0.0061568213 0.0049268061 0.0051530000 0.0005220000 0.0029010000 0.0000210000 0.0000050000 0.0007590000 14214973 96830484 509673472 4.6579766273 4.3206701279 5.9145116806 364 14.5200000000 0.0040230551 0.0043552053 0.0061568213 0.0049200605 0.0066420000 0.0004480000 0.0046610000 0.0000010000 0.0000060000 0.0006080000 14217749 96830484 509673472 4.6502132416 4.3212575912 5.9206075668 365 14.5600000000 0.0042148866 0.0043548209 0.0061568213 0.0049133343 0.0078970000 0.0005890000 0.0034700000 0.0000150000 0.0000140000 0.0015310000 14220525 96830484 509673472 4.6421847343 4.3213014603 5.9256916046 366 14.6000000000 0.0043943669 0.0043549289 0.0061568213 0.0049073923 0.0051760000 0.0005060000 0.0028390000 0.0000010000 0.0000080000 0.0006770000 14223301 96830484 509673472 4.6258244514 4.3275065422 5.9402499199 367 14.6400000000 0.0048042373 0.0043561532 0.0061568213 0.0049011006 0.0072970000 0.0005920000 0.0033470000 0.0000150000 0.0000130000 0.0010990000 14226077 96830484 509673472 4.6166195869 4.3314485550 5.9453239441 368 14.6800000000 0.0050754347 0.0043581078 0.0061568213 0.0048960287 0.0054720000 0.0005070000 0.0027660000 0.0000010000 0.0000100000 0.0007570000 14228853 96830484 509673472 4.6079940796 4.3316946030 5.9491596222 369 14.7200000000 0.0051663825 0.0043602982 0.0061568213 0.0048913580 0.0085020000 0.0006090000 0.0047300000 0.0000180000 0.0000140000 0.0015790000 14231629 96830484 509673472 4.5995845795 4.3293523788 5.9505705833 370 14.7600000000 0.0050971215 0.0043622896 0.0061568213 0.0048854681 0.0050620000 0.0004770000 0.0029970000 0.0000010000 0.0000060000 0.0006410000 14234405 96830484 509673472 4.5914373398 4.3281736374 5.9522075653 371 14.8000000000 0.0049751308 0.0043639415 0.0061568213 0.0048804988 0.0049170000 0.0004390000 0.0029220000 0.0000050000 0.0000040000 0.0007600000 14237181 96830484 509673472 4.5819625854 4.3303527832 5.9589147568 372 14.8400000000 0.0050918018 0.0043658981 0.0061568213 0.0048745026 0.0060840000 0.0004330000 0.0042360000 0.0000010000 0.0000050000 0.0006240000 14239957 96830484 509673472 4.5733714104 4.3316569328 5.9640898705 373 14.8800000000 0.0053014602 0.0043684063 0.0061568213 0.0048703344 0.0055440000 0.0004380000 0.0032300000 0.0000050000 0.0000050000 0.0010710000 14242733 96830484 509673472 4.5637431145 4.3327093124 5.9687404633 374 14.9200000000 0.0059110280 0.0043725310 0.0061568213 0.0048648190 0.0044470000 0.0004380000 0.0025520000 0.0000000000 0.0000050000 0.0006420000 14245509 96830484 509673472 4.5531454086 4.3331894875 5.9720292091 375 14.9600000000 0.0060337274 0.0043769608 0.0061568213 0.0048625324 0.0055930000 0.0004370000 0.0035680000 0.0000050000 0.0000050000 0.0007850000 14248285 96830484 509673472 4.5428295135 4.3327383995 5.9733572006 376 15.0000000000 0.0061878678 0.0043817771 0.0061878678 0.0048563452 0.0048060000 0.0004400000 0.0029040000 0.0000000000 0.0000050000 0.0006530000 14251061 96830484 509673472 4.5338220596 4.3322839737 5.9786667824 377 15.0400000000 0.0061308132 0.0043864164 0.0061878678 0.0048536747 0.0053300000 0.0004400000 0.0029080000 0.0000060000 0.0000040000 0.0011490000 14253837 96830484 509673472 4.5127692223 4.3335695267 5.9859266281 378 15.0800000000 0.0068198801 0.0043928542 0.0068198801 0.0048512017 0.0051590000 0.0004380000 0.0032510000 0.0000000000 0.0000050000 0.0006600000 14256613 96830484 509673472 4.5043954849 4.3339610100 5.9899263382 379 15.1200000000 0.0073400759 0.0044006305 0.0073400759 0.0048458441 0.0078700000 0.0006060000 0.0036800000 0.0000160000 0.0000140000 0.0011650000 14259389 96830484 509673472 4.4973754883 4.3334393501 5.9929614067 380 15.1600000000 0.0076842303 0.0044092715 0.0076842303 0.0048423412 0.0079020000 0.0005940000 0.0047650000 0.0000020000 0.0000140000 0.0009330000 14262165 96830484 509673472 4.4902644157 4.3321404457 5.9966611862 381 15.2000000000 0.0080891885 0.0044189301 0.0080891885 0.0048481028 0.0059560000 0.0004680000 0.0030260000 0.0000080000 0.0000070000 0.0012560000 14264941 96830484 509673472 4.4825639725 4.3332309723 6.0026946068 382 15.2400000000 0.0086791664 0.0044300826 0.0086791664 0.0048491573 0.0064510000 0.0004540000 0.0043370000 0.0000010000 0.0000060000 0.0006810000 14267717 96830484 509673472 4.4729065895 4.3327250481 6.0035915375 383 15.2800000000 0.0088687399 0.0044416717 0.0088687399 0.0048597672 0.0066170000 0.0004620000 0.0043440000 0.0000060000 0.0000050000 0.0008330000 14270493 96830484 509673472 4.4645571709 4.3325452805 6.0062232018 384 15.3200000000 0.0084521724 0.0044521158 0.0088687399 0.0048807586 0.0043940000 0.0004490000 0.0022950000 0.0000010000 0.0000060000 0.0006780000 14273269 96830484 509673472 4.4555482864 4.3343596458 6.0115184784 385 15.3600000000 0.0086808335 0.0044630994 0.0088687399 0.0048803334 0.0069610000 0.0004540000 0.0043560000 0.0000060000 0.0000050000 0.0011550000 14276045 96830484 509673472 4.4478511810 4.3342962265 6.0143036842 386 15.4000000000 0.0084718466 0.0044734848 0.0088687399 0.0048836291 0.0064770000 0.0004560000 0.0043550000 0.0000010000 0.0000060000 0.0006810000 14278821 96830484 509673472 4.4402680397 4.3349428177 6.0173888206 387 15.4400000000 0.0085027069 0.0044838962 0.0088687399 0.0048876667 0.0066610000 0.0004520000 0.0043670000 0.0000070000 0.0000050000 0.0008390000 14281597 96830484 509673472 4.4339089394 4.3356289864 6.0212674141 388 15.4800000000 0.0081035867 0.0044932253 0.0088687399 0.0048984690 0.0089260000 0.0006350000 0.0047900000 0.0000010000 0.0000150000 0.0010110000 14284373 96830484 509673472 4.4270119667 4.3369784355 6.0249905586 389 15.5200000000 0.0083248587 0.0045030753 0.0088687399 0.0048984929 0.0074050000 0.0005040000 0.0045330000 0.0000070000 0.0000080000 0.0012530000 14287149 96830484 509673472 4.4193301201 4.3380045891 6.0290393829 390 15.5600000000 0.0082497066 0.0045126820 0.0088687399 0.0049165330 0.0070420000 0.0005130000 0.0045700000 0.0000010000 0.0000070000 0.0007290000 14289925 96830484 509673472 4.4111976624 4.3386745453 6.0321836472 391 15.6000000000 0.0078663910 0.0045212593 0.0088687399 0.0049196961 0.0072100000 0.0004450000 0.0046370000 0.0000180000 0.0000100000 0.0011990000 14292701 96830484 509673472 4.4038844109 4.3395476341 6.0356063843 392 15.6400000000 0.0076416708 0.0045292195 0.0088687399 0.0049327274 0.0071900000 0.0005560000 0.0045910000 0.0000010000 0.0000120000 0.0008000000 14295477 96830484 509673472 4.3967862129 4.3405895233 6.0405049324 393 15.6800000000 0.0079860892 0.0045380156 0.0088687399 0.0049287765 0.0072370000 0.0004730000 0.0045270000 0.0000080000 0.0000070000 0.0012200000 14298253 96830484 509673472 4.3903069496 4.3403921127 6.0434150696 394 15.7200000000 0.0078852391 0.0045465111 0.0088687399 0.0049317728 0.0087170000 0.0005910000 0.0049020000 0.0000010000 0.0000180000 0.0010010000 14301029 96830484 509673472 4.3834047318 4.3411655426 6.0467028618 395 15.7600000000 0.0078624431 0.0045549059 0.0088687399 0.0049344079 0.0067770000 0.0004700000 0.0045050000 0.0000060000 0.0000050000 0.0008140000 14303805 96830484 509673472 4.3767447472 4.3420386314 6.0528774261 396 15.8000000000 0.0081423642 0.0045639651 0.0088687399 0.0049313332 0.0063150000 0.0004300000 0.0044090000 0.0000010000 0.0000050000 0.0006400000 14306581 96830484 509673472 4.3698215485 4.3438162804 6.0580444336 397 15.8400000000 0.0079074344 0.0045723870 0.0088687399 0.0049305398 0.0077510000 0.0005900000 0.0033840000 0.0000150000 0.0000120000 0.0016180000 14309357 96830484 509673472 4.3632102013 4.3434228897 6.0605831146 398 15.8800000000 0.0074010044 0.0045794940 0.0088687399 0.0049332885 0.0071070000 0.0005040000 0.0046460000 0.0000010000 0.0000080000 0.0007140000 14312133 96830484 509673472 4.3571166992 4.3443903923 6.0677709579 399 15.9200000000 0.0073943236 0.0045865487 0.0088687399 0.0049366326 0.0055170000 0.0004460000 0.0034430000 0.0000050000 0.0000060000 0.0007830000 14314909 96830484 509673472 4.3489279747 4.3462028503 6.0713376999 400 15.9600000000 0.0068113455 0.0045921107 0.0088687399 0.0049371386 0.0077020000 0.0006110000 0.0038220000 0.0000020000 0.0000160000 0.0010040000 14317685 96830484 509673472 4.3425612450 4.3453445435 6.0746207237 401 16.0000000000 0.0058500036 0.0045952476 0.0088687399 0.0049430995 0.0077640000 0.0005070000 0.0047320000 0.0000090000 0.0000060000 0.0012410000 14320461 96830484 509673472 4.3346066475 4.3447451591 6.0787940025 402 16.0400000000 0.0059037218 0.0045985025 0.0088687399 0.0049637745 0.0055970000 0.0004440000 0.0035130000 0.0000010000 0.0000060000 0.0006740000 14323237 96830484 509673472 4.3267054558 4.3458719254 6.0855684280 403 16.0800000000 0.0059520374 0.0046018612 0.0088687399 0.0049600485 0.0086700000 0.0005890000 0.0050410000 0.0000150000 0.0000130000 0.0011550000 14326013 96830484 509673472 4.3211975098 4.3464417458 6.0917119980 404 16.1200000000 0.0061068446 0.0046055864 0.0088687399 0.0049556763 0.0065320000 0.0005040000 0.0040270000 0.0000010000 0.0000070000 0.0007210000 14328789 96830484 509673472 4.3141655922 4.3462915421 6.0960793495 405 16.1600000000 0.0065427860 0.0046103696 0.0088687399 0.0049631493 0.0060050000 0.0004470000 0.0034990000 0.0000070000 0.0000060000 0.0011510000 14331565 96830484 509673472 4.3067812920 4.3460192680 6.1000957489 406 16.2000000000 0.0070050643 0.0046162679 0.0088687399 0.0049842624 0.0085660000 0.0006090000 0.0050000000 0.0000010000 0.0000160000 0.0009870000 14334341 96830484 509673472 4.3007993698 4.3476085663 6.1086111069 407 16.2400000000 0.0075559951 0.0046234908 0.0088687399 0.0049930709 0.0069940000 0.0005020000 0.0043440000 0.0000070000 0.0000070000 0.0008570000 14337117 96830484 509673472 4.2945222855 4.3502359390 6.1141324043 408 16.2800000000 0.0083173318 0.0046325443 0.0088687399 0.0050084851 0.0059120000 0.0004480000 0.0038610000 0.0000010000 0.0000060000 0.0006570000 14339893 96830484 509673472 4.2893333435 4.3515324593 6.1186900139 409 16.3200000000 0.0089931088 0.0046432058 0.0089931088 0.0050238297 0.0090190000 0.0006170000 0.0049920000 0.0000170000 0.0000130000 0.0016160000 14342669 96830484 509673472 4.2829480171 4.3530855179 6.1255230904 410 16.3600000000 0.0096139377 0.0046553296 0.0096139377 0.0050248867 0.0056950000 0.0004670000 0.0035550000 0.0000010000 0.0000060000 0.0006390000 14345445 96830484 509673472 4.2778987885 4.3541121483 6.1294779778 411 16.3999999990 0.0103764376 0.0046692495 0.0103764376 0.0050285081 0.0065030000 0.0004280000 0.0045570000 0.0000050000 0.0000050000 0.0007710000 14348221 96830484 509673472 4.2725520134 4.3550491333 6.1327943802 412 16.4400000000 0.0101869218 0.0046826420 0.0103764376 0.0050227747 0.0074360000 0.0005860000 0.0038620000 0.0000010000 0.0000170000 0.0009610000 14350997 96830484 509673472 4.2679181099 4.3545517921 6.1381549835 413 16.4800000000 0.0100630540 0.0046956696 0.0103764376 0.0050252230 0.0066400000 0.0005040000 0.0036420000 0.0000080000 0.0000070000 0.0011770000 14353773 96830484 509673472 4.2623047829 4.3555927277 6.1453442574 414 16.5200000000 0.0128197856 0.0047152931 0.0128197856 0.0050552842 0.0049360000 0.0004460000 0.0027940000 0.0000000000 0.0000070000 0.0006490000 14356549 96830484 509673472 4.2588329315 4.3586215973 6.1508760452 415 16.5599999990 0.0136055769 0.0047367154 0.0136055769 0.0050891232 0.0081850000 0.0005930000 0.0038390000 0.0000150000 0.0000130000 0.0011240000 14359325 96830484 509673472 4.2527770996 4.3615775108 6.1575818062 416 16.6000000000 0.0159034990 0.0047635587 0.0159034990 0.0051010904 0.0054050000 0.0005030000 0.0028740000 0.0000010000 0.0000070000 0.0007120000 14362101 96830484 509673472 4.2493133545 4.3640036583 6.1617145538 417 16.6400000000 0.0137381982 0.0047850806 0.0159034990 0.0051147929 0.0096420000 0.0005910000 0.0049430000 0.0000140000 0.0000140000 0.0015890000 14364877 96830484 509673472 4.2405619621 4.3644371033 6.1653838158 418 16.6800000000 0.0173482504 0.0048151360 0.0173482504 0.0052477692 0.0052660000 0.0004910000 0.0027750000 0.0000010000 0.0000080000 0.0007200000 14367653 96830484 509673472 4.2306461334 4.3695211411 6.1745090485 419 16.7199999990 0.0219873767 0.0048561199 0.0219873767 0.0052759166 0.0077930000 0.0005080000 0.0046880000 0.0000110000 0.0000090000 0.0009680000 14370429 96830484 509673472 4.2337346077 4.3697061539 6.1810641289 420 16.7600000000 0.0290026348 0.0049136116 0.0290026348 0.0053952049 0.0048520000 0.0004680000 0.0024120000 0.0000010000 0.0000080000 0.0007280000 14373205 96830484 509673472 4.2335510254 4.3757114410 6.1871428490 421 16.8000000000 0.0224928912 0.0049553676 0.0290026348 0.0053970353 0.0071780000 0.0006070000 0.0026580000 0.0000150000 0.0000150000 0.0016330000 14375981 96830484 509673472 4.2227964401 4.3730344772 6.1922693253 422 16.8400000000 0.0171214249 0.0049841971 0.0290026348 0.0053985062 0.0067370000 0.0005880000 0.0025290000 0.0000020000 0.0000150000 0.0010050000 14378757 96830484 509673472 4.2132205963 4.3703145981 6.1969203949 423 16.8799999990 0.0172801353 0.0050132655 0.0290026348 0.0054371807 0.0060030000 0.0005040000 0.0032360000 0.0000100000 0.0000090000 0.0009280000 14381533 96830484 509673472 4.2079839706 4.3710932732 6.2021870613 424 16.9200000000 0.0147866877 0.0050363160 0.0290026348 0.0054694459 0.0077830000 0.0005060000 0.0046670000 0.0000010000 0.0000100000 0.0008410000 14384309 96830484 509673472 4.1943960190 4.3714308739 6.2117824554 425 16.9600000000 0.0120135965 0.0050527332 0.0290026348 0.0054643592 0.0072350000 0.0004680000 0.0045210000 0.0000070000 0.0000050000 0.0011760000 14387085 96830484 509673472 4.1879267693 4.3703436852 6.2153148651 426 17.0000000000 0.0114685753 0.0050677938 0.0290026348 0.0054775820 0.0049770000 0.0004280000 0.0030370000 0.0000000000 0.0000050000 0.0006710000 14389861 96830484 509673472 4.1817598343 4.3716778755 6.2203440666 427 17.0400000000 0.0110688768 0.0050818479 0.0290026348 0.0054824572 0.0082090000 0.0005940000 0.0037770000 0.0000150000 0.0000130000 0.0011780000 14392637 96830484 509673472 4.1758742332 4.3732776642 6.2247915268 428 17.0800000000 0.0114292223 0.0050966782 0.0290026348 0.0054914153 0.0061170000 0.0004990000 0.0035140000 0.0000010000 0.0000080000 0.0007680000 14395413 96830484 509673472 4.1709132195 4.3757438660 6.2287406921 429 17.1200000000 0.0107860258 0.0051099401 0.0290026348 0.0054904176 0.0093800000 0.0005880000 0.0048890000 0.0000150000 0.0000130000 0.0017060000 14398189 96830484 509673472 4.1655411720 4.3754825592 6.2309851646 430 17.1600000000 0.0107887257 0.0051231466 0.0290026348 0.0054926585 0.0051660000 0.0004770000 0.0027550000 0.0000010000 0.0000070000 0.0007660000 14400965 96830484 509673472 4.1606783867 4.3758234978 6.2345027924 431 17.2000000000 0.0102916453 0.0051351384 0.0290026348 0.0054900063 0.0073800000 0.0005050000 0.0045970000 0.0000080000 0.0000070000 0.0009170000 14403741 96830484 509673472 4.1558547020 4.3749232292 6.2381577492 432 17.2400000000 0.0107508339 0.0051481377 0.0290026348 0.0054913612 0.0062300000 0.0005910000 0.0029970000 0.0000010000 0.0000100000 0.0008500000 14406517 96830484 509673472 4.1505603790 4.3760585785 6.2427163124 433 17.2800000000 0.0105557544 0.0051606265 0.0290026348 0.0054893792 0.0063960000 0.0004640000 0.0034590000 0.0000090000 0.0000060000 0.0012870000 14409293 96830484 509673472 4.1465597153 4.3773474693 6.2464528084 434 17.3200000000 0.0107772965 0.0051735681 0.0290026348 0.0054907107 0.0083040000 0.0005890000 0.0048700000 0.0000020000 0.0000150000 0.0010360000 14412069 96830484 509673472 4.1411166191 4.3787226677 6.2488846779 435 17.3600000000 0.0105221011 0.0051858636 0.0290026348 0.0054884458 0.0070000000 0.0004680000 0.0045600000 0.0000070000 0.0000050000 0.0008810000 14414845 96830484 509673472 4.1357965469 4.3770060539 6.2503705025 436 17.4000000000 0.0110007133 0.0051992004 0.0290026348 0.0054946661 0.0046860000 0.0004280000 0.0026750000 0.0000010000 0.0000050000 0.0006760000 14417621 96830484 509673472 4.1308121681 4.3772525787 6.2531628609 437 17.4400000000 0.0110054445 0.0052124870 0.0290026348 0.0054931479 0.0087780000 0.0005860000 0.0037550000 0.0000150000 0.0000150000 0.0017100000 14420397 96830484 509673472 4.1244711876 4.3785839081 6.2562184334 438 17.4800000000 0.0107896291 0.0052252202 0.0290026348 0.0054925089 0.0073340000 0.0005130000 0.0046130000 0.0000010000 0.0000070000 0.0007750000 14423173 96830484 509673472 4.1193342209 4.3769350052 6.2585520744 439 17.5200000000 0.0102730440 0.0052367186 0.0290026348 0.0054900736 0.0065340000 0.0004370000 0.0044320000 0.0000040000 0.0000040000 0.0008460000 14425949 96830484 509673472 4.1143870354 4.3762722015 6.2608976364 440 17.5600000000 0.0106472000 0.0052490152 0.0290026348 0.0054908284 0.0064690000 0.0005050000 0.0032190000 0.0000020000 0.0000100000 0.0008670000 14428725 96830484 509673472 4.1091661453 4.3764448166 6.2630467415 441 17.6000000000 0.0106877647 0.0052613480 0.0290026348 0.0054894825 0.0056290000 0.0004690000 0.0027550000 0.0000080000 0.0000070000 0.0012660000 14431501 96830484 509673472 4.1033549309 4.3761973381 6.2644815445 442 17.6400000000 0.0108849192 0.0052740710 0.0290026348 0.0054887157 0.0082270000 0.0005890000 0.0037810000 0.0000020000 0.0000140000 0.0010650000 14434277 96830484 509673472 4.0981259346 4.3750858307 6.2655959129 443 17.6800000000 0.0107540926 0.0052864412 0.0290026348 0.0054884865 0.0060560000 0.0005210000 0.0031690000 0.0000080000 0.0000060000 0.0009550000 14437053 96830484 509673472 4.0923833847 4.3760709763 6.2674412727 444 17.7200000000 0.0104537364 0.0052980793 0.0290026348 0.0054858338 0.0050640000 0.0004490000 0.0027310000 0.0000010000 0.0000080000 0.0007270000 14439829 96830484 509673472 4.0868930817 4.3752870560 6.2698884010 445 17.7600000000 0.0102377385 0.0053091796 0.0290026348 0.0054827571 0.0098950000 0.0006030000 0.0047600000 0.0000160000 0.0000140000 0.0017720000 14442605 96830484 509673472 4.0819387436 4.3748188019 6.2715253830 446 17.8000000000 0.0112504484 0.0053225009 0.0290026348 0.0054845497 0.0061330000 0.0005030000 0.0032120000 0.0000010000 0.0000100000 0.0008700000 14445381 96830484 509673472 4.0762948990 4.3750395775 6.2730474472 447 17.8400000000 0.0112986891 0.0053358704 0.0290026348 0.0054843004 0.0057120000 0.0005030000 0.0028580000 0.0000080000 0.0000080000 0.0009460000 14448157 96830484 509673472 4.0706191063 4.3746924400 6.2764821053 448 17.8800000000 0.0110952370 0.0053487261 0.0290026348 0.0054832808 0.0050150000 0.0004530000 0.0027240000 0.0000010000 0.0000060000 0.0007200000 14450933 96830484 509673472 4.0639758110 4.3743486404 6.2784104347 449 17.9200000000 0.0107110180 0.0053606689 0.0290026348 0.0054805364 0.0071030000 0.0004330000 0.0044810000 0.0000050000 0.0000040000 0.0012140000 14453709 96830484 509673472 4.0585269928 4.3729724884 6.2794127464 450 17.9600000000 0.0109219281 0.0053730272 0.0290026348 0.0054773664 0.0065770000 0.0004360000 0.0044820000 0.0000000000 0.0000050000 0.0006920000 14456485 96830484 509673472 4.0530219078 4.3719449043 6.2807765007 451 18.0000000000 0.0103007611 0.0053839535 0.0290026348 0.0054791089 0.0075660000 0.0004950000 0.0050590000 0.0000060000 0.0000050000 0.0008790000 14459261 96830484 509673472 4.0396938324 4.3699312210 6.2847137451 452 18.0400000000 0.0052889711 0.0053837433 0.0290026348 0.0054757868 0.0063670000 0.0004300000 0.0044860000 0.0000000000 0.0000050000 0.0006760000 14462037 96830484 509673472 4.0338087082 4.3635616302 6.2871346474 453 18.0800000000 0.0041987747 0.0053811275 0.0290026348 0.0054707924 0.0068320000 0.0004150000 0.0044820000 0.0000040000 0.0000030000 0.0012030000 14464813 96830484 509673472 4.0274205208 4.3591923714 6.2893238068 454 18.1200000000 0.0048431219 0.0053799425 0.0290026348 0.0054673824 0.0062120000 0.0004110000 0.0044640000 0.0000010000 0.0000040000 0.0006670000 14467589 96830484 509673472 4.0200309753 4.3562040329 6.2927889824 455 18.1600000000 0.0056812307 0.0053806046 0.0290026348 0.0054627350 0.0060750000 0.0004150000 0.0041140000 0.0000030000 0.0000030000 0.0008810000 14470365 96830484 509673472 4.0132913589 4.3549995422 6.2963113785 456 18.2000000000 0.0087110037 0.0053879082 0.0290026348 0.0054589610 0.0062200000 0.0004120000 0.0044750000 0.0000010000 0.0000040000 0.0006650000 14473141 96830484 509673472 4.0077252388 4.3497447968 6.2979249954 457 18.2400000000 0.0090015475 0.0053958155 0.0290026348 0.0054561577 0.0067410000 0.0004080000 0.0044640000 0.0000040000 0.0000030000 0.0011970000 14475917 96830484 509673472 4.0008316040 4.3491768837 6.3006110191 458 18.2800000000 0.0150419362 0.0054168769 0.0290026348 0.0054646897 0.0044640000 0.0004060000 0.0027080000 0.0000010000 0.0000030000 0.0006730000 14478693 96830484 509673472 3.9935989380 4.3428845406 6.3023262024 459 18.3200000000 0.0154750030 0.0054387900 0.0290026348 0.0054649007 0.0082930000 0.0006040000 0.0034830000 0.0000150000 0.0000140000 0.0012590000 14481469 96830484 509673472 3.9872605801 4.3413910866 6.3037910461 460 18.3600000000 0.0380852707 0.0055097606 0.0380852707 0.0055460579 0.0090670000 0.0005920000 0.0049980000 0.0000010000 0.0000150000 0.0010630000 14484245 96830484 509673472 3.9814791679 4.3173918724 6.3055038452 461 18.4000000000 0.0294800494 0.0055617569 0.0380852707 0.0055596847 0.0076470000 0.0004730000 0.0047180000 0.0000060000 0.0000050000 0.0012720000 14487021 96830484 509673472 3.9743301868 4.3247489929 6.3081560135 462 18.4400000000 0.1935897022 0.0059687438 0.1935897022 0.0094060230 0.0064550000 0.0004280000 0.0045120000 0.0000000000 0.0000040000 0.0006640000 14489797 96830484 509673472 3.9672443867 4.1597776413 6.3108339310 463 18.4800000000 0.8229851127 0.0077333580 0.8229851127 0.0306661367 0.0078570000 0.0005860000 0.0042900000 0.0000090000 0.0000080000 0.0010170000 14492573 96830484 509673472 3.9617068768 3.5305263996 6.3087115288 464 18.5200000000 0.6122922897 0.0090362867 0.8229851127 0.0321891568 0.0081810000 0.0005910000 0.0048250000 0.0000010000 0.0000100000 0.0008090000 14495349 96830484 509673472 3.9558324814 3.7397944927 6.3114209175 465 18.5600000000 0.7416282892 0.0106117534 0.8229851127 0.0326874283 0.0072960000 0.0004660000 0.0044940000 0.0000060000 0.0000050000 0.0012020000 14498125 96830484 509673472 3.9490458965 3.6092891693 6.3141441345 466 18.6000000000 0.6969183683 0.0120845144 0.8229851127 0.0327268042 0.0074130000 0.0005230000 0.0046960000 0.0000010000 0.0000070000 0.0007210000 14500901 96830484 509673472 3.9429056644 3.6527361870 6.3170428276 467 18.6400000000 0.6903548241 0.0135369133 0.8229851127 0.0326954915 0.0071290000 0.0005870000 0.0034380000 0.0000160000 0.0000140000 0.0011040000 14503677 96830484 509673472 3.9367558956 3.6597509384 6.3182320595 468 18.6800000000 0.6876434684 0.0149773119 0.8229851127 0.0326622639 0.0069200000 0.0004680000 0.0045870000 0.0000010000 0.0000070000 0.0006680000 14506453 96830484 509673472 3.9315557480 3.6615366936 6.3179407120 469 18.7200000000 0.6767868996 0.0163884198 0.8229851127 0.0326333854 0.0070910000 0.0004290000 0.0045170000 0.0000050000 0.0000040000 0.0011350000 14509229 96830484 509673472 3.9250879288 3.6723895073 6.3201556206 470 18.7600000000 0.6730034351 0.0177854730 0.8229851127 0.0325998110 0.0063190000 0.0004200000 0.0045030000 0.0000010000 0.0000050000 0.0006280000 14512005 96830484 509673472 3.9190557003 3.6751551628 6.3208055496 471 18.8000000000 0.6666769385 0.0191631619 0.8229851127 0.0325753346 0.0097710000 0.0005880000 0.0049800000 0.0000150000 0.0000130000 0.0011910000 14514781 96830484 509673472 3.9052858353 3.6772387028 6.3219461441 472 18.8400000000 0.6778495908 0.0205586840 0.8229851127 0.0325436393 0.0071390000 0.0005070000 0.0046490000 0.0000010000 0.0000070000 0.0007270000 14517557 96830484 509673472 3.9002995491 3.6648998260 6.3233084679 473 18.8800000000 0.6689884663 0.0219295715 0.8229851127 0.0325142836 0.0070210000 0.0004360000 0.0045680000 0.0000050000 0.0000040000 0.0011470000 14520333 96830484 509673472 3.8983335495 3.6716768742 6.3220891953 474 18.9200000000 0.6661941409 0.0232887794 0.8229851127 0.0324823012 0.0075960000 0.0005050000 0.0047810000 0.0000010000 0.0000110000 0.0007900000 14523109 96830484 509673472 3.8961031437 3.6726450920 6.3223280907 475 18.9600000000 0.6599095464 0.0246290337 0.8229851127 0.0324521682 0.0066200000 0.0005030000 0.0036610000 0.0000080000 0.0000060000 0.0009410000 14525885 96830484 509673472 3.8925037384 3.6781177521 6.3238759041 476 19.0000000000 0.6426970363 0.0259274959 0.8229851127 0.0324404724 0.0056620000 0.0004460000 0.0035450000 0.0000010000 0.0000060000 0.0006500000 14528661 96830484 509673472 3.8873906136 3.6926453114 6.3241930008 477 19.0400000000 0.6318438053 0.0271977607 0.8229851127 0.0324172398 0.0079090000 0.0005870000 0.0035050000 0.0000150000 0.0000140000 0.0017080000 14531437 96830484 509673472 3.8851234913 3.7012035847 6.3236351013 478 19.0800000000 0.6187384725 0.0284352935 0.8229851127 0.0324008013 0.0056050000 0.0004660000 0.0032220000 0.0000010000 0.0000050000 0.0006850000 14534213 96830484 509673472 3.8789219856 3.7120440006 6.3296408653 479 19.1200000000 0.5568217039 0.0295383967 0.8229851127 0.0325082831 0.0068620000 0.0004300000 0.0045490000 0.0000050000 0.0000050000 0.0008540000 14536989 96830484 509673472 3.8784563541 3.7739679813 6.3301849365 480 19.1600000000 0.5525396466 0.0306279826 0.8229851127 0.0324789749 0.0047560000 0.0004280000 0.0026610000 0.0000010000 0.0000050000 0.0006460000 14539765 96830484 509673472 3.8782989979 3.7776365280 6.3293762207 481 19.2000000000 0.5837048292 0.0317778305 0.8229851127 0.0324697573 0.0090680000 0.0007190000 0.0033990000 0.0000160000 0.0000140000 0.0016920000 14542541 96830484 509673472 3.8767364025 3.7457194328 6.3305406570 482 19.2400000000 0.6635263562 0.0330885121 0.8229851127 0.0326173400 0.0075270000 0.0005130000 0.0047230000 0.0000010000 0.0000080000 0.0007440000 14545317 96830484 509673472 3.8761563301 3.6661636829 6.3308539391 483 19.2800000000 0.5698054433 0.0341997273 0.8229851127 0.0329014155 0.0067080000 0.0004330000 0.0045210000 0.0000050000 0.0000040000 0.0008510000 14548093 96830484 509673472 3.8752229214 3.7586741447 6.3324594498 484 19.3200000000 0.5694137812 0.0353055415 0.8229851127 0.0328708626 0.0064250000 0.0005040000 0.0036630000 0.0000010000 0.0000080000 0.0007350000 14550869 96830484 509673472 3.8755319118 3.7585947514 6.3333516121 485 19.3600000000 0.5489862561 0.0363646770 0.8229851127 0.0328671556 0.0097310000 0.0005880000 0.0050040000 0.0000140000 0.0000130000 0.0017180000 14553645 96830484 509673472 3.8758404255 3.7789514065 6.3335447311 486 19.4000000000 0.4179921448 0.0371499187 0.8229851127 0.0334291692 0.0052760000 0.0004670000 0.0028190000 0.0000010000 0.0000090000 0.0007190000 14556421 96830484 509673472 3.8747379780 3.9099881649 6.3368120193 487 19.4400000000 0.6848717928 0.0384799431 0.8229851127 0.0354222881 0.0077500000 0.0005030000 0.0046880000 0.0000110000 0.0000090000 0.0010180000 14559197 96830484 509673472 3.8752515316 3.6432282925 6.3380093575 488 19.4800000000 0.4768872857 0.0393783188 0.8229851127 0.0367148377 0.0077050000 0.0005010000 0.0046920000 0.0000010000 0.0000100000 0.0008230000 14561973 96830484 509673472 3.8754229546 3.8501529694 6.3413653374 489 19.5200000000 0.2274057418 0.0397628329 0.8229851127 0.0384911846 0.0079730000 0.0005010000 0.0046060000 0.0000080000 0.0000070000 0.0013060000 14564749 96830484 509673472 3.8728575706 4.1001181602 6.3474617004 490 19.5600000000 0.7286987305 0.0411688245 0.8229851127 0.0444869993 0.0065170000 0.0005880000 0.0029560000 0.0000010000 0.0000150000 0.0009150000 14567525 96830484 509673472 3.8736515045 3.5995445251 6.3462371826 491 19.6000000000 0.5540707707 0.0422134314 0.8229851127 0.0451730030 0.0073050000 0.0004670000 0.0046300000 0.0000080000 0.0000070000 0.0009560000 14570301 96830484 509673472 3.8745698929 3.7745757103 6.3512220383 492 19.6400000000 0.0631572977 0.0422560002 0.8229851127 0.0533127714 0.0061400000 0.0004300000 0.0041460000 0.0000000000 0.0000040000 0.0006690000 14573077 96830484 509673472 3.8725461960 4.3920030594 6.3556594849 493 19.6800000000 0.0042280927 0.0421788645 0.8229851127 0.0533417297 0.0098320000 0.0005860000 0.0051670000 0.0000150000 0.0000150000 0.0017060000 14575853 96830484 509673472 3.8770678043 4.3326053619 6.3557682037 494 19.7200000000 0.0174920298 0.0421288911 0.8229851127 0.0532961726 0.0077580000 0.0005020000 0.0049690000 0.0000010000 0.0000070000 0.0007270000 14578629 96830484 509673472 3.8761491776 4.3473734856 6.3607249260 495 19.7600000000 0.0203264207 0.0420848457 0.8229851127 0.0532454695 0.0070520000 0.0004600000 0.0048020000 0.0000050000 0.0000050000 0.0008850000 14581405 96830484 509673472 3.8755128384 4.3501062393 6.3666305542 496 19.8000000000 0.0205788705 0.0420414869 0.8229851127 0.0531934799 0.0077710000 0.0005030000 0.0049690000 0.0000010000 0.0000080000 0.0007590000 14584181 96830484 509673472 3.8752269745 4.3511366844 6.3710541725 497 19.8400000000 0.0203516334 0.0419978454 0.8229851127 0.0531410195 0.0084250000 0.0005190000 0.0049640000 0.0000080000 0.0000060000 0.0013820000 14586957 96830484 509673472 3.8763513565 4.3521585464 6.3725433350 498 19.8800000000 0.0207058154 0.0419550903 0.8229851127 0.0530889710 0.0068420000 0.0004530000 0.0047950000 0.0000000000 0.0000040000 0.0006880000 14589733 96830484 509673472 3.8772256374 4.3530998230 6.3751807213 499 19.9200000000 0.0220113751 0.0419151229 0.8229851127 0.0530372265 0.0073690000 0.0005010000 0.0038300000 0.0000110000 0.0000090000 0.0010800000 14592509 96830484 509673472 3.8773014545 4.3540325165 6.3797349930 500 19.9600000000 0.0214843396 0.0418742613 0.8229851127 0.0529848300 0.0091720000 0.0005910000 0.0052070000 0.0000020000 0.0000140000 0.0010740000 14595285 96830484 509673472 3.8777785301 4.3546633720 6.3825559616 501 20.0000000000 0.0219486542 0.0418344897 0.8229851127 0.0529333764 0.0079320000 0.0004770000 0.0048380000 0.0000060000 0.0000060000 0.0013400000 14598061 96830484 509673472 3.8783605099 4.3556685448 6.3850917816 502 20.0400000000 0.0216196980 0.0417942212 0.8229851127 0.0528821438 0.0066990000 0.0004360000 0.0047410000 0.0000000000 0.0000040000 0.0007160000 14600837 96830484 509673472 3.8784751892 4.3557786942 6.3884053230 503 20.0800000000 0.0219780002 0.0417548251 0.8229851127 0.0528312760 0.0060160000 0.0004100000 0.0039420000 0.0000040000 0.0000030000 0.0009400000 14603613 96830484 509673472 3.8773632050 4.3570537567 6.3917946815 504 20.1200000000 0.0224316902 0.0417164855 0.8229851127 0.0527806451 0.0064720000 0.0004050000 0.0046800000 0.0000010000 0.0000030000 0.0007210000 14606389 96830484 509673472 3.8770191669 4.3577413559 6.3948020935 505 20.1600000000 0.0258775055 0.0416851212 0.8229851127 0.0527315222 0.0102960000 0.0005910000 0.0051830000 0.0000150000 0.0000130000 0.0018560000 14609165 96830484 509673472 3.8764810562 4.3620576859 6.3972330093 506 20.2000000000 0.0257366244 0.0416536025 0.8229851127 0.0526809925 0.0073770000 0.0004770000 0.0048590000 0.0000010000 0.0000060000 0.0007670000 14611941 96830484 509673472 3.8767049313 4.3621034622 6.3991680145 507 20.2400000000 0.0278383680 0.0416263535 0.8229851127 0.0526313005 0.0066510000 0.0004300000 0.0043590000 0.0000060000 0.0000040000 0.0009390000 14614717 96830484 509673472 3.8761775494 4.3638381958 6.4019813538 508 20.2800000000 0.0196201466 0.0415830342 0.8229851127 0.0525797295 0.0080140000 0.0005890000 0.0043790000 0.0000010000 0.0000110000 0.0009140000 14617493 96830484 509673472 3.8740861416 4.3549976349 6.4051914215 509 20.3200000000 0.0203160904 0.0415412524 0.8229851127 0.0525300962 0.0086670000 0.0005890000 0.0043360000 0.0000100000 0.0000100000 0.0015970000 14620269 96830484 509673472 3.8741648197 4.3551650047 6.4080209732 510 20.3600000000 0.0183211025 0.0414957226 0.8229851127 0.0524793785 0.0072050000 0.0004680000 0.0048590000 0.0000010000 0.0000060000 0.0007810000 14623045 96830484 509673472 3.8745565414 4.3537182808 6.4075260162 511 20.4000000000 0.0169726666 0.0414477323 0.8229851127 0.0524289654 0.0070240000 0.0004210000 0.0047440000 0.0000050000 0.0000040000 0.0009620000 14625821 96830484 509673472 3.8733534813 4.3519253731 6.4096236229 512 20.4400000000 0.0137394350 0.0413936146 0.8229851127 0.0523782571 0.0087430000 0.0005850000 0.0051980000 0.0000010000 0.0000100000 0.0009210000 14628597 96830484 509673472 3.8712391853 4.3490161896 6.4117751122 513 20.4800000000 0.0131279677 0.0413385158 0.8229851127 0.0523280327 0.0086040000 0.0004980000 0.0050060000 0.0000080000 0.0000060000 0.0014620000 14680525 96830484 509673472 3.8712165356 4.3485774994 6.4114046097 514 20.5200000000 0.0129202874 0.0412832274 0.8229851127 0.0522781396 0.0070660000 0.0004540000 0.0048570000 0.0000010000 0.0000050000 0.0007760000 14785701 96830484 509673472 3.8694593906 4.3484950066 6.4133381844 515 20.5600000000 0.0132643385 0.0412288218 0.8229851127 0.0522283447 0.0053860000 0.0004140000 0.0032670000 0.0000040000 0.0000030000 0.0009520000 14788477 96830484 509673472 3.8684029579 4.3486604691 6.4138002396 516 20.6000000000 0.0109373378 0.0411701174 0.8229851127 0.0521780082 0.0091690000 0.0005890000 0.0044950000 0.0000010000 0.0000150000 0.0011520000 14791253 96830484 509673472 3.8668656349 4.3460941315 6.4135293961 517 20.6400000000 0.0110393912 0.0411118375 0.8229851127 0.0521282607 0.0070300000 0.0004740000 0.0038010000 0.0000080000 0.0000060000 0.0014050000 14794029 96830484 509673472 3.8657619953 4.3457317352 6.4123907089 518 20.6800000000 0.0082281316 0.0410483554 0.8229851127 0.0520782241 0.0056600000 0.0004320000 0.0033350000 0.0000010000 0.0000060000 0.0007660000 14796805 96830484 509673472 3.8642103672 4.3419308662 6.4123749733 519 20.7200000000 0.0086010844 0.0409858366 0.8229851127 0.0520290870 0.0095990000 0.0005920000 0.0053050000 0.0000140000 0.0000130000 0.0013630000 14799581 96830484 509673472 3.8611023426 4.3422455788 6.4133582115 520 20.7600000000 0.0041480209 0.0409149946 0.8229851127 0.0519792345 0.0056740000 0.0004740000 0.0030470000 0.0000010000 0.0000060000 0.0007970000 14802357 96830484 509673472 3.8592345715 4.3343062401 6.4138164520 521 20.8000000000 0.0047991052 0.0408456743 0.8229851127 0.0519302055 0.0065090000 0.0004400000 0.0037110000 0.0000050000 0.0000040000 0.0013720000 14805133 96830484 509673472 3.8570852280 4.3349170685 6.4126715660 522 20.8400000000 0.0043159062 0.0407756939 0.8229851127 0.0518808005 0.0104290000 0.0005960000 0.0053100000 0.0000010000 0.0000150000 0.0011810000 14807909 96830484 509673472 3.8541753292 4.3302435875 6.4125576019 523 20.8800000000 0.0066851727 0.0407105113 0.8229851127 0.0518313473 0.0078960000 0.0005020000 0.0050040000 0.0000070000 0.0000050000 0.0010140000 14810685 96830484 509673472 3.8536784649 4.3265671730 6.4071364403 524 20.9200000000 0.0076259635 0.0406473728 0.8229851127 0.0517825866 0.0070770000 0.0004360000 0.0049000000 0.0000010000 0.0000040000 0.0007640000 14813461 96830484 509673472 3.8520643711 4.3237266541 6.4062929153 525 20.9600000000 0.0072592571 0.0405837764 0.8229851127 0.0517337137 0.0055740000 0.0004190000 0.0029370000 0.0000040000 0.0000040000 0.0013650000 14816237 96830484 509673472 3.8488984108 4.3218512535 6.4065604210 526 21.0000000000 0.0150917964 0.0405353126 0.8229851127 0.0516848269 0.0067990000 0.0004120000 0.0048320000 0.0000000000 0.0000030000 0.0007700000 14819013 96830484 509673472 3.8460538387 4.3136124611 6.4035634995 527 21.0400000000 0.0172502082 0.0404911283 0.8229851127 0.0516359528 0.0096430000 0.0006070000 0.0053110000 0.0000160000 0.0000160000 0.0013830000 14821789 96830484 509673472 3.8434073925 4.3112721443 6.3995661736 528 21.0800000000 0.0190026164 0.0404504304 0.8229851127 0.0515873953 0.0076450000 0.0004760000 0.0049790000 0.0000000000 0.0000060000 0.0008080000 14824565 96830484 509673472 3.8390970230 4.3073387146 6.3996977806 529 21.1200000000 0.0189405885 0.0404097690 0.8229851127 0.0515394412 0.0075270000 0.0004230000 0.0048400000 0.0000040000 0.0000030000 0.0013800000 14827341 96830484 509673472 3.8349170685 4.3063654900 6.3979492188 530 21.1600000000 0.0189743508 0.0403693249 0.8229851127 0.0514910343 0.0067220000 0.0004120000 0.0048150000 0.0000000000 0.0000040000 0.0007660000 14830117 96830484 509673472 3.8322768211 4.3069810867 6.3934555054 531 21.2000000000 0.0181254745 0.0403274344 0.8229851127 0.0514428486 0.0069230000 0.0004080000 0.0047990000 0.0000030000 0.0000030000 0.0009910000 14832893 96830484 509673472 3.8289535046 4.3068442345 6.3905282021 532 21.2400000000 0.0198428333 0.0402889295 0.8229851127 0.0513947335 0.0067370000 0.0004080000 0.0048320000 0.0000000000 0.0000030000 0.0007650000 14835669 96830484 509673472 3.8244760036 4.3046183586 6.3885941505 533 21.2800000000 0.0213283878 0.0402533562 0.8229851127 0.0513466840 0.0073230000 0.0004180000 0.0047880000 0.0000030000 0.0000030000 0.0013810000 14838445 96830484 509673472 3.8207840919 4.3024926186 6.3860735893 534 21.3200000000 0.0256102234 0.0402259346 0.8229851127 0.0512985916 0.0106030000 0.0005930000 0.0053160000 0.0000020000 0.0000230000 0.0011790000 14841221 96830484 509673472 3.8167550564 4.2956371307 6.3843283653 535 21.3600000000 0.0267675687 0.0402007788 0.8229851127 0.0512512026 0.0079730000 0.0005090000 0.0050130000 0.0000070000 0.0000070000 0.0010530000 14843997 96830484 509673472 3.8114178181 4.2931485176 6.3841147423 536 21.4000000000 0.0311115608 0.0401838213 0.8229851127 0.0512035866 0.0071050000 0.0004410000 0.0048930000 0.0000010000 0.0000050000 0.0007710000 14846773 96830484 509673472 3.8074402809 4.2884073257 6.3811192513 537 21.4400000000 0.0327689163 0.0401700133 0.8229851127 0.0511558415 0.0062760000 0.0004130000 0.0036760000 0.0000040000 0.0000030000 0.0013940000 14849549 96830484 509673472 3.8031694889 4.2872362137 6.3764476776 538 21.4800000000 0.0349198096 0.0401602546 0.8229851127 0.0511082151 0.0067720000 0.0004060000 0.0048320000 0.0000010000 0.0000030000 0.0007630000 14852325 96830484 509673472 3.7983899117 4.2855935097 6.3726534843 539 21.5200000000 0.0357259028 0.0401520276 0.8229851127 0.0510608561 0.0070740000 0.0004060000 0.0048140000 0.0000030000 0.0000030000 0.0009940000 14855101 96830484 509673472 3.7941153049 4.2836551666 6.3702383041 540 21.5600000000 0.0405344926 0.0401527358 0.8229851127 0.0510135502 0.0069660000 0.0004610000 0.0048480000 0.0000000000 0.0000030000 0.0007680000 14857877 96830484 509673472 3.7890944481 4.2785511017 6.3677449226 541 21.6000000000 0.0424984545 0.0401570717 0.8229851127 0.0509671331 0.0111960000 0.0005960000 0.0053230000 0.0000150000 0.0000140000 0.0019690000 14860653 96830484 509673472 3.7841844559 4.2756237984 6.3662209511 542 21.6400000000 0.0477547236 0.0401710895 0.8229851127 0.0509214464 0.0076600000 0.0004700000 0.0049970000 0.0000010000 0.0000060000 0.0008030000 14863429 96830484 509673472 3.7799994946 4.2674789429 6.3645877838 543 21.6800000000 0.0516613685 0.0401922503 0.8229851127 0.0508758184 0.0073200000 0.0004390000 0.0048770000 0.0000050000 0.0000040000 0.0009990000 14866205 96830484 509673472 3.7757244110 4.2614898682 6.3609924316 544 21.7200000000 0.0563322455 0.0402219194 0.8229851127 0.0508369118 0.0067060000 0.0004150000 0.0047990000 0.0000010000 0.0000030000 0.0007630000 14868981 96830484 509673472 3.7681190968 4.2535176277 6.3499913216 545 21.7600000000 0.0533879362 0.0402460772 0.8229851127 0.0507903439 0.0084580000 0.0005050000 0.0046850000 0.0000100000 0.0000090000 0.0015240000 14871757 96830484 509673472 3.7633008957 4.2589340210 6.3427233696 546 21.8000000000 0.0579544045 0.0402785100 0.8229851127 0.0507440942 0.0073350000 0.0004460000 0.0049590000 0.0000010000 0.0000050000 0.0007680000 14874533 96830484 509673472 3.7587828636 4.2534985542 6.3374886513 547 21.8400000000 0.0627047718 0.0403195087 0.8229851127 0.0506990378 0.0060180000 0.0004210000 0.0037360000 0.0000040000 0.0000040000 0.0009820000 14877309 96830484 509673472 3.7541897297 4.2464284897 6.3320217133 548 21.8800000000 0.0654260591 0.0403653236 0.8229851127 0.0506527529 0.0085840000 0.0006060000 0.0032790000 0.0000020000 0.0000150000 0.0011610000 14880085 96830484 509673472 3.7484226227 4.2482566833 6.3253903389 549 21.9200000000 0.0651324168 0.0404104367 0.8229851127 0.0506072045 0.0084490000 0.0005040000 0.0050430000 0.0000070000 0.0000070000 0.0014650000 14882861 96830484 509673472 3.7432494164 4.2512354851 6.3203568459 550 21.9600000000 0.0694731176 0.0404632779 0.8229851127 0.0505625601 0.0069980000 0.0004350000 0.0047540000 0.0000000000 0.0000040000 0.0007660000 14885637 96830484 509673472 3.7397634983 4.2394013405 6.3169226646 551 22.0000000000 0.0672209114 0.0405118398 0.8229851127 0.0505173696 0.0094260000 0.0005960000 0.0052750000 0.0000110000 0.0000100000 0.0011900000 14888413 96830484 509673472 3.7355482578 4.2404131889 6.3094973564 552 22.0400000000 0.0678071007 0.0405612878 0.8229851127 0.0504716327 0.0073670000 0.0004650000 0.0049270000 0.0000010000 0.0000050000 0.0007730000 14891189 96830484 509673472 3.7300202847 4.2459230423 6.3021922112 553 22.0800000000 0.0713006631 0.0406168744 0.8229851127 0.0504260431 0.0075090000 0.0004190000 0.0048650000 0.0000030000 0.0000030000 0.0013810000 14893965 96830484 509673472 3.7258944511 4.2433938980 6.2973175049 554 22.1200000000 0.0759642124 0.0406806782 0.8229851127 0.0503807018 0.0055750000 0.0004070000 0.0036690000 0.0000000000 0.0000030000 0.0007500000 14896741 96830484 509673472 3.7215642929 4.2362432480 6.2945289612 555 22.1600000000 0.0733983964 0.0407396291 0.8229851127 0.0503355929 0.0069760000 0.0004060000 0.0048240000 0.0000030000 0.0000030000 0.0009900000 14899517 96830484 509673472 3.7176733017 4.2393403053 6.2902221680 556 22.2000000000 0.0735066459 0.0407985625 0.8229851127 0.0502909133 0.0063480000 0.0004030000 0.0044510000 0.0000000000 0.0000030000 0.0007450000 14902293 96830484 509673472 3.7141032219 4.2372708321 6.2892541885 557 22.2400000000 0.0714010000 0.0408535041 0.8229851127 0.0502466344 0.0114870000 0.0005910000 0.0053250000 0.0000150000 0.0000140000 0.0019740000 14905069 96830484 509673472 3.7097129822 4.2414598465 6.2864532471 558 22.2800000000 0.0749708265 0.0409146462 0.8229851127 0.0502029245 0.0082660000 0.0005060000 0.0051050000 0.0000010000 0.0000070000 0.0008520000 14907845 96830484 509673472 3.7062158585 4.2370958328 6.2874073982 559 22.3200000000 0.0827708095 0.0409895231 0.8229851127 0.0501982359 0.0075090000 0.0004520000 0.0048680000 0.0000050000 0.0000050000 0.0009820000 14910621 96830484 509673472 3.7022368908 4.2438526154 6.3230876923 560 22.3600000000 0.1386061162 0.0411638384 0.8229851127 0.0502490095 0.0067440000 0.0004240000 0.0047590000 0.0000000000 0.0000040000 0.0007150000 14913397 96830484 509673472 3.6981205940 4.2315349579 6.3801608086 561 22.4000000000 0.1312661022 0.0413244485 0.8229851127 0.0502084518 0.0072600000 0.0004040000 0.0047460000 0.0000040000 0.0000030000 0.0013490000 14916173 96830484 509673472 3.6948745251 4.2485637665 6.3750295639 562 22.4400000000 0.1178309843 0.0414605812 0.8229851127 0.0501694378 0.0089680000 0.0005910000 0.0051950000 0.0000010000 0.0000110000 0.0009170000 14918949 96830484 509673472 3.6914763451 4.2636070251 6.3656439781 563 22.4800000000 0.1120176241 0.0415859045 0.8229851127 0.0501268189 0.0075810000 0.0004650000 0.0048720000 0.0000050000 0.0000050000 0.0010060000 14921725 96830484 509673472 3.6886236668 4.2742934227 6.3575057983 564 22.5200000000 0.1228144467 0.0417299267 0.8229851127 0.0500849106 0.0069490000 0.0004220000 0.0048560000 0.0000000000 0.0000040000 0.0007440000 14924501 96830484 509673472 3.6853344440 4.2752566338 6.3615341187 565 22.5600000000 0.1676811278 0.0419528492 0.8229851127 0.0500723953 0.0075300000 0.0004150000 0.0048500000 0.0000040000 0.0000040000 0.0013360000 14927277 96830484 509673472 3.6773023605 4.2521510124 6.3862638474 566 22.6000000000 0.1839098483 0.0422036566 0.8229851127 0.0500387208 0.0098950000 0.0005930000 0.0053080000 0.0000020000 0.0000170000 0.0010820000 14930053 96830484 509673472 3.6734685898 4.2618193626 6.4004049301 567 22.6400000000 0.2060835361 0.0424926864 0.8229851127 0.0500034580 0.0078230000 0.0004800000 0.0048530000 0.0000060000 0.0000060000 0.0010190000 14932829 96830484 509673472 3.6697933674 4.2528347969 6.4144930840 568 22.6800000000 0.2172989845 0.0428004440 0.8229851127 0.0499608683 0.0062950000 0.0004320000 0.0041230000 0.0000000000 0.0000040000 0.0007240000 14935605 96830484 509673472 3.6662685871 4.2473683357 6.4165201187 569 22.7200000000 0.2366598099 0.0431411459 0.8229851127 0.0499259887 0.0076430000 0.0004620000 0.0048710000 0.0000040000 0.0000030000 0.0013350000 14938381 96830484 509673472 3.6623611450 4.2524046898 6.4301757812 570 22.7600000000 0.2833871543 0.0435626301 0.8229851127 0.0499375571 0.0066520000 0.0004110000 0.0047850000 0.0000000000 0.0000030000 0.0006530000 14941157 96830484 509673472 3.6583175659 4.2641735077 6.4751653671 571 22.8000000000 0.2867240906 0.0439884820 0.8229851127 0.0499011979 0.0109980000 0.0006070000 0.0053210000 0.0000160000 0.0000130000 0.0013360000 14943933 96830484 509673472 3.6558520794 4.2846994400 6.4737200737 572 22.8400000000 0.2925641239 0.0444230548 0.8229851127 0.0498609605 0.0108240000 0.0006100000 0.0053880000 0.0000020000 0.0000170000 0.0010890000 14946709 96830484 509673472 3.6526613235 4.2701220512 6.4697713852 573 22.8800000000 0.3029059768 0.0448741594 0.8229851127 0.0498442811 0.0116080000 0.0006080000 0.0053440000 0.0000150000 0.0000140000 0.0019290000 14949485 96830484 509673472 3.6484069824 4.3093051910 6.4757294655 574 22.9200000000 0.3074436486 0.0453315975 0.8229851127 0.0498042817 0.0078890000 0.0005080000 0.0050890000 0.0000010000 0.0000090000 0.0007900000 14952261 96830484 509673472 3.6436479092 4.2868938446 6.4731388092 575 22.9600000000 0.3090160787 0.0457901792 0.8229851127 0.0497643681 0.0074500000 0.0004380000 0.0049370000 0.0000050000 0.0000040000 0.0009970000 14955037 96830484 509673472 3.6409986019 4.2994523048 6.4669589996 576 23.0000000000 0.3573729396 0.0463311215 0.8229851127 0.0497708554 0.0068590000 0.0004130000 0.0048930000 0.0000000000 0.0000030000 0.0007090000 14957813 96830484 509673472 3.6367349625 4.2917575836 6.5095753670 577 23.0400000000 0.3631586134 0.0468802160 0.8229851127 0.0497332599 0.0090930000 0.0005090000 0.0051770000 0.0000080000 0.0000070000 0.0015360000 14960589 96830484 509673472 3.6325082779 4.3066701889 6.5076832771 578 23.0800000000 0.3928496242 0.0474787790 0.8229851127 0.0497138881 0.0072660000 0.0004550000 0.0050080000 0.0000010000 0.0000060000 0.0007240000 14963365 96830484 509673472 3.6297612190 4.2908630371 6.5300979614 579 23.1200000000 0.4088007510 0.0481028238 0.8229851127 0.0496779371 0.0086570000 0.0005020000 0.0051730000 0.0000110000 0.0000090000 0.0011100000 14966141 96830484 509673472 3.6279749870 4.3067970276 6.5369963646 580 23.1600000000 0.4288023114 0.0487592022 0.8229851127 0.0496416102 0.0074470000 0.0004470000 0.0050050000 0.0000010000 0.0000050000 0.0007440000 14968917 96830484 509673472 3.6263742447 4.2988362312 6.5499577522 581 23.2000000000 0.4609883130 0.0494687188 0.8229851127 0.0496215841 0.0090810000 0.0005040000 0.0050970000 0.0000070000 0.0000070000 0.0015450000 14971693 96830484 509673472 3.6208090782 4.3168730736 6.5750555992 582 23.2400000000 0.4784649312 0.0502058257 0.8229851127 0.0495879021 0.0072410000 0.0004460000 0.0049610000 0.0000000000 0.0000050000 0.0007550000 14974469 96830484 509673472 3.6133210659 4.3213605881 6.5858082771 583 23.2800000000 0.4934185743 0.0509660534 0.8229851127 0.0495501632 0.0072090000 0.0004140000 0.0048840000 0.0000040000 0.0000030000 0.0010440000 14977245 96830484 509673472 3.6109187603 4.3242740631 6.5937128067 584 23.3200000000 0.5119342804 0.0517553825 0.8229851127 0.0495129302 0.0068220000 0.0004040000 0.0048610000 0.0000000000 0.0000040000 0.0007550000 14980021 96830484 509673472 3.6071829796 4.3182678223 6.6059508324 585 23.3600000000 0.5224117041 0.0525599233 0.8229851127 0.0494721413 0.0075100000 0.0004080000 0.0048640000 0.0000040000 0.0000030000 0.0014270000 14982797 96830484 509673472 3.6005692482 4.3151025772 6.6095323563 586 23.4000000000 0.5212914348 0.0533598064 0.8229851127 0.0494300511 0.0097500000 0.0005890000 0.0053850000 0.0000020000 0.0000160000 0.0011210000 14985573 96830484 509673472 3.5974102020 4.3110375404 6.6026172638 587 23.4400000000 0.5251376033 0.0541635164 0.8229851127 0.0493908458 0.0080420000 0.0004770000 0.0050140000 0.0000070000 0.0000050000 0.0010680000 14988349 96830484 509673472 3.5928058624 4.3188610077 6.5997915268 588 23.4800000000 0.5201924443 0.0549560826 0.8229851127 0.0493506058 0.0071280000 0.0004270000 0.0049840000 0.0000000000 0.0000040000 0.0007520000 14991125 96830484 509673472 3.5859975815 4.3151822090 6.5883007050 589 23.5200000000 0.5200207829 0.0557456662 0.8229851127 0.0493109937 0.0085640000 0.0005030000 0.0049920000 0.0000070000 0.0000070000 0.0015270000 14993901 96830484 509673472 3.5796678066 4.3203010559 6.5802536011 590 23.5600000000 0.5193865895 0.0565314982 0.8229851127 0.0492697765 0.0061320000 0.0004310000 0.0038450000 0.0000000000 0.0000040000 0.0007530000 14996677 96830484 509673472 3.5736391544 4.3203401566 6.5720829964 591 23.6000000000 0.5188676119 0.0573137928 0.8229851127 0.0492284274 0.0065310000 0.0004170000 0.0041780000 0.0000040000 0.0000040000 0.0010460000 14999453 96830484 509673472 3.5672574043 4.3204326630 6.5643510818 592 23.6400000000 0.5178158879 0.0580916680 0.8229851127 0.0491868654 0.0068910000 0.0004070000 0.0048680000 0.0000010000 0.0000040000 0.0007510000 15002229 96830484 509673472 3.5609796047 4.3172669411 6.5557022095 593 23.6800000000 0.5171452165 0.0588657887 0.8229851127 0.0491464277 0.0093830000 0.0006070000 0.0033820000 0.0000150000 0.0000130000 0.0020050000 15005005 96830484 509673472 3.5550267696 4.3211259842 6.5471067429 594 23.7200000000 0.5159103274 0.0596352239 0.8229851127 0.0491058899 0.0067980000 0.0004810000 0.0039240000 0.0000010000 0.0000070000 0.0007930000 15007781 96830484 509673472 3.5477566719 4.3208379745 6.5385556221 595 23.7600000000 0.5149048567 0.0604003830 0.8229851127 0.0490654713 0.0060100000 0.0004300000 0.0034240000 0.0000060000 0.0000040000 0.0010280000 15010557 96830484 509673472 3.5392143726 4.3199739456 6.5296392441 596 23.8000000000 0.5131657124 0.0611600563 0.8229851127 0.0490261438 0.0059680000 0.0004140000 0.0038100000 0.0000000000 0.0000040000 0.0007460000 15013333 96830484 509673472 3.5318210125 4.3260869980 6.5191736221 597 23.8400000000 0.5125185251 0.0619161007 0.8229851127 0.0489851798 0.0066180000 0.0004120000 0.0037950000 0.0000040000 0.0000040000 0.0014190000 15016109 96830484 509673472 3.5279526711 4.3282279968 6.5103249550 598 23.8800000000 0.5120346546 0.0626688073 0.8229851127 0.0489445766 0.0071530000 0.0004150000 0.0050010000 0.0000010000 0.0000050000 0.0007510000 15018885 96830484 509673472 3.5194392204 4.3277344704 6.5018191338 599 23.9200000000 0.5110466480 0.0634173513 0.8229851127 0.0489048673 0.0058570000 0.0004110000 0.0034020000 0.0000040000 0.0000040000 0.0010480000 15021661 96830484 509673472 3.5110657215 4.3316855431 6.4915585518 600 23.9600000000 0.5103125572 0.0641621766 0.8229851127 0.0488654219 0.0071560000 0.0004160000 0.0049940000 0.0000010000 0.0000040000 0.0007500000 15024437 96830484 509673472 3.5051558018 4.3357138634 6.4821715355 601 24.0000000000 0.5092680454 0.0649027854 0.8229851127 0.0488265399 0.0078200000 0.0004140000 0.0049750000 0.0000040000 0.0000030000 0.0014350000 15027213 96830484 509673472 3.4976882935 4.3394198418 6.4723205566 602 24.0400000000 0.5082732439 0.0656392811 0.8229851127 0.0487915360 0.0095960000 0.0005940000 0.0050190000 0.0000010000 0.0000150000 0.0011360000 15029989 96830484 509673472 3.4814426899 4.3471832275 6.4528331757 603 24.0800000000 0.5071925521 0.0663715420 0.8229851127 0.0487522099 0.0070710000 0.0004770000 0.0039060000 0.0000060000 0.0000050000 0.0011110000 15032765 96830484 509673472 3.4722945690 4.3462772369 6.4439320564 604 24.1200000000 0.5072759986 0.0671015162 0.8229851127 0.0487140397 0.0057350000 0.0004310000 0.0034070000 0.0000000000 0.0000040000 0.0007750000 15035541 96830484 509673472 3.4605314732 4.3504481316 6.4341812134 605 24.1600000000 0.5060248971 0.0678270094 0.8229851127 0.0486762165 0.0091530000 0.0005920000 0.0033550000 0.0000150000 0.0000150000 0.0020620000 15038317 96830484 509673472 3.4543223381 4.3596539497 6.4228453636 606 24.2000000000 0.5109959841 0.0685583114 0.8229851127 0.0486564389 0.0055780000 0.0004730000 0.0027030000 0.0000010000 0.0000080000 0.0008360000 15041093 96830484 509673472 3.4487547874 4.3252758980 6.4254450798 607 24.2400000000 0.5101985335 0.0692858900 0.8229851127 0.0486169741 0.0070740000 0.0005110000 0.0031620000 0.0000110000 0.0000090000 0.0012700000 15043869 96830484 509673472 3.4419116974 4.3264393806 6.4156928062 608 24.2800000000 0.5107086897 0.0700119143 0.8229851127 0.0485777103 0.0084180000 0.0005090000 0.0051970000 0.0000010000 0.0000080000 0.0009190000 15046645 96830484 509673472 3.4338121414 4.3207297325 6.4077048302 609 24.3200000000 0.5106865168 0.0707355179 0.8229851127 0.0485388721 0.0092190000 0.0005080000 0.0051990000 0.0000080000 0.0000070000 0.0016950000 15049421 96830484 509673472 3.4256722927 4.3161029816 6.4000811577 610 24.3600000000 0.5102186203 0.0714559820 0.8229851127 0.0485001725 0.0074420000 0.0004540000 0.0050380000 0.0000010000 0.0000040000 0.0008080000 15052197 96830484 509673472 3.4207158089 4.3154268265 6.3913664818 611 24.4000000000 0.5099321604 0.0721736190 0.8229851127 0.0484609400 0.0073690000 0.0004110000 0.0049550000 0.0000040000 0.0000030000 0.0010900000 15054973 96830484 509673472 3.4159440994 4.3084950447 6.3833103180 612 24.4400000000 0.5098736286 0.0728888151 0.8229851127 0.0484226027 0.0065990000 0.0004030000 0.0045760000 0.0000000000 0.0000030000 0.0007910000 15057749 96830484 509673472 3.4093747139 4.3094878197 6.3743901253 613 24.4800000000 0.5097433925 0.0736014653 0.8229851127 0.0483839760 0.0072730000 0.0004020000 0.0045510000 0.0000040000 0.0000030000 0.0014870000 15060525 96830484 509673472 3.4023108482 4.3080873489 6.3653292656 614 24.5200000000 0.5127774477 0.0743167356 0.8229851127 0.0483458562 0.0070030000 0.0004010000 0.0049720000 0.0000000000 0.0000030000 0.0007990000 15063301 96830484 509673472 3.3955738544 4.3023362160 6.3612318039 615 24.5600000000 0.5118503571 0.0750281724 0.8229851127 0.0483072719 0.0072940000 0.0004050000 0.0049500000 0.0000030000 0.0000020000 0.0011100000 15066077 96830484 509673472 3.3900206089 4.3002800941 6.3517255783 616 24.6000000000 0.5125592947 0.0757384502 0.8229851127 0.0482689326 0.0096340000 0.0005880000 0.0038280000 0.0000020000 0.0000150000 0.0012790000 15068853 96830484 509673472 3.3825864792 4.2994661331 6.3430290222 617 24.6400000000 0.5123885274 0.0764461489 0.8229851127 0.0482308481 0.0088660000 0.0005090000 0.0051260000 0.0000060000 0.0000050000 0.0016070000 15071629 96830484 509673472 3.3754947186 4.2980556488 6.3338294029 618 24.6800000000 0.5120866895 0.0771510688 0.8229851127 0.0481928174 0.0058350000 0.0004350000 0.0034300000 0.0000000000 0.0000040000 0.0008190000 15074405 96830484 509673472 3.3711292744 4.2968411446 6.3247985840 619 24.7200000000 0.5143259168 0.0778573287 0.8229851127 0.0481545072 0.0058490000 0.0004120000 0.0033950000 0.0000040000 0.0000040000 0.0011270000 15077181 96830484 509673472 3.3677697182 4.2972021103 6.3194618225 620 24.7600000000 0.5137740374 0.0785604201 0.8229851127 0.0481189877 0.0099090000 0.0005910000 0.0055010000 0.0000020000 0.0000150000 0.0011230000 15079957 96830484 509673472 3.3554704189 4.2937874794 6.2999448776 621 24.8000000000 0.5144506693 0.0792623368 0.8229851127 0.0480809004 0.0072260000 0.0004730000 0.0034720000 0.0000060000 0.0000050000 0.0016810000 15082733 96830484 509673472 3.3509650230 4.2911763191 6.2924447060 622 24.8400000000 0.5130065084 0.0799596747 0.8229851127 0.0480430201 0.0074940000 0.0005050000 0.0039980000 0.0000010000 0.0000110000 0.0009620000 15085509 96830484 509673472 3.3441121578 4.2887949944 6.2811226845 623 24.8800000000 0.5136461258 0.0806558006 0.8229851127 0.0480048681 0.0063970000 0.0004440000 0.0034280000 0.0000050000 0.0000050000 0.0011720000 15088285 96830484 509673472 3.3387773037 4.2864017487 6.2726945877 624 24.9200000000 0.5129569769 0.0813485910 0.8229851127 0.0479664887 0.0058140000 0.0004640000 0.0033830000 0.0000000000 0.0000040000 0.0008510000 15091061 96830484 509673472 3.3331992626 4.2826342583 6.2628297806 625 24.9600000000 0.5145642161 0.0820417360 0.8229851127 0.0479283107 0.0103460000 0.0005910000 0.0037870000 0.0000150000 0.0000130000 0.0022220000 15093837 96830484 509673472 3.3275358677 4.2815995216 6.2538385391 626 25.0000000000 0.5161039829 0.0827351262 0.8229851127 0.0478903054 0.0068760000 0.0004720000 0.0039020000 0.0000010000 0.0000070000 0.0008900000 15096613 96830484 509673472 3.3204381466 4.2811770439 6.2446584702 627 25.0400000000 0.5161552429 0.0834263863 0.8229851127 0.0478527602 0.0061770000 0.0004300000 0.0034130000 0.0000050000 0.0000040000 0.0011760000 15099389 96830484 509673472 3.3154275417 4.2788844109 6.2348008156 628 25.0800000000 0.5160384178 0.0841152590 0.8229851127 0.0478151469 0.0080900000 0.0005870000 0.0037530000 0.0000020000 0.0000170000 0.0010810000 15102165 96830484 509673472 3.3101229668 4.2760925293 6.2247915268 629 25.1200000000 0.5160872340 0.0848020189 0.8229851127 0.0477773655 0.0085220000 0.0004790000 0.0050620000 0.0000060000 0.0000060000 0.0016200000 15104941 96830484 509673472 3.3031814098 4.2746849060 6.2123150826 630 25.1600000000 0.5154383779 0.0854855686 0.8229851127 0.0477402823 0.0072280000 0.0004190000 0.0049590000 0.0000010000 0.0000040000 0.0008270000 15107717 96830484 509673472 3.2989563942 4.2731413841 6.2016820908 631 25.2000000000 0.5172725320 0.0861698586 0.8229851127 0.0477026279 0.0080480000 0.0005890000 0.0033730000 0.0000100000 0.0000090000 0.0013860000 15110493 96830484 509673472 3.2956554890 4.2711200714 6.1935076714 632 25.2400000000 0.5156205297 0.0868493692 0.8229851127 0.0476649885 0.0063590000 0.0004670000 0.0034800000 0.0000000000 0.0000060000 0.0008700000 15113269 96830484 509673472 3.2888312340 4.2693543434 6.1789655685 633 25.2800000000 0.5159219503 0.0875272089 0.8229851127 0.0476279299 0.0072100000 0.0004230000 0.0041960000 0.0000040000 0.0000040000 0.0015600000 15116045 96830484 509673472 3.2825808525 4.2662329674 6.1672968864 634 25.3200000000 0.5149078369 0.0882013109 0.8229851127 0.0475905251 0.0086410000 0.0005030000 0.0051860000 0.0000010000 0.0000080000 0.0009340000 15118821 96830484 509673472 3.2796139717 4.2643461227 6.1562037468 635 25.3600000000 0.5157352090 0.0888745926 0.8229851127 0.0475534200 0.0062590000 0.0004450000 0.0033110000 0.0000050000 0.0000040000 0.0011710000 15121597 96830484 509673472 3.2788050175 4.2625608444 6.1486053467 636 25.4000000000 0.5169247985 0.0895476275 0.8229851127 0.0475195951 0.0062010000 0.0004180000 0.0038000000 0.0000010000 0.0000050000 0.0008160000 15124373 96830484 509673472 3.2695789337 4.2602968216 6.1356511116 637 25.4400000000 0.5167962909 0.0902183476 0.8229851127 0.0474822915 0.0108750000 0.0005840000 0.0050250000 0.0000150000 0.0000130000 0.0022050000 15127149 96830484 509673472 3.2605416775 4.2592697144 6.1212334633 638 25.4800000000 0.5168170929 0.0908869976 0.8229851127 0.0474460920 0.0068600000 0.0004730000 0.0038940000 0.0000010000 0.0000070000 0.0008590000 15129925 96830484 509673472 3.2604691982 4.2589163780 6.1117863655 639 25.5200000000 0.5164399147 0.0915529646 0.8229851127 0.0474089508 0.0053680000 0.0004300000 0.0026210000 0.0000050000 0.0000050000 0.0011440000 15132701 96830484 509673472 3.2561478615 4.2573943138 6.0997972488 640 25.5600000000 0.5160719156 0.0922162755 0.8229851127 0.0473721152 0.0081260000 0.0005870000 0.0037660000 0.0000020000 0.0000090000 0.0010680000 15135477 96830484 509673472 3.2521409988 4.2552046776 6.0870285034 641 25.6000000000 0.5169649124 0.0928789099 0.8229851127 0.0473354689 0.0087120000 0.0005880000 0.0033470000 0.0000150000 0.0000130000 0.0019400000 15138253 96830484 509673472 3.2496037483 4.2534151077 6.0768880844 642 25.6400000000 0.5166386962 0.0935389718 0.8229851127 0.0472985414 0.0060700000 0.0004730000 0.0030710000 0.0000000000 0.0000060000 0.0008880000 15141029 96830484 509673472 3.2464687824 4.2510070801 6.0646791458 643 25.6800000000 0.5162076354 0.0941963104 0.8229851127 0.0472617160 0.0078240000 0.0005030000 0.0039870000 0.0000080000 0.0000070000 0.0012800000 15143805 96830484 509673472 3.2438955307 4.2485399246 6.0526795387 644 25.7200000000 0.5165088177 0.0948520751 0.8229851127 0.0472249886 0.0082520000 0.0006000000 0.0037530000 0.0000020000 0.0000170000 0.0011020000 15146581 96830484 509673472 3.2403993607 4.2451329231 6.0418539047 645 25.7600000000 0.5165506601 0.0955058714 0.8229851127 0.0471884056 0.0085920000 0.0004670000 0.0050870000 0.0000060000 0.0000050000 0.0016360000 15149357 96830484 509673472 3.2350940704 4.2430830002 6.0295305252 646 25.8000000000 0.5161808729 0.0961570711 0.8229851127 0.0471520951 0.0085560000 0.0005050000 0.0051590000 0.0000010000 0.0000080000 0.0009540000 15152133 96830484 509673472 3.2323043346 4.2417669296 6.0171203613 647 25.8400000000 0.5164058805 0.0968066055 0.8229851127 0.0471158843 0.0065950000 0.0004490000 0.0037950000 0.0000050000 0.0000040000 0.0011460000 15154909 96830484 509673472 3.2298715115 4.2407112122 6.0057868958 648 25.8800000000 0.5171388388 0.0974552664 0.8229851127 0.0470797890 0.0087380000 0.0005040000 0.0052020000 0.0000010000 0.0000100000 0.0009570000 15157685 96830484 509673472 3.2294080257 4.2382636070 5.9975156784 649 25.9200000000 0.5166289806 0.0981011427 0.8229851127 0.0470441283 0.0060920000 0.0004650000 0.0026240000 0.0000060000 0.0000040000 0.0016060000 15160461 96830484 509673472 3.2251381874 4.2355003357 5.9851694107 650 25.9600000000 0.5172559619 0.0987459963 0.8229851127 0.0470083952 0.0069000000 0.0004210000 0.0045760000 0.0000000000 0.0000040000 0.0008480000 15163237 96830484 509673472 3.2211635113 4.2327227592 5.9737939835 651 26.0000000000 0.5177729726 0.0993896629 0.8229851127 0.0469727428 0.0082890000 0.0005040000 0.0043690000 0.0000100000 0.0000090000 0.0013250000 15166013 96830484 509673472 3.2188513279 4.2294001579 5.9643182755 652 26.0400000000 0.5173449516 0.1000306986 0.8229851127 0.0469371620 0.0057580000 0.0004450000 0.0030550000 0.0000000000 0.0000050000 0.0008570000 15168789 96830484 509673472 3.2167837620 4.2265710831 5.9527916908 653 26.0800000000 0.5177253485 0.1006703535 0.8229851127 0.0469016254 0.0120270000 0.0005880000 0.0054520000 0.0000150000 0.0000150000 0.0022980000 15171565 96830484 509673472 3.2122831345 4.2225012779 5.9411096573 654 26.1200000000 0.5182641745 0.1013088762 0.8229851127 0.0468662328 0.0067640000 0.0005340000 0.0035010000 0.0000010000 0.0000070000 0.0009090000 15174341 96830484 509673472 3.2090642452 4.2188034058 5.9309139252 655 26.1600000000 0.5183300376 0.1019455497 0.8229851127 0.0468308998 0.0076820000 0.0004750000 0.0049710000 0.0000040000 0.0000040000 0.0011640000 15177117 96830484 509673472 3.2057995796 4.2147092819 5.9201540947 656 26.2000000000 0.5185155869 0.1025805650 0.8229851127 0.0467958795 0.0067010000 0.0004060000 0.0045620000 0.0000010000 0.0000040000 0.0008430000 15179893 96830484 509673472 3.2015843391 4.2112092972 5.9091844559 657 26.2400000000 0.5190563202 0.1032144703 0.8229851127 0.0467604718 0.0078720000 0.0004030000 0.0049320000 0.0000040000 0.0000030000 0.0016330000 15182669 96830484 509673472 3.1962964535 4.2067365646 5.8981871605 658 26.2800000000 0.5189736485 0.1038463231 0.8229851127 0.0467252160 0.0090290000 0.0005030000 0.0052810000 0.0000020000 0.0000100000 0.0010980000 15185445 96830484 509673472 3.1940577030 4.2034683228 5.8885135651 659 26.3200000000 0.5193078518 0.1044767655 0.8229851127 0.0466900786 0.0080980000 0.0004500000 0.0050440000 0.0000050000 0.0000040000 0.0011820000 15188221 96830484 509673472 3.1899096966 4.2006936073 5.8773927689 660 26.3600000000 0.5195612311 0.1051056814 0.8229851127 0.0466550400 0.0072200000 0.0004200000 0.0049830000 0.0000000000 0.0000040000 0.0008620000 15190997 96830484 509673472 3.1869852543 4.1976709366 5.8665986061 661 26.4000000000 0.5198476911 0.1057331277 0.8229851127 0.0466202009 0.0078320000 0.0004190000 0.0049170000 0.0000040000 0.0000030000 0.0015610000 15193773 96830484 509673472 3.1830644608 4.1947660446 5.8553700447 662 26.4400000000 0.5201388001 0.1063591181 0.8229851127 0.0465852242 0.0088930000 0.0005140000 0.0052240000 0.0000010000 0.0000080000 0.0009870000 15196549 96830484 509673472 3.1775393486 4.1916093826 5.8434610367 663 26.4800000000 0.5200476050 0.1069830826 0.8229851127 0.0465504038 0.0078450000 0.0004550000 0.0050020000 0.0000040000 0.0000040000 0.0011420000 15199325 96830484 509673472 3.1725358963 4.1894583702 5.8301544189 664 26.5200000000 0.5201578736 0.1076053338 0.8229851127 0.0465160403 0.0071540000 0.0004120000 0.0049320000 0.0000010000 0.0000030000 0.0008320000 15202101 96830484 509673472 3.1684150696 4.1866431236 5.8183207512 665 26.5600000000 0.5202762485 0.1082258916 0.8229851127 0.0464838637 0.0103990000 0.0005880000 0.0053750000 0.0000100000 0.0000090000 0.0019300000 15204877 96830484 509673472 3.1603069305 4.1828060150 5.7938942909 666 26.6000000000 0.5202813745 0.1088445935 0.8229851127 0.0464492598 0.0078230000 0.0004520000 0.0050360000 0.0000010000 0.0000050000 0.0008850000 15207653 96830484 509673472 3.1553978920 4.1819024086 5.7800583839 667 26.6400000000 0.5204763412 0.1094617326 0.8229851127 0.0464148656 0.0075860000 0.0004190000 0.0049470000 0.0000040000 0.0000040000 0.0011460000 15210429 96830484 509673472 3.1519482136 4.1806330681 5.7683181763 668 26.6800000000 0.5206356645 0.1100772624 0.8229851127 0.0463804193 0.0071240000 0.0004080000 0.0049230000 0.0000010000 0.0000030000 0.0008490000 15213205 96830484 509673472 3.1465892792 4.1783170700 5.7548360825 669 26.7200000000 0.5205075145 0.1106907605 0.8229851127 0.0463465162 0.0078140000 0.0004090000 0.0048900000 0.0000030000 0.0000030000 0.0015660000 15215981 96830484 509673472 3.1434254646 4.1775155067 5.7424225807 670 26.7600000000 0.5202676058 0.1113020693 0.8229851127 0.0463122793 0.0055420000 0.0004040000 0.0033410000 0.0000010000 0.0000040000 0.0008470000 15218757 96830484 509673472 3.1403820515 4.1777358055 5.7295713425 671 26.8000000000 0.5205751657 0.1119120143 0.8229851127 0.0462781991 0.0074030000 0.0004080000 0.0048840000 0.0000030000 0.0000040000 0.0011440000 15221533 96830484 509673472 3.1349811554 4.1751022339 5.7167434692 672 26.8400000000 0.5206943750 0.1125203214 0.8229851127 0.0462447815 0.0071090000 0.0004050000 0.0048890000 0.0000000000 0.0000030000 0.0008580000 15224309 96830484 509673472 3.1299016476 4.1720538139 5.7042641640 673 26.8800000000 0.5208151937 0.1131270002 0.8229851127 0.0462112159 0.0078370000 0.0004050000 0.0048790000 0.0000040000 0.0000030000 0.0015880000 15227085 96830484 509673472 3.1262114048 4.1689600945 5.6916179657 674 26.9200000000 0.5209541321 0.1137320850 0.8229851127 0.0461771905 0.0070770000 0.0004020000 0.0048840000 0.0000000000 0.0000030000 0.0008460000 15229861 96830484 509673472 3.1253533363 4.1661128998 5.6802563667 675 26.9600000000 0.5211947560 0.1143357334 0.8229851127 0.0461437219 0.0073910000 0.0004070000 0.0048660000 0.0000040000 0.0000030000 0.0011540000 15232637 96830484 509673472 3.1239397526 4.1627955437 5.6684427261 676 27.0000000000 0.5211973786 0.1149375997 0.8229851127 0.0461113807 0.0109100000 0.0005930000 0.0053930000 0.0000020000 0.0000150000 0.0013740000 15235413 96830484 509673472 3.1204702854 4.1607561111 5.6553201675 677 27.0400000000 0.5215123892 0.1155381533 0.8229851127 0.0460783003 0.0085430000 0.0004730000 0.0046290000 0.0000070000 0.0000060000 0.0017100000 15238189 96830484 509673472 3.1167271137 4.1584358215 5.6432805061 678 27.0800000000 0.5214577913 0.1161368549 0.8229851127 0.0460454814 0.0073170000 0.0004350000 0.0048860000 0.0000010000 0.0000040000 0.0008730000 15240965 96830484 509673472 3.1137814522 4.1572718620 5.6326169968 679 27.1200000000 0.5216228962 0.1167340361 0.8229851127 0.0460125737 0.0073360000 0.0004050000 0.0048220000 0.0000040000 0.0000030000 0.0011730000 15243741 96830484 509673472 3.1109571457 4.1548366547 5.6218671799 680 27.1600000000 0.5216431618 0.1173294907 0.8229851127 0.0459795078 0.0070300000 0.0004000000 0.0048300000 0.0000000000 0.0000030000 0.0008650000 15246517 96830484 509673472 3.1082236767 4.1534271240 5.6125082970 681 27.2000000000 0.5217655301 0.1179233762 0.8229851127 0.0459465578 0.0058790000 0.0004010000 0.0029100000 0.0000030000 0.0000030000 0.0016320000 15249293 96830484 509673472 3.1053287983 4.1518340111 5.6022119522 682 27.2400000000 0.5216568708 0.1185153608 0.8229851127 0.0459138051 0.0089320000 0.0006030000 0.0024700000 0.0000020000 0.0000150000 0.0014060000 15252069 96830484 509673472 3.1015434265 4.1509699821 5.5905847549 683 27.2800000000 0.5218713880 0.1191059260 0.8229851127 0.0458804623 0.0087350000 0.0005020000 0.0050590000 0.0000080000 0.0000070000 0.0013060000 15254845 96830484 509673472 3.0964646339 4.1495203972 5.5788311958 684 27.3200000000 0.5219733119 0.1196949134 0.8229851127 0.0458479491 0.0075030000 0.0004360000 0.0048720000 0.0000010000 0.0000050000 0.0008990000 15257621 96830484 509673472 3.0956203938 4.1468124390 5.5697565079 685 27.3600000000 0.5219967365 0.1202822153 0.8229851127 0.0458156569 0.0078380000 0.0004130000 0.0048350000 0.0000040000 0.0000030000 0.0016570000 15260397 96830484 509673472 3.0955126286 4.1455464363 5.5600934029 686 27.4000000000 0.5220545530 0.1208678893 0.8229851127 0.0457837444 0.0086210000 0.0005170000 0.0050820000 0.0000000000 0.0000080000 0.0010250000 15263173 96830484 509673472 3.0895283222 4.1434869766 5.5470681190 687 27.4400000000 0.5224624872 0.1214524520 0.8229851127 0.0457509418 0.0089940000 0.0005070000 0.0051030000 0.0000080000 0.0000070000 0.0013200000 15265949 96830484 509673472 3.0857686996 4.1403799057 5.5362715721 688 27.4800000000 0.5224292874 0.1220352672 0.8229851127 0.0457181891 0.0075330000 0.0004410000 0.0049100000 0.0000000000 0.0000040000 0.0009010000 15268725 96830484 509673472 3.0836145878 4.1396417618 5.5267367363 689 27.5200000000 0.5224687457 0.1226164478 0.8229851127 0.0456854073 0.0078040000 0.0004120000 0.0048270000 0.0000040000 0.0000030000 0.0016270000 15271501 96830484 509673472 3.0783803463 4.1378316879 5.5135507584 690 27.5600000000 0.5224141479 0.1231958648 0.8229851127 0.0456530528 0.0085700000 0.0005020000 0.0050620000 0.0000010000 0.0000080000 0.0010130000 15274277 96830484 509673472 3.0774166584 4.1364541054 5.5030136108 691 27.6000000000 0.5223944187 0.1237735762 0.8229851127 0.0456201485 0.0071710000 0.0005020000 0.0031120000 0.0000090000 0.0000070000 0.0013310000 15277053 96830484 509673472 3.0753521919 4.1345686913 5.4922838211 692 27.6400000000 0.5224270225 0.1243496650 0.8229851127 0.0455873929 0.0075170000 0.0004420000 0.0048870000 0.0000000000 0.0000050000 0.0008990000 15279829 96830484 509673472 3.0733103752 4.1317324638 5.4799499512 693 27.6800000000 0.5224760771 0.1249241619 0.8229851127 0.0455545471 0.0096440000 0.0005040000 0.0050630000 0.0000100000 0.0000100000 0.0018290000 15282605 96830484 509673472 3.0710380077 4.1297407150 5.4678797722 694 27.7200000000 0.5226376057 0.1254972361 0.8229851127 0.0455219376 0.0065830000 0.0004510000 0.0037190000 0.0000010000 0.0000050000 0.0009220000 15285381 96830484 509673472 3.0691530704 4.1268568039 5.4559836388 695 27.7600000000 0.5230051875 0.1260691900 0.8229851127 0.0454895859 0.0075390000 0.0005040000 0.0034650000 0.0000100000 0.0000090000 0.0013280000 15288157 96830484 509673472 3.0668330193 4.1224150658 5.4439959526 696 27.8000000000 0.5230438709 0.1266395559 0.8229851127 0.0454569187 0.0077070000 0.0004440000 0.0048510000 0.0000010000 0.0000060000 0.0009160000 15290933 96830484 509673472 3.0647590160 4.1197838783 5.4313650131 697 27.8400000000 0.5240027905 0.1272096610 0.8229851127 0.0454262528 0.0079100000 0.0004210000 0.0047920000 0.0000050000 0.0000040000 0.0016450000 15293709 96830484 509673472 3.0602602959 4.1099104881 5.4062132835 698 27.8800000000 0.5251004696 0.1277797051 0.8229851127 0.0453937225 0.0087730000 0.0005010000 0.0045820000 0.0000010000 0.0000100000 0.0011330000 15296485 96830484 509673472 3.0602023602 4.1050124168 5.3966612816 699 27.9200000000 0.5253418088 0.1283484635 0.8229851127 0.0453645512 0.0079260000 0.0004450000 0.0047850000 0.0000060000 0.0000050000 0.0011890000 15299261 96830484 509673472 3.0574026108 4.1052246094 5.3821516037 700 27.9600000000 0.5257002711 0.1289161089 0.8229851127 0.0453322028 0.0098710000 0.0005900000 0.0051420000 0.0000010000 0.0000100000 0.0011220000 15302037 96830484 509673472 3.0564830303 4.1044583321 5.3674225807 701 28.0000000000 0.5258932710 0.1294824101 0.8229851127 0.0453008601 0.0063960000 0.0004740000 0.0025340000 0.0000060000 0.0000050000 0.0017110000 15304813 96830484 509673472 3.0582504272 4.1022081375 5.3555531502 702 28.0400000000 0.5259044170 0.1300471138 0.8229851127 0.0452686262 0.0071800000 0.0004210000 0.0047330000 0.0000000000 0.0000040000 0.0008790000 15307589 96830484 509673472 3.0581727028 4.1017765999 5.3424987793 703 28.0800000000 0.5262570977 0.1306107127 0.8229851127 0.0452365830 0.0099230000 0.0005880000 0.0051700000 0.0000100000 0.0000090000 0.0014010000 15310365 96830484 509673472 3.0548188686 4.0985288620 5.3278179169 704 28.1200000000 0.5265893340 0.1311731823 0.8229851127 0.0452061516 0.0059210000 0.0004540000 0.0029050000 0.0000010000 0.0000060000 0.0009400000 15313141 96830484 509673472 3.0553333759 4.0940566063 5.3153915405 705 28.1600000000 0.5271881819 0.1317349057 0.8229851127 0.0451742441 0.0079500000 0.0004210000 0.0047440000 0.0000040000 0.0000040000 0.0016300000 15315917 96830484 509673472 3.0551588535 4.0883951187 5.3021583557 706 28.2000000000 0.5274366140 0.1322953897 0.8229851127 0.0451422871 0.0086610000 0.0005040000 0.0049430000 0.0000010000 0.0000080000 0.0009860000 15318693 96830484 509673472 3.0545494556 4.0834431648 5.2890629768 707 28.2400000000 0.5277820826 0.1328547768 0.8229851127 0.0451113741 0.0090620000 0.0005010000 0.0049890000 0.0000070000 0.0000070000 0.0012910000 15321469 96830484 509673472 3.0547027588 4.0819692612 5.2746748924 708 28.2800000000 0.5277435184 0.1334125293 0.8229851127 0.0450798721 0.0074490000 0.0004500000 0.0047940000 0.0000000000 0.0000050000 0.0008870000 15324245 96830484 509673472 3.0514209270 4.0821471214 5.2589063644 709 28.3200000000 0.5280222297 0.1339691015 0.8229851127 0.0450498520 0.0076790000 0.0004130000 0.0046940000 0.0000030000 0.0000030000 0.0016080000 15327021 96830484 509673472 3.0510494709 4.0780014992 5.2453927994 710 28.3600000000 0.5281826258 0.1345243318 0.8229851127 0.0450184518 0.0083390000 0.0005040000 0.0045510000 0.0000010000 0.0000090000 0.0010040000 15329797 96830484 509673472 3.0539526939 4.0759205818 5.2355399132 711 28.4000000000 0.5283475518 0.1350782323 0.8229851127 0.0449869144 0.0077460000 0.0004440000 0.0047440000 0.0000050000 0.0000050000 0.0012150000 15332573 96830484 509673472 3.0526797771 4.0737137794 5.2228269577 712 28.4400000000 0.5286805034 0.1356310445 0.8229851127 0.0449554149 0.0070450000 0.0004150000 0.0046900000 0.0000000000 0.0000040000 0.0008750000 15335349 96830484 509673472 3.0524702072 4.0702962875 5.2115268707 713 28.4800000000 0.5290982127 0.1361828918 0.8229851127 0.0449238989 0.0095130000 0.0005660000 0.0049300000 0.0000080000 0.0000080000 0.0017740000 15338125 96830484 509673472 3.0543720722 4.0664744377 5.2017931938 714 28.5200000000 0.5292642713 0.1367334260 0.8229851127 0.0448942969 0.0074340000 0.0004710000 0.0047300000 0.0000010000 0.0000050000 0.0008840000 15340901 96830484 509673472 3.0537648201 4.0648684502 5.1904406548 715 28.5600000000 0.5293532014 0.1372825445 0.8229851127 0.0448639181 0.0084560000 0.0005150000 0.0048570000 0.0000060000 0.0000060000 0.0012120000 15343677 96830484 509673472 3.0518674850 4.0654063225 5.1754131317 716 28.6000000000 0.5295502543 0.1378304045 0.8229851127 0.0448330667 0.0081890000 0.0005270000 0.0048690000 0.0000010000 0.0000080000 0.0009320000 15346453 96830484 509673472 3.0515120029 4.0636525154 5.1627240181 717 28.6400000000 0.5298791528 0.1383771949 0.8229851127 0.0448032729 0.0073960000 0.0004310000 0.0039460000 0.0000040000 0.0000040000 0.0016500000 15349229 96830484 509673472 3.0529241562 4.0589823723 5.1546721458 718 28.6800000000 0.5299684405 0.1389225866 0.8229851127 0.0447726867 0.0087510000 0.0005030000 0.0049250000 0.0000010000 0.0000080000 0.0010010000 15352005 96830484 509673472 3.0523462296 4.0574898720 5.1458783150 719 28.7200000000 0.5300202370 0.1394665333 0.8229851127 0.0447421368 0.0077060000 0.0004440000 0.0046970000 0.0000040000 0.0000040000 0.0012090000 15354781 96830484 509673472 3.0493867397 4.0556516647 5.1331386566 720 28.7600000000 0.5304672122 0.1400095898 0.8229851127 0.0447113292 0.0069700000 0.0004120000 0.0046270000 0.0000000000 0.0000030000 0.0008640000 15357557 96830484 509673472 3.0477435589 4.0535802841 5.1222062111 721 28.8000000000 0.5304816365 0.1405511599 0.8229851127 0.0446808378 0.0110480000 0.0005910000 0.0051380000 0.0000150000 0.0000140000 0.0022100000 15360333 96830484 509673472 3.0486998558 4.0538697243 5.1112542152 722 28.8400000000 0.5304564834 0.1410911950 0.8229851127 0.0446509957 0.0074890000 0.0004690000 0.0044150000 0.0000010000 0.0000060000 0.0009340000 15363109 96830484 509673472 3.0428717136 4.0546517372 5.0983614922 723 28.8800000000 0.5308173299 0.1416302353 0.8229851127 0.0446209518 0.0059420000 0.0004260000 0.0031660000 0.0000050000 0.0000040000 0.0011630000 15365885 96830484 509673472 3.0371384621 4.0533657074 5.0871210098 724 28.9200000000 0.5306242704 0.1421675198 0.8229851127 0.0445906770 0.0088760000 0.0005040000 0.0048370000 0.0000010000 0.0000100000 0.0011200000 15368661 96830484 509673472 3.0341658592 4.0532045364 5.0776915550 725 28.9600000000 0.5309287906 0.1427037423 0.8229851127 0.0445601733 0.0062110000 0.0004480000 0.0024870000 0.0000050000 0.0000050000 0.0016640000 15371437 96830484 509673472 3.0293738842 4.0523967743 5.0659976006 726 29.0000000000 0.5311156511 0.1432387449 0.8229851127 0.0445310692 0.0083640000 0.0005920000 0.0035290000 0.0000010000 0.0000150000 0.0011160000 15374213 96830484 509673472 3.0266647339 4.0495786667 5.0527229309 727 29.0400000000 0.5315316916 0.1437728480 0.8229851127 0.0445017409 0.0080030000 0.0004690000 0.0046750000 0.0000060000 0.0000060000 0.0012570000 15376989 96830484 509673472 3.0163509846 4.0464110374 5.0327162743 728 29.0800000000 0.5320680141 0.1443062205 0.8229851127 0.0444725237 0.0070570000 0.0004200000 0.0045350000 0.0000010000 0.0000040000 0.0009370000 15379765 96830484 509673472 3.0055499077 4.0440797806 5.0186085701 729 29.1200000000 0.5324804783 0.1448386955 0.8229851127 0.0444508637 0.0102090000 0.0005920000 0.0049430000 0.0000100000 0.0000090000 0.0020670000 15382541 96830484 509673472 3.0022277832 4.0380697250 5.0114040375 730 29.1600000000 0.5326837301 0.1453699900 0.8229851127 0.0444207911 0.0075950000 0.0004610000 0.0045860000 0.0000000000 0.0000050000 0.0009570000 15385317 96830484 509673472 2.9994752407 4.0369000435 5.0024299622 731 29.2000000000 0.5327064395 0.1458998620 0.8229851127 0.0443905003 0.0072610000 0.0004260000 0.0045090000 0.0000040000 0.0000040000 0.0012250000 15388093 96830484 509673472 2.9910252094 4.0383172035 4.9879097939 732 29.2400000000 0.5328302979 0.1464284555 0.8229851127 0.0443624697 0.0068110000 0.0004070000 0.0044170000 0.0000010000 0.0000040000 0.0009550000 15390869 96830484 509673472 2.9853000641 4.0384602547 4.9767398834 733 29.2800000000 0.5325567126 0.1469552335 0.8229851127 0.0443327923 0.0113240000 0.0005960000 0.0049030000 0.0000150000 0.0000130000 0.0024590000 15393645 96830484 509673472 2.9819664955 4.0404248238 4.9660291672 734 29.3200000000 0.5325006247 0.1474804997 0.8229851127 0.0443029142 0.0078950000 0.0004760000 0.0045500000 0.0000010000 0.0000060000 0.0010610000 15396421 96830484 509673472 2.9739587307 4.0439767838 4.9531550407 735 29.3600000000 0.5327655077 0.1480046970 0.8229851127 0.0442808429 0.0073590000 0.0004370000 0.0044000000 0.0000050000 0.0000040000 0.0012890000 15399197 96830484 509673472 2.9687032700 4.0409193039 4.9436821938 736 29.4000000000 0.5328543782 0.1485275906 0.8229851127 0.0442528926 0.0067630000 0.0004070000 0.0043380000 0.0000000000 0.0000030000 0.0009970000 15401973 96830484 509673472 2.9660274982 4.0408606529 4.9354329109 737 29.4400000000 0.5327327251 0.1490489001 0.8229851127 0.0442229619 0.0082460000 0.0005010000 0.0032190000 0.0000070000 0.0000070000 0.0020890000 15404749 96830484 509673472 2.9607679844 4.0447320938 4.9225096703 738 29.4800000000 0.5327028036 0.1495687564 0.8229851127 0.0441978549 0.0073310000 0.0004500000 0.0043890000 0.0000010000 0.0000050000 0.0010470000 15407525 96830484 509673472 2.9559445381 4.0448598862 4.9117131233 739 29.5200000000 0.5329467058 0.1500875357 0.8229851127 0.0441736125 0.0090220000 0.0005130000 0.0046030000 0.0000110000 0.0000090000 0.0014360000 15410301 96830484 509673472 2.9554345608 4.0427455902 4.9063496590 740 29.5600000000 0.5331508517 0.1506051889 0.8229851127 0.0441442256 0.0075550000 0.0004560000 0.0044270000 0.0000010000 0.0000050000 0.0010570000 15413077 96830484 509673472 2.9530551434 4.0414357185 4.8975667953 741 29.6000000000 0.5331927538 0.1511215014 0.8229851127 0.0441146797 0.0060750000 0.0004120000 0.0026210000 0.0000040000 0.0000040000 0.0019250000 15415853 96830484 509673472 2.9506583214 4.0409870148 4.8866634369 742 29.6400000000 0.5334595442 0.1516367818 0.8229851127 0.0440850693 0.0071550000 0.0004670000 0.0043240000 0.0000000000 0.0000040000 0.0010440000 15418629 96830484 509673472 2.9487495422 4.0409979820 4.8765468597 743 29.6800000000 0.5332998037 0.1521504601 0.8229851127 0.0440559510 0.0071450000 0.0004530000 0.0042740000 0.0000040000 0.0000030000 0.0013100000 15421405 96830484 509673472 2.9450650215 4.0422019958 4.8674511909 744 29.7200000000 0.5334157348 0.1526629134 0.8229851127 0.0440269015 0.0104110000 0.0006060000 0.0048030000 0.0000020000 0.0000150000 0.0015090000 15424181 96830484 509673472 2.9391541481 4.0433821678 4.8583583832 745 29.7600000000 0.5333724618 0.1531739330 0.8229851127 0.0440012269 0.0068180000 0.0004720000 0.0023310000 0.0000070000 0.0000060000 0.0020160000 15426957 96830484 509673472 2.9358007908 4.0434265137 4.8525905609 746 29.8000000000 0.5333549380 0.1536835590 0.8229851127 0.0439734131 0.0070060000 0.0004390000 0.0042700000 0.0000010000 0.0000050000 0.0010450000 15429733 96830484 509673472 2.9311606884 4.0439515114 4.8441662788 747 29.8400000000 0.5333508253 0.1541918150 0.8229851127 0.0439515112 0.0084810000 0.0005040000 0.0044560000 0.0000080000 0.0000060000 0.0014410000 15432509 96830484 509673472 2.9357175827 4.0421652794 4.8389763832 748 29.8800000000 0.5336719751 0.1546991414 0.8229851127 0.0439232898 0.0061880000 0.0004320000 0.0032800000 0.0000010000 0.0000050000 0.0010560000 15435285 96830484 509673472 2.9377357960 4.0387091637 4.8363585472 749 29.9200000000 0.5339788795 0.1552055229 0.8229851127 0.0438950499 0.0105180000 0.0006210000 0.0047160000 0.0000100000 0.0000090000 0.0022830000 15438061 96830484 509673472 2.9339170456 4.0379934311 4.8284320831 750 29.9600000000 0.5335878730 0.1557100327 0.8229851127 0.0438658749 0.0075570000 0.0004540000 0.0043550000 0.0000000000 0.0000060000 0.0010900000 15440837 96830484 509673472 2.9305384159 4.0403432846 4.8177161217 751 30.0000000000 0.5338244438 0.1562135140 0.8229851127 0.0438386077 0.0072190000 0.0004180000 0.0042590000 0.0000040000 0.0000030000 0.0013240000 15443613 96830484 509673472 2.9292156696 4.0383152962 4.8129448891 752 30.0400000000 0.5341966152 0.1567161511 0.8229851127 0.0438103451 0.0067920000 0.0004060000 0.0042130000 0.0000000000 0.0000040000 0.0010660000 15446389 96830484 509673472 2.9267625809 4.0365753174 4.8094224930 753 30.0800000000 0.5337865949 0.1572169086 0.8229851127 0.0437813582 0.0076940000 0.0004060000 0.0042160000 0.0000040000 0.0000030000 0.0019820000 15449165 96830484 509673472 2.9221360683 4.0394577980 4.7993955612 754 30.1200000000 0.5340846777 0.1577167333 0.8229851127 0.0437567335 0.0064330000 0.0004140000 0.0038830000 0.0000010000 0.0000030000 0.0010630000 15451941 96830484 509673472 2.9232699871 4.0360450745 4.7948045731 755 30.1600000000 0.5344289541 0.1582156899 0.8229851127 0.0437290499 0.0057180000 0.0004060000 0.0028810000 0.0000030000 0.0000030000 0.0013520000 15454717 96830484 509673472 2.9275336266 4.0330266953 4.7931413651 756 30.2000000000 0.5347002149 0.1587136853 0.8229851127 0.0437003844 0.0068010000 0.0004040000 0.0042200000 0.0000000000 0.0000040000 0.0010810000 15457493 96830484 509673472 2.9254608154 4.0320420265 4.7858462334 757 30.2400000000 0.5347615480 0.1592104460 0.8229851127 0.0436718718 0.0108160000 0.0005940000 0.0025980000 0.0000150000 0.0000140000 0.0026440000 15460269 96830484 509673472 2.9233453274 4.0308771133 4.7790679932 758 30.2800000000 0.5346434116 0.1597057401 0.8229851127 0.0436431597 0.0085440000 0.0005050000 0.0044910000 0.0000010000 0.0000090000 0.0012140000 15463045 96830484 509673472 2.9211068153 4.0311255455 4.7722759247 759 30.3200000000 0.5345207453 0.1601995675 0.8229851127 0.0436147009 0.0075530000 0.0004400000 0.0042990000 0.0000050000 0.0000050000 0.0013530000 15465821 96830484 509673472 2.9194896221 4.0329289436 4.7619180679 760 30.3600000000 0.5348319411 0.1606925049 0.8229851127 0.0435892350 0.0068880000 0.0004150000 0.0042440000 0.0000010000 0.0000040000 0.0010820000 15468597 96830484 509673472 2.9230127335 4.0296115875 4.7568035126 761 30.4000000000 0.5351206064 0.1611845260 0.8229851127 0.0435613161 0.0077990000 0.0004060000 0.0042970000 0.0000040000 0.0000030000 0.0020070000 15471373 96830484 509673472 2.9234676361 4.0276508331 4.7523112297 762 30.4400000000 0.5351240039 0.1616752603 0.8229851127 0.0435330971 0.0061720000 0.0004050000 0.0036030000 0.0000000000 0.0000030000 0.0010820000 15474149 96830484 509673472 2.9202184677 4.0270600319 4.7445802689 763 30.4800000000 0.5353683829 0.1621650284 0.8229851127 0.0435066830 0.0108040000 0.0005930000 0.0048510000 0.0000150000 0.0000140000 0.0018620000 15476925 96830484 509673472 2.9198672771 4.0241713524 4.7371096611 764 30.5200000000 0.5353658199 0.1626535111 0.8229851127 0.0434782883 0.0078890000 0.0004670000 0.0044510000 0.0000010000 0.0000060000 0.0011570000 15479701 96830484 509673472 2.9211134911 4.0249447823 4.7300677299 765 30.5600000000 0.5355659723 0.1631409784 0.8229851127 0.0434505498 0.0080620000 0.0004220000 0.0043540000 0.0000040000 0.0000030000 0.0020000000 15482477 96830484 509673472 2.9217319489 4.0231208801 4.7214465141 766 30.6000000000 0.5360717177 0.1636278332 0.8229851127 0.0434239462 0.0069210000 0.0004070000 0.0043280000 0.0000000000 0.0000030000 0.0010840000 15485253 96830484 509673472 2.9266078472 4.0172786713 4.7183685303 767 30.6400000000 0.5360345244 0.1641133699 0.8229851127 0.0433957540 0.0092820000 0.0005030000 0.0046270000 0.0000100000 0.0000090000 0.0016180000 15488029 96830484 509673472 2.9266836643 4.0168251991 4.7081046104 768 30.6800000000 0.5365979075 0.1645983758 0.8229851127 0.0433681338 0.0076950000 0.0004520000 0.0044290000 0.0000000000 0.0000050000 0.0011150000 15490805 96830484 509673472 2.9272022247 4.0141553879 4.6992440224 769 30.7200000000 0.5368385315 0.1650824332 0.8229851127 0.0433417969 0.0098690000 0.0005040000 0.0045990000 0.0000070000 0.0000070000 0.0022080000 15493581 96830484 509673472 2.9333596230 4.0082855225 4.6974864006 770 30.7600000000 0.5367958546 0.1655651780 0.8229851127 0.0433145974 0.0074700000 0.0004670000 0.0044100000 0.0000010000 0.0000050000 0.0011230000 15496357 96830484 509673472 2.9345054626 4.0074114799 4.6896028519 771 30.8000000000 0.5376452208 0.1660477720 0.8229851127 0.0432866142 0.0072570000 0.0004120000 0.0043490000 0.0000030000 0.0000030000 0.0013490000 15499133 96830484 509673472 2.9348273277 4.0040555000 4.6804213524 772 30.8400000000 0.5377504230 0.1665292522 0.8229851127 0.0432587539 0.0100680000 0.0005940000 0.0048870000 0.0000010000 0.0000110000 0.0013370000 15501909 96830484 509673472 2.9410238266 3.9994578362 4.6749176979 773 30.8800000000 0.5382610559 0.1670101471 0.8229851127 0.0432319574 0.0086490000 0.0004750000 0.0044360000 0.0000060000 0.0000050000 0.0020380000 15504685 96830484 509673472 2.9468805790 3.9968199730 4.6688051224 774 30.9200000000 0.5379813313 0.1674894381 0.8229851127 0.0432073171 0.0054580000 0.0004260000 0.0026530000 0.0000010000 0.0000040000 0.0010850000 15507461 96830484 509673472 2.9450149536 3.9971523285 4.6590085030 775 30.9600000000 0.5383053422 0.1679679102 0.8229851127 0.0431803882 0.0102700000 0.0005910000 0.0048630000 0.0000100000 0.0000090000 0.0015740000 15510237 96830484 509673472 2.9433467388 3.9963471889 4.6511163712 776 31.0000000000 0.5382958651 0.1684451369 0.8229851127 0.0431530096 0.0058580000 0.0004830000 0.0023660000 0.0000000000 0.0000060000 0.0011150000 15513013 96830484 509673472 2.9418301582 3.9951798916 4.6442279816 777 31.0400000000 0.5385105610 0.1689214116 0.8229851127 0.0431255691 0.0081020000 0.0004210000 0.0044140000 0.0000040000 0.0000030000 0.0019680000 15515789 96830484 509673472 2.9460859299 3.9940598011 4.6380038261 778 31.0800000000 0.5386782289 0.1693966774 0.8229851127 0.0430984490 0.0072650000 0.0005070000 0.0028480000 0.0000010000 0.0000100000 0.0012900000 15518565 96830484 509673472 2.9451789856 3.9927504063 4.6303882599 779 31.1200000000 0.5384073257 0.1698703753 0.8229851127 0.0430728531 0.0080020000 0.0004490000 0.0044680000 0.0000060000 0.0000050000 0.0013750000 15521341 96830484 509673472 2.9457666874 3.9958062172 4.6218843460 780 31.1600000000 0.5383409858 0.1703427735 0.8229851127 0.0430464236 0.0058000000 0.0004230000 0.0030000000 0.0000010000 0.0000040000 0.0010660000 15524117 96830484 509673472 2.9460923672 3.9997971058 4.6124048233 781 31.2000000000 0.5380079746 0.1708135356 0.8229851127 0.0430190266 0.0077810000 0.0004080000 0.0043420000 0.0000040000 0.0000040000 0.0019380000 15526893 96830484 509673472 2.9510073662 4.0002751350 4.6042990685 782 31.2400000000 0.5387014747 0.1712839806 0.8229851127 0.0429916233 0.0069370000 0.0004050000 0.0043940000 0.0000000000 0.0000030000 0.0010440000 15529669 96830484 509673472 2.9555063248 3.9975893497 4.5982704163 783 31.2800000000 0.5386672020 0.1717531801 0.8229851127 0.0429643811 0.0050930000 0.0004050000 0.0022950000 0.0000030000 0.0000030000 0.0012930000 15532445 96830484 509673472 2.9599492550 3.9968037605 4.5938620567 784 31.3200000000 0.5388923883 0.1722214699 0.8229851127 0.0429372393 0.0121350000 0.0005900000 0.0049780000 0.0000020000 0.0000150000 0.0015290000 15535221 96830484 509673472 2.9612829685 3.9959237576 4.5849294662 785 31.3600000000 0.5392048955 0.1726889647 0.8229851127 0.0429104214 0.0079690000 0.0005040000 0.0032220000 0.0000090000 0.0000070000 0.0020890000 15537997 96830484 509673472 2.9600362778 3.9937729836 4.5794529915 786 31.4000000000 0.5394678116 0.1731556045 0.8229851127 0.0428840917 0.0075530000 0.0004380000 0.0045710000 0.0000010000 0.0000050000 0.0010430000 15540773 96830484 509673472 2.9640190601 3.9886794090 4.5759162903 787 31.4400000000 0.5398040414 0.1736214856 0.8229851127 0.0428570624 0.0089210000 0.0005050000 0.0047450000 0.0000070000 0.0000070000 0.0014610000 15543549 96830484 509673472 2.9673323631 3.9854171276 4.5724902153 788 31.4800000000 0.5397506356 0.1740861165 0.8229851127 0.0428301841 0.0075770000 0.0004370000 0.0046020000 0.0000010000 0.0000050000 0.0010340000 15546325 96830484 509673472 2.9699435234 3.9849286079 4.5672054291 789 31.5200000000 0.5398563147 0.1745497035 0.8229851127 0.0428032946 0.0073070000 0.0004130000 0.0038060000 0.0000040000 0.0000040000 0.0019210000 15549101 96830484 509673472 2.9714548588 3.9843297005 4.5608329773 790 31.5600000000 0.5399445891 0.1750122287 0.8229851127 0.0427765181 0.0087540000 0.0005250000 0.0044160000 0.0000000000 0.0000080000 0.0011800000 15551877 96830484 509673472 2.9729769230 3.9833786488 4.5575551987 791 31.6000000000 0.5398128629 0.1754734179 0.8229851127 0.0427499703 0.0119370000 0.0006070000 0.0043080000 0.0000150000 0.0000140000 0.0017860000 15554653 96830484 509673472 2.9720098972 3.9848294258 4.5500583649 792 31.6400000000 0.5402337909 0.1759339739 0.8229851127 0.0427235562 0.0112470000 0.0006020000 0.0038860000 0.0000020000 0.0000150000 0.0015340000 15557429 96830484 509673472 2.9713211060 3.9811878204 4.5452084541 793 31.6800000000 0.5406033397 0.1763938344 0.8229851127 0.0426967149 0.0112060000 0.0005980000 0.0047040000 0.0000160000 0.0000140000 0.0024020000 15560205 96830484 509673472 2.9741060734 3.9778418541 4.5446648598 794 31.7200000000 0.5402603149 0.1768521045 0.8229851127 0.0426704604 0.0084460000 0.0004680000 0.0047540000 0.0000010000 0.0000060000 0.0011250000 15562981 96830484 509673472 2.9717795849 3.9786591530 4.5361032486 795 31.7600000000 0.5404630303 0.1773094768 0.8229851127 0.0426439354 0.0062230000 0.0004820000 0.0027870000 0.0000040000 0.0000040000 0.0013300000 15565757 96830484 509673472 2.9702594280 3.9772586823 4.5309653282 796 31.8000000000 0.5403535366 0.1777655623 0.8229851127 0.0426173300 0.0057630000 0.0004510000 0.0031130000 0.0000010000 0.0000040000 0.0010550000 15568533 96830484 509673472 2.9730107784 3.9752850533 4.5283322334 797 31.8400000000 0.5404430032 0.1782206155 0.8229851127 0.0425906680 0.0081290000 0.0004090000 0.0045680000 0.0000040000 0.0000030000 0.0019610000 15571309 96830484 509673472 2.9748952389 3.9745848179 4.5238714218 798 31.8800000000 0.5406411886 0.1786747766 0.8229851127 0.0425640312 0.0071610000 0.0004040000 0.0045580000 0.0000000000 0.0000030000 0.0010550000 15574085 96830484 509673472 2.9738273621 3.9721601009 4.5208587646 799 31.9200000000 0.5404636860 0.1791275788 0.8229851127 0.0425387825 0.0063360000 0.0004080000 0.0034630000 0.0000040000 0.0000030000 0.0013090000 15576861 96830484 509673472 2.9713103771 3.9763331413 4.5112800598 800 31.9600000000 0.5409181118 0.1795798169 0.8229851127 0.0425138859 0.0056990000 0.0004020000 0.0031000000 0.0000000000 0.0000030000 0.0010690000 15579637 96830484 509673472 2.9691615105 3.9710562229 4.5066761971 801 32.0000000000 0.5415770411 0.1800317486 0.8229851127 0.0424899104 0.0073520000 0.0004080000 0.0038260000 0.0000030000 0.0000030000 0.0019730000 15582413 96830484 509673472 2.9748959541 3.9604363441 4.5112161636 802 32.0400000000 0.5417534113 0.1804827731 0.8229851127 0.0424660180 0.0121290000 0.0006090000 0.0047270000 0.0000020000 0.0000150000 0.0015780000 15585189 96830484 509673472 2.9741692543 3.9590239525 4.5065994263 803 32.0800000000 0.5419234633 0.1809328860 0.8229851127 0.0424413991 0.0073070000 0.0004750000 0.0032460000 0.0000080000 0.0000070000 0.0014040000 15587965 96830484 509673472 2.9726860523 3.9594569206 4.4987802505 804 32.1199999990 0.5420359373 0.1813820192 0.8229851127 0.0424152002 0.0062690000 0.0004360000 0.0031650000 0.0000000000 0.0000040000 0.0010860000 15590741 96830484 509673472 2.9722061157 3.9562220573 4.4960250854 805 32.1600000000 0.5425869226 0.1818307209 0.8229851127 0.0423892243 0.0094950000 0.0005070000 0.0047230000 0.0000070000 0.0000080000 0.0021060000 15593517 96830484 509673472 2.9717285633 3.9517073631 4.4918971062 806 32.2000000000 0.5425170660 0.1822782226 0.8229851127 0.0423694382 0.0069800000 0.0004370000 0.0038870000 0.0000000000 0.0000050000 0.0011100000 15596293 96830484 509673472 2.9759435654 3.9536726475 4.4741177559 807 32.2400000000 0.5424954295 0.1827245884 0.8229851127 0.0423445825 0.0074430000 0.0004050000 0.0045370000 0.0000030000 0.0000030000 0.0013650000 15599069 96830484 509673472 2.9758160114 3.9546427727 4.4681310654 808 32.2800000000 0.5421795845 0.1831694584 0.8229851127 0.0423212764 0.0072590000 0.0004050000 0.0045820000 0.0000000000 0.0000030000 0.0010860000 15601845 96830484 509673472 2.9740202427 3.9597480297 4.4579825401 809 32.3200000000 0.5424544215 0.1836135684 0.8229851127 0.0422957521 0.0103280000 0.0005080000 0.0048820000 0.0000100000 0.0000090000 0.0022410000 15604621 96830484 509673472 2.9696407318 3.9581623077 4.4502773285 810 32.3600000000 0.5428194404 0.1840570324 0.8229851127 0.0422710414 0.0071810000 0.0004520000 0.0039120000 0.0000000000 0.0000050000 0.0011300000 15607397 96830484 509673472 2.9692504406 3.9541382790 4.4473919868 811 32.4000000000 0.5434204340 0.1845001439 0.8229851127 0.0422462118 0.0087070000 0.0005030000 0.0040650000 0.0000080000 0.0000070000 0.0014930000 15610173 96830484 509673472 2.9657983780 3.9472503662 4.4416646957 812 32.4399999990 0.5441397429 0.1849430498 0.8229851127 0.0422213805 0.0067660000 0.0004790000 0.0035370000 0.0000000000 0.0000060000 0.0011450000 15612949 96830484 509673472 2.9689223766 3.9394347668 4.4424071312 813 32.4800000000 0.5435028672 0.1853840828 0.8229851127 0.0422058422 0.0082990000 0.0004180000 0.0045800000 0.0000030000 0.0000030000 0.0021090000 15615725 96830484 509673472 2.9683792591 3.9490549564 4.4286432266 814 32.5200000000 0.5433526635 0.1858238476 0.8229851127 0.0421833350 0.0073100000 0.0004080000 0.0045660000 0.0000000000 0.0000030000 0.0011490000 15618501 96830484 509673472 2.9620518684 3.9575333595 4.4103679657 815 32.5600000000 0.5439200401 0.1862632295 0.8229851127 0.0421645048 0.0064140000 0.0004040000 0.0034400000 0.0000030000 0.0000030000 0.0014050000 15621277 96830484 509673472 2.9599583149 3.9487762451 4.4095091820 816 32.6000000000 0.5442041159 0.1867018825 0.8229851127 0.0421392214 0.0073030000 0.0004060000 0.0045770000 0.0000010000 0.0000040000 0.0011530000 15624053 96830484 509673472 2.9589340687 3.9450020790 4.4051308632 817 32.6400000000 0.5443750024 0.1871396709 0.8229851127 0.0421142172 0.0064400000 0.0004040000 0.0027410000 0.0000040000 0.0000030000 0.0021140000 15626829 96830484 509673472 2.9555280209 3.9445242882 4.3969979286 818 32.6800000000 0.5448657870 0.1875769889 0.8229851127 0.0420889308 0.0065770000 0.0004080000 0.0038390000 0.0000010000 0.0000030000 0.0011680000 15629605 96830484 509673472 2.9506728649 3.9407591820 4.3890848160 819 32.7200000000 0.5454493761 0.1880139515 0.8229851127 0.0420642167 0.0061310000 0.0004070000 0.0031150000 0.0000040000 0.0000030000 0.0014260000 15632381 96830484 509673472 2.9486055374 3.9338197708 4.3851089478 820 32.7599999990 0.5454898477 0.1884498977 0.8229851127 0.0420391373 0.0066430000 0.0004080000 0.0038890000 0.0000010000 0.0000030000 0.0011790000 15635157 96830484 509673472 2.9490847588 3.9341130257 4.3785676956 821 32.7999999990 0.5457561016 0.1888851063 0.8229851127 0.0420140882 0.0072660000 0.0004080000 0.0035080000 0.0000030000 0.0000030000 0.0021730000 15637933 96830484 509673472 2.9456639290 3.9340450764 4.3696675301 822 32.8400000000 0.5460230112 0.1893195806 0.8229851127 0.0419888565 0.0073580000 0.0004060000 0.0045980000 0.0000010000 0.0000040000 0.0011970000 15640709 96830484 509673472 2.9427590370 3.9317629337 4.3630681038 823 32.8800000000 0.5461257696 0.1897531240 0.8229851127 0.0419638694 0.0069120000 0.0004060000 0.0038660000 0.0000030000 0.0000040000 0.0014720000 15643485 96830484 509673472 2.9413106441 3.9319479465 4.3564896584 824 32.9200000000 0.5462121367 0.1901857199 0.8229851127 0.0419389217 0.0078900000 0.0004050000 0.0047910000 0.0000010000 0.0000040000 0.0012260000 15646261 96830484 509673472 2.9370536804 3.9324862957 4.3466124535 825 32.9600000000 0.5467699766 0.1906179432 0.8229851127 0.0419152476 0.0073850000 0.0004600000 0.0034960000 0.0000030000 0.0000030000 0.0021820000 15649037 96830484 509673472 2.9368751049 3.9263253212 4.3436331749 826 33.0000000000 0.5468677282 0.1910492383 0.8229851127 0.0418903011 0.0074070000 0.0004090000 0.0045980000 0.0000000000 0.0000030000 0.0012080000 15651813 96830484 509673472 2.9388542175 3.9269788265 4.3380312920 827 33.0400000000 0.5471926332 0.1914798833 0.8229851127 0.0418653777 0.0108280000 0.0005910000 0.0035640000 0.0000150000 0.0000130000 0.0020370000 15654589 96830484 509673472 2.9341151714 3.9241788387 4.3282961845 828 33.0800000000 0.5479407907 0.1919103917 0.8229851127 0.0418422605 0.0079670000 0.0004950000 0.0039980000 0.0000000000 0.0000060000 0.0013000000 15657365 96830484 509673472 2.9348402023 3.9147148132 4.3281192780 829 33.1199999990 0.5480754972 0.1923400239 0.8229851127 0.0418198836 0.0086930000 0.0004380000 0.0046250000 0.0000050000 0.0000040000 0.0022370000 15660141 96830484 509673472 2.9362409115 3.9155473709 4.3218784332 830 33.1600000000 0.5478090644 0.1927682998 0.8229851127 0.0417995459 0.0066400000 0.0004070000 0.0038600000 0.0000000000 0.0000030000 0.0012280000 15662917 96830484 509673472 2.9282701015 3.9197604656 4.3083109856 831 33.2000000000 0.5482720733 0.1931961022 0.8229851127 0.0417752575 0.0068980000 0.0004070000 0.0038350000 0.0000040000 0.0000030000 0.0014930000 15665693 96830484 509673472 2.9266960621 3.9155757427 4.3036184311 832 33.2400000000 0.5485541821 0.1936232153 0.8229851127 0.0417506440 0.0091950000 0.0005070000 0.0044990000 0.0000010000 0.0000100000 0.0014640000 15668469 96830484 509673472 2.9304571152 3.9112095833 4.3026480675 833 33.2800000000 0.5488586426 0.1940496684 0.8229851127 0.0417270877 0.0089920000 0.0004510000 0.0046500000 0.0000050000 0.0000040000 0.0022740000 15671245 96830484 509673472 2.9312958717 3.9099991322 4.2953200340 834 33.3200000000 0.5490751266 0.1944753584 0.8229851127 0.0417035714 0.0074510000 0.0004160000 0.0045570000 0.0000010000 0.0000040000 0.0012320000 15674021 96830484 509673472 2.9278929234 3.9081099033 4.2878513336 835 33.3600000000 0.5493769050 0.1949003902 0.8229851127 0.0416798047 0.0061950000 0.0004060000 0.0030990000 0.0000030000 0.0000030000 0.0015050000 15676797 96830484 509673472 2.9262673855 3.9070107937 4.2793178558 836 33.4000000000 0.5494374037 0.1953244775 0.8229851127 0.0416560096 0.0102710000 0.0005900000 0.0039430000 0.0000010000 0.0000150000 0.0018120000 15679573 96830484 509673472 2.9259965420 3.9073772430 4.2713050842 837 33.4399999990 0.5496478677 0.1957478029 0.8229851127 0.0416316353 0.0087010000 0.0004760000 0.0039730000 0.0000060000 0.0000060000 0.0023200000 15682349 96830484 509673472 2.9263215065 3.9053912163 4.2648687363 838 33.4800000000 0.5499750972 0.1961705085 0.8229851127 0.0416071339 0.0076520000 0.0004290000 0.0045850000 0.0000010000 0.0000050000 0.0012280000 15685125 96830484 509673472 2.9274284840 3.9017441273 4.2589712143 839 33.5200000000 0.5502354503 0.1965925168 0.8229851127 0.0415833778 0.0075920000 0.0004070000 0.0045400000 0.0000030000 0.0000030000 0.0014850000 15687901 96830484 509673472 2.9300448895 3.9017734528 4.2481179237 840 33.5600000000 0.5507352352 0.1970141153 0.8229851127 0.0415591535 0.0087050000 0.0005040000 0.0044450000 0.0000010000 0.0000080000 0.0013830000 15690677 96830484 509673472 2.9368953705 3.8953070641 4.2442145348 841 33.6000000000 0.5510692000 0.1974351083 0.8229851127 0.0415349228 0.0087350000 0.0004360000 0.0046160000 0.0000050000 0.0000040000 0.0021890000 15693453 96830484 509673472 2.9402647018 3.8916437626 4.2379202843 842 33.6400000000 0.5512292385 0.1978552913 0.8229851127 0.0415124221 0.0073320000 0.0004100000 0.0045610000 0.0000010000 0.0000030000 0.0011860000 15696229 96830484 509673472 2.9412837029 3.8897645473 4.2290811539 843 33.6800000000 0.5519018769 0.1982752754 0.8229851127 0.0414919429 0.0076540000 0.0004080000 0.0046100000 0.0000040000 0.0000020000 0.0014560000 15699005 96830484 509673472 2.9486262798 3.8846249580 4.2134957314 844 33.7200000000 0.5522833467 0.1986947162 0.8229851127 0.0414684248 0.0074490000 0.0004150000 0.0046540000 0.0000000000 0.0000040000 0.0011710000 15701781 96830484 509673472 2.9505300522 3.8825612068 4.2039337158 845 33.7599999990 0.5521865487 0.1991130498 0.8229851127 0.0414461897 0.0111920000 0.0005930000 0.0051480000 0.0000100000 0.0000100000 0.0025130000 15704557 96830484 509673472 2.9504532814 3.8840422630 4.1925506592 846 33.7999999990 0.5519875884 0.1995301591 0.8229851127 0.0414234136 0.0083080000 0.0004560000 0.0047970000 0.0000000000 0.0000050000 0.0011990000 15707333 96830484 509673472 2.9509823322 3.8885467052 4.1807065010 847 33.8400000000 0.5520449877 0.1999463514 0.8229851127 0.0413992389 0.0078110000 0.0004280000 0.0046700000 0.0000040000 0.0000040000 0.0014410000 15710109 96830484 509673472 2.9555706978 3.8891530037 4.1698822975 848 33.8800000000 0.5523636341 0.2003619378 0.8229851127 0.0413759729 0.0074090000 0.0004060000 0.0046650000 0.0000000000 0.0000040000 0.0011480000 15712885 96830484 509673472 2.9643156528 3.8865990639 4.1623525620 849 33.9200000000 0.5528256893 0.2007770895 0.8229851127 0.0413518073 0.0083050000 0.0004030000 0.0046500000 0.0000030000 0.0000020000 0.0020720000 15715661 96830484 509673472 2.9660081863 3.8819401264 4.1544919014 850 33.9600000000 0.5531296730 0.2011916219 0.8229851127 0.0413274774 0.0105480000 0.0005930000 0.0051720000 0.0000010000 0.0000100000 0.0014530000 15718437 96830484 509673472 2.9734396935 3.8783857822 4.1455936432 851 34.0000000000 0.5534230471 0.2016055249 0.8229851127 0.0413031741 0.0085870000 0.0004550000 0.0047820000 0.0000050000 0.0000050000 0.0014770000 15721213 96830484 509673472 2.9806630611 3.8749077320 4.1384339333 852 34.0400000000 0.5536707044 0.2020187469 0.8229851127 0.0412790273 0.0076390000 0.0004260000 0.0047310000 0.0000000000 0.0000040000 0.0011540000 15723989 96830484 509673472 2.9840836525 3.8739674091 4.1287851334 853 34.0800000000 0.5536048412 0.2024309229 0.8229851127 0.0412548677 0.0083400000 0.0004050000 0.0046780000 0.0000030000 0.0000030000 0.0020640000 15726765 96830484 509673472 2.9895024300 3.8750171661 4.1185040474 854 34.1199999990 0.5538314581 0.2028423989 0.8229851127 0.0412309119 0.0074230000 0.0004040000 0.0046770000 0.0000000000 0.0000030000 0.0011430000 15729541 96830484 509673472 2.9925119877 3.8740961552 4.1102633476 855 34.1600000000 0.5543209910 0.2032534850 0.8229851127 0.0412068758 0.0098920000 0.0005090000 0.0049790000 0.0000100000 0.0000090000 0.0015770000 15732317 96830484 509673472 2.9969284534 3.8703808784 4.1027359962 856 34.2000000000 0.5545245409 0.2036638484 0.8229851127 0.0411832308 0.0090150000 0.0005070000 0.0049190000 0.0000010000 0.0000070000 0.0012860000 15735093 96830484 509673472 3.0038692951 3.8691272736 4.0952873230 857 34.2400000000 0.5546198487 0.2040733653 0.8229851127 0.0411593454 0.0088500000 0.0004390000 0.0047370000 0.0000050000 0.0000040000 0.0020880000 15737869 96830484 509673472 3.0075392723 3.8670189381 4.0876727104 858 34.2800000000 0.5549650788 0.2044823300 0.8229851127 0.0411355309 0.0074270000 0.0004160000 0.0046850000 0.0000010000 0.0000040000 0.0011300000 15740645 96830484 509673472 3.0124506950 3.8639390469 4.0819988251 859 34.3200000000 0.5549349785 0.2048903075 0.8229851127 0.0411131716 0.0092060000 0.0005060000 0.0049280000 0.0000080000 0.0000070000 0.0014940000 15743421 96830484 509673472 3.0163266659 3.8651034832 4.0719809532 860 34.3600000000 0.5551151633 0.2052975457 0.8229851127 0.0410895123 0.0076450000 0.0004470000 0.0044040000 0.0000000000 0.0000040000 0.0011640000 15746197 96830484 509673472 3.0204544067 3.8642892838 4.0629377365 861 34.4000000000 0.5554580688 0.2057042362 0.8229851127 0.0410658277 0.0083320000 0.0004090000 0.0046490000 0.0000030000 0.0000030000 0.0020610000 15748973 96830484 509673472 3.0255718231 3.8605411053 4.0562663078 862 34.4400000000 0.5555936694 0.2061101404 0.8229851127 0.0410421685 0.0074230000 0.0004050000 0.0046400000 0.0000000000 0.0000030000 0.0011490000 15751749 96830484 509673472 3.0300316811 3.8585951328 4.0490579605 863 34.4800000000 0.5555247068 0.2065150240 0.8229851127 0.0410185969 0.0093020000 0.0005060000 0.0048880000 0.0000070000 0.0000070000 0.0015810000 15754525 96830484 509673472 3.0357098579 3.8592407703 4.0414733887 864 34.5200000000 0.5556265116 0.2069190882 0.8229851127 0.0409951979 0.0079130000 0.0004290000 0.0046770000 0.0000000000 0.0000040000 0.0011720000 15757301 96830484 509673472 3.0392484665 3.8604145050 4.0318694115 865 34.5600000000 0.5560265183 0.2073226806 0.8229851127 0.0409730250 0.0083090000 0.0004100000 0.0046180000 0.0000030000 0.0000030000 0.0020680000 15760077 96830484 509673472 3.0444848537 3.8542170525 4.0267553329 866 34.6000000000 0.5570759773 0.2077265528 0.8229851127 0.0409503795 0.0073470000 0.0004050000 0.0045750000 0.0000000000 0.0000030000 0.0011500000 15762853 96830484 509673472 3.0475740433 3.8426301479 4.0257730484 867 34.6400000000 0.5573571920 0.2081298177 0.8229851127 0.0409342586 0.0093070000 0.0005050000 0.0048220000 0.0000080000 0.0000070000 0.0016020000 15765629 96830484 509673472 3.0513155460 3.8383755684 4.0091071129 868 34.6800000000 0.5574639440 0.2085322763 0.8229851127 0.0409118664 0.0079370000 0.0004330000 0.0046570000 0.0000000000 0.0000040000 0.0011900000 15768405 96830484 509673472 3.0579111576 3.8360929489 4.0030922890 869 34.7200000000 0.5574634671 0.2089338082 0.8229851127 0.0408902710 0.0083000000 0.0004120000 0.0045980000 0.0000030000 0.0000030000 0.0020850000 15771181 96830484 509673472 3.0594699383 3.8355143070 3.9943940639 870 34.7600000000 0.5577209592 0.2093347130 0.8229851127 0.0408676298 0.0089510000 0.0005050000 0.0048510000 0.0000010000 0.0000080000 0.0013030000 15773957 96830484 509673472 3.0642771721 3.8333330154 3.9857151508 871 34.8000000000 0.5579409003 0.2097349497 0.8229851127 0.0408443968 0.0076790000 0.0004640000 0.0036240000 0.0000060000 0.0000050000 0.0015160000 15776733 96830484 509673472 3.0706474781 3.8295209408 3.9811317921 872 34.8400000000 0.5582227111 0.2101345916 0.8229851127 0.0408226589 0.0088890000 0.0005090000 0.0041370000 0.0000010000 0.0000080000 0.0013400000 15779509 96830484 509673472 3.0721869469 3.8269946575 3.9741802216 873 34.8800000000 0.5578894019 0.2105329362 0.8229851127 0.0408016433 0.0088930000 0.0005080000 0.0033520000 0.0000080000 0.0000070000 0.0023250000 15782285 96830484 509673472 3.0801684856 3.8307638168 3.9650278091 874 34.9200000000 0.5579645038 0.2109304552 0.8229851127 0.0407791046 0.0065420000 0.0004380000 0.0031900000 0.0000000000 0.0000060000 0.0012140000 15785061 96830484 509673472 3.0807199478 3.8307180405 3.9558115005 875 34.9600000000 0.5577117801 0.2113267767 0.8229851127 0.0407565968 0.0081270000 0.0005040000 0.0033180000 0.0000070000 0.0000070000 0.0016170000 15787837 96830484 509673472 3.0855889320 3.8338813782 3.9472935200 876 35.0000000000 0.5578056574 0.2117223005 0.8229851127 0.0407334823 0.0080540000 0.0005060000 0.0033360000 0.0000010000 0.0000090000 0.0013350000 15790613 96830484 509673472 3.0905094147 3.8320791721 3.9403364658 877 35.0400000000 0.5578362346 0.2121169572 0.8229851127 0.0407103168 0.0070810000 0.0004430000 0.0027870000 0.0000050000 0.0000050000 0.0021700000 15793389 96830484 509673472 3.0990364552 3.8281109333 3.9368915558 878 35.0800000000 0.5581395030 0.2125110603 0.8229851127 0.0406874076 0.0062110000 0.0004120000 0.0031240000 0.0000000000 0.0000030000 0.0011960000 15796165 96830484 509673472 3.1023478508 3.8238286972 3.9314579964 879 35.1200000000 0.5578025579 0.2129038834 0.8229851127 0.0406667692 0.0104410000 0.0006230000 0.0031340000 0.0000150000 0.0000150000 0.0020090000 15798941 96830484 509673472 3.1053407192 3.8270342350 3.9201815128 880 35.1600000000 0.5581223965 0.2132961772 0.8229851127 0.0406437297 0.0068840000 0.0004770000 0.0027290000 0.0000000000 0.0000060000 0.0012850000 15801717 96830484 509673472 3.1137697697 3.8243076801 3.9142980576 881 35.2000000000 0.5581918359 0.2136876592 0.8229851127 0.0406207886 0.0073490000 0.0004310000 0.0031360000 0.0000040000 0.0000040000 0.0021820000 15804493 96830484 509673472 3.1184835434 3.8213064671 3.9099092484 882 35.2400000000 0.5582668185 0.2140783385 0.8229851127 0.0405982742 0.0081340000 0.0005040000 0.0032990000 0.0000010000 0.0000080000 0.0013630000 15807269 96830484 509673472 3.1253387928 3.8207545280 3.9016244411 883 35.2800000000 0.5585908294 0.2144684999 0.8229851127 0.0405756175 0.0085040000 0.0005820000 0.0029520000 0.0000120000 0.0000090000 0.0016400000 15810045 96830484 509673472 3.1272985935 3.8193292618 3.8921723366 884 35.3200000000 0.5585625172 0.2148577465 0.8229851127 0.0405527803 0.0064720000 0.0004910000 0.0027700000 0.0000000000 0.0000050000 0.0012590000 15812821 96830484 509673472 3.1357126236 3.8186070919 3.8860814571 885 35.3600000000 0.5590880513 0.2152467073 0.8229851127 0.0405307533 0.0084390000 0.0005070000 0.0028720000 0.0000080000 0.0000070000 0.0024000000 15815597 96830484 509673472 3.1434996128 3.8110623360 3.8829035759 886 35.4000000000 0.5600340366 0.2156358578 0.8229851127 0.0405085596 0.0064750000 0.0004330000 0.0031120000 0.0000010000 0.0000060000 0.0012380000 15818373 96830484 509673472 3.1445825100 3.8023662567 3.8777911663 887 35.4400000000 0.5603650808 0.2160245041 0.8229851127 0.0404864706 0.0065100000 0.0004180000 0.0030710000 0.0000040000 0.0000030000 0.0014900000 15821149 96830484 509673472 3.1474089622 3.8007247448 3.8673343658 888 35.4800000000 0.5609527826 0.2164129368 0.8229851127 0.0404638015 0.0060360000 0.0004110000 0.0030360000 0.0000000000 0.0000030000 0.0012070000 15823925 96830484 509673472 3.1525659561 3.7956392765 3.8610494137 889 35.5200000000 0.5613549948 0.2168009481 0.8229851127 0.0404418445 0.0073560000 0.0004090000 0.0033940000 0.0000040000 0.0000030000 0.0021680000 15826701 96830484 509673472 3.1569495201 3.7920262814 3.8541791439 890 35.5600000000 0.5615687370 0.2171883277 0.8229851127 0.0404216296 0.0057160000 0.0004110000 0.0027100000 0.0000000000 0.0000030000 0.0011970000 15829477 96830484 509673472 3.1612610817 3.7917585373 3.8449032307 891 35.6000000000 0.5616760850 0.2175749581 0.8229851127 0.0404012934 0.0060160000 0.0004090000 0.0027130000 0.0000040000 0.0000030000 0.0014980000 15832253 96830484 509673472 3.1672449112 3.7925336361 3.8328394890 892 35.6400000000 0.5618724227 0.2179609418 0.8229851127 0.0403793380 0.0060720000 0.0004110000 0.0030660000 0.0000000000 0.0000030000 0.0011960000 15835029 96830484 509673472 3.1711864471 3.7915763855 3.8236632347 893 35.6800000000 0.5621739030 0.2183463987 0.8229851127 0.0403571109 0.0081140000 0.0004100000 0.0041590000 0.0000030000 0.0000030000 0.0021560000 15837805 96830484 509673472 3.1784543991 3.7885077000 3.8180170059 894 35.7200000000 0.5621648431 0.2187309831 0.8229851127 0.0403355724 0.0057110000 0.0004090000 0.0027250000 0.0000000000 0.0000050000 0.0011960000 15840581 96830484 509673472 3.1865830421 3.7891108990 3.8112902641 895 35.7600000000 0.5623544455 0.2191149199 0.8229851127 0.0403142315 0.0056260000 0.0004120000 0.0023470000 0.0000030000 0.0000030000 0.0014830000 15843357 96830484 509673472 3.1919052601 3.7891967297 3.8005640507 896 35.8000000000 0.5623760819 0.2194980239 0.8229851127 0.0402924652 0.0053920000 0.0004110000 0.0023520000 0.0000000000 0.0000030000 0.0012020000 15846133 96830484 509673472 3.1973485947 3.7901930809 3.7920458317 897 35.8400000000 0.5620263815 0.2198798838 0.8229851127 0.0402712954 0.0126320000 0.0006090000 0.0030990000 0.0000170000 0.0000130000 0.0029770000 15848909 96830484 509673472 3.2049558163 3.7961988449 3.7798841000 898 35.8800000000 0.5621596575 0.2202610417 0.8229851127 0.0402505717 0.0079730000 0.0005090000 0.0029200000 0.0000010000 0.0000100000 0.0015220000 15851685 96830484 509673472 3.2128937244 3.7963235378 3.7733533382 899 35.9200000000 0.5623530746 0.2206415668 0.8229851127 0.0402299720 0.0064420000 0.0004520000 0.0024360000 0.0000050000 0.0000050000 0.0015320000 15854461 96830484 509673472 3.2197949886 3.7935438156 3.7660548687 900 35.9600000000 0.5630848408 0.2210220593 0.8229851127 0.0402094254 0.0059210000 0.0004210000 0.0027480000 0.0000000000 0.0000030000 0.0012240000 15857237 96830484 509673472 3.2287676334 3.7855467796 3.7630898952 901 36.0000000000 0.5636785030 0.2214023661 0.8229851127 0.0401880865 0.0066290000 0.0004090000 0.0027090000 0.0000030000 0.0000030000 0.0021930000 15860013 96830484 509673472 3.2319455147 3.7786240578 3.7588903904 902 36.0400000000 0.5638905764 0.2217820648 0.8229851127 0.0401682873 0.0056200000 0.0004030000 0.0026790000 0.0000000000 0.0000040000 0.0011970000 15862789 96830484 509673472 3.2376728058 3.7778334618 3.7454047203 903 36.0800000000 0.5642197132 0.2221612870 0.8229851127 0.0401472773 0.0115700000 0.0006030000 0.0030220000 0.0000160000 0.0000130000 0.0020460000 15865565 96830484 509673472 3.2438755035 3.7735874653 3.7386050224 904 36.1200000000 0.5640584230 0.2225394918 0.8229851127 0.0401260336 0.0070940000 0.0004780000 0.0027810000 0.0000010000 0.0000080000 0.0013610000 15868341 96830484 509673472 3.2566432953 3.7729711533 3.7418785095 905 36.1600000000 0.5643115640 0.2229171405 0.8229851127 0.0401151293 0.0066880000 0.0004360000 0.0023340000 0.0000060000 0.0000040000 0.0021680000 15871117 96830484 509673472 3.2800657749 3.7696020603 3.7148156166 906 36.2000000000 0.5644201040 0.2232940753 0.8229851127 0.0400940605 0.0064140000 0.0004140000 0.0034470000 0.0000000000 0.0000030000 0.0011850000 15873893 96830484 509673472 3.2872734070 3.7668597698 3.7066109180 907 36.2400000000 0.5652200580 0.2236710610 0.8229851127 0.0400725633 0.0059400000 0.0004040000 0.0027070000 0.0000030000 0.0000030000 0.0014890000 15876669 96830484 509673472 3.2935662270 3.7611110210 3.7023620605 908 36.2800000000 0.5652033091 0.2240471978 0.8229851127 0.0400533103 0.0056540000 0.0004050000 0.0027140000 0.0000000000 0.0000040000 0.0011940000 15879445 96830484 509673472 3.2976510525 3.7613911629 3.6956527233 909 36.3200000000 0.5648696423 0.2244221400 0.8229851127 0.0400325564 0.0127010000 0.0005940000 0.0037250000 0.0000150000 0.0000150000 0.0029250000 15882221 96830484 509673472 3.3077137470 3.7645163536 3.6911735535 910 36.3600000000 0.5649607182 0.2247963582 0.8229851127 0.0400114254 0.0077240000 0.0005030000 0.0028180000 0.0000010000 0.0000120000 0.0013610000 15884997 96830484 509673472 3.3164184093 3.7633490562 3.6898579597 911 36.4000000000 0.5651649833 0.2251699791 0.8229851127 0.0399902847 0.0068000000 0.0004500000 0.0027780000 0.0000050000 0.0000040000 0.0015250000 15887773 96830484 509673472 3.3215110302 3.7606801987 3.6877791882 912 36.4400000000 0.5650838614 0.2255426917 0.8229851127 0.0399692930 0.0059290000 0.0004210000 0.0027590000 0.0000010000 0.0000040000 0.0012100000 15890549 96830484 509673472 3.3289468288 3.7609081268 3.6812272072 913 36.4800000000 0.5652330518 0.2259147512 0.8229851127 0.0399480508 0.0092230000 0.0005770000 0.0029390000 0.0000080000 0.0000070000 0.0025660000 15893325 96830484 509673472 3.3360888958 3.7591009140 3.6763792038 914 36.5200000000 0.5656062961 0.2262864050 0.8229851127 0.0399266124 0.0075130000 0.0005090000 0.0025580000 0.0000010000 0.0000100000 0.0013990000 15896101 96830484 509673472 3.3417615891 3.7556023598 3.6726791859 915 36.5600000000 0.5653402805 0.2266569557 0.8229851127 0.0399052616 0.0072840000 0.0004490000 0.0035220000 0.0000060000 0.0000050000 0.0015430000 15898877 96830484 509673472 3.3507037163 3.7559220791 3.6705601215 916 36.6000000000 0.5652161241 0.2270265618 0.8229851127 0.0398844468 0.0064580000 0.0004160000 0.0034520000 0.0000000000 0.0000040000 0.0012020000 15901653 96830484 509673472 3.3594293594 3.7574067116 3.6651670933 917 36.6400000000 0.5656969547 0.2273958861 0.8229851127 0.0398629109 0.0069730000 0.0004060000 0.0030890000 0.0000030000 0.0000030000 0.0021530000 15904429 96830484 509673472 3.3657221794 3.7522943020 3.6622443199 918 36.6800000000 0.5660994053 0.2277648441 0.8229851127 0.0398418963 0.0056540000 0.0004070000 0.0027350000 0.0000000000 0.0000030000 0.0012010000 15907205 96830484 509673472 3.3717668056 3.7474532127 3.6584544182 919 36.7200000000 0.5658696294 0.2281327492 0.8229851127 0.0398211053 0.0056310000 0.0004090000 0.0023670000 0.0000030000 0.0000030000 0.0014980000 15909981 96830484 509673472 3.3792555332 3.7491431236 3.6544625759 920 36.7600000000 0.5660120845 0.2285000094 0.8229851127 0.0397997232 0.0056620000 0.0004060000 0.0027280000 0.0000000000 0.0000040000 0.0011980000 15912757 96830484 509673472 3.3850975037 3.7495892048 3.6479036808 921 36.8000000000 0.5657391548 0.2288661757 0.8229851127 0.0397784613 0.0066600000 0.0004060000 0.0027340000 0.0000040000 0.0000030000 0.0021930000 15915533 96830484 509673472 3.3966841698 3.7524716854 3.6462082863 922 36.8400000000 0.5662271380 0.2292320769 0.8229851127 0.0397581514 0.0116850000 0.0005880000 0.0033900000 0.0000010000 0.0000160000 0.0017600000 15918309 96830484 509673472 3.4066684246 3.7474391460 3.6450400352 923 36.8800000000 0.5661159158 0.2295970648 0.8229851127 0.0397367041 0.0079290000 0.0005060000 0.0025920000 0.0000110000 0.0000090000 0.0017870000 15921085 96830484 509673472 3.4138889313 3.7452890873 3.6432662010 924 36.9200000000 0.5658866763 0.2299610146 0.8229851127 0.0397160637 0.0066020000 0.0004520000 0.0028750000 0.0000010000 0.0000060000 0.0012380000 15923861 96830484 509673472 3.4249854088 3.7480349541 3.6355895996 925 36.9600000000 0.5660676956 0.2303243732 0.8229851127 0.0396954776 0.0065280000 0.0004230000 0.0023200000 0.0000040000 0.0000040000 0.0021890000 15926637 96830484 509673472 3.4357299805 3.7473130226 3.6305251122 926 37.0000000000 0.5659497380 0.2306868196 0.8229851127 0.0396758163 0.0052360000 0.0004070000 0.0023050000 0.0000010000 0.0000040000 0.0012010000 15929413 96830484 509673472 3.4518756866 3.7479493618 3.6226665974 927 37.0400000000 0.5659900904 0.2310485276 0.8229851127 0.0396548907 0.0111900000 0.0005940000 0.0032130000 0.0000150000 0.0000130000 0.0020890000 15932189 96830484 509673472 3.4646511078 3.7484407425 3.6199026108 928 37.0800000000 0.5662279129 0.2314097122 0.8229851127 0.0396337326 0.0066440000 0.0004770000 0.0024220000 0.0000010000 0.0000080000 0.0012780000 15934965 96830484 509673472 3.4722719193 3.7438337803 3.6170601845 929 37.1200000000 0.5665445328 0.2317704602 0.8229851127 0.0396126877 0.0072980000 0.0004340000 0.0028530000 0.0000050000 0.0000040000 0.0022160000 15937741 96830484 509673472 3.4816973209 3.7402956486 3.6141967773 930 37.1600000000 0.5664867759 0.2321303702 0.8229851127 0.0395918308 0.0054600000 0.0004130000 0.0024510000 0.0000000000 0.0000040000 0.0011920000 15940517 96830484 509673472 3.4920554161 3.7398462296 3.6107692719 931 37.2000000000 0.5667239428 0.2324897618 0.8229851127 0.0395708279 0.0102280000 0.0006340000 0.0031800000 0.0000140000 0.0000140000 0.0020520000 15943293 96830484 509673472 3.4992275238 3.7368533611 3.6062252522 932 37.2400000000 0.5668158531 0.2328484808 0.8229851127 0.0395498453 0.0070960000 0.0004710000 0.0029550000 0.0000010000 0.0000060000 0.0012840000 15946069 96830484 509673472 3.5103821754 3.7382299900 3.6057755947 933 37.2800000000 0.5667433143 0.2332063530 0.8229851127 0.0395291298 0.0129330000 0.0005970000 0.0031500000 0.0000150000 0.0000130000 0.0029170000 15948845 96830484 509673472 3.5211820602 3.7394981384 3.6009657383 934 37.3200000000 0.5668630600 0.2335635872 0.8229851127 0.0395086450 0.0117400000 0.0006050000 0.0031470000 0.0000020000 0.0000170000 0.0017640000 15951621 96830484 509673472 3.5317223072 3.7401189804 3.5963847637 935 37.3600000000 0.5671141148 0.2339203257 0.8229851127 0.0394881817 0.0108080000 0.0006110000 0.0027460000 0.0000150000 0.0000150000 0.0020480000 15954397 96830484 509673472 3.5431644917 3.7401213646 3.5952100754 936 37.4000000000 0.5671448708 0.2342763349 0.8229851127 0.0394673486 0.0072200000 0.0004730000 0.0029270000 0.0000000000 0.0000080000 0.0012760000 15957173 96830484 509673472 3.5540828705 3.7384808064 3.5961656570 937 37.4400000000 0.5674842596 0.2346319463 0.8229851127 0.0394465952 0.0075940000 0.0004400000 0.0031990000 0.0000040000 0.0000050000 0.0021810000 15959949 96830484 509673472 3.5654370785 3.7366216183 3.5957477093 938 37.4800000000 0.5680477023 0.2349874002 0.8229851127 0.0394257595 0.0056960000 0.0004130000 0.0026650000 0.0000010000 0.0000030000 0.0011850000 15962725 96830484 509673472 3.5729706287 3.7331509590 3.5928213596 939 37.5200000000 0.5676814318 0.2353417069 0.8229851127 0.0394056025 0.0082900000 0.0005030000 0.0029940000 0.0000110000 0.0000100000 0.0016760000 15965501 96830484 509673472 3.5844879150 3.7358622551 3.5886147022 940 37.5600000000 0.5676311851 0.2356952064 0.8229851127 0.0393848254 0.0064740000 0.0004470000 0.0028310000 0.0000010000 0.0000060000 0.0012170000 15968277 96830484 509673472 3.5962386131 3.7378778458 3.5888249874 941 37.6000000000 0.5678622723 0.2360482001 0.8229851127 0.0393640315 0.0064630000 0.0004160000 0.0024490000 0.0000030000 0.0000030000 0.0021630000 15971053 96830484 509673472 3.6046655178 3.7351813316 3.5867302418 942 37.6400000000 0.5683106184 0.2364009203 0.8229851127 0.0393434106 0.0112260000 0.0005880000 0.0039770000 0.0000020000 0.0000150000 0.0017280000 15973829 96830484 509673472 3.6127436161 3.7317149639 3.5840167999 943 37.6800000000 0.5683205724 0.2367529029 0.8229851127 0.0393228401 0.0074990000 0.0004770000 0.0029530000 0.0000060000 0.0000060000 0.0015440000 15976605 96830484 509673472 3.6242170334 3.7311835289 3.5838813782 944 37.7200000000 0.5683037639 0.2371041221 0.8229851127 0.0393022041 0.0062550000 0.0004400000 0.0028640000 0.0000010000 0.0000050000 0.0011890000 15979381 96830484 509673472 3.6324636936 3.7298338413 3.5847640038 945 37.7600000000 0.5683605671 0.2374546580 0.8229851127 0.0392817576 0.0063790000 0.0004090000 0.0024760000 0.0000040000 0.0000030000 0.0021240000 15982157 96830484 509673472 3.6441054344 3.7286758423 3.5864419937 946 37.8000000000 0.5685680509 0.2378046721 0.8229851127 0.0392615496 0.0060230000 0.0004050000 0.0030970000 0.0000000000 0.0000030000 0.0011530000 15984933 96830484 509673472 3.6536228657 3.7264049053 3.5853812695 947 37.8400000000 0.5687762499 0.2381541669 0.8229851127 0.0392426522 0.0060880000 0.0004090000 0.0028530000 0.0000040000 0.0000030000 0.0014590000 15987709 96830484 509673472 3.6629166603 3.7240996361 3.5821650028 948 37.8800000000 0.5690329075 0.2385031952 0.8229851127 0.0392233458 0.0108680000 0.0005940000 0.0032650000 0.0000020000 0.0000150000 0.0017030000 15990485 96830484 509673472 3.6727299690 3.7215540409 3.5812466145 949 37.9200000000 0.5692281723 0.2388516936 0.8229851127 0.0392044131 0.0080450000 0.0004790000 0.0028480000 0.0000060000 0.0000060000 0.0021760000 15993261 96830484 509673472 3.6821844578 3.7209718227 3.5774667263 950 37.9600000000 0.5694217086 0.2391996620 0.8229851127 0.0391845989 0.0062790000 0.0004380000 0.0029210000 0.0000010000 0.0000050000 0.0011520000 15996037 96830484 509673472 3.6923744678 3.7204873562 3.5757610798 951 38.0000000000 0.5699485540 0.2395474526 0.8229851127 0.0391645181 0.0083090000 0.0005040000 0.0030990000 0.0000100000 0.0000090000 0.0015450000 15998813 96830484 509673472 3.7013213634 3.7182271481 3.5750775337 952 38.0400000000 0.5706328154 0.2398952314 0.8229851127 0.0391448870 0.0077490000 0.0005060000 0.0025590000 0.0000010000 0.0000100000 0.0014130000 16001589 96830484 509673472 3.7109198570 3.7153248787 3.5729851723 953 38.0800000000 0.5708626509 0.2402425214 0.8229851127 0.0391253606 0.0076270000 0.0004550000 0.0029620000 0.0000060000 0.0000050000 0.0020860000 16004365 96830484 509673472 3.7209630013 3.7147376537 3.5723888874 954 38.1200000000 0.5714308619 0.2405896790 0.8229851127 0.0391055859 0.0077100000 0.0005100000 0.0027100000 0.0000010000 0.0000070000 0.0012560000 16007141 96830484 509673472 3.7316131592 3.7136046886 3.5711920261 955 38.1600000000 0.5715518594 0.2409362363 0.8229851127 0.0390865394 0.0084460000 0.0005170000 0.0031050000 0.0000100000 0.0000090000 0.0015900000 16009917 96830484 509673472 3.7414269447 3.7142484188 3.5691668987 956 38.2000000000 0.5722554922 0.2412828045 0.8229851127 0.0390667083 0.0067140000 0.0004490000 0.0029650000 0.0000000000 0.0000050000 0.0011470000 16012693 96830484 509673472 3.7523910999 3.7134003639 3.5668625832 957 38.2400000000 0.5728677511 0.2416292883 0.8229851127 0.0390464954 0.0091500000 0.0005030000 0.0029590000 0.0000080000 0.0000070000 0.0023070000 16015469 96830484 509673472 3.7631299496 3.7124266624 3.5638289452 958 38.2800000000 0.5733440518 0.2419755459 0.8229851127 0.0390262526 0.0061090000 0.0004410000 0.0025650000 0.0000000000 0.0000050000 0.0011590000 16018245 96830484 509673472 3.7716031075 3.7101464272 3.5608181953 959 38.3200000000 0.5735939741 0.2423213419 0.8229851127 0.0390065299 0.0087360000 0.0005160000 0.0031100000 0.0000100000 0.0000090000 0.0016450000 16021021 96830484 509673472 3.7827425003 3.7126839161 3.5587184429 960 38.3600000000 0.5735448599 0.2426663664 0.8229851127 0.0389865502 0.0064300000 0.0004600000 0.0026090000 0.0000010000 0.0000050000 0.0011470000 16023797 96830484 509673472 3.7963063717 3.7163684368 3.5574131012 961 38.4000000000 0.5741385818 0.2430112907 0.8229851127 0.0389692100 0.0069220000 0.0004230000 0.0029160000 0.0000040000 0.0000040000 0.0020580000 16026573 96830484 509673472 3.8051111698 3.7103276253 3.5581736565 962 38.4400000000 0.5742647648 0.2433556290 0.8229851127 0.0389496692 0.0090990000 0.0005050000 0.0039180000 0.0000010000 0.0000100000 0.0013690000 16029349 96830484 509673472 3.8148748875 3.7075250149 3.5574193001 963 38.4800000000 0.5742456913 0.2436992324 0.8229851127 0.0389303229 0.0066660000 0.0004520000 0.0026170000 0.0000050000 0.0000050000 0.0014100000 16032125 96830484 509673472 3.8267443180 3.7051417828 3.5555291176 964 38.5200000000 0.5743880868 0.2440422706 0.8229851127 0.0389110056 0.0092670000 0.0006060000 0.0033040000 0.0000010000 0.0000100000 0.0013450000 16034901 96830484 509673472 3.8368976116 3.7029399872 3.5554215908 965 38.5600000000 0.5747420192 0.2443849647 0.8229851127 0.0388911877 0.0077930000 0.0004560000 0.0030240000 0.0000060000 0.0000060000 0.0020900000 16037677 96830484 509673472 3.8474168777 3.7003679276 3.5523977280 966 38.6000000000 0.5747029781 0.2447269088 0.8229851127 0.0388716534 0.0065770000 0.0004220000 0.0033670000 0.0000010000 0.0000040000 0.0011260000 16040453 96830484 509673472 3.8568687439 3.6978440285 3.5507977009 967 38.6400000000 0.5747291446 0.2450681727 0.8229851127 0.0388530432 0.0058010000 0.0004090000 0.0025600000 0.0000030000 0.0000030000 0.0013960000 16043229 96830484 509673472 3.8679132462 3.6964879036 3.5500771999 968 38.6800000000 0.5748500824 0.2454088565 0.8229851127 0.0388338232 0.0076690000 0.0004060000 0.0045470000 0.0000010000 0.0000040000 0.0011220000 16046005 96830484 509673472 3.8775179386 3.6942465305 3.5470087528 969 38.7200000000 0.5747155547 0.2457486983 0.8229851127 0.0388141913 0.0071660000 0.0004690000 0.0029490000 0.0000030000 0.0000030000 0.0020350000 16048781 96830484 509673472 3.8877704144 3.6939613819 3.5464048386 970 38.7600000000 0.5747392178 0.2460878638 0.8229851127 0.0387945826 0.0069620000 0.0004240000 0.0037580000 0.0000000000 0.0000030000 0.0011080000 16051557 96830484 509673472 3.8954911232 3.6913669109 3.5424408913 971 38.8000000000 0.5745062828 0.2464260908 0.8229851127 0.0387752018 0.0062250000 0.0004110000 0.0029720000 0.0000040000 0.0000030000 0.0013880000 16054333 96830484 509673472 3.9059758186 3.6906149387 3.5391912460 972 38.8400000000 0.5743156075 0.2467634257 0.8229851127 0.0387562214 0.0075240000 0.0004070000 0.0045800000 0.0000000000 0.0000030000 0.0011130000 16057109 96830484 509673472 3.9158225060 3.6903285980 3.5372643471 973 38.8800000000 0.5741792321 0.2470999270 0.8229851127 0.0387391367 0.0064480000 0.0004060000 0.0025780000 0.0000030000 0.0000030000 0.0020450000 16059885 96830484 509673472 3.9262514114 3.6901109219 3.5360465050 974 38.9200000000 0.5741494298 0.2474357068 0.8229851127 0.0387218722 0.0114570000 0.0005950000 0.0029620000 0.0000020000 0.0000160000 0.0015000000 16062661 96830484 509673472 3.9343822002 3.6881206036 3.5372610092 975 38.9600000000 0.5741332173 0.2477707812 0.8229851127 0.0387026954 0.0088350000 0.0004990000 0.0027070000 0.0000140000 0.0000080000 0.0015720000 16065437 96830484 509673472 3.9434671402 3.6863813400 3.5374951363 976 39.0000000000 0.5741037130 0.2481051387 0.8229851127 0.0386832479 0.0064160000 0.0005010000 0.0026490000 0.0000010000 0.0000050000 0.0011280000 16068213 96830484 509673472 3.9529416561 3.6846346855 3.5370917320 977 39.0400000000 0.5739769340 0.2484386820 0.8229851127 0.0386638256 0.0067760000 0.0004680000 0.0024840000 0.0000040000 0.0000040000 0.0020950000 16070989 96830484 509673472 3.9633681774 3.6844573021 3.5365068913 978 39.0800000000 0.5737898946 0.2487713519 0.8229851127 0.0386443982 0.0060260000 0.0004510000 0.0029920000 0.0000000000 0.0000030000 0.0011240000 16073765 96830484 509673472 3.9726488590 3.6831843853 3.5385620594 979 39.1200000000 0.5738624334 0.2491034164 0.8229851127 0.0386271444 0.0057110000 0.0004090000 0.0024480000 0.0000040000 0.0000030000 0.0014060000 16076541 96830484 509673472 3.9809484482 3.6808383465 3.5361387730 980 39.1600000000 0.5736904740 0.2494346277 0.8229851127 0.0386091409 0.0053990000 0.0004100000 0.0024410000 0.0000010000 0.0000040000 0.0011240000 16079317 96830484 509673472 3.9922878742 3.6804206371 3.5342745781 981 39.2000000000 0.5733730793 0.2497648401 0.8229851127 0.0385898733 0.0069240000 0.0004070000 0.0029720000 0.0000040000 0.0000030000 0.0021030000 16082093 96830484 509673472 4.0044403076 3.6816880703 3.5339596272 982 39.2400000000 0.5732236505 0.2500942279 0.8229851127 0.0385704427 0.0055330000 0.0004070000 0.0025680000 0.0000000000 0.0000030000 0.0011300000 16084869 96830484 509673472 4.0104417801 3.6805858612 3.5350415707 983 39.2800000000 0.5731780529 0.2504228992 0.8229851127 0.0385515634 0.0057280000 0.0004120000 0.0024190000 0.0000040000 0.0000030000 0.0014300000 16087645 96830484 509673472 4.0201754570 3.6793594360 3.5356040001 984 39.3200000000 0.5730741620 0.2507507968 0.8229851127 0.0385326187 0.0053880000 0.0004080000 0.0024150000 0.0000010000 0.0000030000 0.0011240000 16090421 96830484 509673472 4.0315256119 3.6791262627 3.5347936153 985 39.3600000000 0.5731212497 0.2510780764 0.8229851127 0.0385133204 0.0067640000 0.0004070000 0.0028000000 0.0000030000 0.0000030000 0.0021130000 16093197 96830484 509673472 4.0397548676 3.6766979694 3.5346109867 986 39.4000000000 0.5729457140 0.2514045142 0.8229851127 0.0384941775 0.0058830000 0.0004080000 0.0029150000 0.0000000000 0.0000040000 0.0011290000 16095973 96830484 509673472 4.0476241112 3.6758563519 3.5375418663 987 39.4400000000 0.5728822947 0.2517302262 0.8229851127 0.0384753765 0.0057070000 0.0004170000 0.0023920000 0.0000040000 0.0000030000 0.0014650000 16098749 96830484 509673472 4.0572042465 3.6745483875 3.5389535427 988 39.4800000000 0.5727134347 0.2520551080 0.8229851127 0.0384563226 0.0058750000 0.0004070000 0.0029080000 0.0000010000 0.0000030000 0.0011290000 16101525 96830484 509673472 4.0676918030 3.6737656593 3.5393240452 989 39.5200000000 0.5727124810 0.2523793319 0.8229851127 0.0384373008 0.0064750000 0.0004050000 0.0025140000 0.0000040000 0.0000030000 0.0021080000 16104301 96830484 509673472 4.0765819550 3.6728396416 3.5394732952 990 39.5600000000 0.5725136995 0.2527026999 0.8229851127 0.0384181312 0.0057460000 0.0004050000 0.0027540000 0.0000000000 0.0000040000 0.0011400000 16107077 96830484 509673472 4.0863361359 3.6731524467 3.5400247574 991 39.6000000000 0.5720630884 0.2530249607 0.8229851127 0.0383988890 0.0057110000 0.0004060000 0.0023830000 0.0000030000 0.0000030000 0.0014700000 16109853 96830484 509673472 4.0960502625 3.6753571033 3.5432806015 992 39.6400000000 0.5718047619 0.2533463113 0.8229851127 0.0383797882 0.0053570000 0.0004050000 0.0023820000 0.0000000000 0.0000030000 0.0011320000 16112629 96830484 509673472 4.1057271957 3.6778898239 3.5445227623 993 39.6800000000 0.5712867379 0.2536664930 0.8229851127 0.0383614717 0.0067360000 0.0004060000 0.0027670000 0.0000040000 0.0000030000 0.0021070000 16115405 96830484 509673472 4.1149005890 3.6803045273 3.5488498211 994 39.7200000000 0.5710795522 0.2539858220 0.8229851127 0.0383433452 0.0057760000 0.0004070000 0.0027690000 0.0000010000 0.0000030000 0.0011390000 16118181 96830484 509673472 4.1245102882 3.6811983585 3.5510354042 995 39.7600000000 0.5709823966 0.2543044115 0.8229851127 0.0383252034 0.0058290000 0.0004070000 0.0025050000 0.0000040000 0.0000030000 0.0014600000 16120957 96830484 509673472 4.1328864098 3.6799693108 3.5529830456 996 39.8000000000 0.5708392859 0.2546222176 0.8229851127 0.0383063351 0.0055180000 0.0004080000 0.0025160000 0.0000000000 0.0000040000 0.0011310000 16123733 96830484 509673472 4.1423625946 3.6792001724 3.5555548668 997 39.8400000000 0.5706542134 0.2549392006 0.8229851127 0.0382874709 0.0069370000 0.0004130000 0.0028960000 0.0000040000 0.0000030000 0.0021150000 16126509 96830484 509673472 4.1529302597 3.6793651581 3.5576658249 998 39.8800000000 0.5706261396 0.2552555201 0.8229851127 0.0382686696 0.0066200000 0.0004660000 0.0031640000 0.0000010000 0.0000040000 0.0011450000 16129285 96830484 509673472 4.1620798111 3.6784303188 3.5591142178 999 39.9200000000 0.5699553490 0.2555705350 0.8229851127 0.0382497511 0.0059210000 0.0004550000 0.0025150000 0.0000040000 0.0000030000 0.0014660000 16132061 96830484 509673472 4.1747617722 3.6830134392 3.5623588562 1000 39.9600000000 0.5698540211 0.2558848185 0.8229851127 0.0382312084 0.0116450000 0.0005960000 0.0031220000 0.0000020000 0.0000150000 0.0015260000 16134837 96830484 509673472 4.1836509705 3.6822147369 3.5627722740 1001 40.0000000000 0.5697277188 0.2561983478 0.8229851127 0.0382121734 0.0092130000 0.0005070000 0.0030960000 0.0000110000 0.0000080000 0.0022530000 16137613 96830484 509673472 4.1927933693 3.6811244488 3.5637106895 1002 40.0400000000 0.5693739653 0.2565108984 0.8229851127 0.0381933280 0.0062400000 0.0004540000 0.0024300000 0.0000000000 0.0000050000 0.0011440000 16140389 96830484 509673472 4.2033185959 3.6824083328 3.5665166378 1003 40.0800000000 0.5682509542 0.2568217060 0.8229851127 0.0381744718 0.0066960000 0.0004150000 0.0032560000 0.0000040000 0.0000030000 0.0014720000 16143165 96830484 509673472 4.2146987915 3.6849863529 3.5678627491 1004 40.1200000000 0.5675147176 0.2571311612 0.8229851127 0.0381563787 0.0062460000 0.0004070000 0.0032410000 0.0000010000 0.0000030000 0.0011240000 16145941 96830484 509673472 4.2233963013 3.6841657162 3.5695612431 1005 40.1600000000 0.5666732192 0.2574391632 0.8229851127 0.0381375007 0.0113550000 0.0005950000 0.0036410000 0.0000160000 0.0000130000 0.0026470000 16148717 96830484 509673472 4.2328462601 3.6843810081 3.5704357624 1006 40.2000000000 0.5655859113 0.2577454721 0.8229851127 0.0381186463 0.0070840000 0.0004770000 0.0029570000 0.0000010000 0.0000060000 0.0011600000 16151493 96830484 509673472 4.2430543900 3.6869349480 3.5735294819 1007 40.2400000000 0.5640581846 0.2580496555 0.8229851127 0.0380999661 0.0080510000 0.0004280000 0.0043990000 0.0000040000 0.0000030000 0.0014650000 16154269 96830484 509673472 4.2528061867 3.6886601448 3.5759158134 1008 40.2800000000 0.5636519194 0.2583528324 0.8229851127 0.0380814799 0.0058610000 0.0004110000 0.0028580000 0.0000000000 0.0000040000 0.0011220000 16157045 96830484 509673472 4.2607259750 3.6882264614 3.5786499977 1009 40.3200000000 0.5632782578 0.2586550380 0.8229851127 0.0380627783 0.0072280000 0.0004080000 0.0032260000 0.0000040000 0.0000030000 0.0021000000 16159821 96830484 509673472 4.2692360878 3.6890571117 3.5820846558 1010 40.3600000000 0.5623353720 0.2589557116 0.8229851127 0.0380441114 0.0101100000 0.0005080000 0.0042500000 0.0000020000 0.0000100000 0.0013030000 16162597 96830484 509673472 4.2791109085 3.6899237633 3.5846292973 1011 40.4000000000 0.5621837974 0.2592556404 0.8229851127 0.0380255610 0.0088900000 0.0005040000 0.0034370000 0.0000090000 0.0000070000 0.0015200000 16165373 96830484 509673472 4.2869200706 3.6891615391 3.5863001347 1012 40.4400000000 0.5619439483 0.2595547396 0.8229851127 0.0380070008 0.0066070000 0.0004530000 0.0028880000 0.0000000000 0.0000050000 0.0011210000 16168149 96830484 509673472 4.2948498726 3.6876983643 3.5875086784 1013 40.4800000000 0.5612241626 0.2598525376 0.8229851127 0.0379886880 0.0080360000 0.0004160000 0.0039410000 0.0000040000 0.0000100000 0.0020830000 16170925 96830484 509673472 4.3038234711 3.6887645721 3.5918672085 1014 40.5200000000 0.5623028874 0.2601508121 0.8229851127 0.0379701826 0.0065230000 0.0004080000 0.0035390000 0.0000000000 0.0000030000 0.0011050000 16173701 96830484 509673472 4.3108797073 3.6889090538 3.5962417126 1015 40.5600000000 0.5621319413 0.2604483305 0.8229851127 0.0379520714 0.0086040000 0.0005080000 0.0030380000 0.0000100000 0.0000080000 0.0015850000 16176477 96830484 509673472 4.3188414574 3.6875052452 3.5970876217 1016 40.6000000000 0.5609476566 0.2607440975 0.8229851127 0.0379337940 0.0064260000 0.0004600000 0.0024890000 0.0000000000 0.0000050000 0.0011200000 16179253 96830484 509673472 4.3262119293 3.6852576733 3.5971984863 1017 40.6400000000 0.5600368977 0.2610383874 0.8229851127 0.0379158297 0.0077180000 0.0004230000 0.0031880000 0.0000040000 0.0000040000 0.0020820000 16182029 96830484 509673472 4.3332295418 3.6863150597 3.6007201672 1018 40.6800000000 0.5590330958 0.2613311130 0.8229851127 0.0378974554 0.0077800000 0.0004230000 0.0046460000 0.0000000000 0.0000040000 0.0011050000 16184805 96830484 509673472 4.3417134285 3.6863536835 3.6028964520 1019 40.7200000000 0.5576899052 0.2616219460 0.8229851127 0.0378790104 0.0057580000 0.0004070000 0.0024170000 0.0000040000 0.0000030000 0.0014130000 16187581 96830484 509673472 4.3485522270 3.6869595051 3.6059887409 1020 40.7600000000 0.5537822843 0.2619083777 0.8229851127 0.0378608812 0.0109300000 0.0005900000 0.0039410000 0.0000020000 0.0000180000 0.0014750000 16190357 96830484 509673472 4.3573136330 3.6870882511 3.6062631607 1021 40.8000000000 0.5529893637 0.2621934717 0.8229851127 0.0378424000 0.0096400000 0.0004750000 0.0047350000 0.0000070000 0.0000060000 0.0020940000 16193133 96830484 509673472 4.3653793335 3.6879420280 3.6101751328 1022 40.8400000000 0.5516620874 0.2624767091 0.8229851127 0.0378239681 0.0071660000 0.0004280000 0.0038900000 0.0000010000 0.0000040000 0.0010930000 16195909 96830484 509673472 4.3726668358 3.6892945766 3.6152374744 1023 40.8800000000 0.5534788966 0.2627611687 0.8229851127 0.0378056558 0.0064210000 0.0004090000 0.0031390000 0.0000030000 0.0000030000 0.0014060000 16198685 96830484 509673472 4.3797516823 3.6900684834 3.6225759983 1024 40.9200000000 0.5509536862 0.2630426067 0.8229851127 0.0377878451 0.0084440000 0.0005080000 0.0025810000 0.0000010000 0.0000100000 0.0012730000 16201461 96830484 509673472 4.3889894485 3.6911284924 3.6246476173 1025 40.9600000000 0.5512681007 0.2633238023 0.8229851127 0.0377695857 0.0091190000 0.0005050000 0.0029840000 0.0000110000 0.0000090000 0.0021830000 16314733 96830484 509673472 4.3985157013 3.6924169064 3.6310694218 1026 41.0000000000 0.5510916114 0.2636042778 0.8229851127 0.0377515491 0.0071330000 0.0004330000 0.0035700000 0.0000010000 0.0000060000 0.0010960000 16510117 96830484 509673472 4.4045205116 3.6927425861 3.6366736889 1027 41.0400000000 0.5502732396 0.2638834102 0.8229851127 0.0377335213 0.0069410000 0.0004170000 0.0035030000 0.0000030000 0.0000040000 0.0014040000 16512893 96830484 509673472 4.4127712250 3.6913919449 3.6376464367 1028 41.0800000000 0.5497070551 0.2641614487 0.8229851127 0.0377154562 0.0102590000 0.0005180000 0.0048460000 0.0000010000 0.0000120000 0.0012840000 16515669 96830484 509673472 4.4237146378 3.6939539909 3.6446602345 1029 41.1200000000 0.5495136380 0.2644387589 0.8229851127 0.0376971845 0.0085840000 0.0004540000 0.0039220000 0.0000060000 0.0000050000 0.0020570000 16518445 96830484 509673472 4.4322376251 3.6937959194 3.6469640732 1030 41.1600000000 0.5502264500 0.2647162227 0.8229851127 0.0376792386 0.0058890000 0.0004110000 0.0027610000 0.0000000000 0.0000040000 0.0010840000 16521221 96830484 509673472 4.4402341843 3.6937513351 3.6511826515 1031 41.2000000000 0.5491890311 0.2649921420 0.8229851127 0.0376615648 0.0088500000 0.0005060000 0.0029370000 0.0000100000 0.0000090000 0.0015660000 16523997 96830484 509673472 4.4490785599 3.6934168339 3.6551644802 1032 41.2400000000 0.5489254594 0.2652672712 0.8229851127 0.0376439569 0.0067730000 0.0004530000 0.0028260000 0.0000010000 0.0000050000 0.0010890000 16526773 96830484 509673472 4.4576177597 3.6938042641 3.6599161625 1033 41.2800000000 0.5483666658 0.2655413268 0.8229851127 0.0376263609 0.0074180000 0.0004230000 0.0031420000 0.0000050000 0.0000040000 0.0020340000 16529549 96830484 509673472 4.4675045013 3.6955554485 3.6652772427 1034 41.3200000000 0.5479741693 0.2658144726 0.8229851127 0.0376094537 0.0058610000 0.0004100000 0.0027410000 0.0000000000 0.0000040000 0.0010700000 16532325 96830484 509673472 4.4775519371 3.6964113712 3.6704893112 1035 41.3600000000 0.5475419164 0.2660866731 0.8229851127 0.0375931082 0.0120130000 0.0006020000 0.0031160000 0.0000160000 0.0000140000 0.0017110000 16535101 96830484 509673472 4.4836306572 3.6968307495 3.6740739346 1036 41.4000000000 0.5474276543 0.2663582377 0.8229851127 0.0375752916 0.0073500000 0.0004760000 0.0028730000 0.0000010000 0.0000080000 0.0011100000 16537877 96830484 509673472 4.4900479317 3.6947009563 3.6772246361 1037 41.4400000000 0.5472246408 0.2666290829 0.8229851127 0.0375577696 0.0076390000 0.0004370000 0.0031280000 0.0000050000 0.0000040000 0.0020430000 16540653 96830484 509673472 4.4995594025 3.6940507889 3.6805331707 1038 41.4800000000 0.5462171435 0.2668984355 0.8229851127 0.0375401112 0.0061710000 0.0004090000 0.0031000000 0.0000000000 0.0000030000 0.0010630000 16543429 96830484 509673472 4.5088787079 3.6964461803 3.6854212284 1039 41.5200000000 0.5454754233 0.2671665558 0.8229851127 0.0375222105 0.0067910000 0.0004070000 0.0034480000 0.0000040000 0.0000030000 0.0013680000 16546205 96830484 509673472 4.5181393623 3.6985039711 3.6891136169 1040 41.5600000000 0.5446861982 0.2674334016 0.8229851127 0.0375042236 0.0057830000 0.0004080000 0.0027330000 0.0000010000 0.0000040000 0.0010570000 16548981 96830484 509673472 4.5255494118 3.7017591000 3.6933054924 1041 41.6000000000 0.5447835922 0.2676998283 0.8229851127 0.0374862237 0.0070080000 0.0004110000 0.0029860000 0.0000030000 0.0000030000 0.0020000000 16551757 96830484 509673472 4.5328769684 3.7015233040 3.6945502758 1042 41.6400000000 0.5443525910 0.2679653300 0.8229851127 0.0374685862 0.0061400000 0.0004130000 0.0030610000 0.0000010000 0.0000030000 0.0010520000 16554533 96830484 509673472 4.5429849625 3.7041242123 3.7003364563 1043 41.6800000000 0.5434911847 0.2682294967 0.8229851127 0.0374525819 0.0064400000 0.0004120000 0.0030540000 0.0000030000 0.0000030000 0.0013580000 16557309 96830484 509673472 4.5491533279 3.7059645653 3.7046613693 1044 41.7200000000 0.5431683064 0.2684928481 0.8229851127 0.0374423993 0.0128770000 0.0006050000 0.0038510000 0.0000020000 0.0000150000 0.0014110000 16560085 96830484 509673472 4.5628457069 3.7069625854 3.7092406750 1045 41.7600000000 0.5427877903 0.2687553312 0.8229851127 0.0374268640 0.0086320000 0.0004780000 0.0031950000 0.0000080000 0.0000080000 0.0020690000 16562861 96830484 509673472 4.5701627731 3.7077412605 3.7129545212 1046 41.8000000000 0.5421339273 0.2690166875 0.8229851127 0.0374100600 0.0070070000 0.0004380000 0.0034690000 0.0000010000 0.0000050000 0.0010420000 16565637 96830484 509673472 4.5755081177 3.7095375061 3.7190759182 1047 41.8400000000 0.5417397618 0.2692771680 0.8229851127 0.0373922578 0.0061080000 0.0004130000 0.0027240000 0.0000030000 0.0000030000 0.0013360000 16568413 96830484 509673472 4.5823473930 3.7097260952 3.7213785648 1048 41.8800000000 0.5409291387 0.2695363778 0.8229851127 0.0373745311 0.0064320000 0.0004050000 0.0034210000 0.0000010000 0.0000040000 0.0010330000 16571189 96830484 509673472 4.5903730392 3.7111127377 3.7270920277 1049 41.9200000000 0.5401060581 0.2697943089 0.8229851127 0.0373568386 0.0066770000 0.0004080000 0.0026990000 0.0000040000 0.0000030000 0.0019810000 16573965 96830484 509673472 4.5975217819 3.7118794918 3.7306802273 1050 41.9600000000 0.5394706130 0.2700511435 0.8229851127 0.0373390680 0.0064170000 0.0004070000 0.0034140000 0.0000000000 0.0000040000 0.0010240000 16576741 96830484 509673472 4.6034560204 3.7127268314 3.7328844070 1051 42.0000000000 0.5385914445 0.2703066528 0.8229851127 0.0373213172 0.0075400000 0.0004110000 0.0041130000 0.0000030000 0.0000030000 0.0013200000 16579517 96830484 509673472 4.6109967232 3.7123253345 3.7355146408 1052 42.0400000000 0.5372101068 0.2705603633 0.8229851127 0.0373036024 0.0064560000 0.0004070000 0.0034240000 0.0000010000 0.0000030000 0.0010220000 16582293 96830484 509673472 4.6175575256 3.7145192623 3.7401981354 1053 42.0800000000 0.5356097221 0.2708120721 0.8229851127 0.0372859711 0.0125450000 0.0005920000 0.0038430000 0.0000150000 0.0000140000 0.0025230000 16585069 96830484 509673472 4.6235332489 3.7167477608 3.7424356937 1054 42.1200000000 0.5336740017 0.2710614667 0.8229851127 0.0372683003 0.0086560000 0.0004670000 0.0046170000 0.0000010000 0.0000060000 0.0010640000 16587845 96830484 509673472 4.6300010681 3.7179853916 3.7456245422 1055 42.1600000000 0.5327595472 0.2713095218 0.8229851127 0.0372511348 0.0069800000 0.0004260000 0.0033930000 0.0000040000 0.0000040000 0.0013040000 16590621 96830484 509673472 4.6418194771 3.7192134857 3.7527468204 1056 42.2000000000 0.5311866403 0.2715556175 0.8229851127 0.0372337275 0.0084090000 0.0004070000 0.0050120000 0.0000010000 0.0000040000 0.0010280000 16593397 96830484 509673472 4.6482892036 3.7203061581 3.7561845779 1057 42.2400000000 0.5300076008 0.2718001322 0.8229851127 0.0372162207 0.0081510000 0.0004580000 0.0040930000 0.0000040000 0.0000030000 0.0019580000 16596173 96830484 509673472 4.6544284821 3.7217841148 3.7611243725 1058 42.2800000000 0.5284165740 0.2720426808 0.8229851127 0.0371986818 0.0064390000 0.0004140000 0.0033660000 0.0000000000 0.0000030000 0.0010110000 16598949 96830484 509673472 4.6606302261 3.7242147923 3.7672569752 1059 42.3200000000 0.5268697143 0.2722833107 0.8229851127 0.0371811720 0.0095080000 0.0005080000 0.0036070000 0.0000100000 0.0000100000 0.0014700000 16601725 96830484 509673472 4.6649098396 3.7279942036 3.7708203793 1060 42.3600000000 0.5261662006 0.2725228228 0.8229851127 0.0371638015 0.0070290000 0.0004480000 0.0030960000 0.0000000000 0.0000060000 0.0010230000 16604501 96830484 509673472 4.6695990562 3.7297856808 3.7759685516 1061 42.4000000000 0.5251398683 0.2727609162 0.8229851127 0.0371463106 0.0077540000 0.0004140000 0.0037240000 0.0000040000 0.0000040000 0.0019330000 16607277 96830484 509673472 4.6747102737 3.7318232059 3.7803668976 1062 42.4400000000 0.5239402056 0.2729974315 0.8229851127 0.0371289781 0.0059940000 0.0004060000 0.0029980000 0.0000000000 0.0000040000 0.0010020000 16610053 96830484 509673472 4.6796092987 3.7345135212 3.7859790325 1063 42.4800000000 0.5227487087 0.2732323810 0.8229851127 0.0371120356 0.0113750000 0.0005920000 0.0037660000 0.0000150000 0.0000140000 0.0016490000 16612829 96830484 509673472 4.6852431297 3.7368602753 3.7912788391 1064 42.5200000000 0.5210673809 0.2734653086 0.8229851127 0.0370953153 0.0074200000 0.0004800000 0.0031150000 0.0000010000 0.0000060000 0.0010440000 16615605 96830484 509673472 4.6901931763 3.7390747070 3.7956552505 1065 42.5600000000 0.5205275416 0.2736972919 0.8229851127 0.0370782090 0.0100710000 0.0005070000 0.0039400000 0.0000080000 0.0000060000 0.0020750000 16618381 96830484 509673472 4.6942577362 3.7407095432 3.8002614975 1066 42.6000000000 0.5183138847 0.2739267634 0.8229851127 0.0370609469 0.0076970000 0.0004370000 0.0041150000 0.0000000000 0.0000060000 0.0010050000 16621157 96830484 509673472 4.6988501549 3.7445781231 3.8046789169 1067 42.6400000000 0.5174123049 0.2741549598 0.8229851127 0.0370438907 0.0078180000 0.0004240000 0.0044330000 0.0000040000 0.0000030000 0.0012710000 16623933 96830484 509673472 4.7034740448 3.7464935780 3.8091664314 1068 42.6800000000 0.5162475705 0.2743816383 0.8229851127 0.0370266291 0.0070400000 0.0004050000 0.0040500000 0.0000000000 0.0000030000 0.0009930000 16626709 96830484 509673472 4.7061262131 3.7495012283 3.8139984608 1069 42.7200000000 0.5136886835 0.2746054989 0.8229851127 0.0370097508 0.0103570000 0.0005050000 0.0046530000 0.0000080000 0.0000080000 0.0020890000 16629485 96830484 509673472 4.7131896019 3.7550132275 3.8187558651 1070 42.7600000000 0.5112688541 0.2748266796 0.8229851127 0.0369943361 0.0080190000 0.0004400000 0.0044670000 0.0000000000 0.0000040000 0.0009990000 16632261 96830484 509673472 4.7186784744 3.7622749805 3.8243923187 1071 42.8000000000 0.5092175603 0.2750455320 0.8229851127 0.0369786521 0.0076590000 0.0004130000 0.0044110000 0.0000040000 0.0000040000 0.0012670000 16635037 96830484 509673472 4.7237515450 3.7675879002 3.8314330578 1072 42.8400000000 0.5071957111 0.2752620900 0.8229851127 0.0369614345 0.0067210000 0.0004040000 0.0037140000 0.0000000000 0.0000040000 0.0009950000 16637813 96830484 509673472 4.7286067009 3.7727594376 3.8365490437 1073 42.8800000000 0.5046994090 0.2754759179 0.8229851127 0.0369446963 0.0083600000 0.0004040000 0.0044150000 0.0000040000 0.0000030000 0.0019120000 16640589 96830484 509673472 4.7312688828 3.7767040730 3.8422856331 1074 42.9200000000 0.5025597811 0.2756873554 0.8229851127 0.0369277644 0.0074210000 0.0004060000 0.0044320000 0.0000000000 0.0000030000 0.0009920000 16643365 96830484 509673472 4.7371578217 3.7823038101 3.8477435112 1075 42.9600000000 0.5013847947 0.2758973065 0.8229851127 0.0369107455 0.0062680000 0.0004090000 0.0030020000 0.0000030000 0.0000030000 0.0012590000 16646141 96830484 509673472 4.7409105301 3.7871346474 3.8554854393 1076 43.0000000000 0.4988134801 0.2761044776 0.8229851127 0.0368943186 0.0074560000 0.0004080000 0.0044330000 0.0000010000 0.0000040000 0.0009990000 16648917 96830484 509673472 4.7447896004 3.7942509651 3.8593118191 1077 43.0400000000 0.5004330277 0.2763127678 0.8229851127 0.0368785753 0.0084290000 0.0004130000 0.0044320000 0.0000030000 0.0000030000 0.0019130000 16651693 96830484 509673472 4.7497487068 3.8002231121 3.8676986694 1078 43.0800000000 0.4990668893 0.2765194043 0.8229851127 0.0368622023 0.0067640000 0.0004090000 0.0037220000 0.0000010000 0.0000030000 0.0010000000 16654469 96830484 509673472 4.7530245781 3.8030583858 3.8717463017 1079 43.1200000000 0.4980534613 0.2767247186 0.8229851127 0.0368455748 0.0126010000 0.0005940000 0.0049360000 0.0000160000 0.0000140000 0.0016680000 16657245 96830484 509673472 4.7569160461 3.8073282242 3.8768990040 1080 43.1600000000 0.4987684786 0.2769303146 0.8229851127 0.0368286625 0.0086480000 0.0004800000 0.0045680000 0.0000000000 0.0000060000 0.0010540000 16660021 96830484 509673472 4.7621550560 3.8095169067 3.8869411945 1081 43.2000000000 0.4964545369 0.2771333898 0.8229851127 0.0368118284 0.0069710000 0.0004300000 0.0027140000 0.0000060000 0.0000040000 0.0019220000 16662797 96830484 509673472 4.7661461830 3.8124752045 3.8925273418 1082 43.2400000000 0.4969455004 0.2773365433 0.8229851127 0.0367950193 0.0060570000 0.0004110000 0.0030110000 0.0000000000 0.0000030000 0.0010080000 16665573 96830484 509673472 4.7683496475 3.8165912628 3.9005970955 1083 43.2800000000 0.4948697984 0.2775374050 0.8229851127 0.0367781233 0.0108690000 0.0005960000 0.0042050000 0.0000110000 0.0000090000 0.0015000000 16668349 96830484 509673472 4.7735319138 3.8206226826 3.9090492725 1084 43.3200000000 0.4936867356 0.2777368048 0.8229851127 0.0367611489 0.0074240000 0.0004570000 0.0034390000 0.0000010000 0.0000070000 0.0010460000 16671125 96830484 509673472 4.7790651321 3.8237454891 3.9178078175 1085 43.3600000000 0.4919897914 0.2779342730 0.8229851127 0.0367447306 0.0069860000 0.0004300000 0.0026660000 0.0000050000 0.0000040000 0.0019630000 16673901 96830484 509673472 4.7822217941 3.8287127018 3.9222867489 1086 43.4000000000 0.4912643135 0.2781307095 0.8229851127 0.0367278439 0.0098000000 0.0005200000 0.0040230000 0.0000020000 0.0000110000 0.0011520000 16676677 96830484 509673472 4.7865166664 3.8319175243 3.9285249710 1087 43.4400000000 0.4890227020 0.2783247223 0.8229851127 0.0367109543 0.0077850000 0.0005040000 0.0037610000 0.0000050000 0.0000040000 0.0013150000 16679453 96830484 509673472 4.7903409004 3.8351759911 3.9349126816 1088 43.4800000000 0.4876327217 0.2785171010 0.8229851127 0.0366942428 0.0072140000 0.0004160000 0.0040640000 0.0000010000 0.0000040000 0.0010310000 16682229 96830484 509673472 4.7929029465 3.8378043175 3.9399714470 1089 43.5200000000 0.4857340753 0.2787073829 0.8229851127 0.0366774930 0.0080920000 0.0004110000 0.0040470000 0.0000040000 0.0000030000 0.0019400000 16685005 96830484 509673472 4.7965941429 3.8408253193 3.9454791546 1090 43.5600000000 0.4850400090 0.2788966789 0.8229851127 0.0366606912 0.0057300000 0.0004130000 0.0026360000 0.0000000000 0.0000030000 0.0010340000 16687781 96830484 509673472 4.8003664017 3.8441789150 3.9544055462 1091 43.6000000000 0.4825634360 0.2790833579 0.8229851127 0.0366440720 0.0077160000 0.0004110000 0.0043730000 0.0000040000 0.0000030000 0.0012970000 16690557 96830484 509673472 4.8044266701 3.8486914635 3.9609332085 1092 43.6400000000 0.4808324575 0.2792681098 0.8229851127 0.0366274413 0.0110790000 0.0005960000 0.0026740000 0.0000010000 0.0000150000 0.0015490000 16693333 96830484 509673472 4.8067502975 3.8534677029 3.9669797421 1093 43.6800000000 0.4786372185 0.2794505152 0.8229851127 0.0366110638 0.0082940000 0.0004790000 0.0027670000 0.0000060000 0.0000060000 0.0020670000 16696109 96830484 509673472 4.8100209236 3.8587386608 3.9744613171 1094 43.7200000000 0.4768473804 0.2796309511 0.8229851127 0.0365945578 0.0065220000 0.0004340000 0.0029920000 0.0000000000 0.0000050000 0.0010760000 16698885 96830484 509673472 4.8112359047 3.8637952805 3.9800946712 1095 43.7600000000 0.4754646122 0.2798097946 0.8229851127 0.0365779502 0.0066770000 0.0004100000 0.0033060000 0.0000030000 0.0000030000 0.0013120000 16701661 96830484 509673472 4.8112859726 3.8672115803 3.9853408337 1096 43.8000000000 0.4739124775 0.2799868956 0.8229851127 0.0365613118 0.0074950000 0.0004090000 0.0043430000 0.0000010000 0.0000040000 0.0010610000 16704437 96830484 509673472 4.8135724068 3.8710923195 3.9915535450 1097 43.8400000000 0.4731020927 0.2801629350 0.8229851127 0.0365447728 0.0111970000 0.0005100000 0.0046460000 0.0000100000 0.0000090000 0.0022780000 16707213 96830484 509673472 4.8155016899 3.8751976490 4.0012617111 1098 43.8800000000 0.4717561305 0.2803374279 0.8229851127 0.0365297177 0.0079230000 0.0004580000 0.0040840000 0.0000010000 0.0000050000 0.0010970000 16709989 96830484 509673472 4.8178577423 3.8794302940 4.0109930038 1099 43.9200000000 0.4706310928 0.2805105795 0.8229851127 0.0365142525 0.0085960000 0.0005110000 0.0028250000 0.0000120000 0.0000090000 0.0014700000 16712765 96830484 509673472 4.8182935715 3.8849666119 4.0174179077 1100 43.9600000000 0.4692628682 0.2806821725 0.8229851127 0.0364978123 0.0082180000 0.0004600000 0.0044080000 0.0000010000 0.0000060000 0.0011010000 16715541 96830484 509673472 4.8184900284 3.8900609016 4.0238375664 1101 44.0000000000 0.4670411646 0.2808514359 0.8229851127 0.0364813379 0.0078120000 0.0004250000 0.0036550000 0.0000040000 0.0000030000 0.0019810000 16718317 96830484 509673472 4.8221893311 3.8945591450 4.0302104950 1102 44.0400000000 0.4659918249 0.2810194399 0.8229851127 0.0364647899 0.0064030000 0.0004120000 0.0032770000 0.0000010000 0.0000030000 0.0010710000 16721093 96830484 509673472 4.8239564896 3.8959789276 4.0375714302 1103 44.0800000000 0.4642747641 0.2811855825 0.8229851127 0.0364486195 0.0077520000 0.0004130000 0.0042930000 0.0000040000 0.0000030000 0.0013220000 16723869 96830484 509673472 4.8266506195 3.8987846375 4.0455274582 1104 44.1200000000 0.4651144147 0.2813521847 0.8229851127 0.0364321340 0.0099350000 0.0005100000 0.0045820000 0.0000010000 0.0000080000 0.0012180000 16726645 96830484 509673472 4.8273124695 3.8993625641 4.0567669868 1105 44.1600000000 0.4635807574 0.2815170974 0.8229851127 0.0364156989 0.0080270000 0.0004310000 0.0033510000 0.0000060000 0.0000050000 0.0020030000 16729421 96830484 509673472 4.8303413391 3.9024658203 4.0665812492 1106 44.2000000000 0.4660062790 0.2816839050 0.8229851127 0.0363994047 0.0075480000 0.0004140000 0.0043180000 0.0000010000 0.0000030000 0.0010740000 16732197 96830484 509673472 4.8322238922 3.9030685425 4.0798892975 1107 44.2400000000 0.4661944211 0.2818505812 0.8229851127 0.0363831539 0.0077210000 0.0004050000 0.0042840000 0.0000040000 0.0000030000 0.0013210000 16734973 96830484 509673472 4.8347673416 3.9051465988 4.0908951759 1108 44.2800000000 0.4678774178 0.2820184754 0.8229851127 0.0363670482 0.0074520000 0.0004060000 0.0042940000 0.0000010000 0.0000030000 0.0010660000 16737749 96830484 509673472 4.8371601105 3.9050505161 4.1028857231 1109 44.3200000000 0.4696914554 0.2821877027 0.8229851127 0.0363507277 0.0083750000 0.0004060000 0.0042970000 0.0000040000 0.0000030000 0.0019790000 16740525 96830484 509673472 4.8384647369 3.9052369595 4.1147799492 1110 44.3600000000 0.4720088243 0.2823587127 0.8229851127 0.0363343831 0.0086840000 0.0005070000 0.0031600000 0.0000010000 0.0000080000 0.0012180000 16743301 96830484 509673472 4.8402171135 3.9053895473 4.1270804405 1111 44.4000000000 0.4735129178 0.2825307687 0.8229851127 0.0363181484 0.0068160000 0.0004400000 0.0026680000 0.0000060000 0.0000050000 0.0013620000 16746077 96830484 509673472 4.8429770470 3.9045782089 4.1387867928 1112 44.4400000000 0.4780991971 0.2827066396 0.8229851127 0.0363019934 0.0076670000 0.0004200000 0.0043240000 0.0000010000 0.0000040000 0.0010700000 16748853 96830484 509673472 4.8458456993 3.9012675285 4.1548933983 1113 44.4800000000 0.4793456793 0.2828833143 0.8229851127 0.0362860019 0.0070440000 0.0004110000 0.0029390000 0.0000030000 0.0000030000 0.0019760000 16751629 96830484 509673472 4.8512248993 3.9004683495 4.1682190895 1114 44.5200000000 0.4828935564 0.2830628568 0.8229851127 0.0362705814 0.0064690000 0.0004100000 0.0032690000 0.0000010000 0.0000040000 0.0010610000 16754405 96830484 509673472 4.8528656960 3.8955552578 4.1793875694 1115 44.5600000000 0.4836216569 0.2832427301 0.8229851127 0.0362543080 0.0077110000 0.0004100000 0.0042780000 0.0000040000 0.0000030000 0.0012900000 16757181 96830484 509673472 4.8559308052 3.8953809738 4.1896657944 1116 44.6000000000 0.4853734374 0.2834238508 0.8229851127 0.0362381680 0.0071480000 0.0004120000 0.0039460000 0.0000010000 0.0000030000 0.0010530000 16759957 96830484 509673472 4.8615598679 3.8937289715 4.2030534744 1117 44.6400000000 0.4881773889 0.2836071575 0.8229851127 0.0362220586 0.0070270000 0.0004150000 0.0029110000 0.0000030000 0.0000040000 0.0019350000 16762733 96830484 509673472 4.8625526428 3.8925943375 4.2159190178 1118 44.6800000000 0.4894229174 0.2837912503 0.8229851127 0.0362062924 0.0064570000 0.0004130000 0.0032640000 0.0000000000 0.0000050000 0.0010470000 16765509 96830484 509673472 4.8659939766 3.8888089657 4.2253112793 1119 44.7200000000 0.4907840192 0.2839762304 0.8229851127 0.0361903098 0.0076920000 0.0004140000 0.0042740000 0.0000040000 0.0000040000 0.0012910000 16768285 96830484 509673472 4.8698935509 3.8877208233 4.2373986244 1120 44.7600000000 0.4925473332 0.2841624546 0.8229851127 0.0361744618 0.0127280000 0.0005810000 0.0048100000 0.0000020000 0.0000150000 0.0015350000 16771061 96830484 509673472 4.8728456497 3.8849139214 4.2499308586 1121 44.8000000000 0.4930776656 0.2843488197 0.8229851127 0.0361584846 0.0085930000 0.0004730000 0.0033880000 0.0000060000 0.0000050000 0.0020250000 16773837 96830484 509673472 4.8769245148 3.8850598335 4.2608723640 1122 44.8400000000 0.4931387901 0.2845349070 0.8229851127 0.0361425550 0.0078090000 0.0004330000 0.0043070000 0.0000000000 0.0000050000 0.0010270000 16776613 96830484 509673472 4.8805508614 3.8832085133 4.2697806358 1123 44.8800000000 0.4940961301 0.2847215154 0.8229851127 0.0361265570 0.0063200000 0.0004140000 0.0029230000 0.0000040000 0.0000030000 0.0012650000 16779389 96830484 509673472 4.8844809532 3.8838918209 4.2813210487 1124 44.9200000000 0.4949333966 0.2849085366 0.8229851127 0.0361105754 0.0073980000 0.0004110000 0.0042770000 0.0000000000 0.0000040000 0.0010170000 16782165 96830484 509673472 4.8881645203 3.8828184605 4.2919850349 1125 44.9600000000 0.4954110980 0.2850956500 0.8229851127 0.0360945848 0.0083050000 0.0004100000 0.0042780000 0.0000040000 0.0000040000 0.0018940000 16784941 96830484 509673472 4.8910965919 3.8830897808 4.3020386696 1126 45.0000000000 0.4958121181 0.2852827872 0.8229851127 0.0360786096 0.0083370000 0.0005120000 0.0027890000 0.0000020000 0.0000100000 0.0011970000 16787717 96830484 509673472 4.8938999176 3.8825519085 4.3114523888 1127 45.0400000000 0.4954649508 0.2854692842 0.8229851127 0.0360627662 0.0067310000 0.0004470000 0.0026280000 0.0000050000 0.0000060000 0.0012670000 16790493 96830484 509673472 4.8961634636 3.8825092316 4.3189177513 1128 45.0800000000 0.4957876801 0.2856557367 0.8229851127 0.0360470447 0.0080810000 0.0005080000 0.0027920000 0.0000010000 0.0000080000 0.0011150000 16793269 96830484 509673472 4.8993434906 3.8819067478 4.3282508850 1129 45.1200000000 0.4956630170 0.2858417485 0.8229851127 0.0360312219 0.0090310000 0.0005180000 0.0027910000 0.0000080000 0.0000070000 0.0020550000 16796045 96830484 509673472 4.9032139778 3.8831460476 4.3380985260 1130 45.1600000000 0.4956559241 0.2860274247 0.8229851127 0.0360153038 0.0079560000 0.0004400000 0.0042240000 0.0000000000 0.0000050000 0.0010040000 16798821 96830484 509673472 4.9058470726 3.8829567432 4.3466262817 1131 45.2000000000 0.4961370528 0.2862131981 0.8229851127 0.0359994024 0.0070820000 0.0004190000 0.0035850000 0.0000030000 0.0000030000 0.0012320000 16801597 96830484 509673472 4.9070725441 3.8822793961 4.3540821075 1132 45.2400000000 0.4952789545 0.2863978851 0.8229851127 0.0359835083 0.0060200000 0.0004120000 0.0029090000 0.0000010000 0.0000040000 0.0009820000 16804373 96830484 509673472 4.9110641479 3.8811054230 4.3604316711 1133 45.2800000000 0.4948247075 0.2865818452 0.8229851127 0.0359676324 0.0065890000 0.0004110000 0.0025720000 0.0000040000 0.0000030000 0.0018620000 16807149 96830484 509673472 4.9139199257 3.8810679913 4.3686494827 1134 45.3200000000 0.4946625233 0.2867653379 0.8229851127 0.0359517713 0.0131760000 0.0005950000 0.0044150000 0.0000020000 0.0000150000 0.0014450000 16809925 96830484 509673472 4.9176292419 3.8824729919 4.3774647713 1135 45.3600000000 0.4942992628 0.2869481872 0.8229851127 0.0359359653 0.0079770000 0.0004810000 0.0030600000 0.0000070000 0.0000060000 0.0012820000 16812701 96830484 509673472 4.9211406708 3.8818118572 4.3844933510 1136 45.4000000000 0.4935201108 0.2871300287 0.8229851127 0.0359201874 0.0074700000 0.0004340000 0.0039890000 0.0000000000 0.0000050000 0.0009990000 16815477 96830484 509673472 4.9254140854 3.8853988647 4.3923397064 1137 45.4400000000 0.4935213029 0.2873115513 0.8229851127 0.0359043933 0.0065770000 0.0004100000 0.0025800000 0.0000030000 0.0000030000 0.0018640000 16818253 96830484 509673472 4.9267663956 3.8871982098 4.3997144699 1138 45.4800000000 0.4924703836 0.2874918315 0.8229851127 0.0358886669 0.0056490000 0.0004080000 0.0025670000 0.0000010000 0.0000040000 0.0009790000 16821029 96830484 509673472 4.9295015335 3.8890082836 4.4054255486 1139 45.5200000000 0.4920385778 0.2876714160 0.8229851127 0.0358729298 0.0059550000 0.0004070000 0.0025750000 0.0000030000 0.0000030000 0.0012450000 16823805 96830484 509673472 4.9334964752 3.8911030293 4.4126105309 1140 45.5600000000 0.4911457002 0.2878499022 0.8229851127 0.0358572262 0.0105700000 0.0005950000 0.0029690000 0.0000020000 0.0000170000 0.0014420000 16826581 96830484 509673472 4.9342970848 3.8929579258 4.4168419838 1141 45.6000000000 0.4906365573 0.2880276293 0.8229851127 0.0358415842 0.0084780000 0.0004810000 0.0033730000 0.0000060000 0.0000050000 0.0019240000 16829357 96830484 509673472 4.9362401962 3.8931751251 4.4223217964 1142 45.6400000000 0.4900394678 0.2882045224 0.8229851127 0.0358262092 0.0077400000 0.0004310000 0.0043070000 0.0000010000 0.0000040000 0.0009880000 16832133 96830484 509673472 4.9403519630 3.8967332840 4.4300713539 1143 45.6800000000 0.4897423685 0.2883808459 0.8229851127 0.0358105417 0.0056260000 0.0004120000 0.0022410000 0.0000040000 0.0000030000 0.0012340000 16834909 96830484 509673472 4.9442753792 3.8967278004 4.4369325638 1144 45.7200000000 0.4885869026 0.2885558512 0.8229851127 0.0357950846 0.0080650000 0.0004740000 0.0027220000 0.0000010000 0.0000070000 0.0010970000 16837685 96830484 509673472 4.9482212067 3.8979315758 4.4427704811 1145 45.7600000000 0.4881108105 0.2887301351 0.8229851127 0.0357794498 0.0069560000 0.0004350000 0.0023160000 0.0000050000 0.0000050000 0.0018850000 16840461 96830484 509673472 4.9511890411 3.9006700516 4.4498267174 1146 45.8000000000 0.4870347977 0.2889031758 0.8229851127 0.0357638802 0.0078550000 0.0004760000 0.0039740000 0.0000010000 0.0000040000 0.0011710000 16843237 96830484 509673472 4.9557151794 3.9013304710 4.4566054344 1147 45.8400000000 0.4867834151 0.2890756956 0.8229851127 0.0357482826 0.0084730000 0.0005240000 0.0027890000 0.0000080000 0.0000070000 0.0013500000 16846013 96830484 509673472 4.9585461617 3.9025111198 4.4628295898 1148 45.8800000000 0.4858609438 0.2892471113 0.8229851127 0.0357327077 0.0065550000 0.0004390000 0.0026650000 0.0000010000 0.0000060000 0.0010080000 16848789 96830484 509673472 4.9615707397 3.9035270214 4.4689698219 1149 45.9200000000 0.4859042466 0.2894182664 0.8229851127 0.0357172767 0.0092660000 0.0005130000 0.0024570000 0.0000120000 0.0000100000 0.0021790000 16851565 96830484 509673472 4.9649953842 3.9042766094 4.4774208069 1150 45.9600000000 0.4850528538 0.2895883834 0.8229851127 0.0357017364 0.0082280000 0.0004600000 0.0042870000 0.0000000000 0.0000050000 0.0010140000 16854341 96830484 509673472 4.9679889679 3.9050221443 4.4837951660 1151 46.0000000000 0.4850766063 0.2897582255 0.8229851127 0.0356862703 0.0078300000 0.0004180000 0.0043110000 0.0000040000 0.0000030000 0.0012330000 16857117 96830484 509673472 4.9705176353 3.9057376385 4.4929275513 1152 46.0400000000 0.4839547873 0.2899267989 0.8229851127 0.0356707802 0.0082000000 0.0005090000 0.0024760000 0.0000010000 0.0000100000 0.0012260000 16859893 96830484 509673472 4.9744625092 3.9071660042 4.5014238358 1153 46.0800000000 0.4834560156 0.2900946473 0.8229851127 0.0356555354 0.0081390000 0.0004510000 0.0033850000 0.0000050000 0.0000050000 0.0018860000 16862669 96830484 509673472 4.9759302139 3.9071688652 4.5090861320 1154 46.1200000000 0.4828966260 0.2902617200 0.8229851127 0.0356400762 0.0061920000 0.0004170000 0.0029630000 0.0000000000 0.0000030000 0.0009880000 16865445 96830484 509673472 4.9770293236 3.9091184139 4.5170249939 1155 46.1600000000 0.4825711548 0.2904282217 0.8229851127 0.0356248023 0.0060250000 0.0004120000 0.0026030000 0.0000030000 0.0000030000 0.0012150000 16868221 96830484 509673472 4.9780430794 3.9134223461 4.5274648666 1156 46.2000000000 0.4817672074 0.2905937399 0.8229851127 0.0356096227 0.0117310000 0.0005970000 0.0030230000 0.0000020000 0.0000150000 0.0014720000 16870997 96830484 509673472 4.9805135727 3.9166517258 4.5367784500 1157 46.2400000000 0.4812168479 0.2907584962 0.8229851127 0.0355945813 0.0088320000 0.0004710000 0.0034440000 0.0000070000 0.0000060000 0.0019410000 16873773 96830484 509673472 4.9838571548 3.9197456837 4.5469937325 1158 46.2800000000 0.4811855257 0.2909229410 0.8229851127 0.0355793353 0.0061850000 0.0004310000 0.0026350000 0.0000010000 0.0000050000 0.0010050000 16876549 96830484 509673472 4.9861640930 3.9262361526 4.5683369637 1159 46.3200000000 0.4811428487 0.2910870652 0.8229851127 0.0355640313 0.0056660000 0.0004130000 0.0022630000 0.0000030000 0.0000030000 0.0012300000 16879325 96830484 509673472 4.9877314568 3.9288990498 4.5769553185 1160 46.3600000000 0.4803513885 0.2912502241 0.8229851127 0.0355487051 0.0119370000 0.0005990000 0.0033640000 0.0000020000 0.0000170000 0.0014600000 16882101 96830484 509673472 4.9883680344 3.9339137077 4.5865983963 1161 46.4000000000 0.4803833663 0.2914131294 0.8229851127 0.0355336088 0.0096570000 0.0004810000 0.0044760000 0.0000070000 0.0000050000 0.0019020000 16884877 96830484 509673472 4.9884042740 3.9387471676 4.5961365700 1162 46.4400000000 0.4798945487 0.2915753337 0.8229851127 0.0355183750 0.0060980000 0.0004340000 0.0026450000 0.0000010000 0.0000040000 0.0009760000 16887653 96830484 509673472 4.9897665977 3.9430286884 4.6064391136 1163 46.4800000000 0.4794453681 0.2917368729 0.8229851127 0.0355031410 0.0059820000 0.0004140000 0.0026140000 0.0000040000 0.0000030000 0.0011900000 16890429 96830484 509673472 4.9909749031 3.9448449612 4.6161522865 1164 46.5200000000 0.4791987836 0.2918979227 0.8229851127 0.0354880209 0.0064700000 0.0004120000 0.0033120000 0.0000010000 0.0000030000 0.0009810000 16893205 96830484 509673472 4.9921140671 3.9482791424 4.6253938675 1165 46.5600000000 0.4787181020 0.2920582833 0.8229851127 0.0354730020 0.0099110000 0.0005170000 0.0031840000 0.0000110000 0.0000090000 0.0021760000 16895981 96830484 509673472 4.9955005646 3.9539117813 4.6366753578 1166 46.6000000000 0.4784380794 0.2922181288 0.8229851127 0.0354578685 0.0074510000 0.0004570000 0.0034070000 0.0000000000 0.0000050000 0.0010040000 16898757 96830484 509673472 4.9954495430 3.9572989941 4.6473159790 1167 46.6400000000 0.4780913591 0.2923774032 0.8229851127 0.0354427475 0.0086960000 0.0005090000 0.0028620000 0.0000090000 0.0000070000 0.0013260000 16901533 96830484 509673472 4.9960217476 3.9605319500 4.6565847397 1168 46.6800000000 0.4780068994 0.2925363325 0.8229851127 0.0354276004 0.0082050000 0.0004510000 0.0044180000 0.0000010000 0.0000060000 0.0009870000 16904309 96830484 509673472 4.9968285561 3.9620904922 4.6666855812 1169 46.7200000000 0.4779161811 0.2926949124 0.8229851127 0.0354126635 0.0142450000 0.0006190000 0.0030300000 0.0000150000 0.0000140000 0.0025100000 16907085 96830484 509673472 4.9961590767 3.9649004936 4.6758279800 1170 46.7600000000 0.4776181877 0.2928529665 0.8229851127 0.0353976542 0.0075000000 0.0004730000 0.0024450000 0.0000010000 0.0000080000 0.0010870000 16909861 96830484 509673472 4.9950838089 3.9677100182 4.6845893860 1171 46.8000000000 0.4772115052 0.2930104033 0.8229851127 0.0353830740 0.0124460000 0.0005960000 0.0041820000 0.0000160000 0.0000140000 0.0016620000 16912637 96830484 509673472 4.9960055351 3.9730319977 4.6958045959 1172 46.8400000000 0.4769160450 0.2931673194 0.8229851127 0.0353680725 0.0078320000 0.0004770000 0.0033420000 0.0000000000 0.0000070000 0.0010350000 16915413 96830484 509673472 4.9953455925 3.9783115387 4.7063212395 1173 46.8800000000 0.4768835604 0.2933239402 0.8229851127 0.0353530615 0.0071220000 0.0004300000 0.0023250000 0.0000040000 0.0000040000 0.0018400000 16918189 96830484 509673472 4.9947185516 3.9796383381 4.7164225578 1174 46.9200000000 0.4767986834 0.2934802219 0.8229851127 0.0353380796 0.0058360000 0.0004700000 0.0023640000 0.0000000000 0.0000030000 0.0009570000 16920965 96830484 509673472 4.9947972298 3.9829859734 4.7266302109 1175 46.9600000000 0.4768168628 0.2936362531 0.8229851127 0.0353231444 0.0113260000 0.0005960000 0.0026620000 0.0000160000 0.0000130000 0.0016250000 16923741 96830484 509673472 4.9941277504 3.9831709862 4.7350587845 1176 47.0000000000 0.4765434861 0.2937917865 0.8229851127 0.0353081215 0.0077320000 0.0004820000 0.0031130000 0.0000010000 0.0000070000 0.0010020000 16926517 96830484 509673472 4.9933800697 3.9881513119 4.7544493675 1177 47.0400000000 0.4764030874 0.2939469363 0.8229851127 0.0352931212 0.0067730000 0.0004360000 0.0023170000 0.0000050000 0.0000040000 0.0018060000 16929293 96830484 509673472 4.9940495491 3.9911994934 4.7643995285 1178 47.0800000000 0.4764349759 0.2941018497 0.8229851127 0.0352781568 0.0062190000 0.0004140000 0.0030060000 0.0000000000 0.0000030000 0.0009480000 16932069 96830484 509673472 4.9950089455 3.9907300472 4.7742571831 1179 47.1200000000 0.4764509499 0.2942565139 0.8229851127 0.0352632234 0.0102190000 0.0005960000 0.0030250000 0.0000160000 0.0000130000 0.0013870000 16934845 96830484 509673472 4.9941296577 3.9914195538 4.7827124596 1180 47.1600000000 0.4762823582 0.2944107731 0.8229851127 0.0352488817 0.0088730000 0.0005090000 0.0031060000 0.0000010000 0.0000110000 0.0011160000 16937621 96830484 509673472 4.9940338135 3.9946982861 4.7921118736 1181 47.2000000000 0.4762917757 0.2945647791 0.8229851127 0.0352339989 0.0072970000 0.0004560000 0.0023630000 0.0000050000 0.0000050000 0.0018340000 16940397 96830484 509673472 4.9907770157 3.9957702160 4.8007369041 1182 47.2400000000 0.4763652086 0.2947185865 0.8229851127 0.0352190826 0.0097720000 0.0005050000 0.0046550000 0.0000000000 0.0000080000 0.0010680000 16943173 96830484 509673472 4.9851398468 3.9937140942 4.8059864044 1183 47.2800000000 0.4762793183 0.2948720614 0.8229851127 0.0352046885 0.0084460000 0.0004390000 0.0044300000 0.0000040000 0.0000040000 0.0011740000 16945949 96830484 509673472 4.9848237038 3.9946691990 4.8165860176 1184 47.3200000000 0.4758796692 0.2950249394 0.8229851127 0.0351901289 0.0085580000 0.0005110000 0.0025200000 0.0000010000 0.0000100000 0.0011740000 16948725 96830484 509673472 4.9888448715 3.9976146221 4.8297529221 1185 47.3600000000 0.4758542180 0.2951775380 0.8229851127 0.0351755694 0.0073890000 0.0004500000 0.0024010000 0.0000060000 0.0000050000 0.0018070000 16951501 96830484 509673472 4.9916448593 3.9956097603 4.8397979736 1186 47.4000000000 0.4759191871 0.2953299339 0.8229851127 0.0351613260 0.0086140000 0.0005290000 0.0029050000 0.0000010000 0.0000100000 0.0010510000 16954277 96830484 509673472 4.9912905693 3.9957830906 4.8492636681 1187 47.4400000000 0.4758098423 0.2954819811 0.8229851127 0.0351465723 0.0084070000 0.0005170000 0.0024170000 0.0000100000 0.0000080000 0.0013280000 16957053 96830484 509673472 4.9918518066 3.9977581501 4.8596158028 1188 47.4800000000 0.4755975008 0.2956335934 0.8229851127 0.0351317887 0.0084300000 0.0004500000 0.0045770000 0.0000010000 0.0000060000 0.0009640000 16959829 96830484 509673472 4.9909267426 3.9983522892 4.8684773445 1189 47.5200000000 0.4755280316 0.2957848924 0.8229851127 0.0351176992 0.0084030000 0.0004150000 0.0043600000 0.0000040000 0.0000030000 0.0017730000 16962605 96830484 509673472 4.9895677567 3.9982681274 4.8770980835 1190 47.5600000000 0.4754558802 0.2959358764 0.8229851127 0.0351034272 0.0070060000 0.0004110000 0.0037620000 0.0000000000 0.0000040000 0.0009470000 16965381 96830484 509673472 4.9904212952 3.9993712902 4.8876166344 1191 47.6000000000 0.4753374755 0.2960865075 0.8229851127 0.0350887330 0.0105200000 0.0005990000 0.0034830000 0.0000100000 0.0000100000 0.0013780000 16968157 96830484 509673472 4.9924173355 3.9986913204 4.8981246948 1192 47.6400000000 0.4751975834 0.2962367684 0.8229851127 0.0350740230 0.0086780000 0.0005150000 0.0029440000 0.0000010000 0.0000110000 0.0010430000 16970933 96830484 509673472 4.9968008995 3.9991865158 4.9089298248 1193 47.6800000000 0.4751795828 0.2963867624 0.8229851127 0.0350593171 0.0072230000 0.0004560000 0.0024120000 0.0000060000 0.0000040000 0.0017780000 16973709 96830484 509673472 4.9998140335 3.9988312721 4.9188122749 1194 47.7200000000 0.4752628803 0.2965365749 0.8229851127 0.0350446841 0.0060060000 0.0004160000 0.0027440000 0.0000000000 0.0000040000 0.0009350000 16976485 96830484 509673472 4.9989948273 3.9975008965 4.9274449348 1195 47.7600000000 0.4750648737 0.2966859710 0.8229851127 0.0350301879 0.0057640000 0.0004080000 0.0023730000 0.0000040000 0.0000030000 0.0011500000 16979261 96830484 509673472 5.0017299652 3.9989809990 4.9385061264 1196 47.8000000000 0.4749886096 0.2968350534 0.8229851127 0.0350156673 0.0127030000 0.0005980000 0.0033730000 0.0000010000 0.0000150000 0.0013550000 16982037 96830484 509673472 5.0066637993 4.0007400513 4.9503879547 1197 47.8400000000 0.4749599397 0.2969838629 0.8229851127 0.0350011039 0.0085720000 0.0004710000 0.0028640000 0.0000080000 0.0000070000 0.0018390000 16984813 96830484 509673472 5.0103282928 4.0015754700 4.9612793922 1198 47.8800000000 0.4749244153 0.2971323942 0.8229851127 0.0349865986 0.0081570000 0.0004390000 0.0046130000 0.0000000000 0.0000040000 0.0009400000 16987589 96830484 509673472 5.0126633644 4.0036187172 4.9724168777 1199 47.9200000000 0.4748205245 0.2972805912 0.8229851127 0.0349722729 0.0061580000 0.0004110000 0.0027630000 0.0000040000 0.0000030000 0.0011430000 16990365 96830484 509673472 5.0147743225 4.0043954849 4.9830894470 1200 47.9600000000 0.4749829173 0.2974286764 0.8229851127 0.0349578431 0.0059430000 0.0004070000 0.0027740000 0.0000010000 0.0000030000 0.0009340000 16993141 96830484 509673472 5.0147294998 4.0026760101 4.9911193848 1201 48.0000000000 0.4748971462 0.2975764437 0.8229851127 0.0349440537 0.0118740000 0.0005950000 0.0027810000 0.0000150000 0.0000140000 0.0023520000 16995917 96830484 509673472 5.0196008682 4.0046639442 5.0030531883 1202 48.0400000000 0.4748271108 0.2977239068 0.8229851127 0.0349303439 0.0091160000 0.0004790000 0.0047600000 0.0000000000 0.0000070000 0.0009670000 16998693 96830484 509673472 5.0252308846 4.0073990822 5.0160737038 1203 48.0800000000 0.4747259319 0.2978710407 0.8229851127 0.0349158712 0.0083390000 0.0004320000 0.0046550000 0.0000040000 0.0000040000 0.0011400000 17001469 96830484 509673472 5.0277171135 4.0084223747 5.0263543129 1204 48.1200000000 0.4747418761 0.2980179433 0.8229851127 0.0349024718 0.0060160000 0.0004330000 0.0028020000 0.0000000000 0.0000040000 0.0009250000 17004245 96830484 509673472 5.0306539536 4.0092086792 5.0370955467 1205 48.1600000000 0.4745916724 0.2981644776 0.8229851127 0.0348881167 0.0094930000 0.0005120000 0.0034130000 0.0000080000 0.0000070000 0.0018680000 17007021 96830484 509673472 5.0339150429 4.0121936798 5.0486621857 1206 48.2000000000 0.4745191932 0.2983107087 0.8229851127 0.0348736458 0.0071050000 0.0004400000 0.0032750000 0.0000000000 0.0000040000 0.0009340000 17009797 96830484 509673472 5.0373253822 4.0134568214 5.0590767860 1207 48.2400000000 0.4745077193 0.2984566880 0.8229851127 0.0348592293 0.0083960000 0.0004720000 0.0033760000 0.0000080000 0.0000070000 0.0012010000 17012573 96830484 509673472 5.0391068459 4.0131125450 5.0681948662 1208 48.2800000000 0.4744469821 0.2986023753 0.8229851127 0.0348448240 0.0063780000 0.0004380000 0.0025270000 0.0000000000 0.0000040000 0.0009270000 17015349 96830484 509673472 5.0427842140 4.0143332481 5.0785427094 1209 48.3200000000 0.4742937088 0.2987476948 0.8229851127 0.0348304856 0.0076230000 0.0004130000 0.0036310000 0.0000040000 0.0000030000 0.0017180000 17018125 96830484 509673472 5.0460424423 4.0165977478 5.0891823769 1210 48.3600000000 0.4741917849 0.2988926900 0.8229851127 0.0348161267 0.0105080000 0.0005980000 0.0036880000 0.0000010000 0.0000110000 0.0011220000 17020901 96830484 509673472 5.0462560654 4.0174989700 5.0983328819 1211 48.4000000000 0.4741520286 0.2990374128 0.8229851127 0.0348017910 0.0070220000 0.0004480000 0.0025740000 0.0000060000 0.0000060000 0.0011650000 17023677 96830484 509673472 5.0485701561 4.0180034637 5.1076855659 1212 48.4400000000 0.4738835990 0.2991816753 0.8229851127 0.0347876467 0.0094500000 0.0005280000 0.0042900000 0.0000010000 0.0000080000 0.0010180000 17026453 96830484 509673472 5.0541691780 4.0221600533 5.1282229424 1213 48.4800000000 0.4737606645 0.2993255986 0.8229851127 0.0347737985 0.0072900000 0.0004460000 0.0025710000 0.0000040000 0.0000040000 0.0017310000 17029229 96830484 509673472 5.0540466309 4.0239214897 5.1364006996 1214 48.5200000000 0.4737975895 0.2994693153 0.8229851127 0.0347598391 0.0088230000 0.0005100000 0.0029870000 0.0000000000 0.0000100000 0.0010390000 17032005 96830484 509673472 5.0534348488 4.0240302086 5.1440515518 1215 48.5600000000 0.4736822546 0.2996127004 0.8229851127 0.0347457373 0.0069010000 0.0004470000 0.0025850000 0.0000050000 0.0000050000 0.0011170000 17034781 96830484 509673472 5.0530619621 4.0248656273 5.1518926620 1216 48.6000000000 0.4734729528 0.2997556776 0.8229851127 0.0347320791 0.0084510000 0.0005050000 0.0030920000 0.0000010000 0.0000070000 0.0010120000 17037557 96830484 509673472 5.0537824631 4.0282192230 5.1675758362 1217 48.6400000000 0.4733177423 0.2998982923 0.8229851127 0.0347178703 0.0075760000 0.0004320000 0.0029550000 0.0000060000 0.0000050000 0.0016970000 17040333 96830484 509673472 5.0550622940 4.0298314095 5.1754655838 1218 48.6800000000 0.4731311500 0.3000405196 0.8229851127 0.0347036949 0.0065320000 0.0004150000 0.0033000000 0.0000010000 0.0000040000 0.0009080000 17043109 96830484 509673472 5.0561013222 4.0319414139 5.1834921837 1219 48.7200000000 0.4731024206 0.3001824900 0.8229851127 0.0346896125 0.0091150000 0.0005110000 0.0027260000 0.0000110000 0.0000090000 0.0013050000 17045885 96830484 509673472 5.0573067665 4.0315055847 5.1899662018 1220 48.7600000000 0.4729665220 0.3003241162 0.8229851127 0.0346756330 0.0078600000 0.0004620000 0.0036430000 0.0000010000 0.0000060000 0.0009140000 17048661 96830484 509673472 5.0562639236 4.0335440636 5.1972241402 1221 48.8000000000 0.4728857577 0.3004654443 0.8229851127 0.0346617118 0.0091810000 0.0005200000 0.0027390000 0.0000110000 0.0000090000 0.0018140000 17051437 96830484 509673472 5.0556197166 4.0351290703 5.2046728134 1222 48.8400000000 0.4727374017 0.3006064197 0.8229851127 0.0346476190 0.0081160000 0.0004430000 0.0042800000 0.0000010000 0.0000060000 0.0008980000 17054213 96830484 509673472 5.0538492203 4.0379290581 5.2118906975 1223 48.8800000000 0.4726085663 0.3007470593 0.8229851127 0.0346334638 0.0082280000 0.0004250000 0.0048440000 0.0000040000 0.0000040000 0.0010810000 17056989 96830484 509673472 5.0535588264 4.0388174057 5.2199902534 1224 48.9200000000 0.4726162851 0.3008874753 0.8229851127 0.0346193437 0.0060970000 0.0004090000 0.0029230000 0.0000000000 0.0000050000 0.0008860000 17059765 96830484 509673472 5.0537180901 4.0393729210 5.2273912430 1225 48.9600000000 0.4725568891 0.3010276136 0.8229851127 0.0346053990 0.0080450000 0.0004110000 0.0040850000 0.0000040000 0.0000030000 0.0016430000 17062541 96830484 509673472 5.0528836250 4.0400743484 5.2355871201 1226 49.0000000000 0.4724159837 0.3011674084 0.8229851127 0.0345914774 0.0057250000 0.0004130000 0.0025400000 0.0000000000 0.0000030000 0.0008860000 17065317 96830484 509673472 5.0510640144 4.0412216187 5.2436275482 1227 49.0400000000 0.4722965956 0.3013068780 0.8229851127 0.0345774320 0.0114910000 0.0006010000 0.0033090000 0.0000160000 0.0000130000 0.0014360000 17068093 96830484 509673472 5.0492448807 4.0425062180 5.2516231537 1228 49.0800000000 0.4721516073 0.3014460023 0.8229851127 0.0345633847 0.0075240000 0.0004820000 0.0030340000 0.0000000000 0.0000070000 0.0009110000 17070869 96830484 509673472 5.0473175049 4.0448946953 5.2599792480 1229 49.1200000000 0.4720783234 0.3015848407 0.8229851127 0.0345494407 0.0094560000 0.0005110000 0.0030300000 0.0000100000 0.0000090000 0.0017480000 17073645 96830484 509673472 5.0453691483 4.0462393761 5.2685594559 1230 49.1600000000 0.4719842076 0.3017233767 0.8229851127 0.0345356078 0.0068920000 0.0004430000 0.0029960000 0.0000010000 0.0000060000 0.0008880000 17076421 96830484 509673472 5.0434036255 4.0472440720 5.2781138420 1231 49.2000000000 0.4718982577 0.3018616179 0.8229851127 0.0345216556 0.0063790000 0.0004260000 0.0028160000 0.0000040000 0.0000030000 0.0010710000 17079197 96830484 509673472 5.0422177315 4.0482873917 5.2863745689 1232 49.2400000000 0.4718513489 0.3019995966 0.8229851127 0.0345078639 0.0075390000 0.0004150000 0.0039330000 0.0000010000 0.0000040000 0.0008830000 17081973 96830484 509673472 5.0401549339 4.0490703583 5.2945127487 1233 49.2800000000 0.4717891812 0.3021373010 0.8229851127 0.0344939518 0.0110690000 0.0006480000 0.0033350000 0.0000230000 0.0000140000 0.0018760000 17084749 96830484 509673472 5.0362367630 4.0499281883 5.3019070625 1234 49.3200000000 0.4717300236 0.3022747344 0.8229851127 0.0344799743 0.0068760000 0.0004580000 0.0026210000 0.0000010000 0.0000070000 0.0008850000 17087525 96830484 509673472 5.0329213142 4.0504784584 5.3106851578 1235 49.3600000000 0.4715949595 0.3024118358 0.8229851127 0.0344663401 0.0063150000 0.0004290000 0.0025820000 0.0000050000 0.0000040000 0.0010600000 17090301 96830484 509673472 5.0311012268 4.0515832901 5.3193035126 1236 49.4000000000 0.4715604186 0.3025486874 0.8229851127 0.0344524279 0.0084950000 0.0005070000 0.0027700000 0.0000010000 0.0000120000 0.0009540000 17093077 96830484 509673472 5.0282850266 4.0523052216 5.3272724152 1237 49.4400000000 0.4713973105 0.3026851858 0.8229851127 0.0344386591 0.0096530000 0.0005230000 0.0031620000 0.0000100000 0.0000090000 0.0017360000 17095853 96830484 509673472 5.0280880928 4.0539608002 5.3370237350 1238 49.4800000000 0.4713702202 0.3028214419 0.8229851127 0.0344247626 0.0062270000 0.0004440000 0.0022090000 0.0000010000 0.0000070000 0.0008530000 17098629 96830484 509673472 5.0270953178 4.0547933578 5.3450784683 1239 49.5200000000 0.4711594582 0.3029573080 0.8229851127 0.0344109088 0.0080170000 0.0004210000 0.0045370000 0.0000040000 0.0000040000 0.0010260000 17101405 96830484 509673472 5.0255351067 4.0576419830 5.3535289764 1240 49.5600000000 0.4709770083 0.3030928077 0.8229851127 0.0343970526 0.0079600000 0.0004130000 0.0048040000 0.0000000000 0.0000040000 0.0008380000 17104181 96830484 509673472 5.0244560242 4.0606188774 5.3629889488 1241 49.6000000000 0.4708281755 0.3032279692 0.8229851127 0.0343832297 0.0099630000 0.0005080000 0.0035920000 0.0000100000 0.0000090000 0.0016830000 17106957 96830484 509673472 5.0213274956 4.0627088547 5.3703627586 1242 49.6400000000 0.4707910717 0.3033628831 0.8229851127 0.0343695786 0.0140710000 0.0006030000 0.0033410000 0.0000030000 0.0000150000 0.0012270000 17109733 96830484 509673472 5.0200085640 4.0637669563 5.3770804405 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:23:03 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188253 0.0606188253 0.0606188253 -nan 0.0031730000 0.0004050000 0.0004820000 0.0000060000 0.0000010000 0.0020970000 13111897 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 1305031229.5644419193 0.0642096773 0.0624142513 0.0642096773 0.1658525169 0.0015220000 0.0003350000 0.0004730000 0.0000030000 0.0000000000 0.0006670000 13902361 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 1305031229.5966169834 0.0662607327 0.0636964117 0.0662607327 0.1252029927 0.0015120000 0.0003310000 0.0004700000 0.0000030000 0.0000000000 0.0006620000 13906425 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 1305031229.6287899017 0.0688454211 0.0649836641 0.0688454211 0.1129913759 0.0021080000 0.0003530000 0.0004720000 0.0000040000 0.0000060000 0.0012370000 13910441 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 1305031229.6646571159 0.0660002902 0.0651869893 0.0688454211 0.1146836890 0.0078270000 0.0005600000 0.0045430000 0.0000150000 0.0000140000 0.0024810000 13914553 96830484 509673472 3.9731421471 4.0052900314 4.0138821602 6 1305031229.6968429089 0.0563680492 0.0637171660 0.0688454211 0.1026627795 0.0068270000 0.0005430000 0.0045360000 0.0000020000 0.0000150000 0.0015180000 13919081 96830484 509673472 3.9885790348 3.9999628067 4.0209746361 7 1305031229.7290771008 0.0504549854 0.0618225687 0.0688454211 0.0944331146 0.0063810000 0.0004530000 0.0043000000 0.0000110000 0.0000090000 0.0014990000 13922697 96830484 509673472 3.9917047024 4.0025601387 4.0272207260 8 1305031229.7648689747 0.0483661555 0.0601405171 0.0688454211 0.0875849373 0.0044810000 0.0004180000 0.0029160000 0.0000010000 0.0000080000 0.0010480000 13926481 96830484 509673472 3.9982874393 3.9969058037 4.0331091881 9 1305031229.7969229221 0.0486076772 0.0588590904 0.0688454211 0.0820248414 0.0077040000 0.0005390000 0.0045700000 0.0000150000 0.0000130000 0.0023680000 13930921 96830484 509673472 3.9983472824 3.9944331646 4.0363621712 10 1305031229.8256299496 0.0431774296 0.0572909243 0.0688454211 0.0773879813 0.0052080000 0.0005600000 0.0028890000 0.0000020000 0.0000160000 0.0014910000 13936081 96830484 509673472 4.0013856888 3.9980478287 4.0419988632 11 1305031229.8630619049 0.0423556939 0.0559331761 0.0688454211 0.0737736313 0.0070710000 0.0005920000 0.0045530000 0.0000150000 0.0000140000 0.0016450000 13939977 96830484 509673472 4.0051445961 3.9986858368 4.0450444221 12 1305031229.8969380856 0.0430130921 0.0548565025 0.0688454211 0.0708063125 0.0054990000 0.0005620000 0.0032160000 0.0000020000 0.0000160000 0.0014450000 13943649 96830484 509673472 4.0110373497 4.0005650520 4.0481510162 13 1305031229.9262549877 0.0434641689 0.0539801691 0.0688454211 0.0678463969 0.0070300000 0.0004810000 0.0043840000 0.0000110000 0.0000100000 0.0019670000 13947265 96830484 509673472 4.0163521767 4.0022740364 4.0533332825 14 1305031229.9662408829 0.0455500260 0.0533780160 0.0688454211 0.0652206899 0.0055460000 0.0005460000 0.0035690000 0.0000020000 0.0000150000 0.0012380000 13951161 96830484 509673472 4.0200204849 4.0031929016 4.0585083961 15 1305031229.9979310036 0.0476515070 0.0529962488 0.0688454211 0.0632070389 0.0070150000 0.0005460000 0.0045700000 0.0000160000 0.0000140000 0.0016020000 13954777 96830484 509673472 4.0225687027 4.0032029152 4.0627369881 16 1305031230.0300021172 0.0504680462 0.0528382361 0.0688454211 0.0611103792 0.0057400000 0.0004590000 0.0040650000 0.0000010000 0.0000080000 0.0010710000 13958449 96830484 509673472 4.0251364708 4.0037593842 4.0669593811 17 1305031230.0656960011 0.0551531464 0.0529744073 0.0688454211 0.0592790164 0.0066600000 0.0005310000 0.0035340000 0.0000150000 0.0000140000 0.0022850000 13963769 96830484 509673472 4.0274000168 4.0023460388 4.0701994896 18 1305031230.0982739925 0.0569927581 0.0531976490 0.0688454211 0.0575946490 0.0045490000 0.0004560000 0.0027280000 0.0000020000 0.0000100000 0.0011630000 13970641 96830484 509673472 4.0271863937 4.0021605492 4.0725536346 19 1305031230.1299350262 0.0595731847 0.0535332035 0.0688454211 0.0559910472 0.0056480000 0.0005390000 0.0032070000 0.0000150000 0.0000140000 0.0015830000 13974313 96830484 509673472 4.0280823708 4.0029597282 4.0756869316 20 1305031230.1657800674 0.0631848425 0.0540157855 0.0688454211 0.0545682210 0.0069130000 0.0005380000 0.0046730000 0.0000020000 0.0000150000 0.0013930000 13978097 96830484 509673472 4.0281105042 4.0022926331 4.0780124664 21 1305031230.1977820396 0.0655851439 0.0545667073 0.0688454211 0.0532413359 0.0068680000 0.0004650000 0.0044150000 0.0000120000 0.0000090000 0.0018150000 13981769 96830484 509673472 4.0275349617 4.0007939339 4.0798673630 22 1305031230.2298529148 0.0665480271 0.0551113127 0.0688454211 0.0520200557 0.0055750000 0.0005710000 0.0032600000 0.0000020000 0.0000150000 0.0014240000 13985441 96830484 509673472 4.0251603127 4.0002784729 4.0809020996 23 1305031230.2655899525 0.0659831464 0.0555840012 0.0688454211 0.0509032614 0.0067990000 0.0005270000 0.0042780000 0.0000150000 0.0000140000 0.0016560000 13989225 96830484 509673472 4.0200958252 3.9984281063 4.0805039406 24 1305031230.2979929447 0.0669876188 0.0560591519 0.0688454211 0.0497967235 0.0049350000 0.0004630000 0.0030480000 0.0000010000 0.0000100000 0.0012040000 13992897 96830484 509673472 4.0181369781 3.9989066124 4.0823583603 25 1305031230.3351120949 0.0694679767 0.0565955049 0.0694679767 0.0487936162 0.0061870000 0.0005450000 0.0028740000 0.0000150000 0.0000140000 0.0024210000 13996737 96830484 509673472 4.0160889626 3.9960453510 4.0837535858 26 1305031230.3656799793 0.0678966343 0.0570301637 0.0694679767 0.0478348896 0.0049990000 0.0004580000 0.0030700000 0.0000010000 0.0000110000 0.0012420000 14000353 96830484 509673472 4.0121469498 3.9971477985 4.0845375061 27 1305031230.3973290920 0.0668950751 0.0573955308 0.0694679767 0.0469088737 0.0051860000 0.0005440000 0.0025480000 0.0000160000 0.0000140000 0.0017350000 14004081 96830484 509673472 4.0076198578 3.9959795475 4.0858693123 28 1305031230.4368140697 0.0694590434 0.0578263705 0.0694679767 0.0465536781 0.0064450000 0.0005440000 0.0039780000 0.0000020000 0.0000170000 0.0015680000 14007921 96830484 509673472 4.0056786537 3.9952559471 4.0883440971 29 1305031230.4653120041 0.0683455318 0.0581891002 0.0694679767 0.0458234850 0.0066370000 0.0004570000 0.0037450000 0.0000100000 0.0000100000 0.0021860000 14011481 96830484 509673472 3.9983661175 3.9910607338 4.0867424011 30 1305031230.4972999096 0.0650921315 0.0584192013 0.0694679767 0.0450822124 0.0072040000 0.0005330000 0.0046880000 0.0000010000 0.0000150000 0.0016160000 14015209 96830484 509673472 3.9886209965 3.9885356426 4.0837569237 31 1305031230.5301918983 0.0636629537 0.0585883546 0.0694679767 0.0443623344 0.0064290000 0.0004610000 0.0043520000 0.0000080000 0.0000060000 0.0014250000 14018825 96830484 509673472 3.9802737236 3.9851016998 4.0814461708 32 1305031230.5661149025 0.0644583330 0.0587717914 0.0694679767 0.0440516623 0.0062440000 0.0005720000 0.0036270000 0.0000020000 0.0000160000 0.0016720000 14022665 96830484 509673472 3.9730746746 3.9822406769 4.0817260742 33 1305031230.5988430977 0.0627732873 0.0588930489 0.0694679767 0.0433996882 0.0072380000 0.0005440000 0.0036000000 0.0000160000 0.0000140000 0.0026770000 14029409 96830484 509673472 3.9625964165 3.9787180424 4.0794324875 34 1305031230.6319139004 0.0612620041 0.0589627240 0.0694679767 0.0428684689 0.0056780000 0.0004570000 0.0037620000 0.0000010000 0.0000080000 0.0012650000 14039537 96830484 509673472 3.9489111900 3.9739980698 4.0776333809 35 1305031230.6660470963 0.0582626387 0.0589427216 0.0694679767 0.0423817992 0.0075580000 0.0005690000 0.0046360000 0.0000180000 0.0000130000 0.0019320000 14043265 96830484 509673472 3.9361889362 3.9741892815 4.0754189491 36 1305031230.6979451180 0.0597360022 0.0589647571 0.0694679767 0.0418313196 0.0066720000 0.0005620000 0.0039530000 0.0000020000 0.0000190000 0.0017360000 14046881 96830484 509673472 3.9268481731 3.9702703953 4.0758104324 37 1305031230.7336409092 0.0619273186 0.0590448264 0.0694679767 0.0414661392 0.0073860000 0.0005620000 0.0035850000 0.0000160000 0.0000150000 0.0028060000 14050609 96830484 509673472 3.9186820984 3.9671814442 4.0738830566 38 1305031230.7659239769 0.0659263432 0.0592259189 0.0694679767 0.0409240790 0.0073460000 0.0005470000 0.0046320000 0.0000020000 0.0000140000 0.0017510000 14054337 96830484 509673472 3.9106149673 3.9623126984 4.0718708038 39 1305031230.7973229885 0.0702698827 0.0595090975 0.0702698827 0.0404457923 0.0056310000 0.0004740000 0.0033400000 0.0000110000 0.0000100000 0.0015930000 14058009 96830484 509673472 3.9019258022 3.9571905136 4.0686817169 40 1305031230.8317570686 0.0752883479 0.0599035787 0.0752883479 0.0399548087 0.0066530000 0.0005450000 0.0038890000 0.0000010000 0.0000150000 0.0017950000 14061737 96830484 509673472 3.8931603432 3.9518435001 4.0666875839 41 1305031230.8655419350 0.0775321722 0.0603335444 0.0775321722 0.0396735174 0.0071050000 0.0005380000 0.0031840000 0.0000150000 0.0000140000 0.0029380000 14065409 96830484 509673472 3.8831915855 3.9491057396 4.0667800903 42 1305031230.8973939419 0.0849009603 0.0609184829 0.0849009603 0.0392595683 0.0053370000 0.0004780000 0.0030420000 0.0000020000 0.0000100000 0.0015860000 14069137 96830484 509673472 3.8751685619 3.9417405128 4.0725178719 43 1305031230.9373099804 0.1036214903 0.0619115761 0.1036214903 0.0394396894 0.0056270000 0.0004210000 0.0032780000 0.0000100000 0.0000060000 0.0017000000 14072977 96830484 509673472 3.8573446274 3.9271049500 4.0855479240 44 1305031230.9650349617 0.1126514822 0.0630647558 0.1126514822 0.0396240876 0.0076940000 0.0005330000 0.0046870000 0.0000010000 0.0000170000 0.0020240000 14076537 96830484 509673472 3.8489439487 3.9250364304 4.1061806679 45 1305031230.9971239567 0.1228604838 0.0643935497 0.1228604838 0.0395394970 0.0076210000 0.0004530000 0.0043850000 0.0000110000 0.0000090000 0.0025370000 14080265 96830484 509673472 3.8421905041 3.9233098030 4.1240959167 46 1305031231.0367500782 0.1285014153 0.0657871990 0.1285014153 0.0392359400 0.0059260000 0.0003980000 0.0038830000 0.0000010000 0.0000060000 0.0014570000 14084105 96830484 509673472 3.8390808105 3.9225959778 4.1336832047 47 1305031231.0644741058 0.1276431382 0.0671032828 0.1285014153 0.0388301834 0.0079450000 0.0005370000 0.0046120000 0.0000150000 0.0000140000 0.0023140000 14087609 96830484 509673472 3.8370058537 3.9242868423 4.1336231232 48 1305031231.0967879295 0.1190562993 0.0681856373 0.1285014153 0.0384312650 0.0051720000 0.0004480000 0.0029700000 0.0000010000 0.0000080000 0.0015360000 14091337 96830484 509673472 3.8386440277 3.9319970608 4.1299257278 49 1305031231.1347110271 0.1253220439 0.0693516864 0.1285014153 0.0380410300 0.0059680000 0.0004030000 0.0029020000 0.0000070000 0.0000060000 0.0024540000 14095121 96830484 509673472 3.8387858868 3.9262878895 4.1350598335 50 1305031231.1652760506 0.1262003928 0.0704886606 0.1285014153 0.0377009880 0.0078080000 0.0005580000 0.0046670000 0.0000020000 0.0000150000 0.0020860000 14098793 96830484 509673472 3.8395664692 3.9259102345 4.1370253563 51 1305031231.1977710724 0.1153621823 0.0713685335 0.1285014153 0.0374272418 0.0074630000 0.0005420000 0.0046280000 0.0000110000 0.0000100000 0.0019510000 14102521 96830484 509673472 3.8438870907 3.9348824024 4.1325783730 52 1305031231.2344679832 0.1073559895 0.0720606000 0.1285014153 0.0376397426 0.0056160000 0.0004570000 0.0034100000 0.0000010000 0.0000070000 0.0015000000 14106305 96830484 509673472 3.8506636620 3.9355275631 4.1207761765 53 1305031231.2656350136 0.0904345289 0.0724072779 0.1285014153 0.0374493579 0.0090350000 0.0005500000 0.0054430000 0.0000160000 0.0000140000 0.0026510000 14109921 96830484 509673472 3.8585505486 3.9467239380 4.1030874252 54 1305031231.2978610992 0.0766260847 0.0724854040 0.1285014153 0.0374312692 0.0056280000 0.0004270000 0.0036460000 0.0000010000 0.0000060000 0.0013360000 14113649 96830484 509673472 3.8617553711 3.9629385471 4.0749583244 55 1305031231.3351519108 0.0696126148 0.0724331714 0.1285014153 0.0373595069 0.0062680000 0.0004260000 0.0042250000 0.0000060000 0.0000060000 0.0014580000 14117433 96830484 509673472 3.8725907803 3.9744107723 4.0630760193 56 1305031231.3650770187 0.0631329566 0.0722670962 0.1285014153 0.0371243655 0.0058880000 0.0003740000 0.0042070000 0.0000000000 0.0000050000 0.0011550000 14121049 96830484 509673472 3.8813085556 3.9861824512 4.0575180054 57 1305031231.3973300457 0.0552771725 0.0719690273 0.1285014153 0.0368373363 0.0085500000 0.0005400000 0.0047340000 0.0000170000 0.0000140000 0.0027340000 14124777 96830484 509673472 3.8936707973 3.9881591797 4.0656743050 58 1305031231.4368579388 0.0494100675 0.0715800797 0.1285014153 0.0365717269 0.0069160000 0.0005320000 0.0046510000 0.0000010000 0.0000110000 0.0013710000 14128617 96830484 509673472 3.9070336819 3.9880902767 4.0772781372 59 1305031231.4649889469 0.0473814271 0.0711699331 0.1285014153 0.0363245176 0.0064140000 0.0004210000 0.0044000000 0.0000080000 0.0000070000 0.0013670000 14132177 96830484 509673472 3.9147350788 3.9904048443 4.0792593956 60 1305031231.4992439747 0.0420104340 0.0706839414 0.1285014153 0.0361054052 0.0059360000 0.0004840000 0.0038260000 0.0000010000 0.0000110000 0.0013410000 14135849 96830484 509673472 3.9257855415 3.9976346493 4.0801510811 61 1305031231.5331959724 0.0397359282 0.0701765970 0.1285014153 0.0358646209 0.0079700000 0.0005650000 0.0044320000 0.0000160000 0.0000140000 0.0025680000 14139689 96830484 509673472 3.9335076809 4.0012335777 4.0831446648 62 1305031231.5650680065 0.0379029922 0.0696560549 0.1285014153 0.0356467557 0.0048600000 0.0004220000 0.0030590000 0.0000010000 0.0000070000 0.0011500000 14143305 96830484 509673472 3.9429721832 4.0043387413 4.0891313553 63 1305031231.6013169289 0.0356899500 0.0691169104 0.1285014153 0.0353649927 0.0063520000 0.0004070000 0.0043830000 0.0000060000 0.0000050000 0.0013280000 14147089 96830484 509673472 3.9475774765 4.0089297295 4.0909676552 64 1305031231.6331589222 0.0349421538 0.0685829298 0.1285014153 0.0351525660 0.0071330000 0.0005490000 0.0044420000 0.0000010000 0.0000150000 0.0015740000 14150817 96830484 509673472 3.9525461197 4.0123147964 4.0922441483 65 1305031231.6650550365 0.0355422720 0.0680746120 0.1285014153 0.0348846832 0.0081570000 0.0005510000 0.0047870000 0.0000160000 0.0000140000 0.0023960000 14160577 96830484 509673472 3.9609827995 4.0156898499 4.0960006714 66 1305031231.7035079002 0.0359736495 0.0675882338 0.1285014153 0.0348113082 0.0061870000 0.0004270000 0.0044900000 0.0000010000 0.0000060000 0.0010320000 14177273 96830484 509673472 3.9648318291 4.0162220001 4.0989775658 67 1305031231.7339379787 0.0358215384 0.0671141040 0.1285014153 0.0346479117 0.0077950000 0.0005510000 0.0049090000 0.0000150000 0.0000130000 0.0017290000 14180833 96830484 509673472 3.9677388668 4.0173707008 4.0997757912 68 1305031231.7655088902 0.0362467244 0.0666601720 0.1285014153 0.0344428377 0.0063130000 0.0004790000 0.0044800000 0.0000010000 0.0000080000 0.0010550000 14184505 96830484 509673472 3.9719734192 4.0189599991 4.1015963554 69 1305031231.8011910915 0.0395300016 0.0662669811 0.1285014153 0.0342162471 0.0055160000 0.0003870000 0.0033020000 0.0000060000 0.0000050000 0.0016180000 14188289 96830484 509673472 3.9772009850 4.0177221298 4.1020860672 70 1305031231.8332920074 0.0401928946 0.0658944942 0.1285014153 0.0341616380 0.0056970000 0.0003810000 0.0042800000 0.0000010000 0.0000060000 0.0008540000 14191961 96830484 509673472 3.9785118103 4.0166339874 4.0990862846 71 1305031231.8649590015 0.0408110991 0.0655412069 0.1285014153 0.0339575013 0.0059250000 0.0003820000 0.0043080000 0.0000050000 0.0000040000 0.0010490000 14195633 96830484 509673472 3.9796402454 4.0160098076 4.0947890282 72 1305031231.9012699127 0.0462740660 0.0652736077 0.1285014153 0.0340150019 0.0056850000 0.0003820000 0.0043230000 0.0000000000 0.0000040000 0.0007900000 14199417 96830484 509673472 3.9711856842 4.0083575249 4.0849370956 73 1305031231.9330461025 0.0498077348 0.0650617464 0.1285014153 0.0338475897 0.0052640000 0.0003750000 0.0033060000 0.0000050000 0.0000040000 0.0013940000 14203089 96830484 509673472 3.9762156010 4.0055418015 4.0834751129 74 1305031231.9650299549 0.0511238016 0.0648733958 0.1285014153 0.0336360278 0.0046540000 0.0003770000 0.0033200000 0.0000010000 0.0000050000 0.0007610000 14206761 96830484 509673472 3.9756486416 4.0047979355 4.0795373917 75 1305031232.0007200241 0.0519673266 0.0647013149 0.1285014153 0.0335460672 0.0048530000 0.0003740000 0.0033010000 0.0000050000 0.0000040000 0.0009860000 14210545 96830484 509673472 3.9750094414 4.0048890114 4.0765004158 76 1305031232.0332028866 0.0545663126 0.0645679596 0.1285014153 0.0334385792 0.0053470000 0.0003810000 0.0039930000 0.0000010000 0.0000050000 0.0007790000 14214273 96830484 509673472 3.9725980759 4.0028810501 4.0721654892 77 1305031232.0651450157 0.0570222586 0.0644699635 0.1285014153 0.0332618386 0.0069640000 0.0005310000 0.0036850000 0.0000160000 0.0000150000 0.0020660000 14217889 96830484 509673472 3.9693605900 4.0023756027 4.0674872398 78 1305031232.1007990837 0.0598187298 0.0644103323 0.1285014153 0.0331274373 0.0058020000 0.0005290000 0.0033330000 0.0000020000 0.0000150000 0.0012730000 14221673 96830484 509673472 3.9646937847 4.0026407242 4.0624933243 79 1305031232.1328380108 0.0634788573 0.0643985415 0.1285014153 0.0329692084 0.0075020000 0.0005480000 0.0047870000 0.0000150000 0.0000150000 0.0014870000 14225401 96830484 509673472 3.9615371227 4.0012812614 4.0583415031 80 1305031232.1650519371 0.0659556016 0.0644180047 0.1285014153 0.0327836762 0.0062580000 0.0004560000 0.0045420000 0.0000000000 0.0000080000 0.0009200000 14229017 96830484 509673472 3.9591035843 4.0009789467 4.0545697212 81 1305031232.1992239952 0.0668427795 0.0644479402 0.1285014153 0.0326218168 0.0078210000 0.0005600000 0.0044410000 0.0000170000 0.0000140000 0.0021070000 14232745 96830484 509673472 3.9590909481 4.0021848679 4.0513677597 82 1305031232.2364680767 0.0681435093 0.0644930081 0.1285014153 0.0324558684 0.0056710000 0.0004610000 0.0038250000 0.0000010000 0.0000100000 0.0010260000 14236585 96830484 509673472 3.9584920406 4.0025792122 4.0481781960 83 1305031232.2626979351 0.0711618066 0.0645733551 0.1285014153 0.0324157526 0.0055600000 0.0004630000 0.0036630000 0.0000070000 0.0000060000 0.0010990000 14240089 96830484 509673472 3.9579079151 4.0004873276 4.0453228951 84 1305031232.2980248928 0.0715694427 0.0646566419 0.1285014153 0.0323799265 0.0055700000 0.0005820000 0.0029120000 0.0000020000 0.0000150000 0.0013580000 14243873 96830484 509673472 3.9576833248 4.0016088486 4.0424175262 85 1305031232.3321430683 0.0766853392 0.0647981560 0.1285014153 0.0322614950 0.0081520000 0.0005490000 0.0047050000 0.0000150000 0.0000130000 0.0021650000 14247601 96830484 509673472 3.9540026188 3.9985418320 4.0386261940 86 1305031232.3647489548 0.0777888820 0.0649492109 0.1285014153 0.0321100402 0.0050770000 0.0004520000 0.0030640000 0.0000010000 0.0000100000 0.0010920000 14251217 96830484 509673472 3.9514708519 4.0012884140 4.0351667404 87 1305031232.4008779526 0.0808718354 0.0651322296 0.1285014153 0.0319436184 0.0052400000 0.0004070000 0.0032950000 0.0000080000 0.0000070000 0.0011700000 14255057 96830484 509673472 3.9476127625 4.0025606155 4.0314664841 88 1305031232.4331440926 0.0822068527 0.0653262594 0.1285014153 0.0317612805 0.0060250000 0.0004080000 0.0042970000 0.0000010000 0.0000080000 0.0009550000 14258785 96830484 509673472 3.9462003708 4.0030550957 4.0289134979 89 1305031232.4647209644 0.0859753415 0.0655582715 0.1285014153 0.0315835165 0.0066920000 0.0005330000 0.0032100000 0.0000160000 0.0000390000 0.0021770000 14262345 96830484 509673472 3.9408099651 4.0039043427 4.0259790421 90 1305031232.5015261173 0.0900212452 0.0658300824 0.1285014153 0.0314140738 0.0061420000 0.0005180000 0.0035410000 0.0000030000 0.0000150000 0.0013420000 14266185 96830484 509673472 3.9379568100 4.0000700951 4.0233101845 91 1305031232.5324640274 0.0992425382 0.0661972522 0.1285014153 0.0312462101 0.0067500000 0.0005260000 0.0039240000 0.0000180000 0.0000130000 0.0015650000 14269857 96830484 509673472 3.9294650555 3.9937314987 4.0196142197 92 1305031232.5647449493 0.1077950224 0.0666494019 0.1285014153 0.0311107749 0.0057930000 0.0004290000 0.0037390000 0.0000010000 0.0000110000 0.0011240000 14273529 96830484 509673472 3.9209015369 3.9889326096 4.0161385536 93 1305031232.6003499031 0.1180794761 0.0672024134 0.1285014153 0.0309666658 0.0064440000 0.0005170000 0.0029070000 0.0000150000 0.0000130000 0.0022550000 14277257 96830484 509673472 3.9122056961 3.9815616608 4.0124711990 94 1305031232.6294269562 0.1234813035 0.0678011250 0.1285014153 0.0308343791 0.0054480000 0.0004280000 0.0033820000 0.0000020000 0.0000120000 0.0011300000 14280817 96830484 509673472 3.9071018696 3.9794561863 4.0087475777 95 1305031232.6647078991 0.1261755675 0.0684155928 0.1285014153 0.0306738547 0.0049740000 0.0003950000 0.0029300000 0.0000080000 0.0000070000 0.0012550000 14284657 96830484 509673472 3.9018571377 3.9812457561 4.0058507919 96 1305031232.7005090714 0.1333688051 0.0690921888 0.1333688051 0.0305246656 0.0062890000 0.0005210000 0.0035970000 0.0000020000 0.0000160000 0.0014010000 14288385 96830484 509673472 3.8939309120 3.9794600010 4.0022983551 97 1305031232.7327980995 0.1361811310 0.0697838274 0.1361811310 0.0304093675 0.0075380000 0.0005030000 0.0039120000 0.0000160000 0.0000130000 0.0023340000 14292057 96830484 509673472 3.8910267353 3.9803545475 3.9986591339 98 1305031232.7684600353 0.1406485438 0.0705069367 0.1406485438 0.0303229068 0.0064300000 0.0004320000 0.0044300000 0.0000010000 0.0000100000 0.0011660000 14295841 96830484 509673472 3.8864107132 3.9775538445 3.9963953495 99 1305031232.8045380116 0.1474343687 0.0712839815 0.1474343687 0.0301851007 0.0053960000 0.0003980000 0.0032900000 0.0000080000 0.0000060000 0.0013010000 14299625 96830484 509673472 3.8793933392 3.9728925228 3.9933712482 100 1305031232.8346450329 0.1512712836 0.0720838545 0.1512712836 0.0300740570 0.0063980000 0.0005190000 0.0036790000 0.0000010000 0.0000170000 0.0014390000 14303241 96830484 509673472 3.8741917610 3.9746558666 3.9896557331 101 1305031232.8685569763 0.1544674933 0.0728995341 0.1544674933 0.0299614040 0.0065040000 0.0005030000 0.0028770000 0.0000150000 0.0000130000 0.0023480000 14307025 96830484 509673472 3.8699858189 3.9746677876 3.9867889881 102 1305031232.9041829109 0.1580434442 0.0737342783 0.1580434442 0.0298424470 0.0064500000 0.0004310000 0.0044790000 0.0000020000 0.0000100000 0.0011430000 14310753 96830484 509673472 3.8650627136 3.9743180275 3.9844172001 103 1305031232.9330000877 0.1595018059 0.0745669728 0.1595018059 0.0297417243 0.0076450000 0.0005340000 0.0046350000 0.0000150000 0.0000140000 0.0017110000 14314313 96830484 509673472 3.8629107475 3.9767136574 3.9821939468 104 1305031232.9683640003 0.1583705395 0.0753727763 0.1595018059 0.0295973433 0.0068540000 0.0005140000 0.0045820000 0.0000010000 0.0000090000 0.0012340000 14318153 96830484 509673472 3.8635804653 3.9770915508 3.9805135727 105 1305031233.0011510849 0.1550354660 0.0761314686 0.1595018059 0.0294994044 0.0059450000 0.0004380000 0.0030720000 0.0000110000 0.0000090000 0.0020240000 14321825 96830484 509673472 3.8653929234 3.9829738140 3.9794945717 106 1305031233.0330219269 0.1526721567 0.0768535505 0.1595018059 0.0296632245 0.0045330000 0.0003950000 0.0026630000 0.0000010000 0.0000070000 0.0010750000 14325497 96830484 509673472 3.8633859158 3.9889028072 3.9824059010 107 1305031233.0688428879 0.1467276514 0.0775065795 0.1595018059 0.0298044605 0.0066240000 0.0005180000 0.0036480000 0.0000170000 0.0000130000 0.0016430000 14329169 96830484 509673472 3.8674097061 3.9922590256 3.9837861061 108 1305031233.1004469395 0.1359139681 0.0780473887 0.1595018059 0.0297553693 0.0063430000 0.0005060000 0.0039970000 0.0000010000 0.0000160000 0.0012940000 14332785 96830484 509673472 3.8749871254 4.0037198067 3.9880661964 109 1305031233.1328918934 0.1288707405 0.0785136580 0.1595018059 0.0301006903 0.0068730000 0.0005050000 0.0032550000 0.0000160000 0.0000130000 0.0022800000 14336457 96830484 509673472 3.8847365379 3.9985458851 3.9897854328 110 1305031233.1684799194 0.1173117086 0.0788663675 0.1595018059 0.0300968836 0.0051820000 0.0004310000 0.0030920000 0.0000010000 0.0000110000 0.0011080000 14340241 96830484 509673472 3.9008972645 4.0019855499 3.9902131557 111 1305031233.2006340027 0.1139735505 0.0791826484 0.1595018059 0.0300002072 0.0058900000 0.0005150000 0.0029710000 0.0000150000 0.0000130000 0.0015710000 14343913 96830484 509673472 3.9042928219 4.0020074844 3.9933516979 112 1305031233.2330091000 0.1112020984 0.0794685364 0.1595018059 0.0299752472 0.0052560000 0.0005180000 0.0025650000 0.0000020000 0.0000150000 0.0013220000 14347585 96830484 509673472 3.9042818546 4.0034441948 3.9971532822 113 1305031233.2684679031 0.1098584756 0.0797374739 0.1595018059 0.0306192452 0.0067830000 0.0005170000 0.0032480000 0.0000160000 0.0000130000 0.0021640000 14351369 96830484 509673472 3.9010772705 4.0039572716 4.0019555092 114 1305031233.3003950119 0.0954523832 0.0798753240 0.1595018059 0.0308696505 0.0065400000 0.0004310000 0.0044090000 0.0000020000 0.0000100000 0.0011440000 14355041 96830484 509673472 3.9098463058 4.0133023262 4.0098042488 115 1305031233.3325300217 0.0881772861 0.0799475150 0.1595018059 0.0307530755 0.0068060000 0.0005160000 0.0038570000 0.0000160000 0.0000130000 0.0015700000 14358713 96830484 509673472 3.9127480984 4.0038623810 4.0230712891 116 1305031233.3686299324 0.0701177865 0.0798627759 0.1595018059 0.0307171295 0.0060040000 0.0005330000 0.0038500000 0.0000010000 0.0000110000 0.0010380000 14362385 96830484 509673472 3.9358651638 4.0126738548 4.0282664299 117 1305031233.4008929729 0.0578634776 0.0796747477 0.1595018059 0.0306981246 0.0080800000 0.0005510000 0.0045850000 0.0000150000 0.0000130000 0.0020640000 14366113 96830484 509673472 3.9621942043 4.0260162354 4.0355210304 118 1305031233.4330079556 0.0598938875 0.0795071133 0.1595018059 0.0307172782 0.0054750000 0.0004570000 0.0036920000 0.0000010000 0.0000080000 0.0008890000 14369841 96830484 509673472 3.9574632645 4.0160646439 4.0406641960 119 1305031233.4687869549 0.0625155345 0.0793643269 0.1595018059 0.0307294815 0.0044350000 0.0004080000 0.0026030000 0.0000070000 0.0000060000 0.0010370000 14373513 96830484 509673472 3.9560582638 4.0093111992 4.0449223518 120 1305031233.5007359982 0.0640838593 0.0792369897 0.1595018059 0.0306303253 0.0045770000 0.0004010000 0.0029590000 0.0000010000 0.0000060000 0.0008440000 14377241 96830484 509673472 3.9523572922 4.0066161156 4.0465812683 121 1305031233.5341610909 0.0649405345 0.0791188372 0.1595018059 0.0306033372 0.0071550000 0.0005330000 0.0036700000 0.0000150000 0.0000130000 0.0020470000 14380969 96830484 509673472 3.9527852535 4.0052227974 4.0493707657 122 1305031233.5697269440 0.0640497059 0.0789953197 0.1595018059 0.0305035051 0.0060000000 0.0005410000 0.0033050000 0.0000020000 0.0000140000 0.0012560000 14384697 96830484 509673472 3.9536762238 4.0051975250 4.0530681610 123 1305031233.6012749672 0.0664718822 0.0788935032 0.1595018059 0.0304404078 0.0068720000 0.0005420000 0.0039450000 0.0000150000 0.0000130000 0.0014720000 14388369 96830484 509673472 3.9524228573 4.0021739006 4.0541315079 124 1305031233.6330409050 0.0666481256 0.0787947501 0.1595018059 0.0303736124 0.0060940000 0.0005400000 0.0039570000 0.0000010000 0.0000090000 0.0009880000 14392041 96830484 509673472 3.9529330730 3.9992823601 4.0584874153 125 1305031233.6717829704 0.0660576522 0.0786928533 0.1595018059 0.0302537419 0.0054950000 0.0004300000 0.0030020000 0.0000080000 0.0000080000 0.0015620000 14395937 96830484 509673472 3.9493193626 3.9991648197 4.0595183372 126 1305031233.7022960186 0.0630999133 0.0785690998 0.1595018059 0.0303106883 0.0075710000 0.0005480000 0.0047680000 0.0000010000 0.0000140000 0.0012870000 14399609 96830484 509673472 3.9506602287 4.0010457039 4.0634040833 127 1305031233.7312009335 0.0559090562 0.0783906743 0.1595018059 0.0304852234 0.0072470000 0.0005470000 0.0047620000 0.0000110000 0.0000100000 0.0012690000 14403169 96830484 509673472 3.9581093788 4.0089669228 4.0703663826 128 1305031233.7691600323 0.0526394881 0.0781894932 0.1595018059 0.0305373647 0.0055070000 0.0004240000 0.0037600000 0.0000010000 0.0000080000 0.0009230000 14406953 96830484 509673472 3.9617068768 4.0132045746 4.0731859207 129 1305031233.7997679710 0.0530553050 0.0779946545 0.1595018059 0.0304311114 0.0084360000 0.0005350000 0.0047840000 0.0000180000 0.0000140000 0.0020940000 14422857 96830484 509673472 3.9604806900 4.0119609833 4.0722026825 130 1305031233.8338310719 0.0565548688 0.0778297331 0.1595018059 0.0303843768 0.0053210000 0.0004590000 0.0034440000 0.0000010000 0.0000070000 0.0009170000 14452185 96830484 509673472 3.9560608864 4.0062003136 4.0686235428 131 1305031233.8655700684 0.0585647114 0.0776826718 0.1595018059 0.0303123312 0.0063710000 0.0005450000 0.0032960000 0.0000160000 0.0000140000 0.0015190000 14455857 96830484 509673472 3.9568920135 4.0042829514 4.0680832863 132 1305031233.8986968994 0.0575829968 0.0775304016 0.1595018059 0.0301973280 0.0052240000 0.0004540000 0.0031060000 0.0000010000 0.0000100000 0.0010450000 14459641 96830484 509673472 3.9570047855 4.0052886009 4.0679898262 133 1305031233.9320030212 0.0572977401 0.0773782763 0.1595018059 0.0301239371 0.0065860000 0.0004220000 0.0040540000 0.0000080000 0.0000080000 0.0015900000 14463313 96830484 509673472 3.9631130695 4.0054159164 4.0708804131 134 1305031233.9681589603 0.0555117801 0.0772150935 0.1595018059 0.0300300520 0.0066410000 0.0004560000 0.0045220000 0.0000010000 0.0000100000 0.0010040000 14467097 96830484 509673472 3.9686245918 4.0079436302 4.0727267265 135 1305031233.9989380836 0.0563585348 0.0770606005 0.1595018059 0.0299605887 0.0064520000 0.0004250000 0.0044400000 0.0000080000 0.0000080000 0.0010850000 14470769 96830484 509673472 3.9696280956 4.0067906380 4.0714130402 136 1305031234.0370678902 0.0540155210 0.0768911513 0.1595018059 0.0298621667 0.0058200000 0.0005460000 0.0029680000 0.0000020000 0.0000170000 0.0012580000 14474609 96830484 509673472 3.9751319885 4.0108146667 4.0730185509 137 1305031234.0687561035 0.0530692749 0.0767172690 0.1595018059 0.0297548007 0.0077140000 0.0005480000 0.0044730000 0.0000150000 0.0000140000 0.0019640000 14478225 96830484 509673472 3.9765322208 4.0121383667 4.0721611977 138 1305031234.0997409821 0.0534477085 0.0765486490 0.1595018059 0.0296526944 0.0049610000 0.0004370000 0.0030930000 0.0000010000 0.0000070000 0.0009040000 14481897 96830484 509673472 3.9837963581 4.0151104927 4.0742435455 139 1305031234.1350688934 0.0530530885 0.0763796162 0.1595018059 0.0295610539 0.0079560000 0.0005440000 0.0048210000 0.0000160000 0.0000130000 0.0015190000 14485625 96830484 509673472 3.9847354889 4.0166130066 4.0728669167 140 1305031234.1659009457 0.0493565388 0.0761865942 0.1595018059 0.0295248987 0.0070990000 0.0005430000 0.0047820000 0.0000010000 0.0000100000 0.0010600000 14489297 96830484 509673472 3.9853947163 4.0225930214 4.0733928680 141 1305031234.2010040283 0.0495187081 0.0759974603 0.1595018059 0.0294751008 0.0071600000 0.0004700000 0.0047250000 0.0000070000 0.0000050000 0.0015310000 14493025 96830484 509673472 3.9849858284 4.0219783783 4.0723714828 142 1305031234.2385749817 0.0483151190 0.0758025142 0.1595018059 0.0293734006 0.0047580000 0.0003950000 0.0031180000 0.0000010000 0.0000060000 0.0008630000 14496921 96830484 509673472 3.9864339828 4.0249533653 4.0728235245 143 1305031234.2655100822 0.0450208746 0.0755872580 0.1595018059 0.0292948874 0.0055230000 0.0003910000 0.0036660000 0.0000060000 0.0000050000 0.0010830000 14500369 96830484 509673472 3.9884891510 4.0325026512 4.0756468773 144 1305031234.3024549484 0.0448562466 0.0753738482 0.1595018059 0.0291923958 0.0049980000 0.0003910000 0.0033310000 0.0000010000 0.0000050000 0.0009000000 14504265 96830484 509673472 3.9889659882 4.0325503349 4.0758886337 145 1305031234.3384580612 0.0441218466 0.0751583172 0.1595018059 0.0291107193 0.0067220000 0.0003920000 0.0043570000 0.0000060000 0.0000050000 0.0015890000 14508049 96830484 509673472 3.9874911308 4.0338325500 4.0748329163 146 1305031234.3661808968 0.0416707881 0.0749289505 0.1595018059 0.0290556422 0.0040090000 0.0003950000 0.0022920000 0.0000000000 0.0000050000 0.0009430000 14511553 96830484 509673472 3.9888339043 4.0392751694 4.0775427818 147 1305031234.4000349045 0.0423396938 0.0747072549 0.1595018059 0.0289565725 0.0049310000 0.0003910000 0.0029780000 0.0000060000 0.0000050000 0.0011760000 14515281 96830484 509673472 3.9910950661 4.0407695770 4.0789103508 148 1305031234.4367709160 0.0447300673 0.0745047063 0.1595018059 0.0289250601 0.0044050000 0.0003910000 0.0026390000 0.0000000000 0.0000050000 0.0009940000 14519121 96830484 509673472 3.9954431057 4.0407052040 4.0794649124 149 1305031234.4676060677 0.0456339233 0.0743109427 0.1595018059 0.0288374282 0.0061580000 0.0003880000 0.0036420000 0.0000060000 0.0000050000 0.0017390000 14522737 96830484 509673472 3.9978091717 4.0435471535 4.0796790123 150 1305031234.4977810383 0.0462484211 0.0741238592 0.1595018059 0.0287455385 0.0044770000 0.0003890000 0.0026450000 0.0000000000 0.0000050000 0.0010590000 14526353 96830484 509673472 3.9991929531 4.0472025871 4.0797543526 151 1305031234.5376710892 0.0500835106 0.0739646516 0.1595018059 0.0288276085 0.0060510000 0.0003870000 0.0039570000 0.0000060000 0.0000050000 0.0013150000 14530249 96830484 509673472 4.0030694008 4.0437340736 4.0763339996 152 1305031234.5690369606 0.0538990125 0.0738326408 0.1595018059 0.0288380678 0.0082620000 0.0005470000 0.0047440000 0.0000030000 0.0000160000 0.0017980000 14533865 96830484 509673472 4.0089321136 4.0506691933 4.0795903206 153 1305031234.5982480049 0.0582128577 0.0737305507 0.1595018059 0.0287479659 0.0084840000 0.0005510000 0.0047250000 0.0000150000 0.0000140000 0.0024190000 14537537 96830484 509673472 4.0134906769 4.0554037094 4.0808358192 154 1305031234.6336491108 0.0601005815 0.0736420444 0.1595018059 0.0286877540 0.0065820000 0.0004300000 0.0043940000 0.0000010000 0.0000070000 0.0012950000 14541209 96830484 509673472 4.0147175789 4.0546984673 4.0770912170 155 1305031234.6658589840 0.0631382614 0.0735742781 0.1595018059 0.0286200863 0.0071540000 0.0004860000 0.0044780000 0.0000100000 0.0000090000 0.0015930000 14544937 96830484 509673472 4.0166015625 4.0580172539 4.0755424500 156 1305031234.6987318993 0.0645184219 0.0735162277 0.1595018059 0.0285411583 0.0061000000 0.0004030000 0.0040210000 0.0000010000 0.0000060000 0.0012800000 14548665 96830484 509673472 4.0146932602 4.0600724220 4.0704240799 157 1305031234.7344369888 0.0658668876 0.0734675058 0.1595018059 0.0284589236 0.0091990000 0.0005650000 0.0047570000 0.0000170000 0.0000140000 0.0030490000 14552337 96830484 509673472 4.0115056038 4.0640597343 4.0652389526 158 1305031234.7689719200 0.0690296963 0.0734394184 0.1595018059 0.0283747782 0.0067870000 0.0004370000 0.0044580000 0.0000000000 0.0000070000 0.0014180000 14556121 96830484 509673472 4.0119304657 4.0681362152 4.0633025169 159 1305031234.8015530109 0.0729394183 0.0734362738 0.1595018059 0.0284048710 0.0066490000 0.0003900000 0.0043160000 0.0000050000 0.0000040000 0.0015580000 14559849 96830484 509673472 4.0074472427 4.0816249847 4.0647621155 160 1305031234.8378078938 0.0758854598 0.0734515812 0.1595018059 0.0283340704 0.0050600000 0.0003790000 0.0029840000 0.0000010000 0.0000050000 0.0013530000 14563689 96830484 509673472 4.0056719780 4.0885624886 4.0675096512 161 1305031234.8693211079 0.0781715140 0.0734808975 0.1595018059 0.0282623041 0.0098340000 0.0005520000 0.0048170000 0.0000140000 0.0000140000 0.0032540000 14567249 96830484 509673472 3.9989967346 4.0942788124 4.0629086494 162 1305031234.9019980431 0.0820893720 0.0735340363 0.1595018059 0.0281843705 0.0066820000 0.0004640000 0.0041920000 0.0000010000 0.0000080000 0.0015420000 14570977 96830484 509673472 3.9961712360 4.1019487381 4.0670146942 163 1305031234.9381608963 0.0842170641 0.0735995763 0.1595018059 0.0282744781 0.0060620000 0.0003890000 0.0037170000 0.0000040000 0.0000040000 0.0016020000 14574761 96830484 509673472 3.9900083542 4.1089334488 4.0729985237 164 1305031234.9730799198 0.0855776221 0.0736726132 0.1595018059 0.0281907475 0.0077110000 0.0004770000 0.0046260000 0.0000010000 0.0000120000 0.0017850000 14578545 96830484 509673472 3.9888501167 4.1118674278 4.0792856216 165 1305031235.0050830841 0.0845695287 0.0737386551 0.1595018059 0.0282537639 0.0076870000 0.0004300000 0.0044840000 0.0000070000 0.0000060000 0.0023460000 14582161 96830484 509673472 3.9893488884 4.1127576828 4.0885453224 166 1305031235.0399720669 0.0799110308 0.0737758381 0.1595018059 0.0281740661 0.0057150000 0.0003800000 0.0037190000 0.0000000000 0.0000030000 0.0013010000 14585945 96830484 509673472 3.9948477745 4.1057209969 4.0941481590 167 1305031235.0729401112 0.0760427043 0.0737894121 0.1595018059 0.0281340899 0.0075590000 0.0004610000 0.0042920000 0.0000110000 0.0000090000 0.0019690000 14589617 96830484 509673472 3.9978909492 4.1012811661 4.1026120186 168 1305031235.0995910168 0.0685773864 0.0737583882 0.1595018059 0.0280595434 0.0067220000 0.0004290000 0.0041610000 0.0000010000 0.0000070000 0.0014900000 14593177 96830484 509673472 4.0002608299 4.0924229622 4.1053867340 169 1305031235.1362709999 0.0604714751 0.0736797674 0.1595018059 0.0280299285 0.0072290000 0.0004020000 0.0040830000 0.0000070000 0.0000060000 0.0022320000 14596961 96830484 509673472 4.0038509369 4.0793185234 4.1047434807 170 1305031235.1663711071 0.0560630746 0.0735761398 0.1595018059 0.0280160552 0.0060400000 0.0003880000 0.0040260000 0.0000010000 0.0000050000 0.0012600000 14600577 96830484 509673472 4.0024437904 4.0766782761 4.1086282730 171 1305031235.1998469830 0.0541360490 0.0734624550 0.1595018059 0.0279415297 0.0083160000 0.0006140000 0.0047500000 0.0000160000 0.0000140000 0.0019700000 14604193 96830484 509673472 4.0057406425 4.0721712112 4.1154694557 172 1305031235.2375700474 0.0503902957 0.0733283146 0.1595018059 0.0279321030 0.0063830000 0.0004660000 0.0040890000 0.0000010000 0.0000070000 0.0013010000 14608033 96830484 509673472 4.0042943954 4.0716423988 4.1189613342 173 1305031235.2690389156 0.0476920083 0.0731801278 0.1595018059 0.0278530493 0.0086450000 0.0005470000 0.0047580000 0.0000100000 0.0000100000 0.0024670000 14611705 96830484 509673472 4.0027723312 4.0716514587 4.1241989136 174 1305031235.3064870834 0.0444318056 0.0730149076 0.1595018059 0.0278806381 0.0064760000 0.0004240000 0.0044070000 0.0000010000 0.0000070000 0.0012120000 14615545 96830484 509673472 3.9991221428 4.0754489899 4.1287522316 175 1305031235.3380000591 0.0361154340 0.0728040534 0.1595018059 0.0278029252 0.0060560000 0.0004600000 0.0034330000 0.0000080000 0.0000070000 0.0015130000 14619161 96830484 509673472 3.9909434319 4.0761723518 4.1291909218 176 1305031235.3698880672 0.0271286853 0.0725445343 0.1595018059 0.0277702276 0.0075040000 0.0005340000 0.0047230000 0.0000010000 0.0000100000 0.0013770000 14622833 96830484 509673472 3.9817500114 4.0752258301 4.1246113777 177 1305031235.4060161114 0.0220075957 0.0722590149 0.1595018059 0.0278121225 0.0072640000 0.0004260000 0.0044790000 0.0000080000 0.0000070000 0.0018280000 14626617 96830484 509673472 3.9766359329 4.0747194290 4.1230812073 178 1305031235.4381530285 0.0191871710 0.0719608585 0.1595018059 0.0277658851 0.0050810000 0.0004630000 0.0027970000 0.0000010000 0.0000070000 0.0011590000 14630289 96830484 509673472 3.9685297012 4.0773820877 4.1233334541 179 1305031235.4700589180 0.0202860702 0.0716721725 0.1595018059 0.0277572675 0.0073920000 0.0004710000 0.0045940000 0.0000110000 0.0000090000 0.0014440000 14633961 96830484 509673472 3.9641029835 4.0682501793 4.1164774895 180 1305031235.5059850216 0.0248021148 0.0714117833 0.1595018059 0.0276911197 0.0055150000 0.0004250000 0.0033940000 0.0000010000 0.0000090000 0.0010270000 14637745 96830484 509673472 3.9594271183 4.0662269592 4.1160016060 181 1305031235.5385539532 0.0252091847 0.0711565203 0.1595018059 0.0276230184 0.0047460000 0.0004010000 0.0022950000 0.0000060000 0.0000060000 0.0015100000 14641417 96830484 509673472 3.9592154026 4.0643353462 4.1180815697 182 1305031235.5703649521 0.0269326717 0.0709135321 0.1595018059 0.0275576260 0.0044460000 0.0004010000 0.0026680000 0.0000010000 0.0000060000 0.0008430000 14645089 96830484 509673472 3.9614031315 4.0596957207 4.1207866669 183 1305031235.6060059071 0.0316162296 0.0706987928 0.1595018059 0.0275168315 0.0081880000 0.0005460000 0.0047830000 0.0000150000 0.0000210000 0.0015070000 14648929 96830484 509673472 3.9570870399 4.0589151382 4.1229109764 184 1305031235.6389510632 0.0381580144 0.0705219407 0.1595018059 0.0274744935 0.0060800000 0.0005320000 0.0029550000 0.0000020000 0.0000160000 0.0012480000 14652601 96830484 509673472 3.9553549290 4.0535931587 4.1245360374 185 1305031235.6705160141 0.0425365046 0.0703706681 0.1595018059 0.0274077822 0.0061060000 0.0004600000 0.0035110000 0.0000080000 0.0000070000 0.0014510000 14656217 96830484 509673472 3.9534156322 4.0514397621 4.1274614334 186 1305031235.7057778835 0.0466278829 0.0702430187 0.1595018059 0.0273338595 0.0079260000 0.0005470000 0.0047570000 0.0000020000 0.0000150000 0.0012770000 14660001 96830484 509673472 3.9587800503 4.0468025208 4.1348166466 187 1305031235.7387969494 0.0543394722 0.0701579730 0.1595018059 0.0272949340 0.0050390000 0.0004600000 0.0027520000 0.0000090000 0.0000070000 0.0011370000 14663729 96830484 509673472 3.9563422203 4.0422925949 4.1383242607 188 1305031235.7696299553 0.0600403287 0.0701041557 0.1595018059 0.0272322791 0.0061400000 0.0003990000 0.0043640000 0.0000010000 0.0000060000 0.0008310000 14667345 96830484 509673472 3.9518446922 4.0411729813 4.1408333778 189 1305031235.8072249889 0.0703912675 0.0701056748 0.1595018059 0.0271728783 0.0079300000 0.0005490000 0.0039570000 0.0000160000 0.0000140000 0.0020400000 14671297 96830484 509673472 3.9472937584 4.0369029045 4.1423058510 190 1305031235.8388121128 0.0771097615 0.0701425385 0.1595018059 0.0271310497 0.0058980000 0.0004600000 0.0034920000 0.0000020000 0.0000100000 0.0010200000 14674969 96830484 509673472 3.9453060627 4.0336894989 4.1466202736 191 1305031235.8700668812 0.0834789500 0.0702123626 0.1595018059 0.0270892355 0.0052420000 0.0004250000 0.0030040000 0.0000070000 0.0000080000 0.0011140000 14678697 96830484 509673472 3.9427998066 4.0312366486 4.1504640579 192 1305031235.9061110020 0.0904471651 0.0703177522 0.1595018059 0.0270230316 0.0054390000 0.0004240000 0.0034260000 0.0000010000 0.0000070000 0.0008850000 14682537 96830484 509673472 3.9424252510 4.0285325050 4.1550655365 193 1305031235.9382328987 0.1000333056 0.0704717188 0.1595018059 0.0269800492 0.0071620000 0.0004260000 0.0044040000 0.0000090000 0.0000070000 0.0016100000 14686321 96830484 509673472 3.9425292015 4.0219292641 4.1600732803 194 1305031235.9700109959 0.1031953618 0.0706403974 0.1595018059 0.0269141772 0.0065580000 0.0004240000 0.0045270000 0.0000010000 0.0000070000 0.0008980000 14689993 96830484 509673472 3.9384655952 4.0234107971 4.1620721817 195 1305031236.0068531036 0.1125479117 0.0708553077 0.1595018059 0.0268548813 0.0064710000 0.0005560000 0.0036880000 0.0000160000 0.0000140000 0.0012610000 14693889 96830484 509673472 3.9404580593 4.0176839828 4.1703205109 196 1305031236.0380480289 0.1178177744 0.0710949121 0.1595018059 0.0267926769 0.0064430000 0.0004260000 0.0044980000 0.0000010000 0.0000080000 0.0009270000 14697561 96830484 509673472 3.9361939430 4.0171155930 4.1715569496 197 1305031236.0698781013 0.1266199797 0.0713767653 0.1595018059 0.0267985676 0.0084910000 0.0005490000 0.0047900000 0.0000150000 0.0000130000 0.0020970000 14701289 96830484 509673472 3.9313144684 4.0128183365 4.1745333672 198 1305031236.1058719158 0.1314004362 0.0716799151 0.1595018059 0.0267398021 0.0063490000 0.0004320000 0.0044870000 0.0000010000 0.0000060000 0.0008700000 14705129 96830484 509673472 3.9312813282 4.0115799904 4.1787791252 199 1305031236.1383249760 0.1359376609 0.0720028184 0.1595018059 0.0266793924 0.0059630000 0.0003850000 0.0040170000 0.0000060000 0.0000060000 0.0010930000 14708913 96830484 509673472 3.9280388355 4.0102863312 4.1801857948 200 1305031236.1709330082 0.1373114586 0.0723293616 0.1595018059 0.0266130961 0.0059870000 0.0003780000 0.0043810000 0.0000010000 0.0000050000 0.0008240000 14712641 96830484 509673472 3.9295091629 4.0111751556 4.1844515800 201 1305031236.2071900368 0.1393360198 0.0726627280 0.1595018059 0.0265545697 0.0089100000 0.0005430000 0.0048170000 0.0000160000 0.0000140000 0.0021300000 14716537 96830484 509673472 3.9288263321 4.0116863251 4.1863603592 202 1305031236.2383749485 0.1437196434 0.0730144949 0.1595018059 0.0265287093 0.0073540000 0.0005490000 0.0048180000 0.0000010000 0.0000110000 0.0010400000 14720265 96830484 509673472 3.9280254841 4.0083522797 4.1904721260 203 1305031236.2699589729 0.1469462514 0.0733786908 0.1595018059 0.0264647606 0.0066150000 0.0004250000 0.0045170000 0.0000060000 0.0000050000 0.0010950000 14723937 96830484 509673472 3.9277174473 4.0050463676 4.1924133301 204 1305031236.3069939613 0.1473843157 0.0737414634 0.1595018059 0.0264476778 0.0053340000 0.0004230000 0.0034970000 0.0000010000 0.0000070000 0.0008410000 14727833 96830484 509673472 3.9291141033 4.0024628639 4.1938347816 205 1305031236.3392169476 0.1491323262 0.0741092237 0.1595018059 0.0263903486 0.0081930000 0.0005460000 0.0049190000 0.0000160000 0.0000160000 0.0017550000 14731561 96830484 509673472 3.9312691689 3.9982295036 4.1946420670 206 1305031236.3700959682 0.1461962759 0.0744591609 0.1595018059 0.0263329050 0.0064100000 0.0004270000 0.0045820000 0.0000010000 0.0000060000 0.0008130000 14735233 96830484 509673472 3.9326515198 3.9976325035 4.1904196739 207 1305031236.4058690071 0.1395165175 0.0747734476 0.1595018059 0.0263137993 0.0076540000 0.0005460000 0.0048940000 0.0000100000 0.0000100000 0.0012260000 14739073 96830484 509673472 3.9369559288 3.9987573624 4.1863064766 208 1305031236.4387879372 0.1316412389 0.0750468505 0.1595018059 0.0262532093 0.0063110000 0.0004240000 0.0045470000 0.0000010000 0.0000060000 0.0007970000 14742801 96830484 509673472 3.9429912567 4.0007176399 4.1810173988 209 1305031236.4751410484 0.1225840822 0.0752743014 0.1595018059 0.0261951563 0.0068130000 0.0003890000 0.0045120000 0.0000060000 0.0000050000 0.0014110000 14746697 96830484 509673472 3.9486157894 4.0034985542 4.1748757362 210 1305031236.5077209473 0.1151864976 0.0754643594 0.1595018059 0.0261391567 0.0066290000 0.0005460000 0.0034230000 0.0000020000 0.0000150000 0.0012000000 14750481 96830484 509673472 3.9521315098 4.0054769516 4.1689252853 211 1305031236.5386450291 0.1116565317 0.0756358863 0.1595018059 0.0260928580 0.0071240000 0.0004830000 0.0047150000 0.0000080000 0.0000070000 0.0011460000 14754153 96830484 509673472 3.9500792027 4.0042014122 4.1589879990 212 1305031236.5740950108 0.1038471237 0.0757689582 0.1595018059 0.0260370161 0.0063890000 0.0004020000 0.0045780000 0.0000010000 0.0000060000 0.0007950000 14757993 96830484 509673472 3.9495344162 4.0059323311 4.1501026154 213 1305031236.6057569981 0.1032345667 0.0758979047 0.1595018059 0.0259773513 0.0079220000 0.0005600000 0.0038090000 0.0000160000 0.0000160000 0.0020220000 14761665 96830484 509673472 3.9509367943 4.0015039444 4.1451373100 214 1305031236.6384010315 0.0979669243 0.0760010310 0.1595018059 0.0259551020 0.0061120000 0.0004610000 0.0039470000 0.0000020000 0.0000110000 0.0009170000 14765393 96830484 509673472 3.9529051781 4.0021691322 4.1383886337 215 1305031236.6751470566 0.0918224454 0.0760746189 0.1595018059 0.0259100849 0.0058430000 0.0004040000 0.0037830000 0.0000060000 0.0000060000 0.0010310000 14769177 96830484 509673472 3.9542632103 4.0023546219 4.1319861412 216 1305031236.7033619881 0.0877279863 0.0761285697 0.1595018059 0.0258540258 0.0063460000 0.0005490000 0.0029920000 0.0000020000 0.0000150000 0.0012510000 14772737 96830484 509673472 3.9616038799 4.0013818741 4.1294097900 217 1305031236.7339220047 0.0787607357 0.0761406995 0.1595018059 0.0258329313 0.0061040000 0.0004710000 0.0031830000 0.0000100000 0.0000090000 0.0016560000 14776353 96830484 509673472 3.9613115788 4.0072731972 4.1182775497 218 1305031236.7740409374 0.0716851354 0.0761202611 0.1595018059 0.0257985055 0.0055540000 0.0004310000 0.0034360000 0.0000010000 0.0000080000 0.0008920000 14780249 96830484 509673472 3.9615685940 4.0095620155 4.1100516319 219 1305031236.8025879860 0.0698568374 0.0760916610 0.1595018059 0.0258537644 0.0054390000 0.0004320000 0.0030710000 0.0000080000 0.0000070000 0.0011240000 14783921 96830484 509673472 3.9616441727 4.0105352402 4.1009459496 220 1305031236.8364150524 0.0615557469 0.0760255887 0.1595018059 0.0257974758 0.0048230000 0.0004320000 0.0027300000 0.0000010000 0.0000090000 0.0008590000 14787593 96830484 509673472 3.9640836716 4.0149526596 4.0941257477 221 1305031236.8743979931 0.0566943511 0.0759381170 0.1595018059 0.0257532989 0.0072710000 0.0004300000 0.0045430000 0.0000080000 0.0000070000 0.0014830000 14791433 96830484 509673472 3.9645218849 4.0160398483 4.0862960815 222 1305031236.9060690403 0.0542858168 0.0758405842 0.1595018059 0.0257431614 0.0066840000 0.0004250000 0.0045600000 0.0000010000 0.0000080000 0.0008930000 14795105 96830484 509673472 3.9667890072 4.0169506073 4.0791072845 223 1305031236.9344370365 0.0522622578 0.0757348517 0.1595018059 0.0257004431 0.0058920000 0.0004300000 0.0034730000 0.0000080000 0.0000070000 0.0011760000 14798665 96830484 509673472 3.9694533348 4.0180330276 4.0732107162 224 1305031236.9744000435 0.0474914238 0.0756087650 0.1595018059 0.0256460756 0.0049530000 0.0004240000 0.0027420000 0.0000010000 0.0000080000 0.0009770000 14802505 96830484 509673472 3.9724662304 4.0206451416 4.0679941177 225 1305031237.0074260235 0.0473210439 0.0754830418 0.1595018059 0.0256007957 0.0063910000 0.0004220000 0.0034330000 0.0000090000 0.0000070000 0.0017200000 14806289 96830484 509673472 3.9817748070 4.0230383873 4.0661082268 226 1305031237.0370240211 0.0477480851 0.0753603208 0.1595018059 0.0255763668 0.0054040000 0.0004210000 0.0030790000 0.0000000000 0.0000080000 0.0010910000 14809905 96830484 509673472 3.9867432117 4.0278010368 4.0624575615 227 1305031237.0734269619 0.0500588864 0.0752488607 0.1595018059 0.0255231364 0.0056750000 0.0004310000 0.0030640000 0.0000080000 0.0000070000 0.0013490000 14813633 96830484 509673472 3.9914934635 4.0286064148 4.0586557388 228 1305031237.1059679985 0.0560274795 0.0751645564 0.1595018059 0.0254817953 0.0072560000 0.0005490000 0.0033860000 0.0000020000 0.0000170000 0.0016930000 14817361 96830484 509673472 3.9991385937 4.0289831161 4.0566763878 229 1305031237.1378319263 0.0633994564 0.0751131804 0.1595018059 0.0254371580 0.0072270000 0.0005460000 0.0033390000 0.0000150000 0.0000130000 0.0022220000 14821033 96830484 509673472 4.0078744888 4.0303034782 4.0542712212 230 1305031237.1712269783 0.0691023096 0.0750870462 0.1595018059 0.0254836630 0.0059890000 0.0004230000 0.0037350000 0.0000010000 0.0000070000 0.0011600000 14824761 96830484 509673472 4.0147109032 4.0374360085 4.0551948547 231 1305031237.2042291164 0.0756042078 0.0750892850 0.1595018059 0.0254853380 0.0084190000 0.0006170000 0.0044480000 0.0000170000 0.0000140000 0.0021070000 14828377 96830484 509673472 4.0218577385 4.0356192589 4.0520620346 232 1305031237.2375690937 0.0836125910 0.0751260234 0.1595018059 0.0254628828 0.0054260000 0.0004340000 0.0030520000 0.0000010000 0.0000080000 0.0012640000 14832161 96830484 509673472 4.0293717384 4.0370807648 4.0498652458 233 1305031237.2746589184 0.0854151621 0.0751701828 0.1595018059 0.0254300232 0.0064090000 0.0003910000 0.0033290000 0.0000060000 0.0000050000 0.0021100000 14835945 96830484 509673472 4.0303826332 4.0381350517 4.0432705879 234 1305031237.3058099747 0.0877825320 0.0752240817 0.1595018059 0.0253815648 0.0052410000 0.0003900000 0.0030130000 0.0000010000 0.0000050000 0.0012690000 14839617 96830484 509673472 4.0314922333 4.0387988091 4.0350494385 235 1305031237.3371419907 0.0896976516 0.0752856714 0.1595018059 0.0253638729 0.0075510000 0.0005350000 0.0030370000 0.0000160000 0.0000140000 0.0022900000 14843289 96830484 509673472 4.0311670303 4.0386362076 4.0265960693 236 1305031237.3741660118 0.0910302028 0.0753523855 0.1595018059 0.0253297542 0.0064610000 0.0004740000 0.0035480000 0.0000010000 0.0000100000 0.0015920000 14847017 96830484 509673472 4.0288505554 4.0423545837 4.0171027184 237 1305031237.4057340622 0.0905741379 0.0754166123 0.1595018059 0.0253289411 0.0074160000 0.0004030000 0.0041010000 0.0000060000 0.0000050000 0.0022520000 14850745 96830484 509673472 4.0235619545 4.0514764786 4.0124745369 238 1305031237.4377219677 0.0953595564 0.0755004062 0.1595018059 0.0253250751 0.0073230000 0.0005490000 0.0029950000 0.0000020000 0.0000150000 0.0020850000 14854417 96830484 509673472 4.0255122185 4.0555477142 4.0091285706 239 1305031237.4741280079 0.0967866108 0.0755894698 0.1595018059 0.0252938131 0.0077320000 0.0004600000 0.0046280000 0.0000080000 0.0000070000 0.0017860000 14858145 96830484 509673472 4.0214271545 4.0615410805 4.0024991035 240 1305031237.5060451031 0.0992693678 0.0756881360 0.1595018059 0.0252784959 0.0058740000 0.0004030000 0.0034270000 0.0000010000 0.0000060000 0.0014690000 14861873 96830484 509673472 4.0175194740 4.0717325211 4.0027174950 241 1305031237.5376501083 0.1013145372 0.0757944696 0.1595018059 0.0252334715 0.0070280000 0.0003860000 0.0037130000 0.0000060000 0.0000050000 0.0023440000 14865545 96830484 509673472 4.0188689232 4.0721673965 3.9979414940 242 1305031237.5739479065 0.1019850597 0.0759026952 0.1595018059 0.0251937811 0.0052860000 0.0003780000 0.0030220000 0.0000010000 0.0000050000 0.0013920000 14869273 96830484 509673472 4.0138831139 4.0747737885 3.9917242527 243 1305031237.6068129539 0.1071506590 0.0760312877 0.1595018059 0.0251663034 0.0095850000 0.0005450000 0.0048790000 0.0000160000 0.0000130000 0.0025130000 14873057 96830484 509673472 4.0136170387 4.0863780975 3.9970831871 244 1305031237.6378550529 0.1095441952 0.0761686356 0.1595018059 0.0251233514 0.0062940000 0.0004600000 0.0031950000 0.0000010000 0.0000100000 0.0017700000 14876673 96830484 509673472 4.0129294395 4.0902810097 3.9964516163 245 1305031237.6752760410 0.1129650176 0.0763188250 0.1595018059 0.0250879956 0.0069670000 0.0004020000 0.0033870000 0.0000070000 0.0000070000 0.0024560000 14880457 96830484 509673472 4.0092329979 4.0972537994 3.9977834225 246 1305031237.7071180344 0.1139585674 0.0764718320 0.1595018059 0.0250394964 0.0068580000 0.0003870000 0.0044180000 0.0000010000 0.0000060000 0.0014560000 14884185 96830484 509673472 4.0069541931 4.0994415283 3.9968953133 247 1305031237.7416670322 0.1156687215 0.0766305239 0.1595018059 0.0250196583 0.0095960000 0.0005480000 0.0048610000 0.0000160000 0.0000160000 0.0025560000 14887913 96830484 509673472 4.0039176941 4.1049318314 4.0010643005 248 1305031237.7743060589 0.1154065952 0.0767868790 0.1595018059 0.0250535389 0.0071830000 0.0004230000 0.0045140000 0.0000010000 0.0000080000 0.0015370000 14891529 96830484 509673472 4.0078945160 4.1013669968 4.0001578331 249 1305031237.8064959049 0.1130715981 0.0769326008 0.1595018059 0.0250108577 0.0076180000 0.0003880000 0.0043970000 0.0000040000 0.0000040000 0.0023320000 14895257 96830484 509673472 4.0039110184 4.0992717743 3.9946055412 250 1305031237.8430309296 0.1179247350 0.0770965693 0.1595018059 0.0250949806 0.0047620000 0.0003690000 0.0026280000 0.0000010000 0.0000030000 0.0013740000 14899097 96830484 509673472 4.0013451576 4.1088118553 4.0043730736 251 1305031237.8754220009 0.1150261015 0.0772476830 0.1595018059 0.0252873971 0.0089950000 0.0005480000 0.0041720000 0.0000170000 0.0000130000 0.0025500000 14902713 96830484 509673472 4.0070366859 4.1012353897 4.0004763603 252 1305031237.9077839851 0.1119986698 0.0773855837 0.1595018059 0.0252538285 0.0063840000 0.0004660000 0.0034920000 0.0000010000 0.0000090000 0.0016420000 14906441 96830484 509673472 4.0036587715 4.0976071358 3.9942247868 253 1305031237.9441869259 0.1201216802 0.0775545011 0.1595018059 0.0254290916 0.0079490000 0.0005550000 0.0033420000 0.0000110000 0.0000090000 0.0028800000 14910225 96830484 509673472 4.0058517456 4.1105561256 4.0110926628 254 1305031237.9738099575 0.1220720485 0.0777297670 0.1595018059 0.0253956688 0.0061150000 0.0004260000 0.0034830000 0.0000010000 0.0000070000 0.0015020000 14913729 96830484 509673472 4.0129613876 4.1094927788 4.0190048218 255 1305031238.0069320202 0.1197007000 0.0778943589 0.1595018059 0.0253607056 0.0065830000 0.0003900000 0.0040630000 0.0000050000 0.0000050000 0.0016150000 14917513 96830484 509673472 4.0172557831 4.1046810150 4.0257263184 256 1305031238.0431399345 0.1203415021 0.0780601681 0.1595018059 0.0255413446 0.0078520000 0.0005490000 0.0033650000 0.0000020000 0.0000150000 0.0021820000 14921297 96830484 509673472 4.0275177956 4.0991597176 4.0379500389 257 1305031238.0740320683 0.1127251834 0.0781950514 0.1595018059 0.0255730513 0.0076810000 0.0004730000 0.0038470000 0.0000080000 0.0000070000 0.0024410000 14949489 96830484 509673472 4.0330481529 4.0836882591 4.0407490730 258 1305031238.1065878868 0.1033147201 0.0782924145 0.1595018059 0.0255947694 0.0074540000 0.0005440000 0.0040170000 0.0000020000 0.0000150000 0.0016920000 15004361 96830484 509673472 4.0355987549 4.0659365654 4.0419721603 259 1305031238.1433279514 0.1013928801 0.0783816055 0.1595018059 0.0256465114 0.0059120000 0.0004230000 0.0030040000 0.0000090000 0.0000060000 0.0017040000 15008145 96830484 509673472 4.0378351212 4.0583910942 4.0485248566 260 1305031238.1723001003 0.0971533433 0.0784538045 0.1595018059 0.0256220894 0.0062590000 0.0004580000 0.0036290000 0.0000010000 0.0000080000 0.0013390000 15011817 96830484 509673472 4.0310087204 4.0629391670 4.0604109764 261 1305031238.2054259777 0.0962079689 0.0785218281 0.1595018059 0.0264188845 0.0091390000 0.0005940000 0.0046830000 0.0000010000 0.0000150000 0.0026200000 15015433 96830484 509673472 4.0310087204 4.0629391670 4.0604109764 262 1305031238.2401471138 0.0820396468 0.0785352549 0.1595018059 0.0268121068 0.0062670000 0.0004320000 0.0039120000 0.0000010000 0.0000060000 0.0011830000 15019217 96830484 509673472 4.0180311203 4.0581941605 4.0631332397 263 1305031238.2725269794 0.0690184012 0.0784990691 0.1595018059 0.0267691760 0.0058080000 0.0003850000 0.0035550000 0.0000060000 0.0000050000 0.0013340000 15022945 96830484 509673472 4.0041632652 4.0578165054 4.0590157509 264 1305031238.3060529232 0.0621151105 0.0784370087 0.1595018059 0.0269395160 0.0054930000 0.0003770000 0.0035480000 0.0000010000 0.0000050000 0.0010350000 15026617 96830484 509673472 3.9928514957 4.0650601387 4.0587701797 265 1305031238.3425960541 0.0506830327 0.0783322767 0.1595018059 0.0270065012 0.0063860000 0.0003750000 0.0038470000 0.0000050000 0.0000040000 0.0016240000 15030401 96830484 509673472 3.9841248989 4.0549855232 4.0523962975 266 1305031238.3741040230 0.0471240580 0.0782149525 0.1595018059 0.0269788977 0.0060350000 0.0003780000 0.0042100000 0.0000010000 0.0000040000 0.0009060000 15034073 96830484 509673472 3.9796221256 4.0491447449 4.0490412712 267 1305031238.4060359001 0.0441482253 0.0780873618 0.1595018059 0.0269299577 0.0049010000 0.0003800000 0.0028810000 0.0000050000 0.0000040000 0.0010980000 15037745 96830484 509673472 3.9774069786 4.0451750755 4.0514974594 268 1305031238.4434239864 0.0443121083 0.0779613347 0.1595018059 0.0268847206 0.0084890000 0.0005700000 0.0046840000 0.0000020000 0.0000160000 0.0013830000 15041529 96830484 509673472 3.9751949310 4.0407595634 4.0514850616 269 1305031238.4740819931 0.0450956151 0.0778391573 0.1595018059 0.0268485435 0.0080330000 0.0005550000 0.0036100000 0.0000150000 0.0000140000 0.0020770000 15045201 96830484 509673472 3.9750638008 4.0361948013 4.0541014671 270 1305031238.5058109760 0.0460528359 0.0777214302 0.1595018059 0.0268711485 0.0063700000 0.0004230000 0.0044020000 0.0000010000 0.0000060000 0.0007950000 15048873 96830484 509673472 3.9729876518 4.0308485031 4.0558815002 271 1305031238.5432639122 0.0499329045 0.0776188895 0.1595018059 0.0268234168 0.0049430000 0.0003850000 0.0029650000 0.0000060000 0.0000050000 0.0009610000 15052713 96830484 509673472 3.9703519344 4.0246801376 4.0563373566 272 1305031238.5741839409 0.0489345044 0.0775134322 0.1595018059 0.0267808750 0.0067000000 0.0005450000 0.0029580000 0.0000020000 0.0000170000 0.0012950000 15056273 96830484 509673472 3.9679155350 4.0249376297 4.0593562126 273 1305031238.6058249474 0.0505358726 0.0774146133 0.1595018059 0.0267355995 0.0077910000 0.0005460000 0.0032700000 0.0000160000 0.0000140000 0.0020670000 15060001 96830484 509673472 3.9640066624 4.0221824646 4.0609774590 274 1305031238.6427590847 0.0517022014 0.0773207724 0.1595018059 0.0266914509 0.0053830000 0.0004620000 0.0030580000 0.0000010000 0.0000080000 0.0009050000 15063841 96830484 509673472 3.9636549950 4.0209794044 4.0651235580 275 1305031238.6738131046 0.0546089374 0.0772381839 0.1595018059 0.0266485913 0.0066710000 0.0005430000 0.0029830000 0.0000180000 0.0000130000 0.0015040000 15067401 96830484 509673472 3.9602715969 4.0200457573 4.0664167404 276 1305031238.7051889896 0.0548214689 0.0771569640 0.1595018059 0.0266014277 0.0083210000 0.0005400000 0.0047740000 0.0000020000 0.0000150000 0.0012830000 15071073 96830484 509673472 3.9584932327 4.0213093758 4.0690402985 277 1305031238.7413070202 0.0593254492 0.0770925903 0.1595018059 0.0265908020 0.0053220000 0.0004200000 0.0026900000 0.0000080000 0.0000070000 0.0014330000 15074913 96830484 509673472 3.9554634094 4.0175914764 4.0704054832 278 1305031238.7717959881 0.0642542541 0.0770464092 0.1595018059 0.0265705049 0.0054800000 0.0003880000 0.0036860000 0.0000010000 0.0000060000 0.0007660000 15078585 96830484 509673472 3.9518938065 4.0140180588 4.0707654953 279 1305031238.8070189953 0.0662698448 0.0770077835 0.1595018059 0.0265460339 0.0073360000 0.0005460000 0.0033890000 0.0000160000 0.0000130000 0.0014400000 15082369 96830484 509673472 3.9496772289 4.0151329041 4.0719952583 280 1305031238.8429400921 0.0690525770 0.0769793721 0.1595018059 0.0265023045 0.0083280000 0.0005480000 0.0048740000 0.0000020000 0.0000150000 0.0012320000 15086209 96830484 509673472 3.9492831230 4.0130381584 4.0760149956 281 1305031238.8737230301 0.0785409585 0.0769849293 0.1595018059 0.0265095555 0.0071780000 0.0004240000 0.0045270000 0.0000060000 0.0000050000 0.0014370000 15089937 96830484 509673472 3.9495582581 4.0046706200 4.0797200203 282 1305031238.9061720371 0.0835858583 0.0770083369 0.1595018059 0.0264758380 0.0055620000 0.0003870000 0.0037730000 0.0000000000 0.0000050000 0.0007670000 15093609 96830484 509673472 3.9504060745 4.0004382133 4.0834288597 283 1305031238.9427859783 0.0844715238 0.0770347085 0.1595018059 0.0264293402 0.0082840000 0.0005320000 0.0049090000 0.0000160000 0.0000130000 0.0014440000 15097505 96830484 509673472 3.9483816624 4.0011816025 4.0828256607 284 1305031238.9723079205 0.0895406306 0.0770787435 0.1595018059 0.0263919380 0.0066000000 0.0004230000 0.0045730000 0.0000000000 0.0000060000 0.0008120000 15101177 96830484 509673472 3.9500744343 3.9967601299 4.0877699852 285 1305031239.0104830265 0.0908020437 0.0771268954 0.1595018059 0.0263677955 0.0066500000 0.0004620000 0.0036200000 0.0000100000 0.0000090000 0.0015620000 15105073 96830484 509673472 3.9489259720 3.9975075722 4.0870299339 286 1305031239.0408790112 0.0938463733 0.0771853551 0.1595018059 0.0263276880 0.0065480000 0.0004030000 0.0045280000 0.0000000000 0.0000060000 0.0008120000 15108745 96830484 509673472 3.9474992752 3.9954578876 4.0885882378 287 1305031239.0746610165 0.1013789177 0.0772696532 0.1595018059 0.0263284068 0.0057930000 0.0004120000 0.0034710000 0.0000080000 0.0000060000 0.0010760000 15112529 96830484 509673472 3.9482641220 3.9885780811 4.0932822227 288 1305031239.1109058857 0.1042687297 0.0773634000 0.1595018059 0.0262829584 0.0084130000 0.0005500000 0.0049320000 0.0000010000 0.0000150000 0.0012540000 15116425 96830484 509673472 3.9480323792 3.9859652519 4.0941758156 289 1305031239.1417789459 0.1055776700 0.0774610273 0.1595018059 0.0262486443 0.0074850000 0.0004620000 0.0043680000 0.0000080000 0.0000060000 0.0016120000 15120097 96830484 509673472 3.9470679760 3.9841091633 4.0940537453 290 1305031239.1757500172 0.1058664620 0.0775589770 0.1595018059 0.0262393307 0.0053420000 0.0004040000 0.0034650000 0.0000000000 0.0000050000 0.0007780000 15123881 96830484 509673472 3.9456858635 3.9831085205 4.0899720192 291 1305031239.2096450329 0.1025162190 0.0776447408 0.1595018059 0.0262029102 0.0076110000 0.0004730000 0.0047160000 0.0000110000 0.0000100000 0.0012300000 15127665 96830484 509673472 3.9465994835 3.9860284328 4.0877413750 292 1305031239.2417099476 0.1025339589 0.0777299778 0.1595018059 0.0261758393 0.0059180000 0.0004260000 0.0035460000 0.0000010000 0.0000070000 0.0009000000 15131393 96830484 509673472 3.9451484680 3.9851312637 4.0846762657 293 1305031239.2738199234 0.1000648737 0.0778062061 0.1595018059 0.0261505006 0.0073300000 0.0004140000 0.0045580000 0.0000070000 0.0000050000 0.0014970000 15135121 96830484 509673472 3.9460630417 3.9862453938 4.0824151039 294 1305031239.3101770878 0.0984734073 0.0778765027 0.1595018059 0.0261067612 0.0065730000 0.0004110000 0.0045510000 0.0000010000 0.0000060000 0.0008170000 15139017 96830484 509673472 3.9460837841 3.9868750572 4.0795497894 295 1305031239.3419699669 0.0950259939 0.0779346366 0.1595018059 0.0260679620 0.0083490000 0.0005650000 0.0049220000 0.0000180000 0.0000140000 0.0014280000 15142745 96830484 509673472 3.9474425316 3.9892711639 4.0772643089 296 1305031239.3750240803 0.0918484554 0.0779816427 0.1595018059 0.0260377496 0.0066900000 0.0004320000 0.0045960000 0.0000000000 0.0000060000 0.0008090000 15146417 96830484 509673472 3.9482157230 3.9909591675 4.0745749474 297 1305031239.4106309414 0.0877915099 0.0780146726 0.1595018059 0.0259951007 0.0095120000 0.0005460000 0.0049090000 0.0000160000 0.0000150000 0.0020340000 15150201 96830484 509673472 3.9490776062 3.9939532280 4.0720934868 298 1305031239.4415419102 0.0880133957 0.0780482254 0.1595018059 0.0259543816 0.0066250000 0.0004320000 0.0045320000 0.0000010000 0.0000070000 0.0008060000 15153873 96830484 509673472 3.9511559010 3.9922821522 4.0710778236 299 1305031239.4733181000 0.0802654475 0.0780556408 0.1595018059 0.0259145160 0.0064170000 0.0003840000 0.0044170000 0.0000050000 0.0000050000 0.0009990000 15157545 96830484 509673472 3.9525175095 3.9990727901 4.0682806969 300 1305031239.5097389221 0.0746869519 0.0780444119 0.1595018059 0.0258768042 0.0059790000 0.0003650000 0.0043190000 0.0000010000 0.0000040000 0.0007540000 15161329 96830484 509673472 3.9555151463 4.0041632652 4.0660686493 301 1305031239.5438020229 0.0710306466 0.0780211103 0.1595018059 0.0258422645 0.0059030000 0.0003680000 0.0036250000 0.0000040000 0.0000030000 0.0013640000 15165113 96830484 509673472 3.9564175606 4.0068216324 4.0626649857 302 1305031239.5761160851 0.0688878596 0.0779908678 0.1595018059 0.0258073631 0.0076520000 0.0005440000 0.0036990000 0.0000020000 0.0000150000 0.0012690000 15168785 96830484 509673472 3.9573717117 4.0085468292 4.0597829819 303 1305031239.6111609936 0.0672582835 0.0779554467 0.1595018059 0.0257683790 0.0078010000 0.0005300000 0.0036910000 0.0000150000 0.0000130000 0.0014930000 15172569 96830484 509673472 3.9586479664 4.0099992752 4.0568184853 304 1305031239.6414220333 0.0671109036 0.0779197738 0.1595018059 0.0257289475 0.0065970000 0.0004590000 0.0041560000 0.0000010000 0.0000090000 0.0009030000 15176185 96830484 509673472 3.9596464634 4.0099287033 4.0533933640 305 1305031239.6710560322 0.0639117807 0.0778738460 0.1595018059 0.0257022036 0.0068110000 0.0004030000 0.0043410000 0.0000060000 0.0000050000 0.0013320000 15179745 96830484 509673472 3.9597408772 4.0134720802 4.0499505997 306 1305031239.7075550556 0.0626698211 0.0778241596 0.1595018059 0.0256975169 0.0074420000 0.0004730000 0.0045820000 0.0000010000 0.0000120000 0.0010090000 15183529 96830484 509673472 3.9656627178 4.0143618584 4.0494165421 307 1305031239.7417550087 0.0630739480 0.0777761134 0.1595018059 0.0256568682 0.0086660000 0.0005480000 0.0048330000 0.0000160000 0.0000140000 0.0015310000 15187313 96830484 509673472 3.9662189484 4.0135455132 4.0450973511 308 1305031239.7712600231 0.0630262345 0.0777282241 0.1595018059 0.0256168991 0.0070470000 0.0004570000 0.0045720000 0.0000010000 0.0000080000 0.0009230000 15190873 96830484 509673472 3.9729480743 4.0145077705 4.0448646545 309 1305031239.8060870171 0.0640990585 0.0776841168 0.1595018059 0.0256560201 0.0067000000 0.0003980000 0.0040540000 0.0000070000 0.0000050000 0.0015050000 15194601 96830484 509673472 3.9809174538 4.0142555237 4.0445904732 310 1305031239.8392889500 0.0594587810 0.0776253254 0.1595018059 0.0256684767 0.0055280000 0.0003740000 0.0036310000 0.0000010000 0.0000040000 0.0008880000 15198329 96830484 509673472 3.9806313515 4.0217199326 4.0418176651 311 1305031239.8744299412 0.0574117191 0.0775603299 0.1595018059 0.0256337723 0.0089640000 0.0005460000 0.0044260000 0.0000160000 0.0000130000 0.0017640000 15202001 96830484 509673472 3.9811182022 4.0253043175 4.0405135155 312 1305031239.9090619087 0.0597555935 0.0775032634 0.1595018059 0.0256375576 0.0072070000 0.0004580000 0.0045130000 0.0000010000 0.0000090000 0.0011240000 15205785 96830484 509673472 3.9873704910 4.0274806023 4.0413007736 313 1305031239.9403729439 0.0617297813 0.0774528689 0.1595018059 0.0256230004 0.0062870000 0.0004020000 0.0033640000 0.0000060000 0.0000050000 0.0017700000 15209401 96830484 509673472 3.9918200970 4.0312814713 4.0418057442 314 1305031239.9710669518 0.0653587803 0.0774143527 0.1595018059 0.0256360311 0.0042830000 0.0003770000 0.0022570000 0.0000000000 0.0000040000 0.0010100000 15213073 96830484 509673472 3.9976010323 4.0351576805 4.0443964005 315 1305031240.0088651180 0.0699692965 0.0773907176 0.1595018059 0.0256606768 0.0077070000 0.0005450000 0.0029310000 0.0000150000 0.0000140000 0.0019820000 15216969 96830484 509673472 4.0029215813 4.0329647064 4.0428557396 316 1305031240.0396599770 0.0762100816 0.0773869814 0.1595018059 0.0256265296 0.0061940000 0.0004630000 0.0027790000 0.0000010000 0.0000110000 0.0014530000 15220529 96830484 509673472 4.0099854469 4.0334696770 4.0425238609 317 1305031240.0711870193 0.0836327672 0.0774066842 0.1595018059 0.0255871356 0.0066380000 0.0004250000 0.0030370000 0.0000080000 0.0000070000 0.0021180000 15224201 96830484 509673472 4.0182247162 4.0319452286 4.0435757637 318 1305031240.1093459129 0.0898014084 0.0774456613 0.1595018059 0.0256002031 0.0085160000 0.0005500000 0.0043230000 0.0000020000 0.0000160000 0.0019500000 15228041 96830484 509673472 4.0249614716 4.0273480415 4.0400590897 319 1305031240.1435019970 0.0977509022 0.0775093141 0.1595018059 0.0256206762 0.0068000000 0.0004770000 0.0038170000 0.0000070000 0.0000060000 0.0015430000 15231825 96830484 509673472 4.0331583023 4.0219240189 4.0334630013 320 1305031240.1775770187 0.1010602042 0.0775829107 0.1595018059 0.0255919141 0.0084670000 0.0005500000 0.0047270000 0.0000010000 0.0000100000 0.0016560000 15235497 96830484 509673472 4.0364408493 4.0286855698 4.0335040092 321 1305031240.2093310356 0.1060720310 0.0776716618 0.1595018059 0.0256371473 0.0068950000 0.0004330000 0.0033830000 0.0000060000 0.0000050000 0.0022930000 15239225 96830484 509673472 4.0414509773 4.0287127495 4.0272159576 322 1305031240.2410049438 0.1081705466 0.0777663788 0.1595018059 0.0256234082 0.0070510000 0.0004630000 0.0038780000 0.0000010000 0.0000070000 0.0015640000 15242841 96830484 509673472 4.0411286354 4.0366001129 4.0184350014 323 1305031240.2774341106 0.1112432927 0.0778700225 0.1595018059 0.0255928081 0.0055140000 0.0004080000 0.0026900000 0.0000060000 0.0000050000 0.0016370000 15246625 96830484 509673472 4.0415902138 4.0509400368 4.0225701332 324 1305031240.3089289665 0.1120903194 0.0779756407 0.1595018059 0.0255662676 0.0059700000 0.0003890000 0.0033790000 0.0000010000 0.0000050000 0.0014240000 15250241 96830484 509673472 4.0376620293 4.0593900681 4.0141382217 325 1305031240.3422729969 0.1158326715 0.0780921239 0.1595018059 0.0255566608 0.0107330000 0.0005500000 0.0045110000 0.0000150000 0.0000130000 0.0033610000 15253969 96830484 509673472 4.0307254791 4.0790562630 4.0171737671 326 1305031240.3774259090 0.1225415766 0.0782284719 0.1595018059 0.0255700446 0.0068830000 0.0004620000 0.0035330000 0.0000010000 0.0000110000 0.0017230000 15257753 96830484 509673472 4.0233635902 4.0975675583 4.0202732086 327 1305031240.4091110229 0.1250451952 0.0783716423 0.1595018059 0.0255388411 0.0063270000 0.0004070000 0.0033830000 0.0000070000 0.0000050000 0.0017510000 15261369 96830484 509673472 4.0109004974 4.1103243828 4.0155715942 328 1305031240.4417860508 0.1351487041 0.0785447431 0.1595018059 0.0255090125 0.0061710000 0.0003800000 0.0036890000 0.0000000000 0.0000040000 0.0015150000 15265097 96830484 509673472 4.0023636818 4.1267952919 4.0203909874 329 1305031240.4776389599 0.1460087746 0.0787498010 0.1595018059 0.0254804574 0.0077030000 0.0003700000 0.0043060000 0.0000040000 0.0000040000 0.0024350000 15268881 96830484 509673472 3.9953234196 4.1415667534 4.0258245468 330 1305031240.5084490776 0.1516257226 0.0789706371 0.1595018059 0.0254554878 0.0086450000 0.0005480000 0.0037470000 0.0000020000 0.0000160000 0.0024570000 15272441 96830484 509673472 3.9921073914 4.1482191086 4.0261487961 331 1305031240.5412700176 0.1618200690 0.0792209375 0.1618200690 0.0254583192 0.0081830000 0.0004580000 0.0045230000 0.0000090000 0.0000070000 0.0020210000 15276169 96830484 509673472 3.9842185974 4.1608524323 4.0329723358 332 1305031240.5759088993 0.1677472293 0.0794875830 0.1677472293 0.0254329378 0.0068900000 0.0004020000 0.0043070000 0.0000010000 0.0000050000 0.0015050000 15279953 96830484 509673472 3.9851129055 4.1658720970 4.0385184288 333 1305031240.6101338863 0.1655390561 0.0797459958 0.1677472293 0.0254061525 0.0076200000 0.0003700000 0.0042760000 0.0000040000 0.0000030000 0.0024270000 15283681 96830484 509673472 3.9870266914 4.1632533073 4.0392208099 334 1305031240.6398229599 0.1619401574 0.0799920861 0.1677472293 0.0253914458 0.0066220000 0.0003650000 0.0042780000 0.0000010000 0.0000040000 0.0014370000 15287241 96830484 509673472 3.9917557240 4.1580715179 4.0416731834 335 1305031240.6747570038 0.1525259167 0.0802086050 0.1677472293 0.0253611831 0.0097710000 0.0005450000 0.0048200000 0.0000160000 0.0000140000 0.0026440000 15291025 96830484 509673472 4.0001616478 4.1460161209 4.0413222313 336 1305031240.7079319954 0.1470285505 0.0804074739 0.1677472293 0.0253571497 0.0064310000 0.0004420000 0.0034430000 0.0000010000 0.0000060000 0.0015810000 15294753 96830484 509673472 4.0029058456 4.1393995285 4.0436501503 337 1305031240.7439579964 0.1445571631 0.0805978290 0.1677472293 0.0253301597 0.0070230000 0.0003920000 0.0036490000 0.0000040000 0.0000040000 0.0023310000 15298425 96830484 509673472 4.0080509186 4.1354684830 4.0492749214 338 1305031240.7768330574 0.1330471486 0.0807530045 0.1677472293 0.0253020453 0.0052210000 0.0003690000 0.0029750000 0.0000000000 0.0000040000 0.0013370000 15302209 96830484 509673472 4.0126309395 4.1211500168 4.0444445610 339 1305031240.8096249104 0.1293193847 0.0808962682 0.1677472293 0.0252846203 0.0092320000 0.0005770000 0.0037450000 0.0000170000 0.0000130000 0.0024880000 15305881 96830484 509673472 4.0138707161 4.1167960167 4.0472168922 340 1305031240.8425960541 0.1246273965 0.0810248892 0.1677472293 0.0252692593 0.0075030000 0.0004670000 0.0042240000 0.0000020000 0.0000090000 0.0015960000 15309553 96830484 509673472 4.0176377296 4.1098651886 4.0518536568 341 1305031240.8794100285 0.1113608852 0.0811138510 0.1677472293 0.0252475787 0.0065290000 0.0004030000 0.0030400000 0.0000060000 0.0000040000 0.0022700000 15313393 96830484 509673472 4.0201468468 4.0922861099 4.0448460579 342 1305031240.9084498882 0.1044875160 0.0811821951 0.1677472293 0.0252301947 0.0070760000 0.0004870000 0.0038750000 0.0000020000 0.0000110000 0.0015260000 15317009 96830484 509673472 4.0198721886 4.0840849876 4.0460844040 343 1305031240.9423189163 0.0868286118 0.0811986569 0.1677472293 0.0252411248 0.0071160000 0.0004110000 0.0043450000 0.0000060000 0.0000050000 0.0015990000 15320681 96830484 509673472 4.0059199333 4.0736050606 4.0392446518 344 1305031240.9779360294 0.0773065016 0.0811873425 0.1677472293 0.0252161859 0.0083260000 0.0005520000 0.0036570000 0.0000020000 0.0000160000 0.0020820000 15324465 96830484 509673472 4.0044970512 4.0600314140 4.0371704102 345 1305031241.0083029270 0.0711672530 0.0811582988 0.1677472293 0.0253087531 0.0074350000 0.0004630000 0.0034470000 0.0000110000 0.0000100000 0.0022920000 15328081 96830484 509673472 4.0000238419 4.0600171089 4.0429039001 346 1305031241.0401480198 0.0665814877 0.0811161693 0.1677472293 0.0252885395 0.0066210000 0.0004000000 0.0042830000 0.0000010000 0.0000050000 0.0012140000 15331641 96830484 509673472 3.9970152378 4.0633912086 4.0547595024 347 1305031241.0759329796 0.0588211268 0.0810519184 0.1677472293 0.0252743200 0.0064880000 0.0003700000 0.0042390000 0.0000040000 0.0000030000 0.0013170000 15335481 96830484 509673472 3.9907791615 4.0613956451 4.0531888008 348 1305031241.1065559387 0.0527150966 0.0809704908 0.1677472293 0.0252469789 0.0082270000 0.0006070000 0.0043490000 0.0000010000 0.0000100000 0.0014460000 15339097 96830484 509673472 3.9834499359 4.0639424324 4.0567636490 349 1305031241.1400520802 0.0477855541 0.0808754050 0.1677472293 0.0252406961 0.0074580000 0.0004660000 0.0040400000 0.0000090000 0.0000070000 0.0019330000 15342769 96830484 509673472 3.9773876667 4.0648903847 4.0568737984 350 1305031241.1781818867 0.0430787355 0.0807674145 0.1677472293 0.0252438047 0.0063700000 0.0003890000 0.0042720000 0.0000010000 0.0000050000 0.0009870000 15346609 96830484 509673472 3.9748287201 4.0620226860 4.0570421219 351 1305031241.2106790543 0.0376964062 0.0806447051 0.1677472293 0.0252145094 0.0092310000 0.0005460000 0.0047070000 0.0000160000 0.0000130000 0.0018070000 15350337 96830484 509673472 3.9670999050 4.0586333275 4.0538973808 352 1305031241.2393150330 0.0374555103 0.0805220085 0.1677472293 0.0252567492 0.0067350000 0.0004290000 0.0043410000 0.0000010000 0.0000050000 0.0009610000 15353841 96830484 509673472 3.9678044319 4.0525584221 4.0530743599 353 1305031241.2768468857 0.0369967781 0.0803987076 0.1677472293 0.0252439794 0.0068370000 0.0003830000 0.0042810000 0.0000050000 0.0000040000 0.0014480000 15357737 96830484 509673472 3.9676074982 4.0489807129 4.0534272194 354 1305031241.3063299656 0.0356786251 0.0802723797 0.1677472293 0.0252099504 0.0071520000 0.0004560000 0.0044870000 0.0000000000 0.0000080000 0.0009520000 15361353 96830484 509673472 3.9656236172 4.0493893623 4.0549745560 355 1305031241.3424758911 0.0348824561 0.0801445207 0.1677472293 0.0251973807 0.0050960000 0.0003980000 0.0026160000 0.0000060000 0.0000060000 0.0010700000 15365137 96830484 509673472 3.9698483944 4.0470509529 4.0611524582 356 1305031241.3795149326 0.0400109366 0.0800317859 0.1677472293 0.0252371924 0.0080200000 0.0005460000 0.0036560000 0.0000020000 0.0000150000 0.0013240000 15368921 96830484 509673472 3.9675149918 4.0403623581 4.0606565475 357 1305031241.4096820354 0.0438859463 0.0799305371 0.1677472293 0.0252192039 0.0070810000 0.0004600000 0.0038050000 0.0000080000 0.0000070000 0.0015390000 15372537 96830484 509673472 3.9673457146 4.0376386642 4.0631237030 358 1305031241.4455459118 0.0470932946 0.0798388129 0.1677472293 0.0251978106 0.0063230000 0.0004030000 0.0043300000 0.0000000000 0.0000050000 0.0008010000 15376321 96830484 509673472 3.9673833847 4.0367693901 4.0680627823 359 1305031241.4775071144 0.0511322245 0.0797588503 0.1677472293 0.0253728914 0.0058020000 0.0005510000 0.0036860000 0.0000150000 0.0000130000 0.0009750000 15379993 96830484 509673472 3.9659650326 4.0328130722 4.0704598427 360 1305031241.5098490715 0.0553682595 0.0796910987 0.1677472293 0.0253691533 0.0073660000 0.0004550000 0.0042190000 0.0000010000 0.0000110000 0.0009980000 15383665 96830484 509673472 3.9618806839 4.0288228989 4.0691280365 361 1305031241.5477299690 0.0585770495 0.0796326110 0.1677472293 0.0253447134 0.0073850000 0.0004240000 0.0044910000 0.0000070000 0.0000060000 0.0014360000 15387561 96830484 509673472 3.9584598541 4.0262870789 4.0657439232 362 1305031241.5783948898 0.0584862493 0.0795741956 0.1677472293 0.0253265205 0.0057080000 0.0003920000 0.0036800000 0.0000000000 0.0000050000 0.0007700000 15391121 96830484 509673472 3.9600698948 4.0262541771 4.0669884682 363 1305031241.6092638969 0.0598288402 0.0795198007 0.1677472293 0.0253247313 0.0064230000 0.0003790000 0.0043370000 0.0000050000 0.0000050000 0.0009650000 15394737 96830484 509673472 3.9604482651 4.0248556137 4.0643930435 364 1305031241.6475839615 0.0625008568 0.0794730454 0.1677472293 0.0252946906 0.0091760000 0.0005420000 0.0047880000 0.0000020000 0.0000160000 0.0012670000 15398633 96830484 509673472 3.9609351158 4.0212116241 4.0619678497 365 1305031241.6783659458 0.0561827347 0.0794092363 0.1677472293 0.0253256449 0.0078960000 0.0004620000 0.0045680000 0.0000100000 0.0000090000 0.0015500000 15402305 96830484 509673472 3.9627175331 4.0276136398 4.0615649223 366 1305031241.7098269463 0.0555863380 0.0793441464 0.1677472293 0.0252975341 0.0057730000 0.0004620000 0.0031330000 0.0000010000 0.0000070000 0.0008850000 15405865 96830484 509673472 3.9627537727 4.0282053947 4.0592927933 367 1305031241.7471020222 0.0537125021 0.0792743054 0.1677472293 0.0252675227 0.0082720000 0.0005480000 0.0047350000 0.0000110000 0.0000090000 0.0012430000 15409761 96830484 509673472 3.9634532928 4.0295848846 4.0582871437 368 1305031241.7782680988 0.0540088750 0.0792056494 0.1677472293 0.0252482425 0.0066810000 0.0004470000 0.0044180000 0.0000000000 0.0000060000 0.0008180000 15413433 96830484 509673472 3.9639964104 4.0292325020 4.0568757057 369 1305031241.8098289967 0.0510734878 0.0791294104 0.1677472293 0.0252470873 0.0067080000 0.0003780000 0.0043070000 0.0000040000 0.0000040000 0.0013460000 15416993 96830484 509673472 3.9635243416 4.0322618484 4.0565423965 370 1305031241.8464360237 0.0540319048 0.0790615793 0.1677472293 0.0252545037 0.0065890000 0.0005640000 0.0029630000 0.0000020000 0.0000170000 0.0012780000 15420833 96830484 509673472 3.9630770683 4.0287742615 4.0538549423 371 1305031241.8787989616 0.0532725789 0.0789920672 0.1677472293 0.0253260489 0.0059070000 0.0004350000 0.0030540000 0.0000090000 0.0000070000 0.0011210000 15424561 96830484 509673472 3.9613656998 4.0298995972 4.0524516106 372 1305031241.9114871025 0.0480630361 0.0789089247 0.1677472293 0.0253555731 0.0077550000 0.0005430000 0.0032880000 0.0000010000 0.0000150000 0.0012830000 15428233 96830484 509673472 3.9637837410 4.0353183746 4.0554471016 373 1305031241.9477050304 0.0490148291 0.0788287796 0.1677472293 0.0253405066 0.0072570000 0.0004760000 0.0038420000 0.0000090000 0.0000070000 0.0016000000 15432017 96830484 509673472 3.9640614986 4.0343985558 4.0548229218 374 1305031241.9783430099 0.0481353253 0.0787467116 0.1677472293 0.0254468055 0.0053180000 0.0004000000 0.0030070000 0.0000000000 0.0000060000 0.0008470000 15435689 96830484 509673472 3.9641056061 4.0355148315 4.0550312996 375 1305031242.0105700493 0.0468800254 0.0786617337 0.1677472293 0.0255283096 0.0089640000 0.0005490000 0.0047910000 0.0000160000 0.0000140000 0.0015210000 15439305 96830484 509673472 3.9611124992 4.0371580124 4.0536470413 376 1305031242.0463600159 0.0479304865 0.0785800017 0.1677472293 0.0255835048 0.0054090000 0.0004230000 0.0030610000 0.0000010000 0.0000080000 0.0008530000 15443089 96830484 509673472 3.9574260712 4.0362062454 4.0512962341 377 1305031242.0795490742 0.0505999587 0.0785057841 0.1677472293 0.0256677933 0.0073670000 0.0004590000 0.0038520000 0.0000110000 0.0000090000 0.0017110000 15446761 96830484 509673472 3.9515867233 4.0338735580 4.0470657349 378 1305031242.1105840206 0.0543424226 0.0784418598 0.1677472293 0.0257259943 0.0049590000 0.0004010000 0.0026520000 0.0000010000 0.0000060000 0.0008380000 15450433 96830484 509673472 3.9468200207 4.0301628113 4.0433697701 379 1305031242.1466050148 0.0581959113 0.0783884405 0.1677472293 0.0258191202 0.0076760000 0.0005510000 0.0029460000 0.0000150000 0.0000140000 0.0015090000 15454217 96830484 509673472 3.9435629845 4.0261778831 4.0405664444 380 1305031242.1797080040 0.0646521524 0.0783522923 0.1677472293 0.0258980411 0.0065390000 0.0004600000 0.0034900000 0.0000010000 0.0000100000 0.0010280000 15457945 96830484 509673472 3.9368829727 4.0199742317 4.0359287262 381 1305031242.2087249756 0.0689965636 0.0783277366 0.1677472293 0.0259237992 0.0070730000 0.0004560000 0.0031500000 0.0000100000 0.0000090000 0.0017250000 15461505 96830484 509673472 3.9338128567 4.0145163536 4.0337910652 382 1305031242.2478089333 0.0727605596 0.0783131628 0.1677472293 0.0259682501 0.0050960000 0.0004190000 0.0027080000 0.0000010000 0.0000080000 0.0008820000 15465401 96830484 509673472 3.9311418533 4.0096473694 4.0316505432 383 1305031242.2794981003 0.0742143169 0.0783024609 0.1677472293 0.0260011219 0.0080950000 0.0005450000 0.0033320000 0.0000160000 0.0000140000 0.0015010000 15469073 96830484 509673472 3.9298417568 4.0078749657 4.0300049782 384 1305031242.3097639084 0.0772116855 0.0782996203 0.1677472293 0.0260067946 0.0066860000 0.0004610000 0.0035570000 0.0000020000 0.0000100000 0.0010260000 15472633 96830484 509673472 3.9286363125 4.0038633347 4.0279603004 385 1305031242.3471269608 0.0784393996 0.0782999834 0.1677472293 0.0260875395 0.0079440000 0.0004600000 0.0045910000 0.0000080000 0.0000070000 0.0015210000 15476529 96830484 509673472 3.9291007519 4.0008807182 4.0266470909 386 1305031242.3784790039 0.0781314448 0.0782995468 0.1677472293 0.0261793829 0.0065380000 0.0003970000 0.0044240000 0.0000010000 0.0000060000 0.0007950000 15480201 96830484 509673472 3.9284813404 4.0001912117 4.0257949829 387 1305031242.4109969139 0.0798211694 0.0783034786 0.1677472293 0.0262230507 0.0051170000 0.0003710000 0.0029480000 0.0000050000 0.0000040000 0.0010140000 15483873 96830484 509673472 3.9282910824 3.9969770908 4.0241570473 388 1305031242.4470989704 0.0807314888 0.0783097364 0.1677472293 0.0263415708 0.0093900000 0.0005470000 0.0047930000 0.0000020000 0.0000150000 0.0013140000 15487713 96830484 509673472 3.9268221855 3.9948191643 4.0214753151 389 1305031242.4776470661 0.0816294849 0.0783182704 0.1677472293 0.0264215980 0.0061820000 0.0004530000 0.0028000000 0.0000080000 0.0000070000 0.0015490000 15491385 96830484 509673472 3.9255995750 3.9939949512 4.0182809830 390 1305031242.5097260475 0.0853670985 0.0783363443 0.1677472293 0.0266143826 0.0047880000 0.0003990000 0.0026630000 0.0000010000 0.0000050000 0.0008080000 15495057 96830484 509673472 3.9216148853 3.9905939102 4.0130372047 391 1305031242.5485460758 0.0840218663 0.0783508853 0.1677472293 0.0270239638 0.0080960000 0.0005450000 0.0033470000 0.0000200000 0.0000140000 0.0015390000 15498953 96830484 509673472 3.9197351933 3.9923753738 4.0105938911 392 1305031242.5748429298 0.0851037651 0.0783681121 0.1677472293 0.0271369840 0.0058700000 0.0004540000 0.0028340000 0.0000020000 0.0000100000 0.0010650000 15502401 96830484 509673472 3.9174273014 3.9928894043 4.0075087547 393 1305031242.6061151028 0.0910012200 0.0784002574 0.1677472293 0.0271911286 0.0072110000 0.0004010000 0.0043870000 0.0000080000 0.0000060000 0.0014800000 15506129 96830484 509673472 3.9096479416 3.9902722836 4.0011000633 394 1305031242.6438109875 0.0932055712 0.0784378343 0.1677472293 0.0273888620 0.0089500000 0.0005450000 0.0047780000 0.0000020000 0.0000150000 0.0013470000 15509969 96830484 509673472 3.9064083099 3.9896965027 3.9976263046 395 1305031242.6752018929 0.0925885811 0.0784736590 0.1677472293 0.0276651071 0.0067060000 0.0004210000 0.0041220000 0.0000060000 0.0000050000 0.0010600000 15513697 96830484 509673472 3.9050204754 3.9905819893 3.9965019226 396 1305031242.7139821053 0.0935157016 0.0785116439 0.1677472293 0.0279881084 0.0064190000 0.0003860000 0.0043710000 0.0000010000 0.0000050000 0.0008030000 15517649 96830484 509673472 3.9017641544 3.9912748337 3.9947624207 397 1305031242.7452580929 0.0964192525 0.0785567513 0.1677472293 0.0280403588 0.0090150000 0.0005400000 0.0040920000 0.0000160000 0.0000130000 0.0020990000 15521321 96830484 509673472 3.8977751732 3.9912455082 3.9915003777 398 1305031242.7775399685 0.1003487483 0.0786115050 0.1677472293 0.0281685696 0.0068900000 0.0004320000 0.0044510000 0.0000010000 0.0000060000 0.0008720000 15525049 96830484 509673472 3.8917880058 3.9894285202 3.9883623123 399 1305031242.8140709400 0.0983080268 0.0786608697 0.1677472293 0.0283583668 0.0062280000 0.0003860000 0.0039970000 0.0000050000 0.0000040000 0.0010300000 15528889 96830484 509673472 3.8935544491 3.9928154945 3.9897384644 400 1305031242.8443179131 0.1002930775 0.0787149503 0.1677472293 0.0283880652 0.0084130000 0.0005470000 0.0044250000 0.0000020000 0.0000150000 0.0013460000 15532561 96830484 509673472 3.8901040554 3.9932765961 3.9886403084 401 1305031242.8740880489 0.1058789864 0.0787826910 0.1677472293 0.0284108258 0.0064980000 0.0004280000 0.0034310000 0.0000060000 0.0000050000 0.0014930000 15536289 96830484 509673472 3.8834934235 3.9901602268 3.9869031906 402 1305031242.9137070179 0.1135085076 0.0788690736 0.1677472293 0.0284698974 0.0058760000 0.0003860000 0.0037170000 0.0000000000 0.0000060000 0.0008270000 15540297 96830484 509673472 3.8738310337 3.9894816875 3.9824519157 403 1305031242.9444379807 0.1126918122 0.0789530010 0.1677472293 0.0286070768 0.0083330000 0.0005420000 0.0040870000 0.0000150000 0.0000130000 0.0015580000 15543969 96830484 509673472 3.8728473186 3.9938371181 3.9828565121 404 1305031242.9760620594 0.1159160659 0.0790444938 0.1677472293 0.0286439850 0.0100040000 0.0006270000 0.0048550000 0.0000020000 0.0000160000 0.0013460000 15547641 96830484 509673472 3.8645570278 3.9969079494 3.9805517197 405 1305031243.0141661167 0.1199031398 0.0791453793 0.1677472293 0.0286876156 0.0103880000 0.0005650000 0.0047870000 0.0000160000 0.0000140000 0.0021330000 15551537 96830484 509673472 3.8580577374 3.9976630211 3.9797828197 406 1305031243.0469100475 0.1192756221 0.0792442223 0.1677472293 0.0286815429 0.0085810000 0.0005650000 0.0040520000 0.0000020000 0.0000150000 0.0014000000 15555433 96830484 509673472 3.8566179276 4.0003290176 3.9808197021 407 1305031243.0780448914 0.1199554950 0.0793442500 0.1677472293 0.0286677678 0.0061560000 0.0004270000 0.0034230000 0.0000090000 0.0000060000 0.0011370000 15559161 96830484 509673472 3.8538999557 4.0027122498 3.9803302288 408 1305031243.1136150360 0.1213330328 0.0794471636 0.1677472293 0.0286665261 0.0047760000 0.0003950000 0.0026470000 0.0000000000 0.0000050000 0.0008760000 15562945 96830484 509673472 3.8494617939 4.0054082870 3.9789080620 409 1305031243.1458160877 0.1238011494 0.0795556086 0.1677472293 0.0286363815 0.0093790000 0.0005630000 0.0036780000 0.0000170000 0.0000160000 0.0022010000 15566729 96830484 509673472 3.8439745903 4.0082006454 3.9759557247 410 1305031243.1780760288 0.1230484620 0.0796616887 0.1677472293 0.0286228089 0.0074640000 0.0005520000 0.0029440000 0.0000020000 0.0000160000 0.0014080000 15570457 96830484 509673472 3.8424875736 4.0100069046 3.9750161171 411 1305031243.2136580944 0.1170619652 0.0797526870 0.1677472293 0.0286333897 0.0076830000 0.0004630000 0.0045540000 0.0000080000 0.0000070000 0.0012090000 15574297 96830484 509673472 3.8493471146 4.0087428093 3.9792399406 412 1305031243.2455608845 0.1191228852 0.0798482457 0.1677472293 0.0288932854 0.0052040000 0.0004000000 0.0030240000 0.0000000000 0.0000050000 0.0008070000 15578025 96830484 509673472 3.8500545025 4.0045251846 3.9786889553 413 1305031243.2781798840 0.1124271601 0.0799271293 0.1677472293 0.0289584214 0.0081730000 0.0005490000 0.0026220000 0.0000180000 0.0000150000 0.0021350000 15581809 96830484 509673472 3.8618824482 4.0042829514 3.9815697670 414 1305031243.3142709732 0.1154987216 0.0800130510 0.1677472293 0.0289976816 0.0057430000 0.0004310000 0.0031240000 0.0000010000 0.0000090000 0.0009380000 15585593 96830484 509673472 3.8598780632 3.9987907410 3.9834883213 415 1305031243.3460359573 0.1156470776 0.0800989161 0.1677472293 0.0293043053 0.0078170000 0.0004720000 0.0046290000 0.0000120000 0.0000090000 0.0012360000 15589377 96830484 509673472 3.8634095192 3.9965538979 3.9846751690 416 1305031243.3789350986 0.1093580425 0.0801692506 0.1677472293 0.0293375697 0.0066580000 0.0004000000 0.0044460000 0.0000000000 0.0000080000 0.0008220000 15593161 96830484 509673472 3.8746144772 3.9999895096 3.9885737896 417 1305031243.4139740467 0.1143823192 0.0802512963 0.1677472293 0.0294146091 0.0069420000 0.0003740000 0.0044190000 0.0000040000 0.0000050000 0.0013990000 15596945 96830484 509673472 3.8656291962 3.9992792606 3.9879724979 418 1305031243.4470911026 0.1080018058 0.0803176851 0.1677472293 0.0296118477 0.0065360000 0.0004690000 0.0031790000 0.0000020000 0.0000100000 0.0010580000 15600729 96830484 509673472 3.8768124580 4.0033993721 3.9923472404 419 1305031243.4780371189 0.1086735725 0.0803853602 0.1677472293 0.0296394712 0.0093330000 0.0005440000 0.0048360000 0.0000160000 0.0000160000 0.0015520000 15604401 96830484 509673472 3.8758447170 4.0066614151 3.9925119877 420 1305031243.5154008865 0.1098597050 0.0804555372 0.1677472293 0.0297407114 0.0069350000 0.0004280000 0.0044650000 0.0000010000 0.0000060000 0.0008560000 15608297 96830484 509673472 3.8700649738 4.0110974312 3.9924106598 421 1305031243.5459430218 0.1080659553 0.0805211202 0.1677472293 0.0297908853 0.0068830000 0.0003820000 0.0043500000 0.0000040000 0.0000040000 0.0013810000 15612025 96830484 509673472 3.8719189167 4.0146465302 3.9935288429 422 1305031243.5779840946 0.1034403667 0.0805754312 0.1677472293 0.0297817916 0.0071330000 0.0004680000 0.0042450000 0.0000010000 0.0000080000 0.0009350000 15615641 96830484 509673472 3.8737773895 4.0202312469 3.9966826439 423 1305031243.6140549183 0.1011619270 0.0806240990 0.1677472293 0.0300281026 0.0082600000 0.0005460000 0.0044220000 0.0000110000 0.0000090000 0.0012920000 15619425 96830484 509673472 3.8753843307 4.0243110657 3.9983010292 424 1305031243.6461870670 0.1040372625 0.0806793187 0.1677472293 0.0302937042 0.0068330000 0.0004320000 0.0044790000 0.0000000000 0.0000060000 0.0008450000 15623209 96830484 509673472 3.8734576702 4.0220317841 3.9958443642 425 1305031243.6782801151 0.1083982065 0.0807445397 0.1677472293 0.0303205339 0.0074580000 0.0004570000 0.0035570000 0.0000110000 0.0000090000 0.0017800000 15626881 96830484 509673472 3.8684229851 4.0180058479 3.9937670231 426 1305031243.7142961025 0.0990676731 0.0807875517 0.1677472293 0.0306390436 0.0063610000 0.0004010000 0.0040860000 0.0000010000 0.0000050000 0.0008440000 15630609 96830484 509673472 3.8775908947 4.0267567635 3.9981894493 427 1305031243.7473781109 0.0987742022 0.0808296750 0.1677472293 0.0308786650 0.0083490000 0.0005470000 0.0048120000 0.0000160000 0.0000140000 0.0016010000 15634337 96830484 509673472 3.8821978569 4.0246510506 3.9983861446 428 1305031243.7790360451 0.0998767987 0.0808741776 0.1677472293 0.0310164045 0.0062560000 0.0003620000 0.0043650000 0.0000000000 0.0000040000 0.0008660000 15637953 96830484 509673472 3.8817284107 4.0193424225 3.9997916222 429 1305031243.8141930103 0.0900358111 0.0808955334 0.1677472293 0.0314460723 0.0097140000 0.0005530000 0.0048740000 0.0000170000 0.0000140000 0.0022340000 15641681 96830484 509673472 3.8968565464 4.0237474442 4.0061039925 430 1305031243.8462920189 0.0887123570 0.0809137121 0.1677472293 0.0317422490 0.0063840000 0.0004830000 0.0035130000 0.0000010000 0.0000070000 0.0009400000 15645353 96830484 509673472 3.9058561325 4.0218520164 4.0080943108 431 1305031243.8788089752 0.0833265111 0.0809193102 0.1677472293 0.0318412831 0.0053210000 0.0004300000 0.0027190000 0.0000070000 0.0000050000 0.0011500000 15649081 96830484 509673472 3.9133405685 4.0240011215 4.0125536919 432 1305031243.9140000343 0.0746783689 0.0809048636 0.1677472293 0.0320342323 0.0100180000 0.0005460000 0.0048870000 0.0000020000 0.0000160000 0.0015010000 15652753 96830484 509673472 3.9233059883 4.0284991264 4.0197453499 433 1305031243.9470779896 0.0645434409 0.0808670774 0.1677472293 0.0321394938 0.0075420000 0.0004740000 0.0041760000 0.0000080000 0.0000070000 0.0016540000 15656537 96830484 509673472 3.9347915649 4.0369029045 4.0293006897 434 1305031243.9816520214 0.0564916059 0.0808109127 0.1677472293 0.0322174422 0.0069960000 0.0004610000 0.0038990000 0.0000010000 0.0000080000 0.0011030000 15660265 96830484 509673472 3.9426362514 4.0436849594 4.0382242203 435 1305031244.0112700462 0.0532228127 0.0807474918 0.1677472293 0.0322671567 0.0076820000 0.0004690000 0.0042830000 0.0000100000 0.0000100000 0.0013710000 15663881 96830484 509673472 3.9485776424 4.0482831001 4.0427365303 436 1305031244.0438230038 0.0487281866 0.0806740530 0.1677472293 0.0322744914 0.0068990000 0.0004020000 0.0044510000 0.0000000000 0.0000060000 0.0010110000 15667553 96830484 509673472 3.9491477013 4.0583682060 4.0453305244 437 1305031244.0818090439 0.0462023541 0.0805951704 0.1677472293 0.0323088500 0.0085070000 0.0004800000 0.0042470000 0.0000110000 0.0000090000 0.0020650000 15671393 96830484 509673472 3.9467549324 4.0639104843 4.0452151299 438 1305031244.1127901077 0.0479046479 0.0805205345 0.1677472293 0.0323914351 0.0058280000 0.0004060000 0.0033860000 0.0000010000 0.0000070000 0.0009880000 15675065 96830484 509673472 3.9511566162 4.0635290146 4.0464348793 439 1305031244.1484949589 0.0454101078 0.0804405563 0.1677472293 0.0323816999 0.0060870000 0.0003830000 0.0036940000 0.0000050000 0.0000040000 0.0012020000 15678849 96830484 509673472 3.9520895481 4.0688362122 4.0495138168 440 1305031244.1824309826 0.0420960858 0.0803534098 0.1677472293 0.0324439498 0.0050910000 0.0003710000 0.0029610000 0.0000010000 0.0000040000 0.0009620000 15682521 96830484 509673472 3.9547364712 4.0746183395 4.0543451309 441 1305031244.2124009132 0.0424794108 0.0802675277 0.1677472293 0.0325498160 0.0054290000 0.0003710000 0.0026120000 0.0000050000 0.0000040000 0.0016390000 15686193 96830484 509673472 3.9583268166 4.0772800446 4.0563411713 442 1305031244.2473471165 0.0401390679 0.0801767394 0.1677472293 0.0326965818 0.0047460000 0.0003710000 0.0026220000 0.0000010000 0.0000040000 0.0009540000 15689921 96830484 509673472 3.9612841606 4.0826287270 4.0590777397 443 1305031244.2831470966 0.0373583138 0.0800800838 0.1677472293 0.0328105581 0.0067150000 0.0003730000 0.0043500000 0.0000050000 0.0000040000 0.0011890000 15693705 96830484 509673472 3.9661021233 4.0878815651 4.0627183914 444 1305031244.3137950897 0.0364377424 0.0799817902 0.1677472293 0.0329297219 0.0047660000 0.0003710000 0.0026390000 0.0000010000 0.0000040000 0.0009640000 15697265 96830484 509673472 3.9710731506 4.0953445435 4.0657701492 445 1305031244.3459599018 0.0376092978 0.0798865711 0.1677472293 0.0330864048 0.0054640000 0.0003680000 0.0026190000 0.0000050000 0.0000030000 0.0016450000 15700993 96830484 509673472 3.9768507481 4.1036486626 4.0686559677 446 1305031244.3808560371 0.0367466286 0.0797898448 0.1677472293 0.0332174975 0.0064530000 0.0003710000 0.0043260000 0.0000010000 0.0000040000 0.0009490000 15704721 96830484 509673472 3.9784271717 4.1087546349 4.0675292015 447 1305031244.4130189419 0.0410375260 0.0797031506 0.1677472293 0.0333992887 0.0066920000 0.0003720000 0.0043420000 0.0000050000 0.0000040000 0.0011740000 15708393 96830484 509673472 3.9870100021 4.1165142059 4.0705733299 448 1305031244.4451670647 0.0428111963 0.0796208025 0.1677472293 0.0334615210 0.0080070000 0.0005920000 0.0026580000 0.0000020000 0.0000170000 0.0016030000 15712065 96830484 509673472 3.9880928993 4.1265683174 4.0696191788 449 1305031244.4806590080 0.0430240184 0.0795392951 0.1677472293 0.0335114333 0.0088460000 0.0005530000 0.0033990000 0.0000160000 0.0000140000 0.0024440000 15715849 96830484 509673472 3.9868872166 4.1322088242 4.0674238205 450 1305031244.5142281055 0.0443214104 0.0794610332 0.1677472293 0.0336068792 0.0072420000 0.0004350000 0.0045000000 0.0000010000 0.0000070000 0.0010370000 15719577 96830484 509673472 3.9859290123 4.1367144585 4.0654582977 451 1305031244.5462141037 0.0444459766 0.0793833945 0.1677472293 0.0335889659 0.0077480000 0.0004650000 0.0045680000 0.0000080000 0.0000070000 0.0013260000 15723249 96830484 509673472 3.9828069210 4.1440234184 4.0661516190 452 1305031244.5808050632 0.0427921377 0.0793024404 0.1677472293 0.0336308650 0.0074620000 0.0004620000 0.0045290000 0.0000010000 0.0000070000 0.0011340000 15726977 96830484 509673472 3.9801719189 4.1455769539 4.0662579536 453 1305031244.6132769585 0.0419659354 0.0792200198 0.1677472293 0.0337055498 0.0084940000 0.0004720000 0.0046070000 0.0000080000 0.0000070000 0.0018710000 15730705 96830484 509673472 3.9783668518 4.1471095085 4.0660147667 454 1305031244.6428399086 0.0421099178 0.0791382795 0.1677472293 0.0336878339 0.0067240000 0.0004050000 0.0044020000 0.0000010000 0.0000050000 0.0009920000 15734265 96830484 509673472 3.9762046337 4.1523947716 4.0675969124 455 1305031244.6806099415 0.0415455550 0.0790556581 0.1677472293 0.0337385984 0.0082230000 0.0004610000 0.0045830000 0.0000100000 0.0000090000 0.0014710000 15738049 96830484 509673472 3.9761617184 4.1555285454 4.0706043243 456 1305031244.7152500153 0.0393442921 0.0789685718 0.1677472293 0.0337446292 0.0068770000 0.0004110000 0.0044090000 0.0000000000 0.0000050000 0.0009750000 15741833 96830484 509673472 3.9727652073 4.1587567329 4.0715208054 457 1305031244.7458879948 0.0374413915 0.0788777027 0.1677472293 0.0339188158 0.0099890000 0.0005500000 0.0048020000 0.0000150000 0.0000130000 0.0023780000 15745449 96830484 509673472 3.9736156464 4.1572399139 4.0727291107 458 1305031244.7818510532 0.0351689234 0.0787822687 0.1677472293 0.0340202592 0.0072370000 0.0004360000 0.0044490000 0.0000010000 0.0000060000 0.0010450000 15749289 96830484 509673472 3.9707067013 4.1548304558 4.0692048073 459 1305031244.8140940666 0.0264710635 0.0786683009 0.1677472293 0.0348588001 0.0067270000 0.0003900000 0.0043180000 0.0000040000 0.0000040000 0.0011740000 15752961 96830484 509673472 3.9740028381 4.1593012810 4.0707092285 460 1305031244.8418219090 0.0302647855 0.0785630759 0.1677472293 0.0348562931 0.0076770000 0.0004790000 0.0045260000 0.0000010000 0.0000080000 0.0011130000 15756465 96830484 509673472 3.9721710682 4.1611571312 4.0656652451 461 1305031244.8818008900 0.0356615260 0.0784700140 0.1677472293 0.0348270079 0.0073860000 0.0003900000 0.0043500000 0.0000050000 0.0000040000 0.0016960000 15760361 96830484 509673472 3.9643664360 4.1666331291 4.0596237183 462 1305031244.9149079323 0.0356615260 0.0783773549 0.1677472293 0.0347892140 0.0086750000 0.0005550000 0.0046830000 0.0000010000 0.0000100000 0.0012580000 15764033 96830484 509673472 3.9643664360 4.1666331291 4.0596237183 463 1305031244.9458680153 0.0349794552 0.0782836229 0.1677472293 0.0347622940 0.0070390000 0.0004330000 0.0043760000 0.0000010000 0.0000070000 0.0010420000 15767649 96830484 509673472 3.9643664360 4.1666331291 4.0596237183 464 1305031244.9818000793 0.0388489291 0.0781986344 0.1677472293 0.0348740544 0.0065960000 0.0003780000 0.0042870000 0.0000010000 0.0000050000 0.0009680000 15771433 96830484 509673472 3.9721593857 4.1828947067 4.0704441071 465 1305031245.0140550137 0.0388489291 0.0781140113 0.1677472293 0.0348364544 0.0102380000 0.0005500000 0.0047260000 0.0000020000 0.0000150000 0.0022400000 15775105 96830484 509673472 3.9721593857 4.1828947067 4.0704441071 466 1305031245.0464398861 0.0431353040 0.0780389497 0.1677472293 0.0348068663 0.0072210000 0.0004370000 0.0044270000 0.0000010000 0.0000070000 0.0010380000 15778777 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 467 1305031245.0817689896 0.0439962856 0.0779660532 0.1677472293 0.0347729541 0.0065510000 0.0003900000 0.0042240000 0.0000000000 0.0000040000 0.0009760000 15782561 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 468 1305031245.1143150330 0.0459374189 0.0778976160 0.1677472293 0.0347409095 0.0081640000 0.0004760000 0.0045200000 0.0000010000 0.0000110000 0.0013010000 15786177 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 469 1305031245.1457099915 0.0492638610 0.0778365632 0.1677472293 0.0347044757 0.0073370000 0.0004070000 0.0043040000 0.0000000000 0.0000050000 0.0015150000 15789905 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 470 1305031245.1818709373 0.0528577380 0.0777834168 0.1677472293 0.0346756414 0.0064670000 0.0003780000 0.0042300000 0.0000000000 0.0000050000 0.0009800000 15793633 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 471 1305031245.2140939236 0.0585632659 0.0777426097 0.1677472293 0.0346638949 0.0089930000 0.0005490000 0.0047620000 0.0000030000 0.0000160000 0.0014780000 15797305 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 472 1305031245.2487950325 0.0629063919 0.0777111770 0.1677472293 0.0346707538 0.0072690000 0.0004320000 0.0044480000 0.0000010000 0.0000060000 0.0010540000 15801089 96830484 509673472 3.9707927704 4.1887936592 4.0709228516 473 1305031245.2807950974 0.0498590507 0.0776522930 0.1677472293 0.0363610215 0.0095020000 0.0005500000 0.0048270000 0.0000120000 0.0000090000 0.0020880000 15804705 96830484 509673472 3.9668848515 4.1662316322 4.0673494339 474 1305031245.3143179417 0.0540443286 0.0776024872 0.1677472293 0.0365104008 0.0070840000 0.0004340000 0.0044580000 0.0000010000 0.0000060000 0.0010760000 15808377 96830484 509673472 3.9670169353 4.1662015915 4.0693211555 475 1305031245.3491809368 0.0531033762 0.0775509101 0.1677472293 0.0367178782 0.0068700000 0.0003780000 0.0043840000 0.0000050000 0.0000040000 0.0012530000 15812217 96830484 509673472 3.9654192924 4.1597709656 4.0666580200 476 1305031245.3806860447 0.0507743023 0.0774946567 0.1677472293 0.0369009709 0.0050170000 0.0003620000 0.0029670000 0.0000010000 0.0000030000 0.0009890000 15815777 96830484 509673472 3.9621834755 4.1512355804 4.0605502129 477 1305031245.4133110046 0.0495232046 0.0774360164 0.1677472293 0.0370509942 0.0108560000 0.0005500000 0.0048160000 0.0000160000 0.0000160000 0.0025430000 15819449 96830484 509673472 3.9596662521 4.1425251961 4.0562167168 478 1305031245.4489970207 0.0497369133 0.0773780684 0.1677472293 0.0370337358 0.0054270000 0.0004270000 0.0023890000 0.0000010000 0.0000080000 0.0012060000 15823177 96830484 509673472 3.9647777081 4.1295990944 4.0516057014 479 1305031245.4846711159 0.0521483347 0.0773253968 0.1677472293 0.0372371800 0.0067620000 0.0004620000 0.0031650000 0.0000080000 0.0000060000 0.0014330000 15826961 96830484 509673472 3.9641788006 4.1272821426 4.0482168198 480 1305031245.5124320984 0.0502433851 0.0772689759 0.1677472293 0.0373223926 0.0069590000 0.0004000000 0.0040780000 0.0000010000 0.0000060000 0.0011140000 15830521 96830484 509673472 3.9589643478 4.1226439476 4.0429024696 481 1305031245.5481460094 0.0494205356 0.0772110789 0.1677472293 0.0374553887 0.0087710000 0.0005480000 0.0037750000 0.0000160000 0.0000130000 0.0021520000 15834249 96830484 509673472 3.9543514252 4.1171698570 4.0380277634 482 1305031245.5786890984 0.0502111763 0.0771550625 0.1677472293 0.0374630056 0.0055810000 0.0004260000 0.0027030000 0.0000010000 0.0000060000 0.0010860000 15837921 96830484 509673472 3.9549963474 4.1127982140 4.0361709595 483 1305031245.6104750633 0.0502946898 0.0770994510 0.1677472293 0.0375189537 0.0088250000 0.0005480000 0.0037480000 0.0000160000 0.0000140000 0.0018420000 15841537 96830484 509673472 3.9509756565 4.1055402756 4.0297589302 484 1305031245.6494629383 0.0500258356 0.0770435138 0.1677472293 0.0376735749 0.0063020000 0.0004240000 0.0034500000 0.0000010000 0.0000070000 0.0010620000 15845377 96830484 509673472 3.9489774704 4.1025176048 4.0279250145 485 1305031245.6802349091 0.0497008264 0.0769871371 0.1677472293 0.0376958129 0.0090130000 0.0005460000 0.0040920000 0.0000150000 0.0000160000 0.0020760000 15849049 96830484 509673472 3.9469079971 4.1017951965 4.0277285576 486 1305031245.7110319138 0.0497308299 0.0769310542 0.1677472293 0.0376998797 0.0070640000 0.0004290000 0.0044370000 0.0000000000 0.0000060000 0.0010220000 15852721 96830484 509673472 3.9433484077 4.0988001823 4.0243058205 487 1305031245.7497749329 0.0498436615 0.0768754332 0.1677472293 0.0377612331 0.0070110000 0.0004590000 0.0035180000 0.0000080000 0.0000070000 0.0013110000 15856561 96830484 509673472 3.9408338070 4.0988311768 4.0231542587 488 1305031245.7818500996 0.0508231260 0.0768220474 0.1677472293 0.0377929094 0.0092310000 0.0005300000 0.0047880000 0.0000010000 0.0000110000 0.0014410000 15860289 96830484 509673472 3.9353551865 4.0964212418 4.0181879997 489 1305031245.8135690689 0.0529539138 0.0767732373 0.1677472293 0.0378750735 0.0078330000 0.0004800000 0.0045120000 0.0000080000 0.0000060000 0.0016290000 15863905 96830484 509673472 3.9311265945 4.0944333076 4.0143270493 490 1305031245.8491089344 0.0547654592 0.0767283234 0.1677472293 0.0379049825 0.0066960000 0.0004590000 0.0035010000 0.0000010000 0.0000080000 0.0009920000 15867689 96830484 509673472 3.9280438423 4.0883831978 4.0104990005 491 1305031245.8820281029 0.0574684367 0.0766890976 0.1677472293 0.0379197689 0.0069910000 0.0003850000 0.0043730000 0.0000050000 0.0000040000 0.0010600000 15871417 96830484 509673472 3.9220316410 4.0812950134 4.0060238838 492 1305031245.9126079082 0.0595122688 0.0766541854 0.1677472293 0.0379224906 0.0098300000 0.0005490000 0.0048250000 0.0000020000 0.0000140000 0.0013650000 15875033 96830484 509673472 3.9228105545 4.0774774551 4.0043153763 493 1305031245.9458959103 0.0626664981 0.0766258128 0.1677472293 0.0379548450 0.0078680000 0.0004340000 0.0045080000 0.0000070000 0.0000060000 0.0015140000 15878705 96830484 509673472 3.9179875851 4.0714116096 4.0003433228 494 1305031245.9808180332 0.0631365925 0.0765985066 0.1677472293 0.0379710699 0.0051800000 0.0003820000 0.0029980000 0.0000010000 0.0000040000 0.0007990000 15882489 96830484 509673472 3.9212520123 4.0690836906 4.0001406670 495 1305031246.0110030174 0.0649104938 0.0765748945 0.1677472293 0.0379772319 0.0097440000 0.0005400000 0.0048880000 0.0000150000 0.0000140000 0.0015530000 15886105 96830484 509673472 3.9249024391 4.0660943985 3.9990725517 496 1305031246.0483930111 0.0669365451 0.0765554623 0.1677472293 0.0380441116 0.0065470000 0.0004280000 0.0037900000 0.0000010000 0.0000060000 0.0008990000 15890001 96830484 509673472 3.9240896702 4.0622501373 3.9965777397 497 1305031246.0805249214 0.0689709783 0.0765402018 0.1677472293 0.0381053768 0.0071410000 0.0003820000 0.0043690000 0.0000050000 0.0000050000 0.0015000000 15893561 96830484 509673472 3.9233605862 4.0589270592 3.9946928024 498 1305031246.1123559475 0.0699225739 0.0765269134 0.1677472293 0.0381941497 0.0079900000 0.0004570000 0.0046080000 0.0000010000 0.0000100000 0.0011050000 15897289 96830484 509673472 3.9251675606 4.0574188232 3.9946539402 499 1305031246.1484489441 0.0732166916 0.0765202797 0.1677472293 0.0382665254 0.0070680000 0.0003960000 0.0044110000 0.0000060000 0.0000050000 0.0010830000 15901017 96830484 509673472 3.9195027351 4.0539979935 3.9894313812 500 1305031246.1805961132 0.0766396224 0.0765205184 0.1677472293 0.0383004861 0.0077160000 0.0005470000 0.0036910000 0.0000010000 0.0000100000 0.0011310000 15904633 96830484 509673472 3.9120867252 4.0506949425 3.9838795662 501 1305031246.2111370564 0.0807929412 0.0765290462 0.1677472293 0.0383780240 0.0066260000 0.0004170000 0.0033770000 0.0000060000 0.0000060000 0.0015780000 15908305 96830484 509673472 3.9054298401 4.0443086624 3.9792253971 502 1305031246.2469689846 0.0844842866 0.0765448933 0.1677472293 0.0384736634 0.0079870000 0.0004660000 0.0042100000 0.0000020000 0.0000100000 0.0011340000 15912089 96830484 509673472 3.8992409706 4.0408720970 3.9746127129 503 1305031246.2796959877 0.0883819982 0.0765684263 0.1677472293 0.0385185932 0.0079950000 0.0004570000 0.0045310000 0.0000080000 0.0000070000 0.0012320000 15915761 96830484 509673472 3.8966898918 4.0366468430 3.9710562229 504 1305031246.3124730587 0.0908969566 0.0765968559 0.1677472293 0.0386169583 0.0088140000 0.0005420000 0.0047620000 0.0000010000 0.0000110000 0.0011430000 15919489 96830484 509673472 3.8918077946 4.0349268913 3.9684836864 505 1305031246.3482720852 0.0926932395 0.0766287299 0.1677472293 0.0387213375 0.0066890000 0.0004230000 0.0033910000 0.0000070000 0.0000060000 0.0016120000 15923273 96830484 509673472 3.8911035061 4.0328707695 3.9678857327 506 1305031246.3782060146 0.0941723809 0.0766634012 0.1677472293 0.0388566637 0.0077470000 0.0004690000 0.0045370000 0.0000010000 0.0000080000 0.0010160000 15926889 96830484 509673472 3.8858094215 4.0332655907 3.9662418365 507 1305031246.4156370163 0.0953521132 0.0767002625 0.1677472293 0.0390037768 0.0080750000 0.0004560000 0.0045510000 0.0000080000 0.0000070000 0.0012640000 15930785 96830484 509673472 3.8790500164 4.0328927040 3.9661421776 508 1305031246.4452888966 0.1013849080 0.0767488544 0.1677472293 0.0390595481 0.0078320000 0.0004570000 0.0045590000 0.0000010000 0.0000080000 0.0010200000 15934401 96830484 509673472 3.8678641319 4.0280814171 3.9623515606 509 1305031246.4774649143 0.1059041545 0.0768061339 0.1677472293 0.0391292853 0.0068370000 0.0003930000 0.0036880000 0.0000050000 0.0000040000 0.0015550000 15938185 96830484 509673472 3.8595283031 4.0277585983 3.9590647221 510 1305031246.5163950920 0.1054879799 0.0768623728 0.1677472293 0.0392374360 0.0083000000 0.0004530000 0.0045700000 0.0000010000 0.0000100000 0.0012000000 15942081 96830484 509673472 3.8597733974 4.0321245193 3.9597291946 511 1305031246.5491750240 0.1050534397 0.0769175413 0.1677472293 0.0393450135 0.0064970000 0.0004030000 0.0037120000 0.0000060000 0.0000050000 0.0011530000 15945865 96830484 509673472 3.8576171398 4.0361895561 3.9600155354 512 1305031246.5795109272 0.1056578010 0.0769736746 0.1677472293 0.0394197685 0.0052770000 0.0003790000 0.0029990000 0.0000000000 0.0000040000 0.0009070000 15949537 96830484 509673472 3.8525290489 4.0390472412 3.9595675468 513 1305031246.6164529324 0.1071800813 0.0770325565 0.1677472293 0.0394680272 0.0072380000 0.0003740000 0.0043480000 0.0000040000 0.0000030000 0.0015590000 16002585 96830484 509673472 3.8525364399 4.0418400764 3.9584419727 514 1305031246.6477630138 0.1082241014 0.0770932404 0.1677472293 0.0395094403 0.0065790000 0.0003740000 0.0043680000 0.0000000000 0.0000040000 0.0008910000 16108713 96830484 509673472 3.8490357399 4.0447778702 3.9576401711 515 1305031246.6807579994 0.1080373153 0.0771533260 0.1677472293 0.0395828682 0.0054020000 0.0003790000 0.0029860000 0.0000040000 0.0000040000 0.0010900000 16112497 96830484 509673472 3.8457944393 4.0469088554 3.9577677250 516 1305031246.7169740200 0.1122002006 0.0772212463 0.1677472293 0.0396877361 0.0065460000 0.0003750000 0.0043370000 0.0000000000 0.0000040000 0.0008910000 16116393 96830484 509673472 3.8372316360 4.0488710403 3.9540369511 517 1305031246.7491660118 0.1160356849 0.0772963226 0.1677472293 0.0397521348 0.0072770000 0.0003780000 0.0043460000 0.0000050000 0.0000040000 0.0015980000 16120121 96830484 509673472 3.8300449848 4.0511236191 3.9501552582 518 1305031246.7808170319 0.1135541797 0.0773663184 0.1677472293 0.0398013605 0.0071310000 0.0004370000 0.0044850000 0.0000000000 0.0000040000 0.0009120000 16123905 96830484 509673472 3.8325734138 4.0552692413 3.9508721828 519 1305031246.8168079853 0.1200947016 0.0774486467 0.1677472293 0.0398304827 0.0068280000 0.0003740000 0.0043480000 0.0000050000 0.0000040000 0.0011370000 16127801 96830484 509673472 3.8243095875 4.0561594963 3.9455680847 520 1305031246.8488121033 0.1179909706 0.0775266127 0.1677472293 0.0398461796 0.0058470000 0.0003720000 0.0036260000 0.0000000000 0.0000040000 0.0008920000 16131585 96830484 509673472 3.8261003494 4.0608510971 3.9453682899 521 1305031246.8806428909 0.1138231978 0.0775962799 0.1677472293 0.0399048455 0.0068880000 0.0003740000 0.0039850000 0.0000040000 0.0000040000 0.0015720000 16135369 96830484 509673472 3.8302068710 4.0657744408 3.9462876320 522 1305031246.9166710377 0.1118136421 0.0776618304 0.1677472293 0.0399656983 0.0105250000 0.0005500000 0.0048150000 0.0000020000 0.0000150000 0.0014510000 16139265 96830484 509673472 3.8307988644 4.0686817169 3.9452128410 523 1305031246.9495339394 0.1163821742 0.0777358655 0.1677472293 0.0399536302 0.0077410000 0.0004630000 0.0045230000 0.0000080000 0.0000080000 0.0012500000 16143049 96830484 509673472 3.8261809349 4.0709371567 3.9396765232 524 1305031246.9775969982 0.1185415909 0.0778137390 0.1677472293 0.0399330526 0.0067520000 0.0003960000 0.0043840000 0.0000000000 0.0000050000 0.0008940000 16146665 96830484 509673472 3.8230025768 4.0713486671 3.9369184971 525 1305031247.0167899132 0.1145718843 0.0778837545 0.1677472293 0.0400087038 0.0071030000 0.0003700000 0.0043680000 0.0000040000 0.0000040000 0.0015150000 16150617 96830484 509673472 3.8249583244 4.0747985840 3.9375197887 526 1305031247.0479340553 0.1182424873 0.0779604821 0.1677472293 0.0399812019 0.0053210000 0.0003650000 0.0033200000 0.0000000000 0.0000030000 0.0008490000 16154401 96830484 509673472 3.8188052177 4.0750370026 3.9324297905 527 1305031247.0778899193 0.1156775132 0.0780320514 0.1677472293 0.0399685524 0.0100430000 0.0005540000 0.0041290000 0.0000160000 0.0000140000 0.0016170000 16158129 96830484 509673472 3.8184039593 4.0773315430 3.9318439960 528 1305031247.1162130833 0.1174662337 0.0781067374 0.1677472293 0.0399346845 0.0074150000 0.0004740000 0.0045150000 0.0000010000 0.0000070000 0.0009220000 16162081 96830484 509673472 3.8117220402 4.0797243118 3.9279155731 529 1305031247.1473660469 0.1190006509 0.0781840416 0.1677472293 0.0399205916 0.0074060000 0.0003940000 0.0043960000 0.0000050000 0.0000040000 0.0015340000 16165865 96830484 509673472 3.8096048832 4.0813102722 3.9246912003 530 1305031247.1796920300 0.1205351204 0.0782639493 0.1677472293 0.0398851912 0.0074430000 0.0004610000 0.0045020000 0.0000000000 0.0000080000 0.0009700000 16169649 96830484 509673472 3.8081576824 4.0779242516 3.9233820438 531 1305031247.2169430256 0.1157508567 0.0783345461 0.1677472293 0.0398569837 0.0069070000 0.0003900000 0.0043550000 0.0000050000 0.0000040000 0.0011030000 16173601 96830484 509673472 3.8128688335 4.0793843269 3.9248893261 532 1305031247.2487928867 0.1115371063 0.0783969569 0.1677472293 0.0398326539 0.0064890000 0.0003720000 0.0043700000 0.0000010000 0.0000040000 0.0008580000 16177329 96830484 509673472 3.8159234524 4.0794315338 3.9273002148 533 1305031247.2794220448 0.1169642136 0.0784693157 0.1677472293 0.0398130485 0.0107740000 0.0005370000 0.0048320000 0.0000170000 0.0000160000 0.0022480000 16181057 96830484 509673472 3.8111712933 4.0765757561 3.9232861996 534 1305031247.3166429996 0.1152052134 0.0785381096 0.1677472293 0.0398079375 0.0074140000 0.0004360000 0.0045160000 0.0000000000 0.0000060000 0.0009290000 16185009 96830484 509673472 3.8164770603 4.0730214119 3.9248406887 535 1305031247.3477900028 0.1169128120 0.0786098380 0.1677472293 0.0398565263 0.0078650000 0.0004610000 0.0045800000 0.0000080000 0.0000070000 0.0012220000 16188793 96830484 509673472 3.8162698746 4.0706844330 3.9251046181 536 1305031247.3786110878 0.1147835627 0.0786773263 0.1677472293 0.0398612120 0.0079520000 0.0004590000 0.0046270000 0.0000010000 0.0000080000 0.0009950000 16192521 96830484 509673472 3.8203575611 4.0693287849 3.9273283482 537 1305031247.4168620110 0.1165673584 0.0787478850 0.1677472293 0.0398942025 0.0077000000 0.0004620000 0.0039240000 0.0000080000 0.0000070000 0.0016990000 16196529 96830484 509673472 3.8198606968 4.0658488274 3.9284884930 538 1305031247.4487700462 0.1171384603 0.0788192429 0.1677472293 0.0400093523 0.0067730000 0.0003880000 0.0044400000 0.0000010000 0.0000050000 0.0008670000 16200313 96830484 509673472 3.8206357956 4.0647487640 3.9303495884 539 1305031247.4802629948 0.1139442772 0.0788844100 0.1677472293 0.0400543781 0.0082780000 0.0004610000 0.0046770000 0.0000090000 0.0000070000 0.0012400000 16203985 96830484 509673472 3.8242163658 4.0666766167 3.9343295097 540 1305031247.5178461075 0.1149672493 0.0789512301 0.1677472293 0.0401230912 0.0074770000 0.0004630000 0.0042780000 0.0000010000 0.0000080000 0.0010030000 16207993 96830484 509673472 3.8258047104 4.0661473274 3.9363698959 541 1305031247.5459010601 0.1145484149 0.0790170289 0.1677472293 0.0401983415 0.0085060000 0.0004730000 0.0046420000 0.0000080000 0.0000080000 0.0016800000 16211609 96830484 509673472 3.8274638653 4.0644316673 3.9390528202 542 1305031247.5779209137 0.1133625954 0.0790803971 0.1677472293 0.0402525568 0.0058010000 0.0003870000 0.0033910000 0.0000000000 0.0000050000 0.0009090000 16215337 96830484 509673472 3.8297915459 4.0642538071 3.9413986206 543 1305031247.6152799129 0.1131766140 0.0791431894 0.1677472293 0.0403818925 0.0061170000 0.0003720000 0.0037220000 0.0000040000 0.0000030000 0.0011050000 16219177 96830484 509673472 3.8330113888 4.0637555122 3.9432332516 544 1305031247.6484000683 0.1130518615 0.0792055215 0.1677472293 0.0404877353 0.0092190000 0.0005470000 0.0041890000 0.0000020000 0.0000150000 0.0014350000 16222961 96830484 509673472 3.8348381519 4.0624446869 3.9442188740 545 1305031247.6835579872 0.1113410965 0.0792644859 0.1677472293 0.0406230056 0.0082160000 0.0004350000 0.0045870000 0.0000070000 0.0000060000 0.0016490000 16226745 96830484 509673472 3.8379185200 4.0615668297 3.9459462166 546 1305031247.7159609795 0.1066378951 0.0793146203 0.1677472293 0.0407925604 0.0067410000 0.0003900000 0.0044720000 0.0000000000 0.0000050000 0.0008980000 16230473 96830484 509673472 3.8461329937 4.0620999336 3.9511673450 547 1305031247.7469019890 0.1046602130 0.0793609560 0.1677472293 0.0409797588 0.0069110000 0.0004630000 0.0032380000 0.0000100000 0.0000070000 0.0012540000 16234201 96830484 509673472 3.8478879929 4.0605373383 3.9529967308 548 1305031247.7822608948 0.1074347422 0.0794121855 0.1677472293 0.0411067986 0.0091020000 0.0005540000 0.0049310000 0.0000020000 0.0000110000 0.0011890000 16237985 96830484 509673472 3.8440883160 4.0526475906 3.9516389370 549 1305031247.8139829636 0.1063578650 0.0794612669 0.1677472293 0.0413416766 0.0078590000 0.0004300000 0.0044970000 0.0000070000 0.0000060000 0.0016260000 16241545 96830484 509673472 3.8519752026 4.0484619141 3.9526495934 550 1305031247.8484420776 0.1043845788 0.0795065820 0.1677472293 0.0414922632 0.0070310000 0.0004000000 0.0044810000 0.0000000000 0.0000050000 0.0009100000 16245441 96830484 509673472 3.8633601665 4.0507855415 3.9516296387 551 1305031247.8820719719 0.1086738110 0.0795595171 0.1677472293 0.0415269242 0.0063400000 0.0003680000 0.0040100000 0.0000040000 0.0000030000 0.0011090000 16249113 96830484 509673472 3.8590567112 4.0414476395 3.9481682777 552 1305031247.9173319340 0.1040870920 0.0796039511 0.1677472293 0.0415050197 0.0043560000 0.0003590000 0.0022830000 0.0000010000 0.0000030000 0.0009130000 16252897 96830484 509673472 3.8560109138 4.0487599373 3.9437463284 553 1305031247.9496860504 0.0962581933 0.0796340673 0.1677472293 0.0415723193 0.0116490000 0.0005510000 0.0048610000 0.0000170000 0.0000130000 0.0023780000 16256513 96830484 509673472 3.8671340942 4.0561876297 3.9467215538 554 1305031247.9861450195 0.0991006494 0.0796692055 0.1677472293 0.0417350948 0.0069340000 0.0004690000 0.0031920000 0.0000020000 0.0000100000 0.0012600000 16260353 96830484 509673472 3.8715040684 4.0511884689 3.9414174557 555 1305031248.0181560516 0.0983770192 0.0797029133 0.1677472293 0.0417049573 0.0060200000 0.0004130000 0.0030660000 0.0000060000 0.0000050000 0.0012360000 16263969 96830484 509673472 3.8674564362 4.0546059608 3.9351453781 556 1305031248.0499138832 0.0943495780 0.0797292562 0.1677472293 0.0417245872 0.0060480000 0.0003780000 0.0036960000 0.0000000000 0.0000040000 0.0009910000 16267641 96830484 509673472 3.8734853268 4.0579314232 3.9352881908 557 1305031248.0857460499 0.0902696326 0.0797481797 0.1677472293 0.0418782820 0.0089900000 0.0004720000 0.0046200000 0.0000080000 0.0000070000 0.0019530000 16271369 96830484 509673472 3.8855845928 4.0581607819 3.9366292953 558 1305031248.1175789833 0.0868516788 0.0797609100 0.1677472293 0.0418903303 0.0093100000 0.0005510000 0.0048500000 0.0000010000 0.0000120000 0.0013170000 16275041 96830484 509673472 3.9003210068 4.0589456558 3.9414885044 559 1305031248.1493461132 0.0807216987 0.0797626287 0.1677472293 0.0418841639 0.0066420000 0.0004380000 0.0034310000 0.0000070000 0.0000050000 0.0013170000 16278713 96830484 509673472 3.9121108055 4.0611896515 3.9496440887 560 1305031248.1848630905 0.0789779350 0.0797612275 0.1677472293 0.0420086596 0.0081020000 0.0004620000 0.0045660000 0.0000010000 0.0000070000 0.0011890000 16282441 96830484 509673472 3.9290907383 4.0649523735 3.9580519199 561 1305031248.2167689800 0.0750966519 0.0797529127 0.1677472293 0.0420376682 0.0074600000 0.0003900000 0.0043750000 0.0000010000 0.0000050000 0.0015590000 16286113 96830484 509673472 3.9290907383 4.0649523735 3.9580519199 562 1305031248.2488510609 0.0718152300 0.0797387887 0.1677472293 0.0420813617 0.0066710000 0.0003720000 0.0043670000 0.0000010000 0.0000040000 0.0010450000 16289729 96830484 509673472 3.9290907383 4.0649523735 3.9580519199 563 1305031248.2847399712 0.0684399605 0.0797187198 0.1677472293 0.0420762477 0.0100600000 0.0005810000 0.0049020000 0.0000020000 0.0000150000 0.0017490000 16293569 96830484 509673472 3.9290907383 4.0649523735 3.9580519199 564 1305031248.3161809444 0.0662477463 0.0796948351 0.1677472293 0.0420594443 0.0070460000 0.0004370000 0.0039130000 0.0000010000 0.0000060000 0.0011180000 16297241 96830484 509673472 3.9290907383 4.0649523735 3.9580519199 565 1305031248.3488430977 0.0862554014 0.0797064467 0.1677472293 0.0429150155 0.0063910000 0.0003890000 0.0031200000 0.0000050000 0.0000040000 0.0017980000 16300857 96830484 509673472 3.9661087990 4.0828065872 3.9699845314 566 1305031248.3881969452 0.0910452530 0.0797264799 0.1677472293 0.0429077861 0.0082530000 0.0004650000 0.0046230000 0.0000010000 0.0000080000 0.0012770000 16304753 96830484 509673472 3.9755375385 4.0859303474 3.9776983261 567 1305031248.4155070782 0.0957617164 0.0797547608 0.1677472293 0.0429386904 0.0059880000 0.0004080000 0.0030240000 0.0000050000 0.0000040000 0.0013570000 16308313 96830484 509673472 3.9820296764 4.0902867317 3.9797346592 568 1305031248.4482519627 0.0993399620 0.0797892417 0.1677472293 0.0429487118 0.0067270000 0.0003710000 0.0043580000 0.0000010000 0.0000040000 0.0010830000 16311985 96830484 509673472 3.9865589142 4.0926189423 3.9793815613 569 1305031248.4852969646 0.1027737558 0.0798296363 0.1677472293 0.0430024555 0.0100460000 0.0005480000 0.0037470000 0.0000160000 0.0000140000 0.0028090000 16315769 96830484 509673472 3.9900028706 4.0942015648 3.9752774239 570 1305031248.5154309273 0.1025223881 0.0798694482 0.1677472293 0.0429729690 0.0066970000 0.0004320000 0.0034300000 0.0000010000 0.0000060000 0.0012380000 16319441 96830484 509673472 3.9894831181 4.1034822464 3.9757440090 571 1305031248.5470030308 0.1054822803 0.0799143043 0.1677472293 0.0429910525 0.0080960000 0.0004740000 0.0045200000 0.0000090000 0.0000070000 0.0014930000 16323113 96830484 509673472 3.9930050373 4.1111536026 3.9776077271 572 1305031248.5860579014 0.1031949446 0.0799550047 0.1677472293 0.0430319967 0.0057130000 0.0003900000 0.0029990000 0.0000000000 0.0000040000 0.0011570000 16326953 96830484 509673472 3.9905147552 4.1165289879 3.9699678421 573 1305031248.6180379391 0.0954878330 0.0799821126 0.1677472293 0.0430817601 0.0076510000 0.0003690000 0.0043220000 0.0000040000 0.0000040000 0.0019290000 16330569 96830484 509673472 3.9764599800 4.1223111153 3.9555814266 574 1305031248.6494390965 0.0954837054 0.0800091189 0.1677472293 0.0430711976 0.0057020000 0.0003630000 0.0032980000 0.0000010000 0.0000040000 0.0011330000 16334241 96830484 509673472 3.9742279053 4.1282305717 3.9513642788 575 1305031248.6860280037 0.0955907479 0.0800362173 0.1677472293 0.0431028407 0.0100310000 0.0005480000 0.0033450000 0.0000180000 0.0000150000 0.0021390000 16338081 96830484 509673472 3.9728469849 4.1377696991 3.9501636028 576 1305031248.7199230194 0.0960649475 0.0800640450 0.1677472293 0.0431070638 0.0079220000 0.0004600000 0.0044890000 0.0000020000 0.0000080000 0.0013610000 16341753 96830484 509673472 3.9705471992 4.1458911896 3.9465434551 577 1305031248.7498369217 0.0962539688 0.0800921038 0.1677472293 0.0431720163 0.0083790000 0.0003930000 0.0045370000 0.0000060000 0.0000050000 0.0020140000 16345369 96830484 509673472 3.9677155018 4.1528973579 3.9430358410 578 1305031248.7856750488 0.0967232212 0.0801208773 0.1677472293 0.0432297898 0.0068150000 0.0004260000 0.0042630000 0.0000010000 0.0000040000 0.0011770000 16349153 96830484 509673472 3.9591178894 4.1612048149 3.9328420162 579 1305031248.8181409836 0.0994674116 0.0801542911 0.1677472293 0.0432074940 0.0068630000 0.0003600000 0.0042320000 0.0000040000 0.0000040000 0.0013930000 16352825 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 580 1305031248.8496789932 0.0961705074 0.0801819052 0.1677472293 0.0431981255 0.0085660000 0.0005480000 0.0036720000 0.0000020000 0.0000150000 0.0015700000 16356497 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 581 1305031248.8855929375 0.0924484283 0.0802030180 0.1677472293 0.0432049845 0.0080340000 0.0004380000 0.0043050000 0.0000010000 0.0000070000 0.0018800000 16360281 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 582 1305031248.9178819656 0.0896505937 0.0802192509 0.1677472293 0.0431753017 0.0066010000 0.0003830000 0.0040700000 0.0000010000 0.0000040000 0.0010980000 16363953 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 583 1305031248.9526810646 0.0866521373 0.0802302851 0.1677472293 0.0431698251 0.0063390000 0.0003650000 0.0040330000 0.0000000000 0.0000040000 0.0010720000 16367737 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 584 1305031248.9845540524 0.0839050859 0.0802365775 0.1677472293 0.0431491912 0.0062370000 0.0003610000 0.0039500000 0.0000010000 0.0000030000 0.0010350000 16371409 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 585 1305031249.0169510841 0.0832296610 0.0802416939 0.1677472293 0.0431218450 0.0103590000 0.0005480000 0.0044330000 0.0000020000 0.0000150000 0.0023790000 16375081 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 586 1305031249.0523660183 0.0830128863 0.0802464229 0.1677472293 0.0430929609 0.0072690000 0.0004350000 0.0040640000 0.0000010000 0.0000070000 0.0011150000 16378865 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 587 1305031249.0845029354 0.0844195932 0.0802535322 0.1677472293 0.0430626726 0.0065490000 0.0003880000 0.0039630000 0.0000010000 0.0000050000 0.0010650000 16382537 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 588 1305031249.1168839931 0.0858652070 0.0802630759 0.1677472293 0.0430261784 0.0081030000 0.0004780000 0.0042910000 0.0000010000 0.0000080000 0.0012240000 16386209 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 589 1305031249.1534469128 0.0888707712 0.0802776900 0.1677472293 0.0430147542 0.0073600000 0.0004110000 0.0040440000 0.0000000000 0.0000050000 0.0016720000 16389993 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 590 1305031249.1847391129 0.0907781124 0.0802954873 0.1677472293 0.0429859513 0.0065210000 0.0003700000 0.0040980000 0.0000000000 0.0000040000 0.0010310000 16393665 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 591 1305031249.2168650627 0.0923996642 0.0803159681 0.1677472293 0.0429732152 0.0100210000 0.0005560000 0.0045990000 0.0000020000 0.0000160000 0.0015890000 16397337 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 592 1305031249.2532238960 0.0946604609 0.0803401987 0.1677472293 0.0430255003 0.0075250000 0.0004340000 0.0042760000 0.0000010000 0.0000060000 0.0011110000 16401121 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 593 1305031249.2848041058 0.0960309878 0.0803666587 0.1677472293 0.0430163919 0.0073040000 0.0003870000 0.0041950000 0.0000000000 0.0000040000 0.0016400000 16404737 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 594 1305031249.3174340725 0.0973270535 0.0803952116 0.1677472293 0.0429979564 0.0080470000 0.0004710000 0.0042530000 0.0000010000 0.0000070000 0.0012060000 16408465 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 595 1305031249.3527359962 0.0983815417 0.0804254407 0.1677472293 0.0429670006 0.0080040000 0.0004590000 0.0042130000 0.0000010000 0.0000070000 0.0012060000 16412193 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 596 1305031249.3847539425 0.0995734781 0.0804575683 0.1677472293 0.0429393954 0.0109520000 0.0005670000 0.0044740000 0.0000030000 0.0000170000 0.0016540000 16415865 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 597 1305031249.4178340435 0.0994338393 0.0804893543 0.1677472293 0.0429353736 0.0117610000 0.0005670000 0.0044950000 0.0000020000 0.0000160000 0.0024000000 16419537 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 598 1305031249.4537220001 0.1016898975 0.0805248067 0.1677472293 0.0429830734 0.0098250000 0.0005500000 0.0044740000 0.0000020000 0.0000160000 0.0016430000 16423321 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 599 1305031249.4859149456 0.1021719277 0.0805609455 0.1677472293 0.0430416311 0.0079880000 0.0004340000 0.0041640000 0.0000010000 0.0000080000 0.0012140000 16426993 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 600 1305031249.5177340508 0.1024966314 0.0805975050 0.1677472293 0.0430963710 0.0084280000 0.0004940000 0.0042380000 0.0000020000 0.0000080000 0.0012190000 16430665 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 601 1305031249.5543251038 0.1036124080 0.0806357993 0.1677472293 0.0432052658 0.0080440000 0.0004310000 0.0041070000 0.0000010000 0.0000090000 0.0017490000 16434449 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 602 1305031249.5859050751 0.1051144451 0.0806764615 0.1677472293 0.0433022046 0.0067090000 0.0003870000 0.0039580000 0.0000010000 0.0000060000 0.0010870000 16438065 96830484 509673472 3.9529438019 4.1773023605 3.9339547157 603 1305031249.6180789471 0.2314474881 0.0809264964 0.2314474881 0.0433372728 0.0070150000 0.0003760000 0.0039980000 0.0000050000 0.0000050000 0.0013590000 16441737 96830484 509673472 3.7881741524 4.1593384743 3.8312256336 604 1305031249.6542129517 0.2332654297 0.0811787132 0.2332654297 0.0437600763 0.0105550000 0.0005460000 0.0046290000 0.0000020000 0.0000150000 0.0017690000 16445465 96830484 509673472 3.7749218941 4.1775660515 3.8452436924 605 1305031249.6856739521 0.2289568484 0.0814229746 0.2332654297 0.0438793515 0.0085240000 0.0004300000 0.0042720000 0.0000060000 0.0000050000 0.0020540000 16449137 96830484 509673472 3.7734191418 4.1683907509 3.8485305309 606 1305031249.7177898884 0.2069893628 0.0816301798 0.2332654297 0.0440011631 0.0067910000 0.0003950000 0.0041760000 0.0000010000 0.0000040000 0.0010990000 16452809 96830484 509673472 3.7885830402 4.1582603455 3.8612051010 607 1305031249.7539620399 0.2078011483 0.0818380397 0.2332654297 0.0443410626 0.0080650000 0.0004610000 0.0043610000 0.0000010000 0.0000080000 0.0012580000 16456537 96830484 509673472 3.7885830402 4.1582603455 3.8612051010 608 1305031249.7854170799 0.2073510587 0.0820444756 0.2332654297 0.0445114463 0.0082930000 0.0004710000 0.0044170000 0.0000010000 0.0000080000 0.0012400000 16460153 96830484 509673472 3.7885830402 4.1582603455 3.8612051010 609 1305031249.8186020851 0.2078922242 0.0822511222 0.2332654297 0.0446404647 0.0089820000 0.0004700000 0.0044910000 0.0000000000 0.0000080000 0.0018490000 16463937 96830484 509673472 3.7885830402 4.1582603455 3.8612051010 610 1305031249.8537468910 0.0860207751 0.0822573019 0.2332654297 0.0468418590 0.0071330000 0.0004120000 0.0043690000 0.0000010000 0.0000060000 0.0010240000 16467609 96830484 509673472 3.9247808456 4.1236267090 3.9349930286 611 1305031249.8855249882 0.0829310119 0.0822584046 0.2332654297 0.0468974167 0.0082850000 0.0004610000 0.0045030000 0.0000090000 0.0000080000 0.0013980000 16471281 96830484 509673472 3.9309113026 4.1245956421 3.9431207180 612 1305031249.9170649052 0.0851867050 0.0822631894 0.2332654297 0.0468997714 0.0066280000 0.0003850000 0.0039800000 0.0000010000 0.0000050000 0.0009870000 16475009 96830484 509673472 3.9247581959 4.1191887856 3.9389865398 613 1305031249.9533979893 0.0889398530 0.0822740811 0.2332654297 0.0469011865 0.0073510000 0.0003690000 0.0042720000 0.0000050000 0.0000030000 0.0017130000 16478737 96830484 509673472 3.9189836979 4.1157050133 3.9354145527 614 1305031249.9851789474 0.0918211639 0.0822896301 0.2332654297 0.0468997176 0.0085150000 0.0004510000 0.0045270000 0.0000020000 0.0000100000 0.0013140000 16482409 96830484 509673472 3.9130508900 4.1141066551 3.9333465099 615 1305031250.0164399147 0.0940777957 0.0823087979 0.2332654297 0.0468818849 0.0067710000 0.0003980000 0.0036700000 0.0000050000 0.0000050000 0.0012450000 16486081 96830484 509673472 3.9101483822 4.1107745171 3.9314479828 616 1305031250.0531940460 0.0971682444 0.0823329204 0.2332654297 0.0469230786 0.0068980000 0.0003720000 0.0042820000 0.0000000000 0.0000060000 0.0009900000 16489865 96830484 509673472 3.9075355530 4.1041288376 3.9279227257 617 1305031250.0845069885 0.0994003564 0.0823605823 0.2332654297 0.0469740784 0.0067580000 0.0003670000 0.0036140000 0.0000040000 0.0000040000 0.0017380000 16493481 96830484 509673472 3.9043030739 4.1026048660 3.9270751476 618 1305031250.1208500862 0.0998716056 0.0823889173 0.2332654297 0.0470522566 0.0103020000 0.0005650000 0.0036880000 0.0000020000 0.0000150000 0.0016500000 16497321 96830484 509673472 3.8982834816 4.0996055603 3.9281060696 619 1305031250.1532480717 0.0988187939 0.0824154599 0.2332654297 0.0472481722 0.0080090000 0.0004620000 0.0044270000 0.0000090000 0.0000070000 0.0013190000 16500937 96830484 509673472 3.8962190151 4.0950984955 3.9312698841 620 1305031250.1853280067 0.0947826207 0.0824354070 0.2332654297 0.0472470295 0.0059560000 0.0003840000 0.0032910000 0.0000000000 0.0000040000 0.0009970000 16504553 96830484 509673472 3.8995244503 4.0873856544 3.9361534119 621 1305031250.2214460373 0.0926101655 0.0824517914 0.2332654297 0.0472511506 0.0063470000 0.0003570000 0.0032450000 0.0000050000 0.0000040000 0.0016670000 16508393 96830484 509673472 3.8926403522 4.0761079788 3.9382181168 622 1305031250.2537350655 0.0915763229 0.0824664611 0.2332654297 0.0473307459 0.0097840000 0.0005450000 0.0043860000 0.0000010000 0.0000150000 0.0015690000 16512065 96830484 509673472 3.8953335285 4.0730729103 3.9423162937 623 1305031250.2852239609 0.0917190090 0.0824813127 0.2332654297 0.0473355362 0.0078860000 0.0004290000 0.0044110000 0.0000070000 0.0000060000 0.0012390000 16515681 96830484 509673472 3.8968567848 4.0688891411 3.9444246292 624 1305031250.3208620548 0.0882050693 0.0824904854 0.2332654297 0.0473776674 0.0068170000 0.0003770000 0.0043270000 0.0000010000 0.0000050000 0.0009470000 16519409 96830484 509673472 3.8957662582 4.0668449402 3.9502193928 625 1305031250.3517000675 0.0862824842 0.0824965526 0.2332654297 0.0473979626 0.0072700000 0.0003590000 0.0042730000 0.0000050000 0.0000030000 0.0016850000 16523025 96830484 509673472 3.9002306461 4.0690698624 3.9554407597 626 1305031250.3851490021 0.0865169838 0.0825029750 0.2332654297 0.0474117509 0.0088170000 0.0004540000 0.0045640000 0.0000020000 0.0000110000 0.0012940000 16526697 96830484 509673472 3.8950607777 4.0654983521 3.9574704170 627 1305031250.4215359688 0.0894477218 0.0825140512 0.2332654297 0.0474209382 0.0075100000 0.0003990000 0.0043500000 0.0000060000 0.0000050000 0.0012360000 16530537 96830484 509673472 3.8915255070 4.0669002533 3.9560554028 628 1305031250.4540181160 0.0900733396 0.0825260882 0.2332654297 0.0474942973 0.0067780000 0.0003700000 0.0043070000 0.0000010000 0.0000040000 0.0009660000 16534321 96830484 509673472 3.8893036842 4.0691204071 3.9579656124 629 1305031250.4856131077 0.0905256793 0.0825388062 0.2332654297 0.0474917341 0.0072230000 0.0003580000 0.0042440000 0.0000040000 0.0000030000 0.0016630000 16537937 96830484 509673472 3.8891060352 4.0721697807 3.9600675106 630 1305031250.5215380192 0.0916857645 0.0825533252 0.2332654297 0.0474695249 0.0095310000 0.0005380000 0.0043940000 0.0000020000 0.0000150000 0.0015760000 16541777 96830484 509673472 3.8841841221 4.0718274117 3.9600908756 631 1305031250.5536580086 0.0939089432 0.0825713214 0.2332654297 0.0474532855 0.0077940000 0.0004280000 0.0044130000 0.0000060000 0.0000050000 0.0012600000 16545561 96830484 509673472 3.8794810772 4.0715646744 3.9603073597 632 1305031250.5853788853 0.0962328389 0.0825929377 0.2332654297 0.0474352656 0.0083140000 0.0004600000 0.0045000000 0.0000010000 0.0000070000 0.0011040000 16549233 96830484 509673472 3.8761672974 4.0754661560 3.9590549469 633 1305031250.6213030815 0.0980681628 0.0826173852 0.2332654297 0.0474136950 0.0077810000 0.0003990000 0.0043410000 0.0000050000 0.0000050000 0.0016830000 16553073 96830484 509673472 3.8745832443 4.0789380074 3.9590678215 634 1305031250.6535439491 0.0979309678 0.0826415391 0.2332654297 0.0474293779 0.0083060000 0.0004620000 0.0044890000 0.0000010000 0.0000080000 0.0010980000 16556913 96830484 509673472 3.8732621670 4.0799403191 3.9614174366 635 1305031250.6852970123 0.0955021828 0.0826617921 0.2332654297 0.0474439422 0.0071610000 0.0003840000 0.0042850000 0.0000060000 0.0000050000 0.0011750000 16560585 96830484 509673472 3.8780364990 4.0841083527 3.9664456844 636 1305031250.7216401100 0.0933497846 0.0826785971 0.2332654297 0.0474222439 0.0065430000 0.0003670000 0.0042360000 0.0000000000 0.0000030000 0.0009170000 16564425 96830484 509673472 3.8772277832 4.0853404999 3.9701154232 637 1305031250.7534279823 0.0933091342 0.0826952855 0.2332654297 0.0474001081 0.0071500000 0.0003540000 0.0042200000 0.0000040000 0.0000030000 0.0015880000 16568153 96830484 509673472 3.8675296307 4.0811543465 3.9715247154 638 1305031250.7853651047 0.0910049900 0.0827083101 0.2332654297 0.0473787328 0.0085030000 0.0005440000 0.0036660000 0.0000020000 0.0000150000 0.0012410000 16571881 96830484 509673472 3.8573505878 4.0718264580 3.9771180153 639 1305031250.8217930794 0.0910751447 0.0827214038 0.2332654297 0.0473465289 0.0076310000 0.0004370000 0.0043780000 0.0000060000 0.0000050000 0.0012190000 16575833 96830484 509673472 3.8536584377 4.0731682777 3.9776737690 640 1305031250.8538279533 0.0891216397 0.0827314041 0.2332654297 0.0473138260 0.0064000000 0.0003740000 0.0039320000 0.0000000000 0.0000040000 0.0009170000 16579617 96830484 509673472 3.8561286926 4.0748915672 3.9793636799 641 1305031250.8820140362 0.0893892497 0.0827417908 0.2332654297 0.0472786065 0.0071690000 0.0003630000 0.0042570000 0.0000040000 0.0000030000 0.0015730000 16583233 96830484 509673472 3.8555500507 4.0741081238 3.9796011448 642 1305031250.9217998981 0.0916490853 0.0827556651 0.2332654297 0.0472439477 0.0065260000 0.0003630000 0.0042670000 0.0000000000 0.0000040000 0.0008950000 16587185 96830484 509673472 3.8536279202 4.0737833977 3.9770443439 643 1305031250.9535419941 0.0936520994 0.0827726113 0.2332654297 0.0472219207 0.0103780000 0.0005770000 0.0047690000 0.0000160000 0.0000140000 0.0017120000 16590969 96830484 509673472 3.8497524261 4.0738902092 3.9738986492 644 1305031250.9853079319 0.0914291963 0.0827860532 0.2332654297 0.0471885355 0.0063220000 0.0004310000 0.0030560000 0.0000000000 0.0000060000 0.0009840000 16594641 96830484 509673472 3.8530659676 4.0735697746 3.9753799438 645 1305031251.0214879513 0.0914835259 0.0827995377 0.2332654297 0.0471650308 0.0075070000 0.0003880000 0.0043220000 0.0000050000 0.0000040000 0.0016150000 16598481 96830484 509673472 3.8550806046 4.0725612640 3.9746420383 646 1305031251.0534679890 0.0937622935 0.0828165079 0.2332654297 0.0471686814 0.0064870000 0.0003630000 0.0042730000 0.0000010000 0.0000030000 0.0008830000 16602209 96830484 509673472 3.8518610001 4.0698938370 3.9708485603 647 1305031251.0851860046 0.0926183239 0.0828316575 0.2332654297 0.0471611187 0.0107000000 0.0005430000 0.0047950000 0.0000160000 0.0000140000 0.0016900000 16605937 96830484 509673472 3.8532860279 4.0660963058 3.9704103470 648 1305031251.1214449406 0.0918399319 0.0828455592 0.2332654297 0.0471551478 0.0070260000 0.0004320000 0.0037450000 0.0000010000 0.0000060000 0.0009790000 16609777 96830484 509673472 3.8570871353 4.0635538101 3.9694888592 649 1305031251.1537809372 0.0889791846 0.0828550101 0.2332654297 0.0472243942 0.0066440000 0.0003880000 0.0033000000 0.0000050000 0.0000040000 0.0015960000 16613561 96830484 509673472 3.8633971214 4.0619902611 3.9690794945 650 1305031251.1851599216 0.0887323543 0.0828640521 0.2332654297 0.0472392867 0.0065730000 0.0003660000 0.0043070000 0.0000000000 0.0000040000 0.0009120000 16617233 96830484 509673472 3.8674879074 4.0568723679 3.9676940441 651 1305031251.2204658985 0.0857262462 0.0828684488 0.2332654297 0.0472428598 0.0067750000 0.0003580000 0.0043040000 0.0000040000 0.0000040000 0.0011350000 16621017 96830484 509673472 3.8732204437 4.0545454025 3.9683721066 652 1305031251.2524240017 0.0836201608 0.0828696017 0.2332654297 0.0472836369 0.0092230000 0.0005430000 0.0037220000 0.0000010000 0.0000150000 0.0015310000 16624689 96830484 509673472 3.8790771961 4.0514659882 3.9687244892 653 1305031251.2844820023 0.0843734816 0.0828719047 0.2332654297 0.0474485108 0.0083700000 0.0004230000 0.0044720000 0.0000080000 0.0000050000 0.0017340000 16628417 96830484 509673472 3.8830854893 4.0469007492 3.9657938480 654 1305031251.3190040588 0.0826586783 0.0828715787 0.2332654297 0.0475158478 0.0069150000 0.0003770000 0.0043740000 0.0000000000 0.0000050000 0.0009510000 16632201 96830484 509673472 3.8923478127 4.0452308655 3.9668323994 655 1305031251.3532440662 0.0796295479 0.0828666290 0.2332654297 0.0475726971 0.0067920000 0.0003610000 0.0043040000 0.0000040000 0.0000030000 0.0011350000 16635873 96830484 509673472 3.9005835056 4.0430674553 3.9693377018 656 1305031251.3870069981 0.0769555047 0.0828576182 0.2332654297 0.0475977328 0.0065900000 0.0003580000 0.0043260000 0.0000000000 0.0000030000 0.0009220000 16639601 96830484 509673472 3.9097254276 4.0444455147 3.9734303951 657 1305031251.4210500717 0.0791253075 0.0828519373 0.2332654297 0.0476764612 0.0073300000 0.0003600000 0.0043500000 0.0000040000 0.0000030000 0.0016070000 16643329 96830484 509673472 3.9123673439 4.0403265953 3.9699773788 658 1305031251.4496629238 0.0775804669 0.0828439260 0.2332654297 0.0477216749 0.0063480000 0.0003620000 0.0040320000 0.0000010000 0.0000040000 0.0009400000 16646889 96830484 509673472 3.9237029552 4.0408229828 3.9755582809 659 1305031251.4890139103 0.0752876997 0.0828324598 0.2332654297 0.0477939824 0.0067620000 0.0004130000 0.0038270000 0.0000040000 0.0000040000 0.0011950000 16650729 96830484 509673472 3.9298076630 4.0424523354 3.9780051708 660 1305031251.5207729340 0.0754659548 0.0828212984 0.2332654297 0.0478730365 0.0067500000 0.0003680000 0.0043420000 0.0000000000 0.0000040000 0.0009540000 16654457 96830484 509673472 3.9387516975 4.0442152023 3.9808342457 661 1305031251.5530450344 0.0752055272 0.0828097768 0.2332654297 0.0479593149 0.0063930000 0.0003610000 0.0033110000 0.0000040000 0.0000030000 0.0016600000 16658129 96830484 509673472 3.9446179867 4.0468740463 3.9813296795 662 1305031251.5887598991 0.0729297847 0.0827948524 0.2332654297 0.0479844149 0.0067400000 0.0003650000 0.0043520000 0.0000010000 0.0000040000 0.0009690000 16661857 96830484 509673472 3.9457008839 4.0540242195 3.9818704128 663 1305031251.6208739281 0.0721239522 0.0827787575 0.2332654297 0.0480121807 0.0069880000 0.0003610000 0.0043790000 0.0000040000 0.0000030000 0.0011930000 16665585 96830484 509673472 3.9501185417 4.0571618080 3.9846086502 664 1305031251.6528749466 0.0714179948 0.0827616479 0.2332654297 0.0480692899 0.0067630000 0.0003600000 0.0043740000 0.0000000000 0.0000030000 0.0009860000 16669257 96830484 509673472 3.9529957771 4.0615124702 3.9852635860 665 1305031251.6897680759 0.0712399185 0.0827443220 0.2332654297 0.0480977300 0.0104480000 0.0005500000 0.0037860000 0.0000160000 0.0000140000 0.0025940000 16673041 96830484 509673472 3.9537353516 4.0665040016 3.9850826263 666 1305031251.7204608917 0.0723256543 0.0827286783 0.2332654297 0.0481498427 0.0078800000 0.0004350000 0.0044960000 0.0000010000 0.0000060000 0.0010950000 16676713 96830484 509673472 3.9589650631 4.0667033195 3.9877481461 667 1305031251.7531440258 0.0757495314 0.0827182149 0.2332654297 0.0482353348 0.0059790000 0.0003920000 0.0029980000 0.0000050000 0.0000050000 0.0012620000 16680385 96830484 509673472 3.9672057629 4.0626931190 3.9893460274 668 1305031251.7892498970 0.0803201124 0.0827146249 0.2332654297 0.0482667978 0.0067680000 0.0003630000 0.0043490000 0.0000010000 0.0000030000 0.0010280000 16684169 96830484 509673472 3.9749472141 4.0662350655 3.9938404560 669 1305031251.8209791183 0.0832959190 0.0827154938 0.2332654297 0.0482959001 0.0113090000 0.0005500000 0.0045030000 0.0000150000 0.0000140000 0.0027150000 16687841 96830484 509673472 3.9815647602 4.0679965019 3.9993970394 670 1305031251.8537969589 0.0905586034 0.0827271999 0.2332654297 0.0484014808 0.0066540000 0.0004310000 0.0031090000 0.0000010000 0.0000060000 0.0011950000 16691513 96830484 509673472 3.9925529957 4.0653662682 4.0039038658 671 1305031251.8896539211 0.0994092152 0.0827520613 0.2332654297 0.0483933265 0.0074130000 0.0003950000 0.0043780000 0.0000050000 0.0000050000 0.0013650000 16695241 96830484 509673472 4.0035872459 4.0681700706 4.0103788376 672 1305031251.9219300747 0.1002766117 0.0827781395 0.2332654297 0.0483816860 0.0087990000 0.0004720000 0.0045680000 0.0000010000 0.0000080000 0.0013580000 16698969 96830484 509673472 4.0053763390 4.0776724815 4.0171108246 673 1305031251.9538369179 0.1001509950 0.0828039536 0.2332654297 0.0483814169 0.0074970000 0.0004070000 0.0036940000 0.0000060000 0.0000050000 0.0020020000 16702585 96830484 509673472 4.0056967735 4.0856127739 4.0215806961 674 1305031251.9898068905 0.1009887531 0.0828309340 0.2332654297 0.0483744106 0.0055660000 0.0003690000 0.0029480000 0.0000010000 0.0000030000 0.0011530000 16706369 96830484 509673472 4.0078744888 4.0880551338 4.0241746902 675 1305031252.0221600533 0.1024825051 0.0828600474 0.2332654297 0.0483912381 0.0106930000 0.0005480000 0.0040580000 0.0000160000 0.0000140000 0.0021530000 16710097 96830484 509673472 4.0106425285 4.0942378044 4.0280437469 676 1305031252.0537619591 0.1044124141 0.0828919296 0.2332654297 0.0483865926 0.0086770000 0.0004650000 0.0045580000 0.0000020000 0.0000080000 0.0014000000 16713769 96830484 509673472 4.0142755508 4.1061496735 4.0352153778 677 1305031252.0895619392 0.1027768627 0.0829213018 0.2332654297 0.0484257550 0.0065600000 0.0004170000 0.0026550000 0.0000060000 0.0000040000 0.0021000000 16717497 96830484 509673472 4.0126924515 4.1188907623 4.0364413261 678 1305031252.1221520901 0.0961408541 0.0829407996 0.2332654297 0.0484742337 0.0074180000 0.0004730000 0.0031590000 0.0000010000 0.0000100000 0.0014130000 16721225 96830484 509673472 4.0070824623 4.1275992393 4.0321135521 679 1305031252.1539709568 0.0925995484 0.0829550246 0.2332654297 0.0485790314 0.0076530000 0.0003890000 0.0044040000 0.0000060000 0.0000040000 0.0014770000 16724785 96830484 509673472 4.0037446022 4.1411967278 4.0304927826 680 1305031252.1897890568 0.0886255726 0.0829633636 0.2332654297 0.0485598566 0.0062680000 0.0003740000 0.0036170000 0.0000010000 0.0000040000 0.0011890000 16728569 96830484 509673472 3.9872720242 4.1622943878 4.0245347023 681 1305031252.2220859528 0.0868407190 0.0829690573 0.2332654297 0.0485360931 0.0102600000 0.0005510000 0.0043950000 0.0000110000 0.0000100000 0.0024720000 16732297 96830484 509673472 3.9706299305 4.1763596535 4.0187635422 682 1305031252.2530639172 0.0815831870 0.0829670252 0.2332654297 0.0485047466 0.0084840000 0.0004690000 0.0041960000 0.0000010000 0.0000070000 0.0014090000 16735969 96830484 509673472 3.9706299305 4.1763596535 4.0187635422 683 1305031252.2888779640 0.2305895984 0.0831831637 0.2332654297 0.0498684010 0.0073200000 0.0004310000 0.0041050000 0.0000050000 0.0000050000 0.0013300000 16739641 96830484 509673472 3.7716100216 4.1901955605 3.8967432976 684 1305031252.3206090927 0.3126302063 0.0835186126 0.3126302063 0.0502917928 0.0083490000 0.0004730000 0.0042830000 0.0000010000 0.0000070000 0.0012330000 16743313 96830484 509673472 3.7116048336 4.1669673920 3.8282907009 685 1305031252.3528549671 0.3846664727 0.0839582445 0.3846664727 0.0505024668 0.0077450000 0.0004040000 0.0039970000 0.0000070000 0.0000050000 0.0019320000 16746929 96830484 509673472 3.6562058926 4.1631026268 3.7816720009 686 1305031252.3893189430 0.3973528743 0.0844150879 0.3973528743 0.0505070314 0.0065720000 0.0003700000 0.0040010000 0.0000010000 0.0000040000 0.0010950000 16750713 96830484 509673472 3.6504404545 4.1582365036 3.7679221630 687 1305031252.4217019081 0.3968003094 0.0848697972 0.3973528743 0.0504987581 0.0093900000 0.0005480000 0.0044390000 0.0000110000 0.0000090000 0.0016240000 16754441 96830484 509673472 3.6521084309 4.1621360779 3.7665607929 688 1305031252.4538249969 0.4106373191 0.0853432965 0.4106373191 0.0504889296 0.0072630000 0.0004140000 0.0040750000 0.0000000000 0.0000050000 0.0011410000 16758113 96830484 509673472 3.6408078671 4.1634206772 3.7561955452 689 1305031252.4895589352 0.4034168124 0.0858049416 0.4106373191 0.0504554565 0.0079200000 0.0004370000 0.0040800000 0.0000050000 0.0000040000 0.0019700000 16761785 96830484 509673472 3.6463363171 4.1680622101 3.7609374523 690 1305031252.5221700668 0.4188123047 0.0862875610 0.4188123047 0.0504316734 0.0083680000 0.0004760000 0.0042110000 0.0000010000 0.0000080000 0.0012600000 16765513 96830484 509673472 3.6323332787 4.1657605171 3.7514483929 691 1305031252.5537741184 0.4619401395 0.0868311971 0.4619401395 0.0504050069 0.0086250000 0.0004720000 0.0041880000 0.0000080000 0.0000080000 0.0015120000 16769185 96830484 509673472 3.5955810547 4.1645784378 3.7260873318 692 1305031252.5897459984 0.4542514980 0.0873621513 0.4619401395 0.0503714248 0.0070730000 0.0004110000 0.0040260000 0.0000010000 0.0000050000 0.0011700000 16772913 96830484 509673472 3.6024980545 4.1669626236 3.7299847603 693 1305031252.6221249104 0.4195635915 0.0878415185 0.4619401395 0.0503425586 0.0091630000 0.0004620000 0.0042000000 0.0000080000 0.0000080000 0.0022080000 16776641 96830484 509673472 3.6327328682 4.1656117439 3.7481138706 694 1305031252.6578559875 0.3834852278 0.0882675181 0.4619401395 0.0503142867 0.0070330000 0.0003910000 0.0040390000 0.0000010000 0.0000050000 0.0011570000 16780369 96830484 509673472 3.6641247272 4.1664590836 3.7686223984 695 1305031252.6889979839 0.3767819703 0.0886826468 0.4619401395 0.0503284577 0.0068780000 0.0003730000 0.0039820000 0.0000040000 0.0000040000 0.0013800000 16783985 96830484 509673472 3.6688797474 4.1624050140 3.7720546722 696 1305031252.7216539383 0.3647030592 0.0890792278 0.4619401395 0.0504159747 0.0089870000 0.0004680000 0.0043250000 0.0000020000 0.0000100000 0.0014400000 16787657 96830484 509673472 3.6752560139 4.1582822800 3.7803585529 697 1305031252.7578220367 0.3568819165 0.0894634498 0.4619401395 0.0505957285 0.0082690000 0.0004130000 0.0041900000 0.0000050000 0.0000050000 0.0019960000 16791497 96830484 509673472 3.6763467789 4.1544547081 3.7869100571 698 1305031252.7896919250 0.3773628473 0.0898759131 0.4619401395 0.0507364911 0.0067780000 0.0003850000 0.0041190000 0.0000010000 0.0000040000 0.0010950000 16795113 96830484 509673472 3.6548726559 4.1487569809 3.7760307789 699 1305031252.8224050999 0.4031242728 0.0903240509 0.4619401395 0.0509148664 0.0084380000 0.0004730000 0.0043140000 0.0000080000 0.0000070000 0.0014850000 16798841 96830484 509673472 3.6292808056 4.1449556351 3.7630980015 700 1305031252.8539779186 0.4191929400 0.0907938636 0.4619401395 0.0509253714 0.0084520000 0.0004620000 0.0042710000 0.0000000000 0.0000080000 0.0012350000 16802401 96830484 509673472 3.6148090363 4.1371860504 3.7529311180 701 1305031252.8897290230 0.4360168576 0.0912863358 0.4619401395 0.0509321002 0.0078270000 0.0004040000 0.0040410000 0.0000050000 0.0000050000 0.0019260000 16806185 96830484 509673472 3.5997505188 4.1243257523 3.7419750690 702 1305031252.9206719398 0.4249268174 0.0917616071 0.4619401395 0.0509865537 0.0066080000 0.0003750000 0.0040130000 0.0000000000 0.0000040000 0.0010670000 16809857 96830484 509673472 3.6075882912 4.1224083900 3.7481706142 703 1305031252.9578649998 0.4388436377 0.0922553227 0.4619401395 0.0511110254 0.0067990000 0.0003670000 0.0040040000 0.0000030000 0.0000030000 0.0012970000 16813753 96830484 509673472 3.5910382271 4.1153864861 3.7416329384 704 1305031252.9894239902 0.4616632462 0.0927800499 0.4619401395 0.0512372935 0.0065410000 0.0003660000 0.0040120000 0.0000010000 0.0000040000 0.0010610000 16817313 96830484 509673472 3.5656263828 4.1103525162 3.7329392433 705 1305031253.0196959972 0.4539781809 0.0932923876 0.4619401395 0.0513696226 0.0109960000 0.0005480000 0.0045100000 0.0000160000 0.0000140000 0.0025470000 16820985 96830484 509673472 3.5662531853 4.1032738686 3.7407259941 706 1305031253.0574259758 0.4642350972 0.0938178022 0.4642350972 0.0514380596 0.0075440000 0.0004340000 0.0041400000 0.0000010000 0.0000060000 0.0011370000 16824825 96830484 509673472 3.5534918308 4.0883445740 3.7362601757 707 1305031253.0895500183 0.4618287683 0.0943383269 0.4642350972 0.0514953396 0.0070060000 0.0003820000 0.0040040000 0.0000050000 0.0000040000 0.0012970000 16828441 96830484 509673472 3.5531895161 4.0749397278 3.7372236252 708 1305031253.1197240353 0.4726847708 0.0948727146 0.4726847708 0.0515601793 0.0064720000 0.0003640000 0.0039550000 0.0000010000 0.0000030000 0.0010570000 16832113 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 709 1305031253.1573839188 0.4703398347 0.0954022874 0.4726847708 0.0515416100 0.0098880000 0.0005480000 0.0044100000 0.0000010000 0.0000100000 0.0020850000 16835897 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 710 1305031253.1892180443 0.4697793424 0.0959295790 0.4726847708 0.0515151809 0.0072590000 0.0004120000 0.0040420000 0.0000010000 0.0000050000 0.0010910000 16839513 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 711 1305031253.2180271149 0.4694898129 0.0964549802 0.4726847708 0.0514977591 0.0066950000 0.0003760000 0.0039840000 0.0000010000 0.0000040000 0.0010690000 16843185 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 712 1305031253.2578470707 0.4694136381 0.0969787985 0.4726847708 0.0515142349 0.0085200000 0.0004930000 0.0042900000 0.0000010000 0.0000070000 0.0012160000 16847081 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 713 1305031253.2897419930 0.4698969126 0.0975018253 0.4726847708 0.0514926063 0.0077830000 0.0003990000 0.0041320000 0.0000010000 0.0000050000 0.0017580000 16850697 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 714 1305031253.3220069408 0.4704389274 0.0980241462 0.4726847708 0.0514633149 0.0081680000 0.0004670000 0.0043160000 0.0000010000 0.0000080000 0.0012640000 16854425 96830484 509673472 3.5405383110 4.0733790398 3.7319507599 715 1305031253.3578300476 0.0700151771 0.0979849728 0.4726847708 0.0540605052 0.0072550000 0.0003890000 0.0041660000 0.0000050000 0.0000040000 0.0012120000 16858153 96830484 509673472 3.9473321438 4.0807762146 4.0086960793 716 1305031253.3880970478 0.0689331144 0.0979443976 0.4726847708 0.0540236831 0.0088120000 0.0004610000 0.0045840000 0.0000010000 0.0000080000 0.0011980000 16861769 96830484 509673472 3.9444797039 4.0855312347 4.0069546700 717 1305031253.4213519096 0.0710273087 0.0979068563 0.4726847708 0.0539874437 0.0068460000 0.0004090000 0.0030180000 0.0000050000 0.0000050000 0.0018120000 16865497 96830484 509673472 3.9473843575 4.0843830109 4.0085501671 718 1305031253.4579629898 0.0716356784 0.0978702669 0.4726847708 0.0539518058 0.0087570000 0.0004590000 0.0045520000 0.0000020000 0.0000080000 0.0012300000 16869281 96830484 509673472 3.9472060204 4.0854969025 4.0095558167 719 1305031253.4896900654 0.0699086338 0.0978313773 0.4726847708 0.0539147005 0.0061530000 0.0003870000 0.0029750000 0.0000060000 0.0000050000 0.0012790000 16872953 96830484 509673472 3.9431777000 4.0884361267 4.0092344284 720 1305031253.5207340717 0.0706662014 0.0977936479 0.4726847708 0.0538791345 0.0065540000 0.0003720000 0.0039480000 0.0000000000 0.0000040000 0.0010390000 16876625 96830484 509673472 3.9424409866 4.0858144760 4.0079932213 721 1305031253.5578539371 0.0708601251 0.0977562921 0.4726847708 0.0538440481 0.0112660000 0.0005510000 0.0029690000 0.0000180000 0.0000140000 0.0026780000 16880409 96830484 509673472 3.9392216206 4.0876555443 4.0064563751 722 1305031253.5898048878 0.0683706105 0.0977155917 0.4726847708 0.0538124294 0.0065360000 0.0004360000 0.0027020000 0.0000020000 0.0000080000 0.0012380000 16884081 96830484 509673472 3.9365756512 4.0905156136 4.0100007057 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:23:14 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253987648 0.0253987648 0.0253987648 -nan 0.0032440000 0.0004030000 0.0004830000 0.0000050000 0.0000010000 0.0021610000 13136893 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 1305031102.2112140656 0.0277590584 0.0265789116 0.0277590584 0.0329535045 0.0015380000 0.0003570000 0.0004740000 0.0000030000 0.0000010000 0.0006680000 13927469 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 1305031102.2432110310 0.0337214470 0.0289597567 0.0337214470 0.0304149093 0.0015650000 0.0003600000 0.0004740000 0.0000040000 0.0000000000 0.0006780000 13931533 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 1305031102.2753260136 0.0413634107 0.0320606702 0.0413634107 0.0283056841 0.0020780000 0.0003570000 0.0004730000 0.0000030000 0.0000050000 0.0011920000 13935605 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 1305031102.3112668991 0.0195331685 0.0295551699 0.0413634107 0.0301324792 0.0050900000 0.0003590000 0.0028630000 0.0000030000 0.0000030000 0.0018110000 13939773 96830484 509673472 3.9956095219 3.9985203743 4.0339021683 6 1305031102.3432331085 0.0165484399 0.0273873815 0.0413634107 0.0279491838 0.0039190000 0.0003590000 0.0025050000 0.0000010000 0.0000040000 0.0009980000 13944245 96830484 509673472 3.9933295250 3.9974973202 4.0460605621 7 1305031102.3753290176 0.0143032754 0.0255182235 0.0413634107 0.0256321107 0.0051120000 0.0005400000 0.0025490000 0.0000150000 0.0000130000 0.0017590000 13947861 96830484 509673472 3.9915521145 3.9987490177 4.0578470230 8 1305031102.4112579823 0.0161144640 0.0243427536 0.0413634107 0.0248949774 0.0048600000 0.0005410000 0.0025350000 0.0000020000 0.0000150000 0.0015290000 13951701 96830484 509673472 3.9903874397 4.0006742477 4.0697317123 9 1305031102.4432709217 0.0140173724 0.0231954890 0.0413634107 0.0252536670 0.0061580000 0.0005190000 0.0029150000 0.0000140000 0.0000130000 0.0024490000 13956141 96830484 509673472 3.9873261452 4.0034246445 4.0821051598 10 1305031102.4753179550 0.0116291679 0.0220388569 0.0413634107 0.0240298461 0.0048530000 0.0005200000 0.0025650000 0.0000020000 0.0000150000 0.0015030000 13961357 96830484 509673472 3.9876585007 4.0076665878 4.0952625275 11 1305031102.5112190247 0.0164511818 0.0215308864 0.0413634107 0.0234071341 0.0057120000 0.0005250000 0.0032250000 0.0000150000 0.0000130000 0.0016840000 13965141 96830484 509673472 3.9873974323 4.0066890717 4.1077733040 12 1305031102.5432200432 0.0179960988 0.0212363208 0.0413634107 0.0223192078 0.0061550000 0.0005270000 0.0035980000 0.0000020000 0.0000140000 0.0017430000 13968869 96830484 509673472 3.9864895344 4.0065875053 4.1198072433 13 1305031102.5752859116 0.0202837195 0.0211630438 0.0413634107 0.0221571619 0.0077040000 0.0006020000 0.0046610000 0.0000150000 0.0000140000 0.0022190000 13972485 96830484 509673472 3.9834952354 4.0057687759 4.1314301491 14 1305031102.6112329960 0.0283714719 0.0216779315 0.0413634107 0.0226168808 0.0044780000 0.0004530000 0.0029900000 0.0000010000 0.0000060000 0.0009150000 13976269 96830484 509673472 3.9842815399 4.0026235580 4.1424007416 15 1305031102.6432650089 0.0308774840 0.0222912350 0.0413634107 0.0225186248 0.0046020000 0.0003970000 0.0029530000 0.0000070000 0.0000050000 0.0011260000 13979941 96830484 509673472 3.9798064232 4.0030684471 4.1535334587 16 1305031102.6752851009 0.0282426793 0.0226632003 0.0413634107 0.0223311391 0.0040370000 0.0003960000 0.0026270000 0.0000010000 0.0000060000 0.0008910000 13983613 96830484 509673472 3.9764451981 4.0097107887 4.1653304100 17 1305031102.7112629414 0.0316483639 0.0231917393 0.0413634107 0.0218740086 0.0064230000 0.0003920000 0.0043290000 0.0000060000 0.0000060000 0.0015700000 13988933 96830484 509673472 3.9767310619 4.0127487183 4.1776719093 18 1305031102.7432339191 0.0347460806 0.0238336472 0.0413634107 0.0212920904 0.0054510000 0.0005270000 0.0032710000 0.0000020000 0.0000150000 0.0013400000 13995861 96830484 509673472 3.9764158726 4.0140295029 4.1902990341 19 1305031102.7754719257 0.0331624523 0.0243246369 0.0413634107 0.0211175882 0.0053490000 0.0005310000 0.0029390000 0.0000140000 0.0000130000 0.0015520000 13999477 96830484 509673472 3.9771006107 4.0198845863 4.2032289505 20 1305031102.8112320900 0.0379258320 0.0250046967 0.0413634107 0.0206050021 0.0055020000 0.0005280000 0.0032970000 0.0000020000 0.0000150000 0.0013540000 14003261 96830484 509673472 3.9762506485 4.0221452713 4.2156362534 21 1305031102.8432900906 0.0389914475 0.0256707324 0.0413634107 0.0201104210 0.0076520000 0.0005250000 0.0047580000 0.0000150000 0.0000120000 0.0020270000 14006989 96830484 509673472 3.9772071838 4.0255956650 4.2280068398 22 1305031102.8753631115 0.0411741994 0.0263754355 0.0413634107 0.0196935103 0.0051430000 0.0005220000 0.0033120000 0.0000010000 0.0000140000 0.0010760000 14010605 96830484 509673472 3.9740698338 4.0273656845 4.2397809029 23 1305031102.9111850262 0.0446477346 0.0271698833 0.0446477346 0.0192971569 0.0054190000 0.0004130000 0.0037420000 0.0000070000 0.0000060000 0.0010910000 14014389 96830484 509673472 3.9713399410 4.0299901962 4.2513952255 24 1305031102.9432289600 0.0453444384 0.0279271564 0.0453444384 0.0191875263 0.0061890000 0.0005310000 0.0040420000 0.0000020000 0.0000150000 0.0012730000 14018117 96830484 509673472 3.9698414803 4.0335536003 4.2626962662 25 1305031102.9752030373 0.0475494377 0.0287120476 0.0475494377 0.0198968655 0.0065730000 0.0005240000 0.0036920000 0.0000140000 0.0000130000 0.0019960000 14021677 96830484 509673472 3.9654788971 4.0359358788 4.2742691040 26 1305031103.0112149715 0.0510677099 0.0295718808 0.0510677099 0.0195053617 0.0062800000 0.0004540000 0.0046000000 0.0000010000 0.0000100000 0.0009890000 14025517 96830484 509673472 3.9648528099 4.0385985374 4.2861418724 27 1305031103.0432269573 0.0534253307 0.0304553419 0.0534253307 0.0191398532 0.0061290000 0.0004180000 0.0044990000 0.0000070000 0.0000070000 0.0010550000 14029245 96830484 509673472 3.9658606052 4.0412397385 4.2976827621 28 1305031103.0753190517 0.0555746518 0.0313524601 0.0555746518 0.0193328588 0.0054690000 0.0005300000 0.0033050000 0.0000020000 0.0000160000 0.0012470000 14032861 96830484 509673472 3.9671397209 4.0437283516 4.3083167076 29 1305031103.1112399101 0.0594786853 0.0323223300 0.0594786853 0.0191764948 0.0065570000 0.0005500000 0.0036630000 0.0000150000 0.0000140000 0.0019550000 14036645 96830484 509673472 3.9668579102 4.0455875397 4.3178997040 30 1305031103.1433179379 0.0581859276 0.0331844499 0.0594786853 0.0188724888 0.0069520000 0.0005270000 0.0047730000 0.0000020000 0.0000140000 0.0012760000 14040317 96830484 509673472 3.9674296379 4.0516200066 4.3274426460 31 1305031103.1754519939 0.0602703467 0.0340581885 0.0602703467 0.0185723416 0.0072050000 0.0005460000 0.0047850000 0.0000150000 0.0000140000 0.0014600000 14043989 96830484 509673472 3.9663927555 4.0536746979 4.3364033699 32 1305031103.2112200260 0.0610791631 0.0349025939 0.0610791631 0.0190973273 0.0062720000 0.0005430000 0.0040410000 0.0000020000 0.0000160000 0.0012830000 14047773 96830484 509673472 3.9658830166 4.0586476326 4.3452482224 33 1305031103.2432160378 0.0621665791 0.0357287753 0.0621665791 0.0188195768 0.0069920000 0.0005540000 0.0040360000 0.0000140000 0.0000150000 0.0019660000 14054573 96830484 509673472 3.9667530060 4.0620617867 4.3542551994 34 1305031103.2753698826 0.0650224090 0.0365903528 0.0650224090 0.0188536840 0.0056970000 0.0005620000 0.0037100000 0.0000020000 0.0000140000 0.0011230000 14064589 96830484 509673472 3.9674243927 4.0629830360 4.3626966476 35 1305031103.3112099171 0.0700994581 0.0375477558 0.0700994581 0.0192337816 0.0043770000 0.0004210000 0.0026880000 0.0000070000 0.0000070000 0.0010510000 14068373 96830484 509673472 3.9659137726 4.0604453087 4.3701758385 36 1305031103.3432230949 0.0758346394 0.0386112803 0.0758346394 0.0198386053 0.0070470000 0.0006240000 0.0047520000 0.0000020000 0.0000170000 0.0012120000 14072101 96830484 509673472 3.9654386044 4.0556082726 4.3751111031 37 1305031103.3753271103 0.0763668492 0.0396317011 0.0763668492 0.0197990422 0.0062000000 0.0005880000 0.0032610000 0.0000140000 0.0000140000 0.0018940000 14075717 96830484 509673472 3.9692049026 4.0556783676 4.3777923584 38 1305031103.4112598896 0.0775985792 0.0406308295 0.0775985792 0.0196909668 0.0058010000 0.0005310000 0.0035930000 0.0000020000 0.0000140000 0.0012280000 14079501 96830484 509673472 3.9701254368 4.0531787872 4.3786320686 39 1305031103.4432799816 0.0807400197 0.0416592702 0.0807400197 0.0195189872 0.0056940000 0.0004550000 0.0037750000 0.0000110000 0.0000080000 0.0011610000 14083229 96830484 509673472 3.9694423676 4.0481290817 4.3773789406 40 1305031103.4752740860 0.0811274201 0.0426459740 0.0811274201 0.0192862609 0.0044660000 0.0004580000 0.0027490000 0.0000010000 0.0000100000 0.0009610000 14086845 96830484 509673472 3.9697213173 4.0450778008 4.3745708466 41 1305031103.5113329887 0.0811965093 0.0435862310 0.0811965093 0.0191503017 0.0065160000 0.0004560000 0.0041830000 0.0000100000 0.0000090000 0.0015700000 14090629 96830484 509673472 3.9700074196 4.0407757759 4.3698401451 42 1305031103.5434439182 0.0811142325 0.0444797548 0.0811965093 0.0190238038 0.0069630000 0.0005310000 0.0047250000 0.0000010000 0.0000140000 0.0012530000 14094357 96830484 509673472 3.9699914455 4.0357689857 4.3631567955 43 1305031103.5754740238 0.0802898780 0.0453125484 0.0811965093 0.0188447384 0.0061060000 0.0005310000 0.0036490000 0.0000150000 0.0000130000 0.0014600000 14097973 96830484 509673472 3.9710965157 4.0310363770 4.3548965454 44 1305031103.6112229824 0.0770353973 0.0460335222 0.0811965093 0.0187143310 0.0055770000 0.0005270000 0.0033360000 0.0000020000 0.0000130000 0.0012490000 14101757 96830484 509673472 3.9728920460 4.0282764435 4.3457398415 45 1305031103.6434450150 0.0753280148 0.0466845109 0.0811965093 0.0185059980 0.0058780000 0.0004560000 0.0034840000 0.0000100000 0.0000110000 0.0016120000 14105485 96830484 509673472 3.9738070965 4.0236849785 4.3359355927 46 1305031103.6755230427 0.0724244937 0.0472440758 0.0811965093 0.0183347242 0.0056400000 0.0004210000 0.0041050000 0.0000010000 0.0000070000 0.0008760000 14109101 96830484 509673472 3.9728190899 4.0198326111 4.3255743980 47 1305031103.7116100788 0.0688742995 0.0477042933 0.0811965093 0.0181523716 0.0052090000 0.0004190000 0.0034250000 0.0000080000 0.0000080000 0.0011110000 14112885 96830484 509673472 3.9738509655 4.0162053108 4.3144388199 48 1305031103.7433259487 0.0657903552 0.0480810863 0.0811965093 0.0180070056 0.0053500000 0.0005270000 0.0029890000 0.0000020000 0.0000140000 0.0013390000 14116613 96830484 509673472 3.9764883518 4.0123662949 4.3024878502 49 1305031103.7753419876 0.0637665316 0.0484011974 0.0811965093 0.0178198511 0.0065240000 0.0005280000 0.0033410000 0.0000140000 0.0000120000 0.0021340000 14120229 96830484 509673472 3.9763774872 4.0067248344 4.2898945808 50 1305031103.8112421036 0.0589137189 0.0486114478 0.0811965093 0.0180198094 0.0072010000 0.0005270000 0.0048130000 0.0000030000 0.0000140000 0.0013540000 14124013 96830484 509673472 3.9775798321 4.0048761368 4.2767825127 51 1305031103.8432509899 0.0549918897 0.0487365545 0.0811965093 0.0180059903 0.0066550000 0.0004530000 0.0045510000 0.0000100000 0.0000090000 0.0013020000 14127741 96830484 509673472 3.9790356159 4.0025854111 4.2640271187 52 1305031103.8753609657 0.0524206422 0.0488074024 0.0811965093 0.0179491745 0.0062380000 0.0004580000 0.0045340000 0.0000010000 0.0000080000 0.0009840000 14131357 96830484 509673472 3.9783596992 3.9991414547 4.2519979477 53 1305031103.9112210274 0.0556625500 0.0489367448 0.0811965093 0.0188995695 0.0069050000 0.0005280000 0.0036230000 0.0000150000 0.0000140000 0.0022150000 14135141 96830484 509673472 3.9783575535 3.9886143208 4.2391419411 54 1305031103.9432110786 0.0558765978 0.0490652606 0.0811965093 0.0187672012 0.0061960000 0.0004540000 0.0044670000 0.0000010000 0.0000070000 0.0010070000 14138869 96830484 509673472 3.9791555405 3.9813926220 4.2256288528 55 1305031103.9753730297 0.0519678183 0.0491180343 0.0811965093 0.0187076146 0.0064240000 0.0004550000 0.0044660000 0.0000070000 0.0000060000 0.0012240000 14142541 96830484 509673472 3.9803013802 3.9784507751 4.2111082077 56 1305031104.0112318993 0.0503385104 0.0491398286 0.0811965093 0.0189031086 0.0057940000 0.0005330000 0.0032870000 0.0000020000 0.0000150000 0.0014290000 14146269 96830484 509673472 3.9830539227 3.9732372761 4.1966252327 57 1305031104.0432488918 0.0481104068 0.0491217685 0.0811965093 0.0188414009 0.0078010000 0.0005260000 0.0047300000 0.0000150000 0.0000120000 0.0021540000 14149997 96830484 509673472 3.9865753651 3.9676582813 4.1817440987 58 1305031104.0754249096 0.0415146127 0.0489906107 0.0811965093 0.0188768792 0.0048030000 0.0004200000 0.0030520000 0.0000010000 0.0000080000 0.0010520000 14153613 96830484 509673472 3.9870052338 3.9672541618 4.1664223671 59 1305031104.1112349033 0.0357050300 0.0487654313 0.0811965093 0.0188046999 0.0062050000 0.0004020000 0.0043780000 0.0000060000 0.0000050000 0.0011800000 14157397 96830484 509673472 3.9883944988 3.9667241573 4.1516180038 60 1305031104.1432299614 0.0334548540 0.0485102550 0.0811965093 0.0187606396 0.0058500000 0.0005290000 0.0032960000 0.0000020000 0.0000190000 0.0014470000 14161125 96830484 509673472 3.9907019138 3.9611420631 4.1371164322 61 1305031104.1754240990 0.0298940595 0.0482050715 0.0811965093 0.0187043848 0.0072080000 0.0005270000 0.0040320000 0.0000140000 0.0000150000 0.0022330000 14164741 96830484 509673472 3.9872705936 3.9578220844 4.1231231689 62 1305031104.2112829685 0.0269866232 0.0478628385 0.0811965093 0.0186048385 0.0051990000 0.0004730000 0.0031340000 0.0000010000 0.0000100000 0.0012000000 14168525 96830484 509673472 3.9878978729 3.9558768272 4.1095046997 63 1305031104.2431960106 0.0239972398 0.0474840194 0.0811965093 0.0184819104 0.0061010000 0.0004550000 0.0038240000 0.0000100000 0.0000080000 0.0014190000 14172253 96830484 509673472 3.9890930653 3.9524769783 4.0963754654 64 1305031104.2755460739 0.0197022911 0.0470499299 0.0811965093 0.0183431273 0.0069890000 0.0005300000 0.0047950000 0.0000020000 0.0000140000 0.0012570000 14175869 96830484 509673472 3.9895734787 3.9513254166 4.0832118988 65 1305031104.3112189770 0.0164034367 0.0465784454 0.0811965093 0.0182450439 0.0057670000 0.0004630000 0.0027850000 0.0000120000 0.0000090000 0.0020910000 14185797 96830484 509673472 3.9910230637 3.9509201050 4.0705366135 66 1305031104.3433420658 0.0120346053 0.0460550539 0.0811965093 0.0181470880 0.0052430000 0.0004250000 0.0034030000 0.0000010000 0.0000080000 0.0011020000 14202325 96830484 509673472 3.9924733639 3.9502434731 4.0582623482 67 1305031104.3758370876 0.0093889795 0.0455077991 0.0811965093 0.0180733316 0.0059060000 0.0005300000 0.0029470000 0.0000160000 0.0000130000 0.0018080000 14205941 96830484 509673472 3.9931848049 3.9502398968 4.0463914871 68 1305031104.4115090370 0.0065578562 0.0449350058 0.0811965093 0.0180054214 0.0063630000 0.0005290000 0.0036500000 0.0000020000 0.0000140000 0.0015730000 14209725 96830484 509673472 3.9933609962 3.9497370720 4.0350332260 69 1305031104.4432880878 0.0045663570 0.0443499529 0.0811965093 0.0179306691 0.0065750000 0.0005260000 0.0029210000 0.0000140000 0.0000150000 0.0025760000 14213397 96830484 509673472 3.9936506748 3.9486737251 4.0246367455 70 1305031104.4754559994 0.0045673465 0.0437816300 0.0811965093 0.0178549072 0.0046200000 0.0004500000 0.0024210000 0.0000010000 0.0000110000 0.0013290000 14217069 96830484 509673472 3.9928319454 3.9481432438 4.0151948929 71 1305031104.5113289356 0.0073851417 0.0432690034 0.0811965093 0.0179347906 0.0062560000 0.0004520000 0.0038000000 0.0000100000 0.0000100000 0.0015530000 14220853 96830484 509673472 3.9901483059 3.9458870888 4.0059685707 72 1305031104.5433681011 0.0059270533 0.0427503652 0.0811965093 0.0179056228 0.0053840000 0.0004550000 0.0031570000 0.0000010000 0.0000110000 0.0013440000 14224581 96830484 509673472 3.9909369946 3.9422233105 3.9962768555 73 1305031104.5753428936 0.0045432854 0.0422269805 0.0811965093 0.0180119956 0.0062590000 0.0004570000 0.0031170000 0.0000100000 0.0000080000 0.0022490000 14228141 96830484 509673472 3.9940152168 3.9403171539 3.9862954617 74 1305031104.6113359928 0.0067798891 0.0417479658 0.0811965093 0.0186922486 0.0043070000 0.0005250000 0.0025840000 0.0000000000 0.0000030000 0.0010490000 14231981 96830484 509673472 3.9984571934 3.9357645512 3.9751853943 75 1305031104.6432430744 0.0103741139 0.0413296477 0.0811965093 0.0186892506 0.0043570000 0.0003570000 0.0025470000 0.0000040000 0.0000030000 0.0013040000 14235653 96830484 509673472 4.0061931610 3.9320588112 3.9621174335 76 1305031104.6755249500 0.0169395506 0.0410087254 0.0811965093 0.0185706314 0.0041530000 0.0003600000 0.0025660000 0.0000000000 0.0000040000 0.0010770000 14239325 96830484 509673472 4.0107893944 3.9379541874 3.9479658604 77 1305031104.7112770081 0.0213630125 0.0407535863 0.0811965093 0.0187540497 0.0049570000 0.0003620000 0.0025200000 0.0000030000 0.0000020000 0.0019210000 14243109 96830484 509673472 4.0135140419 3.9396564960 3.9331431389 78 1305031104.7432799339 0.0287972223 0.0406002996 0.0811965093 0.0186540704 0.0078160000 0.0005370000 0.0047890000 0.0000020000 0.0000160000 0.0018030000 14246781 96830484 509673472 4.0140395164 3.9449841976 3.9176816940 79 1305031104.7753269672 0.0388388522 0.0405780028 0.0811965093 0.0185577785 0.0075500000 0.0005360000 0.0043070000 0.0000140000 0.0000130000 0.0020120000 14250397 96830484 509673472 4.0167222023 3.9519088268 3.9037456512 80 1305031104.8114650249 0.0465800501 0.0406530284 0.0811965093 0.0184874064 0.0062810000 0.0004560000 0.0038200000 0.0000010000 0.0000100000 0.0015400000 14254237 96830484 509673472 4.0193457603 3.9573674202 3.8916373253 81 1305031104.8432579041 0.0574015938 0.0408598008 0.0811965093 0.0183977272 0.0063750000 0.0004210000 0.0033210000 0.0000080000 0.0000060000 0.0022730000 14257909 96830484 509673472 4.0245218277 3.9649987221 3.8812346458 82 1305031104.8753499985 0.0631006733 0.0411310309 0.0811965093 0.0184197300 0.0063250000 0.0004050000 0.0043300000 0.0000010000 0.0000060000 0.0012950000 14261581 96830484 509673472 4.0253348351 3.9699344635 3.8749635220 83 1305031104.9115340710 0.0690760911 0.0414677184 0.0811965093 0.0183531638 0.0051930000 0.0004030000 0.0029530000 0.0000060000 0.0000060000 0.0015380000 14265365 96830484 509673472 4.0270199776 3.9757661819 3.8711888790 84 1305031104.9432621002 0.0730758011 0.0418440051 0.0811965093 0.0182496704 0.0063450000 0.0004030000 0.0043290000 0.0000010000 0.0000060000 0.0013160000 14269037 96830484 509673472 4.0282540321 3.9795072079 3.8702900410 85 1305031104.9752020836 0.0746967122 0.0422305075 0.0811965093 0.0182269853 0.0065340000 0.0003950000 0.0036210000 0.0000060000 0.0000050000 0.0022160000 14272709 96830484 509673472 4.0284028053 3.9818019867 3.8721165657 86 1305031105.0112900734 0.0784286410 0.0426514161 0.0811965093 0.0182971961 0.0053360000 0.0004080000 0.0033250000 0.0000010000 0.0000060000 0.0013110000 14276493 96830484 509673472 4.0291728973 3.9877743721 3.8782751560 87 1305031105.0433731079 0.0813989863 0.0430967904 0.0813989863 0.0182511623 0.0066080000 0.0003990000 0.0043540000 0.0000060000 0.0000060000 0.0015530000 14280165 96830484 509673472 4.0292067528 3.9939043522 3.8861296177 88 1305031105.0753200054 0.0782690346 0.0434964750 0.0813989863 0.0181822922 0.0046470000 0.0004000000 0.0026410000 0.0000010000 0.0000060000 0.0012950000 14283837 96830484 509673472 4.0260066986 3.9942326546 3.8962740898 89 1305031105.1112990379 0.0761289448 0.0438631320 0.0813989863 0.0180953595 0.0058970000 0.0003970000 0.0030050000 0.0000060000 0.0000050000 0.0021750000 14287621 96830484 509673472 4.0240287781 3.9940075874 3.9074983597 90 1305031105.1431059837 0.0710838363 0.0441655843 0.0813989863 0.0180836935 0.0061010000 0.0005310000 0.0029320000 0.0000010000 0.0000140000 0.0018830000 14291293 96830484 509673472 4.0196180344 3.9925308228 3.9200599194 91 1305031105.1751589775 0.0692730471 0.0444414904 0.0813989863 0.0185311353 0.0062870000 0.0005310000 0.0029420000 0.0000140000 0.0000120000 0.0020400000 14294965 96830484 509673472 4.0152425766 3.9975562096 3.9365043640 92 1305031105.2112679482 0.0653712973 0.0446689883 0.0813989863 0.0185580142 0.0072920000 0.0005320000 0.0047640000 0.0000020000 0.0000160000 0.0014700000 14298749 96830484 509673472 4.0104703903 3.9985980988 3.9543125629 93 1305031105.2432699203 0.0548983961 0.0447789820 0.0813989863 0.0185541239 0.0053900000 0.0004210000 0.0026940000 0.0000060000 0.0000050000 0.0019560000 14302421 96830484 509673472 4.0068311691 3.9912550449 3.9692347050 94 1305031105.2752881050 0.0486330576 0.0448199828 0.0813989863 0.0187137098 0.0065350000 0.0004560000 0.0041150000 0.0000010000 0.0000110000 0.0013850000 14306093 96830484 509673472 4.0029506683 3.9906890392 3.9858636856 95 1305031105.3112900257 0.0421652868 0.0447920386 0.0813989863 0.0187025150 0.0051750000 0.0004660000 0.0025690000 0.0000100000 0.0000100000 0.0015740000 14309877 96830484 509673472 3.9950792789 3.9886286259 4.0023078918 96 1305031105.3433020115 0.0337728783 0.0446772557 0.0813989863 0.0186275430 0.0058580000 0.0005280000 0.0029430000 0.0000020000 0.0000140000 0.0015890000 14313549 96830484 509673472 3.9893703461 3.9846174717 4.0176672935 97 1305031105.3753380775 0.0263183378 0.0444879885 0.0813989863 0.0187629679 0.0068150000 0.0005290000 0.0029740000 0.0000150000 0.0000130000 0.0025010000 14317221 96830484 509673472 3.9844853878 3.9794349670 4.0319175720 98 1305031105.4112861156 0.0249307696 0.0442884250 0.0813989863 0.0187955357 0.0054500000 0.0004530000 0.0031590000 0.0000010000 0.0000090000 0.0012640000 14321005 96830484 509673472 3.9820704460 3.9786646366 4.0462956429 99 1305031105.4433159828 0.0220993720 0.0440642932 0.0813989863 0.0187128864 0.0056700000 0.0005250000 0.0025830000 0.0000140000 0.0000120000 0.0017440000 14324677 96830484 509673472 3.9774212837 3.9829874039 4.0610342026 100 1305031105.4752800465 0.0181050282 0.0438047005 0.0813989863 0.0186459055 0.0064770000 0.0005260000 0.0036720000 0.0000020000 0.0000140000 0.0014520000 14328349 96830484 509673472 3.9745833874 3.9801354408 4.0751070976 101 1305031105.5113320351 0.0191012416 0.0435601118 0.0813989863 0.0186275316 0.0053280000 0.0004530000 0.0024130000 0.0000100000 0.0000080000 0.0018880000 14332133 96830484 509673472 3.9734103680 3.9811213017 4.0892281532 102 1305031105.5432820320 0.0173193272 0.0433028492 0.0813989863 0.0185571783 0.0053750000 0.0005300000 0.0025850000 0.0000020000 0.0000150000 0.0014270000 14335805 96830484 509673472 3.9718785286 3.9825701714 4.1032299995 103 1305031105.5754489899 0.0173555221 0.0430509334 0.0813989863 0.0184718855 0.0059170000 0.0005230000 0.0029310000 0.0000150000 0.0000130000 0.0016080000 14339477 96830484 509673472 3.9711656570 3.9818058014 4.1167321205 104 1305031105.6113779545 0.0208569653 0.0428375299 0.0813989863 0.0183882104 0.0065320000 0.0004530000 0.0045400000 0.0000010000 0.0000110000 0.0011150000 14343261 96830484 509673472 3.9703161716 3.9835596085 4.1304140091 105 1305031105.6432731152 0.0232942663 0.0426514036 0.0813989863 0.0183647704 0.0064490000 0.0005240000 0.0029580000 0.0000140000 0.0000130000 0.0021560000 14346933 96830484 509673472 3.9703016281 3.9824786186 4.1442580223 106 1305031105.6751658916 0.0235831030 0.0424715140 0.0813989863 0.0183284885 0.0047960000 0.0004480000 0.0027530000 0.0000010000 0.0000100000 0.0010580000 14350605 96830484 509673472 3.9692029953 3.9850523472 4.1583456993 107 1305031105.7113089561 0.0277902596 0.0423343060 0.0813989863 0.0184172229 0.0060960000 0.0004490000 0.0038170000 0.0000100000 0.0000080000 0.0012810000 14354389 96830484 509673472 3.9711775780 3.9876475334 4.1717758179 108 1305031105.7433118820 0.0305828582 0.0422254963 0.0813989863 0.0183387051 0.0048380000 0.0004610000 0.0027710000 0.0000010000 0.0000100000 0.0010590000 14358061 96830484 509673472 3.9726264477 3.9884402752 4.1854834557 109 1305031105.7753388882 0.0288872719 0.0421031272 0.0813989863 0.0182622118 0.0055430000 0.0004530000 0.0027810000 0.0000090000 0.0000100000 0.0017510000 14361733 96830484 509673472 3.9728925228 3.9941997528 4.1993141174 110 1305031105.8112831116 0.0342789739 0.0420319986 0.0813989863 0.0181979927 0.0059800000 0.0005250000 0.0033240000 0.0000020000 0.0000160000 0.0012990000 14365517 96830484 509673472 3.9727077484 3.9959790707 4.2128524780 111 1305031105.8432710171 0.0352605581 0.0419709946 0.0813989863 0.0181183998 0.0058050000 0.0005240000 0.0029320000 0.0000150000 0.0000130000 0.0015050000 14369189 96830484 509673472 3.9726564884 3.9990558624 4.2265663147 112 1305031105.8753368855 0.0358819142 0.0419166278 0.0813989863 0.0180581572 0.0056190000 0.0005270000 0.0029420000 0.0000020000 0.0000140000 0.0013110000 14372861 96830484 509673472 3.9746859074 4.0031251907 4.2401118279 113 1305031105.9112620354 0.0377205648 0.0418794945 0.0813989863 0.0180832205 0.0065660000 0.0005280000 0.0036920000 0.0000140000 0.0000130000 0.0017640000 14376645 96830484 509673472 3.9755873680 4.0091114044 4.2542772293 114 1305031105.9432721138 0.0392308235 0.0418562606 0.0813989863 0.0180191327 0.0048090000 0.0004200000 0.0030690000 0.0000010000 0.0000070000 0.0008920000 14380317 96830484 509673472 3.9771630764 4.0124654770 4.2675704956 115 1305031105.9753289223 0.0400721766 0.0418407468 0.0813989863 0.0180003944 0.0059040000 0.0005320000 0.0029940000 0.0000150000 0.0000130000 0.0014990000 14383989 96830484 509673472 3.9757676125 4.0170865059 4.2805538177 116 1305031106.0112850666 0.0446809977 0.0418652317 0.0813989863 0.0179473445 0.0056910000 0.0005310000 0.0033050000 0.0000020000 0.0000150000 0.0012670000 14387773 96830484 509673472 3.9755885601 4.0206060410 4.2933101654 117 1305031106.0433549881 0.0464647114 0.0419045435 0.0813989863 0.0178702560 0.0070450000 0.0005250000 0.0036580000 0.0000140000 0.0000130000 0.0019820000 14391501 96830484 509673472 3.9772994518 4.0242099762 4.3055963516 118 1305031106.0753300190 0.0491742194 0.0419661509 0.0813989863 0.0178104272 0.0062980000 0.0004500000 0.0045510000 0.0000010000 0.0000080000 0.0008520000 14395117 96830484 509673472 3.9761519432 4.0270857811 4.3177523613 119 1305031106.1113269329 0.0524631552 0.0420543610 0.0813989863 0.0177979954 0.0069470000 0.0005290000 0.0040570000 0.0000140000 0.0000150000 0.0014640000 14398901 96830484 509673472 3.9733779430 4.0314989090 4.3292565346 120 1305031106.1433548927 0.0534544699 0.0421493619 0.0813989863 0.0177313382 0.0051800000 0.0004510000 0.0031550000 0.0000010000 0.0000100000 0.0009830000 14402629 96830484 509673472 3.9727327824 4.0356755257 4.3409757614 121 1305031106.1755340099 0.0581331439 0.0422814593 0.0813989863 0.0176637728 0.0077730000 0.0005300000 0.0044130000 0.0000150000 0.0000130000 0.0019230000 14406245 96830484 509673472 3.9719450474 4.0359034538 4.3518915176 122 1305031106.2112751007 0.0621873848 0.0424446226 0.0813989863 0.0175950121 0.0068220000 0.0005280000 0.0047270000 0.0000010000 0.0000090000 0.0009700000 14410029 96830484 509673472 3.9704720974 4.0378594398 4.3617534637 123 1305031106.2432670593 0.0667610615 0.0426423173 0.0813989863 0.0175267362 0.0049580000 0.0004190000 0.0030470000 0.0000080000 0.0000070000 0.0010330000 14413757 96830484 509673472 3.9685497284 4.0376758575 4.3709588051 124 1305031106.2763850689 0.0686952546 0.0428524216 0.0813989863 0.0174622036 0.0072540000 0.0005940000 0.0044480000 0.0000020000 0.0000150000 0.0012330000 14417429 96830484 509673472 3.9681494236 4.0408749580 4.3785357475 125 1305031106.3112380505 0.0682641566 0.0430557155 0.0813989863 0.0174048983 0.0075610000 0.0005330000 0.0048160000 0.0000100000 0.0000100000 0.0015690000 14421157 96830484 509673472 3.9683175087 4.0449481010 4.3853969574 126 1305031106.3432579041 0.0698158517 0.0432680975 0.0813989863 0.0174123970 0.0062660000 0.0004550000 0.0045030000 0.0000010000 0.0000080000 0.0008360000 14424885 96830484 509673472 3.9694461823 4.0468583107 4.3916702271 127 1305031106.3753879070 0.0690157712 0.0434708351 0.0813989863 0.0174373696 0.0068110000 0.0004570000 0.0045460000 0.0000100000 0.0000100000 0.0011720000 14428501 96830484 509673472 3.9689362049 4.0499148369 4.3965525627 128 1305031106.4113199711 0.0734285712 0.0437048799 0.0813989863 0.0175795965 0.0053100000 0.0004200000 0.0037540000 0.0000010000 0.0000060000 0.0007550000 14432285 96830484 509673472 3.9698867798 4.0465979576 4.3997077942 129 1305031106.4432780743 0.0795610175 0.0439828345 0.0813989863 0.0177157719 0.0070910000 0.0005270000 0.0036980000 0.0000150000 0.0000130000 0.0018880000 14448245 96830484 509673472 3.9674289227 4.0398216248 4.4007725716 130 1305031106.4753448963 0.0819020644 0.0442745209 0.0819020644 0.0177738655 0.0065590000 0.0004560000 0.0045210000 0.0000010000 0.0000090000 0.0009420000 14477517 96830484 509673472 3.9651622772 4.0355753899 4.3989419937 131 1305031106.5111289024 0.0822503567 0.0445644127 0.0822503567 0.0177816203 0.0062010000 0.0004180000 0.0044350000 0.0000060000 0.0000050000 0.0009560000 14481133 96830484 509673472 3.9656994343 4.0316662788 4.3946018219 132 1305031106.5433020592 0.0827182680 0.0448534571 0.0827182680 0.0177289586 0.0059250000 0.0004560000 0.0038640000 0.0000010000 0.0000090000 0.0009550000 14484861 96830484 509673472 3.9648435116 4.0269980431 4.3879318237 133 1305031106.5752820969 0.0806961507 0.0451229510 0.0827182680 0.0176838824 0.0075900000 0.0005320000 0.0044110000 0.0000160000 0.0000130000 0.0018930000 14488477 96830484 509673472 3.9670240879 4.0240926743 4.3790345192 134 1305031106.6111509800 0.0772186965 0.0453624715 0.0827182680 0.0177069668 0.0069180000 0.0005630000 0.0040410000 0.0000030000 0.0000150000 0.0012680000 14492261 96830484 509673472 3.9659214020 4.0217857361 4.3692770004 135 1305031106.6432070732 0.0750330314 0.0455822534 0.0827182680 0.0176761635 0.0047560000 0.0004630000 0.0027050000 0.0000080000 0.0000080000 0.0010470000 14495989 96830484 509673472 3.9654207230 4.0185132027 4.3589124680 136 1305031106.6752789021 0.0760555193 0.0458063216 0.0827182680 0.0176351581 0.0075040000 0.0005620000 0.0047590000 0.0000020000 0.0000140000 0.0012570000 14499605 96830484 509673472 3.9656088352 4.0117282867 4.3473658562 137 1305031106.7115080357 0.0730865672 0.0460054475 0.0827182680 0.0176641813 0.0068060000 0.0005300000 0.0039920000 0.0000090000 0.0000080000 0.0015700000 14503389 96830484 509673472 3.9652955532 4.0090899467 4.3350405693 138 1305031106.7433409691 0.0729776695 0.0462008983 0.0827182680 0.0176529797 0.0054930000 0.0004240000 0.0037290000 0.0000010000 0.0000070000 0.0008440000 14507117 96830484 509673472 3.9651699066 4.0032796860 4.3222370148 139 1305031106.7753899097 0.0718785971 0.0463856300 0.0827182680 0.0175944185 0.0070720000 0.0005300000 0.0039890000 0.0000140000 0.0000130000 0.0014490000 14510733 96830484 509673472 3.9664618969 3.9985806942 4.3087596893 140 1305031106.8112890720 0.0690598935 0.0465475890 0.0827182680 0.0175538758 0.0049880000 0.0004560000 0.0030920000 0.0000010000 0.0000070000 0.0009030000 14514517 96830484 509673472 3.9699134827 3.9956443310 4.2942028046 141 1305031106.8434159756 0.0659257621 0.0466850229 0.0827182680 0.0175189005 0.0062080000 0.0004730000 0.0034420000 0.0000100000 0.0000090000 0.0017210000 14518189 96830484 509673472 3.9710981846 3.9927227497 4.2797937393 142 1305031106.8759050369 0.0670811236 0.0468286574 0.0827182680 0.0176504706 0.0055910000 0.0004310000 0.0036700000 0.0000010000 0.0000080000 0.0009310000 14521861 96830484 509673472 3.9705073833 3.9839727879 4.2641367912 143 1305031106.9112429619 0.0634815097 0.0469451109 0.0827182680 0.0177056938 0.0051590000 0.0004290000 0.0030180000 0.0000080000 0.0000070000 0.0011480000 14525645 96830484 509673472 3.9658973217 3.9808063507 4.2469491959 144 1305031106.9434390068 0.0559278503 0.0470074910 0.0827182680 0.0176604915 0.0069260000 0.0005440000 0.0039630000 0.0000020000 0.0000150000 0.0013160000 14529317 96830484 509673472 3.9669234753 3.9809794426 4.2293152809 145 1305031106.9755470753 0.0549078025 0.0470619759 0.0827182680 0.0176707255 0.0065240000 0.0005290000 0.0028820000 0.0000180000 0.0000140000 0.0021360000 14532989 96830484 509673472 3.9661099911 3.9740304947 4.2116761208 146 1305031107.0115759373 0.0524831153 0.0470991070 0.0827182680 0.0176295245 0.0057670000 0.0004610000 0.0034670000 0.0000020000 0.0000090000 0.0011000000 14536829 96830484 509673472 3.9650833607 3.9688510895 4.1934027672 147 1305031107.0432810783 0.0421893336 0.0470657072 0.0827182680 0.0176551655 0.0052300000 0.0004510000 0.0027320000 0.0000110000 0.0000090000 0.0012930000 14540501 96830484 509673472 3.9649457932 3.9724967480 4.1755394936 148 1305031107.0754320621 0.0413258374 0.0470269243 0.0827182680 0.0176874648 0.0072280000 0.0005270000 0.0046590000 0.0000020000 0.0000140000 0.0012810000 14544117 96830484 509673472 3.9630219936 3.9659192562 4.1593117714 149 1305031107.1112289429 0.0410794243 0.0469870082 0.0827182680 0.0176334274 0.0074250000 0.0005260000 0.0036210000 0.0000150000 0.0000120000 0.0022460000 14547901 96830484 509673472 3.9622366428 3.9599337578 4.1429367065 150 1305031107.1432600021 0.0347416960 0.0469053728 0.0827182680 0.0176301896 0.0064750000 0.0004550000 0.0044550000 0.0000010000 0.0000070000 0.0009940000 14551629 96830484 509673472 3.9627437592 3.9609045982 4.1273336411 151 1305031107.1753990650 0.0297553800 0.0467917967 0.0827182680 0.0175820316 0.0055120000 0.0004520000 0.0030490000 0.0000100000 0.0000090000 0.0013450000 14555245 96830484 509673472 3.9639210701 3.9599494934 4.1125531197 152 1305031107.2113580704 0.0317171887 0.0466926216 0.0827182680 0.0176661484 0.0063340000 0.0005230000 0.0032580000 0.0000020000 0.0000150000 0.0014090000 14559029 96830484 509673472 3.9625496864 3.9531242847 4.0978236198 153 1305031107.2433779240 0.0279146880 0.0465698900 0.0827182680 0.0176158919 0.0062890000 0.0004550000 0.0034720000 0.0000100000 0.0000090000 0.0017750000 14562701 96830484 509673472 3.9637858868 3.9513568878 4.0834999084 154 1305031107.2753980160 0.0235384144 0.0464203350 0.0827182680 0.0175693496 0.0048380000 0.0003980000 0.0029970000 0.0000010000 0.0000060000 0.0009790000 14566373 96830484 509673472 3.9653098583 3.9513349533 4.0696215630 155 1305031107.3112258911 0.0217679366 0.0462612872 0.0827182680 0.0175691355 0.0057840000 0.0003950000 0.0036840000 0.0000060000 0.0000050000 0.0012250000 14570157 96830484 509673472 3.9670486450 3.9488105774 4.0556712151 156 1305031107.3435089588 0.0224721581 0.0461087928 0.0827182680 0.0176323389 0.0061610000 0.0005270000 0.0029430000 0.0000010000 0.0000160000 0.0015220000 14573885 96830484 509673472 3.9658446312 3.9449679852 4.0422086716 157 1305031107.3754129410 0.0174043588 0.0459259620 0.0827182680 0.0176588417 0.0079290000 0.0005270000 0.0036920000 0.0000160000 0.0000130000 0.0025210000 14577501 96830484 509673472 3.9709961414 3.9457414150 4.0293850899 158 1305031107.4112710953 0.0140260793 0.0457240640 0.0827182680 0.0176318622 0.0044930000 0.0004550000 0.0023060000 0.0000010000 0.0000070000 0.0011340000 14581285 96830484 509673472 3.9761862755 3.9494321346 4.0195651054 159 1305031107.4434189796 0.0150049143 0.0455308618 0.0827182680 0.0175817508 0.0048730000 0.0003960000 0.0026740000 0.0000060000 0.0000050000 0.0013180000 14585013 96830484 509673472 3.9797284603 3.9507062435 4.0114831924 160 1305031107.4753770828 0.0169104561 0.0453519843 0.0827182680 0.0175343067 0.0066660000 0.0005270000 0.0033310000 0.0000020000 0.0000150000 0.0016000000 14588685 96830484 509673472 3.9859714508 3.9541249275 4.0057263374 161 1305031107.5113520622 0.0212842673 0.0452024954 0.0827182680 0.0175052366 0.0075200000 0.0005540000 0.0037000000 0.0000150000 0.0000120000 0.0024430000 14592413 96830484 509673472 3.9895141125 3.9562821388 4.0014166832 162 1305031107.5436050892 0.0259328559 0.0450835470 0.0827182680 0.0175200738 0.0046480000 0.0004530000 0.0024170000 0.0000020000 0.0000090000 0.0011610000 14596141 96830484 509673472 3.9930131435 3.9616954327 3.9998264313 163 1305031107.5754539967 0.0260209180 0.0449665984 0.0827182680 0.0174998106 0.0065340000 0.0005290000 0.0029480000 0.0000150000 0.0000130000 0.0018090000 14599757 96830484 509673472 3.9950380325 3.9604110718 3.9987907410 164 1305031107.6112709045 0.0259164777 0.0448504391 0.0827182680 0.0174565582 0.0053620000 0.0004530000 0.0027890000 0.0000010000 0.0000100000 0.0013040000 14603541 96830484 509673472 3.9977056980 3.9587194920 3.9981040955 165 1305031107.6433229446 0.0264280140 0.0447387880 0.0827182680 0.0174455387 0.0074800000 0.0004200000 0.0044690000 0.0000070000 0.0000060000 0.0019570000 14607269 96830484 509673472 4.0024771690 3.9650547504 3.9997775555 166 1305031107.6755681038 0.0257370472 0.0446243197 0.0827182680 0.0174125629 0.0056560000 0.0003960000 0.0036930000 0.0000010000 0.0000060000 0.0010640000 14610885 96830484 509673472 4.0016613007 3.9650089741 4.0012660027 167 1305031107.7113070488 0.0243405048 0.0445028597 0.0827182680 0.0173682936 0.0079530000 0.0005260000 0.0043810000 0.0000140000 0.0000150000 0.0017930000 14614669 96830484 509673472 4.0019288063 3.9658167362 4.0030269623 168 1305031107.7435379028 0.0247518662 0.0443852943 0.0827182680 0.0173492933 0.0056850000 0.0004570000 0.0034640000 0.0000010000 0.0000080000 0.0011310000 14618341 96830484 509673472 4.0003447533 3.9693098068 4.0055780411 169 1305031107.7758018970 0.0246885829 0.0442687457 0.0827182680 0.0173059916 0.0072720000 0.0005320000 0.0029730000 0.0000150000 0.0000130000 0.0024920000 14622013 96830484 509673472 3.9987180233 3.9714519978 4.0082244873 170 1305031107.8115959167 0.0226445459 0.0441415445 0.0827182680 0.0172568408 0.0052870000 0.0004550000 0.0030990000 0.0000000000 0.0000070000 0.0011010000 14625797 96830484 509673472 3.9976656437 3.9703171253 4.0107975006 171 1305031107.8433320522 0.0211542584 0.0440071160 0.0827182680 0.0172153417 0.0051580000 0.0004010000 0.0030070000 0.0000050000 0.0000060000 0.0012280000 14629469 96830484 509673472 3.9988377094 3.9714496136 4.0133357048 172 1305031107.8753581047 0.0209159926 0.0438728652 0.0827182680 0.0171906405 0.0070020000 0.0005440000 0.0036710000 0.0000020000 0.0000150000 0.0015100000 14633141 96830484 509673472 3.9980936050 3.9705960751 4.0153636932 173 1305031107.9115409851 0.0204699691 0.0437375884 0.0827182680 0.0171731307 0.0067060000 0.0005340000 0.0025660000 0.0000150000 0.0000130000 0.0024170000 14636925 96830484 509673472 4.0000500679 3.9689483643 4.0168428421 174 1305031107.9431219101 0.0223383456 0.0436146042 0.0827182680 0.0171777696 0.0053140000 0.0004560000 0.0027790000 0.0000010000 0.0000100000 0.0012240000 14640597 96830484 509673472 4.0023479462 3.9692502022 4.0179920197 175 1305031107.9758069515 0.0260893404 0.0435144599 0.0827182680 0.0171640793 0.0065330000 0.0005550000 0.0029500000 0.0000140000 0.0000150000 0.0017260000 14644269 96830484 509673472 4.0066862106 3.9700906277 4.0189919472 176 1305031108.0113201141 0.0290381908 0.0434322083 0.0827182680 0.0171301771 0.0050240000 0.0004590000 0.0024540000 0.0000020000 0.0000090000 0.0012510000 14648053 96830484 509673472 4.0114436150 3.9703352451 4.0201120377 177 1305031108.0434179306 0.0322707035 0.0433691490 0.0827182680 0.0170913457 0.0053340000 0.0004260000 0.0023730000 0.0000080000 0.0000070000 0.0018910000 14651725 96830484 509673472 4.0183625221 3.9735107422 4.0215864182 178 1305031108.0753519535 0.0350930467 0.0433226540 0.0827182680 0.0170567921 0.0053140000 0.0004290000 0.0030720000 0.0000000000 0.0000080000 0.0011470000 14655341 96830484 509673472 4.0269947052 3.9772009850 4.0230650902 179 1305031108.1113779545 0.0433075316 0.0433225695 0.0827182680 0.0170164240 0.0058760000 0.0004270000 0.0034010000 0.0000090000 0.0000060000 0.0013700000 14659125 96830484 509673472 4.0322127342 3.9770045280 4.0245161057 180 1305031108.1433339119 0.0476486236 0.0433466032 0.0827182680 0.0169887680 0.0063560000 0.0004250000 0.0041020000 0.0000010000 0.0000070000 0.0011530000 14662797 96830484 509673472 4.0388569832 3.9781455994 4.0271000862 181 1305031108.1760580540 0.0521284379 0.0433951216 0.0827182680 0.0170195474 0.0076970000 0.0005320000 0.0032760000 0.0000160000 0.0000130000 0.0025160000 14666469 96830484 509673472 4.0504846573 3.9824504852 4.0300908089 182 1305031108.2114748955 0.0537921973 0.0434522484 0.0827182680 0.0170093279 0.0060470000 0.0005340000 0.0032970000 0.0000020000 0.0000140000 0.0013010000 14670253 96830484 509673472 4.0601563454 3.9871504307 4.0344171524 183 1305031108.2433469296 0.0539683625 0.0435097135 0.0827182680 0.0170039113 0.0066470000 0.0004220000 0.0043750000 0.0000070000 0.0000070000 0.0012970000 14673925 96830484 509673472 4.0697917938 3.9832165241 4.0378599167 184 1305031108.2753579617 0.0547011681 0.0435705366 0.0827182680 0.0169597397 0.0065390000 0.0004650000 0.0043810000 0.0000010000 0.0000060000 0.0010390000 14677597 96830484 509673472 4.0799126625 3.9796726704 4.0405874252 185 1305031108.3113319874 0.0609352328 0.0436643998 0.0827182680 0.0170755004 0.0076910000 0.0005760000 0.0032920000 0.0000140000 0.0000130000 0.0024750000 14681381 96830484 509673472 4.0875597000 3.9858500957 4.0441341400 186 1305031108.3432779312 0.0618670993 0.0437622638 0.0827182680 0.0170647651 0.0057720000 0.0005360000 0.0029240000 0.0000020000 0.0000160000 0.0013830000 14685109 96830484 509673472 4.0964279175 3.9884080887 4.0483407974 187 1305031108.3754100800 0.0612897575 0.0438559937 0.0827182680 0.0170352842 0.0056610000 0.0004590000 0.0028050000 0.0000110000 0.0000080000 0.0014670000 14688725 96830484 509673472 4.1068553925 3.9881613255 4.0522933006 188 1305031108.4113609791 0.0635507256 0.0439607529 0.0827182680 0.0169946117 0.0060270000 0.0005360000 0.0025770000 0.0000020000 0.0000160000 0.0015400000 14692509 96830484 509673472 4.1184091568 3.9870963097 4.0560441017 189 1305031108.4436099529 0.0609958470 0.0440508857 0.0827182680 0.0170061190 0.0067930000 0.0005370000 0.0024620000 0.0000150000 0.0000130000 0.0023920000 14696237 96830484 509673472 4.1321988106 3.9853367805 4.0588145256 190 1305031108.4754710197 0.0602607578 0.0441362008 0.0827182680 0.0170066299 0.0064450000 0.0004640000 0.0042080000 0.0000010000 0.0000080000 0.0010720000 14699853 96830484 509673472 4.1444215775 3.9838335514 4.0613408089 191 1305031108.5113780499 0.0648095384 0.0442444382 0.0827182680 0.0172567147 0.0055220000 0.0004030000 0.0033320000 0.0000060000 0.0000050000 0.0012170000 14703637 96830484 509673472 4.1559200287 3.9809274673 4.0625443459 192 1305031108.5437369347 0.0651520193 0.0443533319 0.0827182680 0.0173003905 0.0067010000 0.0005330000 0.0033080000 0.0000020000 0.0000140000 0.0014540000 14707365 96830484 509673472 4.1684713364 3.9789075851 4.0621070862 193 1305031108.5754139423 0.0672120228 0.0444717707 0.0827182680 0.0173365221 0.0075810000 0.0005350000 0.0032680000 0.0000170000 0.0000130000 0.0023350000 14710981 96830484 509673472 4.1782078743 3.9800765514 4.0626449585 194 1305031108.6114070415 0.0730182528 0.0446189175 0.0827182680 0.0173337064 0.0064430000 0.0004570000 0.0044180000 0.0000010000 0.0000070000 0.0009900000 14714765 96830484 509673472 4.1861019135 3.9875199795 4.0636954308 195 1305031108.6433029175 0.0745995939 0.0447726645 0.0827182680 0.0172989924 0.0046130000 0.0003900000 0.0025960000 0.0000050000 0.0000040000 0.0011410000 14718493 96830484 509673472 4.1961002350 3.9880688190 4.0646853447 196 1305031108.6753749847 0.0760708526 0.0449323492 0.0827182680 0.0172983044 0.0073820000 0.0005390000 0.0040470000 0.0000010000 0.0000150000 0.0013960000 14722109 96830484 509673472 4.2048883438 3.9921944141 4.0665903091 197 1305031108.7114109993 0.0801115483 0.0451109238 0.0827182680 0.0173114977 0.0071480000 0.0004770000 0.0037930000 0.0000100000 0.0000090000 0.0019360000 14725837 96830484 509673472 4.2139253616 3.9949417114 4.0679583549 198 1305031108.7435019016 0.0826255977 0.0453003918 0.0827182680 0.0172843297 0.0053090000 0.0004580000 0.0027650000 0.0000010000 0.0000100000 0.0011570000 14729565 96830484 509673472 4.2214918137 3.9931044579 4.0688991547 199 1305031108.7754929066 0.0834170058 0.0454919326 0.0834170058 0.0172437092 0.0082820000 0.0005310000 0.0047200000 0.0000150000 0.0000140000 0.0016150000 14733181 96830484 509673472 4.2291932106 3.9930572510 4.0694494247 200 1305031108.8112440109 0.0843496993 0.0456862214 0.0843496993 0.0172022267 0.0066730000 0.0004590000 0.0044850000 0.0000010000 0.0000070000 0.0010210000 14736965 96830484 509673472 4.2369346619 3.9950740337 4.0694832802 201 1305031108.8432641029 0.0833047405 0.0458733783 0.0843496993 0.0185462844 0.0075190000 0.0005270000 0.0032770000 0.0000140000 0.0000130000 0.0022910000 14740693 96830484 509673472 4.2439332008 3.9941561222 4.0684266090 202 1305031108.8765149117 0.0772204623 0.0460285618 0.0843496993 0.0185757371 0.0055040000 0.0004600000 0.0029990000 0.0000010000 0.0000100000 0.0011560000 14744365 96830484 509673472 4.2510972023 3.9932785034 4.0665245056 203 1305031108.9113640785 0.0731678456 0.0461622529 0.0843496993 0.0186542933 0.0061390000 0.0005290000 0.0025780000 0.0000180000 0.0000120000 0.0015940000 14748093 96830484 509673472 4.2563538551 3.9929308891 4.0641188622 204 1305031108.9432430267 0.0728978068 0.0462933095 0.0843496993 0.0187229815 0.0060310000 0.0005300000 0.0026200000 0.0000020000 0.0000160000 0.0014420000 14751821 96830484 509673472 4.2590813637 3.9890213013 4.0609173775 205 1305031108.9752678871 0.0700522810 0.0464092070 0.0843496993 0.0187027828 0.0065340000 0.0005320000 0.0029310000 0.0000160000 0.0000130000 0.0020840000 14755493 96830484 509673472 4.2593078613 3.9896450043 4.0581231117 206 1305031109.0112690926 0.0642368197 0.0464957488 0.0843496993 0.0186730113 0.0053930000 0.0004550000 0.0028140000 0.0000010000 0.0000100000 0.0011480000 14759221 96830484 509673472 4.2578768730 3.9944546223 4.0564498901 207 1305031109.0432770252 0.0610067509 0.0465658502 0.0843496993 0.0186550916 0.0065480000 0.0005280000 0.0029220000 0.0000140000 0.0000130000 0.0016390000 14762949 96830484 509673472 4.2559814453 3.9924385548 4.0542225838 208 1305031109.0754098892 0.0602073297 0.0466314343 0.0843496993 0.0186510209 0.0053890000 0.0004560000 0.0027900000 0.0000020000 0.0000090000 0.0011630000 14766565 96830484 509673472 4.2495880127 3.9928765297 4.0531630516 209 1305031109.1112821102 0.0552219786 0.0466725373 0.0843496993 0.0186233648 0.0071360000 0.0005360000 0.0028150000 0.0000150000 0.0000130000 0.0022990000 14770349 96830484 509673472 4.2423729897 3.9960782528 4.0529804230 210 1305031109.1433339119 0.0529950373 0.0467026445 0.0843496993 0.0186033107 0.0054440000 0.0004660000 0.0027930000 0.0000010000 0.0000110000 0.0011570000 14774077 96830484 509673472 4.2356829643 3.9921839237 4.0519347191 211 1305031109.1754639149 0.0510937013 0.0467234552 0.0843496993 0.0186099599 0.0070070000 0.0005370000 0.0033490000 0.0000140000 0.0000130000 0.0016270000 14777693 96830484 509673472 4.2282419205 3.9907565117 4.0510897636 212 1305031109.2113790512 0.0441484414 0.0467113089 0.0843496993 0.0186072638 0.0056570000 0.0005350000 0.0029580000 0.0000030000 0.0000140000 0.0011260000 14781477 96830484 509673472 4.2202410698 3.9951319695 4.0516724586 213 1305031109.2432899475 0.0396794118 0.0466782953 0.0843496993 0.0185708641 0.0086510000 0.0005720000 0.0041930000 0.0000140000 0.0000130000 0.0022250000 14785205 96830484 509673472 4.2112917900 3.9992685318 4.0534234047 214 1305031109.2753078938 0.0397853293 0.0466460852 0.0843496993 0.0187100015 0.0053280000 0.0005160000 0.0030500000 0.0000010000 0.0000090000 0.0009570000 14788821 96830484 509673472 4.2011914253 3.9917535782 4.0537800789 215 1305031109.3113288879 0.0382876098 0.0466072085 0.0843496993 0.0187740292 0.0062660000 0.0005370000 0.0025800000 0.0000150000 0.0000150000 0.0015530000 14792605 96830484 509673472 4.1893811226 3.9851601124 4.0533180237 216 1305031109.3432478905 0.0337897092 0.0465478683 0.0843496993 0.0188064010 0.0064270000 0.0005500000 0.0029570000 0.0000020000 0.0000140000 0.0013400000 14796333 96830484 509673472 4.1778345108 3.9897949696 4.0540208817 217 1305031109.3753969669 0.0313191861 0.0464776900 0.0843496993 0.0187683375 0.0055330000 0.0004720000 0.0024430000 0.0000120000 0.0000100000 0.0018010000 14799949 96830484 509673472 4.1657295227 3.9903271198 4.0551133156 218 1305031109.4113290310 0.0274503753 0.0463904087 0.0843496993 0.0187283150 0.0049260000 0.0004320000 0.0027280000 0.0000010000 0.0000080000 0.0009550000 14803733 96830484 509673472 4.1552219391 3.9867537022 4.0553317070 219 1305031109.4433019161 0.0231411550 0.0462842478 0.0843496993 0.0187066836 0.0066840000 0.0005530000 0.0029650000 0.0000150000 0.0000130000 0.0015720000 14807405 96830484 509673472 4.1444201469 3.9893662930 4.0557913780 220 1305031109.4753630161 0.0223384723 0.0461754033 0.0843496993 0.0186915140 0.0064640000 0.0005370000 0.0029600000 0.0000020000 0.0000140000 0.0013630000 14811021 96830484 509673472 4.1312208176 3.9886236191 4.0559077263 221 1305031109.5112729073 0.0211865250 0.0460623315 0.0843496993 0.0186744558 0.0059990000 0.0004650000 0.0028030000 0.0000100000 0.0000100000 0.0018380000 14814805 96830484 509673472 4.1181168556 3.9850752354 4.0549368858 222 1305031109.5432939529 0.0227275174 0.0459572197 0.0843496993 0.0186516139 0.0068440000 0.0005340000 0.0037160000 0.0000010000 0.0000150000 0.0013540000 14818533 96830484 509673472 4.1044306755 3.9826135635 4.0532274246 223 1305031109.5753619671 0.0196107756 0.0458390742 0.0843496993 0.0186114400 0.0053530000 0.0004630000 0.0024520000 0.0000100000 0.0000080000 0.0013330000 14822205 96830484 509673472 4.0937304497 3.9846620560 4.0513162613 224 1305031109.6113100052 0.0158952437 0.0457053964 0.0843496993 0.0185938756 0.0065520000 0.0005320000 0.0029630000 0.0000010000 0.0000140000 0.0013620000 14825933 96830484 509673472 4.0803241730 3.9865891933 4.0496668816 225 1305031109.6432290077 0.0156152947 0.0455716626 0.0843496993 0.0185532646 0.0075780000 0.0004590000 0.0046140000 0.0000100000 0.0000090000 0.0016710000 14829661 96830484 509673472 4.0679674149 3.9873354435 4.0485115051 226 1305031109.6752629280 0.0130645102 0.0454278257 0.0843496993 0.0185146661 0.0046910000 0.0004760000 0.0024180000 0.0000010000 0.0000070000 0.0009610000 14833277 96830484 509673472 4.0583105087 3.9893090725 4.0477519035 227 1305031109.7113120556 0.0110444250 0.0452763569 0.0843496993 0.0185425211 0.0085340000 0.0005320000 0.0048020000 0.0000140000 0.0000130000 0.0015540000 14837061 96830484 509673472 4.0457224846 3.9905471802 4.0477538109 228 1305031109.7432739735 0.0093863187 0.0451189445 0.0843496993 0.0185026845 0.0057360000 0.0004700000 0.0034770000 0.0000010000 0.0000070000 0.0009590000 14840789 96830484 509673472 4.0324530602 3.9932115078 4.0487589836 229 1305031109.7752768993 0.0103151314 0.0449669628 0.0843496993 0.0184798635 0.0067810000 0.0004540000 0.0038010000 0.0000100000 0.0000080000 0.0017010000 14844405 96830484 509673472 4.0196361542 3.9923353195 4.0500121117 230 1305031109.8113710880 0.0098433448 0.0448142514 0.0843496993 0.0184480923 0.0055200000 0.0004200000 0.0033560000 0.0000010000 0.0000070000 0.0009260000 14848189 96830484 509673472 4.0069365501 3.9921791553 4.0511617661 231 1305031109.8432960510 0.0087160282 0.0446579820 0.0843496993 0.0184154775 0.0062170000 0.0005310000 0.0025400000 0.0000140000 0.0000130000 0.0015200000 14851917 96830484 509673472 3.9940547943 3.9941065311 4.0530557632 232 1305031109.8753058910 0.0089206267 0.0445039417 0.0843496993 0.0183836298 0.0060180000 0.0005260000 0.0025630000 0.0000020000 0.0000140000 0.0012980000 14855533 96830484 509673472 3.9802725315 3.9946856499 4.0558199883 233 1305031109.9112648964 0.0116139557 0.0443627830 0.0843496993 0.0183605482 0.0078270000 0.0004520000 0.0044700000 0.0000100000 0.0000090000 0.0018030000 14859317 96830484 509673472 3.9615161419 3.9932832718 4.0589799881 234 1305031109.9432990551 0.0128729362 0.0442282110 0.0843496993 0.0183496194 0.0063000000 0.0004170000 0.0043420000 0.0000010000 0.0000050000 0.0008790000 14863045 96830484 509673472 3.9498317242 3.9932186604 4.0623245239 235 1305031109.9752581120 0.0105265025 0.0440847994 0.0843496993 0.0183154171 0.0073580000 0.0005290000 0.0036300000 0.0000140000 0.0000130000 0.0015440000 14866661 96830484 509673472 3.9374551773 3.9972105026 4.0661339760 236 1305031110.0112559795 0.0143392533 0.0439587590 0.0843496993 0.0182804629 0.0057850000 0.0005300000 0.0029000000 0.0000020000 0.0000160000 0.0012450000 14870445 96830484 509673472 3.9241747856 3.9950983524 4.0696339607 237 1305031110.0432989597 0.0154687678 0.0438385481 0.0843496993 0.0182434493 0.0055920000 0.0004220000 0.0026490000 0.0000070000 0.0000060000 0.0016740000 14874173 96830484 509673472 3.9113929272 3.9954559803 4.0732417107 238 1305031110.0753190517 0.0172922984 0.0437270092 0.0843496993 0.0182199908 0.0064790000 0.0005280000 0.0029230000 0.0000010000 0.0000150000 0.0013720000 14877789 96830484 509673472 3.9006958008 3.9956521988 4.0767192841 239 1305031110.1113250256 0.0186904985 0.0436222539 0.0843496993 0.0182368005 0.0081530000 0.0005300000 0.0043650000 0.0000150000 0.0000130000 0.0015850000 14881573 96830484 509673472 3.8858757019 3.9962565899 4.0806970596 240 1305031110.1434319019 0.0225269273 0.0435343567 0.0843496993 0.0182647949 0.0068110000 0.0004560000 0.0045170000 0.0000000000 0.0000080000 0.0010000000 14885301 96830484 509673472 3.8739287853 3.9931213856 4.0840983391 241 1305031110.1756410599 0.0256365687 0.0434600920 0.0843496993 0.0182271935 0.0068560000 0.0003980000 0.0043030000 0.0000060000 0.0000050000 0.0015820000 14888917 96830484 509673472 3.8641531467 3.9915783405 4.0874166489 242 1305031110.2116370201 0.0263321418 0.0433893154 0.0843496993 0.0181978265 0.0068700000 0.0005280000 0.0032970000 0.0000020000 0.0000150000 0.0013710000 14892757 96830484 509673472 3.8545246124 3.9948191643 4.0898728371 243 1305031110.2433230877 0.0306762476 0.0433369982 0.0843496993 0.0181973789 0.0058960000 0.0005280000 0.0028950000 0.0000150000 0.0000120000 0.0013300000 14896429 96830484 509673472 3.8444776535 3.9907865524 4.0924878120 244 1305031110.2793209553 0.0338253118 0.0432980159 0.0843496993 0.0181734223 0.0053180000 0.0004200000 0.0030310000 0.0000000000 0.0000080000 0.0010150000 14900213 96830484 509673472 3.8338224888 3.9892635345 4.0943279266 245 1305031110.3114039898 0.0347155258 0.0432629853 0.0843496993 0.0181377119 0.0074160000 0.0005230000 0.0028920000 0.0000150000 0.0000140000 0.0022610000 14903829 96830484 509673472 3.8247160912 3.9892756939 4.0950717926 246 1305031110.3433549404 0.0343580358 0.0432267864 0.0843496993 0.0181111650 0.0057700000 0.0005300000 0.0029120000 0.0000010000 0.0000090000 0.0011820000 14907501 96830484 509673472 3.8134982586 3.9908843040 4.0956749916 247 1305031110.3792810440 0.0361931510 0.0431983101 0.0843496993 0.0180995426 0.0075250000 0.0005280000 0.0036170000 0.0000140000 0.0000150000 0.0016410000 14911285 96830484 509673472 3.8040251732 3.9926021099 4.0961189270 248 1305031110.4114689827 0.0372209884 0.0431742080 0.0843496993 0.0180785233 0.0069350000 0.0004620000 0.0044930000 0.0000020000 0.0000100000 0.0010530000 14914957 96830484 509673472 3.7931475639 3.9934446812 4.0967817307 249 1305031110.4432599545 0.0369796753 0.0431493304 0.0843496993 0.0180490867 0.0070080000 0.0004020000 0.0042950000 0.0000060000 0.0000050000 0.0016910000 14918629 96830484 509673472 3.7818849087 3.9982709885 4.0979852676 250 1305031110.4793310165 0.0413810983 0.0431422574 0.0843496993 0.0180755006 0.0082260000 0.0005290000 0.0047120000 0.0000020000 0.0000140000 0.0014660000 14922469 96830484 509673472 3.7710721493 3.9979577065 4.0995855331 251 1305031110.5114290714 0.0466809273 0.0431563557 0.0843496993 0.0180623489 0.0060030000 0.0004180000 0.0036780000 0.0000080000 0.0000070000 0.0011880000 14926085 96830484 509673472 3.7637543678 3.9948415756 4.1017336845 252 1305031110.5434079170 0.0486253165 0.0431780579 0.0843496993 0.0180358861 0.0066020000 0.0004600000 0.0041750000 0.0000010000 0.0000100000 0.0010850000 14929813 96830484 509673472 3.7536675930 3.9961040020 4.1035017967 253 1305031110.5794260502 0.0514853820 0.0432108932 0.0843496993 0.0180283160 0.0087020000 0.0005310000 0.0047210000 0.0000150000 0.0000150000 0.0022540000 14933597 96830484 509673472 3.7441768646 4.0000791550 4.1053404808 254 1305031110.6113069057 0.0530796982 0.0432497468 0.0843496993 0.0180417466 0.0055960000 0.0004720000 0.0031000000 0.0000020000 0.0000080000 0.0010900000 14937213 96830484 509673472 3.7330777645 4.0000648499 4.1076612473 255 1305031110.6434180737 0.0582830273 0.0433087008 0.0843496993 0.0180732805 0.0065460000 0.0004070000 0.0043170000 0.0000060000 0.0000050000 0.0011870000 14940941 96830484 509673472 3.7268581390 3.9938185215 4.1097154617 256 1305031110.6796059608 0.0585754141 0.0433683364 0.0843496993 0.0180888977 0.0041320000 0.0003820000 0.0022680000 0.0000000000 0.0000040000 0.0009400000 14944669 96830484 509673472 3.7175381184 3.9953043461 4.1099381447 257 1305031110.7114119530 0.0577748232 0.0434243928 0.0843496993 0.0180602838 0.0069190000 0.0003820000 0.0043180000 0.0000050000 0.0000040000 0.0016540000 14972917 96830484 509673472 3.7098453045 3.9992539883 4.1108288765 258 1305031110.7432489395 0.0608031675 0.0434917524 0.0843496993 0.0180740310 0.0072280000 0.0005400000 0.0033050000 0.0000020000 0.0000150000 0.0014950000 15027789 96830484 509673472 3.7057204247 3.9951612949 4.1122775078 259 1305031110.7791929245 0.0624064468 0.0435647821 0.0843496993 0.0180401919 0.0088550000 0.0005370000 0.0047420000 0.0000140000 0.0000130000 0.0016870000 15031573 96830484 509673472 3.7005522251 3.9933395386 4.1130590439 260 1305031110.8113861084 0.0616931953 0.0436345068 0.0843496993 0.0180067177 0.0066950000 0.0004670000 0.0044520000 0.0000010000 0.0000070000 0.0010170000 15035245 96830484 509673472 3.6981449127 3.9955248833 4.1129026413 261 1305031110.8432180882 0.0605621189 0.0436993635 0.0843496993 0.0179843680 0.0065490000 0.0004620000 0.0027890000 0.0000100000 0.0000100000 0.0020310000 15038917 96830484 509673472 3.6945905685 3.9964191914 4.1129388809 262 1305031110.8793129921 0.0631438345 0.0437735790 0.0843496993 0.0179518596 0.0077730000 0.0005340000 0.0047290000 0.0000010000 0.0000100000 0.0012340000 15042701 96830484 509673472 3.6929273605 3.9921388626 4.1147947311 263 1305031110.9113330841 0.0632022396 0.0438474523 0.0843496993 0.0179283010 0.0058380000 0.0004230000 0.0034000000 0.0000080000 0.0000060000 0.0012430000 15046373 96830484 509673472 3.6950752735 3.9934408665 4.1150364876 264 1305031110.9438619614 0.0634173006 0.0439215805 0.0843496993 0.0179171034 0.0071320000 0.0005350000 0.0036820000 0.0000020000 0.0000150000 0.0015110000 15050101 96830484 509673472 3.6959900856 3.9924626350 4.1158962250 265 1305031110.9793450832 0.0619993061 0.0439897983 0.0843496993 0.0179422512 0.0056080000 0.0004240000 0.0023540000 0.0000070000 0.0000070000 0.0018620000 15053773 96830484 509673472 3.7002024651 3.9939928055 4.1159520149 266 1305031111.0114309788 0.0601938255 0.0440507157 0.0843496993 0.0179314099 0.0079950000 0.0005320000 0.0040690000 0.0000020000 0.0000140000 0.0014700000 15057501 96830484 509673472 3.7067024708 3.9974000454 4.1158590317 267 1305031111.0433270931 0.0617410131 0.0441169715 0.0843496993 0.0178983170 0.0072690000 0.0004600000 0.0045610000 0.0000100000 0.0000080000 0.0012760000 15061173 96830484 509673472 3.7122876644 3.9946098328 4.1170563698 268 1305031111.0792829990 0.0575163588 0.0441669692 0.0843496993 0.0178959238 0.0064890000 0.0004140000 0.0044110000 0.0000010000 0.0000050000 0.0009550000 15064901 96830484 509673472 3.7165815830 3.9973917007 4.1160860062 269 1305031111.1115078926 0.0566066653 0.0442132135 0.0843496993 0.0178776674 0.0082770000 0.0005330000 0.0037110000 0.0000140000 0.0000130000 0.0022930000 15068629 96830484 509673472 3.7246282101 3.9971463680 4.1153721809 270 1305031111.1432569027 0.0577112064 0.0442632060 0.0843496993 0.0178620980 0.0066020000 0.0004230000 0.0044470000 0.0000010000 0.0000060000 0.0009490000 15072301 96830484 509673472 3.7343437672 3.9947056770 4.1152157784 271 1305031111.1793260574 0.0546938181 0.0443016954 0.0843496993 0.0179068000 0.0051710000 0.0003880000 0.0029810000 0.0000060000 0.0000050000 0.0011420000 15076085 96830484 509673472 3.7425434589 3.9953558445 4.1140513420 272 1305031111.2114329338 0.0527611971 0.0443327965 0.0843496993 0.0178900574 0.0069030000 0.0006000000 0.0027480000 0.0000020000 0.0000150000 0.0013970000 15079701 96830484 509673472 3.7551920414 3.9970529079 4.1124629974 273 1305031111.2432360649 0.0492670350 0.0443508706 0.0843496993 0.0179328950 0.0089900000 0.0005370000 0.0047890000 0.0000150000 0.0000140000 0.0022770000 15083373 96830484 509673472 3.7614064217 3.9983544350 4.1108269691 274 1305031111.2793080807 0.0494143292 0.0443693504 0.0843496993 0.0179913155 0.0065850000 0.0004220000 0.0044380000 0.0000010000 0.0000060000 0.0009230000 15087157 96830484 509673472 3.7720420361 3.9934632778 4.1099262238 275 1305031111.3115470409 0.0472264253 0.0443797397 0.0843496993 0.0180027571 0.0080230000 0.0005310000 0.0047620000 0.0000090000 0.0000080000 0.0013540000 15090829 96830484 509673472 3.7845091820 3.9947457314 4.1089243889 276 1305031111.3433969021 0.0405155942 0.0443657392 0.0843496993 0.0181441661 0.0045070000 0.0004220000 0.0023540000 0.0000010000 0.0000050000 0.0009260000 15094501 96830484 509673472 3.7896590233 4.0015420914 4.1070375443 277 1305031111.3791339397 0.0446134210 0.0443666334 0.0843496993 0.0182858360 0.0094980000 0.0005310000 0.0047290000 0.0000140000 0.0000130000 0.0022190000 15098285 96830484 509673472 3.8029403687 3.9950172901 4.1091151237 278 1305031111.4112958908 0.0454345867 0.0443704749 0.0843496993 0.0182633770 0.0052390000 0.0004610000 0.0027680000 0.0000010000 0.0000070000 0.0009970000 15101901 96830484 509673472 3.8149216175 3.9919288158 4.1087741852 279 1305031111.4433860779 0.0404910073 0.0443565700 0.0843496993 0.0182548139 0.0080230000 0.0005350000 0.0047840000 0.0000100000 0.0000100000 0.0013500000 15105629 96830484 509673472 3.8227274418 3.9968175888 4.1074614525 280 1305031111.4792590141 0.0394318923 0.0443389819 0.0843496993 0.0187101059 0.0065870000 0.0004220000 0.0044370000 0.0000000000 0.0000060000 0.0009220000 15109413 96830484 509673472 3.8423230648 3.9954206944 4.1068634987 281 1305031111.5112640858 0.0368306488 0.0443122619 0.0843496993 0.0187082478 0.0078210000 0.0005320000 0.0040330000 0.0000100000 0.0000080000 0.0018880000 15113029 96830484 509673472 3.8569521904 3.9954581261 4.1045732498 282 1305031111.5432500839 0.0359957777 0.0442827708 0.0843496993 0.0186906223 0.0069290000 0.0004480000 0.0045570000 0.0000010000 0.0000080000 0.0009580000 15116757 96830484 509673472 3.8644297123 3.9940829277 4.1026539803 283 1305031111.5792369843 0.0352848060 0.0442509758 0.0843496993 0.0187130234 0.0047570000 0.0003950000 0.0026680000 0.0000060000 0.0000040000 0.0010290000 15120541 96830484 509673472 3.8784348965 3.9931290150 4.1007490158 284 1305031111.6112709045 0.0322864912 0.0442088474 0.0843496993 0.0187961770 0.0068530000 0.0005250000 0.0029800000 0.0000020000 0.0000150000 0.0012930000 15124101 96830484 509673472 3.8891127110 3.9962549210 4.0993752480 285 1305031111.6433949471 0.0375197753 0.0441853769 0.0843496993 0.0188221854 0.0071480000 0.0005480000 0.0033680000 0.0000140000 0.0000130000 0.0018280000 15127829 96830484 509673472 3.8995263577 3.9902036190 4.0995507240 286 1305031111.6793200970 0.0370637290 0.0441604761 0.0843496993 0.0190233857 0.0055540000 0.0004250000 0.0034720000 0.0000000000 0.0000060000 0.0008330000 15131557 96830484 509673472 3.9181654453 3.9887256622 4.0982398987 287 1305031111.7117600441 0.0295448322 0.0441095505 0.0843496993 0.0190442189 0.0074730000 0.0005310000 0.0033660000 0.0000150000 0.0000140000 0.0014870000 15135285 96830484 509673472 3.9327361584 3.9960258007 4.0961833000 288 1305031111.7433860302 0.0316007361 0.0440661171 0.0843496993 0.0191339654 0.0055460000 0.0004600000 0.0028130000 0.0000020000 0.0000090000 0.0010140000 15138957 96830484 509673472 3.9458892345 3.9929974079 4.0948853493 289 1305031111.7794229984 0.0312107671 0.0440216349 0.0843496993 0.0192229715 0.0081380000 0.0005240000 0.0044210000 0.0000150000 0.0000130000 0.0017690000 15142741 96830484 509673472 3.9611067772 3.9945654869 4.0932049751 290 1305031111.8114058971 0.0309789740 0.0439766602 0.0843496993 0.0192454619 0.0061790000 0.0004150000 0.0041400000 0.0000010000 0.0000060000 0.0007830000 15146357 96830484 509673472 3.9712104797 3.9972126484 4.0914425850 291 1305031111.8432989120 0.0350955911 0.0439461411 0.0843496993 0.0192241033 0.0060140000 0.0004580000 0.0031760000 0.0000120000 0.0000090000 0.0012590000 15150029 96830484 509673472 3.9798901081 3.9963450432 4.0900363922 292 1305031111.8794419765 0.0369537175 0.0439221944 0.0843496993 0.0192254959 0.0079080000 0.0005690000 0.0048370000 0.0000020000 0.0000150000 0.0010700000 15153757 96830484 509673472 3.9915211201 4.0003933907 4.0898833275 293 1305031111.9113540649 0.0385296643 0.0439037899 0.0843496993 0.0192509656 0.0072900000 0.0004430000 0.0044750000 0.0000060000 0.0000060000 0.0015060000 15157485 96830484 509673472 4.0034937859 3.9984629154 4.0902080536 294 1305031111.9433000088 0.0403539948 0.0438917158 0.0843496993 0.0192190434 0.0048250000 0.0003890000 0.0029950000 0.0000010000 0.0000050000 0.0008220000 15161157 96830484 509673472 4.0166978836 3.9948821068 4.0906066895 295 1305031111.9794490337 0.0396795459 0.0438774372 0.0843496993 0.0193651873 0.0043230000 0.0003800000 0.0022910000 0.0000050000 0.0000040000 0.0010280000 15164885 96830484 509673472 4.0330777168 3.9964778423 4.0908570290 296 1305031112.0114328861 0.0370342992 0.0438543185 0.0843496993 0.0193895618 0.0040870000 0.0003790000 0.0022900000 0.0000010000 0.0000040000 0.0007960000 15168613 96830484 509673472 4.0462436676 3.9994926453 4.0893440247 297 1305031112.0432701111 0.0420035683 0.0438480870 0.0843496993 0.0193576662 0.0049970000 0.0003830000 0.0025430000 0.0000040000 0.0000030000 0.0014330000 15172285 96830484 509673472 4.0535612106 3.9982373714 4.0880823135 298 1305031112.0793390274 0.0463634804 0.0438565280 0.0843496993 0.0193989630 0.0062170000 0.0003780000 0.0044060000 0.0000010000 0.0000040000 0.0008090000 15176069 96830484 509673472 4.0643949509 3.9997038841 4.0865521431 299 1305031112.1114230156 0.0516683385 0.0438826544 0.0843496993 0.0194659363 0.0050700000 0.0003820000 0.0030160000 0.0000040000 0.0000040000 0.0010350000 15179685 96830484 509673472 4.0704030991 4.0003414154 4.0853486061 300 1305031112.1443419456 0.0550531559 0.0439198894 0.0843496993 0.0194434254 0.0044990000 0.0003890000 0.0026680000 0.0000010000 0.0000040000 0.0008050000 15183357 96830484 509673472 4.0793595314 4.0007495880 4.0850105286 301 1305031112.1793899536 0.0607418343 0.0439757763 0.0843496993 0.0195239477 0.0059740000 0.0003840000 0.0030240000 0.0000050000 0.0000050000 0.0017830000 15187029 96830484 509673472 4.0900788307 4.0028042793 4.0845165253 302 1305031112.2112538815 0.0663850605 0.0440499792 0.0843496993 0.0195156456 0.0071960000 0.0006220000 0.0030180000 0.0000030000 0.0000150000 0.0013220000 15190701 96830484 509673472 4.0984797478 3.9994606972 4.0841550827 303 1305031112.2433691025 0.0708601624 0.0441384617 0.0843496993 0.0195396417 0.0072830000 0.0005600000 0.0029890000 0.0000140000 0.0000130000 0.0015420000 15194429 96830484 509673472 4.1094069481 3.9928004742 4.0823364258 304 1305031112.2793529034 0.0765078068 0.0442449398 0.0843496993 0.0195270696 0.0069680000 0.0004640000 0.0045040000 0.0000010000 0.0000100000 0.0008810000 15198157 96830484 509673472 4.1202297211 3.9936921597 4.0811700821 305 1305031112.3113119602 0.0783050656 0.0443566123 0.0843496993 0.0195194655 0.0059260000 0.0004040000 0.0030500000 0.0000070000 0.0000060000 0.0015720000 15201885 96830484 509673472 4.1308684349 3.9929568768 4.0801486969 306 1305031112.3433229923 0.0780857503 0.0444668383 0.0843496993 0.0194973025 0.0069190000 0.0004600000 0.0038860000 0.0000020000 0.0000090000 0.0011020000 15205557 96830484 509673472 4.1437149048 3.9921340942 4.0786099434 307 1305031112.3793599606 0.0805568844 0.0445843954 0.0843496993 0.0194725586 0.0054460000 0.0004200000 0.0027410000 0.0000080000 0.0000060000 0.0012270000 15209397 96830484 509673472 4.1557707787 3.9956760406 4.0777482986 308 1305031112.4114420414 0.0784217268 0.0446942569 0.0843496993 0.0194518373 0.0071430000 0.0005350000 0.0029900000 0.0000020000 0.0000150000 0.0013990000 15213013 96830484 509673472 4.1689677238 3.9975380898 4.0771627426 309 1305031112.4433910847 0.0766496956 0.0447976725 0.0843496993 0.0194376525 0.0080000000 0.0005330000 0.0029650000 0.0000140000 0.0000130000 0.0022510000 15216741 96830484 509673472 4.1818132401 3.9973807335 4.0764288902 310 1305031112.4794180393 0.0776267052 0.0449035726 0.0843496993 0.0194189272 0.0052830000 0.0004560000 0.0027400000 0.0000010000 0.0000080000 0.0010030000 15220525 96830484 509673472 4.1947040558 3.9962961674 4.0753531456 311 1305031112.5115039349 0.0746928528 0.0449993581 0.0843496993 0.0194045485 0.0068990000 0.0005330000 0.0029660000 0.0000150000 0.0000130000 0.0015990000 15224141 96830484 509673472 4.2070074081 3.9982023239 4.0741734505 312 1305031112.5432119370 0.0732576102 0.0450899294 0.0843496993 0.0193851258 0.0053860000 0.0004600000 0.0027990000 0.0000010000 0.0000090000 0.0010080000 15227813 96830484 509673472 4.2179064751 3.9972741604 4.0735216141 313 1305031112.5792520046 0.0746277273 0.0451842994 0.0843496993 0.0193561334 0.0063510000 0.0004570000 0.0024400000 0.0000100000 0.0000090000 0.0019320000 15231541 96830484 509673472 4.2275738716 3.9983055592 4.0732436180 314 1305031112.6112608910 0.0725120902 0.0452713306 0.0843496993 0.0193984129 0.0058870000 0.0004760000 0.0027720000 0.0000010000 0.0000100000 0.0011360000 15235213 96830484 509673472 4.2380943298 3.9999246597 4.0729851723 315 1305031112.6432459354 0.0716539547 0.0453550849 0.0843496993 0.0194231095 0.0083080000 0.0005350000 0.0039100000 0.0000150000 0.0000130000 0.0016410000 15238941 96830484 509673472 4.2459211349 4.0034198761 4.0732779503 316 1305031112.6799519062 0.0752607286 0.0454497230 0.0843496993 0.0194163207 0.0057910000 0.0004580000 0.0031510000 0.0000010000 0.0000100000 0.0010310000 15242725 96830484 509673472 4.2499232292 4.0029683113 4.0738048553 317 1305031112.7112510204 0.0763892755 0.0455473242 0.0843496993 0.0194154419 0.0056890000 0.0004000000 0.0026760000 0.0000060000 0.0000060000 0.0016830000 15246341 96830484 509673472 4.2528972626 4.0035481453 4.0747618675 318 1305031112.7432448864 0.0763185322 0.0456440890 0.0843496993 0.0194122178 0.0047110000 0.0003830000 0.0026370000 0.0000010000 0.0000050000 0.0009240000 15250069 96830484 509673472 4.2550892830 4.0078201294 4.0763621330 319 1305031112.7793099880 0.0754818171 0.0457376242 0.0843496993 0.0194145356 0.0080140000 0.0005320000 0.0035300000 0.0000150000 0.0000140000 0.0016530000 15253853 96830484 509673472 4.2555775642 4.0124573708 4.0786666870 320 1305031112.8113100529 0.0744489282 0.0458273470 0.0843496993 0.0194299343 0.0066140000 0.0005500000 0.0029460000 0.0000020000 0.0000170000 0.0014010000 15257469 96830484 509673472 4.2561326027 4.0073843002 4.0795850754 321 1305031112.8432860374 0.0722187087 0.0459095631 0.0843496993 0.0194436594 0.0077120000 0.0004210000 0.0044890000 0.0000070000 0.0000070000 0.0017590000 15261141 96830484 509673472 4.2551822662 4.0085639954 4.0811924934 322 1305031112.8794209957 0.0671599433 0.0459755580 0.0843496993 0.0194508832 0.0063000000 0.0003860000 0.0043570000 0.0000010000 0.0000050000 0.0008880000 15264925 96830484 509673472 4.2552838326 4.0114474297 4.0825510025 323 1305031112.9114110470 0.0636761412 0.0460303586 0.0843496993 0.0194230956 0.0064930000 0.0004620000 0.0031830000 0.0000100000 0.0000090000 0.0013390000 15268653 96830484 509673472 4.2544765472 4.0107588768 4.0835237503 324 1305031112.9433209896 0.0608901754 0.0460762222 0.0843496993 0.0193964323 0.0066730000 0.0005320000 0.0024690000 0.0000030000 0.0000160000 0.0013390000 15272325 96830484 509673472 4.2516927719 4.0092000961 4.0840353966 325 1305031112.9792780876 0.0569471084 0.0461096711 0.0843496993 0.0194167052 0.0064970000 0.0004560000 0.0031990000 0.0000100000 0.0000090000 0.0016710000 15276109 96830484 509673472 4.2477469444 4.0065660477 4.0841059685 326 1305031113.0113530159 0.0540785827 0.0461341156 0.0843496993 0.0193925726 0.0054750000 0.0004600000 0.0024620000 0.0000010000 0.0000100000 0.0010670000 15279725 96830484 509673472 4.2432026863 4.0059475899 4.0838685036 327 1305031113.0432310104 0.0515771396 0.0461507610 0.0843496993 0.0193713944 0.0073440000 0.0005330000 0.0029770000 0.0000150000 0.0000130000 0.0015150000 15283453 96830484 509673472 4.2359876633 4.0062365532 4.0838809013 328 1305031113.0792510509 0.0493761227 0.0461605944 0.0843496993 0.0193830972 0.0055770000 0.0004650000 0.0028110000 0.0000020000 0.0000100000 0.0010360000 15287237 96830484 509673472 4.2271685600 4.0002822876 4.0827074051 329 1305031113.1113159657 0.0489612855 0.0461691071 0.0843496993 0.0193758236 0.0070490000 0.0004620000 0.0032100000 0.0000100000 0.0000090000 0.0017830000 15290853 96830484 509673472 4.2191562653 3.9959757328 4.0807466507 330 1305031113.1433060169 0.0457560346 0.0461678554 0.0843496993 0.0193576620 0.0077080000 0.0005360000 0.0037300000 0.0000020000 0.0000150000 0.0013050000 15294581 96830484 509673472 4.2087640762 3.9993674755 4.0799474716 331 1305031113.1793429852 0.0412714928 0.0461530627 0.0843496993 0.0193716075 0.0055940000 0.0004290000 0.0031100000 0.0000060000 0.0000060000 0.0010830000 15298365 96830484 509673472 4.1978793144 3.9978890419 4.0792398453 332 1305031113.2112588882 0.0435491800 0.0461452197 0.0843496993 0.0193592906 0.0072230000 0.0004620000 0.0046530000 0.0000020000 0.0000100000 0.0009120000 15301981 96830484 509673472 4.1868724823 3.9912874699 4.0775237083 333 1305031113.2432270050 0.0399208628 0.0461265280 0.0843496993 0.0193567675 0.0052470000 0.0004010000 0.0023550000 0.0000070000 0.0000070000 0.0015240000 15305709 96830484 509673472 4.1757249832 3.9932687283 4.0770702362 334 1305031113.2793118954 0.0343162641 0.0460911679 0.0843496993 0.0193732102 0.0043260000 0.0003900000 0.0023170000 0.0000010000 0.0000050000 0.0008110000 15309437 96830484 509673472 4.1641840935 3.9914324284 4.0770039558 335 1305031113.3114519119 0.0372062139 0.0460646456 0.0843496993 0.0194391580 0.0078980000 0.0005350000 0.0033570000 0.0000140000 0.0000130000 0.0015290000 15313109 96830484 509673472 4.1524143219 3.9829282761 4.0758633614 336 1305031113.3432519436 0.0342363007 0.0460294422 0.0843496993 0.0194489682 0.0076760000 0.0005360000 0.0041060000 0.0000020000 0.0000140000 0.0013440000 15316781 96830484 509673472 4.1397600174 3.9833378792 4.0746588707 337 1305031113.3793120384 0.0219207983 0.0459579032 0.0843496993 0.0194795129 0.0052730000 0.0004270000 0.0024070000 0.0000080000 0.0000070000 0.0014500000 15320509 96830484 509673472 4.1279964447 3.9910037518 4.0763053894 338 1305031113.4116249084 0.0228137337 0.0458894294 0.0843496993 0.0195019814 0.0073110000 0.0005370000 0.0029960000 0.0000020000 0.0000150000 0.0013480000 15324237 96830484 509673472 4.1127734184 3.9855580330 4.0778636932 339 1305031113.4432659149 0.0220251549 0.0458190333 0.0843496993 0.0194840490 0.0052770000 0.0004620000 0.0024560000 0.0000080000 0.0000060000 0.0011310000 15327909 96830484 509673472 4.0978569984 3.9834506512 4.0787053108 340 1305031113.4793109894 0.0154940533 0.0457298421 0.0843496993 0.0195071527 0.0055280000 0.0004010000 0.0033230000 0.0000000000 0.0000060000 0.0008300000 15331637 96830484 509673472 4.0784230232 3.9874007702 4.0809826851 341 1305031113.5115230083 0.0151699837 0.0456402238 0.0843496993 0.0194841919 0.0080250000 0.0005360000 0.0029830000 0.0000140000 0.0000130000 0.0020380000 15335365 96830484 509673472 4.0603184700 3.9856939316 4.0831770897 342 1305031113.5432419777 0.0164315943 0.0455548184 0.0843496993 0.0194769974 0.0059240000 0.0004590000 0.0028230000 0.0000020000 0.0000100000 0.0010170000 15339037 96830484 509673472 4.0451092720 3.9817159176 4.0843825340 343 1305031113.5793011189 0.0157369692 0.0454678859 0.0843496993 0.0194521091 0.0051640000 0.0004200000 0.0023850000 0.0000070000 0.0000070000 0.0011250000 15342765 96830484 509673472 4.0279908180 3.9796755314 4.0851392746 344 1305031113.6112680435 0.0127955005 0.0453729081 0.0843496993 0.0194275092 0.0091160000 0.0005310000 0.0048350000 0.0000010000 0.0000140000 0.0012950000 15346493 96830484 509673472 4.0123839378 3.9820339680 4.0866441727 345 1305031113.6432220936 0.0126484465 0.0452780546 0.0843496993 0.0194042013 0.0078360000 0.0004750000 0.0045840000 0.0000100000 0.0000090000 0.0015260000 15350165 96830484 509673472 3.9987227917 3.9817471504 4.0875000954 346 1305031113.6792879105 0.0130911693 0.0451850289 0.0843496993 0.0193837873 0.0053740000 0.0003970000 0.0033710000 0.0000010000 0.0000050000 0.0007760000 15354005 96830484 509673472 3.9837195873 3.9802901745 4.0879845619 347 1305031113.7119309902 0.0134627605 0.0450936102 0.0843496993 0.0193586610 0.0071530000 0.0005300000 0.0036920000 0.0000140000 0.0000130000 0.0012420000 15357621 96830484 509673472 3.9697144032 3.9799880981 4.0882301331 348 1305031113.7435901165 0.0134035405 0.0450025468 0.0843496993 0.0193316425 0.0055960000 0.0004230000 0.0030660000 0.0000010000 0.0000070000 0.0009040000 15361349 96830484 509673472 3.9549493790 3.9801857471 4.0886306763 349 1305031113.7793200016 0.0121820085 0.0449085052 0.0843496993 0.0193203599 0.0072430000 0.0003890000 0.0043950000 0.0000060000 0.0000050000 0.0014510000 15365077 96830484 509673472 3.9424910545 3.9806978703 4.0890159607 350 1305031113.8112370968 0.0134005258 0.0448184824 0.0843496993 0.0192945309 0.0076670000 0.0005280000 0.0033230000 0.0000020000 0.0000140000 0.0013080000 15368693 96830484 509673472 3.9276635647 3.9803261757 4.0901756287 351 1305031113.8432950974 0.0101637421 0.0447197509 0.0843496993 0.0192780653 0.0070610000 0.0004470000 0.0041890000 0.0000110000 0.0000080000 0.0011590000 15372421 96830484 509673472 3.9151759148 3.9840192795 4.0910201073 352 1305031113.8792810440 0.0118656401 0.0446264154 0.0843496993 0.0193168147 0.0064100000 0.0003960000 0.0043800000 0.0000010000 0.0000050000 0.0007930000 15376205 96830484 509673472 3.9000346661 3.9824607372 4.0923714638 353 1305031113.9112899303 0.0147837298 0.0445418752 0.0843496993 0.0192896590 0.0081060000 0.0005240000 0.0029600000 0.0000160000 0.0000130000 0.0020930000 15379877 96830484 509673472 3.8875207901 3.9802825451 4.0936470032 354 1305031113.9432909489 0.0117859785 0.0444493444 0.0843496993 0.0192749582 0.0050210000 0.0004470000 0.0023610000 0.0000010000 0.0000070000 0.0009370000 15383549 96830484 509673472 3.8767051697 3.9845008850 4.0943408012 355 1305031113.9792931080 0.0122327870 0.0443585935 0.0843496993 0.0192506101 0.0051840000 0.0003990000 0.0026600000 0.0000060000 0.0000060000 0.0010940000 15387333 96830484 509673472 3.8625550270 3.9857306480 4.0950579643 356 1305031114.0112569332 0.0110412017 0.0442650054 0.0843496993 0.0192389150 0.0056700000 0.0003980000 0.0033660000 0.0000010000 0.0000070000 0.0008770000 15391005 96830484 509673472 3.8477027416 3.9875233173 4.0959391594 357 1305031114.0433011055 0.0119483545 0.0441744825 0.0843496993 0.0192421431 0.0085910000 0.0005330000 0.0033360000 0.0000150000 0.0000130000 0.0021620000 15394677 96830484 509673472 3.8307423592 3.9889664650 4.0980429649 358 1305031114.0792849064 0.0139901396 0.0440901687 0.0843496993 0.0192367689 0.0061160000 0.0004740000 0.0028200000 0.0000010000 0.0000100000 0.0011250000 15398461 96830484 509673472 3.8166935444 3.9876201153 4.0999698639 359 1305031114.1112630367 0.0145061426 0.0440077620 0.0843496993 0.0192135183 0.0057160000 0.0004190000 0.0031090000 0.0000060000 0.0000050000 0.0011400000 15402133 96830484 509673472 3.8029315472 3.9903051853 4.1020121574 360 1305031114.1432840824 0.0165010765 0.0439313545 0.0843496993 0.0191898158 0.0071180000 0.0004580000 0.0042640000 0.0000020000 0.0000110000 0.0010980000 15405861 96830484 509673472 3.7877581120 3.9938735962 4.1050562859 361 1305031114.1793370247 0.0185472146 0.0438610383 0.0843496993 0.0192021748 0.0068750000 0.0004280000 0.0033070000 0.0000080000 0.0000080000 0.0017370000 15409645 96830484 509673472 3.7774364948 3.9927031994 4.1072368622 362 1305031114.2113029957 0.0198165830 0.0437946172 0.0843496993 0.0191994845 0.0056420000 0.0004510000 0.0033630000 0.0000000000 0.0000050000 0.0009140000 15413261 96830484 509673472 3.7649679184 3.9952292442 4.1096730232 363 1305031114.2433369160 0.0228416324 0.0437368955 0.0843496993 0.0192111791 0.0096500000 0.0005490000 0.0048140000 0.0000150000 0.0000130000 0.0016600000 15416933 96830484 509673472 3.7463681698 4.0012631416 4.1133699417 364 1305031114.2793900967 0.0240338445 0.0436827662 0.0843496993 0.0192576298 0.0064120000 0.0004560000 0.0035090000 0.0000020000 0.0000100000 0.0011380000 15420717 96830484 509673472 3.7347316742 3.9979851246 4.1168231964 365 1305031114.3114290237 0.0276949797 0.0436389640 0.0843496993 0.0192405261 0.0062480000 0.0003960000 0.0033690000 0.0000060000 0.0000040000 0.0015980000 15424389 96830484 509673472 3.7224767208 3.9992558956 4.1211352348 366 1305031114.3433310986 0.0306202378 0.0436033938 0.0843496993 0.0192265699 0.0050130000 0.0003750000 0.0029670000 0.0000000000 0.0000040000 0.0009180000 15428117 96830484 509673472 3.7140643597 4.0012683868 4.1244134903 367 1305031114.3793199062 0.0335211381 0.0435759217 0.0843496993 0.0192087165 0.0066240000 0.0003710000 0.0043530000 0.0000050000 0.0000040000 0.0011370000 15431901 96830484 509673472 3.7074227333 4.0013074875 4.1268458366 368 1305031114.4113969803 0.0348641574 0.0435522484 0.0843496993 0.0191907612 0.0054600000 0.0003810000 0.0033130000 0.0000010000 0.0000050000 0.0009790000 15435573 96830484 509673472 3.6948361397 4.0004658699 4.1293973923 369 1305031114.4433450699 0.0372555032 0.0435351840 0.0843496993 0.0191815061 0.0072630000 0.0004130000 0.0043620000 0.0000050000 0.0000040000 0.0017110000 15439245 96830484 509673472 3.6803030968 3.9995982647 4.1329932213 370 1305031114.4793319702 0.0401844606 0.0435261280 0.0843496993 0.0191871351 0.0051360000 0.0003800000 0.0029820000 0.0000000000 0.0000050000 0.0009980000 15443029 96830484 509673472 3.6715927124 3.9970612526 4.1365685463 371 1305031114.5112659931 0.0424421057 0.0435232061 0.0843496993 0.0191650727 0.0057320000 0.0003820000 0.0033440000 0.0000050000 0.0000040000 0.0012290000 15446645 96830484 509673472 3.6638119221 3.9950981140 4.1402297020 372 1305031114.5432360172 0.0459399335 0.0435297027 0.0843496993 0.0191505906 0.0048110000 0.0003810000 0.0026470000 0.0000000000 0.0000040000 0.0010070000 15450373 96830484 509673472 3.6583182812 3.9956204891 4.1447100639 373 1305031114.5792369843 0.0469363667 0.0435388359 0.0843496993 0.0191311737 0.0073300000 0.0003840000 0.0043880000 0.0000050000 0.0000040000 0.0017660000 15454157 96830484 509673472 3.6552681923 3.9921083450 4.1461772919 374 1305031114.6113910675 0.0480838604 0.0435509883 0.0843496993 0.0191151874 0.0058600000 0.0003810000 0.0036920000 0.0000010000 0.0000050000 0.0010090000 15457773 96830484 509673472 3.6491689682 3.9920508862 4.1486649513 375 1305031114.6441500187 0.0487271696 0.0435647915 0.0843496993 0.0190990276 0.0067700000 0.0003790000 0.0043790000 0.0000050000 0.0000040000 0.0012330000 15461501 96830484 509673472 3.6435592175 3.9935507774 4.1501636505 376 1305031114.6792509556 0.0509203114 0.0435843540 0.0843496993 0.0190921178 0.0055170000 0.0003790000 0.0033590000 0.0000000000 0.0000040000 0.0010010000 15465173 96830484 509673472 3.6407241821 3.9873886108 4.1520800591 377 1305031114.7113060951 0.0537331030 0.0436112738 0.0843496993 0.0190890488 0.0059650000 0.0003960000 0.0030090000 0.0000050000 0.0000040000 0.0017650000 15468789 96830484 509673472 3.6397547722 3.9825966358 4.1537547112 378 1305031114.7432758808 0.0554376096 0.0436425604 0.0843496993 0.0190666905 0.0085210000 0.0005510000 0.0037520000 0.0000020000 0.0000150000 0.0015790000 15472517 96830484 509673472 3.6394324303 3.9813609123 4.1543602943 379 1305031114.7792890072 0.0592367351 0.0436837060 0.0843496993 0.0190485388 0.0076740000 0.0005410000 0.0037200000 0.0000150000 0.0000130000 0.0016320000 15476301 96830484 509673472 3.6393492222 3.9782149792 4.1569180489 380 1305031114.8113029003 0.0590756238 0.0437242110 0.0843496993 0.0190356244 0.0059860000 0.0004290000 0.0034320000 0.0000000000 0.0000060000 0.0010570000 15479917 96830484 509673472 3.6383395195 3.9804606438 4.1569666862 381 1305031114.8432080746 0.0592129752 0.0437648640 0.0843496993 0.0190114679 0.0062720000 0.0003910000 0.0033420000 0.0000050000 0.0000040000 0.0017610000 15483645 96830484 509673472 3.6379928589 3.9809150696 4.1568684578 382 1305031114.8792810440 0.0577719547 0.0438015317 0.0843496993 0.0189866308 0.0092110000 0.0005400000 0.0044270000 0.0000020000 0.0000170000 0.0015600000 15487373 96830484 509673472 3.6393580437 3.9821560383 4.1556091309 383 1305031114.9128789902 0.0571677759 0.0438364305 0.0843496993 0.0189653597 0.0067690000 0.0004710000 0.0034990000 0.0000100000 0.0000090000 0.0014490000 15491157 96830484 509673472 3.6432495117 3.9844849110 4.1549410820 384 1305031114.9432640076 0.0573870949 0.0438717187 0.0843496993 0.0189421659 0.0053210000 0.0004060000 0.0030170000 0.0000000000 0.0000050000 0.0009920000 15494717 96830484 509673472 3.6468703747 3.9872381687 4.1562304497 385 1305031114.9792799950 0.0548059195 0.0439001193 0.0843496993 0.0189218864 0.0058540000 0.0003790000 0.0029830000 0.0000050000 0.0000040000 0.0017150000 15498501 96830484 509673472 3.6550958157 3.9902179241 4.1547870636 386 1305031115.0113000870 0.0508368313 0.0439180900 0.0843496993 0.0189053098 0.0084640000 0.0005370000 0.0037210000 0.0000010000 0.0000140000 0.0015260000 15502173 96830484 509673472 3.6594600677 3.9952731133 4.1527380943 387 1305031115.0435299873 0.0496676750 0.0439329468 0.0843496993 0.0189018525 0.0078300000 0.0004770000 0.0046290000 0.0000100000 0.0000090000 0.0013530000 15505901 96830484 509673472 3.6702151299 3.9964213371 4.1529440880 388 1305031115.0792379379 0.0464834645 0.0439395203 0.0843496993 0.0188795456 0.0067310000 0.0004040000 0.0044610000 0.0000010000 0.0000050000 0.0009590000 15509685 96830484 509673472 3.6818528175 3.9967153072 4.1520376205 389 1305031115.1112298965 0.0451093316 0.0439425275 0.0843496993 0.0188718642 0.0060830000 0.0003790000 0.0033660000 0.0000040000 0.0000040000 0.0016430000 15513301 96830484 509673472 3.6930260658 3.9980721474 4.1527953148 390 1305031115.1432940960 0.0413456410 0.0439358689 0.0843496993 0.0188656864 0.0084560000 0.0005370000 0.0045020000 0.0000030000 0.0000140000 0.0014150000 15517029 96830484 509673472 3.7107462883 3.9999189377 4.1509542465 391 1305031115.1794400215 0.0379441790 0.0439205448 0.0843496993 0.0188703019 0.0066240000 0.0004850000 0.0034610000 0.0000070000 0.0000080000 0.0011930000 15520813 96830484 509673472 3.7189850807 3.9997253418 4.1517634392 392 1305031115.2113740444 0.0375142321 0.0439042022 0.0843496993 0.0188769312 0.0061710000 0.0004020000 0.0037690000 0.0000010000 0.0000060000 0.0008970000 15524429 96830484 509673472 3.7321226597 3.9975721836 4.1533555984 393 1305031115.2432971001 0.0382247940 0.0438897508 0.0843496993 0.0188727116 0.0098660000 0.0005380000 0.0049060000 0.0000140000 0.0000120000 0.0021760000 15528157 96830484 509673472 3.7493369579 3.9933655262 4.1551728249 394 1305031115.2799661160 0.0349800140 0.0438671372 0.0843496993 0.0189000804 0.0069560000 0.0004210000 0.0045110000 0.0000010000 0.0000060000 0.0008910000 15531885 96830484 509673472 3.7593297958 3.9963319302 4.1575307846 395 1305031115.3117039204 0.0324780680 0.0438383042 0.0843496993 0.0189214423 0.0052340000 0.0003830000 0.0030060000 0.0000050000 0.0000040000 0.0010490000 15535613 96830484 509673472 3.7755465508 3.9982910156 4.1591010094 396 1305031115.3434259892 0.0319685265 0.0438083300 0.0843496993 0.0189065167 0.0091010000 0.0005680000 0.0048410000 0.0000020000 0.0000140000 0.0013740000 15539285 96830484 509673472 3.7922770977 3.9960169792 4.1596941948 397 1305031115.3791658878 0.0303974040 0.0437745493 0.0843496993 0.0191709826 0.0058380000 0.0004230000 0.0027160000 0.0000080000 0.0000070000 0.0015580000 15542957 96830484 509673472 3.7991383076 4.0045971870 4.1620326042 398 1305031115.4112370014 0.0339021236 0.0437497442 0.0843496993 0.0191577621 0.0060600000 0.0004620000 0.0027950000 0.0000010000 0.0000100000 0.0010740000 15546629 96830484 509673472 3.8104736805 4.0032935143 4.1649160385 399 1305031115.4431591034 0.0346933492 0.0437270465 0.0843496993 0.0191944950 0.0074570000 0.0005480000 0.0025870000 0.0000150000 0.0000130000 0.0015480000 15550301 96830484 509673472 3.8316786289 4.0001983643 4.1685457230 400 1305031115.4792408943 0.0362119339 0.0437082587 0.0843496993 0.0191764897 0.0072310000 0.0004570000 0.0038760000 0.0000010000 0.0000100000 0.0010530000 15554085 96830484 509673472 3.8500685692 4.0013642311 4.1709418297 401 1305031115.5112531185 0.0391280726 0.0436968368 0.0843496993 0.0192427993 0.0089500000 0.0005520000 0.0033760000 0.0000150000 0.0000140000 0.0020830000 15557701 96830484 509673472 3.8665490150 3.9991898537 4.1728677750 402 1305031115.5436201096 0.0383911803 0.0436836386 0.0843496993 0.0192827556 0.0084640000 0.0005670000 0.0037210000 0.0000020000 0.0000150000 0.0012800000 15561429 96830484 509673472 3.8897707462 3.9974358082 4.1730194092 403 1305031115.5793149471 0.0400495306 0.0436746210 0.0843496993 0.0192597029 0.0087060000 0.0005480000 0.0048760000 0.0000150000 0.0000130000 0.0013150000 15565213 96830484 509673472 3.9062952995 3.9975891113 4.1716508865 404 1305031115.6114239693 0.0423504375 0.0436713433 0.0843496993 0.0192399573 0.0054820000 0.0004290000 0.0030910000 0.0000010000 0.0000060000 0.0007900000 15568829 96830484 509673472 3.9197866917 3.9965436459 4.1705231667 405 1305031115.6432540417 0.0419480056 0.0436670882 0.0843496993 0.0192182699 0.0051750000 0.0003880000 0.0026680000 0.0000050000 0.0000040000 0.0012760000 15572501 96830484 509673472 3.9368243217 3.9959459305 4.1690311432 406 1305031115.6792409420 0.0459006540 0.0436725896 0.0843496993 0.0192017530 0.0076980000 0.0005500000 0.0030020000 0.0000030000 0.0000170000 0.0012180000 15576285 96830484 509673472 3.9525227547 3.9947755337 4.1674914360 407 1305031115.7113199234 0.0463099927 0.0436790697 0.0843496993 0.0192220923 0.0078630000 0.0005320000 0.0029880000 0.0000150000 0.0000160000 0.0014350000 15579957 96830484 509673472 3.9674634933 3.9950594902 4.1660380363 408 1305031115.7432498932 0.0420768447 0.0436751426 0.0843496993 0.0192608705 0.0070670000 0.0005460000 0.0033410000 0.0000020000 0.0000140000 0.0011890000 15583685 96830484 509673472 3.9873056412 3.9971837997 4.1640844345 409 1305031115.7794249058 0.0429966301 0.0436734837 0.0843496993 0.0192669766 0.0070150000 0.0004560000 0.0032040000 0.0000090000 0.0000090000 0.0015730000 15587469 96830484 509673472 4.0084419250 3.9960808754 4.1615943909 410 1305031115.8112769127 0.0433317572 0.0436726502 0.0843496993 0.0192624582 0.0052380000 0.0004040000 0.0030650000 0.0000000000 0.0000050000 0.0007870000 15591085 96830484 509673472 4.0207715034 3.9979710579 4.1597805023 411 1305031115.8432240486 0.0403378569 0.0436645364 0.0843496993 0.0192504977 0.0076290000 0.0005290000 0.0026550000 0.0000140000 0.0000130000 0.0014780000 15594813 96830484 509673472 4.0370798111 4.0014257431 4.1581878662 412 1305031115.8791980743 0.0478888713 0.0436747896 0.0843496993 0.0192406688 0.0064410000 0.0004610000 0.0032190000 0.0000020000 0.0000100000 0.0010310000 15598485 96830484 509673472 4.0492076874 3.9981789589 4.1574101448 413 1305031115.9111180305 0.0493596420 0.0436885544 0.0843496993 0.0192260512 0.0061190000 0.0004020000 0.0030660000 0.0000050000 0.0000050000 0.0014620000 15602157 96830484 509673472 4.0621089935 3.9983272552 4.1565632820 414 1305031115.9433109760 0.0466563106 0.0436957229 0.0843496993 0.0192229874 0.0078060000 0.0005370000 0.0030650000 0.0000020000 0.0000150000 0.0012600000 15605773 96830484 509673472 4.0761942863 4.0029439926 4.1565241814 415 1305031115.9807400703 0.0528081842 0.0437176806 0.0843496993 0.0192141282 0.0061460000 0.0004660000 0.0028440000 0.0000100000 0.0000090000 0.0012520000 15609557 96830484 509673472 4.0852861404 4.0047445297 4.1574978828 416 1305031116.0113790035 0.0529815443 0.0437399495 0.0843496993 0.0192558056 0.0051530000 0.0004060000 0.0027370000 0.0000010000 0.0000060000 0.0008160000 15613173 96830484 509673472 4.0967025757 4.0078749657 4.1578860283 417 1305031116.0431640148 0.0554692447 0.0437680773 0.0843496993 0.0192400324 0.0058290000 0.0003920000 0.0030520000 0.0000050000 0.0000040000 0.0013850000 15616901 96830484 509673472 4.1048784256 4.0111041069 4.1587820053 418 1305031116.0800299644 0.0630565360 0.0438142219 0.0843496993 0.0192420979 0.0077700000 0.0005360000 0.0030050000 0.0000010000 0.0000140000 0.0012440000 15620685 96830484 509673472 4.1127333641 4.0126237869 4.1609644890 419 1305031116.1112999916 0.0645946786 0.0438638173 0.0843496993 0.0192255404 0.0085820000 0.0005420000 0.0048300000 0.0000110000 0.0000090000 0.0012120000 15624301 96830484 509673472 4.1222252846 4.0150647163 4.1633386612 420 1305031116.1434469223 0.0675309300 0.0439201676 0.0843496993 0.0192056285 0.0057910000 0.0004290000 0.0034090000 0.0000010000 0.0000060000 0.0007850000 15627973 96830484 509673472 4.1319470406 4.0143661499 4.1653027534 421 1305031116.1795721054 0.0730214044 0.0439892917 0.0843496993 0.0191860017 0.0083180000 0.0005370000 0.0033310000 0.0000140000 0.0000120000 0.0019760000 15631757 96830484 509673472 4.1417407990 4.0139970779 4.1670441628 422 1305031116.2113199234 0.0733632073 0.0440588981 0.0843496993 0.0191661837 0.0058750000 0.0004250000 0.0034530000 0.0000020000 0.0000080000 0.0007890000 15635429 96830484 509673472 4.1513633728 4.0165128708 4.1689867973 423 1305031116.2433199883 0.0747402757 0.0441314309 0.0843496993 0.0191517554 0.0085400000 0.0005330000 0.0048060000 0.0000100000 0.0000080000 0.0011940000 15639101 96830484 509673472 4.1614089012 4.0159330368 4.1700367928 424 1305031116.2793850899 0.0790473446 0.0442137798 0.0843496993 0.0191648009 0.0058760000 0.0004270000 0.0034480000 0.0000010000 0.0000050000 0.0008000000 15642941 96830484 509673472 4.1698331833 4.0165233612 4.1696038246 425 1305031116.3113360405 0.0792837068 0.0442962972 0.0843496993 0.0191630017 0.0054440000 0.0003900000 0.0026620000 0.0000050000 0.0000040000 0.0013680000 15646557 96830484 509673472 4.1781549454 4.0173740387 4.1696710587 426 1305031116.3432919979 0.0793948248 0.0443786881 0.0843496993 0.0191487651 0.0085360000 0.0005330000 0.0037140000 0.0000020000 0.0000150000 0.0012620000 15650229 96830484 509673472 4.1862897873 4.0162415504 4.1682643890 427 1305031116.3793840408 0.0816334412 0.0444659358 0.0843496993 0.0191382330 0.0069730000 0.0005330000 0.0029790000 0.0000140000 0.0000130000 0.0013610000 15653957 96830484 509673472 4.1919283867 4.0143132210 4.1652956009 428 1305031116.4113330841 0.0791359097 0.0445469404 0.0843496993 0.0191198452 0.0069380000 0.0004320000 0.0045190000 0.0000010000 0.0000060000 0.0008360000 15657685 96830484 509673472 4.1972947121 4.0169286728 4.1627392769 429 1305031116.4433689117 0.0750616044 0.0446180702 0.0843496993 0.0191079999 0.0064140000 0.0003820000 0.0037240000 0.0000040000 0.0000030000 0.0014150000 15661413 96830484 509673472 4.2028446198 4.0187644958 4.1614079475 430 1305031116.4798500538 0.0723047704 0.0446824578 0.0843496993 0.0190896229 0.0082360000 0.0005390000 0.0033600000 0.0000030000 0.0000140000 0.0012780000 15665197 96830484 509673472 4.2054367065 4.0173916817 4.1593995094 431 1305031116.5112049580 0.0712898076 0.0447441918 0.0843496993 0.0190733291 0.0061670000 0.0004590000 0.0031200000 0.0000070000 0.0000070000 0.0011290000 15668813 96830484 509673472 4.2027478218 4.0172371864 4.1569142342 432 1305031116.5432620049 0.0696599707 0.0448018672 0.0843496993 0.0190515627 0.0066750000 0.0004630000 0.0032010000 0.0000020000 0.0000100000 0.0010320000 15672485 96830484 509673472 4.1986699104 4.0167374611 4.1548418999 433 1305031116.5793130398 0.0640139282 0.0448462369 0.0843496993 0.0190626389 0.0077440000 0.0004230000 0.0041860000 0.0000070000 0.0000070000 0.0015870000 15676269 96830484 509673472 4.1931638718 4.0176892281 4.1535100937 434 1305031116.6112608910 0.0608559698 0.0448831257 0.0843496993 0.0190601458 0.0073430000 0.0005330000 0.0037370000 0.0000010000 0.0000100000 0.0010120000 15679885 96830484 509673472 4.1866855621 4.0166511536 4.1519322395 435 1305031116.6433548927 0.0596116856 0.0449169844 0.0843496993 0.0190558550 0.0066670000 0.0004260000 0.0038130000 0.0000080000 0.0000070000 0.0010900000 15683557 96830484 509673472 4.1766114235 4.0153083801 4.1507539749 436 1305031116.6792809963 0.0536690131 0.0449370579 0.0843496993 0.0190461132 0.0055680000 0.0003930000 0.0033870000 0.0000000000 0.0000050000 0.0007460000 15687453 96830484 509673472 4.1662631035 4.0147514343 4.1501970291 437 1305031116.7116339207 0.0530715920 0.0449556724 0.0843496993 0.0190272839 0.0096780000 0.0005370000 0.0048270000 0.0000150000 0.0000140000 0.0019620000 15691069 96830484 509673472 4.1534852982 4.0129828453 4.1494112015 438 1305031116.7432909012 0.0526769198 0.0449733008 0.0843496993 0.0190216374 0.0060510000 0.0004630000 0.0031900000 0.0000010000 0.0000070000 0.0008400000 15694741 96830484 509673472 4.1389775276 4.0121283531 4.1492552757 439 1305031116.7792980671 0.0495636687 0.0449837572 0.0843496993 0.0190197515 0.0053830000 0.0004040000 0.0027100000 0.0000050000 0.0000060000 0.0010030000 15698525 96830484 509673472 4.1242003441 4.0106582642 4.1488690376 440 1305031116.8113429546 0.0505492017 0.0449964060 0.0843496993 0.0190598357 0.0054800000 0.0004010000 0.0033420000 0.0000010000 0.0000050000 0.0007500000 15702197 96830484 509673472 4.1095237732 4.0079030991 4.1476149559 441 1305031116.8460888863 0.0484807976 0.0450043071 0.0843496993 0.0191594612 0.0103520000 0.0007410000 0.0041960000 0.0000150000 0.0000140000 0.0020240000 15705925 96830484 509673472 4.0942263603 4.0057511330 4.1464915276 442 1305031116.8801651001 0.0459440239 0.0450064331 0.0843496993 0.0191381384 0.0057570000 0.0004890000 0.0028050000 0.0000020000 0.0000080000 0.0008560000 15709653 96830484 509673472 4.0797128677 4.0074634552 4.1458497047 443 1305031116.9120440483 0.0469146818 0.0450107407 0.0843496993 0.0191293311 0.0062850000 0.0004040000 0.0037350000 0.0000060000 0.0000060000 0.0010010000 15713325 96830484 509673472 4.0651206970 4.0055785179 4.1458368301 444 1305031116.9432959557 0.0436445214 0.0450076636 0.0843496993 0.0191214020 0.0079250000 0.0005380000 0.0033210000 0.0000020000 0.0000160000 0.0012260000 15716997 96830484 509673472 4.0514492989 4.0078411102 4.1454377174 445 1305031116.9793510437 0.0422259234 0.0450014125 0.0843496993 0.0191262864 0.0065520000 0.0004240000 0.0034210000 0.0000060000 0.0000060000 0.0014240000 15720725 96830484 509673472 4.0345335007 4.0087628365 4.1455750465 446 1305031117.0113821030 0.0420152955 0.0449947172 0.0843496993 0.0191235763 0.0071300000 0.0005360000 0.0033240000 0.0000020000 0.0000140000 0.0011460000 15724453 96830484 509673472 4.0185937881 4.0101056099 4.1448636055 447 1305031117.0432610512 0.0413936414 0.0449866611 0.0843496993 0.0191041217 0.0057900000 0.0004230000 0.0030500000 0.0000060000 0.0000050000 0.0010310000 15728125 96830484 509673472 4.0001516342 4.0135641098 4.1451911926 448 1305031117.0795199871 0.0401975773 0.0449759712 0.0843496993 0.0190996927 0.0076750000 0.0005360000 0.0029550000 0.0000020000 0.0000150000 0.0012330000 15731909 96830484 509673472 3.9858975410 4.0165815353 4.1457338333 449 1305031117.1112380028 0.0426572748 0.0449708071 0.0843496993 0.0190962329 0.0074410000 0.0004570000 0.0038720000 0.0000070000 0.0000070000 0.0015040000 15735525 96830484 509673472 3.9745447636 4.0165553093 4.1471490860 450 1305031117.1432180405 0.0444076918 0.0449695557 0.0843496993 0.0190788317 0.0084350000 0.0005310000 0.0047850000 0.0000010000 0.0000090000 0.0009750000 15739253 96830484 509673472 3.9629025459 4.0178036690 4.1491403580 451 1305031117.1792640686 0.0430361368 0.0449652687 0.0843496993 0.0190603981 0.0057660000 0.0004210000 0.0030420000 0.0000070000 0.0000050000 0.0010140000 15743037 96830484 509673472 3.9545869827 4.0211677551 4.1501507759 452 1305031117.2113609314 0.0450248793 0.0449654006 0.0843496993 0.0190620149 0.0055180000 0.0003860000 0.0033150000 0.0000010000 0.0000050000 0.0007580000 15746709 96830484 509673472 3.9458310604 4.0208883286 4.1518983841 453 1305031117.2432770729 0.0435205549 0.0449622111 0.0843496993 0.0190594701 0.0071830000 0.0003880000 0.0043350000 0.0000050000 0.0000050000 0.0013770000 15750381 96830484 509673472 3.9435079098 4.0233888626 4.1536116600 454 1305031117.2792990208 0.0430055857 0.0449579014 0.0843496993 0.0190446058 0.0048360000 0.0003850000 0.0026040000 0.0000010000 0.0000050000 0.0007770000 15754165 96830484 509673472 3.9390420914 4.0243482590 4.1552400589 455 1305031117.3111999035 0.0460737348 0.0449603537 0.0843496993 0.0190333203 0.0084460000 0.0005320000 0.0032730000 0.0000140000 0.0000130000 0.0014560000 15757781 96830484 509673472 3.9348506927 4.0211291313 4.1570434570 456 1305031117.3432428837 0.0498294458 0.0449710316 0.0843496993 0.0190232823 0.0069320000 0.0005520000 0.0032400000 0.0000020000 0.0000100000 0.0010040000 15761509 96830484 509673472 3.9301059246 4.0166549683 4.1580915451 457 1305031117.3794538975 0.0503932722 0.0449828964 0.0843496993 0.0190133493 0.0072390000 0.0004060000 0.0043380000 0.0000050000 0.0000040000 0.0013870000 15765293 96830484 509673472 3.9285306931 4.0129418373 4.1580538750 458 1305031117.4112210274 0.0506399497 0.0449952481 0.0843496993 0.0189936707 0.0053420000 0.0003760000 0.0032560000 0.0000010000 0.0000050000 0.0007610000 15768965 96830484 509673472 3.9269688129 4.0092206001 4.1574110985 459 1305031117.4432740211 0.0495947301 0.0450052687 0.0843496993 0.0189747437 0.0051340000 0.0003700000 0.0029470000 0.0000040000 0.0000030000 0.0009800000 15772637 96830484 509673472 3.9275376797 4.0054993629 4.1565074921 460 1305031117.4794030190 0.0454306118 0.0450061934 0.0843496993 0.0189591847 0.0062060000 0.0003610000 0.0043180000 0.0000000000 0.0000040000 0.0006940000 15776421 96830484 509673472 3.9283974171 4.0024709702 4.1554145813 461 1305031117.5113248825 0.0454066843 0.0450070621 0.0843496993 0.0189408903 0.0106350000 0.0005330000 0.0048490000 0.0000150000 0.0000130000 0.0019670000 15780093 96830484 509673472 3.9279496670 3.9960644245 4.1546568871 462 1305031117.5442850590 0.0429525822 0.0450026152 0.0843496993 0.0189230587 0.0075220000 0.0004750000 0.0045870000 0.0000010000 0.0000080000 0.0008510000 15783709 96830484 509673472 3.9272570610 3.9919099808 4.1536087990 463 1305031117.5791549683 0.0367616676 0.0449848162 0.0843496993 0.0189042346 0.0047970000 0.0004060000 0.0023050000 0.0000050000 0.0000050000 0.0009630000 15787549 96830484 509673472 3.9271891117 3.9889392853 4.1532082558 464 1305031117.6111590862 0.0347314514 0.0449627184 0.0843496993 0.0188851228 0.0043830000 0.0003790000 0.0022950000 0.0000010000 0.0000050000 0.0007300000 15791165 96830484 509673472 3.9263029099 3.9841794968 4.1544847488 465 1305031117.6432840824 0.0346991271 0.0449406462 0.0843496993 0.0188670314 0.0097060000 0.0005610000 0.0037620000 0.0000160000 0.0000140000 0.0020140000 15794893 96830484 509673472 3.9263694286 3.9769952297 4.1565937996 466 1305031117.6792619228 0.0308229476 0.0449103507 0.0843496993 0.0188525472 0.0061570000 0.0004750000 0.0028130000 0.0000010000 0.0000100000 0.0010120000 15798677 96830484 509673472 3.9253726006 3.9717183113 4.1592459679 467 1305031117.7112150192 0.0310839936 0.0448807439 0.0843496993 0.0188339491 0.0052420000 0.0004050000 0.0026870000 0.0000050000 0.0000040000 0.0009940000 15802293 96830484 509673472 3.9264378548 3.9639580250 4.1628875732 468 1305031117.7431840897 0.0321250260 0.0448534881 0.0843496993 0.0188163188 0.0081810000 0.0005310000 0.0030120000 0.0000020000 0.0000150000 0.0012930000 15805965 96830484 509673472 3.9270491600 3.9549446106 4.1668362617 469 1305031117.7794671059 0.0296826810 0.0448211410 0.0843496993 0.0187964339 0.0077770000 0.0004580000 0.0045280000 0.0000070000 0.0000070000 0.0014250000 15809749 96830484 509673472 3.9259104729 3.9477953911 4.1704707146 470 1305031117.8113200665 0.0284285061 0.0447862630 0.0843496993 0.0187800289 0.0065570000 0.0003830000 0.0043790000 0.0000000000 0.0000040000 0.0007670000 15813421 96830484 509673472 3.9277648926 3.9402539730 4.1743822098 471 1305031117.8433070183 0.0303855054 0.0447556882 0.0843496993 0.0187720091 0.0072580000 0.0006130000 0.0029690000 0.0000100000 0.0000090000 0.0012700000 15816981 96830484 509673472 3.9296352863 3.9294755459 4.1786279678 472 1305031117.8794670105 0.0267988797 0.0447176441 0.0843496993 0.0187553960 0.0068520000 0.0004210000 0.0044340000 0.0000010000 0.0000070000 0.0008420000 15820765 96830484 509673472 3.9303262234 3.9231164455 4.1819229126 473 1305031117.9114069939 0.0281010959 0.0446825140 0.0843496993 0.0187366837 0.0081700000 0.0004540000 0.0045380000 0.0000080000 0.0000060000 0.0015460000 15824381 96830484 509673472 3.9288842678 3.9144794941 4.1860628128 474 1305031117.9432721138 0.0297294352 0.0446509674 0.0843496993 0.0187176724 0.0064890000 0.0003830000 0.0043450000 0.0000000000 0.0000040000 0.0007830000 15828053 96830484 509673472 3.9280974865 3.9054844379 4.1907939911 475 1305031117.9792630672 0.0285863336 0.0446171471 0.0843496993 0.0187104403 0.0064250000 0.0003610000 0.0042690000 0.0000040000 0.0000030000 0.0009880000 15831837 96830484 509673472 3.9260003567 3.8996367455 4.1953086853 476 1305031118.0112280846 0.0316208713 0.0445898440 0.0843496993 0.0186945360 0.0081450000 0.0005300000 0.0036390000 0.0000020000 0.0000140000 0.0013350000 15835453 96830484 509673472 3.9235138893 3.8894112110 4.2009997368 477 1305031118.0435490608 0.0338171534 0.0445672597 0.0843496993 0.0186788075 0.0059370000 0.0004240000 0.0026810000 0.0000070000 0.0000070000 0.0014480000 15839181 96830484 509673472 3.9253609180 3.8782467842 4.2064065933 478 1305031118.0793690681 0.0342011787 0.0445455734 0.0843496993 0.0186627614 0.0052620000 0.0003720000 0.0029340000 0.0000010000 0.0000060000 0.0008080000 15842965 96830484 509673472 3.9230427742 3.8706588745 4.2115583420 479 1305031118.1112170219 0.0354276076 0.0445265380 0.0843496993 0.0186502590 0.0083710000 0.0005240000 0.0029040000 0.0000140000 0.0000130000 0.0015220000 15846581 96830484 509673472 3.9240741730 3.8617985249 4.2163286209 480 1305031118.1432559490 0.0376864001 0.0445122877 0.0843496993 0.0186332546 0.0061800000 0.0004490000 0.0030580000 0.0000020000 0.0000080000 0.0009310000 15850309 96830484 509673472 3.9224295616 3.8523852825 4.2209181786 481 1305031118.1793229580 0.0388082080 0.0445004289 0.0843496993 0.0186158396 0.0082510000 0.0005180000 0.0036190000 0.0000140000 0.0000130000 0.0017360000 15854093 96830484 509673472 3.9210948944 3.8436920643 4.2253990173 482 1305031118.2112019062 0.0418078974 0.0444948427 0.0843496993 0.0186074137 0.0069240000 0.0004080000 0.0043620000 0.0000010000 0.0000060000 0.0008570000 15857709 96830484 509673472 3.9209516048 3.8320221901 4.2297248840 483 1305031118.2431728840 0.0441141725 0.0444940546 0.0843496993 0.0185997201 0.0061040000 0.0004400000 0.0027420000 0.0000110000 0.0000090000 0.0011780000 15861381 96830484 509673472 3.9177029133 3.8231680393 4.2337603569 484 1305031118.2791941166 0.0449115261 0.0444949171 0.0843496993 0.0186017728 0.0076000000 0.0005170000 0.0036140000 0.0000030000 0.0000150000 0.0011660000 15865165 96830484 509673472 3.9169557095 3.8152506351 4.2371234894 485 1305031118.3112990856 0.0473807938 0.0445008674 0.0843496993 0.0185830064 0.0063210000 0.0004030000 0.0029770000 0.0000060000 0.0000060000 0.0015490000 15868837 96830484 509673472 3.9154319763 3.8062694073 4.2408828735 486 1305031118.3433239460 0.0467941910 0.0445055862 0.0843496993 0.0185755505 0.0083610000 0.0005130000 0.0032920000 0.0000020000 0.0000140000 0.0014270000 15872509 96830484 509673472 3.9145081043 3.8037955761 4.2435698509 487 1305031118.3792080879 0.0479404628 0.0445126393 0.0843496993 0.0185570264 0.0054270000 0.0004050000 0.0022890000 0.0000070000 0.0000060000 0.0012320000 15876293 96830484 509673472 3.9123899937 3.7989296913 4.2473630905 488 1305031118.4112958908 0.0501919799 0.0445242773 0.0843496993 0.0185500614 0.0069880000 0.0004400000 0.0030700000 0.0000010000 0.0000100000 0.0011660000 15879965 96830484 509673472 3.9089770317 3.7944242954 4.2516474724 489 1305031118.4457030296 0.0483807921 0.0445321638 0.0843496993 0.0185339259 0.0090630000 0.0005290000 0.0032740000 0.0000140000 0.0000130000 0.0022970000 15883693 96830484 509673472 3.9121716022 3.7938735485 4.2553334236 490 1305031118.4792850018 0.0488280095 0.0445409309 0.0843496993 0.0185150861 0.0054540000 0.0004060000 0.0026320000 0.0000010000 0.0000080000 0.0010110000 15887365 96830484 509673472 3.9123435020 3.7913327217 4.2582378387 491 1305031118.5112550259 0.0497293100 0.0445514978 0.0843496993 0.0185005575 0.0058970000 0.0003720000 0.0032240000 0.0000050000 0.0000040000 0.0011280000 15891037 96830484 509673472 3.9122798443 3.7893266678 4.2609434128 492 1305031118.5451989174 0.0472029075 0.0445568869 0.0843496993 0.0184972110 0.0087260000 0.0005290000 0.0036580000 0.0000020000 0.0000150000 0.0014650000 15894765 96830484 509673472 3.9138844013 3.7940397263 4.2627348900 493 1305031118.5792849064 0.0472516008 0.0445623528 0.0843496993 0.0184794533 0.0077930000 0.0004090000 0.0043580000 0.0000060000 0.0000050000 0.0015910000 15898549 96830484 509673472 3.9150269032 3.7955594063 4.2639245987 494 1305031118.6161420345 0.0475183837 0.0445683367 0.0843496993 0.0184632785 0.0072630000 0.0004440000 0.0043950000 0.0000010000 0.0000070000 0.0010040000 15902333 96830484 509673472 3.9158072472 3.7984106541 4.2639946938 495 1305031118.6453309059 0.0451998338 0.0445696124 0.0843496993 0.0184487457 0.0064950000 0.0004490000 0.0030590000 0.0000070000 0.0000070000 0.0012030000 15905949 96830484 509673472 3.9178845882 3.8037807941 4.2627973557 496 1305031118.6792950630 0.0444088690 0.0445692884 0.0843496993 0.0184356136 0.0072670000 0.0005400000 0.0032420000 0.0000010000 0.0000100000 0.0011270000 15909733 96830484 509673472 3.9189624786 3.8099124432 4.2614336014 497 1305031118.7114210129 0.0457901321 0.0445717448 0.0843496993 0.0184275021 0.0056610000 0.0004040000 0.0022960000 0.0000070000 0.0000060000 0.0015380000 15913349 96830484 509673472 3.9181602001 3.8140308857 4.2588949203 498 1305031118.7468008995 0.0496449806 0.0445819320 0.0843496993 0.0184262961 0.0083540000 0.0005320000 0.0036170000 0.0000020000 0.0000160000 0.0014120000 15917133 96830484 509673472 3.9172828197 3.8175835609 4.2560019493 499 1305031118.7792770863 0.0450639762 0.0445828980 0.0843496993 0.0184566740 0.0056110000 0.0004060000 0.0026540000 0.0000080000 0.0000060000 0.0011200000 15920861 96830484 509673472 3.9192223549 3.8295502663 4.2532477379 500 1305031118.8112208843 0.0424775444 0.0445786873 0.0843496993 0.0184565841 0.0059640000 0.0003680000 0.0035650000 0.0000010000 0.0000060000 0.0008350000 15924477 96830484 509673472 3.9220497608 3.8387594223 4.2496643066 501 1305031118.8467741013 0.0478137694 0.0445851446 0.0843496993 0.0184795624 0.0083970000 0.0005320000 0.0028910000 0.0000150000 0.0000130000 0.0021540000 15928261 96830484 509673472 3.9249992371 3.8413722515 4.2438535690 502 1305031118.8792080879 0.0420071669 0.0445800092 0.0843496993 0.0185331234 0.0054040000 0.0004100000 0.0026530000 0.0000010000 0.0000070000 0.0009130000 15931989 96830484 509673472 3.9253451824 3.8571465015 4.2375373840 503 1305031118.9111769199 0.0400942788 0.0445710912 0.0843496993 0.0185339144 0.0089810000 0.0005200000 0.0032910000 0.0000150000 0.0000140000 0.0015670000 15935605 96830484 509673472 3.9244325161 3.8686480522 4.2315840721 504 1305031118.9470090866 0.0432437211 0.0445684575 0.0843496993 0.0185160214 0.0058060000 0.0004510000 0.0026790000 0.0000010000 0.0000080000 0.0009340000 15939389 96830484 509673472 3.9256956577 3.8763375282 4.2241158485 505 1305031118.9793939590 0.0395410769 0.0445585023 0.0843496993 0.0185104955 0.0066580000 0.0004620000 0.0027640000 0.0000110000 0.0000090000 0.0016140000 15943117 96830484 509673472 3.9249093533 3.8897945881 4.2171182632 506 1305031119.0113630295 0.0383167490 0.0445461668 0.0843496993 0.0184987422 0.0067090000 0.0003880000 0.0043060000 0.0000010000 0.0000060000 0.0007940000 15946733 96830484 509673472 3.9229640961 3.9011468887 4.2109003067 507 1305031119.0471799374 0.0419339165 0.0445410145 0.0843496993 0.0184866756 0.0046270000 0.0003650000 0.0022220000 0.0000050000 0.0000040000 0.0009830000 15950517 96830484 509673472 3.9222486019 3.9093039036 4.2038855553 508 1305031119.0792229176 0.0422130600 0.0445364319 0.0843496993 0.0184724114 0.0083710000 0.0005310000 0.0029330000 0.0000020000 0.0000170000 0.0013010000 15954133 96830484 509673472 3.9211313725 3.9182040691 4.1971569061 509 1305031119.1113278866 0.0420238003 0.0445314955 0.0843496993 0.0184578751 0.0083080000 0.0005440000 0.0036240000 0.0000100000 0.0000080000 0.0017050000 15957861 96830484 509673472 3.9197385311 3.9274744987 4.1903271675 510 1305031119.1476290226 0.0425727479 0.0445276548 0.0843496993 0.0184457928 0.0050180000 0.0004270000 0.0023140000 0.0000010000 0.0000070000 0.0008200000 15961645 96830484 509673472 3.9204158783 3.9380714893 4.1837816238 511 1305031119.1792619228 0.0422739089 0.0445232443 0.0843496993 0.0184399544 0.0087090000 0.0005600000 0.0047070000 0.0000110000 0.0000090000 0.0012590000 15965317 96830484 509673472 3.9195466042 3.9469769001 4.1773638725 512 1305031119.2113640308 0.0422781743 0.0445188594 0.0843496993 0.0184277924 0.0068180000 0.0004060000 0.0043950000 0.0000000000 0.0000060000 0.0007850000 15968989 96830484 509673472 3.9201858044 3.9551084042 4.1712021828 513 1305031119.2476599216 0.0421199501 0.0445141832 0.0843496993 0.0184163941 0.0053930000 0.0003790000 0.0025980000 0.0000050000 0.0000040000 0.0013340000 16021925 96830484 509673472 3.9203994274 3.9666597843 4.1651477814 514 1305031119.2792439461 0.0409752913 0.0445072982 0.0843496993 0.0184016786 0.0082680000 0.0005490000 0.0029570000 0.0000020000 0.0000150000 0.0012780000 16127997 96830484 509673472 3.9194629192 3.9768116474 4.1599826813 515 1305031119.3112120628 0.0408021733 0.0445001038 0.0843496993 0.0183849127 0.0061490000 0.0004260000 0.0030870000 0.0000080000 0.0000060000 0.0011080000 16131669 96830484 509673472 3.9199485779 3.9855492115 4.1553983688 516 1305031119.3477499485 0.0447195098 0.0445005290 0.0843496993 0.0183685273 0.0064600000 0.0004610000 0.0026910000 0.0000020000 0.0000110000 0.0010260000 16135453 96830484 509673472 3.9210715294 3.9927284718 4.1510162354 517 1305031119.3792390823 0.0435851812 0.0444987585 0.0843496993 0.0183589838 0.0093130000 0.0005310000 0.0037700000 0.0000140000 0.0000130000 0.0020420000 16139125 96830484 509673472 3.9204514027 4.0030603409 4.1470208168 518 1305031119.4114921093 0.0427998230 0.0444954787 0.0843496993 0.0183488542 0.0054990000 0.0004330000 0.0027450000 0.0000010000 0.0000070000 0.0008540000 16142797 96830484 509673472 3.9211087227 4.0133013725 4.1431446075 519 1305031119.4477260113 0.0465685017 0.0444994729 0.0843496993 0.0183317195 0.0049090000 0.0003880000 0.0022970000 0.0000050000 0.0000040000 0.0009970000 16146637 96830484 509673472 3.9220020771 4.0223755836 4.1394600868 520 1305031119.4792668819 0.0478857420 0.0445059850 0.0843496993 0.0183160704 0.0095470000 0.0005330000 0.0048250000 0.0000020000 0.0000140000 0.0012530000 16150197 96830484 509673472 3.9207916260 4.0305571556 4.1352562904 521 1305031119.5112578869 0.0476455465 0.0445120110 0.0843496993 0.0183043332 0.0078290000 0.0004400000 0.0044980000 0.0000070000 0.0000060000 0.0013840000 16153869 96830484 509673472 3.9187707901 4.0419030190 4.1319046021 522 1305031119.5474140644 0.0518828481 0.0445261314 0.0843496993 0.0182870896 0.0051590000 0.0003890000 0.0029770000 0.0000010000 0.0000050000 0.0007290000 16157709 96830484 509673472 3.9185132980 4.0511837006 4.1285238266 523 1305031119.5795691013 0.0515036397 0.0445394727 0.0843496993 0.0182823156 0.0080820000 0.0005490000 0.0029600000 0.0000160000 0.0000130000 0.0014270000 16161381 96830484 509673472 3.9201095104 4.0622458458 4.1256504059 524 1305031119.6150240898 0.0528819077 0.0445553934 0.0843496993 0.0182707724 0.0072070000 0.0004420000 0.0044420000 0.0000000000 0.0000060000 0.0008410000 16165165 96830484 509673472 3.9185502529 4.0719685555 4.1230988503 525 1305031119.6488890648 0.0586189516 0.0445821811 0.0843496993 0.0182681152 0.0054650000 0.0003860000 0.0025910000 0.0000040000 0.0000030000 0.0014140000 16168893 96830484 509673472 3.9173545837 4.0807957649 4.1215176582 526 1305031119.6792080402 0.0592446551 0.0446100566 0.0843496993 0.0182590425 0.0091930000 0.0005300000 0.0047380000 0.0000020000 0.0000160000 0.0013170000 16172453 96830484 509673472 3.9157209396 4.0920004845 4.1201167107 527 1305031119.7152490616 0.0616091527 0.0446423129 0.0843496993 0.0182439046 0.0070680000 0.0004370000 0.0039940000 0.0000070000 0.0000060000 0.0010840000 16176237 96830484 509673472 3.9131000042 4.1016530991 4.1194024086 528 1305031119.7471930981 0.0698633417 0.0446900800 0.0843496993 0.0182352952 0.0053890000 0.0003940000 0.0029390000 0.0000000000 0.0000050000 0.0008110000 16179965 96830484 509673472 3.9113113880 4.1059374809 4.1191620827 529 1305031119.7791690826 0.0719486475 0.0447416085 0.0843496993 0.0182190033 0.0090870000 0.0005280000 0.0036260000 0.0000140000 0.0000130000 0.0021150000 16183637 96830484 509673472 3.9102451801 4.1146917343 4.1183032990 530 1305031119.8145709038 0.0747219175 0.0447981751 0.0843496993 0.0182062524 0.0070620000 0.0004320000 0.0039330000 0.0000010000 0.0000060000 0.0009110000 16187309 96830484 509673472 3.9109249115 4.1218233109 4.1175222397 531 1305031119.8474450111 0.0785816461 0.0448617975 0.0843496993 0.0181948292 0.0057600000 0.0003940000 0.0032590000 0.0000050000 0.0000050000 0.0010270000 16191093 96830484 509673472 3.9123942852 4.1307916641 4.1166129112 532 1305031119.8792319298 0.0805969238 0.0449289688 0.0843496993 0.0181835476 0.0093340000 0.0005480000 0.0047410000 0.0000020000 0.0000160000 0.0012970000 16194709 96830484 509673472 3.9104282856 4.1375050545 4.1150960922 533 1305031119.9114239216 0.0810197443 0.0449966813 0.0843496993 0.0181842560 0.0071630000 0.0004250000 0.0036570000 0.0000060000 0.0000050000 0.0015210000 16198381 96830484 509673472 3.9089300632 4.1460518837 4.1131167412 534 1305031119.9474620819 0.0828115344 0.0450674956 0.0843496993 0.0181724821 0.0055760000 0.0003850000 0.0032690000 0.0000010000 0.0000040000 0.0008250000 16202221 96830484 509673472 3.9093081951 4.1551189423 4.1115212440 535 1305031119.9795460701 0.0854627639 0.0451430008 0.0854627639 0.0181590878 0.0065560000 0.0003710000 0.0042100000 0.0000040000 0.0000030000 0.0010220000 16205893 96830484 509673472 3.9085807800 4.1589808464 4.1104640961 536 1305031120.0152831078 0.0852316543 0.0452177931 0.0854627639 0.0181681011 0.0094830000 0.0005580000 0.0043890000 0.0000020000 0.0000150000 0.0013150000 16209621 96830484 509673472 3.9065561295 4.1665596962 4.1093735695 537 1305031120.0473101139 0.0883966982 0.0452982007 0.0883966982 0.0181624712 0.0068270000 0.0004400000 0.0033490000 0.0000060000 0.0000060000 0.0015110000 16213349 96830484 509673472 3.9075219631 4.1703948975 4.1095623970 538 1305031120.0794179440 0.0941816643 0.0453890622 0.0941816643 0.0181687543 0.0065210000 0.0003810000 0.0042710000 0.0000010000 0.0000050000 0.0008070000 16217021 96830484 509673472 3.9086477757 4.1661629677 4.1105446815 539 1305031120.1152489185 0.0925657675 0.0454765885 0.0941816643 0.0181621871 0.0076390000 0.0005470000 0.0032940000 0.0000100000 0.0000090000 0.0012460000 16220749 96830484 509673472 3.9075610638 4.1695771217 4.1097750664 540 1305031120.1481750011 0.0908364803 0.0455605883 0.0941816643 0.0181630685 0.0081320000 0.0005440000 0.0040040000 0.0000020000 0.0000090000 0.0010510000 16224477 96830484 509673472 3.9081428051 4.1701011658 4.1094884872 541 1305031120.1792609692 0.0933808386 0.0456489806 0.0941816643 0.0181544112 0.0064760000 0.0004320000 0.0030440000 0.0000060000 0.0000060000 0.0015130000 16228093 96830484 509673472 3.9079337120 4.1638350487 4.1107454300 542 1305031120.2152600288 0.0933337584 0.0457369599 0.0941816643 0.0181398205 0.0079230000 0.0004810000 0.0045380000 0.0000010000 0.0000070000 0.0009290000 16231877 96830484 509673472 3.9083163738 4.1581072807 4.1107535362 543 1305031120.2480180264 0.0854541063 0.0458101038 0.0941816643 0.0181253021 0.0068940000 0.0003850000 0.0043480000 0.0000050000 0.0000040000 0.0010140000 16235605 96830484 509673472 3.9048743248 4.1581053734 4.1087398529 544 1305031120.2794411182 0.0818374529 0.0458763306 0.0941816643 0.0181097224 0.0064570000 0.0003630000 0.0043130000 0.0000010000 0.0000040000 0.0007900000 16239277 96830484 509673472 3.9008502960 4.1535820961 4.1081085205 545 1305031120.3152129650 0.0773911998 0.0459341560 0.0941816643 0.0180936477 0.0100100000 0.0005470000 0.0048060000 0.0000150000 0.0000130000 0.0020130000 16243005 96830484 509673472 3.8957009315 4.1491651535 4.1070885658 546 1305031120.3477969170 0.0704590604 0.0459790734 0.0941816643 0.0180778337 0.0058850000 0.0004300000 0.0030320000 0.0000010000 0.0000070000 0.0008450000 16246733 96830484 509673472 3.8939507008 4.1434717178 4.1067690849 547 1305031120.3794460297 0.0677133426 0.0460188070 0.0941816643 0.0180622304 0.0068300000 0.0003870000 0.0043210000 0.0000050000 0.0000040000 0.0010110000 16250405 96830484 509673472 3.8943192959 4.1365528107 4.1092414856 548 1305031120.4154899120 0.0654621869 0.0460542876 0.0941816643 0.0181145230 0.0075420000 0.0004670000 0.0035000000 0.0000010000 0.0000100000 0.0010310000 16254133 96830484 509673472 3.9037482738 4.1233959198 4.1106972694 549 1305031120.4474329948 0.0590249635 0.0460779137 0.0941816643 0.0181085023 0.0086510000 0.0005500000 0.0036950000 0.0000150000 0.0000130000 0.0017380000 16257861 96830484 509673472 3.9005033970 4.1178727150 4.1141777039 550 1305031120.4794321060 0.0531600602 0.0460907903 0.0941816643 0.0180940847 0.0054440000 0.0004200000 0.0026400000 0.0000010000 0.0000050000 0.0008370000 16261533 96830484 509673472 3.9067921638 4.1131424904 4.1171059608 551 1305031120.5148770809 0.0539110266 0.0461049831 0.0941816643 0.0180843471 0.0074260000 0.0004590000 0.0031110000 0.0000090000 0.0000110000 0.0012500000 16265261 96830484 509673472 3.9086859226 4.1011629105 4.1216187477 552 1305031120.5478069782 0.0477469154 0.0461079576 0.0941816643 0.0180708751 0.0059190000 0.0004240000 0.0030330000 0.0000010000 0.0000070000 0.0008420000 16268989 96830484 509673472 3.9115386009 4.0940566063 4.1252918243 553 1305031120.5795590878 0.0434134677 0.0461030851 0.0941816643 0.0180602846 0.0101940000 0.0005450000 0.0040350000 0.0000150000 0.0000140000 0.0020840000 16272661 96830484 509673472 3.9151830673 4.0898013115 4.1294279099 554 1305031120.6152710915 0.0429169051 0.0460973339 0.0941816643 0.0180490477 0.0073510000 0.0004310000 0.0044640000 0.0000000000 0.0000060000 0.0008540000 16276333 96830484 509673472 3.9181632996 4.0811963081 4.1342878342 555 1305031120.6473538876 0.0380302966 0.0460827987 0.0941816643 0.0180369229 0.0069420000 0.0003870000 0.0043840000 0.0000050000 0.0000040000 0.0010160000 16280061 96830484 509673472 3.9196712971 4.0737032890 4.1384048462 556 1305031120.6793179512 0.0348505080 0.0460625967 0.0941816643 0.0180445690 0.0061850000 0.0004600000 0.0028300000 0.0000010000 0.0000100000 0.0008910000 16283677 96830484 509673472 3.9217972755 4.0690007210 4.1426019669 557 1305031120.7145531178 0.0334592499 0.0460399695 0.0941816643 0.0180290311 0.0097320000 0.0005450000 0.0033780000 0.0000140000 0.0000150000 0.0020120000 16287461 96830484 509673472 3.9226951599 4.0613241196 4.1468973160 558 1305031120.7473959923 0.0296529848 0.0460106022 0.0941816643 0.0180160977 0.0073260000 0.0004300000 0.0045100000 0.0000010000 0.0000060000 0.0008020000 16291189 96830484 509673472 3.9221670628 4.0533466339 4.1513004303 559 1305031120.7799079418 0.0305321105 0.0459829126 0.0941816643 0.0180048826 0.0055340000 0.0003880000 0.0030080000 0.0000050000 0.0000040000 0.0009950000 16294917 96830484 509673472 3.9228150845 4.0433578491 4.1556172371 560 1305031120.8149440289 0.0291317683 0.0459528212 0.0941816643 0.0179967301 0.0092860000 0.0005920000 0.0034210000 0.0000020000 0.0000150000 0.0013030000 16298645 96830484 509673472 3.9233336449 4.0362586975 4.1591615677 561 1305031120.8479421139 0.0241036229 0.0459138744 0.0941816643 0.0179809657 0.0077230000 0.0005040000 0.0036360000 0.0000080000 0.0000060000 0.0015420000 16302373 96830484 509673472 3.9222145081 4.0304350853 4.1627054214 562 1305031120.8834540844 0.0254236013 0.0458774148 0.0941816643 0.0179736877 0.0058000000 0.0004730000 0.0024300000 0.0000010000 0.0000070000 0.0009020000 16306101 96830484 509673472 3.9244086742 4.0192918777 4.1658668518 563 1305031120.9154539108 0.0237793643 0.0458381643 0.0941816643 0.0179667873 0.0067750000 0.0004610000 0.0031780000 0.0000080000 0.0000070000 0.0011360000 16309773 96830484 509673472 3.9235286713 4.0130410194 4.1690082550 564 1305031120.9475090504 0.0210931003 0.0457942900 0.0941816643 0.0179516045 0.0099230000 0.0005440000 0.0048380000 0.0000020000 0.0000140000 0.0013150000 16313445 96830484 509673472 3.9221873283 4.0051207542 4.1718983650 565 1305031120.9833900928 0.0215889718 0.0457514488 0.0941816643 0.0179391369 0.0070180000 0.0004300000 0.0034740000 0.0000060000 0.0000050000 0.0014990000 16317229 96830484 509673472 3.9219050407 3.9961771965 4.1748948097 566 1305031121.0150289536 0.0236481875 0.0457123971 0.0941816643 0.0179300679 0.0066350000 0.0003860000 0.0043810000 0.0000000000 0.0000050000 0.0007890000 16320845 96830484 509673472 3.9203863144 3.9865698814 4.1777338982 567 1305031121.0477550030 0.0191632640 0.0456655732 0.0941816643 0.0179143671 0.0080030000 0.0004570000 0.0044250000 0.0000080000 0.0000070000 0.0011510000 16324629 96830484 509673472 3.9204657078 3.9808082581 4.1799240112 568 1305031121.0831170082 0.0221982021 0.0456242574 0.0941816643 0.0179031535 0.0067260000 0.0003850000 0.0043750000 0.0000000000 0.0000040000 0.0008020000 16328357 96830484 509673472 3.9178645611 3.9704675674 4.1825165749 569 1305031121.1148779392 0.0220994186 0.0455829132 0.0941816643 0.0178898571 0.0070220000 0.0003650000 0.0043250000 0.0000050000 0.0000040000 0.0014110000 16331973 96830484 509673472 3.9192740917 3.9615473747 4.1847653389 570 1305031121.1473550797 0.0199536271 0.0455379496 0.0941816643 0.0178749889 0.0062700000 0.0003610000 0.0041800000 0.0000000000 0.0000040000 0.0008010000 16335701 96830484 509673472 3.9175362587 3.9547533989 4.1868567467 571 1305031121.1832809448 0.0219826829 0.0454966969 0.0941816643 0.0178593744 0.0094120000 0.0005490000 0.0040850000 0.0000150000 0.0000130000 0.0016150000 16339485 96830484 509673472 3.9152162075 3.9461650848 4.1892309189 572 1305031121.2114310265 0.0216476209 0.0454550027 0.0941816643 0.0178481079 0.0053560000 0.0004260000 0.0023760000 0.0000000000 0.0000080000 0.0009340000 16342989 96830484 509673472 3.9158213139 3.9380118847 4.1914639473 573 1305031121.2472009659 0.0215130188 0.0454132191 0.0941816643 0.0178336680 0.0062600000 0.0003860000 0.0029740000 0.0000060000 0.0000050000 0.0015110000 16346773 96830484 509673472 3.9140892029 3.9318604469 4.1941485405 574 1305031121.2828760147 0.0243282542 0.0453764858 0.0941816643 0.0178184404 0.0087470000 0.0005300000 0.0036890000 0.0000020000 0.0000150000 0.0014300000 16350557 96830484 509673472 3.9119839668 3.9227194786 4.1975717545 575 1305031121.3135879040 0.0253343154 0.0453416298 0.0941816643 0.0178118956 0.0055570000 0.0004250000 0.0023460000 0.0000060000 0.0000050000 0.0011440000 16354173 96830484 509673472 3.9131228924 3.9123499393 4.2005591393 576 1305031121.3475399017 0.0273211189 0.0453103442 0.0941816643 0.0178005179 0.0059200000 0.0003820000 0.0032890000 0.0000010000 0.0000050000 0.0008830000 16357901 96830484 509673472 3.9103312492 3.9053997993 4.2041196823 577 1305031121.3832480907 0.0268709790 0.0452783869 0.0941816643 0.0177961882 0.0062640000 0.0003820000 0.0029580000 0.0000050000 0.0000050000 0.0015470000 16361685 96830484 509673472 3.9115560055 3.8965170383 4.2076153755 578 1305031121.4143280983 0.0289885011 0.0452502037 0.0941816643 0.0177820459 0.0056000000 0.0003850000 0.0029340000 0.0000000000 0.0000050000 0.0009150000 16365301 96830484 509673472 3.9100902081 3.8880548477 4.2101998329 579 1305031121.4473190308 0.0318856686 0.0452271216 0.0941816643 0.0177750096 0.0095790000 0.0005260000 0.0032780000 0.0000150000 0.0000130000 0.0016830000 16369029 96830484 509673472 3.9066281319 3.8834908009 4.2138628960 580 1305031121.4830150604 0.0313149542 0.0452031351 0.0941816643 0.0177778112 0.0081800000 0.0004680000 0.0044990000 0.0000010000 0.0000080000 0.0010710000 16372757 96830484 509673472 3.9089534283 3.8738412857 4.2167615891 581 1305031121.5141639709 0.0339341201 0.0451837392 0.0941816643 0.0177670994 0.0062370000 0.0004050000 0.0029280000 0.0000060000 0.0000040000 0.0015940000 16376373 96830484 509673472 3.9068629742 3.8634331226 4.2196006775 582 1305031121.5472700596 0.0344463661 0.0451652901 0.0941816643 0.0177616564 0.0081460000 0.0004550000 0.0041560000 0.0000020000 0.0000090000 0.0012240000 16380157 96830484 509673472 3.9064242840 3.8562862873 4.2236909866 583 1305031121.5832130909 0.0347567983 0.0451474368 0.0941816643 0.0177493453 0.0062550000 0.0003950000 0.0032860000 0.0000060000 0.0000050000 0.0011640000 16383941 96830484 509673472 3.9064216614 3.8477602005 4.2266073227 584 1305031121.6147189140 0.0357840881 0.0451314037 0.0941816643 0.0177364119 0.0098980000 0.0005340000 0.0039900000 0.0000020000 0.0000140000 0.0015400000 16387557 96830484 509673472 3.9063217640 3.8362643719 4.2293782234 585 1305031121.6471829414 0.0353804007 0.0451147353 0.0941816643 0.0177297019 0.0081570000 0.0004140000 0.0043720000 0.0000060000 0.0000050000 0.0016730000 16391229 96830484 509673472 3.9087829590 3.8293919563 4.2316784859 586 1305031121.6832110882 0.0374343097 0.0451016287 0.0941816643 0.0177200099 0.0054620000 0.0003930000 0.0029010000 0.0000010000 0.0000040000 0.0009240000 16395069 96830484 509673472 3.9067897797 3.8221044540 4.2348613739 587 1305031121.7145280838 0.0413631275 0.0450952599 0.0941816643 0.0177061770 0.0084540000 0.0005540000 0.0035880000 0.0000110000 0.0000090000 0.0014570000 16398685 96830484 509673472 3.9035749435 3.8117709160 4.2373533249 588 1305031121.7471449375 0.0428645164 0.0450914661 0.0941816643 0.0176932299 0.0059110000 0.0004200000 0.0029220000 0.0000010000 0.0000070000 0.0009890000 16402357 96830484 509673472 3.9034838676 3.8076465130 4.2404661179 589 1305031121.7828710079 0.0434921756 0.0450887509 0.0941816643 0.0176791250 0.0063760000 0.0003660000 0.0032060000 0.0000050000 0.0000040000 0.0015890000 16406141 96830484 509673472 3.9049355984 3.8004493713 4.2435960770 590 1305031121.8115448952 0.0448876992 0.0450884101 0.0941816643 0.0176688501 0.0065260000 0.0003580000 0.0041620000 0.0000010000 0.0000040000 0.0009080000 16409701 96830484 509673472 3.9047646523 3.7952463627 4.2466301918 591 1305031121.8473351002 0.0454865098 0.0450890837 0.0941816643 0.0176561107 0.0065950000 0.0003490000 0.0041500000 0.0000030000 0.0000030000 0.0011170000 16413485 96830484 509673472 3.9070467949 3.7919385433 4.2493348122 592 1305031121.8821229935 0.0462539494 0.0450910514 0.0941816643 0.0176411933 0.0050850000 0.0003520000 0.0028390000 0.0000000000 0.0000040000 0.0008980000 16417213 96830484 509673472 3.9064486027 3.7890737057 4.2516984940 593 1305031121.9149429798 0.0455694720 0.0450918582 0.0941816643 0.0176270381 0.0057210000 0.0003480000 0.0028240000 0.0000040000 0.0000030000 0.0015570000 16420941 96830484 509673472 3.9077868462 3.7874720097 4.2531414032 594 1305031121.9473180771 0.0462472029 0.0450938032 0.0941816643 0.0176152170 0.0047150000 0.0003470000 0.0024840000 0.0000000000 0.0000030000 0.0008890000 16424613 96830484 509673472 3.9069812298 3.7861640453 4.2542247772 595 1305031121.9829349518 0.0433849767 0.0450909312 0.0941816643 0.0176010810 0.0056140000 0.0003490000 0.0031540000 0.0000030000 0.0000030000 0.0011170000 16428397 96830484 509673472 3.9091875553 3.7899799347 4.2546629906 596 1305031122.0144240856 0.0432243645 0.0450877994 0.0941816643 0.0175872655 0.0096100000 0.0005430000 0.0032590000 0.0000020000 0.0000140000 0.0015180000 16432069 96830484 509673472 3.9080150127 3.7923302650 4.2543573380 597 1305031122.0473060608 0.0432776287 0.0450847673 0.0941816643 0.0175732404 0.0099250000 0.0005430000 0.0046550000 0.0000090000 0.0000100000 0.0019770000 16435741 96830484 509673472 3.9077007771 3.7949357033 4.2532100677 598 1305031122.0829689503 0.0419268794 0.0450794865 0.0941816643 0.0175591767 0.0055780000 0.0003910000 0.0025880000 0.0000010000 0.0000050000 0.0009750000 16439525 96830484 509673472 3.9073171616 3.8016867638 4.2514343262 599 1305031122.1146879196 0.0410815440 0.0450728122 0.0941816643 0.0175455512 0.0067810000 0.0003600000 0.0042010000 0.0000040000 0.0000040000 0.0011150000 16443141 96830484 509673472 3.9073126316 3.8090426922 4.2483549118 600 1305031122.1507480145 0.0397826172 0.0450639952 0.0941816643 0.0175364164 0.0050900000 0.0003480000 0.0028360000 0.0000000000 0.0000030000 0.0008880000 16446925 96830484 509673472 3.9071326256 3.8186545372 4.2455301285 601 1305031122.1830520630 0.0383868702 0.0450528852 0.0941816643 0.0175338265 0.0101340000 0.0005380000 0.0029160000 0.0000140000 0.0000130000 0.0023220000 16450653 96830484 509673472 3.9088232517 3.8270585537 4.2413067818 602 1305031122.2149689198 0.0358550064 0.0450376063 0.0941816643 0.0175604609 0.0062700000 0.0004510000 0.0026760000 0.0000010000 0.0000070000 0.0010540000 16454269 96830484 509673472 3.9077453613 3.8404893875 4.2384119034 603 1305031122.2513549328 0.0367997363 0.0450239448 0.0941816643 0.0175523164 0.0073290000 0.0004510000 0.0034270000 0.0000090000 0.0000080000 0.0012480000 16458109 96830484 509673472 3.9055485725 3.8518714905 4.2346539497 604 1305031122.2838659286 0.0380263440 0.0450123594 0.0941816643 0.0175428846 0.0069150000 0.0003920000 0.0042780000 0.0000010000 0.0000060000 0.0008780000 16461837 96830484 509673472 3.9047770500 3.8598661423 4.2285366058 605 1305031122.3143088818 0.0335457027 0.0449934062 0.0941816643 0.0175633097 0.0074230000 0.0004530000 0.0023840000 0.0000100000 0.0000090000 0.0018720000 16465397 96830484 509673472 3.9041547775 3.8762595654 4.2240948677 606 1305031122.3513510227 0.0353867449 0.0449775537 0.0941816643 0.0175552065 0.0053800000 0.0003930000 0.0026140000 0.0000010000 0.0000070000 0.0008920000 16469181 96830484 509673472 3.9050292969 3.8835906982 4.2199563980 607 1305031122.3826780319 0.0347836949 0.0449607598 0.0941816643 0.0175439050 0.0069290000 0.0003710000 0.0042340000 0.0000040000 0.0000040000 0.0010410000 16472909 96830484 509673472 3.9067525864 3.8916306496 4.2147130966 608 1305031122.4150080681 0.0367445610 0.0449472463 0.0941816643 0.0175415127 0.0066000000 0.0003750000 0.0041440000 0.0000010000 0.0000040000 0.0008050000 16476469 96830484 509673472 3.9061722755 3.8982176781 4.2090091705 609 1305031122.4512720108 0.0382919200 0.0449363180 0.0941816643 0.0175297182 0.0095500000 0.0005460000 0.0032960000 0.0000290000 0.0000130000 0.0021390000 16480309 96830484 509673472 3.9071295261 3.9074168205 4.2032852173 610 1305031122.4833879471 0.0368199721 0.0449230126 0.0941816643 0.0175164795 0.0074780000 0.0004240000 0.0044090000 0.0000010000 0.0000060000 0.0008720000 16483981 96830484 509673472 3.9065248966 3.9177148342 4.1975884438 611 1305031122.5151350498 0.0367297605 0.0449096030 0.0941816643 0.0175059386 0.0049260000 0.0003820000 0.0022440000 0.0000040000 0.0000040000 0.0010130000 16487653 96830484 509673472 3.9067728519 3.9261291027 4.1922154427 612 1305031122.5515100956 0.0380160026 0.0448983389 0.0941816643 0.0174987187 0.0099960000 0.0005430000 0.0036850000 0.0000020000 0.0000140000 0.0013560000 16491437 96830484 509673472 3.9070107937 3.9366648197 4.1868209839 613 1305031122.5832169056 0.0377794392 0.0448867257 0.0941816643 0.0174854269 0.0064330000 0.0004500000 0.0023610000 0.0000090000 0.0000070000 0.0015950000 16495109 96830484 509673472 3.9068763256 3.9460427761 4.1814088821 614 1305031122.6150169373 0.0394059308 0.0448777993 0.0941816643 0.0174791159 0.0051220000 0.0003860000 0.0026340000 0.0000010000 0.0000050000 0.0008020000 16498725 96830484 509673472 3.9061203003 3.9532260895 4.1758794785 615 1305031122.6488099098 0.0432912372 0.0448752196 0.0941816643 0.0174651195 0.0046740000 0.0003680000 0.0021420000 0.0000040000 0.0000040000 0.0010110000 16502509 96830484 509673472 3.9059889317 3.9615347385 4.1703600883 616 1305031122.6834199429 0.0420184061 0.0448705819 0.0941816643 0.0174512558 0.0052290000 0.0003680000 0.0029390000 0.0000000000 0.0000030000 0.0007800000 16506237 96830484 509673472 3.9057207108 3.9727694988 4.1653871536 617 1305031122.7152190208 0.0424929447 0.0448667283 0.0941816643 0.0174393671 0.0119880000 0.0005520000 0.0048600000 0.0000170000 0.0000130000 0.0021290000 16509853 96830484 509673472 3.9057526588 3.9818789959 4.1612811089 618 1305031122.7513089180 0.0441441461 0.0448655591 0.0941816643 0.0174332507 0.0091720000 0.0004650000 0.0052350000 0.0000010000 0.0000070000 0.0009450000 16513693 96830484 509673472 3.9074351788 3.9935245514 4.1572031975 619 1305031122.7834379673 0.0416219607 0.0448603190 0.0941816643 0.0174256443 0.0056850000 0.0004210000 0.0026710000 0.0000050000 0.0000050000 0.0010330000 16517365 96830484 509673472 3.9075305462 4.0067110062 4.1541943550 620 1305031122.8125650883 0.0425992608 0.0448566722 0.0941816643 0.0174134846 0.0048550000 0.0004210000 0.0025130000 0.0000000000 0.0000040000 0.0007660000 16520981 96830484 509673472 3.9083416462 4.0157556534 4.1515216827 621 1305031122.8514859676 0.0476500914 0.0448611704 0.0941816643 0.0174121401 0.0104520000 0.0005420000 0.0048260000 0.0000140000 0.0000120000 0.0020480000 16524821 96830484 509673472 3.9079246521 4.0226650238 4.1490235329 622 1305031122.8837749958 0.0479029343 0.0448660607 0.0941816643 0.0174007315 0.0065030000 0.0004340000 0.0034340000 0.0000010000 0.0000070000 0.0008200000 16528549 96830484 509673472 3.9096019268 4.0317525864 4.1464772224 623 1305031122.9145851135 0.0502185896 0.0448746523 0.0941816643 0.0173938250 0.0062220000 0.0003960000 0.0036810000 0.0000050000 0.0000050000 0.0009700000 16532109 96830484 509673472 3.9072721004 4.0380215645 4.1438083649 624 1305031122.9514129162 0.0551639535 0.0448911415 0.0941816643 0.0173816859 0.0046940000 0.0003630000 0.0025870000 0.0000000000 0.0000030000 0.0007150000 16535949 96830484 509673472 3.9059097767 4.0437488556 4.1412944794 625 1305031122.9830000401 0.0558019392 0.0449085988 0.0941816643 0.0173701235 0.0052800000 0.0003630000 0.0025840000 0.0000040000 0.0000030000 0.0012940000 16539621 96830484 509673472 3.9070637226 4.0513110161 4.1390876770 626 1305031123.0154619217 0.0575563088 0.0449288028 0.0941816643 0.0173565961 0.0097150000 0.0005510000 0.0033220000 0.0000010000 0.0000150000 0.0013050000 16543237 96830484 509673472 3.9056127071 4.0579748154 4.1370291710 627 1305031123.0518379211 0.0622514933 0.0449564307 0.0941816643 0.0173464694 0.0092790000 0.0005530000 0.0046980000 0.0000100000 0.0000090000 0.0012790000 16547077 96830484 509673472 3.9055728912 4.0635552406 4.1346969604 628 1305031123.0829920769 0.0625023544 0.0449843701 0.0941816643 0.0173366548 0.0058490000 0.0004100000 0.0030020000 0.0000010000 0.0000060000 0.0008520000 16550749 96830484 509673472 3.9049286842 4.0722188950 4.1322159767 629 1305031123.1139390469 0.0614369549 0.0450105268 0.0941816643 0.0173295429 0.0088350000 0.0004700000 0.0045280000 0.0000080000 0.0000060000 0.0015950000 16554309 96830484 509673472 3.9066443443 4.0827498436 4.1300907135 630 1305031123.1508400440 0.0665859058 0.0450447735 0.0941816643 0.0173161099 0.0072010000 0.0004720000 0.0035240000 0.0000010000 0.0000110000 0.0009180000 16558149 96830484 509673472 3.9044723511 4.0894556046 4.1289734840 631 1305031123.1821761131 0.0678623691 0.0450809345 0.0941816643 0.0173137281 0.0062980000 0.0004050000 0.0033460000 0.0000060000 0.0000050000 0.0010240000 16561821 96830484 509673472 3.9040510654 4.0986609459 4.1275057793 632 1305031123.2147240639 0.0678898394 0.0451170245 0.0941816643 0.0173026678 0.0068490000 0.0004630000 0.0023050000 0.0000010000 0.0000100000 0.0010980000 16565493 96830484 509673472 3.9067046642 4.1096696854 4.1264762878 633 1305031123.2506411076 0.0729526281 0.0451609986 0.0941816643 0.0173135197 0.0095070000 0.0005550000 0.0044140000 0.0000100000 0.0000090000 0.0017770000 16569277 96830484 509673472 3.9035093784 4.1186871529 4.1259183884 634 1305031123.2823629379 0.0770770535 0.0452113394 0.0941816643 0.0173063806 0.0072000000 0.0004650000 0.0035050000 0.0000010000 0.0000100000 0.0009250000 16572949 96830484 509673472 3.9067399502 4.1258015633 4.1266565323 635 1305031123.3209919930 0.0837921202 0.0452720965 0.0941816643 0.0172979970 0.0060020000 0.0004030000 0.0030090000 0.0000050000 0.0000050000 0.0010340000 16576789 96830484 509673472 3.9053888321 4.1325526237 4.1272168159 636 1305031123.3504929543 0.0860080570 0.0453361468 0.0941816643 0.0172853998 0.0090950000 0.0005480000 0.0033430000 0.0000020000 0.0000140000 0.0012900000 16580405 96830484 509673472 3.9049396515 4.1407799721 4.1271214485 637 1305031123.3822629452 0.0892498195 0.0454050850 0.0941816643 0.0172733506 0.0082400000 0.0004310000 0.0044560000 0.0000070000 0.0000050000 0.0014870000 16584077 96830484 509673472 3.9070820808 4.1476182938 4.1271615028 638 1305031123.4213430882 0.0952210277 0.0454831664 0.0952210277 0.0172602582 0.0051380000 0.0003850000 0.0026200000 0.0000000000 0.0000050000 0.0008040000 16587917 96830484 509673472 3.9070639610 4.1537065506 4.1270966530 639 1305031123.4512660503 0.0984666571 0.0455660827 0.0984666571 0.0172551202 0.0051420000 0.0003760000 0.0025870000 0.0000040000 0.0000030000 0.0009920000 16591477 96830484 509673472 3.9058854580 4.1593661308 4.1266250610 640 1305031123.4836049080 0.0991929770 0.0456498747 0.0991929770 0.0172442233 0.0112130000 0.0005480000 0.0047710000 0.0000030000 0.0000140000 0.0012620000 16595205 96830484 509673472 3.9076104164 4.1680054665 4.1254858971 641 1305031123.5197250843 0.1026260182 0.0457387611 0.1026260182 0.0172322037 0.0068720000 0.0004580000 0.0027150000 0.0000080000 0.0000060000 0.0016070000 16598933 96830484 509673472 3.9072082043 4.1754498482 4.1243700981 642 1305031123.5515730381 0.1045031399 0.0458302944 0.1045031399 0.0172192295 0.0059010000 0.0003900000 0.0033080000 0.0000000000 0.0000050000 0.0008250000 16602661 96830484 509673472 3.9089152813 4.1815929413 4.1235904694 643 1305031123.5796160698 0.1057966426 0.0459235546 0.1057966426 0.0172080192 0.0061590000 0.0003700000 0.0035850000 0.0000040000 0.0000040000 0.0010180000 16606165 96830484 509673472 3.9092912674 4.1884908676 4.1226344109 644 1305031123.6203870773 0.1085049212 0.0460207307 0.1085049212 0.0172032775 0.0095570000 0.0005540000 0.0040610000 0.0000020000 0.0000140000 0.0012760000 16610061 96830484 509673472 3.9112281799 4.1956582069 4.1217908859 645 1305031123.6524300575 0.1087803617 0.0461180324 0.1087803617 0.0171912429 0.0082160000 0.0004330000 0.0044170000 0.0000060000 0.0000070000 0.0015200000 16613733 96830484 509673472 3.9139671326 4.2034521103 4.1212730408 646 1305031123.6837849617 0.1093232408 0.0462158733 0.1093232408 0.0171799794 0.0083040000 0.0004730000 0.0045640000 0.0000010000 0.0000070000 0.0009240000 16617405 96830484 509673472 3.9130246639 4.2104091644 4.1208090782 647 1305031123.7199749947 0.1121994033 0.0463178571 0.1121994033 0.0171675675 0.0071810000 0.0004070000 0.0043600000 0.0000050000 0.0000050000 0.0010370000 16621189 96830484 509673472 3.9128754139 4.2155623436 4.1203169823 648 1305031123.7519800663 0.1129780859 0.0464207278 0.1129780859 0.0171602323 0.0079950000 0.0005330000 0.0038510000 0.0000010000 0.0000070000 0.0009420000 16624861 96830484 509673472 3.9124996662 4.2190098763 4.1195564270 649 1305031123.7841379642 0.1139973328 0.0465248520 0.1139973328 0.0171515134 0.0059060000 0.0004280000 0.0026140000 0.0000070000 0.0000050000 0.0014950000 16628477 96830484 509673472 3.9137275219 4.2205524445 4.1192159653 650 1305031123.8196959496 0.1137374192 0.0466282560 0.1139973328 0.0171396949 0.0070430000 0.0004620000 0.0027970000 0.0000010000 0.0000100000 0.0010430000 16632317 96830484 509673472 3.9153110981 4.2228231430 4.1182913780 651 1305031123.8515510559 0.1135973632 0.0467311271 0.1139973328 0.0171268004 0.0087370000 0.0004620000 0.0045640000 0.0000100000 0.0000090000 0.0012570000 16635989 96830484 509673472 3.9161231518 4.2224869728 4.1176633835 652 1305031123.8838191032 0.1137267202 0.0468338811 0.1139973328 0.0171166434 0.0072240000 0.0004110000 0.0044070000 0.0000010000 0.0000050000 0.0008280000 16639661 96830484 509673472 3.9157211781 4.2209329605 4.1174836159 653 1305031123.9157938957 0.1122503281 0.0469340594 0.1139973328 0.0171052228 0.0072890000 0.0004650000 0.0031190000 0.0000070000 0.0000060000 0.0016220000 16643277 96830484 509673472 3.9158549309 4.2182931900 4.1168465614 654 1305031123.9515299797 0.1084022969 0.0470280476 0.1139973328 0.0171039385 0.0071660000 0.0004730000 0.0034970000 0.0000010000 0.0000080000 0.0009210000 16647117 96830484 509673472 3.9164299965 4.2187800407 4.1162238121 655 1305031123.9834210873 0.1097143143 0.0471237518 0.1139973328 0.0171029227 0.0054920000 0.0003940000 0.0026690000 0.0000060000 0.0000050000 0.0010370000 16650789 96830484 509673472 3.9156155586 4.2128648758 4.1180281639 656 1305031124.0197370052 0.1104427651 0.0472202747 0.1139973328 0.0171158394 0.0082440000 0.0004750000 0.0035740000 0.0000010000 0.0000100000 0.0010460000 16654573 96830484 509673472 3.9144628048 4.2037672997 4.1206173897 657 1305031124.0515310764 0.1062684506 0.0473101501 0.1139973328 0.0171144740 0.0069260000 0.0004330000 0.0031050000 0.0000060000 0.0000050000 0.0015360000 16658189 96830484 509673472 3.9156816006 4.2014441490 4.1207618713 658 1305031124.0839018822 0.1053835154 0.0473984075 0.1139973328 0.0171062902 0.0086390000 0.0004710000 0.0042670000 0.0000020000 0.0000100000 0.0010490000 16661861 96830484 509673472 3.9163351059 4.1960062981 4.1233363152 659 1305031124.1196689606 0.1040967628 0.0474844445 0.1139973328 0.0171103060 0.0075140000 0.0004110000 0.0044670000 0.0000060000 0.0000050000 0.0010330000 16665645 96830484 509673472 3.9096000195 4.1857342720 4.1253428459 660 1305031124.1474580765 0.1008140668 0.0475652469 0.1139973328 0.0171098764 0.0060760000 0.0003760000 0.0037150000 0.0000000000 0.0000040000 0.0007780000 16669261 96830484 509673472 3.9189887047 4.1821665764 4.1279454231 661 1305031124.1827070713 0.0995454937 0.0476438857 0.1139973328 0.0171006426 0.0107760000 0.0005510000 0.0048670000 0.0000150000 0.0000140000 0.0020760000 16672989 96830484 509673472 3.9172673225 4.1754083633 4.1306924820 662 1305031124.2171790600 0.0935347453 0.0477132073 0.1139973328 0.0171047465 0.0063190000 0.0004330000 0.0031090000 0.0000010000 0.0000060000 0.0008370000 16676717 96830484 509673472 3.9049227238 4.1682925224 4.1286239624 663 1305031124.2493400574 0.0938444287 0.0477827868 0.1139973328 0.0170993853 0.0070790000 0.0003930000 0.0044180000 0.0000050000 0.0000050000 0.0010120000 16680333 96830484 509673472 3.9213304520 4.1602935791 4.1346368790 664 1305031124.2825551033 0.0883096233 0.0478438212 0.1139973328 0.0170874101 0.0064580000 0.0003660000 0.0043250000 0.0000000000 0.0000040000 0.0007510000 16684061 96830484 509673472 3.9196691513 4.1572384834 4.1353254318 665 1305031124.3167819977 0.0828360766 0.0478964411 0.1139973328 0.0170936616 0.0070970000 0.0003640000 0.0043070000 0.0000030000 0.0000030000 0.0013870000 16687789 96830484 509673472 3.9132573605 4.1485414505 4.1342072487 666 1305031124.3503708839 0.0802537054 0.0479450256 0.1139973328 0.0170861966 0.0064930000 0.0003670000 0.0043110000 0.0000000000 0.0000040000 0.0007620000 16691461 96830484 509673472 3.9156901836 4.1419172287 4.1360392570 667 1305031124.3824319839 0.0760282204 0.0479871293 0.1139973328 0.0170773314 0.0066740000 0.0003540000 0.0042860000 0.0000030000 0.0000030000 0.0009760000 16695189 96830484 509673472 3.9172713757 4.1356854439 4.1363663673 668 1305031124.4185550213 0.0709492192 0.0480215037 0.1139973328 0.0170800122 0.0057870000 0.0003650000 0.0036030000 0.0000000000 0.0000040000 0.0007770000 16699029 96830484 509673472 3.9212179184 4.1258134842 4.1367354393 669 1305031124.4502561092 0.0683558509 0.0480518989 0.1139973328 0.0170674039 0.0070680000 0.0003600000 0.0042760000 0.0000030000 0.0000030000 0.0013830000 16702589 96830484 509673472 3.9200382233 4.1166477203 4.1373353004 670 1305031124.4801259041 0.0639399737 0.0480756124 0.1139973328 0.0170554506 0.0064250000 0.0003610000 0.0042640000 0.0000010000 0.0000030000 0.0007660000 16706261 96830484 509673472 3.9211738110 4.1090521812 4.1371493340 671 1305031124.5167369843 0.0567212924 0.0480884972 0.1139973328 0.0170433580 0.0053030000 0.0003610000 0.0028910000 0.0000040000 0.0000030000 0.0010000000 16710045 96830484 509673472 3.9231612682 4.1012043953 4.1377472878 672 1305031124.5505030155 0.0526657440 0.0480953086 0.1139973328 0.0170308433 0.0092880000 0.0005540000 0.0025740000 0.0000020000 0.0000160000 0.0013040000 16713773 96830484 509673472 3.9217689037 4.0940203667 4.1391854286 673 1305031124.5846059322 0.0508040413 0.0480993334 0.1139973328 0.0170187110 0.0090890000 0.0004640000 0.0045180000 0.0000100000 0.0000090000 0.0016370000 16717501 96830484 509673472 3.9226129055 4.0840663910 4.1413192749 674 1305031124.6176528931 0.0452122129 0.0480950499 0.1139973328 0.0170206019 0.0058320000 0.0004180000 0.0030080000 0.0000010000 0.0000050000 0.0007690000 16721229 96830484 509673472 3.9231522083 4.0733003616 4.1437940598 675 1305031124.6513130665 0.0420550853 0.0480861018 0.1139973328 0.0170138215 0.0063570000 0.0004720000 0.0024300000 0.0000080000 0.0000070000 0.0010950000 16724901 96830484 509673472 3.9233245850 4.0648431778 4.1465349197 676 1305031124.6854729652 0.0408733450 0.0480754320 0.1139973328 0.0170056474 0.0087890000 0.0004740000 0.0046540000 0.0000020000 0.0000100000 0.0010230000 16728629 96830484 509673472 3.9245975018 4.0536360741 4.1496028900 677 1305031124.7157909870 0.0339158177 0.0480545168 0.1139973328 0.0169942348 0.0058180000 0.0004100000 0.0023580000 0.0000060000 0.0000050000 0.0013990000 16732301 96830484 509673472 3.9255318642 4.0447998047 4.1525506973 678 1305031124.7499411106 0.0318233371 0.0480305770 0.1139973328 0.0169824536 0.0058000000 0.0003790000 0.0033310000 0.0000000000 0.0000040000 0.0007660000 16736029 96830484 509673472 3.9245700836 4.0352973938 4.1562461853 679 1305031124.7851779461 0.0316063911 0.0480063882 0.1139973328 0.0169705643 0.0070210000 0.0003740000 0.0043650000 0.0000030000 0.0000030000 0.0009930000 16739757 96830484 509673472 3.9242486954 4.0237808228 4.1604890823 680 1305031124.8166410923 0.0256317500 0.0479734843 0.1139973328 0.0169592247 0.0048660000 0.0003640000 0.0026010000 0.0000010000 0.0000030000 0.0007760000 16743429 96830484 509673472 3.9228134155 4.0149216652 4.1651682854 681 1305031124.8505589962 0.0250848830 0.0479398740 0.1139973328 0.0169470498 0.0061650000 0.0003610000 0.0033140000 0.0000030000 0.0000030000 0.0013520000 16747157 96830484 509673472 3.9225847721 4.0045790672 4.1706943512 682 1305031124.8835940361 0.0251141675 0.0479064052 0.1139973328 0.0169453710 0.0048510000 0.0003590000 0.0026020000 0.0000010000 0.0000030000 0.0007790000 16750829 96830484 509673472 3.9245989323 3.9930124283 4.1762990952 683 1305031124.9187700748 0.0203001536 0.0478659861 0.1139973328 0.0169443169 0.0096510000 0.0005520000 0.0026250000 0.0000170000 0.0000130000 0.0015790000 16754613 96830484 509673472 3.9243421555 3.9854180813 4.1822209358 684 1305031124.9507479668 0.0212495644 0.0478270732 0.1139973328 0.0169335107 0.0101420000 0.0005480000 0.0048110000 0.0000020000 0.0000140000 0.0013710000 16758229 96830484 509673472 3.9220123291 3.9770793915 4.1884164810 685 1305031124.9864599705 0.0242753793 0.0477926912 0.1139973328 0.0169675038 0.0086620000 0.0004590000 0.0045410000 0.0000070000 0.0000070000 0.0016160000 16762013 96830484 509673472 3.9232943058 3.9608576298 4.1943421364 686 1305031125.0194671154 0.0274264906 0.0477630029 0.1139973328 0.0169580154 0.0070200000 0.0003870000 0.0043710000 0.0000010000 0.0000050000 0.0008340000 16765741 96830484 509673472 3.9215493202 3.9495761395 4.2002201080 687 1305031125.0507979393 0.0244157631 0.0477290185 0.1139973328 0.0169576015 0.0053070000 0.0003620000 0.0028010000 0.0000040000 0.0000030000 0.0010230000 16769357 96830484 509673472 3.9213502407 3.9458298683 4.2053785324 688 1305031125.0834798813 0.0238225367 0.0476942707 0.1139973328 0.0169469631 0.0047810000 0.0003580000 0.0025770000 0.0000000000 0.0000040000 0.0008060000 16773085 96830484 509673472 3.9217803478 3.9383518696 4.2106504440 689 1305031125.1190290451 0.0254765935 0.0476620245 0.1139973328 0.0169400187 0.0096870000 0.0005480000 0.0028440000 0.0000160000 0.0000130000 0.0022160000 16776869 96830484 509673472 3.9194188118 3.9270253181 4.2155580521 690 1305031125.1510369778 0.0252517946 0.0476295459 0.1139973328 0.0169317189 0.0070250000 0.0004590000 0.0031270000 0.0000010000 0.0000070000 0.0010010000 16780485 96830484 509673472 3.9199538231 3.9187588692 4.2194862366 691 1305031125.1870639324 0.0233585853 0.0475944215 0.1139973328 0.0169326605 0.0061160000 0.0003990000 0.0029790000 0.0000060000 0.0000050000 0.0010900000 16784325 96830484 509673472 3.9170186520 3.9156422615 4.2235832214 692 1305031125.2190179825 0.0253236089 0.0475622382 0.1139973328 0.0169244279 0.0066870000 0.0004580000 0.0027830000 0.0000010000 0.0000080000 0.0010000000 16787997 96830484 509673472 3.9147059917 3.9063663483 4.2271308899 693 1305031125.2506420612 0.0289189890 0.0475353360 0.1139973328 0.0169164804 0.0086820000 0.0005460000 0.0029680000 0.0000150000 0.0000160000 0.0018510000 16791613 96830484 509673472 3.9134192467 3.8935265541 4.2303152084 694 1305031125.2863960266 0.0294602476 0.0475092912 0.1139973328 0.0169065215 0.0065110000 0.0004250000 0.0033420000 0.0000010000 0.0000070000 0.0009240000 16795397 96830484 509673472 3.9101812840 3.8875577450 4.2334899902 695 1305031125.3191399574 0.0291328654 0.0474828503 0.1139973328 0.0168980890 0.0081960000 0.0004660000 0.0034770000 0.0000100000 0.0000080000 0.0013700000 16799125 96830484 509673472 3.9100744724 3.8814456463 4.2365098000 696 1305031125.3488988876 0.0332712084 0.0474624313 0.1139973328 0.0168876970 0.0065130000 0.0004550000 0.0024080000 0.0000010000 0.0000100000 0.0011840000 16802685 96830484 509673472 3.9055569172 3.8727924824 4.2391190529 697 1305031125.3867919445 0.0320760012 0.0474403560 0.1139973328 0.0168874478 0.0062190000 0.0003950000 0.0026030000 0.0000060000 0.0000050000 0.0015410000 16806581 96830484 509673472 3.9050667286 3.8709154129 4.2425642014 698 1305031125.4195740223 0.0333224647 0.0474201298 0.1139973328 0.0168769112 0.0098460000 0.0005380000 0.0043820000 0.0000020000 0.0000150000 0.0014490000 16810253 96830484 509673472 3.9052462578 3.8639607430 4.2456917763 699 1305031125.4512319565 0.0354421921 0.0474029940 0.1139973328 0.0168749289 0.0072270000 0.0004260000 0.0036820000 0.0000060000 0.0000060000 0.0011450000 16813925 96830484 509673472 3.9024736881 3.8596348763 4.2486419678 700 1305031125.4869990349 0.0377794430 0.0473892461 0.1139973328 0.0168751500 0.0061000000 0.0003860000 0.0035560000 0.0000000000 0.0000040000 0.0008490000 16817709 96830484 509673472 3.9041550159 3.8488357067 4.2506718636 701 1305031125.5193541050 0.0387326963 0.0473768972 0.1139973328 0.0168698014 0.0071520000 0.0003480000 0.0042140000 0.0000030000 0.0000030000 0.0014480000 16821437 96830484 509673472 3.9027631283 3.8458642960 4.2531795502 702 1305031125.5510499477 0.0381797552 0.0473637959 0.1139973328 0.0168599856 0.0085880000 0.0005320000 0.0036240000 0.0000020000 0.0000110000 0.0011420000 16825053 96830484 509673472 3.9041290283 3.8427789211 4.2546343803 703 1305031125.5853030682 0.0378533863 0.0473502676 0.1139973328 0.0168480902 0.0074920000 0.0004160000 0.0043100000 0.0000060000 0.0000050000 0.0010910000 16828781 96830484 509673472 3.9056262970 3.8399930000 4.2555651665 704 1305031125.6178700924 0.0414063670 0.0473418245 0.1139973328 0.0168571839 0.0060160000 0.0003620000 0.0035610000 0.0000010000 0.0000040000 0.0008310000 16832509 96830484 509673472 3.9043033123 3.8342156410 4.2551364899 705 1305031125.6505749226 0.0449528471 0.0473384359 0.1139973328 0.0168502569 0.0100300000 0.0005550000 0.0032840000 0.0000140000 0.0000130000 0.0022310000 16836181 96830484 509673472 3.9029047489 3.8303525448 4.2533421516 706 1305031125.6846020222 0.0432970636 0.0473327116 0.1139973328 0.0168492128 0.0063950000 0.0004240000 0.0029970000 0.0000010000 0.0000060000 0.0009340000 16839853 96830484 509673472 3.9027714729 3.8345708847 4.2512578964 707 1305031125.7156689167 0.0418761447 0.0473249937 0.1139973328 0.0168665373 0.0058590000 0.0003800000 0.0029070000 0.0000050000 0.0000040000 0.0010880000 16843525 96830484 509673472 3.9041762352 3.8375010490 4.2491927147 708 1305031125.7512919903 0.0390517414 0.0473133083 0.1139973328 0.0168657773 0.0101630000 0.0006410000 0.0036290000 0.0000030000 0.0000150000 0.0014680000 16847309 96830484 509673472 3.9067625999 3.8431160450 4.2460207939 709 1305031125.7868049145 0.0358540080 0.0472971457 0.1139973328 0.0168599623 0.0067500000 0.0004630000 0.0026470000 0.0000060000 0.0000050000 0.0015890000 16851093 96830484 509673472 3.9068965912 3.8526818752 4.2436728477 710 1305031125.8194499016 0.0343202613 0.0472788684 0.1139973328 0.0168515040 0.0067810000 0.0003770000 0.0042380000 0.0000010000 0.0000050000 0.0008720000 16854821 96830484 509673472 3.9087843895 3.8590466976 4.2402296066 711 1305031125.8547739983 0.0322114676 0.0472576765 0.1139973328 0.0168443332 0.0064480000 0.0003520000 0.0038550000 0.0000030000 0.0000030000 0.0010660000 16858493 96830484 509673472 3.9091339111 3.8681728840 4.2367119789 712 1305031125.8866450787 0.0368720219 0.0472430899 0.1139973328 0.0168473189 0.0064930000 0.0003530000 0.0041820000 0.0000000000 0.0000040000 0.0008340000 16862221 96830484 509673472 3.9043676853 3.8759584427 4.2317461967 713 1305031125.9193339348 0.0351025164 0.0472260625 0.1139973328 0.0168457300 0.0057900000 0.0003570000 0.0028640000 0.0000030000 0.0000030000 0.0014570000 16865949 96830484 509673472 3.9051871300 3.8853118420 4.2294154167 714 1305031125.9552519321 0.0384316556 0.0472137454 0.1139973328 0.0168445536 0.0099380000 0.0005270000 0.0029300000 0.0000020000 0.0000140000 0.0014360000 16869677 96830484 509673472 3.9043631554 3.8898634911 4.2255764008 715 1305031125.9870939255 0.0391548350 0.0472024742 0.1139973328 0.0168372042 0.0070720000 0.0004590000 0.0031010000 0.0000090000 0.0000060000 0.0012110000 16873349 96830484 509673472 3.9062905312 3.8991107941 4.2224478722 716 1305031126.0195720196 0.0365432203 0.0471875869 0.1139973328 0.0168296058 0.0054700000 0.0003850000 0.0026110000 0.0000010000 0.0000050000 0.0008800000 16877077 96830484 509673472 3.9071435928 3.9120836258 4.2201309204 717 1305031126.0550379753 0.0325688496 0.0471671982 0.1139973328 0.0168239919 0.0083260000 0.0004680000 0.0035020000 0.0000100000 0.0000100000 0.0018060000 16880805 96830484 509673472 3.9122619629 3.9240980148 4.2180800438 718 1305031126.0870759487 0.0343736932 0.0471493799 0.1139973328 0.0168144089 0.0056180000 0.0003950000 0.0026370000 0.0000010000 0.0000050000 0.0008620000 16884477 96830484 509673472 3.9155859947 3.9354681969 4.2156043053 719 1305031126.1194519997 0.0369399339 0.0471351804 0.1139973328 0.0168043862 0.0050650000 0.0003750000 0.0021260000 0.0000050000 0.0000050000 0.0010500000 16888205 96830484 509673472 3.9149646759 3.9446394444 4.2130475044 720 1305031126.1549999714 0.0357836559 0.0471194144 0.1139973328 0.0167965542 0.0106330000 0.0005410000 0.0036990000 0.0000020000 0.0000140000 0.0013730000 16891877 96830484 509673472 3.9185223579 3.9561195374 4.2107090950 721 1305031126.1871740818 0.0396101810 0.0471089994 0.1139973328 0.0167938015 0.0075640000 0.0004610000 0.0027820000 0.0000100000 0.0000080000 0.0017330000 16895605 96830484 509673472 3.9185955524 3.9687223434 4.2090826035 722 1305031126.2194728851 0.0431976356 0.0471035820 0.1139973328 0.0167972750 0.0073150000 0.0004090000 0.0043630000 0.0000000000 0.0000050000 0.0008040000 16899333 96830484 509673472 3.9204568863 3.9767982960 4.2066941261 723 1305031126.2552359104 0.0434593894 0.0470985416 0.1139973328 0.0167968211 0.0052730000 0.0003750000 0.0025920000 0.0000040000 0.0000040000 0.0009860000 16903117 96830484 509673472 3.9225132465 3.9884183407 4.2041301727 724 1305031126.2871050835 0.0478861555 0.0470996295 0.1139973328 0.0167879709 0.0087870000 0.0005460000 0.0029620000 0.0000020000 0.0000150000 0.0013040000 16906733 96830484 509673472 3.9230947495 3.9996261597 4.2013525963 725 1305031126.3197870255 0.0483302958 0.0471013269 0.1139973328 0.0167806867 0.0081520000 0.0004330000 0.0043310000 0.0000070000 0.0000060000 0.0013850000 16910461 96830484 509673472 3.9236440659 4.0115766525 4.1991972923 726 1305031126.3554151058 0.0509483591 0.0471066259 0.1139973328 0.0167718763 0.0068200000 0.0003890000 0.0043500000 0.0000010000 0.0000040000 0.0007550000 16914189 96830484 509673472 3.9234356880 4.0201334953 4.1967220306 727 1305031126.3874828815 0.0554535203 0.0471181072 0.1139973328 0.0167645370 0.0075980000 0.0004700000 0.0028200000 0.0000100000 0.0000090000 0.0012170000 16917917 96830484 509673472 3.9224810600 4.0298118591 4.1938672066 728 1305031126.4197928905 0.0568268523 0.0471314434 0.1139973328 0.0167542783 0.0083490000 0.0004620000 0.0044570000 0.0000010000 0.0000070000 0.0008420000 16921533 96830484 509673472 3.9205300808 4.0394496918 4.1914896965 729 1305031126.4553799629 0.0604588874 0.0471497252 0.1139973328 0.0167559035 0.0055620000 0.0003880000 0.0023010000 0.0000050000 0.0000050000 0.0012620000 16925261 96830484 509673472 3.9217350483 4.0457844734 4.1891860962 730 1305031126.4903860092 0.0664858371 0.0471762130 0.1139973328 0.0167532765 0.0087640000 0.0004610000 0.0045860000 0.0000010000 0.0000100000 0.0009350000 16929045 96830484 509673472 3.9213564396 4.0532484055 4.1862721443 731 1305031126.5223209858 0.0660477355 0.0472020290 0.1139973328 0.0167516692 0.0058210000 0.0004100000 0.0026690000 0.0000050000 0.0000040000 0.0009410000 16932717 96830484 509673472 3.9224030972 4.0638818741 4.1837258339 732 1305031126.5582089424 0.0695636123 0.0472325777 0.1139973328 0.0167486238 0.0052230000 0.0003850000 0.0025820000 0.0000010000 0.0000050000 0.0007650000 16936501 96830484 509673472 3.9238438606 4.0731711388 4.1819658279 733 1305031126.5901761055 0.0725853294 0.0472671653 0.1139973328 0.0167377400 0.0123920000 0.0005560000 0.0047400000 0.0000140000 0.0000130000 0.0020360000 16940173 96830484 509673472 3.9226052761 4.0792112350 4.1810898781 734 1305031126.6186869144 0.0737204626 0.0473032052 0.1139973328 0.0167269402 0.0069290000 0.0004650000 0.0027940000 0.0000020000 0.0000100000 0.0009750000 16943733 96830484 509673472 3.9223926067 4.0865306854 4.1795382500 735 1305031126.6544740200 0.0778595209 0.0473447784 0.1139973328 0.0167286808 0.0058560000 0.0004070000 0.0026490000 0.0000050000 0.0000050000 0.0009990000 16947573 96830484 509673472 3.9235346317 4.0894250870 4.1790695190 736 1305031126.6900219917 0.0824047104 0.0473924142 0.1139973328 0.0167185652 0.0057860000 0.0003790000 0.0032960000 0.0000000000 0.0000040000 0.0007520000 16951357 96830484 509673472 3.9235606194 4.0934219360 4.1773204803 737 1305031126.7157700062 0.0819299445 0.0474392765 0.1139973328 0.0167081481 0.0107890000 0.0005450000 0.0036240000 0.0000150000 0.0000140000 0.0025380000 16954805 96830484 509673472 3.9251551628 4.0997743607 4.1751317978 738 1305031126.7553739548 0.0845375955 0.0474895453 0.1139973328 0.0166983589 0.0070310000 0.0004790000 0.0037180000 0.0000010000 0.0000070000 0.0008190000 16958701 96830484 509673472 3.9239432812 4.1015081406 4.1729207039 739 1305031126.7875649929 0.0844369531 0.0475395418 0.1139973328 0.0166895309 0.0070660000 0.0003770000 0.0043230000 0.0000040000 0.0000030000 0.0009850000 16962373 96830484 509673472 3.9252524376 4.1068644524 4.1697468758 740 1305031126.8199288845 0.0840696171 0.0475889067 0.1139973328 0.0166812668 0.0055460000 0.0003630000 0.0032680000 0.0000010000 0.0000040000 0.0007400000 16966045 96830484 509673472 3.9265589714 4.1110320091 4.1673583984 741 1305031126.8583779335 0.0860530362 0.0476408151 0.1139973328 0.0166702668 0.0109350000 0.0005480000 0.0048350000 0.0000150000 0.0000130000 0.0019730000 16969941 96830484 509673472 3.9279146194 4.1132936478 4.1661467552 742 1305031126.8881540298 0.0867304206 0.0476934965 0.1139973328 0.0166595531 0.0066910000 0.0004340000 0.0033910000 0.0000010000 0.0000050000 0.0008160000 16973557 96830484 509673472 3.9279017448 4.1146817207 4.1643524170 743 1305031126.9194090366 0.0865577087 0.0477458037 0.1139973328 0.0166491117 0.0054630000 0.0003750000 0.0026130000 0.0000040000 0.0000040000 0.0009680000 16977173 96830484 509673472 3.9296236038 4.1157336235 4.1628065109 744 1305031126.9555010796 0.0859049633 0.0477970929 0.1139973328 0.0166411244 0.0088100000 0.0004700000 0.0045810000 0.0000020000 0.0000100000 0.0010080000 16980957 96830484 509673472 3.9296240807 4.1173219681 4.1612396240 745 1305031126.9873158932 0.0871830136 0.0478499599 0.1139973328 0.0166310617 0.0076660000 0.0004070000 0.0040450000 0.0000060000 0.0000050000 0.0013960000 16984685 96830484 509673472 3.9293160439 4.1161289215 4.1603112221 746 1305031127.0195240974 0.0869803876 0.0479024135 0.1139973328 0.0166206118 0.0066970000 0.0003710000 0.0042870000 0.0000010000 0.0000040000 0.0007490000 16988301 96830484 509673472 3.9294638634 4.1158771515 4.1594090462 747 1305031127.0533180237 0.0852689147 0.0479524356 0.1139973328 0.0166128551 0.0075130000 0.0004640000 0.0028040000 0.0000100000 0.0000090000 0.0012300000 16992029 96830484 509673472 3.9318692684 4.1171183586 4.1589488983 748 1305031127.0886490345 0.0835106671 0.0479999734 0.1139973328 0.0166050090 0.0076120000 0.0003990000 0.0043870000 0.0000010000 0.0000060000 0.0008250000 16995813 96830484 509673472 3.9320108891 4.1173577309 4.1589627266 749 1305031127.1209630966 0.0841681436 0.0480482620 0.1139973328 0.0166014303 0.0090340000 0.0004600000 0.0045630000 0.0000070000 0.0000070000 0.0015230000 16999429 96830484 509673472 3.9309406281 4.1147551537 4.1590542793 750 1305031127.1576919556 0.0823418573 0.0480939868 0.1139973328 0.0165909226 0.0071120000 0.0003870000 0.0043770000 0.0000010000 0.0000040000 0.0007630000 17003269 96830484 509673472 3.9284307957 4.1137866974 4.1581602097 751 1305031127.1875000000 0.0800552815 0.0481365451 0.1139973328 0.0165835336 0.0068960000 0.0003690000 0.0043030000 0.0000040000 0.0000030000 0.0009800000 17006885 96830484 509673472 3.9292585850 4.1142568588 4.1584978104 752 1305031127.2218310833 0.0773776248 0.0481754295 0.1139973328 0.0165752814 0.0051820000 0.0003640000 0.0029040000 0.0000000000 0.0000030000 0.0007540000 17010613 96830484 509673472 3.9281663895 4.1148185730 4.1581482887 753 1305031127.2597610950 0.0767457560 0.0482133715 0.1139973328 0.0165691563 0.0071860000 0.0003640000 0.0042800000 0.0000030000 0.0000030000 0.0013530000 17014453 96830484 509673472 3.9263141155 4.1114940643 4.1591591835 754 1305031127.2870380878 0.0745376721 0.0482482844 0.1139973328 0.0165662884 0.0113370000 0.0005660000 0.0048390000 0.0000030000 0.0000150000 0.0012650000 17017957 96830484 509673472 3.9260702133 4.1112623215 4.1596775055 755 1305031127.3204679489 0.0731848180 0.0482813129 0.1139973328 0.0165566058 0.0070680000 0.0004320000 0.0033830000 0.0000060000 0.0000050000 0.0010340000 17021685 96830484 509673472 3.9252364635 4.1101913452 4.1608643532 756 1305031127.3534069061 0.0753537342 0.0483171230 0.1139973328 0.0165518672 0.0057190000 0.0003920000 0.0029690000 0.0000000000 0.0000050000 0.0007610000 17025357 96830484 509673472 3.9259278774 4.1043429375 4.1628484726 757 1305031127.3837130070 0.0729798228 0.0483497025 0.1139973328 0.0165438436 0.0097940000 0.0004640000 0.0045570000 0.0000100000 0.0000090000 0.0017130000 17029029 96830484 509673472 3.9259274006 4.1044259071 4.1638951302 758 1305031127.4196500778 0.0704505295 0.0483788593 0.1139973328 0.0165344828 0.0060520000 0.0004090000 0.0030090000 0.0000010000 0.0000190000 0.0007840000 17032757 96830484 509673472 3.9264478683 4.1040992737 4.1654181480 759 1305031127.4542460442 0.0714566037 0.0484092647 0.1139973328 0.0165347233 0.0070670000 0.0003790000 0.0043180000 0.0000040000 0.0000040000 0.0009910000 17036541 96830484 509673472 3.9259669781 4.1001987457 4.1670789719 760 1305031127.4872000217 0.0692327470 0.0484366640 0.1139973328 0.0165365390 0.0053180000 0.0003680000 0.0029140000 0.0000000000 0.0000030000 0.0007500000 17040213 96830484 509673472 3.9269373417 4.1003460884 4.1685380936 761 1305031127.5218999386 0.0690186694 0.0484637100 0.1139973328 0.0165261713 0.0069520000 0.0003650000 0.0039270000 0.0000030000 0.0000030000 0.0013690000 17043997 96830484 509673472 3.9268126488 4.0999798775 4.1705899239 762 1305031127.5537250042 0.0713474900 0.0484937413 0.1139973328 0.0165252080 0.0066580000 0.0003630000 0.0042730000 0.0000000000 0.0000030000 0.0007490000 17047613 96830484 509673472 3.9258713722 4.0956940651 4.1724963188 763 1305031127.5866320133 0.0705358237 0.0485226300 0.1139973328 0.0165167866 0.0068810000 0.0003590000 0.0042640000 0.0000030000 0.0000030000 0.0009910000 17051341 96830484 509673472 3.9248633385 4.0953450203 4.1734433174 764 1305031127.6206569672 0.0695019737 0.0485500898 0.1139973328 0.0165066283 0.0120780000 0.0005490000 0.0047960000 0.0000020000 0.0000150000 0.0012810000 17055069 96830484 509673472 3.9271841049 4.0958662033 4.1750493050 765 1305031127.6546559334 0.0709781647 0.0485794076 0.1139973328 0.0164972448 0.0068950000 0.0004320000 0.0026850000 0.0000070000 0.0000070000 0.0015210000 17058741 96830484 509673472 3.9268932343 4.0935111046 4.1762824059 766 1305031127.6871099472 0.0710022375 0.0486086802 0.1139973328 0.0164865710 0.0057260000 0.0003910000 0.0029560000 0.0000000000 0.0000040000 0.0007640000 17062469 96830484 509673472 3.9282884598 4.0915913582 4.1767091751 767 1305031127.7232100964 0.0694712475 0.0486358804 0.1139973328 0.0164780939 0.0069810000 0.0003700000 0.0042780000 0.0000040000 0.0000040000 0.0009660000 17066253 96830484 509673472 3.9279978275 4.0929627419 4.1773209572 768 1305031127.7546939850 0.0705852136 0.0486644603 0.1139973328 0.0164683523 0.0095260000 0.0005500000 0.0047070000 0.0000010000 0.0000100000 0.0010200000 17069869 96830484 509673472 3.9272823334 4.0910420418 4.1783313751 769 1305031127.7876410484 0.0706425160 0.0486930403 0.1139973328 0.0164626497 0.0080500000 0.0003990000 0.0043660000 0.0000050000 0.0000040000 0.0014010000 17073653 96830484 509673472 3.9264039993 4.0891036987 4.1780691147 770 1305031127.8201279640 0.0691418573 0.0487195972 0.1139973328 0.0164537107 0.0121700000 0.0005610000 0.0047330000 0.0000020000 0.0000150000 0.0012770000 17077269 96830484 509673472 3.9259939194 4.0898408890 4.1778607368 771 1305031127.8551321030 0.0690818653 0.0487460074 0.1139973328 0.0164430536 0.0105930000 0.0005620000 0.0029430000 0.0000150000 0.0000140000 0.0015030000 17080997 96830484 509673472 3.9260597229 4.0892810822 4.1781644821 772 1305031127.8871219158 0.0694172457 0.0487727837 0.1139973328 0.0164336583 0.0096930000 0.0005740000 0.0046810000 0.0000020000 0.0000110000 0.0010270000 17084725 96830484 509673472 3.9253835678 4.0877981186 4.1782422066 773 1305031127.9225599766 0.0690959841 0.0487990750 0.1139973328 0.0164254092 0.0064180000 0.0004110000 0.0026260000 0.0000060000 0.0000050000 0.0014240000 17088509 96830484 509673472 3.9236674309 4.0880632401 4.1785807610 774 1305031127.9550879002 0.0684830248 0.0488245064 0.1139973328 0.0164161713 0.0068710000 0.0003770000 0.0042870000 0.0000010000 0.0000040000 0.0007580000 17092181 96830484 509673472 3.9249217510 4.0884695053 4.1797537804 775 1305031127.9870929718 0.0680515766 0.0488493156 0.1139973328 0.0164057827 0.0116680000 0.0005460000 0.0039950000 0.0000140000 0.0000140000 0.0014810000 17095853 96830484 509673472 3.9252977371 4.0878510475 4.1812176704 776 1305031128.0217759609 0.0678237453 0.0488737672 0.1139973328 0.0163982794 0.0091930000 0.0005560000 0.0043220000 0.0000020000 0.0000100000 0.0010270000 17099637 96830484 509673472 3.9250030518 4.0877509117 4.1830682755 777 1305031128.0557179451 0.0680878758 0.0488984957 0.1139973328 0.0163907622 0.0081320000 0.0004220000 0.0043890000 0.0000050000 0.0000050000 0.0013890000 17103309 96830484 509673472 3.9247896671 4.0864267349 4.1853542328 778 1305031128.0872058868 0.0700629428 0.0489256994 0.1139973328 0.0163821579 0.0054940000 0.0003830000 0.0029090000 0.0000000000 0.0000040000 0.0007520000 17106981 96830484 509673472 3.9247739315 4.0832238197 4.1872406006 779 1305031128.1247460842 0.0699115172 0.0489526388 0.1139973328 0.0163728059 0.0079460000 0.0004620000 0.0040860000 0.0000090000 0.0000070000 0.0011060000 17110821 96830484 509673472 3.9254732132 4.0825181007 4.1886167526 780 1305031128.1577820778 0.0698841214 0.0489794741 0.1139973328 0.0163637838 0.0060890000 0.0003800000 0.0032860000 0.0000010000 0.0000050000 0.0007660000 17114549 96830484 509673472 3.9272542000 4.0816340446 4.1905078888 781 1305031128.1872210503 0.0712179616 0.0490079484 0.1139973328 0.0163568627 0.0113540000 0.0005490000 0.0047440000 0.0000160000 0.0000130000 0.0020280000 17118109 96830484 509673472 3.9271979332 4.0788946152 4.1912317276 782 1305031128.2254419327 0.0700664371 0.0490348775 0.1139973328 0.0163515202 0.0077290000 0.0004330000 0.0043880000 0.0000010000 0.0000060000 0.0008180000 17121949 96830484 509673472 3.9270887375 4.0794310570 4.1914291382 783 1305031128.2560069561 0.0693580732 0.0490608330 0.1139973328 0.0163413403 0.0054930000 0.0003820000 0.0025740000 0.0000050000 0.0000050000 0.0009870000 17125565 96830484 509673472 3.9269514084 4.0797338486 4.1921834946 784 1305031128.2912750244 0.0703579783 0.0490879977 0.1139973328 0.0163343930 0.0084100000 0.0004680000 0.0044700000 0.0000010000 0.0000080000 0.0008860000 17129349 96830484 509673472 3.9267296791 4.0780248642 4.1925563812 785 1305031128.3241701126 0.0695714429 0.0491140913 0.1139973328 0.0163247299 0.0096390000 0.0004620000 0.0046580000 0.0000080000 0.0000070000 0.0015560000 17133021 96830484 509673472 3.9283921719 4.0781254768 4.1925015450 786 1305031128.3552060127 0.0691358373 0.0491395642 0.1139973328 0.0163152075 0.0063430000 0.0004430000 0.0034020000 0.0000010000 0.0000050000 0.0007670000 17136693 96830484 509673472 3.9273951054 4.0782189369 4.1924800873 787 1305031128.3913969994 0.0693532452 0.0491652487 0.1139973328 0.0163050003 0.0069630000 0.0003710000 0.0042540000 0.0000040000 0.0000030000 0.0009910000 17140477 96830484 509673472 3.9257180691 4.0772371292 4.1923956871 788 1305031128.4236090183 0.0697431713 0.0491913628 0.1139973328 0.0162947747 0.0092060000 0.0004720000 0.0045240000 0.0000010000 0.0000100000 0.0010210000 17144149 96830484 509673472 3.9251766205 4.0760478973 4.1922821999 789 1305031128.4554989338 0.0685478151 0.0492158957 0.1139973328 0.0162864026 0.0080330000 0.0003990000 0.0043140000 0.0000050000 0.0000050000 0.0013750000 17147821 96830484 509673472 3.9244375229 4.0766425133 4.1918802261 790 1305031128.4895229340 0.0690858141 0.0492410475 0.1139973328 0.0162766279 0.0070760000 0.0003830000 0.0043120000 0.0000000000 0.0000040000 0.0007620000 17151605 96830484 509673472 3.9241495132 4.0753717422 4.1921358109 791 1305031128.5236039162 0.0686180666 0.0492655444 0.1139973328 0.0162665534 0.0051770000 0.0003670000 0.0025590000 0.0000040000 0.0000030000 0.0009620000 17155277 96830484 509673472 3.9242844582 4.0747880936 4.1919641495 792 1305031128.5556390285 0.0683410242 0.0492896296 0.1139973328 0.0162579591 0.0065940000 0.0003620000 0.0042260000 0.0000000000 0.0000030000 0.0007470000 17158949 96830484 509673472 3.9256072044 4.0741043091 4.1919350624 793 1305031128.5914599895 0.0691348910 0.0493146551 0.1139973328 0.0162485911 0.0117130000 0.0005500000 0.0047420000 0.0000160000 0.0000130000 0.0020450000 17162733 96830484 509673472 3.9235653877 4.0724449158 4.1916389465 794 1305031128.6233680248 0.0689627007 0.0493394008 0.1139973328 0.0162390778 0.0069310000 0.0004320000 0.0033430000 0.0000010000 0.0000060000 0.0008250000 17166405 96830484 509673472 3.9247388840 4.0714955330 4.1913552284 795 1305031128.6555540562 0.0679760799 0.0493628432 0.1139973328 0.0162308837 0.0071880000 0.0003970000 0.0042900000 0.0000040000 0.0000040000 0.0009910000 17170077 96830484 509673472 3.9249274731 4.0718374252 4.1909193993 796 1305031128.6904489994 0.0677107498 0.0493858933 0.1139973328 0.0162216023 0.0083990000 0.0004690000 0.0044380000 0.0000010000 0.0000070000 0.0008940000 17173861 96830484 509673472 3.9247143269 4.0716052055 4.1906070709 797 1305031128.7229759693 0.0675810054 0.0494087228 0.1139973328 0.0162123295 0.0093260000 0.0004640000 0.0045110000 0.0000080000 0.0000070000 0.0015330000 17177533 96830484 509673472 3.9242999554 4.0710554123 4.1901798248 798 1305031128.7546460629 0.0666493922 0.0494303276 0.1139973328 0.0162036901 0.0071360000 0.0003890000 0.0042950000 0.0000010000 0.0000050000 0.0007650000 17181205 96830484 509673472 3.9236803055 4.0715799332 4.1895327568 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 01:23:25 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019025257 0.0019025257 0.0019025257 -nan 0.0239450000 0.0006340000 0.0005730000 0.0000210000 0.0000040000 0.0061850000 21824421 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 1311867718.6768438816 0.0021839470 0.0020432363 0.0021839470 0.0015734395 0.0040450000 0.0006270000 0.0005360000 0.0000150000 0.0000010000 0.0011130000 34411421 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 1311867718.7114279270 0.0026191149 0.0022351959 0.0026191149 0.0052681691 0.0039610000 0.0006060000 0.0005350000 0.0000150000 0.0000020000 0.0011070000 34415541 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 1311867718.7410299778 0.0032201277 0.0024814288 0.0032201277 0.0047920539 0.0045220000 0.0005500000 0.0005330000 0.0000150000 0.0000230000 0.0016810000 34419501 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 1311867718.7767970562 0.0102640521 0.0040379535 0.0102640521 0.0093924092 0.0091930000 0.0005360000 0.0047130000 0.0000140000 0.0000130000 0.0026680000 34423669 96830484 509673472 3.9892036915 3.9964058399 4.0032463074 6 1311867718.8094089031 0.0111330729 0.0052204734 0.0111330729 0.0088679123 0.0064380000 0.0004300000 0.0043420000 0.0000010000 0.0000060000 0.0011390000 34428141 96830484 509673472 3.9877474308 3.9977481365 4.0040683746 7 1311867718.8408079147 0.0115129286 0.0061193956 0.0115129286 0.0081087129 0.0063980000 0.0003910000 0.0042560000 0.0000050000 0.0000040000 0.0013550000 34431757 96830484 509673472 3.9869339466 3.9982511997 4.0042514801 8 1311867718.8767778873 0.0151306605 0.0072458037 0.0151306605 0.0077076935 0.0054520000 0.0004670000 0.0030800000 0.0000010000 0.0000100000 0.0012470000 34435541 96830484 509673472 3.9833197594 3.9974725246 4.0047254562 9 1311867718.9088680744 0.0145872217 0.0080615168 0.0151306605 0.0072408222 0.0074170000 0.0004190000 0.0043360000 0.0000060000 0.0000050000 0.0020210000 34439925 96830484 509673472 3.9835488796 3.9977269173 4.0048484802 10 1311867718.9438331127 0.0158416685 0.0088395320 0.0158416685 0.0068818651 0.0063000000 0.0003890000 0.0042360000 0.0000010000 0.0000050000 0.0011190000 34445309 96830484 509673472 3.9821686745 3.9979343414 4.0057206154 11 1311867718.9784109592 0.0144145880 0.0093463552 0.0158416685 0.0067668751 0.0064360000 0.0003810000 0.0042140000 0.0000040000 0.0000030000 0.0013240000 34449093 96830484 509673472 3.9839327335 3.9964644909 4.0056333542 12 1311867719.0091300011 0.0181296188 0.0100782939 0.0181296188 0.0067807369 0.0086880000 0.0005730000 0.0047550000 0.0000020000 0.0000150000 0.0016270000 34452653 96830484 509673472 3.9798796177 3.9964570999 4.0066032410 13 1311867719.0441620350 0.0167917646 0.0105947147 0.0181296188 0.0065079542 0.0076210000 0.0004390000 0.0043750000 0.0000060000 0.0000060000 0.0020550000 34456437 96830484 509673472 3.9810132980 3.9964690208 4.0068116188 14 1311867719.0776190758 0.0181280579 0.0111328106 0.0181296188 0.0063151812 0.0062630000 0.0004010000 0.0042620000 0.0000000000 0.0000050000 0.0010940000 34460165 96830484 509673472 3.9797351360 3.9957485199 4.0073614120 15 1311867719.1086950302 0.0170145445 0.0115249262 0.0181296188 0.0061171978 0.0073800000 0.0004990000 0.0044950000 0.0000070000 0.0000070000 0.0014650000 34463837 96830484 509673472 3.9809360504 3.9950680733 4.0075263977 16 1311867719.1437010765 0.0179954767 0.0119293356 0.0181296188 0.0059708374 0.0053340000 0.0003930000 0.0032670000 0.0000000000 0.0000050000 0.0011120000 34467565 96830484 509673472 3.9795143604 3.9950301647 4.0081753731 17 1311867719.1810290813 0.0160477236 0.0121715937 0.0181296188 0.0059103951 0.0067400000 0.0004680000 0.0030980000 0.0000100000 0.0000100000 0.0022380000 34472885 96830484 509673472 3.9816687107 3.9940738678 4.0082082748 18 1311867719.2127099037 0.0171271432 0.0124469021 0.0181296188 0.0057602695 0.0064250000 0.0004060000 0.0042940000 0.0000010000 0.0000050000 0.0010830000 34479757 96830484 509673472 3.9804296494 3.9934313297 4.0087132454 19 1311867719.2412090302 0.0176422540 0.0127203416 0.0181296188 0.0056867266 0.0057210000 0.0004730000 0.0027700000 0.0000100000 0.0000090000 0.0015220000 34483317 96830484 509673472 3.9793851376 3.9936537743 4.0092010498 20 1311867719.2779469490 0.0179936662 0.0129840079 0.0181296188 0.0058412217 0.0065400000 0.0004350000 0.0044220000 0.0000010000 0.0000060000 0.0011040000 34487045 96830484 509673472 3.9786341190 3.9924819469 4.0094304085 21 1311867719.3104898930 0.0164520442 0.0131491524 0.0181296188 0.0057494339 0.0070440000 0.0003970000 0.0042640000 0.0000060000 0.0000050000 0.0019220000 34490773 96830484 509673472 3.9797942638 3.9931559563 4.0097060204 22 1311867719.3413150311 0.0174264517 0.0133435751 0.0181296188 0.0056630072 0.0060620000 0.0003780000 0.0042110000 0.0000000000 0.0000050000 0.0010590000 34494445 96830484 509673472 3.9786920547 3.9919981956 4.0100612640 23 1311867719.3772718906 0.0166442171 0.0134870813 0.0181296188 0.0055488204 0.0084330000 0.0005580000 0.0046880000 0.0000140000 0.0000130000 0.0018130000 34498173 96830484 509673472 3.9792957306 3.9914023876 4.0097875595 24 1311867719.4105761051 0.0180079658 0.0136754515 0.0181296188 0.0055018137 0.0068460000 0.0004720000 0.0044550000 0.0000010000 0.0000070000 0.0012020000 34501901 96830484 509673472 3.9775919914 3.9909479618 4.0101957321 25 1311867719.4427709579 0.0165170077 0.0137891137 0.0181296188 0.0055139218 0.0075120000 0.0004660000 0.0044030000 0.0000080000 0.0000080000 0.0020470000 34505629 96830484 509673472 3.9794719219 3.9902555943 4.0101256371 26 1311867719.4787840843 0.0194815714 0.0140080544 0.0194815714 0.0054387602 0.0054810000 0.0003930000 0.0035730000 0.0000010000 0.0000040000 0.0010630000 34509357 96830484 509673472 3.9766421318 3.9880125523 4.0103077888 27 1311867719.5104370117 0.0191948060 0.0142001563 0.0194815714 0.0054673182 0.0070770000 0.0004780000 0.0044470000 0.0000080000 0.0000070000 0.0014260000 34513029 96830484 509673472 3.9767742157 3.9878785610 4.0101528168 28 1311867719.5449650288 0.0180429295 0.0143373982 0.0194815714 0.0054495016 0.0053290000 0.0004100000 0.0032840000 0.0000010000 0.0000060000 0.0011080000 34516757 96830484 509673472 3.9764914513 3.9887819290 4.0108141899 29 1311867719.5771939754 0.0191478264 0.0145032751 0.0194815714 0.0054136206 0.0092840000 0.0005540000 0.0047180000 0.0000140000 0.0000140000 0.0026010000 34520485 96830484 509673472 3.9756741524 3.9870018959 4.0107498169 30 1311867719.6112511158 0.0195648875 0.0146719955 0.0195648875 0.0053773952 0.0048550000 0.0004380000 0.0026470000 0.0000010000 0.0000070000 0.0011610000 34524213 96830484 509673472 3.9748101234 3.9866788387 4.0111804008 31 1311867719.6421909332 0.0168362614 0.0147418105 0.0195648875 0.0053001584 0.0064050000 0.0003890000 0.0042570000 0.0000040000 0.0000050000 0.0012940000 34527829 96830484 509673472 3.9770922661 3.9876105785 4.0113821030 32 1311867719.6770479679 0.0178334545 0.0148384244 0.0195648875 0.0052307219 0.0064670000 0.0005560000 0.0036280000 0.0000010000 0.0000140000 0.0013130000 34531613 96830484 509673472 3.9763333797 3.9863960743 4.0119295120 33 1311867719.7107939720 0.0178784989 0.0149305479 0.0195648875 0.0051605900 0.0074000000 0.0004310000 0.0043640000 0.0000090000 0.0000060000 0.0019800000 34538357 96830484 509673472 3.9757232666 3.9867808819 4.0125985146 34 1311867719.7442650795 0.0173720457 0.0150023566 0.0195648875 0.0051127851 0.0051910000 0.0003990000 0.0032350000 0.0000000000 0.0000040000 0.0010650000 34548429 96830484 509673472 3.9755859375 3.9876315594 4.0135035515 35 1311867719.7861878872 0.0184156466 0.0150998792 0.0195648875 0.0050441812 0.0077950000 0.0005540000 0.0046990000 0.0000100000 0.0000090000 0.0015330000 34552437 96830484 509673472 3.9747061729 3.9867012501 4.0141134262 36 1311867719.8099169731 0.0186995156 0.0151998691 0.0195648875 0.0049880448 0.0064290000 0.0004340000 0.0043370000 0.0000010000 0.0000070000 0.0011210000 34555829 96830484 509673472 3.9744174480 3.9862310886 4.0144648552 37 1311867719.8454990387 0.0190912783 0.0153050423 0.0195648875 0.0049652067 0.0077620000 0.0004820000 0.0044350000 0.0000070000 0.0000080000 0.0020590000 34559613 96830484 509673472 3.9746661186 3.9849848747 4.0145101547 38 1311867719.8771090508 0.0189940073 0.0154021203 0.0195648875 0.0049015632 0.0068880000 0.0004740000 0.0044740000 0.0000010000 0.0000070000 0.0011760000 34563285 96830484 509673472 3.9743752480 3.9848139286 4.0147399902 39 1311867719.9114089012 0.0183897503 0.0154787262 0.0195648875 0.0049138695 0.0048530000 0.0004080000 0.0026000000 0.0000050000 0.0000050000 0.0013020000 34567069 96830484 509673472 3.9738569260 3.9853668213 4.0152425766 40 1311867719.9461970329 0.0211615618 0.0156207971 0.0211615618 0.0049006199 0.0065150000 0.0005410000 0.0029270000 0.0000020000 0.0000140000 0.0015770000 34570797 96830484 509673472 3.9715821743 3.9833581448 4.0158872604 41 1311867719.9807810783 0.0207872372 0.0157468079 0.0211615618 0.0048538593 0.0078240000 0.0004710000 0.0044630000 0.0000070000 0.0000080000 0.0021040000 34574525 96830484 509673472 3.9725306034 3.9823985100 4.0158748627 42 1311867720.0117020607 0.0209571347 0.0158708633 0.0211615618 0.0048837466 0.0056840000 0.0004170000 0.0036240000 0.0000000000 0.0000050000 0.0010850000 34578197 96830484 509673472 3.9701812267 3.9839093685 4.0166592598 43 1311867720.0452380180 0.0215892904 0.0160038499 0.0215892904 0.0048597717 0.0071210000 0.0004780000 0.0041370000 0.0000100000 0.0000100000 0.0015550000 34581869 96830484 509673472 3.9692268372 3.9833016396 4.0169448853 44 1311867720.0772819519 0.0182561073 0.0160550376 0.0215892904 0.0048449785 0.0069260000 0.0004840000 0.0044760000 0.0000000000 0.0000070000 0.0011850000 34585597 96830484 509673472 3.9731252193 3.9841437340 4.0174436569 45 1311867720.1172130108 0.0164877065 0.0160646525 0.0215892904 0.0048249417 0.0067910000 0.0004800000 0.0034460000 0.0000100000 0.0000110000 0.0020600000 34589493 96830484 509673472 3.9763276577 3.9841480255 4.0178790092 46 1311867720.1451559067 0.0173737146 0.0160931103 0.0215892904 0.0047744780 0.0049780000 0.0004080000 0.0029330000 0.0000010000 0.0000060000 0.0010860000 34592997 96830484 509673472 3.9753468037 3.9837682247 4.0184264183 47 1311867720.1781630516 0.0154029727 0.0160784266 0.0215892904 0.0047325393 0.0064370000 0.0005510000 0.0032600000 0.0000140000 0.0000150000 0.0015490000 34596669 96830484 509673472 3.9772396088 3.9852161407 4.0189161301 48 1311867720.2094950676 0.0166839957 0.0160910426 0.0215892904 0.0047239719 0.0065380000 0.0005720000 0.0035950000 0.0000020000 0.0000150000 0.0013100000 34600341 96830484 509673472 3.9739062786 3.9858813286 4.0198011398 49 1311867720.2421469688 0.0132937590 0.0160339552 0.0215892904 0.0047531429 0.0067180000 0.0004340000 0.0036390000 0.0000060000 0.0000060000 0.0019740000 34604069 96830484 509673472 3.9793310165 3.9870800972 4.0199284554 50 1311867720.2770779133 0.0157635808 0.0160285477 0.0215892904 0.0047610342 0.0055630000 0.0004800000 0.0030760000 0.0000010000 0.0000080000 0.0011860000 34607797 96830484 509673472 3.9760839939 3.9860494137 4.0212006569 51 1311867720.3094570637 0.0126760276 0.0159628120 0.0215892904 0.0047326642 0.0075360000 0.0005550000 0.0043470000 0.0000100000 0.0000090000 0.0015390000 34611469 96830484 509673472 3.9794588089 3.9882755280 4.0219421387 52 1311867720.3430728912 0.0134300692 0.0159141054 0.0215892904 0.0047872163 0.0065570000 0.0004400000 0.0043580000 0.0000010000 0.0000060000 0.0011200000 34615197 96830484 509673472 3.9783725739 3.9887163639 4.0232467651 53 1311867720.3779859543 0.0138993226 0.0158760906 0.0215892904 0.0048517122 0.0074700000 0.0004780000 0.0041110000 0.0000070000 0.0000080000 0.0020620000 34618869 96830484 509673472 3.9813685417 3.9869272709 4.0234851837 54 1311867720.4096798897 0.0142641813 0.0158462404 0.0215892904 0.0049512368 0.0062760000 0.0004000000 0.0042910000 0.0000010000 0.0000050000 0.0010690000 34622541 96830484 509673472 3.9818754196 3.9865703583 4.0240769386 55 1311867720.4461109638 0.0135617536 0.0158047043 0.0215892904 0.0049126374 0.0054640000 0.0003820000 0.0031990000 0.0000040000 0.0000040000 0.0012850000 34626381 96830484 509673472 3.9829032421 3.9874417782 4.0244336128 56 1311867720.4799289703 0.0139264073 0.0157711633 0.0215892904 0.0049370263 0.0085510000 0.0005600000 0.0046900000 0.0000020000 0.0000160000 0.0015890000 34630109 96830484 509673472 3.9846806526 3.9872336388 4.0243601799 57 1311867720.5104389191 0.0136187905 0.0157334024 0.0215892904 0.0049878386 0.0059290000 0.0004450000 0.0026350000 0.0000060000 0.0000050000 0.0019700000 34633725 96830484 509673472 3.9832081795 3.9868409634 4.0242052078 58 1311867720.5467319489 0.0143004106 0.0157086956 0.0215892904 0.0050831006 0.0066230000 0.0004580000 0.0043880000 0.0000000000 0.0000040000 0.0010850000 34637565 96830484 509673472 3.9860279560 3.9875872135 4.0245943069 59 1311867720.5793280602 0.0141089745 0.0156815817 0.0215892904 0.0051332643 0.0070890000 0.0004810000 0.0041080000 0.0000070000 0.0000070000 0.0014230000 34641237 96830484 509673472 3.9839060307 3.9867296219 4.0251083374 60 1311867720.6121249199 0.0151068093 0.0156720022 0.0215892904 0.0051124852 0.0072350000 0.0004840000 0.0044780000 0.0000010000 0.0000080000 0.0011910000 34644909 96830484 509673472 3.9851346016 3.9862604141 4.0251116753 61 1311867720.6463210583 0.0153045142 0.0156659778 0.0215892904 0.0050979825 0.0073730000 0.0004250000 0.0043130000 0.0000060000 0.0000050000 0.0020710000 34648693 96830484 509673472 3.9850370884 3.9864044189 4.0255784988 62 1311867720.6798269749 0.0170378014 0.0156881040 0.0215892904 0.0050935102 0.0052390000 0.0003840000 0.0032370000 0.0000000000 0.0000030000 0.0010510000 34652309 96830484 509673472 3.9877755642 3.9862463474 4.0255546570 63 1311867720.7102439404 0.0172064323 0.0157122044 0.0215892904 0.0050581679 0.0064140000 0.0003740000 0.0042040000 0.0000030000 0.0000030000 0.0012830000 34655981 96830484 509673472 3.9862077236 3.9851493835 4.0256309509 64 1311867720.7451629639 0.0167719573 0.0157287631 0.0215892904 0.0050646272 0.0058360000 0.0003730000 0.0038720000 0.0000000000 0.0000030000 0.0010390000 34659709 96830484 509673472 3.9855878353 3.9857013226 4.0256361961 65 1311867720.7790179253 0.0580367185 0.0163796547 0.0580367185 0.0062289854 0.0069450000 0.0003720000 0.0041800000 0.0000040000 0.0000030000 0.0018330000 34669637 96830484 509673472 4.0313801765 3.9881794453 4.0336241722 66 1311867720.8115909100 0.0585596487 0.0170187455 0.0585596487 0.0061817808 0.0061310000 0.0003710000 0.0041830000 0.0000010000 0.0000040000 0.0010230000 34686109 96830484 509673472 4.0310735703 3.9873993397 4.0340218544 67 1311867720.8467299938 0.0623712279 0.0176956482 0.0623712279 0.0061468476 0.0063570000 0.0003710000 0.0041920000 0.0000040000 0.0000030000 0.0012360000 34689893 96830484 509673472 4.0346460342 3.9881527424 4.0344128609 68 1311867720.8813319206 0.0595694855 0.0183114399 0.0623712279 0.0061879180 0.0061170000 0.0003700000 0.0041780000 0.0000000000 0.0000030000 0.0010110000 34693621 96830484 509673472 4.0314064026 3.9888162613 4.0349502563 69 1311867720.9149661064 0.0605958104 0.0189242569 0.0623712279 0.0061524819 0.0069450000 0.0003700000 0.0041920000 0.0000030000 0.0000030000 0.0018230000 34697293 96830484 509673472 4.0316729546 3.9873280525 4.0352406502 70 1311867720.9500010014 0.0602902360 0.0195151995 0.0623712279 0.0061086603 0.0080330000 0.0005720000 0.0047070000 0.0000020000 0.0000100000 0.0012970000 34701021 96830484 509673472 4.0310130119 3.9876854420 4.0357837677 71 1311867720.9797990322 0.0627401173 0.0201240011 0.0627401173 0.0060781589 0.0068070000 0.0004330000 0.0043090000 0.0000060000 0.0000060000 0.0012700000 34704581 96830484 509673472 4.0334706306 3.9880969524 4.0356998444 72 1311867721.0093889236 0.0637951270 0.0207305445 0.0637951270 0.0060367723 0.0042500000 0.0003820000 0.0022160000 0.0000000000 0.0000050000 0.0010350000 34708197 96830484 509673472 4.0343379974 3.9879539013 4.0359897614 73 1311867721.0478379726 0.0624161921 0.0213015808 0.0637951270 0.0060020486 0.0069820000 0.0003710000 0.0041990000 0.0000030000 0.0000030000 0.0018350000 34712093 96830484 509673472 4.0325551033 3.9879443645 4.0359640121 74 1311867721.0794439316 0.0642366558 0.0218817845 0.0642366558 0.0059718221 0.0058260000 0.0003720000 0.0038550000 0.0000010000 0.0000030000 0.0010300000 34715709 96830484 509673472 4.0340943336 3.9873862267 4.0361948013 75 1311867721.1103579998 0.0598315336 0.0223877812 0.0642366558 0.0059641920 0.0088310000 0.0005680000 0.0047160000 0.0000140000 0.0000140000 0.0017850000 34719381 96830484 509673472 4.0289483070 3.9869265556 4.0363469124 76 1311867721.1467890739 0.0624389388 0.0229147701 0.0642366558 0.0059616159 0.0068140000 0.0004340000 0.0043460000 0.0000010000 0.0000060000 0.0011040000 34723165 96830484 509673472 4.0309109688 3.9865825176 4.0363221169 77 1311867721.1774179935 0.0631046817 0.0234367170 0.0642366558 0.0059903658 0.0070510000 0.0004100000 0.0042450000 0.0000050000 0.0000040000 0.0018600000 34726837 96830484 509673472 4.0315356255 3.9862382412 4.0365529060 78 1311867721.2112360001 0.0617361404 0.0239277352 0.0642366558 0.0059576910 0.0053830000 0.0003740000 0.0035250000 0.0000010000 0.0000030000 0.0010220000 34730509 96830484 509673472 4.0296792984 3.9862065315 4.0367326736 79 1311867721.2469010353 0.0644295588 0.0244404166 0.0644295588 0.0059370817 0.0062680000 0.0003740000 0.0041800000 0.0000030000 0.0000030000 0.0012490000 34734293 96830484 509673472 4.0322895050 3.9859459400 4.0366501808 80 1311867721.2800450325 0.0632651076 0.0249257252 0.0644295588 0.0058994802 0.0072530000 0.0005550000 0.0039900000 0.0000020000 0.0000140000 0.0015090000 34737965 96830484 509673472 4.0302042961 3.9849245548 4.0368542671 81 1311867721.3099579811 0.0684742257 0.0254633610 0.0684742257 0.0059107350 0.0074460000 0.0004320000 0.0043360000 0.0000070000 0.0000050000 0.0019250000 34741581 96830484 509673472 4.0354948044 3.9851069450 4.0370321274 82 1311867721.3483059406 0.0671397746 0.0259716099 0.0684742257 0.0059010607 0.0050500000 0.0004810000 0.0023810000 0.0000010000 0.0000100000 0.0012590000 34745421 96830484 509673472 4.0336589813 3.9852302074 4.0369844437 83 1311867721.3790040016 0.0668660402 0.0264643139 0.0684742257 0.0058714996 0.0067050000 0.0004100000 0.0043020000 0.0000070000 0.0000060000 0.0013140000 34748981 96830484 509673472 4.0327892303 3.9851279259 4.0371894836 84 1311867721.4092550278 0.0664274096 0.0269400651 0.0684742257 0.0058451190 0.0070320000 0.0004790000 0.0044560000 0.0000010000 0.0000080000 0.0011650000 34752597 96830484 509673472 4.0315480232 3.9846615791 4.0376925468 85 1311867721.4478130341 0.0690606907 0.0274356018 0.0690606907 0.0058160216 0.0086330000 0.0005570000 0.0046500000 0.0000100000 0.0000100000 0.0021940000 34756549 96830484 509673472 4.0336065292 3.9842483997 4.0381011963 86 1311867721.4768960476 0.0707498118 0.0279392554 0.0707498118 0.0057836138 0.0064550000 0.0004170000 0.0043100000 0.0000000000 0.0000070000 0.0010760000 34760109 96830484 509673472 4.0349950790 3.9845581055 4.0384683609 87 1311867721.5093359947 0.0707531273 0.0284313689 0.0707531273 0.0057590575 0.0072320000 0.0004720000 0.0044100000 0.0000080000 0.0000070000 0.0014100000 34763725 96830484 509673472 4.0345478058 3.9842226505 4.0383667946 88 1311867721.5451331139 0.0681918487 0.0288831925 0.0707531273 0.0057495971 0.0066060000 0.0004570000 0.0043780000 0.0000000000 0.0000040000 0.0010610000 34767453 96830484 509673472 4.0309505463 3.9832484722 4.0386443138 89 1311867721.5769670010 0.0681954026 0.0293249028 0.0707531273 0.0057270820 0.0069480000 0.0003770000 0.0041860000 0.0000040000 0.0000040000 0.0018880000 34771013 96830484 509673472 4.0307798386 3.9835884571 4.0385756493 90 1311867721.6129651070 0.0685085207 0.0297602763 0.0707531273 0.0057153749 0.0054050000 0.0004780000 0.0023740000 0.0000010000 0.0000100000 0.0013100000 34774741 96830484 509673472 4.0304903984 3.9833238125 4.0386228561 91 1311867721.6496050358 0.0665523410 0.0301645847 0.0707531273 0.0057527394 0.0080000000 0.0005550000 0.0046650000 0.0000100000 0.0000090000 0.0015350000 34778581 96830484 509673472 4.0275220871 3.9819779396 4.0383949280 92 1311867721.6800351143 0.0678364187 0.0305740612 0.0707531273 0.0057478810 0.0064630000 0.0004360000 0.0042920000 0.0000010000 0.0000060000 0.0010610000 34782197 96830484 509673472 4.0290279388 3.9836957455 4.0385890007 93 1311867721.7162289619 0.0676738173 0.0309729833 0.0707531273 0.0057428082 0.0056620000 0.0003820000 0.0028710000 0.0000040000 0.0000040000 0.0018590000 34786037 96830484 509673472 4.0286183357 3.9834494591 4.0388131142 94 1311867721.7467949390 0.0691749081 0.0313793867 0.0707531273 0.0057676355 0.0077390000 0.0005590000 0.0046410000 0.0000010000 0.0000100000 0.0012930000 34789653 96830484 509673472 4.0287604332 3.9809601307 4.0387282372 95 1311867721.7787001133 0.0723190233 0.0318103303 0.0723190233 0.0057531561 0.0067040000 0.0004280000 0.0042870000 0.0000060000 0.0000060000 0.0013030000 34793325 96830484 509673472 4.0322690010 3.9822542667 4.0391812325 96 1311867721.8154830933 0.0715233758 0.0322240078 0.0723190233 0.0057244519 0.0054930000 0.0003830000 0.0035170000 0.0000010000 0.0000040000 0.0010440000 34797109 96830484 509673472 4.0307526588 3.9819102287 4.0392169952 97 1311867721.8485159874 0.0720565990 0.0326346531 0.0723190233 0.0057001690 0.0084600000 0.0005550000 0.0035940000 0.0000140000 0.0000130000 0.0025770000 34800837 96830484 509673472 4.0304455757 3.9806704521 4.0390920639 98 1311867721.8778810501 0.0698500052 0.0330144016 0.0723190233 0.0056868726 0.0066830000 0.0004430000 0.0043350000 0.0000010000 0.0000070000 0.0011100000 34804453 96830484 509673472 4.0279831886 3.9817285538 4.0390067101 99 1311867721.9146931171 0.0700555965 0.0333885551 0.0723190233 0.0056607635 0.0068480000 0.0004680000 0.0040630000 0.0000080000 0.0000060000 0.0014150000 34808013 96830484 509673472 4.0275874138 3.9808955193 4.0387730598 100 1311867721.9467151165 0.0707715079 0.0337623846 0.0723190233 0.0056343420 0.0070590000 0.0004780000 0.0044260000 0.0000010000 0.0000070000 0.0011830000 34811685 96830484 509673472 4.0276823044 3.9801220894 4.0387005806 101 1311867721.9773728848 0.0693493709 0.0341147310 0.0723190233 0.0056378700 0.0055650000 0.0004070000 0.0025400000 0.0000050000 0.0000040000 0.0019290000 34815357 96830484 509673472 4.0260410309 3.9804310799 4.0385613441 102 1311867722.0166850090 0.0718149468 0.0344843410 0.0723190233 0.0056725017 0.0064620000 0.0004780000 0.0034100000 0.0000020000 0.0000100000 0.0013290000 34819085 96830484 509673472 4.0282001495 3.9799897671 4.0384159088 103 1311867722.0475180149 0.0715329945 0.0348440366 0.0723190233 0.0056817007 0.0072830000 0.0004770000 0.0043880000 0.0000070000 0.0000080000 0.0014180000 34822589 96830484 509673472 4.0277643204 3.9795284271 4.0380892754 104 1311867722.0800709724 0.0732325837 0.0352131573 0.0732325837 0.0056702474 0.0054010000 0.0004020000 0.0032170000 0.0000010000 0.0000050000 0.0010880000 34826317 96830484 509673472 4.0291395187 3.9790785313 4.0381445885 105 1311867722.1161251068 0.0740175024 0.0355827225 0.0740175024 0.0056504584 0.0068920000 0.0004800000 0.0030580000 0.0000110000 0.0000100000 0.0022290000 34830101 96830484 509673472 4.0290360451 3.9777984619 4.0380735397 106 1311867722.1479530334 0.0739709735 0.0359448758 0.0740175024 0.0056377131 0.0064500000 0.0004110000 0.0042670000 0.0000000000 0.0000050000 0.0010740000 34833717 96830484 509673472 4.0281744003 3.9772171974 4.0382156372 107 1311867722.1798410416 0.0720888227 0.0362826697 0.0740175024 0.0056278655 0.0074080000 0.0005580000 0.0039880000 0.0000100000 0.0000090000 0.0015480000 34837389 96830484 509673472 4.0262336731 3.9785513878 4.0379805565 108 1311867722.2146399021 0.0723446906 0.0366165773 0.0740175024 0.0056212949 0.0065850000 0.0004600000 0.0042980000 0.0000000000 0.0000070000 0.0011200000 34841173 96830484 509673472 4.0256328583 3.9768936634 4.0380911827 109 1311867722.2469589710 0.0744808838 0.0369639562 0.0744808838 0.0056017638 0.0078160000 0.0004750000 0.0043910000 0.0000070000 0.0000070000 0.0020470000 34844845 96830484 509673472 4.0278515816 3.9768037796 4.0380687714 110 1311867722.2780389786 0.0722524077 0.0372847603 0.0744808838 0.0055848188 0.0070890000 0.0004770000 0.0044320000 0.0000010000 0.0000090000 0.0011750000 34848517 96830484 509673472 4.0254659653 3.9778261185 4.0381546021 111 1311867722.3154170513 0.0736422613 0.0376123054 0.0744808838 0.0055669048 0.0071250000 0.0004650000 0.0043720000 0.0000080000 0.0000070000 0.0014140000 34852301 96830484 509673472 4.0262641907 3.9763245583 4.0383152962 112 1311867722.3488469124 0.0740819946 0.0379379276 0.0744808838 0.0055450712 0.0070890000 0.0004770000 0.0044110000 0.0000010000 0.0000080000 0.0011800000 34855973 96830484 509673472 4.0261931419 3.9755768776 4.0384173393 113 1311867722.3777940273 0.0726896897 0.0382454653 0.0744808838 0.0055333477 0.0061810000 0.0003940000 0.0032250000 0.0000050000 0.0000050000 0.0019180000 34859589 96830484 509673472 4.0252194405 3.9768378735 4.0381007195 114 1311867722.4150679111 0.0765699819 0.0385816453 0.0765699819 0.0055398776 0.0071430000 0.0004810000 0.0044410000 0.0000020000 0.0000100000 0.0011830000 34863205 96830484 509673472 4.0283312798 3.9748294353 4.0388793945 115 1311867722.4467909336 0.0743670985 0.0388928232 0.0765699819 0.0056003788 0.0067180000 0.0004080000 0.0042470000 0.0000050000 0.0000040000 0.0013300000 34866877 96830484 509673472 4.0252428055 3.9742152691 4.0388531685 116 1311867722.4777851105 0.0739253759 0.0391948279 0.0765699819 0.0056087431 0.0071540000 0.0004720000 0.0044360000 0.0000010000 0.0000080000 0.0012100000 34870493 96830484 509673472 4.0247840881 3.9751193523 4.0390691757 117 1311867722.5147399902 0.0778290480 0.0395250349 0.0778290480 0.0055949682 0.0069160000 0.0004080000 0.0038840000 0.0000060000 0.0000050000 0.0019340000 34874221 96830484 509673472 4.0286231041 3.9744594097 4.0397791862 118 1311867722.5469911098 0.0725005046 0.0398044881 0.0778290480 0.0056288143 0.0061570000 0.0003860000 0.0041650000 0.0000000000 0.0000030000 0.0010510000 34877893 96830484 509673472 4.0221982002 3.9740619659 4.0392723083 119 1311867722.5802359581 0.0758990049 0.0401078033 0.0778290480 0.0056237442 0.0088120000 0.0005610000 0.0046530000 0.0000150000 0.0000140000 0.0018270000 34881565 96830484 509673472 4.0257139206 3.9733829498 4.0397639275 120 1311867722.6146309376 0.0751592442 0.0403998987 0.0778290480 0.0056029005 0.0067180000 0.0004350000 0.0042930000 0.0000000000 0.0000060000 0.0011330000 34885293 96830484 509673472 4.0247216225 3.9729158878 4.0394029617 121 1311867722.6560258865 0.0751952007 0.0406874632 0.0778290480 0.0055836236 0.0065440000 0.0003980000 0.0035380000 0.0000040000 0.0000040000 0.0019380000 34889245 96830484 509673472 4.0242733955 3.9722542763 4.0395369530 122 1311867722.6778230667 0.0763686299 0.0409799317 0.0778290480 0.0055685603 0.0071040000 0.0004750000 0.0043800000 0.0000010000 0.0000080000 0.0011970000 34892693 96830484 509673472 4.0252046585 3.9717495441 4.0398807526 123 1311867722.7252709866 0.0735177100 0.0412444665 0.0778290480 0.0055689535 0.0073710000 0.0004680000 0.0044090000 0.0000080000 0.0000070000 0.0014220000 34896757 96830484 509673472 4.0217981339 3.9715573788 4.0391659737 124 1311867722.7449109554 0.0754863322 0.0415206106 0.0778290480 0.0055611366 0.0065020000 0.0004990000 0.0037320000 0.0000020000 0.0000110000 0.0012010000 34900037 96830484 509673472 4.0239086151 3.9710664749 4.0391044617 125 1311867722.7770080566 0.0739993080 0.0417804402 0.0778290480 0.0055999748 0.0073140000 0.0004120000 0.0042420000 0.0000050000 0.0000050000 0.0019530000 34903765 96830484 509673472 4.0217685699 3.9712188244 4.0390334129 126 1311867722.8162860870 0.0742163733 0.0420378682 0.0778290480 0.0055778225 0.0061810000 0.0003770000 0.0041640000 0.0000000000 0.0000030000 0.0010860000 34907549 96830484 509673472 4.0217175484 3.9711999893 4.0392723083 127 1311867722.8466939926 0.0792579055 0.0423309394 0.0792579055 0.0056081554 0.0074410000 0.0005540000 0.0039230000 0.0000100000 0.0000090000 0.0015470000 34911165 96830484 509673472 4.0256652832 3.9688062668 4.0406956673 128 1311867722.8819770813 0.0782383308 0.0426114659 0.0792579055 0.0055875040 0.0067830000 0.0004390000 0.0042590000 0.0000010000 0.0000060000 0.0011360000 34914949 96830484 509673472 4.0234398842 3.9681599140 4.0411162376 129 1311867722.9150629044 0.0793732330 0.0428964408 0.0793732330 0.0055877327 0.0072060000 0.0003820000 0.0041610000 0.0000040000 0.0000040000 0.0019400000 34930741 96830484 509673472 4.0250101089 3.9704558849 4.0417904854 130 1311867722.9485991001 0.0803096145 0.0431842344 0.0803096145 0.0056007564 0.0073920000 0.0004760000 0.0043730000 0.0000010000 0.0000070000 0.0012080000 34960125 96830484 509673472 4.0244445801 3.9676363468 4.0422201157 131 1311867722.9821140766 0.0829922557 0.0434881125 0.0829922557 0.0055810709 0.0076850000 0.0004780000 0.0044070000 0.0000080000 0.0000070000 0.0014610000 34963797 96830484 509673472 4.0259819031 3.9666936398 4.0441956520 132 1311867723.0147259235 0.0828212127 0.0437860905 0.0829922557 0.0055624308 0.0065590000 0.0004140000 0.0042180000 0.0000010000 0.0000050000 0.0011110000 34967469 96830484 509673472 4.0266947746 3.9689152241 4.0440754890 133 1311867723.0460629463 0.0864060298 0.0441065412 0.0864060298 0.0055797994 0.0057280000 0.0003780000 0.0028200000 0.0000030000 0.0000030000 0.0019370000 34971085 96830484 509673472 4.0285286903 3.9664385319 4.0458254814 134 1311867723.0845439434 0.0894558504 0.0444449689 0.0894558504 0.0055758106 0.0087320000 0.0005420000 0.0046410000 0.0000020000 0.0000140000 0.0016030000 34974925 96830484 509673472 4.0311713219 3.9655163288 4.0461897850 135 1311867723.1140980721 0.0904136449 0.0447854776 0.0904136449 0.0055573380 0.0069960000 0.0004330000 0.0042930000 0.0000070000 0.0000050000 0.0013490000 34978541 96830484 509673472 4.0314822197 3.9654593468 4.0469684601 136 1311867723.1505160332 0.0930988342 0.0451407228 0.0930988342 0.0055461027 0.0053700000 0.0004110000 0.0031840000 0.0000000000 0.0000040000 0.0010830000 34982325 96830484 509673472 4.0329403877 3.9637703896 4.0478096008 137 1311867723.1811029911 0.0944721177 0.0455008060 0.0944721177 0.0055276232 0.0082430000 0.0004920000 0.0043790000 0.0000070000 0.0000070000 0.0021380000 34985941 96830484 509673472 4.0332126617 3.9623823166 4.0482063293 138 1311867723.2201359272 0.0950719565 0.0458600172 0.0950719565 0.0055082218 0.0052060000 0.0003970000 0.0028660000 0.0000010000 0.0000050000 0.0010950000 34989781 96830484 509673472 4.0334825516 3.9624028206 4.0483283997 139 1311867723.2486810684 0.0990804136 0.0462428978 0.0990804136 0.0055059663 0.0049570000 0.0003800000 0.0024850000 0.0000040000 0.0000040000 0.0013200000 34993341 96830484 509673472 4.0371694565 3.9614384174 4.0490102768 140 1311867723.2846419811 0.0877512768 0.0465393862 0.0990804136 0.0055280035 0.0046490000 0.0003790000 0.0024810000 0.0000010000 0.0000040000 0.0010750000 34997125 96830484 509673472 4.0247650146 3.9618155956 4.0454459190 141 1311867723.3132460117 0.0896858498 0.0468453895 0.0990804136 0.0055131172 0.0072320000 0.0003810000 0.0041380000 0.0000040000 0.0000040000 0.0019730000 35000685 96830484 509673472 4.0262088776 3.9608733654 4.0459809303 142 1311867723.3499810696 0.0899734944 0.0471491086 0.0990804136 0.0055015566 0.0053490000 0.0003800000 0.0031450000 0.0000010000 0.0000040000 0.0011040000 35004525 96830484 509673472 4.0258078575 3.9608776569 4.0465502739 143 1311867723.3822429180 0.0915025398 0.0474592724 0.0990804136 0.0054885994 0.0045600000 0.0003760000 0.0021380000 0.0000040000 0.0000040000 0.0013330000 35008253 96830484 509673472 4.0272989273 3.9606471062 4.0466923714 144 1311867723.4193739891 0.0924100578 0.0477714306 0.0990804136 0.0055003285 0.0046330000 0.0003710000 0.0024680000 0.0000000000 0.0000040000 0.0010880000 35012037 96830484 509673472 4.0277271271 3.9599046707 4.0478935242 145 1311867723.4455900192 0.0910805762 0.0480701144 0.0990804136 0.0054883785 0.0058780000 0.0003770000 0.0028060000 0.0000040000 0.0000040000 0.0019740000 35015541 96830484 509673472 4.0265474319 3.9608535767 4.0471878052 146 1311867723.4825348854 0.0937340036 0.0483828808 0.0990804136 0.0054807135 0.0046560000 0.0003730000 0.0024800000 0.0000000000 0.0000040000 0.0010920000 35019381 96830484 509673472 4.0278825760 3.9599990845 4.0484938622 147 1311867723.5147960186 0.0958171561 0.0487055629 0.0990804136 0.0054640932 0.0065480000 0.0004270000 0.0039060000 0.0000030000 0.0000030000 0.0013460000 35022997 96830484 509673472 4.0294294357 3.9596352577 4.0493249893 148 1311867723.5451340675 0.0960451141 0.0490254247 0.0990804136 0.0054472253 0.0095340000 0.0005650000 0.0046190000 0.0000020000 0.0000160000 0.0016520000 35026669 96830484 509673472 4.0289473534 3.9595396519 4.0497169495 149 1311867723.5809938908 0.0987044573 0.0493588411 0.0990804136 0.0054373249 0.0063370000 0.0004360000 0.0026100000 0.0000070000 0.0000070000 0.0021410000 35030453 96830484 509673472 4.0307531357 3.9585576057 4.0506172180 150 1311867723.6132669449 0.1005123183 0.0496998643 0.1005123183 0.0054234134 0.0055690000 0.0004050000 0.0031930000 0.0000000000 0.0000050000 0.0011160000 35034181 96830484 509673472 4.0327286720 3.9590139389 4.0509438515 151 1311867723.6453940868 0.0995262563 0.0500298404 0.1005123183 0.0054063000 0.0074770000 0.0005620000 0.0034400000 0.0000140000 0.0000130000 0.0016120000 35037797 96830484 509673472 4.0321993828 3.9601440430 4.0501279831 152 1311867723.6809489727 0.1013758406 0.0503676430 0.1013758406 0.0053920446 0.0059540000 0.0004360000 0.0032230000 0.0000000000 0.0000060000 0.0011730000 35041581 96830484 509673472 4.0331716537 3.9586770535 4.0507979393 153 1311867723.7130429745 0.1039318442 0.0507177358 0.1039318442 0.0053761162 0.0083990000 0.0004780000 0.0043490000 0.0000080000 0.0000070000 0.0021570000 35045253 96830484 509673472 4.0351424217 3.9580292702 4.0519495010 154 1311867723.7471990585 0.1045510992 0.0510673031 0.1045510992 0.0053605729 0.0065870000 0.0004010000 0.0041780000 0.0000000000 0.0000040000 0.0011280000 35048981 96830484 509673472 4.0359497070 3.9584870338 4.0514483452 155 1311867723.7809250355 0.1058502197 0.0514207413 0.1058502197 0.0053475515 0.0065940000 0.0003830000 0.0041320000 0.0000040000 0.0000030000 0.0013590000 35052709 96830484 509673472 4.0364274979 3.9570546150 4.0511875153 156 1311867723.8157649040 0.1078812778 0.0517826678 0.1078812778 0.0053365687 0.0075560000 0.0004950000 0.0044260000 0.0000010000 0.0000110000 0.0013900000 35056437 96830484 509673472 4.0380215645 3.9564542770 4.0510048866 157 1311867723.8468959332 0.1085045636 0.0521439538 0.1085045636 0.0053211154 0.0062090000 0.0004170000 0.0028900000 0.0000060000 0.0000060000 0.0020540000 35060109 96830484 509673472 4.0395693779 3.9583084583 4.0503721237 158 1311867723.8826351166 0.1075213850 0.0524944438 0.1085045636 0.0053146592 0.0078930000 0.0005760000 0.0028760000 0.0000020000 0.0000150000 0.0016660000 35063837 96830484 509673472 4.0377683640 3.9571022987 4.0495357513 159 1311867723.9172909260 0.1085619479 0.0528470696 0.1085619479 0.0053080082 0.0095710000 0.0005830000 0.0043070000 0.0000140000 0.0000160000 0.0019030000 35067453 96830484 509673472 4.0388836861 3.9577620029 4.0497975349 160 1311867723.9490020275 0.1113756150 0.0532128730 0.1113756150 0.0052963677 0.0084090000 0.0005620000 0.0045600000 0.0000020000 0.0000100000 0.0013940000 35071069 96830484 509673472 4.0420250893 3.9586858749 4.0503821373 161 1311867723.9839010239 0.1131952778 0.0535854346 0.1131952778 0.0052940729 0.0065790000 0.0004180000 0.0028680000 0.0000060000 0.0000050000 0.0020990000 35074853 96830484 509673472 4.0429224968 3.9567751884 4.0505828857 162 1311867724.0132899284 0.1137482971 0.0539568103 0.1137482971 0.0052815009 0.0069710000 0.0004150000 0.0041960000 0.0000010000 0.0000060000 0.0011760000 35078413 96830484 509673472 4.0435466766 3.9571218491 4.0506811142 163 1311867724.0475380421 0.1164056882 0.0543399322 0.1164056882 0.0052704418 0.0058680000 0.0004010000 0.0031630000 0.0000060000 0.0000050000 0.0013720000 35082197 96830484 509673472 4.0463385582 3.9578814507 4.0516853333 164 1311867724.0824530125 0.1177277640 0.0547264434 0.1177277640 0.0052592923 0.0066130000 0.0004830000 0.0030170000 0.0000010000 0.0000100000 0.0013870000 35085925 96830484 509673472 4.0468635559 3.9567277431 4.0523338318 165 1311867724.1132431030 0.1160730645 0.0550982411 0.1177277640 0.0052447336 0.0060050000 0.0004110000 0.0025550000 0.0000060000 0.0000060000 0.0020320000 35089597 96830484 509673472 4.0456442833 3.9577665329 4.0510468483 166 1311867724.1547191143 0.1196651608 0.0554871984 0.1196651608 0.0052449613 0.0064830000 0.0005620000 0.0024810000 0.0000020000 0.0000150000 0.0015070000 35093549 96830484 509673472 4.0485758781 3.9572610855 4.0528225899 167 1311867724.1810541153 0.1212776601 0.0558811533 0.1212776601 0.0052339145 0.0062330000 0.0004370000 0.0032070000 0.0000070000 0.0000060000 0.0014210000 35097053 96830484 509673472 4.0495200157 3.9564697742 4.0539202690 168 1311867724.2139430046 0.1223195866 0.0562766202 0.1223195866 0.0052212118 0.0057640000 0.0004960000 0.0025320000 0.0000010000 0.0000100000 0.0012650000 35100781 96830484 509673472 4.0502071381 3.9560079575 4.0542283058 169 1311867724.2507870197 0.1215531603 0.0566628719 0.1223195866 0.0052107219 0.0096780000 0.0005580000 0.0045810000 0.0000100000 0.0000090000 0.0026710000 35104565 96830484 509673472 4.0497388840 3.9574115276 4.0535984039 170 1311867724.2855930328 0.1250316799 0.0570650413 0.1250316799 0.0052042434 0.0058630000 0.0004730000 0.0031970000 0.0000010000 0.0000050000 0.0011370000 35108293 96830484 509673472 4.0524907112 3.9563665390 4.0550289154 171 1311867724.3144888878 0.1283289939 0.0574817896 0.1283289939 0.0051948213 0.0066620000 0.0003880000 0.0041100000 0.0000050000 0.0000040000 0.0013440000 35111853 96830484 509673472 4.0549578667 3.9545881748 4.0558776855 172 1311867724.3517999649 0.1284594536 0.0578944504 0.1284594536 0.0051965081 0.0074590000 0.0005610000 0.0023690000 0.0000020000 0.0000140000 0.0016770000 35115749 96830484 509673472 4.0546131134 3.9547510147 4.0566139221 173 1311867724.3888330460 0.1282586753 0.0583011801 0.1284594536 0.0051880909 0.0097880000 0.0005780000 0.0035560000 0.0000140000 0.0000140000 0.0027460000 35119477 96830484 509673472 4.0548615456 3.9555399418 4.0556497574 174 1311867724.4160330296 0.1326001287 0.0587281855 0.1326001287 0.0051829924 0.0067970000 0.0005790000 0.0028320000 0.0000020000 0.0000100000 0.0014160000 35123037 96830484 509673472 4.0580439568 3.9534714222 4.0580935478 175 1311867724.4509639740 0.1337950081 0.0591571388 0.1337950081 0.0051700691 0.0062860000 0.0004210000 0.0031920000 0.0000060000 0.0000050000 0.0014490000 35126765 96830484 509673472 4.0589780807 3.9526982307 4.0576968193 176 1311867724.4830689430 0.1340896785 0.0595828918 0.1340896785 0.0051562599 0.0053590000 0.0004180000 0.0025270000 0.0000010000 0.0000060000 0.0011910000 35130437 96830484 509673472 4.0592656136 3.9526565075 4.0570621490 177 1311867724.5208630562 0.1344216615 0.0600057098 0.1344216615 0.0051429592 0.0076630000 0.0004020000 0.0041600000 0.0000060000 0.0000050000 0.0020630000 35134165 96830484 509673472 4.0588450432 3.9520566463 4.0573902130 178 1311867724.5523910522 0.1399739534 0.0604549695 0.1399739534 0.0051466815 0.0065570000 0.0004860000 0.0030170000 0.0000010000 0.0000100000 0.0014200000 35137893 96830484 509673472 4.0634107590 3.9499487877 4.0595602989 179 1311867724.5861799717 0.1404891461 0.0609020879 0.1404891461 0.0051417371 0.0060610000 0.0004160000 0.0032010000 0.0000060000 0.0000050000 0.0013840000 35141565 96830484 509673472 4.0627827644 3.9481294155 4.0600676537 180 1311867724.6193559170 0.1420590430 0.0613529598 0.1420590430 0.0051581173 0.0059090000 0.0003890000 0.0034740000 0.0000010000 0.0000050000 0.0011270000 35145237 96830484 509673472 4.0640406609 3.9478547573 4.0601820946 181 1311867724.6529819965 0.1439958662 0.0618095505 0.1439958662 0.0051473774 0.0084690000 0.0004790000 0.0042620000 0.0000080000 0.0000070000 0.0022120000 35148965 96830484 509673472 4.0658736229 3.9483766556 4.0604820251 182 1311867724.6818330288 0.1443939656 0.0622633110 0.1443939656 0.0051436914 0.0051540000 0.0004280000 0.0025070000 0.0000000000 0.0000050000 0.0011610000 35152525 96830484 509673472 4.0656008720 3.9470009804 4.0598974228 183 1311867724.7153129578 0.1449670196 0.0627152438 0.1449670196 0.0051417264 0.0049570000 0.0003820000 0.0023740000 0.0000040000 0.0000030000 0.0013660000 35156253 96830484 509673472 4.0656175613 3.9476277828 4.0607199669 184 1311867724.7518899441 0.1475158483 0.0631761167 0.1475158483 0.0051337783 0.0076010000 0.0004880000 0.0037030000 0.0000010000 0.0000100000 0.0014170000 35160037 96830484 509673472 4.0678262711 3.9485695362 4.0618658066 185 1311867724.7853860855 0.1498488933 0.0636446182 0.1498488933 0.0051249659 0.0061030000 0.0004130000 0.0025350000 0.0000060000 0.0000060000 0.0020960000 35163765 96830484 509673472 4.0687470436 3.9466862679 4.0633449554 186 1311867724.8179960251 0.1516279727 0.0641176470 0.1516279727 0.0051226640 0.0048340000 0.0003860000 0.0023740000 0.0000000000 0.0000040000 0.0011430000 35167437 96830484 509673472 4.0700335503 3.9462294579 4.0639152527 187 1311867724.8547580242 0.1512534767 0.0645836140 0.1516279727 0.0051271119 0.0093500000 0.0005620000 0.0039080000 0.0000140000 0.0000130000 0.0019290000 35171165 96830484 509673472 4.0697593689 3.9471380711 4.0632100105 188 1311867724.8830249310 0.1540414840 0.0650594537 0.1540414840 0.0051152385 0.0058810000 0.0004400000 0.0029200000 0.0000010000 0.0000080000 0.0012630000 35174725 96830484 509673472 4.0712532997 3.9457592964 4.0650887489 189 1311867724.9137279987 0.1574194133 0.0655481307 0.1574194133 0.0051291282 0.0059080000 0.0004100000 0.0025000000 0.0000180000 0.0000050000 0.0020400000 35178397 96830484 509673472 4.0731973648 3.9436399937 4.0667934418 190 1311867724.9535229206 0.1572725028 0.0660308906 0.1574194133 0.0051173432 0.0046230000 0.0003960000 0.0021600000 0.0000010000 0.0000050000 0.0011380000 35182237 96830484 509673472 4.0733642578 3.9445950985 4.0661931038 191 1311867724.9843940735 0.1582014263 0.0665134588 0.1582014263 0.0051044296 0.0093810000 0.0005660000 0.0045830000 0.0000160000 0.0000150000 0.0019690000 35185909 96830484 509673472 4.0739288330 3.9442887306 4.0667343140 192 1311867725.0159099102 0.1616497040 0.0670089601 0.1616497040 0.0051060621 0.0074140000 0.0004740000 0.0043150000 0.0000010000 0.0000080000 0.0012770000 35189525 96830484 509673472 4.0754170418 3.9412977695 4.0695519447 193 1311867725.0518310070 0.1593548805 0.0674874364 0.1616497040 0.0050940315 0.0069150000 0.0004020000 0.0035030000 0.0000050000 0.0000050000 0.0020400000 35193309 96830484 509673472 4.0737948418 3.9424455166 4.0676078796 194 1311867725.0813930035 0.1604963690 0.0679668639 0.1616497040 0.0050811321 0.0053030000 0.0003830000 0.0030080000 0.0000010000 0.0000040000 0.0011110000 35196925 96830484 509673472 4.0743851662 3.9422783852 4.0684013367 195 1311867725.1151220798 0.1623461246 0.0684508601 0.1623461246 0.0050718284 0.0062460000 0.0004730000 0.0026550000 0.0000080000 0.0000070000 0.0015340000 35200653 96830484 509673472 4.0754508972 3.9405100346 4.0688180923 196 1311867725.1557130814 0.1616059840 0.0689261413 0.1623461246 0.0050608814 0.0068750000 0.0005620000 0.0028340000 0.0000010000 0.0000100000 0.0014380000 35204549 96830484 509673472 4.0748882294 3.9414007664 4.0680270195 197 1311867725.1843969822 0.1668050885 0.0694229888 0.1668050885 0.0050614537 0.0078410000 0.0004480000 0.0042300000 0.0000060000 0.0000060000 0.0020650000 35208109 96830484 509673472 4.0775570869 3.9385538101 4.0723528862 198 1311867725.2150099277 0.1684372872 0.0699230610 0.1684372872 0.0050520377 0.0055450000 0.0003900000 0.0031570000 0.0000000000 0.0000040000 0.0011320000 35211781 96830484 509673472 4.0776867867 3.9361722469 4.0733585358 199 1311867725.2516539097 0.1654639691 0.0704031661 0.1684372872 0.0050407145 0.0072320000 0.0004820000 0.0029930000 0.0000100000 0.0000100000 0.0017010000 35215621 96830484 509673472 4.0766205788 3.9392092228 4.0700111389 200 1311867725.2816410065 0.1654330641 0.0708783155 0.1684372872 0.0050317048 0.0076940000 0.0004720000 0.0043670000 0.0000010000 0.0000070000 0.0012900000 35219237 96830484 509673472 4.0765304565 3.9391365051 4.0696396828 201 1311867725.3196239471 0.1713138223 0.0713779947 0.1713138223 0.0050316319 0.0069750000 0.0004160000 0.0034980000 0.0000050000 0.0000050000 0.0020770000 35223021 96830484 509673472 4.0794310570 3.9355704784 4.0742573738 202 1311867725.3517010212 0.1709508300 0.0718709295 0.1713138223 0.0050219081 0.0054380000 0.0003820000 0.0031150000 0.0000000000 0.0000040000 0.0011330000 35226637 96830484 509673472 4.0789918900 3.9361894131 4.0743923187 203 1311867725.3837459087 0.1803177297 0.0724051502 0.1803177297 0.0050732041 0.0077920000 0.0004360000 0.0042530000 0.0000080000 0.0000070000 0.0015510000 35230197 96830484 509673472 4.0833697319 3.9313197136 4.0838804245 204 1311867725.4178969860 0.1752552688 0.0729093174 0.1803177297 0.0050649631 0.0077170000 0.0004730000 0.0043650000 0.0000010000 0.0000080000 0.0012960000 35233981 96830484 509673472 4.0816020966 3.9346771240 4.0775513649 205 1311867725.4492449760 0.1728085428 0.0733966307 0.1803177297 0.0050597132 0.0060130000 0.0004230000 0.0024990000 0.0000050000 0.0000050000 0.0020980000 35237597 96830484 509673472 4.0797677040 3.9361600876 4.0754761696 206 1311867725.4836509228 0.1872241795 0.0739491917 0.1872241795 0.0051447163 0.0064540000 0.0003910000 0.0041110000 0.0000000000 0.0000030000 0.0011410000 35241325 96830484 509673472 4.0867271423 3.9289305210 4.0888075829 207 1311867725.5178139210 0.1967747062 0.0745425516 0.1967747062 0.0051572975 0.0050110000 0.0003800000 0.0024360000 0.0000030000 0.0000040000 0.0013830000 35245165 96830484 509673472 4.0905156136 3.9237012863 4.0980563164 208 1311867725.5497610569 0.2020856887 0.0751557398 0.2020856887 0.0051550769 0.0063790000 0.0003840000 0.0040530000 0.0000010000 0.0000030000 0.0011350000 35248781 96830484 509673472 4.0926690102 3.9208586216 4.1024580002 209 1311867725.5815479755 0.1955138147 0.0757316157 0.2020856887 0.0051804295 0.0072790000 0.0003810000 0.0040510000 0.0000040000 0.0000040000 0.0020400000 35252453 96830484 509673472 4.0908012390 3.9258589745 4.0943679810 210 1311867725.6194949150 0.2064694017 0.0763541766 0.2064694017 0.0051874503 0.0089550000 0.0005690000 0.0045980000 0.0000020000 0.0000150000 0.0016680000 35256293 96830484 509673472 4.0957264900 3.9197821617 4.1037650108 211 1311867725.6515610218 0.2168832719 0.0770201913 0.2168832719 0.0052944527 0.0072200000 0.0004460000 0.0041810000 0.0000060000 0.0000050000 0.0014710000 35259965 96830484 509673472 4.0983710289 3.9132575989 4.1145992279 212 1311867725.6834650040 0.2122222185 0.0776579367 0.2168832719 0.0052929311 0.0049280000 0.0004040000 0.0024620000 0.0000000000 0.0000050000 0.0011520000 35263637 96830484 509673472 4.0973787308 3.9175481796 4.1089410782 213 1311867725.7201809883 0.2162655294 0.0783086766 0.2168832719 0.0052857050 0.0066790000 0.0003850000 0.0034070000 0.0000030000 0.0000030000 0.0020500000 35267421 96830484 509673472 4.0990962982 3.9152033329 4.1115994453 214 1311867725.7515070438 0.2224049717 0.0789820238 0.2224049717 0.0052815899 0.0074160000 0.0004860000 0.0039910000 0.0000010000 0.0000080000 0.0013050000 35271093 96830484 509673472 4.1010522842 3.9112861156 4.1169681549 215 1311867725.7835409641 0.1844969243 0.0794727907 0.2224049717 0.0055149491 0.0063460000 0.0004070000 0.0035090000 0.0000060000 0.0000040000 0.0014120000 35274709 96830484 509673472 4.0741200447 3.9253044128 4.0916833878 216 1311867725.8211829662 0.1932563186 0.0799995663 0.2224049717 0.0055272347 0.0058780000 0.0003920000 0.0034550000 0.0000010000 0.0000040000 0.0011460000 35278605 96830484 509673472 4.0772519112 3.9198305607 4.0994648933 217 1311867725.8517971039 0.1929133236 0.0805199062 0.2224049717 0.0055205884 0.0073660000 0.0005210000 0.0026870000 0.0000100000 0.0000100000 0.0024430000 35282277 96830484 509673472 4.0767045021 3.9197885990 4.0986442566 218 1311867725.8837900162 0.1971112043 0.0810547287 0.2224049717 0.0055332525 0.0069930000 0.0004320000 0.0042070000 0.0000010000 0.0000060000 0.0011880000 35285837 96830484 509673472 4.0785789490 3.9191308022 4.1025886536 219 1311867725.9192690849 0.2010922283 0.0816028451 0.2224049717 0.0055285360 0.0074140000 0.0004940000 0.0036810000 0.0000080000 0.0000070000 0.0015910000 35289621 96830484 509673472 4.0807118416 3.9173676968 4.1046929359 220 1311867725.9511859417 0.2078801692 0.0821768330 0.2224049717 0.0055229616 0.0067580000 0.0004160000 0.0041700000 0.0000010000 0.0000050000 0.0011680000 35293293 96830484 509673472 4.0828070641 3.9129648209 4.1106672287 221 1311867725.9829630852 0.2091415524 0.0827513340 0.2224049717 0.0055124316 0.0074160000 0.0003880000 0.0041150000 0.0000040000 0.0000030000 0.0020650000 35296909 96830484 509673472 4.0838646889 3.9139018059 4.1113729477 222 1311867726.0219368935 0.2138772309 0.0833419912 0.2224049717 0.0055057777 0.0071240000 0.0003820000 0.0046220000 0.0000010000 0.0000040000 0.0011520000 35300805 96830484 509673472 4.0857071877 3.9113659859 4.1145129204 223 1311867726.0504179001 0.2092882842 0.0839067727 0.2224049717 0.0055067782 0.0067380000 0.0004290000 0.0040920000 0.0000030000 0.0000050000 0.0013730000 35304309 96830484 509673472 4.0835261345 3.9132561684 4.1092929840 224 1311867726.0845088959 0.2176592648 0.0845038821 0.2224049717 0.0055207701 0.0055020000 0.0003900000 0.0031240000 0.0000000000 0.0000030000 0.0011450000 35308093 96830484 509673472 4.0862174034 3.9090123177 4.1177082062 225 1311867726.1199669838 0.2178399563 0.0850964869 0.2224049717 0.0055102523 0.0052930000 0.0003860000 0.0020210000 0.0000040000 0.0000030000 0.0020530000 35311821 96830484 509673472 4.0861639977 3.9087224007 4.1170935631 226 1311867726.1506989002 0.2200970203 0.0856938343 0.2224049717 0.0055020789 0.0093470000 0.0005730000 0.0046680000 0.0000020000 0.0000140000 0.0017390000 35315493 96830484 509673472 4.0862407684 3.9066851139 4.1189484596 227 1311867726.1824700832 0.2157151550 0.0862666155 0.2224049717 0.0054914202 0.0073870000 0.0004470000 0.0042790000 0.0000070000 0.0000060000 0.0014620000 35319165 96830484 509673472 4.0843420029 3.9096434116 4.1147913933 228 1311867726.2198660374 0.2199096233 0.0868527690 0.2224049717 0.0054874068 0.0049950000 0.0004030000 0.0025020000 0.0000010000 0.0000050000 0.0011630000 35322949 96830484 509673472 4.0864143372 3.9078249931 4.1175966263 229 1311867726.2506690025 0.2279288322 0.0874688217 0.2279288322 0.0054899571 0.0060560000 0.0003830000 0.0027890000 0.0000040000 0.0000030000 0.0020420000 35326621 96830484 509673472 4.0886073112 3.9024150372 4.1248974800 230 1311867726.2845950127 0.2249300033 0.0880664790 0.2279288322 0.0054797758 0.0063370000 0.0003800000 0.0040050000 0.0000010000 0.0000040000 0.0011260000 35330293 96830484 509673472 4.0876784325 3.9042515755 4.1212973595 231 1311867726.3187239170 0.2311386168 0.0886858389 0.2311386168 0.0054758362 0.0100890000 0.0005850000 0.0046450000 0.0000140000 0.0000130000 0.0019620000 35334077 96830484 509673472 4.0902843475 3.9017560482 4.1266918182 232 1311867726.3524029255 0.2295562923 0.0892930392 0.2311386168 0.0054682431 0.0059620000 0.0004580000 0.0029150000 0.0000010000 0.0000060000 0.0012150000 35337805 96830484 509673472 4.0905294418 3.9036149979 4.1241121292 233 1311867726.3835608959 0.2323373854 0.0899069634 0.2323373854 0.0054577945 0.0063230000 0.0004240000 0.0028180000 0.0000040000 0.0000050000 0.0020900000 35341421 96830484 509673472 4.0909519196 3.9016354084 4.1262679100 234 1311867726.4218099117 0.2301542908 0.0905063109 0.2323373854 0.0054490168 0.0064270000 0.0003910000 0.0040880000 0.0000010000 0.0000030000 0.0011260000 35345317 96830484 509673472 4.0912122726 3.9045128822 4.1231374741 235 1311867726.4504199028 0.2311124206 0.0911046348 0.2323373854 0.0054374875 0.0049710000 0.0003810000 0.0023400000 0.0000030000 0.0000040000 0.0013970000 35348877 96830484 509673472 4.0911693573 3.9041488171 4.1240429878 236 1311867726.4843189716 0.2337199152 0.0917089368 0.2337199152 0.0054287435 0.0057490000 0.0003850000 0.0034410000 0.0000010000 0.0000040000 0.0011220000 35352605 96830484 509673472 4.0916428566 3.9025132656 4.1263718605 237 1311867726.5207901001 0.2371811718 0.0923227437 0.2371811718 0.0054233678 0.0112300000 0.0005740000 0.0044860000 0.0000140000 0.0000150000 0.0028540000 35356389 96830484 509673472 4.0923428535 3.9000685215 4.1295304298 238 1311867726.5524380207 0.2376661599 0.0929334304 0.2376661599 0.0054184100 0.0054130000 0.0004380000 0.0023470000 0.0000010000 0.0000080000 0.0012500000 35360061 96830484 509673472 4.0925049782 3.9004085064 4.1298971176 239 1311867726.5874860287 0.2343699485 0.0935252150 0.2376661599 0.0054145216 0.0057110000 0.0004110000 0.0028470000 0.0000040000 0.0000040000 0.0014020000 35363845 96830484 509673472 4.0914878845 3.9030070305 4.1264305115 240 1311867726.6204600334 0.2365313172 0.0941210737 0.2376661599 0.0054174721 0.0045110000 0.0003910000 0.0021540000 0.0000000000 0.0000030000 0.0011290000 35367517 96830484 509673472 4.0928564072 3.9021933079 4.1282405853 241 1311867726.6509370804 0.2330003828 0.0946973364 0.2376661599 0.0054224249 0.0090020000 0.0005720000 0.0028750000 0.0000150000 0.0000140000 0.0028090000 35371133 96830484 509673472 4.0919532776 3.9036967754 4.1235733032 242 1311867726.6916151047 0.2359132916 0.0952808734 0.2376661599 0.0054168343 0.0061190000 0.0004740000 0.0026410000 0.0000010000 0.0000070000 0.0013040000 35375085 96830484 509673472 4.0927114487 3.9020249844 4.1267247200 243 1311867726.7201170921 0.2367620915 0.0958631007 0.2376661599 0.0054068997 0.0051940000 0.0004120000 0.0021920000 0.0000050000 0.0000040000 0.0014060000 35378589 96830484 509673472 4.0938143730 3.9023456573 4.1272268295 244 1311867726.7513859272 0.2322483212 0.0964220565 0.2376661599 0.0054006557 0.0055860000 0.0003910000 0.0031470000 0.0000010000 0.0000040000 0.0011300000 35382261 96830484 509673472 4.0916633606 3.9036664963 4.1228585243 245 1311867726.7880010605 0.2282819003 0.0969602599 0.2376661599 0.0053939386 0.0102740000 0.0005650000 0.0046850000 0.0000150000 0.0000140000 0.0027180000 35386101 96830484 509673472 4.0900793076 3.9053204060 4.1192364693 246 1311867726.8198299408 0.2312535942 0.0975061678 0.2376661599 0.0053876807 0.0065260000 0.0004420000 0.0035870000 0.0000010000 0.0000070000 0.0011970000 35389717 96830484 509673472 4.0914669037 3.9038670063 4.1221570969 247 1311867726.8500390053 0.2319788784 0.0980505917 0.2376661599 0.0053771035 0.0052900000 0.0004080000 0.0025070000 0.0000040000 0.0000040000 0.0013920000 35393333 96830484 509673472 4.0917754173 3.9030771255 4.1227545738 248 1311867726.8927390575 0.2272695750 0.0985716360 0.2376661599 0.0053697231 0.0064710000 0.0003810000 0.0041450000 0.0000000000 0.0000030000 0.0011260000 35397341 96830484 509673472 4.0904984474 3.9057035446 4.1179327965 249 1311867726.9216780663 0.2290159017 0.0990955086 0.2376661599 0.0053608246 0.0102480000 0.0005720000 0.0046580000 0.0000140000 0.0000140000 0.0027260000 35400901 96830484 509673472 4.0908041000 3.9048795700 4.1205391884 250 1311867726.9543499947 0.2233144492 0.0995923843 0.2376661599 0.0053860535 0.0062020000 0.0004520000 0.0032530000 0.0000010000 0.0000060000 0.0012040000 35404573 96830484 509673472 4.0897488594 3.9084796906 4.1143946648 251 1311867726.9902989864 0.2238793075 0.1000875513 0.2376661599 0.0053806670 0.0075340000 0.0004070000 0.0043590000 0.0000060000 0.0000040000 0.0016590000 35408301 96830484 509673472 4.0893406868 3.9076182842 4.1157512665 252 1311867727.0208179951 0.2255541086 0.1005854345 0.2376661599 0.0053707069 0.0065600000 0.0004320000 0.0041400000 0.0000000000 0.0000030000 0.0011260000 35411973 96830484 509673472 4.0900721550 3.9064152241 4.1173095703 253 1311867727.0536949635 0.2222996801 0.1010665185 0.2376661599 0.0053663749 0.0060890000 0.0003830000 0.0028150000 0.0000030000 0.0000040000 0.0020530000 35415645 96830484 509673472 4.0893225670 3.9081370831 4.1141114235 254 1311867727.0911629200 0.2229707688 0.1015464565 0.2376661599 0.0053570814 0.0082700000 0.0005680000 0.0039560000 0.0000020000 0.0000110000 0.0014510000 35419485 96830484 509673472 4.0891661644 3.9073743820 4.1157050133 255 1311867727.1196689606 0.2188908309 0.1020066305 0.2376661599 0.0053495464 0.0054280000 0.0004240000 0.0022270000 0.0000060000 0.0000060000 0.0014580000 35422933 96830484 509673472 4.0876197815 3.9091258049 4.1117954254 256 1311867727.1514298916 0.2148566991 0.1024474511 0.2376661599 0.0053452704 0.0049600000 0.0003990000 0.0025140000 0.0000000000 0.0000040000 0.0011150000 35426661 96830484 509673472 4.0858273506 3.9110746384 4.1087894440 257 1311867727.1904149055 0.2162623405 0.1028903106 0.2376661599 0.0053555221 0.0089530000 0.0004940000 0.0037710000 0.0000110000 0.0000090000 0.0024430000 35455021 96830484 509673472 4.0863442421 3.9099972248 4.1109261513 258 1311867727.2208960056 0.2131550312 0.1033176932 0.2376661599 0.0053529927 0.0070840000 0.0004260000 0.0042650000 0.0000000000 0.0000050000 0.0011610000 35509893 96830484 509673472 4.0848340988 3.9120481014 4.1094174385 259 1311867727.2544560432 0.2079332471 0.1037216143 0.2376661599 0.0053590378 0.0068430000 0.0003930000 0.0041610000 0.0000040000 0.0000030000 0.0013860000 35513565 96830484 509673472 4.0829944611 3.9142351151 4.1039109230 260 1311867727.2870850563 0.2086506039 0.1041251873 0.2376661599 0.0053507311 0.0077000000 0.0004850000 0.0043660000 0.0000010000 0.0000070000 0.0012980000 35517293 96830484 509673472 4.0829720497 3.9133992195 4.1054902077 261 1311867727.3192501068 0.2088547349 0.1045264499 0.2376661599 0.0053409621 0.0076800000 0.0004000000 0.0041800000 0.0000040000 0.0000050000 0.0020320000 35520965 96830484 509673472 4.0835719109 3.9127564430 4.1054983139 262 1311867727.3502039909 0.2047627121 0.1049090311 0.2376661599 0.0053397951 0.0059960000 0.0004830000 0.0023550000 0.0000010000 0.0000110000 0.0013860000 35524581 96830484 509673472 4.0816049576 3.9136579037 4.1018657684 263 1311867727.3894629478 0.2037798017 0.1052849656 0.2376661599 0.0053310457 0.0052700000 0.0004140000 0.0022100000 0.0000040000 0.0000060000 0.0014190000 35528365 96830484 509673472 4.0810661316 3.9146244526 4.1027832031 264 1311867727.4182970524 0.2017963529 0.1056505390 0.2376661599 0.0053217970 0.0075560000 0.0005640000 0.0031870000 0.0000010000 0.0000100000 0.0014270000 35531981 96830484 509673472 4.0803852081 3.9152626991 4.1020841599 265 1311867727.4495580196 0.1977885664 0.1059982297 0.2376661599 0.0053172838 0.0073110000 0.0004830000 0.0030440000 0.0000080000 0.0000070000 0.0021980000 35535541 96830484 509673472 4.0786242485 3.9166941643 4.0988740921 266 1311867727.4858360291 0.1985428780 0.1063461419 0.2376661599 0.0053309629 0.0066910000 0.0004110000 0.0041930000 0.0000000000 0.0000040000 0.0011420000 35539381 96830484 509673472 4.0779905319 3.9165246487 4.1020650864 267 1311867727.5198891163 0.1947470456 0.1066772314 0.2376661599 0.0053360550 0.0051030000 0.0003860000 0.0024850000 0.0000040000 0.0000040000 0.0013720000 35543053 96830484 509673472 4.0772609711 3.9184741974 4.0977287292 268 1311867727.5494980812 0.1938658357 0.1070025620 0.2376661599 0.0053320179 0.0064360000 0.0003830000 0.0040240000 0.0000010000 0.0000030000 0.0011130000 35546669 96830484 509673472 4.0762586594 3.9174976349 4.0974082947 269 1311867727.5905909538 0.1911372989 0.1073153306 0.2376661599 0.0053303175 0.0105170000 0.0005780000 0.0046580000 0.0000150000 0.0000130000 0.0028120000 35550621 96830484 509673472 4.0755505562 3.9186129570 4.0950694084 270 1311867727.6176431179 0.1899964958 0.1076215571 0.2376661599 0.0053308335 0.0057400000 0.0004390000 0.0026000000 0.0000010000 0.0000060000 0.0012120000 35554125 96830484 509673472 4.0737485886 3.9179639816 4.0953145027 271 1311867727.6497650146 0.1879402250 0.1079179360 0.2376661599 0.0053262749 0.0069460000 0.0003980000 0.0041810000 0.0000050000 0.0000050000 0.0013790000 35557797 96830484 509673472 4.0727515221 3.9184870720 4.0935645103 272 1311867727.6884338856 0.1830251068 0.1081940653 0.2376661599 0.0053249375 0.0048290000 0.0003770000 0.0024910000 0.0000000000 0.0000030000 0.0010980000 35561469 96830484 509673472 4.0711169243 3.9213631153 4.0888071060 273 1311867727.7184689045 0.1806306839 0.1084594009 0.2376661599 0.0053164892 0.0092110000 0.0005970000 0.0028980000 0.0000150000 0.0000130000 0.0027910000 35565141 96830484 509673472 4.0697522163 3.9219739437 4.0862393379 274 1311867727.7523269653 0.1763135046 0.1087070436 0.2376661599 0.0053106754 0.0056400000 0.0004980000 0.0019910000 0.0000010000 0.0000070000 0.0012870000 35568869 96830484 509673472 4.0661911964 3.9222292900 4.0828127861 275 1311867727.7856590748 0.1752357185 0.1089489660 0.2376661599 0.0053048553 0.0070800000 0.0004290000 0.0041030000 0.0000080000 0.0000050000 0.0014130000 35572541 96830484 509673472 4.0650396347 3.9229295254 4.0828180313 276 1311867727.8181309700 0.1746180952 0.1091868977 0.2376661599 0.0053016592 0.0048950000 0.0003800000 0.0024940000 0.0000010000 0.0000030000 0.0011020000 35576269 96830484 509673472 4.0642418861 3.9233880043 4.0828251839 277 1311867727.8548729420 0.1740632355 0.1094211083 0.2376661599 0.0052935915 0.0082840000 0.0005620000 0.0028770000 0.0000160000 0.0000130000 0.0024070000 35580053 96830484 509673472 4.0639743805 3.9234347343 4.0821146965 278 1311867727.8882629871 0.1714897454 0.1096443767 0.2376661599 0.0052849529 0.0051640000 0.0004110000 0.0022270000 0.0000010000 0.0000060000 0.0011970000 35583781 96830484 509673472 4.0629148483 3.9248991013 4.0800294876 279 1311867727.9193139076 0.1707884967 0.1098635313 0.2376661599 0.0052781272 0.0052590000 0.0003880000 0.0025060000 0.0000040000 0.0000040000 0.0013680000 35587397 96830484 509673472 4.0620083809 3.9251365662 4.0805215836 280 1311867727.9556980133 0.1705573648 0.1100802950 0.2376661599 0.0052697568 0.0090180000 0.0005580000 0.0046310000 0.0000020000 0.0000090000 0.0014400000 35591181 96830484 509673472 4.0624876022 3.9250550270 4.0796504021 281 1311867727.9869389534 0.1702672839 0.1102944836 0.2376661599 0.0052610287 0.0060320000 0.0004210000 0.0022280000 0.0000060000 0.0000060000 0.0020840000 35594909 96830484 509673472 4.0623722076 3.9251966476 4.0795998573 282 1311867728.0179219246 0.1683235765 0.1105002605 0.2376661599 0.0052612821 0.0066800000 0.0003850000 0.0041690000 0.0000010000 0.0000040000 0.0011190000 35598469 96830484 509673472 4.0618333817 3.9263927937 4.0780658722 283 1311867728.0555219650 0.1656919122 0.1106952840 0.2376661599 0.0052551018 0.0072630000 0.0004780000 0.0033980000 0.0000100000 0.0000090000 0.0015110000 35602309 96830484 509673472 4.0599884987 3.9272248745 4.0769233704 284 1311867728.0892169476 0.1644311845 0.1108844949 0.2376661599 0.0052470450 0.0068740000 0.0004010000 0.0042140000 0.0000010000 0.0000050000 0.0011220000 35606037 96830484 509673472 4.0597701073 3.9282937050 4.0761380196 285 1311867728.1177880764 0.1618637890 0.1110633696 0.2376661599 0.0052443820 0.0055020000 0.0003800000 0.0021680000 0.0000040000 0.0000040000 0.0020120000 35609653 96830484 509673472 4.0584774017 3.9292719364 4.0741000175 286 1311867728.1556169987 0.1618498564 0.1112409447 0.2376661599 0.0052381145 0.0094550000 0.0005590000 0.0047000000 0.0000010000 0.0000170000 0.0017100000 35613437 96830484 509673472 4.0585694313 3.9290742874 4.0742688179 287 1311867728.1882989407 0.1603465229 0.1114120443 0.2376661599 0.0052292902 0.0054080000 0.0004490000 0.0021640000 0.0000060000 0.0000050000 0.0014440000 35617221 96830484 509673472 4.0582656860 3.9296066761 4.0724177361 288 1311867728.2182519436 0.1594679058 0.1115789050 0.2376661599 0.0052229281 0.0047210000 0.0004020000 0.0021930000 0.0000010000 0.0000050000 0.0011280000 35620837 96830484 509673472 4.0573115349 3.9295935631 4.0721759796 289 1311867728.2558999062 0.1575443149 0.1117379548 0.2376661599 0.0052146052 0.0101930000 0.0005630000 0.0046780000 0.0000150000 0.0000140000 0.0027620000 35624621 96830484 509673472 4.0564613342 3.9303367138 4.0705204010 290 1311867728.2875900269 0.1390028298 0.1118319716 0.2376661599 0.0052995876 0.0055890000 0.0004450000 0.0026000000 0.0000010000 0.0000060000 0.0011990000 35628293 96830484 509673472 4.0365128517 3.9322264194 4.0650291443 291 1311867728.3226509094 0.1384498775 0.1119234421 0.2376661599 0.0053053467 0.0053590000 0.0004050000 0.0025540000 0.0000050000 0.0000040000 0.0013860000 35632077 96830484 509673472 4.0370683670 3.9333164692 4.0645976067 292 1311867728.3597300053 0.1374299973 0.1120107933 0.2376661599 0.0053056992 0.0045640000 0.0003790000 0.0021620000 0.0000010000 0.0000040000 0.0011130000 35635805 96830484 509673472 4.0359740257 3.9326045513 4.0640106201 293 1311867728.3861401081 0.1378157586 0.1120988649 0.2376661599 0.0052968563 0.0064920000 0.0003790000 0.0031560000 0.0000040000 0.0000030000 0.0020260000 35639365 96830484 509673472 4.0366272926 3.9326791763 4.0640954971 294 1311867728.4175701141 0.1377465278 0.1121861018 0.2376661599 0.0053278823 0.0045510000 0.0003720000 0.0021550000 0.0000010000 0.0000040000 0.0011110000 35643037 96830484 509673472 4.0360202789 3.9320759773 4.0638604164 295 1311867728.4568250179 0.1356786042 0.1122657374 0.2376661599 0.0053206013 0.0091350000 0.0005600000 0.0028820000 0.0000140000 0.0000160000 0.0019950000 35646877 96830484 509673472 4.0348834991 3.9330074787 4.0621705055 296 1311867728.4875330925 0.1338359863 0.1123386099 0.2376661599 0.0053152344 0.0067420000 0.0004710000 0.0033220000 0.0000010000 0.0000070000 0.0012790000 35650493 96830484 509673472 4.0344862938 3.9345746040 4.0606551170 297 1311867728.5187420845 0.1336646080 0.1124104146 0.2376661599 0.0053092403 0.0058150000 0.0004010000 0.0022040000 0.0000050000 0.0000050000 0.0020570000 35654109 96830484 509673472 4.0343918800 3.9340260029 4.0599422455 298 1311867728.5550920963 0.1323416829 0.1124772980 0.2376661599 0.0053027091 0.0049540000 0.0003850000 0.0024970000 0.0000000000 0.0000030000 0.0011150000 35657949 96830484 509673472 4.0334777832 3.9347589016 4.0595436096 299 1311867728.5878560543 0.1328959316 0.1125455878 0.2376661599 0.0052963812 0.0054680000 0.0003720000 0.0028220000 0.0000030000 0.0000030000 0.0013610000 35661677 96830484 509673472 4.0346841812 3.9346809387 4.0588932037 300 1311867728.6187679768 0.1315227449 0.1126088450 0.2376661599 0.0052887656 0.0058590000 0.0003700000 0.0034820000 0.0000010000 0.0000030000 0.0011030000 35665237 96830484 509673472 4.0338578224 3.9352748394 4.0578250885 301 1311867728.6580820084 0.1322224736 0.1126740065 0.2376661599 0.0052809022 0.0096530000 0.0005610000 0.0025210000 0.0000140000 0.0000140000 0.0028150000 35669133 96830484 509673472 4.0342512131 3.9348855019 4.0583224297 302 1311867728.6893489361 0.1317266673 0.1127370948 0.2376661599 0.0052733241 0.0056580000 0.0004400000 0.0022840000 0.0000010000 0.0000080000 0.0012770000 35672805 96830484 509673472 4.0333495140 3.9343600273 4.0581107140 303 1311867728.7210168839 0.1310262382 0.1127974550 0.2376661599 0.0052700302 0.0071710000 0.0004030000 0.0042150000 0.0000040000 0.0000050000 0.0013900000 35676477 96830484 509673472 4.0333256721 3.9347262383 4.0574493408 304 1311867728.7584259510 0.1302899271 0.1128549960 0.2376661599 0.0052614767 0.0049580000 0.0003870000 0.0024890000 0.0000010000 0.0000040000 0.0011150000 35680261 96830484 509673472 4.0329627991 3.9347243309 4.0566720963 305 1311867728.7858450413 0.1294943690 0.1129095514 0.2376661599 0.0052537475 0.0077170000 0.0004810000 0.0030440000 0.0000110000 0.0000100000 0.0022260000 35683877 96830484 509673472 4.0318064690 3.9343407154 4.0562400818 306 1311867728.8203740120 0.1284758002 0.1129604215 0.2376661599 0.0052462667 0.0066230000 0.0004200000 0.0038800000 0.0000010000 0.0000050000 0.0011500000 35687549 96830484 509673472 4.0316915512 3.9347603321 4.0544571877 307 1311867728.8545160294 0.1248464882 0.1129991383 0.2376661599 0.0052397031 0.0068460000 0.0003810000 0.0041610000 0.0000040000 0.0000030000 0.0013450000 35691277 96830484 509673472 4.0299506187 3.9363529682 4.0512442589 308 1311867728.8860759735 0.1279019564 0.1130475241 0.2376661599 0.0052330082 0.0066230000 0.0004780000 0.0029180000 0.0000010000 0.0000080000 0.0012760000 35695005 96830484 509673472 4.0316839218 3.9349977970 4.0535306931 309 1311867728.9193949699 0.1277000308 0.1130949432 0.2376661599 0.0052250306 0.0106990000 0.0006370000 0.0032120000 0.0000160000 0.0000140000 0.0027850000 35698621 96830484 509673472 4.0311717987 3.9348301888 4.0540685654 310 1311867728.9585559368 0.1245372593 0.1131318539 0.2376661599 0.0052368894 0.0108990000 0.0006090000 0.0046480000 0.0000020000 0.0000140000 0.0017550000 35702629 96830484 509673472 4.0298709869 3.9367702007 4.0515279770 311 1311867728.9886839390 0.1261149645 0.1131736002 0.2376661599 0.0052329265 0.0078840000 0.0004780000 0.0043230000 0.0000080000 0.0000070000 0.0014430000 35706133 96830484 509673472 4.0302753448 3.9348523617 4.0529012680 312 1311867729.0231020451 0.1236409843 0.1132071495 0.2376661599 0.0052271397 0.0062830000 0.0004030000 0.0035330000 0.0000000000 0.0000050000 0.0011360000 35709917 96830484 509673472 4.0291848183 3.9363989830 4.0515570641 313 1311867729.0583839417 0.1213922203 0.1132332999 0.2376661599 0.0052263885 0.0071440000 0.0003870000 0.0038190000 0.0000030000 0.0000030000 0.0019970000 35713701 96830484 509673472 4.0272951126 3.9371991158 4.0511608124 314 1311867729.0882170200 0.1182410344 0.1132492481 0.2376661599 0.0052194205 0.0108170000 0.0005720000 0.0046480000 0.0000020000 0.0000150000 0.0017390000 35717317 96830484 509673472 4.0249657631 3.9382655621 4.0489091873 315 1311867729.1263229847 0.1188350990 0.1132669810 0.2376661599 0.0052330252 0.0073340000 0.0004770000 0.0030470000 0.0000100000 0.0000090000 0.0016730000 35721157 96830484 509673472 4.0250558853 3.9392800331 4.0507102013 316 1311867729.1556320190 0.1174893677 0.1132803429 0.2376661599 0.0052283756 0.0061960000 0.0004240000 0.0032350000 0.0000010000 0.0000050000 0.0011580000 35724717 96830484 509673472 4.0243105888 3.9405193329 4.0492687225 317 1311867729.1888830662 0.1178642511 0.1132948032 0.2376661599 0.0052556516 0.0059050000 0.0003980000 0.0023970000 0.0000040000 0.0000040000 0.0020060000 35728445 96830484 509673472 4.0238580704 3.9400036335 4.0495104790 318 1311867729.2240469456 0.1123778448 0.1132919197 0.2376661599 0.0052614302 0.0065790000 0.0003810000 0.0041360000 0.0000000000 0.0000040000 0.0011050000 35732173 96830484 509673472 4.0199446678 3.9419667721 4.0463652611 319 1311867729.2579979897 0.1135188565 0.1132926311 0.2376661599 0.0052533757 0.0055360000 0.0003730000 0.0028160000 0.0000040000 0.0000030000 0.0013960000 35735957 96830484 509673472 4.0190405846 3.9398117065 4.0483088493 320 1311867729.2880148888 0.1160511896 0.1133012516 0.2376661599 0.0052513594 0.0065640000 0.0003720000 0.0041560000 0.0000000000 0.0000030000 0.0010900000 35739573 96830484 509673472 4.0182747841 3.9371383190 4.0524530411 321 1311867729.3236539364 0.1105060354 0.1132925438 0.2376661599 0.0052517888 0.0071770000 0.0003790000 0.0038150000 0.0000040000 0.0000040000 0.0020010000 35743301 96830484 509673472 4.0141549110 3.9390487671 4.0505728722 322 1311867729.3580930233 0.1064112708 0.1132711734 0.2376661599 0.0052565949 0.0065730000 0.0003760000 0.0041520000 0.0000000000 0.0000040000 0.0010940000 35747085 96830484 509673472 4.0115404129 3.9393172264 4.0487322807 323 1311867729.3882780075 0.1079764217 0.1132547809 0.2376661599 0.0052580599 0.0097780000 0.0005650000 0.0038290000 0.0000140000 0.0000140000 0.0019410000 35750645 96830484 509673472 4.0110669136 3.9383251667 4.0517416000 324 1311867729.4253289700 0.1044128612 0.1132274911 0.2376661599 0.0052533405 0.0068720000 0.0004360000 0.0036240000 0.0000010000 0.0000060000 0.0011860000 35754485 96830484 509673472 4.0091471672 3.9400343895 4.0504875183 325 1311867729.4572670460 0.1048053354 0.1132015767 0.2376661599 0.0052472643 0.0075200000 0.0004940000 0.0026980000 0.0000100000 0.0000090000 0.0023100000 35758157 96830484 509673472 4.0092716217 3.9389469624 4.0511846542 326 1311867729.4887750149 0.1028974801 0.1131699691 0.2376661599 0.0052558163 0.0067730000 0.0004180000 0.0039010000 0.0000010000 0.0000050000 0.0011340000 35761885 96830484 509673472 4.0089783669 3.9392106533 4.0496110916 327 1311867729.5223650932 0.1033338159 0.1131398891 0.2376661599 0.0052492235 0.0068460000 0.0003880000 0.0040580000 0.0000040000 0.0000040000 0.0013740000 35765557 96830484 509673472 4.0084433556 3.9382793903 4.0511307716 328 1311867729.5603790283 0.1009692997 0.1131027836 0.2376661599 0.0052447394 0.0065550000 0.0003700000 0.0041360000 0.0000000000 0.0000030000 0.0010850000 35769397 96830484 509673472 4.0076107979 3.9388344288 4.0496706963 329 1311867729.5890150070 0.1021789461 0.1130695805 0.2376661599 0.0052368763 0.0100000000 0.0004820000 0.0044250000 0.0000070000 0.0000070000 0.0021800000 35772957 96830484 509673472 4.0089430809 3.9378590584 4.0503616333 330 1311867729.6254830360 0.0985877216 0.1130256961 0.2376661599 0.0052326238 0.0070850000 0.0004140000 0.0041860000 0.0000000000 0.0000040000 0.0011170000 35776741 96830484 509673472 4.0068488121 3.9391636848 4.0488305092 331 1311867729.6614611149 0.0979047939 0.1129800136 0.2376661599 0.0052264492 0.0070400000 0.0003890000 0.0041520000 0.0000030000 0.0000030000 0.0013410000 35780525 96830484 509673472 4.0072059631 3.9391894341 4.0486383438 332 1311867729.6888220310 0.0957145840 0.1129280093 0.2376661599 0.0052201896 0.0084130000 0.0004800000 0.0044010000 0.0000010000 0.0000080000 0.0012470000 35783973 96830484 509673472 4.0055789948 3.9392800331 4.0473303795 333 1311867729.7230739594 0.0939127803 0.1128709065 0.2376661599 0.0052138450 0.0081360000 0.0004600000 0.0042230000 0.0000050000 0.0000040000 0.0019910000 35787757 96830484 509673472 4.0040559769 3.9398112297 4.0472087860 334 1311867729.7570610046 0.0887011811 0.1127985420 0.2376661599 0.0052126161 0.0058620000 0.0004270000 0.0031730000 0.0000010000 0.0000030000 0.0010920000 35791317 96830484 509673472 4.0026478767 3.9424631596 4.0432143211 335 1311867729.7899730206 0.0807684436 0.1127029298 0.2376661599 0.0052159551 0.0083520000 0.0004840000 0.0044000000 0.0000080000 0.0000090000 0.0014880000 35795045 96830484 509673472 3.9985945225 3.9451951981 4.0367517471 336 1311867729.8264250755 0.0861608386 0.1126239355 0.2376661599 0.0052331069 0.0071220000 0.0004100000 0.0042050000 0.0000000000 0.0000040000 0.0011090000 35798773 96830484 509673472 3.9990270138 3.9418284893 4.0434999466 337 1311867729.8550031185 0.0785435140 0.1125228066 0.2376661599 0.0052317411 0.0076630000 0.0003930000 0.0041270000 0.0000040000 0.0000040000 0.0019830000 35802333 96830484 509673472 3.9953210354 3.9456300735 4.0384869576 338 1311867729.8881840706 0.0771090090 0.1124180321 0.2376661599 0.0052320304 0.0067260000 0.0003760000 0.0041180000 0.0000010000 0.0000040000 0.0010970000 35806117 96830484 509673472 3.9957170486 3.9457502365 4.0361242294 339 1311867729.9233629704 0.0705612078 0.1122945606 0.2376661599 0.0052319032 0.0052760000 0.0003720000 0.0024440000 0.0000030000 0.0000040000 0.0013330000 35809845 96830484 509673472 3.9904680252 3.9483325481 4.0328960419 340 1311867729.9569330215 0.0708693936 0.1121727219 0.2376661599 0.0052250324 0.0065180000 0.0003790000 0.0041130000 0.0000010000 0.0000040000 0.0010930000 35813573 96830484 509673472 3.9915330410 3.9487738609 4.0334081650 341 1311867729.9865698814 0.0683767349 0.1120442879 0.2376661599 0.0052216419 0.0073590000 0.0003800000 0.0040890000 0.0000040000 0.0000030000 0.0019570000 35817133 96830484 509673472 3.9890184402 3.9488995075 4.0317292213 342 1311867730.0230469704 0.0655213371 0.1119082559 0.2376661599 0.0052154258 0.0065250000 0.0003810000 0.0041160000 0.0000000000 0.0000040000 0.0010800000 35820917 96830484 509673472 3.9869267941 3.9498844147 4.0299830437 343 1311867730.0557899475 0.0635626614 0.1117673066 0.2376661599 0.0052107586 0.0055680000 0.0003820000 0.0027930000 0.0000030000 0.0000030000 0.0013310000 35824645 96830484 509673472 3.9852256775 3.9509651661 4.0294880867 344 1311867730.0871100426 0.0637035742 0.1116275865 0.2376661599 0.0052033149 0.0053070000 0.0003790000 0.0028090000 0.0000010000 0.0000030000 0.0010750000 35828317 96830484 509673472 3.9855470657 3.9508571625 4.0293478966 345 1311867730.1231229305 0.0639392510 0.1114893594 0.2376661599 0.0051958680 0.0071630000 0.0003810000 0.0037810000 0.0000040000 0.0000040000 0.0019440000 35832101 96830484 509673472 3.9855771065 3.9508605003 4.0297431946 346 1311867730.1568520069 0.0615990348 0.1113451677 0.2376661599 0.0051894936 0.0052760000 0.0003710000 0.0027910000 0.0000000000 0.0000030000 0.0010660000 35835829 96830484 509673472 3.9856202602 3.9527881145 4.0276975632 347 1311867730.1882419586 0.0595152453 0.1111958020 0.2376661599 0.0051849009 0.0068800000 0.0003810000 0.0041290000 0.0000040000 0.0000030000 0.0013200000 35839445 96830484 509673472 3.9857349396 3.9543292522 4.0257334709 348 1311867730.2224810123 0.0590102263 0.1110458434 0.2376661599 0.0051780509 0.0053290000 0.0003820000 0.0028000000 0.0000000000 0.0000040000 0.0010750000 35843229 96830484 509673472 3.9853832722 3.9547915459 4.0260276794 349 1311867730.2575879097 0.0589960441 0.1108967036 0.2376661599 0.0051724044 0.0075170000 0.0003820000 0.0041130000 0.0000030000 0.0000030000 0.0019520000 35846957 96830484 509673472 3.9875981808 3.9561543465 4.0252327919 350 1311867730.2914879322 0.0593331829 0.1107493793 0.2376661599 0.0051666924 0.0066400000 0.0003790000 0.0041490000 0.0000000000 0.0000040000 0.0010690000 35850685 96830484 509673472 3.9882314205 3.9568948746 4.0261592865 351 1311867730.3230810165 0.0604685657 0.1106061291 0.2376661599 0.0051656124 0.0052180000 0.0003780000 0.0024750000 0.0000040000 0.0000030000 0.0013150000 35854357 96830484 509673472 3.9908950329 3.9574286938 4.0258040428 352 1311867730.3554260731 0.0582087114 0.1104572728 0.2376661599 0.0051647074 0.0066220000 0.0003790000 0.0041280000 0.0000010000 0.0000030000 0.0010690000 35858029 96830484 509673472 3.9874887466 3.9572291374 4.0255298615 353 1311867730.3982920647 0.0597103424 0.1103135138 0.2376661599 0.0051584592 0.0075780000 0.0003820000 0.0041480000 0.0000040000 0.0000030000 0.0019460000 35861981 96830484 509673472 3.9904012680 3.9579131603 4.0259270668 354 1311867730.4225230217 0.0606098324 0.1101731079 0.2376661599 0.0051640952 0.0093570000 0.0005740000 0.0046380000 0.0000010000 0.0000090000 0.0013570000 35865485 96830484 509673472 3.9926302433 3.9593389034 4.0263056755 355 1311867730.4600110054 0.0616956092 0.1100365515 0.2376661599 0.0051572533 0.0061730000 0.0004180000 0.0029200000 0.0000050000 0.0000060000 0.0013390000 35869269 96830484 509673472 3.9932079315 3.9586710930 4.0260577202 356 1311867730.4948410988 0.0638073385 0.1099066942 0.2376661599 0.0051520174 0.0068100000 0.0003910000 0.0041760000 0.0000000000 0.0000040000 0.0010640000 35872997 96830484 509673472 3.9958770275 3.9585559368 4.0265130997 357 1311867730.5300729275 0.0618104637 0.1097719709 0.2376661599 0.0051467080 0.0068640000 0.0003780000 0.0034850000 0.0000030000 0.0000040000 0.0019400000 35876725 96830484 509673472 3.9937131405 3.9592337608 4.0261139870 358 1311867730.5597670078 0.0634479970 0.1096425743 0.2376661599 0.0051415171 0.0066080000 0.0003760000 0.0041340000 0.0000000000 0.0000030000 0.0010540000 35880341 96830484 509673472 3.9951083660 3.9587676525 4.0270819664 359 1311867730.5940020084 0.0615947321 0.1095087363 0.2376661599 0.0051383775 0.0049080000 0.0003810000 0.0021490000 0.0000030000 0.0000030000 0.0013120000 35884125 96830484 509673472 3.9923799038 3.9587721825 4.0267157555 360 1311867730.6230149269 0.0621402524 0.1093771572 0.2376661599 0.0051410975 0.0091520000 0.0005770000 0.0032440000 0.0000020000 0.0000140000 0.0016090000 35887629 96830484 509673472 3.9956867695 3.9606554508 4.0265688896 361 1311867730.6614060402 0.0607423410 0.1092424347 0.2376661599 0.0051350691 0.0083320000 0.0004460000 0.0043000000 0.0000060000 0.0000060000 0.0020110000 35891469 96830484 509673472 3.9942078590 3.9606826305 4.0260796547 362 1311867730.6922950745 0.0603994317 0.1091075093 0.2376661599 0.0051290283 0.0068620000 0.0003960000 0.0042010000 0.0000010000 0.0000040000 0.0010670000 35895141 96830484 509673472 3.9953219891 3.9616572857 4.0255947113 363 1311867730.7275629044 0.0606263243 0.1089739523 0.2376661599 0.0051318091 0.0068970000 0.0003870000 0.0041570000 0.0000030000 0.0000030000 0.0013000000 35898869 96830484 509673472 3.9975583553 3.9625773430 4.0244779587 364 1311867730.7572948933 0.0618506446 0.1088444927 0.2376661599 0.0051284865 0.0053240000 0.0003840000 0.0028260000 0.0000000000 0.0000030000 0.0010540000 35902485 96830484 509673472 3.9999907017 3.9630994797 4.0247011185 365 1311867730.7932779789 0.0588262007 0.1087074562 0.2376661599 0.0051230027 0.0093000000 0.0004910000 0.0044550000 0.0000090000 0.0000090000 0.0021140000 35906325 96830484 509673472 3.9975831509 3.9640650749 4.0230469704 366 1311867730.8240480423 0.0614673086 0.1085783848 0.2376661599 0.0051192491 0.0070730000 0.0004180000 0.0042300000 0.0000010000 0.0000050000 0.0010780000 35909885 96830484 509673472 4.0003557205 3.9625790119 4.0232119560 367 1311867730.8591129780 0.0589990243 0.1084432912 0.2376661599 0.0051154680 0.0062800000 0.0003790000 0.0034840000 0.0000030000 0.0000030000 0.0013180000 35913669 96830484 509673472 3.9991238117 3.9642601013 4.0223588943 368 1311867730.8922739029 0.0589141399 0.1083087011 0.2376661599 0.0051101925 0.0083250000 0.0004840000 0.0044370000 0.0000010000 0.0000080000 0.0011990000 35917229 96830484 509673472 3.9995565414 3.9648005962 4.0232539177 369 1311867730.9270720482 0.0603661276 0.1081787754 0.2376661599 0.0051060629 0.0079210000 0.0004120000 0.0042280000 0.0000050000 0.0000050000 0.0019360000 35921013 96830484 509673472 4.0031051636 3.9659352303 4.0237531662 370 1311867730.9611239433 0.0592402630 0.1080465092 0.2376661599 0.0051053643 0.0057050000 0.0003830000 0.0031760000 0.0000010000 0.0000040000 0.0010420000 35924685 96830484 509673472 4.0025281906 3.9668977261 4.0243473053 371 1311867730.9928169250 0.0614533760 0.1079209212 0.2376661599 0.0051062525 0.0085970000 0.0004860000 0.0044410000 0.0000070000 0.0000070000 0.0014180000 35928357 96830484 509673472 4.0064115524 3.9667212963 4.0241479874 372 1311867731.0221049786 0.0613352545 0.1077956909 0.2376661599 0.0051001631 0.0070580000 0.0003980000 0.0042530000 0.0000010000 0.0000050000 0.0010530000 35931973 96830484 509673472 4.0067100525 3.9665493965 4.0241847038 373 1311867731.0609729290 0.0592863150 0.1076656390 0.2376661599 0.0050960293 0.0062360000 0.0003830000 0.0028420000 0.0000030000 0.0000030000 0.0018870000 35935813 96830484 509673472 4.0057392120 3.9677553177 4.0242033005 374 1311867731.0900061131 0.0606762692 0.1075399989 0.2376661599 0.0050924652 0.0086880000 0.0004840000 0.0044660000 0.0000010000 0.0000100000 0.0013000000 35939373 96830484 509673472 4.0075440407 3.9668011665 4.0244226456 375 1311867731.1276559830 0.0622977391 0.1074193529 0.2376661599 0.0050881811 0.0075020000 0.0004200000 0.0042520000 0.0000040000 0.0000040000 0.0013040000 35943213 96830484 509673472 4.0104398727 3.9662992954 4.0241913795 376 1311867731.1551880836 0.0617477559 0.1072978859 0.2376661599 0.0050821040 0.0067330000 0.0003850000 0.0041750000 0.0000010000 0.0000040000 0.0010440000 35946773 96830484 509673472 4.0110340118 3.9678163528 4.0253458023 377 1311867731.1935870647 0.0608097948 0.1071745753 0.2376661599 0.0050764591 0.0087790000 0.0004830000 0.0043970000 0.0000070000 0.0000070000 0.0020540000 35950557 96830484 509673472 4.0110273361 3.9681451321 4.0250778198 378 1311867731.2235820293 0.0617812425 0.1070544871 0.2376661599 0.0050697976 0.0053930000 0.0004090000 0.0025490000 0.0000000000 0.0000040000 0.0010490000 35954229 96830484 509673472 4.0126447678 3.9680304527 4.0260024071 379 1311867731.2602028847 0.0603421926 0.1069312357 0.2376661599 0.0050640599 0.0085810000 0.0004760000 0.0044520000 0.0000080000 0.0000070000 0.0013960000 35957957 96830484 509673472 4.0125946999 3.9688925743 4.0256104469 380 1311867731.2900059223 0.0603452884 0.1068086411 0.2376661599 0.0050869763 0.0071010000 0.0004080000 0.0042640000 0.0000000000 0.0000040000 0.0010510000 35961573 96830484 509673472 4.0139040947 3.9691362381 4.0256567001 381 1311867731.3230779171 0.0602988675 0.1066865682 0.2376661599 0.0051116214 0.0088040000 0.0004860000 0.0044210000 0.0000070000 0.0000070000 0.0020320000 35965301 96830484 509673472 4.0150136948 3.9691226482 4.0250897408 382 1311867731.3570859432 0.0681807920 0.1065857677 0.2376661599 0.0051420284 0.0080270000 0.0004780000 0.0044210000 0.0000010000 0.0000070000 0.0011590000 35969085 96830484 509673472 4.0255889893 3.9686639309 4.0253210068 383 1311867731.3915760517 0.0631073937 0.1064722472 0.2376661599 0.0051406576 0.0073450000 0.0004100000 0.0042600000 0.0000040000 0.0000040000 0.0012910000 35972757 96830484 509673472 4.0207991600 3.9688470364 4.0240564346 384 1311867731.4279849529 0.0637419075 0.1063609703 0.2376661599 0.0051361918 0.0064230000 0.0003900000 0.0038450000 0.0000000000 0.0000030000 0.0010280000 35976597 96830484 509673472 4.0224280357 3.9683268070 4.0230407715 385 1311867731.4602010250 0.0585594736 0.1062368105 0.2376661599 0.0051441754 0.0083920000 0.0004770000 0.0037790000 0.0000080000 0.0000060000 0.0020650000 35980269 96830484 509673472 4.0169701576 3.9685282707 4.0220160484 386 1311867731.4926180840 0.0547279976 0.1061033680 0.2376661599 0.0051434494 0.0057300000 0.0004000000 0.0029070000 0.0000000000 0.0000040000 0.0010360000 35983941 96830484 509673472 4.0142984390 3.9702265263 4.0206303596 387 1311867731.5259540081 0.0567803122 0.1059759182 0.2376661599 0.0051395130 0.0086970000 0.0004870000 0.0045050000 0.0000070000 0.0000070000 0.0014180000 35987613 96830484 509673472 4.0185508728 3.9708034992 4.0204582214 388 1311867731.5589148998 0.0547796339 0.1058439691 0.2376661599 0.0051388129 0.0059310000 0.0004240000 0.0029160000 0.0000000000 0.0000050000 0.0010720000 35991285 96830484 509673472 4.0181298256 3.9720191956 4.0194754601 389 1311867731.5967359543 0.0515337363 0.1057043541 0.2376661599 0.0051482673 0.0089200000 0.0004850000 0.0044450000 0.0000070000 0.0000070000 0.0020550000 35995181 96830484 509673472 4.0149087906 3.9726533890 4.0190944672 390 1311867731.6247410774 0.0520446040 0.1055667650 0.2376661599 0.0051507986 0.0054520000 0.0004070000 0.0025770000 0.0000010000 0.0000050000 0.0010470000 35998685 96830484 509673472 4.0151467323 3.9722127914 4.0195398331 391 1311867731.6616659164 0.0505847968 0.1054261461 0.2376661599 0.0051583963 0.0073930000 0.0004810000 0.0030930000 0.0000100000 0.0000110000 0.0014750000 36002525 96830484 509673472 4.0138974190 3.9726471901 4.0196232796 392 1311867731.6925039291 0.0499919727 0.1052847324 0.2376661599 0.0051604519 0.0058940000 0.0004800000 0.0025820000 0.0000010000 0.0000050000 0.0010800000 36006141 96830484 509673472 4.0142540932 3.9731690884 4.0194621086 393 1311867731.7299311161 0.0479989909 0.1051389672 0.2376661599 0.0051555663 0.0081210000 0.0005180000 0.0034410000 0.0000070000 0.0000070000 0.0020330000 36009981 96830484 509673472 4.0118341446 3.9727418423 4.0197854042 394 1311867731.7615330219 0.0461973958 0.1049893693 0.2376661599 0.0051511051 0.0071370000 0.0004000000 0.0042820000 0.0000000000 0.0000040000 0.0010500000 36013653 96830484 509673472 4.0100488663 3.9727199078 4.0195765495 395 1311867731.7939310074 0.0444850959 0.1048361939 0.2376661599 0.0051460399 0.0070940000 0.0004860000 0.0027370000 0.0000100000 0.0000090000 0.0015110000 36017325 96830484 509673472 4.0086379051 3.9731287956 4.0195980072 396 1311867731.8252151012 0.0469949692 0.1046901302 0.2376661599 0.0051561298 0.0072910000 0.0004230000 0.0043050000 0.0000010000 0.0000060000 0.0010550000 36020941 96830484 509673472 4.0116262436 3.9716329575 4.0193195343 397 1311867731.8593230247 0.0444527715 0.1045383988 0.2376661599 0.0051706249 0.0069850000 0.0003840000 0.0035580000 0.0000040000 0.0000040000 0.0018610000 36024669 96830484 509673472 4.0091924667 3.9719130993 4.0187315941 398 1311867731.8910930157 0.0446445979 0.1043879119 0.2376661599 0.0051771394 0.0084370000 0.0004850000 0.0044720000 0.0000010000 0.0000070000 0.0011570000 36028397 96830484 509673472 4.0105800629 3.9721391201 4.0182971954 399 1311867731.9224479198 0.0455046296 0.1042403347 0.2376661599 0.0051716004 0.0073710000 0.0003990000 0.0042860000 0.0000050000 0.0000050000 0.0012720000 36032069 96830484 509673472 4.0124759674 3.9720597267 4.0177607536 400 1311867731.9598410130 0.0449660905 0.1040921491 0.2376661599 0.0051654596 0.0067950000 0.0003850000 0.0042270000 0.0000000000 0.0000040000 0.0010190000 36035797 96830484 509673472 4.0127048492 3.9722013474 4.0172982216 401 1311867731.9915709496 0.0409786329 0.1039347588 0.2376661599 0.0051648764 0.0089630000 0.0004900000 0.0044650000 0.0000080000 0.0000060000 0.0020270000 36039469 96830484 509673472 4.0091557503 3.9735231400 4.0165653229 402 1311867732.0239229202 0.0396571010 0.1037748641 0.2376661599 0.0051663394 0.0071340000 0.0004040000 0.0042710000 0.0000000000 0.0000040000 0.0010350000 36043141 96830484 509673472 4.0077500343 3.9722447395 4.0159025192 403 1311867732.0619950294 0.0402890742 0.1036173312 0.2376661599 0.0051616670 0.0070200000 0.0003870000 0.0042350000 0.0000040000 0.0000030000 0.0012660000 36046981 96830484 509673472 4.0088562965 3.9722084999 4.0150070190 404 1311867732.0918290615 0.0376625620 0.1034540768 0.2376661599 0.0051623455 0.0067240000 0.0003740000 0.0042060000 0.0000000000 0.0000030000 0.0010120000 36050597 96830484 509673472 4.0067591667 3.9733295441 4.0141878128 405 1311867732.1221950054 0.0382410996 0.1032930571 0.2376661599 0.0051631811 0.0079530000 0.0004690000 0.0030760000 0.0000070000 0.0000070000 0.0020370000 36054269 96830484 509673472 4.0075497627 3.9721202850 4.0132131577 406 1311867732.1605980396 0.0359375626 0.1031271568 0.2376661599 0.0051617051 0.0078960000 0.0005100000 0.0041220000 0.0000010000 0.0000080000 0.0011420000 36058053 96830484 509673472 4.0056610107 3.9729003906 4.0123829842 407 1311867732.1931400299 0.0351732932 0.1029601940 0.2376661599 0.0051703581 0.0073330000 0.0004250000 0.0042620000 0.0000050000 0.0000050000 0.0012760000 36061781 96830484 509673472 4.0067291260 3.9740424156 4.0116691589 408 1311867732.2232089043 0.0350268520 0.1027936907 0.2376661599 0.0051958874 0.0067110000 0.0003850000 0.0042020000 0.0000010000 0.0000040000 0.0010220000 36065341 96830484 509673472 4.0061998367 3.9731562138 4.0108284950 409 1311867732.2590498924 0.0337207951 0.1026248084 0.2376661599 0.0052632693 0.0077640000 0.0004830000 0.0030670000 0.0000080000 0.0000070000 0.0020260000 36069125 96830484 509673472 4.0062260628 3.9752366543 4.0102734566 410 1311867732.2903969288 0.0317058749 0.1024518354 0.2376661599 0.0052792441 0.0070480000 0.0004010000 0.0042640000 0.0000000000 0.0000050000 0.0010370000 36072797 96830484 509673472 4.0033297539 3.9746968746 4.0103397369 411 1311867732.3218240738 0.0316158459 0.1022794850 0.2376661599 0.0052763908 0.0070890000 0.0003860000 0.0042120000 0.0000040000 0.0000040000 0.0012720000 36076469 96830484 509673472 4.0032181740 3.9739227295 4.0095515251 412 1311867732.3607840538 0.0315371044 0.1021077802 0.2376661599 0.0052700880 0.0067660000 0.0003760000 0.0041810000 0.0000010000 0.0000030000 0.0010180000 36080309 96830484 509673472 4.0054411888 3.9750101566 4.0089788437 413 1311867732.3899528980 0.0300622620 0.1019333359 0.2376661599 0.0052648864 0.0100040000 0.0005990000 0.0046410000 0.0000100000 0.0000090000 0.0022180000 36083869 96830484 509673472 4.0042676926 3.9752721786 4.0084338188 414 1311867732.4218940735 0.0306467507 0.1017611460 0.2376661599 0.0052607351 0.0081150000 0.0004760000 0.0044260000 0.0000010000 0.0000070000 0.0011550000 36087597 96830484 509673472 4.0054297447 3.9741256237 4.0074934959 415 1311867732.4593050480 0.0288472790 0.1015854500 0.2376661599 0.0052589417 0.0057160000 0.0004060000 0.0025660000 0.0000050000 0.0000050000 0.0012730000 36091381 96830484 509673472 4.0051898956 3.9756588936 4.0069322586 416 1311867732.4918489456 0.0271953847 0.1014066277 0.2376661599 0.0052567596 0.0081700000 0.0004770000 0.0044300000 0.0000010000 0.0000070000 0.0011680000 36095109 96830484 509673472 4.0028982162 3.9754042625 4.0063700676 417 1311867732.5229809284 0.0287390407 0.1012323649 0.2376661599 0.0052601772 0.0080080000 0.0004060000 0.0042720000 0.0000050000 0.0000040000 0.0018750000 36098725 96830484 509673472 4.0079193115 3.9762010574 4.0053310394 418 1311867732.5698928833 0.0255699456 0.1010513543 0.2376661599 0.0052587907 0.0068290000 0.0003840000 0.0042090000 0.0000000000 0.0000040000 0.0010290000 36102789 96830484 509673472 4.0055298805 3.9780030251 4.0052199364 419 1311867732.5926280022 0.0237769522 0.1008669285 0.2376661599 0.0052559700 0.0070540000 0.0003750000 0.0041980000 0.0000030000 0.0000030000 0.0012630000 36106237 96830484 509673472 4.0025472641 3.9779736996 4.0048694611 420 1311867732.6242370605 0.0241776258 0.1006843350 0.2376661599 0.0052575074 0.0054610000 0.0003780000 0.0028580000 0.0000000000 0.0000030000 0.0010200000 36109909 96830484 509673472 4.0043768883 3.9778137207 4.0040740967 421 1311867732.6630299091 0.0221516956 0.1004977966 0.2376661599 0.0052545229 0.0079480000 0.0004320000 0.0042130000 0.0000030000 0.0000030000 0.0018390000 36113749 96830484 509673472 4.0022006035 3.9786632061 4.0042133331 422 1311867732.6922440529 0.0214692671 0.1003105252 0.2376661599 0.0052510613 0.0056880000 0.0005780000 0.0028650000 0.0000010000 0.0000030000 0.0010280000 36117365 96830484 509673472 4.0032677650 3.9801597595 4.0040931702 423 1311867732.7260940075 0.0218784884 0.1001251067 0.2376661599 0.0052454914 0.0053590000 0.0003800000 0.0025160000 0.0000030000 0.0000030000 0.0012530000 36121093 96830484 509673472 4.0030140877 3.9791164398 4.0034751892 424 1311867732.7601239681 0.0200365074 0.0999362185 0.2376661599 0.0052489499 0.0054330000 0.0003750000 0.0028400000 0.0000000000 0.0000030000 0.0010160000 36124765 96830484 509673472 3.9988687038 3.9795320034 4.0032024384 425 1311867732.7919039726 0.0199126583 0.0997479278 0.2376661599 0.0052452972 0.0076330000 0.0003770000 0.0042020000 0.0000040000 0.0000030000 0.0018340000 36128493 96830484 509673472 4.0017604828 3.9812357426 4.0030589104 426 1311867732.8280360699 0.0196077768 0.0995598053 0.2376661599 0.0052446582 0.0068090000 0.0003750000 0.0041970000 0.0000000000 0.0000030000 0.0010110000 36132221 96830484 509673472 3.9984018803 3.9801411629 4.0025005341 427 1311867732.8589270115 0.0187423863 0.0993705374 0.2376661599 0.0052409612 0.0053780000 0.0003780000 0.0025320000 0.0000040000 0.0000030000 0.0012510000 36135893 96830484 509673472 3.9982562065 3.9813802242 4.0024275780 428 1311867732.8912909031 0.0179048982 0.0991801971 0.2376661599 0.0052383021 0.0104790000 0.0005650000 0.0047300000 0.0000020000 0.0000150000 0.0015510000 36139565 96830484 509673472 3.9960842133 3.9820880890 4.0023646355 429 1311867732.9262781143 0.0174287334 0.0989896343 0.2376661599 0.0052324438 0.0082670000 0.0004400000 0.0043780000 0.0000080000 0.0000060000 0.0018810000 36143349 96830484 509673472 3.9971141815 3.9831748009 4.0026946068 430 1311867732.9602870941 0.0183295645 0.0988020527 0.2376661599 0.0052323403 0.0068920000 0.0003990000 0.0042440000 0.0000010000 0.0000040000 0.0010080000 36147021 96830484 509673472 3.9956090450 3.9814445972 4.0026655197 431 1311867732.9987640381 0.0179064721 0.0986143599 0.2376661599 0.0052285152 0.0055800000 0.0003860000 0.0028590000 0.0000030000 0.0000030000 0.0012210000 36150917 96830484 509673472 3.9977545738 3.9820616245 4.0026011467 432 1311867733.0276939869 0.0176376011 0.0984269137 0.2376661599 0.0052294202 0.0083480000 0.0004940000 0.0044910000 0.0000010000 0.0000070000 0.0011430000 36154533 96830484 509673472 3.9929354191 3.9824314117 4.0033321381 433 1311867733.0607628822 0.0190347824 0.0982435601 0.2376661599 0.0052457665 0.0091240000 0.0004890000 0.0044860000 0.0000070000 0.0000070000 0.0019800000 36158205 96830484 509673472 3.9939408302 3.9803249836 4.0032792091 434 1311867733.0977020264 0.0178221986 0.0980582574 0.2376661599 0.0052419475 0.0080030000 0.0004750000 0.0041500000 0.0000010000 0.0000070000 0.0011150000 36161989 96830484 509673472 3.9939556122 3.9816641808 4.0033164024 435 1311867733.1263020039 0.0175038241 0.0978730748 0.2376661599 0.0052402841 0.0064500000 0.0004260000 0.0032790000 0.0000060000 0.0000050000 0.0012620000 36165549 96830484 509673472 3.9903638363 3.9830613136 4.0038375854 436 1311867733.1625030041 0.0199489482 0.0976943497 0.2376661599 0.0052420613 0.0082710000 0.0004850000 0.0044810000 0.0000010000 0.0000070000 0.0011260000 36169333 96830484 509673472 3.9897115231 3.9799036980 4.0035223961 437 1311867733.1926651001 0.0197463874 0.0975159791 0.2376661599 0.0052410761 0.0079490000 0.0004120000 0.0042890000 0.0000040000 0.0000040000 0.0018460000 36172949 96830484 509673472 3.9879598618 3.9808537960 4.0036339760 438 1311867733.2259631157 0.0185727011 0.0973357433 0.2376661599 0.0052383007 0.0057360000 0.0003840000 0.0032020000 0.0000000000 0.0000030000 0.0010000000 36176677 96830484 509673472 3.9889347553 3.9825408459 4.0039377213 439 1311867733.2618060112 0.0205114763 0.0971607450 0.2376661599 0.0052370068 0.0083800000 0.0004860000 0.0044730000 0.0000080000 0.0000080000 0.0013720000 36180461 96830484 509673472 3.9857466221 3.9819438457 4.0040612221 440 1311867733.2919199467 0.0215108134 0.0969888133 0.2376661599 0.0052323782 0.0060890000 0.0004040000 0.0032640000 0.0000000000 0.0000040000 0.0010220000 36184021 96830484 509673472 3.9841210842 3.9814405441 4.0037093163 441 1311867733.3300418854 0.0203617513 0.0968150558 0.2376661599 0.0052398625 0.0092620000 0.0004800000 0.0045060000 0.0000080000 0.0000070000 0.0019830000 36187861 96830484 509673472 3.9858462811 3.9817655087 4.0036182404 442 1311867733.3602790833 0.0205395985 0.0966424869 0.2376661599 0.0052372985 0.0071290000 0.0004130000 0.0042940000 0.0000000000 0.0000060000 0.0010190000 36191533 96830484 509673472 3.9870936871 3.9805250168 4.0030636787 443 1311867733.3923840523 0.0227284841 0.0964756381 0.2376661599 0.0052390190 0.0083540000 0.0004880000 0.0044750000 0.0000090000 0.0000080000 0.0013670000 36195205 96830484 509673472 3.9835133553 3.9805142879 4.0029559135 444 1311867733.4289550781 0.0225475542 0.0963091335 0.2376661599 0.0052362007 0.0054370000 0.0004110000 0.0025830000 0.0000010000 0.0000060000 0.0010400000 36198989 96830484 509673472 3.9827084541 3.9822714329 4.0029535294 445 1311867733.4588150978 0.0221037082 0.0961423797 0.2376661599 0.0052338240 0.0076990000 0.0003880000 0.0042500000 0.0000040000 0.0000040000 0.0018380000 36202493 96830484 509673472 3.9837164879 3.9817693233 4.0024495125 446 1311867733.4956119061 0.0222719740 0.0959767510 0.2376661599 0.0052289329 0.0067570000 0.0003810000 0.0042240000 0.0000000000 0.0000040000 0.0010070000 36206165 96830484 509673472 3.9834272861 3.9819784164 4.0022258759 447 1311867733.5290400982 0.0229379497 0.0958133532 0.2376661599 0.0052256914 0.0079200000 0.0004940000 0.0030960000 0.0000100000 0.0000100000 0.0015070000 36209893 96830484 509673472 3.9817390442 3.9829416275 4.0023946762 448 1311867733.5630290508 0.0224975478 0.0956497019 0.2376661599 0.0052201227 0.0074230000 0.0004280000 0.0043370000 0.0000010000 0.0000050000 0.0010320000 36213621 96830484 509673472 3.9825952053 3.9828643799 4.0022010803 449 1311867733.5922229290 0.0254677683 0.0954933947 0.2376661599 0.0052182472 0.0093030000 0.0004900000 0.0044840000 0.0000080000 0.0000070000 0.0019930000 36217181 96830484 509673472 3.9798421860 3.9813358784 4.0018477440 450 1311867733.6283020973 0.0268399771 0.0953408315 0.2376661599 0.0052150512 0.0071560000 0.0004140000 0.0042770000 0.0000010000 0.0000050000 0.0010250000 36220965 96830484 509673472 3.9783537388 3.9814817905 4.0021061897 451 1311867733.6601879597 0.0261513721 0.0951874181 0.2376661599 0.0052097571 0.0054350000 0.0003960000 0.0025460000 0.0000050000 0.0000040000 0.0012590000 36224637 96830484 509673472 3.9788894653 3.9819231033 4.0017929077 452 1311867733.6917510033 0.0268355329 0.0950361971 0.2376661599 0.0052054860 0.0050860000 0.0003800000 0.0025370000 0.0000000000 0.0000030000 0.0010160000 36228309 96830484 509673472 3.9785108566 3.9813554287 4.0015406609 453 1311867733.7288239002 0.0284267534 0.0948891564 0.2376661599 0.0052023935 0.0106190000 0.0005630000 0.0047840000 0.0000150000 0.0000160000 0.0021660000 36232093 96830484 509673472 3.9776799679 3.9801540375 4.0015110970 454 1311867733.7597820759 0.0316430107 0.0947498477 0.2376661599 0.0051987998 0.0084410000 0.0004760000 0.0044920000 0.0000010000 0.0000080000 0.0011480000 36235653 96830484 509673472 3.9744465351 3.9796252251 4.0018949509 455 1311867733.7924160957 0.0303889923 0.0946083953 0.2376661599 0.0052242345 0.0073940000 0.0004190000 0.0042740000 0.0000050000 0.0000050000 0.0012620000 36239325 96830484 509673472 3.9758331776 3.9798524380 4.0019197464 456 1311867733.8282589912 0.0351428315 0.0944779883 0.2376661599 0.0052303874 0.0054910000 0.0003900000 0.0028900000 0.0000010000 0.0000030000 0.0010220000 36243109 96830484 509673472 3.9722027779 3.9778149128 4.0015683174 457 1311867733.8608579636 0.0322007090 0.0943417142 0.2376661599 0.0052276050 0.0075630000 0.0003770000 0.0041890000 0.0000040000 0.0000030000 0.0018500000 36246669 96830484 509673472 3.9752047062 3.9790780544 4.0010237694 458 1311867733.8918149471 0.0335664228 0.0942090170 0.2376661599 0.0052228892 0.0053990000 0.0003750000 0.0028470000 0.0000000000 0.0000040000 0.0010170000 36250229 96830484 509673472 3.9740021229 3.9792828560 4.0008816719 459 1311867733.9289460182 0.0351824313 0.0940804188 0.2376661599 0.0052179111 0.0105030000 0.0005650000 0.0036600000 0.0000160000 0.0000140000 0.0017510000 36254013 96830484 509673472 3.9733006954 3.9778196812 4.0003752708 460 1311867733.9595899582 0.0390788130 0.0939608501 0.2376661599 0.0052245338 0.0084590000 0.0004760000 0.0044730000 0.0000010000 0.0000080000 0.0011480000 36257685 96830484 509673472 3.9699404240 3.9760937691 4.0003004074 461 1311867733.9941790104 0.0397238433 0.0938431993 0.2376661599 0.0052232760 0.0069990000 0.0004180000 0.0032370000 0.0000040000 0.0000050000 0.0018760000 36261413 96830484 509673472 3.9699406624 3.9762616158 4.0006189346 462 1311867734.0275731087 0.0443213694 0.0937360092 0.2376661599 0.0052376184 0.0068170000 0.0003880000 0.0041960000 0.0000010000 0.0000040000 0.0010240000 36265197 96830484 509673472 3.9660146236 3.9735317230 4.0006380081 463 1311867734.0599920750 0.0424905717 0.0936253279 0.2376661599 0.0052334230 0.0069910000 0.0003770000 0.0041830000 0.0000030000 0.0000040000 0.0012580000 36268813 96830484 509673472 3.9680132866 3.9741265774 4.0003232956 464 1311867734.0956780910 0.0413859338 0.0935127430 0.2376661599 0.0052289121 0.0068210000 0.0003780000 0.0041730000 0.0000010000 0.0000040000 0.0010110000 36272597 96830484 509673472 3.9694449902 3.9743018150 4.0002975464 465 1311867734.1274170876 0.0444746874 0.0934072848 0.2376661599 0.0052269356 0.0075930000 0.0003770000 0.0041690000 0.0000040000 0.0000030000 0.0018250000 36276325 96830484 509673472 3.9675440788 3.9714810848 3.9998376369 466 1311867734.1618878841 0.0436349548 0.0933004773 0.2376661599 0.0052272424 0.0082930000 0.0004830000 0.0044320000 0.0000010000 0.0000070000 0.0011390000 36279997 96830484 509673472 3.9682848454 3.9727356434 3.9994733334 467 1311867734.1942350864 0.0431918688 0.0931931783 0.2376661599 0.0052230839 0.0074240000 0.0004070000 0.0042650000 0.0000050000 0.0000040000 0.0012690000 36283725 96830484 509673472 3.9686498642 3.9740920067 3.9994990826 468 1311867734.2291829586 0.0468511209 0.0930941568 0.2376661599 0.0052259927 0.0073140000 0.0004850000 0.0036770000 0.0000010000 0.0000090000 0.0011300000 36287397 96830484 509673472 3.9659502506 3.9713993073 3.9993300438 469 1311867734.2607750893 0.0454671644 0.0929926067 0.2376661599 0.0052225058 0.0066130000 0.0004030000 0.0028850000 0.0000040000 0.0000040000 0.0018470000 36291069 96830484 509673472 3.9671792984 3.9726569653 3.9992074966 470 1311867734.2941219807 0.0448248759 0.0928901222 0.2376661599 0.0052198136 0.0085350000 0.0004870000 0.0044810000 0.0000010000 0.0000080000 0.0011350000 36294741 96830484 509673472 3.9677107334 3.9737920761 3.9995911121 471 1311867734.3263280392 0.0440692119 0.0927864685 0.2376661599 0.0052173773 0.0074890000 0.0004320000 0.0042770000 0.0000040000 0.0000050000 0.0012770000 36298413 96830484 509673472 3.9688763618 3.9734914303 3.9994962215 472 1311867734.3610401154 0.0449295454 0.0926850767 0.2376661599 0.0052142843 0.0058380000 0.0003850000 0.0031960000 0.0000010000 0.0000030000 0.0010100000 36302141 96830484 509673472 3.9684689045 3.9728465080 3.9998109341 473 1311867734.3941841125 0.0459170341 0.0925862013 0.2376661599 0.0052175776 0.0092510000 0.0004870000 0.0044870000 0.0000070000 0.0000070000 0.0019820000 36305869 96830484 509673472 3.9672505856 3.9740583897 4.0005049706 474 1311867734.4276480675 0.0466503575 0.0924892903 0.2376661599 0.0052121625 0.0064840000 0.0004090000 0.0035830000 0.0000010000 0.0000050000 0.0010100000 36309597 96830484 509673472 3.9667606354 3.9737160206 4.0007028580 475 1311867734.4586091042 0.0466263816 0.0923927368 0.2376661599 0.0052084815 0.0070560000 0.0003850000 0.0041970000 0.0000040000 0.0000030000 0.0012340000 36313213 96830484 509673472 3.9671244621 3.9729685783 4.0010600090 476 1311867734.4938759804 0.0470843129 0.0922975510 0.2376661599 0.0052039289 0.0061160000 0.0003770000 0.0035140000 0.0000010000 0.0000040000 0.0009920000 36316997 96830484 509673472 3.9666328430 3.9741191864 4.0014939308 477 1311867734.5300569534 0.0480432510 0.0922047747 0.2376661599 0.0051994598 0.0075910000 0.0003800000 0.0042080000 0.0000030000 0.0000030000 0.0017910000 36320781 96830484 509673472 3.9660084248 3.9738340378 4.0020837784 478 1311867734.5595300198 0.0478077456 0.0921118939 0.2376661599 0.0051981523 0.0064290000 0.0003790000 0.0038470000 0.0000010000 0.0000030000 0.0009910000 36324341 96830484 509673472 3.9668414593 3.9734616280 4.0024404526 479 1311867734.5953910351 0.0497409701 0.0920234368 0.2376661599 0.0051957842 0.0070010000 0.0003820000 0.0041900000 0.0000030000 0.0000030000 0.0012240000 36328069 96830484 509673472 3.9645118713 3.9741671085 4.0034790039 480 1311867734.6285231113 0.0473739319 0.0919304170 0.2376661599 0.0051915957 0.0071450000 0.0004320000 0.0041980000 0.0000000000 0.0000030000 0.0009890000 36331797 96830484 509673472 3.9674279690 3.9743316174 4.0030560493 481 1311867734.6593229771 0.0491519310 0.0918414805 0.2376661599 0.0051871611 0.0076340000 0.0004190000 0.0041840000 0.0000040000 0.0000030000 0.0018010000 36335413 96830484 509673472 3.9657201767 3.9736869335 4.0030698776 482 1311867734.6947479248 0.0487915277 0.0917521652 0.2376661599 0.0051838706 0.0048000000 0.0003830000 0.0021750000 0.0000010000 0.0000040000 0.0009880000 36339141 96830484 509673472 3.9660477638 3.9734318256 4.0032749176 483 1311867734.7310240269 0.0489192270 0.0916634842 0.2376661599 0.0051828009 0.0098050000 0.0005720000 0.0028050000 0.0000160000 0.0000130000 0.0017360000 36342981 96830484 509673472 3.9663736820 3.9732923508 4.0032768250 484 1311867734.7607629299 0.0484738797 0.0915742495 0.2376661599 0.0051777605 0.0079150000 0.0004440000 0.0043960000 0.0000010000 0.0000050000 0.0010520000 36346541 96830484 509673472 3.9673595428 3.9731802940 4.0032038689 485 1311867734.7976419926 0.0496221296 0.0914877503 0.2376661599 0.0051750192 0.0078800000 0.0004120000 0.0042650000 0.0000050000 0.0000050000 0.0018000000 36350381 96830484 509673472 3.9661993980 3.9737472534 4.0035896301 486 1311867734.8298120499 0.0501118898 0.0914026147 0.2376661599 0.0051711535 0.0069640000 0.0003940000 0.0042280000 0.0000000000 0.0000030000 0.0009940000 36354053 96830484 509673472 3.9658539295 3.9742717743 4.0038456917 487 1311867734.8645250797 0.0516696684 0.0913210276 0.2376661599 0.0051678979 0.0058340000 0.0003910000 0.0028660000 0.0000040000 0.0000040000 0.0012390000 36357781 96830484 509673472 3.9642245770 3.9757041931 4.0046510696 488 1311867734.8943901062 0.0497393087 0.0912358191 0.2376661599 0.0051690730 0.0077840000 0.0005140000 0.0034280000 0.0000010000 0.0000070000 0.0011240000 36361453 96830484 509673472 3.9666798115 3.9747776985 4.0042881966 489 1311867734.9263660908 0.0495529845 0.0911505782 0.2376661599 0.0051639364 0.0079570000 0.0004810000 0.0027440000 0.0000100000 0.0000100000 0.0020240000 36365069 96830484 509673472 3.9673330784 3.9743993282 4.0045938492 490 1311867734.9631719589 0.0517360903 0.0910701404 0.2376661599 0.0051628363 0.0073960000 0.0004240000 0.0042890000 0.0000000000 0.0000050000 0.0010320000 36368629 96830484 509673472 3.9656691551 3.9742717743 4.0045528412 491 1311867734.9948470592 0.0509770624 0.0909884845 0.2376661599 0.0051647082 0.0072330000 0.0003880000 0.0042430000 0.0000030000 0.0000040000 0.0012320000 36372301 96830484 509673472 3.9660229683 3.9743947983 4.0042562485 492 1311867735.0292239189 0.0506501943 0.0909064961 0.2376661599 0.0051635126 0.0079060000 0.0004900000 0.0035030000 0.0000010000 0.0000100000 0.0012110000 36376141 96830484 509673472 3.9666428566 3.9747831821 4.0040793419 493 1311867735.0596508980 0.0533291884 0.0908302744 0.2376661599 0.0051605767 0.0083020000 0.0004340000 0.0043250000 0.0000050000 0.0000060000 0.0018090000 36379645 96830484 509673472 3.9637055397 3.9751908779 4.0045328140 494 1311867735.0952830315 0.0510427058 0.0907497327 0.2376661599 0.0051646595 0.0070160000 0.0004000000 0.0042170000 0.0000010000 0.0000040000 0.0009940000 36383429 96830484 509673472 3.9661791325 3.9747362137 4.0043096542 495 1311867735.1313030720 0.0511264503 0.0906696857 0.2376661599 0.0051625749 0.0073330000 0.0004920000 0.0027360000 0.0000100000 0.0000090000 0.0013630000 36387213 96830484 509673472 3.9659986496 3.9754986763 4.0045318604 496 1311867735.1603751183 0.0514582805 0.0905906304 0.2376661599 0.0051574599 0.0073910000 0.0004250000 0.0042870000 0.0000010000 0.0000050000 0.0010180000 36390773 96830484 509673472 3.9658410549 3.9753029346 4.0047430992 497 1311867735.1994349957 0.0527000241 0.0905143918 0.2376661599 0.0051554566 0.0078170000 0.0003970000 0.0042440000 0.0000040000 0.0000030000 0.0017870000 36394613 96830484 509673472 3.9650442600 3.9739778042 4.0050826073 498 1311867735.2263538837 0.0518635847 0.0904367797 0.2376661599 0.0051534931 0.0069650000 0.0003890000 0.0042120000 0.0000010000 0.0000040000 0.0009980000 36398229 96830484 509673472 3.9656851292 3.9753663540 4.0052938461 499 1311867735.2655019760 0.0512905419 0.0903583304 0.2376661599 0.0051487253 0.0051370000 0.0003830000 0.0021820000 0.0000040000 0.0000030000 0.0012300000 36402013 96830484 509673472 3.9662480354 3.9762392044 4.0055732727 500 1311867735.2961549759 0.0523369573 0.0902822876 0.2376661599 0.0051486839 0.0087020000 0.0004930000 0.0041600000 0.0000010000 0.0000100000 0.0012640000 36405685 96830484 509673472 3.9655232430 3.9749574661 4.0062942505 501 1311867735.3321089745 0.0519967154 0.0902058693 0.2376661599 0.0051457882 0.0083790000 0.0004280000 0.0043090000 0.0000050000 0.0000050000 0.0018320000 36409469 96830484 509673472 3.9657568932 3.9762008190 4.0066618919 502 1311867735.3666970730 0.0527146235 0.0901311855 0.2376661599 0.0051484901 0.0060010000 0.0003960000 0.0032200000 0.0000000000 0.0000040000 0.0009930000 36413085 96830484 509673472 3.9654030800 3.9754939079 4.0070738792 503 1311867735.3943350315 0.0531576723 0.0900576796 0.2376661599 0.0051609267 0.0068670000 0.0003870000 0.0039120000 0.0000030000 0.0000040000 0.0012310000 36416589 96830484 509673472 3.9651916027 3.9757504463 4.0073280334 504 1311867735.4322299957 0.0554646738 0.0899890426 0.2376661599 0.0051630137 0.0059420000 0.0003850000 0.0032210000 0.0000010000 0.0000030000 0.0009930000 36420485 96830484 509673472 3.9628338814 3.9766495228 4.0077481270 505 1311867735.4628560543 0.0537167899 0.0899172164 0.2376661599 0.0051599002 0.0077120000 0.0003800000 0.0041950000 0.0000030000 0.0000040000 0.0017700000 36424101 96830484 509673472 3.9653315544 3.9767732620 4.0076980591 506 1311867735.4973869324 0.0560598336 0.0898503046 0.2376661599 0.0051580493 0.0069270000 0.0003820000 0.0042170000 0.0000000000 0.0000040000 0.0009970000 36427885 96830484 509673472 3.9625749588 3.9770455360 4.0084466934 507 1311867735.5293200016 0.0557891950 0.0897831229 0.2376661599 0.0051536357 0.0047970000 0.0003860000 0.0018520000 0.0000040000 0.0000030000 0.0012160000 36431501 96830484 509673472 3.9630970955 3.9769959450 4.0087900162 508 1311867735.5632629395 0.0554933846 0.0897156234 0.2376661599 0.0051491652 0.0069680000 0.0003940000 0.0042260000 0.0000000000 0.0000040000 0.0009840000 36435285 96830484 509673472 3.9637348652 3.9764027596 4.0090346336 509 1311867735.5976569653 0.0560392365 0.0896494616 0.2376661599 0.0051446200 0.0057110000 0.0003860000 0.0021820000 0.0000030000 0.0000030000 0.0017690000 36439013 96830484 509673472 3.9633743763 3.9765882492 4.0091943741 510 1311867735.6363260746 0.0583962686 0.0895881808 0.2376661599 0.0051448083 0.0073150000 0.0004400000 0.0042200000 0.0000000000 0.0000040000 0.0009880000 36442797 96830484 509673472 3.9613523483 3.9758312702 4.0094447136 511 1311867735.6626520157 0.0577802099 0.0895259343 0.2376661599 0.0051442278 0.0069040000 0.0004250000 0.0038790000 0.0000030000 0.0000040000 0.0012220000 36446357 96830484 509673472 3.9623196125 3.9749469757 4.0092415810 512 1311867735.6952130795 0.0556768365 0.0894598227 0.2376661599 0.0051437204 0.0053230000 0.0003940000 0.0025250000 0.0000000000 0.0000040000 0.0009950000 36450029 96830484 509673472 3.9644815922 3.9750032425 4.0086579323 513 1311867735.7291250229 0.0555143431 0.0893936522 0.2376661599 0.0051422754 0.0115550000 0.0005720000 0.0047370000 0.0000150000 0.0000140000 0.0024600000 36502909 96830484 509673472 3.9647939205 3.9754769802 4.0084366798 514 1311867735.7631659508 0.0563937537 0.0893294501 0.2376661599 0.0051420344 0.0064280000 0.0004310000 0.0029440000 0.0000000000 0.0000070000 0.0010570000 36609093 96830484 509673472 3.9638335705 3.9769465923 4.0085415840 515 1311867735.7963778973 0.0563974306 0.0892655044 0.2376661599 0.0051428373 0.0078410000 0.0004250000 0.0042930000 0.0000040000 0.0000050000 0.0012370000 36612765 96830484 509673472 3.9640810490 3.9768595695 4.0084919930 516 1311867735.8277759552 0.0567899644 0.0892025673 0.2376661599 0.0051459858 0.0054370000 0.0004110000 0.0025510000 0.0000000000 0.0000040000 0.0009870000 36616381 96830484 509673472 3.9638307095 3.9778218269 4.0085406303 517 1311867735.8638889790 0.0580099300 0.0891422334 0.2376661599 0.0051423310 0.0073810000 0.0003900000 0.0038850000 0.0000040000 0.0000030000 0.0017480000 36619997 96830484 509673472 3.9627542496 3.9781029224 4.0089817047 518 1311867735.8951849937 0.0580774695 0.0890822628 0.2376661599 0.0051384300 0.0069730000 0.0003900000 0.0042290000 0.0000000000 0.0000030000 0.0009880000 36623669 96830484 509673472 3.9627075195 3.9786217213 4.0094799995 519 1311867735.9322230816 0.0589535646 0.0890242114 0.2376661599 0.0051353527 0.0084300000 0.0005000000 0.0037890000 0.0000070000 0.0000070000 0.0013720000 36627509 96830484 509673472 3.9618029594 3.9796001911 4.0102128983 520 1311867735.9623689651 0.0592838414 0.0889670184 0.2376661599 0.0051328038 0.0060710000 0.0004220000 0.0029250000 0.0000010000 0.0000060000 0.0010110000 36631125 96830484 509673472 3.9612386227 3.9800078869 4.0105671883 521 1311867735.9945859909 0.0584673695 0.0889084778 0.2376661599 0.0051295217 0.0057880000 0.0003950000 0.0022030000 0.0000040000 0.0000030000 0.0017610000 36634741 96830484 509673472 3.9619333744 3.9804103374 4.0108447075 522 1311867736.0290079117 0.0564179905 0.0888462354 0.2376661599 0.0051283219 0.0087860000 0.0004860000 0.0044860000 0.0000010000 0.0000080000 0.0011370000 36638525 96830484 509673472 3.9638752937 3.9809978008 4.0109634399 523 1311867736.0642199516 0.0563434027 0.0887840885 0.2376661599 0.0051250444 0.0077430000 0.0004240000 0.0043220000 0.0000040000 0.0000040000 0.0012460000 36642309 96830484 509673472 3.9639945030 3.9804513454 4.0110979080 524 1311867736.0946779251 0.0562344268 0.0887219709 0.2376661599 0.0051221749 0.0070730000 0.0004100000 0.0042540000 0.0000000000 0.0000030000 0.0009930000 36645869 96830484 509673472 3.9640119076 3.9809482098 4.0114793777 525 1311867736.1299190521 0.0565999523 0.0886607861 0.2376661599 0.0051259407 0.0077950000 0.0003980000 0.0042070000 0.0000040000 0.0000040000 0.0017620000 36649653 96830484 509673472 3.9634861946 3.9808635712 4.0114922523 526 1311867736.1631360054 0.0570936799 0.0886007726 0.2376661599 0.0051224900 0.0069920000 0.0003960000 0.0042140000 0.0000000000 0.0000030000 0.0009840000 36653437 96830484 509673472 3.9626605511 3.9807775021 4.0118665695 527 1311867736.1942429543 0.0590996444 0.0885447932 0.2376661599 0.0051273527 0.0071770000 0.0003920000 0.0041830000 0.0000030000 0.0000040000 0.0012140000 36656997 96830484 509673472 3.9605162144 3.9810979366 4.0119175911 528 1311867736.2298679352 0.0585840382 0.0884880493 0.2376661599 0.0051302893 0.0059430000 0.0003930000 0.0031980000 0.0000010000 0.0000040000 0.0009760000 36660781 96830484 509673472 3.9604222775 3.9814355373 4.0121641159 529 1311867736.2633900642 0.0561544970 0.0884269273 0.2376661599 0.0051359058 0.0096030000 0.0005860000 0.0032680000 0.0000170000 0.0000140000 0.0021050000 36664509 96830484 509673472 3.9627137184 3.9815790653 4.0120835304 530 1311867736.2995250225 0.0579258911 0.0883693782 0.2376661599 0.0051328572 0.0077690000 0.0004410000 0.0043330000 0.0000010000 0.0000050000 0.0010180000 36668293 96830484 509673472 3.9609706402 3.9794678688 4.0123229027 531 1311867736.3304500580 0.0578202382 0.0883118468 0.2376661599 0.0051336426 0.0063510000 0.0004230000 0.0032080000 0.0000030000 0.0000040000 0.0012120000 36671853 96830484 509673472 3.9608509541 3.9810986519 4.0127201080 532 1311867736.3637149334 0.0598006435 0.0882582544 0.2376661599 0.0051314622 0.0088180000 0.0005020000 0.0044830000 0.0000010000 0.0000070000 0.0011210000 36675581 96830484 509673472 3.9589030743 3.9803113937 4.0130276680 533 1311867736.3943159580 0.0630720034 0.0882110006 0.2376661599 0.0051284989 0.0082670000 0.0004250000 0.0042730000 0.0000040000 0.0000040000 0.0017800000 36679141 96830484 509673472 3.9557662010 3.9787356853 4.0132021904 534 1311867736.4313519001 0.0643767715 0.0881663672 0.2376661599 0.0051462629 0.0060520000 0.0004050000 0.0032310000 0.0000010000 0.0000040000 0.0009810000 36683037 96830484 509673472 3.9546995163 3.9799053669 4.0138416290 535 1311867736.4625089169 0.0660856292 0.0881250948 0.2376661599 0.0051430314 0.0078610000 0.0005030000 0.0031050000 0.0000070000 0.0000070000 0.0013560000 36686709 96830484 509673472 3.9528143406 3.9798300266 4.0139641762 536 1311867736.4987530708 0.0676325187 0.0880868624 0.2376661599 0.0051389716 0.0064940000 0.0004250000 0.0032690000 0.0000000000 0.0000050000 0.0010180000 36690437 96830484 509673472 3.9514992237 3.9784734249 4.0141458511 537 1311867736.5321619511 0.0711495280 0.0880553217 0.2376661599 0.0051554708 0.0074670000 0.0004020000 0.0038800000 0.0000040000 0.0000030000 0.0017580000 36694165 96830484 509673472 3.9479489326 3.9798724651 4.0145959854 538 1311867736.5634689331 0.0709435269 0.0880235154 0.2376661599 0.0051511069 0.0060850000 0.0004070000 0.0032280000 0.0000000000 0.0000030000 0.0009930000 36697837 96830484 509673472 3.9481739998 3.9792037010 4.0148410797 539 1311867736.5958600044 0.0729951262 0.0879956334 0.2376661599 0.0051473452 0.0073700000 0.0004950000 0.0030300000 0.0000070000 0.0000070000 0.0013560000 36701509 96830484 509673472 3.9460937977 3.9772324562 4.0148892403 540 1311867736.6320459843 0.0750953183 0.0879717440 0.2376661599 0.0051585220 0.0054650000 0.0004150000 0.0022490000 0.0000010000 0.0000050000 0.0010200000 36705293 96830484 509673472 3.9441831112 3.9785962105 4.0152173042 541 1311867736.6635379791 0.0742043406 0.0879462959 0.2376661599 0.0051740418 0.0090180000 0.0004930000 0.0037950000 0.0000080000 0.0000080000 0.0019550000 36708965 96830484 509673472 3.9446470737 3.9779796600 4.0149154663 542 1311867736.6945500374 0.0787602440 0.0879293475 0.2376661599 0.0051754270 0.0064940000 0.0004300000 0.0032780000 0.0000010000 0.0000050000 0.0010080000 36712525 96830484 509673472 3.9402182102 3.9756786823 4.0150794983 543 1311867736.7332150936 0.0802609622 0.0879152252 0.2376661599 0.0051734726 0.0086920000 0.0004990000 0.0044500000 0.0000070000 0.0000070000 0.0013430000 36716365 96830484 509673472 3.9386558533 3.9763405323 4.0151462555 544 1311867736.7636179924 0.0812800378 0.0879030282 0.2376661599 0.0051726222 0.0085650000 0.0004850000 0.0044880000 0.0000010000 0.0000080000 0.0011260000 36720037 96830484 509673472 3.9382455349 3.9767994881 4.0151934624 545 1311867736.7952749729 0.0843521878 0.0878965129 0.2376661599 0.0051711475 0.0082400000 0.0004220000 0.0042860000 0.0000050000 0.0000040000 0.0018170000 36723653 96830484 509673472 3.9350678921 3.9760000706 4.0153350830 546 1311867736.8325269222 0.0887039453 0.0878979917 0.2376661599 0.0051875553 0.0060230000 0.0003920000 0.0032210000 0.0000010000 0.0000040000 0.0009910000 36727437 96830484 509673472 3.9311161041 3.9766254425 4.0161337852 547 1311867736.8640279770 0.0913921520 0.0879043795 0.2376661599 0.0051944447 0.0072460000 0.0003880000 0.0042120000 0.0000040000 0.0000030000 0.0012210000 36731165 96830484 509673472 3.9286024570 3.9785478115 4.0164995193 548 1311867736.8945000172 0.0923446044 0.0879124821 0.2376661599 0.0051922087 0.0091120000 0.0004980000 0.0045230000 0.0000010000 0.0000080000 0.0011300000 36734725 96830484 509673472 3.9279336929 3.9770362377 4.0166387558 549 1311867736.9362800121 0.0961162373 0.0879274252 0.2376661599 0.0051959065 0.0098350000 0.0004860000 0.0045150000 0.0000070000 0.0000070000 0.0019730000 36738677 96830484 509673472 3.9244551659 3.9778108597 4.0168242455 550 1311867736.9632000923 0.0987655669 0.0879471309 0.2376661599 0.0052002026 0.0075570000 0.0004230000 0.0043160000 0.0000010000 0.0000050000 0.0010160000 36742237 96830484 509673472 3.9219613075 3.9795985222 4.0181341171 551 1311867736.9954400063 0.0996966735 0.0879684550 0.2376661599 0.0052006198 0.0063660000 0.0004090000 0.0032320000 0.0000040000 0.0000040000 0.0012270000 36745909 96830484 509673472 3.9212422371 3.9779288769 4.0181112289 552 1311867737.0307478905 0.1009816900 0.0879920297 0.2376661599 0.0051966704 0.0088270000 0.0004980000 0.0041850000 0.0000010000 0.0000080000 0.0011420000 36749637 96830484 509673472 3.9200198650 3.9775021076 4.0184469223 553 1311867737.0629029274 0.1016862765 0.0880167932 0.2376661599 0.0051941777 0.0082960000 0.0004290000 0.0043290000 0.0000040000 0.0000040000 0.0018210000 36753365 96830484 509673472 3.9195289612 3.9787144661 4.0190753937 554 1311867737.0977239609 0.1031900197 0.0880441817 0.2376661599 0.0051903219 0.0071110000 0.0004120000 0.0042530000 0.0000000000 0.0000040000 0.0009930000 36757093 96830484 509673472 3.9180295467 3.9779894352 4.0190658569 555 1311867737.1300530434 0.1047710776 0.0880743203 0.2376661599 0.0051865176 0.0084620000 0.0005090000 0.0038220000 0.0000090000 0.0000070000 0.0013580000 36760709 96830484 509673472 3.9164469242 3.9772489071 4.0190238953 556 1311867737.1655049324 0.1043436602 0.0881035817 0.2376661599 0.0051836269 0.0054620000 0.0004220000 0.0022630000 0.0000010000 0.0000060000 0.0010100000 36764493 96830484 509673472 3.9170193672 3.9788525105 4.0192551613 557 1311867737.1952710152 0.1062405407 0.0881361435 0.2376661599 0.0051800177 0.0078630000 0.0004090000 0.0042770000 0.0000030000 0.0000030000 0.0017900000 36768109 96830484 509673472 3.9152541161 3.9782621861 4.0191192627 558 1311867737.2333149910 0.1065997556 0.0881692325 0.2376661599 0.0051756539 0.0069920000 0.0004050000 0.0042440000 0.0000000000 0.0000040000 0.0009830000 36772005 96830484 509673472 3.9151203632 3.9775962830 4.0193033218 559 1311867737.2693018913 0.1074459255 0.0882037167 0.2376661599 0.0051765481 0.0084580000 0.0005170000 0.0038210000 0.0000080000 0.0000080000 0.0013310000 36775733 96830484 509673472 3.9147911072 3.9785666466 4.0192284584 560 1311867737.2957379818 0.1085268185 0.0882400080 0.2376661599 0.0051737091 0.0076990000 0.0004360000 0.0043470000 0.0000010000 0.0000050000 0.0010000000 36779237 96830484 509673472 3.9139800072 3.9789433479 4.0196776390 561 1311867737.3316531181 0.1090425700 0.0882770892 0.2376661599 0.0051697091 0.0076120000 0.0004120000 0.0039430000 0.0000030000 0.0000040000 0.0017670000 36783077 96830484 509673472 3.9137136936 3.9780685902 4.0199003220 562 1311867737.3659460545 0.1087687388 0.0883135512 0.2376661599 0.0051652633 0.0064060000 0.0004020000 0.0035800000 0.0000000000 0.0000030000 0.0009760000 36786749 96830484 509673472 3.9138896465 3.9783515930 4.0201148987 563 1311867737.3967239857 0.1099589244 0.0883519977 0.2376661599 0.0051618345 0.0056340000 0.0003980000 0.0025680000 0.0000040000 0.0000030000 0.0012150000 36790421 96830484 509673472 3.9128789902 3.9784824848 4.0204405785 564 1311867737.4355359077 0.1115412936 0.0883931134 0.2376661599 0.0051586859 0.0060810000 0.0004000000 0.0032480000 0.0000000000 0.0000030000 0.0009720000 36794261 96830484 509673472 3.9114251137 3.9786999226 4.0211000443 565 1311867737.4691100121 0.1125725880 0.0884359090 0.2376661599 0.0051544969 0.0065990000 0.0004040000 0.0029040000 0.0000040000 0.0000040000 0.0017690000 36797989 96830484 509673472 3.9105577469 3.9785017967 4.0217399597 566 1311867737.4959459305 0.1132820174 0.0884798067 0.2376661599 0.0051502651 0.0110670000 0.0005920000 0.0048170000 0.0000020000 0.0000140000 0.0015230000 36801493 96830484 509673472 3.9097459316 3.9785778522 4.0221118927 567 1311867737.5353999138 0.1158576161 0.0885280921 0.2376661599 0.0051487664 0.0069020000 0.0004720000 0.0030040000 0.0000060000 0.0000060000 0.0012880000 36805389 96830484 509673472 3.9075083733 3.9778952599 4.0231280327 568 1311867737.5654399395 0.1155754104 0.0885757106 0.2376661599 0.0051449231 0.0060410000 0.0004230000 0.0029450000 0.0000000000 0.0000050000 0.0009860000 36808949 96830484 509673472 3.9083285332 3.9781177044 4.0232977867 569 1311867737.5958089828 0.1165885627 0.0886249423 0.2376661599 0.0051408577 0.0077800000 0.0004600000 0.0036060000 0.0000040000 0.0000030000 0.0019090000 36812621 96830484 509673472 3.9076960087 3.9777448177 4.0239191055 570 1311867737.6330978870 0.1179726347 0.0886764295 0.2376661599 0.0051367546 0.0071750000 0.0004450000 0.0042780000 0.0000000000 0.0000040000 0.0009730000 36816461 96830484 509673472 3.9066126347 3.9777667522 4.0243353844 571 1311867737.6624519825 0.1187152043 0.0887290368 0.2376661599 0.0051327520 0.0077690000 0.0005130000 0.0027990000 0.0000110000 0.0000090000 0.0013870000 36820077 96830484 509673472 3.9061102867 3.9768252373 4.0245995522 572 1311867737.7032339573 0.1201641783 0.0887839933 0.2376661599 0.0051284498 0.0093240000 0.0005220000 0.0045730000 0.0000010000 0.0000080000 0.0011260000 36823917 96830484 509673472 3.9050137997 3.9760739803 4.0251464844 573 1311867737.7314720154 0.1203040853 0.0888390022 0.2376661599 0.0051241402 0.0061420000 0.0004470000 0.0019490000 0.0000050000 0.0000050000 0.0017950000 36827477 96830484 509673472 3.9051427841 3.9762842655 4.0253906250 574 1311867737.7658560276 0.1217694730 0.0888963724 0.2376661599 0.0051212076 0.0070860000 0.0004110000 0.0043120000 0.0000010000 0.0000040000 0.0009820000 36831205 96830484 509673472 3.9040732384 3.9760768414 4.0258197784 575 1311867737.8011269569 0.1216471046 0.0889533302 0.2376661599 0.0051180259 0.0078450000 0.0005050000 0.0031530000 0.0000100000 0.0000090000 0.0013300000 36834989 96830484 509673472 3.9043502808 3.9764094353 4.0258407593 576 1311867737.8323190212 0.1212611422 0.0890094201 0.2376661599 0.0051137763 0.0063300000 0.0004440000 0.0030330000 0.0000000000 0.0000050000 0.0009870000 36838661 96830484 509673472 3.9049808979 3.9763498306 4.0261487961 577 1311867737.8633110523 0.1228430420 0.0890680573 0.2376661599 0.0051193247 0.0086940000 0.0005160000 0.0038510000 0.0000070000 0.0000070000 0.0018900000 36842277 96830484 509673472 3.9041609764 3.9761662483 4.0271821022 578 1311867737.9004418850 0.1245300770 0.0891294102 0.2376661599 0.0051158838 0.0074790000 0.0004330000 0.0043800000 0.0000010000 0.0000050000 0.0009670000 36846005 96830484 509673472 3.9028940201 3.9755942822 4.0277867317 579 1311867737.9305500984 0.1246011555 0.0891906740 0.2376661599 0.0051158088 0.0058210000 0.0004120000 0.0025810000 0.0000030000 0.0000030000 0.0012080000 36849621 96830484 509673472 3.9030873775 3.9751219749 4.0282940865 580 1311867737.9630560875 0.1253125668 0.0892529532 0.2376661599 0.0051118419 0.0054330000 0.0004030000 0.0025950000 0.0000000000 0.0000030000 0.0009570000 36853349 96830484 509673472 3.9028418064 3.9750092030 4.0288190842 581 1311867737.9996941090 0.1266450286 0.0893173113 0.2376661599 0.0051082384 0.0103520000 0.0005990000 0.0025900000 0.0000150000 0.0000130000 0.0024310000 36857133 96830484 509673472 3.9019775391 3.9742963314 4.0296635628 582 1311867738.0315399170 0.1278512180 0.0893835208 0.2376661599 0.0051053922 0.0080090000 0.0004610000 0.0044460000 0.0000010000 0.0000060000 0.0009990000 36860805 96830484 509673472 3.9010922909 3.9750425816 4.0303578377 583 1311867738.0629770756 0.1266505569 0.0894474436 0.2376661599 0.0051023782 0.0076590000 0.0004230000 0.0043590000 0.0000040000 0.0000040000 0.0012010000 36864477 96830484 509673472 3.9029352665 3.9765701294 4.0314078331 584 1311867738.0998299122 0.1272705644 0.0895122093 0.2376661599 0.0050998125 0.0057230000 0.0004040000 0.0029350000 0.0000000000 0.0000030000 0.0009520000 36868205 96830484 509673472 3.9029338360 3.9750547409 4.0321736336 585 1311867738.1308510303 0.1286209673 0.0895790618 0.2376661599 0.0050977785 0.0084980000 0.0005150000 0.0031480000 0.0000080000 0.0000070000 0.0019030000 36871821 96830484 509673472 3.9021370411 3.9739284515 4.0329046249 586 1311867738.1635079384 0.1286810338 0.0896457888 0.2376661599 0.0050939364 0.0058760000 0.0004240000 0.0026500000 0.0000010000 0.0000060000 0.0009640000 36875549 96830484 509673472 3.9025456905 3.9735269547 4.0335102081 587 1311867738.1992070675 0.1312555820 0.0897166743 0.2376661599 0.0050917915 0.0066810000 0.0004130000 0.0036410000 0.0000030000 0.0000030000 0.0011900000 36879277 96830484 509673472 3.9007232189 3.9729046822 4.0346441269 588 1311867738.2306089401 0.1309485883 0.0897867966 0.2376661599 0.0050908040 0.0053770000 0.0003990000 0.0026080000 0.0000010000 0.0000030000 0.0009440000 36882949 96830484 509673472 3.9014365673 3.9713594913 4.0347986221 589 1311867738.2632689476 0.1327251345 0.0898596970 0.2376661599 0.0050890837 0.0118210000 0.0005870000 0.0048580000 0.0000150000 0.0000140000 0.0023310000 36886677 96830484 509673472 3.9001743793 3.9702136517 4.0351309776 590 1311867738.3008689880 0.1338518560 0.0899342600 0.2376661599 0.0050853641 0.0089190000 0.0004970000 0.0042710000 0.0000000000 0.0000080000 0.0010940000 36890461 96830484 509673472 3.8996336460 3.9698112011 4.0351786613 591 1311867738.3339769840 0.1351321191 0.0900107369 0.2376661599 0.0050828763 0.0079030000 0.0004270000 0.0044200000 0.0000050000 0.0000050000 0.0012090000 36894133 96830484 509673472 3.8988671303 3.9693741798 4.0352911949 592 1311867738.3651630878 0.1371155679 0.0900903058 0.2376661599 0.0050799555 0.0062410000 0.0004140000 0.0033250000 0.0000010000 0.0000040000 0.0009610000 36897805 96830484 509673472 3.8970952034 3.9693963528 4.0352945328 593 1311867738.3995900154 0.1395906061 0.0901737802 0.2376661599 0.0050786069 0.0079270000 0.0004070000 0.0043500000 0.0000040000 0.0000030000 0.0017240000 36901589 96830484 509673472 3.8951673508 3.9703376293 4.0356259346 594 1311867738.4334011078 0.1386613250 0.0902554091 0.2376661599 0.0050753015 0.0054140000 0.0004030000 0.0026350000 0.0000000000 0.0000030000 0.0009420000 36905317 96830484 509673472 3.8962566853 3.9710924625 4.0353231430 595 1311867738.4643430710 0.1425564736 0.0903433100 0.2376661599 0.0050730061 0.0084760000 0.0005110000 0.0035600000 0.0000110000 0.0000090000 0.0013380000 36908933 96830484 509673472 3.8931901455 3.9699461460 4.0356416702 596 1311867738.5000250340 0.1407785118 0.0904279328 0.2376661599 0.0050717793 0.0077390000 0.0004470000 0.0044410000 0.0000000000 0.0000050000 0.0009880000 36912717 96830484 509673472 3.8956534863 3.9715588093 4.0358805656 597 1311867738.5332009792 0.1419045925 0.0905141584 0.2376661599 0.0050683079 0.0070210000 0.0004120000 0.0033310000 0.0000040000 0.0000030000 0.0017510000 36916389 96830484 509673472 3.8953111172 3.9726500511 4.0361657143 598 1311867738.5634350777 0.1422925293 0.0906007443 0.2376661599 0.0050656165 0.0087850000 0.0004980000 0.0034160000 0.0000010000 0.0000100000 0.0014520000 36920061 96830484 509673472 3.8956341743 3.9709610939 4.0363683701 599 1311867738.6022439003 0.1421053708 0.0906867287 0.2376661599 0.0050637332 0.0064580000 0.0006400000 0.0026780000 0.0000050000 0.0000050000 0.0012280000 36923901 96830484 509673472 3.8967554569 3.9706735611 4.0362915993 600 1311867738.6328980923 0.1434067190 0.0907745953 0.2376661599 0.0050618509 0.0062400000 0.0004180000 0.0033390000 0.0000000000 0.0000030000 0.0009550000 36927517 96830484 509673472 3.8964157104 3.9720737934 4.0366120338 601 1311867738.6628730297 0.1437251568 0.0908626994 0.2376661599 0.0050608221 0.0084040000 0.0005000000 0.0028520000 0.0000100000 0.0000090000 0.0019230000 36931189 96830484 509673472 3.8968515396 3.9716255665 4.0363001823 602 1311867738.6996099949 0.1461406499 0.0909545232 0.2376661599 0.0050582574 0.0063170000 0.0004250000 0.0030340000 0.0000010000 0.0000050000 0.0009850000 36934973 96830484 509673472 3.8954689503 3.9702982903 4.0366945267 603 1311867738.7314729691 0.1465459913 0.0910467147 0.2376661599 0.0050674799 0.0058090000 0.0004070000 0.0026430000 0.0000040000 0.0000040000 0.0011990000 36938645 96830484 509673472 3.8959627151 3.9715268612 4.0369138718 604 1311867738.7626600266 0.1486848146 0.0911421421 0.2376661599 0.0050653723 0.0081750000 0.0005100000 0.0028450000 0.0000010000 0.0000100000 0.0012240000 36942261 96830484 509673472 3.8948791027 3.9713551998 4.0375022888 605 1311867738.8032259941 0.1494951844 0.0912385934 0.2376661599 0.0050682882 0.0074790000 0.0004490000 0.0030700000 0.0000050000 0.0000050000 0.0017910000 36946157 96830484 509673472 3.8951237202 3.9710428715 4.0376200676 606 1311867738.8306779861 0.1506614983 0.0913366510 0.2376661599 0.0050699654 0.0053180000 0.0004120000 0.0022870000 0.0000000000 0.0000040000 0.0009820000 36949717 96830484 509673472 3.8946306705 3.9714725018 4.0378932953 607 1311867738.8639259338 0.1497069746 0.0914328129 0.2376661599 0.0050668050 0.0053370000 0.0004020000 0.0022690000 0.0000030000 0.0000040000 0.0012010000 36953445 96830484 509673472 3.8964335918 3.9721627235 4.0380444527 608 1311867738.9000120163 0.1502955556 0.0915296267 0.2376661599 0.0050679732 0.0112670000 0.0005870000 0.0048970000 0.0000020000 0.0000150000 0.0015050000 36957229 96830484 509673472 3.8966381550 3.9718887806 4.0379891396 609 1311867738.9307610989 0.1535441726 0.0916314568 0.2376661599 0.0050698458 0.0071370000 0.0004470000 0.0027030000 0.0000060000 0.0000050000 0.0018180000 36960845 96830484 509673472 3.8940012455 3.9712398052 4.0385398865 610 1311867738.9664750099 0.1543338746 0.0917342476 0.2376661599 0.0050677928 0.0057380000 0.0004180000 0.0026630000 0.0000000000 0.0000040000 0.0009770000 36964629 96830484 509673472 3.8937935829 3.9723119736 4.0389375687 611 1311867738.9989941120 0.1559656411 0.0918393727 0.2376661599 0.0050640159 0.0067700000 0.0004010000 0.0036760000 0.0000030000 0.0000030000 0.0012190000 36968357 96830484 509673472 3.8927309513 3.9722018242 4.0390911102 612 1311867739.0329539776 0.1551558226 0.0919428309 0.2376661599 0.0050637879 0.0078370000 0.0005090000 0.0031710000 0.0000010000 0.0000070000 0.0011090000 36972085 96830484 509673472 3.8939816952 3.9707472324 4.0389175415 613 1311867739.0664470196 0.1543550193 0.0920446453 0.2376661599 0.0050615382 0.0074660000 0.0004250000 0.0033710000 0.0000040000 0.0000040000 0.0017830000 36975757 96830484 509673472 3.8953433037 3.9714572430 4.0391678810 614 1311867739.0997900963 0.1544148624 0.0921462254 0.2376661599 0.0050585586 0.0061930000 0.0004150000 0.0033180000 0.0000000000 0.0000040000 0.0009730000 36979317 96830484 509673472 3.8957593441 3.9727900028 4.0393724442 615 1311867739.1321549416 0.1550160199 0.0922484527 0.2376661599 0.0050565981 0.0090690000 0.0004980000 0.0045900000 0.0000070000 0.0000070000 0.0013490000 36982933 96830484 509673472 3.8955895901 3.9719529152 4.0398535728 616 1311867739.1687150002 0.1551064402 0.0923504949 0.2376661599 0.0050532051 0.0076840000 0.0004290000 0.0044180000 0.0000000000 0.0000040000 0.0009920000 36986717 96830484 509673472 3.8957235813 3.9719498158 4.0401844978 617 1311867739.1999289989 0.1550600529 0.0924521311 0.2376661599 0.0050527987 0.0088620000 0.0004970000 0.0031890000 0.0000090000 0.0000110000 0.0019400000 36990333 96830484 509673472 3.8960120678 3.9724926949 4.0410184860 618 1311867739.2313010693 0.1556772441 0.0925544372 0.2376661599 0.0050497731 0.0070440000 0.0004270000 0.0037150000 0.0000010000 0.0000050000 0.0009950000 36993949 96830484 509673472 3.8954658508 3.9718582630 4.0412316322 619 1311867739.2672259808 0.1565302163 0.0926577906 0.2376661599 0.0050460736 0.0062010000 0.0004070000 0.0029650000 0.0000040000 0.0000040000 0.0012240000 36997789 96830484 509673472 3.8944416046 3.9714024067 4.0413174629 620 1311867739.2996931076 0.1557616293 0.0927595710 0.2376661599 0.0050481895 0.0058070000 0.0003950000 0.0029340000 0.0000010000 0.0000030000 0.0009730000 37001461 96830484 509673472 3.8952145576 3.9709525108 4.0417113304 621 1311867739.3319859505 0.1559976339 0.0928614036 0.2376661599 0.0050471777 0.0093800000 0.0004960000 0.0041930000 0.0000080000 0.0000070000 0.0019850000 37005133 96830484 509673472 3.8951072693 3.9720849991 4.0422725677 622 1311867739.3670029640 0.1555503905 0.0929621898 0.2376661599 0.0050453641 0.0070500000 0.0004310000 0.0036820000 0.0000000000 0.0000050000 0.0010160000 37008861 96830484 509673472 3.8953533173 3.9716734886 4.0425581932 623 1311867739.3990058899 0.1555621624 0.0930626713 0.2376661599 0.0050415024 0.0084610000 0.0005070000 0.0028340000 0.0000090000 0.0000100000 0.0014840000 37012589 96830484 509673472 3.8950817585 3.9723012447 4.0427942276 624 1311867739.4311320782 0.1538738161 0.0931601250 0.2376661599 0.0050380325 0.0083010000 0.0004970000 0.0038360000 0.0000010000 0.0000080000 0.0011240000 37016205 96830484 509673472 3.8968486786 3.9726345539 4.0431146622 625 1311867739.4668490887 0.1559761018 0.0932606306 0.2376661599 0.0050352325 0.0074730000 0.0004210000 0.0033360000 0.0000040000 0.0000040000 0.0017980000 37019989 96830484 509673472 3.8947598934 3.9717302322 4.0438075066 626 1311867739.4988598824 0.1566570550 0.0933619028 0.2376661599 0.0050384775 0.0068010000 0.0004090000 0.0038650000 0.0000010000 0.0000040000 0.0009840000 37023661 96830484 509673472 3.8941097260 3.9709777832 4.0445652008 627 1311867739.5316400528 0.1564499885 0.0934625218 0.2376661599 0.0050348303 0.0091200000 0.0005060000 0.0045790000 0.0000070000 0.0000070000 0.0013680000 37027277 96830484 509673472 3.8944365978 3.9718527794 4.0445966721 628 1311867739.5670249462 0.1594845951 0.0935676525 0.2376661599 0.0050351384 0.0060080000 0.0004300000 0.0026340000 0.0000000000 0.0000050000 0.0009990000 37031061 96830484 509673472 3.8915972710 3.9721362591 4.0458283424 629 1311867739.5990490913 0.1615070105 0.0936756642 0.2376661599 0.0050318456 0.0063160000 0.0004010000 0.0025780000 0.0000030000 0.0000040000 0.0017850000 37034733 96830484 509673472 3.8894951344 3.9707567692 4.0465097427 630 1311867739.6325490475 0.1625003517 0.0937849097 0.2376661599 0.0050282460 0.0083670000 0.0004940000 0.0031890000 0.0000010000 0.0000100000 0.0012430000 37038461 96830484 509673472 3.8883540630 3.9717135429 4.0472321510 631 1311867739.6706740856 0.1640571356 0.0938962761 0.2376661599 0.0050260615 0.0080270000 0.0004370000 0.0043960000 0.0000050000 0.0000050000 0.0012680000 37042301 96830484 509673472 3.8864078522 3.9713113308 4.0476264954 632 1311867739.7001221180 0.1648952961 0.0940086164 0.2376661599 0.0050221341 0.0068170000 0.0004070000 0.0038830000 0.0000010000 0.0000040000 0.0009690000 37045917 96830484 509673472 3.8856873512 3.9712042809 4.0488719940 633 1311867739.7323939800 0.1655956060 0.0941217080 0.2376661599 0.0050193523 0.0066170000 0.0003960000 0.0029410000 0.0000040000 0.0000030000 0.0017610000 37049589 96830484 509673472 3.8848237991 3.9720933437 4.0494842529 634 1311867739.7662999630 0.1678943634 0.0942380686 0.2376661599 0.0050176551 0.0061880000 0.0003970000 0.0032680000 0.0000000000 0.0000040000 0.0009760000 37053317 96830484 509673472 3.8823549747 3.9709818363 4.0502500534 635 1311867739.8016180992 0.1686804295 0.0943553007 0.2376661599 0.0050158510 0.0100830000 0.0005070000 0.0046010000 0.0000110000 0.0000090000 0.0014840000 37057101 96830484 509673472 3.8812713623 3.9693803787 4.0507330894 636 1311867739.8325679302 0.1697325855 0.0944738184 0.2376661599 0.0050237643 0.0075120000 0.0004370000 0.0040440000 0.0000010000 0.0000070000 0.0010020000 37060717 96830484 509673472 3.8801376820 3.9715478420 4.0515904427 637 1311867739.8701560497 0.1700579375 0.0945924748 0.2376661599 0.0050205724 0.0074230000 0.0004040000 0.0036350000 0.0000040000 0.0000040000 0.0017600000 37064501 96830484 509673472 3.8793706894 3.9705317020 4.0522217751 638 1311867739.9036860466 0.1701434255 0.0947108932 0.2376661599 0.0050190451 0.0071760000 0.0003980000 0.0043020000 0.0000000000 0.0000040000 0.0009640000 37068285 96830484 509673472 3.8784918785 3.9690153599 4.0521411896 639 1311867739.9317240715 0.1716695428 0.0948313293 0.2376661599 0.0050170109 0.0056890000 0.0003930000 0.0025770000 0.0000040000 0.0000030000 0.0012050000 37071845 96830484 509673472 3.8766202927 3.9697406292 4.0527706146 640 1311867739.9668979645 0.1720353961 0.0949519607 0.2376661599 0.0050136989 0.0083820000 0.0005050000 0.0035130000 0.0000010000 0.0000100000 0.0011210000 37075573 96830484 509673472 3.8759055138 3.9705512524 4.0530767441 641 1311867739.9987080097 0.1746838093 0.0950763473 0.2376661599 0.0050116202 0.0085870000 0.0004220000 0.0043650000 0.0000050000 0.0000040000 0.0018140000 37079301 96830484 509673472 3.8725769520 3.9691879749 4.0536999702 642 1311867740.0328791142 0.1745609939 0.0952001552 0.2376661599 0.0050081656 0.0052170000 0.0004050000 0.0022460000 0.0000000000 0.0000030000 0.0009740000 37083029 96830484 509673472 3.8721435070 3.9692606926 4.0538744926 643 1311867740.0671849251 0.1742160171 0.0953230414 0.2376661599 0.0050083982 0.0060460000 0.0003920000 0.0029190000 0.0000030000 0.0000040000 0.0012080000 37086701 96830484 509673472 3.8722901344 3.9712541103 4.0543255806 644 1311867740.0992529392 0.1757623255 0.0954479472 0.2376661599 0.0050102833 0.0104890000 0.0006630000 0.0033490000 0.0000010000 0.0000140000 0.0015040000 37090429 96830484 509673472 3.8703901768 3.9691326618 4.0544972420 645 1311867740.1347720623 0.1781608015 0.0955761842 0.2376661599 0.0050093400 0.0076090000 0.0004710000 0.0029980000 0.0000060000 0.0000060000 0.0018590000 37094101 96830484 509673472 3.8671793938 3.9674539566 4.0546398163 646 1311867740.1666491032 0.1774354726 0.0957029013 0.2376661599 0.0050094123 0.0074590000 0.0004170000 0.0043220000 0.0000010000 0.0000040000 0.0009830000 37097829 96830484 509673472 3.8678963184 3.9695444107 4.0548014641 647 1311867740.1993310452 0.1789403558 0.0958315527 0.2376661599 0.0050059066 0.0057610000 0.0004090000 0.0025720000 0.0000030000 0.0000030000 0.0012320000 37101557 96830484 509673472 3.8661010265 3.9697937965 4.0552697182 648 1311867740.2383539677 0.1785136014 0.0959591485 0.2376661599 0.0050039606 0.0077460000 0.0005080000 0.0027840000 0.0000010000 0.0000100000 0.0011180000 37105453 96830484 509673472 3.8659949303 3.9684998989 4.0550670624 649 1311867740.2664349079 0.1791272312 0.0960872965 0.2376661599 0.0050038909 0.0075850000 0.0004620000 0.0033060000 0.0000050000 0.0000050000 0.0018120000 37108957 96830484 509673472 3.8651616573 3.9695565701 4.0553374290 650 1311867740.2981588840 0.1794455051 0.0962155399 0.2376661599 0.0050018796 0.0055820000 0.0004040000 0.0025900000 0.0000000000 0.0000030000 0.0009860000 37112629 96830484 509673472 3.8646068573 3.9701473713 4.0555915833 651 1311867740.3347120285 0.1788647175 0.0963424972 0.2376661599 0.0049994599 0.0088860000 0.0004550000 0.0044620000 0.0000060000 0.0000050000 0.0012950000 37116469 96830484 509673472 3.8646531105 3.9689354897 4.0551729202 652 1311867740.3665161133 0.1768444330 0.0964659664 0.2376661599 0.0050010851 0.0074970000 0.0004170000 0.0043200000 0.0000000000 0.0000040000 0.0009840000 37120085 96830484 509673472 3.8665676117 3.9705266953 4.0547494888 653 1311867740.3993780613 0.1776795387 0.0965903363 0.2376661599 0.0049993401 0.0085020000 0.0005050000 0.0031170000 0.0000070000 0.0000110000 0.0019750000 37123757 96830484 509673472 3.8655996323 3.9692766666 4.0546746254 654 1311867740.4346680641 0.1774764806 0.0967140155 0.2376661599 0.0049967032 0.0090360000 0.0004980000 0.0045240000 0.0000010000 0.0000080000 0.0011090000 37127541 96830484 509673472 3.8659043312 3.9697272778 4.0542106628 655 1311867740.4664289951 0.1786957383 0.0968391784 0.2376661599 0.0049935193 0.0079430000 0.0004320000 0.0043550000 0.0000050000 0.0000040000 0.0012310000 37131213 96830484 509673472 3.8645355701 3.9698512554 4.0537991524 656 1311867740.4993040562 0.1792459935 0.0969647985 0.2376661599 0.0049919322 0.0084430000 0.0004940000 0.0035150000 0.0000020000 0.0000100000 0.0011130000 37134885 96830484 509673472 3.8645355701 3.9698283672 4.0538330078 657 1311867740.5354259014 0.1804887354 0.0970919278 0.2376661599 0.0049933965 0.0069550000 0.0004800000 0.0023040000 0.0000060000 0.0000050000 0.0018320000 37138669 96830484 509673472 3.8636419773 3.9695165157 4.0535650253 658 1311867740.5666589737 0.1807109714 0.0972190084 0.2376661599 0.0049896568 0.0066880000 0.0004490000 0.0036290000 0.0000000000 0.0000040000 0.0009700000 37142341 96830484 509673472 3.8635756969 3.9701988697 4.0532436371 659 1311867740.6008880138 0.1833775789 0.0973497498 0.2376661599 0.0049891951 0.0057610000 0.0004010000 0.0025740000 0.0000030000 0.0000030000 0.0012050000 37146069 96830484 509673472 3.8611071110 3.9707493782 4.0534682274 660 1311867740.6346809864 0.1827928573 0.0974792091 0.2376661599 0.0049879715 0.0083530000 0.0005110000 0.0035140000 0.0000010000 0.0000080000 0.0011410000 37149797 96830484 509673472 3.8616743088 3.9707429409 4.0532259941 661 1311867740.6665890217 0.1832825243 0.0976090174 0.2376661599 0.0049844881 0.0066210000 0.0004320000 0.0022830000 0.0000050000 0.0000050000 0.0018250000 37153469 96830484 509673472 3.8609967232 3.9706470966 4.0528883934 662 1311867740.6994900703 0.1838298738 0.0977392604 0.2376661599 0.0049815244 0.0073020000 0.0004980000 0.0024350000 0.0000010000 0.0000080000 0.0011280000 37157141 96830484 509673472 3.8603491783 3.9702236652 4.0525145531 663 1311867740.7368240356 0.1841089278 0.0978695314 0.2376661599 0.0049800502 0.0077250000 0.0004210000 0.0040170000 0.0000040000 0.0000040000 0.0012500000 37160813 96830484 509673472 3.8599705696 3.9697687626 4.0522623062 664 1311867740.7668819427 0.1849758625 0.0980007156 0.2376661599 0.0049774568 0.0080150000 0.0005110000 0.0028020000 0.0000010000 0.0000100000 0.0012650000 37164429 96830484 509673472 3.8588931561 3.9699084759 4.0520811081 665 1311867740.7996399403 0.1878261715 0.0981357915 0.2376661599 0.0049749140 0.0073450000 0.0004440000 0.0029890000 0.0000050000 0.0000050000 0.0018160000 37168157 96830484 509673472 3.8558804989 3.9689836502 4.0526509285 666 1311867740.8349099159 0.1878224164 0.0982704561 0.2376661599 0.0049712607 0.0062050000 0.0004050000 0.0031740000 0.0000000000 0.0000030000 0.0009820000 37171829 96830484 509673472 3.8556547165 3.9694302082 4.0523529053 667 1311867740.8668210506 0.1892781556 0.0984068994 0.2376661599 0.0049684615 0.0082060000 0.0005100000 0.0027990000 0.0000100000 0.0000100000 0.0014890000 37175557 96830484 509673472 3.8538913727 3.9694716930 4.0524854660 668 1311867740.8993830681 0.1901950687 0.0985443069 0.2376661599 0.0049649979 0.0063430000 0.0004440000 0.0026320000 0.0000000000 0.0000050000 0.0010110000 37179229 96830484 509673472 3.8523240089 3.9684956074 4.0523166656 669 1311867740.9399120808 0.1888623238 0.0986793114 0.2376661599 0.0049686515 0.0087710000 0.0005000000 0.0031340000 0.0000080000 0.0000070000 0.0019690000 37183181 96830484 509673472 3.8533184528 3.9700605869 4.0523290634 670 1311867740.9665501118 0.1892000884 0.0988144170 0.2376661599 0.0049657097 0.0064470000 0.0004250000 0.0029950000 0.0000010000 0.0000050000 0.0009930000 37186685 96830484 509673472 3.8525202274 3.9698066711 4.0518398285 671 1311867741.0021579266 0.1898356229 0.0989500671 0.2376661599 0.0049629087 0.0079000000 0.0005060000 0.0030930000 0.0000070000 0.0000070000 0.0013690000 37190469 96830484 509673472 3.8514425755 3.9685277939 4.0516595840 672 1311867741.0367169380 0.1887797266 0.0990837422 0.2376661599 0.0049601674 0.0064240000 0.0004170000 0.0029870000 0.0000000000 0.0000040000 0.0009900000 37194197 96830484 509673472 3.8522663116 3.9694888592 4.0513281822 673 1311867741.0666699409 0.1889273971 0.0992172394 0.2376661599 0.0049585650 0.0060350000 0.0003970000 0.0022390000 0.0000040000 0.0000040000 0.0017940000 37197813 96830484 509673472 3.8519256115 3.9706285000 4.0511965752 674 1311867741.1009640694 0.1888475418 0.0993502221 0.2376661599 0.0049624055 0.0066280000 0.0003990000 0.0036150000 0.0000000000 0.0000030000 0.0009770000 37201541 96830484 509673472 3.8514308929 3.9685239792 4.0506920815 675 1311867741.1357901096 0.1887175888 0.0994826182 0.2376661599 0.0049595977 0.0092500000 0.0005050000 0.0035240000 0.0000090000 0.0000090000 0.0015070000 37205269 96830484 509673472 3.8510279655 3.9688961506 4.0500640869 676 1311867741.1675300598 0.1881006658 0.0996137100 0.2376661599 0.0049568448 0.0067670000 0.0004420000 0.0030330000 0.0000010000 0.0000050000 0.0010120000 37208997 96830484 509673472 3.8517618179 3.9688622952 4.0499744415 677 1311867741.2014830112 0.1892011911 0.0997460401 0.2376661599 0.0049585942 0.0139660000 0.0006040000 0.0040620000 0.0000150000 0.0000140000 0.0024940000 37212669 96830484 509673472 3.8507602215 3.9680795670 4.0494937897 678 1311867741.2411060333 0.1907670349 0.0998802893 0.2376661599 0.0049604206 0.0117330000 0.0006080000 0.0033310000 0.0000020000 0.0000150000 0.0015220000 37216565 96830484 509673472 3.8489110470 3.9667708874 4.0492348671 679 1311867741.2668209076 0.1926123351 0.1000168608 0.2376661599 0.0049621862 0.0089040000 0.0004610000 0.0044560000 0.0000060000 0.0000060000 0.0012820000 37220069 96830484 509673472 3.8473076820 3.9672141075 4.0492796898 680 1311867741.2997009754 0.1933244467 0.1001540779 0.2376661599 0.0049587927 0.0066360000 0.0004620000 0.0030680000 0.0000010000 0.0000040000 0.0009930000 37223741 96830484 509673472 3.8469085693 3.9677405357 4.0490894318 681 1311867741.3348419666 0.1938201636 0.1002916198 0.2376661599 0.0049552706 0.0067490000 0.0004030000 0.0029040000 0.0000040000 0.0000030000 0.0017910000 37227525 96830484 509673472 3.8466308117 3.9682531357 4.0489845276 682 1311867741.3701419830 0.1942084730 0.1004293278 0.2376661599 0.0049525747 0.0121930000 0.0005810000 0.0033700000 0.0000020000 0.0000150000 0.0015350000 37231253 96830484 509673472 3.8466682434 3.9698624611 4.0488858223 683 1311867741.4066278934 0.1947081238 0.1005673641 0.2376661599 0.0049505816 0.0088830000 0.0005010000 0.0031450000 0.0000100000 0.0000100000 0.0014900000 37235093 96830484 509673472 3.8465237617 3.9696459770 4.0486578941 684 1311867741.4393060207 0.1935843080 0.1007033538 0.2376661599 0.0049481879 0.0070620000 0.0004460000 0.0033310000 0.0000010000 0.0000050000 0.0010150000 37238821 96830484 509673472 3.8479838371 3.9704418182 4.0485463142 685 1311867741.4667329788 0.1943169087 0.1008400160 0.2376661599 0.0049446345 0.0061850000 0.0004070000 0.0022470000 0.0000040000 0.0000040000 0.0018070000 37242325 96830484 509673472 3.8477921486 3.9704968929 4.0487289429 686 1311867741.5025069714 0.1961522400 0.1009789551 0.2376661599 0.0049431751 0.0058250000 0.0003960000 0.0028030000 0.0000010000 0.0000030000 0.0009770000 37246109 96830484 509673472 3.8465580940 3.9710581303 4.0490589142 687 1311867741.5368049145 0.1958658993 0.1011170729 0.2376661599 0.0049410585 0.0058770000 0.0004040000 0.0025510000 0.0000030000 0.0000030000 0.0012320000 37249837 96830484 509673472 3.8473327160 3.9705333710 4.0490236282 688 1311867741.5688209534 0.1949276179 0.1012534254 0.2376661599 0.0049376704 0.0090240000 0.0005080000 0.0045090000 0.0000010000 0.0000080000 0.0011310000 37253509 96830484 509673472 3.8489139080 3.9710996151 4.0490441322 689 1311867741.6046030521 0.1957367063 0.1013905564 0.2376661599 0.0049443101 0.0066230000 0.0004280000 0.0022710000 0.0000040000 0.0000040000 0.0018440000 37257237 96830484 509673472 3.8487045765 3.9718945026 4.0492296219 690 1311867741.6355440617 0.1974965483 0.1015298405 0.2376661599 0.0049416240 0.0068490000 0.0003960000 0.0038320000 0.0000000000 0.0000040000 0.0009890000 37260909 96830484 509673472 3.8473892212 3.9713330269 4.0492577553 691 1311867741.6679561138 0.1972237676 0.1016683266 0.2376661599 0.0049381694 0.0075300000 0.0003930000 0.0042810000 0.0000030000 0.0000030000 0.0012400000 37264637 96830484 509673472 3.8483786583 3.9719250202 4.0492806435 692 1311867741.7048020363 0.1982105523 0.1018078385 0.2376661599 0.0049391651 0.0055540000 0.0003970000 0.0025530000 0.0000010000 0.0000030000 0.0009840000 37268421 96830484 509673472 3.8481843472 3.9721448421 4.0491266251 693 1311867741.7345991135 0.1978627443 0.1019464459 0.2376661599 0.0049371108 0.0086150000 0.0005060000 0.0027730000 0.0000100000 0.0000100000 0.0020280000 37271981 96830484 509673472 3.8491091728 3.9715206623 4.0488209724 694 1311867741.7702169418 0.1981057376 0.1020850040 0.2376661599 0.0049337265 0.0062250000 0.0004340000 0.0026170000 0.0000010000 0.0000050000 0.0010170000 37275765 96830484 509673472 3.8497359753 3.9717116356 4.0487651825 695 1311867741.8058650494 0.1988581270 0.1022242459 0.2376661599 0.0049302183 0.0058060000 0.0004140000 0.0022400000 0.0000040000 0.0000040000 0.0012600000 37279549 96830484 509673472 3.8498911858 3.9718275070 4.0485601425 696 1311867741.8388509750 0.1985808164 0.1023626892 0.2376661599 0.0049278253 0.0063160000 0.0003980000 0.0032470000 0.0000000000 0.0000030000 0.0009870000 37283333 96830484 509673472 3.8508973122 3.9719510078 4.0483851433 697 1311867741.8683021069 0.2008323818 0.1025039657 0.2376661599 0.0049246482 0.0060360000 0.0004000000 0.0021100000 0.0000040000 0.0000030000 0.0018090000 37286893 96830484 509673472 3.8492467403 3.9721453190 4.0484776497 698 1311867741.9065721035 0.1987881064 0.1026419086 0.2376661599 0.0049222670 0.0056550000 0.0004000000 0.0025620000 0.0000010000 0.0000030000 0.0009910000 37290733 96830484 509673472 3.8518986702 3.9719090462 4.0474963188 699 1311867741.9387769699 0.2010135353 0.1027826405 0.2376661599 0.0049200090 0.0074890000 0.0003990000 0.0042680000 0.0000030000 0.0000030000 0.0012510000 37294461 96830484 509673472 3.8506751060 3.9724910259 4.0477938652 700 1311867741.9665379524 0.2010190934 0.1029229783 0.2376661599 0.0049176121 0.0123370000 0.0005750000 0.0047750000 0.0000020000 0.0000150000 0.0015340000 37297965 96830484 509673472 3.8512532711 3.9719855785 4.0471506119 701 1311867742.0029959679 0.2022820264 0.1030647173 0.2376661599 0.0049143310 0.0078760000 0.0004640000 0.0030250000 0.0000060000 0.0000060000 0.0019150000 37301749 96830484 509673472 3.8510584831 3.9715023041 4.0474076271 702 1311867742.0344839096 0.2024843246 0.1032063407 0.2376661599 0.0049112961 0.0077090000 0.0004190000 0.0043170000 0.0000010000 0.0000040000 0.0010010000 37305365 96830484 509673472 3.8517286777 3.9726555347 4.0470957756 703 1311867742.0674400330 0.2032377571 0.1033486329 0.2376661599 0.0049091268 0.0076140000 0.0004100000 0.0042640000 0.0000040000 0.0000030000 0.0012460000 37309037 96830484 509673472 3.8519182205 3.9726994038 4.0473098755 704 1311867742.1030650139 0.2036951184 0.1034911705 0.2376661599 0.0049057768 0.0073270000 0.0003970000 0.0042600000 0.0000000000 0.0000030000 0.0009890000 37312765 96830484 509673472 3.8528313637 3.9732356071 4.0472850800 705 1311867742.1348879337 0.2058393955 0.1036363453 0.2376661599 0.0049043629 0.0078160000 0.0003980000 0.0039120000 0.0000030000 0.0000030000 0.0018290000 37316381 96830484 509673472 3.8517062664 3.9729003906 4.0472869873 706 1311867742.1672229767 0.2051465660 0.1037801275 0.2376661599 0.0049020947 0.0052100000 0.0003980000 0.0022170000 0.0000000000 0.0000050000 0.0009970000 37320109 96830484 509673472 3.8530757427 3.9738798141 4.0473499298 707 1311867742.2028279305 0.2053146213 0.1039237406 0.2376661599 0.0048989788 0.0070780000 0.0003960000 0.0038110000 0.0000030000 0.0000030000 0.0012600000 37323949 96830484 509673472 3.8539288044 3.9740219116 4.0472984314 708 1311867742.2362670898 0.2052558064 0.1040668650 0.2376661599 0.0048964043 0.0095490000 0.0005050000 0.0045100000 0.0000010000 0.0000080000 0.0011630000 37327621 96830484 509673472 3.8548862934 3.9744439125 4.0471506119 709 1311867742.2674059868 0.2068498582 0.1042118340 0.2376661599 0.0048934871 0.0086820000 0.0004310000 0.0043150000 0.0000050000 0.0000040000 0.0018610000 37331293 96830484 509673472 3.8540832996 3.9730679989 4.0477705002 710 1311867742.3028159142 0.2076004744 0.1043574518 0.2376661599 0.0048915668 0.0060230000 0.0004040000 0.0028970000 0.0000010000 0.0000030000 0.0009950000 37335077 96830484 509673472 3.8539063931 3.9736425877 4.0476322174 711 1311867742.3350739479 0.2076025009 0.1045026628 0.2376661599 0.0048883443 0.0066380000 0.0004000000 0.0032380000 0.0000030000 0.0000030000 0.0012720000 37338693 96830484 509673472 3.8542509079 3.9738988876 4.0471401215 712 1311867742.3694241047 0.2088550031 0.1046492251 0.2376661599 0.0048855269 0.0053380000 0.0004030000 0.0021990000 0.0000000000 0.0000040000 0.0009990000 37342477 96830484 509673472 3.8532340527 3.9732673168 4.0471668243 713 1311867742.4062991142 0.2098972648 0.1047968380 0.2376661599 0.0048822231 0.0065540000 0.0004010000 0.0025370000 0.0000040000 0.0000120000 0.0018430000 37346261 96830484 509673472 3.8524639606 3.9734945297 4.0467209816 714 1311867742.4346439838 0.2108911276 0.1049454295 0.2376661599 0.0048788920 0.0072890000 0.0004020000 0.0041150000 0.0000010000 0.0000030000 0.0010110000 37349821 96830484 509673472 3.8518004417 3.9729006290 4.0467352867 715 1311867742.4666969776 0.2102885097 0.1050927625 0.2376661599 0.0048757008 0.0062930000 0.0003990000 0.0028770000 0.0000030000 0.0000030000 0.0012700000 37353493 96830484 509673472 3.8527030945 3.9738030434 4.0460605621 716 1311867742.5047059059 0.2106348127 0.1052401676 0.2376661599 0.0048724899 0.0060360000 0.0003990000 0.0028890000 0.0000000000 0.0000030000 0.0010050000 37357277 96830484 509673472 3.8528668880 3.9741013050 4.0459756851 717 1311867742.5359389782 0.2100702524 0.1053863741 0.2376661599 0.0048705457 0.0065720000 0.0003990000 0.0025500000 0.0000040000 0.0000030000 0.0018430000 37360949 96830484 509673472 3.8539218903 3.9752821922 4.0460157394 718 1311867742.5678529739 0.2099820822 0.1055320506 0.2376661599 0.0048680609 0.0053300000 0.0004020000 0.0021960000 0.0000010000 0.0000030000 0.0010080000 37364677 96830484 509673472 3.8544261456 3.9754371643 4.0459656715 719 1311867742.6054639816 0.2112578750 0.1056790962 0.2376661599 0.0048653697 0.0075910000 0.0003970000 0.0042280000 0.0000030000 0.0000030000 0.0012600000 37368461 96830484 509673472 3.8535375595 3.9743061066 4.0461087227 720 1311867742.6347279549 0.2108031064 0.1058251018 0.2376661599 0.0048621787 0.0074220000 0.0004010000 0.0042340000 0.0000000000 0.0000030000 0.0010190000 37372021 96830484 509673472 3.8543171883 3.9750874043 4.0460948944 721 1311867742.6724960804 0.2109668702 0.1059709295 0.2376661599 0.0048594543 0.0075720000 0.0004080000 0.0035480000 0.0000030000 0.0000040000 0.0018480000 37375917 96830484 509673472 3.8544268608 3.9745562077 4.0462250710 722 1311867742.7046229839 0.2110218108 0.1061164293 0.2376661599 0.0048560975 0.0059970000 0.0003970000 0.0028720000 0.0000000000 0.0000040000 0.0010060000 37379533 96830484 509673472 3.8546905518 3.9740598202 4.0462374687 723 1311867742.7356119156 0.2108874023 0.1062613408 0.2376661599 0.0048527528 0.0120190000 0.0005760000 0.0047720000 0.0000150000 0.0000140000 0.0017840000 37383205 96830484 509673472 3.8552482128 3.9743583202 4.0461668968 724 1311867742.7726070881 0.2110856920 0.1064061258 0.2376661599 0.0048498316 0.0082440000 0.0004950000 0.0029760000 0.0000010000 0.0000100000 0.0011760000 37387045 96830484 509673472 3.8556165695 3.9736444950 4.0461955070 725 1311867742.8034689426 0.2118535340 0.1065515705 0.2376661599 0.0048496038 0.0071290000 0.0004260000 0.0025740000 0.0000050000 0.0000050000 0.0019080000 37390717 96830484 509673472 3.8548402786 3.9737448692 4.0461020470 726 1311867742.8352251053 0.2126511484 0.1066977131 0.2376661599 0.0048493208 0.0060820000 0.0004080000 0.0028730000 0.0000000000 0.0000040000 0.0010110000 37394333 96830484 509673472 3.8548381329 3.9738209248 4.0462584496 727 1311867742.8705639839 0.2129845917 0.1068439124 0.2376661599 0.0048462368 0.0076610000 0.0004940000 0.0023870000 0.0000070000 0.0000070000 0.0014270000 37398061 96830484 509673472 3.8547501564 3.9743986130 4.0461421013 728 1311867742.9046700001 0.2125049531 0.1069890512 0.2376661599 0.0048432602 0.0069890000 0.0004170000 0.0032470000 0.0000000000 0.0000070000 0.0010270000 37401789 96830484 509673472 3.8558530807 3.9740068913 4.0463738441 729 1311867742.9382069111 0.2129346579 0.1071343813 0.2376661599 0.0048590615 0.0073210000 0.0004140000 0.0032120000 0.0000050000 0.0000040000 0.0018700000 37405573 96830484 509673472 3.8552539349 3.9743728638 4.0461726189 730 1311867742.9707310200 0.2131344825 0.1072795869 0.2376661599 0.0048605153 0.0052770000 0.0004040000 0.0020760000 0.0000000000 0.0000040000 0.0010300000 37409245 96830484 509673472 3.8555545807 3.9743280411 4.0462193489 731 1311867743.0024189949 0.2138921618 0.1074254317 0.2376661599 0.0048617276 0.0057320000 0.0004050000 0.0022080000 0.0000040000 0.0000040000 0.0012970000 37412861 96830484 509673472 3.8550128937 3.9743232727 4.0463738441 732 1311867743.0345149040 0.2131316364 0.1075698391 0.2376661599 0.0048629171 0.0053670000 0.0004020000 0.0021880000 0.0000010000 0.0000040000 0.0010110000 37416533 96830484 509673472 3.8562881947 3.9748768806 4.0462751389 733 1311867743.0722420216 0.2137179375 0.1077146523 0.2376661599 0.0048619342 0.0068700000 0.0004000000 0.0028570000 0.0000040000 0.0000040000 0.0018550000 37420373 96830484 509673472 3.8560960293 3.9740126133 4.0459394455 734 1311867743.1045989990 0.2137339413 0.1078590928 0.2376661599 0.0048599314 0.0073770000 0.0004010000 0.0042020000 0.0000000000 0.0000050000 0.0010180000 37424045 96830484 509673472 3.8565239906 3.9746510983 4.0460696220 735 1311867743.1350400448 0.2139501870 0.1080034344 0.2376661599 0.0048578007 0.0056150000 0.0004010000 0.0021850000 0.0000040000 0.0000040000 0.0012610000 37427661 96830484 509673472 3.8570613861 3.9743919373 4.0461502075 736 1311867743.1704380512 0.2143841833 0.1081479735 0.2376661599 0.0048601674 0.0060300000 0.0003890000 0.0028740000 0.0000010000 0.0000040000 0.0010150000 37431389 96830484 509673472 3.8566532135 3.9738626480 4.0457568169 737 1311867743.2037980556 0.2138709724 0.1082914239 0.2376661599 0.0048580965 0.0065400000 0.0004010000 0.0025250000 0.0000040000 0.0000040000 0.0018610000 37435117 96830484 509673472 3.8575365543 3.9748938084 4.0452208519 738 1311867743.2358140945 0.2152715027 0.1084363834 0.2376661599 0.0048564299 0.0078810000 0.0004560000 0.0042180000 0.0000000000 0.0000040000 0.0010230000 37438733 96830484 509673472 3.8568508625 3.9742033482 4.0459151268 739 1311867743.2708129883 0.2151341140 0.1085807646 0.2376661599 0.0048571609 0.0060380000 0.0004470000 0.0025200000 0.0000040000 0.0000030000 0.0012650000 37442517 96830484 509673472 3.8571419716 3.9749939442 4.0460419655 740 1311867743.3032529354 0.2144828290 0.1087238755 0.2376661599 0.0048652734 0.0054110000 0.0004010000 0.0021930000 0.0000010000 0.0000040000 0.0010280000 37446189 96830484 509673472 3.8578982353 3.9755961895 4.0458536148 741 1311867743.3363931179 0.2135410160 0.1088653292 0.2376661599 0.0048620886 0.0082790000 0.0003970000 0.0041970000 0.0000050000 0.0000050000 0.0018780000 37449861 96830484 509673472 3.8590850830 3.9755198956 4.0461153984 742 1311867743.3707330227 0.2140381932 0.1090070716 0.2376661599 0.0048594612 0.0060550000 0.0004040000 0.0028670000 0.0000000000 0.0000040000 0.0010150000 37453589 96830484 509673472 3.8585972786 3.9765598774 4.0458741188 743 1311867743.4043838978 0.2146024406 0.1091491919 0.2376661599 0.0048562952 0.0063090000 0.0004000000 0.0028560000 0.0000040000 0.0000040000 0.0012660000 37457317 96830484 509673472 3.8583486080 3.9756665230 4.0466160774 744 1311867743.4352641106 0.2153332978 0.1092919124 0.2376661599 0.0048572950 0.0058530000 0.0004100000 0.0025280000 0.0000010000 0.0000050000 0.0010150000 37460989 96830484 509673472 3.8576471806 3.9749619961 4.0467600822 745 1311867743.4768960476 0.2156897336 0.1094347283 0.2376661599 0.0048565370 0.0063240000 0.0004050000 0.0021940000 0.0000050000 0.0000040000 0.0018780000 37464885 96830484 509673472 3.8576521873 3.9748814106 4.0472054482 746 1311867743.5035250187 0.2164258063 0.1095781480 0.2376661599 0.0048541029 0.0061530000 0.0004060000 0.0028840000 0.0000010000 0.0000040000 0.0010240000 37468445 96830484 509673472 3.8570334911 3.9759168625 4.0469951630 747 1311867743.5389750004 0.2163281590 0.1097210529 0.2376661599 0.0048535285 0.0060170000 0.0004070000 0.0025330000 0.0000040000 0.0000040000 0.0012760000 37472173 96830484 509673472 3.8569281101 3.9755165577 4.0468664169 748 1311867743.5749680996 0.2168504149 0.1098642740 0.2376661599 0.0048540855 0.0067830000 0.0003990000 0.0035610000 0.0000000000 0.0000050000 0.0010150000 37475957 96830484 509673472 3.8570795059 3.9756577015 4.0467329025 749 1311867743.6036109924 0.2169011831 0.1100071804 0.2376661599 0.0048585446 0.0059380000 0.0004040000 0.0018530000 0.0000040000 0.0000030000 0.0018750000 37479517 96830484 509673472 3.8565227985 3.9763116837 4.0467634201 750 1311867743.6354589462 0.2170214206 0.1101498661 0.2376661599 0.0048587979 0.0073340000 0.0004040000 0.0041220000 0.0000000000 0.0000040000 0.0010150000 37483189 96830484 509673472 3.8563203812 3.9754004478 4.0467138290 751 1311867743.6759150028 0.2168676704 0.1102919670 0.2376661599 0.0048556394 0.0077260000 0.0004020000 0.0042180000 0.0000050000 0.0000040000 0.0012830000 37487085 96830484 509673472 3.8563172817 3.9751210213 4.0463933945 752 1311867743.7034959793 0.2159760594 0.1104325044 0.2376661599 0.0048528141 0.0074360000 0.0004040000 0.0042190000 0.0000000000 0.0000050000 0.0010170000 37490645 96830484 509673472 3.8570020199 3.9759020805 4.0459675789 753 1311867743.7388861179 0.2162519246 0.1105730348 0.2376661599 0.0048506982 0.0069830000 0.0003990000 0.0028770000 0.0000040000 0.0000040000 0.0019080000 37494429 96830484 509673472 3.8565764427 3.9752876759 4.0457310677 754 1311867743.7733619213 0.2169053108 0.1107140591 0.2376661599 0.0048476892 0.0064330000 0.0004020000 0.0032150000 0.0000000000 0.0000040000 0.0010150000 37498213 96830484 509673472 3.8557605743 3.9741098881 4.0458641052 755 1311867743.8064749241 0.2174767554 0.1108554666 0.2376661599 0.0048454522 0.0053510000 0.0004040000 0.0018580000 0.0000040000 0.0000040000 0.0012940000 37501829 96830484 509673472 3.8550131321 3.9747805595 4.0455536842 756 1311867743.8391659260 0.2181439847 0.1109973826 0.2376661599 0.0048428964 0.0054300000 0.0004050000 0.0021980000 0.0000000000 0.0000040000 0.0010190000 37505501 96830484 509673472 3.8538842201 3.9739325047 4.0449914932 757 1311867743.8726658821 0.2169790268 0.1111373848 0.2376661599 0.0048404719 0.0067040000 0.0004080000 0.0025420000 0.0000040000 0.0000040000 0.0018850000 37509285 96830484 509673472 3.8550271988 3.9737803936 4.0449657440 758 1311867743.9031310081 0.2173706591 0.1112775342 0.2376661599 0.0048374875 0.0050460000 0.0004050000 0.0017570000 0.0000010000 0.0000040000 0.0010210000 37512901 96830484 509673472 3.8547387123 3.9742591381 4.0446290970 759 1311867743.9453630447 0.2192540616 0.1114197958 0.2376661599 0.0048349283 0.0060710000 0.0004050000 0.0025300000 0.0000040000 0.0000030000 0.0012970000 37516853 96830484 509673472 3.8527038097 3.9731609821 4.0448060036 760 1311867743.9741249084 0.2181513757 0.1115602321 0.2376661599 0.0048333724 0.0057680000 0.0004030000 0.0025340000 0.0000010000 0.0000040000 0.0010220000 37520413 96830484 509673472 3.8534824848 3.9747638702 4.0435729027 761 1311867744.0042529106 0.2177750170 0.1116998047 0.2376661599 0.0048348730 0.0069830000 0.0004060000 0.0028700000 0.0000040000 0.0000040000 0.0018890000 37523973 96830484 509673472 3.8540897369 3.9768767357 4.0435004234 762 1311867744.0407259464 0.2176155895 0.1118388018 0.2376661599 0.0048341199 0.0054220000 0.0004030000 0.0021930000 0.0000000000 0.0000040000 0.0010180000 37527813 96830484 509673472 3.8543796539 3.9749596119 4.0438523293 763 1311867744.0716118813 0.2166870683 0.1119762176 0.2376661599 0.0048321290 0.0063900000 0.0004020000 0.0028840000 0.0000040000 0.0000040000 0.0012920000 37531429 96830484 509673472 3.8552839756 3.9762480259 4.0436801910 764 1311867744.1111290455 0.2176130265 0.1121144857 0.2376661599 0.0048296083 0.0066660000 0.0004060000 0.0034220000 0.0000010000 0.0000040000 0.0010150000 37535157 96830484 509673472 3.8542907238 3.9753460884 4.0437593460 765 1311867744.1412119865 0.2173269689 0.1122520184 0.2376661599 0.0048269422 0.0063420000 0.0004060000 0.0021910000 0.0000040000 0.0000050000 0.0018810000 37538773 96830484 509673472 3.8544893265 3.9769570827 4.0431017876 766 1311867744.1734991074 0.2176999450 0.1123896789 0.2376661599 0.0048254290 0.0074830000 0.0004050000 0.0042300000 0.0000010000 0.0000040000 0.0010090000 37542501 96830484 509673472 3.8545975685 3.9782714844 4.0434617996 767 1311867744.2046771049 0.2184787691 0.1125279958 0.2376661599 0.0048291530 0.0074120000 0.0004080000 0.0034030000 0.0000050000 0.0000040000 0.0012950000 37546117 96830484 509673472 3.8536837101 3.9760799408 4.0435338020 768 1311867744.2400228977 0.2177656144 0.1126650239 0.2376661599 0.0048264278 0.0065850000 0.0004530000 0.0032160000 0.0000000000 0.0000040000 0.0010320000 37549957 96830484 509673472 3.8540663719 3.9755921364 4.0428390503 769 1311867744.2773048878 0.2181284428 0.1128021675 0.2376661599 0.0048252049 0.0073890000 0.0004040000 0.0032270000 0.0000040000 0.0000040000 0.0018950000 37553741 96830484 509673472 3.8539297581 3.9783518314 4.0429553986 770 1311867744.3032519817 0.2180921286 0.1129389077 0.2376661599 0.0048242675 0.0074940000 0.0004040000 0.0042220000 0.0000000000 0.0000040000 0.0010130000 37557245 96830484 509673472 3.8537366390 3.9764244556 4.0430769920 771 1311867744.3391230106 0.2172941118 0.1130742582 0.2376661599 0.0048275849 0.0061620000 0.0004110000 0.0025430000 0.0000050000 0.0000040000 0.0012910000 37561029 96830484 509673472 3.8544042110 3.9759223461 4.0424475670 772 1311867744.3707659245 0.2172202468 0.1132091623 0.2376661599 0.0048259331 0.0075210000 0.0004070000 0.0042330000 0.0000010000 0.0000040000 0.0010240000 37564645 96830484 509673472 3.8548471928 3.9776072502 4.0425605774 773 1311867744.4027431011 0.2179930508 0.1133447172 0.2376661599 0.0048236331 0.0067210000 0.0004050000 0.0025470000 0.0000040000 0.0000050000 0.0018860000 37568373 96830484 509673472 3.8543467522 3.9766993523 4.0431008339 774 1311867744.4383800030 0.2186148912 0.1134807251 0.2376661599 0.0048211009 0.0058230000 0.0004040000 0.0025480000 0.0000000000 0.0000040000 0.0010190000 37572101 96830484 509673472 3.8536779881 3.9762880802 4.0429301262 775 1311867744.4717690945 0.2192912102 0.1136172548 0.2376661599 0.0048182362 0.0067460000 0.0004050000 0.0032200000 0.0000040000 0.0000040000 0.0012800000 37575829 96830484 509673472 3.8529720306 3.9762592316 4.0426774025 776 1311867744.5026860237 0.2182525843 0.1137520941 0.2376661599 0.0048154687 0.0058260000 0.0004050000 0.0025540000 0.0000000000 0.0000040000 0.0010200000 37579501 96830484 509673472 3.8543865681 3.9774229527 4.0426678658 777 1311867744.5383169651 0.2185592204 0.1138869810 0.2376661599 0.0048156544 0.0083890000 0.0004030000 0.0042350000 0.0000040000 0.0000040000 0.0018870000 37583285 96830484 509673472 3.8540544510 3.9764990807 4.0422768593 778 1311867744.5726189613 0.2177577466 0.1140204910 0.2376661599 0.0048134343 0.0067450000 0.0004050000 0.0034420000 0.0000000000 0.0000040000 0.0010180000 37587013 96830484 509673472 3.8547070026 3.9763014317 4.0416369438 779 1311867744.6028740406 0.2193541825 0.1141557076 0.2376661599 0.0048160973 0.0064270000 0.0004040000 0.0028780000 0.0000040000 0.0000040000 0.0012990000 37590629 96830484 509673472 3.8539202213 3.9760487080 4.0425529480 780 1311867744.6386809349 0.2180103958 0.1142888546 0.2376661599 0.0048172897 0.0054980000 0.0004040000 0.0022060000 0.0000010000 0.0000040000 0.0010270000 37594413 96830484 509673472 3.8547523022 3.9767754078 4.0417594910 781 1311867744.6707758904 0.2173816413 0.1144208556 0.2376661599 0.0048143854 0.0060670000 0.0004030000 0.0018680000 0.0000040000 0.0000040000 0.0019160000 37598085 96830484 509673472 3.8553504944 3.9766709805 4.0415487289 782 1311867744.7029349804 0.2189415693 0.1145545138 0.2376661599 0.0048170457 0.0065060000 0.0004050000 0.0032190000 0.0000000000 0.0000050000 0.0010270000 37601757 96830484 509673472 3.8545858860 3.9765062332 4.0421600342 783 1311867744.7396171093 0.2173554599 0.1146858049 0.2376661599 0.0048201636 0.0077620000 0.0004050000 0.0042170000 0.0000050000 0.0000040000 0.0012770000 37605541 96830484 509673472 3.8556411266 3.9781258106 4.0415678024 784 1311867744.7705199718 0.2188460827 0.1148186624 0.2376661599 0.0048179449 0.0057850000 0.0004070000 0.0024210000 0.0000010000 0.0000040000 0.0010310000 37609157 96830484 509673472 3.8541440964 3.9766051769 4.0421891212 785 1311867744.8035891056 0.2190615386 0.1149514559 0.2376661599 0.0048183791 0.0064100000 0.0004080000 0.0022070000 0.0000040000 0.0000040000 0.0018790000 37612885 96830484 509673472 3.8541431427 3.9757034779 4.0418567657 786 1311867744.8424170017 0.2188939303 0.1150836982 0.2376661599 0.0048159218 0.0054980000 0.0004070000 0.0022020000 0.0000010000 0.0000040000 0.0010170000 37616725 96830484 509673472 3.8544838428 3.9764649868 4.0416216850 787 1311867744.8727390766 0.2181696892 0.1152146843 0.2376661599 0.0048166601 0.0099580000 0.0005270000 0.0044910000 0.0000080000 0.0000080000 0.0014410000 37620397 96830484 509673472 3.8548331261 3.9756917953 4.0419139862 788 1311867744.9029939175 0.2190220207 0.1153464195 0.2376661599 0.0048139858 0.0061100000 0.0004320000 0.0022560000 0.0000010000 0.0000050000 0.0010450000 37624013 96830484 509673472 3.8537867069 3.9748370647 4.0415997505 789 1311867744.9392940998 0.2181478739 0.1154767128 0.2376661599 0.0048132212 0.0084640000 0.0004060000 0.0042420000 0.0000040000 0.0000030000 0.0019170000 37627853 96830484 509673472 3.8552737236 3.9761095047 4.0409655571 790 1311867744.9708900452 0.2175933123 0.1156059743 0.2376661599 0.0048131095 0.0051830000 0.0004030000 0.0018720000 0.0000010000 0.0000030000 0.0010320000 37631413 96830484 509673472 3.8556437492 3.9762163162 4.0410470963 791 1311867745.0027489662 0.2184984386 0.1157360533 0.2376661599 0.0048189594 0.0061820000 0.0004040000 0.0025520000 0.0000040000 0.0000030000 0.0013030000 37635085 96830484 509673472 3.8550074100 3.9758052826 4.0400876999 792 1311867745.0384869576 0.2183412164 0.1158656053 0.2376661599 0.0048192478 0.0055350000 0.0004020000 0.0022010000 0.0000010000 0.0000040000 0.0010280000 37638869 96830484 509673472 3.8548560143 3.9755752087 4.0398421288 793 1311867745.0729780197 0.2189442068 0.1159955909 0.2376661599 0.0048189368 0.0070770000 0.0004020000 0.0028820000 0.0000040000 0.0000030000 0.0018970000 37642597 96830484 509673472 3.8544101715 3.9752326012 4.0398292542 794 1311867745.1118760109 0.2185452580 0.1161247466 0.2376661599 0.0048205353 0.0075660000 0.0004010000 0.0042420000 0.0000000000 0.0000030000 0.0010460000 37646437 96830484 509673472 3.8547832966 3.9759762287 4.0397667885 795 1311867745.1405589581 0.2185356468 0.1162535654 0.2376661599 0.0048176840 0.0058120000 0.0004030000 0.0022010000 0.0000030000 0.0000040000 0.0013150000 37649997 96830484 509673472 3.8550329208 3.9764430523 4.0398550034 796 1311867745.1729030609 0.2197981924 0.1163836466 0.2376661599 0.0048150488 0.0075480000 0.0004010000 0.0042280000 0.0000000000 0.0000030000 0.0010290000 37653669 96830484 509673472 3.8538422585 3.9749121666 4.0400323868 797 1311867745.2068369389 0.2206942290 0.1165145256 0.2376661599 0.0048121420 0.0067060000 0.0003990000 0.0025320000 0.0000030000 0.0000040000 0.0019040000 37657397 96830484 509673472 3.8529610634 3.9751622677 4.0401358604 798 1311867745.2430789471 0.2197924256 0.1166439465 0.2376661599 0.0048121419 0.0065970000 0.0004040000 0.0032250000 0.0000000000 0.0000030000 0.0010350000 37661181 96830484 509673472 3.8545205593 3.9767212868 4.0405607224 799 1311867745.2729060650 0.2203534991 0.1167737457 0.2376661599 0.0048091604 0.0110460000 0.0005760000 0.0025770000 0.0000140000 0.0000140000 0.0018530000 37664797 96830484 509673472 3.8540329933 3.9766235352 4.0404129028 800 1311867745.3112850189 0.2210776508 0.1169041256 0.2376661599 0.0048065880 0.0086050000 0.0004380000 0.0043660000 0.0000010000 0.0000060000 0.0010740000 37668581 96830484 509673472 3.8536825180 3.9754507542 4.0411534309 801 1311867745.3395059109 0.2207199335 0.1170337334 0.2376661599 0.0048036153 0.0072770000 0.0004160000 0.0029130000 0.0000040000 0.0000030000 0.0019350000 37672197 96830484 509673472 3.8542046547 3.9753313065 4.0408329964 802 1311867745.3733940125 0.2208795696 0.1171632169 0.2376661599 0.0048012808 0.0068770000 0.0004050000 0.0035540000 0.0000000000 0.0000030000 0.0010390000 37675925 96830484 509673472 3.8543779850 3.9747302532 4.0410833359 803 1311867745.4102098942 0.2216567993 0.1172933459 0.2376661599 0.0047988497 0.0071490000 0.0004040000 0.0035440000 0.0000030000 0.0000040000 0.0013050000 37679709 96830484 509673472 3.8543298244 3.9744620323 4.0419735909 804 1311867745.4433169365 0.2226701528 0.1174244116 0.2376661599 0.0047961305 0.0055150000 0.0003980000 0.0022000000 0.0000000000 0.0000030000 0.0010450000 37683437 96830484 509673472 3.8531742096 3.9749608040 4.0413556099 805 1311867745.4708619118 0.2211449742 0.1175532570 0.2376661599 0.0047934724 0.0093260000 0.0005190000 0.0023970000 0.0000110000 0.0000100000 0.0022880000 37686941 96830484 509673472 3.8547708988 3.9754133224 4.0408864021 806 1311867745.5099780560 0.2225872129 0.1176835721 0.2376661599 0.0047913603 0.0081850000 0.0004320000 0.0043060000 0.0000010000 0.0000060000 0.0010660000 37690837 96830484 509673472 3.8538477421 3.9753742218 4.0414133072 807 1311867745.5417380333 0.2229158729 0.1178139715 0.2376661599 0.0047905766 0.0071970000 0.0004120000 0.0035590000 0.0000040000 0.0000040000 0.0012950000 37694509 96830484 509673472 3.8539590836 3.9736964703 4.0416250229 808 1311867745.5704059601 0.2216038555 0.1179424243 0.2376661599 0.0047880892 0.0075050000 0.0003980000 0.0042150000 0.0000000000 0.0000030000 0.0010420000 37698069 96830484 509673472 3.8552577496 3.9729979038 4.0411162376 809 1311867745.6133821011 0.2221762985 0.1180712672 0.2376661599 0.0047854901 0.0084170000 0.0003960000 0.0042020000 0.0000030000 0.0000030000 0.0019190000 37702077 96830484 509673472 3.8549823761 3.9731583595 4.0411243439 810 1311867745.6438291073 0.2229013294 0.1182006870 0.2376661599 0.0047841568 0.0074240000 0.0003960000 0.0041040000 0.0000000000 0.0000040000 0.0010450000 37705749 96830484 509673472 3.8545918465 3.9731924534 4.0415434837 811 1311867745.6709001064 0.2235372514 0.1183305718 0.2376661599 0.0047893680 0.0064630000 0.0003960000 0.0028500000 0.0000030000 0.0000030000 0.0013340000 37709197 96830484 509673472 3.8542912006 3.9741089344 4.0416460037 812 1311867745.7088780403 0.2232036144 0.1184597258 0.2376661599 0.0047872751 0.0076420000 0.0004010000 0.0042230000 0.0000000000 0.0000040000 0.0010560000 37713093 96830484 509673472 3.8549191952 3.9742450714 4.0409002304 813 1311867745.7423269749 0.2239521593 0.1185894828 0.2376661599 0.0047851412 0.0091140000 0.0005090000 0.0030610000 0.0000080000 0.0000070000 0.0021390000 37716765 96830484 509673472 3.8541650772 3.9739568233 4.0413494110 814 1311867745.7760419846 0.2247655392 0.1187199202 0.2376661599 0.0047901010 0.0065040000 0.0004310000 0.0025780000 0.0000000000 0.0000050000 0.0010760000 37720493 96830484 509673472 3.8537337780 3.9728534222 4.0415401459 815 1311867745.8116889000 0.2247984260 0.1188500779 0.2376661599 0.0047949490 0.0064860000 0.0003990000 0.0028660000 0.0000040000 0.0000030000 0.0013240000 37724277 96830484 509673472 3.8541407585 3.9735567570 4.0420293808 816 1311867745.8389890194 0.2245734632 0.1189796408 0.2376661599 0.0047951248 0.0100840000 0.0005100000 0.0044950000 0.0000010000 0.0000080000 0.0012190000 37727837 96830484 509673472 3.8545966148 3.9728031158 4.0427694321 817 1311867745.8709759712 0.2265814841 0.1191113445 0.2376661599 0.0047933179 0.0074000000 0.0004430000 0.0025680000 0.0000050000 0.0000050000 0.0019710000 37731453 96830484 509673472 3.8526031971 3.9731018543 4.0431776047 818 1311867745.9108459949 0.2254511714 0.1192413442 0.2376661599 0.0047922659 0.0056250000 0.0004110000 0.0021820000 0.0000000000 0.0000030000 0.0010740000 37735349 96830484 509673472 3.8540334702 3.9746203423 4.0426621437 819 1311867745.9435789585 0.2261391580 0.1193718666 0.2376661599 0.0047930671 0.0078050000 0.0003940000 0.0041860000 0.0000030000 0.0000040000 0.0013300000 37739077 96830484 509673472 3.8534064293 3.9729464054 4.0425610542 820 1311867745.9732220173 0.2280758172 0.1195044324 0.2376661599 0.0047909291 0.0061950000 0.0004000000 0.0028550000 0.0000010000 0.0000030000 0.0010540000 37742637 96830484 509673472 3.8524096012 3.9703083038 4.0446724892 821 1311867746.0083909035 0.2287527621 0.1196374998 0.2376661599 0.0047886576 0.0100120000 0.0005070000 0.0030980000 0.0000110000 0.0000090000 0.0023660000 37746365 96830484 509673472 3.8521571159 3.9706425667 4.0449051857 822 1311867746.0391409397 0.2283580750 0.1197697633 0.2376661599 0.0047859792 0.0075630000 0.0004530000 0.0035870000 0.0000000000 0.0000050000 0.0011030000 37750093 96830484 509673472 3.8531234264 3.9703838825 4.0452466011 823 1311867746.0728518963 0.2281881124 0.1199014988 0.2376661599 0.0047833777 0.0098220000 0.0004970000 0.0044210000 0.0000070000 0.0000070000 0.0014620000 37753765 96830484 509673472 3.8534815311 3.9710536003 4.0446343422 824 1311867746.1113359928 0.2282034010 0.1200329331 0.2376661599 0.0047818676 0.0080430000 0.0004280000 0.0042410000 0.0000000000 0.0000040000 0.0010790000 37757549 96830484 509673472 3.8538572788 3.9707419872 4.0443377495 825 1311867746.1412689686 0.2308581769 0.1201672668 0.2376661599 0.0047804006 0.0087950000 0.0004020000 0.0040480000 0.0000040000 0.0000030000 0.0019670000 37761221 96830484 509673472 3.8519141674 3.9690284729 4.0458002090 826 1311867746.1721889973 0.2305228710 0.1203008692 0.2376661599 0.0047778031 0.0072920000 0.0004380000 0.0038370000 0.0000000000 0.0000030000 0.0010630000 37764837 96830484 509673472 3.8519406319 3.9701406956 4.0445246696 827 1311867746.2066209316 0.2287672609 0.1204320257 0.2376661599 0.0047758992 0.0078520000 0.0003990000 0.0041820000 0.0000030000 0.0000040000 0.0013500000 37768565 96830484 509673472 3.8536875248 3.9720060825 4.0431194305 828 1311867746.2386920452 0.2316173911 0.1205663075 0.2376661599 0.0047749862 0.0065660000 0.0003920000 0.0031660000 0.0000010000 0.0000030000 0.0010650000 37772293 96830484 509673472 3.8512134552 3.9684839249 4.0450859070 829 1311867746.2704648972 0.2322102487 0.1207009805 0.2376661599 0.0047721389 0.0084950000 0.0003950000 0.0041650000 0.0000030000 0.0000040000 0.0019670000 37775965 96830484 509673472 3.8508853912 3.9670252800 4.0459399223 830 1311867746.3068819046 0.2292366028 0.1208317463 0.2376661599 0.0047723567 0.0075430000 0.0003880000 0.0041690000 0.0000000000 0.0000030000 0.0010620000 37779693 96830484 509673472 3.8537423611 3.9688942432 4.0449714661 831 1311867746.3393440247 0.2307889760 0.1209640655 0.2376661599 0.0047747363 0.0078170000 0.0003940000 0.0041590000 0.0000030000 0.0000040000 0.0013150000 37783421 96830484 509673472 3.8524866104 3.9689242840 4.0450992584 832 1311867746.3797800541 0.2320956737 0.1210976372 0.2376661599 0.0047725909 0.0098180000 0.0005040000 0.0041040000 0.0000020000 0.0000080000 0.0012270000 37787317 96830484 509673472 3.8512237072 3.9670863152 4.0461883545 833 1311867746.4078478813 0.2312285155 0.1212298471 0.2376661599 0.0047718476 0.0091340000 0.0004200000 0.0042180000 0.0000040000 0.0000040000 0.0020120000 37790877 96830484 509673472 3.8523135185 3.9675807953 4.0461072922 834 1311867746.4389901161 0.2308320254 0.1213612646 0.2376661599 0.0047691567 0.0056190000 0.0003990000 0.0021610000 0.0000010000 0.0000040000 0.0010710000 37794493 96830484 509673472 3.8524808884 3.9688072205 4.0459589958 835 1311867746.4774639606 0.2298693955 0.1214912144 0.2376661599 0.0047687456 0.0085650000 0.0005000000 0.0023650000 0.0000100000 0.0000090000 0.0015830000 37798389 96830484 509673472 3.8529434204 3.9687392712 4.0450477600 836 1311867746.5066781044 0.2298030555 0.1216207741 0.2376661599 0.0047661935 0.0101750000 0.0004860000 0.0044520000 0.0000010000 0.0000080000 0.0012300000 37801949 96830484 509673472 3.8532938957 3.9682948589 4.0451903343 837 1311867746.5406761169 0.2303062081 0.1217506252 0.2376661599 0.0047664066 0.0081480000 0.0004190000 0.0032250000 0.0000050000 0.0000050000 0.0020020000 37805677 96830484 509673472 3.8527615070 3.9693789482 4.0455822945 838 1311867746.5748629570 0.2310914844 0.1218811036 0.2376661599 0.0047642755 0.0075370000 0.0003980000 0.0041570000 0.0000000000 0.0000030000 0.0010840000 37809461 96830484 509673472 3.8518819809 3.9687161446 4.0458216667 839 1311867746.6067559719 0.2288400531 0.1220085874 0.2376661599 0.0047642840 0.0078000000 0.0003930000 0.0041410000 0.0000040000 0.0000030000 0.0013390000 37813077 96830484 509673472 3.8534030914 3.9704258442 4.0439124107 840 1311867746.6396849155 0.2302354723 0.1221374290 0.2376661599 0.0047669969 0.0062660000 0.0003980000 0.0028070000 0.0000000000 0.0000030000 0.0010780000 37816861 96830484 509673472 3.8525128365 3.9693748951 4.0452337265 841 1311867746.6749529839 0.2299305499 0.1222656015 0.2376661599 0.0047686031 0.0074630000 0.0004050000 0.0031440000 0.0000030000 0.0000030000 0.0019860000 37820589 96830484 509673472 3.8525867462 3.9696209431 4.0443511009 842 1311867746.7095060349 0.2305824459 0.1223942438 0.2376661599 0.0047659145 0.0074770000 0.0004010000 0.0041150000 0.0000010000 0.0000040000 0.0010770000 37824317 96830484 509673472 3.8524270058 3.9682328701 4.0452446938 843 1311867746.7391049862 0.2310012281 0.1225230778 0.2376661599 0.0047637482 0.0077250000 0.0003990000 0.0041220000 0.0000040000 0.0000030000 0.0013340000 37827877 96830484 509673472 3.8522131443 3.9677388668 4.0455317497 844 1311867746.7751340866 0.2315296084 0.1226522324 0.2376661599 0.0047611739 0.0075460000 0.0003910000 0.0041240000 0.0000010000 0.0000030000 0.0010830000 37831717 96830484 509673472 3.8519270420 3.9673743248 4.0458364487 845 1311867746.8070099354 0.2310997695 0.1227805727 0.2376661599 0.0047594324 0.0084010000 0.0003900000 0.0041240000 0.0000040000 0.0000030000 0.0019740000 37835389 96830484 509673472 3.8522174358 3.9675326347 4.0450544357 846 1311867746.8401610851 0.2311118394 0.1229086238 0.2376661599 0.0047567757 0.0058480000 0.0003980000 0.0024680000 0.0000010000 0.0000040000 0.0010750000 37839061 96830484 509673472 3.8523166180 3.9666919708 4.0451455116 847 1311867746.8748359680 0.2283555120 0.1230331184 0.2376661599 0.0047547625 0.0097780000 0.0005770000 0.0028490000 0.0000100000 0.0000100000 0.0016340000 37842845 96830484 509673472 3.8543868065 3.9685325623 4.0425019264 848 1311867746.9086029530 0.2297778726 0.1231589966 0.2376661599 0.0047528089 0.0071580000 0.0004350000 0.0028890000 0.0000010000 0.0000060000 0.0011170000 37846517 96830484 509673472 3.8538899422 3.9693908691 4.0437726974 849 1311867746.9389610291 0.2297948897 0.1232845984 0.2376661599 0.0047504646 0.0085830000 0.0004140000 0.0041460000 0.0000040000 0.0000030000 0.0020030000 37850189 96830484 509673472 3.8542554379 3.9674663544 4.0442595482 850 1311867746.9748229980 0.2295164019 0.1234095770 0.2376661599 0.0047512912 0.0078510000 0.0004900000 0.0023280000 0.0000010000 0.0000080000 0.0012270000 37853973 96830484 509673472 3.8552179337 3.9677863121 4.0438466072 851 1311867747.0066559315 0.2289716303 0.1235336217 0.2376661599 0.0047537595 0.0083850000 0.0004200000 0.0041730000 0.0000050000 0.0000040000 0.0013730000 37857589 96830484 509673472 3.8547682762 3.9687812328 4.0428538322 852 1311867747.0389339924 0.2297957391 0.1236583425 0.2376661599 0.0047518585 0.0062190000 0.0003950000 0.0027990000 0.0000000000 0.0000040000 0.0010750000 37861261 96830484 509673472 3.8546361923 3.9665989876 4.0443735123 853 1311867747.0749640465 0.2297554761 0.1237827237 0.2376661599 0.0047503514 0.0105380000 0.0004960000 0.0043580000 0.0000070000 0.0000070000 0.0021650000 37865101 96830484 509673472 3.8551952839 3.9678401947 4.0442051888 854 1311867747.1066820621 0.2287478596 0.1239056337 0.2376661599 0.0047544597 0.0074520000 0.0004270000 0.0035190000 0.0000000000 0.0000040000 0.0010980000 37868717 96830484 509673472 3.8558940887 3.9678616524 4.0441040993 855 1311867747.1389479637 0.2286353856 0.1240281246 0.2376661599 0.0047522630 0.0071910000 0.0004660000 0.0028100000 0.0000040000 0.0000030000 0.0013630000 37872389 96830484 509673472 3.8564314842 3.9693965912 4.0442886353 856 1311867747.1744880676 0.2288787514 0.1241506136 0.2376661599 0.0047503264 0.0076540000 0.0004390000 0.0040880000 0.0000010000 0.0000040000 0.0010910000 37876173 96830484 509673472 3.8563053608 3.9686961174 4.0442595482 857 1311867747.2066030502 0.2295258790 0.1242735720 0.2376661599 0.0047481101 0.0084650000 0.0003810000 0.0040770000 0.0000030000 0.0000030000 0.0020140000 37879845 96830484 509673472 3.8558330536 3.9676935673 4.0446424484 858 1311867747.2385439873 0.2276476473 0.1243940546 0.2376661599 0.0047458483 0.0068870000 0.0003890000 0.0034390000 0.0000000000 0.0000030000 0.0010850000 37883573 96830484 509673472 3.8576073647 3.9688870907 4.0430660248 859 1311867747.2745490074 0.2287178338 0.1245155025 0.2376661599 0.0047579522 0.0078290000 0.0003880000 0.0040930000 0.0000040000 0.0000030000 0.0013670000 37887357 96830484 509673472 3.8571956158 3.9677941799 4.0440950394 860 1311867747.3064720631 0.2302928418 0.1246384994 0.2376661599 0.0047673973 0.0074530000 0.0003840000 0.0040880000 0.0000000000 0.0000030000 0.0010750000 37890917 96830484 509673472 3.8561339378 3.9664964676 4.0453429222 861 1311867747.3388469219 0.2279778570 0.1247585219 0.2376661599 0.0047865782 0.0085110000 0.0003940000 0.0040880000 0.0000040000 0.0000040000 0.0019740000 37894701 96830484 509673472 3.8579821587 3.9669835567 4.0439395905 862 1311867747.3758800030 0.2288559973 0.1248792846 0.2376661599 0.0047903071 0.0066970000 0.0004010000 0.0031050000 0.0000000000 0.0000030000 0.0010860000 37898429 96830484 509673472 3.8576846123 3.9669327736 4.0444622040 863 1311867747.4068729877 0.2277999222 0.1249985438 0.2376661599 0.0047899851 0.0104290000 0.0004980000 0.0043810000 0.0000070000 0.0000070000 0.0015020000 37902101 96830484 509673472 3.8586292267 3.9679937363 4.0439352989 864 1311867747.4396450520 0.2260886729 0.1251155462 0.2376661599 0.0047899388 0.0082680000 0.0004210000 0.0041570000 0.0000010000 0.0000050000 0.0011210000 37905717 96830484 509673472 3.8599510193 3.9694008827 4.0423812866 865 1311867747.4756069183 0.2272280604 0.1252335954 0.2376661599 0.0047913392 0.0085080000 0.0003900000 0.0040740000 0.0000040000 0.0000030000 0.0020040000 37909501 96830484 509673472 3.8591051102 3.9680020809 4.0433568954 866 1311867747.5095520020 0.2263250351 0.1253503291 0.2376661599 0.0047907726 0.0062650000 0.0003900000 0.0027640000 0.0000010000 0.0000030000 0.0010910000 37913285 96830484 509673472 3.8602607250 3.9693589211 4.0433778763 867 1311867747.5405330658 0.2251446843 0.1254654322 0.2376661599 0.0047965517 0.0066180000 0.0003920000 0.0027730000 0.0000040000 0.0000030000 0.0013750000 37916901 96830484 509673472 3.8608174324 3.9697067738 4.0415124893 868 1311867747.5766739845 0.2276213020 0.1255831233 0.2376661599 0.0047969019 0.0072990000 0.0003880000 0.0037560000 0.0000000000 0.0000030000 0.0010790000 37920685 96830484 509673472 3.8590841293 3.9678242207 4.0433492661 869 1311867747.6086390018 0.2204325348 0.1256922711 0.2376661599 0.0048218604 0.0108270000 0.0005230000 0.0043400000 0.0000080000 0.0000070000 0.0022040000 37924357 96830484 509673472 3.8634133339 3.9737610817 4.0359740257 870 1311867747.6432039738 0.2261918038 0.1258077878 0.2376661599 0.0048371727 0.0096210000 0.0004840000 0.0043030000 0.0000010000 0.0000080000 0.0012510000 37928141 96830484 509673472 3.8601791859 3.9699237347 4.0422573090 871 1311867747.6760280132 0.2255320996 0.1259222818 0.2376661599 0.0048409140 0.0083180000 0.0004170000 0.0041470000 0.0000040000 0.0000040000 0.0013980000 37931813 96830484 509673472 3.8606731892 3.9696607590 4.0419812202 872 1311867747.7068400383 0.2244112045 0.1260352278 0.2376661599 0.0048416343 0.0075870000 0.0003970000 0.0040430000 0.0000000000 0.0000030000 0.0010910000 37935429 96830484 509673472 3.8599638939 3.9725525379 4.0384340286 873 1311867747.7480750084 0.2284063995 0.1261524915 0.2376661599 0.0048689673 0.0105200000 0.0005060000 0.0042970000 0.0000070000 0.0000070000 0.0022030000 37939493 96830484 509673472 3.8577198982 3.9695439339 4.0433115959 874 1311867747.7826869488 0.2272869647 0.1262682060 0.2376661599 0.0048667994 0.0067880000 0.0004160000 0.0028070000 0.0000010000 0.0000040000 0.0011170000 37943221 96830484 509673472 3.8587722778 3.9690237045 4.0430707932 875 1311867747.8149020672 0.2257628590 0.1263819142 0.2376661599 0.0048656730 0.0078360000 0.0003920000 0.0040710000 0.0000030000 0.0000030000 0.0013620000 37946893 96830484 509673472 3.8592269421 3.9691560268 4.0415053368 876 1311867747.8466539383 0.2267547101 0.1264964950 0.2376661599 0.0048637550 0.0075100000 0.0003890000 0.0040450000 0.0000010000 0.0000040000 0.0010920000 37950509 96830484 509673472 3.8583202362 3.9704234600 4.0419235229 877 1311867747.8827810287 0.2295389473 0.1266139892 0.2376661599 0.0048719653 0.0078700000 0.0003910000 0.0034040000 0.0000030000 0.0000040000 0.0020130000 37954349 96830484 509673472 3.8563225269 3.9692101479 4.0444736481 878 1311867747.9150440693 0.2288502306 0.1267304314 0.2376661599 0.0048692521 0.0075620000 0.0003930000 0.0040720000 0.0000010000 0.0000030000 0.0010780000 37958077 96830484 509673472 3.8556232452 3.9697992802 4.0426511765 879 1311867747.9477820396 0.2304290086 0.1268484048 0.2376661599 0.0048671794 0.0068760000 0.0003880000 0.0030930000 0.0000040000 0.0000030000 0.0013680000 37961749 96830484 509673472 3.8546092510 3.9685659409 4.0448155403 880 1311867747.9826579094 0.2303688526 0.1269660416 0.2376661599 0.0048648590 0.0075540000 0.0003910000 0.0040740000 0.0000000000 0.0000040000 0.0010790000 37965477 96830484 509673472 3.8544216156 3.9683535099 4.0452232361 881 1311867748.0146598816 0.2321594357 0.1270854439 0.2376661599 0.0048662415 0.0100070000 0.0004910000 0.0030060000 0.0000120000 0.0000090000 0.0022760000 37969149 96830484 509673472 3.8526575565 3.9679911137 4.0468640327 882 1311867748.0469269753 0.2321652472 0.1272045820 0.2376661599 0.0048638007 0.0082690000 0.0004210000 0.0041520000 0.0000010000 0.0000050000 0.0011020000 37972821 96830484 509673472 3.8516383171 3.9687981606 4.0463242531 883 1311867748.0828750134 0.2334610671 0.1273249178 0.2376661599 0.0048618577 0.0078390000 0.0003990000 0.0039740000 0.0000040000 0.0000030000 0.0013670000 37976661 96830484 509673472 3.8501315117 3.9681234360 4.0475239754 884 1311867748.1150569916 0.2339534611 0.1274455383 0.2376661599 0.0048612907 0.0075810000 0.0003910000 0.0040920000 0.0000000000 0.0000040000 0.0010680000 37980277 96830484 509673472 3.8498249054 3.9675428867 4.0489063263 885 1311867748.1486010551 0.2350527793 0.1275671284 0.2376661599 0.0048602902 0.0085470000 0.0003930000 0.0041000000 0.0000030000 0.0000030000 0.0020050000 37984005 96830484 509673472 3.8478243351 3.9684917927 4.0482683182 886 1311867748.1831040382 0.2341866791 0.1276874665 0.2376661599 0.0048578805 0.0088340000 0.0005030000 0.0033180000 0.0000010000 0.0000080000 0.0012450000 37987677 96830484 509673472 3.8484997749 3.9679849148 4.0482292175 887 1311867748.2148320675 0.2369037867 0.1278105965 0.2376661599 0.0048588646 0.0085420000 0.0005090000 0.0026580000 0.0000070000 0.0000070000 0.0015220000 37991405 96830484 509673472 3.8463640213 3.9670534134 4.0505800247 888 1311867748.2466599941 0.2362018079 0.1279326587 0.2376661599 0.0048576194 0.0081320000 0.0004140000 0.0041550000 0.0000000000 0.0000040000 0.0011080000 37995021 96830484 509673472 3.8466186523 3.9677464962 4.0496950150 889 1311867748.2827599049 0.2352928519 0.1280534238 0.2376661599 0.0048553162 0.0066430000 0.0003920000 0.0021370000 0.0000040000 0.0000040000 0.0020130000 37998805 96830484 509673472 3.8471500874 3.9677278996 4.0490927696 890 1311867748.3148829937 0.2349586189 0.1281735420 0.2376661599 0.0048618152 0.0098640000 0.0005040000 0.0043750000 0.0000010000 0.0000070000 0.0012380000 38002477 96830484 509673472 3.8475444317 3.9672641754 4.0495119095 891 1311867748.3470869064 0.2353779227 0.1282938612 0.2376661599 0.0048651193 0.0065580000 0.0004110000 0.0021780000 0.0000040000 0.0000040000 0.0013530000 38006149 96830484 509673472 3.8466870785 3.9666998386 4.0489997864 892 1311867748.3826999664 0.2357021868 0.1284142741 0.2376661599 0.0048659860 0.0073210000 0.0004050000 0.0038040000 0.0000000000 0.0000030000 0.0010800000 38009933 96830484 509673472 3.8464770317 3.9672172070 4.0494279861 893 1311867748.4148259163 0.2354658246 0.1285341526 0.2376661599 0.0048636775 0.0068970000 0.0003900000 0.0024580000 0.0000030000 0.0000030000 0.0019940000 38013549 96830484 509673472 3.8460474014 3.9684824944 4.0483927727 894 1311867748.4520189762 0.2366399914 0.1286550764 0.2376661599 0.0048681235 0.0102990000 0.0004960000 0.0044170000 0.0000010000 0.0000070000 0.0012270000 38017389 96830484 509673472 3.8447308540 3.9670386314 4.0495386124 895 1311867748.4831318855 0.2362082750 0.1287752476 0.2376661599 0.0048655838 0.0086240000 0.0004160000 0.0041900000 0.0000040000 0.0000040000 0.0013660000 38021061 96830484 509673472 3.8446385860 3.9676940441 4.0487570763 896 1311867748.5149960518 0.2345666140 0.1288933183 0.2376661599 0.0048632367 0.0076450000 0.0003940000 0.0041320000 0.0000000000 0.0000040000 0.0010670000 38024733 96830484 509673472 3.8458955288 3.9684228897 4.0478267670 897 1311867748.5467929840 0.2362873107 0.1290130440 0.2376661599 0.0048613282 0.0075970000 0.0003960000 0.0031530000 0.0000040000 0.0000030000 0.0019600000 38028349 96830484 509673472 3.8443555832 3.9674737453 4.0494241714 898 1311867748.5827159882 0.2369889617 0.1291332845 0.2376661599 0.0048586847 0.0092230000 0.0005100000 0.0030530000 0.0000010000 0.0000100000 0.0013180000 38032133 96830484 509673472 3.8432147503 3.9677813053 4.0493402481 899 1311867748.6147999763 0.2352411300 0.1292513132 0.2376661599 0.0048570056 0.0086340000 0.0004170000 0.0042190000 0.0000050000 0.0000040000 0.0013660000 38035861 96830484 509673472 3.8446559906 3.9685409069 4.0490026474 900 1311867748.6470849514 0.2357764840 0.1293696745 0.2376661599 0.0048662739 0.0076470000 0.0004230000 0.0040530000 0.0000010000 0.0000040000 0.0010730000 38039477 96830484 509673472 3.8441584110 3.9683651924 4.0500712395 901 1311867748.6827559471 0.2347530872 0.1294866372 0.2376661599 0.0048640697 0.0086080000 0.0003940000 0.0041370000 0.0000030000 0.0000030000 0.0019700000 38043261 96830484 509673472 3.8449892998 3.9681766033 4.0499057770 902 1311867748.7147359848 0.2343268543 0.1296028681 0.2376661599 0.0048820779 0.0075530000 0.0004000000 0.0040270000 0.0000010000 0.0000040000 0.0010640000 38046933 96830484 509673472 3.8456914425 3.9668292999 4.0505843163 903 1311867748.7499361038 0.2357112318 0.1297203746 0.2376661599 0.0048799965 0.0088370000 0.0005120000 0.0030220000 0.0000070000 0.0000070000 0.0014780000 38050661 96830484 509673472 3.8440957069 3.9664344788 4.0511770248 904 1311867748.7828259468 0.2350803465 0.1298369232 0.2376661599 0.0048778953 0.0091880000 0.0005110000 0.0036980000 0.0000010000 0.0000080000 0.0011940000 38054445 96830484 509673472 3.8441553116 3.9669344425 4.0505104065 905 1311867748.8151619434 0.2350002974 0.1299531258 0.2376661599 0.0048755026 0.0090860000 0.0004950000 0.0026820000 0.0000070000 0.0000070000 0.0021240000 38058117 96830484 509673472 3.8440370560 3.9670979977 4.0508208275 906 1311867748.8466329575 0.2345145345 0.1300685358 0.2376661599 0.0048729579 0.0066750000 0.0004160000 0.0025350000 0.0000010000 0.0000050000 0.0010520000 38061677 96830484 509673472 3.8439986706 3.9672849178 4.0506138802 907 1311867748.8829579353 0.2341639400 0.1301833047 0.2376661599 0.0048709375 0.0079760000 0.0004030000 0.0041700000 0.0000030000 0.0000040000 0.0013200000 38065461 96830484 509673472 3.8434629440 3.9674344063 4.0501480103 908 1311867748.9149119854 0.2331378609 0.1302966908 0.2376661599 0.0048695373 0.0096690000 0.0005130000 0.0042790000 0.0000010000 0.0000080000 0.0011750000 38069189 96830484 509673472 3.8437016010 3.9685175419 4.0498523712 909 1311867748.9472498894 0.2346929163 0.1304115381 0.2376661599 0.0048670409 0.0076970000 0.0004190000 0.0028800000 0.0000040000 0.0000040000 0.0019150000 38072861 96830484 509673472 3.8417496681 3.9674611092 4.0506305695 910 1311867748.9829359055 0.2322367877 0.1305234340 0.2376661599 0.0048656919 0.0076440000 0.0004010000 0.0041630000 0.0000000000 0.0000030000 0.0010310000 38076645 96830484 509673472 3.8429892063 3.9683122635 4.0489625931 911 1311867749.0159859657 0.2313682586 0.1306341308 0.2376661599 0.0048630377 0.0062370000 0.0003890000 0.0024880000 0.0000040000 0.0000030000 0.0012820000 38080317 96830484 509673472 3.8431980610 3.9694859982 4.0482444763 912 1311867749.0467190742 0.2307719737 0.1307439311 0.2376661599 0.0048607653 0.0089530000 0.0005110000 0.0027170000 0.0000010000 0.0000100000 0.0012690000 38083933 96830484 509673472 3.8433775902 3.9693620205 4.0482187271 913 1311867749.0828969479 0.2305085063 0.1308532023 0.2376661599 0.0048582382 0.0092820000 0.0004160000 0.0042570000 0.0000050000 0.0000040000 0.0019140000 38087717 96830484 509673472 3.8431832790 3.9695320129 4.0480952263 914 1311867749.1158421040 0.2289930880 0.1309605763 0.2376661599 0.0048565992 0.0068280000 0.0004460000 0.0028120000 0.0000010000 0.0000040000 0.0010250000 38091445 96830484 509673472 3.8443069458 3.9705538750 4.0473742485 915 1311867749.1485249996 0.2290098071 0.1310677339 0.2376661599 0.0048539616 0.0060230000 0.0003960000 0.0021670000 0.0000030000 0.0000030000 0.0012940000 38095173 96830484 509673472 3.8439946175 3.9710087776 4.0474433899 916 1311867749.1829619408 0.2288499177 0.1311744831 0.2376661599 0.0048518379 0.0098290000 0.0005090000 0.0044180000 0.0000010000 0.0000080000 0.0011710000 38098901 96830484 509673472 3.8433933258 3.9711222649 4.0472192764 917 1311867749.2156000137 0.2278021425 0.1312798567 0.2376661599 0.0048496338 0.0089320000 0.0004180000 0.0041230000 0.0000050000 0.0000050000 0.0019040000 38102517 96830484 509673472 3.8442041874 3.9712338448 4.0467534065 918 1311867749.2468719482 0.2275495231 0.1313847256 0.2376661599 0.0048506030 0.0083190000 0.0005080000 0.0025670000 0.0000000000 0.0000080000 0.0011840000 38106133 96830484 509673472 3.8442394733 3.9706056118 4.0461320877 919 1311867749.2828478813 0.2281559408 0.1314900262 0.2376661599 0.0048522258 0.0079120000 0.0004160000 0.0035640000 0.0000050000 0.0000040000 0.0013150000 38109917 96830484 509673472 3.8438382149 3.9699146748 4.0473575592 920 1311867749.3148140907 0.2275468111 0.1315944358 0.2376661599 0.0048511804 0.0063720000 0.0003970000 0.0028470000 0.0000010000 0.0000040000 0.0010180000 38113645 96830484 509673472 3.8437049389 3.9717483521 4.0457653999 921 1311867749.3468968868 0.2269429117 0.1316979629 0.2376661599 0.0048491064 0.0075580000 0.0003940000 0.0031790000 0.0000040000 0.0000030000 0.0018830000 38117261 96830484 509673472 3.8436851501 3.9723904133 4.0453619957 922 1311867749.3828470707 0.2262800038 0.1318005464 0.2376661599 0.0048465529 0.0063340000 0.0004020000 0.0028400000 0.0000010000 0.0000030000 0.0010190000 38121045 96830484 509673472 3.8433389664 3.9731233120 4.0440053940 923 1311867749.4147930145 0.2239517421 0.1319003852 0.2376661599 0.0048448842 0.0063020000 0.0003950000 0.0025210000 0.0000040000 0.0000030000 0.0012670000 38124773 96830484 509673472 3.8448841572 3.9752953053 4.0426397324 924 1311867749.4467489719 0.2244256735 0.1320005208 0.2376661599 0.0048425458 0.0060230000 0.0004050000 0.0025150000 0.0000010000 0.0000030000 0.0010040000 38128389 96830484 509673472 3.8438737392 3.9760959148 4.0425481796 925 1311867749.4829080105 0.2227392495 0.1320986167 0.2376661599 0.0048424731 0.0069290000 0.0004040000 0.0025270000 0.0000030000 0.0000030000 0.0018720000 38132173 96830484 509673472 3.8443570137 3.9758334160 4.0417842865 926 1311867749.5159850121 0.2234368473 0.1321972541 0.2376661599 0.0048402961 0.0099410000 0.0006040000 0.0025410000 0.0000020000 0.0000140000 0.0013380000 38135845 96830484 509673472 3.8432414532 3.9743323326 4.0426244736 927 1311867749.5468530655 0.2242511511 0.1322965571 0.2376661599 0.0048377684 0.0086290000 0.0004390000 0.0039890000 0.0000050000 0.0000040000 0.0013000000 38139517 96830484 509673472 3.8412919044 3.9748177528 4.0418691635 928 1311867749.5830268860 0.2234022766 0.1323947314 0.2376661599 0.0048353594 0.0071330000 0.0004020000 0.0035510000 0.0000010000 0.0000040000 0.0010010000 38143301 96830484 509673472 3.8412835598 3.9746897221 4.0415744781 929 1311867749.6148250103 0.2225387692 0.1324917648 0.2376661599 0.0048329926 0.0070010000 0.0004080000 0.0025300000 0.0000040000 0.0000030000 0.0018620000 38146917 96830484 509673472 3.8412475586 3.9748792648 4.0410122871 930 1311867749.6469049454 0.2222064435 0.1325882322 0.2376661599 0.0048319637 0.0056280000 0.0004060000 0.0020740000 0.0000010000 0.0000040000 0.0010070000 38150645 96830484 509673472 3.8414897919 3.9743528366 4.0415215492 931 1311867749.6829149723 0.2221589833 0.1326844414 0.2376661599 0.0048299134 0.0067770000 0.0004130000 0.0028720000 0.0000030000 0.0000030000 0.0012560000 38154429 96830484 509673472 3.8402347565 3.9740006924 4.0407919884 932 1311867749.7160799503 0.2221764028 0.1327804628 0.2376661599 0.0048277605 0.0060720000 0.0004070000 0.0025200000 0.0000000000 0.0000030000 0.0010030000 38158101 96830484 509673472 3.8395843506 3.9740152359 4.0401196480 933 1311867749.7468609810 0.2217944115 0.1328758690 0.2376661599 0.0048295499 0.0136780000 0.0005990000 0.0046950000 0.0000150000 0.0000140000 0.0025710000 38161773 96830484 509673472 3.8399446011 3.9736011028 4.0402269363 934 1311867749.7828791142 0.2193753719 0.1329684809 0.2376661599 0.0048285526 0.0088260000 0.0004450000 0.0043280000 0.0000000000 0.0000050000 0.0010420000 38165557 96830484 509673472 3.8412494659 3.9732742310 4.0390968323 935 1311867749.8148949146 0.2182807773 0.1330597240 0.2376661599 0.0048299976 0.0061360000 0.0004110000 0.0022000000 0.0000040000 0.0000030000 0.0012610000 38169173 96830484 509673472 3.8416483402 3.9737117290 4.0386605263 936 1311867749.8469030857 0.2184567750 0.1331509601 0.2376661599 0.0048278268 0.0067430000 0.0004060000 0.0031880000 0.0000010000 0.0000030000 0.0009890000 38172901 96830484 509673472 3.8412890434 3.9742927551 4.0389776230 937 1311867749.8829030991 0.2191129774 0.1332427019 0.2376661599 0.0048434769 0.0086360000 0.0004060000 0.0041990000 0.0000030000 0.0000030000 0.0018320000 38176685 96830484 509673472 3.8404383659 3.9735145569 4.0388007164 938 1311867749.9149639606 0.2177968472 0.1333328449 0.2376661599 0.0048586616 0.0077860000 0.0004010000 0.0041860000 0.0000000000 0.0000030000 0.0009860000 38180301 96830484 509673472 3.8406331539 3.9738814831 4.0381345749 939 1311867749.9508709908 0.2170019597 0.1334219494 0.2376661599 0.0048568859 0.0097450000 0.0004940000 0.0034420000 0.0000090000 0.0000090000 0.0013680000 38184085 96830484 509673472 3.8411245346 3.9737310410 4.0382390022 940 1311867749.9827940464 0.2166785598 0.1335105202 0.2376661599 0.0048566437 0.0064520000 0.0004270000 0.0022420000 0.0000010000 0.0000060000 0.0010270000 38187813 96830484 509673472 3.8408911228 3.9741504192 4.0378274918 941 1311867750.0147750378 0.2151152194 0.1335972415 0.2376661599 0.0048545666 0.0075530000 0.0004010000 0.0030910000 0.0000030000 0.0000030000 0.0018070000 38191485 96830484 509673472 3.8419265747 3.9737894535 4.0374112129 942 1311867750.0470709801 0.2139323354 0.1336825229 0.2376661599 0.0048521533 0.0087180000 0.0004940000 0.0023860000 0.0000010000 0.0000110000 0.0012530000 38195157 96830484 509673472 3.8426754475 3.9735682011 4.0370020866 943 1311867750.0829339027 0.2142548561 0.1337679655 0.2376661599 0.0048504126 0.0070540000 0.0004250000 0.0022320000 0.0000050000 0.0000050000 0.0012710000 38198941 96830484 509673472 3.8418776989 3.9738221169 4.0368623734 944 1311867750.1156458855 0.2139736712 0.1338529291 0.2376661599 0.0048483513 0.0082080000 0.0004560000 0.0042060000 0.0000000000 0.0000040000 0.0009870000 38202613 96830484 509673472 3.8416876793 3.9738121033 4.0366153717 945 1311867750.1474790573 0.2137449980 0.1339374710 0.2376661599 0.0048464090 0.0086300000 0.0003950000 0.0042160000 0.0000040000 0.0000040000 0.0018220000 38206285 96830484 509673472 3.8416182995 3.9739427567 4.0366673470 946 1311867750.1828711033 0.2129494697 0.1340209932 0.2376661599 0.0048452337 0.0057630000 0.0003930000 0.0021780000 0.0000000000 0.0000030000 0.0009920000 38210069 96830484 509673472 3.8419201374 3.9739601612 4.0361399651 947 1311867750.2156589031 0.2126996666 0.1341040752 0.2376661599 0.0048431114 0.0084220000 0.0005100000 0.0023810000 0.0000080000 0.0000070000 0.0013820000 38213741 96830484 509673472 3.8417627811 3.9746637344 4.0360083580 948 1311867750.2469079494 0.2124675214 0.1341867371 0.2376661599 0.0048406360 0.0080540000 0.0004220000 0.0039500000 0.0000000000 0.0000050000 0.0010010000 38217357 96830484 509673472 3.8415665627 3.9746685028 4.0358719826 949 1311867750.2829968929 0.2117621601 0.1342684815 0.2376661599 0.0048401137 0.0082450000 0.0003950000 0.0038880000 0.0000040000 0.0000040000 0.0017880000 38221141 96830484 509673472 3.8419244289 3.9754691124 4.0361428261 950 1311867750.3150129318 0.2118826956 0.1343501807 0.2376661599 0.0048378470 0.0063990000 0.0003920000 0.0028830000 0.0000010000 0.0000030000 0.0009630000 38224869 96830484 509673472 3.8412566185 3.9759078026 4.0357437134 951 1311867750.3469090462 0.2100118846 0.1344297408 0.2376661599 0.0048373219 0.0089580000 0.0004980000 0.0030810000 0.0000080000 0.0000070000 0.0013840000 38228485 96830484 509673472 3.8429410458 3.9745767117 4.0356407166 952 1311867750.3828659058 0.2105215043 0.1345096691 0.2376661599 0.0048348622 0.0076450000 0.0004160000 0.0036060000 0.0000010000 0.0000050000 0.0009810000 38232269 96830484 509673472 3.8422679901 3.9755592346 4.0356349945 953 1311867750.4148640633 0.2104096711 0.1345893124 0.2376661599 0.0048324432 0.0064350000 0.0004020000 0.0020910000 0.0000040000 0.0000030000 0.0017910000 38235997 96830484 509673472 3.8420152664 3.9752819538 4.0356330872 954 1311867750.4469859600 0.2096002400 0.1346679402 0.2376661599 0.0048299732 0.0067490000 0.0003920000 0.0032210000 0.0000010000 0.0000030000 0.0009650000 38239613 96830484 509673472 3.8423249722 3.9749495983 4.0353765488 955 1311867750.4829618931 0.2091739476 0.1347459569 0.2376661599 0.0048280250 0.0059630000 0.0003980000 0.0022010000 0.0000040000 0.0000040000 0.0012160000 38243341 96830484 509673472 3.8422443867 3.9753286839 4.0344491005 956 1311867750.5148859024 0.2090812474 0.1348237135 0.2376661599 0.0048256797 0.0098420000 0.0005820000 0.0025750000 0.0000010000 0.0000110000 0.0012540000 38246957 96830484 509673472 3.8419649601 3.9754457474 4.0341305733 957 1311867750.5476069450 0.2079694420 0.1349001458 0.2376661599 0.0048238514 0.0089480000 0.0005240000 0.0022680000 0.0000080000 0.0000070000 0.0019680000 38250685 96830484 509673472 3.8428390026 3.9747092724 4.0337958336 958 1311867750.5827779770 0.2076240927 0.1349760581 0.2376661599 0.0048236055 0.0085360000 0.0005080000 0.0027590000 0.0000010000 0.0000080000 0.0011100000 38254469 96830484 509673472 3.8428702354 3.9757878780 4.0335669518 959 1311867750.6148829460 0.2069399953 0.1350510987 0.2376661599 0.0048220827 0.0063540000 0.0004310000 0.0019160000 0.0000050000 0.0000050000 0.0012370000 38258085 96830484 509673472 3.8430929184 3.9763422012 4.0330748558 960 1311867750.6469810009 0.2067088336 0.1351257422 0.2376661599 0.0048198404 0.0065350000 0.0004000000 0.0029000000 0.0000000000 0.0000030000 0.0009630000 38261813 96830484 509673472 3.8426654339 3.9761054516 4.0327348709 961 1311867750.6829319000 0.2064736485 0.1351999856 0.2376661599 0.0048199064 0.0068990000 0.0003980000 0.0025510000 0.0000040000 0.0000030000 0.0017700000 38265597 96830484 509673472 3.8424463272 3.9769670963 4.0329227448 962 1311867750.7149219513 0.2047832757 0.1352723175 0.2376661599 0.0048194584 0.0061150000 0.0004040000 0.0025620000 0.0000010000 0.0000030000 0.0009560000 38269325 96830484 509673472 3.8438239098 3.9768319130 4.0327029228 963 1311867750.7469151020 0.2046165019 0.1353443260 0.2376661599 0.0048172843 0.0094700000 0.0005020000 0.0034650000 0.0000080000 0.0000070000 0.0013690000 38272941 96830484 509673472 3.8436970711 3.9761080742 4.0327849388 964 1311867750.7832129002 0.2038813829 0.1354154225 0.2376661599 0.0048174621 0.0064480000 0.0004160000 0.0022710000 0.0000010000 0.0000040000 0.0009730000 38276669 96830484 509673472 3.8440647125 3.9765667915 4.0329794884 965 1311867750.8149549961 0.2025986612 0.1354850424 0.2376661599 0.0048150579 0.0096360000 0.0005020000 0.0024100000 0.0000100000 0.0000090000 0.0020980000 38280229 96830484 509673472 3.8452386856 3.9777836800 4.0331773758 966 1311867750.8468461037 0.2022132427 0.1355541192 0.2376661599 0.0048171992 0.0071900000 0.0004230000 0.0029630000 0.0000000000 0.0000050000 0.0009870000 38283901 96830484 509673472 3.8452105522 3.9775769711 4.0329566002 967 1311867750.8828840256 0.2015905529 0.1356224093 0.2376661599 0.0048148699 0.0061290000 0.0004090000 0.0022270000 0.0000040000 0.0000040000 0.0012160000 38287741 96830484 509673472 3.8455390930 3.9776992798 4.0328049660 968 1311867750.9147970676 0.2007075995 0.1356896460 0.2376661599 0.0048133592 0.0053160000 0.0004010000 0.0017590000 0.0000000000 0.0000030000 0.0009520000 38291357 96830484 509673472 3.8463776112 3.9779064655 4.0329284668 969 1311867750.9468770027 0.2008157820 0.1357568557 0.2376661599 0.0048118151 0.0126430000 0.0006440000 0.0047470000 0.0000120000 0.0000090000 0.0021170000 38295029 96830484 509673472 3.8460185528 3.9783585072 4.0329499245 970 1311867750.9830369949 0.2001856416 0.1358232771 0.2376661599 0.0048110424 0.0079660000 0.0004400000 0.0035650000 0.0000010000 0.0000050000 0.0009790000 38298869 96830484 509673472 3.8464298248 3.9773540497 4.0328221321 971 1311867751.0168409348 0.1987376064 0.1358880704 0.2376661599 0.0048102853 0.0078900000 0.0004110000 0.0039460000 0.0000040000 0.0000030000 0.0012140000 38302597 96830484 509673472 3.8475058079 3.9769561291 4.0324101448 972 1311867751.0470340252 0.1980091333 0.1359519810 0.2376661599 0.0048091669 0.0075500000 0.0004010000 0.0039380000 0.0000000000 0.0000030000 0.0009680000 38306213 96830484 509673472 3.8475608826 3.9779736996 4.0318937302 973 1311867751.0828599930 0.1962658018 0.1360139685 0.2376661599 0.0048068449 0.0090300000 0.0005160000 0.0024070000 0.0000070000 0.0000070000 0.0019490000 38309941 96830484 509673472 3.8488881588 3.9781444073 4.0311555862 974 1311867751.1174809933 0.1970838755 0.1360766686 0.2376661599 0.0048047443 0.0088360000 0.0005030000 0.0031090000 0.0000010000 0.0000080000 0.0010940000 38313725 96830484 509673472 3.8474981785 3.9769756794 4.0307669640 975 1311867751.1468789577 0.1962473691 0.1361383821 0.2376661599 0.0048050202 0.0093750000 0.0005300000 0.0034600000 0.0000080000 0.0000070000 0.0013510000 38317285 96830484 509673472 3.8482878208 3.9773597717 4.0304484367 976 1311867751.1835930347 0.1951197088 0.1361988138 0.2376661599 0.0048039207 0.0070880000 0.0004210000 0.0029630000 0.0000010000 0.0000050000 0.0009780000 38321125 96830484 509673472 3.8486955166 3.9780967236 4.0299601555 977 1311867751.2161049843 0.1955737025 0.1362595865 0.2376661599 0.0048016862 0.0112390000 0.0004970000 0.0045840000 0.0000070000 0.0000070000 0.0019430000 38324797 96830484 509673472 3.8478913307 3.9780743122 4.0297446251 978 1311867751.2468481064 0.1956478804 0.1363203107 0.2376661599 0.0048004210 0.0065460000 0.0004160000 0.0022760000 0.0000010000 0.0000050000 0.0009840000 38328413 96830484 509673472 3.8477687836 3.9776084423 4.0294423103 979 1311867751.2831909657 0.1955886036 0.1363808503 0.2376661599 0.0048025906 0.0079240000 0.0004010000 0.0040630000 0.0000040000 0.0000030000 0.0012380000 38332253 96830484 509673472 3.8475351334 3.9799444675 4.0294342041 980 1311867751.3149859905 0.1951242238 0.1364407925 0.2376661599 0.0048003315 0.0064910000 0.0003940000 0.0028980000 0.0000000000 0.0000040000 0.0009640000 38335869 96830484 509673472 3.8477919102 3.9801971912 4.0292010307 981 1311867751.3498640060 0.1958852708 0.1365013883 0.2376661599 0.0047992770 0.0069250000 0.0003960000 0.0025710000 0.0000030000 0.0000030000 0.0017470000 38339653 96830484 509673472 3.8464975357 3.9783906937 4.0288743973 982 1311867751.3834669590 0.1944687068 0.1365604182 0.2376661599 0.0047979336 0.0061440000 0.0003930000 0.0025660000 0.0000000000 0.0000040000 0.0009470000 38343381 96830484 509673472 3.8474540710 3.9799935818 4.0281348228 983 1311867751.4151160717 0.1930488646 0.1366178835 0.2376661599 0.0047975507 0.0064080000 0.0003940000 0.0025730000 0.0000040000 0.0000030000 0.0012220000 38347053 96830484 509673472 3.8490197659 3.9803805351 4.0274062157 984 1311867751.4513890743 0.1927053332 0.1366748830 0.2376661599 0.0047963348 0.0079540000 0.0003890000 0.0042830000 0.0000000000 0.0000030000 0.0009420000 38350781 96830484 509673472 3.8489291668 3.9783072472 4.0271754265 985 1311867751.4838130474 0.1930329949 0.1367320993 0.2376661599 0.0047939531 0.0083700000 0.0003970000 0.0039390000 0.0000040000 0.0000030000 0.0017480000 38354509 96830484 509673472 3.8485960960 3.9788062572 4.0266690254 986 1311867751.5149779320 0.1925300509 0.1367886895 0.2376661599 0.0047930935 0.0077990000 0.0003910000 0.0041570000 0.0000000000 0.0000040000 0.0009710000 38358181 96830484 509673472 3.8486118317 3.9801578522 4.0264730453 987 1311867751.5495769978 0.1923073679 0.1368449395 0.2376661599 0.0047908939 0.0086630000 0.0004980000 0.0024390000 0.0000100000 0.0000090000 0.0013450000 38361909 96830484 509673472 3.8485355377 3.9796922207 4.0263757706 988 1311867751.5829720497 0.1907794774 0.1368995291 0.2376661599 0.0047887636 0.0068460000 0.0004190000 0.0026260000 0.0000010000 0.0000060000 0.0010130000 38365581 96830484 509673472 3.8503253460 3.9798367023 4.0261983871 989 1311867751.6149520874 0.1906026751 0.1369538295 0.2376661599 0.0047872763 0.0066870000 0.0004040000 0.0022440000 0.0000030000 0.0000030000 0.0017770000 38369253 96830484 509673472 3.8502974510 3.9804401398 4.0260186195 990 1311867751.6501350403 0.1893642992 0.1370067694 0.2376661599 0.0047854978 0.0065170000 0.0003970000 0.0029190000 0.0000000000 0.0000040000 0.0009720000 38372981 96830484 509673472 3.8509171009 3.9799747467 4.0256686211 991 1311867751.6839730740 0.1889974475 0.1370592323 0.2376661599 0.0047831403 0.0107920000 0.0005920000 0.0033100000 0.0000200000 0.0000150000 0.0014640000 38376765 96830484 509673472 3.8510823250 3.9799478054 4.0254602432 992 1311867751.7150709629 0.1880716383 0.1371106560 0.2376661599 0.0047820306 0.0089830000 0.0004580000 0.0043680000 0.0000000000 0.0000050000 0.0010080000 38380325 96830484 509673472 3.8518266678 3.9794404507 4.0252509117 993 1311867751.7507519722 0.1871556789 0.1371610539 0.2376661599 0.0047799226 0.0068210000 0.0004110000 0.0022350000 0.0000040000 0.0000040000 0.0017810000 38384109 96830484 509673472 3.8523280621 3.9793870449 4.0249376297 994 1311867751.7830109596 0.1874256432 0.1372116219 0.2376661599 0.0047784483 0.0058720000 0.0003970000 0.0022220000 0.0000010000 0.0000030000 0.0009630000 38387781 96830484 509673472 3.8516924381 3.9790971279 4.0248403549 995 1311867751.8149600029 0.1864786893 0.1372611365 0.2376661599 0.0047772134 0.0093530000 0.0005040000 0.0027860000 0.0000110000 0.0000090000 0.0013510000 38391453 96830484 509673472 3.8524124622 3.9800283909 4.0247273445 996 1311867751.8509531021 0.1855143905 0.1373095835 0.2376661599 0.0047763081 0.0076350000 0.0004280000 0.0033230000 0.0000000000 0.0000040000 0.0009790000 38395237 96830484 509673472 3.8530454636 3.9796502590 4.0244050026 997 1311867751.8832330704 0.1853525490 0.1373577711 0.2376661599 0.0047742106 0.0078130000 0.0004180000 0.0032600000 0.0000040000 0.0000030000 0.0017550000 38398909 96830484 509673472 3.8527309895 3.9793455601 4.0243220329 998 1311867751.9149179459 0.1849929243 0.1374055017 0.2376661599 0.0047738627 0.0078210000 0.0004040000 0.0041600000 0.0000010000 0.0000040000 0.0009620000 38402525 96830484 509673472 3.8524940014 3.9801387787 4.0242938995 999 1311867751.9530611038 0.1824649423 0.1374506062 0.2376661599 0.0047724373 0.0106970000 0.0004890000 0.0044410000 0.0000070000 0.0000080000 0.0013470000 38406421 96830484 509673472 3.8546850681 3.9805493355 4.0240550041 1000 1311867751.9829521179 0.1815708876 0.1374947265 0.2376661599 0.0047707803 0.0066210000 0.0004180000 0.0022890000 0.0000000000 0.0000040000 0.0009650000 38410037 96830484 509673472 3.8551743031 3.9800782204 4.0239095688 1001 1311867752.0153670311 0.1813644469 0.1375385524 0.2376661599 0.0047709921 0.0088070000 0.0004030000 0.0043150000 0.0000030000 0.0000030000 0.0017770000 38413653 96830484 509673472 3.8549027443 3.9810774326 4.0239362717 1002 1311867752.0510330200 0.1792480648 0.1375801787 0.2376661599 0.0047691942 0.0098790000 0.0005350000 0.0035730000 0.0000010000 0.0000070000 0.0011000000 38417437 96830484 509673472 3.8568871021 3.9816915989 4.0234165192 1003 1311867752.0828928947 0.1784647256 0.1376209409 0.2376661599 0.0047672862 0.0074410000 0.0004320000 0.0029740000 0.0000050000 0.0000040000 0.0012180000 38421165 96830484 509673472 3.8571135998 3.9810600281 4.0231304169 1004 1311867752.1150529385 0.1752313077 0.1376584014 0.2376661599 0.0047656328 0.0062540000 0.0003980000 0.0025920000 0.0000010000 0.0000030000 0.0009430000 38424781 96830484 509673472 3.8602008820 3.9807384014 4.0225601196 1005 1311867752.1509859562 0.1727566123 0.1376933250 0.2376661599 0.0047646502 0.0093630000 0.0005080000 0.0027790000 0.0000080000 0.0000070000 0.0019190000 38428565 96830484 509673472 3.8617575169 3.9812574387 4.0221052170 1006 1311867752.1829679012 0.1727765501 0.1377281990 0.2376661599 0.0047636409 0.0069160000 0.0004340000 0.0026400000 0.0000010000 0.0000050000 0.0009710000 38432293 96830484 509673472 3.8611423969 3.9809741974 4.0219373703 1007 1311867752.2150039673 0.1722763330 0.1377625070 0.2376661599 0.0047613447 0.0061890000 0.0004100000 0.0022580000 0.0000040000 0.0000040000 0.0011980000 38435965 96830484 509673472 3.8609516621 3.9814257622 4.0215411186 1008 1311867752.2512340546 0.1707574427 0.1377952401 0.2376661599 0.0047611326 0.0061420000 0.0004030000 0.0024850000 0.0000000000 0.0000040000 0.0009450000 38439693 96830484 509673472 3.8621392250 3.9823472500 4.0211400986 1009 1311867752.2833271027 0.1713500321 0.1378284956 0.2376661599 0.0047597084 0.0106600000 0.0005090000 0.0041450000 0.0000080000 0.0000070000 0.0018990000 38443365 96830484 509673472 3.8613467216 3.9823105335 4.0213541985 1010 1311867752.3150799274 0.1685404480 0.1378589034 0.2376661599 0.0047621584 0.0075530000 0.0004380000 0.0033630000 0.0000010000 0.0000040000 0.0009630000 38446981 96830484 509673472 3.8637311459 3.9813783169 4.0207986832 1011 1311867752.3509979248 0.1683879644 0.1378891003 0.2376661599 0.0047625267 0.0060780000 0.0004210000 0.0021470000 0.0000040000 0.0000040000 0.0012100000 38450765 96830484 509673472 3.8640439510 3.9815278053 4.0209093094 1012 1311867752.3829851151 0.1690185368 0.1379198606 0.2376661599 0.0047603333 0.0058950000 0.0004160000 0.0022710000 0.0000000000 0.0000050000 0.0009370000 38454493 96830484 509673472 3.8632876873 3.9807779789 4.0207819939 1013 1311867752.4160280228 0.1672149003 0.1379487797 0.2376661599 0.0047584861 0.0089320000 0.0004180000 0.0043630000 0.0000040000 0.0000030000 0.0017270000 38458165 96830484 509673472 3.8649182320 3.9811415672 4.0202240944 1014 1311867752.4510710239 0.1680724323 0.1379784875 0.2376661599 0.0047620535 0.0093860000 0.0005100000 0.0031890000 0.0000010000 0.0000080000 0.0010920000 38461949 96830484 509673472 3.8636572361 3.9814500809 4.0202021599 1015 1311867752.4829080105 0.1670292318 0.1380071089 0.2376661599 0.0047606290 0.0074750000 0.0004360000 0.0028910000 0.0000040000 0.0000050000 0.0012040000 38465621 96830484 509673472 3.8648498058 3.9802894592 4.0196971893 1016 1311867752.5181159973 0.1669816822 0.1380356272 0.2376661599 0.0047610785 0.0060130000 0.0004170000 0.0022660000 0.0000000000 0.0000030000 0.0009430000 38469349 96830484 509673472 3.8645293713 3.9799904823 4.0192689896 1017 1311867752.5511059761 0.1659666002 0.1380630913 0.2376661599 0.0047604841 0.0074030000 0.0004080000 0.0029550000 0.0000040000 0.0000030000 0.0017100000 38473021 96830484 509673472 3.8656365871 3.9807429314 4.0187115669 1018 1311867752.5830090046 0.1654548645 0.1380899987 0.2376661599 0.0047583610 0.0058500000 0.0004090000 0.0021630000 0.0000010000 0.0000030000 0.0009480000 38476749 96830484 509673472 3.8659324646 3.9809372425 4.0185112953 1019 1311867752.6167891026 0.1656566709 0.1381170514 0.2376661599 0.0047561638 0.0122570000 0.0005910000 0.0047460000 0.0000090000 0.0000090000 0.0014330000 38480421 96830484 509673472 3.8657674789 3.9803450108 4.0180578232 1020 1311867752.6514921188 0.1662115604 0.1381445950 0.2376661599 0.0047553306 0.0072710000 0.0004460000 0.0026770000 0.0000010000 0.0000060000 0.0009930000 38484149 96830484 509673472 3.8652708530 3.9808919430 4.0179896355 1021 1311867752.6830079556 0.1648746282 0.1381707753 0.2376661599 0.0047558017 0.0071720000 0.0004180000 0.0026200000 0.0000040000 0.0000040000 0.0017120000 38487821 96830484 509673472 3.8666539192 3.9803707600 4.0174431801 1022 1311867752.7152869701 0.1640625447 0.1381961097 0.2376661599 0.0047570523 0.0063060000 0.0004070000 0.0026070000 0.0000010000 0.0000030000 0.0009440000 38491549 96830484 509673472 3.8675992489 3.9797098637 4.0170674324 1023 1311867752.7510609627 0.1644552946 0.1382217785 0.2376661599 0.0047547296 0.0080290000 0.0004120000 0.0041120000 0.0000030000 0.0000030000 0.0011890000 38495221 96830484 509673472 3.8671159744 3.9789991379 4.0165777206 1024 1311867752.7830440998 0.1644692272 0.1382474107 0.2376661599 0.0047639258 0.0063740000 0.0004120000 0.0026020000 0.0000010000 0.0000030000 0.0009420000 38498949 96830484 509673472 3.8670942783 3.9801611900 4.0162138939 1025 1311867752.8162839413 0.1621084213 0.1382706898 0.2376661599 0.0047620644 0.0075440000 0.0004040000 0.0029540000 0.0000040000 0.0000040000 0.0017200000 38600925 96830484 509673472 3.8694326878 3.9807612896 4.0153489113 1026 1311867752.8511059284 0.1612574011 0.1382930940 0.2376661599 0.0047599113 0.0060670000 0.0004120000 0.0022480000 0.0000000000 0.0000040000 0.0009440000 38809453 96830484 509673472 3.8703866005 3.9808328152 4.0148072243 1027 1311867752.8833000660 0.1619211882 0.1383161009 0.2376661599 0.0047578628 0.0097430000 0.0005140000 0.0033940000 0.0000070000 0.0000070000 0.0013080000 38813181 96830484 509673472 3.8696331978 3.9809424877 4.0147500038 1028 1311867752.9183809757 0.1602614522 0.1383374485 0.2376661599 0.0047557122 0.0103370000 0.0005280000 0.0045810000 0.0000000000 0.0000090000 0.0010940000 38816965 96830484 509673472 3.8717200756 3.9815080166 4.0142726898 1029 1311867752.9511129856 0.1597455144 0.1383582532 0.2376661599 0.0047598085 0.0082860000 0.0004480000 0.0033350000 0.0000040000 0.0000040000 0.0017470000 38820581 96830484 509673472 3.8721330166 3.9810674191 4.0140113831 1030 1311867752.9828579426 0.1602004319 0.1383794592 0.2376661599 0.0047576797 0.0065750000 0.0004090000 0.0028590000 0.0000010000 0.0000040000 0.0009240000 38824309 96830484 509673472 3.8716096878 3.9808292389 4.0137319565 1031 1311867753.0168170929 0.1576011181 0.1383981029 0.2376661599 0.0047556583 0.0064060000 0.0004050000 0.0019000000 0.0000040000 0.0000030000 0.0011860000 38827981 96830484 509673472 3.8744628429 3.9810256958 4.0132412910 1032 1311867753.0510199070 0.1601639688 0.1384191939 0.2376661599 0.0047538913 0.0083040000 0.0004630000 0.0043450000 0.0000000000 0.0000030000 0.0009420000 38831709 96830484 509673472 3.8718044758 3.9804122448 4.0130586624 1033 1311867753.0829060078 0.1593909711 0.1384394957 0.2376661599 0.0047530312 0.0068090000 0.0004110000 0.0022560000 0.0000040000 0.0000030000 0.0017170000 38835325 96830484 509673472 3.8723824024 3.9805207253 4.0124530792 1034 1311867753.1184310913 0.1584126353 0.1384588121 0.2376661599 0.0047508257 0.0095540000 0.0005090000 0.0032010000 0.0000000000 0.0000080000 0.0010710000 38839165 96830484 509673472 3.8733069897 3.9818799496 4.0119643211 1035 1311867753.1510760784 0.1572225392 0.1384769413 0.2376661599 0.0047487345 0.0086920000 0.0004330000 0.0040620000 0.0000050000 0.0000040000 0.0012090000 38842781 96830484 509673472 3.8744840622 3.9806349277 4.0117940903 1036 1311867753.1830070019 0.1575652361 0.1384953663 0.2376661599 0.0047467461 0.0060280000 0.0004040000 0.0022560000 0.0000010000 0.0000040000 0.0009450000 38846397 96830484 509673472 3.8737304211 3.9796648026 4.0114417076 1037 1311867753.2186999321 0.1561581492 0.1385123989 0.2376661599 0.0047469188 0.0089300000 0.0004010000 0.0043380000 0.0000030000 0.0000030000 0.0016990000 38850237 96830484 509673472 3.8750565052 3.9818029404 4.0112972260 1038 1311867753.2520470619 0.1557065696 0.1385289636 0.2376661599 0.0047446921 0.0060770000 0.0003990000 0.0022640000 0.0000000000 0.0000030000 0.0009420000 38853853 96830484 509673472 3.8753173351 3.9819457531 4.0111775398 1039 1311867753.2829909325 0.1543542147 0.1385441948 0.2376661599 0.0047431275 0.0089360000 0.0004980000 0.0026690000 0.0000080000 0.0000070000 0.0013040000 38857525 96830484 509673472 3.8761005402 3.9816651344 4.0107970238 1040 1311867753.3196740150 0.1500238478 0.1385552329 0.2376661599 0.0047453541 0.0076780000 0.0004320000 0.0033520000 0.0000000000 0.0000040000 0.0009560000 38861365 96830484 509673472 3.8797891140 3.9828526974 4.0100402832 1041 1311867753.3509368896 0.1487834156 0.1385650583 0.2376661599 0.0047433678 0.0114540000 0.0005180000 0.0046190000 0.0000070000 0.0000070000 0.0018800000 38864925 96830484 509673472 3.8808038235 3.9833257198 4.0099143982 1042 1311867753.3829340935 0.1501561552 0.1385761822 0.2376661599 0.0047428661 0.0069050000 0.0004290000 0.0025370000 0.0000000000 0.0000050000 0.0009630000 38868653 96830484 509673472 3.8790519238 3.9813518524 4.0101799965 1043 1311867753.4182109833 0.1513951272 0.1385884726 0.2376661599 0.0047412058 0.0110020000 0.0005010000 0.0046070000 0.0000080000 0.0000070000 0.0013130000 38872437 96830484 509673472 3.8772492409 3.9822378159 4.0097908974 1044 1311867753.4511721134 0.1500712931 0.1385994715 0.2376661599 0.0047391829 0.0151420000 0.0005960000 0.0033290000 0.0000020000 0.0000160000 0.0014520000 38876053 96830484 509673472 3.8780221939 3.9828205109 4.0092639923 1045 1311867753.4831509590 0.1484964490 0.1386089423 0.2376661599 0.0047377038 0.0141900000 0.0006050000 0.0033520000 0.0000140000 0.0000140000 0.0023940000 38879781 96830484 509673472 3.8788840771 3.9821982384 4.0084753036 1046 1311867753.5199849606 0.1477284580 0.1386176608 0.2376661599 0.0047355598 0.0093530000 0.0004450000 0.0044270000 0.0000010000 0.0000050000 0.0009640000 38883621 96830484 509673472 3.8788228035 3.9829277992 4.0077714920 1047 1311867753.5532789230 0.1467492580 0.1386254273 0.2376661599 0.0047334136 0.0084550000 0.0004150000 0.0043340000 0.0000040000 0.0000030000 0.0011820000 38887293 96830484 509673472 3.8790893555 3.9825334549 4.0074677467 1048 1311867753.5832290649 0.1451252997 0.1386316295 0.2376661599 0.0047315206 0.0066720000 0.0003990000 0.0029400000 0.0000010000 0.0000040000 0.0009310000 38890909 96830484 509673472 3.8800272942 3.9825015068 4.0068717003 1049 1311867753.6183180809 0.1436869651 0.1386364487 0.2376661599 0.0047296096 0.0165780000 0.0006040000 0.0037380000 0.0000150000 0.0000140000 0.0023770000 38894693 96830484 509673472 3.8805289268 3.9833679199 4.0063476562 1050 1311867753.6509299278 0.1440097988 0.1386415662 0.2376661599 0.0047276990 0.0091550000 0.0005430000 0.0030720000 0.0000010000 0.0000070000 0.0010700000 38898365 96830484 509673472 3.8795928955 3.9825475216 4.0062675476 1051 1311867753.6830120087 0.1419884115 0.1386447506 0.2376661599 0.0047272924 0.0081780000 0.0004250000 0.0036820000 0.0000040000 0.0000040000 0.0011830000 38901981 96830484 509673472 3.8810791969 3.9824063778 4.0056338310 1052 1311867753.7204821110 0.1404289901 0.1386464467 0.2376661599 0.0047252462 0.0063830000 0.0004050000 0.0025850000 0.0000010000 0.0000030000 0.0009340000 38905877 96830484 509673472 3.8821201324 3.9833469391 4.0054039955 1053 1311867753.7510209084 0.1403565407 0.1386480707 0.2376661599 0.0047237021 0.0088420000 0.0003960000 0.0043110000 0.0000040000 0.0000040000 0.0016880000 38909437 96830484 509673472 3.8813748360 3.9830152988 4.0053939819 1054 1311867753.7865459919 0.1384635419 0.1386478956 0.2376661599 0.0047232766 0.0080480000 0.0004020000 0.0042950000 0.0000000000 0.0000030000 0.0009260000 38913221 96830484 509673472 3.8822951317 3.9822473526 4.0049791336 1055 1311867753.8151860237 0.1359712183 0.1386453585 0.2376661599 0.0047219909 0.0107870000 0.0004980000 0.0042270000 0.0000070000 0.0000070000 0.0013080000 38916781 96830484 509673472 3.8847126961 3.9839215279 4.0048475266 1056 1311867753.8510670662 0.1355080456 0.1386423875 0.2376661599 0.0047212858 0.0067620000 0.0004300000 0.0022870000 0.0000000000 0.0000050000 0.0009460000 38920565 96830484 509673472 3.8841965199 3.9838902950 4.0047850609 1057 1311867753.8831698895 0.1341672689 0.1386381537 0.2376661599 0.0047302258 0.0089120000 0.0004140000 0.0043080000 0.0000040000 0.0000030000 0.0017070000 38924293 96830484 509673472 3.8849034309 3.9819424152 4.0045351982 1058 1311867753.9155960083 0.1326466501 0.1386324907 0.2376661599 0.0047287475 0.0070650000 0.0004060000 0.0032590000 0.0000010000 0.0000030000 0.0009320000 38927909 96830484 509673472 3.8857171535 3.9826886654 4.0042643547 1059 1311867753.9511620998 0.1314968169 0.1386257526 0.2376661599 0.0047297297 0.0093400000 0.0005180000 0.0020740000 0.0000100000 0.0000090000 0.0014220000 38931693 96830484 509673472 3.8862190247 3.9842483997 4.0045185089 1060 1311867753.9859020710 0.1314182281 0.1386189530 0.2376661599 0.0047295829 0.0105700000 0.0004980000 0.0042200000 0.0000010000 0.0000070000 0.0010570000 38935477 96830484 509673472 3.8855464458 3.9828875065 4.0046019554 1061 1311867754.0151760578 0.1310267299 0.1386117973 0.2376661599 0.0047280989 0.0084670000 0.0004260000 0.0033250000 0.0000050000 0.0000040000 0.0017110000 38939037 96830484 509673472 3.8847100735 3.9816348553 4.0047488213 1062 1311867754.0510439873 0.1273071319 0.1386011526 0.2376661599 0.0047345801 0.0080600000 0.0004060000 0.0043030000 0.0000000000 0.0000030000 0.0009290000 38942877 96830484 509673472 3.8877642155 3.9833285809 4.0047698021 1063 1311867754.0839149952 0.1253614426 0.1385886976 0.2376661599 0.0047332491 0.0067360000 0.0004070000 0.0025710000 0.0000040000 0.0000040000 0.0011640000 38946549 96830484 509673472 3.8890309334 3.9831357002 4.0045685768 1064 1311867754.1166028976 0.1236656755 0.1385746722 0.2376661599 0.0047319482 0.0081480000 0.0004060000 0.0042810000 0.0000000000 0.0000040000 0.0009370000 38950221 96830484 509673472 3.8898727894 3.9823846817 4.0048408508 1065 1311867754.1511039734 0.1216300875 0.1385587618 0.2376661599 0.0047326356 0.0088850000 0.0004020000 0.0042720000 0.0000040000 0.0000030000 0.0017070000 38953893 96830484 509673472 3.8911116123 3.9829094410 4.0046076775 1066 1311867754.1832261086 0.1205805242 0.1385418966 0.2376661599 0.0047307188 0.0067150000 0.0003970000 0.0029080000 0.0000010000 0.0000030000 0.0009560000 38957621 96830484 509673472 3.8914678097 3.9838733673 4.0051712990 1067 1311867754.2166349888 0.1196507215 0.1385241917 0.2376661599 0.0047302932 0.0083020000 0.0003980000 0.0042760000 0.0000040000 0.0000040000 0.0011630000 38961293 96830484 509673472 3.8909759521 3.9830279350 4.0048942566 1068 1311867754.2522869110 0.1182970032 0.1385052524 0.2376661599 0.0047346379 0.0093310000 0.0005100000 0.0031380000 0.0000000000 0.0000080000 0.0010590000 38965077 96830484 509673472 3.8911707401 3.9825341702 4.0050430298 1069 1311867754.2873370647 0.1143599302 0.1384826655 0.2376661599 0.0047399873 0.0108550000 0.0004890000 0.0045180000 0.0000080000 0.0000080000 0.0018290000 38968861 96830484 509673472 3.8938708305 3.9832956791 4.0048732758 1070 1311867754.3188319206 0.1166961938 0.1384623043 0.2376661599 0.0047380977 0.0073670000 0.0004430000 0.0029460000 0.0000010000 0.0000050000 0.0009410000 38972533 96830484 509673472 3.8903596401 3.9825999737 4.0054159164 1071 1311867754.3511719704 0.1159307584 0.1384412665 0.2376661599 0.0047400044 0.0073140000 0.0004040000 0.0032510000 0.0000030000 0.0000040000 0.0011780000 38976205 96830484 509673472 3.8901784420 3.9825937748 4.0055465698 1072 1311867754.3868899345 0.1138968766 0.1384183706 0.2376661599 0.0047410659 0.0066990000 0.0003910000 0.0029000000 0.0000000000 0.0000040000 0.0009220000 38979933 96830484 509673472 3.8910493851 3.9832246304 4.0051846504 1073 1311867754.4159760475 0.1135691106 0.1383952119 0.2376661599 0.0047389970 0.0087920000 0.0003960000 0.0042320000 0.0000040000 0.0000040000 0.0016900000 38983605 96830484 509673472 3.8908376694 3.9831216335 4.0051598549 1074 1311867754.4545960426 0.1105421260 0.1383692779 0.2376661599 0.0047536257 0.0080790000 0.0003970000 0.0042400000 0.0000000000 0.0000040000 0.0009340000 38987389 96830484 509673472 3.8928229809 3.9821226597 4.0054373741 1075 1311867754.4863700867 0.1089725643 0.1383419322 0.2376661599 0.0047611236 0.0075980000 0.0004060000 0.0035700000 0.0000030000 0.0000030000 0.0011640000 38991061 96830484 509673472 3.8939206600 3.9823374748 4.0055394173 1076 1311867754.5164580345 0.1082617342 0.1383139766 0.2376661599 0.0047595335 0.0100060000 0.0005010000 0.0031420000 0.0000010000 0.0000110000 0.0011680000 38994677 96830484 509673472 3.8941402435 3.9829354286 4.0057816505 1077 1311867754.5513699055 0.1074889302 0.1382853554 0.2376661599 0.0047590630 0.0095880000 0.0004550000 0.0043160000 0.0000040000 0.0000040000 0.0016860000 38998349 96830484 509673472 3.8944337368 3.9832489491 4.0060515404 1078 1311867754.5835940838 0.1047472060 0.1382542439 0.2376661599 0.0047606003 0.0081080000 0.0004030000 0.0042510000 0.0000010000 0.0000040000 0.0009220000 39002077 96830484 509673472 3.8966672421 3.9818668365 4.0056762695 1079 1311867754.6154909134 0.1052297354 0.1382236373 0.2376661599 0.0047600923 0.0077890000 0.0003930000 0.0032190000 0.0000040000 0.0000030000 0.0011610000 39005693 96830484 509673472 3.8957023621 3.9821128845 4.0061297417 1080 1311867754.6510920525 0.1046634167 0.1381925631 0.2376661599 0.0047581812 0.0082090000 0.0004480000 0.0042230000 0.0000010000 0.0000030000 0.0009210000 39009421 96830484 509673472 3.8958070278 3.9826130867 4.0062794685 1081 1311867754.6872758865 0.1028948575 0.1381599102 0.2376661599 0.0047589368 0.0088720000 0.0003900000 0.0042320000 0.0000030000 0.0000030000 0.0016820000 39013205 96830484 509673472 3.8969757557 3.9815003872 4.0062088966 1082 1311867754.7162959576 0.1029324830 0.1381273525 0.2376661599 0.0047568140 0.0063720000 0.0003950000 0.0025360000 0.0000000000 0.0000040000 0.0009170000 39016765 96830484 509673472 3.8964726925 3.9820907116 4.0064840317 1083 1311867754.7516000271 0.1017711535 0.1380937826 0.2376661599 0.0047560558 0.0073490000 0.0003940000 0.0032180000 0.0000040000 0.0000030000 0.0011510000 39020549 96830484 509673472 3.8971328735 3.9836680889 4.0067591667 1084 1311867754.7865269184 0.1006300747 0.1380592220 0.2376661599 0.0047561369 0.0081240000 0.0003940000 0.0042660000 0.0000010000 0.0000040000 0.0009210000 39024277 96830484 509673472 3.8977379799 3.9832334518 4.0067892075 1085 1311867754.8154470921 0.1013750359 0.1380254117 0.2376661599 0.0047551908 0.0075190000 0.0003910000 0.0028880000 0.0000030000 0.0000030000 0.0016640000 39027837 96830484 509673472 3.8964893818 3.9812140465 4.0070176125 1086 1311867754.8510210514 0.1007465497 0.1379910849 0.2376661599 0.0047690529 0.0080950000 0.0003990000 0.0042580000 0.0000010000 0.0000040000 0.0009260000 39031621 96830484 509673472 3.8963007927 3.9819898605 4.0074381828 1087 1311867754.8877389431 0.0979393423 0.1379542388 0.2376661599 0.0047687906 0.0066010000 0.0003970000 0.0025450000 0.0000030000 0.0000030000 0.0011590000 39035461 96830484 509673472 3.8982951641 3.9817719460 4.0070619583 1088 1311867754.9201259613 0.0959560126 0.1379156375 0.2376661599 0.0047676359 0.0080950000 0.0003990000 0.0042580000 0.0000010000 0.0000040000 0.0009310000 39039133 96830484 509673472 3.8995237350 3.9802572727 4.0069432259 1089 1311867754.9510319233 0.0952396616 0.1378764493 0.2376661599 0.0047669045 0.0075130000 0.0004060000 0.0028960000 0.0000030000 0.0000030000 0.0016530000 39042749 96830484 509673472 3.8994233608 3.9805035591 4.0068531036 1090 1311867754.9837870598 0.0940293223 0.1378362226 0.2376661599 0.0047660634 0.0064870000 0.0003950000 0.0025660000 0.0000010000 0.0000030000 0.0009100000 39046477 96830484 509673472 3.8994426727 3.9816441536 4.0074601173 1091 1311867755.0183880329 0.0931241512 0.1377952399 0.2376661599 0.0047678842 0.0080620000 0.0004020000 0.0039280000 0.0000030000 0.0000030000 0.0011580000 39050205 96830484 509673472 3.8998079300 3.9797482491 4.0077290535 1092 1311867755.0540831089 0.0938165933 0.1377549664 0.2376661599 0.0047686362 0.0081590000 0.0003990000 0.0042520000 0.0000000000 0.0000040000 0.0009140000 39053989 96830484 509673472 3.8986811638 3.9788141251 4.0083642006 1093 1311867755.0850980282 0.0944292918 0.1377153272 0.2376661599 0.0047686640 0.0088440000 0.0004050000 0.0042610000 0.0000030000 0.0000030000 0.0016390000 39057661 96830484 509673472 3.8976335526 3.9791312218 4.0088796616 1094 1311867755.1156959534 0.0940116420 0.1376753787 0.2376661599 0.0047702117 0.0081100000 0.0003970000 0.0042660000 0.0000010000 0.0000040000 0.0009130000 39061221 96830484 509673472 3.8975150585 3.9789528847 4.0090374947 1095 1311867755.1556220055 0.0931734964 0.1376347377 0.2376661599 0.0047684251 0.0079970000 0.0004100000 0.0039410000 0.0000040000 0.0000030000 0.0011400000 39065117 96830484 509673472 3.8977367878 3.9786958694 4.0092658997 1096 1311867755.1847031116 0.0938673392 0.1375948039 0.2376661599 0.0047668695 0.0080000000 0.0004000000 0.0042720000 0.0000000000 0.0000040000 0.0009020000 39068789 96830484 509673472 3.8965690136 3.9775185585 4.0095276833 1097 1311867755.2151238918 0.0921951830 0.1375534187 0.2376661599 0.0047647443 0.0070990000 0.0004050000 0.0025690000 0.0000040000 0.0000030000 0.0016240000 39072349 96830484 509673472 3.8976867199 3.9792737961 4.0095229149 1098 1311867755.2512340546 0.0923286006 0.1375122303 0.2376661599 0.0047639160 0.0070060000 0.0003940000 0.0032340000 0.0000000000 0.0000030000 0.0008990000 39076133 96830484 509673472 3.8970582485 3.9777011871 4.0098757744 1099 1311867755.2832889557 0.0919544399 0.1374707765 0.2376661599 0.0047640839 0.0082990000 0.0004030000 0.0042700000 0.0000040000 0.0000040000 0.0011500000 39079805 96830484 509673472 3.8968963623 3.9769237041 4.0095257759 1100 1311867755.3192110062 0.0907501653 0.1374283032 0.2376661599 0.0047625016 0.0066720000 0.0003990000 0.0028780000 0.0000010000 0.0000040000 0.0009150000 39083589 96830484 509673472 3.8976898193 3.9783854485 4.0091962814 1101 1311867755.3553090096 0.0916946903 0.1373867649 0.2376661599 0.0047603558 0.0106210000 0.0004700000 0.0044220000 0.0000060000 0.0000060000 0.0017260000 39087429 96830484 509673472 3.8964331150 3.9765272141 4.0091123581 1102 1311867755.3900220394 0.0932476297 0.1373467113 0.2376661599 0.0047585152 0.0084660000 0.0004150000 0.0042760000 0.0000010000 0.0000040000 0.0009240000 39091101 96830484 509673472 3.8944580555 3.9745433331 4.0088315010 1103 1311867755.4156589508 0.0926012620 0.1373061442 0.2376661599 0.0047593683 0.0082870000 0.0004080000 0.0042350000 0.0000030000 0.0000040000 0.0011520000 39094661 96830484 509673472 3.8945660591 3.9770722389 4.0085592270 1104 1311867755.4549160004 0.0923862904 0.1372654559 0.2376661599 0.0047579470 0.0062410000 0.0003970000 0.0024210000 0.0000000000 0.0000040000 0.0009220000 39098501 96830484 509673472 3.8941221237 3.9781503677 4.0087251663 1105 1311867755.4860870838 0.0924031287 0.1372248566 0.2376661599 0.0047569604 0.0088310000 0.0003970000 0.0042400000 0.0000040000 0.0000030000 0.0016760000 39102117 96830484 509673472 3.8937594891 3.9753923416 4.0085740089 1106 1311867755.5161950588 0.0945351049 0.1371862582 0.2376661599 0.0047593145 0.0081610000 0.0004030000 0.0042310000 0.0000010000 0.0000030000 0.0009340000 39105677 96830484 509673472 3.8913660049 3.9767415524 4.0091309547 1107 1311867755.5550999641 0.0929027572 0.1371462551 0.2376661599 0.0047572182 0.0083630000 0.0003970000 0.0042290000 0.0000030000 0.0000030000 0.0011670000 39109573 96830484 509673472 3.8926279545 3.9779751301 4.0090284348 1108 1311867755.5854589939 0.0935919583 0.1371069461 0.2376661599 0.0047551435 0.0095460000 0.0005040000 0.0027630000 0.0000010000 0.0000100000 0.0011810000 39113245 96830484 509673472 3.8917191029 3.9778993130 4.0089144707 1109 1311867755.6171119213 0.0924542546 0.1370666822 0.2376661599 0.0047534449 0.0101280000 0.0004910000 0.0027730000 0.0000100000 0.0000090000 0.0018960000 39116861 96830484 509673472 3.8926181793 3.9782328606 4.0087447166 1110 1311867755.6542940140 0.0926464796 0.1370266640 0.2376661599 0.0047515287 0.0097510000 0.0004280000 0.0044770000 0.0000010000 0.0000060000 0.0013430000 39120701 96830484 509673472 3.8923563957 3.9783008099 4.0090055466 1111 1311867755.6831719875 0.0937594026 0.1369877196 0.2376661599 0.0047498468 0.0083930000 0.0004070000 0.0042450000 0.0000040000 0.0000030000 0.0011640000 39124261 96830484 509673472 3.8910579681 3.9766504765 4.0086421967 1112 1311867755.7182741165 0.0922553465 0.1369474926 0.2376661599 0.0047482008 0.0081770000 0.0004330000 0.0042340000 0.0000000000 0.0000040000 0.0009370000 39128045 96830484 509673472 3.8921194077 3.9764232635 4.0079836845 1113 1311867755.7511448860 0.0932118073 0.1369081973 0.2376661599 0.0047479499 0.0088770000 0.0004000000 0.0042450000 0.0000030000 0.0000040000 0.0016940000 39131717 96830484 509673472 3.8907668591 3.9769876003 4.0077109337 1114 1311867755.7863750458 0.0944072977 0.1368700457 0.2376661599 0.0047461534 0.0105440000 0.0004930000 0.0041450000 0.0000010000 0.0000070000 0.0010770000 39135445 96830484 509673472 3.8893582821 3.9773690701 4.0077996254 1115 1311867755.8156878948 0.0907022730 0.1368286396 0.2376661599 0.0047486446 0.0077710000 0.0004260000 0.0029570000 0.0000050000 0.0000040000 0.0012060000 39139117 96830484 509673472 3.8928663731 3.9760513306 4.0066599846 1116 1311867755.8554079533 0.0892270803 0.1367859859 0.2376661599 0.0047477911 0.0068680000 0.0004050000 0.0028680000 0.0000000000 0.0000040000 0.0009500000 39142901 96830484 509673472 3.8940002918 3.9784977436 4.0066685677 1117 1311867755.8848359585 0.0905512124 0.1367445940 0.2376661599 0.0047459483 0.0078920000 0.0003960000 0.0032180000 0.0000030000 0.0000030000 0.0016840000 39146573 96830484 509673472 3.8923976421 3.9784088135 4.0069551468 1118 1311867755.9156229496 0.0894404650 0.1367022826 0.2376661599 0.0047475782 0.0067520000 0.0004000000 0.0028750000 0.0000000000 0.0000030000 0.0009400000 39150245 96830484 509673472 3.8933255672 3.9759294987 4.0064811707 1119 1311867755.9550359249 0.0889248028 0.1366595860 0.2376661599 0.0047477489 0.0084470000 0.0003900000 0.0042470000 0.0000030000 0.0000030000 0.0011730000 39154029 96830484 509673472 3.8934180737 3.9780130386 4.0066571236 1120 1311867755.9855198860 0.0899454281 0.1366178769 0.2376661599 0.0047461206 0.0081190000 0.0003940000 0.0042210000 0.0000000000 0.0000030000 0.0009370000 39157645 96830484 509673472 3.8923170567 3.9779632092 4.0069489479 1121 1311867756.0173881054 0.0899557695 0.1365762515 0.2376661599 0.0047444234 0.0109690000 0.0004930000 0.0042280000 0.0000080000 0.0000060000 0.0018690000 39161261 96830484 509673472 3.8921730518 3.9770176411 4.0068826675 1122 1311867756.0554430485 0.0873423591 0.1365323710 0.2376661599 0.0047429315 0.0073430000 0.0004240000 0.0029290000 0.0000010000 0.0000050000 0.0009470000 39165045 96830484 509673472 3.8945426941 3.9788320065 4.0067253113 1123 1311867756.0835959911 0.0883167982 0.1364894364 0.2376661599 0.0047415500 0.0083830000 0.0004000000 0.0042380000 0.0000030000 0.0000030000 0.0011610000 39168661 96830484 509673472 3.8935062885 3.9781789780 4.0068383217 1124 1311867756.1196908951 0.0907075331 0.1364487052 0.2376661599 0.0047420098 0.0067690000 0.0003940000 0.0028870000 0.0000000000 0.0000030000 0.0009290000 39172445 96830484 509673472 3.8913848400 3.9752948284 4.0070438385 1125 1311867756.1519339085 0.0881391317 0.1364057633 0.2376661599 0.0047409016 0.0068740000 0.0003970000 0.0022020000 0.0000040000 0.0000030000 0.0016860000 39175949 96830484 509673472 3.8937010765 3.9772186279 4.0065937042 1126 1311867756.1836869717 0.0899160579 0.1363644759 0.2376661599 0.0047414045 0.0091870000 0.0005010000 0.0027530000 0.0000010000 0.0000080000 0.0010660000 39179509 96830484 509673472 3.8919343948 3.9780657291 4.0072669983 1127 1311867756.2230648994 0.0905539170 0.1363238276 0.2376661599 0.0047459593 0.0090140000 0.0004230000 0.0042900000 0.0000050000 0.0000050000 0.0011780000 39183181 96830484 509673472 3.8915827274 3.9757130146 4.0072698593 1128 1311867756.2552509308 0.0898544863 0.1362826314 0.2376661599 0.0047465999 0.0064790000 0.0004080000 0.0025370000 0.0000000000 0.0000040000 0.0009560000 39186853 96830484 509673472 3.8922531605 3.9760484695 4.0073208809 1129 1311867756.2851591110 0.0898472518 0.1362415017 0.2376661599 0.0047452372 0.0073280000 0.0003910000 0.0025520000 0.0000030000 0.0000030000 0.0017020000 39190525 96830484 509673472 3.8923349380 3.9777653217 4.0075502396 1130 1311867756.3200058937 0.0907896608 0.1362012789 0.2376661599 0.0047433791 0.0065160000 0.0003990000 0.0025570000 0.0000000000 0.0000030000 0.0009300000 39194253 96830484 509673472 3.8915998936 3.9765000343 4.0077195168 1131 1311867756.3546419144 0.0893282965 0.1361598350 0.2376661599 0.0047423636 0.0126270000 0.0005880000 0.0047410000 0.0000120000 0.0000090000 0.0014230000 39198037 96830484 509673472 3.8931705952 3.9762248993 4.0073962212 1132 1311867756.3843090534 0.0902547315 0.1361192828 0.2376661599 0.0047419732 0.0091410000 0.0004430000 0.0043390000 0.0000010000 0.0000050000 0.0009720000 39201597 96830484 509673472 3.8921794891 3.9772975445 4.0078153610 1133 1311867756.4231688976 0.0899143144 0.1360785017 0.2376661599 0.0047403969 0.0090570000 0.0004060000 0.0042590000 0.0000030000 0.0000040000 0.0016740000 39205381 96830484 509673472 3.8927071095 3.9772026539 4.0079278946 1134 1311867756.4510979652 0.0910824984 0.1360388227 0.2376661599 0.0047388602 0.0068490000 0.0004000000 0.0028870000 0.0000000000 0.0000040000 0.0009390000 39208885 96830484 509673472 3.8916983604 3.9752964973 4.0080385208 1135 1311867756.4865350723 0.0904399529 0.1359986475 0.2376661599 0.0047434661 0.0084240000 0.0003950000 0.0042380000 0.0000030000 0.0000040000 0.0011560000 39212725 96830484 509673472 3.8923423290 3.9767761230 4.0084595680 1136 1311867756.5264549255 0.0900911763 0.1359582360 0.2376661599 0.0047418404 0.0081990000 0.0004000000 0.0042590000 0.0000000000 0.0000030000 0.0009330000 39216565 96830484 509673472 3.8929066658 3.9762141705 4.0084443092 1137 1311867756.5525779724 0.0907405168 0.1359184667 0.2376661599 0.0047403427 0.0089760000 0.0004010000 0.0042680000 0.0000050000 0.0000030000 0.0016640000 39220125 96830484 509673472 3.8924376965 3.9756066799 4.0087218285 1138 1311867756.5897810459 0.0894389600 0.1358776235 0.2376661599 0.0047387300 0.0065340000 0.0004070000 0.0025540000 0.0000010000 0.0000040000 0.0009250000 39223965 96830484 509673472 3.8937871456 3.9762728214 4.0085978508 1139 1311867756.6202929020 0.0914654210 0.1358386313 0.2376661599 0.0047373818 0.0078050000 0.0004090000 0.0036020000 0.0000040000 0.0000040000 0.0011540000 39227525 96830484 509673472 3.8920829296 3.9744055271 4.0091476440 1140 1311867756.6518390179 0.0917005017 0.1357999136 0.2376661599 0.0047353391 0.0062900000 0.0004020000 0.0022140000 0.0000010000 0.0000040000 0.0009320000 39231197 96830484 509673472 3.8919646740 3.9737169743 4.0094976425 1141 1311867756.6839349270 0.0901979506 0.1357599469 0.2376661599 0.0047345209 0.0105790000 0.0005130000 0.0034700000 0.0000080000 0.0000070000 0.0018240000 39234813 96830484 509673472 3.8931925297 3.9746284485 4.0093617439 1142 1311867756.7217059135 0.0906086192 0.1357204099 0.2376661599 0.0047351412 0.0089090000 0.0004370000 0.0043490000 0.0000000000 0.0000040000 0.0009460000 39238597 96830484 509673472 3.8927965164 3.9739451408 4.0097293854 1143 1311867756.7516939640 0.0904535949 0.1356808064 0.2376661599 0.0047335973 0.0084980000 0.0004070000 0.0042890000 0.0000040000 0.0000030000 0.0011450000 39242213 96830484 509673472 3.8928725719 3.9735219479 4.0097284317 1144 1311867756.7872660160 0.0917408019 0.1356423973 0.2376661599 0.0047321559 0.0110410000 0.0005020000 0.0045480000 0.0000010000 0.0000080000 0.0010560000 39245997 96830484 509673472 3.8916165829 3.9736096859 4.0101070404 1145 1311867756.8227219582 0.0905112699 0.1356029814 0.2376661599 0.0047302704 0.0080950000 0.0004380000 0.0026350000 0.0000040000 0.0000040000 0.0016710000 39249781 96830484 509673472 3.8927834034 3.9734661579 4.0101833344 1146 1311867756.8542120457 0.0910261944 0.1355640837 0.2376661599 0.0047368057 0.0060930000 0.0004110000 0.0020040000 0.0000000000 0.0000030000 0.0009360000 39253397 96830484 509673472 3.8923044205 3.9724109173 4.0103988647 1147 1311867756.8841960430 0.0924110040 0.1355264611 0.2376661599 0.0047486908 0.0064360000 0.0004070000 0.0022200000 0.0000040000 0.0000030000 0.0011500000 39257069 96830484 509673472 3.8907346725 3.9731888771 4.0110440254 1148 1311867756.9223539829 0.0917635858 0.1354883402 0.2376661599 0.0047475848 0.0066390000 0.0004050000 0.0025840000 0.0000010000 0.0000040000 0.0009170000 39260853 96830484 509673472 3.8912053108 3.9726476669 4.0110669136 1149 1311867756.9552440643 0.0904488564 0.1354491413 0.2376661599 0.0047472148 0.0102150000 0.0005210000 0.0027840000 0.0000070000 0.0000070000 0.0018400000 39264581 96830484 509673472 3.8924980164 3.9713630676 4.0105643272 1150 1311867756.9841780663 0.0910272747 0.1354105136 0.2376661599 0.0047467245 0.0069710000 0.0004290000 0.0022830000 0.0000000000 0.0000040000 0.0009370000 39268141 96830484 509673472 3.8917124271 3.9726655483 4.0109515190 1151 1311867757.0282740593 0.0899580121 0.1353710240 0.2376661599 0.0047506452 0.0114540000 0.0005000000 0.0045860000 0.0000070000 0.0000070000 0.0012690000 39272149 96830484 509673472 3.8926141262 3.9711520672 4.0108604431 1152 1311867757.0552940369 0.0898124501 0.1353314767 0.2376661599 0.0047491577 0.0088960000 0.0004290000 0.0043590000 0.0000010000 0.0000050000 0.0009350000 39275709 96830484 509673472 3.8929004669 3.9699091911 4.0106468201 1153 1311867757.0858569145 0.0887304693 0.1352910595 0.2376661599 0.0047485079 0.0071550000 0.0004140000 0.0022320000 0.0000040000 0.0000030000 0.0016600000 39279325 96830484 509673472 3.8936672211 3.9723603725 4.0107355118 1154 1311867757.1283040047 0.0883892179 0.1352504166 0.2376661599 0.0047590592 0.0076800000 0.0004010000 0.0036130000 0.0000000000 0.0000030000 0.0009190000 39283221 96830484 509673472 3.8944463730 3.9688296318 4.0106267929 1155 1311867757.1522068977 0.0865465328 0.1352082488 0.2376661599 0.0047583878 0.0076620000 0.0004020000 0.0032630000 0.0000030000 0.0000030000 0.0011710000 39286613 96830484 509673472 3.8962776661 3.9682505131 4.0097727776 1156 1311867757.1851921082 0.0905420110 0.1351696102 0.2376661599 0.0047617936 0.0069610000 0.0003960000 0.0029040000 0.0000000000 0.0000030000 0.0009320000 39290341 96830484 509673472 3.8922114372 3.9702498913 4.0106444359 1157 1311867757.2192370892 0.0894195586 0.1351300682 0.2376661599 0.0047607125 0.0077450000 0.0003940000 0.0028940000 0.0000030000 0.0000030000 0.0016730000 39294125 96830484 509673472 3.8937149048 3.9686789513 4.0099611282 1158 1311867757.2523930073 0.0881406441 0.1350894901 0.2376661599 0.0047816200 0.0074350000 0.0004090000 0.0032410000 0.0000000000 0.0000040000 0.0009420000 39297797 96830484 509673472 3.8951964378 3.9682178497 4.0091357231 1159 1311867757.2835690975 0.0883567929 0.1350491685 0.2376661599 0.0047850638 0.0086170000 0.0003920000 0.0042380000 0.0000040000 0.0000040000 0.0011910000 39301413 96830484 509673472 3.8948159218 3.9705543518 4.0089120865 1160 1311867757.3233768940 0.0907533765 0.1350109825 0.2376661599 0.0047946790 0.0069690000 0.0003900000 0.0028770000 0.0000000000 0.0000040000 0.0009480000 39305309 96830484 509673472 3.8931384087 3.9701061249 4.0089774132 1161 1311867757.3555359840 0.0900115892 0.1349722233 0.2376661599 0.0047929999 0.0090980000 0.0003980000 0.0042360000 0.0000040000 0.0000040000 0.0017180000 39309037 96830484 509673472 3.8938658237 3.9702539444 4.0087280273 1162 1311867757.3833439350 0.0899221152 0.1349334539 0.2376661599 0.0047927809 0.0073190000 0.0003880000 0.0032130000 0.0000000000 0.0000040000 0.0009610000 39312541 96830484 509673472 3.8940050602 3.9714508057 4.0090708733 1163 1311867757.4264349937 0.0904864073 0.1348952363 0.2376661599 0.0047925199 0.0109000000 0.0004910000 0.0044800000 0.0000080000 0.0000070000 0.0013100000 39316437 96830484 509673472 3.8937478065 3.9705903530 4.0092177391 1164 1311867757.4546940327 0.0896729603 0.1348563856 0.2376661599 0.0047907172 0.0110480000 0.0004870000 0.0045290000 0.0000020000 0.0000080000 0.0010870000 39319997 96830484 509673472 3.8944742680 3.9706571102 4.0086779594 1165 1311867757.4884710312 0.0899350941 0.1348178265 0.2376661599 0.0047888213 0.0096420000 0.0004230000 0.0042810000 0.0000040000 0.0000050000 0.0017320000 39323781 96830484 509673472 3.8943912983 3.9713425636 4.0090546608 1166 1311867757.5210690498 0.0897736028 0.1347791951 0.2376661599 0.0047912417 0.0082170000 0.0004010000 0.0042240000 0.0000000000 0.0000030000 0.0009470000 39327285 96830484 509673472 3.8947718143 3.9693403244 4.0089521408 1167 1311867757.5554831028 0.0896352604 0.1347405114 0.2376661599 0.0047896810 0.0084970000 0.0004040000 0.0042010000 0.0000040000 0.0000040000 0.0011860000 39331069 96830484 509673472 3.8948943615 3.9692590237 4.0088768005 1168 1311867757.5887749195 0.0899027660 0.1347021229 0.2376661599 0.0047888158 0.0099410000 0.0004920000 0.0033880000 0.0000010000 0.0000070000 0.0010990000 39334797 96830484 509673472 3.8946406841 3.9705224037 4.0091352463 1169 1311867757.6231749058 0.0911334455 0.1346648528 0.2376661599 0.0047888192 0.0091610000 0.0004710000 0.0035710000 0.0000040000 0.0000040000 0.0017490000 39338525 96830484 509673472 3.8932805061 3.9691977501 4.0092611313 1170 1311867757.6566219330 0.0908615291 0.1346274141 0.2376661599 0.0047869949 0.0082780000 0.0004360000 0.0041910000 0.0000010000 0.0000040000 0.0009580000 39342197 96830484 509673472 3.8935835361 3.9701149464 4.0094494820 1171 1311867757.6914329529 0.0916173682 0.1345906848 0.2376661599 0.0047853695 0.0067260000 0.0003960000 0.0024190000 0.0000040000 0.0000030000 0.0012050000 39345925 96830484 509673472 3.8927855492 3.9709217548 4.0098719597 1172 1311867757.7207450867 0.0905899629 0.1345531415 0.2376661599 0.0047841061 0.0073070000 0.0003990000 0.0031800000 0.0000010000 0.0000040000 0.0009640000 39349597 96830484 509673472 3.8936867714 3.9706776142 4.0097060204 1173 1311867757.7614738941 0.0906710774 0.1345157314 0.2376661599 0.0047825461 0.0073890000 0.0004010000 0.0025160000 0.0000030000 0.0000030000 0.0017280000 39353437 96830484 509673472 3.8936257362 3.9697599411 4.0098896027 1174 1311867757.7876570225 0.0916929990 0.1344792554 0.2376661599 0.0047808045 0.0082270000 0.0003990000 0.0041840000 0.0000000000 0.0000030000 0.0009670000 39356997 96830484 509673472 3.8926026821 3.9693546295 4.0098652840 1175 1311867757.8206570148 0.0915399343 0.1344427113 0.2376661599 0.0047792326 0.0084580000 0.0003940000 0.0041630000 0.0000030000 0.0000030000 0.0011980000 39360725 96830484 509673472 3.8927931786 3.9686057568 4.0095992088 1176 1311867757.8555610180 0.0930527672 0.1344075158 0.2376661599 0.0047778658 0.0096930000 0.0004890000 0.0033850000 0.0000010000 0.0000080000 0.0010900000 39364397 96830484 509673472 3.8911147118 3.9685146809 4.0094819069 1177 1311867757.8887560368 0.0940033868 0.1343731878 0.2376661599 0.0047769930 0.0091870000 0.0004170000 0.0038920000 0.0000050000 0.0000040000 0.0017660000 39368125 96830484 509673472 3.8902561665 3.9688315392 4.0095276833 1178 1311867757.9201729298 0.0947171226 0.1343395239 0.2376661599 0.0047749954 0.0080990000 0.0003970000 0.0040580000 0.0000000000 0.0000030000 0.0009700000 39371741 96830484 509673472 3.8894553185 3.9686284065 4.0092768669 1179 1311867757.9554479122 0.0946867913 0.1343058913 0.2376661599 0.0047734985 0.0064630000 0.0003900000 0.0021730000 0.0000040000 0.0000030000 0.0011850000 39375525 96830484 509673472 3.8895261288 3.9688541889 4.0089502335 1180 1311867757.9904439449 0.0953503475 0.1342728782 0.2376661599 0.0047768248 0.0082110000 0.0003900000 0.0041510000 0.0000000000 0.0000040000 0.0009750000 39379365 96830484 509673472 3.8888769150 3.9703071117 4.0086627007 1181 1311867758.0221159458 0.0947836787 0.1342394411 0.2376661599 0.0047764608 0.0118120000 0.0004920000 0.0044430000 0.0000080000 0.0000080000 0.0019190000 39382981 96830484 509673472 3.8895463943 3.9691667557 4.0082406998 1182 1311867758.0557579994 0.0937430039 0.1342051801 0.2376661599 0.0047751284 0.0092160000 0.0004830000 0.0027010000 0.0000020000 0.0000080000 0.0011020000 39386765 96830484 509673472 3.8905389309 3.9694788456 4.0078492165 1183 1311867758.0871500969 0.0956003144 0.1341725471 0.2376661599 0.0047734964 0.0109270000 0.0004840000 0.0044470000 0.0000080000 0.0000070000 0.0013280000 39390325 96830484 509673472 3.8886041641 3.9692480564 4.0076227188 1184 1311867758.1223280430 0.0943142995 0.1341388831 0.2376661599 0.0047723903 0.0086830000 0.0004140000 0.0042100000 0.0000010000 0.0000050000 0.0009990000 39394109 96830484 509673472 3.8899822235 3.9691557884 4.0071730614 1185 1311867758.1526539326 0.0944485664 0.1341053891 0.2376661599 0.0047739564 0.0090640000 0.0003940000 0.0040580000 0.0000030000 0.0000030000 0.0017710000 39397725 96830484 509673472 3.8898336887 3.9691207409 4.0069169998 1186 1311867758.1877539158 0.0954461321 0.1340727928 0.2376661599 0.0047724562 0.0081640000 0.0003930000 0.0040590000 0.0000000000 0.0000030000 0.0009820000 39401509 96830484 509673472 3.8888461590 3.9687018394 4.0066051483 1187 1311867758.2221779823 0.0949557722 0.1340398383 0.2376661599 0.0047728192 0.0068480000 0.0003890000 0.0024970000 0.0000030000 0.0000030000 0.0012150000 39405237 96830484 509673472 3.8892848492 3.9686098099 4.0060229301 1188 1311867758.2562980652 0.0947649553 0.1340067786 0.2376661599 0.0047713165 0.0059160000 0.0003880000 0.0018420000 0.0000000000 0.0000040000 0.0009970000 39408965 96830484 509673472 3.8892965317 3.9685432911 4.0055904388 1189 1311867758.2902839184 0.0936996043 0.1339728785 0.2376661599 0.0047699846 0.0090810000 0.0003860000 0.0041590000 0.0000040000 0.0000040000 0.0017910000 39412749 96830484 509673472 3.8902144432 3.9682672024 4.0049858093 1190 1311867758.3220090866 0.0935533270 0.1339389125 0.2376661599 0.0047694971 0.0068350000 0.0003860000 0.0027290000 0.0000000000 0.0000040000 0.0009890000 39416365 96830484 509673472 3.8902795315 3.9682049751 4.0045981407 1191 1311867758.3539829254 0.0930352509 0.1339045686 0.2376661599 0.0047678865 0.0065720000 0.0003860000 0.0021710000 0.0000040000 0.0000030000 0.0012380000 39420093 96830484 509673472 3.8905241489 3.9686856270 4.0040912628 1192 1311867758.3902978897 0.0937830582 0.1338709096 0.2376661599 0.0047662444 0.0107370000 0.0004870000 0.0041280000 0.0000010000 0.0000080000 0.0011230000 39423821 96830484 509673472 3.8896224499 3.9687736034 4.0041980743 1193 1311867758.4210340977 0.0931172743 0.1338367489 0.2376661599 0.0047651830 0.0097430000 0.0004110000 0.0042810000 0.0000050000 0.0000050000 0.0018310000 39427493 96830484 509673472 3.8900501728 3.9677979946 4.0035400391 1194 1311867758.4536960125 0.0942563415 0.1338035995 0.2376661599 0.0047647245 0.0082870000 0.0003870000 0.0041620000 0.0000000000 0.0000040000 0.0010000000 39431165 96830484 509673472 3.8888092041 3.9685261250 4.0037207603 1195 1311867758.4900159836 0.0958104655 0.1337718061 0.2376661599 0.0047656349 0.0177090000 0.0006090000 0.0034910000 0.0000140000 0.0000140000 0.0017580000 39434893 96830484 509673472 3.8871326447 3.9698705673 4.0040593147 1196 1311867758.5217890739 0.0940255076 0.1337385734 0.2376661599 0.0047670851 0.0137040000 0.0005640000 0.0046990000 0.0000020000 0.0000150000 0.0014700000 39438565 96830484 509673472 3.8888461590 3.9682521820 4.0035924911 1197 1311867758.5528969765 0.0935505629 0.1337049995 0.2376661599 0.0047657056 0.0091850000 0.0004150000 0.0032540000 0.0000050000 0.0000060000 0.0017620000 39442237 96830484 509673472 3.8891460896 3.9680516720 4.0034694672 1198 1311867758.5893049240 0.0932748541 0.1336712514 0.2376661599 0.0047641972 0.0065930000 0.0003840000 0.0021700000 0.0000000000 0.0000040000 0.0009610000 39446021 96830484 509673472 3.8892858028 3.9691653252 4.0035791397 1199 1311867758.6221299171 0.0925383195 0.1336369454 0.2376661599 0.0047643360 0.0068880000 0.0003750000 0.0024750000 0.0000030000 0.0000030000 0.0011870000 39449693 96830484 509673472 3.8898286819 3.9684050083 4.0033860207 1200 1311867758.6535029411 0.0946110561 0.1336044238 0.2376661599 0.0047623939 0.0068790000 0.0003770000 0.0028200000 0.0000000000 0.0000030000 0.0009590000 39453421 96830484 509673472 3.8877382278 3.9668509960 4.0036764145 1201 1311867758.6911680698 0.0944911912 0.1335718566 0.2376661599 0.0047628350 0.0080630000 0.0003780000 0.0031600000 0.0000030000 0.0000030000 0.0017190000 39457205 96830484 509673472 3.8878064156 3.9688131809 4.0039134026 1202 1311867758.7212190628 0.0937228352 0.1335387043 0.2376661599 0.0047630736 0.0065530000 0.0003770000 0.0024760000 0.0000000000 0.0000030000 0.0009590000 39460821 96830484 509673472 3.8885936737 3.9678156376 4.0038428307 1203 1311867758.7601859570 0.0922881812 0.1335044146 0.2376661599 0.0047614670 0.0089870000 0.0004820000 0.0023040000 0.0000080000 0.0000070000 0.0013180000 39464661 96830484 509673472 3.8898591995 3.9683101177 4.0036392212 1204 1311867758.7879199982 0.0928739831 0.1334706684 0.2376661599 0.0047599672 0.0087230000 0.0004080000 0.0040990000 0.0000000000 0.0000040000 0.0009740000 39468221 96830484 509673472 3.8892083168 3.9684338570 4.0039520264 1205 1311867758.8218998909 0.0928470865 0.1334369559 0.2376661599 0.0047595758 0.0067320000 0.0003800000 0.0018130000 0.0000040000 0.0000030000 0.0017150000 39471893 96830484 509673472 3.8892340660 3.9672913551 4.0041327477 1206 1311867758.8574860096 0.0961236283 0.1334060162 0.2376661599 0.0047624337 0.0103800000 0.0004830000 0.0030530000 0.0000010000 0.0000110000 0.0012200000 39475677 96830484 509673472 3.8859982491 3.9664402008 4.0048317909 1207 1311867758.8875849247 0.0959290788 0.1333749665 0.2376661599 0.0047604928 0.0092940000 0.0003980000 0.0042030000 0.0000050000 0.0000050000 0.0012070000 39479293 96830484 509673472 3.8863024712 3.9663507938 4.0047836304 1208 1311867758.9205179214 0.0956955403 0.1333437749 0.2376661599 0.0047591102 0.0100150000 0.0004670000 0.0026950000 0.0000020000 0.0000100000 0.0012130000 39482853 96830484 509673472 3.8866195679 3.9666728973 4.0047593117 1209 1311867758.9576990604 0.0959854200 0.1333128747 0.2376661599 0.0047601621 0.0104860000 0.0004700000 0.0026930000 0.0000090000 0.0000140000 0.0019330000 39486749 96830484 509673472 3.8864874840 3.9646358490 4.0047717094 1210 1311867758.9880809784 0.0985103846 0.1332841123 0.2376661599 0.0047594994 0.0074080000 0.0003880000 0.0025180000 0.0000010000 0.0000050000 0.0009860000 39490365 96830484 509673472 3.8840363026 3.9647152424 4.0049443245 1211 1311867759.0196750164 0.0968264118 0.1332540069 0.2376661599 0.0047580198 0.0085550000 0.0003750000 0.0041170000 0.0000040000 0.0000030000 0.0012120000 39494037 96830484 509673472 3.8856728077 3.9653167725 4.0044741631 1212 1311867759.0579299927 0.0974061340 0.1332244294 0.2376661599 0.0047572463 0.0083050000 0.0003640000 0.0040830000 0.0000000000 0.0000030000 0.0009690000 39497877 96830484 509673472 3.8850178719 3.9663040638 4.0048208237 1213 1311867759.0873589516 0.0976107642 0.1331950694 0.2376661599 0.0047557065 0.0117880000 0.0004630000 0.0042700000 0.0000090000 0.0000070000 0.0019340000 39501437 96830484 509673472 3.8846995831 3.9671704769 4.0050706863 1214 1311867759.1199090481 0.0981307626 0.1331661862 0.2376661599 0.0047541524 0.0089740000 0.0003890000 0.0041330000 0.0000010000 0.0000040000 0.0009940000 39505109 96830484 509673472 3.8840537071 3.9671745300 4.0051283836 1215 1311867759.1563479900 0.0964204669 0.1331359428 0.2376661599 0.0047543550 0.0085240000 0.0003590000 0.0040950000 0.0000040000 0.0000030000 0.0012050000 39508781 96830484 509673472 3.8857023716 3.9665436745 4.0047121048 1216 1311867759.1888740063 0.0974597484 0.1331066038 0.2376661599 0.0047525206 0.0069330000 0.0003510000 0.0027660000 0.0000000000 0.0000040000 0.0009770000 39512509 96830484 509673472 3.8846437931 3.9660997391 4.0050902367 1217 1311867759.2214748859 0.0972800180 0.1330771653 0.2376661599 0.0047511542 0.0090400000 0.0003540000 0.0040690000 0.0000040000 0.0000030000 0.0017670000 39516125 96830484 509673472 3.8847613335 3.9655392170 4.0050435066 1218 1311867759.2585420609 0.0960329175 0.1330467513 0.2376661599 0.0047500095 0.0078860000 0.0003530000 0.0037420000 0.0000010000 0.0000030000 0.0009770000 39519965 96830484 509673472 3.8859879971 3.9655146599 4.0047073364 1219 1311867759.2957389355 0.0972836092 0.1330174132 0.2376661599 0.0047481087 0.0084180000 0.0003530000 0.0039560000 0.0000030000 0.0000030000 0.0012130000 39523749 96830484 509673472 3.8847663403 3.9648971558 4.0048952103 1220 1311867759.3223690987 0.0991776735 0.1329896758 0.2376661599 0.0047469685 0.0083150000 0.0003530000 0.0040490000 0.0000000000 0.0000060000 0.0009840000 39527253 96830484 509673472 3.8828761578 3.9647445679 4.0051412582 1221 1311867759.3619010448 0.0985848084 0.1329614981 0.2376661599 0.0047452375 0.0089080000 0.0003560000 0.0037300000 0.0000040000 0.0000030000 0.0017800000 39531149 96830484 509673472 3.8838546276 3.9645717144 4.0050148964 1222 1311867759.3886260986 0.0993959829 0.1329340305 0.2376661599 0.0047452971 0.0063780000 0.0003540000 0.0021000000 0.0000000000 0.0000030000 0.0009840000 39534709 96830484 509673472 3.8829820156 3.9630374908 4.0051665306 1223 1311867759.4206190109 0.0995542035 0.1329067371 0.2376661599 0.0047449408 0.0069170000 0.0003490000 0.0024160000 0.0000030000 0.0000030000 0.0012280000 39538381 96830484 509673472 3.8829095364 3.9641981125 4.0052919388 1224 1311867759.4585750103 0.0990221798 0.1328790536 0.2376661599 0.0047431999 0.0082600000 0.0003510000 0.0040330000 0.0000010000 0.0000030000 0.0009960000 39542221 96830484 509673472 3.8835544586 3.9644360542 4.0053224564 1225 1311867759.4905979633 0.1004177630 0.1328525546 0.2376661599 0.0047414743 0.0076000000 0.0003490000 0.0024210000 0.0000040000 0.0000040000 0.0017960000 39545893 96830484 509673472 3.8820426464 3.9651598930 4.0054531097 1226 1311867759.5243968964 0.0990854800 0.1328250121 0.2376661599 0.0047400473 0.0082940000 0.0003460000 0.0040290000 0.0000000000 0.0000040000 0.0009920000 39549621 96830484 509673472 3.8837449551 3.9638121128 4.0054349899 1227 1311867759.5617649555 0.0996571854 0.1327979805 0.2376661599 0.0047382528 0.0069520000 0.0003470000 0.0024130000 0.0000030000 0.0000030000 0.0012450000 39553405 96830484 509673472 3.8832490444 3.9638898373 4.0055303574 1228 1311867759.5870699883 0.0992482156 0.1327706598 0.2376661599 0.0047365253 0.0063420000 0.0003450000 0.0020900000 0.0000010000 0.0000030000 0.0010030000 39556853 96830484 509673472 3.8838074207 3.9633543491 4.0056319237 1229 1311867759.6198399067 0.0999063849 0.1327439191 0.2376661599 0.0047346084 0.0090090000 0.0003460000 0.0039150000 0.0000030000 0.0000030000 0.0018060000 39560525 96830484 509673472 3.8833625317 3.9624414444 4.0058493614 1230 1311867759.6576719284 0.1001760811 0.1327174412 0.2376661599 0.0047328706 0.0082680000 0.0003450000 0.0040130000 0.0000000000 0.0000040000 0.0009940000 39564309 96830484 509673472 3.8834414482 3.9624183178 4.0058393478 1231 1311867759.6904048920 0.1016958877 0.1326922409 0.2376661599 0.0047313788 0.0084590000 0.0003420000 0.0039920000 0.0000040000 0.0000030000 0.0012310000 39568037 96830484 509673472 3.8821480274 3.9623379707 4.0059995651 1232 1311867759.7190918922 0.1007394046 0.1326663052 0.2376661599 0.0047307836 0.0078600000 0.0003430000 0.0036790000 0.0000000000 0.0000040000 0.0009970000 39571597 96830484 509673472 3.8832910061 3.9617526531 4.0055723190 1233 1311867759.7576398849 0.1006781533 0.1326403618 0.2376661599 0.0047293241 0.0104370000 0.0004540000 0.0019430000 0.0000100000 0.0000090000 0.0021930000 39575437 96830484 509673472 3.8835012913 3.9617049694 4.0055537224 1234 1311867759.7871410847 0.1017402485 0.1326153212 0.2376661599 0.0047311714 0.0090000000 0.0003700000 0.0040680000 0.0000010000 0.0000050000 0.0010170000 39579053 96830484 509673472 3.8825476170 3.9617409706 4.0057115555 1235 1311867759.8209869862 0.1023773625 0.1325908371 0.2376661599 0.0047388678 0.0104140000 0.0004410000 0.0029740000 0.0000100000 0.0000090000 0.0013640000 39582725 96830484 509673472 3.8818025589 3.9603056908 4.0055665970 1236 1311867759.8573861122 0.1036662608 0.1325674353 0.2376661599 0.0047462508 0.0089730000 0.0003760000 0.0040510000 0.0000000000 0.0000040000 0.0010240000 39586565 96830484 509673472 3.8808686733 3.9613096714 4.0055079460 1237 1311867759.8883268833 0.1020090282 0.1325427317 0.2376661599 0.0047513336 0.0081170000 0.0003450000 0.0030170000 0.0000040000 0.0000040000 0.0018300000 39590181 96830484 509673472 3.8825004101 3.9610795975 4.0050511360 1238 1311867759.9261589050 0.1008715779 0.1325171491 0.2376661599 0.0047527157 0.0081770000 0.0003470000 0.0038670000 0.0000010000 0.0000040000 0.0010180000 39594021 96830484 509673472 3.8836238384 3.9603202343 4.0043802261 1239 1311867759.9576280117 0.1030083671 0.1324933325 0.2376661599 0.0047534159 0.0111810000 0.0004430000 0.0042070000 0.0000080000 0.0000070000 0.0013830000 39597693 96830484 509673472 3.8815639019 3.9601738453 4.0045962334 1240 1311867759.9870700836 0.1038243324 0.1324702124 0.2376661599 0.0047530862 0.0085930000 0.0003680000 0.0038890000 0.0000000000 0.0000040000 0.0010480000 39601253 96830484 509673472 3.8807108402 3.9616463184 4.0043687820 1241 1311867760.0261199474 0.1048594043 0.1324479635 0.2376661599 0.0047538678 0.0090940000 0.0003400000 0.0039570000 0.0000040000 0.0000030000 0.0018570000 39605093 96830484 509673472 3.8794879913 3.9592900276 4.0037579536 1242 1311867760.0566520691 0.1041828245 0.1324252058 0.2376661599 0.0047533904 0.0081690000 0.0003410000 0.0039390000 0.0000000000 0.0000030000 0.0010250000 39608765 96830484 509673472 3.8801548481 3.9601650238 4.0037565231 1243 1311867760.0870590210 0.1046640426 0.1324028718 0.2376661599 0.0047516905 0.0098140000 0.0004310000 0.0019170000 0.0000100000 0.0000100000 0.0015250000 39612381 96830484 509673472 3.8795492649 3.9614810944 4.0038208961 1244 1311867760.1246991158 0.1043732092 0.1323803399 0.2376661599 0.0047513697 0.0090350000 0.0003690000 0.0040150000 0.0000010000 0.0000050000 0.0010410000 39616221 96830484 509673472 3.8795902729 3.9601769447 4.0034732819 1245 1311867760.1576859951 0.1051093936 0.1323584355 0.2376661599 0.0047510459 0.0105870000 0.0004300000 0.0022330000 0.0000100000 0.0000100000 0.0021840000 39619893 96830484 509673472 3.8789384365 3.9597458839 4.0035305023 1246 1311867760.1870229244 0.1049297899 0.1323364221 0.2376661599 0.0047496018 0.0071730000 0.0003640000 0.0020820000 0.0000010000 0.0000060000 0.0010650000 39623509 96830484 509673472 3.8789808750 3.9615302086 4.0033478737 1247 1311867760.2261290550 0.1050734743 0.1323145593 0.2376661599 0.0047496409 0.0072500000 0.0003370000 0.0026620000 0.0000040000 0.0000040000 0.0012640000 39627349 96830484 509673472 3.8786294460 3.9604771137 4.0031523705 1248 1311867760.2573459148 0.1053445786 0.1322929488 0.2376661599 0.0047478221 0.0082000000 0.0003320000 0.0039250000 0.0000010000 0.0000030000 0.0010340000 39631021 96830484 509673472 3.8782300949 3.9590070248 4.0026192665 1249 1311867760.2895119190 0.1055162027 0.1322715102 0.2376661599 0.0047467510 0.0100730000 0.0003330000 0.0038960000 0.0000030000 0.0000030000 0.0023770000 39634749 96830484 509673472 3.8780019283 3.9611184597 4.0025248528 1250 1311867760.3248739243 0.1049842760 0.1322496804 0.2376661599 0.0047451706 0.0070500000 0.0003390000 0.0027600000 0.0000000000 0.0000040000 0.0010340000 39638533 96830484 509673472 3.8785228729 3.9605777264 4.0023636818 1251 1311867760.3574841022 0.1061265171 0.1322287986 0.2376661599 0.0047549325 0.0084590000 0.0003300000 0.0038940000 0.0000030000 0.0000030000 0.0012660000 39642149 96830484 509673472 3.8772871494 3.9584398270 4.0020728111 1252 1311867760.3897368908 0.1061643288 0.1322079803 0.2376661599 0.0047534202 0.0114070000 0.0004290000 0.0041800000 0.0000010000 0.0000080000 0.0011800000 39645877 96830484 509673472 3.8770809174 3.9597609043 4.0013732910 1253 1311867760.4247770309 0.1056211293 0.1321867618 0.2376661599 0.0047545063 0.0116650000 0.0004280000 0.0041280000 0.0000080000 0.0000070000 0.0020780000 39649605 96830484 509673472 3.8773937225 3.9604179859 4.0010271072 1254 1311867760.4572839737 0.1071590930 0.1321668035 0.2376661599 0.0047529885 0.0086700000 0.0003470000 0.0039150000 0.0000000000 0.0000040000 0.0010610000 39653221 96830484 509673472 3.8761661053 3.9592716694 4.0007100105 1255 1311867760.4886090755 0.1081542373 0.1321476700 0.2376661599 0.0047515040 0.0069000000 0.0003330000 0.0023180000 0.0000040000 0.0000040000 0.0012840000 39656949 96830484 509673472 3.8752343655 3.9601817131 4.0006303787 1256 1311867760.5243430138 0.1076148450 0.1321281375 0.2376661599 0.0047498609 0.0081060000 0.0003260000 0.0038250000 0.0000010000 0.0000040000 0.0010540000 39660733 96830484 509673472 3.8760893345 3.9604997635 4.0004262924 1257 1311867760.5571060181 0.1074224785 0.1321084830 0.2376661599 0.0047482570 0.0089590000 0.0003250000 0.0037510000 0.0000030000 0.0000030000 0.0019120000 39664405 96830484 509673472 3.8764379025 3.9593217373 3.9999434948 1258 1311867760.5894339085 0.1073172167 0.1320887761 0.2376661599 0.0047465001 0.0081130000 0.0003230000 0.0038110000 0.0000010000 0.0000030000 0.0010510000 39668133 96830484 509673472 3.8766791821 3.9589436054 3.9997076988 1259 1311867760.6240029335 0.1078532264 0.1320695263 0.2376661599 0.0047449441 0.0082870000 0.0003200000 0.0037170000 0.0000040000 0.0000040000 0.0012840000 39671861 96830484 509673472 3.8763523102 3.9595038891 3.9993493557 1260 1311867760.6560370922 0.1063682958 0.1320491285 0.2376661599 0.0047438008 0.0081760000 0.0003200000 0.0038250000 0.0000000000 0.0000030000 0.0010510000 39675533 96830484 509673472 3.8780708313 3.9585642815 3.9987225533 1261 1311867760.6867549419 0.1095906943 0.1320313185 0.2376661599 0.0047426293 0.0115830000 0.0004140000 0.0040620000 0.0000080000 0.0000080000 0.0021010000 39679149 96830484 509673472 3.8747143745 3.9571821690 3.9988422394 1262 1311867760.7232599258 0.1088020280 0.1320129117 0.2376661599 0.0047414950 0.0110910000 0.0004130000 0.0041040000 0.0000010000 0.0000080000 0.0011850000 39682933 96830484 509673472 3.8756704330 3.9586963654 3.9985642433 1263 1311867760.7558701038 0.1094090864 0.1319950148 0.2376661599 0.0047397856 0.0090620000 0.0003450000 0.0038770000 0.0000040000 0.0000040000 0.0013100000 39686661 96830484 509673472 3.8751192093 3.9591660500 3.9983687401 1264 1311867760.7868170738 0.1095236242 0.1319772368 0.2376661599 0.0047388331 0.0062330000 0.0003230000 0.0018760000 0.0000010000 0.0000040000 0.0010630000 39690277 96830484 509673472 3.8750395775 3.9571554661 3.9977941513 1265 1311867760.8233850002 0.1057776213 0.1319565257 0.2376661599 0.0047373699 0.0091120000 0.0003200000 0.0037990000 0.0000040000 0.0000030000 0.0019360000 39694061 96830484 509673472 3.8790764809 3.9588034153 3.9973433018 1266 1311867760.8547210693 0.1068932414 0.1319367284 0.2376661599 0.0047358574 0.0081550000 0.0003170000 0.0038050000 0.0000010000 0.0000030000 0.0010650000 39697733 96830484 509673472 3.8781561852 3.9591495991 3.9973287582 1267 1311867760.8877849579 0.1089422256 0.1319185796 0.2376661599 0.0047346988 0.0074810000 0.0003140000 0.0028810000 0.0000040000 0.0000030000 0.0013040000 39701405 96830484 509673472 3.8760926723 3.9578449726 3.9974477291 1268 1311867760.9240860939 0.1089379713 0.1319004561 0.2376661599 0.0047384023 0.0080200000 0.0003170000 0.0037090000 0.0000000000 0.0000030000 0.0010720000 39705245 96830484 509673472 3.8761339188 3.9581761360 3.9971008301 1269 1311867760.9559810162 0.1063973606 0.1318803591 0.2376661599 0.0047369540 0.0090230000 0.0003150000 0.0037870000 0.0000030000 0.0000030000 0.0019430000 39708917 96830484 509673472 3.8786976337 3.9593491554 3.9966590405 1270 1311867760.9867389202 0.1080117747 0.1318615650 0.2376661599 0.0047351648 0.0091390000 0.0004380000 0.0021510000 0.0000010000 0.0000080000 0.0011860000 39712477 96830484 509673472 3.8769423962 3.9592392445 3.9966363907 1271 1311867761.0245900154 0.1071578190 0.1318421285 0.2376661599 0.0047340041 0.0076590000 0.0003410000 0.0023330000 0.0000040000 0.0000040000 0.0013200000 39716373 96830484 509673472 3.8777291775 3.9598827362 3.9964385033 1272 1311867761.0566051006 0.1080428958 0.1318234184 0.2376661599 0.0047324925 0.0110920000 0.0004080000 0.0039390000 0.0000010000 0.0000080000 0.0012050000 39720045 96830484 509673472 3.8767688274 3.9601337910 3.9962248802 1273 1311867761.0866270065 0.1048972309 0.1318022667 0.2376661599 0.0047356251 0.0096910000 0.0003380000 0.0038560000 0.0000050000 0.0000040000 0.0019670000 39723605 96830484 509673472 3.8798117638 3.9591298103 3.9955446720 1274 1311867761.1242640018 0.1082738563 0.1317837985 0.2376661599 0.0047397027 0.0104220000 0.0004070000 0.0034160000 0.0000010000 0.0000070000 0.0011980000 39727501 96830484 509673472 3.8762950897 3.9601597786 3.9958288670 1275 1311867761.1547141075 0.1083115414 0.1317653889 0.2376661599 0.0047381226 0.0093360000 0.0004050000 0.0021430000 0.0000090000 0.0000070000 0.0014300000 39731117 96830484 509673472 3.8762784004 3.9603881836 3.9956839085 1276 1311867761.1912519932 0.1056145057 0.1317448945 0.2376661599 0.0047404890 0.0087360000 0.0003360000 0.0038340000 0.0000000000 0.0000040000 0.0010910000 39734845 96830484 509673472 3.8788809776 3.9596357346 3.9952793121 1277 1311867761.2244689465 0.1070164591 0.1317255300 0.2376661599 0.0047389376 0.0122410000 0.0004030000 0.0040250000 0.0000070000 0.0000090000 0.0021380000 39738629 96830484 509673472 3.8772966862 3.9585440159 3.9950368404 1278 1311867761.2564349174 0.1079024076 0.1317068891 0.2376661599 0.0047407444 0.0089380000 0.0003860000 0.0039340000 0.0000000000 0.0000040000 0.0011010000 39742301 96830484 509673472 3.8765063286 3.9611563683 3.9950718880 1279 1311867761.2914810181 0.1085440218 0.1316887789 0.2376661599 0.0047392622 0.0066430000 0.0003120000 0.0019450000 0.0000030000 0.0000030000 0.0013040000 39745973 96830484 509673472 3.8756740093 3.9591529369 3.9947395325 1280 1311867761.3245120049 0.1095321700 0.1316714691 0.2376661599 0.0047378642 0.0078730000 0.0003120000 0.0034570000 0.0000000000 0.0000030000 0.0010850000 39749757 96830484 509673472 3.8746349812 3.9583401680 3.9950375557 1281 1311867761.3563210964 0.1069253832 0.1316521513 0.2376661599 0.0047362488 0.0075610000 0.0003150000 0.0022430000 0.0000040000 0.0000040000 0.0019780000 39753373 96830484 509673472 3.8772590160 3.9606006145 3.9946918488 1282 1311867761.3919639587 0.1070870906 0.1316329898 0.2376661599 0.0047348087 0.0113400000 0.0004350000 0.0040500000 0.0000010000 0.0000110000 0.0012130000 39757157 96830484 509673472 3.8767695427 3.9588499069 3.9941561222 1283 1311867761.4230949879 0.1073795259 0.1316140861 0.2376661599 0.0047335420 0.0095130000 0.0004050000 0.0021440000 0.0000080000 0.0000070000 0.0014220000 39760829 96830484 509673472 3.8762016296 3.9585103989 3.9935421944 1284 1311867761.4547801018 0.1072850451 0.1315951382 0.2376661599 0.0047331175 0.0088430000 0.0003450000 0.0038250000 0.0000010000 0.0000050000 0.0010970000 39764445 96830484 509673472 3.8765020370 3.9613010883 3.9935510159 1285 1311867761.4908668995 0.1074207723 0.1315763255 0.2376661599 0.0047313041 0.0090870000 0.0003100000 0.0037490000 0.0000030000 0.0000030000 0.0019890000 39768285 96830484 509673472 3.8762996197 3.9614424706 3.9930779934 1286 1311867761.5258040428 0.1085141301 0.1315583922 0.2376661599 0.0047296814 0.0100650000 0.0004280000 0.0021500000 0.0000010000 0.0000100000 0.0013360000 39771957 96830484 509673472 3.8750045300 3.9587841034 3.9925866127 1287 1311867761.5562748909 0.1085823327 0.1315405398 0.2376661599 0.0047278534 0.0090510000 0.0003370000 0.0034170000 0.0000050000 0.0000050000 0.0013450000 39775573 96830484 509673472 3.8750755787 3.9588298798 3.9923934937 1288 1311867761.5914149284 0.1067794338 0.1315213153 0.2376661599 0.0047272311 0.0073040000 0.0003040000 0.0028330000 0.0000010000 0.0000030000 0.0010870000 39779301 96830484 509673472 3.8769729137 3.9595971107 3.9915046692 1289 1311867761.6232030392 0.1083243191 0.1315033192 0.2376661599 0.0047263090 0.0117620000 0.0004020000 0.0039940000 0.0000080000 0.0000070000 0.0021650000 39783029 96830484 509673472 3.8754258156 3.9574775696 3.9913339615 1290 1311867761.6567790508 0.1084176004 0.1314854233 0.2376661599 0.0047278400 0.0099840000 0.0003950000 0.0021340000 0.0000010000 0.0000100000 0.0013480000 39786701 96830484 509673472 3.8755745888 3.9588458538 3.9913029671 1291 1311867761.6917459965 0.1087721512 0.1314678298 0.2376661599 0.0047268701 0.0081590000 0.0003110000 0.0025830000 0.0000050000 0.0000050000 0.0013350000 39790429 96830484 509673472 3.8753504753 3.9599003792 3.9909441471 1292 1311867761.7235610485 0.1076050475 0.1314493601 0.2376661599 0.0047259402 0.0083070000 0.0003080000 0.0037480000 0.0000000000 0.0000040000 0.0011130000 39794101 96830484 509673472 3.8765327930 3.9575021267 3.9905939102 1293 1311867761.7545659542 0.1080860272 0.1314312910 0.2376661599 0.0047243033 0.0091530000 0.0003020000 0.0037150000 0.0000040000 0.0000030000 0.0020050000 39797717 96830484 509673472 3.8761534691 3.9572386742 3.9904408455 1294 1311867761.7916970253 0.1110885814 0.1314155702 0.2376661599 0.0047236137 0.0067040000 0.0003000000 0.0022140000 0.0000000000 0.0000030000 0.0011040000 39801501 96830484 509673472 3.8735070229 3.9589359760 3.9908053875 1295 1311867761.8235230446 0.1109210402 0.1313997443 0.2376661599 0.0047218646 0.0083010000 0.0002960000 0.0035990000 0.0000030000 0.0000030000 0.0013370000 39805173 96830484 509673472 3.8737683296 3.9592194557 3.9906558990 1296 1311867761.8546519279 0.1089689359 0.1313824366 0.2376661599 0.0047204701 0.0109030000 0.0003890000 0.0039450000 0.0000010000 0.0000080000 0.0012410000 39808845 96830484 509673472 3.8758215904 3.9591436386 3.9902939796 1297 1311867761.8910980225 0.1114249974 0.1313670492 0.2376661599 0.0047203611 0.0096930000 0.0003260000 0.0037510000 0.0000050000 0.0000040000 0.0020480000 39812629 96830484 509673472 3.8736412525 3.9599361420 3.9908068180 1298 1311867761.9224560261 0.1096535474 0.1313503208 0.2376661599 0.0047210806 0.0063760000 0.0003010000 0.0019080000 0.0000000000 0.0000030000 0.0011020000 39816301 96830484 509673472 3.8755671978 3.9590930939 3.9902868271 1299 1311867761.9546790123 0.1097376049 0.1313336828 0.2376661599 0.0047212180 0.0083710000 0.0002890000 0.0036910000 0.0000040000 0.0000030000 0.0013310000 39820029 96830484 509673472 3.8756043911 3.9567015171 3.9898405075 1300 1311867761.9942779541 0.1128428429 0.1313194591 0.2376661599 0.0047200872 0.0075470000 0.0002950000 0.0031020000 0.0000000000 0.0000040000 0.0011040000 39823925 96830484 509673472 3.8728017807 3.9565231800 3.9898145199 1301 1311867762.0235669613 0.1107678264 0.1313036623 0.2376661599 0.0047194897 0.0072930000 0.0002790000 0.0018910000 0.0000040000 0.0000040000 0.0020440000 39827485 96830484 509673472 3.8751227856 3.9563808441 3.9890642166 1302 1311867762.0558550358 0.1138428971 0.1312902516 0.2376661599 0.0047188372 0.0069160000 0.0002840000 0.0025000000 0.0000000000 0.0000030000 0.0011080000 39831157 96830484 509673472 3.8722774982 3.9561967850 3.9892611504 1303 1311867762.0913889408 0.1130813211 0.1312762770 0.2376661599 0.0047382561 0.0069470000 0.0002800000 0.0021910000 0.0000040000 0.0000030000 0.0013470000 39834885 96830484 509673472 3.8730576038 3.9570198059 3.9891488552 1304 1311867762.1225299835 0.1136573479 0.1312627655 0.2376661599 0.0047368736 0.0073070000 0.0002790000 0.0027670000 0.0000010000 0.0000040000 0.0011140000 39838557 96830484 509673472 3.8728227615 3.9578666687 3.9894759655 1305 1311867762.1545391083 0.1130397692 0.1312488015 0.2376661599 0.0047504726 0.0073060000 0.0002760000 0.0019010000 0.0000030000 0.0000040000 0.0020410000 39842285 96830484 509673472 3.8739123344 3.9569473267 3.9890797138 1306 1311867762.1913030148 0.1146573126 0.1312360975 0.2376661599 0.0047491581 0.0081280000 0.0002760000 0.0036590000 0.0000000000 0.0000040000 0.0011170000 39846013 96830484 509673472 3.8726949692 3.9553647041 3.9894914627 1307 1311867762.2234869003 0.1162542477 0.1312246347 0.2376661599 0.0047476424 0.0105770000 0.0003750000 0.0027120000 0.0000100000 0.0000100000 0.0014950000 39849741 96830484 509673472 3.8714525700 3.9559850693 3.9896848202 1308 1311867762.2565600872 0.1164469793 0.1312133368 0.2376661599 0.0047458336 0.0088680000 0.0003000000 0.0037070000 0.0000000000 0.0000040000 0.0011320000 39853469 96830484 509673472 3.8715384007 3.9558074474 3.9895930290 1309 1311867762.2907900810 0.1177878380 0.1312030805 0.2376661599 0.0047442066 0.0121130000 0.0003980000 0.0039100000 0.0000080000 0.0000070000 0.0022430000 39857141 96830484 509673472 3.8703725338 3.9549970627 3.9898304939 1310 1311867762.3235380650 0.1157622710 0.1311912936 0.2376661599 0.0047720284 0.0084220000 0.0003020000 0.0033880000 0.0000000000 0.0000050000 0.0011380000 39860869 96830484 509673472 3.8724400997 3.9547770023 3.9893283844 1311 1311867762.3545570374 0.1162508205 0.1311798974 0.2376661599 0.0047707311 0.0092990000 0.0003960000 0.0017590000 0.0000070000 0.0000080000 0.0014730000 39864541 96830484 509673472 3.8722259998 3.9552016258 3.9893546104 1312 1311867762.3949799538 0.1158551946 0.1311682170 0.2376661599 0.0047833249 0.0071730000 0.0003000000 0.0019230000 0.0000010000 0.0000050000 0.0011390000 39868437 96830484 509673472 3.8727855682 3.9548869133 3.9889974594 1313 1311867762.4242470264 0.1170929298 0.1311574970 0.2376661599 0.0047815237 0.0089400000 0.0002750000 0.0035290000 0.0000040000 0.0000040000 0.0020590000 39872053 96830484 509673472 3.8716111183 3.9537122250 3.9889440536 1314 1311867762.4588010311 0.1169693023 0.1311466993 0.2376661599 0.0047804797 0.0064430000 0.0002740000 0.0018630000 0.0000010000 0.0000040000 0.0011270000 39875725 96830484 509673472 3.8720343113 3.9549536705 3.9891090393 1315 1311867762.4918160439 0.1183487400 0.1311369670 0.2376661599 0.0047791450 0.0077550000 0.0002730000 0.0030250000 0.0000030000 0.0000030000 0.0013570000 39879397 96830484 509673472 3.8704068661 3.9536149502 3.9888029099 1316 1311867762.5242910385 0.1189636439 0.1311277168 0.2376661599 0.0047782033 0.0063640000 0.0002710000 0.0018620000 0.0000010000 0.0000040000 0.0011240000 39883125 96830484 509673472 3.8698740005 3.9537398815 3.9891908169 1317 1311867762.5594940186 0.1165982857 0.1311166846 0.2376661599 0.0047768092 0.0121420000 0.0003660000 0.0038950000 0.0000070000 0.0000070000 0.0022390000 39886909 96830484 509673472 3.8721394539 3.9550123215 3.9888961315 1318 1311867762.5913679600 0.1180572361 0.1311067760 0.2376661599 0.0047751526 0.0073320000 0.0003020000 0.0021070000 0.0000010000 0.0000050000 0.0011390000 39890525 96830484 509673472 3.8704588413 3.9549727440 3.9892108440 1319 1311867762.6233699322 0.1178779751 0.1310967466 0.2376661599 0.0047734945 0.0083750000 0.0002710000 0.0035980000 0.0000040000 0.0000040000 0.0013570000 39894197 96830484 509673472 3.8706521988 3.9538400173 3.9894161224 1320 1311867762.6626110077 0.1200469509 0.1310883756 0.2376661599 0.0047719320 0.0070050000 0.0002680000 0.0024340000 0.0000010000 0.0000040000 0.0011250000 39898093 96830484 509673472 3.8682549000 3.9536275864 3.9894988537 1321 1311867762.6927230358 0.1192567199 0.1310794190 0.2376661599 0.0047701644 0.0076540000 0.0002680000 0.0021450000 0.0000030000 0.0000030000 0.0020610000 39901597 96830484 509673472 3.8690147400 3.9547903538 3.9893922806 1322 1311867762.7241640091 0.1179143786 0.1310694605 0.2376661599 0.0047708528 0.0069370000 0.0002710000 0.0024270000 0.0000010000 0.0000040000 0.0011130000 39905269 96830484 509673472 3.8701908588 3.9528255463 3.9888906479 1323 1311867762.7605299950 0.1204465032 0.1310614311 0.2376661599 0.0047703739 0.0083480000 0.0002690000 0.0035950000 0.0000030000 0.0000030000 0.0013550000 39908997 96830484 509673472 3.8672297001 3.9518613815 3.9888937473 1324 1311867762.7905199528 0.1260578781 0.1310576520 0.2376661599 0.0047739316 0.0080810000 0.0002650000 0.0035740000 0.0000000000 0.0000030000 0.0011180000 39912613 96830484 509673472 3.8616263866 3.9528195858 3.9897701740 1325 1311867762.8258841038 0.1221510768 0.1310509300 0.2376661599 0.0047726975 0.0117430000 0.0003580000 0.0038220000 0.0000070000 0.0000070000 0.0022290000 39916397 96830484 509673472 3.8656377792 3.9538002014 3.9895901680 1326 1311867762.8593358994 0.1238104105 0.1310454696 0.2376661599 0.0047720180 0.0086730000 0.0002900000 0.0036280000 0.0000010000 0.0000050000 0.0011270000 39920125 96830484 509673472 3.8640434742 3.9524350166 3.9901540279 1327 1311867762.8911890984 0.1251384318 0.1310410182 0.2376661599 0.0047708298 0.0072330000 0.0002690000 0.0024130000 0.0000040000 0.0000030000 0.0013560000 39923741 96830484 509673472 3.8627061844 3.9527990818 3.9903798103 1328 1311867762.9231870174 0.1213582754 0.1310337270 0.2376661599 0.0047696561 0.0066400000 0.0002610000 0.0021170000 0.0000000000 0.0000030000 0.0011220000 39927469 96830484 509673472 3.8665864468 3.9546098709 3.9904758930 1329 1311867762.9586219788 0.1221454442 0.1310270390 0.2376661599 0.0047681431 0.0090270000 0.0002620000 0.0035460000 0.0000040000 0.0000030000 0.0020670000 39931253 96830484 509673472 3.8655498028 3.9532546997 3.9902560711 1330 1311867762.9910819530 0.1239759624 0.1310217375 0.2376661599 0.0047664522 0.0080740000 0.0002620000 0.0035320000 0.0000010000 0.0000040000 0.0011270000 39934925 96830484 509673472 3.8636200428 3.9525990486 3.9904699326 1331 1311867763.0241999626 0.1250917912 0.1310172822 0.2376661599 0.0047652458 0.0116010000 0.0003600000 0.0038660000 0.0000070000 0.0000080000 0.0014960000 39938653 96830484 509673472 3.8627550602 3.9536082745 3.9907965660 1332 1311867763.0586409569 0.1249730140 0.1310127445 0.2376661599 0.0047651518 0.0073260000 0.0002970000 0.0018780000 0.0000010000 0.0000050000 0.0011530000 39942325 96830484 509673472 3.8630194664 3.9538989067 3.9907717705 1333 1311867763.0910348892 0.1283528507 0.1310107490 0.2376661599 0.0047636142 0.0090530000 0.0002630000 0.0035280000 0.0000030000 0.0000030000 0.0020670000 39946053 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1334 1311867763.1222279072 0.1286155879 0.1310089536 0.2376661599 0.0047626095 0.0080670000 0.0002560000 0.0035140000 0.0000000000 0.0000030000 0.0011280000 39949669 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1335 1311867763.1606709957 0.1287866533 0.1310072889 0.2376661599 0.0047610743 0.0080410000 0.0002570000 0.0035130000 0.0000010000 0.0000040000 0.0011330000 39953509 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1336 1311867763.1913530827 0.1290132999 0.1310057964 0.2376661599 0.0047634682 0.0086440000 0.0003080000 0.0035080000 0.0000000000 0.0000030000 0.0011200000 39957181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1337 1311867763.2239060402 0.1292598695 0.1310044906 0.2376661599 0.0047618255 0.0089230000 0.0002910000 0.0035000000 0.0000000000 0.0000040000 0.0018470000 39960853 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1338 1311867763.2619409561 0.1295824498 0.1310034277 0.2376661599 0.0047600816 0.0080880000 0.0002560000 0.0034990000 0.0000010000 0.0000040000 0.0011210000 39964581 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1339 1311867763.2997210026 0.1298645437 0.1310025772 0.2376661599 0.0047614167 0.0080840000 0.0002560000 0.0035020000 0.0000000000 0.0000030000 0.0011150000 39968477 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1340 1311867763.3283360004 0.1302091926 0.1310019851 0.2376661599 0.0047598871 0.0080450000 0.0002540000 0.0035140000 0.0000010000 0.0000030000 0.0011120000 39972037 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1341 1311867763.3595879078 0.1304924488 0.1310016052 0.2376661599 0.0047584892 0.0087790000 0.0002560000 0.0034910000 0.0000010000 0.0000030000 0.0018320000 39975597 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1342 1311867763.3930239677 0.1307789087 0.1310014392 0.2376661599 0.0047574070 0.0080140000 0.0002550000 0.0034890000 0.0000010000 0.0000040000 0.0011200000 39979325 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1343 1311867763.4231410027 0.1311795413 0.1310015718 0.2376661599 0.0047557076 0.0081460000 0.0002560000 0.0034940000 0.0000000000 0.0000030000 0.0011180000 39982941 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1344 1311867763.4599080086 0.1315629780 0.1310019895 0.2376661599 0.0047542419 0.0075570000 0.0002650000 0.0029440000 0.0000010000 0.0000030000 0.0011290000 39986781 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1345 1311867763.4920830727 0.1320014298 0.1310027326 0.2376661599 0.0047546703 0.0085100000 0.0002570000 0.0032200000 0.0000000000 0.0000040000 0.0018370000 39990397 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1346 1311867763.5240089893 0.1323083490 0.1310037026 0.2376661599 0.0047529543 0.0077670000 0.0002560000 0.0032140000 0.0000000000 0.0000030000 0.0011200000 39994125 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1347 1311867763.5586268902 0.1325412691 0.1310048441 0.2376661599 0.0047513524 0.0075010000 0.0002550000 0.0029370000 0.0000000000 0.0000030000 0.0011230000 39997797 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1348 1311867763.5911428928 0.1327084154 0.1310061079 0.2376661599 0.0047535757 0.0087140000 0.0002550000 0.0035150000 0.0000000000 0.0000040000 0.0011270000 40001525 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1349 1311867763.6315419674 0.1328033954 0.1310074402 0.2376661599 0.0047518374 0.0082880000 0.0002640000 0.0026660000 0.0000000000 0.0000040000 0.0018500000 40005365 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1350 1311867763.6613171101 0.1328984052 0.1310088409 0.2376661599 0.0047504111 0.0076930000 0.0002600000 0.0029310000 0.0000010000 0.0000040000 0.0011280000 40008869 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1351 1311867763.6906011105 0.1329536289 0.1310102804 0.2376661599 0.0047498697 0.0081730000 0.0002590000 0.0034920000 0.0000000000 0.0000030000 0.0011310000 40012541 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1352 1311867763.7281720638 0.1331056356 0.1310118302 0.2376661599 0.0047482039 0.0079130000 0.0002500000 0.0032100000 0.0000000000 0.0000040000 0.0011200000 40016381 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1353 1311867763.7617700100 0.1332385838 0.1310134760 0.2376661599 0.0047464717 0.0121980000 0.0003490000 0.0037830000 0.0000010000 0.0000100000 0.0020040000 40020053 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1354 1311867763.7929420471 0.1333521158 0.1310152032 0.2376661599 0.0047452003 0.0088600000 0.0002880000 0.0035660000 0.0000010000 0.0000050000 0.0011340000 40023725 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1355 1311867763.8308730125 0.1334669441 0.1310170126 0.2376661599 0.0047437875 0.0082530000 0.0002540000 0.0034930000 0.0000010000 0.0000040000 0.0011200000 40027565 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1356 1311867763.8622579575 0.1335253417 0.1310188624 0.2376661599 0.0047423289 0.0081260000 0.0002490000 0.0034630000 0.0000010000 0.0000040000 0.0011190000 40031181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1357 1311867763.8950018883 0.1336219609 0.1310207807 0.2376661599 0.0047411036 0.0089150000 0.0002560000 0.0034850000 0.0000000000 0.0000050000 0.0018400000 40034909 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1358 1311867763.9286549091 0.1337995231 0.1310228269 0.2376661599 0.0047426191 0.0081210000 0.0002520000 0.0034610000 0.0000000000 0.0000030000 0.0011190000 40038581 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1359 1311867763.9622230530 0.1339750737 0.1310249993 0.2376661599 0.0047408831 0.0114400000 0.0003400000 0.0037560000 0.0000010000 0.0000100000 0.0012190000 40042309 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1360 1311867763.9930698872 0.1339592338 0.1310271568 0.2376661599 0.0047393977 0.0089440000 0.0002880000 0.0035310000 0.0000010000 0.0000040000 0.0011280000 40045925 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1361 1311867764.0303530693 0.1340804696 0.1310294002 0.2376661599 0.0047423831 0.0093230000 0.0002520000 0.0036120000 0.0000010000 0.0000040000 0.0019840000 40049765 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1362 1311867764.0625600815 0.1343336254 0.1310318262 0.2376661599 0.0047413026 0.0085700000 0.0002620000 0.0036230000 0.0000010000 0.0000040000 0.0011930000 40053381 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1363 1311867764.0939369202 0.1344701946 0.1310343489 0.2376661599 0.0047400003 0.0075700000 0.0002590000 0.0027490000 0.0000000000 0.0000040000 0.0011920000 40057053 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1364 1311867764.1303229332 0.1345923394 0.1310369574 0.2376661599 0.0047409720 0.0084170000 0.0002570000 0.0036190000 0.0000010000 0.0000040000 0.0011970000 40060837 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1365 1311867764.1600530148 0.1347091645 0.1310396476 0.2376661599 0.0047397440 0.0104110000 0.0002840000 0.0041790000 0.0000010000 0.0000040000 0.0020080000 40064453 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1366 1311867764.1931879520 0.1347718388 0.1310423799 0.2376661599 0.0047381765 0.0086260000 0.0003120000 0.0036200000 0.0000010000 0.0000040000 0.0011950000 40068181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1367 1311867764.2289299965 0.1349379271 0.1310452296 0.2376661599 0.0047410519 0.0084800000 0.0002520000 0.0036370000 0.0000000000 0.0000040000 0.0011990000 40071909 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1368 1311867764.2623479366 0.1349062473 0.1310480519 0.2376661599 0.0047399197 0.0084680000 0.0002580000 0.0036080000 0.0000000000 0.0000030000 0.0012000000 40075637 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1369 1311867764.2925939560 0.1348650008 0.1310508401 0.2376661599 0.0047382292 0.0124150000 0.0003580000 0.0039010000 0.0000010000 0.0000080000 0.0021630000 40079253 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1370 1311867764.3292350769 0.1347720325 0.1310535563 0.2376661599 0.0047495237 0.0090120000 0.0002900000 0.0036640000 0.0000010000 0.0000050000 0.0012170000 40083093 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1371 1311867764.3632280827 0.1346692890 0.1310561936 0.2376661599 0.0047482139 0.0084370000 0.0002710000 0.0035980000 0.0000010000 0.0000040000 0.0011920000 40086821 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1372 1311867764.3937499523 0.1344782859 0.1310586878 0.2376661599 0.0047468474 0.0079250000 0.0002570000 0.0030210000 0.0000010000 0.0000040000 0.0012040000 40090437 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1373 1311867764.4299139977 0.1342251748 0.1310609941 0.2376661599 0.0047544059 0.0125350000 0.0003520000 0.0038930000 0.0000010000 0.0000100000 0.0021520000 40094221 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1374 1311867764.4600350857 0.1340083927 0.1310631392 0.2376661599 0.0047530349 0.0090870000 0.0002780000 0.0036550000 0.0000000000 0.0000040000 0.0012060000 40097781 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1375 1311867764.4931490421 0.1336051077 0.1310649879 0.2376661599 0.0047521272 0.0083860000 0.0002610000 0.0035950000 0.0000000000 0.0000030000 0.0011960000 40101453 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1376 1311867764.5289220810 0.1332904398 0.1310666052 0.2376661599 0.0047539947 0.0084180000 0.0002630000 0.0035930000 0.0000000000 0.0000040000 0.0011980000 40105237 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1377 1311867764.5604650974 0.1331014931 0.1310680830 0.2376661599 0.0047526193 0.0092000000 0.0002620000 0.0035670000 0.0000000000 0.0000040000 0.0019880000 40108853 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1378 1311867764.5906419754 0.1327724904 0.1310693199 0.2376661599 0.0047516290 0.0154380000 0.0004380000 0.0041210000 0.0000020000 0.0000160000 0.0016630000 40112469 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1379 1311867764.6277070045 0.1329086274 0.1310706537 0.2376661599 0.0047664562 0.0095910000 0.0003010000 0.0036930000 0.0000010000 0.0000050000 0.0012160000 40116253 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1380 1311867764.6609039307 0.1328684390 0.1310719564 0.2376661599 0.0047685558 0.0085280000 0.0002920000 0.0035860000 0.0000010000 0.0000040000 0.0011910000 40120037 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1381 1311867764.6907351017 0.1327548027 0.1310731750 0.2376661599 0.0047672804 0.0091980000 0.0002570000 0.0035840000 0.0000010000 0.0000040000 0.0019770000 40123597 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1382 1311867764.7274560928 0.1323656291 0.1310741102 0.2376661599 0.0047663368 0.0084100000 0.0002600000 0.0035930000 0.0000000000 0.0000040000 0.0011950000 40127381 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1383 1311867764.7591719627 0.1322821826 0.1310749837 0.2376661599 0.0047697370 0.0112070000 0.0003540000 0.0038270000 0.0000010000 0.0000080000 0.0012960000 40131109 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1384 1311867764.7921779156 0.1322403550 0.1310758257 0.2376661599 0.0047695158 0.0089060000 0.0002910000 0.0036200000 0.0000010000 0.0000050000 0.0012110000 40134725 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1385 1311867764.8278260231 0.1320167631 0.1310765051 0.2376661599 0.0047700268 0.0092240000 0.0002590000 0.0035850000 0.0000010000 0.0000040000 0.0019830000 40138509 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1386 1311867764.8610520363 0.1318379194 0.1310770545 0.2376661599 0.0047725965 0.0083880000 0.0002540000 0.0035670000 0.0000000000 0.0000030000 0.0011890000 40142181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1387 1311867764.8946199417 0.1315357983 0.1310773852 0.2376661599 0.0047740709 0.0084150000 0.0002570000 0.0035590000 0.0000010000 0.0000040000 0.0011860000 40145965 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1388 1311867764.9271790981 0.1312161386 0.1310774852 0.2376661599 0.0047752489 0.0084310000 0.0002540000 0.0035730000 0.0000010000 0.0000040000 0.0011880000 40149637 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1389 1311867764.9599800110 0.1308457851 0.1310773184 0.2376661599 0.0047735530 0.0092040000 0.0002530000 0.0035690000 0.0000000000 0.0000030000 0.0019770000 40153365 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1390 1311867764.9950439930 0.1304454058 0.1310768637 0.2376661599 0.0047772749 0.0084090000 0.0002560000 0.0035760000 0.0000000000 0.0000030000 0.0011910000 40157093 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1391 1311867765.0330669880 0.1299583614 0.1310760596 0.2376661599 0.0047765675 0.0085130000 0.0002540000 0.0035660000 0.0000000000 0.0000030000 0.0011880000 40160821 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1392 1311867765.0598719120 0.1297277510 0.1310750910 0.2376661599 0.0047755680 0.0112280000 0.0003510000 0.0038090000 0.0000010000 0.0000090000 0.0012930000 40164381 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1393 1311867765.0951199532 0.1296294928 0.1310740533 0.2376661599 0.0047749201 0.0097520000 0.0002710000 0.0036310000 0.0000010000 0.0000050000 0.0019980000 40168165 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1394 1311867765.1273620129 0.1292837411 0.1310727690 0.2376661599 0.0047740676 0.0084450000 0.0002740000 0.0035720000 0.0000010000 0.0000030000 0.0011930000 40171781 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1395 1311867765.1595649719 0.1290592551 0.1310713256 0.2376661599 0.0047724356 0.0085790000 0.0002590000 0.0035930000 0.0000000000 0.0000030000 0.0011910000 40175397 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1396 1311867765.1969060898 0.1289521009 0.1310698075 0.2376661599 0.0047707307 0.0078950000 0.0002570000 0.0029900000 0.0000010000 0.0000040000 0.0012000000 40179125 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1397 1311867765.2290871143 0.1288974285 0.1310682525 0.2376661599 0.0047718391 0.0093190000 0.0002540000 0.0035860000 0.0000010000 0.0000040000 0.0019930000 40182797 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1398 1311867765.2611060143 0.1287677884 0.1310666070 0.2376661599 0.0047702494 0.0193520000 0.0004550000 0.0041010000 0.0000020000 0.0000180000 0.0016520000 40186469 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1399 1311867765.2958459854 0.1288009584 0.1310649875 0.2376661599 0.0047685600 0.0146690000 0.0004830000 0.0040930000 0.0000020000 0.0000150000 0.0016460000 40190141 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1400 1311867765.3289039135 0.1288665831 0.1310634172 0.2376661599 0.0047675662 0.0112370000 0.0003500000 0.0038300000 0.0000010000 0.0000080000 0.0012900000 40193925 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1401 1311867765.3593490124 0.1288915426 0.1310618670 0.2376661599 0.0047658867 0.0097760000 0.0002770000 0.0036270000 0.0000010000 0.0000050000 0.0020050000 40197541 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1402 1311867765.3951449394 0.1288474202 0.1310602875 0.2376661599 0.0047642780 0.0076020000 0.0002610000 0.0027220000 0.0000000000 0.0000040000 0.0011830000 40201325 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1403 1311867765.4278709888 0.1289493442 0.1310587829 0.2376661599 0.0047668166 0.0143540000 0.0003700000 0.0038990000 0.0000020000 0.0000110000 0.0014260000 40204941 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1404 1311867765.4589679241 0.1288998127 0.1310572451 0.2376661599 0.0047657630 0.0092520000 0.0002920000 0.0030900000 0.0000000000 0.0000060000 0.0012160000 40208613 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1405 1311867765.4974000454 0.1286740452 0.1310555489 0.2376661599 0.0047655451 0.0094150000 0.0002660000 0.0036130000 0.0000000000 0.0000040000 0.0019890000 40212453 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1406 1311867765.5298929214 0.1285113096 0.1310537394 0.2376661599 0.0047643764 0.0114860000 0.0003490000 0.0038380000 0.0000010000 0.0000090000 0.0013110000 40216181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1407 1311867765.5625720024 0.1283316463 0.1310518047 0.2376661599 0.0047651029 0.0090430000 0.0002670000 0.0036410000 0.0000000000 0.0000040000 0.0012090000 40219853 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1408 1311867765.5947990417 0.1280480623 0.1310496713 0.2376661599 0.0047634233 0.0083690000 0.0002520000 0.0035780000 0.0000010000 0.0000030000 0.0011890000 40223525 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1409 1311867765.6310911179 0.1279125959 0.1310474449 0.2376661599 0.0047618163 0.0092090000 0.0002490000 0.0035980000 0.0000000000 0.0000030000 0.0020000000 40227253 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1410 1311867765.6618249416 0.1278614253 0.1310451853 0.2376661599 0.0047611784 0.0115970000 0.0003470000 0.0038540000 0.0000010000 0.0000070000 0.0013080000 40230925 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1411 1311867765.6966838837 0.1278065592 0.1310428900 0.2376661599 0.0047595567 0.0090920000 0.0002820000 0.0036610000 0.0000010000 0.0000050000 0.0012070000 40234653 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1412 1311867765.7292089462 0.1275731325 0.1310404327 0.2376661599 0.0047578990 0.0084020000 0.0002480000 0.0035910000 0.0000000000 0.0000030000 0.0011880000 40238437 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1413 1311867765.7602009773 0.1274551749 0.1310378954 0.2376661599 0.0047567246 0.0095340000 0.0003050000 0.0033160000 0.0000000000 0.0000040000 0.0019830000 40242053 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1414 1311867765.7960450649 0.1272230893 0.1310351975 0.2376661599 0.0047552453 0.0085150000 0.0002910000 0.0035860000 0.0000000000 0.0000040000 0.0011870000 40245837 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1415 1311867765.8298408985 0.1272560954 0.1310325267 0.2376661599 0.0047537407 0.0076000000 0.0002470000 0.0027230000 0.0000010000 0.0000040000 0.0011950000 40249509 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1416 1311867765.8610999584 0.1273013800 0.1310298917 0.2376661599 0.0047524607 0.0083930000 0.0002540000 0.0036050000 0.0000010000 0.0000040000 0.0011890000 40253181 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1417 1311867765.8960449696 0.1270879805 0.1310271099 0.2376661599 0.0047524662 0.0093020000 0.0002570000 0.0036200000 0.0000010000 0.0000040000 0.0019900000 40256909 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1418 1311867765.9303019047 0.1270455122 0.1310243020 0.2376661599 0.0047518471 0.0084170000 0.0002570000 0.0035990000 0.0000000000 0.0000040000 0.0011910000 40260693 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1419 1311867765.9612519741 0.1270761490 0.1310215196 0.2376661599 0.0047509918 0.0084060000 0.0002480000 0.0036130000 0.0000010000 0.0000040000 0.0011840000 40264253 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1420 1311867765.9962689877 0.1271727830 0.1310188092 0.2376661599 0.0047499384 0.0084060000 0.0002510000 0.0036100000 0.0000000000 0.0000040000 0.0011860000 40267981 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1421 1311867766.0289440155 0.1272700578 0.1310161711 0.2376661599 0.0047483521 0.0092790000 0.0002580000 0.0036140000 0.0000000000 0.0000040000 0.0019820000 40271765 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1422 1311867766.0606811047 0.1273137927 0.1310135675 0.2376661599 0.0047474375 0.0085430000 0.0002570000 0.0036370000 0.0000000000 0.0000040000 0.0011880000 40275437 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1423 1311867766.0968139172 0.1274678558 0.1310110758 0.2376661599 0.0047467659 0.0084570000 0.0002580000 0.0036240000 0.0000000000 0.0000030000 0.0011910000 40279221 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1424 1311867766.1277561188 0.1274715662 0.1310085902 0.2376661599 0.0047465345 0.0084290000 0.0002570000 0.0036330000 0.0000000000 0.0000030000 0.0011830000 40282781 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1425 1311867766.1625239849 0.1273433566 0.1310060181 0.2376661599 0.0047489611 0.0092140000 0.0002590000 0.0036220000 0.0000000000 0.0000040000 0.0019720000 40286565 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1426 1311867766.1968889236 0.1271617413 0.1310033222 0.2376661599 0.0047511556 0.0086140000 0.0002650000 0.0036380000 0.0000010000 0.0000040000 0.0011920000 40290293 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1427 1311867766.2298009396 0.1268946230 0.1310004430 0.2376661599 0.0047537949 0.0086910000 0.0002660000 0.0036380000 0.0000000000 0.0000040000 0.0011920000 40294021 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1428 1311867766.2654640675 0.1264638901 0.1309972661 0.2376661599 0.0047568636 0.0119630000 0.0003600000 0.0039400000 0.0000010000 0.0000070000 0.0013170000 40297749 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1429 1311867766.2981679440 0.1262692660 0.1309939575 0.2376661599 0.0047652877 0.0099210000 0.0002950000 0.0037150000 0.0000000000 0.0000050000 0.0020080000 40301421 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1430 1311867766.3291699886 0.1258117557 0.1309903336 0.2376661599 0.0047680721 0.0082390000 0.0002720000 0.0033710000 0.0000000000 0.0000030000 0.0011990000 40305093 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1431 1311867766.3653209209 0.1258181483 0.1309867192 0.2376661599 0.0047974642 0.0085040000 0.0002730000 0.0036460000 0.0000000000 0.0000040000 0.0011970000 40308821 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1432 1311867766.3979220390 0.1258834004 0.1309831554 0.2376661599 0.0048075562 0.0120170000 0.0003660000 0.0039550000 0.0000010000 0.0000080000 0.0013270000 40312549 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1433 1311867766.4302849770 0.1259415895 0.1309796372 0.2376661599 0.0048061372 0.0092330000 0.0002980000 0.0028340000 0.0000000000 0.0000040000 0.0020030000 40316277 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1434 1311867766.4642350674 0.1260990500 0.1309762338 0.2376661599 0.0048092978 0.0086740000 0.0002710000 0.0036720000 0.0000010000 0.0000040000 0.0012010000 40319949 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1435 1311867766.4967210293 0.1264040619 0.1309730476 0.2376661599 0.0048081566 0.0086310000 0.0002720000 0.0036840000 0.0000010000 0.0000030000 0.0012010000 40323621 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1436 1311867766.5302040577 0.1267457902 0.1309701038 0.2376661599 0.0048068938 0.0086180000 0.0002710000 0.0036930000 0.0000010000 0.0000030000 0.0012070000 40327237 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1437 1311867766.5639820099 0.1271491349 0.1309674448 0.2376661599 0.0048053256 0.0094290000 0.0002690000 0.0036860000 0.0000010000 0.0000040000 0.0019930000 40330965 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1438 1311867766.5953519344 0.1277347207 0.1309651967 0.2376661599 0.0048039808 0.0086110000 0.0002840000 0.0036750000 0.0000010000 0.0000040000 0.0011970000 40334637 96830484 509673472 3.8597266674 3.9518022537 3.9910783768 1439 1311867766.6287128925 0.1213571504 0.1309585199 0.2376661599 0.0048245943 0.0089760000 0.0002740000 0.0036820000 0.0000040000 0.0000030000 0.0014580000 40338365 96830484 509673472 3.8656754494 3.9560203552 3.9860467911 1440 1311867766.6636400223 0.1210344285 0.1309516281 0.2376661599 0.0048253679 0.0086700000 0.0002720000 0.0036890000 0.0000000000 0.0000030000 0.0012040000 40342093 96830484 509673472 3.8663516045 3.9522759914 3.9846541882 1441 1311867766.6964800358 0.1214243248 0.1309450165 0.2376661599 0.0048363866 0.0108710000 0.0002740000 0.0042550000 0.0000030000 0.0000040000 0.0022740000 40345709 96830484 509673472 3.8669767380 3.9520306587 3.9838988781 1442 1311867766.7300829887 0.1228998750 0.1309394374 0.2376661599 0.0048407581 0.0081130000 0.0003210000 0.0030970000 0.0000000000 0.0000030000 0.0012020000 40349493 96830484 509673472 3.8660991192 3.9510865211 3.9834136963 1443 1311867766.7628269196 0.1252785921 0.1309355144 0.2376661599 0.0048392611 0.0088700000 0.0002760000 0.0036920000 0.0000030000 0.0000040000 0.0014750000 40353165 96830484 509673472 3.8642437458 3.9507174492 3.9828667641 1444 1311867766.7970418930 0.1213776767 0.1309288954 0.2376661599 0.0048397606 0.0077330000 0.0002800000 0.0028000000 0.0000000000 0.0000040000 0.0012120000 40356837 96830484 509673472 3.8686590195 3.9496834278 3.9809548855 1445 1311867766.8299551010 0.1216301993 0.1309224603 0.2376661599 0.0048394445 0.0085660000 0.0002800000 0.0024890000 0.0000040000 0.0000040000 0.0022750000 40360509 96830484 509673472 3.8690023422 3.9511377811 3.9801959991 1446 1311867766.8662180901 0.1277970374 0.1309202989 0.2376661599 0.0048411814 0.0083580000 0.0002750000 0.0033970000 0.0000010000 0.0000040000 0.0012160000 40364349 96830484 509673472 3.8633499146 3.9498798847 3.9798688889 1447 1311867766.8958721161 0.1243584752 0.1309157641 0.2376661599 0.0048421973 0.0079680000 0.0002740000 0.0027940000 0.0000040000 0.0000040000 0.0014540000 40367853 96830484 509673472 3.8671562672 3.9494698048 3.9780840874 1448 1311867766.9286260605 0.1258295923 0.1309122516 0.2376661599 0.0048479286 0.0115550000 0.0003740000 0.0039350000 0.0000010000 0.0000080000 0.0013320000 40371581 96830484 509673472 3.8658995628 3.9501249790 3.9774637222 1449 1311867766.9661469460 0.1240145266 0.1309074912 0.2376661599 0.0048667450 0.0101570000 0.0002980000 0.0037620000 0.0000050000 0.0000040000 0.0022650000 40375421 96830484 509673472 3.8683760166 3.9508929253 3.9765870571 1450 1311867766.9956479073 0.1195737422 0.1308996749 0.2376661599 0.0048699240 0.0121470000 0.0003760000 0.0040040000 0.0000010000 0.0000080000 0.0013290000 40378981 96830484 509673472 3.8728961945 3.9507591724 3.9754540920 1451 1311867767.0294270515 0.1185187846 0.1308911422 0.2376661599 0.0048690287 0.0095790000 0.0003100000 0.0037880000 0.0000040000 0.0000040000 0.0014600000 40382765 96830484 509673472 3.8738584518 3.9484050274 3.9749107361 1452 1311867767.0660951138 0.1234563887 0.1308860218 0.2376661599 0.0048748482 0.0086800000 0.0002890000 0.0037420000 0.0000010000 0.0000040000 0.0012070000 40386493 96830484 509673472 3.8691394329 3.9487180710 3.9759144783 1453 1311867767.0968320370 0.1180501506 0.1308771878 0.2376661599 0.0048766264 0.0097780000 0.0002810000 0.0037560000 0.0000040000 0.0000030000 0.0022580000 40390165 96830484 509673472 3.8745365143 3.9484946728 3.9750177860 1454 1311867767.1276900768 0.1186447591 0.1308687748 0.2376661599 0.0048779472 0.0087060000 0.0002900000 0.0037430000 0.0000000000 0.0000030000 0.0012010000 40393781 96830484 509673472 3.8737757206 3.9464547634 3.9750483036 1455 1311867767.1632909775 0.1193767637 0.1308608766 0.2376661599 0.0048763010 0.0068520000 0.0002890000 0.0016400000 0.0000030000 0.0000030000 0.0014730000 40397565 96830484 509673472 3.8729474545 3.9461741447 3.9750161171 1456 1311867767.1955349445 0.1212061346 0.1308542456 0.2376661599 0.0048773112 0.0105010000 0.0003820000 0.0024460000 0.0000010000 0.0000080000 0.0013260000 40401237 96830484 509673472 3.8709754944 3.9470129013 3.9754683971 1457 1311867767.2308650017 0.1193029359 0.1308463174 0.2376661599 0.0048768867 0.0103890000 0.0003220000 0.0037990000 0.0000040000 0.0000040000 0.0022460000 40405077 96830484 509673472 3.8730025291 3.9465227127 3.9750998020 1458 1311867767.2658200264 0.1188156530 0.1308380659 0.2376661599 0.0048755213 0.0087140000 0.0002940000 0.0037540000 0.0000010000 0.0000040000 0.0012020000 40408805 96830484 509673472 3.8733344078 3.9474632740 3.9751141071 1459 1311867767.2981290817 0.1171288788 0.1308286696 0.2376661599 0.0048741370 0.0074930000 0.0002900000 0.0022720000 0.0000040000 0.0000030000 0.0014490000 40412477 96830484 509673472 3.8748776913 3.9482650757 3.9753942490 1460 1311867767.3362140656 0.1179319769 0.1308198363 0.2376661599 0.0048768098 0.0087840000 0.0002860000 0.0038020000 0.0000000000 0.0000030000 0.0011980000 40416317 96830484 509673472 3.8738138676 3.9473915100 3.9752500057 1461 1311867767.3633511066 0.1179772913 0.1308110460 0.2376661599 0.0048755509 0.0096690000 0.0002910000 0.0036730000 0.0000030000 0.0000030000 0.0022240000 40419877 96830484 509673472 3.8736040592 3.9465034008 3.9752302170 1462 1311867767.3987689018 0.1148816943 0.1308001504 0.2376661599 0.0048744168 0.0088330000 0.0003010000 0.0037780000 0.0000010000 0.0000040000 0.0011990000 40423661 96830484 509673472 3.8758218288 3.9478881359 3.9750633240 1463 1311867767.4331369400 0.1157472283 0.1307898614 0.2376661599 0.0048733296 0.0090550000 0.0003010000 0.0038050000 0.0000030000 0.0000030000 0.0014360000 40427389 96830484 509673472 3.8750438690 3.9492111206 3.9755938053 1464 1311867767.4638109207 0.1135691851 0.1307780986 0.2376661599 0.0048731177 0.0088200000 0.0002990000 0.0038080000 0.0000000000 0.0000040000 0.0011950000 40431005 96830484 509673472 3.8770320415 3.9485397339 3.9754657745 1465 1311867767.4974899292 0.1132659763 0.1307661449 0.2376661599 0.0048715706 0.0130230000 0.0004120000 0.0040860000 0.0000080000 0.0000070000 0.0023930000 40434733 96830484 509673472 3.8768484592 3.9483740330 3.9751145840 1466 1311867767.5351889133 0.1129514426 0.1307539930 0.2376661599 0.0048751942 0.0084850000 0.0003140000 0.0029440000 0.0000010000 0.0000050000 0.0012000000 40438573 96830484 509673472 3.8771467209 3.9496617317 3.9752492905 1467 1311867767.5664100647 0.1128570959 0.1307417934 0.2376661599 0.0048773917 0.0073340000 0.0003070000 0.0020150000 0.0000040000 0.0000030000 0.0014350000 40442245 96830484 509673472 3.8769903183 3.9496581554 3.9756305218 1468 1311867767.5953979492 0.1123539954 0.1307292676 0.2376661599 0.0048757467 0.0076790000 0.0003030000 0.0026080000 0.0000010000 0.0000040000 0.0011890000 40445805 96830484 509673472 3.8771154881 3.9495944977 3.9755964279 1469 1311867767.6338059902 0.1123444736 0.1307167525 0.2376661599 0.0048744502 0.0099400000 0.0002950000 0.0038480000 0.0000030000 0.0000030000 0.0022070000 40449645 96830484 509673472 3.8767635822 3.9495222569 3.9758102894 1470 1311867767.6632149220 0.1127091572 0.1307045024 0.2376661599 0.0048729711 0.0070040000 0.0003040000 0.0020000000 0.0000000000 0.0000030000 0.0011830000 40453261 96830484 509673472 3.8762142658 3.9483358860 3.9758763313 1471 1311867767.6991050243 0.1143264547 0.1306933684 0.2376661599 0.0048724152 0.0091020000 0.0002940000 0.0038710000 0.0000040000 0.0000040000 0.0014530000 40457045 96830484 509673472 3.8743836880 3.9477281570 3.9758834839 1472 1311867767.7346129417 0.1133704931 0.1306816002 0.2376661599 0.0048707888 0.0066490000 0.0003160000 0.0016870000 0.0000000000 0.0000030000 0.0011840000 40460773 96830484 509673472 3.8751547337 3.9484691620 3.9758582115 1473 1311867767.7651679516 0.1122060940 0.1306690574 0.2376661599 0.0048691868 0.0090470000 0.0003020000 0.0029270000 0.0000030000 0.0000030000 0.0022060000 40464445 96830484 509673472 3.8760542870 3.9482047558 3.9753072262 1474 1311867767.7999849319 0.1137334704 0.1306575679 0.2376661599 0.0048676354 0.0085400000 0.0002980000 0.0035510000 0.0000010000 0.0000030000 0.0011810000 40468173 96830484 509673472 3.8743689060 3.9474306107 3.9751603603 1475 1311867767.8344929218 0.1134135425 0.1306458770 0.2376661599 0.0048662732 0.0082120000 0.0003070000 0.0029260000 0.0000040000 0.0000030000 0.0014450000 40471845 96830484 509673472 3.8745248318 3.9467542171 3.9749169350 1476 1311867767.8673300743 0.1126904637 0.1306337121 0.2376661599 0.0048646831 0.0087950000 0.0003100000 0.0037640000 0.0000010000 0.0000040000 0.0011910000 40475517 96830484 509673472 3.8751471043 3.9466786385 3.9746549129 1477 1311867767.8966870308 0.1130096465 0.1306217797 0.2376661599 0.0048640515 0.0086870000 0.0003100000 0.0026340000 0.0000030000 0.0000040000 0.0021930000 40479077 96830484 509673472 3.8748798370 3.9491465092 3.9747121334 1478 1311867767.9358460903 0.1109893098 0.1306084966 0.2376661599 0.0048626838 0.0088600000 0.0003130000 0.0038750000 0.0000010000 0.0000040000 0.0011780000 40482973 96830484 509673472 3.8767950535 3.9492797852 3.9746124744 1479 1311867767.9646739960 0.1118120402 0.1305957877 0.2376661599 0.0048611101 0.0079890000 0.0003140000 0.0026360000 0.0000030000 0.0000030000 0.0014400000 40486589 96830484 509673472 3.8758583069 3.9488294125 3.9747884274 1480 1311867767.9988079071 0.1115162596 0.1305828961 0.2376661599 0.0048595594 0.0089050000 0.0003150000 0.0038760000 0.0000000000 0.0000030000 0.0011700000 40490317 96830484 509673472 3.8759093285 3.9496128559 3.9743962288 1481 1311867768.0346310139 0.1111546457 0.1305697778 0.2376661599 0.0048581337 0.0098070000 0.0003160000 0.0037930000 0.0000030000 0.0000030000 0.0021770000 40494101 96830484 509673472 3.8762521744 3.9498662949 3.9744703770 1482 1311867768.0639820099 0.1111474335 0.1305566723 0.2376661599 0.0048568619 0.0089120000 0.0003130000 0.0038830000 0.0000010000 0.0000040000 0.0011710000 40497661 96830484 509673472 3.8760814667 3.9492230415 3.9740083218 1483 1311867768.0985600948 0.1120837852 0.1305442159 0.2376661599 0.0048552380 0.0091840000 0.0003140000 0.0038860000 0.0000030000 0.0000030000 0.0014410000 40501445 96830484 509673472 3.8747582436 3.9493510723 3.9735620022 1484 1311867768.1352849007 0.1117432341 0.1305315468 0.2376661599 0.0048536414 0.0088380000 0.0003130000 0.0038800000 0.0000000000 0.0000030000 0.0011810000 40505229 96830484 509673472 3.8748233318 3.9494810104 3.9731876850 1485 1311867768.1651999950 0.1102595627 0.1305178956 0.2376661599 0.0048520857 0.0100130000 0.0003180000 0.0038960000 0.0000040000 0.0000040000 0.0021740000 40508845 96830484 509673472 3.8760190010 3.9505019188 3.9724638462 1486 1311867768.1962070465 0.1106297746 0.1305045119 0.2376661599 0.0048508173 0.0089220000 0.0003210000 0.0039150000 0.0000010000 0.0000040000 0.0011550000 40512461 96830484 509673472 3.8753345013 3.9508943558 3.9721267223 1487 1311867768.2323460579 0.1097382084 0.1304905467 0.2376661599 0.0048501697 0.0124650000 0.0004200000 0.0041890000 0.0000080000 0.0000070000 0.0015520000 40516245 96830484 509673472 3.8758757114 3.9501061440 3.9715952873 1488 1311867768.2749121189 0.1103984490 0.1304770439 0.2376661599 0.0048503391 0.0095890000 0.0003470000 0.0039790000 0.0000010000 0.0000050000 0.0011770000 40520253 96830484 509673472 3.8749089241 3.9514386654 3.9717326164 1489 1311867768.2962079048 0.1100657731 0.1304633359 0.2376661599 0.0048487655 0.0090570000 0.0003260000 0.0029960000 0.0000030000 0.0000030000 0.0021510000 40523589 96830484 509673472 3.8752124310 3.9530532360 3.9716224670 1490 1311867768.3351829052 0.1074270010 0.1304478753 0.2376661599 0.0048509312 0.0090760000 0.0003310000 0.0039290000 0.0000000000 0.0000040000 0.0011500000 40527485 96830484 509673472 3.8774597645 3.9525897503 3.9710443020 1491 1311867768.3693380356 0.1047145128 0.1304306161 0.2376661599 0.0048510851 0.0077010000 0.0003310000 0.0023610000 0.0000030000 0.0000030000 0.0014000000 40531101 96830484 509673472 3.8798453808 3.9522542953 3.9703211784 1492 1311867768.4011199474 0.1043055207 0.1304131060 0.2376661599 0.0048506983 0.0089870000 0.0003300000 0.0039380000 0.0000010000 0.0000040000 0.0011470000 40534717 96830484 509673472 3.8801450729 3.9535789490 3.9701373577 1493 1311867768.4324789047 0.1079745442 0.1303980768 0.2376661599 0.0048523846 0.0099900000 0.0003300000 0.0039640000 0.0000040000 0.0000030000 0.0021440000 40538277 96830484 509673472 3.8763337135 3.9544649124 3.9708359241 1494 1311867768.4655070305 0.1058953255 0.1303816761 0.2376661599 0.0048528210 0.0119530000 0.0004560000 0.0042140000 0.0000010000 0.0000080000 0.0012680000 40541949 96830484 509673472 3.8781285286 3.9533939362 3.9704723358 1495 1311867768.4980540276 0.1045989320 0.1303644301 0.2376661599 0.0048515657 0.0097260000 0.0003500000 0.0040090000 0.0000040000 0.0000040000 0.0014020000 40545677 96830484 509673472 3.8793647289 3.9550485611 3.9704117775 1496 1311867768.5367710590 0.1057592183 0.1303479828 0.2376661599 0.0048535184 0.0081300000 0.0003380000 0.0030440000 0.0000010000 0.0000040000 0.0011370000 40549461 96830484 509673472 3.8785400391 3.9560401440 3.9710607529 1497 1311867768.5648899078 0.1042286307 0.1303305350 0.2376661599 0.0048545950 0.0107920000 0.0003370000 0.0039990000 0.0000040000 0.0000030000 0.0021160000 40553077 96830484 509673472 3.8799409866 3.9544627666 3.9709420204 1498 1311867768.5998411179 0.1038226560 0.1303128394 0.2376661599 0.0048530107 0.0095300000 0.0003860000 0.0040780000 0.0000000000 0.0000030000 0.0011310000 40556805 96830484 509673472 3.8802113533 3.9539141655 3.9710445404 1499 1311867768.6319470406 0.1045430303 0.1302956481 0.2376661599 0.0048515350 0.0126860000 0.0004310000 0.0041690000 0.0000090000 0.0000070000 0.0015290000 40560477 96830484 509673472 3.8794949055 3.9541683197 3.9713313580 1500 1311867768.6643230915 0.1018032804 0.1302766532 0.2376661599 0.0048506350 0.0110450000 0.0004420000 0.0029460000 0.0000010000 0.0000070000 0.0012670000 40564205 96830484 509673472 3.8823511600 3.9555890560 3.9715173244 1501 1311867768.7014238834 0.1037765369 0.1302589982 0.2376661599 0.0048502533 0.0105610000 0.0003660000 0.0040690000 0.0000040000 0.0000050000 0.0020890000 40567933 96830484 509673472 3.8802750111 3.9543492794 3.9720923901 1502 1311867768.7344141006 0.1036787257 0.1302413016 0.2376661599 0.0048487957 0.0085210000 0.0003370000 0.0033880000 0.0000010000 0.0000040000 0.0011180000 40571717 96830484 509673472 3.8801329136 3.9531760216 3.9723572731 1503 1311867768.7646389008 0.1037433967 0.1302236716 0.2376661599 0.0048480183 0.0094010000 0.0003400000 0.0040240000 0.0000030000 0.0000040000 0.0013980000 40575333 96830484 509673472 3.8801832199 3.9536528587 3.9729506969 1504 1311867768.8039369583 0.1050017327 0.1302069017 0.2376661599 0.0048473892 0.0091810000 0.0003370000 0.0040350000 0.0000010000 0.0000040000 0.0011190000 40579173 96830484 509673472 3.8789782524 3.9541802406 3.9733200073 1505 1311867768.8365039825 0.1041932032 0.1301896169 0.2376661599 0.0048461809 0.0081770000 0.0003400000 0.0020920000 0.0000040000 0.0000030000 0.0020670000 40582901 96830484 509673472 3.8799126148 3.9541244507 3.9736111164 1506 1311867768.8651020527 0.1037278771 0.1301720460 0.2376661599 0.0048455921 0.0081340000 0.0003390000 0.0030560000 0.0000000000 0.0000030000 0.0011170000 40586461 96830484 509673472 3.8803434372 3.9525120258 3.9737706184 1507 1311867768.9001519680 0.1039035469 0.1301546150 0.2376661599 0.0048442520 0.0094220000 0.0003390000 0.0040460000 0.0000040000 0.0000040000 0.0013700000 40590245 96830484 509673472 3.8803155422 3.9539823532 3.9742794037 1508 1311867768.9330470562 0.1047831625 0.1301377904 0.2376661599 0.0048431095 0.0075190000 0.0003400000 0.0023250000 0.0000010000 0.0000040000 0.0011120000 40593861 96830484 509673472 3.8797709942 3.9525110722 3.9748806953 1509 1311867768.9639101028 0.1046304777 0.1301208870 0.2376661599 0.0048416490 0.0100660000 0.0003370000 0.0039350000 0.0000040000 0.0000030000 0.0020590000 40597477 96830484 509673472 3.8799021244 3.9526913166 3.9751677513 1510 1311867768.9992640018 0.1044198200 0.1301038664 0.2376661599 0.0048416186 0.0075530000 0.0003380000 0.0024270000 0.0000010000 0.0000030000 0.0011050000 40601261 96830484 509673472 3.8802094460 3.9534521103 3.9755249023 1511 1311867769.0331530571 0.1049155891 0.1300871965 0.2376661599 0.0048412812 0.0074570000 0.0003420000 0.0021050000 0.0000040000 0.0000030000 0.0013590000 40604877 96830484 509673472 3.8798644543 3.9539110661 3.9760253429 1512 1311867769.0641028881 0.1043166667 0.1300701525 0.2376661599 0.0048400900 0.0075710000 0.0003410000 0.0024440000 0.0000000000 0.0000030000 0.0011070000 40608549 96830484 509673472 3.8804378510 3.9533658028 3.9760725498 1513 1311867769.0999929905 0.1042196155 0.1300530669 0.2376661599 0.0048386118 0.0082230000 0.0003510000 0.0021140000 0.0000040000 0.0000030000 0.0020550000 40612333 96830484 509673472 3.8803584576 3.9522252083 3.9759964943 1514 1311867769.1327989101 0.1051123813 0.1300365935 0.2376661599 0.0048372155 0.0072150000 0.0003470000 0.0021170000 0.0000010000 0.0000040000 0.0011050000 40615949 96830484 509673472 3.8793799877 3.9528670311 3.9763488770 1515 1311867769.1643240452 0.1026156470 0.1300184939 0.2376661599 0.0048426631 0.0094310000 0.0003440000 0.0040980000 0.0000040000 0.0000030000 0.0013670000 40619621 96830484 509673472 3.8817532063 3.9531593323 3.9763920307 1516 1311867769.2002429962 0.1036611795 0.1300011078 0.2376661599 0.0048426590 0.0107830000 0.0004450000 0.0023360000 0.0000010000 0.0000090000 0.0012650000 40623349 96830484 509673472 3.8809044361 3.9526536465 3.9765889645 1517 1311867769.2324860096 0.1036866158 0.1299837614 0.2376661599 0.0048433174 0.0103840000 0.0003830000 0.0038320000 0.0000050000 0.0000050000 0.0020500000 40627021 96830484 509673472 3.8809010983 3.9541275501 3.9768040180 1518 1311867769.2636189461 0.1044827476 0.1299669623 0.2376661599 0.0048434698 0.0072080000 0.0003700000 0.0021220000 0.0000010000 0.0000030000 0.0010960000 40630693 96830484 509673472 3.8802747726 3.9527871609 3.9771218300 1519 1311867769.3002018929 0.1055329219 0.1299508767 0.2376661599 0.0048504986 0.0088660000 0.0003580000 0.0034470000 0.0000030000 0.0000030000 0.0013530000 40634421 96830484 509673472 3.8791191578 3.9536540508 3.9771904945 1520 1311867769.3330841064 0.1033251882 0.1299333598 0.2376661599 0.0048495134 0.0072360000 0.0003570000 0.0021420000 0.0000010000 0.0000040000 0.0010870000 40638093 96830484 509673472 3.8813667297 3.9551496506 3.9771213531 1521 1311867769.3653230667 0.1013522223 0.1299145687 0.2376661599 0.0048480574 0.0116590000 0.0004570000 0.0026890000 0.0000080000 0.0000070000 0.0022020000 40641877 96830484 509673472 3.8832483292 3.9562859535 3.9769921303 1522 1311867769.3995320797 0.1020049080 0.1298962313 0.2376661599 0.0048467917 0.0085240000 0.0003810000 0.0028570000 0.0000000000 0.0000050000 0.0010990000 40645605 96830484 509673472 3.8824090958 3.9562144279 3.9772386551 1523 1311867769.4340240955 0.1012232974 0.1298774046 0.2376661599 0.0048460686 0.0075280000 0.0003690000 0.0021680000 0.0000040000 0.0000040000 0.0013470000 40649277 96830484 509673472 3.8830063343 3.9552056789 3.9770598412 1524 1311867769.4644269943 0.1006522551 0.1298582280 0.2376661599 0.0048521262 0.0092240000 0.0003680000 0.0041700000 0.0000000000 0.0000030000 0.0010670000 40652949 96830484 509673472 3.8836283684 3.9556751251 3.9773266315 1525 1311867769.4999239445 0.1014305577 0.1298395869 0.2376661599 0.0048561072 0.0113570000 0.0004280000 0.0045810000 0.0000040000 0.0000030000 0.0020500000 40656733 96830484 509673472 3.8829057217 3.9561674595 3.9774713516 1526 1311867769.5317490101 0.1019918248 0.1298213381 0.2376661599 0.0048548356 0.0083290000 0.0003720000 0.0031800000 0.0000000000 0.0000030000 0.0010680000 40660349 96830484 509673472 3.8823392391 3.9551317692 3.9771020412 1527 1311867769.5660109520 0.1020321772 0.1298031395 0.2376661599 0.0048533817 0.0095380000 0.0003690000 0.0041920000 0.0000030000 0.0000040000 0.0013310000 40663965 96830484 509673472 3.8821101189 3.9546453953 3.9772264957 1528 1311867769.6002509594 0.1017587706 0.1297847859 0.2376661599 0.0048518684 0.0114500000 0.0004730000 0.0027400000 0.0000010000 0.0000100000 0.0012770000 40667693 96830484 509673472 3.8823215961 3.9552190304 3.9771049023 1529 1311867769.6330249310 0.1027330533 0.1297670935 0.2376661599 0.0048553019 0.0123780000 0.0004740000 0.0037620000 0.0000090000 0.0000080000 0.0021420000 40671421 96830484 509673472 3.8814840317 3.9543838501 3.9774692059 1530 1311867769.6637229919 0.1017394140 0.1297487747 0.2376661599 0.0048539939 0.0127760000 0.0004750000 0.0044980000 0.0000010000 0.0000080000 0.0011970000 40675037 96830484 509673472 3.8823709488 3.9549758434 3.9775333405 1531 1311867769.7014029026 0.1025348380 0.1297309994 0.2376661599 0.0048597030 0.0097350000 0.0003940000 0.0038320000 0.0000050000 0.0000040000 0.0013270000 40678933 96830484 509673472 3.8816044331 3.9559462070 3.9782249928 1532 1311867769.7340829372 0.1007397771 0.1297120757 0.2376661599 0.0048587894 0.0076390000 0.0003750000 0.0025440000 0.0000000000 0.0000030000 0.0010540000 40682549 96830484 509673472 3.8835628033 3.9563369751 3.9785206318 1533 1311867769.7641069889 0.1022965685 0.1296941921 0.2376661599 0.0048625263 0.0102570000 0.0003750000 0.0042640000 0.0000030000 0.0000030000 0.0019450000 40686221 96830484 509673472 3.8820853233 3.9570116997 3.9795370102 1534 1311867769.8003458977 0.1010747775 0.1296755354 0.2376661599 0.0048823507 0.0108830000 0.0004740000 0.0027630000 0.0000010000 0.0000080000 0.0011770000 40689949 96830484 509673472 3.8828260899 3.9569785595 3.9797801971 1535 1311867769.8341090679 0.1010644957 0.1296568963 0.2376661599 0.0048817367 0.0092110000 0.0003990000 0.0033120000 0.0000050000 0.0000040000 0.0013200000 40693677 96830484 509673472 3.8827805519 3.9560530186 3.9800620079 1536 1311867769.8692820072 0.1011774614 0.1296383550 0.2376661599 0.0048803425 0.0094370000 0.0003830000 0.0043040000 0.0000010000 0.0000030000 0.0010400000 40697461 96830484 509673472 3.8827846050 3.9558446407 3.9805076122 1537 1311867769.9001140594 0.1005507931 0.1296194301 0.2376661599 0.0048789645 0.0103920000 0.0003870000 0.0043190000 0.0000040000 0.0000040000 0.0018980000 40701133 96830484 509673472 3.8835060596 3.9574949741 3.9810492992 1538 1311867769.9321451187 0.1000709832 0.1296002178 0.2376661599 0.0048776281 0.0094910000 0.0003970000 0.0043320000 0.0000010000 0.0000040000 0.0010190000 40704749 96830484 509673472 3.8839855194 3.9583699703 3.9812109470 1539 1311867769.9684319496 0.0995269567 0.1295806770 0.2376661599 0.0048764180 0.0110840000 0.0004950000 0.0028250000 0.0000080000 0.0000080000 0.0013920000 40708533 96830484 509673472 3.8843295574 3.9575743675 3.9812836647 1540 1311867770.0010259151 0.0990261212 0.1295608364 0.2376661599 0.0048750914 0.0100050000 0.0004240000 0.0043960000 0.0000000000 0.0000040000 0.0010210000 40712317 96830484 509673472 3.8849499226 3.9581947327 3.9816009998 1541 1311867770.0330319405 0.0980301946 0.1295403753 0.2376661599 0.0048736210 0.0085790000 0.0004030000 0.0026110000 0.0000040000 0.0000030000 0.0018710000 40715933 96830484 509673472 3.8858714104 3.9588987827 3.9816555977 1542 1311867770.0690810680 0.0963533595 0.1295188532 0.2376661599 0.0048735799 0.0096070000 0.0004060000 0.0043940000 0.0000000000 0.0000040000 0.0010070000 40719717 96830484 509673472 3.8872947693 3.9579691887 3.9815771580 1543 1311867770.1002650261 0.0976683050 0.1294982112 0.2376661599 0.0048755255 0.0083710000 0.0004060000 0.0029790000 0.0000030000 0.0000030000 0.0012670000 40723389 96830484 509673472 3.8859696388 3.9576759338 3.9821085930 1544 1311867770.1335709095 0.0975966379 0.1294775496 0.2376661599 0.0048741338 0.0080840000 0.0004070000 0.0029890000 0.0000000000 0.0000030000 0.0010000000 40727061 96830484 509673472 3.8860061169 3.9582018852 3.9823317528 1545 1311867770.1684958935 0.0969392210 0.1294564892 0.2376661599 0.0048727830 0.0082670000 0.0004030000 0.0022860000 0.0000040000 0.0000030000 0.0018620000 40730845 96830484 509673472 3.8865323067 3.9580767155 3.9822871685 1546 1311867770.2001299858 0.0964785144 0.1294351580 0.2376661599 0.0048713169 0.0124610000 0.0005060000 0.0046490000 0.0000010000 0.0000080000 0.0011400000 40734517 96830484 509673472 3.8868758678 3.9576029778 3.9826223850 1547 1311867770.2336180210 0.0970483795 0.1294142228 0.2376661599 0.0048704646 0.0103380000 0.0004260000 0.0044540000 0.0000050000 0.0000040000 0.0012750000 40738189 96830484 509673472 3.8857884407 3.9578750134 3.9828946590 1548 1311867770.2679719925 0.0965023264 0.1293929619 0.2376661599 0.0048713155 0.0095860000 0.0004070000 0.0044060000 0.0000000000 0.0000040000 0.0009990000 40741917 96830484 509673472 3.8863890171 3.9570064545 3.9830021858 1549 1311867770.3009040356 0.0959469676 0.1293713699 0.2376661599 0.0048704386 0.0079440000 0.0004090000 0.0019320000 0.0000030000 0.0000030000 0.0018680000 40745589 96830484 509673472 3.8868677616 3.9566106796 3.9830241203 1550 1311867770.3339090347 0.0977453142 0.1293509660 0.2376661599 0.0048729243 0.0095880000 0.0004150000 0.0044300000 0.0000000000 0.0000030000 0.0009970000 40749317 96830484 509673472 3.8847513199 3.9566636086 3.9832725525 1551 1311867770.3681850433 0.0960162729 0.1293294736 0.2376661599 0.0048885987 0.0116080000 0.0005080000 0.0028610000 0.0000070000 0.0000070000 0.0013910000 40753045 96830484 509673472 3.8861398697 3.9572756290 3.9831359386 1552 1311867770.4014930725 0.0941413715 0.1293068009 0.2376661599 0.0048910496 0.0133310000 0.0005140000 0.0047180000 0.0000010000 0.0000070000 0.0011320000 40756717 96830484 509673472 3.8879339695 3.9579768181 3.9828341007 1553 1311867770.4333899021 0.0940081328 0.1292840715 0.2376661599 0.0048913595 0.0091090000 0.0004390000 0.0023600000 0.0000060000 0.0000050000 0.0018530000 40760445 96830484 509673472 3.8878185749 3.9582161903 3.9830091000 1554 1311867770.4684588909 0.0934989303 0.1292610438 0.2376661599 0.0048899186 0.0123980000 0.0005140000 0.0046760000 0.0000010000 0.0000080000 0.0011110000 40764173 96830484 509673472 3.8882963657 3.9573421478 3.9830496311 1555 1311867770.5046019554 0.0920594335 0.1292371199 0.2376661599 0.0048884696 0.0083220000 0.0004360000 0.0023490000 0.0000040000 0.0000040000 0.0012900000 40767957 96830484 509673472 3.8894445896 3.9572916031 3.9827649593 1556 1311867770.5338129997 0.0932568088 0.1292139963 0.2376661599 0.0048873338 0.0095860000 0.0004220000 0.0044380000 0.0000010000 0.0000040000 0.0009880000 40771517 96830484 509673472 3.8883068562 3.9573597908 3.9832792282 1557 1311867770.5683600903 0.0935111940 0.1291910658 0.2376661599 0.0048901826 0.0105170000 0.0004220000 0.0044660000 0.0000040000 0.0000040000 0.0018260000 40775245 96830484 509673472 3.8878891468 3.9577257633 3.9837751389 1558 1311867770.6027359962 0.0942747742 0.1291686548 0.2376661599 0.0048919070 0.0078300000 0.0004250000 0.0026580000 0.0000010000 0.0000040000 0.0009810000 40778973 96830484 509673472 3.8872895241 3.9588630199 3.9841508865 1559 1311867770.6331069469 0.0913657323 0.1291444066 0.2376661599 0.0048924107 0.0099400000 0.0004220000 0.0044370000 0.0000030000 0.0000030000 0.0012380000 40782589 96830484 509673472 3.8900291920 3.9585623741 3.9839899540 1560 1311867770.6699299812 0.0919846445 0.1291205863 0.2376661599 0.0048908858 0.0096470000 0.0004230000 0.0044340000 0.0000000000 0.0000030000 0.0009940000 40786429 96830484 509673472 3.8898546696 3.9578640461 3.9842152596 1561 1311867770.7014191151 0.0928373486 0.1290973427 0.2376661599 0.0048896247 0.0091220000 0.0004210000 0.0030090000 0.0000040000 0.0000030000 0.0019230000 40790101 96830484 509673472 3.8892979622 3.9572834969 3.9847104549 1562 1311867770.7347331047 0.0933095515 0.1290744312 0.2376661599 0.0048890899 0.0116940000 0.0005250000 0.0029200000 0.0000010000 0.0000100000 0.0012830000 40793829 96830484 509673472 3.8889896870 3.9583802223 3.9850535393 1563 1311867770.7684218884 0.0925722793 0.1290510773 0.2376661599 0.0048880052 0.0096570000 0.0004640000 0.0034400000 0.0000050000 0.0000040000 0.0013200000 40797501 96830484 509673472 3.8897757530 3.9577147961 3.9848749638 1564 1311867770.8017508984 0.0927534923 0.1290278691 0.2376661599 0.0048865756 0.0096760000 0.0004270000 0.0043300000 0.0000010000 0.0000040000 0.0010390000 40801173 96830484 509673472 3.8896591663 3.9573290348 3.9853367805 1565 1311867770.8396499157 0.0914317369 0.1290038460 0.2376661599 0.0048859122 0.0085160000 0.0004270000 0.0023020000 0.0000030000 0.0000030000 0.0019110000 40805069 96830484 509673472 3.8912174702 3.9583985806 3.9855921268 1566 1311867770.8699400425 0.0911363736 0.1289796650 0.2376661599 0.0048855767 0.0098950000 0.0004320000 0.0044410000 0.0000010000 0.0000040000 0.0010400000 40808685 96830484 509673472 3.8917145729 3.9569816589 3.9857094288 1567 1311867770.9027009010 0.0907771960 0.1289552856 0.2376661599 0.0048843644 0.0076750000 0.0004220000 0.0021830000 0.0000030000 0.0000030000 0.0013020000 40812357 96830484 509673472 3.8921530247 3.9566845894 3.9859154224 1568 1311867770.9355690479 0.0915561244 0.1289314341 0.2376661599 0.0048858696 0.0096240000 0.0004210000 0.0044370000 0.0000010000 0.0000030000 0.0010300000 40816085 96830484 509673472 3.8913764954 3.9583880901 3.9866588116 1569 1311867770.9692869186 0.0921202004 0.1289079725 0.2376661599 0.0048850405 0.0105640000 0.0004260000 0.0044570000 0.0000040000 0.0000030000 0.0019070000 40819813 96830484 509673472 3.8911192417 3.9572591782 3.9872796535 1570 1311867771.0021619797 0.0922643915 0.1288846327 0.2376661599 0.0048856862 0.0097600000 0.0004290000 0.0044520000 0.0000000000 0.0000040000 0.0010290000 40823485 96830484 509673472 3.8910627365 3.9569470882 3.9877810478 1571 1311867771.0365509987 0.0922263786 0.1288612983 0.2376661599 0.0048976990 0.0100080000 0.0004200000 0.0044770000 0.0000040000 0.0000040000 0.0012920000 40827157 96830484 509673472 3.8909735680 3.9584879875 3.9887337685 1572 1311867771.0685739517 0.0903404653 0.1288367940 0.2376661599 0.0048965046 0.0126520000 0.0005230000 0.0048070000 0.0000010000 0.0000070000 0.0011600000 40830885 96830484 509673472 3.8929202557 3.9589130878 3.9891984463 1573 1311867771.1014111042 0.0876163989 0.1288105890 0.2376661599 0.0049021184 0.0099650000 0.0004480000 0.0034390000 0.0000040000 0.0000040000 0.0018900000 40834613 96830484 509673472 3.8957872391 3.9581460953 3.9892518520 1574 1311867771.1381099224 0.0877806470 0.1287845217 0.2376661599 0.0049011313 0.0128800000 0.0005310000 0.0047170000 0.0000010000 0.0000090000 0.0011540000 40838397 96830484 509673472 3.8957357407 3.9580168724 3.9894859791 1575 1311867771.1686840057 0.0887356326 0.1287590939 0.2376661599 0.0049000953 0.0104290000 0.0004420000 0.0045330000 0.0000040000 0.0000040000 0.0013060000 40842013 96830484 509673472 3.8948090076 3.9583621025 3.9899907112 1576 1311867771.2019159794 0.0885273740 0.1287335661 0.2376661599 0.0048987107 0.0098260000 0.0004300000 0.0044790000 0.0000010000 0.0000040000 0.0010160000 40845685 96830484 509673472 3.8952322006 3.9573578835 3.9901554585 1577 1311867771.2363801003 0.0892525092 0.1287085306 0.2376661599 0.0048976927 0.0091920000 0.0004320000 0.0025190000 0.0000040000 0.0000030000 0.0018660000 40849413 96830484 509673472 3.8947055340 3.9577589035 3.9905905724 1578 1311867771.2705540657 0.0891055018 0.1286834336 0.2376661599 0.0048963066 0.0084440000 0.0004750000 0.0030590000 0.0000010000 0.0000030000 0.0010100000 40853197 96830484 509673472 3.8951997757 3.9584624767 3.9907751083 1579 1311867771.3016860485 0.0894424096 0.1286585818 0.2376661599 0.0048948756 0.0100390000 0.0004360000 0.0044840000 0.0000030000 0.0000030000 0.0012700000 40856813 96830484 509673472 3.8951387405 3.9580595493 3.9910840988 1580 1311867771.3360719681 0.0891440958 0.1286335726 0.2376661599 0.0048933637 0.0076110000 0.0004490000 0.0023290000 0.0000000000 0.0000030000 0.0010080000 40860541 96830484 509673472 3.8958578110 3.9574716091 3.9912793636 1581 1311867771.3679900169 0.0893958211 0.1286087543 0.2376661599 0.0048918281 0.0105220000 0.0004330000 0.0044020000 0.0000040000 0.0000030000 0.0018440000 40864213 96830484 509673472 3.8957166672 3.9584085941 3.9914493561 1582 1311867771.4030399323 0.0879463181 0.1285830511 0.2376661599 0.0048903748 0.0092030000 0.0004390000 0.0038290000 0.0000000000 0.0000040000 0.0010060000 40867941 96830484 509673472 3.8973045349 3.9599773884 3.9914498329 1583 1311867771.4361710548 0.0881381631 0.1285575016 0.2376661599 0.0048895382 0.0132660000 0.0005310000 0.0046600000 0.0000070000 0.0000080000 0.0013840000 40871669 96830484 509673472 3.8974709511 3.9582450390 3.9914729595 1584 1311867771.4682569504 0.0885109901 0.1285322197 0.2376661599 0.0048881065 0.0103540000 0.0004600000 0.0045880000 0.0000010000 0.0000050000 0.0010050000 40875341 96830484 509673472 3.8973407745 3.9591987133 3.9918482304 1585 1311867771.5008640289 0.0870040357 0.1285060190 0.2376661599 0.0048868648 0.0099230000 0.0004360000 0.0038240000 0.0000040000 0.0000030000 0.0018230000 40879013 96830484 509673472 3.8991363049 3.9608106613 3.9919142723 1586 1311867771.5365910530 0.0863510221 0.1284794395 0.2376661599 0.0048859711 0.0090870000 0.0004450000 0.0038350000 0.0000000000 0.0000030000 0.0009850000 40882797 96830484 509673472 3.9003551006 3.9591476917 3.9918191433 1587 1311867771.5686171055 0.0870412067 0.1284533285 0.2376661599 0.0048844708 0.0080030000 0.0004530000 0.0023780000 0.0000040000 0.0000030000 0.0012560000 40886525 96830484 509673472 3.9000122547 3.9583358765 3.9921376705 1588 1311867771.6077210903 0.0862965286 0.1284267814 0.2376661599 0.0048840640 0.0084030000 0.0004420000 0.0031050000 0.0000010000 0.0000040000 0.0009770000 40890365 96830484 509673472 3.9010512829 3.9600076675 3.9923937321 1589 1311867771.6366779804 0.0873159394 0.1284009092 0.2376661599 0.0048831461 0.0107090000 0.0004550000 0.0045790000 0.0000030000 0.0000030000 0.0017950000 40893925 96830484 509673472 3.9005901814 3.9579272270 3.9927861691 1590 1311867771.6715440750 0.0859553888 0.1283742139 0.2376661599 0.0048822794 0.0116840000 0.0005540000 0.0029580000 0.0000010000 0.0000100000 0.0011350000 40897709 96830484 509673472 3.9021615982 3.9574081898 3.9927423000 1591 1311867771.7024850845 0.0850015953 0.1283469527 0.2376661599 0.0048814077 0.0128480000 0.0005460000 0.0048390000 0.0000070000 0.0000080000 0.0013470000 40901381 96830484 509673472 3.9033312798 3.9593322277 3.9933276176 1592 1311867771.7367300987 0.0853779688 0.1283199621 0.2376661599 0.0048803243 0.0102720000 0.0004650000 0.0046520000 0.0000000000 0.0000040000 0.0009670000 40905053 96830484 509673472 3.9034123421 3.9593884945 3.9937584400 1593 1311867771.7697410583 0.0855580792 0.1282931185 0.2376661599 0.0048800723 0.0093000000 0.0004510000 0.0031350000 0.0000040000 0.0000030000 0.0017680000 40908781 96830484 509673472 3.9038531780 3.9577071667 3.9938979149 1594 1311867771.8023030758 0.0863979980 0.1282668355 0.2376661599 0.0048787871 0.0194910000 0.0006310000 0.0051620000 0.0000020000 0.0000150000 0.0014990000 40912453 96830484 509673472 3.9036924839 3.9578199387 3.9942719936 1595 1311867771.8386220932 0.0857806429 0.1282401984 0.2376661599 0.0048780951 0.0115000000 0.0004840000 0.0047280000 0.0000050000 0.0000050000 0.0012630000 40916293 96830484 509673472 3.9045131207 3.9585764408 3.9943962097 1596 1311867771.8711829185 0.0862807930 0.1282139080 0.2376661599 0.0048766882 0.0081620000 0.0004520000 0.0027850000 0.0000010000 0.0000040000 0.0009760000 40919909 96830484 509673472 3.9045951366 3.9573113918 3.9945037365 1597 1311867771.9016489983 0.0850745216 0.1281868953 0.2376661599 0.0048758775 0.0106940000 0.0004490000 0.0045990000 0.0000030000 0.0000030000 0.0017960000 40923581 96830484 509673472 3.9062674046 3.9563298225 3.9939873219 1598 1311867771.9377520084 0.0851135626 0.1281599407 0.2376661599 0.0048755269 0.0116630000 0.0005470000 0.0033340000 0.0000020000 0.0000090000 0.0011090000 40927365 96830484 509673472 3.9066746235 3.9571189880 3.9942185879 1599 1311867771.9696009159 0.0852836221 0.1281331263 0.2376661599 0.0048745008 0.0096730000 0.0004650000 0.0035430000 0.0000050000 0.0000050000 0.0012440000 40931037 96830484 509673472 3.9069602489 3.9567544460 3.9940583706 1600 1311867772.0018649101 0.0863732323 0.1281070263 0.2376661599 0.0048732586 0.0130450000 0.0005720000 0.0043770000 0.0000010000 0.0000080000 0.0011230000 40934765 96830484 509673472 3.9063618183 3.9560353756 3.9940786362 1601 1311867772.0375399590 0.0885740891 0.1280823337 0.2376661599 0.0048746251 0.0119110000 0.0004720000 0.0046780000 0.0000060000 0.0000050000 0.0018180000 40938493 96830484 509673472 3.9043338299 3.9569880962 3.9946868420 1602 1311867772.0696671009 0.0868099630 0.1280565707 0.2376661599 0.0048737280 0.0081590000 0.0005080000 0.0026570000 0.0000010000 0.0000040000 0.0009740000 40942221 96830484 509673472 3.9061815739 3.9570930004 3.9942960739 1603 1311867772.1012299061 0.0873840973 0.1280311979 0.2376661599 0.0048725303 0.0089500000 0.0004490000 0.0033980000 0.0000040000 0.0000040000 0.0012310000 40945837 96830484 509673472 3.9057981968 3.9565167427 3.9943952560 1604 1311867772.1369819641 0.0889144987 0.1280068110 0.2376661599 0.0048715289 0.0092990000 0.0004510000 0.0039020000 0.0000000000 0.0000040000 0.0009710000 40949509 96830484 509673472 3.9041929245 3.9572362900 3.9948744774 1605 1311867772.1690549850 0.0889084712 0.1279824506 0.2376661599 0.0048700377 0.0107920000 0.0004500000 0.0046420000 0.0000030000 0.0000040000 0.0017870000 40953237 96830484 509673472 3.9042861462 3.9576227665 3.9951813221 1606 1311867772.2016880512 0.0844688565 0.1279553562 0.2376661599 0.0048732989 0.0080800000 0.0004490000 0.0027770000 0.0000000000 0.0000040000 0.0009610000 40956965 96830484 509673472 3.9090251923 3.9572391510 3.9945032597 1607 1311867772.2370250225 0.0866525695 0.1279296544 0.2376661599 0.0048723818 0.0101910000 0.0004460000 0.0046150000 0.0000040000 0.0000030000 0.0012220000 40960637 96830484 509673472 3.9070837498 3.9561874866 3.9949703217 1608 1311867772.2710011005 0.0853076205 0.1279031482 0.2376661599 0.0048709824 0.0114680000 0.0005410000 0.0029920000 0.0000010000 0.0000080000 0.0010990000 40964421 96830484 509673472 3.9083805084 3.9570834637 3.9950294495 1609 1311867772.3046050072 0.0860748738 0.1278771518 0.2376661599 0.0048695477 0.0111630000 0.0004630000 0.0046740000 0.0000040000 0.0000030000 0.0017790000 40968149 96830484 509673472 3.9076292515 3.9571142197 3.9952645302 1610 1311867772.3366808891 0.0879589021 0.1278523578 0.2376661599 0.0048683715 0.0099910000 0.0004460000 0.0046010000 0.0000010000 0.0000030000 0.0009600000 40971765 96830484 509673472 3.9058725834 3.9557089806 3.9956722260 1611 1311867772.3689630032 0.0873965025 0.1278272456 0.2376661599 0.0048669553 0.0080190000 0.0004500000 0.0023990000 0.0000030000 0.0000030000 0.0012210000 40975493 96830484 509673472 3.9060382843 3.9565954208 3.9957172871 1612 1311867772.4054839611 0.0876516327 0.1278023227 0.2376661599 0.0048656450 0.0076950000 0.0004490000 0.0024040000 0.0000010000 0.0000030000 0.0009510000 40979333 96830484 509673472 3.9058439732 3.9562275410 3.9959778786 1613 1311867772.4385271072 0.0882599726 0.1277778079 0.2376661599 0.0048644026 0.0097060000 0.0004520000 0.0035190000 0.0000040000 0.0000030000 0.0017630000 40983005 96830484 509673472 3.9051167965 3.9552457333 3.9960589409 1614 1311867772.4697830677 0.0886493027 0.1277535647 0.2376661599 0.0048629956 0.0080620000 0.0004510000 0.0027690000 0.0000010000 0.0000040000 0.0009560000 40986621 96830484 509673472 3.9048275948 3.9539091587 3.9961905479 1615 1311867772.5049729347 0.0894457027 0.1277298447 0.2376661599 0.0048629243 0.0136410000 0.0005440000 0.0048780000 0.0000080000 0.0000070000 0.0013460000 40990405 96830484 509673472 3.9035415649 3.9542937279 3.9963262081 1616 1311867772.5382430553 0.0900226310 0.1277065110 0.2376661599 0.0048616076 0.0104140000 0.0004640000 0.0045560000 0.0000010000 0.0000040000 0.0009610000 40994077 96830484 509673472 3.9025545120 3.9547028542 3.9966316223 1617 1311867772.5713028908 0.0884430483 0.1276822294 0.2376661599 0.0048607698 0.0140300000 0.0005430000 0.0047550000 0.0000080000 0.0000070000 0.0019360000 40997805 96830484 509673472 3.9039611816 3.9545402527 3.9961731434 1618 1311867772.6077790260 0.0888317302 0.1276582179 0.2376661599 0.0048606592 0.0117750000 0.0005460000 0.0030000000 0.0000010000 0.0000110000 0.0010950000 41001533 96830484 509673472 3.9030227661 3.9549384117 3.9966180325 1619 1311867772.6382429600 0.0895791426 0.1276346978 0.2376661599 0.0048596333 0.0108260000 0.0004760000 0.0047090000 0.0000050000 0.0000040000 0.0012000000 41005149 96830484 509673472 3.9019997120 3.9548997879 3.9968104362 1620 1311867772.6695280075 0.0918075964 0.1276125823 0.2376661599 0.0048598036 0.0084680000 0.0004510000 0.0031610000 0.0000010000 0.0000030000 0.0009370000 41008821 96830484 509673472 3.8998434544 3.9528059959 3.9972469807 1621 1311867772.7066609859 0.0904653296 0.1275896661 0.2376661599 0.0048585713 0.0107060000 0.0004480000 0.0046210000 0.0000040000 0.0000030000 0.0017290000 41012605 96830484 509673472 3.9011151791 3.9527902603 3.9971916676 1622 1311867772.7385280132 0.0907559618 0.1275669572 0.2376661599 0.0048571664 0.0117870000 0.0005490000 0.0033840000 0.0000010000 0.0000080000 0.0010560000 41016277 96830484 509673472 3.9005539417 3.9533348083 3.9972867966 1623 1311867772.7712020874 0.0903358385 0.1275440175 0.2376661599 0.0048558763 0.0107130000 0.0004610000 0.0046770000 0.0000040000 0.0000050000 0.0012020000 41020005 96830484 509673472 3.9010195732 3.9528539181 3.9976925850 1624 1311867772.8056819439 0.0888275206 0.1275201773 0.2376661599 0.0048547553 0.0134100000 0.0005480000 0.0049440000 0.0000010000 0.0000080000 0.0010610000 41023789 96830484 509673472 3.9027941227 3.9516305923 3.9976210594 1625 1311867772.8384070396 0.0910420567 0.1274977293 0.2376661599 0.0048556735 0.0112680000 0.0004710000 0.0046960000 0.0000050000 0.0000040000 0.0017310000 41027405 96830484 509673472 3.9002149105 3.9529733658 3.9984807968 1626 1311867772.8747529984 0.0902663097 0.1274748317 0.2376661599 0.0048544450 0.0092410000 0.0004510000 0.0039030000 0.0000000000 0.0000040000 0.0009250000 41031245 96830484 509673472 3.9014005661 3.9521510601 3.9987905025 1627 1311867772.9054989815 0.0902465805 0.1274519502 0.2376661599 0.0048536613 0.0151060000 0.0006790000 0.0050960000 0.0000100000 0.0000100000 0.0014510000 41034861 96830484 509673472 3.9018995762 3.9506576061 3.9988231659 1628 1311867772.9415910244 0.0893634707 0.1274285543 0.2376661599 0.0048533810 0.0106810000 0.0004690000 0.0047260000 0.0000010000 0.0000050000 0.0009480000 41038589 96830484 509673472 3.9027261734 3.9519257545 3.9989185333 1629 1311867772.9716000557 0.0880871266 0.1274044036 0.2376661599 0.0048520242 0.0100380000 0.0004470000 0.0039070000 0.0000040000 0.0000050000 0.0017040000 41042205 96830484 509673472 3.9041976929 3.9523441792 3.9987223148 1630 1311867773.0115981102 0.0889849067 0.1273808334 0.2376661599 0.0048511311 0.0099610000 0.0004490000 0.0046620000 0.0000000000 0.0000040000 0.0009240000 41046045 96830484 509673472 3.9040913582 3.9505627155 3.9989709854 1631 1311867773.0406711102 0.0905793160 0.1273582696 0.2376661599 0.0048518437 0.0098930000 0.0004510000 0.0042980000 0.0000030000 0.0000030000 0.0011830000 41049661 96830484 509673472 3.9024360180 3.9512848854 3.9994845390 1632 1311867773.0706710815 0.0907303020 0.1273358260 0.2376661599 0.0048505210 0.0077840000 0.0004510000 0.0024450000 0.0000000000 0.0000030000 0.0009170000 41053221 96830484 509673472 3.9024379253 3.9516248703 3.9998850822 1633 1311867773.1044468880 0.0912849084 0.1273137495 0.2376661599 0.0048506437 0.0085910000 0.0004510000 0.0024330000 0.0000030000 0.0000030000 0.0016940000 41056949 96830484 509673472 3.9027211666 3.9493410587 4.0000524521 1634 1311867773.1367809772 0.0919885263 0.1272921307 0.2376661599 0.0048495940 0.0085530000 0.0004480000 0.0031850000 0.0000010000 0.0000040000 0.0009160000 41060621 96830484 509673472 3.9028663635 3.9476571083 4.0004615784 1635 1311867773.1702499390 0.0912206471 0.1272700686 0.2376661599 0.0048483096 0.0083890000 0.0004500000 0.0028050000 0.0000040000 0.0000030000 0.0011670000 41064349 96830484 509673472 3.9036831856 3.9483094215 4.0006060600 1636 1311867773.2047750950 0.0913097337 0.1272480879 0.2376661599 0.0048468877 0.0112500000 0.0005860000 0.0026260000 0.0000010000 0.0000080000 0.0010350000 41068077 96830484 509673472 3.9034986496 3.9487540722 4.0007672310 1637 1311867773.2366468906 0.0921808407 0.1272266663 0.2376661599 0.0048458136 0.0095850000 0.0004610000 0.0028500000 0.0000050000 0.0000040000 0.0016980000 41071749 96830484 509673472 3.9030745029 3.9484341145 4.0015401840 1638 1311867773.2714850903 0.0914512649 0.1272048254 0.2376661599 0.0048445899 0.0101320000 0.0004650000 0.0046860000 0.0000000000 0.0000040000 0.0009030000 41075533 96830484 509673472 3.9038619995 3.9488186836 4.0018744469 1639 1311867773.3104391098 0.0905072317 0.1271824352 0.2376661599 0.0048435629 0.0089180000 0.0004480000 0.0031930000 0.0000030000 0.0000030000 0.0011630000 41079373 96830484 509673472 3.9052762985 3.9488162994 4.0022797585 1640 1311867773.3365778923 0.0972119644 0.1271641605 0.2376661599 0.0048445331 0.0083190000 0.0004490000 0.0028330000 0.0000000000 0.0000030000 0.0009010000 41082821 96830484 509673472 3.8988013268 3.9473028183 4.0035309792 1641 1311867773.3720550537 0.0955927446 0.1271449213 0.2376661599 0.0048441697 0.0090180000 0.0004500000 0.0028250000 0.0000030000 0.0000030000 0.0016720000 41086605 96830484 509673472 3.9007666111 3.9470198154 4.0036311150 1642 1311867773.4075679779 0.0944910124 0.1271250347 0.2376661599 0.0048432924 0.0099820000 0.0004490000 0.0045810000 0.0000010000 0.0000040000 0.0008950000 41090333 96830484 509673472 3.9020755291 3.9474134445 4.0036277771 1643 1311867773.4431231022 0.0946899056 0.1271052933 0.2376661599 0.0048438390 0.0103230000 0.0004480000 0.0046960000 0.0000030000 0.0000030000 0.0011640000 41094117 96830484 509673472 3.9019846916 3.9479777813 4.0044407845 1644 1311867773.4752271175 0.0961220413 0.1270864470 0.2376661599 0.0048431485 0.0092600000 0.0004470000 0.0039570000 0.0000010000 0.0000030000 0.0008890000 41097789 96830484 509673472 3.9010324478 3.9466738701 4.0047788620 1645 1311867773.5056390762 0.0956222340 0.1270673198 0.2376661599 0.0048419905 0.0109140000 0.0004500000 0.0046880000 0.0000040000 0.0000040000 0.0016550000 41101405 96830484 509673472 3.9020569324 3.9466047287 4.0053071976 1646 1311867773.5412580967 0.0946368426 0.1270476172 0.2376661599 0.0048409895 0.0093420000 0.0004570000 0.0039770000 0.0000010000 0.0000070000 0.0008940000 41105189 96830484 509673472 3.9031007290 3.9477818012 4.0056023598 1647 1311867773.5752460957 0.0956788361 0.1270285712 0.2376661599 0.0048403786 0.0088240000 0.0004560000 0.0031990000 0.0000040000 0.0000030000 0.0011480000 41108917 96830484 509673472 3.9027214050 3.9458789825 4.0058841705 1648 1311867773.6103789806 0.0945363715 0.1270088551 0.2376661599 0.0048389978 0.0099810000 0.0004530000 0.0045930000 0.0000000000 0.0000040000 0.0008990000 41112701 96830484 509673472 3.9042885303 3.9459035397 4.0060501099 1649 1311867773.6384060383 0.0917928666 0.1269874991 0.2376661599 0.0048397508 0.0089340000 0.0004540000 0.0028420000 0.0000040000 0.0000030000 0.0016410000 41116205 96830484 509673472 3.9070255756 3.9476678371 4.0060429573 1650 1311867773.6767098904 0.0932718888 0.1269670654 0.2376661599 0.0048422835 0.0094010000 0.0004560000 0.0039670000 0.0000010000 0.0000030000 0.0008850000 41120045 96830484 509673472 3.9055750370 3.9475493431 4.0064749718 1651 1311867773.7092239857 0.0953586251 0.1269479204 0.2376661599 0.0048415694 0.0103170000 0.0004540000 0.0046940000 0.0000040000 0.0000030000 0.0011450000 41123717 96830484 509673472 3.9045245647 3.9453189373 4.0071344376 1652 1311867773.7367770672 0.0923081264 0.1269269520 0.2376661599 0.0048411350 0.0093280000 0.0004510000 0.0039680000 0.0000000000 0.0000030000 0.0009000000 41127221 96830484 509673472 3.9068415165 3.9480757713 4.0072660446 1653 1311867773.7767388821 0.0931512788 0.1269065190 0.2376661599 0.0048409937 0.0107610000 0.0004530000 0.0039630000 0.0000040000 0.0000040000 0.0016450000 41131117 96830484 509673472 3.9068610668 3.9469459057 4.0079293251 1654 1311867773.8052179813 0.0932986736 0.1268861999 0.2376661599 0.0048411732 0.0130480000 0.0005960000 0.0049560000 0.0000010000 0.0000070000 0.0010150000 41134677 96830484 509673472 3.9069230556 3.9460461140 4.0081706047 1655 1311867773.8394160271 0.0928570628 0.1268656385 0.2376661599 0.0048406368 0.0105990000 0.0004660000 0.0047320000 0.0000040000 0.0000040000 0.0011480000 41138405 96830484 509673472 3.9076349735 3.9448845387 4.0081491470 1656 1311867773.8739800453 0.0924699008 0.1268448681 0.2376661599 0.0048396496 0.0112590000 0.0005480000 0.0026380000 0.0000010000 0.0000080000 0.0010190000 41142133 96830484 509673472 3.9075486660 3.9453432560 4.0085096359 1657 1311867773.9096889496 0.0910949036 0.1268232930 0.2376661599 0.0048387488 0.0112460000 0.0004680000 0.0047760000 0.0000040000 0.0000030000 0.0016330000 41145917 96830484 509673472 3.9091892242 3.9451336861 4.0085992813 1658 1311867773.9369859695 0.0929329917 0.1268028525 0.2376661599 0.0048378770 0.0100600000 0.0004510000 0.0047220000 0.0000000000 0.0000030000 0.0008870000 41149421 96830484 509673472 3.9072108269 3.9446251392 4.0085978508 1659 1311867773.9740200043 0.0901646018 0.1267807680 0.2376661599 0.0048370882 0.0095280000 0.0004550000 0.0039650000 0.0000040000 0.0000030000 0.0011310000 41153261 96830484 509673472 3.9102301598 3.9449801445 4.0086808205 1660 1311867774.0073120594 0.0893376544 0.1267582119 0.2376661599 0.0048366560 0.0099420000 0.0004570000 0.0045960000 0.0000010000 0.0000040000 0.0008810000 41156933 96830484 509673472 3.9114358425 3.9449284077 4.0087962151 1661 1311867774.0389740467 0.0900710821 0.1267361245 0.2376661599 0.0048379395 0.0107710000 0.0004470000 0.0046950000 0.0000030000 0.0000040000 0.0016270000 41160661 96830484 509673472 3.9110524654 3.9438762665 4.0091004372 1662 1311867774.0735630989 0.0912370905 0.1267147653 0.2376661599 0.0048387022 0.0099230000 0.0004510000 0.0046170000 0.0000000000 0.0000040000 0.0008730000 41164389 96830484 509673472 3.9103298187 3.9439713955 4.0096673965 1663 1311867774.1093399525 0.0894892514 0.1266923807 0.2376661599 0.0048419231 0.0099660000 0.0004550000 0.0043600000 0.0000030000 0.0000030000 0.0011420000 41168173 96830484 509673472 3.9116261005 3.9454290867 4.0095424652 1664 1311867774.1424911022 0.0903417319 0.1266705354 0.2376661599 0.0048422509 0.0121030000 0.0005490000 0.0034350000 0.0000010000 0.0000080000 0.0009930000 41171901 96830484 509673472 3.9113049507 3.9442887306 4.0099358559 1665 1311867774.1754300594 0.0902653188 0.1266486704 0.2376661599 0.0048430095 0.0096690000 0.0004780000 0.0028760000 0.0000050000 0.0000040000 0.0016340000 41175573 96830484 509673472 3.9112465382 3.9446508884 4.0101289749 1666 1311867774.2059481144 0.0883863345 0.1266257038 0.2376661599 0.0048418837 0.0082330000 0.0004540000 0.0028420000 0.0000000000 0.0000040000 0.0008650000 41179245 96830484 509673472 3.9128043652 3.9467144012 4.0104317665 1667 1311867774.2384989262 0.0880212784 0.1266025458 0.2376661599 0.0048407399 0.0105750000 0.0004550000 0.0048090000 0.0000040000 0.0000040000 0.0011750000 41182861 96830484 509673472 3.9132432938 3.9467973709 4.0105895996 1668 1311867774.2744109631 0.0884436890 0.1265796688 0.2376661599 0.0048395391 0.0129710000 0.0005670000 0.0051500000 0.0000010000 0.0000080000 0.0009810000 41186701 96830484 509673472 3.9134533405 3.9454414845 4.0109601021 1669 1311867774.3046739101 0.0881082341 0.1265566182 0.2376661599 0.0048393292 0.0101010000 0.0004800000 0.0033780000 0.0000040000 0.0000040000 0.0016860000 41190317 96830484 509673472 3.9130504131 3.9475591183 4.0112957954 1670 1311867774.3375370502 0.0859532207 0.1265323048 0.2376661599 0.0048383163 0.0104050000 0.0004730000 0.0049380000 0.0000010000 0.0000040000 0.0008880000 41193989 96830484 509673472 3.9149022102 3.9492611885 4.0115056038 1671 1311867774.3727159500 0.0863187462 0.1265082392 0.2376661599 0.0048370006 0.0091240000 0.0004740000 0.0033400000 0.0000030000 0.0000030000 0.0011560000 41197717 96830484 509673472 3.9151561260 3.9480850697 4.0117878914 1672 1311867774.4051818848 0.0865188241 0.1264843221 0.2376661599 0.0048371032 0.0103950000 0.0004730000 0.0049200000 0.0000000000 0.0000030000 0.0008850000 41201445 96830484 509673472 3.9152340889 3.9480469227 4.0124616623 1673 1311867774.4376831055 0.0840467438 0.1264589559 0.2376661599 0.0048357457 0.0100350000 0.0004660000 0.0037450000 0.0000030000 0.0000040000 0.0016690000 41205117 96830484 509673472 3.9170918465 3.9502282143 4.0122385025 1674 1311867774.4740140438 0.0862180442 0.1264349172 0.2376661599 0.0048349362 0.0130200000 0.0005780000 0.0036170000 0.0000020000 0.0000100000 0.0011160000 41208901 96830484 509673472 3.9157812595 3.9479308128 4.0132422447 1675 1311867774.5066258907 0.0867021009 0.1264111961 0.2376661599 0.0048335453 0.0112760000 0.0004980000 0.0048730000 0.0000050000 0.0000040000 0.0011680000 41212629 96830484 509673472 3.9155168533 3.9469265938 4.0134444237 1676 1311867774.5394051075 0.0844197273 0.1263861415 0.2376661599 0.0048326707 0.0080880000 0.0004740000 0.0025760000 0.0000000000 0.0000040000 0.0008730000 41216301 96830484 509673472 3.9170539379 3.9487788677 4.0132241249 1677 1311867774.5727870464 0.0843696073 0.1263610869 0.2376661599 0.0048317893 0.0129110000 0.0005670000 0.0035770000 0.0000070000 0.0000070000 0.0017890000 41219973 96830484 509673472 3.9172911644 3.9488203526 4.0136847496 1678 1311867774.6076970100 0.0848671496 0.1263363587 0.2376661599 0.0048306232 0.0098710000 0.0004840000 0.0029990000 0.0000000000 0.0000050000 0.0011770000 41223757 96830484 509673472 3.9170753956 3.9486706257 4.0142526627 1679 1311867774.6373310089 0.0837511420 0.1263109953 0.2376661599 0.0048296829 0.0130900000 0.0006290000 0.0035850000 0.0000110000 0.0000090000 0.0012580000 41227373 96830484 509673472 3.9179995060 3.9498248100 4.0144414902 1680 1311867774.6731650829 0.0825710818 0.1262849596 0.2376661599 0.0048283178 0.0110930000 0.0005000000 0.0050000000 0.0000000000 0.0000040000 0.0008740000 41231101 96830484 509673472 3.9188165665 3.9507312775 4.0146031380 1681 1311867774.7048470974 0.0845334753 0.1262601223 0.2376661599 0.0048272037 0.0111270000 0.0004690000 0.0049400000 0.0000030000 0.0000030000 0.0016550000 41234829 96830484 509673472 3.9183080196 3.9488706589 4.0157103539 1682 1311867774.7448370457 0.0848580301 0.1262355075 0.2376661599 0.0048287679 0.0100880000 0.0004760000 0.0045590000 0.0000000000 0.0000040000 0.0008630000 41238725 96830484 509673472 3.9178767204 3.9501695633 4.0160417557 1683 1311867774.7731618881 0.0829296932 0.1262097762 0.2376661599 0.0048277651 0.0096020000 0.0004750000 0.0037710000 0.0000040000 0.0000030000 0.0011300000 41242229 96830484 509673472 3.9197800159 3.9510753155 4.0159330368 1684 1311867774.8052101135 0.0837661847 0.1261845722 0.2376661599 0.0048271094 0.0104960000 0.0004770000 0.0049470000 0.0000010000 0.0000030000 0.0008800000 41245957 96830484 509673472 3.9200751781 3.9493904114 4.0170283318 1685 1311867774.8443410397 0.0840721354 0.1261595796 0.2376661599 0.0048256878 0.0112300000 0.0004750000 0.0049470000 0.0000030000 0.0000030000 0.0016090000 41249797 96830484 509673472 3.9199094772 3.9495692253 4.0175333023 1686 1311867774.8735189438 0.0846528113 0.1261349611 0.2376661599 0.0048247318 0.0124720000 0.0005690000 0.0043690000 0.0000020000 0.0000080000 0.0009820000 41253413 96830484 509673472 3.9199213982 3.9490575790 4.0182538033 1687 1311867774.9063620567 0.0846996009 0.1261103996 0.2376661599 0.0048241670 0.0092120000 0.0004870000 0.0030100000 0.0000040000 0.0000030000 0.0011380000 41257085 96830484 509673472 3.9206166267 3.9480638504 4.0185689926 1688 1311867774.9433379173 0.0851191655 0.1260861157 0.2376661599 0.0048228206 0.0127990000 0.0005700000 0.0039980000 0.0000010000 0.0000080000 0.0009690000 41260925 96830484 509673472 3.9205579758 3.9482147694 4.0191617012 1689 1311867774.9730870724 0.0844294578 0.1260614522 0.2376661599 0.0048214532 0.0095030000 0.0004980000 0.0026210000 0.0000050000 0.0000050000 0.0016450000 41264485 96830484 509673472 3.9210896492 3.9490141869 4.0189943314 1690 1311867775.0104990005 0.0855283663 0.1260374681 0.2376661599 0.0048200685 0.0103850000 0.0004780000 0.0049670000 0.0000010000 0.0000040000 0.0008640000 41268381 96830484 509673472 3.9206571579 3.9481899738 4.0196328163 1691 1311867775.0417571068 0.0849047750 0.1260131436 0.2376661599 0.0048186609 0.0083080000 0.0004760000 0.0025770000 0.0000030000 0.0000040000 0.0011340000 41271997 96830484 509673472 3.9209268093 3.9490594864 4.0196800232 1692 1311867775.0737869740 0.0845163018 0.1259886183 0.2376661599 0.0048176024 0.0104220000 0.0004710000 0.0049840000 0.0000000000 0.0000040000 0.0008490000 41275669 96830484 509673472 3.9213209152 3.9499127865 4.0199604034 1693 1311867775.1060369015 0.0845259652 0.1259641276 0.2376661599 0.0048163726 0.0138960000 0.0005680000 0.0052030000 0.0000080000 0.0000070000 0.0017340000 41279341 96830484 509673472 3.9216568470 3.9495983124 4.0202488899 1694 1311867775.1426749229 0.0859938934 0.1259405325 0.2376661599 0.0048151488 0.0109330000 0.0004910000 0.0050080000 0.0000010000 0.0000050000 0.0008750000 41283125 96830484 509673472 3.9211525917 3.9479701519 4.0207910538 1695 1311867775.1733469963 0.0848316923 0.1259162795 0.2376661599 0.0048138178 0.0089260000 0.0004780000 0.0029790000 0.0000040000 0.0000040000 0.0011320000 41286741 96830484 509673472 3.9224700928 3.9484710693 4.0211043358 1696 1311867775.2047309875 0.0851312578 0.1258922317 0.2376661599 0.0048124249 0.0081020000 0.0004730000 0.0025950000 0.0000000000 0.0000040000 0.0008590000 41290469 96830484 509673472 3.9217863083 3.9487047195 4.0207176208 1697 1311867775.2407341003 0.0838680267 0.1258674679 0.2376661599 0.0048119494 0.0088320000 0.0004730000 0.0025920000 0.0000040000 0.0000030000 0.0016070000 41294253 96830484 509673472 3.9224245548 3.9502162933 4.0204653740 1698 1311867775.2726259232 0.0845254585 0.1258431204 0.2376661599 0.0048108330 0.0104050000 0.0004730000 0.0049620000 0.0000000000 0.0000030000 0.0008520000 41297869 96830484 509673472 3.9222745895 3.9497914314 4.0215363503 1699 1311867775.3058989048 0.0849364698 0.1258190435 0.2376661599 0.0048100296 0.0123080000 0.0005700000 0.0027800000 0.0000090000 0.0000100000 0.0012990000 41301597 96830484 509673472 3.9226825237 3.9484672546 4.0217027664 1700 1311867775.3405869007 0.0848893300 0.1257949672 0.2376661599 0.0048112864 0.0134790000 0.0005840000 0.0052190000 0.0000010000 0.0000090000 0.0009710000 41305381 96830484 509673472 3.9221620560 3.9500682354 4.0216593742 1701 1311867775.3728890419 0.0848341510 0.1257708868 0.2376661599 0.0048110497 0.0105170000 0.0004850000 0.0038220000 0.0000040000 0.0000040000 0.0016330000 41309109 96830484 509673472 3.9220151901 3.9504027367 4.0217103958 1702 1311867775.4055740833 0.0869541690 0.1257480802 0.2376661599 0.0048105029 0.0089070000 0.0004670000 0.0033880000 0.0000000000 0.0000030000 0.0008470000 41312781 96830484 509673472 3.9218306541 3.9479346275 4.0235528946 1703 1311867775.4408710003 0.0862565413 0.1257248908 0.2376661599 0.0048108177 0.0109490000 0.0004710000 0.0049720000 0.0000030000 0.0000030000 0.0011250000 41316565 96830484 509673472 3.9219315052 3.9493603706 4.0228939056 1704 1311867775.4725620747 0.0855990872 0.1257013428 0.2376661599 0.0048099990 0.0105220000 0.0004710000 0.0049710000 0.0000000000 0.0000030000 0.0008470000 41320181 96830484 509673472 3.9224760532 3.9498229027 4.0232396126 1705 1311867775.5057229996 0.0859657526 0.1256780375 0.2376661599 0.0048086965 0.0105010000 0.0004710000 0.0041830000 0.0000040000 0.0000030000 0.0015890000 41323965 96830484 509673472 3.9230737686 3.9491393566 4.0242433548 1706 1311867775.5413000584 0.0853550062 0.1256544015 0.2376661599 0.0048086364 0.0084960000 0.0004680000 0.0029870000 0.0000000000 0.0000030000 0.0008460000 41327749 96830484 509673472 3.9241149426 3.9487597942 4.0244545937 1707 1311867775.5736858845 0.0852458552 0.1256307292 0.2376661599 0.0048076973 0.0109170000 0.0004680000 0.0049940000 0.0000030000 0.0000040000 0.0011220000 41331365 96830484 509673472 3.9237768650 3.9497773647 4.0244445801 1708 1311867775.6086819172 0.0855842829 0.1256072828 0.2376661599 0.0048064086 0.0106110000 0.0004630000 0.0049790000 0.0000000000 0.0000040000 0.0008430000 41335093 96830484 509673472 3.9243853092 3.9492311478 4.0252685547 1709 1311867775.6414420605 0.0853813067 0.1255837451 0.2376661599 0.0048051352 0.0092960000 0.0004690000 0.0029770000 0.0000040000 0.0000030000 0.0016020000 41338877 96830484 509673472 3.9254312515 3.9486668110 4.0255708694 1710 1311867775.6726739407 0.0862781256 0.1255607594 0.2376661599 0.0048050676 0.0092920000 0.0004660000 0.0037900000 0.0000010000 0.0000040000 0.0008420000 41342437 96830484 509673472 3.9234521389 3.9499430656 4.0254373550 1711 1311867775.7051100731 0.0864641145 0.1255379092 0.2376661599 0.0048037546 0.0095550000 0.0004710000 0.0037980000 0.0000040000 0.0000040000 0.0011070000 41346165 96830484 509673472 3.9233679771 3.9499778748 4.0255651474 1712 1311867775.7416241169 0.0872513950 0.1255155456 0.2376661599 0.0048024319 0.0140970000 0.0005660000 0.0052620000 0.0000010000 0.0000080000 0.0009630000 41349949 96830484 509673472 3.9233458042 3.9492735863 4.0264358521 1713 1311867775.7742578983 0.0873605683 0.1254932718 0.2376661599 0.0048021269 0.0130860000 0.0005660000 0.0032050000 0.0000100000 0.0000100000 0.0017720000 41353621 96830484 509673472 3.9234387875 3.9495406151 4.0269951820 1714 1311867775.8062939644 0.0869028866 0.1254707570 0.2376661599 0.0048019242 0.0102770000 0.0004840000 0.0042160000 0.0000010000 0.0000040000 0.0008560000 41357293 96830484 509673472 3.9234151840 3.9508616924 4.0269613266 1715 1311867775.8408269882 0.0879993662 0.1254489078 0.2376661599 0.0048007506 0.0095340000 0.0004700000 0.0037670000 0.0000040000 0.0000040000 0.0011270000 41361077 96830484 509673472 3.9232647419 3.9498622417 4.0275816917 1716 1311867775.8729701042 0.0890814885 0.1254277146 0.2376661599 0.0047998326 0.0100890000 0.0004690000 0.0045940000 0.0000000000 0.0000030000 0.0008470000 41364693 96830484 509673472 3.9223606586 3.9498918056 4.0283718109 1717 1311867775.9066479206 0.0893708542 0.1254067147 0.2376661599 0.0047984751 0.0100450000 0.0004690000 0.0037830000 0.0000030000 0.0000040000 0.0016230000 41368477 96830484 509673472 3.9219563007 3.9499554634 4.0283002853 1718 1311867775.9435749054 0.0893340185 0.1253857178 0.2376661599 0.0047972788 0.0104500000 0.0004660000 0.0050010000 0.0000010000 0.0000040000 0.0008360000 41372205 96830484 509673472 3.9223895073 3.9499461651 4.0287852287 1719 1311867775.9730579853 0.0902913883 0.1253653023 0.2376661599 0.0047959790 0.0103340000 0.0004710000 0.0045790000 0.0000030000 0.0000030000 0.0011340000 41375821 96830484 509673472 3.9214408398 3.9502716064 4.0291385651 1720 1311867776.0135231018 0.0912542567 0.1253454703 0.2376661599 0.0047951769 0.0101500000 0.0004760000 0.0045880000 0.0000000000 0.0000030000 0.0008440000 41379717 96830484 509673472 3.9220385551 3.9483394623 4.0299224854 1721 1311867776.0423479080 0.0909845531 0.1253255046 0.2376661599 0.0047942438 0.0093640000 0.0004750000 0.0029970000 0.0000040000 0.0000030000 0.0016110000 41383221 96830484 509673472 3.9221699238 3.9487826824 4.0298233032 1722 1311867776.0782909393 0.0910464227 0.1253055980 0.2376661599 0.0047928972 0.0139760000 0.0005690000 0.0052440000 0.0000010000 0.0000080000 0.0009420000 41387061 96830484 509673472 3.9219856262 3.9492278099 4.0297560692 1723 1311867776.1090068817 0.0908029974 0.1252855733 0.2376661599 0.0047916922 0.0090360000 0.0004850000 0.0026260000 0.0000050000 0.0000040000 0.0011220000 41390733 96830484 509673472 3.9220714569 3.9499897957 4.0297765732 1724 1311867776.1410119534 0.0919013321 0.1252662089 0.2376661599 0.0047904215 0.0104940000 0.0004760000 0.0049850000 0.0000010000 0.0000030000 0.0008460000 41394405 96830484 509673472 3.9215774536 3.9493324757 4.0306196213 1725 1311867776.1773319244 0.0922380388 0.1252470621 0.2376661599 0.0047891468 0.0113220000 0.0004740000 0.0049750000 0.0000030000 0.0000030000 0.0016070000 41398189 96830484 509673472 3.9214003086 3.9491176605 4.0307359695 1726 1311867776.2094259262 0.0909616724 0.1252271981 0.2376661599 0.0047879456 0.0178210000 0.0005870000 0.0052930000 0.0000010000 0.0000100000 0.0010770000 41401861 96830484 509673472 3.9224288464 3.9503288269 4.0305323601 1727 1311867776.2407069206 0.0917197317 0.1252077959 0.2376661599 0.0047867441 0.0206740000 0.0007020000 0.0033880000 0.0000160000 0.0000150000 0.0015700000 41405533 96830484 509673472 3.9216735363 3.9502193928 4.0308017731 1728 1311867776.2753469944 0.0924863666 0.1251888599 0.2376661599 0.0047854794 0.0100380000 0.0005070000 0.0026820000 0.0000010000 0.0000060000 0.0009150000 41409317 96830484 509673472 3.9209170341 3.9503326416 4.0311212540 1729 1311867776.3120670319 0.0933865085 0.1251704664 0.2376661599 0.0047841281 0.0091860000 0.0004900000 0.0026040000 0.0000050000 0.0000040000 0.0016320000 41413045 96830484 509673472 3.9204499722 3.9498205185 4.0313777924 1730 1311867776.3407590389 0.0928051919 0.1251517582 0.2376661599 0.0047829371 0.0081930000 0.0004670000 0.0025990000 0.0000000000 0.0000030000 0.0008520000 41416717 96830484 509673472 3.9208219051 3.9505236149 4.0314106941 1731 1311867776.3730750084 0.0922504961 0.1251327511 0.2376661599 0.0047815886 0.0087970000 0.0004710000 0.0029880000 0.0000030000 0.0000030000 0.0011190000 41420389 96830484 509673472 3.9219183922 3.9503748417 4.0318198204 1732 1311867776.4097070694 0.0933856890 0.1251144214 0.2376661599 0.0047808144 0.0116830000 0.0005680000 0.0027790000 0.0000010000 0.0000080000 0.0009580000 41424229 96830484 509673472 3.9209928513 3.9501044750 4.0323061943 1733 1311867776.4422268867 0.0935496464 0.1250962074 0.2376661599 0.0047799884 0.0105280000 0.0004850000 0.0038240000 0.0000040000 0.0000040000 0.0015970000 41427901 96830484 509673472 3.9205029011 3.9508676529 4.0323147774 1734 1311867776.4727520943 0.0930768624 0.1250777418 0.2376661599 0.0047787645 0.0094480000 0.0004710000 0.0037880000 0.0000010000 0.0000040000 0.0008420000 41431517 96830484 509673472 3.9212961197 3.9508273602 4.0325078964 1735 1311867776.5105879307 0.0925117433 0.1250589718 0.2376661599 0.0047777449 0.0084570000 0.0004720000 0.0025960000 0.0000040000 0.0000040000 0.0011270000 41435357 96830484 509673472 3.9217836857 3.9515419006 4.0327510834 1736 1311867776.5415630341 0.0919671580 0.1250399097 0.2376661599 0.0047765325 0.0089780000 0.0004710000 0.0033890000 0.0000000000 0.0000030000 0.0008510000 41438973 96830484 509673472 3.9227182865 3.9515740871 4.0331516266 1737 1311867776.5743160248 0.0925929397 0.1250212298 0.2376661599 0.0047753726 0.0097440000 0.0004700000 0.0033960000 0.0000030000 0.0000030000 0.0016330000 41442701 96830484 509673472 3.9226598740 3.9511954784 4.0340099335 1738 1311867776.6094930172 0.0926477239 0.1250026029 0.2376661599 0.0047740811 0.0089490000 0.0004700000 0.0033830000 0.0000000000 0.0000040000 0.0008500000 41446485 96830484 509673472 3.9222500324 3.9519071579 4.0341768265 1739 1311867776.6413109303 0.0920554399 0.1249836569 0.2376661599 0.0047728949 0.0099960000 0.0004720000 0.0041700000 0.0000040000 0.0000040000 0.0011370000 41450157 96830484 509673472 3.9233207703 3.9518914223 4.0345902443 1740 1311867776.6763460636 0.0922262892 0.1249648308 0.2376661599 0.0047719556 0.0082290000 0.0004690000 0.0026010000 0.0000000000 0.0000030000 0.0008630000 41453997 96830484 509673472 3.9232542515 3.9523637295 4.0354127884 1741 1311867776.7134280205 0.0921977833 0.1249460100 0.2376661599 0.0047708200 0.0113490000 0.0004710000 0.0049880000 0.0000040000 0.0000030000 0.0016120000 41457781 96830484 509673472 3.9229261875 3.9532816410 4.0356750488 1742 1311867776.7423970699 0.0926106200 0.1249274478 0.2376661599 0.0047695313 0.0106210000 0.0004700000 0.0049840000 0.0000000000 0.0000040000 0.0008440000 41461341 96830484 509673472 3.9228446484 3.9531786442 4.0366287231 1743 1311867776.7739920616 0.0927483290 0.1249089859 0.2376661599 0.0047686519 0.0088630000 0.0004690000 0.0029750000 0.0000040000 0.0000030000 0.0011060000 41465125 96830484 509673472 3.9233162403 3.9528791904 4.0373234749 1744 1311867776.8117430210 0.0925491974 0.1248904310 0.2376661599 0.0047683021 0.0135740000 0.0005650000 0.0050730000 0.0000010000 0.0000080000 0.0009630000 41469021 96830484 509673472 3.9243812561 3.9528059959 4.0383434296 1745 1311867776.8449618816 0.0944977254 0.1248730139 0.2376661599 0.0047683308 0.0116360000 0.0004860000 0.0049850000 0.0000050000 0.0000040000 0.0016320000 41472805 96830484 509673472 3.9231112003 3.9521193504 4.0393571854 1746 1311867776.8748989105 0.0929424167 0.1248547261 0.2376661599 0.0047681974 0.0105700000 0.0004720000 0.0049660000 0.0000000000 0.0000030000 0.0008560000 41476421 96830484 509673472 3.9257671833 3.9518995285 4.0398726463 1747 1311867776.9104089737 0.0929488987 0.1248364629 0.2376661599 0.0047674697 0.0098170000 0.0004740000 0.0037700000 0.0000030000 0.0000030000 0.0011210000 41480205 96830484 509673472 3.9256675243 3.9523804188 4.0402393341 1748 1311867776.9465129375 0.0916125253 0.1248174560 0.2376661599 0.0047665227 0.0106640000 0.0004690000 0.0049860000 0.0000010000 0.0000030000 0.0008520000 41484045 96830484 509673472 3.9268751144 3.9531691074 4.0402965546 1749 1311867776.9780058861 0.0955137759 0.1248007015 0.2376661599 0.0047681078 0.0109520000 0.0004710000 0.0045720000 0.0000030000 0.0000040000 0.0016350000 41487717 96830484 509673472 3.9243528843 3.9510223866 4.0425314903 1750 1311867777.0103049278 0.0953577757 0.1247838770 0.2376661599 0.0047678838 0.0085830000 0.0004720000 0.0029770000 0.0000000000 0.0000030000 0.0008520000 41491501 96830484 509673472 3.9252374172 3.9508059025 4.0433058739 1751 1311867777.0430829525 0.0948782638 0.1247667978 0.2376661599 0.0047665725 0.0137060000 0.0005670000 0.0034380000 0.0000110000 0.0000100000 0.0012420000 41495229 96830484 509673472 3.9248337746 3.9515166283 4.0426621437 1752 1311867777.0763421059 0.0935851038 0.1247490000 0.2376661599 0.0047657158 0.0111710000 0.0005340000 0.0050130000 0.0000000000 0.0000040000 0.0008590000 41498957 96830484 509673472 3.9264354706 3.9517059326 4.0427093506 1753 1311867777.1087210178 0.0937870890 0.1247313378 0.2376661599 0.0047644542 0.0128240000 0.0005680000 0.0027740000 0.0000100000 0.0000100000 0.0017860000 41502685 96830484 509673472 3.9267613888 3.9513003826 4.0433764458 1754 1311867777.1435770988 0.0919136852 0.1247126276 0.2376661599 0.0047637757 0.0100490000 0.0004960000 0.0038210000 0.0000000000 0.0000050000 0.0008580000 41506525 96830484 509673472 3.9290194511 3.9518620968 4.0434446335 1755 1311867777.1783010960 0.0917822868 0.1246938639 0.2376661599 0.0047624220 0.0109040000 0.0004870000 0.0049600000 0.0000040000 0.0000040000 0.0011130000 41510309 96830484 509673472 3.9292504787 3.9522986412 4.0437045097 1756 1311867777.2115299702 0.0922406688 0.1246753826 0.2376661599 0.0047611651 0.0143330000 0.0005770000 0.0052720000 0.0000010000 0.0000080000 0.0009830000 41514149 96830484 509673472 3.9292008877 3.9520161152 4.0444974899 1757 1311867777.2420690060 0.0911133736 0.1246562807 0.2376661599 0.0047602552 0.0112590000 0.0004820000 0.0045950000 0.0000040000 0.0000040000 0.0016170000 41517709 96830484 509673472 3.9316616058 3.9516432285 4.0450811386 1758 1311867777.2766950130 0.0909449607 0.1246371047 0.2376661599 0.0047594036 0.0099230000 0.0004670000 0.0041730000 0.0000010000 0.0000040000 0.0008560000 41521493 96830484 509673472 3.9316284657 3.9519472122 4.0451316833 1759 1311867777.3093490601 0.0924368203 0.1246187987 0.2376661599 0.0047602768 0.0108150000 0.0004710000 0.0049650000 0.0000040000 0.0000040000 0.0011230000 41525221 96830484 509673472 3.9304914474 3.9514343739 4.0460839272 1760 1311867777.3419890404 0.0924049020 0.1246004954 0.2376661599 0.0047590233 0.0099100000 0.0004750000 0.0041690000 0.0000000000 0.0000040000 0.0008450000 41528949 96830484 509673472 3.9312663078 3.9506034851 4.0466375351 1761 1311867777.3780329227 0.0927048549 0.1245823831 0.2376661599 0.0047586732 0.0102350000 0.0004730000 0.0037560000 0.0000040000 0.0000030000 0.0016270000 41532845 96830484 509673472 3.9303495884 3.9509170055 4.0466976166 1762 1311867777.4108960629 0.0925383568 0.1245641970 0.2376661599 0.0047573372 0.0103320000 0.0004820000 0.0045710000 0.0000000000 0.0000030000 0.0008440000 41536573 96830484 509673472 3.9309735298 3.9507639408 4.0474901199 1763 1311867777.4411139488 0.0926831961 0.1245461136 0.2376661599 0.0047565143 0.0095130000 0.0004760000 0.0029700000 0.0000040000 0.0000030000 0.0011300000 41540245 96830484 509673472 3.9309554100 3.9502544403 4.0475540161 1764 1311867777.4770240784 0.0929344669 0.1245281932 0.2376661599 0.0047553934 0.0089000000 0.0004730000 0.0029750000 0.0000000000 0.0000040000 0.0008520000 41544141 96830484 509673472 3.9317686558 3.9496226311 4.0489487648 1765 1311867777.5098700523 0.0903973505 0.1245088556 0.2376661599 0.0047553273 0.0103780000 0.0004730000 0.0037780000 0.0000040000 0.0000030000 0.0016130000 41547869 96830484 509673472 3.9340600967 3.9505686760 4.0482811928 1766 1311867777.5421240330 0.0902083069 0.1244894328 0.2376661599 0.0047544443 0.0107120000 0.0004740000 0.0049630000 0.0000000000 0.0000040000 0.0008460000 41551541 96830484 509673472 3.9335064888 3.9513614178 4.0485248566 1767 1311867777.5777161121 0.0907315388 0.1244703282 0.2376661599 0.0047532330 0.0094850000 0.0004730000 0.0033780000 0.0000030000 0.0000030000 0.0011130000 41555437 96830484 509673472 3.9338779449 3.9506382942 4.0498695374 1768 1311867777.6086440086 0.0894596279 0.1244505258 0.2376661599 0.0047519511 0.0107450000 0.0004720000 0.0049600000 0.0000010000 0.0000040000 0.0008480000 41559109 96830484 509673472 3.9351251125 3.9510757923 4.0499119759 1769 1311867777.6407959461 0.0922221318 0.1244323073 0.2376661599 0.0047528091 0.0107170000 0.0004720000 0.0041710000 0.0000040000 0.0000030000 0.0016280000 41562893 96830484 509673472 3.9328076839 3.9498014450 4.0518102646 1770 1311867777.6765840054 0.0891850293 0.1244123936 0.2376661599 0.0047533024 0.0096020000 0.0004690000 0.0037750000 0.0000010000 0.0000040000 0.0008470000 41566733 96830484 509673472 3.9357056618 3.9507632256 4.0512976646 1771 1311867777.7086570263 0.0879540294 0.1243918073 0.2376661599 0.0047528507 0.0128380000 0.0005660000 0.0035860000 0.0000080000 0.0000070000 0.0012460000 41570405 96830484 509673472 3.9375534058 3.9507300854 4.0515213013 1772 1311867777.7411170006 0.0913893282 0.1243731829 0.2376661599 0.0047541939 0.0112980000 0.0004880000 0.0050180000 0.0000000000 0.0000040000 0.0008560000 41574133 96830484 509673472 3.9344251156 3.9493086338 4.0532283783 1773 1311867777.7797420025 0.0906722173 0.1243541750 0.2376661599 0.0047529012 0.0091780000 0.0004910000 0.0025800000 0.0000040000 0.0000040000 0.0016260000 41578085 96830484 509673472 3.9352235794 3.9493927956 4.0533833504 1774 1311867777.8103909492 0.0881895944 0.1243337891 0.2376661599 0.0047554181 0.0107910000 0.0004700000 0.0049750000 0.0000010000 0.0000040000 0.0008600000 41581813 96830484 509673472 3.9392988682 3.9495842457 4.0537242889 1775 1311867777.8421120644 0.0890229419 0.1243138957 0.2376661599 0.0047553799 0.0138500000 0.0005640000 0.0052220000 0.0000080000 0.0000080000 0.0011740000 41585485 96830484 509673472 3.9368994236 3.9505398273 4.0538139343 1776 1311867777.8771729469 0.0905129164 0.1242948636 0.2376661599 0.0047545452 0.0128780000 0.0005650000 0.0039840000 0.0000010000 0.0000070000 0.0009670000 41589325 96830484 509673472 3.9355175495 3.9499287605 4.0546917915 1777 1311867777.9091188908 0.0916118547 0.1242764714 0.2376661599 0.0047534930 0.0103560000 0.0004890000 0.0034110000 0.0000040000 0.0000040000 0.0016300000 41593053 96830484 509673472 3.9343698025 3.9493811131 4.0554881096 1778 1311867777.9424149990 0.0891364887 0.1242567076 0.2376661599 0.0047539716 0.0108080000 0.0004740000 0.0049920000 0.0000000000 0.0000030000 0.0008500000 41596781 96830484 509673472 3.9383461475 3.9497756958 4.0558972359 1779 1311867777.9770610332 0.0911738575 0.1242381113 0.2376661599 0.0047588644 0.0106930000 0.0004730000 0.0045650000 0.0000040000 0.0000040000 0.0011380000 41600677 96830484 509673472 3.9339787960 3.9505710602 4.0560269356 1780 1311867778.0100560188 0.0936597586 0.1242209324 0.2376661599 0.0047593692 0.0107700000 0.0004760000 0.0049770000 0.0000000000 0.0000030000 0.0008510000 41604405 96830484 509673472 3.9343390465 3.9480090141 4.0587034225 1781 1311867778.0413420200 0.0967383832 0.1242055015 0.2376661599 0.0047592948 0.0111940000 0.0004730000 0.0045630000 0.0000040000 0.0000030000 0.0016220000 41608077 96830484 509673472 3.9327619076 3.9457247257 4.0606966019 1782 1311867778.0773630142 0.0974254608 0.1241904734 0.2376661599 0.0047644641 0.0107840000 0.0004770000 0.0049620000 0.0000010000 0.0000040000 0.0008590000 41611917 96830484 509673472 3.9296696186 3.9472293854 4.0601868629 1783 1311867778.1094930172 0.1012547165 0.1241776098 0.2376661599 0.0047641122 0.0110860000 0.0004750000 0.0049620000 0.0000040000 0.0000030000 0.0011220000 41615645 96830484 509673472 3.9276285172 3.9447658062 4.0623230934 1784 1311867778.1418550014 0.1009047702 0.1241645645 0.2376661599 0.0047628855 0.0108220000 0.0004710000 0.0049650000 0.0000000000 0.0000030000 0.0008480000 41619429 96830484 509673472 3.9286987782 3.9446833134 4.0628323555 1785 1311867778.1826310158 0.0960851833 0.1241488337 0.2376661599 0.0047649950 0.0115590000 0.0004800000 0.0049510000 0.0000030000 0.0000030000 0.0016110000 41623325 96830484 509673472 3.9322834015 3.9468047619 4.0602960587 1786 1311867778.2094058990 0.0988292620 0.1241346570 0.2376661599 0.0047638279 0.0109860000 0.0004760000 0.0049490000 0.0000010000 0.0000040000 0.0008400000 41626941 96830484 509673472 3.9317688942 3.9444403648 4.0624179840 1787 1311867778.2432699203 0.0950603932 0.1241183872 0.2376661599 0.0047647326 0.0111680000 0.0004780000 0.0049670000 0.0000040000 0.0000040000 0.0011220000 41630725 96830484 509673472 3.9349122047 3.9458825588 4.0606036186 1788 1311867778.2796919346 0.0992428437 0.1241044747 0.2376661599 0.0047648976 0.0149300000 0.0006000000 0.0052590000 0.0000010000 0.0000080000 0.0009610000 41634565 96830484 509673472 3.9312078953 3.9438986778 4.0627274513 1789 1311867778.3125588894 0.1027125865 0.1240925172 0.2376661599 0.0047666331 0.0146000000 0.0005780000 0.0052080000 0.0000070000 0.0000080000 0.0017740000 41638293 96830484 509673472 3.9281668663 3.9420499802 4.0643167496 1790 1311867778.3414309025 0.0963738263 0.1240770319 0.2376661599 0.0047677280 0.0111740000 0.0004830000 0.0050170000 0.0000000000 0.0000040000 0.0008650000 41641965 96830484 509673472 3.9331009388 3.9449934959 4.0611133575 1791 1311867778.3782539368 0.0989596248 0.1240630077 0.2376661599 0.0047670200 0.0104260000 0.0004770000 0.0041910000 0.0000030000 0.0000030000 0.0011300000 41645861 96830484 509673472 3.9305562973 3.9435338974 4.0618567467 1792 1311867778.4093298912 0.0956785530 0.1240471681 0.2376661599 0.0047730909 0.0108000000 0.0004730000 0.0049930000 0.0000010000 0.0000040000 0.0008530000 41649533 96830484 509673472 3.9382746220 3.9430224895 4.0627741814 1793 1311867778.4445381165 0.0992696732 0.1240333491 0.2376661599 0.0047789265 0.0112270000 0.0004750000 0.0045890000 0.0000030000 0.0000030000 0.0016230000 41653373 96830484 509673472 3.9318909645 3.9427392483 4.0630807877 1794 1311867778.4812810421 0.0962057635 0.1240178376 0.2376661599 0.0047838559 0.0091900000 0.0004740000 0.0033910000 0.0000010000 0.0000040000 0.0008410000 41657269 96830484 509673472 3.9366331100 3.9431047440 4.0623044968 1795 1311867778.5097670555 0.0966509581 0.1240025915 0.2376661599 0.0047828155 0.0095630000 0.0004740000 0.0034120000 0.0000030000 0.0000040000 0.0011220000 41660885 96830484 509673472 3.9338686466 3.9433872700 4.0612659454 1796 1311867778.5484840870 0.0953792036 0.1239866542 0.2376661599 0.0047816628 0.0108090000 0.0004720000 0.0050220000 0.0000000000 0.0000030000 0.0008380000 41664781 96830484 509673472 3.9341793060 3.9441220760 4.0604124069 1797 1311867778.5830690861 0.0941643566 0.1239700586 0.2376661599 0.0047814245 0.0116370000 0.0004720000 0.0050220000 0.0000040000 0.0000030000 0.0016100000 41668621 96830484 509673472 3.9363057613 3.9439401627 4.0601673126 1798 1311867778.6150701046 0.0969940126 0.1239550552 0.2376661599 0.0047807089 0.0108730000 0.0004720000 0.0050330000 0.0000010000 0.0000040000 0.0008440000 41672349 96830484 509673472 3.9337761402 3.9423148632 4.0612330437 1799 1311867778.6452109814 0.0999516621 0.1239417126 0.2376661599 0.0047854248 0.0120570000 0.0004750000 0.0051910000 0.0000030000 0.0000040000 0.0011190000 41676021 96830484 509673472 3.9290564060 3.9419510365 4.0619568825 1800 1311867778.6781129837 0.0984663516 0.1239275596 0.2376661599 0.0047841173 0.0091190000 0.0004750000 0.0031490000 0.0000010000 0.0000040000 0.0008370000 41679749 96830484 509673472 3.9300301075 3.9427123070 4.0611524582 1801 1311867778.7125270367 0.0994587317 0.1239139734 0.2376661599 0.0047832678 0.0096980000 0.0004740000 0.0029990000 0.0000030000 0.0000040000 0.0015970000 41683533 96830484 509673472 3.9298675060 3.9416172504 4.0617866516 1802 1311867778.7490179539 0.0982713923 0.1238997433 0.2376661599 0.0047826170 0.0109390000 0.0004730000 0.0050210000 0.0000000000 0.0000040000 0.0008330000 41687429 96830484 509673472 3.9307496548 3.9422476292 4.0613064766 1803 1311867778.7815420628 0.0982601345 0.1238855228 0.2376661599 0.0047822960 0.0112340000 0.0004860000 0.0050020000 0.0000040000 0.0000030000 0.0011170000 41691213 96830484 509673472 3.9289362431 3.9431686401 4.0606045723 1804 1311867778.8090119362 0.0989781618 0.1238717160 0.2376661599 0.0047812682 0.0107920000 0.0004720000 0.0049040000 0.0000000000 0.0000030000 0.0008360000 41694773 96830484 509673472 3.9286906719 3.9420974255 4.0607128143 1805 1311867778.8465809822 0.1020087823 0.1238596036 0.2376661599 0.0047812115 0.0105110000 0.0004740000 0.0038260000 0.0000040000 0.0000040000 0.0015880000 41698669 96830484 509673472 3.9256634712 3.9406032562 4.0618295670 1806 1311867778.8808300495 0.1007058173 0.1238467831 0.2376661599 0.0047816933 0.0093810000 0.0004880000 0.0034120000 0.0000010000 0.0000040000 0.0008270000 41702453 96830484 509673472 3.9273900986 3.9408733845 4.0614562035 1807 1311867778.9117860794 0.0998188779 0.1238334860 0.2376661599 0.0047812003 0.0092520000 0.0004770000 0.0030090000 0.0000030000 0.0000040000 0.0011030000 41706125 96830484 509673472 3.9274191856 3.9411990643 4.0603885651 1808 1311867778.9482150078 0.1025395989 0.1238217084 0.2376661599 0.0047801713 0.0109550000 0.0004740000 0.0050480000 0.0000000000 0.0000040000 0.0008190000 41710021 96830484 509673472 3.9241483212 3.9398376942 4.0608172417 1809 1311867778.9777760506 0.1023720503 0.1238098512 0.2376661599 0.0047789831 0.0117510000 0.0004780000 0.0050300000 0.0000040000 0.0000030000 0.0015880000 41713693 96830484 509673472 3.9229772091 3.9402935505 4.0599198341 1810 1311867779.0105700493 0.1012871191 0.1237974077 0.2376661599 0.0047780791 0.0109660000 0.0004740000 0.0050340000 0.0000000000 0.0000030000 0.0008290000 41717421 96830484 509673472 3.9226992130 3.9415400028 4.0587568283 1811 1311867779.0471200943 0.1023264006 0.1237855518 0.2376661599 0.0047769574 0.0112560000 0.0004760000 0.0050380000 0.0000040000 0.0000030000 0.0010930000 41721317 96830484 509673472 3.9212324619 3.9411025047 4.0585179329 1812 1311867779.0780360699 0.1032422557 0.1237742145 0.2376661599 0.0047757250 0.0110730000 0.0004750000 0.0050310000 0.0000010000 0.0000030000 0.0008300000 41724933 96830484 509673472 3.9197342396 3.9409015179 4.0581564903 1813 1311867779.1124050617 0.1033095196 0.1237629267 0.2376661599 0.0047758935 0.0117510000 0.0004740000 0.0050300000 0.0000030000 0.0000030000 0.0015850000 41728717 96830484 509673472 3.9183411598 3.9418921471 4.0573439598 1814 1311867779.1473538876 0.1016732752 0.1237507494 0.2376661599 0.0047754285 0.0109790000 0.0004740000 0.0050270000 0.0000000000 0.0000030000 0.0008290000 41732389 96830484 509673472 3.9205181599 3.9421918392 4.0567054749 1815 1311867779.1777000427 0.1041367278 0.1237399428 0.2376661599 0.0047751201 0.0108360000 0.0004690000 0.0046310000 0.0000030000 0.0000030000 0.0011000000 41736005 96830484 509673472 3.9184079170 3.9410173893 4.0574007034 1816 1311867779.2123599052 0.1031295657 0.1237285934 0.2376661599 0.0047742901 0.0109400000 0.0004710000 0.0050270000 0.0000000000 0.0000030000 0.0008220000 41739733 96830484 509673472 3.9190735817 3.9415173531 4.0565972328 1817 1311867779.2447109222 0.1035413593 0.1237174832 0.2376661599 0.0047737468 0.0101180000 0.0004730000 0.0034310000 0.0000040000 0.0000030000 0.0015650000 41743461 96830484 509673472 3.9182796478 3.9416179657 4.0561995506 1818 1311867779.2782809734 0.1034812704 0.1237063522 0.2376661599 0.0047740550 0.0132390000 0.0005270000 0.0052040000 0.0000010000 0.0000060000 0.0008640000 41747133 96830484 509673472 3.9189438820 3.9412620068 4.0562515259 1819 1311867779.3104579449 0.1018566266 0.1236943403 0.2376661599 0.0047735599 0.0115090000 0.0004850000 0.0050750000 0.0000040000 0.0000030000 0.0011060000 41750861 96830484 509673472 3.9201259613 3.9419953823 4.0549860001 1820 1311867779.3468949795 0.1001432315 0.1236814001 0.2376661599 0.0047732886 0.0110240000 0.0004760000 0.0050480000 0.0000010000 0.0000030000 0.0008350000 41754701 96830484 509673472 3.9210250378 3.9435670376 4.0537633896 1821 1311867779.3772010803 0.1015812010 0.1236692638 0.2376661599 0.0047724808 0.0150720000 0.0005690000 0.0053090000 0.0000070000 0.0000080000 0.0017240000 41758317 96830484 509673472 3.9202013016 3.9422686100 4.0538992882 1822 1311867779.4088799953 0.1017142311 0.1236572138 0.2376661599 0.0047712100 0.0142700000 0.0005690000 0.0053030000 0.0000010000 0.0000080000 0.0009320000 41761989 96830484 509673472 3.9202270508 3.9419198036 4.0535430908 1823 1311867779.4446020126 0.1025497988 0.1236456354 0.2376661599 0.0047699891 0.0123480000 0.0004880000 0.0050780000 0.0000040000 0.0000040000 0.0011090000 41765773 96830484 509673472 3.9190185070 3.9417991638 4.0529980659 1824 1311867779.4768970013 0.1040621251 0.1236348989 0.2376661599 0.0047694022 0.0105210000 0.0005160000 0.0042670000 0.0000000000 0.0000030000 0.0008720000 41769501 96830484 509673472 3.9186024666 3.9399201870 4.0534763336 1825 1311867779.5098230839 0.1045787781 0.1236244572 0.2376661599 0.0047683250 0.0119510000 0.0004790000 0.0050530000 0.0000040000 0.0000030000 0.0015860000 41773173 96830484 509673472 3.9183678627 3.9391708374 4.0533151627 1826 1311867779.5450038910 0.1019218415 0.1236125718 0.2376661599 0.0047677068 0.0085520000 0.0004750000 0.0026190000 0.0000010000 0.0000030000 0.0008260000 41776957 96830484 509673472 3.9197876453 3.9407951832 4.0514898300 1827 1311867779.5777029991 0.1037120819 0.1236016794 0.2376661599 0.0047667432 0.0145330000 0.0005710000 0.0048930000 0.0000070000 0.0000080000 0.0011970000 41780629 96830484 509673472 3.9182066917 3.9397158623 4.0516514778 1828 1311867779.6092689037 0.1019692197 0.1235898454 0.2376661599 0.0047677074 0.0113770000 0.0004840000 0.0051060000 0.0000010000 0.0000040000 0.0008330000 41784301 96830484 509673472 3.9200284481 3.9399530888 4.0506939888 1829 1311867779.6482150555 0.1015750170 0.1235778089 0.2376661599 0.0047669722 0.0137030000 0.0005680000 0.0040540000 0.0000080000 0.0000080000 0.0017290000 41788141 96830484 509673472 3.9189772606 3.9412827492 4.0495376587 1830 1311867779.6796278954 0.0980410874 0.1235638544 0.2376661599 0.0047674029 0.0112960000 0.0004850000 0.0051130000 0.0000010000 0.0000050000 0.0008330000 41791813 96830484 509673472 3.9218666553 3.9431111813 4.0478715897 1831 1311867779.7129859924 0.0979634225 0.1235498727 0.2376661599 0.0047664270 0.0113070000 0.0004750000 0.0050620000 0.0000040000 0.0000040000 0.0010890000 41795485 96830484 509673472 3.9220423698 3.9430620670 4.0474987030 1832 1311867779.7461729050 0.0976121873 0.1235357146 0.2376661599 0.0047667597 0.0146850000 0.0005710000 0.0053310000 0.0000010000 0.0000080000 0.0009330000 41799269 96830484 509673472 3.9235019684 3.9420294762 4.0475373268 1833 1311867779.7771708965 0.0945548117 0.1235199040 0.2376661599 0.0047674695 0.0121680000 0.0004860000 0.0050960000 0.0000040000 0.0000040000 0.0015830000 41802885 96830484 509673472 3.9260678291 3.9431924820 4.0459828377 1834 1311867779.8130059242 0.0938391984 0.1235037204 0.2376661599 0.0047670803 0.0089500000 0.0004740000 0.0030280000 0.0000000000 0.0000030000 0.0008260000 41806613 96830484 509673472 3.9271025658 3.9430925846 4.0455365181 1835 1311867779.8454499245 0.0919906646 0.1234865471 0.2376661599 0.0047681162 0.0113000000 0.0004740000 0.0050610000 0.0000030000 0.0000030000 0.0011010000 41810341 96830484 509673472 3.9299001694 3.9424555302 4.0448231697 1836 1311867779.8771400452 0.0906469002 0.1234686605 0.2376661599 0.0047668653 0.0109440000 0.0004860000 0.0050520000 0.0000010000 0.0000040000 0.0008300000 41813957 96830484 509673472 3.9301633835 3.9434638023 4.0434589386 1837 1311867779.9128279686 0.0901229680 0.1234505083 0.2376661599 0.0047665307 0.0117990000 0.0004740000 0.0050460000 0.0000040000 0.0000030000 0.0015830000 41817797 96830484 509673472 3.9309558868 3.9432342052 4.0428261757 1838 1311867779.9448599815 0.0881132707 0.1234312824 0.2376661599 0.0047664555 0.0140350000 0.0005760000 0.0052810000 0.0000010000 0.0000090000 0.0009660000 41821469 96830484 509673472 3.9329156876 3.9437386990 4.0418429375 1839 1311867779.9769320488 0.0883048922 0.1234121816 0.2376661599 0.0047655568 0.0116520000 0.0004760000 0.0050540000 0.0000040000 0.0000030000 0.0010990000 41825141 96830484 509673472 3.9328103065 3.9434626102 4.0416460037 1840 1311867780.0130739212 0.0858432204 0.1233917636 0.2376661599 0.0047652613 0.0109840000 0.0004720000 0.0050170000 0.0000010000 0.0000040000 0.0008440000 41828925 96830484 509673472 3.9331002235 3.9455749989 4.0392537117 1841 1311867780.0448310375 0.0839487761 0.1233703389 0.2376661599 0.0047648344 0.0117910000 0.0004740000 0.0050040000 0.0000040000 0.0000030000 0.0015830000 41832597 96830484 509673472 3.9336221218 3.9473609924 4.0379152298 1842 1311867780.0771219730 0.0837999359 0.1233488566 0.2376661599 0.0047641608 0.0147060000 0.0005980000 0.0052700000 0.0000010000 0.0000080000 0.0009550000 41836269 96830484 509673472 3.9340131283 3.9471416473 4.0377488136 1843 1311867780.1143870354 0.0837395191 0.1233273648 0.2376661599 0.0047630651 0.0116930000 0.0004860000 0.0050560000 0.0000040000 0.0000040000 0.0011120000 41840109 96830484 509673472 3.9334840775 3.9471013546 4.0367674828 1844 1311867780.1448268890 0.0817414969 0.1233048128 0.2376661599 0.0047672653 0.0139960000 0.0005690000 0.0052370000 0.0000010000 0.0000070000 0.0009430000 41843725 96830484 509673472 3.9348506927 3.9470624924 4.0354313850 1845 1311867780.1773400307 0.0800499246 0.1232813684 0.2376661599 0.0047676297 0.0119820000 0.0004870000 0.0050230000 0.0000040000 0.0000030000 0.0016210000 41847397 96830484 509673472 3.9354987144 3.9483244419 4.0336232185 1846 1311867780.2158250809 0.0793904066 0.1232575922 0.2376661599 0.0047685301 0.0103500000 0.0004740000 0.0041960000 0.0000010000 0.0000040000 0.0008530000 41851293 96830484 509673472 3.9353032112 3.9488034248 4.0333213806 1847 1311867780.2454960346 0.0804010928 0.1232343889 0.2376661599 0.0047703196 0.0112940000 0.0004720000 0.0049970000 0.0000030000 0.0000030000 0.0011120000 41854909 96830484 509673472 3.9341142178 3.9483959675 4.0323233604 1848 1311867780.2815570831 0.0806620866 0.1232113519 0.2376661599 0.0047690650 0.0102690000 0.0004720000 0.0041860000 0.0000010000 0.0000040000 0.0008550000 41858693 96830484 509673472 3.9341313839 3.9478909969 4.0326752663 1849 1311867780.3140099049 0.0787745938 0.1231873191 0.2376661599 0.0047698830 0.0117530000 0.0004720000 0.0049840000 0.0000040000 0.0000030000 0.0016130000 41862365 96830484 509673472 3.9341177940 3.9485480785 4.0295038223 1850 1311867780.3464050293 0.0786152557 0.1231632260 0.2376661599 0.0047687248 0.0110740000 0.0004730000 0.0049760000 0.0000010000 0.0000040000 0.0008590000 41866037 96830484 509673472 3.9332456589 3.9487428665 4.0279150009 1851 1311867780.3772649765 0.0784813091 0.1231390867 0.2376661599 0.0047682160 0.0112350000 0.0004740000 0.0049750000 0.0000040000 0.0000030000 0.0011270000 41869653 96830484 509673472 3.9331815243 3.9475705624 4.0269799232 1852 1311867780.4132668972 0.0794974491 0.1231155221 0.2376661599 0.0047677259 0.0112210000 0.0004750000 0.0049750000 0.0000000000 0.0000030000 0.0008530000 41873493 96830484 509673472 3.9325470924 3.9470419884 4.0268216133 1853 1311867780.4451050758 0.0791338459 0.1230917867 0.2376661599 0.0047676020 0.0146100000 0.0005700000 0.0052150000 0.0000070000 0.0000080000 0.0016860000 41877165 96830484 509673472 3.9312539101 3.9487214088 4.0256304741 1854 1311867780.4791510105 0.0803706273 0.1230687440 0.2376661599 0.0047670246 0.0113130000 0.0004890000 0.0049880000 0.0000010000 0.0000040000 0.0008790000 41880893 96830484 509673472 3.9270529747 3.9501936436 4.0237598419 1855 1311867780.5153009892 0.0818945765 0.1230465477 0.2376661599 0.0047674330 0.0113410000 0.0004760000 0.0049620000 0.0000030000 0.0000030000 0.0011400000 41884733 96830484 509673472 3.9259958267 3.9496154785 4.0235514641 1856 1311867780.5455119610 0.0802771524 0.1230235039 0.2376661599 0.0047731757 0.0112550000 0.0004760000 0.0049450000 0.0000000000 0.0000030000 0.0008660000 41888349 96830484 509673472 3.9275891781 3.9487950802 4.0231170654 1857 1311867780.5798339844 0.0807266831 0.1230007269 0.2376661599 0.0047727445 0.0117460000 0.0004710000 0.0049290000 0.0000040000 0.0000040000 0.0016210000 41892077 96830484 509673472 3.9270906448 3.9484264851 4.0227394104 1858 1311867780.6136929989 0.0835749730 0.1229795074 0.2376661599 0.0047772913 0.0103390000 0.0004700000 0.0041710000 0.0000000000 0.0000040000 0.0008690000 41895749 96830484 509673472 3.9244425297 3.9479634762 4.0222392082 1859 1311867780.6459660530 0.0862889886 0.1229597707 0.2376661599 0.0047766938 0.0108510000 0.0004710000 0.0045470000 0.0000040000 0.0000030000 0.0011420000 41899477 96830484 509673472 3.9209904671 3.9477391243 4.0218462944 1860 1311867780.6793959141 0.0859077945 0.1229398503 0.2376661599 0.0047765957 0.0151290000 0.0005650000 0.0052420000 0.0000010000 0.0000100000 0.0009910000 41903205 96830484 509673472 3.9201302528 3.9498095512 4.0212683678 1861 1311867780.7156999111 0.0874591321 0.1229207849 0.2376661599 0.0047759538 0.0119670000 0.0004790000 0.0045770000 0.0000040000 0.0000040000 0.0016710000 41906989 96830484 509673472 3.9182424545 3.9497416019 4.0211215019 1862 1311867780.7469029427 0.0869807452 0.1229014831 0.2376661599 0.0047753383 0.0111650000 0.0004750000 0.0049460000 0.0000000000 0.0000030000 0.0008770000 41910605 96830484 509673472 3.9193096161 3.9484019279 4.0208992958 1863 1311867780.7774689198 0.0883494765 0.1228829366 0.2376661599 0.0047741144 0.0137490000 0.0005710000 0.0047540000 0.0000070000 0.0000070000 0.0012480000 41914277 96830484 509673472 3.9180161953 3.9474432468 4.0205874443 1864 1311867780.8164570332 0.0898030251 0.1228651899 0.2376661599 0.0047731933 0.0114250000 0.0004880000 0.0049590000 0.0000000000 0.0000040000 0.0008850000 41918173 96830484 509673472 3.9160583019 3.9476678371 4.0202307701 1865 1311867780.8460350037 0.0899849460 0.1228475597 0.2376661599 0.0047723285 0.0115700000 0.0004790000 0.0045500000 0.0000040000 0.0000040000 0.0016510000 41921733 96830484 509673472 3.9160273075 3.9462075233 4.0198960304 1866 1311867780.8791809082 0.0924437121 0.1228312661 0.2376661599 0.0047710828 0.0147440000 0.0006000000 0.0051940000 0.0000000000 0.0000080000 0.0009980000 41925461 96830484 509673472 3.9144015312 3.9437634945 4.0200085640 1867 1311867780.9152340889 0.0936681852 0.1228156459 0.2376661599 0.0047702678 0.0099020000 0.0004910000 0.0029890000 0.0000050000 0.0000040000 0.0011690000 41929245 96830484 509673472 3.9128730297 3.9439408779 4.0197501183 1868 1311867780.9457290173 0.0926181674 0.1227994802 0.2376661599 0.0047710997 0.0095750000 0.0004720000 0.0033510000 0.0000000000 0.0000040000 0.0008890000 41932861 96830484 509673472 3.9142978191 3.9430396557 4.0192656517 1869 1311867780.9838399887 0.0946526825 0.1227844204 0.2376661599 0.0047702401 0.0128880000 0.0004750000 0.0054860000 0.0000040000 0.0000040000 0.0016800000 41936701 96830484 509673472 3.9124691486 3.9417665005 4.0190854073 1870 1311867781.0137300491 0.0937233120 0.1227688797 0.2376661599 0.0047693074 0.0112420000 0.0004750000 0.0050380000 0.0000000000 0.0000030000 0.0008920000 41940317 96830484 509673472 3.9131309986 3.9424042702 4.0186653137 1871 1311867781.0463659763 0.0949550718 0.1227540139 0.2376661599 0.0047682446 0.0090410000 0.0004740000 0.0025560000 0.0000040000 0.0000030000 0.0011770000 41943989 96830484 509673472 3.9115805626 3.9422495365 4.0181879997 1872 1311867781.0821859837 0.0951583236 0.1227392726 0.2376661599 0.0047672775 0.0111290000 0.0004720000 0.0049060000 0.0000010000 0.0000040000 0.0008970000 41947773 96830484 509673472 3.9118719101 3.9404900074 4.0173816681 1873 1311867781.1157560349 0.0953417718 0.1227246450 0.2376661599 0.0047661884 0.0118630000 0.0004750000 0.0049190000 0.0000040000 0.0000040000 0.0016540000 41951501 96830484 509673472 3.9114940166 3.9404339790 4.0170488358 1874 1311867781.1459479332 0.0945583507 0.1227096150 0.2376661599 0.0047669460 0.0112020000 0.0004710000 0.0048940000 0.0000010000 0.0000040000 0.0009000000 41955117 96830484 509673472 3.9122152328 3.9394013882 4.0162711143 1875 1311867781.1839950085 0.0960423574 0.1226953925 0.2376661599 0.0047660918 0.0113340000 0.0004740000 0.0049080000 0.0000040000 0.0000030000 0.0011790000 41958957 96830484 509673472 3.9105138779 3.9390819073 4.0157213211 1876 1311867781.2133030891 0.0947632417 0.1226805032 0.2376661599 0.0047651419 0.0111220000 0.0004740000 0.0048940000 0.0000000000 0.0000040000 0.0009090000 41962517 96830484 509673472 3.9122292995 3.9382679462 4.0151162148 1877 1311867781.2467529774 0.0957749709 0.1226661689 0.2376661599 0.0047645151 0.0102790000 0.0004720000 0.0033310000 0.0000030000 0.0000030000 0.0016910000 41966189 96830484 509673472 3.9105637074 3.9396829605 4.0145339966 1878 1311867781.2855589390 0.0979711190 0.1226530193 0.2376661599 0.0047638243 0.0113040000 0.0004730000 0.0049050000 0.0000000000 0.0000030000 0.0009130000 41970085 96830484 509673472 3.9085187912 3.9390139580 4.0140314102 1879 1311867781.3133049011 0.0975667238 0.1226396684 0.2376661599 0.0047628381 0.0115050000 0.0004740000 0.0049030000 0.0000040000 0.0000040000 0.0011850000 41973589 96830484 509673472 3.9088928699 3.9397504330 4.0133943558 1880 1311867781.3465669155 0.0978317484 0.1226264727 0.2376661599 0.0047620891 0.0092900000 0.0004710000 0.0029400000 0.0000000000 0.0000030000 0.0009320000 41977373 96830484 509673472 3.9082412720 3.9403843880 4.0128192902 1881 1311867781.3809239864 0.0982487798 0.1226135127 0.2376661599 0.0047608293 0.0108090000 0.0004740000 0.0037280000 0.0000030000 0.0000030000 0.0017330000 41981101 96830484 509673472 3.9078221321 3.9399454594 4.0120964050 1882 1311867781.4144830704 0.0962332338 0.1225994956 0.2376661599 0.0047601384 0.0112220000 0.0004700000 0.0048560000 0.0000000000 0.0000030000 0.0009340000 41984773 96830484 509673472 3.9092934132 3.9415607452 4.0114254951 1883 1311867781.4457330704 0.0978244469 0.1225863383 0.2376661599 0.0047602752 0.0113520000 0.0004700000 0.0048870000 0.0000030000 0.0000030000 0.0012020000 41988445 96830484 509673472 3.9071240425 3.9408152103 4.0111889839 1884 1311867781.4812419415 0.0983542204 0.1225734763 0.2376661599 0.0047597419 0.0092950000 0.0004720000 0.0029320000 0.0000010000 0.0000040000 0.0009390000 41992229 96830484 509673472 3.9071862698 3.9405050278 4.0105876923 1885 1311867781.5131030083 0.0977105126 0.1225602864 0.2376661599 0.0047591515 0.0192880000 0.0007100000 0.0045620000 0.0000150000 0.0000160000 0.0024200000 41995845 96830484 509673472 3.9077017307 3.9410653114 4.0104227066 1886 1311867781.5451910496 0.0985680297 0.1225475652 0.2376661599 0.0047596361 0.0114170000 0.0004890000 0.0041520000 0.0000010000 0.0000060000 0.0009600000 41999573 96830484 509673472 3.9060359001 3.9425284863 4.0101733208 1887 1311867781.5813419819 0.0954363719 0.1225331978 0.2376661599 0.0047635896 0.0094660000 0.0004730000 0.0029260000 0.0000040000 0.0000030000 0.0012350000 42003357 96830484 509673472 3.9088699818 3.9426314831 4.0092477798 1888 1311867781.6135890484 0.0980823636 0.1225202471 0.2376661599 0.0047631111 0.0098760000 0.0004660000 0.0035710000 0.0000000000 0.0000030000 0.0009480000 42006973 96830484 509673472 3.9064590931 3.9413619041 4.0090050697 1889 1311867781.6467020512 0.0972149149 0.1225068510 0.2376661599 0.0047619519 0.0119760000 0.0004710000 0.0048440000 0.0000040000 0.0000040000 0.0017810000 42010701 96830484 509673472 3.9072146416 3.9416532516 4.0085191727 1890 1311867781.6832339764 0.0973965302 0.1224935651 0.2376661599 0.0047614877 0.0110630000 0.0004690000 0.0048430000 0.0000000000 0.0000040000 0.0009540000 42014485 96830484 509673472 3.9065651894 3.9423303604 4.0079474449 1891 1311867781.7131800652 0.0972350910 0.1224802079 0.2376661599 0.0047603250 0.0114360000 0.0004750000 0.0048200000 0.0000040000 0.0000030000 0.0012370000 42018101 96830484 509673472 3.9065260887 3.9422984123 4.0074677467 1892 1311867781.7453010082 0.0980717018 0.1224673070 0.2376661599 0.0047595191 0.0113270000 0.0004690000 0.0048170000 0.0000000000 0.0000040000 0.0009690000 42021829 96830484 509673472 3.9057445526 3.9415662289 4.0075311661 1893 1311867781.7820630074 0.0961473137 0.1224534031 0.2376661599 0.0047618678 0.0146090000 0.0006230000 0.0031160000 0.0000100000 0.0000090000 0.0018720000 42025613 96830484 509673472 3.9075591564 3.9413356781 4.0067920685 1894 1311867781.8145859241 0.0947517157 0.1224387771 0.2376661599 0.0047643585 0.0116290000 0.0005300000 0.0048580000 0.0000010000 0.0000040000 0.0009300000 42029285 96830484 509673472 3.9085671902 3.9411680698 4.0062699318 1895 1311867781.8453550339 0.0954892561 0.1224245557 0.2376661599 0.0047640786 0.0143900000 0.0005640000 0.0050430000 0.0000080000 0.0000080000 0.0013090000 42032957 96830484 509673472 3.9072515965 3.9424235821 4.0061526299 1896 1311867781.8827259541 0.0945356116 0.1224098464 0.2376661599 0.0047658379 0.0113270000 0.0004820000 0.0048180000 0.0000000000 0.0000050000 0.0009350000 42036741 96830484 509673472 3.9077787399 3.9422688484 4.0052976608 1897 1311867781.9138391018 0.0964123532 0.1223961419 0.2376661599 0.0047656375 0.0103700000 0.0004690000 0.0032590000 0.0000030000 0.0000030000 0.0017260000 42040413 96830484 509673472 3.9064855576 3.9399197102 4.0049629211 1898 1311867781.9470670223 0.0957515538 0.1223821036 0.2376661599 0.0047647087 0.0110850000 0.0004730000 0.0047770000 0.0000010000 0.0000040000 0.0009460000 42044141 96830484 509673472 3.9070866108 3.9392471313 4.0039691925 1899 1311867781.9856810570 0.0969601348 0.1223687166 0.2376661599 0.0047658669 0.0113140000 0.0004710000 0.0047730000 0.0000040000 0.0000030000 0.0012630000 42047925 96830484 509673472 3.9046928883 3.9413111210 4.0039587021 1900 1311867782.0139210224 0.0965726897 0.1223551397 0.2376661599 0.0047662960 0.0134090000 0.0005830000 0.0038310000 0.0000010000 0.0000080000 0.0011240000 42051485 96830484 509673472 3.9052937031 3.9397258759 4.0030188560 1901 1311867782.0464830399 0.0977163240 0.1223421787 0.2376661599 0.0047664158 0.0121160000 0.0004810000 0.0047920000 0.0000040000 0.0000040000 0.0018330000 42055213 96830484 509673472 3.9037194252 3.9403648376 4.0025901794 1902 1311867782.0839829445 0.0996585637 0.1223302526 0.2376661599 0.0047698589 0.0142270000 0.0005670000 0.0049600000 0.0000010000 0.0000080000 0.0011120000 42058941 96830484 509673472 3.9010429382 3.9424157143 4.0025944710 1903 1311867782.1135599613 0.0976516083 0.1223172843 0.2376661599 0.0047691105 0.0094430000 0.0004770000 0.0024690000 0.0000040000 0.0000030000 0.0012730000 42062557 96830484 509673472 3.9026582241 3.9437088966 4.0023107529 1904 1311867782.1472380161 0.0988587812 0.1223049636 0.2376661599 0.0047679909 0.0111430000 0.0004710000 0.0047180000 0.0000010000 0.0000040000 0.0009950000 42066285 96830484 509673472 3.9015195370 3.9430537224 4.0023465157 1905 1311867782.1819090843 0.0991645902 0.1222928165 0.2376661599 0.0047673694 0.0104830000 0.0004720000 0.0031910000 0.0000040000 0.0000030000 0.0018490000 42070069 96830484 509673472 3.9008567333 3.9445159435 4.0023937225 1906 1311867782.2144429684 0.0985919163 0.1222803816 0.2376661599 0.0047664755 0.0111080000 0.0004690000 0.0047020000 0.0000010000 0.0000030000 0.0009700000 42073741 96830484 509673472 3.9018673897 3.9444062710 4.0023069382 1907 1311867782.2494089603 0.0979018286 0.1222675978 0.2376661599 0.0047677296 0.0130710000 0.0005660000 0.0026350000 0.0000100000 0.0000090000 0.0013680000 42077469 96830484 509673472 3.9024531841 3.9436969757 4.0017833710 1908 1311867782.2860810757 0.0994620100 0.1222556452 0.2376661599 0.0047666587 0.0114320000 0.0004820000 0.0046170000 0.0000000000 0.0000040000 0.0009840000 42081309 96830484 509673472 3.9009878635 3.9436805248 4.0019626617 1909 1311867782.3144040108 0.0987568051 0.1222433357 0.2376661599 0.0047657968 0.0119620000 0.0004620000 0.0046890000 0.0000030000 0.0000030000 0.0017880000 42084813 96830484 509673472 3.9014804363 3.9446344376 4.0014595985 1910 1311867782.3526129723 0.0995923057 0.1222314765 0.2376661599 0.0047655796 0.0088470000 0.0004630000 0.0024410000 0.0000000000 0.0000040000 0.0009720000 42088709 96830484 509673472 3.9009423256 3.9435670376 4.0012674332 1911 1311867782.3825540543 0.1009862870 0.1222203592 0.2376661599 0.0047645515 0.0142200000 0.0005570000 0.0049250000 0.0000080000 0.0000080000 0.0013580000 42092269 96830484 509673472 3.8994503021 3.9436583519 4.0012931824 1912 1311867782.4147620201 0.1006164104 0.1222090601 0.2376661599 0.0047639019 0.0137810000 0.0005460000 0.0045230000 0.0000010000 0.0000080000 0.0011060000 42095829 96830484 509673472 3.8998329639 3.9449369907 4.0013623238 1913 1311867782.4514210224 0.0994442478 0.1221971600 0.2376661599 0.0047632803 0.0135120000 0.0005790000 0.0030080000 0.0000080000 0.0000070000 0.0019820000 42099613 96830484 509673472 3.9011464119 3.9441611767 4.0008454323 1914 1311867782.4812099934 0.0986888036 0.1221848777 0.2376661599 0.0047620639 0.0094310000 0.0004690000 0.0024510000 0.0000000000 0.0000050000 0.0009820000 42103285 96830484 509673472 3.9020791054 3.9443352222 4.0006117821 1915 1311867782.5149359703 0.1006033495 0.1221736080 0.2376661599 0.0047625597 0.0114090000 0.0004550000 0.0046760000 0.0000030000 0.0000040000 0.0012620000 42106957 96830484 509673472 3.9001960754 3.9452898502 4.0011243820 1916 1311867782.5516130924 0.0997659042 0.1221619129 0.2376661599 0.0047625743 0.0097420000 0.0004590000 0.0031810000 0.0000010000 0.0000040000 0.0009850000 42110741 96830484 509673472 3.9013581276 3.9445488453 4.0009670258 1917 1311867782.5828690529 0.1001730114 0.1221504425 0.2376661599 0.0047616202 0.0097160000 0.0004550000 0.0024260000 0.0000040000 0.0000040000 0.0018370000 42114357 96830484 509673472 3.9008266926 3.9453680515 4.0007514954 1918 1311867782.6142859459 0.1005797535 0.1221391960 0.2376661599 0.0047605828 0.0109800000 0.0004550000 0.0046620000 0.0000000000 0.0000040000 0.0009900000 42118085 96830484 509673472 3.9005162716 3.9458856583 4.0007734299 1919 1311867782.6501080990 0.1007470191 0.1221280485 0.2376661599 0.0047601640 0.0100270000 0.0004610000 0.0031750000 0.0000030000 0.0000030000 0.0012530000 42121869 96830484 509673472 3.9007461071 3.9446964264 4.0005540848 1920 1311867782.6862080097 0.1018207222 0.1221174717 0.2376661599 0.0047608197 0.0111340000 0.0004560000 0.0046690000 0.0000000000 0.0000030000 0.0009890000 42125653 96830484 509673472 3.9006116390 3.9444911480 4.0003662109 1921 1311867782.7131700516 0.1001375988 0.1221060298 0.2376661599 0.0047599640 0.0119830000 0.0004550000 0.0046830000 0.0000040000 0.0000030000 0.0018290000 42129157 96830484 509673472 3.9021036625 3.9457178116 3.9999330044 1922 1311867782.7489991188 0.1018970534 0.1220955153 0.2376661599 0.0047602690 0.0107440000 0.0004530000 0.0043000000 0.0000000000 0.0000030000 0.0009900000 42132941 96830484 509673472 3.9003639221 3.9447073936 3.9996533394 1923 1311867782.7844688892 0.1012458056 0.1220846730 0.2376661599 0.0047593653 0.0101270000 0.0004560000 0.0034390000 0.0000040000 0.0000030000 0.0012620000 42136725 96830484 509673472 3.9010515213 3.9440829754 3.9990406036 1924 1311867782.8159070015 0.1018157452 0.1220741382 0.2376661599 0.0047589807 0.0099600000 0.0004570000 0.0035260000 0.0000010000 0.0000030000 0.0009910000 42140397 96830484 509673472 3.8995542526 3.9455130100 3.9993405342 1925 1311867782.8522670269 0.1007553264 0.1220630635 0.2376661599 0.0047587643 0.0104400000 0.0004580000 0.0031740000 0.0000040000 0.0000030000 0.0018290000 42144125 96830484 509673472 3.9013128281 3.9438073635 3.9981391430 1926 1311867782.8824830055 0.1024437621 0.1220528770 0.2376661599 0.0047577313 0.0111820000 0.0004520000 0.0046540000 0.0000010000 0.0000040000 0.0009860000 42147797 96830484 509673472 3.8997879028 3.9423043728 3.9978330135 1927 1311867782.9145979881 0.1012850031 0.1220420996 0.2376661599 0.0047577789 0.0138470000 0.0005100000 0.0048280000 0.0000070000 0.0000060000 0.0013320000 42151469 96830484 509673472 3.9005730152 3.9443602562 3.9974102974 1928 1311867782.9517209530 0.1027329117 0.1220320845 0.2376661599 0.0047566947 0.0098130000 0.0004600000 0.0031660000 0.0000010000 0.0000040000 0.0010030000 42155309 96830484 509673472 3.8990435600 3.9440445900 3.9970812798 1929 1311867782.9812240601 0.1012621075 0.1220213173 0.2376661599 0.0047566112 0.0118490000 0.0004490000 0.0045040000 0.0000040000 0.0000030000 0.0018470000 42158869 96830484 509673472 3.9006183147 3.9421873093 3.9959840775 1930 1311867783.0143089294 0.1030183733 0.1220114712 0.2376661599 0.0047577173 0.0110130000 0.0004530000 0.0046290000 0.0000010000 0.0000060000 0.0009950000 42162597 96830484 509673472 3.8983428478 3.9439637661 3.9960432053 1931 1311867783.0528459549 0.1025818661 0.1220014093 0.2376661599 0.0047568635 0.0095710000 0.0004560000 0.0027710000 0.0000040000 0.0000040000 0.0012780000 42166381 96830484 509673472 3.8985712528 3.9442319870 3.9953887463 1932 1311867783.0829811096 0.1029664800 0.1219915568 0.2376661599 0.0047568491 0.0089670000 0.0004530000 0.0023900000 0.0000010000 0.0000040000 0.0010060000 42170053 96830484 509673472 3.8984184265 3.9425334930 3.9948446751 1933 1311867783.1137030125 0.1030943915 0.1219817807 0.2376661599 0.0047561124 0.0105510000 0.0004520000 0.0031360000 0.0000040000 0.0000040000 0.0018620000 42173669 96830484 509673472 3.8982498646 3.9432823658 3.9949576855 1934 1311867783.1539480686 0.1035095081 0.1219722294 0.2376661599 0.0047549866 0.0098570000 0.0004500000 0.0033880000 0.0000000000 0.0000040000 0.0010080000 42177565 96830484 509673472 3.8976397514 3.9435586929 3.9946486950 1935 1311867783.1857850552 0.1045526713 0.1219632270 0.2376661599 0.0047539731 0.0113370000 0.0004510000 0.0045950000 0.0000030000 0.0000030000 0.0012950000 42181237 96830484 509673472 3.8963987827 3.9434645176 3.9943294525 1936 1311867783.2169439793 0.1057142317 0.1219548340 0.2376661599 0.0047531622 0.0110510000 0.0004490000 0.0045810000 0.0000010000 0.0000040000 0.0010110000 42184853 96830484 509673472 3.8949294090 3.9437921047 3.9945766926 1937 1311867783.2548489571 0.1052485183 0.1219462091 0.2376661599 0.0047519783 0.0119270000 0.0004490000 0.0045810000 0.0000040000 0.0000040000 0.0018650000 42188749 96830484 509673472 3.8952195644 3.9443855286 3.9942171574 1938 1311867783.2816879749 0.1048584953 0.1219373919 0.2376661599 0.0047512486 0.0097890000 0.0004500000 0.0031250000 0.0000000000 0.0000040000 0.0010230000 42192309 96830484 509673472 3.8956222534 3.9436986446 3.9939262867 1939 1311867783.3132228851 0.1065635532 0.1219294632 0.2376661599 0.0047500986 0.0113930000 0.0004490000 0.0045870000 0.0000040000 0.0000040000 0.0012960000 42195869 96830484 509673472 3.8940689564 3.9429237843 3.9941656590 1940 1311867783.3503270149 0.1103856862 0.1219235128 0.2376661599 0.0047509394 0.0148140000 0.0005730000 0.0048040000 0.0000010000 0.0000080000 0.0011610000 42199709 96830484 509673472 3.8899946213 3.9438557625 3.9947404861 1941 1311867783.3855919838 0.1125358045 0.1219186763 0.2376661599 0.0047506622 0.0123150000 0.0005130000 0.0046870000 0.0000040000 0.0000040000 0.0018890000 42203493 96830484 509673472 3.8878688812 3.9430122375 3.9943299294 1942 1311867783.4198501110 0.1105281860 0.1219128109 0.2376661599 0.0047506841 0.0092090000 0.0004450000 0.0027470000 0.0000010000 0.0000030000 0.0010190000 42207221 96830484 509673472 3.8899495602 3.9425601959 3.9940307140 1943 1311867783.4503099918 0.1103892997 0.1219068801 0.2376661599 0.0047498864 0.0103480000 0.0004640000 0.0034710000 0.0000030000 0.0000030000 0.0013010000 42210837 96830484 509673472 3.8895726204 3.9440865517 3.9936785698 1944 1311867783.4863688946 0.1106698811 0.1219010998 0.2376661599 0.0047496515 0.0111030000 0.0004410000 0.0045730000 0.0000010000 0.0000040000 0.0010250000 42214621 96830484 509673472 3.8893873692 3.9430837631 3.9935245514 1945 1311867783.5186200142 0.1101686209 0.1218950677 0.2376661599 0.0047488710 0.0099870000 0.0004470000 0.0023740000 0.0000040000 0.0000030000 0.0018940000 42218237 96830484 509673472 3.8899993896 3.9424624443 3.9933729172 1946 1311867783.5488419533 0.1117970496 0.1218898785 0.2376661599 0.0047491274 0.0093580000 0.0004410000 0.0027240000 0.0000010000 0.0000040000 0.0010280000 42221853 96830484 509673472 3.8879625797 3.9437305927 3.9936406612 1947 1311867783.5823969841 0.1094825938 0.1218835060 0.2376661599 0.0047495210 0.0095480000 0.0004400000 0.0027300000 0.0000030000 0.0000030000 0.0013020000 42225637 96830484 509673472 3.8902735710 3.9429397583 3.9925534725 1948 1311867783.6168529987 0.1110681742 0.1218779540 0.2376661599 0.0047488771 0.0096010000 0.0004400000 0.0030910000 0.0000010000 0.0000040000 0.0010290000 42229309 96830484 509673472 3.8887040615 3.9427623749 3.9927256107 1949 1311867783.6515829563 0.1097164452 0.1218717141 0.2376661599 0.0047476960 0.0108360000 0.0004370000 0.0034630000 0.0000030000 0.0000030000 0.0018930000 42233037 96830484 509673472 3.8901300430 3.9432702065 3.9925522804 1950 1311867783.6816630363 0.1106010973 0.1218659343 0.2376661599 0.0047472651 0.0110230000 0.0004370000 0.0045760000 0.0000000000 0.0000040000 0.0010210000 42236709 96830484 509673472 3.8891992569 3.9434893131 3.9927222729 1951 1311867783.7179610729 0.1104531288 0.1218600846 0.2376661599 0.0047467141 0.0091900000 0.0004390000 0.0023790000 0.0000050000 0.0000030000 0.0012960000 42240493 96830484 509673472 3.8893358707 3.9433109760 3.9925489426 1952 1311867783.7488200665 0.1112559512 0.1218546522 0.2376661599 0.0047459570 0.0110140000 0.0004440000 0.0045730000 0.0000000000 0.0000030000 0.0010240000 42244109 96830484 509673472 3.8885793686 3.9444856644 3.9930071831 1953 1311867783.7808690071 0.1101991907 0.1218486842 0.2376661599 0.0047450067 0.0099080000 0.0004710000 0.0023840000 0.0000040000 0.0000030000 0.0019000000 42247781 96830484 509673472 3.8898236752 3.9448406696 3.9931597710 1954 1311867783.8168580532 0.1107873097 0.1218430233 0.2376661599 0.0047459080 0.0151640000 0.0005430000 0.0048480000 0.0000000000 0.0000080000 0.0011550000 42251509 96830484 509673472 3.8894116879 3.9434289932 3.9930369854 1955 1311867783.8489229679 0.1096790656 0.1218368013 0.2376661599 0.0047456855 0.0117810000 0.0004570000 0.0046270000 0.0000040000 0.0000040000 0.0013080000 42255181 96830484 509673472 3.8904912472 3.9460759163 3.9940958023 1956 1311867783.8808929920 0.1093651503 0.1218304252 0.2376661599 0.0047447485 0.0151410000 0.0005400000 0.0048870000 0.0000010000 0.0000080000 0.0011560000 42258853 96830484 509673472 3.8906898499 3.9459369183 3.9938337803 1957 1311867783.9168200493 0.1113786399 0.1218250845 0.2376661599 0.0047506684 0.0113290000 0.0004650000 0.0035100000 0.0000040000 0.0000040000 0.0019090000 42262637 96830484 509673472 3.8889849186 3.9450094700 3.9946155548 1958 1311867783.9508318901 0.1100757122 0.1218190838 0.2376661599 0.0047496373 0.0095770000 0.0004420000 0.0031230000 0.0000010000 0.0000040000 0.0010230000 42266365 96830484 509673472 3.8901884556 3.9456419945 3.9950382710 1959 1311867783.9816930294 0.1106538698 0.1218133844 0.2376661599 0.0047498514 0.0107120000 0.0004430000 0.0038640000 0.0000030000 0.0000030000 0.0012870000 42269981 96830484 509673472 3.8895976543 3.9458341599 3.9957387447 1960 1311867784.0175230503 0.1111054420 0.1218079211 0.2376661599 0.0047491072 0.0110470000 0.0004650000 0.0045730000 0.0000010000 0.0000030000 0.0010140000 42273821 96830484 509673472 3.8891196251 3.9440283775 3.9954724312 1961 1311867784.0505928993 0.1119692847 0.1218029040 0.2376661599 0.0047494871 0.0142500000 0.0005470000 0.0026000000 0.0000110000 0.0000090000 0.0022190000 42277549 96830484 509673472 3.8879477978 3.9452543259 3.9958078861 1962 1311867784.0830729008 0.1112710387 0.1217975361 0.2376661599 0.0047487361 0.0139430000 0.0005440000 0.0033520000 0.0000020000 0.0000100000 0.0011550000 42281165 96830484 509673472 3.8883812428 3.9458484650 3.9959962368 1963 1311867784.1187570095 0.1111981049 0.1217921364 0.2376661599 0.0047488644 0.0156590000 0.0005450000 0.0048560000 0.0000090000 0.0000070000 0.0014300000 42284949 96830484 509673472 3.8884701729 3.9439327717 3.9956848621 1964 1311867784.1503119469 0.1114030257 0.1217868467 0.2376661599 0.0047483198 0.0111620000 0.0005150000 0.0040290000 0.0000000000 0.0000040000 0.0010300000 42288621 96830484 509673472 3.8879306316 3.9438805580 3.9960126877 1965 1311867784.1823339462 0.1093192846 0.1217805019 0.2376661599 0.0047474688 0.0106140000 0.0004490000 0.0031250000 0.0000030000 0.0000030000 0.0018870000 42292349 96830484 509673472 3.8898293972 3.9444050789 3.9962365627 1966 1311867784.2173891068 0.1106820554 0.1217748567 0.2376661599 0.0047472409 0.0111500000 0.0004470000 0.0045970000 0.0000000000 0.0000030000 0.0010220000 42296021 96830484 509673472 3.8883171082 3.9423475266 3.9961278439 1967 1311867784.2502059937 0.1117061004 0.1217697378 0.2376661599 0.0047472548 0.0095830000 0.0004450000 0.0027340000 0.0000030000 0.0000030000 0.0012930000 42299749 96830484 509673472 3.8868410587 3.9426729679 3.9964907169 1968 1311867784.2819900513 0.1100424007 0.1217637788 0.2376661599 0.0047469266 0.0096820000 0.0004450000 0.0031280000 0.0000000000 0.0000030000 0.0010200000 42303365 96830484 509673472 3.8883299828 3.9441242218 3.9969360828 1969 1311867784.3176920414 0.1112487838 0.1217584385 0.2376661599 0.0047476723 0.0120280000 0.0004470000 0.0045720000 0.0000030000 0.0000030000 0.0018860000 42307205 96830484 509673472 3.8871076107 3.9421484470 3.9970707893 1970 1311867784.3490819931 0.1114874408 0.1217532248 0.2376661599 0.0047470408 0.0134060000 0.0005430000 0.0036840000 0.0000010000 0.0000080000 0.0011700000 42310821 96830484 509673472 3.8871517181 3.9413323402 3.9971978664 1971 1311867784.3815689087 0.1104382724 0.1217474841 0.2376661599 0.0047470584 0.0107040000 0.0004620000 0.0035240000 0.0000040000 0.0000040000 0.0013030000 42314549 96830484 509673472 3.8879897594 3.9426229000 3.9974820614 1972 1311867784.4190580845 0.1107791588 0.1217419221 0.2376661599 0.0047465259 0.0112630000 0.0004480000 0.0045770000 0.0000000000 0.0000030000 0.0010160000 42318333 96830484 509673472 3.8874864578 3.9418125153 3.9972071648 1973 1311867784.4496140480 0.1108779386 0.1217364158 0.2376661599 0.0047453594 0.0103100000 0.0004490000 0.0027430000 0.0000030000 0.0000030000 0.0018920000 42322005 96830484 509673472 3.8876347542 3.9413747787 3.9976427555 1974 1311867784.4828379154 0.1099809259 0.1217304606 0.2376661599 0.0047451771 0.0088700000 0.0004450000 0.0023840000 0.0000010000 0.0000030000 0.0010220000 42325733 96830484 509673472 3.8883807659 3.9428379536 3.9980068207 1975 1311867784.5185639858 0.1120086089 0.1217255381 0.2376661599 0.0047444515 0.0169790000 0.0006280000 0.0050710000 0.0000100000 0.0000100000 0.0015600000 42329405 96830484 509673472 3.8865721226 3.9417402744 3.9983873367 1976 1311867784.5499279499 0.1099670976 0.1217195875 0.2376661599 0.0047444555 0.0100540000 0.0004720000 0.0027990000 0.0000000000 0.0000050000 0.0010350000 42333077 96830484 509673472 3.8883125782 3.9407789707 3.9980511665 1977 1311867784.5848410130 0.1107727140 0.1217140504 0.2376661599 0.0047439257 0.0104610000 0.0004560000 0.0031170000 0.0000030000 0.0000030000 0.0018840000 42336861 96830484 509673472 3.8871581554 3.9417817593 3.9982078075 1978 1311867784.6179790497 0.1113180071 0.1217087946 0.2376661599 0.0047434434 0.0144280000 0.0005390000 0.0037240000 0.0000010000 0.0000100000 0.0011550000 42340533 96830484 509673472 3.8865671158 3.9402763844 3.9981603622 1979 1311867784.6492750645 0.1109586209 0.1217033624 0.2376661599 0.0047424356 0.0101390000 0.0004610000 0.0027920000 0.0000050000 0.0000050000 0.0013100000 42344205 96830484 509673472 3.8866949081 3.9403631687 3.9982447624 1980 1311867784.6878700256 0.1115595028 0.1216982393 0.2376661599 0.0047428763 0.0093770000 0.0004420000 0.0027430000 0.0000010000 0.0000030000 0.0010250000 42348045 96830484 509673472 3.8858826160 3.9419200420 3.9987347126 1981 1311867784.7168869972 0.1123014316 0.1216934958 0.2376661599 0.0047422708 0.0101090000 0.0004420000 0.0027490000 0.0000030000 0.0000040000 0.0019000000 42351605 96830484 509673472 3.8848552704 3.9406945705 3.9984958172 1982 1311867784.7578089237 0.1119094640 0.1216885594 0.2376661599 0.0047437146 0.0097250000 0.0004400000 0.0031140000 0.0000010000 0.0000030000 0.0010130000 42355613 96830484 509673472 3.8847570419 3.9406507015 3.9987390041 1983 1311867784.7870030403 0.1122282818 0.1216837887 0.2376661599 0.0047425855 0.0144160000 0.0005410000 0.0041170000 0.0000080000 0.0000070000 0.0014230000 42359173 96830484 509673472 3.8845293522 3.9414818287 3.9992027283 1984 1311867784.8199620247 0.1119937375 0.1216789046 0.2376661599 0.0047427964 0.0098530000 0.0004600000 0.0027880000 0.0000000000 0.0000040000 0.0010250000 42362733 96830484 509673472 3.8842551708 3.9398136139 3.9987654686 1985 1311867784.8550779819 0.1120726913 0.1216740652 0.2376661599 0.0047418705 0.0102250000 0.0004530000 0.0027580000 0.0000040000 0.0000040000 0.0018880000 42366461 96830484 509673472 3.8840353489 3.9397089481 3.9989054203 1986 1311867784.8873779774 0.1123614162 0.1216693760 0.2376661599 0.0047407637 0.0097250000 0.0004470000 0.0031180000 0.0000000000 0.0000040000 0.0010200000 42370133 96830484 509673472 3.8834865093 3.9406335354 3.9993712902 1987 1311867784.9173130989 0.1134973913 0.1216652633 0.2376661599 0.0047399881 0.0101230000 0.0004400000 0.0031400000 0.0000040000 0.0000030000 0.0013080000 42373805 96830484 509673472 3.8825991154 3.9391357899 3.9991338253 1988 1311867784.9491391182 0.1120029539 0.1216604030 0.2376661599 0.0047395743 0.0095530000 0.0004450000 0.0031260000 0.0000000000 0.0000040000 0.0010160000 42377421 96830484 509673472 3.8835256100 3.9394662380 3.9989156723 1989 1311867784.9848570824 0.1121007279 0.1216555967 0.2376661599 0.0047387572 0.0098080000 0.0004430000 0.0023780000 0.0000040000 0.0000040000 0.0018870000 42381205 96830484 509673472 3.8832619190 3.9393608570 3.9989848137 1990 1311867785.0184569359 0.1119511798 0.1216507201 0.2376661599 0.0047377074 0.0099450000 0.0004420000 0.0034970000 0.0000000000 0.0000040000 0.0010150000 42384877 96830484 509673472 3.8834400177 3.9381914139 3.9985971451 1991 1311867785.0500280857 0.1127774641 0.1216462634 0.2376661599 0.0047368454 0.0106910000 0.0004430000 0.0038590000 0.0000040000 0.0000030000 0.0012940000 42388605 96830484 509673472 3.8823406696 3.9388542175 3.9989886284 1992 1311867785.0871460438 0.1136531457 0.1216422508 0.2376661599 0.0047359275 0.0096530000 0.0004440000 0.0031340000 0.0000010000 0.0000040000 0.0010230000 42392389 96830484 509673472 3.8814663887 3.9389760494 3.9992311001 1993 1311867785.1168398857 0.1129850745 0.1216379070 0.2376661599 0.0047357178 0.0148970000 0.0005400000 0.0044760000 0.0000080000 0.0000070000 0.0020570000 42396061 96830484 509673472 3.8819053173 3.9390730858 3.9987337589 1994 1311867785.1499750614 0.1121308059 0.1216331392 0.2376661599 0.0047349089 0.0100430000 0.0004570000 0.0031840000 0.0000010000 0.0000040000 0.0010180000 42399677 96830484 509673472 3.8828485012 3.9386222363 3.9985899925 1995 1311867785.1850368977 0.1127377003 0.1216286803 0.2376661599 0.0047341428 0.0113400000 0.0004450000 0.0046130000 0.0000030000 0.0000030000 0.0012990000 42403461 96830484 509673472 3.8821365833 3.9400286674 3.9989006519 1996 1311867785.2169620991 0.1129075289 0.1216243110 0.2376661599 0.0047330984 0.0092020000 0.0004420000 0.0027720000 0.0000000000 0.0000040000 0.0010120000 42407077 96830484 509673472 3.8817305565 3.9401149750 3.9986398220 1997 1311867785.2491741180 0.1136041433 0.1216202949 0.2376661599 0.0047319280 0.0100730000 0.0004450000 0.0027570000 0.0000040000 0.0000040000 0.0018810000 42410749 96830484 509673472 3.8810431957 3.9398460388 3.9989886284 1998 1311867785.2858769894 0.1129367203 0.1216159488 0.2376661599 0.0047308102 0.0139050000 0.0005380000 0.0033920000 0.0000010000 0.0000110000 0.0011410000 42414589 96830484 509673472 3.8815431595 3.9403479099 3.9988081455 1999 1311867785.3214280605 0.1126711741 0.1216114741 0.2376661599 0.0047298836 0.0135880000 0.0005490000 0.0033410000 0.0000080000 0.0000070000 0.0014320000 42418485 96830484 509673472 3.8814938068 3.9402084351 3.9986305237 2000 1311867785.3573219776 0.1145644486 0.1216079506 0.2376661599 0.0047300450 0.0114510000 0.0004560000 0.0046490000 0.0000000000 0.0000050000 0.0010220000 42422213 96830484 509673472 3.8795785904 3.9395201206 3.9991114140 2001 1311867785.3893299103 0.1142220348 0.1216042595 0.2376661599 0.0047291660 0.0111870000 0.0004450000 0.0038970000 0.0000040000 0.0000030000 0.0018830000 42425885 96830484 509673472 3.8794746399 3.9409792423 3.9988842010 2002 1311867785.4211249352 0.1123966575 0.1215996603 0.2376661599 0.0047291000 0.0103400000 0.0004500000 0.0038750000 0.0000010000 0.0000040000 0.0010160000 42429557 96830484 509673472 3.8811843395 3.9405870438 3.9986178875 2003 1311867785.4570529461 0.1139861867 0.1215958593 0.2376661599 0.0047292183 0.0133240000 0.0005580000 0.0024800000 0.0000100000 0.0000100000 0.0014280000 42433341 96830484 509673472 3.8793933392 3.9397494793 3.9986419678 2004 1311867785.4900350571 0.1138166040 0.1215919774 0.2376661599 0.0047286217 0.0105090000 0.0005010000 0.0031900000 0.0000010000 0.0000050000 0.0010480000 42437069 96830484 509673472 3.8792674541 3.9419260025 3.9989683628 2005 1311867785.5211930275 0.1134584174 0.1215879208 0.2376661599 0.0047278044 0.0106400000 0.0004510000 0.0031370000 0.0000040000 0.0000030000 0.0018780000 42440685 96830484 509673472 3.8792128563 3.9419271946 3.9990038872 2006 1311867785.5571260452 0.1125831231 0.1215834318 0.2376661599 0.0047283126 0.0093440000 0.0004490000 0.0027620000 0.0000010000 0.0000040000 0.0010310000 42444469 96830484 509673472 3.8792374134 3.9407594204 3.9989933968 2007 1311867785.5891211033 0.1132831872 0.1215792962 0.2376661599 0.0047277440 0.0095510000 0.0004470000 0.0027530000 0.0000030000 0.0000030000 0.0012890000 42448141 96830484 509673472 3.8782219887 3.9412748814 3.9992702007 2008 1311867785.6211590767 0.1118212789 0.1215744366 0.2376661599 0.0047364739 0.0096300000 0.0004480000 0.0031470000 0.0000010000 0.0000040000 0.0010060000 42451869 96830484 509673472 3.8790616989 3.9420211315 3.9987637997 2009 1311867785.6570439339 0.1127744094 0.1215700563 0.2376661599 0.0047390141 0.0113100000 0.0004500000 0.0038650000 0.0000030000 0.0000040000 0.0018800000 42455653 96830484 509673472 3.8781003952 3.9403800964 3.9988718033 2010 1311867785.6892280579 0.1142683700 0.1215664236 0.2376661599 0.0047381276 0.0094420000 0.0004450000 0.0027570000 0.0000000000 0.0000040000 0.0010080000 42459269 96830484 509673472 3.8763308525 3.9406607151 3.9989602566 2011 1311867785.7214241028 0.1131832153 0.1215622550 0.2376661599 0.0047395239 0.0126630000 0.0004520000 0.0046240000 0.0000030000 0.0000030000 0.0017960000 42462941 96830484 509673472 3.8769471645 3.9417624474 3.9987380505 2012 1311867785.7573668957 0.1142570078 0.1215586241 0.2376661599 0.0047391390 0.0113010000 0.0004980000 0.0046270000 0.0000000000 0.0000040000 0.0010050000 42466725 96830484 509673472 3.8756051064 3.9399406910 3.9984543324 2013 1311867785.7892301083 0.1139703393 0.1215548545 0.2376661599 0.0047388879 0.0116780000 0.0004450000 0.0042380000 0.0000040000 0.0000040000 0.0018790000 42470397 96830484 509673472 3.8758015633 3.9395453930 3.9986405373 2014 1311867785.8210389614 0.1130022705 0.1215506079 0.2376661599 0.0047378164 0.0135330000 0.0005440000 0.0026020000 0.0000020000 0.0000110000 0.0012570000 42474069 96830484 509673472 3.8766031265 3.9404902458 3.9984767437 2015 1311867785.8574340343 0.1138043553 0.1215467636 0.2376661599 0.0047373050 0.0101890000 0.0004550000 0.0027950000 0.0000050000 0.0000040000 0.0013050000 42477853 96830484 509673472 3.8755044937 3.9405553341 3.9984011650 2016 1311867785.8893110752 0.1146394908 0.1215433374 0.2376661599 0.0047364843 0.0097510000 0.0004450000 0.0031230000 0.0000000000 0.0000030000 0.0010150000 42481581 96830484 509673472 3.8747131824 3.9395935535 3.9986419678 2017 1311867785.9211509228 0.1141570061 0.1215396754 0.2376661599 0.0047365786 0.0101180000 0.0004450000 0.0027640000 0.0000030000 0.0000040000 0.0018870000 42485253 96830484 509673472 3.8747687340 3.9409592152 3.9988939762 2018 1311867785.9588449001 0.1143734157 0.1215361242 0.2376661599 0.0047370516 0.0111000000 0.0004440000 0.0045870000 0.0000010000 0.0000040000 0.0010200000 42489037 96830484 509673472 3.8742783070 3.9412422180 3.9987912178 2019 1311867785.9892621040 0.1151344329 0.1215329535 0.2376661599 0.0047360278 0.0091520000 0.0004460000 0.0023910000 0.0000040000 0.0000030000 0.0013000000 42492709 96830484 509673472 3.8733177185 3.9402723312 3.9990172386 2020 1311867786.0210618973 0.1134529412 0.1215289535 0.2376661599 0.0047350825 0.0135980000 0.0005500000 0.0033480000 0.0000010000 0.0000080000 0.0011560000 42496381 96830484 509673472 3.8746185303 3.9412622452 3.9990098476 2021 1311867786.0572268963 0.1141248643 0.1215252899 0.2376661599 0.0047348814 0.0153280000 0.0005540000 0.0048760000 0.0000080000 0.0000070000 0.0020410000 42500109 96830484 509673472 3.8734049797 3.9405806065 3.9992222786 2022 1311867786.0892500877 0.1157223508 0.1215224200 0.2376661599 0.0047339499 0.0133010000 0.0005540000 0.0033320000 0.0000010000 0.0000080000 0.0011390000 42503837 96830484 509673472 3.8714649677 3.9394361973 3.9994797707 2023 1311867786.1211619377 0.1151593477 0.1215192746 0.2376661599 0.0047330224 0.0248790000 0.0006310000 0.0043440000 0.0000160000 0.0000140000 0.0018090000 42507565 96830484 509673472 3.8716073036 3.9396710396 3.9994843006 2024 1311867786.1570990086 0.1160480231 0.1215165714 0.2376661599 0.0047320262 0.0127790000 0.0005260000 0.0043240000 0.0000000000 0.0000070000 0.0010530000 42511293 96830484 509673472 3.8702056408 3.9405951500 3.9998035431 2025 1311867786.1891019344 0.1164543629 0.1215140716 0.2376661599 0.0047313424 0.0135020000 0.0005590000 0.0025690000 0.0000080000 0.0000070000 0.0020750000 42514909 96830484 509673472 3.8693296909 3.9392626286 3.9998080730 2026 1311867786.2216470242 0.1158033609 0.1215112529 0.2376661599 0.0047303997 0.0104920000 0.0004530000 0.0035280000 0.0000010000 0.0000040000 0.0010180000 42518581 96830484 509673472 3.8694519997 3.9394612312 3.9997618198 2027 1311867786.2570950985 0.1166280955 0.1215088438 0.2376661599 0.0047294548 0.0101220000 0.0004460000 0.0031260000 0.0000040000 0.0000030000 0.0012960000 42522421 96830484 509673472 3.8681721687 3.9399051666 3.9999811649 2028 1311867786.2895779610 0.1166452095 0.1215064456 0.2376661599 0.0047292205 0.0097810000 0.0004460000 0.0031210000 0.0000010000 0.0000030000 0.0010200000 42526037 96830484 509673472 3.8677010536 3.9391407967 3.9999003410 2029 1311867786.3211650848 0.1165714711 0.1215040134 0.2376661599 0.0047288375 0.0101710000 0.0004420000 0.0027530000 0.0000030000 0.0000030000 0.0019050000 42529653 96830484 509673472 3.8676605225 3.9390025139 4.0000739098 2030 1311867786.3572299480 0.1173432097 0.1215019637 0.2376661599 0.0047282650 0.0111750000 0.0004380000 0.0045870000 0.0000010000 0.0000040000 0.0010190000 42533493 96830484 509673472 3.8667063713 3.9393625259 4.0004692078 2031 1311867786.3891439438 0.1168747321 0.1214996854 0.2376661599 0.0047271997 0.0144170000 0.0005570000 0.0026080000 0.0000090000 0.0000090000 0.0014380000 42537109 96830484 509673472 3.8667795658 3.9387824535 4.0001301765 2032 1311867786.4213869572 0.1159482375 0.1214969534 0.2376661599 0.0047267967 0.0119300000 0.0005070000 0.0046390000 0.0000000000 0.0000040000 0.0010220000 42540837 96830484 509673472 3.8676381111 3.9377813339 4.0002927780 2033 1311867786.4573409557 0.1185184494 0.1214954883 0.2376661599 0.0047305177 0.0117110000 0.0004450000 0.0042170000 0.0000030000 0.0000040000 0.0019150000 42544621 96830484 509673472 3.8647537231 3.9394385815 4.0009517670 2034 1311867786.4891700745 0.1171050146 0.1214933298 0.2376661599 0.0047318726 0.0092940000 0.0004380000 0.0027320000 0.0000010000 0.0000040000 0.0010220000 42548237 96830484 509673472 3.8658699989 3.9382088184 4.0008983612 2035 1311867786.5218079090 0.1169177815 0.1214910813 0.2376661599 0.0047321263 0.0095110000 0.0004350000 0.0026250000 0.0000040000 0.0000030000 0.0013030000 42551965 96830484 509673472 3.8659498692 3.9365923405 4.0011844635 2036 1311867786.5572519302 0.1174442172 0.1214890937 0.2376661599 0.0047311792 0.0111600000 0.0004350000 0.0045750000 0.0000000000 0.0000050000 0.0010300000 42555749 96830484 509673472 3.8652141094 3.9371256828 4.0013723373 2037 1311867786.5895760059 0.1171021685 0.1214869401 0.2376661599 0.0047306220 0.0110890000 0.0004360000 0.0034780000 0.0000040000 0.0000040000 0.0019210000 42559421 96830484 509673472 3.8649764061 3.9371490479 4.0014276505 2038 1311867786.6211080551 0.1174536124 0.1214849610 0.2376661599 0.0047308225 0.0093790000 0.0004400000 0.0027320000 0.0000000000 0.0000040000 0.0010320000 42563093 96830484 509673472 3.8646202087 3.9355463982 4.0016460419 2039 1311867786.6573529243 0.1164494976 0.1214824914 0.2376661599 0.0047306598 0.0114790000 0.0004390000 0.0045590000 0.0000030000 0.0000040000 0.0013100000 42566877 96830484 509673472 3.8654439449 3.9357740879 4.0016498566 2040 1311867786.6891629696 0.1172282323 0.1214804060 0.2376661599 0.0047298720 0.0114080000 0.0004390000 0.0045440000 0.0000010000 0.0000040000 0.0010400000 42570493 96830484 509673472 3.8644294739 3.9360902309 4.0021610260 2041 1311867786.7210969925 0.1179387942 0.1214786708 0.2376661599 0.0047289369 0.0121720000 0.0004340000 0.0045470000 0.0000030000 0.0000040000 0.0019390000 42574165 96830484 509673472 3.8634383678 3.9358711243 4.0024938583 2042 1311867786.7570719719 0.1171465293 0.1214765493 0.2376661599 0.0047281492 0.0113460000 0.0004380000 0.0045550000 0.0000000000 0.0000040000 0.0010440000 42577893 96830484 509673472 3.8637480736 3.9371788502 4.0024433136 2043 1311867786.7892940044 0.1174053550 0.1214745565 0.2376661599 0.0047270466 0.0096830000 0.0004390000 0.0027370000 0.0000030000 0.0000040000 0.0013240000 42581621 96830484 509673472 3.8633296490 3.9380462170 4.0028624535 2044 1311867786.8211419582 0.1178730652 0.1214727945 0.2376661599 0.0047260660 0.0143130000 0.0005490000 0.0047720000 0.0000000000 0.0000220000 0.0011460000 42585293 96830484 509673472 3.8627498150 3.9358766079 4.0033454895 2045 1311867786.8575630188 0.1163779572 0.1214703032 0.2376661599 0.0047269567 0.0106280000 0.0004470000 0.0027590000 0.0000040000 0.0000040000 0.0019420000 42589021 96830484 509673472 3.8633470535 3.9377052784 4.0035877228 2046 1311867786.8893759251 0.1171609238 0.1214681969 0.2376661599 0.0047289646 0.0112700000 0.0004280000 0.0045530000 0.0000010000 0.0000040000 0.0010450000 42592749 96830484 509673472 3.8628282547 3.9387319088 4.0040850639 2047 1311867786.9211881161 0.1174864396 0.1214662517 0.2376661599 0.0047315202 0.0100750000 0.0004340000 0.0030830000 0.0000030000 0.0000030000 0.0013170000 42596421 96830484 509673472 3.8620345592 3.9366204739 4.0043168068 2048 1311867786.9576020241 0.1176251173 0.1214643762 0.2376661599 0.0047303701 0.0134030000 0.0005440000 0.0025590000 0.0000010000 0.0000100000 0.0011700000 42600261 96830484 509673472 3.8618636131 3.9369039536 4.0046930313 2049 1311867786.9892089367 0.1162166744 0.1214618151 0.2376661599 0.0047302310 0.0116500000 0.0004450000 0.0035040000 0.0000040000 0.0000040000 0.0019570000 42800429 96830484 509673472 3.8626282215 3.9384746552 4.0048537254 2050 1311867787.0211400986 0.1173857376 0.1214598268 0.2376661599 0.0047292438 0.0107030000 0.0004310000 0.0038190000 0.0000010000 0.0000040000 0.0010420000 43213757 96830484 509673472 3.8618550301 3.9363946915 4.0049695969 2051 1311867787.0571250916 0.1179784313 0.1214581293 0.2376661599 0.0047283412 0.0105120000 0.0004350000 0.0034430000 0.0000040000 0.0000030000 0.0013330000 43217597 96830484 509673472 3.8611841202 3.9357571602 4.0052814484 2052 1311867787.0895950794 0.1174847558 0.1214561930 0.2376661599 0.0047276780 0.0134710000 0.0005410000 0.0032780000 0.0000010000 0.0000090000 0.0011790000 43221213 96830484 509673472 3.8615303040 3.9372270107 4.0056633949 2053 1311867787.1239550114 0.1183072627 0.1214546592 0.2376661599 0.0047273887 0.0112080000 0.0004370000 0.0031060000 0.0000040000 0.0000030000 0.0019640000 43224941 96830484 509673472 3.8604300022 3.9355268478 4.0057215691 2054 1311867787.1573429108 0.1175906137 0.1214527779 0.2376661599 0.0047268221 0.0143270000 0.0005320000 0.0036910000 0.0000010000 0.0000090000 0.0011920000 43228669 96830484 509673472 3.8607316017 3.9366843700 4.0057582855 2055 1311867787.1892991066 0.1171976328 0.1214507073 0.2376661599 0.0047259120 0.0102190000 0.0004470000 0.0023810000 0.0000040000 0.0000040000 0.0013590000 43232341 96830484 509673472 3.8608906269 3.9379513264 4.0057473183 2056 1311867787.2230238914 0.1173036173 0.1214486903 0.2376661599 0.0047259764 0.0109260000 0.0004260000 0.0041610000 0.0000000000 0.0000030000 0.0010600000 43236069 96830484 509673472 3.8607387543 3.9348564148 4.0058102608 2057 1311867787.2571809292 0.1178518385 0.1214469417 0.2376661599 0.0047255989 0.0121430000 0.0004320000 0.0045090000 0.0000040000 0.0000030000 0.0019870000 43239797 96830484 509673472 3.8599443436 3.9353642464 4.0062055588 2058 1311867787.2893400192 0.1162546352 0.1214444187 0.2376661599 0.0047246392 0.0112370000 0.0004360000 0.0045190000 0.0000010000 0.0000040000 0.0010740000 43243469 96830484 509673472 3.8611543179 3.9367263317 4.0062623024 2059 1311867787.3217399120 0.1166855469 0.1214421074 0.2376661599 0.0047251466 0.0104500000 0.0004290000 0.0034450000 0.0000030000 0.0000030000 0.0013370000 43247141 96830484 509673472 3.8604848385 3.9342021942 4.0059938431 2060 1311867787.3572421074 0.1178009957 0.1214403399 0.2376661599 0.0047250290 0.0146880000 0.0005430000 0.0047660000 0.0000010000 0.0000080000 0.0012150000 43250925 96830484 509673472 3.8594787121 3.9343113899 4.0064172745 2061 1311867787.3892920017 0.1161451414 0.1214377707 0.2376661599 0.0047240111 0.0125460000 0.0004520000 0.0045570000 0.0000040000 0.0000040000 0.0020170000 43254597 96830484 509673472 3.8606293201 3.9357635975 4.0058450699 2062 1311867787.4245440960 0.1165737882 0.1214354118 0.2376661599 0.0047236121 0.0112750000 0.0004250000 0.0045140000 0.0000010000 0.0000040000 0.0010700000 43258325 96830484 509673472 3.8596825600 3.9342155457 4.0056633949 2063 1311867787.4572229385 0.1163979024 0.1214329699 0.2376661599 0.0047228366 0.0116000000 0.0004310000 0.0045020000 0.0000040000 0.0000040000 0.0013610000 43262053 96830484 509673472 3.8596782684 3.9347949028 4.0057773590 2064 1311867787.4892969131 0.1155551448 0.1214301222 0.2376661599 0.0047217972 0.0112410000 0.0004300000 0.0044940000 0.0000000000 0.0000030000 0.0010850000 43265669 96830484 509673472 3.8602800369 3.9360692501 4.0055274963 2065 1311867787.5220890045 0.1168266237 0.1214278929 0.2376661599 0.0047208113 0.0122540000 0.0004250000 0.0045040000 0.0000030000 0.0000040000 0.0020230000 43269341 96830484 509673472 3.8587050438 3.9345848560 4.0055088997 2066 1311867787.5581040382 0.1174648553 0.1214259747 0.2376661599 0.0047198866 0.0114600000 0.0004320000 0.0045050000 0.0000000000 0.0000030000 0.0010870000 43273125 96830484 509673472 3.8579509258 3.9335575104 4.0054001808 2067 1311867787.5897688866 0.1142983586 0.1214225264 0.2376661599 0.0047189945 0.0116800000 0.0004270000 0.0044950000 0.0000040000 0.0000030000 0.0013750000 43276853 96830484 509673472 3.8606073856 3.9355795383 4.0047569275 2068 1311867787.6235499382 0.1154578030 0.1214196421 0.2376661599 0.0047183241 0.0094820000 0.0004240000 0.0026970000 0.0000000000 0.0000040000 0.0010850000 43280525 96830484 509673472 3.8589980602 3.9343700409 4.0047016144 2069 1311867787.6574609280 0.1157400534 0.1214168970 0.2376661599 0.0047179987 0.0103690000 0.0004270000 0.0026910000 0.0000040000 0.0000040000 0.0020300000 43284253 96830484 509673472 3.8584239483 3.9330303669 4.0042924881 2070 1311867787.6898610592 0.1171701401 0.1214148454 0.2376661599 0.0047180549 0.0093990000 0.0004280000 0.0026850000 0.0000010000 0.0000040000 0.0010910000 43287981 96830484 509673472 3.8567347527 3.9336240292 4.0044441223 2071 1311867787.7212240696 0.1160984635 0.1214122783 0.2376661599 0.0047169471 0.0115410000 0.0004300000 0.0044790000 0.0000040000 0.0000040000 0.0013680000 43291653 96830484 509673472 3.8575723171 3.9350490570 4.0041403770 2072 1311867787.7579810619 0.1153253093 0.1214093406 0.2376661599 0.0047169074 0.0112990000 0.0004240000 0.0044830000 0.0000000000 0.0000030000 0.0010950000 43295437 96830484 509673472 3.8579347134 3.9347128868 4.0041298866 2073 1311867787.7901558876 0.1165839285 0.1214070129 0.2376661599 0.0047159743 0.0173760000 0.0005410000 0.0036560000 0.0000120000 0.0000100000 0.0024100000 43299109 96830484 509673472 3.8562510014 3.9348454475 4.0040087700 2074 1311867787.8218519688 0.1148231551 0.1214038384 0.2376661599 0.0047163688 0.0120250000 0.0004500000 0.0045380000 0.0000000000 0.0000050000 0.0011060000 43302837 96830484 509673472 3.8576445580 3.9342010021 4.0033302307 2075 1311867787.8573749065 0.1160028428 0.1214012355 0.2376661599 0.0047156017 0.0098520000 0.0004270000 0.0026850000 0.0000030000 0.0000030000 0.0013820000 43306509 96830484 509673472 3.8561649323 3.9333305359 4.0032596588 2076 1311867787.8894400597 0.1161335185 0.1213986981 0.2376661599 0.0047145443 0.0112890000 0.0004290000 0.0044590000 0.0000000000 0.0000040000 0.0010960000 43310237 96830484 509673472 3.8558311462 3.9330058098 4.0031394958 2077 1311867787.9214320183 0.1150424853 0.1213956378 0.2376661599 0.0047135378 0.0146360000 0.0005160000 0.0036110000 0.0000070000 0.0000080000 0.0022350000 43313965 96830484 509673472 3.8563573360 3.9344904423 4.0026326180 2078 1311867787.9577279091 0.1173341200 0.1213936833 0.2376661599 0.0047132664 0.0123500000 0.0004980000 0.0045230000 0.0000010000 0.0000050000 0.0011160000 43317693 96830484 509673472 3.8534696102 3.9332864285 4.0026655197 2079 1311867787.9892189503 0.1179842874 0.1213920433 0.2376661599 0.0047123621 0.0145150000 0.0005820000 0.0032570000 0.0000080000 0.0000080000 0.0015160000 43321309 96830484 509673472 3.8524079323 3.9334697723 4.0027060509 2080 1311867788.0211091042 0.1172995940 0.1213900758 0.2376661599 0.0047115613 0.0150220000 0.0005360000 0.0047240000 0.0000010000 0.0000070000 0.0012400000 43325037 96830484 509673472 3.8525369167 3.9346947670 4.0019140244 2081 1311867788.0577259064 0.1203714460 0.1213895863 0.2376661599 0.0047116866 0.0126030000 0.0004320000 0.0045050000 0.0000040000 0.0000030000 0.0021000000 43328877 96830484 509673472 3.8487832546 3.9343793392 4.0019397736 2082 1311867788.0892241001 0.1210849211 0.1213894400 0.2376661599 0.0047113764 0.0096400000 0.0004140000 0.0026690000 0.0000010000 0.0000040000 0.0011200000 43332493 96830484 509673472 3.8476908207 3.9345426559 4.0022420883 2083 1311867788.1307280064 0.1220369488 0.1213897508 0.2376661599 0.0047127218 0.0149430000 0.0005090000 0.0036540000 0.0000100000 0.0000090000 0.0015320000 43336445 96830484 509673472 3.8458807468 3.9357082844 4.0022158623 2084 1311867788.1572849751 0.1214873791 0.1213897977 0.2376661599 0.0047116954 0.0101180000 0.0004250000 0.0027100000 0.0000000000 0.0000050000 0.0011160000 43340005 96830484 509673472 3.8458065987 3.9356875420 4.0025215149 2085 1311867788.1904621124 0.1172583997 0.1213878162 0.2376661599 0.0047141393 0.0122890000 0.0004130000 0.0044470000 0.0000050000 0.0000030000 0.0020800000 43343677 96830484 509673472 3.8491611481 3.9360508919 4.0022020340 2086 1311867788.2247180939 0.1163680479 0.1213854098 0.2376661599 0.0047132233 0.0099340000 0.0004080000 0.0030160000 0.0000000000 0.0000040000 0.0011040000 43347405 96830484 509673472 3.8493096828 3.9373559952 4.0021595955 2087 1311867788.2583730221 0.1163311154 0.1213829880 0.2376661599 0.0047135033 0.0109100000 0.0004120000 0.0037310000 0.0000030000 0.0000030000 0.0013990000 43351077 96830484 509673472 3.8485968113 3.9371688366 4.0022830963 2088 1311867788.2893440723 0.1196342036 0.1213821505 0.2376661599 0.0047125851 0.0099820000 0.0004170000 0.0030200000 0.0000000000 0.0000030000 0.0011120000 43354749 96830484 509673472 3.8446824551 3.9360232353 4.0030388832 2089 1311867788.3251628876 0.1214162558 0.1213821668 0.2376661599 0.0047122628 0.0105070000 0.0004130000 0.0026640000 0.0000030000 0.0000030000 0.0020800000 43358533 96830484 509673472 3.8423020840 3.9362020493 4.0035595894 2090 1311867788.3571081161 0.1226584390 0.1213827774 0.2376661599 0.0047115841 0.0186260000 0.0006000000 0.0034340000 0.0000020000 0.0000150000 0.0016570000 43362205 96830484 509673472 3.8406267166 3.9365599155 4.0038752556 2091 1311867788.3910779953 0.1247740537 0.1213843993 0.2376661599 0.0047105461 0.0140300000 0.0005080000 0.0025180000 0.0000110000 0.0000090000 0.0015370000 43365933 96830484 509673472 3.8377921581 3.9364511967 4.0045604706 2092 1311867788.4251430035 0.1274123937 0.1213872807 0.2376661599 0.0047096659 0.0118970000 0.0004230000 0.0044850000 0.0000010000 0.0000040000 0.0011190000 43369661 96830484 509673472 3.8345792294 3.9358837605 4.0049872398 2093 1311867788.4573140144 0.1295198649 0.1213911663 0.2376661599 0.0047093887 0.0114410000 0.0004120000 0.0033730000 0.0000030000 0.0000030000 0.0020210000 43373333 96830484 509673472 3.8318548203 3.9361436367 4.0048866272 2094 1311867788.4924380779 0.1296370178 0.1213951042 0.2376661599 0.0047090791 0.0114780000 0.0004090000 0.0044300000 0.0000000000 0.0000030000 0.0011160000 43377061 96830484 509673472 3.8314962387 3.9351584911 4.0055375099 2095 1311867788.5262899399 0.1304201633 0.1213994121 0.2376661599 0.0047080271 0.0116830000 0.0004130000 0.0044160000 0.0000030000 0.0000030000 0.0014010000 43380789 96830484 509673472 3.8301022053 3.9348614216 4.0056533813 2096 1311867788.5573079586 0.1327132136 0.1214048099 0.2376661599 0.0047076037 0.0113790000 0.0004120000 0.0044280000 0.0000010000 0.0000040000 0.0010940000 43384461 96830484 509673472 3.8271853924 3.9355051517 4.0058574677 2097 1311867788.5915369987 0.1333605349 0.1214105112 0.2376661599 0.0047068091 0.0124250000 0.0004240000 0.0044320000 0.0000040000 0.0000030000 0.0020310000 43388189 96830484 509673472 3.8258202076 3.9357700348 4.0056896210 2098 1311867788.6251940727 0.1340263635 0.1214165245 0.2376661599 0.0047062328 0.0103830000 0.0004120000 0.0033640000 0.0000000000 0.0000030000 0.0010860000 43391861 96830484 509673472 3.8244156837 3.9350438118 4.0058064461 2099 1311867788.6593029499 0.1323314756 0.1214217246 0.2376661599 0.0047053650 0.0106250000 0.0004060000 0.0033580000 0.0000040000 0.0000030000 0.0013640000 43395589 96830484 509673472 3.8257324696 3.9354922771 4.0056500435 2100 1311867788.6898009777 0.1351090968 0.1214282424 0.2376661599 0.0047055295 0.0143820000 0.0005220000 0.0032170000 0.0000010000 0.0000090000 0.0014670000 43399261 96830484 509673472 3.8221561909 3.9359920025 4.0055141449 2101 1311867788.7262809277 0.1370891780 0.1214356964 0.2376661599 0.0047050388 0.0109600000 0.0004660000 0.0026800000 0.0000040000 0.0000040000 0.0020380000 43403101 96830484 509673472 3.8195562363 3.9348380566 4.0061435699 2102 1311867788.7571070194 0.1337699741 0.1214415643 0.2376661599 0.0047049612 0.0113040000 0.0004080000 0.0044090000 0.0000010000 0.0000040000 0.0011000000 43406773 96830484 509673472 3.8221333027 3.9349949360 4.0052218437 2103 1311867788.7899940014 0.1356400698 0.1214483159 0.2376661599 0.0047051577 0.0144230000 0.0005000000 0.0028520000 0.0000100000 0.0000110000 0.0015720000 43410389 96830484 509673472 3.8195724487 3.9358515739 4.0048503876 2104 1311867788.8253190517 0.1366473883 0.1214555397 0.2376661599 0.0047048518 0.0108230000 0.0004160000 0.0033800000 0.0000000000 0.0000040000 0.0011020000 43414229 96830484 509673472 3.8178722858 3.9341313839 4.0049662590 2105 1311867788.8572509289 0.1367695332 0.1214628148 0.2376661599 0.0047037605 0.0105180000 0.0004150000 0.0026320000 0.0000030000 0.0000040000 0.0020430000 43417901 96830484 509673472 3.8171668053 3.9337468147 4.0046267509 2106 1311867788.8892900944 0.1369753331 0.1214701807 0.2376661599 0.0047035788 0.0114320000 0.0004020000 0.0043840000 0.0000000000 0.0000030000 0.0011000000 43421517 96830484 509673472 3.8163797855 3.9355015755 4.0044393539 2107 1311867788.9253408909 0.1369240880 0.1214775152 0.2376661599 0.0047036530 0.0105010000 0.0004050000 0.0033330000 0.0000040000 0.0000040000 0.0013710000 43425357 96830484 509673472 3.8155944347 3.9340841770 4.0042266846 2108 1311867788.9572029114 0.1381080300 0.1214854045 0.2376661599 0.0047028384 0.0145940000 0.0005110000 0.0046410000 0.0000010000 0.0000080000 0.0012220000 43429029 96830484 509673472 3.8141608238 3.9332785606 4.0040774345 2109 1311867788.9914720058 0.1381458491 0.1214933042 0.2376661599 0.0047022754 0.0140140000 0.0004940000 0.0031290000 0.0000070000 0.0000080000 0.0022180000 43432757 96830484 509673472 3.8132674694 3.9340381622 4.0041995049 2110 1311867789.0253350735 0.1399575621 0.1215020550 0.2376661599 0.0047022382 0.0154430000 0.0004990000 0.0046950000 0.0000000000 0.0000080000 0.0012250000 43436429 96830484 509673472 3.8108825684 3.9346807003 4.0044345856 2111 1311867789.0572888851 0.1399335265 0.1215107861 0.2376661599 0.0047013193 0.0152130000 0.0005180000 0.0046310000 0.0000070000 0.0000080000 0.0015060000 43440101 96830484 509673472 3.8104958534 3.9349913597 4.0048360825 2112 1311867789.0921590328 0.1400474459 0.1215195630 0.2376661599 0.0047008437 0.0108700000 0.0004150000 0.0033690000 0.0000000000 0.0000040000 0.0011190000 43443885 96830484 509673472 3.8095688820 3.9348506927 4.0047221184 2113 1311867789.1266920567 0.1409837604 0.1215287746 0.2376661599 0.0047006390 0.0123190000 0.0004020000 0.0043730000 0.0000040000 0.0000030000 0.0020660000 43447669 96830484 509673472 3.8082008362 3.9346411228 4.0052313805 2114 1311867789.1574180126 0.1418064684 0.1215383667 0.2376661599 0.0046998314 0.0102850000 0.0004040000 0.0033210000 0.0000000000 0.0000030000 0.0011130000 43451229 96830484 509673472 3.8070213795 3.9341609478 4.0047502518 2115 1311867789.1895699501 0.1428176612 0.1215484278 0.2376661599 0.0046991473 0.0116600000 0.0004020000 0.0043830000 0.0000040000 0.0000030000 0.0013960000 43454957 96830484 509673472 3.8058228493 3.9343972206 4.0055999756 2116 1311867789.2251811028 0.1419500858 0.1215580695 0.2376661599 0.0046982238 0.0112860000 0.0004000000 0.0043820000 0.0000000000 0.0000040000 0.0011100000 43458741 96830484 509673472 3.8059599400 3.9351811409 4.0051283836 2117 1311867789.2573940754 0.1413516849 0.1215674193 0.2376661599 0.0046985051 0.0115680000 0.0004090000 0.0036710000 0.0000030000 0.0000030000 0.0020680000 43462357 96830484 509673472 3.8059778214 3.9350986481 4.0046229362 2118 1311867789.2926049232 0.1432947069 0.1215776777 0.2376661599 0.0046974133 0.0136740000 0.0004950000 0.0031710000 0.0000020000 0.0000080000 0.0012390000 43466141 96830484 509673472 3.8034675121 3.9336977005 4.0049033165 2119 1311867789.3252000809 0.1432450116 0.1215879030 0.2376661599 0.0046963469 0.0107010000 0.0004170000 0.0030140000 0.0000040000 0.0000030000 0.0014000000 43469869 96830484 509673472 3.8028640747 3.9338178635 4.0047416687 2120 1311867789.3589100838 0.1412585974 0.1215971816 0.2376661599 0.0046953501 0.0113500000 0.0004040000 0.0043580000 0.0000010000 0.0000030000 0.0011090000 43473541 96830484 509673472 3.8040945530 3.9346373081 4.0039906502 2121 1311867789.3897531033 0.1431215256 0.1216073298 0.2376661599 0.0046952635 0.0162780000 0.0005000000 0.0046400000 0.0000070000 0.0000070000 0.0022300000 43477213 96830484 509673472 3.8015892506 3.9346032143 4.0037245750 2122 1311867789.4252359867 0.1431385130 0.1216174764 0.2376661599 0.0046949907 0.0118680000 0.0004120000 0.0044130000 0.0000000000 0.0000040000 0.0011220000 43480997 96830484 509673472 3.8007760048 3.9340453148 4.0032424927 2123 1311867789.4577910900 0.1417880505 0.1216269774 0.2376661599 0.0046945541 0.0116520000 0.0004020000 0.0043490000 0.0000030000 0.0000030000 0.0013870000 43484613 96830484 509673472 3.8014209270 3.9344964027 4.0030035973 2124 1311867789.4892559052 0.1426759362 0.1216368875 0.2376661599 0.0046938158 0.0145910000 0.0005020000 0.0035470000 0.0000010000 0.0000110000 0.0012480000 43488341 96830484 509673472 3.7998614311 3.9349231720 4.0023579597 2125 1311867789.5256059170 0.1446703523 0.1216477268 0.2376661599 0.0046929388 0.0129020000 0.0004150000 0.0043950000 0.0000040000 0.0000030000 0.0021010000 43492069 96830484 509673472 3.7973268032 3.9343812466 4.0028162003 2126 1311867789.5572779179 0.1442792863 0.1216583719 0.2376661599 0.0046922219 0.0095820000 0.0004020000 0.0026160000 0.0000000000 0.0000030000 0.0011190000 43495741 96830484 509673472 3.7970001698 3.9336724281 4.0027670860 2127 1311867789.5892720222 0.1450435668 0.1216693663 0.2376661599 0.0046911982 0.0185540000 0.0005930000 0.0030020000 0.0000150000 0.0000140000 0.0019120000 43499357 96830484 509673472 3.7957344055 3.9334170818 4.0032649040 2128 1311867789.6253700256 0.1470614225 0.1216812987 0.2376661599 0.0046917883 0.0152140000 0.0005280000 0.0045860000 0.0000010000 0.0000070000 0.0012490000 43503197 96830484 509673472 3.7928652763 3.9344167709 4.0031948090 2129 1311867789.6574499607 0.1437018216 0.1216916418 0.2376661599 0.0046916577 0.0146050000 0.0005190000 0.0035010000 0.0000070000 0.0000070000 0.0022550000 43506869 96830484 509673472 3.7953782082 3.9350643158 4.0020432472 2130 1311867789.6894960403 0.1444451362 0.1217023242 0.2376661599 0.0046907845 0.0114490000 0.0004160000 0.0040520000 0.0000010000 0.0000040000 0.0011330000 43510485 96830484 509673472 3.7939100266 3.9355974197 4.0023393631 2131 1311867789.7253561020 0.1449364722 0.1217132272 0.2376661599 0.0046930549 0.0116850000 0.0003980000 0.0043420000 0.0000040000 0.0000030000 0.0014010000 43514269 96830484 509673472 3.7926659584 3.9373164177 4.0022683144 2132 1311867789.7572269440 0.1432445049 0.1217233263 0.2376661599 0.0046922836 0.0105170000 0.0004040000 0.0033020000 0.0000010000 0.0000030000 0.0011120000 43517941 96830484 509673472 3.7935464382 3.9382650852 4.0020442009 2133 1311867789.7893610001 0.1410669386 0.1217323950 0.2376661599 0.0046929734 0.0156550000 0.0005010000 0.0046040000 0.0000080000 0.0000070000 0.0022240000 43521613 96830484 509673472 3.7948675156 3.9383735657 4.0013999939 2134 1311867789.8253350258 0.1440064460 0.1217428327 0.2376661599 0.0046925368 0.0108310000 0.0004140000 0.0033190000 0.0000010000 0.0000050000 0.0011250000 43525397 96830484 509673472 3.7915954590 3.9378960133 4.0023312569 2135 1311867789.8573670387 0.1440638602 0.1217532875 0.2376661599 0.0046914662 0.0114610000 0.0004010000 0.0039910000 0.0000030000 0.0000030000 0.0013910000 43529125 96830484 509673472 3.7908902168 3.9381744862 4.0020661354 2136 1311867789.8893530369 0.1410245001 0.1217623096 0.2376661599 0.0046907574 0.0101390000 0.0004040000 0.0029510000 0.0000010000 0.0000030000 0.0011210000 43532741 96830484 509673472 3.7930779457 3.9387562275 4.0016870499 2137 1311867789.9253480434 0.1430622488 0.1217722768 0.2376661599 0.0046901043 0.0118070000 0.0004180000 0.0036480000 0.0000040000 0.0000030000 0.0020630000 43536525 96830484 509673472 3.7902936935 3.9385733604 4.0027928352 2138 1311867789.9573481083 0.1409008056 0.1217812237 0.2376661599 0.0046898829 0.0115500000 0.0004010000 0.0043480000 0.0000010000 0.0000030000 0.0011120000 43540141 96830484 509673472 3.7914454937 3.9387509823 4.0019707680 2139 1311867789.9892580509 0.1427323371 0.1217910186 0.2376661599 0.0046891153 0.0118770000 0.0004210000 0.0043420000 0.0000030000 0.0000040000 0.0014010000 43543813 96830484 509673472 3.7890059948 3.9393956661 4.0023303032 2140 1311867790.0253860950 0.1457756907 0.1218022264 0.2376661599 0.0046891339 0.0104810000 0.0004000000 0.0032950000 0.0000000000 0.0000030000 0.0011070000 43547653 96830484 509673472 3.7851400375 3.9393153191 4.0032477379 2141 1311867790.0572309494 0.1460474133 0.1218135506 0.2376661599 0.0046880805 0.0147850000 0.0005010000 0.0035140000 0.0000080000 0.0000080000 0.0022400000 43551269 96830484 509673472 3.7842292786 3.9397552013 4.0036344528 2142 1311867790.0896899700 0.1440882534 0.1218239496 0.2376661599 0.0046880611 0.0114480000 0.0004110000 0.0040450000 0.0000010000 0.0000040000 0.0011260000 43554997 96830484 509673472 3.7856652737 3.9397351742 4.0035190582 2143 1311867790.1257700920 0.1445553601 0.1218345569 0.2376661599 0.0046874214 0.0103310000 0.0004160000 0.0029610000 0.0000030000 0.0000040000 0.0013830000 43558781 96830484 509673472 3.7844095230 3.9403200150 4.0035743713 2144 1311867790.1572160721 0.1414771229 0.1218437185 0.2376661599 0.0046870478 0.0106090000 0.0004000000 0.0032940000 0.0000000000 0.0000040000 0.0011130000 43562397 96830484 509673472 3.7867946625 3.9408817291 4.0033378601 2145 1311867790.1894400120 0.1450790316 0.1218545509 0.2376661599 0.0046874246 0.0168940000 0.0005630000 0.0046170000 0.0000080000 0.0000070000 0.0022670000 43566125 96830484 509673472 3.7828173637 3.9405431747 4.0043525696 2146 1311867790.2254109383 0.1430869848 0.1218644448 0.2376661599 0.0046866919 0.0167720000 0.0005030000 0.0046590000 0.0000020000 0.0000100000 0.0013800000 43569909 96830484 509673472 3.7841975689 3.9413218498 4.0041227341 2147 1311867790.2576739788 0.1438077688 0.1218746653 0.2376661599 0.0046856431 0.0152480000 0.0004950000 0.0035690000 0.0000120000 0.0000100000 0.0015280000 43573637 96830484 509673472 3.7827527523 3.9416308403 4.0043010712 2148 1311867790.2894508839 0.1453770101 0.1218856068 0.2376661599 0.0046851882 0.0120040000 0.0004150000 0.0043980000 0.0000000000 0.0000040000 0.0011230000 43577253 96830484 509673472 3.7808556557 3.9408819675 4.0046982765 2149 1311867790.3254859447 0.1473410279 0.1218974520 0.2376661599 0.0046859778 0.0121040000 0.0003980000 0.0040110000 0.0000030000 0.0000030000 0.0020760000 43581037 96830484 509673472 3.7783858776 3.9413366318 4.0054469109 2150 1311867790.3573629856 0.1472355723 0.1219092372 0.2376661599 0.0046862415 0.0107100000 0.0004030000 0.0036510000 0.0000000000 0.0000030000 0.0011140000 43584709 96830484 509673472 3.7780454159 3.9411718845 4.0052237511 2151 1311867790.3896288872 0.1454726011 0.1219201918 0.2376661599 0.0046852598 0.0116490000 0.0003890000 0.0043350000 0.0000030000 0.0000040000 0.0013950000 43588381 96830484 509673472 3.7790644169 3.9415504932 4.0046801567 2152 1311867790.4259679317 0.1462803930 0.1219315116 0.2376661599 0.0046877476 0.0100200000 0.0004040000 0.0029510000 0.0000000000 0.0000040000 0.0011190000 43592221 96830484 509673472 3.7779858112 3.9419479370 4.0046954155 2153 1311867790.4603750706 0.1474442035 0.1219433614 0.2376661599 0.0046883205 0.0116710000 0.0003980000 0.0036410000 0.0000040000 0.0000030000 0.0020800000 43595949 96830484 509673472 3.7761452198 3.9417500496 4.0051345825 2154 1311867790.4893760681 0.1461966932 0.1219546211 0.2376661599 0.0046886182 0.0107370000 0.0004020000 0.0036490000 0.0000000000 0.0000040000 0.0011100000 43599509 96830484 509673472 3.7769002914 3.9420354366 4.0049519539 2155 1311867790.5260839462 0.1480789632 0.1219667438 0.2376661599 0.0046905371 0.0141660000 0.0005110000 0.0031690000 0.0000090000 0.0000070000 0.0015300000 43603293 96830484 509673472 3.7746429443 3.9427309036 4.0050601959 2156 1311867790.5578188896 0.1491020918 0.1219793297 0.2376661599 0.0046919147 0.0117570000 0.0004160000 0.0043880000 0.0000000000 0.0000040000 0.0011280000 43606909 96830484 509673472 3.7733709812 3.9432284832 4.0056743622 2157 1311867790.5941619873 0.1512970328 0.1219929216 0.2376661599 0.0046945390 0.0106750000 0.0003970000 0.0026040000 0.0000030000 0.0000030000 0.0020740000 43610693 96830484 509673472 3.7709450722 3.9428584576 4.0054922104 2158 1311867790.6255199909 0.1516217589 0.1220066514 0.2376661599 0.0046938374 0.0093530000 0.0003990000 0.0022600000 0.0000010000 0.0000050000 0.0011130000 43614421 96830484 509673472 3.7699708939 3.9428849220 4.0056347847 2159 1311867790.6573970318 0.1523100138 0.1220206872 0.2376661599 0.0046946255 0.0149040000 0.0005200000 0.0028220000 0.0000100000 0.0000110000 0.0015990000 43617981 96830484 509673472 3.7684466839 3.9431319237 4.0055379868 2160 1311867790.6901810169 0.1526120156 0.1220348499 0.2376661599 0.0046940754 0.0145290000 0.0004870000 0.0030590000 0.0000020000 0.0000100000 0.0012390000 43621709 96830484 509673472 3.7676823139 3.9431419373 4.0057983398 2161 1311867790.7253530025 0.1515709311 0.1220485176 0.2376661599 0.0046932336 0.0125440000 0.0004120000 0.0040370000 0.0000040000 0.0000040000 0.0020790000 43625437 96830484 509673472 3.7682676315 3.9430377483 4.0058217049 2162 1311867790.7575750351 0.1503921598 0.1220616276 0.2376661599 0.0046921759 0.0097880000 0.0003950000 0.0025900000 0.0000000000 0.0000030000 0.0011130000 43629109 96830484 509673472 3.7686243057 3.9442999363 4.0050082207 2163 1311867790.7912769318 0.1515607834 0.1220752656 0.2376661599 0.0046939198 0.0097170000 0.0004020000 0.0022640000 0.0000040000 0.0000040000 0.0013900000 43632837 96830484 509673472 3.7670490742 3.9461097717 4.0053834915 2164 1311867790.8261909485 0.1516943127 0.1220889528 0.2376661599 0.0046933473 0.0098000000 0.0004010000 0.0026150000 0.0000010000 0.0000030000 0.0011070000 43636621 96830484 509673472 3.7663500309 3.9457917213 4.0055909157 2165 1311867790.8573698997 0.1506730169 0.1221021556 0.2376661599 0.0046924264 0.0114890000 0.0004030000 0.0032930000 0.0000030000 0.0000030000 0.0020600000 43640293 96830484 509673472 3.7670397758 3.9457104206 4.0058789253 2166 1311867790.8950428963 0.1518608630 0.1221158946 0.2376661599 0.0046927806 0.0184460000 0.0005140000 0.0046690000 0.0000010000 0.0000120000 0.0015820000 43644077 96830484 509673472 3.7655692101 3.9470064640 4.0065064430 2167 1311867790.9258179665 0.1511297822 0.1221292836 0.2376661599 0.0046922325 0.0109800000 0.0004810000 0.0026420000 0.0000040000 0.0000040000 0.0014200000 43647749 96830484 509673472 3.7659728527 3.9482901096 4.0064077377 2168 1311867790.9607090950 0.1499967128 0.1221421376 0.2376661599 0.0046921597 0.0114630000 0.0004020000 0.0043590000 0.0000010000 0.0000030000 0.0011110000 43651477 96830484 509673472 3.7663612366 3.9486553669 4.0063233376 2169 1311867790.9944651127 0.1481910497 0.1221541472 0.2376661599 0.0046939738 0.0124820000 0.0004040000 0.0043370000 0.0000040000 0.0000040000 0.0020670000 43655205 96830484 509673472 3.7676961422 3.9484450817 4.0062751770 2170 1311867791.0299000740 0.1501239985 0.1221670366 0.2376661599 0.0046944629 0.0156060000 0.0004960000 0.0046510000 0.0000010000 0.0000090000 0.0012540000 43658989 96830484 509673472 3.7654020786 3.9493575096 4.0067701340 2171 1311867791.0577330589 0.1492833346 0.1221795268 0.2376661599 0.0046941676 0.0114750000 0.0004150000 0.0036870000 0.0000040000 0.0000040000 0.0013970000 43662437 96830484 509673472 3.7656652927 3.9501249790 4.0066099167 2172 1311867791.0913140774 0.1495593190 0.1221921326 0.2376661599 0.0046931196 0.0110300000 0.0003990000 0.0036460000 0.0000010000 0.0000040000 0.0011200000 43666221 96830484 509673472 3.7650482655 3.9505529404 4.0067496300 2173 1311867791.1254060268 0.1488649845 0.1222044072 0.2376661599 0.0046938734 0.0121520000 0.0004040000 0.0039970000 0.0000030000 0.0000040000 0.0020760000 43669949 96830484 509673472 3.7651896477 3.9503626823 4.0064105988 2174 1311867791.1664540768 0.1490634680 0.1222167619 0.2376661599 0.0046950822 0.0116020000 0.0003980000 0.0043460000 0.0000000000 0.0000030000 0.0011160000 43673901 96830484 509673472 3.7644762993 3.9511950016 4.0065050125 2175 1311867791.1905651093 0.1497459710 0.1222294190 0.2376661599 0.0046951261 0.0101840000 0.0004100000 0.0026130000 0.0000030000 0.0000040000 0.0014030000 43677349 96830484 509673472 3.7637398243 3.9503450394 4.0069656372 2176 1311867791.2257969379 0.1523614526 0.1222432665 0.2376661599 0.0046954898 0.0098870000 0.0003920000 0.0026030000 0.0000010000 0.0000040000 0.0011230000 43681133 96830484 509673472 3.7605633736 3.9494149685 4.0072455406 2177 1311867791.2579009533 0.1527361423 0.1222572733 0.2376661599 0.0046955575 0.0125990000 0.0003950000 0.0043460000 0.0000040000 0.0000030000 0.0020610000 43684749 96830484 509673472 3.7594878674 3.9487845898 4.0075755119 2178 1311867791.2920219898 0.1525042951 0.1222711608 0.2376661599 0.0046945431 0.0109860000 0.0003970000 0.0036500000 0.0000000000 0.0000030000 0.0011150000 43688477 96830484 509673472 3.7593033314 3.9493026733 4.0076885223 2179 1311867791.3277790546 0.1529653221 0.1222852472 0.2376661599 0.0046948873 0.0118640000 0.0003990000 0.0043220000 0.0000040000 0.0000040000 0.0014080000 43692261 96830484 509673472 3.7584209442 3.9491848946 4.0075755119 2180 1311867791.3597049713 0.1535263211 0.1222995779 0.2376661599 0.0046961776 0.0104930000 0.0003910000 0.0032870000 0.0000010000 0.0000040000 0.0011210000 43695989 96830484 509673472 3.7573242188 3.9497461319 4.0081534386 2181 1311867791.3896780014 0.1529352516 0.1223136246 0.2376661599 0.0046955222 0.0111700000 0.0003980000 0.0029340000 0.0000040000 0.0000030000 0.0020820000 43699605 96830484 509673472 3.7571587563 3.9501876831 4.0076107979 2182 1311867791.4270040989 0.1536508799 0.1223279863 0.2376661599 0.0046953480 0.0100860000 0.0004140000 0.0029360000 0.0000000000 0.0000040000 0.0011270000 43703445 96830484 509673472 3.7558119297 3.9500582218 4.0081529617 2183 1311867791.4574470520 0.1544325352 0.1223426929 0.2376661599 0.0046945565 0.0116700000 0.0004000000 0.0042190000 0.0000040000 0.0000030000 0.0013990000 43707061 96830484 509673472 3.7545032501 3.9495236874 4.0083732605 2184 1311867791.4916520119 0.1570258439 0.1223585735 0.2376661599 0.0046966033 0.0115130000 0.0004130000 0.0043280000 0.0000010000 0.0000040000 0.0011300000 43710789 96830484 509673472 3.7515003681 3.9490611553 4.0089554787 2185 1311867791.5275359154 0.1539011896 0.1223730094 0.2376661599 0.0046960114 0.0153610000 0.0004850000 0.0045230000 0.0000070000 0.0000070000 0.0021960000 43714573 96830484 509673472 3.7542228699 3.9500389099 4.0087094307 2186 1311867791.5593819618 0.1534363031 0.1223872195 0.2376661599 0.0046963052 0.0119230000 0.0004090000 0.0043300000 0.0000000000 0.0000040000 0.0011330000 43718245 96830484 509673472 3.7542159557 3.9511137009 4.0089244843 2187 1311867791.5894811153 0.1510740519 0.1224003365 0.2376661599 0.0046956345 0.0108410000 0.0003980000 0.0032810000 0.0000030000 0.0000030000 0.0014270000 43721861 96830484 509673472 3.7559995651 3.9520869255 4.0082707405 2188 1311867791.6275899410 0.1508142352 0.1224133228 0.2376661599 0.0046948913 0.0115230000 0.0004030000 0.0042940000 0.0000000000 0.0000040000 0.0011330000 43725701 96830484 509673472 3.7558050156 3.9515345097 4.0082101822 2189 1311867791.6574349403 0.1529723853 0.1224272831 0.2376661599 0.0046941045 0.0126990000 0.0004080000 0.0043180000 0.0000030000 0.0000040000 0.0020960000 43729373 96830484 509673472 3.7534501553 3.9513683319 4.0085530281 2190 1311867791.6894969940 0.1532638967 0.1224413637 0.2376661599 0.0046933852 0.0113300000 0.0004020000 0.0039660000 0.0000010000 0.0000040000 0.0011350000 43732989 96830484 509673472 3.7529833317 3.9510316849 4.0088014603 2191 1311867791.7263259888 0.1538594067 0.1224557033 0.2376661599 0.0046926587 0.0108420000 0.0004030000 0.0032780000 0.0000040000 0.0000030000 0.0014020000 43736829 96830484 509673472 3.7521450520 3.9513576031 4.0088076591 2192 1311867791.7602820396 0.1527059674 0.1224695036 0.2376661599 0.0046916603 0.0146650000 0.0005240000 0.0035120000 0.0000010000 0.0000080000 0.0012560000 43740557 96830484 509673472 3.7530975342 3.9523129463 4.0087513924 2193 1311867791.7897930145 0.1515162885 0.1224827488 0.2376661599 0.0046912306 0.0119790000 0.0004170000 0.0033080000 0.0000040000 0.0000040000 0.0020770000 43744173 96830484 509673472 3.7541053295 3.9520630836 4.0082688332 2194 1311867791.8265190125 0.1540793031 0.1224971502 0.2376661599 0.0046909821 0.0115620000 0.0003970000 0.0043060000 0.0000010000 0.0000040000 0.0011240000 43747957 96830484 509673472 3.7514050007 3.9518251419 4.0087513924 2195 1311867791.8574469090 0.1545328200 0.1225117450 0.2376661599 0.0046906566 0.0101180000 0.0004030000 0.0025830000 0.0000040000 0.0000040000 0.0014050000 43751629 96830484 509673472 3.7510080338 3.9520857334 4.0094385147 2196 1311867791.8895421028 0.1538972110 0.1225260371 0.2376661599 0.0046895883 0.0157310000 0.0005010000 0.0045990000 0.0000010000 0.0000090000 0.0012500000 43755245 96830484 509673472 3.7513833046 3.9531061649 4.0090708733 2197 1311867791.9276258945 0.1549686491 0.1225408039 0.2376661599 0.0046890501 0.0119120000 0.0004100000 0.0033110000 0.0000040000 0.0000030000 0.0020700000 43759085 96830484 509673472 3.7499883175 3.9530320168 4.0087900162 2198 1311867791.9574968815 0.1524268389 0.1225544008 0.2376661599 0.0046885909 0.0105850000 0.0004010000 0.0032680000 0.0000000000 0.0000030000 0.0011260000 43762701 96830484 509673472 3.7524023056 3.9539003372 4.0089211464 2199 1311867791.9918000698 0.1529023796 0.1225682016 0.2376661599 0.0046882095 0.0112970000 0.0004000000 0.0035820000 0.0000040000 0.0000040000 0.0014090000 43766317 96830484 509673472 3.7517337799 3.9529900551 4.0087943077 2200 1311867792.0277240276 0.1542878300 0.1225826196 0.2376661599 0.0046880194 0.0147950000 0.0004920000 0.0035100000 0.0000010000 0.0000080000 0.0012480000 43770045 96830484 509673472 3.7502267361 3.9532980919 4.0090332031 2201 1311867792.0615789890 0.1552389264 0.1225974567 0.2376661599 0.0046873040 0.0148980000 0.0005070000 0.0027920000 0.0000080000 0.0000070000 0.0022700000 43773885 96830484 509673472 3.7489817142 3.9532802105 4.0095663071 2202 1311867792.0946090221 0.1556183547 0.1226124525 0.2376661599 0.0046863686 0.0113760000 0.0004060000 0.0036300000 0.0000010000 0.0000040000 0.0011380000 43777501 96830484 509673472 3.7483792305 3.9535882473 4.0093960762 2203 1311867792.1256630421 0.1565746963 0.1226278689 0.2376661599 0.0046857773 0.0109070000 0.0003970000 0.0032510000 0.0000040000 0.0000030000 0.0014030000 43781173 96830484 509673472 3.7471306324 3.9537696838 4.0091481209 2204 1311867792.1595768929 0.1550765187 0.1226425915 0.2376661599 0.0046850491 0.0115630000 0.0003930000 0.0042780000 0.0000000000 0.0000030000 0.0011270000 43784901 96830484 509673472 3.7482769489 3.9543557167 4.0091056824 2205 1311867792.1948819160 0.1537084579 0.1226566803 0.2376661599 0.0046874821 0.0162560000 0.0005080000 0.0045540000 0.0000080000 0.0000080000 0.0022770000 43788685 96830484 509673472 3.7494132519 3.9544210434 4.0091171265 2206 1311867792.2253580093 0.1542703062 0.1226710111 0.2376661599 0.0046925972 0.0117260000 0.0004100000 0.0042960000 0.0000010000 0.0000040000 0.0011420000 43792301 96830484 509673472 3.7480583191 3.9554305077 4.0090050697 2207 1311867792.2575860023 0.1558311135 0.1226860361 0.2376661599 0.0046916030 0.0117690000 0.0003930000 0.0042650000 0.0000030000 0.0000040000 0.0014060000 43795973 96830484 509673472 3.7460744381 3.9558641911 4.0091624260 2208 1311867792.2995440960 0.1559907645 0.1227011197 0.2376661599 0.0046913589 0.0115070000 0.0003920000 0.0042640000 0.0000010000 0.0000040000 0.0011350000 43799925 96830484 509673472 3.7452347279 3.9546244144 4.0090951920 2209 1311867792.3314530849 0.1550150961 0.1227157480 0.2376661599 0.0046907959 0.0124210000 0.0003970000 0.0042520000 0.0000030000 0.0000040000 0.0021080000 43803597 96830484 509673472 3.7458472252 3.9553029537 4.0090942383 2210 1311867792.3589100838 0.1559696794 0.1227307951 0.2376661599 0.0046902816 0.0133920000 0.0004880000 0.0023910000 0.0000010000 0.0000080000 0.0012680000 43807101 96830484 509673472 3.7446777821 3.9551060200 4.0093760490 2211 1311867792.3954761028 0.1570775509 0.1227463296 0.2376661599 0.0046893089 0.0160990000 0.0004890000 0.0043360000 0.0000080000 0.0000080000 0.0020820000 43810941 96830484 509673472 3.7431211472 3.9553828239 4.0093884468 2212 1311867792.4281890392 0.1543641239 0.1227606233 0.2376661599 0.0046888345 0.0111500000 0.0004050000 0.0036120000 0.0000010000 0.0000050000 0.0011580000 43814613 96830484 509673472 3.7451872826 3.9556922913 4.0085673332 2213 1311867792.4589219093 0.1559557170 0.1227756234 0.2376661599 0.0046881652 0.0117000000 0.0003980000 0.0032300000 0.0000040000 0.0000040000 0.0021160000 43818229 96830484 509673472 3.7432732582 3.9555301666 4.0084810257 2214 1311867792.4948880672 0.1583471447 0.1227916900 0.2376661599 0.0046878615 0.0149330000 0.0004860000 0.0044720000 0.0000010000 0.0000080000 0.0012800000 43822013 96830484 509673472 3.7405035496 3.9548289776 4.0089669228 2215 1311867792.5256149769 0.1577708572 0.1228074819 0.2376661599 0.0046869731 0.0120930000 0.0004070000 0.0042550000 0.0000040000 0.0000040000 0.0014140000 43825685 96830484 509673472 3.7409160137 3.9547276497 4.0089654922 2216 1311867792.5579619408 0.1578291357 0.1228232859 0.2376661599 0.0046864850 0.0115060000 0.0003880000 0.0042130000 0.0000010000 0.0000040000 0.0011400000 43829301 96830484 509673472 3.7402858734 3.9552116394 4.0083098412 2217 1311867792.5937440395 0.1576579213 0.1228389984 0.2376661599 0.0046855689 0.0158290000 0.0004880000 0.0044830000 0.0000070000 0.0000070000 0.0022710000 43833029 96830484 509673472 3.7403120995 3.9544651508 4.0082249641 2218 1311867792.6254990101 0.1562545747 0.1228540641 0.2376661599 0.0046845735 0.0108840000 0.0004040000 0.0032410000 0.0000010000 0.0000040000 0.0011510000 43836645 96830484 509673472 3.7413537502 3.9550418854 4.0082125664 2219 1311867792.6587610245 0.1562265009 0.1228691035 0.2376661599 0.0046839762 0.0160750000 0.0004770000 0.0045090000 0.0000080000 0.0000070000 0.0015360000 43840373 96830484 509673472 3.7410652637 3.9551098347 4.0080828667 2220 1311867792.6947619915 0.1562852114 0.1228841558 0.2376661599 0.0046832096 0.0114170000 0.0004030000 0.0035720000 0.0000010000 0.0000040000 0.0011660000 43844157 96830484 509673472 3.7406246662 3.9541058540 4.0081219673 2221 1311867792.7254660130 0.1549301296 0.1228985844 0.2376661599 0.0046822854 0.0109390000 0.0003920000 0.0025310000 0.0000030000 0.0000040000 0.0021430000 43847829 96830484 509673472 3.7419614792 3.9547266960 4.0075836182 2222 1311867792.7574810982 0.1552273184 0.1229131338 0.2376661599 0.0046812386 0.0147680000 0.0004860000 0.0044080000 0.0000010000 0.0000080000 0.0012300000 43851501 96830484 509673472 3.7410962582 3.9545836449 4.0077595711 2223 1311867792.7968890667 0.1549214870 0.1229275325 0.2376661599 0.0046809388 0.0108380000 0.0004030000 0.0028840000 0.0000050000 0.0000040000 0.0014320000 43855397 96830484 509673472 3.7409346104 3.9548485279 4.0076274872 2224 1311867792.8254449368 0.1569881439 0.1229428475 0.2376661599 0.0046809852 0.0106030000 0.0003970000 0.0031800000 0.0000000000 0.0000030000 0.0011630000 43858901 96830484 509673472 3.7386705875 3.9544110298 4.0083832741 2225 1311867792.8578031063 0.1559892148 0.1229576998 0.2376661599 0.0046811608 0.0153260000 0.0004930000 0.0030900000 0.0000110000 0.0000090000 0.0023030000 43862573 96830484 509673472 3.7389721870 3.9548473358 4.0081257820 2226 1311867792.8974819183 0.1528628170 0.1229711343 0.2376661599 0.0046805775 0.0107040000 0.0003960000 0.0025440000 0.0000000000 0.0000040000 0.0011730000 43866525 96830484 509673472 3.7413439751 3.9555037022 4.0075445175 2227 1311867792.9254279137 0.1523884088 0.1229843437 0.2376661599 0.0046796176 0.0108270000 0.0003820000 0.0031760000 0.0000040000 0.0000040000 0.0014180000 43870029 96830484 509673472 3.7415409088 3.9553098679 4.0076017380 2228 1311867792.9580180645 0.1556378901 0.1229989997 0.2376661599 0.0046813505 0.0101350000 0.0003840000 0.0028460000 0.0000000000 0.0000030000 0.0011650000 43873757 96830484 509673472 3.7379701138 3.9556872845 4.0076899529 2229 1311867792.9958879948 0.1554460227 0.1230135564 0.2376661599 0.0046813649 0.0125410000 0.0003820000 0.0041880000 0.0000030000 0.0000040000 0.0021580000 43877597 96830484 509673472 3.7372477055 3.9554138184 4.0081391335 2230 1311867793.0254249573 0.1532673240 0.1230271231 0.2376661599 0.0046814971 0.0150510000 0.0004720000 0.0044460000 0.0000010000 0.0000080000 0.0012980000 43881157 96830484 509673472 3.7387585640 3.9556374550 4.0077590942 2231 1311867793.0575890541 0.1526015550 0.1230403793 0.2376661599 0.0046812181 0.0120240000 0.0003930000 0.0041970000 0.0000050000 0.0000040000 0.0014430000 43884829 96830484 509673472 3.7385683060 3.9559516907 4.0076971054 2232 1311867793.0956139565 0.1563752145 0.1230553142 0.2376661599 0.0046806675 0.0109550000 0.0003740000 0.0035020000 0.0000000000 0.0000030000 0.0011650000 43888725 96830484 509673472 3.7340049744 3.9556384087 4.0085754395 2233 1311867793.1253910065 0.1548912227 0.1230695712 0.2376661599 0.0046802175 0.0136750000 0.0003700000 0.0041710000 0.0000040000 0.0000030000 0.0027080000 43892285 96830484 509673472 3.7350568771 3.9561076164 4.0084404945 2234 1311867793.1573770046 0.1554571092 0.1230840688 0.2376661599 0.0046798167 0.0120220000 0.0003760000 0.0041490000 0.0000010000 0.0000030000 0.0011690000 43895957 96830484 509673472 3.7341122627 3.9572136402 4.0090794563 2235 1311867793.1934790611 0.1566086709 0.1230990686 0.2376661599 0.0046794900 0.0117150000 0.0003710000 0.0038320000 0.0000040000 0.0000030000 0.0014540000 43899741 96830484 509673472 3.7323136330 3.9555535316 4.0092725754 2236 1311867793.2255470753 0.1556884944 0.1231136435 0.2376661599 0.0046784883 0.0104330000 0.0003690000 0.0028270000 0.0000000000 0.0000030000 0.0011780000 43903413 96830484 509673472 3.7329597473 3.9562470913 4.0095901489 2237 1311867793.2574770451 0.1584643722 0.1231294462 0.2376661599 0.0046775032 0.0128070000 0.0003740000 0.0041580000 0.0000040000 0.0000040000 0.0021720000 43907029 96830484 509673472 3.7298383713 3.9557681084 4.0101785660 2238 1311867793.2951428890 0.1571010053 0.1231446257 0.2376661599 0.0046770375 0.0117740000 0.0003670000 0.0041590000 0.0000010000 0.0000040000 0.0011760000 43910925 96830484 509673472 3.7304391861 3.9561049938 4.0100631714 2239 1311867793.3254458904 0.1573074460 0.1231598837 0.2376661599 0.0046762471 0.0104990000 0.0003700000 0.0028370000 0.0000030000 0.0000040000 0.0014500000 43914541 96830484 509673472 3.7300662994 3.9554417133 4.0106906891 2240 1311867793.3620529175 0.1540715396 0.1231736836 0.2376661599 0.0046762289 0.0143590000 0.0004830000 0.0030680000 0.0000010000 0.0000080000 0.0013020000 43918381 96830484 509673472 3.7327136993 3.9566960335 4.0100078583 2241 1311867793.3934969902 0.1539986730 0.1231874386 0.2376661599 0.0046752784 0.0116990000 0.0003770000 0.0028650000 0.0000040000 0.0000040000 0.0021830000 43921997 96830484 509673472 3.7322306633 3.9567477703 4.0102181435 2242 1311867793.4254410267 0.1502370983 0.1231995036 0.2376661599 0.0046776617 0.0104080000 0.0003630000 0.0028380000 0.0000010000 0.0000040000 0.0011790000 43925669 96830484 509673472 3.7355508804 3.9579284191 4.0098295212 2243 1311867793.4615969658 0.1501570940 0.1232115221 0.2376661599 0.0046775018 0.0160170000 0.0004680000 0.0044390000 0.0000070000 0.0000070000 0.0015580000 43929453 96830484 509673472 3.7353258133 3.9572987556 4.0101914406 2244 1311867793.4961650372 0.1480364054 0.1232225849 0.2376661599 0.0046765750 0.0153860000 0.0004650000 0.0044110000 0.0000010000 0.0000070000 0.0012990000 43933069 96830484 509673472 3.7370669842 3.9586789608 4.0100760460 2245 1311867793.5258960724 0.1428037286 0.1232313070 0.2376661599 0.0046783538 0.0129010000 0.0003760000 0.0041740000 0.0000040000 0.0000040000 0.0021850000 43936685 96830484 509673472 3.7421791553 3.9585742950 4.0098118782 2246 1311867793.5653350353 0.1423363686 0.1232398133 0.2376661599 0.0046776450 0.0107280000 0.0003560000 0.0031470000 0.0000010000 0.0000040000 0.0011810000 43940581 96830484 509673472 3.7422540188 3.9591233730 4.0098757744 2247 1311867793.5951368809 0.1412133723 0.1232478122 0.2376661599 0.0046772412 0.0119660000 0.0003630000 0.0041410000 0.0000040000 0.0000040000 0.0014600000 43944085 96830484 509673472 3.7433781624 3.9595587254 4.0098733902 2248 1311867793.6255569458 0.1403787881 0.1232554327 0.2376661599 0.0046765603 0.0118070000 0.0003590000 0.0041470000 0.0000010000 0.0000040000 0.0011860000 43947757 96830484 509673472 3.7439496517 3.9598979950 4.0100150108 2249 1311867793.6641399860 0.1393421590 0.1232625856 0.2376661599 0.0046758338 0.0114100000 0.0003610000 0.0028460000 0.0000030000 0.0000030000 0.0021750000 43951541 96830484 509673472 3.7446403503 3.9601256847 4.0101060867 2250 1311867793.6930859089 0.1361156106 0.1232682980 0.2376661599 0.0046808322 0.0117280000 0.0003560000 0.0041380000 0.0000010000 0.0000040000 0.0011760000 43955157 96830484 509673472 3.7472989559 3.9604792595 4.0090875626 2251 1311867793.7268340588 0.1332168728 0.1232727176 0.2376661599 0.0046803076 0.0121220000 0.0003620000 0.0041560000 0.0000030000 0.0000030000 0.0014600000 43958941 96830484 509673472 3.7498724461 3.9612112045 4.0086746216 2252 1311867793.7666549683 0.1299600154 0.1232756871 0.2376661599 0.0046795659 0.0114530000 0.0003580000 0.0038230000 0.0000010000 0.0000040000 0.0011770000 43962781 96830484 509673472 3.7524037361 3.9620685577 4.0080070496 2253 1311867793.7944359779 0.1256388873 0.1232767360 0.2376661599 0.0046831364 0.0110820000 0.0003580000 0.0024970000 0.0000040000 0.0000040000 0.0021350000 43966285 96830484 509673472 3.7565569878 3.9629261494 4.0070552826 2254 1311867793.8265230656 0.1270605028 0.1232784147 0.2376661599 0.0046822616 0.0111310000 0.0003600000 0.0034990000 0.0000010000 0.0000040000 0.0011720000 43970013 96830484 509673472 3.7544796467 3.9631118774 4.0071167946 2255 1311867793.8667359352 0.1264320463 0.1232798132 0.2376661599 0.0046816742 0.0102910000 0.0003580000 0.0024930000 0.0000040000 0.0000030000 0.0014410000 43973965 96830484 509673472 3.7547602654 3.9626324177 4.0071401596 2256 1311867793.8930900097 0.1206982210 0.1232786689 0.2376661599 0.0046835284 0.0104710000 0.0003630000 0.0028120000 0.0000010000 0.0000040000 0.0011720000 43977469 96830484 509673472 3.7603948116 3.9637086391 4.0064744949 2257 1311867793.9269030094 0.1218461767 0.1232780342 0.2376661599 0.0046825785 0.0202470000 0.0005430000 0.0032650000 0.0000150000 0.0000140000 0.0027990000 43981197 96830484 509673472 3.7585487366 3.9631345272 4.0066013336 2258 1311867793.9623370171 0.1201061681 0.1232766295 0.2376661599 0.0046820322 0.0112890000 0.0003880000 0.0025520000 0.0000000000 0.0000050000 0.0011920000 43984869 96830484 509673472 3.7597482204 3.9638571739 4.0063567162 2259 1311867793.9955279827 0.1204345897 0.1232753714 0.2376661599 0.0046815386 0.0119970000 0.0003630000 0.0041500000 0.0000040000 0.0000030000 0.0014540000 43988653 96830484 509673472 3.7586538792 3.9644608498 4.0060176849 2260 1311867794.0277070999 0.1209416538 0.1232743388 0.2376661599 0.0046813069 0.0118450000 0.0003610000 0.0041510000 0.0000000000 0.0000040000 0.0011720000 43992325 96830484 509673472 3.7575726509 3.9647419453 4.0063548088 2261 1311867794.0608921051 0.1211559251 0.1232734019 0.2376661599 0.0046803444 0.0126820000 0.0003580000 0.0041640000 0.0000040000 0.0000040000 0.0021370000 43995997 96830484 509673472 3.7569630146 3.9653680325 4.0064268112 2262 1311867794.0951509476 0.1189295799 0.1232714815 0.2376661599 0.0046793886 0.0117280000 0.0003600000 0.0041730000 0.0000010000 0.0000030000 0.0011600000 43999725 96830484 509673472 3.7589380741 3.9670143127 4.0060348511 2263 1311867794.1269369125 0.1184471548 0.1232693497 0.2376661599 0.0046796913 0.0141200000 0.0004590000 0.0027050000 0.0000070000 0.0000070000 0.0015260000 44003453 96830484 509673472 3.7590548992 3.9670464993 4.0059151649 2264 1311867794.1632831097 0.1162391752 0.1232662445 0.2376661599 0.0046794533 0.0151290000 0.0004630000 0.0040680000 0.0000010000 0.0000080000 0.0012690000 44007237 96830484 509673472 3.7608938217 3.9693508148 4.0059437752 2265 1311867794.1936271191 0.1192194894 0.1232644578 0.2376661599 0.0046792152 0.0129200000 0.0003750000 0.0042030000 0.0000040000 0.0000040000 0.0021300000 44010797 96830484 509673472 3.7575435638 3.9695849419 4.0064764023 2266 1311867794.2258520126 0.1197526157 0.1232629080 0.2376661599 0.0046782493 0.0117390000 0.0003580000 0.0041600000 0.0000010000 0.0000040000 0.0011550000 44014469 96830484 509673472 3.7566888332 3.9701511860 4.0071096420 2267 1311867794.2619779110 0.1185251102 0.1232608181 0.2376661599 0.0046778772 0.0119930000 0.0003720000 0.0041610000 0.0000030000 0.0000030000 0.0014160000 44018253 96830484 509673472 3.7574687004 3.9702248573 4.0068755150 2268 1311867794.2955250740 0.1183520183 0.1232586538 0.2376661599 0.0046769952 0.0118910000 0.0003800000 0.0041800000 0.0000000000 0.0000040000 0.0011510000 44021925 96830484 509673472 3.7574198246 3.9715662003 4.0070419312 2269 1311867794.3254759312 0.1198330969 0.1232571440 0.2376661599 0.0046764434 0.0126770000 0.0003680000 0.0041650000 0.0000040000 0.0000040000 0.0020870000 44025541 96830484 509673472 3.7556569576 3.9723050594 4.0077838898 2270 1311867794.3628959656 0.1192132086 0.1232553626 0.2376661599 0.0046764212 0.0109160000 0.0003750000 0.0031720000 0.0000000000 0.0000040000 0.0011590000 44029381 96830484 509673472 3.7558312416 3.9733474255 4.0077643394 2271 1311867794.3958311081 0.1203513741 0.1232540838 0.2376661599 0.0046755641 0.0117270000 0.0003760000 0.0038400000 0.0000030000 0.0000030000 0.0014210000 44033109 96830484 509673472 3.7543699741 3.9733037949 4.0083141327 2272 1311867794.4267809391 0.1194882691 0.1232524264 0.2376661599 0.0046747551 0.0163510000 0.0004790000 0.0044500000 0.0000020000 0.0000080000 0.0012540000 44036781 96830484 509673472 3.7548713684 3.9745876789 4.0081219673 2273 1311867794.4620559216 0.1205323935 0.1232512297 0.2376661599 0.0046738140 0.0182000000 0.0005610000 0.0040020000 0.0000150000 0.0000140000 0.0029190000 44040565 96830484 509673472 3.7533295155 3.9749493599 4.0083036423 2274 1311867794.4987208843 0.1203982010 0.1232499751 0.2376661599 0.0046728631 0.0128290000 0.0004290000 0.0040660000 0.0000010000 0.0000040000 0.0011510000 44044293 96830484 509673472 3.7530174255 3.9759962559 4.0082311630 2275 1311867794.5290880203 0.1195854843 0.1232483643 0.2376661599 0.0046723969 0.0105700000 0.0004180000 0.0025190000 0.0000040000 0.0000030000 0.0014270000 44047909 96830484 509673472 3.7532708645 3.9763426781 4.0080170631 2276 1311867794.5637059212 0.1187007055 0.1232463662 0.2376661599 0.0046720923 0.0162430000 0.0004690000 0.0044700000 0.0000000000 0.0000080000 0.0012550000 44051637 96830484 509673472 3.7535626888 3.9763088226 4.0079412460 2277 1311867794.5940639973 0.1200687513 0.1232449707 0.2376661599 0.0046716906 0.0161790000 0.0004700000 0.0044230000 0.0000080000 0.0000070000 0.0022510000 44055309 96830484 509673472 3.7516667843 3.9762423038 4.0081462860 2278 1311867794.6319000721 0.1181251481 0.1232427232 0.2376661599 0.0046714604 0.0119680000 0.0003840000 0.0041970000 0.0000000000 0.0000040000 0.0011400000 44059093 96830484 509673472 3.7531793118 3.9773774147 4.0075459480 2279 1311867794.6658101082 0.1194237694 0.1232410474 0.2376661599 0.0046714484 0.0119820000 0.0003730000 0.0041810000 0.0000040000 0.0000030000 0.0014240000 44062821 96830484 509673472 3.7516508102 3.9778735638 4.0079360008 2280 1311867794.6949920654 0.1190567240 0.1232392122 0.2376661599 0.0046711366 0.0107420000 0.0003740000 0.0031740000 0.0000010000 0.0000040000 0.0011390000 44066437 96830484 509673472 3.7516455650 3.9780547619 4.0079636574 2281 1311867794.7305591106 0.1173683032 0.1232366384 0.2376661599 0.0046711917 0.0120440000 0.0003820000 0.0035130000 0.0000040000 0.0000030000 0.0020770000 44070221 96830484 509673472 3.7529952526 3.9788420200 4.0075445175 2282 1311867794.7625899315 0.1188505217 0.1232347163 0.2376661599 0.0046702594 0.0118560000 0.0003760000 0.0041850000 0.0000010000 0.0000040000 0.0011310000 44073837 96830484 509673472 3.7512421608 3.9793648720 4.0076961517 2283 1311867794.7959010601 0.1191150844 0.1232329119 0.2376661599 0.0046693406 0.0164250000 0.0004700000 0.0044840000 0.0000080000 0.0000070000 0.0015110000 44077565 96830484 509673472 3.7507247925 3.9796221256 4.0077934265 2284 1311867794.8306028843 0.1176223233 0.1232304554 0.2376661599 0.0046697273 0.0111720000 0.0003930000 0.0028670000 0.0000000000 0.0000040000 0.0011490000 44081293 96830484 509673472 3.7520782948 3.9797754288 4.0076403618 2285 1311867794.8631660938 0.1197708920 0.1232289413 0.2376661599 0.0046688628 0.0120580000 0.0003770000 0.0035060000 0.0000040000 0.0000040000 0.0020980000 44084853 96830484 509673472 3.7496833801 3.9807760715 4.0078191757 2286 1311867794.8947780132 0.1193494573 0.1232272443 0.2376661599 0.0046680382 0.0104690000 0.0003760000 0.0028500000 0.0000010000 0.0000040000 0.0011420000 44088525 96830484 509673472 3.7499437332 3.9808394909 4.0078182220 2287 1311867794.9343950748 0.1206508279 0.1232261177 0.2376661599 0.0046672633 0.0116720000 0.0003670000 0.0038310000 0.0000040000 0.0000040000 0.0014250000 44092421 96830484 509673472 3.7481973171 3.9810318947 4.0080823898 2288 1311867794.9646499157 0.1186867207 0.1232241337 0.2376661599 0.0046666309 0.0103810000 0.0003760000 0.0028270000 0.0000000000 0.0000040000 0.0011470000 44096037 96830484 509673472 3.7499325275 3.9818284512 4.0075440407 2289 1311867794.9988350868 0.1182824001 0.1232219748 0.2376661599 0.0046661649 0.0127820000 0.0003640000 0.0041710000 0.0000040000 0.0000040000 0.0021270000 44099821 96830484 509673472 3.7500219345 3.9825391769 4.0072989464 2290 1311867795.0307559967 0.1185130179 0.1232199185 0.2376661599 0.0046652952 0.0116900000 0.0003650000 0.0041650000 0.0000000000 0.0000030000 0.0011670000 44103437 96830484 509673472 3.7496480942 3.9832308292 4.0074396133 2291 1311867795.0651550293 0.1170995906 0.1232172471 0.2376661599 0.0046644016 0.0119840000 0.0003630000 0.0041590000 0.0000030000 0.0000030000 0.0014300000 44107165 96830484 509673472 3.7507078648 3.9840991497 4.0073204041 2292 1311867795.0993340015 0.1158452109 0.1232140306 0.2376661599 0.0046636709 0.0104610000 0.0003670000 0.0028330000 0.0000010000 0.0000040000 0.0011620000 44110893 96830484 509673472 3.7516560555 3.9849214554 4.0069890022 2293 1311867795.1310648918 0.1168015823 0.1232112341 0.2376661599 0.0046626702 0.0168470000 0.0004560000 0.0044420000 0.0000080000 0.0000070000 0.0023170000 44114621 96830484 509673472 3.7505519390 3.9855091572 4.0073022842 2294 1311867795.1630289555 0.1171685234 0.1232086000 0.2376661599 0.0046619961 0.0110730000 0.0003760000 0.0028750000 0.0000000000 0.0000040000 0.0011650000 44118237 96830484 509673472 3.7498707771 3.9855735302 4.0074276924 2295 1311867795.1945760250 0.1172699705 0.1232060123 0.2376661599 0.0046610507 0.0121980000 0.0003610000 0.0041620000 0.0000030000 0.0000030000 0.0014250000 44121965 96830484 509673472 3.7491941452 3.9852702618 4.0073423386 2296 1311867795.2313210964 0.1176605523 0.1232035971 0.2376661599 0.0046601352 0.0123600000 0.0004150000 0.0041790000 0.0000000000 0.0000040000 0.0011590000 44125749 96830484 509673472 3.7484872341 3.9863305092 4.0071511269 2297 1311867795.2631359100 0.1190953851 0.1232018085 0.2376661599 0.0046591355 0.0129900000 0.0004220000 0.0041660000 0.0000040000 0.0000040000 0.0021460000 44129421 96830484 509673472 3.7467095852 3.9856677055 4.0072808266 2298 1311867795.2958068848 0.1186579689 0.1231998312 0.2376661599 0.0046582032 0.0118710000 0.0003720000 0.0041650000 0.0000000000 0.0000040000 0.0011550000 44133149 96830484 509673472 3.7469139099 3.9853806496 4.0071415901 2299 1311867795.3314220905 0.1169109046 0.1231970957 0.2376661599 0.0046574228 0.0281990000 0.0005660000 0.0043370000 0.0000140000 0.0000150000 0.0018970000 44136877 96830484 509673472 3.7484023571 3.9867503643 4.0065755844 2300 1311867795.3670549393 0.1172509715 0.1231945105 0.2376661599 0.0046571131 0.0139360000 0.0004290000 0.0042840000 0.0000010000 0.0000070000 0.0011900000 44140773 96830484 509673472 3.7480437756 3.9869961739 4.0067787170 2301 1311867795.3950240612 0.1156456172 0.1231912298 0.2376661599 0.0046572730 0.0122780000 0.0003720000 0.0035200000 0.0000040000 0.0000040000 0.0021540000 44144277 96830484 509673472 3.7492368221 3.9877779484 4.0063834190 2302 1311867795.4294250011 0.1160303503 0.1231881190 0.2376661599 0.0046564854 0.0118110000 0.0003620000 0.0041640000 0.0000010000 0.0000040000 0.0011640000 44148061 96830484 509673472 3.7486300468 3.9880862236 4.0065526962 2303 1311867795.4614660740 0.1148210838 0.1231844859 0.2376661599 0.0046564441 0.0120680000 0.0003750000 0.0041690000 0.0000040000 0.0000040000 0.0014310000 44151845 96830484 509673472 3.7502739429 3.9891281128 4.0063238144 2304 1311867795.4961009026 0.1139700785 0.1231804866 0.2376661599 0.0046555196 0.0127760000 0.0005490000 0.0046650000 0.0000010000 0.0000040000 0.0011530000 44155629 96830484 509673472 3.7511506081 3.9896950722 4.0061721802 2305 1311867795.5292580128 0.1142871976 0.1231766284 0.2376661599 0.0046546107 0.0107210000 0.0003620000 0.0018450000 0.0000040000 0.0000030000 0.0021300000 44159357 96830484 509673472 3.7508056164 3.9903168678 4.0065236092 2306 1311867795.5632829666 0.1125285551 0.1231720108 0.2376661599 0.0046539918 0.0117500000 0.0003710000 0.0038400000 0.0000010000 0.0000040000 0.0011600000 44163197 96830484 509673472 3.7526731491 3.9917361736 4.0062308311 2307 1311867795.5938069820 0.1117144302 0.1231670444 0.2376661599 0.0046531371 0.0124030000 0.0003680000 0.0041910000 0.0000040000 0.0000040000 0.0014190000 44166869 96830484 509673472 3.7538738251 3.9920659065 4.0063290596 2308 1311867795.6295180321 0.1117372140 0.1231620921 0.2376661599 0.0046522571 0.0110720000 0.0003730000 0.0031880000 0.0000000000 0.0000030000 0.0011610000 44170709 96830484 509673472 3.7539875507 3.9935450554 4.0063977242 2309 1311867795.6619150639 0.1122298017 0.1231573575 0.2376661599 0.0046518427 0.0116740000 0.0003740000 0.0028460000 0.0000040000 0.0000030000 0.0021240000 44174437 96830484 509673472 3.7537727356 3.9938480854 4.0067934990 2310 1311867795.6935899258 0.1091909111 0.1231513114 0.2376661599 0.0046508948 0.0120070000 0.0003740000 0.0041810000 0.0000010000 0.0000040000 0.0011530000 44178109 96830484 509673472 3.7570879459 3.9964656830 4.0062313080 2311 1311867795.7300128937 0.1112966612 0.1231461817 0.2376661599 0.0046509733 0.0105630000 0.0003740000 0.0025030000 0.0000040000 0.0000040000 0.0014120000 44182005 96830484 509673472 3.7553868294 3.9969077110 4.0065217018 2312 1311867795.7627360821 0.1099971458 0.1231404944 0.2376661599 0.0046502723 0.0120890000 0.0003820000 0.0041770000 0.0000000000 0.0000030000 0.0011450000 44185789 96830484 509673472 3.7570679188 3.9979529381 4.0064668655 2313 1311867795.7993569374 0.1101851538 0.1231348933 0.2376661599 0.0046498193 0.0130230000 0.0003780000 0.0041900000 0.0000040000 0.0000040000 0.0021220000 44189629 96830484 509673472 3.7568957806 3.9993343353 4.0067753792 2314 1311867795.8297359943 0.1130300164 0.1231305265 0.2376661599 0.0046491316 0.0158980000 0.0004840000 0.0037890000 0.0000020000 0.0000080000 0.0012770000 44193301 96830484 509673472 3.7539653778 3.9995393753 4.0071964264 2315 1311867795.8630819321 0.1106727570 0.1231251452 0.2376661599 0.0046487941 0.0112380000 0.0003940000 0.0028670000 0.0000040000 0.0000040000 0.0014270000 44197085 96830484 509673472 3.7564640045 3.9997789860 4.0066566467 2316 1311867795.9011631012 0.1111288816 0.1231199654 0.2376661599 0.0046479442 0.0099500000 0.0003790000 0.0021770000 0.0000010000 0.0000040000 0.0011560000 44200981 96830484 509673472 3.7561302185 4.0009465218 4.0067257881 2317 1311867795.9300799370 0.1118976027 0.1231151219 0.2376661599 0.0046469617 0.0105830000 0.0003760000 0.0018430000 0.0000040000 0.0000040000 0.0021220000 44204597 96830484 509673472 3.7554550171 4.0009431839 4.0069336891 2318 1311867795.9624390602 0.1110384315 0.1231099120 0.2376661599 0.0046461410 0.0120390000 0.0003860000 0.0041760000 0.0000000000 0.0000030000 0.0011470000 44208325 96830484 509673472 3.7563884258 4.0013060570 4.0064892769 2319 1311867796.0000178814 0.1121371463 0.1231051803 0.2376661599 0.0046452500 0.0123230000 0.0003800000 0.0041730000 0.0000040000 0.0000040000 0.0014190000 44212221 96830484 509673472 3.7554924488 4.0008611679 4.0065188408 2320 1311867796.0296399593 0.1118836924 0.1231003434 0.2376661599 0.0046442962 0.0106700000 0.0003790000 0.0028310000 0.0000000000 0.0000040000 0.0011580000 44215837 96830484 509673472 3.7558233738 4.0006771088 4.0063652992 2321 1311867796.0617599487 0.1117975712 0.1230954737 0.2376661599 0.0046438050 0.0117670000 0.0003770000 0.0028370000 0.0000040000 0.0000030000 0.0021310000 44219621 96830484 509673472 3.7561385632 4.0013260841 4.0064549446 2322 1311867796.0984148979 0.1094763726 0.1230896084 0.2376661599 0.0046430429 0.0120600000 0.0003800000 0.0041720000 0.0000000000 0.0000030000 0.0011550000 44223405 96830484 509673472 3.7585191727 4.0024113655 4.0057959557 2323 1311867796.1296660900 0.1111671105 0.1230844760 0.2376661599 0.0046422159 0.0124820000 0.0003890000 0.0041660000 0.0000030000 0.0000040000 0.0014140000 44226965 96830484 509673472 3.7569634914 4.0024480820 4.0059742928 2324 1311867796.1618049145 0.1106641144 0.1230791317 0.2376661599 0.0046412587 0.0106930000 0.0003790000 0.0028430000 0.0000000000 0.0000040000 0.0011530000 44230693 96830484 509673472 3.7576029301 4.0021276474 4.0060248375 2325 1311867796.1990590096 0.1088413075 0.1230730079 0.2376661599 0.0046407138 0.0130120000 0.0003810000 0.0041840000 0.0000040000 0.0000040000 0.0021160000 44234589 96830484 509673472 3.7597506046 4.0034823418 4.0057916641 2326 1311867796.2292931080 0.1093684286 0.1230671159 0.2376661599 0.0046397262 0.0100410000 0.0003830000 0.0021770000 0.0000010000 0.0000040000 0.0011680000 44238261 96830484 509673472 3.7592561245 4.0032973289 4.0059051514 2327 1311867796.2631280422 0.1104530990 0.1230616952 0.2376661599 0.0046387673 0.0103880000 0.0003820000 0.0021720000 0.0000030000 0.0000030000 0.0014390000 44241989 96830484 509673472 3.7584185600 4.0033111572 4.0059981346 2328 1311867796.3010690212 0.1093569398 0.1230558083 0.2376661599 0.0046378195 0.0100100000 0.0003770000 0.0021760000 0.0000000000 0.0000040000 0.0011560000 44245829 96830484 509673472 3.7599558830 4.0041756630 4.0059332848 2329 1311867796.3299860954 0.1084699929 0.1230495456 0.2376661599 0.0046368289 0.0111400000 0.0003810000 0.0021720000 0.0000040000 0.0000040000 0.0021350000 44249445 96830484 509673472 3.7611851692 4.0044445992 4.0057415962 2330 1311867796.3619849682 0.1104832590 0.1230441524 0.2376661599 0.0046363978 0.0113350000 0.0003850000 0.0035170000 0.0000010000 0.0000040000 0.0011560000 44253229 96830484 509673472 3.7594482899 4.0042691231 4.0062618256 2331 1311867796.3998959064 0.1092446893 0.1230382324 0.2376661599 0.0046354986 0.0119080000 0.0003860000 0.0038420000 0.0000040000 0.0000030000 0.0014160000 44256957 96830484 509673472 3.7612078190 4.0049123764 4.0062174797 2332 1311867796.4297831059 0.1099412143 0.1230326162 0.2376661599 0.0046345172 0.0097620000 0.0003890000 0.0018410000 0.0000000000 0.0000030000 0.0011490000 44260629 96830484 509673472 3.7607822418 4.0045118332 4.0064201355 2333 1311867796.4618980885 0.1118307710 0.1230278147 0.2376661599 0.0046336833 0.0131170000 0.0003820000 0.0041820000 0.0000030000 0.0000030000 0.0021300000 44264413 96830484 509673472 3.7589852810 4.0042495728 4.0067744255 2334 1311867796.5018439293 0.1102306396 0.1230223317 0.2376661599 0.0046332687 0.0127750000 0.0003780000 0.0020770000 0.0000010000 0.0000040000 0.0012510000 44268365 96830484 509673472 3.7609126568 4.0044903755 4.0066094398 2335 1311867796.5301249027 0.1102019250 0.1230168412 0.2376661599 0.0046323167 0.0121110000 0.0004270000 0.0018600000 0.0000050000 0.0000030000 0.0014320000 44271981 96830484 509673472 3.7611618042 4.0047507286 4.0065670013 2336 1311867796.5621480942 0.1118381768 0.1230120558 0.2376661599 0.0046314629 0.0112250000 0.0004380000 0.0025440000 0.0000000000 0.0000040000 0.0011490000 44275709 96830484 509673472 3.7598557472 4.0045471191 4.0071077347 2337 1311867796.6018888950 0.1107830405 0.1230068230 0.2376661599 0.0046306991 0.0135700000 0.0004270000 0.0041890000 0.0000050000 0.0000040000 0.0021150000 44279661 96830484 509673472 3.7614848614 4.0051164627 4.0071716309 2338 1311867796.6323978901 0.1063807309 0.1229997118 0.2376661599 0.0046306174 0.0120230000 0.0003960000 0.0038680000 0.0000000000 0.0000040000 0.0011630000 44283333 96830484 509673472 3.7663464546 4.0059852600 4.0063138008 2339 1311867796.6659901142 0.1086353436 0.1229935706 0.2376661599 0.0046309308 0.0109920000 0.0003840000 0.0028580000 0.0000030000 0.0000030000 0.0014150000 44287117 96830484 509673472 3.7645931244 4.0062561035 4.0070276260 2340 1311867796.7025029659 0.1087624207 0.1229874889 0.2376661599 0.0046300239 0.0107050000 0.0003890000 0.0028620000 0.0000010000 0.0000040000 0.0011450000 44290845 96830484 509673472 3.7648525238 4.0061893463 4.0070581436 2341 1311867796.7335898876 0.1093653217 0.1229816699 0.2376661599 0.0046295364 0.0131080000 0.0003810000 0.0042070000 0.0000040000 0.0000030000 0.0021140000 44294517 96830484 509673472 3.7651054859 4.0061597824 4.0073776245 2342 1311867796.7634348869 0.1080520302 0.1229752952 0.2376661599 0.0046285626 0.0155780000 0.0004870000 0.0044540000 0.0000010000 0.0000070000 0.0012670000 44298245 96830484 509673472 3.7669451237 4.0068063736 4.0073037148 2343 1311867796.7990939617 0.1094842628 0.1229695372 0.2376661599 0.0046290012 0.0109170000 0.0003990000 0.0025410000 0.0000040000 0.0000040000 0.0014250000 44302029 96830484 509673472 3.7660186291 4.0076522827 4.0082335472 2344 1311867796.8303010464 0.1114391685 0.1229646181 0.2376661599 0.0046290835 0.0111800000 0.0003860000 0.0032010000 0.0000000000 0.0000040000 0.0011430000 44305757 96830484 509673472 3.7645180225 4.0074338913 4.0091772079 2345 1311867796.8626410961 0.1094259024 0.1229588446 0.2376661599 0.0046281798 0.0131430000 0.0003940000 0.0042260000 0.0000030000 0.0000040000 0.0021050000 44309429 96830484 509673472 3.7672173977 4.0084271431 4.0093717575 2346 1311867796.8988420963 0.1150744557 0.1229554838 0.2376661599 0.0046287497 0.0105480000 0.0003960000 0.0025520000 0.0000010000 0.0000040000 0.0011410000 44313269 96830484 509673472 3.7623126507 4.0082330704 4.0109186172 2347 1311867796.9308090210 0.1160449609 0.1229525394 0.2376661599 0.0046278985 0.0121880000 0.0003890000 0.0039030000 0.0000040000 0.0000040000 0.0014230000 44316997 96830484 509673472 3.7618587017 4.0078816414 4.0115108490 2348 1311867796.9623529911 0.1179521382 0.1229504098 0.2376661599 0.0046272068 0.0122460000 0.0004020000 0.0042510000 0.0000010000 0.0000030000 0.0011350000 44320725 96830484 509673472 3.7604115009 4.0080027580 4.0124707222 2349 1311867796.9994709492 0.1161485910 0.1229475142 0.2376661599 0.0046264656 0.0116020000 0.0003920000 0.0025550000 0.0000030000 0.0000030000 0.0021050000 44324565 96830484 509673472 3.7627618313 4.0077896118 4.0126647949 2350 1311867797.0328159332 0.1179137602 0.1229453721 0.2376661599 0.0046264182 0.0121490000 0.0003970000 0.0042550000 0.0000010000 0.0000040000 0.0011440000 44328237 96830484 509673472 3.7610962391 4.0080609322 4.0131106377 2351 1311867797.0733079910 0.1196556017 0.1229439728 0.2376661599 0.0046255517 0.0108320000 0.0004120000 0.0025530000 0.0000030000 0.0000030000 0.0014090000 44332301 96830484 509673472 3.7599184513 4.0072498322 4.0140891075 2352 1311867797.0992720127 0.1209251732 0.1229431145 0.2376661599 0.0046249687 0.0104820000 0.0003950000 0.0025540000 0.0000000000 0.0000030000 0.0011320000 44335805 96830484 509673472 3.7589414120 4.0073552132 4.0148596764 2353 1311867797.1336839199 0.1228983700 0.1229430955 0.2376661599 0.0046264805 0.0117800000 0.0004000000 0.0029100000 0.0000040000 0.0000030000 0.0020800000 44339645 96830484 509673472 3.7573935986 4.0074148178 4.0159115791 2354 1311867797.1708030701 0.1251659989 0.1229440398 0.2376661599 0.0046265084 0.0123300000 0.0004030000 0.0042640000 0.0000010000 0.0000040000 0.0011310000 44343485 96830484 509673472 3.7556204796 4.0074872971 4.0167994499 2355 1311867797.1996591091 0.1265568584 0.1229455739 0.2376661599 0.0046265856 0.0154020000 0.0004920000 0.0027960000 0.0000100000 0.0000100000 0.0015000000 44347101 96830484 509673472 3.7546589375 4.0081892014 4.0175194740 2356 1311867797.2372090816 0.1263346821 0.1229470124 0.2376661599 0.0046258342 0.0127160000 0.0004140000 0.0043310000 0.0000000000 0.0000040000 0.0011390000 44351053 96830484 509673472 3.7555611134 4.0085868835 4.0179595947 2357 1311867797.2708179951 0.1281185150 0.1229492065 0.2376661599 0.0046261709 0.0115800000 0.0003990000 0.0025660000 0.0000040000 0.0000030000 0.0020730000 44354781 96830484 509673472 3.7541596889 4.0091753006 4.0191955566 2358 1311867797.3019850254 0.1288172156 0.1229516951 0.2376661599 0.0046256791 0.0134540000 0.0003980000 0.0044590000 0.0000010000 0.0000050000 0.0013970000 44358509 96830484 509673472 3.7538673878 4.0093626976 4.0201859474 2359 1311867797.3296120167 0.1271626800 0.1229534801 0.2376661599 0.0046250851 0.0127220000 0.0003960000 0.0044120000 0.0000040000 0.0000040000 0.0013990000 44362069 96830484 509673472 3.7556464672 4.0094270706 4.0203771591 2360 1311867797.3703179359 0.1273776591 0.1229553548 0.2376661599 0.0046245224 0.0119380000 0.0003970000 0.0039290000 0.0000010000 0.0000040000 0.0011260000 44366021 96830484 509673472 3.7552645206 4.0101332664 4.0207977295 2361 1311867797.3999080658 0.1291694343 0.1229579868 0.2376661599 0.0046238953 0.0170580000 0.0004990000 0.0045370000 0.0000090000 0.0000080000 0.0022300000 44369693 96830484 509673472 3.7534255981 4.0100679398 4.0216860771 2362 1311867797.4322440624 0.1271819919 0.1229597751 0.2376661599 0.0046234124 0.0121090000 0.0004080000 0.0036450000 0.0000000000 0.0000040000 0.0011390000 44373477 96830484 509673472 3.7553112507 4.0103111267 4.0221595764 2363 1311867797.4688720703 0.1268571466 0.1229614244 0.2376661599 0.0046226217 0.0111960000 0.0004020000 0.0029240000 0.0000030000 0.0000030000 0.0013980000 44377261 96830484 509673472 3.7552223206 4.0096364021 4.0223021507 2364 1311867797.5000469685 0.1282480210 0.1229636607 0.2376661599 0.0046220236 0.0101540000 0.0004020000 0.0022290000 0.0000000000 0.0000040000 0.0011320000 44380989 96830484 509673472 3.7537858486 4.0101771355 4.0230274200 2365 1311867797.5296459198 0.1287262142 0.1229660973 0.2376661599 0.0046213880 0.0130880000 0.0004000000 0.0042940000 0.0000040000 0.0000040000 0.0020950000 44384661 96830484 509673472 3.7531850338 4.0103683472 4.0235190392 2366 1311867797.5718441010 0.1273215115 0.1229679381 0.2376661599 0.0046205072 0.0100730000 0.0004000000 0.0022460000 0.0000010000 0.0000040000 0.0011240000 44388613 96830484 509673472 3.7543749809 4.0107507706 4.0238184929 2367 1311867797.5997619629 0.1289555132 0.1229704677 0.2376661599 0.0046200516 0.0108200000 0.0004050000 0.0025650000 0.0000030000 0.0000030000 0.0014120000 44392229 96830484 509673472 3.7525823116 4.0097141266 4.0241694450 2368 1311867797.6303300858 0.1291713715 0.1229730864 0.2376661599 0.0046192223 0.0101830000 0.0004030000 0.0022260000 0.0000000000 0.0000040000 0.0011340000 44395901 96830484 509673472 3.7522175312 4.0093407631 4.0243973732 2369 1311867797.6706480980 0.1295706332 0.1229758713 0.2376661599 0.0046182787 0.0131050000 0.0003980000 0.0042880000 0.0000030000 0.0000030000 0.0020690000 44399853 96830484 509673472 3.7515516281 4.0083813667 4.0246262550 2370 1311867797.7010281086 0.1304913461 0.1229790424 0.2376661599 0.0046174926 0.0122050000 0.0003950000 0.0043060000 0.0000010000 0.0000040000 0.0011310000 44403525 96830484 509673472 3.7505145073 4.0084805489 4.0250067711 2371 1311867797.7299659252 0.1297910362 0.1229819154 0.2376661599 0.0046166144 0.0123390000 0.0003970000 0.0042880000 0.0000030000 0.0000030000 0.0013740000 44407141 96830484 509673472 3.7510194778 4.0076527596 4.0252594948 2372 1311867797.7678339481 0.1294064820 0.1229846239 0.2376661599 0.0046158599 0.0110080000 0.0004020000 0.0031590000 0.0000010000 0.0000040000 0.0011280000 44411037 96830484 509673472 3.7512190342 4.0072050095 4.0250954628 2373 1311867797.8001670837 0.1304513961 0.1229877705 0.2376661599 0.0046149890 0.0131920000 0.0004030000 0.0043010000 0.0000040000 0.0000040000 0.0020840000 44414821 96830484 509673472 3.7501900196 4.0069251060 4.0253515244 2374 1311867797.8302230835 0.1306289136 0.1229909892 0.2376661599 0.0046140710 0.0111270000 0.0003990000 0.0032800000 0.0000010000 0.0000030000 0.0011170000 44418493 96830484 509673472 3.7499940395 4.0066885948 4.0252561569 2375 1311867797.8681600094 0.1312924474 0.1229944845 0.2376661599 0.0046135421 0.0104560000 0.0004010000 0.0022390000 0.0000040000 0.0000040000 0.0013930000 44422389 96830484 509673472 3.7494287491 4.0068931580 4.0256361961 2376 1311867797.8986220360 0.1333381683 0.1229988379 0.2376661599 0.0046128607 0.0101440000 0.0003980000 0.0022500000 0.0000010000 0.0000050000 0.0011110000 44426005 96830484 509673472 3.7474498749 4.0059986115 4.0259418488 2377 1311867797.9362978935 0.1345559508 0.1230037000 0.2376661599 0.0046119964 0.0132300000 0.0004010000 0.0043050000 0.0000040000 0.0000040000 0.0020580000 44429901 96830484 509673472 3.7463130951 4.0058751106 4.0258469582 2378 1311867797.9696850777 0.1321831644 0.1230075601 0.2376661599 0.0046114799 0.0102090000 0.0004030000 0.0022340000 0.0000000000 0.0000030000 0.0011140000 44433573 96830484 509673472 3.7487316132 4.0053744316 4.0255212784 2379 1311867798.0026450157 0.1344329417 0.1230123627 0.2376661599 0.0046108007 0.0126070000 0.0003970000 0.0042860000 0.0000040000 0.0000030000 0.0013930000 44437301 96830484 509673472 3.7465898991 4.0048685074 4.0259571075 2380 1311867798.0362720490 0.1332783401 0.1230166762 0.2376661599 0.0046099331 0.0123550000 0.0004030000 0.0043100000 0.0000000000 0.0000030000 0.0011270000 44441029 96830484 509673472 3.7480401993 4.0044226646 4.0259261131 2381 1311867798.0708239079 0.1343373060 0.1230214307 0.2376661599 0.0046092145 0.0133300000 0.0004070000 0.0043110000 0.0000040000 0.0000040000 0.0020570000 44444757 96830484 509673472 3.7470312119 4.0043153763 4.0258731842 2382 1311867798.1006710529 0.1317864954 0.1230251105 0.2376661599 0.0046096802 0.0123700000 0.0004020000 0.0043140000 0.0000000000 0.0000040000 0.0011120000 44448373 96830484 509673472 3.7497971058 4.0032138824 4.0256199837 2383 1311867798.1315639019 0.1340067685 0.1230297188 0.2376661599 0.0046094959 0.0160260000 0.0005040000 0.0028090000 0.0000100000 0.0000100000 0.0016560000 44451989 96830484 509673472 3.7478735447 4.0030369759 4.0258851051 2384 1311867798.1681389809 0.1376352310 0.1230358453 0.2376661599 0.0046092499 0.0111210000 0.0004080000 0.0026310000 0.0000010000 0.0000040000 0.0011250000 44455773 96830484 509673472 3.7446153164 4.0020642281 4.0262408257 2385 1311867798.2041590214 0.1357057542 0.1230411576 0.2376661599 0.0046086502 0.0121480000 0.0004000000 0.0032740000 0.0000030000 0.0000040000 0.0020470000 44459613 96830484 509673472 3.7471125126 4.0025520325 4.0258851051 2386 1311867798.2401928902 0.1373953670 0.1230471736 0.2376661599 0.0046082824 0.0114510000 0.0004030000 0.0036210000 0.0000000000 0.0000030000 0.0011150000 44463397 96830484 509673472 3.7458171844 4.0021381378 4.0259370804 2387 1311867798.2742829323 0.1379018724 0.1230533968 0.2376661599 0.0046078124 0.0117340000 0.0004010000 0.0036230000 0.0000030000 0.0000030000 0.0013960000 44467125 96830484 509673472 3.7459011078 4.0022201538 4.0263309479 2388 1311867798.3000180721 0.1371363252 0.1230592941 0.2376661599 0.0046069641 0.0109190000 0.0003990000 0.0029330000 0.0000010000 0.0000040000 0.0011240000 44470629 96830484 509673472 3.7471513748 4.0024738312 4.0263404846 2389 1311867798.3389759064 0.1381538957 0.1230656125 0.2376661599 0.0046067141 0.0111320000 0.0003970000 0.0022520000 0.0000040000 0.0000040000 0.0020540000 44474525 96830484 509673472 3.7466590405 4.0027270317 4.0263285637 2390 1311867798.3689808846 0.1376740932 0.1230717249 0.2376661599 0.0046057583 0.0121330000 0.0003990000 0.0043140000 0.0000010000 0.0000040000 0.0011160000 44478085 96830484 509673472 3.7477195263 4.0029487610 4.0263762474 2391 1311867798.4016571045 0.1376186013 0.1230778089 0.2376661599 0.0046048749 0.0104470000 0.0004030000 0.0022660000 0.0000040000 0.0000040000 0.0013860000 44481813 96830484 509673472 3.7484259605 4.0031056404 4.0266871452 2392 1311867798.4377439022 0.1374514699 0.1230838179 0.2376661599 0.0046041226 0.0155850000 0.0004980000 0.0038840000 0.0000010000 0.0000080000 0.0012380000 44485597 96830484 509673472 3.7492136955 4.0027623177 4.0268135071 2393 1311867798.4722189903 0.1369281411 0.1230896033 0.2376661599 0.0046033474 0.0135100000 0.0004190000 0.0043650000 0.0000040000 0.0000040000 0.0020680000 44489325 96830484 509673472 3.7502198219 4.0028510094 4.0265431404 2394 1311867798.4979979992 0.1360995471 0.1230950377 0.2376661599 0.0046026075 0.0106450000 0.0004450000 0.0025980000 0.0000000000 0.0000040000 0.0011140000 44492829 96830484 509673472 3.7514820099 4.0029749870 4.0263586044 2395 1311867798.5371229649 0.1381230205 0.1231013124 0.2376661599 0.0046017136 0.0104980000 0.0004070000 0.0022650000 0.0000040000 0.0000030000 0.0013900000 44496669 96830484 509673472 3.7500736713 4.0024271011 4.0265727043 2396 1311867798.5710020065 0.1368089318 0.1231070334 0.2376661599 0.0046009246 0.0104930000 0.0004040000 0.0026000000 0.0000000000 0.0000030000 0.0011120000 44500397 96830484 509673472 3.7518079281 4.0023965836 4.0263776779 2397 1311867798.6058080196 0.1364312619 0.1231125922 0.2376661599 0.0046001628 0.0160520000 0.0004980000 0.0028400000 0.0000100000 0.0000100000 0.0022090000 44504125 96830484 509673472 3.7527556419 4.0027418137 4.0260696411 2398 1311867798.6374750137 0.1376329660 0.1231186474 0.2376661599 0.0046012105 0.0148290000 0.0004990000 0.0031980000 0.0000010000 0.0000080000 0.0012470000 44507741 96830484 509673472 3.7522628307 4.0029950142 4.0263977051 2399 1311867798.6689419746 0.1375698298 0.1231246712 0.2376661599 0.0046007410 0.0121720000 0.0004210000 0.0037110000 0.0000050000 0.0000040000 0.0013810000 44511413 96830484 509673472 3.7528858185 4.0039091110 4.0263357162 2400 1311867798.7046790123 0.1369108111 0.1231304154 0.2376661599 0.0046006557 0.0101470000 0.0004090000 0.0022730000 0.0000000000 0.0000030000 0.0011100000 44515197 96830484 509673472 3.7543084621 4.0042109489 4.0265951157 2401 1311867798.7372579575 0.1385350078 0.1231368313 0.2376661599 0.0046004630 0.0126230000 0.0004090000 0.0036760000 0.0000040000 0.0000040000 0.0020410000 44518925 96830484 509673472 3.7534837723 4.0043654442 4.0266699791 2402 1311867798.7684650421 0.1393773556 0.1231435926 0.2376661599 0.0046003076 0.0100920000 0.0004030000 0.0022730000 0.0000010000 0.0000040000 0.0011040000 44522541 96830484 509673472 3.7533185482 4.0052051544 4.0268592834 2403 1311867798.8009719849 0.1367580593 0.1231492582 0.2376661599 0.0046004531 0.0128440000 0.0004540000 0.0037410000 0.0000040000 0.0000040000 0.0013910000 44526213 96830484 509673472 3.7566502094 4.0060405731 4.0265250206 2404 1311867798.8353779316 0.1395741999 0.1231560905 0.2376661599 0.0046011889 0.0109350000 0.0004530000 0.0029900000 0.0000010000 0.0000050000 0.0011080000 44529941 96830484 509673472 3.7550411224 4.0070185661 4.0271048546 2405 1311867798.8719079494 0.1399283856 0.1231630645 0.2376661599 0.0046004328 0.0122800000 0.0004100000 0.0033230000 0.0000030000 0.0000030000 0.0020340000 44533725 96830484 509673472 3.7557456493 4.0075216293 4.0269069672 2406 1311867798.9030900002 0.1389885098 0.1231696419 0.2376661599 0.0045995923 0.0144810000 0.0005040000 0.0028460000 0.0000010000 0.0000080000 0.0012150000 44537341 96830484 509673472 3.7573070526 4.0082497597 4.0263299942 2407 1311867798.9344220161 0.1402793080 0.1231767502 0.2376661599 0.0045989988 0.0131150000 0.0004360000 0.0044220000 0.0000050000 0.0000040000 0.0013700000 44541013 96830484 509673472 3.7571768761 4.0089936256 4.0267257690 2408 1311867798.9702930450 0.1398509294 0.1231836747 0.2376661599 0.0045982419 0.0106870000 0.0004180000 0.0026410000 0.0000000000 0.0000030000 0.0010920000 44544797 96830484 509673472 3.7587435246 4.0093183517 4.0264439583 2409 1311867798.9996600151 0.1402354091 0.1231907531 0.2376661599 0.0045988462 0.0133940000 0.0004200000 0.0043850000 0.0000040000 0.0000040000 0.0020060000 44548413 96830484 509673472 3.7582271099 4.0100374222 4.0261626244 2410 1311867799.0381140709 0.1406241953 0.1231979869 0.2376661599 0.0046000095 0.0110580000 0.0004160000 0.0029970000 0.0000010000 0.0000040000 0.0010980000 44552309 96830484 509673472 3.7597784996 4.0110812187 4.0260810852 2411 1311867799.0688700676 0.1408118755 0.1232052925 0.2376661599 0.0045991919 0.0151990000 0.0005230000 0.0028790000 0.0000080000 0.0000070000 0.0014760000 44555925 96830484 509673472 3.7604761124 4.0112104416 4.0261597633 2412 1311867799.1011309624 0.1402134299 0.1232123440 0.2376661599 0.0045987764 0.0127770000 0.0004350000 0.0044570000 0.0000010000 0.0000050000 0.0010960000 44559597 96830484 509673472 3.7615649700 4.0113878250 4.0260157585 2413 1311867799.1368980408 0.1413636357 0.1232198663 0.2376661599 0.0045981516 0.0120570000 0.0004170000 0.0030050000 0.0000030000 0.0000040000 0.0020150000 44563381 96830484 509673472 3.7614896297 4.0118570328 4.0259346962 2414 1311867799.1699140072 0.1410711706 0.1232272612 0.2376661599 0.0045972773 0.0101950000 0.0004170000 0.0023030000 0.0000000000 0.0000040000 0.0010830000 44567053 96830484 509673472 3.7626192570 4.0127434731 4.0256800652 2415 1311867799.2040729523 0.1398640871 0.1232341501 0.2376661599 0.0045997252 0.0128140000 0.0004220000 0.0044330000 0.0000040000 0.0000030000 0.0013590000 44570781 96830484 509673472 3.7643427849 4.0120959282 4.0249075890 2416 1311867799.2358450890 0.1415611356 0.1232417358 0.2376661599 0.0045990617 0.0146380000 0.0005190000 0.0028610000 0.0000010000 0.0000080000 0.0012060000 44574453 96830484 509673472 3.7632236481 4.0123324394 4.0246105194 2417 1311867799.2801609039 0.1425876766 0.1232497399 0.2376661599 0.0045982927 0.0118320000 0.0004330000 0.0023520000 0.0000040000 0.0000040000 0.0020120000 44578461 96830484 509673472 3.7633574009 4.0127201080 4.0244107246 2418 1311867799.2992970943 0.1411660016 0.1232571495 0.2376661599 0.0045974401 0.0107500000 0.0004160000 0.0026800000 0.0000010000 0.0000030000 0.0011050000 44581741 96830484 509673472 3.7649359703 4.0120997429 4.0236482620 2419 1311867799.3363530636 0.1421299130 0.1232649513 0.2376661599 0.0045965570 0.0128930000 0.0004180000 0.0044320000 0.0000040000 0.0000030000 0.0013490000 44585581 96830484 509673472 3.7645549774 4.0119957924 4.0229263306 2420 1311867799.3682019711 0.1424695402 0.1232728871 0.2376661599 0.0045964079 0.0110220000 0.0004160000 0.0030250000 0.0000000000 0.0000030000 0.0010940000 44589197 96830484 509673472 3.7645668983 4.0132102966 4.0224866867 2421 1311867799.4002521038 0.1426117867 0.1232808751 0.2376661599 0.0045954815 0.0117080000 0.0004180000 0.0026730000 0.0000040000 0.0000030000 0.0019990000 44592925 96830484 509673472 3.7650368214 4.0136861801 4.0222687721 2422 1311867799.4359819889 0.1422867924 0.1232887223 0.2376661599 0.0045945522 0.0110580000 0.0004140000 0.0030180000 0.0000010000 0.0000040000 0.0010800000 44596709 96830484 509673472 3.7656962872 4.0142211914 4.0217933655 2423 1311867799.4694008827 0.1426216066 0.1232967012 0.2376661599 0.0045937340 0.0165570000 0.0005200000 0.0047280000 0.0000070000 0.0000070000 0.0014910000 44600381 96830484 509673472 3.7658271790 4.0145640373 4.0216026306 2424 1311867799.5055029392 0.1416665465 0.1233042795 0.2376661599 0.0045929592 0.0126460000 0.0004270000 0.0044790000 0.0000010000 0.0000040000 0.0010940000 44604165 96830484 509673472 3.7671155930 4.0155806541 4.0213346481 2425 1311867799.5358369350 0.1391360611 0.1233108081 0.2376661599 0.0045927255 0.0135030000 0.0004190000 0.0044280000 0.0000030000 0.0000040000 0.0020120000 44607781 96830484 509673472 3.7697839737 4.0168008804 4.0210890770 2426 1311867799.5718040466 0.1404039413 0.1233178539 0.2376661599 0.0045918865 0.0117380000 0.0004660000 0.0030280000 0.0000000000 0.0000030000 0.0010880000 44611565 96830484 509673472 3.7685754299 4.0168704987 4.0207910538 2427 1311867799.6046330929 0.1408568025 0.1233250805 0.2376661599 0.0045910992 0.0118460000 0.0004230000 0.0033930000 0.0000030000 0.0000030000 0.0013730000 44615181 96830484 509673472 3.7681751251 4.0172200203 4.0203199387 2428 1311867799.6362400055 0.1401763409 0.1233320209 0.2376661599 0.0045902638 0.0157100000 0.0005140000 0.0036170000 0.0000010000 0.0000080000 0.0012230000 44618909 96830484 509673472 3.7688670158 4.0178837776 4.0195126534 2429 1311867799.6706030369 0.1419464499 0.1233396843 0.2376661599 0.0045898385 0.0137900000 0.0004290000 0.0044720000 0.0000040000 0.0000050000 0.0020170000 44622637 96830484 509673472 3.7674922943 4.0173783302 4.0190997124 2430 1311867799.7089800835 0.1424072981 0.1233475310 0.2376661599 0.0045889870 0.0125440000 0.0004250000 0.0044410000 0.0000000000 0.0000070000 0.0010920000 44626477 96830484 509673472 3.7672910690 4.0176634789 4.0184545517 2431 1311867799.7397329807 0.1405977458 0.1233546270 0.2376661599 0.0045885079 0.0128730000 0.0004220000 0.0044520000 0.0000030000 0.0000040000 0.0013720000 44630093 96830484 509673472 3.7691123486 4.0186181068 4.0177731514 2432 1311867799.7721259594 0.1410248727 0.1233618927 0.2376661599 0.0045875923 0.0105600000 0.0004240000 0.0026780000 0.0000010000 0.0000040000 0.0010950000 44633821 96830484 509673472 3.7688941956 4.0185351372 4.0172071457 2433 1311867799.8072490692 0.1410363764 0.1233691572 0.2376661599 0.0045869233 0.0117510000 0.0004250000 0.0026920000 0.0000040000 0.0000030000 0.0020130000 44637549 96830484 509673472 3.7689573765 4.0195446014 4.0163421631 2434 1311867799.8393049240 0.1384116560 0.1233753373 0.2376661599 0.0045863383 0.0125200000 0.0004160000 0.0044690000 0.0000010000 0.0000040000 0.0010920000 44641221 96830484 509673472 3.7716813087 4.0201101303 4.0156803131 2435 1311867799.8678040504 0.1394792050 0.1233819508 0.2376661599 0.0045864896 0.0111430000 0.0004300000 0.0026940000 0.0000040000 0.0000040000 0.0013600000 44644837 96830484 509673472 3.7707664967 4.0202608109 4.0155725479 2436 1311867799.9071669579 0.1390933394 0.1233884005 0.2376661599 0.0045857487 0.0111530000 0.0004220000 0.0030570000 0.0000010000 0.0000040000 0.0010880000 44648733 96830484 509673472 3.7714233398 4.0212178230 4.0154252052 2437 1311867799.9347701073 0.1373008192 0.1233941093 0.2376661599 0.0045849182 0.0125500000 0.0004270000 0.0034140000 0.0000040000 0.0000030000 0.0020170000 44652181 96830484 509673472 3.7734181881 4.0219697952 4.0150713921 2438 1311867799.9675478935 0.1376850754 0.1233999711 0.2376661599 0.0045841627 0.0125450000 0.0004240000 0.0044940000 0.0000000000 0.0000030000 0.0010840000 44655909 96830484 509673472 3.7732403278 4.0219125748 4.0154700279 2439 1311867800.0074419975 0.1391548961 0.1234064307 0.2376661599 0.0045833935 0.0108390000 0.0004270000 0.0023510000 0.0000040000 0.0000030000 0.0013620000 44659805 96830484 509673472 3.7722291946 4.0223803520 4.0155615807 2440 1311867800.0354819298 0.1386145204 0.1234126635 0.2376661599 0.0045826290 0.0125990000 0.0004280000 0.0044980000 0.0000000000 0.0000030000 0.0010840000 44663365 96830484 509673472 3.7731087208 4.0225839615 4.0152306557 2441 1311867800.0715930462 0.1378583014 0.1234185814 0.2376661599 0.0045824641 0.0125200000 0.0004290000 0.0034290000 0.0000030000 0.0000030000 0.0019980000 44667149 96830484 509673472 3.7744941711 4.0232148170 4.0150766373 2442 1311867800.1054389477 0.1372007579 0.1234242252 0.2376661599 0.0045815409 0.0115340000 0.0004270000 0.0034350000 0.0000000000 0.0000030000 0.0010800000 44670877 96830484 509673472 3.7757711411 4.0244393349 4.0148653984 2443 1311867800.1350870132 0.1380933672 0.1234302298 0.2376661599 0.0045808740 0.0120760000 0.0004370000 0.0034470000 0.0000030000 0.0000040000 0.0013590000 44674437 96830484 509673472 3.7751781940 4.0239729881 4.0144929886 2444 1311867800.1694350243 0.1383135319 0.1234363195 0.2376661599 0.0045801294 0.0108250000 0.0004280000 0.0027200000 0.0000010000 0.0000040000 0.0010850000 44678165 96830484 509673472 3.7755119801 4.0245842934 4.0143723488 2445 1311867800.2077379227 0.1379249841 0.1234422454 0.2376661599 0.0045792321 0.0137600000 0.0004330000 0.0045070000 0.0000030000 0.0000030000 0.0019960000 44682061 96830484 509673472 3.7766201496 4.0247335434 4.0141916275 2446 1311867800.2413349152 0.1380356699 0.1234482116 0.2376661599 0.0045784542 0.0162910000 0.0005430000 0.0047630000 0.0000010000 0.0000080000 0.0012160000 44685789 96830484 509673472 3.7772600651 4.0258426666 4.0141334534 2447 1311867800.2718439102 0.1388351172 0.1234544997 0.2376661599 0.0045775422 0.0117860000 0.0004480000 0.0031000000 0.0000040000 0.0000040000 0.0013680000 44689405 96830484 509673472 3.7771568298 4.0257129669 4.0144834518 2448 1311867800.3038680553 0.1370149255 0.1234600391 0.2376661599 0.0045772573 0.0104030000 0.0004310000 0.0023590000 0.0000000000 0.0000030000 0.0010800000 44693021 96830484 509673472 3.7796149254 4.0263028145 4.0145349503 2449 1311867800.3359420300 0.1382179260 0.1234660651 0.2376661599 0.0045772357 0.0121530000 0.0004310000 0.0030880000 0.0000040000 0.0000040000 0.0020050000 44696749 96830484 509673472 3.7792108059 4.0269641876 4.0148296356 2450 1311867800.3712899685 0.1381969303 0.1234720777 0.2376661599 0.0045763212 0.0144450000 0.0005260000 0.0025380000 0.0000010000 0.0000080000 0.0012130000 44700421 96830484 509673472 3.7804443836 4.0275745392 4.0150270462 2451 1311867800.4036390781 0.1392777711 0.1234785264 0.2376661599 0.0045754875 0.0162280000 0.0005410000 0.0036910000 0.0000080000 0.0000070000 0.0014790000 44704149 96830484 509673472 3.7802088261 4.0273652077 4.0152034760 2452 1311867800.4360520840 0.1387172937 0.1234847412 0.2376661599 0.0045746458 0.0119460000 0.0004470000 0.0034850000 0.0000010000 0.0000040000 0.0010970000 44707765 96830484 509673472 3.7817485332 4.0272607803 4.0154323578 2453 1311867800.4683868885 0.1390123814 0.1234910713 0.2376661599 0.0045738490 0.0117510000 0.0004350000 0.0027340000 0.0000040000 0.0000030000 0.0019940000 44711437 96830484 509673472 3.7823517323 4.0275335312 4.0153160095 2454 1311867800.5043759346 0.1402037889 0.1234978817 0.2376661599 0.0045734901 0.0121880000 0.0004360000 0.0042020000 0.0000000000 0.0000030000 0.0010740000 44715277 96830484 509673472 3.7823791504 4.0279726982 4.0156154633 2455 1311867800.5355989933 0.1399948001 0.1235046014 0.2376661599 0.0045728357 0.0107650000 0.0004420000 0.0023730000 0.0000030000 0.0000030000 0.0013550000 44718949 96830484 509673472 3.7834494114 4.0280437469 4.0156884193 2456 1311867800.5714819431 0.1412989646 0.1235118467 0.2376661599 0.0045719855 0.0107720000 0.0004340000 0.0026270000 0.0000010000 0.0000040000 0.0010730000 44722789 96830484 509673472 3.7833087444 4.0283122063 4.0159068108 2457 1311867800.6043050289 0.1407284588 0.1235188539 0.2376661599 0.0045711042 0.0123750000 0.0004380000 0.0031020000 0.0000030000 0.0000030000 0.0019890000 44726461 96830484 509673472 3.7847216129 4.0285878181 4.0157203674 2458 1311867800.6356160641 0.1410770863 0.1235259972 0.2376661599 0.0045701970 0.0106000000 0.0004370000 0.0023780000 0.0000010000 0.0000030000 0.0010710000 44730133 96830484 509673472 3.7853438854 4.0283012390 4.0157380104 2459 1311867800.6704459190 0.1391277760 0.1235323419 0.2376661599 0.0045700132 0.0121640000 0.0004370000 0.0034900000 0.0000030000 0.0000030000 0.0013540000 44733861 96830484 509673472 3.7883200645 4.0288753510 4.0155787468 2460 1311867800.7034249306 0.1396270096 0.1235388845 0.2376661599 0.0045695327 0.0110120000 0.0004430000 0.0027560000 0.0000010000 0.0000040000 0.0010690000 44737533 96830484 509673472 3.7886679173 4.0289807320 4.0157499313 2461 1311867800.7352058887 0.1405317187 0.1235457893 0.2376661599 0.0045688025 0.0122560000 0.0004390000 0.0030020000 0.0000030000 0.0000030000 0.0019790000 44741205 96830484 509673472 3.7889091969 4.0289640427 4.0159091949 2462 1311867800.7744410038 0.1387124658 0.1235519496 0.2376661599 0.0045696508 0.0113370000 0.0004460000 0.0031240000 0.0000010000 0.0000030000 0.0010580000 44745045 96830484 509673472 3.7914690971 4.0283575058 4.0156526566 2463 1311867800.8084959984 0.1399643123 0.1235586132 0.2376661599 0.0045692451 0.0114680000 0.0004450000 0.0027500000 0.0000030000 0.0000030000 0.0013490000 44748773 96830484 509673472 3.7909793854 4.0281305313 4.0160188675 2464 1311867800.8347818851 0.1403084397 0.1235654110 0.2376661599 0.0045684309 0.0157850000 0.0005340000 0.0029740000 0.0000010000 0.0000100000 0.0012390000 44752277 96830484 509673472 3.7912962437 4.0287294388 4.0162172318 2465 1311867800.8741569519 0.1405288875 0.1235722927 0.2376661599 0.0045677663 0.0122640000 0.0004560000 0.0027920000 0.0000040000 0.0000040000 0.0019840000 44756173 96830484 509673472 3.7915263176 4.0285158157 4.0159840584 2466 1311867800.9060831070 0.1391270310 0.1235786004 0.2376661599 0.0045668721 0.0160280000 0.0005320000 0.0029710000 0.0000020000 0.0000100000 0.0013250000 44759789 96830484 509673472 3.7935421467 4.0288448334 4.0160026550 2467 1311867800.9397630692 0.1404341608 0.1235854328 0.2376661599 0.0045660913 0.0127720000 0.0004550000 0.0038810000 0.0000050000 0.0000040000 0.0013510000 44763517 96830484 509673472 3.7926585674 4.0282583237 4.0159392357 2468 1311867800.9754400253 0.1414399296 0.1235926672 0.2376661599 0.0045660233 0.0108390000 0.0004390000 0.0027570000 0.0000010000 0.0000030000 0.0010630000 44767301 96830484 509673472 3.7922186852 4.0274376869 4.0158205032 2469 1311867801.0043320656 0.1416496933 0.1235999807 0.2376661599 0.0045659788 0.0138450000 0.0004360000 0.0038610000 0.0000030000 0.0000040000 0.0019660000 44770861 96830484 509673472 3.7923808098 4.0273108482 4.0158848763 2470 1311867801.0391418934 0.1407509595 0.1236069245 0.2376661599 0.0045654884 0.0155940000 0.0005480000 0.0040070000 0.0000020000 0.0000070000 0.0011290000 44774645 96830484 509673472 3.7936112881 4.0263943672 4.0156726837 2471 1311867801.0742049217 0.1406302154 0.1236138137 0.2376661599 0.0045648369 0.0115900000 0.0004390000 0.0027820000 0.0000040000 0.0000030000 0.0013460000 44778317 96830484 509673472 3.7941446304 4.0272655487 4.0156822205 2472 1311867801.1095008850 0.1411759704 0.1236209181 0.2376661599 0.0045641787 0.0128350000 0.0004350000 0.0044680000 0.0000010000 0.0000040000 0.0010610000 44782101 96830484 509673472 3.7938475609 4.0267653465 4.0160384178 2473 1311867801.1356039047 0.1408566236 0.1236278877 0.2376661599 0.0045633488 0.0126690000 0.0004350000 0.0034790000 0.0000040000 0.0000030000 0.0019640000 44785605 96830484 509673472 3.7944631577 4.0265316963 4.0163531303 2474 1311867801.1731019020 0.1401031762 0.1236345470 0.2376661599 0.0045625612 0.0103290000 0.0004360000 0.0020300000 0.0000010000 0.0000040000 0.0010590000 44789445 96830484 509673472 3.7952291965 4.0265264511 4.0161314011 2475 1311867801.2059779167 0.1388661712 0.1236407012 0.2376661599 0.0045629398 0.0158250000 0.0005320000 0.0026010000 0.0000110000 0.0000090000 0.0014630000 44793117 96830484 509673472 3.7962374687 4.0252976418 4.0159349442 2476 1311867801.2351169586 0.1368562281 0.1236460387 0.2376661599 0.0045621427 0.0119360000 0.0004540000 0.0031740000 0.0000010000 0.0000050000 0.0010710000 44796565 96830484 509673472 3.7981858253 4.0249915123 4.0159029961 2477 1311867801.2740859985 0.1385831684 0.1236520690 0.2376661599 0.0045612940 0.0126980000 0.0004340000 0.0034910000 0.0000030000 0.0000040000 0.0019630000 44800517 96830484 509673472 3.7963223457 4.0246500969 4.0160441399 2478 1311867801.3080420494 0.1362735331 0.1236571624 0.2376661599 0.0045611133 0.0128960000 0.0004420000 0.0045850000 0.0000000000 0.0000030000 0.0010590000 44804189 96830484 509673472 3.7983357906 4.0248665810 4.0157818794 2479 1311867801.3364291191 0.1364791244 0.1236623347 0.2376661599 0.0045610529 0.0172470000 0.0005260000 0.0048510000 0.0000080000 0.0000080000 0.0014540000 44807749 96830484 509673472 3.7980966568 4.0252265930 4.0160102844 2480 1311867801.3723030090 0.1348316669 0.1236668384 0.2376661599 0.0045609046 0.0129970000 0.0004520000 0.0046310000 0.0000000000 0.0000050000 0.0010740000 44811533 96830484 509673472 3.7994906902 4.0251307487 4.0158481598 2481 1311867801.4048879147 0.1343635321 0.1236711499 0.2376661599 0.0045599964 0.0138740000 0.0004400000 0.0045950000 0.0000040000 0.0000040000 0.0019530000 44815205 96830484 509673472 3.7997643948 4.0253520012 4.0157442093 2482 1311867801.4369940758 0.1335784644 0.1236751415 0.2376661599 0.0045597846 0.0126590000 0.0004380000 0.0044740000 0.0000000000 0.0000040000 0.0010650000 44818933 96830484 509673472 3.8001356125 4.0254850388 4.0158104897 2483 1311867801.4725570679 0.1349965334 0.1236797011 0.2376661599 0.0045657378 0.0109630000 0.0004380000 0.0023990000 0.0000030000 0.0000030000 0.0013400000 44822661 96830484 509673472 3.7991995811 4.0261306763 4.0164666176 2484 1311867801.5049059391 0.1342837214 0.1236839700 0.2376661599 0.0045651664 0.0110220000 0.0004430000 0.0027710000 0.0000010000 0.0000040000 0.0010750000 44826277 96830484 509673472 3.7999157906 4.0265283585 4.0168600082 2485 1311867801.5366990566 0.1345193088 0.1236883303 0.2376661599 0.0045653452 0.0120090000 0.0004420000 0.0027740000 0.0000030000 0.0000040000 0.0019870000 44830005 96830484 509673472 3.8002066612 4.0269360542 4.0169305801 2486 1311867801.5724411011 0.1341895759 0.1236925545 0.2376661599 0.0045649915 0.0127820000 0.0004460000 0.0044830000 0.0000010000 0.0000040000 0.0010540000 44833789 96830484 509673472 3.8007819653 4.0265326500 4.0177502632 2487 1311867801.6040530205 0.1338868141 0.1236966535 0.2376661599 0.0045641769 0.0155060000 0.0005340000 0.0033230000 0.0000070000 0.0000080000 0.0014560000 44837405 96830484 509673472 3.8016374111 4.0267586708 4.0181589127 2488 1311867801.6371319294 0.1353360265 0.1237013317 0.2376661599 0.0045636996 0.0165720000 0.0005510000 0.0041400000 0.0000010000 0.0000080000 0.0011800000 44841133 96830484 509673472 3.8009028435 4.0267353058 4.0187544823 2489 1311867801.6713359356 0.1339944303 0.1237054671 0.2376661599 0.0045702292 0.0126590000 0.0004520000 0.0031730000 0.0000040000 0.0000040000 0.0019490000 44844861 96830484 509673472 3.8022956848 4.0277380943 4.0188899040 2490 1311867801.7047519684 0.1312564760 0.1237084997 0.2376661599 0.0045724185 0.0138790000 0.0004400000 0.0046210000 0.0000000000 0.0000040000 0.0010500000 44848589 96830484 509673472 3.8059031963 4.0263180733 4.0185909271 2491 1311867801.7362918854 0.1349328905 0.1237130056 0.2376661599 0.0045775058 0.0161590000 0.0005870000 0.0030980000 0.0000110000 0.0000090000 0.0014370000 44852261 96830484 509673472 3.8037390709 4.0258474350 4.0190830231 2492 1311867801.7739040852 0.1340329647 0.1237171469 0.2376661599 0.0045774615 0.0112740000 0.0004630000 0.0024550000 0.0000000000 0.0000040000 0.0010590000 44856101 96830484 509673472 3.8056859970 4.0256991386 4.0184655190 2493 1311867801.8057849407 0.1339416653 0.1237212482 0.2376661599 0.0045766577 0.0125560000 0.0004430000 0.0031760000 0.0000030000 0.0000040000 0.0019320000 44859717 96830484 509673472 3.8068630695 4.0250878334 4.0181393623 2494 1311867801.8389480114 0.1353106052 0.1237258951 0.2376661599 0.0045758316 0.0156960000 0.0005370000 0.0033960000 0.0000010000 0.0000080000 0.0011650000 44863389 96830484 509673472 3.8066499233 4.0241022110 4.0176601410 2495 1311867801.8715689182 0.1358324140 0.1237307474 0.2376661599 0.0045757146 0.0121190000 0.0004570000 0.0031830000 0.0000040000 0.0000050000 0.0013260000 44867173 96830484 509673472 3.8071050644 4.0234885216 4.0164055824 2496 1311867801.9050290585 0.1349695027 0.1237352501 0.2376661599 0.0045761127 0.0107560000 0.0004580000 0.0024050000 0.0000000000 0.0000030000 0.0010450000 44870845 96830484 509673472 3.8091685772 4.0231399536 4.0150508881 2497 1311867801.9403839111 0.1353213787 0.1237398901 0.2376661599 0.0045758414 0.0119390000 0.0004410000 0.0027860000 0.0000030000 0.0000030000 0.0019580000 44874629 96830484 509673472 3.8099923134 4.0230154991 4.0142078400 2498 1311867801.9724469185 0.1358795166 0.1237447498 0.2376661599 0.0045754014 0.0130810000 0.0004460000 0.0046070000 0.0000000000 0.0000030000 0.0010650000 44878301 96830484 509673472 3.8104701042 4.0237593651 4.0129036903 2499 1311867802.0031659603 0.1372924596 0.1237501711 0.2376661599 0.0045814553 0.0115490000 0.0004390000 0.0027860000 0.0000040000 0.0000030000 0.0013520000 44881917 96830484 509673472 3.8104231358 4.0243067741 4.0118565559 2500 1311867802.0413680077 0.1379458904 0.1237558494 0.2376661599 0.0045845084 0.0112430000 0.0004420000 0.0027780000 0.0000010000 0.0000040000 0.0010670000 44885813 96830484 509673472 3.8115854263 4.0246872902 4.0105905533 2501 1311867802.0717110634 0.1376262754 0.1237613953 0.2376661599 0.0045842372 0.0121440000 0.0004430000 0.0027780000 0.0000030000 0.0000030000 0.0019710000 44889429 96830484 509673472 3.8131546974 4.0252475739 4.0088977814 2502 1311867802.1040730476 0.1390096992 0.1237674898 0.2376661599 0.0045840905 0.0108320000 0.0004410000 0.0024220000 0.0000010000 0.0000040000 0.0010780000 44893045 96830484 509673472 3.8134160042 4.0264725685 4.0075054169 2503 1311867802.1390628815 0.1352481544 0.1237720765 0.2376661599 0.0045837501 0.0156740000 0.0005320000 0.0029900000 0.0000070000 0.0000080000 0.0014680000 44896773 96830484 509673472 3.8191339970 4.0265622139 4.0051136017 2504 1311867802.1724100113 0.1320572644 0.1237753853 0.2376661599 0.0045902916 0.0131070000 0.0004600000 0.0046420000 0.0000000000 0.0000040000 0.0010950000 44900501 96830484 509673472 3.8234703541 4.0263509750 4.0025644302 2505 1311867802.2056589127 0.1346980333 0.1237797457 0.2376661599 0.0045944618 0.0125780000 0.0004440000 0.0031750000 0.0000030000 0.0000040000 0.0020020000 44904173 96830484 509673472 3.8229515553 4.0268192291 4.0007905960 2506 1311867802.2409839630 0.1322016865 0.1237831064 0.2376661599 0.0046014257 0.0128830000 0.0004420000 0.0046280000 0.0000010000 0.0000040000 0.0010800000 44907957 96830484 509673472 3.8271608353 4.0266613960 3.9983017445 2507 1311867802.2706429958 0.1313001513 0.1237861048 0.2376661599 0.0046005524 0.0127630000 0.0004420000 0.0042530000 0.0000040000 0.0000030000 0.0013360000 44911573 96830484 509673472 3.8297624588 4.0254507065 3.9958415031 2508 1311867802.3064510822 0.1322271973 0.1237894705 0.2376661599 0.0046011724 0.0110050000 0.0004420000 0.0027880000 0.0000000000 0.0000030000 0.0010750000 44915301 96830484 509673472 3.8301520348 4.0242156982 3.9937844276 2509 1311867802.3400380611 0.1306673139 0.1237922117 0.2376661599 0.0046056345 0.0170490000 0.0005360000 0.0044690000 0.0000080000 0.0000070000 0.0021620000 44919029 96830484 509673472 3.8329560757 4.0242013931 3.9912972450 2510 1311867802.3742809296 0.1329342574 0.1237958540 0.2376661599 0.0046054981 0.0116700000 0.0004510000 0.0031700000 0.0000010000 0.0000170000 0.0010800000 44922645 96830484 509673472 3.8322608471 4.0225934982 3.9890608788 2511 1311867802.4052720070 0.1312250346 0.1237988126 0.2376661599 0.0046060976 0.0113060000 0.0004380000 0.0027690000 0.0000030000 0.0000030000 0.0013530000 44926317 96830484 509673472 3.8353221416 4.0217247009 3.9867551327 2512 1311867802.4389400482 0.1308936775 0.1238016370 0.2376661599 0.0046083253 0.0114010000 0.0004350000 0.0031410000 0.0000010000 0.0000040000 0.0010970000 44929989 96830484 509673472 3.8367021084 4.0225696564 3.9849705696 2513 1311867802.4714379311 0.1294295490 0.1238038765 0.2376661599 0.0046076556 0.0123700000 0.0004420000 0.0031590000 0.0000030000 0.0000030000 0.0020260000 44933717 96830484 509673472 3.8392055035 4.0217161179 3.9824314117 2514 1311867802.5060200691 0.1312627792 0.1238068435 0.2376661599 0.0046076884 0.0110760000 0.0004390000 0.0027840000 0.0000010000 0.0000040000 0.0010820000 44937445 96830484 509673472 3.8385937214 4.0214934349 3.9804704189 2515 1311867802.5389459133 0.1290819794 0.1238089410 0.2376661599 0.0046083264 0.0132380000 0.0004390000 0.0046320000 0.0000040000 0.0000040000 0.0013570000 44941061 96830484 509673472 3.8420155048 4.0211248398 3.9781761169 2516 1311867802.5715909004 0.1280056536 0.1238106090 0.2376661599 0.0046103188 0.0120980000 0.0004380000 0.0038730000 0.0000000000 0.0000040000 0.0010890000 44944845 96830484 509673472 3.8443660736 4.0221676826 3.9755492210 2517 1311867802.6031410694 0.1272889376 0.1238119909 0.2376661599 0.0046103678 0.0120110000 0.0004390000 0.0027790000 0.0000040000 0.0000040000 0.0020240000 44948461 96830484 509673472 3.8465192318 4.0223813057 3.9733579159 2518 1311867802.6396369934 0.1290646791 0.1238140770 0.2376661599 0.0046099219 0.0113580000 0.0004420000 0.0031520000 0.0000000000 0.0000040000 0.0010780000 44952245 96830484 509673472 3.8460569382 4.0206918716 3.9713408947 2519 1311867802.6727440357 0.1274467856 0.1238155191 0.2376661599 0.0046092495 0.0166440000 0.0005380000 0.0037570000 0.0000080000 0.0000070000 0.0015010000 44955917 96830484 509673472 3.8490290642 4.0210456848 3.9689958096 2520 1311867802.7073149681 0.1276177317 0.1238170279 0.2376661599 0.0046095143 0.0132440000 0.0004510000 0.0046440000 0.0000010000 0.0000040000 0.0010830000 44959645 96830484 509673472 3.8501207829 4.0227341652 3.9673018456 2521 1311867802.7416400909 0.1253361404 0.1238176305 0.2376661599 0.0046092241 0.0124280000 0.0004400000 0.0031610000 0.0000040000 0.0000030000 0.0020090000 44963373 96830484 509673472 3.8538665771 4.0228571892 3.9649519920 2522 1311867802.7708799839 0.1257342249 0.1238183904 0.2376661599 0.0046084648 0.0164440000 0.0005340000 0.0037630000 0.0000010000 0.0000070000 0.0012140000 44966989 96830484 509673472 3.8547341824 4.0227227211 3.9627468586 2523 1311867802.8048460484 0.1260553449 0.1238192770 0.2376661599 0.0046078808 0.0135440000 0.0004560000 0.0046790000 0.0000040000 0.0000040000 0.0013900000 44970605 96830484 509673472 3.8557116985 4.0229029655 3.9611790180 2524 1311867802.8393790722 0.1268276274 0.1238204689 0.2376661599 0.0046071942 0.0129670000 0.0004390000 0.0046420000 0.0000010000 0.0000030000 0.0010670000 44974389 96830484 509673472 3.8563499451 4.0230188370 3.9600493908 2525 1311867802.8706729412 0.1266327947 0.1238215827 0.2376661599 0.0046069723 0.0172050000 0.0005470000 0.0034030000 0.0000100000 0.0000100000 0.0021770000 44978061 96830484 509673472 3.8579106331 4.0223522186 3.9581949711 2526 1311867802.9066920280 0.1279583275 0.1238232204 0.2376661599 0.0046075671 0.0133670000 0.0004590000 0.0046510000 0.0000000000 0.0000040000 0.0010910000 44981845 96830484 509673472 3.8577177525 4.0223264694 3.9566557407 2527 1311867802.9404280186 0.1292108893 0.1238253524 0.2376661599 0.0046067346 0.0132900000 0.0004430000 0.0046240000 0.0000040000 0.0000040000 0.0013630000 44985517 96830484 509673472 3.8579227924 4.0223274231 3.9551410675 2528 1311867802.9723958969 0.1280434132 0.1238270210 0.2376661599 0.0046059235 0.0128420000 0.0004420000 0.0046160000 0.0000000000 0.0000030000 0.0010790000 44989189 96830484 509673472 3.8603582382 4.0223250389 3.9537622929 2529 1311867803.0042099953 0.1250883788 0.1238275197 0.2376661599 0.0046071180 0.0137910000 0.0004460000 0.0046250000 0.0000040000 0.0000030000 0.0020150000 44992861 96830484 509673472 3.8641173840 4.0233006477 3.9520189762 2530 1311867803.0404539108 0.1271773577 0.1238288438 0.2376661599 0.0046070140 0.0128180000 0.0004410000 0.0046150000 0.0000010000 0.0000040000 0.0010760000 44996645 96830484 509673472 3.8635489941 4.0228009224 3.9508106709 2531 1311867803.0710830688 0.1258506775 0.1238296426 0.2376661599 0.0046064855 0.0171920000 0.0005420000 0.0048930000 0.0000090000 0.0000080000 0.0014750000 45000261 96830484 509673472 3.8655145168 4.0218262672 3.9492247105 2532 1311867803.1049640179 0.1276981831 0.1238311705 0.2376661599 0.0046059657 0.0118260000 0.0004630000 0.0031650000 0.0000010000 0.0000040000 0.0010910000 45003933 96830484 509673472 3.8645370007 4.0217595100 3.9481673241 2533 1311867803.1399960518 0.1288518459 0.1238331526 0.2376661599 0.0046051912 0.0187720000 0.0005510000 0.0051040000 0.0000080000 0.0000090000 0.0025850000 45007717 96830484 509673472 3.8640673161 4.0224699974 3.9470465183 2534 1311867803.1724820137 0.1271398067 0.1238344575 0.2376661599 0.0046043374 0.0132300000 0.0004920000 0.0046410000 0.0000010000 0.0000040000 0.0010850000 45011389 96830484 509673472 3.8661453724 4.0220303535 3.9453690052 2535 1311867803.2086870670 0.1285362840 0.1238363123 0.2376661599 0.0046037304 0.0132240000 0.0004410000 0.0046090000 0.0000030000 0.0000030000 0.0013510000 45015229 96830484 509673472 3.8652739525 4.0223846436 3.9443025589 2536 1311867803.2400670052 0.1274995357 0.1238377567 0.2376661599 0.0046039752 0.0175000000 0.0005350000 0.0048980000 0.0000010000 0.0000080000 0.0012140000 45018845 96830484 509673472 3.8661549091 4.0222711563 3.9432659149 2537 1311867803.2704820633 0.1257968098 0.1238385289 0.2376661599 0.0046043910 0.0127700000 0.0004550000 0.0031880000 0.0000040000 0.0000040000 0.0020380000 45022461 96830484 509673472 3.8682889938 4.0213375092 3.9418234825 2538 1311867803.3084690571 0.1279028654 0.1238401303 0.2376661599 0.0046038360 0.0131960000 0.0004340000 0.0046360000 0.0000000000 0.0000040000 0.0010880000 45026357 96830484 509673472 3.8659317493 4.0200853348 3.9409611225 2539 1311867803.3390929699 0.1277309656 0.1238416628 0.2376661599 0.0046033982 0.0132290000 0.0004400000 0.0046130000 0.0000040000 0.0000040000 0.0013610000 45029861 96830484 509673472 3.8657624722 4.0202860832 3.9397773743 2540 1311867803.3732869625 0.1238241792 0.1238416559 0.2376661599 0.0046036150 0.0121580000 0.0004310000 0.0038740000 0.0000010000 0.0000040000 0.0010820000 45033645 96830484 509673472 3.8696935177 4.0205726624 3.9389371872 2541 1311867803.4067549706 0.1245047674 0.1238419168 0.2376661599 0.0046028589 0.0175310000 0.0005350000 0.0048630000 0.0000080000 0.0000070000 0.0021860000 45037373 96830484 509673472 3.8688788414 4.0207424164 3.9383318424 2542 1311867803.4397881031 0.1251298934 0.1238424235 0.2376661599 0.0046020053 0.0113150000 0.0004400000 0.0027700000 0.0000010000 0.0000040000 0.0010830000 45041045 96830484 509673472 3.8683671951 4.0208802223 3.9377934933 2543 1311867803.4707190990 0.1245453283 0.1238426999 0.2376661599 0.0046013752 0.0167730000 0.0005360000 0.0044680000 0.0000080000 0.0000080000 0.0014860000 45044717 96830484 509673472 3.8689229488 4.0204682350 3.9364285469 2544 1311867803.5065801144 0.1262114644 0.1238436310 0.2376661599 0.0046016233 0.0130990000 0.0004450000 0.0046240000 0.0000010000 0.0000040000 0.0010800000 45048501 96830484 509673472 3.8675448895 4.0212035179 3.9360909462 2545 1311867803.5397379398 0.1241914257 0.1238437677 0.2376661599 0.0046011222 0.0127280000 0.0004410000 0.0034830000 0.0000040000 0.0000030000 0.0020130000 45052173 96830484 509673472 3.8694837093 4.0213403702 3.9348423481 2546 1311867803.5702500343 0.1244781166 0.1238440169 0.2376661599 0.0046002981 0.0168730000 0.0005610000 0.0048770000 0.0000010000 0.0000080000 0.0012100000 45055789 96830484 509673472 3.8690037727 4.0211524963 3.9338061810 2547 1311867803.6121668816 0.1252476871 0.1238445680 0.2376661599 0.0045995339 0.0134520000 0.0004420000 0.0046480000 0.0000040000 0.0000030000 0.0013630000 45059797 96830484 509673472 3.8681001663 4.0213737488 3.9335198402 2548 1311867803.6394500732 0.1209750473 0.1238434418 0.2376661599 0.0045991794 0.0129710000 0.0004390000 0.0045910000 0.0000010000 0.0000040000 0.0010870000 45063301 96830484 509673472 3.8720796108 4.0225248337 3.9318141937 2549 1311867803.6726729870 0.1252713948 0.1238440020 0.2376661599 0.0045999147 0.0140220000 0.0004360000 0.0046120000 0.0000030000 0.0000030000 0.0020150000 45066973 96830484 509673472 3.8675422668 4.0227003098 3.9321496487 2550 1311867803.7105441093 0.1252480447 0.1238445526 0.2376661599 0.0045997685 0.0114980000 0.0004400000 0.0031400000 0.0000010000 0.0000040000 0.0010790000 45070869 96830484 509673472 3.8670625687 4.0233516693 3.9315638542 2551 1311867803.7378931046 0.1242898256 0.1238447271 0.2376661599 0.0045992001 0.0193980000 0.0006200000 0.0051110000 0.0000100000 0.0000100000 0.0016060000 45074373 96830484 509673472 3.8678500652 4.0248723030 3.9308114052 2552 1311867803.7722349167 0.1243292689 0.1238449170 0.2376661599 0.0045987589 0.0133850000 0.0004620000 0.0046880000 0.0000010000 0.0000040000 0.0010760000 45078157 96830484 509673472 3.8676087856 4.0249757767 3.9300963879 2553 1311867803.8064799309 0.1266785860 0.1238460269 0.2376661599 0.0045982242 0.0128800000 0.0004970000 0.0028000000 0.0000030000 0.0000040000 0.0019910000 45081885 96830484 509673472 3.8652021885 4.0246148109 3.9298765659 2554 1311867803.8385739326 0.1262032390 0.1238469499 0.2376661599 0.0045991562 0.0120080000 0.0004930000 0.0035350000 0.0000010000 0.0000040000 0.0010780000 45085501 96830484 509673472 3.8658828735 4.0269622803 3.9298667908 2555 1311867803.8737049103 0.1277744621 0.1238484871 0.2376661599 0.0045988381 0.0112210000 0.0004450000 0.0024200000 0.0000030000 0.0000030000 0.0013360000 45089341 96830484 509673472 3.8641817570 4.0280404091 3.9295036793 2556 1311867803.9077479839 0.1270197034 0.1238497278 0.2376661599 0.0045995172 0.0168860000 0.0005380000 0.0049290000 0.0000010000 0.0000080000 0.0011660000 45093069 96830484 509673472 3.8647739887 4.0278668404 3.9287469387 2557 1311867803.9400169849 0.1290522516 0.1238517624 0.2376661599 0.0046026407 0.0171120000 0.0005420000 0.0034070000 0.0000100000 0.0000110000 0.0021270000 45096685 96830484 509673472 3.8627569675 4.0282974243 3.9286711216 2558 1311867803.9723939896 0.1296259612 0.1238540197 0.2376661599 0.0046029741 0.0122020000 0.0004600000 0.0032060000 0.0000010000 0.0000050000 0.0010530000 45100413 96830484 509673472 3.8617377281 4.0302848816 3.9285662174 2559 1311867804.0064320564 0.1290298998 0.1238560423 0.2376661599 0.0046024061 0.0134130000 0.0004470000 0.0046680000 0.0000030000 0.0000040000 0.0013250000 45104085 96830484 509673472 3.8619606495 4.0293073654 3.9277198315 2560 1311867804.0387020111 0.1299745440 0.1238584324 0.2376661599 0.0046019200 0.0132910000 0.0004470000 0.0046650000 0.0000000000 0.0000030000 0.0010480000 45107757 96830484 509673472 3.8604598045 4.0297245979 3.9270813465 2561 1311867804.0722310543 0.1302347779 0.1238609222 0.2376661599 0.0046012857 0.0142600000 0.0004480000 0.0046880000 0.0000030000 0.0000040000 0.0019660000 45111485 96830484 509673472 3.8596873283 4.0311741829 3.9265747070 2562 1311867804.1084001064 0.1304470897 0.1238634929 0.2376661599 0.0046012387 0.0169420000 0.0005800000 0.0049260000 0.0000010000 0.0000080000 0.0011710000 45115213 96830484 509673472 3.8589658737 4.0300216675 3.9261984825 2563 1311867804.1399340630 0.1314933896 0.1238664698 0.2376661599 0.0046009364 0.0126350000 0.0004540000 0.0035680000 0.0000040000 0.0000040000 0.0013250000 45118885 96830484 509673472 3.8573226929 4.0300893784 3.9254462719 2564 1311867804.1736989021 0.1290285587 0.1238684831 0.2376661599 0.0046008258 0.0153490000 0.0005610000 0.0029950000 0.0000010000 0.0000070000 0.0011770000 45122613 96830484 509673472 3.8594570160 4.0303378105 3.9245011806 2565 1311867804.2092669010 0.1313820481 0.1238714124 0.2376661599 0.0045999685 0.0145750000 0.0004580000 0.0047150000 0.0000040000 0.0000040000 0.0019550000 45126341 96830484 509673472 3.8565533161 4.0286355019 3.9240925312 2566 1311867804.2408709526 0.1310129464 0.1238741955 0.2376661599 0.0045996389 0.0171460000 0.0005440000 0.0049110000 0.0000010000 0.0000080000 0.0011800000 45129957 96830484 509673472 3.8563418388 4.0295257568 3.9232089520 2567 1311867804.2707660198 0.1269146204 0.1238753799 0.2376661599 0.0045993686 0.0131230000 0.0004440000 0.0039540000 0.0000040000 0.0000040000 0.0013350000 45133573 96830484 509673472 3.8602654934 4.0306706429 3.9226505756 2568 1311867804.3078389168 0.1279165894 0.1238769536 0.2376661599 0.0045986512 0.0115320000 0.0004610000 0.0028110000 0.0000000000 0.0000030000 0.0010500000 45137301 96830484 509673472 3.8587279320 4.0305314064 3.9221620560 2569 1311867804.3404970169 0.1281763017 0.1238786272 0.2376661599 0.0045977732 0.0165290000 0.0005420000 0.0026600000 0.0000100000 0.0000090000 0.0021390000 45141029 96830484 509673472 3.8580436707 4.0305132866 3.9214053154 2570 1311867804.3725171089 0.1259347647 0.1238794272 0.2376661599 0.0045969775 0.0316630000 0.0006510000 0.0051940000 0.0000020000 0.0000150000 0.0015580000 45144701 96830484 509673472 3.8598401546 4.0318002701 3.9202768803 2571 1311867804.4121570587 0.1274980605 0.1238808347 0.2376661599 0.0045961657 0.0159200000 0.0005020000 0.0048040000 0.0000060000 0.0000060000 0.0014020000 45148597 96830484 509673472 3.8579730988 4.0313043594 3.9196527004 2572 1311867804.4434490204 0.1257831305 0.1238815743 0.2376661599 0.0045955183 0.0135620000 0.0004530000 0.0046750000 0.0000010000 0.0000040000 0.0010490000 45152269 96830484 509673472 3.8596961498 4.0321187973 3.9193277359 2573 1311867804.4745810032 0.1242007092 0.1238816983 0.2376661599 0.0045947021 0.0143160000 0.0004450000 0.0046540000 0.0000030000 0.0000030000 0.0019680000 45155885 96830484 509673472 3.8612332344 4.0327196121 3.9183366299 2574 1311867804.5092110634 0.1292663068 0.1238837903 0.2376661599 0.0045942605 0.0133930000 0.0004450000 0.0046590000 0.0000000000 0.0000030000 0.0010570000 45159613 96830484 509673472 3.8561420441 4.0311012268 3.9182603359 2575 1311867804.5393021107 0.1271424443 0.1238850558 0.2376661599 0.0045939529 0.0134160000 0.0004440000 0.0046540000 0.0000030000 0.0000040000 0.0013370000 45163229 96830484 509673472 3.8580610752 4.0324063301 3.9173526764 2576 1311867804.5744440556 0.1258751750 0.1238858283 0.2376661599 0.0045931011 0.0120860000 0.0004430000 0.0035420000 0.0000000000 0.0000030000 0.0010570000 45166957 96830484 509673472 3.8595328331 4.0334582329 3.9168002605 2577 1311867804.6065940857 0.1261887252 0.1238867220 0.2376661599 0.0045923702 0.0140910000 0.0004490000 0.0046570000 0.0000040000 0.0000030000 0.0019710000 45170685 96830484 509673472 3.8593802452 4.0322909355 3.9162585735 2578 1311867804.6414110661 0.1241542548 0.1238868257 0.2376661599 0.0045918030 0.0130370000 0.0004470000 0.0046520000 0.0000000000 0.0000040000 0.0010590000 45174413 96830484 509673472 3.8616852760 4.0337886810 3.9155101776 2579 1311867804.6758968830 0.1268807054 0.1238879866 0.2376661599 0.0045931595 0.0133890000 0.0004490000 0.0046680000 0.0000030000 0.0000040000 0.0013320000 45178197 96830484 509673472 3.8590965271 4.0351181030 3.9153392315 2580 1311867804.7094891071 0.1260555685 0.1238888268 0.2376661599 0.0045923507 0.0130890000 0.0004440000 0.0046590000 0.0000000000 0.0000030000 0.0010580000 45181869 96830484 509673472 3.8602688313 4.0345144272 3.9150335789 2581 1311867804.7431960106 0.1265598983 0.1238898616 0.2376661599 0.0045927572 0.0140290000 0.0004480000 0.0046560000 0.0000030000 0.0000030000 0.0019740000 45185597 96830484 509673472 3.8602888584 4.0360350609 3.9149274826 2582 1311867804.7739880085 0.1255779862 0.1238905155 0.2376661599 0.0045920997 0.0128230000 0.0004490000 0.0043120000 0.0000000000 0.0000040000 0.0010620000 45189157 96830484 509673472 3.8613262177 4.0378503799 3.9144680500 2583 1311867804.8113589287 0.1248488650 0.1238908865 0.2376661599 0.0045940315 0.0133890000 0.0004470000 0.0046810000 0.0000040000 0.0000040000 0.0013330000 45192997 96830484 509673472 3.8617126942 4.0363287926 3.9141008854 2584 1311867804.8407669067 0.1240649149 0.1238909538 0.2376661599 0.0045933810 0.0115750000 0.0004490000 0.0031820000 0.0000010000 0.0000040000 0.0010580000 45196613 96830484 509673472 3.8627288342 4.0380864143 3.9140636921 2585 1311867804.8758749962 0.1239243969 0.1238909668 0.2376661599 0.0045938974 0.0140660000 0.0004460000 0.0047250000 0.0000040000 0.0000040000 0.0019640000 45200341 96830484 509673472 3.8630175591 4.0390739441 3.9138283730 2586 1311867804.9093499184 0.1254494637 0.1238915694 0.2376661599 0.0045932302 0.0116550000 0.0004500000 0.0031880000 0.0000010000 0.0000040000 0.0010450000 45204069 96830484 509673472 3.8617634773 4.0376343727 3.9136819839 2587 1311867804.9418170452 0.1270117909 0.1238927755 0.2376661599 0.0045953529 0.0136250000 0.0004480000 0.0047140000 0.0000040000 0.0000040000 0.0013200000 45207741 96830484 509673472 3.8601896763 4.0392351151 3.9142181873 2588 1311867804.9785380363 0.1240867749 0.1238928505 0.2376661599 0.0045949451 0.0128380000 0.0004510000 0.0043240000 0.0000010000 0.0000040000 0.0010420000 45211469 96830484 509673472 3.8634402752 4.0399699211 3.9138510227 2589 1311867805.0090980530 0.1275827140 0.1238942757 0.2376661599 0.0045948614 0.0136690000 0.0007370000 0.0032470000 0.0000030000 0.0000040000 0.0019620000 45215085 96830484 509673472 3.8603870869 4.0380873680 3.9143257141 2590 1311867805.0401790142 0.1266436130 0.1238953372 0.2376661599 0.0045941233 0.0131640000 0.0005150000 0.0047030000 0.0000010000 0.0000040000 0.0010450000 45218757 96830484 509673472 3.8616628647 4.0383276939 3.9143459797 2591 1311867805.0801899433 0.1255328953 0.1238959693 0.2376661599 0.0045939410 0.0179690000 0.0005570000 0.0049900000 0.0000070000 0.0000080000 0.0014390000 45222653 96830484 509673472 3.8635101318 4.0389919281 3.9149110317 2592 1311867805.1079609394 0.1287123859 0.1238978274 0.2376661599 0.0045953059 0.0165040000 0.0005430000 0.0049080000 0.0000010000 0.0000060000 0.0011160000 45226269 96830484 509673472 3.8614940643 4.0375747681 3.9155740738 2593 1311867805.1444120407 0.1283020526 0.1238995259 0.2376661599 0.0045965394 0.0170230000 0.0005490000 0.0038170000 0.0000080000 0.0000070000 0.0021250000 45230053 96830484 509673472 3.8625860214 4.0376243591 3.9158849716 2594 1311867805.1750040054 0.1294186115 0.1239016536 0.2376661599 0.0045966685 0.0119760000 0.0004560000 0.0032440000 0.0000000000 0.0000030000 0.0010560000 45233613 96830484 509673472 3.8620800972 4.0383086205 3.9165959358 2595 1311867805.2100739479 0.1264803112 0.1239026473 0.2376661599 0.0045964307 0.0135020000 0.0004530000 0.0047150000 0.0000030000 0.0000030000 0.0013040000 45237397 96830484 509673472 3.8655493259 4.0383481979 3.9166564941 2596 1311867805.2393519878 0.1272010803 0.1239039179 0.2376661599 0.0045955950 0.0113400000 0.0004480000 0.0028350000 0.0000000000 0.0000030000 0.0010310000 45241013 96830484 509673472 3.8654496670 4.0377459526 3.9173514843 2597 1311867805.2741580009 0.1295488775 0.1239060915 0.2376661599 0.0045950648 0.0140870000 0.0004520000 0.0047230000 0.0000040000 0.0000040000 0.0019270000 45244741 96830484 509673472 3.8639233112 4.0373358727 3.9183599949 2598 1311867805.3108520508 0.1277647465 0.1239075767 0.2376661599 0.0045945966 0.0170320000 0.0005450000 0.0049770000 0.0000010000 0.0000070000 0.0011700000 45248525 96830484 509673472 3.8664033413 4.0375318527 3.9184398651 2599 1311867805.3395309448 0.1275224388 0.1239089676 0.2376661599 0.0045937371 0.0136330000 0.0004590000 0.0047350000 0.0000040000 0.0000030000 0.0013220000 45252141 96830484 509673472 3.8670666218 4.0372838974 3.9185159206 2600 1311867805.3745789528 0.1308855861 0.1239116509 0.2376661599 0.0045951892 0.0134580000 0.0004650000 0.0047170000 0.0000010000 0.0000040000 0.0010330000 45255869 96830484 509673472 3.8644280434 4.0368723869 3.9194159508 2601 1311867805.4084360600 0.1286247969 0.1239134630 0.2376661599 0.0045945062 0.0141790000 0.0004520000 0.0047200000 0.0000030000 0.0000030000 0.0019310000 45259653 96830484 509673472 3.8670985699 4.0378651619 3.9195475578 2602 1311867805.4401900768 0.1295377314 0.1239156245 0.2376661599 0.0045938363 0.0117890000 0.0004480000 0.0032000000 0.0000000000 0.0000030000 0.0010330000 45263269 96830484 509673472 3.8664226532 4.0391511917 3.9200434685 2603 1311867805.4747269154 0.1278602630 0.1239171399 0.2376661599 0.0045955374 0.0115620000 0.0004490000 0.0028170000 0.0000040000 0.0000030000 0.0013100000 45266997 96830484 509673472 3.8684363365 4.0383052826 3.9204425812 2604 1311867805.5079410076 0.1277178228 0.1239185995 0.2376661599 0.0045951445 0.0171270000 0.0005640000 0.0049690000 0.0000000000 0.0000090000 0.0011810000 45270725 96830484 509673472 3.8691627979 4.0382413864 3.9212093353 2605 1311867805.5406329632 0.1294583976 0.1239207261 0.2376661599 0.0045950323 0.0125330000 0.0004520000 0.0028440000 0.0000040000 0.0000030000 0.0019440000 45274453 96830484 509673472 3.8679409027 4.0387020111 3.9221322536 2606 1311867805.5750451088 0.1266145706 0.1239217598 0.2376661599 0.0045948407 0.0125930000 0.0004480000 0.0039540000 0.0000000000 0.0000040000 0.0010360000 45278125 96830484 509673472 3.8713710308 4.0367245674 3.9220468998 2607 1311867805.6078290939 0.1288770288 0.1239236605 0.2376661599 0.0045942710 0.0137370000 0.0004450000 0.0046990000 0.0000030000 0.0000040000 0.0013260000 45281853 96830484 509673472 3.8696951866 4.0349998474 3.9225218296 2608 1311867805.6431670189 0.1267641485 0.1239247497 0.2376661599 0.0045954487 0.0133690000 0.0004440000 0.0046850000 0.0000000000 0.0000030000 0.0010510000 45285637 96830484 509673472 3.8720521927 4.0365772247 3.9226846695 2609 1311867805.6750800610 0.1280019730 0.1239263124 0.2376661599 0.0045948342 0.0134960000 0.0005000000 0.0033160000 0.0000040000 0.0000030000 0.0019750000 45289309 96830484 509673472 3.8711056709 4.0363092422 3.9230268002 2610 1311867805.7071790695 0.1286198497 0.1239281107 0.2376661599 0.0045942846 0.0133620000 0.0004420000 0.0046760000 0.0000000000 0.0000030000 0.0010500000 45293037 96830484 509673472 3.8708424568 4.0355224609 3.9231953621 2611 1311867805.7425789833 0.1287035048 0.1239299397 0.2376661599 0.0045958412 0.0135630000 0.0004600000 0.0046610000 0.0000040000 0.0000030000 0.0013270000 45296821 96830484 509673472 3.8714349270 4.0359315872 3.9234182835 2612 1311867805.7748079300 0.1275165826 0.1239313128 0.2376661599 0.0045951297 0.0133140000 0.0004450000 0.0046550000 0.0000010000 0.0000040000 0.0010550000 45300437 96830484 509673472 3.8730456829 4.0361051559 3.9234547615 2613 1311867805.8089549541 0.1268016845 0.1239324113 0.2376661599 0.0045948605 0.0141650000 0.0004460000 0.0046450000 0.0000030000 0.0000030000 0.0019770000 45304165 96830484 509673472 3.8741769791 4.0362682343 3.9235029221 2614 1311867805.8436930180 0.1289711148 0.1239343389 0.2376661599 0.0045983596 0.0133360000 0.0004440000 0.0046250000 0.0000000000 0.0000040000 0.0010600000 45307837 96830484 509673472 3.8722848892 4.0368595123 3.9242815971 2615 1311867805.8754489422 0.1244254187 0.1239345267 0.2376661599 0.0045994567 0.0134200000 0.0004470000 0.0046110000 0.0000040000 0.0000030000 0.0013270000 45311509 96830484 509673472 3.8773014545 4.0368332863 3.9243006706 2616 1311867805.9129049778 0.1279855669 0.1239360753 0.2376661599 0.0046017182 0.0131520000 0.0004450000 0.0046010000 0.0000010000 0.0000040000 0.0010540000 45315349 96830484 509673472 3.8744027615 4.0360894203 3.9250814915 2617 1311867805.9434199333 0.1297492832 0.1239382966 0.2376661599 0.0046017541 0.0140410000 0.0004410000 0.0045940000 0.0000030000 0.0000030000 0.0019890000 45319021 96830484 509673472 3.8730642796 4.0355539322 3.9255063534 2618 1311867805.9747679234 0.1278386712 0.1239397864 0.2376661599 0.0046012703 0.0131460000 0.0004410000 0.0045630000 0.0000010000 0.0000030000 0.0010620000 45322637 96830484 509673472 3.8752262592 4.0370044708 3.9252305031 2619 1311867806.0099248886 0.1335121542 0.1239434414 0.2376661599 0.0046036660 0.0136510000 0.0004400000 0.0045820000 0.0000040000 0.0000030000 0.0013440000 45326365 96830484 509673472 3.8700878620 4.0369734764 3.9263341427 2620 1311867806.0427870750 0.1311935931 0.1239462086 0.2376661599 0.0046034206 0.0173330000 0.0005510000 0.0048180000 0.0000010000 0.0000080000 0.0011940000 45330149 96830484 509673472 3.8729982376 4.0370349884 3.9264366627 2621 1311867806.0743720531 0.1324163973 0.1239494403 0.2376661599 0.0046090752 0.0142120000 0.0004420000 0.0045770000 0.0000040000 0.0000040000 0.0019960000 45333709 96830484 509673472 3.8721768856 4.0381531715 3.9270720482 2622 1311867806.1078710556 0.1330212504 0.1239529002 0.2376661599 0.0046082053 0.0115870000 0.0004350000 0.0027310000 0.0000010000 0.0000040000 0.0010680000 45337437 96830484 509673472 3.8722789288 4.0375995636 3.9272744656 2623 1311867806.1461410522 0.1321969330 0.1239560431 0.2376661599 0.0046080183 0.0136280000 0.0004310000 0.0045460000 0.0000050000 0.0000040000 0.0013440000 45341277 96830484 509673472 3.8741984367 4.0385231972 3.9277968407 2624 1311867806.1751658916 0.1312592775 0.1239588264 0.2376661599 0.0046076242 0.0172050000 0.0005470000 0.0047980000 0.0000010000 0.0000080000 0.0011950000 45344837 96830484 509673472 3.8758964539 4.0397353172 3.9281997681 2625 1311867806.2106690407 0.1308351159 0.1239614459 0.2376661599 0.0046083955 0.0142890000 0.0004400000 0.0045730000 0.0000030000 0.0000030000 0.0019820000 45348621 96830484 509673472 3.8772366047 4.0387825966 3.9282536507 2626 1311867806.2435200214 0.1312001646 0.1239642025 0.2376661599 0.0046078180 0.0170140000 0.0005320000 0.0037110000 0.0000010000 0.0000080000 0.0012040000 45352349 96830484 509673472 3.8778092861 4.0385389328 3.9288942814 2627 1311867806.2773389816 0.1304792166 0.1239666825 0.2376661599 0.0046075414 0.0137610000 0.0004500000 0.0045980000 0.0000050000 0.0000040000 0.0013530000 45356077 96830484 509673472 3.8792636395 4.0405344963 3.9293348789 2628 1311867806.3098840714 0.1306319237 0.1239692187 0.2376661599 0.0046068905 0.0132900000 0.0004310000 0.0045540000 0.0000000000 0.0000040000 0.0010650000 45359693 96830484 509673472 3.8799045086 4.0392417908 3.9295186996 2629 1311867806.3459429741 0.1311154217 0.1239719370 0.2376661599 0.0046067332 0.0178350000 0.0005310000 0.0048050000 0.0000080000 0.0000080000 0.0021590000 45363533 96830484 509673472 3.8801970482 4.0401377678 3.9300677776 2630 1311867806.3760368824 0.1314364821 0.1239747752 0.2376661599 0.0046061341 0.0129870000 0.0004420000 0.0042130000 0.0000000000 0.0000030000 0.0010650000 45367149 96830484 509673472 3.8805236816 4.0411577225 3.9305257797 2631 1311867806.4090569019 0.1325661689 0.1239780406 0.2376661599 0.0046129849 0.0120260000 0.0004450000 0.0030900000 0.0000040000 0.0000040000 0.0013320000 45370821 96830484 509673472 3.8803927898 4.0394392014 3.9306957722 2632 1311867806.4434189796 0.1316490620 0.1239809552 0.2376661599 0.0046131248 0.0131220000 0.0004370000 0.0045530000 0.0000000000 0.0000030000 0.0010640000 45374549 96830484 509673472 3.8819293976 4.0393528938 3.9305574894 2633 1311867806.4748079777 0.1313922703 0.1239837699 0.2376661599 0.0046150327 0.0132500000 0.0004370000 0.0038050000 0.0000040000 0.0000030000 0.0019870000 45378221 96830484 509673472 3.8828179836 4.0401659012 3.9309072495 2634 1311867806.5103459358 0.1322490722 0.1239869079 0.2376661599 0.0046144623 0.0132480000 0.0004360000 0.0045440000 0.0000010000 0.0000040000 0.0010690000 45382005 96830484 509673472 3.8829066753 4.0384917259 3.9309463501 2635 1311867806.5426719189 0.1293261200 0.1239889341 0.2376661599 0.0046143951 0.0133860000 0.0004350000 0.0045210000 0.0000040000 0.0000040000 0.0013410000 45385677 96830484 509673472 3.8864748478 4.0391364098 3.9311718941 2636 1311867806.5787520409 0.1298729181 0.1239911663 0.2376661599 0.0046139239 0.0177290000 0.0005740000 0.0048250000 0.0000010000 0.0000070000 0.0011930000 45389405 96830484 509673472 3.8864195347 4.0409865379 3.9315533638 2637 1311867806.6116139889 0.1312163323 0.1239939062 0.2376661599 0.0046144247 0.0180980000 0.0005340000 0.0047810000 0.0000080000 0.0000080000 0.0021730000 45393189 96830484 509673472 3.8855183125 4.0397920609 3.9320659637 2638 1311867806.6448700428 0.1301380247 0.1239962353 0.2376661599 0.0046136173 0.0120210000 0.0004400000 0.0030950000 0.0000010000 0.0000040000 0.0010680000 45396861 96830484 509673472 3.8870236874 4.0402097702 3.9325115681 2639 1311867806.6744968891 0.1281477213 0.1239978084 0.2376661599 0.0046136027 0.0134220000 0.0004400000 0.0045410000 0.0000030000 0.0000040000 0.0013270000 45400477 96830484 509673472 3.8893482685 4.0422863960 3.9332764149 2640 1311867806.7064468861 0.1297354400 0.1239999818 0.2376661599 0.0046129943 0.0119260000 0.0004370000 0.0031010000 0.0000010000 0.0000040000 0.0010570000 45404149 96830484 509673472 3.8879814148 4.0417528152 3.9340507984 2641 1311867806.7427020073 0.1305691451 0.1240024692 0.2376661599 0.0046122558 0.0123480000 0.0004350000 0.0027310000 0.0000030000 0.0000030000 0.0019740000 45407933 96830484 509673472 3.8876311779 4.0413756371 3.9344167709 2642 1311867806.7790679932 0.1278657317 0.1240039314 0.2376661599 0.0046128842 0.0172610000 0.0005330000 0.0048240000 0.0000020000 0.0000080000 0.0011830000 45411661 96830484 509673472 3.8903234005 4.0426983833 3.9351749420 2643 1311867806.8067629337 0.1282888204 0.1240055526 0.2376661599 0.0046124341 0.0135760000 0.0004450000 0.0045910000 0.0000040000 0.0000030000 0.0013410000 45415277 96830484 509673472 3.8902940750 4.0421447754 3.9356338978 2644 1311867806.8439810276 0.1295408010 0.1240076461 0.2376661599 0.0046117583 0.0129170000 0.0004380000 0.0042130000 0.0000000000 0.0000040000 0.0010580000 45419061 96830484 509673472 3.8894081116 4.0406060219 3.9360227585 2645 1311867806.8763918877 0.1281494349 0.1240092120 0.2376661599 0.0046113937 0.0141100000 0.0004350000 0.0045710000 0.0000040000 0.0000040000 0.0019800000 45422733 96830484 509673472 3.8910744190 4.0426506996 3.9367473125 2646 1311867806.9124479294 0.1315892488 0.1240120767 0.2376661599 0.0046112135 0.0120650000 0.0004370000 0.0034790000 0.0000000000 0.0000040000 0.0010530000 45426517 96830484 509673472 3.8878428936 4.0419435501 3.9370055199 2647 1311867806.9446148872 0.1317227781 0.1240149897 0.2376661599 0.0046106112 0.0135140000 0.0004420000 0.0045580000 0.0000040000 0.0000030000 0.0013430000 45430133 96830484 509673472 3.8882703781 4.0405936241 3.9372489452 2648 1311867806.9770460129 0.1308642626 0.1240175763 0.2376661599 0.0046103726 0.0131670000 0.0004370000 0.0045480000 0.0000010000 0.0000040000 0.0010580000 45433917 96830484 509673472 3.8893702030 4.0424299240 3.9377419949 2649 1311867807.0138700008 0.1306067258 0.1240200637 0.2376661599 0.0046108925 0.0175630000 0.0005980000 0.0038040000 0.0000080000 0.0000070000 0.0021620000 45437645 96830484 509673472 3.8902649879 4.0409688950 3.9377944469 2650 1311867807.0428779125 0.1286616176 0.1240218153 0.2376661599 0.0046107859 0.0134260000 0.0004440000 0.0045760000 0.0000000000 0.0000030000 0.0010630000 45441317 96830484 509673472 3.8928551674 4.0398340225 3.9379127026 2651 1311867807.0794920921 0.1313836873 0.1240245923 0.2376661599 0.0046116551 0.0135560000 0.0004350000 0.0045720000 0.0000030000 0.0000030000 0.0013400000 45445045 96830484 509673472 3.8906414509 4.0393743515 3.9386656284 2652 1311867807.1121389866 0.1321060956 0.1240276396 0.2376661599 0.0046112287 0.0132280000 0.0004370000 0.0045500000 0.0000000000 0.0000030000 0.0010690000 45448773 96830484 509673472 3.8901951313 4.0407114029 3.9393448830 2653 1311867807.1428070068 0.1334835142 0.1240312038 0.2376661599 0.0046109364 0.0202880000 0.0006130000 0.0050270000 0.0000100000 0.0000100000 0.0023360000 45452445 96830484 509673472 3.8894157410 4.0391283035 3.9395716190 2654 1311867807.1802010536 0.1334880441 0.1240347671 0.2376661599 0.0046116846 0.0120090000 0.0004570000 0.0027470000 0.0000010000 0.0000040000 0.0010730000 45456117 96830484 509673472 3.8899266720 4.0403032303 3.9403388500 2655 1311867807.2105820179 0.1351378113 0.1240389490 0.2376661599 0.0046134183 0.0135940000 0.0004260000 0.0045080000 0.0000030000 0.0000040000 0.0013340000 45459733 96830484 509673472 3.8883883953 4.0427832603 3.9412164688 2656 1311867807.2429521084 0.1357068419 0.1240433420 0.2376661599 0.0046127834 0.0134160000 0.0004210000 0.0045090000 0.0000010000 0.0000040000 0.0010710000 45463405 96830484 509673472 3.8882274628 4.0411882401 3.9415709972 2657 1311867807.2808670998 0.1358029544 0.1240477679 0.2376661599 0.0046119770 0.0124450000 0.0004320000 0.0027160000 0.0000040000 0.0000040000 0.0019920000 45467245 96830484 509673472 3.8889117241 4.0394835472 3.9415597916 2658 1311867807.3107318878 0.1369999051 0.1240526408 0.2376661599 0.0046113542 0.0114510000 0.0004280000 0.0027020000 0.0000000000 0.0000030000 0.0010740000 45470861 96830484 509673472 3.8884603977 4.0397667885 3.9420468807 2659 1311867807.3434429169 0.1356914937 0.1240570180 0.2376661599 0.0046108550 0.0134310000 0.0004190000 0.0045110000 0.0000030000 0.0000030000 0.0013460000 45474533 96830484 509673472 3.8905365467 4.0394711494 3.9423887730 2660 1311867807.3776888847 0.1365347654 0.1240617089 0.2376661599 0.0046107711 0.0124550000 0.0004230000 0.0037960000 0.0000000000 0.0000030000 0.0010710000 45478261 96830484 509673472 3.8903901577 4.0380291939 3.9422564507 2661 1311867807.4111731052 0.1347498894 0.1240657255 0.2376661599 0.0046122828 0.0131260000 0.0004170000 0.0034410000 0.0000040000 0.0000040000 0.0020040000 45481989 96830484 509673472 3.8924808502 4.0389785767 3.9421861172 2662 1311867807.4426960945 0.1358071715 0.1240701362 0.2376661599 0.0046123566 0.0132890000 0.0004240000 0.0045020000 0.0000010000 0.0000040000 0.0010770000 45485661 96830484 509673472 3.8917896748 4.0398950577 3.9422583580 2663 1311867807.4781239033 0.1359687299 0.1240746043 0.2376661599 0.0046159403 0.0135460000 0.0004260000 0.0045220000 0.0000030000 0.0000040000 0.0013480000 45489389 96830484 509673472 3.8921763897 4.0378937721 3.9415292740 2664 1311867807.5104010105 0.1372312605 0.1240795430 0.2376661599 0.0046155767 0.0125270000 0.0004270000 0.0037720000 0.0000010000 0.0000040000 0.0010770000 45493005 96830484 509673472 3.8913373947 4.0371694565 3.9412765503 2665 1311867807.5430259705 0.1366867274 0.1240842737 0.2376661599 0.0046152689 0.0137920000 0.0004180000 0.0041380000 0.0000040000 0.0000040000 0.0020220000 45496677 96830484 509673472 3.8922250271 4.0377759933 3.9408810139 2666 1311867807.5746030807 0.1362545043 0.1240888387 0.2376661599 0.0046169064 0.0134520000 0.0004260000 0.0045020000 0.0000000000 0.0000030000 0.0010800000 45500349 96830484 509673472 3.8927559853 4.0356988907 3.9400632381 2667 1311867807.6121149063 0.1352543831 0.1240930252 0.2376661599 0.0046176544 0.0178860000 0.0005310000 0.0043850000 0.0000080000 0.0000080000 0.0014820000 45504189 96830484 509673472 3.8938694000 4.0351457596 3.9391405582 2668 1311867807.6434121132 0.1346861273 0.1240969956 0.2376661599 0.0046179102 0.0126980000 0.0004190000 0.0030780000 0.0000010000 0.0000050000 0.0010810000 45507861 96830484 509673472 3.8945755959 4.0352721214 3.9386878014 2669 1311867807.6772611141 0.1342308074 0.1241007925 0.2376661599 0.0046176326 0.0162350000 0.0004900000 0.0048900000 0.0000040000 0.0000050000 0.0022300000 45511589 96830484 509673472 3.8949818611 4.0346069336 3.9376904964 2670 1311867807.7112979889 0.1355600506 0.1241050844 0.2376661599 0.0046169767 0.0140680000 0.0004010000 0.0044780000 0.0000000000 0.0000040000 0.0010840000 45515317 96830484 509673472 3.8935899734 4.0326738358 3.9370021820 2671 1311867807.7441759109 0.1331018656 0.1241084527 0.2376661599 0.0046187379 0.0130480000 0.0004060000 0.0030340000 0.0000040000 0.0000040000 0.0013620000 45519045 96830484 509673472 3.8956170082 4.0350494385 3.9368386269 2672 1311867807.7760479450 0.1352762282 0.1241126322 0.2376661599 0.0046188189 0.0133260000 0.0004070000 0.0044490000 0.0000010000 0.0000040000 0.0010910000 45522661 96830484 509673472 3.8930764198 4.0357074738 3.9370055199 2673 1311867807.8105859756 0.1335511059 0.1241161633 0.2376661599 0.0046192080 0.0136150000 0.0004110000 0.0037350000 0.0000030000 0.0000040000 0.0020070000 45526389 96830484 509673472 3.8942110538 4.0351386070 3.9362356663 2674 1311867807.8429179192 0.1330317557 0.1241194974 0.2376661599 0.0046189056 0.0133790000 0.0003990000 0.0044320000 0.0000000000 0.0000030000 0.0010990000 45530061 96830484 509673472 3.8944332600 4.0356488228 3.9361472130 2675 1311867807.8800721169 0.1328060627 0.1241227448 0.2376661599 0.0046183362 0.0135820000 0.0004000000 0.0044300000 0.0000030000 0.0000030000 0.0013730000 45533789 96830484 509673472 3.8940052986 4.0370669365 3.9360210896 2676 1311867807.9118909836 0.1336983293 0.1241263231 0.2376661599 0.0046180686 0.0176330000 0.0004980000 0.0046990000 0.0000010000 0.0000080000 0.0012240000 45537517 96830484 509673472 3.8928308487 4.0353059769 3.9358177185 2677 1311867807.9477560520 0.1297261864 0.1241284149 0.2376661599 0.0046206433 0.0131840000 0.0004180000 0.0030340000 0.0000040000 0.0000040000 0.0020570000 45541245 96830484 509673472 3.8966233730 4.0343132019 3.9349219799 2678 1311867807.9757928848 0.1302549690 0.1241307027 0.2376661599 0.0046199090 0.0124040000 0.0003990000 0.0033680000 0.0000000000 0.0000040000 0.0010970000 45544805 96830484 509673472 3.8959019184 4.0348582268 3.9351069927 2679 1311867808.0103120804 0.1285087466 0.1241323369 0.2376661599 0.0046220446 0.0119400000 0.0003990000 0.0026550000 0.0000030000 0.0000040000 0.0013710000 45548533 96830484 509673472 3.8980014324 4.0357570648 3.9348156452 2680 1311867808.0437099934 0.1327594668 0.1241355559 0.2376661599 0.0046239515 0.0121370000 0.0003970000 0.0030080000 0.0000010000 0.0000040000 0.0011060000 45552261 96830484 509673472 3.8937737942 4.0366663933 3.9352428913 2681 1311867808.0799739361 0.1375623196 0.1241405641 0.2376661599 0.0046507156 0.0127570000 0.0004040000 0.0026740000 0.0000040000 0.0000040000 0.0020650000 45556045 96830484 509673472 3.8894002438 4.0358777046 3.9345803261 2682 1311867808.1118609905 0.1358623654 0.1241449346 0.2376661599 0.0046528360 0.0124680000 0.0004020000 0.0033580000 0.0000010000 0.0000040000 0.0011040000 45559717 96830484 509673472 3.8913171291 4.0355262756 3.9334118366 2683 1311867808.1470420361 0.1325116605 0.1241480530 0.2376661599 0.0046532742 0.0181110000 0.0004910000 0.0046900000 0.0000090000 0.0000070000 0.0014980000 45563445 96830484 509673472 3.8948013783 4.0344977379 3.9316861629 2684 1311867808.1792190075 0.1364491731 0.1241526362 0.2376661599 0.0046563497 0.0158640000 0.0004920000 0.0031970000 0.0000010000 0.0000090000 0.0012240000 45567061 96830484 509673472 3.8908896446 4.0356750488 3.9316384792 2685 1311867808.2112250328 0.1353449672 0.1241568046 0.2376661599 0.0046784737 0.0145570000 0.0004000000 0.0044190000 0.0000040000 0.0000040000 0.0020770000 45570789 96830484 509673472 3.8912405968 4.0332407951 3.9300026894 2686 1311867808.2432029247 0.1341087967 0.1241605098 0.2376661599 0.0046776709 0.0133880000 0.0003970000 0.0044040000 0.0000010000 0.0000040000 0.0011320000 45574517 96830484 509673472 3.8928546906 4.0324668884 3.9287390709 2687 1311867808.2811930180 0.1365988553 0.1241651388 0.2376661599 0.0046783407 0.0129810000 0.0003910000 0.0036890000 0.0000040000 0.0000030000 0.0013940000 45578301 96830484 509673472 3.8906996250 4.0326957703 3.9282615185 2688 1311867808.3112449646 0.1356806457 0.1241694229 0.2376661599 0.0046775509 0.0171430000 0.0005150000 0.0046270000 0.0000010000 0.0000080000 0.0012390000 45581917 96830484 509673472 3.8919792175 4.0326375961 3.9275355339 2689 1311867808.3454720974 0.1378720254 0.1241745187 0.2376661599 0.0046774685 0.0145070000 0.0004050000 0.0044080000 0.0000030000 0.0000030000 0.0020910000 45585645 96830484 509673472 3.8902406693 4.0325474739 3.9275255203 2690 1311867808.3792409897 0.1372101307 0.1241793646 0.2376661599 0.0046767240 0.0178560000 0.0004830000 0.0046480000 0.0000010000 0.0000080000 0.0012300000 45589317 96830484 509673472 3.8910062313 4.0326099396 3.9269285202 2691 1311867808.4111659527 0.1403133124 0.1241853602 0.2376661599 0.0046763005 0.0139390000 0.0004060000 0.0043730000 0.0000040000 0.0000040000 0.0013920000 45593045 96830484 509673472 3.8881862164 4.0320224762 3.9266428947 2692 1311867808.4447789192 0.1384533197 0.1241906603 0.2376661599 0.0046762031 0.0135000000 0.0003950000 0.0043450000 0.0000000000 0.0000030000 0.0011220000 45596717 96830484 509673472 3.8901157379 4.0335607529 3.9261844158 2693 1311867808.4827229977 0.1410843730 0.1241969335 0.2376661599 0.0046778990 0.0144710000 0.0003860000 0.0043440000 0.0000030000 0.0000030000 0.0020930000 45600613 96830484 509673472 3.8875749111 4.0326852798 3.9262578487 2694 1311867808.5103700161 0.1379719973 0.1242020467 0.2376661599 0.0046853192 0.0123890000 0.0003840000 0.0032990000 0.0000010000 0.0000040000 0.0011190000 45604117 96830484 509673472 3.8909273148 4.0316095352 3.9252026081 2695 1311867808.5431969166 0.1404730827 0.1242080842 0.2376661599 0.0046867173 0.0136390000 0.0003870000 0.0043270000 0.0000030000 0.0000040000 0.0013950000 45607901 96830484 509673472 3.8883516788 4.0337376595 3.9255471230 2696 1311867808.5788240433 0.1418605447 0.1242146319 0.2376661599 0.0046859500 0.0129380000 0.0004030000 0.0039990000 0.0000010000 0.0000040000 0.0011240000 45611629 96830484 509673472 3.8870573044 4.0320200920 3.9248075485 2697 1311867808.6111960411 0.1398838162 0.1242204417 0.2376661599 0.0046853053 0.0143640000 0.0003870000 0.0043390000 0.0000040000 0.0000040000 0.0021090000 45615301 96830484 509673472 3.8889441490 4.0319995880 3.9244387150 2698 1311867808.6424980164 0.1375330687 0.1242253760 0.2376661599 0.0046847451 0.0133010000 0.0003820000 0.0043410000 0.0000010000 0.0000040000 0.0011340000 45618973 96830484 509673472 3.8911912441 4.0319070816 3.9234945774 2699 1311867808.6796329021 0.1417001784 0.1242318505 0.2376661599 0.0046853199 0.0136260000 0.0003850000 0.0043380000 0.0000040000 0.0000030000 0.0014080000 45622701 96830484 509673472 3.8869168758 4.0322694778 3.9237260818 2700 1311867808.7121589184 0.1410722584 0.1242380877 0.2376661599 0.0046846559 0.0116490000 0.0003840000 0.0025880000 0.0000010000 0.0000040000 0.0011310000 45626485 96830484 509673472 3.8875377178 4.0326004028 3.9231882095 2701 1311867808.7424249649 0.1405379474 0.1242441225 0.2376661599 0.0046847288 0.0126190000 0.0003870000 0.0025900000 0.0000030000 0.0000030000 0.0021210000 45630101 96830484 509673472 3.8883688450 4.0312647820 3.9222671986 2702 1311867808.7797210217 0.1422993690 0.1242508046 0.2376661599 0.0046847391 0.0171370000 0.0004860000 0.0045930000 0.0000010000 0.0000090000 0.0012570000 45633885 96830484 509673472 3.8870644569 4.0298223495 3.9219388962 2703 1311867808.8102169037 0.1417548209 0.1242572804 0.2376661599 0.0046853484 0.0138870000 0.0003870000 0.0043470000 0.0000030000 0.0000030000 0.0014160000 45637501 96830484 509673472 3.8876676559 4.0314860344 3.9214479923 2704 1311867808.8426899910 0.1416370869 0.1242637079 0.2376661599 0.0046890865 0.0178620000 0.0004800000 0.0045910000 0.0000010000 0.0000080000 0.0012650000 45641173 96830484 509673472 3.8880901337 4.0296573639 3.9198930264 2705 1311867808.8811960220 0.1397663206 0.1242694390 0.2376661599 0.0046884752 0.0137800000 0.0003950000 0.0036300000 0.0000040000 0.0000040000 0.0021480000 45645069 96830484 509673472 3.8903329372 4.0300216675 3.9189612865 2706 1311867808.9101860523 0.1421136558 0.1242760333 0.2376661599 0.0046881075 0.0134060000 0.0003930000 0.0042960000 0.0000010000 0.0000040000 0.0011360000 45648629 96830484 509673472 3.8882293701 4.0298247337 3.9192154408 2707 1311867808.9424829483 0.1392295808 0.1242815573 0.2376661599 0.0046881112 0.0118840000 0.0003840000 0.0026040000 0.0000040000 0.0000030000 0.0014140000 45652357 96830484 509673472 3.8914403915 4.0279812813 3.9176855087 2708 1311867808.9811229706 0.1413701028 0.1242878677 0.2376661599 0.0046908614 0.0131740000 0.0003820000 0.0042810000 0.0000010000 0.0000040000 0.0011360000 45656197 96830484 509673472 3.8894152641 4.0287914276 3.9174032211 2709 1311867809.0102269650 0.1419093311 0.1242943725 0.2376661599 0.0046902085 0.0139110000 0.0003810000 0.0039480000 0.0000030000 0.0000040000 0.0021440000 45659757 96830484 509673472 3.8887658119 4.0295662880 3.9170360565 2710 1311867809.0425639153 0.1403902173 0.1243003119 0.2376661599 0.0046895052 0.0139030000 0.0004240000 0.0042930000 0.0000010000 0.0000040000 0.0011440000 45663485 96830484 509673472 3.8906645775 4.0277571678 3.9155275822 2711 1311867809.0782320499 0.1413981020 0.1243066187 0.2376661599 0.0046901905 0.0135540000 0.0003810000 0.0042730000 0.0000030000 0.0000030000 0.0014230000 45667213 96830484 509673472 3.8898012638 4.0286226273 3.9154527187 2712 1311867809.1110110283 0.1393852979 0.1243121787 0.2376661599 0.0046897467 0.0178640000 0.0004900000 0.0045560000 0.0000010000 0.0000080000 0.0012650000 45670941 96830484 509673472 3.8918220997 4.0295658112 3.9144384861 2713 1311867809.1425359249 0.1421898007 0.1243187683 0.2376661599 0.0046899827 0.0163740000 0.0004730000 0.0027270000 0.0000080000 0.0000080000 0.0023150000 45674613 96830484 509673472 3.8892631531 4.0286245346 3.9142024517 2714 1311867809.1801810265 0.1449121684 0.1243263562 0.2376661599 0.0046910595 0.0169000000 0.0004660000 0.0035050000 0.0000010000 0.0000080000 0.0012700000 45678397 96830484 509673472 3.8867464066 4.0295715332 3.9140202999 2715 1311867809.2120649815 0.1447342932 0.1243338729 0.2376661599 0.0046913022 0.0137470000 0.0003880000 0.0043010000 0.0000050000 0.0000040000 0.0014260000 45682069 96830484 509673472 3.8872127533 4.0311365128 3.9143028259 2716 1311867809.2422831059 0.1423126012 0.1243404925 0.2376661599 0.0046906406 0.0133930000 0.0003740000 0.0042870000 0.0000000000 0.0000030000 0.0011410000 45685741 96830484 509673472 3.8898413181 4.0316500664 3.9136707783 2717 1311867809.2790520191 0.1425131857 0.1243471810 0.2376661599 0.0046901706 0.0124990000 0.0003790000 0.0025540000 0.0000040000 0.0000040000 0.0021390000 45689413 96830484 509673472 3.8900175095 4.0301322937 3.9129359722 2718 1311867809.3103950024 0.1431795210 0.1243541097 0.2376661599 0.0046894719 0.0125600000 0.0003720000 0.0035680000 0.0000010000 0.0000040000 0.0011400000 45693085 96830484 509673472 3.8897933960 4.0309300423 3.9129683971 2719 1311867809.3436670303 0.1473211944 0.1243625566 0.2376661599 0.0046896805 0.0126480000 0.0003780000 0.0032340000 0.0000040000 0.0000030000 0.0014250000 45696813 96830484 509673472 3.8862781525 4.0307025909 3.9132933617 2720 1311867809.3787779808 0.1461277008 0.1243705585 0.2376661599 0.0046888558 0.0132790000 0.0003730000 0.0042620000 0.0000010000 0.0000040000 0.0011510000 45700485 96830484 509673472 3.8880686760 4.0308542252 3.9128608704 2721 1311867809.4101309776 0.1468604803 0.1243788238 0.2376661599 0.0046883011 0.0131760000 0.0003650000 0.0028840000 0.0000030000 0.0000030000 0.0021260000 45704157 96830484 509673472 3.8879280090 4.0305156708 3.9122397900 2722 1311867809.4475460052 0.1446123570 0.1243862571 0.2376661599 0.0046888124 0.0133150000 0.0003740000 0.0042420000 0.0000000000 0.0000040000 0.0011470000 45707997 96830484 509673472 3.8911449909 4.0308475494 3.9116051197 2723 1311867809.4785499573 0.1439088136 0.1243934267 0.2376661599 0.0046882868 0.0125500000 0.0003740000 0.0032320000 0.0000030000 0.0000030000 0.0014310000 45711725 96830484 509673472 3.8924303055 4.0305638313 3.9108142853 2724 1311867809.5100600719 0.1448333710 0.1244009303 0.2376661599 0.0046891019 0.0132780000 0.0003750000 0.0042430000 0.0000000000 0.0000040000 0.0011460000 45715285 96830484 509673472 3.8921818733 4.0315837860 3.9107613564 2725 1311867809.5460391045 0.1438304633 0.1244080604 0.2376661599 0.0046883888 0.0141870000 0.0003850000 0.0042240000 0.0000040000 0.0000030000 0.0021390000 45719125 96830484 509673472 3.8939559460 4.0327363014 3.9100141525 2726 1311867809.5791211128 0.1449953318 0.1244156126 0.2376661599 0.0046876558 0.0131360000 0.0003760000 0.0042320000 0.0000000000 0.0000040000 0.0011410000 45722797 96830484 509673472 3.8938527107 4.0325279236 3.9099144936 2727 1311867809.6122300625 0.1440964788 0.1244228296 0.2376661599 0.0046871529 0.0124150000 0.0003780000 0.0032090000 0.0000030000 0.0000040000 0.0014200000 45726525 96830484 509673472 3.8952338696 4.0346732140 3.9093184471 2728 1311867809.6463921070 0.1404558569 0.1244287068 0.2376661599 0.0046875662 0.0174430000 0.0004720000 0.0041490000 0.0000010000 0.0000080000 0.0012730000 45730253 96830484 509673472 3.8997035027 4.0346550941 3.9082973003 2729 1311867809.6796839237 0.1417494714 0.1244350538 0.2376661599 0.0046870612 0.0152490000 0.0003810000 0.0042780000 0.0000040000 0.0000030000 0.0021540000 45733925 96830484 509673472 3.8995039463 4.0354566574 3.9089038372 2730 1311867809.7111020088 0.1439150870 0.1244421893 0.2376661599 0.0046864696 0.0138270000 0.0004240000 0.0042350000 0.0000000000 0.0000030000 0.0011280000 45737597 96830484 509673472 3.8982758522 4.0348773003 3.9082782269 2731 1311867809.7464809418 0.1409077048 0.1244482184 0.2376661599 0.0046864988 0.0125480000 0.0003750000 0.0028970000 0.0000040000 0.0000030000 0.0014090000 45741381 96830484 509673472 3.9023160934 4.0340795517 3.9065394402 2732 1311867809.7800478935 0.1441061944 0.1244554139 0.2376661599 0.0046864778 0.0133700000 0.0003670000 0.0042360000 0.0000010000 0.0000040000 0.0011310000 45745053 96830484 509673472 3.9003357887 4.0346150398 3.9063699245 2733 1311867809.8107759953 0.1407036036 0.1244613591 0.2376661599 0.0046878210 0.0146690000 0.0003730000 0.0042310000 0.0000030000 0.0000040000 0.0021520000 45748725 96830484 509673472 3.9047627449 4.0344471931 3.9046044350 2734 1311867809.8470799923 0.1414211839 0.1244675624 0.2376661599 0.0046870670 0.0131310000 0.0003740000 0.0038970000 0.0000000000 0.0000040000 0.0011460000 45752509 96830484 509673472 3.9049308300 4.0338511467 3.9034466743 2735 1311867809.8791100979 0.1430096328 0.1244743419 0.2376661599 0.0046868770 0.0138980000 0.0003660000 0.0042310000 0.0000030000 0.0000030000 0.0014270000 45756181 96830484 509673472 3.9040257931 4.0335650444 3.9020614624 2736 1311867809.9124441147 0.1418393701 0.1244806888 0.2376661599 0.0046870827 0.0134030000 0.0003700000 0.0042290000 0.0000010000 0.0000040000 0.0011410000 45759853 96830484 509673472 3.9059238434 4.0337343216 3.9006092548 2737 1311867809.9469900131 0.1430580318 0.1244874763 0.2376661599 0.0046864611 0.0143510000 0.0003670000 0.0041990000 0.0000030000 0.0000030000 0.0021330000 45763581 96830484 509673472 3.9051795006 4.0329403877 3.8994486332 2738 1311867809.9805769920 0.1437878460 0.1244945253 0.2376661599 0.0046875240 0.0175240000 0.0004640000 0.0044300000 0.0000010000 0.0000080000 0.0012620000 45767197 96830484 509673472 3.9044327736 4.0345535278 3.8983333111 2739 1311867810.0119459629 0.1479997337 0.1245031070 0.2376661599 0.0046885331 0.0180570000 0.0004670000 0.0041200000 0.0000070000 0.0000080000 0.0015390000 45770813 96830484 509673472 3.9003088474 4.0340557098 3.8981568813 2740 1311867810.0470910072 0.1472828686 0.1245114208 0.2376661599 0.0046876961 0.0137380000 0.0003650000 0.0042040000 0.0000010000 0.0000050000 0.0011570000 45774541 96830484 509673472 3.9010288715 4.0332579613 3.8975329399 2741 1311867810.0808799267 0.1449072361 0.1245188618 0.2376661599 0.0046878614 0.0135990000 0.0003610000 0.0031800000 0.0000040000 0.0000030000 0.0021620000 45778213 96830484 509673472 3.9030232430 4.0349874496 3.8967635632 2742 1311867810.1118919849 0.1469611973 0.1245270465 0.2376661599 0.0046879380 0.0135360000 0.0003580000 0.0041730000 0.0000010000 0.0000040000 0.0011530000 45781885 96830484 509673472 3.9008648396 4.0357303619 3.8970596790 2743 1311867810.1474719048 0.1468875557 0.1245351983 0.2376661599 0.0046871758 0.0138410000 0.0003510000 0.0041710000 0.0000040000 0.0000040000 0.0014260000 45785669 96830484 509673472 3.9007916451 4.0357112885 3.8965117931 2744 1311867810.1817660332 0.1444750726 0.1245424650 0.2376661599 0.0046865852 0.0182050000 0.0004600000 0.0044710000 0.0000010000 0.0000080000 0.0012710000 45789341 96830484 509673472 3.9031414986 4.0344905853 3.8957414627 2745 1311867810.2106039524 0.1435989439 0.1245494073 0.2376661599 0.0046858500 0.0149440000 0.0003670000 0.0042010000 0.0000050000 0.0000040000 0.0021880000 45792957 96830484 509673472 3.9038453102 4.0364546776 3.8948647976 2746 1311867810.2471721172 0.1418391317 0.1245557036 0.2376661599 0.0046876155 0.0134660000 0.0003520000 0.0041730000 0.0000010000 0.0000040000 0.0011420000 45796741 96830484 509673472 3.9059898853 4.0367860794 3.8939950466 2747 1311867810.2785871029 0.1426928788 0.1245623062 0.2376661599 0.0046867746 0.0174480000 0.0004830000 0.0040780000 0.0000080000 0.0000070000 0.0015440000 45800357 96830484 509673472 3.9051678181 4.0363545418 3.8934528828 2748 1311867810.3111360073 0.1411540210 0.1245683439 0.2376661599 0.0046861716 0.0137590000 0.0003630000 0.0041930000 0.0000010000 0.0000040000 0.0011730000 45804085 96830484 509673472 3.9068698883 4.0360178947 3.8932192326 2749 1311867810.3463029861 0.1405360848 0.1245741525 0.2376661599 0.0046857856 0.0145770000 0.0003590000 0.0041750000 0.0000040000 0.0000030000 0.0021720000 45807869 96830484 509673472 3.9077131748 4.0351648331 3.8927583694 2750 1311867810.3784830570 0.1380714029 0.1245790606 0.2376661599 0.0046853247 0.0135810000 0.0003570000 0.0041810000 0.0000000000 0.0000040000 0.0011540000 45811597 96830484 509673472 3.9101464748 4.0351152420 3.8919966221 2751 1311867810.4100239277 0.1352044493 0.1245829229 0.2376661599 0.0046847280 0.0138000000 0.0003510000 0.0041690000 0.0000040000 0.0000040000 0.0014300000 45815157 96830484 509673472 3.9129598141 4.0342416763 3.8909559250 2752 1311867810.4462749958 0.1351276040 0.1245867546 0.2376661599 0.0046839920 0.0134130000 0.0003590000 0.0041790000 0.0000000000 0.0000030000 0.0011500000 45818941 96830484 509673472 3.9131126404 4.0341992378 3.8904862404 2753 1311867810.4781119823 0.1341525316 0.1245902292 0.2376661599 0.0046837581 0.0147070000 0.0003590000 0.0041990000 0.0000040000 0.0000040000 0.0021740000 45822557 96830484 509673472 3.9142045975 4.0352959633 3.8901548386 2754 1311867810.5101990700 0.1320563257 0.1245929402 0.2376661599 0.0046832175 0.0135260000 0.0003570000 0.0041940000 0.0000000000 0.0000030000 0.0011680000 45826229 96830484 509673472 3.9164276123 4.0358524323 3.8895854950 2755 1311867810.5459640026 0.1326303035 0.1245958576 0.2376661599 0.0046825817 0.0136510000 0.0003600000 0.0042060000 0.0000040000 0.0000040000 0.0014320000 45830013 96830484 509673472 3.9161937237 4.0354833603 3.8894431591 2756 1311867810.5791409016 0.1284427494 0.1245972534 0.2376661599 0.0046819979 0.0134830000 0.0003570000 0.0041880000 0.0000010000 0.0000040000 0.0011400000 45833685 96830484 509673472 3.9204027653 4.0367426872 3.8888278008 2757 1311867810.6141140461 0.1292041093 0.1245989244 0.2376661599 0.0046813718 0.0225630000 0.0005330000 0.0047360000 0.0000140000 0.0000160000 0.0027100000 45837469 96830484 509673472 3.9195275307 4.0374994278 3.8886077404 2758 1311867810.6471910477 0.1232858077 0.1245984483 0.2376661599 0.0046836596 0.0139140000 0.0003710000 0.0040160000 0.0000010000 0.0000040000 0.0011530000 45841197 96830484 509673472 3.9255392551 4.0365672112 3.8878929615 2759 1311867810.6781129837 0.1283769011 0.1245998178 0.2376661599 0.0046847214 0.0129530000 0.0003660000 0.0032010000 0.0000030000 0.0000030000 0.0014250000 45844813 96830484 509673472 3.9202635288 4.0378918648 3.8880612850 2760 1311867810.7146449089 0.1226618960 0.1245991157 0.2376661599 0.0046859187 0.0134870000 0.0003650000 0.0042080000 0.0000000000 0.0000030000 0.0011480000 45848597 96830484 509673472 3.9262630939 4.0381250381 3.8873460293 2761 1311867810.7468900681 0.1190526709 0.1245971068 0.2376661599 0.0046859669 0.0145900000 0.0003650000 0.0042090000 0.0000040000 0.0000030000 0.0021620000 45852325 96830484 509673472 3.9300105572 4.0377192497 3.8869295120 2762 1311867810.7789669037 0.1185360923 0.1245949124 0.2376661599 0.0046865013 0.0135090000 0.0003620000 0.0042060000 0.0000010000 0.0000040000 0.0011520000 45855997 96830484 509673472 3.9305875301 4.0381665230 3.8865830898 2763 1311867810.8146491051 0.1204520836 0.1245934130 0.2376661599 0.0046858475 0.0139090000 0.0003580000 0.0042090000 0.0000030000 0.0000030000 0.0014300000 45859725 96830484 509673472 3.9289195538 4.0379252434 3.8862662315 2764 1311867810.8460769653 0.1193399727 0.1245915123 0.2376661599 0.0046895166 0.0122990000 0.0003580000 0.0028580000 0.0000010000 0.0000040000 0.0011490000 45863397 96830484 509673472 3.9299302101 4.0388050079 3.8859293461 2765 1311867810.8793289661 0.1209755093 0.1245902045 0.2376661599 0.0046892361 0.0144580000 0.0003610000 0.0042080000 0.0000040000 0.0000030000 0.0021710000 45867125 96830484 509673472 3.9284076691 4.0404520035 3.8861660957 2766 1311867810.9141631126 0.1143269017 0.1245864940 0.2376661599 0.0046925481 0.0135880000 0.0003600000 0.0042380000 0.0000010000 0.0000040000 0.0011480000 45870909 96830484 509673472 3.9356176853 4.0407013893 3.8861439228 2767 1311867810.9458940029 0.1142796576 0.1245827691 0.2376661599 0.0046954766 0.0177470000 0.0004530000 0.0044570000 0.0000070000 0.0000070000 0.0015510000 45874525 96830484 509673472 3.9361169338 4.0403370857 3.8853991032 2768 1311867810.9796259403 0.1149389297 0.1245792851 0.2376661599 0.0046948432 0.0137260000 0.0003720000 0.0042330000 0.0000000000 0.0000030000 0.0011620000 45878197 96830484 509673472 3.9357814789 4.0406947136 3.8852880001 2769 1311867811.0151500702 0.1138277426 0.1245754022 0.2376661599 0.0046991619 0.0161370000 0.0003610000 0.0047970000 0.0000040000 0.0000030000 0.0022060000 45881981 96830484 509673472 3.9370658398 4.0410008430 3.8848102093 2770 1311867811.0469939709 0.1120845303 0.1245708929 0.2376661599 0.0046991007 0.0141570000 0.0003650000 0.0042350000 0.0000010000 0.0000050000 0.0011500000 45885653 96830484 509673472 3.9390718937 4.0428857803 3.8843929768 2771 1311867811.0785760880 0.1124587804 0.1245665219 0.2376661599 0.0046990858 0.0145500000 0.0003660000 0.0042300000 0.0000040000 0.0000040000 0.0014310000 45889325 96830484 509673472 3.9390799999 4.0429711342 3.8840212822 2772 1311867811.1144239902 0.1075246260 0.1245603740 0.2376661599 0.0047003236 0.0142690000 0.0003570000 0.0042270000 0.0000010000 0.0000050000 0.0011650000 45893109 96830484 509673472 3.9443283081 4.0442667007 3.8836951256 2773 1311867811.1461989880 0.1067121252 0.1245539376 0.2376661599 0.0046998334 0.0152440000 0.0003580000 0.0042260000 0.0000040000 0.0000040000 0.0021460000 45896781 96830484 509673472 3.9454169273 4.0447168350 3.8831639290 2774 1311867811.1786370277 0.1049591899 0.1245468738 0.2376661599 0.0046991555 0.0139170000 0.0003860000 0.0039070000 0.0000010000 0.0000050000 0.0011580000 45900509 96830484 509673472 3.9475455284 4.0459537506 3.8829209805 2775 1311867811.2142488956 0.1067571118 0.1245404631 0.2376661599 0.0046994995 0.0144590000 0.0003690000 0.0042270000 0.0000040000 0.0000040000 0.0014300000 45904181 96830484 509673472 3.9461696148 4.0448484421 3.8827881813 2776 1311867811.2464840412 0.1093711480 0.1245349987 0.2376661599 0.0047000506 0.0132260000 0.0003640000 0.0032140000 0.0000010000 0.0000040000 0.0011470000 45907909 96830484 509673472 3.9434356689 4.0468864441 3.8827960491 2777 1311867811.2798390388 0.1028385833 0.1245271858 0.2376661599 0.0047017875 0.0152590000 0.0003620000 0.0042290000 0.0000040000 0.0000040000 0.0021520000 45911637 96830484 509673472 3.9504048824 4.0473146439 3.8821325302 2778 1311867811.3147039413 0.1077309772 0.1245211396 0.2376661599 0.0047045196 0.0142540000 0.0003650000 0.0042260000 0.0000010000 0.0000040000 0.0011530000 45915365 96830484 509673472 3.9455106258 4.0480976105 3.8818895817 2779 1311867811.3470849991 0.1072080582 0.1245149096 0.2376661599 0.0047053105 0.0136860000 0.0003680000 0.0032120000 0.0000040000 0.0000040000 0.0014370000 45919037 96830484 509673472 3.9462220669 4.0473704338 3.8815417290 2780 1311867811.3799240589 0.1087576896 0.1245092416 0.2376661599 0.0047054288 0.0135070000 0.0003680000 0.0035520000 0.0000010000 0.0000050000 0.0011490000 45922709 96830484 509673472 3.9448881149 4.0495033264 3.8817389011 2781 1311867811.4141869545 0.1076992899 0.1245031970 0.2376661599 0.0047055271 0.0154160000 0.0003630000 0.0042460000 0.0000040000 0.0000050000 0.0021570000 45926437 96830484 509673472 3.9465131760 4.0493617058 3.8815696239 2782 1311867811.4464430809 0.1098720133 0.1244979378 0.2376661599 0.0047052428 0.0142420000 0.0003800000 0.0042390000 0.0000010000 0.0000040000 0.0011480000 45930165 96830484 509673472 3.9443824291 4.0504446030 3.8807830811 2783 1311867811.4788289070 0.1081442460 0.1244920615 0.2376661599 0.0047054939 0.0145490000 0.0003620000 0.0042390000 0.0000040000 0.0000040000 0.0014230000 45933893 96830484 509673472 3.9462418556 4.0522685051 3.8802845478 2784 1311867811.5141620636 0.1106545255 0.1244870911 0.2376661599 0.0047074831 0.0142120000 0.0003700000 0.0042410000 0.0000000000 0.0000040000 0.0011490000 45937565 96830484 509673472 3.9441657066 4.0534772873 3.8809337616 2785 1311867811.5465340614 0.1073719040 0.1244809456 0.2376661599 0.0047074220 0.0145800000 0.0003670000 0.0035680000 0.0000040000 0.0000040000 0.0021540000 45941293 96830484 509673472 3.9480867386 4.0538096428 3.8803720474 2786 1311867811.5787150860 0.1111055836 0.1244761447 0.2376661599 0.0047102146 0.0142950000 0.0003680000 0.0042620000 0.0000000000 0.0000040000 0.0011430000 45944965 96830484 509673472 3.9444227219 4.0559420586 3.8799312115 2787 1311867811.6143789291 0.1092647463 0.1244706867 0.2376661599 0.0047106246 0.0146530000 0.0003620000 0.0042690000 0.0000040000 0.0000040000 0.0014170000 45948693 96830484 509673472 3.9463274479 4.0577964783 3.8798742294 2788 1311867811.6465210915 0.1115761921 0.1244660617 0.2376661599 0.0047199811 0.0133890000 0.0003640000 0.0032420000 0.0000010000 0.0000050000 0.0011540000 45952421 96830484 509673472 3.9443652630 4.0556135178 3.8800423145 2789 1311867811.6790111065 0.1069169343 0.1244597695 0.2376661599 0.0047221467 0.0164890000 0.0003780000 0.0048410000 0.0000040000 0.0000040000 0.0022120000 45956037 96830484 509673472 3.9498162270 4.0551314354 3.8794603348 2790 1311867811.7141160965 0.1097722426 0.1244545051 0.2376661599 0.0047233342 0.0144830000 0.0003660000 0.0042740000 0.0000010000 0.0000050000 0.0011440000 45959821 96830484 509673472 3.9472494125 4.0568985939 3.8794167042 2791 1311867811.7471590042 0.1082317978 0.1244486926 0.2376661599 0.0047237805 0.0129240000 0.0003650000 0.0025540000 0.0000040000 0.0000040000 0.0014110000 45963549 96830484 509673472 3.9488766193 4.0578622818 3.8789057732 2792 1311867811.7787630558 0.1098777577 0.1244434738 0.2376661599 0.0047239573 0.0128580000 0.0003690000 0.0029020000 0.0000010000 0.0000040000 0.0011480000 45967221 96830484 509673472 3.9471998215 4.0568223000 3.8782377243 2793 1311867811.8140239716 0.1092836112 0.1244380460 0.2376661599 0.0047233323 0.0146770000 0.0003670000 0.0035660000 0.0000040000 0.0000040000 0.0021360000 45971005 96830484 509673472 3.9479289055 4.0574474335 3.8782839775 2794 1311867811.8467700481 0.1091206074 0.1244325637 0.2376661599 0.0047229462 0.0143740000 0.0003710000 0.0042440000 0.0000000000 0.0000040000 0.0011440000 45974677 96830484 509673472 3.9482533932 4.0571613312 3.8778440952 2795 1311867811.8873019218 0.1091433540 0.1244270935 0.2376661599 0.0047224635 0.0146630000 0.0003650000 0.0042410000 0.0000050000 0.0000040000 0.0014190000 45978573 96830484 509673472 3.9484043121 4.0575013161 3.8776581287 2796 1311867811.9162950516 0.1072187051 0.1244209389 0.2376661599 0.0047217161 0.0142740000 0.0003650000 0.0042410000 0.0000010000 0.0000050000 0.0011520000 45982077 96830484 509673472 3.9502909184 4.0574297905 3.8771069050 2797 1311867811.9480459690 0.1098248884 0.1244157204 0.2376661599 0.0047217237 0.0152840000 0.0003620000 0.0042390000 0.0000040000 0.0000040000 0.0021570000 45985693 96830484 509673472 3.9477326870 4.0570521355 3.8768880367 2798 1311867811.9825990200 0.1085859835 0.1244100629 0.2376661599 0.0047213639 0.0129820000 0.0003650000 0.0028740000 0.0000010000 0.0000060000 0.0011550000 45989477 96830484 509673472 3.9490997791 4.0572137833 3.8762884140 2799 1311867812.0155920982 0.1080170944 0.1244042062 0.2376661599 0.0047208006 0.0146570000 0.0003640000 0.0042160000 0.0000040000 0.0000040000 0.0014360000 45993149 96830484 509673472 3.9500839710 4.0566163063 3.8761644363 2800 1311867812.0471529961 0.1104628816 0.1243992271 0.2376661599 0.0047208122 0.0136240000 0.0003630000 0.0035550000 0.0000010000 0.0000040000 0.0011600000 45996821 96830484 509673472 3.9475429058 4.0579433441 3.8761458397 2801 1311867812.0860528946 0.1119598672 0.1243947861 0.2376661599 0.0047201013 0.0151830000 0.0003630000 0.0042180000 0.0000040000 0.0000040000 0.0021430000 46000717 96830484 509673472 3.9462654591 4.0582151413 3.8763206005 2802 1311867812.1176469326 0.1108636782 0.1243899570 0.2376661599 0.0047194299 0.0142920000 0.0003560000 0.0042210000 0.0000010000 0.0000040000 0.0011450000 46004389 96830484 509673472 3.9476051331 4.0578680038 3.8761844635 2803 1311867812.1501319408 0.1097420305 0.1243847312 0.2376661599 0.0047186665 0.0135800000 0.0003550000 0.0032030000 0.0000050000 0.0000040000 0.0014340000 46008005 96830484 509673472 3.9489121437 4.0581121445 3.8757064342 2804 1311867812.1841530800 0.1097222492 0.1243795021 0.2376661599 0.0047178539 0.0135380000 0.0003640000 0.0035550000 0.0000000000 0.0000040000 0.0011540000 46011789 96830484 509673472 3.9492435455 4.0581645966 3.8758275509 2805 1311867812.2161788940 0.1100485846 0.1243743930 0.2376661599 0.0047238098 0.0153560000 0.0003650000 0.0042340000 0.0000050000 0.0000040000 0.0021450000 46015461 96830484 509673472 3.9496600628 4.0579681396 3.8762435913 2806 1311867812.2469139099 0.1107783616 0.1243695477 0.2376661599 0.0047235279 0.0130030000 0.0003640000 0.0028720000 0.0000000000 0.0000040000 0.0011500000 46019077 96830484 509673472 3.9488854408 4.0590124130 3.8758926392 2807 1311867812.2830879688 0.1082772762 0.1243638147 0.2376661599 0.0047339912 0.0147530000 0.0003680000 0.0042270000 0.0000040000 0.0000040000 0.0014290000 46022917 96830484 509673472 3.9514822960 4.0597720146 3.8761768341 2808 1311867812.3143959045 0.1098302528 0.1243586390 0.2376661599 0.0047427945 0.0129750000 0.0003640000 0.0028750000 0.0000010000 0.0000040000 0.0011500000 46026477 96830484 509673472 3.9505250454 4.0601124763 3.8762571812 2809 1311867812.3466560841 0.1100922748 0.1243535602 0.2376661599 0.0047420234 0.0153470000 0.0003620000 0.0042230000 0.0000040000 0.0000040000 0.0021550000 46030205 96830484 509673472 3.9507765770 4.0602135658 3.8766629696 2810 1311867812.3833289146 0.1090563759 0.1243481163 0.2376661599 0.0047416549 0.0140760000 0.0003540000 0.0038790000 0.0000010000 0.0000040000 0.0011580000 46034045 96830484 509673472 3.9522817135 4.0596642494 3.8767464161 2811 1311867812.4177269936 0.1098535433 0.1243429600 0.2376661599 0.0047410425 0.0146340000 0.0003590000 0.0042120000 0.0000040000 0.0000040000 0.0014270000 46037773 96830484 509673472 3.9520053864 4.0604109764 3.8766963482 2812 1311867812.4586019516 0.1105065420 0.1243380395 0.2376661599 0.0047402725 0.0143690000 0.0003600000 0.0042220000 0.0000010000 0.0000050000 0.0011560000 46041669 96830484 509673472 3.9519236088 4.0608778000 3.8770205975 2813 1311867812.4830911160 0.1125015467 0.1243338317 0.2376661599 0.0047400149 0.0147670000 0.0003580000 0.0035560000 0.0000050000 0.0000040000 0.0021450000 46045005 96830484 509673472 3.9499349594 4.0606665611 3.8768661022 2814 1311867812.5157220364 0.1106379479 0.1243289646 0.2376661599 0.0047433733 0.0143790000 0.0003600000 0.0042100000 0.0000010000 0.0000050000 0.0011580000 46048621 96830484 509673472 3.9517414570 4.0612797737 3.8767151833 2815 1311867812.5469310284 0.1100559607 0.1243238943 0.2376661599 0.0047427626 0.0145910000 0.0003610000 0.0042020000 0.0000050000 0.0000040000 0.0014300000 46052293 96830484 509673472 3.9526517391 4.0616970062 3.8764076233 2816 1311867812.5857439041 0.1083065048 0.1243182063 0.2376661599 0.0047420015 0.0142210000 0.0003580000 0.0042000000 0.0000000000 0.0000040000 0.0011550000 46056133 96830484 509673472 3.9547913074 4.0619311333 3.8761346340 2817 1311867812.6147639751 0.1093238890 0.1243128835 0.2376661599 0.0047413092 0.0153190000 0.0003510000 0.0042090000 0.0000040000 0.0000040000 0.0021750000 46059693 96830484 509673472 3.9539823532 4.0618920326 3.8762445450 2818 1311867812.6462490559 0.1084976569 0.1243072713 0.2376661599 0.0047409032 0.0142960000 0.0003510000 0.0041910000 0.0000010000 0.0000040000 0.0011590000 46063421 96830484 509673472 3.9549210072 4.0620164871 3.8757629395 2819 1311867812.6821310520 0.1082521528 0.1243015760 0.2376661599 0.0047402788 0.0135600000 0.0003530000 0.0031940000 0.0000040000 0.0000040000 0.0014240000 46067205 96830484 509673472 3.9552190304 4.0620565414 3.8755097389 2820 1311867812.7141439915 0.1058481857 0.1242950322 0.2376661599 0.0047400930 0.0136110000 0.0003560000 0.0035210000 0.0000000000 0.0000040000 0.0011700000 46070821 96830484 509673472 3.9574506283 4.0627546310 3.8750696182 2821 1311867812.7468860149 0.1075181365 0.1242890851 0.2376661599 0.0047398226 0.0148190000 0.0003580000 0.0035120000 0.0000050000 0.0000040000 0.0021540000 46074549 96830484 509673472 3.9555835724 4.0631322861 3.8750936985 2822 1311867812.7839629650 0.1093876362 0.1242838046 0.2376661599 0.0047392413 0.0145140000 0.0003540000 0.0041820000 0.0000000000 0.0000040000 0.0011620000 46078389 96830484 509673472 3.9535501003 4.0634012222 3.8751287460 2823 1311867812.8143351078 0.1078023985 0.1242779663 0.2376661599 0.0047410587 0.0146800000 0.0003570000 0.0041920000 0.0000040000 0.0000040000 0.0014450000 46081949 96830484 509673472 3.9550781250 4.0630989075 3.8750019073 2824 1311867812.8463029861 0.1082286984 0.1242722832 0.2376661599 0.0047407407 0.0127020000 0.0003580000 0.0025090000 0.0000010000 0.0000050000 0.0011660000 46085677 96830484 509673472 3.9543015957 4.0640821457 3.8748233318 2825 1311867812.8841478825 0.1084131524 0.1242666693 0.2376661599 0.0047447831 0.0153740000 0.0003560000 0.0041770000 0.0000050000 0.0000040000 0.0021700000 46089517 96830484 509673472 3.9535686970 4.0656046867 3.8749785423 2826 1311867812.9142088890 0.1067408025 0.1242604677 0.2376661599 0.0047441641 0.0130330000 0.0003590000 0.0028480000 0.0000010000 0.0000040000 0.0011690000 46093077 96830484 509673472 3.9549558163 4.0655207634 3.8750114441 2827 1311867812.9470400810 0.1100551113 0.1242554428 0.2376661599 0.0047447752 0.0145140000 0.0004050000 0.0035180000 0.0000040000 0.0000040000 0.0014430000 46096805 96830484 509673472 3.9511699677 4.0652055740 3.8751337528 2828 1311867812.9833469391 0.1078360230 0.1242496368 0.2376661599 0.0047449491 0.0132520000 0.0003560000 0.0031600000 0.0000000000 0.0000040000 0.0011680000 46100533 96830484 509673472 3.9530036449 4.0664753914 3.8751614094 2829 1311867813.0143780708 0.1104763299 0.1242447682 0.2376661599 0.0047527920 0.0146220000 0.0003530000 0.0035060000 0.0000040000 0.0000040000 0.0021680000 46104205 96830484 509673472 3.9502732754 4.0666627884 3.8757884502 2830 1311867813.0462698936 0.1091759279 0.1242394435 0.2376661599 0.0047601326 0.0142530000 0.0003530000 0.0041810000 0.0000000000 0.0000040000 0.0011700000 46107877 96830484 509673472 3.9508583546 4.0674624443 3.8757629395 2831 1311867813.0825068951 0.1079484001 0.1242336890 0.2376661599 0.0047649887 0.0145090000 0.0003500000 0.0041520000 0.0000040000 0.0000040000 0.0014430000 46111717 96830484 509673472 3.9516155720 4.0685110092 3.8754613400 2832 1311867813.1142160892 0.1081897616 0.1242280237 0.2376661599 0.0047686880 0.0143590000 0.0003570000 0.0042000000 0.0000010000 0.0000050000 0.0011700000 46115389 96830484 509673472 3.9507515430 4.0686712265 3.8757295609 2833 1311867813.1504809856 0.1100625843 0.1242230236 0.2376661599 0.0047688363 0.0153080000 0.0003570000 0.0041850000 0.0000050000 0.0000040000 0.0021760000 46119117 96830484 509673472 3.9486982822 4.0680446625 3.8757834435 2834 1311867813.1829130650 0.1066959202 0.1242168390 0.2376661599 0.0047693362 0.0127910000 0.0003570000 0.0025080000 0.0000000000 0.0000040000 0.0011700000 46122845 96830484 509673472 3.9514956474 4.0693140030 3.8752608299 2835 1311867813.2166841030 0.1081878170 0.1242111850 0.2376661599 0.0047698016 0.0145910000 0.0003550000 0.0041710000 0.0000050000 0.0000040000 0.0014510000 46126517 96830484 509673472 3.9495117664 4.0701689720 3.8754363060 2836 1311867813.2536849976 0.1075144410 0.1242052976 0.2376661599 0.0047703601 0.0139910000 0.0003550000 0.0038420000 0.0000010000 0.0000050000 0.0011740000 46130301 96830484 509673472 3.9496774673 4.0692949295 3.8752510548 2837 1311867813.2831010818 0.1081476212 0.1241996375 0.2376661599 0.0047772270 0.0152570000 0.0003540000 0.0041560000 0.0000050000 0.0000040000 0.0021700000 46133917 96830484 509673472 3.9490089417 4.0706067085 3.8753404617 2838 1311867813.3142321110 0.1108109429 0.1241949198 0.2376661599 0.0047795539 0.0143310000 0.0003540000 0.0041840000 0.0000010000 0.0000050000 0.0011720000 46137589 96830484 509673472 3.9458916187 4.0720200539 3.8757522106 2839 1311867813.3517169952 0.1092105284 0.1241896418 0.2376661599 0.0047980638 0.0132510000 0.0003580000 0.0028480000 0.0000040000 0.0000040000 0.0014410000 46141373 96830484 509673472 3.9467003345 4.0712871552 3.8756449223 2840 1311867813.3851261139 0.1085611805 0.1241841388 0.2376661599 0.0047974297 0.0144730000 0.0003730000 0.0041740000 0.0000010000 0.0000050000 0.0011670000 46145101 96830484 509673472 3.9472603798 4.0713496208 3.8756701946 2841 1311867813.4148280621 0.1092470065 0.1241788811 0.2376661599 0.0048154280 0.0144240000 0.0003540000 0.0031660000 0.0000050000 0.0000040000 0.0021640000 46148661 96830484 509673472 3.9468884468 4.0725350380 3.8762099743 2842 1311867813.4501829147 0.1084475070 0.1241733458 0.2376661599 0.0048272664 0.0134060000 0.0003490000 0.0031700000 0.0000010000 0.0000040000 0.0011780000 46152389 96830484 509673472 3.9472196102 4.0727362633 3.8758833408 2843 1311867813.4843769073 0.1092753783 0.1241681056 0.2376661599 0.0048272733 0.0147090000 0.0003520000 0.0041750000 0.0000040000 0.0000040000 0.0014530000 46156173 96830484 509673472 3.9465379715 4.0739946365 3.8762059212 2844 1311867813.5152790546 0.1117756441 0.1241637482 0.2376661599 0.0048335567 0.0130730000 0.0003510000 0.0028330000 0.0000000000 0.0000040000 0.0011700000 46159789 96830484 509673472 3.9437675476 4.0744147301 3.8766837120 2845 1311867813.5519089699 0.1123133451 0.1241595828 0.2376661599 0.0048370181 0.0153970000 0.0003540000 0.0041600000 0.0000050000 0.0000040000 0.0021910000 46163573 96830484 509673472 3.9430639744 4.0764346123 3.8769485950 2846 1311867813.5863409042 0.1126719341 0.1241555464 0.2376661599 0.0048363815 0.0155640000 0.0003610000 0.0047860000 0.0000000000 0.0000060000 0.0011760000 46167301 96830484 509673472 3.9423954487 4.0777082443 3.8769786358 2847 1311867813.6168019772 0.1150567308 0.1241523505 0.2376661599 0.0048475688 0.0148420000 0.0004000000 0.0041850000 0.0000050000 0.0000040000 0.0014380000 46170917 96830484 509673472 3.9394042492 4.0789794922 3.8774240017 2848 1311867813.6515810490 0.1161579266 0.1241495434 0.2376661599 0.0048473634 0.0144460000 0.0003570000 0.0041820000 0.0000010000 0.0000050000 0.0011710000 46174645 96830484 509673472 3.9384908676 4.0788650513 3.8774683475 2849 1311867813.6860060692 0.1148957163 0.1241462953 0.2376661599 0.0048468816 0.0143790000 0.0003560000 0.0031690000 0.0000040000 0.0000040000 0.0021710000 46178373 96830484 509673472 3.9399552345 4.0793766975 3.8769841194 2850 1311867813.7184169292 0.1138192490 0.1241426718 0.2376661599 0.0048461189 0.0134620000 0.0003540000 0.0031710000 0.0000010000 0.0000050000 0.0011710000 46182045 96830484 509673472 3.9410419464 4.0803604126 3.8766188622 2851 1311867813.7506020069 0.1162441224 0.1241399014 0.2376661599 0.0048461613 0.0147350000 0.0003570000 0.0041650000 0.0000050000 0.0000040000 0.0014600000 46185717 96830484 509673472 3.9383854866 4.0813722610 3.8764688969 2852 1311867813.7827889919 0.1178304404 0.1241376891 0.2376661599 0.0048457246 0.0131410000 0.0003560000 0.0028310000 0.0000010000 0.0000050000 0.0011750000 46189445 96830484 509673472 3.9368016720 4.0829334259 3.8760271072 2853 1311867813.8147668839 0.1181352884 0.1241355852 0.2376661599 0.0048448867 0.0147790000 0.0003530000 0.0041500000 0.0000030000 0.0000030000 0.0021820000 46193005 96830484 509673472 3.9368143082 4.0832986832 3.8761711121 2854 1311867813.8517930508 0.1185091808 0.1241336138 0.2376661599 0.0048442156 0.0118540000 0.0003520000 0.0021580000 0.0000000000 0.0000040000 0.0011840000 46196901 96830484 509673472 3.9366211891 4.0843963623 3.8758721352 2855 1311867813.8838069439 0.1184661239 0.1241316287 0.2376661599 0.0048441637 0.0137330000 0.0003500000 0.0038020000 0.0000040000 0.0000030000 0.0014390000 46200517 96830484 509673472 3.9371962547 4.0852241516 3.8753600121 2856 1311867813.9144020081 0.1213464737 0.1241306535 0.2376661599 0.0048437740 0.0176900000 0.0004590000 0.0030910000 0.0000010000 0.0000100000 0.0012970000 46204133 96830484 509673472 3.9342565536 4.0860347748 3.8753325939 2857 1311867813.9523379803 0.1237710565 0.1241305276 0.2376661599 0.0048442110 0.0191740000 0.0004490000 0.0044250000 0.0000080000 0.0000070000 0.0023350000 46208029 96830484 509673472 3.9321434498 4.0867748260 3.8756370544 2858 1311867813.9825320244 0.1242913902 0.1241305839 0.2376661599 0.0048435508 0.0137620000 0.0003550000 0.0038300000 0.0000000000 0.0000030000 0.0011840000 46211645 96830484 509673472 3.9321329594 4.0895471573 3.8755662441 2859 1311867814.0155770779 0.1220682412 0.1241298625 0.2376661599 0.0048484122 0.0126870000 0.0003470000 0.0028080000 0.0000040000 0.0000030000 0.0014490000 46215317 96830484 509673472 3.9355163574 4.0893950462 3.8753392696 2860 1311867814.0528070927 0.1211172417 0.1241288092 0.2376661599 0.0048477770 0.0137550000 0.0003480000 0.0041430000 0.0000000000 0.0000040000 0.0011790000 46219213 96830484 509673472 3.9364817142 4.0905399323 3.8753864765 2861 1311867814.0849530697 0.1216686368 0.1241279493 0.2376661599 0.0048475360 0.0128750000 0.0003390000 0.0024790000 0.0000030000 0.0000030000 0.0021680000 46222829 96830484 509673472 3.9360470772 4.0917596817 3.8747425079 2862 1311867814.1153879166 0.1253938079 0.1241283916 0.2376661599 0.0048477247 0.0136590000 0.0003380000 0.0041240000 0.0000000000 0.0000040000 0.0011720000 46226445 96830484 509673472 3.9327185154 4.0922412872 3.8750605583 2863 1311867814.1526429653 0.1254946291 0.1241288688 0.2376661599 0.0048471951 0.0138310000 0.0003330000 0.0041230000 0.0000040000 0.0000040000 0.0014490000 46230341 96830484 509673472 3.9333972931 4.0921454430 3.8749692440 2864 1311867814.1845281124 0.1240678653 0.1241288475 0.2376661599 0.0048468939 0.0135280000 0.0003480000 0.0041070000 0.0000000000 0.0000030000 0.0011760000 46234013 96830484 509673472 3.9353699684 4.0926847458 3.8746349812 2865 1311867814.2153480053 0.1280735284 0.1241302243 0.2376661599 0.0048472761 0.0145330000 0.0003430000 0.0041070000 0.0000030000 0.0000030000 0.0021850000 46237573 96830484 509673472 3.9313895702 4.0937204361 3.8747668266 2866 1311867814.2520170212 0.1321159601 0.1241330107 0.2376661599 0.0048468773 0.0134910000 0.0003450000 0.0037780000 0.0000010000 0.0000040000 0.0011860000 46241413 96830484 509673472 3.9275739193 4.0931496620 3.8748748302 2867 1311867814.2834239006 0.1371055096 0.1241375355 0.2376661599 0.0048475271 0.0140250000 0.0003410000 0.0041090000 0.0000040000 0.0000030000 0.0014550000 46245141 96830484 509673472 3.9230167866 4.0935397148 3.8753786087 2868 1311867814.3181779385 0.1378354281 0.1241423116 0.2376661599 0.0048467962 0.0131520000 0.0003380000 0.0034390000 0.0000010000 0.0000040000 0.0011840000 46248869 96830484 509673472 3.9225339890 4.0952486992 3.8750767708 2869 1311867814.3510050774 0.1368782222 0.1241467507 0.2376661599 0.0048484735 0.0142070000 0.0003370000 0.0034280000 0.0000030000 0.0000040000 0.0021890000 46252485 96830484 509673472 3.9238419533 4.0954999924 3.8745448589 2870 1311867814.3861339092 0.1376002580 0.1241514384 0.2376661599 0.0048476884 0.0184540000 0.0004490000 0.0043800000 0.0000010000 0.0000090000 0.0012890000 46256269 96830484 509673472 3.9232406616 4.0949406624 3.8741924763 2871 1311867814.4182898998 0.1382906735 0.1241563632 0.2376661599 0.0048477216 0.0180810000 0.0004520000 0.0043500000 0.0000080000 0.0000090000 0.0015770000 46259941 96830484 509673472 3.9227297306 4.0958290100 3.8738849163 2872 1311867814.4512650967 0.1356721669 0.1241603729 0.2376661599 0.0048478536 0.0125970000 0.0003450000 0.0027880000 0.0000010000 0.0000040000 0.0011970000 46263669 96830484 509673472 3.9253745079 4.0970287323 3.8731012344 2873 1311867814.4847788811 0.1363594085 0.1241646190 0.2376661599 0.0048471105 0.0146090000 0.0003330000 0.0040840000 0.0000040000 0.0000030000 0.0022120000 46267341 96830484 509673472 3.9248018265 4.0974359512 3.8730168343 2874 1311867814.5201790333 0.1366374791 0.1241689589 0.2376661599 0.0048532870 0.0185530000 0.0004270000 0.0043840000 0.0000010000 0.0000070000 0.0013080000 46271125 96830484 509673472 3.9242210388 4.0977430344 3.8728258610 2875 1311867814.5517210960 0.1368632019 0.1241733743 0.2376661599 0.0048526265 0.0132540000 0.0003380000 0.0031260000 0.0000050000 0.0000040000 0.0014770000 46274797 96830484 509673472 3.9237518311 4.0970387459 3.8729474545 2876 1311867814.5848219395 0.1391701400 0.1241785887 0.2376661599 0.0048522056 0.0124510000 0.0003350000 0.0028000000 0.0000000000 0.0000040000 0.0011940000 46278413 96830484 509673472 3.9209368229 4.0980591774 3.8729460239 2877 1311867814.6200098991 0.1387796700 0.1241836638 0.2376661599 0.0048518030 0.0131600000 0.0003340000 0.0024540000 0.0000040000 0.0000030000 0.0022070000 46282141 96830484 509673472 3.9205238819 4.0981621742 3.8726582527 2878 1311867814.6503028870 0.1362416893 0.1241878535 0.2376661599 0.0048513614 0.0184310000 0.0004300000 0.0043560000 0.0000010000 0.0000080000 0.0012930000 46285813 96830484 509673472 3.9223532677 4.1000404358 3.8726558685 2879 1311867814.6833140850 0.1397340745 0.1241932534 0.2376661599 0.0048512432 0.0143600000 0.0003420000 0.0041030000 0.0000040000 0.0000050000 0.0014670000 46289485 96830484 509673472 3.9183797836 4.0997915268 3.8733279705 2880 1311867814.7211821079 0.1377445310 0.1241979587 0.2376661599 0.0048510334 0.0120630000 0.0003350000 0.0021260000 0.0000000000 0.0000030000 0.0011790000 46293325 96830484 509673472 3.9196994305 4.1004743576 3.8734867573 2881 1311867814.7502319813 0.1390686333 0.1242031204 0.2376661599 0.0048503811 0.0132820000 0.0003360000 0.0024700000 0.0000040000 0.0000030000 0.0022010000 46296941 96830484 509673472 3.9180264473 4.1014232635 3.8741884232 2882 1311867814.7828900814 0.1408807486 0.1242089072 0.2376661599 0.0048509506 0.0138520000 0.0003430000 0.0041130000 0.0000010000 0.0000040000 0.0011870000 46300613 96830484 509673472 3.9159250259 4.1025433540 3.8746953011 2883 1311867814.8186480999 0.1427794099 0.1242153486 0.2376661599 0.0048506992 0.0131570000 0.0003430000 0.0031330000 0.0000050000 0.0000030000 0.0014510000 46304397 96830484 509673472 3.9141509533 4.1023564339 3.8756039143 2884 1311867814.8526010513 0.1391346902 0.1242205217 0.2376661599 0.0048505686 0.0180430000 0.0004360000 0.0026980000 0.0000010000 0.0000100000 0.0014120000 46308125 96830484 509673472 3.9178886414 4.1026520729 3.8756885529 2885 1311867814.8852329254 0.1437802762 0.1242273015 0.2376661599 0.0048515109 0.0162160000 0.0003540000 0.0047420000 0.0000040000 0.0000040000 0.0022080000 46311797 96830484 509673472 3.9130628109 4.1032066345 3.8764145374 2886 1311867814.9202771187 0.1454184949 0.1242346443 0.2376661599 0.0048508903 0.0182550000 0.0004800000 0.0040510000 0.0000010000 0.0000080000 0.0012930000 46315581 96830484 509673472 3.9113271236 4.1035523415 3.8771045208 2887 1311867814.9503459930 0.1437523216 0.1242414048 0.2376661599 0.0048502560 0.0142250000 0.0003440000 0.0041380000 0.0000040000 0.0000040000 0.0014690000 46319197 96830484 509673472 3.9131803513 4.1047291756 3.8772754669 2888 1311867814.9839959145 0.1442461610 0.1242483317 0.2376661599 0.0048514502 0.0137940000 0.0003490000 0.0041410000 0.0000000000 0.0000030000 0.0011860000 46322925 96830484 509673472 3.9128146172 4.1057896614 3.8776502609 2889 1311867815.0193099976 0.1444761753 0.1242553333 0.2376661599 0.0048537281 0.0130730000 0.0003440000 0.0024840000 0.0000030000 0.0000030000 0.0021870000 46326597 96830484 509673472 3.9129583836 4.1064267159 3.8779532909 2890 1311867815.0509970188 0.1446888894 0.1242624038 0.2376661599 0.0048529565 0.0136890000 0.0003440000 0.0041420000 0.0000010000 0.0000040000 0.0011980000 46330213 96830484 509673472 3.9132273197 4.1077766418 3.8784420490 2891 1311867815.0835149288 0.1457635611 0.1242698411 0.2376661599 0.0048537778 0.0168620000 0.0004480000 0.0023640000 0.0000240000 0.0000080000 0.0015400000 46333885 96830484 509673472 3.9128816128 4.1069035530 3.8788092136 2892 1311867815.1192519665 0.1518376917 0.1242793735 0.2376661599 0.0048547887 0.0140100000 0.0003550000 0.0041760000 0.0000010000 0.0000040000 0.0011760000 46337669 96830484 509673472 3.9075601101 4.1080212593 3.8794941902 2893 1311867815.1505639553 0.1540665478 0.1242896698 0.2376661599 0.0048556064 0.0145840000 0.0003530000 0.0038290000 0.0000040000 0.0000030000 0.0021940000 46341285 96830484 509673472 3.9060351849 4.1076850891 3.8796007633 2894 1311867815.1827230453 0.1594532281 0.1243018203 0.2376661599 0.0048576985 0.0128490000 0.0003590000 0.0031540000 0.0000010000 0.0000040000 0.0011750000 46345013 96830484 509673472 3.9015934467 4.1080055237 3.8800129890 2895 1311867815.2192549706 0.1674914360 0.1243167390 0.2376661599 0.0048624570 0.0123820000 0.0003480000 0.0024870000 0.0000030000 0.0000040000 0.0014600000 46348797 96830484 509673472 3.8944945335 4.1086177826 3.8807806969 2896 1311867815.2503280640 0.1673996001 0.1243316157 0.2376661599 0.0048618511 0.0131490000 0.0003620000 0.0034870000 0.0000000000 0.0000030000 0.0011830000 46352413 96830484 509673472 3.8954296112 4.1084074974 3.8809208870 2897 1311867815.2826719284 0.1670671552 0.1243463673 0.2376661599 0.0048611289 0.0195030000 0.0004470000 0.0044480000 0.0000090000 0.0000070000 0.0023320000 46356141 96830484 509673472 3.8966369629 4.1095938683 3.8812429905 2898 1311867815.3188140392 0.1704595089 0.1243622794 0.2376661599 0.0048608109 0.0173450000 0.0004470000 0.0027120000 0.0000020000 0.0000100000 0.0013250000 46359925 96830484 509673472 3.8937182426 4.1093425751 3.8817253113 2899 1311867815.3506569862 0.1713957340 0.1243785034 0.2376661599 0.0048600777 0.0143190000 0.0003660000 0.0042020000 0.0000040000 0.0000040000 0.0014660000 46363541 96830484 509673472 3.8933196068 4.1107454300 3.8819422722 2900 1311867815.3841490746 0.1706504077 0.1243944592 0.2376661599 0.0048598023 0.0137510000 0.0003550000 0.0041680000 0.0000000000 0.0000030000 0.0011770000 46367269 96830484 509673472 3.8946273327 4.1102538109 3.8818814754 2901 1311867815.4187209606 0.1709911972 0.1244105215 0.2376661599 0.0048601626 0.0147260000 0.0003550000 0.0041630000 0.0000030000 0.0000040000 0.0021720000 46371053 96830484 509673472 3.8944394588 4.1108746529 3.8822972775 2902 1311867815.4505259991 0.1710747480 0.1244266016 0.2376661599 0.0048594147 0.0116980000 0.0003510000 0.0021770000 0.0000010000 0.0000040000 0.0011690000 46374669 96830484 509673472 3.8945331573 4.1120014191 3.8826735020 2903 1311867815.4827210903 0.1716413349 0.1244428657 0.2376661599 0.0048591307 0.0135390000 0.0003540000 0.0035500000 0.0000030000 0.0000040000 0.0014660000 46378397 96830484 509673472 3.8940641880 4.1122860909 3.8831918240 2904 1311867815.5188379288 0.1695478410 0.1244583977 0.2376661599 0.0048583933 0.0125630000 0.0003560000 0.0028560000 0.0000010000 0.0000040000 0.0011710000 46382181 96830484 509673472 3.8961975574 4.1121206284 3.8831682205 2905 1311867815.5508639812 0.1689787507 0.1244737231 0.2376661599 0.0048577303 0.0153930000 0.0004200000 0.0039200000 0.0000030000 0.0000040000 0.0021780000 46385797 96830484 509673472 3.8967754841 4.1131029129 3.8833272457 2906 1311867815.5879790783 0.1637870967 0.1244872515 0.2376661599 0.0048593209 0.0140530000 0.0004140000 0.0041910000 0.0000010000 0.0000040000 0.0011720000 46389637 96830484 509673472 3.9023296833 4.1134076118 3.8834154606 2907 1311867815.6201279163 0.1644941270 0.1245010137 0.2376661599 0.0048598369 0.0128840000 0.0003540000 0.0028700000 0.0000030000 0.0000030000 0.0014430000 46393309 96830484 509673472 3.9018001556 4.1136999130 3.8841829300 2908 1311867815.6522359848 0.1605063826 0.1245133952 0.2376661599 0.0048592607 0.0138560000 0.0003540000 0.0041910000 0.0000010000 0.0000040000 0.0011760000 46397037 96830484 509673472 3.9061272144 4.1140913963 3.8838157654 2909 1311867815.6869289875 0.1608490348 0.1245258860 0.2376661599 0.0048598962 0.0139940000 0.0003560000 0.0031870000 0.0000040000 0.0000040000 0.0021770000 46400765 96830484 509673472 3.9062738419 4.1135263443 3.8844182491 2910 1311867815.7186810970 0.1606880724 0.1245383128 0.2376661599 0.0048628212 0.0139000000 0.0003560000 0.0042050000 0.0000000000 0.0000030000 0.0011800000 46404493 96830484 509673472 3.9066100121 4.1150870323 3.8846774101 2911 1311867815.7527859211 0.1620696783 0.1245512058 0.2376661599 0.0048756372 0.0192220000 0.0004590000 0.0034590000 0.0000100000 0.0000110000 0.0016740000 46408165 96830484 509673472 3.9057598114 4.1149487495 3.8851747513 2912 1311867815.7881309986 0.1597198695 0.1245632829 0.2376661599 0.0048751223 0.0141790000 0.0003730000 0.0042490000 0.0000000000 0.0000040000 0.0011750000 46411949 96830484 509673472 3.9082887173 4.1152634621 3.8847973347 2913 1311867815.8185119629 0.1627775431 0.1245764015 0.2376661599 0.0048874704 0.0149140000 0.0003530000 0.0042130000 0.0000040000 0.0000030000 0.0021730000 46415509 96830484 509673472 3.9054713249 4.1155571938 3.8855082989 2914 1311867815.8516321182 0.1609537005 0.1245888851 0.2376661599 0.0048867268 0.0123820000 0.0003590000 0.0028730000 0.0000000000 0.0000030000 0.0011690000 46419237 96830484 509673472 3.9076471329 4.1154026985 3.8856878281 2915 1311867815.8881559372 0.1631333679 0.1246021079 0.2376661599 0.0048864655 0.0142940000 0.0003570000 0.0042090000 0.0000030000 0.0000040000 0.0014370000 46423077 96830484 509673472 3.9058659077 4.1158695221 3.8862514496 2916 1311867815.9183700085 0.1647507995 0.1246158763 0.2376661599 0.0048860423 0.0132570000 0.0003700000 0.0032050000 0.0000010000 0.0000030000 0.0011660000 46426637 96830484 509673472 3.9046654701 4.1169981956 3.8868761063 2917 1311867815.9544029236 0.1642657518 0.1246294690 0.2376661599 0.0048855977 0.0150610000 0.0003540000 0.0042240000 0.0000040000 0.0000040000 0.0021700000 46430421 96830484 509673472 3.9055819511 4.1166906357 3.8869929314 2918 1311867815.9880459309 0.1633376628 0.1246427343 0.2376661599 0.0048884621 0.0141200000 0.0003590000 0.0042230000 0.0000000000 0.0000040000 0.0011830000 46434149 96830484 509673472 3.9067666531 4.1167931557 3.8872418404 2919 1311867816.0232369900 0.1578142494 0.1246540983 0.2376661599 0.0048898639 0.0133910000 0.0003620000 0.0032050000 0.0000040000 0.0000030000 0.0014350000 46437933 96830484 509673472 3.9129874706 4.1176409721 3.8867871761 2920 1311867816.0513160229 0.1584632844 0.1246656768 0.2376661599 0.0048892689 0.0181480000 0.0004540000 0.0037970000 0.0000010000 0.0000080000 0.0012820000 46441437 96830484 509673472 3.9130969048 4.1181383133 3.8875372410 2921 1311867816.0872139931 0.1664232016 0.1246799724 0.2376661599 0.0048936106 0.0150620000 0.0003710000 0.0042530000 0.0000040000 0.0000040000 0.0021700000 46445277 96830484 509673472 3.9057085514 4.1188001633 3.8884377480 2922 1311867816.1192660332 0.1662515253 0.1246941995 0.2376661599 0.0048927916 0.0182040000 0.0004700000 0.0034770000 0.0000010000 0.0000110000 0.0013060000 46448893 96830484 509673472 3.9066343307 4.1186823845 3.8887574673 2923 1311867816.1530499458 0.1663992107 0.1247084674 0.2376661599 0.0048923075 0.0135030000 0.0003710000 0.0032370000 0.0000050000 0.0000040000 0.0014500000 46452509 96830484 509673472 3.9071533680 4.1193799973 3.8891856670 2924 1311867816.1877670288 0.1619613767 0.1247212078 0.2376661599 0.0048945572 0.0130690000 0.0003610000 0.0028750000 0.0000000000 0.0000030000 0.0011810000 46456293 96830484 509673472 3.9120974541 4.1203947067 3.8891553879 2925 1311867816.2185130119 0.1633199006 0.1247344039 0.2376661599 0.0048941954 0.0187010000 0.0004580000 0.0044480000 0.0000080000 0.0000080000 0.0023240000 46459965 96830484 509673472 3.9111890793 4.1205034256 3.8893375397 2926 1311867816.2509930134 0.1631632149 0.1247475375 0.2376661599 0.0048964116 0.0140580000 0.0003670000 0.0042290000 0.0000000000 0.0000040000 0.0011700000 46463581 96830484 509673472 3.9116642475 4.1213726997 3.8896400928 2927 1311867816.2875878811 0.1602309048 0.1247596603 0.2376661599 0.0048967341 0.0130290000 0.0003560000 0.0028830000 0.0000040000 0.0000040000 0.0014400000 46467365 96830484 509673472 3.9150617123 4.1208910942 3.8892607689 2928 1311867816.3221759796 0.1574114263 0.1247708118 0.2376661599 0.0048959920 0.0139270000 0.0003620000 0.0042060000 0.0000000000 0.0000040000 0.0011810000 46471149 96830484 509673472 3.9183220863 4.1219172478 3.8890552521 2929 1311867816.3515660763 0.1639022678 0.1247841718 0.2376661599 0.0048977396 0.0195540000 0.0004560000 0.0045010000 0.0000080000 0.0000070000 0.0023220000 46474709 96830484 509673472 3.9123637676 4.1213994026 3.8896064758 2930 1311867816.3902490139 0.1662590206 0.1247983271 0.2376661599 0.0048975268 0.0125460000 0.0003660000 0.0025480000 0.0000000000 0.0000040000 0.0011760000 46478549 96830484 509673472 3.9103188515 4.1208434105 3.8892610073 2931 1311867816.4188189507 0.1674041748 0.1248128634 0.2376661599 0.0048969172 0.0122350000 0.0003600000 0.0022090000 0.0000030000 0.0000030000 0.0014440000 46482165 96830484 509673472 3.9092667103 4.1196403503 3.8888435364 2932 1311867816.4527490139 0.1688994318 0.1248278997 0.2376661599 0.0048965261 0.0141580000 0.0003540000 0.0042160000 0.0000010000 0.0000040000 0.0011750000 46485893 96830484 509673472 3.9079065323 4.1207942963 3.8888187408 2933 1311867816.4875969887 0.1707624793 0.1248435610 0.2376661599 0.0048983632 0.0138710000 0.0003590000 0.0028640000 0.0000040000 0.0000040000 0.0021690000 46489621 96830484 509673472 3.9058065414 4.1195044518 3.8883762360 2934 1311867816.5199189186 0.1735355556 0.1248601568 0.2376661599 0.0048982194 0.0140940000 0.0003760000 0.0042180000 0.0000000000 0.0000030000 0.0011700000 46493237 96830484 509673472 3.9028239250 4.1195549965 3.8880968094 2935 1311867816.5529119968 0.1737899035 0.1248768279 0.2376661599 0.0048999267 0.0141190000 0.0003590000 0.0040910000 0.0000040000 0.0000040000 0.0014360000 46497021 96830484 509673472 3.9025120735 4.1193308830 3.8882277012 2936 1311867816.5888628960 0.1715386361 0.1248927209 0.2376661599 0.0048997344 0.0127270000 0.0003570000 0.0028700000 0.0000010000 0.0000040000 0.0011610000 46500805 96830484 509673472 3.9046807289 4.1185455322 3.8875982761 2937 1311867816.6194050312 0.1723872870 0.1249088920 0.2376661599 0.0048989685 0.0139890000 0.0003580000 0.0032240000 0.0000040000 0.0000040000 0.0021460000 46504421 96830484 509673472 3.9033827782 4.1182632446 3.8875155449 2938 1311867816.6509261131 0.1731288433 0.1249253045 0.2376661599 0.0048984579 0.0139400000 0.0003560000 0.0042330000 0.0000010000 0.0000030000 0.0011540000 46508037 96830484 509673472 3.9021625519 4.1178288460 3.8873147964 2939 1311867816.6893680096 0.1725109071 0.1249414956 0.2376661599 0.0048978697 0.0139350000 0.0003540000 0.0038740000 0.0000030000 0.0000040000 0.0014270000 46511933 96830484 509673472 3.9019834995 4.1170268059 3.8869180679 2940 1311867816.7204029560 0.1738063097 0.1249581163 0.2376661599 0.0048988587 0.0177040000 0.0004650000 0.0027660000 0.0000010000 0.0000120000 0.0013830000 46515493 96830484 509673472 3.8996477127 4.1163640022 3.8867607117 2941 1311867816.7523219585 0.1739480644 0.1249747739 0.2376661599 0.0048980292 0.0136110000 0.0003710000 0.0025620000 0.0000040000 0.0000050000 0.0021530000 46519165 96830484 509673472 3.8984875679 4.1163973808 3.8865962029 2942 1311867816.7867000103 0.1729056984 0.1249910658 0.2376661599 0.0048974276 0.0141330000 0.0003600000 0.0042180000 0.0000000000 0.0000030000 0.0011590000 46522893 96830484 509673472 3.8990113735 4.1166329384 3.8861649036 2943 1311867816.8192241192 0.1735983938 0.1250075821 0.2376661599 0.0048970668 0.0177310000 0.0004550000 0.0034090000 0.0000080000 0.0000070000 0.0015250000 46526565 96830484 509673472 3.8976893425 4.1149554253 3.8860192299 2944 1311867816.8584229946 0.1742603034 0.1250243119 0.2376661599 0.0048969241 0.0133060000 0.0004090000 0.0025730000 0.0000000000 0.0000050000 0.0011570000 46530461 96830484 509673472 3.8964018822 4.1144199371 3.8854999542 2945 1311867816.8891038895 0.1725957394 0.1250404652 0.2376661599 0.0048963175 0.0153650000 0.0004080000 0.0042370000 0.0000030000 0.0000030000 0.0021290000 46534021 96830484 509673472 3.8978068829 4.1129541397 3.8847951889 2946 1311867816.9194529057 0.1738700271 0.1250570401 0.2376661599 0.0049047963 0.0127340000 0.0003620000 0.0025320000 0.0000010000 0.0000040000 0.0011520000 46537693 96830484 509673472 3.8964381218 4.1129884720 3.8847610950 2947 1311867816.9566609859 0.1745584458 0.1250738373 0.2376661599 0.0049058721 0.0146390000 0.0003540000 0.0042280000 0.0000030000 0.0000030000 0.0014310000 46541365 96830484 509673472 3.8948132992 4.1119070053 3.8844928741 2948 1311867816.9880828857 0.1720723212 0.1250897798 0.2376661599 0.0049201789 0.0126460000 0.0003610000 0.0025500000 0.0000010000 0.0000040000 0.0011530000 46545037 96830484 509673472 3.8965733051 4.1118812561 3.8837752342 2949 1311867817.0196158886 0.1725806296 0.1251058839 0.2376661599 0.0049199172 0.0136540000 0.0003610000 0.0025440000 0.0000040000 0.0000030000 0.0021330000 46548709 96830484 509673472 3.8958499432 4.1104130745 3.8835852146 2950 1311867817.0547220707 0.1729092300 0.1251220884 0.2376661599 0.0049197460 0.0142700000 0.0003590000 0.0042100000 0.0000000000 0.0000040000 0.0011570000 46552437 96830484 509673472 3.8948953152 4.1096749306 3.8832263947 2951 1311867817.0868639946 0.1736127585 0.1251385203 0.2376661599 0.0049190563 0.0181440000 0.0004670000 0.0030930000 0.0000100000 0.0000110000 0.0015330000 46556109 96830484 509673472 3.8939681053 4.1101803780 3.8832843304 2952 1311867817.1189420223 0.1729664057 0.1251547222 0.2376661599 0.0049187044 0.0145290000 0.0003680000 0.0042270000 0.0000000000 0.0000040000 0.0011700000 46559837 96830484 509673472 3.8942492008 4.1095533371 3.8826389313 2953 1311867817.1549699306 0.1737083197 0.1251711643 0.2376661599 0.0049179601 0.0174220000 0.0004170000 0.0033650000 0.0000080000 0.0000080000 0.0022230000 46563621 96830484 509673472 3.8930015564 4.1095027924 3.8826532364 2954 1311867817.1863970757 0.1712958664 0.1251867786 0.2376661599 0.0049188785 0.0133040000 0.0003710000 0.0032300000 0.0000000000 0.0000040000 0.0011600000 46567237 96830484 509673472 3.8952784538 4.1090054512 3.8820180893 2955 1311867817.2202200890 0.1729516089 0.1252029427 0.2376661599 0.0049185944 0.0142520000 0.0003610000 0.0038790000 0.0000030000 0.0000030000 0.0014310000 46570965 96830484 509673472 3.8935992718 4.1077141762 3.8821961880 2956 1311867817.2567460537 0.1739911884 0.1252194475 0.2376661599 0.0049192629 0.0142320000 0.0003630000 0.0042190000 0.0000000000 0.0000030000 0.0011530000 46574749 96830484 509673472 3.8926417828 4.1062593460 3.8817932606 2957 1311867817.2865970135 0.1708732992 0.1252348868 0.2376661599 0.0049197270 0.0152680000 0.0003600000 0.0042130000 0.0000040000 0.0000040000 0.0021230000 46578365 96830484 509673472 3.8954789639 4.1060299873 3.8811967373 2958 1311867817.3192870617 0.1711921394 0.1252504234 0.2376661599 0.0049190709 0.0126420000 0.0003610000 0.0025360000 0.0000000000 0.0000040000 0.0011520000 46582093 96830484 509673472 3.8947257996 4.1048903465 3.8804945946 2959 1311867817.3578689098 0.1731172353 0.1252666000 0.2376661599 0.0049201741 0.0187900000 0.0004590000 0.0038040000 0.0000070000 0.0000080000 0.0015420000 46585933 96830484 509673472 3.8924288750 4.1037092209 3.8804769516 2960 1311867817.3868360519 0.1736112982 0.1252829327 0.2376661599 0.0049205291 0.0130420000 0.0003680000 0.0025460000 0.0000000000 0.0000040000 0.0011640000 46589493 96830484 509673472 3.8916146755 4.1025080681 3.8802976608 2961 1311867817.4206850529 0.1726489365 0.1252989293 0.2376661599 0.0049199411 0.0146990000 0.0003620000 0.0035530000 0.0000040000 0.0000040000 0.0021480000 46593221 96830484 509673472 3.8921675682 4.1011619568 3.8796260357 2962 1311867817.4551830292 0.1711556613 0.1253144110 0.2376661599 0.0049194186 0.0130010000 0.0003570000 0.0028750000 0.0000010000 0.0000040000 0.0011480000 46596949 96830484 509673472 3.8931994438 4.1006407738 3.8796358109 2963 1311867817.4888920784 0.1706840545 0.1253297231 0.2376661599 0.0049198097 0.0149860000 0.0003610000 0.0035460000 0.0000040000 0.0000040000 0.0014340000 46600733 96830484 509673472 3.8933293819 4.0978126526 3.8790154457 2964 1311867817.5194959641 0.1706099659 0.1253449998 0.2376661599 0.0049196062 0.0135820000 0.0004090000 0.0029730000 0.0000000000 0.0000030000 0.0011550000 46604293 96830484 509673472 3.8930320740 4.0981383324 3.8786730766 2965 1311867817.5576219559 0.1728383005 0.1253610178 0.2376661599 0.0049192207 0.0143680000 0.0003620000 0.0032070000 0.0000040000 0.0000040000 0.0021310000 46608189 96830484 509673472 3.8902516365 4.0963153839 3.8785104752 2966 1311867817.5864789486 0.1705333292 0.1253762478 0.2376661599 0.0049191851 0.0185260000 0.0004710000 0.0037920000 0.0000010000 0.0000090000 0.0012560000 46611749 96830484 509673472 3.8919882774 4.0952801704 3.8778741360 2967 1311867817.6205849648 0.1708459407 0.1253915730 0.2376661599 0.0049183610 0.0139190000 0.0003680000 0.0032120000 0.0000030000 0.0000040000 0.0014430000 46615477 96830484 509673472 3.8910324574 4.0947833061 3.8776915073 2968 1311867817.6566040516 0.1669428945 0.1254055727 0.2376661599 0.0049182586 0.0183760000 0.0004600000 0.0027470000 0.0000020000 0.0000100000 0.0013960000 46619261 96830484 509673472 3.8943305016 4.0935254097 3.8774178028 2969 1311867817.6880049706 0.1663542390 0.1254193648 0.2376661599 0.0049180299 0.0139030000 0.0003740000 0.0025460000 0.0000050000 0.0000040000 0.0021470000 46622933 96830484 509673472 3.8942732811 4.0923428535 3.8767912388 2970 1311867817.7194509506 0.1665357351 0.1254332087 0.2376661599 0.0049173269 0.0133030000 0.0003610000 0.0031950000 0.0000010000 0.0000040000 0.0011460000 46626661 96830484 509673472 3.8937098980 4.0913372040 3.8765778542 2971 1311867817.7552740574 0.1649516076 0.1254465101 0.2376661599 0.0049181573 0.0175920000 0.0004540000 0.0034000000 0.0000090000 0.0000080000 0.0015360000 46630333 96830484 509673472 3.8950269222 4.0893421173 3.8758673668 2972 1311867817.7872710228 0.1625435948 0.1254589923 0.2376661599 0.0049191189 0.0146030000 0.0003680000 0.0042270000 0.0000010000 0.0000040000 0.0011860000 46634061 96830484 509673472 3.8971691132 4.0876059532 3.8752129078 2973 1311867817.8201289177 0.1591421068 0.1254703220 0.2376661599 0.0049221923 0.0140550000 0.0003640000 0.0028780000 0.0000040000 0.0000040000 0.0021110000 46637789 96830484 509673472 3.9002120495 4.0874314308 3.8747520447 2974 1311867817.8596370220 0.1590914279 0.1254816270 0.2376661599 0.0049240028 0.0126230000 0.0003640000 0.0025340000 0.0000010000 0.0000030000 0.0011470000 46641685 96830484 509673472 3.8998637199 4.0857706070 3.8745868206 2975 1311867817.8866479397 0.1587638408 0.1254928143 0.2376661599 0.0049239378 0.0128770000 0.0003640000 0.0025350000 0.0000030000 0.0000030000 0.0014170000 46645189 96830484 509673472 3.9001588821 4.0838370323 3.8747251034 2976 1311867817.9203889370 0.1550885290 0.1255027591 0.2376661599 0.0049256873 0.0123430000 0.0003640000 0.0022020000 0.0000000000 0.0000040000 0.0011440000 46648917 96830484 509673472 3.9034814835 4.0831546783 3.8743515015 2977 1311867817.9569509029 0.1504919976 0.1255111532 0.2376661599 0.0049259742 0.0184380000 0.0004600000 0.0031080000 0.0000080000 0.0000070000 0.0022880000 46652701 96830484 509673472 3.9076306820 4.0829381943 3.8737442493 2978 1311867817.9865961075 0.1482580304 0.1255187915 0.2376661599 0.0049269054 0.0190320000 0.0004610000 0.0045280000 0.0000010000 0.0000070000 0.0012660000 46656317 96830484 509673472 3.9097743034 4.0809187889 3.8732850552 2979 1311867818.0255188942 0.1484912187 0.1255265029 0.2376661599 0.0049271956 0.0180790000 0.0004780000 0.0031000000 0.0000100000 0.0000100000 0.0015310000 46660157 96830484 509673472 3.9094076157 4.0807762146 3.8732831478 2980 1311867818.0579230785 0.1492626816 0.1255344681 0.2376661599 0.0049273243 0.0130160000 0.0003830000 0.0025570000 0.0000010000 0.0000040000 0.0011510000 46663885 96830484 509673472 3.9088048935 4.0798754692 3.8733918667 2981 1311867818.0892961025 0.1446762383 0.1255408894 0.2376661599 0.0049283117 0.0188800000 0.0004650000 0.0044640000 0.0000080000 0.0000080000 0.0022550000 46667445 96830484 509673472 3.9130876064 4.0790710449 3.8723442554 2982 1311867818.1228859425 0.1463490427 0.1255478673 0.2376661599 0.0049308530 0.0140590000 0.0003760000 0.0035760000 0.0000000000 0.0000040000 0.0011420000 46671229 96830484 509673472 3.9112391472 4.0783786774 3.8722352982 2983 1311867818.1594460011 0.1439291537 0.1255540293 0.2376661599 0.0049303130 0.0147670000 0.0003700000 0.0042440000 0.0000040000 0.0000040000 0.0014200000 46674957 96830484 509673472 3.9137468338 4.0772399902 3.8718154430 2984 1311867818.1912620068 0.1428894103 0.1255598387 0.2376661599 0.0049426582 0.0141790000 0.0003770000 0.0039170000 0.0000000000 0.0000030000 0.0011370000 46678685 96830484 509673472 3.9146811962 4.0766339302 3.8714282513 2985 1311867818.2233390808 0.1410406083 0.1255650249 0.2376661599 0.0049492363 0.0189310000 0.0004770000 0.0031140000 0.0000110000 0.0000100000 0.0022740000 46682413 96830484 509673472 3.9162878990 4.0765771866 3.8707211018 2986 1311867818.2556240559 0.1422230452 0.1255706036 0.2376661599 0.0049504200 0.0186370000 0.0004740000 0.0038300000 0.0000010000 0.0000230000 0.0012540000 46686029 96830484 509673472 3.9151873589 4.0749068260 3.8704407215 2987 1311867818.2891340256 0.1404014975 0.1255755688 0.2376661599 0.0049505493 0.0149630000 0.0003820000 0.0042680000 0.0000050000 0.0000040000 0.0014120000 46689757 96830484 509673472 3.9168493748 4.0738167763 3.8698375225 2988 1311867818.3256890774 0.1398697197 0.1255803526 0.2376661599 0.0049499700 0.0130160000 0.0003830000 0.0025550000 0.0000000000 0.0000030000 0.0011520000 46693541 96830484 509673472 3.9173834324 4.0736351013 3.8695759773 2989 1311867818.3582971096 0.1400141567 0.1255851816 0.2376661599 0.0049491928 0.0137240000 0.0003810000 0.0025500000 0.0000030000 0.0000030000 0.0021240000 46697269 96830484 509673472 3.9169981480 4.0730004311 3.8689889908 2990 1311867818.3892099857 0.1402188838 0.1255900758 0.2376661599 0.0049490608 0.0182940000 0.0004700000 0.0044880000 0.0000010000 0.0000070000 0.0012600000 46700941 96830484 509673472 3.9169991016 4.0722756386 3.8688127995 2991 1311867818.4233601093 0.1391706467 0.1255946163 0.2376661599 0.0049499120 0.0131510000 0.0003810000 0.0025800000 0.0000040000 0.0000030000 0.0014170000 46704669 96830484 509673472 3.9177732468 4.0714941025 3.8683288097 2992 1311867818.4555370808 0.1367211491 0.1255983351 0.2376661599 0.0049497596 0.0142560000 0.0003890000 0.0039280000 0.0000010000 0.0000040000 0.0011400000 46708285 96830484 509673472 3.9200057983 4.0706133842 3.8677508831 2993 1311867818.4896349907 0.1363690048 0.1256019337 0.2376661599 0.0049496347 0.0144050000 0.0003750000 0.0032290000 0.0000040000 0.0000040000 0.0021210000 46712069 96830484 509673472 3.9200470448 4.0694489479 3.8673670292 2994 1311867818.5246019363 0.1356793493 0.1256052995 0.2376661599 0.0049504089 0.0145050000 0.0003810000 0.0042550000 0.0000000000 0.0000040000 0.0011400000 46715797 96830484 509673472 3.9204628468 4.0691418648 3.8673746586 2995 1311867818.5566370487 0.1366914958 0.1256090011 0.2376661599 0.0049504705 0.0181230000 0.0004770000 0.0031350000 0.0000080000 0.0000070000 0.0015360000 46719469 96830484 509673472 3.9184629917 4.0684304237 3.8669569492 2996 1311867818.5892300606 0.1330968589 0.1256115004 0.2376661599 0.0049539743 0.0146520000 0.0003890000 0.0042980000 0.0000000000 0.0000040000 0.0011460000 46723141 96830484 509673472 3.9214715958 4.0677080154 3.8664815426 2997 1311867818.6233239174 0.1332161874 0.1256140378 0.2376661599 0.0049536652 0.0143590000 0.0003820000 0.0032510000 0.0000030000 0.0000030000 0.0021280000 46726869 96830484 509673472 3.9206156731 4.0671596527 3.8667566776 2998 1311867818.6555750370 0.1304874122 0.1256156634 0.2376661599 0.0049563930 0.0138520000 0.0003810000 0.0036250000 0.0000000000 0.0000030000 0.0011400000 46730485 96830484 509673472 3.9222013950 4.0657329559 3.8665149212 2999 1311867818.6877410412 0.1306728274 0.1256173497 0.2376661599 0.0049557726 0.0185510000 0.0004720000 0.0031460000 0.0000100000 0.0000090000 0.0015450000 46734213 96830484 509673472 3.9212296009 4.0655617714 3.8664789200 3000 1311867818.7238090038 0.1288382560 0.1256184233 0.2376661599 0.0049552593 0.0138790000 0.0003920000 0.0029450000 0.0000010000 0.0000040000 0.0011380000 46737941 96830484 509673472 3.9222760201 4.0643224716 3.8664753437 3001 1311867818.7561779022 0.1256747842 0.1256184421 0.2376661599 0.0049548808 0.0159870000 0.0004320000 0.0044340000 0.0000040000 0.0000030000 0.0021240000 46741669 96830484 509673472 3.9251368046 4.0633749962 3.8662042618 3002 1311867818.7870090008 0.1265828758 0.1256187633 0.2376661599 0.0049550878 0.0132280000 0.0003830000 0.0029230000 0.0000000000 0.0000040000 0.0011410000 46745285 96830484 509673472 3.9234459400 4.0629558563 3.8662872314 3003 1311867818.8250839710 0.1246232316 0.1256184318 0.2376661599 0.0049550850 0.0141880000 0.0003830000 0.0039440000 0.0000040000 0.0000040000 0.0014010000 46749069 96830484 509673472 3.9245986938 4.0625729561 3.8662784100 3004 1311867818.8546340466 0.1247528642 0.1256181437 0.2376661599 0.0049548123 0.0134590000 0.0003830000 0.0032720000 0.0000000000 0.0000040000 0.0011350000 46752685 96830484 509673472 3.9238097668 4.0615777969 3.8662607670 3005 1311867818.8872439861 0.1227262318 0.1256171813 0.2376661599 0.0049652833 0.0136410000 0.0003860000 0.0025870000 0.0000030000 0.0000030000 0.0021100000 46756469 96830484 509673472 3.9250214100 4.0601911545 3.8659620285 3006 1311867818.9249579906 0.1232373565 0.1256163896 0.2376661599 0.0049654784 0.0143290000 0.0003850000 0.0043040000 0.0000010000 0.0000040000 0.0011330000 46760309 96830484 509673472 3.9237041473 4.0585265160 3.8660204411 3007 1311867818.9544699192 0.1194038391 0.1256143236 0.2376661599 0.0049706620 0.0146830000 0.0003780000 0.0043080000 0.0000040000 0.0000040000 0.0014190000 46763869 96830484 509673472 3.9270946980 4.0576529503 3.8654532433 3008 1311867818.9864790440 0.1230703518 0.1256134779 0.2376661599 0.0049712191 0.0144350000 0.0003820000 0.0043130000 0.0000000000 0.0000040000 0.0011370000 46767541 96830484 509673472 3.9228360653 4.0559029579 3.8660540581 3009 1311867819.0252439976 0.1222328618 0.1256123544 0.2376661599 0.0049718236 0.0140560000 0.0003780000 0.0029360000 0.0000040000 0.0000030000 0.0021160000 46771437 96830484 509673472 3.9230151176 4.0541992188 3.8657050133 3010 1311867819.0550930500 0.1223435327 0.1256112684 0.2376661599 0.0049843860 0.0134030000 0.0003840000 0.0032940000 0.0000000000 0.0000030000 0.0011310000 46775053 96830484 509673472 3.9221642017 4.0518016815 3.8656020164 3011 1311867819.0875039101 0.1228640527 0.1256103560 0.2376661599 0.0049849344 0.0181560000 0.0004870000 0.0024520000 0.0000090000 0.0000090000 0.0016540000 46778725 96830484 509673472 3.9212813377 4.0505876541 3.8658845425 3012 1311867819.1251850128 0.1238377318 0.1256097675 0.2376661599 0.0049944769 0.0148610000 0.0004020000 0.0043610000 0.0000000000 0.0000040000 0.0011370000 46782509 96830484 509673472 3.9194948673 4.0498828888 3.8657033443 3013 1311867819.1578950882 0.1254562885 0.1256097165 0.2376661599 0.0049942732 0.0192850000 0.0004870000 0.0031660000 0.0000100000 0.0000100000 0.0023100000 46786237 96830484 509673472 3.9169976711 4.0475373268 3.8656895161 3014 1311867819.1891999245 0.1242313832 0.1256092592 0.2376661599 0.0049958621 0.0146970000 0.0003970000 0.0043340000 0.0000000000 0.0000040000 0.0011310000 46789909 96830484 509673472 3.9182970524 4.0452504158 3.8658695221 3015 1311867819.2251279354 0.1217290163 0.1256079722 0.2376661599 0.0049987083 0.0192590000 0.0004770000 0.0045880000 0.0000080000 0.0000070000 0.0015530000 46793637 96830484 509673472 3.9203605652 4.0445189476 3.8657276630 3016 1311867819.2586779594 0.1167015582 0.1256050192 0.2376661599 0.0050018110 0.0145740000 0.0003890000 0.0043140000 0.0000000000 0.0000030000 0.0011270000 46797365 96830484 509673472 3.9254741669 4.0431895256 3.8649332523 3017 1311867819.2937591076 0.1183628067 0.1256026187 0.2376661599 0.0050009861 0.0147490000 0.0003840000 0.0036030000 0.0000040000 0.0000040000 0.0021160000 46801093 96830484 509673472 3.9233345985 4.0420703888 3.8648648262 3018 1311867819.3250200748 0.1214726269 0.1256012503 0.2376661599 0.0050002848 0.0128060000 0.0003870000 0.0025780000 0.0000010000 0.0000030000 0.0011290000 46804765 96830484 509673472 3.9200842381 4.0409970284 3.8652763367 3019 1311867819.3568780422 0.1224538237 0.1256002077 0.2376661599 0.0049998167 0.0133150000 0.0003840000 0.0025980000 0.0000040000 0.0000030000 0.0014050000 46808437 96830484 509673472 3.9188938141 4.0411624908 3.8652539253 3020 1311867819.3930859566 0.1216704622 0.1255989065 0.2376661599 0.0050042462 0.0153930000 0.0004340000 0.0043140000 0.0000010000 0.0000040000 0.0013160000 46812221 96830484 509673472 3.9193346500 4.0401711464 3.8649773598 3021 1311867819.4237139225 0.1228930801 0.1255980108 0.2376661599 0.0050040110 0.0196980000 0.0004820000 0.0031490000 0.0000090000 0.0000100000 0.0024500000 46815893 96830484 509673472 3.9177238941 4.0410666466 3.8654808998 3022 1311867819.4571580887 0.1237856820 0.1255974111 0.2376661599 0.0050033842 0.0143100000 0.0003900000 0.0039820000 0.0000010000 0.0000040000 0.0011310000 46819565 96830484 509673472 3.9166507721 4.0400328636 3.8656272888 3023 1311867819.4921460152 0.1233027875 0.1255966520 0.2376661599 0.0050037954 0.0148260000 0.0003810000 0.0043100000 0.0000030000 0.0000030000 0.0014050000 46823293 96830484 509673472 3.9176042080 4.0382218361 3.8658945560 3024 1311867819.5226500034 0.1229199246 0.1255957669 0.2376661599 0.0050039058 0.0143700000 0.0003820000 0.0043220000 0.0000000000 0.0000030000 0.0011270000 46826965 96830484 509673472 3.9178190231 4.0392899513 3.8661127090 3025 1311867819.5550689697 0.1230440065 0.1255949233 0.2376661599 0.0050032569 0.0145940000 0.0003910000 0.0032750000 0.0000040000 0.0000030000 0.0021090000 46830581 96830484 509673472 3.9172620773 4.0393385887 3.8657612801 3026 1311867819.5923891068 0.1220876500 0.1255937643 0.2376661599 0.0050041619 0.0145240000 0.0003860000 0.0043090000 0.0000000000 0.0000040000 0.0011330000 46834477 96830484 509673472 3.9184994698 4.0373649597 3.8659789562 3027 1311867819.6253750324 0.1202146560 0.1255919872 0.2376661599 0.0050047673 0.0182920000 0.0004820000 0.0028420000 0.0000110000 0.0000090000 0.0015280000 46838149 96830484 509673472 3.9204516411 4.0383634567 3.8664422035 3028 1311867819.6557610035 0.1262693554 0.1255922109 0.2376661599 0.0050047183 0.0142750000 0.0003970000 0.0036520000 0.0000010000 0.0000040000 0.0011360000 46841765 96830484 509673472 3.9141809940 4.0381870270 3.8670969009 3029 1311867819.6919729710 0.1200915426 0.1255903949 0.2376661599 0.0050069337 0.0202010000 0.0004790000 0.0045910000 0.0000080000 0.0000080000 0.0022840000 46845549 96830484 509673472 3.9201200008 4.0370249748 3.8656413555 3030 1311867819.7227339745 0.1219253168 0.1255891853 0.2376661599 0.0050063028 0.0146890000 0.0003930000 0.0043200000 0.0000000000 0.0000030000 0.0011270000 46849221 96830484 509673472 3.9185509682 4.0355343819 3.8660378456 3031 1311867819.7567169666 0.1224851385 0.1255881612 0.2376661599 0.0050071682 0.0191610000 0.0004960000 0.0045820000 0.0000070000 0.0000090000 0.0015330000 46852949 96830484 509673472 3.9180386066 4.0365009308 3.8665699959 3032 1311867819.7913908958 0.1238102987 0.1255875749 0.2376661599 0.0050069272 0.0129580000 0.0003910000 0.0026010000 0.0000010000 0.0000040000 0.0011380000 46856677 96830484 509673472 3.9166233540 4.0356574059 3.8664062023 3033 1311867819.8285260201 0.1228143945 0.1255866605 0.2376661599 0.0050065192 0.0134730000 0.0003830000 0.0022350000 0.0000040000 0.0000040000 0.0021100000 46860461 96830484 509673472 3.9176998138 4.0339369774 3.8661482334 3034 1311867819.8552229404 0.1235893294 0.1255860022 0.2376661599 0.0050095169 0.0168800000 0.0004440000 0.0034270000 0.0000010000 0.0000080000 0.0011980000 46863965 96830484 509673472 3.9167091846 4.0353608131 3.8663539886 3035 1311867819.8941109180 0.1210549697 0.1255845093 0.2376661599 0.0050096840 0.0133170000 0.0003890000 0.0025960000 0.0000040000 0.0000030000 0.0014050000 46867917 96830484 509673472 3.9193246365 4.0355362892 3.8663027287 3036 1311867819.9237871170 0.1215539351 0.1255831817 0.2376661599 0.0050098920 0.0144170000 0.0003840000 0.0041950000 0.0000000000 0.0000040000 0.0011210000 46871477 96830484 509673472 3.9189915657 4.0331587791 3.8660604954 3037 1311867819.9576539993 0.1217287332 0.1255819125 0.2376661599 0.0050090902 0.0154830000 0.0003960000 0.0042920000 0.0000030000 0.0000030000 0.0021240000 46875205 96830484 509673472 3.9188966751 4.0337677002 3.8667705059 3038 1311867819.9939079285 0.1220460683 0.1255807487 0.2376661599 0.0050084600 0.0146150000 0.0003880000 0.0043140000 0.0000000000 0.0000030000 0.0011200000 46879045 96830484 509673472 3.9183773994 4.0345716476 3.8665969372 3039 1311867820.0229809284 0.1219788119 0.1255795634 0.2376661599 0.0050082603 0.0129830000 0.0003830000 0.0024890000 0.0000040000 0.0000040000 0.0013960000 46882605 96830484 509673472 3.9185140133 4.0335850716 3.8665351868 3040 1311867820.0577530861 0.1240316778 0.1255790542 0.2376661599 0.0050076806 0.0189840000 0.0004830000 0.0045720000 0.0000010000 0.0000070000 0.0012600000 46886333 96830484 509673472 3.9167201519 4.0330371857 3.8672845364 3041 1311867820.0944790840 0.1203490049 0.1255773344 0.2376661599 0.0050075448 0.0156780000 0.0003930000 0.0043230000 0.0000040000 0.0000040000 0.0021150000 46890117 96830484 509673472 3.9205324650 4.0338835716 3.8673279285 3042 1311867820.1251690388 0.1227858737 0.1255764168 0.2376661599 0.0050073458 0.0143230000 0.0003890000 0.0042020000 0.0000000000 0.0000030000 0.0011220000 46893733 96830484 509673472 3.9182348251 4.0321087837 3.8676309586 3043 1311867820.1551020145 0.1202671602 0.1255746720 0.2376661599 0.0050067764 0.0145720000 0.0003850000 0.0043080000 0.0000030000 0.0000030000 0.0013890000 46897405 96830484 509673472 3.9208898544 4.0322036743 3.8679032326 3044 1311867820.1938860416 0.1202504635 0.1255729229 0.2376661599 0.0050061123 0.0147230000 0.0003840000 0.0043130000 0.0000010000 0.0000040000 0.0011250000 46901245 96830484 509673472 3.9208796024 4.0330038071 3.8680777550 3045 1311867820.2262499332 0.1196383163 0.1255709740 0.2376661599 0.0050059106 0.0185510000 0.0004750000 0.0034970000 0.0000080000 0.0000080000 0.0022560000 46904917 96830484 509673472 3.9218115807 4.0318174362 3.8683619499 3046 1311867820.2557370663 0.1214111745 0.1255696083 0.2376661599 0.0050054408 0.0142270000 0.0003910000 0.0035260000 0.0000000000 0.0000040000 0.0011230000 46908477 96830484 509673472 3.9200632572 4.0306754112 3.8686985970 3047 1311867820.2941820621 0.1234063357 0.1255688983 0.2376661599 0.0050052522 0.0152110000 0.0003810000 0.0043160000 0.0000030000 0.0000030000 0.0014070000 46912429 96830484 509673472 3.9180035591 4.0314555168 3.8693778515 3048 1311867820.3227488995 0.1194380447 0.1255668869 0.2376661599 0.0050062367 0.0129590000 0.0003810000 0.0025990000 0.0000000000 0.0000040000 0.0011190000 46915989 96830484 509673472 3.9221439362 4.0296244621 3.8686375618 3049 1311867820.3565030098 0.1186651066 0.1255646233 0.2376661599 0.0050054501 0.0155490000 0.0003830000 0.0043200000 0.0000030000 0.0000030000 0.0021120000 46919661 96830484 509673472 3.9230210781 4.0291194916 3.8687071800 3050 1311867820.3936169147 0.1190100461 0.1255624742 0.2376661599 0.0050046939 0.0129800000 0.0003880000 0.0025930000 0.0000000000 0.0000030000 0.0011250000 46923501 96830484 509673472 3.9228904247 4.0288996696 3.8694405556 3051 1311867820.4230690002 0.1200437471 0.1255606654 0.2376661599 0.0050042334 0.0133380000 0.0003890000 0.0025990000 0.0000040000 0.0000030000 0.0014030000 46927061 96830484 509673472 3.9218051434 4.0280370712 3.8693592548 3052 1311867820.4605870247 0.1201972216 0.1255589081 0.2376661599 0.0050034475 0.0147440000 0.0003840000 0.0043180000 0.0000000000 0.0000040000 0.0011340000 46930845 96830484 509673472 3.9216020107 4.0270895958 3.8697893620 3053 1311867820.4940779209 0.1177575141 0.1255563527 0.2376661599 0.0050033598 0.0148150000 0.0003840000 0.0036360000 0.0000040000 0.0000030000 0.0021010000 46934573 96830484 509673472 3.9238538742 4.0271654129 3.8694379330 3054 1311867820.5266289711 0.1188045964 0.1255541419 0.2376661599 0.0050026668 0.0146610000 0.0003780000 0.0042990000 0.0000010000 0.0000040000 0.0011250000 46938301 96830484 509673472 3.9227039814 4.0261135101 3.8699672222 3055 1311867820.5596110821 0.1180262342 0.1255516778 0.2376661599 0.0050023663 0.0135040000 0.0003830000 0.0029370000 0.0000040000 0.0000030000 0.0014060000 46941973 96830484 509673472 3.9233844280 4.0261602402 3.8703148365 3056 1311867820.5906820297 0.1186564043 0.1255494215 0.2376661599 0.0050015923 0.0144150000 0.0003780000 0.0039810000 0.0000010000 0.0000040000 0.0011320000 46945589 96830484 509673472 3.9224092960 4.0265121460 3.8705022335 3057 1311867820.6261150837 0.1179587692 0.1255469385 0.2376661599 0.0050012142 0.0167830000 0.0003860000 0.0049180000 0.0000030000 0.0000040000 0.0021180000 46949373 96830484 509673472 3.9223737717 4.0255293846 3.8706841469 3058 1311867820.6602840424 0.1161039472 0.1255438505 0.2376661599 0.0050006312 0.0147540000 0.0004320000 0.0043180000 0.0000000000 0.0000030000 0.0011300000 46953045 96830484 509673472 3.9240555763 4.0246357918 3.8708481789 3059 1311867820.6933140755 0.1166139692 0.1255409313 0.2376661599 0.0050000528 0.0140060000 0.0003880000 0.0033050000 0.0000030000 0.0000030000 0.0014260000 46956829 96830484 509673472 3.9232587814 4.0248384476 3.8714597225 3060 1311867820.7232019901 0.1200805977 0.1255391469 0.2376661599 0.0049995880 0.0149060000 0.0003890000 0.0043240000 0.0000010000 0.0000040000 0.0011290000 46960445 96830484 509673472 3.9195075035 4.0241990089 3.8718981743 3061 1311867820.7605569363 0.1182948947 0.1255367802 0.2376661599 0.0050002555 0.0186960000 0.0004830000 0.0028080000 0.0000080000 0.0000070000 0.0023060000 46964229 96830484 509673472 3.9211895466 4.0225133896 3.8718910217 3062 1311867820.7916440964 0.1171768308 0.1255340500 0.2376661599 0.0050000206 0.0136240000 0.0003930000 0.0029580000 0.0000000000 0.0000030000 0.0011290000 46967845 96830484 509673472 3.9219255447 4.0232157707 3.8720014095 3063 1311867820.8228490353 0.1172672734 0.1255313511 0.2376661599 0.0049994379 0.0341430000 0.0005810000 0.0048610000 0.0000160000 0.0000140000 0.0019130000 46971573 96830484 509673472 3.9215362072 4.0225000381 3.8721172810 3064 1311867820.8588171005 0.1174302027 0.1255287071 0.2376661599 0.0049994270 0.0162780000 0.0004170000 0.0044090000 0.0000010000 0.0000060000 0.0011590000 46975357 96830484 509673472 3.9210228920 4.0212669373 3.8721480370 3065 1311867820.8911399841 0.1213269159 0.1255273362 0.2376661599 0.0049989434 0.0143890000 0.0003950000 0.0025980000 0.0000040000 0.0000040000 0.0021500000 46978973 96830484 509673472 3.9167432785 4.0201077461 3.8727295399 3066 1311867820.9231750965 0.1224170402 0.1255263218 0.2376661599 0.0049988191 0.0147360000 0.0003790000 0.0039600000 0.0000000000 0.0000040000 0.0011330000 46982645 96830484 509673472 3.9152698517 4.0213785172 3.8733186722 3067 1311867820.9593999386 0.1226749197 0.1255253921 0.2376661599 0.0049980208 0.0148730000 0.0003880000 0.0043060000 0.0000040000 0.0000030000 0.0013970000 46986485 96830484 509673472 3.9145631790 4.0203118324 3.8735127449 3068 1311867820.9930229187 0.1204497069 0.1255237377 0.2376661599 0.0049974655 0.0285850000 0.0005630000 0.0048590000 0.0000020000 0.0000170000 0.0016440000 46990213 96830484 509673472 3.9166665077 4.0203013420 3.8738656044 3069 1311867821.0258319378 0.1229318157 0.1255228931 0.2376661599 0.0049992859 0.0164420000 0.0004140000 0.0043850000 0.0000050000 0.0000050000 0.0021500000 46993773 96830484 509673472 3.9137699604 4.0212745667 3.8744006157 3070 1311867821.0608170033 0.1236779466 0.1255222922 0.2376661599 0.0049993138 0.0158830000 0.0004340000 0.0043290000 0.0000010000 0.0000040000 0.0011380000 46997557 96830484 509673472 3.9126033783 4.0197744370 3.8743910789 3071 1311867821.0909409523 0.1215986386 0.1255210145 0.2376661599 0.0049990354 0.0153200000 0.0004350000 0.0043310000 0.0000040000 0.0000040000 0.0014260000 47001173 96830484 509673472 3.9143362045 4.0204229355 3.8747253418 3072 1311867821.1260650158 0.1243832260 0.1255206442 0.2376661599 0.0050003648 0.0148950000 0.0003890000 0.0043420000 0.0000010000 0.0000040000 0.0011280000 47004901 96830484 509673472 3.9109473228 4.0216193199 3.8755009174 3073 1311867821.1620008945 0.1219378263 0.1255194783 0.2376661599 0.0050027713 0.0151910000 0.0003920000 0.0036350000 0.0000040000 0.0000030000 0.0021150000 47008629 96830484 509673472 3.9130132198 4.0191850662 3.8750152588 3074 1311867821.1925799847 0.1204019263 0.1255178135 0.2376661599 0.0050032960 0.0146540000 0.0003850000 0.0043440000 0.0000010000 0.0000040000 0.0011250000 47012301 96830484 509673472 3.9144241810 4.0170011520 3.8751356602 3075 1311867821.2257659435 0.1225296482 0.1255168417 0.2376661599 0.0050026586 0.0148930000 0.0003830000 0.0043540000 0.0000030000 0.0000040000 0.0014180000 47015973 96830484 509673472 3.9115762711 4.0178532600 3.8755528927 3076 1311867821.2620539665 0.1225028187 0.1255158619 0.2376661599 0.0050020667 0.0133840000 0.0003870000 0.0029530000 0.0000010000 0.0000040000 0.0011260000 47019757 96830484 509673472 3.9112596512 4.0171990395 3.8758583069 3077 1311867821.2933909893 0.1230039597 0.1255150455 0.2376661599 0.0050014287 0.0187440000 0.0004760000 0.0035100000 0.0000070000 0.0000080000 0.0022950000 47023429 96830484 509673472 3.9106202126 4.0149402618 3.8760519028 3078 1311867821.3235690594 0.1245898902 0.1255147449 0.2376661599 0.0050013459 0.0186730000 0.0004820000 0.0035610000 0.0000010000 0.0000080000 0.0012680000 47027101 96830484 509673472 3.9087617397 4.0157260895 3.8772726059 3079 1311867821.3590209484 0.1245721877 0.1255144388 0.2376661599 0.0050008955 0.0139830000 0.0003940000 0.0029800000 0.0000040000 0.0000040000 0.0014170000 47030885 96830484 509673472 3.9083881378 4.0147275925 3.8774104118 3080 1311867821.3907248974 0.1245714501 0.1255141326 0.2376661599 0.0050010699 0.0148640000 0.0003920000 0.0043400000 0.0000010000 0.0000040000 0.0011320000 47034445 96830484 509673472 3.9084117413 4.0112905502 3.8771293163 3081 1311867821.4246149063 0.1272308826 0.1255146899 0.2376661599 0.0050012446 0.0158520000 0.0003910000 0.0043350000 0.0000040000 0.0000040000 0.0021270000 47038173 96830484 509673472 3.9051661491 4.0128116608 3.8777668476 3082 1311867821.4626159668 0.1276028901 0.1255153674 0.2376661599 0.0050005717 0.0186710000 0.0004830000 0.0045750000 0.0000010000 0.0000080000 0.0012660000 47042069 96830484 509673472 3.9043467045 4.0128669739 3.8777737617 3083 1311867821.4939169884 0.1271022558 0.1255158821 0.2376661599 0.0050000836 0.0152920000 0.0003880000 0.0043550000 0.0000040000 0.0000030000 0.0014190000 47045685 96830484 509673472 3.9046270847 4.0112433434 3.8773093224 3084 1311867821.5273780823 0.1288834363 0.1255169741 0.2376661599 0.0049999591 0.0146350000 0.0003840000 0.0043250000 0.0000000000 0.0000040000 0.0011370000 47049413 96830484 509673472 3.9023578167 4.0115013123 3.8779008389 3085 1311867821.5590820312 0.1301220059 0.1255184668 0.2376661599 0.0049996545 0.0139900000 0.0003780000 0.0025960000 0.0000040000 0.0000040000 0.0021380000 47053085 96830484 509673472 3.9002914429 4.0127630234 3.8781771660 3086 1311867821.5928409100 0.1286060810 0.1255194673 0.2376661599 0.0050001767 0.0131040000 0.0003840000 0.0026000000 0.0000010000 0.0000040000 0.0011430000 47056701 96830484 509673472 3.9012920856 4.0112447739 3.8780109882 3087 1311867821.6260631084 0.1271002740 0.1255199794 0.2376661599 0.0049996530 0.0150430000 0.0003830000 0.0043160000 0.0000030000 0.0000030000 0.0014230000 47060373 96830484 509673472 3.9023859501 4.0116553307 3.8787384033 3088 1311867821.6634659767 0.1294659972 0.1255212572 0.2376661599 0.0049991675 0.0150480000 0.0003930000 0.0043380000 0.0000010000 0.0000040000 0.0011380000 47064381 96830484 509673472 3.8990015984 4.0129446983 3.8790102005 3089 1311867821.6953229904 0.1295220256 0.1255225524 0.2376661599 0.0049991699 0.0156780000 0.0003820000 0.0043100000 0.0000040000 0.0000030000 0.0021330000 47067997 96830484 509673472 3.8983814716 4.0111546516 3.8793318272 3090 1311867821.7313649654 0.1288792342 0.1255236387 0.2376661599 0.0049988180 0.0252170000 0.0004910000 0.0038920000 0.0000010000 0.0000110000 0.0013900000 47071781 96830484 509673472 3.8983342648 4.0104603767 3.8797671795 3091 1311867821.7634460926 0.1284156293 0.1255245743 0.2376661599 0.0049982077 0.0159100000 0.0004090000 0.0043940000 0.0000050000 0.0000050000 0.0014370000 47075509 96830484 509673472 3.8982088566 4.0109548569 3.8802194595 3092 1311867821.7956120968 0.1298461854 0.1255259720 0.2376661599 0.0049975423 0.0133450000 0.0003890000 0.0026110000 0.0000010000 0.0000040000 0.0011460000 47079069 96830484 509673472 3.8961048126 4.0095744133 3.8806097507 3093 1311867821.8313920498 0.1293844283 0.1255272195 0.2376661599 0.0049969618 0.0194950000 0.0004960000 0.0045520000 0.0000070000 0.0000080000 0.0022810000 47082853 96830484 509673472 3.8958899975 4.0087790489 3.8807213306 3094 1311867821.8633379936 0.1312437057 0.1255290671 0.2376661599 0.0049972099 0.0148910000 0.0004390000 0.0043350000 0.0000000000 0.0000050000 0.0011440000 47086469 96830484 509673472 3.8942134380 4.0095462799 3.8812942505 3095 1311867821.8956110477 0.1307792068 0.1255307634 0.2376661599 0.0049968324 0.0151330000 0.0003850000 0.0043280000 0.0000040000 0.0000030000 0.0014230000 47090197 96830484 509673472 3.8941969872 4.0086398125 3.8809363842 3096 1311867821.9314410686 0.1312365830 0.1255326064 0.2376661599 0.0049963899 0.0147480000 0.0003850000 0.0042990000 0.0000000000 0.0000030000 0.0011370000 47093981 96830484 509673472 3.8933038712 4.0069065094 3.8806173801 3097 1311867821.9633870125 0.1316398382 0.1255345784 0.2376661599 0.0049957769 0.0143210000 0.0003810000 0.0025800000 0.0000050000 0.0000030000 0.0021370000 47097709 96830484 509673472 3.8926634789 4.0068149567 3.8807287216 3098 1311867821.9954171181 0.1315140873 0.1255365085 0.2376661599 0.0049952885 0.0150780000 0.0003850000 0.0043160000 0.0000000000 0.0000030000 0.0011400000 47101381 96830484 509673472 3.8923523426 4.0057868958 3.8805871010 3099 1311867822.0314009190 0.1305461526 0.1255381250 0.2376661599 0.0049955236 0.0146350000 0.0003860000 0.0036210000 0.0000040000 0.0000040000 0.0014300000 47105109 96830484 509673472 3.8927803040 4.0036568642 3.8802990913 3100 1311867822.0633769035 0.1333665401 0.1255406503 0.2376661599 0.0049959892 0.0149790000 0.0003790000 0.0042870000 0.0000000000 0.0000040000 0.0011490000 47108837 96830484 509673472 3.8894059658 4.0051970482 3.8809530735 3101 1311867822.0962209702 0.1337944716 0.1255433120 0.2376661599 0.0049953199 0.0144230000 0.0003770000 0.0029180000 0.0000030000 0.0000030000 0.0021420000 47112453 96830484 509673472 3.8885829449 4.0052804947 3.8812358379 3102 1311867822.1315379143 0.1343876123 0.1255461631 0.2376661599 0.0049955561 0.0175050000 0.0004920000 0.0027880000 0.0000010000 0.0000080000 0.0012820000 47116237 96830484 509673472 3.8876774311 4.0056581497 3.8812599182 3103 1311867822.1634409428 0.1359729171 0.1255495234 0.2376661599 0.0049950482 0.0146520000 0.0003720000 0.0036350000 0.0000040000 0.0000030000 0.0014320000 47119965 96830484 509673472 3.8859200478 4.0060710907 3.8820610046 3104 1311867822.1960899830 0.1370906234 0.1255532415 0.2376661599 0.0049944880 0.0148770000 0.0003850000 0.0043040000 0.0000010000 0.0000040000 0.0011500000 47123581 96830484 509673472 3.8844568729 4.0065822601 3.8827610016 3105 1311867822.2317450047 0.1354279965 0.1255564218 0.2376661599 0.0049943540 0.0202670000 0.0004890000 0.0045430000 0.0000070000 0.0000070000 0.0023080000 47127365 96830484 509673472 3.8860373497 4.0048737526 3.8829801083 3106 1311867822.2634150982 0.1346107125 0.1255593369 0.2376661599 0.0049952442 0.0142880000 0.0004580000 0.0032810000 0.0000000000 0.0000040000 0.0011560000 47131093 96830484 509673472 3.8873395920 4.0043520927 3.8823146820 3107 1311867822.2954349518 0.1348506361 0.1255623273 0.2376661599 0.0049950077 0.0150670000 0.0003750000 0.0042980000 0.0000040000 0.0000040000 0.0014320000 47134709 96830484 509673472 3.8864419460 4.0040616989 3.8824603558 3108 1311867822.3315870762 0.1330398619 0.1255647332 0.2376661599 0.0049946361 0.0148670000 0.0003790000 0.0043130000 0.0000010000 0.0000040000 0.0011560000 47138493 96830484 509673472 3.8881483078 4.0032925606 3.8826770782 3109 1311867822.3635189533 0.1349400133 0.1255677487 0.2376661599 0.0049940328 0.0156170000 0.0003780000 0.0043210000 0.0000040000 0.0000030000 0.0021520000 47142221 96830484 509673472 3.8858933449 4.0026659966 3.8827981949 3110 1311867822.3960089684 0.1351271272 0.1255708225 0.2376661599 0.0049934455 0.0179160000 0.0004910000 0.0027890000 0.0000010000 0.0000090000 0.0012740000 47145837 96830484 509673472 3.8851492405 4.0031886101 3.8827300072 3111 1311867822.4314260483 0.1348626018 0.1255738092 0.2376661599 0.0049927829 0.0133940000 0.0003780000 0.0022640000 0.0000040000 0.0000050000 0.0014240000 47149621 96830484 509673472 3.8847784996 4.0021777153 3.8828904629 3112 1311867822.4634740353 0.1360265166 0.1255771681 0.2376661599 0.0049925206 0.0190260000 0.0004810000 0.0042420000 0.0000010000 0.0000070000 0.0012750000 47153293 96830484 509673472 3.8835296631 4.0009946823 3.8831689358 3113 1311867822.4957718849 0.1377567947 0.1255810806 0.2376661599 0.0049922174 0.0197260000 0.0004930000 0.0042100000 0.0000080000 0.0000080000 0.0023220000 47156909 96830484 509673472 3.8813204765 4.0009484291 3.8836953640 3114 1311867822.5315260887 0.1388185322 0.1255853315 0.2376661599 0.0049922896 0.0134420000 0.0003790000 0.0025810000 0.0000000000 0.0000040000 0.0011540000 47160749 96830484 509673472 3.8800442219 3.9991648197 3.8833827972 3115 1311867822.5634500980 0.1376707852 0.1255892113 0.2376661599 0.0049921870 0.0141440000 0.0003710000 0.0032700000 0.0000040000 0.0000030000 0.0014320000 47164421 96830484 509673472 3.8813755512 3.9974212646 3.8835353851 3116 1311867822.5955328941 0.1386828125 0.1255934134 0.2376661599 0.0049921552 0.0147230000 0.0003720000 0.0043150000 0.0000000000 0.0000040000 0.0011500000 47168093 96830484 509673472 3.8801567554 3.9948661327 3.8834764957 3117 1311867822.6315131187 0.1418044120 0.1255986142 0.2376661599 0.0049926358 0.0143890000 0.0003690000 0.0029150000 0.0000040000 0.0000030000 0.0021650000 47171877 96830484 509673472 3.8770804405 3.9940185547 3.8834252357 3118 1311867822.6634640694 0.1401871741 0.1256032930 0.2376661599 0.0049927763 0.0129980000 0.0003600000 0.0022270000 0.0000000000 0.0000030000 0.0011590000 47175549 96830484 509673472 3.8785531521 3.9926502705 3.8829715252 3119 1311867822.6954870224 0.1419391930 0.1256085306 0.2376661599 0.0049922168 0.0135180000 0.0003660000 0.0025700000 0.0000040000 0.0000030000 0.0014400000 47179221 96830484 509673472 3.8764431477 3.9922230244 3.8830616474 3120 1311867822.7317390442 0.1442914307 0.1256145187 0.2376661599 0.0049931283 0.0136470000 0.0003800000 0.0029000000 0.0000000000 0.0000030000 0.0011640000 47182949 96830484 509673472 3.8736314774 3.9928398132 3.8835146427 3121 1311867822.7634871006 0.1458954662 0.1256210169 0.2376661599 0.0049924577 0.0144630000 0.0003610000 0.0029070000 0.0000030000 0.0000030000 0.0021780000 47186621 96830484 509673472 3.8714191914 3.9942100048 3.8838024139 3122 1311867822.7954308987 0.1464196891 0.1256276789 0.2376661599 0.0049921665 0.0132920000 0.0003640000 0.0025480000 0.0000010000 0.0000040000 0.0011690000 47190293 96830484 509673472 3.8707327843 3.9920041561 3.8841233253 3123 1311867822.8314750195 0.1445108801 0.1256337253 0.2376661599 0.0049923962 0.0143810000 0.0003670000 0.0032520000 0.0000030000 0.0000030000 0.0014350000 47194077 96830484 509673472 3.8715918064 3.9929978848 3.8841633797 3124 1311867822.8634629250 0.1449034214 0.1256398936 0.2376661599 0.0049945517 0.0142940000 0.0003650000 0.0032540000 0.0000010000 0.0000040000 0.0011470000 47197749 96830484 509673472 3.8709013462 3.9951865673 3.8847234249 3125 1311867822.8955349922 0.1431933492 0.1256455107 0.2376661599 0.0049940045 0.0196200000 0.0005200000 0.0031550000 0.0000080000 0.0000080000 0.0023370000 47201309 96830484 509673472 3.8721272945 3.9945597649 3.8848822117 3126 1311867822.9318330288 0.1428063661 0.1256510004 0.2376661599 0.0049934287 0.0153100000 0.0003810000 0.0043190000 0.0000010000 0.0000040000 0.0011460000 47205149 96830484 509673472 3.8718583584 3.9946033955 3.8851664066 3127 1311867822.9635109901 0.1417022943 0.1256561336 0.2376661599 0.0049930824 0.0135830000 0.0003730000 0.0025940000 0.0000040000 0.0000040000 0.0014150000 47208821 96830484 509673472 3.8721303940 3.9958491325 3.8854153156 3128 1311867822.9979970455 0.1401824355 0.1256607775 0.2376661599 0.0049930465 0.0148120000 0.0003850000 0.0039670000 0.0000000000 0.0000030000 0.0011340000 47212605 96830484 509673472 3.8730893135 3.9956228733 3.8856692314 3129 1311867823.0344979763 0.1403780431 0.1256654810 0.2376661599 0.0049925189 0.0139470000 0.0003790000 0.0022420000 0.0000030000 0.0000030000 0.0021250000 47216277 96830484 509673472 3.8721535206 3.9952025414 3.8856842518 3130 1311867823.0634639263 0.1412186623 0.1256704501 0.2376661599 0.0049922784 0.0143280000 0.0003860000 0.0033030000 0.0000010000 0.0000040000 0.0011240000 47219837 96830484 509673472 3.8706309795 3.9953517914 3.8861176968 3131 1311867823.0971090794 0.1424659342 0.1256758144 0.2376661599 0.0049916080 0.0148300000 0.0003800000 0.0036380000 0.0000040000 0.0000030000 0.0014020000 47223565 96830484 509673472 3.8686573505 3.9957535267 3.8864881992 3132 1311867823.1313869953 0.1409976482 0.1256807064 0.2376661599 0.0049927796 0.0175490000 0.0004900000 0.0024340000 0.0000010000 0.0000090000 0.0012440000 47227293 96830484 509673472 3.8692970276 3.9941527843 3.8864288330 3133 1311867823.1635200977 0.1413868368 0.1256857195 0.2376661599 0.0049934104 0.0147580000 0.0003850000 0.0026110000 0.0000040000 0.0000040000 0.0021080000 47230965 96830484 509673472 3.8682041168 3.9935607910 3.8865137100 3134 1311867823.1954131126 0.1430959105 0.1256912748 0.2376661599 0.0049955011 0.0142470000 0.0003870000 0.0029530000 0.0000010000 0.0000040000 0.0011250000 47234637 96830484 509673472 3.8657712936 3.9944286346 3.8872933388 3135 1311867823.2316908836 0.1426234692 0.1256966758 0.2376661599 0.0049948992 0.0156260000 0.0003810000 0.0043290000 0.0000040000 0.0000030000 0.0013850000 47238477 96830484 509673472 3.8654797077 3.9936759472 3.8872249126 3136 1311867823.2635869980 0.1443347931 0.1257026191 0.2376661599 0.0049998105 0.0140550000 0.0003900000 0.0029490000 0.0000000000 0.0000040000 0.0011270000 47242149 96830484 509673472 3.8635783195 3.9932115078 3.8876132965 3137 1311867823.2955200672 0.1441913992 0.1257085129 0.2376661599 0.0049991096 0.0191480000 0.0004900000 0.0038680000 0.0000080000 0.0000070000 0.0022500000 47245765 96830484 509673472 3.8630654812 3.9951779842 3.8881590366 3138 1311867823.3330919743 0.1459112614 0.1257149509 0.2376661599 0.0049985082 0.0144270000 0.0003910000 0.0036490000 0.0000000000 0.0000030000 0.0011170000 47249605 96830484 509673472 3.8606760502 3.9951188564 3.8882789612 3139 1311867823.3635790348 0.1463861763 0.1257215362 0.2376661599 0.0049979210 0.0135900000 0.0003810000 0.0026060000 0.0000030000 0.0000030000 0.0014080000 47253277 96830484 509673472 3.8597025871 3.9942309856 3.8884727955 3140 1311867823.3954129219 0.1483527124 0.1257287436 0.2376661599 0.0049979258 0.0135720000 0.0003850000 0.0026070000 0.0000000000 0.0000030000 0.0011180000 47256893 96830484 509673472 3.8570187092 3.9961323738 3.8889641762 3141 1311867823.4318161011 0.1494902074 0.1257363086 0.2376661599 0.0049978459 0.0152260000 0.0003820000 0.0036670000 0.0000040000 0.0000040000 0.0020810000 47260733 96830484 509673472 3.8553082943 3.9954609871 3.8891773224 3142 1311867823.4634220600 0.1506733894 0.1257442452 0.2376661599 0.0050007123 0.0150410000 0.0003870000 0.0043420000 0.0000000000 0.0000040000 0.0011200000 47264405 96830484 509673472 3.8539640903 3.9961616993 3.8894939423 3143 1311867823.4969789982 0.1506287605 0.1257521627 0.2376661599 0.0050009487 0.0133110000 0.0003830000 0.0022510000 0.0000030000 0.0000030000 0.0013900000 47268133 96830484 509673472 3.8531935215 3.9973025322 3.8896005154 3144 1311867823.5356218815 0.1495333761 0.1257597267 0.2376661599 0.0050007133 0.0141790000 0.0003860000 0.0032910000 0.0000000000 0.0000030000 0.0011000000 47271917 96830484 509673472 3.8537764549 3.9980809689 3.8896577358 3145 1311867823.5636498928 0.1481167376 0.1257668354 0.2376661599 0.0050031301 0.0184570000 0.0004920000 0.0027980000 0.0000070000 0.0000070000 0.0022160000 47275533 96830484 509673472 3.8550281525 3.9961717129 3.8894829750 3146 1311867823.5974569321 0.1511764824 0.1257749122 0.2376661599 0.0050031476 0.0157110000 0.0003870000 0.0043850000 0.0000000000 0.0000030000 0.0011130000 47279261 96830484 509673472 3.8513989449 3.9970254898 3.8903944492 3147 1311867823.6316640377 0.1497817338 0.1257825407 0.2376661599 0.0050206287 0.0150190000 0.0003860000 0.0036530000 0.0000030000 0.0000030000 0.0013790000 47282989 96830484 509673472 3.8520214558 3.9991438389 3.8905689716 3148 1311867823.6636750698 0.1479475498 0.1257895817 0.2376661599 0.0050242025 0.0132370000 0.0003930000 0.0022730000 0.0000000000 0.0000040000 0.0010970000 47286661 96830484 509673472 3.8532969952 4.0000343323 3.8907327652 3149 1311867823.6956110001 0.1466229558 0.1257961976 0.2376661599 0.0050250208 0.0159950000 0.0003900000 0.0043710000 0.0000040000 0.0000040000 0.0020460000 47290277 96830484 509673472 3.8542768955 3.9983122349 3.8907175064 3150 1311867823.7316160202 0.1475802660 0.1258031132 0.2376661599 0.0050246324 0.0169810000 0.0004540000 0.0027610000 0.0000010000 0.0000080000 0.0012000000 47294117 96830484 509673472 3.8528065681 3.9993202686 3.8913581371 3151 1311867823.7635159492 0.1463989317 0.1258096494 0.2376661599 0.0050240532 0.0154380000 0.0003940000 0.0044110000 0.0000040000 0.0000040000 0.0013840000 47297789 96830484 509673472 3.8533678055 3.9999699593 3.8912177086 3152 1311867823.7964189053 0.1469699144 0.1258163627 0.2376661599 0.0050236049 0.0137280000 0.0003980000 0.0026370000 0.0000000000 0.0000030000 0.0010950000 47301461 96830484 509673472 3.8524169922 3.9983940125 3.8915188313 3153 1311867823.8316709995 0.1466479599 0.1258229696 0.2376661599 0.0050229099 0.0141830000 0.0003960000 0.0026360000 0.0000030000 0.0000030000 0.0020400000 47305245 96830484 509673472 3.8523046970 3.9991548061 3.8922104836 3154 1311867823.8635869026 0.1469700783 0.1258296745 0.2376661599 0.0050232108 0.0132130000 0.0003960000 0.0022860000 0.0000000000 0.0000030000 0.0010880000 47308917 96830484 509673472 3.8515994549 4.0002808571 3.8928341866 3155 1311867823.8993299007 0.1464561522 0.1258362122 0.2376661599 0.0050230211 0.0181010000 0.0004850000 0.0031970000 0.0000080000 0.0000070000 0.0014850000 47312645 96830484 509673472 3.8517544270 4.0004487038 3.8930485249 3156 1311867823.9316000938 0.1461647898 0.1258426534 0.2376661599 0.0050350463 0.0139990000 0.0004020000 0.0030180000 0.0000000000 0.0000030000 0.0010880000 47316373 96830484 509673472 3.8519105911 3.9994316101 3.8935148716 3157 1311867823.9639530182 0.1470505148 0.1258493712 0.2376661599 0.0050451621 0.0161330000 0.0003970000 0.0044360000 0.0000030000 0.0000030000 0.0020280000 47320101 96830484 509673472 3.8508105278 3.9998836517 3.8940553665 3158 1311867823.9956440926 0.1473475844 0.1258561787 0.2376661599 0.0050457660 0.0133040000 0.0004000000 0.0023050000 0.0000010000 0.0000040000 0.0010910000 47323661 96830484 509673472 3.8500409126 4.0009551048 3.8944697380 3159 1311867824.0315599442 0.1465867907 0.1258627411 0.2376661599 0.0050453983 0.0180800000 0.0005060000 0.0032080000 0.0000080000 0.0000070000 0.0014890000 47327501 96830484 509673472 3.8503108025 4.0005302429 3.8945777416 3160 1311867824.0634789467 0.1483285278 0.1258698505 0.2376661599 0.0050466619 0.0135940000 0.0004030000 0.0026600000 0.0000000000 0.0000030000 0.0010830000 47331173 96830484 509673472 3.8485863209 4.0001921654 3.8954362869 3161 1311867824.0966339111 0.1497267187 0.1258773978 0.2376661599 0.0050461349 0.0140800000 0.0003950000 0.0023130000 0.0000030000 0.0000040000 0.0020050000 47334845 96830484 509673472 3.8467192650 4.0012979507 3.8957304955 3162 1311867824.1315801144 0.1476002336 0.1258842677 0.2376661599 0.0050459131 0.0151370000 0.0004020000 0.0033380000 0.0000010000 0.0000040000 0.0010790000 47338629 96830484 509673472 3.8481390476 4.0004553795 3.8955276012 3163 1311867824.1636250019 0.1491939873 0.1258916372 0.2376661599 0.0050451681 0.0198240000 0.0005600000 0.0047170000 0.0000080000 0.0000080000 0.0014780000 47342301 96830484 509673472 3.8463745117 3.9999029636 3.8961346149 3164 1311867824.1974411011 0.1493557245 0.1258990532 0.2376661599 0.0050449902 0.0183860000 0.0004970000 0.0028840000 0.0000010000 0.0000080000 0.0011940000 47346029 96830484 509673472 3.8459112644 4.0024724007 3.8968884945 3165 1311867824.2314341068 0.1518974900 0.1259072676 0.2376661599 0.0050471588 0.0163580000 0.0004050000 0.0044620000 0.0000030000 0.0000030000 0.0020020000 47349701 96830484 509673472 3.8428573608 4.0020751953 3.8974399567 3166 1311867824.2667160034 0.1503220052 0.1259149791 0.2376661599 0.0050469014 0.0152150000 0.0004000000 0.0044540000 0.0000000000 0.0000040000 0.0010660000 47353485 96830484 509673472 3.8442277908 4.0016322136 3.8974938393 3167 1311867824.3015260696 0.1503991187 0.1259227101 0.2376661599 0.0050484707 0.0137850000 0.0004020000 0.0026690000 0.0000030000 0.0000030000 0.0013430000 47357213 96830484 509673472 3.8437700272 4.0040807724 3.8979656696 3168 1311867824.3329520226 0.1508092135 0.1259305657 0.2376661599 0.0050478244 0.0135390000 0.0004080000 0.0026670000 0.0000000000 0.0000030000 0.0010810000 47360941 96830484 509673472 3.8429903984 4.0049829483 3.8983006477 3169 1311867824.3655378819 0.1497967839 0.1259380969 0.2376661599 0.0050484084 0.0183110000 0.0005000000 0.0025060000 0.0000080000 0.0000070000 0.0021620000 47364613 96830484 509673472 3.8436212540 4.0057077408 3.8987405300 3170 1311867824.3960471153 0.1487194747 0.1259452834 0.2376661599 0.0050477329 0.0138720000 0.0004110000 0.0026970000 0.0000000000 0.0000030000 0.0010690000 47368173 96830484 509673472 3.8444592953 4.0077548027 3.8989233971 3171 1311867824.4315910339 0.1483614296 0.1259523525 0.2376661599 0.0050470694 0.0132060000 0.0004020000 0.0019740000 0.0000030000 0.0000030000 0.0013600000 47371957 96830484 509673472 3.8447234631 4.0091934204 3.8994791508 3172 1311867824.4656479359 0.1478198171 0.1259592464 0.2376661599 0.0050462994 0.0185390000 0.0005020000 0.0029070000 0.0000010000 0.0000080000 0.0011760000 47375741 96830484 509673472 3.8450629711 4.0111317635 3.9003171921 3173 1311867824.4978680611 0.1455559134 0.1259654225 0.2376661599 0.0050487992 0.0164700000 0.0004100000 0.0045420000 0.0000040000 0.0000030000 0.0019560000 47379413 96830484 509673472 3.8470222950 4.0114927292 3.9004702568 3174 1311867824.5316801071 0.1446743160 0.1259713169 0.2376661599 0.0050480364 0.0153660000 0.0004110000 0.0043950000 0.0000000000 0.0000050000 0.0010600000 47383085 96830484 509673472 3.8479056358 4.0129008293 3.9013965130 3175 1311867824.5658340454 0.1442733705 0.1259770813 0.2376661599 0.0050472909 0.0139460000 0.0004060000 0.0027120000 0.0000040000 0.0000040000 0.0013810000 47386869 96830484 509673472 3.8482775688 4.0139436722 3.9020090103 3176 1311867824.5956490040 0.1451213360 0.1259831091 0.2376661599 0.0050467130 0.0156460000 0.0004120000 0.0045290000 0.0000010000 0.0000040000 0.0011000000 47390429 96830484 509673472 3.8474383354 4.0140137672 3.9026296139 3177 1311867824.6318910122 0.1425710171 0.1259883304 0.2376661599 0.0050462045 0.0187400000 0.0005160000 0.0025400000 0.0000090000 0.0000080000 0.0022400000 47394269 96830484 509673472 3.8501906395 4.0141067505 3.9031581879 3178 1311867824.6661880016 0.1435646713 0.1259938610 0.2376661599 0.0050456282 0.0137880000 0.0004230000 0.0023610000 0.0000010000 0.0000040000 0.0011050000 47397941 96830484 509673472 3.8493475914 4.0148372650 3.9042811394 3179 1311867824.6979959011 0.1437963247 0.1259994610 0.2376661599 0.0050521112 0.0148990000 0.0004220000 0.0034560000 0.0000040000 0.0000030000 0.0013940000 47401613 96830484 509673472 3.8491504192 4.0143632889 3.9051940441 3180 1311867824.7314980030 0.1426030099 0.1260046823 0.2376661599 0.0050583337 0.0171520000 0.0007030000 0.0049650000 0.0000010000 0.0000040000 0.0012770000 47405229 96830484 509673472 3.8499875069 4.0147128105 3.9058873653 3181 1311867824.7639760971 0.1406953037 0.1260093005 0.2376661599 0.0050579338 0.0147180000 0.0004230000 0.0026070000 0.0000040000 0.0000040000 0.0020690000 47409013 96830484 509673472 3.8518698215 4.0152459145 3.9064800739 3182 1311867824.7997510433 0.1418542415 0.1260142801 0.2376661599 0.0050607404 0.0155870000 0.0004160000 0.0045460000 0.0000010000 0.0000040000 0.0010930000 47412685 96830484 509673472 3.8506813049 4.0164537430 3.9069526196 3183 1311867824.8315179348 0.1414379776 0.1260191257 0.2376661599 0.0050649843 0.0143550000 0.0004170000 0.0030850000 0.0000040000 0.0000040000 0.0013700000 47416413 96830484 509673472 3.8509449959 4.0152897835 3.9076802731 3184 1311867824.8635060787 0.1414627284 0.1260239761 0.2376661599 0.0050644688 0.0194330000 0.0005360000 0.0047810000 0.0000000000 0.0000080000 0.0012180000 47420085 96830484 509673472 3.8508076668 4.0151572227 3.9081051350 3185 1311867824.8995370865 0.1416294128 0.1260288758 0.2376661599 0.0050690557 0.0181720000 0.0005420000 0.0021820000 0.0000090000 0.0000080000 0.0022060000 47423813 96830484 509673472 3.8505127430 4.0158782005 3.9089660645 3186 1311867824.9316530228 0.1398659050 0.1260332188 0.2376661599 0.0050684310 0.0136710000 0.0004390000 0.0020110000 0.0000000000 0.0000040000 0.0010910000 47427541 96830484 509673472 3.8519072533 4.0153179169 3.9095416069 3187 1311867824.9636321068 0.1415031701 0.1260380729 0.2376661599 0.0050691762 0.0198000000 0.0005470000 0.0048080000 0.0000080000 0.0000080000 0.0014530000 47431213 96830484 509673472 3.8498203754 4.0152263641 3.9104256630 3188 1311867824.9996089935 0.1403912306 0.1260425752 0.2376661599 0.0050694108 0.0159860000 0.0004370000 0.0045760000 0.0000000000 0.0000040000 0.0010530000 47435053 96830484 509673472 3.8503897190 4.0151891708 3.9110586643 3189 1311867825.0316529274 0.1405696869 0.1260471305 0.2376661599 0.0050688877 0.0141280000 0.0004300000 0.0023540000 0.0000040000 0.0000040000 0.0020190000 47438669 96830484 509673472 3.8496646881 4.0147356987 3.9114294052 3190 1311867825.0644180775 0.1403759271 0.1260516223 0.2376661599 0.0050683943 0.0154460000 0.0004410000 0.0045270000 0.0000000000 0.0000030000 0.0010450000 47442285 96830484 509673472 3.8493161201 4.0143237114 3.9115114212 3191 1311867825.0997018814 0.1390700936 0.1260557021 0.2376661599 0.0050678939 0.0147010000 0.0004320000 0.0030820000 0.0000040000 0.0000040000 0.0013740000 47446069 96830484 509673472 3.8501069546 4.0149354935 3.9118480682 3192 1311867825.1316909790 0.1409398019 0.1260603650 0.2376661599 0.0050671518 0.0140080000 0.0004380000 0.0027390000 0.0000000000 0.0000040000 0.0010870000 47449797 96830484 509673472 3.8476943970 4.0143690109 3.9121375084 3193 1311867825.1636679173 0.1393480301 0.1260645265 0.2376661599 0.0050670789 0.0150350000 0.0004400000 0.0030920000 0.0000040000 0.0000040000 0.0019500000 47453469 96830484 509673472 3.8488304615 4.0119147301 3.9116740227 3194 1311867825.1996359825 0.1397888362 0.1260688234 0.2376661599 0.0050668991 0.0138180000 0.0004330000 0.0027380000 0.0000010000 0.0000040000 0.0010480000 47457197 96830484 509673472 3.8476529121 4.0126075745 3.9124705791 3195 1311867825.2316811085 0.1383782178 0.1260726761 0.2376661599 0.0050679076 0.0139560000 0.0004320000 0.0027280000 0.0000040000 0.0000030000 0.0013630000 47460925 96830484 509673472 3.8470106125 4.0146203041 3.9121508598 3196 1311867825.2670049667 0.1361759454 0.1260758373 0.2376661599 0.0050693838 0.0148420000 0.0004360000 0.0038330000 0.0000000000 0.0000040000 0.0010450000 47464709 96830484 509673472 3.8482644558 4.0124993324 3.9117710590 3197 1311867825.2996079922 0.1372829527 0.1260793428 0.2376661599 0.0050686109 0.0143200000 0.0004360000 0.0023830000 0.0000030000 0.0000030000 0.0020400000 47468437 96830484 509673472 3.8462057114 4.0131802559 3.9123067856 3198 1311867825.3316459656 0.1366153657 0.1260826374 0.2376661599 0.0050697236 0.0140530000 0.0004400000 0.0027480000 0.0000010000 0.0000040000 0.0010500000 47472053 96830484 509673472 3.8458113670 4.0143771172 3.9127833843 3199 1311867825.3635549545 0.1378319561 0.1260863102 0.2376661599 0.0050691925 0.0138890000 0.0004370000 0.0026290000 0.0000030000 0.0000030000 0.0013430000 47475725 96830484 509673472 3.8436224461 4.0133481026 3.9131753445 3200 1311867825.3995220661 0.1374523491 0.1260898621 0.2376661599 0.0050687963 0.0152790000 0.0004390000 0.0042210000 0.0000000000 0.0000030000 0.0010510000 47479565 96830484 509673472 3.8433787823 4.0120229721 3.9137480259 3201 1311867825.4329199791 0.1362319291 0.1260930305 0.2376661599 0.0050685045 0.0204820000 0.0005480000 0.0044950000 0.0000070000 0.0000070000 0.0021360000 47483237 96830484 509673472 3.8438041210 4.0129599571 3.9139335155 3202 1311867825.4655759335 0.1382857859 0.1260968384 0.2376661599 0.0050677768 0.0157230000 0.0004460000 0.0046020000 0.0000010000 0.0000040000 0.0010520000 47486853 96830484 509673472 3.8411068916 4.0121541023 3.9139356613 3203 1311867825.4996039867 0.1383126378 0.1261006522 0.2376661599 0.0050669964 0.0196880000 0.0005460000 0.0039630000 0.0000080000 0.0000070000 0.0014660000 47490525 96830484 509673472 3.8405249119 4.0124268532 3.9140913486 3204 1311867825.5338120461 0.1380450279 0.1261043802 0.2376661599 0.0050662361 0.0139570000 0.0004460000 0.0027570000 0.0000010000 0.0000050000 0.0010470000 47494309 96830484 509673472 3.8405170441 4.0131258965 3.9145700932 3205 1311867825.5637319088 0.1390881091 0.1261084313 0.2376661599 0.0050656367 0.0143960000 0.0004400000 0.0023880000 0.0000040000 0.0000040000 0.0019490000 47497925 96830484 509673472 3.8392128944 4.0134830475 3.9145536423 3206 1311867825.5995988846 0.1410389096 0.1261130883 0.2376661599 0.0050649205 0.0143220000 0.0004450000 0.0031140000 0.0000010000 0.0000040000 0.0010980000 47501653 96830484 509673472 3.8365094662 4.0132627487 3.9149127007 3207 1311867825.6372098923 0.1393547505 0.1261172173 0.2376661599 0.0050644873 0.0151160000 0.0004410000 0.0034900000 0.0000040000 0.0000040000 0.0013670000 47505493 96830484 509673472 3.8376567364 4.0135931969 3.9149036407 3208 1311867825.6636829376 0.1382362098 0.1261209950 0.2376661599 0.0050638065 0.0191360000 0.0005370000 0.0044530000 0.0000010000 0.0000080000 0.0012320000 47508997 96830484 509673472 3.8388702869 4.0140919685 3.9149265289 3209 1311867825.6997060776 0.1397122741 0.1261252304 0.2376661599 0.0050642284 0.0149080000 0.0004430000 0.0027820000 0.0000040000 0.0000040000 0.0020360000 47512781 96830484 509673472 3.8368976116 4.0129084587 3.9150698185 3210 1311867825.7345299721 0.1411925405 0.1261299243 0.2376661599 0.0050635690 0.0159190000 0.0004380000 0.0045850000 0.0000010000 0.0000030000 0.0010960000 47516509 96830484 509673472 3.8349027634 4.0131707191 3.9155368805 3211 1311867825.7654349804 0.1375386715 0.1261334773 0.2376661599 0.0050629308 0.0190530000 0.0005470000 0.0029910000 0.0000100000 0.0000090000 0.0014980000 47520125 96830484 509673472 3.8385477066 4.0144925117 3.9149610996 3212 1311867825.7998030186 0.1400839984 0.1261378205 0.2376661599 0.0050628645 0.0156920000 0.0004500000 0.0045930000 0.0000000000 0.0000030000 0.0010880000 47523965 96830484 509673472 3.8358123302 4.0114502907 3.9149670601 3213 1311867825.8355960846 0.1410211772 0.1261424528 0.2376661599 0.0050623294 0.0165540000 0.0004430000 0.0045880000 0.0000040000 0.0000030000 0.0020310000 47527749 96830484 509673472 3.8344025612 4.0128650665 3.9152925014 3214 1311867825.8656499386 0.1396766156 0.1261466638 0.2376661599 0.0050617245 0.0157150000 0.0004430000 0.0046010000 0.0000000000 0.0000030000 0.0010960000 47531309 96830484 509673472 3.8355667591 4.0143761635 3.9148399830 3215 1311867825.8996019363 0.1370785683 0.1261500641 0.2376661599 0.0050616888 0.0196070000 0.0005500000 0.0048070000 0.0000080000 0.0000070000 0.0014910000 47535093 96830484 509673472 3.8381960392 4.0129299164 3.9144668579 3216 1311867825.9338490963 0.1377141327 0.1261536599 0.2376661599 0.0050613035 0.0142370000 0.0004900000 0.0020080000 0.0000000000 0.0000040000 0.0010950000 47538821 96830484 509673472 3.8371641636 4.0131006241 3.9146547318 3217 1311867825.9640550613 0.1375849396 0.1261572133 0.2376661599 0.0050607992 0.0167530000 0.0004390000 0.0045890000 0.0000040000 0.0000040000 0.0020430000 47542437 96830484 509673472 3.8374245167 4.0146613121 3.9143266678 3218 1311867825.9996759892 0.1379962265 0.1261608923 0.2376661599 0.0050604307 0.0143170000 0.0004470000 0.0031050000 0.0000000000 0.0000030000 0.0010960000 47546165 96830484 509673472 3.8367266655 4.0129327774 3.9141972065 3219 1311867826.0327920914 0.1379060149 0.1261645409 0.2376661599 0.0050600761 0.0152410000 0.0004350000 0.0037340000 0.0000030000 0.0000030000 0.0013750000 47549893 96830484 509673472 3.8367354870 4.0147948265 3.9141964912 3220 1311867826.0636880398 0.1382472217 0.1261682933 0.2376661599 0.0050597833 0.0181960000 0.0005370000 0.0029410000 0.0000010000 0.0000080000 0.0012320000 47553565 96830484 509673472 3.8361485004 4.0160441399 3.9143702984 3221 1311867826.1009249687 0.1398082525 0.1261725280 0.2376661599 0.0050598124 0.0155830000 0.0004420000 0.0031360000 0.0000030000 0.0000030000 0.0020460000 47557349 96830484 509673472 3.8343467712 4.0140900612 3.9143784046 3222 1311867826.1333520412 0.1401201785 0.1261768569 0.2376661599 0.0050591384 0.0161140000 0.0004400000 0.0044880000 0.0000000000 0.0000040000 0.0010880000 47561077 96830484 509673472 3.8339862823 4.0138707161 3.9148335457 3223 1311867826.1658940315 0.1398641616 0.1261811037 0.2376661599 0.0050584521 0.0162370000 0.0004540000 0.0046010000 0.0000040000 0.0000040000 0.0013550000 47564749 96830484 509673472 3.8339803219 4.0153326988 3.9147326946 3224 1311867826.1998670101 0.1380495429 0.1261847849 0.2376661599 0.0050586454 0.0150570000 0.0004460000 0.0034910000 0.0000010000 0.0000040000 0.0010940000 47568477 96830484 509673472 3.8356385231 4.0146923065 3.9142093658 3225 1311867826.2345190048 0.1389269680 0.1261887360 0.2376661599 0.0050578873 0.0166410000 0.0004440000 0.0044990000 0.0000040000 0.0000030000 0.0020070000 47572205 96830484 509673472 3.8347296715 4.0135602951 3.9141910076 3226 1311867826.2638120651 0.1386628598 0.1261926027 0.2376661599 0.0050576221 0.0147730000 0.0004410000 0.0033720000 0.0000000000 0.0000040000 0.0010910000 47575821 96830484 509673472 3.8344182968 4.0135941505 3.9142284393 3227 1311867826.3011031151 0.1412617266 0.1261972724 0.2376661599 0.0050581734 0.0194920000 0.0005350000 0.0033440000 0.0000080000 0.0000070000 0.0014830000 47579549 96830484 509673472 3.8318743706 4.0125737190 3.9141626358 3228 1311867826.3321969509 0.1400421262 0.1262015614 0.2376661599 0.0050586624 0.0143350000 0.0004430000 0.0024020000 0.0000000000 0.0000040000 0.0010890000 47583053 96830484 509673472 3.8323466778 4.0126891136 3.9138510227 3229 1311867826.3637990952 0.1419892013 0.1262064508 0.2376661599 0.0050592560 0.0167810000 0.0004460000 0.0044810000 0.0000040000 0.0000040000 0.0020440000 47586725 96830484 509673472 3.8306746483 4.0133671761 3.9142627716 3230 1311867826.3997180462 0.1418567598 0.1262112961 0.2376661599 0.0050585305 0.0158560000 0.0004470000 0.0043660000 0.0000000000 0.0000040000 0.0010890000 47590453 96830484 509673472 3.8304727077 4.0132293701 3.9140005112 3231 1311867826.4321830273 0.1416791975 0.1262160834 0.2376661599 0.0050580204 0.0146800000 0.0004370000 0.0031080000 0.0000040000 0.0000030000 0.0013720000 47594181 96830484 509673472 3.8305172920 4.0128593445 3.9140572548 3232 1311867826.4641919136 0.1417578012 0.1262208921 0.2376661599 0.0050575994 0.0138310000 0.0004400000 0.0023800000 0.0000000000 0.0000040000 0.0011070000 47597909 96830484 509673472 3.8302040100 4.0147562027 3.9141449928 3233 1311867826.5007300377 0.1412420720 0.1262255383 0.2376661599 0.0050569164 0.0192100000 0.0005540000 0.0021980000 0.0000120000 0.0000090000 0.0022910000 47601637 96830484 509673472 3.8304510117 4.0145311356 3.9137651920 3234 1311867826.5320169926 0.1411997974 0.1262301686 0.2376661599 0.0050561671 0.0150850000 0.0004460000 0.0023890000 0.0000010000 0.0000040000 0.0012680000 47605309 96830484 509673472 3.8302245140 4.0139584541 3.9138369560 3235 1311867826.5638980865 0.1430649757 0.1262353725 0.2376661599 0.0050555156 0.0143640000 0.0004890000 0.0023860000 0.0000040000 0.0000030000 0.0013870000 47609037 96830484 509673472 3.8283772469 4.0145187378 3.9139826298 3236 1311867826.6006839275 0.1421986371 0.1262403055 0.2376661599 0.0050548332 0.0142660000 0.0004480000 0.0023890000 0.0000000000 0.0000040000 0.0010820000 47612765 96830484 509673472 3.8290495872 4.0142250061 3.9138638973 3237 1311867826.6315999031 0.1402755082 0.1262446414 0.2376661599 0.0050545514 0.0157980000 0.0004360000 0.0031270000 0.0000040000 0.0000030000 0.0020440000 47616381 96830484 509673472 3.8304371834 4.0144667625 3.9133598804 3238 1311867826.6638810635 0.1420504451 0.1262495228 0.2376661599 0.0050544172 0.0141580000 0.0004370000 0.0023910000 0.0000000000 0.0000040000 0.0010950000 47620053 96830484 509673472 3.8284018040 4.0159735680 3.9139356613 3239 1311867826.6997959614 0.1413752139 0.1262541926 0.2376661599 0.0050537223 0.0156070000 0.0004340000 0.0038420000 0.0000040000 0.0000030000 0.0013640000 47623781 96830484 509673472 3.8284003735 4.0158042908 3.9138023853 3240 1311867826.7349510193 0.1425945014 0.1262592359 0.2376661599 0.0050531144 0.0157530000 0.0004440000 0.0044730000 0.0000010000 0.0000040000 0.0010890000 47627565 96830484 509673472 3.8269515038 4.0138840675 3.9136927128 3241 1311867826.7678439617 0.1406001747 0.1262636608 0.2376661599 0.0050526106 0.0165080000 0.0004410000 0.0044610000 0.0000030000 0.0000030000 0.0020400000 47631181 96830484 509673472 3.8285295963 4.0146465302 3.9133718014 3242 1311867826.8019490242 0.1404486001 0.1262680362 0.2376661599 0.0050523998 0.0145250000 0.0004450000 0.0031100000 0.0000000000 0.0000030000 0.0010910000 47634965 96830484 509673472 3.8284735680 4.0143857002 3.9129259586 3243 1311867826.8324790001 0.1425932497 0.1262730701 0.2376661599 0.0050552448 0.0147300000 0.0004410000 0.0032520000 0.0000040000 0.0000030000 0.0013690000 47638581 96830484 509673472 3.8260939121 4.0124773979 3.9130756855 3244 1311867826.8646159172 0.1422798336 0.1262780044 0.2376661599 0.0050545979 0.0194400000 0.0005310000 0.0048160000 0.0000010000 0.0000090000 0.0012340000 47642197 96830484 509673472 3.8261790276 4.0125989914 3.9130642414 3245 1311867826.9008219242 0.1415999681 0.1262827261 0.2376661599 0.0050547798 0.0149280000 0.0004450000 0.0026250000 0.0000040000 0.0000040000 0.0020550000 47645981 96830484 509673472 3.8261163235 4.0130953789 3.9126904011 3246 1311867826.9319140911 0.1433754712 0.1262879919 0.2376661599 0.0050577736 0.0157900000 0.0004340000 0.0045690000 0.0000010000 0.0000030000 0.0010970000 47649541 96830484 509673472 3.8247194290 4.0134267807 3.9128658772 3247 1311867826.9639439583 0.1419779658 0.1262928240 0.2376661599 0.0050582475 0.0160050000 0.0004340000 0.0045680000 0.0000040000 0.0000040000 0.0013850000 47653101 96830484 509673472 3.8257536888 4.0134339333 3.9125297070 3248 1311867827.0083661079 0.1435893327 0.1262981493 0.2376661599 0.0050597263 0.0157420000 0.0004460000 0.0045570000 0.0000000000 0.0000040000 0.0010950000 47657053 96830484 509673472 3.8239161968 4.0137405396 3.9127273560 3249 1311867827.0334970951 0.1427548230 0.1263032145 0.2376661599 0.0050591430 0.0148610000 0.0004340000 0.0027430000 0.0000040000 0.0000040000 0.0020400000 47660501 96830484 509673472 3.8246085644 4.0132312775 3.9123966694 3250 1311867827.0653018951 0.1434511244 0.1263084908 0.2376661599 0.0050599970 0.0145360000 0.0004430000 0.0030970000 0.0000010000 0.0000040000 0.0010900000 47664005 96830484 509673472 3.8235263824 4.0129384995 3.9122397900 3251 1311867827.0995759964 0.1436448097 0.1263138234 0.2376661599 0.0050611392 0.0198380000 0.0005370000 0.0048080000 0.0000080000 0.0000070000 0.0015160000 47667621 96830484 509673472 3.8237178326 4.0134310722 3.9118995667 3252 1311867827.1319890022 0.1431444138 0.1263189988 0.2376661599 0.0050606117 0.0156900000 0.0004490000 0.0042420000 0.0000000000 0.0000040000 0.0011050000 47671125 96830484 509673472 3.8242800236 4.0137114525 3.9117364883 3253 1311867827.1636219025 0.1416008174 0.1263236966 0.2376661599 0.0050608731 0.0199420000 0.0005280000 0.0033350000 0.0000100000 0.0000090000 0.0022210000 47674853 96830484 509673472 3.8258960247 4.0136575699 3.9113416672 3254 1311867827.2006959915 0.1446192414 0.1263293191 0.2376661599 0.0050635228 0.0192510000 0.0005600000 0.0037310000 0.0000010000 0.0000090000 0.0012360000 47678637 96830484 509673472 3.8230288029 4.0124120712 3.9110589027 3255 1311867827.2315700054 0.1431214064 0.1263344779 0.2376661599 0.0050628453 0.0162350000 0.0004410000 0.0045940000 0.0000040000 0.0000040000 0.0013910000 47682197 96830484 509673472 3.8247046471 4.0136508942 3.9105367661 3256 1311867827.2656030655 0.1434886307 0.1263397464 0.2376661599 0.0050622737 0.0139430000 0.0004420000 0.0023660000 0.0000010000 0.0000040000 0.0011080000 47685757 96830484 509673472 3.8245213032 4.0135450363 3.9102394581 3257 1311867827.2999110222 0.1447312981 0.1263453932 0.2376661599 0.0050623165 0.0147170000 0.0004360000 0.0023840000 0.0000040000 0.0000040000 0.0020560000 47689541 96830484 509673472 3.8231353760 4.0130977631 3.9106118679 3258 1311867827.3331999779 0.1439006329 0.1263507815 0.2376661599 0.0050617971 0.0139640000 0.0004390000 0.0023830000 0.0000010000 0.0000040000 0.0010990000 47693157 96830484 509673472 3.8237779140 4.0153603554 3.9107377529 3259 1311867827.3665180206 0.1436558515 0.1263560915 0.2376661599 0.0050611052 0.0161020000 0.0004380000 0.0044650000 0.0000030000 0.0000030000 0.0013630000 47696829 96830484 509673472 3.8239412308 4.0148515701 3.9105081558 3260 1311867827.4023349285 0.1426446885 0.1263610880 0.2376661599 0.0050618500 0.0205850000 0.0005460000 0.0048560000 0.0000020000 0.0000090000 0.0012360000 47700669 96830484 509673472 3.8251292706 4.0144052505 3.9104142189 3261 1311867827.4316511154 0.1435983032 0.1263663738 0.2376661599 0.0050617348 0.0153070000 0.0004330000 0.0027550000 0.0000030000 0.0000030000 0.0020450000 47704229 96830484 509673472 3.8240950108 4.0156903267 3.9108321667 3262 1311867827.4660930634 0.1428559572 0.1263714289 0.2376661599 0.0050610581 0.0196220000 0.0005320000 0.0048080000 0.0000010000 0.0000080000 0.0012260000 47707957 96830484 509673472 3.8246204853 4.0152325630 3.9103193283 3263 1311867827.5022308826 0.1420081258 0.1263762210 0.2376661599 0.0050621045 0.0142990000 0.0004440000 0.0023780000 0.0000040000 0.0000040000 0.0013750000 47711797 96830484 509673472 3.8255207539 4.0134897232 3.9098308086 3264 1311867827.5346870422 0.1430044770 0.1263813154 0.2376661599 0.0050626605 0.0160250000 0.0004360000 0.0045740000 0.0000000000 0.0000030000 0.0010980000 47715413 96830484 509673472 3.8243696690 4.0152449608 3.9102129936 3265 1311867827.5639040470 0.1426698714 0.1263863043 0.2376661599 0.0050621678 0.0196130000 0.0005290000 0.0025750000 0.0000110000 0.0000100000 0.0022520000 47719085 96830484 509673472 3.8245191574 4.0146160126 3.9098048210 3266 1311867827.6014358997 0.1435337514 0.1263915546 0.2376661599 0.0050622572 0.0142570000 0.0004470000 0.0026320000 0.0000000000 0.0000040000 0.0010930000 47722869 96830484 509673472 3.8237667084 4.0129981041 3.9096248150 3267 1311867827.6328499317 0.1421469599 0.1263963772 0.2376661599 0.0050625352 0.0162760000 0.0004380000 0.0045790000 0.0000030000 0.0000030000 0.0013780000 47726541 96830484 509673472 3.8249046803 4.0149426460 3.9098105431 3268 1311867827.6636641026 0.1434887201 0.1264016074 0.2376661599 0.0050618489 0.0137020000 0.0004560000 0.0023740000 0.0000010000 0.0000040000 0.0011010000 47730213 96830484 509673472 3.8232812881 4.0153055191 3.9100623131 3269 1311867827.7023649216 0.1432013512 0.1264067465 0.2376661599 0.0050614785 0.0201930000 0.0005480000 0.0046780000 0.0000080000 0.0000080000 0.0021970000 47734053 96830484 509673472 3.8238918781 4.0140800476 3.9101841450 3270 1311867827.7343521118 0.1422772408 0.1264115999 0.2376661599 0.0050615225 0.0149540000 0.0004430000 0.0022160000 0.0000000000 0.0000050000 0.0014960000 47737725 96830484 509673472 3.8247547150 4.0148706436 3.9103074074 3271 1311867827.7669301033 0.1406933814 0.1264159660 0.2376661599 0.0050638964 0.0165840000 0.0004880000 0.0045900000 0.0000040000 0.0000040000 0.0013750000 47741341 96830484 509673472 3.8260612488 4.0153965950 3.9101581573 3272 1311867827.8077390194 0.1422823071 0.1264208152 0.2376661599 0.0050642095 0.0150410000 0.0004460000 0.0034820000 0.0000000000 0.0000040000 0.0010920000 47745293 96830484 509673472 3.8244564533 4.0140223503 3.9105703831 3273 1311867827.8316879272 0.1424901932 0.1264257248 0.2376661599 0.0050642143 0.0167660000 0.0004390000 0.0044550000 0.0000040000 0.0000030000 0.0020450000 47748685 96830484 509673472 3.8242888451 4.0144028664 3.9107275009 3274 1311867827.8644089699 0.1410563141 0.1264301936 0.2376661599 0.0050637127 0.0199370000 0.0005330000 0.0048080000 0.0000010000 0.0000080000 0.0012400000 47752469 96830484 509673472 3.8257384300 4.0144667625 3.9104723930 3275 1311867827.9007999897 0.1427451223 0.1264351752 0.2376661599 0.0050651451 0.0163840000 0.0004460000 0.0044630000 0.0000040000 0.0000040000 0.0013790000 47756141 96830484 509673472 3.8242781162 4.0131502151 3.9105901718 3276 1311867827.9316790104 0.1419409662 0.1264399084 0.2376661599 0.0050663581 0.0160760000 0.0004520000 0.0044680000 0.0000010000 0.0000040000 0.0011010000 47759813 96830484 509673472 3.8246750832 4.0139651299 3.9107000828 3277 1311867827.9717168808 0.1437184066 0.1264451810 0.2376661599 0.0050697638 0.0166800000 0.0004390000 0.0044460000 0.0000040000 0.0000040000 0.0020530000 47763653 96830484 509673472 3.8231298923 4.0136966705 3.9110205173 3278 1311867827.9999699593 0.1419672370 0.1264499162 0.2376661599 0.0050699527 0.0149210000 0.0004320000 0.0034760000 0.0000000000 0.0000030000 0.0011050000 47767325 96830484 509673472 3.8247809410 4.0125398636 3.9103174210 3279 1311867828.0320069790 0.1432446837 0.1264550382 0.2376661599 0.0050701807 0.0194310000 0.0005250000 0.0029740000 0.0000100000 0.0000110000 0.0014620000 47770941 96830484 509673472 3.8235373497 4.0140662193 3.9106905460 3280 1311867828.0711700916 0.1427087784 0.1264599936 0.2376661599 0.0050717989 0.0143680000 0.0004390000 0.0023800000 0.0000000000 0.0000040000 0.0011290000 47774781 96830484 509673472 3.8238303661 4.0137825012 3.9107050896 3281 1311867828.1003229618 0.1427165717 0.1264649483 0.2376661599 0.0050711492 0.0174120000 0.0004310000 0.0045730000 0.0000040000 0.0000040000 0.0019710000 47778453 96830484 509673472 3.8239159584 4.0128374100 3.9106853008 3282 1311867828.1317639351 0.1429427415 0.1264699690 0.2376661599 0.0050726618 0.0162390000 0.0004410000 0.0045750000 0.0000000000 0.0000030000 0.0010610000 47782069 96830484 509673472 3.8239846230 4.0133910179 3.9111063480 3283 1311867828.1714239120 0.1450163871 0.1264756182 0.2376661599 0.0050730521 0.0162540000 0.0004470000 0.0045800000 0.0000030000 0.0000040000 0.0013270000 47785965 96830484 509673472 3.8216531277 4.0139231682 3.9111173153 3284 1311867828.2080869675 0.1430062503 0.1264806519 0.2376661599 0.0050775614 0.0141680000 0.0004370000 0.0027320000 0.0000000000 0.0000040000 0.0010540000 47789805 96830484 509673472 3.8241674900 4.0136990547 3.9109954834 3285 1311867828.2316999435 0.1429578215 0.1264856678 0.2376661599 0.0050780246 0.0154000000 0.0004360000 0.0031080000 0.0000030000 0.0000040000 0.0020500000 47793197 96830484 509673472 3.8241772652 4.0139942169 3.9114711285 3286 1311867828.2725389004 0.1417750567 0.1264903207 0.2376661599 0.0050773924 0.0187090000 0.0005400000 0.0025960000 0.0000010000 0.0000090000 0.0012360000 47797093 96830484 509673472 3.8254945278 4.0150403976 3.9115447998 3287 1311867828.3008439541 0.1428146362 0.1264952870 0.2376661599 0.0050770205 0.0162750000 0.0004330000 0.0045750000 0.0000040000 0.0000040000 0.0013730000 47800709 96830484 509673472 3.8248951435 4.0126938820 3.9117355347 ================================================ FILE: icra2018_results/1080/violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 01:24:21 Properties: ================= frame-limit: 0 log-file: out_paper//violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520030 0.0582520030 0.0582520030 -nan 0.0079590000 0.0004370000 0.0005210000 0.0000050000 0.0000010000 0.0022690000 22194645 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 2 1311867170.4941389561 0.0599970818 0.0591245424 0.0599970818 0.0035989983 0.0022090000 0.0004500000 0.0005130000 0.0000040000 0.0000010000 0.0007370000 34781533 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 3 1311867170.5264289379 0.0615839623 0.0599443490 0.0615839623 0.0081929692 0.0041980000 0.0006030000 0.0005700000 0.0000150000 0.0000020000 0.0011250000 34785653 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 4 1311867170.5623490810 0.0628964603 0.0606823768 0.0628964603 0.0105670472 0.0048250000 0.0005820000 0.0005910000 0.0000140000 0.0000230000 0.0017540000 34789837 96830484 509673472 4.0000000000 4.0000000000 4.0000000000 5 1311867170.5942170620 0.0609257706 0.0607310556 0.0628964603 0.0111246966 0.0076730000 0.0006260000 0.0031330000 0.0000150000 0.0000130000 0.0026080000 34793837 96830484 509673472 4.0031237602 3.9974739552 3.9970715046 6 1311867170.6260869503 0.0606061891 0.0607102445 0.0628964603 0.0110246630 0.0070020000 0.0004760000 0.0046840000 0.0000000000 0.0000060000 0.0011700000 34798309 96830484 509673472 4.0016183853 3.9956717491 3.9953823090 7 1311867170.6621398926 0.0602248944 0.0606409088 0.0628964603 0.0105576308 0.0055070000 0.0004260000 0.0031330000 0.0000050000 0.0000040000 0.0014060000 34802149 96830484 509673472 4.0018339157 3.9940984249 3.9936194420 8 1311867170.6942050457 0.0600368455 0.0605654009 0.0628964603 0.0100586598 0.0073080000 0.0005150000 0.0047630000 0.0000010000 0.0000070000 0.0012270000 34805765 96830484 509673472 4.0011434555 3.9931440353 3.9919631481 9 1311867170.7263879776 0.0608400255 0.0605959147 0.0628964603 0.0100336623 0.0071300000 0.0005080000 0.0033290000 0.0000080000 0.0000080000 0.0022770000 34810205 96830484 509673472 4.0015687943 3.9936788082 3.9908602238 10 1311867170.7620189190 0.0603617802 0.0605725013 0.0628964603 0.0098656895 0.0075960000 0.0005080000 0.0048410000 0.0000000000 0.0000080000 0.0012520000 34815645 96830484 509673472 3.9995110035 3.9909105301 3.9892902374 11 1311867170.7941920757 0.0607238449 0.0605862598 0.0628964603 0.0096819656 0.0053950000 0.0004550000 0.0028100000 0.0000050000 0.0000050000 0.0014360000 34819205 96830484 509673472 4.0003819466 3.9889509678 3.9876792431 12 1311867170.8262820244 0.0612688363 0.0606431412 0.0628964603 0.0096081815 0.0072100000 0.0005060000 0.0044530000 0.0000010000 0.0000080000 0.0012480000 34822933 96830484 509673472 4.0014419556 3.9856193066 3.9859523773 13 1311867170.8622210026 0.0614231341 0.0607031406 0.0628964603 0.0096871982 0.0070940000 0.0004470000 0.0039270000 0.0000050000 0.0000050000 0.0020820000 34826717 96830484 509673472 4.0042138100 3.9817700386 3.9834048748 14 1311867170.8943779469 0.0618286505 0.0607835342 0.0628964603 0.0094048533 0.0058800000 0.0005090000 0.0032620000 0.0000010000 0.0000080000 0.0012600000 34830333 96830484 509673472 4.0020446777 3.9801094532 3.9812369347 15 1311867170.9263520241 0.0620389245 0.0608672269 0.0628964603 0.0093875104 0.0051750000 0.0004340000 0.0028210000 0.0000060000 0.0000050000 0.0014220000 34834061 96830484 509673472 4.0027852058 3.9772689342 3.9783914089 16 1311867170.9621469975 0.0615617968 0.0609106375 0.0628964603 0.0091731308 0.0051310000 0.0004140000 0.0031630000 0.0000010000 0.0000040000 0.0011200000 34837845 96830484 509673472 4.0006017685 3.9752972126 3.9754087925 17 1311867170.9942629337 0.0615465529 0.0609480443 0.0628964603 0.0090184500 0.0084510000 0.0005760000 0.0035590000 0.0000140000 0.0000140000 0.0027830000 34842997 96830484 509673472 3.9983141422 3.9747190475 3.9725222588 18 1311867171.0262739658 0.0615842752 0.0609833904 0.0628964603 0.0087669772 0.0070700000 0.0004670000 0.0047880000 0.0000010000 0.0000070000 0.0011810000 34849925 96830484 509673472 3.9982182980 3.9730949402 3.9697563648 19 1311867171.0623519421 0.0607632287 0.0609718030 0.0628964603 0.0091378273 0.0061330000 0.0005090000 0.0033050000 0.0000080000 0.0000080000 0.0015250000 34853709 96830484 509673472 3.9972651005 3.9699728489 3.9667029381 20 1311867171.0942349434 0.0605181381 0.0609491197 0.0628964603 0.0090702124 0.0046890000 0.0004360000 0.0024510000 0.0000000000 0.0000060000 0.0011600000 34857325 96830484 509673472 3.9972701073 3.9690628052 3.9645524025 21 1311867171.1262509823 0.0605349913 0.0609293993 0.0628964603 0.0089256808 0.0077560000 0.0004120000 0.0046020000 0.0000040000 0.0000040000 0.0021510000 34861053 96830484 509673472 3.9977769852 3.9692504406 3.9624044895 22 1311867171.1622469425 0.0602456145 0.0608983182 0.0628964603 0.0088226150 0.0073800000 0.0005900000 0.0031240000 0.0000010000 0.0000190000 0.0016440000 34864837 96830484 509673472 3.9996650219 3.9667217731 3.9608986378 23 1311867171.1942689419 0.0591652691 0.0608229682 0.0628964603 0.0090508667 0.0092860000 0.0005890000 0.0047260000 0.0000160000 0.0000150000 0.0019340000 34868453 96830484 509673472 4.0014710426 3.9671664238 3.9596331120 24 1311867171.2262530327 0.0610344373 0.0608317795 0.0628964603 0.0090322382 0.0070010000 0.0005860000 0.0031300000 0.0000020000 0.0000160000 0.0016730000 34872181 96830484 509673472 4.0051121712 3.9670631886 3.9591307640 25 1311867171.2622439861 0.0604282394 0.0608156379 0.0628964603 0.0090268206 0.0071170000 0.0004690000 0.0032560000 0.0000070000 0.0000080000 0.0023270000 34875965 96830484 509673472 4.0062756538 3.9663705826 3.9580407143 26 1311867171.2943410873 0.0607744530 0.0608140538 0.0628964603 0.0090315186 0.0075890000 0.0004670000 0.0047750000 0.0000010000 0.0000080000 0.0012840000 34879525 96830484 509673472 4.0050034523 3.9689943790 3.9576413631 27 1311867171.3263869286 0.0610777140 0.0608238190 0.0628964603 0.0092652168 0.0070290000 0.0004720000 0.0040370000 0.0000080000 0.0000080000 0.0015600000 34883253 96830484 509673472 4.0014104843 3.9707036018 3.9562153816 28 1311867171.3622460365 0.0606426857 0.0608173500 0.0628964603 0.0091327742 0.0069190000 0.0004280000 0.0046630000 0.0000000000 0.0000040000 0.0011790000 34887037 96830484 509673472 3.9983029366 3.9719862938 3.9549043179 29 1311867171.3941431046 0.0616778992 0.0608470241 0.0628964603 0.0093273781 0.0076940000 0.0005760000 0.0035700000 0.0000150000 0.0000140000 0.0024370000 34890653 96830484 509673472 3.9963865280 3.9747483730 3.9538209438 30 1311867171.4262878895 0.0624610595 0.0609008253 0.0628964603 0.0092851315 0.0056730000 0.0005380000 0.0032260000 0.0000010000 0.0000060000 0.0011930000 34894381 96830484 509673472 3.9952287674 3.9750316143 3.9522840977 31 1311867171.4622440338 0.0615437888 0.0609215660 0.0628964603 0.0092230778 0.0070030000 0.0005490000 0.0040910000 0.0000080000 0.0000070000 0.0015290000 34898165 96830484 509673472 3.9949390888 3.9722182751 3.9500682354 32 1311867171.4944040775 0.0617154725 0.0609463756 0.0628964603 0.0091412939 0.0053470000 0.0005110000 0.0025920000 0.0000010000 0.0000120000 0.0014020000 34901781 96830484 509673472 3.9956381321 3.9733390808 3.9481217861 33 1311867171.5261778831 0.0613007732 0.0609571149 0.0628964603 0.0090000002 0.0078030000 0.0004460000 0.0046740000 0.0000060000 0.0000050000 0.0021490000 34908581 96830484 509673472 3.9945807457 3.9734292030 3.9461219311 34 1311867171.5622971058 0.0606253669 0.0609473576 0.0628964603 0.0088657115 0.0049040000 0.0004210000 0.0027680000 0.0000010000 0.0000040000 0.0011470000 34918765 96830484 509673472 3.9948854446 3.9731416702 3.9447348118 35 1311867171.5942931175 0.0608280785 0.0609439496 0.0628964603 0.0088001305 0.0066210000 0.0004110000 0.0042250000 0.0000040000 0.0000040000 0.0014290000 34922381 96830484 509673472 3.9961769581 3.9744696617 3.9438025951 36 1311867171.6263399124 0.0606494807 0.0609357700 0.0628964603 0.0087034177 0.0052510000 0.0004120000 0.0031330000 0.0000010000 0.0000040000 0.0011620000 34926109 96830484 509673472 3.9952955246 3.9733216763 3.9432132244 37 1311867171.6622560024 0.0605893955 0.0609264085 0.0628964603 0.0086032929 0.0066130000 0.0004120000 0.0034950000 0.0000040000 0.0000030000 0.0021500000 34929893 96830484 509673472 3.9916267395 3.9727754593 3.9424490929 38 1311867171.6943440437 0.0612231456 0.0609342174 0.0628964603 0.0087735289 0.0052270000 0.0004100000 0.0031230000 0.0000000000 0.0000030000 0.0011430000 34933509 96830484 509673472 3.9922935963 3.9735369682 3.9422614574 39 1311867171.7262439728 0.0611792952 0.0609405014 0.0628964603 0.0086862684 0.0069900000 0.0004100000 0.0045960000 0.0000040000 0.0000040000 0.0014300000 34937237 96830484 509673472 3.9922668934 3.9728963375 3.9418635368 40 1311867171.7621190548 0.0614394918 0.0609529762 0.0628964603 0.0085988770 0.0052320000 0.0004080000 0.0031340000 0.0000010000 0.0000040000 0.0011360000 34941021 96830484 509673472 3.9937579632 3.9712598324 3.9414825439 41 1311867171.7941710949 0.0609960221 0.0609540261 0.0628964603 0.0085926179 0.0077150000 0.0004060000 0.0046060000 0.0000030000 0.0000030000 0.0021480000 34944637 96830484 509673472 3.9931714535 3.9692866802 3.9404478073 42 1311867171.8262550831 0.0613914765 0.0609644415 0.0628964603 0.0085122294 0.0067090000 0.0003970000 0.0046120000 0.0000010000 0.0000030000 0.0011490000 34948365 96830484 509673472 3.9928753376 3.9690339565 3.9393236637 43 1311867171.8623590469 0.0609233789 0.0609634866 0.0628964603 0.0084161766 0.0055030000 0.0003990000 0.0031180000 0.0000040000 0.0000040000 0.0014320000 34952149 96830484 509673472 3.9888582230 3.9687423706 3.9379642010 44 1311867171.8944430351 0.0605693236 0.0609545284 0.0628964603 0.0085263041 0.0079960000 0.0005930000 0.0035860000 0.0000020000 0.0000170000 0.0016720000 34955821 96830484 509673472 3.9858267307 3.9683175087 3.9371459484 45 1311867171.9262220860 0.0615006573 0.0609666646 0.0628964603 0.0084614188 0.0069320000 0.0005170000 0.0029710000 0.0000090000 0.0000070000 0.0023070000 34959493 96830484 509673472 3.9849169254 3.9696800709 3.9369018078 46 1311867171.9624669552 0.0616435930 0.0609813804 0.0628964603 0.0084028963 0.0069420000 0.0004470000 0.0046520000 0.0000010000 0.0000050000 0.0011530000 34963277 96830484 509673472 3.9828529358 3.9694175720 3.9368674755 47 1311867171.9946711063 0.0619901568 0.0610028437 0.0628964603 0.0084643592 0.0055460000 0.0004110000 0.0031370000 0.0000030000 0.0000030000 0.0014250000 34966949 96830484 509673472 3.9826195240 3.9692623615 3.9370539188 48 1311867172.0262680054 0.0626841038 0.0610378700 0.0628964603 0.0085240266 0.0059360000 0.0004070000 0.0038440000 0.0000010000 0.0000030000 0.0011360000 34970621 96830484 509673472 3.9832072258 3.9691314697 3.9375071526 49 1311867172.0622880459 0.0630630553 0.0610792003 0.0630630553 0.0084651369 0.0076450000 0.0004070000 0.0045650000 0.0000040000 0.0000030000 0.0021150000 34974405 96830484 509673472 3.9815318584 3.9699490070 3.9382374287 50 1311867172.0941960812 0.0632718727 0.0611230537 0.0632718727 0.0084486043 0.0054600000 0.0004110000 0.0034660000 0.0000010000 0.0000040000 0.0011220000 34978077 96830484 509673472 3.9807801247 3.9696555138 3.9387965202 51 1311867172.1263689995 0.0637577474 0.0611747144 0.0637577474 0.0084525234 0.0053670000 0.0004130000 0.0031100000 0.0000050000 0.0000030000 0.0013930000 34981749 96830484 509673472 3.9780061245 3.9700372219 3.9398126602 52 1311867172.1623349190 0.0626572818 0.0612032253 0.0637577474 0.0084112287 0.0058160000 0.0004090000 0.0038450000 0.0000000000 0.0000030000 0.0011190000 34985533 96830484 509673472 3.9731960297 3.9699573517 3.9402027130 53 1311867172.1944270134 0.0616274700 0.0612112299 0.0637577474 0.0083624669 0.0085750000 0.0006020000 0.0035310000 0.0000150000 0.0000150000 0.0027420000 34989205 96830484 509673472 3.9676141739 3.9710235596 3.9405820370 54 1311867172.2264409065 0.0615979098 0.0612183907 0.0637577474 0.0085073720 0.0070970000 0.0004650000 0.0047230000 0.0000000000 0.0000060000 0.0011800000 34992877 96830484 509673472 3.9637224674 3.9708914757 3.9409677982 55 1311867172.2622280121 0.0611097924 0.0612164161 0.0637577474 0.0084387835 0.0069500000 0.0004280000 0.0045970000 0.0000050000 0.0000040000 0.0014210000 34996661 96830484 509673472 3.9607932568 3.9717509747 3.9413547516 56 1311867172.2944829464 0.0612971485 0.0612178578 0.0637577474 0.0083772122 0.0074420000 0.0005070000 0.0047870000 0.0000010000 0.0000070000 0.0012500000 35000333 96830484 509673472 3.9581859112 3.9725575447 3.9417734146 57 1311867172.3263380527 0.0608499125 0.0612114026 0.0637577474 0.0083477459 0.0077160000 0.0004350000 0.0046160000 0.0000060000 0.0000040000 0.0020980000 35004005 96830484 509673472 3.9550111294 3.9723889828 3.9422457218 58 1311867172.3624010086 0.0609846711 0.0612074934 0.0637577474 0.0082953492 0.0051080000 0.0004150000 0.0031070000 0.0000010000 0.0000040000 0.0011160000 35007789 96830484 509673472 3.9512674809 3.9734699726 3.9424097538 59 1311867172.3942890167 0.0598596819 0.0611846492 0.0637577474 0.0082383493 0.0091300000 0.0006130000 0.0050480000 0.0000180000 0.0000140000 0.0021420000 35011461 96830484 509673472 3.9469454288 3.9733080864 3.9423053265 60 1311867172.4265220165 0.0596610494 0.0611592559 0.0637577474 0.0082908146 0.0057650000 0.0005320000 0.0032650000 0.0000000000 0.0000070000 0.0011930000 35015133 96830484 509673472 3.9418118000 3.9735550880 3.9418115616 61 1311867172.4623498917 0.0591398403 0.0611261507 0.0637577474 0.0082664749 0.0069870000 0.0004810000 0.0038780000 0.0000050000 0.0000050000 0.0021020000 35018917 96830484 509673472 3.9385046959 3.9727995396 3.9413874149 62 1311867172.4952669144 0.0595760904 0.0611011497 0.0637577474 0.0083038217 0.0043740000 0.0004100000 0.0023830000 0.0000000000 0.0000030000 0.0011170000 35022533 96830484 509673472 3.9373388290 3.9733445644 3.9412674904 63 1311867172.5263059139 0.0592489541 0.0610717498 0.0637577474 0.0082500636 0.0077770000 0.0005780000 0.0035340000 0.0000150000 0.0000160000 0.0019040000 35026205 96830484 509673472 3.9349291325 3.9717116356 3.9406616688 64 1311867172.5624930859 0.0588418916 0.0610369082 0.0637577474 0.0081993709 0.0054640000 0.0004830000 0.0029050000 0.0000010000 0.0000080000 0.0012580000 35029989 96830484 509673472 3.9305922985 3.9709236622 3.9400775433 65 1311867172.5945439339 0.0596781150 0.0610160037 0.0637577474 0.0082036329 0.0073770000 0.0004330000 0.0042510000 0.0000050000 0.0000050000 0.0021100000 35039749 96830484 509673472 3.9334201813 3.9711177349 3.9393708706 66 1311867172.6263699532 0.0593872145 0.0609913251 0.0637577474 0.0081780870 0.0055040000 0.0005080000 0.0028150000 0.0000010000 0.0000110000 0.0012500000 35056277 96830484 509673472 3.9303703308 3.9711251259 3.9385797977 67 1311867172.6624419689 0.0592238568 0.0609649450 0.0637577474 0.0081196619 0.0055190000 0.0004510000 0.0028350000 0.0000060000 0.0000050000 0.0014630000 35060061 96830484 509673472 3.9275341034 3.9713242054 3.9379885197 68 1311867172.6945450306 0.0590699762 0.0609370778 0.0637577474 0.0081848771 0.0087120000 0.0006210000 0.0050470000 0.0000020000 0.0000180000 0.0016420000 35063733 96830484 509673472 3.9258546829 3.9711468220 3.9375226498 69 1311867172.7263929844 0.0594129525 0.0609149890 0.0637577474 0.0081567831 0.0070460000 0.0004700000 0.0035910000 0.0000060000 0.0000060000 0.0022100000 35067405 96830484 509673472 3.9233510494 3.9712176323 3.9371755123 70 1311867172.7623739243 0.0597391129 0.0608981908 0.0637577474 0.0081148060 0.0056760000 0.0004350000 0.0035160000 0.0000000000 0.0000040000 0.0011350000 35071189 96830484 509673472 3.9206831455 3.9724926949 3.9369637966 71 1311867172.7944509983 0.0589739382 0.0608710886 0.0637577474 0.0080623809 0.0070610000 0.0005150000 0.0037170000 0.0000110000 0.0000090000 0.0016550000 35074805 96830484 509673472 3.9160063267 3.9716730118 3.9364054203 72 1311867172.8263089657 0.0594245233 0.0608509975 0.0637577474 0.0080262576 0.0051600000 0.0004570000 0.0028540000 0.0000000000 0.0000060000 0.0011700000 35078533 96830484 509673472 3.9132046700 3.9718430042 3.9355020523 73 1311867172.8632309437 0.0592925325 0.0608296486 0.0637577474 0.0079904506 0.0077120000 0.0004310000 0.0046210000 0.0000050000 0.0000050000 0.0021010000 35082373 96830484 509673472 3.9103691578 3.9712569714 3.9346945286 74 1311867172.8944649696 0.0586254746 0.0607998625 0.0637577474 0.0079366560 0.0074830000 0.0005150000 0.0044880000 0.0000010000 0.0000100000 0.0013880000 35085933 96830484 509673472 3.9072580338 3.9710249901 3.9340236187 75 1311867172.9263219833 0.0582592636 0.0607659878 0.0637577474 0.0078837383 0.0057860000 0.0004600000 0.0032130000 0.0000060000 0.0000050000 0.0014340000 35089661 96830484 509673472 3.9041235447 3.9702072144 3.9334352016 76 1311867172.9623310566 0.0580770373 0.0607306069 0.0637577474 0.0078323723 0.0072010000 0.0005950000 0.0039560000 0.0000010000 0.0000160000 0.0013840000 35093445 96830484 509673472 3.9025301933 3.9699087143 3.9327597618 77 1311867172.9945271015 0.0584781431 0.0607013541 0.0637577474 0.0078111621 0.0080050000 0.0004710000 0.0047300000 0.0000060000 0.0000060000 0.0021260000 35097061 96830484 509673472 3.9040038586 3.9697415829 3.9322490692 78 1311867173.0262629986 0.0575019941 0.0606603367 0.0637577474 0.0077735481 0.0069320000 0.0004470000 0.0046840000 0.0000010000 0.0000050000 0.0011500000 35100733 96830484 509673472 3.8992249966 3.9692816734 3.9320385456 79 1311867173.0624630451 0.0575703718 0.0606212232 0.0637577474 0.0077283407 0.0078940000 0.0005080000 0.0048740000 0.0000070000 0.0000070000 0.0015350000 35104517 96830484 509673472 3.8989999294 3.9687919617 3.9317200184 80 1311867173.0945179462 0.0580102205 0.0605885857 0.0637577474 0.0077105846 0.0054770000 0.0004520000 0.0031900000 0.0000000000 0.0000050000 0.0011490000 35108189 96830484 509673472 3.8984663486 3.9687352180 3.9317715168 81 1311867173.1267819405 0.0577806979 0.0605539204 0.0637577474 0.0076826849 0.0084740000 0.0005090000 0.0048410000 0.0000070000 0.0000080000 0.0022530000 35111917 96830484 509673472 3.8967058659 3.9687793255 3.9315271378 82 1311867173.1622309685 0.0582025051 0.0605252446 0.0637577474 0.0076704786 0.0053490000 0.0004350000 0.0031720000 0.0000010000 0.0000050000 0.0011380000 35115701 96830484 509673472 3.8968162537 3.9697999954 3.9316177368 83 1311867173.1943008900 0.0585988648 0.0605020352 0.0637577474 0.0076244638 0.0069290000 0.0004190000 0.0045900000 0.0000040000 0.0000040000 0.0014080000 35119317 96830484 509673472 3.8961222172 3.9703371525 3.9316987991 84 1311867173.2264449596 0.0575960167 0.0604674397 0.0637577474 0.0075848757 0.0055090000 0.0004190000 0.0034820000 0.0000000000 0.0000030000 0.0011110000 35122989 96830484 509673472 3.8910253048 3.9698231220 3.9317402840 85 1311867173.2622020245 0.0589039922 0.0604490462 0.0637577474 0.0075444558 0.0075500000 0.0004160000 0.0045610000 0.0000040000 0.0000030000 0.0020680000 35126773 96830484 509673472 3.8931634426 3.9705581665 3.9319744110 86 1311867173.2942678928 0.0589665920 0.0604318084 0.0637577474 0.0075005744 0.0066340000 0.0004240000 0.0045740000 0.0000010000 0.0000030000 0.0011120000 35130389 96830484 509673472 3.8908131123 3.9703872204 3.9320144653 87 1311867173.3262879848 0.0585580468 0.0604102709 0.0637577474 0.0075056018 0.0069070000 0.0004190000 0.0045870000 0.0000040000 0.0000030000 0.0013880000 35134061 96830484 509673472 3.8877170086 3.9690959454 3.9320204258 88 1311867173.3623280525 0.0584996492 0.0603885593 0.0637577474 0.0074629774 0.0077180000 0.0005900000 0.0035500000 0.0000020000 0.0000160000 0.0016430000 35137901 96830484 509673472 3.8851072788 3.9691021442 3.9319217205 89 1311867173.3942871094 0.0580370165 0.0603621375 0.0637577474 0.0074311201 0.0082660000 0.0004780000 0.0048090000 0.0000070000 0.0000050000 0.0021440000 35141517 96830484 509673472 3.8817796707 3.9692578316 3.9317965508 90 1311867173.4262790680 0.0577495731 0.0603331090 0.0637577474 0.0074131959 0.0050170000 0.0004460000 0.0028150000 0.0000010000 0.0000050000 0.0011340000 35145189 96830484 509673472 3.8794896603 3.9691517353 3.9315094948 91 1311867173.4622900486 0.0571256988 0.0602978627 0.0637577474 0.0073989460 0.0079310000 0.0005130000 0.0048820000 0.0000080000 0.0000070000 0.0015150000 35148973 96830484 509673472 3.8764684200 3.9686400890 3.9310812950 92 1311867173.4943389893 0.0578684770 0.0602714564 0.0637577474 0.0074551921 0.0061920000 0.0004540000 0.0039470000 0.0000010000 0.0000050000 0.0011650000 35152645 96830484 509673472 3.8755378723 3.9682328701 3.9305660725 93 1311867173.5263900757 0.0575688183 0.0602423957 0.0637577474 0.0074174477 0.0070920000 0.0005160000 0.0033320000 0.0000070000 0.0000070000 0.0022470000 35156373 96830484 509673472 3.8731749058 3.9677689075 3.9301288128 94 1311867173.5624370575 0.0574184135 0.0602123534 0.0637577474 0.0073972584 0.0069500000 0.0004450000 0.0045830000 0.0000000000 0.0000040000 0.0011170000 35160157 96830484 509673472 3.8714122772 3.9680020809 3.9299952984 95 1311867173.5943109989 0.0574446805 0.0601832200 0.0637577474 0.0073860264 0.0059210000 0.0004130000 0.0034410000 0.0000040000 0.0000040000 0.0014010000 35163773 96830484 509673472 3.8687539101 3.9682145119 3.9296784401 96 1311867173.6263959408 0.0564535148 0.0601443689 0.0637577474 0.0073598886 0.0066940000 0.0004070000 0.0045220000 0.0000010000 0.0000040000 0.0011270000 35167445 96830484 509673472 3.8647358418 3.9674725533 3.9291656017 97 1311867173.6623299122 0.0572960302 0.0601150046 0.0637577474 0.0073273793 0.0094990000 0.0005960000 0.0049630000 0.0000100000 0.0000100000 0.0024100000 35171229 96830484 509673472 3.8653810024 3.9680862427 3.9287612438 98 1311867173.6943540573 0.0578030758 0.0600914134 0.0637577474 0.0072930183 0.0077830000 0.0005150000 0.0047380000 0.0000010000 0.0000080000 0.0012480000 35174901 96830484 509673472 3.8647260666 3.9680962563 3.9283313751 99 1311867173.7267971039 0.0568078421 0.0600582461 0.0637577474 0.0072938537 0.0054380000 0.0004350000 0.0027750000 0.0000050000 0.0000050000 0.0014180000 35178629 96830484 509673472 3.8594048023 3.9674184322 3.9273953438 100 1311867173.7623970509 0.0574068166 0.0600317318 0.0637577474 0.0072720450 0.0067350000 0.0004130000 0.0045330000 0.0000000000 0.0000040000 0.0011150000 35182413 96830484 509673472 3.8598110676 3.9679677486 3.9268794060 101 1311867173.7943561077 0.0578246005 0.0600098790 0.0637577474 0.0072396336 0.0076230000 0.0004060000 0.0045040000 0.0000030000 0.0000030000 0.0020580000 35185973 96830484 509673472 3.8589994907 3.9682583809 3.9263858795 102 1311867173.8265669346 0.0570794754 0.0599811495 0.0637577474 0.0072066602 0.0066740000 0.0004040000 0.0045110000 0.0000000000 0.0000040000 0.0011120000 35189701 96830484 509673472 3.8559322357 3.9667279720 3.9253532887 103 1311867173.8635799885 0.0576790385 0.0599587989 0.0637577474 0.0072057408 0.0054990000 0.0004080000 0.0030580000 0.0000040000 0.0000030000 0.0013750000 35193429 96830484 509673472 3.8541846275 3.9677591324 3.9248888493 104 1311867173.8946080208 0.0578815192 0.0599388251 0.0637577474 0.0071745285 0.0063270000 0.0004100000 0.0041340000 0.0000010000 0.0000040000 0.0011160000 35197101 96830484 509673472 3.8540163040 3.9673402309 3.9240922928 105 1311867173.9266970158 0.0567950085 0.0599088840 0.0637577474 0.0071477398 0.0068950000 0.0004060000 0.0037990000 0.0000030000 0.0000030000 0.0020370000 35200829 96830484 509673472 3.8498871326 3.9668931961 3.9229803085 106 1311867173.9625461102 0.0570135266 0.0598815693 0.0637577474 0.0071499078 0.0074780000 0.0006010000 0.0027090000 0.0000020000 0.0000160000 0.0016410000 35204613 96830484 509673472 3.8477575779 3.9680867195 3.9225807190 107 1311867173.9944310188 0.0575681366 0.0598599484 0.0637577474 0.0071346309 0.0066240000 0.0005160000 0.0032710000 0.0000100000 0.0000070000 0.0015060000 35208229 96830484 509673472 3.8487575054 3.9683182240 3.9220459461 108 1311867174.0264260769 0.0566341728 0.0598300801 0.0637577474 0.0072149750 0.0069860000 0.0004470000 0.0045810000 0.0000010000 0.0000060000 0.0011430000 35211901 96830484 509673472 3.8441214561 3.9667611122 3.9209406376 109 1311867174.0624630451 0.0573899075 0.0598076932 0.0637577474 0.0071891030 0.0076530000 0.0004090000 0.0045080000 0.0000040000 0.0000040000 0.0020450000 35215685 96830484 509673472 3.8460204601 3.9672348499 3.9204835892 110 1311867174.0945188999 0.0590073392 0.0598004173 0.0637577474 0.0071670134 0.0068320000 0.0005120000 0.0037270000 0.0000000000 0.0000080000 0.0012490000 35219357 96830484 509673472 3.8467373848 3.9684255123 3.9209423065 111 1311867174.1264541149 0.0583415553 0.0597872744 0.0637577474 0.0071501297 0.0072550000 0.0004520000 0.0045830000 0.0000060000 0.0000050000 0.0013860000 35223029 96830484 509673472 3.8435299397 3.9667100906 3.9200704098 112 1311867174.1624329090 0.0585765280 0.0597764641 0.0637577474 0.0071482622 0.0053590000 0.0004260000 0.0030830000 0.0000000000 0.0000040000 0.0011200000 35226813 96830484 509673472 3.8408043385 3.9674162865 3.9199702740 113 1311867174.1943979263 0.0595370643 0.0597743456 0.0637577474 0.0071377243 0.0065610000 0.0004180000 0.0034140000 0.0000030000 0.0000030000 0.0020350000 35230485 96830484 509673472 3.8417639732 3.9687635899 3.9202756882 114 1311867174.2267580032 0.0586235262 0.0597642507 0.0637577474 0.0071159945 0.0049060000 0.0004130000 0.0027050000 0.0000000000 0.0000030000 0.0011110000 35234213 96830484 509673472 3.8371002674 3.9668674469 3.9199421406 115 1311867174.2626769543 0.0586367361 0.0597544462 0.0637577474 0.0070850991 0.0062710000 0.0004110000 0.0038040000 0.0000040000 0.0000030000 0.0013800000 35237941 96830484 509673472 3.8343393803 3.9667532444 3.9197421074 116 1311867174.2945280075 0.0598609857 0.0597553646 0.0637577474 0.0070664429 0.0067090000 0.0004130000 0.0045160000 0.0000000000 0.0000040000 0.0011070000 35241613 96830484 509673472 3.8349862099 3.9675159454 3.9196453094 117 1311867174.3265740871 0.0585864410 0.0597453738 0.0637577474 0.0070383912 0.0058000000 0.0004100000 0.0027050000 0.0000030000 0.0000030000 0.0020090000 35245285 96830484 509673472 3.8305757046 3.9666721821 3.9187395573 118 1311867174.3624329567 0.0584115162 0.0597340699 0.0637577474 0.0070161831 0.0049200000 0.0004110000 0.0027190000 0.0000010000 0.0000040000 0.0011040000 35249125 96830484 509673472 3.8273510933 3.9675929546 3.9189102650 119 1311867174.3946359158 0.0590554178 0.0597283670 0.0637577474 0.0070160394 0.0077370000 0.0004220000 0.0051010000 0.0000040000 0.0000030000 0.0013840000 35252741 96830484 509673472 3.8264915943 3.9688477516 3.9190454483 120 1311867174.4266788960 0.0587112941 0.0597198914 0.0637577474 0.0069921537 0.0085530000 0.0006190000 0.0034850000 0.0000010000 0.0000150000 0.0018010000 35256469 96830484 509673472 3.8230154514 3.9683203697 3.9189977646 121 1311867174.4630160332 0.0581621565 0.0597070175 0.0637577474 0.0069800439 0.0076880000 0.0004740000 0.0039660000 0.0000060000 0.0000060000 0.0021190000 35260197 96830484 509673472 3.8200304508 3.9676721096 3.9188086987 122 1311867174.4945669174 0.0592420697 0.0597032065 0.0637577474 0.0069521615 0.0057900000 0.0004280000 0.0034800000 0.0000000000 0.0000040000 0.0011240000 35263869 96830484 509673472 3.8213641644 3.9686348438 3.9189791679 123 1311867174.5267519951 0.0586431921 0.0596945885 0.0637577474 0.0069369162 0.0066140000 0.0004100000 0.0041600000 0.0000040000 0.0000030000 0.0013660000 35267597 96830484 509673472 3.8180158138 3.9680442810 3.9187803268 124 1311867174.5623500347 0.0582667328 0.0596830735 0.0637577474 0.0069479701 0.0074990000 0.0004700000 0.0047250000 0.0000010000 0.0000070000 0.0011810000 35271381 96830484 509673472 3.8148062229 3.9674873352 3.9187946320 125 1311867174.5944879055 0.0586831868 0.0596750744 0.0637577474 0.0069418595 0.0067470000 0.0005090000 0.0028350000 0.0000080000 0.0000080000 0.0022500000 35274997 96830484 509673472 3.8145186901 3.9690039158 3.9190835953 126 1311867174.6265459061 0.0587533452 0.0596677591 0.0637577474 0.0069207156 0.0069870000 0.0004370000 0.0045790000 0.0000010000 0.0000050000 0.0011230000 35278669 96830484 509673472 3.8111238480 3.9694685936 3.9196407795 127 1311867174.6624910831 0.0581241623 0.0596556048 0.0637577474 0.0068994012 0.0070160000 0.0004170000 0.0045250000 0.0000030000 0.0000030000 0.0013830000 35282453 96830484 509673472 3.8073427677 3.9683637619 3.9196870327 128 1311867174.6945910454 0.0587962978 0.0596488915 0.0637577474 0.0068976458 0.0088330000 0.0006400000 0.0049960000 0.0000010000 0.0000100000 0.0013830000 35286125 96830484 509673472 3.8070576191 3.9702293873 3.9203555584 129 1311867174.7265629768 0.0591082610 0.0596447005 0.0637577474 0.0069030138 0.0070190000 0.0004500000 0.0035300000 0.0000070000 0.0000060000 0.0020630000 35302029 96830484 509673472 3.8038132191 3.9701642990 3.9207525253 130 1311867174.7623760700 0.0585926957 0.0596366082 0.0637577474 0.0069037353 0.0054630000 0.0004260000 0.0031240000 0.0000000000 0.0000040000 0.0011350000 35331469 96830484 509673472 3.7996220589 3.9672796726 3.9206836224 131 1311867174.7944738865 0.0588086285 0.0596302877 0.0637577474 0.0068795077 0.0058820000 0.0004100000 0.0034270000 0.0000040000 0.0000030000 0.0013560000 35335029 96830484 509673472 3.8008141518 3.9683408737 3.9202239513 132 1311867174.8273398876 0.0587719530 0.0596237852 0.0637577474 0.0068546051 0.0067640000 0.0004090000 0.0045160000 0.0000010000 0.0000040000 0.0011100000 35338757 96830484 509673472 3.7979240417 3.9676134586 3.9202442169 133 1311867174.8624229431 0.0576086752 0.0596086340 0.0637577474 0.0068330519 0.0061980000 0.0004150000 0.0030670000 0.0000040000 0.0000030000 0.0020230000 35342541 96830484 509673472 3.7947576046 3.9672920704 3.9191060066 134 1311867174.8944199085 0.0568479337 0.0595880318 0.0637577474 0.0068255603 0.0083030000 0.0005830000 0.0038840000 0.0000020000 0.0000160000 0.0016720000 35346157 96830484 509673472 3.7914390564 3.9691376686 3.9182305336 135 1311867174.9270179272 0.0568257235 0.0595675702 0.0637577474 0.0068186860 0.0075810000 0.0005090000 0.0043670000 0.0000080000 0.0000080000 0.0015190000 35349885 96830484 509673472 3.7904198170 3.9684202671 3.9177308083 136 1311867174.9626429081 0.0571254455 0.0595496134 0.0637577474 0.0068028251 0.0064950000 0.0005270000 0.0032980000 0.0000010000 0.0000070000 0.0012640000 35353669 96830484 509673472 3.7908852100 3.9681277275 3.9168889523 137 1311867174.9943349361 0.0565228164 0.0595275200 0.0637577474 0.0068132426 0.0080200000 0.0004540000 0.0046220000 0.0000060000 0.0000050000 0.0020670000 35357285 96830484 509673472 3.7861692905 3.9690084457 3.9163672924 138 1311867175.0265510082 0.0573677793 0.0595118697 0.0637577474 0.0068453952 0.0053550000 0.0004180000 0.0031030000 0.0000000000 0.0000030000 0.0011190000 35361013 96830484 509673472 3.7853596210 3.9726111889 3.9166469574 139 1311867175.0633120537 0.0569303557 0.0594932977 0.0637577474 0.0068221116 0.0079130000 0.0005150000 0.0044360000 0.0000080000 0.0000070000 0.0015200000 35364797 96830484 509673472 3.7810542583 3.9713470936 3.9167153835 140 1311867175.0947189331 0.0556246266 0.0594656643 0.0637577474 0.0068175598 0.0071050000 0.0004620000 0.0046310000 0.0000000000 0.0000050000 0.0011320000 35368469 96830484 509673472 3.7695028782 3.9731397629 3.9162249565 141 1311867175.1265308857 0.0559683405 0.0594408606 0.0637577474 0.0068047839 0.0077290000 0.0004180000 0.0045550000 0.0000040000 0.0000030000 0.0020480000 35372141 96830484 509673472 3.7715828419 3.9735109806 3.9168913364 142 1311867175.1625180244 0.0562458262 0.0594183603 0.0637577474 0.0068141082 0.0060310000 0.0004120000 0.0038200000 0.0000010000 0.0000030000 0.0011020000 35375925 96830484 509673472 3.7706353664 3.9732284546 3.9173333645 143 1311867175.1946399212 0.0561625399 0.0593955924 0.0637577474 0.0067939638 0.0072320000 0.0005860000 0.0031130000 0.0000150000 0.0000160000 0.0016340000 35379541 96830484 509673472 3.7684998512 3.9729716778 3.9174847603 144 1311867175.2270050049 0.0558439456 0.0593709282 0.0637577474 0.0068443934 0.0072640000 0.0004500000 0.0046670000 0.0000010000 0.0000060000 0.0011510000 35383269 96830484 509673472 3.7658009529 3.9744892120 3.9181044102 145 1311867175.2624669075 0.0559854396 0.0593475800 0.0637577474 0.0068518995 0.0070480000 0.0004260000 0.0038460000 0.0000040000 0.0000040000 0.0020030000 35386997 96830484 509673472 3.7663865089 3.9758076668 3.9181706905 146 1311867175.2944509983 0.0558440126 0.0593235829 0.0637577474 0.0068509526 0.0049840000 0.0004150000 0.0027410000 0.0000000000 0.0000030000 0.0011210000 35390669 96830484 509673472 3.7597634792 3.9758141041 3.9187920094 147 1311867175.3267059326 0.0557511784 0.0592992809 0.0637577474 0.0068292646 0.0075740000 0.0005210000 0.0040910000 0.0000100000 0.0000090000 0.0014960000 35394397 96830484 509673472 3.7616651058 3.9775178432 3.9196035862 148 1311867175.3625650406 0.0566780940 0.0592815701 0.0637577474 0.0068530447 0.0064370000 0.0004560000 0.0039030000 0.0000000000 0.0000050000 0.0011270000 35398125 96830484 509673472 3.7566528320 3.9765651226 3.9204177856 149 1311867175.3945989609 0.0564483777 0.0592625554 0.0637577474 0.0068447124 0.0057880000 0.0004870000 0.0023850000 0.0000040000 0.0000030000 0.0020190000 35401797 96830484 509673472 3.7568316460 3.9759130478 3.9204194546 150 1311867175.4266059399 0.0568273179 0.0592463205 0.0637577474 0.0068322774 0.0094780000 0.0006490000 0.0050610000 0.0000020000 0.0000170000 0.0016430000 35405469 96830484 509673472 3.7502093315 3.9772038460 3.9211165905 151 1311867175.4625999928 0.0565683804 0.0592285858 0.0637577474 0.0068266783 0.0076310000 0.0004800000 0.0047010000 0.0000060000 0.0000060000 0.0014220000 35409309 96830484 509673472 3.7487766743 3.9770450592 3.9212799072 152 1311867175.4945731163 0.0569883212 0.0592138472 0.0637577474 0.0068124430 0.0080960000 0.0005380000 0.0048260000 0.0000010000 0.0000080000 0.0012530000 35412981 96830484 509673472 3.7432794571 3.9772000313 3.9217386246 153 1311867175.5264270306 0.0577878691 0.0592045271 0.0637577474 0.0068159016 0.0080290000 0.0004410000 0.0046360000 0.0000050000 0.0000050000 0.0020400000 35416597 96830484 509673472 3.7386081219 3.9779498577 3.9220488071 154 1311867175.5625700951 0.0572768487 0.0591920097 0.0637577474 0.0068397502 0.0068280000 0.0004250000 0.0045700000 0.0000000000 0.0000040000 0.0011090000 35420437 96830484 509673472 3.7366914749 3.9784944057 3.9221930504 155 1311867175.5946640968 0.0581699945 0.0591854161 0.0637577474 0.0068727978 0.0079910000 0.0005160000 0.0044940000 0.0000080000 0.0000070000 0.0015050000 35424053 96830484 509673472 3.7346920967 3.9798607826 3.9225594997 156 1311867175.6264801025 0.0577352531 0.0591761201 0.0637577474 0.0068804880 0.0057960000 0.0004570000 0.0031770000 0.0000010000 0.0000060000 0.0011340000 35427725 96830484 509673472 3.7307281494 3.9798533916 3.9227101803 157 1311867175.6624929905 0.0585139580 0.0591719025 0.0637577474 0.0069374248 0.0054860000 0.0004250000 0.0023960000 0.0000040000 0.0000040000 0.0020210000 35431509 96830484 509673472 3.7309486866 3.9813790321 3.9231522083 158 1311867175.6947000027 0.0583333187 0.0591665951 0.0637577474 0.0069406391 0.0067230000 0.0004240000 0.0045670000 0.0000000000 0.0000040000 0.0011100000 35435181 96830484 509673472 3.7281014919 3.9804604053 3.9232361317 159 1311867175.7273120880 0.0588349327 0.0591645091 0.0637577474 0.0069304400 0.0084040000 0.0006170000 0.0035060000 0.0000150000 0.0000150000 0.0019010000 35438909 96830484 509673472 3.7254810333 3.9800164700 3.9235537052 160 1311867175.7624969482 0.0590280518 0.0591636563 0.0637577474 0.0069313748 0.0074290000 0.0004810000 0.0047490000 0.0000010000 0.0000070000 0.0011900000 35442693 96830484 509673472 3.7214353085 3.9807789326 3.9235339165 161 1311867175.7948620319 0.0592168160 0.0591639865 0.0637577474 0.0069392740 0.0071460000 0.0005360000 0.0033010000 0.0000070000 0.0000070000 0.0022010000 35446309 96830484 509673472 3.7187461853 3.9798445702 3.9235744476 162 1311867175.8287971020 0.0594024919 0.0591654587 0.0637577474 0.0069290441 0.0055220000 0.0004510000 0.0031700000 0.0000010000 0.0000050000 0.0011290000 35450093 96830484 509673472 3.7145383358 3.9787149429 3.9233865738 163 1311867175.8625519276 0.0595644526 0.0591679065 0.0637577474 0.0069490254 0.0059630000 0.0004370000 0.0034940000 0.0000040000 0.0000040000 0.0013800000 35453821 96830484 509673472 3.7131619453 3.9804272652 3.9233534336 164 1311867175.8946080208 0.0598671399 0.0591721701 0.0637577474 0.0069355109 0.0067620000 0.0004300000 0.0045600000 0.0000000000 0.0000040000 0.0011160000 35457437 96830484 509673472 3.7105743885 3.9806568623 3.9229016304 165 1311867175.9282429218 0.0596230365 0.0591749027 0.0637577474 0.0069361429 0.0076240000 0.0004290000 0.0045440000 0.0000030000 0.0000030000 0.0020230000 35461165 96830484 509673472 3.7058129311 3.9796054363 3.9223577976 166 1311867175.9629371166 0.0601696745 0.0591808953 0.0637577474 0.0069169422 0.0049290000 0.0004330000 0.0027220000 0.0000010000 0.0000050000 0.0011200000 35464893 96830484 509673472 3.7028191090 3.9799289703 3.9225363731 167 1311867175.9983000755 0.0602542982 0.0591873228 0.0637577474 0.0069290742 0.0051520000 0.0004220000 0.0027130000 0.0000040000 0.0000040000 0.0013770000 35468621 96830484 509673472 3.7022147179 3.9811637402 3.9223587513 168 1311867176.0268509388 0.0608780906 0.0591973869 0.0637577474 0.0069150130 0.0082030000 0.0005920000 0.0035290000 0.0000020000 0.0000150000 0.0016680000 35472181 96830484 509673472 3.6976473331 3.9791486263 3.9221167564 169 1311867176.0627059937 0.0605441593 0.0592053560 0.0637577474 0.0069334610 0.0088690000 0.0005300000 0.0048500000 0.0000100000 0.0000100000 0.0022160000 35475965 96830484 509673472 3.6931881905 3.9796335697 3.9216041565 170 1311867176.0946600437 0.0614908487 0.0592188001 0.0637577474 0.0069802034 0.0060600000 0.0004550000 0.0035590000 0.0000010000 0.0000050000 0.0011680000 35479581 96830484 509673472 3.6905205250 3.9805898666 3.9213216305 171 1311867176.1268119812 0.0614938773 0.0592321046 0.0637577474 0.0069624556 0.0067010000 0.0004340000 0.0042290000 0.0000040000 0.0000040000 0.0013920000 35483309 96830484 509673472 3.6917023659 3.9804010391 3.9204955101 172 1311867176.1625900269 0.0611436442 0.0592432182 0.0637577474 0.0070260694 0.0052720000 0.0004150000 0.0030990000 0.0000000000 0.0000040000 0.0011240000 35487093 96830484 509673472 3.6886413097 3.9809086323 3.9198961258 173 1311867176.1946918964 0.0615979694 0.0592568295 0.0637577474 0.0070644488 0.0065500000 0.0004190000 0.0034620000 0.0000030000 0.0000030000 0.0020220000 35490765 96830484 509673472 3.6877567768 3.9812715054 3.9191629887 174 1311867176.2265360355 0.0616783500 0.0592707463 0.0637577474 0.0070451546 0.0060220000 0.0004160000 0.0038480000 0.0000010000 0.0000040000 0.0011180000 35494437 96830484 509673472 3.6851911545 3.9816446304 3.9187550545 175 1311867176.2625019550 0.0617401376 0.0592848571 0.0637577474 0.0070323221 0.0055430000 0.0004200000 0.0030970000 0.0000030000 0.0000030000 0.0013750000 35498221 96830484 509673472 3.6816439629 3.9821553230 3.9178876877 176 1311867176.2946109772 0.0621677786 0.0593012373 0.0637577474 0.0070273959 0.0059980000 0.0004160000 0.0038290000 0.0000010000 0.0000030000 0.0011070000 35501837 96830484 509673472 3.6787440777 3.9842076302 3.9174854755 177 1311867176.3266019821 0.0629064217 0.0593216056 0.0637577474 0.0070176718 0.0101230000 0.0006120000 0.0042890000 0.0000140000 0.0000130000 0.0027270000 35505509 96830484 509673472 3.6760869026 3.9866058826 3.9171867371 178 1311867176.3624560833 0.0631066486 0.0593428699 0.0637577474 0.0069998625 0.0060720000 0.0005320000 0.0028710000 0.0000010000 0.0000080000 0.0012660000 35509349 96830484 509673472 3.6750473976 3.9853043556 3.9163694382 179 1311867176.3952438831 0.0632266477 0.0593645670 0.0637577474 0.0069819634 0.0070870000 0.0004440000 0.0042600000 0.0000040000 0.0000040000 0.0014040000 35512965 96830484 509673472 3.6742818356 3.9867353439 3.9159069061 180 1311867176.4268360138 0.0630261749 0.0593849092 0.0637577474 0.0069688030 0.0068080000 0.0004200000 0.0045690000 0.0000010000 0.0000040000 0.0011290000 35516637 96830484 509673472 3.6731972694 3.9876923561 3.9152295589 181 1311867176.4629659653 0.0626756102 0.0594030899 0.0637577474 0.0070380576 0.0058150000 0.0004160000 0.0027210000 0.0000040000 0.0000030000 0.0020170000 35520421 96830484 509673472 3.6709725857 3.9875035286 3.9144165516 182 1311867176.4945809841 0.0635297075 0.0594257636 0.0637577474 0.0070339629 0.0079470000 0.0005180000 0.0048380000 0.0000010000 0.0000090000 0.0012550000 35524037 96830484 509673472 3.6688797474 3.9874629974 3.9135446548 183 1311867176.5266211033 0.0639399514 0.0594504313 0.0639399514 0.0070912782 0.0073060000 0.0004520000 0.0046250000 0.0000050000 0.0000050000 0.0014140000 35527765 96830484 509673472 3.6665670872 3.9897999763 3.9128189087 184 1311867176.5636389256 0.0640162155 0.0594752454 0.0640162155 0.0070852938 0.0080550000 0.0005510000 0.0048100000 0.0000010000 0.0000080000 0.0012730000 35531605 96830484 509673472 3.6647760868 3.9891290665 3.9120671749 185 1311867176.5946090221 0.0641046837 0.0595002694 0.0641046837 0.0070753577 0.0066990000 0.0004820000 0.0031610000 0.0000040000 0.0000040000 0.0020680000 35535221 96830484 509673472 3.6606109142 3.9890639782 3.9111316204 186 1311867176.6283841133 0.0637077093 0.0595228900 0.0641046837 0.0070654395 0.0078750000 0.0005260000 0.0044700000 0.0000020000 0.0000080000 0.0012930000 35538949 96830484 509673472 3.6598742008 3.9895942211 3.9103658199 187 1311867176.6625781059 0.0638261586 0.0595459021 0.0641046837 0.0070499710 0.0067610000 0.0004560000 0.0038830000 0.0000060000 0.0000050000 0.0014350000 35542677 96830484 509673472 3.6566646099 3.9905455112 3.9097344875 188 1311867176.6945180893 0.0632701367 0.0595657119 0.0641046837 0.0070334848 0.0081960000 0.0005150000 0.0048110000 0.0000010000 0.0000080000 0.0012930000 35546293 96830484 509673472 3.6558721066 3.9907469749 3.9086947441 189 1311867176.7265889645 0.0637772679 0.0595879953 0.0641046837 0.0070165365 0.0081190000 0.0004390000 0.0046290000 0.0000050000 0.0000040000 0.0020650000 35550021 96830484 509673472 3.6516697407 3.9915637970 3.9083724022 190 1311867176.7632329464 0.0635762289 0.0596089860 0.0641046837 0.0070120468 0.0069120000 0.0004190000 0.0045680000 0.0000010000 0.0000040000 0.0011410000 35553805 96830484 509673472 3.6510024071 3.9922585487 3.9080145359 191 1311867176.7947680950 0.0635117739 0.0596294194 0.0641046837 0.0070103982 0.0068020000 0.0004130000 0.0041890000 0.0000030000 0.0000030000 0.0013910000 35557421 96830484 509673472 3.6487154961 3.9922082424 3.9075140953 192 1311867176.8266770840 0.0638642982 0.0596514761 0.0641046837 0.0069928015 0.0049750000 0.0004110000 0.0026370000 0.0000010000 0.0000040000 0.0011090000 35561149 96830484 509673472 3.6454520226 3.9919810295 3.9071960449 193 1311867176.8627309799 0.0636807829 0.0596723533 0.0641046837 0.0069777154 0.0092800000 0.0005990000 0.0030010000 0.0000150000 0.0000140000 0.0027290000 35564933 96830484 509673472 3.6437606812 3.9931559563 3.9066402912 194 1311867176.8949549198 0.0640313551 0.0596948224 0.0641046837 0.0069606727 0.0067540000 0.0004620000 0.0038190000 0.0000010000 0.0000060000 0.0011710000 35568605 96830484 509673472 3.6391282082 3.9932906628 3.9064118862 195 1311867176.9268178940 0.0634560809 0.0597141109 0.0641046837 0.0069630050 0.0071410000 0.0004380000 0.0044470000 0.0000050000 0.0000050000 0.0013640000 35572277 96830484 509673472 3.6381256580 3.9932513237 3.9060437679 196 1311867176.9650609493 0.0637741387 0.0597348253 0.0641046837 0.0069757218 0.0066830000 0.0004020000 0.0044030000 0.0000010000 0.0000040000 0.0010990000 35576061 96830484 509673472 3.6360445023 3.9945266247 3.9060404301 197 1311867176.9947481155 0.0638701171 0.0597558166 0.0641046837 0.0069598440 0.0075650000 0.0004020000 0.0043980000 0.0000040000 0.0000040000 0.0019880000 35579677 96830484 509673472 3.6337573528 3.9948918819 3.9057564735 198 1311867177.0267279148 0.0642010719 0.0597782674 0.0642010719 0.0069451836 0.0066570000 0.0003980000 0.0043950000 0.0000000000 0.0000040000 0.0011120000 35583349 96830484 509673472 3.6303091049 3.9935972691 3.9054996967 199 1311867177.0626339912 0.0640844852 0.0597999067 0.0642010719 0.0069322102 0.0075250000 0.0004950000 0.0039100000 0.0000080000 0.0000070000 0.0015190000 35587133 96830484 509673472 3.6303141117 3.9948506355 3.9052336216 200 1311867177.0946850777 0.0638887137 0.0598203507 0.0642010719 0.0069176354 0.0051960000 0.0004170000 0.0026900000 0.0000010000 0.0000050000 0.0011330000 35590805 96830484 509673472 3.6280131340 3.9950532913 3.9046540260 201 1311867177.1266150475 0.0641462952 0.0598418729 0.0642010719 0.0069019182 0.0075920000 0.0004020000 0.0044080000 0.0000050000 0.0000040000 0.0019990000 35594477 96830484 509673472 3.6263492107 3.9943785667 3.9046247005 202 1311867177.1627299786 0.0642629415 0.0598637593 0.0642629415 0.0068863157 0.0066450000 0.0003980000 0.0043840000 0.0000000000 0.0000040000 0.0011150000 35598261 96830484 509673472 3.6238303185 3.9949815273 3.9045321941 203 1311867177.1946458817 0.0644952357 0.0598865745 0.0644952357 0.0068717377 0.0068680000 0.0003970000 0.0043730000 0.0000030000 0.0000030000 0.0013480000 35601933 96830484 509673472 3.6199085712 3.9958906174 3.9043800831 204 1311867177.2264730930 0.0648701414 0.0599110037 0.0648701414 0.0068560471 0.0066440000 0.0003930000 0.0044010000 0.0000000000 0.0000030000 0.0011020000 35605605 96830484 509673472 3.6176383495 3.9950613976 3.9040629864 205 1311867177.2638640404 0.0654421225 0.0599379848 0.0654421225 0.0068397896 0.0064980000 0.0004000000 0.0033380000 0.0000030000 0.0000030000 0.0019800000 35609445 96830484 509673472 3.6151175499 3.9954860210 3.9039289951 206 1311867177.2946178913 0.0648285896 0.0599617256 0.0654421225 0.0068406717 0.0091310000 0.0005680000 0.0048950000 0.0000020000 0.0000140000 0.0015490000 35613061 96830484 509673472 3.6134538651 3.9953577518 3.9033684731 207 1311867177.3276090622 0.0649357513 0.0599857547 0.0654421225 0.0068246773 0.0078220000 0.0005350000 0.0045070000 0.0000070000 0.0000060000 0.0015400000 35616789 96830484 509673472 3.6097204685 3.9960055351 3.9029917717 208 1311867177.3627710342 0.0651531219 0.0600105978 0.0654421225 0.0068123251 0.0069260000 0.0005030000 0.0035500000 0.0000010000 0.0000080000 0.0012580000 35620517 96830484 509673472 3.6090042591 3.9967708588 3.9027023315 209 1311867177.3946089745 0.0656571984 0.0600376151 0.0656571984 0.0068180434 0.0068170000 0.0004160000 0.0034030000 0.0000050000 0.0000040000 0.0020220000 35624189 96830484 509673472 3.6055185795 3.9963564873 3.9024224281 210 1311867177.4312860966 0.0657087043 0.0600646202 0.0657087043 0.0068050096 0.0049730000 0.0004030000 0.0026610000 0.0000000000 0.0000040000 0.0011120000 35628029 96830484 509673472 3.6044044495 3.9974038601 3.9021790028 211 1311867177.4626040459 0.0659974068 0.0600927377 0.0659974068 0.0067907620 0.0068930000 0.0003930000 0.0043840000 0.0000040000 0.0000030000 0.0013490000 35631701 96830484 509673472 3.6013531685 3.9977629185 3.9018924236 212 1311867177.4946429729 0.0657545552 0.0601194444 0.0659974068 0.0067769333 0.0097030000 0.0005670000 0.0048870000 0.0000020000 0.0000140000 0.0016810000 35635373 96830484 509673472 3.6006777287 3.9982607365 3.9013884068 213 1311867177.5276319981 0.0656567439 0.0601454411 0.0659974068 0.0067642516 0.0073420000 0.0004890000 0.0031880000 0.0000070000 0.0000070000 0.0022110000 35639045 96830484 509673472 3.5998415947 3.9990441799 3.9009246826 214 1311867177.5626399517 0.0665277615 0.0601752650 0.0665277615 0.0067580888 0.0052060000 0.0004200000 0.0026810000 0.0000000000 0.0000050000 0.0011190000 35642773 96830484 509673472 3.5980210304 3.9995219707 3.9009375572 215 1311867177.5947310925 0.0662750602 0.0602036362 0.0665277615 0.0067501172 0.0052340000 0.0004050000 0.0026590000 0.0000030000 0.0000030000 0.0013610000 35646445 96830484 509673472 3.5909225941 3.9986886978 3.8996832371 216 1311867177.6311450005 0.0661088899 0.0602309753 0.0665277615 0.0067351020 0.0066540000 0.0003950000 0.0043860000 0.0000000000 0.0000040000 0.0011000000 35650285 96830484 509673472 3.5893995762 3.9998772144 3.8990478516 217 1311867177.6624829769 0.0657296255 0.0602563147 0.0665277615 0.0067238893 0.0075520000 0.0004970000 0.0028450000 0.0000100000 0.0000100000 0.0023560000 35653957 96830484 509673472 3.5891127586 4.0009436607 3.8984239101 218 1311867177.6945610046 0.0663866252 0.0602844354 0.0665277615 0.0067335965 0.0071760000 0.0004340000 0.0044880000 0.0000010000 0.0000050000 0.0011260000 35657629 96830484 509673472 3.5842671394 4.0008306503 3.8982784748 219 1311867177.7305839062 0.0660099536 0.0603105793 0.0665277615 0.0067240041 0.0079500000 0.0004970000 0.0042990000 0.0000080000 0.0000070000 0.0014830000 35661357 96830484 509673472 3.5847110748 4.0025725365 3.8975491524 220 1311867177.7625379562 0.0661217943 0.0603369939 0.0665277615 0.0067156384 0.0046960000 0.0004350000 0.0019850000 0.0000010000 0.0000050000 0.0011340000 35665029 96830484 509673472 3.5854368210 4.0026125908 3.8971245289 221 1311867177.7945590019 0.0663691983 0.0603642890 0.0665277615 0.0067023874 0.0075450000 0.0004950000 0.0032080000 0.0000070000 0.0000070000 0.0021510000 35668701 96830484 509673472 3.5822920799 4.0026531219 3.8963344097 222 1311867177.8309149742 0.0668511465 0.0603935091 0.0668511465 0.0066930535 0.0052560000 0.0004220000 0.0026920000 0.0000010000 0.0000060000 0.0011420000 35672485 96830484 509673472 3.5797483921 4.0026988983 3.8956034184 223 1311867177.8625319004 0.0664021298 0.0604204535 0.0668511465 0.0066823507 0.0080050000 0.0004930000 0.0046370000 0.0000080000 0.0000070000 0.0014960000 35676157 96830484 509673472 3.5812766552 4.0029025078 3.8948099613 224 1311867177.8946919441 0.0671698898 0.0604505850 0.0671698898 0.0066689557 0.0059250000 0.0004190000 0.0034070000 0.0000010000 0.0000050000 0.0011030000 35679773 96830484 509673472 3.5776071548 4.0037965775 3.8946375847 225 1311867177.9317860603 0.0673516095 0.0604812562 0.0673516095 0.0066551986 0.0092640000 0.0005680000 0.0041650000 0.0000100000 0.0000100000 0.0023390000 35683669 96830484 509673472 3.5759050846 4.0039086342 3.8938920498 226 1311867177.9627909660 0.0671769381 0.0605108831 0.0673516095 0.0066453140 0.0072150000 0.0004380000 0.0045010000 0.0000000000 0.0000050000 0.0011260000 35687285 96830484 509673472 3.5762979984 4.0040225983 3.8928081989 227 1311867177.9947769642 0.0672156587 0.0605404195 0.0673516095 0.0066373812 0.0067070000 0.0004100000 0.0040690000 0.0000050000 0.0000040000 0.0013420000 35690845 96830484 509673472 3.5746929646 4.0059251785 3.8920235634 228 1311867178.0306100845 0.0675772354 0.0605712828 0.0675772354 0.0066236064 0.0056070000 0.0003950000 0.0033430000 0.0000000000 0.0000040000 0.0010760000 35694629 96830484 509673472 3.5719273090 4.0055108070 3.8914048672 229 1311867178.0634479523 0.0674413443 0.0606012830 0.0675772354 0.0066106051 0.0057880000 0.0003970000 0.0026330000 0.0000040000 0.0000030000 0.0019620000 35698301 96830484 509673472 3.5726356506 4.0046963692 3.8906731606 230 1311867178.0951139927 0.0672365203 0.0606301319 0.0675772354 0.0065974203 0.0059770000 0.0003970000 0.0036990000 0.0000000000 0.0000040000 0.0010960000 35701973 96830484 509673472 3.5703957081 4.0066061020 3.8900599480 231 1311867178.1307909489 0.0682952404 0.0606633142 0.0682952404 0.0065915792 0.0092040000 0.0005670000 0.0037730000 0.0000150000 0.0000150000 0.0018990000 35705757 96830484 509673472 3.5650269985 4.0054464340 3.8899245262 232 1311867178.1627469063 0.0686391816 0.0606976929 0.0686391816 0.0066052275 0.0075250000 0.0004610000 0.0045410000 0.0000010000 0.0000060000 0.0011700000 35709429 96830484 509673472 3.5631899834 4.0051159859 3.8894879818 233 1311867178.1950459480 0.0680663809 0.0607293182 0.0686391816 0.0066063636 0.0077780000 0.0004120000 0.0044390000 0.0000040000 0.0000040000 0.0019990000 35713045 96830484 509673472 3.5645031929 4.0071053505 3.8889832497 234 1311867178.2307190895 0.0686376244 0.0607631144 0.0686391816 0.0065939451 0.0056300000 0.0003960000 0.0033410000 0.0000000000 0.0000030000 0.0010900000 35716829 96830484 509673472 3.5599694252 4.0057821274 3.8884873390 235 1311867178.2628939152 0.0681177974 0.0607944109 0.0686391816 0.0065819719 0.0055460000 0.0003960000 0.0029900000 0.0000030000 0.0000030000 0.0013580000 35720557 96830484 509673472 3.5594677925 4.0057320595 3.8879113197 236 1311867178.2954900265 0.0680664331 0.0608252246 0.0686391816 0.0065709201 0.0076580000 0.0004930000 0.0039790000 0.0000010000 0.0000170000 0.0013870000 35724229 96830484 509673472 3.5568151474 4.0072441101 3.8877139091 237 1311867178.3306670189 0.0684102327 0.0608572288 0.0686391816 0.0065637126 0.0089210000 0.0005730000 0.0048120000 0.0000070000 0.0000080000 0.0021680000 35727957 96830484 509673472 3.5540380478 4.0054364204 3.8876016140 238 1311867178.3627231121 0.0674759597 0.0608850386 0.0686391816 0.0065526675 0.0054900000 0.0004240000 0.0030480000 0.0000000000 0.0000060000 0.0011300000 35731685 96830484 509673472 3.5550167561 4.0064439774 3.8871035576 239 1311867178.3949439526 0.0675428808 0.0609128957 0.0686391816 0.0065408482 0.0078220000 0.0004930000 0.0046210000 0.0000080000 0.0000070000 0.0014870000 35735301 96830484 509673472 3.5519020557 4.0069160461 3.8868725300 240 1311867178.4306581020 0.0680612549 0.0609426805 0.0686391816 0.0065431424 0.0058260000 0.0004200000 0.0033930000 0.0000000000 0.0000040000 0.0011270000 35739085 96830484 509673472 3.5486943722 4.0072054863 3.8871960640 241 1311867178.4628739357 0.0684848428 0.0609739758 0.0686391816 0.0065300181 0.0097100000 0.0005910000 0.0048680000 0.0000100000 0.0000090000 0.0023680000 35742757 96830484 509673472 3.5461192131 4.0077319145 3.8874433041 242 1311867178.4946439266 0.0685756207 0.0610053875 0.0686391816 0.0065184090 0.0053390000 0.0004320000 0.0027300000 0.0000010000 0.0000070000 0.0011730000 35746429 96830484 509673472 3.5439693928 4.0067596436 3.8874332905 243 1311867178.5306270123 0.0681074038 0.0610346140 0.0686391816 0.0065208317 0.0069770000 0.0004080000 0.0044160000 0.0000030000 0.0000030000 0.0013540000 35750213 96830484 509673472 3.5440480709 4.0083079338 3.8871891499 244 1311867178.5626420975 0.0688924715 0.0610668183 0.0688924715 0.0065082960 0.0076730000 0.0004680000 0.0045920000 0.0000010000 0.0000070000 0.0011850000 35753941 96830484 509673472 3.5405995846 4.0083093643 3.8876810074 245 1311867178.5947000980 0.0688152313 0.0610984445 0.0688924715 0.0065061811 0.0078480000 0.0004240000 0.0044730000 0.0000050000 0.0000050000 0.0020010000 35757613 96830484 509673472 3.5398678780 4.0073456764 3.8874654770 246 1311867178.6306900978 0.0690849870 0.0611309101 0.0690849870 0.0065036086 0.0074860000 0.0005020000 0.0039500000 0.0000010000 0.0000080000 0.0012700000 35761341 96830484 509673472 3.5374119282 4.0081586838 3.8873257637 247 1311867178.6626410484 0.0686973035 0.0611615433 0.0690849870 0.0065125857 0.0055630000 0.0004220000 0.0026870000 0.0000050000 0.0000050000 0.0014030000 35765069 96830484 509673472 3.5371067524 4.0093278885 3.8871545792 248 1311867178.6946120262 0.0695184842 0.0611952406 0.0695184842 0.0065030151 0.0067550000 0.0004010000 0.0043990000 0.0000010000 0.0000040000 0.0011010000 35768685 96830484 509673472 3.5337607861 4.0074453354 3.8872303963 249 1311867178.7307450771 0.0692881867 0.0612277424 0.0695184842 0.0064999420 0.0085460000 0.0004920000 0.0042740000 0.0000090000 0.0000070000 0.0021920000 35772469 96830484 509673472 3.5331273079 4.0090379715 3.8868000507 250 1311867178.7632350922 0.0690842420 0.0612591684 0.0695184842 0.0064928121 0.0052730000 0.0004170000 0.0026880000 0.0000000000 0.0000050000 0.0011160000 35776197 96830484 509673472 3.5326330662 4.0094428062 3.8864734173 251 1311867178.8006799221 0.0694811344 0.0612919252 0.0695184842 0.0064880411 0.0053900000 0.0004050000 0.0026660000 0.0000040000 0.0000040000 0.0013520000 35779981 96830484 509673472 3.5301928520 4.0075950623 3.8862762451 252 1311867178.8309500217 0.0694326833 0.0613242298 0.0695184842 0.0064844646 0.0097440000 0.0005710000 0.0049730000 0.0000020000 0.0000170000 0.0016890000 35783597 96830484 509673472 3.5291404724 4.0099205971 3.8861405849 253 1311867178.8627939224 0.0692832470 0.0613556884 0.0695184842 0.0064831344 0.0082780000 0.0004630000 0.0045350000 0.0000060000 0.0000050000 0.0020400000 35787325 96830484 509673472 3.5290689468 4.0097503662 3.8858597279 254 1311867178.8952279091 0.0700576156 0.0613899479 0.0700576156 0.0064839114 0.0069060000 0.0004120000 0.0044260000 0.0000010000 0.0000050000 0.0011040000 35790997 96830484 509673472 3.5273945332 4.0066232681 3.8856339455 255 1311867178.9306209087 0.0695599765 0.0614219873 0.0700576156 0.0064818994 0.0066900000 0.0004050000 0.0040700000 0.0000030000 0.0000030000 0.0013650000 35794725 96830484 509673472 3.5290970802 4.0092201233 3.8846030235 256 1311867178.9627609253 0.0693005919 0.0614527631 0.0700576156 0.0064794581 0.0064270000 0.0004000000 0.0040710000 0.0000000000 0.0000030000 0.0011040000 35798453 96830484 509673472 3.5292747021 4.0094728470 3.8837656975 257 1311867178.9946830273 0.0698419660 0.0614854059 0.0700576156 0.0064777620 0.0076240000 0.0003970000 0.0044020000 0.0000040000 0.0000040000 0.0019620000 35826701 96830484 509673472 3.5235691071 4.0086216927 3.8831658363 258 1311867179.0309159756 0.0699913055 0.0615183745 0.0700576156 0.0065152772 0.0049460000 0.0003930000 0.0026260000 0.0000000000 0.0000040000 0.0010820000 35881685 96830484 509673472 3.5216279030 4.0100998878 3.8826680183 259 1311867179.0628120899 0.0696005374 0.0615495797 0.0700576156 0.0065102004 0.0059680000 0.0004000000 0.0033400000 0.0000030000 0.0000030000 0.0013490000 35885413 96830484 509673472 3.5224785805 4.0088891983 3.8817791939 260 1311867179.0968201160 0.0709879771 0.0615858813 0.0709879771 0.0066079380 0.0067880000 0.0003990000 0.0044020000 0.0000010000 0.0000030000 0.0011150000 35889085 96830484 509673472 3.5176877975 4.0057868958 3.8812792301 261 1311867179.1310369968 0.0698138997 0.0616174062 0.0709879771 0.0065965440 0.0065900000 0.0004000000 0.0033530000 0.0000040000 0.0000040000 0.0019660000 35892757 96830484 509673472 3.5214345455 4.0081915855 3.8799328804 262 1311867179.1627540588 0.0705507025 0.0616515028 0.0709879771 0.0066022123 0.0050040000 0.0004020000 0.0026420000 0.0000000000 0.0000050000 0.0010850000 35896429 96830484 509673472 3.5194902420 4.0068979263 3.8787593842 263 1311867179.1957008839 0.0707167163 0.0616859713 0.0709879771 0.0065949531 0.0062970000 0.0003950000 0.0036870000 0.0000040000 0.0000040000 0.0013480000 35900101 96830484 509673472 3.5146133900 4.0059151649 3.8772268295 264 1311867179.2307469845 0.0709139481 0.0617209258 0.0709879771 0.0066565932 0.0067420000 0.0003980000 0.0043660000 0.0000010000 0.0000040000 0.0011030000 35903829 96830484 509673472 3.5122539997 4.0098562241 3.8764493465 265 1311867179.2634611130 0.0708108321 0.0617552273 0.0709879771 0.0066560694 0.0058900000 0.0003920000 0.0026260000 0.0000040000 0.0000030000 0.0019910000 35907613 96830484 509673472 3.5104486942 4.0080833435 3.8755328655 266 1311867179.2959330082 0.0705812499 0.0617884078 0.0709879771 0.0066476633 0.0060860000 0.0003930000 0.0036950000 0.0000010000 0.0000040000 0.0011160000 35911229 96830484 509673472 3.5091285706 4.0076570511 3.8746876717 267 1311867179.3307149410 0.0698494390 0.0618185989 0.0709879771 0.0066373454 0.0059700000 0.0004010000 0.0033340000 0.0000040000 0.0000040000 0.0013520000 35914957 96830484 509673472 3.5115351677 4.0090875626 3.8739516735 268 1311867179.3629300594 0.0700628534 0.0618493611 0.0709879771 0.0066276981 0.0095800000 0.0006020000 0.0037700000 0.0000020000 0.0000150000 0.0016680000 35918741 96830484 509673472 3.5092113018 4.0090918541 3.8736510277 269 1311867179.3948490620 0.0700569749 0.0618798727 0.0709879771 0.0066207022 0.0086020000 0.0004550000 0.0045430000 0.0000060000 0.0000060000 0.0021010000 35922301 96830484 509673472 3.5078029633 4.0077838898 3.8732006550 270 1311867179.4308040142 0.0698456690 0.0619093756 0.0709879771 0.0066345248 0.0066180000 0.0004170000 0.0040690000 0.0000010000 0.0000050000 0.0011240000 35926141 96830484 509673472 3.5059013367 4.0100598335 3.8731136322 271 1311867179.4637460709 0.0702638477 0.0619402039 0.0709879771 0.0066295567 0.0056170000 0.0003930000 0.0029850000 0.0000030000 0.0000030000 0.0013720000 35929869 96830484 509673472 3.5040934086 4.0106911659 3.8735630512 272 1311867179.4949469566 0.0700538158 0.0619700334 0.0709879771 0.0066392378 0.0060930000 0.0004030000 0.0036820000 0.0000010000 0.0000030000 0.0011190000 35933485 96830484 509673472 3.5042166710 4.0098252296 3.8731780052 273 1311867179.5307800770 0.0697226822 0.0619984314 0.0709879771 0.0066371980 0.0065890000 0.0003920000 0.0033180000 0.0000040000 0.0000030000 0.0019950000 35937269 96830484 509673472 3.5042963028 4.0127372742 3.8731951714 274 1311867179.5627610683 0.0699289590 0.0620273749 0.0709879771 0.0066491167 0.0081780000 0.0004930000 0.0046170000 0.0000010000 0.0000070000 0.0012690000 35940941 96830484 509673472 3.5026528835 4.0125622749 3.8733427525 275 1311867179.5946741104 0.0702473819 0.0620572658 0.0709879771 0.0066410538 0.0059330000 0.0004160000 0.0030220000 0.0000060000 0.0000050000 0.0013860000 35944613 96830484 509673472 3.5008282661 4.0130381584 3.8735029697 276 1311867179.6306900978 0.0700502321 0.0620862259 0.0709879771 0.0066547555 0.0069230000 0.0004880000 0.0035440000 0.0000000000 0.0000080000 0.0012600000 35948341 96830484 509673472 3.5011649132 4.0146784782 3.8734714985 277 1311867179.6625750065 0.0704535842 0.0621164329 0.0709879771 0.0066508536 0.0089860000 0.0004860000 0.0046430000 0.0000070000 0.0000070000 0.0022110000 35952069 96830484 509673472 3.5007596016 4.0135588646 3.8736913204 278 1311867179.6946051121 0.0706107467 0.0621469880 0.0709879771 0.0066534478 0.0061290000 0.0005070000 0.0024970000 0.0000020000 0.0000110000 0.0012700000 35955685 96830484 509673472 3.4993124008 4.0149288177 3.8738932610 279 1311867179.7309470177 0.0708442554 0.0621781610 0.0709879771 0.0066445593 0.0074100000 0.0004330000 0.0044580000 0.0000050000 0.0000040000 0.0013870000 35959525 96830484 509673472 3.4996151924 4.0147566795 3.8740954399 280 1311867179.7627270222 0.0706144050 0.0622082905 0.0709879771 0.0066621844 0.0068250000 0.0004020000 0.0043840000 0.0000010000 0.0000040000 0.0011100000 35963197 96830484 509673472 3.4987087250 4.0136499405 3.8738851547 281 1311867179.7948911190 0.0700968951 0.0622363638 0.0709879771 0.0066779039 0.0091910000 0.0004910000 0.0046480000 0.0000080000 0.0000070000 0.0022050000 35966813 96830484 509673472 3.4985945225 4.0156531334 3.8737187386 282 1311867179.8307530880 0.0700315088 0.0622640061 0.0709879771 0.0066686067 0.0056960000 0.0004150000 0.0030300000 0.0000010000 0.0000050000 0.0011320000 35970653 96830484 509673472 3.4989874363 4.0164537430 3.8739416599 283 1311867179.8627979755 0.0706624985 0.0622936828 0.0709879771 0.0066620870 0.0060210000 0.0003980000 0.0033520000 0.0000030000 0.0000030000 0.0013610000 35974325 96830484 509673472 3.4965326786 4.0143213272 3.8743314743 284 1311867179.8948040009 0.0705086961 0.0623226089 0.0709879771 0.0066523619 0.0079200000 0.0004930000 0.0042890000 0.0000010000 0.0000080000 0.0012710000 35977997 96830484 509673472 3.4974555969 4.0144023895 3.8744494915 285 1311867179.9309051037 0.0706707761 0.0623519007 0.0709879771 0.0066773827 0.0080800000 0.0004420000 0.0044580000 0.0000060000 0.0000050000 0.0020170000 35981781 96830484 509673472 3.4962406158 4.0177216530 3.8750171661 286 1311867179.9635379314 0.0707743466 0.0623813498 0.0709879771 0.0066780070 0.0057910000 0.0004070000 0.0033470000 0.0000000000 0.0000040000 0.0011040000 35985509 96830484 509673472 3.4952116013 4.0160140991 3.8751471043 287 1311867179.9958879948 0.0708468035 0.0624108462 0.0709879771 0.0066710888 0.0070310000 0.0004050000 0.0043830000 0.0000040000 0.0000030000 0.0013510000 35989125 96830484 509673472 3.4934065342 4.0161080360 3.8754036427 288 1311867180.0309770107 0.0707580671 0.0624398296 0.0709879771 0.0066686055 0.0095600000 0.0004900000 0.0046910000 0.0000010000 0.0000080000 0.0012640000 35992909 96830484 509673472 3.4940555096 4.0186820030 3.8759567738 289 1311867180.0626471043 0.0711454526 0.0624699528 0.0711454526 0.0066585251 0.0082700000 0.0004360000 0.0044660000 0.0000050000 0.0000050000 0.0020520000 35996581 96830484 509673472 3.4930503368 4.0174808502 3.8761343956 290 1311867180.0947730541 0.0712094903 0.0625000892 0.0712094903 0.0066480845 0.0069180000 0.0004070000 0.0043940000 0.0000010000 0.0000040000 0.0011120000 36000197 96830484 509673472 3.4899671078 4.0181913376 3.8759350777 291 1311867180.1307730675 0.0713927224 0.0625306481 0.0713927224 0.0066448665 0.0058630000 0.0004070000 0.0029770000 0.0000040000 0.0000040000 0.0013780000 36003981 96830484 509673472 3.4924974442 4.0176906586 3.8759150505 292 1311867180.1636900902 0.0711769313 0.0625602586 0.0713927224 0.0066605547 0.0068940000 0.0004060000 0.0044240000 0.0000010000 0.0000050000 0.0010980000 36007765 96830484 509673472 3.4947612286 4.0178866386 3.8757147789 293 1311867180.1949090958 0.0708893612 0.0625886856 0.0713927224 0.0066503491 0.0082750000 0.0005040000 0.0035830000 0.0000080000 0.0000070000 0.0021930000 36011325 96830484 509673472 3.4947190285 4.0175938606 3.8749930859 294 1311867180.2308139801 0.0702936500 0.0626148929 0.0713927224 0.0066467932 0.0054630000 0.0004250000 0.0026950000 0.0000000000 0.0000060000 0.0011400000 36015053 96830484 509673472 3.4961068630 4.0179152489 3.8739488125 295 1311867180.2637619972 0.0697393641 0.0626390437 0.0713927224 0.0066655277 0.0072560000 0.0004090000 0.0043920000 0.0000030000 0.0000030000 0.0013690000 36018781 96830484 509673472 3.4968338013 4.0184240341 3.8730769157 296 1311867180.2947549820 0.0702809840 0.0626648611 0.0713927224 0.0066545464 0.0047830000 0.0004010000 0.0019200000 0.0000000000 0.0000030000 0.0011520000 36022397 96830484 509673472 3.4951081276 4.0175895691 3.8730254173 297 1311867180.3308670521 0.0701173171 0.0626899535 0.0713927224 0.0066454793 0.0092360000 0.0005620000 0.0043990000 0.0000100000 0.0000100000 0.0021990000 36026181 96830484 509673472 3.4951746464 4.0186748505 3.8725121021 298 1311867180.3658289909 0.0701656267 0.0627150397 0.0713927224 0.0066445159 0.0061920000 0.0004320000 0.0033800000 0.0000010000 0.0000060000 0.0011480000 36029909 96830484 509673472 3.4948005676 4.0190272331 3.8720560074 299 1311867180.3964109421 0.0704426095 0.0627408844 0.0713927224 0.0066342223 0.0075870000 0.0005080000 0.0035700000 0.0000080000 0.0000080000 0.0015040000 36033581 96830484 509673472 3.4964542389 4.0194158554 3.8720457554 300 1311867180.4309151173 0.0711517483 0.0627689206 0.0713927224 0.0066238251 0.0072090000 0.0004200000 0.0044510000 0.0000000000 0.0000040000 0.0011230000 36037309 96830484 509673472 3.4935820103 4.0180840492 3.8717291355 301 1311867180.4670670033 0.0708775222 0.0627958595 0.0713927224 0.0066187055 0.0077640000 0.0004060000 0.0043850000 0.0000030000 0.0000040000 0.0019910000 36041093 96830484 509673472 3.4947397709 4.0195446014 3.8713712692 302 1311867180.4947559834 0.0711136833 0.0628234019 0.0713927224 0.0066180809 0.0054410000 0.0003980000 0.0029660000 0.0000000000 0.0000030000 0.0010990000 36044597 96830484 509673472 3.4959864616 4.0189895630 3.8712604046 303 1311867180.5308880806 0.0705109984 0.0628487735 0.0713927224 0.0066073349 0.0089740000 0.0005690000 0.0048330000 0.0000100000 0.0000090000 0.0016330000 36048437 96830484 509673472 3.4982213974 4.0194015503 3.8709445000 304 1311867180.5629510880 0.0711651146 0.0628761299 0.0713927224 0.0065970165 0.0055220000 0.0004450000 0.0027120000 0.0000010000 0.0000060000 0.0011290000 36052109 96830484 509673472 3.4971044064 4.0197248459 3.8714048862 305 1311867180.5946910381 0.0712965652 0.0629037379 0.0713927224 0.0065883879 0.0086060000 0.0005180000 0.0045630000 0.0000070000 0.0000070000 0.0020610000 36055781 96830484 509673472 3.4969217777 4.0200953484 3.8716077805 306 1311867180.6308128834 0.0710636675 0.0629304043 0.0713927224 0.0065790624 0.0060130000 0.0004290000 0.0033780000 0.0000000000 0.0000040000 0.0011120000 36059565 96830484 509673472 3.4983756542 4.0193700790 3.8717463017 307 1311867180.6640911102 0.0707574114 0.0629558995 0.0713927224 0.0065836819 0.0065900000 0.0004980000 0.0028360000 0.0000070000 0.0000080000 0.0014870000 36063237 96830484 509673472 3.4989216328 4.0203590393 3.8719112873 308 1311867180.6957859993 0.0709528998 0.0629818638 0.0713927224 0.0065735425 0.0071160000 0.0005080000 0.0035930000 0.0000010000 0.0000120000 0.0012590000 36066909 96830484 509673472 3.4998593330 4.0190887451 3.8722839355 309 1311867180.7309739590 0.0704708919 0.0630061001 0.0713927224 0.0065672836 0.0076470000 0.0004370000 0.0041230000 0.0000050000 0.0000050000 0.0019740000 36070693 96830484 509673472 3.5012259483 4.0202684402 3.8721747398 310 1311867180.7650830746 0.0708195046 0.0630313046 0.0713927224 0.0065684182 0.0068610000 0.0004150000 0.0043900000 0.0000010000 0.0000040000 0.0010950000 36074421 96830484 509673472 3.5026121140 4.0198240280 3.8723402023 311 1311867180.7949280739 0.0710973814 0.0630572406 0.0713927224 0.0065580119 0.0053230000 0.0004100000 0.0026250000 0.0000040000 0.0000030000 0.0013500000 36077981 96830484 509673472 3.5026044846 4.0198035240 3.8726892471 312 1311867180.8309240341 0.0713222250 0.0630837309 0.0713927224 0.0065483274 0.0097010000 0.0005760000 0.0041580000 0.0000020000 0.0000140000 0.0016500000 36081821 96830484 509673472 3.5031819344 4.0210380554 3.8731288910 313 1311867180.8652698994 0.0712386295 0.0631097849 0.0713927224 0.0065463654 0.0084840000 0.0004630000 0.0045470000 0.0000060000 0.0000060000 0.0020580000 36085549 96830484 509673472 3.5036773682 4.0196628571 3.8732254505 314 1311867180.8966469765 0.0708177909 0.0631343327 0.0713927224 0.0065365439 0.0052540000 0.0004180000 0.0026710000 0.0000000000 0.0000050000 0.0011030000 36089221 96830484 509673472 3.5059237480 4.0206828117 3.8730258942 315 1311867180.9306049347 0.0712929741 0.0631602331 0.0713927224 0.0065449981 0.0049300000 0.0004020000 0.0022710000 0.0000030000 0.0000030000 0.0013500000 36092949 96830484 509673472 3.5051784515 4.0202946663 3.8733479977 316 1311867180.9631829262 0.0714369565 0.0631864253 0.0714369565 0.0065448957 0.0087560000 0.0005980000 0.0030360000 0.0000020000 0.0000150000 0.0016550000 36096621 96830484 509673472 3.5056321621 4.0206155777 3.8732786179 317 1311867180.9948179722 0.0709331930 0.0632108630 0.0714369565 0.0065389634 0.0074790000 0.0004680000 0.0034860000 0.0000070000 0.0000060000 0.0020370000 36100237 96830484 509673472 3.5097532272 4.0211033821 3.8736002445 318 1311867181.0308310986 0.0712458491 0.0632361303 0.0714369565 0.0065296870 0.0063440000 0.0004290000 0.0037380000 0.0000000000 0.0000040000 0.0010930000 36104021 96830484 509673472 3.5109403133 4.0195627213 3.8737978935 319 1311867181.0627830029 0.0718187168 0.0632630350 0.0718187168 0.0065270566 0.0062810000 0.0005010000 0.0024980000 0.0000100000 0.0000100000 0.0014630000 36107749 96830484 509673472 3.5127937794 4.0192117691 3.8740732670 320 1311867181.0948719978 0.0709819049 0.0632871564 0.0718187168 0.0065247787 0.0058450000 0.0004430000 0.0030550000 0.0000010000 0.0000070000 0.0011100000 36111421 96830484 509673472 3.5155885220 4.0196566582 3.8740398884 321 1311867181.1311910152 0.0695637316 0.0633067096 0.0718187168 0.0065205911 0.0092230000 0.0005020000 0.0047300000 0.0000120000 0.0000100000 0.0021680000 36115205 96830484 509673472 3.5209167004 4.0207161903 3.8734245300 322 1311867181.1629528999 0.0707118139 0.0633297068 0.0718187168 0.0065281079 0.0073510000 0.0004490000 0.0044960000 0.0000010000 0.0000060000 0.0011200000 36118877 96830484 509673472 3.5204284191 4.0192556381 3.8737952709 323 1311867181.1972830296 0.0704626143 0.0633517901 0.0718187168 0.0065187036 0.0058940000 0.0004210000 0.0030310000 0.0000040000 0.0000030000 0.0013490000 36122605 96830484 509673472 3.5217864513 4.0196046829 3.8735554218 324 1311867181.2342460155 0.0703658462 0.0633734385 0.0718187168 0.0065098338 0.0050520000 0.0004020000 0.0026260000 0.0000010000 0.0000040000 0.0010780000 36126445 96830484 509673472 3.5247099400 4.0186100006 3.8732745647 325 1311867181.2629361153 0.0709839612 0.0633968555 0.0718187168 0.0065011780 0.0111340000 0.0005990000 0.0041590000 0.0000150000 0.0000140000 0.0026870000 36130005 96830484 509673472 3.5250530243 4.0185470581 3.8736307621 326 1311867181.2948091030 0.0700939298 0.0634173986 0.0718187168 0.0064920788 0.0065400000 0.0005750000 0.0028430000 0.0000010000 0.0000080000 0.0012250000 36133621 96830484 509673472 3.5287914276 4.0199007988 3.8733654022 327 1311867181.3317139149 0.0704488084 0.0634389014 0.0718187168 0.0064883073 0.0051220000 0.0004460000 0.0020000000 0.0000060000 0.0000050000 0.0013850000 36137461 96830484 509673472 3.5284640789 4.0193972588 3.8733463287 328 1311867181.3626708984 0.0699355006 0.0634587081 0.0718187168 0.0064904595 0.0058660000 0.0004140000 0.0033610000 0.0000010000 0.0000040000 0.0010820000 36141077 96830484 509673472 3.5317890644 4.0219306946 3.8737156391 329 1311867181.3948218822 0.0700246841 0.0634786655 0.0718187168 0.0064822305 0.0076230000 0.0005040000 0.0032080000 0.0000080000 0.0000070000 0.0021300000 36144749 96830484 509673472 3.5319178104 4.0200910568 3.8735527992 330 1311867181.4308950901 0.0702442825 0.0634991674 0.0718187168 0.0064734044 0.0057190000 0.0004250000 0.0030580000 0.0000010000 0.0000050000 0.0010800000 36148421 96830484 509673472 3.5328662395 4.0197858810 3.8737037182 331 1311867181.4628310204 0.0702135414 0.0635194525 0.0718187168 0.0064676268 0.0084560000 0.0006040000 0.0038030000 0.0000170000 0.0000140000 0.0015830000 36152093 96830484 509673472 3.5357956886 4.0197587013 3.8742520809 332 1311867181.4963610172 0.0693665147 0.0635370641 0.0718187168 0.0064758021 0.0063590000 0.0004510000 0.0034590000 0.0000010000 0.0000060000 0.0011440000 36155821 96830484 509673472 3.5391538143 4.0199532509 3.8741977215 333 1311867181.5359110832 0.0696181282 0.0635553256 0.0718187168 0.0064694683 0.0062320000 0.0004240000 0.0026760000 0.0000050000 0.0000040000 0.0019450000 36159661 96830484 509673472 3.5405721664 4.0191311836 3.8741695881 334 1311867181.5671720505 0.0696204528 0.0635734846 0.0718187168 0.0064646791 0.0069480000 0.0004070000 0.0044210000 0.0000010000 0.0000040000 0.0010760000 36163277 96830484 509673472 3.5412743092 4.0182719231 3.8736319542 335 1311867181.5948610306 0.0697826296 0.0635920194 0.0718187168 0.0064612537 0.0061100000 0.0004050000 0.0033600000 0.0000040000 0.0000040000 0.0013220000 36166781 96830484 509673472 3.5423333645 4.0196805000 3.8738434315 336 1311867181.6313591003 0.0696653426 0.0636100948 0.0718187168 0.0064607634 0.0048420000 0.0004090000 0.0023120000 0.0000010000 0.0000040000 0.0010730000 36170621 96830484 509673472 3.5448198318 4.0186891556 3.8736040592 337 1311867181.6628570557 0.0704243705 0.0636303152 0.0718187168 0.0064580156 0.0063860000 0.0004060000 0.0030110000 0.0000040000 0.0000040000 0.0019360000 36174293 96830484 509673472 3.5447573662 4.0164480209 3.8732936382 338 1311867181.6949229240 0.0695557371 0.0636478460 0.0718187168 0.0064536496 0.0058510000 0.0004070000 0.0033640000 0.0000010000 0.0000040000 0.0010740000 36177909 96830484 509673472 3.5473892689 4.0184879303 3.8728120327 339 1311867181.7310829163 0.0701745376 0.0636670988 0.0718187168 0.0064552744 0.0071680000 0.0004080000 0.0044330000 0.0000050000 0.0000040000 0.0013150000 36181693 96830484 509673472 3.5502285957 4.0167922974 3.8725740910 340 1311867181.7634840012 0.0706311539 0.0636875813 0.0718187168 0.0064458984 0.0068880000 0.0004010000 0.0044230000 0.0000010000 0.0000050000 0.0010650000 36185421 96830484 509673472 3.5489928722 4.0150527954 3.8721232414 341 1311867181.7948980331 0.0695154369 0.0637046718 0.0718187168 0.0064426061 0.0077680000 0.0004010000 0.0044150000 0.0000040000 0.0000040000 0.0019320000 36188981 96830484 509673472 3.5534636974 4.0164251328 3.8713910580 342 1311867181.8308010101 0.0698142797 0.0637225361 0.0718187168 0.0064376167 0.0058440000 0.0004040000 0.0033620000 0.0000010000 0.0000050000 0.0010560000 36192765 96830484 509673472 3.5543565750 4.0149269104 3.8714122772 343 1311867181.8627979755 0.0688337758 0.0637374377 0.0718187168 0.0064311501 0.0071880000 0.0004080000 0.0044280000 0.0000040000 0.0000040000 0.0013290000 36196493 96830484 509673472 3.5572323799 4.0146222115 3.8711218834 344 1311867181.8949289322 0.0686744824 0.0637517896 0.0718187168 0.0064242811 0.0068270000 0.0004100000 0.0043240000 0.0000000000 0.0000050000 0.0010680000 36200109 96830484 509673472 3.5598328114 4.0155568123 3.8712923527 345 1311867181.9307990074 0.0685436055 0.0637656789 0.0718187168 0.0064193348 0.0076700000 0.0004050000 0.0043150000 0.0000050000 0.0000040000 0.0019190000 36203949 96830484 509673472 3.5610313416 4.0142393112 3.8708453178 346 1311867181.9629189968 0.0695300624 0.0637823390 0.0718187168 0.0064187643 0.0062110000 0.0004020000 0.0037210000 0.0000000000 0.0000050000 0.0010560000 36207621 96830484 509673472 3.5599577427 4.0141925812 3.8714623451 347 1311867181.9955599308 0.0693958402 0.0637985162 0.0718187168 0.0064365295 0.0064480000 0.0004080000 0.0037040000 0.0000050000 0.0000040000 0.0013130000 36211293 96830484 509673472 3.5620965958 4.0132541656 3.8721954823 348 1311867182.0320639610 0.0688459799 0.0638130204 0.0718187168 0.0064287973 0.0068970000 0.0004020000 0.0044270000 0.0000010000 0.0000040000 0.0010540000 36215077 96830484 509673472 3.5643918514 4.0124950409 3.8721928596 349 1311867182.0629000664 0.0683766901 0.0638260968 0.0718187168 0.0064234442 0.0078250000 0.0004070000 0.0044210000 0.0000040000 0.0000040000 0.0019160000 36218749 96830484 509673472 3.5668773651 4.0129089355 3.8723573685 350 1311867182.0948839188 0.0684877783 0.0638394159 0.0718187168 0.0064253753 0.0055540000 0.0004120000 0.0030040000 0.0000000000 0.0000050000 0.0010610000 36222365 96830484 509673472 3.5687134266 4.0125198364 3.8725278378 351 1311867182.1314840317 0.0686539635 0.0638531326 0.0718187168 0.0064167606 0.0071590000 0.0004100000 0.0043960000 0.0000040000 0.0000040000 0.0013090000 36226205 96830484 509673472 3.5708663464 4.0123853683 3.8730778694 352 1311867182.1629920006 0.0683947876 0.0638660350 0.0718187168 0.0064089349 0.0047880000 0.0004040000 0.0022880000 0.0000000000 0.0000040000 0.0010590000 36229877 96830484 509673472 3.5721871853 4.0127439499 3.8731770515 353 1311867182.1994500160 0.0690002963 0.0638805796 0.0718187168 0.0064034805 0.0063480000 0.0004080000 0.0029870000 0.0000040000 0.0000040000 0.0019140000 36233605 96830484 509673472 3.5727093220 4.0119833946 3.8736672401 354 1311867182.2307739258 0.0690267310 0.0638951168 0.0718187168 0.0063981152 0.0069060000 0.0004020000 0.0043950000 0.0000000000 0.0000040000 0.0010500000 36237221 96830484 509673472 3.5744864941 4.0111842155 3.8741242886 355 1311867182.2629120350 0.0687112063 0.0639086832 0.0718187168 0.0063990741 0.0071710000 0.0004030000 0.0044150000 0.0000040000 0.0000040000 0.0013120000 36240949 96830484 509673472 3.5775165558 4.0113406181 3.8744156361 356 1311867182.2973539829 0.0695353821 0.0639244886 0.0718187168 0.0063943208 0.0051400000 0.0004020000 0.0026490000 0.0000000000 0.0000040000 0.0010540000 36244677 96830484 509673472 3.5771238804 4.0097894669 3.8748028278 357 1311867182.3308460712 0.0703106299 0.0639423769 0.0718187168 0.0064120334 0.0078040000 0.0004160000 0.0044100000 0.0000050000 0.0000040000 0.0019210000 36248349 96830484 509673472 3.5769214630 4.0097551346 3.8754427433 358 1311867182.3629670143 0.0702988878 0.0639601325 0.0718187168 0.0064326846 0.0054920000 0.0004040000 0.0029990000 0.0000010000 0.0000050000 0.0010500000 36252077 96830484 509673472 3.5782809258 4.0091981888 3.8758502007 359 1311867182.3990368843 0.0702068806 0.0639775330 0.0718187168 0.0064287024 0.0064480000 0.0004020000 0.0036940000 0.0000040000 0.0000040000 0.0013050000 36255805 96830484 509673472 3.5800004005 4.0082120895 3.8760416508 360 1311867182.4308118820 0.0714357942 0.0639982504 0.0718187168 0.0064258277 0.0054980000 0.0004060000 0.0029920000 0.0000010000 0.0000050000 0.0010490000 36259477 96830484 509673472 3.5791959763 4.0059370995 3.8763630390 361 1311867182.4629440308 0.0716952682 0.0640195717 0.0718187168 0.0064224967 0.0067310000 0.0004080000 0.0033480000 0.0000040000 0.0000040000 0.0019210000 36263205 96830484 509673472 3.5795643330 4.0065917969 3.8761563301 362 1311867182.4969599247 0.0719595701 0.0640415054 0.0719595701 0.0064188455 0.0062070000 0.0004040000 0.0037060000 0.0000000000 0.0000050000 0.0010530000 36266877 96830484 509673472 3.5824565887 4.0048780441 3.8761961460 363 1311867182.5309500694 0.0727458224 0.0640654843 0.0727458224 0.0064104826 0.0050790000 0.0004100000 0.0023050000 0.0000040000 0.0000040000 0.0012650000 36270605 96830484 509673472 3.5822649002 4.0030927658 3.8756902218 364 1311867182.5629699230 0.0738242418 0.0640922940 0.0738242418 0.0064053864 0.0054760000 0.0004080000 0.0029860000 0.0000010000 0.0000050000 0.0010150000 36274277 96830484 509673472 3.5817718506 4.0032210350 3.8752882481 365 1311867182.6036369801 0.0742629915 0.0641201590 0.0742629915 0.0064031295 0.0073400000 0.0004050000 0.0040430000 0.0000040000 0.0000040000 0.0018260000 36278173 96830484 509673472 3.5808782578 4.0028653145 3.8738944530 366 1311867182.6308450699 0.0747050270 0.0641490794 0.0747050270 0.0064133844 0.0068560000 0.0004010000 0.0043930000 0.0000010000 0.0000040000 0.0010140000 36281677 96830484 509673472 3.5814750195 4.0018148422 3.8733496666 367 1311867182.6635921001 0.0746263191 0.0641776277 0.0747050270 0.0064067746 0.0060510000 0.0003990000 0.0033300000 0.0000050000 0.0000040000 0.0012730000 36285405 96830484 509673472 3.5828523636 4.0023708344 3.8733122349 368 1311867182.6970019341 0.0742243081 0.0642049285 0.0747050270 0.0064016399 0.0068490000 0.0003990000 0.0043840000 0.0000010000 0.0000040000 0.0010080000 36289077 96830484 509673472 3.5864126682 4.0017552376 3.8726701736 369 1311867182.7330639362 0.0747468323 0.0642334973 0.0747468323 0.0063981140 0.0076730000 0.0004000000 0.0043780000 0.0000050000 0.0000040000 0.0018320000 36292861 96830484 509673472 3.5871927738 4.0003767014 3.8719415665 370 1311867182.7631130219 0.0749486387 0.0642624572 0.0749486387 0.0063922695 0.0054540000 0.0004010000 0.0029820000 0.0000000000 0.0000050000 0.0010120000 36296365 96830484 509673472 3.5897800922 4.0007958412 3.8720903397 371 1311867182.7970550060 0.0756370649 0.0642931165 0.0756370649 0.0063843886 0.0053780000 0.0004130000 0.0026340000 0.0000050000 0.0000040000 0.0012670000 36300149 96830484 509673472 3.5904059410 3.9993853569 3.8717136383 372 1311867182.8306989670 0.0766451657 0.0643263209 0.0766451657 0.0063783418 0.0054830000 0.0004030000 0.0029760000 0.0000000000 0.0000040000 0.0010200000 36303821 96830484 509673472 3.5905170441 3.9991414547 3.8714771271 373 1311867182.8641169071 0.0766855478 0.0643594556 0.0766855478 0.0063754283 0.0056310000 0.0003940000 0.0022820000 0.0000040000 0.0000040000 0.0018530000 36307493 96830484 509673472 3.5916819572 3.9993298054 3.8713386059 374 1311867182.8969969749 0.0754810274 0.0643891924 0.0766855478 0.0063682063 0.0068820000 0.0003960000 0.0043950000 0.0000000000 0.0000040000 0.0010180000 36311221 96830484 509673472 3.5955982208 3.9987952709 3.8712718487 375 1311867182.9318990707 0.0760080442 0.0644201760 0.0766855478 0.0063598773 0.0064290000 0.0004020000 0.0036870000 0.0000050000 0.0000040000 0.0012580000 36314949 96830484 509673472 3.5969996452 3.9998464584 3.8715755939 376 1311867182.9630720615 0.0749654695 0.0644482220 0.0766855478 0.0063519418 0.0069900000 0.0004020000 0.0043940000 0.0000010000 0.0000040000 0.0010660000 36318621 96830484 509673472 3.6008543968 3.9997613430 3.8717284203 377 1311867182.9983949661 0.0758959353 0.0644785873 0.0766855478 0.0063606435 0.0072480000 0.0004040000 0.0033450000 0.0000040000 0.0000040000 0.0019820000 36322349 96830484 509673472 3.6013021469 3.9989960194 3.8720152378 378 1311867183.0308830738 0.0759696588 0.0645089869 0.0766855478 0.0063525787 0.0049950000 0.0004630000 0.0022800000 0.0000000000 0.0000040000 0.0010690000 36326021 96830484 509673472 3.6030488014 3.9985396862 3.8723702431 379 1311867183.0628600121 0.0760930851 0.0645395518 0.0766855478 0.0063451814 0.0072280000 0.0004040000 0.0043980000 0.0000040000 0.0000040000 0.0013170000 36329749 96830484 509673472 3.6052658558 3.9996292591 3.8729238510 380 1311867183.1000499725 0.0764363706 0.0645708593 0.0766855478 0.0063660809 0.0069430000 0.0004040000 0.0043960000 0.0000010000 0.0000050000 0.0010610000 36333477 96830484 509673472 3.6061589718 3.9978656769 3.8732073307 381 1311867183.1344780922 0.0763472319 0.0646017684 0.0766855478 0.0063601841 0.0078280000 0.0004040000 0.0044020000 0.0000050000 0.0000040000 0.0019280000 36337261 96830484 509673472 3.6078972816 3.9984197617 3.8735749722 382 1311867183.1673240662 0.0760798752 0.0646318158 0.0766855478 0.0063538782 0.0058980000 0.0004050000 0.0033380000 0.0000000000 0.0000050000 0.0010620000 36340989 96830484 509673472 3.6098918915 3.9994337559 3.8738856316 383 1311867183.2004919052 0.0773053169 0.0646649058 0.0773053169 0.0063492235 0.0058190000 0.0004040000 0.0029810000 0.0000040000 0.0000040000 0.0013120000 36344661 96830484 509673472 3.6098189354 3.9975085258 3.8746342659 384 1311867183.2311279774 0.0766623020 0.0646961491 0.0773053169 0.0063415132 0.0066250000 0.0004020000 0.0040610000 0.0000010000 0.0000040000 0.0010640000 36348277 96830484 509673472 3.6125931740 3.9972434044 3.8748700619 385 1311867183.2633349895 0.0759426728 0.0647253608 0.0773053169 0.0063349895 0.0074760000 0.0004020000 0.0040480000 0.0000050000 0.0000040000 0.0019230000 36352005 96830484 509673472 3.6150617599 3.9977049828 3.8749127388 386 1311867183.2991099358 0.0761630163 0.0647549920 0.0773053169 0.0063303382 0.0069280000 0.0004000000 0.0043880000 0.0000000000 0.0000040000 0.0010450000 36355733 96830484 509673472 3.6157913208 3.9954917431 3.8748905659 387 1311867183.3320920467 0.0757622123 0.0647834345 0.0773053169 0.0063300551 0.0072180000 0.0004010000 0.0043950000 0.0000040000 0.0000040000 0.0013100000 36359461 96830484 509673472 3.6178042889 3.9963641167 3.8748724461 388 1311867183.3695240021 0.0765926391 0.0648138706 0.0773053169 0.0063220946 0.0052000000 0.0004160000 0.0026300000 0.0000010000 0.0000050000 0.0010620000 36363301 96830484 509673472 3.6181550026 3.9959888458 3.8751382828 389 1311867183.3986210823 0.0767785236 0.0648446280 0.0773053169 0.0063158264 0.0063260000 0.0004030000 0.0029790000 0.0000050000 0.0000040000 0.0018340000 36366861 96830484 509673472 3.6185858250 3.9944674969 3.8748145103 390 1311867183.4311549664 0.0765246153 0.0648745767 0.0773053169 0.0063216403 0.0069880000 0.0004060000 0.0044090000 0.0000000000 0.0000040000 0.0010190000 36370533 96830484 509673472 3.6205639839 3.9951288700 3.8748135567 391 1311867183.4667448997 0.0770712495 0.0649057703 0.0773053169 0.0063195242 0.0072060000 0.0004030000 0.0043960000 0.0000040000 0.0000040000 0.0012790000 36374317 96830484 509673472 3.6221010685 3.9957308769 3.8751714230 392 1311867183.4988338947 0.0766705200 0.0649357824 0.0773053169 0.0063461054 0.0058760000 0.0003990000 0.0033360000 0.0000010000 0.0000040000 0.0010070000 36378045 96830484 509673472 3.6239759922 3.9937705994 3.8751120567 393 1311867183.5321829319 0.0761544555 0.0649643286 0.0773053169 0.0063390609 0.0063360000 0.0004030000 0.0029880000 0.0000040000 0.0000040000 0.0018260000 36381717 96830484 509673472 3.6259632111 3.9933977127 3.8752803802 394 1311867183.5661609173 0.0762518644 0.0649929772 0.0773053169 0.0063317937 0.0051780000 0.0004020000 0.0026350000 0.0000010000 0.0000040000 0.0010040000 36385445 96830484 509673472 3.6279404163 3.9944918156 3.8756375313 395 1311867183.5985479355 0.0769845173 0.0650233355 0.0773053169 0.0063284510 0.0061230000 0.0004060000 0.0033280000 0.0000050000 0.0000040000 0.0012490000 36389117 96830484 509673472 3.6283712387 3.9927046299 3.8755905628 396 1311867183.6310880184 0.0766769648 0.0650527639 0.0773053169 0.0063399655 0.0069390000 0.0004040000 0.0043750000 0.0000010000 0.0000050000 0.0010080000 36392789 96830484 509673472 3.6306636333 3.9925158024 3.8759090900 397 1311867183.6649260521 0.0771728382 0.0650832930 0.0773053169 0.0063343664 0.0077570000 0.0004040000 0.0043720000 0.0000040000 0.0000040000 0.0018200000 36396517 96830484 509673472 3.6324875355 3.9930028915 3.8766858578 398 1311867183.6993949413 0.0765143335 0.0651120142 0.0773053169 0.0063276884 0.0055970000 0.0004050000 0.0029920000 0.0000000000 0.0000040000 0.0010520000 36400301 96830484 509673472 3.6356804371 3.9912104607 3.8770468235 399 1311867183.7308928967 0.0787362829 0.0651461603 0.0787362829 0.0063310269 0.0061490000 0.0004050000 0.0033180000 0.0000050000 0.0000050000 0.0012990000 36403861 96830484 509673472 3.6343557835 3.9912912846 3.8776614666 400 1311867183.7676479816 0.0765381157 0.0651746402 0.0787362829 0.0063419855 0.0055910000 0.0004190000 0.0029930000 0.0000010000 0.0000050000 0.0010530000 36407701 96830484 509673472 3.6398353577 3.9906301498 3.8779368401 401 1311867183.7971870899 0.0765220299 0.0652029379 0.0787362829 0.0063344822 0.0078390000 0.0004030000 0.0043850000 0.0000040000 0.0000030000 0.0019210000 36411261 96830484 509673472 3.6414570808 3.9896061420 3.8782849312 402 1311867183.8309071064 0.0786997601 0.0652365121 0.0787362829 0.0063287976 0.0062540000 0.0004020000 0.0036740000 0.0000000000 0.0000040000 0.0010520000 36414933 96830484 509673472 3.6401491165 3.9889991283 3.8791496754 403 1311867183.8655049801 0.0765412971 0.0652645636 0.0787362829 0.0063270624 0.0069500000 0.0004180000 0.0040330000 0.0000050000 0.0000040000 0.0013090000 36418661 96830484 509673472 3.6450276375 3.9870417118 3.8789672852 404 1311867183.8970971107 0.0771922395 0.0652940876 0.0787362829 0.0063194870 0.0070270000 0.0004050000 0.0043890000 0.0000010000 0.0000050000 0.0010500000 36422277 96830484 509673472 3.6453266144 3.9869441986 3.8792946339 405 1311867183.9314939976 0.0789754093 0.0653278686 0.0789754093 0.0063140077 0.0064540000 0.0004040000 0.0029720000 0.0000040000 0.0000040000 0.0019140000 36426061 96830484 509673472 3.6442649364 3.9871883392 3.8799698353 406 1311867183.9658319950 0.0773444921 0.0653574662 0.0789754093 0.0063172031 0.0058800000 0.0004050000 0.0033260000 0.0000010000 0.0000050000 0.0010010000 36429733 96830484 509673472 3.6477186680 3.9856557846 3.8799638748 407 1311867183.9966781139 0.0770218968 0.0653861258 0.0789754093 0.0063104270 0.0070350000 0.0004610000 0.0036920000 0.0000040000 0.0000040000 0.0014320000 36433405 96830484 509673472 3.6496117115 3.9852018356 3.8801720142 408 1311867184.0309689045 0.0781964958 0.0654175237 0.0789754093 0.0063353897 0.0048550000 0.0004030000 0.0022780000 0.0000000000 0.0000040000 0.0010040000 36437133 96830484 509673472 3.6498863697 3.9849071503 3.8808584213 409 1311867184.0647850037 0.0769062489 0.0654456135 0.0789754093 0.0063333082 0.0063470000 0.0004010000 0.0029770000 0.0000040000 0.0000040000 0.0018020000 36440861 96830484 509673472 3.6527254581 3.9844279289 3.8810434341 410 1311867184.0968890190 0.0769299492 0.0654736241 0.0789754093 0.0063257386 0.0069560000 0.0004020000 0.0043880000 0.0000000000 0.0000040000 0.0009990000 36444477 96830484 509673472 3.6539461613 3.9841940403 3.8814573288 411 1311867184.1312260628 0.0778376088 0.0655037068 0.0789754093 0.0063200219 0.0071960000 0.0004070000 0.0043880000 0.0000050000 0.0000040000 0.0012480000 36448205 96830484 509673472 3.6542799473 3.9836905003 3.8820731640 412 1311867184.1650640965 0.0781952292 0.0655345115 0.0789754093 0.0063124955 0.0069380000 0.0004020000 0.0043840000 0.0000010000 0.0000040000 0.0010020000 36451877 96830484 509673472 3.6552758217 3.9830403328 3.8824238777 413 1311867184.1969559193 0.0778427720 0.0655643135 0.0789754093 0.0063067155 0.0077880000 0.0004010000 0.0043980000 0.0000040000 0.0000050000 0.0018110000 36455605 96830484 509673472 3.6577098370 3.9842305183 3.8827590942 414 1311867184.2309360504 0.0759910271 0.0655894988 0.0789754093 0.0063016101 0.0055650000 0.0004160000 0.0030000000 0.0000000000 0.0000040000 0.0010010000 36459333 96830484 509673472 3.6629738808 3.9841692448 3.8832409382 415 1311867184.2681369781 0.0771804377 0.0656174288 0.0789754093 0.0063020814 0.0072210000 0.0004060000 0.0044030000 0.0000050000 0.0000040000 0.0012490000 36463173 96830484 509673472 3.6626262665 3.9817855358 3.8831655979 416 1311867184.2983899117 0.0779989213 0.0656471920 0.0789754093 0.0062959465 0.0070270000 0.0004070000 0.0044130000 0.0000010000 0.0000050000 0.0010040000 36466789 96830484 509673472 3.6636219025 3.9828541279 3.8839008808 417 1311867184.3314700127 0.0773380026 0.0656752275 0.0789754093 0.0062884124 0.0078330000 0.0004150000 0.0043960000 0.0000040000 0.0000040000 0.0018220000 36470461 96830484 509673472 3.6666698456 3.9834575653 3.8842153549 418 1311867184.3697841167 0.0776626617 0.0657039056 0.0789754093 0.0062909424 0.0056310000 0.0004040000 0.0029970000 0.0000010000 0.0000040000 0.0010540000 36474301 96830484 509673472 3.6681506634 3.9818952084 3.8840961456 419 1311867184.4000220299 0.0775441751 0.0657321640 0.0789754093 0.0063245003 0.0069140000 0.0004010000 0.0040430000 0.0000040000 0.0000040000 0.0012980000 36477917 96830484 509673472 3.6718397141 3.9827790260 3.8846840858 420 1311867184.4310610294 0.0771291628 0.0657592997 0.0789754093 0.0063198640 0.0049230000 0.0004040000 0.0022940000 0.0000000000 0.0000040000 0.0010510000 36481589 96830484 509673472 3.6751546860 3.9832556248 3.8853244781 421 1311867184.4655809402 0.0790885687 0.0657909607 0.0790885687 0.0063184214 0.0078910000 0.0004030000 0.0044080000 0.0000040000 0.0000050000 0.0018970000 36485317 96830484 509673472 3.6741621494 3.9808380604 3.8851153851 422 1311867184.5037670135 0.0784454644 0.0658209477 0.0790885687 0.0063598666 0.0059520000 0.0004020000 0.0033350000 0.0000000000 0.0000040000 0.0010420000 36489157 96830484 509673472 3.6772513390 3.9799489975 3.8842751980 423 1311867184.5310881138 0.0780299976 0.0658498107 0.0790885687 0.0063794495 0.0062260000 0.0004030000 0.0033530000 0.0000050000 0.0000040000 0.0013020000 36492717 96830484 509673472 3.6804058552 3.9803936481 3.8837623596 424 1311867184.5682930946 0.0773919076 0.0658770326 0.0790885687 0.0063733174 0.0070280000 0.0004040000 0.0043910000 0.0000010000 0.0000040000 0.0010420000 36496557 96830484 509673472 3.6840012074 3.9805729389 3.8831946850 425 1311867184.6018071175 0.0775209516 0.0659044300 0.0790885687 0.0063663274 0.0077640000 0.0004030000 0.0042660000 0.0000040000 0.0000040000 0.0018960000 36500229 96830484 509673472 3.6849911213 3.9791517258 3.8824987411 426 1311867184.6367399693 0.0799483359 0.0659373970 0.0799483359 0.0063629888 0.0048980000 0.0004000000 0.0022750000 0.0000000000 0.0000040000 0.0010450000 36504013 96830484 509673472 3.6846101284 3.9797887802 3.8833491802 427 1311867184.6662440300 0.0770815164 0.0659634956 0.0799483359 0.0063807743 0.0072520000 0.0004010000 0.0043740000 0.0000040000 0.0000040000 0.0012990000 36507573 96830484 509673472 3.6905238628 3.9786992073 3.8831064701 428 1311867184.6994929314 0.0779914558 0.0659915983 0.0799483359 0.0063759040 0.0055620000 0.0004040000 0.0029730000 0.0000010000 0.0000050000 0.0009960000 36511357 96830484 509673472 3.6911883354 3.9772558212 3.8833043575 429 1311867184.7359158993 0.0775475204 0.0660185352 0.0799483359 0.0063754650 0.0070570000 0.0004010000 0.0036730000 0.0000040000 0.0000050000 0.0017940000 36515029 96830484 509673472 3.6949601173 3.9782369137 3.8837337494 430 1311867184.7690689564 0.0795659572 0.0660500408 0.0799483359 0.0063801182 0.0070250000 0.0004060000 0.0043710000 0.0000000000 0.0000050000 0.0009860000 36518813 96830484 509673472 3.6946818829 3.9760177135 3.8847279549 431 1311867184.8001279831 0.0786580592 0.0660792938 0.0799483359 0.0063809612 0.0061870000 0.0004060000 0.0033190000 0.0000040000 0.0000040000 0.0012400000 36522429 96830484 509673472 3.6983335018 3.9758288860 3.8851413727 432 1311867184.8348441124 0.0783160254 0.0661076195 0.0799483359 0.0063738809 0.0069610000 0.0004010000 0.0043860000 0.0000010000 0.0000050000 0.0009810000 36526101 96830484 509673472 3.7018790245 3.9760088921 3.8861846924 433 1311867184.8690660000 0.0772807226 0.0661334235 0.0799483359 0.0063669725 0.0078020000 0.0004050000 0.0043850000 0.0000050000 0.0000050000 0.0017970000 36529829 96830484 509673472 3.7054851055 3.9748270512 3.8867888451 434 1311867184.9055209160 0.0761424601 0.0661564858 0.0799483359 0.0063613771 0.0069710000 0.0004040000 0.0043800000 0.0000010000 0.0000040000 0.0009870000 36533501 96830484 509673472 3.7099702358 3.9745657444 3.8876368999 435 1311867184.9332280159 0.0756585822 0.0661783297 0.0799483359 0.0063572545 0.0072450000 0.0004060000 0.0043920000 0.0000050000 0.0000040000 0.0012380000 36537005 96830484 509673472 3.7140097618 3.9752771854 3.8892323971 436 1311867184.9656410217 0.0760865733 0.0662010550 0.0799483359 0.0063559097 0.0062840000 0.0004020000 0.0036890000 0.0000000000 0.0000050000 0.0009890000 36540677 96830484 509673472 3.7154910564 3.9738237858 3.8904731274 437 1311867184.9983251095 0.0755893141 0.0662225384 0.0799483359 0.0063525511 0.0078440000 0.0004040000 0.0044050000 0.0000050000 0.0000040000 0.0017910000 36544405 96830484 509673472 3.7186844349 3.9727399349 3.8914537430 438 1311867185.0360550880 0.0741522610 0.0662406428 0.0799483359 0.0063454601 0.0062730000 0.0004050000 0.0036860000 0.0000000000 0.0000040000 0.0009800000 36548189 96830484 509673472 3.7242202759 3.9727478027 3.8928797245 439 1311867185.0652348995 0.0721729919 0.0662541561 0.0799483359 0.0063435772 0.0055160000 0.0004040000 0.0026490000 0.0000040000 0.0000040000 0.0012390000 36551805 96830484 509673472 3.7294447422 3.9707856178 3.8939146996 440 1311867185.0991280079 0.0737304166 0.0662711476 0.0799483359 0.0063404181 0.0062970000 0.0004120000 0.0036920000 0.0000000000 0.0000040000 0.0009850000 36555533 96830484 509673472 3.7301702499 3.9720575809 3.8955287933 441 1311867185.1360778809 0.0742032006 0.0662891342 0.0799483359 0.0063368045 0.0067440000 0.0004070000 0.0033320000 0.0000040000 0.0000040000 0.0017770000 36559317 96830484 509673472 3.7326133251 3.9717147350 3.8973126411 442 1311867185.1648709774 0.0732415989 0.0663048637 0.0799483359 0.0063318837 0.0070090000 0.0004010000 0.0043990000 0.0000010000 0.0000040000 0.0009790000 36562933 96830484 509673472 3.7367889881 3.9709208012 3.8988537788 443 1311867185.2000720501 0.0734387934 0.0663209674 0.0799483359 0.0063267225 0.0066320000 0.0004050000 0.0036980000 0.0000040000 0.0000040000 0.0012340000 36566605 96830484 509673472 3.7403063774 3.9708926678 3.9005711079 444 1311867185.2342920303 0.0734033361 0.0663369187 0.0799483359 0.0063254032 0.0056270000 0.0004030000 0.0029930000 0.0000000000 0.0000040000 0.0009800000 36570389 96830484 509673472 3.7442679405 3.9708619118 3.9025323391 445 1311867185.2663950920 0.0717901587 0.0663491731 0.0799483359 0.0063199078 0.0083870000 0.0005340000 0.0035850000 0.0000120000 0.0000110000 0.0019470000 36574117 96830484 509673472 3.7488884926 3.9679427147 3.9035711288 446 1311867185.2970550060 0.0719534159 0.0663617387 0.0799483359 0.0063310193 0.0057350000 0.0004450000 0.0026980000 0.0000010000 0.0000050000 0.0010060000 36577733 96830484 509673472 3.7516334057 3.9690635204 3.9052007198 447 1311867185.3360140324 0.0719911233 0.0663743324 0.0799483359 0.0063239395 0.0075540000 0.0004240000 0.0044730000 0.0000050000 0.0000040000 0.0012340000 36581573 96830484 509673472 3.7550027370 3.9683358669 3.9069044590 448 1311867185.3681778908 0.0715787038 0.0663859493 0.0799483359 0.0063172830 0.0075400000 0.0005130000 0.0035930000 0.0000010000 0.0000100000 0.0010990000 36585301 96830484 509673472 3.7581923008 3.9668695927 3.9079732895 449 1311867185.4036509991 0.0714011043 0.0663971189 0.0799483359 0.0063129992 0.0078600000 0.0004500000 0.0041430000 0.0000060000 0.0000050000 0.0017990000 36589029 96830484 509673472 3.7612357140 3.9668948650 3.9090180397 450 1311867185.4386389256 0.0728332475 0.0664114214 0.0799483359 0.0063088589 0.0070140000 0.0004110000 0.0044240000 0.0000010000 0.0000040000 0.0009690000 36592757 96830484 509673472 3.7624983788 3.9676256180 3.9105896950 451 1311867185.4655449390 0.0713470653 0.0664223652 0.0799483359 0.0063034102 0.0089000000 0.0005130000 0.0046790000 0.0000080000 0.0000080000 0.0013450000 36596261 96830484 509673472 3.7672173977 3.9656198025 3.9113874435 452 1311867185.5013909340 0.0695523769 0.0664292900 0.0799483359 0.0063218699 0.0060130000 0.0004350000 0.0030700000 0.0000000000 0.0000060000 0.0009930000 36600045 96830484 509673472 3.7720432281 3.9645676613 3.9115688801 453 1311867185.5336329937 0.0711995885 0.0664398205 0.0799483359 0.0063464023 0.0078380000 0.0004090000 0.0044370000 0.0000030000 0.0000030000 0.0017600000 36603717 96830484 509673472 3.7730579376 3.9659695625 3.9127109051 454 1311867185.5666799545 0.0709341019 0.0664497198 0.0799483359 0.0063398912 0.0069450000 0.0004040000 0.0044090000 0.0000000000 0.0000040000 0.0009590000 36607445 96830484 509673472 3.7766418457 3.9646434784 3.9135234356 455 1311867185.5970540047 0.0699569359 0.0664574279 0.0799483359 0.0063383015 0.0050800000 0.0004020000 0.0022960000 0.0000040000 0.0000040000 0.0012110000 36611061 96830484 509673472 3.7800650597 3.9632441998 3.9137454033 456 1311867185.6329469681 0.0715939775 0.0664686923 0.0799483359 0.0063619729 0.0094360000 0.0005890000 0.0038040000 0.0000010000 0.0000150000 0.0014720000 36614845 96830484 509673472 3.7820708752 3.9652016163 3.9146533012 457 1311867185.6664180756 0.0698456913 0.0664760818 0.0799483359 0.0063687618 0.0085130000 0.0004630000 0.0045670000 0.0000070000 0.0000060000 0.0018100000 36618517 96830484 509673472 3.7876977921 3.9635643959 3.9153907299 458 1311867185.6973390579 0.0695670918 0.0664828307 0.0799483359 0.0063619348 0.0064540000 0.0004210000 0.0037490000 0.0000010000 0.0000040000 0.0009630000 36622189 96830484 509673472 3.7903397083 3.9625456333 3.9160416126 459 1311867185.7351899147 0.0697952658 0.0664900474 0.0799483359 0.0063605169 0.0053470000 0.0004120000 0.0025280000 0.0000040000 0.0000030000 0.0012060000 36625973 96830484 509673472 3.7943654060 3.9645612240 3.9176788330 460 1311867185.7649769783 0.0701789260 0.0664980667 0.0799483359 0.0063573364 0.0085890000 0.0005140000 0.0046790000 0.0000010000 0.0000080000 0.0010820000 36629645 96830484 509673472 3.7963678837 3.9620692730 3.9188992977 461 1311867185.7989649773 0.0706046149 0.0665069746 0.0799483359 0.0063648913 0.0094690000 0.0004990000 0.0046820000 0.0000110000 0.0000090000 0.0019160000 36633317 96830484 509673472 3.7987997532 3.9610552788 3.9197318554 462 1311867185.8327999115 0.0695933700 0.0665136551 0.0799483359 0.0063590551 0.0068560000 0.0005030000 0.0028590000 0.0000010000 0.0000110000 0.0011390000 36637101 96830484 509673472 3.8031988144 3.9614648819 3.9206240177 463 1311867185.8649098873 0.0695358366 0.0665201825 0.0799483359 0.0063529857 0.0060740000 0.0004490000 0.0027230000 0.0000060000 0.0000050000 0.0012350000 36640773 96830484 509673472 3.8056030273 3.9600088596 3.9216592312 464 1311867185.9030420780 0.0689893141 0.0665255039 0.0799483359 0.0063482878 0.0070540000 0.0004180000 0.0044380000 0.0000000000 0.0000050000 0.0009660000 36644557 96830484 509673472 3.8085455894 3.9596028328 3.9223449230 465 1311867185.9396789074 0.0704806149 0.0665340095 0.0799483359 0.0063464306 0.0077570000 0.0004040000 0.0044200000 0.0000040000 0.0000040000 0.0017220000 36648397 96830484 509673472 3.8089866638 3.9595293999 3.9241383076 466 1311867185.9650609493 0.0694602728 0.0665402890 0.0799483359 0.0063579054 0.0069700000 0.0004030000 0.0044150000 0.0000010000 0.0000040000 0.0009470000 36651789 96830484 509673472 3.8117189407 3.9571144581 3.9249763489 467 1311867186.0039470196 0.0687661469 0.0665450553 0.0799483359 0.0063531899 0.0062600000 0.0004610000 0.0030960000 0.0000030000 0.0000030000 0.0012040000 36655685 96830484 509673472 3.8147428036 3.9551327229 3.9259548187 468 1311867186.0396919250 0.0704622939 0.0665534255 0.0799483359 0.0063660176 0.0077130000 0.0005120000 0.0032500000 0.0000010000 0.0000100000 0.0011950000 36659469 96830484 509673472 3.8148288727 3.9570319653 3.9273743629 469 1311867186.0653240681 0.0694117770 0.0665595201 0.0799483359 0.0063702473 0.0070390000 0.0004540000 0.0031130000 0.0000050000 0.0000050000 0.0017590000 36663029 96830484 509673472 3.8167693615 3.9542090893 3.9280521870 470 1311867186.1047339439 0.0698094070 0.0665664347 0.0799483359 0.0063635748 0.0064220000 0.0004190000 0.0037240000 0.0000010000 0.0000050000 0.0009470000 36666869 96830484 509673472 3.8171119690 3.9527697563 3.9286117554 471 1311867186.1361179352 0.0691898242 0.0665720045 0.0799483359 0.0063588321 0.0072810000 0.0004050000 0.0044240000 0.0000040000 0.0000040000 0.0012050000 36670485 96830484 509673472 3.8197660446 3.9523954391 3.9291822910 472 1311867186.1649448872 0.0696825683 0.0665785947 0.0799483359 0.0063526038 0.0062860000 0.0004040000 0.0037140000 0.0000000000 0.0000030000 0.0009470000 36674101 96830484 509673472 3.8204319477 3.9513027668 3.9296917915 473 1311867186.2044749260 0.0685050488 0.0665826676 0.0799483359 0.0063469474 0.0077870000 0.0004040000 0.0044250000 0.0000040000 0.0000040000 0.0017220000 36677997 96830484 509673472 3.8236155510 3.9500696659 3.9297661781 474 1311867186.2359659672 0.0690721720 0.0665879197 0.0799483359 0.0063436573 0.0071230000 0.0004080000 0.0044220000 0.0000010000 0.0000040000 0.0009480000 36681613 96830484 509673472 3.8245320320 3.9501247406 3.9305310249 475 1311867186.2674899101 0.0698501989 0.0665947876 0.0799483359 0.0063377301 0.0088980000 0.0005080000 0.0046930000 0.0000090000 0.0000080000 0.0013300000 36685285 96830484 509673472 3.8255538940 3.9482996464 3.9312303066 476 1311867186.3030838966 0.0691487566 0.0666001531 0.0799483359 0.0063322455 0.0057460000 0.0004360000 0.0027090000 0.0000010000 0.0000050000 0.0009580000 36689069 96830484 509673472 3.8286306858 3.9482369423 3.9318470955 477 1311867186.3349270821 0.0694714263 0.0666061726 0.0799483359 0.0063267158 0.0091360000 0.0005080000 0.0046190000 0.0000080000 0.0000080000 0.0017980000 36692685 96830484 509673472 3.8305795193 3.9486656189 3.9329967499 478 1311867186.3670160770 0.0682074130 0.0666095224 0.0799483359 0.0063316516 0.0060670000 0.0004390000 0.0030760000 0.0000000000 0.0000050000 0.0009550000 36696301 96830484 509673472 3.8337314129 3.9458332062 3.9334595203 479 1311867186.4019849300 0.0688769743 0.0666142561 0.0799483359 0.0063358381 0.0056210000 0.0004150000 0.0026610000 0.0000040000 0.0000040000 0.0012040000 36700029 96830484 509673472 3.8347339630 3.9464964867 3.9345281124 480 1311867186.4360210896 0.0688851252 0.0666189871 0.0799483359 0.0063348262 0.0090790000 0.0005190000 0.0047420000 0.0000010000 0.0000110000 0.0010770000 36703757 96830484 509673472 3.8376777172 3.9470462799 3.9362852573 481 1311867186.4659481049 0.0681821480 0.0666222369 0.0799483359 0.0063326183 0.0077020000 0.0004650000 0.0037970000 0.0000070000 0.0000050000 0.0017420000 36707373 96830484 509673472 3.8399436474 3.9445700645 3.9371705055 482 1311867186.5031139851 0.0684135556 0.0666259534 0.0799483359 0.0063277451 0.0054400000 0.0004230000 0.0026750000 0.0000010000 0.0000050000 0.0009440000 36711213 96830484 509673472 3.8410282135 3.9430623055 3.9379949570 483 1311867186.5363171101 0.0683399662 0.0666295021 0.0799483359 0.0063243859 0.0071100000 0.0004120000 0.0040870000 0.0000040000 0.0000040000 0.0012280000 36714885 96830484 509673472 3.8440086842 3.9448370934 3.9395470619 484 1311867186.5651130676 0.0689655617 0.0666343286 0.0799483359 0.0063229743 0.0061060000 0.0004110000 0.0033750000 0.0000010000 0.0000040000 0.0009760000 36718501 96830484 509673472 3.8445413113 3.9425208569 3.9402716160 485 1311867186.6014220715 0.0694555268 0.0666401455 0.0799483359 0.0063174644 0.0072480000 0.0004050000 0.0037150000 0.0000030000 0.0000040000 0.0017750000 36722285 96830484 509673472 3.8459336758 3.9417538643 3.9404881001 486 1311867186.6362628937 0.0699932426 0.0666470449 0.0799483359 0.0063110670 0.0071410000 0.0004080000 0.0044360000 0.0000000000 0.0000040000 0.0009750000 36726013 96830484 509673472 3.8473050594 3.9416954517 3.9407145977 487 1311867186.6650478840 0.0699859113 0.0666539009 0.0799483359 0.0063066370 0.0074100000 0.0004060000 0.0044300000 0.0000040000 0.0000040000 0.0012280000 36729573 96830484 509673472 3.8493885994 3.9421150684 3.9408483505 488 1311867186.7043809891 0.0695047379 0.0666597428 0.0799483359 0.0063247217 0.0060720000 0.0004100000 0.0033630000 0.0000010000 0.0000040000 0.0009720000 36733525 96830484 509673472 3.8518710136 3.9417970181 3.9404487610 489 1311867186.7337749004 0.0700896010 0.0666667568 0.0799483359 0.0063313837 0.0103370000 0.0005940000 0.0030850000 0.0000150000 0.0000150000 0.0024660000 36737085 96830484 509673472 3.8528602123 3.9432442188 3.9404075146 490 1311867186.7673180103 0.0705988407 0.0666747815 0.0799483359 0.0063263578 0.0064050000 0.0004720000 0.0027740000 0.0000010000 0.0000060000 0.0010400000 36740813 96830484 509673472 3.8543326855 3.9442586899 3.9406266212 491 1311867186.8047299385 0.0695900545 0.0666807189 0.0799483359 0.0063294308 0.0069240000 0.0004270000 0.0037510000 0.0000040000 0.0000040000 0.0012280000 36744653 96830484 509673472 3.8568408489 3.9425885677 3.9397232533 492 1311867186.8340749741 0.0709540620 0.0666894045 0.0799483359 0.0063312654 0.0070810000 0.0005070000 0.0028740000 0.0000010000 0.0000090000 0.0010980000 36748213 96830484 509673472 3.8570687771 3.9453668594 3.9397094250 493 1311867186.8775999546 0.0711534247 0.0666984593 0.0799483359 0.0063251552 0.0084860000 0.0004410000 0.0045300000 0.0000050000 0.0000040000 0.0018070000 36752221 96830484 509673472 3.8598968983 3.9455790520 3.9398169518 494 1311867186.9052100182 0.0706095770 0.0667063766 0.0799483359 0.0063232872 0.0091540000 0.0005140000 0.0047640000 0.0000010000 0.0000080000 0.0011010000 36755725 96830484 509673472 3.8627898693 3.9464995861 3.9397902489 495 1311867186.9334239960 0.0711191297 0.0667152912 0.0799483359 0.0063174244 0.0065080000 0.0004410000 0.0031100000 0.0000050000 0.0000050000 0.0012620000 36759397 96830484 509673472 3.8642780781 3.9474325180 3.9396235943 496 1311867186.9663379192 0.0715860054 0.0667251112 0.0799483359 0.0063175671 0.0081960000 0.0004280000 0.0050940000 0.0000000000 0.0000040000 0.0009820000 36763013 96830484 509673472 3.8669455051 3.9493808746 3.9399209023 497 1311867187.0017139912 0.0723565519 0.0667364421 0.0799483359 0.0063206915 0.0099520000 0.0005970000 0.0047880000 0.0000080000 0.0000080000 0.0019450000 36766629 96830484 509673472 3.8684394360 3.9490256310 3.9396002293 498 1311867187.0336461067 0.0713236555 0.0667456534 0.0799483359 0.0063168551 0.0070130000 0.0004650000 0.0038590000 0.0000000000 0.0000050000 0.0009870000 36770301 96830484 509673472 3.8726570606 3.9495613575 3.9390952587 499 1311867187.0749349594 0.0733684525 0.0667589255 0.0799483359 0.0063197673 0.0075810000 0.0004350000 0.0045430000 0.0000040000 0.0000030000 0.0012230000 36774253 96830484 509673472 3.8739514351 3.9526481628 3.9395887852 500 1311867187.1016030312 0.0732315853 0.0667718708 0.0799483359 0.0063150517 0.0065610000 0.0004200000 0.0038090000 0.0000010000 0.0000040000 0.0009710000 36777813 96830484 509673472 3.8766112328 3.9529676437 3.9397392273 501 1311867187.1342070103 0.0738038048 0.0667859066 0.0799483359 0.0063160700 0.0098410000 0.0005150000 0.0047650000 0.0000080000 0.0000080000 0.0019340000 36781485 96830484 509673472 3.8778970242 3.9501221180 3.9392879009 502 1311867187.1710209846 0.0740549341 0.0668003868 0.0799483359 0.0063215015 0.0076620000 0.0004380000 0.0045560000 0.0000010000 0.0000050000 0.0009670000 36785269 96830484 509673472 3.8813242912 3.9522075653 3.9394752979 503 1311867187.2041370869 0.0741936564 0.0668150851 0.0799483359 0.0063202245 0.0067950000 0.0004240000 0.0037730000 0.0000040000 0.0000040000 0.0012100000 36788997 96830484 509673472 3.8852286339 3.9539978504 3.9393453598 504 1311867187.2331659794 0.0738567784 0.0668290567 0.0799483359 0.0063186743 0.0061220000 0.0004210000 0.0033820000 0.0000010000 0.0000040000 0.0009530000 36792613 96830484 509673472 3.8864583969 3.9511184692 3.9384908676 505 1311867187.2707629204 0.0729755163 0.0668412279 0.0799483359 0.0063247682 0.0097770000 0.0005220000 0.0047330000 0.0000080000 0.0000070000 0.0019180000 36796397 96830484 509673472 3.8903353214 3.9541060925 3.9380822182 506 1311867187.3015060425 0.0720662922 0.0668515541 0.0799483359 0.0063274295 0.0065700000 0.0004430000 0.0034380000 0.0000000000 0.0000040000 0.0009650000 36800069 96830484 509673472 3.8925302029 3.9534816742 3.9376587868 507 1311867187.3336570263 0.0725154057 0.0668627254 0.0799483359 0.0063226520 0.0057400000 0.0004260000 0.0026730000 0.0000040000 0.0000040000 0.0012140000 36803685 96830484 509673472 3.8921325207 3.9513883591 3.9369053841 508 1311867187.3707590103 0.0717577636 0.0668723613 0.0799483359 0.0063174069 0.0089460000 0.0005190000 0.0047080000 0.0000020000 0.0000080000 0.0010940000 36807525 96830484 509673472 3.8946447372 3.9517531395 3.9364397526 509 1311867187.4033529758 0.0718243569 0.0668820902 0.0799483359 0.0063156053 0.0084680000 0.0004470000 0.0045230000 0.0000040000 0.0000050000 0.0017510000 36811253 96830484 509673472 3.8956222534 3.9522528648 3.9357428551 510 1311867187.4335899353 0.0703558773 0.0668889016 0.0799483359 0.0063165042 0.0062160000 0.0004260000 0.0034010000 0.0000000000 0.0000040000 0.0009550000 36814869 96830484 509673472 3.8988621235 3.9512543678 3.9350297451 511 1311867187.4763159752 0.0724373758 0.0668997596 0.0799483359 0.0063198524 0.0067990000 0.0004240000 0.0037450000 0.0000030000 0.0000030000 0.0012210000 36818821 96830484 509673472 3.8991224766 3.9518616199 3.9345233440 512 1311867187.5056400299 0.0726772621 0.0669110438 0.0799483359 0.0063171397 0.0080670000 0.0005240000 0.0036240000 0.0000010000 0.0000080000 0.0010830000 36822381 96830484 509673472 3.9012620449 3.9503710270 3.9336411953 513 1311867187.5342190266 0.0719688013 0.0669209030 0.0799483359 0.0063129154 0.0098680000 0.0005400000 0.0047080000 0.0000070000 0.0000080000 0.0019010000 36875149 96830484 509673472 3.9054830074 3.9503569603 3.9327824116 514 1311867187.5709679127 0.0721623451 0.0669311004 0.0799483359 0.0063071180 0.0065950000 0.0004470000 0.0034480000 0.0000010000 0.0000050000 0.0009620000 36981333 96830484 509673472 3.9089760780 3.9506487846 3.9317963123 515 1311867187.6045789719 0.0732330978 0.0669433372 0.0799483359 0.0063275670 0.0054140000 0.0004250000 0.0023300000 0.0000040000 0.0000030000 0.0012020000 36985117 96830484 509673472 3.9098529816 3.9513945580 3.9304127693 516 1311867187.6353919506 0.0729058757 0.0669548925 0.0799483359 0.0063229800 0.0072130000 0.0004140000 0.0044670000 0.0000000000 0.0000040000 0.0009480000 36988733 96830484 509673472 3.9125175476 3.9497861862 3.9289608002 517 1311867187.6707689762 0.0727277175 0.0669660586 0.0799483359 0.0063283373 0.0093620000 0.0005970000 0.0027250000 0.0000150000 0.0000160000 0.0022890000 36992461 96830484 509673472 3.9161448479 3.9515922070 3.9280009270 518 1311867187.7035770416 0.0716073811 0.0669750186 0.0799483359 0.0063252116 0.0079830000 0.0004640000 0.0045650000 0.0000010000 0.0000060000 0.0009870000 36996189 96830484 509673472 3.9209411144 3.9519934654 3.9272422791 519 1311867187.7345480919 0.0721777678 0.0669850432 0.0799483359 0.0063313836 0.0075990000 0.0004340000 0.0044800000 0.0000040000 0.0000040000 0.0012140000 36999581 96830484 509673472 3.9205484390 3.9492955208 3.9257662296 520 1311867187.7707819939 0.0721281916 0.0669949339 0.0799483359 0.0063351668 0.0072500000 0.0004320000 0.0044640000 0.0000010000 0.0000040000 0.0009660000 37003365 96830484 509673472 3.9229784012 3.9524219036 3.9250123501 521 1311867187.8017508984 0.0714857280 0.0670035534 0.0799483359 0.0063327302 0.0086630000 0.0005260000 0.0032760000 0.0000100000 0.0000100000 0.0019900000 37007037 96830484 509673472 3.9264898300 3.9524950981 3.9240627289 522 1311867187.8339610100 0.0720687360 0.0670132569 0.0799483359 0.0063284397 0.0077310000 0.0004580000 0.0045560000 0.0000010000 0.0000050000 0.0009840000 37010709 96830484 509673472 3.9273214340 3.9522688389 3.9231302738 523 1311867187.8708090782 0.0717772096 0.0670223657 0.0799483359 0.0063283234 0.0061100000 0.0004290000 0.0030490000 0.0000030000 0.0000030000 0.0012140000 37014493 96830484 509673472 3.9302144051 3.9538552761 3.9225201607 524 1311867187.9038810730 0.0725516304 0.0670329178 0.0799483359 0.0063291228 0.0074880000 0.0005190000 0.0032570000 0.0000020000 0.0000100000 0.0010720000 37018277 96830484 509673472 3.9313035011 3.9541399479 3.9218392372 525 1311867187.9363000393 0.0702793896 0.0670391015 0.0799483359 0.0063250058 0.0085330000 0.0004520000 0.0045710000 0.0000050000 0.0000050000 0.0017750000 37021893 96830484 509673472 3.9370691776 3.9543578625 3.9209599495 526 1311867187.9713420868 0.0705905110 0.0670458533 0.0799483359 0.0063251638 0.0085290000 0.0005240000 0.0046870000 0.0000010000 0.0000080000 0.0010820000 37025677 96830484 509673472 3.9391715527 3.9530489445 3.9195926189 527 1311867188.0047569275 0.0710808262 0.0670535098 0.0799483359 0.0063434140 0.0078680000 0.0004450000 0.0045550000 0.0000050000 0.0000050000 0.0012380000 37029405 96830484 509673472 3.9421403408 3.9543476105 3.9185376167 528 1311867188.0333108902 0.0714019537 0.0670617454 0.0799483359 0.0063489679 0.0053910000 0.0004190000 0.0026730000 0.0000010000 0.0000050000 0.0009680000 37032965 96830484 509673472 3.9449410439 3.9553017616 3.9177556038 529 1311867188.0698699951 0.0696797967 0.0670666945 0.0799483359 0.0063450383 0.0081990000 0.0005330000 0.0035510000 0.0000070000 0.0000080000 0.0019150000 37036693 96830484 509673472 3.9504404068 3.9529204369 3.9163882732 530 1311867188.1088800430 0.0709436983 0.0670740096 0.0799483359 0.0063436164 0.0065210000 0.0004400000 0.0034570000 0.0000010000 0.0000050000 0.0009750000 37040645 96830484 509673472 3.9517679214 3.9532735348 3.9147734642 531 1311867188.1359970570 0.0694721416 0.0670785259 0.0799483359 0.0063488598 0.0090800000 0.0005150000 0.0047220000 0.0000080000 0.0000070000 0.0013470000 37044149 96830484 509673472 3.9551515579 3.9556264877 3.9136691093 532 1311867188.1703350544 0.0707222670 0.0670853750 0.0799483359 0.0063466658 0.0077910000 0.0004480000 0.0045380000 0.0000010000 0.0000050000 0.0009850000 37047877 96830484 509673472 3.9578096867 3.9539740086 3.9123442173 533 1311867188.2026720047 0.0709534660 0.0670926322 0.0799483359 0.0063466992 0.0064250000 0.0004300000 0.0026980000 0.0000030000 0.0000040000 0.0017770000 37051605 96830484 509673472 3.9596366882 3.9532999992 3.9107980728 534 1311867188.2352449894 0.0690203682 0.0670962422 0.0799483359 0.0063547356 0.0065820000 0.0004230000 0.0037470000 0.0000010000 0.0000040000 0.0009680000 37055221 96830484 509673472 3.9654154778 3.9549875259 3.9098827839 535 1311867188.2706460953 0.0704251379 0.0671024644 0.0799483359 0.0063529913 0.0091130000 0.0005310000 0.0047130000 0.0000080000 0.0000080000 0.0013500000 37059005 96830484 509673472 3.9675691128 3.9549760818 3.9087839127 536 1311867188.3047339916 0.0708964393 0.0671095427 0.0799483359 0.0063474938 0.0076740000 0.0004480000 0.0045230000 0.0000000000 0.0000050000 0.0009840000 37062789 96830484 509673472 3.9705264568 3.9553453922 3.9075903893 537 1311867188.3398799896 0.0721043348 0.0671188440 0.0799483359 0.0063424088 0.0080680000 0.0004230000 0.0044450000 0.0000040000 0.0000040000 0.0018030000 37066573 96830484 509673472 3.9722485542 3.9561293125 3.9064929485 538 1311867188.3718800545 0.0731735006 0.0671300980 0.0799483359 0.0063475951 0.0072140000 0.0004130000 0.0044250000 0.0000000000 0.0000030000 0.0009800000 37070189 96830484 509673472 3.9739818573 3.9589445591 3.9060866833 539 1311867188.4054470062 0.0718654022 0.0671388834 0.0799483359 0.0063522486 0.0093740000 0.0005290000 0.0047140000 0.0000090000 0.0000080000 0.0013770000 37073861 96830484 509673472 3.9785871506 3.9587934017 3.9055027962 540 1311867188.4398789406 0.0716020837 0.0671471486 0.0799483359 0.0063506363 0.0072790000 0.0004420000 0.0041480000 0.0000000000 0.0000050000 0.0009980000 37077645 96830484 509673472 3.9816670418 3.9582226276 3.9046936035 541 1311867188.4724500179 0.0728488415 0.0671576878 0.0799483359 0.0063561180 0.0063140000 0.0004170000 0.0026700000 0.0000030000 0.0000040000 0.0018000000 37081317 96830484 509673472 3.9835755825 3.9615929127 3.9043366909 542 1311867188.5049159527 0.0722511187 0.0671670852 0.0799483359 0.0063579122 0.0075410000 0.0005180000 0.0032300000 0.0000010000 0.0000090000 0.0011200000 37084989 96830484 509673472 3.9874100685 3.9618926048 3.9040434361 543 1311867188.5389990807 0.0720814839 0.0671761357 0.0799483359 0.0063584411 0.0079030000 0.0005240000 0.0032370000 0.0000090000 0.0000090000 0.0013760000 37088773 96830484 509673472 3.9896192551 3.9610409737 3.9032418728 544 1311867188.5723888874 0.0738826618 0.0671884639 0.0799483359 0.0063784074 0.0074080000 0.0005230000 0.0028820000 0.0000020000 0.0000100000 0.0012420000 37092445 96830484 509673472 3.9911305904 3.9655377865 3.9031329155 545 1311867188.6045958996 0.0731407478 0.0671993855 0.0799483359 0.0063732059 0.0085680000 0.0004620000 0.0045730000 0.0000050000 0.0000050000 0.0018190000 37096117 96830484 509673472 3.9951183796 3.9653344154 3.9031302929 546 1311867188.6398339272 0.0727403611 0.0672095338 0.0799483359 0.0063722502 0.0072680000 0.0004200000 0.0044560000 0.0000010000 0.0000040000 0.0009660000 37099789 96830484 509673472 3.9980299473 3.9635546207 3.9027950764 547 1311867188.6715080738 0.0744422153 0.0672227562 0.0799483359 0.0063774823 0.0071250000 0.0005210000 0.0025170000 0.0000110000 0.0000090000 0.0013730000 37103517 96830484 509673472 3.9986915588 3.9658176899 3.9021227360 548 1311867188.7038300037 0.0745572597 0.0672361404 0.0799483359 0.0063798088 0.0077030000 0.0004490000 0.0045530000 0.0000010000 0.0000060000 0.0010110000 37107189 96830484 509673472 4.0008521080 3.9643082619 3.9013309479 549 1311867188.7393829823 0.0744658709 0.0672493093 0.0799483359 0.0063910520 0.0078830000 0.0004220000 0.0040980000 0.0000040000 0.0000040000 0.0018160000 37110917 96830484 509673472 4.0037951469 3.9636759758 3.9002795219 550 1311867188.7721049786 0.0774940997 0.0672679362 0.0799483359 0.0063881182 0.0073750000 0.0004140000 0.0044350000 0.0000010000 0.0000030000 0.0009870000 37114645 96830484 509673472 4.0038132668 3.9660482407 3.8991434574 551 1311867188.8045220375 0.0773175061 0.0672861750 0.0799483359 0.0063828903 0.0084750000 0.0005190000 0.0035890000 0.0000080000 0.0000080000 0.0013750000 37118373 96830484 509673472 4.0086784363 3.9674637318 3.8983061314 552 1311867188.8402431011 0.0782354772 0.0673060106 0.0799483359 0.0063780353 0.0077700000 0.0004410000 0.0044970000 0.0000010000 0.0000040000 0.0010080000 37122101 96830484 509673472 4.0118579865 3.9661619663 3.8974010944 553 1311867188.8705990314 0.0810811967 0.0673309206 0.0810811967 0.0063799049 0.0071260000 0.0004180000 0.0033710000 0.0000040000 0.0000040000 0.0018200000 37125717 96830484 509673472 4.0117669106 3.9674935341 3.8963057995 554 1311867188.9016311169 0.0818963125 0.0673572119 0.0818963125 0.0063775317 0.0091340000 0.0005160000 0.0046660000 0.0000000000 0.0000080000 0.0011390000 37129389 96830484 509673472 4.0149593353 3.9701421261 3.8951957226 555 1311867188.9401769638 0.0823710337 0.0673842638 0.0823710337 0.0063764230 0.0073200000 0.0005070000 0.0034150000 0.0000050000 0.0000050000 0.0012820000 37133285 96830484 509673472 4.0187888145 3.9689168930 3.8941020966 556 1311867188.9709990025 0.0831387639 0.0674125993 0.0831387639 0.0063764714 0.0073770000 0.0004160000 0.0044110000 0.0000010000 0.0000040000 0.0010160000 37136845 96830484 509673472 4.0207962990 3.9684624672 3.8932967186 557 1311867189.0052258968 0.0831905007 0.0674409258 0.0831905007 0.0063720198 0.0064330000 0.0004050000 0.0026250000 0.0000040000 0.0000030000 0.0018570000 37140629 96830484 509673472 4.0249795914 3.9698221684 3.8927297592 558 1311867189.0400099754 0.0826174840 0.0674681240 0.0831905007 0.0063722948 0.0059530000 0.0004210000 0.0029930000 0.0000000000 0.0000040000 0.0010090000 37144301 96830484 509673472 4.0301890373 3.9689853191 3.8926887512 559 1311867189.0724329948 0.0814288259 0.0674930984 0.0831905007 0.0063696952 0.0072470000 0.0004060000 0.0040430000 0.0000030000 0.0000040000 0.0012640000 37148085 96830484 509673472 4.0344867706 3.9680824280 3.8928103447 560 1311867189.1026360989 0.0804279223 0.0675161963 0.0831905007 0.0063655331 0.0073240000 0.0004070000 0.0043690000 0.0000000000 0.0000030000 0.0010120000 37151701 96830484 509673472 4.0390915871 3.9689183235 3.8934617043 561 1311867189.1417639256 0.0795332417 0.0675376170 0.0831905007 0.0063599644 0.0081850000 0.0004050000 0.0043710000 0.0000040000 0.0000040000 0.0018720000 37155597 96830484 509673472 4.0438203812 3.9691498280 3.8942680359 562 1311867189.1717920303 0.0804332122 0.0675605629 0.0831905007 0.0063563379 0.0062800000 0.0004000000 0.0033350000 0.0000000000 0.0000030000 0.0010200000 37159213 96830484 509673472 4.0438742638 3.9686579704 3.8949360847 563 1311867189.2019069195 0.0794723704 0.0675817207 0.0831905007 0.0063530453 0.0075210000 0.0004090000 0.0043590000 0.0000040000 0.0000040000 0.0012660000 37162829 96830484 509673472 4.0478887558 3.9689888954 3.8961489201 564 1311867189.2390630245 0.0795827806 0.0676029992 0.0831905007 0.0063481572 0.0054940000 0.0004110000 0.0026250000 0.0000000000 0.0000040000 0.0010130000 37166613 96830484 509673472 4.0500769615 3.9686670303 3.8970799446 565 1311867189.2722640038 0.0791183412 0.0676233803 0.0831905007 0.0063443901 0.0101990000 0.0006280000 0.0030230000 0.0000150000 0.0000150000 0.0025310000 37170285 96830484 509673472 4.0525588989 3.9676394463 3.8978893757 566 1311867189.3046789169 0.0797856748 0.0676448684 0.0831905007 0.0063392746 0.0080400000 0.0004710000 0.0044980000 0.0000010000 0.0000070000 0.0010530000 37174013 96830484 509673472 4.0540528297 3.9668385983 3.8987798691 567 1311867189.3397970200 0.0779602379 0.0676630613 0.0831905007 0.0063487948 0.0063080000 0.0004290000 0.0030050000 0.0000040000 0.0000040000 0.0012750000 37177741 96830484 509673472 4.0582375526 3.9652724266 3.8994376659 568 1311867189.3720359802 0.0782305971 0.0676816661 0.0831905007 0.0063774147 0.0072470000 0.0004080000 0.0043660000 0.0000000000 0.0000040000 0.0010050000 37181413 96830484 509673472 4.0612764359 3.9647960663 3.8998768330 569 1311867189.4056949615 0.0786045939 0.0677008629 0.0831905007 0.0063753940 0.0086500000 0.0005100000 0.0035820000 0.0000080000 0.0000080000 0.0020270000 37185141 96830484 509673472 4.0640459061 3.9653277397 3.9011964798 570 1311867189.4405019283 0.0779764578 0.0677188902 0.0831905007 0.0063794866 0.0062660000 0.0004330000 0.0030370000 0.0000010000 0.0000050000 0.0010340000 37188869 96830484 509673472 4.0679197311 3.9631664753 3.9017803669 571 1311867189.4729130268 0.0776548460 0.0677362912 0.0831905007 0.0063745320 0.0081270000 0.0005130000 0.0038630000 0.0000090000 0.0000110000 0.0013890000 37192597 96830484 509673472 4.0721383095 3.9611332417 3.9020922184 572 1311867189.5060400963 0.0783933550 0.0677549224 0.0831905007 0.0063723917 0.0075930000 0.0004280000 0.0044370000 0.0000010000 0.0000050000 0.0010460000 37196269 96830484 509673472 4.0748829842 3.9617180824 3.9024248123 573 1311867189.5394289494 0.0770152360 0.0677710835 0.0831905007 0.0063671791 0.0095650000 0.0005100000 0.0044850000 0.0000080000 0.0000070000 0.0020510000 37199941 96830484 509673472 4.0799312592 3.9592187405 3.9022283554 574 1311867189.5720269680 0.0775869936 0.0677881844 0.0831905007 0.0063638598 0.0076420000 0.0004350000 0.0044140000 0.0000000000 0.0000050000 0.0010360000 37203669 96830484 509673472 4.0819654465 3.9567313194 3.9013013840 575 1311867189.6112909317 0.0782423392 0.0678063656 0.0831905007 0.0063603623 0.0074210000 0.0004050000 0.0043690000 0.0000040000 0.0000030000 0.0012980000 37207509 96830484 509673472 4.0867829323 3.9568855762 3.9011132717 576 1311867189.6424219608 0.0792586058 0.0678262479 0.0831905007 0.0063570746 0.0072750000 0.0004090000 0.0043390000 0.0000010000 0.0000040000 0.0010390000 37211181 96830484 509673472 4.0892829895 3.9564857483 3.9009778500 577 1311867189.6728401184 0.0787951127 0.0678452581 0.0831905007 0.0063518471 0.0088040000 0.0005140000 0.0035430000 0.0000080000 0.0000070000 0.0020460000 37214853 96830484 509673472 4.0931448936 3.9546251297 3.9006950855 578 1311867189.7065870762 0.0805647597 0.0678672641 0.0831905007 0.0063507696 0.0063020000 0.0004270000 0.0030320000 0.0000010000 0.0000060000 0.0010660000 37218525 96830484 509673472 4.0955619812 3.9542179108 3.9008805752 579 1311867189.7401719093 0.0803994611 0.0678889087 0.0831905007 0.0063463013 0.0053880000 0.0004080000 0.0022850000 0.0000040000 0.0000030000 0.0012870000 37222253 96830484 509673472 4.1007003784 3.9546189308 3.9019734859 580 1311867189.7729759216 0.0823408663 0.0679138259 0.0831905007 0.0063425466 0.0089170000 0.0005910000 0.0026710000 0.0000020000 0.0000150000 0.0015420000 37225925 96830484 509673472 4.1019048691 3.9544069767 3.9027099609 581 1311867189.8073968887 0.0808877945 0.0679361563 0.0831905007 0.0063405062 0.0088330000 0.0004660000 0.0045070000 0.0000060000 0.0000060000 0.0019020000 37229653 96830484 509673472 4.1066422462 3.9525794983 3.9034249783 582 1311867189.8405311108 0.0823620707 0.0679609431 0.0831905007 0.0063384478 0.0060890000 0.0004220000 0.0030180000 0.0000000000 0.0000040000 0.0010260000 37233325 96830484 509673472 4.1086339951 3.9528858662 3.9042799473 583 1311867189.8713529110 0.0814171508 0.0679840240 0.0831905007 0.0063347219 0.0057130000 0.0004180000 0.0026380000 0.0000040000 0.0000040000 0.0012800000 37236997 96830484 509673472 4.1131300926 3.9519691467 3.9051103592 584 1311867189.9102680683 0.0818206742 0.0680077169 0.0831905007 0.0063347640 0.0066590000 0.0007520000 0.0031230000 0.0000000000 0.0000040000 0.0010310000 37240837 96830484 509673472 4.1155037880 3.9501163960 3.9050211906 585 1311867189.9402260780 0.0817753226 0.0680312513 0.0831905007 0.0063304944 0.0099830000 0.0005910000 0.0037650000 0.0000110000 0.0000100000 0.0022070000 37244509 96830484 509673472 4.1186938286 3.9503843784 3.9051804543 586 1311867189.9727621078 0.0810473412 0.0680534631 0.0831905007 0.0063251478 0.0065080000 0.0004450000 0.0030850000 0.0000010000 0.0000060000 0.0010380000 37248181 96830484 509673472 4.1234192848 3.9507968426 3.9055907726 587 1311867190.0107009411 0.0812355429 0.0680759198 0.0831905007 0.0063231282 0.0074820000 0.0004220000 0.0043030000 0.0000050000 0.0000040000 0.0012830000 37251965 96830484 509673472 4.1268277168 3.9494502544 3.9055521488 588 1311867190.0402929783 0.0813727453 0.0680985334 0.0831905007 0.0063187221 0.0071890000 0.0004000000 0.0044110000 0.0000010000 0.0000040000 0.0010120000 37255581 96830484 509673472 4.1299295425 3.9492070675 3.9056177139 589 1311867190.0719039440 0.0813430473 0.0681210198 0.0831905007 0.0063138788 0.0080160000 0.0004040000 0.0043920000 0.0000030000 0.0000030000 0.0018480000 37259253 96830484 509673472 4.1330246925 3.9485106468 3.9054906368 590 1311867190.1096539497 0.0891105831 0.0681565954 0.0891105831 0.0063274587 0.0058300000 0.0004060000 0.0029990000 0.0000000000 0.0000030000 0.0010080000 37263093 96830484 509673472 4.1253657341 3.9478292465 3.9037992954 591 1311867190.1396369934 0.0897558779 0.0681931424 0.0897558779 0.0063244782 0.0086890000 0.0005920000 0.0030350000 0.0000100000 0.0000110000 0.0015330000 37266765 96830484 509673472 4.1276769638 3.9484488964 3.9032399654 592 1311867190.1706380844 0.0897723958 0.0682295938 0.0897723958 0.0063318965 0.0061980000 0.0004490000 0.0027210000 0.0000010000 0.0000060000 0.0010470000 37270325 96830484 509673472 4.1303830147 3.9473123550 3.9030485153 593 1311867190.2096021175 0.0902058482 0.0682666533 0.0902058482 0.0063267717 0.0080530000 0.0004160000 0.0043140000 0.0000040000 0.0000040000 0.0018720000 37274221 96830484 509673472 4.1320805550 3.9457533360 3.9015507698 594 1311867190.2394330502 0.0898601785 0.0683030060 0.0902058482 0.0063289019 0.0057780000 0.0004000000 0.0029820000 0.0000010000 0.0000040000 0.0010220000 37277781 96830484 509673472 4.1358566284 3.9472062588 3.9009830952 595 1311867190.2714810371 0.0892664492 0.0683382387 0.0902058482 0.0063317301 0.0074400000 0.0004000000 0.0043760000 0.0000040000 0.0000030000 0.0012950000 37281509 96830484 509673472 4.1394343376 3.9467537403 3.9005479813 596 1311867190.3072700500 0.0902842134 0.0683750608 0.0902842134 0.0063273591 0.0057800000 0.0004040000 0.0029830000 0.0000000000 0.0000040000 0.0010310000 37285293 96830484 509673472 4.1409597397 3.9463288784 3.8999633789 597 1311867190.3414731026 0.0903088748 0.0684118009 0.0903088748 0.0063251337 0.0106080000 0.0005820000 0.0030400000 0.0000150000 0.0000160000 0.0026040000 37289021 96830484 509673472 4.1443219185 3.9469218254 3.9001803398 598 1311867190.3716828823 0.0894261077 0.0684469418 0.0903088748 0.0063253978 0.0071920000 0.0004590000 0.0034530000 0.0000010000 0.0000060000 0.0011020000 37292637 96830484 509673472 4.1486225128 3.9481031895 3.9006056786 599 1311867190.4101090431 0.0909347609 0.0684844841 0.0909347609 0.0063249076 0.0056450000 0.0004220000 0.0023210000 0.0000040000 0.0000040000 0.0013110000 37296421 96830484 509673472 4.1493558884 3.9470722675 3.9003937244 600 1311867190.4394960403 0.0913855135 0.0685226525 0.0913855135 0.0063223200 0.0051290000 0.0004030000 0.0023000000 0.0000000000 0.0000040000 0.0010350000 37300149 96830484 509673472 4.1521739960 3.9487254620 3.9013063908 601 1311867190.4708199501 0.0916107073 0.0685610686 0.0916107073 0.0063184144 0.0092740000 0.0006270000 0.0026690000 0.0000150000 0.0000140000 0.0022460000 37303709 96830484 509673472 4.1546616554 3.9480929375 3.9020433426 602 1311867190.5097529888 0.0916190371 0.0685993708 0.0916190371 0.0063138384 0.0076440000 0.0004420000 0.0041610000 0.0000000000 0.0000050000 0.0010480000 37307661 96830484 509673472 4.1567573547 3.9467179775 3.9021625519 603 1311867190.5405189991 0.0926885083 0.0686393196 0.0926885083 0.0063164598 0.0062980000 0.0004220000 0.0029220000 0.0000050000 0.0000040000 0.0012980000 37311221 96830484 509673472 4.1588492393 3.9478700161 3.9027214050 604 1311867190.5708439350 0.0928937569 0.0686794760 0.0928937569 0.0063123319 0.0078420000 0.0005300000 0.0032450000 0.0000020000 0.0000110000 0.0011540000 37314837 96830484 509673472 4.1610827446 3.9471573830 3.9034469128 605 1311867190.6067750454 0.0929389372 0.0687195743 0.0929389372 0.0063075105 0.0086190000 0.0004470000 0.0044740000 0.0000050000 0.0000060000 0.0019070000 37318621 96830484 509673472 4.1633787155 3.9460165501 3.9035503864 606 1311867190.6389939785 0.0930435956 0.0687597129 0.0930435956 0.0063035656 0.0052020000 0.0004130000 0.0023090000 0.0000000000 0.0000040000 0.0010230000 37322349 96830484 509673472 4.1662302017 3.9467866421 3.9042868614 607 1311867190.6723659039 0.0923567191 0.0687985877 0.0930435956 0.0062995594 0.0077260000 0.0005120000 0.0028660000 0.0000100000 0.0000100000 0.0014370000 37326021 96830484 509673472 4.1698536873 3.9451227188 3.9050550461 608 1311867190.7114980221 0.0927593336 0.0688379969 0.0930435956 0.0062967523 0.0077590000 0.0004380000 0.0044820000 0.0000010000 0.0000050000 0.0010500000 37329861 96830484 509673472 4.1724023819 3.9452474117 3.9057610035 609 1311867190.7392649651 0.0924713761 0.0688768037 0.0930435956 0.0062918890 0.0071470000 0.0004120000 0.0033790000 0.0000040000 0.0000040000 0.0018850000 37333365 96830484 509673472 4.1746969223 3.9449834824 3.9062244892 610 1311867190.7751801014 0.0926431865 0.0689157650 0.0930435956 0.0062874257 0.0074850000 0.0005240000 0.0025050000 0.0000010000 0.0000110000 0.0011790000 37337149 96830484 509673472 4.1770219803 3.9452190399 3.9067697525 611 1311867190.8070900440 0.0931771323 0.0689554726 0.0931771323 0.0062836185 0.0064510000 0.0004320000 0.0027120000 0.0000060000 0.0000060000 0.0013400000 37340877 96830484 509673472 4.1788568497 3.9447121620 3.9075405598 612 1311867190.8414280415 0.0918753967 0.0689929235 0.0931771323 0.0062858829 0.0074590000 0.0005120000 0.0028860000 0.0000010000 0.0000080000 0.0011600000 37344605 96830484 509673472 4.1824831963 3.9431602955 3.9082980156 613 1311867190.8739249706 0.0936383530 0.0690331281 0.0936383530 0.0062823198 0.0086350000 0.0005130000 0.0032320000 0.0000080000 0.0000080000 0.0020510000 37348277 96830484 509673472 4.1827392578 3.9424340725 3.9088358879 614 1311867190.9076139927 0.0937864631 0.0690734430 0.0937864631 0.0062776103 0.0079640000 0.0005120000 0.0032450000 0.0000020000 0.0000100000 0.0011550000 37352005 96830484 509673472 4.1851325035 3.9425485134 3.9096195698 615 1311867190.9393599033 0.0923799500 0.0691113397 0.0937864631 0.0062745115 0.0064100000 0.0004500000 0.0027160000 0.0000050000 0.0000050000 0.0013240000 37355621 96830484 509673472 4.1886839867 3.9404280186 3.9103677273 616 1311867190.9741609097 0.0920193121 0.0691485280 0.0937864631 0.0062702479 0.0056520000 0.0004150000 0.0026710000 0.0000000000 0.0000050000 0.0010240000 37359405 96830484 509673472 4.1914062500 3.9395091534 3.9104919434 617 1311867191.0085949898 0.0930166543 0.0691872122 0.0937864631 0.0062747644 0.0088810000 0.0005070000 0.0039000000 0.0000080000 0.0000080000 0.0019850000 37363133 96830484 509673472 4.1938114166 3.9414660931 3.9115300179 618 1311867191.0396919250 0.0930472240 0.0692258206 0.0937864631 0.0062707651 0.0056540000 0.0004380000 0.0023470000 0.0000000000 0.0000050000 0.0010310000 37366805 96830484 509673472 4.1961302757 3.9412772655 3.9124741554 619 1311867191.0764329433 0.0926725119 0.0692636989 0.0937864631 0.0062682317 0.0084800000 0.0005100000 0.0036100000 0.0000080000 0.0000080000 0.0014130000 37370589 96830484 509673472 4.1979432106 3.9376425743 3.9126210213 620 1311867191.1103041172 0.0937548950 0.0693032009 0.0937864631 0.0062741835 0.0078700000 0.0005100000 0.0032340000 0.0000010000 0.0000100000 0.0011620000 37374317 96830484 509673472 4.2007098198 3.9387362003 3.9138276577 621 1311867191.1388139725 0.0928194523 0.0693410692 0.0937864631 0.0062823737 0.0072980000 0.0004460000 0.0030660000 0.0000060000 0.0000050000 0.0019430000 37377933 96830484 509673472 4.2043347359 3.9383699894 3.9148600101 622 1311867191.1742820740 0.0936741456 0.0693801899 0.0937864631 0.0062785042 0.0059390000 0.0004130000 0.0030270000 0.0000010000 0.0000050000 0.0010250000 37381661 96830484 509673472 4.2056841850 3.9370055199 3.9151985645 623 1311867191.2077920437 0.0936034098 0.0694190715 0.0937864631 0.0062736665 0.0081540000 0.0005150000 0.0032450000 0.0000100000 0.0000100000 0.0014130000 37385389 96830484 509673472 4.2093820572 3.9378008842 3.9162681103 624 1311867191.2408421040 0.0944832414 0.0694592384 0.0944832414 0.0062695948 0.0066740000 0.0004610000 0.0030670000 0.0000010000 0.0000060000 0.0010570000 37389117 96830484 509673472 4.2112560272 3.9376485348 3.9169812202 625 1311867191.2769579887 0.0952337757 0.0695004777 0.0952337757 0.0062663686 0.0062480000 0.0004090000 0.0023230000 0.0000040000 0.0000040000 0.0018920000 37392845 96830484 509673472 4.2133092880 3.9369041920 3.9175226688 626 1311867191.3085029125 0.0953422114 0.0695417584 0.0953422114 0.0062666205 0.0078540000 0.0005100000 0.0028810000 0.0000020000 0.0000100000 0.0012320000 37396349 96830484 509673472 4.2164340019 3.9381279945 3.9183857441 627 1311867191.3404779434 0.0956296846 0.0695833660 0.0956296846 0.0062625401 0.0065840000 0.0004510000 0.0027130000 0.0000050000 0.0000060000 0.0013260000 37400021 96830484 509673472 4.2187275887 3.9378185272 3.9191341400 628 1311867191.3794629574 0.0957332030 0.0696250058 0.0957332030 0.0062588524 0.0064330000 0.0004140000 0.0033860000 0.0000010000 0.0000040000 0.0010250000 37403917 96830484 509673472 4.2202720642 3.9353339672 3.9195256233 629 1311867191.4091579914 0.0953337029 0.0696658782 0.0957332030 0.0062553143 0.0072260000 0.0004060000 0.0033660000 0.0000040000 0.0000040000 0.0019070000 37407477 96830484 509673472 4.2231264114 3.9349908829 3.9201917648 630 1311867191.4415969849 0.0946398899 0.0697055195 0.0957332030 0.0062510188 0.0057090000 0.0004080000 0.0026600000 0.0000010000 0.0000040000 0.0010250000 37411149 96830484 509673472 4.2272725105 3.9361085892 3.9213221073 631 1311867191.4775309563 0.0953606367 0.0697461773 0.0957332030 0.0062514212 0.0091300000 0.0005250000 0.0032390000 0.0000100000 0.0000100000 0.0015580000 37414877 96830484 509673472 4.2278485298 3.9342195988 3.9214661121 632 1311867191.5075590611 0.0953734890 0.0697867269 0.0957332030 0.0062473499 0.0068510000 0.0004500000 0.0030980000 0.0000010000 0.0000050000 0.0010670000 37418437 96830484 509673472 4.2301335335 3.9353108406 3.9222218990 633 1311867191.5390620232 0.0951453000 0.0698267878 0.0957332030 0.0062424465 0.0070450000 0.0004190000 0.0030390000 0.0000040000 0.0000050000 0.0019200000 37422109 96830484 509673472 4.2320747375 3.9344077110 3.9227499962 634 1311867191.5764698982 0.0951453298 0.0698667224 0.0957332030 0.0062387132 0.0063830000 0.0004080000 0.0033710000 0.0000010000 0.0000040000 0.0010300000 37425893 96830484 509673472 4.2345676422 3.9339327812 3.9237227440 635 1311867191.6118669510 0.0959556401 0.0699078073 0.0959556401 0.0062656206 0.0066970000 0.0004110000 0.0033770000 0.0000040000 0.0000040000 0.0013100000 37429677 96830484 509673472 4.2367315292 3.9359796047 3.9246032238 636 1311867191.6451880932 0.0955487713 0.0699481233 0.0959556401 0.0062617659 0.0056840000 0.0004070000 0.0026680000 0.0000000000 0.0000030000 0.0010300000 37433349 96830484 509673472 4.2388195992 3.9353299141 3.9256095886 637 1311867191.6827919483 0.0937973112 0.0699855632 0.0959556401 0.0062651995 0.0083380000 0.0004090000 0.0044290000 0.0000030000 0.0000030000 0.0019000000 37437245 96830484 509673472 4.2421998978 3.9339442253 3.9266786575 638 1311867191.7119400501 0.0942602307 0.0700236112 0.0959556401 0.0062639165 0.0063920000 0.0004140000 0.0033760000 0.0000010000 0.0000040000 0.0010190000 37440805 96830484 509673472 4.2438340187 3.9353766441 3.9275867939 639 1311867191.7457199097 0.0939759240 0.0700610953 0.0959556401 0.0062826473 0.0059440000 0.0004090000 0.0026720000 0.0000040000 0.0000040000 0.0012720000 37444421 96830484 509673472 4.2446427345 3.9340105057 3.9280874729 640 1311867191.7763800621 0.0948536023 0.0700998336 0.0959556401 0.0062879245 0.0074830000 0.0004140000 0.0044520000 0.0000000000 0.0000030000 0.0010160000 37448037 96830484 509673472 4.2454795837 3.9347078800 3.9289844036 641 1311867191.8097250462 0.0934039205 0.0701361894 0.0959556401 0.0062848851 0.0069050000 0.0004080000 0.0030290000 0.0000040000 0.0000040000 0.0018930000 37451765 96830484 509673472 4.2489805222 3.9348411560 3.9306168556 642 1311867191.8395779133 0.0923082903 0.0701707254 0.0959556401 0.0062895083 0.0090190000 0.0005970000 0.0026790000 0.0000020000 0.0000160000 0.0014230000 37455381 96830484 509673472 4.2507138252 3.9337501526 3.9310150146 643 1311867191.8745219707 0.0928412825 0.0702059829 0.0959556401 0.0062918353 0.0069150000 0.0004590000 0.0027600000 0.0000070000 0.0000060000 0.0013400000 37459109 96830484 509673472 4.2519350052 3.9344134331 3.9322726727 644 1311867191.9077119827 0.0916007385 0.0702392045 0.0959556401 0.0062881272 0.0080220000 0.0004890000 0.0044920000 0.0000010000 0.0000040000 0.0010260000 37462837 96830484 509673472 4.2547597885 3.9344937801 3.9336447716 645 1311867191.9391601086 0.0921983570 0.0702732497 0.0959556401 0.0062856491 0.0082740000 0.0004150000 0.0043490000 0.0000030000 0.0000040000 0.0018960000 37466509 96830484 509673472 4.2544522285 3.9323618412 3.9340651035 646 1311867191.9755239487 0.0914518610 0.0703060340 0.0959556401 0.0062850438 0.0074890000 0.0004250000 0.0044680000 0.0000010000 0.0000040000 0.0010100000 37470237 96830484 509673472 4.2571144104 3.9331688881 3.9354245663 647 1311867192.0076289177 0.0917203575 0.0703391318 0.0959556401 0.0062806617 0.0070590000 0.0004120000 0.0037580000 0.0000040000 0.0000040000 0.0012960000 37473909 96830484 509673472 4.2582097054 3.9332616329 3.9361541271 648 1311867192.0447950363 0.0913051590 0.0703714868 0.0959556401 0.0062904777 0.0056630000 0.0004080000 0.0026750000 0.0000010000 0.0000040000 0.0010090000 37477749 96830484 509673472 4.2588171959 3.9308381081 3.9364044666 649 1311867192.0751929283 0.0932465196 0.0704067334 0.0959556401 0.0062919203 0.0093130000 0.0005160000 0.0039840000 0.0000080000 0.0000080000 0.0020820000 37481309 96830484 509673472 4.2580065727 3.9318585396 3.9368634224 650 1311867192.1073920727 0.0920186341 0.0704399825 0.0959556401 0.0062889495 0.0062180000 0.0004400000 0.0027370000 0.0000010000 0.0000050000 0.0010290000 37485037 96830484 509673472 4.2621259689 3.9331841469 3.9385416508 651 1311867192.1433029175 0.0929764807 0.0704746008 0.0959556401 0.0062932043 0.0063290000 0.0004100000 0.0030280000 0.0000040000 0.0000040000 0.0012940000 37488821 96830484 509673472 4.2610964775 3.9305746555 3.9383921623 652 1311867192.1754670143 0.0936801210 0.0705101920 0.0959556401 0.0062986022 0.0053370000 0.0004100000 0.0023190000 0.0000000000 0.0000030000 0.0010140000 37492493 96830484 509673472 4.2623248100 3.9317116737 3.9392256737 653 1311867192.2077538967 0.0938125774 0.0705458772 0.0959556401 0.0062951895 0.0110350000 0.0005960000 0.0030560000 0.0000170000 0.0000160000 0.0025740000 37496221 96830484 509673472 4.2644853592 3.9325325489 3.9404997826 654 1311867192.2451250553 0.0931200385 0.0705803942 0.0959556401 0.0063046684 0.0066670000 0.0004580000 0.0027540000 0.0000010000 0.0000060000 0.0010800000 37500061 96830484 509673472 4.2657546997 3.9295876026 3.9412529469 655 1311867192.2744629383 0.0935578346 0.0706154743 0.0959556401 0.0063028352 0.0059190000 0.0004310000 0.0023410000 0.0000040000 0.0000040000 0.0012990000 37503621 96830484 509673472 4.2677125931 3.9317262173 3.9419634342 656 1311867192.3067719936 0.0937108546 0.0706506807 0.0959556401 0.0063006895 0.0075540000 0.0004230000 0.0044500000 0.0000010000 0.0000040000 0.0010190000 37507293 96830484 509673472 4.2694516182 3.9307334423 3.9431478977 657 1311867192.3427391052 0.0936809033 0.0706857343 0.0959556401 0.0062977133 0.0073070000 0.0004100000 0.0033660000 0.0000040000 0.0000040000 0.0018820000 37511077 96830484 509673472 4.2708048820 3.9289608002 3.9435703754 658 1311867192.3755910397 0.0944795385 0.0707218951 0.0959556401 0.0062994876 0.0060480000 0.0004100000 0.0030200000 0.0000010000 0.0000040000 0.0010090000 37514805 96830484 509673472 4.2724514008 3.9295804501 3.9441215992 659 1311867192.4059340954 0.0935623422 0.0707565543 0.0959556401 0.0062952873 0.0083740000 0.0005090000 0.0032390000 0.0000090000 0.0000070000 0.0014140000 37518365 96830484 509673472 4.2756414413 3.9290885925 3.9448380470 660 1311867192.4447100163 0.0954382271 0.0707939508 0.0959556401 0.0062917686 0.0066080000 0.0004370000 0.0030920000 0.0000000000 0.0000050000 0.0010310000 37522261 96830484 509673472 4.2756471634 3.9274928570 3.9448711872 661 1311867192.4748210907 0.0964225307 0.0708327232 0.0964225307 0.0062892080 0.0066260000 0.0004160000 0.0026790000 0.0000040000 0.0000040000 0.0018800000 37525877 96830484 509673472 4.2770814896 3.9279675484 3.9454119205 662 1311867192.5077190399 0.0972810760 0.0708726754 0.0972810760 0.0062852295 0.0079380000 0.0005200000 0.0032180000 0.0000010000 0.0000080000 0.0011580000 37529549 96830484 509673472 4.2781538963 3.9272601604 3.9459273815 663 1311867192.5427820683 0.0963447317 0.0709110948 0.0972810760 0.0062862007 0.0069070000 0.0004400000 0.0031050000 0.0000050000 0.0000050000 0.0013130000 37533333 96830484 509673472 4.2801585197 3.9251155853 3.9456644058 664 1311867192.5787169933 0.0979376361 0.0709517974 0.0979376361 0.0062875771 0.0083470000 0.0005170000 0.0032440000 0.0000010000 0.0000120000 0.0011890000 37537061 96830484 509673472 4.2812304497 3.9265363216 3.9457261562 665 1311867192.6109929085 0.1019544229 0.0709984179 0.1019544229 0.0062849723 0.0071930000 0.0004600000 0.0027340000 0.0000060000 0.0000050000 0.0019360000 37540733 96830484 509673472 4.2782974243 3.9269258976 3.9455735683 666 1311867192.6435210705 0.1033791900 0.0710470377 0.1033791900 0.0062854815 0.0065270000 0.0004240000 0.0034150000 0.0000010000 0.0000040000 0.0010190000 37544461 96830484 509673472 4.2777838707 3.9254734516 3.9451186657 667 1311867192.6790139675 0.1036476269 0.0710959142 0.1036476269 0.0062830786 0.0056430000 0.0004090000 0.0023160000 0.0000040000 0.0000040000 0.0013080000 37548245 96830484 509673472 4.2798695564 3.9264287949 3.9456946850 668 1311867192.7113289833 0.1043931469 0.0711457603 0.1043931469 0.0062801585 0.0080220000 0.0005210000 0.0032360000 0.0000010000 0.0000080000 0.0011630000 37551861 96830484 509673472 4.2804498672 3.9261353016 3.9459254742 669 1311867192.7439620495 0.1052834317 0.0711967882 0.1052834317 0.0062791645 0.0072010000 0.0004360000 0.0027340000 0.0000050000 0.0000050000 0.0018960000 37555589 96830484 509673472 4.2802863121 3.9248390198 3.9457781315 670 1311867192.7760629654 0.1047324464 0.0712468414 0.1052834317 0.0062764683 0.0075720000 0.0004190000 0.0044660000 0.0000010000 0.0000040000 0.0010250000 37559261 96830484 509673472 4.2829227448 3.9260554314 3.9464437962 671 1311867192.8091869354 0.1050765738 0.0712972583 0.1052834317 0.0062719214 0.0077920000 0.0004130000 0.0044460000 0.0000040000 0.0000040000 0.0012970000 37562989 96830484 509673472 4.2839055061 3.9255523682 3.9468514919 672 1311867192.8422288895 0.1034556776 0.0713451131 0.1052834317 0.0062685694 0.0057280000 0.0004120000 0.0026720000 0.0000000000 0.0000040000 0.0010220000 37566661 96830484 509673472 4.2865214348 3.9240293503 3.9472100735 673 1311867192.8792889118 0.1055719703 0.0713959703 0.1055719703 0.0062713234 0.0069310000 0.0004090000 0.0030240000 0.0000030000 0.0000030000 0.0018710000 37570501 96830484 509673472 4.2860546112 3.9257490635 3.9477758408 674 1311867192.9092190266 0.1050249338 0.0714458649 0.1055719703 0.0062668236 0.0079570000 0.0004730000 0.0044590000 0.0000000000 0.0000040000 0.0010230000 37574061 96830484 509673472 4.2877526283 3.9250090122 3.9487619400 675 1311867192.9434111118 0.1047116667 0.0714951475 0.1055719703 0.0062646060 0.0078020000 0.0004180000 0.0044420000 0.0000040000 0.0000040000 0.0012970000 37577845 96830484 509673472 4.2886219025 3.9230091572 3.9486782551 676 1311867192.9776289463 0.1044017747 0.0715438260 0.1055719703 0.0062651052 0.0077890000 0.0005210000 0.0029090000 0.0000010000 0.0000090000 0.0011530000 37581517 96830484 509673472 4.2911658287 3.9243578911 3.9494733810 677 1311867193.0086810589 0.1051853150 0.0715935180 0.1055719703 0.0062623591 0.0089210000 0.0004470000 0.0045370000 0.0000050000 0.0000050000 0.0019110000 37585189 96830484 509673472 4.2911829948 3.9241025448 3.9498131275 678 1311867193.0430600643 0.1043768823 0.0716418710 0.1055719703 0.0062607011 0.0091020000 0.0005080000 0.0040400000 0.0000000000 0.0000090000 0.0011560000 37588917 96830484 509673472 4.2925291061 3.9214506149 3.9498705864 679 1311867193.0767369270 0.1052472293 0.0716913635 0.1055719703 0.0062671107 0.0066440000 0.0004430000 0.0027520000 0.0000050000 0.0000050000 0.0013420000 37592589 96830484 509673472 4.2939319611 3.9236142635 3.9501156807 680 1311867193.1105849743 0.1045079976 0.0717396232 0.1055719703 0.0062637074 0.0061860000 0.0004250000 0.0030530000 0.0000010000 0.0000040000 0.0010150000 37596317 96830484 509673472 4.2964458466 3.9237642288 3.9507372379 681 1311867193.1429219246 0.1029005572 0.0717853808 0.1055719703 0.0062646044 0.0084120000 0.0004200000 0.0044650000 0.0000040000 0.0000030000 0.0018710000 37600045 96830484 509673472 4.2980794907 3.9211466312 3.9506676197 682 1311867193.1767370701 0.1047046483 0.0718336496 0.1055719703 0.0062808545 0.0064600000 0.0004170000 0.0034060000 0.0000010000 0.0000040000 0.0010180000 37603717 96830484 509673472 4.2993826866 3.9247334003 3.9508557320 683 1311867193.2122681141 0.1049479619 0.0718821332 0.1055719703 0.0062811471 0.0061170000 0.0004190000 0.0026920000 0.0000040000 0.0000040000 0.0012880000 37607501 96830484 509673472 4.3001713753 3.9233157635 3.9512445927 684 1311867193.2432429790 0.1038953662 0.0719289361 0.1055719703 0.0062803297 0.0095130000 0.0005320000 0.0047260000 0.0000010000 0.0000070000 0.0011670000 37611173 96830484 509673472 4.3022112846 3.9219963551 3.9512591362 685 1311867193.2773900032 0.1049543619 0.0719771484 0.1055719703 0.0062791028 0.0088110000 0.0004450000 0.0045460000 0.0000050000 0.0000050000 0.0018730000 37614901 96830484 509673472 4.3032574654 3.9243519306 3.9513683319 686 1311867193.3139379025 0.1055816635 0.0720261346 0.1055816635 0.0062806148 0.0065190000 0.0004230000 0.0034030000 0.0000010000 0.0000040000 0.0010150000 37618685 96830484 509673472 4.3034386635 3.9222481251 3.9510264397 687 1311867193.3426671028 0.1055374071 0.0720749138 0.1055816635 0.0062799488 0.0094990000 0.0005200000 0.0046900000 0.0000080000 0.0000070000 0.0014290000 37622245 96830484 509673472 4.3049125671 3.9228825569 3.9512817860 688 1311867193.3788230419 0.1047434881 0.0721223972 0.1055816635 0.0062763341 0.0064020000 0.0004550000 0.0027510000 0.0000010000 0.0000050000 0.0010340000 37626029 96830484 509673472 4.3080658913 3.9242155552 3.9516043663 689 1311867193.4126739502 0.1053589731 0.0721706360 0.1055816635 0.0062849935 0.0084360000 0.0004280000 0.0044690000 0.0000050000 0.0000030000 0.0018740000 37629701 96830484 509673472 4.3081197739 3.9221317768 3.9513998032 690 1311867193.4440810680 0.1055034176 0.0722189444 0.1055816635 0.0062842777 0.0061550000 0.0004140000 0.0030410000 0.0000000000 0.0000040000 0.0010130000 37633429 96830484 509673472 4.3095855713 3.9224064350 3.9512693882 691 1311867193.4782969952 0.1052386984 0.0722667299 0.1055816635 0.0062804098 0.0078820000 0.0004380000 0.0044810000 0.0000040000 0.0000040000 0.0012860000 37637157 96830484 509673472 4.3120751381 3.9234883785 3.9515948296 692 1311867193.5199069977 0.1060576588 0.0723155607 0.1060576588 0.0062774782 0.0079830000 0.0005310000 0.0028920000 0.0000010000 0.0000080000 0.0011590000 37640997 96830484 509673472 4.3127112389 3.9218533039 3.9514806271 693 1311867193.5431120396 0.1062519401 0.0723645309 0.1062519401 0.0062742255 0.0089920000 0.0004480000 0.0045290000 0.0000050000 0.0000050000 0.0019030000 37644501 96830484 509673472 4.3137516975 3.9223985672 3.9515280724 694 1311867193.5765709877 0.1062453315 0.0724133505 0.1062519401 0.0062701318 0.0095480000 0.0005170000 0.0044120000 0.0000010000 0.0000090000 0.0011540000 37648173 96830484 509673472 4.3159251213 3.9234879017 3.9516580105 695 1311867193.6127800941 0.1074450538 0.0724637559 0.1074450538 0.0062660887 0.0100150000 0.0005240000 0.0047460000 0.0000070000 0.0000070000 0.0014260000 37652013 96830484 509673472 4.3153429031 3.9216842651 3.9510252476 696 1311867193.6461451054 0.1075349376 0.0725141455 0.1075349376 0.0062621776 0.0081840000 0.0004520000 0.0045220000 0.0000000000 0.0000040000 0.0010340000 37655685 96830484 509673472 4.3168168068 3.9217669964 3.9509370327 697 1311867193.6757860184 0.1076849848 0.0725646058 0.1076849848 0.0062588805 0.0085030000 0.0004300000 0.0044870000 0.0000030000 0.0000030000 0.0018690000 37659301 96830484 509673472 4.3191204071 3.9237663746 3.9514052868 698 1311867193.7122890949 0.1086871773 0.0726163573 0.1086871773 0.0062550930 0.0069080000 0.0004310000 0.0037630000 0.0000010000 0.0000040000 0.0010170000 37663085 96830484 509673472 4.3186178207 3.9218363762 3.9510831833 699 1311867193.7430191040 0.1097797900 0.0726695239 0.1097797900 0.0062519323 0.0061030000 0.0004200000 0.0026890000 0.0000040000 0.0000040000 0.0013020000 37666701 96830484 509673472 4.3191432953 3.9227521420 3.9510293007 700 1311867193.7760169506 0.1114136353 0.0727248726 0.1114136353 0.0062497714 0.0065330000 0.0004300000 0.0034000000 0.0000010000 0.0000040000 0.0010030000 37670373 96830484 509673472 4.3192691803 3.9243049622 3.9505710602 701 1311867193.8139710426 0.1117504090 0.0727805439 0.1117504090 0.0062479665 0.0092980000 0.0005170000 0.0039070000 0.0000080000 0.0000070000 0.0019970000 37674269 96830484 509673472 4.3202075958 3.9225168228 3.9508357048 702 1311867193.8436760902 0.1122403294 0.0728367544 0.1122403294 0.0062449348 0.0062550000 0.0004570000 0.0027200000 0.0000010000 0.0000050000 0.0010210000 37677829 96830484 509673472 4.3210253716 3.9226377010 3.9507417679 703 1311867193.8771181107 0.1123744175 0.0728929957 0.1123744175 0.0062413820 0.0083160000 0.0005350000 0.0028940000 0.0000080000 0.0000070000 0.0014200000 37681557 96830484 509673472 4.3227734566 3.9235365391 3.9505040646 704 1311867193.9151229858 0.1131176874 0.0729501331 0.1131176874 0.0062378168 0.0074550000 0.0004530000 0.0038190000 0.0000000000 0.0000050000 0.0010290000 37685341 96830484 509673472 4.3232016563 3.9222838879 3.9504404068 705 1311867193.9425311089 0.1145784780 0.0730091804 0.1145784780 0.0062350591 0.0081740000 0.0004480000 0.0041110000 0.0000040000 0.0000030000 0.0018820000 37688957 96830484 509673472 4.3230404854 3.9235384464 3.9502298832 706 1311867193.9781770706 0.1147217602 0.0730682634 0.1147217602 0.0062311497 0.0057990000 0.0004230000 0.0026910000 0.0000010000 0.0000040000 0.0010120000 37692741 96830484 509673472 4.3246130943 3.9237041473 3.9502260685 707 1311867194.0148570538 0.1171804592 0.0731306568 0.1171804592 0.0062294470 0.0068770000 0.0004650000 0.0034000000 0.0000030000 0.0000030000 0.0012830000 37696469 96830484 509673472 4.3230652809 3.9227867126 3.9495236874 708 1311867194.0433440208 0.1181642190 0.0731942636 0.1181642190 0.0062288824 0.0096700000 0.0006190000 0.0034420000 0.0000010000 0.0000110000 0.0012870000 37700085 96830484 509673472 4.3236126900 3.9235265255 3.9496040344 709 1311867194.0746119022 0.1165591553 0.0732554270 0.1181642190 0.0062252257 0.0082620000 0.0004770000 0.0034920000 0.0000050000 0.0000050000 0.0019000000 37703701 96830484 509673472 4.3269562721 3.9243392944 3.9500877857 710 1311867194.1131060123 0.1173855439 0.0733175821 0.1181642190 0.0062219227 0.0073750000 0.0004410000 0.0041450000 0.0000000000 0.0000030000 0.0010100000 37707597 96830484 509673472 4.3266086578 3.9229965210 3.9497239590 711 1311867194.1428558826 0.1202494875 0.0733835904 0.1202494875 0.0062221974 0.0079230000 0.0004410000 0.0044910000 0.0000040000 0.0000040000 0.0012970000 37711213 96830484 509673472 4.3246269226 3.9244081974 3.9495260715 712 1311867194.1758549213 0.1191851795 0.0734479185 0.1202494875 0.0062233452 0.0076630000 0.0004300000 0.0044950000 0.0000010000 0.0000040000 0.0010090000 37714885 96830484 509673472 4.3269577026 3.9255831242 3.9499645233 713 1311867194.2138450146 0.1202985793 0.0735136277 0.1202985793 0.0062207809 0.0084730000 0.0004220000 0.0044780000 0.0000040000 0.0000040000 0.0018460000 37718725 96830484 509673472 4.3259201050 3.9238274097 3.9496769905 714 1311867194.2451140881 0.1201289371 0.0735789152 0.1202985793 0.0062189991 0.0093640000 0.0005220000 0.0047150000 0.0000010000 0.0000080000 0.0011580000 37722285 96830484 509673472 4.3273572922 3.9255251884 3.9498760700 715 1311867194.2760241032 0.1200582087 0.0736439213 0.1202985793 0.0062153205 0.0083070000 0.0004570000 0.0045540000 0.0000050000 0.0000050000 0.0013240000 37725901 96830484 509673472 4.3280220032 3.9252672195 3.9504728317 716 1311867194.3139200211 0.1207853556 0.0737097612 0.1207853556 0.0062119488 0.0066030000 0.0004320000 0.0034210000 0.0000000000 0.0000040000 0.0010090000 37729741 96830484 509673472 4.3274965286 3.9239895344 3.9500532150 717 1311867194.3447821140 0.1193963289 0.0737734803 0.1207853556 0.0062157173 0.0081730000 0.0004270000 0.0041280000 0.0000040000 0.0000040000 0.0018630000 37733413 96830484 509673472 4.3300786018 3.9256632328 3.9506959915 718 1311867194.3802230358 0.1187981442 0.0738361888 0.1207853556 0.0062124256 0.0142780000 0.0006330000 0.0050260000 0.0000020000 0.0000190000 0.0015510000 37737141 96830484 509673472 4.3311524391 3.9253094196 3.9511771202 719 1311867194.4124519825 0.1186619848 0.0738985334 0.1207853556 0.0062108673 0.0119700000 0.0006340000 0.0034720000 0.0000150000 0.0000140000 0.0018290000 37740757 96830484 509673472 4.3311924934 3.9231688976 3.9516444206 720 1311867194.4447510242 0.1199659929 0.0739625160 0.1207853556 0.0062074197 0.0068100000 0.0004890000 0.0024250000 0.0000000000 0.0000070000 0.0010820000 37744485 96830484 509673472 4.3307127953 3.9238190651 3.9516301155 721 1311867194.4805839062 0.1192251295 0.0740252935 0.1207853556 0.0062039492 0.0088380000 0.0004490000 0.0045380000 0.0000040000 0.0000040000 0.0018750000 37748157 96830484 509673472 4.3324432373 3.9246087074 3.9519100189 722 1311867194.5174930096 0.1202360839 0.0740892974 0.1207853556 0.0062018227 0.0090630000 0.0005340000 0.0036630000 0.0000010000 0.0000100000 0.0011610000 37752053 96830484 509673472 4.3313279152 3.9231326580 3.9516842365 723 1311867194.5439500809 0.1191650853 0.0741516429 0.1207853556 0.0062006135 0.0138870000 0.0006800000 0.0039300000 0.0000170000 0.0000150000 0.0018370000 37755501 96830484 509673472 4.3331031799 3.9239840508 3.9516949654 724 1311867194.5795979500 0.1198313311 0.0742147364 0.1207853556 0.0061963645 0.0083970000 0.0005940000 0.0035920000 0.0000020000 0.0000090000 0.0011720000 37759229 96830484 509673472 4.3328294754 3.9239301682 3.9522421360 725 1311867194.6129479408 0.1181880012 0.0742753891 0.1207853556 0.0061927109 0.0075800000 0.0004600000 0.0031110000 0.0000060000 0.0000050000 0.0018930000 37762957 96830484 509673472 4.3347802162 3.9226911068 3.9527933598 726 1311867194.6493880749 0.1176489815 0.0743351324 0.1207853556 0.0062036777 0.0062460000 0.0004380000 0.0030630000 0.0000000000 0.0000030000 0.0010020000 37766797 96830484 509673472 4.3359255791 3.9238471985 3.9535562992 727 1311867194.6784319878 0.1166220009 0.0743932986 0.1207853556 0.0062035575 0.0075770000 0.0004260000 0.0041350000 0.0000040000 0.0000040000 0.0012860000 37770357 96830484 509673472 4.3371844292 3.9232990742 3.9538362026 728 1311867194.7133309841 0.1177254617 0.0744528208 0.1207853556 0.0062005979 0.0066170000 0.0004270000 0.0034260000 0.0000000000 0.0000030000 0.0010170000 37774085 96830484 509673472 4.3362555504 3.9233808517 3.9537475109 729 1311867194.7475099564 0.1172105148 0.0745114734 0.1207853556 0.0061965484 0.0063680000 0.0004290000 0.0023520000 0.0000030000 0.0000030000 0.0018540000 37777813 96830484 509673472 4.3376851082 3.9240267277 3.9543159008 730 1311867194.7784450054 0.1172213852 0.0745699801 0.1207853556 0.0061927163 0.0057780000 0.0004340000 0.0026950000 0.0000010000 0.0000040000 0.0010170000 37781485 96830484 509673472 4.3380494118 3.9238634109 3.9547169209 731 1311867194.8130390644 0.1184587106 0.0746300194 0.1207853556 0.0061888045 0.0098330000 0.0005290000 0.0047680000 0.0000070000 0.0000070000 0.0014250000 37785213 96830484 509673472 4.3367238045 3.9237093925 3.9548552036 732 1311867194.8476719856 0.1191095188 0.0746907838 0.1207853556 0.0061849837 0.0119950000 0.0006160000 0.0027080000 0.0000020000 0.0000160000 0.0015490000 37788941 96830484 509673472 4.3362503052 3.9245431423 3.9546158314 733 1311867194.8814148903 0.1196210012 0.0747520801 0.1207853556 0.0061811681 0.0130710000 0.0006340000 0.0027020000 0.0000150000 0.0000150000 0.0026100000 37792669 96830484 509673472 4.3355236053 3.9250195026 3.9548039436 734 1311867194.9104089737 0.1199202016 0.0748136170 0.1207853556 0.0061873164 0.0078250000 0.0004960000 0.0024670000 0.0000010000 0.0000080000 0.0011500000 37796229 96830484 509673472 4.3351936340 3.9257698059 3.9549660683 735 1311867194.9451448917 0.1188691929 0.0748735566 0.1207853556 0.0061846125 0.0077390000 0.0005000000 0.0028530000 0.0000080000 0.0000070000 0.0013540000 37800013 96830484 509673472 4.3353009224 3.9245462418 3.9554574490 736 1311867194.9787399769 0.1158358455 0.0749292119 0.1207853556 0.0061839183 0.0067670000 0.0004610000 0.0031080000 0.0000000000 0.0000050000 0.0010220000 37803741 96830484 509673472 4.3378205299 3.9233324528 3.9560322762 737 1311867195.0132799149 0.1155864894 0.0749843778 0.1207853556 0.0061817186 0.0086080000 0.0004310000 0.0045290000 0.0000030000 0.0000030000 0.0018590000 37807469 96830484 509673472 4.3374204636 3.9245042801 3.9563851357 738 1311867195.0464940071 0.1151394546 0.0750387885 0.1207853556 0.0061789773 0.0058980000 0.0004330000 0.0027080000 0.0000000000 0.0000040000 0.0009970000 37811141 96830484 509673472 4.3367624283 3.9225823879 3.9566438198 739 1311867195.0781710148 0.1139992997 0.0750915091 0.1207853556 0.0061760316 0.0068920000 0.0004270000 0.0034370000 0.0000040000 0.0000040000 0.0012730000 37814813 96830484 509673472 4.3375277519 3.9232854843 3.9569456577 740 1311867195.1115310192 0.1139338017 0.0751439986 0.1207853556 0.0061722260 0.0069590000 0.0004270000 0.0037930000 0.0000000000 0.0000030000 0.0010010000 37818485 96830484 509673472 4.3371324539 3.9241144657 3.9573266506 741 1311867195.1458311081 0.1142964885 0.0751968360 0.1207853556 0.0061680716 0.0087800000 0.0005340000 0.0025650000 0.0000100000 0.0000100000 0.0020420000 37822269 96830484 509673472 4.3354358673 3.9232897758 3.9569747448 742 1311867195.1780319214 0.1140299067 0.0752491717 0.1207853556 0.0061661901 0.0064900000 0.0004550000 0.0027740000 0.0000010000 0.0000060000 0.0010360000 37825941 96830484 509673472 4.3353614807 3.9248821735 3.9572126865 743 1311867195.2114748955 0.1123921350 0.0752991622 0.1207853556 0.0061624246 0.0074790000 0.0005350000 0.0021530000 0.0000080000 0.0000080000 0.0014120000 37829613 96830484 509673472 4.3355054855 3.9245402813 3.9572746754 744 1311867195.2436800003 0.1118664965 0.0753483119 0.1207853556 0.0061608916 0.0064700000 0.0004480000 0.0027800000 0.0000010000 0.0000050000 0.0010190000 37833341 96830484 509673472 4.3351302147 3.9232797623 3.9575695992 745 1311867195.2780399323 0.1117544994 0.0753971792 0.1207853556 0.0061573117 0.0102250000 0.0005330000 0.0036830000 0.0000090000 0.0000070000 0.0021260000 37837069 96830484 509673472 4.3342890739 3.9238026142 3.9575960636 746 1311867195.3123180866 0.1116651893 0.0754457959 0.1207853556 0.0061533472 0.0084160000 0.0005130000 0.0044800000 0.0000000000 0.0000050000 0.0012020000 37840797 96830484 509673472 4.3333230019 3.9234788418 3.9577131271 747 1311867195.3425979614 0.1127231792 0.0754956986 0.1207853556 0.0061536924 0.0061610000 0.0004400000 0.0027270000 0.0000040000 0.0000040000 0.0012730000 37844413 96830484 509673472 4.3302330971 3.9217317104 3.9568831921 748 1311867195.3782711029 0.1108758599 0.0755429983 0.1207853556 0.0061511523 0.0085030000 0.0005340000 0.0033200000 0.0000010000 0.0000090000 0.0011390000 37848197 96830484 509673472 4.3313093185 3.9225924015 3.9567909241 749 1311867195.4119830132 0.1103807315 0.0755895107 0.1207853556 0.0061494176 0.0069970000 0.0004650000 0.0024210000 0.0000050000 0.0000060000 0.0018720000 37851869 96830484 509673472 4.3305110931 3.9227175713 3.9566745758 750 1311867195.4435520172 0.1111329198 0.0756369019 0.1207853556 0.0061474862 0.0078010000 0.0005410000 0.0029110000 0.0000010000 0.0000080000 0.0011290000 37855597 96830484 509673472 4.3274140358 3.9216949940 3.9558660984 751 1311867195.4788239002 0.1097840369 0.0756823708 0.1207853556 0.0061436723 0.0063100000 0.0004560000 0.0024230000 0.0000050000 0.0000050000 0.0012730000 37859325 96830484 509673472 4.3280124664 3.9235730171 3.9557058811 752 1311867195.5113179684 0.1101192906 0.0757281645 0.1207853556 0.0061396974 0.0081130000 0.0005440000 0.0029440000 0.0000010000 0.0000110000 0.0011630000 37862997 96830484 509673472 4.3262076378 3.9236056805 3.9557042122 753 1311867195.5439620018 0.1098965332 0.0757735408 0.1207853556 0.0061356701 0.0076460000 0.0004720000 0.0031470000 0.0000050000 0.0000050000 0.0018860000 37866725 96830484 509673472 4.3237795830 3.9220244884 3.9554655552 754 1311867195.5782160759 0.1078719646 0.0758161117 0.1207853556 0.0061333573 0.0077130000 0.0004580000 0.0045400000 0.0000000000 0.0000040000 0.0009910000 37870453 96830484 509673472 4.3248400688 3.9226515293 3.9559154510 755 1311867195.6119859219 0.1082751974 0.0758591039 0.1207853556 0.0061307236 0.0070920000 0.0004290000 0.0036850000 0.0000040000 0.0000040000 0.0012690000 37874181 96830484 509673472 4.3226284981 3.9227075577 3.9557971954 756 1311867195.6430909634 0.1092633009 0.0759032893 0.1207853556 0.0061271291 0.0090830000 0.0005290000 0.0039340000 0.0000020000 0.0000100000 0.0011330000 37877797 96830484 509673472 4.3191390038 3.9220919609 3.9551358223 757 1311867195.6779129505 0.1084431708 0.0759462746 0.1207853556 0.0061237352 0.0087500000 0.0004790000 0.0042310000 0.0000050000 0.0000060000 0.0018610000 37881581 96830484 509673472 4.3183565140 3.9226224422 3.9551682472 758 1311867195.7107300758 0.1089152768 0.0759897694 0.1207853556 0.0061234460 0.0063060000 0.0004410000 0.0030880000 0.0000010000 0.0000040000 0.0009950000 37885197 96830484 509673472 4.3156208992 3.9226107597 3.9552006721 759 1311867195.7458300591 0.1079956517 0.0760319378 0.1207853556 0.0061203748 0.0062970000 0.0004300000 0.0027180000 0.0000030000 0.0000030000 0.0012780000 37888981 96830484 509673472 4.3143396378 3.9215991497 3.9551234245 760 1311867195.7821879387 0.1068992540 0.0760725527 0.1207853556 0.0061168570 0.0058180000 0.0004320000 0.0025960000 0.0000010000 0.0000040000 0.0010040000 37892709 96830484 509673472 4.3139004707 3.9218165874 3.9555778503 761 1311867195.8100500107 0.1075354442 0.0761138969 0.1207853556 0.0061133172 0.0094260000 0.0005350000 0.0024230000 0.0000100000 0.0000100000 0.0022090000 37896269 96830484 509673472 4.3113236427 3.9216661453 3.9554145336 762 1311867195.8458549976 0.1068819985 0.0761542750 0.1207853556 0.0061095037 0.0068920000 0.0004700000 0.0027930000 0.0000010000 0.0000060000 0.0010350000 37900053 96830484 509673472 4.3096814156 3.9210612774 3.9553391933 763 1311867195.8778660297 0.1063556150 0.0761938573 0.1207853556 0.0061079606 0.0073190000 0.0004410000 0.0038100000 0.0000040000 0.0000030000 0.0012790000 37903781 96830484 509673472 4.3089375496 3.9229433537 3.9554123878 764 1311867195.9098269939 0.1065685302 0.0762336147 0.1207853556 0.0061055791 0.0069870000 0.0004280000 0.0038070000 0.0000000000 0.0000040000 0.0009890000 37907453 96830484 509673472 4.3068513870 3.9223833084 3.9555668831 765 1311867195.9458460808 0.1063809097 0.0762730230 0.1207853556 0.0061018299 0.0086950000 0.0005440000 0.0025580000 0.0000100000 0.0000090000 0.0020220000 37911181 96830484 509673472 4.3047409058 3.9216749668 3.9553868771 766 1311867195.9778430462 0.1068647578 0.0763129600 0.1207853556 0.0061007686 0.0066480000 0.0004590000 0.0027660000 0.0000000000 0.0000060000 0.0010400000 37914909 96830484 509673472 4.3033943176 3.9236795902 3.9556045532 767 1311867196.0100569725 0.1058428138 0.0763514604 0.1207853556 0.0060986144 0.0060000000 0.0004350000 0.0023710000 0.0000040000 0.0000040000 0.0012700000 37918581 96830484 509673472 4.3026957512 3.9227323532 3.9558644295 768 1311867196.0498790741 0.1049820408 0.0763887398 0.1207853556 0.0060952168 0.0063040000 0.0004260000 0.0030750000 0.0000010000 0.0000040000 0.0010000000 37922477 96830484 509673472 4.3016881943 3.9220142365 3.9555795193 769 1311867196.0793108940 0.1060942188 0.0764273685 0.1207853556 0.0060977531 0.0064270000 0.0004270000 0.0023600000 0.0000040000 0.0000030000 0.0018310000 37926149 96830484 509673472 4.2997612953 3.9241929054 3.9558503628 770 1311867196.1113979816 0.1058859304 0.0764656264 0.1207853556 0.0060948863 0.0066730000 0.0004250000 0.0034420000 0.0000010000 0.0000040000 0.0009990000 37929709 96830484 509673472 4.2977652550 3.9228541851 3.9558475018 771 1311867196.1473290920 0.1045012251 0.0765019891 0.1207853556 0.0060915524 0.0105430000 0.0006130000 0.0023300000 0.0000150000 0.0000140000 0.0018030000 37933549 96830484 509673472 4.2972745895 3.9219648838 3.9560441971 772 1311867196.1811769009 0.1046175659 0.0765384082 0.1207853556 0.0060931316 0.0070270000 0.0004730000 0.0028250000 0.0000010000 0.0000070000 0.0010720000 37937277 96830484 509673472 4.2959380150 3.9236955643 3.9559559822 773 1311867196.2114949226 0.1058106795 0.0765762766 0.1207853556 0.0060911317 0.0087740000 0.0004430000 0.0045380000 0.0000040000 0.0000040000 0.0018370000 37940837 96830484 509673472 4.2927060127 3.9225218296 3.9557466507 774 1311867196.2462599277 0.1054118723 0.0766135319 0.1207853556 0.0060882654 0.0076590000 0.0004270000 0.0044040000 0.0000010000 0.0000040000 0.0009950000 37944621 96830484 509673472 4.2913684845 3.9222927094 3.9558415413 775 1311867196.2800569534 0.1055223644 0.0766508336 0.1207853556 0.0060845407 0.0055760000 0.0004240000 0.0020050000 0.0000040000 0.0000040000 0.0012710000 37948349 96830484 509673472 4.2897229195 3.9232089520 3.9557082653 776 1311867196.3111600876 0.1052508652 0.0766876893 0.1207853556 0.0060811683 0.0089520000 0.0005410000 0.0033240000 0.0000020000 0.0000110000 0.0011950000 37951965 96830484 509673472 4.2879681587 3.9222397804 3.9557614326 777 1311867196.3484730721 0.1053285301 0.0767245501 0.1207853556 0.0060778632 0.0092630000 0.0004570000 0.0045920000 0.0000050000 0.0000040000 0.0018570000 37955805 96830484 509673472 4.2862029076 3.9225978851 3.9555811882 778 1311867196.3842670918 0.1049134433 0.0767607826 0.1207853556 0.0060747651 0.0077630000 0.0004390000 0.0045100000 0.0000000000 0.0000040000 0.0009930000 37959533 96830484 509673472 4.2851810455 3.9238274097 3.9558415413 779 1311867196.4107549191 0.1051850542 0.0767972708 0.1207853556 0.0060725667 0.0064660000 0.0004250000 0.0029550000 0.0000040000 0.0000030000 0.0012610000 37963037 96830484 509673472 4.2828307152 3.9221947193 3.9559991360 780 1311867196.4463150501 0.1048036516 0.0768331764 0.1207853556 0.0060720672 0.0070360000 0.0004280000 0.0037920000 0.0000010000 0.0000040000 0.0009880000 37966821 96830484 509673472 4.2819061279 3.9231929779 3.9561450481 781 1311867196.4798319340 0.1040398702 0.0768680121 0.1207853556 0.0060682462 0.0068300000 0.0004240000 0.0027300000 0.0000040000 0.0000050000 0.0018120000 37970549 96830484 509673472 4.2813639641 3.9236662388 3.9566833973 782 1311867196.5113470554 0.1044883654 0.0769033323 0.1207853556 0.0060646755 0.0078060000 0.0005310000 0.0025330000 0.0000010000 0.0000090000 0.0011350000 37974165 96830484 509673472 4.2786736488 3.9230239391 3.9565665722 783 1311867196.5468420982 0.1041323096 0.0769381074 0.1207853556 0.0060617759 0.0068420000 0.0004530000 0.0027640000 0.0000050000 0.0000040000 0.0012710000 37977949 96830484 509673472 4.2767667770 3.9237375259 3.9567906857 784 1311867196.5795550346 0.1038508862 0.0769724350 0.1207853556 0.0060596288 0.0060400000 0.0004240000 0.0027310000 0.0000010000 0.0000040000 0.0009810000 37981677 96830484 509673472 4.2763223648 3.9248991013 3.9573333263 785 1311867196.6108930111 0.1028794050 0.0770054375 0.1207853556 0.0060589827 0.0092090000 0.0005330000 0.0024310000 0.0000110000 0.0000100000 0.0021710000 37985293 96830484 509673472 4.2750101089 3.9235463142 3.9576900005 786 1311867196.6521809101 0.1031944826 0.0770387569 0.1207853556 0.0060620679 0.0064640000 0.0004620000 0.0024220000 0.0000010000 0.0000050000 0.0010330000 37989245 96830484 509673472 4.2722530365 3.9247739315 3.9575536251 787 1311867196.6805100441 0.1020327955 0.0770705155 0.1207853556 0.0060696732 0.0067490000 0.0004350000 0.0031080000 0.0000040000 0.0000040000 0.0012570000 37992805 96830484 509673472 4.2716269493 3.9256653786 3.9581763744 788 1311867196.7112100124 0.1012433395 0.0771011917 0.1207853556 0.0060667110 0.0056220000 0.0004270000 0.0023570000 0.0000010000 0.0000040000 0.0009690000 37996421 96830484 509673472 4.2705340385 3.9243934155 3.9588773251 789 1311867196.7464900017 0.1024227738 0.0771332849 0.1207853556 0.0060633623 0.0068860000 0.0004290000 0.0027150000 0.0000030000 0.0000030000 0.0017910000 38000205 96830484 509673472 4.2672929764 3.9258115292 3.9590694904 790 1311867196.7783749104 0.1008976921 0.0771633665 0.1207853556 0.0060598971 0.0052400000 0.0004250000 0.0020020000 0.0000000000 0.0000030000 0.0009600000 38003933 96830484 509673472 4.2666058540 3.9255049229 3.9594635963 791 1311867196.8109180927 0.1010048836 0.0771935074 0.1207853556 0.0060577206 0.0114320000 0.0006640000 0.0031110000 0.0000150000 0.0000140000 0.0017650000 38007493 96830484 509673472 4.2640013695 3.9250724316 3.9596755505 792 1311867196.8488750458 0.1007766128 0.0772232841 0.1207853556 0.0060553151 0.0070460000 0.0004710000 0.0027980000 0.0000010000 0.0000060000 0.0010320000 38011389 96830484 509673472 4.2618374825 3.9251878262 3.9599065781 793 1311867196.8821749687 0.1004164666 0.0772525315 0.1207853556 0.0060517520 0.0071360000 0.0004470000 0.0027540000 0.0000040000 0.0000040000 0.0017750000 38015061 96830484 509673472 4.2603201866 3.9259285927 3.9602673054 794 1311867196.9115700722 0.0997272208 0.0772808371 0.1207853556 0.0060494574 0.0063510000 0.0004310000 0.0030730000 0.0000010000 0.0000040000 0.0009590000 38018621 96830484 509673472 4.2584815025 3.9241807461 3.9603843689 795 1311867196.9482440948 0.0994386822 0.0773087086 0.1207853556 0.0060461613 0.0065640000 0.0004220000 0.0030410000 0.0000040000 0.0000030000 0.0012310000 38022461 96830484 509673472 4.2564539909 3.9247958660 3.9604568481 796 1311867196.9809880257 0.0987888500 0.0773356937 0.1207853556 0.0060435657 0.0076870000 0.0004900000 0.0028590000 0.0000010000 0.0000080000 0.0011030000 38026189 96830484 509673472 4.2550148964 3.9245133400 3.9606099129 797 1311867197.0154891014 0.0986472517 0.0773624335 0.1207853556 0.0060402820 0.0079160000 0.0004440000 0.0034890000 0.0000050000 0.0000050000 0.0017870000 38029861 96830484 509673472 4.2530908585 3.9240427017 3.9606249332 798 1311867197.0490679741 0.0987707153 0.0773892609 0.1207853556 0.0060371200 0.0069410000 0.0004270000 0.0036770000 0.0000000000 0.0000060000 0.0009560000 38033589 96830484 509673472 4.2506494522 3.9240255356 3.9604647160 799 1311867197.0806479454 0.0971134529 0.0774139470 0.1207853556 0.0060342948 0.0080410000 0.0005220000 0.0021800000 0.0000100000 0.0000090000 0.0014240000 38037149 96830484 509673472 4.2504014969 3.9234924316 3.9604532719 800 1311867197.1148109436 0.0976614282 0.0774392563 0.1207853556 0.0060306139 0.0083590000 0.0004380000 0.0045740000 0.0000010000 0.0000050000 0.0009750000 38040933 96830484 509673472 4.2472200394 3.9233646393 3.9599227905 801 1311867197.1468429565 0.0979719013 0.0774648901 0.1207853556 0.0060281221 0.0068660000 0.0004360000 0.0027280000 0.0000040000 0.0000030000 0.0017610000 38044605 96830484 509673472 4.2450432777 3.9243788719 3.9598374367 802 1311867197.1792430878 0.0980243981 0.0774905254 0.1207853556 0.0060253779 0.0078390000 0.0004190000 0.0045150000 0.0000000000 0.0000030000 0.0009630000 38048333 96830484 509673472 4.2425484657 3.9238207340 3.9596962929 803 1311867197.2143619061 0.0981302038 0.0775162286 0.1207853556 0.0060245648 0.0066480000 0.0004230000 0.0030610000 0.0000030000 0.0000040000 0.0012430000 38052061 96830484 509673472 4.2401185036 3.9243113995 3.9596161842 804 1311867197.2459290028 0.0976378694 0.0775412555 0.1207853556 0.0060211273 0.0066690000 0.0004220000 0.0027170000 0.0000010000 0.0000040000 0.0011850000 38055733 96830484 509673472 4.2389540672 3.9248127937 3.9598250389 805 1311867197.2799959183 0.0972879678 0.0775657856 0.1207853556 0.0060182050 0.0066940000 0.0004880000 0.0023090000 0.0000040000 0.0000040000 0.0019290000 38059517 96830484 509673472 4.2369012833 3.9243545532 3.9599995613 806 1311867197.3157260418 0.0971447676 0.0775900771 0.1207853556 0.0060151522 0.0089810000 0.0005340000 0.0036640000 0.0000010000 0.0000070000 0.0011060000 38063189 96830484 509673472 4.2345519066 3.9246435165 3.9598429203 807 1311867197.3468708992 0.0964924768 0.0776135002 0.1207853556 0.0060119824 0.0081900000 0.0004520000 0.0041100000 0.0000050000 0.0000050000 0.0012430000 38066861 96830484 509673472 4.2331418991 3.9247529507 3.9600462914 808 1311867197.3784019947 0.0967873633 0.0776372302 0.1207853556 0.0060095005 0.0086140000 0.0005150000 0.0029630000 0.0000020000 0.0000100000 0.0011600000 38070477 96830484 509673472 4.2304663658 3.9241023064 3.9598355293 809 1311867197.4155099392 0.0969908386 0.0776611531 0.1207853556 0.0060062001 0.0069440000 0.0004490000 0.0022380000 0.0000050000 0.0000050000 0.0018060000 38074261 96830484 509673472 4.2277865410 3.9240038395 3.9594538212 810 1311867197.4478878975 0.0959482864 0.0776837298 0.1207853556 0.0060027963 0.0054240000 0.0004400000 0.0020260000 0.0000010000 0.0000040000 0.0009640000 38077933 96830484 509673472 4.2274103165 3.9240984917 3.9594745636 811 1311867197.4793179035 0.0968921557 0.0777074147 0.1207853556 0.0059993179 0.0086720000 0.0004280000 0.0045280000 0.0000040000 0.0000030000 0.0012020000 38081493 96830484 509673472 4.2239346504 3.9238004684 3.9584555626 812 1311867197.5150759220 0.0974119902 0.0777316814 0.1207853556 0.0059973783 0.0088930000 0.0005330000 0.0029560000 0.0000010000 0.0000100000 0.0012270000 38085277 96830484 509673472 4.2213897705 3.9247136116 3.9577038288 813 1311867197.5469260216 0.0970855281 0.0777554869 0.1207853556 0.0059941643 0.0072250000 0.0004540000 0.0022830000 0.0000060000 0.0000060000 0.0018160000 38088893 96830484 509673472 4.2201871872 3.9253869057 3.9573974609 814 1311867197.5802750587 0.0970922038 0.0777792420 0.1207853556 0.0059931010 0.0069920000 0.0004290000 0.0034640000 0.0000000000 0.0000050000 0.0009650000 38092621 96830484 509673472 4.2176389694 3.9239599705 3.9565989971 815 1311867197.6152749062 0.0991352424 0.0778054457 0.1207853556 0.0059938511 0.0086290000 0.0005290000 0.0025870000 0.0000120000 0.0000110000 0.0013900000 38096349 96830484 509673472 4.2134084702 3.9255416393 3.9552218914 816 1311867197.6470439434 0.0983402357 0.0778306109 0.1207853556 0.0059913590 0.0090120000 0.0005200000 0.0033070000 0.0000010000 0.0000100000 0.0010970000 38100021 96830484 509673472 4.2131013870 3.9273464680 3.9549787045 817 1311867197.6800849438 0.0982260257 0.0778555747 0.1207853556 0.0059908238 0.0079920000 0.0004530000 0.0031410000 0.0000060000 0.0000050000 0.0017650000 38103749 96830484 509673472 4.2103357315 3.9254324436 3.9542222023 818 1311867197.7143290043 0.0986318663 0.0778809736 0.1207853556 0.0059913490 0.0080950000 0.0004420000 0.0045410000 0.0000000000 0.0000040000 0.0009690000 38107477 96830484 509673472 4.2086548805 3.9277849197 3.9535682201 819 1311867197.7463419437 0.0985704958 0.0779062355 0.1207853556 0.0059893632 0.0082870000 0.0004260000 0.0045320000 0.0000040000 0.0000040000 0.0012230000 38111149 96830484 509673472 4.2067556381 3.9277589321 3.9529585838 820 1311867197.7793009281 0.0993272215 0.0779323587 0.1207853556 0.0059867176 0.0093750000 0.0005180000 0.0036790000 0.0000010000 0.0000080000 0.0010950000 38114877 96830484 509673472 4.2031483650 3.9263911247 3.9517717361 821 1311867197.8146750927 0.0991288200 0.0779581765 0.1207853556 0.0059885769 0.0072480000 0.0004550000 0.0023990000 0.0000050000 0.0000050000 0.0018010000 38118661 96830484 509673472 4.2024512291 3.9288246632 3.9511742592 822 1311867197.8467919827 0.0985470787 0.0779832239 0.1207853556 0.0059875991 0.0066680000 0.0004440000 0.0030930000 0.0000010000 0.0000050000 0.0009660000 38122277 96830484 509673472 4.2011218071 3.9274122715 3.9505765438 823 1311867197.8802978992 0.0996063203 0.0780094974 0.1207853556 0.0059861322 0.0103640000 0.0005300000 0.0047780000 0.0000080000 0.0000070000 0.0013430000 38125949 96830484 509673472 4.1974959373 3.9281733036 3.9492516518 824 1311867197.9148609638 0.0991782621 0.0780351876 0.1207853556 0.0059872885 0.0068170000 0.0004670000 0.0027710000 0.0000000000 0.0000050000 0.0009800000 38129733 96830484 509673472 4.1969394684 3.9297432899 3.9488248825 825 1311867197.9470140934 0.0982753932 0.0780597212 0.1207853556 0.0059906506 0.0066540000 0.0004240000 0.0023660000 0.0000030000 0.0000030000 0.0017820000 38133405 96830484 509673472 4.1953973770 3.9290113449 3.9481797218 826 1311867197.9812700748 0.0983963385 0.0780843418 0.1207853556 0.0059870561 0.0057070000 0.0004190000 0.0022470000 0.0000010000 0.0000040000 0.0009610000 38137133 96830484 509673472 4.1932425499 3.9292478561 3.9474494457 827 1311867198.0145471096 0.0983406678 0.0781088355 0.1207853556 0.0059847466 0.0060250000 0.0004220000 0.0022380000 0.0000050000 0.0000030000 0.0012350000 38140917 96830484 509673472 4.1919307709 3.9305522442 3.9473042488 828 1311867198.0463368893 0.0976108313 0.0781323887 0.1207853556 0.0059824302 0.0083910000 0.0005260000 0.0021890000 0.0000010000 0.0000110000 0.0012300000 38144533 96830484 509673472 4.1904788017 3.9297447205 3.9466950893 829 1311867198.0787069798 0.0979668349 0.0781563144 0.1207853556 0.0059820964 0.0080010000 0.0004640000 0.0031400000 0.0000050000 0.0000050000 0.0018220000 38148261 96830484 509673472 4.1883220673 3.9305212498 3.9461557865 830 1311867198.1143770218 0.0957413912 0.0781775013 0.1207853556 0.0059796458 0.0088380000 0.0005190000 0.0035360000 0.0000000000 0.0000090000 0.0010910000 38151989 96830484 509673472 4.1889810562 3.9309718609 3.9459795952 831 1311867198.1463611126 0.0972360745 0.0782004358 0.1207853556 0.0059761700 0.0082740000 0.0005210000 0.0025700000 0.0000090000 0.0000080000 0.0013670000 38155661 96830484 509673472 4.1851248741 3.9313771725 3.9451775551 832 1311867198.1822519302 0.0962934792 0.0782221822 0.1207853556 0.0059728637 0.0067860000 0.0004530000 0.0027770000 0.0000010000 0.0000050000 0.0009740000 38159445 96830484 509673472 4.1839275360 3.9318935871 3.9444489479 833 1311867198.2144989967 0.0963996500 0.0782440039 0.1207853556 0.0059760231 0.0094300000 0.0004350000 0.0044900000 0.0000040000 0.0000040000 0.0020550000 38163117 96830484 509673472 4.1818633080 3.9320840836 3.9439239502 834 1311867198.2464120388 0.0958236828 0.0782650827 0.1207853556 0.0059739077 0.0064730000 0.0004360000 0.0027350000 0.0000010000 0.0000040000 0.0011340000 38166789 96830484 509673472 4.1803088188 3.9317083359 3.9430820942 835 1311867198.2821578979 0.0955250636 0.0782857533 0.1207853556 0.0059710438 0.0093940000 0.0005630000 0.0033380000 0.0000110000 0.0000090000 0.0013560000 38170573 96830484 509673472 4.1783857346 3.9326140881 3.9424822330 836 1311867198.3159120083 0.0948520824 0.0783055695 0.1207853556 0.0059704862 0.0064990000 0.0004550000 0.0024100000 0.0000000000 0.0000050000 0.0009880000 38174245 96830484 509673472 4.1769161224 3.9333956242 3.9415524006 837 1311867198.3481218815 0.0933451876 0.0783235380 0.1207853556 0.0059683969 0.0088870000 0.0004270000 0.0045750000 0.0000040000 0.0000040000 0.0017800000 38177917 96830484 509673472 4.1761078835 3.9326140881 3.9409868717 838 1311867198.3828320503 0.0939557254 0.0783421921 0.1207853556 0.0059694384 0.0080500000 0.0004230000 0.0045560000 0.0000000000 0.0000030000 0.0009630000 38181701 96830484 509673472 4.1730685234 3.9343106747 3.9399843216 839 1311867198.4242680073 0.0928054824 0.0783594308 0.1207853556 0.0059718493 0.0096390000 0.0005220000 0.0037090000 0.0000070000 0.0000080000 0.0013740000 38185429 96830484 509673472 4.1711668968 3.9348378181 3.9389147758 840 1311867198.4497859478 0.0922352150 0.0783759496 0.1207853556 0.0059687627 0.0064230000 0.0004540000 0.0022890000 0.0000000000 0.0000050000 0.0009920000 38188821 96830484 509673472 4.1693153381 3.9328794479 3.9379897118 841 1311867198.4856219292 0.0938936248 0.0783944011 0.1207853556 0.0059748595 0.0075520000 0.0004350000 0.0030960000 0.0000040000 0.0000040000 0.0017970000 38192493 96830484 509673472 4.1648554802 3.9345262051 3.9368560314 842 1311867198.5190339088 0.0936110988 0.0784124732 0.1207853556 0.0059725867 0.0058690000 0.0004370000 0.0023580000 0.0000010000 0.0000040000 0.0009680000 38196221 96830484 509673472 4.1627092361 3.9358577728 3.9360237122 843 1311867198.5499279499 0.0921615586 0.0784287829 0.1207853556 0.0059731286 0.0103970000 0.0005290000 0.0046640000 0.0000070000 0.0000080000 0.0013600000 38199893 96830484 509673472 4.1613082886 3.9346270561 3.9349918365 844 1311867198.5824239254 0.0910808444 0.0784437735 0.1207853556 0.0059706173 0.0067530000 0.0004490000 0.0026500000 0.0000010000 0.0000050000 0.0009810000 38203565 96830484 509673472 4.1602768898 3.9366595745 3.9341692924 845 1311867198.6147489548 0.0900135785 0.0784574656 0.1207853556 0.0059723672 0.0071040000 0.0004390000 0.0027110000 0.0000040000 0.0000040000 0.0017900000 38207237 96830484 509673472 4.1588592529 3.9363510609 3.9334304333 846 1311867198.6482009888 0.0900832266 0.0784712076 0.1207853556 0.0059699511 0.0080460000 0.0004200000 0.0045050000 0.0000010000 0.0000040000 0.0009630000 38210909 96830484 509673472 4.1562986374 3.9373266697 3.9325220585 847 1311867198.6827540398 0.0906635746 0.0784856024 0.1207853556 0.0059677460 0.0061430000 0.0004160000 0.0023480000 0.0000030000 0.0000040000 0.0012480000 38214637 96830484 509673472 4.1530041695 3.9382910728 3.9315447807 848 1311867198.7146520615 0.0903837010 0.0784996331 0.1207853556 0.0059642385 0.0062120000 0.0004220000 0.0026980000 0.0000010000 0.0000040000 0.0009670000 38218253 96830484 509673472 4.1514000893 3.9389686584 3.9310815334 849 1311867198.7467699051 0.0906278118 0.0785139184 0.1207853556 0.0059618052 0.0088580000 0.0004200000 0.0045000000 0.0000030000 0.0000030000 0.0017880000 38221869 96830484 509673472 4.1488866806 3.9386131763 3.9302799702 850 1311867198.7842700481 0.0896511897 0.0785270211 0.1207853556 0.0059586194 0.0085330000 0.0005260000 0.0029210000 0.0000010000 0.0000080000 0.0011040000 38225653 96830484 509673472 4.1480197906 3.9400374889 3.9298293591 851 1311867198.8149418831 0.0921280161 0.0785430034 0.1207853556 0.0059559275 0.0070980000 0.0004470000 0.0027620000 0.0000060000 0.0000040000 0.0012590000 38229269 96830484 509673472 4.1423830986 3.9405496120 3.9284589291 852 1311867198.8464009762 0.0925768092 0.0785594750 0.1207853556 0.0059531779 0.0089880000 0.0005250000 0.0029310000 0.0000010000 0.0000110000 0.0012380000 38232941 96830484 509673472 4.1399741173 3.9413144588 3.9277124405 853 1311867198.8845369816 0.0921517909 0.0785754097 0.1207853556 0.0059505920 0.0077680000 0.0004480000 0.0027550000 0.0000050000 0.0000050000 0.0018270000 38236669 96830484 509673472 4.1389365196 3.9422469139 3.9271509647 854 1311867198.9147930145 0.0929314047 0.0785922200 0.1207853556 0.0059471741 0.0063980000 0.0004340000 0.0027170000 0.0000000000 0.0000040000 0.0009710000 38240285 96830484 509673472 4.1364879608 3.9431064129 3.9263315201 855 1311867198.9465179443 0.0937737897 0.0786099763 0.1207853556 0.0059438645 0.0094220000 0.0005280000 0.0033250000 0.0000100000 0.0000100000 0.0013740000 38243957 96830484 509673472 4.1338863373 3.9443397522 3.9252800941 856 1311867198.9839329720 0.0941222534 0.0786280981 0.1207853556 0.0059407020 0.0065480000 0.0004500000 0.0024110000 0.0000010000 0.0000050000 0.0010030000 38247853 96830484 509673472 4.1315984726 3.9450409412 3.9244496822 857 1311867199.0148730278 0.0952941552 0.0786475451 0.1207853556 0.0059417835 0.0067940000 0.0004250000 0.0023580000 0.0000040000 0.0000030000 0.0017870000 38251469 96830484 509673472 4.1285233498 3.9461996555 3.9233851433 858 1311867199.0468010902 0.0969455391 0.0786688714 0.1207853556 0.0059431064 0.0090550000 0.0005290000 0.0033090000 0.0000000000 0.0000080000 0.0011050000 38255141 96830484 509673472 4.1261930466 3.9473481178 3.9225218296 859 1311867199.0849320889 0.0965430439 0.0786896795 0.1207853556 0.0059433964 0.0071210000 0.0004460000 0.0027710000 0.0000050000 0.0000040000 0.0012470000 38259037 96830484 509673472 4.1254906654 3.9485638142 3.9217019081 860 1311867199.1149818897 0.0978250653 0.0787119300 0.1207853556 0.0059407565 0.0073810000 0.0004240000 0.0038130000 0.0000010000 0.0000040000 0.0009690000 38262597 96830484 509673472 4.1227555275 3.9490282536 3.9205563068 861 1311867199.1465420723 0.0991772637 0.0787356992 0.1207853556 0.0059381901 0.0067570000 0.0004170000 0.0023600000 0.0000040000 0.0000040000 0.0017890000 38266269 96830484 509673472 4.1204447746 3.9504916668 3.9192922115 862 1311867199.1823658943 0.1005490944 0.0787610048 0.1207853556 0.0059368554 0.0087270000 0.0005220000 0.0029600000 0.0000010000 0.0000080000 0.0010840000 38270053 96830484 509673472 4.1182131767 3.9527621269 3.9180831909 863 1311867199.2146680355 0.1016372740 0.0787875126 0.1207853556 0.0059336165 0.0075200000 0.0004470000 0.0031330000 0.0000050000 0.0000040000 0.0012480000 38273781 96830484 509673472 4.1154985428 3.9528708458 3.9168224335 864 1311867199.2467749119 0.1017775163 0.0788141214 0.1207853556 0.0059303681 0.0059630000 0.0004230000 0.0023470000 0.0000000000 0.0000040000 0.0009680000 38277397 96830484 509673472 4.1143956184 3.9542524815 3.9159238338 865 1311867199.2833590508 0.1018747166 0.0788407811 0.1207853556 0.0059269544 0.0069430000 0.0004170000 0.0025900000 0.0000030000 0.0000030000 0.0017910000 38281237 96830484 509673472 4.1128416061 3.9550995827 3.9148173332 866 1311867199.3159129620 0.1024784818 0.0788680763 0.1207853556 0.0059270130 0.0086280000 0.0005210000 0.0029100000 0.0000010000 0.0000080000 0.0010990000 38284797 96830484 509673472 4.1108503342 3.9555153847 3.9135513306 867 1311867199.3465209007 0.1031576693 0.0788960920 0.1207853556 0.0059238391 0.0089420000 0.0004480000 0.0045750000 0.0000040000 0.0000040000 0.0012530000 38288413 96830484 509673472 4.1087355614 3.9561538696 3.9123151302 868 1311867199.3829050064 0.1032342240 0.0789241313 0.1207853556 0.0059207961 0.0066120000 0.0004260000 0.0030850000 0.0000010000 0.0000040000 0.0009720000 38292253 96830484 509673472 4.1068096161 3.9567816257 3.9111936092 869 1311867199.4147589207 0.1030792892 0.0789519278 0.1207853556 0.0059174279 0.0079080000 0.0004210000 0.0034230000 0.0000040000 0.0000040000 0.0017980000 38295869 96830484 509673472 4.1049427986 3.9564588070 3.9100074768 870 1311867199.4512910843 0.1033436134 0.0789799643 0.1207853556 0.0059146193 0.0055690000 0.0004160000 0.0019780000 0.0000000000 0.0000030000 0.0009740000 38299709 96830484 509673472 4.1025362015 3.9576475620 3.9086189270 871 1311867199.4837360382 0.1021274030 0.0790065400 0.1207853556 0.0059122005 0.0107470000 0.0005260000 0.0047870000 0.0000080000 0.0000080000 0.0013680000 38303381 96830484 509673472 4.1020689011 3.9578616619 3.9078948498 872 1311867199.5150198936 0.1018873230 0.0790327794 0.1207853556 0.0059089749 0.0072410000 0.0004470000 0.0031030000 0.0000000000 0.0000040000 0.0009800000 38307053 96830484 509673472 4.1003470421 3.9578843117 3.9070618153 873 1311867199.5544059277 0.1020376086 0.0790591309 0.1207853556 0.0059076942 0.0068120000 0.0004200000 0.0023580000 0.0000040000 0.0000030000 0.0018070000 38310949 96830484 509673472 4.0976076126 3.9589385986 3.9061119556 874 1311867199.5835030079 0.1023486927 0.0790857780 0.1207853556 0.0059043984 0.0055290000 0.0004150000 0.0019820000 0.0000010000 0.0000040000 0.0009780000 38314565 96830484 509673472 4.0950384140 3.9595210552 3.9053916931 875 1311867199.6158308983 0.1020024642 0.0791119685 0.1207853556 0.0059019145 0.0104870000 0.0005250000 0.0047850000 0.0000080000 0.0000070000 0.0013760000 38318125 96830484 509673472 4.0925655365 3.9594149590 3.9047544003 876 1311867199.6538460255 0.1003742591 0.0791362405 0.1207853556 0.0058996903 0.0067810000 0.0004410000 0.0026570000 0.0000000000 0.0000050000 0.0009890000 38322021 96830484 509673472 4.0916252136 3.9596366882 3.9044280052 877 1311867199.6824479103 0.1005998328 0.0791607144 0.1207853556 0.0058965466 0.0097250000 0.0005170000 0.0029180000 0.0000100000 0.0000100000 0.0019850000 38325581 96830484 509673472 4.0889902115 3.9593656063 3.9038786888 878 1311867199.7146759033 0.0996083170 0.0791840032 0.1207853556 0.0058940962 0.0069040000 0.0004460000 0.0027560000 0.0000000000 0.0000060000 0.0009940000 38329309 96830484 509673472 4.0875468254 3.9596304893 3.9033989906 879 1311867199.7511539459 0.0994279906 0.0792070339 0.1207853556 0.0058916910 0.0066670000 0.0004280000 0.0027080000 0.0000040000 0.0000040000 0.0012550000 38333037 96830484 509673472 4.0852155685 3.9605605602 3.9031276703 880 1311867199.7826020718 0.0998131558 0.0792304499 0.1207853556 0.0058896699 0.0062590000 0.0004260000 0.0025750000 0.0000000000 0.0000030000 0.0009830000 38336709 96830484 509673472 4.0820603371 3.9598419666 3.9025902748 881 1311867199.8150150776 0.0986407921 0.0792524821 0.1207853556 0.0058920134 0.0089910000 0.0004180000 0.0044770000 0.0000040000 0.0000030000 0.0018090000 38340381 96830484 509673472 4.0803456306 3.9593894482 3.9020414352 882 1311867199.8519051075 0.0983582959 0.0792741440 0.1207853556 0.0058890541 0.0062910000 0.0004150000 0.0026860000 0.0000000000 0.0000040000 0.0009810000 38344165 96830484 509673472 4.0784502029 3.9605915546 3.9017736912 883 1311867199.8839609623 0.0980349928 0.0792953908 0.1207853556 0.0058893146 0.0087550000 0.0005200000 0.0031840000 0.0000090000 0.0000070000 0.0013920000 38347893 96830484 509673472 4.0759553909 3.9595463276 3.9013988972 884 1311867199.9148159027 0.0978082716 0.0793163329 0.1207853556 0.0058872832 0.0060860000 0.0004470000 0.0020080000 0.0000010000 0.0000060000 0.0009920000 38351565 96830484 509673472 4.0736451149 3.9593207836 3.9010891914 885 1311867199.9520709515 0.0970402434 0.0793363599 0.1207853556 0.0058842057 0.0067720000 0.0004160000 0.0023350000 0.0000040000 0.0000030000 0.0017680000 38355349 96830484 509673472 4.0726933479 3.9601893425 3.9009034634 886 1311867199.9828410149 0.0957830921 0.0793549228 0.1207853556 0.0058826052 0.0106060000 0.0005240000 0.0047590000 0.0000010000 0.0000080000 0.0011160000 38358965 96830484 509673472 4.0714015961 3.9589793682 3.9005031586 887 1311867200.0144031048 0.0950555950 0.0793726237 0.1207853556 0.0058803622 0.0075280000 0.0004670000 0.0029790000 0.0000050000 0.0000050000 0.0012690000 38362637 96830484 509673472 4.0699272156 3.9593882561 3.9001846313 888 1311867200.0539638996 0.0947178900 0.0793899044 0.1207853556 0.0058793145 0.0059840000 0.0004270000 0.0023210000 0.0000010000 0.0000040000 0.0009730000 38366533 96830484 509673472 4.0681786537 3.9612510204 3.9001407623 889 1311867200.0830330849 0.0944627970 0.0794068593 0.1207853556 0.0058767461 0.0089490000 0.0005230000 0.0022720000 0.0000100000 0.0000100000 0.0019780000 38370093 96830484 509673472 4.0659899712 3.9598221779 3.9001615047 890 1311867200.1174468994 0.0947481468 0.0794240967 0.1207853556 0.0058757204 0.0071830000 0.0004490000 0.0030950000 0.0000010000 0.0000060000 0.0009920000 38373821 96830484 509673472 4.0628924370 3.9609603882 3.9000043869 891 1311867200.1517000198 0.0928363055 0.0794391497 0.1207853556 0.0058757767 0.0061710000 0.0004310000 0.0023360000 0.0000040000 0.0000040000 0.0011970000 38377549 96830484 509673472 4.0631475449 3.9612309933 3.9003145695 892 1311867200.1853220463 0.0933643579 0.0794547609 0.1207853556 0.0058759480 0.0091760000 0.0005750000 0.0031700000 0.0000010000 0.0000080000 0.0010520000 38381333 96830484 509673472 4.0599241257 3.9600241184 3.9002935886 893 1311867200.2179059982 0.0920581594 0.0794688745 0.1207853556 0.0058753454 0.0076720000 0.0004900000 0.0027390000 0.0000050000 0.0000050000 0.0017410000 38385005 96830484 509673472 4.0597758293 3.9618093967 3.9004743099 894 1311867200.2522649765 0.0917410851 0.0794826018 0.1207853556 0.0058721181 0.0067130000 0.0004310000 0.0030520000 0.0000010000 0.0000040000 0.0009400000 38388733 96830484 509673472 4.0577135086 3.9617109299 3.9009869099 895 1311867200.2825429440 0.0903118551 0.0794947015 0.1207853556 0.0058710966 0.0091010000 0.0005380000 0.0028980000 0.0000080000 0.0000080000 0.0013390000 38392349 96830484 509673472 4.0566182137 3.9607005119 3.9013271332 896 1311867200.3148880005 0.0901933610 0.0795066420 0.1207853556 0.0058680331 0.0085700000 0.0004440000 0.0045160000 0.0000000000 0.0000050000 0.0009380000 38396077 96830484 509673472 4.0547919273 3.9621453285 3.9018030167 897 1311867200.3514990807 0.0884514898 0.0795166139 0.1207853556 0.0058680473 0.0078050000 0.0004230000 0.0033810000 0.0000040000 0.0000030000 0.0017140000 38399805 96830484 509673472 4.0538420677 3.9602928162 3.9024462700 898 1311867200.3837759495 0.0879026726 0.0795259525 0.1207853556 0.0058741329 0.0080500000 0.0004170000 0.0044410000 0.0000000000 0.0000040000 0.0009700000 38403533 96830484 509673472 4.0520982742 3.9612047672 3.9028456211 899 1311867200.4162800312 0.0876694620 0.0795350109 0.1207853556 0.0058715826 0.0068940000 0.0004180000 0.0030260000 0.0000040000 0.0000040000 0.0011970000 38407149 96830484 509673472 4.0498542786 3.9610161781 3.9031908512 900 1311867200.4522490501 0.0872512162 0.0795435845 0.1207853556 0.0058693791 0.0080430000 0.0004100000 0.0044560000 0.0000000000 0.0000030000 0.0009260000 38410933 96830484 509673472 4.0469732285 3.9601798058 3.9033198357 901 1311867200.4850699902 0.0870819017 0.0795519511 0.1207853556 0.0058701235 0.0070730000 0.0004140000 0.0026630000 0.0000040000 0.0000040000 0.0017120000 38414605 96830484 509673472 4.0444283485 3.9606900215 3.9036850929 902 1311867200.5143918991 0.0866005793 0.0795597655 0.1207853556 0.0058680563 0.0069290000 0.0004100000 0.0033620000 0.0000000000 0.0000030000 0.0009270000 38418277 96830484 509673472 4.0422558784 3.9596788883 3.9043478966 903 1311867200.5505030155 0.0865242481 0.0795674781 0.1207853556 0.0058716347 0.0072560000 0.0004120000 0.0033710000 0.0000030000 0.0000030000 0.0012020000 38422061 96830484 509673472 4.0392231941 3.9601953030 3.9047565460 904 1311867200.5832219124 0.0876037031 0.0795763678 0.1207853556 0.0058765909 0.0080460000 0.0004130000 0.0044470000 0.0000000000 0.0000030000 0.0009350000 38425733 96830484 509673472 4.0357851982 3.9609110355 3.9053008556 905 1311867200.6145610809 0.0876324326 0.0795852695 0.1207853556 0.0058754872 0.0081780000 0.0004140000 0.0037400000 0.0000040000 0.0000030000 0.0017090000 38429349 96830484 509673472 4.0325179100 3.9600055218 3.9058866501 906 1311867200.6504778862 0.0862849653 0.0795926643 0.1207853556 0.0058748664 0.0103910000 0.0005230000 0.0047210000 0.0000010000 0.0000080000 0.0010650000 38433133 96830484 509673472 4.0311431885 3.9602370262 3.9064328671 907 1311867200.6851279736 0.0861175582 0.0795998582 0.1207853556 0.0058720567 0.0069230000 0.0004430000 0.0023690000 0.0000040000 0.0000050000 0.0012040000 38436917 96830484 509673472 4.0282983780 3.9600961208 3.9067621231 908 1311867200.7189719677 0.0868395343 0.0796078315 0.1207853556 0.0058701751 0.0077350000 0.0004240000 0.0041020000 0.0000000000 0.0000040000 0.0009350000 38440645 96830484 509673472 4.0242862701 3.9599032402 3.9070975780 909 1311867200.7503669262 0.0878221989 0.0796168682 0.1207853556 0.0058677098 0.0088890000 0.0004190000 0.0044410000 0.0000040000 0.0000040000 0.0017010000 38444261 96830484 509673472 4.0205712318 3.9607396126 3.9075064659 910 1311867200.7832930088 0.0872533843 0.0796252599 0.1207853556 0.0058720374 0.0076720000 0.0004170000 0.0040870000 0.0000000000 0.0000030000 0.0009190000 38447989 96830484 509673472 4.0186886787 3.9607858658 3.9080660343 911 1311867200.8181068897 0.0872301981 0.0796336078 0.1207853556 0.0058698325 0.0083640000 0.0004190000 0.0044720000 0.0000040000 0.0000030000 0.0011910000 38451717 96830484 509673472 4.0151324272 3.9605443478 3.9084057808 912 1311867200.8501501083 0.0877640694 0.0796425228 0.1207853556 0.0058670583 0.0062770000 0.0004180000 0.0026800000 0.0000000000 0.0000040000 0.0009230000 38455333 96830484 509673472 4.0122456551 3.9612066746 3.9089138508 913 1311867200.8845369816 0.0877153203 0.0796513649 0.1207853556 0.0058665794 0.0099690000 0.0005200000 0.0032640000 0.0000110000 0.0000100000 0.0018730000 38459173 96830484 509673472 4.0094590187 3.9608974457 3.9095878601 914 1311867200.9194929600 0.0890123174 0.0796616066 0.1207853556 0.0058661555 0.0076470000 0.0004450000 0.0034530000 0.0000010000 0.0000050000 0.0009400000 38462901 96830484 509673472 4.0053038597 3.9600534439 3.9100890160 915 1311867200.9512679577 0.0885170102 0.0796712847 0.1207853556 0.0058651147 0.0083920000 0.0004180000 0.0044590000 0.0000040000 0.0000040000 0.0012030000 38466517 96830484 509673472 4.0032906532 3.9601197243 3.9105679989 916 1311867200.9856009483 0.0888510793 0.0796813063 0.1207853556 0.0058665610 0.0080970000 0.0004190000 0.0044560000 0.0000000000 0.0000040000 0.0009250000 38470301 96830484 509673472 4.0017004013 3.9594073296 3.9107739925 917 1311867201.0184400082 0.0891866833 0.0796916720 0.1207853556 0.0058633739 0.0089390000 0.0004180000 0.0044530000 0.0000040000 0.0000040000 0.0016960000 38473973 96830484 509673472 3.9998073578 3.9594724178 3.9108245373 918 1311867201.0555179119 0.0892893448 0.0797021270 0.1207853556 0.0058618609 0.0080710000 0.0004140000 0.0044240000 0.0000010000 0.0000040000 0.0009230000 38477813 96830484 509673472 3.9981684685 3.9597785473 3.9106976986 919 1311867201.0825428963 0.0900955796 0.0797134365 0.1207853556 0.0058617580 0.0084020000 0.0004140000 0.0044440000 0.0000030000 0.0000030000 0.0011910000 38481317 96830484 509673472 3.9958381653 3.9591379166 3.9107525349 920 1311867201.1193449497 0.0906726569 0.0797253487 0.1207853556 0.0058595722 0.0078450000 0.0004250000 0.0040880000 0.0000010000 0.0000040000 0.0009310000 38485157 96830484 509673472 3.9938585758 3.9591193199 3.9108181000 921 1311867201.1506710052 0.0906450897 0.0797372051 0.1207853556 0.0058565115 0.0078470000 0.0004310000 0.0026670000 0.0000030000 0.0000030000 0.0020040000 38488717 96830484 509673472 3.9928553104 3.9593181610 3.9107549191 922 1311867201.1830160618 0.0905049220 0.0797488837 0.1207853556 0.0058545667 0.0069400000 0.0004650000 0.0031500000 0.0000000000 0.0000040000 0.0009330000 38492389 96830484 509673472 3.9917421341 3.9588043690 3.9108374119 923 1311867201.2196528912 0.0916495696 0.0797617772 0.1207853556 0.0058529258 0.0062590000 0.0004130000 0.0023100000 0.0000050000 0.0000040000 0.0011840000 38496117 96830484 509673472 3.9887452126 3.9597628117 3.9106483459 924 1311867201.2503149509 0.0911243409 0.0797740744 0.1207853556 0.0058497798 0.0081060000 0.0004200000 0.0044290000 0.0000000000 0.0000040000 0.0009390000 38499789 96830484 509673472 3.9881775379 3.9599494934 3.9108929634 925 1311867201.2824099064 0.0905794278 0.0797857558 0.1207853556 0.0058473762 0.0088730000 0.0004100000 0.0044130000 0.0000040000 0.0000030000 0.0017140000 38503461 96830484 509673472 3.9872384071 3.9604773521 3.9106116295 926 1311867201.3180539608 0.0905198529 0.0797973477 0.1207853556 0.0058454806 0.0070090000 0.0004170000 0.0033700000 0.0000010000 0.0000040000 0.0009290000 38507245 96830484 509673472 3.9849748611 3.9590463638 3.9105849266 927 1311867201.3522200584 0.0913928449 0.0798098564 0.1207853556 0.0058449261 0.0073110000 0.0004130000 0.0033690000 0.0000040000 0.0000040000 0.0012040000 38510973 96830484 509673472 3.9820950031 3.9605939388 3.9103443623 928 1311867201.3842790127 0.0908711925 0.0798217759 0.1207853556 0.0058449500 0.0072780000 0.0004160000 0.0036070000 0.0000010000 0.0000040000 0.0009370000 38514645 96830484 509673472 3.9805834293 3.9622032642 3.9103317261 929 1311867201.4198760986 0.0904106647 0.0798331741 0.1207853556 0.0058637712 0.0071090000 0.0004140000 0.0026570000 0.0000040000 0.0000030000 0.0017250000 38518317 96830484 509673472 3.9771738052 3.9605357647 3.9099113941 930 1311867201.4558579922 0.0908184275 0.0798449862 0.1207853556 0.0058659431 0.0081250000 0.0004140000 0.0044310000 0.0000000000 0.0000030000 0.0009440000 38521989 96830484 509673472 3.9737153053 3.9617559910 3.9097309113 931 1311867201.4853110313 0.0911793709 0.0798571606 0.1207853556 0.0058652497 0.0069270000 0.0004170000 0.0030250000 0.0000030000 0.0000040000 0.0011990000 38525605 96830484 509673472 3.9713141918 3.9643669128 3.9096822739 932 1311867201.5198690891 0.0906885192 0.0798687822 0.1207853556 0.0058638331 0.0081290000 0.0004130000 0.0044450000 0.0000010000 0.0000040000 0.0009370000 38529389 96830484 509673472 3.9684829712 3.9633383751 3.9097843170 933 1311867201.5527739525 0.0917182416 0.0798814826 0.1207853556 0.0058624808 0.0090010000 0.0004280000 0.0044320000 0.0000040000 0.0000040000 0.0017080000 38533005 96830484 509673472 3.9640653133 3.9638118744 3.9094476700 934 1311867201.5840220451 0.0910287052 0.0798934175 0.1207853556 0.0058594358 0.0069550000 0.0004190000 0.0032570000 0.0000000000 0.0000040000 0.0009330000 38536677 96830484 509673472 3.9626424313 3.9640626907 3.9093685150 935 1311867201.6197049618 0.0906284675 0.0799048989 0.1207853556 0.0058566805 0.0066720000 0.0004180000 0.0026590000 0.0000030000 0.0000030000 0.0012070000 38540461 96830484 509673472 3.9608142376 3.9642691612 3.9089934826 936 1311867201.6515579224 0.0894005373 0.0799150438 0.1207853556 0.0058558668 0.0105240000 0.0005240000 0.0047190000 0.0000010000 0.0000070000 0.0010750000 38544077 96830484 509673472 3.9598436356 3.9638962746 3.9087905884 937 1311867201.6839449406 0.0900098085 0.0799258173 0.1207853556 0.0058527926 0.0099860000 0.0005160000 0.0035840000 0.0000090000 0.0000080000 0.0018910000 38547805 96830484 509673472 3.9568307400 3.9648253918 3.9083168507 938 1311867201.7189009190 0.0905907452 0.0799371871 0.1207853556 0.0058526310 0.0075480000 0.0004430000 0.0034150000 0.0000000000 0.0000060000 0.0009510000 38551589 96830484 509673472 3.9547085762 3.9663352966 3.9083101749 939 1311867201.7507290840 0.0899282470 0.0799478272 0.1207853556 0.0058510209 0.0105990000 0.0005170000 0.0046940000 0.0000080000 0.0000070000 0.0013210000 38555261 96830484 509673472 3.9529421329 3.9655568600 3.9079296589 940 1311867201.7858049870 0.0898880363 0.0799584019 0.1207853556 0.0058543799 0.0084730000 0.0004450000 0.0043890000 0.0000010000 0.0000050000 0.0009500000 38558933 96830484 509673472 3.9504680634 3.9659733772 3.9077000618 941 1311867201.8190178871 0.0898023173 0.0799688631 0.1207853556 0.0058609589 0.0079190000 0.0004210000 0.0033890000 0.0000030000 0.0000030000 0.0017100000 38562717 96830484 509673472 3.9499981403 3.9689087868 3.9078993797 942 1311867201.8505740166 0.0893652216 0.0799788380 0.1207853556 0.0058635140 0.0060040000 0.0004180000 0.0023070000 0.0000010000 0.0000040000 0.0009360000 38566333 96830484 509673472 3.9485690594 3.9678335190 3.9076094627 943 1311867201.8862850666 0.0889678970 0.0799883704 0.1207853556 0.0058606981 0.0083150000 0.0004220000 0.0043240000 0.0000040000 0.0000040000 0.0011990000 38570061 96830484 509673472 3.9478201866 3.9677534103 3.9075272083 944 1311867201.9195730686 0.0898865536 0.0799988557 0.1207853556 0.0058601950 0.0081210000 0.0004160000 0.0044360000 0.0000010000 0.0000040000 0.0009230000 38573845 96830484 509673472 3.9458825588 3.9690856934 3.9073636532 945 1311867201.9516520500 0.0897110403 0.0800091332 0.1207853556 0.0058582004 0.0108300000 0.0005140000 0.0045320000 0.0000080000 0.0000070000 0.0018650000 38577405 96830484 509673472 3.9446234703 3.9685926437 3.9068350792 946 1311867201.9894599915 0.0886646956 0.0800182828 0.1207853556 0.0058556140 0.0074370000 0.0004320000 0.0034030000 0.0000010000 0.0000040000 0.0009490000 38581301 96830484 509673472 3.9448421001 3.9686851501 3.9062466621 947 1311867202.0184879303 0.0892287716 0.0800280088 0.1207853556 0.0058530513 0.0074070000 0.0004250000 0.0033660000 0.0000040000 0.0000040000 0.0011940000 38584861 96830484 509673472 3.9431536198 3.9692213535 3.9057502747 948 1311867202.0507359505 0.0883774981 0.0800368163 0.1207853556 0.0058508350 0.0081630000 0.0004190000 0.0044190000 0.0000010000 0.0000030000 0.0009450000 38588533 96830484 509673472 3.9435696602 3.9698698521 3.9052488804 949 1311867202.0866351128 0.0888001770 0.0800460506 0.1207853556 0.0058479856 0.0089040000 0.0004160000 0.0044220000 0.0000030000 0.0000030000 0.0017070000 38592317 96830484 509673472 3.9421129227 3.9702112675 3.9048478603 950 1311867202.1185920238 0.0898082927 0.0800563266 0.1207853556 0.0058462858 0.0090750000 0.0005130000 0.0032140000 0.0000010000 0.0000080000 0.0010830000 38595989 96830484 509673472 3.9393312931 3.9706127644 3.9045867920 951 1311867202.1516621113 0.0896601900 0.0800664253 0.1207853556 0.0058443639 0.0073610000 0.0004440000 0.0029420000 0.0000040000 0.0000040000 0.0011780000 38599717 96830484 509673472 3.9385731220 3.9718163013 3.9046499729 952 1311867202.1866259575 0.0879722461 0.0800747297 0.1207853556 0.0058422673 0.0080700000 0.0004370000 0.0044320000 0.0000000000 0.0000030000 0.0009290000 38603445 96830484 509673472 3.9394416809 3.9718120098 3.9046266079 953 1311867202.2191269398 0.0892675444 0.0800843759 0.1207853556 0.0058401887 0.0088400000 0.0004220000 0.0044250000 0.0000030000 0.0000030000 0.0016960000 38607117 96830484 509673472 3.9363932610 3.9721925259 3.9044563770 954 1311867202.2513220310 0.0888107643 0.0800935231 0.1207853556 0.0058374295 0.0087610000 0.0005160000 0.0028650000 0.0000010000 0.0000080000 0.0010510000 38610733 96830484 509673472 3.9357426167 3.9729635715 3.9046037197 955 1311867202.2868280411 0.0880952328 0.0801019018 0.1207853556 0.0058355108 0.0075360000 0.0004510000 0.0030750000 0.0000060000 0.0000050000 0.0012010000 38614517 96830484 509673472 3.9353156090 3.9738974571 3.9045939445 956 1311867202.3199880123 0.0887602568 0.0801109587 0.1207853556 0.0058340037 0.0067490000 0.0004270000 0.0030260000 0.0000000000 0.0000040000 0.0009190000 38618189 96830484 509673472 3.9327259064 3.9723598957 3.9045443535 957 1311867202.3523900509 0.0882091820 0.0801194208 0.1207853556 0.0058314996 0.0088120000 0.0004230000 0.0044320000 0.0000030000 0.0000040000 0.0016890000 38621861 96830484 509673472 3.9318156242 3.9727184772 3.9043910503 958 1311867202.3883628845 0.0876385421 0.0801272696 0.1207853556 0.0058286605 0.0073470000 0.0004230000 0.0037170000 0.0000000000 0.0000040000 0.0009230000 38625645 96830484 509673472 3.9311423302 3.9741995335 3.9043834209 959 1311867202.4196391106 0.0882886946 0.0801357799 0.1207853556 0.0058275027 0.0082770000 0.0004220000 0.0044170000 0.0000030000 0.0000040000 0.0011760000 38629317 96830484 509673472 3.9293057919 3.9738802910 3.9043595791 960 1311867202.4529430866 0.0882094353 0.0801441900 0.1207853556 0.0058248929 0.0081140000 0.0004310000 0.0044160000 0.0000010000 0.0000030000 0.0009230000 38632989 96830484 509673472 3.9284212589 3.9728929996 3.9044308662 961 1311867202.4875710011 0.0888454095 0.0801532443 0.1207853556 0.0058245142 0.0088830000 0.0004430000 0.0044120000 0.0000030000 0.0000040000 0.0016910000 38636717 96830484 509673472 3.9273769855 3.9739565849 3.9048082829 962 1311867202.5206449032 0.0890093520 0.0801624502 0.1207853556 0.0058386118 0.0103540000 0.0005170000 0.0045700000 0.0000010000 0.0000080000 0.0010450000 38640389 96830484 509673472 3.9261100292 3.9747400284 3.9045948982 963 1311867202.5508940220 0.0896261856 0.0801722776 0.1207853556 0.0058356557 0.0068360000 0.0004460000 0.0023480000 0.0000050000 0.0000050000 0.0012010000 38644005 96830484 509673472 3.9245519638 3.9743237495 3.9047646523 964 1311867202.5864949226 0.0903614983 0.0801828473 0.1207853556 0.0058449597 0.0060300000 0.0004260000 0.0023140000 0.0000000000 0.0000040000 0.0009230000 38647845 96830484 509673472 3.9229972363 3.9735596180 3.9047477245 965 1311867202.6185030937 0.0904754400 0.0801935132 0.1207853556 0.0058461341 0.0088870000 0.0004210000 0.0044190000 0.0000040000 0.0000040000 0.0017050000 38651517 96830484 509673472 3.9214963913 3.9735159874 3.9041471481 966 1311867202.6514449120 0.0915278643 0.0802052465 0.1207853556 0.0058509228 0.0084690000 0.0005280000 0.0028200000 0.0000010000 0.0000080000 0.0010580000 38655189 96830484 509673472 3.9185152054 3.9745469093 3.9034109116 967 1311867202.6866559982 0.0911265984 0.0802165406 0.1207853556 0.0058485035 0.0089240000 0.0004450000 0.0044900000 0.0000050000 0.0000050000 0.0012130000 38658973 96830484 509673472 3.9177520275 3.9752728939 3.9027495384 968 1311867202.7185359001 0.0914035738 0.0802280974 0.1207853556 0.0058459656 0.0063500000 0.0004270000 0.0026410000 0.0000000000 0.0000030000 0.0009360000 38662645 96830484 509673472 3.9153392315 3.9738862514 3.9016113281 969 1311867202.7507350445 0.0912239030 0.0802394450 0.1207853556 0.0058439566 0.0090160000 0.0005210000 0.0027810000 0.0000080000 0.0000070000 0.0018830000 38666317 96830484 509673472 3.9134776592 3.9728484154 3.9002983570 970 1311867202.7897169590 0.0915978551 0.0802511547 0.1207853556 0.0058413465 0.0084510000 0.0004410000 0.0044360000 0.0000000000 0.0000050000 0.0009660000 38670213 96830484 509673472 3.9119334221 3.9738647938 3.8994185925 971 1311867202.8190000057 0.0919237658 0.0802631759 0.1207853556 0.0058399745 0.0086290000 0.0005170000 0.0024640000 0.0000070000 0.0000080000 0.0013390000 38673829 96830484 509673472 3.9100241661 3.9740810394 3.8983874321 972 1311867202.8527579308 0.0911442935 0.0802743705 0.1207853556 0.0058370332 0.0102240000 0.0005170000 0.0046320000 0.0000010000 0.0000090000 0.0010830000 38677501 96830484 509673472 3.9089529514 3.9738447666 3.8973889351 973 1311867202.8873219490 0.0905855969 0.0802849678 0.1207853556 0.0058362307 0.0108670000 0.0005090000 0.0046350000 0.0000080000 0.0000080000 0.0018830000 38681229 96830484 509673472 3.9086794853 3.9755394459 3.8969635963 974 1311867202.9199879169 0.0902740210 0.0802952235 0.1207853556 0.0058339083 0.0085310000 0.0004430000 0.0044530000 0.0000010000 0.0000060000 0.0010100000 38684901 96830484 509673472 3.9087965488 3.9760460854 3.8972260952 975 1311867202.9525690079 0.0909366235 0.0803061378 0.1207853556 0.0058375422 0.0093700000 0.0005050000 0.0035310000 0.0000080000 0.0000070000 0.0013430000 38688629 96830484 509673472 3.9077556133 3.9752063751 3.8972651958 976 1311867202.9868710041 0.0891108215 0.0803151590 0.1207853556 0.0058427897 0.0085470000 0.0004420000 0.0044520000 0.0000000000 0.0000050000 0.0009740000 38692357 96830484 509673472 3.9097299576 3.9756352901 3.8978135586 977 1311867203.0202019215 0.0896389037 0.0803247022 0.1207853556 0.0058398414 0.0090080000 0.0004200000 0.0043850000 0.0000040000 0.0000040000 0.0018190000 38696029 96830484 509673472 3.9092433453 3.9760005474 3.8981893063 978 1311867203.0560851097 0.0902468935 0.0803348476 0.1207853556 0.0058432298 0.0093950000 0.0005150000 0.0032410000 0.0000020000 0.0000110000 0.0010880000 38699813 96830484 509673472 3.9088842869 3.9732558727 3.8986687660 979 1311867203.0865778923 0.0905841067 0.0803453167 0.1207853556 0.0058416305 0.0092960000 0.0005090000 0.0028770000 0.0000100000 0.0000100000 0.0013450000 38703429 96830484 509673472 3.9098908901 3.9734957218 3.8991873264 980 1311867203.1189930439 0.0900776237 0.0803552476 0.1207853556 0.0058483529 0.0109450000 0.0005680000 0.0046840000 0.0000010000 0.0000080000 0.0010790000 38707101 96830484 509673472 3.9110794067 3.9715569019 3.8995010853 981 1311867203.1549820900 0.0908213556 0.0803659165 0.1207853556 0.0058535533 0.0094850000 0.0004860000 0.0044730000 0.0000050000 0.0000050000 0.0017330000 38710885 96830484 509673472 3.9105148315 3.9696683884 3.8995952606 982 1311867203.1877939701 0.0927531794 0.0803785308 0.1207853556 0.0058870696 0.0081070000 0.0004230000 0.0044130000 0.0000010000 0.0000040000 0.0009340000 38714557 96830484 509673472 3.9086902142 3.9679799080 3.8993849754 983 1311867203.2185909748 0.0930772796 0.0803914491 0.1207853556 0.0058870434 0.0085490000 0.0004170000 0.0043920000 0.0000040000 0.0000030000 0.0012050000 38718229 96830484 509673472 3.9099318981 3.9696190357 3.8993289471 984 1311867203.2552030087 0.0933390036 0.0804046072 0.1207853556 0.0058853574 0.0071270000 0.0004180000 0.0033400000 0.0000010000 0.0000040000 0.0009510000 38722013 96830484 509673472 3.9098176956 3.9675009251 3.8991208076 985 1311867203.2864799500 0.0937591717 0.0804181652 0.1207853556 0.0058848431 0.0090080000 0.0004180000 0.0043970000 0.0000040000 0.0000030000 0.0017240000 38725629 96830484 509673472 3.9091284275 3.9662814140 3.8984589577 986 1311867203.3194670677 0.0929173231 0.0804308418 0.1207853556 0.0058823138 0.0082040000 0.0004210000 0.0043950000 0.0000010000 0.0000040000 0.0009460000 38729413 96830484 509673472 3.9106402397 3.9661910534 3.8980391026 987 1311867203.3547461033 0.0925633386 0.0804431341 0.1207853556 0.0058805028 0.0091610000 0.0005170000 0.0028330000 0.0000090000 0.0000080000 0.0013440000 38733085 96830484 509673472 3.9116463661 3.9663443565 3.8978209496 988 1311867203.3865599632 0.0918522477 0.0804546818 0.1207853556 0.0058833713 0.0077500000 0.0004450000 0.0034080000 0.0000000000 0.0000050000 0.0009600000 38736757 96830484 509673472 3.9122641087 3.9646680355 3.8975689411 989 1311867203.4183609486 0.0914348066 0.0804657840 0.1207853556 0.0058893200 0.0083190000 0.0004200000 0.0036990000 0.0000030000 0.0000040000 0.0017170000 38740485 96830484 509673472 3.9118368626 3.9606685638 3.8968029022 990 1311867203.4545118809 0.0922550783 0.0804776924 0.1207853556 0.0058874402 0.0082020000 0.0004200000 0.0043950000 0.0000000000 0.0000030000 0.0009440000 38744269 96830484 509673472 3.9112064838 3.9604668617 3.8966014385 991 1311867203.4864439964 0.0913131610 0.0804886263 0.1207853556 0.0058859823 0.0067620000 0.0004170000 0.0026360000 0.0000040000 0.0000040000 0.0012100000 38747885 96830484 509673472 3.9120082855 3.9584782124 3.8964889050 992 1311867203.5185539722 0.0917676911 0.0804999963 0.1207853556 0.0058875602 0.0082600000 0.0004220000 0.0043960000 0.0000010000 0.0000040000 0.0009460000 38751613 96830484 509673472 3.9110906124 3.9553165436 3.8957438469 993 1311867203.5560259819 0.0924206004 0.0805120009 0.1207853556 0.0058850401 0.0073200000 0.0004150000 0.0026620000 0.0000040000 0.0000040000 0.0017310000 38755397 96830484 509673472 3.9103603363 3.9530985355 3.8951091766 994 1311867203.5876550674 0.0923602879 0.0805239207 0.1207853556 0.0058827082 0.0068530000 0.0004220000 0.0029950000 0.0000000000 0.0000030000 0.0009560000 38759069 96830484 509673472 3.9106724262 3.9522030354 3.8947722912 995 1311867203.6191980839 0.0921861008 0.0805356415 0.1207853556 0.0058810600 0.0085470000 0.0004170000 0.0043980000 0.0000040000 0.0000040000 0.0012070000 38762741 96830484 509673472 3.9106402397 3.9496004581 3.8944711685 996 1311867203.6557719707 0.0911235809 0.0805462720 0.1207853556 0.0058783967 0.0082390000 0.0004190000 0.0044050000 0.0000000000 0.0000040000 0.0009480000 38766469 96830484 509673472 3.9117612839 3.9469285011 3.8938107491 997 1311867203.6866750717 0.0924699605 0.0805582316 0.1207853556 0.0058767381 0.0080040000 0.0004150000 0.0033470000 0.0000040000 0.0000040000 0.0017210000 38770141 96830484 509673472 3.9097244740 3.9455358982 3.8933150768 998 1311867203.7195260525 0.0913821533 0.0805690772 0.1207853556 0.0058748925 0.0082700000 0.0004150000 0.0043950000 0.0000000000 0.0000030000 0.0009440000 38773813 96830484 509673472 3.9114656448 3.9437541962 3.8930695057 999 1311867203.7566421032 0.0918987989 0.0805804182 0.1207853556 0.0058723023 0.0075280000 0.0004150000 0.0033550000 0.0000030000 0.0000030000 0.0012060000 38777653 96830484 509673472 3.9114992619 3.9425599575 3.8930301666 1000 1311867203.7867228985 0.0920955017 0.0805919333 0.1207853556 0.0058693868 0.0083150000 0.0004190000 0.0044130000 0.0000010000 0.0000040000 0.0009490000 38781269 96830484 509673472 3.9111602306 3.9405224323 3.8927054405 1001 1311867203.8193860054 0.0916243643 0.0806029547 0.1207853556 0.0058666506 0.0073280000 0.0004200000 0.0026380000 0.0000040000 0.0000030000 0.0017280000 38784941 96830484 509673472 3.9119789600 3.9391508102 3.8921782970 1002 1311867203.8572859764 0.0922303051 0.0806145589 0.1207853556 0.0058652267 0.0064710000 0.0004190000 0.0026600000 0.0000010000 0.0000040000 0.0009530000 38788781 96830484 509673472 3.9113850594 3.9379880428 3.8914771080 1003 1311867203.8891890049 0.0923295319 0.0806262388 0.1207853556 0.0058629877 0.0070820000 0.0004160000 0.0029980000 0.0000040000 0.0000030000 0.0012060000 38792453 96830484 509673472 3.9108667374 3.9360842705 3.8905334473 1004 1311867203.9188020229 0.0924186558 0.0806379842 0.1207853556 0.0058605128 0.0081950000 0.0004160000 0.0044050000 0.0000010000 0.0000040000 0.0009500000 38796069 96830484 509673472 3.9104816914 3.9346456528 3.8897078037 1005 1311867203.9553489685 0.0929694995 0.0806502544 0.1207853556 0.0058579443 0.0090630000 0.0004110000 0.0044040000 0.0000030000 0.0000030000 0.0017430000 38799853 96830484 509673472 3.9101803303 3.9357099533 3.8887014389 1006 1311867203.9866371155 0.0922335610 0.0806617686 0.1207853556 0.0058584606 0.0082460000 0.0004130000 0.0044120000 0.0000000000 0.0000030000 0.0009470000 38803525 96830484 509673472 3.9104826450 3.9325456619 3.8877015114 1007 1311867204.0199849606 0.0919386819 0.0806729671 0.1207853556 0.0058569304 0.0085600000 0.0004130000 0.0044160000 0.0000030000 0.0000030000 0.0012210000 38807197 96830484 509673472 3.9109535217 3.9324123859 3.8864505291 1008 1311867204.0551509857 0.0933169723 0.0806855108 0.1207853556 0.0058543834 0.0092010000 0.0005200000 0.0028520000 0.0000010000 0.0000100000 0.0010960000 38810981 96830484 509673472 3.9090509415 3.9311268330 3.8853728771 1009 1311867204.0867509842 0.0919024125 0.0806966277 0.1207853556 0.0058545404 0.0086630000 0.0004420000 0.0030570000 0.0000040000 0.0000040000 0.0017670000 38814653 96830484 509673472 3.9102525711 3.9291498661 3.8841819763 1010 1311867204.1191530228 0.0924222395 0.0807082372 0.1207853556 0.0058517977 0.0086530000 0.0004710000 0.0045010000 0.0000010000 0.0000040000 0.0009560000 38818325 96830484 509673472 3.9097943306 3.9280548096 3.8831689358 1011 1311867204.1555769444 0.0923430696 0.0807197454 0.1207853556 0.0058492079 0.0064530000 0.0004180000 0.0022980000 0.0000040000 0.0000040000 0.0012240000 38822053 96830484 509673472 3.9098961353 3.9263691902 3.8823957443 1012 1311867204.1876530647 0.0915557072 0.0807304529 0.1207853556 0.0058483831 0.0075610000 0.0004140000 0.0036990000 0.0000010000 0.0000040000 0.0009630000 38825725 96830484 509673472 3.9106652737 3.9246785641 3.8816933632 1013 1311867204.2187769413 0.0927397609 0.0807423081 0.1207853556 0.0058469097 0.0091890000 0.0004180000 0.0044030000 0.0000040000 0.0000030000 0.0017720000 38829397 96830484 509673472 3.9094033241 3.9241368771 3.8812537193 1014 1311867204.2566440105 0.0920370743 0.0807534469 0.1207853556 0.0058445371 0.0083000000 0.0004160000 0.0044020000 0.0000000000 0.0000030000 0.0009710000 38833237 96830484 509673472 3.9105720520 3.9224250317 3.8808276653 1015 1311867204.2867140770 0.0919775143 0.0807645051 0.1207853556 0.0058420086 0.0068250000 0.0004040000 0.0026480000 0.0000040000 0.0000040000 0.0012400000 38836853 96830484 509673472 3.9101772308 3.9200510979 3.8800704479 1016 1311867204.3204538822 0.0926536024 0.0807762070 0.1207853556 0.0058394171 0.0104190000 0.0005170000 0.0043380000 0.0000010000 0.0000080000 0.0011150000 38840525 96830484 509673472 3.9097545147 3.9195280075 3.8797323704 1017 1311867204.3625741005 0.0933744386 0.0807885946 0.1207853556 0.0058366420 0.0103130000 0.0005100000 0.0035760000 0.0000080000 0.0000070000 0.0019300000 38844533 96830484 509673472 3.9090266228 3.9179980755 3.8796563148 1018 1311867204.3869600296 0.0941957608 0.0808017647 0.1207853556 0.0058340572 0.0084500000 0.0005030000 0.0024720000 0.0000010000 0.0000080000 0.0010860000 38847981 96830484 509673472 3.9076461792 3.9167144299 3.8791911602 1019 1311867204.4240970612 0.0944772437 0.0808151852 0.1207853556 0.0058313669 0.0090710000 0.0004350000 0.0044540000 0.0000040000 0.0000040000 0.0012510000 38851821 96830484 509673472 3.9074974060 3.9152834415 3.8789255619 1020 1311867204.4549949169 0.0948555917 0.0808289503 0.1207853556 0.0058296013 0.0061090000 0.0004160000 0.0022650000 0.0000010000 0.0000040000 0.0009850000 38855437 96830484 509673472 3.9073791504 3.9147777557 3.8787941933 1021 1311867204.4872748852 0.0945712626 0.0808424100 0.1207853556 0.0058281138 0.0072840000 0.0004090000 0.0026220000 0.0000040000 0.0000040000 0.0017840000 38859109 96830484 509673472 3.9073824883 3.9126183987 3.8783485889 1022 1311867204.5237219334 0.0960867330 0.0808573261 0.1207853556 0.0058256619 0.0071610000 0.0004110000 0.0033070000 0.0000010000 0.0000040000 0.0009720000 38862949 96830484 509673472 3.9054708481 3.9112257957 3.8780982494 1023 1311867204.5581860542 0.0964804962 0.0808725980 0.1207853556 0.0058247548 0.0063510000 0.0004040000 0.0022540000 0.0000040000 0.0000030000 0.0012360000 38866677 96830484 509673472 3.9053561687 3.9112207890 3.8779356480 1024 1311867204.5878469944 0.0961567611 0.0808875240 0.1207853556 0.0058227096 0.0105650000 0.0005040000 0.0046150000 0.0000010000 0.0000070000 0.0011100000 38870293 96830484 509673472 3.9049928188 3.9086246490 3.8778679371 1025 1311867204.6241528988 0.0966755599 0.0809029269 0.1207853556 0.0058200638 0.0082580000 0.0004270000 0.0030100000 0.0000050000 0.0000050000 0.0018200000 38972381 96830484 509673472 3.9036915302 3.9081203938 3.8778927326 1026 1311867204.6541819572 0.0966608822 0.0809182856 0.1207853556 0.0058175693 0.0106370000 0.0004930000 0.0046070000 0.0000010000 0.0000080000 0.0011110000 39180797 96830484 509673472 3.9035685062 3.9060614109 3.8781247139 1027 1311867204.6871540546 0.0965815410 0.0809335370 0.1207853556 0.0058150903 0.0086790000 0.0004300000 0.0040600000 0.0000050000 0.0000050000 0.0012600000 39184469 96830484 509673472 3.9035043716 3.9050431252 3.8781507015 1028 1311867204.7225689888 0.0977956131 0.0809499398 0.1207853556 0.0058146926 0.0070730000 0.0004030000 0.0033110000 0.0000010000 0.0000040000 0.0009830000 39188253 96830484 509673472 3.9023857117 3.9052228928 3.8785161972 1029 1311867204.7539510727 0.0986119509 0.0809671041 0.1207853556 0.0058121486 0.0089200000 0.0003980000 0.0043190000 0.0000040000 0.0000040000 0.0018020000 39191925 96830484 509673472 3.9003427029 3.9034445286 3.8788716793 1030 1311867204.7878720760 0.0982266963 0.0809838610 0.1207853556 0.0058103907 0.0080810000 0.0003990000 0.0043370000 0.0000010000 0.0000040000 0.0009810000 39195653 96830484 509673472 3.8997147083 3.9016430378 3.8796219826 1031 1311867204.8227200508 0.0980867743 0.0810004496 0.1207853556 0.0058082394 0.0072490000 0.0003940000 0.0032780000 0.0000040000 0.0000040000 0.0012350000 39199381 96830484 509673472 3.8998379707 3.9015712738 3.8810942173 1032 1311867204.8542668819 0.0969515815 0.0810159062 0.1207853556 0.0058079488 0.0080550000 0.0003940000 0.0043250000 0.0000010000 0.0000040000 0.0009780000 39203053 96830484 509673472 3.9001798630 3.8993332386 3.8821060658 1033 1311867204.8864960670 0.0971724167 0.0810315465 0.1207853556 0.0058057912 0.0088830000 0.0003940000 0.0043240000 0.0000030000 0.0000030000 0.0018040000 39206725 96830484 509673472 3.8991038799 3.8963310719 3.8832025528 1034 1311867204.9220221043 0.0984548032 0.0810483969 0.1207853556 0.0058032140 0.0066900000 0.0003970000 0.0029480000 0.0000000000 0.0000040000 0.0009820000 39210509 96830484 509673472 3.8972442150 3.8949885368 3.8844296932 1035 1311867204.9542920589 0.0990834311 0.0810658220 0.1207853556 0.0058005665 0.0083120000 0.0003940000 0.0043110000 0.0000040000 0.0000040000 0.0012500000 39214181 96830484 509673472 3.8960978985 3.8937392235 3.8854169846 1036 1311867204.9865999222 0.0974477232 0.0810816347 0.1207853556 0.0057994465 0.0100610000 0.0005020000 0.0039270000 0.0000010000 0.0000090000 0.0011180000 39217853 96830484 509673472 3.8976390362 3.8903646469 3.8861458302 1037 1311867205.0227239132 0.0975286141 0.0810974948 0.1207853556 0.0058006701 0.0095030000 0.0004200000 0.0043810000 0.0000050000 0.0000040000 0.0018330000 39221637 96830484 509673472 3.8975603580 3.8886232376 3.8869063854 1038 1311867205.0550808907 0.0969939679 0.0811128094 0.1207853556 0.0058144474 0.0063450000 0.0003960000 0.0025860000 0.0000010000 0.0000040000 0.0009890000 39225365 96830484 509673472 3.8979394436 3.8884406090 3.8877363205 1039 1311867205.0880999565 0.0972967818 0.0811283858 0.1207853556 0.0058119728 0.0083280000 0.0003940000 0.0042980000 0.0000030000 0.0000040000 0.0012480000 39228925 96830484 509673472 3.8970725536 3.8856272697 3.8885710239 1040 1311867205.1232450008 0.0993930101 0.0811459480 0.1207853556 0.0058120948 0.0092190000 0.0005280000 0.0027920000 0.0000010000 0.0000100000 0.0011510000 39232709 96830484 509673472 3.8951406479 3.8845577240 3.8892745972 1041 1311867205.1545319557 0.0983368978 0.0811624619 0.1207853556 0.0058179011 0.0086390000 0.0004170000 0.0033350000 0.0000060000 0.0000050000 0.0018400000 39236325 96830484 509673472 3.8977577686 3.8835973740 3.8900182247 1042 1311867205.1863510609 0.0980825499 0.0811787000 0.1207853556 0.0058248297 0.0081270000 0.0004060000 0.0042960000 0.0000000000 0.0000040000 0.0010050000 39239997 96830484 509673472 3.8977396488 3.8808426857 3.8907365799 1043 1311867205.2223129272 0.0988252684 0.0811956190 0.1207853556 0.0058239571 0.0093330000 0.0004890000 0.0031300000 0.0000090000 0.0000070000 0.0013710000 39243781 96830484 509673472 3.8966166973 3.8789894581 3.8912847042 1044 1311867205.2541849613 0.0974420458 0.0812111807 0.1207853556 0.0058222973 0.0086190000 0.0004210000 0.0043370000 0.0000000000 0.0000050000 0.0010120000 39247453 96830484 509673472 3.8981301785 3.8773450851 3.8919494152 1045 1311867205.2880499363 0.0979669392 0.0812272149 0.1207853556 0.0058198894 0.0077560000 0.0003960000 0.0031320000 0.0000040000 0.0000040000 0.0018300000 39251181 96830484 509673472 3.8975546360 3.8754589558 3.8928697109 1046 1311867205.3218879700 0.0981276333 0.0812433721 0.1207853556 0.0058184257 0.0080540000 0.0003790000 0.0042790000 0.0000010000 0.0000040000 0.0009990000 39254853 96830484 509673472 3.8970203400 3.8730468750 3.8935782909 1047 1311867205.3542900085 0.0980816483 0.0812594545 0.1207853556 0.0058231946 0.0082880000 0.0003790000 0.0042550000 0.0000040000 0.0000040000 0.0012570000 39258581 96830484 509673472 3.8969836235 3.8714528084 3.8945202827 1048 1311867205.3862779140 0.0988090634 0.0812762003 0.1207853556 0.0058304059 0.0080420000 0.0003800000 0.0042720000 0.0000000000 0.0000030000 0.0009980000 39262253 96830484 509673472 3.8956918716 3.8702147007 3.8955616951 1049 1311867205.4225649834 0.0985695869 0.0812926859 0.1207853556 0.0058338282 0.0088700000 0.0004900000 0.0023490000 0.0000080000 0.0000080000 0.0020130000 39266037 96830484 509673472 3.8949811459 3.8681585789 3.8960709572 1050 1311867205.4540419579 0.0982266739 0.0813088135 0.1207853556 0.0058357716 0.0075530000 0.0004040000 0.0032740000 0.0000000000 0.0000050000 0.0010140000 39269709 96830484 509673472 3.8953864574 3.8674993515 3.8969931602 1051 1311867205.4865119457 0.0979457870 0.0813246432 0.1207853556 0.0058366364 0.0083230000 0.0003790000 0.0042500000 0.0000030000 0.0000030000 0.0012630000 39273381 96830484 509673472 3.8940851688 3.8655302525 3.8981325626 1052 1311867205.5230340958 0.0973246396 0.0813398523 0.1207853556 0.0058470564 0.0106940000 0.0004940000 0.0045500000 0.0000010000 0.0000090000 0.0011310000 39277165 96830484 509673472 3.8937840462 3.8634212017 3.8988869190 1053 1311867205.5542900562 0.0984787419 0.0813561286 0.1207853556 0.0058688687 0.0095690000 0.0004070000 0.0043180000 0.0000050000 0.0000050000 0.0018590000 39280837 96830484 509673472 3.8919107914 3.8639922142 3.8998770714 1054 1311867205.5866839886 0.0980061814 0.0813719256 0.1207853556 0.0058661326 0.0081080000 0.0003970000 0.0042630000 0.0000010000 0.0000050000 0.0009980000 39284509 96830484 509673472 3.8915088177 3.8627738953 3.9011230469 1055 1311867205.6226179600 0.0982704684 0.0813879432 0.1207853556 0.0058684104 0.0062770000 0.0003840000 0.0022140000 0.0000040000 0.0000040000 0.0012710000 39288293 96830484 509673472 3.8889851570 3.8592805862 3.9020082951 1056 1311867205.6555979252 0.0995797589 0.0814051703 0.1207853556 0.0058667625 0.0073460000 0.0003830000 0.0035550000 0.0000010000 0.0000040000 0.0010080000 39291965 96830484 509673472 3.8862345219 3.8576979637 3.9028620720 1057 1311867205.6902959347 0.0985518172 0.0814213922 0.1207853556 0.0058642606 0.0087530000 0.0004390000 0.0023260000 0.0000080000 0.0000070000 0.0020060000 39295749 96830484 509673472 3.8868947029 3.8559701443 3.9036126137 1058 1311867205.7222061157 0.0981434286 0.0814371976 0.1207853556 0.0058615215 0.0086350000 0.0004150000 0.0042840000 0.0000000000 0.0000050000 0.0010200000 39299421 96830484 509673472 3.8861043453 3.8529551029 3.9041285515 1059 1311867205.7548348904 0.0979448706 0.0814527856 0.1207853556 0.0058590353 0.0084540000 0.0003830000 0.0042400000 0.0000030000 0.0000040000 0.0012810000 39303149 96830484 509673472 3.8852889538 3.8508162498 3.9043862820 1060 1311867205.7906379700 0.0987962484 0.0814691473 0.1207853556 0.0058570903 0.0074200000 0.0003740000 0.0035350000 0.0000000000 0.0000040000 0.0010200000 39306877 96830484 509673472 3.8837356567 3.8494081497 3.9052841663 1061 1311867205.8232109547 0.0977221578 0.0814844659 0.1207853556 0.0058680060 0.0089980000 0.0003750000 0.0042270000 0.0000030000 0.0000030000 0.0018660000 39310605 96830484 509673472 3.8838686943 3.8461158276 3.9056394100 1062 1311867205.8554759026 0.0983918756 0.0815003862 0.1207853556 0.0058704440 0.0080810000 0.0003740000 0.0042010000 0.0000000000 0.0000040000 0.0010180000 39314333 96830484 509673472 3.8823633194 3.8452060223 3.9062252045 1063 1311867205.8905880451 0.0993566886 0.0815171843 0.1207853556 0.0058702432 0.0083530000 0.0003670000 0.0042010000 0.0000030000 0.0000030000 0.0012680000 39318005 96830484 509673472 3.8806049824 3.8445038795 3.9065418243 1064 1311867205.9223020077 0.0981775969 0.0815328425 0.1207853556 0.0058786634 0.0108690000 0.0004710000 0.0045010000 0.0000010000 0.0000080000 0.0011630000 39321677 96830484 509673472 3.8813166618 3.8427288532 3.9068980217 1065 1311867205.9544939995 0.0981957912 0.0815484885 0.1207853556 0.0058763591 0.0083170000 0.0004030000 0.0029230000 0.0000050000 0.0000040000 0.0018900000 39325349 96830484 509673472 3.8804471493 3.8406474590 3.9072296619 1066 1311867205.9905850887 0.1001716629 0.0815659587 0.1207853556 0.0058852692 0.0067900000 0.0003770000 0.0028640000 0.0000000000 0.0000050000 0.0010110000 39329189 96830484 509673472 3.8780646324 3.8406798840 3.9077897072 1067 1311867206.0259850025 0.0996780321 0.0815829334 0.1207853556 0.0058860362 0.0095630000 0.0004760000 0.0030780000 0.0000270000 0.0000090000 0.0014040000 39332917 96830484 509673472 3.8785905838 3.8407042027 3.9078550339 1068 1311867206.0604250431 0.0998595804 0.0816000464 0.1207853556 0.0058927433 0.0086040000 0.0004720000 0.0037160000 0.0000010000 0.0000060000 0.0010420000 39336589 96830484 509673472 3.8768215179 3.8365764618 3.9080085754 1069 1311867206.0903289318 0.0992846936 0.0816165896 0.1207853556 0.0058902475 0.0090300000 0.0003800000 0.0042210000 0.0000030000 0.0000040000 0.0018740000 39340205 96830484 509673472 3.8768696785 3.8339810371 3.9080090523 1070 1311867206.1227540970 0.0983514264 0.0816322296 0.1207853556 0.0058877584 0.0081330000 0.0003750000 0.0042030000 0.0000010000 0.0000040000 0.0010190000 39343877 96830484 509673472 3.8783519268 3.8327059746 3.9084136486 1071 1311867206.1546130180 0.0988569334 0.0816483124 0.1207853556 0.0058852078 0.0108940000 0.0004700000 0.0041630000 0.0000080000 0.0000080000 0.0014430000 39347549 96830484 509673472 3.8772945404 3.8298888206 3.9080350399 1072 1311867206.1903800964 0.0992899686 0.0816647692 0.1207853556 0.0058864517 0.0091020000 0.0004810000 0.0027300000 0.0000010000 0.0000080000 0.0011740000 39351389 96830484 509673472 3.8761966228 3.8275589943 3.9081273079 1073 1311867206.2239561081 0.0996051654 0.0816814890 0.1207853556 0.0058844638 0.0091460000 0.0004010000 0.0038320000 0.0000050000 0.0000050000 0.0019050000 39355117 96830484 509673472 3.8758504391 3.8268203735 3.9079484940 1074 1311867206.2553579807 0.0995113254 0.0816980904 0.1207853556 0.0058831652 0.0078310000 0.0003800000 0.0038780000 0.0000000000 0.0000030000 0.0010240000 39358733 96830484 509673472 3.8752381802 3.8245551586 3.9075520039 1075 1311867206.2904770374 0.0999927223 0.0817151086 0.1207853556 0.0058804615 0.0084410000 0.0003780000 0.0042140000 0.0000040000 0.0000030000 0.0012920000 39362461 96830484 509673472 3.8737692833 3.8219747543 3.9072363377 1076 1311867206.3222041130 0.1009351388 0.0817329711 0.1207853556 0.0058779677 0.0169710000 0.0005790000 0.0047330000 0.0000010000 0.0000150000 0.0015890000 39366077 96830484 509673472 3.8724188805 3.8216245174 3.9067304134 1077 1311867206.3542530537 0.1014036685 0.0817512355 0.1207853556 0.0058763476 0.0128670000 0.0005870000 0.0032810000 0.0000150000 0.0000160000 0.0025640000 39369805 96830484 509673472 3.8709933758 3.8197765350 3.9063692093 1078 1311867206.3900070190 0.1001880914 0.0817683383 0.1207853556 0.0058758369 0.0076760000 0.0004170000 0.0026080000 0.0000010000 0.0000060000 0.0010730000 39373533 96830484 509673472 3.8719930649 3.8171670437 3.9063401222 1079 1311867206.4220259190 0.1005316451 0.0817857278 0.1207853556 0.0058749416 0.0086630000 0.0003880000 0.0042310000 0.0000040000 0.0000030000 0.0012910000 39377205 96830484 509673472 3.8715908527 3.8164098263 3.9061808586 1080 1311867206.4542310238 0.0994680747 0.0818021004 0.1207853556 0.0058724101 0.0076290000 0.0003830000 0.0035270000 0.0000000000 0.0000040000 0.0010410000 39380933 96830484 509673472 3.8724522591 3.8146080971 3.9061820507 1081 1311867206.4905378819 0.1000379324 0.0818189698 0.1207853556 0.0058778148 0.0161770000 0.0005740000 0.0029370000 0.0000150000 0.0000150000 0.0026270000 39384661 96830484 509673472 3.8708777428 3.8117794991 3.9061152935 1082 1311867206.5250329971 0.1007626206 0.0818364778 0.1207853556 0.0058793026 0.0084790000 0.0004360000 0.0026700000 0.0000010000 0.0000080000 0.0011010000 39388445 96830484 509673472 3.8696143627 3.8093419075 3.9060235023 1083 1311867206.5539300442 0.0992946178 0.0818525979 0.1207853556 0.0058839543 0.0100860000 0.0004720000 0.0031090000 0.0000120000 0.0000100000 0.0014490000 39392061 96830484 509673472 3.8713800907 3.8068675995 3.9059345722 1084 1311867206.5921130180 0.0988116041 0.0818682428 0.1207853556 0.0058832011 0.0071580000 0.0004030000 0.0018980000 0.0000010000 0.0000050000 0.0011020000 39395845 96830484 509673472 3.8721530437 3.8055701256 3.9055457115 1085 1311867206.6226360798 0.1015166938 0.0818863519 0.1207853556 0.0058967674 0.0079900000 0.0004380000 0.0028770000 0.0000040000 0.0000040000 0.0018740000 39399461 96830484 509673472 3.8691773415 3.8035163879 3.9054503441 1086 1311867206.6566751003 0.1001867205 0.0819032031 0.1207853556 0.0058950873 0.0081910000 0.0003770000 0.0042100000 0.0000000000 0.0000030000 0.0010300000 39403189 96830484 509673472 3.8701148033 3.8014855385 3.9052877426 1087 1311867206.6945209503 0.1004237682 0.0819202414 0.1207853556 0.0058928988 0.0100370000 0.0004660000 0.0029900000 0.0000100000 0.0000090000 0.0014630000 39407029 96830484 509673472 3.8700916767 3.8011331558 3.9048600197 1088 1311867206.7248480320 0.0989798680 0.0819359212 0.1207853556 0.0059015713 0.0072730000 0.0004020000 0.0025790000 0.0000010000 0.0000060000 0.0010540000 39410645 96830484 509673472 3.8706619740 3.7978930473 3.9045689106 1089 1311867206.7587969303 0.1017667800 0.0819541313 0.1207853556 0.0059477356 0.0074420000 0.0003800000 0.0025310000 0.0000040000 0.0000040000 0.0019070000 39414429 96830484 509673472 3.8687355518 3.7973768711 3.9041836262 1090 1311867206.7902839184 0.1003303081 0.0819709902 0.1207853556 0.0059659613 0.0065410000 0.0003700000 0.0025060000 0.0000000000 0.0000040000 0.0010350000 39418101 96830484 509673472 3.8689475060 3.7957773209 3.9034664631 1091 1311867206.8229770660 0.1006659195 0.0819881258 0.1207853556 0.0059638694 0.0067750000 0.0003730000 0.0025220000 0.0000040000 0.0000040000 0.0012850000 39421773 96830484 509673472 3.8680675030 3.7940373421 3.9028651714 1092 1311867206.8605449200 0.0999876931 0.0820046089 0.1207853556 0.0059612749 0.0061840000 0.0003750000 0.0021720000 0.0000010000 0.0000030000 0.0010380000 39425557 96830484 509673472 3.8680059910 3.7910046577 3.9022152424 1093 1311867206.8907771111 0.0990296826 0.0820201854 0.1207853556 0.0059597932 0.0091260000 0.0003730000 0.0041710000 0.0000040000 0.0000030000 0.0018970000 39429173 96830484 509673472 3.8692853451 3.7906756401 3.9015336037 1094 1311867206.9225020409 0.1006272808 0.0820371937 0.1207853556 0.0059571897 0.0101350000 0.0004660000 0.0034320000 0.0000010000 0.0000100000 0.0011950000 39432845 96830484 509673472 3.8669748306 3.7884187698 3.9010455608 1095 1311867206.9592480659 0.1012530401 0.0820547424 0.1207853556 0.0059553998 0.0090780000 0.0003960000 0.0042450000 0.0000050000 0.0000050000 0.0013110000 39436685 96830484 509673472 3.8661484718 3.7852616310 3.9005429745 1096 1311867206.9948680401 0.1011963040 0.0820722073 0.1207853556 0.0059658997 0.0068520000 0.0003710000 0.0028410000 0.0000010000 0.0000040000 0.0010510000 39440413 96830484 509673472 3.8663020134 3.7834348679 3.9001352787 1097 1311867207.0247550011 0.1017554477 0.0820901501 0.1207853556 0.0059683226 0.0069490000 0.0003700000 0.0021540000 0.0000030000 0.0000030000 0.0019160000 39444085 96830484 509673472 3.8666512966 3.7823998928 3.8999752998 1098 1311867207.0597259998 0.1020877361 0.0821083629 0.1207853556 0.0059658141 0.0080000000 0.0003760000 0.0038320000 0.0000010000 0.0000040000 0.0010470000 39447869 96830484 509673472 3.8657283783 3.7798936367 3.8997313976 1099 1311867207.0942800045 0.1010746583 0.0821256206 0.1207853556 0.0059708852 0.0067810000 0.0003680000 0.0024960000 0.0000040000 0.0000040000 0.0013260000 39451541 96830484 509673472 3.8668246269 3.7771115303 3.8995413780 1100 1311867207.1229140759 0.0999860689 0.0821418574 0.1207853556 0.0059733461 0.0064850000 0.0003650000 0.0024770000 0.0000000000 0.0000050000 0.0010600000 39455101 96830484 509673472 3.8687789440 3.7766931057 3.8992576599 1101 1311867207.1583549976 0.1024895310 0.0821603385 0.1207853556 0.0059794823 0.0080730000 0.0003690000 0.0031400000 0.0000040000 0.0000040000 0.0019350000 39458885 96830484 509673472 3.8661539555 3.7740459442 3.8993294239 1102 1311867207.1904919147 0.1008876339 0.0821773324 0.1207853556 0.0059791836 0.0082250000 0.0003680000 0.0041290000 0.0000010000 0.0000040000 0.0010640000 39462501 96830484 509673472 3.8675267696 3.7724850178 3.8990008831 1103 1311867207.2226181030 0.1016787887 0.0821950128 0.1207853556 0.0059778118 0.0071340000 0.0003660000 0.0028200000 0.0000030000 0.0000040000 0.0013290000 39466229 96830484 509673472 3.8666517735 3.7714045048 3.8991773129 1104 1311867207.2604830265 0.1009264812 0.0822119797 0.1207853556 0.0059764934 0.0061620000 0.0003690000 0.0021380000 0.0000010000 0.0000040000 0.0010550000 39470069 96830484 509673472 3.8671567440 3.7696931362 3.8992531300 1105 1311867207.2926900387 0.1000227854 0.0822280981 0.1207853556 0.0059768048 0.0090730000 0.0003730000 0.0041350000 0.0000040000 0.0000030000 0.0019420000 39473741 96830484 509673472 3.8674898148 3.7667427063 3.8996152878 1106 1311867207.3235239983 0.1007023081 0.0822448017 0.1207853556 0.0059806716 0.0109910000 0.0004570000 0.0044200000 0.0000010000 0.0000080000 0.0012220000 39477357 96830484 509673472 3.8665437698 3.7651536465 3.9001495838 1107 1311867207.3597478867 0.1006278247 0.0822614079 0.1207853556 0.0059784096 0.0073090000 0.0003980000 0.0022030000 0.0000040000 0.0000050000 0.0013600000 39481197 96830484 509673472 3.8661994934 3.7647874355 3.9006292820 1108 1311867207.3901309967 0.1002754197 0.0822776660 0.1207853556 0.0059793514 0.0095110000 0.0004620000 0.0023490000 0.0000010000 0.0000100000 0.0013540000 39484813 96830484 509673472 3.8656101227 3.7619900703 3.9010977745 1109 1311867207.4227840900 0.1001575515 0.0822937885 0.1207853556 0.0059767540 0.0080470000 0.0003930000 0.0023140000 0.0000050000 0.0000050000 0.0019770000 39488485 96830484 509673472 3.8643920422 3.7608678341 3.9010920525 1110 1311867207.4586789608 0.1002386585 0.0823099551 0.1207853556 0.0059763127 0.0066000000 0.0003710000 0.0024760000 0.0000000000 0.0000030000 0.0010630000 39492269 96830484 509673472 3.8639988899 3.7602841854 3.9017622471 1111 1311867207.4927639961 0.1003206670 0.0823261663 0.1207853556 0.0059743714 0.0067880000 0.0003670000 0.0024780000 0.0000030000 0.0000030000 0.0013160000 39495997 96830484 509673472 3.8623905182 3.7570960522 3.9019417763 1112 1311867207.5237300396 0.1011461392 0.0823430908 0.1207853556 0.0059761040 0.0096790000 0.0004650000 0.0033460000 0.0000010000 0.0000080000 0.0012220000 39499669 96830484 509673472 3.8603346348 3.7542927265 3.9023737907 1113 1311867207.5598409176 0.0997734740 0.0823587515 0.1207853556 0.0059737711 0.0079920000 0.0003930000 0.0025340000 0.0000050000 0.0000040000 0.0019720000 39503397 96830484 509673472 3.8614358902 3.7535626888 3.9027237892 1114 1311867207.5944800377 0.1008543968 0.0823753544 0.1207853556 0.0059732469 0.0068790000 0.0003680000 0.0028150000 0.0000000000 0.0000040000 0.0010590000 39507181 96830484 509673472 3.8591215611 3.7516877651 3.9028809071 1115 1311867207.6259219646 0.0982665643 0.0823896066 0.1207853556 0.0059714447 0.0085590000 0.0003720000 0.0041440000 0.0000040000 0.0000040000 0.0013050000 39510797 96830484 509673472 3.8604762554 3.7477116585 3.9033958912 1116 1311867207.6592938900 0.0981532484 0.0824037317 0.1207853556 0.0059697169 0.0106100000 0.0004670000 0.0043780000 0.0000010000 0.0000080000 0.0012220000 39514581 96830484 509673472 3.8599982262 3.7470693588 3.9033114910 1117 1311867207.6923089027 0.0986306146 0.0824182589 0.1207853556 0.0059683021 0.0095750000 0.0004000000 0.0041880000 0.0000050000 0.0000050000 0.0019700000 39518253 96830484 509673472 3.8590443134 3.7451703548 3.9034917355 1118 1311867207.7238640785 0.0983866230 0.0824325419 0.1207853556 0.0059674548 0.0065760000 0.0003690000 0.0024820000 0.0000000000 0.0000040000 0.0010670000 39521925 96830484 509673472 3.8582177162 3.7416377068 3.9038188457 1119 1311867207.7588050365 0.0989959538 0.0824473439 0.1207853556 0.0059657912 0.0081800000 0.0003670000 0.0038000000 0.0000040000 0.0000040000 0.0013330000 39525541 96830484 509673472 3.8566234112 3.7396111488 3.9036514759 1120 1311867207.7921919823 0.1005692184 0.0824635241 0.1207853556 0.0059635593 0.0066420000 0.0003760000 0.0024750000 0.0000010000 0.0000040000 0.0010740000 39529269 96830484 509673472 3.8542251587 3.7382018566 3.9038960934 1121 1311867207.8237760067 0.0989388749 0.0824782211 0.1207853556 0.0059625131 0.0078280000 0.0003670000 0.0028060000 0.0000030000 0.0000030000 0.0019430000 39532941 96830484 509673472 3.8554632664 3.7353627682 3.9039158821 1122 1311867207.8608479500 0.0983886346 0.0824924015 0.1207853556 0.0059609874 0.0082560000 0.0003690000 0.0041080000 0.0000000000 0.0000040000 0.0010730000 39536725 96830484 509673472 3.8563635349 3.7341690063 3.9042286873 1123 1311867207.8937089443 0.0980188251 0.0825062274 0.1207853556 0.0059584418 0.0109170000 0.0004660000 0.0043620000 0.0000080000 0.0000080000 0.0015030000 39540453 96830484 509673472 3.8568630219 3.7330181599 3.9041485786 1124 1311867207.9244139194 0.0997561067 0.0825215743 0.1207853556 0.0059565998 0.0086750000 0.0003860000 0.0041670000 0.0000000000 0.0000050000 0.0010860000 39544069 96830484 509673472 3.8541126251 3.7305631638 3.9045820236 1125 1311867207.9614970684 0.0971729755 0.0825345977 0.1207853556 0.0059588414 0.0074720000 0.0003560000 0.0024620000 0.0000030000 0.0000030000 0.0019610000 39547741 96830484 509673472 3.8567488194 3.7295699120 3.9046225548 1126 1311867207.9914131165 0.0972275957 0.0825476466 0.1207853556 0.0059732770 0.0098660000 0.0004630000 0.0030340000 0.0000010000 0.0000080000 0.0012340000 39551357 96830484 509673472 3.8571193218 3.7283778191 3.9049961567 1127 1311867208.0248498917 0.0967988968 0.0825602919 0.1207853556 0.0059883498 0.0073420000 0.0003880000 0.0021880000 0.0000050000 0.0000050000 0.0013690000 39555141 96830484 509673472 3.8564586639 3.7246165276 3.9052894115 1128 1311867208.0618500710 0.0981228575 0.0825740885 0.1207853556 0.0059882101 0.0072560000 0.0003640000 0.0031020000 0.0000000000 0.0000040000 0.0010770000 39558757 96830484 509673472 3.8550825119 3.7232279778 3.9055740833 1129 1311867208.0924620628 0.0973182470 0.0825871479 0.1207853556 0.0059858507 0.0091330000 0.0003620000 0.0040830000 0.0000040000 0.0000040000 0.0019630000 39562373 96830484 509673472 3.8563609123 3.7229328156 3.9055063725 1130 1311867208.1276559830 0.0974910036 0.0826003372 0.1207853556 0.0059842952 0.0083160000 0.0003650000 0.0040880000 0.0000000000 0.0000040000 0.0010790000 39566101 96830484 509673472 3.8554551601 3.7205667496 3.9054329395 1131 1311867208.1596069336 0.0960760266 0.0826122520 0.1207853556 0.0059817613 0.0083120000 0.0003600000 0.0038760000 0.0000030000 0.0000040000 0.0013480000 39569773 96830484 509673472 3.8571643829 3.7198600769 3.9052150249 1132 1311867208.1905009747 0.0983692631 0.0826261717 0.1207853556 0.0059798961 0.0079270000 0.0003570000 0.0037660000 0.0000010000 0.0000040000 0.0010840000 39573333 96830484 509673472 3.8541901112 3.7185432911 3.9049127102 1133 1311867208.2280850410 0.0984653980 0.0826401516 0.1207853556 0.0059779665 0.0075850000 0.0003680000 0.0024400000 0.0000030000 0.0000040000 0.0019580000 39577229 96830484 509673472 3.8541452885 3.7171978951 3.9047195911 1134 1311867208.2581789494 0.0977673009 0.0826534912 0.1207853556 0.0059759653 0.0082520000 0.0003570000 0.0040680000 0.0000000000 0.0000040000 0.0010790000 39580845 96830484 509673472 3.8543224335 3.7150297165 3.9044871330 1135 1311867208.2901990414 0.0975330397 0.0826666009 0.1207853556 0.0059735215 0.0084880000 0.0003490000 0.0040640000 0.0000040000 0.0000030000 0.0013470000 39584461 96830484 509673472 3.8545715809 3.7141883373 3.9040517807 1136 1311867208.3270208836 0.0982443243 0.0826803137 0.1207853556 0.0059760008 0.0082340000 0.0003500000 0.0040660000 0.0000000000 0.0000030000 0.0010790000 39588301 96830484 509673472 3.8541200161 3.7131001949 3.9039866924 1137 1311867208.3580970764 0.0985668823 0.0826942861 0.1207853556 0.0059775151 0.0091700000 0.0003500000 0.0040870000 0.0000030000 0.0000030000 0.0019970000 39591973 96830484 509673472 3.8533511162 3.7114486694 3.9039988518 1138 1311867208.3910560608 0.0973910168 0.0827072006 0.1207853556 0.0059757323 0.0062410000 0.0003580000 0.0021060000 0.0000000000 0.0000040000 0.0010880000 39595589 96830484 509673472 3.8547544479 3.7105474472 3.9038624763 1139 1311867208.4260230064 0.0980866179 0.0827207032 0.1207853556 0.0059735297 0.0068600000 0.0003610000 0.0024450000 0.0000030000 0.0000030000 0.0013630000 39599373 96830484 509673472 3.8531756401 3.7080104351 3.9036383629 1140 1311867208.4577419758 0.0983714014 0.0827344318 0.1207853556 0.0059746796 0.0082080000 0.0003580000 0.0040680000 0.0000000000 0.0000030000 0.0010960000 39603045 96830484 509673472 3.8533923626 3.7068696022 3.9037795067 1141 1311867208.4907650948 0.0967789441 0.0827467408 0.1207853556 0.0059736395 0.0091620000 0.0003600000 0.0040570000 0.0000040000 0.0000030000 0.0019960000 39606773 96830484 509673472 3.8551990986 3.7055809498 3.9038097858 1142 1311867208.5257411003 0.0969525576 0.0827591802 0.1207853556 0.0059719590 0.0062490000 0.0003540000 0.0020970000 0.0000010000 0.0000030000 0.0010860000 39610557 96830484 509673472 3.8542993069 3.7042906284 3.9038698673 1143 1311867208.5583798885 0.0989598185 0.0827733540 0.1207853556 0.0059700609 0.0071890000 0.0003560000 0.0027720000 0.0000040000 0.0000030000 0.0013500000 39614229 96830484 509673472 3.8515887260 3.7030997276 3.9045531750 1144 1311867208.5904500484 0.0998585746 0.0827882886 0.1207853556 0.0059687076 0.0098320000 0.0004470000 0.0023170000 0.0000010000 0.0000100000 0.0013600000 39617957 96830484 509673472 3.8507997990 3.7028713226 3.9050908089 1145 1311867208.6259779930 0.0967069492 0.0828004447 0.1207853556 0.0059683657 0.0100130000 0.0004360000 0.0041270000 0.0000050000 0.0000040000 0.0020430000 39621629 96830484 509673472 3.8536746502 3.7012872696 3.9053657055 1146 1311867208.6582078934 0.0969733745 0.0828128120 0.1207853556 0.0059658088 0.0082400000 0.0003590000 0.0040710000 0.0000000000 0.0000030000 0.0010910000 39625357 96830484 509673472 3.8526771069 3.6996431351 3.9060215950 1147 1311867208.6910300255 0.0954087675 0.0828237936 0.1207853556 0.0059687665 0.0082320000 0.0003580000 0.0037250000 0.0000030000 0.0000030000 0.0013590000 39629029 96830484 509673472 3.8532817364 3.6991591454 3.9065818787 1148 1311867208.7262260914 0.0964970440 0.0828357041 0.1207853556 0.0059707606 0.0069640000 0.0003630000 0.0027480000 0.0000000000 0.0000040000 0.0010990000 39632813 96830484 509673472 3.8520696163 3.6979215145 3.9069552422 1149 1311867208.7591009140 0.0981950238 0.0828490717 0.1207853556 0.0059687293 0.0075510000 0.0003610000 0.0024270000 0.0000040000 0.0000040000 0.0020080000 39636485 96830484 509673472 3.8496694565 3.6980335712 3.9074120522 1150 1311867208.7909750938 0.0958777592 0.0828604010 0.1207853556 0.0059682458 0.0071750000 0.0003620000 0.0030910000 0.0000000000 0.0000040000 0.0010970000 39640101 96830484 509673472 3.8514573574 3.6962046623 3.9078731537 1151 1311867208.8259930611 0.0965026245 0.0828722535 0.1207853556 0.0059671379 0.0082870000 0.0003670000 0.0039680000 0.0000030000 0.0000030000 0.0013450000 39643885 96830484 509673472 3.8499677181 3.6935904026 3.9084074497 1152 1311867208.8588190079 0.0978569463 0.0828852610 0.1207853556 0.0059717481 0.0082070000 0.0003630000 0.0040600000 0.0000000000 0.0000030000 0.0010920000 39647613 96830484 509673472 3.8485393524 3.6940875053 3.9086821079 1153 1311867208.8916258812 0.0970857665 0.0828975772 0.1207853556 0.0059833095 0.0090800000 0.0003560000 0.0040600000 0.0000040000 0.0000040000 0.0020010000 39651229 96830484 509673472 3.8478279114 3.6938476562 3.9091820717 1154 1311867208.9275119305 0.0979318991 0.0829106052 0.1207853556 0.0059857371 0.0106890000 0.0004550000 0.0043380000 0.0000010000 0.0000070000 0.0012370000 39654957 96830484 509673472 3.8465721607 3.6909093857 3.9094524384 1155 1311867208.9577760696 0.0981126875 0.0829237671 0.1207853556 0.0059835427 0.0089320000 0.0003850000 0.0041210000 0.0000050000 0.0000050000 0.0013910000 39658573 96830484 509673472 3.8456096649 3.6882359982 3.9094514847 1156 1311867208.9911639690 0.0964073986 0.0829354312 0.1207853556 0.0059809978 0.0068640000 0.0003620000 0.0027590000 0.0000000000 0.0000040000 0.0010960000 39662301 96830484 509673472 3.8479454517 3.6884746552 3.9090266228 1157 1311867209.0270779133 0.0961590409 0.0829468604 0.1207853556 0.0059802431 0.0090870000 0.0003610000 0.0040640000 0.0000040000 0.0000030000 0.0020120000 39666085 96830484 509673472 3.8478391171 3.6857554913 3.9091072083 1158 1311867209.0579569340 0.0977737233 0.0829596643 0.1207853556 0.0059782290 0.0096110000 0.0004500000 0.0032870000 0.0000010000 0.0000080000 0.0012470000 39669701 96830484 509673472 3.8456945419 3.6850178242 3.9082970619 1159 1311867209.0906980038 0.0986667350 0.0829732165 0.1207853556 0.0059766313 0.0081730000 0.0003780000 0.0033300000 0.0000050000 0.0000050000 0.0013860000 39673429 96830484 509673472 3.8446879387 3.6854684353 3.9078211784 1160 1311867209.1260778904 0.0982255787 0.0829863651 0.1207853556 0.0059743941 0.0072580000 0.0003610000 0.0030710000 0.0000000000 0.0000040000 0.0011040000 39677101 96830484 509673472 3.8448002338 3.6845333576 3.9071643353 1161 1311867209.1600620747 0.0992751345 0.0830003951 0.1207853556 0.0059727865 0.0090760000 0.0003550000 0.0040210000 0.0000040000 0.0000040000 0.0020290000 39680885 96830484 509673472 3.8431582451 3.6820757389 3.9069643021 1162 1311867209.1917839050 0.0998343974 0.0830148821 0.1207853556 0.0059710077 0.0081440000 0.0003540000 0.0040070000 0.0000000000 0.0000030000 0.0011090000 39684557 96830484 509673472 3.8429179192 3.6828002930 3.9064860344 1163 1311867209.2259531021 0.0997256041 0.0830292508 0.1207853556 0.0059684892 0.0096090000 0.0004490000 0.0023130000 0.0000100000 0.0000090000 0.0016060000 39688229 96830484 509673472 3.8424794674 3.6813268661 3.9059097767 1164 1311867209.2580060959 0.1003161892 0.0830441021 0.1207853556 0.0059663078 0.0070670000 0.0003800000 0.0021490000 0.0000010000 0.0000060000 0.0011580000 39691957 96830484 509673472 3.8414504528 3.6802613735 3.9056591988 1165 1311867209.2903130054 0.0997046977 0.0830584030 0.1207853556 0.0059640439 0.0076500000 0.0003590000 0.0024380000 0.0000040000 0.0000040000 0.0020420000 39695629 96830484 509673472 3.8419983387 3.6806533337 3.9047760963 1166 1311867209.3274219036 0.0993256345 0.0830723544 0.1207853556 0.0059639783 0.0062710000 0.0003520000 0.0020840000 0.0000010000 0.0000050000 0.0011120000 39699413 96830484 509673472 3.8411805630 3.6774499416 3.9043121338 1167 1311867209.3581039906 0.0998956114 0.0830867702 0.1207853556 0.0059614560 0.0084610000 0.0003490000 0.0040030000 0.0000030000 0.0000030000 0.0013980000 39703029 96830484 509673472 3.8397762775 3.6756381989 3.9036953449 1168 1311867209.3937969208 0.0992273018 0.0831005891 0.1207853556 0.0059600119 0.0081240000 0.0003520000 0.0039110000 0.0000010000 0.0000040000 0.0011270000 39706813 96830484 509673472 3.8404228687 3.6756520271 3.9034404755 1169 1311867209.4258151054 0.0988969877 0.0831141019 0.1207853556 0.0059582470 0.0091820000 0.0003550000 0.0039020000 0.0000040000 0.0000040000 0.0020630000 39710541 96830484 509673472 3.8398189545 3.6738197803 3.9028539658 1170 1311867209.4581329823 0.0981932878 0.0831269901 0.1207853556 0.0059564675 0.0079290000 0.0003500000 0.0036570000 0.0000000000 0.0000040000 0.0011260000 39714157 96830484 509673472 3.8400168419 3.6720461845 3.9027850628 1171 1311867209.4940650463 0.0989006832 0.0831404603 0.1207853556 0.0059560984 0.0083580000 0.0003430000 0.0039890000 0.0000030000 0.0000040000 0.0013860000 39717997 96830484 509673472 3.8392822742 3.6731777191 3.9024436474 1172 1311867209.5258729458 0.0996830836 0.0831545752 0.1207853556 0.0059536348 0.0065750000 0.0003370000 0.0024090000 0.0000010000 0.0000040000 0.0011160000 39721613 96830484 509673472 3.8370935917 3.6714606285 3.9020593166 1173 1311867209.5580699444 0.0992166921 0.0831682684 0.1207853556 0.0059525059 0.0102580000 0.0004490000 0.0026150000 0.0000080000 0.0000080000 0.0022390000 39725285 96830484 509673472 3.8361225128 3.6687018871 3.9019556046 1174 1311867209.5939540863 0.1010748520 0.0831835210 0.1207853556 0.0059510708 0.0077680000 0.0004330000 0.0024590000 0.0000010000 0.0000050000 0.0011480000 39729069 96830484 509673472 3.8329365253 3.6674394608 3.9017772675 1175 1311867209.6262791157 0.1004788503 0.0831982405 0.1207853556 0.0059486832 0.0096790000 0.0004480000 0.0022800000 0.0000100000 0.0000090000 0.0016160000 39732685 96830484 509673472 3.8325924873 3.6658074856 3.9014983177 1176 1311867209.6582019329 0.0992215574 0.0832118657 0.1207853556 0.0059479545 0.0092260000 0.0003730000 0.0040650000 0.0000010000 0.0000050000 0.0011540000 39736301 96830484 509673472 3.8332393169 3.6637411118 3.9013078213 1177 1311867209.6967020035 0.0981137082 0.0832245266 0.1207853556 0.0059524652 0.0081860000 0.0003540000 0.0029220000 0.0000040000 0.0000040000 0.0020780000 39740085 96830484 509673472 3.8337984085 3.6612992287 3.9013655186 1178 1311867209.7262639999 0.0987269953 0.0832376866 0.1207853556 0.0059606621 0.0066570000 0.0003530000 0.0023830000 0.0000010000 0.0000040000 0.0011290000 39743701 96830484 509673472 3.8328080177 3.6608548164 3.9007191658 1179 1311867209.7583460808 0.1006044000 0.0832524166 0.1207853556 0.0059606137 0.0069030000 0.0003380000 0.0023780000 0.0000030000 0.0000030000 0.0013880000 39747429 96830484 509673472 3.8298907280 3.6590409279 3.9002659321 1180 1311867209.7959320545 0.1004976630 0.0832670312 0.1207853556 0.0059582053 0.0063390000 0.0003320000 0.0020600000 0.0000010000 0.0000040000 0.0011230000 39751269 96830484 509673472 3.8295395374 3.6570785046 3.8996598721 1181 1311867209.8262419701 0.0996432900 0.0832808977 0.1207853556 0.0059570005 0.0117280000 0.0004400000 0.0042210000 0.0000070000 0.0000090000 0.0022820000 39754885 96830484 509673472 3.8302221298 3.6559267044 3.8990380764 1182 1311867209.8588960171 0.1009204611 0.0832958212 0.1207853556 0.0059558434 0.0087500000 0.0003600000 0.0040170000 0.0000010000 0.0000060000 0.0011550000 39758557 96830484 509673472 3.8291900158 3.6576411724 3.8982694149 1183 1311867209.8946969509 0.0999017581 0.0833098583 0.1207853556 0.0059547116 0.0085320000 0.0003360000 0.0039850000 0.0000030000 0.0000040000 0.0014060000 39762341 96830484 509673472 3.8301088810 3.6555132866 3.8980453014 1184 1311867209.9268450737 0.1011716798 0.0833249443 0.1207853556 0.0059529487 0.0082290000 0.0003350000 0.0039670000 0.0000000000 0.0000040000 0.0011380000 39765957 96830484 509673472 3.8287608624 3.6552722454 3.8978428841 1185 1311867209.9588210583 0.1028154269 0.0833413920 0.1207853556 0.0059506641 0.0091240000 0.0003530000 0.0038490000 0.0000030000 0.0000030000 0.0020890000 39769685 96830484 509673472 3.8269233704 3.6555683613 3.8974015713 1186 1311867209.9942541122 0.1011284292 0.0833563895 0.1207853556 0.0059514845 0.0064530000 0.0003420000 0.0020670000 0.0000010000 0.0000040000 0.0011380000 39773469 96830484 509673472 3.8286361694 3.6534976959 3.8969657421 1187 1311867210.0261061192 0.1015685946 0.0833717325 0.1207853556 0.0059500478 0.0114590000 0.0004320000 0.0042370000 0.0000080000 0.0000070000 0.0015490000 39777085 96830484 509673472 3.8279156685 3.6522533894 3.8968093395 1188 1311867210.0603590012 0.1009261087 0.0833865089 0.1207853556 0.0059509962 0.0071990000 0.0003600000 0.0021080000 0.0000000000 0.0000050000 0.0011620000 39780925 96830484 509673472 3.8293359280 3.6531600952 3.8963158131 1189 1311867210.0942480564 0.1008427665 0.0834011904 0.1207853556 0.0059518534 0.0120650000 0.0004300000 0.0042480000 0.0000080000 0.0000070000 0.0022960000 39784597 96830484 509673472 3.8293046951 3.6513643265 3.8962635994 1190 1311867210.1280341148 0.0994946733 0.0834147143 0.1207853556 0.0059511171 0.0073580000 0.0003570000 0.0024160000 0.0000000000 0.0000050000 0.0011610000 39788325 96830484 509673472 3.8309228420 3.6488246918 3.8967418671 1191 1311867210.1578240395 0.0996043161 0.0834283076 0.1207853556 0.0059501021 0.0069460000 0.0003350000 0.0023730000 0.0000040000 0.0000040000 0.0014020000 39791941 96830484 509673472 3.8315777779 3.6501262188 3.8966734409 1192 1311867210.1943209171 0.1019423530 0.0834438395 0.1207853556 0.0059506724 0.0072880000 0.0003350000 0.0030080000 0.0000000000 0.0000030000 0.0011380000 39795781 96830484 509673472 3.8286106586 3.6490793228 3.8965606689 1193 1311867210.2258129120 0.1015117243 0.0834589844 0.1207853556 0.0059489231 0.0076440000 0.0003390000 0.0023700000 0.0000040000 0.0000040000 0.0020910000 39799397 96830484 509673472 3.8284733295 3.6472346783 3.8957183361 1194 1311867210.2579770088 0.1009151563 0.0834736043 0.1207853556 0.0059468279 0.0073540000 0.0003390000 0.0030030000 0.0000000000 0.0000030000 0.0011430000 39803069 96830484 509673472 3.8295423985 3.6480803490 3.8950409889 1195 1311867210.2953989506 0.1006118655 0.0834879460 0.1207853556 0.0059444574 0.0066420000 0.0003500000 0.0020490000 0.0000040000 0.0000030000 0.0014070000 39806909 96830484 509673472 3.8298003674 3.6479892731 3.8943998814 1196 1311867210.3271369934 0.1009402722 0.0835025382 0.1207853556 0.0059463925 0.0080710000 0.0003330000 0.0037610000 0.0000010000 0.0000040000 0.0011370000 39810525 96830484 509673472 3.8293340206 3.6478910446 3.8942897320 1197 1311867210.3582420349 0.1002467498 0.0835165267 0.1207853556 0.0059492096 0.0073700000 0.0003350000 0.0020510000 0.0000040000 0.0000030000 0.0020930000 39814197 96830484 509673472 3.8301284313 3.6474981308 3.8939065933 1198 1311867210.3937919140 0.1019882485 0.0835319455 0.1207853556 0.0059470267 0.0083320000 0.0003350000 0.0039480000 0.0000010000 0.0000040000 0.0011400000 39817981 96830484 509673472 3.8278262615 3.6466741562 3.8938758373 1199 1311867210.4260039330 0.1016742811 0.0835470767 0.1207853556 0.0059485466 0.0071420000 0.0003360000 0.0025790000 0.0000040000 0.0000030000 0.0014160000 39821597 96830484 509673472 3.8274376392 3.6459810734 3.8932628632 1200 1311867210.4581708908 0.1005159989 0.0835612175 0.1207853556 0.0059467800 0.0084100000 0.0003330000 0.0039550000 0.0000010000 0.0000040000 0.0011610000 39825325 96830484 509673472 3.8291649818 3.6465706825 3.8931174278 1201 1311867210.4943509102 0.1013665870 0.0835760430 0.1207853556 0.0059622119 0.0115920000 0.0004440000 0.0039130000 0.0000080000 0.0000070000 0.0022980000 39829053 96830484 509673472 3.8284180164 3.6482923031 3.8925175667 1202 1311867210.5261299610 0.1003016680 0.0835899578 0.1207853556 0.0059625345 0.0081220000 0.0003470000 0.0033660000 0.0000000000 0.0000050000 0.0011790000 39832725 96830484 509673472 3.8286914825 3.6464908123 3.8919856548 1203 1311867210.5634729862 0.1021228656 0.0836053634 0.1207853556 0.0059622013 0.0068160000 0.0003380000 0.0020600000 0.0000030000 0.0000030000 0.0015000000 39836565 96830484 509673472 3.8263289928 3.6469659805 3.8915879726 1204 1311867210.5943870544 0.1010069549 0.0836198165 0.1207853556 0.0059603725 0.0105050000 0.0004500000 0.0032700000 0.0000010000 0.0000100000 0.0012860000 39840237 96830484 509673472 3.8278567791 3.6489012241 3.8905968666 1205 1311867210.6260209084 0.0992481336 0.0836327861 0.1207853556 0.0059689518 0.0099180000 0.0003610000 0.0040480000 0.0000050000 0.0000060000 0.0021160000 39843797 96830484 509673472 3.8284010887 3.6447718143 3.8900370598 1206 1311867210.6675710678 0.0985553488 0.0836451597 0.1207853556 0.0059722469 0.0067510000 0.0003350000 0.0023730000 0.0000010000 0.0000040000 0.0011310000 39847805 96830484 509673472 3.8292880058 3.6436614990 3.8897933960 1207 1311867210.6952280998 0.1000000238 0.0836587097 0.1207853556 0.0059758316 0.0066140000 0.0003280000 0.0019500000 0.0000040000 0.0000040000 0.0014060000 39851421 96830484 509673472 3.8286552429 3.6460623741 3.8890910149 1208 1311867210.7260899544 0.0994804800 0.0836718072 0.1207853556 0.0059747280 0.0070850000 0.0003400000 0.0026970000 0.0000010000 0.0000040000 0.0011350000 39854925 96830484 509673472 3.8286354542 3.6447393894 3.8885338306 1209 1311867210.7620921135 0.1000467837 0.0836853514 0.1207853556 0.0059727990 0.0073610000 0.0003300000 0.0020550000 0.0000040000 0.0000040000 0.0020680000 39858765 96830484 509673472 3.8278055191 3.6437785625 3.8884904385 1210 1311867210.7943489552 0.1011327431 0.0836997707 0.1207853556 0.0059781245 0.0082930000 0.0003330000 0.0039570000 0.0000010000 0.0000040000 0.0011350000 39862213 96830484 509673472 3.8275711536 3.6474127769 3.8879208565 1211 1311867210.8263258934 0.1010494381 0.0837140975 0.1207853556 0.0059776437 0.0076740000 0.0003340000 0.0030160000 0.0000040000 0.0000040000 0.0014010000 39865885 96830484 509673472 3.8269653320 3.6457304955 3.8878731728 1212 1311867210.8623979092 0.1013423428 0.0837286422 0.1207853556 0.0059755605 0.0060990000 0.0003340000 0.0017370000 0.0000000000 0.0000040000 0.0011330000 39869669 96830484 509673472 3.8268797398 3.6463181973 3.8879830837 1213 1311867210.8942279816 0.0994986743 0.0837416431 0.1207853556 0.0059736214 0.0092590000 0.0003310000 0.0039660000 0.0000030000 0.0000030000 0.0020930000 39873397 96830484 509673472 3.8293592930 3.6467695236 3.8877334595 1214 1311867210.9288311005 0.0994743779 0.0837546025 0.1207853556 0.0059712212 0.0064850000 0.0003360000 0.0020650000 0.0000000000 0.0000040000 0.0011450000 39877125 96830484 509673472 3.8294870853 3.6463994980 3.8882637024 1215 1311867210.9653480053 0.0986153781 0.0837668336 0.1207853556 0.0059796506 0.0108370000 0.0004480000 0.0041760000 0.0000080000 0.0000070000 0.0014640000 39880909 96830484 509673472 3.8317346573 3.6505432129 3.8882265091 1216 1311867210.9945580959 0.0983014703 0.0837787864 0.1207853556 0.0059885788 0.0098690000 0.0004410000 0.0026190000 0.0000010000 0.0000100000 0.0012850000 39884525 96830484 509673472 3.8306193352 3.6473886967 3.8882174492 1217 1311867211.0263500214 0.0967293084 0.0837894278 0.1207853556 0.0059880227 0.0099420000 0.0003650000 0.0040500000 0.0000050000 0.0000050000 0.0021150000 39888197 96830484 509673472 3.8319461346 3.6460859776 3.8883547783 1218 1311867211.0651569366 0.0980865881 0.0838011660 0.1207853556 0.0059970501 0.0069660000 0.0003430000 0.0026130000 0.0000000000 0.0000040000 0.0011250000 39892037 96830484 509673472 3.8318960667 3.6510200500 3.8880238533 1219 1311867211.0940821171 0.0994412154 0.0838139962 0.1207853556 0.0059985704 0.0072400000 0.0003390000 0.0026090000 0.0000030000 0.0000030000 0.0013900000 39895597 96830484 509673472 3.8290650845 3.6483252048 3.8878898621 1220 1311867211.1266880035 0.0972282887 0.0838249915 0.1207853556 0.0059996700 0.0097350000 0.0004300000 0.0026050000 0.0000010000 0.0000080000 0.0012850000 39899269 96830484 509673472 3.8306317329 3.6454505920 3.8877460957 1221 1311867211.1646990776 0.0982857943 0.0838368349 0.1207853556 0.0059988262 0.0117180000 0.0004320000 0.0042380000 0.0000080000 0.0000080000 0.0022500000 39903165 96830484 509673472 3.8303470612 3.6484794617 3.8872573376 1222 1311867211.1946630478 0.0982172862 0.0838486029 0.1207853556 0.0059964481 0.0114070000 0.0004440000 0.0043070000 0.0000010000 0.0000080000 0.0013010000 39906781 96830484 509673472 3.8305947781 3.6488738060 3.8870365620 1223 1311867211.2270209789 0.0979319215 0.0838601183 0.1207853556 0.0060024617 0.0097720000 0.0004340000 0.0025890000 0.0000090000 0.0000070000 0.0015680000 39910453 96830484 509673472 3.8299114704 3.6465823650 3.8871979713 1224 1311867211.2645599842 0.0964344814 0.0838703915 0.1207853556 0.0060006960 0.0079990000 0.0003640000 0.0030610000 0.0000000000 0.0000050000 0.0011520000 39914293 96830484 509673472 3.8317837715 3.6478707790 3.8866794109 1225 1311867211.2953100204 0.0965713486 0.0838807596 0.1207853556 0.0059984233 0.0118960000 0.0004430000 0.0042490000 0.0000080000 0.0000080000 0.0022890000 39917965 96830484 509673472 3.8324556351 3.6498837471 3.8866848946 1226 1311867211.3262948990 0.0990418717 0.0838931259 0.1207853556 0.0059966787 0.0087670000 0.0003510000 0.0040330000 0.0000010000 0.0000050000 0.0011390000 39921581 96830484 509673472 3.8290450573 3.6490123272 3.8866891861 1227 1311867211.3653290272 0.0984124243 0.0839049591 0.1207853556 0.0059943766 0.0066050000 0.0003420000 0.0019610000 0.0000040000 0.0000030000 0.0013990000 39925477 96830484 509673472 3.8297207355 3.6490595341 3.8868668079 1228 1311867211.3949019909 0.0983174741 0.0839166957 0.1207853556 0.0059928416 0.0067970000 0.0003440000 0.0023850000 0.0000010000 0.0000040000 0.0011380000 39929093 96830484 509673472 3.8304126263 3.6514143944 3.8867309093 1229 1311867211.4295680523 0.0984541103 0.0839285243 0.1207853556 0.0059982769 0.0092980000 0.0003430000 0.0039860000 0.0000040000 0.0000030000 0.0020630000 39932765 96830484 509673472 3.8304855824 3.6526315212 3.8869562149 1230 1311867211.4645059109 0.0991519988 0.0839409011 0.1207853556 0.0059971100 0.0064470000 0.0003420000 0.0020580000 0.0000010000 0.0000040000 0.0011370000 39936493 96830484 509673472 3.8287348747 3.6511344910 3.8870513439 1231 1311867211.4942829609 0.1000499502 0.0839539873 0.1207853556 0.0059954352 0.0076050000 0.0003510000 0.0022490000 0.0000050000 0.0000040000 0.0016670000 39940109 96830484 509673472 3.8281538486 3.6528322697 3.8871212006 1232 1311867211.5279569626 0.0987030715 0.0839659589 0.1207853556 0.0059957138 0.0084280000 0.0003980000 0.0039790000 0.0000010000 0.0000040000 0.0011310000 39943781 96830484 509673472 3.8294870853 3.6537656784 3.8872992992 1233 1311867211.5646700859 0.0983226299 0.0839776026 0.1207853556 0.0059953605 0.0092810000 0.0003400000 0.0039840000 0.0000030000 0.0000030000 0.0020500000 39947621 96830484 509673472 3.8307776451 3.6534504890 3.8875129223 1234 1311867211.5967590809 0.0994774178 0.0839901633 0.1207853556 0.0059958645 0.0081270000 0.0003500000 0.0037870000 0.0000010000 0.0000040000 0.0011170000 39951293 96830484 509673472 3.8293607235 3.6536529064 3.8878912926 1235 1311867211.6269431114 0.0994376838 0.0840026714 0.1207853556 0.0059994587 0.0066850000 0.0003520000 0.0020720000 0.0000040000 0.0000040000 0.0013960000 39954909 96830484 509673472 3.8300223351 3.6548213959 3.8881769180 1236 1311867211.6620280743 0.0991654992 0.0840149390 0.1207853556 0.0060069303 0.0087800000 0.0004470000 0.0018030000 0.0000010000 0.0000090000 0.0012750000 39958693 96830484 509673472 3.8300285339 3.6559112072 3.8879883289 1237 1311867211.6944348812 0.0999431834 0.0840278155 0.1207853556 0.0060092252 0.0098670000 0.0003670000 0.0040500000 0.0000040000 0.0000040000 0.0020970000 39962365 96830484 509673472 3.8284010887 3.6536989212 3.8878498077 1238 1311867211.7267570496 0.1000855714 0.0840407863 0.1207853556 0.0060091947 0.0067640000 0.0003450000 0.0023940000 0.0000000000 0.0000040000 0.0011300000 39965981 96830484 509673472 3.8291707039 3.6568934917 3.8875341415 1239 1311867211.7642099857 0.1000705510 0.0840537239 0.1207853556 0.0060072671 0.0085760000 0.0003410000 0.0039950000 0.0000030000 0.0000030000 0.0013900000 39969877 96830484 509673472 3.8292214870 3.6557919979 3.8873240948 1240 1311867211.7948160172 0.1000540182 0.0840666274 0.1207853556 0.0060053331 0.0068530000 0.0003480000 0.0023930000 0.0000000000 0.0000040000 0.0011290000 39973381 96830484 509673472 3.8296813965 3.6568059921 3.8867552280 1241 1311867211.8337268829 0.0998511314 0.0840793466 0.1207853556 0.0060033059 0.0077090000 0.0003400000 0.0023820000 0.0000040000 0.0000040000 0.0020630000 39977221 96830484 509673472 3.8300938606 3.6565008163 3.8863844872 1242 1311867211.8630928993 0.1003687829 0.0840924621 0.1207853556 0.0060018453 0.0110200000 0.0004310000 0.0042640000 0.0000010000 0.0000080000 0.0012800000 39980837 96830484 509673472 3.8303296566 3.6584498882 3.8862912655 1243 1311867211.8967690468 0.0995382145 0.0841048882 0.1207853556 0.0059994460 0.0091170000 0.0003800000 0.0040330000 0.0000050000 0.0000050000 0.0014220000 39984509 96830484 509673472 3.8314459324 3.6600127220 3.8857383728 1244 1311867211.9324300289 0.1012254879 0.0841186508 0.1207853556 0.0059988672 0.0094620000 0.0004290000 0.0025740000 0.0000010000 0.0000080000 0.0012680000 39988293 96830484 509673472 3.8290696144 3.6594824791 3.8852515221 1245 1311867211.9653239250 0.0998705402 0.0841313029 0.1207853556 0.0059972190 0.0089290000 0.0003660000 0.0030650000 0.0000050000 0.0000050000 0.0020920000 39992021 96830484 509673472 3.8312783241 3.6604745388 3.8849747181 1246 1311867211.9972860813 0.1005370766 0.0841444697 0.1207853556 0.0059951324 0.0064720000 0.0003410000 0.0020670000 0.0000010000 0.0000040000 0.0011230000 39995637 96830484 509673472 3.8313801289 3.6631700993 3.8843915462 1247 1311867212.0317659378 0.0999456570 0.0841571410 0.1207853556 0.0059929349 0.0073560000 0.0003400000 0.0027010000 0.0000040000 0.0000040000 0.0013940000 39999421 96830484 509673472 3.8325357437 3.6643428802 3.8840262890 1248 1311867212.0621519089 0.1003905088 0.0841701485 0.1207853556 0.0059905658 0.0082270000 0.0003340000 0.0037610000 0.0000000000 0.0000040000 0.0011310000 40003037 96830484 509673472 3.8318674564 3.6643557549 3.8837583065 1249 1311867212.0954549313 0.1003486067 0.0841831017 0.1207853556 0.0059910309 0.0093120000 0.0003390000 0.0039810000 0.0000030000 0.0000030000 0.0020570000 40006709 96830484 509673472 3.8330070972 3.6676831245 3.8835549355 1250 1311867212.1331028938 0.1014253944 0.0841968955 0.1207853556 0.0059920010 0.0083420000 0.0003390000 0.0039710000 0.0000010000 0.0000040000 0.0011150000 40010549 96830484 509673472 3.8316059113 3.6686496735 3.8830716610 1251 1311867212.1668488979 0.1021329984 0.0842112329 0.1207853556 0.0059904802 0.0086090000 0.0003400000 0.0039730000 0.0000030000 0.0000030000 0.0013920000 40014221 96830484 509673472 3.8300554752 3.6673445702 3.8828246593 1252 1311867212.1945068836 0.1007159352 0.0842244156 0.1207853556 0.0059899860 0.0074300000 0.0003380000 0.0030120000 0.0000000000 0.0000050000 0.0011230000 40017781 96830484 509673472 3.8327345848 3.6694581509 3.8826029301 1253 1311867212.2301759720 0.1017864794 0.0842384316 0.1207853556 0.0059928289 0.0088380000 0.0003440000 0.0035560000 0.0000040000 0.0000040000 0.0020410000 40021509 96830484 509673472 3.8321869373 3.6718633175 3.8817141056 1254 1311867212.2647190094 0.1007188559 0.0842515739 0.1207853556 0.0059946753 0.0074920000 0.0003370000 0.0030200000 0.0000000000 0.0000040000 0.0011220000 40025293 96830484 509673472 3.8332123756 3.6706452370 3.8810813427 1255 1311867212.2944819927 0.1025131121 0.0842661249 0.1207853556 0.0059925855 0.0066910000 0.0003420000 0.0020600000 0.0000030000 0.0000030000 0.0013990000 40028909 96830484 509673472 3.8316671848 3.6727137566 3.8801352978 1256 1311867212.3326430321 0.1024698913 0.0842806183 0.1207853556 0.0059914091 0.0083940000 0.0003370000 0.0039630000 0.0000010000 0.0000040000 0.0011250000 40032749 96830484 509673472 3.8323495388 3.6750245094 3.8794302940 1257 1311867212.3653640747 0.1013227105 0.0842941761 0.1207853556 0.0059894438 0.0102380000 0.0004340000 0.0025770000 0.0000080000 0.0000070000 0.0022540000 40036421 96830484 509673472 3.8345146179 3.6784379482 3.8782804012 1258 1311867212.3955509663 0.1029100046 0.0843089740 0.1207853556 0.0060019675 0.0068140000 0.0003660000 0.0017800000 0.0000000000 0.0000050000 0.0011510000 40040037 96830484 509673472 3.8327918053 3.6783237457 3.8778414726 1259 1311867212.4329519272 0.1016556025 0.0843227521 0.1207853556 0.0060192052 0.0086380000 0.0003400000 0.0039720000 0.0000040000 0.0000040000 0.0013950000 40043877 96830484 509673472 3.8345007896 3.6801776886 3.8773875237 1260 1311867212.4622640610 0.1031839699 0.0843377214 0.1207853556 0.0060280604 0.0074160000 0.0003360000 0.0030220000 0.0000010000 0.0000040000 0.0011170000 40047493 96830484 509673472 3.8336253166 3.6827042103 3.8770370483 1261 1311867212.4944300652 0.1033162251 0.0843527717 0.1207853556 0.0060313494 0.0103020000 0.0003540000 0.0041510000 0.0000050000 0.0000040000 0.0023740000 40051165 96830484 509673472 3.8337113857 3.6829967499 3.8765223026 1262 1311867212.5300269127 0.1029170230 0.0843674819 0.1207853556 0.0060299851 0.0084550000 0.0003460000 0.0039600000 0.0000000000 0.0000040000 0.0011250000 40054949 96830484 509673472 3.8344595432 3.6830246449 3.8757977486 1263 1311867212.5625970364 0.1025119871 0.0843818481 0.1207853556 0.0060373634 0.0070530000 0.0003400000 0.0023780000 0.0000030000 0.0000030000 0.0013860000 40058621 96830484 509673472 3.8362545967 3.6848013401 3.8749630451 1264 1311867212.5948359966 0.1022223234 0.0843959624 0.1207853556 0.0060361351 0.0080690000 0.0003360000 0.0036360000 0.0000010000 0.0000040000 0.0011210000 40062293 96830484 509673472 3.8370707035 3.6853094101 3.8738846779 1265 1311867212.6323919296 0.1005521715 0.0844087341 0.1207853556 0.0060353631 0.0077140000 0.0003390000 0.0023790000 0.0000040000 0.0000030000 0.0020520000 40066021 96830484 509673472 3.8397483826 3.6852843761 3.8730919361 1266 1311867212.6629829407 0.1010502800 0.0844218791 0.1207853556 0.0060385829 0.0098990000 0.0004280000 0.0029180000 0.0000010000 0.0000080000 0.0012750000 40069637 96830484 509673472 3.8401515484 3.6874749660 3.8722066879 1267 1311867212.6944150925 0.1003798917 0.0844344742 0.1207853556 0.0060364681 0.0083930000 0.0003640000 0.0030610000 0.0000050000 0.0000050000 0.0014140000 40073365 96830484 509673472 3.8419911861 3.6890153885 3.8714206219 1268 1311867212.7323219776 0.1017494574 0.0844481296 0.1207853556 0.0060356718 0.0084350000 0.0003400000 0.0039670000 0.0000000000 0.0000030000 0.0011280000 40077149 96830484 509673472 3.8409273624 3.6897633076 3.8706343174 1269 1311867212.7618949413 0.1018186361 0.0844618179 0.1207853556 0.0060347720 0.0071180000 0.0003430000 0.0017300000 0.0000040000 0.0000030000 0.0020720000 40080709 96830484 509673472 3.8407788277 3.6900386810 3.8698463440 1270 1311867212.7951610088 0.1023975015 0.0844759405 0.1207853556 0.0060331445 0.0064950000 0.0003360000 0.0020470000 0.0000000000 0.0000040000 0.0011220000 40084437 96830484 509673472 3.8412582874 3.6937000751 3.8690481186 1271 1311867212.8303771019 0.1018340066 0.0844895975 0.1207853556 0.0060310151 0.0086680000 0.0003340000 0.0039490000 0.0000040000 0.0000040000 0.0013890000 40088277 96830484 509673472 3.8420534134 3.6932601929 3.8684523106 1272 1311867212.8625240326 0.1029930264 0.0845041442 0.1207853556 0.0060311391 0.0082210000 0.0003320000 0.0036320000 0.0000000000 0.0000040000 0.0011270000 40091893 96830484 509673472 3.8405969143 3.6926610470 3.8674850464 1273 1311867212.8941800594 0.1033715829 0.0845189655 0.1207853556 0.0060388165 0.0094630000 0.0003390000 0.0039520000 0.0000040000 0.0000030000 0.0020810000 40095565 96830484 509673472 3.8409810066 3.6954438686 3.8665349483 1274 1311867212.9306590557 0.1010522544 0.0845319429 0.1207853556 0.0060478732 0.0069320000 0.0003320000 0.0023620000 0.0000000000 0.0000030000 0.0011450000 40099349 96830484 509673472 3.8441026211 3.6980729103 3.8657193184 1275 1311867212.9621579647 0.1022278816 0.0845458221 0.1207853556 0.0060635138 0.0071530000 0.0003330000 0.0023600000 0.0000030000 0.0000030000 0.0014070000 40103021 96830484 509673472 3.8433208466 3.6983563900 3.8648419380 1276 1311867212.9971981049 0.1019921675 0.0845594948 0.1207853556 0.0060655500 0.0084660000 0.0003260000 0.0039420000 0.0000010000 0.0000040000 0.0011360000 40106749 96830484 509673472 3.8454310894 3.7018823624 3.8640260696 1277 1311867213.0305559635 0.1023247689 0.0845734065 0.1207853556 0.0060673717 0.0115640000 0.0004360000 0.0032380000 0.0000100000 0.0000110000 0.0022720000 40110533 96830484 509673472 3.8448250294 3.7014627457 3.8637292385 1278 1311867213.0622329712 0.1022533178 0.0845872406 0.1207853556 0.0060663190 0.0090490000 0.0003560000 0.0040030000 0.0000010000 0.0000050000 0.0011470000 40114149 96830484 509673472 3.8453674316 3.7017555237 3.8634274006 1279 1311867213.0985310078 0.1016392037 0.0846005728 0.1207853556 0.0060644088 0.0100070000 0.0004290000 0.0025540000 0.0000080000 0.0000070000 0.0015450000 40117933 96830484 509673472 3.8468799591 3.7039175034 3.8624954224 1280 1311867213.1321671009 0.1010498703 0.0846134238 0.1207853556 0.0060620639 0.0070460000 0.0003630000 0.0017560000 0.0000000000 0.0000050000 0.0011430000 40121661 96830484 509673472 3.8487000465 3.7051248550 3.8619065285 1281 1311867213.1642329693 0.1021016836 0.0846270759 0.1207853556 0.0060602102 0.0085490000 0.0003380000 0.0030040000 0.0000050000 0.0000030000 0.0020810000 40125333 96830484 509673472 3.8483762741 3.7062227726 3.8614053726 1282 1311867213.1981649399 0.1011741385 0.0846399831 0.1207853556 0.0060618401 0.0062720000 0.0003350000 0.0017370000 0.0000000000 0.0000050000 0.0011230000 40129061 96830484 509673472 3.8497188091 3.7063961029 3.8603732586 1283 1311867213.2303979397 0.1033770591 0.0846545872 0.1207853556 0.0060606467 0.0087130000 0.0003290000 0.0038410000 0.0000040000 0.0000030000 0.0013820000 40132733 96830484 509673472 3.8483216763 3.7078561783 3.8601307869 1284 1311867213.2621340752 0.1038208306 0.0846695142 0.1207853556 0.0060586656 0.0116070000 0.0004550000 0.0042380000 0.0000010000 0.0000090000 0.0012730000 40136405 96830484 509673472 3.8489005566 3.7103490829 3.8588967323 1285 1311867213.2983639240 0.1026510447 0.0846835076 0.1207853556 0.0060582399 0.0100400000 0.0003600000 0.0040060000 0.0000050000 0.0000050000 0.0021090000 40140189 96830484 509673472 3.8503508568 3.7093839645 3.8582932949 1286 1311867213.3312969208 0.1044112965 0.0846988480 0.1207853556 0.0060605678 0.0084910000 0.0003340000 0.0039560000 0.0000000000 0.0000040000 0.0011230000 40143917 96830484 509673472 3.8497581482 3.7138428688 3.8578498363 1287 1311867213.3622069359 0.1040802225 0.0847139074 0.1207853556 0.0060588801 0.0066710000 0.0003370000 0.0017230000 0.0000040000 0.0000030000 0.0014010000 40147533 96830484 509673472 3.8502316475 3.7150971889 3.8569273949 1288 1311867213.3980619907 0.1051637456 0.0847297846 0.1207853556 0.0060568586 0.0065860000 0.0003330000 0.0020450000 0.0000010000 0.0000040000 0.0011310000 40151317 96830484 509673472 3.8499143124 3.7167105675 3.8568804264 1289 1311867213.4303960800 0.1045269221 0.0847451431 0.1207853556 0.0060552645 0.0095970000 0.0003340000 0.0039400000 0.0000040000 0.0000030000 0.0020800000 40155045 96830484 509673472 3.8516080379 3.7185602188 3.8566281796 1290 1311867213.4620630741 0.1054019108 0.0847611561 0.1207853556 0.0060535620 0.0066950000 0.0003370000 0.0020360000 0.0000010000 0.0000040000 0.0011600000 40158661 96830484 509673472 3.8514134884 3.7210493088 3.8562405109 1291 1311867213.4981389046 0.1047052443 0.0847766046 0.1207853556 0.0060560944 0.0088460000 0.0003360000 0.0039340000 0.0000040000 0.0000040000 0.0013780000 40162445 96830484 509673472 3.8523883820 3.7226977348 3.8558743000 1292 1311867213.5318338871 0.1042920426 0.0847917095 0.1207853556 0.0060554661 0.0086160000 0.0003420000 0.0039390000 0.0000010000 0.0000040000 0.0011210000 40166173 96830484 509673472 3.8532419205 3.7252905369 3.8555364609 1293 1311867213.5621318817 0.1025732681 0.0848054616 0.1207853556 0.0060534939 0.0086200000 0.0003360000 0.0030030000 0.0000030000 0.0000030000 0.0020680000 40169789 96830484 509673472 3.8559908867 3.7275338173 3.8555462360 1294 1311867213.5989580154 0.1019110978 0.0848186808 0.1207853556 0.0060548631 0.0086800000 0.0003350000 0.0039510000 0.0000010000 0.0000040000 0.0011170000 40173629 96830484 509673472 3.8567070961 3.7283151150 3.8554975986 1295 1311867213.6327760220 0.1015038863 0.0848315652 0.1207853556 0.0060531332 0.0076600000 0.0003390000 0.0026980000 0.0000040000 0.0000030000 0.0013900000 40177301 96830484 509673472 3.8576581478 3.7299890518 3.8555004597 1296 1311867213.6623249054 0.1032784656 0.0848457989 0.1207853556 0.0060540186 0.0069480000 0.0003400000 0.0023730000 0.0000000000 0.0000030000 0.0011200000 40180837 96830484 509673472 3.8568456173 3.7331910133 3.8555686474 1297 1311867213.6987268925 0.1022886485 0.0848592475 0.1207853556 0.0060521369 0.0094090000 0.0003340000 0.0039810000 0.0000030000 0.0000040000 0.0020520000 40184621 96830484 509673472 3.8593046665 3.7356569767 3.8558235168 1298 1311867213.7312800884 0.1026167721 0.0848729282 0.1207853556 0.0060567194 0.0083950000 0.0003400000 0.0038790000 0.0000010000 0.0000040000 0.0011120000 40188349 96830484 509673472 3.8598983288 3.7371947765 3.8562040329 1299 1311867213.7623159885 0.1017313972 0.0848859062 0.1207853556 0.0060658130 0.0068650000 0.0003380000 0.0020600000 0.0000040000 0.0000030000 0.0013670000 40191965 96830484 509673472 3.8612749577 3.7384157181 3.8564491272 1300 1311867213.7984969616 0.1023884341 0.0848993697 0.1207853556 0.0060640600 0.0072330000 0.0003420000 0.0027150000 0.0000010000 0.0000040000 0.0011030000 40195637 96830484 509673472 3.8615548611 3.7406919003 3.8568463326 1301 1311867213.8303530216 0.1017239615 0.0849123017 0.1207853556 0.0060619403 0.0094340000 0.0003370000 0.0039910000 0.0000030000 0.0000040000 0.0020390000 40199309 96830484 509673472 3.8633642197 3.7419245243 3.8575553894 1302 1311867213.8669381142 0.1012955084 0.0849248849 0.1207853556 0.0060646221 0.0110030000 0.0004340000 0.0042440000 0.0000010000 0.0000080000 0.0012330000 40203093 96830484 509673472 3.8638389111 3.7408092022 3.8578128815 1303 1311867213.8988749981 0.1028940305 0.0849386755 0.1207853556 0.0060625256 0.0092750000 0.0003770000 0.0040410000 0.0000050000 0.0000060000 0.0013810000 40206845 96830484 509673472 3.8631074429 3.7429580688 3.8579607010 1304 1311867213.9324591160 0.1035435945 0.0849529430 0.1207853556 0.0060623632 0.0065750000 0.0003440000 0.0020850000 0.0000010000 0.0000040000 0.0010990000 40210517 96830484 509673472 3.8638741970 3.7472095490 3.8578906059 1305 1311867213.9625511169 0.1042817608 0.0849677544 0.1207853556 0.0060610336 0.0109860000 0.0004390000 0.0026060000 0.0000120000 0.0000100000 0.0022610000 40214133 96830484 509673472 3.8627939224 3.7463691235 3.8575642109 1306 1311867214.0014989376 0.1040811539 0.0849823895 0.1207853556 0.0060594926 0.0080800000 0.0003660000 0.0027530000 0.0000000000 0.0000050000 0.0011140000 40218085 96830484 509673472 3.8639416695 3.7479033470 3.8570055962 1307 1311867214.0316550732 0.1036866233 0.0849967003 0.1207853556 0.0060600547 0.0078730000 0.0003430000 0.0030320000 0.0000040000 0.0000030000 0.0013780000 40221645 96830484 509673472 3.8648908138 3.7504615784 3.8564686775 1308 1311867214.0640029907 0.1031397879 0.0850105711 0.1207853556 0.0060586287 0.0110240000 0.0004400000 0.0042460000 0.0000000000 0.0000090000 0.0012350000 40225373 96830484 509673472 3.8665819168 3.7521269321 3.8564708233 1309 1311867214.0984749794 0.1047762483 0.0850256710 0.1207853556 0.0060564898 0.0099300000 0.0003580000 0.0040510000 0.0000050000 0.0000040000 0.0020320000 40229101 96830484 509673472 3.8656136990 3.7545826435 3.8560702801 1310 1311867214.1326990128 0.1048890427 0.0850408338 0.1207853556 0.0060554706 0.0085560000 0.0003590000 0.0040150000 0.0000000000 0.0000030000 0.0010900000 40232773 96830484 509673472 3.8662192822 3.7561113834 3.8560581207 1311 1311867214.1643800735 0.1053472161 0.0850563231 0.1207853556 0.0060552981 0.0065470000 0.0003420000 0.0017460000 0.0000030000 0.0000040000 0.0013370000 40236501 96830484 509673472 3.8662378788 3.7578766346 3.8560683727 1312 1311867214.2013020515 0.1053165793 0.0850717653 0.1207853556 0.0060535160 0.0066300000 0.0003470000 0.0020860000 0.0000000000 0.0000040000 0.0010920000 40240229 96830484 509673472 3.8663647175 3.7581355572 3.8561129570 1313 1311867214.2338430882 0.1057900712 0.0850875447 0.1207853556 0.0060513601 0.0095210000 0.0003400000 0.0040190000 0.0000040000 0.0000030000 0.0019940000 40243957 96830484 509673472 3.8661129475 3.7595121861 3.8559954166 1314 1311867214.2674899101 0.1051469818 0.0851028106 0.1207853556 0.0060494493 0.0115740000 0.0004340000 0.0042830000 0.0000010000 0.0000080000 0.0012300000 40247685 96830484 509673472 3.8673877716 3.7613399029 3.8558771610 1315 1311867214.3004720211 0.1058109030 0.0851185582 0.1207853556 0.0060474153 0.0113560000 0.0004380000 0.0042730000 0.0000070000 0.0000080000 0.0014850000 40251357 96830484 509673472 3.8669328690 3.7635474205 3.8558115959 1316 1311867214.3310549259 0.1045039296 0.0851332888 0.1207853556 0.0060456053 0.0090150000 0.0003600000 0.0040410000 0.0000000000 0.0000050000 0.0011010000 40254973 96830484 509673472 3.8683569431 3.7642080784 3.8553690910 1317 1311867214.3663671017 0.1049078405 0.0851483036 0.1207853556 0.0060449726 0.0082690000 0.0003430000 0.0027300000 0.0000030000 0.0000030000 0.0020070000 40258757 96830484 509673472 3.8687179089 3.7662417889 3.8553195000 1318 1311867214.3980031013 0.1045424566 0.0851630184 0.1207853556 0.0060430072 0.0085650000 0.0003450000 0.0039920000 0.0000010000 0.0000040000 0.0010930000 40262429 96830484 509673472 3.8691587448 3.7659711838 3.8548521996 1319 1311867214.4332211018 0.1045392752 0.0851777085 0.1207853556 0.0060417361 0.0121510000 0.0004410000 0.0040590000 0.0000080000 0.0000070000 0.0014660000 40266157 96830484 509673472 3.8693659306 3.7668294907 3.8542306423 1320 1311867214.4698181152 0.1051489115 0.0851928382 0.1207853556 0.0060439180 0.0093040000 0.0004070000 0.0041780000 0.0000010000 0.0000050000 0.0010900000 40270109 96830484 509673472 3.8689348698 3.7681438923 3.8534915447 1321 1311867214.5059390068 0.1057921350 0.0852084320 0.1207853556 0.0060451265 0.0082690000 0.0003440000 0.0027230000 0.0000040000 0.0000030000 0.0019960000 40273893 96830484 509673472 3.8694655895 3.7706882954 3.8532228470 1322 1311867214.5373690128 0.1054285616 0.0852237271 0.1207853556 0.0060443079 0.0079330000 0.0003470000 0.0033570000 0.0000000000 0.0000030000 0.0010760000 40277565 96830484 509673472 3.8708026409 3.7725243568 3.8530395031 1323 1311867214.5691421032 0.1054783687 0.0852390367 0.1207853556 0.0060429955 0.0075680000 0.0003430000 0.0027290000 0.0000040000 0.0000040000 0.0013480000 40281237 96830484 509673472 3.8715620041 3.7752134800 3.8528349400 1324 1311867214.6048638821 0.1046956405 0.0852537320 0.1207853556 0.0060408104 0.0085610000 0.0003450000 0.0040140000 0.0000000000 0.0000040000 0.0010690000 40285021 96830484 509673472 3.8728375435 3.7762191296 3.8526027203 1325 1311867214.6369891167 0.1055702567 0.0852690652 0.1207853556 0.0060399392 0.0112450000 0.0004770000 0.0032620000 0.0000080000 0.0000070000 0.0021790000 40288637 96830484 509673472 3.8718781471 3.7763428688 3.8526165485 1326 1311867214.6691009998 0.1056810021 0.0852844589 0.1207853556 0.0060381493 0.0076190000 0.0003660000 0.0024410000 0.0000000000 0.0000050000 0.0011090000 40292365 96830484 509673472 3.8729240894 3.7791643143 3.8524236679 1327 1311867214.7048900127 0.1066519693 0.0853005610 0.1207853556 0.0060367928 0.0086770000 0.0003470000 0.0038280000 0.0000040000 0.0000040000 0.0013290000 40296093 96830484 509673472 3.8726222515 3.7789092064 3.8524756432 1328 1311867214.7369639874 0.1056275219 0.0853158674 0.1207853556 0.0060411402 0.0086100000 0.0003430000 0.0040120000 0.0000000000 0.0000040000 0.0010780000 40299765 96830484 509673472 3.8744266033 3.7810406685 3.8522317410 1329 1311867214.7695059776 0.1060569510 0.0853314740 0.1207853556 0.0060428074 0.0082740000 0.0003430000 0.0027290000 0.0000040000 0.0000040000 0.0019940000 40303493 96830484 509673472 3.8745977879 3.7830803394 3.8518736362 1330 1311867214.8049929142 0.1061482355 0.0853471257 0.1207853556 0.0060417938 0.0076380000 0.0003460000 0.0030490000 0.0000000000 0.0000030000 0.0010760000 40307277 96830484 509673472 3.8748199940 3.7839770317 3.8511903286 1331 1311867214.8369181156 0.1051911488 0.0853620348 0.1207853556 0.0060428027 0.0088650000 0.0003430000 0.0040160000 0.0000040000 0.0000030000 0.0013500000 40310893 96830484 509673472 3.8756358624 3.7837240696 3.8506839275 1332 1311867214.8699979782 0.1061948612 0.0853776750 0.1207853556 0.0060416589 0.0067500000 0.0003510000 0.0020890000 0.0000000000 0.0000040000 0.0010800000 40314621 96830484 509673472 3.8755259514 3.7865869999 3.8505556583 1333 1311867214.9049839973 0.1066250056 0.0853936145 0.1207853556 0.0060404964 0.0096440000 0.0003480000 0.0040480000 0.0000040000 0.0000040000 0.0019850000 40318405 96830484 509673472 3.8755161762 3.7890191078 3.8502337933 1334 1311867214.9372529984 0.1054401174 0.0854086419 0.1207853556 0.0060420206 0.0086410000 0.0003490000 0.0040270000 0.0000010000 0.0000040000 0.0010770000 40322077 96830484 509673472 3.8768515587 3.7886247635 3.8497781754 1335 1311867214.9693040848 0.1058763042 0.0854239735 0.1207853556 0.0060410099 0.0075800000 0.0003420000 0.0027460000 0.0000040000 0.0000030000 0.0013370000 40325749 96830484 509673472 3.8770289421 3.7914597988 3.8495805264 1336 1311867215.0050640106 0.1064023003 0.0854396758 0.1207853556 0.0060393682 0.0073100000 0.0003500000 0.0027420000 0.0000000000 0.0000030000 0.0010640000 40329589 96830484 509673472 3.8774268627 3.7955267429 3.8496105671 1337 1311867215.0371069908 0.1060150266 0.0854550650 0.1207853556 0.0060390995 0.0095680000 0.0003530000 0.0040400000 0.0000040000 0.0000040000 0.0019750000 40333149 96830484 509673472 3.8771309853 3.7950804234 3.8492326736 1338 1311867215.0692911148 0.1060492545 0.0854704568 0.1207853556 0.0060377754 0.0086660000 0.0003480000 0.0040500000 0.0000010000 0.0000040000 0.0010740000 40336877 96830484 509673472 3.8779799938 3.7984750271 3.8494963646 1339 1311867215.1050040722 0.1048383340 0.0854849212 0.1207853556 0.0060368436 0.0113130000 0.0004540000 0.0039660000 0.0000090000 0.0000170000 0.0014560000 40340661 96830484 509673472 3.8797988892 3.8011929989 3.8496255875 1340 1311867215.1369140148 0.1053104997 0.0854997164 0.1207853556 0.0060347826 0.0091280000 0.0003740000 0.0041150000 0.0000000000 0.0000050000 0.0010940000 40344277 96830484 509673472 3.8790175915 3.8013894558 3.8504664898 1341 1311867215.1694459915 0.1039973348 0.0855135103 0.1207853556 0.0060334301 0.0086340000 0.0003490000 0.0030920000 0.0000040000 0.0000030000 0.0019480000 40348061 96830484 509673472 3.8808507919 3.8016791344 3.8509337902 1342 1311867215.2049460411 0.1032289714 0.0855267111 0.1207853556 0.0060323759 0.0073850000 0.0003630000 0.0027680000 0.0000000000 0.0000040000 0.0010600000 40351789 96830484 509673472 3.8821544647 3.8051915169 3.8510851860 1343 1311867215.2369511127 0.1039741710 0.0855404471 0.1207853556 0.0060302632 0.0088880000 0.0003570000 0.0040550000 0.0000040000 0.0000040000 0.0013120000 40355405 96830484 509673472 3.8814001083 3.8056852818 3.8514974117 1344 1311867215.2690820694 0.1050930247 0.0855549952 0.1207853556 0.0060282742 0.0086330000 0.0003620000 0.0040610000 0.0000010000 0.0000040000 0.0010670000 40359133 96830484 509673472 3.8799171448 3.8070845604 3.8516652584 1345 1311867215.3049569130 0.1054173484 0.0855697627 0.1207853556 0.0060273378 0.0099110000 0.0003630000 0.0040780000 0.0000040000 0.0000030000 0.0020100000 40362917 96830484 509673472 3.8805518150 3.8089981079 3.8517076969 1346 1311867215.3369619846 0.1045916602 0.0855838949 0.1207853556 0.0060269247 0.0088400000 0.0003660000 0.0040530000 0.0000010000 0.0000040000 0.0010670000 40366589 96830484 509673472 3.8818225861 3.8099327087 3.8515102863 1347 1311867215.3691840172 0.1050163731 0.0855983214 0.1207853556 0.0060264391 0.0078980000 0.0003610000 0.0022950000 0.0000040000 0.0000030000 0.0016170000 40370261 96830484 509673472 3.8807764053 3.8106050491 3.8514492512 1348 1311867215.4049520493 0.1051980928 0.0856128612 0.1207853556 0.0060250836 0.0074570000 0.0003630000 0.0027710000 0.0000010000 0.0000040000 0.0010620000 40374045 96830484 509673472 3.8815686703 3.8130519390 3.8512623310 1349 1311867215.4370350838 0.1047320664 0.0856270341 0.1207853556 0.0060234200 0.0077190000 0.0004020000 0.0021160000 0.0000040000 0.0000040000 0.0019570000 40377661 96830484 509673472 3.8831434250 3.8151481152 3.8509516716 1350 1311867215.4690899849 0.1047532484 0.0856412017 0.1207853556 0.0060239595 0.0118530000 0.0004570000 0.0043890000 0.0000010000 0.0000090000 0.0012020000 40381389 96830484 509673472 3.8837893009 3.8151445389 3.8509271145 1351 1311867215.5049800873 0.1046841741 0.0856552971 0.1207853556 0.0060239790 0.0110230000 0.0004770000 0.0033330000 0.0000080000 0.0000080000 0.0014790000 40385173 96830484 509673472 3.8844311237 3.8171861172 3.8507311344 1352 1311867215.5371229649 0.1042386666 0.0856690422 0.1207853556 0.0060220205 0.0086560000 0.0003890000 0.0034670000 0.0000000000 0.0000050000 0.0010880000 40388789 96830484 509673472 3.8856110573 3.8198525906 3.8502392769 1353 1311867215.5690340996 0.1032365933 0.0856820264 0.1207853556 0.0060205192 0.0113990000 0.0004610000 0.0026740000 0.0000100000 0.0000090000 0.0021810000 40392517 96830484 509673472 3.8872647285 3.8204991817 3.8499748707 1354 1311867215.6050848961 0.1045957208 0.0856959951 0.1207853556 0.0060199585 0.0093670000 0.0003860000 0.0041510000 0.0000010000 0.0000060000 0.0010860000 40396301 96830484 509673472 3.8865838051 3.8227384090 3.8500645161 1355 1311867215.6370549202 0.1039636135 0.0857094768 0.1207853556 0.0060186283 0.0071050000 0.0003560000 0.0021330000 0.0000040000 0.0000040000 0.0013330000 40399973 96830484 509673472 3.8881678581 3.8264057636 3.8503148556 1356 1311867215.6689219475 0.1033056155 0.0857224533 0.1207853556 0.0060171383 0.0104740000 0.0004780000 0.0023220000 0.0000010000 0.0000110000 0.0013550000 40403645 96830484 509673472 3.8884747028 3.8265430927 3.8501043320 1357 1311867215.7049510479 0.1042755023 0.0857361254 0.1207853556 0.0060165228 0.0103100000 0.0003800000 0.0041630000 0.0000050000 0.0000050000 0.0019790000 40407429 96830484 509673472 3.8875799179 3.8276746273 3.8500056267 1358 1311867215.7388830185 0.1039136797 0.0857495109 0.1207853556 0.0060146135 0.0114870000 0.0004680000 0.0043430000 0.0000010000 0.0000080000 0.0011990000 40411157 96830484 509673472 3.8893289566 3.8317396641 3.8502323627 1359 1311867215.7691988945 0.1026253775 0.0857619288 0.1207853556 0.0060127226 0.0096670000 0.0003770000 0.0041630000 0.0000040000 0.0000040000 0.0013490000 40414661 96830484 509673472 3.8907518387 3.8322398663 3.8501465321 1360 1311867215.8048830032 0.1025046483 0.0857742396 0.1207853556 0.0060136380 0.0068540000 0.0003670000 0.0021110000 0.0000010000 0.0000040000 0.0010570000 40418445 96830484 509673472 3.8906867504 3.8328366280 3.8500740528 1361 1311867215.8373351097 0.1032181308 0.0857870566 0.1207853556 0.0060122917 0.0105320000 0.0004600000 0.0019820000 0.0000080000 0.0000080000 0.0021550000 40422117 96830484 509673472 3.8902218342 3.8339867592 3.8500683308 1362 1311867215.8691670895 0.1029385030 0.0857996494 0.1207853556 0.0060103229 0.0075260000 0.0003860000 0.0021660000 0.0000010000 0.0000050000 0.0010850000 40425845 96830484 509673472 3.8914840221 3.8352134228 3.8497509956 1363 1311867215.9052760601 0.1030958742 0.0858123392 0.1207853556 0.0060084598 0.0074550000 0.0003610000 0.0024560000 0.0000040000 0.0000030000 0.0013310000 40429629 96830484 509673472 3.8908939362 3.8344075680 3.8492815495 1364 1311867215.9370880127 0.1033669338 0.0858252092 0.1207853556 0.0060065322 0.0107310000 0.0004950000 0.0023270000 0.0000010000 0.0000110000 0.0013440000 40433245 96830484 509673472 3.8912785053 3.8362464905 3.8489005566 1365 1311867215.9702870846 0.1029331684 0.0858377425 0.1207853556 0.0060043493 0.0088940000 0.0003810000 0.0025080000 0.0000050000 0.0000050000 0.0019450000 40436973 96830484 509673472 3.8923935890 3.8378012180 3.8486347198 1366 1311867216.0050790310 0.1039627045 0.0858510111 0.1207853556 0.0060029094 0.0104100000 0.0004770000 0.0026690000 0.0000010000 0.0000100000 0.0012100000 40440757 96830484 509673472 3.8912248611 3.8381145000 3.8482961655 1367 1311867216.0369679928 0.1021712050 0.0858629498 0.1207853556 0.0060009149 0.0116930000 0.0004660000 0.0043220000 0.0000080000 0.0000080000 0.0014740000 40444373 96830484 509673472 3.8939802647 3.8392560482 3.8478610516 1368 1311867216.0694830418 0.1027596891 0.0858753012 0.1207853556 0.0060005444 0.0082650000 0.0003760000 0.0031480000 0.0000000000 0.0000050000 0.0010690000 40448101 96830484 509673472 3.8935601711 3.8407597542 3.8476500511 1369 1311867216.1050429344 0.1037627533 0.0858883673 0.1207853556 0.0059992220 0.0096910000 0.0003590000 0.0041190000 0.0000040000 0.0000030000 0.0019460000 40451885 96830484 509673472 3.8933541775 3.8434221745 3.8480420113 1370 1311867216.1392951012 0.1036826894 0.0859013559 0.1207853556 0.0059971567 0.0087850000 0.0003710000 0.0041000000 0.0000000000 0.0000030000 0.0010480000 40455613 96830484 509673472 3.8933954239 3.8441231251 3.8479621410 1371 1311867216.1692190170 0.1032347307 0.0859139987 0.1207853556 0.0059963406 0.0091060000 0.0003610000 0.0041040000 0.0000040000 0.0000040000 0.0013230000 40459229 96830484 509673472 3.8942303658 3.8453180790 3.8483486176 1372 1311867216.2049610615 0.1028309613 0.0859263289 0.1207853556 0.0059941895 0.0089240000 0.0003710000 0.0041190000 0.0000010000 0.0000040000 0.0010570000 40463013 96830484 509673472 3.8954572678 3.8483448029 3.8484899998 1373 1311867216.2370231152 0.1025517732 0.0859384377 0.1207853556 0.0059931964 0.0084530000 0.0003680000 0.0027960000 0.0000030000 0.0000030000 0.0019380000 40466629 96830484 509673472 3.8952648640 3.8483397961 3.8490769863 1374 1311867216.2706630230 0.1024258509 0.0859504373 0.1207853556 0.0059929279 0.0068680000 0.0003710000 0.0021440000 0.0000010000 0.0000040000 0.0010490000 40470413 96830484 509673472 3.8958916664 3.8504195213 3.8498377800 1375 1311867216.3050479889 0.1028187796 0.0859627052 0.1207853556 0.0059910964 0.0071420000 0.0003690000 0.0021590000 0.0000040000 0.0000040000 0.0013060000 40474141 96830484 509673472 3.8959717751 3.8527173996 3.8505477905 1376 1311867216.3395419121 0.1006284356 0.0859733634 0.1207853556 0.0059918798 0.0121660000 0.0004880000 0.0044200000 0.0000010000 0.0000080000 0.0011950000 40477925 96830484 509673472 3.8986582756 3.8545410633 3.8509325981 1377 1311867216.3694689274 0.1009643972 0.0859842501 0.1207853556 0.0059898140 0.0081510000 0.0003900000 0.0018590000 0.0000060000 0.0000040000 0.0019500000 40481485 96830484 509673472 3.8982143402 3.8549582958 3.8515977859 1378 1311867216.4055120945 0.1004911289 0.0859947776 0.1207853556 0.0059877059 0.0081780000 0.0003690000 0.0035130000 0.0000010000 0.0000040000 0.0010400000 40485325 96830484 509673472 3.8993141651 3.8566946983 3.8521099091 1379 1311867216.4373409748 0.1007014811 0.0860054424 0.1207853556 0.0059855807 0.0081950000 0.0003740000 0.0031500000 0.0000040000 0.0000040000 0.0012890000 40488885 96830484 509673472 3.8989961147 3.8577148914 3.8524146080 1380 1311867216.4697530270 0.1010201424 0.0860163226 0.1207853556 0.0059836772 0.0078700000 0.0003730000 0.0031580000 0.0000000000 0.0000040000 0.0010370000 40492669 96830484 509673472 3.8987946510 3.8600852489 3.8525083065 1381 1311867216.5049800873 0.0996292159 0.0860261799 0.1207853556 0.0059826956 0.0097870000 0.0003750000 0.0041570000 0.0000040000 0.0000040000 0.0019130000 40496397 96830484 509673472 3.9009582996 3.8609466553 3.8529083729 1382 1311867216.5372259617 0.1001452059 0.0860363963 0.1207853556 0.0059806947 0.0088880000 0.0003730000 0.0041650000 0.0000000000 0.0000030000 0.0010320000 40500069 96830484 509673472 3.9006171227 3.8609008789 3.8535363674 1383 1311867216.5693330765 0.1007649079 0.0860470459 0.1207853556 0.0059788633 0.0071850000 0.0003720000 0.0021530000 0.0000030000 0.0000030000 0.0013040000 40503741 96830484 509673472 3.9001739025 3.8622143269 3.8537089825 1384 1311867216.6050319672 0.1006278694 0.0860575812 0.1207853556 0.0059782690 0.0068510000 0.0003800000 0.0021660000 0.0000000000 0.0000030000 0.0010290000 40507525 96830484 509673472 3.9016344547 3.8638954163 3.8544011116 1385 1311867216.6373488903 0.1004599705 0.0860679800 0.1207853556 0.0059764664 0.0078390000 0.0003810000 0.0021570000 0.0000040000 0.0000030000 0.0019080000 40511197 96830484 509673472 3.9019773006 3.8638727665 3.8545329571 1386 1311867216.6691188812 0.1008513719 0.0860786463 0.1207853556 0.0059745025 0.0069110000 0.0003790000 0.0021590000 0.0000010000 0.0000040000 0.0010590000 40514869 96830484 509673472 3.9018907547 3.8637638092 3.8545923233 1387 1311867216.7052359581 0.1002778336 0.0860888836 0.1207853556 0.0059730460 0.0093100000 0.0003820000 0.0041560000 0.0000040000 0.0000040000 0.0013000000 40518653 96830484 509673472 3.9029431343 3.8658831120 3.8546676636 1388 1311867216.7372078896 0.1004445702 0.0860992263 0.1207853556 0.0059714310 0.0072380000 0.0003790000 0.0024960000 0.0000010000 0.0000040000 0.0010350000 40522269 96830484 509673472 3.9031038284 3.8668489456 3.8545365334 1389 1311867216.7691950798 0.1003565267 0.0861094908 0.1207853556 0.0059694516 0.0096750000 0.0003770000 0.0040460000 0.0000040000 0.0000030000 0.0019040000 40525997 96830484 509673472 3.9032027721 3.8668150902 3.8542783260 1390 1311867216.8050019741 0.1009966284 0.0861202009 0.1207853556 0.0059679999 0.0119620000 0.0004860000 0.0044240000 0.0000010000 0.0000080000 0.0011820000 40529781 96830484 509673472 3.9036417007 3.8681769371 3.8541727066 1391 1311867216.8379631042 0.1001434848 0.0861302824 0.1207853556 0.0059662918 0.0097980000 0.0004070000 0.0042260000 0.0000050000 0.0000040000 0.0013090000 40533453 96830484 509673472 3.9052307606 3.8685321808 3.8545155525 1392 1311867216.8703401089 0.0996254534 0.0861399772 0.1207853556 0.0059663318 0.0068900000 0.0003920000 0.0021620000 0.0000010000 0.0000040000 0.0010280000 40537125 96830484 509673472 3.9056615829 3.8692307472 3.8542153835 1393 1311867216.9049589634 0.1004325971 0.0861502375 0.1207853556 0.0059648812 0.0097940000 0.0003770000 0.0041710000 0.0000030000 0.0000030000 0.0018960000 40540909 96830484 509673472 3.9050564766 3.8701782227 3.8540048599 1394 1311867216.9374070168 0.0993344709 0.0861596953 0.1207853556 0.0059628341 0.0075700000 0.0003780000 0.0028360000 0.0000000000 0.0000030000 0.0010260000 40544525 96830484 509673472 3.9077363014 3.8710556030 3.8539776802 1395 1311867216.9691729546 0.1000178158 0.0861696295 0.1207853556 0.0059611828 0.0091770000 0.0003770000 0.0041710000 0.0000050000 0.0000030000 0.0012960000 40548197 96830484 509673472 3.9069764614 3.8722167015 3.8541183472 1396 1311867217.0053269863 0.0996407643 0.0861792793 0.1207853556 0.0059606123 0.0088760000 0.0003800000 0.0041610000 0.0000000000 0.0000040000 0.0010310000 40552037 96830484 509673472 3.9080557823 3.8736314774 3.8542954922 1397 1311867217.0373110771 0.0992744714 0.0861886531 0.1207853556 0.0059596647 0.0112460000 0.0004810000 0.0030330000 0.0000080000 0.0000070000 0.0020750000 40555653 96830484 509673472 3.9086003304 3.8734202385 3.8541667461 1398 1311867217.0691289902 0.0995168835 0.0861981869 0.1207853556 0.0059585232 0.0094500000 0.0003920000 0.0042270000 0.0000000000 0.0000040000 0.0010400000 40559325 96830484 509673472 3.9092710018 3.8741416931 3.8542511463 1399 1311867217.1052579880 0.1006309316 0.0862085033 0.1207853556 0.0059574422 0.0078510000 0.0003770000 0.0027330000 0.0000040000 0.0000040000 0.0012960000 40563165 96830484 509673472 3.9086167812 3.8760287762 3.8544299603 1400 1311867217.1370849609 0.0993622318 0.0862178989 0.1207853556 0.0059563118 0.0076080000 0.0003770000 0.0028370000 0.0000000000 0.0000040000 0.0010270000 40566781 96830484 509673472 3.9101560116 3.8758280277 3.8542490005 1401 1311867217.1691889763 0.1000128165 0.0862277453 0.1207853556 0.0059545691 0.0097280000 0.0003770000 0.0040590000 0.0000040000 0.0000040000 0.0018980000 40570509 96830484 509673472 3.9098711014 3.8762471676 3.8543345928 1402 1311867217.2057919502 0.1001533121 0.0862376780 0.1207853556 0.0059528438 0.0069370000 0.0003760000 0.0021660000 0.0000010000 0.0000040000 0.0010340000 40574293 96830484 509673472 3.9103457928 3.8783140182 3.8540899754 1403 1311867217.2371680737 0.0995165706 0.0862471426 0.1207853556 0.0059514758 0.0077670000 0.0004290000 0.0020700000 0.0000040000 0.0000040000 0.0012980000 40577965 96830484 509673472 3.9102742672 3.8782320023 3.8534989357 1404 1311867217.2692279816 0.0998723656 0.0862568472 0.1207853556 0.0059499020 0.0066710000 0.0004210000 0.0018300000 0.0000000000 0.0000030000 0.0010270000 40581637 96830484 509673472 3.9101054668 3.8791050911 3.8533148766 1405 1311867217.3051640987 0.0998987108 0.0862665567 0.1207853556 0.0059480364 0.0124460000 0.0004850000 0.0044180000 0.0000080000 0.0000080000 0.0020570000 40585421 96830484 509673472 3.9109773636 3.8816835880 3.8533813953 1406 1311867217.3374049664 0.1002627909 0.0862765114 0.1207853556 0.0059461554 0.0081440000 0.0003920000 0.0028770000 0.0000010000 0.0000040000 0.0010400000 40589093 96830484 509673472 3.9101278782 3.8831441402 3.8531599045 1407 1311867217.3695969582 0.1004201099 0.0862865637 0.1207853556 0.0059443478 0.0092410000 0.0003770000 0.0041990000 0.0000040000 0.0000030000 0.0012860000 40592765 96830484 509673472 3.9096179008 3.8847341537 3.8533444405 1408 1311867217.4120450020 0.0999353454 0.0862962574 0.1207853556 0.0059436974 0.0089820000 0.0003830000 0.0042040000 0.0000000000 0.0000030000 0.0010190000 40596605 96830484 509673472 3.9101352692 3.8854835033 3.8535027504 1409 1311867217.4372820854 0.0992678627 0.0863054637 0.1207853556 0.0059423265 0.0085370000 0.0003770000 0.0028710000 0.0000030000 0.0000030000 0.0018760000 40600053 96830484 509673472 3.9108850956 3.8856430054 3.8535158634 1410 1311867217.4694299698 0.0998068750 0.0863150391 0.1207853556 0.0059414386 0.0089460000 0.0003820000 0.0041960000 0.0000000000 0.0000040000 0.0010170000 40603781 96830484 509673472 3.9105789661 3.8874418736 3.8536164761 1411 1311867217.5050430298 0.0999479890 0.0863247010 0.1207853556 0.0059400896 0.0072120000 0.0003750000 0.0021770000 0.0000040000 0.0000040000 0.0012660000 40607565 96830484 509673472 3.9102792740 3.8883845806 3.8534193039 1412 1311867217.5370678902 0.0997549072 0.0863342125 0.1207853556 0.0059382844 0.0091130000 0.0003900000 0.0041950000 0.0000000000 0.0000040000 0.0010180000 40611181 96830484 509673472 3.9105322361 3.8891532421 3.8530542850 1413 1311867217.5691540241 0.1000610217 0.0863439272 0.1207853556 0.0059363897 0.0079610000 0.0003810000 0.0021840000 0.0000040000 0.0000030000 0.0018690000 40614853 96830484 509673472 3.9109320641 3.8909742832 3.8533434868 1414 1311867217.6050539017 0.0993223190 0.0863531057 0.1207853556 0.0059347935 0.0090020000 0.0003850000 0.0042070000 0.0000000000 0.0000040000 0.0010090000 40618693 96830484 509673472 3.9116287231 3.8921532631 3.8530926704 1415 1311867217.6370990276 0.0997643620 0.0863625836 0.1207853556 0.0059338882 0.0113940000 0.0004930000 0.0030970000 0.0000120000 0.0000100000 0.0014080000 40622309 96830484 509673472 3.9106984138 3.8939116001 3.8530356884 1416 1311867217.6691000462 0.0984558165 0.0863711240 0.1207853556 0.0059331432 0.0097260000 0.0004070000 0.0042980000 0.0000000000 0.0000050000 0.0010350000 40626037 96830484 509673472 3.9121410847 3.8947606087 3.8530759811 1417 1311867217.7050631046 0.0979766920 0.0863793142 0.1207853556 0.0059324853 0.0093980000 0.0003830000 0.0035670000 0.0000030000 0.0000030000 0.0018550000 40629821 96830484 509673472 3.9128386974 3.8948318958 3.8530023098 1418 1311867217.7371540070 0.0987185314 0.0863880161 0.1207853556 0.0059304841 0.0118070000 0.0004980000 0.0044700000 0.0000000000 0.0000090000 0.0011510000 40633437 96830484 509673472 3.9121398926 3.8950591087 3.8531186581 1419 1311867217.7694880962 0.0979437232 0.0863961596 0.1207853556 0.0059287681 0.0078580000 0.0003960000 0.0022310000 0.0000050000 0.0000050000 0.0013020000 40637165 96830484 509673472 3.9137639999 3.8964517117 3.8529779911 1420 1311867217.8051838875 0.0982011929 0.0864044730 0.1207853556 0.0059267093 0.0069550000 0.0003870000 0.0021940000 0.0000000000 0.0000040000 0.0010100000 40640949 96830484 509673472 3.9138784409 3.8967616558 3.8530235291 1421 1311867217.8372271061 0.0982099921 0.0864127809 0.1207853556 0.0059249136 0.0075340000 0.0003860000 0.0018600000 0.0000040000 0.0000040000 0.0018610000 40644565 96830484 509673472 3.9141407013 3.8968973160 3.8527495861 1422 1311867217.8690850735 0.0974747762 0.0864205601 0.1207853556 0.0059237162 0.0090280000 0.0003850000 0.0042410000 0.0000000000 0.0000030000 0.0010040000 40648293 96830484 509673472 3.9157521725 3.8990116119 3.8526694775 1423 1311867217.9056351185 0.0987742171 0.0864292415 0.1207853556 0.0059225177 0.0080020000 0.0003860000 0.0028820000 0.0000040000 0.0000040000 0.0012700000 40652133 96830484 509673472 3.9143981934 3.9005374908 3.8527443409 1424 1311867217.9372580051 0.0979703739 0.0864373463 0.1207853556 0.0059211218 0.0070470000 0.0003830000 0.0022050000 0.0000010000 0.0000040000 0.0010040000 40655693 96830484 509673472 3.9151637554 3.9012203217 3.8525640965 1425 1311867217.9711000919 0.0973962471 0.0864450367 0.1207853556 0.0059191841 0.0090330000 0.0003810000 0.0032370000 0.0000040000 0.0000030000 0.0018630000 40659477 96830484 509673472 3.9162428379 3.9037015438 3.8526546955 1426 1311867218.0052239895 0.0969215259 0.0864523835 0.1207853556 0.0059173581 0.0091140000 0.0003870000 0.0042670000 0.0000000000 0.0000040000 0.0009990000 40663205 96830484 509673472 3.9169228077 3.9047610760 3.8529152870 1427 1311867218.0371439457 0.0969978943 0.0864597735 0.1207853556 0.0059154796 0.0092600000 0.0003850000 0.0041430000 0.0000030000 0.0000030000 0.0012680000 40666821 96830484 509673472 3.9168274403 3.9052133560 3.8533771038 1428 1311867218.0710949898 0.0968769863 0.0864670684 0.1207853556 0.0059134317 0.0070070000 0.0003900000 0.0022120000 0.0000010000 0.0000030000 0.0010010000 40670437 96830484 509673472 3.9175715446 3.9073176384 3.8536427021 1429 1311867218.1050980091 0.0966694206 0.0864742079 0.1207853556 0.0059114141 0.0079310000 0.0003820000 0.0022140000 0.0000040000 0.0000040000 0.0018450000 40674221 96830484 509673472 3.9175560474 3.9084115028 3.8536298275 1430 1311867218.1371181011 0.0959475264 0.0864808326 0.1207853556 0.0059093531 0.0090400000 0.0003990000 0.0042640000 0.0000010000 0.0000040000 0.0009970000 40677893 96830484 509673472 3.9186866283 3.9102773666 3.8538720608 1431 1311867218.1712090969 0.0968568996 0.0864880836 0.1207853556 0.0059098854 0.0084790000 0.0003860000 0.0025550000 0.0000030000 0.0000040000 0.0014530000 40681621 96830484 509673472 3.9171822071 3.9117600918 3.8543033600 1432 1311867218.2050349712 0.0974681452 0.0864957512 0.1207853556 0.0059078703 0.0125660000 0.0005800000 0.0045210000 0.0000010000 0.0000080000 0.0011360000 40685349 96830484 509673472 3.9164528847 3.9134137630 3.8546333313 1433 1311867218.2372438908 0.0966285691 0.0865028223 0.1207853556 0.0059064026 0.0106050000 0.0004100000 0.0043700000 0.0000050000 0.0000040000 0.0018590000 40688965 96830484 509673472 3.9171848297 3.9138238430 3.8548936844 1434 1311867218.2715640068 0.0970106646 0.0865101499 0.1207853556 0.0059049174 0.0090930000 0.0004070000 0.0042860000 0.0000010000 0.0000040000 0.0009960000 40692749 96830484 509673472 3.9169402122 3.9160931110 3.8551683426 1435 1311867218.3051331043 0.0961556658 0.0865168715 0.1207853556 0.0059042464 0.0200600000 0.0005820000 0.0044420000 0.0000150000 0.0000150000 0.0017850000 40696477 96830484 509673472 3.9173848629 3.9154951572 3.8547766209 1436 1311867218.3373649120 0.0966078937 0.0865238987 0.1207853556 0.0059022316 0.0113110000 0.0004520000 0.0044760000 0.0000010000 0.0000070000 0.0010600000 40700093 96830484 509673472 3.9166345596 3.9163639545 3.8544335365 1437 1311867218.3734769821 0.0974434987 0.0865314976 0.1207853556 0.0059018286 0.0125720000 0.0004950000 0.0045370000 0.0000080000 0.0000070000 0.0019880000 40703933 96830484 509673472 3.9160296917 3.9190509319 3.8541071415 1438 1311867218.4052689075 0.0969079360 0.0865387135 0.1207853556 0.0059007494 0.0094210000 0.0004030000 0.0043210000 0.0000010000 0.0000050000 0.0010060000 40707605 96830484 509673472 3.9165773392 3.9204094410 3.8535025120 1439 1311867218.4372320175 0.0971722305 0.0865461030 0.1207853556 0.0059005710 0.0095150000 0.0003930000 0.0042800000 0.0000040000 0.0000040000 0.0012540000 40711277 96830484 509673472 3.9155797958 3.9192841053 3.8527126312 1440 1311867218.4729750156 0.0963430107 0.0865529064 0.1207853556 0.0059003744 0.0181670000 0.0005830000 0.0029920000 0.0000020000 0.0000150000 0.0015270000 40715005 96830484 509673472 3.9167444706 3.9205980301 3.8523004055 1441 1311867218.5051169395 0.0980819091 0.0865609071 0.1207853556 0.0059045231 0.0099350000 0.0004770000 0.0023410000 0.0000060000 0.0000060000 0.0019280000 40718733 96830484 509673472 3.9150941372 3.9238622189 3.8522503376 1442 1311867218.5372729301 0.0974511504 0.0865684593 0.1207853556 0.0059027129 0.0081300000 0.0004060000 0.0029300000 0.0000010000 0.0000040000 0.0009990000 40722349 96830484 509673472 3.9155073166 3.9249947071 3.8519995213 1443 1311867218.5714759827 0.0972548947 0.0865758650 0.1207853556 0.0059006961 0.0074680000 0.0003870000 0.0022220000 0.0000030000 0.0000030000 0.0012760000 40726133 96830484 509673472 3.9156661034 3.9259808064 3.8520600796 1444 1311867218.6059319973 0.0975829586 0.0865834876 0.1207853556 0.0058992843 0.0095100000 0.0004110000 0.0045390000 0.0000000000 0.0000040000 0.0010310000 40729917 96830484 509673472 3.9155039787 3.9273519516 3.8528504372 1445 1311867218.6372020245 0.0976668224 0.0865911577 0.1207853556 0.0058980832 0.0082230000 0.0004110000 0.0023480000 0.0000040000 0.0000040000 0.0019450000 40733477 96830484 509673472 3.9152634144 3.9280881882 3.8533725739 1446 1311867218.6710820198 0.0973238125 0.0865985800 0.1207853556 0.0058968399 0.0122520000 0.0005150000 0.0047790000 0.0000010000 0.0000080000 0.0011820000 40737261 96830484 509673472 3.9156477451 3.9288718700 3.8537538052 1447 1311867218.7058999538 0.0977586880 0.0866062926 0.1207853556 0.0058962152 0.0089400000 0.0004380000 0.0032460000 0.0000040000 0.0000040000 0.0013120000 40740877 96830484 509673472 3.9152636528 3.9296514988 3.8541955948 1448 1311867218.7378489971 0.0965278894 0.0866131446 0.1207853556 0.0058966171 0.0087640000 0.0004250000 0.0038220000 0.0000000000 0.0000040000 0.0010270000 40744549 96830484 509673472 3.9160871506 3.9294509888 3.8547458649 1449 1311867218.7715899944 0.0976688862 0.0866207745 0.1207853556 0.0058960278 0.0100840000 0.0004210000 0.0043220000 0.0000030000 0.0000040000 0.0019190000 40748277 96830484 509673472 3.9152250290 3.9297165871 3.8552279472 1450 1311867218.8052420616 0.0973776951 0.0866281930 0.1207853556 0.0058957542 0.0094900000 0.0004120000 0.0045530000 0.0000000000 0.0000040000 0.0010220000 40752061 96830484 509673472 3.9156866074 3.9316756725 3.8557572365 1451 1311867218.8379960060 0.0976248533 0.0866357717 0.1207853556 0.0058939095 0.0097150000 0.0004240000 0.0045610000 0.0000040000 0.0000030000 0.0013060000 40755677 96830484 509673472 3.9151542187 3.9323112965 3.8563563824 1452 1311867218.8727340698 0.0982671976 0.0866437823 0.1207853556 0.0058966602 0.0096080000 0.0004320000 0.0045640000 0.0000000000 0.0000030000 0.0010280000 40759405 96830484 509673472 3.9137976170 3.9310266972 3.8564913273 1453 1311867218.9054861069 0.0973787755 0.0866511705 0.1207853556 0.0058981028 0.0098460000 0.0004240000 0.0038320000 0.0000030000 0.0000030000 0.0019200000 40763021 96830484 509673472 3.9144687653 3.9336891174 3.8571209908 1454 1311867218.9372200966 0.0963351578 0.0866578307 0.1207853556 0.0058989545 0.0078120000 0.0004230000 0.0027470000 0.0000010000 0.0000040000 0.0010310000 40766749 96830484 509673472 3.9145996571 3.9335517883 3.8569455147 1455 1311867218.9731678963 0.0968429297 0.0866648308 0.1207853556 0.0058974290 0.0098280000 0.0004250000 0.0045750000 0.0000030000 0.0000040000 0.0013040000 40770533 96830484 509673472 3.9141006470 3.9344210625 3.8575923443 1456 1311867219.0051829815 0.0967351422 0.0866717472 0.1207853556 0.0058954368 0.0084160000 0.0004260000 0.0034830000 0.0000010000 0.0000040000 0.0010230000 40774261 96830484 509673472 3.9143695831 3.9357306957 3.8580608368 1457 1311867219.0371239185 0.0964718536 0.0866784734 0.1207853556 0.0058935107 0.0086570000 0.0004260000 0.0027420000 0.0000040000 0.0000040000 0.0018950000 40777933 96830484 509673472 3.9139080048 3.9363615513 3.8580043316 1458 1311867219.0738430023 0.0946367607 0.0866839318 0.1207853556 0.0058941308 0.0095240000 0.0004290000 0.0045930000 0.0000000000 0.0000040000 0.0010170000 40781717 96830484 509673472 3.9161403179 3.9373350143 3.8583827019 1459 1311867219.1050798893 0.0952003226 0.0866897689 0.1207853556 0.0058970120 0.0098390000 0.0004270000 0.0045890000 0.0000040000 0.0000040000 0.0013030000 40785333 96830484 509673472 3.9151933193 3.9370949268 3.8587865829 1460 1311867219.1383259296 0.0941878110 0.0866949046 0.1207853556 0.0058950847 0.0080530000 0.0004310000 0.0031290000 0.0000010000 0.0000040000 0.0010170000 40789005 96830484 509673472 3.9168999195 3.9384801388 3.8591988087 1461 1311867219.1708459854 0.0956347510 0.0867010236 0.1207853556 0.0058933185 0.0086320000 0.0004240000 0.0027640000 0.0000040000 0.0000040000 0.0018920000 40792733 96830484 509673472 3.9154326916 3.9400515556 3.8596820831 1462 1311867219.2052450180 0.0947441906 0.0867065251 0.1207853556 0.0058924486 0.0128200000 0.0005480000 0.0049080000 0.0000000000 0.0000080000 0.0011410000 40796517 96830484 509673472 3.9166383743 3.9407491684 3.8601622581 1463 1311867219.2391340733 0.0946253836 0.0867119378 0.1207853556 0.0058942606 0.0086310000 0.0004490000 0.0028030000 0.0000040000 0.0000040000 0.0013210000 40800189 96830484 509673472 3.9167599678 3.9422316551 3.8604328632 1464 1311867219.2709059715 0.0948596150 0.0867175032 0.1207853556 0.0058930465 0.0073750000 0.0004330000 0.0024050000 0.0000000000 0.0000040000 0.0010150000 40803861 96830484 509673472 3.9165973663 3.9430837631 3.8605668545 1465 1311867219.3052430153 0.0942959040 0.0867226761 0.1207853556 0.0058984319 0.0083670000 0.0004430000 0.0024020000 0.0000040000 0.0000030000 0.0018840000 40807589 96830484 509673472 3.9173703194 3.9432518482 3.8606755733 1466 1311867219.3401598930 0.0938287303 0.0867275234 0.1207853556 0.0058966426 0.0096220000 0.0004370000 0.0046160000 0.0000010000 0.0000040000 0.0010090000 40811317 96830484 509673472 3.9189970493 3.9444203377 3.8612241745 1467 1311867219.3715050220 0.0936993808 0.0867322758 0.1207853556 0.0058948986 0.0098070000 0.0004500000 0.0045070000 0.0000040000 0.0000040000 0.0012920000 40814933 96830484 509673472 3.9200875759 3.9459650517 3.8614552021 1468 1311867219.4051969051 0.0951226503 0.0867379914 0.1207853556 0.0058931917 0.0092100000 0.0004360000 0.0042540000 0.0000010000 0.0000040000 0.0010060000 40818717 96830484 509673472 3.9179451466 3.9463810921 3.8615014553 1469 1311867219.4394860268 0.0947422832 0.0867434402 0.1207853556 0.0058913617 0.0082720000 0.0004420000 0.0023830000 0.0000040000 0.0000040000 0.0018750000 40822445 96830484 509673472 3.9188733101 3.9473731518 3.8617093563 1470 1311867219.4717299938 0.0953442529 0.0867492910 0.1207853556 0.0058895241 0.0096180000 0.0004390000 0.0046320000 0.0000000000 0.0000040000 0.0010190000 40826117 96830484 509673472 3.9186291695 3.9486837387 3.8621397018 1471 1311867219.5051560402 0.0947945416 0.0867547603 0.1207853556 0.0058883838 0.0099110000 0.0004420000 0.0046390000 0.0000040000 0.0000040000 0.0012980000 40829845 96830484 509673472 3.9194748402 3.9487197399 3.8624458313 1472 1311867219.5391950607 0.0955105349 0.0867607085 0.1207853556 0.0058877064 0.0108830000 0.0005380000 0.0026080000 0.0000010000 0.0000110000 0.0012290000 40833517 96830484 509673472 3.9192612171 3.9507498741 3.8626744747 1473 1311867219.5743470192 0.0956873372 0.0867667687 0.1207853556 0.0058863440 0.0093900000 0.0004600000 0.0028350000 0.0000060000 0.0000050000 0.0018970000 40837301 96830484 509673472 3.9195485115 3.9526765347 3.8629100323 1474 1311867219.6086258888 0.0952594280 0.0867725303 0.1207853556 0.0058849520 0.0073550000 0.0004440000 0.0024080000 0.0000000000 0.0000040000 0.0010070000 40840973 96830484 509673472 3.9201304913 3.9517817497 3.8633723259 1475 1311867219.6425020695 0.0960776210 0.0867788389 0.1207853556 0.0058944305 0.0072960000 0.0004430000 0.0020250000 0.0000040000 0.0000040000 0.0012970000 40844701 96830484 509673472 3.9202811718 3.9533965588 3.8634686470 1476 1311867219.6711170673 0.0954507664 0.0867847141 0.1207853556 0.0059109874 0.0095870000 0.0004430000 0.0046210000 0.0000000000 0.0000040000 0.0010060000 40848261 96830484 509673472 3.9217424393 3.9536240101 3.8637230396 1477 1311867219.7052869797 0.0968046710 0.0867914981 0.1207853556 0.0059100762 0.0104610000 0.0004420000 0.0046240000 0.0000030000 0.0000030000 0.0018760000 40851989 96830484 509673472 3.9202551842 3.9532113075 3.8633964062 1478 1311867219.7395179272 0.0951171368 0.0867971312 0.1207853556 0.0059106604 0.0077640000 0.0004440000 0.0027900000 0.0000010000 0.0000040000 0.0010020000 40855717 96830484 509673472 3.9232316017 3.9538800716 3.8636732101 1479 1311867219.7772109509 0.0957522988 0.0868031861 0.1207853556 0.0059227788 0.0099890000 0.0004370000 0.0046310000 0.0000040000 0.0000040000 0.0012830000 40859501 96830484 509673472 3.9237709045 3.9553384781 3.8636665344 1480 1311867219.8051769733 0.0952017456 0.0868088608 0.1207853556 0.0059217397 0.0094470000 0.0004470000 0.0037130000 0.0000010000 0.0000040000 0.0010220000 40863117 96830484 509673472 3.9249827862 3.9555368423 3.8634474277 1481 1311867219.8397340775 0.0961721018 0.0868151830 0.1207853556 0.0059218025 0.0109440000 0.0004450000 0.0047540000 0.0000040000 0.0000040000 0.0019820000 40866901 96830484 509673472 3.9242925644 3.9568920135 3.8634192944 1482 1311867219.8753221035 0.0955628008 0.0868210856 0.1207853556 0.0059295722 0.0094010000 0.0004420000 0.0042700000 0.0000000000 0.0000040000 0.0010560000 40870629 96830484 509673472 3.9262540340 3.9583997726 3.8637135029 1483 1311867219.9108390808 0.0954432338 0.0868268996 0.1207853556 0.0059457154 0.0074560000 0.0004370000 0.0020380000 0.0000040000 0.0000040000 0.0013370000 40874301 96830484 509673472 3.9266436100 3.9593091011 3.8638513088 1484 1311867219.9417819977 0.0949060395 0.0868323437 0.1207853556 0.0059460196 0.0097070000 0.0004420000 0.0046280000 0.0000000000 0.0000030000 0.0010550000 40877973 96830484 509673472 3.9273355007 3.9604742527 3.8639559746 1485 1311867219.9732298851 0.0952415988 0.0868380065 0.1207853556 0.0059456694 0.0088610000 0.0004400000 0.0027670000 0.0000040000 0.0000040000 0.0019710000 40881533 96830484 509673472 3.9273819923 3.9611153603 3.8640797138 1486 1311867220.0068678856 0.0946102813 0.0868432369 0.1207853556 0.0059458146 0.0097600000 0.0004370000 0.0046300000 0.0000010000 0.0000040000 0.0010530000 40885317 96830484 509673472 3.9287257195 3.9612188339 3.8643300533 1487 1311867220.0422430038 0.0942746326 0.0868482344 0.1207853556 0.0059455766 0.0100820000 0.0004390000 0.0046340000 0.0000040000 0.0000040000 0.0013240000 40889045 96830484 509673472 3.9293668270 3.9633433819 3.8645930290 1488 1311867220.0743820667 0.0952268168 0.0868538652 0.1207853556 0.0059439596 0.0097610000 0.0004350000 0.0046330000 0.0000000000 0.0000040000 0.0010450000 40892717 96830484 509673472 3.9289424419 3.9643003941 3.8647053242 1489 1311867220.1052761078 0.0945053771 0.0868590039 0.1207853556 0.0059483953 0.0108440000 0.0004420000 0.0046460000 0.0000040000 0.0000030000 0.0019750000 40896389 96830484 509673472 3.9300842285 3.9653079510 3.8649194241 1490 1311867220.1421229839 0.0952478424 0.0868646340 0.1207853556 0.0059469757 0.0096410000 0.0004400000 0.0045280000 0.0000000000 0.0000030000 0.0010520000 40900117 96830484 509673472 3.9294226170 3.9672760963 3.8651196957 1491 1311867220.1714730263 0.0950334892 0.0868701128 0.1207853556 0.0059505115 0.0082240000 0.0004350000 0.0027850000 0.0000040000 0.0000040000 0.0013300000 40903789 96830484 509673472 3.9291448593 3.9691298008 3.8651497364 1492 1311867220.2061989307 0.0957824141 0.0868760862 0.1207853556 0.0059541486 0.0099050000 0.0004440000 0.0046430000 0.0000010000 0.0000040000 0.0010510000 40907573 96830484 509673472 3.9285345078 3.9698743820 3.8651678562 1493 1311867220.2422249317 0.0956320614 0.0868819508 0.1207853556 0.0059570782 0.0107480000 0.0004360000 0.0046280000 0.0000040000 0.0000030000 0.0019530000 40911357 96830484 509673472 3.9285283089 3.9695949554 3.8649809361 1494 1311867220.2741279602 0.0959148705 0.0868879970 0.1207853556 0.0059554787 0.0097860000 0.0004410000 0.0046470000 0.0000010000 0.0000040000 0.0010450000 40914973 96830484 509673472 3.9283452034 3.9708836079 3.8650116920 1495 1311867220.3064579964 0.0958776399 0.0868940101 0.1207853556 0.0059649581 0.0074700000 0.0004410000 0.0020410000 0.0000030000 0.0000030000 0.0013300000 40918645 96830484 509673472 3.9288063049 3.9717373848 3.8650910854 1496 1311867220.3420999050 0.0957979411 0.0868999619 0.1207853556 0.0059677106 0.0079020000 0.0004420000 0.0027840000 0.0000010000 0.0000040000 0.0010430000 40922317 96830484 509673472 3.9287102222 3.9727094173 3.8648920059 1497 1311867220.3714869022 0.0946801230 0.0869051591 0.1207853556 0.0060127870 0.0084370000 0.0004330000 0.0024230000 0.0000040000 0.0000040000 0.0019490000 40925933 96830484 509673472 3.9292020798 3.9734003544 3.8647747040 1498 1311867220.4063799381 0.0942110568 0.0869100362 0.1207853556 0.0060133173 0.0079100000 0.0004420000 0.0028170000 0.0000000000 0.0000040000 0.0010370000 40929773 96830484 509673472 3.9306435585 3.9760773182 3.8649909496 1499 1311867220.4408841133 0.0950204581 0.0869154468 0.1207853556 0.0060120539 0.0116690000 0.0005450000 0.0030250000 0.0000090000 0.0000080000 0.0014610000 40933501 96830484 509673472 3.9289848804 3.9774482250 3.8651547432 1500 1311867220.4728751183 0.0960218236 0.0869215177 0.1207853556 0.0060156698 0.0104670000 0.0004890000 0.0047440000 0.0000010000 0.0000040000 0.0010500000 40937117 96830484 509673472 3.9277966022 3.9790167809 3.8650724888 1501 1311867220.5091059208 0.0958486423 0.0869274651 0.1207853556 0.0060144946 0.0092860000 0.0004440000 0.0031740000 0.0000030000 0.0000040000 0.0019320000 40940957 96830484 509673472 3.9290308952 3.9788236618 3.8654456139 1502 1311867220.5419850349 0.0955801308 0.0869332259 0.1207853556 0.0060125125 0.0097930000 0.0004460000 0.0046730000 0.0000000000 0.0000040000 0.0010320000 40944573 96830484 509673472 3.9295461178 3.9801018238 3.8656544685 1503 1311867220.5716400146 0.0950702131 0.0869386397 0.1207853556 0.0060116420 0.0101010000 0.0004430000 0.0046770000 0.0000040000 0.0000040000 0.0013190000 40948133 96830484 509673472 3.9303777218 3.9802441597 3.8653647900 1504 1311867220.6104249954 0.0959291607 0.0869446175 0.1207853556 0.0060120652 0.0097810000 0.0004430000 0.0046530000 0.0000000000 0.0000060000 0.0010300000 40951973 96830484 509673472 3.9295806885 3.9805860519 3.8651051521 1505 1311867220.6415500641 0.0963593721 0.0869508731 0.1207853556 0.0060103512 0.0082740000 0.0004470000 0.0020490000 0.0000040000 0.0000030000 0.0019250000 40955533 96830484 509673472 3.9297103882 3.9814732075 3.8648376465 1506 1311867220.6713089943 0.0961303785 0.0869569684 0.1207853556 0.0060084041 0.0098620000 0.0004420000 0.0046740000 0.0000000000 0.0000030000 0.0010250000 40959205 96830484 509673472 3.9304735661 3.9821600914 3.8643519878 1507 1311867220.7073359489 0.0965797380 0.0869633538 0.1207853556 0.0060096142 0.0113010000 0.0004410000 0.0053320000 0.0000040000 0.0000030000 0.0013080000 40962989 96830484 509673472 3.9314892292 3.9830622673 3.8640146255 1508 1311867220.7393438816 0.0952381864 0.0869688411 0.1207853556 0.0060087320 0.0099190000 0.0004930000 0.0046720000 0.0000000000 0.0000040000 0.0010320000 40966661 96830484 509673472 3.9327113628 3.9824163914 3.8633584976 1509 1311867220.7719850540 0.0948059186 0.0869740346 0.1207853556 0.0060071906 0.0092610000 0.0004430000 0.0031620000 0.0000030000 0.0000040000 0.0019420000 40970277 96830484 509673472 3.9345154762 3.9840919971 3.8629951477 1510 1311867220.8097529411 0.0956906378 0.0869798072 0.1207853556 0.0060078464 0.0098900000 0.0004420000 0.0046710000 0.0000010000 0.0000040000 0.0010370000 40974173 96830484 509673472 3.9341259003 3.9849221706 3.8626239300 1511 1311867220.8415019512 0.0955507308 0.0869854796 0.1207853556 0.0060067432 0.0101270000 0.0004420000 0.0046520000 0.0000040000 0.0000030000 0.0013160000 40977789 96830484 509673472 3.9354054928 3.9867041111 3.8625731468 1512 1311867220.8712480068 0.0955536589 0.0869911464 0.1207853556 0.0060094529 0.0098640000 0.0004460000 0.0046660000 0.0000000000 0.0000030000 0.0010350000 40981461 96830484 509673472 3.9363174438 3.9879975319 3.8628160954 1513 1311867220.9075961113 0.0950198993 0.0869964529 0.1207853556 0.0060101694 0.0096380000 0.0004530000 0.0035350000 0.0000040000 0.0000030000 0.0019320000 40985245 96830484 509673472 3.9372844696 3.9874789715 3.8628249168 1514 1311867220.9392969608 0.0954372063 0.0870020280 0.1207853556 0.0060084379 0.0097570000 0.0004420000 0.0045730000 0.0000000000 0.0000030000 0.0010390000 40988917 96830484 509673472 3.9373271465 3.9885115623 3.8628244400 1515 1311867220.9713189602 0.0965827405 0.0870083519 0.1207853556 0.0060158451 0.0082420000 0.0004460000 0.0027930000 0.0000040000 0.0000030000 0.0013160000 40992589 96830484 509673472 3.9363510609 3.9892859459 3.8629059792 1516 1311867221.0090179443 0.0960480720 0.0870143148 0.1207853556 0.0060138757 0.0098250000 0.0004420000 0.0046510000 0.0000000000 0.0000040000 0.0010370000 40996429 96830484 509673472 3.9375364780 3.9902441502 3.8631234169 1517 1311867221.0392940044 0.0962806642 0.0870204231 0.1207853556 0.0060119128 0.0107490000 0.0004460000 0.0045420000 0.0000040000 0.0000030000 0.0019300000 41000045 96830484 509673472 3.9374368191 3.9901916981 3.8632211685 1518 1311867221.0720989704 0.0969118699 0.0870269392 0.1207853556 0.0060103394 0.0098460000 0.0004440000 0.0046730000 0.0000000000 0.0000030000 0.0010370000 41003717 96830484 509673472 3.9369564056 3.9911386967 3.8633329868 1519 1311867221.1077580452 0.0966845751 0.0870332971 0.1207853556 0.0060091618 0.0086230000 0.0004410000 0.0031740000 0.0000030000 0.0000030000 0.0013330000 41007501 96830484 509673472 3.9378371239 3.9933407307 3.8634257317 1520 1311867221.1397790909 0.0968353078 0.0870397458 0.1207853556 0.0060079813 0.0116880000 0.0005370000 0.0037460000 0.0000000000 0.0000090000 0.0011870000 41011229 96830484 509673472 3.9385251999 3.9926877022 3.8635847569 1521 1311867221.1716909409 0.0978797153 0.0870468727 0.1207853556 0.0060097248 0.0092710000 0.0004610000 0.0027110000 0.0000040000 0.0000040000 0.0019570000 41014789 96830484 509673472 3.9379315376 3.9939005375 3.8633246422 1522 1311867221.2083969116 0.0975806862 0.0870537937 0.1207853556 0.0060107125 0.0088420000 0.0004440000 0.0035600000 0.0000000000 0.0000040000 0.0010400000 41018573 96830484 509673472 3.9392070770 3.9966723919 3.8634424210 1523 1311867221.2398130894 0.0966133326 0.0870600705 0.1207853556 0.0060105857 0.0101730000 0.0004470000 0.0046790000 0.0000040000 0.0000030000 0.0013170000 41022301 96830484 509673472 3.9406719208 3.9965968132 3.8631973267 1524 1311867221.2721240520 0.0968662128 0.0870665050 0.1207853556 0.0060091753 0.0076480000 0.0004430000 0.0024220000 0.0000000000 0.0000040000 0.0010400000 41025973 96830484 509673472 3.9404311180 3.9964408875 3.8628456593 1525 1311867221.3075931072 0.0982482135 0.0870738372 0.1207853556 0.0060109582 0.0108000000 0.0004470000 0.0046770000 0.0000040000 0.0000030000 0.0019360000 41029701 96830484 509673472 3.9397408962 3.9994115829 3.8624072075 1526 1311867221.3393449783 0.0971539393 0.0870804428 0.1207853556 0.0060095688 0.0084080000 0.0004450000 0.0031750000 0.0000000000 0.0000050000 0.0010400000 41033373 96830484 509673472 3.9422032833 4.0005559921 3.8621313572 1527 1311867221.3714220524 0.0965871289 0.0870866685 0.1207853556 0.0060087024 0.0101050000 0.0004430000 0.0046800000 0.0000040000 0.0000040000 0.0012990000 41037101 96830484 509673472 3.9429810047 3.9999921322 3.8612270355 1528 1311867221.4073879719 0.0966914371 0.0870929544 0.1207853556 0.0060071119 0.0098710000 0.0004420000 0.0046810000 0.0000010000 0.0000040000 0.0010540000 41040773 96830484 509673472 3.9442238808 4.0033049583 3.8606522083 1529 1311867221.4400680065 0.0962537751 0.0870989458 0.1207853556 0.0060061066 0.0134330000 0.0005390000 0.0049400000 0.0000080000 0.0000080000 0.0021050000 41044501 96830484 509673472 3.9456636906 4.0040111542 3.8602392673 1530 1311867221.4712409973 0.0960723311 0.0871048107 0.1207853556 0.0060052927 0.0103230000 0.0004630000 0.0047280000 0.0000000000 0.0000040000 0.0010480000 41048117 96830484 509673472 3.9468593597 4.0059409142 3.8598728180 1531 1311867221.5081720352 0.0963962302 0.0871108796 0.1207853556 0.0060039369 0.0101950000 0.0004440000 0.0047000000 0.0000040000 0.0000040000 0.0013200000 41051901 96830484 509673472 3.9466581345 4.0063543320 3.8594441414 1532 1311867221.5396909714 0.0969449729 0.0871172987 0.1207853556 0.0060021797 0.0117880000 0.0005360000 0.0037780000 0.0000010000 0.0000090000 0.0011620000 41055629 96830484 509673472 3.9466919899 4.0083165169 3.8590483665 1533 1311867221.5712790489 0.0972691700 0.0871239209 0.1207853556 0.0060019577 0.0097720000 0.0004600000 0.0032270000 0.0000040000 0.0000040000 0.0019420000 41059301 96830484 509673472 3.9466533661 4.0097603798 3.8585000038 1534 1311867221.6073110104 0.0968459547 0.0871302586 0.1207853556 0.0060010864 0.0098910000 0.0004430000 0.0046980000 0.0000000000 0.0000040000 0.0010240000 41063029 96830484 509673472 3.9470565319 4.0093626976 3.8576414585 1535 1311867221.6403770447 0.0972113311 0.0871368261 0.1207853556 0.0060002699 0.0086200000 0.0004460000 0.0031670000 0.0000040000 0.0000040000 0.0013190000 41066813 96830484 509673472 3.9467880726 4.0128369331 3.8568975925 1536 1311867221.6771481037 0.0972026363 0.0871433794 0.1207853556 0.0059997394 0.0121250000 0.0005400000 0.0034260000 0.0000010000 0.0000110000 0.0012160000 41070597 96830484 509673472 3.9472606182 4.0153083801 3.8560304642 1537 1311867221.7072019577 0.0971160010 0.0871498677 0.1207853556 0.0060007989 0.0099560000 0.0004620000 0.0032410000 0.0000050000 0.0000040000 0.0019460000 41074157 96830484 509673472 3.9469909668 4.0173873901 3.8549790382 1538 1311867221.7423930168 0.0961663276 0.0871557302 0.1207853556 0.0059992392 0.0099150000 0.0004410000 0.0046850000 0.0000010000 0.0000040000 0.0010270000 41077941 96830484 509673472 3.9481060505 4.0195803642 3.8539900780 1539 1311867221.7773499489 0.0959376246 0.0871614364 0.1207853556 0.0059983994 0.0083010000 0.0004480000 0.0028140000 0.0000040000 0.0000030000 0.0013050000 41081613 96830484 509673472 3.9488787651 4.0220923424 3.8533775806 1540 1311867221.8074541092 0.0960920453 0.0871672355 0.1207853556 0.0059966558 0.0099180000 0.0004450000 0.0047040000 0.0000000000 0.0000040000 0.0010390000 41085229 96830484 509673472 3.9487857819 4.0242352486 3.8524489403 1541 1311867221.8396520615 0.0956714079 0.0871727541 0.1207853556 0.0060038775 0.0107840000 0.0004420000 0.0046940000 0.0000030000 0.0000030000 0.0019240000 41088957 96830484 509673472 3.9484174252 4.0227942467 3.8507857323 1542 1311867221.8777329922 0.0957190096 0.0871782964 0.1207853556 0.0060057863 0.0098740000 0.0004410000 0.0046880000 0.0000000000 0.0000040000 0.0010330000 41092797 96830484 509673472 3.9489240646 4.0243039131 3.8494241238 1543 1311867221.9077489376 0.0955424681 0.0871837172 0.1207853556 0.0060060802 0.0101830000 0.0004460000 0.0047210000 0.0000030000 0.0000040000 0.0013070000 41096413 96830484 509673472 3.9494524002 4.0269279480 3.8480570316 1544 1311867221.9424629211 0.0956539661 0.0871892031 0.1207853556 0.0060060687 0.0100430000 0.0004430000 0.0046860000 0.0000000000 0.0000030000 0.0010380000 41100141 96830484 509673472 3.9481918812 4.0272459984 3.8467082977 1545 1311867221.9775359631 0.0949592739 0.0871942322 0.1207853556 0.0060051081 0.0096940000 0.0004470000 0.0035710000 0.0000030000 0.0000030000 0.0019020000 41103925 96830484 509673472 3.9491448402 4.0288958549 3.8455955982 1546 1311867222.0090060234 0.0957808048 0.0871997863 0.1207853556 0.0060032376 0.0122500000 0.0005580000 0.0034410000 0.0000010000 0.0000100000 0.0012310000 41107597 96830484 509673472 3.9479796886 4.0309510231 3.8448109627 1547 1311867222.0428760052 0.0959303081 0.0872054298 0.1207853556 0.0060044227 0.0108590000 0.0004660000 0.0047630000 0.0000050000 0.0000050000 0.0013410000 41111157 96830484 509673472 3.9471693039 4.0315818787 3.8438348770 1548 1311867222.0782530308 0.0966201723 0.0872115117 0.1207853556 0.0060080998 0.0100450000 0.0004480000 0.0047120000 0.0000010000 0.0000040000 0.0010430000 41114829 96830484 509673472 3.9461040497 4.0346164703 3.8432083130 1549 1311867222.1110939980 0.0957894474 0.0872170494 0.1207853556 0.0060064981 0.0093380000 0.0004460000 0.0032020000 0.0000040000 0.0000040000 0.0019370000 41118501 96830484 509673472 3.9469208717 4.0378766060 3.8429276943 1550 1311867222.1406900883 0.0957829729 0.0872225758 0.1207853556 0.0060207952 0.0099370000 0.0004450000 0.0047030000 0.0000010000 0.0000040000 0.0010330000 41122117 96830484 509673472 3.9454209805 4.0395302773 3.8427820206 1551 1311867222.1797990799 0.0959992111 0.0872282345 0.1207853556 0.0060331199 0.0102410000 0.0004480000 0.0046830000 0.0000040000 0.0000050000 0.0013190000 41126013 96830484 509673472 3.9447572231 4.0405526161 3.8424298763 1552 1311867222.2081730366 0.0963564068 0.0872341161 0.1207853556 0.0060353615 0.0079090000 0.0004480000 0.0026960000 0.0000010000 0.0000040000 0.0010330000 41129573 96830484 509673472 3.9447424412 4.0453639030 3.8429322243 1553 1311867222.2400839329 0.0970243961 0.0872404202 0.1207853556 0.0060358879 0.0108250000 0.0004490000 0.0047000000 0.0000030000 0.0000030000 0.0019150000 41133245 96830484 509673472 3.9432103634 4.0475788116 3.8432376385 1554 1311867222.2760300636 0.0963247120 0.0872462659 0.1207853556 0.0060350570 0.0099660000 0.0004490000 0.0046950000 0.0000000000 0.0000030000 0.0010270000 41137029 96830484 509673472 3.9425985813 4.0470824242 3.8432989120 1555 1311867222.3077421188 0.0970697179 0.0872525833 0.1207853556 0.0060332754 0.0084150000 0.0004510000 0.0028170000 0.0000050000 0.0000040000 0.0013060000 41140701 96830484 509673472 3.9413740635 4.0508933067 3.8440477848 1556 1311867222.3396389484 0.0977905989 0.0872593558 0.1207853556 0.0060343208 0.0099660000 0.0004440000 0.0046920000 0.0000000000 0.0000030000 0.0010150000 41144373 96830484 509673472 3.9396014214 4.0524811745 3.8443446159 1557 1311867222.3792359829 0.0958683267 0.0872648850 0.1207853556 0.0060354709 0.0105460000 0.0004520000 0.0043120000 0.0000040000 0.0000040000 0.0019030000 41148213 96830484 509673472 3.9416904449 4.0524792671 3.8446164131 1558 1311867222.4102001190 0.0960161462 0.0872705020 0.1207853556 0.0060346038 0.0100590000 0.0004460000 0.0047230000 0.0000000000 0.0000040000 0.0010190000 41151885 96830484 509673472 3.9411604404 4.0545682907 3.8452572823 1559 1311867222.4436430931 0.0951953158 0.0872755852 0.1207853556 0.0060336992 0.0109360000 0.0004490000 0.0047360000 0.0000040000 0.0000040000 0.0013130000 41155557 96830484 509673472 3.9427301884 4.0571832657 3.8463976383 1560 1311867222.4781119823 0.0946026295 0.0872802820 0.1207853556 0.0060322727 0.0079400000 0.0005010000 0.0025450000 0.0000000000 0.0000030000 0.0010390000 41159341 96830484 509673472 3.9422283173 4.0584802628 3.8470079899 1561 1311867222.5087089539 0.0940619707 0.0872846265 0.1207853556 0.0060305450 0.0090660000 0.0004550000 0.0028350000 0.0000040000 0.0000040000 0.0019020000 41162957 96830484 509673472 3.9436838627 4.0602588654 3.8481316566 1562 1311867222.5401790142 0.0938235223 0.0872888127 0.1207853556 0.0060291496 0.0100860000 0.0004490000 0.0047220000 0.0000000000 0.0000040000 0.0010140000 41166629 96830484 509673472 3.9445164204 4.0616579056 3.8489186764 1563 1311867222.5774040222 0.0932930186 0.0872926542 0.1207853556 0.0060279588 0.0096540000 0.0004550000 0.0039800000 0.0000030000 0.0000030000 0.0012930000 41170413 96830484 509673472 3.9448878765 4.0616068840 3.8495981693 1564 1311867222.6084389687 0.0922120139 0.0872957996 0.1207853556 0.0060270231 0.0089340000 0.0004550000 0.0036070000 0.0000000000 0.0000040000 0.0010090000 41174085 96830484 509673472 3.9458603859 4.0617327690 3.8504862785 1565 1311867222.6433119774 0.0940050706 0.0873000866 0.1207853556 0.0060257471 0.0089330000 0.0004640000 0.0028500000 0.0000030000 0.0000030000 0.0018770000 41177813 96830484 509673472 3.9435493946 4.0642251968 3.8510346413 1566 1311867222.6796491146 0.0943491980 0.0873045880 0.1207853556 0.0060261304 0.0092830000 0.0004520000 0.0039830000 0.0000000000 0.0000040000 0.0009940000 41181653 96830484 509673472 3.9435412884 4.0650200844 3.8516941071 1567 1311867222.7080249786 0.0935389698 0.0873085665 0.1207853556 0.0060265327 0.0128840000 0.0005530000 0.0050120000 0.0000080000 0.0000070000 0.0013620000 41185157 96830484 509673472 3.9445800781 4.0664172173 3.8523385525 1568 1311867222.7400081158 0.0935090706 0.0873125209 0.1207853556 0.0060283669 0.0103770000 0.0004680000 0.0047990000 0.0000000000 0.0000040000 0.0010050000 41188885 96830484 509673472 3.9450044632 4.0678868294 3.8532471657 1569 1311867222.7793939114 0.0926612020 0.0873159299 0.1207853556 0.0060314274 0.0090800000 0.0004600000 0.0028610000 0.0000050000 0.0000030000 0.0018460000 41192613 96830484 509673472 3.9459452629 4.0674085617 3.8537464142 1570 1311867222.8093209267 0.0922550634 0.0873190759 0.1207853556 0.0060305685 0.0100680000 0.0004570000 0.0047610000 0.0000010000 0.0000040000 0.0010000000 41196173 96830484 509673472 3.9465947151 4.0673279762 3.8542408943 1571 1311867222.8402760029 0.0919303149 0.0873220111 0.1207853556 0.0060289742 0.0088110000 0.0004590000 0.0032250000 0.0000040000 0.0000040000 0.0012590000 41199845 96830484 509673472 3.9474468231 4.0694894791 3.8548746109 1572 1311867222.8812980652 0.0907977819 0.0873242221 0.1207853556 0.0060276939 0.0088790000 0.0004540000 0.0036180000 0.0000000000 0.0000040000 0.0009940000 41203685 96830484 509673472 3.9484245777 4.0693359375 3.8553869724 1573 1311867222.9082360268 0.0913018435 0.0873267508 0.1207853556 0.0060265802 0.0101640000 0.0004670000 0.0040010000 0.0000040000 0.0000040000 0.0018690000 41207245 96830484 509673472 3.9474639893 4.0689253807 3.8556756973 1574 1311867222.9470820427 0.0914978087 0.0873294008 0.1207853556 0.0060253736 0.0101210000 0.0004540000 0.0047560000 0.0000000000 0.0000030000 0.0009980000 41211141 96830484 509673472 3.9475114346 4.0712046623 3.8564751148 1575 1311867222.9831020832 0.0908546075 0.0873316390 0.1207853556 0.0060236036 0.0095750000 0.0004560000 0.0039830000 0.0000040000 0.0000030000 0.0012910000 41214925 96830484 509673472 3.9479122162 4.0711665154 3.8568942547 1576 1311867223.0078310966 0.0908448473 0.0873338682 0.1207853556 0.0060244955 0.0081230000 0.0004490000 0.0028480000 0.0000000000 0.0000030000 0.0010030000 41218373 96830484 509673472 3.9477043152 4.0701055527 3.8572521210 1577 1311867223.0454061031 0.0909535512 0.0873361635 0.1207853556 0.0060233438 0.0097610000 0.0004580000 0.0036070000 0.0000040000 0.0000030000 0.0018570000 41222213 96830484 509673472 3.9473078251 4.0719327927 3.8577048779 1578 1311867223.0808250904 0.0903004259 0.0873380420 0.1207853556 0.0060232183 0.0124620000 0.0005450000 0.0042390000 0.0000010000 0.0000080000 0.0011230000 41225997 96830484 509673472 3.9479892254 4.0725293159 3.8580601215 1579 1311867223.1094229221 0.0909719244 0.0873403434 0.1207853556 0.0060228846 0.0108490000 0.0004780000 0.0048020000 0.0000040000 0.0000040000 0.0012650000 41229557 96830484 509673472 3.9466147423 4.0736742020 3.8584532738 1580 1311867223.1473770142 0.0910933837 0.0873427187 0.1207853556 0.0060220089 0.0124420000 0.0005490000 0.0038600000 0.0000020000 0.0000090000 0.0011190000 41233397 96830484 509673472 3.9467399120 4.0758099556 3.8590247631 1581 1311867223.1758580208 0.0915049389 0.0873453514 0.1207853556 0.0060215628 0.0114780000 0.0004770000 0.0048140000 0.0000050000 0.0000050000 0.0018550000 41236957 96830484 509673472 3.9454648495 4.0760049820 3.8592932224 1582 1311867223.2080020905 0.0906655192 0.0873474501 0.1207853556 0.0060199582 0.0093050000 0.0004660000 0.0039960000 0.0000010000 0.0000040000 0.0009930000 41240573 96830484 509673472 3.9456648827 4.0765204430 3.8595900536 1583 1311867223.2450079918 0.0901067108 0.0873491931 0.1207853556 0.0060193998 0.0088190000 0.0004650000 0.0032350000 0.0000040000 0.0000040000 0.0012600000 41244413 96830484 509673472 3.9459002018 4.0782995224 3.8602037430 1584 1311867223.2779359818 0.0902535096 0.0873510267 0.1207853556 0.0060183709 0.0100670000 0.0004570000 0.0047600000 0.0000010000 0.0000040000 0.0009810000 41248141 96830484 509673472 3.9457702637 4.0801453590 3.8609054089 1585 1311867223.3085999489 0.0908488333 0.0873532335 0.1207853556 0.0060170211 0.0086930000 0.0004640000 0.0024940000 0.0000030000 0.0000040000 0.0018370000 41251757 96830484 509673472 3.9442689419 4.0806398392 3.8613379002 1586 1311867223.3452420235 0.0902222693 0.0873550425 0.1207853556 0.0060170097 0.0111070000 0.0005680000 0.0051730000 0.0000010000 0.0000040000 0.0009930000 41255597 96830484 509673472 3.9449088573 4.0833373070 3.8620507717 1587 1311867223.3794689178 0.0888431221 0.0873559801 0.1207853556 0.0060200127 0.0105030000 0.0005170000 0.0047620000 0.0000040000 0.0000040000 0.0012460000 41259269 96830484 509673472 3.9447908401 4.0855474472 3.8624315262 1588 1311867223.4074239731 0.0907021984 0.0873580873 0.1207853556 0.0060209261 0.0101680000 0.0004550000 0.0047720000 0.0000000000 0.0000040000 0.0009720000 41262773 96830484 509673472 3.9433455467 4.0847430229 3.8625719547 1589 1311867223.4458000660 0.0905901790 0.0873601214 0.1207853556 0.0060194470 0.0102010000 0.0004570000 0.0040060000 0.0000040000 0.0000030000 0.0018270000 41266613 96830484 509673472 3.9427790642 4.0844073296 3.8625991344 1590 1311867223.4758329391 0.0903390497 0.0873619949 0.1207853556 0.0060177196 0.0100790000 0.0004570000 0.0047590000 0.0000010000 0.0000040000 0.0009720000 41270285 96830484 509673472 3.9429206848 4.0858335495 3.8624734879 1591 1311867223.5077428818 0.0922209322 0.0873650489 0.1207853556 0.0060175535 0.0104520000 0.0004590000 0.0047660000 0.0000030000 0.0000030000 0.0012470000 41273957 96830484 509673472 3.9394969940 4.0877594948 3.8620676994 1592 1311867223.5466530323 0.0903696045 0.0873669362 0.1207853556 0.0060256022 0.0132880000 0.0005490000 0.0048970000 0.0000010000 0.0000080000 0.0011130000 41277797 96830484 509673472 3.9408152103 4.0873727798 3.8616094589 1593 1311867223.5759539604 0.0913110599 0.0873694121 0.1207853556 0.0060288042 0.0107050000 0.0004810000 0.0040380000 0.0000040000 0.0000040000 0.0018470000 41281469 96830484 509673472 3.9396848679 4.0894579887 3.8611223698 1594 1311867223.6078069210 0.0913641229 0.0873719182 0.1207853556 0.0060269238 0.0082130000 0.0004630000 0.0028660000 0.0000010000 0.0000040000 0.0009770000 41285029 96830484 509673472 3.9390757084 4.0894708633 3.8607902527 1595 1311867223.6502039433 0.0905142128 0.0873738883 0.1207853556 0.0060300525 0.0084600000 0.0004560000 0.0028530000 0.0000040000 0.0000040000 0.0012490000 41289037 96830484 509673472 3.9392259121 4.0900545120 3.8600835800 1596 1311867223.6753880978 0.0904341489 0.0873758058 0.1207853556 0.0060283903 0.0100700000 0.0004550000 0.0047740000 0.0000010000 0.0000040000 0.0009630000 41292485 96830484 509673472 3.9393835068 4.0918612480 3.8597738743 1597 1311867223.7088580132 0.0905931592 0.0873778204 0.1207853556 0.0060267734 0.0110490000 0.0004610000 0.0047600000 0.0000040000 0.0000030000 0.0018140000 41296213 96830484 509673472 3.9388930798 4.0938682556 3.8596789837 1598 1311867223.7452809811 0.0910920277 0.0873801447 0.1207853556 0.0060259950 0.0119520000 0.0005510000 0.0038330000 0.0000010000 0.0000080000 0.0010990000 41300053 96830484 509673472 3.9379606247 4.0951609612 3.8593096733 1599 1311867223.7760720253 0.0908885896 0.0873823388 0.1207853556 0.0060260216 0.0116620000 0.0005540000 0.0027030000 0.0000090000 0.0000100000 0.0013860000 41303669 96830484 509673472 3.9390223026 4.0978584290 3.8592453003 1600 1311867223.8077559471 0.0914147943 0.0873848591 0.1207853556 0.0060241443 0.0106900000 0.0004820000 0.0048490000 0.0000010000 0.0000040000 0.0009850000 41307285 96830484 509673472 3.9385864735 4.0997114182 3.8591239452 1601 1311867223.8438520432 0.0923014954 0.0873879301 0.1207853556 0.0060255920 0.0102110000 0.0004720000 0.0040170000 0.0000040000 0.0000040000 0.0018130000 41311125 96830484 509673472 3.9381895065 4.1014966965 3.8589067459 1602 1311867223.8760919571 0.0927868560 0.0873913002 0.1207853556 0.0060249720 0.0097040000 0.0004770000 0.0044040000 0.0000010000 0.0000040000 0.0009640000 41314797 96830484 509673472 3.9375400543 4.1020503044 3.8586757183 1603 1311867223.9078280926 0.0928605571 0.0873947121 0.1207853556 0.0060233256 0.0105460000 0.0004700000 0.0048070000 0.0000030000 0.0000030000 0.0012350000 41318413 96830484 509673472 3.9381415844 4.1039285660 3.8585703373 1604 1311867223.9491670132 0.0935622826 0.0873985572 0.1207853556 0.0060218105 0.0102020000 0.0004700000 0.0048150000 0.0000000000 0.0000040000 0.0009700000 41322365 96830484 509673472 3.9375238419 4.1052832603 3.8582735062 1605 1311867223.9760739803 0.0927172229 0.0874018710 0.1207853556 0.0060241772 0.0094620000 0.0004620000 0.0032660000 0.0000030000 0.0000030000 0.0018180000 41325925 96830484 509673472 3.9391002655 4.1068162918 3.8579137325 1606 1311867224.0093441010 0.0940962210 0.0874060393 0.1207853556 0.0060270589 0.0101630000 0.0004690000 0.0048200000 0.0000010000 0.0000040000 0.0009590000 41329597 96830484 509673472 3.9378538132 4.1087617874 3.8573317528 1607 1311867224.0470440388 0.0940705538 0.0874101865 0.1207853556 0.0060254244 0.0085040000 0.0004670000 0.0028840000 0.0000040000 0.0000030000 0.0012400000 41333493 96830484 509673472 3.9388146400 4.1100831032 3.8572304249 1608 1311867224.0761411190 0.0941175148 0.0874143578 0.1207853556 0.0060235807 0.0126200000 0.0005610000 0.0046770000 0.0000010000 0.0000080000 0.0010910000 41337053 96830484 509673472 3.9390730858 4.1110706329 3.8568274975 1609 1311867224.1081349850 0.0941106752 0.0874185195 0.1207853556 0.0060220843 0.0099450000 0.0004870000 0.0033250000 0.0000050000 0.0000040000 0.0018090000 41340725 96830484 509673472 3.9398486614 4.1130056381 3.8561463356 1610 1311867224.1458990574 0.0949694216 0.0874232095 0.1207853556 0.0060231895 0.0082470000 0.0004700000 0.0029020000 0.0000010000 0.0000040000 0.0009670000 41344509 96830484 509673472 3.9396774769 4.1153187752 3.8558502197 1611 1311867224.1768929958 0.0948418602 0.0874278145 0.1207853556 0.0060256829 0.0089280000 0.0004690000 0.0032690000 0.0000030000 0.0000030000 0.0012410000 41348181 96830484 509673472 3.9410679340 4.1170248985 3.8554961681 1612 1311867224.2143769264 0.0940576941 0.0874319274 0.1207853556 0.0060242040 0.0102770000 0.0004690000 0.0048190000 0.0000000000 0.0000040000 0.0009660000 41351853 96830484 509673472 3.9425406456 4.1187033653 3.8548195362 1613 1311867224.2470428944 0.0953105465 0.0874368118 0.1207853556 0.0060226171 0.0109960000 0.0004740000 0.0048200000 0.0000030000 0.0000030000 0.0018000000 41355525 96830484 509673472 3.9411427975 4.1207728386 3.8542065620 1614 1311867224.2768630981 0.0976030454 0.0874431106 0.1207853556 0.0060248441 0.0102370000 0.0004750000 0.0048260000 0.0000000000 0.0000040000 0.0009590000 41359085 96830484 509673472 3.9388706684 4.1239209175 3.8539066315 1615 1311867224.3146169186 0.0965817347 0.0874487692 0.1207853556 0.0060262506 0.0131650000 0.0006020000 0.0039150000 0.0000100000 0.0000100000 0.0013670000 41362981 96830484 509673472 3.9409289360 4.1236939430 3.8531703949 1616 1311867224.3456730843 0.0970208123 0.0874546925 0.1207853556 0.0060244931 0.0108330000 0.0004840000 0.0048950000 0.0000000000 0.0000050000 0.0009870000 41366653 96830484 509673472 3.9400632381 4.1257414818 3.8523395061 1617 1311867224.3769209385 0.0973421261 0.0874608072 0.1207853556 0.0060230002 0.0128380000 0.0005940000 0.0031240000 0.0000110000 0.0000090000 0.0020080000 41370213 96830484 509673472 3.9399714470 4.1288323402 3.8518218994 1618 1311867224.4141020775 0.0983776152 0.0874675543 0.1207853556 0.0060237234 0.0093210000 0.0004870000 0.0033230000 0.0000000000 0.0000050000 0.0009920000 41374053 96830484 509673472 3.9388248920 4.1289911270 3.8509979248 1619 1311867224.4464271069 0.0986186415 0.0874744419 0.1207853556 0.0060230105 0.0105340000 0.0004720000 0.0048390000 0.0000040000 0.0000040000 0.0012590000 41377725 96830484 509673472 3.9382903576 4.1307024956 3.8501210213 1620 1311867224.4776859283 0.0985488221 0.0874812779 0.1207853556 0.0060247581 0.0103140000 0.0004780000 0.0048190000 0.0000000000 0.0000030000 0.0009760000 41381341 96830484 509673472 3.9393537045 4.1346554756 3.8497998714 1621 1311867224.5181219578 0.0993255824 0.0874885847 0.1207853556 0.0060306790 0.0091030000 0.0004700000 0.0027860000 0.0000040000 0.0000040000 0.0018280000 41385237 96830484 509673472 3.9386863708 4.1342210770 3.8489573002 1622 1311867224.5470569134 0.0989151224 0.0874956294 0.1207853556 0.0060293191 0.0153820000 0.0006480000 0.0053430000 0.0000020000 0.0000100000 0.0012420000 41388853 96830484 509673472 3.9395329952 4.1343274117 3.8482019901 1623 1311867224.5859119892 0.1011411771 0.0875040371 0.1207853556 0.0060397685 0.0095070000 0.0004900000 0.0029600000 0.0000050000 0.0000040000 0.0012920000 41392749 96830484 509673472 3.9373600483 4.1410079002 3.8479452133 1624 1311867224.6181120872 0.1013135090 0.0875125404 0.1207853556 0.0060381121 0.0086270000 0.0004580000 0.0031740000 0.0000000000 0.0000030000 0.0010070000 41396365 96830484 509673472 3.9366571903 4.1430544853 3.8473067284 1625 1311867224.6502161026 0.0999306589 0.0875201823 0.1207853556 0.0060366914 0.0092140000 0.0004700000 0.0029140000 0.0000030000 0.0000030000 0.0018480000 41400093 96830484 509673472 3.9376740456 4.1417980194 3.8466663361 1626 1311867224.6785190105 0.1006046981 0.0875282294 0.1207853556 0.0060367691 0.0124880000 0.0005530000 0.0035220000 0.0000020000 0.0000100000 0.0011270000 41403597 96830484 509673472 3.9363367558 4.1441688538 3.8464043140 1627 1311867224.7173650265 0.1003195867 0.0875360913 0.1207853556 0.0060379565 0.0096460000 0.0004830000 0.0033310000 0.0000050000 0.0000050000 0.0012760000 41407493 96830484 509673472 3.9375042915 4.1477403641 3.8465259075 1628 1311867224.7520918846 0.1004345119 0.0875440142 0.1207853556 0.0060364138 0.0098810000 0.0004640000 0.0044460000 0.0000010000 0.0000050000 0.0009860000 41411277 96830484 509673472 3.9368596077 4.1481962204 3.8463673592 1629 1311867224.7866261005 0.0997702256 0.0875515195 0.1207853556 0.0060360515 0.0092060000 0.0004670000 0.0029140000 0.0000030000 0.0000030000 0.0018410000 41414949 96830484 509673472 3.9373157024 4.1484856606 3.8460643291 1630 1311867224.8123459816 0.1008412540 0.0875596728 0.1207853556 0.0060383274 0.0082810000 0.0004550000 0.0029030000 0.0000010000 0.0000040000 0.0009930000 41418509 96830484 509673472 3.9360995293 4.1515269279 3.8461687565 1631 1311867224.8458189964 0.1005989462 0.0875676674 0.1207853556 0.0060633106 0.0106650000 0.0004630000 0.0048600000 0.0000040000 0.0000040000 0.0012670000 41422125 96830484 509673472 3.9367327690 4.1539564133 3.8465547562 1632 1311867224.8779430389 0.1012043729 0.0875760232 0.1207853556 0.0060685506 0.0083410000 0.0004530000 0.0029010000 0.0000010000 0.0000040000 0.0009950000 41425741 96830484 509673472 3.9354193211 4.1554350853 3.8465561867 1633 1311867224.9142448902 0.1002138034 0.0875837622 0.1207853556 0.0060728707 0.0104130000 0.0004710000 0.0040760000 0.0000040000 0.0000040000 0.0018450000 41429581 96830484 509673472 3.9376916885 4.1582860947 3.8473300934 1634 1311867224.9471449852 0.1013949141 0.0875922146 0.1207853556 0.0060756247 0.0125300000 0.0005580000 0.0043010000 0.0000010000 0.0000080000 0.0011200000 41433141 96830484 509673472 3.9363501072 4.1599292755 3.8475439548 1635 1311867224.9800488949 0.0987988934 0.0875990688 0.1207853556 0.0060751232 0.0109130000 0.0004780000 0.0048780000 0.0000040000 0.0000040000 0.0012720000 41436925 96830484 509673472 3.9389030933 4.1593437195 3.8475987911 1636 1311867225.0142920017 0.1000082046 0.0876066539 0.1207853556 0.0060761745 0.0103040000 0.0004660000 0.0048400000 0.0000010000 0.0000040000 0.0009900000 41440485 96830484 509673472 3.9375498295 4.1642036438 3.8479290009 1637 1311867225.0493879318 0.1000351757 0.0876142461 0.1207853556 0.0060756915 0.0102740000 0.0005110000 0.0033090000 0.0000030000 0.0000030000 0.0018350000 41444157 96830484 509673472 3.9371490479 4.1677651405 3.8485338688 1638 1311867225.0798690319 0.1003209949 0.0876220036 0.1207853556 0.0060769422 0.0092970000 0.0005020000 0.0036970000 0.0000010000 0.0000040000 0.0009860000 41447829 96830484 509673472 3.9373092651 4.1673479080 3.8491375446 1639 1311867225.1138188839 0.1009893492 0.0876301594 0.1207853556 0.0060767717 0.0098660000 0.0004590000 0.0040720000 0.0000040000 0.0000040000 0.0012640000 41451501 96830484 509673472 3.9369621277 4.1704497337 3.8497753143 1640 1311867225.1472380161 0.1013825983 0.0876385450 0.1207853556 0.0060750441 0.0091880000 0.0004550000 0.0036670000 0.0000000000 0.0000040000 0.0009790000 41455173 96830484 509673472 3.9362940788 4.1730618477 3.8502137661 1641 1311867225.1810939312 0.1017277837 0.0876471308 0.1207853556 0.0060732210 0.0099700000 0.0004570000 0.0036690000 0.0000040000 0.0000040000 0.0018270000 41458957 96830484 509673472 3.9356133938 4.1749734879 3.8504035473 1642 1311867225.2153220177 0.1017806828 0.0876557383 0.1207853556 0.0060715053 0.0103180000 0.0004580000 0.0048100000 0.0000010000 0.0000040000 0.0009780000 41462685 96830484 509673472 3.9356789589 4.1755890846 3.8508052826 1643 1311867225.2483470440 0.1020810679 0.0876645182 0.1207853556 0.0060706296 0.0093590000 0.0004620000 0.0035500000 0.0000030000 0.0000040000 0.0012690000 41466357 96830484 509673472 3.9350111485 4.1775703430 3.8508450985 1644 1311867225.2792909145 0.1011078209 0.0876726954 0.1207853556 0.0060703461 0.0081080000 0.0004540000 0.0025240000 0.0000010000 0.0000040000 0.0009900000 41470029 96830484 509673472 3.9362943172 4.1796808243 3.8510477543 1645 1311867225.3207540512 0.0997925401 0.0876800631 0.1207853556 0.0060692847 0.0093810000 0.0004560000 0.0028850000 0.0000040000 0.0000040000 0.0018460000 41473981 96830484 509673472 3.9380943775 4.1798348427 3.8509759903 1646 1311867225.3462350368 0.0995391086 0.0876872678 0.1207853556 0.0060680477 0.0084580000 0.0004580000 0.0028990000 0.0000000000 0.0000040000 0.0009800000 41477485 96830484 509673472 3.9385185242 4.1814761162 3.8509557247 1647 1311867225.3852069378 0.1004641354 0.0876950255 0.1207853556 0.0060663297 0.0093850000 0.0004600000 0.0036710000 0.0000040000 0.0000030000 0.0012710000 41481325 96830484 509673472 3.9368338585 4.1839327812 3.8509430885 1648 1311867225.4130129814 0.1002139300 0.0877026219 0.1207853556 0.0060645045 0.0099580000 0.0004590000 0.0044420000 0.0000000000 0.0000040000 0.0009770000 41484829 96830484 509673472 3.9369833469 4.1848268509 3.8509500027 1649 1311867225.4504270554 0.0997573733 0.0877099322 0.1207853556 0.0060628878 0.0105650000 0.0004660000 0.0040540000 0.0000030000 0.0000030000 0.0018460000 41488725 96830484 509673472 3.9369552135 4.1858248711 3.8504819870 1650 1311867225.4842948914 0.1002936587 0.0877175588 0.1207853556 0.0060617994 0.0104450000 0.0004520000 0.0048290000 0.0000000000 0.0000030000 0.0009800000 41492397 96830484 509673472 3.9357674122 4.1875920296 3.8501775265 1651 1311867225.5163919926 0.0997002721 0.0877248166 0.1207853556 0.0060607390 0.0106470000 0.0004580000 0.0048480000 0.0000040000 0.0000040000 0.0012670000 41496125 96830484 509673472 3.9363629818 4.1873569489 3.8498680592 1652 1311867225.5493750572 0.0994547978 0.0877319171 0.1207853556 0.0060622889 0.0089010000 0.0004550000 0.0032890000 0.0000010000 0.0000040000 0.0010040000 41499741 96830484 509673472 3.9364621639 4.1902570724 3.8493883610 1653 1311867225.5882349014 0.1007117406 0.0877397694 0.1207853556 0.0060610586 0.0097560000 0.0004670000 0.0032810000 0.0000030000 0.0000030000 0.0018620000 41503581 96830484 509673472 3.9329683781 4.1931352615 3.8483943939 1654 1311867225.6179010868 0.1007587761 0.0877476406 0.1207853556 0.0060603956 0.0084210000 0.0004660000 0.0028960000 0.0000010000 0.0000040000 0.0009910000 41507197 96830484 509673472 3.9322676659 4.1919145584 3.8474540710 1655 1311867225.6461288929 0.1006768122 0.0877554528 0.1207853556 0.0060589947 0.0107190000 0.0004610000 0.0048430000 0.0000030000 0.0000040000 0.0012690000 41510757 96830484 509673472 3.9311273098 4.1923274994 3.8458848000 1656 1311867225.6847119331 0.1017998233 0.0877639337 0.1207853556 0.0060573980 0.0080800000 0.0004540000 0.0025130000 0.0000010000 0.0000040000 0.0010110000 41514653 96830484 509673472 3.9286170006 4.1951913834 3.8450992107 1657 1311867225.7160770893 0.1006503254 0.0877717106 0.1207853556 0.0060569170 0.0093130000 0.0004580000 0.0028950000 0.0000040000 0.0000040000 0.0018750000 41518325 96830484 509673472 3.9296970367 4.1960625648 3.8439965248 1658 1311867225.7506299019 0.1019816101 0.0877802811 0.1207853556 0.0060595888 0.0090880000 0.0004580000 0.0035310000 0.0000010000 0.0000040000 0.0009980000 41522053 96830484 509673472 3.9273962975 4.1975440979 3.8428540230 1659 1311867225.7872900963 0.1024668813 0.0877891338 0.1207853556 0.0060613936 0.0086850000 0.0004550000 0.0028680000 0.0000030000 0.0000030000 0.0012860000 41525781 96830484 509673472 3.9274473190 4.2027645111 3.8422422409 1660 1311867225.8170781136 0.1028013527 0.0877981773 0.1207853556 0.0060628765 0.0118540000 0.0005430000 0.0030750000 0.0000010000 0.0000080000 0.0011350000 41529341 96830484 509673472 3.9246087074 4.2019357681 3.8407411575 1661 1311867225.8520019054 0.1035602167 0.0878076668 0.1207853556 0.0060663518 0.0103360000 0.0004650000 0.0032940000 0.0000040000 0.0000050000 0.0018970000 41533181 96830484 509673472 3.9229943752 4.2028923035 3.8399696350 1662 1311867225.8862910271 0.1044736952 0.0878176945 0.1207853556 0.0060685167 0.0139460000 0.0005560000 0.0050690000 0.0000010000 0.0000080000 0.0011430000 41536909 96830484 509673472 3.9221370220 4.2053532600 3.8397316933 1663 1311867225.9177930355 0.1043862775 0.0878276576 0.1207853556 0.0060667942 0.0099400000 0.0004620000 0.0032890000 0.0000040000 0.0000040000 0.0012920000 41540525 96830484 509673472 3.9218549728 4.2064528465 3.8391733170 1664 1311867225.9504909515 0.1022209227 0.0878363074 0.1207853556 0.0060682921 0.0104710000 0.0005060000 0.0048030000 0.0000010000 0.0000040000 0.0010110000 41544253 96830484 509673472 3.9236233234 4.2058701515 3.8382265568 1665 1311867225.9852480888 0.1024713144 0.0878450972 0.1207853556 0.0060676124 0.0101060000 0.0004520000 0.0036380000 0.0000040000 0.0000030000 0.0018800000 41548037 96830484 509673472 3.9237852097 4.2076487541 3.8381474018 1666 1311867226.0173718929 0.1022116616 0.0878537205 0.1207853556 0.0060661058 0.0084550000 0.0004490000 0.0028740000 0.0000010000 0.0000040000 0.0010150000 41551709 96830484 509673472 3.9235363007 4.2079000473 3.8372101784 1667 1311867226.0511479378 0.1032494158 0.0878629561 0.1207853556 0.0060655389 0.0091280000 0.0004520000 0.0032520000 0.0000030000 0.0000030000 0.0012960000 41555381 96830484 509673472 3.9214947224 4.2103428841 3.8365283012 1668 1311867226.0877819061 0.1045631841 0.0878729682 0.1207853556 0.0060687789 0.0088840000 0.0004530000 0.0032650000 0.0000000000 0.0000030000 0.0010030000 41559165 96830484 509673472 3.9198093414 4.2142605782 3.8364465237 1669 1311867226.1182270050 0.1026776507 0.0878818386 0.1207853556 0.0060789712 0.0108950000 0.0004580000 0.0044210000 0.0000040000 0.0000040000 0.0018840000 41562837 96830484 509673472 3.9211244583 4.2121648788 3.8356003761 1670 1311867226.1477489471 0.1012181714 0.0878898245 0.1207853556 0.0060774882 0.0103410000 0.0004550000 0.0047830000 0.0000000000 0.0000040000 0.0010060000 41566397 96830484 509673472 3.9232523441 4.2139105797 3.8351800442 1671 1311867226.1833140850 0.1023551077 0.0878984811 0.1207853556 0.0060760543 0.0090630000 0.0004510000 0.0032550000 0.0000030000 0.0000030000 0.0012850000 41570181 96830484 509673472 3.9224212170 4.2175879478 3.8355476856 1672 1311867226.2166810036 0.1014587060 0.0879065913 0.1207853556 0.0060748041 0.0088030000 0.0004550000 0.0032590000 0.0000010000 0.0000040000 0.0010050000 41573853 96830484 509673472 3.9232008457 4.2170205116 3.8349885941 1673 1311867226.2487111092 0.1016251296 0.0879147913 0.1207853556 0.0060743216 0.0093980000 0.0004550000 0.0028730000 0.0000040000 0.0000040000 0.0018850000 41577581 96830484 509673472 3.9230132103 4.2194290161 3.8345625401 1674 1311867226.2829930782 0.1024429202 0.0879234700 0.1207853556 0.0060732703 0.0118850000 0.0005480000 0.0030750000 0.0000010000 0.0000080000 0.0011370000 41581309 96830484 509673472 3.9226217270 4.2211036682 3.8341779709 1675 1311867226.3211309910 0.1025552005 0.0879322053 0.1207853556 0.0060714673 0.0100020000 0.0004620000 0.0036800000 0.0000050000 0.0000040000 0.0012930000 41585205 96830484 509673472 3.9227745533 4.2224440575 3.8335704803 1676 1311867226.3455820084 0.1043729484 0.0879420148 0.1207853556 0.0060726948 0.0104570000 0.0004470000 0.0047860000 0.0000000000 0.0000030000 0.0010110000 41588597 96830484 509673472 3.9208621979 4.2264547348 3.8336703777 1677 1311867226.3873078823 0.1026932225 0.0879508110 0.1207853556 0.0060718648 0.0101630000 0.0004520000 0.0036430000 0.0000040000 0.0000040000 0.0018920000 41592605 96830484 509673472 3.9232339859 4.2275452614 3.8333675861 1678 1311867226.4188749790 0.1024819836 0.0879594708 0.1207853556 0.0060702155 0.0084820000 0.0004500000 0.0028800000 0.0000010000 0.0000040000 0.0010030000 41596221 96830484 509673472 3.9232628345 4.2296686172 3.8329794407 1679 1311867226.4472739697 0.1021362022 0.0879679144 0.1207853556 0.0060687254 0.0105760000 0.0004530000 0.0046700000 0.0000030000 0.0000030000 0.0012800000 41599837 96830484 509673472 3.9238681793 4.2308778763 3.8328292370 1680 1311867226.4849569798 0.1030908749 0.0879769162 0.1207853556 0.0060678799 0.0084450000 0.0004540000 0.0028910000 0.0000010000 0.0000030000 0.0010070000 41603621 96830484 509673472 3.9224419594 4.2323188782 3.8323307037 1681 1311867226.5167839527 0.1035726964 0.0879861938 0.1207853556 0.0060668608 0.0131380000 0.0005640000 0.0031110000 0.0000130000 0.0000110000 0.0020760000 41607237 96830484 509673472 3.9222486019 4.2343864441 3.8320004940 1682 1311867226.5462191105 0.1032731086 0.0879952824 0.1207853556 0.0060661231 0.0140880000 0.0005760000 0.0050720000 0.0000010000 0.0000080000 0.0011430000 41610853 96830484 509673472 3.9212417603 4.2335739136 3.8309211731 1683 1311867226.5842289925 0.1025793031 0.0880039479 0.1207853556 0.0060653868 0.0097900000 0.0004830000 0.0033060000 0.0000050000 0.0000050000 0.0013010000 41614693 96830484 509673472 3.9230556488 4.2367916107 3.8310637474 1684 1311867226.6149599552 0.1036272272 0.0880132253 0.1207853556 0.0060636437 0.0092580000 0.0004520000 0.0036560000 0.0000000000 0.0000040000 0.0010090000 41618309 96830484 509673472 3.9213089943 4.2379617691 3.8307809830 1685 1311867226.6545290947 0.1031583473 0.0880222135 0.1207853556 0.0060621830 0.0112850000 0.0004560000 0.0047970000 0.0000040000 0.0000030000 0.0018900000 41622205 96830484 509673472 3.9216713905 4.2380113602 3.8302016258 1686 1311867226.6802148819 0.1026661322 0.0880308991 0.1207853556 0.0060611912 0.0084910000 0.0004530000 0.0028780000 0.0000010000 0.0000040000 0.0010000000 41625709 96830484 509673472 3.9221241474 4.2392601967 3.8300175667 1687 1311867226.7142350674 0.1030757725 0.0880398173 0.1207853556 0.0060605503 0.0090310000 0.0004610000 0.0029990000 0.0000040000 0.0000040000 0.0012970000 41629437 96830484 509673472 3.9225091934 4.2402663231 3.8295845985 1688 1311867226.7506589890 0.1033323780 0.0880488768 0.1207853556 0.0060622882 0.0089770000 0.0004530000 0.0032850000 0.0000000000 0.0000030000 0.0010070000 41633221 96830484 509673472 3.9214475155 4.2393050194 3.8289573193 1689 1311867226.7818078995 0.1024252325 0.0880573886 0.1207853556 0.0060615608 0.0106630000 0.0004550000 0.0040260000 0.0000040000 0.0000030000 0.0019230000 41636893 96830484 509673472 3.9234390259 4.2419567108 3.8287889957 1690 1311867226.8133080006 0.1026920006 0.0880660481 0.1207853556 0.0060617458 0.0104570000 0.0004590000 0.0048020000 0.0000000000 0.0000040000 0.0009910000 41640509 96830484 509673472 3.9233291149 4.2448234558 3.8287513256 1691 1311867226.8513610363 0.1015242636 0.0880740069 0.1207853556 0.0060604995 0.0092110000 0.0004590000 0.0032610000 0.0000040000 0.0000040000 0.0012790000 41644349 96830484 509673472 3.9242272377 4.2439608574 3.8280336857 1692 1311867226.8838679790 0.1021335199 0.0880823163 0.1207853556 0.0060639123 0.0081510000 0.0004580000 0.0024970000 0.0000000000 0.0000050000 0.0010090000 41648021 96830484 509673472 3.9227836132 4.2441663742 3.8275594711 1693 1311867226.9181559086 0.1018380076 0.0880904413 0.1207853556 0.0060625205 0.0093590000 0.0004580000 0.0028670000 0.0000030000 0.0000040000 0.0018660000 41651749 96830484 509673472 3.9235458374 4.2460498810 3.8273594379 1694 1311867226.9514899254 0.1028834954 0.0880991739 0.1207853556 0.0060611344 0.0104640000 0.0004530000 0.0047820000 0.0000010000 0.0000040000 0.0010040000 41655477 96830484 509673472 3.9213345051 4.2454547882 3.8266897202 1695 1311867226.9810149670 0.1022607237 0.0881075288 0.1207853556 0.0060594716 0.0088120000 0.0004520000 0.0028570000 0.0000040000 0.0000040000 0.0012920000 41659149 96830484 509673472 3.9224116802 4.2472643852 3.8263807297 1696 1311867227.0125620365 0.1012047902 0.0881152513 0.1207853556 0.0060583033 0.0125620000 0.0005580000 0.0030990000 0.0000010000 0.0000110000 0.0011430000 41662709 96830484 509673472 3.9241328239 4.2495756149 3.8260931969 1697 1311867227.0480670929 0.1015126482 0.0881231460 0.1207853556 0.0060598536 0.0097260000 0.0004760000 0.0025220000 0.0000050000 0.0000050000 0.0018870000 41666549 96830484 509673472 3.9229493141 4.2500143051 3.8254945278 1698 1311867227.0861930847 0.1025844738 0.0881316627 0.1207853556 0.0060620336 0.0104350000 0.0004560000 0.0047800000 0.0000010000 0.0000040000 0.0010020000 41670221 96830484 509673472 3.9211304188 4.2518286705 3.8257017136 1699 1311867227.1158189774 0.1020136029 0.0881398333 0.1207853556 0.0060617171 0.0087910000 0.0004610000 0.0028810000 0.0000040000 0.0000040000 0.0012890000 41673781 96830484 509673472 3.9228646755 4.2546610832 3.8260984421 1700 1311867227.1503999233 0.1026904583 0.0881483925 0.1207853556 0.0060636950 0.0077750000 0.0004550000 0.0021230000 0.0000000000 0.0000040000 0.0010170000 41677565 96830484 509673472 3.9215784073 4.2546930313 3.8263819218 1701 1311867227.1841590405 0.1027734950 0.0881569905 0.1207853556 0.0060621821 0.0138600000 0.0005650000 0.0031070000 0.0000100000 0.0000100000 0.0022280000 41681293 96830484 509673472 3.9214799404 4.2575974464 3.8266038895 1702 1311867227.2148449421 0.1035581455 0.0881660393 0.1207853556 0.0060607377 0.0131210000 0.0005490000 0.0050230000 0.0000010000 0.0000080000 0.0011040000 41684853 96830484 509673472 3.9207723141 4.2591099739 3.8269484043 1703 1311867227.2480258942 0.1033222601 0.0881749391 0.1207853556 0.0060607686 0.0096620000 0.0004870000 0.0033050000 0.0000040000 0.0000040000 0.0012920000 41688581 96830484 509673472 3.9204971790 4.2584133148 3.8268296719 1704 1311867227.2819800377 0.1035670638 0.0881839720 0.1207853556 0.0060628865 0.0093450000 0.0004610000 0.0036330000 0.0000000000 0.0000040000 0.0010020000 41692309 96830484 509673472 3.9205281734 4.2609882355 3.8273088932 1705 1311867227.3152499199 0.1029445007 0.0881926292 0.1207853556 0.0060622823 0.0094310000 0.0004590000 0.0028940000 0.0000030000 0.0000030000 0.0018810000 41696037 96830484 509673472 3.9206724167 4.2606921196 3.8272109032 1706 1311867227.3479840755 0.1039112732 0.0882018429 0.1207853556 0.0060611160 0.0081230000 0.0004570000 0.0024960000 0.0000000000 0.0000040000 0.0009950000 41699709 96830484 509673472 3.9193415642 4.2635555267 3.8276343346 1707 1311867227.3841071129 0.1031717658 0.0882106127 0.1207853556 0.0060640651 0.0107770000 0.0004590000 0.0048020000 0.0000030000 0.0000030000 0.0012750000 41703493 96830484 509673472 3.9194526672 4.2631740570 3.8275997639 1708 1311867227.4141440392 0.1031871140 0.0882193811 0.1207853556 0.0060667530 0.0089840000 0.0004560000 0.0032750000 0.0000000000 0.0000040000 0.0009990000 41707109 96830484 509673472 3.9190125465 4.2642812729 3.8275704384 1709 1311867227.4479200840 0.1037063971 0.0882284431 0.1207853556 0.0060685497 0.0113290000 0.0004590000 0.0046720000 0.0000030000 0.0000030000 0.0018620000 41710837 96830484 509673472 3.9183969498 4.2665157318 3.8278629780 1710 1311867227.4818758965 0.1033017039 0.0882372579 0.1207853556 0.0060675005 0.0128530000 0.0005720000 0.0033960000 0.0000010000 0.0000120000 0.0011260000 41714621 96830484 509673472 3.9185163975 4.2655143738 3.8276331425 1711 1311867227.5169329643 0.1037417799 0.0882463196 0.1207853556 0.0060663568 0.0112620000 0.0004920000 0.0048420000 0.0000040000 0.0000040000 0.0012980000 41718293 96830484 509673472 3.9173052311 4.2659850121 3.8273046017 1712 1311867227.5501220226 0.1046781912 0.0882559176 0.1207853556 0.0060650882 0.0093630000 0.0004560000 0.0036280000 0.0000000000 0.0000030000 0.0009940000 41722021 96830484 509673472 3.9154694080 4.2668895721 3.8271713257 1713 1311867227.5819540024 0.1045703590 0.0882654415 0.1207853556 0.0060634694 0.0127750000 0.0005570000 0.0027150000 0.0000110000 0.0000100000 0.0020620000 41725749 96830484 509673472 3.9157426357 4.2679119110 3.8272624016 1714 1311867227.6162750721 0.1042233482 0.0882747519 0.1207853556 0.0060649352 0.0111380000 0.0005060000 0.0048510000 0.0000000000 0.0000050000 0.0010110000 41729421 96830484 509673472 3.9164047241 4.2692232132 3.8275430202 1715 1311867227.6503078938 0.1044576988 0.0882841880 0.1207853556 0.0060781195 0.0092560000 0.0005060000 0.0025010000 0.0000030000 0.0000030000 0.0014530000 41733205 96830484 509673472 3.9156682491 4.2698502541 3.8276121616 1716 1311867227.6823980808 0.1049802229 0.0882939176 0.1207853556 0.0060764574 0.0091760000 0.0004620000 0.0032740000 0.0000010000 0.0000050000 0.0009980000 41736877 96830484 509673472 3.9142267704 4.2686338425 3.8274750710 1717 1311867227.7135930061 0.1046287641 0.0883034312 0.1207853556 0.0060768841 0.0114440000 0.0004580000 0.0047950000 0.0000030000 0.0000030000 0.0018700000 41740437 96830484 509673472 3.9155349731 4.2714600563 3.8280713558 1718 1311867227.7496368885 0.1041509137 0.0883126556 0.1207853556 0.0060751987 0.0085700000 0.0004590000 0.0029040000 0.0000010000 0.0000040000 0.0009920000 41744277 96830484 509673472 3.9163806438 4.2725057602 3.8285777569 1719 1311867227.7827620506 0.1043576151 0.0883219895 0.1207853556 0.0060736377 0.0122060000 0.0005530000 0.0023000000 0.0000100000 0.0000100000 0.0015490000 41748005 96830484 509673472 3.9154808521 4.2729926109 3.8284497261 1720 1311867227.8141551018 0.1041749418 0.0883312063 0.1207853556 0.0060735570 0.0111050000 0.0004810000 0.0048360000 0.0000000000 0.0000050000 0.0010070000 41751621 96830484 509673472 3.9168362617 4.2749648094 3.8292670250 1721 1311867227.8497691154 0.1042196527 0.0883404384 0.1207853556 0.0060749927 0.0129340000 0.0005530000 0.0027230000 0.0000100000 0.0000100000 0.0020620000 41755405 96830484 509673472 3.9171743393 4.2761445045 3.8299081326 1722 1311867227.8832869530 0.1029436365 0.0883489188 0.1207853556 0.0060735702 0.0110460000 0.0004880000 0.0048550000 0.0000010000 0.0000040000 0.0010040000 41759077 96830484 509673472 3.9199972153 4.2770490646 3.8305430412 1723 1311867227.9196939468 0.1030938700 0.0883574765 0.1207853556 0.0060719443 0.0096580000 0.0004700000 0.0036430000 0.0000040000 0.0000030000 0.0012940000 41762917 96830484 509673472 3.9203934669 4.2777075768 3.8307886124 1724 1311867227.9516780376 0.1031195968 0.0883660392 0.1207853556 0.0060711247 0.0082310000 0.0004680000 0.0025100000 0.0000010000 0.0000050000 0.0009860000 41766589 96830484 509673472 3.9211177826 4.2796254158 3.8308281898 1725 1311867227.9828588963 0.1050037816 0.0883756843 0.1207853556 0.0060698627 0.0114340000 0.0004630000 0.0048170000 0.0000030000 0.0000030000 0.0018750000 41770261 96830484 509673472 3.9189889431 4.2808041573 3.8313865662 1726 1311867228.0181910992 0.1060786918 0.0883859410 0.1207853556 0.0060684483 0.0101230000 0.0004610000 0.0044200000 0.0000000000 0.0000030000 0.0009840000 41773989 96830484 509673472 3.9178328514 4.2822976112 3.8316643238 1727 1311867228.0516328812 0.1057482660 0.0883959944 0.1207853556 0.0060668758 0.0103680000 0.0004610000 0.0044470000 0.0000040000 0.0000040000 0.0012750000 41777717 96830484 509673472 3.9193255901 4.2841629982 3.8320145607 1728 1311867228.0825328827 0.1055058464 0.0884058960 0.1207853556 0.0060654309 0.0086990000 0.0004700000 0.0029040000 0.0000000000 0.0000040000 0.0009870000 41781333 96830484 509673472 3.9203169346 4.2851872444 3.8324017525 1729 1311867228.1179840565 0.1050189734 0.0884155044 0.1207853556 0.0060644610 0.0115500000 0.0004730000 0.0048080000 0.0000030000 0.0000040000 0.0018820000 41785061 96830484 509673472 3.9214529991 4.2860465050 3.8323798180 1730 1311867228.1511390209 0.1053325012 0.0884252831 0.1207853556 0.0060641098 0.0168330000 0.0006440000 0.0037090000 0.0000010000 0.0000160000 0.0014870000 41788845 96830484 509673472 3.9225106239 4.2879261971 3.8329422474 1731 1311867228.1828610897 0.1051646098 0.0884349534 0.1207853556 0.0060624637 0.0118290000 0.0005060000 0.0047680000 0.0000060000 0.0000050000 0.0012930000 41792517 96830484 509673472 3.9233591557 4.2891211510 3.8328340054 1732 1311867228.2179419994 0.1052659824 0.0884446711 0.1207853556 0.0060676629 0.0086570000 0.0004700000 0.0029080000 0.0000010000 0.0000040000 0.0009950000 41796189 96830484 509673472 3.9242000580 4.2896413803 3.8329925537 1733 1311867228.2541251183 0.1057896167 0.0884546797 0.1207853556 0.0060736520 0.0133520000 0.0005580000 0.0031200000 0.0000120000 0.0000110000 0.0020420000 41800029 96830484 509673472 3.9236431122 4.2906179428 3.8325943947 1734 1311867228.2826519012 0.1063817888 0.0884650183 0.1207853556 0.0060719883 0.0143020000 0.0005810000 0.0051110000 0.0000010000 0.0000080000 0.0011190000 41803589 96830484 509673472 3.9227502346 4.2919802666 3.8325233459 1735 1311867228.3181738853 0.1069597155 0.0884756780 0.1207853556 0.0060707762 0.0091640000 0.0004850000 0.0025460000 0.0000050000 0.0000040000 0.0012960000 41807373 96830484 509673472 3.9220123291 4.2922835350 3.8325026035 1736 1311867228.3504519463 0.1075349748 0.0884866569 0.1207853556 0.0060692243 0.0101770000 0.0004640000 0.0044400000 0.0000000000 0.0000040000 0.0009900000 41811045 96830484 509673472 3.9217035770 4.2940740585 3.8326206207 1737 1311867228.3824779987 0.1071413159 0.0884973965 0.1207853556 0.0060676440 0.0091710000 0.0004650000 0.0025250000 0.0000030000 0.0000030000 0.0018820000 41814773 96830484 509673472 3.9228329659 4.2954416275 3.8327176571 1738 1311867228.4176759720 0.1067593545 0.0885079039 0.1207853556 0.0060660716 0.0082310000 0.0004650000 0.0025140000 0.0000010000 0.0000040000 0.0010030000 41818445 96830484 509673472 3.9233822823 4.2954292297 3.8326566219 1739 1311867228.4483039379 0.1062486991 0.0885181057 0.1207853556 0.0060653577 0.0107610000 0.0005330000 0.0040700000 0.0000040000 0.0000040000 0.0012930000 41822117 96830484 509673472 3.9241588116 4.2961964607 3.8326098919 1740 1311867228.4835319519 0.1061950102 0.0885282648 0.1207853556 0.0060638371 0.0083330000 0.0005140000 0.0025190000 0.0000000000 0.0000040000 0.0009820000 41825845 96830484 509673472 3.9242749214 4.2959470749 3.8324880600 1741 1311867228.5177900791 0.1072312593 0.0885390075 0.1207853556 0.0060647096 0.0115800000 0.0004730000 0.0048350000 0.0000030000 0.0000040000 0.0018670000 41829573 96830484 509673472 3.9231228828 4.2957520485 3.8325963020 1742 1311867228.5529639721 0.1074903086 0.0885498865 0.1207853556 0.0060631342 0.0087180000 0.0004680000 0.0029080000 0.0000010000 0.0000040000 0.0009780000 41833357 96830484 509673472 3.9220862389 4.2946434021 3.8319387436 1743 1311867228.5834119320 0.1079308018 0.0885610058 0.1207853556 0.0060614177 0.0085770000 0.0004700000 0.0025190000 0.0000040000 0.0000040000 0.0012760000 41836973 96830484 509673472 3.9214608669 4.2943892479 3.8316342831 1744 1311867228.6168839931 0.1080045775 0.0885721546 0.1207853556 0.0060601985 0.0086830000 0.0004830000 0.0029160000 0.0000000000 0.0000040000 0.0009920000 41840757 96830484 509673472 3.9210355282 4.2927217484 3.8311610222 1745 1311867228.6513540745 0.1072755530 0.0885828729 0.1207853556 0.0060589165 0.0111970000 0.0004550000 0.0044670000 0.0000040000 0.0000040000 0.0018700000 41844429 96830484 509673472 3.9214315414 4.2912187576 3.8302636147 1746 1311867228.6960909367 0.1075577140 0.0885937405 0.1207853556 0.0060572285 0.0090640000 0.0004610000 0.0033190000 0.0000000000 0.0000040000 0.0009820000 41848493 96830484 509673472 3.9208858013 4.2895298004 3.8295950890 1747 1311867228.7251129150 0.1083624735 0.0886050563 0.1207853556 0.0060560995 0.0086260000 0.0004610000 0.0025350000 0.0000040000 0.0000040000 0.0012850000 41851997 96830484 509673472 3.9176690578 4.2885046005 3.8285181522 1748 1311867228.7533209324 0.1083547026 0.0886163548 0.1207853556 0.0060545607 0.0124980000 0.0005510000 0.0031530000 0.0000010000 0.0000090000 0.0011330000 41855445 96830484 509673472 3.9176902771 4.2888178825 3.8281867504 1749 1311867228.7872729301 0.1075782776 0.0886271964 0.1207853556 0.0060607035 0.0101810000 0.0004700000 0.0029700000 0.0000040000 0.0000040000 0.0018890000 41858893 96830484 509673472 3.9181201458 4.2866888046 3.8276367188 1750 1311867228.8184990883 0.1086412743 0.0886386330 0.1207853556 0.0060646777 0.0107030000 0.0004590000 0.0048810000 0.0000010000 0.0000040000 0.0009960000 41862509 96830484 509673472 3.9162423611 4.2855772972 3.8268449306 1751 1311867228.8512189388 0.1081926599 0.0886498003 0.1207853556 0.0060632114 0.0086000000 0.0004600000 0.0025510000 0.0000050000 0.0000040000 0.0012850000 41866237 96830484 509673472 3.9159553051 4.2861418724 3.8264775276 1752 1311867228.8835051060 0.1083082855 0.0886610209 0.1207853556 0.0060618549 0.0092460000 0.0004580000 0.0033210000 0.0000000000 0.0000050000 0.0009890000 41869853 96830484 509673472 3.9155881405 4.2835302353 3.8260025978 1753 1311867228.9181449413 0.1080207005 0.0886720647 0.1207853556 0.0060601735 0.0104960000 0.0004590000 0.0037160000 0.0000040000 0.0000030000 0.0018630000 41873637 96830484 509673472 3.9156920910 4.2814197540 3.8251776695 1754 1311867228.9496490955 0.1082122400 0.0886832050 0.1207853556 0.0060587693 0.0089110000 0.0004640000 0.0029270000 0.0000010000 0.0000040000 0.0009960000 41877309 96830484 509673472 3.9149291515 4.2821712494 3.8244793415 1755 1311867228.9844760895 0.1082813665 0.0886943721 0.1207853556 0.0060574200 0.0109200000 0.0004560000 0.0047500000 0.0000040000 0.0000030000 0.0012870000 41881037 96830484 509673472 3.9144315720 4.2793779373 3.8240849972 1756 1311867229.0238449574 0.1079368740 0.0887053302 0.1207853556 0.0060560492 0.0107580000 0.0004520000 0.0048800000 0.0000000000 0.0000030000 0.0009900000 41884933 96830484 509673472 3.9145839214 4.2761411667 3.8233613968 1757 1311867229.0509281158 0.1087657958 0.0887167476 0.1207853556 0.0060550635 0.0116600000 0.0004510000 0.0048620000 0.0000030000 0.0000030000 0.0018800000 41888493 96830484 509673472 3.9130105972 4.2766680717 3.8228402138 1758 1311867229.0874319077 0.1087142900 0.0887281228 0.1207853556 0.0060541007 0.0084080000 0.0004510000 0.0025310000 0.0000010000 0.0000040000 0.0010000000 41892221 96830484 509673472 3.9130227566 4.2754292488 3.8226835728 1759 1311867229.1218080521 0.1081521064 0.0887391654 0.1207853556 0.0060528239 0.0106100000 0.0004540000 0.0044670000 0.0000030000 0.0000030000 0.0012870000 41896005 96830484 509673472 3.9138116837 4.2731118202 3.8224532604 1760 1311867229.1517140865 0.1088149622 0.0887505721 0.1207853556 0.0060531035 0.0221680000 0.0006570000 0.0053830000 0.0000010000 0.0000160000 0.0015180000 41899677 96830484 509673472 3.9122405052 4.2707028389 3.8219587803 1761 1311867229.1890540123 0.1091112867 0.0887621342 0.1207853556 0.0060522501 0.0112440000 0.0004930000 0.0029980000 0.0000080000 0.0000070000 0.0019090000 41903461 96830484 509673472 3.9120030403 4.2701082230 3.8217275143 1762 1311867229.2214341164 0.1097875014 0.0887740668 0.1207853556 0.0060510429 0.0203370000 0.0006460000 0.0037540000 0.0000020000 0.0000160000 0.0015170000 41907133 96830484 509673472 3.9109947681 4.2677183151 3.8218569756 1763 1311867229.2532980442 0.1092374921 0.0887856740 0.1207853556 0.0060523115 0.0110770000 0.0004940000 0.0034010000 0.0000060000 0.0000050000 0.0013220000 41910805 96830484 509673472 3.9115278721 4.2653937340 3.8211724758 1764 1311867229.2841351032 0.1082678586 0.0887967183 0.1207853556 0.0060507737 0.0107430000 0.0004620000 0.0048450000 0.0000000000 0.0000040000 0.0010230000 41914421 96830484 509673472 3.9130880833 4.2645497322 3.8208312988 1765 1311867229.3193020821 0.1092148349 0.0888082867 0.1207853556 0.0060519789 0.0092390000 0.0004600000 0.0025030000 0.0000040000 0.0000030000 0.0018910000 41918205 96830484 509673472 3.9110019207 4.2626061440 3.8202495575 1766 1311867229.3502240181 0.1086986810 0.0888195496 0.1207853556 0.0060520482 0.0105790000 0.0004570000 0.0047180000 0.0000010000 0.0000040000 0.0010100000 41921821 96830484 509673472 3.9117040634 4.2598609924 3.8196387291 1767 1311867229.3850710392 0.1083682477 0.0888306128 0.1207853556 0.0060508916 0.0109510000 0.0004540000 0.0048350000 0.0000040000 0.0000040000 0.0013000000 41925549 96830484 509673472 3.9119224548 4.2582182884 3.8188908100 1768 1311867229.4180469513 0.1090032384 0.0888420227 0.1207853556 0.0060506787 0.0144400000 0.0005470000 0.0051030000 0.0000000000 0.0000080000 0.0011530000 41929221 96830484 509673472 3.9113073349 4.2571721077 3.8186757565 1769 1311867229.4483740330 0.1077312082 0.0888527006 0.1207853556 0.0060495998 0.0104920000 0.0004690000 0.0033160000 0.0000050000 0.0000040000 0.0019090000 41932837 96830484 509673472 3.9124212265 4.2539963722 3.8179626465 1770 1311867229.4843358994 0.1070563346 0.0888629851 0.1207853556 0.0060538450 0.0092170000 0.0004560000 0.0032780000 0.0000010000 0.0000040000 0.0010160000 41936621 96830484 509673472 3.9130368233 4.2512755394 3.8171844482 1771 1311867229.5189929008 0.1075404212 0.0888735314 0.1207853556 0.0060526584 0.0092640000 0.0004560000 0.0031480000 0.0000030000 0.0000030000 0.0013100000 41940293 96830484 509673472 3.9117007256 4.2490420341 3.8162238598 1772 1311867229.5504579544 0.1085450128 0.0888846327 0.1207853556 0.0060511615 0.0088080000 0.0004550000 0.0028950000 0.0000010000 0.0000040000 0.0010230000 41943965 96830484 509673472 3.9092996120 4.2462038994 3.8154304028 1773 1311867229.5853381157 0.1077620983 0.0888952799 0.1207853556 0.0060504501 0.0100370000 0.0004510000 0.0032680000 0.0000030000 0.0000030000 0.0019060000 41947693 96830484 509673472 3.9100649357 4.2458705902 3.8147823811 1774 1311867229.6182799339 0.1078676134 0.0889059745 0.1207853556 0.0060488183 0.0107560000 0.0004530000 0.0047940000 0.0000000000 0.0000040000 0.0010270000 41951365 96830484 509673472 3.9094219208 4.2435159683 3.8143658638 1775 1311867229.6503160000 0.1073825508 0.0889163839 0.1207853556 0.0060471422 0.0095860000 0.0004490000 0.0032730000 0.0000040000 0.0000040000 0.0013120000 41955093 96830484 509673472 3.9101128578 4.2418169975 3.8141145706 1776 1311867229.6876978874 0.1086025089 0.0889274684 0.1207853556 0.0060458870 0.0091530000 0.0004490000 0.0032690000 0.0000000000 0.0000040000 0.0010250000 41958877 96830484 509673472 3.9083547592 4.2415685654 3.8139379025 1777 1311867229.7184219360 0.1087549478 0.0889386262 0.1207853556 0.0060458881 0.0115780000 0.0004510000 0.0048000000 0.0000040000 0.0000030000 0.0019130000 41962493 96830484 509673472 3.9078598022 4.2410688400 3.8134512901 1778 1311867229.7500000000 0.1071896404 0.0889488911 0.1207853556 0.0060448067 0.0095530000 0.0004490000 0.0036480000 0.0000000000 0.0000040000 0.0010230000 41966165 96830484 509673472 3.9091019630 4.2375864983 3.8129990101 1779 1311867229.7854330540 0.1077894270 0.0889594817 0.1207853556 0.0060433162 0.0109840000 0.0004530000 0.0047840000 0.0000030000 0.0000030000 0.0013250000 41969949 96830484 509673472 3.9084615707 4.2372479439 3.8124656677 1780 1311867229.8184831142 0.1079223603 0.0889701350 0.1207853556 0.0060416422 0.0120210000 0.0005410000 0.0030550000 0.0000000000 0.0000080000 0.0011630000 41973621 96830484 509673472 3.9082586765 4.2355680466 3.8121304512 1781 1311867229.8494279385 0.1086593196 0.0889811901 0.1207853556 0.0060402423 0.0120100000 0.0004620000 0.0048370000 0.0000040000 0.0000040000 0.0019320000 41977293 96830484 509673472 3.9064362049 4.2334117889 3.8115339279 1782 1311867229.8853340149 0.1079956964 0.0889918604 0.1207853556 0.0060387237 0.0102840000 0.0004470000 0.0044030000 0.0000000000 0.0000040000 0.0010340000 41981077 96830484 509673472 3.9070756435 4.2314410210 3.8109507561 1783 1311867229.9183139801 0.1084696054 0.0890027846 0.1207853556 0.0060377811 0.0090900000 0.0004500000 0.0028600000 0.0000040000 0.0000040000 0.0013200000 41984749 96830484 509673472 3.9058783054 4.2308712006 3.8100237846 1784 1311867229.9534161091 0.1084173545 0.0890136672 0.1207853556 0.0060387004 0.0087470000 0.0004500000 0.0028560000 0.0000010000 0.0000040000 0.0010410000 41988533 96830484 509673472 3.9055988789 4.2279448509 3.8095378876 1785 1311867229.9877750874 0.1093902066 0.0890250826 0.1207853556 0.0060372315 0.0096810000 0.0004520000 0.0028610000 0.0000040000 0.0000030000 0.0019250000 41992317 96830484 509673472 3.9037926197 4.2265052795 3.8089454174 1786 1311867230.0194880962 0.1103790402 0.0890370389 0.1207853556 0.0060359414 0.0144810000 0.0005400000 0.0048790000 0.0000010000 0.0000090000 0.0014610000 41995933 96830484 509673472 3.9024355412 4.2257499695 3.8083302975 1787 1311867230.0512609482 0.1097706184 0.0890486413 0.1207853556 0.0060344486 0.0138810000 0.0006050000 0.0049990000 0.0000080000 0.0000080000 0.0014410000 41999661 96830484 509673472 3.9034378529 4.2243423462 3.8080425262 1788 1311867230.0876040459 0.1103105620 0.0890605328 0.1207853556 0.0060328863 0.0132490000 0.0005090000 0.0049350000 0.0000010000 0.0000070000 0.0011160000 42003333 96830484 509673472 3.9015536308 4.2216415405 3.8069911003 1789 1311867230.1212029457 0.1097644344 0.0890721057 0.1207853556 0.0060312381 0.0099430000 0.0004600000 0.0028650000 0.0000040000 0.0000040000 0.0019610000 42007173 96830484 509673472 3.9015994072 4.2195444107 3.8061110973 1790 1311867230.1508131027 0.1083944291 0.0890829003 0.1207853556 0.0060298181 0.0092330000 0.0004400000 0.0032140000 0.0000010000 0.0000040000 0.0010520000 42010733 96830484 509673472 3.9041252136 4.2186670303 3.8058478832 1791 1311867230.1872301102 0.1090633273 0.0890940563 0.1207853556 0.0060323767 0.0091100000 0.0004520000 0.0028370000 0.0000030000 0.0000030000 0.0013330000 42014517 96830484 509673472 3.9021308422 4.2175688744 3.8051819801 1792 1311867230.2194790840 0.1099372953 0.0891056876 0.1207853556 0.0060387013 0.0135540000 0.0005380000 0.0049590000 0.0000010000 0.0000080000 0.0011930000 42018189 96830484 509673472 3.9015696049 4.2155709267 3.8046641350 1793 1311867230.2494208813 0.1091254726 0.0891168531 0.1207853556 0.0060432558 0.0104430000 0.0004600000 0.0032360000 0.0000040000 0.0000040000 0.0019840000 42021805 96830484 509673472 3.9020364285 4.2152934074 3.8039386272 1794 1311867230.2894790173 0.1115314215 0.0891293473 0.1207853556 0.0060486962 0.0107770000 0.0004500000 0.0047160000 0.0000000000 0.0000040000 0.0010630000 42025701 96830484 509673472 3.8989317417 4.2141804695 3.8030693531 1795 1311867230.3189430237 0.1117380932 0.0891419427 0.1207853556 0.0060470544 0.0110480000 0.0004510000 0.0047140000 0.0000040000 0.0000030000 0.0013410000 42029261 96830484 509673472 3.8983592987 4.2123980522 3.8023498058 1796 1311867230.3552010059 0.1102226749 0.0891536803 0.1207853556 0.0060460249 0.0087960000 0.0004450000 0.0028290000 0.0000010000 0.0000040000 0.0010600000 42033101 96830484 509673472 3.9002821445 4.2104573250 3.8014931679 1797 1311867230.3913140297 0.1108672321 0.0891657635 0.1207853556 0.0060445480 0.0116060000 0.0004490000 0.0047160000 0.0000040000 0.0000030000 0.0019860000 42036829 96830484 509673472 3.8995873928 4.2099165916 3.8011794090 1798 1311867230.4169929028 0.1118431091 0.0891783760 0.1207853556 0.0060432347 0.0087970000 0.0004460000 0.0028170000 0.0000000000 0.0000040000 0.0010650000 42040333 96830484 509673472 3.8976526260 4.2083921432 3.8003973961 1799 1311867230.4538938999 0.1116518304 0.0891908682 0.1207853556 0.0060416456 0.0126430000 0.0005400000 0.0026360000 0.0000100000 0.0000110000 0.0014860000 42044173 96830484 509673472 3.8972115517 4.2065591812 3.7994921207 1800 1311867230.4892110825 0.1112183556 0.0892031057 0.1207853556 0.0060502321 0.0091390000 0.0004650000 0.0024770000 0.0000010000 0.0000060000 0.0010820000 42047901 96830484 509673472 3.8966009617 4.2049255371 3.7988693714 1801 1311867230.5216429234 0.1106395945 0.0892150083 0.1207853556 0.0060491424 0.0115670000 0.0004630000 0.0046850000 0.0000040000 0.0000030000 0.0019740000 42051629 96830484 509673472 3.8974399567 4.2045359612 3.7986888885 1802 1311867230.5564150810 0.1123923287 0.0892278703 0.1207853556 0.0060605589 0.0106400000 0.0004400000 0.0046900000 0.0000010000 0.0000040000 0.0010630000 42055413 96830484 509673472 3.8955037594 4.2042531967 3.7982277870 1803 1311867230.5930590630 0.1111644804 0.0892400370 0.1207853556 0.0060593136 0.0094690000 0.0004410000 0.0031760000 0.0000040000 0.0000040000 0.0013370000 42059141 96830484 509673472 3.8974416256 4.2029075623 3.7979955673 1804 1311867230.6184151173 0.1112866849 0.0892522580 0.1207853556 0.0060578576 0.0087730000 0.0004380000 0.0028080000 0.0000010000 0.0000040000 0.0010680000 42062589 96830484 509673472 3.8961234093 4.2001385689 3.7971150875 1805 1311867230.6534399986 0.1126179472 0.0892652030 0.1207853556 0.0060563206 0.0105070000 0.0004450000 0.0035700000 0.0000040000 0.0000040000 0.0019990000 42066373 96830484 509673472 3.8939037323 4.1993637085 3.7968297005 1806 1311867230.6920781136 0.1116228029 0.0892775826 0.1207853556 0.0060556026 0.0107130000 0.0004470000 0.0046970000 0.0000010000 0.0000040000 0.0010670000 42070269 96830484 509673472 3.8955023289 4.1985907555 3.7967655659 1807 1311867230.7185189724 0.1118426397 0.0892900702 0.1207853556 0.0060540030 0.0111210000 0.0004500000 0.0046930000 0.0000040000 0.0000040000 0.0013550000 42073717 96830484 509673472 3.8945322037 4.1974763870 3.7962150574 1808 1311867230.7529120445 0.1112366915 0.0893022088 0.1207853556 0.0060528429 0.0106880000 0.0004390000 0.0046890000 0.0000010000 0.0000040000 0.0010740000 42077501 96830484 509673472 3.8951508999 4.1974067688 3.7959825993 1809 1311867230.7871611118 0.1114631295 0.0893144592 0.1207853556 0.0060596134 0.0097750000 0.0004460000 0.0028210000 0.0000030000 0.0000030000 0.0019920000 42081285 96830484 509673472 3.8925907612 4.1950035095 3.7954475880 1810 1311867230.8195741177 0.1108210757 0.0893263413 0.1207853556 0.0060650961 0.0105450000 0.0004380000 0.0045440000 0.0000000000 0.0000040000 0.0010710000 42084901 96830484 509673472 3.8946599960 4.1953105927 3.7957272530 1811 1311867230.8534181118 0.1110417321 0.0893383321 0.1207853556 0.0060636819 0.0095940000 0.0004940000 0.0024320000 0.0000040000 0.0000040000 0.0015280000 42088629 96830484 509673472 3.8943629265 4.1956734657 3.7958672047 1812 1311867230.8890159130 0.1108462363 0.0893502018 0.1207853556 0.0060621909 0.0085490000 0.0004440000 0.0024310000 0.0000000000 0.0000050000 0.0010680000 42092413 96830484 509673472 3.8940732479 4.1946811676 3.7956864834 1813 1311867230.9176509380 0.1108968109 0.0893620863 0.1207853556 0.0060606447 0.0098660000 0.0004410000 0.0027960000 0.0000030000 0.0000030000 0.0019980000 42096029 96830484 509673472 3.8937213421 4.1946120262 3.7955932617 1814 1311867230.9559168816 0.1108142436 0.0893739122 0.1207853556 0.0060592048 0.0093030000 0.0004430000 0.0031750000 0.0000010000 0.0000040000 0.0010640000 42099813 96830484 509673472 3.8933930397 4.1928992271 3.7955355644 1815 1311867230.9881010056 0.1115765050 0.0893861450 0.1207853556 0.0060580684 0.0109740000 0.0004480000 0.0046670000 0.0000040000 0.0000040000 0.0013380000 42103485 96830484 509673472 3.8922770023 4.1931686401 3.7952651978 1816 1311867231.0166280270 0.1114109308 0.0893982732 0.1207853556 0.0060567551 0.0106960000 0.0004370000 0.0045570000 0.0000010000 0.0000040000 0.0010580000 42107101 96830484 509673472 3.8920493126 4.1916465759 3.7949233055 1817 1311867231.0603969097 0.1103977710 0.0894098304 0.1207853556 0.0060559943 0.0099090000 0.0004420000 0.0028140000 0.0000040000 0.0000030000 0.0019790000 42110997 96830484 509673472 3.8935286999 4.1915893555 3.7947199345 1818 1311867231.0868620872 0.1118039638 0.0894221485 0.1207853556 0.0060549121 0.0108400000 0.0004390000 0.0046920000 0.0000010000 0.0000040000 0.0010610000 42114445 96830484 509673472 3.8905043602 4.1903390884 3.7938749790 1819 1311867231.1221020222 0.1115594953 0.0894343185 0.1207853556 0.0060536384 0.0124330000 0.0005390000 0.0030000000 0.0000070000 0.0000080000 0.0014560000 42118285 96830484 509673472 3.8905899525 4.1887760162 3.7935922146 1820 1311867231.1523799896 0.1122535542 0.0894468566 0.1207853556 0.0060567650 0.0095290000 0.0004580000 0.0028480000 0.0000010000 0.0000050000 0.0010660000 42121845 96830484 509673472 3.8883199692 4.1851973534 3.7925980091 1821 1311867231.1860070229 0.1119225249 0.0894591990 0.1207853556 0.0060554099 0.0102930000 0.0004480000 0.0031800000 0.0000030000 0.0000040000 0.0019760000 42125573 96830484 509673472 3.8890035152 4.1860961914 3.7921853065 1822 1311867231.2188270092 0.1122099832 0.0894716858 0.1207853556 0.0060546163 0.0108400000 0.0004410000 0.0046860000 0.0000000000 0.0000030000 0.0010630000 42129245 96830484 509673472 3.8881866932 4.1839227676 3.7918105125 1823 1311867231.2522621155 0.1122331694 0.0894841715 0.1207853556 0.0060550406 0.0111280000 0.0004490000 0.0046860000 0.0000030000 0.0000030000 0.0013400000 42132973 96830484 509673472 3.8873679638 4.1819286346 3.7911205292 1824 1311867231.2864110470 0.1139043272 0.0894975597 0.1207853556 0.0060551284 0.0108150000 0.0004450000 0.0046610000 0.0000010000 0.0000040000 0.0010730000 42136701 96830484 509673472 3.8847396374 4.1814622879 3.7901957035 1825 1311867231.3215939999 0.1142294556 0.0895111115 0.1207853556 0.0060538638 0.0117490000 0.0004430000 0.0046550000 0.0000040000 0.0000040000 0.0019920000 42140485 96830484 509673472 3.8840341568 4.1805415154 3.7900178432 1826 1311867231.3525509834 0.1135374084 0.0895242693 0.1207853556 0.0060523429 0.0089050000 0.0004470000 0.0027930000 0.0000010000 0.0000040000 0.0010430000 42144101 96830484 509673472 3.8842973709 4.1788353920 3.7895786762 1827 1311867231.3874650002 0.1131213531 0.0895371851 0.1207853556 0.0060507216 0.0091780000 0.0004400000 0.0027760000 0.0000050000 0.0000030000 0.0013250000 42147829 96830484 509673472 3.8844711781 4.1784276962 3.7891800404 1828 1311867231.4187040329 0.1133385301 0.0895502055 0.1207853556 0.0060491816 0.0104970000 0.0004390000 0.0043980000 0.0000000000 0.0000030000 0.0010500000 42151501 96830484 509673472 3.8837676048 4.1779670715 3.7890348434 1829 1311867231.4542400837 0.1130949333 0.0895630785 0.1207853556 0.0060476599 0.0116830000 0.0004440000 0.0046390000 0.0000030000 0.0000030000 0.0019590000 42155285 96830484 509673472 3.8834645748 4.1767749786 3.7890651226 1830 1311867231.4867990017 0.1134899184 0.0895761533 0.1207853556 0.0060460887 0.0133120000 0.0005370000 0.0039830000 0.0000010000 0.0000090000 0.0011740000 42158957 96830484 509673472 3.8821871281 4.1761631966 3.7890682220 1831 1311867231.5193030834 0.1132503599 0.0895890830 0.1207853556 0.0060446013 0.0114470000 0.0004560000 0.0046690000 0.0000040000 0.0000050000 0.0013330000 42162629 96830484 509673472 3.8823692799 4.1757912636 3.7892866135 1832 1311867231.5524148941 0.1127796769 0.0896017416 0.1207853556 0.0060436207 0.0116240000 0.0006220000 0.0050800000 0.0000000000 0.0000030000 0.0010460000 42166301 96830484 509673472 3.8824520111 4.1737718582 3.7891399860 1833 1311867231.5855851173 0.1122503951 0.0896140976 0.1207853556 0.0060471855 0.0119430000 0.0004430000 0.0046180000 0.0000040000 0.0000060000 0.0019610000 42170085 96830484 509673472 3.8824317455 4.1732773781 3.7892560959 1834 1311867231.6210820675 0.1120080128 0.0896263081 0.1207853556 0.0060547388 0.0108830000 0.0004420000 0.0046320000 0.0000010000 0.0000040000 0.0010540000 42173813 96830484 509673472 3.8836011887 4.1729283333 3.7891092300 1835 1311867231.6522169113 0.1130747870 0.0896390865 0.1207853556 0.0060532137 0.0222410000 0.0006370000 0.0043950000 0.0000150000 0.0000150000 0.0018340000 42177485 96830484 509673472 3.8813970089 4.1709232330 3.7886433601 1836 1311867231.6880500317 0.1132604778 0.0896519522 0.1207853556 0.0060516529 0.0122210000 0.0004840000 0.0047570000 0.0000010000 0.0000050000 0.0010800000 42181269 96830484 509673472 3.8812921047 4.1708984375 3.7885539532 1837 1311867231.7208089828 0.1129678935 0.0896646446 0.1207853556 0.0060503691 0.0109670000 0.0004460000 0.0039130000 0.0000030000 0.0000040000 0.0019620000 42184997 96830484 509673472 3.8817467690 4.1703023911 3.7882347107 1838 1311867231.7523078918 0.1123144180 0.0896769677 0.1207853556 0.0060515441 0.0106470000 0.0004450000 0.0045200000 0.0000010000 0.0000050000 0.0010400000 42188557 96830484 509673472 3.8825643063 4.1691308022 3.7876906395 1839 1311867231.7860589027 0.1124583036 0.0896893556 0.1207853556 0.0060499900 0.0111090000 0.0004440000 0.0046650000 0.0000040000 0.0000040000 0.0013260000 42192341 96830484 509673472 3.8820672035 4.1659660339 3.7873082161 1840 1311867231.8202130795 0.1129696593 0.0897020079 0.1207853556 0.0060495858 0.0092080000 0.0004450000 0.0031430000 0.0000010000 0.0000040000 0.0010480000 42196069 96830484 509673472 3.8816852570 4.1657791138 3.7868273258 1841 1311867231.8521840572 0.1132244766 0.0897147849 0.1207853556 0.0060485719 0.0136370000 0.0005350000 0.0030040000 0.0000120000 0.0000100000 0.0021150000 42199685 96830484 509673472 3.8815138340 4.1650204659 3.7861895561 1842 1311867231.8857500553 0.1128814220 0.0897273618 0.1207853556 0.0060476780 0.0144560000 0.0005380000 0.0049290000 0.0000020000 0.0000080000 0.0011760000 42203469 96830484 509673472 3.8811764717 4.1621842384 3.7856020927 1843 1311867231.9208559990 0.1120302901 0.0897394632 0.1207853556 0.0060460961 0.0101070000 0.0004540000 0.0031750000 0.0000050000 0.0000050000 0.0013430000 42207253 96830484 509673472 3.8824300766 4.1615152359 3.7846882343 1844 1311867231.9533181190 0.1129390821 0.0897520444 0.1207853556 0.0060451609 0.0092330000 0.0004450000 0.0031440000 0.0000000000 0.0000040000 0.0010540000 42210869 96830484 509673472 3.8814957142 4.1603956223 3.7843892574 1845 1311867231.9870491028 0.1132380515 0.0897647739 0.1207853556 0.0060436212 0.0091650000 0.0004370000 0.0020280000 0.0000040000 0.0000040000 0.0019680000 42214597 96830484 509673472 3.8811640739 4.1591320038 3.7838165760 1846 1311867232.0202860832 0.1144224405 0.0897781313 0.1207853556 0.0060423062 0.0089590000 0.0004460000 0.0027620000 0.0000010000 0.0000040000 0.0010550000 42218325 96830484 509673472 3.8792097569 4.1568918228 3.7831807137 1847 1311867232.0522420406 0.1138098761 0.0897911425 0.1207853556 0.0060408632 0.0139440000 0.0005360000 0.0048500000 0.0000080000 0.0000090000 0.0014600000 42221997 96830484 509673472 3.8802556992 4.1566081047 3.7828845978 1848 1311867232.0878489017 0.1142452285 0.0898043752 0.1207853556 0.0060392649 0.0092950000 0.0004540000 0.0027810000 0.0000010000 0.0000040000 0.0010610000 42225781 96830484 509673472 3.8794033527 4.1550836563 3.7822377682 1849 1311867232.1203238964 0.1143072397 0.0898176272 0.1207853556 0.0060387336 0.0117100000 0.0004370000 0.0045920000 0.0000030000 0.0000040000 0.0019760000 42229453 96830484 509673472 3.8793437481 4.1533226967 3.7814996243 1850 1311867232.1545510292 0.1133264825 0.0898303347 0.1207853556 0.0060378007 0.0095930000 0.0004370000 0.0034900000 0.0000010000 0.0000040000 0.0010520000 42233181 96830484 509673472 3.8809859753 4.1543192863 3.7814328671 1851 1311867232.1846179962 0.1144043282 0.0898436107 0.1207853556 0.0060369908 0.0091670000 0.0004380000 0.0027430000 0.0000040000 0.0000040000 0.0013350000 42236797 96830484 509673472 3.8787212372 4.1517577171 3.7807126045 1852 1311867232.2209780216 0.1150495782 0.0898572209 0.1207853556 0.0060356072 0.0123960000 0.0005380000 0.0032970000 0.0000010000 0.0000090000 0.0011780000 42240581 96830484 509673472 3.8773114681 4.1494827271 3.7800152302 1853 1311867232.2531120777 0.1149298400 0.0898707517 0.1207853556 0.0060343341 0.0109280000 0.0004480000 0.0035050000 0.0000040000 0.0000050000 0.0019840000 42244197 96830484 509673472 3.8778469563 4.1500082016 3.7798032761 1854 1311867232.2844479084 0.1154461205 0.0898845464 0.1207853556 0.0060331704 0.0107020000 0.0004380000 0.0045650000 0.0000010000 0.0000040000 0.0010550000 42247925 96830484 509673472 3.8761897087 4.1472754478 3.7789826393 1855 1311867232.3209791183 0.1151079908 0.0898981439 0.1207853556 0.0060317322 0.0129560000 0.0005410000 0.0025460000 0.0000080000 0.0000080000 0.0014590000 42251709 96830484 509673472 3.8765218258 4.1467394829 3.7785186768 1856 1311867232.3544659615 0.1145368591 0.0899114191 0.1207853556 0.0060303550 0.0105150000 0.0004940000 0.0038460000 0.0000000000 0.0000040000 0.0010670000 42255381 96830484 509673472 3.8774099350 4.1466116905 3.7780318260 1857 1311867232.3858909607 0.1167705357 0.0899258828 0.1207853556 0.0060292651 0.0136300000 0.0005250000 0.0029470000 0.0000100000 0.0000090000 0.0021420000 42259053 96830484 509673472 3.8746318817 4.1452236176 3.7777261734 1858 1311867232.4203910828 0.1157198250 0.0899397654 0.1207853556 0.0060282489 0.0139560000 0.0005410000 0.0048320000 0.0000010000 0.0000080000 0.0011880000 42262781 96830484 509673472 3.8757646084 4.1441073418 3.7771060467 1859 1311867232.4544560909 0.1152617484 0.0899533867 0.1207853556 0.0060268093 0.0108150000 0.0004420000 0.0038690000 0.0000040000 0.0000040000 0.0013420000 42266509 96830484 509673472 3.8770208359 4.1445794106 3.7770748138 1860 1311867232.4846010208 0.1143985763 0.0899665293 0.1207853556 0.0060299454 0.0107350000 0.0004330000 0.0045360000 0.0000010000 0.0000050000 0.0010660000 42270125 96830484 509673472 3.8768374920 4.1427979469 3.7766914368 1861 1311867232.5203030109 0.1145178676 0.0899797219 0.1207853556 0.0060291068 0.0100870000 0.0004310000 0.0029710000 0.0000040000 0.0000040000 0.0019790000 42273909 96830484 509673472 3.8775870800 4.1426348686 3.7764725685 1862 1311867232.5550050735 0.1140378118 0.0899926424 0.1207853556 0.0060292085 0.0107210000 0.0004310000 0.0045570000 0.0000010000 0.0000050000 0.0010650000 42277637 96830484 509673472 3.8774631023 4.1427345276 3.7765614986 1863 1311867232.5844318867 0.1152677312 0.0900062093 0.1207853556 0.0060313307 0.0110830000 0.0004280000 0.0044400000 0.0000040000 0.0000040000 0.0013460000 42281197 96830484 509673472 3.8766176701 4.1398653984 3.7760536671 1864 1311867232.6201601028 0.1148146763 0.0900195186 0.1207853556 0.0060298664 0.0095810000 0.0004370000 0.0034500000 0.0000000000 0.0000030000 0.0010660000 42284981 96830484 509673472 3.8775417805 4.1386756897 3.7759339809 1865 1311867232.6554861069 0.1134853438 0.0900321008 0.1207853556 0.0060296885 0.0151890000 0.0005220000 0.0048290000 0.0000080000 0.0000070000 0.0021660000 42288597 96830484 509673472 3.8808166981 4.1402730942 3.7763290405 1866 1311867232.6850490570 0.1135126650 0.0900446841 0.1207853556 0.0060289449 0.0099840000 0.0004470000 0.0034960000 0.0000000000 0.0000040000 0.0010760000 42292213 96830484 509673472 3.8796710968 4.1363039017 3.7754230499 1867 1311867232.7210319042 0.1135932356 0.0900572972 0.1207853556 0.0060273341 0.0111680000 0.0004390000 0.0045670000 0.0000030000 0.0000040000 0.0013560000 42295997 96830484 509673472 3.8796582222 4.1344504356 3.7752928734 1868 1311867232.7539520264 0.1147205308 0.0900705002 0.1207853556 0.0060269917 0.0090580000 0.0004360000 0.0028550000 0.0000010000 0.0000040000 0.0010750000 42299613 96830484 509673472 3.8787672520 4.1348209381 3.7752385139 1869 1311867232.7885808945 0.1143344790 0.0900834825 0.1207853556 0.0060256039 0.0133200000 0.0005270000 0.0032880000 0.0000080000 0.0000090000 0.0021440000 42303341 96830484 509673472 3.8793673515 4.1327757835 3.7749793530 1870 1311867232.8206169605 0.1155626401 0.0900971078 0.1207853556 0.0060241949 0.0109300000 0.0004490000 0.0044920000 0.0000010000 0.0000040000 0.0010630000 42307069 96830484 509673472 3.8769555092 4.1277832985 3.7746446133 1871 1311867232.8539369106 0.1144360155 0.0901101163 0.1207853556 0.0060230333 0.0110300000 0.0004270000 0.0045390000 0.0000040000 0.0000040000 0.0013380000 42310741 96830484 509673472 3.8791663647 4.1290731430 3.7744247913 1872 1311867232.8882710934 0.1139990240 0.0901228774 0.1207853556 0.0060215459 0.0082440000 0.0004320000 0.0019920000 0.0000010000 0.0000040000 0.0010690000 42314469 96830484 509673472 3.8795282841 4.1267032623 3.7740235329 1873 1311867232.9203770161 0.1144380271 0.0901358594 0.1207853556 0.0060206230 0.0116410000 0.0004280000 0.0045170000 0.0000040000 0.0000030000 0.0019840000 42318197 96830484 509673472 3.8786339760 4.1240248680 3.7736835480 1874 1311867232.9559900761 0.1130749509 0.0901481001 0.1207853556 0.0060200562 0.0144970000 0.0005230000 0.0048040000 0.0000020000 0.0000080000 0.0012050000 42321981 96830484 509673472 3.8801620007 4.1222271919 3.7731332779 1875 1311867232.9890038967 0.1155405492 0.0901616427 0.1207853556 0.0060217384 0.0113530000 0.0004420000 0.0045400000 0.0000040000 0.0000050000 0.0013580000 42325597 96830484 509673472 3.8778405190 4.1240491867 3.7730314732 1876 1311867233.0212259293 0.1135763079 0.0901741239 0.1207853556 0.0060215569 0.0126980000 0.0005150000 0.0032610000 0.0000010000 0.0000080000 0.0012080000 42329325 96830484 509673472 3.8803019524 4.1210861206 3.7730205059 1877 1311867233.0569291115 0.1147178933 0.0901871999 0.1207853556 0.0060203911 0.0119040000 0.0004310000 0.0045200000 0.0000040000 0.0000040000 0.0020060000 42333053 96830484 509673472 3.8783526421 4.1195201874 3.7725961208 1878 1311867233.0943200588 0.1146381572 0.0902002196 0.1207853556 0.0060197809 0.0088640000 0.0004260000 0.0026910000 0.0000000000 0.0000040000 0.0010800000 42336893 96830484 509673472 3.8794093132 4.1203937531 3.7729995251 1879 1311867233.1241600513 0.1147688553 0.0902132950 0.1207853556 0.0060188153 0.0106210000 0.0004920000 0.0035340000 0.0000040000 0.0000040000 0.0013600000 42340397 96830484 509673472 3.8787801266 4.1181945801 3.7727494240 1880 1311867233.1530799866 0.1139310300 0.0902259108 0.1207853556 0.0060188190 0.0141790000 0.0005300000 0.0040480000 0.0000010000 0.0000080000 0.0012120000 42343957 96830484 509673472 3.8790755272 4.1161642075 3.7728972435 1881 1311867233.1887679100 0.1134874970 0.0902382774 0.1207853556 0.0060175479 0.0143840000 0.0005300000 0.0040100000 0.0000080000 0.0000070000 0.0021870000 42347741 96830484 509673472 3.8805599213 4.1155376434 3.7727961540 1882 1311867233.2210481167 0.1137734950 0.0902507828 0.1207853556 0.0060160467 0.0111740000 0.0004440000 0.0045640000 0.0000010000 0.0000040000 0.0010810000 42351413 96830484 509673472 3.8792376518 4.1124544144 3.7725834846 1883 1311867233.2590179443 0.1141110361 0.0902634542 0.1207853556 0.0060145313 0.0095230000 0.0004240000 0.0030510000 0.0000040000 0.0000040000 0.0013530000 42355253 96830484 509673472 3.8792996407 4.1111855507 3.7725412846 1884 1311867233.2899589539 0.1138110831 0.0902759530 0.1207853556 0.0060129835 0.0106430000 0.0004200000 0.0044730000 0.0000010000 0.0000040000 0.0010830000 42358925 96830484 509673472 3.8799650669 4.1119389534 3.7726914883 1885 1311867233.3212211132 0.1125775725 0.0902877841 0.1207853556 0.0060128580 0.0117710000 0.0004260000 0.0044760000 0.0000040000 0.0000040000 0.0019630000 42362597 96830484 509673472 3.8807828426 4.1100010872 3.7725112438 1886 1311867233.3533849716 0.1162606999 0.0903015555 0.1207853556 0.0060139422 0.0107040000 0.0004260000 0.0044920000 0.0000000000 0.0000040000 0.0010770000 42366213 96830484 509673472 3.8764240742 4.1071443558 3.7726497650 1887 1311867233.3884561062 0.1157233715 0.0903150276 0.1207853556 0.0060147590 0.0098890000 0.0004220000 0.0033930000 0.0000030000 0.0000030000 0.0013480000 42369997 96830484 509673472 3.8772194386 4.1063294411 3.7726223469 1888 1311867233.4236669540 0.1152625456 0.0903282413 0.1207853556 0.0060192382 0.0108450000 0.0004200000 0.0044630000 0.0000000000 0.0000040000 0.0010810000 42373725 96830484 509673472 3.8773601055 4.1049332619 3.7725229263 1889 1311867233.4522700310 0.1135404110 0.0903405294 0.1207853556 0.0060230429 0.0114110000 0.0004220000 0.0041200000 0.0000050000 0.0000040000 0.0020170000 42377397 96830484 509673472 3.8791117668 4.1010837555 3.7716701031 1890 1311867233.4881610870 0.1143249944 0.0903532196 0.1207853556 0.0060268686 0.0106880000 0.0004140000 0.0044530000 0.0000010000 0.0000040000 0.0010820000 42381069 96830484 509673472 3.8779869080 4.1002550125 3.7713823318 1891 1311867233.5201199055 0.1140395477 0.0903657454 0.1207853556 0.0060267857 0.0103540000 0.0004170000 0.0037190000 0.0000030000 0.0000030000 0.0013480000 42384797 96830484 509673472 3.8787639141 4.1001691818 3.7713420391 1892 1311867233.5526270866 0.1136572063 0.0903780559 0.1207853556 0.0060260838 0.0085770000 0.0004150000 0.0023220000 0.0000010000 0.0000040000 0.0010620000 42388469 96830484 509673472 3.8786067963 4.0980319977 3.7709529400 1893 1311867233.5890851021 0.1142670363 0.0903906755 0.1207853556 0.0060250632 0.0101310000 0.0004070000 0.0030150000 0.0000030000 0.0000040000 0.0019760000 42392253 96830484 509673472 3.8780789375 4.0986599922 3.7709841728 1894 1311867233.6202619076 0.1136742160 0.0904029689 0.1207853556 0.0060235636 0.0106290000 0.0004090000 0.0044380000 0.0000010000 0.0000040000 0.0010610000 42395925 96830484 509673472 3.8792004585 4.0977463722 3.7712790966 1895 1311867233.6539080143 0.1154659241 0.0904161947 0.1207853556 0.0060229862 0.0139120000 0.0005070000 0.0046610000 0.0000070000 0.0000090000 0.0014710000 42399597 96830484 509673472 3.8768188953 4.0969967842 3.7712130547 1896 1311867233.6879289150 0.1164816320 0.0904299423 0.1207853556 0.0060215085 0.0094960000 0.0004260000 0.0029250000 0.0000010000 0.0000050000 0.0010740000 42403325 96830484 509673472 3.8751249313 4.0960459709 3.7711274624 1897 1311867233.7197790146 0.1149019971 0.0904428427 0.1207853556 0.0060199700 0.0138230000 0.0005040000 0.0039360000 0.0000090000 0.0000070000 0.0021500000 42407053 96830484 509673472 3.8771722317 4.0954766273 3.7710719109 1898 1311867233.7577540874 0.1150908545 0.0904558290 0.1207853556 0.0060187018 0.0090430000 0.0004430000 0.0023350000 0.0000010000 0.0000050000 0.0010750000 42410893 96830484 509673472 3.8764305115 4.0944170952 3.7710070610 1899 1311867233.7896089554 0.1152343079 0.0904688772 0.1207853556 0.0060184026 0.0109990000 0.0004080000 0.0044190000 0.0000040000 0.0000040000 0.0013470000 42414565 96830484 509673472 3.8756222725 4.0934982300 3.7708430290 1900 1311867233.8221189976 0.1147319973 0.0904816472 0.1207853556 0.0060181754 0.0089580000 0.0004180000 0.0026540000 0.0000000000 0.0000030000 0.0010720000 42418293 96830484 509673472 3.8760888577 4.0923299789 3.7711241245 1901 1311867233.8562450409 0.1147790849 0.0904944286 0.1207853556 0.0060166884 0.0109530000 0.0004100000 0.0037280000 0.0000030000 0.0000030000 0.0019840000 42421965 96830484 509673472 3.8757109642 4.0913615227 3.7711806297 1902 1311867233.8885691166 0.1143700406 0.0905069815 0.1207853556 0.0060151422 0.0106110000 0.0004150000 0.0044200000 0.0000010000 0.0000040000 0.0010620000 42425637 96830484 509673472 3.8757264614 4.0897970200 3.7710657120 1903 1311867233.9203450680 0.1127992049 0.0905186958 0.1207853556 0.0060145649 0.0110060000 0.0004060000 0.0044420000 0.0000040000 0.0000030000 0.0013430000 42429309 96830484 509673472 3.8774256706 4.0890083313 3.7711825371 1904 1311867233.9552910328 0.1125628278 0.0905302736 0.1207853556 0.0060131131 0.0094690000 0.0004080000 0.0032580000 0.0000000000 0.0000040000 0.0010650000 42433093 96830484 509673472 3.8770833015 4.0878038406 3.7709379196 1905 1311867233.9885900021 0.1134398654 0.0905422996 0.1207853556 0.0060115967 0.0112390000 0.0004060000 0.0040750000 0.0000030000 0.0000030000 0.0019880000 42436765 96830484 509673472 3.8757195473 4.0871601105 3.7710165977 1906 1311867234.0205829144 0.1134500578 0.0905543184 0.1207853556 0.0060101009 0.0129580000 0.0005050000 0.0024950000 0.0000010000 0.0000110000 0.0013080000 42440437 96830484 509673472 3.8755254745 4.0872254372 3.7707741261 1907 1311867234.0566239357 0.1139826551 0.0905666038 0.1207853556 0.0060087518 0.0143510000 0.0005190000 0.0046890000 0.0000080000 0.0000070000 0.0014750000 42444277 96830484 509673472 3.8744084835 4.0847740173 3.7708702087 1908 1311867234.0907170773 0.1130108386 0.0905783670 0.1207853556 0.0060073808 0.0110440000 0.0004240000 0.0044590000 0.0000000000 0.0000040000 0.0010730000 42447949 96830484 509673472 3.8747565746 4.0824861526 3.7703676224 1909 1311867234.1214520931 0.1146185398 0.0905909601 0.1207853556 0.0060069491 0.0115600000 0.0004020000 0.0043880000 0.0000040000 0.0000040000 0.0019940000 42451621 96830484 509673472 3.8728394508 4.0827312469 3.7705550194 1910 1311867234.1561689377 0.1141871512 0.0906033141 0.1207853556 0.0060056837 0.0096620000 0.0004090000 0.0033700000 0.0000010000 0.0000040000 0.0010670000 42455349 96830484 509673472 3.8729798794 4.0805697441 3.7704024315 1911 1311867234.1892559528 0.1159902140 0.0906165988 0.1207853556 0.0060043430 0.0099460000 0.0004050000 0.0033340000 0.0000030000 0.0000030000 0.0013420000 42459021 96830484 509673472 3.8700320721 4.0792679787 3.7704219818 1912 1311867234.2203600407 0.1151659414 0.0906294384 0.1207853556 0.0060033842 0.0102440000 0.0004070000 0.0040320000 0.0000010000 0.0000040000 0.0010580000 42462693 96830484 509673472 3.8709716797 4.0780472755 3.7700970173 1913 1311867234.2588930130 0.1158599183 0.0906426273 0.1207853556 0.0060020944 0.0112900000 0.0004040000 0.0040200000 0.0000030000 0.0000040000 0.0019800000 42466533 96830484 509673472 3.8695392609 4.0781450272 3.7702012062 1914 1311867234.2895319462 0.1149048284 0.0906553035 0.1207853556 0.0060006278 0.0106590000 0.0004100000 0.0043520000 0.0000010000 0.0000040000 0.0010570000 42470205 96830484 509673472 3.8696467876 4.0766224861 3.7700815201 1915 1311867234.3213200569 0.1149268448 0.0906679779 0.1207853556 0.0060026047 0.0098800000 0.0004040000 0.0033170000 0.0000040000 0.0000040000 0.0013420000 42473877 96830484 509673472 3.8690881729 4.0761718750 3.7704157829 1916 1311867234.3570129871 0.1152832955 0.0906808252 0.1207853556 0.0060011681 0.0089060000 0.0004210000 0.0026170000 0.0000010000 0.0000040000 0.0010730000 42477605 96830484 509673472 3.8681645393 4.0761713982 3.7707982063 1917 1311867234.3885769844 0.1117638871 0.0906918231 0.1207853556 0.0060020360 0.0116990000 0.0004080000 0.0043630000 0.0000040000 0.0000030000 0.0019850000 42481277 96830484 509673472 3.8715465069 4.0741720200 3.7708067894 1918 1311867234.4204909801 0.1121684760 0.0907030205 0.1207853556 0.0060005246 0.0096970000 0.0004060000 0.0033200000 0.0000000000 0.0000040000 0.0010650000 42485005 96830484 509673472 3.8702483177 4.0723671913 3.7710719109 1919 1311867234.4579920769 0.1124997810 0.0907143789 0.1207853556 0.0059998069 0.0088770000 0.0004010000 0.0022770000 0.0000050000 0.0000030000 0.0013500000 42488733 96830484 509673472 3.8698995113 4.0730643272 3.7714092731 1920 1311867234.4878959656 0.1120276973 0.0907254796 0.1207853556 0.0060016106 0.0096760000 0.0004020000 0.0033220000 0.0000000000 0.0000040000 0.0010660000 42492405 96830484 509673472 3.8701875210 4.0717072487 3.7716188431 1921 1311867234.5201239586 0.1115460098 0.0907363180 0.1207853556 0.0060001878 0.0115760000 0.0004020000 0.0043730000 0.0000040000 0.0000030000 0.0020000000 42496077 96830484 509673472 3.8704061508 4.0693650246 3.7719528675 1922 1311867234.5594279766 0.1130958274 0.0907479515 0.1207853556 0.0060011171 0.0099620000 0.0004080000 0.0036710000 0.0000000000 0.0000040000 0.0010710000 42499973 96830484 509673472 3.8689413071 4.0697011948 3.7725849152 1923 1311867234.5882380009 0.1124335453 0.0907592284 0.1207853556 0.0060003920 0.0096180000 0.0003980000 0.0029620000 0.0000030000 0.0000030000 0.0013360000 42503589 96830484 509673472 3.8694889545 4.0688524246 3.7728908062 1924 1311867234.6204199791 0.1135532036 0.0907710756 0.1207853556 0.0059989190 0.0093780000 0.0004080000 0.0029680000 0.0000010000 0.0000040000 0.0010670000 42507261 96830484 509673472 3.8677217960 4.0664167404 3.7731857300 1925 1311867234.6590909958 0.1135763377 0.0907829225 0.1207853556 0.0059980655 0.0104680000 0.0004080000 0.0029600000 0.0000030000 0.0000030000 0.0019850000 42511101 96830484 509673472 3.8680212498 4.0686802864 3.7738707066 1926 1311867234.6880459785 0.1126306206 0.0907942661 0.1207853556 0.0059967004 0.0107100000 0.0004040000 0.0043790000 0.0000000000 0.0000030000 0.0010710000 42514661 96830484 509673472 3.8686969280 4.0671310425 3.7740082741 1927 1311867234.7198779583 0.1132859215 0.0908059379 0.1207853556 0.0059967817 0.0154340000 0.0004980000 0.0046480000 0.0000080000 0.0000080000 0.0014890000 42518333 96830484 509673472 3.8682634830 4.0661697388 3.7745730877 1928 1311867234.7586181164 0.1122409180 0.0908170556 0.1207853556 0.0059952514 0.0113440000 0.0004670000 0.0045410000 0.0000000000 0.0000040000 0.0010770000 42522117 96830484 509673472 3.8696479797 4.0657534599 3.7754673958 1929 1311867234.7882609367 0.1123859212 0.0908282370 0.1207853556 0.0060010761 0.0107110000 0.0004040000 0.0033370000 0.0000040000 0.0000030000 0.0019850000 42525789 96830484 509673472 3.8696398735 4.0665779114 3.7765905857 1930 1311867234.8206560612 0.1124884486 0.0908394599 0.1207853556 0.0059995706 0.0107210000 0.0004080000 0.0043800000 0.0000010000 0.0000040000 0.0010720000 42529461 96830484 509673472 3.8687696457 4.0646057129 3.7773342133 1931 1311867234.8590250015 0.1115129367 0.0908501660 0.1207853556 0.0059981254 0.0147310000 0.0005100000 0.0046530000 0.0000080000 0.0000070000 0.0014720000 42533245 96830484 509673472 3.8707816601 4.0654253960 3.7783968449 1932 1311867234.8881230354 0.1120730937 0.0908611510 0.1207853556 0.0059969732 0.0140820000 0.0005150000 0.0039560000 0.0000010000 0.0000080000 0.0011800000 42536861 96830484 509673472 3.8704931736 4.0652022362 3.7794215679 1933 1311867234.9204928875 0.1124073043 0.0908722975 0.1207853556 0.0059958886 0.0117310000 0.0004170000 0.0040620000 0.0000050000 0.0000050000 0.0019730000 42540589 96830484 509673472 3.8702900410 4.0640254021 3.7801568508 1934 1311867234.9566090107 0.1135772169 0.0908840373 0.1207853556 0.0059950829 0.0108600000 0.0004120000 0.0043830000 0.0000010000 0.0000040000 0.0010610000 42544373 96830484 509673472 3.8692932129 4.0639843941 3.7807490826 1935 1311867234.9904088974 0.1136360839 0.0908957955 0.1207853556 0.0059935909 0.0165530000 0.0005890000 0.0048630000 0.0000100000 0.0000110000 0.0016090000 42548101 96830484 509673472 3.8694603443 4.0635504723 3.7810649872 1936 1311867235.0205988884 0.1125668883 0.0909069892 0.1207853556 0.0059928196 0.0114360000 0.0004340000 0.0044380000 0.0000000000 0.0000050000 0.0010830000 42551717 96830484 509673472 3.8705730438 4.0611205101 3.7808513641 1937 1311867235.0563809872 0.1154761538 0.0909196734 0.1207853556 0.0059918278 0.0102480000 0.0004030000 0.0029740000 0.0000040000 0.0000040000 0.0019930000 42555501 96830484 509673472 3.8666353226 4.0609068871 3.7810225487 1938 1311867235.0911149979 0.1141616777 0.0909316661 0.1207853556 0.0059908680 0.0106540000 0.0004060000 0.0043480000 0.0000010000 0.0000040000 0.0010620000 42559229 96830484 509673472 3.8679800034 4.0603542328 3.7809050083 1939 1311867235.1208140850 0.1125104353 0.0909427950 0.1207853556 0.0059906731 0.0142400000 0.0004950000 0.0045920000 0.0000080000 0.0000080000 0.0014750000 42562901 96830484 509673472 3.8696262836 4.0587916374 3.7809410095 1940 1311867235.1564071178 0.1116850823 0.0909534869 0.1207853556 0.0059906517 0.0133770000 0.0005000000 0.0038590000 0.0000010000 0.0000110000 0.0011980000 42566629 96830484 509673472 3.8701057434 4.0590372086 3.7817575932 1941 1311867235.1885681152 0.1108974218 0.0909637619 0.1207853556 0.0059904732 0.0119330000 0.0004130000 0.0043730000 0.0000040000 0.0000040000 0.0020090000 42570301 96830484 509673472 3.8701970577 4.0586838722 3.7817237377 1942 1311867235.2202088833 0.1116555184 0.0909744168 0.1207853556 0.0059891770 0.0134590000 0.0004990000 0.0030810000 0.0000010000 0.0000110000 0.0012190000 42573973 96830484 509673472 3.8679370880 4.0571656227 3.7816767693 1943 1311867235.2576260567 0.1124854684 0.0909854879 0.1207853556 0.0059886429 0.0107610000 0.0004120000 0.0036870000 0.0000050000 0.0000040000 0.0013480000 42577645 96830484 509673472 3.8672597408 4.0578093529 3.7821531296 1944 1311867235.2899661064 0.1126075685 0.0909966103 0.1207853556 0.0059893008 0.0107350000 0.0004020000 0.0043420000 0.0000000000 0.0000040000 0.0010660000 42581373 96830484 509673472 3.8657207489 4.0565319061 3.7824401855 1945 1311867235.3247830868 0.1115005910 0.0910071522 0.1207853556 0.0059878946 0.0116290000 0.0004050000 0.0043600000 0.0000040000 0.0000040000 0.0020030000 42585157 96830484 509673472 3.8662950993 4.0561761856 3.7822718620 1946 1311867235.3567800522 0.1113217771 0.0910175914 0.1207853556 0.0059974405 0.0107120000 0.0004030000 0.0043340000 0.0000010000 0.0000040000 0.0010640000 42588829 96830484 509673472 3.8656942844 4.0564627647 3.7825746536 1947 1311867235.3886280060 0.1115237847 0.0910281236 0.1207853556 0.0060065190 0.0110320000 0.0004020000 0.0043530000 0.0000030000 0.0000030000 0.0013510000 42592501 96830484 509673472 3.8657202721 4.0562324524 3.7830059528 1948 1311867235.4246189594 0.1118350402 0.0910388048 0.1207853556 0.0060058046 0.0094020000 0.0004020000 0.0029640000 0.0000010000 0.0000040000 0.0010720000 42596285 96830484 509673472 3.8642151356 4.0556912422 3.7836995125 1949 1311867235.4564850330 0.1122272834 0.0910496762 0.1207853556 0.0060054579 0.0117070000 0.0004010000 0.0043500000 0.0000040000 0.0000040000 0.0019860000 42599957 96830484 509673472 3.8644430637 4.0572385788 3.7845876217 1950 1311867235.4897930622 0.1121277809 0.0910604855 0.1207853556 0.0060050678 0.0094870000 0.0004480000 0.0026210000 0.0000010000 0.0000040000 0.0010600000 42603629 96830484 509673472 3.8638534546 4.0570745468 3.7854282856 1951 1311867235.5240719318 0.1118144169 0.0910711231 0.1207853556 0.0060038554 0.0103080000 0.0004450000 0.0033060000 0.0000040000 0.0000030000 0.0013470000 42607357 96830484 509673472 3.8639299870 4.0562329292 3.7859833241 1952 1311867235.5577290058 0.1129230410 0.0910823177 0.1207853556 0.0060035355 0.0094670000 0.0004080000 0.0029640000 0.0000000000 0.0000030000 0.0010690000 42611029 96830484 509673472 3.8631002903 4.0576291084 3.7871737480 1953 1311867235.5880639553 0.1130498052 0.0910935658 0.1207853556 0.0060020630 0.0096060000 0.0004010000 0.0022680000 0.0000030000 0.0000030000 0.0019900000 42614701 96830484 509673472 3.8627510071 4.0566601753 3.7877779007 1954 1311867235.6249940395 0.1128594801 0.0911047050 0.1207853556 0.0060011002 0.0138770000 0.0004950000 0.0046040000 0.0000010000 0.0000080000 0.0012080000 42618541 96830484 509673472 3.8622760773 4.0543675423 3.7878026962 1955 1311867235.6563270092 0.1129682362 0.0911158884 0.1207853556 0.0060004787 0.0112890000 0.0004140000 0.0044030000 0.0000040000 0.0000040000 0.0013550000 42622157 96830484 509673472 3.8626744747 4.0558915138 3.7883884907 1956 1311867235.6885619164 0.1132446229 0.0911272016 0.1207853556 0.0059992451 0.0107340000 0.0004050000 0.0043760000 0.0000000000 0.0000050000 0.0010650000 42625829 96830484 509673472 3.8619983196 4.0548267365 3.7886109352 1957 1311867235.7241950035 0.1137221009 0.0911387473 0.1207853556 0.0059979109 0.0117740000 0.0004150000 0.0043770000 0.0000040000 0.0000040000 0.0020050000 42629613 96830484 509673472 3.8609924316 4.0545134544 3.7888808250 1958 1311867235.7561719418 0.1128891930 0.0911498558 0.1207853556 0.0059964974 0.0091180000 0.0004060000 0.0026320000 0.0000010000 0.0000040000 0.0010720000 42633341 96830484 509673472 3.8621246815 4.0547342300 3.7896945477 1959 1311867235.7903280258 0.1132414117 0.0911611327 0.1207853556 0.0059956537 0.0154490000 0.0004970000 0.0046750000 0.0000110000 0.0000100000 0.0015060000 42637013 96830484 509673472 3.8614685535 4.0543627739 3.7902412415 1960 1311867235.8249480724 0.1137635782 0.0911726646 0.1207853556 0.0059943284 0.0112920000 0.0004080000 0.0044140000 0.0000000000 0.0000040000 0.0010660000 42640741 96830484 509673472 3.8609490395 4.0542821884 3.7912650108 1961 1311867235.8562169075 0.1142858043 0.0911844510 0.1207853556 0.0059950076 0.0147350000 0.0005000000 0.0046190000 0.0000090000 0.0000080000 0.0021600000 42644469 96830484 509673472 3.8610551357 4.0562133789 3.7926311493 1962 1311867235.8881049156 0.1162893549 0.0911972466 0.1207853556 0.0059940014 0.0101020000 0.0004150000 0.0033620000 0.0000000000 0.0000040000 0.0010670000 42648029 96830484 509673472 3.8575730324 4.0548152924 3.7932050228 1963 1311867235.9239900112 0.1140299663 0.0912088781 0.1207853556 0.0059932247 0.0098060000 0.0004000000 0.0029750000 0.0000040000 0.0000030000 0.0013430000 42651869 96830484 509673472 3.8600313663 4.0538382530 3.7939026356 1964 1311867235.9563760757 0.1145958379 0.0912207859 0.1207853556 0.0059929669 0.0090330000 0.0003990000 0.0026320000 0.0000000000 0.0000050000 0.0010530000 42655597 96830484 509673472 3.8600192070 4.0547704697 3.7949750423 1965 1311867235.9890949726 0.1133811995 0.0912320635 0.1207853556 0.0059931500 0.0110810000 0.0003990000 0.0036870000 0.0000040000 0.0000040000 0.0019810000 42659213 96830484 509673472 3.8604607582 4.0540103912 3.7951254845 1966 1311867236.0250449181 0.1141048446 0.0912436977 0.1207853556 0.0059917222 0.0101560000 0.0004030000 0.0036880000 0.0000000000 0.0000040000 0.0010640000 42662997 96830484 509673472 3.8589899540 4.0536656380 3.7956509590 1967 1311867236.0599400997 0.1135408953 0.0912550333 0.1207853556 0.0059902196 0.0131970000 0.0004940000 0.0024790000 0.0000100000 0.0000090000 0.0014890000 42666725 96830484 509673472 3.8593168259 4.0543813705 3.7964322567 1968 1311867236.0884859562 0.1137551218 0.0912664663 0.1207853556 0.0059888874 0.0112380000 0.0004150000 0.0043070000 0.0000010000 0.0000050000 0.0010640000 42670285 96830484 509673472 3.8583800793 4.0537085533 3.7971434593 1969 1311867236.1247038841 0.1131066456 0.0912775583 0.1207853556 0.0059874242 0.0117530000 0.0004030000 0.0043840000 0.0000050000 0.0000040000 0.0019780000 42674125 96830484 509673472 3.8586790562 4.0532760620 3.7982120514 1970 1311867236.1581289768 0.1128659621 0.0912885169 0.1207853556 0.0059861992 0.0094170000 0.0004040000 0.0029770000 0.0000010000 0.0000040000 0.0010630000 42677797 96830484 509673472 3.8587834835 4.0528793335 3.7993094921 1971 1311867236.1901528835 0.1128743887 0.0912994686 0.1207853556 0.0059849394 0.0111720000 0.0004010000 0.0043760000 0.0000040000 0.0000040000 0.0013410000 42681413 96830484 509673472 3.8580670357 4.0538454056 3.8005423546 1972 1311867236.2242329121 0.1119511798 0.0913099411 0.1207853556 0.0059836070 0.0093770000 0.0004020000 0.0029810000 0.0000000000 0.0000030000 0.0010560000 42685141 96830484 509673472 3.8580951691 4.0532307625 3.8015258312 1973 1311867236.2599489689 0.1123971865 0.0913206290 0.1207853556 0.0059822357 0.0117940000 0.0003990000 0.0043850000 0.0000040000 0.0000040000 0.0019870000 42688925 96830484 509673472 3.8571012020 4.0539021492 3.8029749393 1974 1311867236.2890419960 0.1122003570 0.0913312064 0.1207853556 0.0059807579 0.0143450000 0.0004980000 0.0046440000 0.0000010000 0.0000080000 0.0011780000 42692485 96830484 509673472 3.8568744659 4.0532488823 3.8041000366 1975 1311867236.3262441158 0.1130295396 0.0913421929 0.1207853556 0.0059793433 0.0143110000 0.0004990000 0.0045030000 0.0000080000 0.0000080000 0.0014730000 42696325 96830484 509673472 3.8555378914 4.0532813072 3.8055777550 1976 1311867236.3568809032 0.1132814214 0.0913532957 0.1207853556 0.0059785839 0.0139640000 0.0004940000 0.0044990000 0.0000010000 0.0000080000 0.0011780000 42699997 96830484 509673472 3.8547027111 4.0523405075 3.8067142963 1977 1311867236.3897418976 0.1135792658 0.0913645380 0.1207853556 0.0059771107 0.0115010000 0.0004160000 0.0036140000 0.0000040000 0.0000040000 0.0019850000 42703669 96830484 509673472 3.8536279202 4.0521636009 3.8076999187 1978 1311867236.4243390560 0.1123831868 0.0913751642 0.1207853556 0.0059778392 0.0108630000 0.0004030000 0.0043850000 0.0000000000 0.0000050000 0.0010530000 42707397 96830484 509673472 3.8544723988 4.0519447327 3.8094069958 1979 1311867236.4566040039 0.1117865890 0.0913854782 0.1207853556 0.0059769503 0.0135920000 0.0004980000 0.0028630000 0.0000100000 0.0000100000 0.0014420000 42711125 96830484 509673472 3.8551120758 4.0520491600 3.8107130527 1980 1311867236.4936130047 0.1135963053 0.0913966958 0.1207853556 0.0059815564 0.0113830000 0.0004150000 0.0044430000 0.0000000000 0.0000050000 0.0010610000 42714909 96830484 509673472 3.8530008793 4.0514082909 3.8122851849 1981 1311867236.5246999264 0.1127516478 0.0914074757 0.1207853556 0.0059801145 0.0100290000 0.0003980000 0.0026360000 0.0000030000 0.0000040000 0.0019560000 42718581 96830484 509673472 3.8545825481 4.0522804260 3.8142085075 1982 1311867236.5602099895 0.1131970212 0.0914184694 0.1207853556 0.0059798518 0.0159920000 0.0005090000 0.0047120000 0.0000020000 0.0000110000 0.0012980000 42722365 96830484 509673472 3.8535861969 4.0519089699 3.8158590794 1983 1311867236.5972909927 0.1128514856 0.0914292778 0.1207853556 0.0059785355 0.0108040000 0.0004310000 0.0033960000 0.0000050000 0.0000050000 0.0013450000 42726149 96830484 509673472 3.8539628983 4.0513868332 3.8175439835 1984 1311867236.6246581078 0.1136894673 0.0914404976 0.1207853556 0.0059771351 0.0109990000 0.0004070000 0.0044170000 0.0000000000 0.0000040000 0.0010430000 42729653 96830484 509673472 3.8529510498 4.0507183075 3.8192582130 1985 1311867236.6600480080 0.1140710488 0.0914518984 0.1207853556 0.0059756545 0.0108250000 0.0004050000 0.0033710000 0.0000040000 0.0000030000 0.0019540000 42733437 96830484 509673472 3.8530654907 4.0517525673 3.8216803074 1986 1311867236.6956660748 0.1138073951 0.0914631550 0.1207853556 0.0059750802 0.0108310000 0.0004100000 0.0044340000 0.0000010000 0.0000040000 0.0010350000 42737221 96830484 509673472 3.8535203934 4.0524230003 3.8238904476 1987 1311867236.7276370525 0.1136702374 0.0914743311 0.1207853556 0.0059739138 0.0097300000 0.0004020000 0.0030100000 0.0000040000 0.0000030000 0.0013070000 42740837 96830484 509673472 3.8534357548 4.0515847206 3.8258676529 1988 1311867236.7619268894 0.1133151948 0.0914853175 0.1207853556 0.0059733469 0.0098890000 0.0004020000 0.0033650000 0.0000010000 0.0000040000 0.0010420000 42744565 96830484 509673472 3.8539202213 4.0508613586 3.8280432224 1989 1311867236.7923469543 0.1145382449 0.0914969077 0.1207853556 0.0059742494 0.0120690000 0.0004030000 0.0044560000 0.0000040000 0.0000030000 0.0019460000 42748181 96830484 509673472 3.8529052734 4.0508518219 3.8302612305 1990 1311867236.8255391121 0.1143938005 0.0915084137 0.1207853556 0.0059734326 0.0111180000 0.0004040000 0.0044490000 0.0000010000 0.0000040000 0.0010410000 42751965 96830484 509673472 3.8526041508 4.0504832268 3.8321213722 1991 1311867236.8583440781 0.1141253263 0.0915197733 0.1207853556 0.0059727067 0.0113530000 0.0004020000 0.0044590000 0.0000040000 0.0000030000 0.0013180000 42755581 96830484 509673472 3.8530597687 4.0505218506 3.8341383934 1992 1311867236.8928480148 0.1133572236 0.0915307358 0.1207853556 0.0059722220 0.0110350000 0.0004090000 0.0044430000 0.0000000000 0.0000040000 0.0010330000 42759309 96830484 509673472 3.8533253670 4.0491628647 3.8358998299 1993 1311867236.9255330563 0.1126603782 0.0915413378 0.1207853556 0.0059709283 0.0118630000 0.0004050000 0.0044570000 0.0000030000 0.0000030000 0.0019300000 42762981 96830484 509673472 3.8539071083 4.0487608910 3.8378202915 1994 1311867236.9581959248 0.1135519594 0.0915523762 0.1207853556 0.0059695794 0.0108120000 0.0004080000 0.0041060000 0.0000010000 0.0000040000 0.0010370000 42766653 96830484 509673472 3.8530726433 4.0488767624 3.8403108120 1995 1311867236.9937291145 0.1123130843 0.0915627826 0.1207853556 0.0059722659 0.0092730000 0.0004050000 0.0023290000 0.0000040000 0.0000040000 0.0013150000 42770437 96830484 509673472 3.8539915085 4.0504922867 3.8425998688 1996 1311867237.0244200230 0.1126908362 0.0915733678 0.1207853556 0.0059710648 0.0120630000 0.0004080000 0.0050150000 0.0000000000 0.0000040000 0.0010400000 42774053 96830484 509673472 3.8528690338 4.0498070717 3.8448443413 1997 1311867237.0603060722 0.1119089350 0.0915835508 0.1207853556 0.0059742138 0.0123050000 0.0004050000 0.0046030000 0.0000040000 0.0000040000 0.0019220000 42777837 96830484 509673472 3.8527648449 4.0501022339 3.8467838764 1998 1311867237.0927588940 0.1112482548 0.0915933930 0.1207853556 0.0059848709 0.0107310000 0.0004150000 0.0041090000 0.0000000000 0.0000040000 0.0010290000 42781565 96830484 509673472 3.8540725708 4.0512480736 3.8490130901 1999 1311867237.1276650429 0.1107348278 0.0916029685 0.1207853556 0.0059843317 0.0114650000 0.0004200000 0.0044660000 0.0000040000 0.0000040000 0.0013080000 42785293 96830484 509673472 3.8535602093 4.0496335030 3.8506541252 2000 1311867237.1566579342 0.1126984581 0.0916135163 0.1207853556 0.0059831364 0.0112160000 0.0004110000 0.0044450000 0.0000010000 0.0000040000 0.0010280000 42788853 96830484 509673472 3.8501732349 4.0497317314 3.8522825241 2001 1311867237.1925950050 0.1118543968 0.0916236316 0.1207853556 0.0059823293 0.0105750000 0.0004100000 0.0030220000 0.0000040000 0.0000040000 0.0019160000 42792637 96830484 509673472 3.8506307602 4.0496134758 3.8540077209 2002 1311867237.2254281044 0.1110569313 0.0916333386 0.1207853556 0.0059809958 0.0111470000 0.0004090000 0.0044690000 0.0000000000 0.0000040000 0.0010300000 42796365 96830484 509673472 3.8512568474 4.0481963158 3.8554427624 2003 1311867237.2569580078 0.1119892523 0.0916435013 0.1207853556 0.0059803435 0.0114230000 0.0004170000 0.0044620000 0.0000040000 0.0000040000 0.0013100000 42800037 96830484 509673472 3.8488326073 4.0470933914 3.8568859100 2004 1311867237.2944281101 0.1120812967 0.0916536998 0.1207853556 0.0059790427 0.0110450000 0.0004070000 0.0044760000 0.0000010000 0.0000040000 0.0010250000 42803821 96830484 509673472 3.8484485149 4.0486583710 3.8585417271 2005 1311867237.3250501156 0.1105897278 0.0916631442 0.1207853556 0.0059777971 0.0118380000 0.0004130000 0.0041090000 0.0000040000 0.0000040000 0.0019340000 42807493 96830484 509673472 3.8500509262 4.0483565331 3.8600273132 2006 1311867237.3565309048 0.1117355675 0.0916731504 0.1207853556 0.0059785579 0.0112660000 0.0004080000 0.0044720000 0.0000000000 0.0000030000 0.0010320000 42811165 96830484 509673472 3.8483505249 4.0472736359 3.8617861271 2007 1311867237.3934979439 0.1106787920 0.0916826201 0.1207853556 0.0059777386 0.0114420000 0.0004150000 0.0044590000 0.0000040000 0.0000040000 0.0012990000 42814893 96830484 509673472 3.8491725922 4.0488214493 3.8635830879 2008 1311867237.4248709679 0.1108372882 0.0916921592 0.1207853556 0.0059765305 0.0112080000 0.0004230000 0.0044600000 0.0000000000 0.0000040000 0.0010290000 42818621 96830484 509673472 3.8483595848 4.0473980904 3.8653459549 2009 1311867237.4579510689 0.1101527587 0.0917013482 0.1207853556 0.0059752938 0.0106720000 0.0004200000 0.0030440000 0.0000030000 0.0000030000 0.0019240000 42822293 96830484 509673472 3.8485321999 4.0457334518 3.8668816090 2010 1311867237.4933559895 0.1115317345 0.0917112141 0.1207853556 0.0059757413 0.0101720000 0.0004370000 0.0034040000 0.0000010000 0.0000040000 0.0010250000 42826077 96830484 509673472 3.8469088078 4.0475955009 3.8692066669 2011 1311867237.5253219604 0.1086336821 0.0917196290 0.1207853556 0.0059782280 0.0116430000 0.0004240000 0.0045020000 0.0000040000 0.0000040000 0.0013090000 42829749 96830484 509673472 3.8497915268 4.0461120605 3.8709003925 2012 1311867237.5581231117 0.1092857048 0.0917283597 0.1207853556 0.0059771530 0.0112240000 0.0004210000 0.0044940000 0.0000010000 0.0000040000 0.0010270000 42833477 96830484 509673472 3.8487095833 4.0447492599 3.8726165295 2013 1311867237.5925350189 0.1107949167 0.0917378314 0.1207853556 0.0059793840 0.0120810000 0.0004190000 0.0045060000 0.0000040000 0.0000040000 0.0019070000 42837149 96830484 509673472 3.8473846912 4.0458903313 3.8750984669 2014 1311867237.6261129379 0.1106917411 0.0917472425 0.1207853556 0.0059780304 0.0104890000 0.0004280000 0.0037900000 0.0000010000 0.0000040000 0.0010290000 42840933 96830484 509673472 3.8470985889 4.0451135635 3.8770403862 2015 1311867237.6569290161 0.1108758524 0.0917567356 0.1207853556 0.0059772726 0.0114920000 0.0004220000 0.0045090000 0.0000040000 0.0000040000 0.0013020000 42844549 96830484 509673472 3.8462750912 4.0435762405 3.8789005280 2016 1311867237.6925010681 0.1102862805 0.0917659268 0.1207853556 0.0059758856 0.0097530000 0.0004260000 0.0030660000 0.0000000000 0.0000040000 0.0010260000 42848277 96830484 509673472 3.8471572399 4.0440998077 3.8810398579 2017 1311867237.7243609428 0.1109095812 0.0917754180 0.1207853556 0.0059745096 0.0118100000 0.0004230000 0.0041540000 0.0000040000 0.0000040000 0.0018980000 42851949 96830484 509673472 3.8467302322 4.0440616608 3.8832979202 2018 1311867237.7617940903 0.1098656654 0.0917843824 0.1207853556 0.0059731757 0.0112780000 0.0004230000 0.0045180000 0.0000000000 0.0000040000 0.0010190000 42855845 96830484 509673472 3.8471198082 4.0422897339 3.8852386475 2019 1311867237.7926809788 0.1097561866 0.0917932837 0.1207853556 0.0059721665 0.0105400000 0.0004220000 0.0032510000 0.0000040000 0.0000030000 0.0013060000 42859405 96830484 509673472 3.8472278118 4.0433735847 3.8877799511 2020 1311867237.8255820274 0.1099708527 0.0918022825 0.1207853556 0.0059711687 0.0114300000 0.0004710000 0.0045300000 0.0000000000 0.0000040000 0.0010150000 42863133 96830484 509673472 3.8467130661 4.0436096191 3.8901410103 2021 1311867237.8612699509 0.1088673323 0.0918107264 0.1207853556 0.0059703454 0.0107150000 0.0004230000 0.0030780000 0.0000040000 0.0000040000 0.0019010000 42866973 96830484 509673472 3.8475019932 4.0428876877 3.8920662403 2022 1311867237.8926060200 0.1097273752 0.0918195873 0.1207853556 0.0059702717 0.0101850000 0.0004260000 0.0034370000 0.0000010000 0.0000040000 0.0010200000 42870589 96830484 509673472 3.8462495804 4.0434775352 3.8948600292 2023 1311867237.9253590107 0.1089982316 0.0918280789 0.1207853556 0.0059698143 0.0116950000 0.0004270000 0.0045530000 0.0000040000 0.0000030000 0.0012970000 42874205 96830484 509673472 3.8474411964 4.0427885056 3.8971071243 2024 1311867237.9613509178 0.1090156138 0.0918365708 0.1207853556 0.0059690288 0.0112910000 0.0004290000 0.0045110000 0.0000010000 0.0000040000 0.0010110000 42877989 96830484 509673472 3.8466374874 4.0418515205 3.8990707397 2025 1311867237.9928910732 0.1081641316 0.0918446338 0.1207853556 0.0059679681 0.0121860000 0.0004270000 0.0045250000 0.0000040000 0.0000040000 0.0018830000 42881661 96830484 509673472 3.8481822014 4.0420055389 3.9013216496 2026 1311867238.0245919228 0.1085637137 0.0918528860 0.1207853556 0.0059675555 0.0105300000 0.0004300000 0.0038070000 0.0000010000 0.0000040000 0.0010210000 42885277 96830484 509673472 3.8480391502 4.0426216125 3.9036617279 2027 1311867238.0607950687 0.1088457480 0.0918612693 0.1207853556 0.0059665507 0.0104220000 0.0004260000 0.0034580000 0.0000040000 0.0000040000 0.0012880000 42889061 96830484 509673472 3.8475883007 4.0411691666 3.9058365822 2028 1311867238.0932629108 0.1082268283 0.0918693391 0.1207853556 0.0059656237 0.0112420000 0.0004290000 0.0045500000 0.0000010000 0.0000040000 0.0010000000 42892733 96830484 509673472 3.8474221230 4.0388746262 3.9074563980 2029 1311867238.1251931190 0.1102530137 0.0918783996 0.1207853556 0.0059670178 0.0107960000 0.0004310000 0.0030980000 0.0000040000 0.0000040000 0.0018760000 42896405 96830484 509673472 3.8464112282 4.0409922600 3.9100730419 2030 1311867238.1608469486 0.1089750007 0.0918868215 0.1207853556 0.0059708263 0.0105390000 0.0004300000 0.0038310000 0.0000010000 0.0000040000 0.0010000000 42900189 96830484 509673472 3.8487234116 4.0414781570 3.9126367569 2031 1311867238.1928510666 0.1088091433 0.0918951535 0.1207853556 0.0059753260 0.0117330000 0.0004320000 0.0045480000 0.0000030000 0.0000030000 0.0012720000 42903861 96830484 509673472 3.8486361504 4.0407123566 3.9146518707 2032 1311867238.2246770859 0.1090383902 0.0919035902 0.1207853556 0.0059743126 0.0112850000 0.0004250000 0.0045470000 0.0000010000 0.0000040000 0.0010010000 42907533 96830484 509673472 3.8492271900 4.0414795876 3.9170980453 2033 1311867238.2605938911 0.1087719128 0.0919118874 0.1207853556 0.0059743874 0.0122220000 0.0004370000 0.0045960000 0.0000040000 0.0000040000 0.0018710000 42911317 96830484 509673472 3.8502454758 4.0408644676 3.9193584919 2034 1311867238.2926790714 0.1081297100 0.0919198608 0.1207853556 0.0059792473 0.0114060000 0.0004340000 0.0045840000 0.0000000000 0.0000050000 0.0009980000 42914933 96830484 509673472 3.8512041569 4.0384130478 3.9213838577 2035 1311867238.3257811069 0.1094604507 0.0919284803 0.1207853556 0.0059900934 0.0116380000 0.0004310000 0.0045810000 0.0000040000 0.0000040000 0.0012820000 42918717 96830484 509673472 3.8503699303 4.0394992828 3.9239137173 2036 1311867238.3604390621 0.1079294756 0.0919363393 0.1207853556 0.0059888762 0.0113210000 0.0004380000 0.0045700000 0.0000010000 0.0000040000 0.0010050000 42922445 96830484 509673472 3.8535180092 4.0390219688 3.9261376858 2037 1311867238.3936378956 0.1071736366 0.0919438196 0.1207853556 0.0059907029 0.0107050000 0.0004270000 0.0031090000 0.0000040000 0.0000030000 0.0018560000 42926173 96830484 509673472 3.8542940617 4.0374126434 3.9280622005 2038 1311867238.4264049530 0.1082091928 0.0919518006 0.1207853556 0.0059930421 0.0113620000 0.0004300000 0.0045880000 0.0000010000 0.0000050000 0.0010000000 42929845 96830484 509673472 3.8535315990 4.0361194611 3.9300312996 2039 1311867238.4616210461 0.1092788726 0.0919602984 0.1207853556 0.0059919283 0.0116080000 0.0004380000 0.0045920000 0.0000030000 0.0000030000 0.0012780000 42933629 96830484 509673472 3.8531908989 4.0367355347 3.9325709343 2040 1311867238.4932549000 0.1079973876 0.0919681597 0.1207853556 0.0059955129 0.0099510000 0.0004420000 0.0031090000 0.0000000000 0.0000030000 0.0010070000 42937189 96830484 509673472 3.8546426296 4.0357604027 3.9345803261 2041 1311867238.5248661041 0.1072067916 0.0919756260 0.1207853556 0.0059945395 0.0122470000 0.0004370000 0.0045780000 0.0000030000 0.0000040000 0.0018520000 42940917 96830484 509673472 3.8560864925 4.0338830948 3.9366357327 2042 1311867238.5605928898 0.1057906151 0.0919823914 0.1207853556 0.0060000905 0.0113570000 0.0004390000 0.0045970000 0.0000010000 0.0000040000 0.0010000000 42944701 96830484 509673472 3.8584895134 4.0340199471 3.9391899109 2043 1311867238.5929119587 0.1062972173 0.0919893982 0.1207853556 0.0060044370 0.0115990000 0.0004310000 0.0045880000 0.0000040000 0.0000030000 0.0012620000 42948317 96830484 509673472 3.8581211567 4.0326757431 3.9416761398 2044 1311867238.6249868870 0.1047250405 0.0919956289 0.1207853556 0.0060034535 0.0112960000 0.0004400000 0.0045820000 0.0000000000 0.0000040000 0.0009990000 42952045 96830484 509673472 3.8601114750 4.0319447517 3.9439966679 2045 1311867238.6608479023 0.1051496044 0.0920020612 0.1207853556 0.0060025356 0.0122060000 0.0004340000 0.0046110000 0.0000040000 0.0000040000 0.0018320000 42955829 96830484 509673472 3.8602142334 4.0321497917 3.9469227791 2046 1311867238.6929359436 0.1046469063 0.0920082415 0.1207853556 0.0060017516 0.0114410000 0.0004400000 0.0045980000 0.0000000000 0.0000040000 0.0009930000 42959501 96830484 509673472 3.8605158329 4.0314440727 3.9496967793 2047 1311867238.7246360779 0.1051036343 0.0920146388 0.1207853556 0.0060021868 0.0116350000 0.0004400000 0.0046100000 0.0000040000 0.0000030000 0.0012650000 42963117 96830484 509673472 3.8607311249 4.0307493210 3.9526596069 2048 1311867238.7627971172 0.1038375273 0.0920204117 0.1207853556 0.0060009325 0.0098740000 0.0004350000 0.0031260000 0.0000000000 0.0000050000 0.0009850000 42966957 96830484 509673472 3.8615956306 4.0311975479 3.9556806087 2049 1311867238.7949919701 0.1033571512 0.0920259445 0.1207853556 0.0059996337 0.0123190000 0.0004340000 0.0046110000 0.0000040000 0.0000030000 0.0018260000 43167293 96830484 509673472 3.8629956245 4.0309557915 3.9588215351 2050 1311867238.8246819973 0.1034516916 0.0920315181 0.1207853556 0.0060024210 0.0096580000 0.0004410000 0.0027590000 0.0000000000 0.0000040000 0.0009860000 43580453 96830484 509673472 3.8627603054 4.0292563438 3.9616770744 2051 1311867238.8630580902 0.1039604172 0.0920373342 0.1207853556 0.0060013371 0.0099240000 0.0004390000 0.0027800000 0.0000030000 0.0000040000 0.0012580000 43584349 96830484 509673472 3.8619482517 4.0298571587 3.9649705887 2052 1311867238.8933889866 0.1035852954 0.0920429619 0.1207853556 0.0060000601 0.0264040000 0.0006470000 0.0051340000 0.0000020000 0.0000170000 0.0014790000 43587965 96830484 509673472 3.8628513813 4.0300498009 3.9681954384 2053 1311867238.9278979301 0.1018833220 0.0920477550 0.1207853556 0.0059996364 0.0149720000 0.0005480000 0.0047980000 0.0000060000 0.0000060000 0.0018920000 43591749 96830484 509673472 3.8653950691 4.0286221504 3.9712533951 2054 1311867238.9628050327 0.1027391106 0.0920529602 0.1207853556 0.0059998825 0.0107810000 0.0004510000 0.0039240000 0.0000000000 0.0000050000 0.0009750000 43595533 96830484 509673472 3.8632185459 4.0265798569 3.9740045071 2055 1311867238.9937820435 0.1030431464 0.0920583082 0.1207853556 0.0059997811 0.0094700000 0.0004400000 0.0024080000 0.0000040000 0.0000030000 0.0012420000 43599093 96830484 509673472 3.8638684750 4.0272531509 3.9775044918 2056 1311867239.0287299156 0.1021484509 0.0920632159 0.1207853556 0.0060032856 0.0102580000 0.0004440000 0.0035150000 0.0000010000 0.0000040000 0.0009720000 43602877 96830484 509673472 3.8655509949 4.0271968842 3.9804840088 2057 1311867239.0619978905 0.1015072986 0.0920678071 0.1207853556 0.0060049468 0.0226540000 0.0006150000 0.0039890000 0.0000150000 0.0000150000 0.0024860000 43606661 96830484 509673472 3.8653144836 4.0250763893 3.9835140705 2058 1311867239.0939240456 0.1026305258 0.0920729396 0.1207853556 0.0060051438 0.0133140000 0.0005320000 0.0047660000 0.0000010000 0.0000050000 0.0009820000 43610221 96830484 509673472 3.8646121025 4.0257973671 3.9870502949 2059 1311867239.1358110905 0.1013920158 0.0920774656 0.1207853556 0.0060041939 0.0117520000 0.0004980000 0.0046740000 0.0000040000 0.0000040000 0.0012250000 43614173 96830484 509673472 3.8660032749 4.0251808167 3.9903740883 2060 1311867239.1620550156 0.1012564451 0.0920819214 0.1207853556 0.0060036983 0.0112940000 0.0004400000 0.0046610000 0.0000000000 0.0000030000 0.0009530000 43617677 96830484 509673472 3.8665273190 4.0239973068 3.9934377670 2061 1311867239.1936569214 0.1019528881 0.0920867108 0.1207853556 0.0060028026 0.0106560000 0.0004380000 0.0031690000 0.0000040000 0.0000040000 0.0017660000 43621293 96830484 509673472 3.8665781021 4.0234560966 3.9969203472 2062 1311867239.2294950485 0.1016325057 0.0920913402 0.1207853556 0.0060017074 0.0147850000 0.0005360000 0.0045520000 0.0000010000 0.0000090000 0.0010750000 43625077 96830484 509673472 3.8674817085 4.0230908394 4.0004749298 2063 1311867239.2609150410 0.1010392234 0.0920956775 0.1207853556 0.0060011765 0.0118710000 0.0004550000 0.0047130000 0.0000040000 0.0000050000 0.0012250000 43628749 96830484 509673472 3.8689048290 4.0212521553 4.0037426949 2064 1311867239.2928791046 0.1022479311 0.0921005962 0.1207853556 0.0059999297 0.0106100000 0.0004420000 0.0039300000 0.0000010000 0.0000040000 0.0009490000 43632365 96830484 509673472 3.8680720329 4.0196189880 4.0072298050 2065 1311867239.3295290470 0.1017866284 0.0921052868 0.1207853556 0.0059985826 0.0159050000 0.0005350000 0.0049680000 0.0000080000 0.0000080000 0.0019440000 43636205 96830484 509673472 3.8694067001 4.0195631981 4.0107769966 2066 1311867239.3615000248 0.1012913138 0.0921097331 0.1207853556 0.0059981823 0.0116320000 0.0004540000 0.0047200000 0.0000000000 0.0000040000 0.0009590000 43639877 96830484 509673472 3.8709511757 4.0181536674 4.0140395164 2067 1311867239.3928411007 0.1014236361 0.0921142391 0.1207853556 0.0059979109 0.0116290000 0.0004390000 0.0046830000 0.0000040000 0.0000040000 0.0012040000 43643549 96830484 509673472 3.8713564873 4.0158476830 4.0170698166 2068 1311867239.4293289185 0.1010211110 0.0921185461 0.1207853556 0.0060008834 0.0105460000 0.0004410000 0.0039180000 0.0000010000 0.0000040000 0.0009480000 43647277 96830484 509673472 3.8727498055 4.0152812004 4.0202999115 2069 1311867239.4619059563 0.1010744199 0.0921228747 0.1207853556 0.0060031602 0.0110080000 0.0004400000 0.0035410000 0.0000030000 0.0000030000 0.0017490000 43651061 96830484 509673472 3.8733499050 4.0133252144 4.0233035088 2070 1311867239.4938249588 0.1006310135 0.0921269849 0.1207853556 0.0060021486 0.0110510000 0.0004390000 0.0042900000 0.0000000000 0.0000030000 0.0009550000 43654677 96830484 509673472 3.8747553825 4.0113873482 4.0260653496 2071 1311867239.5295019150 0.1005866975 0.0921310698 0.1207853556 0.0060037524 0.0117210000 0.0004370000 0.0046650000 0.0000040000 0.0000040000 0.0012250000 43658461 96830484 509673472 3.8755981922 4.0099744797 4.0288119316 2072 1311867239.5617070198 0.1011270657 0.0921354114 0.1207853556 0.0060092125 0.0141480000 0.0005310000 0.0033980000 0.0000020000 0.0000120000 0.0010720000 43662133 96830484 509673472 3.8756864071 4.0101919174 4.0319423676 2073 1311867239.5944910049 0.1001185477 0.0921392625 0.1207853556 0.0060081351 0.0145380000 0.0005530000 0.0037430000 0.0000080000 0.0000080000 0.0019430000 43665805 96830484 509673472 3.8782422543 4.0082521439 4.0348458290 2074 1311867239.6284430027 0.0998616666 0.0921429859 0.1207853556 0.0060145381 0.0114640000 0.0004560000 0.0045630000 0.0000000000 0.0000040000 0.0009550000 43669533 96830484 509673472 3.8784735203 4.0059576035 4.0374140739 2075 1311867239.6623089314 0.0999818444 0.0921467637 0.1207853556 0.0060135467 0.0154740000 0.0005380000 0.0049290000 0.0000090000 0.0000080000 0.0013360000 43673317 96830484 509673472 3.8796420097 4.0062246323 4.0404729843 2076 1311867239.6931240559 0.1000047475 0.0921505488 0.1207853556 0.0060241017 0.0100320000 0.0004580000 0.0028190000 0.0000010000 0.0000050000 0.0009660000 43676877 96830484 509673472 3.8810219765 4.0064821243 4.0434889793 2077 1311867239.7284948826 0.0999688059 0.0921543130 0.1207853556 0.0060241580 0.0113160000 0.0004390000 0.0039040000 0.0000040000 0.0000040000 0.0017600000 43680661 96830484 509673472 3.8816232681 4.0056447983 4.0462317467 2078 1311867239.7614610195 0.0993219465 0.0921577623 0.1207853556 0.0060233520 0.0102460000 0.0004400000 0.0035180000 0.0000010000 0.0000050000 0.0009530000 43684445 96830484 509673472 3.8828389645 4.0048828125 4.0489163399 2079 1311867239.7926149368 0.0989624783 0.0921610354 0.1207853556 0.0060221693 0.0102390000 0.0004410000 0.0031550000 0.0000040000 0.0000040000 0.0012240000 43688005 96830484 509673472 3.8840100765 4.0062899590 4.0520043373 2080 1311867239.8308320045 0.0983053371 0.0921639894 0.1207853556 0.0060220263 0.0153120000 0.0005380000 0.0036520000 0.0000020000 0.0000110000 0.0014650000 43691901 96830484 509673472 3.8846058846 4.0050935745 4.0547494888 2081 1311867239.8608438969 0.0972693041 0.0921664427 0.1207853556 0.0060291764 0.0126270000 0.0005080000 0.0046980000 0.0000040000 0.0000040000 0.0017360000 43695517 96830484 509673472 3.8857967854 4.0043358803 4.0576038361 2082 1311867239.8929069042 0.0973794088 0.0921689465 0.1207853556 0.0060310513 0.0115360000 0.0004380000 0.0046670000 0.0000000000 0.0000030000 0.0009360000 43699189 96830484 509673472 3.8860652447 4.0042557716 4.0607194901 2083 1311867239.9306600094 0.0968972817 0.0921712165 0.1207853556 0.0060314749 0.0098150000 0.0004420000 0.0026820000 0.0000040000 0.0000040000 0.0012110000 43703029 96830484 509673472 3.8862137794 4.0033106804 4.0634708405 2084 1311867239.9613699913 0.0970130786 0.0921735398 0.1207853556 0.0060328878 0.0115550000 0.0004440000 0.0046900000 0.0000010000 0.0000040000 0.0009300000 43706701 96830484 509673472 3.8866059780 4.0035881996 4.0664720535 2085 1311867239.9948220253 0.0961918980 0.0921754671 0.1207853556 0.0060315945 0.0110690000 0.0004440000 0.0035650000 0.0000030000 0.0000040000 0.0017090000 43710373 96830484 509673472 3.8875989914 4.0026369095 4.0692739487 2086 1311867240.0292289257 0.0961503461 0.0921773726 0.1207853556 0.0060313033 0.0140880000 0.0005400000 0.0030410000 0.0000020000 0.0000100000 0.0010860000 43714101 96830484 509673472 3.8872313499 4.0015788078 4.0719866753 2087 1311867240.0618810654 0.0957001969 0.0921790606 0.1207853556 0.0060303844 0.0155450000 0.0005390000 0.0049500000 0.0000080000 0.0000080000 0.0013200000 43717829 96830484 509673472 3.8886775970 4.0020451546 4.0747394562 2088 1311867240.0945510864 0.0958138034 0.0921808013 0.1207853556 0.0060295731 0.0099760000 0.0004720000 0.0028440000 0.0000010000 0.0000040000 0.0009230000 43721445 96830484 509673472 3.8882427216 4.0019264221 4.0774550438 2089 1311867240.1297509670 0.0954619274 0.0921823720 0.1207853556 0.0060284302 0.0122130000 0.0004430000 0.0046980000 0.0000040000 0.0000040000 0.0017050000 43725229 96830484 509673472 3.8894598484 4.0014810562 4.0804967880 2090 1311867240.1617240906 0.0960810781 0.0921842374 0.1207853556 0.0060280108 0.0107030000 0.0004540000 0.0039600000 0.0000000000 0.0000050000 0.0009230000 43728901 96830484 509673472 3.8893220425 4.0019388199 4.0837607384 2091 1311867240.1963129044 0.0965367034 0.0921863190 0.1207853556 0.0060271082 0.0154930000 0.0005430000 0.0042220000 0.0000100000 0.0000100000 0.0013140000 43732685 96830484 509673472 3.8888473511 4.0011029243 4.0863466263 2092 1311867240.2291030884 0.0961544812 0.0921882158 0.1207853556 0.0060257006 0.0101070000 0.0004520000 0.0028500000 0.0000010000 0.0000050000 0.0009190000 43736357 96830484 509673472 3.8904578686 4.0008273125 4.0890665054 2093 1311867240.2612760067 0.0945842415 0.0921893606 0.1207853556 0.0060257369 0.0102340000 0.0004460000 0.0027000000 0.0000040000 0.0000030000 0.0016830000 43740085 96830484 509673472 3.8935334682 4.0012221336 4.0917735100 2094 1311867240.2981250286 0.0952471569 0.0921908208 0.1207853556 0.0060244267 0.0140860000 0.0005400000 0.0041790000 0.0000020000 0.0000080000 0.0010440000 43743701 96830484 509673472 3.8931162357 4.0005831718 4.0944771767 2095 1311867240.3289160728 0.0957516506 0.0921925205 0.1207853556 0.0060252440 0.0120170000 0.0004580000 0.0047300000 0.0000040000 0.0000040000 0.0011930000 43747373 96830484 509673472 3.8923223019 3.9994790554 4.0969648361 2096 1311867240.3609399796 0.0951704234 0.0921939413 0.1207853556 0.0060244246 0.0154490000 0.0005410000 0.0049660000 0.0000010000 0.0000080000 0.0010380000 43751101 96830484 509673472 3.8934185505 3.9984643459 4.0994849205 2097 1311867240.3967890739 0.0944512263 0.0921950177 0.1207853556 0.0060234465 0.0128030000 0.0004600000 0.0047300000 0.0000050000 0.0000050000 0.0018370000 43754773 96830484 509673472 3.8951766491 3.9979183674 4.1018838882 2098 1311867240.4286890030 0.0937027261 0.0921957363 0.1207853556 0.0060224411 0.0140580000 0.0005480000 0.0030350000 0.0000010000 0.0000110000 0.0010530000 43758333 96830484 509673472 3.8959720135 3.9957802296 4.1039705276 2099 1311867240.4650850296 0.0935100541 0.0921963625 0.1207853556 0.0060253999 0.0122360000 0.0004600000 0.0047390000 0.0000040000 0.0000040000 0.0011770000 43762173 96830484 509673472 3.8959703445 3.9943695068 4.1061048508 2100 1311867240.4972898960 0.0939430818 0.0921971943 0.1207853556 0.0060293560 0.0103220000 0.0004480000 0.0035660000 0.0000000000 0.0000040000 0.0009090000 43765845 96830484 509673472 3.8957934380 3.9940836430 4.1082506180 2101 1311867240.5309979916 0.0930234790 0.0921975876 0.1207853556 0.0060323708 0.0114570000 0.0004440000 0.0039380000 0.0000040000 0.0000040000 0.0016850000 43769573 96830484 509673472 3.8972959518 3.9924731255 4.1100339890 2102 1311867240.5608210564 0.0921826512 0.0921975804 0.1207853556 0.0060310176 0.0097520000 0.0004450000 0.0028070000 0.0000010000 0.0000040000 0.0009030000 43773189 96830484 509673472 3.8982098103 3.9921960831 4.1118025780 2103 1311867240.5965991020 0.0917131528 0.0921973501 0.1207853556 0.0060300038 0.0143050000 0.0005360000 0.0034100000 0.0000080000 0.0000090000 0.0012850000 43776973 96830484 509673472 3.8994228840 3.9913005829 4.1134233475 2104 1311867240.6290791035 0.0918911323 0.0921972046 0.1207853556 0.0060307801 0.0118350000 0.0004550000 0.0047320000 0.0000010000 0.0000040000 0.0009110000 43780645 96830484 509673472 3.8991441727 3.9892907143 4.1147685051 2105 1311867240.6622560024 0.0908187702 0.0921965497 0.1207853556 0.0060339605 0.0121850000 0.0004410000 0.0046950000 0.0000040000 0.0000040000 0.0016630000 43784317 96830484 509673472 3.9002830982 3.9886741638 4.1161108017 2106 1311867240.6968801022 0.0916216150 0.0921962767 0.1207853556 0.0060325755 0.0095760000 0.0004510000 0.0028150000 0.0000010000 0.0000050000 0.0009080000 43788045 96830484 509673472 3.8983643055 3.9883131981 4.1174044609 2107 1311867240.7291979790 0.0910094082 0.0921957134 0.1207853556 0.0060337511 0.0102470000 0.0004520000 0.0031820000 0.0000040000 0.0000040000 0.0011790000 43791717 96830484 509673472 3.8988761902 3.9886724949 4.1185970306 2108 1311867240.7625629902 0.0908259526 0.0921950636 0.1207853556 0.0060331030 0.0114080000 0.0004480000 0.0046840000 0.0000000000 0.0000050000 0.0009040000 43795389 96830484 509673472 3.8991720676 3.9887881279 4.1201872826 2109 1311867240.7965719700 0.0896683112 0.0921938655 0.1207853556 0.0060323764 0.0150440000 0.0005400000 0.0045640000 0.0000080000 0.0000080000 0.0018270000 43799173 96830484 509673472 3.8998715878 3.9884030819 4.1214799881 2110 1311867240.8293309212 0.0895564407 0.0921926156 0.1207853556 0.0060312366 0.0151060000 0.0005500000 0.0030500000 0.0000010000 0.0000110000 0.0011540000 43802845 96830484 509673472 3.8989012241 3.9889678955 4.1232728958 2111 1311867240.8621098995 0.0887509212 0.0921909852 0.1207853556 0.0060301775 0.0144370000 0.0005630000 0.0030590000 0.0000100000 0.0000100000 0.0012890000 43806573 96830484 509673472 3.8994164467 3.9893438816 4.1250457764 2112 1311867240.8973500729 0.0881574899 0.0921890754 0.1207853556 0.0060292369 0.0119690000 0.0004620000 0.0047680000 0.0000000000 0.0000040000 0.0009070000 43810357 96830484 509673472 3.8993797302 3.9898481369 4.1271533966 2113 1311867240.9290270805 0.0876518339 0.0921869281 0.1207853556 0.0060280549 0.0111770000 0.0004460000 0.0035920000 0.0000030000 0.0000030000 0.0016540000 43813973 96830484 509673472 3.8993062973 3.9906568527 4.1293592453 2114 1311867240.9614369869 0.0876336470 0.0921847743 0.1207853556 0.0060266803 0.0096490000 0.0004440000 0.0028460000 0.0000000000 0.0000040000 0.0008900000 43817645 96830484 509673472 3.8990182877 3.9912807941 4.1315860748 2115 1311867240.9968450069 0.0871165693 0.0921823779 0.1207853556 0.0060255450 0.0158310000 0.0005420000 0.0050200000 0.0000080000 0.0000080000 0.0012820000 43821485 96830484 509673472 3.8988499641 3.9912972450 4.1339030266 2116 1311867241.0315620899 0.0870976523 0.0921799749 0.1207853556 0.0060264605 0.0114010000 0.0004660000 0.0042720000 0.0000000000 0.0000040000 0.0008910000 43825213 96830484 509673472 3.8973090649 3.9921486378 4.1365280151 2117 1311867241.0633668900 0.0873224735 0.0921776804 0.1207853556 0.0060333209 0.0107760000 0.0004470000 0.0032320000 0.0000040000 0.0000040000 0.0016240000 43828773 96830484 509673472 3.8975455761 3.9941864014 4.1395735741 2118 1311867241.0990099907 0.0863048583 0.0921749076 0.1207853556 0.0060361729 0.0114930000 0.0004480000 0.0047560000 0.0000010000 0.0000040000 0.0008740000 43832613 96830484 509673472 3.8969640732 3.9926111698 4.1418466568 2119 1311867241.1285290718 0.0873944536 0.0921726516 0.1207853556 0.0060366129 0.0117150000 0.0004540000 0.0046150000 0.0000040000 0.0000030000 0.0011420000 43836173 96830484 509673472 3.8955714703 3.9923844337 4.1441378593 2120 1311867241.1641499996 0.0862760320 0.0921698702 0.1207853556 0.0060392907 0.0114600000 0.0004480000 0.0047430000 0.0000000000 0.0000040000 0.0008770000 43840013 96830484 509673472 3.8956952095 3.9933109283 4.1466307640 2121 1311867241.1980121136 0.0868734643 0.0921673731 0.1207853556 0.0060387022 0.0153300000 0.0005460000 0.0038830000 0.0000080000 0.0000080000 0.0018030000 43843685 96830484 509673472 3.8942060471 3.9926638603 4.1490678787 2122 1311867241.2313330173 0.0881206021 0.0921654660 0.1207853556 0.0060393112 0.0115580000 0.0004620000 0.0044070000 0.0000010000 0.0000040000 0.0008930000 43847469 96830484 509673472 3.8926270008 3.9937138557 4.1516637802 2123 1311867241.2640700340 0.0883827806 0.0921636842 0.1207853556 0.0060379799 0.0115800000 0.0004520000 0.0043710000 0.0000040000 0.0000040000 0.0011510000 43851085 96830484 509673472 3.8923246861 3.9947903156 4.1540260315 2124 1311867241.3000609875 0.0880190432 0.0921617329 0.1207853556 0.0060432745 0.0121440000 0.0004990000 0.0046520000 0.0000010000 0.0000040000 0.0008890000 43854925 96830484 509673472 3.8909893036 3.9932529926 4.1555342674 2125 1311867241.3294849396 0.0884535983 0.0921599879 0.1207853556 0.0060442526 0.0108210000 0.0004910000 0.0032150000 0.0000040000 0.0000050000 0.0016270000 43858485 96830484 509673472 3.8899428844 3.9938261509 4.1573910713 2126 1311867241.3612549305 0.0885997266 0.0921583133 0.1207853556 0.0060431525 0.0115200000 0.0004620000 0.0047450000 0.0000000000 0.0000040000 0.0008860000 43862213 96830484 509673472 3.8890378475 3.9934809208 4.1593232155 2127 1311867241.3981139660 0.0891975164 0.0921569213 0.1207853556 0.0060448378 0.0102780000 0.0004450000 0.0032260000 0.0000040000 0.0000040000 0.0011260000 43865941 96830484 509673472 3.8868687153 3.9922144413 4.1609821320 2128 1311867241.4300589561 0.0889579728 0.0921554180 0.1207853556 0.0060567325 0.0096210000 0.0004440000 0.0028310000 0.0000010000 0.0000040000 0.0008860000 43869669 96830484 509673472 3.8865578175 3.9928226471 4.1628446579 2129 1311867241.4652009010 0.0892598554 0.0921540579 0.1207853556 0.0060579537 0.0123490000 0.0004510000 0.0047430000 0.0000040000 0.0000040000 0.0016260000 43873397 96830484 509673472 3.8853752613 3.9933495522 4.1648521423 2130 1311867241.4969789982 0.0884798989 0.0921523330 0.1207853556 0.0060622386 0.0160170000 0.0006330000 0.0035900000 0.0000010000 0.0000120000 0.0011250000 43877013 96830484 509673472 3.8846657276 3.9926364422 4.1665821075 2131 1311867241.5331718922 0.0889063403 0.0921508098 0.1207853556 0.0060637286 0.0122320000 0.0004680000 0.0044160000 0.0000050000 0.0000050000 0.0011660000 43880853 96830484 509673472 3.8836724758 3.9930088520 4.1682662964 2132 1311867241.5656960011 0.0883227959 0.0921490143 0.1207853556 0.0060637032 0.0115320000 0.0004440000 0.0047240000 0.0000010000 0.0000040000 0.0008700000 43884525 96830484 509673472 3.8831374645 3.9929046631 4.1697773933 2133 1311867241.6002480984 0.0887038708 0.0921473991 0.1207853556 0.0060638129 0.0100150000 0.0004510000 0.0024540000 0.0000040000 0.0000040000 0.0016070000 43888253 96830484 509673472 3.8817963600 3.9913370609 4.1708607674 2134 1311867241.6291201115 0.0888365358 0.0921458476 0.1207853556 0.0060627532 0.0111330000 0.0004500000 0.0043580000 0.0000000000 0.0000040000 0.0008680000 43891869 96830484 509673472 3.8818507195 3.9919805527 4.1720199585 2135 1311867241.6646790504 0.0880058855 0.0921439085 0.1207853556 0.0060676475 0.0102980000 0.0004470000 0.0032180000 0.0000040000 0.0000040000 0.0011300000 43895597 96830484 509673472 3.8818116188 3.9928286076 4.1730871201 2136 1311867241.6999258995 0.0877843648 0.0921418675 0.1207853556 0.0060681208 0.0116500000 0.0004560000 0.0047400000 0.0000000000 0.0000040000 0.0008630000 43899381 96830484 509673472 3.8810429573 3.9919366837 4.1738905907 2137 1311867241.7297649384 0.0888652727 0.0921403343 0.1207853556 0.0060790732 0.0123090000 0.0004480000 0.0047420000 0.0000030000 0.0000030000 0.0016000000 43902941 96830484 509673472 3.8808209896 3.9924173355 4.1747498512 2138 1311867241.7676639557 0.0881242082 0.0921384558 0.1207853556 0.0060779964 0.0088710000 0.0004470000 0.0020860000 0.0000010000 0.0000040000 0.0008580000 43906837 96830484 509673472 3.8804481030 3.9931721687 4.1756939888 2139 1311867241.7974851131 0.0881843939 0.0921366073 0.1207853556 0.0060775107 0.0118110000 0.0004510000 0.0047420000 0.0000040000 0.0000040000 0.0011090000 43910397 96830484 509673472 3.8797743320 3.9924082756 4.1765427589 2140 1311867241.8296549320 0.0884199515 0.0921348705 0.1207853556 0.0060770664 0.0097460000 0.0004480000 0.0028600000 0.0000010000 0.0000040000 0.0008580000 43914069 96830484 509673472 3.8780655861 3.9923079014 4.1774144173 2141 1311867241.8668920994 0.0875861570 0.0921327459 0.1207853556 0.0060765272 0.0123270000 0.0004490000 0.0047570000 0.0000040000 0.0000040000 0.0015840000 43917909 96830484 509673472 3.8783047199 3.9927213192 4.1786599159 2142 1311867241.8979690075 0.0883923471 0.0921309997 0.1207853556 0.0060755942 0.0155870000 0.0005470000 0.0050310000 0.0000020000 0.0000070000 0.0009830000 43921525 96830484 509673472 3.8772065639 3.9925835133 4.1802272797 2143 1311867241.9292619228 0.0881303325 0.0921291329 0.1207853556 0.0060747126 0.0122030000 0.0004610000 0.0047920000 0.0000040000 0.0000040000 0.0011250000 43925197 96830484 509673472 3.8770031929 3.9932506084 4.1821794510 2144 1311867241.9654040337 0.0873536021 0.0921269055 0.1207853556 0.0060734186 0.0100500000 0.0004510000 0.0032520000 0.0000010000 0.0000040000 0.0008530000 43928981 96830484 509673472 3.8766462803 3.9938607216 4.1843361855 2145 1311867241.9974029064 0.0876640156 0.0921248249 0.1207853556 0.0060735602 0.0104490000 0.0004530000 0.0028520000 0.0000030000 0.0000030000 0.0015670000 43932653 96830484 509673472 3.8757789135 3.9931392670 4.1862449646 2146 1311867242.0296339989 0.0875722095 0.0921227034 0.1207853556 0.0060736044 0.0115580000 0.0004500000 0.0047620000 0.0000010000 0.0000040000 0.0008510000 43936325 96830484 509673472 3.8759918213 3.9934215546 4.1881809235 2147 1311867242.0670061111 0.0873113424 0.0921204625 0.1207853556 0.0060724788 0.0161830000 0.0005510000 0.0056440000 0.0000080000 0.0000080000 0.0011630000 43940165 96830484 509673472 3.8755528927 3.9948711395 4.1902103424 2148 1311867242.0972509384 0.0871039852 0.0921181270 0.1207853556 0.0060733137 0.0100090000 0.0005030000 0.0028910000 0.0000000000 0.0000040000 0.0008450000 43943781 96830484 509673472 3.8753407001 3.9935438633 4.1917338371 2149 1311867242.1308040619 0.0873461515 0.0921159065 0.1207853556 0.0060754293 0.0116280000 0.0004520000 0.0040030000 0.0000040000 0.0000040000 0.0015460000 43947453 96830484 509673472 3.8751769066 3.9948108196 4.1933565140 2150 1311867242.1670179367 0.0868322104 0.0921134489 0.1207853556 0.0060762386 0.0102540000 0.0004590000 0.0031360000 0.0000000000 0.0000040000 0.0008330000 43951181 96830484 509673472 3.8751633167 3.9943487644 4.1946740150 2151 1311867242.1982409954 0.0868067220 0.0921109819 0.1207853556 0.0060766401 0.0101210000 0.0004540000 0.0028710000 0.0000040000 0.0000040000 0.0010960000 43954797 96830484 509673472 3.8744745255 3.9936330318 4.1959819794 2152 1311867242.2334370613 0.0872481465 0.0921087222 0.1207853556 0.0060791079 0.0181890000 0.0006340000 0.0036650000 0.0000020000 0.0000160000 0.0013170000 43958581 96830484 509673472 3.8732073307 3.9949769974 4.1977591515 2153 1311867242.2696599960 0.0865680501 0.0921061487 0.1207853556 0.0060777367 0.0131230000 0.0004760000 0.0048450000 0.0000050000 0.0000050000 0.0015470000 43962365 96830484 509673472 3.8739242554 3.9948301315 4.1994810104 2154 1311867242.2982430458 0.0871621221 0.0921038534 0.1207853556 0.0060764966 0.0098340000 0.0004560000 0.0028670000 0.0000000000 0.0000040000 0.0008330000 43965925 96830484 509673472 3.8728725910 3.9941592216 4.2011642456 2155 1311867242.3293490410 0.0873193368 0.0921016332 0.1207853556 0.0060755547 0.0096630000 0.0004540000 0.0024970000 0.0000030000 0.0000030000 0.0010940000 43969597 96830484 509673472 3.8722889423 3.9945204258 4.2031016350 2156 1311867242.3659460545 0.0873250887 0.0920994178 0.1207853556 0.0060762861 0.0097160000 0.0004720000 0.0028590000 0.0000000000 0.0000030000 0.0008340000 43973381 96830484 509673472 3.8720526695 3.9942924976 4.2048153877 2157 1311867242.3974800110 0.0877327472 0.0920973933 0.1207853556 0.0060757156 0.0116610000 0.0004480000 0.0040190000 0.0000040000 0.0000040000 0.0015240000 43977053 96830484 509673472 3.8720397949 3.9940199852 4.2065711021 2158 1311867242.4322769642 0.0881224573 0.0920955514 0.1207853556 0.0060743374 0.0118260000 0.0004560000 0.0047970000 0.0000010000 0.0000040000 0.0008330000 43980837 96830484 509673472 3.8710913658 3.9934887886 4.2082166672 2159 1311867242.4648990631 0.0883769467 0.0920938290 0.1207853556 0.0060739919 0.0141290000 0.0005540000 0.0026960000 0.0000100000 0.0000100000 0.0012360000 43984453 96830484 509673472 3.8706331253 3.9927446842 4.2096023560 2160 1311867242.4975609779 0.0883644000 0.0920921024 0.1207853556 0.0060726763 0.0120880000 0.0004680000 0.0048340000 0.0000000000 0.0000040000 0.0008390000 43988125 96830484 509673472 3.8702008724 3.9925460815 4.2108592987 2161 1311867242.5292570591 0.0881611183 0.0920902834 0.1207853556 0.0060714485 0.0107910000 0.0004540000 0.0032490000 0.0000050000 0.0000030000 0.0015350000 43991797 96830484 509673472 3.8704171181 3.9927341938 4.2123060226 2162 1311867242.5650939941 0.0880498514 0.0920884145 0.1207853556 0.0060703455 0.0101460000 0.0004490000 0.0032650000 0.0000000000 0.0000040000 0.0008320000 43995637 96830484 509673472 3.8698396683 3.9914255142 4.2135348320 2163 1311867242.5985031128 0.0885016546 0.0920867563 0.1207853556 0.0060690451 0.0101230000 0.0004520000 0.0028610000 0.0000040000 0.0000040000 0.0010990000 43999365 96830484 509673472 3.8690609932 3.9914460182 4.2150998116 2164 1311867242.6305589676 0.0885313898 0.0920851133 0.1207853556 0.0060677426 0.0105690000 0.0004490000 0.0036420000 0.0000010000 0.0000040000 0.0008400000 44002981 96830484 509673472 3.8695023060 3.9907810688 4.2166433334 2165 1311867242.6692740917 0.0882905647 0.0920833607 0.1207853556 0.0060667635 0.0123820000 0.0004560000 0.0048000000 0.0000040000 0.0000040000 0.0015380000 44006877 96830484 509673472 3.8682382107 3.9904739857 4.2182593346 2166 1311867242.6981039047 0.0880223662 0.0920814858 0.1207853556 0.0060657660 0.0115190000 0.0004470000 0.0047770000 0.0000010000 0.0000040000 0.0008390000 44010437 96830484 509673472 3.8691613674 3.9914529324 4.2202439308 2167 1311867242.7372829914 0.0877811387 0.0920795013 0.1207853556 0.0060653600 0.0120030000 0.0004520000 0.0047960000 0.0000030000 0.0000030000 0.0010900000 44014277 96830484 509673472 3.8696694374 3.9916543961 4.2224345207 2168 1311867242.7656900883 0.0877408460 0.0920775001 0.1207853556 0.0060653616 0.0105970000 0.0004580000 0.0036270000 0.0000000000 0.0000040000 0.0008310000 44017893 96830484 509673472 3.8694343567 3.9895341396 4.2240872383 2169 1311867242.7994089127 0.0884131715 0.0920758107 0.1207853556 0.0060681575 0.0109970000 0.0004510000 0.0032650000 0.0000040000 0.0000040000 0.0015320000 44021565 96830484 509673472 3.8687162399 3.9907326698 4.2261304855 2170 1311867242.8355538845 0.0876691416 0.0920737800 0.1207853556 0.0060689410 0.0118600000 0.0004510000 0.0046560000 0.0000000000 0.0000040000 0.0008260000 44025405 96830484 509673472 3.8692698479 3.9912350178 4.2281723022 2171 1311867242.8666720390 0.0874868557 0.0920716671 0.1207853556 0.0060690752 0.0112840000 0.0004580000 0.0040250000 0.0000040000 0.0000040000 0.0010840000 44029077 96830484 509673472 3.8699517250 3.9902179241 4.2300248146 2172 1311867242.8980929852 0.0890872329 0.0920702931 0.1207853556 0.0060932440 0.0098400000 0.0004520000 0.0028700000 0.0000010000 0.0000040000 0.0008280000 44032693 96830484 509673472 3.8688776493 3.9911310673 4.2321190834 2173 1311867242.9335498810 0.0881851688 0.0920685052 0.1207853556 0.0061203283 0.0111910000 0.0004510000 0.0036490000 0.0000040000 0.0000040000 0.0015170000 44036477 96830484 509673472 3.8688817024 3.9908585548 4.2340874672 2174 1311867242.9649999142 0.0888041183 0.0920670036 0.1207853556 0.0061227493 0.0113280000 0.0004510000 0.0044110000 0.0000000000 0.0000040000 0.0008230000 44040149 96830484 509673472 3.8681576252 3.9904608727 4.2359700203 2175 1311867242.9970819950 0.0886577144 0.0920654361 0.1207853556 0.0061216796 0.0103280000 0.0004490000 0.0032610000 0.0000040000 0.0000040000 0.0010710000 44043765 96830484 509673472 3.8683679104 3.9898986816 4.2377324104 2176 1311867243.0332529545 0.0896146521 0.0920643099 0.1207853556 0.0061204762 0.0150850000 0.0005510000 0.0034890000 0.0000010000 0.0000110000 0.0010350000 44047549 96830484 509673472 3.8680558205 3.9899663925 4.2397089005 2177 1311867243.0648689270 0.0884480998 0.0920626488 0.1207853556 0.0061192597 0.0127670000 0.0004570000 0.0048610000 0.0000050000 0.0000040000 0.0015080000 44051221 96830484 509673472 3.8679447174 3.9896454811 4.2415294647 2178 1311867243.0972158909 0.0883308873 0.0920609354 0.1207853556 0.0061180013 0.0156110000 0.0005430000 0.0049370000 0.0000010000 0.0000080000 0.0009390000 44054893 96830484 509673472 3.8677940369 3.9893276691 4.2434430122 2179 1311867243.1357100010 0.0871476084 0.0920586805 0.1207853556 0.0061243820 0.0145560000 0.0005450000 0.0038640000 0.0000080000 0.0000080000 0.0011840000 44058733 96830484 509673472 3.8673076630 3.9883384705 4.2452697754 2180 1311867243.1655960083 0.0889343694 0.0920572473 0.1207853556 0.0061330969 0.0105800000 0.0004650000 0.0033020000 0.0000010000 0.0000040000 0.0008200000 44062349 96830484 509673472 3.8655548096 3.9885113239 4.2472701073 2181 1311867243.1977169514 0.0892155617 0.0920559444 0.1207853556 0.0061329826 0.0116590000 0.0004570000 0.0040290000 0.0000030000 0.0000040000 0.0015010000 44065965 96830484 509673472 3.8650689125 3.9883124828 4.2491807938 2182 1311867243.2358860970 0.0888345614 0.0920544681 0.1207853556 0.0061335723 0.0118400000 0.0004510000 0.0048010000 0.0000010000 0.0000040000 0.0008190000 44069861 96830484 509673472 3.8642239571 3.9869511127 4.2510051727 2183 1311867243.2649240494 0.0892427936 0.0920531801 0.1207853556 0.0061323618 0.0108480000 0.0004500000 0.0036370000 0.0000050000 0.0000040000 0.0010760000 44073365 96830484 509673472 3.8637521267 3.9864296913 4.2528610229 2184 1311867243.2970221043 0.0887891129 0.0920516855 0.1207853556 0.0061311391 0.0099140000 0.0004500000 0.0028700000 0.0000000000 0.0000040000 0.0008220000 44077093 96830484 509673472 3.8637604713 3.9860725403 4.2546319962 2185 1311867243.3327538967 0.0888394937 0.0920502154 0.1207853556 0.0061308221 0.0151750000 0.0005490000 0.0031100000 0.0000100000 0.0000100000 0.0017510000 44080821 96830484 509673472 3.8629114628 3.9850363731 4.2564125061 2186 1311867243.3681559563 0.0895051807 0.0920490512 0.1207853556 0.0061297095 0.0122280000 0.0004670000 0.0048500000 0.0000010000 0.0000040000 0.0008220000 44084605 96830484 509673472 3.8616852760 3.9849402905 4.2583708763 2187 1311867243.4021821022 0.0894842073 0.0920478784 0.1207853556 0.0061283778 0.0104480000 0.0004490000 0.0032750000 0.0000040000 0.0000040000 0.0010790000 44088333 96830484 509673472 3.8617360592 3.9844672680 4.2600960732 2188 1311867243.4344329834 0.0897303149 0.0920468192 0.1207853556 0.0061281874 0.0102390000 0.0004540000 0.0032710000 0.0000010000 0.0000040000 0.0008150000 44092005 96830484 509673472 3.8614518642 3.9841544628 4.2618560791 2189 1311867243.4665510654 0.0892534107 0.0920455431 0.1207853556 0.0061270002 0.0157180000 0.0005480000 0.0042850000 0.0000080000 0.0000080000 0.0016500000 44095677 96830484 509673472 3.8612947464 3.9847209454 4.2638392448 2190 1311867243.4982140064 0.0897162408 0.0920444795 0.1207853556 0.0061260480 0.0103530000 0.0004700000 0.0029120000 0.0000000000 0.0000040000 0.0008160000 44099293 96830484 509673472 3.8606586456 3.9842662811 4.2657670975 2191 1311867243.5339779854 0.0898849666 0.0920434939 0.1207853556 0.0061247957 0.0108630000 0.0004560000 0.0036460000 0.0000040000 0.0000040000 0.0010670000 44103133 96830484 509673472 3.8603875637 3.9841163158 4.2675194740 2192 1311867243.5669720173 0.0892556757 0.0920422220 0.1207853556 0.0061238302 0.0126180000 0.0004580000 0.0048220000 0.0000000000 0.0000030000 0.0008100000 44106861 96830484 509673472 3.8607525826 3.9837918282 4.2692718506 2193 1311867243.5978341103 0.0894531608 0.0920410414 0.1207853556 0.0061225665 0.0110570000 0.0005040000 0.0032830000 0.0000040000 0.0000030000 0.0014650000 44110477 96830484 509673472 3.8603372574 3.9829103947 4.2708158493 2194 1311867243.6333720684 0.0898338109 0.0920400354 0.1207853556 0.0061239884 0.0102850000 0.0004550000 0.0032640000 0.0000000000 0.0000050000 0.0008060000 44114205 96830484 509673472 3.8605284691 3.9832925797 4.2725520134 2195 1311867243.6661529541 0.0903638452 0.0920392718 0.1207853556 0.0061226855 0.0157840000 0.0005600000 0.0043070000 0.0000080000 0.0000080000 0.0011730000 44117933 96830484 509673472 3.8601961136 3.9831659794 4.2742400169 2196 1311867243.6981849670 0.0900922045 0.0920383851 0.1207853556 0.0061222843 0.0123550000 0.0004730000 0.0048490000 0.0000010000 0.0000050000 0.0008160000 44121549 96830484 509673472 3.8608956337 3.9820861816 4.2756681442 2197 1311867243.7344710827 0.0899207890 0.0920374213 0.1207853556 0.0061213730 0.0101130000 0.0004570000 0.0025080000 0.0000030000 0.0000040000 0.0014510000 44125389 96830484 509673472 3.8606324196 3.9827766418 4.2774214745 2198 1311867243.7666299343 0.0901013687 0.0920365404 0.1207853556 0.0061207889 0.0103540000 0.0004560000 0.0032900000 0.0000010000 0.0000040000 0.0008000000 44129117 96830484 509673472 3.8611462116 3.9825043678 4.2792024612 2199 1311867243.7979769707 0.0898341313 0.0920355389 0.1207853556 0.0061197341 0.0101680000 0.0004620000 0.0029060000 0.0000030000 0.0000030000 0.0010590000 44132733 96830484 509673472 3.8622648716 3.9821679592 4.2810006142 2200 1311867243.8330240250 0.0899076909 0.0920345717 0.1207853556 0.0061184207 0.0144150000 0.0005530000 0.0031550000 0.0000010000 0.0000110000 0.0009320000 44136461 96830484 509673472 3.8619689941 3.9826922417 4.2829141617 2201 1311867243.8647689819 0.0905999169 0.0920339199 0.1207853556 0.0061178640 0.0114350000 0.0004710000 0.0033380000 0.0000040000 0.0000050000 0.0014570000 44140133 96830484 509673472 3.8623771667 3.9820067883 4.2848424911 2202 1311867243.8968739510 0.0910748243 0.0920334843 0.1207853556 0.0061167363 0.0099820000 0.0004510000 0.0029070000 0.0000000000 0.0000030000 0.0007950000 44143861 96830484 509673472 3.8620789051 3.9816036224 4.2864484787 2203 1311867243.9329960346 0.0911906809 0.0920331017 0.1207853556 0.0061159122 0.0121200000 0.0004580000 0.0048280000 0.0000040000 0.0000030000 0.0010490000 44147589 96830484 509673472 3.8626086712 3.9816973209 4.2881474495 2204 1311867243.9660589695 0.0913816839 0.0920328062 0.1207853556 0.0061147275 0.0147410000 0.0005510000 0.0032830000 0.0000010000 0.0000120000 0.0010120000 44151317 96830484 509673472 3.8625266552 3.9811060429 4.2895784378 2205 1311867244.0016739368 0.0909623429 0.0920323207 0.1207853556 0.0061141577 0.0146740000 0.0005490000 0.0027440000 0.0000100000 0.0000110000 0.0016620000 44155101 96830484 509673472 3.8633489609 3.9807240963 4.2911529541 2206 1311867244.0341379642 0.0905594677 0.0920316531 0.1207853556 0.0061130676 0.0123390000 0.0004700000 0.0048900000 0.0000010000 0.0000040000 0.0008080000 44158773 96830484 509673472 3.8641006947 3.9806487560 4.2926721573 2207 1311867244.0655789375 0.0910304785 0.0920311994 0.1207853556 0.0061119408 0.0121360000 0.0004540000 0.0048350000 0.0000030000 0.0000040000 0.0010550000 44162445 96830484 509673472 3.8637990952 3.9802162647 4.2942967415 2208 1311867244.1010930538 0.0907721594 0.0920306292 0.1207853556 0.0061107646 0.0106720000 0.0004620000 0.0032770000 0.0000000000 0.0000040000 0.0008030000 44166229 96830484 509673472 3.8640792370 3.9797270298 4.2960381508 2209 1311867244.1353089809 0.0905465931 0.0920299574 0.1207853556 0.0061097795 0.0122300000 0.0004570000 0.0044520000 0.0000040000 0.0000040000 0.0014580000 44169957 96830484 509673472 3.8648490906 3.9791843891 4.2978463173 2210 1311867244.1648418903 0.0907528102 0.0920293795 0.1207853556 0.0061084893 0.0099570000 0.0004570000 0.0028950000 0.0000000000 0.0000040000 0.0008040000 44173517 96830484 509673472 3.8647685051 3.9785981178 4.2996263504 2211 1311867244.2024741173 0.0898597762 0.0920283982 0.1207853556 0.0061071667 0.0162350000 0.0005540000 0.0051200000 0.0000080000 0.0000080000 0.0011760000 44177413 96830484 509673472 3.8654260635 3.9787678719 4.3016023636 2212 1311867244.2330279350 0.0899073854 0.0920274394 0.1207853556 0.0061058833 0.0101280000 0.0004680000 0.0025490000 0.0000010000 0.0000050000 0.0008070000 44181029 96830484 509673472 3.8664250374 3.9786965847 4.3037366867 2213 1311867244.2649021149 0.0895936936 0.0920263396 0.1207853556 0.0061050647 0.0109730000 0.0004540000 0.0032970000 0.0000040000 0.0000040000 0.0014490000 44184645 96830484 509673472 3.8674273491 3.9776604176 4.3057546616 2214 1311867244.3010311127 0.0896887034 0.0920252838 0.1207853556 0.0061044848 0.0097880000 0.0004580000 0.0025160000 0.0000010000 0.0000040000 0.0007970000 44188485 96830484 509673472 3.8674476147 3.9782950878 4.3080182076 2215 1311867244.3355190754 0.0891380832 0.0920239803 0.1207853556 0.0061034087 0.0133910000 0.0004540000 0.0054350000 0.0000040000 0.0000040000 0.0010590000 44192213 96830484 509673472 3.8687655926 3.9785633087 4.3101515770 2216 1311867244.3649079800 0.0896681547 0.0920229172 0.1207853556 0.0061026826 0.0121370000 0.0004990000 0.0048460000 0.0000000000 0.0000030000 0.0007870000 44195773 96830484 509673472 3.8691921234 3.9778010845 4.3121209145 2217 1311867244.4008760452 0.0899692178 0.0920219908 0.1207853556 0.0061021677 0.0126660000 0.0004540000 0.0048480000 0.0000050000 0.0000040000 0.0014350000 44199557 96830484 509673472 3.8692660332 3.9783883095 4.3142814636 2218 1311867244.4329938889 0.0894980207 0.0920208529 0.1207853556 0.0061024837 0.0119470000 0.0004510000 0.0048570000 0.0000000000 0.0000040000 0.0007830000 44203229 96830484 509673472 3.8702735901 3.9782688618 4.3163514137 2219 1311867244.4654510021 0.0892067403 0.0920195847 0.1207853556 0.0061018690 0.0114320000 0.0004530000 0.0040700000 0.0000040000 0.0000040000 0.0010360000 44206957 96830484 509673472 3.8713366985 3.9782996178 4.3183927536 2220 1311867244.5052490234 0.0884622112 0.0920179823 0.1207853556 0.0061011142 0.0151470000 0.0005530000 0.0039320000 0.0000000000 0.0000090000 0.0009090000 44210853 96830484 509673472 3.8727281094 3.9792089462 4.3206276894 2221 1311867244.5330989361 0.0886467621 0.0920164644 0.1207853556 0.0061000302 0.0161230000 0.0005510000 0.0051100000 0.0000080000 0.0000070000 0.0015900000 44214357 96830484 509673472 3.8733818531 3.9796516895 4.3229675293 2222 1311867244.5669400692 0.0889542848 0.0920150863 0.1207853556 0.0060987237 0.0107160000 0.0004700000 0.0033200000 0.0000010000 0.0000040000 0.0007930000 44218029 96830484 509673472 3.8732728958 3.9799265862 4.3251857758 2223 1311867244.6027030945 0.0890035182 0.0920137316 0.1207853556 0.0061028657 0.0143790000 0.0005530000 0.0027300000 0.0000100000 0.0000100000 0.0011920000 44221701 96830484 509673472 3.8741967678 3.9814462662 4.3277730942 2224 1311867244.6328020096 0.0891116560 0.0920124267 0.1207853556 0.0061031677 0.0124780000 0.0004680000 0.0048990000 0.0000000000 0.0000040000 0.0007800000 44225261 96830484 509673472 3.8748838902 3.9811992645 4.3301978111 2225 1311867244.6672449112 0.0894762799 0.0920112868 0.1207853556 0.0061022554 0.0105900000 0.0004570000 0.0029130000 0.0000040000 0.0000030000 0.0014240000 44229045 96830484 509673472 3.8750989437 3.9808814526 4.3325538635 2226 1311867244.7012600899 0.0894025937 0.0920101149 0.1207853556 0.0061011644 0.0161440000 0.0005520000 0.0051230000 0.0000010000 0.0000080000 0.0008960000 44232773 96830484 509673472 3.8761365414 3.9807941914 4.3348956108 2227 1311867244.7346320152 0.0896565393 0.0920090581 0.1207853556 0.0061001744 0.0104660000 0.0004730000 0.0025560000 0.0000040000 0.0000040000 0.0010530000 44236445 96830484 509673472 3.8765432835 3.9809272289 4.3371214867 2228 1311867244.7650001049 0.0897089168 0.0920080257 0.1207853556 0.0060989261 0.0136090000 0.0005640000 0.0027170000 0.0000010000 0.0000080000 0.0008940000 44240061 96830484 509673472 3.8773396015 3.9814541340 4.3394031525 2229 1311867244.8015320301 0.0894281715 0.0920068683 0.1207853556 0.0060978067 0.0159540000 0.0005510000 0.0051050000 0.0000090000 0.0000080000 0.0015420000 44243901 96830484 509673472 3.8785166740 3.9813425541 4.3416943550 2230 1311867244.8331909180 0.0894982964 0.0920057434 0.1207853556 0.0060969036 0.0121040000 0.0004660000 0.0048900000 0.0000000000 0.0000040000 0.0007770000 44247517 96830484 509673472 3.8787209988 3.9805359840 4.3435831070 2231 1311867244.8651568890 0.0894993171 0.0920046199 0.1207853556 0.0060956482 0.0120460000 0.0004480000 0.0047260000 0.0000040000 0.0000040000 0.0010230000 44251245 96830484 509673472 3.8794651031 3.9812352657 4.3459186554 2232 1311867244.9013550282 0.0894483253 0.0920034746 0.1207853556 0.0060943584 0.0120290000 0.0004560000 0.0048690000 0.0000000000 0.0000040000 0.0007640000 44255029 96830484 509673472 3.8795971870 3.9811952114 4.3479437828 2233 1311867244.9328739643 0.0892055556 0.0920022216 0.1207853556 0.0060930760 0.0118230000 0.0004600000 0.0040750000 0.0000040000 0.0000030000 0.0013980000 44258589 96830484 509673472 3.8801860809 3.9808630943 4.3499183655 2234 1311867244.9652509689 0.0890829191 0.0920009149 0.1207853556 0.0060918951 0.0136660000 0.0005520000 0.0027210000 0.0000010000 0.0000080000 0.0008760000 44262317 96830484 509673472 3.8801474571 3.9816753864 4.3522057533 2235 1311867245.0022718906 0.0893066004 0.0919997094 0.1207853556 0.0060915258 0.0106360000 0.0004730000 0.0029660000 0.0000050000 0.0000040000 0.0010110000 44266213 96830484 509673472 3.8801245689 3.9807639122 4.3543066978 2236 1311867245.0349979401 0.0895378888 0.0919986084 0.1207853556 0.0060915870 0.0100120000 0.0004540000 0.0029240000 0.0000000000 0.0000040000 0.0007630000 44269829 96830484 509673472 3.8801925182 3.9810559750 4.3563394547 2237 1311867245.0664730072 0.0894175023 0.0919974545 0.1207853556 0.0060902669 0.0125150000 0.0004590000 0.0048610000 0.0000040000 0.0000030000 0.0013860000 44273501 96830484 509673472 3.8802006245 3.9815993309 4.3585972786 2238 1311867245.1041638851 0.0891216248 0.0919961695 0.1207853556 0.0060896371 0.0107400000 0.0004560000 0.0037000000 0.0000000000 0.0000040000 0.0007620000 44277285 96830484 509673472 3.8802099228 3.9812235832 4.3603663445 2239 1311867245.1338050365 0.0896372572 0.0919951160 0.1207853556 0.0060886354 0.0097960000 0.0004540000 0.0025250000 0.0000040000 0.0000040000 0.0010070000 44280901 96830484 509673472 3.8802034855 3.9808182716 4.3623628616 2240 1311867245.1749250889 0.0889795646 0.0919937698 0.1207853556 0.0060874117 0.0106210000 0.0004670000 0.0033210000 0.0000010000 0.0000050000 0.0007480000 44284909 96830484 509673472 3.8798756599 3.9815022945 4.3643827438 2241 1311867245.2108979225 0.0885859653 0.0919922491 0.1207853556 0.0060860935 0.0102710000 0.0004610000 0.0025370000 0.0000040000 0.0000040000 0.0013880000 44288693 96830484 509673472 3.8794701099 3.9812533855 4.3662757874 2242 1311867245.2429010868 0.0890568793 0.0919909398 0.1207853556 0.0060858244 0.0114500000 0.0004640000 0.0044560000 0.0000000000 0.0000030000 0.0007550000 44292421 96830484 509673472 3.8791282177 3.9811837673 4.3684148788 2243 1311867245.2755670547 0.0889602825 0.0919895887 0.1207853556 0.0060857063 0.0098040000 0.0004580000 0.0025320000 0.0000050000 0.0000040000 0.0010060000 44296093 96830484 509673472 3.8791408539 3.9811599255 4.3707962036 2244 1311867245.3120090961 0.0885634050 0.0919880618 0.1207853556 0.0060844116 0.0119240000 0.0004630000 0.0048590000 0.0000010000 0.0000040000 0.0007490000 44299877 96830484 509673472 3.8787920475 3.9808292389 4.3729410172 2245 1311867245.3430099487 0.0884007663 0.0919864639 0.1207853556 0.0060831789 0.0098350000 0.0004530000 0.0021450000 0.0000050000 0.0000040000 0.0013650000 44303549 96830484 509673472 3.8786499500 3.9803371429 4.3750724792 2246 1311867245.3749370575 0.0883812457 0.0919848588 0.1207853556 0.0060830367 0.0099870000 0.0004640000 0.0029190000 0.0000010000 0.0000040000 0.0007540000 44307165 96830484 509673472 3.8786268234 3.9803330898 4.3774209023 2247 1311867245.4122350216 0.0878761187 0.0919830302 0.1207853556 0.0060818468 0.0154290000 0.0005670000 0.0050940000 0.0000080000 0.0000080000 0.0010850000 44311061 96830484 509673472 3.8774292469 3.9806482792 4.3798990250 2248 1311867245.4428830147 0.0887322202 0.0919815841 0.1207853556 0.0060842009 0.0103100000 0.0004780000 0.0029330000 0.0000010000 0.0000040000 0.0007540000 44314565 96830484 509673472 3.8768715858 3.9801056385 4.3820972443 2249 1311867245.4751451015 0.0887176767 0.0919801329 0.1207853556 0.0060835136 0.0101430000 0.0004630000 0.0025340000 0.0000040000 0.0000040000 0.0013610000 44318293 96830484 509673472 3.8769009113 3.9813191891 4.3845591545 2250 1311867245.5108819008 0.0884350389 0.0919785573 0.1207853556 0.0060826912 0.0096620000 0.0004550000 0.0025290000 0.0000010000 0.0000040000 0.0007430000 44322077 96830484 509673472 3.8762004375 3.9811208248 4.3869543076 2251 1311867245.5429608822 0.0881232396 0.0919768446 0.1207853556 0.0060815054 0.0143940000 0.0005690000 0.0027450000 0.0000120000 0.0000100000 0.0011020000 44325749 96830484 509673472 3.8763177395 3.9810442924 4.3893036842 2252 1311867245.5749409199 0.0885312483 0.0919753145 0.1207853556 0.0060802340 0.0112960000 0.0004670000 0.0037540000 0.0000010000 0.0000050000 0.0007460000 44329421 96830484 509673472 3.8756132126 3.9819228649 4.3920001984 2253 1311867245.6109130383 0.0890502110 0.0919740162 0.1207853556 0.0060794388 0.0126040000 0.0004590000 0.0049000000 0.0000040000 0.0000030000 0.0013390000 44333205 96830484 509673472 3.8751432896 3.9803259373 4.3941464424 2254 1311867245.6428189278 0.0881558433 0.0919723223 0.1207853556 0.0060842500 0.0101780000 0.0004580000 0.0029430000 0.0000000000 0.0000040000 0.0007400000 44336821 96830484 509673472 3.8740971088 3.9801926613 4.3963570595 2255 1311867245.6751749516 0.0887283906 0.0919708837 0.1207853556 0.0060836873 0.0122650000 0.0004580000 0.0049080000 0.0000040000 0.0000040000 0.0009930000 44340549 96830484 509673472 3.8742103577 3.9808053970 4.3987889290 2256 1311867245.7109169960 0.0889113322 0.0919695275 0.1207853556 0.0060824889 0.0118460000 0.0004580000 0.0048360000 0.0000000000 0.0000040000 0.0007370000 44344333 96830484 509673472 3.8733797073 3.9795832634 4.4007468224 2257 1311867245.7429819107 0.0885269046 0.0919680022 0.1207853556 0.0060819164 0.0125750000 0.0004580000 0.0048840000 0.0000040000 0.0000040000 0.0013420000 44347949 96830484 509673472 3.8734915257 3.9800515175 4.4028534889 2258 1311867245.7752521038 0.0885441378 0.0919664859 0.1207853556 0.0060835026 0.0103930000 0.0004580000 0.0033350000 0.0000010000 0.0000040000 0.0007300000 44351677 96830484 509673472 3.8729765415 3.9798133373 4.4050564766 2259 1311867245.8110349178 0.0885962099 0.0919649940 0.1207853556 0.0060826141 0.0142310000 0.0005670000 0.0027250000 0.0000080000 0.0000080000 0.0011000000 44355461 96830484 509673472 3.8732824326 3.9785950184 4.4068398476 2260 1311867245.8428230286 0.0887751579 0.0919635825 0.1207853556 0.0060821022 0.0111800000 0.0005200000 0.0033470000 0.0000010000 0.0000050000 0.0007400000 44359189 96830484 509673472 3.8725485802 3.9784038067 4.4086961746 2261 1311867245.8757770061 0.0893250182 0.0919624155 0.1207853556 0.0060807839 0.0106610000 0.0004560000 0.0029290000 0.0000040000 0.0000040000 0.0013350000 44362805 96830484 509673472 3.8717908859 3.9785168171 4.4106230736 2262 1311867245.9110751152 0.0888380632 0.0919610343 0.1207853556 0.0060805786 0.0104330000 0.0004600000 0.0033220000 0.0000010000 0.0000040000 0.0007390000 44366589 96830484 509673472 3.8715963364 3.9777352810 4.4121003151 2263 1311867245.9428870678 0.0887233540 0.0919596036 0.1207853556 0.0060806423 0.0101530000 0.0004680000 0.0029300000 0.0000030000 0.0000040000 0.0009800000 44370261 96830484 509673472 3.8713793755 3.9781072140 4.4139056206 2264 1311867245.9751350880 0.0888261944 0.0919582196 0.1207853556 0.0060794609 0.0153660000 0.0005690000 0.0051360000 0.0000010000 0.0000080000 0.0008430000 44373933 96830484 509673472 3.8706586361 3.9781777859 4.4156146049 2265 1311867246.0112419128 0.0882769972 0.0919565943 0.1207853556 0.0060781423 0.0107280000 0.0004740000 0.0025600000 0.0000040000 0.0000040000 0.0013400000 44377717 96830484 509673472 3.8698399067 3.9787204266 4.4176940918 2266 1311867246.0429229736 0.0884469301 0.0919550455 0.1207853556 0.0060768601 0.0112440000 0.0004580000 0.0041160000 0.0000010000 0.0000040000 0.0007280000 44381333 96830484 509673472 3.8689248562 3.9787924290 4.4198913574 2267 1311867246.0752329826 0.0885074958 0.0919535247 0.1207853556 0.0060755990 0.0098560000 0.0004630000 0.0024110000 0.0000030000 0.0000040000 0.0009700000 44385005 96830484 509673472 3.8684647083 3.9792876244 4.4221391678 2268 1311867246.1109249592 0.0883104876 0.0919519185 0.1207853556 0.0060748045 0.0121070000 0.0004610000 0.0049020000 0.0000000000 0.0000040000 0.0007150000 44388789 96830484 509673472 3.8682298660 3.9800770283 4.4244265556 2269 1311867246.1430890560 0.0889326036 0.0919505878 0.1207853556 0.0060736709 0.0118600000 0.0004590000 0.0041060000 0.0000040000 0.0000040000 0.0013080000 44392517 96830484 509673472 3.8671414852 3.9799928665 4.4265003204 2270 1311867246.1749811172 0.0887346566 0.0919491711 0.1207853556 0.0060727188 0.0120570000 0.0004590000 0.0049020000 0.0000010000 0.0000040000 0.0007160000 44396133 96830484 509673472 3.8668477535 3.9810836315 4.4287319183 2271 1311867246.2109639645 0.0886529386 0.0919477196 0.1207853556 0.0060717390 0.0124320000 0.0004590000 0.0049080000 0.0000040000 0.0000040000 0.0009550000 44399917 96830484 509673472 3.8660597801 3.9817557335 4.4309568405 2272 1311867246.2429399490 0.0888003185 0.0919463343 0.1207853556 0.0060705078 0.0120690000 0.0004630000 0.0049090000 0.0000000000 0.0000030000 0.0007050000 44403589 96830484 509673472 3.8662779331 3.9821999073 4.4331130981 2273 1311867246.2750649452 0.0888957232 0.0919449922 0.1207853556 0.0060697636 0.0107270000 0.0004560000 0.0029540000 0.0000030000 0.0000040000 0.0012870000 44407261 96830484 509673472 3.8663742542 3.9835138321 4.4353260994 2274 1311867246.3108720779 0.0885320753 0.0919434914 0.1207853556 0.0060697407 0.0108000000 0.0004620000 0.0037350000 0.0000010000 0.0000040000 0.0007010000 44411045 96830484 509673472 3.8664963245 3.9841895103 4.4373536110 2275 1311867246.3429319859 0.0886597410 0.0919420480 0.1207853556 0.0060689387 0.0103170000 0.0004590000 0.0029520000 0.0000030000 0.0000030000 0.0009280000 44414717 96830484 509673472 3.8660910130 3.9842460155 4.4393472672 2276 1311867246.3752970695 0.0889126211 0.0919407169 0.1207853556 0.0060678131 0.0096940000 0.0004590000 0.0025580000 0.0000000000 0.0000040000 0.0007010000 44418389 96830484 509673472 3.8658905029 3.9852671623 4.4413275719 2277 1311867246.4109311104 0.0889517516 0.0919394043 0.1207853556 0.0060667206 0.0111340000 0.0004610000 0.0033640000 0.0000040000 0.0000040000 0.0012660000 44422173 96830484 509673472 3.8656115532 3.9855778217 4.4432840347 2278 1311867246.4430770874 0.0890086442 0.0919381177 0.1207853556 0.0060655517 0.0104880000 0.0004640000 0.0033510000 0.0000000000 0.0000030000 0.0007000000 44425845 96830484 509673472 3.8656110764 3.9864163399 4.4452152252 2279 1311867246.4751329422 0.0895599425 0.0919370742 0.1207853556 0.0060642540 0.0141230000 0.0005720000 0.0031220000 0.0000070000 0.0000080000 0.0010710000 44429517 96830484 509673472 3.8649165630 3.9865546227 4.4469847679 2280 1311867246.5109679699 0.0894830674 0.0919359979 0.1207853556 0.0060638326 0.0124050000 0.0004790000 0.0049570000 0.0000000000 0.0000040000 0.0007040000 44433301 96830484 509673472 3.8653092384 3.9875154495 4.4486637115 2281 1311867246.5431129932 0.0898280367 0.0919350737 0.1207853556 0.0060629752 0.0157190000 0.0006000000 0.0043910000 0.0000080000 0.0000080000 0.0014030000 44436917 96830484 509673472 3.8652145863 3.9873523712 4.4500665665 2282 1311867246.5752038956 0.0895674601 0.0919340362 0.1207853556 0.0060621040 0.0129710000 0.0005280000 0.0049640000 0.0000010000 0.0000050000 0.0007000000 44440645 96830484 509673472 3.8662939072 3.9874818325 4.4513487816 2283 1311867246.6111249924 0.0900656804 0.0919332178 0.1207853556 0.0060620771 0.0116560000 0.0004590000 0.0041290000 0.0000040000 0.0000040000 0.0009350000 44444429 96830484 509673472 3.8652453423 3.9870347977 4.4525771141 2284 1311867246.6431870461 0.0894968882 0.0919321511 0.1207853556 0.0060620188 0.0104340000 0.0004650000 0.0032230000 0.0000000000 0.0000040000 0.0006990000 44448101 96830484 509673472 3.8652560711 3.9875838757 4.4535784721 2285 1311867246.6751689911 0.0896969065 0.0919311729 0.1207853556 0.0060613957 0.0127030000 0.0004590000 0.0049180000 0.0000030000 0.0000040000 0.0012600000 44451773 96830484 509673472 3.8647730350 3.9868288040 4.4543504715 2286 1311867246.7110559940 0.0897357836 0.0919302126 0.1207853556 0.0060600960 0.0105110000 0.0004660000 0.0033360000 0.0000000000 0.0000030000 0.0006940000 44455557 96830484 509673472 3.8647716045 3.9867017269 4.4552416801 2287 1311867246.7433049679 0.0898127705 0.0919292867 0.1207853556 0.0060588116 0.0156840000 0.0005720000 0.0051400000 0.0000080000 0.0000090000 0.0010550000 44459285 96830484 509673472 3.8645541668 3.9863038063 4.4559707642 2288 1311867246.7749860287 0.0902805626 0.0919285661 0.1207853556 0.0060578336 0.0104790000 0.0004830000 0.0029660000 0.0000000000 0.0000040000 0.0007050000 44462901 96830484 509673472 3.8643589020 3.9859092236 4.4567699432 2289 1311867246.8111929893 0.0905857384 0.0919279795 0.1207853556 0.0060569273 0.0126770000 0.0004580000 0.0048890000 0.0000040000 0.0000040000 0.0012460000 44466685 96830484 509673472 3.8639369011 3.9860703945 4.4573855400 2290 1311867246.8430919647 0.0906735435 0.0919274317 0.1207853556 0.0060556430 0.0121280000 0.0004660000 0.0049170000 0.0000010000 0.0000040000 0.0006960000 44470413 96830484 509673472 3.8639862537 3.9855101109 4.4580140114 2291 1311867246.8750779629 0.0907323137 0.0919269100 0.1207853556 0.0060547136 0.0124090000 0.0004640000 0.0048980000 0.0000040000 0.0000040000 0.0009390000 44474029 96830484 509673472 3.8638000488 3.9853181839 4.4584946632 2292 1311867246.9111549854 0.0908438042 0.0919264374 0.1207853556 0.0060534737 0.0138070000 0.0005710000 0.0027300000 0.0000010000 0.0000080000 0.0008380000 44477813 96830484 509673472 3.8633515835 3.9853398800 4.4590277672 2293 1311867246.9430611134 0.0905611366 0.0919258420 0.1207853556 0.0060526915 0.0108410000 0.0004730000 0.0024570000 0.0000040000 0.0000040000 0.0012600000 44481429 96830484 509673472 3.8636581898 3.9844384193 4.4593358040 2294 1311867246.9751238823 0.0905759633 0.0919252536 0.1207853556 0.0060516217 0.0185760000 0.0006610000 0.0029340000 0.0000030000 0.0000150000 0.0012050000 44485157 96830484 509673472 3.8626301289 3.9845633507 4.4597501755 2295 1311867247.0109090805 0.0902851671 0.0919245390 0.1207853556 0.0060506627 0.0114490000 0.0004840000 0.0029910000 0.0000040000 0.0000050000 0.0009570000 44488941 96830484 509673472 3.8631172180 3.9843189716 4.4602432251 2296 1311867247.0440731049 0.0900829360 0.0919237369 0.1207853556 0.0060493590 0.0099790000 0.0004650000 0.0025580000 0.0000010000 0.0000040000 0.0007090000 44492669 96830484 509673472 3.8632633686 3.9838509560 4.4607014656 2297 1311867247.0751919746 0.0903497413 0.0919230516 0.1207853556 0.0060483910 0.0126960000 0.0004610000 0.0049160000 0.0000040000 0.0000040000 0.0012700000 44496285 96830484 509673472 3.8630008698 3.9843776226 4.4614024162 2298 1311867247.1112151146 0.0906740874 0.0919225081 0.1207853556 0.0060472428 0.0100120000 0.0004620000 0.0028100000 0.0000010000 0.0000040000 0.0007040000 44500069 96830484 509673472 3.8624930382 3.9842541218 4.4620103836 2299 1311867247.1430439949 0.0906651616 0.0919219612 0.1207853556 0.0060465720 0.0100050000 0.0004600000 0.0025480000 0.0000030000 0.0000030000 0.0009440000 44503741 96830484 509673472 3.8627238274 3.9844267368 4.4625277519 2300 1311867247.1751630306 0.0905855969 0.0919213802 0.1207853556 0.0060454898 0.0104570000 0.0004580000 0.0033450000 0.0000000000 0.0000050000 0.0007020000 44507413 96830484 509673472 3.8628983498 3.9847590923 4.4629106522 2301 1311867247.2113189697 0.0906416252 0.0919208240 0.1207853556 0.0060443768 0.0151560000 0.0005730000 0.0031760000 0.0000090000 0.0000080000 0.0014370000 44511197 96830484 509673472 3.8632352352 3.9838898182 4.4631185532 2302 1311867247.2437279224 0.0912858173 0.0919205482 0.1207853556 0.0060445309 0.0124600000 0.0004770000 0.0048340000 0.0000010000 0.0000040000 0.0007060000 44514869 96830484 509673472 3.8618888855 3.9825761318 4.4630389214 2303 1311867247.2777190208 0.0915997550 0.0919204089 0.1207853556 0.0060441278 0.0104670000 0.0004590000 0.0029390000 0.0000040000 0.0000040000 0.0009500000 44518653 96830484 509673472 3.8612110615 3.9824173450 4.4628205299 2304 1311867247.3109691143 0.0918394327 0.0919203737 0.1207853556 0.0060431362 0.0114070000 0.0004730000 0.0041180000 0.0000010000 0.0000040000 0.0007040000 44522269 96830484 509673472 3.8602833748 3.9817631245 4.4621233940 2305 1311867247.3432049751 0.0919462219 0.0919203849 0.1207853556 0.0060429924 0.0115720000 0.0004590000 0.0037340000 0.0000030000 0.0000030000 0.0012660000 44525941 96830484 509673472 3.8598554134 3.9810876846 4.4613966942 2306 1311867247.3753070831 0.0919211656 0.0919203853 0.1207853556 0.0060417678 0.0121990000 0.0004640000 0.0049130000 0.0000010000 0.0000040000 0.0006980000 44529613 96830484 509673472 3.8593533039 3.9812033176 4.4605555534 2307 1311867247.4116749763 0.0920744166 0.0919204520 0.1207853556 0.0060424264 0.0113880000 0.0004600000 0.0037390000 0.0000040000 0.0000040000 0.0009380000 44533453 96830484 509673472 3.8592073917 3.9794311523 4.4594240189 2308 1311867247.4440929890 0.0924049616 0.0919206620 0.1207853556 0.0060416475 0.0101860000 0.0004650000 0.0028120000 0.0000000000 0.0000030000 0.0007020000 44537069 96830484 509673472 3.8587055206 3.9788110256 4.4582581520 2309 1311867247.4751029015 0.0926357210 0.0919209717 0.1207853556 0.0060403847 0.0116070000 0.0004620000 0.0037320000 0.0000040000 0.0000040000 0.0012650000 44540741 96830484 509673472 3.8581511974 3.9780905247 4.4569621086 2310 1311867247.5110449791 0.0926304907 0.0919212788 0.1207853556 0.0060439243 0.0143640000 0.0005720000 0.0035520000 0.0000010000 0.0000090000 0.0008210000 44544525 96830484 509673472 3.8584394455 3.9761092663 4.4553761482 2311 1311867247.5430850983 0.0929387957 0.0919217191 0.1207853556 0.0060478098 0.0125930000 0.0004740000 0.0049410000 0.0000050000 0.0000040000 0.0009610000 44548197 96830484 509673472 3.8579709530 3.9763274193 4.4536433220 2312 1311867247.5751209259 0.0922769085 0.0919218727 0.1207853556 0.0060520725 0.0122110000 0.0004580000 0.0048800000 0.0000000000 0.0000030000 0.0007120000 44551813 96830484 509673472 3.8584022522 3.9755964279 4.4519343376 2313 1311867247.6114599705 0.0932120979 0.0919224305 0.1207853556 0.0060535789 0.0103650000 0.0004650000 0.0025470000 0.0000040000 0.0000040000 0.0012850000 44555653 96830484 509673472 3.8588871956 3.9744012356 4.4499974251 2314 1311867247.6431109905 0.0933046192 0.0919230279 0.1207853556 0.0060524672 0.0102120000 0.0004560000 0.0029350000 0.0000010000 0.0000050000 0.0007140000 44559269 96830484 509673472 3.8589935303 3.9739334583 4.4479122162 2315 1311867247.6750760078 0.0926538333 0.0919233435 0.1207853556 0.0060568240 0.0140460000 0.0005620000 0.0030930000 0.0000090000 0.0000080000 0.0010750000 44562941 96830484 509673472 3.8609089851 3.9716951847 4.4456110001 2316 1311867247.7112369537 0.0939629450 0.0919242242 0.1207853556 0.0060561168 0.0103290000 0.0004620000 0.0029740000 0.0000010000 0.0000050000 0.0007230000 44566781 96830484 509673472 3.8603792191 3.9696409702 4.4427733421 2317 1311867247.7431221008 0.0937942937 0.0919250313 0.1207853556 0.0060554878 0.0108400000 0.0004610000 0.0029490000 0.0000040000 0.0000040000 0.0013010000 44570397 96830484 509673472 3.8606750965 3.9695668221 4.4399018288 2318 1311867247.7750411034 0.0932433903 0.0919256001 0.1207853556 0.0060546503 0.0117900000 0.0004620000 0.0045210000 0.0000010000 0.0000040000 0.0007220000 44574069 96830484 509673472 3.8610010147 3.9693877697 4.4371476173 2319 1311867247.8111629486 0.0934413299 0.0919262537 0.1207853556 0.0060535766 0.0124680000 0.0004620000 0.0048990000 0.0000030000 0.0000030000 0.0009710000 44577853 96830484 509673472 3.8609440327 3.9689695835 4.4342989922 2320 1311867247.8438889980 0.0936882272 0.0919270131 0.1207853556 0.0060543725 0.0123310000 0.0004630000 0.0048980000 0.0000010000 0.0000040000 0.0007260000 44581581 96830484 509673472 3.8607485294 3.9691331387 4.4319362640 2321 1311867247.8752439022 0.0930832028 0.0919275113 0.1207853556 0.0060534233 0.0156090000 0.0005770000 0.0035500000 0.0000080000 0.0000080000 0.0014920000 44585197 96830484 509673472 3.8618535995 3.9698004723 4.4298186302 2322 1311867247.9113290310 0.0937439576 0.0919282936 0.1207853556 0.0060528259 0.0125220000 0.0004760000 0.0049220000 0.0000000000 0.0000040000 0.0007380000 44588981 96830484 509673472 3.8617265224 3.9688768387 4.4276638031 2323 1311867247.9430620670 0.0933743864 0.0919289161 0.1207853556 0.0060518181 0.0108440000 0.0004580000 0.0033220000 0.0000040000 0.0000040000 0.0009750000 44592709 96830484 509673472 3.8627970219 3.9687135220 4.4255785942 2324 1311867247.9769830704 0.0933449641 0.0919295254 0.1207853556 0.0060506002 0.0102970000 0.0004650000 0.0029450000 0.0000010000 0.0000040000 0.0007480000 44596437 96830484 509673472 3.8635210991 3.9692161083 4.4237713814 2325 1311867248.0109910965 0.0934561789 0.0919301820 0.1207853556 0.0060511045 0.0106750000 0.0004760000 0.0029410000 0.0000040000 0.0000040000 0.0013210000 44600109 96830484 509673472 3.8641345501 3.9671602249 4.4215183258 2326 1311867248.0431969166 0.0937078372 0.0919309463 0.1207853556 0.0060504161 0.0098960000 0.0004630000 0.0025370000 0.0000000000 0.0000030000 0.0007260000 44603837 96830484 509673472 3.8635213375 3.9672007561 4.4192075729 2327 1311867248.0751419067 0.0937597528 0.0919317322 0.1207853556 0.0060493589 0.0111670000 0.0005130000 0.0030320000 0.0000040000 0.0000040000 0.0009890000 44607453 96830484 509673472 3.8637690544 3.9674775600 4.4168996811 2328 1311867248.1121830940 0.0937171280 0.0919324991 0.1207853556 0.0060482798 0.0123000000 0.0004640000 0.0048900000 0.0000000000 0.0000040000 0.0007290000 44611293 96830484 509673472 3.8644056320 3.9665632248 4.4143085480 2329 1311867248.1431720257 0.0940156728 0.0919333935 0.1207853556 0.0060477002 0.0109870000 0.0004650000 0.0029220000 0.0000040000 0.0000030000 0.0013310000 44614909 96830484 509673472 3.8637912273 3.9668662548 4.4117722511 2330 1311867248.1757500172 0.0942494348 0.0919343875 0.1207853556 0.0060464055 0.0124540000 0.0004610000 0.0048990000 0.0000010000 0.0000040000 0.0007380000 44618525 96830484 509673472 3.8639643192 3.9667141438 4.4094247818 2331 1311867248.2111859322 0.0938264355 0.0919351992 0.1207853556 0.0060453020 0.0105860000 0.0004670000 0.0029290000 0.0000040000 0.0000040000 0.0009950000 44622365 96830484 509673472 3.8643782139 3.9666588306 4.4069786072 2332 1311867248.2431430817 0.0941677466 0.0919361566 0.1207853556 0.0060441550 0.0253990000 0.0006520000 0.0033120000 0.0000020000 0.0000160000 0.0012280000 44626037 96830484 509673472 3.8644039631 3.9669678211 4.4047269821 2333 1311867248.2755289078 0.0940772668 0.0919370743 0.1207853556 0.0060428790 0.0150280000 0.0005020000 0.0049910000 0.0000050000 0.0000050000 0.0013910000 44629709 96830484 509673472 3.8648769855 3.9669020176 4.4022383690 2334 1311867248.3112230301 0.0937171876 0.0919378370 0.1207853556 0.0060430245 0.0125290000 0.0004570000 0.0048980000 0.0000000000 0.0000030000 0.0007450000 44633437 96830484 509673472 3.8649966717 3.9670450687 4.3995714188 2335 1311867248.3434588909 0.0939694196 0.0919387071 0.1207853556 0.0060432935 0.0113590000 0.0004600000 0.0036980000 0.0000040000 0.0000040000 0.0010000000 44636997 96830484 509673472 3.8655147552 3.9676752090 4.3972954750 2336 1311867248.3752219677 0.0940623283 0.0919396162 0.1207853556 0.0060449035 0.0110080000 0.0004610000 0.0033200000 0.0000000000 0.0000040000 0.0007480000 44640669 96830484 509673472 3.8661010265 3.9691433907 4.3951268196 2337 1311867248.4115560055 0.0938912630 0.0919404513 0.1207853556 0.0060455644 0.0157850000 0.0005250000 0.0050450000 0.0000070000 0.0000060000 0.0014510000 44644509 96830484 509673472 3.8662798405 3.9691526890 4.3928689957 2338 1311867248.4431369305 0.0938950181 0.0919412873 0.1207853556 0.0060442986 0.0105710000 0.0004670000 0.0029400000 0.0000010000 0.0000040000 0.0007540000 44648125 96830484 509673472 3.8673574924 3.9691610336 4.3904495239 2339 1311867248.4759230614 0.0943694934 0.0919423254 0.1207853556 0.0060434157 0.0147470000 0.0005680000 0.0035170000 0.0000080000 0.0000080000 0.0011010000 44651853 96830484 509673472 3.8669507504 3.9694428444 4.3881411552 2340 1311867248.5111510754 0.0937579796 0.0919431013 0.1207853556 0.0060429116 0.0105910000 0.0004710000 0.0029360000 0.0000000000 0.0000050000 0.0007640000 44655581 96830484 509673472 3.8678843975 3.9701099396 4.3858327866 2341 1311867248.5431890488 0.0942289531 0.0919440778 0.1207853556 0.0060418162 0.0109530000 0.0004600000 0.0029250000 0.0000040000 0.0000030000 0.0013760000 44659309 96830484 509673472 3.8682146072 3.9702215195 4.3834772110 2342 1311867248.5751869678 0.0938800648 0.0919449044 0.1207853556 0.0060408244 0.0121020000 0.0004600000 0.0047410000 0.0000010000 0.0000040000 0.0007530000 44662925 96830484 509673472 3.8688585758 3.9699914455 4.3811244965 2343 1311867248.6114389896 0.0935311839 0.0919455814 0.1207853556 0.0060398079 0.0109450000 0.0004550000 0.0033320000 0.0000030000 0.0000030000 0.0009890000 44666765 96830484 509673472 3.8698773384 3.9704902172 4.3787903786 2344 1311867248.6432449818 0.0940925702 0.0919464974 0.1207853556 0.0060385419 0.0121210000 0.0004630000 0.0047500000 0.0000010000 0.0000040000 0.0007550000 44670381 96830484 509673472 3.8698358536 3.9701466560 4.3763523102 2345 1311867248.6753089428 0.0938740596 0.0919473194 0.1207853556 0.0060372961 0.0129720000 0.0004570000 0.0049070000 0.0000040000 0.0000040000 0.0013780000 44673997 96830484 509673472 3.8696866035 3.9706058502 4.3737854958 2346 1311867248.7112829685 0.0943659097 0.0919483503 0.1207853556 0.0060370119 0.0131480000 0.0004630000 0.0048830000 0.0000000000 0.0000040000 0.0007540000 44677837 96830484 509673472 3.8699777126 3.9716510773 4.3713436127 2347 1311867248.7433049679 0.0942633748 0.0919493367 0.1207853556 0.0060370695 0.0128140000 0.0005060000 0.0048740000 0.0000040000 0.0000040000 0.0010060000 44681453 96830484 509673472 3.8704710007 3.9717607498 4.3686361313 2348 1311867248.7762219906 0.0938773006 0.0919501578 0.1207853556 0.0060358311 0.0123270000 0.0004760000 0.0048650000 0.0000010000 0.0000040000 0.0007560000 44685181 96830484 509673472 3.8710739613 3.9722113609 4.3658218384 2349 1311867248.8111898899 0.0943208411 0.0919511670 0.1207853556 0.0060380317 0.0125080000 0.0004630000 0.0044960000 0.0000030000 0.0000030000 0.0013780000 44688909 96830484 509673472 3.8710741997 3.9735021591 4.3633151054 2350 1311867248.8433189392 0.0939841047 0.0919520321 0.1207853556 0.0060450578 0.0104280000 0.0004610000 0.0029270000 0.0000000000 0.0000040000 0.0007580000 44692581 96830484 509673472 3.8714563847 3.9727535248 4.3603224754 2351 1311867248.8755309582 0.0943179280 0.0919530385 0.1207853556 0.0060447602 0.0109180000 0.0004580000 0.0033210000 0.0000040000 0.0000040000 0.0009990000 44696309 96830484 509673472 3.8719301224 3.9721951485 4.3573746681 2352 1311867248.9111700058 0.0946538374 0.0919541868 0.1207853556 0.0060442482 0.0109850000 0.0004660000 0.0035740000 0.0000000000 0.0000030000 0.0007560000 44700093 96830484 509673472 3.8726592064 3.9737544060 4.3546237946 2353 1311867248.9430971146 0.0948132277 0.0919554018 0.1207853556 0.0060430691 0.0129060000 0.0004570000 0.0048730000 0.0000040000 0.0000040000 0.0013810000 44703709 96830484 509673472 3.8728699684 3.9734196663 4.3515167236 2354 1311867248.9766070843 0.0951866060 0.0919567745 0.1207853556 0.0060426311 0.0124290000 0.0004580000 0.0048780000 0.0000010000 0.0000040000 0.0007630000 44707493 96830484 509673472 3.8733193874 3.9728372097 4.3483481407 2355 1311867249.0112600327 0.0953264758 0.0919582053 0.1207853556 0.0060419274 0.0185530000 0.0006530000 0.0053340000 0.0000110000 0.0000110000 0.0012130000 44711165 96830484 509673472 3.8743476868 3.9740519524 4.3454027176 2356 1311867249.0432310104 0.0952102393 0.0919595857 0.1207853556 0.0060410420 0.0116950000 0.0004730000 0.0037400000 0.0000000000 0.0000050000 0.0007690000 44714837 96830484 509673472 3.8763608932 3.9744782448 4.3424539566 2357 1311867249.0799250603 0.0956276432 0.0919611419 0.1207853556 0.0060399856 0.0150840000 0.0005540000 0.0035130000 0.0000080000 0.0000090000 0.0015590000 44718677 96830484 509673472 3.8764569759 3.9746403694 4.3393430710 2358 1311867249.1120550632 0.0955934599 0.0919626823 0.1207853556 0.0060397033 0.0110240000 0.0004750000 0.0033360000 0.0000010000 0.0000040000 0.0007700000 44722349 96830484 509673472 3.8777816296 3.9759318829 4.3365936279 2359 1311867249.1435980797 0.0954221189 0.0919641488 0.1207853556 0.0060396088 0.0101450000 0.0004600000 0.0025360000 0.0000040000 0.0000040000 0.0009930000 44726021 96830484 509673472 3.8793494701 3.9767010212 4.3338103294 2360 1311867249.1785130501 0.0948800594 0.0919653844 0.1207853556 0.0060400155 0.0124790000 0.0004600000 0.0048820000 0.0000010000 0.0000040000 0.0007600000 44729693 96830484 509673472 3.8813872337 3.9754691124 4.3306288719 2361 1311867249.2113580704 0.0951639712 0.0919667391 0.1207853556 0.0060396242 0.0123000000 0.0004600000 0.0040870000 0.0000030000 0.0000030000 0.0014190000 44733421 96830484 509673472 3.8819682598 3.9768130779 4.3277597427 2362 1311867249.2432780266 0.0958328173 0.0919683759 0.1207853556 0.0060394727 0.0111470000 0.0004610000 0.0037130000 0.0000010000 0.0000040000 0.0007650000 44737149 96830484 509673472 3.8826456070 3.9778878689 4.3250417709 2363 1311867249.2773559093 0.0958538130 0.0919700202 0.1207853556 0.0060414712 0.0101580000 0.0004580000 0.0025370000 0.0000040000 0.0000040000 0.0010320000 44740877 96830484 509673472 3.8833792210 3.9760067463 4.3218564987 2364 1311867249.3112919331 0.0957276225 0.0919716097 0.1207853556 0.0060428903 0.0111780000 0.0004610000 0.0037150000 0.0000010000 0.0000040000 0.0007810000 44744549 96830484 509673472 3.8845086098 3.9773623943 4.3190369606 2365 1311867249.3437249660 0.0959133431 0.0919732764 0.1207853556 0.0060422042 0.0163930000 0.0005800000 0.0047190000 0.0000090000 0.0000080000 0.0015870000 44748277 96830484 509673472 3.8856236935 3.9787189960 4.3164052963 2366 1311867249.3768579960 0.0955440402 0.0919747856 0.1207853556 0.0060440718 0.0125100000 0.0004740000 0.0048830000 0.0000010000 0.0000050000 0.0007880000 44752005 96830484 509673472 3.8867285252 3.9776704311 4.3134636879 2367 1311867249.4112169743 0.0959368423 0.0919764595 0.1207853556 0.0060435414 0.0126240000 0.0004570000 0.0048680000 0.0000040000 0.0000040000 0.0010340000 44755733 96830484 509673472 3.8872556686 3.9775440693 4.3105907440 2368 1311867249.4432210922 0.0956971124 0.0919780307 0.1207853556 0.0060431410 0.0123780000 0.0004620000 0.0048590000 0.0000000000 0.0000030000 0.0007910000 44759349 96830484 509673472 3.8885004520 3.9787187576 4.3080644608 2369 1311867249.4764440060 0.0960419029 0.0919797461 0.1207853556 0.0060419113 0.0164720000 0.0005510000 0.0051210000 0.0000080000 0.0000070000 0.0015900000 44763077 96830484 509673472 3.8886430264 3.9781033993 4.3052668571 2370 1311867249.5111339092 0.0958423764 0.0919813759 0.1207853556 0.0060413701 0.0125070000 0.0004690000 0.0048840000 0.0000000000 0.0000040000 0.0007880000 44766805 96830484 509673472 3.8891632557 3.9772081375 4.3022823334 2371 1311867249.5432300568 0.0957911164 0.0919829827 0.1207853556 0.0060409328 0.0126130000 0.0004550000 0.0048670000 0.0000040000 0.0000040000 0.0010410000 44770477 96830484 509673472 3.8896696568 3.9784207344 4.2997198105 2372 1311867249.5759820938 0.0956751257 0.0919845393 0.1207853556 0.0060396745 0.0126070000 0.0004540000 0.0048660000 0.0000000000 0.0000030000 0.0007890000 44774205 96830484 509673472 3.8905339241 3.9783537388 4.2969121933 2373 1311867249.6112229824 0.0955460072 0.0919860401 0.1207853556 0.0060387581 0.0145360000 0.0005180000 0.0030720000 0.0000080000 0.0000090000 0.0015680000 44777933 96830484 509673472 3.8906993866 3.9773130417 4.2939591408 2374 1311867249.6433780193 0.0957951918 0.0919876446 0.1207853556 0.0060407431 0.0114430000 0.0004700000 0.0033500000 0.0000010000 0.0000050000 0.0008100000 44781605 96830484 509673472 3.8908720016 3.9788863659 4.2917456627 2375 1311867249.6751029491 0.0948330462 0.0919888427 0.1207853556 0.0060457171 0.0108310000 0.0004620000 0.0029220000 0.0000030000 0.0000030000 0.0010510000 44785277 96830484 509673472 3.8918879032 3.9786229134 4.2891254425 2376 1311867249.7111389637 0.0954339281 0.0919902927 0.1207853556 0.0060452042 0.0107960000 0.0004640000 0.0031940000 0.0000010000 0.0000040000 0.0007990000 44789005 96830484 509673472 3.8920140266 3.9774382114 4.2863020897 2377 1311867249.7432470322 0.0955098569 0.0919917733 0.1207853556 0.0060470118 0.0114920000 0.0004610000 0.0031940000 0.0000040000 0.0000030000 0.0014620000 44792733 96830484 509673472 3.8919980526 3.9791491032 4.2837667465 2378 1311867249.7751579285 0.0948891640 0.0919929917 0.1207853556 0.0060482261 0.0102600000 0.0004630000 0.0025290000 0.0000000000 0.0000040000 0.0007970000 44796349 96830484 509673472 3.8921973705 3.9804968834 4.2815852165 2379 1311867249.8111488819 0.0952166840 0.0919943468 0.1207853556 0.0060471770 0.0147190000 0.0005530000 0.0031290000 0.0000080000 0.0000080000 0.0011680000 44800189 96830484 509673472 3.8929512501 3.9798879623 4.2790174484 2380 1311867249.8433248997 0.0950282961 0.0919956216 0.1207853556 0.0060459320 0.0126850000 0.0004720000 0.0047760000 0.0000000000 0.0000040000 0.0008130000 44803805 96830484 509673472 3.8935663700 3.9815464020 4.2766656876 2381 1311867249.8784089088 0.0955406278 0.0919971104 0.1207853556 0.0060448341 0.0112060000 0.0004570000 0.0029330000 0.0000040000 0.0000040000 0.0014560000 44807589 96830484 509673472 3.8934831619 3.9824488163 4.2744174004 2382 1311867249.9112401009 0.0955166295 0.0919985880 0.1207853556 0.0060436975 0.0124730000 0.0004620000 0.0048990000 0.0000010000 0.0000040000 0.0007970000 44811261 96830484 509673472 3.8945772648 3.9830365181 4.2717351913 2383 1311867249.9432768822 0.0951126963 0.0919998948 0.1207853556 0.0060433640 0.0126270000 0.0004610000 0.0048750000 0.0000030000 0.0000040000 0.0010550000 44814989 96830484 509673472 3.8951709270 3.9829764366 4.2689423561 2384 1311867249.9751698971 0.0953785628 0.0920013120 0.1207853556 0.0060430858 0.0125930000 0.0004640000 0.0048780000 0.0000000000 0.0000050000 0.0007990000 44818605 96830484 509673472 3.8953578472 3.9837920666 4.2661628723 2385 1311867250.0117108822 0.0952032357 0.0920026545 0.1207853556 0.0060423917 0.0130410000 0.0004580000 0.0048700000 0.0000040000 0.0000030000 0.0014520000 44822445 96830484 509673472 3.8958194256 3.9843385220 4.2632231712 2386 1311867250.0434269905 0.0957733318 0.0920042349 0.1207853556 0.0060417791 0.0125850000 0.0004640000 0.0048770000 0.0000010000 0.0000040000 0.0007980000 44826117 96830484 509673472 3.8956933022 3.9846744537 4.2602210045 2387 1311867250.0767190456 0.0956463218 0.0920057607 0.1207853556 0.0060419883 0.0124110000 0.0004590000 0.0044840000 0.0000040000 0.0000040000 0.0010560000 44829845 96830484 509673472 3.8957550526 3.9840731621 4.2570691109 2388 1311867250.1116099358 0.0962067917 0.0920075199 0.1207853556 0.0060412642 0.0126470000 0.0004570000 0.0048680000 0.0000010000 0.0000040000 0.0007970000 44833573 96830484 509673472 3.8957355022 3.9849364758 4.2543354034 2389 1311867250.1432220936 0.0962964073 0.0920093152 0.1207853556 0.0060400374 0.0116990000 0.0004580000 0.0033080000 0.0000040000 0.0000040000 0.0014770000 44837189 96830484 509673472 3.8963246346 3.9848732948 4.2513422966 2390 1311867250.1758980751 0.0963491052 0.0920111310 0.1207853556 0.0060388104 0.0127330000 0.0004740000 0.0042810000 0.0000000000 0.0000040000 0.0008590000 44840917 96830484 509673472 3.8965892792 3.9844052792 4.2482328415 2391 1311867250.2133369446 0.0964274481 0.0920129780 0.1207853556 0.0060376292 0.0153770000 0.0005650000 0.0035250000 0.0000080000 0.0000080000 0.0011830000 44844701 96830484 509673472 3.8975977898 3.9854428768 4.2453064919 2392 1311867250.2457129955 0.0964794904 0.0920148453 0.1207853556 0.0060370079 0.0161610000 0.0005610000 0.0039610000 0.0000010000 0.0000110000 0.0009440000 44848429 96830484 509673472 3.8976669312 3.9861631393 4.2425241470 2393 1311867250.2751679420 0.0970945507 0.0920169680 0.1207853556 0.0060377001 0.0114530000 0.0004660000 0.0025700000 0.0000050000 0.0000040000 0.0014850000 44851989 96830484 509673472 3.8967428207 3.9866511822 4.2397279739 2394 1311867250.3114409447 0.0968526900 0.0920189880 0.1207853556 0.0060372632 0.0125780000 0.0004600000 0.0048930000 0.0000010000 0.0000040000 0.0008060000 44855829 96830484 509673472 3.8981971741 3.9867794514 4.2371630669 2395 1311867250.3431971073 0.0971040353 0.0920211112 0.1207853556 0.0060367348 0.0103150000 0.0004610000 0.0025410000 0.0000040000 0.0000040000 0.0010690000 44859445 96830484 509673472 3.8982639313 3.9877469540 4.2348275185 2396 1311867250.3780639172 0.0969951600 0.0920231872 0.1207853556 0.0060357042 0.0109840000 0.0004630000 0.0033190000 0.0000000000 0.0000050000 0.0008090000 44863229 96830484 509673472 3.8984444141 3.9880363941 4.2322797775 2397 1311867250.4116489887 0.0972066671 0.0920253496 0.1207853556 0.0060352657 0.0131090000 0.0004610000 0.0048750000 0.0000040000 0.0000040000 0.0014870000 44866957 96830484 509673472 3.8989474773 3.9877367020 4.2296199799 2398 1311867250.4441781044 0.0969144702 0.0920273885 0.1207853556 0.0060340510 0.0125540000 0.0004640000 0.0048900000 0.0000000000 0.0000050000 0.0008070000 44870573 96830484 509673472 3.8991372585 3.9880204201 4.2270793915 2399 1311867250.4793250561 0.0969316661 0.0920294328 0.1207853556 0.0060329910 0.0113220000 0.0004640000 0.0033170000 0.0000040000 0.0000040000 0.0010690000 44874357 96830484 509673472 3.9003667831 3.9895029068 4.2247295380 2400 1311867250.5113220215 0.0970058516 0.0920315063 0.1207853556 0.0060324752 0.0145960000 0.0005740000 0.0031190000 0.0000010000 0.0000080000 0.0009390000 44878029 96830484 509673472 3.9005181789 3.9890451431 4.2222747803 2401 1311867250.5443398952 0.0968937129 0.0920335314 0.1207853556 0.0060313153 0.0127010000 0.0004730000 0.0041320000 0.0000040000 0.0000040000 0.0014980000 44881701 96830484 509673472 3.9012992382 3.9890775681 4.2198820114 2402 1311867250.5793490410 0.0977840871 0.0920359254 0.1207853556 0.0060307038 0.0113400000 0.0004620000 0.0037150000 0.0000000000 0.0000040000 0.0008010000 44885485 96830484 509673472 3.9008889198 3.9909849167 4.2179322243 2403 1311867250.6114881039 0.0977293104 0.0920382947 0.1207853556 0.0060296722 0.0108640000 0.0004570000 0.0029330000 0.0000040000 0.0000040000 0.0010680000 44889213 96830484 509673472 3.9018278122 3.9907376766 4.2156867981 2404 1311867250.6433761120 0.0975843295 0.0920406017 0.1207853556 0.0060293965 0.0162280000 0.0005770000 0.0044020000 0.0000010000 0.0000090000 0.0009360000 44892885 96830484 509673472 3.9020361900 3.9898588657 4.2130961418 2405 1311867250.6795539856 0.0984714329 0.0920432757 0.1207853556 0.0060297248 0.0159820000 0.0005700000 0.0043010000 0.0000080000 0.0000080000 0.0016600000 44896613 96830484 509673472 3.9020519257 3.9912323952 4.2108802795 2406 1311867250.7112920284 0.0978597105 0.0920456931 0.1207853556 0.0060288032 0.0108700000 0.0004640000 0.0029420000 0.0000010000 0.0000050000 0.0008200000 44900285 96830484 509673472 3.9032001495 3.9917159081 4.2084841728 2407 1311867250.7445890903 0.0986312553 0.0920484291 0.1207853556 0.0060305058 0.0104000000 0.0004640000 0.0025400000 0.0000040000 0.0000040000 0.0010710000 44904013 96830484 509673472 3.9017729759 3.9907093048 4.2059450150 2408 1311867250.7792830467 0.0986289158 0.0920511619 0.1207853556 0.0060301355 0.0105360000 0.0004670000 0.0029250000 0.0000000000 0.0000040000 0.0008140000 44907685 96830484 509673472 3.9025933743 3.9909021854 4.2037296295 2409 1311867250.8145580292 0.0986865237 0.0920539163 0.1207853556 0.0060294801 0.0157970000 0.0005720000 0.0039390000 0.0000080000 0.0000070000 0.0016840000 44911469 96830484 509673472 3.9027540684 3.9917676449 4.2017397881 2410 1311867250.8433599472 0.0985086113 0.0920565946 0.1207853556 0.0060285188 0.0105710000 0.0004610000 0.0025520000 0.0000010000 0.0000050000 0.0008290000 44915029 96830484 509673472 3.9028196335 3.9905173779 4.1996455193 2411 1311867250.8792760372 0.0981571674 0.0920591249 0.1207853556 0.0060298738 0.0127480000 0.0004660000 0.0036960000 0.0000040000 0.0000040000 0.0010800000 44918813 96830484 509673472 3.9028325081 3.9899604321 4.1975736618 2412 1311867250.9116361141 0.0984890461 0.0920617907 0.1207853556 0.0060293105 0.0120330000 0.0005100000 0.0040810000 0.0000000000 0.0000040000 0.0008200000 44922541 96830484 509673472 3.9025139809 3.9902465343 4.1955456734 2413 1311867250.9433720112 0.0980149582 0.0920642578 0.1207853556 0.0060284392 0.0126270000 0.0004590000 0.0040850000 0.0000030000 0.0000030000 0.0015270000 44926157 96830484 509673472 3.9034249783 3.9895861149 4.1935558319 2414 1311867250.9793050289 0.0985489190 0.0920669441 0.1207853556 0.0060279533 0.0106000000 0.0004570000 0.0029200000 0.0000000000 0.0000040000 0.0008200000 44929941 96830484 509673472 3.9027676582 3.9903287888 4.1916689873 2415 1311867251.0112459660 0.0980164632 0.0920694077 0.1207853556 0.0060271729 0.0116650000 0.0004590000 0.0036830000 0.0000030000 0.0000030000 0.0010870000 44933613 96830484 509673472 3.9034311771 3.9906468391 4.1898941994 2416 1311867251.0437910557 0.0985040665 0.0920720710 0.1207853556 0.0060266596 0.0125170000 0.0004580000 0.0048470000 0.0000000000 0.0000030000 0.0008220000 44937285 96830484 509673472 3.9027900696 3.9893276691 4.1876845360 2417 1311867251.0793159008 0.0986320227 0.0920747851 0.1207853556 0.0060261167 0.0153870000 0.0005790000 0.0027230000 0.0000080000 0.0000070000 0.0016870000 44941069 96830484 509673472 3.9026923180 3.9895377159 4.1856436729 2418 1311867251.1115839481 0.0982785895 0.0920773508 0.1207853556 0.0060251187 0.0127370000 0.0004720000 0.0048850000 0.0000000000 0.0000040000 0.0008260000 44944797 96830484 509673472 3.9027953148 3.9903774261 4.1839938164 2419 1311867251.1432809830 0.0988931730 0.0920801684 0.1207853556 0.0060247889 0.0155040000 0.0005640000 0.0035160000 0.0000090000 0.0000070000 0.0012080000 44948469 96830484 509673472 3.9021224976 3.9899613857 4.1818771362 2420 1311867251.1794250011 0.0982520729 0.0920827188 0.1207853556 0.0060265596 0.0127670000 0.0004720000 0.0048760000 0.0000000000 0.0000050000 0.0008370000 44952253 96830484 509673472 3.9025981426 3.9888834953 4.1797389984 2421 1311867251.2113831043 0.0989379361 0.0920855503 0.1207853556 0.0060323121 0.0128050000 0.0004630000 0.0044410000 0.0000040000 0.0000030000 0.0015180000 44955925 96830484 509673472 3.9019658566 3.9905090332 4.1779761314 2422 1311867251.2472319603 0.0986060724 0.0920882426 0.1207853556 0.0060330773 0.0125670000 0.0004610000 0.0048390000 0.0000010000 0.0000040000 0.0008260000 44959709 96830484 509673472 3.9020607471 3.9902398586 4.1759839058 2423 1311867251.2793700695 0.0984325334 0.0920908609 0.1207853556 0.0060319887 0.0116690000 0.0004660000 0.0036780000 0.0000040000 0.0000030000 0.0010890000 44963325 96830484 509673472 3.9019985199 3.9883780479 4.1736273766 2424 1311867251.3133869171 0.0986070633 0.0920935491 0.1207853556 0.0060320115 0.0113570000 0.0004650000 0.0036870000 0.0000010000 0.0000040000 0.0008260000 44967109 96830484 509673472 3.9018695354 3.9890954494 4.1717677116 2425 1311867251.3432419300 0.0980675071 0.0920960126 0.1207853556 0.0060344647 0.0133870000 0.0004580000 0.0048370000 0.0000040000 0.0000040000 0.0015270000 44970669 96830484 509673472 3.9010248184 3.9887924194 4.1696672440 2426 1311867251.3801820278 0.0983062461 0.0920985725 0.1207853556 0.0060333475 0.0158310000 0.0005670000 0.0027270000 0.0000010000 0.0000110000 0.0010730000 44974509 96830484 509673472 3.9010326862 3.9881474972 4.1675257683 2427 1311867251.4113550186 0.0979412794 0.0921009798 0.1207853556 0.0060322882 0.0133840000 0.0004660000 0.0048740000 0.0000050000 0.0000040000 0.0011010000 44978181 96830484 509673472 3.9012143612 3.9886898994 4.1655769348 2428 1311867251.4433960915 0.0987126753 0.0921037030 0.1207853556 0.0060316829 0.0127310000 0.0004600000 0.0048450000 0.0000010000 0.0000040000 0.0008330000 44981797 96830484 509673472 3.9003605843 3.9886589050 4.1637377739 2429 1311867251.4793379307 0.0983911157 0.0921062914 0.1207853556 0.0060304996 0.0132750000 0.0004600000 0.0047090000 0.0000040000 0.0000040000 0.0015470000 44985581 96830484 509673472 3.9007248878 3.9882440567 4.1618456841 2430 1311867251.5175099373 0.0983552188 0.0921088630 0.1207853556 0.0060295333 0.0160930000 0.0005540000 0.0050650000 0.0000010000 0.0000080000 0.0009400000 44989477 96830484 509673472 3.9006073475 3.9881999493 4.1599922180 2431 1311867251.5431749821 0.0990363061 0.0921117126 0.1207853556 0.0060288383 0.0130590000 0.0004580000 0.0048660000 0.0000050000 0.0000040000 0.0011040000 44992925 96830484 509673472 3.9002556801 3.9883608818 4.1582870483 2432 1311867251.5795340538 0.0993914157 0.0921147059 0.1207853556 0.0060277056 0.0106730000 0.0004600000 0.0028980000 0.0000000000 0.0000040000 0.0008390000 44996765 96830484 509673472 3.9003179073 3.9883897305 4.1563811302 2433 1311867251.6119680405 0.0991562828 0.0921176001 0.1207853556 0.0060264692 0.0114680000 0.0004530000 0.0029190000 0.0000040000 0.0000040000 0.0015410000 45000493 96830484 509673472 3.9007372856 3.9885039330 4.1545138359 2434 1311867251.6432960033 0.0986553207 0.0921202861 0.1207853556 0.0060256853 0.0125190000 0.0004580000 0.0048280000 0.0000010000 0.0000040000 0.0008360000 45004109 96830484 509673472 3.9012734890 3.9880177975 4.1525068283 2435 1311867251.6797280312 0.0994718000 0.0921233052 0.1207853556 0.0060262895 0.0128970000 0.0004600000 0.0048410000 0.0000040000 0.0000040000 0.0010990000 45007893 96830484 509673472 3.9003908634 3.9876632690 4.1505379677 2436 1311867251.7123379707 0.0993300676 0.0921262637 0.1207853556 0.0060261227 0.0110820000 0.0004520000 0.0032990000 0.0000010000 0.0000040000 0.0008410000 45011621 96830484 509673472 3.9006361961 3.9886939526 4.1486077309 2437 1311867251.7434990406 0.0985780135 0.0921289111 0.1207853556 0.0060252741 0.0133780000 0.0004690000 0.0048430000 0.0000030000 0.0000040000 0.0015340000 45015181 96830484 509673472 3.9018917084 3.9895386696 4.1467738152 2438 1311867251.7797439098 0.0987466052 0.0921316255 0.1207853556 0.0060247337 0.0107210000 0.0004590000 0.0029220000 0.0000010000 0.0000040000 0.0008330000 45019021 96830484 509673472 3.9015474319 3.9875485897 4.1444797516 2439 1311867251.8112530708 0.0989687964 0.0921344287 0.1207853556 0.0060245004 0.0122560000 0.0004630000 0.0040660000 0.0000030000 0.0000030000 0.0011010000 45022693 96830484 509673472 3.9008288383 3.9881024361 4.1423864365 2440 1311867251.8433279991 0.0985028744 0.0921370388 0.1207853556 0.0060233771 0.0115510000 0.0004560000 0.0036820000 0.0000010000 0.0000040000 0.0008390000 45026365 96830484 509673472 3.9014873505 3.9892458916 4.1407432556 2441 1311867251.8805420399 0.0979908034 0.0921394369 0.1207853556 0.0060229411 0.0121920000 0.0004600000 0.0036770000 0.0000040000 0.0000040000 0.0015460000 45030093 96830484 509673472 3.9016530514 3.9885501862 4.1387863159 2442 1311867251.9112489223 0.0979551002 0.0921418184 0.1207853556 0.0060217201 0.0104050000 0.0004730000 0.0025130000 0.0000000000 0.0000030000 0.0008440000 45033765 96830484 509673472 3.9016795158 3.9889805317 4.1370921135 2443 1311867251.9432179928 0.0987399518 0.0921445192 0.1207853556 0.0060219123 0.0155600000 0.0005660000 0.0035340000 0.0000090000 0.0000080000 0.0012280000 45037381 96830484 509673472 3.9013128281 3.9902682304 4.1356477737 2444 1311867251.9800109863 0.0985072702 0.0921471226 0.1207853556 0.0060218413 0.0171240000 0.0005620000 0.0051130000 0.0000010000 0.0000080000 0.0009620000 45041221 96830484 509673472 3.9016938210 3.9895787239 4.1339073181 2445 1311867252.0119040012 0.0979575589 0.0921494991 0.1207853556 0.0060210373 0.0134720000 0.0004730000 0.0047630000 0.0000040000 0.0000040000 0.0015810000 45044949 96830484 509673472 3.9023036957 3.9898648262 4.1321191788 2446 1311867252.0441029072 0.0984602571 0.0921520791 0.1207853556 0.0060201450 0.0103310000 0.0004530000 0.0025240000 0.0000000000 0.0000030000 0.0008470000 45048621 96830484 509673472 3.9021532536 3.9894278049 4.1302347183 2447 1311867252.0794539452 0.0992884710 0.0921549955 0.1207853556 0.0060190941 0.0105650000 0.0004600000 0.0025230000 0.0000040000 0.0000040000 0.0011210000 45052293 96830484 509673472 3.9016964436 3.9892983437 4.1280608177 2448 1311867252.1122460365 0.0992536545 0.0921578953 0.1207853556 0.0060183568 0.0126370000 0.0004570000 0.0048410000 0.0000010000 0.0000040000 0.0008450000 45056077 96830484 509673472 3.9013597965 3.9890823364 4.1254172325 2449 1311867252.1432950497 0.0989859477 0.0921606834 0.1207853556 0.0060190594 0.0133040000 0.0004590000 0.0048520000 0.0000040000 0.0000040000 0.0015670000 45059637 96830484 509673472 3.9014501572 3.9876296520 4.1225929260 2450 1311867252.1794359684 0.0997244194 0.0921637706 0.1207853556 0.0060179925 0.0159690000 0.0005690000 0.0042970000 0.0000010000 0.0000080000 0.0009790000 45063421 96830484 509673472 3.9007291794 3.9872734547 4.1196837425 2451 1311867252.2113459110 0.0990090519 0.0921665635 0.1207853556 0.0060186427 0.0115600000 0.0004660000 0.0032020000 0.0000040000 0.0000040000 0.0011290000 45067149 96830484 509673472 3.9018385410 3.9876115322 4.1168680191 2452 1311867252.2432808876 0.0998666584 0.0921697038 0.1207853556 0.0060183847 0.0127480000 0.0004630000 0.0048430000 0.0000010000 0.0000040000 0.0008570000 45070821 96830484 509673472 3.9002294540 3.9859528542 4.1137757301 2453 1311867252.2794110775 0.0992593989 0.0921725940 0.1207853556 0.0060193685 0.0111360000 0.0004580000 0.0025120000 0.0000040000 0.0000040000 0.0015870000 45074605 96830484 509673472 3.9011147022 3.9844639301 4.1108493805 2454 1311867252.3112668991 0.0989257321 0.0921753459 0.1207853556 0.0060192432 0.0139460000 0.0004600000 0.0055110000 0.0000010000 0.0000040000 0.0008750000 45078277 96830484 509673472 3.9014024734 3.9843113422 4.1079468727 2455 1311867252.3450291157 0.0987255275 0.0921780140 0.1207853556 0.0060181821 0.0128940000 0.0004540000 0.0048310000 0.0000040000 0.0000030000 0.0011280000 45081949 96830484 509673472 3.9015347958 3.9839825630 4.1050281525 2456 1311867252.3794589043 0.0983177871 0.0921805139 0.1207853556 0.0060177358 0.0107590000 0.0004590000 0.0028980000 0.0000000000 0.0000040000 0.0008590000 45085733 96830484 509673472 3.9013185501 3.9806795120 4.1018285751 2457 1311867252.4111969471 0.0988685340 0.0921832359 0.1207853556 0.0060173583 0.0163800000 0.0005760000 0.0031370000 0.0000100000 0.0000090000 0.0018420000 45089405 96830484 509673472 3.9005668163 3.9795379639 4.0987625122 2458 1311867252.4456050396 0.1002765894 0.0921865286 0.1207853556 0.0060271913 0.0129730000 0.0004670000 0.0048480000 0.0000010000 0.0000040000 0.0008750000 45093133 96830484 509673472 3.8998167515 3.9798333645 4.0959692001 2459 1311867252.4792900085 0.0992085785 0.0921893843 0.1207853556 0.0060359388 0.0155720000 0.0005780000 0.0031070000 0.0000100000 0.0000100000 0.0012620000 45096805 96830484 509673472 3.8996107578 3.9782743454 4.0927939415 2460 1311867252.5112249851 0.0988371819 0.0921920866 0.1207853556 0.0060349133 0.0130120000 0.0004730000 0.0048580000 0.0000010000 0.0000050000 0.0008830000 45100533 96830484 509673472 3.8997106552 3.9766411781 4.0893907547 2461 1311867252.5432820320 0.0988175869 0.0921947788 0.1207853556 0.0060342760 0.0134960000 0.0004590000 0.0048100000 0.0000030000 0.0000030000 0.0016290000 45104205 96830484 509673472 3.9003493786 3.9770252705 4.0864934921 2462 1311867252.5791800022 0.0994976461 0.0921977450 0.1207853556 0.0060331307 0.0118990000 0.0004590000 0.0040260000 0.0000010000 0.0000040000 0.0008810000 45107989 96830484 509673472 3.8992512226 3.9765505791 4.0836048126 2463 1311867252.6112799644 0.0991784036 0.0922005792 0.1207853556 0.0060319592 0.0130400000 0.0004590000 0.0048050000 0.0000040000 0.0000040000 0.0011560000 45111661 96830484 509673472 3.8994381428 3.9749968052 4.0805001259 2464 1311867252.6432769299 0.0996431261 0.0922035998 0.1207853556 0.0060309169 0.0127330000 0.0004610000 0.0048170000 0.0000000000 0.0000030000 0.0008860000 45115389 96830484 509673472 3.8990492821 3.9746186733 4.0773100853 2465 1311867252.6792490482 0.1006037742 0.0922070075 0.1207853556 0.0060305503 0.0119020000 0.0004590000 0.0032430000 0.0000030000 0.0000040000 0.0016310000 45119061 96830484 509673472 3.8982403278 3.9744024277 4.0746164322 2466 1311867252.7112491131 0.1006869078 0.0922104463 0.1207853556 0.0060300259 0.0105760000 0.0004560000 0.0024990000 0.0000010000 0.0000040000 0.0008920000 45122789 96830484 509673472 3.8976361752 3.9732868671 4.0715155602 2467 1311867252.7432410717 0.1005646884 0.0922138327 0.1207853556 0.0060290041 0.0130490000 0.0004570000 0.0048000000 0.0000050000 0.0000040000 0.0011700000 45126405 96830484 509673472 3.8978791237 3.9713718891 4.0681114197 2468 1311867252.7792730331 0.1011591032 0.0922174572 0.1207853556 0.0060278490 0.0107660000 0.0004550000 0.0028740000 0.0000010000 0.0000040000 0.0009040000 45130189 96830484 509673472 3.8977530003 3.9713454247 4.0650382042 2469 1311867252.8112781048 0.1012891084 0.0922211314 0.1207853556 0.0060273014 0.0135430000 0.0004560000 0.0047780000 0.0000040000 0.0000040000 0.0016680000 45133917 96830484 509673472 3.8980786800 3.9717833996 4.0620226860 2470 1311867252.8433189392 0.1010054648 0.0922246878 0.1207853556 0.0060266329 0.0111080000 0.0004590000 0.0032360000 0.0000000000 0.0000030000 0.0009090000 45137589 96830484 509673472 3.8983571529 3.9702529907 4.0586552620 2471 1311867252.8792660236 0.1015908420 0.0922284782 0.1207853556 0.0060275407 0.0114700000 0.0004590000 0.0032410000 0.0000030000 0.0000030000 0.0011800000 45141317 96830484 509673472 3.8985927105 3.9705908298 4.0556626320 2472 1311867252.9112188816 0.1011488065 0.0922320868 0.1207853556 0.0060264088 0.0126640000 0.0004570000 0.0047830000 0.0000000000 0.0000030000 0.0009070000 45145045 96830484 509673472 3.8990001678 3.9710607529 4.0528993607 2473 1311867252.9446918964 0.1006555855 0.0922354930 0.1207853556 0.0060259684 0.0120090000 0.0004560000 0.0032740000 0.0000040000 0.0000040000 0.0016710000 45148717 96830484 509673472 3.8993515968 3.9698789120 4.0497570038 2474 1311867252.9806020260 0.1011820510 0.0922391092 0.1207853556 0.0060256425 0.0107450000 0.0004600000 0.0028740000 0.0000000000 0.0000040000 0.0009030000 45152501 96830484 509673472 3.8993771076 3.9685144424 4.0468163490 2475 1311867253.0113809109 0.0996992514 0.0922421234 0.1207853556 0.0060247643 0.0164790000 0.0005650000 0.0050320000 0.0000080000 0.0000080000 0.0012980000 45156173 96830484 509673472 3.9016671181 3.9705710411 4.0441226959 2476 1311867253.0434310436 0.1000765935 0.0922452876 0.1207853556 0.0060242871 0.0134770000 0.0005000000 0.0047980000 0.0000010000 0.0000040000 0.0008960000 45159845 96830484 509673472 3.9016714096 3.9688093662 4.0412473679 2477 1311867253.0799300671 0.0998446345 0.0922483555 0.1207853556 0.0060312648 0.0176380000 0.0005970000 0.0050580000 0.0000080000 0.0000080000 0.0018440000 45163629 96830484 509673472 3.9017875195 3.9671225548 4.0379714966 2478 1311867253.1113030910 0.1001049504 0.0922515261 0.1207853556 0.0060339594 0.0115850000 0.0004620000 0.0032700000 0.0000000000 0.0000040000 0.0009120000 45167301 96830484 509673472 3.9026060104 3.9686915874 4.0352582932 2479 1311867253.1440761089 0.1002186239 0.0922547399 0.1207853556 0.0060331788 0.0133130000 0.0004560000 0.0047640000 0.0000040000 0.0000040000 0.0011760000 45170973 96830484 509673472 3.9029200077 3.9680030346 4.0322098732 2480 1311867253.1794049740 0.1001648381 0.0922579295 0.1207853556 0.0060321517 0.0110280000 0.0004580000 0.0028520000 0.0000000000 0.0000040000 0.0009020000 45174701 96830484 509673472 3.9029610157 3.9673101902 4.0290288925 2481 1311867253.2112159729 0.1001359895 0.0922611048 0.1207853556 0.0060314953 0.0114180000 0.0004560000 0.0024820000 0.0000040000 0.0000030000 0.0016870000 45178429 96830484 509673472 3.9032223225 3.9667518139 4.0262427330 2482 1311867253.2458410263 0.0999895930 0.0922642186 0.1207853556 0.0060303306 0.0111170000 0.0004570000 0.0028550000 0.0000000000 0.0000030000 0.0009060000 45182157 96830484 509673472 3.9035158157 3.9671914577 4.0235586166 2483 1311867253.2793951035 0.1006401554 0.0922675919 0.1207853556 0.0060294662 0.0131840000 0.0004590000 0.0047620000 0.0000040000 0.0000040000 0.0011800000 45185829 96830484 509673472 3.9038157463 3.9667727947 4.0209784508 2484 1311867253.3114080429 0.0998788774 0.0922706561 0.1207853556 0.0060283136 0.0116800000 0.0004560000 0.0036140000 0.0000010000 0.0000040000 0.0009100000 45189557 96830484 509673472 3.9050734043 3.9667561054 4.0184316635 2485 1311867253.3445611000 0.1000799686 0.0922737986 0.1207853556 0.0060329741 0.0175780000 0.0005500000 0.0050110000 0.0000080000 0.0000070000 0.0018690000 45193285 96830484 509673472 3.9053981304 3.9664289951 4.0158681870 2486 1311867253.3794078827 0.0994963720 0.0922767039 0.1207853556 0.0060347845 0.0111260000 0.0004690000 0.0024840000 0.0000010000 0.0000050000 0.0009390000 45196957 96830484 509673472 3.9072237015 3.9664499760 4.0133695602 2487 1311867253.4129528999 0.0989780203 0.0922793985 0.1207853556 0.0060356283 0.0131930000 0.0004610000 0.0047560000 0.0000050000 0.0000040000 0.0012140000 45200741 96830484 509673472 3.9088878632 3.9660284519 4.0109229088 2488 1311867253.4444990158 0.1003334522 0.0922826356 0.1207853556 0.0060363398 0.0128130000 0.0004570000 0.0047380000 0.0000010000 0.0000040000 0.0009330000 45204357 96830484 509673472 3.9077270031 3.9660391808 4.0086717606 2489 1311867253.4804859161 0.1000759900 0.0922857668 0.1207853556 0.0060363012 0.0156520000 0.0005510000 0.0030310000 0.0000080000 0.0000070000 0.0018980000 45208141 96830484 509673472 3.9097728729 3.9667248726 4.0065522194 2490 1311867253.5113739967 0.1004050523 0.0922890275 0.1207853556 0.0060356989 0.0113610000 0.0004670000 0.0029750000 0.0000010000 0.0000040000 0.0009350000 45211813 96830484 509673472 3.9100127220 3.9652235508 4.0042238235 2491 1311867253.5441629887 0.1004860923 0.0922923182 0.1207853556 0.0060356443 0.0115610000 0.0004620000 0.0032170000 0.0000040000 0.0000040000 0.0012000000 45215429 96830484 509673472 3.9108214378 3.9639770985 4.0017290115 2492 1311867253.5794069767 0.1011598781 0.0922958766 0.1207853556 0.0060345894 0.0129670000 0.0004610000 0.0047340000 0.0000000000 0.0000040000 0.0009280000 45219213 96830484 509673472 3.9109511375 3.9637832642 3.9996266365 2493 1311867253.6118021011 0.1009998620 0.0922993680 0.1207853556 0.0060334288 0.0124780000 0.0004570000 0.0035930000 0.0000040000 0.0000040000 0.0017150000 45222941 96830484 509673472 3.9116041660 3.9623868465 3.9971077442 2494 1311867253.6447649002 0.1016020626 0.0923030980 0.1207853556 0.0060324941 0.0109170000 0.0004530000 0.0028420000 0.0000010000 0.0000040000 0.0009240000 45226613 96830484 509673472 3.9116578102 3.9615774155 3.9945924282 2495 1311867253.6799790859 0.1022057235 0.0923070670 0.1207853556 0.0060314804 0.0115430000 0.0004580000 0.0032200000 0.0000040000 0.0000050000 0.0011940000 45230397 96830484 509673472 3.9114544392 3.9612395763 3.9921269417 2496 1311867253.7115769386 0.1032166108 0.0923114378 0.1207853556 0.0060316405 0.0131230000 0.0004530000 0.0047230000 0.0000010000 0.0000040000 0.0009250000 45234069 96830484 509673472 3.9099750519 3.9595668316 3.9892163277 2497 1311867253.7435369492 0.1024671048 0.0923155049 0.1207853556 0.0060331982 0.0136890000 0.0004640000 0.0047360000 0.0000040000 0.0000030000 0.0017010000 45237685 96830484 509673472 3.9098796844 3.9570255280 3.9854342937 2498 1311867253.7806150913 0.1029598117 0.0923197661 0.1207853556 0.0060332862 0.0112580000 0.0004600000 0.0032110000 0.0000000000 0.0000040000 0.0009450000 45241469 96830484 509673472 3.9089941978 3.9561550617 3.9818923473 2499 1311867253.8113009930 0.1029296070 0.0923240117 0.1207853556 0.0060321444 0.0170370000 0.0005700000 0.0049870000 0.0000080000 0.0000080000 0.0013450000 45245141 96830484 509673472 3.9078409672 3.9549462795 3.9784121513 2500 1311867253.8469560146 0.1020933837 0.0923279195 0.1207853556 0.0060320871 0.0129710000 0.0004760000 0.0047580000 0.0000000000 0.0000040000 0.0009530000 45248925 96830484 509673472 3.9077522755 3.9539644718 3.9745540619 2501 1311867253.8792059422 0.1017127931 0.0923316719 0.1207853556 0.0060312930 0.0135860000 0.0004590000 0.0047350000 0.0000040000 0.0000030000 0.0017600000 45252541 96830484 509673472 3.9064943790 3.9514768124 3.9705073833 2502 1311867253.9114460945 0.1020139381 0.0923355417 0.1207853556 0.0060301254 0.0109380000 0.0004610000 0.0028380000 0.0000000000 0.0000050000 0.0009470000 45256213 96830484 509673472 3.9045035839 3.9502761364 3.9665300846 2503 1311867253.9461600780 0.1016699076 0.0923392710 0.1207853556 0.0060292746 0.0131720000 0.0004560000 0.0047180000 0.0000030000 0.0000040000 0.0012320000 45259997 96830484 509673472 3.9038052559 3.9512143135 3.9627676010 2504 1311867253.9794149399 0.1006186083 0.0923425774 0.1207853556 0.0060283546 0.0151060000 0.0005650000 0.0026470000 0.0000010000 0.0000090000 0.0010850000 45263613 96830484 509673472 3.9035639763 3.9504899979 3.9590823650 2505 1311867254.0119979382 0.1019337326 0.0923464062 0.1207853556 0.0060291847 0.0127740000 0.0004720000 0.0032450000 0.0000050000 0.0000050000 0.0017830000 45267341 96830484 509673472 3.8998184204 3.9486141205 3.9552452564 2506 1311867254.0457749367 0.1011764929 0.0923499298 0.1207853556 0.0060280994 0.0115570000 0.0004570000 0.0032060000 0.0000000000 0.0000040000 0.0009610000 45271069 96830484 509673472 3.8991875648 3.9479758739 3.9518175125 2507 1311867254.0793740749 0.1003898606 0.0923531368 0.1207853556 0.0060328397 0.0124800000 0.0004690000 0.0035790000 0.0000040000 0.0000030000 0.0012440000 45274741 96830484 509673472 3.8995816708 3.9474153519 3.9485182762 2508 1311867254.1113519669 0.0995435640 0.0923560038 0.1207853556 0.0060317300 0.0166010000 0.0005660000 0.0042150000 0.0000010000 0.0000100000 0.0010850000 45278413 96830484 509673472 3.8995330334 3.9463341236 3.9451637268 2509 1311867254.1476950645 0.1010746583 0.0923594788 0.1207853556 0.0060311268 0.0165580000 0.0005420000 0.0041690000 0.0000080000 0.0000080000 0.0019670000 45282253 96830484 509673472 3.8972401619 3.9474837780 3.9422793388 2510 1311867254.1795129776 0.1017711982 0.0923632284 0.1207853556 0.0060301760 0.0120200000 0.0004620000 0.0035810000 0.0000000000 0.0000040000 0.0009940000 45285869 96830484 509673472 3.8958668709 3.9478514194 3.9393632412 2511 1311867254.2114939690 0.1001590192 0.0923663331 0.1207853556 0.0060368286 0.0143160000 0.0004510000 0.0046930000 0.0000040000 0.0000040000 0.0012590000 45289597 96830484 509673472 3.8958604336 3.9466295242 3.9362227917 2512 1311867254.2469160557 0.1011762992 0.0923698403 0.1207853556 0.0060370465 0.0121230000 0.0004890000 0.0033120000 0.0000010000 0.0000040000 0.0009700000 45293381 96830484 509673472 3.8948001862 3.9471001625 3.9332766533 2513 1311867254.2798569202 0.1023856401 0.0923738258 0.1207853556 0.0060370423 0.0196070000 0.0006950000 0.0043980000 0.0000100000 0.0000100000 0.0021670000 45296997 96830484 509673472 3.8942940235 3.9496445656 3.9306128025 2514 1311867254.3114631176 0.1042970568 0.0923785686 0.1207853556 0.0060430245 0.0132960000 0.0004670000 0.0047490000 0.0000010000 0.0000040000 0.0009900000 45300669 96830484 509673472 3.8917291164 3.9515984058 3.9277970791 2515 1311867254.3475589752 0.1058670357 0.0923839318 0.1207853556 0.0060440516 0.0175800000 0.0005480000 0.0049890000 0.0000090000 0.0000070000 0.0014160000 45304509 96830484 509673472 3.8893568516 3.9496667385 3.9241485596 2516 1311867254.3794488907 0.1066277251 0.0923895931 0.1207853556 0.0060432461 0.0139500000 0.0004670000 0.0047250000 0.0000010000 0.0000040000 0.0010040000 45308125 96830484 509673472 3.8876245022 3.9480535984 3.9202592373 2517 1311867254.4115350246 0.1072523221 0.0923954980 0.1207853556 0.0060473725 0.0122300000 0.0005040000 0.0028220000 0.0000050000 0.0000040000 0.0020300000 45311853 96830484 509673472 3.8869109154 3.9496037960 3.9165561199 2518 1311867254.4483439922 0.1085949987 0.0924019315 0.1207853556 0.0060464519 0.0110590000 0.0004540000 0.0027890000 0.0000000000 0.0000040000 0.0009920000 45315637 96830484 509673472 3.8858718872 3.9502327442 3.9125614166 2519 1311867254.4794480801 0.1080946401 0.0924081612 0.1207853556 0.0060456812 0.0115790000 0.0004580000 0.0028060000 0.0000030000 0.0000030000 0.0012840000 45319253 96830484 509673472 3.8849554062 3.9492907524 3.9082608223 2520 1311867254.5114428997 0.1072818860 0.0924140635 0.1207853556 0.0060444844 0.0115340000 0.0004570000 0.0031760000 0.0000000000 0.0000040000 0.0010000000 45322925 96830484 509673472 3.8847131729 3.9496448040 3.9041225910 2521 1311867254.5500459671 0.1066363901 0.0924197050 0.1207853556 0.0060450104 0.0119690000 0.0004530000 0.0027970000 0.0000050000 0.0000040000 0.0018580000 45326765 96830484 509673472 3.8849511147 3.9506032467 3.8996345997 2522 1311867254.5794870853 0.1058206856 0.0924250187 0.1207853556 0.0060484789 0.0128070000 0.0004520000 0.0046600000 0.0000000000 0.0000030000 0.0010030000 45330381 96830484 509673472 3.8847086430 3.9508039951 3.8953881264 2523 1311867254.6114809513 0.1063462794 0.0924305364 0.1207853556 0.0060474570 0.0109140000 0.0004560000 0.0024140000 0.0000040000 0.0000030000 0.0012890000 45334053 96830484 509673472 3.8828868866 3.9523868561 3.8915386200 2524 1311867254.6452929974 0.1061424688 0.0924359690 0.1207853556 0.0060482742 0.0113490000 0.0004510000 0.0031590000 0.0000000000 0.0000050000 0.0010060000 45337781 96830484 509673472 3.8832643032 3.9542415142 3.8877913952 2525 1311867254.6794900894 0.1072804108 0.0924418480 0.1207853556 0.0060483338 0.0163470000 0.0005620000 0.0030070000 0.0000080000 0.0000070000 0.0020620000 45341565 96830484 509673472 3.8813195229 3.9541673660 3.8837170601 2526 1311867254.7113230228 0.1063428000 0.0924473512 0.1207853556 0.0060471750 0.0131720000 0.0004650000 0.0046920000 0.0000010000 0.0000050000 0.0010270000 45345237 96830484 509673472 3.8813617229 3.9542460442 3.8796007633 2527 1311867254.7453329563 0.1064145565 0.0924528784 0.1207853556 0.0060485453 0.0127060000 0.0004490000 0.0042560000 0.0000050000 0.0000040000 0.0012910000 45348909 96830484 509673472 3.8819415569 3.9558477402 3.8761296272 2528 1311867254.7794649601 0.1087513566 0.0924593255 0.1207853556 0.0060524214 0.0159940000 0.0005110000 0.0048090000 0.0000010000 0.0000070000 0.0010920000 45352637 96830484 509673472 3.8795568943 3.9569175243 3.8728077412 2529 1311867254.8115739822 0.1078773364 0.0924654220 0.1207853556 0.0060513458 0.0123230000 0.0004540000 0.0031600000 0.0000030000 0.0000040000 0.0018950000 45356309 96830484 509673472 3.8809249401 3.9571800232 3.8695702553 2530 1311867254.8482780457 0.1081309915 0.0924716140 0.1207853556 0.0060516295 0.0158300000 0.0005420000 0.0030030000 0.0000010000 0.0000110000 0.0011550000 45360205 96830484 509673472 3.8804469109 3.9577083588 3.8663809299 2531 1311867254.8794910908 0.1096327603 0.0924783943 0.1207853556 0.0060505297 0.0167320000 0.0005540000 0.0048480000 0.0000080000 0.0000070000 0.0014070000 45363765 96830484 509673472 3.8791282177 3.9586160183 3.8634805679 2532 1311867254.9138929844 0.1087816134 0.0924848332 0.1207853556 0.0060503698 0.0110540000 0.0004520000 0.0024160000 0.0000010000 0.0000040000 0.0010410000 45367493 96830484 509673472 3.8799824715 3.9585094452 3.8601682186 2533 1311867254.9490759373 0.1096411273 0.0924916063 0.1207853556 0.0060498019 0.0160980000 0.0005370000 0.0029630000 0.0000080000 0.0000080000 0.0020840000 45371277 96830484 509673472 3.8788092136 3.9588570595 3.8571181297 2534 1311867254.9819579124 0.1102617532 0.0924986190 0.1207853556 0.0060491872 0.0116810000 0.0004700000 0.0031480000 0.0000010000 0.0000040000 0.0010310000 45375005 96830484 509673472 3.8786084652 3.9606001377 3.8545615673 2535 1311867255.0154359341 0.1101266518 0.0925055729 0.1207853556 0.0060504011 0.0132060000 0.0004470000 0.0045970000 0.0000030000 0.0000030000 0.0013130000 45378677 96830484 509673472 3.8789024353 3.9603095055 3.8518598080 2536 1311867255.0494379997 0.1112549156 0.0925129661 0.1207853556 0.0060495783 0.0172440000 0.0005400000 0.0048680000 0.0000010000 0.0000080000 0.0011560000 45382405 96830484 509673472 3.8777332306 3.9604179859 3.8491735458 2537 1311867255.0822079182 0.1129412204 0.0925210183 0.1207853556 0.0060485795 0.0152660000 0.0004590000 0.0052120000 0.0000050000 0.0000040000 0.0019190000 45386077 96830484 509673472 3.8756852150 3.9619376659 3.8468523026 2538 1311867255.1176838875 0.1126035899 0.0925289310 0.1207853556 0.0060475777 0.0123580000 0.0004960000 0.0031170000 0.0000010000 0.0000040000 0.0010350000 45389749 96830484 509673472 3.8770039082 3.9623405933 3.8444125652 2539 1311867255.1510150433 0.1121479869 0.0925366581 0.1207853556 0.0060479169 0.0112760000 0.0004370000 0.0023810000 0.0000040000 0.0000040000 0.0013170000 45393421 96830484 509673472 3.8772683144 3.9614932537 3.8416087627 2540 1311867255.1838800907 0.1130937338 0.0925447514 0.1207853556 0.0060475175 0.0112570000 0.0004420000 0.0027470000 0.0000000000 0.0000030000 0.0010320000 45396981 96830484 509673472 3.8764603138 3.9628045559 3.8391168118 2541 1311867255.2169129848 0.1132695898 0.0925529076 0.1207853556 0.0060478627 0.0135090000 0.0004360000 0.0042210000 0.0000040000 0.0000040000 0.0019310000 45400653 96830484 509673472 3.8768763542 3.9654812813 3.8368480206 2542 1311867255.2459371090 0.1144238710 0.0925615115 0.1207853556 0.0060472144 0.0179700000 0.0005400000 0.0048850000 0.0000010000 0.0000120000 0.0011850000 45404269 96830484 509673472 3.8751142025 3.9653897285 3.8342533112 2543 1311867255.2793660164 0.1145228371 0.0925701474 0.1207853556 0.0060556774 0.0135090000 0.0004510000 0.0046030000 0.0000040000 0.0000040000 0.0013380000 45407941 96830484 509673472 3.8748195171 3.9649372101 3.8317048550 2544 1311867255.3138630390 0.1137306243 0.0925784652 0.1207853556 0.0060548243 0.0119020000 0.0004410000 0.0031040000 0.0000010000 0.0000040000 0.0010400000 45411669 96830484 509673472 3.8763990402 3.9657430649 3.8288660049 2545 1311867255.3468410969 0.1142288297 0.0925869723 0.1207853556 0.0060543108 0.0140160000 0.0004470000 0.0045700000 0.0000040000 0.0000040000 0.0019390000 45415397 96830484 509673472 3.8761358261 3.9650967121 3.8260905743 2546 1311867255.3794751167 0.1145387441 0.0925955943 0.1207853556 0.0060531787 0.0130730000 0.0004330000 0.0045750000 0.0000000000 0.0000040000 0.0010430000 45419069 96830484 509673472 3.8761329651 3.9649100304 3.8231351376 2547 1311867255.4137639999 0.1157176569 0.0926046725 0.1207853556 0.0060561427 0.0162140000 0.0005370000 0.0036800000 0.0000080000 0.0000070000 0.0014620000 45422797 96830484 509673472 3.8752996922 3.9656944275 3.8201522827 2548 1311867255.4455530643 0.1157115474 0.0926137411 0.1207853556 0.0060551649 0.0166380000 0.0005540000 0.0037160000 0.0000010000 0.0000100000 0.0011670000 45426469 96830484 509673472 3.8755714893 3.9667415619 3.8170986176 2549 1311867255.4794819355 0.1168573275 0.0926232521 0.1207853556 0.0060553601 0.0126170000 0.0004520000 0.0027630000 0.0000040000 0.0000040000 0.0019600000 45430197 96830484 509673472 3.8751986027 3.9666311741 3.8143601418 2550 1311867255.5156099796 0.1186004058 0.0926334392 0.1207853556 0.0060571255 0.0114680000 0.0004370000 0.0027380000 0.0000010000 0.0000040000 0.0010460000 45433981 96830484 509673472 3.8745865822 3.9678382874 3.8117582798 2551 1311867255.5457780361 0.1175734103 0.0926432158 0.1207853556 0.0060593870 0.0133750000 0.0004400000 0.0045670000 0.0000040000 0.0000040000 0.0013350000 45437597 96830484 509673472 3.8756802082 3.9678895473 3.8088946342 2552 1311867255.5794420242 0.1182729825 0.0926532588 0.1207853556 0.0060582043 0.0154990000 0.0005490000 0.0032850000 0.0000010000 0.0000080000 0.0011810000 45441269 96830484 509673472 3.8759303093 3.9672741890 3.8059787750 2553 1311867255.6153330803 0.1179848388 0.0926631811 0.1207853556 0.0060584104 0.0133640000 0.0004570000 0.0038480000 0.0000040000 0.0000040000 0.0019510000 45445053 96830484 509673472 3.8765432835 3.9675962925 3.8030722141 2554 1311867255.6456480026 0.1188866943 0.0926734487 0.1207853556 0.0060576716 0.0130180000 0.0004310000 0.0045530000 0.0000000000 0.0000040000 0.0010430000 45448725 96830484 509673472 3.8764190674 3.9700472355 3.8007926941 2555 1311867255.6801021099 0.1186954454 0.0926836334 0.1207853556 0.0060568768 0.0133880000 0.0004380000 0.0045640000 0.0000030000 0.0000040000 0.0013260000 45452453 96830484 509673472 3.8775222301 3.9698560238 3.7982625961 2556 1311867255.7182919979 0.1205768883 0.0926945463 0.1207853556 0.0060584207 0.0173820000 0.0005520000 0.0048310000 0.0000000000 0.0000100000 0.0011840000 45456293 96830484 509673472 3.8747832775 3.9677796364 3.7949450016 2557 1311867255.7457749844 0.1213855371 0.0927057669 0.1213855371 0.0060582893 0.0158500000 0.0004900000 0.0032380000 0.0000080000 0.0000070000 0.0020390000 45459853 96830484 509673472 3.8741586208 3.9693138599 3.7924320698 2558 1311867255.7810928822 0.1196703613 0.0927163081 0.1213855371 0.0060618340 0.0133700000 0.0004520000 0.0045920000 0.0000010000 0.0000050000 0.0010580000 45463581 96830484 509673472 3.8779373169 3.9719350338 3.7898170948 2559 1311867255.8176100254 0.1208866388 0.0927273165 0.1213855371 0.0060657972 0.0124600000 0.0004440000 0.0034680000 0.0000040000 0.0000040000 0.0013510000 45467365 96830484 509673472 3.8761942387 3.9701085091 3.7868771553 2560 1311867255.8457250595 0.1206235513 0.0927382135 0.1213855371 0.0060652786 0.0118070000 0.0004480000 0.0031020000 0.0000010000 0.0000040000 0.0010660000 45470925 96830484 509673472 3.8761792183 3.9698090553 3.7839756012 2561 1311867255.8793790340 0.1208048165 0.0927491727 0.1213855371 0.0060642452 0.0141650000 0.0004330000 0.0045860000 0.0000040000 0.0000040000 0.0019510000 45474653 96830484 509673472 3.8760516644 3.9714579582 3.7810983658 2562 1311867255.9140310287 0.1205810532 0.0927600360 0.1213855371 0.0060631380 0.0131350000 0.0004440000 0.0045830000 0.0000010000 0.0000040000 0.0010520000 45478437 96830484 509673472 3.8762547970 3.9708557129 3.7782347202 2563 1311867255.9459080696 0.1198865026 0.0927706199 0.1213855371 0.0060625364 0.0132230000 0.0004610000 0.0045850000 0.0000040000 0.0000040000 0.0013450000 45482109 96830484 509673472 3.8760817051 3.9686722755 3.7748901844 2564 1311867255.9794859886 0.1202706024 0.0927813453 0.1213855371 0.0060614846 0.0110460000 0.0004370000 0.0023590000 0.0000010000 0.0000040000 0.0010570000 45485781 96830484 509673472 3.8756065369 3.9685969353 3.7718436718 2565 1311867256.0177969933 0.1194223687 0.0927917317 0.1213855371 0.0060603646 0.0166910000 0.0005400000 0.0029660000 0.0000100000 0.0000100000 0.0021480000 45489677 96830484 509673472 3.8763375282 3.9691989422 3.7689812183 2566 1311867256.0460140705 0.1207825691 0.0928026400 0.1213855371 0.0060595245 0.0119500000 0.0004620000 0.0027650000 0.0000000000 0.0000050000 0.0010730000 45493237 96830484 509673472 3.8735661507 3.9682774544 3.7658772469 2567 1311867256.0856881142 0.1186337322 0.0928127028 0.1213855371 0.0060646253 0.0172270000 0.0005410000 0.0044550000 0.0000080000 0.0000070000 0.0014870000 45497077 96830484 509673472 3.8758361340 3.9680826664 3.7628414631 2568 1311867256.1167299747 0.1189896762 0.0928228963 0.1213855371 0.0060651603 0.0128750000 0.0004370000 0.0042030000 0.0000010000 0.0000050000 0.0010640000 45500749 96830484 509673472 3.8755018711 3.9685742855 3.7601156235 2569 1311867256.1452269554 0.1183966026 0.0928328511 0.1213855371 0.0060651783 0.0140940000 0.0004410000 0.0045670000 0.0000030000 0.0000030000 0.0019750000 45504309 96830484 509673472 3.8756594658 3.9692361355 3.7573533058 2570 1311867256.1795060635 0.1193698272 0.0928431767 0.1213855371 0.0060656991 0.0131150000 0.0004420000 0.0045790000 0.0000010000 0.0000040000 0.0010660000 45508093 96830484 509673472 3.8736138344 3.9679269791 3.7541217804 2571 1311867256.2177491188 0.1186757833 0.0928532244 0.1213855371 0.0060661472 0.0116690000 0.0004430000 0.0027400000 0.0000040000 0.0000040000 0.0013520000 45511933 96830484 509673472 3.8736772537 3.9667391777 3.7512691021 2572 1311867256.2454690933 0.1185439751 0.0928632130 0.1213855371 0.0060658896 0.0122060000 0.0004350000 0.0034410000 0.0000010000 0.0000040000 0.0010680000 45515437 96830484 509673472 3.8732881546 3.9663643837 3.7483160496 2573 1311867256.2847039700 0.1177445054 0.0928728832 0.1213855371 0.0060658123 0.0166200000 0.0005370000 0.0029260000 0.0000080000 0.0000070000 0.0022050000 45519333 96830484 509673472 3.8740432262 3.9666171074 3.7449736595 2574 1311867256.3143420219 0.1169686317 0.0928822444 0.1213855371 0.0060663116 0.0134400000 0.0004420000 0.0045620000 0.0000000000 0.0000050000 0.0010840000 45522893 96830484 509673472 3.8730862141 3.9637055397 3.7410485744 2575 1311867256.3471789360 0.1167271957 0.0928915046 0.1213855371 0.0060659939 0.0116180000 0.0004400000 0.0027010000 0.0000040000 0.0000040000 0.0013690000 45526621 96830484 509673472 3.8727624416 3.9642946720 3.7374854088 2576 1311867256.3848650455 0.1163608357 0.0929006153 0.1213855371 0.0060649274 0.0131120000 0.0004370000 0.0045040000 0.0000000000 0.0000030000 0.0010810000 45530405 96830484 509673472 3.8727650642 3.9632654190 3.7338230610 2577 1311867256.4158649445 0.1160368323 0.0929095933 0.1213855371 0.0060639583 0.0145420000 0.0004320000 0.0041270000 0.0000030000 0.0000030000 0.0020120000 45534021 96830484 509673472 3.8720066547 3.9618015289 3.7299575806 2578 1311867256.4452838898 0.1159575656 0.0929185336 0.1213855371 0.0060643767 0.0117860000 0.0004850000 0.0026960000 0.0000000000 0.0000030000 0.0012730000 45537637 96830484 509673472 3.8716864586 3.9612083435 3.7264578342 2579 1311867256.4844601154 0.1150802299 0.0929271267 0.1213855371 0.0060664856 0.0122150000 0.0004370000 0.0030700000 0.0000040000 0.0000040000 0.0013940000 45541477 96830484 509673472 3.8719558716 3.9624602795 3.7227187157 2580 1311867256.5135829449 0.1151951924 0.0929357577 0.1213855371 0.0060663044 0.0132970000 0.0004350000 0.0045310000 0.0000000000 0.0000040000 0.0010760000 45545149 96830484 509673472 3.8699996471 3.9601597786 3.7187364101 2581 1311867256.5478789806 0.1138672084 0.0929438675 0.1213855371 0.0060850575 0.0126520000 0.0004540000 0.0027000000 0.0000030000 0.0000030000 0.0020270000 45548877 96830484 509673472 3.8698465824 3.9578168392 3.7149178982 2582 1311867256.5836489201 0.1130491942 0.0929516543 0.1213855371 0.0060933312 0.0132470000 0.0004300000 0.0044790000 0.0000000000 0.0000040000 0.0010820000 45552717 96830484 509673472 3.8717091084 3.9579441547 3.7115492821 2583 1311867256.6160368919 0.1124758497 0.0929592130 0.1213855371 0.0060921870 0.0174740000 0.0005280000 0.0044060000 0.0000080000 0.0000080000 0.0014970000 45556333 96830484 509673472 3.8724613190 3.9579875469 3.7083446980 2584 1311867256.6452310085 0.1149113402 0.0929677084 0.1213855371 0.0060914780 0.0125930000 0.0004420000 0.0034370000 0.0000000000 0.0000160000 0.0010900000 45559949 96830484 509673472 3.8686771393 3.9566934109 3.7048974037 2585 1311867256.6832759380 0.1150933951 0.0929762677 0.1213855371 0.0060905674 0.0143210000 0.0004320000 0.0044890000 0.0000040000 0.0000040000 0.0020260000 45563845 96830484 509673472 3.8688948154 3.9567549229 3.7014837265 2586 1311867256.7140300274 0.1153426766 0.0929849167 0.1213855371 0.0060909760 0.0117620000 0.0004300000 0.0026980000 0.0000000000 0.0000040000 0.0010830000 45567405 96830484 509673472 3.8690867424 3.9583053589 3.6988880634 2587 1311867256.7463369370 0.1145176440 0.0929932401 0.1213855371 0.0060903441 0.0135380000 0.0004280000 0.0045060000 0.0000030000 0.0000030000 0.0013750000 45571077 96830484 509673472 3.8698503971 3.9576699734 3.6958568096 2588 1311867256.7827401161 0.1151621565 0.0930018062 0.1213855371 0.0060894744 0.0119250000 0.0004290000 0.0030470000 0.0000010000 0.0000040000 0.0010890000 45574917 96830484 509673472 3.8700339794 3.9577023983 3.6930809021 2589 1311867256.8140430450 0.1142465696 0.0930100120 0.1213855371 0.0060892632 0.0163870000 0.0004820000 0.0028350000 0.0000080000 0.0000070000 0.0021910000 45578533 96830484 509673472 3.8722202778 3.9587397575 3.6903486252 2590 1311867256.8477399349 0.1158896908 0.0930188458 0.1213855371 0.0060893963 0.0135760000 0.0004430000 0.0045260000 0.0000000000 0.0000050000 0.0010880000 45582261 96830484 509673472 3.8700067997 3.9544060230 3.6871476173 2591 1311867256.8838980198 0.1154866815 0.0930275173 0.1213855371 0.0060897929 0.0136330000 0.0004280000 0.0045290000 0.0000030000 0.0000030000 0.0013810000 45585989 96830484 509673472 3.8699555397 3.9527888298 3.6836144924 2592 1311867256.9148108959 0.1138936058 0.0930355675 0.1213855371 0.0060891725 0.0131980000 0.0004110000 0.0044640000 0.0000000000 0.0000050000 0.0010910000 45589661 96830484 509673472 3.8723213673 3.9525759220 3.6800971031 2593 1311867256.9465379715 0.1149840429 0.0930440320 0.1213855371 0.0060881952 0.0134750000 0.0004130000 0.0037410000 0.0000040000 0.0000040000 0.0020500000 45593333 96830484 509673472 3.8716433048 3.9526953697 3.6764113903 2594 1311867256.9814610481 0.1157020107 0.0930527668 0.1213855371 0.0060873176 0.0138990000 0.0004230000 0.0044710000 0.0000010000 0.0000050000 0.0010960000 45597061 96830484 509673472 3.8709166050 3.9516620636 3.6725869179 2595 1311867257.0129959583 0.1152899787 0.0930613360 0.1213855371 0.0060871216 0.0128580000 0.0004140000 0.0030420000 0.0000040000 0.0000040000 0.0013870000 45600789 96830484 509673472 3.8715138435 3.9501776695 3.6688458920 2596 1311867257.0451910496 0.1174379066 0.0930707261 0.1213855371 0.0060891966 0.0121400000 0.0004600000 0.0023230000 0.0000000000 0.0000040000 0.0010870000 45604405 96830484 509673472 3.8695268631 3.9509360790 3.6658182144 2597 1311867257.0841369629 0.1162979305 0.0930796699 0.1213855371 0.0060883812 0.0134810000 0.0004610000 0.0030280000 0.0000040000 0.0000040000 0.0020410000 45608245 96830484 509673472 3.8723537922 3.9539060593 3.6626415253 2598 1311867257.1134428978 0.1170416623 0.0930888932 0.1213855371 0.0060873278 0.0138100000 0.0004170000 0.0044720000 0.0000000000 0.0000040000 0.0010940000 45611917 96830484 509673472 3.8713948727 3.9530711174 3.6600117683 2599 1311867257.1474308968 0.1170424074 0.0930981096 0.1213855371 0.0060863187 0.0123140000 0.0004170000 0.0026970000 0.0000040000 0.0000040000 0.0014030000 45615645 96830484 509673472 3.8713905811 3.9532330036 3.6568031311 2600 1311867257.1821229458 0.1151048020 0.0931065737 0.1213855371 0.0060858082 0.0138530000 0.0004180000 0.0044830000 0.0000000000 0.0000040000 0.0010920000 45619373 96830484 509673472 3.8738002777 3.9547233582 3.6533625126 2601 1311867257.2147839069 0.1140511334 0.0931146262 0.1213855371 0.0060892433 0.0148100000 0.0004130000 0.0044780000 0.0000050000 0.0000040000 0.0020530000 45623045 96830484 509673472 3.8744537830 3.9542465210 3.6500825882 2602 1311867257.2457039356 0.1156069040 0.0931232705 0.1213855371 0.0060907623 0.0138130000 0.0004180000 0.0044670000 0.0000000000 0.0000040000 0.0011010000 45626661 96830484 509673472 3.8724536896 3.9529125690 3.6469089985 2603 1311867257.2824490070 0.1164035723 0.0931322141 0.1213855371 0.0060897269 0.0123130000 0.0004170000 0.0026700000 0.0000050000 0.0000040000 0.0013940000 45630501 96830484 509673472 3.8720903397 3.9546771049 3.6440978050 2604 1311867257.3133430481 0.1169447601 0.0931413587 0.1213855371 0.0060888662 0.0120620000 0.0004180000 0.0026950000 0.0000000000 0.0000040000 0.0010960000 45634117 96830484 509673472 3.8724815845 3.9570596218 3.6413190365 2605 1311867257.3452849388 0.1177854314 0.0931508190 0.1213855371 0.0060878305 0.0129150000 0.0004260000 0.0026980000 0.0000040000 0.0000040000 0.0020700000 45637733 96830484 509673472 3.8710377216 3.9557735920 3.6381757259 2606 1311867257.3839631081 0.1199519336 0.0931611034 0.1213855371 0.0060871393 0.0118890000 0.0004310000 0.0030280000 0.0000000000 0.0000030000 0.0011030000 45641573 96830484 509673472 3.8695847988 3.9579665661 3.6353709698 2607 1311867257.4198129177 0.1221532300 0.0931722243 0.1221532300 0.0060897490 0.0126210000 0.0004260000 0.0034010000 0.0000040000 0.0000040000 0.0014050000 45645357 96830484 509673472 3.8690481186 3.9594824314 3.6332139969 2608 1311867257.4458611012 0.1226801649 0.0931835387 0.1226801649 0.0060889047 0.0115780000 0.0004190000 0.0026970000 0.0000000000 0.0000030000 0.0011000000 45648861 96830484 509673472 3.8688507080 3.9607722759 3.6310739517 2609 1311867257.4851269722 0.1236197650 0.0931952045 0.1236197650 0.0060888204 0.0125860000 0.0004160000 0.0026870000 0.0000030000 0.0000030000 0.0020800000 45652757 96830484 509673472 3.8682100773 3.9599559307 3.6283636093 2610 1311867257.5166249275 0.1257258654 0.0932076684 0.1257258654 0.0060892296 0.0127090000 0.0004130000 0.0037630000 0.0000000000 0.0000040000 0.0011450000 45656429 96830484 509673472 3.8673272133 3.9634208679 3.6262483597 2611 1311867257.5537879467 0.1250501275 0.0932198639 0.1257258654 0.0060882692 0.0122690000 0.0004260000 0.0030530000 0.0000040000 0.0000040000 0.0014520000 45660213 96830484 509673472 3.8702263832 3.9644496441 3.6243040562 2612 1311867257.5836200714 0.1222558245 0.0932309802 0.1257258654 0.0061002623 0.0134740000 0.0004210000 0.0044730000 0.0000000000 0.0000040000 0.0011490000 45663829 96830484 509673472 3.8740613461 3.9639735222 3.6219260693 2613 1311867257.6154460907 0.1240037456 0.0932427570 0.1257258654 0.0061055382 0.0142010000 0.0004150000 0.0044520000 0.0000040000 0.0000050000 0.0021740000 45667445 96830484 509673472 3.8727765083 3.9658355713 3.6194722652 2614 1311867257.6519720554 0.1216467544 0.0932536231 0.1257258654 0.0061047332 0.0115480000 0.0004210000 0.0026930000 0.0000000000 0.0000050000 0.0011520000 45671285 96830484 509673472 3.8769838810 3.9668965340 3.6176745892 2615 1311867257.6842958927 0.1264548153 0.0932663196 0.1264548153 0.0061055122 0.0136330000 0.0004250000 0.0044880000 0.0000040000 0.0000040000 0.0014470000 45674957 96830484 509673472 3.8717992306 3.9691371918 3.6150681973 2616 1311867257.7187778950 0.1259656996 0.0932788193 0.1264548153 0.0061043970 0.0133560000 0.0004150000 0.0044750000 0.0000000000 0.0000030000 0.0011400000 45678741 96830484 509673472 3.8733839989 3.9691505432 3.6130414009 2617 1311867257.7527809143 0.1241028458 0.0932905977 0.1264548153 0.0061059633 0.0123020000 0.0004210000 0.0023220000 0.0000040000 0.0000030000 0.0021300000 45682469 96830484 509673472 3.8765132427 3.9672114849 3.6115362644 2618 1311867257.7838430405 0.1212039739 0.0933012598 0.1264548153 0.0061055784 0.0177610000 0.0005210000 0.0048200000 0.0000010000 0.0000080000 0.0012740000 45686141 96830484 509673472 3.8815941811 3.9674251080 3.6102106571 2619 1311867257.8181409836 0.1205916628 0.0933116800 0.1264548153 0.0061051241 0.0130800000 0.0004430000 0.0034390000 0.0000040000 0.0000040000 0.0014560000 45689869 96830484 509673472 3.8830771446 3.9673647881 3.6084499359 2620 1311867257.8530700207 0.1227452606 0.0933229142 0.1264548153 0.0061135873 0.0123600000 0.0004230000 0.0034140000 0.0000010000 0.0000040000 0.0011390000 45693597 96830484 509673472 3.8820211887 3.9690287113 3.6063830853 2621 1311867257.8854579926 0.1222143322 0.0933339372 0.1264548153 0.0061151027 0.0129740000 0.0004150000 0.0030510000 0.0000040000 0.0000040000 0.0021410000 45697213 96830484 509673472 3.8833427429 3.9689452648 3.6045694351 2622 1311867257.9152529240 0.1210729778 0.0933445166 0.1264548153 0.0061157138 0.0131940000 0.0004260000 0.0045050000 0.0000000000 0.0000050000 0.0011400000 45700829 96830484 509673472 3.8857712746 3.9680995941 3.6034572124 2623 1311867257.9559030533 0.1202690974 0.0933547814 0.1264548153 0.0061152690 0.0116010000 0.0004170000 0.0023320000 0.0000030000 0.0000040000 0.0014500000 45704781 96830484 509673472 3.8879396915 3.9676990509 3.6021955013 2624 1311867257.9850780964 0.1186019629 0.0933644030 0.1264548153 0.0061147292 0.0115870000 0.0004240000 0.0027060000 0.0000010000 0.0000040000 0.0011410000 45708341 96830484 509673472 3.8903822899 3.9663169384 3.6010129452 2625 1311867258.0135710239 0.1199681684 0.0933745378 0.1264548153 0.0061141633 0.0164130000 0.0005200000 0.0028950000 0.0000080000 0.0000080000 0.0023500000 45711957 96830484 509673472 3.8886349201 3.9659395218 3.5989110470 2626 1311867258.0526609421 0.1198823974 0.0933846322 0.1264548153 0.0061136112 0.0176880000 0.0005180000 0.0048020000 0.0000000000 0.0000090000 0.0013040000 45715797 96830484 509673472 3.8896267414 3.9646358490 3.5975015163 2627 1311867258.0836610794 0.1213905960 0.0933952930 0.1264548153 0.0061143412 0.0123790000 0.0004290000 0.0030560000 0.0000040000 0.0000040000 0.0014420000 45719413 96830484 509673472 3.8879632950 3.9642152786 3.5961256027 2628 1311867258.1137859821 0.1199418679 0.0934053944 0.1264548153 0.0061139578 0.0134270000 0.0004210000 0.0044790000 0.0000010000 0.0000040000 0.0011580000 45723085 96830484 509673472 3.8899166584 3.9631416798 3.5946297646 2629 1311867258.1501069069 0.1221105829 0.0934163131 0.1264548153 0.0061158768 0.0130210000 0.0004160000 0.0030280000 0.0000040000 0.0000040000 0.0021640000 45726813 96830484 509673472 3.8876893520 3.9643363953 3.5923254490 2630 1311867258.1848480701 0.1217857525 0.0934271000 0.1264548153 0.0061147804 0.0121140000 0.0004160000 0.0030330000 0.0000000000 0.0000030000 0.0011500000 45730541 96830484 509673472 3.8891758919 3.9631235600 3.5915279388 2631 1311867258.2162730694 0.1206595376 0.0934374506 0.1264548153 0.0061138823 0.0119030000 0.0004290000 0.0026630000 0.0000030000 0.0000040000 0.0014480000 45734269 96830484 509673472 3.8909299374 3.9623022079 3.5901377201 2632 1311867258.2524979115 0.1207138151 0.0934478139 0.1264548153 0.0061143271 0.0133340000 0.0004300000 0.0044790000 0.0000010000 0.0000040000 0.0011500000 45738053 96830484 509673472 3.8913037777 3.9622044563 3.5889501572 2633 1311867258.2857830524 0.1206164509 0.0934581324 0.1264548153 0.0061135408 0.0161200000 0.0004740000 0.0031750000 0.0000080000 0.0000090000 0.0022690000 45741725 96830484 509673472 3.8913958073 3.9612505436 3.5878193378 2634 1311867258.3132910728 0.1191825196 0.0934678987 0.1264548153 0.0061129567 0.0134860000 0.0004190000 0.0044850000 0.0000000000 0.0000030000 0.0011530000 45745341 96830484 509673472 3.8930552006 3.9586415291 3.5870389938 2635 1311867258.3510708809 0.1192588657 0.0934776866 0.1264548153 0.0061141501 0.0124090000 0.0004180000 0.0030290000 0.0000030000 0.0000030000 0.0014390000 45749125 96830484 509673472 3.8942203522 3.9592378139 3.5863246918 2636 1311867258.3812119961 0.1193958595 0.0934875189 0.1264548153 0.0061131094 0.0122670000 0.0004130000 0.0033780000 0.0000000000 0.0000040000 0.0011520000 45752685 96830484 509673472 3.8942444324 3.9597408772 3.5855958462 2637 1311867258.4142711163 0.1191890612 0.0934972655 0.1264548153 0.0061120298 0.0151700000 0.0004640000 0.0045120000 0.0000040000 0.0000040000 0.0021910000 45756357 96830484 509673472 3.8943150043 3.9594578743 3.5845053196 2638 1311867258.4507009983 0.1214004233 0.0935078428 0.1264548153 0.0061127498 0.0133530000 0.0004600000 0.0044740000 0.0000010000 0.0000040000 0.0011560000 45760197 96830484 509673472 3.8916680813 3.9605040550 3.5834083557 2639 1311867258.4826059341 0.1211302429 0.0935183098 0.1264548153 0.0061121488 0.0172720000 0.0005050000 0.0047030000 0.0000080000 0.0000080000 0.0015710000 45763925 96830484 509673472 3.8915793896 3.9588785172 3.5825514793 2640 1311867258.5139899254 0.1220344305 0.0935291114 0.1264548153 0.0061119463 0.0135940000 0.0004140000 0.0044640000 0.0000000000 0.0000040000 0.0011540000 45767541 96830484 509673472 3.8907625675 3.9570696354 3.5815954208 2641 1311867258.5500509739 0.1218305826 0.0935398276 0.1264548153 0.0061220183 0.0145590000 0.0004130000 0.0044610000 0.0000040000 0.0000040000 0.0021630000 45771325 96830484 509673472 3.8903956413 3.9559407234 3.5802264214 2642 1311867258.5836040974 0.1225535497 0.0935508093 0.1264548153 0.0061281876 0.0132510000 0.0004130000 0.0043340000 0.0000000000 0.0000030000 0.0011490000 45774997 96830484 509673472 3.8906118870 3.9559221268 3.5787138939 2643 1311867258.6141679287 0.1232458055 0.0935620447 0.1264548153 0.0061283813 0.0136150000 0.0004080000 0.0044370000 0.0000040000 0.0000040000 0.0014560000 45778613 96830484 509673472 3.8898417950 3.9548823833 3.5770545006 2644 1311867258.6506860256 0.1244497299 0.0935737268 0.1264548153 0.0061282685 0.0134420000 0.0004120000 0.0044390000 0.0000000000 0.0000040000 0.0011640000 45782397 96830484 509673472 3.8896477222 3.9555714130 3.5752024651 2645 1311867258.6856470108 0.1242730841 0.0935853334 0.1264548153 0.0061281959 0.0130960000 0.0004140000 0.0030240000 0.0000030000 0.0000040000 0.0021850000 45786181 96830484 509673472 3.8904383183 3.9533455372 3.5733430386 2646 1311867258.7134239674 0.1241074130 0.0935968686 0.1264548153 0.0061272567 0.0135270000 0.0004180000 0.0044430000 0.0000000000 0.0000040000 0.0011610000 45789685 96830484 509673472 3.8905315399 3.9496259689 3.5712177753 2647 1311867258.7543559074 0.1260177642 0.0936091167 0.1264548153 0.0061282681 0.0178050000 0.0005130000 0.0043370000 0.0000080000 0.0000080000 0.0016070000 45793581 96830484 509673472 3.8903546333 3.9508678913 3.5690569878 2648 1311867258.7843589783 0.1251323223 0.0936210213 0.1264548153 0.0061284701 0.0168590000 0.0005050000 0.0046450000 0.0000010000 0.0000080000 0.0012840000 45797197 96830484 509673472 3.8918900490 3.9519984722 3.5675330162 2649 1311867258.8193690777 0.1241402104 0.0936325423 0.1264548153 0.0061277677 0.0131490000 0.0004340000 0.0030060000 0.0000040000 0.0000040000 0.0021980000 45800981 96830484 509673472 3.8932023048 3.9505338669 3.5655195713 2650 1311867258.8514409065 0.1265532821 0.0936449652 0.1265532821 0.0061272202 0.0169820000 0.0005020000 0.0036300000 0.0000020000 0.0000100000 0.0013220000 45804709 96830484 509673472 3.8899967670 3.9490189552 3.5633764267 2651 1311867258.8846011162 0.1254487485 0.0936569621 0.1265532821 0.0061263718 0.0126800000 0.0004250000 0.0030380000 0.0000040000 0.0000040000 0.0014970000 45808325 96830484 509673472 3.8927264214 3.9488625526 3.5620210171 2652 1311867258.9178969860 0.1250038296 0.0936687822 0.1265532821 0.0061252308 0.0115390000 0.0004040000 0.0023090000 0.0000010000 0.0000040000 0.0011600000 45812053 96830484 509673472 3.8938977718 3.9480199814 3.5600233078 2653 1311867258.9506199360 0.1256559640 0.0936808392 0.1265532821 0.0061249396 0.0144750000 0.0004100000 0.0044090000 0.0000040000 0.0000040000 0.0021980000 45815725 96830484 509673472 3.8934383392 3.9468264580 3.5580270290 2654 1311867258.9841670990 0.1262894124 0.0936931258 0.1265532821 0.0061256437 0.0120310000 0.0004090000 0.0030000000 0.0000000000 0.0000030000 0.0011770000 45819509 96830484 509673472 3.8941547871 3.9471387863 3.5561773777 2655 1311867259.0194389820 0.1262821555 0.0937054004 0.1265532821 0.0061247983 0.0124220000 0.0004160000 0.0029830000 0.0000030000 0.0000030000 0.0014780000 45823181 96830484 509673472 3.8950648308 3.9458394051 3.5536134243 2656 1311867259.0497961044 0.1265491694 0.0937177662 0.1265532821 0.0061269829 0.0132770000 0.0004130000 0.0044130000 0.0000000000 0.0000040000 0.0011640000 45826853 96830484 509673472 3.8959724903 3.9434709549 3.5515680313 2657 1311867259.0845470428 0.1266645342 0.0937301662 0.1266645342 0.0061268912 0.0141080000 0.0004620000 0.0033560000 0.0000040000 0.0000040000 0.0022090000 45830525 96830484 509673472 3.8978843689 3.9446628094 3.5491008759 2658 1311867259.1189930439 0.1273804307 0.0937428262 0.1273804307 0.0061263748 0.0138140000 0.0004590000 0.0044020000 0.0000010000 0.0000040000 0.0011790000 45834309 96830484 509673472 3.8987810612 3.9459612370 3.5468118191 2659 1311867259.1506030560 0.1285073459 0.0937559005 0.1285073459 0.0061280445 0.0125940000 0.0004060000 0.0029790000 0.0000030000 0.0000030000 0.0014900000 45837981 96830484 509673472 3.8986678123 3.9442284107 3.5447831154 2660 1311867259.1837821007 0.1276203096 0.0937686315 0.1285073459 0.0061279065 0.0133830000 0.0004150000 0.0044110000 0.0000000000 0.0000040000 0.0011780000 45841653 96830484 509673472 3.9017734528 3.9435899258 3.5429127216 2661 1311867259.2191979885 0.1267636716 0.0937810310 0.1285073459 0.0061268170 0.0144040000 0.0004100000 0.0043780000 0.0000030000 0.0000040000 0.0022140000 45845493 96830484 509673472 3.9047768116 3.9438834190 3.5407226086 2662 1311867259.2532899380 0.1256189048 0.0937929911 0.1285073459 0.0061267108 0.0115680000 0.0004090000 0.0026320000 0.0000000000 0.0000050000 0.0011930000 45849221 96830484 509673472 3.9090027809 3.9417064190 3.5382034779 2663 1311867259.2815980911 0.1261452585 0.0938051399 0.1285073459 0.0061257563 0.0165410000 0.0005000000 0.0032120000 0.0000080000 0.0000080000 0.0016270000 45852781 96830484 509673472 3.9092659950 3.9414622784 3.5359780788 2664 1311867259.3212718964 0.1275224686 0.0938177966 0.1285073459 0.0061256610 0.0179350000 0.0005030000 0.0046630000 0.0000010000 0.0000080000 0.0013240000 45856677 96830484 509673472 3.9099657536 3.9424846172 3.5333528519 2665 1311867259.3519039154 0.1251917183 0.0938295691 0.1285073459 0.0061246294 0.0146390000 0.0004230000 0.0042830000 0.0000050000 0.0000050000 0.0022200000 45860349 96830484 509673472 3.9139707088 3.9424154758 3.5300807953 2666 1311867259.3840188980 0.1270308346 0.0938420227 0.1285073459 0.0061237418 0.0133930000 0.0004050000 0.0043650000 0.0000010000 0.0000040000 0.0011730000 45863965 96830484 509673472 3.9125649929 3.9414906502 3.5266134739 2667 1311867259.4204289913 0.1291475445 0.0938552606 0.1291475445 0.0061247484 0.0135980000 0.0004020000 0.0043440000 0.0000040000 0.0000030000 0.0014770000 45867749 96830484 509673472 3.9114062786 3.9406943321 3.5237364769 2668 1311867259.4579179287 0.1289900690 0.0938684296 0.1291475445 0.0061237525 0.0119650000 0.0004020000 0.0029560000 0.0000000000 0.0000030000 0.0011680000 45871589 96830484 509673472 3.9137938023 3.9423997402 3.5207595825 2669 1311867259.4850549698 0.1291405261 0.0938816451 0.1291475445 0.0061242225 0.0145660000 0.0004020000 0.0043480000 0.0000030000 0.0000040000 0.0022100000 45875037 96830484 509673472 3.9139745235 3.9411280155 3.5180301666 2670 1311867259.5189819336 0.1273872107 0.0938941940 0.1291475445 0.0061235614 0.0121180000 0.0004050000 0.0029380000 0.0000000000 0.0000040000 0.0011770000 45878765 96830484 509673472 3.9169042110 3.9385211468 3.5151393414 2671 1311867259.5505928993 0.1287841350 0.0939072565 0.1291475445 0.0061225663 0.0123710000 0.0003950000 0.0029360000 0.0000040000 0.0000040000 0.0014510000 45882437 96830484 509673472 3.9161298275 3.9381260872 3.5117442608 2672 1311867259.5823240280 0.1277190149 0.0939199106 0.1291475445 0.0061220083 0.0171950000 0.0004970000 0.0045840000 0.0000010000 0.0000080000 0.0012740000 45886165 96830484 509673472 3.9185142517 3.9371981621 3.5089104176 2673 1311867259.6192719936 0.1272314042 0.0939323728 0.1291475445 0.0061220890 0.0185930000 0.0004940000 0.0045900000 0.0000070000 0.0000080000 0.0023450000 45889893 96830484 509673472 3.9210996628 3.9380846024 3.5055546761 2674 1311867259.6494839191 0.1274667084 0.0939449137 0.1291475445 0.0061214047 0.0117960000 0.0004040000 0.0026200000 0.0000010000 0.0000040000 0.0011500000 45893453 96830484 509673472 3.9216825962 3.9397063255 3.5024881363 2675 1311867259.6828589439 0.1280577481 0.0939576662 0.1291475445 0.0061218506 0.0125950000 0.0004000000 0.0029510000 0.0000030000 0.0000030000 0.0014540000 45897181 96830484 509673472 3.9219069481 3.9413318634 3.4992442131 2676 1311867259.7201991081 0.1280674040 0.0939704127 0.1291475445 0.0061210781 0.0166210000 0.0005100000 0.0027990000 0.0000010000 0.0000110000 0.0013350000 45901021 96830484 509673472 3.9225835800 3.9422881603 3.4959294796 2677 1311867259.7557690144 0.1262412518 0.0939824675 0.1291475445 0.0061200902 0.0146160000 0.0004080000 0.0043550000 0.0000050000 0.0000040000 0.0021740000 45904805 96830484 509673472 3.9250035286 3.9407343864 3.4934253693 2678 1311867259.7817859650 0.1292694956 0.0939956442 0.1292694956 0.0061191590 0.0175570000 0.0004940000 0.0046050000 0.0000010000 0.0000090000 0.0013320000 45908309 96830484 509673472 3.9213802814 3.9414906502 3.4910695553 2679 1311867259.8177011013 0.1276997626 0.0940082250 0.1292694956 0.0061181691 0.0124660000 0.0004040000 0.0026130000 0.0000040000 0.0000050000 0.0015090000 45912093 96830484 509673472 3.9238898754 3.9420018196 3.4885516167 2680 1311867259.8548939228 0.1266915947 0.0940204203 0.1292694956 0.0061174141 0.0159080000 0.0004930000 0.0028040000 0.0000010000 0.0000080000 0.0013130000 45915877 96830484 509673472 3.9262890816 3.9418320656 3.4867587090 2681 1311867259.8818409443 0.1285826713 0.0940333119 0.1292694956 0.0061168367 0.0146120000 0.0004100000 0.0040210000 0.0000040000 0.0000040000 0.0022370000 45919437 96830484 509673472 3.9236195087 3.9410080910 3.4842553139 2682 1311867259.9219179153 0.1272791922 0.0940457078 0.1292694956 0.0061164508 0.0124770000 0.0004050000 0.0029560000 0.0000000000 0.0000030000 0.0011820000 45923333 96830484 509673472 3.9262542725 3.9426350594 3.4819033146 2683 1311867259.9520130157 0.1270004809 0.0940579906 0.1292694956 0.0061153964 0.0172780000 0.0004950000 0.0045840000 0.0000080000 0.0000070000 0.0016190000 45926949 96830484 509673472 3.9271817207 3.9446496964 3.4792220592 2684 1311867259.9923639297 0.1276211590 0.0940704955 0.1292694956 0.0061152595 0.0137420000 0.0004030000 0.0043830000 0.0000010000 0.0000040000 0.0011880000 45930845 96830484 509673472 3.9270036221 3.9432301521 3.4769165516 2685 1311867260.0219469070 0.1289265603 0.0940834773 0.1292694956 0.0061149663 0.0129480000 0.0004050000 0.0026040000 0.0000040000 0.0000040000 0.0022390000 45934405 96830484 509673472 3.9264936447 3.9437780380 3.4753561020 2686 1311867260.0493209362 0.1254436374 0.0940951527 0.1292694956 0.0061148350 0.0136940000 0.0004020000 0.0043800000 0.0000000000 0.0000040000 0.0011840000 45937909 96830484 509673472 3.9316983223 3.9453759193 3.4730217457 2687 1311867260.0888080597 0.1262534857 0.0941071208 0.1292694956 0.0061144058 0.0129310000 0.0003980000 0.0033230000 0.0000040000 0.0000040000 0.0015020000 45941805 96830484 509673472 3.9313454628 3.9451572895 3.4703536034 2688 1311867260.1210498810 0.1269397438 0.0941193353 0.1292694956 0.0061168944 0.0118990000 0.0003960000 0.0026220000 0.0000000000 0.0000040000 0.0011850000 45945477 96830484 509673472 3.9323115349 3.9455547333 3.4677696228 2689 1311867260.1513869762 0.1248356998 0.0941307583 0.1292694956 0.0061191975 0.0145850000 0.0004030000 0.0043600000 0.0000040000 0.0000040000 0.0022290000 45949093 96830484 509673472 3.9354546070 3.9460611343 3.4652059078 2690 1311867260.1908860207 0.1251050830 0.0941422729 0.1292694956 0.0061181756 0.0137360000 0.0004060000 0.0043530000 0.0000000000 0.0000040000 0.0011810000 45952933 96830484 509673472 3.9369935989 3.9466054440 3.4622952938 2691 1311867260.2204439640 0.1276397556 0.0941547209 0.1292694956 0.0061175353 0.0163870000 0.0005100000 0.0031580000 0.0000080000 0.0000080000 0.0016290000 45956549 96830484 509673472 3.9342563152 3.9479978085 3.4588444233 2692 1311867260.2496669292 0.1281371266 0.0941673444 0.1292694956 0.0061164879 0.0172830000 0.0005050000 0.0035500000 0.0000010000 0.0000100000 0.0013390000 45960221 96830484 509673472 3.9340136051 3.9469084740 3.4557819366 2693 1311867260.2869880199 0.1296116859 0.0941805060 0.1296116859 0.0061165709 0.0133830000 0.0004160000 0.0029850000 0.0000040000 0.0000050000 0.0022430000 45964005 96830484 509673472 3.9343392849 3.9496128559 3.4528610706 2694 1311867260.3195590973 0.1289500147 0.0941934123 0.1296116859 0.0061158016 0.0167330000 0.0004520000 0.0045500000 0.0000010000 0.0000070000 0.0012470000 45967677 96830484 509673472 3.9358086586 3.9510819912 3.4495749474 2695 1311867260.3505260944 0.1314949393 0.0942072533 0.1314949393 0.0061157556 0.0128810000 0.0004040000 0.0029670000 0.0000040000 0.0000050000 0.0015030000 45971349 96830484 509673472 3.9329786301 3.9508371353 3.4464612007 2696 1311867260.3868899345 0.1344416142 0.0942221770 0.1344416142 0.0061188809 0.0126120000 0.0004470000 0.0026210000 0.0000000000 0.0000040000 0.0011870000 45975133 96830484 509673472 3.9310803413 3.9537804127 3.4437527657 2697 1311867260.4211299419 0.1339622587 0.0942369120 0.1344416142 0.0061180909 0.0148540000 0.0004370000 0.0043600000 0.0000040000 0.0000040000 0.0022350000 45978805 96830484 509673472 3.9328160286 3.9571170807 3.4406881332 2698 1311867260.4521770477 0.1327410042 0.0942511833 0.1344416142 0.0061172790 0.0172230000 0.0004970000 0.0035660000 0.0000010000 0.0000110000 0.0013420000 45982421 96830484 509673472 3.9346187115 3.9569385052 3.4382643700 2699 1311867260.4867470264 0.1348577142 0.0942662283 0.1348577142 0.0061183782 0.0128930000 0.0004110000 0.0029910000 0.0000040000 0.0000040000 0.0015190000 45986149 96830484 509673472 3.9326817989 3.9580874443 3.4352867603 2700 1311867260.5192930698 0.1339382827 0.0942809217 0.1348577142 0.0061200996 0.0158870000 0.0004960000 0.0028220000 0.0000010000 0.0000090000 0.0013390000 45989709 96830484 509673472 3.9353675842 3.9610371590 3.4324796200 2701 1311867260.5527870655 0.1350100487 0.0942960010 0.1350100487 0.0061197392 0.0133840000 0.0004100000 0.0030010000 0.0000040000 0.0000040000 0.0022690000 45993493 96830484 509673472 3.9348616600 3.9613230228 3.4302229881 2702 1311867260.5880448818 0.1371709853 0.0943118688 0.1371709853 0.0061197061 0.0122690000 0.0004020000 0.0029840000 0.0000010000 0.0000050000 0.0011860000 45997277 96830484 509673472 3.9327831268 3.9612669945 3.4269478321 2703 1311867260.6196188927 0.1363875717 0.0943274351 0.1371709853 0.0061191611 0.0133560000 0.0004070000 0.0036880000 0.0000040000 0.0000040000 0.0014910000 46000949 96830484 509673472 3.9342231750 3.9609720707 3.4239532948 2704 1311867260.6493411064 0.1343156844 0.0943422237 0.1371709853 0.0061183143 0.0164410000 0.0004980000 0.0028700000 0.0000010000 0.0000090000 0.0013320000 46004509 96830484 509673472 3.9373118877 3.9598481655 3.4215610027 2705 1311867260.6865339279 0.1343856156 0.0943570272 0.1371709853 0.0061182724 0.0131850000 0.0004100000 0.0026580000 0.0000040000 0.0000040000 0.0022630000 46008349 96830484 509673472 3.9395663738 3.9578099251 3.4186558723 2706 1311867260.7188229561 0.1381352544 0.0943732054 0.1381352544 0.0061174575 0.0163800000 0.0005100000 0.0031800000 0.0000010000 0.0000090000 0.0013360000 46012021 96830484 509673472 3.9355366230 3.9570324421 3.4157543182 2707 1311867260.7493369579 0.1364767253 0.0943887589 0.1381352544 0.0061184077 0.0129870000 0.0004090000 0.0033620000 0.0000040000 0.0000040000 0.0015070000 46015581 96830484 509673472 3.9387834072 3.9580199718 3.4132537842 2708 1311867260.7859649658 0.1350654215 0.0944037799 0.1381352544 0.0061201872 0.0137850000 0.0004060000 0.0044250000 0.0000000000 0.0000040000 0.0011970000 46019421 96830484 509673472 3.9410274029 3.9561555386 3.4104647636 2709 1311867260.8179080486 0.1372841001 0.0944196087 0.1381352544 0.0061218371 0.0186730000 0.0004960000 0.0046370000 0.0000070000 0.0000080000 0.0024510000 46023149 96830484 509673472 3.9393212795 3.9551293850 3.4068453312 2710 1311867260.8514599800 0.1360158920 0.0944349579 0.1381352544 0.0061259271 0.0126640000 0.0004090000 0.0033440000 0.0000010000 0.0000050000 0.0012020000 46026821 96830484 509673472 3.9410002232 3.9536647797 3.4038138390 2711 1311867260.8867430687 0.1361300796 0.0944503379 0.1381352544 0.0061255415 0.0124650000 0.0004040000 0.0029620000 0.0000030000 0.0000030000 0.0015200000 46030493 96830484 509673472 3.9417538643 3.9522457123 3.4001896381 2712 1311867260.9177849293 0.1376488805 0.0944662665 0.1381352544 0.0061248616 0.0125500000 0.0004000000 0.0033080000 0.0000010000 0.0000040000 0.0011980000 46034165 96830484 509673472 3.9409148693 3.9535405636 3.3971669674 2713 1311867260.9494459629 0.1372689158 0.0944820434 0.1381352544 0.0061372491 0.0138770000 0.0004010000 0.0036780000 0.0000030000 0.0000030000 0.0022770000 46037837 96830484 509673472 3.9406275749 3.9527378082 3.3936982155 2714 1311867260.9869680405 0.1389594525 0.0944984315 0.1389594525 0.0061469365 0.0116840000 0.0003970000 0.0022650000 0.0000000000 0.0000030000 0.0012020000 46041677 96830484 509673472 3.9403438568 3.9508213997 3.3905982971 2715 1311867261.0202260017 0.1416338980 0.0945157927 0.1416338980 0.0061468583 0.0139860000 0.0004000000 0.0043610000 0.0000040000 0.0000040000 0.0015240000 46045349 96830484 509673472 3.9371001720 3.9495217800 3.3871483803 2716 1311867261.0519640446 0.1401337385 0.0945325887 0.1416338980 0.0061477792 0.0128860000 0.0004400000 0.0028530000 0.0000000000 0.0000050000 0.0012010000 46049021 96830484 509673472 3.9390547276 3.9477787018 3.3845951557 2717 1311867261.0871579647 0.1412184238 0.0945497715 0.1416338980 0.0061467486 0.0132730000 0.0004390000 0.0029590000 0.0000030000 0.0000030000 0.0022580000 46052805 96830484 509673472 3.9373836517 3.9441204071 3.3811550140 2718 1311867261.1197659969 0.1431186348 0.0945676409 0.1431186348 0.0061468097 0.0136620000 0.0003960000 0.0043360000 0.0000000000 0.0000040000 0.0012090000 46056477 96830484 509673472 3.9351115227 3.9417295456 3.3778252602 2719 1311867261.1530790329 0.1423022449 0.0945851968 0.1431186348 0.0061495054 0.0123890000 0.0003840000 0.0029110000 0.0000030000 0.0000040000 0.0015020000 46060205 96830484 509673472 3.9363961220 3.9413337708 3.3747754097 2720 1311867261.1872630119 0.1443205029 0.0946034819 0.1443205029 0.0061519455 0.0136640000 0.0003870000 0.0042820000 0.0000010000 0.0000040000 0.0011780000 46063933 96830484 509673472 3.9336798191 3.9397041798 3.3715691566 2721 1311867261.2191090584 0.1450214386 0.0946220111 0.1450214386 0.0061568841 0.0171630000 0.0004910000 0.0031680000 0.0000080000 0.0000080000 0.0024560000 46067605 96830484 509673472 3.9318890572 3.9370527267 3.3685514927 2722 1311867261.2548229694 0.1471506059 0.0946413089 0.1471506059 0.0061562020 0.0129500000 0.0003820000 0.0035960000 0.0000010000 0.0000040000 0.0012020000 46071333 96830484 509673472 3.9302446842 3.9377439022 3.3659658432 2723 1311867261.2879600525 0.1470418572 0.0946605525 0.1471506059 0.0061556707 0.0121870000 0.0003810000 0.0025730000 0.0000040000 0.0000040000 0.0015310000 46075117 96830484 509673472 3.9304602146 3.9386136532 3.3630909920 2724 1311867261.3185029030 0.1496460140 0.0946807381 0.1496460140 0.0061619266 0.0122080000 0.0003810000 0.0029070000 0.0000000000 0.0000050000 0.0011750000 46078789 96830484 509673472 3.9271898270 3.9396791458 3.3605928421 2725 1311867261.3546299934 0.1524132043 0.0947019243 0.1524132043 0.0061623504 0.0137460000 0.0003690000 0.0032180000 0.0000040000 0.0000040000 0.0022970000 46082517 96830484 509673472 3.9231715202 3.9405550957 3.3578271866 2726 1311867261.3858330250 0.1528230309 0.0947232453 0.1528230309 0.0061613904 0.0180340000 0.0004790000 0.0045530000 0.0000010000 0.0000080000 0.0013520000 46086133 96830484 509673472 3.9222538471 3.9417927265 3.3556194305 2727 1311867261.4186379910 0.1534354836 0.0947447753 0.1534354836 0.0061605115 0.0130050000 0.0004010000 0.0032540000 0.0000040000 0.0000040000 0.0015440000 46089805 96830484 509673472 3.9213392735 3.9434013367 3.3541712761 2728 1311867261.4558680058 0.1518922001 0.0947657238 0.1534354836 0.0061624127 0.0118410000 0.0003720000 0.0024300000 0.0000010000 0.0000040000 0.0011990000 46093645 96830484 509673472 3.9208819866 3.9408953190 3.3522613049 2729 1311867261.4862189293 0.1519976407 0.0947866955 0.1534354836 0.0061641966 0.0131780000 0.0003810000 0.0029000000 0.0000040000 0.0000030000 0.0022650000 46097261 96830484 509673472 3.9203491211 3.9406063557 3.3503310680 2730 1311867261.5178630352 0.1548108160 0.0948086824 0.1548108160 0.0061635833 0.0114860000 0.0003780000 0.0021040000 0.0000000000 0.0000040000 0.0012060000 46100989 96830484 509673472 3.9164466858 3.9411084652 3.3491742611 2731 1311867261.5556519032 0.1518869996 0.0948295825 0.1548108160 0.0061626766 0.0128820000 0.0003860000 0.0032440000 0.0000030000 0.0000030000 0.0015220000 46104773 96830484 509673472 3.9194197655 3.9413521290 3.3476245403 2732 1311867261.5857899189 0.1541805267 0.0948513069 0.1548108160 0.0061655872 0.0180710000 0.0004770000 0.0045460000 0.0000010000 0.0000080000 0.0013410000 46108389 96830484 509673472 3.9160153866 3.9399731159 3.3460345268 2733 1311867261.6174640656 0.1536216140 0.0948728109 0.1548108160 0.0061650007 0.0147290000 0.0003950000 0.0042980000 0.0000050000 0.0000040000 0.0022220000 46112117 96830484 509673472 3.9163942337 3.9420971870 3.3441662788 2734 1311867261.6652009487 0.1533351690 0.0948941943 0.1548108160 0.0061654924 0.0124540000 0.0003850000 0.0028970000 0.0000010000 0.0000040000 0.0011920000 46116181 96830484 509673472 3.9157142639 3.9413461685 3.3415153027 2735 1311867261.6889929771 0.1556235999 0.0949163988 0.1556235999 0.0061649572 0.0127480000 0.0003880000 0.0029080000 0.0000040000 0.0000030000 0.0014910000 46119629 96830484 509673472 3.9121887684 3.9413897991 3.3388712406 2736 1311867261.7193109989 0.1613748968 0.0949406892 0.1613748968 0.0061660043 0.0177820000 0.0004870000 0.0041870000 0.0000010000 0.0000080000 0.0013220000 46123189 96830484 509673472 3.9049677849 3.9434857368 3.3354094028 2737 1311867261.7601549625 0.1583135873 0.0949638434 0.1613748968 0.0061675795 0.0149810000 0.0003920000 0.0042810000 0.0000040000 0.0000040000 0.0022660000 46127029 96830484 509673472 3.9089434147 3.9445168972 3.3325634003 2738 1311867261.7876880169 0.1591212600 0.0949872756 0.1613748968 0.0061690513 0.0129780000 0.0003760000 0.0032460000 0.0000010000 0.0000040000 0.0011850000 46130589 96830484 509673472 3.9078371525 3.9474005699 3.3294713497 2739 1311867261.8213939667 0.1602619886 0.0950111072 0.1613748968 0.0061755212 0.0127560000 0.0003870000 0.0029150000 0.0000040000 0.0000040000 0.0015110000 46134317 96830484 509673472 3.9068300724 3.9504892826 3.3262145519 2740 1311867261.8598148823 0.1617246419 0.0950354552 0.1617246419 0.0061748916 0.0176500000 0.0004810000 0.0031330000 0.0000010000 0.0000120000 0.0015000000 46138101 96830484 509673472 3.9046745300 3.9495594501 3.3235511780 2741 1311867261.8885459900 0.1589702368 0.0950587805 0.1617246419 0.0061799308 0.0133480000 0.0003970000 0.0026090000 0.0000040000 0.0000040000 0.0023060000 46141717 96830484 509673472 3.9079551697 3.9516234398 3.3212890625 2742 1311867261.9212360382 0.1580317318 0.0950817466 0.1617246419 0.0061837435 0.0132300000 0.0003780000 0.0035900000 0.0000000000 0.0000040000 0.0012080000 46145389 96830484 509673472 3.9094972610 3.9538445473 3.3180813789 2743 1311867261.9592299461 0.1595783681 0.0951052598 0.1617246419 0.0061830344 0.0127840000 0.0003870000 0.0029190000 0.0000040000 0.0000040000 0.0015520000 46149285 96830484 509673472 3.9078214169 3.9545881748 3.3146669865 2744 1311867261.9886140823 0.1580473036 0.0951281978 0.1617246419 0.0061827997 0.0123410000 0.0003870000 0.0025640000 0.0000010000 0.0000040000 0.0012120000 46152845 96830484 509673472 3.9100577831 3.9546277523 3.3125917912 2745 1311867262.0219531059 0.1582591385 0.0951511964 0.1617246419 0.0061823627 0.0150210000 0.0003880000 0.0043000000 0.0000050000 0.0000040000 0.0023160000 46156573 96830484 509673472 3.9105596542 3.9566738605 3.3095974922 2746 1311867262.0576629639 0.1607796997 0.0951750960 0.1617246419 0.0061815474 0.0128280000 0.0003820000 0.0032470000 0.0000000000 0.0000030000 0.0012390000 46160357 96830484 509673472 3.9080147743 3.9574282169 3.3064112663 2747 1311867262.0944681168 0.1590359062 0.0951983435 0.1617246419 0.0061807618 0.0141110000 0.0003810000 0.0042970000 0.0000040000 0.0000030000 0.0015640000 46164085 96830484 509673472 3.9111447334 3.9580619335 3.3037419319 2748 1311867262.1180479527 0.1581574827 0.0952212544 0.1617246419 0.0061797869 0.0137540000 0.0004060000 0.0043010000 0.0000000000 0.0000040000 0.0012280000 46167533 96830484 509673472 3.9123673439 3.9597580433 3.3009185791 2749 1311867262.1539878845 0.1570655555 0.0952437514 0.1617246419 0.0061803861 0.0136340000 0.0003840000 0.0029230000 0.0000040000 0.0000040000 0.0023290000 46171317 96830484 509673472 3.9140217304 3.9603807926 3.2978258133 2750 1311867262.1906540394 0.1578383446 0.0952665131 0.1617246419 0.0061794559 0.0125950000 0.0003790000 0.0032770000 0.0000000000 0.0000040000 0.0012210000 46175045 96830484 509673472 3.9137177467 3.9608094692 3.2943103313 2751 1311867262.2200620174 0.1611459702 0.0952904605 0.1617246419 0.0061791974 0.0139340000 0.0003840000 0.0042930000 0.0000040000 0.0000040000 0.0015430000 46178717 96830484 509673472 3.9097232819 3.9608211517 3.2907621861 2752 1311867262.2557590008 0.1583197117 0.0953133636 0.1617246419 0.0061784946 0.0122510000 0.0003830000 0.0029170000 0.0000010000 0.0000040000 0.0012270000 46182445 96830484 509673472 3.9141087532 3.9623351097 3.2877502441 2753 1311867262.2893559933 0.1620412022 0.0953376018 0.1620412022 0.0061803876 0.0174830000 0.0004890000 0.0034980000 0.0000080000 0.0000080000 0.0025170000 46186173 96830484 509673472 3.9101123810 3.9643032551 3.2840430737 2754 1311867262.3192830086 0.1645542979 0.0953627350 0.1645542979 0.0061794237 0.0125960000 0.0003910000 0.0029350000 0.0000010000 0.0000050000 0.0012330000 46189845 96830484 509673472 3.9066851139 3.9658489227 3.2794466019 2755 1311867262.3543510437 0.1652458608 0.0953881009 0.1652458608 0.0061824932 0.0182890000 0.0004790000 0.0045560000 0.0000080000 0.0000080000 0.0017070000 46193573 96830484 509673472 3.9066123962 3.9675428867 3.2750792503 2756 1311867262.3862760067 0.1663133502 0.0954138358 0.1663133502 0.0061814442 0.0147270000 0.0004330000 0.0044430000 0.0000010000 0.0000050000 0.0012320000 46197189 96830484 509673472 3.9056553841 3.9699220657 3.2710585594 2757 1311867262.4192481041 0.1706237644 0.0954411154 0.1706237644 0.0061806078 0.0129590000 0.0003860000 0.0022260000 0.0000040000 0.0000040000 0.0023510000 46200917 96830484 509673472 3.9003150463 3.9714934826 3.2657926083 2758 1311867262.4579370022 0.1714006215 0.0954686569 0.1714006215 0.0061797955 0.0119490000 0.0003810000 0.0025710000 0.0000010000 0.0000040000 0.0012280000 46204757 96830484 509673472 3.9003286362 3.9726870060 3.2614977360 2759 1311867262.4882910252 0.1737120003 0.0954970162 0.1737120003 0.0061822299 0.0166220000 0.0004750000 0.0027450000 0.0000080000 0.0000080000 0.0017070000 46208429 96830484 509673472 3.8970837593 3.9754312038 3.2562353611 2760 1311867262.5228719711 0.1769159883 0.0955265159 0.1769159883 0.0061817575 0.0121530000 0.0003860000 0.0026060000 0.0000010000 0.0000040000 0.0012530000 46212157 96830484 509673472 3.8935482502 3.9756588936 3.2517063618 2761 1311867262.5554070473 0.1792083532 0.0955568244 0.1792083532 0.0061822536 0.0132020000 0.0003820000 0.0025650000 0.0000040000 0.0000040000 0.0023450000 46215829 96830484 509673472 3.8914082050 3.9786815643 3.2471661568 2762 1311867262.5873200893 0.1789081246 0.0955870023 0.1792083532 0.0061911671 0.0122220000 0.0003740000 0.0027900000 0.0000000000 0.0000030000 0.0012420000 46219557 96830484 509673472 3.8918900490 3.9799206257 3.2430448532 2763 1311867262.6235508919 0.1803700924 0.0956176874 0.1803700924 0.0061936383 0.0184300000 0.0004600000 0.0045400000 0.0000090000 0.0000080000 0.0017200000 46223341 96830484 509673472 3.8900029659 3.9821264744 3.2388932705 2764 1311867262.6548008919 0.1793053001 0.0956479651 0.1803700924 0.0061934858 0.0128290000 0.0003750000 0.0032520000 0.0000000000 0.0000040000 0.0012550000 46226957 96830484 509673472 3.8911767006 3.9836950302 3.2353603840 2765 1311867262.6901140213 0.1823160946 0.0956793098 0.1823160946 0.0061944182 0.0134720000 0.0003680000 0.0029050000 0.0000040000 0.0000040000 0.0023650000 46230685 96830484 509673472 3.8876025677 3.9842517376 3.2315232754 2766 1311867262.7234799862 0.1786151677 0.0957092939 0.1823160946 0.0061934860 0.0120380000 0.0003730000 0.0025710000 0.0000000000 0.0000040000 0.0012580000 46234413 96830484 509673472 3.8920202255 3.9850203991 3.2278242111 2767 1311867262.7550880909 0.1771138608 0.0957387137 0.1823160946 0.0061990987 0.0172460000 0.0004770000 0.0027730000 0.0000100000 0.0000100000 0.0017080000 46238085 96830484 509673472 3.8936698437 3.9832003117 3.2249622345 2768 1311867262.7890789509 0.1793046296 0.0957689037 0.1823160946 0.0062002227 0.0127100000 0.0003810000 0.0029530000 0.0000000000 0.0000040000 0.0012460000 46241757 96830484 509673472 3.8919072151 3.9834711552 3.2210669518 2769 1311867262.8232269287 0.1789387167 0.0957989397 0.1823160946 0.0061999163 0.0126950000 0.0003730000 0.0018860000 0.0000040000 0.0000040000 0.0023560000 46245597 96830484 509673472 3.8946719170 3.9828314781 3.2188353539 2770 1311867262.8561139107 0.1823978573 0.0958302029 0.1823978573 0.0062000966 0.0164250000 0.0004650000 0.0027640000 0.0000010000 0.0000090000 0.0014140000 46249213 96830484 509673472 3.8908007145 3.9836099148 3.2157888412 2771 1311867262.8878281116 0.1821506470 0.0958613542 0.1823978573 0.0061995544 0.0133620000 0.0003760000 0.0032560000 0.0000040000 0.0000040000 0.0015800000 46252885 96830484 509673472 3.8923692703 3.9840695858 3.2128586769 2772 1311867262.9221930504 0.1853490919 0.0958936370 0.1853490919 0.0062001877 0.0124030000 0.0003790000 0.0029040000 0.0000000000 0.0000050000 0.0012560000 46256669 96830484 509673472 3.8902876377 3.9851791859 3.2108335495 2773 1311867262.9539968967 0.1870974898 0.0959265269 0.1870974898 0.0062005896 0.0141390000 0.0003810000 0.0035710000 0.0000040000 0.0000040000 0.0023590000 46260341 96830484 509673472 3.8904469013 3.9850990772 3.2088608742 2774 1311867262.9877319336 0.1881545186 0.0959597742 0.1881545186 0.0062011791 0.0116740000 0.0003660000 0.0022030000 0.0000010000 0.0000040000 0.0012570000 46264069 96830484 509673472 3.8891668320 3.9846785069 3.2065157890 2775 1311867263.0238440037 0.1904126406 0.0959938113 0.1904126406 0.0062001466 0.0123830000 0.0003690000 0.0025350000 0.0000040000 0.0000040000 0.0015740000 46267853 96830484 509673472 3.8875691891 3.9846308231 3.2040753365 2776 1311867263.0552799702 0.1916750520 0.0960282786 0.1916750520 0.0061991407 0.0144230000 0.0004130000 0.0042510000 0.0000010000 0.0000040000 0.0012450000 46271469 96830484 509673472 3.8867354393 3.9842822552 3.2020561695 2777 1311867263.0870039463 0.1935978234 0.0960634135 0.1935978234 0.0061981213 0.0141890000 0.0004160000 0.0035430000 0.0000040000 0.0000040000 0.0023780000 46275141 96830484 509673472 3.8849158287 3.9848551750 3.1995813847 2778 1311867263.1226899624 0.1952973157 0.0960991348 0.1952973157 0.0061972864 0.0137440000 0.0003630000 0.0041960000 0.0000010000 0.0000040000 0.0012300000 46278925 96830484 509673472 3.8829774857 3.9853205681 3.1970863342 2779 1311867263.1537079811 0.1942564398 0.0961344559 0.1952973157 0.0062007907 0.0136260000 0.0003620000 0.0038470000 0.0000040000 0.0000040000 0.0015480000 46282541 96830484 509673472 3.8837912083 3.9855234623 3.1941020489 2780 1311867263.1884229183 0.1942151189 0.0961697367 0.1952973157 0.0062001343 0.0178950000 0.0004490000 0.0041310000 0.0000010000 0.0000080000 0.0013810000 46286269 96830484 509673472 3.8838975430 3.9873678684 3.1919596195 2781 1311867263.2225809097 0.1916332990 0.0962040638 0.1952973157 0.0061994383 0.0138800000 0.0003640000 0.0028700000 0.0000050000 0.0000050000 0.0023570000 46290053 96830484 509673472 3.8866336346 3.9884631634 3.1895096302 2782 1311867263.2536139488 0.1894317865 0.0962375748 0.1952973157 0.0061992772 0.0122370000 0.0003620000 0.0025190000 0.0000010000 0.0000040000 0.0012460000 46293669 96830484 509673472 3.8887510300 3.9903655052 3.1865913868 2783 1311867263.2884469032 0.1918238997 0.0962719213 0.1952973157 0.0061991049 0.0132740000 0.0003620000 0.0031770000 0.0000040000 0.0000040000 0.0015720000 46297397 96830484 509673472 3.8855471611 3.9879899025 3.1845982075 2784 1311867263.3236269951 0.1917513460 0.0963062171 0.1952973157 0.0062173714 0.0125470000 0.0003600000 0.0028490000 0.0000010000 0.0000040000 0.0012400000 46301181 96830484 509673472 3.8858983517 3.9884667397 3.1828789711 2785 1311867263.3539469242 0.1889698356 0.0963394895 0.1952973157 0.0062182310 0.0187420000 0.0004530000 0.0044710000 0.0000090000 0.0000070000 0.0025450000 46304797 96830484 509673472 3.8883321285 3.9866695404 3.1803114414 2786 1311867263.3856530190 0.1909208298 0.0963734383 0.1952973157 0.0062173035 0.0122060000 0.0003610000 0.0025220000 0.0000010000 0.0000050000 0.0012450000 46308469 96830484 509673472 3.8861989975 3.9871954918 3.1779398918 2787 1311867263.4221460819 0.1927212179 0.0964080087 0.1952973157 0.0062163145 0.0124880000 0.0003600000 0.0025150000 0.0000040000 0.0000040000 0.0015460000 46312253 96830484 509673472 3.8848264217 3.9882102013 3.1756188869 2788 1311867263.4549560547 0.1947426796 0.0964432794 0.1952973157 0.0062157331 0.0176880000 0.0004490000 0.0044040000 0.0000010000 0.0000090000 0.0013820000 46315869 96830484 509673472 3.8834986687 3.9884214401 3.1734542847 2789 1311867263.4876389503 0.1937157810 0.0964781566 0.1952973157 0.0062156078 0.0179980000 0.0004500000 0.0030860000 0.0000100000 0.0000100000 0.0025410000 46319653 96830484 509673472 3.8851311207 3.9863116741 3.1710340977 2790 1311867263.5235950947 0.1927380115 0.0965126583 0.1952973157 0.0062197404 0.0139850000 0.0003600000 0.0041900000 0.0000000000 0.0000040000 0.0012340000 46323493 96830484 509673472 3.8870084286 3.9879674911 3.1676940918 2791 1311867263.5535099506 0.1964803338 0.0965484762 0.1964803338 0.0062209064 0.0131310000 0.0003590000 0.0031630000 0.0000040000 0.0000040000 0.0015730000 46327053 96830484 509673472 3.8840746880 3.9870219231 3.1652002335 2792 1311867263.5855040550 0.1944440156 0.0965835391 0.1964803338 0.0062206315 0.0164570000 0.0004470000 0.0030140000 0.0000010000 0.0000080000 0.0013830000 46330669 96830484 509673472 3.8879799843 3.9885323048 3.1625695229 2793 1311867263.6236140728 0.1959542483 0.0966191176 0.1964803338 0.0062228425 0.0177330000 0.0004500000 0.0027040000 0.0000110000 0.0000100000 0.0025600000 46334565 96830484 509673472 3.8884027004 3.9890105724 3.1590700150 2794 1311867263.6543920040 0.1959321052 0.0966546627 0.1964803338 0.0062225501 0.0130410000 0.0003690000 0.0028530000 0.0000000000 0.0000040000 0.0012640000 46338125 96830484 509673472 3.8901758194 3.9885280132 3.1569414139 2795 1311867263.6903779507 0.1977561563 0.0966908349 0.1977561563 0.0062216650 0.0128350000 0.0003600000 0.0024870000 0.0000040000 0.0000030000 0.0015790000 46341965 96830484 509673472 3.8898079395 3.9896881580 3.1533098221 2796 1311867263.7227630615 0.1958203912 0.0967262890 0.1977561563 0.0062225431 0.0138550000 0.0003530000 0.0041630000 0.0000000000 0.0000030000 0.0012380000 46345637 96830484 509673472 3.8932416439 3.9905128479 3.1496548653 2797 1311867263.7559669018 0.1988290399 0.0967627934 0.1988290399 0.0062220345 0.0142700000 0.0003540000 0.0033600000 0.0000030000 0.0000040000 0.0023450000 46349309 96830484 509673472 3.8907127380 3.9903910160 3.1461627483 2798 1311867263.7911560535 0.1946103275 0.0967977639 0.1988290399 0.0062224675 0.0136410000 0.0003520000 0.0041580000 0.0000010000 0.0000040000 0.0012350000 46353037 96830484 509673472 3.8976745605 3.9923624992 3.1429138184 2799 1311867263.8235189915 0.1949271262 0.0968328226 0.1988290399 0.0062214918 0.0126570000 0.0003460000 0.0028100000 0.0000030000 0.0000040000 0.0015650000 46356765 96830484 509673472 3.8982386589 3.9915137291 3.1392817497 2800 1311867263.8555519581 0.1935362071 0.0968673595 0.1988290399 0.0062210023 0.0135870000 0.0003510000 0.0041520000 0.0000010000 0.0000040000 0.0012460000 46360381 96830484 509673472 3.9016292095 3.9932138920 3.1363279819 2801 1311867263.8925390244 0.1960821003 0.0969027807 0.1988290399 0.0062199523 0.0129690000 0.0003530000 0.0024750000 0.0000040000 0.0000040000 0.0023510000 46364221 96830484 509673472 3.8998944759 3.9920961857 3.1328213215 2802 1311867263.9255890846 0.1965725571 0.0969383517 0.1988290399 0.0062188915 0.0118850000 0.0003540000 0.0024770000 0.0000010000 0.0000040000 0.0012470000 46367893 96830484 509673472 3.9011411667 3.9936113358 3.1305353642 2803 1311867263.9557209015 0.1986441910 0.0969746363 0.1988290399 0.0062181329 0.0138350000 0.0003540000 0.0041540000 0.0000040000 0.0000030000 0.0015630000 46371509 96830484 509673472 3.9002013206 3.9943423271 3.1281778812 2804 1311867263.9913449287 0.1969791502 0.0970103013 0.1988290399 0.0062174530 0.0119800000 0.0003540000 0.0024810000 0.0000000000 0.0000040000 0.0012490000 46375293 96830484 509673472 3.9033842087 3.9966495037 3.1247270107 2805 1311867264.0265080929 0.1972968131 0.0970460540 0.1988290399 0.0062165857 0.0139890000 0.0003540000 0.0031650000 0.0000030000 0.0000040000 0.0023850000 46379077 96830484 509673472 3.9044787884 3.9951505661 3.1227424145 2806 1311867264.0539839268 0.1992885917 0.0970824911 0.1992885917 0.0062163534 0.0131620000 0.0003530000 0.0038140000 0.0000000000 0.0000040000 0.0012440000 46382637 96830484 509673472 3.9031903744 3.9953708649 3.1209383011 2807 1311867264.0935840607 0.2031923085 0.0971202930 0.2031923085 0.0062157254 0.0141830000 0.0003690000 0.0041580000 0.0000040000 0.0000040000 0.0015800000 46386533 96830484 509673472 3.9007060528 3.9974300861 3.1189424992 2808 1311867264.1232929230 0.2020027041 0.0971576443 0.2031923085 0.0062150917 0.0121770000 0.0003530000 0.0028230000 0.0000010000 0.0000040000 0.0012520000 46390149 96830484 509673472 3.9028625488 3.9967219830 3.1168127060 2809 1311867264.1547811031 0.2007828504 0.0971945347 0.2031923085 0.0062155355 0.0148710000 0.0003530000 0.0041660000 0.0000040000 0.0000030000 0.0023920000 46393709 96830484 509673472 3.9046599865 3.9971103668 3.1145830154 2810 1311867264.1908740997 0.1990605742 0.0972307860 0.2031923085 0.0062157640 0.0173500000 0.0004630000 0.0043940000 0.0000010000 0.0000070000 0.0014140000 46397493 96830484 509673472 3.9081521034 3.9988048077 3.1119000912 2811 1311867264.2230439186 0.1990703940 0.0972670149 0.2031923085 0.0062167999 0.0136030000 0.0003620000 0.0035200000 0.0000040000 0.0000040000 0.0016100000 46401221 96830484 509673472 3.9083938599 3.9981048107 3.1094548702 2812 1311867264.2549281120 0.1999688298 0.0973035376 0.2031923085 0.0062186012 0.0177130000 0.0004660000 0.0037610000 0.0000020000 0.0000100000 0.0013980000 46404837 96830484 509673472 3.9084281921 3.9990375042 3.1069576740 2813 1311867264.2910940647 0.1983939707 0.0973394745 0.2031923085 0.0062237192 0.0133870000 0.0003700000 0.0025290000 0.0000040000 0.0000040000 0.0024060000 46408621 96830484 509673472 3.9112281799 3.9993979931 3.1040899754 2814 1311867264.3223540783 0.1998134553 0.0973758903 0.2031923085 0.0062271796 0.0163070000 0.0004540000 0.0022630000 0.0000010000 0.0000080000 0.0014180000 46412293 96830484 509673472 3.9105238914 3.9987645149 3.1013743877 2815 1311867264.3539710045 0.1988096833 0.0974119236 0.2031923085 0.0062327083 0.0138260000 0.0004130000 0.0025220000 0.0000040000 0.0000040000 0.0017950000 46415909 96830484 509673472 3.9114334583 3.9986865520 3.0989999771 2816 1311867264.3903570175 0.1951347888 0.0974466263 0.2031923085 0.0062346919 0.0131300000 0.0003600000 0.0031890000 0.0000010000 0.0000040000 0.0012690000 46419693 96830484 509673472 3.9166300297 3.9996931553 3.0964229107 2817 1311867264.4247128963 0.1944325864 0.0974810551 0.2031923085 0.0062386456 0.0143540000 0.0003570000 0.0035070000 0.0000050000 0.0000040000 0.0023730000 46423477 96830484 509673472 3.9165837765 3.9984047413 3.0933787823 2818 1311867264.4536709785 0.1914833486 0.0975144129 0.2031923085 0.0062402500 0.0138390000 0.0003560000 0.0041690000 0.0000000000 0.0000040000 0.0012520000 46427037 96830484 509673472 3.9195520878 3.9979631901 3.0911679268 2819 1311867264.4911220074 0.1898044348 0.0975471515 0.2031923085 0.0062395993 0.0134570000 0.0003560000 0.0034990000 0.0000040000 0.0000040000 0.0015900000 46430877 96830484 509673472 3.9216697216 4.0008587837 3.0888741016 2820 1311867264.5220930576 0.1875339150 0.0975790617 0.2031923085 0.0062399549 0.0119210000 0.0003560000 0.0024780000 0.0000000000 0.0000040000 0.0012390000 46434493 96830484 509673472 3.9238052368 3.9994657040 3.0862734318 2821 1311867264.5544660091 0.1858503670 0.0976103525 0.2031923085 0.0062407198 0.0137490000 0.0003560000 0.0028210000 0.0000030000 0.0000030000 0.0023880000 46438165 96830484 509673472 3.9264869690 3.9999082088 3.0849556923 2822 1311867264.5919189453 0.1818161458 0.0976401915 0.2031923085 0.0062411038 0.0126720000 0.0003540000 0.0031400000 0.0000010000 0.0000040000 0.0012470000 46442005 96830484 509673472 3.9312820435 3.9988784790 3.0826005936 2823 1311867264.6239540577 0.1814991534 0.0976698971 0.2031923085 0.0062417404 0.0124490000 0.0003600000 0.0024910000 0.0000030000 0.0000030000 0.0015660000 46445677 96830484 509673472 3.9319441319 3.9993414879 3.0809602737 2824 1311867264.6537890434 0.1802793741 0.0976991498 0.2031923085 0.0062414136 0.0133710000 0.0003570000 0.0038100000 0.0000000000 0.0000030000 0.0012330000 46449349 96830484 509673472 3.9328603745 3.9975802898 3.0788199902 2825 1311867264.6908979416 0.1778226793 0.0977275121 0.2031923085 0.0062412289 0.0134910000 0.0003510000 0.0027950000 0.0000040000 0.0000040000 0.0023670000 46453077 96830484 509673472 3.9361202717 3.9989225864 3.0768823624 2826 1311867264.7228040695 0.1770181805 0.0977555697 0.2031923085 0.0062413733 0.0129170000 0.0003520000 0.0034580000 0.0000010000 0.0000040000 0.0012350000 46456805 96830484 509673472 3.9370355606 3.9982135296 3.0754141808 2827 1311867264.7547140121 0.1737695634 0.0977824582 0.2031923085 0.0062404299 0.0139080000 0.0003610000 0.0041100000 0.0000040000 0.0000040000 0.0015480000 46460421 96830484 509673472 3.9409055710 3.9963881969 3.0737035275 2828 1311867264.7909140587 0.1751431674 0.0978098135 0.2031923085 0.0062403635 0.0136110000 0.0003500000 0.0041130000 0.0000000000 0.0000030000 0.0012210000 46464205 96830484 509673472 3.9401571751 3.9983510971 3.0725681782 2829 1311867264.8233439922 0.1740955859 0.0978367791 0.2031923085 0.0062398019 0.0132480000 0.0003560000 0.0024820000 0.0000040000 0.0000040000 0.0023160000 46467933 96830484 509673472 3.9415080547 3.9995822906 3.0707345009 2830 1311867264.8540790081 0.1737278998 0.0978635958 0.2031923085 0.0062390307 0.0183060000 0.0004490000 0.0043880000 0.0000010000 0.0000080000 0.0013830000 46471549 96830484 509673472 3.9422540665 4.0019164085 3.0689415932 2831 1311867264.8904409409 0.1761845350 0.0978912613 0.2031923085 0.0062380392 0.0179420000 0.0004410000 0.0033560000 0.0000120000 0.0000110000 0.0016990000 46475333 96830484 509673472 3.9395205975 4.0016527176 3.0674676895 2832 1311867264.9235579967 0.1740618050 0.0979181576 0.2031923085 0.0062370297 0.0123230000 0.0003600000 0.0024780000 0.0000000000 0.0000040000 0.0012350000 46479061 96830484 509673472 3.9426355362 4.0016856194 3.0666170120 2833 1311867264.9598839283 0.1746520102 0.0979452434 0.2031923085 0.0062362951 0.0138170000 0.0003580000 0.0028110000 0.0000040000 0.0000040000 0.0023460000 46482845 96830484 509673472 3.9419913292 3.9998137951 3.0652544498 2834 1311867264.9916839600 0.1772060245 0.0979732112 0.2031923085 0.0062356920 0.0129800000 0.0003530000 0.0031290000 0.0000010000 0.0000040000 0.0012250000 46486517 96830484 509673472 3.9404585361 4.0027871132 3.0649437904 2835 1311867265.0220029354 0.1777353734 0.0980013460 0.2031923085 0.0062346364 0.0139830000 0.0003560000 0.0027860000 0.0000040000 0.0000040000 0.0015650000 46490133 96830484 509673472 3.9397196770 4.0004839897 3.0639541149 2836 1311867265.0581490993 0.1806269139 0.0980304805 0.2031923085 0.0062338381 0.0124290000 0.0003940000 0.0024790000 0.0000010000 0.0000040000 0.0012330000 46493917 96830484 509673472 3.9370057583 4.0011262894 3.0633852482 2837 1311867265.0911719799 0.1781523526 0.0980587223 0.2031923085 0.0062331446 0.0134100000 0.0003530000 0.0024640000 0.0000040000 0.0000030000 0.0023560000 46497533 96830484 509673472 3.9400629997 4.0015988350 3.0620095730 2838 1311867265.1217110157 0.1826736778 0.0980885373 0.2031923085 0.0062344351 0.0123060000 0.0003440000 0.0024530000 0.0000000000 0.0000030000 0.0012400000 46501149 96830484 509673472 3.9357147217 4.0031614304 3.0610210896 2839 1311867265.1582090855 0.1815236062 0.0981179262 0.2031923085 0.0062334185 0.0125520000 0.0003490000 0.0024650000 0.0000040000 0.0000040000 0.0015390000 46504933 96830484 509673472 3.9372687340 4.0011086464 3.0595777035 2840 1311867265.1899518967 0.1815742552 0.0981473122 0.2031923085 0.0062334860 0.0179800000 0.0004480000 0.0043660000 0.0000010000 0.0000090000 0.0013880000 46508549 96830484 509673472 3.9371094704 4.0030612946 3.0577547550 2841 1311867265.2225220203 0.1883879900 0.0981790759 0.2031923085 0.0062344763 0.0192830000 0.0004640000 0.0043810000 0.0000090000 0.0000080000 0.0025430000 46512277 96830484 509673472 3.9294552803 4.0019164085 3.0567777157 2842 1311867265.2581849098 0.1907275468 0.0982116405 0.2031923085 0.0062365242 0.0174590000 0.0004590000 0.0043420000 0.0000010000 0.0000080000 0.0013610000 46515949 96830484 509673472 3.9275426865 4.0011920929 3.0548050404 2843 1311867265.2915129662 0.1938174963 0.0982452690 0.2031923085 0.0062369567 0.0143470000 0.0003570000 0.0041070000 0.0000040000 0.0000040000 0.0015630000 46519677 96830484 509673472 3.9252486229 4.0017681122 3.0532500744 2844 1311867265.3220860958 0.1984258741 0.0982804942 0.2031923085 0.0062365203 0.0190510000 0.0004530000 0.0037020000 0.0000010000 0.0000100000 0.0015270000 46523349 96830484 509673472 3.9198544025 4.0024900436 3.0516064167 2845 1311867265.3585588932 0.1992242783 0.0983159753 0.2031923085 0.0062354482 0.0326610000 0.0005830000 0.0025270000 0.0000150000 0.0000150000 0.0030900000 46527133 96830484 509673472 3.9194712639 4.0017385483 3.0501339436 2846 1311867265.3912470341 0.2019613832 0.0983523933 0.2031923085 0.0062349029 0.0158340000 0.0003830000 0.0041920000 0.0000010000 0.0000060000 0.0012980000 46530805 96830484 509673472 3.9169468880 4.0036320686 3.0485763550 2847 1311867265.4244530201 0.2039954811 0.0983895001 0.2039954811 0.0062340845 0.0129930000 0.0003610000 0.0024560000 0.0000040000 0.0000040000 0.0015700000 46534589 96830484 509673472 3.9146564007 4.0036149025 3.0465030670 2848 1311867265.4604411125 0.2058859468 0.0984272446 0.2058859468 0.0062332228 0.0182400000 0.0004380000 0.0043430000 0.0000010000 0.0000090000 0.0014060000 46538261 96830484 509673472 3.9127678871 4.0039215088 3.0445079803 2849 1311867265.4902420044 0.2015545368 0.0984634423 0.2058859468 0.0062322881 0.0138240000 0.0003550000 0.0027930000 0.0000040000 0.0000040000 0.0023850000 46541933 96830484 509673472 3.9176776409 4.0054764748 3.0422711372 2850 1311867265.5230569839 0.2034580857 0.0985002826 0.2058859468 0.0062316829 0.0232310000 0.0004520000 0.0044070000 0.0000010000 0.0000110000 0.0015510000 46545661 96830484 509673472 3.9153869152 4.0048179626 3.0405385494 2851 1311867265.5594520569 0.2074740827 0.0985385056 0.2074740827 0.0062309938 0.0137040000 0.0003500000 0.0021420000 0.0000050000 0.0000050000 0.0015880000 46549389 96830484 509673472 3.9112415314 4.0063548088 3.0386400223 2852 1311867265.5932300091 0.2042522579 0.0985755721 0.2074740827 0.0062308348 0.0144600000 0.0003580000 0.0041380000 0.0000010000 0.0000060000 0.0012780000 46553173 96830484 509673472 3.9149422646 4.0057530403 3.0365624428 2853 1311867265.6250700951 0.2090028822 0.0986142778 0.2090028822 0.0062304348 0.0225540000 0.0004510000 0.0036890000 0.0000110000 0.0000100000 0.0027740000 46556733 96830484 509673472 3.9098770618 4.0063967705 3.0349519253 2854 1311867265.6610729694 0.2106014341 0.0986535164 0.2106014341 0.0062296166 0.0128610000 0.0003510000 0.0024760000 0.0000010000 0.0000050000 0.0012720000 46560517 96830484 509673472 3.9080603123 4.0053825378 3.0326857567 2855 1311867265.6956009865 0.2095022053 0.0986923426 0.2106014341 0.0062285694 0.0132470000 0.0003400000 0.0030870000 0.0000040000 0.0000040000 0.0015750000 46564245 96830484 509673472 3.9102036953 4.0082283020 3.0316646099 2856 1311867265.7221889496 0.2107263356 0.0987315702 0.2107263356 0.0062276113 0.0138570000 0.0003410000 0.0040860000 0.0000010000 0.0000040000 0.0012560000 46567805 96830484 509673472 3.9087302685 4.0104598999 3.0295450687 2857 1311867265.7626268864 0.2063049078 0.0987692227 0.2107263356 0.0062280442 0.0130440000 0.0003450000 0.0021220000 0.0000040000 0.0000030000 0.0024100000 46571701 96830484 509673472 3.9137158394 4.0097146034 3.0287053585 2858 1311867265.7925920486 0.2066710740 0.0988069771 0.2107263356 0.0062274285 0.0121550000 0.0003400000 0.0024450000 0.0000010000 0.0000040000 0.0012560000 46575317 96830484 509673472 3.9132440090 4.0111064911 3.0274062157 2859 1311867265.8224210739 0.2079402655 0.0988451489 0.2107263356 0.0062265273 0.0133050000 0.0003450000 0.0030830000 0.0000040000 0.0000040000 0.0016090000 46578933 96830484 509673472 3.9119994640 4.0128893852 3.0262744427 2860 1311867265.8593389988 0.2066105008 0.0988828291 0.2107263356 0.0062256795 0.0163680000 0.0004370000 0.0022820000 0.0000000000 0.0000080000 0.0014180000 46582717 96830484 509673472 3.9136471748 4.0118246078 3.0259888172 2861 1311867265.8943600655 0.2099056989 0.0989216347 0.2107263356 0.0062249356 0.0152980000 0.0003540000 0.0040880000 0.0000040000 0.0000040000 0.0024100000 46586445 96830484 509673472 3.9099311829 4.0137767792 3.0244364738 2862 1311867265.9256451130 0.2075480223 0.0989595894 0.2107263356 0.0062242023 0.0165200000 0.0004490000 0.0023160000 0.0000010000 0.0000120000 0.0014090000 46590117 96830484 509673472 3.9130053520 4.0132565498 3.0241258144 2863 1311867265.9620978832 0.2090546489 0.0989980439 0.2107263356 0.0062233816 0.0139070000 0.0003570000 0.0037710000 0.0000040000 0.0000040000 0.0015820000 46593901 96830484 509673472 3.9112870693 4.0119390488 3.0230996609 2864 1311867265.9908990860 0.2102195621 0.0990368782 0.2107263356 0.0062238241 0.0138500000 0.0003450000 0.0040620000 0.0000000000 0.0000040000 0.0012580000 46597461 96830484 509673472 3.9099626541 4.0125560760 3.0210821629 2865 1311867266.0233469009 0.2087162137 0.0990751607 0.2107263356 0.0062227565 0.0149190000 0.0003480000 0.0040550000 0.0000040000 0.0000040000 0.0024060000 46601189 96830484 509673472 3.9122207165 4.0116872787 3.0209653378 2866 1311867266.0634260178 0.2142261714 0.0991153390 0.2142261714 0.0062219441 0.0187690000 0.0004840000 0.0043260000 0.0000010000 0.0000080000 0.0013980000 46605085 96830484 509673472 3.9057638645 4.0117187500 3.0188519955 2867 1311867266.0954639912 0.2132156044 0.0991551368 0.2142261714 0.0062209641 0.0142240000 0.0003500000 0.0039950000 0.0000040000 0.0000030000 0.0015610000 46608701 96830484 509673472 3.9069290161 4.0128297806 3.0174195766 2868 1311867266.1241600513 0.2125282437 0.0991946671 0.2142261714 0.0062201716 0.0130580000 0.0003580000 0.0029880000 0.0000000000 0.0000040000 0.0012430000 46612317 96830484 509673472 3.9077360630 4.0119943619 3.0162324905 2869 1311867266.1634809971 0.2082058787 0.0992326634 0.2142261714 0.0062206726 0.0209390000 0.0004490000 0.0025320000 0.0000100000 0.0000100000 0.0027820000 46616213 96830484 509673472 3.9127559662 4.0123510361 3.0153162479 2870 1311867266.1922690868 0.2095808387 0.0992711122 0.2142261714 0.0062197503 0.0143840000 0.0003510000 0.0040960000 0.0000010000 0.0000040000 0.0012650000 46619773 96830484 509673472 3.9110596180 4.0136747360 3.0145397186 2871 1311867266.2255198956 0.2094645947 0.0993094938 0.2142261714 0.0062189711 0.0126940000 0.0003430000 0.0024280000 0.0000040000 0.0000040000 0.0015760000 46623501 96830484 509673472 3.9104785919 4.0142073631 3.0127038956 2872 1311867266.2597849369 0.2085738778 0.0993475385 0.2142261714 0.0062179059 0.0122620000 0.0003400000 0.0024360000 0.0000010000 0.0000040000 0.0012550000 46627173 96830484 509673472 3.9115881920 4.0140390396 3.0119557381 2873 1311867266.2915120125 0.2100278288 0.0993860628 0.2142261714 0.0062170089 0.0149550000 0.0003460000 0.0040480000 0.0000030000 0.0000030000 0.0024030000 46630845 96830484 509673472 3.9091506004 4.0110859871 3.0108332634 2874 1311867266.3258039951 0.2139420360 0.0994259222 0.2142261714 0.0062164612 0.0136660000 0.0003380000 0.0040630000 0.0000000000 0.0000040000 0.0012510000 46634517 96830484 509673472 3.9046287537 4.0140180588 3.0089538097 2875 1311867266.3601551056 0.2115310580 0.0994649153 0.2142261714 0.0062160368 0.0138600000 0.0003360000 0.0040360000 0.0000040000 0.0000040000 0.0015830000 46638245 96830484 509673472 3.9070222378 4.0142569542 3.0071525574 2876 1311867266.3913159370 0.2123757154 0.0995041750 0.2142261714 0.0062150197 0.0122080000 0.0003420000 0.0024250000 0.0000010000 0.0000040000 0.0012460000 46641917 96830484 509673472 3.9056975842 4.0136547089 3.0056793690 2877 1311867266.4254870415 0.2135537565 0.0995438168 0.2142261714 0.0062153226 0.0148990000 0.0003570000 0.0040420000 0.0000040000 0.0000030000 0.0023980000 46645645 96830484 509673472 3.9040100574 4.0123906136 3.0048766136 2878 1311867266.4612910748 0.2113505155 0.0995826656 0.2142261714 0.0062146781 0.0120390000 0.0003330000 0.0021010000 0.0000010000 0.0000040000 0.0012550000 46649429 96830484 509673472 3.9059925079 4.0115976334 3.0032997131 2879 1311867266.4912600517 0.2122160196 0.0996217879 0.2142261714 0.0062137807 0.0165160000 0.0004370000 0.0019480000 0.0000080000 0.0000090000 0.0017340000 46652989 96830484 509673472 3.9046518803 4.0116386414 3.0018649101 2880 1311867266.5284929276 0.2100978196 0.0996601477 0.2142261714 0.0062131375 0.0126720000 0.0003440000 0.0024310000 0.0000010000 0.0000050000 0.0012600000 46656885 96830484 509673472 3.9061801434 4.0105547905 2.9994294643 2881 1311867266.5587360859 0.2092834413 0.0996981981 0.2142261714 0.0062133508 0.0145400000 0.0003370000 0.0033980000 0.0000040000 0.0000040000 0.0024190000 46660445 96830484 509673472 3.9068458080 4.0127301216 2.9974195957 2882 1311867266.5906820297 0.2097321749 0.0997363778 0.2142261714 0.0062123061 0.0118810000 0.0003220000 0.0017870000 0.0000010000 0.0000040000 0.0012730000 46664117 96830484 509673472 3.9059245586 4.0116615295 2.9961290359 2883 1311867266.6256470680 0.2116188258 0.0997751855 0.2142261714 0.0062124495 0.0126560000 0.0003210000 0.0019940000 0.0000040000 0.0000030000 0.0016290000 46667845 96830484 509673472 3.9029645920 4.0100150108 2.9937255383 2884 1311867266.6596419811 0.2090106010 0.0998130618 0.2142261714 0.0062116951 0.0131260000 0.0003280000 0.0020840000 0.0000000000 0.0000040000 0.0012670000 46671573 96830484 509673472 3.9060106277 4.0097303391 2.9937148094 2885 1311867266.6914939880 0.2137008011 0.0998525377 0.2142261714 0.0062113460 0.0144490000 0.0003680000 0.0030520000 0.0000040000 0.0000040000 0.0023850000 46675245 96830484 509673472 3.9008121490 4.0124382973 2.9932999611 2886 1311867266.7260789871 0.2145568728 0.0998922828 0.2145568728 0.0062104189 0.0139250000 0.0003260000 0.0040520000 0.0000000000 0.0000040000 0.0012580000 46678973 96830484 509673472 3.8990995884 4.0094637871 2.9922530651 2887 1311867266.7576239109 0.2164950669 0.0999326717 0.2164950669 0.0062096927 0.0140860000 0.0003220000 0.0040280000 0.0000040000 0.0000040000 0.0015560000 46682701 96830484 509673472 3.8971643448 4.0130290985 2.9913702011 2888 1311867266.7898240089 0.2143260241 0.0999722816 0.2164950669 0.0062094012 0.0138570000 0.0003330000 0.0040130000 0.0000010000 0.0000040000 0.0012560000 46686373 96830484 509673472 3.8991999626 4.0119404793 2.9912934303 2889 1311867266.8257129192 0.2113308161 0.1000108273 0.2164950669 0.0062086541 0.0145480000 0.0003240000 0.0037180000 0.0000030000 0.0000030000 0.0024130000 46690157 96830484 509673472 3.9023330212 4.0109362602 2.9914033413 2890 1311867266.8575000763 0.2165960222 0.1000511682 0.2165960222 0.0062080520 0.0126900000 0.0003370000 0.0028380000 0.0000010000 0.0000040000 0.0012610000 46693829 96830484 509673472 3.8967349529 4.0121173859 2.9922568798 2891 1311867266.8898739815 0.2173260301 0.1000917337 0.2173260301 0.0062076018 0.0122480000 0.0003250000 0.0019830000 0.0000040000 0.0000040000 0.0015990000 46697501 96830484 509673472 3.8955404758 4.0107879639 2.9931795597 2892 1311867266.9266190529 0.2141108364 0.1001311593 0.2173260301 0.0062072620 0.0139060000 0.0003450000 0.0040370000 0.0000010000 0.0000040000 0.0012540000 46701285 96830484 509673472 3.8987491131 4.0118560791 2.9935219288 2893 1311867266.9576549530 0.2146926820 0.1001707589 0.2173260301 0.0062063326 0.0149980000 0.0003240000 0.0039400000 0.0000030000 0.0000030000 0.0023790000 46704957 96830484 509673472 3.8984200954 4.0117068291 2.9959769249 2894 1311867266.9920771122 0.2161476612 0.1002108339 0.2173260301 0.0062083567 0.0124090000 0.0003370000 0.0024280000 0.0000010000 0.0000040000 0.0012600000 46708685 96830484 509673472 3.8967473507 4.0139684677 2.9972181320 2895 1311867267.0259480476 0.2138545811 0.1002500890 0.2173260301 0.0062088128 0.0132810000 0.0003330000 0.0030790000 0.0000030000 0.0000040000 0.0015590000 46712357 96830484 509673472 3.8987920284 4.0130200386 2.9989645481 2896 1311867267.0603609085 0.2146729529 0.1002895997 0.2173260301 0.0062088524 0.0123600000 0.0003360000 0.0024400000 0.0000010000 0.0000040000 0.0012520000 46716029 96830484 509673472 3.8977890015 4.0133457184 3.0006923676 2897 1311867267.0929799080 0.2171219587 0.1003299284 0.2173260301 0.0062078867 0.0149180000 0.0003430000 0.0039570000 0.0000040000 0.0000040000 0.0024160000 46719589 96830484 509673472 3.8944826126 4.0123949051 3.0011706352 2898 1311867267.1266899109 0.2177371532 0.1003704416 0.2177371532 0.0062108559 0.0119210000 0.0003460000 0.0018940000 0.0000000000 0.0000040000 0.0012500000 46723261 96830484 509673472 3.8937094212 4.0129981041 3.0025260448 2899 1311867267.1586909294 0.2179389298 0.1004109965 0.2179389298 0.0062102268 0.0171330000 0.0004390000 0.0025250000 0.0000100000 0.0000070000 0.0017380000 46726989 96830484 509673472 3.8933665752 4.0145483017 3.0032870770 2900 1311867267.1916129589 0.2143570036 0.1004502882 0.2179389298 0.0062106499 0.0127120000 0.0003450000 0.0024480000 0.0000000000 0.0000040000 0.0012640000 46730661 96830484 509673472 3.8961222172 4.0101523399 3.0036630630 2901 1311867267.2262039185 0.2146641612 0.1004896587 0.2179389298 0.0062098128 0.0132850000 0.0003450000 0.0021050000 0.0000040000 0.0000030000 0.0023960000 46734333 96830484 509673472 3.8954298496 4.0100426674 3.0043921471 2902 1311867267.2587449551 0.2151071578 0.1005291547 0.2179389298 0.0062090927 0.0138340000 0.0003450000 0.0039560000 0.0000000000 0.0000040000 0.0012520000 46738005 96830484 509673472 3.8945212364 4.0112113953 3.0047416687 2903 1311867267.2920761108 0.2183988839 0.1005697575 0.2183988839 0.0062088238 0.0143130000 0.0003430000 0.0040740000 0.0000040000 0.0000030000 0.0015650000 46741733 96830484 509673472 3.8905649185 4.0121541023 3.0053286552 2904 1311867267.3265810013 0.2174839377 0.1006100172 0.2183988839 0.0062079376 0.0132000000 0.0003430000 0.0030900000 0.0000000000 0.0000030000 0.0012570000 46745517 96830484 509673472 3.8909993172 4.0102906227 3.0063483715 2905 1311867267.3609950542 0.2164866179 0.1006499059 0.2183988839 0.0062074448 0.0153130000 0.0003430000 0.0040740000 0.0000040000 0.0000040000 0.0023870000 46749189 96830484 509673472 3.8922400475 4.0107483864 3.0081176758 2906 1311867267.3945980072 0.2149923593 0.1006892529 0.2183988839 0.0062066859 0.0139270000 0.0003420000 0.0039940000 0.0000010000 0.0000040000 0.0012430000 46752861 96830484 509673472 3.8933486938 4.0097289085 3.0086026192 2907 1311867267.4286189079 0.2204200923 0.1007304400 0.2204200923 0.0062067637 0.0130570000 0.0003490000 0.0027690000 0.0000050000 0.0000040000 0.0015750000 46756645 96830484 509673472 3.8870456219 4.0090131760 3.0091962814 2908 1311867267.4595789909 0.2189924270 0.1007711078 0.2204200923 0.0062059517 0.0123210000 0.0003470000 0.0021220000 0.0000000000 0.0000040000 0.0012600000 46760261 96830484 509673472 3.8887848854 4.0101861954 3.0098106861 2909 1311867267.4935429096 0.2165294588 0.1008109009 0.2204200923 0.0062052813 0.0153280000 0.0003460000 0.0040920000 0.0000040000 0.0000040000 0.0024050000 46763989 96830484 509673472 3.8914859295 4.0107932091 3.0109000206 2910 1311867267.5264101028 0.2179431021 0.1008511526 0.2204200923 0.0062051148 0.0139580000 0.0003450000 0.0041050000 0.0000010000 0.0000040000 0.0012470000 46767661 96830484 509673472 3.8902094364 4.0128221512 3.0117352009 2911 1311867267.5577969551 0.2221681625 0.1008928279 0.2221681625 0.0062089029 0.0143340000 0.0003520000 0.0040960000 0.0000040000 0.0000040000 0.0015980000 46771389 96830484 509673472 3.8862371445 4.0121827126 3.0130980015 2912 1311867267.5954480171 0.2224405110 0.1009345682 0.2224405110 0.0062095133 0.0140490000 0.0003420000 0.0040820000 0.0000000000 0.0000040000 0.0012570000 46775173 96830484 509673472 3.8850007057 4.0108180046 3.0148179531 2913 1311867267.6272020340 0.2189862281 0.1009750940 0.2224405110 0.0062092944 0.0131630000 0.0003520000 0.0020210000 0.0000050000 0.0000040000 0.0023700000 46778845 96830484 509673472 3.8886709213 4.0108985901 3.0163676739 2914 1311867267.6608970165 0.2192801684 0.1010156929 0.2224405110 0.0062084508 0.0208020000 0.0005260000 0.0044430000 0.0000020000 0.0000100000 0.0015340000 46782517 96830484 509673472 3.8877537251 4.0104236603 3.0172765255 2915 1311867267.6955730915 0.2218600512 0.1010571489 0.2224405110 0.0062075099 0.0148060000 0.0003770000 0.0041270000 0.0000040000 0.0000040000 0.0016130000 46786301 96830484 509673472 3.8848650455 4.0108084679 3.0189306736 2916 1311867267.7264549732 0.2209327668 0.1010982585 0.2224405110 0.0062156007 0.0126150000 0.0003490000 0.0024650000 0.0000010000 0.0000040000 0.0012570000 46789917 96830484 509673472 3.8857614994 4.0127825737 3.0199017525 2917 1311867267.7624979019 0.2191202343 0.1011387186 0.2224405110 0.0062216142 0.0136010000 0.0003500000 0.0021280000 0.0000040000 0.0000040000 0.0024090000 46793757 96830484 509673472 3.8871610165 4.0101938248 3.0218906403 2918 1311867267.7957980633 0.2178005874 0.1011786987 0.2224405110 0.0062208061 0.0127630000 0.0003530000 0.0024580000 0.0000010000 0.0000040000 0.0012750000 46797429 96830484 509673472 3.8876006603 4.0086579323 3.0228111744 2919 1311867267.8323969841 0.2167586088 0.1012182944 0.2224405110 0.0062201268 0.0125770000 0.0003510000 0.0021320000 0.0000030000 0.0000030000 0.0015940000 46801269 96830484 509673472 3.8884055614 4.0075273514 3.0248324871 2920 1311867267.8601078987 0.2151865363 0.1012573246 0.2224405110 0.0062194500 0.0169700000 0.0004430000 0.0031900000 0.0000020000 0.0000080000 0.0014140000 46804773 96830484 509673472 3.8898956776 4.0106153488 3.0257802010 2921 1311867267.8989579678 0.2114972025 0.1012950650 0.2224405110 0.0062230464 0.0137190000 0.0003580000 0.0024810000 0.0000040000 0.0000040000 0.0023860000 46808669 96830484 509673472 3.8922169209 4.0086698532 3.0268006325 2922 1311867267.9282948971 0.2162158638 0.1013343945 0.2224405110 0.0062226721 0.0180650000 0.0004520000 0.0037190000 0.0000010000 0.0000090000 0.0014160000 46812229 96830484 509673472 3.8870494366 4.0080609322 3.0291895866 2923 1311867267.9643011093 0.2105161250 0.1013717472 0.2224405110 0.0062226049 0.0134600000 0.0003550000 0.0027950000 0.0000040000 0.0000050000 0.0016180000 46816013 96830484 509673472 3.8930480480 4.0079407692 3.0309667587 2924 1311867267.9947459698 0.2097141296 0.1014088000 0.2224405110 0.0062216366 0.0147270000 0.0003480000 0.0037210000 0.0000010000 0.0000040000 0.0014670000 46819685 96830484 509673472 3.8933169842 4.0071973801 3.0318288803 2925 1311867268.0287120342 0.2116438001 0.1014464872 0.2224405110 0.0062210368 0.0153330000 0.0003480000 0.0041070000 0.0000040000 0.0000040000 0.0024110000 46823357 96830484 509673472 3.8904275894 4.0053153038 3.0334589481 2926 1311867268.0588328838 0.2109508216 0.1014839117 0.2224405110 0.0062209553 0.0125800000 0.0003500000 0.0024660000 0.0000000000 0.0000040000 0.0012610000 46827029 96830484 509673472 3.8914651871 4.0069870949 3.0359692574 2927 1311867268.0946080685 0.2103870362 0.1015211181 0.2224405110 0.0062203229 0.0127070000 0.0003480000 0.0021310000 0.0000040000 0.0000040000 0.0015940000 46830813 96830484 509673472 3.8912043571 4.0043401718 3.0384101868 2928 1311867268.1253910065 0.2104257345 0.1015583123 0.2224405110 0.0062198878 0.0180450000 0.0004370000 0.0043430000 0.0000010000 0.0000080000 0.0014010000 46834429 96830484 509673472 3.8906779289 4.0036892891 3.0402300358 2929 1311867268.1606659889 0.2123566568 0.1015961404 0.2224405110 0.0062218816 0.0137660000 0.0003570000 0.0024770000 0.0000040000 0.0000040000 0.0023940000 46838157 96830484 509673472 3.8883662224 4.0040235519 3.0429866314 2930 1311867268.1981959343 0.2135019898 0.1016343335 0.2224405110 0.0062212516 0.0134170000 0.0003550000 0.0031270000 0.0000000000 0.0000040000 0.0012550000 46841997 96830484 509673472 3.8863890171 4.0046324730 3.0453264713 2931 1311867268.2290298939 0.2146966904 0.1016729082 0.2224405110 0.0062204009 0.0193150000 0.0004500000 0.0044280000 0.0000100000 0.0000070000 0.0017020000 46845669 96830484 509673472 3.8843500614 4.0044503212 3.0470893383 2932 1311867268.2579200268 0.2136763632 0.1017111085 0.2224405110 0.0062202116 0.0143970000 0.0003540000 0.0041380000 0.0000010000 0.0000040000 0.0012530000 46849229 96830484 509673472 3.8846054077 4.0023336411 3.0495779514 2933 1311867268.2951550484 0.2140414119 0.1017494073 0.2224405110 0.0062215997 0.0140410000 0.0003530000 0.0024650000 0.0000040000 0.0000040000 0.0023910000 46853013 96830484 509673472 3.8836669922 4.0014691353 3.0528736115 2934 1311867268.3274168968 0.2134486288 0.1017874779 0.2224405110 0.0062216374 0.0172510000 0.0004440000 0.0023360000 0.0000010000 0.0000110000 0.0014930000 46856685 96830484 509673472 3.8835687637 4.0011200905 3.0551908016 2935 1311867268.3586890697 0.2135365456 0.1018255526 0.2224405110 0.0062210592 0.0146850000 0.0003620000 0.0041490000 0.0000050000 0.0000040000 0.0016090000 46860413 96830484 509673472 3.8828301430 3.9990932941 3.0573704243 2936 1311867268.3934800625 0.2145809084 0.1018639570 0.2224405110 0.0062201645 0.0134150000 0.0003590000 0.0031320000 0.0000010000 0.0000050000 0.0012490000 46864141 96830484 509673472 3.8803830147 3.9993596077 3.0599284172 2937 1311867268.4261479378 0.2142100930 0.1019022090 0.2224405110 0.0062191388 0.0152120000 0.0003550000 0.0041230000 0.0000040000 0.0000030000 0.0024020000 46867813 96830484 509673472 3.8800120354 3.9988350868 3.0625226498 2938 1311867268.4581170082 0.2141293585 0.1019404075 0.2224405110 0.0062194636 0.0132430000 0.0003580000 0.0031260000 0.0000000000 0.0000040000 0.0012510000 46871485 96830484 509673472 3.8791058064 3.9990041256 3.0647895336 2939 1311867268.4943540096 0.2129942924 0.1019781938 0.2224405110 0.0062187236 0.0128990000 0.0003550000 0.0024860000 0.0000040000 0.0000040000 0.0015790000 46875269 96830484 509673472 3.8789525032 3.9956736565 3.0679318905 2940 1311867268.5280330181 0.2104909867 0.1020151029 0.2224405110 0.0062177827 0.0141260000 0.0003580000 0.0041540000 0.0000000000 0.0000040000 0.0012550000 46878997 96830484 509673472 3.8803181648 3.9955835342 3.0695655346 2941 1311867268.5616149902 0.2135046721 0.1020530116 0.2224405110 0.0062177119 0.0152800000 0.0003460000 0.0041340000 0.0000040000 0.0000030000 0.0023770000 46882725 96830484 509673472 3.8761162758 3.9971828461 3.0720324516 2942 1311867268.5949339867 0.2107434124 0.1020899560 0.2224405110 0.0062181598 0.0142150000 0.0003540000 0.0041370000 0.0000000000 0.0000040000 0.0012460000 46886397 96830484 509673472 3.8780944347 3.9972820282 3.0738677979 2943 1311867268.6294579506 0.2100235969 0.1021266307 0.2224405110 0.0062211808 0.0150490000 0.0003550000 0.0037950000 0.0000030000 0.0000040000 0.0015570000 46890181 96830484 509673472 3.8775453568 3.9967260361 3.0759482384 2944 1311867268.6639370918 0.2098819613 0.1021632324 0.2224405110 0.0062218485 0.0174830000 0.0004990000 0.0023350000 0.0000010000 0.0000100000 0.0015220000 46893965 96830484 509673472 3.8763408661 3.9959926605 3.0783290863 2945 1311867268.6937808990 0.2116099894 0.1022003960 0.2224405110 0.0062212478 0.0139650000 0.0003680000 0.0024960000 0.0000050000 0.0000050000 0.0023950000 46897525 96830484 509673472 3.8733673096 3.9956769943 3.0806603432 2946 1311867268.7282569408 0.2114183903 0.1022374693 0.2224405110 0.0062202284 0.0142470000 0.0003570000 0.0041270000 0.0000010000 0.0000040000 0.0012560000 46901253 96830484 509673472 3.8722813129 3.9958574772 3.0822844505 2947 1311867268.7629311085 0.2110183239 0.1022743817 0.2224405110 0.0062202426 0.0144020000 0.0003550000 0.0040230000 0.0000040000 0.0000030000 0.0015860000 46905037 96830484 509673472 3.8721945286 3.9951813221 3.0850257874 2948 1311867268.7951219082 0.2122970521 0.1023117028 0.2224405110 0.0062197927 0.0142490000 0.0003590000 0.0041290000 0.0000010000 0.0000040000 0.0012490000 46908653 96830484 509673472 3.8702659607 3.9960715771 3.0874578953 2949 1311867268.8264629841 0.2108207345 0.1023484980 0.2224405110 0.0062192694 0.0142740000 0.0003520000 0.0031410000 0.0000040000 0.0000040000 0.0023470000 46912325 96830484 509673472 3.8703413010 3.9949605465 3.0903673172 2950 1311867268.8615820408 0.2097015828 0.1023848889 0.2224405110 0.0062190632 0.0120750000 0.0003600000 0.0018150000 0.0000000000 0.0000040000 0.0012460000 46916053 96830484 509673472 3.8698847294 3.9932739735 3.0929710865 2951 1311867268.8947710991 0.2074602693 0.1024204956 0.2224405110 0.0062262571 0.0143690000 0.0003600000 0.0040260000 0.0000040000 0.0000040000 0.0015820000 46919725 96830484 509673472 3.8709065914 3.9946539402 3.0959167480 2952 1311867268.9271900654 0.2114743739 0.1024574379 0.2224405110 0.0062348735 0.0142000000 0.0003560000 0.0041510000 0.0000000000 0.0000040000 0.0012520000 46923453 96830484 509673472 3.8657598495 3.9946744442 3.0991871357 2953 1311867268.9633738995 0.2080548555 0.1024931973 0.2224405110 0.0062344042 0.0155760000 0.0003590000 0.0041470000 0.0000030000 0.0000030000 0.0023820000 46927293 96830484 509673472 3.8679723740 3.9925973415 3.1028192043 2954 1311867268.9942259789 0.2104587108 0.1025297462 0.2224405110 0.0062348203 0.0141620000 0.0003530000 0.0041800000 0.0000010000 0.0000040000 0.0012490000 46930853 96830484 509673472 3.8644595146 3.9933812618 3.1057984829 2955 1311867269.0293419361 0.2081701905 0.1025654960 0.2224405110 0.0062346789 0.0192910000 0.0004890000 0.0044400000 0.0000080000 0.0000080000 0.0017240000 46934693 96830484 509673472 3.8656826019 3.9903342724 3.1097366810 2956 1311867269.0628340244 0.2076523751 0.1026010463 0.2224405110 0.0062337048 0.0144870000 0.0003630000 0.0041780000 0.0000000000 0.0000040000 0.0012520000 46938421 96830484 509673472 3.8650338650 3.9902029037 3.1126885414 2957 1311867269.0942130089 0.2085976601 0.1026368923 0.2224405110 0.0062327081 0.0136790000 0.0003550000 0.0024890000 0.0000040000 0.0000030000 0.0023610000 46941925 96830484 509673472 3.8627939224 3.9895486832 3.1158995628 2958 1311867269.1263980865 0.2124029696 0.1026740005 0.2224405110 0.0062319073 0.0180910000 0.0004490000 0.0033960000 0.0000010000 0.0000110000 0.0013920000 46945597 96830484 509673472 3.8576717377 3.9891176224 3.1192877293 2959 1311867269.1618270874 0.2091191709 0.1027099739 0.2224405110 0.0062310353 0.0128530000 0.0003630000 0.0021580000 0.0000040000 0.0000040000 0.0015990000 46949325 96830484 509673472 3.8594045639 3.9890944958 3.1215553284 2960 1311867269.1941618919 0.2075792104 0.1027454027 0.2224405110 0.0062306367 0.0127920000 0.0003630000 0.0024980000 0.0000000000 0.0000050000 0.0012670000 46952997 96830484 509673472 3.8594224453 3.9880759716 3.1249182224 2961 1311867269.2266249657 0.2097268999 0.1027815329 0.2224405110 0.0062330873 0.0173720000 0.0004550000 0.0020130000 0.0000090000 0.0000070000 0.0025600000 46956669 96830484 509673472 3.8561148643 3.9888956547 3.1275136471 2962 1311867269.2623720169 0.2054924369 0.1028162091 0.2224405110 0.0062337607 0.0128880000 0.0003610000 0.0024050000 0.0000010000 0.0000040000 0.0012750000 46960453 96830484 509673472 3.8587465286 3.9880480766 3.1302144527 2963 1311867269.2948200703 0.2044193149 0.1028504997 0.2224405110 0.0062621456 0.0146140000 0.0003640000 0.0041720000 0.0000030000 0.0000030000 0.0015590000 46964181 96830484 509673472 3.8578321934 3.9870843887 3.1330144405 2964 1311867269.3261830807 0.2040405124 0.1028846394 0.2224405110 0.0062689253 0.0145220000 0.0003620000 0.0041930000 0.0000010000 0.0000040000 0.0012520000 46967797 96830484 509673472 3.8576436043 3.9891338348 3.1364111900 2965 1311867269.3641560078 0.2053285092 0.1029191904 0.2224405110 0.0062704527 0.0157000000 0.0003590000 0.0041830000 0.0000040000 0.0000040000 0.0023880000 46971637 96830484 509673472 3.8547315598 3.9910280704 3.1392009258 2966 1311867269.3967740536 0.2032200545 0.1029530073 0.2224405110 0.0062718691 0.0142560000 0.0003650000 0.0038810000 0.0000000000 0.0000030000 0.0012570000 46975309 96830484 509673472 3.8550724983 3.9865946770 3.1434772015 2967 1311867269.4275820255 0.2009244859 0.1029860277 0.2224405110 0.0062730981 0.0146450000 0.0003640000 0.0041120000 0.0000040000 0.0000040000 0.0015660000 46978981 96830484 509673472 3.8569943905 3.9883203506 3.1462388039 2968 1311867269.4626441002 0.2014557421 0.1030192048 0.2224405110 0.0062723057 0.0138660000 0.0003630000 0.0035570000 0.0000000000 0.0000040000 0.0012470000 46982709 96830484 509673472 3.8554828167 3.9885170460 3.1494925022 2969 1311867269.4938280582 0.1999631375 0.1030518569 0.2224405110 0.0062883670 0.0180170000 0.0004570000 0.0027360000 0.0000090000 0.0000080000 0.0025630000 46986325 96830484 509673472 3.8567669392 3.9893505573 3.1533641815 2970 1311867269.5278589725 0.1975743622 0.1030836826 0.2224405110 0.0063076750 0.0132370000 0.0003720000 0.0025680000 0.0000010000 0.0000050000 0.0012440000 46990109 96830484 509673472 3.8585515022 3.9903962612 3.1570279598 2971 1311867269.5634589195 0.1955448985 0.1031148039 0.2224405110 0.0063071256 0.0132440000 0.0003680000 0.0025610000 0.0000040000 0.0000040000 0.0015790000 46993893 96830484 509673472 3.8590648174 3.9905126095 3.1599750519 2972 1311867269.5962390900 0.1951536983 0.1031457725 0.2224405110 0.0063066240 0.0130010000 0.0003760000 0.0025560000 0.0000000000 0.0000030000 0.0012450000 46997565 96830484 509673472 3.8586642742 3.9904074669 3.1624586582 2973 1311867269.6306080818 0.1941085756 0.1031763688 0.2224405110 0.0063056669 0.0136820000 0.0003770000 0.0022100000 0.0000040000 0.0000030000 0.0023660000 47001293 96830484 509673472 3.8582947254 3.9896523952 3.1653490067 2974 1311867269.6631560326 0.1939648241 0.1032068962 0.2224405110 0.0063046410 0.0133990000 0.0003730000 0.0029230000 0.0000010000 0.0000040000 0.0012460000 47005021 96830484 509673472 3.8577420712 3.9902951717 3.1683835983 2975 1311867269.6964600086 0.1909859031 0.1032364018 0.2224405110 0.0063092910 0.0148900000 0.0003820000 0.0043100000 0.0000030000 0.0000030000 0.0015800000 47008637 96830484 509673472 3.8604013920 3.9918553829 3.1712126732 2976 1311867269.7280869484 0.1900552809 0.1032655748 0.2224405110 0.0063089576 0.0129240000 0.0003810000 0.0022330000 0.0000010000 0.0000040000 0.0012520000 47012365 96830484 509673472 3.8597278595 3.9914422035 3.1723575592 2977 1311867269.7622261047 0.1899476498 0.1032946921 0.2224405110 0.0063085526 0.0136360000 0.0003740000 0.0022220000 0.0000040000 0.0000040000 0.0023540000 47016093 96830484 509673472 3.8589389324 3.9900400639 3.1752882004 2978 1311867269.7974090576 0.1860705167 0.1033224878 0.2224405110 0.0063077472 0.0125640000 0.0003810000 0.0022400000 0.0000010000 0.0000040000 0.0012370000 47019821 96830484 509673472 3.8618667126 3.9895095825 3.1768946648 2979 1311867269.8295869827 0.1866862923 0.1033504716 0.2224405110 0.0063183078 0.0129690000 0.0003790000 0.0022330000 0.0000040000 0.0000040000 0.0015670000 47023493 96830484 509673472 3.8603181839 3.9895629883 3.1793382168 2980 1311867269.8676230907 0.1879279166 0.1033788533 0.2224405110 0.0063179687 0.0181730000 0.0004750000 0.0035140000 0.0000010000 0.0000080000 0.0013950000 47027277 96830484 509673472 3.8569667339 3.9870002270 3.1811370850 2981 1311867269.8953619003 0.1877145618 0.1034071444 0.2224405110 0.0063170252 0.0161380000 0.0003860000 0.0043260000 0.0000040000 0.0000030000 0.0023590000 47030837 96830484 509673472 3.8571541309 3.9875037670 3.1831188202 2982 1311867269.9344720840 0.1847456992 0.1034344209 0.2224405110 0.0063161155 0.0145710000 0.0003830000 0.0032810000 0.0000000000 0.0000040000 0.0012450000 47034677 96830484 509673472 3.8596894741 3.9879820347 3.1850528717 2983 1311867269.9627900124 0.1876688302 0.1034626591 0.2224405110 0.0063218777 0.0151050000 0.0004360000 0.0043120000 0.0000040000 0.0000040000 0.0015680000 47038293 96830484 509673472 3.8559727669 3.9873592854 3.1869351864 2984 1311867269.9987258911 0.1895964295 0.1034915243 0.2224405110 0.0063213405 0.0144300000 0.0003810000 0.0040900000 0.0000000000 0.0000040000 0.0012360000 47042077 96830484 509673472 3.8533196449 3.9862935543 3.1888396740 2985 1311867270.0306990147 0.1879095286 0.1035198050 0.2224405110 0.0063218821 0.0279010000 0.0005690000 0.0047260000 0.0000160000 0.0000150000 0.0030980000 47045693 96830484 509673472 3.8545384407 3.9844684601 3.1911909580 2986 1311867270.0660951138 0.1902541369 0.1035488520 0.2224405110 0.0063213304 0.0148710000 0.0004040000 0.0036910000 0.0000010000 0.0000040000 0.0012650000 47049477 96830484 509673472 3.8520076275 3.9849524498 3.1938614845 2987 1311867270.0948200226 0.1901105046 0.1035778315 0.2224405110 0.0063204366 0.0137430000 0.0003810000 0.0028310000 0.0000040000 0.0000030000 0.0015810000 47052981 96830484 509673472 3.8523929119 3.9863049984 3.1958916187 2988 1311867270.1336340904 0.1897588372 0.1036066739 0.2224405110 0.0063193900 0.0133380000 0.0003810000 0.0029430000 0.0000010000 0.0000040000 0.0012510000 47056933 96830484 509673472 3.8524060249 3.9864029884 3.1985309124 2989 1311867270.1624090672 0.1908351034 0.1036358570 0.2224405110 0.0063184071 0.0151540000 0.0003780000 0.0036660000 0.0000040000 0.0000040000 0.0023510000 47060493 96830484 509673472 3.8514275551 3.9867923260 3.2012779713 2990 1311867270.1943540573 0.1894168258 0.1036645463 0.2224405110 0.0063176328 0.0132810000 0.0003840000 0.0029410000 0.0000010000 0.0000050000 0.0012480000 47064165 96830484 509673472 3.8526711464 3.9847254753 3.2043530941 2991 1311867270.2323369980 0.1878279597 0.1036926852 0.2224405110 0.0063191586 0.0132730000 0.0003830000 0.0025980000 0.0000030000 0.0000030000 0.0015810000 47068005 96830484 509673472 3.8539955616 3.9852545261 3.2063839436 2992 1311867270.2655749321 0.1870295554 0.1037205384 0.2224405110 0.0063203917 0.0141710000 0.0003890000 0.0039880000 0.0000010000 0.0000040000 0.0012540000 47071677 96830484 509673472 3.8540260792 3.9825677872 3.2090864182 2993 1311867270.2960460186 0.1846012473 0.1037475617 0.2224405110 0.0063194662 0.0142290000 0.0003990000 0.0026090000 0.0000030000 0.0000040000 0.0023610000 47075293 96830484 509673472 3.8568873405 3.9816055298 3.2119858265 2994 1311867270.3346099854 0.1824364066 0.1037738439 0.2224405110 0.0063191992 0.0130610000 0.0003860000 0.0026210000 0.0000000000 0.0000040000 0.0012400000 47079189 96830484 509673472 3.8586487770 3.9812738895 3.2142791748 2995 1311867270.3624660969 0.1852291375 0.1038010410 0.2224405110 0.0063182772 0.0136110000 0.0003950000 0.0029710000 0.0000040000 0.0000030000 0.0015830000 47082749 96830484 509673472 3.8553376198 3.9813487530 3.2163934708 2996 1311867270.3957469463 0.1865351945 0.1038286558 0.2224405110 0.0063185671 0.0133430000 0.0003920000 0.0029500000 0.0000000000 0.0000040000 0.0012410000 47086421 96830484 509673472 3.8540353775 3.9805676937 3.2196035385 2997 1311867270.4334359169 0.1851717979 0.1038557974 0.2224405110 0.0063249420 0.0135890000 0.0003910000 0.0022620000 0.0000040000 0.0000040000 0.0023530000 47090317 96830484 509673472 3.8554766178 3.9808726311 3.2230854034 2998 1311867270.4641909599 0.1839676946 0.1038825191 0.2224405110 0.0063241321 0.0170460000 0.0004920000 0.0024620000 0.0000010000 0.0000090000 0.0014130000 47093989 96830484 509673472 3.8565647602 3.9792718887 3.2257492542 2999 1311867270.4954609871 0.1827673912 0.1039088229 0.2224405110 0.0063236896 0.0153080000 0.0003970000 0.0043800000 0.0000040000 0.0000040000 0.0015810000 47097549 96830484 509673472 3.8575661182 3.9771318436 3.2287702560 3000 1311867270.5331869125 0.1845875680 0.1039357158 0.2224405110 0.0063230697 0.0141180000 0.0004040000 0.0026140000 0.0000000000 0.0000040000 0.0012670000 47101445 96830484 509673472 3.8559131622 3.9771580696 3.2317342758 3001 1311867270.5629880428 0.1833607703 0.1039621820 0.2224405110 0.0063224294 0.0145230000 0.0004510000 0.0027540000 0.0000040000 0.0000040000 0.0023570000 47105061 96830484 509673472 3.8569045067 3.9733326435 3.2345972061 3002 1311867270.5944859982 0.1809008569 0.1039878111 0.2224405110 0.0063216278 0.0173560000 0.0005230000 0.0028160000 0.0000010000 0.0000080000 0.0014100000 47108621 96830484 509673472 3.8592302799 3.9703359604 3.2367815971 3003 1311867270.6312110424 0.1815052927 0.1040136245 0.2224405110 0.0063220775 0.0191420000 0.0004900000 0.0046380000 0.0000080000 0.0000070000 0.0017230000 47112405 96830484 509673472 3.8595721722 3.9718770981 3.2396869659 3004 1311867270.6644439697 0.1827334911 0.1040398295 0.2224405110 0.0063236901 0.0140010000 0.0004040000 0.0033400000 0.0000010000 0.0000040000 0.0012510000 47116077 96830484 509673472 3.8586788177 3.9710536003 3.2414629459 3005 1311867270.6950180531 0.1807986498 0.1040653732 0.2224405110 0.0063236279 0.0144580000 0.0003980000 0.0029850000 0.0000040000 0.0000040000 0.0023320000 47119693 96830484 509673472 3.8603141308 3.9698014259 3.2435584068 3006 1311867270.7318449020 0.1809914112 0.1040909640 0.2224405110 0.0063230863 0.0146720000 0.0004000000 0.0043720000 0.0000000000 0.0000030000 0.0012350000 47123533 96830484 509673472 3.8605251312 3.9681947231 3.2459442616 3007 1311867270.7623898983 0.1805181950 0.1041163805 0.2224405110 0.0063221808 0.0130920000 0.0003900000 0.0026150000 0.0000040000 0.0000030000 0.0015490000 47127149 96830484 509673472 3.8612802029 3.9696712494 3.2476468086 3008 1311867270.7960500717 0.1816473305 0.1041421554 0.2224405110 0.0063217003 0.0144440000 0.0004000000 0.0042490000 0.0000000000 0.0000040000 0.0012430000 47130877 96830484 509673472 3.8600249290 3.9679341316 3.2492787838 3009 1311867270.8322730064 0.1818119586 0.1041679679 0.2224405110 0.0063242977 0.0199480000 0.0005110000 0.0046490000 0.0000080000 0.0000080000 0.0025370000 47134661 96830484 509673472 3.8601822853 3.9686911106 3.2516689301 3010 1311867270.8635489941 0.1800303161 0.1041931713 0.2224405110 0.0063246214 0.0133560000 0.0004090000 0.0026390000 0.0000010000 0.0000040000 0.0012490000 47138333 96830484 509673472 3.8627393246 3.9684133530 3.2541553974 3011 1311867270.8945889473 0.1819304824 0.1042189891 0.2224405110 0.0063244853 0.0130750000 0.0003970000 0.0022750000 0.0000040000 0.0000040000 0.0015590000 47141949 96830484 509673472 3.8600416183 3.9660191536 3.2555613518 3012 1311867270.9326179028 0.1811464578 0.1042445294 0.2224405110 0.0063276702 0.0134070000 0.0003940000 0.0030010000 0.0000000000 0.0000040000 0.0012420000 47145789 96830484 509673472 3.8621315956 3.9663753510 3.2580480576 3013 1311867270.9624550343 0.1789016724 0.1042693078 0.2224405110 0.0063308248 0.0180150000 0.0004970000 0.0028380000 0.0000090000 0.0000080000 0.0025240000 47149405 96830484 509673472 3.8662297726 3.9689238071 3.2606065273 3014 1311867270.9944560528 0.1777459383 0.1042936862 0.2224405110 0.0063305891 0.0130930000 0.0004040000 0.0026730000 0.0000000000 0.0000040000 0.0012360000 47153077 96830484 509673472 3.8670737743 3.9660139084 3.2617411613 3015 1311867271.0306649208 0.1759692729 0.1043174592 0.2224405110 0.0063297542 0.0143420000 0.0004050000 0.0036920000 0.0000040000 0.0000040000 0.0015610000 47156805 96830484 509673472 3.8690264225 3.9627571106 3.2636106014 3016 1311867271.0623910427 0.1748347729 0.1043408403 0.2224405110 0.0063294095 0.0137120000 0.0004010000 0.0030100000 0.0000010000 0.0000040000 0.0012240000 47160477 96830484 509673472 3.8712918758 3.9616360664 3.2658901215 3017 1311867271.0983459949 0.1767386496 0.1043648369 0.2224405110 0.0063314430 0.0186410000 0.0004950000 0.0025270000 0.0000110000 0.0000100000 0.0025270000 47164261 96830484 509673472 3.8697128296 3.9610679150 3.2670001984 3018 1311867271.1322019100 0.1794748753 0.1043897242 0.2224405110 0.0063304762 0.0151680000 0.0004070000 0.0044270000 0.0000010000 0.0000040000 0.0012270000 47167933 96830484 509673472 3.8665959835 3.9587755203 3.2684051991 3019 1311867271.1643741131 0.1791697145 0.1044144940 0.2224405110 0.0063298773 0.0152410000 0.0004030000 0.0044210000 0.0000030000 0.0000030000 0.0015670000 47171605 96830484 509673472 3.8681497574 3.9595808983 3.2701568604 3020 1311867271.1988029480 0.1812852025 0.1044399479 0.2224405110 0.0063296109 0.0148900000 0.0004010000 0.0044140000 0.0000000000 0.0000050000 0.0012220000 47175389 96830484 509673472 3.8660330772 3.9580757618 3.2716522217 3021 1311867271.2320818901 0.1793198735 0.1044647344 0.2224405110 0.0063305876 0.0184360000 0.0005100000 0.0028500000 0.0000070000 0.0000080000 0.0025190000 47179005 96830484 509673472 3.8684840202 3.9561464787 3.2735087872 3022 1311867271.2645740509 0.1813988239 0.1044901924 0.2224405110 0.0063334873 0.0144810000 0.0004020000 0.0035980000 0.0000010000 0.0000050000 0.0012340000 47182677 96830484 509673472 3.8675746918 3.9580512047 3.2761740685 3023 1311867271.2998549938 0.1795124412 0.1045150095 0.2224405110 0.0063344156 0.0135650000 0.0004040000 0.0026310000 0.0000040000 0.0000040000 0.0015610000 47186461 96830484 509673472 3.8702433109 3.9564094543 3.2789175510 3024 1311867271.3354289532 0.1790206879 0.1045396477 0.2224405110 0.0063358469 0.0186370000 0.0004970000 0.0046430000 0.0000010000 0.0000080000 0.0013710000 47190189 96830484 509673472 3.8700463772 3.9514987469 3.2815914154 3025 1311867271.3673670292 0.1763455421 0.1045633851 0.2224405110 0.0063354551 0.0141220000 0.0004090000 0.0022950000 0.0000040000 0.0000040000 0.0023260000 47193917 96830484 509673472 3.8736560345 3.9519741535 3.2843205929 3026 1311867271.3988809586 0.1756162792 0.1045868659 0.2224405110 0.0063348963 0.0134240000 0.0003990000 0.0026440000 0.0000000000 0.0000040000 0.0012330000 47197589 96830484 509673472 3.8750474453 3.9501476288 3.2869424820 3027 1311867271.4355340004 0.1755813509 0.1046103197 0.2224405110 0.0063340772 0.0139140000 0.0004020000 0.0026390000 0.0000040000 0.0000040000 0.0015520000 47201373 96830484 509673472 3.8745846748 3.9470412731 3.2894816399 3028 1311867271.4657170773 0.1750449538 0.1046335808 0.2224405110 0.0063364053 0.0137370000 0.0004040000 0.0030070000 0.0000010000 0.0000040000 0.0012350000 47204933 96830484 509673472 3.8751590252 3.9441874027 3.2924220562 3029 1311867271.4997088909 0.1748689115 0.1046567684 0.2224405110 0.0063389905 0.0144430000 0.0004010000 0.0026290000 0.0000040000 0.0000040000 0.0023320000 47208717 96830484 509673472 3.8752555847 3.9433965683 3.2947359085 3030 1311867271.5323960781 0.1738907099 0.1046796179 0.2224405110 0.0063386611 0.0133890000 0.0003990000 0.0026110000 0.0000000000 0.0000040000 0.0012380000 47212389 96830484 509673472 3.8764758110 3.9415755272 3.2980184555 3031 1311867271.5676190853 0.1732696295 0.1047022474 0.2224405110 0.0063378544 0.0137550000 0.0004010000 0.0029780000 0.0000040000 0.0000040000 0.0015460000 47216117 96830484 509673472 3.8767592907 3.9384768009 3.3013691902 3032 1311867271.5991230011 0.1726782024 0.1047246669 0.2224405110 0.0063369341 0.0128520000 0.0003990000 0.0022730000 0.0000000000 0.0000030000 0.0012300000 47219789 96830484 509673472 3.8776955605 3.9383924007 3.3045992851 3033 1311867271.6349890232 0.1718457788 0.1047467972 0.2224405110 0.0063364054 0.0158120000 0.0003990000 0.0043780000 0.0000040000 0.0000040000 0.0022970000 47223517 96830484 509673472 3.8779397011 3.9358327389 3.3084158897 3034 1311867271.6658320427 0.1708320975 0.1047685788 0.2224405110 0.0063356278 0.0146660000 0.0003980000 0.0043800000 0.0000000000 0.0000040000 0.0012260000 47227189 96830484 509673472 3.8793652058 3.9355895519 3.3126208782 3035 1311867271.7005228996 0.1704118550 0.1047902075 0.2224405110 0.0063383008 0.0140850000 0.0003940000 0.0033180000 0.0000040000 0.0000040000 0.0015430000 47230917 96830484 509673472 3.8792457581 3.9349768162 3.3167841434 3036 1311867271.7349541187 0.1704325974 0.1048118289 0.2224405110 0.0063378643 0.0138850000 0.0004130000 0.0033260000 0.0000010000 0.0000040000 0.0012160000 47234701 96830484 509673472 3.8777129650 3.9336121082 3.3211452961 3037 1311867271.7661850452 0.1663160622 0.1048320805 0.2224405110 0.0063401885 0.0142020000 0.0003960000 0.0026340000 0.0000030000 0.0000040000 0.0022990000 47238317 96830484 509673472 3.8805515766 3.9299638271 3.3256361485 3038 1311867271.7994530201 0.1672876775 0.1048526386 0.2224405110 0.0063438576 0.0155540000 0.0003980000 0.0040230000 0.0000000000 0.0000040000 0.0011810000 47242101 96830484 509673472 3.8791754246 3.9300606251 3.3298871517 3039 1311867271.8341000080 0.1629301757 0.1048717494 0.2224405110 0.0063434278 0.0140070000 0.0004440000 0.0030820000 0.0000040000 0.0000040000 0.0014790000 47245773 96830484 509673472 3.8826959133 3.9282927513 3.3342928886 3040 1311867271.8629150391 0.1622775942 0.1048906329 0.2224405110 0.0063432570 0.0140120000 0.0003970000 0.0033320000 0.0000000000 0.0000030000 0.0011630000 47249389 96830484 509673472 3.8825356960 3.9233241081 3.3395173550 3041 1311867271.9009630680 0.1600522846 0.1049087722 0.2224405110 0.0063423263 0.0141950000 0.0004010000 0.0026270000 0.0000040000 0.0000030000 0.0022220000 47253229 96830484 509673472 3.8840389252 3.9220128059 3.3443799019 3042 1311867271.9304800034 0.1609508246 0.1049271949 0.2224405110 0.0063417460 0.0135880000 0.0004070000 0.0029770000 0.0000000000 0.0000040000 0.0011830000 47256845 96830484 509673472 3.8830966949 3.9225656986 3.3493733406 3043 1311867271.9669768810 0.1593393981 0.1049450761 0.2224405110 0.0063412195 0.0132620000 0.0004020000 0.0022720000 0.0000040000 0.0000030000 0.0014730000 47260573 96830484 509673472 3.8848099709 3.9202940464 3.3550398350 3044 1311867271.9994390011 0.1582976133 0.1049626032 0.2224405110 0.0063402739 0.0183850000 0.0004990000 0.0039260000 0.0000010000 0.0000100000 0.0013230000 47264245 96830484 509673472 3.8860533237 3.9190697670 3.3604958057 3045 1311867272.0337600708 0.1566656083 0.1049795828 0.2224405110 0.0063396355 0.0153650000 0.0004060000 0.0037340000 0.0000040000 0.0000040000 0.0022120000 47267973 96830484 509673472 3.8879590034 3.9199247360 3.3658161163 3046 1311867272.0626399517 0.1564298123 0.1049964739 0.2224405110 0.0063396779 0.0132750000 0.0004090000 0.0026320000 0.0000000000 0.0000040000 0.0011640000 47271589 96830484 509673472 3.8880095482 3.9166696072 3.3699598312 3047 1311867272.0988030434 0.1568450034 0.1050134901 0.2224405110 0.0063391636 0.0143340000 0.0003970000 0.0033540000 0.0000040000 0.0000050000 0.0014820000 47275373 96830484 509673472 3.8877084255 3.9140794277 3.3749837875 3048 1311867272.1336209774 0.1559415907 0.1050301988 0.2224405110 0.0063381544 0.0139350000 0.0004080000 0.0029840000 0.0000010000 0.0000040000 0.0011670000 47279157 96830484 509673472 3.8896260262 3.9127261639 3.3796951771 3049 1311867272.1659350395 0.1579084545 0.1050475417 0.2224405110 0.0063387362 0.0148610000 0.0004150000 0.0029840000 0.0000040000 0.0000040000 0.0021990000 47282829 96830484 509673472 3.8876039982 3.9101560116 3.3833932877 3050 1311867272.1987910271 0.1578749567 0.1050648621 0.2224405110 0.0063384353 0.0133840000 0.0004070000 0.0026420000 0.0000000000 0.0000040000 0.0011860000 47286557 96830484 509673472 3.8883433342 3.9084179401 3.3870205879 3051 1311867272.2319760323 0.1578335613 0.1050821577 0.2224405110 0.0063381833 0.0139130000 0.0004030000 0.0029820000 0.0000040000 0.0000040000 0.0014820000 47290229 96830484 509673472 3.8894519806 3.9057586193 3.3912997246 3052 1311867272.2655110359 0.1578189731 0.1050994371 0.2224405110 0.0063410014 0.0193370000 0.0005080000 0.0046560000 0.0000010000 0.0000100000 0.0013290000 47293957 96830484 509673472 3.8905041218 3.9065806866 3.3947856426 3053 1311867272.2982270718 0.1591374874 0.1051171371 0.2224405110 0.0063401349 0.0143220000 0.0004110000 0.0022900000 0.0000040000 0.0000040000 0.0021950000 47297685 96830484 509673472 3.8898189068 3.9061660767 3.3976368904 3054 1311867272.3315019608 0.1580529511 0.1051344703 0.2224405110 0.0063448254 0.0182430000 0.0005030000 0.0035820000 0.0000010000 0.0000080000 0.0013190000 47301357 96830484 509673472 3.8909034729 3.9033420086 3.4005138874 3055 1311867272.3696749210 0.1586310118 0.1051519815 0.2224405110 0.0063456947 0.0155380000 0.0004120000 0.0044320000 0.0000040000 0.0000030000 0.0014910000 47305197 96830484 509673472 3.8906641006 3.9024417400 3.4036717415 3056 1311867272.3987050056 0.1589674205 0.1051695913 0.2224405110 0.0063451411 0.0150860000 0.0004080000 0.0043870000 0.0000000000 0.0000040000 0.0011620000 47308757 96830484 509673472 3.8906841278 3.9011332989 3.4071440697 3057 1311867272.4335730076 0.1539136022 0.1051855363 0.2224405110 0.0063447413 0.0169880000 0.0004090000 0.0040470000 0.0000040000 0.0000040000 0.0028040000 47312541 96830484 509673472 3.8964633942 3.8986532688 3.4101171494 3058 1311867272.4686141014 0.1518272758 0.1052007887 0.2224405110 0.0063441961 0.0133710000 0.0004550000 0.0022720000 0.0000010000 0.0000160000 0.0011710000 47316269 96830484 509673472 3.8990962505 3.8963279724 3.4135804176 3059 1311867272.5011420250 0.1512356550 0.1052158377 0.2224405110 0.0063433004 0.0137580000 0.0004030000 0.0022820000 0.0000040000 0.0000040000 0.0014730000 47319941 96830484 509673472 3.9000151157 3.8952209949 3.4169869423 3060 1311867272.5325479507 0.1483762860 0.1052299424 0.2224405110 0.0063426327 0.0137630000 0.0004050000 0.0026530000 0.0000000000 0.0000040000 0.0011490000 47323613 96830484 509673472 3.9034819603 3.8932766914 3.4198250771 3061 1311867272.5676600933 0.1465875953 0.1052434535 0.2224405110 0.0063420124 0.0146560000 0.0004100000 0.0026460000 0.0000040000 0.0000030000 0.0022000000 47327341 96830484 509673472 3.9060113430 3.8928024769 3.4226436615 3062 1311867272.5996229649 0.1483800858 0.1052575413 0.2224405110 0.0063411382 0.0142170000 0.0004060000 0.0033300000 0.0000010000 0.0000050000 0.0011580000 47331069 96830484 509673472 3.9045298100 3.8934273720 3.4252307415 3063 1311867272.6315360069 0.1475836635 0.1052713598 0.2224405110 0.0063405062 0.0142250000 0.0004040000 0.0029840000 0.0000040000 0.0000030000 0.0014690000 47334685 96830484 509673472 3.9054031372 3.8921713829 3.4273900986 3064 1311867272.6661291122 0.1482559741 0.1052853887 0.2224405110 0.0063396348 0.0186710000 0.0004940000 0.0031990000 0.0000010000 0.0000100000 0.0013020000 47338413 96830484 509673472 3.9048633575 3.8927643299 3.4298555851 3065 1311867272.6987280846 0.1475367397 0.1052991738 0.2224405110 0.0063388228 0.0148740000 0.0004090000 0.0026570000 0.0000050000 0.0000040000 0.0021910000 47342141 96830484 509673472 3.9063739777 3.8922734261 3.4328269958 3066 1311867272.7307109833 0.1450803578 0.1053121488 0.2224405110 0.0063382358 0.0155260000 0.0004120000 0.0044170000 0.0000010000 0.0000040000 0.0011520000 47345813 96830484 509673472 3.9094064236 3.8892986774 3.4355182648 3067 1311867272.7686150074 0.1460406184 0.1053254283 0.2224405110 0.0063404508 0.0143580000 0.0004030000 0.0029940000 0.0000050000 0.0000040000 0.0014710000 47349597 96830484 509673472 3.9092919827 3.8904485703 3.4380321503 3068 1311867272.7996079922 0.1478241086 0.1053392806 0.2224405110 0.0063395211 0.0134590000 0.0004080000 0.0022760000 0.0000000000 0.0000040000 0.0011660000 47353213 96830484 509673472 3.9085896015 3.8900136948 3.4409050941 3069 1311867272.8310160637 0.1478346288 0.1053531272 0.2224405110 0.0063390913 0.0205160000 0.0005270000 0.0039390000 0.0000080000 0.0000090000 0.0023590000 47356885 96830484 509673472 3.9095952511 3.8907608986 3.4435813427 3070 1311867272.8674850464 0.1486095041 0.1053672173 0.2224405110 0.0063384896 0.0161500000 0.0004170000 0.0044230000 0.0000010000 0.0000050000 0.0011500000 47360725 96830484 509673472 3.9103548527 3.8902325630 3.4461565018 3071 1311867272.8996291161 0.1448714286 0.1053800809 0.2224405110 0.0063383965 0.0163020000 0.0004250000 0.0044010000 0.0000040000 0.0000050000 0.0014690000 47364341 96830484 509673472 3.9161965847 3.8898611069 3.4484570026 3072 1311867272.9314110279 0.1456018090 0.1053931739 0.2224405110 0.0063382218 0.0140770000 0.0004070000 0.0026320000 0.0000010000 0.0000050000 0.0011510000 47368013 96830484 509673472 3.9173178673 3.8888936043 3.4505538940 3073 1311867272.9664669037 0.1465597749 0.1054065701 0.2224405110 0.0063373491 0.0168630000 0.0003990000 0.0043950000 0.0000040000 0.0000040000 0.0021810000 47371797 96830484 509673472 3.9177038670 3.8900375366 3.4519510269 3074 1311867272.9987599850 0.1468854249 0.1054200636 0.2224405110 0.0063367245 0.0139930000 0.0004040000 0.0033230000 0.0000000000 0.0000040000 0.0011720000 47375469 96830484 509673472 3.9188301563 3.8896038532 3.4535326958 3075 1311867273.0328490734 0.1452391297 0.1054330129 0.2224405110 0.0063358588 0.0140210000 0.0004040000 0.0029620000 0.0000030000 0.0000040000 0.0014760000 47379253 96830484 509673472 3.9222579002 3.8884592056 3.4547796249 3076 1311867273.0662739277 0.1460972130 0.1054462327 0.2224405110 0.0063348631 0.0185550000 0.0005020000 0.0038900000 0.0000010000 0.0000080000 0.0013080000 47382925 96830484 509673472 3.9230096340 3.8884038925 3.4561657906 3077 1311867273.0999150276 0.1473410726 0.1054598482 0.2224405110 0.0063339443 0.0161550000 0.0004120000 0.0042780000 0.0000040000 0.0000050000 0.0021780000 47386597 96830484 509673472 3.9235281944 3.8903677464 3.4575114250 3078 1311867273.1310710907 0.1469310075 0.1054733216 0.2224405110 0.0063330857 0.0130240000 0.0004050000 0.0022670000 0.0000000000 0.0000040000 0.0011610000 47390269 96830484 509673472 3.9250900745 3.8909983635 3.4584178925 3079 1311867273.1665740013 0.1453276128 0.1054862655 0.2224405110 0.0063323388 0.0140500000 0.0004040000 0.0029910000 0.0000030000 0.0000030000 0.0014700000 47394053 96830484 509673472 3.9273631573 3.8917202950 3.4591503143 3080 1311867273.1997520924 0.1438503861 0.1054987214 0.2224405110 0.0063314203 0.0140130000 0.0004030000 0.0033260000 0.0000000000 0.0000040000 0.0011530000 47397725 96830484 509673472 3.9302110672 3.8921940327 3.4609963894 3081 1311867273.2331819534 0.1438867152 0.1055111810 0.2224405110 0.0063311944 0.0161560000 0.0004070000 0.0043420000 0.0000030000 0.0000040000 0.0021610000 47401509 96830484 509673472 3.9300279617 3.8895990849 3.4622356892 3082 1311867273.2668380737 0.1410900205 0.1055227250 0.2224405110 0.0063317822 0.0148140000 0.0003970000 0.0043600000 0.0000000000 0.0000040000 0.0011530000 47405181 96830484 509673472 3.9334545135 3.8886466026 3.4638640881 3083 1311867273.2985589504 0.1405826211 0.1055340970 0.2224405110 0.0063308554 0.0318810000 0.0005530000 0.0026680000 0.0000340000 0.0000280000 0.0020100000 47408909 96830484 509673472 3.9353356361 3.8900704384 3.4661738873 3084 1311867273.3308010101 0.1404279470 0.1055454115 0.2224405110 0.0063309596 0.0166540000 0.0004390000 0.0044620000 0.0000010000 0.0000060000 0.0011850000 47412525 96830484 509673472 3.9358136654 3.8896453381 3.4681036472 3085 1311867273.3663508892 0.1406795979 0.1055568002 0.2224405110 0.0063299918 0.0201510000 0.0005120000 0.0042730000 0.0000070000 0.0000080000 0.0023820000 47416309 96830484 509673472 3.9359438419 3.8894021511 3.4700155258 3086 1311867273.3992459774 0.1417699754 0.1055685349 0.2224405110 0.0063300132 0.0140650000 0.0004080000 0.0029820000 0.0000000000 0.0000040000 0.0011690000 47419981 96830484 509673472 3.9358861446 3.8901715279 3.4731714725 3087 1311867273.4308409691 0.1401223540 0.1055797282 0.2224405110 0.0063295724 0.0143400000 0.0004090000 0.0032220000 0.0000030000 0.0000040000 0.0014690000 47423709 96830484 509673472 3.9383428097 3.8915622234 3.4762804508 3088 1311867273.4663250446 0.1373963505 0.1055900315 0.2224405110 0.0063294658 0.0232950000 0.0005170000 0.0046870000 0.0000010000 0.0000110000 0.0014440000 47427437 96830484 509673472 3.9425313473 3.8903100491 3.4792230129 3089 1311867273.4997849464 0.1399033219 0.1056011398 0.2224405110 0.0063290219 0.0145080000 0.0004200000 0.0023130000 0.0000060000 0.0000050000 0.0021700000 47431109 96830484 509673472 3.9399971962 3.8907630444 3.4823260307 3090 1311867273.5318419933 0.1378520280 0.1056115769 0.2224405110 0.0063292828 0.0178750000 0.0005050000 0.0028590000 0.0000010000 0.0000080000 0.0012870000 47434837 96830484 509673472 3.9425692558 3.8903977871 3.4859104156 3091 1311867273.5687909126 0.1374630928 0.1056218815 0.2224405110 0.0063289098 0.0155110000 0.0004710000 0.0034590000 0.0000040000 0.0000030000 0.0014680000 47438677 96830484 509673472 3.9437103271 3.8923540115 3.4890697002 3092 1311867273.6000390053 0.1381115466 0.1056323892 0.2224405110 0.0063285547 0.0137200000 0.0004760000 0.0025580000 0.0000010000 0.0000040000 0.0011340000 47442237 96830484 509673472 3.9428346157 3.8893575668 3.4921681881 3093 1311867273.6349599361 0.1385933757 0.1056430458 0.2224405110 0.0063278585 0.0145950000 0.0004200000 0.0026700000 0.0000040000 0.0000050000 0.0021490000 47446021 96830484 509673472 3.9433965683 3.8888690472 3.4960343838 3094 1311867273.6673769951 0.1415822804 0.1056546616 0.2224405110 0.0063270259 0.0190580000 0.0005020000 0.0047010000 0.0000010000 0.0000080000 0.0012880000 47449749 96830484 509673472 3.9414231777 3.8893611431 3.5005662441 3095 1311867273.6987860203 0.1430539340 0.1056667454 0.2224405110 0.0063273119 0.0146970000 0.0004200000 0.0034030000 0.0000040000 0.0000040000 0.0014530000 47453365 96830484 509673472 3.9399478436 3.8884332180 3.5037927628 3096 1311867273.7346739769 0.1405252814 0.1056780046 0.2224405110 0.0063289415 0.0150200000 0.0004170000 0.0044590000 0.0000010000 0.0000040000 0.0011310000 47457149 96830484 509673472 3.9440388680 3.8905382156 3.5083272457 3097 1311867273.7665960789 0.1398137957 0.1056890268 0.2224405110 0.0063303225 0.0148750000 0.0004220000 0.0030360000 0.0000050000 0.0000040000 0.0021410000 47460821 96830484 509673472 3.9470391273 3.8907711506 3.5117883682 3098 1311867273.7990698814 0.1402359754 0.1057001782 0.2224405110 0.0063302288 0.0140570000 0.0004280000 0.0034180000 0.0000000000 0.0000030000 0.0011300000 47464549 96830484 509673472 3.9463641644 3.8886034489 3.5144073963 3099 1311867273.8358130455 0.1412609518 0.1057116531 0.2224405110 0.0063300773 0.0135390000 0.0004290000 0.0026830000 0.0000040000 0.0000040000 0.0014510000 47468333 96830484 509673472 3.9455869198 3.8875658512 3.5172526836 3100 1311867273.8668060303 0.1423458755 0.1057234706 0.2224405110 0.0063307011 0.0152910000 0.0004250000 0.0045030000 0.0000000000 0.0000040000 0.0011270000 47472005 96830484 509673472 3.9443159103 3.8877582550 3.5199143887 3101 1311867273.8990719318 0.1456761509 0.1057363544 0.2224405110 0.0063339191 0.0141800000 0.0004330000 0.0023340000 0.0000040000 0.0000040000 0.0021240000 47475733 96830484 509673472 3.9402484894 3.8870189190 3.5222892761 3102 1311867273.9384820461 0.1453685910 0.1057491308 0.2224405110 0.0063329609 0.0137940000 0.0004300000 0.0030680000 0.0000010000 0.0000040000 0.0011210000 47479573 96830484 509673472 3.9404356480 3.8874638081 3.5252993107 3103 1311867273.9669051170 0.1440371126 0.1057614698 0.2224405110 0.0063325474 0.0133080000 0.0004330000 0.0023350000 0.0000040000 0.0000050000 0.0014400000 47483133 96830484 509673472 3.9409992695 3.8882727623 3.5278074741 3104 1311867273.9996581078 0.1438638568 0.1057737450 0.2224405110 0.0063315487 0.0151600000 0.0004300000 0.0044930000 0.0000000000 0.0000040000 0.0011210000 47486861 96830484 509673472 3.9397859573 3.8871245384 3.5305328369 3105 1311867274.0348489285 0.1421973705 0.1057854757 0.2224405110 0.0063308773 0.0201280000 0.0005240000 0.0040810000 0.0000110000 0.0000100000 0.0023060000 47490533 96830484 509673472 3.9407420158 3.8883700371 3.5343799591 3106 1311867274.0670020580 0.1390336454 0.1057961802 0.2224405110 0.0063331523 0.0146270000 0.0004350000 0.0038060000 0.0000000000 0.0000040000 0.0011220000 47494261 96830484 509673472 3.9428348541 3.8871691227 3.5381333828 3107 1311867274.1025679111 0.1380801201 0.1058065709 0.2224405110 0.0063331506 0.0144730000 0.0004420000 0.0030810000 0.0000050000 0.0000040000 0.0014390000 47498045 96830484 509673472 3.9418187141 3.8852593899 3.5419197083 3108 1311867274.1350569725 0.1358342320 0.1058162323 0.2224405110 0.0063322613 0.0138760000 0.0004330000 0.0027350000 0.0000000000 0.0000040000 0.0011150000 47501773 96830484 509673472 3.9438908100 3.8849112988 3.5469131470 3109 1311867274.1667969227 0.1339557320 0.1058252833 0.2224405110 0.0063319250 0.0150580000 0.0004380000 0.0030790000 0.0000030000 0.0000030000 0.0021220000 47505389 96830484 509673472 3.9441621304 3.8836348057 3.5504181385 3110 1311867274.2008550167 0.1308171451 0.1058333192 0.2224405110 0.0063374668 0.0161380000 0.0004800000 0.0045070000 0.0000000000 0.0000040000 0.0011150000 47509061 96830484 509673472 3.9449739456 3.8814365864 3.5541851521 3111 1311867274.2389180660 0.1323759407 0.1058418511 0.2224405110 0.0063383040 0.0144890000 0.0004840000 0.0030530000 0.0000040000 0.0000040000 0.0014420000 47512957 96830484 509673472 3.9411232471 3.8797702789 3.5586609840 3112 1311867274.2668540478 0.1348515153 0.1058511730 0.2224405110 0.0063375900 0.0163830000 0.0004830000 0.0024500000 0.0000010000 0.0000080000 0.0012090000 47516517 96830484 509673472 3.9383163452 3.8808381557 3.5636413097 3113 1311867274.3018939495 0.1332345456 0.1058599694 0.2224405110 0.0063381177 0.0156810000 0.0004380000 0.0037770000 0.0000040000 0.0000040000 0.0021200000 47520245 96830484 509673472 3.9378578663 3.8788547516 3.5676922798 3114 1311867274.3358139992 0.1327730268 0.1058686120 0.2224405110 0.0063387306 0.0136680000 0.0004320000 0.0026870000 0.0000000000 0.0000040000 0.0011150000 47523973 96830484 509673472 3.9368119240 3.8770806789 3.5718123913 3115 1311867274.3679759502 0.1320768595 0.1058770256 0.2224405110 0.0063379181 0.0156530000 0.0004350000 0.0044830000 0.0000040000 0.0000030000 0.0014130000 47527701 96830484 509673472 3.9365775585 3.8768775463 3.5763757229 3116 1311867274.4007549286 0.1340695918 0.1058860733 0.2224405110 0.0063371811 0.0187690000 0.0005220000 0.0032740000 0.0000010000 0.0000110000 0.0012640000 47531317 96830484 509673472 3.9329829216 3.8764178753 3.5803356171 3117 1311867274.4357678890 0.1342255771 0.1058951652 0.2224405110 0.0063394401 0.0155110000 0.0004370000 0.0034080000 0.0000050000 0.0000050000 0.0020840000 47535101 96830484 509673472 3.9317951202 3.8746082783 3.5845177174 3118 1311867274.4689209461 0.1361606866 0.1059048719 0.2224405110 0.0063412119 0.0145640000 0.0004320000 0.0034020000 0.0000010000 0.0000040000 0.0011180000 47538829 96830484 509673472 3.9284865856 3.8744013309 3.5881812572 3119 1311867274.4997699261 0.1342672855 0.1059139653 0.2224405110 0.0063404857 0.0157840000 0.0004330000 0.0044570000 0.0000040000 0.0000040000 0.0014170000 47542389 96830484 509673472 3.9298493862 3.8721320629 3.5919368267 3120 1311867274.5345981121 0.1355646104 0.1059234687 0.2224405110 0.0063402739 0.0182010000 0.0005200000 0.0036050000 0.0000010000 0.0000080000 0.0012590000 47546117 96830484 509673472 3.9270646572 3.8703403473 3.5952217579 3121 1311867274.5686841011 0.1361682266 0.1059331595 0.2224405110 0.0063394450 0.0150290000 0.0004340000 0.0026940000 0.0000040000 0.0000040000 0.0020640000 47549789 96830484 509673472 3.9255843163 3.8680481911 3.5994112492 3122 1311867274.6001191139 0.1363908798 0.1059429153 0.2224405110 0.0063393699 0.0143600000 0.0004320000 0.0030450000 0.0000000000 0.0000040000 0.0011070000 47553461 96830484 509673472 3.9252099991 3.8689105511 3.6022639275 3123 1311867274.6349270344 0.1361315250 0.1059525818 0.2224405110 0.0063397587 0.0139220000 0.0004330000 0.0027010000 0.0000040000 0.0000040000 0.0014230000 47557245 96830484 509673472 3.9238564968 3.8661365509 3.6051654816 3124 1311867274.6665649414 0.1369854361 0.1059625155 0.2224405110 0.0063411691 0.0138590000 0.0004310000 0.0030480000 0.0000000000 0.0000040000 0.0011180000 47560861 96830484 509673472 3.9229123592 3.8654003143 3.6086738110 3125 1311867274.6988699436 0.1379372180 0.1059727474 0.2224405110 0.0063404472 0.0147810000 0.0004240000 0.0026900000 0.0000040000 0.0000040000 0.0020850000 47564589 96830484 509673472 3.9211368561 3.8662846088 3.6116771698 3126 1311867274.7355759144 0.1367123127 0.1059825810 0.2224405110 0.0063437970 0.0183790000 0.0005180000 0.0029030000 0.0000010000 0.0000100000 0.0012440000 47568317 96830484 509673472 3.9210491180 3.8646624088 3.6146254539 3127 1311867274.7669000626 0.1375691295 0.1059926822 0.2224405110 0.0063429063 0.0159650000 0.0004180000 0.0044980000 0.0000040000 0.0000030000 0.0014090000 47571989 96830484 509673472 3.9195468426 3.8635354042 3.6183738708 3128 1311867274.8040020466 0.1379237920 0.1060028903 0.2224405110 0.0063425988 0.0141730000 0.0004100000 0.0030480000 0.0000000000 0.0000040000 0.0011100000 47575829 96830484 509673472 3.9177060127 3.8640437126 3.6213655472 3129 1311867274.8350889683 0.1385233402 0.1060132836 0.2224405110 0.0063425739 0.0145430000 0.0004100000 0.0026850000 0.0000050000 0.0000040000 0.0020640000 47579501 96830484 509673472 3.9162106514 3.8633809090 3.6248936653 3130 1311867274.8671360016 0.1391632408 0.1060238746 0.2224405110 0.0063417818 0.0150470000 0.0004100000 0.0041220000 0.0000010000 0.0000040000 0.0011000000 47583173 96830484 509673472 3.9143862724 3.8633859158 3.6284229755 3131 1311867274.9044289589 0.1398700178 0.1060346846 0.2224405110 0.0063408128 0.0142130000 0.0004090000 0.0030410000 0.0000040000 0.0000040000 0.0014080000 47586957 96830484 509673472 3.9128241539 3.8637638092 3.6323573589 3132 1311867274.9350550175 0.1405578703 0.1060457074 0.2224405110 0.0063403212 0.0141010000 0.0004030000 0.0032810000 0.0000010000 0.0000040000 0.0010920000 47590629 96830484 509673472 3.9113500118 3.8646903038 3.6361644268 3133 1311867274.9666490555 0.1388608217 0.1060561814 0.2224405110 0.0063397104 0.0194620000 0.0005050000 0.0032740000 0.0000100000 0.0000100000 0.0022340000 47594245 96830484 509673472 3.9122471809 3.8633980751 3.6396458149 3134 1311867275.0030829906 0.1404202878 0.1060671463 0.2224405110 0.0063402692 0.0139290000 0.0004170000 0.0027000000 0.0000000000 0.0000050000 0.0011130000 47598085 96830484 509673472 3.9092869759 3.8612530231 3.6442098618 3135 1311867275.0368080139 0.1416501850 0.1060784966 0.2224405110 0.0063450099 0.0140640000 0.0004160000 0.0026760000 0.0000040000 0.0000040000 0.0014110000 47601757 96830484 509673472 3.9072065353 3.8633170128 3.6482086182 3136 1311867275.0664451122 0.1407888383 0.1060895649 0.2224405110 0.0063464389 0.0188490000 0.0005170000 0.0032670000 0.0000020000 0.0000100000 0.0012430000 47605373 96830484 509673472 3.9074535370 3.8624467850 3.6522035599 3137 1311867275.1023271084 0.1402966529 0.1061004693 0.2224405110 0.0063465668 0.0148130000 0.0004220000 0.0026970000 0.0000050000 0.0000040000 0.0020590000 47609157 96830484 509673472 3.9064872265 3.8599362373 3.6561620235 3138 1311867275.1351230145 0.1409336478 0.1061115698 0.2224405110 0.0063458572 0.0196410000 0.0005070000 0.0047380000 0.0000010000 0.0000080000 0.0012310000 47612829 96830484 509673472 3.9049847126 3.8592264652 3.6600270271 3139 1311867275.1667180061 0.1411755979 0.1061227402 0.2224405110 0.0063448686 0.0136320000 0.0004220000 0.0023530000 0.0000040000 0.0000040000 0.0014100000 47616501 96830484 509673472 3.9041664600 3.8588271141 3.6640996933 3140 1311867275.2041749954 0.1421959549 0.1061342285 0.2224405110 0.0063452503 0.0137330000 0.0004150000 0.0026770000 0.0000000000 0.0000050000 0.0011040000 47620341 96830484 509673472 3.9015121460 3.8586163521 3.6678376198 3141 1311867275.2371780872 0.1425677389 0.1061458278 0.2224405110 0.0063444585 0.0145220000 0.0004140000 0.0026760000 0.0000040000 0.0000030000 0.0020520000 47624069 96830484 509673472 3.9005727768 3.8577952385 3.6714968681 3142 1311867275.2668180466 0.1430550367 0.1061575749 0.2224405110 0.0063459741 0.0155260000 0.0004120000 0.0044870000 0.0000010000 0.0000050000 0.0010870000 47627629 96830484 509673472 3.9002263546 3.8594071865 3.6752243042 3143 1311867275.3026800156 0.1421046555 0.1061690120 0.2224405110 0.0063473819 0.0140350000 0.0004170000 0.0026920000 0.0000040000 0.0000040000 0.0013820000 47631413 96830484 509673472 3.9000451565 3.8592708111 3.6787569523 3144 1311867275.3351879120 0.1419009417 0.1061803772 0.2224405110 0.0063471069 0.0147870000 0.0004150000 0.0037710000 0.0000010000 0.0000040000 0.0010820000 47635085 96830484 509673472 3.8994932175 3.8591170311 3.6833107471 3145 1311867275.3669109344 0.1402683556 0.1061912160 0.2224405110 0.0063490878 0.0164820000 0.0004170000 0.0044780000 0.0000030000 0.0000030000 0.0020290000 47638757 96830484 509673472 3.8999640942 3.8571789265 3.6874251366 3146 1311867275.4038369656 0.1406352520 0.1062021645 0.2224405110 0.0063494798 0.0143580000 0.0004140000 0.0030570000 0.0000000000 0.0000040000 0.0010760000 47642485 96830484 509673472 3.8985843658 3.8584291935 3.6916449070 3147 1311867275.4349598885 0.1398268938 0.1062128492 0.2224405110 0.0063499738 0.0164780000 0.0004800000 0.0045290000 0.0000030000 0.0000030000 0.0015640000 47646157 96830484 509673472 3.8985464573 3.8562459946 3.6952259541 3148 1311867275.4669399261 0.1403863579 0.1062237048 0.2224405110 0.0063490899 0.0156220000 0.0004290000 0.0045160000 0.0000010000 0.0000040000 0.0010740000 47649773 96830484 509673472 3.8962290287 3.8557336330 3.6991188526 3149 1311867275.5037291050 0.1396647245 0.1062343244 0.2224405110 0.0063484319 0.0155400000 0.0004280000 0.0034420000 0.0000040000 0.0000040000 0.0020170000 47653613 96830484 509673472 3.8953139782 3.8566660881 3.7029690742 3150 1311867275.5353329182 0.1374108791 0.1062442217 0.2224405110 0.0063491408 0.0143570000 0.0004250000 0.0030680000 0.0000000000 0.0000040000 0.0010710000 47657285 96830484 509673472 3.8966553211 3.8551721573 3.7069079876 3151 1311867275.5668909550 0.1384826899 0.1062544529 0.2224405110 0.0063512938 0.0177250000 0.0005360000 0.0025250000 0.0000080000 0.0000080000 0.0015120000 47660901 96830484 509673472 3.8937926292 3.8539800644 3.7101230621 3152 1311867275.6028299332 0.1371517628 0.1062642553 0.2224405110 0.0063517612 0.0180000000 0.0005220000 0.0024130000 0.0000010000 0.0000110000 0.0012080000 47664741 96830484 509673472 3.8934040070 3.8534576893 3.7139832973 3153 1311867275.6383280754 0.1365905702 0.1062738735 0.2224405110 0.0063517851 0.0195330000 0.0005260000 0.0033290000 0.0000100000 0.0000100000 0.0021470000 47668525 96830484 509673472 3.8922569752 3.8528425694 3.7175481319 3154 1311867275.6682209969 0.1368145347 0.1062835567 0.2224405110 0.0063512785 0.0141000000 0.0004320000 0.0023510000 0.0000000000 0.0000050000 0.0010880000 47672085 96830484 509673472 3.8902850151 3.8510785103 3.7208089828 3155 1311867275.7045888901 0.1380103230 0.1062936127 0.2224405110 0.0063503745 0.0142150000 0.0004280000 0.0023590000 0.0000040000 0.0000040000 0.0013830000 47675869 96830484 509673472 3.8872272968 3.8506815434 3.7239940166 3156 1311867275.7349820137 0.1369037777 0.1063033118 0.2224405110 0.0063495702 0.0156560000 0.0004300000 0.0044130000 0.0000000000 0.0000040000 0.0010700000 47679429 96830484 509673472 3.8872954845 3.8506271839 3.7271885872 3157 1311867275.7792279720 0.1358277202 0.1063126638 0.2224405110 0.0063497370 0.0149370000 0.0004350000 0.0027120000 0.0000040000 0.0000040000 0.0019910000 47683549 96830484 509673472 3.8857102394 3.8494873047 3.7301552296 3158 1311867275.8028490543 0.1370650977 0.1063224018 0.2224405110 0.0063496498 0.0156950000 0.0004390000 0.0045030000 0.0000000000 0.0000040000 0.0010690000 47686941 96830484 509673472 3.8835625648 3.8490540981 3.7335174084 3159 1311867275.8355960846 0.1357327700 0.1063317118 0.2224405110 0.0063498301 0.0160590000 0.0004300000 0.0045140000 0.0000030000 0.0000040000 0.0013590000 47690557 96830484 509673472 3.8837311268 3.8499162197 3.7367765903 3160 1311867275.8701560497 0.1351317614 0.1063408257 0.2224405110 0.0063489264 0.0141910000 0.0004310000 0.0030690000 0.0000000000 0.0000040000 0.0010840000 47694341 96830484 509673472 3.8826432228 3.8496909142 3.7401230335 3161 1311867275.9032120705 0.1358803809 0.1063501707 0.2224405110 0.0063480731 0.0148300000 0.0004340000 0.0027170000 0.0000040000 0.0000030000 0.0019880000 47698069 96830484 509673472 3.8796548843 3.8482577801 3.7433364391 3162 1311867275.9371318817 0.1353112906 0.1063593298 0.2224405110 0.0063471521 0.0143320000 0.0004310000 0.0030720000 0.0000000000 0.0000040000 0.0010660000 47701797 96830484 509673472 3.8782689571 3.8478136063 3.7465584278 3163 1311867275.9683859348 0.1338873953 0.1063680330 0.2224405110 0.0063466239 0.0158250000 0.0004280000 0.0045260000 0.0000040000 0.0000040000 0.0013590000 47705469 96830484 509673472 3.8787949085 3.8490600586 3.7498242855 3164 1311867276.0048470497 0.1333670169 0.1063765662 0.2224405110 0.0063482011 0.0143580000 0.0004350000 0.0030780000 0.0000010000 0.0000040000 0.0010550000 47709253 96830484 509673472 3.8770980835 3.8486275673 3.7527098656 3165 1311867276.0387539864 0.1324706227 0.1063848107 0.2224405110 0.0063487084 0.0213160000 0.0005280000 0.0054350000 0.0000090000 0.0000080000 0.0021680000 47712981 96830484 509673472 3.8759489059 3.8467526436 3.7562730312 3166 1311867276.0739030838 0.1324406862 0.1063930406 0.2224405110 0.0063500158 0.0158470000 0.0004820000 0.0044290000 0.0000000000 0.0000040000 0.0010580000 47716765 96830484 509673472 3.8751924038 3.8477563858 3.7595818043 3167 1311867276.1051371098 0.1312955022 0.1064009038 0.2224405110 0.0063512236 0.0159960000 0.0004350000 0.0045520000 0.0000040000 0.0000040000 0.0013350000 47720437 96830484 509673472 3.8753652573 3.8471527100 3.7626590729 3168 1311867276.1382379532 0.1320338994 0.1064089950 0.2224405110 0.0063522526 0.0141480000 0.0004340000 0.0027240000 0.0000000000 0.0000040000 0.0010650000 47724053 96830484 509673472 3.8732805252 3.8447732925 3.7659885883 3169 1311867276.1709389687 0.1315785795 0.1064169374 0.2224405110 0.0063540567 0.0191360000 0.0005270000 0.0025550000 0.0000110000 0.0000100000 0.0021620000 47727725 96830484 509673472 3.8730399609 3.8448922634 3.7693614960 3170 1311867276.2042279243 0.1326933205 0.1064252265 0.2224405110 0.0063534619 0.0153560000 0.0004440000 0.0038440000 0.0000000000 0.0000040000 0.0010730000 47731509 96830484 509673472 3.8713486195 3.8460471630 3.7725341320 3171 1311867276.2357859612 0.1321666688 0.1064333443 0.2224405110 0.0063525494 0.0146810000 0.0004300000 0.0031050000 0.0000040000 0.0000030000 0.0013570000 47735125 96830484 509673472 3.8716549873 3.8461515903 3.7759289742 3172 1311867276.2747719288 0.1325637698 0.1064415821 0.2224405110 0.0063519573 0.0141460000 0.0004360000 0.0030990000 0.0000000000 0.0000040000 0.0010720000 47739021 96830484 509673472 3.8699781895 3.8464996815 3.7789177895 3173 1311867276.3027520180 0.1322346181 0.1064497110 0.2224405110 0.0063519932 0.0145110000 0.0004420000 0.0023630000 0.0000030000 0.0000030000 0.0019800000 47742525 96830484 509673472 3.8708622456 3.8455512524 3.7818098068 3174 1311867276.3387188911 0.1309806257 0.1064574397 0.2224405110 0.0063517353 0.0144080000 0.0004700000 0.0034520000 0.0000000000 0.0000040000 0.0010510000 47746309 96830484 509673472 3.8707818985 3.8448660374 3.7842783928 3175 1311867276.3729600906 0.1328318864 0.1064657466 0.2224405110 0.0063507782 0.0158660000 0.0004350000 0.0045640000 0.0000030000 0.0000040000 0.0013490000 47750037 96830484 509673472 3.8674440384 3.8437335491 3.7869443893 3176 1311867276.4031929970 0.1322239190 0.1064738569 0.2224405110 0.0063515074 0.0155950000 0.0004380000 0.0045670000 0.0000000000 0.0000030000 0.0010470000 47753653 96830484 509673472 3.8672530651 3.8429949284 3.7888197899 3177 1311867276.4360129833 0.1325288415 0.1064820580 0.2224405110 0.0063516708 0.0144010000 0.0004340000 0.0023690000 0.0000040000 0.0000040000 0.0019680000 47757325 96830484 509673472 3.8654439449 3.8419120312 3.7913274765 3178 1311867276.4737091064 0.1315535009 0.1064899471 0.2224405110 0.0063525822 0.0138140000 0.0004330000 0.0027350000 0.0000000000 0.0000040000 0.0010520000 47761221 96830484 509673472 3.8654992580 3.8409175873 3.7938952446 3179 1311867276.5048420429 0.1321423352 0.1064980164 0.2224405110 0.0063519527 0.0158970000 0.0004340000 0.0045560000 0.0000040000 0.0000040000 0.0013430000 47764837 96830484 509673472 3.8641519547 3.8420586586 3.7962422371 3180 1311867276.5387470722 0.1308821440 0.1065056844 0.2224405110 0.0063512030 0.0144550000 0.0004360000 0.0034710000 0.0000010000 0.0000040000 0.0010490000 47768565 96830484 509673472 3.8653445244 3.8418424129 3.7983233929 3181 1311867276.5746779442 0.1314082593 0.1065135129 0.2224405110 0.0063502990 0.0164860000 0.0004390000 0.0044530000 0.0000030000 0.0000030000 0.0019610000 47772349 96830484 509673472 3.8638310432 3.8421604633 3.8010785580 3182 1311867276.6041920185 0.1318143904 0.1065214642 0.2224405110 0.0063493552 0.0184420000 0.0005360000 0.0029800000 0.0000010000 0.0000090000 0.0011810000 47775853 96830484 509673472 3.8628656864 3.8434257507 3.8034310341 3183 1311867276.6361470222 0.1314668953 0.1065293012 0.2224405110 0.0063484400 0.0147520000 0.0004600000 0.0027610000 0.0000040000 0.0000040000 0.0013400000 47779469 96830484 509673472 3.8625698090 3.8420481682 3.8058371544 3184 1311867276.6710920334 0.1316213310 0.1065371819 0.2224405110 0.0063479665 0.0143660000 0.0004540000 0.0031160000 0.0000010000 0.0000040000 0.0010420000 47783253 96830484 509673472 3.8612239361 3.8415992260 3.8087193966 3185 1311867276.7029719353 0.1316027194 0.1065450518 0.2224405110 0.0063492139 0.0161370000 0.0004630000 0.0038760000 0.0000040000 0.0000030000 0.0019460000 47786925 96830484 509673472 3.8618290424 3.8415548801 3.8114242554 3186 1311867276.7360780239 0.1314779967 0.1065528776 0.2224405110 0.0063484361 0.0139940000 0.0004450000 0.0027460000 0.0000000000 0.0000040000 0.0010420000 47790597 96830484 509673472 3.8599674702 3.8399481773 3.8136186600 3187 1311867276.7721960545 0.1291975528 0.1065599829 0.2224405110 0.0063533341 0.0196570000 0.0005490000 0.0048350000 0.0000080000 0.0000080000 0.0014360000 47794437 96830484 509673472 3.8607382774 3.8388834000 3.8159706593 3188 1311867276.8029088974 0.1319185048 0.1065679372 0.2224405110 0.0063620902 0.0141830000 0.0004440000 0.0027290000 0.0000000000 0.0000040000 0.0010470000 47798053 96830484 509673472 3.8575890064 3.8397915363 3.8178637028 3189 1311867276.8375699520 0.1307127476 0.1065755085 0.2224405110 0.0063634972 0.0169560000 0.0004480000 0.0046010000 0.0000040000 0.0000030000 0.0019550000 47801781 96830484 509673472 3.8575155735 3.8388600349 3.8194847107 3190 1311867276.8740971088 0.1302151382 0.1065829191 0.2224405110 0.0063631710 0.0202950000 0.0005430000 0.0037450000 0.0000010000 0.0000100000 0.0013300000 47805621 96830484 509673472 3.8570613861 3.8376209736 3.8214998245 3191 1311867276.9029750824 0.1309125870 0.1065905435 0.2224405110 0.0063642482 0.0191450000 0.0005470000 0.0029720000 0.0000110000 0.0000100000 0.0014770000 47809181 96830484 509673472 3.8560843468 3.8390350342 3.8235454559 3192 1311867276.9374980927 0.1299919337 0.1065978748 0.2224405110 0.0063664898 0.0150970000 0.0004460000 0.0034890000 0.0000000000 0.0000040000 0.0010610000 47812909 96830484 509673472 3.8551878929 3.8379995823 3.8254857063 3193 1311867276.9726910591 0.1284790188 0.1066047276 0.2224405110 0.0063662412 0.0156910000 0.0004470000 0.0034950000 0.0000040000 0.0000040000 0.0019670000 47816693 96830484 509673472 3.8559892178 3.8367629051 3.8281786442 3194 1311867277.0050029755 0.1289173067 0.1066117134 0.2224405110 0.0063665927 0.0155080000 0.0004530000 0.0042310000 0.0000010000 0.0000040000 0.0010500000 47820421 96830484 509673472 3.8547139168 3.8383464813 3.8307781219 3195 1311867277.0356070995 0.1284873486 0.1066185603 0.2224405110 0.0063656056 0.0196540000 0.0005410000 0.0033530000 0.0000100000 0.0000100000 0.0014760000 47824037 96830484 509673472 3.8551001549 3.8396279812 3.8338749409 3196 1311867277.0711610317 0.1267543435 0.1066248606 0.2224405110 0.0063648342 0.0137760000 0.0004480000 0.0023880000 0.0000000000 0.0000040000 0.0010620000 47827765 96830484 509673472 3.8559753895 3.8388290405 3.8364176750 3197 1311867277.1039769650 0.1268955916 0.1066312011 0.2224405110 0.0063645602 0.0207610000 0.0005570000 0.0048700000 0.0000080000 0.0000090000 0.0021450000 47831493 96830484 509673472 3.8549509048 3.8371186256 3.8396432400 3198 1311867277.1350269318 0.1262649596 0.1066373405 0.2224405110 0.0063651664 0.0146310000 0.0004500000 0.0035140000 0.0000010000 0.0000040000 0.0010530000 47835053 96830484 509673472 3.8556668758 3.8386681080 3.8428134918 3199 1311867277.1708490849 0.1259560585 0.1066433795 0.2224405110 0.0063649832 0.0141730000 0.0004490000 0.0026410000 0.0000040000 0.0000040000 0.0013370000 47838837 96830484 509673472 3.8552253246 3.8401176929 3.8460295200 3200 1311867277.2029759884 0.1252977699 0.1066492090 0.2224405110 0.0063644993 0.0149890000 0.0004500000 0.0038780000 0.0000010000 0.0000040000 0.0010380000 47842565 96830484 509673472 3.8551714420 3.8394522667 3.8490476608 3201 1311867277.2351000309 0.1249877736 0.1066549380 0.2224405110 0.0063637923 0.0199910000 0.0006010000 0.0035020000 0.0000090000 0.0000080000 0.0020870000 47846237 96830484 509673472 3.8548667431 3.8377943039 3.8519411087 3202 1311867277.2733149529 0.1244975775 0.1066605103 0.2224405110 0.0063632132 0.0161310000 0.0004570000 0.0046290000 0.0000000000 0.0000040000 0.0010390000 47850133 96830484 509673472 3.8543074131 3.8385114670 3.8550131321 3203 1311867277.3063778877 0.1240455359 0.1066659381 0.2224405110 0.0063622555 0.0157980000 0.0004510000 0.0042560000 0.0000040000 0.0000040000 0.0013290000 47853805 96830484 509673472 3.8545005322 3.8391199112 3.8580372334 3204 1311867277.3396029472 0.1238719746 0.1066713082 0.2224405110 0.0063614127 0.0153390000 0.0004510000 0.0042740000 0.0000000000 0.0000040000 0.0010330000 47857533 96830484 509673472 3.8543055058 3.8401219845 3.8608491421 3205 1311867277.3773889542 0.1226589978 0.1066762966 0.2224405110 0.0063613524 0.0184430000 0.0005550000 0.0025960000 0.0000080000 0.0000080000 0.0021010000 47861317 96830484 509673472 3.8549122810 3.8390004635 3.8637700081 3206 1311867277.4055531025 0.1250614822 0.1066820312 0.2224405110 0.0063605223 0.0138470000 0.0004530000 0.0024310000 0.0000010000 0.0000050000 0.0010280000 47864821 96830484 509673472 3.8520059586 3.8381700516 3.8666610718 3207 1311867277.4425079823 0.1257344484 0.1066879721 0.2224405110 0.0063606438 0.0150340000 0.0004510000 0.0031500000 0.0000030000 0.0000030000 0.0013310000 47868605 96830484 509673472 3.8504319191 3.8394727707 3.8695671558 3208 1311867277.4723749161 0.1260248423 0.1066939998 0.2224405110 0.0063680928 0.0153130000 0.0004490000 0.0038910000 0.0000010000 0.0000040000 0.0010390000 47872221 96830484 509673472 3.8513960838 3.8415229321 3.8726253510 3209 1311867277.5057780743 0.1247357056 0.1066996220 0.2224405110 0.0063709148 0.0154620000 0.0004520000 0.0031430000 0.0000040000 0.0000040000 0.0019120000 47875837 96830484 509673472 3.8510961533 3.8402678967 3.8751187325 3210 1311867277.5401940346 0.1240965202 0.1067050416 0.2224405110 0.0063771131 0.0144070000 0.0004460000 0.0031530000 0.0000000000 0.0000040000 0.0010360000 47879621 96830484 509673472 3.8501598835 3.8381054401 3.8779203892 3211 1311867277.5715351105 0.1243354604 0.1067105323 0.2224405110 0.0063805128 0.0151720000 0.0004520000 0.0034900000 0.0000040000 0.0000030000 0.0013140000 47883293 96830484 509673472 3.8502357006 3.8389334679 3.8801236153 3212 1311867277.6027710438 0.1242969260 0.1067160075 0.2224405110 0.0063800371 0.0148710000 0.0004480000 0.0035100000 0.0000010000 0.0000040000 0.0010320000 47886909 96830484 509673472 3.8506691456 3.8386704922 3.8825371265 3213 1311867277.6416130066 0.1235731915 0.1067212540 0.2224405110 0.0063824290 0.0189280000 0.0005370000 0.0033170000 0.0000080000 0.0000080000 0.0021010000 47890749 96830484 509673472 3.8503992558 3.8357903957 3.8845586777 3214 1311867277.6713008881 0.1237977445 0.1067265672 0.2224405110 0.0063818762 0.0150710000 0.0004490000 0.0034950000 0.0000010000 0.0000050000 0.0010300000 47894421 96830484 509673472 3.8505778313 3.8353042603 3.8868646622 3215 1311867277.7063589096 0.1284623742 0.1067333279 0.2224405110 0.0063848221 0.0144560000 0.0004460000 0.0023900000 0.0000040000 0.0000050000 0.0013380000 47898093 96830484 509673472 3.8450655937 3.8387880325 3.8888962269 3216 1311867277.7401409149 0.1277388483 0.1067398595 0.2224405110 0.0063841113 0.0138230000 0.0004450000 0.0024050000 0.0000010000 0.0000040000 0.0010280000 47901821 96830484 509673472 3.8457179070 3.8395876884 3.8915407658 3217 1311867277.7720079422 0.1276425868 0.1067463571 0.2224405110 0.0063831390 0.0163180000 0.0004560000 0.0042370000 0.0000040000 0.0000040000 0.0019020000 47905493 96830484 509673472 3.8459663391 3.8392217159 3.8944036961 3218 1311867277.8036880493 0.1271680593 0.1067527032 0.2224405110 0.0063826927 0.0141720000 0.0004540000 0.0027660000 0.0000010000 0.0000050000 0.0010350000 47909165 96830484 509673472 3.8468947411 3.8397183418 3.8976137638 3219 1311867277.8400499821 0.1263644546 0.1067587957 0.2224405110 0.0063817362 0.0157330000 0.0004540000 0.0027770000 0.0000050000 0.0000040000 0.0019380000 47912949 96830484 509673472 3.8482646942 3.8399925232 3.9009928703 3220 1311867277.8711171150 0.1264460683 0.1067649097 0.2224405110 0.0063819672 0.0157780000 0.0004910000 0.0046210000 0.0000000000 0.0000040000 0.0010240000 47916621 96830484 509673472 3.8478827477 3.8376407623 3.9045479298 3221 1311867277.9031610489 0.1266607493 0.1067710866 0.2224405110 0.0063810183 0.0162360000 0.0004450000 0.0038720000 0.0000040000 0.0000040000 0.0019110000 47920293 96830484 509673472 3.8480730057 3.8372521400 3.9078423977 3222 1311867277.9393019676 0.1268564016 0.1067773204 0.2224405110 0.0063817737 0.0139650000 0.0004440000 0.0027790000 0.0000010000 0.0000040000 0.0010270000 47924077 96830484 509673472 3.8489854336 3.8388469219 3.9118046761 3223 1311867277.9714229107 0.1273308843 0.1067836976 0.2224405110 0.0063826944 0.0151480000 0.0004460000 0.0035200000 0.0000040000 0.0000040000 0.0013160000 47927749 96830484 509673472 3.8488485813 3.8381977081 3.9150500298 3224 1311867278.0041360855 0.1271046847 0.1067900006 0.2224405110 0.0063818156 0.0140330000 0.0004420000 0.0027630000 0.0000010000 0.0000040000 0.0010360000 47931421 96830484 509673472 3.8499777317 3.8366122246 3.9184277058 3225 1311867278.0394210815 0.1276700795 0.1067964751 0.2224405110 0.0063822457 0.0166860000 0.0004470000 0.0046110000 0.0000030000 0.0000030000 0.0019080000 47935149 96830484 509673472 3.8503158092 3.8359858990 3.9216823578 3226 1311867278.0712630749 0.1281844527 0.1068031049 0.2224405110 0.0063820117 0.0196890000 0.0005450000 0.0048390000 0.0000010000 0.0000080000 0.0011820000 47938821 96830484 509673472 3.8509862423 3.8372423649 3.9251310825 3227 1311867278.1056289673 0.1290174127 0.1068099888 0.2224405110 0.0063810922 0.0148390000 0.0004560000 0.0031160000 0.0000040000 0.0000040000 0.0013230000 47942605 96830484 509673472 3.8509719372 3.8375890255 3.9286282063 3228 1311867278.1391980648 0.1284704804 0.1068166990 0.2224405110 0.0063801680 0.0136670000 0.0004420000 0.0023740000 0.0000010000 0.0000040000 0.0010250000 47946277 96830484 509673472 3.8522784710 3.8363311291 3.9323658943 3229 1311867278.1710369587 0.1284189522 0.1068233891 0.2224405110 0.0063792812 0.0150440000 0.0004520000 0.0027320000 0.0000030000 0.0000040000 0.0019180000 47949949 96830484 509673472 3.8531310558 3.8369896412 3.9363923073 3230 1311867278.2038609982 0.1283321679 0.1068300482 0.2224405110 0.0063804814 0.0147880000 0.0004520000 0.0034550000 0.0000000000 0.0000040000 0.0010390000 47953677 96830484 509673472 3.8544740677 3.8379495144 3.9399583340 3231 1311867278.2388060093 0.1283858120 0.1068367197 0.2224405110 0.0063843186 0.0144120000 0.0004470000 0.0027340000 0.0000040000 0.0000040000 0.0013130000 47957461 96830484 509673472 3.8538196087 3.8373556137 3.9433608055 3232 1311867278.2707629204 0.1284388751 0.1068434035 0.2224405110 0.0063854353 0.0188090000 0.0005360000 0.0029320000 0.0000010000 0.0000110000 0.0011820000 47961077 96830484 509673472 3.8546507359 3.8374464512 3.9467303753 3233 1311867278.3027629852 0.1272211373 0.1068497066 0.2224405110 0.0063850463 0.0162400000 0.0004430000 0.0038170000 0.0000040000 0.0000040000 0.0019270000 47964749 96830484 509673472 3.8569424152 3.8389313221 3.9500138760 3234 1311867278.3421599865 0.1274676174 0.1068560819 0.2224405110 0.0063845287 0.0186680000 0.0005760000 0.0036400000 0.0000020000 0.0000090000 0.0011770000 47968645 96830484 509673472 3.8564364910 3.8377432823 3.9531271458 3235 1311867278.3714361191 0.1276669651 0.1068625150 0.2224405110 0.0063835886 0.0164990000 0.0004440000 0.0045550000 0.0000040000 0.0000040000 0.0013260000 47972205 96830484 509673472 3.8564445972 3.8362395763 3.9561371803 3236 1311867278.4035348892 0.1272835881 0.1068688256 0.2224405110 0.0063828114 0.0152770000 0.0004420000 0.0037980000 0.0000000000 0.0000040000 0.0010550000 47975933 96830484 509673472 3.8579754829 3.8382196426 3.9594962597 3237 1311867278.4391169548 0.1264087707 0.1068748620 0.2224405110 0.0063821141 0.0170860000 0.0004470000 0.0044970000 0.0000040000 0.0000040000 0.0019570000 47979661 96830484 509673472 3.8589940071 3.8385593891 3.9624526501 3238 1311867278.4713339806 0.1250181794 0.1068804653 0.2224405110 0.0063820888 0.0185570000 0.0005380000 0.0032610000 0.0000010000 0.0000090000 0.0011950000 47983389 96830484 509673472 3.8602144718 3.8363714218 3.9650337696 3239 1311867278.5041239262 0.1239368170 0.1068857312 0.2224405110 0.0063817139 0.0164220000 0.0004410000 0.0045080000 0.0000040000 0.0000040000 0.0013270000 47987061 96830484 509673472 3.8611857891 3.8349184990 3.9678573608 3240 1311867278.5423910618 0.1230397299 0.1068907170 0.2224405110 0.0063808650 0.0140920000 0.0004320000 0.0026950000 0.0000000000 0.0000040000 0.0010650000 47990901 96830484 509673472 3.8624336720 3.8353476524 3.9711303711 3241 1311867278.5710260868 0.1222897619 0.1068954683 0.2224405110 0.0063802877 0.0155610000 0.0004240000 0.0033850000 0.0000040000 0.0000040000 0.0019700000 47994461 96830484 509673472 3.8643941879 3.8371844292 3.9743866920 3242 1311867278.6069030762 0.1222303212 0.1069001984 0.2224405110 0.0063795390 0.0157480000 0.0004220000 0.0044340000 0.0000000000 0.0000040000 0.0010480000 47998245 96830484 509673472 3.8641555309 3.8363184929 3.9775316715 3243 1311867278.6393239498 0.1226496398 0.1069050548 0.2224405110 0.0063788408 0.0150690000 0.0004210000 0.0033920000 0.0000040000 0.0000030000 0.0013300000 48001917 96830484 509673472 3.8636798859 3.8357388973 3.9808025360 3244 1311867278.6709709167 0.1230855212 0.1069100426 0.2224405110 0.0063819427 0.0181920000 0.0005130000 0.0028550000 0.0000000000 0.0000080000 0.0011910000 48005645 96830484 509673472 3.8637468815 3.8373293877 3.9841799736 3245 1311867278.7069129944 0.1204185262 0.1069142055 0.2224405110 0.0063814945 0.0152380000 0.0004380000 0.0025690000 0.0000040000 0.0000040000 0.0019610000 48009373 96830484 509673472 3.8678028584 3.8372612000 3.9875805378 3246 1311867278.7390680313 0.1208770722 0.1069185071 0.2224405110 0.0063811709 0.0152220000 0.0004220000 0.0033740000 0.0000010000 0.0000040000 0.0010470000 48013045 96830484 509673472 3.8669543266 3.8357384205 3.9905755520 3247 1311867278.7718300819 0.1215508208 0.1069230135 0.2224405110 0.0063809641 0.0144680000 0.0004240000 0.0025550000 0.0000040000 0.0000040000 0.0013320000 48016717 96830484 509673472 3.8663947582 3.8349554539 3.9935350418 3248 1311867278.8068239689 0.1211185977 0.1069273840 0.2224405110 0.0063802299 0.0152240000 0.0004200000 0.0033630000 0.0000000000 0.0000040000 0.0010580000 48020501 96830484 509673472 3.8680396080 3.8377587795 3.9967439175 3249 1311867278.8386530876 0.1201200336 0.1069314446 0.2224405110 0.0063807484 0.0154230000 0.0004190000 0.0030230000 0.0000040000 0.0000040000 0.0019680000 48024229 96830484 509673472 3.8697154522 3.8355157375 3.9996626377 3250 1311867278.8741700649 0.1202639639 0.1069355469 0.2224405110 0.0063801584 0.0188500000 0.0004700000 0.0046030000 0.0000000000 0.0000070000 0.0011150000 48027957 96830484 509673472 3.8689751625 3.8335144520 4.0024600029 3251 1311867278.9090650082 0.1210911721 0.1069399011 0.2224405110 0.0063806272 0.0145110000 0.0004220000 0.0026510000 0.0000040000 0.0000030000 0.0013330000 48031685 96830484 509673472 3.8690094948 3.8365635872 4.0057563782 3252 1311867278.9392769337 0.1207247078 0.1069441400 0.2224405110 0.0063808497 0.0159500000 0.0004180000 0.0044600000 0.0000000000 0.0000040000 0.0010430000 48035357 96830484 509673472 3.8702819347 3.8390414715 4.0086760521 3253 1311867278.9711430073 0.1204465181 0.1069482907 0.2224405110 0.0063803026 0.0205150000 0.0005110000 0.0043470000 0.0000090000 0.0000080000 0.0021180000 48039029 96830484 509673472 3.8697438240 3.8360545635 4.0113563538 3254 1311867279.0073111057 0.1194629148 0.1069521366 0.2224405110 0.0063815353 0.0181380000 0.0005220000 0.0024880000 0.0000010000 0.0000090000 0.0011740000 48042813 96830484 509673472 3.8702063560 3.8344883919 4.0142722130 3255 1311867279.0397729874 0.1178541556 0.1069554860 0.2224405110 0.0063817749 0.0159030000 0.0007710000 0.0026950000 0.0000040000 0.0000040000 0.0013170000 48046485 96830484 509673472 3.8731906414 3.8366367817 4.0175695419 3256 1311867279.0738539696 0.1186988130 0.1069590926 0.2224405110 0.0063809945 0.0146740000 0.0004800000 0.0026830000 0.0000000000 0.0000040000 0.0010550000 48050213 96830484 509673472 3.8717436790 3.8370933533 4.0205583572 3257 1311867279.1068439484 0.1186081916 0.1069626693 0.2224405110 0.0063803399 0.0158540000 0.0004300000 0.0030610000 0.0000040000 0.0000040000 0.0019550000 48053885 96830484 509673472 3.8715901375 3.8350620270 4.0233445168 3258 1311867279.1392490864 0.1183538362 0.1069661656 0.2224405110 0.0063798015 0.0154940000 0.0004390000 0.0037360000 0.0000000000 0.0000040000 0.0010440000 48057613 96830484 509673472 3.8716042042 3.8361213207 4.0263886452 3259 1311867279.1712040901 0.1169210747 0.1069692202 0.2224405110 0.0063851008 0.0192380000 0.0005210000 0.0036410000 0.0000080000 0.0000070000 0.0014460000 48061229 96830484 509673472 3.8746573925 3.8387229443 4.0292882919 3260 1311867279.2070438862 0.1172484308 0.1069723734 0.2224405110 0.0063856621 0.0153010000 0.0004340000 0.0034060000 0.0000000000 0.0000040000 0.0010390000 48065013 96830484 509673472 3.8730053902 3.8376955986 4.0321455002 3261 1311867279.2411210537 0.1173772216 0.1069755640 0.2224405110 0.0063853014 0.0168440000 0.0004310000 0.0044830000 0.0000030000 0.0000040000 0.0019410000 48068741 96830484 509673472 3.8721375465 3.8367528915 4.0349564552 3262 1311867279.2717759609 0.1156075448 0.1069782103 0.2224405110 0.0063848566 0.0200480000 0.0005290000 0.0028920000 0.0000010000 0.0000120000 0.0013210000 48072357 96830484 509673472 3.8744864464 3.8381450176 4.0381250381 3263 1311867279.3067219257 0.1161724478 0.1069810280 0.2224405110 0.0063848045 0.0152250000 0.0004430000 0.0030670000 0.0000050000 0.0000040000 0.0013360000 48076141 96830484 509673472 3.8741018772 3.8390402794 4.0408539772 3264 1311867279.3388090134 0.1159405634 0.1069837730 0.2224405110 0.0063851425 0.0146160000 0.0004360000 0.0030520000 0.0000000000 0.0000040000 0.0010450000 48079813 96830484 509673472 3.8740561008 3.8378231525 4.0438880920 3265 1311867279.3804929256 0.1148293912 0.1069861759 0.2224405110 0.0063858125 0.0159330000 0.0004440000 0.0034250000 0.0000050000 0.0000040000 0.0019160000 48083765 96830484 509673472 3.8744721413 3.8392457962 4.0468277931 3266 1311867279.4089910984 0.1142800227 0.1069884092 0.2224405110 0.0063858183 0.0148130000 0.0004390000 0.0033100000 0.0000000000 0.0000040000 0.0010390000 48087213 96830484 509673472 3.8759999275 3.8404734135 4.0498023033 3267 1311867279.4410970211 0.1151638404 0.1069909116 0.2224405110 0.0063856247 0.0148920000 0.0004450000 0.0030660000 0.0000040000 0.0000030000 0.0013210000 48090885 96830484 509673472 3.8739233017 3.8401141167 4.0525922775 3268 1311867279.4725570679 0.1138243377 0.1069930026 0.2224405110 0.0063851102 0.0148120000 0.0004480000 0.0034260000 0.0000000000 0.0000040000 0.0010370000 48094557 96830484 509673472 3.8756115437 3.8378393650 4.0556516647 3269 1311867279.5095710754 0.1142457351 0.1069952212 0.2224405110 0.0063850756 0.0165800000 0.0004430000 0.0044000000 0.0000040000 0.0000040000 0.0019020000 48098397 96830484 509673472 3.8752028942 3.8405129910 4.0586385727 3270 1311867279.5407390594 0.1140715331 0.1069973853 0.2224405110 0.0063853757 0.0148240000 0.0004370000 0.0034350000 0.0000000000 0.0000040000 0.0010200000 48101901 96830484 509673472 3.8748149872 3.8404200077 4.0612759590 3271 1311867279.5734229088 0.1150538176 0.1069998482 0.2224405110 0.0063847486 0.0160200000 0.0004440000 0.0045200000 0.0000040000 0.0000040000 0.0012930000 48105685 96830484 509673472 3.8735177517 3.8385066986 4.0639472008 3272 1311867279.6121640205 0.1137124002 0.1070018998 0.2224405110 0.0063849128 0.0157710000 0.0004330000 0.0045100000 0.0000000000 0.0000040000 0.0010100000 48109525 96830484 509673472 3.8744370937 3.8386166096 4.0665950775 3273 1311867279.6389439106 0.1134213656 0.1070038611 0.2224405110 0.0063867517 0.0162550000 0.0005070000 0.0035010000 0.0000040000 0.0000040000 0.0018870000 48113029 96830484 509673472 3.8757219315 3.8402676582 4.0691409111 3274 1311867279.6749770641 0.1126913205 0.1070055983 0.2224405110 0.0063892704 0.0198450000 0.0005860000 0.0040400000 0.0000010000 0.0000080000 0.0011730000 48116869 96830484 509673472 3.8757479191 3.8381149769 4.0713944435 3275 1311867279.7107980251 0.1127201840 0.1070073432 0.2224405110 0.0063891206 0.0150800000 0.0004520000 0.0030840000 0.0000040000 0.0000040000 0.0012860000 48120541 96830484 509673472 3.8757922649 3.8391492367 4.0741496086 3276 1311867279.7410199642 0.1129781008 0.1070091657 0.2224405110 0.0063884604 0.0144020000 0.0004460000 0.0027480000 0.0000010000 0.0000040000 0.0010060000 48124157 96830484 509673472 3.8759558201 3.8406801224 4.0767269135 3277 1311867279.7777059078 0.1119787917 0.1070106823 0.2224405110 0.0063880726 0.0153120000 0.0004460000 0.0027500000 0.0000040000 0.0000040000 0.0018630000 48127997 96830484 509673472 3.8768088818 3.8396794796 4.0794591904 3278 1311867279.8118851185 0.1125134677 0.1070123610 0.2224405110 0.0063875206 0.0139430000 0.0004460000 0.0023800000 0.0000000000 0.0000030000 0.0010060000 48131725 96830484 509673472 3.8767890930 3.8380248547 4.0824632645 3279 1311867279.8438251019 0.1110862345 0.1070136034 0.2224405110 0.0063868178 0.0149850000 0.0004500000 0.0031080000 0.0000030000 0.0000040000 0.0012830000 48135397 96830484 509673472 3.8789477348 3.8396799564 4.0854010582 3280 1311867279.8808829784 0.1101130694 0.1070145483 0.2224405110 0.0063886750 0.0156980000 0.0004620000 0.0042300000 0.0000010000 0.0000040000 0.0009990000 48139181 96830484 509673472 3.8801405430 3.8401389122 4.0883040428 3281 1311867279.9088180065 0.1102473587 0.1070155336 0.2224405110 0.0063889314 0.0168470000 0.0004510000 0.0045870000 0.0000040000 0.0000040000 0.0018510000 48142797 96830484 509673472 3.8804450035 3.8379800320 4.0910696983 3282 1311867279.9440410137 0.1105343252 0.1070166058 0.2224405110 0.0063884993 0.0206210000 0.0005380000 0.0048360000 0.0000010000 0.0000090000 0.0011480000 48146581 96830484 509673472 3.8811352253 3.8382203579 4.0944232941 3283 1311867279.9795188904 0.1099576652 0.1070175016 0.2224405110 0.0063915624 0.0151660000 0.0004540000 0.0031530000 0.0000040000 0.0000040000 0.0012790000 48150309 96830484 509673472 3.8826196194 3.8402316570 4.0974349976 3284 1311867280.0113790035 0.1090424582 0.1070181183 0.2224405110 0.0063937532 0.0161910000 0.0004650000 0.0045880000 0.0000000000 0.0000040000 0.0010010000 48153925 96830484 509673472 3.8838818073 3.8388948441 4.1003355980 3285 1311867280.0401859283 0.1100731045 0.1070190482 0.2224405110 0.0063933056 0.0154380000 0.0004540000 0.0031080000 0.0000040000 0.0000040000 0.0018450000 48157485 96830484 509673472 3.8837156296 3.8398225307 4.1036787033 3286 1311867280.0785079002 0.1092033759 0.1070197130 0.2224405110 0.0063936913 0.0146510000 0.0004540000 0.0027700000 0.0000000000 0.0000040000 0.0010020000 48161325 96830484 509673472 3.8860044479 3.8413534164 4.1070713997 3287 1311867280.1111929417 0.1085546911 0.1070201800 0.2224405110 0.0063931540 0.0155170000 0.0004490000 0.0034920000 0.0000050000 0.0000040000 0.0012770000 48164997 96830484 509673472 3.8875505924 3.8388507366 4.1099658012 3288 1311867280.1450068951 0.1100185066 0.1070210919 0.2224405110 0.0063923678 0.0160230000 0.0004450000 0.0045850000 0.0000010000 0.0000040000 0.0010000000 48168781 96830484 509673472 3.8863017559 3.8388597965 4.1130261421 3289 1311867280.1753098965 0.1106991470 0.1070222101 0.2224405110 0.0063938285 0.0155070000 0.0004530000 0.0031370000 0.0000040000 0.0000030000 0.0018240000 48172341 96830484 509673472 3.8866884708 3.8408019543 4.1160683632 3290 1311867280.2123339176 0.1104183495 0.1070232424 0.2224405110 0.0063948861 0.0195960000 0.0005470000 0.0048500000 0.0000010000 0.0000080000 0.0011260000 48176181 96830484 509673472 3.8870081902 3.8395161629 4.1186795235 3291 1311867280.2422859669 0.1100111529 0.1070241503 0.2224405110 0.0063945062 0.0151030000 0.0004690000 0.0027610000 0.0000050000 0.0000040000 0.0012610000 48179797 96830484 509673472 3.8878295422 3.8375422955 4.1216297150 3292 1311867280.2794580460 0.1107904390 0.1070252944 0.2224405110 0.0063999075 0.0147120000 0.0004550000 0.0027990000 0.0000010000 0.0000050000 0.0009730000 48183637 96830484 509673472 3.8881654739 3.8408708572 4.1245245934 3293 1311867280.3114728928 0.1106912345 0.1070264076 0.2224405110 0.0064011039 0.0199860000 0.0005510000 0.0030010000 0.0000100000 0.0000100000 0.0019630000 48187309 96830484 509673472 3.8881962299 3.8384795189 4.1270389557 3294 1311867280.3445079327 0.1115762740 0.1070277889 0.2224405110 0.0064024678 0.0147280000 0.0004570000 0.0024360000 0.0000010000 0.0000050000 0.0009760000 48190925 96830484 509673472 3.8877677917 3.8386697769 4.1299161911 3295 1311867280.3755340576 0.1123709530 0.1070294105 0.2224405110 0.0064017025 0.0153430000 0.0004600000 0.0031840000 0.0000050000 0.0000050000 0.0012290000 48194597 96830484 509673472 3.8878419399 3.8405332565 4.1327280998 3296 1311867280.4071900845 0.1124290600 0.1070310487 0.2224405110 0.0064018427 0.0187910000 0.0005480000 0.0033660000 0.0000010000 0.0000080000 0.0010790000 48198213 96830484 509673472 3.8877818584 3.8384127617 4.1351723671 3297 1311867280.4424109459 0.1121748239 0.1070326089 0.2224405110 0.0064028643 0.0150630000 0.0004600000 0.0024390000 0.0000040000 0.0000040000 0.0017510000 48201997 96830484 509673472 3.8886506557 3.8393909931 4.1378955841 3298 1311867280.4782869816 0.1115086153 0.1070339661 0.2224405110 0.0064025785 0.0156450000 0.0004590000 0.0035980000 0.0000000000 0.0000040000 0.0009460000 48205781 96830484 509673472 3.8893055916 3.8402302265 4.1404724121 3299 1311867280.5091259480 0.1119691059 0.1070354620 0.2224405110 0.0064016509 0.0206880000 0.0005560000 0.0045730000 0.0000080000 0.0000080000 0.0013490000 48209453 96830484 509673472 3.8889088631 3.8398244381 4.1430411339 3300 1311867280.5455989838 0.1114673391 0.1070368050 0.2224405110 0.0064008256 0.0165750000 0.0004620000 0.0047410000 0.0000000000 0.0000040000 0.0009450000 48213181 96830484 509673472 3.8893926144 3.8399965763 4.1456913948 3301 1311867280.5782079697 0.1119050905 0.1070382798 0.2224405110 0.0064011896 0.0154480000 0.0004660000 0.0028520000 0.0000040000 0.0000040000 0.0017270000 48216853 96830484 509673472 3.8893811703 3.8412966728 4.1483683586 3302 1311867280.6130499840 0.1119554788 0.1070397690 0.2224405110 0.0064015087 0.0158710000 0.0004590000 0.0043590000 0.0000000000 0.0000040000 0.0009360000 48220581 96830484 509673472 3.8891246319 3.8403759003 4.1507854462 3303 1311867280.6422739029 0.1116970256 0.1070411790 0.2224405110 0.0064016625 0.0164700000 0.0004640000 0.0047240000 0.0000040000 0.0000040000 0.0012090000 48224197 96830484 509673472 3.8898627758 3.8394663334 4.1532354355 3304 1311867280.6755290031 0.1112740561 0.1070424601 0.2224405110 0.0064011129 0.0160770000 0.0004610000 0.0047410000 0.0000000000 0.0000030000 0.0009330000 48227925 96830484 509673472 3.8907852173 3.8401234150 4.1557760239 3305 1311867280.7094879150 0.1118730828 0.1070439217 0.2224405110 0.0064004499 0.0169640000 0.0004640000 0.0047490000 0.0000030000 0.0000040000 0.0017160000 48231653 96830484 509673472 3.8903577328 3.8402006626 4.1580753326 3306 1311867280.7411808968 0.1121051535 0.1070454526 0.2224405110 0.0064010381 0.0142680000 0.0004570000 0.0028410000 0.0000000000 0.0000040000 0.0009380000 48235269 96830484 509673472 3.8894588947 3.8394515514 4.1604418755 3307 1311867280.7752668858 0.1126143709 0.1070471366 0.2224405110 0.0064019475 0.0196660000 0.0005640000 0.0034550000 0.0000100000 0.0000100000 0.0013210000 48238997 96830484 509673472 3.8895566463 3.8405680656 4.1626410484 3308 1311867280.8076250553 0.1119774058 0.1070486270 0.2224405110 0.0064010448 0.0155780000 0.0004640000 0.0032420000 0.0000010000 0.0000040000 0.0009330000 48242669 96830484 509673472 3.8904886246 3.8404757977 4.1650052071 3309 1311867280.8401010036 0.1120302230 0.1070501325 0.2224405110 0.0064001354 0.0204910000 0.0006150000 0.0049790000 0.0000080000 0.0000070000 0.0018350000 48246397 96830484 509673472 3.8908908367 3.8403565884 4.1675701141 3310 1311867280.8754839897 0.1121609509 0.1070516765 0.2224405110 0.0063991816 0.0305160000 0.0006620000 0.0052780000 0.0000010000 0.0000170000 0.0014560000 48250125 96830484 509673472 3.8902480602 3.8403320312 4.1697664261 3311 1311867280.9079110622 0.1114932373 0.1070530180 0.2224405110 0.0063982268 0.0171050000 0.0004710000 0.0044180000 0.0000050000 0.0000050000 0.0012120000 48253797 96830484 509673472 3.8910930157 3.8408637047 4.1721673012 3312 1311867280.9394528866 0.1120578796 0.1070545291 0.2224405110 0.0063973001 0.0161680000 0.0004560000 0.0046360000 0.0000000000 0.0000030000 0.0009180000 48257525 96830484 509673472 3.8903884888 3.8406412601 4.1747541428 3313 1311867280.9766991138 0.1109582186 0.1070557074 0.2224405110 0.0063963789 0.0170650000 0.0004620000 0.0047690000 0.0000030000 0.0000030000 0.0016820000 48261197 96830484 509673472 3.8916463852 3.8412241936 4.1773929596 3314 1311867281.0075190067 0.1114288270 0.1070570270 0.2224405110 0.0063955880 0.0163810000 0.0004590000 0.0047810000 0.0000010000 0.0000040000 0.0009060000 48264869 96830484 509673472 3.8912055492 3.8407280445 4.1798963547 3315 1311867281.0433430672 0.1107924581 0.1070581538 0.2224405110 0.0063947751 0.0148480000 0.0004730000 0.0028770000 0.0000050000 0.0000040000 0.0011880000 48268653 96830484 509673472 3.8919167519 3.8402273655 4.1824593544 3316 1311867281.0752780437 0.1107618362 0.1070592708 0.2224405110 0.0063939123 0.0197450000 0.0005550000 0.0046530000 0.0000010000 0.0000080000 0.0010400000 48272269 96830484 509673472 3.8921563625 3.8404481411 4.1850519180 3317 1311867281.1074900627 0.1105627567 0.1070603270 0.2224405110 0.0063935692 0.0161400000 0.0004980000 0.0036700000 0.0000050000 0.0000040000 0.0016420000 48275997 96830484 509673472 3.8929319382 3.8405191898 4.1877508163 3318 1311867281.1451520920 0.1112905666 0.1070616019 0.2224405110 0.0063934463 0.0207770000 0.0005550000 0.0051190000 0.0000010000 0.0000090000 0.0010250000 48279781 96830484 509673472 3.8920571804 3.8402574062 4.1901283264 3319 1311867281.1786689758 0.1100216433 0.1070624938 0.2224405110 0.0063931547 0.0151260000 0.0004680000 0.0032760000 0.0000040000 0.0000040000 0.0011620000 48283565 96830484 509673472 3.8944926262 3.8400790691 4.1924123764 3320 1311867281.2083299160 0.1099058315 0.1070633502 0.2224405110 0.0063922585 0.0164340000 0.0004700000 0.0048220000 0.0000000000 0.0000030000 0.0008850000 48287181 96830484 509673472 3.8957135677 3.8409357071 4.1947259903 3321 1311867281.2457950115 0.1088552997 0.1070638898 0.2224405110 0.0063937588 0.0168870000 0.0004670000 0.0048560000 0.0000040000 0.0000040000 0.0016290000 48290965 96830484 509673472 3.8969850540 3.8390042782 4.1969532967 3322 1311867281.2754399776 0.1094756946 0.1070646158 0.2224405110 0.0063930643 0.0198810000 0.0005780000 0.0050890000 0.0000010000 0.0000080000 0.0010130000 48294525 96830484 509673472 3.8971304893 3.8394744396 4.1992230415 3323 1311867281.3072988987 0.1096339971 0.1070653890 0.2224405110 0.0063947906 0.0216070000 0.0005660000 0.0051420000 0.0000090000 0.0000070000 0.0012740000 48298253 96830484 509673472 3.8978300095 3.8402352333 4.2017149925 3324 1311867281.3465099335 0.1087789908 0.1070659045 0.2224405110 0.0063972907 0.0152740000 0.0005220000 0.0033120000 0.0000010000 0.0000040000 0.0008730000 48302093 96830484 509673472 3.8994977474 3.8387463093 4.2041110992 3325 1311867281.3751530647 0.1089100838 0.1070664591 0.2224405110 0.0063963442 0.0167250000 0.0004790000 0.0040760000 0.0000050000 0.0000040000 0.0016090000 48305653 96830484 509673472 3.8998296261 3.8378226757 4.2062530518 3326 1311867281.4080700874 0.1091771722 0.1070670938 0.2224405110 0.0063958789 0.0166030000 0.0004760000 0.0048720000 0.0000000000 0.0000050000 0.0008630000 48309381 96830484 509673472 3.9003012180 3.8389291763 4.2086591721 3327 1311867281.4434111118 0.1083448008 0.1070674778 0.2224405110 0.0063958951 0.0169370000 0.0004960000 0.0048730000 0.0000030000 0.0000040000 0.0011020000 48313165 96830484 509673472 3.9016346931 3.8380529881 4.2108960152 3328 1311867281.4753720760 0.1093982235 0.1070681781 0.2224405110 0.0063952808 0.0155290000 0.0004760000 0.0036950000 0.0000010000 0.0000040000 0.0008580000 48316781 96830484 509673472 3.9004573822 3.8368451595 4.2130413055 3329 1311867281.5101969242 0.1089293361 0.1070687372 0.2224405110 0.0063946986 0.0205230000 0.0005730000 0.0051120000 0.0000080000 0.0000070000 0.0016750000 48320565 96830484 509673472 3.9016110897 3.8384609222 4.2153391838 3330 1311867281.5435659885 0.1080148220 0.1070690213 0.2224405110 0.0063946707 0.0153130000 0.0004820000 0.0033240000 0.0000010000 0.0000040000 0.0008510000 48324293 96830484 509673472 3.9030013084 3.8379662037 4.2175064087 3331 1311867281.5754749775 0.1078507155 0.1070692560 0.2224405110 0.0063939118 0.0163460000 0.0004790000 0.0044930000 0.0000040000 0.0000040000 0.0011040000 48327965 96830484 509673472 3.9038805962 3.8364598751 4.2196593285 3332 1311867281.6111190319 0.1077855825 0.1070694710 0.2224405110 0.0063940218 0.0167940000 0.0004900000 0.0048870000 0.0000010000 0.0000040000 0.0008710000 48331693 96830484 509673472 3.9044828415 3.8374269009 4.2218403816 3333 1311867281.6435608864 0.1081088036 0.1070697828 0.2224405110 0.0063938412 0.0165040000 0.0004800000 0.0040950000 0.0000040000 0.0000040000 0.0015760000 48335421 96830484 509673472 3.9045133591 3.8371367455 4.2237286568 3334 1311867281.6755120754 0.1070820615 0.1070697865 0.2224405110 0.0063940203 0.0220630000 0.0006540000 0.0037260000 0.0000010000 0.0000100000 0.0011100000 48339093 96830484 509673472 3.9064359665 3.8358316422 4.2255868912 3335 1311867281.7089190483 0.1068514958 0.1070697210 0.2224405110 0.0063932113 0.0155230000 0.0004830000 0.0033230000 0.0000050000 0.0000040000 0.0011370000 48342765 96830484 509673472 3.9077095985 3.8357908726 4.2275385857 3336 1311867281.7452239990 0.1073222682 0.1070697967 0.2224405110 0.0063927044 0.0160900000 0.0004740000 0.0044910000 0.0000010000 0.0000040000 0.0008600000 48346605 96830484 509673472 3.9079499245 3.8361890316 4.2292680740 3337 1311867281.7755289078 0.1075618938 0.1070699442 0.2224405110 0.0063921988 0.0187010000 0.0005620000 0.0027140000 0.0000080000 0.0000080000 0.0017310000 48350165 96830484 509673472 3.9082696438 3.8347513676 4.2307248116 3338 1311867281.8075580597 0.1072864085 0.1070700091 0.2224405110 0.0063914315 0.0145970000 0.0004910000 0.0024310000 0.0000000000 0.0000040000 0.0008650000 48353837 96830484 509673472 3.9094119072 3.8350517750 4.2321839333 3339 1311867281.8447821140 0.1070650667 0.1070700076 0.2224405110 0.0063904790 0.0173560000 0.0004850000 0.0048720000 0.0000040000 0.0000040000 0.0011410000 48357677 96830484 509673472 3.9105296135 3.8351428509 4.2336421013 3340 1311867281.8756659031 0.1068635806 0.1070699458 0.2224405110 0.0063896045 0.0168500000 0.0004820000 0.0048760000 0.0000010000 0.0000040000 0.0008540000 48361349 96830484 509673472 3.9118571281 3.8341546059 4.2350330353 3341 1311867281.9077229500 0.1067156494 0.1070698397 0.2224405110 0.0063891950 0.0159640000 0.0004780000 0.0033180000 0.0000040000 0.0000040000 0.0015850000 48365021 96830484 509673472 3.9131708145 3.8346447945 4.2366008759 3342 1311867281.9444870949 0.1068556532 0.1070697756 0.2224405110 0.0063898485 0.0150840000 0.0004780000 0.0033130000 0.0000010000 0.0000050000 0.0008560000 48368749 96830484 509673472 3.9137628078 3.8355238438 4.2379236221 3343 1311867281.9785399437 0.1057725027 0.1070693876 0.2224405110 0.0063914529 0.0164630000 0.0004690000 0.0048790000 0.0000040000 0.0000040000 0.0010990000 48372477 96830484 509673472 3.9162049294 3.8336968422 4.2391009331 3344 1311867282.0098121166 0.1056145504 0.1070689525 0.2224405110 0.0063905847 0.0148800000 0.0004750000 0.0033320000 0.0000000000 0.0000040000 0.0008610000 48376149 96830484 509673472 3.9173834324 3.8335776329 4.2405190468 3345 1311867282.0436799526 0.1062534824 0.1070687087 0.2224405110 0.0063902720 0.0222890000 0.0005650000 0.0035600000 0.0000100000 0.0000100000 0.0019050000 48379821 96830484 509673472 3.9174718857 3.8348443508 4.2420306206 3346 1311867282.0755469799 0.1056489497 0.1070682844 0.2224405110 0.0063894550 0.0153520000 0.0004760000 0.0033300000 0.0000010000 0.0000040000 0.0008520000 48383493 96830484 509673472 3.9188885689 3.8341436386 4.2434344292 3347 1311867282.1077909470 0.1055225655 0.1070678226 0.2224405110 0.0063885858 0.0205320000 0.0005710000 0.0043510000 0.0000090000 0.0000080000 0.0012570000 48387165 96830484 509673472 3.9201514721 3.8340952396 4.2450203896 3348 1311867282.1464140415 0.1051445305 0.1070672481 0.2224405110 0.0063877152 0.0167500000 0.0004790000 0.0048970000 0.0000000000 0.0000050000 0.0008410000 48391005 96830484 509673472 3.9212336540 3.8353328705 4.2468652725 3349 1311867282.1797480583 0.1048691496 0.1070665918 0.2224405110 0.0063868108 0.0173020000 0.0004740000 0.0048880000 0.0000040000 0.0000040000 0.0015490000 48394733 96830484 509673472 3.9221308231 3.8351016045 4.2486362457 3350 1311867282.2136330605 0.1048334092 0.1070659252 0.2224405110 0.0063858790 0.0164130000 0.0004740000 0.0048900000 0.0000010000 0.0000040000 0.0008320000 48398461 96830484 509673472 3.9228601456 3.8345446587 4.2504320145 3351 1311867282.2453169823 0.1046451777 0.1070652028 0.2224405110 0.0063852178 0.0161980000 0.0004680000 0.0044880000 0.0000040000 0.0000040000 0.0011060000 48402133 96830484 509673472 3.9240849018 3.8349685669 4.2522821426 3352 1311867282.2844099998 0.1040365472 0.1070642992 0.2224405110 0.0063847132 0.0146040000 0.0004730000 0.0029470000 0.0000010000 0.0000040000 0.0008400000 48405917 96830484 509673472 3.9255244732 3.8345961571 4.2538986206 3353 1311867282.3187301159 0.1036093011 0.1070632688 0.2224405110 0.0063845343 0.0153280000 0.0004700000 0.0029390000 0.0000040000 0.0000030000 0.0015250000 48409645 96830484 509673472 3.9265654087 3.8342032433 4.2555661201 3354 1311867282.3445549011 0.1035386398 0.1070622180 0.2224405110 0.0063837068 0.0146390000 0.0004700000 0.0025550000 0.0000000000 0.0000040000 0.0008420000 48413149 96830484 509673472 3.9275398254 3.8343162537 4.2571873665 3355 1311867282.3837130070 0.1040602624 0.1070613232 0.2224405110 0.0063836917 0.0166560000 0.0004710000 0.0049000000 0.0000040000 0.0000040000 0.0010960000 48416765 96830484 509673472 3.9278600216 3.8338773251 4.2589249611 3356 1311867282.4114849567 0.1034349054 0.1070602426 0.2224405110 0.0063835777 0.0165230000 0.0004620000 0.0048760000 0.0000010000 0.0000040000 0.0008260000 48420269 96830484 509673472 3.9294469357 3.8334653378 4.2606210709 3357 1311867282.4437038898 0.1031832770 0.1070590877 0.2224405110 0.0063828403 0.0172280000 0.0004720000 0.0044800000 0.0000040000 0.0000040000 0.0015260000 48423997 96830484 509673472 3.9302954674 3.8333587646 4.2623767853 3358 1311867282.4754569530 0.1032658666 0.1070579581 0.2224405110 0.0063823651 0.0158150000 0.0005210000 0.0037300000 0.0000000000 0.0000040000 0.0008330000 48427613 96830484 509673472 3.9305946827 3.8336460590 4.2639694214 3359 1311867282.5128560066 0.1035671681 0.1070569189 0.2224405110 0.0063818491 0.0150140000 0.0004710000 0.0029480000 0.0000040000 0.0000040000 0.0011030000 48431453 96830484 509673472 3.9311170578 3.8321790695 4.2655558586 3360 1311867282.5435400009 0.1035248488 0.1070558677 0.2224405110 0.0063809579 0.0151850000 0.0004650000 0.0036070000 0.0000010000 0.0000040000 0.0008220000 48435125 96830484 509673472 3.9319124222 3.8319926262 4.2670898438 3361 1311867282.5755639076 0.1034372076 0.1070547910 0.2224405110 0.0063802000 0.0151070000 0.0004780000 0.0025720000 0.0000040000 0.0000030000 0.0015170000 48438797 96830484 509673472 3.9323995113 3.8326866627 4.2685956955 3362 1311867282.6112899780 0.1033444554 0.1070536874 0.2224405110 0.0063794705 0.0163860000 0.0004730000 0.0048900000 0.0000000000 0.0000040000 0.0008330000 48442525 96830484 509673472 3.9326429367 3.8314735889 4.2698168755 3363 1311867282.6437261105 0.1033565924 0.1070525880 0.2224405110 0.0063786993 0.0152440000 0.0004650000 0.0033320000 0.0000040000 0.0000040000 0.0011000000 48446197 96830484 509673472 3.9330384731 3.8311054707 4.2710533142 3364 1311867282.6766591072 0.1034330875 0.1070515121 0.2224405110 0.0063779700 0.0163690000 0.0004670000 0.0048880000 0.0000000000 0.0000030000 0.0008240000 48449869 96830484 509673472 3.9333615303 3.8321287632 4.2720866203 3365 1311867282.7147250175 0.1036027968 0.1070504872 0.2224405110 0.0063773333 0.0213530000 0.0005690000 0.0051420000 0.0000080000 0.0000080000 0.0017040000 48453709 96830484 509673472 3.9326684475 3.8306112289 4.2727875710 3366 1311867282.7462520599 0.1033437327 0.1070493860 0.2224405110 0.0063765221 0.0155030000 0.0004660000 0.0037270000 0.0000000000 0.0000040000 0.0008300000 48457381 96830484 509673472 3.9331469536 3.8299195766 4.2735366821 3367 1311867282.7754290104 0.1039227098 0.1070484574 0.2224405110 0.0063758342 0.0150340000 0.0004660000 0.0029480000 0.0000040000 0.0000040000 0.0011000000 48460829 96830484 509673472 3.9319581985 3.8306334019 4.2741265297 3368 1311867282.8116350174 0.1035585552 0.1070474212 0.2224405110 0.0063749434 0.0149520000 0.0004870000 0.0029430000 0.0000010000 0.0000040000 0.0008290000 48464557 96830484 509673472 3.9316611290 3.8298649788 4.2749271393 3369 1311867282.8475370407 0.1035003662 0.1070463683 0.2224405110 0.0063749748 0.0211330000 0.0005730000 0.0039680000 0.0000100000 0.0000100000 0.0017110000 48468341 96830484 509673472 3.9306054115 3.8308260441 4.2760682106 3370 1311867282.8757910728 0.1028739810 0.1070451302 0.2224405110 0.0063740515 0.0146280000 0.0004790000 0.0025670000 0.0000010000 0.0000040000 0.0008250000 48471957 96830484 509673472 3.9310166836 3.8318355083 4.2774519920 3371 1311867282.9114630222 0.1024145856 0.1070437566 0.2224405110 0.0063732096 0.0153910000 0.0004690000 0.0033230000 0.0000050000 0.0000040000 0.0010880000 48475685 96830484 509673472 3.9311211109 3.8313624859 4.2788233757 3372 1311867282.9456479549 0.1022595465 0.1070423378 0.2224405110 0.0063725324 0.0157360000 0.0004670000 0.0040980000 0.0000010000 0.0000050000 0.0008240000 48479413 96830484 509673472 3.9312481880 3.8313722610 4.2805433273 3373 1311867282.9811890125 0.1020792574 0.1070408664 0.2224405110 0.0063725529 0.0153240000 0.0004840000 0.0029500000 0.0000040000 0.0000040000 0.0015080000 48483141 96830484 509673472 3.9305028915 3.8326771259 4.2818713188 3374 1311867283.0114879608 0.1022719219 0.1070394529 0.2224405110 0.0063719329 0.0157590000 0.0004690000 0.0041180000 0.0000000000 0.0000040000 0.0008110000 48486813 96830484 509673472 3.9302105904 3.8317940235 4.2833313942 3375 1311867283.0462460518 0.1025206745 0.1070381140 0.2224405110 0.0063716967 0.0156880000 0.0004680000 0.0025500000 0.0000040000 0.0000040000 0.0010740000 48490541 96830484 509673472 3.9294834137 3.8308382034 4.2844099998 3376 1311867283.0752930641 0.1026304588 0.1070368084 0.2224405110 0.0063713371 0.0166410000 0.0005100000 0.0048970000 0.0000010000 0.0000040000 0.0008140000 48494157 96830484 509673472 3.9289588928 3.8320107460 4.2855944633 3377 1311867283.1116878986 0.1012362763 0.1070350908 0.2224405110 0.0063727166 0.0171610000 0.0004630000 0.0049120000 0.0000040000 0.0000030000 0.0015040000 48497997 96830484 509673472 3.9292080402 3.8321740627 4.2865805626 3378 1311867283.1435511112 0.1015173793 0.1070334573 0.2224405110 0.0063725833 0.0164550000 0.0004720000 0.0048980000 0.0000010000 0.0000040000 0.0008080000 48501669 96830484 509673472 3.9288897514 3.8301134109 4.2872123718 3379 1311867283.1788220406 0.1020321548 0.1070319772 0.2224405110 0.0063739948 0.0166910000 0.0004670000 0.0048850000 0.0000040000 0.0000030000 0.0010630000 48505341 96830484 509673472 3.9289121628 3.8312695026 4.2880706787 3380 1311867283.2158269882 0.1023312584 0.1070305865 0.2224405110 0.0063734488 0.0166140000 0.0004670000 0.0048940000 0.0000000000 0.0000040000 0.0007990000 48509181 96830484 509673472 3.9293236732 3.8314056396 4.2888369560 3381 1311867283.2441749573 0.1025408581 0.1070292586 0.2224405110 0.0063732936 0.0197770000 0.0005620000 0.0031370000 0.0000080000 0.0000080000 0.0016580000 48512741 96830484 509673472 3.9290390015 3.8294095993 4.2893753052 3382 1311867283.2776839733 0.1027084514 0.1070279810 0.2224405110 0.0063730168 0.0160470000 0.0004840000 0.0037160000 0.0000010000 0.0000040000 0.0008150000 48516469 96830484 509673472 3.9290671349 3.8299546242 4.2904086113 3383 1311867283.3134660721 0.1020026654 0.1070264955 0.2224405110 0.0063725159 0.0210580000 0.0005590000 0.0051490000 0.0000080000 0.0000080000 0.0011870000 48520253 96830484 509673472 3.9299008846 3.8307042122 4.2912802696 3384 1311867283.3498029709 0.1020455360 0.1070250236 0.2224405110 0.0063725328 0.0170810000 0.0004760000 0.0049080000 0.0000000000 0.0000040000 0.0008260000 48524149 96830484 509673472 3.9299893379 3.8294117451 4.2922921181 3385 1311867283.3852219582 0.1025232002 0.1070236937 0.2224405110 0.0063721310 0.0157710000 0.0004680000 0.0033370000 0.0000040000 0.0000040000 0.0015200000 48527933 96830484 509673472 3.9294831753 3.8292706013 4.2933096886 3386 1311867283.4173080921 0.1027377918 0.1070224279 0.2224405110 0.0063719401 0.0164560000 0.0004670000 0.0049020000 0.0000000000 0.0000040000 0.0008140000 48531549 96830484 509673472 3.9297845364 3.8303282261 4.2943387032 3387 1311867283.4492650032 0.1025450379 0.1070211060 0.2224405110 0.0063710392 0.0144680000 0.0004660000 0.0025570000 0.0000040000 0.0000030000 0.0010850000 48535221 96830484 509673472 3.9303877354 3.8300721645 4.2950496674 3388 1311867283.4853370190 0.1026614308 0.1070198192 0.2224405110 0.0063705862 0.0164730000 0.0004650000 0.0049090000 0.0000010000 0.0000040000 0.0008150000 48539005 96830484 509673472 3.9304499626 3.8286178112 4.2956471443 3389 1311867283.5172159672 0.1029712483 0.1070186245 0.2224405110 0.0063698208 0.0170830000 0.0004780000 0.0047570000 0.0000040000 0.0000040000 0.0015130000 48542677 96830484 509673472 3.9301614761 3.8291873932 4.2961773872 3390 1311867283.5495610237 0.1031332985 0.1070174784 0.2224405110 0.0063692504 0.0141500000 0.0004630000 0.0025440000 0.0000010000 0.0000050000 0.0008230000 48546349 96830484 509673472 3.9302191734 3.8301205635 4.2968535423 3391 1311867283.5853879452 0.1029123217 0.1070162678 0.2224405110 0.0063689131 0.0156590000 0.0004710000 0.0037080000 0.0000040000 0.0000030000 0.0010790000 48550077 96830484 509673472 3.9307029247 3.8289170265 4.2973871231 3392 1311867283.6173179150 0.1030912623 0.1070151107 0.2224405110 0.0063685049 0.0164730000 0.0004750000 0.0048720000 0.0000010000 0.0000040000 0.0008220000 48553749 96830484 509673472 3.9305956364 3.8296661377 4.2981681824 3393 1311867283.6493821144 0.1027822569 0.1070138632 0.2224405110 0.0063676525 0.0210610000 0.0005690000 0.0051120000 0.0000080000 0.0000070000 0.0016970000 48557477 96830484 509673472 3.9309895039 3.8300969601 4.2987804413 3394 1311867283.6852879524 0.1028599218 0.1070126393 0.2224405110 0.0063672902 0.0152020000 0.0004710000 0.0033220000 0.0000010000 0.0000040000 0.0008240000 48561261 96830484 509673472 3.9305694103 3.8302817345 4.2993206978 3395 1311867283.7179150581 0.1022942290 0.1070112494 0.2224405110 0.0063665348 0.0160810000 0.0004780000 0.0041020000 0.0000040000 0.0000040000 0.0010800000 48564877 96830484 509673472 3.9315609932 3.8306143284 4.3002748489 3396 1311867283.7492079735 0.1026999280 0.1070099799 0.2224405110 0.0063658883 0.0147710000 0.0004660000 0.0029540000 0.0000000000 0.0000040000 0.0008170000 48568549 96830484 509673472 3.9310228825 3.8315839767 4.3009567261 3397 1311867283.7853169441 0.1026673093 0.1070087015 0.2224405110 0.0063653650 0.0172890000 0.0004930000 0.0048940000 0.0000040000 0.0000030000 0.0015080000 48572333 96830484 509673472 3.9308545589 3.8309030533 4.3015732765 3398 1311867283.8174130917 0.1030218080 0.1070075282 0.2224405110 0.0063647721 0.0158350000 0.0004720000 0.0041260000 0.0000000000 0.0000040000 0.0008190000 48575949 96830484 509673472 3.9300789833 3.8312208652 4.3021655083 3399 1311867283.8494520187 0.1026554182 0.1070062478 0.2224405110 0.0063642968 0.0149420000 0.0004690000 0.0029290000 0.0000030000 0.0000040000 0.0010910000 48579677 96830484 509673472 3.9303178787 3.8323764801 4.3027749062 3400 1311867283.8853459358 0.1026629135 0.1070049704 0.2224405110 0.0063635737 0.0167450000 0.0004890000 0.0049000000 0.0000010000 0.0000040000 0.0008150000 48583405 96830484 509673472 3.9298224449 3.8320586681 4.3032445908 3401 1311867283.9175400734 0.1024503261 0.1070036312 0.2224405110 0.0063626761 0.0170920000 0.0004680000 0.0048790000 0.0000040000 0.0000030000 0.0015000000 48587077 96830484 509673472 3.9295608997 3.8315424919 4.3035306931 3402 1311867283.9498898983 0.1024882346 0.1070023039 0.2224405110 0.0063617926 0.0164420000 0.0004600000 0.0048770000 0.0000000000 0.0000040000 0.0008140000 48590749 96830484 509673472 3.9290616512 3.8324577808 4.3039679527 3403 1311867283.9856629372 0.1025106162 0.1070009840 0.2224405110 0.0063611913 0.0167940000 0.0004670000 0.0048810000 0.0000050000 0.0000030000 0.0010740000 48594589 96830484 509673472 3.9282889366 3.8320453167 4.3042635918 3404 1311867284.0172998905 0.1026995331 0.1069997203 0.2224405110 0.0063604306 0.0137850000 0.0004670000 0.0025520000 0.0000000000 0.0000040000 0.0008140000 48598205 96830484 509673472 3.9276139736 3.8311698437 4.3044924736 3405 1311867284.0497789383 0.1030397564 0.1069985573 0.2224405110 0.0063611108 0.0168070000 0.0004710000 0.0048570000 0.0000040000 0.0000040000 0.0015110000 48601933 96830484 509673472 3.9265038967 3.8324947357 4.3048963547 3406 1311867284.0853729248 0.1025880724 0.1069972624 0.2224405110 0.0063603094 0.0161620000 0.0004610000 0.0048840000 0.0000010000 0.0000040000 0.0008180000 48605661 96830484 509673472 3.9264075756 3.8335125446 4.3053798676 3407 1311867284.1175038815 0.1028271392 0.1069960384 0.2224405110 0.0063603861 0.0168840000 0.0004790000 0.0048590000 0.0000040000 0.0000040000 0.0010830000 48609333 96830484 509673472 3.9252169132 3.8326172829 4.3055825233 3408 1311867284.1494109631 0.1020491794 0.1069945869 0.2224405110 0.0063597027 0.0213520000 0.0005740000 0.0051780000 0.0000010000 0.0000080000 0.0009370000 48613005 96830484 509673472 3.9257862568 3.8333222866 4.3062410355 3409 1311867284.1874890327 0.1020462513 0.1069931353 0.2224405110 0.0063589335 0.0194330000 0.0005710000 0.0035460000 0.0000090000 0.0000080000 0.0016450000 48616845 96830484 509673472 3.9254565239 3.8349084854 4.3069992065 3410 1311867284.2173368931 0.1023939624 0.1069917866 0.2224405110 0.0063586219 0.0165830000 0.0005560000 0.0038280000 0.0000000000 0.0000040000 0.0008230000 48620461 96830484 509673472 3.9247033596 3.8333964348 4.3073267937 3411 1311867284.2494308949 0.1028356031 0.1069905681 0.2224405110 0.0063578704 0.0153200000 0.0004730000 0.0029640000 0.0000050000 0.0000040000 0.0010850000 48624133 96830484 509673472 3.9242718220 3.8341324329 4.3078298569 3412 1311867284.2853159904 0.1026166677 0.1069892862 0.2224405110 0.0063569920 0.0170570000 0.0004770000 0.0049380000 0.0000000000 0.0000040000 0.0007980000 48627861 96830484 509673472 3.9247486591 3.8348090649 4.3082418442 3413 1311867284.3178350925 0.1032279655 0.1069881842 0.2224405110 0.0063561376 0.0174550000 0.0004790000 0.0048990000 0.0000030000 0.0000040000 0.0014860000 48631589 96830484 509673472 3.9238686562 3.8346571922 4.3082904816 3414 1311867284.3494238853 0.1028315127 0.1069869666 0.2224405110 0.0063554932 0.0167430000 0.0004670000 0.0049260000 0.0000010000 0.0000040000 0.0007910000 48635261 96830484 509673472 3.9247856140 3.8362326622 4.3087835312 3415 1311867284.3854329586 0.1024078727 0.1069856257 0.2224405110 0.0063549724 0.0169290000 0.0004680000 0.0048900000 0.0000040000 0.0000040000 0.0010540000 48639045 96830484 509673472 3.9256439209 3.8362991810 4.3091592789 3416 1311867284.4175798893 0.1027475372 0.1069843851 0.2224405110 0.0063543132 0.0144850000 0.0004680000 0.0025580000 0.0000000000 0.0000040000 0.0008020000 48642717 96830484 509673472 3.9254655838 3.8363459110 4.3093881607 3417 1311867284.4495139122 0.1023792401 0.1069830374 0.2224405110 0.0063535930 0.0173490000 0.0004690000 0.0049300000 0.0000040000 0.0000040000 0.0014550000 48646389 96830484 509673472 3.9264922142 3.8372485638 4.3098549843 3418 1311867284.4854190350 0.1030529961 0.1069818876 0.2224405110 0.0063528691 0.0146010000 0.0004630000 0.0025610000 0.0000000000 0.0000040000 0.0007930000 48650117 96830484 509673472 3.9258832932 3.8367118835 4.3101820946 3419 1311867284.5177299976 0.1026552394 0.1069806221 0.2224405110 0.0063521561 0.0171780000 0.0004640000 0.0049090000 0.0000040000 0.0000040000 0.0010680000 48653845 96830484 509673472 3.9268805981 3.8363802433 4.3105387688 3420 1311867284.5494539738 0.1024258286 0.1069792903 0.2224405110 0.0063519222 0.0150210000 0.0004660000 0.0029560000 0.0000010000 0.0000040000 0.0007970000 48657517 96830484 509673472 3.9277923107 3.8372960091 4.3109683990 3421 1311867284.5854179859 0.1027073413 0.1069780415 0.2224405110 0.0063511431 0.0170490000 0.0004660000 0.0045410000 0.0000040000 0.0000040000 0.0014550000 48661245 96830484 509673472 3.9280095100 3.8379085064 4.3112483025 3422 1311867284.6174941063 0.1028317511 0.1069768299 0.2224405110 0.0063505342 0.0153230000 0.0004630000 0.0033590000 0.0000000000 0.0000040000 0.0007950000 48664917 96830484 509673472 3.9281649590 3.8369698524 4.3114871979 3423 1311867284.6495230198 0.1025871933 0.1069755475 0.2224405110 0.0063505318 0.0173620000 0.0004670000 0.0049260000 0.0000040000 0.0000040000 0.0010500000 48668645 96830484 509673472 3.9289104939 3.8380377293 4.3118748665 3424 1311867284.6853780746 0.1024273783 0.1069742192 0.2224405110 0.0063505091 0.0154540000 0.0004780000 0.0033520000 0.0000000000 0.0000040000 0.0007870000 48672373 96830484 509673472 3.9295642376 3.8390381336 4.3122935295 3425 1311867284.7174859047 0.1019682884 0.1069727576 0.2224405110 0.0063513608 0.0170280000 0.0004680000 0.0041500000 0.0000040000 0.0000040000 0.0014420000 48676045 96830484 509673472 3.9306943417 3.8372008801 4.3125777245 3426 1311867284.7498660088 0.1026801467 0.1069715046 0.2224405110 0.0063532526 0.0169690000 0.0004670000 0.0049180000 0.0000000000 0.0000050000 0.0008050000 48679773 96830484 509673472 3.9298663139 3.8387374878 4.3130536079 3427 1311867284.7854089737 0.1025775224 0.1069702225 0.2224405110 0.0063524738 0.0212320000 0.0005730000 0.0052060000 0.0000090000 0.0000070000 0.0011680000 48683501 96830484 509673472 3.9302000999 3.8398854733 4.3135581017 3428 1311867284.8186919689 0.1023073494 0.1069688622 0.2224405110 0.0063530186 0.0173530000 0.0005150000 0.0045380000 0.0000000000 0.0000040000 0.0007900000 48687229 96830484 509673472 3.9310801029 3.8383393288 4.3139224052 3429 1311867284.8492770195 0.1023807228 0.1069675242 0.2224405110 0.0063531539 0.0194980000 0.0005780000 0.0031360000 0.0000080000 0.0000080000 0.0016310000 48690845 96830484 509673472 3.9313383102 3.8396384716 4.3142905235 3430 1311867284.8853850365 0.1024306938 0.1069662015 0.2224405110 0.0063523360 0.0157290000 0.0004650000 0.0033760000 0.0000010000 0.0000040000 0.0007930000 48694573 96830484 509673472 3.9316222668 3.8401758671 4.3146905899 3431 1311867284.9174609184 0.1024654210 0.1069648897 0.2224405110 0.0063520914 0.0159900000 0.0004690000 0.0033580000 0.0000030000 0.0000040000 0.0010500000 48698301 96830484 509673472 3.9315702915 3.8384730816 4.3146300316 3432 1311867284.9492468834 0.1025039256 0.1069635899 0.2224405110 0.0063517514 0.0168260000 0.0004730000 0.0049300000 0.0000000000 0.0000040000 0.0007840000 48701973 96830484 509673472 3.9315519333 3.8397798538 4.3146615028 3433 1311867284.9852581024 0.1028727442 0.1069623983 0.2224405110 0.0063509935 0.0154460000 0.0004660000 0.0025600000 0.0000050000 0.0000030000 0.0014390000 48705813 96830484 509673472 3.9309496880 3.8395338058 4.3144173622 3434 1311867285.0175390244 0.1026489362 0.1069611422 0.2224405110 0.0063510847 0.0168110000 0.0004630000 0.0049600000 0.0000000000 0.0000040000 0.0007780000 48709429 96830484 509673472 3.9310317039 3.8378727436 4.3140373230 3435 1311867285.0493679047 0.1028327495 0.1069599403 0.2224405110 0.0063505031 0.0197270000 0.0005780000 0.0035500000 0.0000090000 0.0000070000 0.0011610000 48713101 96830484 509673472 3.9303500652 3.8384692669 4.3134827614 3436 1311867285.0853259563 0.1027801782 0.1069587238 0.2224405110 0.0063495840 0.0149330000 0.0004680000 0.0025800000 0.0000010000 0.0000050000 0.0007870000 48716885 96830484 509673472 3.9302928448 3.8383991718 4.3130483627 3437 1311867285.1177120209 0.1031571180 0.1069576178 0.2224405110 0.0063493271 0.0175040000 0.0004700000 0.0045200000 0.0000040000 0.0000030000 0.0014460000 48720557 96830484 509673472 3.9298412800 3.8361699581 4.3122901917 3438 1311867285.1502749920 0.1033069119 0.1069565559 0.2224405110 0.0063494333 0.0224440000 0.0006550000 0.0037740000 0.0000010000 0.0000110000 0.0010430000 48724285 96830484 509673472 3.9291281700 3.8365383148 4.3114390373 3439 1311867285.1855800152 0.1029175669 0.1069553814 0.2224405110 0.0063486600 0.0203110000 0.0006010000 0.0031520000 0.0000100000 0.0000110000 0.0012450000 48727957 96830484 509673472 3.9294500351 3.8369405270 4.3105859756 3440 1311867285.2187609673 0.1030328274 0.1069542411 0.2224405110 0.0063480741 0.0191960000 0.0005860000 0.0027450000 0.0000010000 0.0000090000 0.0009190000 48731741 96830484 509673472 3.9289348125 3.8354136944 4.3096385002 3441 1311867285.2493660450 0.1033270285 0.1069531870 0.2224405110 0.0063472004 0.0178490000 0.0004770000 0.0048900000 0.0000040000 0.0000040000 0.0014760000 48735357 96830484 509673472 3.9284372330 3.8345432281 4.3088936806 3442 1311867285.2853620052 0.1034969017 0.1069521829 0.2224405110 0.0063467323 0.0169940000 0.0004680000 0.0048970000 0.0000010000 0.0000040000 0.0008130000 48739141 96830484 509673472 3.9279592037 3.8352837563 4.3081216812 3443 1311867285.3175029755 0.1034679860 0.1069511709 0.2224405110 0.0063459663 0.0150170000 0.0004750000 0.0025590000 0.0000040000 0.0000040000 0.0010750000 48742813 96830484 509673472 3.9277019501 3.8350040913 4.3074202538 3444 1311867285.3493449688 0.1029961407 0.1069500225 0.2224405110 0.0063451665 0.0145360000 0.0004720000 0.0025490000 0.0000000000 0.0000040000 0.0008070000 48746485 96830484 509673472 3.9280631542 3.8342502117 4.3069262505 3445 1311867285.3855409622 0.1025558561 0.1069487470 0.2224405110 0.0063451370 0.0165660000 0.0004750000 0.0037160000 0.0000040000 0.0000030000 0.0014760000 48750325 96830484 509673472 3.9281971455 3.8356935978 4.3066225052 3446 1311867285.4175810814 0.1025224999 0.1069474625 0.2224405110 0.0063446081 0.0168280000 0.0004690000 0.0048780000 0.0000000000 0.0000040000 0.0008190000 48753941 96830484 509673472 3.9276847839 3.8356108665 4.3064465523 3447 1311867285.4492840767 0.1026970521 0.1069462295 0.2224405110 0.0063437045 0.0149980000 0.0004770000 0.0025570000 0.0000040000 0.0000040000 0.0010630000 48757613 96830484 509673472 3.9272656441 3.8352072239 4.3066358566 3448 1311867285.4853799343 0.1023632959 0.1069449003 0.2224405110 0.0063436563 0.0244280000 0.0005710000 0.0051770000 0.0000010000 0.0000120000 0.0010460000 48761341 96830484 509673472 3.9275212288 3.8367505074 4.3071007729 3449 1311867285.5176479816 0.1021588594 0.1069435127 0.2224405110 0.0063434605 0.0177640000 0.0004850000 0.0047840000 0.0000040000 0.0000040000 0.0014740000 48765069 96830484 509673472 3.9274609089 3.8363087177 4.3075633049 3450 1311867285.5494589806 0.1025097147 0.1069422275 0.2224405110 0.0063430402 0.0187050000 0.0005570000 0.0027120000 0.0000010000 0.0000080000 0.0009310000 48768741 96830484 509673472 3.9264194965 3.8356552124 4.3079419136 3451 1311867285.5855739117 0.1019343138 0.1069407763 0.2224405110 0.0063429050 0.0173770000 0.0004710000 0.0049260000 0.0000040000 0.0000040000 0.0010640000 48772525 96830484 509673472 3.9272711277 3.8372023106 4.3087792397 3452 1311867285.6175510883 0.1018867940 0.1069393123 0.2224405110 0.0063427266 0.0169090000 0.0004700000 0.0049060000 0.0000000000 0.0000040000 0.0008040000 48776197 96830484 509673472 3.9268872738 3.8365089893 4.3092331886 3453 1311867285.6494030952 0.1022632644 0.1069379581 0.2224405110 0.0063418667 0.0173610000 0.0004800000 0.0047710000 0.0000030000 0.0000030000 0.0014710000 48779869 96830484 509673472 3.9260706902 3.8359005451 4.3098082542 3454 1311867285.6856529713 0.1021703407 0.1069365778 0.2224405110 0.0063413899 0.0168980000 0.0004630000 0.0049010000 0.0000000000 0.0000030000 0.0007900000 48783653 96830484 509673472 3.9261329174 3.8381767273 4.3106122017 3455 1311867285.7177190781 0.1023953632 0.1069352634 0.2224405110 0.0063417871 0.0166930000 0.0004770000 0.0041210000 0.0000030000 0.0000040000 0.0010550000 48787325 96830484 509673472 3.9255905151 3.8367221355 4.3109798431 3456 1311867285.7497379780 0.1025477648 0.1069339938 0.2224405110 0.0063411519 0.0170720000 0.0004630000 0.0049130000 0.0000000000 0.0000040000 0.0007910000 48790997 96830484 509673472 3.9251601696 3.8365969658 4.3112740517 3457 1311867285.7854781151 0.1023089513 0.1069326560 0.2224405110 0.0063402459 0.0151410000 0.0004690000 0.0021620000 0.0000040000 0.0000040000 0.0014670000 48794837 96830484 509673472 3.9253404140 3.8372480869 4.3116378784 3458 1311867285.8179709911 0.1025634855 0.1069313925 0.2224405110 0.0063396242 0.0168450000 0.0004640000 0.0049010000 0.0000000000 0.0000040000 0.0007930000 48798453 96830484 509673472 3.9245946407 3.8361632824 4.3117094040 3459 1311867285.8496279716 0.1028795764 0.1069302211 0.2224405110 0.0063391350 0.0193060000 0.0005850000 0.0031190000 0.0000090000 0.0000080000 0.0011560000 48802125 96830484 509673472 3.9237723351 3.8362598419 4.3118276596 3460 1311867285.8852860928 0.1023389176 0.1069288941 0.2224405110 0.0063382912 0.0172990000 0.0004640000 0.0045320000 0.0000010000 0.0000040000 0.0007980000 48805965 96830484 509673472 3.9242794514 3.8362374306 4.3119444847 3461 1311867285.9187369347 0.1025055870 0.1069276161 0.2224405110 0.0063383433 0.0184720000 0.0005240000 0.0049190000 0.0000040000 0.0000040000 0.0014690000 48809637 96830484 509673472 3.9234466553 3.8347094059 4.3118104935 3462 1311867285.9496929646 0.1025142744 0.1069263413 0.2224405110 0.0063377875 0.0172340000 0.0005230000 0.0049010000 0.0000000000 0.0000040000 0.0008030000 48813309 96830484 509673472 3.9231350422 3.8340992928 4.3118934631 3463 1311867285.9858360291 0.1020814702 0.1069249422 0.2224405110 0.0063380624 0.0198780000 0.0005590000 0.0035250000 0.0000080000 0.0000080000 0.0011820000 48817037 96830484 509673472 3.9232716560 3.8358242512 4.3121609688 3464 1311867286.0184700489 0.1028012037 0.1069237518 0.2224405110 0.0063377359 0.0154900000 0.0004630000 0.0025510000 0.0000010000 0.0000040000 0.0008150000 48820709 96830484 509673472 3.9216771126 3.8347194195 4.3121876717 3465 1311867286.0494220257 0.1027418748 0.1069225449 0.2224405110 0.0063369615 0.0167710000 0.0004720000 0.0033360000 0.0000040000 0.0000050000 0.0015150000 48824381 96830484 509673472 3.9218888283 3.8343102932 4.3126955032 3466 1311867286.0854020119 0.1027526483 0.1069213418 0.2224405110 0.0063384741 0.0171790000 0.0004640000 0.0049040000 0.0000010000 0.0000040000 0.0008200000 48828109 96830484 509673472 3.9221978188 3.8355684280 4.3132672310 3467 1311867286.1240980625 0.1030073836 0.1069202129 0.2224405110 0.0063393872 0.0159910000 0.0004760000 0.0033250000 0.0000040000 0.0000040000 0.0010620000 48831893 96830484 509673472 3.9213299751 3.8347363472 4.3135046959 3468 1311867286.1506319046 0.1032064259 0.1069191420 0.2224405110 0.0063396369 0.0190030000 0.0005800000 0.0030960000 0.0000010000 0.0000080000 0.0009410000 48835397 96830484 509673472 3.9213044643 3.8353466988 4.3138060570 3469 1311867286.1857590675 0.1027170569 0.1069179307 0.2224405110 0.0063387443 0.0178630000 0.0004720000 0.0047760000 0.0000040000 0.0000040000 0.0014790000 48839125 96830484 509673472 3.9218564034 3.8359835148 4.3142085075 3470 1311867286.2179830074 0.1024721190 0.1069166495 0.2224405110 0.0063389557 0.0203490000 0.0005790000 0.0051290000 0.0000010000 0.0000090000 0.0009110000 48842797 96830484 509673472 3.9218192101 3.8355743885 4.3144974709 3471 1311867286.2525210381 0.1022962034 0.1069153183 0.2224405110 0.0063381516 0.0173960000 0.0005000000 0.0047680000 0.0000040000 0.0000040000 0.0010710000 48846469 96830484 509673472 3.9219191074 3.8357756138 4.3148665428 3472 1311867286.2861630917 0.1026409119 0.1069140872 0.2224405110 0.0063374241 0.0169320000 0.0004700000 0.0048890000 0.0000010000 0.0000040000 0.0007990000 48850141 96830484 509673472 3.9212849140 3.8369281292 4.3150343895 3473 1311867286.3203520775 0.1027278677 0.1069128818 0.2224405110 0.0063365476 0.0167990000 0.0004750000 0.0037410000 0.0000040000 0.0000030000 0.0014650000 48853813 96830484 509673472 3.9209609032 3.8368506432 4.3149957657 3474 1311867286.3524320126 0.1027097628 0.1069116720 0.2224405110 0.0063359189 0.0148660000 0.0004650000 0.0025490000 0.0000010000 0.0000040000 0.0008020000 48857485 96830484 509673472 3.9203481674 3.8369045258 4.3147349358 3475 1311867286.3855628967 0.1022812203 0.1069103395 0.2224405110 0.0063354706 0.0157320000 0.0004710000 0.0033210000 0.0000040000 0.0000030000 0.0010680000 48861157 96830484 509673472 3.9203078747 3.8387198448 4.3142571449 3476 1311867286.4177770615 0.1013289914 0.1069087338 0.2224405110 0.0063354461 0.0169720000 0.0004660000 0.0048660000 0.0000010000 0.0000040000 0.0008150000 48864885 96830484 509673472 3.9211528301 3.8401544094 4.3138251305 3477 1311867286.4494199753 0.1005863473 0.1069069154 0.2224405110 0.0063346907 0.0172300000 0.0004800000 0.0041040000 0.0000040000 0.0000040000 0.0014980000 48868557 96830484 509673472 3.9216754436 3.8401205540 4.3133316040 3478 1311867286.4855709076 0.1002821177 0.1069050107 0.2224405110 0.0063354001 0.0158100000 0.0005190000 0.0029420000 0.0000000000 0.0000040000 0.0008310000 48872285 96830484 509673472 3.9218461514 3.8411390781 4.3130908012 3479 1311867286.5190370083 0.0991623327 0.1069027851 0.2224405110 0.0063348355 0.0193630000 0.0006050000 0.0031220000 0.0000080000 0.0000070000 0.0011930000 48876069 96830484 509673472 3.9236993790 3.8422212601 4.3130493164 3480 1311867286.5512158871 0.0993227586 0.1069006070 0.2224405110 0.0063340578 0.0157450000 0.0004690000 0.0033220000 0.0000010000 0.0000050000 0.0008300000 48879685 96830484 509673472 3.9232711792 3.8417971134 4.3127398491 3481 1311867286.5855200291 0.0987778828 0.1068982735 0.2224405110 0.0063334373 0.0179250000 0.0004700000 0.0048720000 0.0000040000 0.0000040000 0.0015460000 48883525 96830484 509673472 3.9242966175 3.8423700333 4.3127660751 3482 1311867286.6190819740 0.0986329913 0.1068958998 0.2224405110 0.0063332322 0.0146650000 0.0004620000 0.0025270000 0.0000010000 0.0000040000 0.0008430000 48887197 96830484 509673472 3.9246892929 3.8433103561 4.3130488396 3483 1311867286.6500060558 0.0989984050 0.1068936323 0.2224405110 0.0063329302 0.0159660000 0.0004690000 0.0031780000 0.0000040000 0.0000030000 0.0010920000 48890813 96830484 509673472 3.9243590832 3.8424685001 4.3128876686 3484 1311867286.6856429577 0.0983126089 0.1068911694 0.2224405110 0.0063329399 0.0160160000 0.0005130000 0.0037050000 0.0000010000 0.0000040000 0.0008450000 48894541 96830484 509673472 3.9254310131 3.8410480022 4.3127532005 3485 1311867286.7176160812 0.0981669500 0.1068886660 0.2224405110 0.0063327030 0.0178800000 0.0004700000 0.0048580000 0.0000030000 0.0000040000 0.0015440000 48898213 96830484 509673472 3.9260120392 3.8420772552 4.3128046989 3486 1311867286.7495489120 0.0988880768 0.1068863709 0.2224405110 0.0063322337 0.0149880000 0.0004730000 0.0025370000 0.0000010000 0.0000050000 0.0008470000 48901941 96830484 509673472 3.9248383045 3.8424565792 4.3127074242 3487 1311867286.7856459618 0.0989013687 0.1068840810 0.2224405110 0.0063320351 0.0151620000 0.0004760000 0.0025220000 0.0000030000 0.0000040000 0.0011080000 48905669 96830484 509673472 3.9252889156 3.8419449329 4.3129205704 3488 1311867286.8176259995 0.0981783569 0.1068815851 0.2224405110 0.0063312184 0.0163900000 0.0004660000 0.0040760000 0.0000010000 0.0000040000 0.0008530000 48909397 96830484 509673472 3.9271512032 3.8421556950 4.3133063316 3489 1311867286.8535819054 0.0985515788 0.1068791976 0.2224405110 0.0063304493 0.0211020000 0.0005810000 0.0050850000 0.0000080000 0.0000070000 0.0016690000 48913181 96830484 509673472 3.9269206524 3.8419704437 4.3134431839 3490 1311867286.8868150711 0.0989735797 0.1068769324 0.2224405110 0.0063295990 0.0161760000 0.0004690000 0.0037090000 0.0000010000 0.0000040000 0.0008420000 48916853 96830484 509673472 3.9260706902 3.8413953781 4.3132791519 3491 1311867286.9174380302 0.0978686810 0.1068743520 0.2224405110 0.0063287495 0.0191880000 0.0005720000 0.0034510000 0.0000090000 0.0000080000 0.0012260000 48920469 96830484 509673472 3.9280118942 3.8415641785 4.3135652542 3492 1311867286.9543609619 0.0972120464 0.1068715850 0.2224405110 0.0063284701 0.0156880000 0.0004660000 0.0033070000 0.0000010000 0.0000050000 0.0008390000 48924309 96830484 509673472 3.9294135571 3.8436665535 4.3138532639 3493 1311867286.9854118824 0.0973881558 0.1068688700 0.2224405110 0.0063283656 0.0163580000 0.0004840000 0.0029160000 0.0000050000 0.0000040000 0.0015730000 48927925 96830484 509673472 3.9291496277 3.8427498341 4.3139128685 3494 1311867287.0174310207 0.0975862145 0.1068662132 0.2224405110 0.0063277072 0.0172470000 0.0004610000 0.0048690000 0.0000000000 0.0000040000 0.0008340000 48931597 96830484 509673472 3.9291138649 3.8415656090 4.3138747215 3495 1311867287.0547020435 0.0982970446 0.1068637614 0.2224405110 0.0063306367 0.0175710000 0.0004640000 0.0048600000 0.0000030000 0.0000040000 0.0010930000 48935437 96830484 509673472 3.9292263985 3.8431291580 4.3139204979 3496 1311867287.0856859684 0.0978800058 0.1068611917 0.2224405110 0.0063299479 0.0149510000 0.0004640000 0.0025360000 0.0000010000 0.0000040000 0.0008430000 48939109 96830484 509673472 3.9296326637 3.8436992168 4.3138232231 3497 1311867287.1178219318 0.0982742161 0.1068587362 0.2224405110 0.0063301596 0.0162590000 0.0004670000 0.0029200000 0.0000040000 0.0000040000 0.0015180000 48942725 96830484 509673472 3.9292171001 3.8429150581 4.3136119843 3498 1311867287.1537048817 0.0978631377 0.1068561645 0.2224405110 0.0063292953 0.0170060000 0.0004680000 0.0047420000 0.0000000000 0.0000040000 0.0008250000 48946509 96830484 509673472 3.9302055836 3.8432013988 4.3135986328 3499 1311867287.1874449253 0.0981026068 0.1068536628 0.2224405110 0.0063291126 0.0196390000 0.0005750000 0.0023360000 0.0000110000 0.0000100000 0.0012290000 48950237 96830484 509673472 3.9301571846 3.8443191051 4.3136124611 3500 1311867287.2175579071 0.0981219113 0.1068511680 0.2224405110 0.0063301240 0.0166720000 0.0004670000 0.0037210000 0.0000010000 0.0000050000 0.0008360000 48953853 96830484 509673472 3.9302563667 3.8429899216 4.3135595322 3501 1311867287.2536680698 0.0984983370 0.1068487822 0.2224405110 0.0063294854 0.0181900000 0.0004780000 0.0048840000 0.0000040000 0.0000040000 0.0015220000 48957637 96830484 509673472 3.9298789501 3.8429169655 4.3134837151 3502 1311867287.2870221138 0.0983212814 0.1068463471 0.2224405110 0.0063288979 0.0191410000 0.0005740000 0.0027180000 0.0000010000 0.0000080000 0.0009450000 48961365 96830484 509673472 3.9303383827 3.8437201977 4.3134026527 3503 1311867287.3175630569 0.0985738337 0.1068439856 0.2224405110 0.0063286153 0.0178730000 0.0004680000 0.0047450000 0.0000040000 0.0000030000 0.0010890000 48964981 96830484 509673472 3.9298410416 3.8427658081 4.3131494522 3504 1311867287.3540940285 0.0987453461 0.1068416743 0.2224405110 0.0063277813 0.0175170000 0.0004770000 0.0048720000 0.0000010000 0.0000040000 0.0008310000 48968821 96830484 509673472 3.9296901226 3.8424978256 4.3129487038 3505 1311867287.3855540752 0.0984066054 0.1068392677 0.2224405110 0.0063269490 0.0164280000 0.0004660000 0.0029320000 0.0000030000 0.0000030000 0.0015230000 48972493 96830484 509673472 3.9302752018 3.8430132866 4.3128490448 3506 1311867287.4175760746 0.0981761441 0.1068367968 0.2224405110 0.0063261446 0.0166450000 0.0004660000 0.0040860000 0.0000000000 0.0000040000 0.0008390000 48976109 96830484 509673472 3.9307940006 3.8422746658 4.3126988411 3507 1311867287.4535288811 0.0984111652 0.1068343943 0.2224405110 0.0063253349 0.0165490000 0.0004710000 0.0037080000 0.0000040000 0.0000040000 0.0010970000 48979893 96830484 509673472 3.9306964874 3.8413348198 4.3125076294 3508 1311867287.4867310524 0.0975154415 0.1068317378 0.2224405110 0.0063262975 0.0171820000 0.0004660000 0.0048490000 0.0000010000 0.0000040000 0.0008370000 48983565 96830484 509673472 3.9309794903 3.8425271511 4.3124337196 3509 1311867287.5174999237 0.0986611918 0.1068294093 0.2224405110 0.0063300663 0.0163490000 0.0004660000 0.0029250000 0.0000030000 0.0000040000 0.0015170000 48987237 96830484 509673472 3.9302952290 3.8426048756 4.3122849464 3510 1311867287.5534870625 0.0976212844 0.1068267859 0.2224405110 0.0063297400 0.0153550000 0.0004660000 0.0025360000 0.0000000000 0.0000050000 0.0008450000 48991021 96830484 509673472 3.9318327904 3.8426146507 4.3124394417 3511 1311867287.5869519711 0.0980688781 0.1068242915 0.2224405110 0.0063290137 0.0177980000 0.0004680000 0.0048700000 0.0000040000 0.0000040000 0.0011060000 48994749 96830484 509673472 3.9312827587 3.8429496288 4.3125848770 3512 1311867287.6176569462 0.0978542864 0.1068217374 0.2224405110 0.0063297273 0.0182540000 0.0004650000 0.0050880000 0.0000010000 0.0000040000 0.0008330000 48998365 96830484 509673472 3.9314126968 3.8417894840 4.3125309944 3513 1311867287.6539158821 0.0975068137 0.1068190859 0.2224405110 0.0063288896 0.0172970000 0.0005130000 0.0037110000 0.0000050000 0.0000040000 0.0015240000 49002205 96830484 509673472 3.9319674969 3.8420729637 4.3124051094 3514 1311867287.6875660419 0.0978218019 0.1068165254 0.2224405110 0.0063300917 0.0228110000 0.0006400000 0.0037030000 0.0000020000 0.0000120000 0.0010740000 49005877 96830484 509673472 3.9308321476 3.8435997963 4.3123946190 3515 1311867287.7176280022 0.0980530009 0.1068140323 0.2224405110 0.0063295253 0.0158320000 0.0004780000 0.0025360000 0.0000040000 0.0000040000 0.0011040000 49009493 96830484 509673472 3.9303803444 3.8433895111 4.3125181198 3516 1311867287.7553908825 0.0977876186 0.1068114650 0.2224405110 0.0063294192 0.0156550000 0.0004660000 0.0029430000 0.0000000000 0.0000040000 0.0008510000 49013333 96830484 509673472 3.9309642315 3.8426523209 4.3126354218 3517 1311867287.7872428894 0.0978668109 0.1068089218 0.2224405110 0.0063286000 0.0159080000 0.0004700000 0.0025450000 0.0000040000 0.0000040000 0.0015290000 49016949 96830484 509673472 3.9311230183 3.8432922363 4.3128066063 3518 1311867287.8260099888 0.0981560796 0.1068064622 0.2224405110 0.0063278285 0.0156080000 0.0004630000 0.0033290000 0.0000010000 0.0000040000 0.0008350000 49020789 96830484 509673472 3.9310486317 3.8439366817 4.3131694794 3519 1311867287.8536510468 0.0985283181 0.1068041098 0.2224405110 0.0063274313 0.0177290000 0.0004650000 0.0048790000 0.0000040000 0.0000040000 0.0010990000 49024349 96830484 509673472 3.9310939312 3.8429017067 4.3133788109 3520 1311867287.8931109905 0.0992782786 0.1068019717 0.2224405110 0.0063271294 0.0164750000 0.0004610000 0.0040990000 0.0000000000 0.0000040000 0.0008360000 49028133 96830484 509673472 3.9308230877 3.8432471752 4.3137383461 3521 1311867287.9175710678 0.0988708735 0.1067997192 0.2224405110 0.0063271951 0.0199810000 0.0005800000 0.0031180000 0.0000080000 0.0000080000 0.0016410000 49031581 96830484 509673472 3.9327120781 3.8449735641 4.3143563271 3522 1311867287.9535610676 0.0988647118 0.1067974662 0.2224405110 0.0063332782 0.0160930000 0.0004700000 0.0033310000 0.0000000000 0.0000040000 0.0008210000 49035309 96830484 509673472 3.9326899052 3.8429925442 4.3143968582 3523 1311867287.9868519306 0.0994370580 0.1067953770 0.2224405110 0.0063332060 0.0212350000 0.0005720000 0.0043460000 0.0000090000 0.0000070000 0.0012030000 49038981 96830484 509673472 3.9334301949 3.8408296108 4.3142075539 3524 1311867288.0178821087 0.0992418528 0.1067932335 0.2224405110 0.0063339600 0.0263050000 0.0006570000 0.0037170000 0.0000020000 0.0000270000 0.0013010000 49042653 96830484 509673472 3.9348490238 3.8423361778 4.3142499924 3525 1311867288.0536389351 0.0995813012 0.1067911876 0.2224405110 0.0063337626 0.0282540000 0.0006650000 0.0033300000 0.0000150000 0.0000170000 0.0021810000 49046437 96830484 509673472 3.9341847897 3.8425440788 4.3141593933 3526 1311867288.0854179859 0.0993166864 0.1067890678 0.2224405110 0.0063339273 0.0173930000 0.0004810000 0.0029550000 0.0000000000 0.0000040000 0.0008300000 49050053 96830484 509673472 3.9347701073 3.8400464058 4.3139925003 3527 1311867288.1175940037 0.0996061414 0.1067870312 0.2224405110 0.0063338250 0.0183660000 0.0005270000 0.0049940000 0.0000050000 0.0000040000 0.0010870000 49053781 96830484 509673472 3.9348320961 3.8406836987 4.3140835762 3528 1311867288.1540820599 0.0990687385 0.1067848435 0.2224405110 0.0063340169 0.0158900000 0.0004680000 0.0033150000 0.0000000000 0.0000050000 0.0008290000 49057565 96830484 509673472 3.9357490540 3.8403942585 4.3140168190 3529 1311867288.1854550838 0.0998732522 0.1067828850 0.2224405110 0.0063332982 0.0180560000 0.0004680000 0.0048730000 0.0000040000 0.0000030000 0.0015290000 49061237 96830484 509673472 3.9347457886 3.8378438950 4.3136987686 3530 1311867288.2175340652 0.0993643031 0.1067807834 0.2224405110 0.0063346893 0.0170380000 0.0004630000 0.0048520000 0.0000000000 0.0000040000 0.0008350000 49064797 96830484 509673472 3.9354431629 3.8391532898 4.3134813309 3531 1311867288.2535810471 0.0990228280 0.1067785863 0.2224405110 0.0063341698 0.0160870000 0.0004850000 0.0033100000 0.0000030000 0.0000030000 0.0011060000 49068637 96830484 509673472 3.9356920719 3.8399293423 4.3132081032 3532 1311867288.2854719162 0.0995889083 0.1067765507 0.2224405110 0.0063346627 0.0169140000 0.0004690000 0.0048640000 0.0000010000 0.0000040000 0.0008330000 49072253 96830484 509673472 3.9344143867 3.8379786015 4.3125929832 3533 1311867288.3175830841 0.0992019996 0.1067744068 0.2224405110 0.0063343077 0.0157210000 0.0004690000 0.0025220000 0.0000040000 0.0000040000 0.0015340000 49075981 96830484 509673472 3.9341781139 3.8385963440 4.3124179840 3534 1311867288.3535211086 0.0988365114 0.1067721606 0.2224405110 0.0063334642 0.0197910000 0.0005770000 0.0031110000 0.0000010000 0.0000080000 0.0009740000 49079765 96830484 509673472 3.9343461990 3.8392682076 4.3125572205 3535 1311867288.3858890533 0.0989413783 0.1067699454 0.2224405110 0.0063332504 0.0201400000 0.0005690000 0.0031290000 0.0000080000 0.0000080000 0.0012280000 49083437 96830484 509673472 3.9335296154 3.8382735252 4.3125133514 3536 1311867288.4177610874 0.0988658071 0.1067677101 0.2224405110 0.0063325500 0.0153580000 0.0004670000 0.0025360000 0.0000010000 0.0000040000 0.0008550000 49087109 96830484 509673472 3.9328811169 3.8385767937 4.3125076294 3537 1311867288.4560298920 0.0987258554 0.1067654365 0.2224405110 0.0063319457 0.0166250000 0.0004700000 0.0033200000 0.0000040000 0.0000040000 0.0015460000 49090949 96830484 509673472 3.9323096275 3.8393614292 4.3127832413 3538 1311867288.4854650497 0.0987044573 0.1067631581 0.2224405110 0.0063312658 0.0158100000 0.0004650000 0.0033050000 0.0000000000 0.0000040000 0.0008520000 49094621 96830484 509673472 3.9314947128 3.8391072750 4.3127894402 3539 1311867288.5176889896 0.0986652449 0.1067608699 0.2224405110 0.0063306742 0.0157200000 0.0004700000 0.0029130000 0.0000040000 0.0000030000 0.0010980000 49098237 96830484 509673472 3.9311649799 3.8382594585 4.3130984306 3540 1311867288.5544929504 0.0984801799 0.1067585307 0.2224405110 0.0063302353 0.0175640000 0.0004680000 0.0048550000 0.0000000000 0.0000040000 0.0008490000 49102021 96830484 509673472 3.9308001995 3.8392882347 4.3131527901 3541 1311867288.5874340534 0.0989017263 0.1067563119 0.2224405110 0.0063294204 0.0180250000 0.0004680000 0.0048670000 0.0000030000 0.0000030000 0.0015340000 49105693 96830484 509673472 3.9293625355 3.8391914368 4.3129982948 3542 1311867288.6175410748 0.0992397740 0.1067541898 0.2224405110 0.0063286086 0.0169710000 0.0004700000 0.0048470000 0.0000010000 0.0000040000 0.0008350000 49109309 96830484 509673472 3.9285879135 3.8386976719 4.3129682541 3543 1311867288.6551198959 0.0992140621 0.1067520616 0.2224405110 0.0063279392 0.0150450000 0.0004770000 0.0021530000 0.0000040000 0.0000040000 0.0011040000 49113149 96830484 509673472 3.9283711910 3.8395290375 4.3129014969 3544 1311867288.6874110699 0.0995610878 0.1067500325 0.2224405110 0.0063270601 0.0172330000 0.0004730000 0.0048630000 0.0000000000 0.0000040000 0.0008520000 49116821 96830484 509673472 3.9274759293 3.8393177986 4.3127636909 3545 1311867288.7177178860 0.0999216139 0.1067481063 0.2224405110 0.0063262020 0.0224310000 0.0005800000 0.0051310000 0.0000080000 0.0000080000 0.0017070000 49120437 96830484 509673472 3.9267089367 3.8391957283 4.3125352859 3546 1311867288.7560660839 0.0996286646 0.1067460986 0.2224405110 0.0063253507 0.0212620000 0.0005640000 0.0027250000 0.0000020000 0.0000110000 0.0011120000 49124277 96830484 509673472 3.9268965721 3.8401231766 4.3122792244 3547 1311867288.7855091095 0.0997778475 0.1067441340 0.2224405110 0.0063245182 0.0156470000 0.0004750000 0.0025390000 0.0000040000 0.0000050000 0.0011000000 49127893 96830484 509673472 3.9268207550 3.8394172192 4.3121051788 3548 1311867288.8192400932 0.1003159136 0.1067423222 0.2224405110 0.0063237218 0.0174320000 0.0004800000 0.0048860000 0.0000010000 0.0000040000 0.0008340000 49131677 96830484 509673472 3.9259469509 3.8392903805 4.3118824959 3549 1311867288.8543450832 0.1000452340 0.1067404352 0.2224405110 0.0063231793 0.0163510000 0.0004760000 0.0029170000 0.0000040000 0.0000030000 0.0015440000 49135405 96830484 509673472 3.9265716076 3.8401341438 4.3116216660 3550 1311867288.8855559826 0.1000420973 0.1067385483 0.2224405110 0.0063224628 0.0149310000 0.0004750000 0.0021500000 0.0000010000 0.0000050000 0.0008340000 49139077 96830484 509673472 3.9264185429 3.8396062851 4.3113760948 3551 1311867288.9176120758 0.1002454534 0.1067367198 0.2224405110 0.0063216961 0.0178990000 0.0004720000 0.0048690000 0.0000040000 0.0000040000 0.0010960000 49142693 96830484 509673472 3.9263617992 3.8396267891 4.3112382889 3552 1311867288.9599480629 0.1007648408 0.1067350386 0.2224405110 0.0063213175 0.0174120000 0.0004780000 0.0048760000 0.0000010000 0.0000040000 0.0008270000 49146701 96830484 509673472 3.9257123470 3.8406982422 4.3111248016 3553 1311867288.9855918884 0.1005357876 0.1067332938 0.2224405110 0.0063206960 0.0171610000 0.0004700000 0.0036910000 0.0000040000 0.0000040000 0.0015170000 49150205 96830484 509673472 3.9262895584 3.8402931690 4.3111195564 3554 1311867289.0176560879 0.1005364582 0.1067315501 0.2224405110 0.0063200919 0.0157420000 0.0004650000 0.0033150000 0.0000010000 0.0000040000 0.0008260000 49153821 96830484 509673472 3.9264953136 3.8401610851 4.3110003471 3555 1311867289.0535120964 0.1003657132 0.1067297595 0.2224405110 0.0063204761 0.0200180000 0.0005830000 0.0027430000 0.0000110000 0.0000100000 0.0011990000 49157661 96830484 509673472 3.9269535542 3.8397283554 4.3110699654 3556 1311867289.0855109692 0.1006561294 0.1067280515 0.2224405110 0.0063197240 0.0206510000 0.0005840000 0.0051110000 0.0000010000 0.0000080000 0.0009540000 49161277 96830484 509673472 3.9266912937 3.8397386074 4.3111510277 3557 1311867289.1175429821 0.1005010530 0.1067263008 0.2224405110 0.0063191033 0.0219140000 0.0005780000 0.0051080000 0.0000080000 0.0000090000 0.0016850000 49164949 96830484 509673472 3.9271669388 3.8400332928 4.3112025261 3558 1311867289.1545929909 0.1006612927 0.1067245962 0.2224405110 0.0063182255 0.0174670000 0.0004690000 0.0048650000 0.0000000000 0.0000040000 0.0008250000 49168845 96830484 509673472 3.9270243645 3.8400309086 4.3111615181 3559 1311867289.1856400967 0.1008694991 0.1067229511 0.2224405110 0.0063174163 0.0187070000 0.0004840000 0.0048610000 0.0000040000 0.0000040000 0.0016170000 49172405 96830484 509673472 3.9265897274 3.8392698765 4.3110818863 3560 1311867289.2185060978 0.1005579010 0.1067212193 0.2224405110 0.0063169696 0.0192300000 0.0006000000 0.0027070000 0.0000020000 0.0000100000 0.0009530000 49176133 96830484 509673472 3.9268360138 3.8397519588 4.3111329079 3561 1311867289.2550480366 0.1005911008 0.1067194979 0.2224405110 0.0063173475 0.0162730000 0.0004780000 0.0025680000 0.0000040000 0.0000040000 0.0015130000 49179973 96830484 509673472 3.9267814159 3.8392066956 4.3111424446 3562 1311867289.2853870392 0.1005447581 0.1067177644 0.2224405110 0.0063167901 0.0156620000 0.0004760000 0.0029350000 0.0000010000 0.0000050000 0.0008340000 49183645 96830484 509673472 3.9268431664 3.8383362293 4.3110890388 3563 1311867289.3176290989 0.1000431105 0.1067158910 0.2224405110 0.0063161189 0.0160180000 0.0004780000 0.0029390000 0.0000030000 0.0000040000 0.0010840000 49187261 96830484 509673472 3.9272646904 3.8388805389 4.3109197617 3564 1311867289.3539168835 0.1000291184 0.1067140148 0.2224405110 0.0063153631 0.0177350000 0.0004700000 0.0048800000 0.0000000000 0.0000040000 0.0008250000 49191045 96830484 509673472 3.9269142151 3.8390231133 4.3109173775 3565 1311867289.3861899376 0.1001509279 0.1067121739 0.2224405110 0.0063145407 0.0164580000 0.0004710000 0.0029210000 0.0000040000 0.0000050000 0.0015160000 49194773 96830484 509673472 3.9261109829 3.8386473656 4.3108572960 3566 1311867289.4177041054 0.0996131301 0.1067101831 0.2224405110 0.0063144604 0.0154530000 0.0004710000 0.0025360000 0.0000010000 0.0000050000 0.0008330000 49198389 96830484 509673472 3.9268448353 3.8394837379 4.3110809326 3567 1311867289.4536058903 0.0995678455 0.1067081808 0.2224405110 0.0063137159 0.0173010000 0.0004720000 0.0040960000 0.0000040000 0.0000040000 0.0010980000 49202173 96830484 509673472 3.9266774654 3.8398966789 4.3114752769 3568 1311867289.4859669209 0.0996764302 0.1067062100 0.2224405110 0.0063135559 0.0150000000 0.0004610000 0.0025250000 0.0000000000 0.0000040000 0.0008240000 49205901 96830484 509673472 3.9260528088 3.8387100697 4.3115596771 3569 1311867289.5183238983 0.0997454971 0.1067042596 0.2224405110 0.0063134361 0.0180820000 0.0004620000 0.0048650000 0.0000040000 0.0000040000 0.0015140000 49209517 96830484 509673472 3.9258584976 3.8401103020 4.3119826317 3570 1311867289.5548820496 0.0996940583 0.1067022960 0.2224405110 0.0063125872 0.0172760000 0.0004610000 0.0048690000 0.0000010000 0.0000040000 0.0008220000 49213357 96830484 509673472 3.9254324436 3.8408100605 4.3123369217 3571 1311867289.5856130123 0.1002010480 0.1067004754 0.2224405110 0.0063136160 0.0165000000 0.0004660000 0.0037120000 0.0000040000 0.0000030000 0.0010860000 49217029 96830484 509673472 3.9243803024 3.8387608528 4.3122539520 3572 1311867289.6176490784 0.1001949012 0.1066986542 0.2224405110 0.0063131541 0.0153450000 0.0004670000 0.0029230000 0.0000010000 0.0000040000 0.0008370000 49220645 96830484 509673472 3.9240758419 3.8395507336 4.3125214577 3573 1311867289.6536390781 0.0996798351 0.1066966898 0.2224405110 0.0063125562 0.0159350000 0.0004700000 0.0025310000 0.0000050000 0.0000040000 0.0015040000 49224429 96830484 509673472 3.9242691994 3.8413577080 4.3130173683 3574 1311867289.6856849194 0.0994498730 0.1066946621 0.2224405110 0.0063122302 0.0159230000 0.0004670000 0.0033310000 0.0000000000 0.0000040000 0.0008270000 49228101 96830484 509673472 3.9236366749 3.8408432007 4.3134489059 3575 1311867289.7204349041 0.0999090075 0.1066927640 0.2224405110 0.0063118585 0.0168870000 0.0004790000 0.0037210000 0.0000040000 0.0000040000 0.0010850000 49231885 96830484 509673472 3.9224445820 3.8411872387 4.3142433167 3576 1311867289.7564179897 0.0998750329 0.1066908575 0.2224405110 0.0063116501 0.0164870000 0.0004680000 0.0025500000 0.0000000000 0.0000040000 0.0008300000 49235613 96830484 509673472 3.9222402573 3.8419353962 4.3150386810 3577 1311867289.7855679989 0.1004452258 0.1066891115 0.2224405110 0.0063112909 0.0187710000 0.0005200000 0.0050200000 0.0000040000 0.0000040000 0.0014910000 49239229 96830484 509673472 3.9211668968 3.8410670757 4.3155655861 3578 1311867289.8240370750 0.1002821848 0.1066873208 0.2224405110 0.0063107699 0.0158850000 0.0004700000 0.0029490000 0.0000000000 0.0000050000 0.0008150000 49243069 96830484 509673472 3.9209020138 3.8395431042 4.3159480095 3579 1311867289.8541870117 0.1000633016 0.1066854700 0.2224405110 0.0063110734 0.0212920000 0.0005770000 0.0051250000 0.0000090000 0.0000080000 0.0011870000 49246741 96830484 509673472 3.9210152626 3.8415803909 4.3165626526 3580 1311867289.8855679035 0.1005301103 0.1066837506 0.2224405110 0.0063110527 0.0208820000 0.0005570000 0.0051280000 0.0000020000 0.0000090000 0.0009300000 49250357 96830484 509673472 3.9202177525 3.8408687115 4.3169498444 3581 1311867289.9200530052 0.1013717651 0.1066822673 0.2224405110 0.0063116537 0.0170660000 0.0004690000 0.0033330000 0.0000040000 0.0000050000 0.0014690000 49254085 96830484 509673472 3.9191985130 3.8397018909 4.3173151016 3582 1311867289.9536409378 0.1007325873 0.1066806063 0.2224405110 0.0063114497 0.0164720000 0.0004630000 0.0036020000 0.0000000000 0.0000040000 0.0008260000 49257813 96830484 509673472 3.9190866947 3.8402535915 4.3177242279 3583 1311867289.9855279922 0.1003796831 0.1066788477 0.2224405110 0.0063105866 0.0178770000 0.0004840000 0.0047660000 0.0000040000 0.0000040000 0.0010760000 49261429 96830484 509673472 3.9190838337 3.8400022984 4.3180198669 3584 1311867290.0232169628 0.1006532460 0.1066771664 0.2224405110 0.0063118982 0.0210300000 0.0005560000 0.0051160000 0.0000010000 0.0000080000 0.0009140000 49265325 96830484 509673472 3.9185006618 3.8375139236 4.3181824684 3585 1311867290.0535910130 0.1002924666 0.1066753855 0.2224405110 0.0063117947 0.0169130000 0.0004700000 0.0029380000 0.0000040000 0.0000040000 0.0015000000 49268941 96830484 509673472 3.9190051556 3.8386061192 4.3186006546 3586 1311867290.0854740143 0.1004458889 0.1066736483 0.2224405110 0.0063113908 0.0158940000 0.0004660000 0.0028150000 0.0000000000 0.0000040000 0.0008230000 49272669 96830484 509673472 3.9186122417 3.8385543823 4.3189959526 3587 1311867290.1248800755 0.1004403606 0.1066719106 0.2224405110 0.0063112561 0.0156250000 0.0004720000 0.0021670000 0.0000040000 0.0000040000 0.0010690000 49276453 96830484 509673472 3.9186468124 3.8373401165 4.3193373680 3588 1311867290.1536118984 0.1003350988 0.1066701445 0.2224405110 0.0063107974 0.0161010000 0.0004760000 0.0029670000 0.0000010000 0.0000040000 0.0008210000 49280069 96830484 509673472 3.9190247059 3.8387053013 4.3198294640 3589 1311867290.1856379509 0.1001651660 0.1066683320 0.2224405110 0.0063101440 0.0172450000 0.0004760000 0.0033500000 0.0000040000 0.0000040000 0.0015000000 49283797 96830484 509673472 3.9196789265 3.8391103745 4.3202247620 3590 1311867290.2225489616 0.1004800498 0.1066666082 0.2224405110 0.0063094824 0.0212060000 0.0005780000 0.0043600000 0.0000010000 0.0000090000 0.0009330000 49287525 96830484 509673472 3.9191670418 3.8387379646 4.3204879761 3591 1311867290.2540318966 0.0998578817 0.1066647122 0.2224405110 0.0063095967 0.0198120000 0.0005610000 0.0031070000 0.0000090000 0.0000090000 0.0011930000 49291197 96830484 509673472 3.9206254482 3.8400001526 4.3210186958 3592 1311867290.2892379761 0.1003959626 0.1066629670 0.2224405110 0.0063092349 0.0161770000 0.0004790000 0.0032190000 0.0000010000 0.0000050000 0.0008170000 49294981 96830484 509673472 3.9197187424 3.8393766880 4.3214201927 3593 1311867290.3220748901 0.1007603034 0.1066613242 0.2224405110 0.0063090650 0.0175920000 0.0004670000 0.0033370000 0.0000040000 0.0000040000 0.0014980000 49298653 96830484 509673472 3.9192411900 3.8384287357 4.3214478493 3594 1311867290.3587789536 0.1002990603 0.1066595539 0.2224405110 0.0063087778 0.0177010000 0.0004640000 0.0047670000 0.0000010000 0.0000040000 0.0008250000 49302437 96830484 509673472 3.9199061394 3.8392245770 4.3215312958 3595 1311867290.3864240646 0.1000525057 0.1066577161 0.2224405110 0.0063079466 0.0179780000 0.0004770000 0.0048900000 0.0000040000 0.0000030000 0.0010790000 49305941 96830484 509673472 3.9200539589 3.8389587402 4.3215026855 3596 1311867290.4216320515 0.0999730676 0.1066558572 0.2224405110 0.0063072459 0.0175650000 0.0004750000 0.0047740000 0.0000000000 0.0000040000 0.0008210000 49309781 96830484 509673472 3.9191749096 3.8380107880 4.3212122917 3597 1311867290.4578390121 0.1001188755 0.1066540398 0.2224405110 0.0063068085 0.0176750000 0.0004650000 0.0041140000 0.0000040000 0.0000040000 0.0015080000 49313341 96830484 509673472 3.9181532860 3.8392453194 4.3212699890 3598 1311867290.4859950542 0.1000829712 0.1066522135 0.2224405110 0.0063061727 0.0191680000 0.0005580000 0.0023240000 0.0000010000 0.0000080000 0.0009600000 49316901 96830484 509673472 3.9180696011 3.8391518593 4.3211112022 3599 1311867290.5223400593 0.1001869887 0.1066504171 0.2224405110 0.0063062540 0.0181640000 0.0004660000 0.0049110000 0.0000040000 0.0000040000 0.0010610000 49320685 96830484 509673472 3.9175548553 3.8374440670 4.3209457397 3600 1311867290.5537059307 0.1004566848 0.1066486966 0.2224405110 0.0063065265 0.0216810000 0.0005680000 0.0051560000 0.0000010000 0.0000080000 0.0009590000 49324357 96830484 509673472 3.9171450138 3.8387503624 4.3208680153 3601 1311867290.5855538845 0.1006796882 0.1066470390 0.2224405110 0.0063063421 0.0238160000 0.0005820000 0.0035510000 0.0000120000 0.0000100000 0.0018560000 49328085 96830484 509673472 3.9162566662 3.8392424583 4.3205323219 3602 1311867290.6221020222 0.1003321782 0.1066452859 0.2224405110 0.0063059564 0.0214900000 0.0005630000 0.0047600000 0.0000010000 0.0000080000 0.0009540000 49331813 96830484 509673472 3.9166743755 3.8384058475 4.3202538490 3603 1311867290.6536018848 0.1006480753 0.1066436214 0.2224405110 0.0063069704 0.0161190000 0.0004700000 0.0025550000 0.0000050000 0.0000040000 0.0010710000 49335485 96830484 509673472 3.9164366722 3.8398759365 4.3200535774 3604 1311867290.6857531071 0.1008616611 0.1066420171 0.2224405110 0.0063061173 0.0163100000 0.0004600000 0.0033300000 0.0000000000 0.0000040000 0.0008430000 49339101 96830484 509673472 3.9164862633 3.8401618004 4.3199348450 3605 1311867290.7256150246 0.1008138433 0.1066404004 0.2224405110 0.0063069751 0.0185430000 0.0004670000 0.0048950000 0.0000040000 0.0000030000 0.0015200000 49343053 96830484 509673472 3.9169814587 3.8383398056 4.3195838928 3606 1311867290.7539739609 0.1011975929 0.1066388910 0.2224405110 0.0063067537 0.0176020000 0.0004640000 0.0048960000 0.0000010000 0.0000030000 0.0008320000 49346613 96830484 509673472 3.9165940285 3.8390073776 4.3193850517 3607 1311867290.7866060734 0.1010427997 0.1066373395 0.2224405110 0.0063059255 0.0196040000 0.0005600000 0.0023220000 0.0000080000 0.0000090000 0.0012030000 49350229 96830484 509673472 3.9171750546 3.8395891190 4.3190312386 3608 1311867290.8231720924 0.1010621786 0.1066357943 0.2224405110 0.0063057073 0.0157090000 0.0004670000 0.0025560000 0.0000000000 0.0000040000 0.0008470000 49354069 96830484 509673472 3.9172914028 3.8382065296 4.3184270859 3609 1311867290.8556039333 0.1012014970 0.1066342886 0.2224405110 0.0063051183 0.0173240000 0.0004660000 0.0027560000 0.0000050000 0.0000040000 0.0015370000 49357741 96830484 509673472 3.9175181389 3.8382887840 4.3181333542 3610 1311867290.8876988888 0.1015533730 0.1066328811 0.2224405110 0.0063073344 0.0154070000 0.0005190000 0.0021490000 0.0000000000 0.0000040000 0.0008500000 49361413 96830484 509673472 3.9181091785 3.8383672237 4.3177652359 3611 1311867290.9227120876 0.1015730575 0.1066314799 0.2224405110 0.0063065353 0.0210290000 0.0005670000 0.0050800000 0.0000080000 0.0000080000 0.0011470000 49365141 96830484 509673472 3.9184024334 3.8377497196 4.3172183037 3612 1311867290.9537110329 0.1010548025 0.1066299359 0.2224405110 0.0063076227 0.0176250000 0.0004690000 0.0048920000 0.0000010000 0.0000040000 0.0008440000 49368813 96830484 509673472 3.9186716080 3.8377220631 4.3168401718 3613 1311867290.9906909466 0.1011142582 0.1066284093 0.2224405110 0.0063070075 0.0182340000 0.0004700000 0.0048810000 0.0000040000 0.0000040000 0.0015190000 49372653 96830484 509673472 3.9192385674 3.8379607201 4.3165411949 3614 1311867291.0239291191 0.1013306230 0.1066269434 0.2224405110 0.0063065145 0.0174720000 0.0004670000 0.0048680000 0.0000000000 0.0000040000 0.0008360000 49376381 96830484 509673472 3.9195044041 3.8374867439 4.3162527084 3615 1311867291.0558199883 0.1009892076 0.1066253839 0.2224405110 0.0063058423 0.0161730000 0.0004770000 0.0029320000 0.0000040000 0.0000030000 0.0010950000 49380053 96830484 509673472 3.9206457138 3.8367116451 4.3158998489 3616 1311867291.0934820175 0.1007831916 0.1066237682 0.2224405110 0.0063058178 0.0165360000 0.0004740000 0.0037230000 0.0000000000 0.0000040000 0.0008350000 49383837 96830484 509673472 3.9216637611 3.8380708694 4.3156590462 3617 1311867291.1203110218 0.1003400534 0.1066220310 0.2224405110 0.0063057093 0.0165750000 0.0004700000 0.0025400000 0.0000040000 0.0000050000 0.0015170000 49387397 96830484 509673472 3.9226012230 3.8371956348 4.3152470589 3618 1311867291.1541891098 0.1014912948 0.1066206128 0.2224405110 0.0063068043 0.0177610000 0.0004720000 0.0048870000 0.0000010000 0.0000040000 0.0008380000 49391013 96830484 509673472 3.9219899178 3.8368849754 4.3146705627 3619 1311867291.1891989708 0.1007757261 0.1066189978 0.2224405110 0.0063070110 0.0204230000 0.0005760000 0.0039210000 0.0000080000 0.0000080000 0.0011950000 49394797 96830484 509673472 3.9228608608 3.8382058144 4.3143548965 3620 1311867291.2211010456 0.1008529440 0.1066174050 0.2224405110 0.0063066839 0.0161040000 0.0004670000 0.0029460000 0.0000010000 0.0000040000 0.0008450000 49398469 96830484 509673472 3.9232993126 3.8370518684 4.3139901161 3621 1311867291.2543909550 0.1008552760 0.1066158136 0.2224405110 0.0063059959 0.0219010000 0.0005670000 0.0049810000 0.0000080000 0.0000080000 0.0017070000 49402197 96830484 509673472 3.9235651493 3.8374557495 4.3136186600 3622 1311867291.2877960205 0.1003812477 0.1066140923 0.2224405110 0.0063051459 0.0219830000 0.0005660000 0.0051320000 0.0000010000 0.0000080000 0.0009660000 49405869 96830484 509673472 3.9246621132 3.8381626606 4.3132309914 3623 1311867291.3210899830 0.1010597348 0.1066125593 0.2224405110 0.0063049842 0.0159970000 0.0004680000 0.0025490000 0.0000030000 0.0000040000 0.0010890000 49409541 96830484 509673472 3.9240396023 3.8371536732 4.3126840591 3624 1311867291.3547959328 0.1011366248 0.1066110482 0.2224405110 0.0063041636 0.0159940000 0.0004660000 0.0029390000 0.0000010000 0.0000050000 0.0008460000 49413325 96830484 509673472 3.9241721630 3.8370423317 4.3122205734 3625 1311867291.3878760338 0.1009662226 0.1066094910 0.2224405110 0.0063037827 0.0196660000 0.0004710000 0.0048860000 0.0000050000 0.0000040000 0.0015290000 49416997 96830484 509673472 3.9245541096 3.8376774788 4.3118963242 3626 1311867291.4223349094 0.1009153575 0.1066079207 0.2224405110 0.0063031702 0.0155980000 0.0005140000 0.0025410000 0.0000000000 0.0000040000 0.0008490000 49420725 96830484 509673472 3.9247846603 3.8370800018 4.3115744591 3627 1311867291.4536559582 0.1006051078 0.1066062656 0.2224405110 0.0063023866 0.0180620000 0.0004710000 0.0048650000 0.0000030000 0.0000030000 0.0010980000 49424397 96830484 509673472 3.9252927303 3.8368515968 4.3110256195 3628 1311867291.4883999825 0.1005484760 0.1066045959 0.2224405110 0.0063023269 0.0156680000 0.0004670000 0.0029220000 0.0000000000 0.0000040000 0.0008470000 49428125 96830484 509673472 3.9252960682 3.8382027149 4.3107013702 3629 1311867291.5201730728 0.1003019512 0.1066028592 0.2224405110 0.0063016680 0.0186780000 0.0004650000 0.0048900000 0.0000040000 0.0000040000 0.0015290000 49431853 96830484 509673472 3.9256160259 3.8377606869 4.3105263710 3630 1311867291.5536448956 0.1010623947 0.1066013329 0.2224405110 0.0063010564 0.0181700000 0.0004730000 0.0048670000 0.0000000000 0.0000040000 0.0008510000 49435525 96830484 509673472 3.9244132042 3.8374752998 4.3102107048 3631 1311867291.5895080566 0.1003120318 0.1065996008 0.2224405110 0.0063006300 0.0167850000 0.0004640000 0.0033210000 0.0000040000 0.0000040000 0.0011150000 49439309 96830484 509673472 3.9259896278 3.8380641937 4.3100795746 3632 1311867291.6206870079 0.1003642082 0.1065978840 0.2224405110 0.0063005108 0.0158350000 0.0004670000 0.0025360000 0.0000010000 0.0000040000 0.0008570000 49442925 96830484 509673472 3.9251956940 3.8375813961 4.3096117973 3633 1311867291.6539781094 0.1002341658 0.1065961323 0.2224405110 0.0062999126 0.0186490000 0.0004750000 0.0048720000 0.0000050000 0.0000040000 0.0015390000 49446653 96830484 509673472 3.9251432419 3.8370068073 4.3094148636 3634 1311867291.6896810532 0.1000705361 0.1065943366 0.2224405110 0.0062991879 0.0180240000 0.0004680000 0.0048750000 0.0000010000 0.0000040000 0.0008580000 49450437 96830484 509673472 3.9255740643 3.8380212784 4.3091373444 3635 1311867291.7202739716 0.0996701047 0.1065924317 0.2224405110 0.0062986618 0.0179340000 0.0004700000 0.0048600000 0.0000040000 0.0000030000 0.0011110000 49454053 96830484 509673472 3.9260544777 3.8369390965 4.3089308739 3636 1311867291.7537178993 0.1003234982 0.1065907076 0.2224405110 0.0062982173 0.0161500000 0.0004790000 0.0031800000 0.0000010000 0.0000040000 0.0008490000 49457781 96830484 509673472 3.9246010780 3.8371360302 4.3085274696 3637 1311867291.7890019417 0.0997491032 0.1065888265 0.2224405110 0.0062976938 0.0169300000 0.0004690000 0.0029420000 0.0000040000 0.0000040000 0.0015460000 49461565 96830484 509673472 3.9256463051 3.8379044533 4.3084483147 3638 1311867291.8217189312 0.0997048393 0.1065869343 0.2224405110 0.0062977259 0.0161420000 0.0004690000 0.0032020000 0.0000000000 0.0000050000 0.0008590000 49465181 96830484 509673472 3.9256317616 3.8366613388 4.3083796501 3639 1311867291.8538639545 0.0999701247 0.1065851159 0.2224405110 0.0062971973 0.0160700000 0.0004780000 0.0025390000 0.0000040000 0.0000040000 0.0011170000 49468909 96830484 509673472 3.9255557060 3.8371715546 4.3084654808 3640 1311867291.8879489899 0.1001472026 0.1065833473 0.2224405110 0.0062971096 0.0155140000 0.0004780000 0.0021510000 0.0000000000 0.0000040000 0.0008650000 49472581 96830484 509673472 3.9260845184 3.8373265266 4.3086204529 3641 1311867291.9206929207 0.0999782383 0.1065815332 0.2224405110 0.0062966355 0.0199820000 0.0005690000 0.0023060000 0.0000080000 0.0000080000 0.0017120000 49476365 96830484 509673472 3.9263970852 3.8368773460 4.3086032867 3642 1311867291.9537200928 0.1002514362 0.1065797951 0.2224405110 0.0062965096 0.0304620000 0.0006680000 0.0053510000 0.0000020000 0.0000150000 0.0013710000 49479981 96830484 509673472 3.9268145561 3.8370165825 4.3088717461 3643 1311867291.9902889729 0.0998878628 0.1065779582 0.2224405110 0.0062971143 0.0177100000 0.0004740000 0.0037140000 0.0000040000 0.0000040000 0.0011040000 49483821 96830484 509673472 3.9273872375 3.8366980553 4.3090810776 3644 1311867292.0225260258 0.1007889733 0.1065763695 0.2224405110 0.0062991997 0.0175080000 0.0004670000 0.0040910000 0.0000010000 0.0000040000 0.0008660000 49487493 96830484 509673472 3.9272227287 3.8366720676 4.3092851639 3645 1311867292.0536830425 0.1006164998 0.1065747345 0.2224405110 0.0062984127 0.0167210000 0.0004690000 0.0027920000 0.0000040000 0.0000040000 0.0015580000 49491109 96830484 509673472 3.9280803204 3.8367936611 4.3095326424 3646 1311867292.0922849178 0.0999320149 0.1065729125 0.2224405110 0.0063000041 0.0155600000 0.0004690000 0.0021540000 0.0000000000 0.0000040000 0.0008570000 49494949 96830484 509673472 3.9283196926 3.8368093967 4.3097481728 3647 1311867292.1243879795 0.1002767906 0.1065711862 0.2224405110 0.0062993236 0.0161580000 0.0004670000 0.0025300000 0.0000040000 0.0000040000 0.0011030000 49498565 96830484 509673472 3.9278726578 3.8373072147 4.3099532127 3648 1311867292.1602649689 0.1002404019 0.1065694508 0.2224405110 0.0062984642 0.0178900000 0.0004830000 0.0048590000 0.0000010000 0.0000040000 0.0008510000 49502349 96830484 509673472 3.9280052185 3.8376195431 4.3102579117 3649 1311867292.1899850368 0.1000284180 0.1065676582 0.2224405110 0.0062977385 0.0166970000 0.0004660000 0.0029140000 0.0000040000 0.0000040000 0.0015390000 49505965 96830484 509673472 3.9283142090 3.8372633457 4.3105306625 3650 1311867292.2207419872 0.1005914360 0.1065660209 0.2224405110 0.0062969016 0.0165850000 0.0004670000 0.0037060000 0.0000010000 0.0000050000 0.0008520000 49509525 96830484 509673472 3.9275054932 3.8370440006 4.3107705116 3651 1311867292.2576909065 0.1003144756 0.1065643086 0.2224405110 0.0062961461 0.0217230000 0.0005830000 0.0051230000 0.0000090000 0.0000080000 0.0012360000 49513365 96830484 509673472 3.9276618958 3.8372170925 4.3109912872 3652 1311867292.2878270149 0.1003179625 0.1065625982 0.2224405110 0.0062953106 0.0178410000 0.0004840000 0.0048680000 0.0000010000 0.0000040000 0.0008510000 49516981 96830484 509673472 3.9274957180 3.8369042873 4.3112010956 3653 1311867292.3217270374 0.0995952860 0.1065606909 0.2224405110 0.0062966124 0.0184930000 0.0004740000 0.0047170000 0.0000030000 0.0000030000 0.0015520000 49520653 96830484 509673472 3.9273910522 3.8367702961 4.3113489151 3654 1311867292.3621709347 0.1006022170 0.1065590602 0.2224405110 0.0062989251 0.0167300000 0.0004830000 0.0036900000 0.0000010000 0.0000040000 0.0008560000 49524605 96830484 509673472 3.9262864590 3.8370554447 4.3114380836 3655 1311867292.3953619003 0.1005639881 0.1065574200 0.2224405110 0.0062981489 0.0159200000 0.0004700000 0.0025450000 0.0000040000 0.0000030000 0.0011070000 49528333 96830484 509673472 3.9261043072 3.8362429142 4.3115258217 3656 1311867292.4259300232 0.1005669534 0.1065557815 0.2224405110 0.0062973513 0.0155200000 0.0004660000 0.0024090000 0.0000010000 0.0000040000 0.0008680000 49531949 96830484 509673472 3.9259669781 3.8360812664 4.3115825653 3657 1311867292.4565210342 0.1006002948 0.1065541530 0.2224405110 0.0062964990 0.0210290000 0.0005700000 0.0023330000 0.0000100000 0.0000110000 0.0018510000 49535509 96830484 509673472 3.9256501198 3.8360395432 4.3115282059 3658 1311867292.4883699417 0.1001934037 0.1065524141 0.2224405110 0.0062958582 0.0193500000 0.0005310000 0.0052870000 0.0000010000 0.0000050000 0.0008580000 49539237 96830484 509673472 3.9260623455 3.8353090286 4.3115224838 3659 1311867292.5229649544 0.1003576368 0.1065507211 0.2224405110 0.0062950113 0.0185060000 0.0005130000 0.0046210000 0.0000040000 0.0000040000 0.0011170000 49542965 96830484 509673472 3.9255986214 3.8353712559 4.3114719391 3660 1311867292.5581150055 0.1003087088 0.1065490156 0.2224405110 0.0062943745 0.0166280000 0.0004680000 0.0029390000 0.0000010000 0.0000040000 0.0008610000 49546693 96830484 509673472 3.9255223274 3.8362202644 4.3117575645 3661 1311867292.5882439613 0.1007302403 0.1065474262 0.2224405110 0.0062936430 0.0220380000 0.0005550000 0.0050730000 0.0000080000 0.0000090000 0.0016750000 49550365 96830484 509673472 3.9245650768 3.8364543915 4.3118081093 3662 1311867292.6230869293 0.1001966372 0.1065456920 0.2224405110 0.0062928298 0.0159280000 0.0004680000 0.0025400000 0.0000000000 0.0000170000 0.0008520000 49554093 96830484 509673472 3.9254341125 3.8364925385 4.3121194839 3663 1311867292.6595211029 0.1001040190 0.1065439334 0.2224405110 0.0062919768 0.0185530000 0.0004660000 0.0048770000 0.0000040000 0.0000040000 0.0011140000 49557933 96830484 509673472 3.9257557392 3.8369798660 4.3123960495 3664 1311867292.6880218983 0.1004006043 0.1065422567 0.2224405110 0.0062914687 0.0168080000 0.0004630000 0.0037020000 0.0000010000 0.0000050000 0.0008520000 49561437 96830484 509673472 3.9252924919 3.8358893394 4.3124213219 3665 1311867292.7206969261 0.0999678373 0.1065404629 0.2224405110 0.0062907444 0.0171890000 0.0004640000 0.0029410000 0.0000040000 0.0000040000 0.0015330000 49565165 96830484 509673472 3.9262957573 3.8357162476 4.3126864433 3666 1311867292.7561879158 0.1003493071 0.1065387741 0.2224405110 0.0062901749 0.0213320000 0.0005580000 0.0050200000 0.0000010000 0.0000080000 0.0009680000 49568949 96830484 509673472 3.9259183407 3.8361470699 4.3128042221 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:16:00 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0051490000 86986196 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0090761073 0.0045380536 0.0090761073 0.0108709261 0.0257170000 103538857 0 402718720 0.0021791174 0.0018214645 0.0004411704 3 0.0800000000 0.0103211887 0.0064657653 0.0103211887 0.0113080456 0.0189910000 106810769 0 402718720 0.0059174011 -0.0071328436 0.0010008662 4 0.1200000000 0.0048878756 0.0060712929 0.0103211887 0.0112128200 0.0181150000 106813417 0 402718720 0.0048612426 -0.0070005618 0.0010327058 5 0.1600000000 0.0032245086 0.0055019361 0.0103211887 0.0105501973 0.0175710000 106816081 0 402718720 0.0006014459 -0.0013379942 0.0005574760 6 0.2000000000 0.0094174864 0.0061545278 0.0103211887 0.0096519669 0.0167970000 106819129 0 402718720 0.0015716671 -0.0006602437 0.0007672103 7 0.2400000000 0.0100641586 0.0067130465 0.0103211887 0.0088826377 0.0154390000 106821377 0 402718720 0.0016557914 -0.0002924298 0.0006700487 8 0.2800000000 0.0069222571 0.0067391978 0.0103211887 0.0084511798 0.0160830000 106823625 0 402718720 0.0009001076 -0.0005924877 0.0006828007 9 0.3200000000 0.0075042327 0.0068242017 0.0103211887 0.0079463376 0.0158180000 106826705 0 402718720 0.0011385574 -0.0000332233 0.0006531931 10 0.3600000000 0.0088657802 0.0070283595 0.0103211887 0.0075323970 0.0153130000 106830553 0 402718720 0.0016033956 -0.0001645716 0.0008678159 11 0.4000000000 0.0085398350 0.0071657664 0.0103211887 0.0071606491 0.0224060000 106832801 0 402718720 0.0020945438 -0.0009851144 0.0009023340 12 0.4400000000 0.0071468074 0.0071641865 0.0103211887 0.0068788419 0.0292300000 106835049 0 402718720 0.0021323934 -0.0019730923 0.0003361021 13 0.4800000000 0.0069915461 0.0071509064 0.0103211887 0.0067589240 0.0244030000 106837297 0 402718720 0.0014652659 -0.0006900396 0.0005437252 14 0.5200000000 0.0063366094 0.0070927424 0.0103211887 0.0065940851 0.0172240000 106839545 0 402718720 0.0014001307 -0.0004686379 0.0004216829 15 0.5600000000 0.0058464846 0.0070096585 0.0103211887 0.0063686321 0.0174690000 106841793 0 402718720 0.0014998523 -0.0004094870 0.0003048269 16 0.6000000000 0.0063125961 0.0069660921 0.0103211887 0.0061584865 0.0168100000 106844041 0 402718720 0.0016335065 -0.0000963954 0.0002616511 17 0.6400000000 0.0049413196 0.0068469878 0.0103211887 0.0059803881 0.0168020000 106847953 0 402718720 0.0013247451 -0.0008822971 0.0000742717 18 0.6800000000 0.0040652994 0.0066924496 0.0103211887 0.0058586153 0.0163820000 106853401 0 402718720 0.0008679936 -0.0015124173 0.0000108540 19 0.7200000000 0.0064174556 0.0066779762 0.0103211887 0.0061606346 0.0187030000 106855649 0 402718720 -0.0005954048 -0.0061624143 0.0008409359 20 0.7600000000 0.0099731805 0.0068427364 0.0103211887 0.0061111837 0.0194790000 106857897 0 402718720 -0.0029005758 -0.0083624162 0.0013820176 21 0.8000000000 0.0114343548 0.0070613849 0.0114343548 0.0060206685 0.0189240000 106860145 0 402718720 -0.0044242679 -0.0094639929 0.0016149521 22 0.8400000000 0.0079693776 0.0071026573 0.0114343548 0.0060157946 0.0184080000 106862393 0 402718720 -0.0021216504 -0.0073527349 0.0010652001 23 0.8800000000 0.0049629519 0.0070096267 0.0114343548 0.0061122361 0.0203950000 106864641 0 402718720 0.0000876460 -0.0036846281 0.0004616799 24 0.9200000000 0.0056977822 0.0069549665 0.0114343548 0.0060644880 0.0170600000 106866889 0 402718720 0.0011139771 -0.0007524509 0.0001194901 25 0.9600000000 0.0068465173 0.0069506285 0.0114343548 0.0059501705 0.0180110000 106869137 0 402718720 0.0009097299 -0.0007820157 0.0003513246 26 1.0000000000 0.0070996378 0.0069563596 0.0114343548 0.0058340518 0.0164070000 106871385 0 402718720 0.0002967512 -0.0010704736 0.0002656909 27 1.0400000000 0.0065219537 0.0069402705 0.0114343548 0.0057300952 0.0164070000 106873633 0 402718720 0.0005783816 -0.0015068244 0.0002210101 28 1.0800000000 0.0078988941 0.0069745071 0.0114343548 0.0056302154 0.0215110000 106875881 0 402718720 0.0017015099 -0.0013893475 0.0006221447 29 1.1200000000 0.0087835193 0.0070368868 0.0114343548 0.0056775138 0.0204830000 106878129 0 402718720 0.0013563763 -0.0022361451 0.0009875023 30 1.1600000000 0.0085128797 0.0070860866 0.0114343548 0.0058596014 0.0166170000 106880377 0 402718720 0.0006768740 -0.0075496999 0.0017560360 31 1.2000000000 0.0122895967 0.0072539417 0.0122895967 0.0059543240 0.0167880000 106882625 0 402718720 -0.0005340102 -0.0094562313 0.0024793341 32 1.2400000000 0.0152215101 0.0075029283 0.0152215101 0.0062540690 0.0187540000 106884873 0 402718720 -0.0017468809 -0.0087435581 0.0027844021 33 1.2800000000 0.0112211350 0.0076156012 0.0152215101 0.0063361083 0.0170890000 106890449 0 402718720 0.0026313239 -0.0105645787 0.0025953718 34 1.3200000000 0.0130641405 0.0077758523 0.0152215101 0.0065182786 0.0170500000 106899097 0 402718720 -0.0002138325 -0.0096790893 0.0032194322 35 1.3600000000 0.0142992502 0.0079622351 0.0152215101 0.0068337557 0.0203380000 106901345 0 402718720 -0.0000633359 -0.0119353915 0.0039390516 36 1.4000000000 0.0134318229 0.0081141681 0.0152215101 0.0070209945 0.0175290000 106903593 0 402718720 0.0010074640 -0.0110027688 0.0043097888 37 1.4400000000 0.0141834356 0.0082782024 0.0152215101 0.0073873360 0.0180060000 106905841 0 402718720 0.0009466707 -0.0100106020 0.0040910570 38 1.4800000000 0.0138772354 0.0084255454 0.0152215101 0.0092056554 0.0188730000 106908089 0 402718720 0.0029094347 -0.0039842073 0.0040815650 39 1.5200000000 0.0120719103 0.0085190419 0.0152215101 0.0093572448 0.0182560000 106910337 0 402718720 0.0059150970 -0.0064615067 0.0044277660 40 1.5600000000 0.0164566748 0.0087174827 0.0164566748 0.0095293695 0.0186860000 106912585 0 402718720 0.0031999419 -0.0038337675 0.0047206455 41 1.6000000000 0.0147684896 0.0088650683 0.0164566748 0.0095158145 0.0189060000 106914833 0 402718720 0.0067995493 -0.0068542194 0.0052167103 42 1.6400000000 0.0146906991 0.0090037737 0.0164566748 0.0096680129 0.0518780000 106917081 0 402718720 0.0099841142 -0.0040979721 0.0049299602 43 1.6800000000 0.0176614784 0.0092051157 0.0176614784 0.0099642170 0.0209290000 106919329 0 402718720 0.0086385012 -0.0015595873 0.0050202664 44 1.7200000000 0.0187400077 0.0094218178 0.0187400077 0.0101984061 0.0184350000 106921577 0 402718720 0.0084166499 -0.0014294221 0.0053914213 45 1.7600000000 0.0207224842 0.0096729437 0.0207224842 0.0104168733 0.0188970000 106923825 0 402718720 0.0088780830 -0.0022556596 0.0059102187 46 1.8000000000 0.0424402095 0.0103852756 0.0424402095 0.0109944644 0.0185710000 106926073 0 402718720 0.0141265169 -0.0022402413 0.0059006521 47 1.8400000000 0.0901282355 0.0120819343 0.0901282355 0.0118417894 0.0365620000 119264973 0 402718720 0.0268364865 -0.0103489682 0.0065285773 48 1.8800000000 0.0920914859 0.0137488000 0.0920914859 0.0119234748 0.0129400000 122926829 0 402718720 0.0274492316 -0.0108009921 0.0067929290 49 1.9200000000 0.0939238220 0.0153850249 0.0939238220 0.0120103138 0.0132600000 126121269 0 402718720 0.0280267671 -0.0112577714 0.0072332532 50 1.9600000000 0.0954109058 0.0169855425 0.0954109058 0.0120469146 0.0203860000 126123517 0 402718720 0.0290916990 -0.0113245538 0.0074150302 51 2.0000000000 0.0958849713 0.0185325902 0.0958849713 0.0120448271 0.0158680000 126125765 0 402718720 0.0314911939 -0.0118300905 0.0072714626 52 2.0400000000 0.0983777642 0.0200680743 0.0983777642 0.0120538543 0.0153400000 126128013 0 402718720 0.0322438776 -0.0122684054 0.0075103855 53 2.0800000000 0.0989764929 0.0215569124 0.0989764929 0.0120484754 0.0151150000 126130261 0 402718720 0.0330549143 -0.0127282068 0.0076387515 54 2.1200000000 0.0988628045 0.0229885029 0.0989764929 0.0120118627 0.0160300000 126132509 0 402718720 0.0364427567 -0.0163786728 0.0079330821 55 2.1600000000 0.1004487127 0.0243968704 0.1004487127 0.0121666843 0.0162560000 126134757 0 402718720 0.0383493826 -0.0081814062 0.0058278027 56 2.2000000000 0.1066973433 0.0258665217 0.1066973433 0.0123896700 0.0140410000 126137005 0 402718720 0.0335090533 -0.0152502209 0.0078038904 57 2.2400000000 0.1056254283 0.0272658008 0.1066973433 0.0125034895 0.0148640000 126139253 0 402718720 0.0341918431 -0.0155783100 0.0083240056 58 2.2800000000 0.1071278825 0.0286427332 0.1071278825 0.0126108332 0.0453180000 144973081 0 402718720 0.0347130895 -0.0166208390 0.0084497361 59 2.3200000000 0.1151228026 0.0301084971 0.1151228026 0.0132743371 0.0122120000 148634537 0 402718720 0.0295621920 -0.0287047625 0.0134781310 60 2.3600000000 0.1169582084 0.0315559923 0.1169582084 0.0133791682 0.0117820000 151828977 0 402718720 0.0308929328 -0.0292428825 0.0132753681 61 2.4000000000 0.1176965982 0.0329681334 0.1176965982 0.0135807528 0.0215430000 151831225 0 402718720 0.0321937278 -0.0309426095 0.0135756796 62 2.4400000000 0.1213711053 0.0343939877 0.1213711053 0.0137770642 0.0149760000 151833473 0 402718720 0.0323627479 -0.0324268900 0.0134779317 63 2.4800000000 0.1242517680 0.0358203017 0.1242517680 0.0139514332 0.0146600000 151835721 0 402718720 0.0331000984 -0.0317470022 0.0132808881 64 2.5200000000 0.1254974902 0.0372215078 0.1254974902 0.0139962642 0.0149900000 151837969 0 402718720 0.0356157981 -0.0324344747 0.0128259249 65 2.5600000000 0.1294420511 0.0386402854 0.1294420511 0.0140858189 0.0145450000 151846873 0 402718720 0.0359970480 -0.0328251719 0.0127754472 66 2.6000000000 0.1339453608 0.0400843017 0.1339453608 0.0141371194 0.0447360000 164165561 0 402718720 0.0363741592 -0.0339016691 0.0124892229 67 2.6400000000 0.1336754411 0.0414811844 0.1339453608 0.0142725688 0.0116870000 167827833 0 402718720 0.0396133661 -0.0273474865 0.0106952870 68 2.6800000000 0.1371727437 0.0428884132 0.1371727437 0.0143312588 0.0212460000 171022273 0 402718720 0.0411203764 -0.0290026311 0.0099499160 69 2.7200000000 0.1395255029 0.0442889507 0.1395255029 0.0143973991 0.0151200000 171024521 0 402718720 0.0423226692 -0.0297610126 0.0096210623 70 2.7600000000 0.1405808181 0.0456645488 0.1405808181 0.0145417108 0.0150410000 171026769 0 402718720 0.0436272509 -0.0287103318 0.0095325718 71 2.8000000000 0.1349863857 0.0469226028 0.1405808181 0.0145809963 0.0147420000 171029017 0 402718720 0.0532008745 -0.0282456782 0.0064648762 72 2.8400000000 0.1475342363 0.0483199866 0.1475342363 0.0149919145 0.0143550000 171031265 0 402718720 0.0442540161 -0.0323285125 0.0095680691 73 2.8800000000 0.1484009326 0.0496909585 0.1484009326 0.0150687912 0.0132860000 171033513 0 402718720 0.0457451344 -0.0325692482 0.0087101711 74 2.9200000000 0.1513331532 0.0510645017 0.1513331532 0.0151065852 0.0134300000 171035761 0 402718720 0.0475019626 -0.0320047475 0.0077049984 75 2.9600000000 0.1529542953 0.0524230323 0.1529542953 0.0152289771 0.0136910000 171038009 0 402718720 0.0476320200 -0.0329112113 0.0076879403 76 3.0000000000 0.1574505568 0.0538049734 0.1574505568 0.0152181965 0.0136640000 171040257 0 402718720 0.0485516451 -0.0335198157 0.0070531545 77 3.0400000000 0.1598505527 0.0551821887 0.1598505527 0.0152520544 0.0160080000 171042505 0 402718720 0.0494067296 -0.0336155817 0.0063704178 78 3.0800000000 0.1646061540 0.0565850600 0.1646061540 0.0152452923 0.0146620000 171044753 0 402718720 0.0500196815 -0.0373736396 0.0062180050 79 3.1200000000 0.1672827452 0.0579862966 0.1672827452 0.0152604893 0.0129070000 171047001 0 402718720 0.0515838265 -0.0363148935 0.0050178119 80 3.1600000000 0.1746612936 0.0594447340 0.1746612936 0.0155804207 0.0168480000 171049249 0 402718720 0.0537601784 -0.0380486846 0.0032773581 81 3.2000000000 0.1778192222 0.0609061475 0.1778192222 0.0155781192 0.0152710000 171051497 0 402718720 0.0550336204 -0.0388798900 0.0028580870 82 3.2400000000 0.1805500537 0.0623652195 0.1805500537 0.0155523083 0.0450750000 183356525 0 402718720 0.0560129732 -0.0394697487 0.0025839738 83 3.2800000000 0.1828808188 0.0638172147 0.1828808188 0.0155666310 0.0133540000 187017981 0 402718720 0.0570341200 -0.0382818468 0.0015101606 84 3.3200000000 0.1843397617 0.0652520069 0.1843397617 0.0155313020 0.0202570000 190212421 0 402718720 0.0580961965 -0.0390835032 0.0012673653 85 3.3600000000 0.1874794513 0.0666899768 0.1874794513 0.0155239184 0.0170690000 190214669 0 402718720 0.0587836914 -0.0401238427 0.0010436611 86 3.4000000000 0.1896828264 0.0681201262 0.1896828264 0.0155310613 0.0166110000 190216917 0 402718720 0.0588459373 -0.0402453691 0.0007481099 87 3.4400000000 0.1928208619 0.0695534680 0.1928208619 0.0155340306 0.0163430000 190219165 0 402718720 0.0597696714 -0.0416923426 0.0003268212 88 3.4800000000 0.1962620020 0.0709933377 0.1962620020 0.0155509745 0.0155620000 190221413 0 402718720 0.0605591834 -0.0427341945 -0.0000076216 89 3.5200000000 0.1987060755 0.0724283123 0.1987060755 0.0155381845 0.0151730000 190223661 0 402718720 0.0610834956 -0.0432689562 -0.0009307143 90 3.5600000000 0.2008892745 0.0738556563 0.2008892745 0.0155269044 0.0152130000 190225909 0 402718720 0.0615000539 -0.0441871658 -0.0010631203 91 3.6000000000 0.2033597827 0.0752787786 0.2033597827 0.0155310098 0.0146550000 190228157 0 402718720 0.0619715825 -0.0446623079 -0.0009372078 92 3.6400000000 0.2058611363 0.0766981521 0.2058611363 0.0155133070 0.0152940000 190230405 0 402718720 0.0627843812 -0.0441636443 -0.0016591453 93 3.6800000000 0.2069817632 0.0780990511 0.2069817632 0.0154642406 0.0178350000 190232653 0 402718720 0.0641535744 -0.0466014929 -0.0023309330 94 3.7200000000 0.2086866349 0.0794882807 0.2086866349 0.0154135957 0.0158970000 190234901 0 402718720 0.0654644743 -0.0499802977 -0.0020686050 95 3.7600000000 0.2109864056 0.0808724715 0.2109864056 0.0153630014 0.0144580000 190237149 0 402718720 0.0666403770 -0.0510469601 -0.0029123267 96 3.8000000000 0.2145563811 0.0822650122 0.2145563811 0.0153140073 0.0216330000 190239397 0 402718720 0.0662108660 -0.0514454544 -0.0031637726 97 3.8400000000 0.2173414081 0.0836575524 0.2173414081 0.0152706528 0.0195990000 190241645 0 402718720 0.0662759095 -0.0527078956 -0.0033521913 98 3.8800000000 0.2175050676 0.0850233434 0.2175050676 0.0152299089 0.0498380000 202550049 0 402718720 0.0668570250 -0.0504183918 -0.0042468188 99 3.9200000000 0.2198337018 0.0863850642 0.2198337018 0.0151672599 0.0155190000 206211505 0 402718720 0.0675121322 -0.0506629236 -0.0052662040 100 3.9600000000 0.2206612080 0.0877278256 0.2206612080 0.0151080679 0.0157200000 209405945 0 402718720 0.0684209540 -0.0516004600 -0.0056986744 101 4.0000000000 0.2231639326 0.0890687771 0.2231639326 0.0150572137 0.0257100000 209408193 0 402718720 0.0689259991 -0.0539091602 -0.0055155624 102 4.0400000000 0.2240339071 0.0903919647 0.2240339071 0.0150032826 0.0170650000 209410441 0 402718720 0.0700700656 -0.0528047904 -0.0070454380 103 4.0800000000 0.2268296927 0.0917166028 0.2268296927 0.0149646592 0.0150690000 209412689 0 402718720 0.0701438040 -0.0540131480 -0.0064487397 104 4.1200000000 0.2305829078 0.0930518558 0.2305829078 0.0149173031 0.0151490000 209414937 0 402718720 0.0687673315 -0.0574226305 -0.0057166624 105 4.1600000000 0.2313056290 0.0943685584 0.2313056290 0.0148719133 0.0149520000 209417185 0 402718720 0.0709249005 -0.0552412458 -0.0069589722 106 4.2000000000 0.2318626493 0.0956656724 0.2318626493 0.0148141802 0.0151180000 209419433 0 402718720 0.0717778876 -0.0543770231 -0.0083897496 107 4.2400000000 0.2324980646 0.0969444798 0.2324980646 0.0147494960 0.0162300000 209421681 0 402718720 0.0721071213 -0.0546353534 -0.0086494042 108 4.2800000000 0.2352567613 0.0982251491 0.2352567613 0.0146880556 0.0162820000 209423929 0 402718720 0.0736140311 -0.0555058718 -0.0099538621 109 4.3200000000 0.2365678847 0.0994943485 0.2365678847 0.0146205475 0.0149030000 209426177 0 402718720 0.0741460174 -0.0556534193 -0.0104507199 110 4.3600000000 0.2374698371 0.1007486711 0.2374698371 0.0145556037 0.0193570000 209428425 0 402718720 0.0743918270 -0.0557503253 -0.0109492093 111 4.4000000000 0.2388073057 0.1019924426 0.2388073057 0.0144913924 0.0163800000 209430673 0 402718720 0.0749417022 -0.0563683473 -0.0108925616 112 4.4400000000 0.2412775755 0.1032360599 0.2412775755 0.0144344779 0.0176270000 209432921 0 402718720 0.0752247274 -0.0566926636 -0.0122273341 113 4.4800000000 0.2422103733 0.1044659211 0.2422103733 0.0143714401 0.0196310000 209435169 0 402718720 0.0759595707 -0.0570170321 -0.0128244339 114 4.5200000000 0.2428155839 0.1056795146 0.2428155839 0.0143086444 0.0181270000 209437417 0 402718720 0.0765583888 -0.0571088530 -0.0135327363 115 4.5600000000 0.2440994978 0.1068831666 0.2440994978 0.0142498820 0.0171410000 209439665 0 402718720 0.0771284699 -0.0578095503 -0.0142088570 116 4.6000000000 0.2448794097 0.1080727894 0.2448794097 0.0141930253 0.0170860000 209441913 0 402718720 0.0771512315 -0.0573296025 -0.0145984041 117 4.6400000000 0.2457497120 0.1092495152 0.2457497120 0.0141526973 0.0182400000 209444161 0 402718720 0.0777430758 -0.0578494743 -0.0155286919 118 4.6800000000 0.2465330809 0.1104129353 0.2465330809 0.0141192393 0.0165300000 209446409 0 402718720 0.0777593255 -0.0585516095 -0.0153577831 119 4.7200000000 0.2461177409 0.1115533118 0.2465330809 0.0140790718 0.0198710000 209448657 0 402718720 0.0786343962 -0.0585875995 -0.0162202902 120 4.7600000000 0.2458557934 0.1126724992 0.2465330809 0.0140319294 0.0187810000 209450905 0 402718720 0.0792348310 -0.0589804240 -0.0170629732 121 4.8000000000 0.2460161597 0.1137745129 0.2465330809 0.0139853144 0.0165090000 209453153 0 402718720 0.0783879533 -0.0584701523 -0.0164579917 122 4.8400000000 0.2456259578 0.1148552624 0.2465330809 0.0139574791 0.0209070000 209455401 0 402718720 0.0789257064 -0.0588850081 -0.0172683336 123 4.8800000000 0.2443057448 0.1159077054 0.2465330809 0.0139115888 0.0205050000 209457649 0 402718720 0.0795500129 -0.0593390800 -0.0182244387 124 4.9200000000 0.2439070940 0.1169399585 0.2465330809 0.0138701439 0.0202390000 209459897 0 402718720 0.0794271380 -0.0590832084 -0.0181884747 125 4.9600000000 0.2437229902 0.1179542228 0.2465330809 0.0138293650 0.0215030000 209462145 0 402718720 0.0795105174 -0.0595059358 -0.0182045139 126 5.0000000000 0.2434357554 0.1189501079 0.2465330809 0.0137898872 0.0181030000 209464393 0 402718720 0.0800673738 -0.0601659119 -0.0186217353 127 5.0400000000 0.2420881391 0.1199196987 0.2465330809 0.0137610048 0.0179480000 209466641 0 402718720 0.0804255232 -0.0608190335 -0.0187688507 128 5.0800000000 0.2417284995 0.1208713300 0.2465330809 0.0137329922 0.0186010000 209468889 0 402718720 0.0803015530 -0.0611618124 -0.0185942892 129 5.1200000000 0.2419788986 0.1218101484 0.2465330809 0.0137066074 0.0196950000 209484449 0 402718720 0.0809318423 -0.0620184019 -0.0190418195 130 5.1600000000 0.2400106490 0.1227193830 0.2465330809 0.0136815478 0.0181870000 209512297 0 402718720 0.0808187127 -0.0614043884 -0.0188398063 131 5.2000000000 0.2381397486 0.1236004545 0.2465330809 0.0136597819 0.0167290000 209514545 0 402718720 0.0806330293 -0.0617779195 -0.0185845569 132 5.2400000000 0.2364225239 0.1244551671 0.2465330809 0.0136377858 0.0169540000 209516793 0 402718720 0.0803558826 -0.0618185923 -0.0183642264 133 5.2800000000 0.2357420325 0.1252919105 0.2465330809 0.0136067977 0.0166930000 209519041 0 402718720 0.0797891766 -0.0615524054 -0.0172419120 134 5.3200000000 0.2350672930 0.1261111297 0.2465330809 0.0135663784 0.0157420000 209521289 0 402718720 0.0786384568 -0.0603893511 -0.0161341242 135 5.3600000000 0.2315375507 0.1268920662 0.2465330809 0.0135322060 0.0187240000 209523537 0 402718720 0.0793879703 -0.0616969317 -0.0165434964 136 5.4000000000 0.2304175198 0.1276532828 0.2465330809 0.0134986320 0.0166320000 209525785 0 402718720 0.0793392286 -0.0614018366 -0.0160743278 137 5.4400000000 0.2296003997 0.1283974223 0.2465330809 0.0134669925 0.0160140000 209528033 0 402718720 0.0801245645 -0.0623810925 -0.0155084552 138 5.4800000000 0.2267442197 0.1291100802 0.2465330809 0.0135234128 0.0170820000 209530281 0 402718720 0.0783313662 -0.0606524572 -0.0145304976 139 5.5200000000 0.2245360166 0.1297965978 0.2465330809 0.0134929262 0.0178450000 209532529 0 402718720 0.0781840533 -0.0608521104 -0.0144013595 140 5.5600000000 0.2238007784 0.1304680562 0.2465330809 0.0134746509 0.0470330000 209534777 0 402718720 0.0783040822 -0.0609407350 -0.0140330428 141 5.6000000000 0.2225115746 0.1311208471 0.2465330809 0.0134505798 0.0203600000 209537025 0 402718720 0.0781086311 -0.0610457659 -0.0137441261 142 5.6400000000 0.2206490934 0.1317513277 0.2465330809 0.0134251028 0.0157550000 209539273 0 402718720 0.0797475427 -0.0618116260 -0.0132543286 143 5.6800000000 0.2185878605 0.1323585762 0.2465330809 0.0134146550 0.0160320000 209541521 0 402718720 0.0798173025 -0.0629006699 -0.0130804740 144 5.7200000000 0.2169678956 0.1329461409 0.2465330809 0.0133822442 0.0159620000 209543769 0 402718720 0.0787467584 -0.0625387281 -0.0124344258 145 5.7600000000 0.2155357748 0.1335157246 0.2465330809 0.0133516673 0.0159290000 209546017 0 402718720 0.0793174133 -0.0625387505 -0.0123836566 146 5.8000000000 0.2146682590 0.1340715639 0.2465330809 0.0133215596 0.0171870000 209548265 0 402718720 0.0777510107 -0.0618676506 -0.0120600043 147 5.8400000000 0.2129684985 0.1346082777 0.2465330809 0.0132949700 0.0158730000 209550513 0 402718720 0.0769127756 -0.0620287694 -0.0106823444 148 5.8800000000 0.2125549018 0.1351349441 0.2465330809 0.0132750961 0.0158700000 209552761 0 402718720 0.0761487931 -0.0620372482 -0.0105206184 149 5.9200000000 0.2105457038 0.1356410566 0.2465330809 0.0132496984 0.0157130000 209555009 0 402718720 0.0746750459 -0.0617955215 -0.0096619660 150 5.9600000000 0.2072833031 0.1361186716 0.2465330809 0.0132246877 0.0156330000 209557257 0 402718720 0.0734090954 -0.0611932538 -0.0087273484 151 6.0000000000 0.2048266232 0.1365736911 0.2465330809 0.0131928596 0.0166480000 209559505 0 402718720 0.0714116544 -0.0601286776 -0.0087435907 152 6.0400000000 0.2013279349 0.1369997059 0.2465330809 0.0131720852 0.0184220000 209561753 0 402718720 0.0704425648 -0.0589877367 -0.0080023026 153 6.0800000000 0.1982754767 0.1374002011 0.2465330809 0.0131485490 0.0165600000 209564001 0 402718720 0.0697902739 -0.0583753996 -0.0074360748 154 6.1200000000 0.1962814778 0.1377825471 0.2465330809 0.0131368716 0.0167550000 209566249 0 402718720 0.0695117936 -0.0584141649 -0.0072346013 155 6.1600000000 0.1932562888 0.1381404422 0.2465330809 0.0131221354 0.0159200000 209568497 0 402718720 0.0677679777 -0.0581902675 -0.0063242060 156 6.2000000000 0.1897326708 0.1384711616 0.2465330809 0.0131079731 0.0164750000 209570745 0 402718720 0.0668089762 -0.0577164553 -0.0055783354 157 6.2400000000 0.1887833327 0.1387916213 0.2465330809 0.0130943608 0.0159510000 209572993 0 402718720 0.0643436462 -0.0575028248 -0.0044950838 158 6.2800000000 0.1907440424 0.1391204341 0.2465330809 0.0130975662 0.0169970000 209575241 0 402718720 0.0601500645 -0.0580579266 -0.0027990462 159 6.3200000000 0.1926106662 0.1394568506 0.2465330809 0.0131015854 0.0170890000 209577489 0 402718720 0.0551734455 -0.0597408600 -0.0006553043 160 6.3600000000 0.1866455227 0.1397517798 0.2465330809 0.0131107410 0.0169340000 209579737 0 402718720 0.0591727830 -0.0604009368 -0.0020258394 161 6.4000000000 0.1879718304 0.1400512832 0.2465330809 0.0131240749 0.0144690000 209581985 0 402718720 0.0575498901 -0.0639633611 -0.0000598561 162 6.4400000000 0.1867232621 0.1403393819 0.2465330809 0.0131216936 0.0399610000 209584233 0 402718720 0.0542520173 -0.0637728050 0.0016828112 163 6.4800000000 0.1839866787 0.1406071567 0.2465330809 0.0131250406 0.0179570000 209586481 0 402718720 0.0535685308 -0.0655228347 0.0018671441 164 6.5200000000 0.1813008934 0.1408552892 0.2465330809 0.0131067357 0.0148230000 209588729 0 402718720 0.0508664809 -0.0624015369 0.0026773862 165 6.5600000000 0.1739520282 0.1410558755 0.2465330809 0.0130927205 0.0156790000 209590977 0 402718720 0.0540575534 -0.0587576851 0.0007649975 166 6.6000000000 0.1691784114 0.1412252884 0.2465330809 0.0130865691 0.0155790000 209593225 0 402718720 0.0522039942 -0.0579792522 0.0007936138 167 6.6400000000 0.1663484275 0.1413757264 0.2465330809 0.0131040217 0.0148630000 209595473 0 402718720 0.0506355427 -0.0568799414 0.0025124731 168 6.6800000000 0.1647391468 0.1415147943 0.2465330809 0.0131029010 0.0349020000 209597721 0 402718720 0.0502654463 -0.0578089878 0.0024418095 169 6.7200000000 0.1617181748 0.1416343410 0.2465330809 0.0131351679 0.0199130000 209599969 0 402718720 0.0487695895 -0.0573138297 0.0032700533 170 6.7600000000 0.1592262536 0.1417378228 0.2465330809 0.0131625472 0.0163000000 209602217 0 402718720 0.0478868149 -0.0586859956 0.0035336325 171 6.8000000000 0.1598698795 0.1418438582 0.2465330809 0.0131499888 0.0164730000 209604465 0 402718720 0.0454952754 -0.0576471761 0.0038159911 172 6.8400000000 0.1591821164 0.1419446621 0.2465330809 0.0131669294 0.0164650000 209606713 0 402718720 0.0447428823 -0.0578116924 0.0042002532 173 6.8800000000 0.1594017446 0.1420455700 0.2465330809 0.0131960820 0.0164250000 209608961 0 402718720 0.0435673036 -0.0579702295 0.0046604858 174 6.9200000000 0.1572500914 0.1421329524 0.2465330809 0.0132280531 0.0172760000 209611209 0 402718720 0.0428782739 -0.0571498275 0.0053153411 175 6.9600000000 0.1573256552 0.1422197678 0.2465330809 0.0132833822 0.0172640000 209613457 0 402718720 0.0435287990 -0.0577367023 0.0052272943 176 7.0000000000 0.1617952585 0.1423309922 0.2465330809 0.0133170751 0.0160230000 209615705 0 402718720 0.0405556038 -0.0594342574 0.0072665815 177 7.0400000000 0.1582341641 0.1424208406 0.2465330809 0.0133503426 0.0174750000 209617953 0 402718720 0.0430897139 -0.0592085049 0.0053352951 178 7.0800000000 0.1571619958 0.1425036561 0.2465330809 0.0134213117 0.0160310000 209620201 0 402718720 0.0435724631 -0.0605017282 0.0062109954 179 7.1200000000 0.1587374657 0.1425943478 0.2465330809 0.0135188144 0.0159990000 209622449 0 402718720 0.0417556688 -0.0643185750 0.0072844415 180 7.1600000000 0.1619086415 0.1427016494 0.2465330809 0.0135458955 0.0153670000 209624697 0 402718720 0.0389269590 -0.0653696880 0.0087931566 181 7.2000000000 0.1601126194 0.1427978426 0.2465330809 0.0135367299 0.0157560000 209626945 0 402718720 0.0372889228 -0.0641923323 0.0079801967 182 7.2400000000 0.1671344042 0.1429315600 0.2465330809 0.0135715733 0.0168680000 209629193 0 402718720 0.0337705836 -0.0693856254 0.0108080562 183 7.2800000000 0.1646188498 0.1430500697 0.2465330809 0.0135519796 0.0172860000 209631441 0 402718720 0.0314623043 -0.0677389875 0.0107985120 184 7.3200000000 0.1637811065 0.1431627384 0.2465330809 0.0135570947 0.0163530000 209633689 0 402718720 0.0310010575 -0.0690796971 0.0114575531 185 7.3600000000 0.1644961089 0.1432780539 0.2465330809 0.0135585486 0.0182680000 209635937 0 402718720 0.0280666854 -0.0718689561 0.0126358243 186 7.4000000000 0.1647557467 0.1433935254 0.2465330809 0.0135843293 0.0182140000 209638185 0 402718720 0.0270217787 -0.0715651661 0.0130870659 187 7.4400000000 0.1636162847 0.1435016685 0.2465330809 0.0136088099 0.0508400000 209640433 0 402718720 0.0260152500 -0.0729525834 0.0137515403 188 7.4800000000 0.1642527729 0.1436120467 0.2465330809 0.0136261449 0.0423280000 221944593 0 402718720 0.0226845611 -0.0740476996 0.0154639464 189 7.5200000000 0.1603418738 0.1437005643 0.2465330809 0.0136646143 0.0117160000 225606049 0 402718720 0.0217692815 -0.0689942762 0.0143561857 190 7.5600000000 0.1581199616 0.1437764559 0.2465330809 0.0137123595 0.0136100000 228800489 0 402718720 0.0201366358 -0.0684801638 0.0148273399 191 7.6000000000 0.1581246257 0.1438515772 0.2465330809 0.0137510386 0.0108850000 228802737 0 402718720 0.0202762187 -0.0684387535 0.0145330522 192 7.6400000000 0.1569532603 0.1439198151 0.2465330809 0.0137721079 0.0203770000 228804985 0 402718720 0.0191764608 -0.0687704608 0.0148707395 193 7.6800000000 0.1568591744 0.1439868584 0.2465330809 0.0138113909 0.0196850000 228807233 0 402718720 0.0187670123 -0.0692102537 0.0150119746 194 7.7200000000 0.1541331410 0.1440391589 0.2465330809 0.0138171768 0.0175170000 228809481 0 402718720 0.0182845015 -0.0686542690 0.0148875928 195 7.7600000000 0.1576704830 0.1441090631 0.2465330809 0.0138388364 0.0224210000 228811729 0 402718720 0.0192359220 -0.0721980035 0.0152947605 196 7.8000000000 0.1558015645 0.1441687187 0.2465330809 0.0138262979 0.0184340000 228813977 0 402718720 0.0180753190 -0.0726644024 0.0152977994 197 7.8400000000 0.1578833163 0.1442383360 0.2465330809 0.0138534317 0.0186230000 228816225 0 402718720 0.0187255610 -0.0720483512 0.0152392657 198 7.8800000000 0.1570608765 0.1443030963 0.2465330809 0.0138628637 0.0183410000 228818473 0 402718720 0.0191053040 -0.0730080903 0.0151845003 199 7.9200000000 0.1588901728 0.1443763982 0.2465330809 0.0139119997 0.0154630000 228820721 0 402718720 0.0214730240 -0.0722680762 0.0146839945 200 7.9600000000 0.1587755680 0.1444483940 0.2465330809 0.0139115837 0.0167500000 228822969 0 402718720 0.0191982631 -0.0698670968 0.0145605840 201 8.0000000000 0.1611364931 0.1445314194 0.2465330809 0.0139587786 0.0169670000 228825217 0 402718720 0.0207102615 -0.0722508207 0.0148017816 202 8.0400000000 0.1601850241 0.1446089125 0.2465330809 0.0139554037 0.0181220000 228827465 0 402718720 0.0201846715 -0.0719638541 0.0147412447 203 8.0800000000 0.1579537988 0.1446746508 0.2465330809 0.0139306902 0.0172450000 228829713 0 402718720 0.0191162489 -0.0696273595 0.0143487947 204 8.1200000000 0.1621221602 0.1447601778 0.2465330809 0.0139154651 0.0182510000 228831961 0 402718720 0.0190059897 -0.0741328374 0.0153718712 205 8.1600000000 0.1584700793 0.1448270554 0.2465330809 0.0138954230 0.0163210000 228834209 0 402718720 0.0193557348 -0.0733670145 0.0152032729 206 8.1999999990 0.1554611325 0.1448786771 0.2465330809 0.0138812958 0.0162280000 228836457 0 402718720 0.0173462946 -0.0723201707 0.0160890371 207 8.2400000000 0.1555535346 0.1449302465 0.2465330809 0.0138659987 0.0165870000 228838705 0 402718720 0.0156903565 -0.0711385533 0.0163251609 208 8.2799999990 0.1535988152 0.1449719223 0.2465330809 0.0139019943 0.0158040000 228840953 0 402718720 0.0164002683 -0.0718100816 0.0171461795 209 8.3200000000 0.1532643884 0.1450115992 0.2465330809 0.0139045725 0.0158250000 228843201 0 402718720 0.0156984720 -0.0705724806 0.0173372887 210 8.3599999990 0.1540321261 0.1450545541 0.2465330809 0.0139143663 0.0160780000 228845449 0 402718720 0.0152737089 -0.0706987455 0.0169694331 211 8.4000000000 0.1548807472 0.1451011237 0.2465330809 0.0139524381 0.0167850000 228847697 0 402718720 0.0133228768 -0.0715729520 0.0179725066 212 8.4399999990 0.1565067321 0.1451549237 0.2465330809 0.0140253357 0.0169510000 228849945 0 402718720 0.0130752064 -0.0759056360 0.0202291813 213 8.4800000000 0.1516742557 0.1451855309 0.2465330809 0.0140183016 0.0170590000 228852193 0 402718720 0.0121297790 -0.0713557079 0.0186981112 214 8.5200000000 0.1534579396 0.1452241870 0.2465330809 0.0140394135 0.0171670000 228854441 0 402718720 0.0095316973 -0.0725202113 0.0201772861 215 8.5600000000 0.1485129744 0.1452394837 0.2465330809 0.0140760311 0.0377990000 241156405 0 402718720 0.0104079023 -0.0700346902 0.0197074804 216 8.6000000000 0.1397010535 0.1452138429 0.2465330809 0.0141117579 0.0114820000 244819541 0 402718720 0.0186595134 -0.0603211969 0.0164927207 217 8.6400000000 0.1414964348 0.1451967119 0.2465330809 0.0141210345 0.0105180000 248013981 0 402718720 0.0181007162 -0.0611788779 0.0169005841 218 8.6800000000 0.1473576725 0.1452066246 0.2465330809 0.0141642928 0.0523670000 248016229 0 402718720 0.0176937394 -0.0671490878 0.0198142100 219 8.7200000000 0.1470543146 0.1452150615 0.2465330809 0.0142424087 0.0249110000 248018477 0 402718720 0.0213780012 -0.0693755895 0.0206483584 220 8.7600000000 0.1449974477 0.1452140724 0.2465330809 0.0142887088 0.0240010000 248020725 0 402718720 0.0239713341 -0.0707970783 0.0221157372 221 8.8000000000 0.1436633021 0.1452070553 0.2465330809 0.0143016940 0.0201520000 248022973 0 402718720 0.0222930945 -0.0661190823 0.0224666242 222 8.8400000000 0.1469725668 0.1452150081 0.2465330809 0.0143119449 0.0555250000 260331613 0 402718720 0.0175569002 -0.0654228553 0.0234361663 223 8.8800000000 0.1439739466 0.1452094428 0.2465330809 0.0143469352 0.0303880000 263993069 0 402718720 0.0172176436 -0.0633686408 0.0249643438 224 8.9200000000 0.1421566904 0.1451958144 0.2465330809 0.0143505562 0.0171850000 267187509 0 402718720 0.0141730402 -0.0618905872 0.0253397189 225 8.9600000000 0.1202301085 0.1450848557 0.2465330809 0.0144550605 0.0241010000 267189757 0 402718720 0.0033620631 -0.0620138124 0.0197462197 226 9.0000000000 0.1212108806 0.1449792187 0.2465330809 0.0144497323 0.0229880000 267192005 0 402718720 0.0020023147 -0.0623133071 0.0191536695 227 9.0400000000 0.1186865494 0.1448633919 0.2465330809 0.0144563563 0.0224010000 267194253 0 402718720 0.0009423252 -0.0619271994 0.0193896219 228 9.0800000000 0.1165006831 0.1447389941 0.2465330809 0.0144572892 0.0209240000 267196501 0 402718720 -0.0000675622 -0.0609214120 0.0191685557 229 9.1200000000 0.1143818498 0.1446064301 0.2465330809 0.0144612895 0.0201270000 267198749 0 402718720 -0.0011428396 -0.0607878305 0.0188961849 230 9.1600000000 0.1130069494 0.1444690411 0.2465330809 0.0144627112 0.0189410000 267200997 0 402718720 -0.0026842144 -0.0605039112 0.0189261455 231 9.2000000000 0.1109035015 0.1443237357 0.2465330809 0.0144750366 0.0177540000 267203245 0 402718720 -0.0026897176 -0.0604183190 0.0182124730 232 9.2400000000 0.1096731871 0.1441743799 0.2465330809 0.0144734419 0.0625520000 279518093 0 402718720 -0.0043770266 -0.0605833828 0.0185508411 233 9.2800000000 0.1033487692 0.1439991627 0.2465330809 0.0144982134 0.0154030000 283179549 0 402718720 -0.0026420832 -0.0546636805 0.0169496760 234 9.3200000000 0.1021435410 0.1438202925 0.2465330809 0.0144958695 0.0150140000 286373989 0 402718720 -0.0037300980 -0.0544850342 0.0163989179 235 9.3600000000 0.1005750522 0.1436362702 0.2465330809 0.0145155143 0.0294820000 286376237 0 402718720 -0.0044073984 -0.0542318225 0.0162266232 236 9.4000000000 0.0991766900 0.1434478822 0.2465330809 0.0145532587 0.0238420000 286378485 0 402718720 -0.0050411285 -0.0544738434 0.0161151774 237 9.4400000000 0.0960791484 0.1432480141 0.2465330809 0.0145905679 0.0232620000 286380733 0 402718720 -0.0059273602 -0.0545060821 0.0159535557 238 9.4800000000 0.0917994082 0.1430318435 0.2465330809 0.0146203627 0.0227370000 286382981 0 402718720 -0.0073247380 -0.0544950031 0.0159177240 239 9.5200000000 0.0916495547 0.1428168548 0.2465330809 0.0146324043 0.0223400000 286385229 0 402718720 -0.0077015553 -0.0545227379 0.0156873930 240 9.5600000000 0.0857573748 0.1425791070 0.2465330809 0.0148176052 0.0701810000 298695993 0 402718720 -0.0088394936 -0.0550524220 0.0160350334 241 9.6000000000 0.0834281519 0.1423336673 0.2465330809 0.0148107587 0.0144690000 302357449 0 402718720 -0.0116578564 -0.0523132756 0.0152750332 242 9.6400000000 0.0807584524 0.1420792243 0.2465330809 0.0148345709 0.0124190000 305551889 0 402718720 -0.0114214141 -0.0523079149 0.0153085869 243 9.6800000000 0.0780256242 0.1418156293 0.2465330809 0.0148571657 0.0120690000 305554137 0 402718720 -0.0117324544 -0.0524195842 0.0151075954 244 9.7200000000 0.0773712173 0.1415515128 0.2465330809 0.0148657802 0.0130560000 305556385 0 402718720 -0.0125156380 -0.0526547469 0.0153128803 245 9.7600000000 0.0779527649 0.1412919261 0.2465330809 0.0148607580 0.0298010000 305558633 0 402718720 -0.0134216193 -0.0527076609 0.0152838947 246 9.8000000000 0.0764192492 0.1410282160 0.2465330809 0.0148659267 0.0264030000 305560881 0 402718720 -0.0138459140 -0.0528210066 0.0151893822 247 9.8400000000 0.0754641369 0.1407627744 0.2465330809 0.0148703740 0.0760970000 317873409 0 402718720 -0.0147104608 -0.0527216010 0.0148546016 248 9.8800000000 0.0715920776 0.1404838603 0.2465330809 0.0148827816 0.0115510000 321534865 0 402718720 -0.0153214652 -0.0522925444 0.0149115920 249 9.9200000000 0.0687415674 0.1401957386 0.2465330809 0.0148870088 0.0236200000 324729305 0 402718720 -0.0161146279 -0.0525162742 0.0141008887 250 9.9600000000 0.0686576441 0.1399095863 0.2465330809 0.0148785870 0.0294470000 324731553 0 402718720 -0.0167079289 -0.0524816327 0.0138659701 251 10.0000000000 0.0667906627 0.1396182758 0.2465330809 0.0148787437 0.0286500000 324733801 0 402718720 -0.0179346744 -0.0527846664 0.0135019375 252 10.0400000000 0.0651525483 0.1393227769 0.2465330809 0.0148838885 0.0271820000 324736049 0 402718720 -0.0186916403 -0.0529533289 0.0129616009 253 10.0800000000 0.0645577610 0.1390272630 0.2465330809 0.0148795644 0.0259910000 324738297 0 402718720 -0.0193272233 -0.0527808294 0.0125400499 254 10.1200000000 0.0630229637 0.1387280335 0.2465330809 0.0148760231 0.0755300000 337050509 0 402718720 -0.0200633816 -0.0528482608 0.0123016201 255 10.1600000000 0.0631970540 0.1384318335 0.2465330809 0.0148711922 0.0110610000 340711965 0 402718720 -0.0209219679 -0.0536057912 0.0120068137 256 10.2000000000 0.0622917637 0.1381344114 0.2465330809 0.0148723091 0.0116980000 343906405 0 402718720 -0.0207983442 -0.0535273105 0.0116963265 257 10.2400000000 0.0603009388 0.1378315574 0.2465330809 0.0149802089 0.0308510000 343935277 0 402718720 -0.0221482236 -0.0540889055 0.0112866778 258 10.2800000000 0.0606101342 0.1375322496 0.2465330809 0.0149837691 0.0311770000 343988725 0 402718720 -0.0226093605 -0.0544239543 0.0107637551 259 10.3200000000 0.0603147484 0.1372341125 0.2465330809 0.0149720889 0.0288560000 343990973 0 402718720 -0.0233230609 -0.0545329414 0.0104924636 260 10.3600000000 0.0595151857 0.1369351936 0.2465330809 0.0149599167 0.0295570000 343993221 0 402718720 -0.0240009148 -0.0548584275 0.0100525441 261 10.4000000000 0.0593778603 0.1366380390 0.2465330809 0.0149409627 0.0277540000 343995469 0 402718720 -0.0240709949 -0.0552845746 0.0093527455 262 10.4400000000 0.0593795702 0.1363431594 0.2465330809 0.0149223647 0.0268350000 343997717 0 402718720 -0.0245367419 -0.0560881756 0.0089894701 263 10.4800000000 0.0591316000 0.1360495793 0.2465330809 0.0149029464 0.0272420000 343999965 0 402718720 -0.0252142828 -0.0561055467 0.0083299903 264 10.5200000000 0.0592808798 0.1357587888 0.2465330809 0.0148860927 0.0911200000 356337589 0 402718720 -0.0253489036 -0.0568604842 0.0080708740 265 10.5600000000 0.0598631240 0.1354723900 0.2465330809 0.0148794532 0.0107610000 359999045 0 402718720 -0.0254205726 -0.0565713421 0.0079816822 266 10.6000000000 0.0607326292 0.1351914135 0.2465330809 0.0148781256 0.0171990000 363193485 0 402718720 -0.0250988547 -0.0575038120 0.0071895728 267 10.6400000000 0.0610414594 0.1349136983 0.2465330809 0.0148745451 0.0260540000 363195733 0 402718720 -0.0259523820 -0.0569145679 0.0067223394 268 10.6800000000 0.0618877374 0.1346412134 0.2465330809 0.0148832924 0.0251070000 363197981 0 402718720 -0.0260805320 -0.0575406589 0.0058542332 269 10.7200000000 0.0625114590 0.1343730730 0.2465330809 0.0148934177 0.0257780000 363200229 0 402718720 -0.0268807951 -0.0582231954 0.0052801520 270 10.7600000000 0.0634087846 0.1341102423 0.2465330809 0.0148934736 0.0243360000 363202477 0 402718720 -0.0283495858 -0.0586155988 0.0045295758 271 10.8000000000 0.0641702637 0.1338521612 0.2465330809 0.0148967988 0.0227760000 363204725 0 402718720 -0.0285031106 -0.0592580512 0.0032625322 272 10.8400000000 0.0650733709 0.1335992980 0.2465330809 0.0149002835 0.0233170000 363206973 0 402718720 -0.0296747964 -0.0600379109 0.0023672928 273 10.8800000000 0.0654767677 0.1333497650 0.2465330809 0.0149096212 0.0212370000 363209221 0 402718720 -0.0310710799 -0.0598652363 0.0012394572 274 10.9200000000 0.0670463890 0.1331077818 0.2465330809 0.0149160890 0.0208400000 363211469 0 402718720 -0.0307210758 -0.0615648217 0.0001784687 275 10.9600000000 0.0670061037 0.1328674121 0.2465330809 0.0149197172 0.0191470000 363213717 0 402718720 -0.0322233848 -0.0610582605 -0.0003447253 276 11.0000000000 0.0691206679 0.1326364456 0.2465330809 0.0149150830 0.0195680000 363215965 0 402718720 -0.0322256759 -0.0621751621 -0.0010418437 277 11.0400000000 0.0734784380 0.1324228788 0.2465330809 0.0152116471 0.0200000000 363218213 0 402718720 -0.0345232151 -0.0641065687 -0.0036002486 278 11.0800000000 0.0749267191 0.1322160581 0.2465330809 0.0151995769 0.0190800000 363220461 0 402718720 -0.0348118320 -0.0652429760 -0.0041918820 279 11.1200000000 0.0756439120 0.1320132905 0.2465330809 0.0151865081 0.0182820000 363222709 0 402718720 -0.0355812423 -0.0666203573 -0.0041891411 280 11.1600000000 0.0760117173 0.1318132849 0.2465330809 0.0151753089 0.0180970000 363224957 0 402718720 -0.0358365029 -0.0666433722 -0.0046107131 281 11.2000000000 0.0762585178 0.1316155811 0.2465330809 0.0151731921 0.0914080000 375534889 0 402718720 -0.0366927348 -0.0669711977 -0.0048599415 282 11.2400000000 0.0803663805 0.1314338464 0.2465330809 0.0151756489 0.0087780000 379196345 0 402718720 -0.0334542878 -0.0710939094 -0.0059346342 283 11.2800000000 0.0806702003 0.1312544695 0.2465330809 0.0151736006 0.0087470000 382390785 0 402718720 -0.0332203209 -0.0714543238 -0.0066578458 284 11.3200000000 0.0815778524 0.1310795519 0.2465330809 0.0151765512 0.0136000000 382393033 0 402718720 -0.0334007144 -0.0717258826 -0.0070045036 285 11.3600000000 0.0822140947 0.1309080941 0.2465330809 0.0151739299 0.0220090000 382395281 0 402718720 -0.0337323621 -0.0719996467 -0.0074233282 286 11.4000000000 0.0828082189 0.1307399127 0.2465330809 0.0151676082 0.0577880000 382397529 0 402718720 -0.0334073640 -0.0726651475 -0.0080667771 287 11.4400000000 0.0833474845 0.1305747823 0.2465330809 0.0151505172 0.0237070000 382399777 0 402718720 -0.0335243046 -0.0732603818 -0.0083104502 288 11.4800000000 0.0840997100 0.1304134105 0.2465330809 0.0151313211 0.0219160000 382402025 0 402718720 -0.0336950943 -0.0735232383 -0.0089337546 289 11.5200000000 0.0843617842 0.1302540624 0.2465330809 0.0151152911 0.0215340000 382404273 0 402718720 -0.0337093025 -0.0746371374 -0.0091220038 290 11.5600000000 0.0847747400 0.1300972371 0.2465330809 0.0151003060 0.0210820000 382406521 0 402718720 -0.0338976234 -0.0746438727 -0.0093450109 291 11.6000000000 0.0848172680 0.1299416358 0.2465330809 0.0150789791 0.0206780000 382408769 0 402718720 -0.0339302532 -0.0748697892 -0.0095758485 292 11.6400000000 0.0856326893 0.1297898929 0.2465330809 0.0150541217 0.0830610000 394728865 0 402718720 -0.0341290236 -0.0755010322 -0.0100472830 293 11.6800000000 0.0882711112 0.1296481905 0.2465330809 0.0150304977 0.0088790000 398390321 0 402718720 -0.0339199752 -0.0778120384 -0.0070825433 294 11.7200000000 0.0887012631 0.1295089153 0.2465330809 0.0150065707 0.0090170000 401584761 0 402718720 -0.0336507410 -0.0780394003 -0.0074762572 295 11.7600000000 0.0884218961 0.1293696373 0.2465330809 0.0149964590 0.0082690000 401587009 0 402718720 -0.0336310342 -0.0783584192 -0.0078121950 296 11.8000000000 0.0884403959 0.1292313628 0.2465330809 0.0149833019 0.0083600000 401589257 0 402718720 -0.0329947025 -0.0777231529 -0.0084242783 297 11.8400000000 0.0892967209 0.1290969027 0.2465330809 0.0149682674 0.0100570000 401591505 0 402718720 -0.0330479778 -0.0787036121 -0.0084302798 298 11.8800000000 0.0913423821 0.1289702097 0.2465330809 0.0150348136 0.0128400000 401593753 0 402718720 -0.0323120542 -0.0786807239 -0.0095430641 299 11.9200000000 0.0926295966 0.1288486692 0.2465330809 0.0150438514 0.0760860000 413912757 0 402718720 -0.0316129029 -0.0780630782 -0.0104799727 300 11.9600000000 0.0928896591 0.1287288058 0.2465330809 0.0150642951 0.0144800000 417577525 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 301 12.0000000000 0.0944327489 0.1286148654 0.2465330809 0.0150565982 0.0059920000 431648317 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 302 12.0400000000 0.0987542346 0.1285159892 0.2465330809 0.0150994877 0.0108430000 434996165 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 303 12.0800000000 0.1012453288 0.1284259870 0.2465330809 0.0150962502 0.0060790000 435074997 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 304 12.1200000000 0.1043273807 0.1283467153 0.2465330809 0.0150893794 0.0041270000 435153829 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 305 12.1600000000 0.1067180037 0.1282758014 0.2465330809 0.0150855412 0.0153900000 435232661 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 306 12.2000000000 0.1087587029 0.1282120201 0.2465330809 0.0150830678 0.0084440000 435311493 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 307 12.2400000000 0.1115336940 0.1281576933 0.2465330809 0.0150877309 0.0108620000 435390325 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 308 12.2800000000 0.1147778779 0.1281142523 0.2465330809 0.0150935098 0.0060640000 435469157 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 309 12.3200000000 0.1184167340 0.1280828688 0.2465330809 0.0150928811 0.0127260000 435547989 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 310 12.3600000000 0.1221056953 0.1280635876 0.2465330809 0.0150888455 0.0086050000 435626821 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 311 12.4000000000 0.1251655072 0.1280542690 0.2465330809 0.0150839086 0.0108760000 435705653 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 312 12.4400000000 0.1281966567 0.1280547253 0.2465330809 0.0150740875 0.0057580000 435784485 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 313 12.4800000000 0.1311919540 0.1280647484 0.2465330809 0.0150638553 0.0077350000 435863317 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 314 12.5200000000 0.1337124109 0.1280827346 0.2465330809 0.0150535896 0.0059340000 435942149 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 315 12.5600000000 0.1366705447 0.1281099975 0.2465330809 0.0150399176 0.0055880000 436020981 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 316 12.6000000000 0.1395959705 0.1281463455 0.2465330809 0.0150246504 0.0058870000 436099813 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 317 12.6400000000 0.1425103396 0.1281916578 0.2465330809 0.0150083371 0.0051060000 436178645 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 318 12.6800000000 0.1453706175 0.1282456797 0.2465330809 0.0149918736 0.0052690000 436257477 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 319 12.7200000000 0.1506988853 0.1283160659 0.2465330809 0.0149937399 0.0045060000 436336309 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 320 12.7600000000 0.1529811621 0.1283931444 0.2465330809 0.0149749745 0.0146920000 436415141 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 321 12.8000000000 0.1556442827 0.1284780389 0.2465330809 0.0149565786 0.0113570000 436493973 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 322 12.8400000000 0.1582957953 0.1285706406 0.2465330809 0.0149366651 0.0057390000 436572805 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 323 12.8800000000 0.1603449136 0.1286690130 0.2465330809 0.0149194015 0.0039970000 436651637 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 324 12.9200000000 0.1628624946 0.1287745484 0.2465330809 0.0149007010 0.0122810000 436730469 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 325 12.9600000000 0.1650578827 0.1288861894 0.2465330809 0.0148815119 0.0067000000 436809301 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 326 13.0000000000 0.1675166637 0.1290046878 0.2465330809 0.0148631126 0.0061050000 436888133 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 327 13.0400000000 0.1694873571 0.1291284880 0.2465330809 0.0148461040 0.0044620000 436966965 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 328 13.0800000000 0.1716917604 0.1292582541 0.2465330809 0.0148272177 0.0138750000 437045797 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 329 13.1200000000 0.1734180152 0.1293924783 0.2465330809 0.0148120630 0.0074450000 437124629 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 330 13.1600000000 0.1750851274 0.1295309409 0.2465330809 0.0147981289 0.0049650000 437203461 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 331 13.2000000000 0.1766524166 0.1296733018 0.2465330809 0.0147899702 0.0035160000 437282293 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 332 13.2400000000 0.1779024005 0.1298185702 0.2465330809 0.0147826690 0.0155810000 437361125 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 333 13.2800000000 0.1793914884 0.1299674378 0.2465330809 0.0147781173 0.0076690000 437439957 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 334 13.3200000000 0.1817186922 0.1301223817 0.2465330809 0.0148449675 0.0076310000 437518789 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 335 13.3600000000 0.1825394034 0.1302788504 0.2465330809 0.0148490158 0.0039490000 437597621 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 336 13.4000000000 0.1833752245 0.1304368753 0.2465330809 0.0148557668 0.0060320000 437676453 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 337 13.4400000000 0.1841055602 0.1305961296 0.2465330809 0.0148577280 0.0058610000 437755285 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 338 13.4800000000 0.1847868711 0.1307564572 0.2465330809 0.0148627675 0.0032190000 437834117 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 339 13.5200000000 0.1856652945 0.1309184302 0.2465330809 0.0148712913 0.0031610000 437912949 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 340 13.5600000000 0.1859948486 0.1310804197 0.2465330809 0.0148673069 0.0031840000 437991781 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 341 13.6000000000 0.1864609271 0.1312428258 0.2465330809 0.0148631247 0.0034720000 438070613 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 342 13.6400000000 0.1876353770 0.1314077163 0.2465330809 0.0148648086 0.0038820000 438149445 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 343 13.6800000000 0.1883101910 0.1315736128 0.2465330809 0.0148686005 0.0229120000 438228277 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 344 13.7200000000 0.1889528632 0.1317404129 0.2465330809 0.0148765558 0.0074350000 438307109 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 345 13.7600000000 0.1902603805 0.1319100360 0.2465330809 0.0149903216 0.0057200000 438385941 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 346 13.8000000000 0.1908884794 0.1320804939 0.2465330809 0.0149949595 0.0047760000 438464773 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 347 13.8400000000 0.1917915791 0.1322525720 0.2465330809 0.0150019928 0.0060050000 438543605 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 348 13.8800000000 0.1927123070 0.1324263069 0.2465330809 0.0150011214 0.0125180000 438622437 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 349 13.9200000000 0.1937362254 0.1326019800 0.2465330809 0.0149934061 0.0093980000 438701269 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 350 13.9600000000 0.1946030706 0.1327791260 0.2465330809 0.0149974147 0.0057360000 438780101 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 351 14.0000000000 0.1954572499 0.1329576961 0.2465330809 0.0150027057 0.0095870000 438858933 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 352 14.0400000000 0.1962705404 0.1331375622 0.2465330809 0.0150099231 0.0077070000 438937765 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 353 14.0800000000 0.1970430315 0.1333185975 0.2465330809 0.0150238766 0.0073730000 439016597 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 354 14.1200000000 0.1976196170 0.1335002388 0.2465330809 0.0150337562 0.0090200000 439095429 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 355 14.1600000000 0.1982286125 0.1336825722 0.2465330809 0.0150340560 0.0107270000 439174261 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 356 14.2000000000 0.1991688162 0.1338665223 0.2465330809 0.0150328457 0.0062760000 439253093 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 357 14.2400000000 0.1997102797 0.1340509586 0.2465330809 0.0150307266 0.0087630000 439331925 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 358 14.2800000000 0.2000804991 0.1342353987 0.2465330809 0.0150337806 0.0075030000 439410757 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 359 14.3200000000 0.2005703896 0.1344201758 0.2465330809 0.0150399607 0.0152840000 439489589 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 360 14.3600000000 0.2010833919 0.1346053514 0.2465330809 0.0150410462 0.0149240000 439568421 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 361 14.4000000000 0.2013195008 0.1347901552 0.2465330809 0.0150396979 0.0258800000 439647253 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 362 14.4400000000 0.2015372813 0.1349745395 0.2465330809 0.0150487126 0.0209440000 439649781 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 363 14.4800000000 0.2015304863 0.1351578892 0.2465330809 0.0150610755 0.0114440000 439651789 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 364 14.5200000000 0.2020452917 0.1353416458 0.2465330809 0.0150736210 0.0041090000 439730621 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 365 14.5600000000 0.2020181268 0.1355243211 0.2465330809 0.0150915089 0.0034240000 439809453 0 402718720 -0.0324846879 -0.0755208805 -0.0105145480 366 14.6000000000 0.1826855540 0.1356531769 0.2465330809 0.0666154114 0.0086880000 439888285 0 402718720 -0.0911621824 -0.0414749384 0.0173530802 367 14.6400000000 0.1846195757 0.1357866004 0.2465330809 0.0665687503 0.0181730000 429011933 0 402718720 -0.0886605829 -0.0392052606 0.0193839613 368 14.6800000000 0.1856525987 0.1359221058 0.2465330809 0.0664929256 0.0284020000 429014181 0 402718720 -0.0872029066 -0.0419834331 0.0205486473 369 14.7200000000 0.1813320965 0.1360451681 0.2465330809 0.0664271863 0.0156250000 429016429 0 402718720 -0.0884613246 -0.0390168764 0.0185799245 370 14.7600000000 0.1808755994 0.1361663314 0.2465330809 0.0663499971 0.0170530000 429018677 0 402718720 -0.0919916481 -0.0403758474 0.0210988447 371 14.8000000000 0.1799391806 0.1362843175 0.2465330809 0.0662624887 0.0269560000 429020925 0 402718720 -0.0925977454 -0.0379146300 0.0230811872 372 14.8400000000 0.1772046685 0.1363943185 0.2465330809 0.0661750344 0.0251950000 429023173 0 402718720 -0.0961316675 -0.0346445180 0.0247502364 373 14.8800000000 0.1761939973 0.1365010200 0.2465330809 0.0661087255 0.0174140000 429025421 0 402718720 -0.0980666801 -0.0327370018 0.0273140073 374 14.9200000000 0.1763198376 0.1366074875 0.2465330809 0.0660278613 0.0145570000 429027669 0 402718720 -0.0986308604 -0.0356096439 0.0283188540 375 14.9600000000 0.1725760549 0.1367034036 0.2465330809 0.0659644342 0.0153420000 429029917 0 402718720 -0.1076615602 -0.0409940854 0.0268444661 376 15.0000000000 0.1710179448 0.1367946657 0.2465330809 0.0658829715 0.0171380000 429032165 0 402718720 -0.1081585065 -0.0413260311 0.0270802621 377 15.0400000000 0.1735705882 0.1368922146 0.2465330809 0.0658196524 0.0153480000 429034413 0 402718720 -0.1182036102 -0.0455348752 0.0322729275 378 15.0800000000 0.1758147478 0.1369951842 0.2465330809 0.0657489954 0.0155150000 429036661 0 402718720 -0.1186524779 -0.0463584512 0.0355256498 379 15.1200000000 0.1788308173 0.1371055685 0.2465330809 0.0656767541 0.0161950000 429038909 0 402718720 -0.1252528280 -0.0504078977 0.0391511880 380 15.1600000000 0.1763966978 0.1372089662 0.2465330809 0.0655955808 0.0242460000 432547389 0 402718720 -0.1251809001 -0.0486807525 0.0388178490 381 15.2000000000 0.1755141914 0.1373095049 0.2465330809 0.0655143004 0.0089860000 429352533 0 402718720 -0.1247571260 -0.0485696420 0.0389022306 382 15.2400000000 0.1743945181 0.1374065860 0.2465330809 0.0654338039 0.0090530000 429354781 0 402718720 -0.1242132410 -0.0484838784 0.0389357321 383 15.2800000000 0.1735009253 0.1375008271 0.2465330809 0.0653531609 0.0280290000 429357029 0 402718720 -0.1234379560 -0.0485833213 0.0388523154 384 15.3200000000 0.1724128276 0.1375917438 0.2465330809 0.0652759900 0.0278170000 429359277 0 402718720 -0.1233737841 -0.0482940972 0.0390811600 385 15.3600000000 0.1706937999 0.1376777232 0.2465330809 0.0651968464 0.0292020000 429361525 0 402718720 -0.1228222400 -0.0483526513 0.0388639383 386 15.4000000000 0.1705310643 0.1377628355 0.2465330809 0.0651185155 0.0277860000 429363773 0 402718720 -0.1228798702 -0.0480436124 0.0394656882 387 15.4400000000 0.1688143760 0.1378430720 0.2465330809 0.0650407574 0.0259070000 429366021 0 402718720 -0.1220433936 -0.0484307632 0.0392226391 388 15.4800000000 0.1669503152 0.1379180907 0.2465330809 0.0649628434 0.0284450000 429368269 0 402718720 -0.1225385368 -0.0476330630 0.0395053178 389 15.5200000000 0.1669834852 0.1379928089 0.2465330809 0.0648882144 0.0265390000 429370517 0 402718720 -0.1238308474 -0.0466849655 0.0408127084 390 15.5600000000 0.1656076610 0.1380636162 0.2465330809 0.0648150566 0.0218530000 429372765 0 402718720 -0.1246468723 -0.0467762277 0.0418104529 391 15.6000000000 0.1648671776 0.1381321675 0.2465330809 0.0647406591 0.0184940000 429375013 0 402718720 -0.1257574707 -0.0464047343 0.0425984561 392 15.6400000000 0.1626068205 0.1381946029 0.2465330809 0.0646654329 0.0199380000 429377261 0 402718720 -0.1260030419 -0.0461959317 0.0425000526 393 15.6800000000 0.1615610421 0.1382540595 0.2465330809 0.0645932994 0.0187890000 429379509 0 402718720 -0.1262331754 -0.0460957773 0.0426260158 394 15.7200000000 0.1614150554 0.1383128437 0.2465330809 0.0645221639 0.0231650000 429381757 0 402718720 -0.1264478415 -0.0460331067 0.0428076908 395 15.7600000000 0.1601607949 0.1383681550 0.2465330809 0.0644479909 0.0188390000 429384005 0 402718720 -0.1263781041 -0.0457484014 0.0428486243 396 15.8000000000 0.1594679505 0.1384214373 0.2465330809 0.0643745020 0.0229060000 429386253 0 402718720 -0.1275394410 -0.0448702201 0.0428810380 397 15.8400000000 0.1588450670 0.1384728822 0.2465330809 0.0643022657 0.0220270000 429388501 0 402718720 -0.1281701922 -0.0448620766 0.0421562158 398 15.8800000000 0.1595434546 0.1385258233 0.2465330809 0.0642259530 0.0214560000 429390749 0 402718720 -0.1287071705 -0.0446839519 0.0419999063 399 15.9200000000 0.1595260054 0.1385784554 0.2465330809 0.0641526057 0.0201010000 429392997 0 402718720 -0.1285171062 -0.0449735969 0.0420123711 400 15.9600000000 0.1586491466 0.1386286321 0.2465330809 0.0640761182 0.0206270000 429395245 0 402718720 -0.1282762885 -0.0453494638 0.0413897969 401 16.0000000000 0.1577580720 0.1386763364 0.2465330809 0.0639989911 0.0205940000 429397493 0 402718720 -0.1285772175 -0.0452057272 0.0414262079 402 16.0400000000 0.1561794132 0.1387198764 0.2465330809 0.0639279232 0.0181080000 429399741 0 402718720 -0.1295553297 -0.0457736738 0.0384496562 403 16.0800000000 0.1547299773 0.1387596037 0.2465330809 0.0638540528 0.0169810000 429401989 0 402718720 -0.1315191090 -0.0448406190 0.0382389836 404 16.1200000000 0.1545127481 0.1387985967 0.2465330809 0.0637819427 0.0179700000 429404237 0 402718720 -0.1318524480 -0.0445798971 0.0377953053 405 16.1600000000 0.1547509730 0.1388379852 0.2465330809 0.0637089128 0.0176020000 429406485 0 402718720 -0.1315516233 -0.0445499569 0.0366828181 406 16.2000000000 0.1543395668 0.1388761665 0.2465330809 0.0636351671 0.0165860000 429408733 0 402718720 -0.1318667382 -0.0441766120 0.0362377688 407 16.2400000000 0.1540274620 0.1389133932 0.2465330809 0.0635679572 0.0409350000 441708461 0 402718720 -0.1336639524 -0.0434749648 0.0351787880 408 16.2800000000 0.1368496567 0.1389083351 0.2465330809 0.0635218528 0.0107590000 445216269 0 402718720 -0.1079793051 -0.0278020836 0.0362236425 409 16.3200000000 0.1360411048 0.1389013247 0.2465330809 0.0634487360 0.0110590000 448410709 0 402718720 -0.1075933799 -0.0281260200 0.0353716090 410 16.3600000000 0.1346015185 0.1388908374 0.2465330809 0.0633776550 0.0165520000 448412957 0 402718720 -0.1069449112 -0.0282754265 0.0345708504 411 16.3999999990 0.1324392557 0.1388751401 0.2465330809 0.0633078182 0.0534690000 448415205 0 402718720 -0.1066276506 -0.0281805303 0.0335924737 412 16.4400000000 0.1318654418 0.1388581263 0.2465330809 0.0632371152 0.0200320000 448417453 0 402718720 -0.1067623645 -0.0282247327 0.0329370946 413 16.4800000000 0.1296000332 0.1388357096 0.2465330809 0.0631658181 0.0236620000 448419701 0 402718720 -0.1058354825 -0.0279896390 0.0322200432 414 16.5200000000 0.1292392462 0.1388125297 0.2465330809 0.0630929953 0.0378500000 460719141 0 402718720 -0.1051801667 -0.0277893171 0.0319019221 415 16.5599999990 0.1302587539 0.1387919182 0.2465330809 0.0630418137 0.0100320000 464380597 0 402718720 -0.1151562482 -0.0236516539 0.0299269743 416 16.6000000000 0.1300594807 0.1387709268 0.2465330809 0.0629673515 0.0101910000 467575037 0 402718720 -0.1145791709 -0.0237549767 0.0293661840 417 16.6400000000 0.1306505799 0.1387514535 0.2465330809 0.0628962192 0.0095310000 467577285 0 402718720 -0.1145531908 -0.0238314662 0.0288965870 418 16.6800000000 0.1298336834 0.1387301192 0.2465330809 0.0628221826 0.0115880000 467579533 0 402718720 -0.1144989803 -0.0235915892 0.0287172589 419 16.7199999990 0.1297164410 0.1387086068 0.2465330809 0.0627508780 0.0169530000 467581781 0 402718720 -0.1143015474 -0.0241294522 0.0278591085 420 16.7600000000 0.1285856068 0.1386845044 0.2465330809 0.0626800585 0.0179180000 467584029 0 402718720 -0.1139931530 -0.0246368423 0.0273252204 421 16.8000000000 0.1275225133 0.1386579914 0.2465330809 0.0626101863 0.0455820000 479882121 0 402718720 -0.1141467690 -0.0244352557 0.0269635487 422 16.8400000000 0.1299495250 0.1386373552 0.2465330809 0.0625410905 0.0252460000 483543577 0 402718720 -0.1153724939 -0.0255824607 0.0274022147 423 16.8799999990 0.1300413907 0.1386170338 0.2465330809 0.1004214034 0.0116680000 497618273 0 402718720 0.0100634899 -0.0611345619 -0.0030742460 424 16.9200000000 0.1094234958 0.1385481811 0.2465330809 0.1003313526 0.0340570000 486739041 0 402718720 -0.0240742974 -0.0482099615 0.0023077105 425 16.9600000000 0.1075751185 0.1384753033 0.2465330809 0.1002166657 0.0258970000 486741289 0 402718720 -0.0243856665 -0.0471962020 0.0032213288 426 17.0000000000 0.1033428460 0.1383928327 0.2465330809 0.1000999496 0.0250060000 486743537 0 402718720 -0.0241097640 -0.0471251011 0.0038106886 427 17.0400000000 0.1021496207 0.1383079540 0.2465330809 0.0999840198 0.0240820000 486745785 0 402718720 -0.0235251803 -0.0472368486 0.0041744546 428 17.0800000000 0.1013565958 0.1382216191 0.2465330809 0.0998686211 0.0237840000 486748033 0 402718720 -0.0231888983 -0.0470327996 0.0047872178 429 17.1200000000 0.1006309539 0.1381339951 0.2465330809 0.0997533851 0.0236000000 486750281 0 402718720 -0.0226690602 -0.0472018681 0.0052488605 430 17.1600000000 0.1020379886 0.1380500509 0.2465330809 0.0996387141 0.0233190000 486752529 0 402718720 -0.0220693015 -0.0465117656 0.0054823132 431 17.2000000000 0.1018852890 0.1379661420 0.2465330809 0.0995244311 0.0231530000 486754777 0 402718720 -0.0216379948 -0.0465438217 0.0058126729 432 17.2400000000 0.0986264944 0.1378750780 0.2465330809 0.0994105882 0.0228710000 486757025 0 402718720 -0.0207335465 -0.0480472445 0.0063795238 433 17.2800000000 0.0954979956 0.1377772094 0.2465330809 0.0992985895 0.0221170000 486759273 0 402718720 -0.0198373385 -0.0492437817 0.0069564125 434 17.3200000000 0.0937308073 0.1376757200 0.2465330809 0.0991865987 0.0226410000 486761521 0 402718720 -0.0195327364 -0.0497462749 0.0077181510 435 17.3600000000 0.0912908986 0.1375690882 0.2465330809 0.0990745102 0.0214330000 486763769 0 402718720 -0.0183542762 -0.0507242344 0.0080223987 436 17.4000000000 0.0899509564 0.1374598723 0.2465330809 0.0989627170 0.0213610000 486766017 0 402718720 -0.0181057807 -0.0512060001 0.0085072136 437 17.4400000000 0.0895484462 0.1373502352 0.2465330809 0.0988512102 0.0311160000 490277501 0 402718720 -0.0181009620 -0.0515091643 0.0087258136 438 17.4800000000 0.0888831541 0.1372395798 0.2465330809 0.0987430934 0.0121550000 486927173 0 402718720 -0.0181513764 -0.0515437387 0.0091331173 439 17.5200000000 0.0876407623 0.1371265984 0.2465330809 0.0986343848 0.0386290000 486929421 0 402718720 -0.0184560176 -0.0514779203 0.0094436221 440 17.5600000000 0.0869507119 0.1370125623 0.2465330809 0.0985255733 0.0181310000 486931669 0 402718720 -0.0189206898 -0.0514423810 0.0095637180 441 17.6000000000 0.0858427063 0.1368965309 0.2465330809 0.0984184305 0.0161760000 486933917 0 402718720 -0.0194155090 -0.0513087809 0.0099405656 442 17.6400000000 0.0826006234 0.1367736895 0.2465330809 0.0983272866 0.0196320000 486936165 0 402718720 -0.0223375168 -0.0512845553 0.0100635523 443 17.6800000000 0.0830844194 0.1366524947 0.2465330809 0.0982212063 0.0158990000 486938413 0 402718720 -0.0232529026 -0.0513129607 0.0098042320 444 17.7200000000 0.0829842612 0.1365316203 0.2465330809 0.0981141908 0.1435830000 499268881 0 402718720 -0.0238009598 -0.0515357256 0.0099711213 445 17.7600000000 0.0817876905 0.1364086003 0.2465330809 0.0980085535 0.0120600000 502776689 0 402718720 -0.0249905996 -0.0541877225 0.0110255070 446 17.8000000000 0.0806015804 0.1362834724 0.2465330809 0.0979022988 0.0198800000 505971129 0 402718720 -0.0254324190 -0.0549792983 0.0115110688 447 17.8400000000 0.0777087510 0.1361524328 0.2465330809 0.0977938599 0.0205860000 505973377 0 402718720 -0.0243857764 -0.0564605743 0.0124847014 448 17.8800000000 0.0762651339 0.1360187558 0.2465330809 0.0976851234 0.0198400000 505975625 0 402718720 -0.0236162934 -0.0577373281 0.0135762049 449 17.9200000000 0.0736177340 0.1358797780 0.2465330809 0.0975773764 0.0522920000 505977873 0 402718720 -0.0242159031 -0.0584406666 0.0139061492 450 17.9600000000 0.0712372810 0.1357361280 0.2465330809 0.0974691206 0.0205000000 505980121 0 402718720 -0.0240107626 -0.0596407726 0.0144636482 451 18.0000000000 0.0699004307 0.1355901508 0.2465330809 0.0973621606 0.0185870000 505982369 0 402718720 -0.0239115097 -0.0598401763 0.0155151747 452 18.0400000000 0.0679334477 0.1354404679 0.2465330809 0.0972554819 0.0178090000 505984617 0 402718720 -0.0234159082 -0.0607264750 0.0169212185 453 18.0800000000 0.0656908005 0.1352864951 0.2465330809 0.0971487641 0.0178980000 505986865 0 402718720 -0.0233955849 -0.0608492047 0.0178881902 454 18.1200000000 0.0646702722 0.1351309528 0.2465330809 0.0970419845 0.0174800000 505989113 0 402718720 -0.0226826072 -0.0614129007 0.0191550888 455 18.1600000000 0.0623677075 0.1349710335 0.2465330809 0.0969353173 0.0185400000 505991361 0 402718720 -0.0226278324 -0.0615760311 0.0207192022 456 18.2000000000 0.0605947897 0.1348079277 0.2465330809 0.0968298882 0.0185130000 505993609 0 402718720 -0.0222478677 -0.0620283931 0.0222787056 457 18.2400000000 0.0615067221 0.1346475312 0.2465330809 0.0967257803 0.0183190000 505995857 0 402718720 -0.0225760527 -0.0609153695 0.0236019008 458 18.2800000000 0.0610996336 0.1344869463 0.2465330809 0.0966209590 0.0183960000 505998105 0 402718720 -0.0224649925 -0.0606237426 0.0258411765 459 18.3200000000 0.0604780950 0.1343257070 0.2465330809 0.0965155613 0.0179030000 506000353 0 402718720 -0.0208179392 -0.0604283847 0.0276990402 460 18.3600000000 0.0626413897 0.1341698715 0.2465330809 0.0964112616 0.0174780000 506002601 0 402718720 -0.0210271794 -0.0592054129 0.0300071444 461 18.4000000000 0.0625066683 0.1340144199 0.2465330809 0.0963068536 0.0175020000 506004849 0 402718720 -0.0208371058 -0.0592369102 0.0325268693 462 18.4400000000 0.0637700707 0.1338623758 0.2465330809 0.0962028564 0.0171220000 506007097 0 402718720 -0.0199541058 -0.0594015270 0.0349116139 463 18.4800000000 0.0654226467 0.1337145578 0.2465330809 0.0960995782 0.0160490000 506009345 0 402718720 -0.0198885370 -0.0578176230 0.0374564566 464 18.5200000000 0.0688303709 0.1335747212 0.2465330809 0.0959967057 0.0171330000 506011593 0 402718720 -0.0191926081 -0.0576970279 0.0404354036 465 18.5600000000 0.0769737810 0.1334529988 0.2465330809 0.0958967471 0.0174980000 506013841 0 402718720 -0.0192492418 -0.0544847399 0.0468082838 466 18.6000000000 0.0828822032 0.1333444777 0.2465330809 0.0957944161 0.0175010000 506016089 0 402718720 -0.0179564580 -0.0534134656 0.0500803180 467 18.6400000000 0.0872845724 0.1332458484 0.2465330809 0.0956924045 0.0173910000 506018337 0 402718720 -0.0174511541 -0.0527839102 0.0536157787 468 18.6800000000 0.0940970406 0.1331621971 0.2465330809 0.0955912161 0.0171650000 506020585 0 402718720 -0.0169281084 -0.0508775339 0.0571941175 469 18.7200000000 0.1007080153 0.1330929984 0.2465330809 0.0954907025 0.0172620000 506022833 0 402718720 -0.0163989756 -0.0499154255 0.0610695034 470 18.7600000000 0.1084230393 0.1330405091 0.2465330809 0.0953914316 0.0173550000 506025081 0 402718720 -0.0158211663 -0.0479593910 0.0648930743 471 18.8000000000 0.1167867333 0.1330060001 0.2465330809 0.0952927199 0.0171210000 506027329 0 402718720 -0.0154910916 -0.0457322747 0.0689100996 472 18.8400000000 0.1254434884 0.1329899778 0.2465330809 0.0951925939 0.0169960000 506029577 0 402718720 -0.0142916646 -0.0431946293 0.0723833814 473 18.8800000000 0.1346110851 0.1329934051 0.2465330809 0.0950927095 0.0163060000 506031825 0 402718720 -0.0136026647 -0.0404658094 0.0763909519 474 18.9200000000 0.1430960000 0.1330147186 0.2465330809 0.0949935132 0.0167010000 506034073 0 402718720 -0.0126524931 -0.0381053761 0.0800006464 475 18.9600000000 0.1516969651 0.1330540496 0.2465330809 0.0948953981 0.0168930000 506036321 0 402718720 -0.0114179328 -0.0361636430 0.0840734094 476 19.0000000000 0.1590244025 0.1331086092 0.2465330809 0.0947972291 0.0176470000 506038569 0 402718720 -0.0102075646 -0.0348466933 0.0879851282 477 19.0400000000 0.1679140180 0.1331815765 0.2465330809 0.0946985318 0.0175760000 506040817 0 402718720 -0.0096294461 -0.0321647637 0.0916491747 478 19.0800000000 0.1771424115 0.1332735448 0.2465330809 0.0946003561 0.0176990000 506043065 0 402718720 -0.0084055485 -0.0294789188 0.0950979218 479 19.1200000000 0.1848393828 0.1333811979 0.2465330809 0.0945030306 0.0172610000 506045313 0 402718720 -0.0071451063 -0.0280190855 0.0989085212 480 19.1600000000 0.1930249929 0.1335054558 0.2465330809 0.0944060346 0.0174780000 506047561 0 402718720 -0.0060404432 -0.0260277279 0.1024039462 481 19.2000000000 0.2025886327 0.1336490799 0.2465330809 0.0943085158 0.0179420000 506049809 0 402718720 -0.0056736716 -0.0221674759 0.1053822786 482 19.2400000000 0.2107266486 0.1338089918 0.2465330809 0.0942138896 0.0181510000 506052057 0 402718720 -0.0043195295 -0.0206002463 0.1092675701 483 19.2800000000 0.2172830254 0.1339818159 0.2465330809 0.0941201492 0.0185670000 506054305 0 402718720 -0.0034173778 -0.0202446561 0.1131673083 484 19.3200000000 0.2239899784 0.1341677832 0.2465330809 0.0940257777 0.1400920000 518446673 0 402718720 -0.0021767768 -0.0195515566 0.1169387400 485 19.3600000000 0.2317560911 0.1343689962 0.2465330809 0.0939293628 0.0166170000 522108129 0 402718720 -0.0001045393 -0.0199858937 0.1212940589 486 19.4000000000 0.2401221693 0.1345865953 0.2465330809 0.0938333122 0.0184680000 525302569 0 402718720 0.0006534988 -0.0173026100 0.1244861335 487 19.4400000000 0.2479102165 0.1348192927 0.2479102165 0.0937375437 0.0483050000 525304817 0 402718720 0.0008679111 -0.0156788491 0.1283409297 488 19.4800000000 0.2551234663 0.1350658176 0.2551234663 0.0936420231 0.0178730000 525307065 0 402718720 0.0014117805 -0.0148066469 0.1321396530 489 19.5200000000 0.2638414502 0.1353291625 0.2638414502 0.0935472818 0.0153170000 525309313 0 402718720 0.0017544671 -0.0118832858 0.1353092492 490 19.5600000000 0.2717818320 0.1356076373 0.2717818320 0.0934526002 0.0149010000 525311561 0 402718720 0.0018200983 -0.0101041682 0.1388463974 491 19.6000000000 0.2798156142 0.1359013399 0.2798156142 0.0933579473 0.0158780000 525313809 0 402718720 0.0030609136 -0.0074062296 0.1419855356 492 19.6400000000 0.2870437503 0.1362085399 0.2870437503 0.0932635280 0.0152190000 525316057 0 402718720 0.0029736864 -0.0058793710 0.1454516947 493 19.6800000000 0.2938775718 0.1365283554 0.2938775718 0.0931694573 0.0144850000 525318305 0 402718720 0.0030522614 -0.0046730903 0.1491111219 494 19.7200000000 0.3004252017 0.1368601304 0.3004252017 0.0930756408 0.0166480000 525320553 0 402718720 0.0032270148 -0.0041322177 0.1529361904 495 19.7600000000 0.3083739281 0.1372066229 0.3083739281 0.0929824932 0.0153980000 525322801 0 402718720 0.0033611828 -0.0020891414 0.1564434767 496 19.8000000000 0.3167298138 0.1375685649 0.3167298138 0.0928900844 0.0149000000 525325049 0 402718720 0.0034588671 0.0001412875 0.1597374827 497 19.8400000000 0.3250313997 0.1379457537 0.3250313997 0.0927979546 0.0155000000 525327297 0 402718720 0.0035543193 0.0024728619 0.1632066220 498 19.8800000000 0.3331229389 0.1383376757 0.3331229389 0.0927072918 0.0181690000 525329545 0 402718720 0.0030709831 0.0054013445 0.1666009873 499 19.9200000000 0.3417812586 0.1387453783 0.3417812586 0.0926168814 0.0172540000 525331793 0 402718720 0.0029072543 0.0076978048 0.1703246683 500 19.9600000000 0.3482015729 0.1391642907 0.3482015729 0.0925257672 0.0174100000 525334041 0 402718720 0.0021523752 0.0091178482 0.1742012054 501 20.0000000000 0.3554937840 0.1395960861 0.3554937840 0.0924353949 0.0185000000 525336289 0 402718720 0.0016555788 0.0099162096 0.1776224971 502 20.0400000000 0.3630307317 0.1400411750 0.3630307317 0.0923453470 0.0183430000 525338537 0 402718720 0.0011286030 0.0119346362 0.1813478321 503 20.0800000000 0.3716556430 0.1405016411 0.3716556430 0.0922554139 0.0185290000 525340785 0 402718720 0.0006117445 0.0137271853 0.1845841110 504 20.1200000000 0.3789703548 0.1409747934 0.3789703548 0.0921642405 0.0183280000 525343033 0 402718720 -0.0003304187 0.0162288845 0.1882128268 505 20.1600000000 0.3875298798 0.1414630212 0.3875298798 0.0920734590 0.0192520000 525345281 0 402718720 -0.0003397054 0.0179222934 0.1913988888 506 20.2000000000 0.3961800933 0.1419664147 0.3961800933 0.0919850183 0.0202250000 525347529 0 402718720 -0.0008810931 0.0212878287 0.1944906414 507 20.2400000000 0.4036864936 0.1424826278 0.4036864936 0.0918977968 0.0204400000 525349777 0 402718720 -0.0018554375 0.0232310891 0.1978913993 508 20.2800000000 0.4109326899 0.1430110728 0.4109326899 0.0918112193 0.0202400000 525352025 0 402718720 -0.0025635744 0.0249139778 0.2011304349 509 20.3200000000 0.4182502925 0.1435518179 0.4182502925 0.0917284077 0.0193160000 525354273 0 402718720 -0.0035812706 0.0276698209 0.2042622566 510 20.3600000000 0.4251318574 0.1441039356 0.4251318574 0.0916435084 0.0190560000 525356521 0 402718720 -0.0047344952 0.0293474570 0.2071742415 511 20.4000000000 0.4318076670 0.1446669566 0.4318076670 0.0915577886 0.0203800000 525358769 0 402718720 -0.0053598983 0.0308822598 0.2099570632 512 20.4400000000 0.4384868741 0.1452408236 0.4384868741 0.0914739336 0.0196930000 525361017 0 402718720 -0.0055000032 0.0333654806 0.2125296146 513 20.4800000000 0.4443980455 0.1458239761 0.4443980455 0.0913888439 0.0204480000 525412417 0 402718720 -0.0062236958 0.0351766534 0.2153068334 514 20.5200000000 0.4499827623 0.1464157247 0.4499827623 0.0913044587 0.0199720000 525517065 0 402718720 -0.0065494766 0.0361008421 0.2179978043 515 20.5600000000 0.4548117816 0.1470145520 0.4548117816 0.0912207207 0.0203360000 525519313 0 402718720 -0.0066216206 0.0366886072 0.2202361673 516 20.6000000000 0.4607791007 0.1476226228 0.4607791007 0.0911403521 0.0204960000 525521561 0 402718720 -0.0066584470 0.0387869589 0.2225291133 517 20.6400000000 0.4658261538 0.1482381036 0.4658261538 0.0910590004 0.0198890000 525523809 0 402718720 -0.0063972599 0.0401838608 0.2245362550 518 20.6800000000 0.4705687761 0.1488603635 0.4705687761 0.0909790063 0.1577790000 537865629 0 402718720 -0.0064457334 0.0413435698 0.2266468406 519 20.7200000000 0.4737037718 0.1494862661 0.4737037718 0.0909076158 0.0170960000 541527085 0 402718720 -0.0089935185 0.0453115851 0.2289507389 520 20.7600000000 0.4778320193 0.1501177002 0.4778320193 0.0908297754 0.0210150000 544721525 0 402718720 -0.0085039288 0.0465040654 0.2307931930 521 20.8000000000 0.4811491668 0.1507530773 0.4811491668 0.0907506461 0.0163410000 544723773 0 402718720 -0.0078839380 0.0468445718 0.2326348722 522 20.8400000000 0.4843832850 0.1513922156 0.4843832850 0.0906731176 0.0158340000 544726021 0 402718720 -0.0074193068 0.0468685031 0.2343365550 523 20.8800000000 0.4868577421 0.1520336411 0.4868577421 0.0905957665 0.0164880000 544728269 0 402718720 -0.0067735813 0.0469838753 0.2359832078 524 20.9200000000 0.4905473888 0.1526796597 0.4905473888 0.0905208102 0.0152560000 544730517 0 402718720 -0.0057162186 0.0483953357 0.2371644676 525 20.9600000000 0.4933832884 0.1533286190 0.4933832884 0.0904416446 0.0153580000 544732765 0 402718720 -0.0048297243 0.0491469130 0.2384748161 526 21.0000000000 0.4954391420 0.1539790192 0.4954391420 0.0903611925 0.0157760000 544735013 0 402718720 -0.0038009963 0.0490505397 0.2397770286 527 21.0400000000 0.4981293082 0.1546320558 0.4981293082 0.0902832889 0.0153520000 544737261 0 402718720 -0.0028291368 0.0497278124 0.2408740520 528 21.0800000000 0.5007306933 0.1552875457 0.5007306933 0.0902032822 0.0159740000 544739509 0 402718720 -0.0016459781 0.0501949005 0.2417822778 529 21.1200000000 0.5026562810 0.1559441974 0.5026562810 0.0901217869 0.0158270000 544741757 0 402718720 -0.0006441431 0.0502842218 0.2427679747 530 21.1600000000 0.5049560666 0.1566027103 0.5049560666 0.0900414339 0.0148200000 544744005 0 402718720 0.0006449333 0.0506789424 0.2435455918 531 21.2000000000 0.5067967176 0.1572622094 0.5067967176 0.0899619605 0.0156530000 544746253 0 402718720 0.0017323857 0.0507970080 0.2444099635 532 21.2400000000 0.5081841350 0.1579218371 0.5081841350 0.0898836406 0.0169180000 544748501 0 402718720 0.0029545103 0.0505417660 0.2452595234 533 21.2800000000 0.5099359751 0.1585822764 0.5099359751 0.0898061981 0.1678980000 557086237 0 402718720 0.0041939099 0.0507583916 0.2458429188 534 21.3200000000 0.5125958323 0.1592452231 0.5125958323 0.0897275616 0.0155290000 560747693 0 402718720 0.0060941563 0.0499195643 0.2457652837 535 21.3600000000 0.5142015815 0.1599086929 0.5142015815 0.0896505718 0.0208500000 563942133 0 402718720 0.0075476021 0.0504664369 0.2465412766 536 21.4000000000 0.5162830949 0.1605735705 0.5162830949 0.0895738298 0.0162570000 563944381 0 402718720 0.0084086284 0.0502090827 0.2471284419 537 21.4400000000 0.5179964304 0.1612391625 0.5179964304 0.0894979646 0.0158520000 563946629 0 402718720 0.0100880722 0.0505572520 0.2479782552 538 21.4800000000 0.5201119184 0.1619062122 0.5201119184 0.0894199871 0.0149310000 563948877 0 402718720 0.0115689505 0.0506574884 0.2484125197 539 21.5200000000 0.5216975212 0.1625737285 0.5216975212 0.0893420604 0.0156020000 563951125 0 402718720 0.0135411974 0.0514554493 0.2489588857 540 21.5600000000 0.5235381126 0.1632421811 0.5235381126 0.0892632133 0.0144060000 563953373 0 402718720 0.0146884872 0.0515882410 0.2496070117 541 21.6000000000 0.5252245069 0.1639112797 0.5252245069 0.0891845292 0.0148240000 563955621 0 402718720 0.0163681675 0.0513912998 0.2501746118 542 21.6400000000 0.5268380046 0.1645808862 0.5268380046 0.0891078274 0.0152940000 563957869 0 402718720 0.0175543837 0.0525007509 0.2508430183 543 21.6800000000 0.5286477804 0.1652513593 0.5286477804 0.0890328941 0.0155280000 563960117 0 402718720 0.0191610046 0.0528504848 0.2514600754 544 21.7200000000 0.5307995677 0.1659233229 0.5307995677 0.0889584532 0.0181730000 563962365 0 402718720 0.0195798408 0.0525482781 0.2521082163 545 21.7600000000 0.5328237414 0.1665965347 0.5328237414 0.0888832358 0.0157490000 563964613 0 402718720 0.0213357806 0.0535456873 0.2528550923 546 21.8000000000 0.5365425944 0.1672740915 0.5365425944 0.0888244157 0.0162380000 563966861 0 402718720 0.0230630804 0.0539290868 0.2542956769 547 21.8400000000 0.5383261442 0.1679524317 0.5383261442 0.0887483620 0.0190870000 563969109 0 402718720 0.0244588610 0.0546048991 0.2550648153 548 21.8800000000 0.5409045219 0.1686330012 0.5409045219 0.0886743898 0.0170640000 563971357 0 402718720 0.0257535838 0.0548075065 0.2553787529 549 21.9200000000 0.5431279540 0.1693151414 0.5431279540 0.0886022553 0.0167500000 563973605 0 402718720 0.0268323794 0.0554797165 0.2560919225 550 21.9600000000 0.5449876189 0.1699981822 0.5449876189 0.0885283727 0.0148090000 563975853 0 402718720 0.0286871195 0.0559013560 0.2565733790 551 22.0000000000 0.5468829274 0.1706821836 0.5468829274 0.0884584544 0.0155360000 563978101 0 402718720 0.0296320561 0.0570969917 0.2571891844 552 22.0400000000 0.5492691398 0.1713680295 0.5492691398 0.0883841031 0.0164470000 563980349 0 402718720 0.0312049985 0.0578804910 0.2573791146 553 22.0800000000 0.5510653853 0.1720546432 0.5510653853 0.0883063556 0.0174650000 563982597 0 402718720 0.0328515582 0.0573000945 0.2577408254 554 22.1200000000 0.5523408055 0.1727410803 0.5523408055 0.0882285920 0.0151390000 563984845 0 402718720 0.0338547081 0.0572487190 0.2584624290 555 22.1600000000 0.5546606183 0.1734292236 0.5546606183 0.0881508951 0.1425740000 576312329 0 402718720 0.0359203964 0.0577401817 0.2585575879 556 22.2000000000 0.5568665862 0.1741188591 0.5568665862 0.0880756209 0.0228890000 579973785 0 402718720 0.0390724279 0.0591864102 0.2586945295 557 22.2400000000 0.5580518246 0.1748081463 0.5580518246 0.0879987204 0.0459760000 583168225 0 402718720 0.0408342220 0.0611952841 0.2594406605 558 22.2800000000 0.5614005327 0.1755009642 0.5614005327 0.0879225317 0.0190670000 583170473 0 402718720 0.0425606556 0.0610972010 0.2595837712 559 22.3200000000 0.5638463497 0.1761956787 0.5638463497 0.0878470720 0.0162710000 583172721 0 402718720 0.0436345525 0.0621948540 0.2601453960 560 22.3600000000 0.5660291910 0.1768918100 0.5660291910 0.0877706623 0.0155110000 583174969 0 402718720 0.0454982668 0.0626728907 0.2609262466 561 22.4000000000 0.5691704750 0.1775910589 0.5691704750 0.0876949151 0.0164230000 583177217 0 402718720 0.0470855348 0.0626526624 0.2609451711 562 22.4400000000 0.5717478395 0.1782924055 0.5717478395 0.0876198014 0.0163190000 583179465 0 402718720 0.0486266539 0.0636928827 0.2613826692 563 22.4800000000 0.5744989514 0.1789961472 0.5744989514 0.0875431265 0.0157900000 583181713 0 402718720 0.0507233031 0.0646903291 0.2613124549 564 22.5200000000 0.5766564012 0.1797012185 0.5766564012 0.0874662111 0.0165500000 583183961 0 402718720 0.0522129834 0.0654559806 0.2617919445 565 22.5600000000 0.5785549283 0.1804071543 0.5785549283 0.0873894860 0.0191990000 583186209 0 402718720 0.0534386523 0.0657837093 0.2622510791 566 22.6000000000 0.5814700127 0.1811157459 0.5814700127 0.0873132148 0.0166150000 583188457 0 402718720 0.0551590025 0.0666313097 0.2624350488 567 22.6400000000 0.5835250616 0.1818254625 0.5835250616 0.0872366100 0.0165010000 583190705 0 402718720 0.0567638129 0.0674222484 0.2627566159 568 22.6800000000 0.5857235193 0.1825365507 0.5857235193 0.0871605789 0.0200830000 583192953 0 402718720 0.0581325181 0.0680434033 0.2631744444 569 22.7200000000 0.5875954032 0.1832484291 0.5875954032 0.0870842247 0.0173260000 583195201 0 402718720 0.0600027926 0.0683740824 0.2630634010 570 22.7600000000 0.5898308158 0.1839617316 0.5898308158 0.0870084231 0.0167440000 583197449 0 402718720 0.0613757707 0.0692849979 0.2632557154 571 22.8000000000 0.5921348929 0.1846765707 0.5921348929 0.0869323539 0.0173110000 583199697 0 402718720 0.0632183105 0.0701796934 0.2633442581 572 22.8400000000 0.5939590931 0.1853920996 0.5939590931 0.0868563772 0.0179440000 583201945 0 402718720 0.0651061758 0.0711839050 0.2632364035 573 22.8800000000 0.5959699750 0.1861086404 0.5959699750 0.0867808181 0.0171880000 583204193 0 402718720 0.0665572733 0.0719015226 0.2633376122 574 22.9200000000 0.5979817510 0.1868261894 0.5979817510 0.0867055393 0.1041180000 595519777 0 402718720 0.0678970963 0.0728897974 0.2633946240 575 22.9600000000 0.6006846428 0.1875459432 0.6006846428 0.0866303578 0.0163090000 599181233 0 402718720 0.0681393817 0.0744766891 0.2628495693 576 23.0000000000 0.6023488045 0.1882660871 0.6023488045 0.0865550825 0.0250630000 602375673 0 402718720 0.0697015971 0.0764368922 0.2629750669 577 23.0400000000 0.6052119136 0.1889886968 0.6052119136 0.0864800589 0.0548230000 602377921 0 402718720 0.0707191750 0.0766734928 0.2628253698 578 23.0800000000 0.6064179540 0.1897108928 0.6064179540 0.0864051009 0.0201280000 602384265 0 402718720 0.0717146099 0.0775394663 0.2630049288 579 23.1200000000 0.6085903049 0.1904343460 0.6085903049 0.0863305587 0.0186550000 602386513 0 402718720 0.0728709921 0.0784442946 0.2625621259 580 23.1600000000 0.6113994122 0.1911601478 0.6113994122 0.0862562168 0.0171470000 602388761 0 402718720 0.0749737620 0.0804683939 0.2620963454 581 23.2000000000 0.6126394868 0.1918855856 0.6126394868 0.0861819101 0.0174140000 602391009 0 402718720 0.0752252564 0.0828287452 0.2630053759 582 23.2400000000 0.6154484153 0.1926133568 0.6154484153 0.0861079969 0.0181020000 602393257 0 402718720 0.0765735433 0.0829623342 0.2619905472 583 23.2800000000 0.6179502606 0.1933429226 0.6179502606 0.0860340794 0.0174190000 602395505 0 402718720 0.0775579289 0.0846355930 0.2618823349 584 23.3200000000 0.6192451119 0.1940722072 0.6192451119 0.0859605753 0.0179030000 602397753 0 402718720 0.0784140900 0.0854568258 0.2615247965 585 23.3600000000 0.6198671460 0.1948000618 0.6198671460 0.0858870719 0.0188730000 602400001 0 402718720 0.0789549425 0.0868202299 0.2616190314 586 23.4000000000 0.6217365265 0.1955286223 0.6217365265 0.0858137367 0.0155220000 602402249 0 402718720 0.0801616758 0.0872400701 0.2612731457 587 23.4400000000 0.6232261062 0.1962572381 0.6232261062 0.0857405317 0.0180430000 602404497 0 402718720 0.0808637738 0.0883482620 0.2611205578 588 23.4800000000 0.6247047186 0.1969858903 0.6247047186 0.0856675947 0.0207880000 602406745 0 402718720 0.0815713033 0.0891599357 0.2610430121 589 23.5200000000 0.6261693239 0.1977145549 0.6261693239 0.0855948502 0.0184590000 602408993 0 402718720 0.0826901123 0.0901567489 0.2608268857 590 23.5600000000 0.6274762750 0.1984429646 0.6274762750 0.0855223136 0.0173770000 602411241 0 402718720 0.0832723379 0.0906504691 0.2608670592 591 23.6000000000 0.6291400194 0.1991717244 0.6291400194 0.0854499097 0.0189460000 602413489 0 402718720 0.0839153603 0.0916498974 0.2609349787 592 23.6400000000 0.6305460930 0.1999003973 0.6305460930 0.0853779503 0.0181990000 602415737 0 402718720 0.0849144757 0.0924623311 0.2605872452 593 23.6800000000 0.6328195333 0.2006304465 0.6328195333 0.0853070960 0.0178570000 602417985 0 402718720 0.0862577483 0.0936592743 0.2606284618 594 23.7200000000 0.6337645650 0.2013596285 0.6337645650 0.0852353042 0.0172880000 602420233 0 402718720 0.0866071507 0.0937789008 0.2608378530 595 23.7600000000 0.6348322034 0.2020881538 0.6348322034 0.0851635416 0.0524950000 602422481 0 402718720 0.0873142630 0.0945749581 0.2608783543 596 23.8000000000 0.6364020705 0.2028168684 0.6364020705 0.0850919933 0.0186260000 602424729 0 402718720 0.0877381712 0.0953546837 0.2610497773 597 23.8400000000 0.6376965046 0.2035453100 0.6376965046 0.0850206447 0.0180110000 602426977 0 402718720 0.0881007239 0.0960274190 0.2611884773 598 23.8800000000 0.6386827826 0.2042729647 0.6386827826 0.0849496676 0.0187010000 602429225 0 402718720 0.0884478912 0.0964126810 0.2613582313 599 23.9200000000 0.6400174499 0.2050004179 0.6400174499 0.0848789143 0.0186530000 602431473 0 402718720 0.0886453465 0.0970323086 0.2616095245 600 23.9600000000 0.6411373019 0.2057273127 0.6411373019 0.0848084114 0.1720680000 614754865 0 402718720 0.0888792425 0.0976441056 0.2617505193 601 24.0000000000 0.6482155323 0.2064635660 0.6482155323 0.0847383910 0.0306200000 618416321 0 402718720 0.0842921883 0.0985800847 0.2585252821 602 24.0400000000 0.6495920420 0.2071996598 0.6495920420 0.0846683162 0.0195210000 621610761 0 402718720 0.0848157555 0.0978154242 0.2581808269 603 24.0800000000 0.6506464481 0.2079350608 0.6506464481 0.0845980925 0.0219640000 621613009 0 402718720 0.0846796706 0.0981329158 0.2585074008 604 24.1200000000 0.6519212723 0.2086701373 0.6519212723 0.0845279251 0.0222360000 621615257 0 402718720 0.0850364864 0.0983345881 0.2585291266 605 24.1600000000 0.6545394659 0.2094071114 0.6545394659 0.0844580895 0.0502420000 621617505 0 402718720 0.0855501518 0.0994764268 0.2588619292 606 24.2000000000 0.6547816396 0.2101420529 0.6547816396 0.0843883398 0.0230100000 621619753 0 402718720 0.0854465961 0.1013385355 0.2596441507 607 24.2400000000 0.6565427184 0.2108774741 0.6565427184 0.0843188223 0.0213020000 621622001 0 402718720 0.0861461908 0.1009531766 0.2591394484 608 24.2800000000 0.6575617194 0.2116121521 0.6575617194 0.0842493998 0.0208740000 621624249 0 402718720 0.0863623619 0.1011011675 0.2594413757 609 24.3200000000 0.6586197615 0.2123461547 0.6586197615 0.0841801394 0.0206910000 621626497 0 402718720 0.0867701992 0.1013058871 0.2593296766 610 24.3600000000 0.6597821116 0.2130796563 0.6597821116 0.0841110944 0.0229230000 621628745 0 402718720 0.0866572335 0.1024408638 0.2595896423 611 24.4000000000 0.6609391570 0.2138126506 0.6609391570 0.0840421452 0.0200300000 621630993 0 402718720 0.0870447457 0.1032775715 0.2596211731 612 24.4400000000 0.6621724963 0.2145452647 0.6621724963 0.0839734234 0.0202160000 621633241 0 402718720 0.0868687555 0.1038097963 0.2598927617 613 24.4800000000 0.6633957028 0.2152774840 0.6633957028 0.0839048348 0.0226490000 621635489 0 402718720 0.0872921199 0.1047284603 0.2598930895 614 24.5200000000 0.6644508243 0.2160090367 0.6644508243 0.0838365383 0.0205670000 621637737 0 402718720 0.0871075243 0.1053907201 0.2601883113 615 24.5600000000 0.6654395461 0.2167398180 0.6654395461 0.0837684432 0.0201990000 621639985 0 402718720 0.0866017863 0.1069517359 0.2606873512 616 24.6000000000 0.6667978168 0.2174704316 0.6667978168 0.0837005183 0.0201230000 621642233 0 402718720 0.0867265090 0.1071816534 0.2609761953 617 24.6400000000 0.6681274772 0.2182008320 0.6681274772 0.0836326990 0.0200500000 621644481 0 402718720 0.0865423381 0.1076928824 0.2611341476 618 24.6800000000 0.6692843437 0.2189307406 0.6692843437 0.0835654504 0.0192380000 621646729 0 402718720 0.0861796960 0.1083997861 0.2616494596 619 24.7200000000 0.6705841422 0.2196603907 0.6705841422 0.0834983534 0.0203830000 621648977 0 402718720 0.0856193677 0.1094999313 0.2622052133 620 24.7600000000 0.6715807915 0.2203892946 0.6715807915 0.0834318543 0.0546300000 621651225 0 402718720 0.0851928517 0.1099648774 0.2625263035 621 24.8000000000 0.6727202535 0.2211176858 0.6727202535 0.0833654159 0.0205850000 621653473 0 402718720 0.0846345872 0.1106403098 0.2631295025 622 24.8400000000 0.6741117239 0.2218459721 0.6741117239 0.0832993948 0.0208590000 621655721 0 402718720 0.0839265510 0.1114218831 0.2639077902 623 24.8800000000 0.6759061813 0.2225748006 0.6759061813 0.0832342300 0.0185110000 621657969 0 402718720 0.0835665315 0.1126124039 0.2644886076 624 24.9200000000 0.6768284440 0.2233027712 0.6768284440 0.0831691892 0.0194970000 621660217 0 402718720 0.0831575468 0.1131181642 0.2651323378 625 24.9600000000 0.6785246730 0.2240311263 0.6785246730 0.0831038626 0.0209300000 621662465 0 402718720 0.0824940205 0.1138335690 0.2656997144 626 25.0000000000 0.6802316308 0.2247598811 0.6802316308 0.0830386235 0.0211890000 621664713 0 402718720 0.0815891325 0.1151383966 0.2665227354 627 25.0400000000 0.6817350984 0.2254887092 0.6817350984 0.0829749585 0.0194300000 621666961 0 402718720 0.0813309476 0.1165146679 0.2667582631 628 25.0800000000 0.6830608845 0.2262173273 0.6830608845 0.0829116247 0.0204660000 621669209 0 402718720 0.0806933865 0.1173716336 0.2672721446 629 25.1200000000 0.6842231750 0.2269454765 0.6842231750 0.0828492579 0.0200650000 621671457 0 402718720 0.0802611783 0.1180290803 0.2676034868 630 25.1600000000 0.6851042509 0.2276727126 0.6851042509 0.0827846191 0.0195840000 621673705 0 402718720 0.0790246725 0.1188179329 0.2685363889 631 25.2000000000 0.6862195134 0.2283994112 0.6862195134 0.0827203673 0.0211870000 621675953 0 402718720 0.0782915503 0.1197134703 0.2690528929 632 25.2400000000 0.6870162487 0.2291250708 0.6870162487 0.0826561981 0.0204200000 621678201 0 402718720 0.0772044212 0.1197376326 0.2699700296 633 25.2800000000 0.6879240870 0.2298498717 0.6879240870 0.0825914080 0.0201720000 621680449 0 402718720 0.0760416016 0.1203332245 0.2706777453 634 25.3200000000 0.6895388961 0.2305749333 0.6895388961 0.0825267568 0.0218810000 621682697 0 402718720 0.0749177039 0.1212929338 0.2714937329 635 25.3600000000 0.6908805966 0.2312998241 0.6908805966 0.0824625396 0.0555960000 621684945 0 402718720 0.0735874549 0.1222994104 0.2725111246 636 25.4000000000 0.6917880774 0.2320238622 0.6917880774 0.0823991765 0.0213030000 621687193 0 402718720 0.0724938512 0.1227545291 0.2732755542 637 25.4400000000 0.6927866936 0.2327471948 0.6927866936 0.0823356309 0.0215890000 621689441 0 402718720 0.0710907429 0.1232879832 0.2743297517 638 25.4800000000 0.6940268874 0.2334702037 0.6940268874 0.0822720430 0.0220980000 621691689 0 402718720 0.0694852918 0.1237609088 0.2754421234 639 25.5200000000 0.6948873401 0.2341922962 0.6948873401 0.0822087056 0.0213060000 621693937 0 402718720 0.0679484457 0.1240236461 0.2766016722 640 25.5600000000 0.6954828501 0.2349130627 0.6954828501 0.0821452621 0.0217750000 621696185 0 402718720 0.0663046017 0.1239219978 0.2779210508 641 25.6000000000 0.6964352727 0.2356330662 0.6964352727 0.0820819101 0.0222050000 621698433 0 402718720 0.0648143291 0.1239243224 0.2788982093 642 25.6400000000 0.6979317665 0.2363531576 0.6979317665 0.0820193844 0.0225880000 621700681 0 402718720 0.0633843020 0.1249930710 0.2799897492 643 25.6800000000 0.6990395188 0.2370727320 0.6990395188 0.0819573732 0.0230840000 621702929 0 402718720 0.0618275441 0.1255699694 0.2810898423 644 25.7200000000 0.6998887658 0.2377913905 0.6998887658 0.0818955736 0.0229230000 621705177 0 402718720 0.0604836158 0.1254970878 0.2819541991 645 25.7600000000 0.7011578679 0.2385097881 0.7011578679 0.0818332304 0.0237510000 621707425 0 402718720 0.0591097064 0.1262388378 0.2828199267 646 25.8000000000 0.7025520802 0.2392281198 0.7025520802 0.0817713486 0.0233820000 621709673 0 402718720 0.0577531308 0.1267976463 0.2837748528 647 25.8400000000 0.7033435702 0.2399454544 0.7033435702 0.0817095166 0.0247890000 621711921 0 402718720 0.0562436990 0.1270839125 0.2849046886 648 25.8800000000 0.7048145533 0.2406628450 0.7048145533 0.0816472184 0.0243310000 621714169 0 402718720 0.0547946095 0.1277984232 0.2857787609 649 25.9200000000 0.7062498331 0.2413802363 0.7062498331 0.0815851297 0.0604310000 621716417 0 402718720 0.0534830838 0.1284601241 0.2866396606 650 25.9600000000 0.7082643509 0.2420985196 0.7082643509 0.0815235108 0.0258850000 621718665 0 402718720 0.0519518591 0.1296214759 0.2874590755 651 26.0000000000 0.7094528079 0.2428164217 0.7094528079 0.0814638060 0.0255970000 621720913 0 402718720 0.0509337969 0.1305264831 0.2882803679 652 26.0400000000 0.7107462883 0.2435341056 0.7107462883 0.0814036338 0.0264320000 621723161 0 402718720 0.0497140512 0.1313323677 0.2888229787 653 26.0800000000 0.7118137479 0.2442512260 0.7118137479 0.0813438445 0.0263790000 621725409 0 402718720 0.0481373779 0.1319752485 0.2896111906 654 26.1200000000 0.7129744291 0.2449679281 0.7129744291 0.0812845396 0.0358830000 621727657 0 402718720 0.0468076579 0.1323048472 0.2903783321 655 26.1600000000 0.7146854401 0.2456850541 0.7146854401 0.0812243734 0.0269970000 621729905 0 402718720 0.0459920764 0.1335552782 0.2908933461 656 26.2000000000 0.7165193558 0.2464027893 0.7165193558 0.0811633378 0.0274170000 621732153 0 402718720 0.0428256951 0.1348222792 0.2922370136 657 26.2400000000 0.7173823714 0.2471196532 0.7173823714 0.0811048317 0.0281480000 621734401 0 402718720 0.0419600643 0.1348361224 0.2926942408 658 26.2800000000 0.7184079885 0.2478358969 0.7184079885 0.0810447205 0.1165580000 634056073 0 402718720 0.0407752432 0.1355953515 0.2932440042 659 26.3200000000 0.7210248709 0.2485539378 0.7210248709 0.0809863700 0.0304080000 637717529 0 402718720 0.0420130268 0.1368759274 0.2920684218 660 26.3600000000 0.7216249108 0.2492707120 0.7216249108 0.0809276470 0.0363620000 640911969 0 402718720 0.0406408571 0.1374025941 0.2925987244 661 26.4000000000 0.7231466174 0.2499876196 0.7231466174 0.0808690553 0.0720130000 640914217 0 402718720 0.0400246270 0.1386464387 0.2928173542 662 26.4400000000 0.7243356705 0.2507041574 0.7243356705 0.0808094725 0.0336050000 640916465 0 402718720 0.0390010104 0.1396582425 0.2931287289 663 26.4800000000 0.7246280313 0.2514189747 0.7246280313 0.0807509396 0.0308300000 640918713 0 402718720 0.0380878262 0.1395508349 0.2935459316 664 26.5200000000 0.7254981399 0.2521329494 0.7254981399 0.0806925057 0.0291250000 640920961 0 402718720 0.0368916467 0.1400856972 0.2939545512 665 26.5600000000 0.7261080742 0.2528456939 0.7261080742 0.0806334282 0.0282390000 640923209 0 402718720 0.0364849456 0.1414901763 0.2943709195 666 26.6000000000 0.7270951271 0.2535577802 0.7270951271 0.0805743110 0.0292390000 640925457 0 402718720 0.0348987132 0.1414885074 0.2947462499 667 26.6400000000 0.7280480862 0.2542691599 0.7280480862 0.0805151369 0.0264520000 640927705 0 402718720 0.0337198824 0.1420515478 0.2949737310 668 26.6800000000 0.7289014459 0.2549796873 0.7289014459 0.0804561318 0.0286160000 640929953 0 402718720 0.0323805995 0.1427791268 0.2953904867 669 26.7200000000 0.7295469046 0.2556890554 0.7295469046 0.0803975976 0.0225600000 640932201 0 402718720 0.0310793985 0.1435557008 0.2957980633 670 26.7600000000 0.7296089530 0.2563963985 0.7296089530 0.0803388439 0.0228730000 640934449 0 402718720 0.0296841692 0.1431288868 0.2960830629 671 26.8000000000 0.7296570539 0.2571017050 0.7296570539 0.0802807328 0.0257170000 640936697 0 402718720 0.0285609104 0.1430381089 0.2967180014 672 26.8400000000 0.7303195596 0.2578058982 0.7303195596 0.0802218640 0.0230540000 640938945 0 402718720 0.0272499509 0.1428811997 0.2970226407 673 26.8800000000 0.7305043340 0.2585082733 0.7305043340 0.0801627922 0.0223520000 640941193 0 402718720 0.0259073377 0.1430009902 0.2976346612 674 26.9200000000 0.7307481170 0.2592089259 0.7307481170 0.0801054937 0.0468060000 640943441 0 402718720 0.0245604794 0.1427946836 0.2981884181 675 26.9600000000 0.7310675383 0.2599079757 0.7310675383 0.0800480632 0.0243700000 640945689 0 402718720 0.0232477542 0.1427355409 0.2984783947 676 27.0000000000 0.7311865687 0.2606051334 0.7311865687 0.0799895861 0.0231020000 640947937 0 402718720 0.0218501538 0.1429146528 0.2988065183 677 27.0400000000 0.7311276793 0.2613001445 0.7311865687 0.0799317704 0.0248060000 640950185 0 402718720 0.0203568973 0.1430570781 0.2991696894 678 27.0800000000 0.7311732769 0.2619931727 0.7311865687 0.0798738954 0.0240230000 640952433 0 402718720 0.0188399330 0.1429722458 0.2994896770 679 27.1200000000 0.7308956981 0.2626837508 0.7311865687 0.0798156997 0.0242910000 640954681 0 402718720 0.0170051735 0.1426122636 0.2999102473 680 27.1600000000 0.7309985161 0.2633724490 0.7311865687 0.0797585350 0.0264190000 640956929 0 402718720 0.0154337017 0.1424327344 0.3004219532 681 27.2000000000 0.7310305834 0.2640591717 0.7311865687 0.0797020431 0.0250720000 640959177 0 402718720 0.0145577965 0.1424072981 0.3007452488 682 27.2400000000 0.7309194207 0.2647437175 0.7311865687 0.0796455111 0.0246520000 640961425 0 402718720 0.0134163359 0.1422520727 0.3010341525 683 27.2800000000 0.7307552695 0.2654260184 0.7311865687 0.0795893357 0.0259370000 640963673 0 402718720 0.0125876870 0.1419690549 0.3013912439 684 27.3200000000 0.7313915491 0.2661072546 0.7313915491 0.0795313884 0.1712100000 653295629 0 402718720 0.0107776197 0.1420590281 0.3016392589 685 27.3600000000 0.7302709818 0.2667848659 0.7313915491 0.0794742127 0.0192460000 656957085 0 402718720 0.0099702924 0.1442147046 0.3028489053 686 27.4000000000 0.7302452326 0.2674604641 0.7313915491 0.0794178817 0.0368660000 660151525 0 402718720 0.0088932859 0.1442369670 0.3031349778 687 27.4400000000 0.7309626341 0.2681351397 0.7313915491 0.0793617007 0.0636740000 660153773 0 402718720 0.0076481071 0.1445486993 0.3036965728 688 27.4800000000 0.7314143181 0.2688085106 0.7314143181 0.0793059752 0.0250770000 660156021 0 402718720 0.0067189420 0.1448298991 0.3042089939 689 27.5200000000 0.7321634293 0.2694810141 0.7321634293 0.0792496588 0.0243330000 660158269 0 402718720 0.0055249673 0.1448668540 0.3043053150 690 27.5600000000 0.7328968644 0.2701526313 0.7328968644 0.0791932112 0.0242070000 660160517 0 402718720 0.0045299628 0.1452942491 0.3046279252 691 27.6000000000 0.7329833508 0.2708224298 0.7329833508 0.0791371288 0.0242180000 660162765 0 402718720 0.0031602960 0.1456047595 0.3052808642 692 27.6400000000 0.7339743376 0.2714917244 0.7339743376 0.0790811626 0.0231840000 660165013 0 402718720 0.0020358346 0.1458693296 0.3055556118 693 27.6800000000 0.7340213060 0.2721591553 0.7340213060 0.0790251746 0.0216270000 660167261 0 402718720 0.0005252817 0.1456662565 0.3060506582 694 27.7200000000 0.7347320318 0.2728256868 0.7347320318 0.0789689968 0.0210130000 660169509 0 402718720 -0.0003098559 0.1458111405 0.3064653575 695 27.7600000000 0.7353391647 0.2734911738 0.7353391647 0.0789134327 0.0267540000 660171757 0 402718720 -0.0011932246 0.1458472610 0.3068332374 696 27.8000000000 0.7352028489 0.2741545527 0.7353391647 0.0788581397 0.0214970000 660174005 0 402718720 -0.0023776970 0.1454778761 0.3073187172 697 27.8400000000 0.7358626723 0.2748169746 0.7358626723 0.0788032343 0.0207090000 660176253 0 402718720 -0.0035953708 0.1456830204 0.3076782823 698 27.8800000000 0.7364035845 0.2754782735 0.7364035845 0.0787485690 0.0253250000 660178501 0 402718720 -0.0044317390 0.1457375735 0.3080567420 699 27.9200000000 0.7371893525 0.2761388044 0.7371893525 0.0786934191 0.0219670000 660180749 0 402718720 -0.0057498650 0.1458797157 0.3084292412 700 27.9600000000 0.7376317978 0.2767980801 0.7376317978 0.0786390235 0.0203030000 660182997 0 402718720 -0.0069363327 0.1460772008 0.3087681830 701 28.0000000000 0.7382801771 0.2774563998 0.7382801771 0.0785844143 0.0513490000 660185245 0 402718720 -0.0079496019 0.1464129537 0.3091023862 702 28.0400000000 0.7392722964 0.2781142572 0.7392722964 0.0785292628 0.0243230000 660187493 0 402718720 -0.0094643887 0.1471336186 0.3093194366 703 28.0800000000 0.7399683595 0.2787712331 0.7399683595 0.0784747124 0.2220370000 672528685 0 402718720 -0.0103508933 0.1473325491 0.3098014891 704 28.1200000000 0.7378746271 0.2794233686 0.7399683595 0.0784205521 0.0193650000 676190141 0 402718720 -0.0114257857 0.1491341740 0.3120408356 705 28.1600000000 0.7385835052 0.2800746596 0.7399683595 0.0783661696 0.0335020000 679384581 0 402718720 -0.0124716274 0.1490417123 0.3125243783 706 28.2000000000 0.7387699485 0.2807243696 0.7399683595 0.0783122783 0.0269340000 679386829 0 402718720 -0.0129296137 0.1488249898 0.3128914535 707 28.2400000000 0.7391610146 0.2813727949 0.7399683595 0.0782580502 0.0245150000 679389077 0 402718720 -0.0144683309 0.1486749798 0.3133646250 708 28.2800000000 0.7395191789 0.2820198943 0.7399683595 0.0782038035 0.0238980000 679391325 0 402718720 -0.0151595725 0.1486110091 0.3137882650 709 28.3200000000 0.7405707836 0.2826666515 0.7405707836 0.0781490844 0.0224080000 679393573 0 402718720 -0.0162730124 0.1490916312 0.3140707612 710 28.3600000000 0.7409628034 0.2833121391 0.7409628034 0.0780947089 0.0236300000 679395821 0 402718720 -0.0176405273 0.1493309289 0.3144564331 711 28.4000000000 0.7414906621 0.2839565533 0.7414906621 0.0780408094 0.0238600000 679398069 0 402718720 -0.0188430492 0.1492393315 0.3149608076 712 28.4400000000 0.7418431044 0.2845996524 0.7418431044 0.0779864547 0.0233780000 679400317 0 402718720 -0.0204392504 0.1493442059 0.3153429329 713 28.4800000000 0.7425534725 0.2852419439 0.7425534725 0.0779322819 0.0201970000 679402565 0 402718720 -0.0217121504 0.1497867852 0.3157086670 714 28.5200000000 0.7430496216 0.2858831311 0.7430496216 0.0778783995 0.0254130000 679404813 0 402718720 -0.0230496749 0.1495300978 0.3162462413 715 28.5600000000 0.7438106537 0.2865235892 0.7438106537 0.0778242486 0.0536280000 679407061 0 402718720 -0.0242622662 0.1498215199 0.3166938424 716 28.6000000000 0.7440634966 0.2871626114 0.7440634966 0.0777707663 0.0227180000 679409309 0 402718720 -0.0260416344 0.1494328231 0.3171607256 717 28.6400000000 0.7446159124 0.2878006216 0.7446159124 0.0777169781 0.0264940000 679411557 0 402718720 -0.0274045784 0.1495974809 0.3174804151 718 28.6800000000 0.7453110814 0.2884378228 0.7453110814 0.0776634628 0.2155080000 691758825 0 402718720 -0.0291424002 0.1499566585 0.3177770376 719 28.7200000000 0.7464805245 0.2890748780 0.7464805245 0.0776114729 0.0278860000 695427625 0 402718720 -0.0306710489 0.1482425034 0.3175738752 720 28.7600000000 0.7470693588 0.2897109814 0.7470693588 0.0775593748 0.0246470000 698622065 0 402718720 -0.0320191123 0.1484130919 0.3178662360 721 28.8000000000 0.7472541928 0.2903455767 0.7472541928 0.0775070221 0.0208510000 698624313 0 402718720 -0.0331159756 0.1481872499 0.3184099793 722 28.8400000000 0.7474219799 0.2909786466 0.7474219799 0.0774541797 0.0196140000 698626561 0 402718720 -0.0351833664 0.1477068067 0.3188287020 723 28.8800000000 0.7479960918 0.2916107592 0.7479960918 0.0774012561 0.0198510000 698628809 0 402718720 -0.0361887403 0.1480215192 0.3191097975 724 28.9200000000 0.7482889295 0.2922415302 0.7482889295 0.0773481368 0.0189820000 698631057 0 402718720 -0.0381858647 0.1476643980 0.3195023835 725 28.9600000000 0.7486804128 0.2928711010 0.7486804128 0.0772953410 0.0198180000 698633305 0 402718720 -0.0392246470 0.1476424187 0.3199113607 726 29.0000000000 0.7492020130 0.2934996560 0.7492020130 0.0772425608 0.0185570000 698635553 0 402718720 -0.0404882878 0.1476190537 0.3202002347 727 29.0400000000 0.7497035861 0.2941271717 0.7497035861 0.0771902608 0.0183630000 698637801 0 402718720 -0.0416495353 0.1476455778 0.3205419183 728 29.0800000000 0.7497905493 0.2947530830 0.7497905493 0.0771384748 0.0229740000 698640049 0 402718720 -0.0424729772 0.1474402249 0.3207757473 729 29.1200000000 0.7502297759 0.2953778795 0.7502297759 0.0770871629 0.0214840000 698642297 0 402718720 -0.0434738882 0.1473321319 0.3210848868 730 29.1600000000 0.7503636479 0.2960011477 0.7503636479 0.0770358168 0.0195560000 698644545 0 402718720 -0.0442033671 0.1470564753 0.3214069903 731 29.2000000000 0.7502492070 0.2966225541 0.7503636479 0.0769840409 0.0560950000 698646793 0 402718720 -0.0458916798 0.1466479897 0.3216086328 732 29.2400000000 0.7506672144 0.2972428337 0.7506672144 0.0769324131 0.2573240000 711113477 0 402718720 -0.0469849147 0.1466646940 0.3217926919 733 29.2800000000 0.7503340244 0.2978609663 0.7506672144 0.0768812027 0.0260660000 714774933 0 402718720 -0.0475000069 0.1458761990 0.3224978745 734 29.3200000000 0.7505281568 0.2984776790 0.7506672144 0.0768291729 0.0238850000 717969373 0 402718720 -0.0483439825 0.1455845237 0.3226363659 735 29.3600000000 0.7505648136 0.2990927636 0.7506672144 0.0767771037 0.0194290000 717971621 0 402718720 -0.0495530814 0.1456180215 0.3227508664 736 29.4000000000 0.7502611279 0.2997057641 0.7506672144 0.0767256817 0.0179380000 717973869 0 402718720 -0.0504874773 0.1451154202 0.3228011727 737 29.4400000000 0.7497569919 0.3003164170 0.7506672144 0.0766742357 0.0183510000 717976117 0 402718720 -0.0514216945 0.1445585191 0.3229713440 738 29.4800000000 0.7495472431 0.3009251309 0.7506672144 0.0766227440 0.0185950000 717978365 0 402718720 -0.0518011712 0.1440925002 0.3232083619 739 29.5200000000 0.7490650415 0.3015315448 0.7506672144 0.0765716114 0.0186170000 717980613 0 402718720 -0.0522634909 0.1434483677 0.3233936727 740 29.5600000000 0.7485952377 0.3021356850 0.7506672144 0.0765208343 0.0178360000 717982861 0 402718720 -0.0527148657 0.1428375095 0.3235447705 741 29.6000000000 0.7484353185 0.3027379787 0.7506672144 0.0764702594 0.0179610000 717985109 0 402718720 -0.0534816757 0.1424289346 0.3237701654 742 29.6400000000 0.7483118176 0.3033384825 0.7506672144 0.0764197323 0.0256700000 717987357 0 402718720 -0.0540046431 0.1420357674 0.3239409029 743 29.6800000000 0.7478654981 0.3039367692 0.7506672144 0.0763694334 0.0203710000 717989605 0 402718720 -0.0544561222 0.1416239291 0.3239953220 744 29.7200000000 0.7470328808 0.3045323285 0.7506672144 0.0763199120 0.0186000000 717991853 0 402718720 -0.0555588268 0.1403783411 0.3243754208 745 29.7600000000 0.7465841174 0.3051256866 0.7506672144 0.0762690561 0.0216310000 717994101 0 402718720 -0.0556693859 0.1396113336 0.3245798945 746 29.8000000000 0.7465743423 0.3057174408 0.7506672144 0.0762180080 0.0560970000 717996349 0 402718720 -0.0562336110 0.1394093335 0.3247527182 747 29.8400000000 0.7463288903 0.3063072821 0.7506672144 0.0761671336 0.0190290000 717998597 0 402718720 -0.0566603281 0.1389177144 0.3249715865 748 29.8800000000 0.7460796237 0.3068952131 0.7506672144 0.0761161765 0.2988690000 730361901 0 402718720 -0.0568656214 0.1384537965 0.3251008987 749 29.9200000000 0.7454302907 0.3074807072 0.7506672144 0.0760653276 0.0176900000 734023357 0 402718720 -0.0580468960 0.1377967000 0.3259262443 750 29.9600000000 0.7455003262 0.3080647333 0.7506672144 0.0760146141 0.0257340000 737217797 0 402718720 -0.0585671924 0.1376772970 0.3260620832 751 30.0000000000 0.7447821498 0.3086462478 0.7506672144 0.0759639677 0.0205430000 737220045 0 402718720 -0.0584797934 0.1364146471 0.3263602853 752 30.0400000000 0.7446529865 0.3092260440 0.7506672144 0.0759134446 0.0172440000 737222293 0 402718720 -0.0585765019 0.1359098107 0.3266250491 753 30.0800000000 0.7447380424 0.3098044132 0.7506672144 0.0758631856 0.0161400000 737224541 0 402718720 -0.0589494891 0.1355668902 0.3269358873 754 30.1200000000 0.7446233034 0.3103810961 0.7506672144 0.0758132334 0.0171430000 737226789 0 402718720 -0.0586836077 0.1349944919 0.3272689283 755 30.1600000000 0.7447713017 0.3109564474 0.7506672144 0.0757633484 0.0164700000 737229037 0 402718720 -0.0585186072 0.1345663220 0.3277347386 756 30.2000000000 0.7450040579 0.3115305844 0.7506672144 0.0757132632 0.0160840000 737231285 0 402718720 -0.0587756000 0.1342224777 0.3279297650 757 30.2400000000 0.7449843884 0.3121031786 0.7506672144 0.0756636314 0.0160020000 737233533 0 402718720 -0.0586409606 0.1336253434 0.3283937573 758 30.2800000000 0.7461348772 0.3126757798 0.7506672144 0.0756144424 0.0156920000 737235781 0 402718720 -0.0586450957 0.1340340674 0.3286959827 759 30.3200000000 0.7463044524 0.3132470956 0.7506672144 0.0755660396 0.0189450000 737238029 0 402718720 -0.0586080961 0.1337577552 0.3291289806 760 30.3600000000 0.7461419106 0.3138166940 0.7506672144 0.0755187052 0.0193070000 737240277 0 402718720 -0.0583066829 0.1328985095 0.3295515180 761 30.4000000000 0.7469472885 0.3143858538 0.7506672144 0.0754702707 0.2969880000 749598709 0 402718720 -0.0577625260 0.1329363734 0.3300015032 762 30.4400000000 0.7478384972 0.3149546893 0.7506672144 0.0754210841 0.0150140000 753260165 0 402718720 -0.0576108471 0.1320934296 0.3304557204 763 30.4800000000 0.7477661967 0.3155219390 0.7506672144 0.0753720218 0.0260750000 756454605 0 402718720 -0.0571006238 0.1312679350 0.3310849071 764 30.5200000000 0.7478818893 0.3160878551 0.7506672144 0.0753236807 0.0166980000 756456853 0 402718720 -0.0561068729 0.1307491064 0.3316242695 765 30.5600000000 0.7483792901 0.3166529420 0.7506672144 0.0752754232 0.0459830000 756459101 0 402718720 -0.0555082969 0.1302733719 0.3321564496 766 30.6000000000 0.7486137748 0.3172168595 0.7506672144 0.0752284851 0.0183400000 756461349 0 402718720 -0.0546724312 0.1297303587 0.3327158391 767 30.6400000000 0.7485099435 0.3177791712 0.7506672144 0.0751834468 0.0154800000 756463597 0 402718720 -0.0536270700 0.1287282407 0.3332796991 768 30.6800000000 0.7491508126 0.3183408531 0.7506672144 0.0751384424 0.0150800000 756465845 0 402718720 -0.0525153913 0.1284946501 0.3338156939 769 30.7200000000 0.7503258586 0.3189026021 0.7506672144 0.0751102173 0.2665770000 768831553 0 402718720 -0.0503228605 0.1277694255 0.3349317908 770 30.7600000000 0.7498086095 0.3194622203 0.7506672144 0.0750731896 0.0226310000 772493009 0 402718720 -0.0487376004 0.1258462369 0.3352633715 771 30.8000000000 0.7497784495 0.3200203477 0.7506672144 0.0750321253 0.0159100000 775687449 0 402718720 -0.0474903360 0.1250226945 0.3356213570 772 30.8400000000 0.7498840690 0.3205771660 0.7506672144 0.0749907724 0.0142070000 775689697 0 402718720 -0.0467418022 0.1246614158 0.3359071314 773 30.8800000000 0.7496938109 0.3211322975 0.7506672144 0.0749520090 0.0137590000 775691945 0 402718720 -0.0454576835 0.1235742792 0.3364129364 774 30.9200000000 0.7490295768 0.3216851363 0.7506672144 0.0749122958 0.0137670000 775694193 0 402718720 -0.0442409813 0.1223068312 0.3368007839 775 30.9600000000 0.7488636971 0.3222363345 0.7506672144 0.0748719540 0.0134740000 775696441 0 402718720 -0.0431684963 0.1216641441 0.3371306658 776 31.0000000000 0.7487961054 0.3227860249 0.7506672144 0.0748335023 0.2875030000 788056637 0 402718720 -0.0417987108 0.1207907945 0.3376774490 777 31.0400000000 0.7488195896 0.3233343306 0.7506672144 0.0747923042 0.0239090000 791718093 0 402718720 -0.0407129154 0.1199988723 0.3384265006 778 31.0800000000 0.7485988140 0.3238809431 0.7506672144 0.0747501220 0.0163100000 794912533 0 402718720 -0.0396483913 0.1187986508 0.3388712108 779 31.1200000000 0.7486588359 0.3244262292 0.7506672144 0.0747062315 0.0148100000 794914781 0 402718720 -0.0384697504 0.1176953539 0.3395695388 780 31.1600000000 0.7487872243 0.3249702818 0.7506672144 0.0746614690 0.0151370000 794917029 0 402718720 -0.0374984480 0.1167609617 0.3402261138 781 31.2000000000 0.7485856414 0.3255126830 0.7506672144 0.0746163255 0.0151460000 794919277 0 402718720 -0.0368038267 0.1155460179 0.3407852948 782 31.2400000000 0.7486143708 0.3260537338 0.7506672144 0.0745722282 0.0135150000 794921525 0 402718720 -0.0357993431 0.1142279878 0.3415756822 783 31.2800000000 0.7484944463 0.3265932494 0.7506672144 0.0745273544 0.2502940000 807280493 0 402718720 -0.0349194445 0.1129167005 0.3422838748 784 31.3200000000 0.7480120659 0.3271307734 0.7506672144 0.0744827370 0.0203970000 810941949 0 402718720 -0.0340615995 0.1112069860 0.3430622220 785 31.3600000000 0.7478026152 0.3276666611 0.7506672144 0.0744371931 0.0144480000 814136389 0 402718720 -0.0334010869 0.1096179709 0.3435809314 786 31.4000000000 0.7476147413 0.3282009461 0.7506672144 0.0743910108 0.0136880000 814138637 0 402718720 -0.0329578482 0.1084367409 0.3440535069 787 31.4400000000 0.7464106679 0.3287323435 0.7506672144 0.0743452189 0.0131660000 814140885 0 402718720 -0.0323251672 0.1063861027 0.3447570205 788 31.4800000000 0.7462249994 0.3292621565 0.7506672144 0.0743006986 0.0133850000 814143133 0 402718720 -0.0316285528 0.1047421321 0.3453631699 789 31.5200000000 0.7457405329 0.3297900125 0.7506672144 0.0742566527 0.0131630000 814145381 0 402718720 -0.0312290136 0.1033212841 0.3460053205 790 31.5600000000 0.7447978854 0.3303153389 0.7506672144 0.0742133900 0.2591620000 826510441 0 402718720 -0.0307264123 0.1010137647 0.3466756046 791 31.6000000000 0.7436579466 0.3308378960 0.7506672144 0.0741786081 0.0172070000 830171897 0 402718720 -0.0302429665 0.0976115242 0.3482380807 792 31.6400000000 0.7434507608 0.3313588718 0.7506672144 0.0741344566 0.0138230000 833366337 0 402718720 -0.0297276042 0.0962844267 0.3491608799 793 31.6800000000 0.7426955104 0.3318775813 0.7506672144 0.0740901256 0.0125150000 833368585 0 402718720 -0.0295816101 0.0941407830 0.3498967886 794 31.7200000000 0.7433320284 0.3323957859 0.7506672144 0.0740446948 0.0120920000 833370833 0 402718720 -0.0294302907 0.0936523825 0.3504096568 795 31.7600000000 0.7438254356 0.3329133075 0.7506672144 0.0740001290 0.0113400000 833373081 0 402718720 -0.0295884814 0.0932023376 0.3509939015 796 31.8000000000 0.7436494827 0.3334293077 0.7506672144 0.0739582921 0.0112740000 833375329 0 402718720 -0.0293643456 0.0914532989 0.3518599570 797 31.8400000000 0.7435960174 0.3339439460 0.7506672144 0.0739177656 0.0108900000 833377577 0 402718720 -0.0293344390 0.0894791186 0.3528510332 798 31.8800000000 0.7424090505 0.3344558070 0.7506672144 0.0739060696 0.1755630000 845727997 0 402718720 -0.0288936328 0.0836103261 0.3553037941 799 31.9200000000 0.7413697839 0.3349650861 0.7506672144 0.0738657559 0.0137130000 849389453 0 402718720 -0.0292849988 0.0809621215 0.3568275273 800 31.9600000000 0.7414238453 0.3354731595 0.7506672144 0.0738225647 0.0111090000 852583893 0 402718720 -0.0294216052 0.0795293599 0.3579149246 801 32.0000000000 0.7422660589 0.3359810158 0.7506672144 0.0737773893 0.0183190000 852586141 0 402718720 -0.0293807257 0.0783020332 0.3589608669 802 32.0400000000 0.7418631911 0.3364871033 0.7506672144 0.0737314851 0.0118630000 852588389 0 402718720 -0.0297684018 0.0755992755 0.3599539101 803 32.0800000000 0.7414228916 0.3369913820 0.7506672144 0.0736859362 0.0103290000 852590637 0 402718720 -0.0300411507 0.0725378469 0.3612238765 804 32.1199999990 0.7420666814 0.3374952070 0.7506672144 0.0736414676 0.0103310000 852592885 0 402718720 -0.0305330101 0.0676783174 0.3637291789 805 32.1600000000 0.7430089116 0.3379989507 0.7506672144 0.0735958241 0.1889770000 864953433 0 402718720 -0.0308613107 0.0662826747 0.3648995161 806 32.2000000000 0.7437205315 0.3385023274 0.7506672144 0.0735503152 0.0123370000 868614889 0 402718720 -0.0313631333 0.0644956231 0.3663462996 807 32.2400000000 0.7436974049 0.3390044279 0.7506672144 0.0735049250 0.0109290000 871809329 0 402718720 -0.0317286514 0.0620645322 0.3679410517 808 32.2800000000 0.7448396683 0.3395066992 0.7506672144 0.0734594285 0.0097770000 871811577 0 402718720 -0.0322520211 0.0600579605 0.3690644801 809 32.3200000000 0.7449113131 0.3400078174 0.7506672144 0.0734155494 0.0097370000 871813825 0 402718720 -0.0326000042 0.0554319844 0.3708883226 810 32.3600000000 0.7448226810 0.3405075888 0.7506672144 0.0733706605 0.0246250000 871816073 0 402718720 -0.0329596289 0.0517663360 0.3727943897 811 32.4000000000 0.7467444539 0.3410084974 0.7506672144 0.0733256229 0.0191110000 871818321 0 402718720 -0.0336373784 0.0507718213 0.3739325106 812 32.4399999990 0.7482157350 0.3415099842 0.7506672144 0.0732804531 0.1432390000 884178557 0 402718720 -0.0339782611 0.0487657189 0.3754871786 813 32.4800000000 0.7491958141 0.3420114427 0.7506672144 0.0732360172 0.0109280000 887840013 0 402718720 -0.0342284106 0.0456987396 0.3775162697 814 32.5200000000 0.7503058910 0.3425130330 0.7506672144 0.0731923323 0.0096140000 891034453 0 402718720 -0.0344646312 0.0420613997 0.3794065416 815 32.5600000000 0.7514935136 0.3430148495 0.7514935136 0.0731490274 0.0097130000 891036701 0 402718720 -0.0349668376 0.0390058495 0.3813239336 816 32.6000000000 0.7535127997 0.3435179107 0.7535127997 0.0731051245 0.0096520000 891038949 0 402718720 -0.0353492498 0.0366476290 0.3832381070 817 32.6400000000 0.7559669018 0.3440227443 0.7559669018 0.0730615580 0.0098080000 891041197 0 402718720 -0.0356188528 0.0323209986 0.3855341077 818 32.6800000000 0.7576554418 0.3445284077 0.7576554418 0.0730185362 0.0098390000 891043445 0 402718720 -0.0360815711 0.0272420179 0.3879596889 819 32.7200000000 0.7591753006 0.3450346921 0.7591753006 0.0729745741 0.0097270000 891045693 0 402718720 -0.0364894569 0.0237308778 0.3900000751 820 32.7599999990 0.7608460784 0.3455417791 0.7608460784 0.0729301737 0.0165410000 891047941 0 402718720 -0.0372330323 0.0217134934 0.3917181194 821 32.7999999990 0.7627124786 0.3460499042 0.7627124786 0.0728864298 0.0105240000 891050189 0 402718720 -0.0377932154 0.0190107636 0.3934487402 822 32.8400000000 0.7644667625 0.3465589272 0.7644667625 0.0728441021 0.0104690000 891052437 0 402718720 -0.0381485261 0.0147852497 0.3957377672 823 32.8800000000 0.7666502595 0.3470693662 0.7666502595 0.0728021149 0.0102640000 891054685 0 402718720 -0.0378413759 0.0109682009 0.3977077603 824 32.9200000000 0.7689338923 0.3475813377 0.7689338923 0.0727590301 0.0098000000 891056933 0 402718720 -0.0378277674 0.0073385956 0.3997787237 825 32.9600000000 0.7708943486 0.3480944444 0.7708943486 0.0727150261 0.1134720000 903399841 0 402718720 -0.0380548052 0.0043426487 0.4014577866 826 33.0000000000 0.7723438144 0.3486080635 0.7723438144 0.0726712188 0.0113510000 907061297 0 402718720 -0.0393913239 0.0012217648 0.4039643705 827 33.0400000000 0.7742893100 0.3491227929 0.7742893100 0.0726273482 0.0097750000 910255737 0 402718720 -0.0394946560 -0.0023185853 0.4056216478 828 33.0800000000 0.7758572698 0.3496381727 0.7758572698 0.0725834945 0.0091350000 910257985 0 402718720 -0.0396509469 -0.0048058811 0.4069980681 829 33.1199999990 0.7774605751 0.3501542432 0.7774605751 0.0725399657 0.0089270000 910260233 0 402718720 -0.0396886952 -0.0084686540 0.4087110460 830 33.1600000000 0.7795065641 0.3506715351 0.7795065641 0.0724966169 0.0311340000 910262481 0 402718720 -0.0396055616 -0.0127510028 0.4106832445 831 33.2000000000 0.7812249660 0.3511896500 0.7812249660 0.0724531456 0.0148240000 910264729 0 402718720 -0.0396052077 -0.0163288061 0.4124218524 832 33.2400000000 0.7833926678 0.3517091247 0.7833926678 0.0724101296 0.1463320000 927847805 0 402718720 -0.0396052077 -0.0163288061 0.4124218524 833 33.2800000000 0.7863632441 0.3522309184 0.7863632441 0.0723681916 0.0285450000 931195653 0 402718720 -0.0387510061 -0.0151215550 0.4121665955 834 33.3200000000 0.7886733413 0.3527542307 0.7886733413 0.0723253990 0.0271800000 931274485 0 402718720 -0.0387510061 -0.0151215550 0.4121665955 835 33.3600000000 0.7906684875 0.3532786789 0.7906684875 0.0722823950 0.0252970000 931353317 0 402718720 -0.0387510061 -0.0151215550 0.4121665955 836 33.4000000000 0.7933464050 0.3538050757 0.7933464050 0.0722394473 0.0229250000 931432149 0 402718720 -0.0387510061 -0.0151215550 0.4121665955 837 33.4399999990 0.7963729501 0.3543338306 0.7963729501 0.0721967967 0.0234310000 931510981 0 402718720 -0.0387510061 -0.0151215550 0.4121665955 838 33.4800000000 0.8540058136 0.3549300979 0.8540058136 0.0741353835 0.0161250000 931589813 0 402718720 0.1005366743 0.0272473171 0.3738146126 839 33.5200000000 0.8571935296 0.3555287432 0.8571935296 0.0740913783 0.0209230000 925663029 0 402718720 0.0997209698 0.0286760051 0.3727311194 840 33.5600000000 0.8587354422 0.3561277988 0.8587354422 0.0740474481 0.0216560000 937896893 0 402718720 0.0997209698 0.0286760051 0.3727311194 841 33.6000000000 0.8626621366 0.3567300989 0.8626621366 0.0740043099 0.0213430000 941244741 0 402718720 0.0997209698 0.0286760051 0.3727311194 842 33.6400000000 0.8673532009 0.3573365396 0.8673532009 0.0739621473 0.0191240000 941323573 0 402718720 0.0997209698 0.0286760051 0.3727311194 843 33.6800000000 0.8681826591 0.3579425255 0.8681826591 0.0739189933 0.0191040000 941402405 0 402718720 0.0997209698 0.0286760051 0.3727311194 844 33.7200000000 0.8695693612 0.3585487184 0.8695693612 0.0738752911 0.0525830000 941481237 0 402718720 0.0997209698 0.0286760051 0.3727311194 845 33.7599999990 0.8723437190 0.3591567599 0.8723437190 0.0738319583 0.0156020000 941560069 0 402718720 0.0997209698 0.0286760051 0.3727311194 846 33.7999999990 0.8732804656 0.3597644711 0.8732804656 0.0737889036 0.0126510000 941638901 0 402718720 0.0997209698 0.0286760051 0.3727311194 847 33.8400000000 0.8739113212 0.3603714922 0.8739113212 0.0737454791 0.0124940000 941717733 0 402718720 0.0997209698 0.0286760051 0.3727311194 848 33.8800000000 0.8781635761 0.3609820960 0.8781635761 0.0737028469 0.0119780000 941796565 0 402718720 0.0997209698 0.0286760051 0.3727311194 849 33.9200000000 0.8800572753 0.3615934920 0.8800572753 0.0736597581 0.0107620000 941875397 0 402718720 0.0997209698 0.0286760051 0.3727311194 850 33.9600000000 0.8798338175 0.3622031865 0.8800572753 0.0736165630 0.0105470000 941954229 0 402718720 0.0997209698 0.0286760051 0.3727311194 851 34.0000000000 0.8815549016 0.3628134705 0.8815549016 0.0735735190 0.0104220000 941956237 0 402718720 0.0997209698 0.0286760051 0.3727311194 852 34.0400000000 0.8819795251 0.3634228204 0.8819795251 0.0735304349 0.0102010000 941958245 0 402718720 0.0997209698 0.0286760051 0.3727311194 853 34.0800000000 0.8823042512 0.3640311222 0.8823042512 0.0734874622 0.0102120000 941960253 0 402718720 0.0997209698 0.0286760051 0.3727311194 854 34.1199999990 0.8840029240 0.3646399884 0.8840029240 0.0734447041 0.0101900000 941962261 0 402718720 0.0997209698 0.0286760051 0.3727311194 855 34.1600000000 0.8852621913 0.3652489033 0.8852621913 0.0734022600 0.0090680000 941964269 0 402718720 0.0997209698 0.0286760051 0.3727311194 856 34.2000000000 0.8843561411 0.3658553370 0.8852621913 0.0733601568 0.0066640000 941966277 0 402718720 0.0997209698 0.0286760051 0.3727311194 857 34.2400000000 0.8835467696 0.3664594110 0.8852621913 0.0733175309 0.0066460000 941968285 0 402718720 0.0997209698 0.0286760051 0.3727311194 858 34.2800000000 0.8832901120 0.3670617778 0.8852621913 0.0732749329 0.0073670000 941970293 0 402718720 0.0997209698 0.0286760051 0.3727311194 859 34.3200000000 0.8819204569 0.3676611476 0.8852621913 0.0732327719 0.0083100000 941972301 0 402718720 0.0997209698 0.0286760051 0.3727311194 860 34.3600000000 0.8809925318 0.3682580446 0.8852621913 0.0731907643 0.0065500000 941974309 0 402718720 0.0997209698 0.0286760051 0.3727311194 861 34.4000000000 0.8802407980 0.3688526819 0.8852621913 0.0731489630 0.0067190000 942053141 0 402718720 0.0997209698 0.0286760051 0.3727311194 862 34.4400000000 0.8800657392 0.3694457365 0.8852621913 0.0731080471 0.0064690000 942055149 0 402718720 0.0997209698 0.0286760051 0.3727311194 863 34.4800000000 0.8802838922 0.3700376695 0.8852621913 0.0730662610 0.0051960000 942057157 0 402718720 0.0997209698 0.0286760051 0.3727311194 864 34.5200000000 0.8778804541 0.3706254505 0.8852621913 0.0730247015 0.0051830000 942059165 0 402718720 0.0997209698 0.0286760051 0.3727311194 865 34.5600000000 0.8765608668 0.3712103469 0.8852621913 0.0729833421 0.0057160000 942137997 0 402718720 0.0997209698 0.0286760051 0.3727311194 866 34.6000000000 0.8767654300 0.3717941288 0.8852621913 0.0729418993 0.0076350000 942216829 0 402718720 0.0997209698 0.0286760051 0.3727311194 867 34.6400000000 0.8760612607 0.3723757518 0.8852621913 0.0728999359 0.0203340000 942295661 0 402718720 0.0997209698 0.0286760051 0.3727311194 868 34.6800000000 0.8745651245 0.3729543109 0.8852621913 0.0728580955 0.0067300000 942374493 0 402718720 0.0997209698 0.0286760051 0.3727311194 869 34.7200000000 0.8742853999 0.3735312167 0.8852621913 0.0728163276 0.0042210000 942376501 0 402718720 0.0997209698 0.0286760051 0.3727311194 870 34.7600000000 0.8740592599 0.3741065363 0.8852621913 0.0727744633 0.0056390000 942455333 0 402718720 0.0997209698 0.0286760051 0.3727311194 871 34.8000000000 0.8739796281 0.3746804434 0.8852621913 0.0727326973 0.0055470000 942534165 0 402718720 0.0997209698 0.0286760051 0.3727311194 872 34.8400000000 0.8748378754 0.3752540184 0.8852621913 0.0726911873 0.0065080000 942536173 0 402718720 0.0997209698 0.0286760051 0.3727311194 873 34.8800000000 0.8748862743 0.3758263349 0.8852621913 0.0726500602 0.0066090000 942615005 0 402718720 0.0997209698 0.0286760051 0.3727311194 874 34.9200000000 0.8741739392 0.3763965266 0.8852621913 0.0726086581 0.0041780000 942617013 0 402718720 0.0997209698 0.0286760051 0.3727311194 875 34.9600000000 0.8743845820 0.3769656558 0.8852621913 0.0725672255 0.0041750000 942619021 0 402718720 0.0997209698 0.0286760051 0.3727311194 876 35.0000000000 0.8748034239 0.3775339638 0.8852621913 0.0725260223 0.0042000000 942621029 0 402718720 0.0997209698 0.0286760051 0.3727311194 877 35.0400000000 0.8742167950 0.3781003068 0.8852621913 0.0724846905 0.0041050000 942623037 0 402718720 0.0997209698 0.0286760051 0.3727311194 878 35.0800000000 0.8742954731 0.3786654494 0.8852621913 0.0724434351 0.0041020000 942625045 0 402718720 0.0997209698 0.0286760051 0.3727311194 879 35.1200000000 0.8745121956 0.3792295526 0.8852621913 0.0724023972 0.0040720000 942627053 0 402718720 0.0997209698 0.0286760051 0.3727311194 880 35.1600000000 0.8734283447 0.3797911422 0.8852621913 0.0723621540 0.0041220000 942629061 0 402718720 0.0997209698 0.0286760051 0.3727311194 881 35.2000000000 0.8721860647 0.3803500467 0.8852621913 0.0723210930 0.0190370000 942631069 0 402718720 0.0997209698 0.0286760051 0.3727311194 882 35.2400000000 0.8717640638 0.3809072055 0.8852621913 0.0722802708 0.0106330000 942633077 0 402718720 0.0997209698 0.0286760051 0.3727311194 883 35.2800000000 0.8712061644 0.3814624704 0.8852621913 0.0722395942 0.0069010000 942635085 0 402718720 0.0997209698 0.0286760051 0.3727311194 884 35.3200000000 0.8700240254 0.3820151419 0.8852621913 0.0721991471 0.0055240000 942637093 0 402718720 0.0997209698 0.0286760051 0.3727311194 885 35.3600000000 0.8692242503 0.3825656606 0.8852621913 0.0721590111 0.0043570000 942639101 0 402718720 0.0997209698 0.0286760051 0.3727311194 886 35.4000000000 0.8683313727 0.3831139289 0.8852621913 0.0721190528 0.0040750000 942641109 0 402718720 0.0997209698 0.0286760051 0.3727311194 887 35.4400000000 0.8671094775 0.3836595834 0.8852621913 0.0720793348 0.0040520000 942643117 0 402718720 0.0997209698 0.0286760051 0.3727311194 888 35.4800000000 0.8662777543 0.3842030724 0.8852621913 0.0720393802 0.0041910000 942645125 0 402718720 0.0997209698 0.0286760051 0.3727311194 889 35.5200000000 0.8653189540 0.3847442601 0.8852621913 0.0720000640 0.0042040000 942647133 0 402718720 0.0997209698 0.0286760051 0.3727311194 890 35.5600000000 0.8639956117 0.3852827448 0.8852621913 0.0719604889 0.0041650000 942649141 0 402718720 0.0997209698 0.0286760051 0.3727311194 891 35.6000000000 0.8639501929 0.3858199697 0.8852621913 0.0719209664 0.0045160000 942651149 0 402718720 0.0997209698 0.0286760051 0.3727311194 892 35.6400000000 0.8627363443 0.3863546293 0.8852621913 0.0718821736 0.0042710000 942653157 0 402718720 0.0997209698 0.0286760051 0.3727311194 893 35.6800000000 0.8614968657 0.3868867035 0.8852621913 0.0718431218 0.0043250000 942731989 0 402718720 0.0997209698 0.0286760051 0.3727311194 894 35.7200000000 0.8613581657 0.3874174322 0.8852621913 0.0718042788 0.0054380000 942733997 0 402718720 0.0997209698 0.0286760051 0.3727311194 895 35.7600000000 0.8612650633 0.3879468709 0.8852621913 0.0717663241 0.0042110000 942736005 0 402718720 0.0997209698 0.0286760051 0.3727311194 896 35.8000000000 0.8600594401 0.3884737823 0.8852621913 0.0717293810 0.0053570000 942738013 0 402718720 0.0997209698 0.0286760051 0.3727311194 897 35.8400000000 0.8594067693 0.3889987912 0.8852621913 0.0716916688 0.0130790000 942740021 0 402718720 0.0997209698 0.0286760051 0.3727311194 898 35.8800000000 0.8587230444 0.3895218694 0.8852621913 0.0716530280 0.0044340000 942818853 0 402718720 0.0997209698 0.0286760051 0.3727311194 899 35.9200000000 0.8589609861 0.3900440486 0.8852621913 0.0716149429 0.0054490000 942820861 0 402718720 0.0997209698 0.0286760051 0.3727311194 900 35.9600000000 0.8585839868 0.3905646485 0.8852621913 0.0715766347 0.0056640000 942899693 0 402718720 0.0997209698 0.0286760051 0.3727311194 901 36.0000000000 0.8580895662 0.3910835441 0.8852621913 0.0715384982 0.0080120000 942978525 0 402718720 0.0997209698 0.0286760051 0.3727311194 902 36.0400000000 0.8577711582 0.3916009362 0.8852621913 0.0715007709 0.0072280000 942980533 0 402718720 0.0997209698 0.0286760051 0.3727311194 903 36.0800000000 0.8567733765 0.3921160773 0.8852621913 0.0714626944 0.0106950000 942982541 0 402718720 0.0997209698 0.0286760051 0.3727311194 904 36.1200000000 0.8568152785 0.3926301251 0.8852621913 0.0714251979 0.0073620000 943061373 0 402718720 0.0997209698 0.0286760051 0.3727311194 905 36.1600000000 0.8561140895 0.3931422621 0.8852621913 0.0713878969 0.0084820000 943140205 0 402718720 0.0997209698 0.0286760051 0.3727311194 906 36.2000000000 0.8555898070 0.3936526898 0.8852621913 0.0713505904 0.0067340000 943219037 0 402718720 0.0997209698 0.0286760051 0.3727311194 907 36.2400000000 0.8558330536 0.3941622602 0.8852621913 0.0713132102 0.0089230000 943297869 0 402718720 0.0997209698 0.0286760051 0.3727311194 908 36.2800000000 0.8554033041 0.3946702349 0.8852621913 0.0712756631 0.0108840000 943376701 0 402718720 0.0997209698 0.0286760051 0.3727311194 909 36.3200000000 0.8551658392 0.3951768308 0.8852621913 0.0712375883 0.0095300000 943378709 0 402718720 0.0997209698 0.0286760051 0.3727311194 910 36.3600000000 0.8551160693 0.3956822585 0.8852621913 0.0711994181 0.0096420000 943380717 0 402718720 0.0997209698 0.0286760051 0.3727311194 911 36.4000000000 0.8554426432 0.3961869351 0.8852621913 0.0711614586 0.0114190000 943459549 0 402718720 0.0997209698 0.0286760051 0.3727311194 912 36.4400000000 0.8560228944 0.3966911412 0.8852621913 0.0711238186 0.0101450000 943461557 0 402718720 0.0997209698 0.0286760051 0.3727311194 913 36.4800000000 0.8554864526 0.3971936552 0.8852621913 0.0710927779 0.0100610000 943463565 0 402718720 0.0997209698 0.0286760051 0.3727311194 914 36.5200000000 0.8557743430 0.3976953846 0.8852621913 0.0710557360 0.0122490000 943542397 0 402718720 0.0997209698 0.0286760051 0.3727311194 915 36.5600000000 0.8561135530 0.3981963881 0.8852621913 0.0710184635 0.0147250000 943544405 0 402718720 0.0997209698 0.0286760051 0.3727311194 916 36.6000000000 0.8561655879 0.3986963545 0.8852621913 0.0709812535 0.0134490000 943546413 0 402718720 0.0997209698 0.0286760051 0.3727311194 917 36.6400000000 0.8564029932 0.3991954893 0.8852621913 0.0709439513 0.0131280000 943548421 0 402718720 0.0997209698 0.0286760051 0.3727311194 918 36.6800000000 0.8567868471 0.3996939548 0.8852621913 0.0709069403 0.0147730000 943627253 0 402718720 0.0997209698 0.0286760051 0.3727311194 919 36.7200000000 0.8572476506 0.4001918370 0.8852621913 0.0708703060 0.0140290000 943706085 0 402718720 0.0997209698 0.0286760051 0.3727311194 920 36.7600000000 0.8571206331 0.4006884987 0.8852621913 0.0708335463 0.0131830000 943784917 0 402718720 0.0997209698 0.0286760051 0.3727311194 921 36.8000000000 0.8578673005 0.4011848927 0.8852621913 0.0707964330 0.0148600000 943863749 0 402718720 0.0997209698 0.0286760051 0.3727311194 922 36.8400000000 0.8589097261 0.4016813404 0.8852621913 0.0707597496 0.0165110000 943942581 0 402718720 0.0997209698 0.0286760051 0.3727311194 923 36.8800000000 0.8600692153 0.4021779687 0.8852621913 0.0707235484 0.0149940000 944021413 0 402718720 0.0997209698 0.0286760051 0.3727311194 924 36.9200000000 0.8607771993 0.4026742882 0.8852621913 0.0706874798 0.0157930000 944100245 0 402718720 0.0997209698 0.0286760051 0.3727311194 925 36.9600000000 0.8613312244 0.4031701335 0.8852621913 0.0706514279 0.0163090000 944179077 0 402718720 0.0997209698 0.0286760051 0.3727311194 926 37.0000000000 0.8617027998 0.4036653092 0.8852621913 0.0706148306 0.0152790000 944257909 0 402718720 0.0997209698 0.0286760051 0.3727311194 927 37.0400000000 0.8626342416 0.4041604213 0.8852621913 0.0705784753 0.0142280000 944336741 0 402718720 0.0997209698 0.0286760051 0.3727311194 928 37.0800000000 0.8629597425 0.4046548171 0.8852621913 0.0705426674 0.0150040000 944415573 0 402718720 0.0997209698 0.0286760051 0.3727311194 929 37.1200000000 0.8625931144 0.4051477539 0.8852621913 0.0705063477 0.0169930000 944494405 0 402718720 0.0997209698 0.0286760051 0.3727311194 930 37.1600000000 0.8623544574 0.4056393740 0.8852621913 0.0704696790 0.0194580000 944573237 0 402718720 0.0997209698 0.0286760051 0.3727311194 931 37.2000000000 0.8627212644 0.4061303320 0.8852621913 0.0704331406 0.0204920000 944652069 0 402718720 0.0997209698 0.0286760051 0.3727311194 932 37.2400000000 0.8625555038 0.4066200586 0.8852621913 0.0703975257 0.0192740000 944730901 0 402718720 0.0997209698 0.0286760051 0.3727311194 933 37.2800000000 0.8615940809 0.4071077049 0.8852621913 0.0703624789 0.0201120000 944809733 0 402718720 0.0997209698 0.0286760051 0.3727311194 934 37.3200000000 0.8610509038 0.4075937255 0.8852621913 0.0703273278 0.0233550000 944888565 0 402718720 0.0997209698 0.0286760051 0.3727311194 935 37.3600000000 0.8599522114 0.4080775314 0.8852621913 0.0702913626 0.0253410000 944967397 0 402718720 0.0997209698 0.0286760051 0.3727311194 936 37.4000000000 0.8597215414 0.4085600570 0.8852621913 0.0702555276 0.0668600000 945046229 0 402718720 0.0997209698 0.0286760051 0.3727311194 937 37.4400000000 0.8590539694 0.4090408403 0.8852621913 0.0702194682 0.0306640000 945125061 0 402718720 0.0997209698 0.0286760051 0.3727311194 938 37.4800000000 0.8590071201 0.4095205485 0.8852621913 0.0701828743 0.0332110000 945203893 0 402718720 0.0997209698 0.0286760051 0.3727311194 939 37.5200000000 0.8588940501 0.4099991145 0.8852621913 0.0701465309 0.0322500000 945282725 0 402718720 0.0997209698 0.0286760051 0.3727311194 940 37.5600000000 0.8588119149 0.4104765749 0.8852621913 0.0701101375 0.0365930000 945361557 0 402718720 0.0997209698 0.0286760051 0.3727311194 941 37.6000000000 0.8578245640 0.4109519713 0.8852621913 0.0700736704 0.0359890000 945440389 0 402718720 0.0997209698 0.0286760051 0.3727311194 942 37.6400000000 0.8569595218 0.4114254400 0.8852621913 0.0700370665 0.0348520000 945519221 0 402718720 0.0997209698 0.0286760051 0.3727311194 943 37.6800000000 0.8567427397 0.4118976747 0.8852621913 0.0700005146 0.0362340000 945598053 0 402718720 0.0997209698 0.0286760051 0.3727311194 944 37.7200000000 0.8570199013 0.4123692025 0.8852621913 0.0699642504 0.0336710000 945676885 0 402718720 0.0997209698 0.0286760051 0.3727311194 945 37.7600000000 0.8585543036 0.4128413560 0.8852621913 0.0699283404 0.0371550000 945755717 0 402718720 0.0997209698 0.0286760051 0.3727311194 946 37.8000000000 0.8586429954 0.4133126051 0.8852621913 0.0698923918 0.0353570000 945834549 0 402718720 0.0997209698 0.0286760051 0.3727311194 947 37.8400000000 0.8585887551 0.4137828017 0.8852621913 0.0698562459 0.0344710000 945913381 0 402718720 0.0997209698 0.0286760051 0.3727311194 948 37.8800000000 0.8605173230 0.4142540406 0.8852621913 0.0698201828 0.0513280000 945992213 0 402718720 0.0997209698 0.0286760051 0.3727311194 949 37.9200000000 0.8672755361 0.4147314079 0.8852621913 0.0697869159 0.0324190000 946071045 0 402718720 0.0997209698 0.0286760051 0.3727311194 950 37.9600000000 0.8752716184 0.4152161870 0.8852621913 0.0697520564 0.0335610000 946149877 0 402718720 0.0997209698 0.0286760051 0.3727311194 951 38.0000000000 0.8781455755 0.4157029687 0.8852621913 0.0697168522 0.0300910000 946228709 0 402718720 0.0997209698 0.0286760051 0.3727311194 952 38.0400000000 0.8784466386 0.4161890440 0.8852621913 0.0696813194 0.0331340000 946307541 0 402718720 0.0997209698 0.0286760051 0.3727311194 953 38.0800000000 0.8788602948 0.4166745332 0.8852621913 0.0696454189 0.0332670000 946386373 0 402718720 0.0997209698 0.0286760051 0.3727311194 954 38.1200000000 0.8802281022 0.4171604385 0.8852621913 0.0696102012 0.0277320000 946465205 0 402718720 0.0997209698 0.0286760051 0.3727311194 955 38.1600000000 0.8789445162 0.4176439820 0.8852621913 0.0695750535 0.0253030000 946544037 0 402718720 0.0997209698 0.0286760051 0.3727311194 956 38.2000000000 0.8794482946 0.4181270409 0.8852621913 0.0695401667 0.0262460000 946622869 0 402718720 0.0997209698 0.0286760051 0.3727311194 957 38.2400000000 0.8786017895 0.4186082057 0.8852621913 0.0695047600 0.0240110000 946701701 0 402718720 0.0997209698 0.0286760051 0.3727311194 958 38.2800000000 0.8761222363 0.4190857778 0.8852621913 0.0694689723 0.0241740000 946780533 0 402718720 0.0997209698 0.0286760051 0.3727311194 959 38.3200000000 0.8758873940 0.4195621090 0.8852621913 0.0694336674 0.0217920000 946859365 0 402718720 0.0997209698 0.0286760051 0.3727311194 960 38.3600000000 0.8771334887 0.4200387458 0.8852621913 0.0693990865 0.0211890000 946938197 0 402718720 0.0997209698 0.0286760051 0.3727311194 961 38.4000000000 0.8760071993 0.4205132187 0.8852621913 0.0693638015 0.0515440000 947017029 0 402718720 0.0997209698 0.0286760051 0.3727311194 962 38.4400000000 0.8756201267 0.4209863028 0.8852621913 0.0693287622 0.0233550000 947095861 0 402718720 0.0997209698 0.0286760051 0.3727311194 963 38.4800000000 0.8736057281 0.4214563126 0.8852621913 0.0692935562 0.0226380000 947174693 0 402718720 0.0997209698 0.0286760051 0.3727311194 964 38.5200000000 0.8745879531 0.4219263662 0.8852621913 0.0692587700 0.0242800000 947253525 0 402718720 0.0997209698 0.0286760051 0.3727311194 965 38.5600000000 0.8732983470 0.4223941092 0.8852621913 0.0692235775 0.0219840000 947332357 0 402718720 0.0997209698 0.0286760051 0.3727311194 966 38.6000000000 0.8728787899 0.4228604494 0.8852621913 0.0691883521 0.0204640000 947411189 0 402718720 0.0997209698 0.0286760051 0.3727311194 967 38.6400000000 0.8749464750 0.4233279634 0.8852621913 0.0691535031 0.0181860000 947490021 0 402718720 0.0997209698 0.0286760051 0.3727311194 968 38.6800000000 0.8734024763 0.4237929164 0.8852621913 0.0691186470 0.0199250000 947568853 0 402718720 0.0997209698 0.0286760051 0.3727311194 969 38.7200000000 0.8739441037 0.4242574687 0.8852621913 0.0690845927 0.0191830000 947647685 0 402718720 0.0997209698 0.0286760051 0.3727311194 970 38.7600000000 0.8728225827 0.4247199070 0.8852621913 0.0690501474 0.0218420000 947726517 0 402718720 0.0997209698 0.0286760051 0.3727311194 971 38.8000000000 0.8713679314 0.4251798947 0.8852621913 0.0690153935 0.0198460000 947805349 0 402718720 0.0997209698 0.0286760051 0.3727311194 972 38.8400000000 0.8710774183 0.4256386370 0.8852621913 0.0689815146 0.0202700000 947884181 0 402718720 0.0997209698 0.0286760051 0.3727311194 973 38.8800000000 0.8702257276 0.4260955610 0.8852621913 0.0689472826 0.0201330000 947963013 0 402718720 0.0997209698 0.0286760051 0.3727311194 974 38.9200000000 0.8704147935 0.4265517409 0.8852621913 0.0689133429 0.0190030000 948041845 0 402718720 0.0997209698 0.0286760051 0.3727311194 975 38.9600000000 0.8699302077 0.4270064881 0.8852621913 0.0688792894 0.0213050000 948120677 0 402718720 0.0997209698 0.0286760051 0.3727311194 976 39.0000000000 0.8689054847 0.4274592534 0.8852621913 0.0688447387 0.0197240000 948199509 0 402718720 0.0997209698 0.0286760051 0.3727311194 977 39.0400000000 0.8684145212 0.4279105894 0.8852621913 0.0688110635 0.0546690000 948278341 0 402718720 0.0997209698 0.0286760051 0.3727311194 978 39.0800000000 0.8667973280 0.4283593489 0.8852621913 0.0687764886 0.0212550000 948357173 0 402718720 0.0997209698 0.0286760051 0.3727311194 979 39.1200000000 0.8646966219 0.4288050458 0.8852621913 0.0687420026 0.0192170000 948436005 0 402718720 0.0997209698 0.0286760051 0.3727311194 980 39.1600000000 0.8632047772 0.4292483108 0.8852621913 0.0687077091 0.0172160000 948514837 0 402718720 0.0997209698 0.0286760051 0.3727311194 981 39.2000000000 0.8628373742 0.4296902976 0.8852621913 0.0686735026 0.0187800000 948593669 0 402718720 0.0997209698 0.0286760051 0.3727311194 982 39.2400000000 0.8613792062 0.4301298994 0.8852621913 0.0686395841 0.0331080000 948672501 0 402718720 0.0997209698 0.0286760051 0.3727311194 983 39.2800000000 0.8599578738 0.4305671608 0.8852621913 0.0686056849 0.0232210000 948751333 0 402718720 0.0997209698 0.0286760051 0.3727311194 984 39.3200000000 0.8591486812 0.4310027111 0.8852621913 0.0685715026 0.0286060000 948830165 0 402718720 0.0997209698 0.0286760051 0.3727311194 985 39.3600000000 0.8567625284 0.4314349546 0.8852621913 0.0685373760 0.0248370000 948908997 0 402718720 0.0997209698 0.0286760051 0.3727311194 986 39.4000000000 0.8551971912 0.4318647337 0.8852621913 0.0685031305 0.0237370000 948987829 0 402718720 0.0997209698 0.0286760051 0.3727311194 987 39.4400000000 0.8537414670 0.4322921671 0.8852621913 0.0684687964 0.0214910000 949066661 0 402718720 0.0997209698 0.0286760051 0.3727311194 988 39.4800000000 0.8523933291 0.4327173707 0.8852621913 0.0684347007 0.0181970000 949145493 0 402718720 0.0997209698 0.0286760051 0.3727311194 989 39.5200000000 0.8500925303 0.4331393880 0.8852621913 0.0684008330 0.0173060000 949224325 0 402718720 0.0997209698 0.0286760051 0.3727311194 990 39.5600000000 0.8488545418 0.4335593023 0.8852621913 0.0683672416 0.0208460000 949303157 0 402718720 0.0997209698 0.0286760051 0.3727311194 991 39.6000000000 0.8464903831 0.4339759836 0.8852621913 0.0683332405 0.0202130000 949381989 0 402718720 0.0997209698 0.0286760051 0.3727311194 992 39.6400000000 0.8446277976 0.4343899471 0.8852621913 0.0682992547 0.0187740000 949460821 0 402718720 0.0997209698 0.0286760051 0.3727311194 993 39.6800000000 0.8430457115 0.4348014836 0.8852621913 0.0682652961 0.0167300000 949539653 0 402718720 0.0997209698 0.0286760051 0.3727311194 994 39.7200000000 0.8400111794 0.4352091392 0.8852621913 0.0682313758 0.0215040000 949618485 0 402718720 0.0997209698 0.0286760051 0.3727311194 995 39.7600000000 0.8369445205 0.4356128934 0.8852621913 0.0681974935 0.0198050000 949697317 0 402718720 0.0997209698 0.0286760051 0.3727311194 996 39.8000000000 0.8345741034 0.4360134568 0.8852621913 0.0681632984 0.0088850000 949776149 0 402718720 0.0997209698 0.0286760051 0.3727311194 997 39.8400000000 0.8330003619 0.4364116383 0.8852621913 0.0681291207 0.0092650000 949854981 0 402718720 0.0997209698 0.0286760051 0.3727311194 998 39.8800000000 0.8309364319 0.4368069537 0.8852621913 0.0680949788 0.0101810000 949933813 0 402718720 0.0997209698 0.0286760051 0.3727311194 999 39.9200000000 0.8265212774 0.4371970581 0.8852621913 0.0680608805 0.0076520000 950012645 0 402718720 0.0997209698 0.0286760051 0.3727311194 1000 39.9600000000 0.8246691823 0.4375845303 0.8852621913 0.0680268318 0.0074820000 950091477 0 402718720 0.0997209698 0.0286760051 0.3727311194 1001 40.0000000000 0.8223547339 0.4379689161 0.8852621913 0.0679928178 0.0073920000 950170309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1002 40.0400000000 0.8203009367 0.4383504850 0.8852621913 0.0679588910 0.0095800000 950249141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1003 40.0800000000 0.8186045289 0.4387296017 0.8852621913 0.0679249874 0.0079920000 950327973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1004 40.1200000000 0.8154756427 0.4391048467 0.8852621913 0.0678911495 0.0089350000 950406805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1005 40.1600000000 0.8147739172 0.4394786468 0.8852621913 0.0678575613 0.0087010000 950485637 0 402718720 0.0997209698 0.0286760051 0.3727311194 1006 40.2000000000 0.8125121593 0.4398494555 0.8852621913 0.0678239707 0.0089000000 950564469 0 402718720 0.0997209698 0.0286760051 0.3727311194 1007 40.2400000000 0.8093120456 0.4402163498 0.8852621913 0.0677902595 0.0077990000 950643301 0 402718720 0.0997209698 0.0286760051 0.3727311194 1008 40.2800000000 0.8073005676 0.4405805206 0.8852621913 0.0677567864 0.0070010000 950722133 0 402718720 0.0997209698 0.0286760051 0.3727311194 1009 40.3200000000 0.8044699430 0.4409411643 0.8852621913 0.0677234651 0.0068020000 950800965 0 402718720 0.0997209698 0.0286760051 0.3727311194 1010 40.3600000000 0.8010810018 0.4412977384 0.8852621913 0.0676899030 0.0070690000 950879797 0 402718720 0.0997209698 0.0286760051 0.3727311194 1011 40.4000000000 0.7974895239 0.4416500547 0.8852621913 0.0676565612 0.0068240000 950958629 0 402718720 0.0997209698 0.0286760051 0.3727311194 1012 40.4400000000 0.7946351171 0.4419988541 0.8852621913 0.0676232343 0.0067630000 951037461 0 402718720 0.0997209698 0.0286760051 0.3727311194 1013 40.4800000000 0.7921762466 0.4423445376 0.8852621913 0.0675898757 0.0066710000 951116293 0 402718720 0.0997209698 0.0286760051 0.3727311194 1014 40.5200000000 0.7899280190 0.4426873221 0.8852621913 0.0675566367 0.0065860000 951195125 0 402718720 0.0997209698 0.0286760051 0.3727311194 1015 40.5600000000 0.7875256538 0.4430270643 0.8852621913 0.0675235787 0.0066260000 951273957 0 402718720 0.0997209698 0.0286760051 0.3727311194 1016 40.6000000000 0.7857044935 0.4433643453 0.8852621913 0.0674904680 0.0067140000 951352789 0 402718720 0.0997209698 0.0286760051 0.3727311194 1017 40.6400000000 0.7830193639 0.4436983227 0.8852621913 0.0674574308 0.0068780000 951431621 0 402718720 0.0997209698 0.0286760051 0.3727311194 1018 40.6800000000 0.7808562517 0.4440295191 0.8852621913 0.0674244865 0.0068800000 951510453 0 402718720 0.0997209698 0.0286760051 0.3727311194 1019 40.7200000000 0.7786512375 0.4443579015 0.8852621913 0.0673918262 0.0069030000 951589285 0 402718720 0.0997209698 0.0286760051 0.3727311194 1020 40.7600000000 0.7770112157 0.4446840322 0.8852621913 0.0673591600 0.0065690000 951668117 0 402718720 0.0997209698 0.0286760051 0.3727311194 1021 40.8000000000 0.7747892737 0.4450073478 0.8852621913 0.0673265591 0.0065030000 951746949 0 402718720 0.0997209698 0.0286760051 0.3727311194 1022 40.8400000000 0.7734385729 0.4453287091 0.8852621913 0.0672938738 0.0065380000 951825781 0 402718720 0.0997209698 0.0286760051 0.3727311194 1023 40.8800000000 0.7720283866 0.4456480636 0.8852621913 0.0672612638 0.0064580000 951904613 0 402718720 0.0997209698 0.0286760051 0.3727311194 1024 40.9200000000 0.7702389359 0.4459650469 0.8852621913 0.0672293199 0.0066840000 951983445 0 402718720 0.0997209698 0.0286760051 0.3727311194 1025 40.9600000000 0.7688576579 0.4462800641 0.8852621913 0.0671975103 0.0066590000 952062277 0 402718720 0.0997209698 0.0286760051 0.3727311194 1026 41.0000000000 0.7658293247 0.4465915156 0.8852621913 0.0671655959 0.0066060000 952345909 0 402718720 0.0997209698 0.0286760051 0.3727311194 1027 41.0400000000 0.7636590600 0.4469002474 0.8852621913 0.0671337937 0.0066860000 952424741 0 402718720 0.0997209698 0.0286760051 0.3727311194 1028 41.0800000000 0.7619371414 0.4472067035 0.8852621913 0.0671018859 0.0065390000 952503573 0 402718720 0.0997209698 0.0286760051 0.3727311194 1029 41.1200000000 0.7595081329 0.4475102035 0.8852621913 0.0670698910 0.0063690000 952582405 0 402718720 0.0997209698 0.0286760051 0.3727311194 1030 41.1600000000 0.7575166225 0.4478111806 0.8852621913 0.0670381292 0.0065810000 952661237 0 402718720 0.0997209698 0.0286760051 0.3727311194 1031 41.2000000000 0.7548858523 0.4481090221 0.8852621913 0.0670064595 0.0062090000 952740069 0 402718720 0.0997209698 0.0286760051 0.3727311194 1032 41.2400000000 0.7527550459 0.4484042218 0.8852621913 0.0669743948 0.0062350000 952818901 0 402718720 0.0997209698 0.0286760051 0.3727311194 1033 41.2800000000 0.7511478662 0.4486972940 0.8852621913 0.0669424728 0.0060930000 952820909 0 402718720 0.0997209698 0.0286760051 0.3727311194 1034 41.3200000000 0.7471247315 0.4489859086 0.8852621913 0.0669136225 0.0060470000 952822917 0 402718720 0.0997209698 0.0286760051 0.3727311194 1035 41.3600000000 0.7458282113 0.4492727127 0.8852621913 0.0668818269 0.0060680000 952824925 0 402718720 0.0997209698 0.0286760051 0.3727311194 1036 41.4000000000 0.7437511086 0.4495569583 0.8852621913 0.0668505263 0.0059430000 952826933 0 402718720 0.0997209698 0.0286760051 0.3727311194 1037 41.4400000000 0.7421478033 0.4498391095 0.8852621913 0.0668193878 0.0061150000 952828941 0 402718720 0.0997209698 0.0286760051 0.3727311194 1038 41.4800000000 0.7400085330 0.4501186562 0.8852621913 0.0667880374 0.0057690000 952830949 0 402718720 0.0997209698 0.0286760051 0.3727311194 1039 41.5200000000 0.7381518483 0.4503958777 0.8852621913 0.0667570008 0.0057840000 952832957 0 402718720 0.0997209698 0.0286760051 0.3727311194 1040 41.5600000000 0.7364550829 0.4506709347 0.8852621913 0.0667259357 0.0057600000 952834965 0 402718720 0.0997209698 0.0286760051 0.3727311194 1041 41.6000000000 0.7349537015 0.4509440209 0.8852621913 0.0666947766 0.0058220000 952913797 0 402718720 0.0997209698 0.0286760051 0.3727311194 1042 41.6400000000 0.7331497669 0.4512148518 0.8852621913 0.0666640168 0.0056360000 952992629 0 402718720 0.0997209698 0.0286760051 0.3727311194 1043 41.6800000000 0.7313714623 0.4514834583 0.8852621913 0.0666333795 0.0057850000 953071461 0 402718720 0.0997209698 0.0286760051 0.3727311194 1044 41.7200000000 0.7301945090 0.4517504229 0.8852621913 0.0666024830 0.0055010000 953073469 0 402718720 0.0997209698 0.0286760051 0.3727311194 1045 41.7600000000 0.7296969891 0.4520164005 0.8852621913 0.0665715357 0.0055940000 953152301 0 402718720 0.0997209698 0.0286760051 0.3727311194 1046 41.8000000000 0.7284508348 0.4522806781 0.8852621913 0.0665410938 0.0052850000 953154309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1047 41.8400000000 0.7280420661 0.4525440605 0.8852621913 0.0665102466 0.0052290000 953156317 0 402718720 0.0997209698 0.0286760051 0.3727311194 1048 41.8800000000 0.7266955376 0.4528056555 0.8852621913 0.0664791780 0.0054410000 953235149 0 402718720 0.0997209698 0.0286760051 0.3727311194 1049 41.9200000000 0.7252563238 0.4530653796 0.8852621913 0.0664483847 0.0056110000 953313981 0 402718720 0.0997209698 0.0286760051 0.3727311194 1050 41.9600000000 0.7239720225 0.4533233860 0.8852621913 0.0664174309 0.0055420000 953392813 0 402718720 0.0997209698 0.0286760051 0.3727311194 1051 42.0000000000 0.7228909731 0.4535798727 0.8852621913 0.0663866703 0.0054280000 953471645 0 402718720 0.0997209698 0.0286760051 0.3727311194 1052 42.0400000000 0.7222794890 0.4538352906 0.8852621913 0.0663558243 0.0057470000 953550477 0 402718720 0.0997209698 0.0286760051 0.3727311194 1053 42.0800000000 0.7209824920 0.4540889917 0.8852621913 0.0663253335 0.0055310000 953629309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1054 42.1200000000 0.7202564478 0.4543415225 0.8852621913 0.0662947653 0.0055700000 953708141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1055 42.1600000000 0.7196934223 0.4545930408 0.8852621913 0.0662641629 0.0055130000 953786973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1056 42.2000000000 0.7192544341 0.4548436672 0.8852621913 0.0662340495 0.0056700000 953865805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1057 42.2400000000 0.7187358737 0.4550933287 0.8852621913 0.0662038648 0.0055410000 953944637 0 402718720 0.0997209698 0.0286760051 0.3727311194 1058 42.2800000000 0.7187966704 0.4553425757 0.8852621913 0.0661732829 0.0053450000 953946645 0 402718720 0.0997209698 0.0286760051 0.3727311194 1059 42.3200000000 0.7190580964 0.4555915988 0.8852621913 0.0661430015 0.0055980000 954025477 0 402718720 0.0997209698 0.0286760051 0.3727311194 1060 42.3600000000 0.7192236185 0.4558403083 0.8852621913 0.0661127402 0.0058500000 954104309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1061 42.4000000000 0.7195062637 0.4560888153 0.8852621913 0.0660824525 0.0059910000 954183141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1062 42.4400000000 0.7215042710 0.4563387357 0.8852621913 0.0660545756 0.0059430000 954261973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1063 42.4800000000 0.7222282887 0.4565888670 0.8852621913 0.0660240793 0.0067060000 954340805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1064 42.5200000000 0.7229129076 0.4568391715 0.8852621913 0.0659936072 0.0061470000 954419637 0 402718720 0.0997209698 0.0286760051 0.3727311194 1065 42.5600000000 0.7238613963 0.4570898966 0.8852621913 0.0659631581 0.0058430000 954421645 0 402718720 0.0997209698 0.0286760051 0.3727311194 1066 42.6000000000 0.7241162658 0.4573403904 0.8852621913 0.0659329605 0.0062310000 954500477 0 402718720 0.0997209698 0.0286760051 0.3727311194 1067 42.6400000000 0.7247360945 0.4575909956 0.8852621913 0.0659030391 0.0063200000 954579309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1068 42.6800000000 0.7255029678 0.4578418495 0.8852621913 0.0658731433 0.0060500000 954658141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1069 42.7200000000 0.7258201241 0.4580925307 0.8852621913 0.0658434068 0.0057950000 954736973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1070 42.7600000000 0.7258345485 0.4583427569 0.8852621913 0.0658135633 0.0057880000 954815805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1071 42.8000000000 0.7272859216 0.4585938710 0.8852621913 0.0657835343 0.0059890000 954894637 0 402718720 0.0997209698 0.0286760051 0.3727311194 1072 42.8400000000 0.7286985517 0.4588458343 0.8852621913 0.0657540363 0.0060740000 954973469 0 402718720 0.0997209698 0.0286760051 0.3727311194 1073 42.8800000000 0.7288237214 0.4590974447 0.8852621913 0.0657243571 0.0059280000 955052301 0 402718720 0.0997209698 0.0286760051 0.3727311194 1074 42.9200000000 0.7292134166 0.4593489493 0.8852621913 0.0656948152 0.0057850000 955131133 0 402718720 0.0997209698 0.0286760051 0.3727311194 1075 42.9600000000 0.7293059826 0.4596000721 0.8852621913 0.0656648371 0.0056400000 955133141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1076 43.0000000000 0.7308959961 0.4598522059 0.8852621913 0.0656347315 0.0059800000 955211973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1077 43.0400000000 0.7333336473 0.4601061348 0.8852621913 0.0656046354 0.0056100000 955290805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1078 43.0800000000 0.7350519896 0.4603611866 0.8852621913 0.0655746306 0.0059810000 955292813 0 402718720 0.0997209698 0.0286760051 0.3727311194 1079 43.1200000000 0.7376248240 0.4606181501 0.8852621913 0.0655444879 0.0059700000 955371645 0 402718720 0.0997209698 0.0286760051 0.3727311194 1080 43.1600000000 0.7394016981 0.4608762830 0.8852621913 0.0655145353 0.0060860000 955450477 0 402718720 0.0997209698 0.0286760051 0.3727311194 1081 43.2000000000 0.7418397069 0.4611361937 0.8852621913 0.0654847566 0.0055970000 955529309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1082 43.2400000000 0.7436163425 0.4613972659 0.8852621913 0.0654549871 0.0056690000 955608141 0 402718720 0.0997209698 0.0286760051 0.3727311194 1083 43.2800000000 0.7455390096 0.4616596313 0.8852621913 0.0654255086 0.0057500000 955686973 0 402718720 0.0997209698 0.0286760051 0.3727311194 1084 43.3200000000 0.7465923429 0.4619224844 0.8852621913 0.0653956641 0.0059180000 955765805 0 402718720 0.0997209698 0.0286760051 0.3727311194 1085 43.3600000000 0.7475445867 0.4621857306 0.8852621913 0.0653658395 0.0057890000 955844637 0 402718720 0.0997209698 0.0286760051 0.3727311194 1086 43.4000000000 0.7485592365 0.4624494262 0.8852621913 0.0653360578 0.0058090000 955923469 0 402718720 0.0997209698 0.0286760051 0.3727311194 1087 43.4400000000 0.7501314282 0.4627140831 0.8852621913 0.0653062675 0.0057500000 956002301 0 402718720 0.0997209698 0.0286760051 0.3727311194 1088 43.4800000000 0.7510885596 0.4629791332 0.8852621913 0.0652767589 0.0058470000 956004309 0 402718720 0.0997209698 0.0286760051 0.3727311194 1089 43.5200000000 0.7527114749 0.4632451867 0.8852621913 0.0652473012 0.0057500000 956006317 0 402718720 0.0997209698 0.0286760051 0.3727311194 1090 43.5600000000 0.7537863255 0.4635117382 0.8852621913 0.0652179768 0.0055520000 956008325 0 402718720 0.0997209698 0.0286760051 0.3727311194 1091 43.6000000000 0.7551684976 0.4637790680 0.8852621913 0.0651885955 0.0064620000 956010333 0 402718720 0.0997209698 0.0286760051 0.3727311194 1092 43.6400000000 0.7572237253 0.4640477902 0.8852621913 0.0651594921 0.0061630000 956012341 0 402718720 0.0997209698 0.0286760051 0.3727311194 1093 43.6800000000 0.7594929934 0.4643180969 0.8852621913 0.0651301316 0.0067530000 956091173 0 402718720 0.0997209698 0.0286760051 0.3727311194 1094 43.7200000000 0.7612040043 0.4645894734 0.8852621913 0.0651008334 0.0063670000 956170005 0 402718720 0.0997209698 0.0286760051 0.3727311194 1095 43.7600000000 0.7635182142 0.4648624677 0.8852621913 0.0650716249 0.0062600000 956172013 0 402718720 0.0997209698 0.0286760051 0.3727311194 1096 43.8000000000 0.7656056881 0.4651368684 0.8852621913 0.0650423580 0.0059870000 956174021 0 402718720 0.0997209698 0.0286760051 0.3727311194 1097 43.8400000000 0.7674874067 0.4654124842 0.8852621913 0.0650130442 0.0059690000 956176029 0 402718720 0.0997209698 0.0286760051 0.3727311194 1098 43.8800000000 0.7691760063 0.4656891359 0.8852621913 0.0649836571 0.0060100000 956178037 0 402718720 0.0997209698 0.0286760051 0.3727311194 1099 43.9200000000 0.7703067064 0.4659663129 0.8852621913 0.0649544181 0.0060180000 956180045 0 402718720 0.0997209698 0.0286760051 0.3727311194 1100 43.9600000000 0.7721574903 0.4662446686 0.8852621913 0.0649256218 0.0053000000 956182053 0 402718720 0.0997209698 0.0286760051 0.3727311194 1101 44.0000000000 0.7735642195 0.4665237962 0.8852621913 0.0648972336 0.0053590000 956260885 0 402718720 0.0997209698 0.0286760051 0.3727311194 1102 44.0400000000 0.7757055163 0.4668043604 0.8852621913 0.0648684959 0.0051340000 956339717 0 402718720 0.0997209698 0.0286760051 0.3727311194 1103 44.0800000000 0.7776138186 0.4670861459 0.8852621913 0.0648395651 0.0062960000 956418549 0 402718720 0.0997209698 0.0286760051 0.3727311194 1104 44.1200000000 0.7792687416 0.4673689200 0.8852621913 0.0648106201 0.0209680000 956420557 0 402718720 0.0997209698 0.0286760051 0.3727311194 1105 44.1600000000 0.7813630700 0.4676530776 0.8852621913 0.0647816771 0.0114290000 956422565 0 402718720 0.0997209698 0.0286760051 0.3727311194 1106 44.2000000000 0.7831508517 0.4679383378 0.8852621913 0.0647529353 0.0072030000 956501397 0 402718720 0.0997209698 0.0286760051 0.3727311194 1107 44.2400000000 0.7847697735 0.4682245451 0.8852621913 0.0647241004 0.0060240000 956503405 0 402718720 0.0997209698 0.0286760051 0.3727311194 1108 44.2800000000 0.7864401937 0.4685117433 0.8852621913 0.0646952525 0.0061560000 956582237 0 402718720 0.0997209698 0.0286760051 0.3727311194 1109 44.3200000000 0.7881583571 0.4687999729 0.8852621913 0.0646663144 0.0148270000 956584245 0 402718720 0.0997209698 0.0286760051 0.3727311194 1110 44.3600000000 0.7892347574 0.4690886529 0.8852621913 0.0646374638 0.0091740000 956663077 0 402718720 0.0997209698 0.0286760051 0.3727311194 1111 44.4000000000 0.7910116911 0.4693784126 0.8852621913 0.0646085441 0.0074550000 956741909 0 402718720 0.0997209698 0.0286760051 0.3727311194 1112 44.4400000000 0.7925447822 0.4696690298 0.8852621913 0.0645797649 0.0066490000 956820741 0 402718720 0.0997209698 0.0286760051 0.3727311194 1113 44.4800000000 0.7940559387 0.4699604826 0.8852621913 0.0645511235 0.0060440000 956899573 0 402718720 0.0997209698 0.0286760051 0.3727311194 1114 44.5200000000 0.7961522937 0.4702532939 0.8852621913 0.0645225251 0.0068030000 956901581 0 402718720 0.0997209698 0.0286760051 0.3727311194 1115 44.5600000000 0.7974843979 0.4705467747 0.8852621913 0.0644941304 0.0072200000 956980413 0 402718720 0.0997209698 0.0286760051 0.3727311194 1116 44.6000000000 0.7991708517 0.4708412407 0.8852621913 0.0644654977 0.0081760000 957059245 0 402718720 0.0997209698 0.0286760051 0.3727311194 1117 44.6400000000 0.8008746505 0.4711367048 0.8852621913 0.0644369823 0.0069180000 957138077 0 402718720 0.0997209698 0.0286760051 0.3727311194 1118 44.6800000000 0.8033510447 0.4714338554 0.8852621913 0.0644084992 0.0291320000 957216909 0 402718720 0.0997209698 0.0286760051 0.3727311194 1119 44.7200000000 0.8058969378 0.4717327500 0.8852621913 0.0643799975 0.0143440000 957295741 0 402718720 0.0997209698 0.0286760051 0.3727311194 1120 44.7600000000 0.8085491657 0.4720334790 0.8852621913 0.0643516591 0.0107500000 957374573 0 402718720 0.0997209698 0.0286760051 0.3727311194 1121 44.8000000000 0.8103702068 0.4723352959 0.8852621913 0.0643230373 0.0125550000 957453405 0 402718720 0.0997209698 0.0286760051 0.3727311194 1122 44.8400000000 0.7989031672 0.4726263546 0.8852621913 0.0685097485 0.0132770000 957532237 0 402718720 -0.0474627092 0.0368649252 0.3531246185 1123 44.8800000000 0.8111737370 0.4729278215 0.8852621913 0.0684891203 0.0167830000 946856301 0 402718720 -0.0468542576 0.0417424627 0.3444849253 1124 44.9200000000 0.8696992993 0.4732808211 0.8852621913 0.0716166008 0.0246640000 950240653 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1125 44.9600000000 0.8720101118 0.4736352471 0.8852621913 0.0715850158 0.0142660000 957617285 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1126 45.0000000000 0.8750780821 0.4739917683 0.8852621913 0.0715534726 0.0126690000 958277013 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1127 45.0400000000 0.8775652051 0.4743498636 0.8852621913 0.0715222881 0.0151170000 958279021 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1128 45.0800000000 0.8801857829 0.4747096472 0.8852621913 0.0714908661 0.0133200000 958281029 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1129 45.1200000000 0.8833239675 0.4750715731 0.8852621913 0.0714594169 0.0132970000 958283037 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1130 45.1600000000 0.8852244616 0.4754345403 0.8852621913 0.0714283343 0.0153760000 958285045 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1131 45.2000000000 0.8881673813 0.4757994676 0.8881673813 0.0713970430 0.0167540000 958287053 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1132 45.2400000000 0.8902046680 0.4761655499 0.8902046680 0.0713659289 0.0127670000 958289061 0 402718720 -0.0735977441 -0.0641118512 0.2796272337 1133 45.2800000000 0.9466847777 0.4765808361 0.9466847777 0.0713599432 0.0300100000 958291341 0 402718720 -0.0366409495 -0.0488563515 0.2282291651 1134 45.3200000000 1.0058583021 0.4770475711 1.0058583021 0.0720896648 0.0299640000 960983061 0 402718720 -0.0377454050 -0.1343756318 0.1753185093 1135 45.3600000000 1.0200822353 0.4775260157 1.0200822353 0.0725393637 0.0316230000 964332501 0 402718720 -0.1176478565 -0.1236747801 0.1584585309 1136 45.4000000000 1.0329297781 0.4780149275 1.0329297781 0.0725332204 0.0686210000 967681941 0 402718720 -0.1233913302 -0.1305620670 0.1485949159 1137 45.4400000000 1.0724275112 0.4785377178 1.0724275112 0.0728268452 0.0361900000 971031381 0 402718720 -0.1507148743 -0.1758472621 0.1187504306 1138 45.4800000000 1.0925728083 0.4790772917 1.0925728083 0.0728203123 0.0414880000 974380821 0 402718720 -0.1490883976 -0.2151538432 0.1049677730 1139 45.5200000000 1.0884921551 0.4796123355 1.0925728083 0.0730735675 0.0365020000 977730261 0 402718720 -0.1966865212 -0.2666629851 0.1221955791 1140 45.5600000000 1.1010862589 0.4801574880 1.1010862589 0.0730887498 0.0321120000 981079701 0 402718720 -0.2064361423 -0.2734928429 0.1139255166 1141 45.6000000000 1.1199978590 0.4807182596 1.1199978590 0.0730795210 0.0259590000 984429141 0 402718720 -0.1961941272 -0.2832508087 0.0985902473 1142 45.6400000000 1.1316524744 0.4812882546 1.1316524744 0.0730569222 0.0315520000 987778581 0 402718720 -0.1981628239 -0.2926568687 0.0916668475 1143 45.6800000000 1.1463545561 0.4818701148 1.1463545561 0.0730997466 0.0296220000 991128021 0 402718720 -0.2075054646 -0.3299670219 0.0900166556 1144 45.7200000000 1.1927505732 0.4824915138 1.1927505732 0.0731141947 0.0399640000 994477461 0 402718720 -0.2024233043 -0.4060915411 0.0690093786 1145 45.7600000000 1.2267491817 0.4831415205 1.2267491817 0.0731217597 0.0263690000 997826901 0 402718720 -0.2033927441 -0.4665145874 0.0585204400 1146 45.8000000000 1.2381495237 0.4838003408 1.2381495237 0.0730992753 0.0337000000 1001176341 0 402718720 -0.2058891505 -0.4752733111 0.0536880083 1147 45.8400000000 1.3073247671 0.4845183220 1.3073247671 0.0730855680 0.0379580000 1004525781 0 402718720 -0.1739217639 -0.5383324027 0.0082119908 1148 45.8800000000 1.3167375326 0.4852432516 1.3167375326 0.0730639895 0.0297670000 1007875221 0 402718720 -0.1712498814 -0.5392605066 0.0019170543 1149 45.9200000000 1.3140453100 0.4859645763 1.3167375326 0.0731956495 0.0322730000 1011224661 0 402718720 -0.2104523927 -0.5092782378 -0.0016746691 1150 45.9600000000 1.3167539835 0.4866870018 1.3167539835 0.0732518438 0.0391280000 1014574101 0 402718720 -0.2454074174 -0.5075100660 0.0011705719 1151 46.0000000000 1.3198629618 0.4874108732 1.3198629618 0.0732232949 0.0325940000 1017923541 0 402718720 -0.2452408075 -0.5075914264 0.0001662115 1152 46.0400000000 1.3214462996 0.4881348623 1.3214462996 0.0731921525 0.0324970000 1021272981 0 402718720 -0.2452408075 -0.5075914264 0.0001662115 1153 46.0800000000 1.3249959946 0.4888606742 1.3249959946 0.0731611118 0.0352540000 1024622421 0 402718720 -0.2452408075 -0.5075914264 0.0001662115 1154 46.1200000000 1.3376879692 0.4895962265 1.3376879692 0.0731343709 0.0309090000 1027971861 0 402718720 -0.2468741536 -0.5078314543 -0.0098505132 1155 46.1600000000 1.3667222261 0.4903556429 1.3667222261 0.0731606522 0.0404200000 1031321301 0 402718720 -0.2768440247 -0.5288433433 -0.0258257966 1156 46.2000000000 1.3995680809 0.4911421589 1.3995680809 0.0731437616 0.0306960000 1034670741 0 402718720 -0.2792247236 -0.5407462120 -0.0536951087 1157 46.2400000000 1.4584660530 0.4919782210 1.4584660530 0.0731313660 0.0404640000 1038020181 0 402718720 -0.2687889338 -0.5394120812 -0.1173341274 1158 46.2800000000 1.4716426134 0.4928242179 1.4716426134 0.0731496872 0.0316300000 1041369621 0 402718720 -0.3060315549 -0.5589996576 -0.1153831184 1159 46.3200000000 1.5027089119 0.4936955593 1.5027089119 0.0732048931 0.0380210000 1044719061 0 402718720 -0.3089694977 -0.5174769163 -0.1633643210 1160 46.3600000000 1.5112450123 0.4945727571 1.5112450123 0.0732413837 0.0619350000 1048068501 0 402718720 -0.2822456062 -0.4592818022 -0.1948050559 1161 46.4000000000 1.4904026985 0.4954304918 1.5112450123 0.0732420671 0.0314480000 1051417941 0 402718720 -0.2589874268 -0.4070403576 -0.1913169026 1162 46.4400000000 1.4493887424 0.4962514541 1.5112450123 0.0732798466 0.0258520000 1054767893 0 402718720 -0.3009196818 -0.3553725183 -0.1571693569 1163 46.4800000000 1.3766198158 0.4970084347 1.5112450123 0.0733512754 0.0356290000 1058117333 0 402718720 -0.2802319825 -0.2675194442 -0.1046089530 1164 46.5200000000 1.3045287132 0.4977021806 1.5112450123 0.0734524275 0.0341830000 1061466773 0 402718720 -0.2333627641 -0.2005886734 -0.0475368388 1165 46.5600000000 1.2633656263 0.4983594024 1.5112450123 0.0734978906 0.0455710000 1064816213 0 402718720 -0.1700565219 -0.1832833588 -0.0125225112 1166 46.6000000000 1.2380605936 0.4989937945 1.5112450123 0.0735534665 0.0301950000 1068165653 0 402718720 -0.2175308466 -0.1837371588 0.0186688360 1167 46.6400000000 1.2323795557 0.4996222314 1.5112450123 0.0735243760 0.0249860000 1071515093 0 402718720 -0.2137299329 -0.1702242941 0.0221062861 1168 46.6800000000 1.2187445164 0.5002379182 1.5112450123 0.0735630446 0.0252240000 1074864533 0 402718720 -0.1779813468 -0.1283338815 0.0277710035 1169 46.7200000000 1.1975984573 0.5008344628 1.5112450123 0.0735828160 0.0352710000 1078213973 0 402718720 -0.2110080272 -0.1529456675 0.0572741888 1170 46.7600000000 1.1830406189 0.5014175449 1.5112450123 0.0736167704 0.0302100000 1081563413 0 402718720 -0.1832202673 -0.1111683473 0.0651424378 1171 46.8000000000 1.1571328640 0.5019775068 1.5112450123 0.0739702928 0.0648140000 1084912853 0 402718720 -0.2619237006 -0.1781548858 0.1127460077 1172 46.8400000000 1.1597101688 0.5025387121 1.5112450123 0.0739494808 0.0362770000 1088262293 0 402718720 -0.2592572868 -0.1734034866 0.1096551269 1173 46.8800000000 1.1714795828 0.5031089942 1.5112450123 0.0739192010 0.0309390000 1091611733 0 402718720 -0.2543119192 -0.1742876619 0.0978635103 1174 46.9200000000 1.1881802082 0.5036925302 1.5112450123 0.0739128655 0.0308590000 1094977157 0 402718720 -0.2594602406 -0.2159310877 0.0906664506 1175 46.9600000000 1.2080255747 0.5042919625 1.5112450123 0.0738864850 0.0302760000 1098326597 0 402718720 -0.2565271854 -0.2269593328 0.0723415539 1176 47.0000000000 1.2198246717 0.5049004087 1.5112450123 0.0738618487 0.0378800000 1101676037 0 402718720 -0.2321066558 -0.2387099117 0.0598329343 1177 47.0400000000 1.2326458693 0.5055187141 1.5112450123 0.0738380246 0.0318100000 1105025477 0 402718720 -0.2406819165 -0.2450723946 0.0501245707 1178 47.0800000000 1.2204838991 0.5061256455 1.5112450123 0.0738657450 0.0370960000 1108374917 0 402718720 -0.2710091174 -0.2798660100 0.0774296671 1179 47.1200000000 1.2356780767 0.5067444347 1.5112450123 0.0739310805 0.0316060000 1111724357 0 402718720 -0.2120131850 -0.2509275675 0.0473034531 1180 47.1600000000 1.2248289585 0.5073529809 1.5112450123 0.0739832433 0.0305680000 1115073797 0 402718720 -0.2727297246 -0.2662591934 0.0723268613 1181 47.2000000000 1.2460585833 0.5079784725 1.5112450123 0.0740186513 0.0291060000 1118423237 0 402718720 -0.2015052736 -0.2652873099 0.0412892103 1182 47.2400000000 1.2287164927 0.5085882340 1.5112450123 0.0740813855 0.0364080000 1121772677 0 402718720 -0.2746047080 -0.2672220767 0.0719934031 1183 47.2800000000 1.2521888018 0.5092168059 1.5112450123 0.0741375789 0.0531910000 1125122117 0 402718720 -0.2039850205 -0.2597528696 0.0365487635 1184 47.3200000000 1.2372591496 0.5098317065 1.5112450123 0.0741689933 0.0376720000 1128471557 0 402718720 -0.2647879124 -0.2527604103 0.0599930510 1185 47.3600000000 1.2436472178 0.5104509601 1.5112450123 0.0741556051 0.0245350000 1131820997 0 402718720 -0.2328979224 -0.2476231456 0.0481481925 1186 47.4000000000 1.2379454374 0.5110643618 1.5112450123 0.0741453235 0.0261980000 1135170437 0 402718720 -0.2601091266 -0.2451893240 0.0583481342 1187 47.4400000000 1.2470302582 0.5116843837 1.5112450123 0.0741317828 0.0257230000 1138519877 0 402718720 -0.2298745364 -0.2414769530 0.0441471636 1188 47.4800000000 1.2414447069 0.5122986600 1.5112450123 0.0741197957 0.0362680000 1141869317 0 402718720 -0.2519699633 -0.2211403996 0.0498437248 1189 47.5200000000 1.2504925728 0.5129195128 1.5112450123 0.0741082957 0.0313410000 1145218757 0 402718720 -0.2531437874 -0.2009363621 0.0374339819 1190 47.5600000000 1.2385298014 0.5135292693 1.5112450123 0.0741098806 0.0346970000 1148568197 0 402718720 -0.2633130252 -0.1740643531 0.0478608757 1191 47.6000000000 1.2414535284 0.5141404568 1.5112450123 0.0740788795 0.0272210000 1151917637 0 402718720 -0.2526021004 -0.1916519701 0.0465743951 1192 47.6400000000 1.2385088205 0.5147481483 1.5112450123 0.0740693057 0.0392870000 1155267077 0 402718720 -0.2594224215 -0.1735486537 0.0482216515 1193 47.6800000000 1.2232445478 0.5153420263 1.5112450123 0.0741148336 0.0336450000 1158616517 0 402718720 -0.2872723341 -0.2196926624 0.0776618496 1194 47.7200000000 1.2006303072 0.5159159696 1.5112450123 0.0742301323 0.0299470000 1161966469 0 402718720 -0.2940789461 -0.1697483063 0.0944203287 1195 47.7600000000 1.2111234665 0.5164977332 1.5112450123 0.0743460594 0.0703370000 1165315909 0 402718720 -0.3231921792 -0.2512486279 0.1068983600 1196 47.8000000000 1.2129076719 0.5170800157 1.5112450123 0.0743607230 0.0285130000 1168665349 0 402718720 -0.3646352291 -0.2588886023 0.1181531027 1197 47.8400000000 1.1991888285 0.5176498644 1.5112450123 0.0745481208 0.0357410000 1172014789 0 402718720 -0.4261106551 -0.2018035054 0.1395706683 1198 47.8800000000 1.1903293133 0.5182113664 1.5112450123 0.0746241577 0.0276970000 1175364229 0 402718720 -0.4427255094 -0.1645769328 0.1490880847 1199 47.9200000000 1.2248001099 0.5188006815 1.5112450123 0.0749929040 0.0360500000 1178713669 0 402718720 -0.3231426775 -0.1751368791 0.0800482184 1200 47.9600000000 1.0762189627 0.5192651967 1.5112450123 0.1160114959 0.0334370000 1182063109 0 402718720 -0.1658261865 0.0813625306 0.1916399896 1201 48.0000000000 1.1199734211 0.5197653701 1.5112450123 0.1163942504 0.0261480000 1179987389 0 402718720 -0.2259872705 -0.0521287322 0.1561549157 1202 48.0400000000 1.0448770523 0.5202022350 1.5112450123 0.1163836711 0.0132410000 1194909269 0 402718720 -0.2098211497 -0.0677860901 0.2314876467 1203 48.0800000000 1.0295943022 0.5206256698 1.5112450123 0.1163360773 0.0249010000 1192833757 0 402718720 -0.1986690760 -0.0749202371 0.2463886142 1204 48.1200000000 1.0317317247 0.5210501765 1.5112450123 0.1180643977 0.0140930000 1207755701 0 402718720 -0.0417310297 0.0557846986 0.2313603759 1205 48.1600000000 1.0266814232 0.5214697875 1.5112450123 0.1180198387 0.0224740000 1205680125 0 402718720 -0.0447597206 0.0594313405 0.2370208949 1206 48.2000000000 1.1141169071 0.5219612030 1.5112450123 0.1188835797 0.0265340000 1220602133 0 402718720 -0.1300469488 0.0035154687 0.1516203433 1207 48.2400000000 1.1768282652 0.5225037607 1.5112450123 0.1195975652 0.0272110000 1218526493 0 402718720 -0.2505803108 -0.1710679382 0.1188216135 1208 48.2800000000 1.1344636679 0.5230103500 1.5112450123 0.1200512436 0.0445290000 1233448565 0 402718720 -0.2005541474 0.0559470356 0.1409070045 1209 48.3200000000 1.1531705856 0.5235315743 1.5112450123 0.1200037260 0.0287070000 1231372861 0 402718720 -0.2116291374 0.0509393439 0.1238516271 1210 48.3600000000 1.2501188517 0.5241320597 1.5112450123 0.1212216454 0.0243580000 1246294997 0 402718720 -0.3549246490 -0.2524673343 0.0832985789 1211 48.4000000000 1.2363668680 0.5247201974 1.5112450123 0.1237749881 0.0291260000 1246374101 0 402718720 -0.1012304276 -0.0342652313 0.0314941183 1212 48.4400000000 1.2440235615 0.5253136821 1.5112450123 0.1237253320 0.0057500000 1235606789 0 402718720 -0.0951459333 -0.0451681651 0.0248502828 1213 48.4800000000 1.2473590374 0.5259089379 1.5112450123 0.1236754588 0.0179770000 1235609037 0 402718720 -0.0963281319 -0.0494682603 0.0219201483 1214 48.5200000000 1.2874960899 0.5265362750 1.5112450123 0.1262361812 0.0289350000 1238994949 0 402718720 -0.2876563966 -0.3540353775 0.0581161864 1215 48.5600000000 1.0630153418 0.5269778215 1.5112450123 0.1288463999 0.0241130000 1246371581 0 402718720 -0.0907288790 0.0850827470 0.2085546851 1216 48.6000000000 1.0702620745 0.5274246013 1.5112450123 0.1287959675 0.0322340000 1239000829 0 402718720 -0.0787672028 0.0756711215 0.2010968179 1217 48.6400000000 1.0265451670 0.5278347250 1.5112450123 0.1323928922 0.0279960000 1246377461 0 402718720 0.0235678256 0.5426575541 0.3934605122 1218 48.6800000000 0.9724695086 0.5281997782 1.5112450123 0.1331639289 0.0302930000 1239008009 0 402718720 0.0637214705 0.6072982550 0.5082786679 1219 48.7200000000 0.9733299017 0.5285649383 1.5112450123 0.1331100259 0.0251290000 1246384641 0 402718720 0.0637214705 0.6072982550 0.5082786679 1220 48.7600000000 1.2839506865 0.5291841069 1.5112450123 0.1409482054 0.0128430000 1246386649 0 402718720 -0.0683512837 -0.2168288082 0.0070065041 1221 48.8000000000 1.2893288136 0.5298066661 1.5112450123 0.1408925318 0.0505670000 1239017217 0 402718720 -0.0440123305 -0.2551388144 0.0090810256 1222 48.8400000000 0.9863191247 0.5301802442 1.5112450123 0.1419474338 0.0277000000 1246393849 0 402718720 -0.1125633642 0.1181965247 0.2980505824 1223 48.8800000000 0.9893100858 0.5305556570 1.5112450123 0.1418943108 0.0305040000 1235637937 0 402718720 -0.1193338931 0.1039984822 0.2949607074 1224 48.9200000000 0.9956119657 0.5309356050 1.5112450123 0.1418389489 0.0325390000 1239025549 0 402718720 -0.1241263822 0.0919581354 0.2891554832 1225 48.9600000000 0.9808113575 0.5313028505 1.5112450123 0.1419395022 0.0226640000 1246402181 0 402718720 -0.0544261076 0.1211458594 0.3025322556 1226 49.0000000000 0.9761276245 0.5316656765 1.5112450123 0.1419912309 0.0484770000 1235638141 0 402718720 -0.0568287671 0.0812409222 0.3043429852 1227 49.0400000000 0.9793353081 0.5320305255 1.5112450123 0.1419352707 0.0367990000 1235640389 0 402718720 -0.0556554869 0.0814831555 0.3023711741 1228 49.0800000000 0.9840353131 0.5323986075 1.5112450123 0.1418805575 0.0359860000 1235642637 0 402718720 -0.0506904460 0.0829524100 0.2985549271 1229 49.1200000000 0.9885947108 0.5327698005 1.5112450123 0.1418250098 0.0353420000 1235644885 0 402718720 -0.0471534282 0.0848500803 0.2949791551 1230 49.1600000000 0.9905719757 0.5331419974 1.5112450123 0.1417706460 0.0349110000 1235647133 0 402718720 -0.0409407876 0.0862366706 0.2936875820 1231 49.2000000000 0.9910752177 0.5335139984 1.5112450123 0.1420187651 0.0385700000 1239034989 0 402718720 0.0503368266 0.0627114177 0.2909755707 1232 49.2400000000 0.9906860590 0.5338850796 1.5112450123 0.1419618196 0.0490240000 1235653061 0 402718720 0.0492119826 0.0626222268 0.2917584181 1233 49.2800000000 0.9915605187 0.5342562681 1.5112450123 0.1419045447 0.0125680000 1235655309 0 402718720 0.0496667810 0.0630444363 0.2915520966 1234 49.3200000000 0.9918842316 0.5346271173 1.5112450123 0.1418474235 0.0157410000 1235657557 0 402718720 0.0495707914 0.0631584376 0.2919752300 1235 49.3600000000 0.9926650524 0.5349979982 1.5112450123 0.1417908180 0.0154650000 1235659805 0 402718720 0.0496120602 0.0638288185 0.2919052839 1236 49.4000000000 0.9927468300 0.5353683452 1.5112450123 0.1417353977 0.0210310000 1235662053 0 402718720 0.0491311140 0.0634885356 0.2924047112 1237 49.4400000000 0.9927149415 0.5357380676 1.5112450123 0.1416796367 0.0214660000 1235664301 0 402718720 0.0489673279 0.0639384091 0.2924329340 1238 49.4800000000 0.9915775657 0.5361062740 1.5112450123 0.1416243070 0.0244360000 1235666549 0 402718720 0.0479550771 0.0630199611 0.2933138907 1239 49.5200000000 0.9919605851 0.5364741951 1.5112450123 0.1415689170 0.0216400000 1235668797 0 402718720 0.0477231033 0.0636660308 0.2928525805 1240 49.5600000000 0.9923363924 0.5368418259 1.5112450123 0.1415136242 0.0217710000 1235671045 0 402718720 0.0474889353 0.0633745492 0.2931962311 1241 49.6000000000 0.9912824035 0.5372080149 1.5112450123 0.1414582692 0.0254070000 1235673293 0 402718720 0.0459770747 0.0617440939 0.2939991653 1242 49.6400000000 0.9903461337 0.5375728605 1.5112450123 0.1414020310 0.0245120000 1235675541 0 402718720 0.0454162918 0.0609583110 0.2947620153 1243 49.6800000000 0.9903977513 0.5379371604 1.5112450123 0.1413455221 0.0239050000 1235677789 0 402718720 0.0445310287 0.0603948422 0.2953406572 1244 49.7200000000 0.9892232418 0.5382999306 1.5112450123 0.1412892694 0.0271690000 1235680037 0 402718720 0.0429216288 0.0590099767 0.2961117625 1245 49.7600000000 0.9881274104 0.5386612378 1.5112450123 0.1412327733 0.0201940000 1235682285 0 402718720 0.0417097956 0.0590567291 0.2963706851 1246 49.8000000000 0.9878821373 0.5390217682 1.5112450123 0.1411763625 0.0435260000 1235684533 0 402718720 0.0411081128 0.0588817857 0.2968564928 1247 49.8400000000 0.9871956706 0.5393811699 1.5112450123 0.1411199824 0.0207510000 1235686781 0 402718720 0.0408038162 0.0582629964 0.2970325053 1248 49.8800000000 0.9867405295 0.5397396310 1.5112450123 0.1410636203 0.0173140000 1235689029 0 402718720 0.0402368046 0.0579214357 0.2972629070 1249 49.9200000000 0.9869365096 0.5400976749 1.5112450123 0.1410072081 0.0177130000 1235691277 0 402718720 0.0399648026 0.0575845353 0.2972839177 1250 49.9600000000 0.9862092733 0.5404545642 1.5112450123 0.1409509070 0.0188980000 1235693525 0 402718720 0.0394989997 0.0571194068 0.2975291908 1251 50.0000000000 0.9847854972 0.5408097448 1.5112450123 0.1408946841 0.0179120000 1235695773 0 402718720 0.0391231515 0.0566371791 0.2978626490 1252 50.0400000000 0.9840053916 0.5411637349 1.5112450123 0.1408385041 0.0175450000 1235698021 0 402718720 0.0388536341 0.0562061220 0.2979914248 1253 50.0800000000 0.9831537604 0.5415164803 1.5112450123 0.1407823536 0.0179120000 1235700269 0 402718720 0.0383822694 0.0557968393 0.2983607650 1254 50.1200000000 0.9829279184 0.5418684831 1.5112450123 0.1407262641 0.0185410000 1235702517 0 402718720 0.0379831456 0.0554866679 0.2983303368 1255 50.1600000000 0.9822488427 0.5422193838 1.5112450123 0.1406703014 0.0157900000 1235704765 0 402718720 0.0376355201 0.0550612062 0.2986237109 1256 50.2000000000 0.9817789793 0.5425693516 1.5112450123 0.1406145190 0.0174680000 1235707013 0 402718720 0.0371869244 0.0547026172 0.2987003028 1257 50.2400000000 0.9819552898 0.5429189029 1.5112450123 0.1405587491 0.0177420000 1235709261 0 402718720 0.0367002338 0.0544359162 0.2988352180 1258 50.2800000000 0.9807125926 0.5432669106 1.5112450123 0.1405029695 0.0183510000 1235711509 0 402718720 0.0364339463 0.0542798787 0.2988440394 1259 50.3200000000 0.9802543521 0.5436140015 1.5112450123 0.1404474187 0.0183460000 1235713757 0 402718720 0.0355000421 0.0537055396 0.2991892099 1260 50.3600000000 0.9784124494 0.5439590796 1.5112450123 0.1403920279 0.0182760000 1235716005 0 402718720 0.0348924734 0.0530429594 0.2996478379 1261 50.4000000000 0.9780102372 0.5443032915 1.5112450123 0.1403366535 0.0186510000 1235718253 0 402718720 0.0340902470 0.0525558591 0.2999027073 1262 50.4400000000 0.9765591621 0.5446458080 1.5112450123 0.1402813148 0.0186430000 1235720501 0 402718720 0.0334917530 0.0519587472 0.3001770675 1263 50.4800000000 0.9750912189 0.5449866199 1.5112450123 0.1402260048 0.0183640000 1235722749 0 402718720 0.0328723751 0.0513402745 0.3005676866 1264 50.5200000000 0.9741541147 0.5453261511 1.5112450123 0.1401706676 0.0445790000 1235724997 0 402718720 0.0326995403 0.0509751663 0.3005861640 1265 50.5600000000 0.9742284417 0.5456652043 1.5112450123 0.1401154480 0.0209390000 1235727245 0 402718720 0.0319037922 0.0506361164 0.3008024395 1266 50.6000000000 0.9733151197 0.5460030005 1.5112450123 0.1400602857 0.0186530000 1235729493 0 402718720 0.0313412249 0.0501580983 0.3010087013 1267 50.6400000000 0.9718651175 0.5463391189 1.5112450123 0.1400051359 0.0186930000 1235731741 0 402718720 0.0308308396 0.0497301072 0.3012888432 1268 50.6800000000 0.9707050920 0.5466737924 1.5112450123 0.1399505634 0.0184890000 1235733989 0 402718720 0.0297480300 0.0487279482 0.3016163111 1269 50.7200000000 0.9699261785 0.5470073246 1.5112450123 0.1398957296 0.0188940000 1235736237 0 402718720 0.0294086281 0.0483425707 0.3015772998 1270 50.7600000000 0.9691330791 0.5473397071 1.5112450123 0.1398409296 0.0190950000 1235738485 0 402718720 0.0289953034 0.0479890034 0.3016379476 1271 50.8000000000 0.9670715928 0.5476699446 1.5112450123 0.1397861648 0.0191460000 1235740733 0 402718720 0.0291360877 0.0476261191 0.3015217483 1272 50.8400000000 0.9661024809 0.5479989010 1.5112450123 0.1397315083 0.0184660000 1235742981 0 402718720 0.0290220045 0.0472088158 0.3015532196 1273 50.8800000000 0.9649229646 0.5483264140 1.5112450123 0.1396767980 0.0191690000 1235745229 0 402718720 0.0288569778 0.0467690341 0.3016554713 1274 50.9200000000 0.9637248516 0.5486524725 1.5112450123 0.1396221455 0.1565280000 1239447329 0 402718720 0.0285514109 0.0463296659 0.3017029762 1275 50.9600000000 0.9604091644 0.5489754189 1.5112450123 0.1395744367 0.0127600000 1239450897 0 402718720 0.0178453662 0.0616170615 0.3062950671 1276 51.0000000000 0.9600517154 0.5492975790 1.5112450123 0.1395199339 0.0359060000 1239453145 0 402718720 0.0172792654 0.0612009652 0.3064206243 1277 51.0400000000 0.9603143930 0.5496194403 1.5112450123 0.1394654367 0.0351510000 1239455393 0 402718720 0.0167313609 0.0610812269 0.3064220548 1278 51.0800000000 0.9605110288 0.5499409517 1.5112450123 0.1394110854 0.0318140000 1239457641 0 402718720 0.0162881762 0.0607424267 0.3064136207 1279 51.1200000000 0.9604048729 0.5502618773 1.5112450123 0.1393568854 0.0546490000 1239459889 0 402718720 0.0159783531 0.0605438314 0.3064671159 1280 51.1600000000 0.9599698186 0.5505819617 1.5112450123 0.1393029060 0.0268070000 1239462137 0 402718720 0.0160489157 0.0605702177 0.3063128889 1281 51.2000000000 0.9580016136 0.5509000098 1.5112450123 0.1392489991 0.0251520000 1239464385 0 402718720 0.0157457367 0.0600552745 0.3066034913 1282 51.2400000000 0.9572859406 0.5512170035 1.5112450123 0.1391948673 0.0242310000 1239466633 0 402718720 0.0157401916 0.0598926060 0.3066246510 1283 51.2800000000 0.9573749304 0.5515335724 1.5112450123 0.1391408666 0.0223650000 1239468881 0 402718720 0.0155624663 0.0598149300 0.3065786660 1284 51.3200000000 0.9572091103 0.5518495191 1.5112450123 0.1390870435 0.0306030000 1239471129 0 402718720 0.0152546326 0.0596596040 0.3067479730 1285 51.3600000000 0.9568857551 0.5521647224 1.5112450123 0.1390332746 0.0239260000 1239473377 0 402718720 0.0148748979 0.0594083332 0.3069228232 1286 51.4000000000 0.9568806887 0.5524794315 1.5112450123 0.1389794683 0.0216290000 1239475625 0 402718720 0.0145689184 0.0593097173 0.3070780635 1287 51.4400000000 0.9569410682 0.5527936986 1.5112450123 0.1389261384 0.0206080000 1239477873 0 402718720 0.0143579720 0.0592160150 0.3071261346 1288 51.4800000000 0.9576699138 0.5531080434 1.5112450123 0.1388730931 0.0213980000 1239480121 0 402718720 0.0141896959 0.0594010465 0.3070064783 1289 51.5200000000 0.9566664100 0.5534211221 1.5112450123 0.1388200335 0.0197990000 1239482369 0 402718720 0.0140681332 0.0590284467 0.3073035479 1290 51.5600000000 0.9567512870 0.5537337811 1.5112450123 0.1387680130 0.0748070000 1243182733 0 402718720 0.0133768637 0.0587297752 0.3075228333 1291 51.6000000000 0.9564007521 0.5540456843 1.5112450123 0.1387159057 0.0124090000 1243186301 0 402718720 0.0132187055 0.0584764108 0.3078051507 1292 51.6400000000 0.9559074640 0.5543567228 1.5112450123 0.1386634759 0.0127170000 1243188549 0 402718720 0.0130571192 0.0581709631 0.3078674674 1293 51.6800000000 0.9554400444 0.5546669187 1.5112450123 0.1386109766 0.0405690000 1243190797 0 402718720 0.0129641630 0.0579804368 0.3079432249 1294 51.7200000000 0.9555502534 0.5549767204 1.5112450123 0.1385580458 0.0176680000 1243193045 0 402718720 0.0126773268 0.0578240193 0.3079613745 1295 51.7600000000 0.9553241730 0.5552858690 1.5112450123 0.1385062063 0.0131520000 1243195293 0 402718720 0.0126275197 0.0579239316 0.3077422976 1296 51.8000000000 0.9542794228 0.5555937344 1.5112450123 0.1384601399 0.0222920000 1243197541 0 402718720 0.0125954906 0.0571264960 0.3078105152 1297 51.8400000000 0.9543882012 0.5559012089 1.5112450123 0.1384089913 0.0219180000 1243199789 0 402718720 0.0124183483 0.0572522394 0.3078877926 1298 51.8800000000 0.9534659386 0.5562074991 1.5112450123 0.1383580021 0.0438540000 1243202037 0 402718720 0.0122402478 0.0568311065 0.3080886602 1299 51.9200000000 0.9527980685 0.5565128037 1.5112450123 0.1383069748 0.0353730000 1243204285 0 402718720 0.0120654022 0.0565390885 0.3084310591 1300 51.9600000000 0.9524986744 0.5568174082 1.5112450123 0.1382563822 0.0982080000 1246906853 0 402718720 0.0117447646 0.0564360432 0.3085168004 1301 52.0000000000 0.9514873624 0.5571207671 1.5112450123 0.1382056247 0.0126110000 1246910421 0 402718720 0.0113684358 0.0564053543 0.3089782894 1302 52.0400000000 0.9501561522 0.5574226376 1.5112450123 0.1381550274 0.0175410000 1246912669 0 402718720 0.0108702453 0.0556129366 0.3092823625 1303 52.0800000000 0.9489539862 0.5577231221 1.5112450123 0.1381033910 0.0362090000 1246914917 0 402718720 0.0104397247 0.0549858734 0.3092237711 1304 52.1200000000 0.9478623271 0.5580223086 1.5112450123 0.1380515552 0.0776780000 1246917165 0 402718720 0.0100909472 0.0543430559 0.3092449009 1305 52.1600000000 0.9466359019 0.5583200968 1.5112450123 0.1379999890 0.0361540000 1246919413 0 402718720 0.0097370222 0.0533816256 0.3092891276 1306 52.2000000000 0.9452663660 0.5586163803 1.5112450123 0.1379479433 0.0329750000 1246921661 0 402718720 0.0092789661 0.0532071330 0.3094573319 1307 52.2400000000 0.9438561797 0.5589111315 1.5112450123 0.1378951968 0.0322900000 1246923909 0 402718720 0.0089191291 0.0541557074 0.3099883199 1308 52.2800000000 0.9428259730 0.5592046444 1.5112450123 0.1378428672 0.0284800000 1246926157 0 402718720 0.0084626172 0.0517396182 0.3098379076 1309 52.3200000000 0.9413945079 0.5594966153 1.5112450123 0.1377911964 0.0276660000 1246928405 0 402718720 0.0082090069 0.0518314354 0.3100182414 1310 52.3600000000 0.9405282140 0.5597874791 1.5112450123 0.1377405144 0.0261970000 1246930653 0 402718720 0.0079993550 0.0516676754 0.3100001216 1311 52.4000000000 0.9392203093 0.5600769015 1.5112450123 0.1376897690 0.0273120000 1246932901 0 402718720 0.0076814629 0.0492025204 0.3102679551 1312 52.4400000000 0.9381818771 0.5603650913 1.5112450123 0.1376387242 0.0257610000 1246935149 0 402718720 0.0065696593 0.0484578162 0.3097665906 1313 52.4800000000 0.9366238713 0.5606516555 1.5112450123 0.1375875617 0.0244980000 1246937397 0 402718720 0.0061676912 0.0481692217 0.3100090027 1314 52.5200000000 0.9353799224 0.5609368368 1.5112450123 0.1375369992 0.0249960000 1246939645 0 402718720 0.0046856664 0.0462129749 0.3092424870 1315 52.5600000000 0.9338680506 0.5612204347 1.5112450123 0.1374859098 0.0248980000 1246941893 0 402718720 0.0037515380 0.0446322486 0.3090910017 1316 52.6000000000 0.9323688149 0.5615024624 1.5112450123 0.1374346376 0.0246940000 1246944141 0 402718720 0.0029076752 0.0433536619 0.3091858327 1317 52.6400000000 0.9307413101 0.5617828259 1.5112450123 0.1373841752 0.0584170000 1246946389 0 402718720 0.0017274269 0.0417638868 0.3092634082 1318 52.6800000000 0.9295601249 0.5620618679 1.5112450123 0.1373337107 0.0238820000 1246948637 0 402718720 0.0004292349 0.0402475074 0.3091467917 1319 52.7200000000 0.9284681678 0.5623396589 1.5112450123 0.1372831163 0.0242450000 1246950885 0 402718720 -0.0008265689 0.0384777300 0.3090644181 1320 52.7600000000 0.9277495742 0.5626164846 1.5112450123 0.1372328900 0.0240220000 1246953133 0 402718720 -0.0020928397 0.0366809703 0.3089756966 1321 52.8000000000 0.9266715646 0.5628920751 1.5112450123 0.1371828668 0.0238310000 1246955381 0 402718720 -0.0037870810 0.0344595276 0.3090124726 1322 52.8400000000 0.9260815382 0.5631668024 1.5112450123 0.1371318792 0.0247870000 1246957629 0 402718720 -0.0052972510 0.0325156599 0.3088293672 1323 52.8800000000 0.9253669977 0.5634405742 1.5112450123 0.1370814939 0.0251750000 1246959877 0 402718720 -0.0065778987 0.0307899024 0.3087643683 1324 52.9200000000 0.9249987006 0.5637136544 1.5112450123 0.1370320112 0.0259410000 1246962125 0 402718720 -0.0084214099 0.0286551230 0.3085494041 1325 52.9600000000 0.9249631763 0.5639862956 1.5112450123 0.1369818316 0.0261540000 1246964373 0 402718720 -0.0098930355 0.0266519897 0.3083362877 1326 53.0000000000 0.9248689413 0.5642584544 1.5112450123 0.1369317836 0.0262730000 1246966621 0 402718720 -0.0116107995 0.0245390013 0.3082092702 1327 53.0400000000 0.9251078367 0.5645303831 1.5112450123 0.1368814813 0.0282610000 1246968869 0 402718720 -0.0134561202 0.0222564135 0.3080469072 1328 53.0800000000 0.9258737564 0.5648024790 1.5112450123 0.1368317471 0.0279890000 1246971117 0 402718720 -0.0154966144 0.0189714935 0.3081115484 1329 53.1200000000 0.9267172217 0.5650748001 1.5112450123 0.1367809243 0.0268830000 1246973365 0 402718720 -0.0168296378 0.0167624876 0.3080227971 1330 53.1600000000 0.9272946119 0.5653471458 1.5112450123 0.1367304393 0.0593300000 1246975613 0 402718720 -0.0186139066 0.0149237467 0.3078315854 1331 53.2000000000 0.9286869168 0.5656201284 1.5112450123 0.1366818523 0.0273720000 1246977861 0 402718720 -0.0208753888 0.0123514188 0.3076425195 1332 53.2400000000 0.9305979013 0.5658941357 1.5112450123 0.1366320214 0.0268070000 1246980109 0 402718720 -0.0231488124 0.0096929315 0.3074719608 1333 53.2800000000 0.9319700003 0.5661687613 1.5112450123 0.1365811486 0.0274360000 1246982357 0 402718720 -0.0250589438 0.0076362146 0.3072177768 1334 53.3200000000 0.9337722659 0.5664443261 1.5112450123 0.1365304608 0.0274970000 1246984605 0 402718720 -0.0268801358 0.0059749079 0.3065246046 1335 53.3600000000 0.9359232783 0.5667210894 1.5112450123 0.1364798385 0.0269830000 1246986853 0 402718720 -0.0288411863 0.0035730663 0.3062616289 1336 53.4000000000 0.9380126595 0.5669990022 1.5112450123 0.1364291021 0.0288240000 1246989101 0 402718720 -0.0305813141 0.0029782255 0.3056336641 1337 53.4400000000 0.9398334622 0.5672778612 1.5112450123 0.1363784544 0.0276060000 1246991349 0 402718720 -0.0320305414 0.0018173717 0.3047258258 1338 53.4800000000 0.9418727756 0.5675578275 1.5112450123 0.1363291150 0.0285260000 1246993597 0 402718720 -0.0344575644 0.0018964005 0.3043625355 1339 53.5200000000 0.9451680183 0.5678398366 1.5112450123 0.1362808937 0.3251480000 1250704341 0 402718720 -0.0367531106 0.0010972446 0.3038536012 1340 53.5600000000 0.9483523369 0.5681238012 1.5112450123 0.1362330249 0.0349150000 1250707909 0 402718720 -0.0377885848 0.0035539481 0.3031422198 1341 53.6000000000 0.9521936178 0.5684102067 1.5112450123 0.1361831296 0.0327260000 1250710157 0 402718720 -0.0396910608 0.0026324338 0.3024576902 1342 53.6400000000 0.9559030533 0.5686989495 1.5112450123 0.1361326153 0.0291770000 1250712405 0 402718720 -0.0408485569 0.0013971659 0.3020047247 1343 53.6800000000 0.9585548043 0.5689892368 1.5112450123 0.1360819684 0.0560560000 1250714653 0 402718720 -0.0419636108 0.0007938278 0.3016754687 1344 53.7200000000 0.9614320993 0.5692812330 1.5112450123 0.1360317038 0.0279660000 1250716901 0 402718720 -0.0429842994 -0.0007016808 0.3013340533 1345 53.7600000000 0.9653994441 0.5695757447 1.5112450123 0.1359824075 0.0294000000 1250719149 0 402718720 -0.0446794741 -0.0015589122 0.3007397652 1346 53.8000000000 0.9684646726 0.5698720960 1.5112450123 0.1359331885 0.0259590000 1250721397 0 402718720 -0.0457258075 -0.0021946465 0.3003261089 1347 53.8400000000 0.9763826132 0.5701738856 1.5112450123 0.1358928948 0.0253050000 1250723645 0 402718720 -0.0477693006 -0.0030223355 0.2999994159 1348 53.8800000000 0.9810714722 0.5704787058 1.5112450123 0.1358434267 0.0254860000 1250725893 0 402718720 -0.0488836281 -0.0028032791 0.2995343506 1349 53.9200000000 0.9840984941 0.5707853179 1.5112450123 0.1357931320 0.0278450000 1250728141 0 402718720 -0.0496033207 -0.0028687979 0.2994358540 1350 53.9600000000 0.9869321585 0.5710935748 1.5112450123 0.1357429996 0.0258860000 1250730389 0 402718720 -0.0503883213 -0.0039113839 0.2995162606 1351 54.0000000000 0.9886574745 0.5714026525 1.5112450123 0.1356928156 0.0265030000 1250732637 0 402718720 -0.0502282195 -0.0053849095 0.3002605736 1352 54.0400000000 0.9917726517 0.5717135770 1.5112450123 0.1356433536 0.0296210000 1250734885 0 402718720 -0.0508359745 -0.0074940273 0.2996565104 1353 54.0800000000 0.9948821664 0.5720263402 1.5112450123 0.1355954985 0.0251520000 1250737133 0 402718720 -0.0519293547 -0.0071746539 0.2993487418 1354 54.1200000000 0.9966998100 0.5723399838 1.5112450123 0.1355469912 0.0242610000 1250739381 0 402718720 -0.0519861691 -0.0059699528 0.2990006208 1355 54.1600000000 0.9987350106 0.5726546665 1.5112450123 0.1354987763 0.0235910000 1250741629 0 402718720 -0.0525526665 -0.0054276558 0.2985036373 1356 54.2000000000 1.0024710894 0.5729716403 1.5112450123 0.1354498330 0.0581050000 1250743877 0 402718720 -0.0526436120 -0.0082064122 0.2984589636 1357 54.2400000000 1.0036352873 0.5732890048 1.5112450123 0.1354012485 0.0247790000 1250746125 0 402718720 -0.0537436120 -0.0073810988 0.2988191545 1358 54.2800000000 1.0053136349 0.5736071378 1.5112450123 0.1353519515 0.0253730000 1250748373 0 402718720 -0.0536025651 -0.0067830565 0.2974643111 1359 54.3200000000 1.0078560114 0.5739266734 1.5112450123 0.1353026127 0.0240580000 1250750621 0 402718720 -0.0544845127 -0.0097336899 0.2974202633 1360 54.3600000000 1.0111731291 0.5742481782 1.5112450123 0.1352539283 0.0243250000 1250752869 0 402718720 -0.0556704253 -0.0103965113 0.2980225980 1361 54.4000000000 1.0128827095 0.5745704666 1.5112450123 0.1352044659 0.0259160000 1250755117 0 402718720 -0.0558662191 -0.0094943643 0.2968273759 1362 54.4400000000 1.0127744675 0.5748922022 1.5112450123 0.1351575396 0.0316400000 1250757365 0 402718720 -0.0573137775 -0.0036692934 0.2959653735 1363 54.4800000000 1.0161089897 0.5752159123 1.5112450123 0.1351085003 0.0251740000 1250759613 0 402718720 -0.0586023368 -0.0046021002 0.2955861986 1364 54.5200000000 1.0189239979 0.5755412115 1.5112450123 0.1350595196 0.0266150000 1250761861 0 402718720 -0.0592787825 -0.0055955471 0.2950917184 1365 54.5600000000 1.0197396278 0.5758666316 1.5112450123 0.1350111079 0.0249060000 1250764109 0 402718720 -0.0601139702 -0.0052480288 0.2955178916 1366 54.6000000000 1.0221271515 0.5761933230 1.5112450123 0.1349641670 0.0260920000 1250766357 0 402718720 -0.0621558987 -0.0062114801 0.2963149250 1367 54.6400000000 1.0268261433 0.5765229739 1.5112450123 0.1349175325 0.0258780000 1250768605 0 402718720 -0.0623173453 -0.0055681486 0.2953509390 1368 54.6800000000 1.0294464827 0.5768540584 1.5112450123 0.1348694761 0.0252480000 1250770853 0 402718720 -0.0628791600 -0.0052439286 0.2949391603 1369 54.7200000000 1.0330716372 0.5771873072 1.5112450123 0.1348226298 0.1550500000 1254473825 0 402718720 -0.0642226338 -0.0062513887 0.2955013216 1370 54.7600000000 1.0415685177 0.5775262715 1.5112450123 0.1347744690 0.0157990000 1254477393 0 402718720 -0.0631181896 -0.0154483775 0.2958586812 1371 54.8000000000 1.0454598665 0.5778675798 1.5112450123 0.1347261526 0.0174060000 1254479641 0 402718720 -0.0633439571 -0.0153411338 0.2953374088 1372 54.8400000000 1.0509556532 0.5782123962 1.5112450123 0.1346787100 0.0265900000 1254481889 0 402718720 -0.0650604218 -0.0162256137 0.2952421308 1373 54.8800000000 1.0555797815 0.5785600782 1.5112450123 0.1346309581 0.0302140000 1254484137 0 402718720 -0.0661192685 -0.0163957272 0.2947683334 1374 54.9200000000 1.0597171783 0.5789102653 1.5112450123 0.1345833497 0.0349650000 1254486385 0 402718720 -0.0672156513 -0.0168363862 0.2944101989 1375 54.9600000000 1.0646035671 0.5792634968 1.5112450123 0.1345361264 0.0306190000 1254488633 0 402718720 -0.0684702322 -0.0172299314 0.2938409448 1376 55.0000000000 1.0696477890 0.5796198807 1.5112450123 0.1344888023 0.0275270000 1254490881 0 402718720 -0.0693337172 -0.0173786227 0.2929739654 1377 55.0400000000 1.0742087364 0.5799790592 1.5112450123 0.1344426032 0.0293790000 1254493129 0 402718720 -0.0710609481 -0.0178453512 0.2929169238 1378 55.0800000000 1.0790886879 0.5803412578 1.5112450123 0.1343955965 0.0270300000 1254495377 0 402718720 -0.0721747950 -0.0180181786 0.2922875583 1379 55.1200000000 1.0836858749 0.5807062648 1.5112450123 0.1343489437 0.0237640000 1254497625 0 402718720 -0.0736075491 -0.0186604131 0.2920762897 1380 55.1600000000 1.0889832973 0.5810745815 1.5112450123 0.1343027091 0.0251160000 1254499873 0 402718720 -0.0746007338 -0.0190897509 0.2910779119 1381 55.2000000000 1.0939406157 0.5814459544 1.5112450123 0.1342567244 0.0606620000 1254502121 0 402718720 -0.0757195279 -0.0195272304 0.2904749513 1382 55.2400000000 1.0987040997 0.5818202367 1.5112450123 0.1342112072 0.0250820000 1254504369 0 402718720 -0.0763143003 -0.0196463559 0.2897980511 1383 55.2800000000 1.1041185856 0.5821978928 1.5112450123 0.1341660020 0.0246040000 1254506617 0 402718720 -0.0775007904 -0.0204709657 0.2890687883 1384 55.3200000000 1.1092118025 0.5825786832 1.5112450123 0.1341204870 0.0254960000 1254508865 0 402718720 -0.0784469917 -0.0208947361 0.2880680859 1385 55.3600000000 1.1134051085 0.5829619514 1.5112450123 0.1340751383 0.0239100000 1254511113 0 402718720 -0.0791603476 -0.0208612215 0.2880712152 1386 55.4000000000 1.1182838678 0.5833481865 1.5112450123 0.1340299964 0.0322770000 1254513361 0 402718720 -0.0800624788 -0.0215000995 0.2870884240 1387 55.4400000000 1.1223361492 0.5837367864 1.5112450123 0.1339852722 0.1434010000 1263145021 0 402718720 -0.0802678987 -0.0216717217 0.2865554094 1388 55.4800000000 1.1294212341 0.5841299308 1.5112450123 0.1339392755 0.0152580000 1263148589 0 402718720 -0.0811272934 -0.0261092819 0.2850957215 1389 55.5200000000 1.1331518888 0.5845251950 1.5112450123 0.1338947488 0.0149250000 1263150837 0 402718720 -0.0812474787 -0.0261851307 0.2849175036 1390 55.5600000000 1.1376563311 0.5849231310 1.5112450123 0.1338505633 0.0198160000 1263153085 0 402718720 -0.0817085877 -0.0260886084 0.2841060758 1391 55.6000000000 1.1421462297 0.5853237228 1.5112450123 0.1338052749 0.0200430000 1263155333 0 402718720 -0.0833750367 -0.0265035536 0.2841452360 1392 55.6400000000 1.1467876434 0.5857270733 1.5112450123 0.1337593208 0.0607820000 1263157581 0 402718720 -0.0836848468 -0.0266593508 0.2836845517 1393 55.6800000000 1.1509943008 0.5861328645 1.5112450123 0.1337135641 0.0262330000 1263159829 0 402718720 -0.0847338662 -0.0270049833 0.2839111686 1394 55.7200000000 1.1545683146 0.5865406375 1.5112450123 0.1336684084 0.0244900000 1263162077 0 402718720 -0.0849342793 -0.0268493053 0.2836976647 1395 55.7600000000 1.1580036879 0.5869502884 1.5112450123 0.1336239787 0.0231870000 1263164325 0 402718720 -0.0848605186 -0.0267225429 0.2838544250 1396 55.8000000000 1.1625921726 0.5873626393 1.5112450123 0.1335811582 0.0228670000 1263166573 0 402718720 -0.0853089690 -0.0268428139 0.2839792371 1397 55.8400000000 1.1664546728 0.5877771647 1.5112450123 0.1335385601 0.0240080000 1263168821 0 402718720 -0.0865721107 -0.0266628601 0.2855054140 1398 55.8800000000 1.1729792356 0.5881957642 1.5112450123 0.1334939380 0.0193780000 1263171069 0 402718720 -0.0849653110 -0.0265065879 0.2844389975 1399 55.9200000000 1.1786218882 0.5886177986 1.5112450123 0.1334490059 0.0197490000 1263173317 0 402718720 -0.0850746632 -0.0264383461 0.2848873138 1400 55.9600000000 1.1841838360 0.5890432029 1.5112450123 0.1334029837 0.1385420000 1271796549 0 402718720 -0.0853261203 -0.0264843013 0.2849859595 1401 56.0000000000 1.1911950111 0.5894730044 1.5112450123 0.1333572284 0.0132700000 1271800117 0 402718720 -0.0911813453 -0.0279429983 0.2850812376 1402 56.0400000000 1.1969410181 0.5899062911 1.5112450123 0.1333112594 0.0149050000 1271802365 0 402718720 -0.0906802341 -0.0277379826 0.2853672504 1403 56.0800000000 1.2019947767 0.5903425623 1.5112450123 0.1332662751 0.0163330000 1271804613 0 402718720 -0.0906710923 -0.0272779986 0.2856728435 1404 56.1200000000 1.2084684372 0.5907828229 1.5112450123 0.1332221947 0.0162900000 1271806861 0 402718720 -0.0909833089 -0.0273198821 0.2860296667 1405 56.1600000000 1.2146098614 0.5912268279 1.5112450123 0.1331781798 0.0173140000 1271809109 0 402718720 -0.0907630771 -0.0271729510 0.2863712013 1406 56.2000000000 1.2298914194 0.5916810702 1.5112450123 0.1331491938 0.0333960000 1271811357 0 402718720 -0.0911062285 -0.0267519187 0.2875881493 1407 56.2400000000 1.2383310795 0.5921406650 1.5112450123 0.1331052254 0.0309230000 1271813605 0 402718720 -0.0912330896 -0.0264100190 0.2881624103 1408 56.2800000000 1.2466427088 0.5926055102 1.5112450123 0.1330608436 0.0226560000 1271815853 0 402718720 -0.0906381458 -0.0258912407 0.2885480225 1409 56.3200000000 1.2538609505 0.5930748186 1.5112450123 0.1330173712 0.0215740000 1271818101 0 402718720 -0.0903053731 -0.0254130252 0.2892626822 1410 56.3600000000 1.2632546425 0.5935501234 1.5112450123 0.1329756598 0.0205350000 1271820349 0 402718720 -0.0907823071 -0.0255746767 0.2897109687 1411 56.4000000000 1.2720057964 0.5940309566 1.5112450123 0.1329321664 0.1274700000 1280442633 0 402718720 -0.0902196318 -0.0250776764 0.2902630568 1412 56.4400000000 1.2783678770 0.5945156145 1.5112450123 0.1328879761 0.0129850000 1280446201 0 402718720 -0.0895787477 -0.0234516505 0.2918967605 1413 56.4800000000 1.2879940271 0.5950063989 1.5112450123 0.1328432201 0.0134360000 1280448449 0 402718720 -0.0897521079 -0.0232271720 0.2924900055 1414 56.5200000000 1.2974177599 0.5955031538 1.5112450123 0.1327978049 0.0174820000 1280450697 0 402718720 -0.0901496708 -0.0229848009 0.2931301296 1415 56.5600000000 1.3058938980 0.5960051967 1.5112450123 0.1327518206 0.0241400000 1280452945 0 402718720 -0.0896930099 -0.0219162218 0.2933522761 1416 56.6000000000 1.3142198324 0.5965124105 1.5112450123 0.1327070646 0.0607630000 1280455193 0 402718720 -0.0907465518 -0.0225606505 0.2943988740 1417 56.6400000000 1.3227527142 0.5970249301 1.5112450123 0.1326626006 0.0243040000 1280457441 0 402718720 -0.0911955237 -0.0224913806 0.2936904430 1418 56.6800000000 1.3302104473 0.5975419862 1.5112450123 0.1326183380 0.0226170000 1280459689 0 402718720 -0.0915854648 -0.0223773308 0.2942210734 1419 56.7200000000 1.3370910883 0.5980631624 1.5112450123 0.1325750911 0.0211220000 1280461937 0 402718720 -0.0929357335 -0.0227266401 0.2953628898 1420 56.7600000000 1.3446316719 0.5985889149 1.5112450123 0.1325316170 0.0202670000 1280464185 0 402718720 -0.0927892551 -0.0228880513 0.2957028747 1421 56.8000000000 1.3512336016 0.5991185733 1.5112450123 0.1324878649 0.0182830000 1280466433 0 402718720 -0.0932255089 -0.0227830037 0.2960909903 1422 56.8400000000 1.3575420380 0.5996519232 1.5112450123 0.1324438228 0.0181470000 1280468681 0 402718720 -0.0936360583 -0.0223221574 0.2963560820 1423 56.8800000000 1.3643056154 0.6001892764 1.5112450123 0.1324000911 0.0172240000 1280470929 0 402718720 -0.0950782150 -0.0229476634 0.2967225611 1424 56.9200000000 1.3716578484 0.6007310381 1.5112450123 0.1323558090 0.0180580000 1280473177 0 402718720 -0.0955893919 -0.0227552429 0.2967341840 1425 56.9600000000 1.3777314425 0.6012763015 1.5112450123 0.1323113946 0.1324940000 1289101673 0 402718720 -0.0957926884 -0.0227160882 0.2972389758 1426 57.0000000000 1.3858177662 0.6018264709 1.5112450123 0.1322664746 0.0125000000 1289105241 0 402718720 -0.0927248895 -0.0242624898 0.2964464128 1427 57.0400000000 1.3930803537 0.6023809585 1.5112450123 0.1322229628 0.0129330000 1289107489 0 402718720 -0.0933414623 -0.0241239704 0.2969045043 1428 57.0800000000 1.4008983374 0.6029401443 1.5112450123 0.1321791818 0.0236160000 1289109737 0 402718720 -0.0939011797 -0.0243177433 0.2975206375 1429 57.1200000000 1.4083468914 0.6035037600 1.5112450123 0.1321348913 0.0240290000 1289111985 0 402718720 -0.0945015475 -0.0246088263 0.2977003455 1430 57.1600000000 1.4162219763 0.6040720944 1.5112450123 0.1320908604 0.0523180000 1289114233 0 402718720 -0.0943907350 -0.0243109874 0.2978387773 1431 57.2000000000 1.4238642454 0.6046449750 1.5112450123 0.1320473780 0.0235340000 1289116481 0 402718720 -0.0950187892 -0.0241447631 0.2982976139 1432 57.2400000000 1.4309747219 0.6052220209 1.5112450123 0.1320038165 0.0211820000 1289118729 0 402718720 -0.0953744873 -0.0242554732 0.2987236977 1433 57.2800000000 1.4390249252 0.6058038792 1.5112450123 0.1319607078 0.0203000000 1289120977 0 402718720 -0.0961318612 -0.0244614556 0.2989893854 1434 57.3200000000 1.4467937946 0.6063903436 1.5112450123 0.1319191684 0.0192170000 1289123225 0 402718720 -0.0961232483 -0.0239441004 0.2994437218 1435 57.3600000000 1.4547960758 0.6069815671 1.5112450123 0.1318782740 0.0892590000 1297743573 0 402718720 -0.0970855951 -0.0241713077 0.2996143997 1436 57.4000000000 1.4619662762 0.6075769603 1.5112450123 0.1318371550 0.0125380000 1297747141 0 402718720 -0.0978863314 -0.0233360920 0.3002032340 1437 57.4400000000 1.4715199471 0.6081781733 1.5112450123 0.1317967942 0.0167390000 1297749389 0 402718720 -0.0985056683 -0.0235517547 0.3009616435 1438 57.4800000000 1.4810849428 0.6087852016 1.5112450123 0.1317553065 0.0210860000 1297751637 0 402718720 -0.0999133140 -0.0236947462 0.3008553386 1439 57.5200000000 1.4911094904 0.6093983526 1.5112450123 0.1317138036 0.0222670000 1297753885 0 402718720 -0.1010556147 -0.0237904005 0.3007054925 1440 57.5600000000 1.4998329878 0.6100167100 1.5112450123 0.1316717241 0.0519230000 1297756133 0 402718720 -0.1019257605 -0.0244232845 0.3012927473 1441 57.6000000000 1.5080864429 0.6106399367 1.5112450123 0.1316297471 0.0225510000 1297758381 0 402718720 -0.1029057205 -0.0245334450 0.3013921678 1442 57.6400000000 1.5157142878 0.6112675889 1.5157142878 0.1315866817 0.0209350000 1297760629 0 402718720 -0.1040074751 -0.0247187093 0.3016113639 1443 57.6800000000 1.5238285065 0.6118999942 1.5238285065 0.1315436508 0.1327300000 1306380005 0 402718720 -0.1046354473 -0.0247092936 0.3018237352 1444 57.7200000000 1.5260025263 0.6125330292 1.5260025263 0.1315005645 0.0120660000 1306383573 0 402718720 -0.1026455536 -0.0232258942 0.3054951429 1445 57.7600000000 1.5335865021 0.6131704364 1.5335865021 0.1314574964 0.0114920000 1306385821 0 402718720 -0.1033591777 -0.0233378168 0.3057840168 1446 57.8000000000 1.5413157940 0.6138123074 1.5413157940 0.1314137453 0.0138800000 1306388069 0 402718720 -0.1045681983 -0.0238191523 0.3057360351 1447 57.8400000000 1.5467667580 0.6144570582 1.5467667580 0.1313695650 0.0133470000 1306390317 0 402718720 -0.1047395691 -0.0236601830 0.3059288263 1448 57.8800000000 1.5522887707 0.6151047320 1.5522887707 0.1313255452 0.0186570000 1306392565 0 402718720 -0.1053162217 -0.0239090379 0.3062309623 1449 57.9200000000 1.5581624508 0.6157555655 1.5581624508 0.1312820409 0.0210140000 1306394813 0 402718720 -0.1057331339 -0.0239707753 0.3063381910 1450 57.9600000000 1.5640230179 0.6164095431 1.5640230179 0.1312396630 0.0952590000 1315020661 0 402718720 -0.1063979343 -0.0240666308 0.3065314591 1451 58.0000000000 1.5722175837 0.6170682667 1.5722175837 0.1311972353 0.0112340000 1315024229 0 402718720 -0.1099447310 -0.0261843782 0.3046506941 1452 58.0400000000 1.5784496069 0.6177303751 1.5784496069 0.1311544906 0.0112290000 1315026477 0 402718720 -0.1101707518 -0.0262243543 0.3050003350 1453 58.0800000000 1.5848195553 0.6183959561 1.5848195553 0.1311114742 0.0112100000 1315028725 0 402718720 -0.1101922020 -0.0262290277 0.3051664233 1454 58.1200000000 1.5893836021 0.6190637605 1.5893836021 0.1310674872 0.0112240000 1315030973 0 402718720 -0.1100802943 -0.0263920408 0.3055683076 1455 58.1600000000 1.5932030678 0.6197332721 1.5932030678 0.1310234987 0.0426040000 1315033221 0 402718720 -0.1097940132 -0.0260312576 0.3060135245 1456 58.2000000000 1.5961277485 0.6204038727 1.5961277485 0.1309796269 0.0265930000 1315035469 0 402718720 -0.1092870012 -0.0260165706 0.3063619733 1457 58.2400000000 1.3482518196 0.6209034252 1.5961277485 0.1595489394 0.0913350000 1329504369 0 402718720 -0.5922254920 0.4225658476 0.4505787194 1458 58.2800000000 1.3171674013 0.6213809725 1.5961277485 0.1595022647 0.0316320000 1323656081 0 402718720 -0.5774794221 0.4155079126 0.4899254739 1459 58.3200000000 1.5169500113 0.6219947963 1.5961277485 0.1620070490 0.0226510000 1334424153 0 402718720 -0.0681755990 0.1179848611 0.3250837028 1460 58.3600000000 1.5213434696 0.6226107886 1.5961277485 0.1619515987 0.0264840000 1323660545 0 402718720 -0.0689621866 0.1158327609 0.3244827092 1461 58.4000000000 1.5270240307 0.6232298257 1.5961277485 0.1618962412 0.0277560000 1323662793 0 402718720 -0.0723697767 0.1127312481 0.3245801926 1462 58.4400000000 1.5325782299 0.6238518150 1.5961277485 0.1618410080 0.0275620000 1323665041 0 402718720 -0.0757417902 0.1095964983 0.3248641491 1463 58.4800000000 1.5367101431 0.6244757784 1.5961277485 0.1617859993 0.0277610000 1323667289 0 402718720 -0.0798318312 0.1060310006 0.3260158598 1464 58.5200000000 1.5412697792 0.6251020038 1.5961277485 0.1617312642 0.0282360000 1323669537 0 402718720 -0.0850761533 0.1019874141 0.3277560771 1465 58.5600000000 1.5468553305 0.6257311869 1.5961277485 0.1616788126 0.0263920000 1323671785 0 402718720 -0.0951672792 0.0946924910 0.3301729858 1466 58.6000000000 1.5510803461 0.6263623937 1.5961277485 0.1616252390 0.0296770000 1323674033 0 402718720 -0.1032213122 0.0887867063 0.3327124417 1467 58.6400000000 1.5529137850 0.6269939898 1.5961277485 0.1615711757 0.0299300000 1323676281 0 402718720 -0.1096976846 0.0848861486 0.3382610381 1468 58.6800000000 1.5509783030 0.6276234069 1.5961277485 0.1615167133 0.0304480000 1323678529 0 402718720 -0.1139896810 0.0822538957 0.3460113704 1469 58.7200000000 1.5484707355 0.6282502600 1.5961277485 0.1614625749 0.0308710000 1323680777 0 402718720 -0.1195640564 0.0808002427 0.3535816967 1470 58.7600000000 1.5443439484 0.6288734530 1.5961277485 0.1614081788 0.0310910000 1323683025 0 402718720 -0.1241156235 0.0810158029 0.3628628254 1471 58.8000000000 1.5405428410 0.6294932147 1.5961277485 0.1613546031 0.0321880000 1327078461 0 402718720 -0.1307668686 0.0802762061 0.3730981052 1472 58.8400000000 1.6749625206 0.6302034520 1.6749625206 0.1722922541 0.0297170000 1334455093 0 402718720 -0.0178087875 -0.1656389236 0.3893078566 1473 58.8800000000 1.6797730923 0.6309159908 1.6797730923 0.1722337857 0.0267020000 1328607645 0 402718720 -0.0204084050 -0.1704191267 0.3911102712 1474 58.9200000000 1.6813774109 0.6316286512 1.6813774109 0.1721756496 0.0103750000 1328608573 0 402718720 -0.0196133386 -0.1703778952 0.3917635381 1475 58.9600000000 1.6828222275 0.6323413248 1.6828222275 0.1721175153 0.0349260000 1328610821 0 402718720 -0.0202056058 -0.1691210121 0.3915477693 1476 59.0000000000 1.6854723692 0.6330548282 1.6854723692 0.1720593993 0.0168330000 1328613069 0 402718720 -0.0198485665 -0.1698298901 0.3919690251 1477 59.0400000000 1.6882517338 0.6337692472 1.6882517338 0.1720014022 0.0124740000 1328615317 0 402718720 -0.0204609819 -0.1696297228 0.3919965327 1478 59.0800000000 1.6906912327 0.6344843501 1.6906912327 0.1719432883 0.0180920000 1328617565 0 402718720 -0.0205945186 -0.1684496850 0.3916453719 1479 59.1200000000 1.6947836876 0.6352012529 1.6947836876 0.1718857975 0.0134400000 1328619813 0 402718720 -0.0200200751 -0.1689672321 0.3922564983 1480 59.1600000000 1.6966875792 0.6359184734 1.6966875792 0.1718277905 0.0141700000 1328622061 0 402718720 -0.0192325097 -0.1682937890 0.3923691511 1481 59.2000000000 1.6972658634 0.6366351158 1.6972658634 0.1717698428 0.0209710000 1328624309 0 402718720 -0.0193198305 -0.1649689674 0.3908200860 1482 59.2400000000 1.6993125677 0.6373521721 1.6993125677 0.1717119791 0.0211220000 1328626557 0 402718720 -0.0212888625 -0.1632712781 0.3900347948 1483 59.2800000000 1.7024295330 0.6380703632 1.7024295330 0.1716547091 0.0165500000 1328628805 0 402718720 -0.0205968209 -0.1683680415 0.3922958970 1484 59.3200000000 1.7029796839 0.6387879571 1.7029796839 0.1715971707 0.0165650000 1328631053 0 402718720 -0.0201760381 -0.1687061042 0.3935965598 1485 59.3600000000 1.7035862207 0.6395049929 1.7035862207 0.1715395206 0.0174350000 1328633301 0 402718720 -0.0201241989 -0.1674442291 0.3927657902 1486 59.4000000000 1.7052787542 0.6402222027 1.7052787542 0.1714818811 0.0186180000 1328635549 0 402718720 -0.0198383890 -0.1667095125 0.3921452761 1487 59.4400000000 1.7066667080 0.6409393813 1.7066667080 0.1714244434 0.0171960000 1328637797 0 402718720 -0.0205320660 -0.1673934907 0.3928202391 1488 59.4800000000 1.7080713511 0.6416565399 1.7080713511 0.1713670783 0.0179510000 1328640045 0 402718720 -0.0208467916 -0.1680058092 0.3936322331 1489 59.5200000000 1.7093821764 0.6423736155 1.7093821764 0.1713096548 0.0182890000 1328642293 0 402718720 -0.0210438520 -0.1681980491 0.3937443197 1490 59.5600000000 1.7116823196 0.6430912724 1.7116823196 0.1712523264 0.0178970000 1328644541 0 402718720 -0.0207146276 -0.1674800366 0.3933101892 1491 59.6000000000 1.7142038345 0.6438096577 1.7142038345 0.1711950845 0.0166020000 1328646789 0 402718720 -0.0211743843 -0.1686836183 0.3937872946 1492 59.6400000000 1.7158901691 0.6445282103 1.7158901691 0.1711377527 0.0165620000 1328649037 0 402718720 -0.0211093370 -0.1689358354 0.3943584263 1493 59.6800000000 1.7190140486 0.6452478928 1.7190140486 0.1710804295 0.0467560000 1328651285 0 402718720 -0.0212997608 -0.1689283699 0.3938453496 1494 59.7200000000 1.7201437950 0.6459673679 1.7201437950 0.1710231962 0.0182850000 1328653533 0 402718720 -0.0211259145 -0.1688206345 0.3943243027 1495 59.7600000000 1.7220400572 0.6466871490 1.7220400572 0.1709661792 0.0157710000 1328655781 0 402718720 -0.0215362906 -0.1691244394 0.3944994509 1496 59.8000000000 1.7241250277 0.6474073615 1.7241250277 0.1709094060 0.0152870000 1328658029 0 402718720 -0.0216257051 -0.1693424284 0.3949416876 1497 59.8400000000 1.7263547182 0.6481281012 1.7263547182 0.1708525617 0.0158760000 1328660277 0 402718720 -0.0218326151 -0.1702186763 0.3958205879 1498 59.8800000000 1.7290211916 0.6488496587 1.7290211916 0.1707955384 0.0154080000 1328662525 0 402718720 -0.0220198259 -0.1696553677 0.3945903778 1499 59.9200000000 1.7310566902 0.6495716113 1.7310566902 0.1707386994 0.0156100000 1328664773 0 402718720 -0.0219819266 -0.1699535847 0.3947557211 1500 59.9600000000 1.7317472696 0.6502930618 1.7317472696 0.1706818992 0.0156520000 1328667021 0 402718720 -0.0224331655 -0.1701512188 0.3952075243 1501 60.0000000000 1.7323788404 0.6510139717 1.7323788404 0.1706252245 0.2373260000 1332374897 0 402718720 -0.0233493969 -0.1685482115 0.3940472305 1502 60.0400000000 1.7497210503 0.6517454677 1.7497210503 0.1705699737 0.0185850000 1332378465 0 402718720 -0.0133633409 -0.1993748248 0.3994930089 1503 60.0800000000 1.7499855757 0.6524761664 1.7499855757 0.1705135169 0.0106540000 1332380713 0 402718720 -0.0133158788 -0.1978540123 0.3987109363 1504 60.1200000000 1.7510709763 0.6532066151 1.7510709763 0.1704571176 0.0107740000 1332382961 0 402718720 -0.0140776131 -0.1983893514 0.3988755941 1505 60.1600000000 1.7511335611 0.6539361346 1.7511335611 0.1704008572 0.0108320000 1332385209 0 402718720 -0.0141410045 -0.1980853081 0.3986778855 1506 60.2000000000 1.6657352448 0.6546079800 1.7511335611 0.1710763898 0.0366870000 1343154785 0 402718720 -0.0114668524 -0.0095809009 0.3552963734 1507 60.2400000000 1.6614851952 0.6552761135 1.7511335611 0.1710206033 0.0310030000 1332388353 0 402718720 0.0021076787 -0.0086804833 0.3589889407 1508 60.2800000000 1.6591435671 0.6559418081 1.7511335611 0.1709643295 0.0268790000 1332390601 0 402718720 0.0147755751 -0.0055958508 0.3611108363 1509 60.3200000000 1.6570539474 0.6566052356 1.7511335611 0.1709078734 0.0237480000 1332392849 0 402718720 0.0210684035 -0.0039124279 0.3636974096 1510 60.3600000000 1.6589218378 0.6572690215 1.7511335611 0.1708513054 0.0234470000 1332395097 0 402718720 0.0237233769 -0.0032064414 0.3637164831 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:16:48 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0111460000 86835764 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0037849296 0.0018924648 0.0037849296 0.0060263164 0.0473430000 103191817 0 402718720 0.0025480420 0.0031959305 0.0002693544 3 0.0800000000 0.0076568876 0.0038139391 0.0076568876 0.0055899764 0.0313710000 106463729 0 402718720 0.0040668268 0.0040879590 0.0003226431 4 0.1200000000 0.0019599893 0.0033504516 0.0076568876 0.0063305545 0.0261610000 106466377 0 402718720 0.0003446783 0.0003025839 -0.0001039995 5 0.1600000000 0.0011969473 0.0029197508 0.0076568876 0.0055538909 0.0285840000 106469041 0 402718720 0.0002654626 -0.0001555826 0.0000482072 6 0.2000000000 0.0019221603 0.0027534857 0.0076568876 0.0051342035 0.0230100000 106472089 0 402718720 -0.0000124036 -0.0004208818 -0.0002705478 7 0.2400000000 0.0020356860 0.0026509429 0.0076568876 0.0052573144 0.0429830000 106474337 0 402718720 -0.0006841324 -0.0042872936 -0.0002662277 8 0.2800000000 0.0004976149 0.0023817769 0.0076568876 0.0050463494 0.0245790000 106476585 0 402718720 -0.0002614823 -0.0013510506 -0.0000265006 9 0.3200000000 0.0008822109 0.0022151584 0.0076568876 0.0047471232 0.0254610000 106479665 0 402718720 0.0000199236 -0.0002946719 -0.0001229336 10 0.3600000000 0.0012654619 0.0021201888 0.0076568876 0.0044918190 0.0247060000 106483513 0 402718720 -0.0000967789 -0.0006893479 -0.0001435844 11 0.4000000000 0.0008638793 0.0020059788 0.0076568876 0.0042702043 0.0239490000 106485761 0 402718720 0.0000038373 -0.0004640371 -0.0000634342 12 0.4400000000 0.0002339298 0.0018583081 0.0076568876 0.0040867773 0.0248470000 106488009 0 402718720 0.0000231531 -0.0002852500 0.0000549865 13 0.4800000000 0.0003751785 0.0017442212 0.0076568876 0.0039278292 0.0224780000 106490257 0 402718720 0.0002109970 -0.0001441989 0.0002467537 14 0.5200000000 0.0001391804 0.0016295754 0.0076568876 0.0038205790 0.0230610000 106492505 0 402718720 0.0001644095 0.0001758823 0.0002705961 15 0.5600000000 0.0004124852 0.0015484361 0.0076568876 0.0037626015 0.0244390000 106494753 0 402718720 0.0003981159 -0.0000354972 0.0003574994 16 0.6000000000 0.0048976266 0.0017577605 0.0076568876 0.0040901534 0.0385600000 106497001 0 402718720 0.0031973498 0.0041113524 0.0006565518 17 0.6400000000 0.0048224498 0.0019380363 0.0076568876 0.0039622620 0.0291420000 106500913 0 402718720 0.0028835321 0.0040163929 0.0006387165 18 0.6800000000 0.0069809640 0.0022181990 0.0076568876 0.0038877483 0.0291510000 106506361 0 402718720 0.0044615953 0.0048372033 0.0006310178 19 0.7200000000 0.0067060362 0.0024544009 0.0076568876 0.0038468797 0.0332390000 106508609 0 402718720 0.0043834760 0.0045648073 0.0006131558 20 0.7600000000 0.0009629477 0.0023798283 0.0076568876 0.0044025393 0.0247910000 106510857 0 402718720 0.0003945441 -0.0000750638 0.0002806116 21 0.8000000000 0.0010078183 0.0023144945 0.0076568876 0.0043927432 0.0571460000 106513105 0 402718720 0.0000389596 -0.0001004536 0.0002872839 22 0.8400000000 0.0012701012 0.0022670220 0.0076568876 0.0043266110 0.0242090000 106515353 0 402718720 0.0005438842 0.0002467624 0.0003408244 23 0.8800000000 0.0014065572 0.0022296105 0.0076568876 0.0042536338 0.0235210000 106517601 0 402718720 0.0004238894 0.0001534630 0.0002430393 24 0.9200000000 0.0009448408 0.0021760784 0.0076568876 0.0041639638 0.0245800000 106519849 0 402718720 0.0001552277 -0.0000756123 0.0001892569 25 0.9600000000 0.0008451883 0.0021228428 0.0076568876 0.0040772548 0.0263370000 106522097 0 402718720 -0.0000215771 -0.0002459663 0.0001463919 26 1.0000000000 0.0005091472 0.0020607776 0.0076568876 0.0039980688 0.0256670000 106524345 0 402718720 -0.0000052450 -0.0003447931 0.0000852767 27 1.0400000000 0.0006894248 0.0020099868 0.0076568876 0.0039242444 0.0251080000 106526593 0 402718720 -0.0000652036 -0.0003749468 0.0000991684 28 1.0800000000 0.0008619934 0.0019689870 0.0076568876 0.0038644231 0.0251280000 106528841 0 402718720 -0.0000559759 -0.0003162466 0.0001353753 29 1.1200000000 0.0009581841 0.0019341317 0.0076568876 0.0037986785 0.0262470000 106531089 0 402718720 -0.0002123440 -0.0003642494 0.0001600456 30 1.1600000000 0.0008834552 0.0018991092 0.0076568876 0.0037437287 0.0255960000 106533337 0 402718720 -0.0000828248 -0.0002380635 0.0001162662 31 1.2000000000 0.0009700008 0.0018691379 0.0076568876 0.0036955797 0.0260590000 106535585 0 402718720 -0.0001835176 -0.0000550395 0.0000607214 32 1.2400000000 0.0015137489 0.0018580320 0.0076568876 0.0036388381 0.0236700000 106537833 0 402718720 -0.0000240980 -0.0000363863 0.0001714740 33 1.2800000000 0.0012664216 0.0018401045 0.0076568876 0.0036052122 0.0256890000 106543409 0 402718720 -0.0003956624 -0.0002133921 0.0001680388 34 1.3200000000 0.0016713749 0.0018351418 0.0076568876 0.0035638175 0.0622480000 106552057 0 402718720 -0.0005152764 -0.0002382026 0.0002611775 35 1.3600000000 0.0021231601 0.0018433709 0.0076568876 0.0035226656 0.0257030000 106554305 0 402718720 -0.0006759297 -0.0004865177 0.0001983840 36 1.4000000000 0.0023181769 0.0018565600 0.0076568876 0.0034748421 0.0259950000 106556553 0 402718720 -0.0006912968 -0.0008687755 0.0002178592 37 1.4400000000 0.0058410405 0.0019642486 0.0076568876 0.0037879950 0.0384600000 106558801 0 402718720 -0.0015587214 -0.0070732892 0.0003603691 38 1.4800000000 0.0051817386 0.0020489194 0.0076568876 0.0037383631 0.0295150000 106561049 0 402718720 -0.0020639275 -0.0070456294 0.0000854978 39 1.5200000000 0.0031455655 0.0020770385 0.0076568876 0.0040564723 0.0275340000 106563297 0 402718720 -0.0011696139 -0.0016123506 0.0003090257 40 1.5600000000 0.0090065282 0.0022502758 0.0090065282 0.0044620948 0.0324010000 106565545 0 402718720 0.0046769097 -0.0057203318 0.0004839569 41 1.6000000000 0.0032668938 0.0022750714 0.0090065282 0.0044802866 0.0232850000 106567793 0 402718720 -0.0011848289 -0.0008186619 0.0008062566 42 1.6400000000 0.0035716663 0.0023059427 0.0090065282 0.0044825234 0.0239430000 106570041 0 402718720 -0.0015010642 -0.0009887316 0.0008571219 43 1.6800000000 0.0045221797 0.0023574831 0.0090065282 0.0044667749 0.0245080000 106572289 0 402718720 -0.0010663477 -0.0002346615 0.0012416781 44 1.7200000000 0.0039007515 0.0023925573 0.0090065282 0.0044217336 0.0240650000 106574537 0 402718720 -0.0019679833 -0.0005108605 0.0016393828 45 1.7600000000 0.0043049864 0.0024350558 0.0090065282 0.0043836355 0.0238840000 106576785 0 402718720 -0.0019394887 -0.0007878960 0.0020493697 46 1.8000000000 0.0047884411 0.0024862163 0.0090065282 0.0044244071 0.0289670000 106579033 0 402718720 -0.0024243037 -0.0006660448 0.0023703419 47 1.8400000000 0.0049116448 0.0025378212 0.0090065282 0.0044949388 0.0542150000 106581281 0 402718720 -0.0024007449 -0.0011162291 0.0029240593 48 1.8800000000 0.0056569115 0.0026028022 0.0090065282 0.0045724685 0.0272440000 106583529 0 402718720 -0.0026136923 -0.0005056791 0.0036493444 49 1.9200000000 0.0070775291 0.0026941232 0.0090065282 0.0047158319 0.0259600000 106585777 0 402718720 -0.0020058299 -0.0005130537 0.0043394389 50 1.9600000000 0.0070908139 0.0027820570 0.0090065282 0.0049209612 0.0258750000 106588025 0 402718720 -0.0023850333 -0.0010809792 0.0052022319 51 2.0000000000 0.0076509188 0.0028775249 0.0090065282 0.0050231705 0.0474080000 118932225 0 402718720 -0.0024308655 -0.0006962031 0.0061464906 52 2.0400000000 0.0081672389 0.0029792501 0.0090065282 0.0051252283 0.0203590000 122594081 0 402718720 -0.0021432973 -0.0006172564 0.0071999608 53 2.0800000000 0.0091421856 0.0030955319 0.0091421856 0.0051657245 0.0196870000 125788521 0 402718720 -0.0024467099 -0.0006478986 0.0081716850 54 2.1200000000 0.0100926384 0.0032251080 0.0100926384 0.0052087899 0.0208070000 125790769 0 402718720 -0.0019831227 -0.0005388754 0.0091796815 55 2.1600000000 0.0109094577 0.0033648234 0.0109094577 0.0051964313 0.0229090000 125793017 0 402718720 -0.0019923742 -0.0001364443 0.0105195241 56 2.2000000000 0.0124572376 0.0035271880 0.0124572376 0.0052157488 0.0275650000 125795265 0 402718720 -0.0048149419 0.0012562707 0.0118119223 57 2.2400000000 0.0129865101 0.0036931410 0.0129865101 0.0051817598 0.0219860000 125797513 0 402718720 -0.0019187012 0.0008022435 0.0131165115 58 2.2800000000 0.0143126836 0.0038762366 0.0143126836 0.0052246730 0.0233430000 125799761 0 402718720 -0.0019175516 0.0022002861 0.0145683894 59 2.3200000000 0.0155828753 0.0040746542 0.0155828753 0.0052596132 0.0179220000 125802009 0 402718720 0.0006259107 0.0026106178 0.0161926076 60 2.3600000000 0.0184659045 0.0043145083 0.0184659045 0.0055341072 0.0208440000 125804257 0 402718720 0.0014522414 0.0048991875 0.0178677011 61 2.4000000000 0.0196708199 0.0045662512 0.0196708199 0.0057522208 0.0496340000 125806505 0 402718720 0.0014111963 0.0051158099 0.0193284452 62 2.4400000000 0.0217972249 0.0048441701 0.0217972249 0.0059960895 0.0210170000 125808753 0 402718720 0.0017704405 0.0067472393 0.0209703054 63 2.4800000000 0.0228611045 0.0051301532 0.0228611045 0.0061721304 0.0214130000 125811001 0 402718720 0.0012599312 0.0060553649 0.0224384982 64 2.5200000000 0.0229464266 0.0054085324 0.0229464266 0.0063022678 0.0202190000 125813249 0 402718720 0.0025699062 0.0041715675 0.0238646995 65 2.5600000000 0.0251917168 0.0057128891 0.0251917168 0.0065016048 0.0245610000 125822153 0 402718720 0.0038108211 0.0064006275 0.0257728789 66 2.6000000000 0.0284163672 0.0060568812 0.0284163672 0.0068112788 0.0247520000 125837201 0 402718720 0.0056159873 0.0094692782 0.0274741873 67 2.6400000000 0.0288588237 0.0063972087 0.0288588237 0.0071033020 0.0259300000 125839449 0 402718720 0.0059422688 0.0091384724 0.0290361680 68 2.6800000000 0.0311242659 0.0067608419 0.0311242659 0.0074547756 0.0277590000 125841697 0 402718720 0.0060855146 0.0115288198 0.0307231825 69 2.7200000000 0.0330043733 0.0071411829 0.0330043733 0.0076325729 0.0268300000 125843945 0 402718720 0.0079599675 0.0124298865 0.0323749296 70 2.7600000000 0.0348090082 0.0075364376 0.0348090082 0.0077725922 0.0262730000 125846193 0 402718720 0.0076278117 0.0127019305 0.0337431729 71 2.8000000000 0.0363800526 0.0079426857 0.0363800526 0.0077818620 0.0261730000 125848441 0 402718720 0.0092469351 0.0145130008 0.0355113596 72 2.8400000000 0.0364834666 0.0083390854 0.0364834666 0.0077741785 0.0703770000 144687209 0 402718720 0.0100562489 0.0125465468 0.0368449204 73 2.8800000000 0.0381912813 0.0087480196 0.0381912813 0.0077793381 0.0190960000 148348665 0 402718720 0.0093650874 0.0120041482 0.0376899391 74 2.9200000000 0.0395993330 0.0091649293 0.0395993330 0.0077821448 0.0691460000 151543105 0 402718720 0.0111173289 0.0140189026 0.0395485722 75 2.9600000000 0.0407506227 0.0095860718 0.0407506227 0.0078454181 0.0216670000 151545353 0 402718720 0.0114819491 0.0139789646 0.0408243574 76 3.0000000000 0.0429146960 0.0100246064 0.0429146960 0.0080063579 0.0229830000 151547601 0 402718720 0.0126255946 0.0153878760 0.0422740579 77 3.0400000000 0.0443827249 0.0104708157 0.0443827249 0.0081661003 0.0215050000 151549849 0 402718720 0.0130320359 0.0152908098 0.0434885845 78 3.0800000000 0.0457401425 0.0109229866 0.0457401425 0.0083661926 0.0185390000 151552097 0 402718720 0.0134552652 0.0160641354 0.0449945033 79 3.1200000000 0.0469978452 0.0113796303 0.0469978452 0.0085378611 0.0188500000 151554345 0 402718720 0.0142290033 0.0167691540 0.0464845821 80 3.1600000000 0.0485647395 0.0118444442 0.0485647395 0.0086695479 0.0183120000 151556593 0 402718720 0.0146634206 0.0167948846 0.0477211624 81 3.2000000000 0.0501934923 0.0123178892 0.0501934923 0.0088172768 0.0192500000 151558841 0 402718720 0.0151042165 0.0175215695 0.0491698496 82 3.2400000000 0.0512464046 0.0127926272 0.0512464046 0.0089588732 0.0213370000 151561089 0 402718720 0.0159074441 0.0178076141 0.0506170057 83 3.2800000000 0.0529992245 0.0132770441 0.0529992245 0.0091389390 0.0728580000 163872477 0 402718720 0.0162851587 0.0182972364 0.0520468429 84 3.3200000000 0.0546337068 0.0137693853 0.0546337068 0.0092160136 0.0194740000 167534749 0 402718720 0.0172303505 0.0195083525 0.0534750335 85 3.3600000000 0.0560037270 0.0142662599 0.0560037270 0.0092746490 0.0271030000 170729189 0 402718720 0.0180095807 0.0205997266 0.0549422465 86 3.4000000000 0.0574731044 0.0147686651 0.0574731044 0.0093270510 0.0188560000 170731437 0 402718720 0.0181056857 0.0211306419 0.0563607402 87 3.4400000000 0.0584173091 0.0152703736 0.0584173091 0.0093783753 0.0176020000 170733685 0 402718720 0.0189305041 0.0209082589 0.0578115582 88 3.4800000000 0.0606697612 0.0157862757 0.0606697612 0.0094737481 0.0507320000 170735933 0 402718720 0.0183585491 0.0221790653 0.0593178310 89 3.5200000000 0.0619015768 0.0163044252 0.0619015768 0.0095444218 0.0209960000 170738181 0 402718720 0.0191742349 0.0227577072 0.0610473268 90 3.5600000000 0.0632807985 0.0168263849 0.0632807985 0.0096426723 0.0182720000 170740429 0 402718720 0.0195806678 0.0232837703 0.0626358315 91 3.6000000000 0.0651238561 0.0173571263 0.0651238561 0.0097741712 0.0190250000 170742677 0 402718720 0.0201288369 0.0238380749 0.0643304363 92 3.6400000000 0.0664597452 0.0178908505 0.0664597452 0.0098493231 0.0167310000 170744925 0 402718720 0.0205779672 0.0238896571 0.0660446212 93 3.6800000000 0.0690498054 0.0184409467 0.0690498054 0.0098624127 0.0292820000 170747173 0 402718720 0.0207122639 0.0264444966 0.0680217966 94 3.7200000000 0.0696183667 0.0189853874 0.0696183667 0.0098366147 0.0201490000 170749421 0 402718720 0.0213155169 0.0251322426 0.0694371089 95 3.7600000000 0.0710759535 0.0195337091 0.0710759535 0.0098186508 0.0590480000 183058149 0 402718720 0.0221950635 0.0257695094 0.0712575018 96 3.8000000000 0.0740377828 0.0201014599 0.0740377828 0.0098596162 0.0322980000 186719605 0 402718720 0.0219104700 0.0287551619 0.0731653795 97 3.8400000000 0.0740168393 0.0206572886 0.0740377828 0.0099113811 0.0240620000 189914045 0 402718720 0.0250886772 0.0293026883 0.0753989071 98 3.8800000000 0.0756695792 0.0212186385 0.0756695792 0.0100398311 0.0182090000 189916293 0 402718720 0.0246382616 0.0293631330 0.0769214630 99 3.9200000000 0.0766761228 0.0217788151 0.0766761228 0.0101359116 0.0180430000 189918541 0 402718720 0.0261022877 0.0292836353 0.0787311122 100 3.9600000000 0.0805611685 0.0223666386 0.0805611685 0.0103033101 0.0395560000 189920789 0 402718720 0.0232062042 0.0338869281 0.0804433674 101 4.0000000000 0.0799353868 0.0229366262 0.0805611685 0.0103338108 0.0187280000 189923037 0 402718720 0.0249545854 0.0313792527 0.0822068974 102 4.0400000000 0.0814442784 0.0235102306 0.0814442784 0.0103419995 0.0164480000 189925285 0 402718720 0.0254691280 0.0317170657 0.0837859958 103 4.0800000000 0.0828662813 0.0240865030 0.0828662813 0.0103510659 0.0149070000 189927533 0 402718720 0.0253991410 0.0329590589 0.0855951607 104 4.1200000000 0.0844037011 0.0246664760 0.0844037011 0.0103537978 0.0169280000 189929781 0 402718720 0.0260202810 0.0336701907 0.0873578787 105 4.1600000000 0.0855680853 0.0252464914 0.0855680853 0.0103540317 0.0202440000 189932029 0 402718720 0.0263274144 0.0338647477 0.0887711868 106 4.2000000000 0.0880505666 0.0258389826 0.0880505666 0.0103653828 0.0568300000 202243793 0 402718720 0.0260270536 0.0378823616 0.0907679871 107 4.2400000000 0.0894080326 0.0264330859 0.0894080326 0.0103404496 0.0173320000 205905249 0 402718720 0.0264288001 0.0381955430 0.0922424495 108 4.2800000000 0.0904952586 0.0270262542 0.0904952586 0.0103224319 0.0236290000 209099689 0 402718720 0.0267350059 0.0393147133 0.0937615782 109 4.3200000000 0.0917968526 0.0276204799 0.0917968526 0.0103020943 0.0204110000 209101937 0 402718720 0.0266576037 0.0401451476 0.0949149877 110 4.3600000000 0.0933333859 0.0282178699 0.0933333859 0.0102618096 0.0180120000 209104185 0 402718720 0.0257233027 0.0403875895 0.0959116071 111 4.4000000000 0.0941216797 0.0288115979 0.0941216797 0.0102379073 0.0468700000 209106433 0 402718720 0.0273752641 0.0417978838 0.0979215577 112 4.4400000000 0.0952332318 0.0294046482 0.0952332318 0.0101993048 0.0210060000 209108681 0 402718720 0.0271871090 0.0418997444 0.0990900099 113 4.4800000000 0.0967126340 0.0300002941 0.0967126340 0.0101657187 0.0172610000 209110929 0 402718720 0.0262548830 0.0431518182 0.1002253741 114 4.5200000000 0.0975671709 0.0305929860 0.0975671709 0.0101307381 0.0176390000 209113177 0 402718720 0.0273774117 0.0434436016 0.1017163992 115 4.5600000000 0.0983696282 0.0311823481 0.0983696282 0.0100975447 0.0553320000 221420217 0 402718720 0.0275942795 0.0433905870 0.1031571627 116 4.6000000000 0.0980550051 0.0317588365 0.0983696282 0.0100636024 0.0161590000 225081673 0 402718720 0.0307382401 0.0440905206 0.1053594127 117 4.6400000000 0.0998829007 0.0323410935 0.0998829007 0.0100349290 0.0249810000 228276113 0 402718720 0.0303809568 0.0451380089 0.1065535545 118 4.6800000000 0.1001583561 0.0329158161 0.1001583561 0.0099993625 0.0224230000 228278361 0 402718720 0.0310195982 0.0445277691 0.1083192900 119 4.7200000000 0.1026291028 0.0335016420 0.1026291028 0.0099781005 0.0194140000 228280609 0 402718720 0.0301158167 0.0462131612 0.1095947698 120 4.7600000000 0.1029667780 0.0340805181 0.1029667780 0.0099466534 0.0190350000 228282857 0 402718720 0.0315867513 0.0460973196 0.1117626801 121 4.8000000000 0.1043904945 0.0346615923 0.1043904945 0.0099292015 0.0181470000 228285105 0 402718720 0.0318448320 0.0466303974 0.1133445129 122 4.8400000000 0.1053696275 0.0352411664 0.1053696275 0.0099290267 0.0449530000 240589929 0 402718720 0.0319855884 0.0466792434 0.1152516678 123 4.8800000000 0.1073699892 0.0358275796 0.1073699892 0.0099166644 0.0137260000 244253065 0 402718720 0.0312265083 0.0475974753 0.1166721359 124 4.9200000000 0.1079086810 0.0364088788 0.1079086810 0.0098859372 0.0222300000 247447505 0 402718720 0.0323045440 0.0477163717 0.1188026816 125 4.9600000000 0.1086056828 0.0369864532 0.1086056828 0.0098886515 0.0229630000 247449753 0 402718720 0.0346912667 0.0507121235 0.1224887818 126 5.0000000000 0.1108362004 0.0375725623 0.1108362004 0.0098811625 0.0189280000 247452001 0 402718720 0.0325777307 0.0490491278 0.1225165278 127 5.0400000000 0.1120936945 0.0381593429 0.1120936945 0.0098784070 0.0382640000 247454249 0 402718720 0.0333845206 0.0501966216 0.1248663291 128 5.0800000000 0.1142160296 0.0387535358 0.1142160296 0.0099051756 0.0204250000 247456497 0 402718720 0.0330174938 0.0519163311 0.1264356077 129 5.1200000000 0.1148729026 0.0393436084 0.1148729026 0.0098813243 0.0637880000 259779121 0 402718720 0.0336657353 0.0514000170 0.1284568012 130 5.1600000000 0.1168881655 0.0399401050 0.1168881655 0.0099179965 0.0248500000 263465665 0 402718720 0.0356189348 0.0561444908 0.1317337155 131 5.2000000000 0.1164591834 0.0405242201 0.1168881655 0.0098929179 0.0208980000 266660105 0 402718720 0.0373887718 0.0547835305 0.1338775456 132 5.2400000000 0.1174547896 0.0411070274 0.1174547896 0.0098668534 0.0189960000 266662353 0 402718720 0.0376625434 0.0552808233 0.1356454194 133 5.2800000000 0.1186158583 0.0416898006 0.1186158583 0.0098586755 0.0175020000 266664601 0 402718720 0.0382093117 0.0555412956 0.1373512298 134 5.3200000000 0.1197505146 0.0422723432 0.1197505146 0.0098761227 0.0167860000 266666849 0 402718720 0.0387705229 0.0563672408 0.1391740888 135 5.3600000000 0.1202132553 0.0428496833 0.1202132553 0.0098812041 0.0177910000 266669097 0 402718720 0.0407310538 0.0582525097 0.1420351863 136 5.4000000000 0.1216271594 0.0434289294 0.1216271594 0.0098835855 0.0168880000 266671345 0 402718720 0.0406618454 0.0570467822 0.1424705386 137 5.4400000000 0.1228932962 0.0440089613 0.1228932962 0.0098786726 0.0153380000 266673593 0 402718720 0.0411541425 0.0573323816 0.1438442320 138 5.4800000000 0.1238492057 0.0445875138 0.1238492057 0.0098588557 0.0163420000 266675841 0 402718720 0.0417026766 0.0580856763 0.1454120278 139 5.5200000000 0.1249375343 0.0451655715 0.1249375343 0.0098454339 0.0739720000 279000453 0 402718720 0.0422208384 0.0586156249 0.1468109787 140 5.5600000000 0.1264204681 0.0457459636 0.1264204681 0.0098300752 0.0123640000 282661909 0 402718720 0.0421239175 0.0585633293 0.1476334929 141 5.6000000000 0.1281406134 0.0463303229 0.1281406134 0.0098795363 0.0227560000 285856349 0 402718720 0.0425805263 0.0596069619 0.1505793482 142 5.6400000000 0.1289690882 0.0469122860 0.1289690882 0.0098790722 0.0152980000 285858597 0 402718720 0.0424716473 0.0596441105 0.1519550532 143 5.6800000000 0.1295346767 0.0474900649 0.1295346767 0.0098771636 0.0151950000 285860845 0 402718720 0.0427884087 0.0596783571 0.1534086913 144 5.7200000000 0.1304396391 0.0480661037 0.1304396391 0.0098679691 0.0453650000 285863093 0 402718720 0.0426790342 0.0601303801 0.1545067430 145 5.7600000000 0.1310268939 0.0486382470 0.1310268939 0.0098517735 0.0214720000 285865341 0 402718720 0.0425209478 0.0601567663 0.1555555761 146 5.8000000000 0.1312092394 0.0492038018 0.1312092394 0.0098450603 0.0828690000 298179373 0 402718720 0.0422111116 0.0599024445 0.1569533646 147 5.8400000000 0.1322406083 0.0497686780 0.1322406083 0.0098260297 0.0117060000 301840829 0 402718720 0.0415328555 0.0590129048 0.1572964936 148 5.8800000000 0.1329359561 0.0503306191 0.1329359561 0.0098068324 0.0118630000 305035269 0 402718720 0.0417306013 0.0593375973 0.1583816111 149 5.9200000000 0.1327046901 0.0508834652 0.1329359561 0.0097884288 0.0166700000 305037517 0 402718720 0.0417027287 0.0593718477 0.1604088098 150 5.9600000000 0.1303167492 0.0514130204 0.1329359561 0.0097665854 0.0147360000 305039765 0 402718720 0.0423407927 0.0573995411 0.1640332937 151 6.0000000000 0.1347319037 0.0519648011 0.1347319037 0.0097479816 0.0121860000 305042013 0 402718720 0.0400220491 0.0587939508 0.1616963297 152 6.0400000000 0.1322135627 0.0524927535 0.1347319037 0.0097588106 0.0127360000 305044261 0 402718720 0.0423919670 0.0589896403 0.1664918512 153 6.0800000000 0.1374571770 0.0530480765 0.1374571770 0.0097414660 0.0757430000 317360437 0 402718720 0.0387099609 0.0602038391 0.1637320369 154 6.1200000000 0.1376328766 0.0535973285 0.1376328766 0.0097273047 0.0113090000 321021893 0 402718720 0.0392632782 0.0601344667 0.1655817330 155 6.1600000000 0.1389588267 0.0541480478 0.1389588267 0.0097059132 0.0108200000 324216333 0 402718720 0.0380426049 0.0607172661 0.1664975137 156 6.2000000000 0.1354599297 0.0546692778 0.1389588267 0.0098059394 0.0170350000 324218581 0 402718720 0.0394839756 0.0631563365 0.1766982377 157 6.2400000000 0.1378521472 0.0551991050 0.1389588267 0.0097791450 0.0137150000 324220829 0 402718720 0.0378346071 0.0633841082 0.1763737053 158 6.2800000000 0.1395668238 0.0557330779 0.1395668238 0.0097512564 0.0403610000 324223077 0 402718720 0.0369349271 0.0625128523 0.1760742068 159 6.3200000000 0.1419758946 0.0562754856 0.1419758946 0.0097382139 0.0165300000 324225325 0 402718720 0.0350925662 0.0630678236 0.1757347733 160 6.3600000000 0.1432875693 0.0568193111 0.1432875693 0.0097181668 0.0740880000 336544165 0 402718720 0.0342093557 0.0636547208 0.1766432673 161 6.4000000000 0.1434086114 0.0573571328 0.1434086114 0.0097122936 0.0147560000 340205621 0 402718720 0.0332662724 0.0650055557 0.1793177873 162 6.4400000000 0.1426879019 0.0578838660 0.1434086114 0.0097052285 0.0117880000 343400061 0 402718720 0.0327962190 0.0643319190 0.1817090362 163 6.4800000000 0.1459362209 0.0584240645 0.1459362209 0.0097028834 0.0095990000 343402309 0 402718720 0.0305770263 0.0644021481 0.1796817929 164 6.5200000000 0.1476236135 0.0589679642 0.1476236135 0.0096820581 0.0090830000 343404557 0 402718720 0.0292294193 0.0644360930 0.1796596497 165 6.5600000000 0.1489372253 0.0595132324 0.1489372253 0.0096729136 0.0091770000 343406805 0 402718720 0.0276899301 0.0648814067 0.1805000305 166 6.6000000000 0.1487521380 0.0600508162 0.1489372253 0.0096509417 0.0095900000 343409053 0 402718720 0.0271475483 0.0642666742 0.1821971685 167 6.6400000000 0.1503331661 0.0605914291 0.1503331661 0.0096309428 0.0446590000 355741065 0 402718720 0.0256314706 0.0646410733 0.1825755090 168 6.6800000000 0.1511940211 0.0611307302 0.1511940211 0.0096061406 0.0087390000 359402521 0 402718720 0.0235036500 0.0633226633 0.1826297790 169 6.7200000000 0.1513730735 0.0616647086 0.1513730735 0.0095833928 0.0088560000 362596961 0 402718720 0.0238070041 0.0627970845 0.1837041825 170 6.7600000000 0.1520346105 0.0621962962 0.1520346105 0.0095630581 0.0090030000 362599209 0 402718720 0.0224860180 0.0626176447 0.1846709847 171 6.8000000000 0.1513954699 0.0627179288 0.1520346105 0.0095587783 0.0106320000 362601457 0 402718720 0.0227337889 0.0626299232 0.1873313338 172 6.8400000000 0.1523068398 0.0632387946 0.1523068398 0.0095366090 0.0093520000 362603705 0 402718720 0.0214441065 0.0619375482 0.1872747093 173 6.8800000000 0.1533963680 0.0637599366 0.1533963680 0.0095130719 0.0318010000 380024993 0 402718720 0.0214441065 0.0619375482 0.1872747093 174 6.9200000000 0.1529933661 0.0642727724 0.1533963680 0.0094892725 0.0037660000 383372841 0 402718720 0.0201576389 0.0602348708 0.1880890280 175 6.9600000000 0.1542579979 0.0647869737 0.1542579979 0.0094645014 0.0032570000 383451673 0 402718720 0.0201576389 0.0602348708 0.1880890280 176 7.0000000000 0.1550418288 0.0652997854 0.1550418288 0.0094406488 0.0030000000 383530505 0 402718720 0.0201576389 0.0602348708 0.1880890280 177 7.0400000000 0.1561053395 0.0658128111 0.1561053395 0.0094166581 0.0027780000 383609337 0 402718720 0.0201576389 0.0602348708 0.1880890280 178 7.0800000000 0.1570121050 0.0663251667 0.1570121050 0.0093909373 0.0046110000 383688169 0 402718720 0.0201576389 0.0602348708 0.1880890280 179 7.1200000000 0.1578774452 0.0668366319 0.1578774452 0.0093649368 0.0097790000 383767001 0 402718720 0.0201576389 0.0602348708 0.1880890280 180 7.1600000000 0.1588616371 0.0673478820 0.1588616371 0.0093402018 0.0056840000 383845833 0 402718720 0.0201576389 0.0602348708 0.1880890280 181 7.2000000000 0.1594327837 0.0678566383 0.1594327837 0.0093156980 0.0052530000 383924665 0 402718720 0.0201576389 0.0602348708 0.1880890280 182 7.2400000000 0.1599646658 0.0683627264 0.1599646658 0.0092911386 0.0198450000 384003497 0 402718720 0.0201576389 0.0602348708 0.1880890280 183 7.2800000000 0.1602678299 0.0688649401 0.1602678299 0.0092677195 0.0098590000 384082329 0 402718720 0.0201576389 0.0602348708 0.1880890280 184 7.3200000000 0.1610193998 0.0693657795 0.1610193998 0.0092472673 0.0060560000 384161161 0 402718720 0.0201576389 0.0602348708 0.1880890280 185 7.3600000000 1.0492343903 0.0746623666 1.0492343903 0.0946854190 0.0068850000 384240265 0 402718720 -0.6083924174 0.0487472974 -0.5156702399 186 7.4000000000 1.1585266590 0.0804895940 1.1585266590 0.0949833556 0.0114670000 384320689 0 402718720 -0.7334800363 0.0336450040 -0.5569524765 187 7.4400000000 1.2020488977 0.0864872373 1.2020488977 0.0951278084 0.0078160000 387670129 0 402718720 -0.7493209839 -0.0284643527 -0.6009951234 188 7.4800000000 1.5136315823 0.0940784307 1.5136315823 0.0988193808 0.0137560000 391019569 0 402718720 -1.0841207504 -0.0933118388 -0.7112336159 189 7.5200000000 1.5669916868 0.1018716225 1.5669916868 0.0986460752 0.0088070000 394369009 0 402718720 -1.1565483809 -0.0923312977 -0.7104067802 190 7.5600000000 1.6411041021 0.1099728461 1.6411041021 0.0986299261 0.0067340000 397721761 0 402718720 -1.2565392256 -0.1008751243 -0.7055285573 191 7.6000000000 1.7668857574 0.1186477828 1.7668857574 0.0994952232 0.0060620000 401071201 0 402718720 -1.3731062412 -0.1394110024 -0.7563424706 192 7.6400000000 1.9684734344 0.1282822914 1.9684734344 0.1004845720 0.0060520000 404420641 0 402718720 -1.6093380451 -0.1279806942 -0.7752461433 193 7.6800000000 2.0497124195 0.1382378879 2.0497124195 0.1004902672 0.0170230000 407770081 0 402718720 -1.6503506899 -0.1572973728 -0.8538478613 194 7.7200000000 2.0802948475 0.1482484908 2.0802948475 0.1002722090 0.0088990000 411119521 0 402718720 -1.6786265373 -0.1620754898 -0.8648851514 195 7.7600000000 1.9871001244 0.1576784992 2.0802948475 0.1009472179 0.0069670000 414468961 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 196 7.8000000000 1.9877352715 0.1670155235 2.0802948475 0.1006884973 0.0060280000 417816809 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 197 7.8400000000 1.9883713722 0.1762609847 2.0802948475 0.1004315667 0.0141960000 417895641 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 198 7.8800000000 1.9890816212 0.1854166444 2.0802948475 0.1001767760 0.0083810000 417974473 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 199 7.9200000000 1.9895241261 0.1944825112 2.0802948475 0.0999238286 0.0064460000 418053305 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 200 7.9600000000 1.9901142120 0.2034606697 2.0802948475 0.0996726161 0.0049770000 418132137 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 201 8.0000000000 1.9906355143 0.2123520868 2.0802948475 0.0994232016 0.0157510000 418210969 0 402718720 -1.6689516306 -0.2071314752 -0.7028481364 202 8.0400000000 2.0966291428 0.2216801911 2.0966291428 0.1008041869 0.0083240000 418291393 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 203 8.0800000000 2.0968987942 0.2309177211 2.0968987942 0.1005545279 0.0066630000 421639241 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 204 8.1200000000 2.0972728729 0.2400665209 2.0972728729 0.1003067454 0.0052650000 421718073 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 205 8.1600000000 2.0976164341 0.2491277400 2.0976164341 0.1000608285 0.0127740000 421796905 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 206 8.1999999990 2.0977327824 0.2581015509 2.0977327824 0.0998166394 0.0082430000 421875737 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 207 8.2400000000 2.0979969501 0.2669899344 2.0979969501 0.0995746840 0.0054500000 421954569 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 208 8.2799999990 2.0980560780 0.2757931371 2.0980560780 0.0993347497 0.0102660000 422033401 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 209 8.3200000000 2.0980038643 0.2845118487 2.0980560780 0.0990961508 0.0064520000 422112233 0 402718720 -1.8091652393 -0.3510617912 -0.6372320056 210 8.3599999990 2.3994371891 0.2945829217 2.3994371891 0.1063537009 0.0125170000 422192657 0 402718720 -2.1759967804 -0.6295245886 -0.4232678115 211 8.4000000000 2.7211656570 0.3060833138 2.7211656570 0.1119283183 0.0079070000 425542097 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 212 8.4399999990 2.7211110592 0.3174749541 2.7211656570 0.1116628565 0.0054290000 428889945 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 213 8.4800000000 2.7210652828 0.3287594158 2.7211656570 0.1113994068 0.0089300000 428968777 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 214 8.5200000000 2.7209808826 0.3399380208 2.7211656570 0.1111377077 0.0052160000 429047609 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 215 8.5600000000 2.7209181786 0.3510123471 2.7211656570 0.1108777947 0.0116040000 429126441 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 216 8.6000000000 2.7208135128 0.3619836488 2.7211656570 0.1106199571 0.0070170000 429205273 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 217 8.6400000000 2.7206804752 0.3728532194 2.7211656570 0.1103639565 0.0048590000 429284105 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 218 8.6800000000 2.7205841541 0.3836226274 2.7211656570 0.1101097998 0.0068220000 429362937 0 402718720 -2.4771974087 -0.9009253979 -0.3077414632 219 8.7200000000 0.6122277975 0.3846664866 2.7211656570 0.2719001516 0.0118310000 429441769 0 402718720 0.3638784289 0.1938296556 0.7986213565 220 8.7600000000 0.6391290426 0.3858231346 2.7211656570 0.2715326679 0.0230550000 427174873 0 402718720 0.3833850622 0.3099260330 0.7472054362 221 8.8000000000 0.6393264532 0.3869702084 2.7211656570 0.2709152146 0.0030600000 442289521 0 402718720 0.3833850622 0.3099260330 0.7472054362 222 8.8400000000 0.6395710111 0.3881080499 2.7211656570 0.2703020028 0.0026120000 445637369 0 402718720 0.3833850622 0.3099260330 0.7472054362 223 8.8800000000 0.6399071217 0.3892371937 2.7211656570 0.2696929630 0.0019980000 445716201 0 402718720 0.3833850622 0.3099260330 0.7472054362 224 8.9200000000 0.6403567195 0.3903582630 2.7211656570 0.2690879907 0.0018830000 445795033 0 402718720 0.3833850622 0.3099260330 0.7472054362 225 8.9600000000 0.6407828927 0.3914712613 2.7211656570 0.2684869586 0.0023640000 445873865 0 402718720 0.3833850622 0.3099260330 0.7472054362 226 9.0000000000 0.6412705183 0.3925765678 2.7211656570 0.2678900605 0.0027130000 445952697 0 402718720 0.3833850622 0.3099260330 0.7472054362 227 9.0400000000 0.6418029666 0.3936744814 2.7211656570 0.2672970272 0.0109960000 446031529 0 402718720 0.3833850622 0.3099260330 0.7472054362 228 9.0800000000 0.6422989964 0.3947649398 2.7211656570 0.2667080578 0.0083450000 446110361 0 402718720 0.3833850622 0.3099260330 0.7472054362 229 9.1200000000 0.6430898309 0.3958493280 2.7211656570 0.2661230106 0.0055670000 446189193 0 402718720 0.3833850622 0.3099260330 0.7472054362 230 9.1600000000 0.6438062787 0.3969274017 2.7211656570 0.2655415836 0.0057270000 446268025 0 402718720 0.3833850622 0.3099260330 0.7472054362 231 9.2000000000 0.6444963217 0.3979991286 2.7211656570 0.2649639924 0.0083430000 446346857 0 402718720 0.3833850622 0.3099260330 0.7472054362 232 9.2400000000 0.6451557875 0.3990644591 2.7211656570 0.2643902412 0.0048090000 446425689 0 402718720 0.3833850622 0.3099260330 0.7472054362 233 9.2800000000 0.6457490921 0.4001231914 2.7211656570 0.2638203494 0.0075540000 446504521 0 402718720 0.3833850622 0.3099260330 0.7472054362 234 9.3200000000 0.6466858387 0.4011768779 2.7211656570 0.2632542746 0.0074500000 446583353 0 402718720 0.3833850622 0.3099260330 0.7472054362 235 9.3600000000 0.6475143433 0.4022251224 2.7211656570 0.2626916574 0.0039680000 446662185 0 402718720 0.3833850622 0.3099260330 0.7472054362 236 9.4000000000 0.6483672857 0.4032680977 2.7211656570 0.2621326311 0.0031880000 446741017 0 402718720 0.3833850622 0.3099260330 0.7472054362 237 9.4400000000 0.6492700577 0.4043060807 2.7211656570 0.2615770925 0.0033510000 446819849 0 402718720 0.3833850622 0.3099260330 0.7472054362 238 9.4800000000 0.6509154439 0.4053422545 2.7211656570 0.2610264981 0.0081000000 446898681 0 402718720 0.3833850622 0.3099260330 0.7472054362 239 9.5200000000 0.6518325806 0.4063735947 2.7211656570 0.2604783295 0.0080920000 446977513 0 402718720 0.3833850622 0.3099260330 0.7472054362 240 9.5600000000 0.6526538134 0.4073997623 2.7211656570 0.2599336961 0.0079950000 447056345 0 402718720 0.3833850622 0.3099260330 0.7472054362 241 9.6000000000 0.6535152197 0.4084209883 2.7211656570 0.2593928818 0.0083480000 447135177 0 402718720 0.3833850622 0.3099260330 0.7472054362 242 9.6400000000 0.6544765234 0.4094377467 2.7211656570 0.2588555550 0.0047120000 447214009 0 402718720 0.3833850622 0.3099260330 0.7472054362 243 9.6800000000 0.6556713581 0.4104510537 2.7211656570 0.2583214353 0.0018200000 447292841 0 402718720 0.3833850622 0.3099260330 0.7472054362 244 9.7200000000 0.6566995978 0.4114602691 2.7211656570 0.2577904582 0.0086760000 447371673 0 402718720 0.3833850622 0.3099260330 0.7472054362 245 9.7600000000 0.6579258442 0.4124662510 2.7211656570 0.2572625610 0.0068940000 447450505 0 402718720 0.3833850622 0.3099260330 0.7472054362 246 9.8000000000 0.6591287255 0.4134689440 2.7211656570 0.2567376407 0.0088820000 447529337 0 402718720 0.3833850622 0.3099260330 0.7472054362 247 9.8400000000 0.6601641178 0.4144677099 2.7211656570 0.2562160432 0.0052460000 447608169 0 402718720 0.3833850622 0.3099260330 0.7472054362 248 9.8800000000 0.6614512801 0.4154636114 2.7211656570 0.2556978254 0.0079470000 447687001 0 402718720 0.3833850622 0.3099260330 0.7472054362 249 9.9200000000 0.6627352238 0.4164566701 2.7211656570 0.2551828531 0.0059740000 447765833 0 402718720 0.3833850622 0.3099260330 0.7472054362 250 9.9600000000 0.6638777256 0.4174463543 2.7211656570 0.2546708083 0.0048180000 447844665 0 402718720 0.3833850622 0.3099260330 0.7472054362 251 10.0000000000 0.6649340391 0.4184323610 2.7211656570 0.2541618527 0.0038890000 447923497 0 402718720 0.3833850622 0.3099260330 0.7472054362 252 10.0400000000 0.6661407351 0.4194153307 2.7211656570 0.2536562160 0.0020240000 448002329 0 402718720 0.3833850622 0.3099260330 0.7472054362 253 10.0800000000 0.6673384905 0.4203952642 2.7211656570 0.2531534280 0.0079610000 448081161 0 402718720 0.3833850622 0.3099260330 0.7472054362 254 10.1200000000 0.6684619188 0.4213719046 2.7211656570 0.2526536038 0.0087160000 448159993 0 402718720 0.3833850622 0.3099260330 0.7472054362 255 10.1600000000 0.6696476340 0.4223455349 2.7211656570 0.2521569721 0.0088040000 448238825 0 402718720 0.3833850622 0.3099260330 0.7472054362 256 10.2000000000 0.6707973480 0.4233160498 2.7211656570 0.2516631855 0.0058270000 448317657 0 402718720 0.3833850622 0.3099260330 0.7472054362 257 10.2400000000 0.6719031930 0.4242833149 2.7211656570 0.2511722249 0.0081280000 448396489 0 402718720 0.3833850622 0.3099260330 0.7472054362 258 10.2800000000 0.6730728745 0.4252476155 2.7211656570 0.2506837850 0.0055110000 448526521 0 402718720 0.3833850622 0.3099260330 0.7472054362 259 10.3200000000 0.6742850542 0.4262091500 2.7211656570 0.2501979006 0.0089180000 448605353 0 402718720 0.3833850622 0.3099260330 0.7472054362 260 10.3600000000 0.6753420830 0.4271673536 2.7211656570 0.2497150005 0.0048840000 448684185 0 402718720 0.3833850622 0.3099260330 0.7472054362 261 10.4000000000 0.6765844822 0.4281229748 2.7211656570 0.2492351966 0.0053030000 448763017 0 402718720 0.3833850622 0.3099260330 0.7472054362 262 10.4400000000 0.6778680086 0.4290762001 2.7211656570 0.2487578912 0.0017970000 448841849 0 402718720 0.3833850622 0.3099260330 0.7472054362 263 10.4800000000 0.6790568233 0.4300266968 2.7211656570 0.2482830754 0.0019370000 448920681 0 402718720 0.3833850622 0.3099260330 0.7472054362 264 10.5200000000 0.6803454757 0.4309748740 2.7211656570 0.2478109916 0.0076240000 448999513 0 402718720 0.3833850622 0.3099260330 0.7472054362 265 10.5600000000 0.6816794276 0.4319209289 2.7211656570 0.2473419095 0.0020660000 449078345 0 402718720 0.3833850622 0.3099260330 0.7472054362 266 10.6000000000 0.6830282807 0.4328649415 2.7211656570 0.2468752784 0.0091790000 449157177 0 402718720 0.3833850622 0.3099260330 0.7472054362 267 10.6400000000 0.6843807101 0.4338069481 2.7211656570 0.2464109235 0.0088310000 449236009 0 402718720 0.3833850622 0.3099260330 0.7472054362 268 10.6800000000 0.6858893633 0.4347475542 2.7211656570 0.2459492958 0.0081340000 449314841 0 402718720 0.3833850622 0.3099260330 0.7472054362 269 10.7200000000 0.6872448921 0.4356862060 2.7211656570 0.2454903993 0.0059850000 449393673 0 402718720 0.3833850622 0.3099260330 0.7472054362 270 10.7600000000 0.6887331605 0.4366234169 2.7211656570 0.2450342470 0.0059990000 449472505 0 402718720 0.3833850622 0.3099260330 0.7472054362 271 10.8000000000 0.6903125644 0.4375595392 2.7211656570 0.2445804050 0.0081340000 449551337 0 402718720 0.3833850622 0.3099260330 0.7472054362 272 10.8400000000 0.6917358041 0.4384940108 2.7211656570 0.2441288543 0.0072360000 449630169 0 402718720 0.3833850622 0.3099260330 0.7472054362 273 10.8800000000 0.6933323145 0.4394274844 2.7211656570 0.2436800502 0.0020230000 449709001 0 402718720 0.3833850622 0.3099260330 0.7472054362 274 10.9200000000 0.6948628426 0.4403597303 2.7211656570 0.2432336337 0.0082080000 449787833 0 402718720 0.3833850622 0.3099260330 0.7472054362 275 10.9600000000 0.6964964271 0.4412911364 2.7211656570 0.2427895269 0.0080920000 449866665 0 402718720 0.3833850622 0.3099260330 0.7472054362 276 11.0000000000 0.6980962753 0.4422215898 2.7211656570 0.2423477942 0.0057300000 449945497 0 402718720 0.3833850622 0.3099260330 0.7472054362 277 11.0400000000 0.6996098161 0.4431507892 2.7211656570 0.2419085492 0.0076110000 450024329 0 402718720 0.3833850622 0.3099260330 0.7472054362 278 11.0800000000 0.7011566758 0.4440788679 2.7211656570 0.2414717852 0.0078080000 450103161 0 402718720 0.3833850622 0.3099260330 0.7472054362 279 11.1200000000 0.7027133703 0.4450058733 2.7211656570 0.2410372464 0.0057130000 450181993 0 402718720 0.3833850622 0.3099260330 0.7472054362 280 11.1600000000 0.7041429281 0.4459313628 2.7211656570 0.2406049359 0.0083540000 450260825 0 402718720 0.3833850622 0.3099260330 0.7472054362 281 11.2000000000 0.7055854201 0.4468553986 2.7211656570 0.2401749693 0.0053220000 450339657 0 402718720 0.3833850622 0.3099260330 0.7472054362 282 11.2400000000 0.7070986629 0.4477782470 2.7211656570 0.2397472906 0.0086060000 450418489 0 402718720 0.3833850622 0.3099260330 0.7472054362 283 11.2800000000 0.7085779309 0.4486998007 2.7211656570 0.2393218612 0.0054500000 450497321 0 402718720 0.3833850622 0.3099260330 0.7472054362 284 11.3200000000 0.7100178599 0.4496199347 2.7211656570 0.2388986730 0.0041840000 450576153 0 402718720 0.3833850622 0.3099260330 0.7472054362 285 11.3600000000 0.7117157578 0.4505395692 2.7211656570 0.2384777138 0.0042990000 450654985 0 402718720 0.3833850622 0.3099260330 0.7472054362 286 11.4000000000 0.7135528326 0.4514591960 2.7211656570 0.2380589719 0.0087530000 450733817 0 402718720 0.3833850622 0.3099260330 0.7472054362 287 11.4400000000 0.7153437138 0.4523786542 2.7211656570 0.2376424824 0.0081330000 450812649 0 402718720 0.3833850622 0.3099260330 0.7472054362 288 11.4800000000 0.7173703909 0.4532987644 2.7211656570 0.2372282279 0.0073250000 450891481 0 402718720 0.3833850622 0.3099260330 0.7472054362 289 11.5200000000 0.7194141150 0.4542195788 2.7211656570 0.2368163202 0.0045370000 450970313 0 402718720 0.3833850622 0.3099260330 0.7472054362 290 11.5600000000 0.7216575742 0.4551417788 2.7211656570 0.2364064805 0.0043700000 451049145 0 402718720 0.3833850622 0.3099260330 0.7472054362 291 11.6000000000 0.7238436341 0.4560651528 2.7211656570 0.2359988182 0.0044960000 451127977 0 402718720 0.3833850622 0.3099260330 0.7472054362 292 11.6400000000 0.7261409760 0.4569900700 2.7211656570 0.2355930848 0.0042550000 451206809 0 402718720 0.3833850622 0.3099260330 0.7472054362 293 11.6800000000 0.7284556627 0.4579165738 2.7211656570 0.2351894903 0.0043040000 451285641 0 402718720 0.3833850622 0.3099260330 0.7472054362 294 11.7200000000 0.7309594154 0.4588452909 2.7211656570 0.2347881026 0.0043850000 451364473 0 402718720 0.3833850622 0.3099260330 0.7472054362 295 11.7600000000 0.7333212495 0.4597757179 2.7211656570 0.2343886870 0.0085440000 451443305 0 402718720 0.3833850622 0.3099260330 0.7472054362 296 11.8000000000 0.7357326150 0.4607080047 2.7211656570 0.2339912123 0.0083820000 451522137 0 402718720 0.3833850622 0.3099260330 0.7472054362 297 11.8400000000 0.7381066680 0.4616420069 2.7211656570 0.2335956777 0.0073410000 451600969 0 402718720 0.3833850622 0.3099260330 0.7472054362 298 11.8800000000 0.7405416965 0.4625779119 2.7211656570 0.2332021391 0.0042210000 451679801 0 402718720 0.3833850622 0.3099260330 0.7472054362 299 11.9200000000 0.7429096699 0.4635154764 2.7211656570 0.2328107438 0.0043970000 451758633 0 402718720 0.3833850622 0.3099260330 0.7472054362 300 11.9600000000 0.7454974055 0.4644554161 2.7211656570 0.2324213150 0.0042930000 451837465 0 402718720 0.3833850622 0.3099260330 0.7472054362 301 12.0000000000 0.7479500771 0.4653972588 2.7211656570 0.2320339021 0.0081740000 451916297 0 402718720 0.3833850622 0.3099260330 0.7472054362 302 12.0400000000 0.7503703237 0.4663408783 2.7211656570 0.2316485333 0.0077130000 451995129 0 402718720 0.3833850622 0.3099260330 0.7472054362 303 12.0800000000 0.7529640198 0.4672868292 2.7211656570 0.2312648597 0.0078850000 452073961 0 402718720 0.3833850622 0.3099260330 0.7472054362 304 12.1200000000 0.7555176616 0.4682349570 2.7211656570 0.2308830129 0.0054370000 452152793 0 402718720 0.3833850622 0.3099260330 0.7472054362 305 12.1600000000 0.7580390573 0.4691851343 2.7211656570 0.2305030485 0.0082500000 452231625 0 402718720 0.3833850622 0.3099260330 0.7472054362 306 12.2000000000 0.7604680657 0.4701370393 2.7211656570 0.2301248951 0.0056280000 452310457 0 402718720 0.3833850622 0.3099260330 0.7472054362 307 12.2400000000 0.7630364895 0.4710911092 2.7211656570 0.2297485673 0.0055230000 452389289 0 402718720 0.3833850622 0.3099260330 0.7472054362 308 12.2800000000 0.7656012774 0.4720473111 2.7211656570 0.2293740901 0.0053720000 452468121 0 402718720 0.3833850622 0.3099260330 0.7472054362 309 12.3200000000 0.7681625485 0.4730056128 2.7211656570 0.2290014854 0.0055540000 452546953 0 402718720 0.3833850622 0.3099260330 0.7472054362 310 12.3600000000 0.7706516981 0.4739657615 2.7211656570 0.2286307121 0.0052620000 452625785 0 402718720 0.3833850622 0.3099260330 0.7472054362 311 12.4000000000 0.7730432749 0.4749274255 2.7211656570 0.2282617103 0.0076410000 452704617 0 402718720 0.3833850622 0.3099260330 0.7472054362 312 12.4400000000 0.7754944563 0.4758907814 2.7211656570 0.2278944671 0.0079920000 452783449 0 402718720 0.3833850622 0.3099260330 0.7472054362 313 12.4800000000 0.7778636813 0.4768555510 2.7211656570 0.2275290956 0.0052650000 452862281 0 402718720 0.3833850622 0.3099260330 0.7472054362 314 12.5200000000 0.7802833915 0.4778218817 2.7211656570 0.2271655548 0.0079770000 452941113 0 402718720 0.3833850622 0.3099260330 0.7472054362 315 12.5600000000 0.7827212214 0.4787898161 2.7211656570 0.2268037012 0.0055530000 453019945 0 402718720 0.3833850622 0.3099260330 0.7472054362 316 12.6000000000 0.7850711942 0.4797590610 2.7211656570 0.2264435406 0.0045220000 453098777 0 402718720 0.3833850622 0.3099260330 0.7472054362 317 12.6400000000 0.7873970270 0.4807295278 2.7211656570 0.2260850442 0.0078890000 453177609 0 402718720 0.3833850622 0.3099260330 0.7472054362 318 12.6800000000 0.7895195484 0.4817005656 2.7211656570 0.2257284282 0.0078140000 453256441 0 402718720 0.3833850622 0.3099260330 0.7472054362 319 12.7200000000 0.7916971445 0.4826723417 2.7211656570 0.2253734406 0.0052240000 453335273 0 402718720 0.3833850622 0.3099260330 0.7472054362 320 12.7600000000 0.7938270569 0.4836447002 2.7211656570 0.2250200657 0.0077910000 453414105 0 402718720 0.3833850622 0.3099260330 0.7472054362 321 12.8000000000 0.7959877253 0.4846177314 2.7211656570 0.2246683109 0.0074270000 453492937 0 402718720 0.3833850622 0.3099260330 0.7472054362 322 12.8400000000 0.7981945276 0.4855915724 2.7211656570 0.2243182193 0.0048940000 453571769 0 402718720 0.3833850622 0.3099260330 0.7472054362 323 12.8800000000 0.8002845645 0.4865658541 2.7211656570 0.2239698946 0.0071310000 453650601 0 402718720 0.3833850622 0.3099260330 0.7472054362 324 12.9200000000 0.8025643826 0.4875411582 2.7211656570 0.2236230460 0.0080290000 453729433 0 402718720 0.3833850622 0.3099260330 0.7472054362 325 12.9600000000 0.8048458695 0.4885174804 2.7211656570 0.2232777397 0.0044330000 453808265 0 402718720 0.3833850622 0.3099260330 0.7472054362 326 13.0000000000 0.8070446849 0.4894945577 2.7211656570 0.2229340412 0.0074070000 453887097 0 402718720 0.3833850622 0.3099260330 0.7472054362 327 13.0400000000 0.8094236851 0.4904729342 2.7211656570 0.2225919452 0.0066060000 453965929 0 402718720 0.3833850622 0.3099260330 0.7472054362 328 13.0800000000 0.8115703464 0.4914518897 2.7211656570 0.2222513962 0.0050820000 454044761 0 402718720 0.3833850622 0.3099260330 0.7472054362 329 13.1200000000 0.8139578700 0.4924321511 2.7211656570 0.2219124033 0.0047680000 454123593 0 402718720 0.3833850622 0.3099260330 0.7472054362 330 13.1600000000 0.8163278103 0.4934136531 2.7211656570 0.2215749798 0.0075030000 454202425 0 402718720 0.3833850622 0.3099260330 0.7472054362 331 13.2000000000 0.8187353611 0.4943964981 2.7211656570 0.2212390718 0.0077860000 454281257 0 402718720 0.3833850622 0.3099260330 0.7472054362 332 13.2400000000 0.8211873770 0.4953808080 2.7211656570 0.2209046728 0.0060620000 454360089 0 402718720 0.3833850622 0.3099260330 0.7472054362 333 13.2800000000 0.8236996531 0.4963667505 2.7211656570 0.2205717805 0.0076310000 454438921 0 402718720 0.3833850622 0.3099260330 0.7472054362 334 13.3200000000 0.8262847662 0.4973545290 2.7211656570 0.2202403491 0.0051260000 454517753 0 402718720 0.3833850622 0.3099260330 0.7472054362 335 13.3600000000 0.8289834857 0.4983444661 2.7211656570 0.2199104408 0.0037040000 454596585 0 402718720 0.3833850622 0.3099260330 0.7472054362 336 13.4000000000 0.8315214515 0.4993360643 2.7211656570 0.2195821727 0.0039410000 454675417 0 402718720 0.3833850622 0.3099260330 0.7472054362 337 13.4400000000 0.8344474435 0.5003304601 2.7211656570 0.2192552382 0.0076610000 454754249 0 402718720 0.3833850622 0.3099260330 0.7472054362 338 13.4800000000 0.8369925618 0.5013265018 2.7211656570 0.2189297307 0.0077290000 454833081 0 402718720 0.3833850622 0.3099260330 0.7472054362 339 13.5200000000 0.8395482302 0.5023242060 2.7211656570 0.2186056878 0.0077570000 454911913 0 402718720 0.3833850622 0.3099260330 0.7472054362 340 13.5600000000 0.8421103954 0.5033235772 2.7211656570 0.2182830630 0.0051030000 454990745 0 402718720 0.3833850622 0.3099260330 0.7472054362 341 13.6000000000 0.8446254134 0.5043244623 2.7211656570 0.2179618884 0.0072670000 455069577 0 402718720 0.3833850622 0.3099260330 0.7472054362 342 13.6400000000 0.8473549485 0.5053274755 2.7211656570 0.2176421017 0.0074720000 455148409 0 402718720 0.3833850622 0.3099260330 0.7472054362 343 13.6800000000 0.8500364423 0.5063324579 2.7211656570 0.2173237035 0.0054830000 455227241 0 402718720 0.3833850622 0.3099260330 0.7472054362 344 13.7200000000 0.8529231548 0.5073399890 2.7211656570 0.2170066830 0.0050290000 455306073 0 402718720 0.3833850622 0.3099260330 0.7472054362 345 13.7600000000 0.8555953503 0.5083494248 2.7211656570 0.2166910619 0.0076110000 455384905 0 402718720 0.3833850622 0.3099260330 0.7472054362 346 13.8000000000 0.8581386805 0.5093603764 2.7211656570 0.2163768070 0.0071280000 455463737 0 402718720 0.3833850622 0.3099260330 0.7472054362 347 13.8400000000 0.8608667850 0.5103733632 2.7211656570 0.2160639608 0.0052180000 455542569 0 402718720 0.3833850622 0.3099260330 0.7472054362 348 13.8800000000 0.8633559346 0.5113876809 2.7211656570 0.2157524266 0.0079490000 455621401 0 402718720 0.3833850622 0.3099260330 0.7472054362 349 13.9200000000 0.8660556674 0.5124039215 2.7211656570 0.2154422596 0.0050940000 455700233 0 402718720 0.3833850622 0.3099260330 0.7472054362 350 13.9600000000 0.8688483834 0.5134223343 2.7211656570 0.2151334248 0.0050270000 455779065 0 402718720 0.3833850622 0.3099260330 0.7472054362 351 14.0000000000 0.8714601398 0.5144423850 2.7211656570 0.2148259292 0.0073060000 455857897 0 402718720 0.3833850622 0.3099260330 0.7472054362 352 14.0400000000 0.8742280006 0.5154645032 2.7211656570 0.2145197515 0.0078400000 455936729 0 402718720 0.3833850622 0.3099260330 0.7472054362 353 14.0800000000 0.8767407537 0.5164879487 2.7211656570 0.2142148709 0.0049990000 456015561 0 402718720 0.3833850622 0.3099260330 0.7472054362 354 14.1200000000 0.8792889714 0.5175128104 2.7211656570 0.2139113171 0.0040170000 456094393 0 402718720 0.3833850622 0.3099260330 0.7472054362 355 14.1600000000 0.8814816475 0.5185380747 2.7211656570 0.2136090460 0.0038810000 456173225 0 402718720 0.3833850622 0.3099260330 0.7472054362 356 14.2000000000 0.8838456273 0.5195642195 2.7211656570 0.2133080622 0.0083460000 456252057 0 402718720 0.3833850622 0.3099260330 0.7472054362 357 14.2400000000 0.8861457109 0.5205910584 2.7211656570 0.2130084208 0.0077240000 456330889 0 402718720 0.3833850622 0.3099260330 0.7472054362 358 14.2800000000 0.8882349133 0.5216179966 2.7211656570 0.2127100626 0.0069900000 456409721 0 402718720 0.3833850622 0.3099260330 0.7472054362 359 14.3200000000 0.8906381130 0.5226459077 2.7211656570 0.2124129470 0.0047900000 456488553 0 402718720 0.3833850622 0.3099260330 0.7472054362 360 14.3600000000 0.8926178813 0.5236736077 2.7211656570 0.2121169211 0.0074770000 456567385 0 402718720 0.3833850622 0.3099260330 0.7472054362 361 14.4000000000 0.8945909142 0.5247010794 2.7211656570 0.2118222784 0.0072350000 456646217 0 402718720 0.3833850622 0.3099260330 0.7472054362 362 14.4400000000 0.8968899846 0.5257292256 2.7211656570 0.2115287364 0.0051910000 456725049 0 402718720 0.3833850622 0.3099260330 0.7472054362 363 14.4800000000 0.8989298940 0.5267573266 2.7211656570 0.2112363845 0.0075960000 456803881 0 402718720 0.3833850622 0.3099260330 0.7472054362 364 14.5200000000 0.9008832574 0.5277851451 2.7211656570 0.2109452670 0.0051710000 456882713 0 402718720 0.3833850622 0.3099260330 0.7472054362 365 14.5600000000 0.9029412270 0.5288129700 2.7211656570 0.2106553313 0.0041840000 456961545 0 402718720 0.3833850622 0.3099260330 0.7472054362 366 14.6000000000 0.9050228596 0.5298408658 2.7211656570 0.2103666330 0.0082630000 457040377 0 402718720 0.3833850622 0.3099260330 0.7472054362 367 14.6400000000 0.9071198106 0.5308688739 2.7211656570 0.2100791705 0.0080010000 457119209 0 402718720 0.3833850622 0.3099260330 0.7472054362 368 14.6800000000 0.9091939330 0.5318969311 2.7211656570 0.2097928005 0.0057700000 457198041 0 402718720 0.3833850622 0.3099260330 0.7472054362 369 14.7200000000 0.9111060500 0.5329245981 2.7211656570 0.2095076063 0.0043940000 457276873 0 402718720 0.3833850622 0.3099260330 0.7472054362 370 14.7600000000 0.9129039049 0.5339515692 2.7211656570 0.2092235421 0.0042000000 457355705 0 402718720 0.3833850622 0.3099260330 0.7472054362 371 14.8000000000 0.9151312709 0.5349790077 2.7211656570 0.2089406392 0.0043210000 457434537 0 402718720 0.3833850622 0.3099260330 0.7472054362 372 14.8400000000 0.9174489379 0.5360071527 2.7211656570 0.2086589564 0.0088470000 457513369 0 402718720 0.3833850622 0.3099260330 0.7472054362 373 14.8800000000 0.9195601940 0.5370354450 2.7211656570 0.2083784192 0.0080630000 457592201 0 402718720 0.3833850622 0.3099260330 0.7472054362 374 14.9200000000 0.9216265082 0.5380637634 2.7211656570 0.2080991199 0.0069560000 457671033 0 402718720 0.3833850622 0.3099260330 0.7472054362 375 14.9600000000 0.9237158298 0.5390921689 2.7211656570 0.2078210012 0.0041420000 457749865 0 402718720 0.3833850622 0.3099260330 0.7472054362 376 15.0000000000 0.9259165525 0.5401209572 2.7211656570 0.2075438217 0.0081740000 457828697 0 402718720 0.3833850622 0.3099260330 0.7472054362 377 15.0400000000 0.9279297590 0.5411496277 2.7211656570 0.2072678436 0.0076620000 457907529 0 402718720 0.3833850622 0.3099260330 0.7472054362 378 15.0800000000 0.9302227497 0.5421789217 2.7211656570 0.2069931956 0.0051180000 457986361 0 402718720 0.3833850622 0.3099260330 0.7472054362 379 15.1200000000 0.9326062799 0.5432090730 2.7211656570 0.2067193498 0.0084740000 458065193 0 402718720 0.3833850622 0.3099260330 0.7472054362 380 15.1600000000 0.9350813031 0.5442403157 2.7211656570 0.2064464709 0.0054680000 458144025 0 402718720 0.3833850622 0.3099260330 0.7472054362 381 15.2000000000 0.9371392727 0.5452715466 2.7211656570 0.2061746840 0.0057610000 458222857 0 402718720 0.3833850622 0.3099260330 0.7472054362 382 15.2400000000 0.9397208095 0.5463041363 2.7211656570 0.2059040357 0.0055220000 458301689 0 402718720 0.3833850622 0.3099260330 0.7472054362 383 15.2800000000 0.9417594671 0.5473366567 2.7211656570 0.2056345185 0.0060470000 458380521 0 402718720 0.3833850622 0.3099260330 0.7472054362 384 15.3200000000 0.9443327785 0.5483705008 2.7211656570 0.2053660934 0.0082960000 458459353 0 402718720 0.3833850622 0.3099260330 0.7472054362 385 15.3600000000 0.9466796517 0.5494050700 2.7211656570 0.2050987015 0.0057630000 458538185 0 402718720 0.3833850622 0.3099260330 0.7472054362 386 15.4000000000 0.9491280913 0.5504406219 2.7211656570 0.2048322840 0.0081430000 458617017 0 402718720 0.3833850622 0.3099260330 0.7472054362 387 15.4400000000 0.9515331984 0.5514770368 2.7211656570 0.2045668680 0.0052390000 458695849 0 402718720 0.3833850622 0.3099260330 0.7472054362 388 15.4800000000 0.9537649751 0.5525138614 2.7211656570 0.2043025335 0.0085260000 458774681 0 402718720 0.3833850622 0.3099260330 0.7472054362 389 15.5200000000 0.9562406540 0.5535517195 2.7211656570 0.2040392585 0.0051790000 458853513 0 402718720 0.3833850622 0.3099260330 0.7472054362 390 15.5600000000 0.9586938620 0.5545905455 2.7211656570 0.2037769411 0.0085560000 458932345 0 402718720 0.3833850622 0.3099260330 0.7472054362 391 15.6000000000 0.9610590935 0.5556301070 2.7211656570 0.2035156358 0.0047580000 459011177 0 402718720 0.3833850622 0.3099260330 0.7472054362 392 15.6400000000 0.9635314941 0.5566706718 2.7211656570 0.2032554674 0.0082060000 459090009 0 402718720 0.3833850622 0.3099260330 0.7472054362 393 15.6800000000 0.9657912254 0.5577116910 2.7211656570 0.2029963010 0.0055870000 459168841 0 402718720 0.3833850622 0.3099260330 0.7472054362 394 15.7200000000 0.9681124687 0.5587533173 2.7211656570 0.2027381010 0.0042260000 459247673 0 402718720 0.3833850622 0.3099260330 0.7472054362 395 15.7600000000 0.9709774256 0.5597969227 2.7211656570 0.2024809504 0.0082070000 459326505 0 402718720 0.3833850622 0.3099260330 0.7472054362 396 15.8000000000 0.9733317494 0.5608412025 2.7211656570 0.2022247706 0.0072230000 459405337 0 402718720 0.3833850622 0.3099260330 0.7472054362 397 15.8400000000 0.9754427671 0.5618855390 2.7211656570 0.2019696029 0.0057310000 459484169 0 402718720 0.3833850622 0.3099260330 0.7472054362 398 15.8800000000 0.9782195687 0.5629316044 2.7211656570 0.2017154731 0.0043500000 459563001 0 402718720 0.3833850622 0.3099260330 0.7472054362 399 15.9200000000 0.9805214405 0.5639781954 2.7211656570 0.2014620022 0.0079480000 459641833 0 402718720 0.3833850622 0.3099260330 0.7472054362 400 15.9600000000 0.9827994704 0.5650252486 2.7211656570 0.2012094450 0.0075720000 459720665 0 402718720 0.3833850622 0.3099260330 0.7472054362 401 16.0000000000 0.9850201011 0.5660726173 2.7211656570 0.2009580322 0.0053060000 459799497 0 402718720 0.3833850622 0.3099260330 0.7472054362 402 16.0400000000 0.9872505665 0.5671203237 2.7211656570 0.2007074297 0.0076920000 459878329 0 402718720 0.3833850622 0.3099260330 0.7472054362 403 16.0800000000 0.9893863797 0.5681681303 2.7211656570 0.2004578866 0.0051400000 459957161 0 402718720 0.3833850622 0.3099260330 0.7472054362 404 16.1200000000 0.9913483262 0.5692156060 2.7211656570 0.2002094933 0.0080450000 460035993 0 402718720 0.3833850622 0.3099260330 0.7472054362 405 16.1600000000 0.9933809638 0.5702629279 2.7211656570 0.1999619339 0.0054620000 460114825 0 402718720 0.3833850622 0.3099260330 0.7472054362 406 16.2000000000 0.9951687455 0.5713094939 2.7211656570 0.1997150885 0.0040730000 460193657 0 402718720 0.3833850622 0.3099260330 0.7472054362 407 16.2400000000 0.9969701767 0.5723553433 2.7211656570 0.1994693745 0.0077880000 460272489 0 402718720 0.3833850622 0.3099260330 0.7472054362 408 16.2800000000 0.9987574220 0.5734004464 2.7211656570 0.1992244590 0.0081250000 460351321 0 402718720 0.3833850622 0.3099260330 0.7472054362 409 16.3200000000 1.0006506443 0.5744450679 2.7211656570 0.1989802653 0.0052470000 460430153 0 402718720 0.3833850622 0.3099260330 0.7472054362 410 16.3600000000 1.0021157265 0.5754881671 2.7211656570 0.1987369743 0.0040270000 460508985 0 402718720 0.3833850622 0.3099260330 0.7472054362 411 16.3999999990 1.0037083626 0.5765300654 2.7211656570 0.1984947810 0.0043020000 460587817 0 402718720 0.3833850622 0.3099260330 0.7472054362 412 16.4400000000 1.0054618120 0.5775711618 2.7211656570 0.1982534601 0.0045460000 460666649 0 402718720 0.3833850622 0.3099260330 0.7472054362 413 16.4800000000 1.0073477030 0.5786117830 2.7211656570 0.1980129135 0.0092820000 460745481 0 402718720 0.3833850622 0.3099260330 0.7472054362 414 16.5200000000 1.0090708733 0.5796515392 2.7211656570 0.1977731707 0.0088360000 460824313 0 402718720 0.3833850622 0.3099260330 0.7472054362 415 16.5599999990 1.0108723640 0.5806906256 2.7211656570 0.1975343224 0.0061760000 460903145 0 402718720 0.3833850622 0.3099260330 0.7472054362 416 16.6000000000 1.0126775503 0.5817290557 2.7211656570 0.1972964519 0.0062190000 460981977 0 402718720 0.3833850622 0.3099260330 0.7472054362 417 16.6400000000 1.0147472620 0.5827674686 2.7211656570 0.1970595655 0.0090520000 461060809 0 402718720 0.3833850622 0.3099260330 0.7472054362 418 16.6800000000 1.0168821812 0.5838060206 2.7211656570 0.1968234633 0.0057330000 461139641 0 402718720 0.3833850622 0.3099260330 0.7472054362 419 16.7199999990 1.0188305378 0.5848442653 2.7211656570 0.1965883279 0.0086430000 461218473 0 402718720 0.3833850622 0.3099260330 0.7472054362 420 16.7600000000 1.0207920074 0.5858822361 2.7211656570 0.1963541681 0.0047010000 461297305 0 402718720 0.3833850622 0.3099260330 0.7472054362 421 16.8000000000 1.0230096579 0.5869205435 2.7211656570 0.1961204951 0.0093790000 461376137 0 402718720 0.3833850622 0.3099260330 0.7472054362 422 16.8400000000 1.0246701241 0.5879578648 2.7211656570 0.1958876877 0.0052190000 461454969 0 402718720 0.3833850622 0.3099260330 0.7472054362 423 16.8799999990 1.0269459486 0.5889956617 2.7211656570 0.1956556672 0.0092920000 461533801 0 402718720 0.3833850622 0.3099260330 0.7472054362 424 16.9200000000 1.0291155577 0.5900336803 2.7211656570 0.1954245481 0.0052480000 461612633 0 402718720 0.3833850622 0.3099260330 0.7472054362 425 16.9600000000 1.0312172174 0.5910717592 2.7211656570 0.1951947697 0.0040650000 461691465 0 402718720 0.3833850622 0.3099260330 0.7472054362 426 17.0000000000 1.0333126783 0.5921098834 2.7211656570 0.1949655554 0.0098000000 461770297 0 402718720 0.3833850622 0.3099260330 0.7472054362 427 17.0400000000 1.0355957747 0.5931484921 2.7211656570 0.1947368972 0.0059340000 461849129 0 402718720 0.3833850622 0.3099260330 0.7472054362 428 17.0800000000 1.0371007919 0.5941857638 2.7211656570 0.1945091707 0.0049600000 461927961 0 402718720 0.3833850622 0.3099260330 0.7472054362 429 17.1200000000 1.0392354727 0.5952231757 2.7211656570 0.1942821216 0.0051850000 462006793 0 402718720 0.3833850622 0.3099260330 0.7472054362 430 17.1600000000 1.0416939259 0.5962614798 2.7211656570 0.1940556806 0.0050760000 462085625 0 402718720 0.3833850622 0.3099260330 0.7472054362 431 17.2000000000 1.0439364910 0.5973001689 2.7211656570 0.1938300379 0.0049120000 462164457 0 402718720 0.3833850622 0.3099260330 0.7472054362 432 17.2400000000 1.0460339785 0.5983389046 2.7211656570 0.1936052994 0.0048810000 462243289 0 402718720 0.3833850622 0.3099260330 0.7472054362 433 17.2800000000 1.0486059189 0.5993787822 2.7211656570 0.1933814456 0.0049280000 462322121 0 402718720 0.3833850622 0.3099260330 0.7472054362 434 17.3200000000 1.0507072210 0.6004187095 2.7211656570 0.1931582803 0.0046170000 462400953 0 402718720 0.3833850622 0.3099260330 0.7472054362 435 17.3600000000 1.0530829430 0.6014593169 2.7211656570 0.1929358503 0.0048560000 462479785 0 402718720 0.3833850622 0.3099260330 0.7472054362 436 17.4000000000 1.0550181866 0.6024995895 2.7211656570 0.1927145410 0.0047870000 462558617 0 402718720 0.3833850622 0.3099260330 0.7472054362 437 17.4400000000 1.0568015575 0.6035391821 2.7211656570 0.1924941589 0.0051820000 462637449 0 402718720 0.3833850622 0.3099260330 0.7472054362 438 17.4800000000 1.0586110353 0.6045781590 2.7211656570 0.1922743626 0.0049540000 462716281 0 402718720 0.3833850622 0.3099260330 0.7472054362 439 17.5200000000 1.0596790314 0.6056148352 2.7211656570 0.1920555258 0.0050790000 462795113 0 402718720 0.3833850622 0.3099260330 0.7472054362 440 17.5600000000 1.0613856316 0.6066506779 2.7211656570 0.1918372126 0.0104850000 462873945 0 402718720 0.3833850622 0.3099260330 0.7472054362 441 17.6000000000 1.0629456043 0.6076853603 2.7211656570 0.1916196840 0.0086080000 462952777 0 402718720 0.3833850622 0.3099260330 0.7472054362 442 17.6400000000 1.0650728941 0.6087201737 2.7211656570 0.1914029215 0.0044880000 463031609 0 402718720 0.3833850622 0.3099260330 0.7472054362 443 17.6800000000 1.0669838190 0.6097546289 2.7211656570 0.1911867065 0.0065450000 463110441 0 402718720 0.3833850622 0.3099260330 0.7472054362 444 17.7200000000 1.0689804554 0.6107889213 2.7211656570 0.1909710260 0.0069020000 463189273 0 402718720 0.3833850622 0.3099260330 0.7472054362 445 17.7600000000 1.0710043907 0.6118231134 2.7211656570 0.1907559118 0.0068440000 463268105 0 402718720 0.3833850622 0.3099260330 0.7472054362 446 17.8000000000 1.0731375217 0.6128574506 2.7211656570 0.1905414767 0.0094240000 463346937 0 402718720 0.3833850622 0.3099260330 0.7472054362 447 17.8400000000 1.0750179291 0.6138913667 2.7211656570 0.1903277461 0.0049160000 463425769 0 402718720 0.3833850622 0.3099260330 0.7472054362 448 17.8800000000 1.0768022537 0.6149246499 2.7211656570 0.1901148569 0.0042400000 463504601 0 402718720 0.3833850622 0.3099260330 0.7472054362 449 17.9200000000 1.0785517693 0.6159572270 2.7211656570 0.1899027506 0.0104750000 463583433 0 402718720 0.3833850622 0.3099260330 0.7472054362 450 17.9600000000 1.0825535059 0.6169941076 2.7211656570 0.1896914013 0.0070420000 463662265 0 402718720 0.3833850622 0.3099260330 0.7472054362 451 18.0000000000 1.0845838785 0.6180308921 2.7211656570 0.1894809860 0.0041600000 463741097 0 402718720 0.3833850622 0.3099260330 0.7472054362 452 18.0400000000 1.0867990255 0.6190679897 2.7211656570 0.1892712264 0.0035280000 463819929 0 402718720 0.3833850622 0.3099260330 0.7472054362 453 18.0800000000 1.0888835192 0.6201051101 2.7211656570 0.1890621821 0.0035470000 463898761 0 402718720 0.3833850622 0.3099260330 0.7472054362 454 18.1200000000 1.0912616253 0.6211428998 2.7211656570 0.1888536531 0.0104060000 463977593 0 402718720 0.3833850622 0.3099260330 0.7472054362 455 18.1600000000 1.0936278105 0.6221813281 2.7211656570 0.1886456218 0.0099070000 464056425 0 402718720 0.3833850622 0.3099260330 0.7472054362 456 18.2000000000 1.0958342552 0.6232200407 2.7211656570 0.1884383308 0.0055520000 464135257 0 402718720 0.3833850622 0.3099260330 0.7472054362 457 18.2400000000 1.0981409550 0.6242592549 2.7211656570 0.1882319666 0.0041790000 464214089 0 402718720 0.3833850622 0.3099260330 0.7472054362 458 18.2800000000 1.1006174088 0.6252993382 2.7211656570 0.1880262009 0.0040670000 464292921 0 402718720 0.3833850622 0.3099260330 0.7472054362 459 18.3200000000 1.1032205820 0.6263405610 2.7211656570 0.1878214038 0.0040110000 464371753 0 402718720 0.3833850622 0.3099260330 0.7472054362 460 18.3600000000 1.1056619883 0.6273825641 2.7211656570 0.1876171311 0.0041210000 464450585 0 402718720 0.3833850622 0.3099260330 0.7472054362 461 18.4000000000 1.1083184481 0.6284258090 2.7211656570 0.1874133369 0.0040840000 464529417 0 402718720 0.3833850622 0.3099260330 0.7472054362 462 18.4400000000 1.1106967926 0.6294696856 2.7211656570 0.1872106443 0.0044240000 464608249 0 402718720 0.3833850622 0.3099260330 0.7472054362 463 18.4800000000 1.1132999659 0.6305146754 2.7211656570 0.1870083891 0.0101970000 464687081 0 402718720 0.3833850622 0.3099260330 0.7472054362 464 18.5200000000 1.1160070896 0.6315609952 2.7211656570 0.1868066975 0.0102110000 464765913 0 402718720 0.3833850622 0.3099260330 0.7472054362 465 18.5600000000 1.1187412739 0.6326086947 2.7211656570 0.1866056994 0.0057650000 464844745 0 402718720 0.3833850622 0.3099260330 0.7472054362 466 18.6000000000 1.1218425035 0.6336585527 2.7211656570 0.1864050974 0.0065840000 464923577 0 402718720 0.3833850622 0.3099260330 0.7472054362 467 18.6400000000 1.1247458458 0.6347101315 2.7211656570 0.1862050494 0.0089110000 465002409 0 402718720 0.3833850622 0.3099260330 0.7472054362 468 18.6800000000 1.1276053190 0.6357633263 2.7211656570 0.1860057312 0.0047890000 465081241 0 402718720 0.3833850622 0.3099260330 0.7472054362 469 18.7200000000 1.1302812099 0.6368177355 2.7211656570 0.1858072951 0.0097830000 465160073 0 402718720 0.3833850622 0.3099260330 0.7472054362 470 18.7600000000 1.1332699060 0.6378740167 2.7211656570 0.1856092849 0.0064120000 465238905 0 402718720 0.3833850622 0.3099260330 0.7472054362 471 18.8000000000 1.1357582808 0.6389310958 2.7211656570 0.1854127287 0.0050220000 465317737 0 402718720 0.3833850622 0.3099260330 0.7472054362 472 18.8400000000 1.1384191513 0.6399893332 2.7211656570 0.1852179334 0.0048820000 465396569 0 402718720 0.3833850622 0.3099260330 0.7472054362 473 18.8800000000 1.1414856911 0.6410495792 2.7211656570 0.1850234681 0.0110110000 465475401 0 402718720 0.3833850622 0.3099260330 0.7472054362 474 18.9200000000 1.1445773840 0.6421118742 2.7211656570 0.1848282058 0.0069770000 465554233 0 402718720 0.3833850622 0.3099260330 0.7472054362 475 18.9600000000 1.1472392082 0.6431753001 2.7211656570 0.1846334624 0.0038680000 465633065 0 402718720 0.3833850622 0.3099260330 0.7472054362 476 19.0000000000 1.1497976780 0.6442396328 2.7211656570 0.1844397732 0.0101090000 465711897 0 402718720 0.3833850622 0.3099260330 0.7472054362 477 19.0400000000 1.1522110701 0.6453045625 2.7211656570 0.1842463874 0.0063610000 465790729 0 402718720 0.3833850622 0.3099260330 0.7472054362 478 19.0800000000 1.1543958187 0.6463696070 2.7211656570 0.1840533188 0.0040480000 465869561 0 402718720 0.3833850622 0.3099260330 0.7472054362 479 19.1200000000 1.1570103168 0.6474356627 2.7211656570 0.1838609968 0.0103020000 465948393 0 402718720 0.3833850622 0.3099260330 0.7472054362 480 19.1600000000 1.1593991518 0.6485022533 2.7211656570 0.1836693172 0.0067870000 466027225 0 402718720 0.3833850622 0.3099260330 0.7472054362 481 19.2000000000 1.1617075205 0.6495692081 2.7211656570 0.1834780926 0.0057760000 466106057 0 402718720 0.3833850622 0.3099260330 0.7472054362 482 19.2400000000 1.1641640663 0.6506368323 2.7211656570 0.1832874994 0.0024000000 466184889 0 402718720 0.3833850622 0.3099260330 0.7472054362 483 19.2800000000 1.1664389372 0.6517047456 2.7211656570 0.1830978199 0.0025730000 466263721 0 402718720 0.3833850622 0.3099260330 0.7472054362 484 19.3200000000 1.1682779789 0.6527720457 2.7211656570 0.1829083511 0.0023270000 466342553 0 402718720 0.3833850622 0.3099260330 0.7472054362 485 19.3600000000 1.1698510647 0.6538381880 2.7211656570 0.1827193498 0.0025800000 466428729 0 402718720 0.3833850622 0.3099260330 0.7472054362 486 19.4000000000 1.1714767218 0.6549032878 2.7211656570 0.1825309511 0.0025320000 466507561 0 402718720 0.3833850622 0.3099260330 0.7472054362 487 19.4400000000 1.1731954813 0.6559675428 2.7211656570 0.1823432405 0.0026380000 466586393 0 402718720 0.3833850622 0.3099260330 0.7472054362 488 19.4800000000 1.1749722958 0.6570310772 2.7211656570 0.1821561531 0.0024570000 466665225 0 402718720 0.3833850622 0.3099260330 0.7472054362 489 19.5200000000 1.1767289639 0.6580938540 2.7211656570 0.1819696909 0.0025760000 466744057 0 402718720 0.3833850622 0.3099260330 0.7472054362 490 19.5600000000 1.1783075333 0.6591555146 2.7211656570 0.1817836446 0.0022820000 466822889 0 402718720 0.3833850622 0.3099260330 0.7472054362 491 19.6000000000 1.1803493500 0.6602170092 2.7211656570 0.1815983321 0.0024950000 466901721 0 402718720 0.3833850622 0.3099260330 0.7472054362 492 19.6400000000 1.1815433502 0.6612766156 2.7211656570 0.1814134645 0.0022950000 466980553 0 402718720 0.3833850622 0.3099260330 0.7472054362 493 19.6800000000 1.1832429171 0.6623353707 2.7211656570 0.1812291999 0.0023720000 467059385 0 402718720 0.3833850622 0.3099260330 0.7472054362 494 19.7200000000 1.1843520403 0.6633920846 2.7211656570 0.1810454393 0.0026380000 467138217 0 402718720 0.3833850622 0.3099260330 0.7472054362 495 19.7600000000 1.1868133545 0.6644495013 2.7211656570 0.1808625193 0.0024020000 467217049 0 402718720 0.3833850622 0.3099260330 0.7472054362 496 19.8000000000 1.1895035505 0.6655080781 2.7211656570 0.1806802909 0.0025090000 467295881 0 402718720 0.3833850622 0.3099260330 0.7472054362 497 19.8400000000 1.1913232803 0.6665660563 2.7211656570 0.1804983219 0.0024410000 467374713 0 402718720 0.3833850622 0.3099260330 0.7472054362 498 19.8800000000 1.1921418905 0.6676214295 2.7211656570 0.1803167035 0.0021520000 467453545 0 402718720 0.3833850622 0.3099260330 0.7472054362 499 19.9200000000 1.1935967207 0.6686754882 2.7211656570 0.1801356146 0.0024290000 467532377 0 402718720 0.3833850622 0.3099260330 0.7472054362 500 19.9600000000 1.1948969364 0.6697279311 2.7211656570 0.1799550437 0.0022860000 467611209 0 402718720 0.3833850622 0.3099260330 0.7472054362 501 20.0000000000 1.1978172064 0.6707820015 2.7211656570 0.1797755054 0.0024920000 467690041 0 402718720 0.3833850622 0.3099260330 0.7472054362 502 20.0400000000 1.2008304596 0.6718378749 2.7211656570 0.1795966358 0.0105730000 467768873 0 402718720 0.3833850622 0.3099260330 0.7472054362 503 20.0800000000 1.2025463581 0.6728929614 2.7211656570 0.1794177178 0.0115420000 467847705 0 402718720 0.3833850622 0.3099260330 0.7472054362 504 20.1200000000 1.2039903402 0.6739467260 2.7211656570 0.1792393207 0.0071450000 467926537 0 402718720 0.3833850622 0.3099260330 0.7472054362 505 20.1600000000 1.2058421373 0.6749999843 2.7211656570 0.1790615553 0.0043810000 468005369 0 402718720 0.3833850622 0.3099260330 0.7472054362 506 20.2000000000 1.2077579498 0.6760528656 2.7211656570 0.1788845351 0.0111090000 468084201 0 402718720 0.3833850622 0.3099260330 0.7472054362 507 20.2400000000 1.2104969025 0.6771069959 2.7211656570 0.1787081280 0.0065760000 468163033 0 402718720 0.3833850622 0.3099260330 0.7472054362 508 20.2800000000 1.2126666307 0.6781612471 2.7211656570 0.1785320894 0.0044220000 468241865 0 402718720 0.3833850622 0.3099260330 0.7472054362 509 20.3200000000 1.2139962912 0.6792139682 2.7211656570 0.1783564715 0.0126200000 468320697 0 402718720 0.3833850622 0.3099260330 0.7472054362 510 20.3600000000 1.2155834436 0.6802656731 2.7211656570 0.1781817465 0.0067700000 468399529 0 402718720 0.3833850622 0.3099260330 0.7472054362 511 20.4000000000 1.2176953554 0.6813173946 2.7211656570 0.1780073462 0.0040060000 468478361 0 402718720 0.3833850622 0.3099260330 0.7472054362 512 20.4400000000 1.2197993994 0.6823691172 2.7211656570 0.1778332975 0.0118490000 468557193 0 402718720 0.3833850622 0.3099260330 0.7472054362 513 20.4800000000 1.2205014229 0.6834181081 2.7211656570 0.1776597605 0.0065810000 468636025 0 402718720 0.3833850622 0.3099260330 0.7472054362 514 20.5200000000 1.2228337526 0.6844675549 2.7211656570 0.1774868060 0.0071430000 468817257 0 402718720 0.3833850622 0.3099260330 0.7472054362 515 20.5600000000 1.2245098352 0.6855161806 2.7211656570 0.1773142543 0.0072020000 468896089 0 402718720 0.3833850622 0.3099260330 0.7472054362 516 20.6000000000 1.2256041765 0.6865628628 2.7211656570 0.1771422845 0.0055730000 468974921 0 402718720 0.3833850622 0.3099260330 0.7472054362 517 20.6400000000 1.2265362740 0.6876072988 2.7211656570 0.1769706862 0.0058410000 469053753 0 402718720 0.3833850622 0.3099260330 0.7472054362 518 20.6800000000 1.2276055813 0.6886497665 2.7211656570 0.1767996603 0.0045950000 469132585 0 402718720 0.3833850622 0.3099260330 0.7472054362 519 20.7200000000 1.2290766239 0.6896910514 2.7211656570 0.1766291854 0.0026690000 469211417 0 402718720 0.3833850622 0.3099260330 0.7472054362 520 20.7600000000 1.2308069468 0.6907316589 2.7211656570 0.1764590805 0.0024510000 469290249 0 402718720 0.3833850622 0.3099260330 0.7472054362 521 20.8000000000 1.2319349051 0.6917704367 2.7211656570 0.1762894426 0.0028200000 469369081 0 402718720 0.3833850622 0.3099260330 0.7472054362 522 20.8400000000 1.2332700491 0.6928077923 2.7211656570 0.1761204552 0.0031840000 469447913 0 402718720 0.3833850622 0.3099260330 0.7472054362 523 20.8800000000 1.2347246408 0.6938439622 2.7211656570 0.1759517384 0.0085060000 469526745 0 402718720 0.3833850622 0.3099260330 0.7472054362 524 20.9200000000 1.2366726398 0.6948798948 2.7211656570 0.1757835468 0.0023650000 469605577 0 402718720 0.3833850622 0.3099260330 0.7472054362 525 20.9600000000 1.2383079529 0.6959149958 2.7211656570 0.1756158745 0.0024010000 469684409 0 402718720 0.3833850622 0.3099260330 0.7472054362 526 21.0000000000 1.2397897243 0.6969489782 2.7211656570 0.1754487668 0.0105430000 469763241 0 402718720 0.3833850622 0.3099260330 0.7472054362 527 21.0400000000 1.2410782576 0.6979814816 2.7211656570 0.1752822768 0.0113450000 469842073 0 402718720 0.3833850622 0.3099260330 0.7472054362 528 21.0800000000 1.2420912981 0.6990119926 2.7211656570 0.1751164258 0.0056860000 469920905 0 402718720 0.3833850622 0.3099260330 0.7472054362 529 21.1200000000 1.2435642481 0.7000413920 2.7211656570 0.1749511607 0.0053970000 469999737 0 402718720 0.3833850622 0.3099260330 0.7472054362 530 21.1600000000 1.2452841997 0.7010701520 2.7211656570 0.1747863592 0.0099890000 470078569 0 402718720 0.3833850622 0.3099260330 0.7472054362 531 21.2000000000 1.2465374470 0.7020973974 2.7211656570 0.1746218521 0.0060840000 470157401 0 402718720 0.3833850622 0.3099260330 0.7472054362 532 21.2400000000 1.2478171587 0.7031231864 2.7211656570 0.1744577800 0.0074320000 470236233 0 402718720 0.3833850622 0.3099260330 0.7472054362 533 21.2800000000 1.2490720749 0.7041474807 2.7211656570 0.1742941454 0.0053160000 470315065 0 402718720 0.3833850622 0.3099260330 0.7472054362 534 21.3200000000 1.2501912117 0.7051700345 2.7211656570 0.1741308938 0.0041480000 470393897 0 402718720 0.3833850622 0.3099260330 0.7472054362 535 21.3600000000 1.2515244484 0.7061912577 2.7211656570 0.1739681027 0.0040800000 470472729 0 402718720 0.3833850622 0.3099260330 0.7472054362 536 21.4000000000 1.2527482510 0.7072109536 2.7211656570 0.1738059035 0.0041860000 470551561 0 402718720 0.3833850622 0.3099260330 0.7472054362 537 21.4400000000 1.2540925741 0.7082293551 2.7211656570 0.1736439938 0.0104170000 470630393 0 402718720 0.3833850622 0.3099260330 0.7472054362 538 21.4800000000 1.2548280954 0.7092453379 2.7211656570 0.1734826936 0.0101810000 470709225 0 402718720 0.3833850622 0.3099260330 0.7472054362 539 21.5200000000 1.2560346127 0.7102597893 2.7211656570 0.1733219267 0.0054690000 470788057 0 402718720 0.3833850622 0.3099260330 0.7472054362 540 21.5600000000 1.2570966482 0.7112724501 2.7211656570 0.1731614387 0.0068600000 470866889 0 402718720 0.3833850622 0.3099260330 0.7472054362 541 21.6000000000 1.2584376335 0.7122838460 2.7211656570 0.1730014810 0.0055240000 470945721 0 402718720 0.3833850622 0.3099260330 0.7472054362 542 21.6400000000 1.2598023415 0.7132940278 2.7211656570 0.1728419918 0.0052950000 471024553 0 402718720 0.3833850622 0.3099260330 0.7472054362 543 21.6800000000 1.2613191605 0.7143032821 2.7211656570 0.1726829987 0.0108310000 471103385 0 402718720 0.3833850622 0.3099260330 0.7472054362 544 21.7200000000 1.2628712654 0.7153116792 2.7211656570 0.1725244315 0.0060430000 471105425 0 402718720 0.3833850622 0.3099260330 0.7472054362 545 21.7600000000 1.2641171217 0.7163186616 2.7211656570 0.1723663860 0.0044610000 471184257 0 402718720 0.3833850622 0.3099260330 0.7472054362 546 21.8000000000 1.2653372288 0.7173241902 2.7211656570 0.1722089534 0.0109090000 471263089 0 402718720 0.3833850622 0.3099260330 0.7472054362 547 21.8400000000 1.2664475441 0.7183280720 2.7211656570 0.1720523001 0.0065360000 471341921 0 402718720 0.3833850622 0.3099260330 0.7472054362 548 21.8800000000 1.2679103613 0.7193309594 2.7211656570 0.1718958623 0.0040180000 471420753 0 402718720 0.3833850622 0.3099260330 0.7472054362 549 21.9200000000 1.2698010206 0.7203336371 2.7211656570 0.1717404495 0.0035040000 471499585 0 402718720 0.3833850622 0.3099260330 0.7472054362 550 21.9600000000 1.2712978125 0.7213353901 2.7211656570 0.1715848274 0.0103280000 471578417 0 402718720 0.3833850622 0.3099260330 0.7472054362 551 22.0000000000 1.2725319862 0.7223357469 2.7211656570 0.1714294315 0.0087960000 471657249 0 402718720 0.3833850622 0.3099260330 0.7472054362 552 22.0400000000 1.2738733292 0.7233349092 2.7211656570 0.1712743161 0.0045200000 471736081 0 402718720 0.3833850622 0.3099260330 0.7472054362 553 22.0800000000 1.2755239010 0.7243334426 2.7211656570 0.1711199843 0.0067390000 471814913 0 402718720 0.3833850622 0.3099260330 0.7472054362 554 22.1200000000 1.2765599489 0.7253302414 2.7211656570 0.1709658771 0.0070580000 471893745 0 402718720 0.3833850622 0.3099260330 0.7472054362 555 22.1600000000 1.2774074078 0.7263249750 2.7211656570 0.1708119561 0.0070290000 471972577 0 402718720 0.3833850622 0.3099260330 0.7472054362 556 22.2000000000 1.2783513069 0.7273178281 2.7211656570 0.1706584719 0.0066770000 472051409 0 402718720 0.3833850622 0.3099260330 0.7472054362 557 22.2400000000 1.2794605494 0.7283091077 2.7211656570 0.1705052909 0.0091480000 472130241 0 402718720 0.3833850622 0.3099260330 0.7472054362 558 22.2800000000 1.2799961567 0.7292977942 2.7211656570 0.1703524394 0.0061590000 472209073 0 402718720 0.3833850622 0.3099260330 0.7472054362 559 22.3200000000 1.2810590267 0.7302848447 2.7211656570 0.1702000804 0.0066640000 472287905 0 402718720 0.3833850622 0.3099260330 0.7472054362 560 22.3600000000 1.2818655968 0.7312698103 2.7211656570 0.1700479817 0.0091920000 472366737 0 402718720 0.3833850622 0.3099260330 0.7472054362 561 22.4000000000 1.2825473547 0.7322524797 2.7211656570 0.1698963259 0.0051340000 472445569 0 402718720 0.3833850622 0.3099260330 0.7472054362 562 22.4400000000 1.2836155891 0.7332335529 2.7211656570 0.1697450682 0.0100280000 472524401 0 402718720 0.3833850622 0.3099260330 0.7472054362 563 22.4800000000 1.2843418121 0.7342124308 2.7211656570 0.1695942032 0.0054570000 472603233 0 402718720 0.3833850622 0.3099260330 0.7472054362 564 22.5200000000 1.2849196196 0.7351888620 2.7211656570 0.1694437941 0.0118350000 472682065 0 402718720 0.3833850622 0.3099260330 0.7472054362 565 22.5600000000 1.2861307859 0.7361639804 2.7211656570 0.1692939087 0.0052900000 472760897 0 402718720 0.3833850622 0.3099260330 0.7472054362 566 22.6000000000 1.2865587473 0.7371364093 2.7211656570 0.1691442930 0.0037150000 472762905 0 402718720 0.3833850622 0.3099260330 0.7472054362 567 22.6400000000 1.2875478268 0.7381071526 2.7211656570 0.1689950931 0.0098820000 472841737 0 402718720 0.3833850622 0.3099260330 0.7472054362 568 22.6800000000 1.2882199287 0.7390756610 2.7211656570 0.1688463188 0.0053940000 472843745 0 402718720 0.3833850622 0.3099260330 0.7472054362 569 22.7200000000 1.2889393568 0.7400420295 2.7211656570 0.1686981324 0.0041470000 472922577 0 402718720 0.3833850622 0.3099260330 0.7472054362 570 22.7600000000 1.2897520065 0.7410064330 2.7211656570 0.1685502524 0.0041020000 473001409 0 402718720 0.3833850622 0.3099260330 0.7472054362 571 22.8000000000 1.2907146215 0.7419691443 2.7211656570 0.1684030941 0.0105320000 473080241 0 402718720 0.3833850622 0.3099260330 0.7472054362 572 22.8400000000 1.2912966013 0.7429295070 2.7211656570 0.1682561751 0.0084330000 473159073 0 402718720 0.3833850622 0.3099260330 0.7472054362 573 22.8800000000 1.2923045158 0.7438882767 2.7211656570 0.1681096980 0.0048620000 473237905 0 402718720 0.3833850622 0.3099260330 0.7472054362 574 22.9200000000 1.2932217121 0.7448453036 2.7211656570 0.1679635984 0.0060150000 473239913 0 402718720 0.3833850622 0.3099260330 0.7472054362 575 22.9600000000 1.2940922976 0.7458005157 2.7211656570 0.1678178393 0.0072020000 473318745 0 402718720 0.3833850622 0.3099260330 0.7472054362 576 23.0000000000 1.2953538895 0.7467546015 2.7211656570 0.1676726727 0.0071980000 473397577 0 402718720 0.3833850622 0.3099260330 0.7472054362 577 23.0400000000 1.2961053848 0.7477066825 2.7211656570 0.1675277864 0.0047480000 473399585 0 402718720 0.3833850622 0.3099260330 0.7472054362 578 23.0800000000 1.2970573902 0.7486571163 2.7211656570 0.1673832260 0.0106610000 473478417 0 402718720 0.3833850622 0.3099260330 0.7472054362 579 23.1200000000 1.2980070114 0.7496059071 2.7211656570 0.1672389333 0.0056070000 473480425 0 402718720 0.3833850622 0.3099260330 0.7472054362 580 23.1600000000 1.2989379168 0.7505530313 2.7211656570 0.1670949945 0.0056270000 473559257 0 402718720 0.3833850622 0.3099260330 0.7472054362 581 23.2000000000 1.2996761799 0.7514981658 2.7211656570 0.1669513568 0.0063080000 473561265 0 402718720 0.3833850622 0.3099260330 0.7472054362 582 23.2400000000 1.2999488115 0.7524405208 2.7211656570 0.1668080432 0.0023000000 473563273 0 402718720 0.3833850622 0.3099260330 0.7472054362 583 23.2800000000 1.3001629114 0.7533800104 2.7211656570 0.1666652028 0.0157410000 473642105 0 402718720 0.3833850622 0.3099260330 0.7472054362 584 23.3200000000 1.3013225794 0.7543182682 2.7211656570 0.1665226733 0.0078030000 473720937 0 402718720 0.3833850622 0.3099260330 0.7472054362 585 23.3600000000 1.3012099266 0.7552531257 2.7211656570 0.1663806199 0.0060290000 473799769 0 402718720 0.3833850622 0.3099260330 0.7472054362 586 23.4000000000 1.3015637398 0.7561853964 2.7211656570 0.1662390820 0.0049240000 473878601 0 402718720 0.3833850622 0.3099260330 0.7472054362 587 23.4400000000 1.3020571470 0.7571153312 2.7211656570 0.1660977153 0.0050410000 473957433 0 402718720 0.3833850622 0.3099260330 0.7472054362 588 23.4800000000 1.3018487692 0.7580417486 2.7211656570 0.1659567112 0.0128060000 474036265 0 402718720 0.3833850622 0.3099260330 0.7472054362 589 23.5200000000 1.3022675514 0.7589657313 2.7211656570 0.1658160847 0.0055110000 474115097 0 402718720 0.3833850622 0.3099260330 0.7472054362 590 23.5600000000 1.3026106358 0.7598871634 2.7211656570 0.1656757630 0.0036670000 474193929 0 402718720 0.3833850622 0.3099260330 0.7472054362 591 23.6000000000 1.3030169010 0.7608061646 2.7211656570 0.1655357358 0.0031780000 474272761 0 402718720 0.3833850622 0.3099260330 0.7472054362 592 23.6400000000 1.3034995794 0.7617228765 2.7211656570 0.1653962857 0.0030520000 474351593 0 402718720 0.3833850622 0.3099260330 0.7472054362 593 23.6800000000 1.3037154675 0.7626368606 2.7211656570 0.1652569906 0.0034080000 474430425 0 402718720 0.3833850622 0.3099260330 0.7472054362 594 23.7200000000 1.3042957783 0.7635487443 2.7211656570 0.1651179080 0.0030310000 474509257 0 402718720 0.3833850622 0.3099260330 0.7472054362 595 23.7600000000 1.3045918941 0.7644580605 2.7211656570 0.1649792498 0.0033520000 474588089 0 402718720 0.3833850622 0.3099260330 0.7472054362 596 23.8000000000 1.3052020073 0.7653653490 2.7211656570 0.1648410337 0.0051720000 474666921 0 402718720 0.3833850622 0.3099260330 0.7472054362 597 23.8400000000 1.3050546646 0.7662693512 2.7211656570 0.1647030141 0.0136220000 474745753 0 402718720 0.3833850622 0.3099260330 0.7472054362 598 23.8800000000 1.3054215908 0.7671709436 2.7211656570 0.1645653227 0.0106150000 474824585 0 402718720 0.3833850622 0.3099260330 0.7472054362 599 23.9200000000 1.3056100607 0.7680698403 2.7211656570 0.1644278897 0.0058310000 474903417 0 402718720 0.3833850622 0.3099260330 0.7472054362 600 23.9600000000 1.3059058189 0.7689662336 2.7211656570 0.1642908183 0.0038080000 474982249 0 402718720 0.3833850622 0.3099260330 0.7472054362 601 24.0000000000 1.3061077595 0.7698599799 2.7211656570 0.1641541781 0.0029430000 475061081 0 402718720 0.3833850622 0.3099260330 0.7472054362 602 24.0400000000 1.3062223196 0.7707509472 2.7211656570 0.1640179561 0.0028230000 475139913 0 402718720 0.3833850622 0.3099260330 0.7472054362 603 24.0800000000 1.3061152697 0.7716387819 2.7211656570 0.1638822561 0.0032450000 475218745 0 402718720 0.3833850622 0.3099260330 0.7472054362 604 24.1200000000 1.3059973717 0.7725234816 2.7211656570 0.1637467985 0.0028890000 475297577 0 402718720 0.3833850622 0.3099260330 0.7472054362 605 24.1600000000 1.3062198162 0.7734056243 2.7211656570 0.1636115827 0.0036720000 475376409 0 402718720 0.3833850622 0.3099260330 0.7472054362 606 24.2000000000 1.3062443733 0.7742848961 2.7211656570 0.1634765209 0.0041060000 475455241 0 402718720 0.3833850622 0.3099260330 0.7472054362 607 24.2400000000 1.3061562777 0.7751611258 2.7211656570 0.1633417488 0.0109040000 475534073 0 402718720 0.3833850622 0.3099260330 0.7472054362 608 24.2800000000 1.3060052395 0.7760342246 2.7211656570 0.1632072715 0.0107380000 475612905 0 402718720 0.3833850622 0.3099260330 0.7472054362 609 24.3200000000 1.3066706657 0.7769055488 2.7211656570 0.1630731729 0.0051690000 475691737 0 402718720 0.3833850622 0.3099260330 0.7472054362 610 24.3600000000 1.3068425655 0.7777742981 2.7211656570 0.1629395588 0.0050930000 475770569 0 402718720 0.3833850622 0.3099260330 0.7472054362 611 24.4000000000 1.3068170547 0.7786401618 2.7211656570 0.1628061892 0.0053400000 475849401 0 402718720 0.3833850622 0.3099260330 0.7472054362 612 24.4400000000 1.3071354628 0.7795037162 2.7211656570 0.1626732483 0.0157680000 475928233 0 402718720 0.3833850622 0.3099260330 0.7472054362 613 24.4800000000 1.3063215017 0.7803631253 2.7211656570 0.1625404894 0.0085020000 476007065 0 402718720 0.3833850622 0.3099260330 0.7472054362 614 24.5200000000 1.3063299656 0.7812197489 2.7211656570 0.1624082147 0.0058680000 476085897 0 402718720 0.3833850622 0.3099260330 0.7472054362 615 24.5600000000 1.3072035313 0.7820750070 2.7211656570 0.1622766760 0.0043070000 476164729 0 402718720 0.3833850622 0.3099260330 0.7472054362 616 24.6000000000 1.3081097603 0.7829289596 2.7211656570 0.1621454162 0.0033890000 476243561 0 402718720 0.3833850622 0.3099260330 0.7472054362 617 24.6400000000 1.3078721762 0.7837797589 2.7211656570 0.1620142404 0.0037200000 476322393 0 402718720 0.3833850622 0.3099260330 0.7472054362 618 24.6800000000 1.3078968525 0.7846278448 2.7211656570 0.1618833002 0.0037340000 476401225 0 402718720 0.3833850622 0.3099260330 0.7472054362 619 24.7200000000 1.3079701662 0.7854733090 2.7211656570 0.1617530118 0.0175230000 476480057 0 402718720 0.3833850622 0.3099260330 0.7472054362 620 24.7600000000 1.3085589409 0.7863169955 2.7211656570 0.1616228819 0.0101820000 476558889 0 402718720 0.3833850622 0.3099260330 0.7472054362 621 24.8000000000 1.3084132671 0.7871577303 2.7211656570 0.1614926773 0.0058300000 476637721 0 402718720 0.3833850622 0.3099260330 0.7472054362 622 24.8400000000 1.3080896139 0.7879952413 2.7211656570 0.1613626769 0.0049170000 476716553 0 402718720 0.3833850622 0.3099260330 0.7472054362 623 24.8800000000 1.3077681065 0.7888295477 2.7211656570 0.1612330009 0.0044020000 476795385 0 402718720 0.3833850622 0.3099260330 0.7472054362 624 24.9200000000 1.3080996275 0.7896617113 2.7211656570 0.1611036757 0.0038480000 476874217 0 402718720 0.3833850622 0.3099260330 0.7472054362 625 24.9600000000 1.3072110415 0.7904897902 2.7211656570 0.1609747088 0.0042200000 476953049 0 402718720 0.3833850622 0.3099260330 0.7472054362 626 25.0000000000 1.3065338135 0.7913141417 2.7211656570 0.1608459650 0.0037070000 477031881 0 402718720 0.3833850622 0.3099260330 0.7472054362 627 25.0400000000 1.3063489199 0.7921355688 2.7211656570 0.1607175951 0.0038370000 477110713 0 402718720 0.3833850622 0.3099260330 0.7472054362 628 25.0800000000 1.3055676222 0.7929531357 2.7211656570 0.1605895760 0.0035000000 477189545 0 402718720 0.3833850622 0.3099260330 0.7472054362 629 25.1200000000 1.3048163652 0.7937669087 2.7211656570 0.1604617783 0.0032280000 477268377 0 402718720 0.3833850622 0.3099260330 0.7472054362 630 25.1600000000 1.3043346405 0.7945773337 2.7211656570 0.1603341965 0.0041620000 477347209 0 402718720 0.3833850622 0.3099260330 0.7472054362 631 25.2000000000 1.3033509254 0.7953836310 2.7211656570 0.1602069061 0.0044700000 477426041 0 402718720 0.3833850622 0.3099260330 0.7472054362 632 25.2400000000 1.3025977612 0.7961861850 2.7211656570 0.1600799669 0.0042770000 477504873 0 402718720 0.3833850622 0.3099260330 0.7472054362 633 25.2800000000 1.3016653061 0.7969847302 2.7211656570 0.1599533375 0.0042730000 477583705 0 402718720 0.3833850622 0.3099260330 0.7472054362 634 25.3200000000 1.3002980947 0.7977785999 2.7211656570 0.1598269667 0.0171350000 477662537 0 402718720 0.3833850622 0.3099260330 0.7472054362 635 25.3600000000 0.6269755363 0.7975096187 2.7211656570 0.1672264947 0.0298240000 477741369 0 402718720 -0.0127204871 -0.2858396471 0.1560840905 636 25.4000000000 0.6365298033 0.7972565058 2.7211656570 0.1670965193 0.0302570000 475534809 0 402718720 0.0003718459 -0.2973985672 0.1568837464 637 25.4400000000 0.6355710626 0.7970026825 2.7211656570 0.1669651114 0.0051410000 490589041 0 402718720 0.0003718459 -0.2973985672 0.1568837464 638 25.4800000000 0.6341212392 0.7967473824 2.7211656570 0.1668340120 0.0045740000 493936889 0 402718720 0.0003718459 -0.2973985672 0.1568837464 639 25.5200000000 0.6333927512 0.7964917413 2.7211656570 0.1667032411 0.0042710000 494015721 0 402718720 0.0003718459 -0.2973985672 0.1568837464 640 25.5600000000 0.6323594451 0.7962352846 2.7211656570 0.1665727682 0.0044200000 494094553 0 402718720 0.0003718459 -0.2973985672 0.1568837464 641 25.6000000000 0.6312209368 0.7959778520 2.7211656570 0.1664425955 0.0042120000 494173385 0 402718720 0.0003718459 -0.2973985672 0.1568837464 642 25.6400000000 0.6302996874 0.7957197863 2.7211656570 0.1663127163 0.0034780000 494252217 0 402718720 0.0003718459 -0.2973985672 0.1568837464 643 25.6800000000 0.6296911836 0.7954615769 2.7211656570 0.1661831686 0.0032980000 494331049 0 402718720 0.0003718459 -0.2973985672 0.1568837464 644 25.7200000000 0.6282219291 0.7952018880 2.7211656570 0.1660538952 0.0030500000 494409881 0 402718720 0.0003718459 -0.2973985672 0.1568837464 645 25.7600000000 0.6266191602 0.7949405195 2.7211656570 0.1659249263 0.0036710000 494488713 0 402718720 0.0003718459 -0.2973985672 0.1568837464 646 25.8000000000 0.6258447170 0.7946787613 2.7211656570 0.1657963409 0.0034720000 494567545 0 402718720 0.0003718459 -0.2973985672 0.1568837464 647 25.8400000000 0.6246351600 0.7944159427 2.7211656570 0.1656679897 0.0033490000 494646377 0 402718720 0.0003718459 -0.2973985672 0.1568837464 648 25.8800000000 0.6231210828 0.7941515988 2.7211656570 0.1655399126 0.0164730000 494725209 0 402718720 0.0003718459 -0.2973985672 0.1568837464 649 25.9200000000 0.6219178438 0.7938862155 2.7211656570 0.1654121620 0.0133270000 494804041 0 402718720 0.0003718459 -0.2973985672 0.1568837464 650 25.9600000000 0.6209072471 0.7936200940 2.7211656570 0.1652847659 0.0074380000 494882873 0 402718720 0.0003718459 -0.2973985672 0.1568837464 651 26.0000000000 0.6201010346 0.7933535517 2.7211656570 0.1651576409 0.0069960000 494961705 0 402718720 0.0003718459 -0.2973985672 0.1568837464 652 26.0400000000 0.6196894050 0.7930871956 2.7211656570 0.1650307841 0.0044760000 495040537 0 402718720 0.0003718459 -0.2973985672 0.1568837464 653 26.0800000000 0.6188763976 0.7928204103 2.7211656570 0.1649042034 0.0036160000 495119369 0 402718720 0.0003718459 -0.2973985672 0.1568837464 654 26.1200000000 0.6162435412 0.7925504151 2.7211656570 0.1647781997 0.0159130000 495198201 0 402718720 0.0003718459 -0.2973985672 0.1568837464 655 26.1600000000 0.6150919199 0.7922794861 2.7211656570 0.1646521897 0.0081280000 495277033 0 402718720 0.0003718459 -0.2973985672 0.1568837464 656 26.2000000000 0.6137632728 0.7920073578 2.7211656570 0.1645265383 0.0058300000 495355865 0 402718720 0.0003718459 -0.2973985672 0.1568837464 657 26.2400000000 0.6121528149 0.7917336065 2.7211656570 0.1644011226 0.0042470000 495434697 0 402718720 0.0003718459 -0.2973985672 0.1568837464 658 26.2800000000 0.6109679937 0.7914588868 2.7211656570 0.1642759724 0.0039170000 495513529 0 402718720 0.0003718459 -0.2973985672 0.1568837464 659 26.3200000000 0.6105069518 0.7911843011 2.7211656570 0.1641511130 0.0037860000 495592361 0 402718720 0.0003718459 -0.2973985672 0.1568837464 660 26.3600000000 0.6090245843 0.7909083016 2.7211656570 0.1640265286 0.0116050000 495671193 0 402718720 0.0003718459 -0.2973985672 0.1568837464 661 26.4000000000 0.6071106195 0.7906302415 2.7211656570 0.1639022566 0.0036100000 495750025 0 402718720 0.0003718459 -0.2973985672 0.1568837464 662 26.4400000000 0.6060864329 0.7903514744 2.7211656570 0.1637783002 0.0041840000 495828857 0 402718720 0.0003718459 -0.2973985672 0.1568837464 663 26.4800000000 0.6048334837 0.7900716585 2.7211656570 0.1636546438 0.0037390000 495907689 0 402718720 0.0003718459 -0.2973985672 0.1568837464 664 26.5200000000 0.6030419469 0.7897899872 2.7211656570 0.1635313342 0.0172410000 495986521 0 402718720 0.0003718459 -0.2973985672 0.1568837464 665 26.5600000000 0.6016497016 0.7895070695 2.7211656570 0.1634082957 0.0091700000 496065353 0 402718720 0.0003718459 -0.2973985672 0.1568837464 666 26.6000000000 0.6004564762 0.7892232097 2.7211656570 0.1632856676 0.0059400000 496144185 0 402718720 0.0003718459 -0.2973985672 0.1568837464 667 26.6400000000 0.5995761156 0.7889388813 2.7211656570 0.1631632402 0.0062030000 496223017 0 402718720 0.0003718459 -0.2973985672 0.1568837464 668 26.6800000000 0.5983939767 0.7886536344 2.7211656570 0.1630411465 0.0091740000 496301849 0 402718720 0.0003718459 -0.2973985672 0.1568837464 669 26.7200000000 0.5974745154 0.7883678659 2.7211656570 0.1629193449 0.0060930000 496380681 0 402718720 0.0003718459 -0.2973985672 0.1568837464 670 26.7600000000 0.5970048904 0.7880822495 2.7211656570 0.1627980813 0.0115660000 496459513 0 402718720 0.0003718459 -0.2973985672 0.1568837464 671 26.8000000000 0.5970330834 0.7877975265 2.7211656570 0.1626769645 0.0075820000 496538345 0 402718720 0.0003718459 -0.2973985672 0.1568837464 672 26.8400000000 0.5961913466 0.7875123982 2.7211656570 0.1625558943 0.0052650000 496617177 0 402718720 0.0003718459 -0.2973985672 0.1568837464 673 26.8800000000 0.5955442190 0.7872271558 2.7211656570 0.1624352331 0.0045180000 496696009 0 402718720 0.0003718459 -0.2973985672 0.1568837464 674 26.9200000000 0.5957438946 0.7869430560 2.7211656570 0.1623147774 0.0037440000 496774841 0 402718720 0.0003718459 -0.2973985672 0.1568837464 675 26.9600000000 0.5962753892 0.7866605854 2.7211656570 0.1621943361 0.0047450000 496853673 0 402718720 0.0003718459 -0.2973985672 0.1568837464 676 27.0000000000 0.5952408314 0.7863774200 2.7211656570 0.1620741719 0.0047040000 496932505 0 402718720 0.0003718459 -0.2973985672 0.1568837464 677 27.0400000000 0.5957977772 0.7860959139 2.7211656570 0.1619543413 0.0047380000 497011337 0 402718720 0.0003718459 -0.2973985672 0.1568837464 678 27.0800000000 0.5958229899 0.7858152754 2.7211656570 0.1618347200 0.0196690000 497090169 0 402718720 0.0003718459 -0.2973985672 0.1568837464 679 27.1200000000 0.5962564349 0.7855361018 2.7211656570 0.1617153741 0.0145450000 497169001 0 402718720 0.0003718459 -0.2973985672 0.1568837464 680 27.1600000000 0.5971837044 0.7852591130 2.7211656570 0.1615963126 0.0065970000 497247833 0 402718720 0.0003718459 -0.2973985672 0.1568837464 681 27.2000000000 0.5978171229 0.7849838678 2.7211656570 0.1614775504 0.0066710000 497326665 0 402718720 0.0003718459 -0.2973985672 0.1568837464 682 27.2400000000 0.5987319946 0.7847107712 2.7211656570 0.1613590723 0.0044830000 497405497 0 402718720 0.0003718459 -0.2973985672 0.1568837464 683 27.2800000000 0.5994393229 0.7844395100 2.7211656570 0.1612407996 0.0045510000 497484329 0 402718720 0.0003718459 -0.2973985672 0.1568837464 684 27.3200000000 0.6005597115 0.7841706798 2.7211656570 0.1611227965 0.0194380000 497563161 0 402718720 0.0003718459 -0.2973985672 0.1568837464 685 27.3600000000 0.6002780795 0.7839022235 2.7211656570 0.1610050130 0.0093350000 497641993 0 402718720 0.0003718459 -0.2973985672 0.1568837464 686 27.4000000000 0.6010499597 0.7836356750 2.7211656570 0.1608875303 0.0070170000 497720825 0 402718720 0.0003718459 -0.2973985672 0.1568837464 687 27.4400000000 0.6025086641 0.7833720258 2.7211656570 0.1607703761 0.0246850000 497799657 0 402718720 0.0003718459 -0.2973985672 0.1568837464 688 27.4800000000 0.6038893461 0.7831111498 2.7211656570 0.1606534230 0.0154990000 497878489 0 402718720 0.0003718459 -0.2973985672 0.1568837464 689 27.5200000000 0.6053428054 0.7828531406 2.7211656570 0.1605367308 0.0069080000 497957321 0 402718720 0.0003718459 -0.2973985672 0.1568837464 690 27.5600000000 0.6074350476 0.7825989115 2.7211656570 0.1604203328 0.0059080000 498036153 0 402718720 0.0003718459 -0.2973985672 0.1568837464 691 27.6000000000 0.6096916795 0.7823486839 2.7211656570 0.1603041627 0.0053390000 498114985 0 402718720 0.0003718459 -0.2973985672 0.1568837464 692 27.6400000000 0.6117016077 0.7821020841 2.7211656570 0.1601883996 0.0202240000 498193817 0 402718720 0.0003718459 -0.2973985672 0.1568837464 693 27.6800000000 0.6128250957 0.7818578172 2.7211656570 0.1600729027 0.0095140000 498272649 0 402718720 0.0003718459 -0.2973985672 0.1568837464 694 27.7200000000 0.6144722700 0.7816166276 2.7211656570 0.1599575867 0.0050870000 498351481 0 402718720 0.0003718459 -0.2973985672 0.1568837464 695 27.7600000000 0.6157529950 0.7813779749 2.7211656570 0.1598424518 0.0179400000 498430313 0 402718720 0.0003718459 -0.2973985672 0.1568837464 696 27.8000000000 0.6168496609 0.7811415837 2.7211656570 0.1597275343 0.0091990000 498509145 0 402718720 0.0003718459 -0.2973985672 0.1568837464 697 27.8400000000 0.6212793589 0.7809122261 2.7211656570 0.1596129605 0.0071110000 498587977 0 402718720 0.0003718459 -0.2973985672 0.1568837464 698 27.8800000000 0.6221469045 0.7806847686 2.7211656570 0.1594984879 0.0056160000 498666809 0 402718720 0.0003718459 -0.2973985672 0.1568837464 699 27.9200000000 0.6254712939 0.7804627179 2.7211656570 0.1593844171 0.0054480000 498745641 0 402718720 0.0003718459 -0.2973985672 0.1568837464 700 27.9600000000 0.6269382238 0.7802433971 2.7211656570 0.1592704105 0.0052440000 498824473 0 402718720 0.0003718459 -0.2973985672 0.1568837464 701 28.0000000000 0.6275736690 0.7800256087 2.7211656570 0.1591566619 0.0198160000 498903305 0 402718720 0.0003718459 -0.2973985672 0.1568837464 702 28.0400000000 0.6284820437 0.7798097346 2.7211656570 0.1590432301 0.0096250000 498982137 0 402718720 0.0003718459 -0.2973985672 0.1568837464 703 28.0800000000 0.6303339005 0.7795971090 2.7211656570 0.1589301204 0.0074420000 499060969 0 402718720 0.0003718459 -0.2973985672 0.1568837464 704 28.1200000000 0.6316499710 0.7793869568 2.7211656570 0.1588171094 0.0065030000 499139801 0 402718720 0.0003718459 -0.2973985672 0.1568837464 705 28.1600000000 0.6324589849 0.7791785483 2.7211656570 0.1587043100 0.0058190000 499218633 0 402718720 0.0003718459 -0.2973985672 0.1568837464 706 28.2000000000 0.6334775686 0.7789721730 2.7211656570 0.1585918786 0.0144110000 499297465 0 402718720 0.0003718459 -0.2973985672 0.1568837464 707 28.2400000000 0.6352686882 0.7787689149 2.7211656570 0.1584796883 0.0088570000 499376297 0 402718720 0.0003718459 -0.2973985672 0.1568837464 708 28.2800000000 0.6367694736 0.7785683507 2.7211656570 0.1583676355 0.0061850000 499455129 0 402718720 0.0003718459 -0.2973985672 0.1568837464 709 28.3200000000 0.6370256543 0.7783687136 2.7211656570 0.1582558098 0.0134990000 499533961 0 402718720 0.0003718459 -0.2973985672 0.1568837464 710 28.3600000000 0.6374554038 0.7781702442 2.7211656570 0.1581442468 0.0144560000 499612793 0 402718720 0.0003718459 -0.2973985672 0.1568837464 711 28.4000000000 0.6389276385 0.7779744037 2.7211656570 0.1580328979 0.0082220000 499691625 0 402718720 0.0003718459 -0.2973985672 0.1568837464 712 28.4400000000 0.6388759017 0.7777790406 2.7211656570 0.1579218097 0.0068430000 499770457 0 402718720 0.0003718459 -0.2973985672 0.1568837464 713 28.4800000000 0.7777988315 0.7777790684 2.7211656570 0.1662652705 0.0261570000 499849289 0 402718720 -0.7350735664 -0.1870352477 -0.5514563918 714 28.5200000000 0.9570117593 0.7780300945 2.7211656570 0.1664126331 0.0254090000 497640313 0 402718720 -0.8796495199 -0.3255025744 -0.5656731129 715 28.5600000000 1.2919434309 0.7787488544 2.7211656570 0.1669349723 0.0160850000 511391393 0 402718720 -1.1213115454 -0.6196975112 -0.3227137625 716 28.6000000000 1.4448033571 0.7796790982 2.7211656570 0.1670156259 0.0263100000 513757529 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 717 28.6400000000 1.4470903873 0.7806099368 2.7211656570 0.1668992879 0.0049850000 527508673 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 718 28.6800000000 1.4493637085 0.7815413487 2.7211656570 0.1667830617 0.0047970000 529550873 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 719 28.7200000000 1.4516017437 0.7824732825 2.7211656570 0.1666670649 0.0047010000 529552881 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 720 28.7600000000 1.4541226625 0.7834061289 2.7211656570 0.1665513860 0.0045710000 529554889 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 721 28.8000000000 1.4576032162 0.7843412150 2.7211656570 0.1664359290 0.0045620000 529556897 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 722 28.8400000000 1.4607636929 0.7852780882 2.7211656570 0.1663206029 0.0045080000 529558905 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 723 28.8800000000 1.4636697769 0.7862163893 2.7211656570 0.1662054878 0.0041400000 529560913 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 724 28.9200000000 1.4665913582 0.7871561337 2.7211656570 0.1660906840 0.0090310000 529562921 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 725 28.9600000000 1.4696055651 0.7880974433 2.7211656570 0.1659761905 0.0065420000 529564929 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 726 29.0000000000 1.4722489119 0.7890398007 2.7211656570 0.1658619419 0.0061210000 529566937 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 727 29.0400000000 1.4760162830 0.7899847477 2.7211656570 0.1657480370 0.0051650000 529568945 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 728 29.0800000000 1.4795672894 0.7909319765 2.7211656570 0.1656341301 0.0195220000 529570953 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 729 29.1200000000 1.4820995331 0.7918800801 2.7211656570 0.1655203852 0.0088650000 529572961 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 730 29.1600000000 1.4847863913 0.7928292669 2.7211656570 0.1654069126 0.0063690000 529574969 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 731 29.2000000000 1.4882879257 0.7937806467 2.7211656570 0.1652937766 0.0045990000 529576977 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 732 29.2400000000 1.4912998676 0.7947335418 2.7211656570 0.1651808146 0.0123480000 529578985 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 733 29.2800000000 1.4943705797 0.7956880262 2.7211656570 0.1650680842 0.0073500000 529580993 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 734 29.3200000000 1.4974249601 0.7966440710 2.7211656570 0.1649556238 0.0046750000 529583001 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 735 29.3600000000 1.4999470711 0.7976009459 2.7211656570 0.1648434185 0.0181440000 529585009 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 736 29.4000000000 1.5022487640 0.7985583478 2.7211656570 0.1647314832 0.0090660000 529587017 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 737 29.4400000000 1.5046380758 0.7995163935 2.7211656570 0.1646198348 0.0065410000 529589025 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 738 29.4800000000 1.5073132515 0.8004754679 2.7211656570 0.1645083986 0.0053880000 529591033 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 739 29.5200000000 1.5092109442 0.8014345145 2.7211656570 0.1643970719 0.0132580000 529593041 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 740 29.5600000000 1.5107954741 0.8023931104 2.7211656570 0.1642860278 0.0081970000 529595049 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 741 29.6000000000 1.5125740767 0.8033515193 2.7211656570 0.1641755129 0.0060520000 529597057 0 402718720 -1.2137420177 -0.7472105622 -0.2426382303 742 29.6400000000 0.9092276096 0.8034942094 2.7211656570 0.1663877750 0.0191010000 529599065 0 402718720 -0.7740358114 -0.2481805235 -0.4103394151 743 29.6800000000 1.1054004431 0.8039005435 2.7211656570 0.1666961628 0.0295770000 529923633 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 744 29.7200000000 1.1074669361 0.8043085629 2.7211656570 0.1665843256 0.0061540000 543675641 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 745 29.7600000000 1.1099343300 0.8047187988 2.7211656570 0.1664726833 0.0057980000 545717841 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 746 29.8000000000 1.1120566130 0.8051307798 2.7211656570 0.1663610748 0.0054630000 545719849 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 747 29.8400000000 1.1132370234 0.8055432379 2.7211656570 0.1662496340 0.0056870000 545721857 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 748 29.8800000000 1.1170761585 0.8059597258 2.7211656570 0.1661394529 0.0057310000 545723865 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 749 29.9200000000 1.1192657948 0.8063780250 2.7211656570 0.1660285231 0.0109890000 545725873 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 750 29.9600000000 1.1208738089 0.8067973527 2.7211656570 0.1659177342 0.0075050000 545727881 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 751 30.0000000000 1.1229182482 0.8072182860 2.7211656570 0.1658071552 0.0057660000 545729889 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 752 30.0400000000 1.1249740124 0.8076408335 2.7211656570 0.1656968153 0.0056590000 545731897 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 753 30.0800000000 1.1265656948 0.8080643725 2.7211656570 0.1655866816 0.0056340000 545733905 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 754 30.1200000000 1.1286267042 0.8084895214 2.7211656570 0.1654767226 0.0053520000 545735913 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 755 30.1600000000 1.1302911043 0.8089157487 2.7211656570 0.1653670020 0.0053890000 545737921 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 756 30.2000000000 1.1315125227 0.8093424640 2.7211656570 0.1652574810 0.0237350000 545739929 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 757 30.2400000000 1.1329782009 0.8097699881 2.7211656570 0.1651484048 0.0100280000 545741937 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 758 30.2800000000 1.1348991394 0.8101989184 2.7211656570 0.1650398660 0.0072320000 545743945 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 759 30.3200000000 1.1373344660 0.8106299270 2.7211656570 0.1649314941 0.0061760000 545745953 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 760 30.3600000000 1.1392692327 0.8110623472 2.7211656570 0.1648230169 0.0063090000 545747961 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 761 30.4000000000 1.1410815716 0.8114960124 2.7211656570 0.1647147369 0.0122560000 545749969 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 762 30.4400000000 1.1434978247 0.8119317103 2.7211656570 0.1646067483 0.0082180000 545751977 0 402718720 -0.9306946397 -0.3938501179 -0.4429344535 763 30.4800000000 0.5593661666 0.8116006938 2.7211656570 0.1755147576 0.0153360000 545753985 0 402718720 0.0540587008 0.0069440021 0.1675871909 764 30.5200000000 0.5513542295 0.8112600571 2.7211656570 0.1757427084 0.0280350000 546077881 0 402718720 0.0857216790 -0.1515138745 0.1485079378 765 30.5600000000 0.5513326526 0.8109202827 2.7211656570 0.1756279187 0.0076520000 561136209 0 402718720 0.0857216790 -0.1515138745 0.1485079378 766 30.6000000000 0.5517871380 0.8105819888 2.7211656570 0.1755134025 0.0071750000 564484057 0 402718720 0.0857216790 -0.1515138745 0.1485079378 767 30.6400000000 0.5522468090 0.8102451763 2.7211656570 0.1753988915 0.0068080000 564562889 0 402718720 0.0857216790 -0.1515138745 0.1485079378 768 30.6800000000 0.5523725748 0.8099094047 2.7211656570 0.1752845538 0.0066600000 564641721 0 402718720 0.0857216790 -0.1515138745 0.1485079378 769 30.7200000000 0.5530716777 0.8095754154 2.7211656570 0.1751704674 0.0065560000 564720553 0 402718720 0.0857216790 -0.1515138745 0.1485079378 770 30.7600000000 0.5538060069 0.8092432474 2.7211656570 0.1750565406 0.0063230000 564799385 0 402718720 0.0857216790 -0.1515138745 0.1485079378 771 30.8000000000 0.5539654493 0.8089121478 2.7211656570 0.1749429067 0.0064660000 564878217 0 402718720 0.0857216790 -0.1515138745 0.1485079378 772 30.8400000000 0.5544282794 0.8085825055 2.7211656570 0.1748295601 0.0064120000 564957049 0 402718720 0.0857216790 -0.1515138745 0.1485079378 773 30.8800000000 0.5550731421 0.8082545503 2.7211656570 0.1747163666 0.0063980000 565035881 0 402718720 0.0857216790 -0.1515138745 0.1485079378 774 30.9200000000 0.5555394292 0.8079280449 2.7211656570 0.1746033326 0.0064640000 565114713 0 402718720 0.0857216790 -0.1515138745 0.1485079378 775 30.9600000000 0.5562353730 0.8076032802 2.7211656570 0.1744905105 0.0066030000 565193545 0 402718720 0.0857216790 -0.1515138745 0.1485079378 776 31.0000000000 0.5567113757 0.8072799659 2.7211656570 0.1743779725 0.0068510000 565272377 0 402718720 0.0857216790 -0.1515138745 0.1485079378 777 31.0400000000 0.5570079088 0.8069578654 2.7211656570 0.1742657025 0.0068080000 565351209 0 402718720 0.0857216790 -0.1515138745 0.1485079378 778 31.0800000000 0.5582442284 0.8066381821 2.7211656570 0.1741537300 0.0067230000 565430041 0 402718720 0.0857216790 -0.1515138745 0.1485079378 779 31.1200000000 0.5593311191 0.8063207148 2.7211656570 0.1740420860 0.0065590000 565508873 0 402718720 0.0857216790 -0.1515138745 0.1485079378 780 31.1600000000 0.5598287582 0.8060046994 2.7211656570 0.1739309098 0.0065050000 565587705 0 402718720 0.0857216790 -0.1515138745 0.1485079378 781 31.2000000000 0.5603724122 0.8056901895 2.7211656570 0.1738199623 0.0061400000 565666537 0 402718720 0.0857216790 -0.1515138745 0.1485079378 782 31.2400000000 0.5609145164 0.8053771771 2.7211656570 0.1737092270 0.0062350000 565745369 0 402718720 0.0857216790 -0.1515138745 0.1485079378 783 31.2800000000 0.5613800287 0.8050655588 2.7211656570 0.1735986737 0.0064490000 565824201 0 402718720 0.0857216790 -0.1515138745 0.1485079378 784 31.3200000000 0.5615956783 0.8047550104 2.7211656570 0.1734880700 0.0060110000 565903033 0 402718720 0.0857216790 -0.1515138745 0.1485079378 785 31.3600000000 0.5617606044 0.8044454634 2.7211656570 0.1733774485 0.0058470000 565981865 0 402718720 0.0857216790 -0.1515138745 0.1485079378 786 31.4000000000 0.5625219345 0.8041376727 2.7211656570 0.1732669954 0.0059310000 566060697 0 402718720 0.0857216790 -0.1515138745 0.1485079378 787 31.4400000000 0.5630969405 0.8038313947 2.7211656570 0.1731568620 0.0059580000 566139529 0 402718720 0.0857216790 -0.1515138745 0.1485079378 788 31.4800000000 0.5634921193 0.8035263957 2.7211656570 0.1730469778 0.0061030000 566218361 0 402718720 0.0857216790 -0.1515138745 0.1485079378 789 31.5200000000 0.5642348528 0.8032231111 2.7211656570 0.1729373171 0.0059230000 566297193 0 402718720 0.0857216790 -0.1515138745 0.1485079378 790 31.5600000000 0.5646783113 0.8029211556 2.7211656570 0.1728282437 0.0059110000 566376025 0 402718720 0.0857216790 -0.1515138745 0.1485079378 791 31.6000000000 0.5649330616 0.8026202857 2.7211656570 0.1727194687 0.0054090000 566454857 0 402718720 0.0857216790 -0.1515138745 0.1485079378 792 31.6400000000 0.5651260018 0.8023204192 2.7211656570 0.1726105410 0.0054970000 566533689 0 402718720 0.0857216790 -0.1515138745 0.1485079378 793 31.6800000000 0.5655359030 0.8020218259 2.7211656570 0.1725018217 0.0052980000 566612521 0 402718720 0.0857216790 -0.1515138745 0.1485079378 794 31.7200000000 0.5659238696 0.8017244733 2.7211656570 0.1723934747 0.0055730000 566691353 0 402718720 0.0857216790 -0.1515138745 0.1485079378 795 31.7600000000 0.5658415556 0.8014277652 2.7211656570 0.1722854087 0.0056180000 566770185 0 402718720 0.0857216790 -0.1515138745 0.1485079378 796 31.8000000000 0.5659922361 0.8011319919 2.7211656570 0.1721775796 0.0057810000 566849017 0 402718720 0.0857216790 -0.1515138745 0.1485079378 797 31.8400000000 0.5660721064 0.8008370611 2.7211656570 0.1720705970 0.0236480000 566927849 0 402718720 0.0857216790 -0.1515138745 0.1485079378 798 31.8800000000 0.5660965443 0.8005429000 2.7211656570 0.1719640789 0.0108840000 567006681 0 402718720 0.0857216790 -0.1515138745 0.1485079378 799 31.9200000000 0.5659681559 0.8002493146 2.7211656570 0.1718571074 0.0077710000 567085513 0 402718720 0.0857216790 -0.1515138745 0.1485079378 800 31.9600000000 0.5659078360 0.7999563878 2.7211656570 0.1717498787 0.0063960000 567164345 0 402718720 0.0857216790 -0.1515138745 0.1485079378 801 32.0000000000 0.5656188130 0.7996638315 2.7211656570 0.1716426242 0.0060070000 567243177 0 402718720 0.0857216790 -0.1515138745 0.1485079378 802 32.0400000000 0.5654218197 0.7993717592 2.7211656570 0.1715356024 0.0057260000 567322009 0 402718720 0.0857216790 -0.1515138745 0.1485079378 803 32.0800000000 0.5652962923 0.7990802580 2.7211656570 0.1714287767 0.0145020000 567400841 0 402718720 0.0857216790 -0.1515138745 0.1485079378 804 32.1199999990 0.5648643970 0.7987889447 2.7211656570 0.1713221250 0.0086800000 567479673 0 402718720 0.0857216790 -0.1515138745 0.1485079378 805 32.1600000000 0.5646253824 0.7984980583 2.7211656570 0.1712157119 0.0068430000 567558505 0 402718720 0.0857216790 -0.1515138745 0.1485079378 806 32.2000000000 0.5641266108 0.7982072749 2.7211656570 0.1711094719 0.0057160000 567637337 0 402718720 0.0857216790 -0.1515138745 0.1485079378 807 32.2400000000 0.5638116002 0.7979168217 2.7211656570 0.1710033088 0.0131010000 567716169 0 402718720 0.0857216790 -0.1515138745 0.1485079378 808 32.2800000000 0.5634477139 0.7976266372 2.7211656570 0.1708973313 0.0087590000 567795001 0 402718720 0.0857216790 -0.1515138745 0.1485079378 809 32.3200000000 0.5630590916 0.7973366897 2.7211656570 0.1707915670 0.0065570000 567873833 0 402718720 0.0857216790 -0.1515138745 0.1485079378 810 32.3600000000 0.5623897314 0.7970466317 2.7211656570 0.1706860081 0.0136940000 567952665 0 402718720 0.0857216790 -0.1515138745 0.1485079378 811 32.4000000000 0.5617827177 0.7967565406 2.7211656570 0.1705806244 0.0082420000 568031497 0 402718720 0.0857216790 -0.1515138745 0.1485079378 812 32.4399999990 0.5610694885 0.7964662856 2.7211656570 0.1704754612 0.0066070000 568110329 0 402718720 0.0857216790 -0.1515138745 0.1485079378 813 32.4800000000 0.5605733991 0.7961761344 2.7211656570 0.1703704933 0.0056420000 568189161 0 402718720 0.0857216790 -0.1515138745 0.1485079378 814 32.5200000000 0.5597371459 0.7958856688 2.7211656570 0.1702657856 0.0049260000 568267993 0 402718720 0.0857216790 -0.1515138745 0.1485079378 815 32.5600000000 0.5589554310 0.7955949569 2.7211656570 0.1701613498 0.0210270000 568346825 0 402718720 0.0857216790 -0.1515138745 0.1485079378 816 32.6000000000 0.5584452152 0.7953043322 2.7211656570 0.1700571103 0.0090540000 568425657 0 402718720 0.0857216790 -0.1515138745 0.1485079378 817 32.6400000000 0.5576469898 0.7950134419 2.7211656570 0.1699530826 0.0063540000 568504489 0 402718720 0.0857216790 -0.1515138745 0.1485079378 818 32.6800000000 0.5569230914 0.7947223779 2.7211656570 0.1698492489 0.0058760000 568583321 0 402718720 0.0857216790 -0.1515138745 0.1485079378 819 32.7200000000 0.5560096502 0.7944309094 2.7211656570 0.1697455880 0.0055260000 568662153 0 402718720 0.0857216790 -0.1515138745 0.1485079378 820 32.7599999990 0.5551334023 0.7941390832 2.7211656570 0.1696421457 0.0051450000 568740985 0 402718720 0.0857216790 -0.1515138745 0.1485079378 821 32.7999999990 0.5544905066 0.7938471848 2.7211656570 0.1695388794 0.0050990000 568819817 0 402718720 0.0857216790 -0.1515138745 0.1485079378 822 32.8400000000 0.5745602250 0.7935804123 2.7211656570 0.1700803219 0.0310330000 568898649 0 402718720 0.0358774774 0.1298636794 0.1598770469 823 32.8800000000 0.5879180431 0.7933305188 2.7211656570 0.1699812982 0.0246380000 558062633 0 402718720 0.0284277312 0.1568903625 0.1654240936 824 32.9200000000 0.9545679688 0.7935261953 2.7211656570 0.1717386188 0.0354140000 561588297 0 402718720 -0.2092607319 0.7798489928 -0.0275911074 825 32.9600000000 0.9544845819 0.7937212964 2.7211656570 0.1716347320 0.0054130000 568964929 0 402718720 -0.2092607319 0.7798489928 -0.0275911074 826 33.0000000000 0.9541937709 0.7939155730 2.7211656570 0.1715310118 0.0049080000 568966937 0 402718720 -0.2092607319 0.7798489928 -0.0275911074 827 33.0400000000 0.4677571356 0.7935211855 2.7211656570 0.1725515890 0.0192690000 568968945 0 402718720 0.0359633267 0.4074619412 -0.2380034626 828 33.0800000000 0.4437675774 0.7930987778 2.7211656570 0.1724662291 0.0255950000 561599513 0 402718720 0.0735498071 0.4042471945 -0.2723158896 829 33.1199999990 0.4434191585 0.7926769688 2.7211656570 0.1723623601 0.0137890000 568976145 0 402718720 0.0735498071 0.4042471945 -0.2723158896 830 33.1600000000 0.4431591928 0.7922558631 2.7211656570 0.1722585270 0.0152880000 568978153 0 402718720 0.0735498071 0.4042471945 -0.2723158896 831 33.2000000000 0.4424120784 0.7918348718 2.7211656570 0.1721550105 0.0095840000 568980161 0 402718720 0.0735498071 0.4042471945 -0.2723158896 832 33.2400000000 0.4422875345 0.7914147428 2.7211656570 0.1720514263 0.0069800000 568982169 0 402718720 0.0735498071 0.4042471945 -0.2723158896 833 33.2800000000 0.4420980513 0.7909953950 2.7211656570 0.1719480635 0.0055940000 568984177 0 402718720 0.0735498071 0.4042471945 -0.2723158896 834 33.3200000000 0.4415102601 0.7905763481 2.7211656570 0.1718448921 0.0045620000 568986185 0 402718720 0.0735498071 0.4042471945 -0.2723158896 835 33.3600000000 0.4410853684 0.7901577960 2.7211656570 0.1717418747 0.0047560000 568988193 0 402718720 0.0735498071 0.4042471945 -0.2723158896 836 33.4000000000 0.4409803450 0.7897401196 2.7211656570 0.1716390637 0.0047920000 568990201 0 402718720 0.0735498071 0.4042471945 -0.2723158896 837 33.4399999990 0.4407977164 0.7893232231 2.7211656570 0.1715364368 0.0046980000 568992209 0 402718720 0.0735498071 0.4042471945 -0.2723158896 838 33.4800000000 0.4404058456 0.7889068539 2.7211656570 0.1714339983 0.0047430000 568994217 0 402718720 0.0735498071 0.4042471945 -0.2723158896 839 33.5200000000 0.4401237071 0.7884911410 2.7211656570 0.1713317208 0.0043820000 568996225 0 402718720 0.0735498071 0.4042471945 -0.2723158896 840 33.5600000000 0.4403424263 0.7880766782 2.7211656570 0.1712296356 0.0219690000 568998233 0 402718720 0.0735498071 0.4042471945 -0.2723158896 841 33.6000000000 0.4406481981 0.7876635647 2.7211656570 0.1711278685 0.0097660000 569000241 0 402718720 0.0735498071 0.4042471945 -0.2723158896 842 33.6400000000 0.4405682385 0.7872513374 2.7211656570 0.1710264615 0.0063680000 569002249 0 402718720 0.0735498071 0.4042471945 -0.2723158896 843 33.6800000000 0.4401326776 0.7868395715 2.7211656570 0.1709250968 0.0053940000 569004257 0 402718720 0.0735498071 0.4042471945 -0.2723158896 844 33.7200000000 0.4400768876 0.7864287153 2.7211656570 0.1708238091 0.0046460000 569006265 0 402718720 0.0735498071 0.4042471945 -0.2723158896 845 33.7599999990 0.4398047626 0.7860185094 2.7211656570 0.1707227549 0.0049580000 569008273 0 402718720 0.0735498071 0.4042471945 -0.2723158896 846 33.7999999990 0.3476516306 0.7855003453 2.7211656570 0.1711836291 0.0232350000 569010281 0 402718720 -0.1266389638 -0.0080318786 -0.2160779983 847 33.8400000000 0.3066719472 0.7849350225 2.7211656570 0.1710849447 0.0252290000 563033753 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 848 33.8800000000 0.3052340746 0.7843693374 2.7211656570 0.1709840258 0.0100710000 573932705 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 849 33.9200000000 0.3039447963 0.7838034663 2.7211656570 0.1708833138 0.0107710000 573934713 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 850 33.9600000000 0.3023894429 0.7832370969 2.7211656570 0.1707828401 0.0098930000 573936721 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 851 34.0000000000 0.3010518253 0.7826704867 2.7211656570 0.1706825548 0.0067570000 573938729 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 852 34.0400000000 0.2995170951 0.7821034052 2.7211656570 0.1705823657 0.0234650000 573940737 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 853 34.0800000000 0.2980876565 0.7815359776 2.7211656570 0.1704822611 0.0164920000 573942745 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 854 34.1199999990 0.2965781093 0.7809681113 2.7211656570 0.1703823227 0.0077980000 573944753 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 855 34.1600000000 0.2948879004 0.7803995964 2.7211656570 0.1702825677 0.0064860000 573946761 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 856 34.2000000000 0.2932196558 0.7798304610 2.7211656570 0.1701831642 0.0052970000 573948769 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 857 34.2400000000 0.2918973267 0.7792611108 2.7211656570 0.1700839709 0.0049480000 573950777 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 858 34.2800000000 0.2902532816 0.7786911716 2.7211656570 0.1699848223 0.0041890000 573952785 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 859 34.3200000000 0.2884012759 0.7781204033 2.7211656570 0.1698859154 0.0036790000 573954793 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 860 34.3600000000 0.2866581678 0.7775489356 2.7211656570 0.1697871226 0.0039890000 573956801 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 861 34.4000000000 0.2848126292 0.7769766519 2.7211656570 0.1696884448 0.0041170000 573958809 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 862 34.4400000000 0.2828553617 0.7764034253 2.7211656570 0.1695899321 0.0040570000 573960817 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 863 34.4800000000 0.2809269130 0.7758292926 2.7211656570 0.1694915931 0.0044660000 573962825 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 864 34.5200000000 0.2784939408 0.7752536730 2.7211656570 0.1693934483 0.0041600000 573964833 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 865 34.5600000000 0.2760348320 0.7746765414 2.7211656570 0.1692955152 0.0040880000 573966841 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 866 34.6000000000 0.2733332217 0.7740976230 2.7211656570 0.1691977303 0.0208320000 573968849 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 867 34.6400000000 0.2707434893 0.7735170531 2.7211656570 0.1691001046 0.0108970000 573970857 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 868 34.6800000000 0.2679482698 0.7729346006 2.7211656570 0.1690026333 0.0070860000 573972865 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 869 34.7200000000 0.2651099563 0.7723502224 2.7211656570 0.1689053281 0.0052540000 573974873 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 870 34.7600000000 0.2619183362 0.7717635191 2.7211656570 0.1688082522 0.0048270000 573976881 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 871 34.8000000000 0.2585982382 0.7711743511 2.7211656570 0.1687113578 0.0048810000 573978889 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 872 34.8400000000 0.2550167441 0.7705824273 2.7211656570 0.1686145776 0.0135040000 573980897 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 873 34.8800000000 0.2517785132 0.7699881502 2.7211656570 0.1685180998 0.0090570000 573982905 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 874 34.9200000000 0.2485084534 0.7693914915 2.7211656570 0.1684217192 0.0061680000 573984913 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 875 34.9600000000 0.2450526953 0.7687922471 2.7211656570 0.1683256546 0.0048300000 573986921 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 876 35.0000000000 0.2415732592 0.7681903990 2.7211656570 0.1682296187 0.0039950000 573988929 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 877 35.0400000000 0.2380788773 0.7675859389 2.7211656570 0.1681336790 0.0044210000 573990937 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 878 35.0800000000 0.2344453782 0.7669787173 2.7211656570 0.1680378777 0.0212120000 573992945 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 879 35.1200000000 0.2310192734 0.7663689796 2.7211656570 0.1679421634 0.0098660000 573994953 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 880 35.1600000000 0.2275620699 0.7657566990 2.7211656570 0.1678466708 0.0068210000 573996961 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 881 35.2000000000 0.2240833938 0.7651418598 2.7211656570 0.1677515125 0.0053240000 573998969 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 882 35.2400000000 0.2205956429 0.7645244605 2.7211656570 0.1676563075 0.0045500000 574077801 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 883 35.2800000000 0.2170224488 0.7639044129 2.7211656570 0.1675612635 0.0043590000 574156633 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 884 35.3200000000 0.2139018178 0.7632822380 2.7211656570 0.1674663816 0.0043660000 574235465 0 402718720 -0.0948584750 -0.0084299939 -0.2434926182 885 35.3600000000 0.7943695784 0.7633173649 2.7211656570 0.1714132010 0.0162580000 574314297 0 402718720 0.2680969238 0.3493404984 0.4078972638 886 35.4000000000 0.7999882698 0.7633587542 2.7211656570 0.1713193463 0.0287500000 568413345 0 402718720 0.2826395035 0.3428465128 0.4155652523 887 35.4400000000 0.7989788651 0.7633989122 2.7211656570 0.1712227156 0.0058540000 579697665 0 402718720 0.2826395035 0.3428465128 0.4155652523 888 35.4800000000 0.7979938388 0.7634378704 2.7211656570 0.1711263154 0.0053250000 579930145 0 402718720 0.2826395035 0.3428465128 0.4155652523 889 35.5200000000 0.7968611121 0.7634754669 2.7211656570 0.1710301672 0.0051520000 580008977 0 402718720 0.2826395035 0.3428465128 0.4155652523 890 35.5600000000 0.7956489325 0.7635116169 2.7211656570 0.1709341900 0.0045230000 580087809 0 402718720 0.2826395035 0.3428465128 0.4155652523 891 35.6000000000 0.7944684029 0.7635463607 2.7211656570 0.1708384072 0.0050050000 580166641 0 402718720 0.2826395035 0.3428465128 0.4155652523 892 35.6400000000 0.7935055494 0.7635799473 2.7211656570 0.1707428885 0.0047380000 580245473 0 402718720 0.2826395035 0.3428465128 0.4155652523 893 35.6800000000 0.7926380038 0.7636124871 2.7211656570 0.1706475618 0.0055820000 580324305 0 402718720 0.2826395035 0.3428465128 0.4155652523 894 35.7200000000 0.7918303013 0.7636440506 2.7211656570 0.1705523790 0.0044760000 580403137 0 402718720 0.2826395035 0.3428465128 0.4155652523 895 35.7600000000 0.7911712527 0.7636748073 2.7211656570 0.1704572329 0.0223590000 580481969 0 402718720 0.2826395035 0.3428465128 0.4155652523 896 35.8000000000 0.7905517220 0.7637048038 2.7211656570 0.1703622034 0.0086520000 580560801 0 402718720 0.2826395035 0.3428465128 0.4155652523 897 35.8400000000 0.7900475860 0.7637341715 2.7211656570 0.1702672537 0.0075590000 580639633 0 402718720 0.2826395035 0.3428465128 0.4155652523 898 35.8800000000 0.7894510031 0.7637628094 2.7211656570 0.1701725045 0.0052470000 580718465 0 402718720 0.2826395035 0.3428465128 0.4155652523 899 35.9200000000 0.7893981934 0.7637913248 2.7211656570 0.1700780590 0.0048480000 580797297 0 402718720 0.2826395035 0.3428465128 0.4155652523 900 35.9600000000 0.7897090912 0.7638201223 2.7211656570 0.1699838546 0.0050370000 580876129 0 402718720 0.2826395035 0.3428465128 0.4155652523 901 36.0000000000 0.7902022004 0.7638494032 2.7211656570 0.1698896676 0.0045440000 580954961 0 402718720 0.2826395035 0.3428465128 0.4155652523 902 36.0400000000 0.7905271053 0.7638789794 2.7211656570 0.1697955141 0.0049300000 581033793 0 402718720 0.2826395035 0.3428465128 0.4155652523 903 36.0800000000 0.7909240127 0.7639089296 2.7211656570 0.1697014889 0.0190620000 581112625 0 402718720 0.2826395035 0.3428465128 0.4155652523 904 36.1200000000 0.7915254235 0.7639394788 2.7211656570 0.1696075741 0.0084310000 581191457 0 402718720 0.2826395035 0.3428465128 0.4155652523 905 36.1600000000 0.7914943695 0.7639699262 2.7211656570 0.1695138079 0.0070250000 581270289 0 402718720 0.2826395035 0.3428465128 0.4155652523 906 36.2000000000 0.7921828628 0.7640010663 2.7211656570 0.1694201995 0.0058820000 581349121 0 402718720 0.2826395035 0.3428465128 0.4155652523 907 36.2400000000 0.7933644056 0.7640334404 2.7211656570 0.1693267612 0.0039890000 581427953 0 402718720 0.2826395035 0.3428465128 0.4155652523 908 36.2800000000 0.7946011424 0.7640671053 2.7211656570 0.1692334874 0.0193920000 581506785 0 402718720 0.2826395035 0.3428465128 0.4155652523 909 36.3200000000 0.7953524590 0.7641015226 2.7211656570 0.1691403582 0.0088140000 581585617 0 402718720 0.2826395035 0.3428465128 0.4155652523 910 36.3600000000 0.7960144877 0.7641365918 2.7211656570 0.1690473799 0.0063760000 581664449 0 402718720 0.2826395035 0.3428465128 0.4155652523 911 36.4000000000 0.7972470522 0.7641729370 2.7211656570 0.1689545761 0.0052260000 581743281 0 402718720 0.2826395035 0.3428465128 0.4155652523 912 36.4400000000 0.7978277802 0.7642098393 2.7211656570 0.1688619100 0.0126650000 581822113 0 402718720 0.2826395035 0.3428465128 0.4155652523 913 36.4800000000 0.7983094454 0.7642471882 2.7211656570 0.1687693676 0.0070330000 581900945 0 402718720 0.2826395035 0.3428465128 0.4155652523 914 36.5200000000 0.7991837263 0.7642854120 2.7211656570 0.1686769857 0.0060480000 581979777 0 402718720 0.2826395035 0.3428465128 0.4155652523 915 36.5600000000 0.8085356355 0.7643337729 2.7211656570 0.1687525041 0.0117350000 582058609 0 402718720 0.2089121342 0.4684482515 0.3711920381 916 36.6000000000 0.8192186356 0.7643936909 2.7211656570 0.1686664359 0.0262090000 576156697 0 402718720 0.1979002655 0.4947402179 0.3670384288 917 36.6400000000 0.8202902079 0.7644546467 2.7211656570 0.1685744362 0.0043210000 587441977 0 402718720 0.1979002655 0.4947402179 0.3670384288 918 36.6800000000 0.8206251860 0.7645158347 2.7211656570 0.1684825789 0.0037220000 587674457 0 402718720 0.1979002655 0.4947402179 0.3670384288 919 36.7200000000 0.8207506537 0.7645770260 2.7211656570 0.1683908567 0.0039630000 587753289 0 402718720 0.1979002655 0.4947402179 0.3670384288 920 36.7600000000 0.8213083148 0.7646386904 2.7211656570 0.1682993069 0.0042220000 587832121 0 402718720 0.1979002655 0.4947402179 0.3670384288 921 36.8000000000 0.8214527965 0.7647003779 2.7211656570 0.1682079032 0.0039530000 587910953 0 402718720 0.1979002655 0.4947402179 0.3670384288 922 36.8400000000 0.8211401105 0.7647615923 2.7211656570 0.1681166624 0.0170810000 587989785 0 402718720 0.1979002655 0.4947402179 0.3670384288 923 36.8800000000 0.8212681413 0.7648228128 2.7211656570 0.1680256715 0.0096980000 588068617 0 402718720 0.1979002655 0.4947402179 0.3670384288 924 36.9200000000 0.8218630552 0.7648845447 2.7211656570 0.1679348273 0.0080890000 588147449 0 402718720 0.1979002655 0.4947402179 0.3670384288 925 36.9600000000 0.8222055435 0.7649465134 2.7211656570 0.1678440162 0.0052940000 588226281 0 402718720 0.1979002655 0.4947402179 0.3670384288 926 37.0000000000 0.8222889900 0.7650084383 2.7211656570 0.1677532916 0.0035290000 588305113 0 402718720 0.1979002655 0.4947402179 0.3670384288 927 37.0400000000 0.8224552870 0.7650704090 2.7211656570 0.1676627290 0.0159740000 588383945 0 402718720 0.1979002655 0.4947402179 0.3670384288 928 37.0800000000 0.8217231035 0.7651314572 2.7211656570 0.1675723079 0.0078970000 588462777 0 402718720 0.1979002655 0.4947402179 0.3670384288 929 37.1200000000 0.8215988278 0.7651922401 2.7211656570 0.1674821058 0.0063060000 588541609 0 402718720 0.1979002655 0.4947402179 0.3670384288 930 37.1600000000 0.8214582205 0.7652527412 2.7211656570 0.1673920069 0.0042070000 588620441 0 402718720 0.1979002655 0.4947402179 0.3670384288 931 37.2000000000 0.8212247491 0.7653128615 2.7211656570 0.1673020383 0.0159670000 588699273 0 402718720 0.1979002655 0.4947402179 0.3670384288 932 37.2400000000 0.8212073445 0.7653728341 2.7211656570 0.1672122170 0.0088140000 588778105 0 402718720 0.1979002655 0.4947402179 0.3670384288 933 37.2800000000 0.8207774758 0.7654322174 2.7211656570 0.1671225347 0.0061930000 588856937 0 402718720 0.1979002655 0.4947402179 0.3670384288 934 37.3200000000 0.8201012015 0.7654907495 2.7211656570 0.1670330265 0.0043810000 588935769 0 402718720 0.1979002655 0.4947402179 0.3670384288 935 37.3600000000 0.8198722601 0.7655489116 2.7211656570 0.1669437739 0.0153340000 589014601 0 402718720 0.1979002655 0.4947402179 0.3670384288 936 37.4000000000 0.8198382258 0.7656069130 2.7211656570 0.1668545929 0.0094970000 589093433 0 402718720 0.1979002655 0.4947402179 0.3670384288 937 37.4400000000 0.8198999166 0.7656648564 2.7211656570 0.1667654975 0.0068160000 589172265 0 402718720 0.1979002655 0.4947402179 0.3670384288 938 37.4800000000 0.8199914694 0.7657227739 2.7211656570 0.1666765361 0.0057130000 589251097 0 402718720 0.1979002655 0.4947402179 0.3670384288 939 37.5200000000 0.8200523257 0.7657806329 2.7211656570 0.1665876890 0.0046380000 589329929 0 402718720 0.1979002655 0.4947402179 0.3670384288 940 37.5600000000 0.8199419379 0.7658382513 2.7211656570 0.1664989805 0.0050360000 589408761 0 402718720 0.1979002655 0.4947402179 0.3670384288 941 37.6000000000 0.8195505142 0.7658953312 2.7211656570 0.1664104309 0.0050050000 589487593 0 402718720 0.1979002655 0.4947402179 0.3670384288 942 37.6400000000 0.8192809224 0.7659520039 2.7211656570 0.1663220521 0.0039950000 589566425 0 402718720 0.1979002655 0.4947402179 0.3670384288 943 37.6800000000 0.8192965984 0.7660085729 2.7211656570 0.1662338480 0.0041360000 589645257 0 402718720 0.1979002655 0.4947402179 0.3670384288 944 37.7200000000 0.8190791607 0.7660647917 2.7211656570 0.1661457573 0.0218970000 589724089 0 402718720 0.1979002655 0.4947402179 0.3670384288 945 37.7600000000 0.8190142512 0.7661208229 2.7211656570 0.1660578239 0.0111190000 589802921 0 402718720 0.1979002655 0.4947402179 0.3670384288 946 37.8000000000 0.8189734817 0.7661766925 2.7211656570 0.1659700204 0.0075470000 589881753 0 402718720 0.1979002655 0.4947402179 0.3670384288 947 37.8400000000 0.8187445998 0.7662322025 2.7211656570 0.1658823293 0.0052420000 589960585 0 402718720 0.1979002655 0.4947402179 0.3670384288 948 37.8800000000 0.8186440468 0.7662874892 2.7211656570 0.1657947989 0.0042440000 590039417 0 402718720 0.1979002655 0.4947402179 0.3670384288 949 37.9200000000 0.8185765147 0.7663425883 2.7211656570 0.1657074168 0.0044910000 590118249 0 402718720 0.1979002655 0.4947402179 0.3670384288 950 37.9600000000 0.8184224963 0.7663974092 2.7211656570 0.1656201296 0.0042350000 590197081 0 402718720 0.1979002655 0.4947402179 0.3670384288 951 38.0000000000 0.8182981014 0.7664519841 2.7211656570 0.1655329654 0.0043100000 590275913 0 402718720 0.1979002655 0.4947402179 0.3670384288 952 38.0400000000 0.8180148005 0.7665061467 2.7211656570 0.1654459774 0.0187020000 590354745 0 402718720 0.1979002655 0.4947402179 0.3670384288 953 38.0800000000 0.8180412650 0.7665602234 2.7211656570 0.1653590978 0.0110640000 590433577 0 402718720 0.1979002655 0.4947402179 0.3670384288 954 38.1200000000 0.8178054094 0.7666139396 2.7211656570 0.1652723283 0.0072190000 590512409 0 402718720 0.1979002655 0.4947402179 0.3670384288 955 38.1600000000 0.8177700639 0.7666675062 2.7211656570 0.1651857211 0.0073760000 590591241 0 402718720 0.1979002655 0.4947402179 0.3670384288 956 38.2000000000 0.8176629543 0.7667208487 2.7211656570 0.1650992377 0.0052880000 590670073 0 402718720 0.1979002655 0.4947402179 0.3670384288 957 38.2400000000 0.8178721666 0.7667742984 2.7211656570 0.1650128922 0.0161400000 590748905 0 402718720 0.1979002655 0.4947402179 0.3670384288 958 38.2800000000 0.8177061677 0.7668274632 2.7211656570 0.1649266747 0.0098480000 590827737 0 402718720 0.1979002655 0.4947402179 0.3670384288 959 38.3200000000 0.8178145885 0.7668806301 2.7211656570 0.1648406010 0.0067040000 590906569 0 402718720 0.1979002655 0.4947402179 0.3670384288 960 38.3600000000 0.8176693320 0.7669335350 2.7211656570 0.1647546412 0.0056490000 590985401 0 402718720 0.1979002655 0.4947402179 0.3670384288 961 38.4000000000 0.8176513314 0.7669863111 2.7211656570 0.1646688190 0.0129940000 591064233 0 402718720 0.1979002655 0.4947402179 0.3670384288 962 38.4400000000 0.8176622987 0.7670389888 2.7211656570 0.1645831388 0.0089880000 591143065 0 402718720 0.1979002655 0.4947402179 0.3670384288 963 38.4800000000 0.8177908659 0.7670916907 2.7211656570 0.1644975946 0.0056680000 591221897 0 402718720 0.1979002655 0.4947402179 0.3670384288 964 38.5200000000 0.8176631927 0.7671441507 2.7211656570 0.1644121768 0.0051910000 591300729 0 402718720 0.1979002655 0.4947402179 0.3670384288 965 38.5600000000 0.8175891638 0.7671964254 2.7211656570 0.1643268978 0.0171420000 591379561 0 402718720 0.1979002655 0.4947402179 0.3670384288 966 38.6000000000 0.8176618814 0.7672486670 2.7211656570 0.1642417513 0.0084780000 591458393 0 402718720 0.1979002655 0.4947402179 0.3670384288 967 38.6400000000 0.8176962137 0.7673008362 2.7211656570 0.1641567204 0.0062110000 591537225 0 402718720 0.1979002655 0.4947402179 0.3670384288 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:17:05 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0053640000 86827604 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0010221110 0.0005110555 0.0010221110 0.0016486765 0.0204230000 103183657 0 402718720 -0.0006010678 -0.0001195244 0.0001060443 3 0.0800000000 0.0050368467 0.0020196526 0.0050368467 0.0023331402 0.0206990000 106455569 0 402718720 -0.0005712564 -0.0001159089 -0.0002626415 4 0.1200000000 0.0030105244 0.0022673706 0.0050368467 0.0021972292 0.0206330000 106458217 0 402718720 -0.0008395423 -0.0004368496 -0.0003819885 5 0.1600000000 0.0058184462 0.0029775857 0.0058184462 0.0019636265 0.0199700000 106460881 0 402718720 -0.0009795793 -0.0000027206 -0.0002612148 6 0.2000000000 0.0051384396 0.0033377280 0.0058184462 0.0018817739 0.0198960000 106463929 0 402718720 -0.0005845805 -0.0000757059 -0.0006002540 7 0.2400000000 0.0052057360 0.0036045863 0.0058184462 0.0017252949 0.0199620000 106466177 0 402718720 -0.0005683319 0.0000713028 -0.0004218094 8 0.2800000000 0.0065800720 0.0039765220 0.0065800720 0.0016593006 0.0196570000 106468425 0 402718720 -0.0006063433 0.0001757963 -0.0005147401 9 0.3200000000 0.0080526182 0.0044294216 0.0080526182 0.0016340920 0.0212800000 106471505 0 402718720 -0.0010380259 0.0000522868 -0.0005210924 10 0.3600000000 0.0081044836 0.0047969278 0.0081044836 0.0016454699 0.0215000000 106475353 0 402718720 -0.0013087916 0.0000750954 -0.0004509437 11 0.4000000000 0.0093984492 0.0052152479 0.0093984492 0.0018088903 0.0191240000 106477601 0 402718720 -0.0008957226 0.0000751102 -0.0001808895 12 0.4400000000 0.0094706044 0.0055698610 0.0094706044 0.0021761640 0.0197740000 106479849 0 402718720 -0.0007593075 -0.0000005458 -0.0004498283 13 0.4800000000 0.0110082580 0.0059881992 0.0110082580 0.0022167070 0.0191870000 106482097 0 402718720 -0.0016798322 -0.0000336746 -0.0001003841 14 0.5200000000 0.0109660253 0.0063437582 0.0110082580 0.0021937212 0.0289890000 106484345 0 402718720 -0.0019606531 -0.0010226226 -0.0000116620 15 0.5600000000 0.0139691764 0.0068521194 0.0139691764 0.0021532649 0.0205780000 106486593 0 402718720 -0.0020313677 0.0001300166 -0.0003221555 16 0.6000000000 0.0133041330 0.0072553703 0.0139691764 0.0022222298 0.0197500000 106488841 0 402718720 -0.0015773640 -0.0000094086 -0.0005183284 17 0.6400000000 0.0138059510 0.0076406985 0.0139691764 0.0022505849 0.0195610000 106492753 0 402718720 -0.0031562904 -0.0012515889 -0.0008958912 18 0.6800000000 0.0174049083 0.0081831546 0.0174049083 0.0023576317 0.0219150000 106498201 0 402718720 -0.0016320179 -0.0045921686 -0.0006295637 19 0.7200000000 0.0175940488 0.0086784649 0.0175940488 0.0025288205 0.0186140000 106500449 0 402718720 -0.0023679030 -0.0004589465 -0.0013908958 20 0.7600000000 0.0203366689 0.0092613751 0.0203366689 0.0025888000 0.0189510000 106502697 0 402718720 -0.0026747861 -0.0005096134 -0.0014838291 21 0.8000000000 0.0241022408 0.0099680829 0.0241022408 0.0025306025 0.0191320000 106504945 0 402718720 -0.0018647636 -0.0001894720 -0.0016551752 22 0.8400000000 0.0295359325 0.0108575307 0.0295359325 0.0026146935 0.0199860000 106507193 0 402718720 -0.0021181731 -0.0002913807 -0.0015463522 23 0.8800000000 0.0290699080 0.0116493731 0.0295359325 0.0025785272 0.0206070000 106509441 0 402718720 -0.0020462936 0.0000022076 -0.0023591069 24 0.9200000000 0.0352930799 0.0126345276 0.0352930799 0.0028196324 0.0221750000 106511689 0 402718720 -0.0041387957 0.0000000737 -0.0031308315 25 0.9600000000 0.0355664901 0.0135518061 0.0355664901 0.0027740306 0.0191050000 106513937 0 402718720 -0.0050042840 0.0009137367 -0.0037828644 26 1.0000000000 0.0407356694 0.0145973393 0.0407356694 0.0028441873 0.0246260000 106516185 0 402718720 -0.0061319182 0.0006566583 -0.0029565943 27 1.0400000000 0.0460910574 0.0157637733 0.0460910574 0.0030297597 0.0214360000 106518433 0 402718720 -0.0064592562 0.0004693865 -0.0043467609 28 1.0800000000 0.0489963107 0.0169506496 0.0489963107 0.0033440414 0.0190370000 106520681 0 402718720 -0.0083498303 -0.0004474318 -0.0041515878 29 1.1200000000 0.0525621250 0.0181786315 0.0525621250 0.0036770268 0.0212230000 106522929 0 402718720 -0.0109420186 -0.0000399562 -0.0050495001 30 1.1600000000 0.0571475215 0.0194775945 0.0571475215 0.0041794470 0.0329080000 106525177 0 402718720 -0.0159000810 -0.0000889053 -0.0038441299 31 1.2000000000 0.0600341931 0.0207858719 0.0600341931 0.0043455298 0.0271500000 106527425 0 402718720 -0.0195541866 -0.0003700769 -0.0041839192 32 1.2400000000 0.0642836168 0.0221451764 0.0642836168 0.0044772236 0.0272580000 106529673 0 402718720 -0.0222196467 -0.0007074057 -0.0050073327 33 1.2800000000 0.0680458769 0.0235361068 0.0680458769 0.0045985394 0.0258990000 106535249 0 402718720 -0.0239848010 -0.0007214104 -0.0050769718 34 1.3200000000 0.0854386613 0.0253567701 0.0854386613 0.0055973019 0.0258630000 106543897 0 402718720 -0.0348482728 -0.0008019696 -0.0049022478 35 1.3600000000 0.0871313363 0.0271217577 0.0871313363 0.0057724779 0.0267630000 106546145 0 402718720 -0.0367471129 -0.0007946193 -0.0057829092 36 1.4000000000 0.0902810544 0.0288761826 0.0902810544 0.0062030982 0.0264460000 106548393 0 402718720 -0.0394289307 -0.0011519954 -0.0064139809 37 1.4400000000 0.0969246328 0.0307153299 0.0969246328 0.0064337492 0.0257290000 106550641 0 402718720 -0.0435134619 -0.0008812989 -0.0056946720 38 1.4800000000 0.1037840843 0.0326381919 0.1037840843 0.0065433934 0.0387050000 118892141 0 402718720 -0.0484429635 -0.0007620376 -0.0051629506 39 1.5200000000 0.1067030206 0.0345372901 0.1067030206 0.0064768831 0.0159040000 122553997 0 402718720 -0.0489069261 -0.0011520091 -0.0063196477 40 1.5600000000 0.1133394241 0.0365073434 0.1133394241 0.0064370452 0.0238070000 125748437 0 402718720 -0.0521548055 -0.0016218214 -0.0061395774 41 1.6000000000 0.1198616028 0.0385403741 0.1198616028 0.0064013111 0.0173390000 125750685 0 402718720 -0.0559138320 -0.0019886955 -0.0056572510 42 1.6400000000 0.1288172752 0.0406898242 0.1288172752 0.0064332890 0.0158490000 125752933 0 402718720 -0.0601656809 -0.0008910592 -0.0049997773 43 1.6800000000 0.1335005611 0.0428482134 0.1335005611 0.0063742072 0.0155440000 125755181 0 402718720 -0.0621613003 -0.0007944948 -0.0036822946 44 1.7200000000 0.1372464299 0.0449936274 0.1372464299 0.0063196490 0.0154730000 125757429 0 402718720 -0.0647445843 -0.0016313283 -0.0045193150 45 1.7600000000 0.1420539021 0.0471505224 0.1420539021 0.0062788642 0.0148450000 125759677 0 402718720 -0.0682628602 -0.0014697916 -0.0031571491 46 1.8000000000 0.1461073607 0.0493017580 0.1461073607 0.0062140242 0.0161000000 125761925 0 402718720 -0.0701636970 -0.0004700999 -0.0036043331 47 1.8400000000 0.1495470703 0.0514346370 0.1495470703 0.0062266301 0.0157800000 125764173 0 402718720 -0.0697437748 -0.0003123159 -0.0032924262 48 1.8800000000 0.1527054012 0.0535444446 0.1527054012 0.0061764370 0.0157130000 125766421 0 402718720 -0.0710848942 -0.0000658497 -0.0029243326 49 1.9200000000 0.1573966146 0.0556638766 0.1573966146 0.0061560534 0.0197960000 125768669 0 402718720 -0.0736479759 -0.0000878447 -0.0027709759 50 1.9600000000 0.1666463017 0.0578835251 0.1666463017 0.0063479760 0.0155350000 125770917 0 402718720 -0.0786924884 -0.0000066427 -0.0007028050 51 2.0000000000 0.1648788005 0.0599814717 0.1666463017 0.0062871257 0.0168020000 125773165 0 402718720 -0.0787848234 -0.0021353804 -0.0015991166 52 2.0400000000 0.1678642184 0.0620561399 0.1678642184 0.0062368057 0.0214200000 125775413 0 402718720 -0.0797809660 -0.0011418709 -0.0020321822 53 2.0800000000 0.1690072417 0.0640740852 0.1690072417 0.0062299296 0.0203820000 125777661 0 402718720 -0.0806599557 -0.0014444985 -0.0032268446 54 2.1200000000 0.1773535907 0.0661718539 0.1773535907 0.0062330208 0.0201850000 125779909 0 402718720 -0.0853610411 -0.0017707776 -0.0011762143 55 2.1600000000 0.1792208999 0.0682272911 0.1792208999 0.0062119541 0.0226060000 125782157 0 402718720 -0.0857493803 -0.0017121264 -0.0008412982 56 2.2000000000 0.1921453774 0.0704401140 0.1921453774 0.0063255825 0.0216330000 125784405 0 402718720 -0.0928636864 -0.0006414056 0.0018607760 57 2.2400000000 0.1954839081 0.0726338648 0.1954839081 0.0062839662 0.0221400000 125786653 0 402718720 -0.0944608077 -0.0013362539 0.0023466900 58 2.2800000000 0.2009222656 0.0748457338 0.2009222656 0.0063859825 0.0219070000 125788901 0 402718720 -0.0983995497 -0.0018866452 0.0037058054 59 2.3200000000 0.2107910663 0.0771498920 0.2107910663 0.0067649150 0.0227040000 125791149 0 402718720 -0.1027900577 -0.0012729637 0.0057026003 60 2.3600000000 0.2128191739 0.0794110467 0.2128191739 0.0068195288 0.0231180000 125793397 0 402718720 -0.1038557813 -0.0013865192 0.0052556051 61 2.4000000000 0.2173991203 0.0816731462 0.2173991203 0.0069361494 0.0232090000 125795645 0 402718720 -0.1060889363 -0.0012071860 0.0053246208 62 2.4400000000 0.2337903976 0.0841266503 0.2337903976 0.0076108332 0.0239340000 125797893 0 402718720 -0.1137990132 -0.0009842241 0.0088096196 63 2.4800000000 0.2390441597 0.0865856584 0.2390441597 0.0077847861 0.0245840000 125800141 0 402718720 -0.1172221527 -0.0012369355 0.0097387042 64 2.5200000000 0.2465581745 0.0890852289 0.2465581745 0.0082257953 0.0232250000 125802389 0 402718720 -0.1224385053 -0.0008748922 0.0113452338 65 2.5600000000 0.2576562464 0.0916786292 0.2576562464 0.0086210974 0.0238170000 125811293 0 402718720 -0.1253427565 0.0002159419 0.0125944251 66 2.6000000000 0.2649591267 0.0943040913 0.2649591267 0.0087772542 0.0237580000 125826341 0 402718720 -0.1287907958 0.0006271695 0.0131456200 67 2.6400000000 0.2720668018 0.0969572661 0.2720668018 0.0088879516 0.0570910000 144663089 0 402718720 -0.1320098788 0.0017284239 0.0141074117 68 2.6800000000 0.2744824886 0.0995679311 0.2744824886 0.0088824142 0.0225050000 148324545 0 402718720 -0.1406597644 0.0025082221 0.0145887658 69 2.7200000000 0.2811039686 0.1021988882 0.2811039686 0.0088429507 0.0174690000 151518985 0 402718720 -0.1438241750 0.0029017453 0.0162004028 70 2.7600000000 0.2871097922 0.1048404725 0.2871097922 0.0087928865 0.0158960000 151521233 0 402718720 -0.1466896087 0.0032136887 0.0160009712 71 2.8000000000 0.2915111482 0.1074696370 0.2915111482 0.0087542959 0.0149740000 151523481 0 402718720 -0.1492812485 0.0035502850 0.0148926862 72 2.8400000000 0.3018983901 0.1101700363 0.3018983901 0.0088141926 0.0162560000 151525729 0 402718720 -0.1551019698 0.0057803071 0.0157016926 73 2.8800000000 0.3084669411 0.1128864323 0.3084669411 0.0087703724 0.0148050000 151527977 0 402718720 -0.1585803181 0.0060032313 0.0162813291 74 2.9200000000 0.3091797233 0.1155390443 0.3091797233 0.0087713983 0.0160010000 151530225 0 402718720 -0.1598259062 0.0068172263 0.0152416499 75 2.9600000000 0.3102965355 0.1181358109 0.3102965355 0.0087605037 0.0168690000 151532473 0 402718720 -0.1599810719 0.0082372781 0.0140581075 76 3.0000000000 0.3078273237 0.1206317518 0.3102965355 0.0087653502 0.0162470000 151534721 0 402718720 -0.1601888835 0.0088258097 0.0111521548 77 3.0400000000 0.3083820045 0.1230700668 0.3102965355 0.0087747773 0.0173890000 151536969 0 402718720 -0.1598771363 0.0090502528 0.0088516306 78 3.0800000000 0.3078468740 0.1254390002 0.3102965355 0.0087654802 0.0167160000 151539217 0 402718720 -0.1585443467 0.0099994652 0.0062454906 79 3.1200000000 0.3124079704 0.1278056960 0.3124079704 0.0087474453 0.0167820000 151541465 0 402718720 -0.1608774811 0.0113122286 0.0054211803 80 3.1600000000 0.3146394193 0.1301411176 0.3146394193 0.0087257510 0.0189770000 151543713 0 402718720 -0.1620870382 0.0127399731 0.0042311531 81 3.2000000000 0.3223671615 0.1325142786 0.3223671615 0.0087497045 0.0172730000 151545961 0 402718720 -0.1663203686 0.0123278257 0.0052228710 82 3.2400000000 0.3282389641 0.1349011650 0.3282389641 0.0087868472 0.0171130000 151548209 0 402718720 -0.1688868403 0.0127321687 0.0049807443 83 3.2800000000 0.3332856596 0.1372913397 0.3332856596 0.0088707086 0.0185970000 151550457 0 402718720 -0.1715983152 0.0137378564 0.0039253146 84 3.3200000000 0.3414836526 0.1397222005 0.3414836526 0.0089323604 0.0179760000 151552705 0 402718720 -0.1759088933 0.0135109499 0.0039092163 85 3.3600000000 0.3503438830 0.1422001027 0.3503438830 0.0090042505 0.0186380000 151554953 0 402718720 -0.1806448698 0.0142289940 0.0041058715 86 3.4000000000 0.3605352044 0.1447388829 0.3605352044 0.0091436663 0.0183090000 151557201 0 402718720 -0.1852977574 0.0147510581 0.0052353563 87 3.4400000000 0.3668980300 0.1472924363 0.3668980300 0.0092889149 0.0469730000 163866489 0 402718720 -0.1886557788 0.0140747735 0.0051088589 88 3.4800000000 0.3752645254 0.1498830283 0.3752645254 0.0094753954 0.0211770000 167528761 0 402718720 -0.1933291405 0.0139919491 0.0046040085 89 3.5200000000 0.3814198077 0.1524845651 0.3814198077 0.0096300770 0.0160020000 170723201 0 402718720 -0.1964999139 0.0141907157 0.0045886636 90 3.5600000000 0.3859815001 0.1550789755 0.3859815001 0.0097254154 0.0154060000 170725449 0 402718720 -0.1993962973 0.0137450006 0.0045555052 91 3.6000000000 0.3953829706 0.1577196787 0.3953829706 0.0098457129 0.0136360000 170727697 0 402718720 -0.2045249790 0.0132343518 0.0056582247 92 3.6400000000 0.4052372575 0.1604100872 0.4052372575 0.0099464152 0.0149770000 170729945 0 402718720 -0.2099640369 0.0140501261 0.0074910829 93 3.6800000000 0.4082173407 0.1630746813 0.4082173407 0.0099240125 0.0145060000 170732193 0 402718720 -0.2116825879 0.0136093767 0.0064481697 94 3.7200000000 0.4130294621 0.1657337747 0.4130294621 0.0098996403 0.0147850000 170734441 0 402718720 -0.2140740007 0.0127975354 0.0063101258 95 3.7600000000 0.4216758311 0.1684279016 0.4216758311 0.0099380774 0.0145000000 170736689 0 402718720 -0.2185904980 0.0136595787 0.0087615699 96 3.8000000000 0.4282309115 0.1711341830 0.4282309115 0.0099352782 0.0143930000 170738937 0 402718720 -0.2221803367 0.0135824857 0.0086163804 97 3.8400000000 0.4321443141 0.1738250091 0.4321443141 0.0098931711 0.0164240000 170741185 0 402718720 -0.2238389254 0.0125287948 0.0093493834 98 3.8800000000 0.4412858784 0.1765542016 0.4412858784 0.0099272498 0.0145150000 170743433 0 402718720 -0.2293332517 0.0124536343 0.0112518016 99 3.9200000000 0.4452390075 0.1792681896 0.4452390075 0.0098954436 0.0154760000 170745681 0 402718720 -0.2310054153 0.0132249510 0.0121419476 100 3.9600000000 0.4506099820 0.1819816075 0.4506099820 0.0098632022 0.0186730000 170747929 0 402718720 -0.2340003699 0.0129553536 0.0137993721 101 4.0000000000 0.4564238489 0.1846988574 0.4564238489 0.0098257915 0.0172020000 170750177 0 402718720 -0.2369859815 0.0122189401 0.0159838982 102 4.0400000000 0.4589808583 0.1873878966 0.4589808583 0.0097822234 0.0170460000 170752425 0 402718720 -0.2380815744 0.0116968919 0.0164446160 103 4.0800000000 0.4659328759 0.1900922168 0.4659328759 0.0097572031 0.0181610000 170754673 0 402718720 -0.2420490086 0.0115062967 0.0192626882 104 4.1200000000 0.4746868014 0.1928287032 0.4746868014 0.0097748828 0.0183760000 170756921 0 402718720 -0.2465592325 0.0110575436 0.0239610206 105 4.1600000000 0.4773190022 0.1955381346 0.4773190022 0.0097486657 0.0175170000 170759169 0 402718720 -0.2468432039 0.0110867396 0.0241745692 106 4.2000000000 0.4812963605 0.1982339670 0.4812963605 0.0097633663 0.0174530000 170761417 0 402718720 -0.2495068014 0.0106935408 0.0260909740 107 4.2400000000 0.4816958606 0.2008831435 0.4816958606 0.0097283004 0.0174610000 170763665 0 402718720 -0.2492392361 0.0101050595 0.0248189624 108 4.2800000000 0.4881804287 0.2035433036 0.4881804287 0.0097040345 0.0179240000 170765913 0 402718720 -0.2528761327 0.0099894824 0.0278310236 109 4.3200000000 0.4893859029 0.2061657127 0.4893859029 0.0096692947 0.0180610000 170768161 0 402718720 -0.2535161972 0.0101422239 0.0282976534 110 4.3600000000 0.4946853518 0.2087886186 0.4946853518 0.0096851829 0.0180870000 170770409 0 402718720 -0.2565478384 0.0098418463 0.0317895412 111 4.4000000000 0.4991100729 0.2114041272 0.4991100729 0.0096862800 0.0187040000 170772657 0 402718720 -0.2589139640 0.0090666311 0.0342084058 112 4.4400000000 0.5043582916 0.2140197893 0.5043582916 0.0097071410 0.0428330000 183079565 0 402718720 -0.2620716095 0.0105703380 0.0372801423 113 4.4800000000 0.5073931813 0.2166160140 0.5073931813 0.0096943305 0.0138690000 186741021 0 402718720 -0.2635770738 0.0110402107 0.0388241000 114 4.5200000000 0.5155249834 0.2192380225 0.5155249834 0.0097758143 0.0197440000 189935461 0 402718720 -0.2671762407 0.0098763071 0.0429840386 115 4.5600000000 0.5154689550 0.2218139437 0.5155249834 0.0097717272 0.0149440000 189937709 0 402718720 -0.2680678666 0.0110291652 0.0446045920 116 4.6000000000 0.5235694647 0.2244152844 0.5235694647 0.0098516379 0.0138920000 189939957 0 402718720 -0.2713770866 0.0119551113 0.0485775843 117 4.6400000000 0.5294877887 0.2270227417 0.5294877887 0.0098822749 0.0139450000 189942205 0 402718720 -0.2741332054 0.0133876381 0.0523652136 118 4.6800000000 0.5333180428 0.2296184646 0.5333180428 0.0098513429 0.0136050000 189944453 0 402718720 -0.2762209773 0.0128565161 0.0541787259 119 4.7200000000 0.5386661291 0.2322155038 0.5386661291 0.0098132933 0.0131050000 189946701 0 402718720 -0.2779812515 0.0128724435 0.0562440567 120 4.7600000000 0.5437530875 0.2348116503 0.5437530875 0.0097798252 0.0140750000 189948949 0 402718720 -0.2804790735 0.0136902547 0.0595824607 121 4.8000000000 0.5515725017 0.2374295086 0.5515725017 0.0097583301 0.0133390000 189951197 0 402718720 -0.2840192616 0.0137148686 0.0663305596 122 4.8400000000 0.5526536703 0.2400133132 0.5526536703 0.0097212193 0.0133660000 189953445 0 402718720 -0.2845902145 0.0141890720 0.0665420368 123 4.8800000000 0.5571398735 0.2425915779 0.5571398735 0.0097045564 0.0162080000 189955693 0 402718720 -0.2865120769 0.0156567600 0.0686997026 124 4.9200000000 0.5650275946 0.2451918684 0.5650275946 0.0097153188 0.0145650000 189957941 0 402718720 -0.2898373306 0.0161452927 0.0748185068 125 4.9600000000 0.5687020421 0.2477799498 0.5687020421 0.0096983589 0.0148770000 189960189 0 402718720 -0.2912147343 0.0159034804 0.0764933899 126 5.0000000000 0.5725595951 0.2503575660 0.5725595951 0.0096810646 0.0177730000 189962437 0 402718720 -0.2931111753 0.0166854262 0.0793475732 127 5.0400000000 0.5809868574 0.2529609462 0.5809868574 0.0096711683 0.0162680000 189964685 0 402718720 -0.2965086997 0.0175804645 0.0857666582 128 5.0800000000 0.5854790211 0.2555587437 0.5854790211 0.0096390568 0.0165560000 189966933 0 402718720 -0.2983017862 0.0175498221 0.0878348947 129 5.1200000000 0.5887804627 0.2581418578 0.5887804627 0.0096102276 0.0165360000 189982493 0 402718720 -0.2999273837 0.0176104177 0.0904811397 130 5.1600000000 0.5976077914 0.2607531342 0.5976077914 0.0096396193 0.0172740000 190010341 0 402718720 -0.3026690185 0.0176745821 0.0968957767 131 5.2000000000 0.6004859805 0.2633465147 0.6004859805 0.0096558063 0.0165860000 190012589 0 402718720 -0.3040387928 0.0183656998 0.0984177589 132 5.2400000000 0.6003753543 0.2658997635 0.6004859805 0.0096493236 0.0171390000 190014837 0 402718720 -0.3041263223 0.0182983875 0.0975877866 133 5.2800000000 0.6102161407 0.2684886084 0.6102161407 0.0096959443 0.0176550000 190017085 0 402718720 -0.3076654971 0.0182976741 0.1045560315 134 5.3200000000 0.6189224720 0.2711037865 0.6189224720 0.0097624697 0.0171030000 190019333 0 402718720 -0.3105833232 0.0195158757 0.1104523465 135 5.3600000000 0.6216925979 0.2737007407 0.6216925979 0.0097741791 0.0450710000 202329057 0 402718720 -0.3117433190 0.0194945876 0.1118059978 136 5.4000000000 0.6278383136 0.2763046934 0.6278383136 0.0098143022 0.0221410000 205990513 0 402718720 -0.3143869638 0.0193609763 0.1172653809 137 5.4400000000 0.6325834394 0.2789052682 0.6325834394 0.0098663081 0.0156850000 209184953 0 402718720 -0.3164680600 0.0201274976 0.1209488362 138 5.4800000000 0.6370843053 0.2815007685 0.6370843053 0.0099042126 0.0160020000 209187201 0 402718720 -0.3183452487 0.0199269801 0.1227249056 139 5.5200000000 0.6419104934 0.2840936442 0.6419104934 0.0099426086 0.0154980000 209189449 0 402718720 -0.3204228580 0.0190570001 0.1246168315 140 5.5600000000 0.6500366330 0.2867075227 0.6500366330 0.0100531391 0.0140550000 209191697 0 402718720 -0.3241244555 0.0198736060 0.1302408129 141 5.6000000000 0.6554880142 0.2893229872 0.6554880142 0.0100835374 0.0143670000 209193945 0 402718720 -0.3252510726 0.0198457986 0.1316012293 142 5.6400000000 0.6641548276 0.2919626480 0.6641548276 0.0101566055 0.0137070000 209196193 0 402718720 -0.3285426199 0.0204624515 0.1371442527 143 5.6800000000 0.6696986556 0.2946041586 0.6696986556 0.0102273056 0.0131330000 209198441 0 402718720 -0.3303154111 0.0211573076 0.1406756043 144 5.7200000000 0.6753698587 0.2972483648 0.6753698587 0.0102782234 0.0132290000 209200689 0 402718720 -0.3324537277 0.0218615271 0.1435438693 145 5.7600000000 0.6803185940 0.2998902285 0.6803185940 0.0102821734 0.0164640000 209202937 0 402718720 -0.3343620896 0.0216264818 0.1459590644 146 5.8000000000 0.6859486699 0.3025344644 0.6859486699 0.0102818417 0.0147400000 209205185 0 402718720 -0.3364254236 0.0216086507 0.1495205611 147 5.8400000000 0.6972199678 0.3052193998 0.6972199678 0.0102990883 0.0141190000 209207433 0 402718720 -0.3398281634 0.0214723535 0.1570994407 148 5.8800000000 0.6988965869 0.3078793808 0.6988965869 0.0102744231 0.0179980000 209209681 0 402718720 -0.3403292000 0.0213995054 0.1582107842 149 5.9200000000 0.7047211528 0.3105427484 0.7047211528 0.0102581996 0.0167030000 209211929 0 402718720 -0.3415447474 0.0216303989 0.1616670340 150 5.9600000000 0.7088704705 0.3131982665 0.7088704705 0.0102393616 0.0160270000 209214177 0 402718720 -0.3428902626 0.0216409229 0.1651712954 151 6.0000000000 0.7134874463 0.3158491882 0.7134874463 0.0102173823 0.0164120000 209216425 0 402718720 -0.3439982831 0.0219048057 0.1683527082 152 6.0400000000 0.7185481787 0.3184985237 0.7185481787 0.0102043055 0.0429930000 221522265 0 402718720 -0.3447693288 0.0227750223 0.1719049066 153 6.0800000000 0.7221766114 0.3211369426 0.7221766114 0.0102003738 0.0207310000 225183721 0 402718720 -0.3464052379 0.0232961383 0.1760382652 154 6.1200000000 0.7280732989 0.3237793864 0.7280732989 0.0102208167 0.0156030000 228378161 0 402718720 -0.3480424881 0.0230599567 0.1804041415 155 6.1600000000 0.7299470901 0.3263998232 0.7299470901 0.0102567957 0.0140840000 228380409 0 402718720 -0.3495118916 0.0233747326 0.1839635670 156 6.2000000000 0.7376989722 0.3290363562 0.7376989722 0.0103520126 0.0143270000 228382657 0 402718720 -0.3505620360 0.0234494768 0.1883842051 157 6.2400000000 0.7422654629 0.3316683888 0.7422654629 0.0104148603 0.0147240000 228384905 0 402718720 -0.3510501385 0.0236589555 0.1923416257 158 6.2800000000 0.7482877374 0.3343052201 0.7482877374 0.0104795453 0.0140770000 228387153 0 402718720 -0.3523753285 0.0237022061 0.1984969527 159 6.3200000000 0.7513378263 0.3369280667 0.7513378263 0.0104924567 0.0141490000 228389401 0 402718720 -0.3521249592 0.0235469732 0.2009515762 160 6.3600000000 0.7566862702 0.3395515554 0.7566862702 0.0105249944 0.0140030000 228391649 0 402718720 -0.3524422348 0.0239901543 0.2063861191 161 6.4000000000 0.7596268058 0.3421607185 0.7596268058 0.0105066838 0.0146500000 228393897 0 402718720 -0.3525141180 0.0243066009 0.2103177160 162 6.4400000000 0.7632328868 0.3447599294 0.7632328868 0.0104814048 0.0165870000 228396145 0 402718720 -0.3522535563 0.0236962251 0.2145528048 163 6.4800000000 0.7680872679 0.3473570296 0.7680872679 0.0104620942 0.0411060000 240701429 0 402718720 -0.3523919880 0.0237446111 0.2190685272 164 6.5200000000 0.7712938190 0.3499420101 0.7712938190 0.0104333972 0.0204120000 244364565 0 402718720 -0.3526204824 0.0238789637 0.2242215127 165 6.5600000000 0.7779642344 0.3525360841 0.7779642344 0.0104031196 0.0151640000 247559005 0 402718720 -0.3526974022 0.0247213561 0.2304646969 166 6.6000000000 0.7810848355 0.3551177031 0.7810848355 0.0103794708 0.0139030000 247561253 0 402718720 -0.3524577916 0.0249313507 0.2346698940 167 6.6400000000 0.7841995358 0.3576870554 0.7841995358 0.0103534925 0.0137230000 247563501 0 402718720 -0.3519793153 0.0253541786 0.2380654067 168 6.6800000000 0.7874469757 0.3602451502 0.7874469757 0.0103244048 0.0140720000 247565749 0 402718720 -0.3519443870 0.0257717669 0.2434362173 169 6.7200000000 0.7928531170 0.3628049606 0.7928531170 0.0102964424 0.0141950000 247567997 0 402718720 -0.3515776992 0.0248068850 0.2481770068 170 6.7600000000 0.7999325395 0.3653762993 0.7999325395 0.0102998173 0.0137690000 247570245 0 402718720 -0.3525275588 0.0253861248 0.2539035976 171 6.8000000000 0.8026705980 0.3679335759 0.8026705980 0.0102883798 0.0136900000 247572493 0 402718720 -0.3520610034 0.0263133012 0.2571960390 172 6.8400000000 0.8069714308 0.3704861216 0.8069714308 0.0102683787 0.0135560000 247574741 0 402718720 -0.3518681824 0.0269141942 0.2618531585 173 6.8800000000 0.8122707009 0.3730397897 0.8122707009 0.0102494445 0.0155700000 247576989 0 402718720 -0.3520891368 0.0275392104 0.2666411996 174 6.9200000000 0.8174779415 0.3755940319 0.8174779415 0.0102307346 0.0141630000 247579237 0 402718720 -0.3524176478 0.0278209038 0.2712008953 175 6.9600000000 0.8219661713 0.3781447299 0.8219661713 0.0102090332 0.0141740000 247581485 0 402718720 -0.3519482911 0.0282956176 0.2752332091 176 7.0000000000 0.8280820847 0.3807011921 0.8280820847 0.0101942869 0.0174310000 247583733 0 402718720 -0.3525529504 0.0283221379 0.2804933488 177 7.0400000000 0.8299837112 0.3832395114 0.8299837112 0.0101840894 0.0156370000 247585981 0 402718720 -0.3522150218 0.0274505895 0.2831838727 178 7.0800000000 0.8322598934 0.3857620979 0.8322598934 0.0101574140 0.0149530000 247588229 0 402718720 -0.3516640365 0.0272462331 0.2856094539 179 7.1200000000 0.8372799754 0.3882845441 0.8372799754 0.0101477859 0.0164950000 247590477 0 402718720 -0.3516795039 0.0282423086 0.2904897332 180 7.1600000000 0.8421733379 0.3908061485 0.8421733379 0.0101282327 0.0169360000 247592725 0 402718720 -0.3512351215 0.0288783237 0.2949400246 181 7.2000000000 0.8452867270 0.3933170909 0.8452867270 0.0101008894 0.0513800000 259903005 0 402718720 -0.3505506217 0.0291190427 0.2987278104 182 7.2400000000 0.8510167003 0.3958319240 0.8510167003 0.0100773713 0.0198770000 263564461 0 402718720 -0.3507442772 0.0287639704 0.3034910560 183 7.2800000000 0.8586645722 0.3983610641 0.8586645722 0.0100563164 0.0144510000 266758901 0 402718720 -0.3512417376 0.0289066769 0.3090647459 184 7.3200000000 0.8615168333 0.4008782150 0.8615168333 0.0100311432 0.0134940000 266761149 0 402718720 -0.3507487774 0.0283339210 0.3129876852 185 7.3600000000 0.8676520586 0.4034013169 0.8676520586 0.0100167143 0.0131480000 266763397 0 402718720 -0.3497818112 0.0288904216 0.3179847300 186 7.4000000000 0.8749185205 0.4059363556 0.8749185205 0.0100161295 0.0136960000 266765645 0 402718720 -0.3497821689 0.0291053150 0.3250473738 187 7.4400000000 0.8772376776 0.4084566835 0.8772376776 0.0100016376 0.0137900000 266767893 0 402718720 -0.3487755954 0.0289534498 0.3273704648 188 7.4800000000 0.8825381994 0.4109783937 0.8825381994 0.0100214538 0.0141780000 266770141 0 402718720 -0.3478926122 0.0300165024 0.3330676854 189 7.5200000000 0.8888508677 0.4135068195 0.8888508677 0.0100081516 0.0132780000 266772389 0 402718720 -0.3471903801 0.0304779541 0.3396416605 190 7.5600000000 0.8944304585 0.4160379966 0.8944304585 0.0099832837 0.0132690000 266774637 0 402718720 -0.3463217020 0.0302876364 0.3444376588 191 7.6000000000 0.9011255503 0.4185777220 0.9011255503 0.0099816195 0.0155040000 266776885 0 402718720 -0.3457262218 0.0310245268 0.3501581550 192 7.6400000000 0.9061426520 0.4211171227 0.9061426520 0.0099859559 0.0616240000 279102157 0 402718720 -0.3444477022 0.0330410302 0.3554238975 193 7.6800000000 0.9146364331 0.4236742175 0.9146364331 0.0099645842 0.0192850000 282763613 0 402718720 -0.3441362679 0.0332992412 0.3617093563 194 7.7200000000 0.9218332767 0.4262420477 0.9218332767 0.0099487420 0.0144670000 285958053 0 402718720 -0.3442996144 0.0319975875 0.3676230311 195 7.7600000000 0.9271444082 0.4288107778 0.9271444082 0.0099609777 0.0132640000 285960301 0 402718720 -0.3439233303 0.0319002643 0.3721566498 196 7.8000000000 0.9341305494 0.4313889399 0.9341305494 0.0100165768 0.0133960000 285962549 0 402718720 -0.3432424068 0.0328902043 0.3780444860 197 7.8400000000 0.9389053583 0.4339651654 0.9389053583 0.0100492065 0.0132920000 285964797 0 402718720 -0.3426213861 0.0337745585 0.3822146952 198 7.8800000000 0.9462633133 0.4365525297 0.9462633133 0.0100892382 0.0128200000 285967045 0 402718720 -0.3422258496 0.0344071090 0.3881729543 199 7.9200000000 0.9529997706 0.4391477420 0.9529997706 0.0100928840 0.0131870000 285969293 0 402718720 -0.3413788974 0.0349746943 0.3934619427 200 7.9600000000 0.9592309594 0.4417481581 0.9592309594 0.0100952746 0.0124060000 285971541 0 402718720 -0.3415375054 0.0342200808 0.3985419273 201 8.0000000000 0.9681730270 0.4443671873 0.9681730270 0.0101335107 0.0680500000 298286773 0 402718720 -0.3410054445 0.0342790373 0.4049820900 202 8.0400000000 0.9721210003 0.4469798299 0.9721210003 0.0101488560 0.0167890000 301948229 0 402718720 -0.3398658335 0.0345104337 0.4085408151 203 8.0800000000 0.9794805646 0.4496029863 0.9794805646 0.0101724847 0.0144450000 305142669 0 402718720 -0.3391140103 0.0347674116 0.4146667123 204 8.1200000000 0.9845325947 0.4522251902 0.9845325947 0.0101696128 0.0135420000 305144917 0 402718720 -0.3384808898 0.0347656496 0.4192883968 205 8.1600000000 0.9890484810 0.4548438404 0.9890484810 0.0101589495 0.0127600000 305147165 0 402718720 -0.3374020457 0.0344475880 0.4233745635 206 8.1999999990 0.9941090941 0.4574616329 0.9941090941 0.0101507072 0.0123760000 305149413 0 402718720 -0.3362645209 0.0343486778 0.4283294976 207 8.2400000000 0.9991822243 0.4600786406 0.9991822243 0.0101452458 0.0125270000 305151661 0 402718720 -0.3346384168 0.0350381210 0.4329459667 208 8.2799999990 1.0030200481 0.4626889358 1.0030200481 0.0101230621 0.0121730000 305153909 0 402718720 -0.3334478438 0.0352818370 0.4382093847 209 8.3200000000 1.0083713531 0.4652998565 1.0083713531 0.0100989838 0.0122390000 305156157 0 402718720 -0.3314937055 0.0360897593 0.4421331584 210 8.3599999990 1.0117087364 0.4679018035 1.0117087364 0.0100838135 0.0126360000 305158405 0 402718720 -0.3294953704 0.0362538472 0.4460187554 211 8.4000000000 1.0164397955 0.4705015097 1.0164397955 0.0100669125 0.0133990000 305160653 0 402718720 -0.3277050853 0.0356719345 0.4511058927 212 8.4399999990 1.0193883181 0.4730905984 1.0193883181 0.0100445726 0.0702850000 317478809 0 402718720 -0.3252347708 0.0360395201 0.4553400278 213 8.4800000000 1.0243117809 0.4756784913 1.0243117809 0.0100214660 0.0164170000 321140265 0 402718720 -0.3231192827 0.0365029871 0.4604446590 214 8.5200000000 1.0273880959 0.4782565735 1.0273880959 0.0100220883 0.0131240000 324334705 0 402718720 -0.3204509616 0.0369575098 0.4655798078 215 8.5600000000 1.0299692154 0.4808226788 1.0299692154 0.0100121634 0.0118440000 324336953 0 402718720 -0.3178730607 0.0363798812 0.4687892795 216 8.6000000000 1.0327202082 0.4833777600 1.0327202082 0.0099959503 0.0119370000 324339201 0 402718720 -0.3147983253 0.0371462032 0.4727402329 217 8.6400000000 1.0380108356 0.4859336728 1.0380108356 0.0099847788 0.0115050000 324341449 0 402718720 -0.3115737736 0.0382140242 0.4789801240 218 8.6800000000 1.0397810936 0.4884742573 1.0397810936 0.0099986872 0.0116390000 324343697 0 402718720 -0.3084067404 0.0378233753 0.4823375344 219 8.7200000000 1.0416063070 0.4909999744 1.0416063070 0.0099812435 0.0113170000 324345945 0 402718720 -0.3047378659 0.0392596647 0.4860548675 220 8.7600000000 1.0442626476 0.4935148047 1.0442626476 0.0099646015 0.0116410000 324348193 0 402718720 -0.3010775149 0.0404858403 0.4901413321 221 8.8000000000 1.0473954678 0.4960210521 1.0473954678 0.0099592330 0.0119550000 324350441 0 402718720 -0.2975641489 0.0410492979 0.4942808151 222 8.8400000000 1.0519853830 0.4985253959 1.0519853830 0.0099414540 0.0132440000 324352689 0 402718720 -0.2942618728 0.0414640121 0.4994584620 223 8.8800000000 1.0537692308 0.5010152786 1.0537692308 0.0099293848 0.0123410000 324354937 0 402718720 -0.2910462618 0.0420455001 0.5022886395 224 8.9200000000 1.0558432341 0.5034921891 1.0558432341 0.0099109673 0.0134970000 324357185 0 402718720 -0.2866427600 0.0432965346 0.5068061352 225 8.9600000000 1.0568205118 0.5059514261 1.0568205118 0.0098942850 0.0141280000 324359433 0 402718720 -0.2829603255 0.0439508334 0.5096468925 226 9.0000000000 1.0596554279 0.5084014438 1.0596554279 0.0098731683 0.0154850000 324361681 0 402718720 -0.2791900933 0.0452713892 0.5140193701 227 9.0400000000 1.0604673624 0.5108334522 1.0604673624 0.0098578412 0.0142790000 324363929 0 402718720 -0.2748233974 0.0475657918 0.5172956586 228 9.0800000000 1.0648046732 0.5132631506 1.0648046732 0.0098585508 0.0142350000 324366177 0 402718720 -0.2707956433 0.0493953973 0.5219143629 229 9.1200000000 1.0653085709 0.5156738293 1.0653085709 0.0098937253 0.0139710000 324368425 0 402718720 -0.2670617104 0.0502202436 0.5252236724 230 9.1600000000 1.0663840771 0.5180682217 1.0663840771 0.0099538713 0.0144030000 324370673 0 402718720 -0.2633331716 0.0518945120 0.5270731449 231 9.2000000000 1.0677944422 0.5204479888 1.0677944422 0.0100700780 0.0143020000 324372921 0 402718720 -0.2601428926 0.0518694818 0.5296427011 232 9.2400000000 1.0697886944 0.5228158367 1.0697886944 0.0101398781 0.0142350000 324375169 0 402718720 -0.2566582859 0.0530637279 0.5326526761 233 9.2800000000 1.0712833405 0.5251697745 1.0712833405 0.0102077458 0.0147390000 324377417 0 402718720 -0.2532252371 0.0541531257 0.5351321101 234 9.3200000000 1.0725697279 0.5275090905 1.0725697279 0.0102527201 0.0147830000 324379665 0 402718720 -0.2497391850 0.0553517453 0.5374407172 235 9.3600000000 1.0737156868 0.5298333739 1.0737156868 0.0102882935 0.0144430000 324381913 0 402718720 -0.2466205806 0.0560950898 0.5400568247 236 9.4000000000 1.0761059523 0.5321480882 1.0761059523 0.0103042245 0.0148920000 324384161 0 402718720 -0.2427918166 0.0575185381 0.5431861877 237 9.4400000000 1.0770404339 0.5344472121 1.0770404339 0.0103122876 0.0147240000 324386409 0 402718720 -0.2391695231 0.0590146184 0.5456309319 238 9.4800000000 1.0789725780 0.5367351338 1.0789725780 0.0103174507 0.0152150000 324388657 0 402718720 -0.2353519052 0.0613052025 0.5482578874 239 9.5200000000 1.0807883739 0.5390115072 1.0807883739 0.0103439152 0.0150050000 324390905 0 402718720 -0.2315854728 0.0622321703 0.5508334041 240 9.5600000000 1.0832982063 0.5412793684 1.0832982063 0.0103601878 0.0154750000 324393153 0 402718720 -0.2279406488 0.0646625161 0.5539540052 241 9.6000000000 1.0856798887 0.5435382917 1.0856798887 0.0103882869 0.0151950000 324395401 0 402718720 -0.2245188504 0.0646914542 0.5573967695 242 9.6400000000 1.0883061886 0.5457893987 1.0883061886 0.0103909461 0.0148990000 324397649 0 402718720 -0.2212020606 0.0655847341 0.5602961183 243 9.6800000000 1.0906634331 0.5480316787 1.0906634331 0.0103858494 0.0155030000 324399897 0 402718720 -0.2173429132 0.0679290742 0.5628029704 244 9.7200000000 1.0928949118 0.5502647247 1.0928949118 0.0103892307 0.0759870000 336721097 0 402718720 -0.2133662850 0.0700582564 0.5658233166 245 9.7600000000 1.0939289331 0.5524837623 1.0939289331 0.0104016480 0.0173700000 340382553 0 402718720 -0.2103543878 0.0707375109 0.5698718429 246 9.8000000000 1.0970891714 0.5546976055 1.0970891714 0.0103948572 0.0190640000 343576993 0 402718720 -0.2066447139 0.0716053247 0.5729529262 247 9.8400000000 1.1006529331 0.5569079509 1.1006529331 0.0103849430 0.0177500000 343579241 0 402718720 -0.2033293545 0.0715960413 0.5766546130 248 9.8800000000 1.1037877798 0.5591131115 1.1037877798 0.0103652199 0.0179100000 343581489 0 402718720 -0.2001116127 0.0722964704 0.5795533061 249 9.9200000000 1.1062053442 0.5613102691 1.1062053442 0.0103499204 0.0165580000 343583737 0 402718720 -0.1963402182 0.0728895366 0.5824087858 250 9.9600000000 1.1096193790 0.5635035055 1.1096193790 0.0103364629 0.0159620000 343585985 0 402718720 -0.1929075420 0.0736384690 0.5855966806 251 10.0000000000 1.1129138470 0.5656923913 1.1129138470 0.0103229783 0.0159250000 343588233 0 402718720 -0.1892560273 0.0744017288 0.5888003111 252 10.0400000000 1.1173499823 0.5678815088 1.1173499823 0.0103091634 0.0153320000 343590481 0 402718720 -0.1863273680 0.0739592165 0.5925435424 253 10.0800000000 1.1214652061 0.5700695866 1.1214652061 0.0103000436 0.0147110000 343592729 0 402718720 -0.1836611331 0.0727620199 0.5961072445 254 10.1200000000 1.1251574755 0.5722549720 1.1251574755 0.0103233371 0.0158320000 343594977 0 402718720 -0.1802565753 0.0739839673 0.5992047191 255 10.1600000000 1.1288121939 0.5744375493 1.1288121939 0.0103425135 0.0153080000 343597225 0 402718720 -0.1763115972 0.0763203055 0.6024689674 256 10.2000000000 1.1322031021 0.5766163210 1.1322031021 0.0103298034 0.0148320000 343599473 0 402718720 -0.1723644733 0.0780251473 0.6054214835 257 10.2400000000 1.1356946230 0.5787917230 1.1356946230 0.0103133858 0.0159330000 343628345 0 402718720 -0.1689929813 0.0777233914 0.6086630225 258 10.2800000000 1.1396112442 0.5809654421 1.1396112442 0.0102967942 0.0162370000 343681793 0 402718720 -0.1652827114 0.0795790181 0.6117190123 259 10.3200000000 1.1418882608 0.5831311672 1.1418882608 0.0102780357 0.0156700000 343684041 0 402718720 -0.1616239846 0.0808270276 0.6140349507 260 10.3600000000 1.1451563835 0.5852928027 1.1451563835 0.0102627855 0.0161040000 343686289 0 402718720 -0.1579993516 0.0813129470 0.6171442270 261 10.4000000000 1.1480120420 0.5874488151 1.1480120420 0.0102483827 0.0863660000 356038349 0 402718720 -0.1548199803 0.0810430646 0.6191711426 262 10.4400000000 1.1503139734 0.5895971554 1.1503139734 0.0102329087 0.0210090000 359699805 0 402718720 -0.1511825621 0.0836084634 0.6221004128 263 10.4800000000 1.1520640850 0.5917358129 1.1520640850 0.0102136125 0.0170780000 362894245 0 402718720 -0.1473961174 0.0840778500 0.6241913438 264 10.5200000000 1.1540338993 0.5938657299 1.1540338993 0.0101961429 0.0158320000 362896493 0 402718720 -0.1437197626 0.0838720426 0.6263259053 265 10.5600000000 1.1561374664 0.5959875101 1.1561374664 0.0101792873 0.0152090000 362898741 0 402718720 -0.1397460550 0.0844422206 0.6286537647 266 10.6000000000 1.1572129726 0.5980973802 1.1572129726 0.0101697548 0.0143260000 362900989 0 402718720 -0.1355833262 0.0852065012 0.6301243305 267 10.6400000000 1.1579390764 0.6001941656 1.1579390764 0.0101655604 0.0141140000 362903237 0 402718720 -0.1316031218 0.0848472342 0.6315984130 268 10.6800000000 1.1601835489 0.6022836782 1.1601835489 0.0101535588 0.0147630000 362905485 0 402718720 -0.1275763661 0.0845343396 0.6336929202 269 10.7200000000 1.1598248482 0.6043563220 1.1601835489 0.0101407855 0.0142900000 362907733 0 402718720 -0.1233092025 0.0844852626 0.6346352696 270 10.7600000000 1.1633309126 0.6064265982 1.1633309126 0.0101415735 0.0147440000 362909981 0 402718720 -0.1143533513 0.0859282166 0.6383813620 271 10.8000000000 1.1639099121 0.6084837322 1.1639099121 0.0101649062 0.0170020000 362912229 0 402718720 -0.1092835069 0.0872258171 0.6395299435 272 10.8400000000 1.1645317078 0.6105280263 1.1645317078 0.0102216829 0.0157690000 362914477 0 402718720 -0.1050002798 0.0865565464 0.6408413649 273 10.8800000000 1.1658997536 0.6125623549 1.1658997536 0.0102242879 0.0155140000 362916725 0 402718720 -0.1004560962 0.0868138969 0.6424898505 274 10.9200000000 1.1667189598 0.6145848243 1.1667189598 0.0102287661 0.0179880000 362918973 0 402718720 -0.0957959890 0.0872296393 0.6438397169 275 10.9600000000 1.1671009064 0.6165939737 1.1671009064 0.0102342328 0.0167690000 362921221 0 402718720 -0.0911556184 0.0871205330 0.6447941065 276 11.0000000000 1.1682173014 0.6185926089 1.1682173014 0.0102301308 0.0169040000 362923469 0 402718720 -0.0863206685 0.0877939165 0.6461570859 277 11.0400000000 1.1691628695 0.6205802272 1.1691628695 0.0102333420 0.0913330000 375246641 0 402718720 -0.0815407559 0.0882948935 0.6473316550 278 11.0800000000 1.1696069241 0.6225551434 1.1696069241 0.0102345542 0.0210360000 378908097 0 402718720 -0.0756380334 0.0892736316 0.6492352486 279 11.1200000000 1.1710901260 0.6245212186 1.1710901260 0.0102480337 0.0170400000 382102537 0 402718720 -0.0708094016 0.0896965787 0.6505530477 280 11.1600000000 1.1721918583 0.6264771851 1.1721918583 0.0102613038 0.0151710000 382104785 0 402718720 -0.0658517703 0.0906021520 0.6516433358 281 11.2000000000 1.1725025177 0.6284203358 1.1725025177 0.0102721072 0.0153240000 382107033 0 402718720 -0.0613615923 0.0906149298 0.6529632807 282 11.2400000000 1.1747617722 0.6303577168 1.1747617722 0.0102650875 0.0145370000 382109281 0 402718720 -0.0569953099 0.0903627351 0.6543250084 283 11.2800000000 1.1755628586 0.6322842367 1.1755628586 0.0102509933 0.0141280000 382111529 0 402718720 -0.0526774116 0.0908078700 0.6551924944 284 11.3200000000 1.1783620119 0.6342070458 1.1783620119 0.0102394512 0.0148950000 382113777 0 402718720 -0.0481290147 0.0915179104 0.6571373940 285 11.3600000000 1.1803545952 0.6361233530 1.1803545952 0.0102415061 0.0148580000 382116025 0 402718720 -0.0440471247 0.0918309614 0.6586307883 286 11.4000000000 1.1824150085 0.6380334637 1.1824150085 0.0102442679 0.0147520000 382118273 0 402718720 -0.0403246395 0.0917967558 0.6599106193 287 11.4400000000 1.1844230890 0.6399372603 1.1844230890 0.0102397310 0.0173830000 382120521 0 402718720 -0.0369526260 0.0915918276 0.6614134312 288 11.4800000000 1.1864837408 0.6418349911 1.1864837408 0.0102346976 0.0157370000 382122769 0 402718720 -0.0337572135 0.0914890915 0.6628546715 289 11.5200000000 1.1901938915 0.6437324267 1.1901938915 0.0102303367 0.0157490000 382125017 0 402718720 -0.0307537857 0.0913594067 0.6651406288 290 11.5600000000 1.1936014891 0.6456285270 1.1936014891 0.0102280373 0.0179090000 382127265 0 402718720 -0.0277809799 0.0914086401 0.6672220826 291 11.6000000000 1.1976667643 0.6475255656 1.1976667643 0.0102227157 0.0182870000 382129513 0 402718720 -0.0250555370 0.0909419209 0.6697724462 292 11.6400000000 1.2011207342 0.6494214394 1.2011207342 0.0102180741 0.0178430000 382131761 0 402718720 -0.0221663248 0.0912120342 0.6718076468 293 11.6800000000 1.2052565813 0.6513184877 1.2052565813 0.0102107230 0.0183700000 382134009 0 402718720 -0.0196579508 0.0912258402 0.6742620468 294 11.7200000000 1.2096464634 0.6532175624 1.2096464634 0.0102012640 0.0186000000 382136257 0 402718720 -0.0174593553 0.0908263251 0.6768254638 295 11.7600000000 1.2138975859 0.6551181727 1.2138975859 0.0101947576 0.0184610000 382138505 0 402718720 -0.0154703856 0.0907769725 0.6793323159 296 11.8000000000 1.2179039717 0.6570194761 1.2179039717 0.0101880225 0.0188970000 382140753 0 402718720 -0.0133625707 0.0908128098 0.6816382408 297 11.8400000000 1.2225669622 0.6589236764 1.2225669622 0.0101847537 0.0188660000 382143001 0 402718720 -0.0115890848 0.0905250609 0.6843225956 298 11.8800000000 1.2274463177 0.6608314705 1.2274463177 0.0101889222 0.0189640000 382145249 0 402718720 -0.0098578446 0.0901793987 0.6872101426 299 11.9200000000 1.2324999571 0.6627434052 1.2324999571 0.0101882410 0.0190390000 382147497 0 402718720 -0.0079335636 0.0900870413 0.6901897788 300 11.9600000000 1.2377671003 0.6646601508 1.2377671003 0.0101799381 0.0194950000 382149745 0 402718720 -0.0061656870 0.0902757496 0.6931439638 301 12.0000000000 1.2435417175 0.6665833454 1.2435417175 0.0101712690 0.0197840000 382151993 0 402718720 -0.0045154481 0.0902849063 0.6964399815 302 12.0400000000 1.2497663498 0.6685144150 1.2497663498 0.0101684399 0.0201010000 382154241 0 402718720 -0.0031890310 0.0901388451 0.6999848485 303 12.0800000000 1.2559936047 0.6704532902 1.2559936047 0.0101746862 0.1011450000 394476981 0 402718720 -0.0015099198 0.0901125818 0.7036165595 304 12.1200000000 1.2622817755 0.6724000944 1.2622817755 0.0101870656 0.0231480000 398138437 0 402718720 -0.0003342890 0.0899768546 0.7074885368 305 12.1600000000 1.2693988085 0.6743574672 1.2693988085 0.0101983432 0.0165390000 401332877 0 402718720 0.0011516125 0.0898500681 0.7116490602 306 12.2000000000 1.2766413689 0.6763257153 1.2766413689 0.0102030711 0.0143400000 401335125 0 402718720 0.0025666840 0.0896626562 0.7158393860 307 12.2400000000 1.2839113474 0.6783048216 1.2839113474 0.0102195116 0.0148010000 401337373 0 402718720 0.0038898608 0.0900208876 0.7200373411 308 12.2800000000 1.2913733721 0.6802953039 1.2913733721 0.0102386063 0.0156330000 401339621 0 402718720 0.0047345287 0.0896705836 0.7242365479 309 12.3200000000 1.2980740070 0.6822945877 1.2980740070 0.0102718943 0.0146160000 401341869 0 402718720 0.0055629346 0.0895339400 0.7283462882 310 12.3600000000 1.3055896759 0.6843052170 1.3055896759 0.0103168932 0.0154950000 401344117 0 402718720 0.0062435633 0.0892111287 0.7326647043 311 12.4000000000 1.3124010563 0.6863248178 1.3124010563 0.0103474908 0.0154490000 401346365 0 402718720 0.0071660699 0.0893748552 0.7366332412 312 12.4400000000 1.3274778128 0.6883797954 1.3274778128 0.0104543505 0.0152100000 401348613 0 402718720 0.0081258016 0.0891562179 0.7453703284 313 12.4800000000 1.3342715502 0.6904433473 1.3342715502 0.0104552228 0.0180580000 401350861 0 402718720 0.0084168874 0.0890455619 0.7492390275 314 12.5200000000 1.3421097994 0.6925187182 1.3421097994 0.0104582452 0.0180850000 401353109 0 402718720 0.0085856933 0.0885084346 0.7538766861 315 12.5600000000 1.3493013382 0.6946037423 1.3493013382 0.0104657427 0.0170420000 401355357 0 402718720 0.0088017508 0.0884917900 0.7580159307 316 12.6000000000 1.3569842577 0.6966998832 1.3569842577 0.0104672713 0.0215550000 401357605 0 402718720 0.0090883831 0.0885317102 0.7625515461 317 12.6400000000 1.3642265797 0.6988056457 1.3642265797 0.0104683597 0.0203770000 401359853 0 402718720 0.0090817418 0.0882313699 0.7667674422 318 12.6800000000 1.3714936972 0.7009210169 1.3714936972 0.0104733674 0.0210750000 401362101 0 402718720 0.0089623146 0.0879890993 0.7709401250 319 12.7200000000 1.3777439594 0.7030427189 1.3777439594 0.0104825630 0.0213580000 401364349 0 402718720 0.0088464385 0.0879971832 0.7747459412 320 12.7600000000 1.3841965199 0.7051713245 1.3841965199 0.0104927100 0.0206650000 401366597 0 402718720 0.0085990224 0.0880027115 0.7786002159 321 12.8000000000 1.3908978701 0.7073075443 1.3908978701 0.0105153031 0.0214430000 401368845 0 402718720 0.0079354327 0.0875796899 0.7824009657 322 12.8400000000 1.3967202902 0.7094485777 1.3967202902 0.0105498678 0.0218610000 401371093 0 402718720 0.0077733370 0.0877757445 0.7859126329 323 12.8800000000 1.4020211697 0.7115927653 1.4020211697 0.0106009175 0.0213730000 401373341 0 402718720 0.0071816645 0.0872219652 0.7891439795 324 12.9200000000 1.4077882767 0.7137415168 1.4077882767 0.0106639412 0.0209320000 401375589 0 402718720 0.0061189868 0.0867893547 0.7924501896 325 12.9600000000 1.4139235020 0.7158959230 1.4139235020 0.0107308051 0.1005930000 413698657 0 402718720 0.0055895210 0.0872112885 0.7953243852 326 13.0000000000 1.4188694954 0.7180522836 1.4188694954 0.0108134131 0.0305500000 417363425 0 402718720 0.0045124707 0.0874378309 0.7974629402 327 13.0400000000 1.4249148369 0.7202139428 1.4249148369 0.0109148415 0.0263830000 420557865 0 402718720 0.0035897193 0.0872247890 0.8010748625 328 13.0800000000 1.4290174246 0.7223749290 1.4290174246 0.0110060530 0.0240860000 420560113 0 402718720 0.0036170003 0.0882253721 0.8034268618 329 13.1200000000 1.4347391129 0.7245401697 1.4347391129 0.0110944843 0.0213090000 420562361 0 402718720 0.0030032196 0.0884138942 0.8067224622 330 13.1600000000 1.4395821095 0.7267069635 1.4395821095 0.0111727201 0.0210190000 420564609 0 402718720 0.0024671571 0.0884743929 0.8097720146 331 13.2000000000 1.4455382824 0.7288786593 1.4455382824 0.0112410269 0.0192930000 420566857 0 402718720 0.0019547199 0.0886068642 0.8135709167 332 13.2400000000 1.4507424831 0.7310529479 1.4507424831 0.0112959837 0.0184290000 420569105 0 402718720 0.0013915427 0.0886362642 0.8167839050 333 13.2800000000 1.4566786289 0.7332320040 1.4566786289 0.0113505404 0.1100660000 432889773 0 402718720 0.0007410531 0.0886926353 0.8202607632 334 13.3200000000 1.4616991282 0.7354130433 1.4616991282 0.0114193344 0.0364710000 436551229 0 402718720 0.0000725956 0.0886140540 0.8232076168 335 13.3600000000 1.4670330286 0.7375969836 1.4670330286 0.0114691298 0.0309130000 439745669 0 402718720 -0.0003848662 0.0889990479 0.8266726732 336 13.4000000000 1.4722473621 0.7397834430 1.4722473621 0.0115407657 0.0300010000 439747917 0 402718720 -0.0009471264 0.0893545747 0.8294695616 337 13.4400000000 1.4770948887 0.7419713108 1.4770948887 0.0116516495 0.0286810000 439750165 0 402718720 -0.0014783128 0.0902813822 0.8322746158 338 13.4800000000 1.4809844494 0.7441577402 1.4809844494 0.0117687275 0.0258870000 439752413 0 402718720 -0.0019961593 0.0908285230 0.8347595334 339 13.5200000000 1.4844548702 0.7463415076 1.4844548702 0.0118881397 0.0246830000 439754661 0 402718720 -0.0028204599 0.0908620581 0.8368282318 340 13.5600000000 1.4877156019 0.7485220196 1.4877156019 0.0119643478 0.1470980000 452084009 0 402718720 -0.0036582488 0.0909329727 0.8386456370 341 13.6000000000 1.4916925430 0.7507014053 1.4916925430 0.0120491306 0.0389210000 455745465 0 402718720 -0.0054880800 0.0918612182 0.8393404484 342 13.6400000000 1.4950498343 0.7528778627 1.4950498343 0.0121133386 0.0288360000 458939905 0 402718720 -0.0062430841 0.0920461863 0.8416810036 343 13.6800000000 1.4981032610 0.7550505315 1.4981032610 0.0121540618 0.0282620000 458942153 0 402718720 -0.0069550090 0.0921443999 0.8434481621 344 13.7200000000 1.5015360117 0.7572205474 1.5015360117 0.0122090054 0.0259630000 458944401 0 402718720 -0.0072612129 0.0926845670 0.8456183076 345 13.7600000000 1.5048559904 0.7593876067 1.5048559904 0.0122870453 0.0241410000 458946649 0 402718720 -0.0079053799 0.0926114023 0.8477769494 346 13.8000000000 1.5080037117 0.7615512370 1.5080037117 0.0123654479 0.0231830000 458948897 0 402718720 -0.0085159512 0.0926782563 0.8496498466 347 13.8400000000 1.5105593204 0.7637097618 1.5105593204 0.0123998331 0.0225540000 458951145 0 402718720 -0.0093007069 0.0921836868 0.8515525460 348 13.8800000000 1.5143061876 0.7658666481 1.5143061876 0.0124284891 0.0226600000 458953393 0 402718720 -0.0096048191 0.0929675326 0.8537070751 349 13.9200000000 1.5180033445 0.7680217675 1.5180033445 0.0124649428 0.2201830000 471346877 0 402718720 -0.0101501783 0.0929065272 0.8557656407 350 13.9600000000 1.5283795595 0.7701942184 1.5283795595 0.0125512845 0.0340120000 475008333 0 402718720 -0.0129863648 0.0931396857 0.8538938761 351 14.0000000000 1.5310250521 0.7723618276 1.5310250521 0.0125553224 0.0247240000 478202773 0 402718720 -0.0130222179 0.0933057517 0.8555055261 352 14.0400000000 1.5338323116 0.7745250960 1.5338323116 0.0125490046 0.0226960000 478205021 0 402718720 -0.0131753124 0.0931192562 0.8573291302 353 14.0800000000 1.5362763405 0.7766830315 1.5362763405 0.0125354933 0.0215460000 478207269 0 402718720 -0.0132914744 0.0927055627 0.8591059446 354 14.1200000000 1.5392686129 0.7788372281 1.5392686129 0.0125270752 0.0208760000 478209517 0 402718720 -0.0131792575 0.0926690251 0.8609263897 355 14.1600000000 1.5420424938 0.7809871021 1.5420424938 0.0125160260 0.0216270000 478211765 0 402718720 -0.0132944146 0.0923038796 0.8627855182 356 14.2000000000 1.5448775291 0.7831328617 1.5448775291 0.0125099569 0.0215580000 478214013 0 402718720 -0.0133227715 0.0918375552 0.8646097779 357 14.2400000000 1.5483425856 0.7852763063 1.5483425856 0.0125025497 0.0228720000 478216261 0 402718720 -0.0131752724 0.0921666920 0.8667274117 358 14.2800000000 1.5515034199 0.7874166055 1.5515034199 0.0124925584 0.0227330000 478218509 0 402718720 -0.0132494103 0.0915859789 0.8688879609 359 14.3200000000 1.5546122789 0.7895536408 1.5546122789 0.0124784745 0.0278170000 478220757 0 402718720 -0.0134478202 0.0908596888 0.8711459637 360 14.3600000000 1.5582659245 0.7916889527 1.5582659245 0.0124661408 0.0263760000 478223005 0 402718720 -0.0136226648 0.0900971070 0.8735511303 361 14.4000000000 1.5621812344 0.7938232804 1.5621812344 0.0124566573 0.0265800000 478225253 0 402718720 -0.0137303984 0.0897809342 0.8760818839 362 14.4400000000 1.5661444664 0.7959567643 1.5661444664 0.0124454690 0.0319100000 478227501 0 402718720 -0.0137254307 0.0897777155 0.8786672354 363 14.4800000000 1.5706048012 0.7980907809 1.5706048012 0.0124324408 0.0313970000 478229749 0 402718720 -0.0138121583 0.0897500739 0.8814454079 364 14.5200000000 1.5749228001 0.8002249348 1.5749228001 0.0124190521 0.0312620000 478231997 0 402718720 -0.0139269382 0.0893604308 0.8843069077 365 14.5600000000 1.5790797472 0.8023587836 1.5790797472 0.0124053644 0.0312460000 478234245 0 402718720 -0.0141869104 0.0888421535 0.8871616721 366 14.6000000000 1.5839134455 0.8044941789 1.5839134455 0.0123923706 0.0327240000 478236493 0 402718720 -0.0142435888 0.0893368199 0.8901916742 367 14.6400000000 1.5884262323 0.8066302335 1.5884262323 0.0123788799 0.0320540000 478238741 0 402718720 -0.0143446969 0.0893487409 0.8930335641 368 14.6800000000 1.5930933952 0.8087673617 1.5930933952 0.0123720715 0.0321110000 478240989 0 402718720 -0.0144975167 0.0892931297 0.8960545063 369 14.7200000000 1.5975744724 0.8109050503 1.5975744724 0.0123743600 0.1649460000 490566353 0 402718720 -0.0148859415 0.0888219029 0.8990072012 370 14.7600000000 1.6105450392 0.8130662395 1.6105450392 0.0123693472 0.0349070000 494227809 0 402718720 -0.0164210517 0.0887987688 0.8938490152 371 14.8000000000 1.6149467230 0.8152276424 1.6149467230 0.0123707212 0.0244900000 497422249 0 402718720 -0.0164681952 0.0884479210 0.8966792822 372 14.8400000000 1.6190943718 0.8173885745 1.6190943718 0.0123888280 0.0228310000 497424497 0 402718720 -0.0166029893 0.0881923139 0.8995234370 373 14.8800000000 1.6234774590 0.8195496707 1.6234774590 0.0124265837 0.0228810000 497426745 0 402718720 -0.0167412460 0.0880019292 0.9024422169 374 14.9200000000 1.6278059483 0.8217107837 1.6278059483 0.0124689826 0.0236500000 497428993 0 402718720 -0.0167991612 0.0875807703 0.9054035544 375 14.9600000000 1.6319646835 0.8238714608 1.6319646835 0.0125387399 0.0227610000 497431241 0 402718720 -0.0168149192 0.0872902870 0.9081746340 376 15.0000000000 1.6365536451 0.8260328496 1.6365536451 0.0126161689 0.0231710000 497433489 0 402718720 -0.0165724885 0.0877012014 0.9110243917 377 15.0400000000 1.6445508003 0.8282039847 1.6445508003 0.0128803963 0.0221370000 497435737 0 402718720 -0.0159342960 0.0879195854 0.9161602855 378 15.0800000000 1.6484993696 0.8303740783 1.6484993696 0.0129364103 0.0219140000 497437985 0 402718720 -0.0152929015 0.0883114934 0.9187440276 379 15.1200000000 1.6519964933 0.8325419475 1.6519964933 0.0129795900 0.0283350000 497440233 0 402718720 -0.0147022111 0.0884045735 0.9209113121 380 15.1600000000 1.6552631855 0.8347070034 1.6552631855 0.0130280075 0.1378230000 509759485 0 402718720 -0.0136666317 0.0887646899 0.9230120182 381 15.2000000000 1.6593823433 0.8368715056 1.6593823433 0.0130765929 0.0444710000 513420941 0 402718720 -0.0108478265 0.0904509351 0.9238966107 382 15.2400000000 1.6621420383 0.8390318997 1.6621420383 0.0131337268 0.0298220000 516615381 0 402718720 -0.0099667944 0.0905127898 0.9259119034 383 15.2800000000 1.6649250984 0.8411882788 1.6649250984 0.0131892500 0.0275760000 516617629 0 402718720 -0.0090213176 0.0908045471 0.9276673794 384 15.3200000000 1.6672983170 0.8433396070 1.6672983170 0.0132381703 0.0255600000 516619877 0 402718720 -0.0080386596 0.0908696949 0.9291152954 385 15.3600000000 1.6687300205 0.8454834782 1.6687300205 0.0132912955 0.0257990000 516622125 0 402718720 -0.0069583757 0.0907146037 0.9301897883 386 15.4000000000 1.6700235605 0.8476195924 1.6700235605 0.0133391943 0.0264150000 516624373 0 402718720 -0.0057579945 0.0910065919 0.9310374260 387 15.4400000000 1.6714777946 0.8497484250 1.6714777946 0.0134097006 0.0249520000 516626621 0 402718720 -0.0043843384 0.0917879716 0.9318153858 388 15.4800000000 1.6721546650 0.8518680287 1.6721546650 0.0135224436 0.0229910000 516628869 0 402718720 -0.0032542639 0.0922730267 0.9321191907 389 15.5200000000 1.6728037596 0.8539784033 1.6728037596 0.0136340842 0.0242180000 516631117 0 402718720 -0.0022892191 0.0923183635 0.9324497581 390 15.5600000000 1.6737068892 0.8560802712 1.6737068892 0.0137386226 0.1581360000 528952669 0 402718720 -0.0008027906 0.0935282782 0.9329208732 391 15.6000000000 1.6750484705 0.8581748190 1.6750484705 0.0138201521 0.0227890000 532614125 0 402718720 0.0009576721 0.0948346406 0.9328099489 392 15.6400000000 1.6751701832 0.8602589909 1.6751701832 0.0139021015 0.0302440000 535808565 0 402718720 0.0021122671 0.0946185440 0.9331322312 393 15.6800000000 1.6754999161 0.8623333953 1.6754999161 0.0140249974 0.0250150000 535810813 0 402718720 0.0029620845 0.0940116793 0.9333874583 394 15.7200000000 1.6759777069 0.8643984824 1.6759777069 0.0141739140 0.0229190000 535813061 0 402718720 0.0037605355 0.0932587907 0.9337547421 395 15.7600000000 1.6763772964 0.8664541249 1.6763772964 0.0143179911 0.0237170000 535815309 0 402718720 0.0048880526 0.0935399011 0.9338870645 396 15.8000000000 1.6765266657 0.8684997627 1.6765266657 0.0144286215 0.0228490000 535817557 0 402718720 0.0062537841 0.0935376287 0.9339004755 397 15.8400000000 1.6763581038 0.8705346703 1.6765266657 0.0145678696 0.0212120000 535819805 0 402718720 0.0074315653 0.0933728516 0.9340779185 398 15.8800000000 1.6761184931 0.8725587503 1.6765266657 0.0146824093 0.0198820000 535822053 0 402718720 0.0083309645 0.0927044600 0.9336386323 399 15.9200000000 1.6751363277 0.8745702229 1.6765266657 0.0147786128 0.2451960000 548157577 0 402718720 0.0101506449 0.0931726098 0.9332638979 400 15.9600000000 1.6767115593 0.8765755762 1.6767115593 0.0148729024 0.0246490000 551819033 0 402718720 0.0116711333 0.0937876031 0.9321976304 401 16.0000000000 1.6772080660 0.8785721660 1.6772080660 0.0149670144 0.0302320000 555013473 0 402718720 0.0132013150 0.0940159932 0.9323382378 402 16.0400000000 1.6772861481 0.8805590167 1.6772861481 0.0150659880 0.0260850000 555015721 0 402718720 0.0152758397 0.0940925404 0.9325670600 403 16.0800000000 1.6782320738 0.8825383543 1.6782320738 0.0151344567 0.0246510000 555017969 0 402718720 0.0168808307 0.0937618241 0.9332184196 404 16.1200000000 1.6777745485 0.8845067607 1.6782320738 0.0151943518 0.0268390000 555020217 0 402718720 0.0185823664 0.0939346999 0.9328265786 405 16.1600000000 1.6787660122 0.8864678947 1.6787660122 0.0152752746 0.0231020000 555022465 0 402718720 0.0206322316 0.0940272957 0.9334172010 406 16.2000000000 1.6804586649 0.8884235370 1.6804586649 0.0153886765 0.2732400000 567365793 0 402718720 0.0228197444 0.0944965854 0.9344750643 407 16.2400000000 1.6819759607 0.8903732972 1.6819759607 0.0155238702 0.0251140000 571027249 0 402718720 0.0246362612 0.0948995352 0.9350168109 408 16.2800000000 1.6836037636 0.8923174895 1.6836037636 0.0156842369 0.0243380000 574221689 0 402718720 0.0268991534 0.0947588906 0.9363406301 409 16.3200000000 1.6855758429 0.8942569965 1.6855758429 0.0158273057 0.0205370000 574223937 0 402718720 0.0289155357 0.0957288146 0.9372735620 410 16.3600000000 1.6885772943 0.8961943631 1.6885772943 0.0159559737 0.0203440000 574226185 0 402718720 0.0312735289 0.0968597457 0.9388963580 411 16.3999999990 1.6896367073 0.8981248798 1.6896367073 0.0161229779 0.0195060000 574228433 0 402718720 0.0325785689 0.0963897184 0.9394453764 412 16.4400000000 1.6934735775 0.9000553378 1.6934735775 0.0163441054 0.0177190000 574230681 0 402718720 0.0345719010 0.0962007120 0.9418831468 413 16.4800000000 1.6978055239 0.9019869363 1.6978055239 0.0165436910 0.2443350000 586571837 0 402718720 0.0369571373 0.0966508165 0.9444645047 414 16.5200000000 1.7004941702 0.9039156977 1.7004941702 0.0167039927 0.0265940000 590233293 0 402718720 0.0384595357 0.0960147232 0.9452169538 415 16.5599999990 1.7036702633 0.9058428171 1.7036702633 0.0168793866 0.0196600000 593427733 0 402718720 0.0397355594 0.0938811824 0.9472603798 416 16.6000000000 1.7072602510 0.9077693014 1.7072602510 0.0170587717 0.0176620000 593429981 0 402718720 0.0423084237 0.0939133316 0.9494050145 417 16.6400000000 1.7084734440 0.9096894552 1.7084734440 0.0171722965 0.0168840000 593432229 0 402718720 0.0444863327 0.0943724886 0.9499913454 418 16.6800000000 1.7080249786 0.9115993488 1.7084734440 0.0172688564 0.0162390000 593434477 0 402718720 0.0455702990 0.0934983343 0.9496433735 419 16.7199999990 1.7118974924 0.9135093682 1.7118974924 0.0174046164 0.0160190000 593436725 0 402718720 0.0483964868 0.0941047296 0.9517698288 420 16.7600000000 1.7121195793 0.9154108211 1.7121195793 0.0174745175 0.1986060000 605774249 0 402718720 0.0510203429 0.0953055024 0.9517999887 421 16.8000000000 1.7129169703 0.9173051350 1.7129169703 0.0175148206 0.0241990000 609435705 0 402718720 0.0515580066 0.0931944624 0.9518178701 422 16.8400000000 1.7139582634 0.9191929386 1.7139582634 0.0177622720 0.0175660000 612630145 0 402718720 0.0548252761 0.0908512846 0.9525315762 423 16.8799999990 1.7141482830 0.9210722657 1.7141482830 0.0178016380 0.0164250000 612632393 0 402718720 0.0575183257 0.0905811563 0.9523788691 424 16.9200000000 1.7122087479 0.9229381536 1.7141482830 0.0178232979 0.0165380000 612634641 0 402718720 0.0602085330 0.0886174738 0.9526475668 425 16.9600000000 1.7117009163 0.9247940660 1.7141482830 0.0178535042 0.0147750000 612636889 0 402718720 0.0622930974 0.0896527469 0.9508900642 426 17.0000000000 1.7114278078 0.9266406241 1.7141482830 0.0178698109 0.0155920000 612639137 0 402718720 0.0655510798 0.0896872655 0.9506478906 427 17.0400000000 1.7084767818 0.9284716221 1.7141482830 0.0178825584 0.1601870000 624974629 0 402718720 0.0676132888 0.0883715600 0.9490574598 428 17.0800000000 1.7064262629 0.9302892731 1.7141482830 0.0178886300 0.0167550000 628636085 0 402718720 0.0701467246 0.0871649608 0.9481235147 429 17.1200000000 1.7057135105 0.9320967888 1.7141482830 0.0178914804 0.0210670000 631830525 0 402718720 0.0738000497 0.0867358670 0.9475938082 430 17.1600000000 1.7011735439 0.9338853394 1.7141482830 0.0178956760 0.0188110000 631832773 0 402718720 0.0778403133 0.0857787877 0.9454586506 431 17.2000000000 1.6987904310 0.9356600612 1.7141482830 0.0178969126 0.0188220000 631835021 0 402718720 0.0809027925 0.0842166096 0.9445986748 432 17.2400000000 1.6967443228 0.9374218303 1.7141482830 0.0178946890 0.0177700000 631837269 0 402718720 0.0842021704 0.0833730325 0.9424812198 433 17.2800000000 1.6935212612 0.9391680184 1.7141482830 0.0178860425 0.0162000000 631839517 0 402718720 0.0880678520 0.0828215852 0.9405425191 434 17.3200000000 1.6885236502 0.9408946443 1.7141482830 0.0178811308 0.0180090000 631841765 0 402718720 0.0915490091 0.0811563432 0.9373325706 435 17.3600000000 1.6857708693 0.9426070034 1.7141482830 0.0178812587 0.0162310000 631844013 0 402718720 0.0961089507 0.0809964612 0.9354710579 436 17.4000000000 1.6824780703 0.9443039554 1.7141482830 0.0178709505 0.0162510000 631846261 0 402718720 0.1014807075 0.0822807625 0.9328349829 437 17.4400000000 1.6781953573 0.9459833408 1.7141482830 0.0178560623 0.0174890000 631848509 0 402718720 0.1074617282 0.0840196833 0.9299039245 438 17.4800000000 1.6740791798 0.9476456600 1.7141482830 0.0178746270 0.1200780000 644176325 0 402718720 0.1120691523 0.0843083933 0.9270933867 439 17.5200000000 1.6677590609 0.9492860095 1.7141482830 0.0179215503 0.0247090000 647837781 0 402718720 0.1136807799 0.0839418545 0.9227323532 440 17.5600000000 1.6624302864 0.9509067919 1.7141482830 0.0179286857 0.0213150000 651032221 0 402718720 0.1155554503 0.0808136016 0.9196853042 441 17.6000000000 1.6576293707 0.9525093374 1.7141482830 0.0179172007 0.0198190000 651034469 0 402718720 0.1182505414 0.0784065425 0.9171333909 442 17.6400000000 1.6528627872 0.9540938475 1.7141482830 0.0179205846 0.0203140000 651036717 0 402718720 0.1228868961 0.0786663145 0.9140245318 443 17.6800000000 1.6438391209 0.9556508346 1.7141482830 0.0179323720 0.0182800000 651038965 0 402718720 0.1315959394 0.0799538642 0.9081382155 444 17.7200000000 1.6377297640 0.9571870484 1.7141482830 0.0179231168 0.0173620000 651041213 0 402718720 0.1349704415 0.0796257183 0.9044074416 445 17.7600000000 1.6331878901 0.9587061514 1.7141482830 0.0179140853 0.0906760000 663358809 0 402718720 0.1383495927 0.0786681175 0.9015024304 446 17.8000000000 1.6288933754 0.9602088133 1.7141482830 0.0179025296 0.0191670000 667020265 0 402718720 0.1429550350 0.0786965415 0.8976703882 447 17.8400000000 1.6246711016 0.9616953061 1.7141482830 0.0178919795 0.0196630000 670214705 0 402718720 0.1457046717 0.0779151544 0.8947970867 448 17.8800000000 1.6205135584 0.9631658826 1.7141482830 0.0178819822 0.0174790000 670216953 0 402718720 0.1483348906 0.0772401169 0.8923040628 449 17.9200000000 1.6160285473 0.9646199197 1.7141482830 0.0178774946 0.0177820000 670219201 0 402718720 0.1508659124 0.0765033513 0.8894349337 450 17.9600000000 1.6128778458 0.9660604929 1.7141482830 0.0178769127 0.0172430000 670221449 0 402718720 0.1532344520 0.0749651045 0.8874891400 451 18.0000000000 1.6101977825 0.9674887352 1.7141482830 0.0178751254 0.0162560000 670223697 0 402718720 0.1566153616 0.0747946054 0.8854910135 452 18.0400000000 1.6069889069 0.9689035586 1.7141482830 0.0178668450 0.0150430000 670225945 0 402718720 0.1598980725 0.0747170523 0.8833112121 453 18.0800000000 1.6035902500 0.9703046330 1.7141482830 0.0178571119 0.0928150000 682655185 0 402718720 0.1627702266 0.0734611973 0.8811146021 454 18.1200000000 1.6021128893 0.9716962811 1.7141482830 0.0178489547 0.0195960000 686316641 0 402718720 0.1661808044 0.0745308399 0.8778770566 455 18.1600000000 1.5997039080 0.9730765177 1.7141482830 0.0178334418 0.0189470000 689511081 0 402718720 0.1698221415 0.0741260499 0.8763015270 456 18.2000000000 1.5965886116 0.9744438687 1.7141482830 0.0178166618 0.0169360000 689513329 0 402718720 0.1726434082 0.0729407519 0.8738002181 457 18.2400000000 1.5943788290 0.9758004004 1.7141482830 0.0178023643 0.0158420000 689515577 0 402718720 0.1757241488 0.0716785565 0.8722626567 458 18.2800000000 1.5940599442 0.9771503121 1.7141482830 0.0177964996 0.0160620000 689517825 0 402718720 0.1800970435 0.0722328871 0.8712401986 459 18.3200000000 1.5917520523 0.9784893137 1.7141482830 0.0177807375 0.0155690000 689520073 0 402718720 0.1842984557 0.0730409920 0.8690299988 460 18.3600000000 1.5902507305 0.9798192298 1.7141482830 0.0177684685 0.0155560000 689522321 0 402718720 0.1871011555 0.0715400502 0.8676976562 461 18.4000000000 1.5897766352 0.9811423478 1.7141482830 0.0177560868 0.0159850000 689524569 0 402718720 0.1910352260 0.0709035471 0.8665816784 462 18.4400000000 1.5876629353 0.9824551629 1.7141482830 0.0177403884 0.0153910000 689526817 0 402718720 0.1949704885 0.0709289908 0.8647194505 463 18.4800000000 1.5849343538 0.9837564139 1.7141482830 0.0177276672 0.0165280000 689529065 0 402718720 0.1983092576 0.0704195201 0.8623928428 464 18.5200000000 1.5841196775 0.9850503002 1.7141482830 0.0177173796 0.0176620000 689531313 0 402718720 0.2009955496 0.0690495595 0.8612855673 465 18.5600000000 1.5832272768 0.9863367023 1.7141482830 0.0177182291 0.0984610000 701850857 0 402718720 0.2038682997 0.0677348524 0.8600274324 466 18.6000000000 1.5828584433 0.9876167919 1.7141482830 0.0177330162 0.0229580000 705512313 0 402718720 0.2082912773 0.0670157149 0.8596708179 467 18.6400000000 1.5826766491 0.9888910100 1.7141482830 0.0177354491 0.0169820000 708706753 0 402718720 0.2122889161 0.0663933381 0.8587096930 468 18.6800000000 1.5838217735 0.9901622296 1.7141482830 0.0177484826 0.0167020000 708709001 0 402718720 0.2159645259 0.0652806312 0.8583216667 469 18.7200000000 1.5844346285 0.9914293349 1.7141482830 0.0177714094 0.0150030000 708711249 0 402718720 0.2195910811 0.0647783801 0.8576860428 470 18.7600000000 1.5858697891 0.9926941018 1.7141482830 0.0178074547 0.0152420000 708713497 0 402718720 0.2230141014 0.0636013001 0.8574259877 471 18.8000000000 1.5861178637 0.9939540249 1.7141482830 0.0178534151 0.0157970000 708715745 0 402718720 0.2269787043 0.0628731102 0.8566266298 472 18.8400000000 1.5858737230 0.9952080921 1.7141482830 0.0178858478 0.0154730000 708717993 0 402718720 0.2307268679 0.0629008114 0.8555151820 473 18.8800000000 1.5851078033 0.9964552373 1.7141482830 0.0178994505 0.0153440000 708720241 0 402718720 0.2347476035 0.0628480166 0.8538707495 474 18.9200000000 1.5812022686 0.9976888809 1.7141482830 0.0178970674 0.0155260000 708722489 0 402718720 0.2363350540 0.0625007004 0.8513715267 475 18.9600000000 1.5812766552 0.9989174867 1.7141482830 0.0179097306 0.0190290000 708724737 0 402718720 0.2393097430 0.0617653839 0.8505172729 476 19.0000000000 1.5812822580 1.0001409421 1.7141482830 0.0179259654 0.0166820000 708726985 0 402718720 0.2431918830 0.0613487735 0.8495095968 477 19.0400000000 1.5777182579 1.0013517960 1.7141482830 0.0179229222 0.0163590000 708729233 0 402718720 0.2458610088 0.0616573282 0.8466788530 478 19.0800000000 1.5817843676 1.0025660901 1.7141482830 0.0179385573 0.0196030000 708731481 0 402718720 0.2509196401 0.0611332543 0.8477157354 479 19.1200000000 1.5822776556 1.0037763439 1.7141482830 0.0179374443 0.0201450000 708733729 0 402718720 0.2536465526 0.0602401532 0.8471549153 480 19.1600000000 1.5851958990 1.0049876346 1.7141482830 0.0179568340 0.0190500000 708735977 0 402718720 0.2573444545 0.0596059673 0.8477904797 481 19.2000000000 1.5830183029 1.0061893616 1.7141482830 0.0179601815 0.0195660000 708738225 0 402718720 0.2599792480 0.0602691546 0.8457916379 482 19.2400000000 1.5856834650 1.0073916315 1.7141482830 0.0179609859 0.0190630000 708740473 0 402718720 0.2636124790 0.0603108965 0.8459996581 483 19.2800000000 1.5863648653 1.0085903339 1.7141482830 0.0179592108 0.0947340000 721070677 0 402718720 0.2667210996 0.0595462210 0.8456015587 484 19.3200000000 1.5838418007 1.0097788699 1.7141482830 0.0179474695 0.0174640000 724732133 0 402718720 0.2679021060 0.0589956641 0.8448890448 485 19.3600000000 1.5829277039 1.0109606201 1.7141482830 0.0179381862 0.0268640000 727926573 0 402718720 0.2711839974 0.0601027831 0.8434687853 486 19.4000000000 1.5834492445 1.0121385802 1.7141482830 0.0179250711 0.0215700000 727928821 0 402718720 0.2745033801 0.0612942912 0.8423309326 487 19.4400000000 1.5826413631 1.0133100439 1.7141482830 0.0179251721 0.0206800000 727931069 0 402718720 0.2766965926 0.0600342788 0.8413545489 488 19.4800000000 1.5777220726 1.0144666259 1.7141482830 0.0179156787 0.0209780000 727933317 0 402718720 0.2764400542 0.0591984317 0.8387502432 489 19.5200000000 1.5760546923 1.0156150677 1.7141482830 0.0179149105 0.0223500000 727935565 0 402718720 0.2782924473 0.0589386635 0.8371821642 490 19.5600000000 1.5715765953 1.0167496831 1.7141482830 0.0179156468 0.0201670000 727937813 0 402718720 0.2796117067 0.0585111603 0.8344814181 491 19.6000000000 1.5698037148 1.0178760661 1.7141482830 0.0179193973 0.0198210000 727940061 0 402718720 0.2817060053 0.0581776984 0.8329601288 492 19.6400000000 1.5628690720 1.0189837754 1.7141482830 0.0179107094 0.0186220000 727942309 0 402718720 0.2817619145 0.0583360419 0.8290205598 493 19.6800000000 1.5563110113 1.0200736887 1.7141482830 0.0179078989 0.0186230000 727944557 0 402718720 0.2822959423 0.0580991618 0.8252962828 494 19.7200000000 1.5519859791 1.0211504342 1.7141482830 0.0179085501 0.0216150000 727946805 0 402718720 0.2826855183 0.0562855639 0.8227636814 495 19.7600000000 1.5452040434 1.0222091284 1.7141482830 0.0179048525 0.0212870000 727949053 0 402718720 0.2826902568 0.0551912747 0.8192294240 496 19.8000000000 1.5405398607 1.0232541500 1.7141482830 0.0178923854 0.0180740000 727951301 0 402718720 0.2820223868 0.0551146269 0.8168863058 497 19.8400000000 1.5371267796 1.0242880990 1.7141482830 0.0178825556 0.0227370000 727953549 0 402718720 0.2831609845 0.0540588088 0.8146737814 498 19.8800000000 1.5298604965 1.0253033046 1.7141482830 0.0178701694 0.0205210000 727955797 0 402718720 0.2822310328 0.0535511039 0.8111184835 499 19.9200000000 1.5261147022 1.0263069346 1.7141482830 0.0178633954 0.0203630000 727958045 0 402718720 0.2825433314 0.0529879034 0.8089361787 500 19.9600000000 1.5195679665 1.0272934567 1.7141482830 0.0178592197 0.0195310000 727960293 0 402718720 0.2824477851 0.0523502752 0.8054834008 501 20.0000000000 1.5132558346 1.0282634415 1.7141482830 0.0178523862 0.0219740000 727962541 0 402718720 0.2825633585 0.0516815409 0.8018228412 502 20.0400000000 1.5100932121 1.0292232617 1.7141482830 0.0178450551 0.0197600000 727964789 0 402718720 0.2838319540 0.0507289357 0.7997925282 503 20.0800000000 1.5025293827 1.0301642282 1.7141482830 0.0178351866 0.0235280000 727967037 0 402718720 0.2844393551 0.0507413000 0.7953684330 504 20.1200000000 1.4955942631 1.0310877005 1.7141482830 0.0178257507 0.0216480000 727969285 0 402718720 0.2835209668 0.0491429120 0.7921023369 505 20.1600000000 1.4867303371 1.0319899631 1.7141482830 0.0178148337 0.0218600000 727971533 0 402718720 0.2821436226 0.0485821776 0.7877052426 506 20.2000000000 1.4812471867 1.0328778233 1.7141482830 0.0178074760 0.0247130000 727973781 0 402718720 0.2823861837 0.0496065989 0.7846786976 507 20.2400000000 1.4741145372 1.0337481126 1.7141482830 0.0178043830 0.0239200000 727976029 0 402718720 0.2824601233 0.0498826467 0.7809170485 508 20.2800000000 1.4665513039 1.0346000874 1.7141482830 0.0178057487 0.0203790000 727978277 0 402718720 0.2796202004 0.0489912033 0.7777037024 509 20.3200000000 1.4612126350 1.0354382260 1.7141482830 0.0177940258 0.0227280000 727980525 0 402718720 0.2804347575 0.0482109711 0.7746636271 510 20.3600000000 1.4530849457 1.0362571412 1.7141482830 0.0177830408 0.0226630000 727982773 0 402718720 0.2822180986 0.0487541743 0.7694939375 511 20.4000000000 1.4463115931 1.0370595960 1.7141482830 0.0177736260 0.0236680000 727985021 0 402718720 0.2828435004 0.0501308255 0.7652769089 512 20.4400000000 1.4375877380 1.0378418776 1.7141482830 0.0177814428 0.0238200000 727987269 0 402718720 0.2809484601 0.0500325151 0.7612329125 513 20.4800000000 1.4318660498 1.0386099559 1.7141482830 0.0177845357 0.0243700000 728042765 0 402718720 0.2832663655 0.0498074926 0.7570937276 514 20.5200000000 1.4249759912 1.0393616408 1.7141482830 0.0177791455 0.0245230000 728147413 0 402718720 0.2834032178 0.0501168892 0.7533544302 515 20.5600000000 1.4187020063 1.0400982240 1.7141482830 0.0177764197 0.0257970000 728149661 0 402718720 0.2852269709 0.0509222224 0.7490845919 516 20.6000000000 1.4110881090 1.0408171967 1.7141482830 0.0177821076 0.0254740000 728151909 0 402718720 0.2861232162 0.0506394170 0.7445106506 517 20.6400000000 1.4107561111 1.0415327458 1.7141482830 0.0177770770 0.0250040000 728154157 0 402718720 0.2847373188 0.0497857220 0.7447846532 518 20.6800000000 1.4015098810 1.0422276824 1.7141482830 0.0177683464 0.0256690000 728156405 0 402718720 0.2897067666 0.0499545857 0.7374779582 519 20.7200000000 1.4018740654 1.0429206426 1.7141482830 0.0177645413 0.0249570000 728158653 0 402718720 0.2865530252 0.0508247986 0.7390666008 520 20.7600000000 1.4002792835 1.0436078708 1.7141482830 0.0177606187 0.0235920000 728160901 0 402718720 0.2833103240 0.0511145927 0.7395523190 521 20.8000000000 1.3949056864 1.0442821468 1.7141482830 0.0177652578 0.0241030000 728163149 0 402718720 0.2833219767 0.0505892672 0.7366318703 522 20.8400000000 1.3912249804 1.0449467883 1.7141482830 0.0177570050 0.0234480000 728165397 0 402718720 0.2839602828 0.0491645709 0.7344064116 523 20.8800000000 1.3921637535 1.0456106831 1.7141482830 0.0177497404 0.0237220000 728167645 0 402718720 0.2799697220 0.0483415350 0.7366353869 524 20.9200000000 1.3830109835 1.0462545768 1.7141482830 0.0177360581 0.1085590000 740489005 0 402718720 0.2859414220 0.0488500893 0.7290685177 525 20.9600000000 1.3802855015 1.0468908261 1.7141482830 0.0177304925 0.0170260000 744157805 0 402718720 0.2865563035 0.0499724969 0.7264579535 526 21.0000000000 1.3741128445 1.0475129212 1.7141482830 0.0177174108 0.0320060000 747352245 0 402718720 0.2885588408 0.0486415364 0.7222176194 527 21.0400000000 1.3687717915 1.0481225206 1.7141482830 0.0177086715 0.0232760000 747354493 0 402718720 0.2888159752 0.0485602878 0.7192758322 528 21.0800000000 1.3663901091 1.0487253001 1.7141482830 0.0176981793 0.0214770000 747356741 0 402718720 0.2897168994 0.0484500602 0.7177446485 529 21.1200000000 1.3571606874 1.0493083538 1.7141482830 0.0176875210 0.0226580000 747358989 0 402718720 0.2938039303 0.0477332175 0.7107763886 530 21.1600000000 1.3552421331 1.0498855873 1.7141482830 0.0176816740 0.0207570000 747361237 0 402718720 0.2928709984 0.0479570962 0.7100942731 531 21.2000000000 1.3480640650 1.0504471287 1.7141482830 0.0176697295 0.0202110000 747363485 0 402718720 0.2948361337 0.0476936586 0.7051954269 532 21.2400000000 1.3431893587 1.0509973961 1.7141482830 0.0176605819 0.0195960000 747365733 0 402718720 0.2951256335 0.0473049805 0.7024301887 533 21.2800000000 1.3395296335 1.0515387324 1.7141482830 0.0176477502 0.0233570000 747367981 0 402718720 0.2944768071 0.0470233448 0.7008495927 534 21.3200000000 1.3323451281 1.0520645870 1.7141482830 0.0176353778 0.0205040000 747370229 0 402718720 0.2965844572 0.0463978052 0.6956481338 535 21.3600000000 1.3248294592 1.0525744279 1.7141482830 0.0176235107 0.0256210000 747372477 0 402718720 0.2991079092 0.0471559390 0.6903014779 536 21.4000000000 1.3217617273 1.0530766430 1.7141482830 0.0176140088 0.0215960000 747374725 0 402718720 0.2980811596 0.0468826666 0.6890476942 537 21.4400000000 1.3135592937 1.0535617131 1.7141482830 0.0176038937 0.0209020000 747376973 0 402718720 0.3009071350 0.0465045646 0.6832037568 538 21.4800000000 1.3085643053 1.0540356956 1.7141482830 0.0175927885 0.0261540000 747379221 0 402718720 0.3008981645 0.0465286486 0.6803727746 539 21.5200000000 1.3033070564 1.0544981657 1.7141482830 0.0175824303 0.0225640000 747381469 0 402718720 0.3001847565 0.0463886112 0.6777834892 540 21.5600000000 1.2954280376 1.0549443321 1.7141482830 0.0175709319 0.0204470000 747383717 0 402718720 0.3013352752 0.0468032919 0.6728939414 541 21.6000000000 1.2901972532 1.0553791804 1.7141482830 0.0175603913 0.0222970000 747385965 0 402718720 0.3013660014 0.0473238900 0.6697447300 542 21.6400000000 1.2829661369 1.0557990825 1.7141482830 0.0175538859 0.0234040000 747388213 0 402718720 0.3020592630 0.0469005257 0.6652880311 543 21.6800000000 1.2799934149 1.0562119635 1.7141482830 0.0175416322 0.0220930000 747390461 0 402718720 0.3021989465 0.0459899530 0.6635388136 544 21.7200000000 1.2740590572 1.0566124177 1.7141482830 0.0175277413 0.0237370000 747392709 0 402718720 0.3023606241 0.0464360602 0.6602041125 545 21.7600000000 1.2677243948 1.0569997791 1.7141482830 0.0175126251 0.0219080000 747394957 0 402718720 0.3028775454 0.0459922999 0.6562926173 546 21.8000000000 1.2642440796 1.0573793474 1.7141482830 0.0175005787 0.0224050000 747397205 0 402718720 0.3033219874 0.0463228375 0.6540915370 547 21.8400000000 1.2578741312 1.0577458827 1.7141482830 0.0174853793 0.0248410000 747399453 0 402718720 0.3038148880 0.0470079258 0.6501014829 548 21.8800000000 1.2548484802 1.0581055589 1.7141482830 0.0174721967 0.0237190000 747401701 0 402718720 0.3027289212 0.0470387936 0.6489751935 549 21.9200000000 1.2512525320 1.0584573749 1.7141482830 0.0174586257 0.0217930000 747403949 0 402718720 0.3030061722 0.0468019210 0.6468028426 550 21.9600000000 1.2472581863 1.0588006491 1.7141482830 0.0174453050 0.0243850000 747406197 0 402718720 0.3026400506 0.0475482717 0.6446235776 551 22.0000000000 1.2426753044 1.0591343599 1.7141482830 0.0174345988 0.0238020000 747408445 0 402718720 0.3026429415 0.0476102754 0.6419975162 552 22.0400000000 1.2389214039 1.0594600611 1.7141482830 0.0174226199 0.0228530000 747410693 0 402718720 0.3036201596 0.0481971316 0.6392055154 553 22.0800000000 1.2369990349 1.0597811081 1.7141482830 0.0174135453 0.0236670000 747412941 0 402718720 0.3030900359 0.0481611528 0.6383833885 554 22.1200000000 1.2329306602 1.0600936524 1.7141482830 0.0174039494 0.1015170000 759729617 0 402718720 0.3031916618 0.0477167442 0.6360217929 555 22.1600000000 1.2282623053 1.0603966590 1.7141482830 0.0173892932 0.0248640000 763391073 0 402718720 0.3014591336 0.0492965914 0.6345473528 556 22.2000000000 1.2233370543 1.0606897172 1.7141482830 0.0173832126 0.0300740000 766585513 0 402718720 0.3015665412 0.0497405045 0.6315087080 557 22.2400000000 1.2204469442 1.0609765345 1.7141482830 0.0173782258 0.0236260000 766587761 0 402718720 0.3011092842 0.0491840579 0.6303941607 558 22.2800000000 1.2162669897 1.0612548328 1.7141482830 0.0173669096 0.0245930000 766590009 0 402718720 0.3003706634 0.0486607403 0.6283082366 559 22.3200000000 1.2131848335 1.0615266217 1.7141482830 0.0173561995 0.0234080000 766592257 0 402718720 0.3000344634 0.0492436960 0.6265282035 560 22.3600000000 1.2108751535 1.0617933155 1.7141482830 0.0173470331 0.0224510000 766594505 0 402718720 0.2995755672 0.0493067056 0.6254780293 561 22.4000000000 1.2069358826 1.0620520367 1.7141482830 0.0173378503 0.0241190000 766596753 0 402718720 0.3006240427 0.0490198322 0.6227348447 562 22.4400000000 1.2047410011 1.0623059316 1.7141482830 0.0173280829 0.0222380000 766599001 0 402718720 0.2999874651 0.0495381579 0.6217690706 563 22.4800000000 1.1998734474 1.0625502789 1.7141482830 0.0173214392 0.0227350000 766601249 0 402718720 0.3007195294 0.0495155044 0.6186208129 564 22.5200000000 1.1964161396 1.0627876297 1.7141482830 0.0173137063 0.0219550000 766603497 0 402718720 0.3006285727 0.0489899591 0.6168010831 565 22.5600000000 1.1906740665 1.0630139774 1.7141482830 0.0173057832 0.0244070000 766605745 0 402718720 0.3016637266 0.0483587123 0.6128456593 566 22.6000000000 1.1870541573 1.0632331297 1.7141482830 0.0172990736 0.0207620000 766607993 0 402718720 0.3019675314 0.0481334627 0.6104694009 567 22.6400000000 1.1837649345 1.0634457078 1.7141482830 0.0172904871 0.0218290000 766610241 0 402718720 0.3022440374 0.0480845422 0.6083778143 568 22.6800000000 1.1793037653 1.0636496833 1.7141482830 0.0172812858 0.0822910000 778922865 0 402718720 0.3030912876 0.0476077348 0.6052580476 569 22.7200000000 1.1734333038 1.0638426246 1.7141482830 0.0172731821 0.0305610000 782584321 0 402718720 0.3050827384 0.0468714908 0.6014050245 570 22.7600000000 1.1673911810 1.0640242887 1.7141482830 0.0172627069 0.0236010000 785778761 0 402718720 0.3045008183 0.0475632288 0.5982978344 571 22.8000000000 1.1620186567 1.0641959076 1.7141482830 0.0172550206 0.0208140000 785781009 0 402718720 0.3039233983 0.0479442887 0.5956256390 572 22.8400000000 1.1568778753 1.0643579390 1.7141482830 0.0172485610 0.0200880000 785783257 0 402718720 0.3036725223 0.0472339429 0.5927312970 573 22.8800000000 1.1511346102 1.0645093817 1.7141482830 0.0172369991 0.0204240000 785785505 0 402718720 0.3031461537 0.0473834090 0.5897911787 574 22.9200000000 1.1463518143 1.0646519644 1.7141482830 0.0172262544 0.0216440000 785787753 0 402718720 0.3024506867 0.0475184768 0.5873492956 575 22.9600000000 1.1402634382 1.0647834626 1.7141482830 0.0172163959 0.0213590000 785790001 0 402718720 0.3017968535 0.0470284633 0.5841688514 576 23.0000000000 1.1356896162 1.0649065635 1.7141482830 0.0172039437 0.0215440000 785792249 0 402718720 0.3014706671 0.0460084416 0.5816945434 577 23.0400000000 1.1298204660 1.0650190660 1.7141482830 0.0171916604 0.0208070000 785794497 0 402718720 0.3005425036 0.0465645753 0.5786998868 578 23.0800000000 1.1240490675 1.0651211940 1.7141482830 0.0171802500 0.0259550000 785796745 0 402718720 0.3001998663 0.0465167277 0.5754336119 579 23.1200000000 1.1185448170 1.0652134628 1.7141482830 0.0171684497 0.0219680000 785798993 0 402718720 0.2999122143 0.0458005294 0.5722911954 580 23.1600000000 1.1123772860 1.0652947797 1.7141482830 0.0171550345 0.0222740000 785801241 0 402718720 0.2996757925 0.0456095487 0.5688253641 581 23.2000000000 1.1064977646 1.0653656971 1.7141482830 0.0171415181 0.0269120000 785803489 0 402718720 0.2989878953 0.0457259342 0.5657613277 582 23.2400000000 1.0995337963 1.0654244051 1.7141482830 0.0171311485 0.0234290000 785805737 0 402718720 0.2985100448 0.0449876413 0.5620856285 583 23.2800000000 1.0940320492 1.0654734749 1.7141482830 0.0171181442 0.0954980000 798121309 0 402718720 0.2983272672 0.0442221612 0.5588885546 584 23.3200000000 1.0869188309 1.0655101964 1.7141482830 0.0171067195 0.0274890000 801782765 0 402718720 0.2980957627 0.0450458527 0.5547471046 585 23.3600000000 1.0799547434 1.0655348879 1.7141482830 0.0170939790 0.0250970000 804977205 0 402718720 0.2971471548 0.0449408926 0.5511943102 586 23.4000000000 1.0734007359 1.0655483108 1.7141482830 0.0170826439 0.0203170000 804979453 0 402718720 0.2972692251 0.0442323647 0.5472471714 587 23.4400000000 1.0674400330 1.0655515335 1.7141482830 0.0170731631 0.0188000000 804981701 0 402718720 0.2963692546 0.0442788601 0.5441880226 588 23.4800000000 1.0510008335 1.0655267874 1.7141482830 0.0170717752 0.0184620000 804983949 0 402718720 0.2950724065 0.0449254960 0.5352189541 589 23.5200000000 1.0448608398 1.0654917009 1.7141482830 0.0170635700 0.0182540000 804986197 0 402718720 0.2943532765 0.0453067869 0.5318965316 590 23.5600000000 1.0375535488 1.0654443481 1.7141482830 0.0170602793 0.0181610000 804988445 0 402718720 0.2933712304 0.0455954559 0.5281990170 591 23.6000000000 1.0306174755 1.0653854194 1.7141482830 0.0170595961 0.0181160000 804990693 0 402718720 0.2927855551 0.0453037806 0.5244628787 592 23.6400000000 1.0223139524 1.0653126636 1.7141482830 0.0170505206 0.0172380000 804992941 0 402718720 0.2922560275 0.0449480489 0.5198190808 593 23.6800000000 1.0146694183 1.0652272618 1.7141482830 0.0170393036 0.0209720000 804995189 0 402718720 0.2914208174 0.0448139757 0.5157495141 594 23.7200000000 1.0074952841 1.0651300699 1.7141482830 0.0170278709 0.0217770000 804997437 0 402718720 0.2907800078 0.0448414721 0.5117757916 595 23.7600000000 1.0014069080 1.0650229722 1.7141482830 0.0170164429 0.1010890000 817312341 0 402718720 0.2899716794 0.0448096395 0.5086441040 596 23.8000000000 0.9940507412 1.0649038912 1.7141482830 0.0170044421 0.0286440000 820973797 0 402718720 0.2889421284 0.0441360101 0.5040745735 597 23.8400000000 0.9869630337 1.0647733370 1.7141482830 0.0169925825 0.0202910000 824168237 0 402718720 0.2877432406 0.0455584265 0.5010125637 598 23.8800000000 0.9788557291 1.0646296621 1.7141482830 0.0169858232 0.0172940000 824170485 0 402718720 0.2868490517 0.0453805439 0.4965146184 599 23.9200000000 0.9721382260 1.0644752524 1.7141482830 0.0169762640 0.0184870000 824172733 0 402718720 0.2854482830 0.0463396572 0.4933662117 600 23.9600000000 0.9651308060 1.0643096783 1.7141482830 0.0169714334 0.0189480000 824174981 0 402718720 0.2847342491 0.0462863036 0.4895652831 601 24.0000000000 0.9582399726 1.0641331896 1.7141482830 0.0169627226 0.0172610000 824177229 0 402718720 0.2836036086 0.0461278968 0.4862836301 602 24.0400000000 0.9506295323 1.0639446453 1.7141482830 0.0169520046 0.0182220000 824179477 0 402718720 0.2826375663 0.0465745479 0.4820938408 603 24.0800000000 0.9443901777 1.0637463792 1.7141482830 0.0169408142 0.0173500000 824181725 0 402718720 0.2815759480 0.0464831479 0.4790915251 604 24.1200000000 0.9386920333 1.0635393356 1.7141482830 0.0169289137 0.0176380000 824183973 0 402718720 0.2802608609 0.0469145775 0.4764048159 605 24.1600000000 0.9328062534 1.0633232478 1.7141482830 0.0169188452 0.0219920000 824186221 0 402718720 0.2793191671 0.0465303771 0.4734567702 606 24.2000000000 0.9275625348 1.0630992203 1.7141482830 0.0169075383 0.0188420000 824188469 0 402718720 0.2785367072 0.0460998416 0.4708078504 607 24.2400000000 0.9197803140 1.0628631100 1.7141482830 0.0168956723 0.0173460000 824190717 0 402718720 0.2775581777 0.0458867773 0.4666061103 608 24.2800000000 0.9138984680 1.0626181024 1.7141482830 0.0168832094 0.0225580000 824192965 0 402718720 0.2764702439 0.0463423580 0.4637512863 609 24.3200000000 0.9082465768 1.0623646188 1.7141482830 0.0168737879 0.1070990000 836511113 0 402718720 0.2758792937 0.0457750484 0.4606179893 610 24.3600000000 0.9028778076 1.0621031650 1.7141482830 0.0168624707 0.0257090000 840172057 0 402718720 0.2752592862 0.0442454927 0.4577441812 611 24.4000000000 0.8949917555 1.0618296602 1.7141482830 0.0168504139 0.0206720000 843366497 0 402718720 0.2745711803 0.0442388803 0.4531731904 612 24.4400000000 0.8889304996 1.0615471453 1.7141482830 0.0168384432 0.0170350000 843368745 0 402718720 0.2736023068 0.0448742434 0.4500395060 613 24.4800000000 0.8840427399 1.0612575785 1.7141482830 0.0168280254 0.0166930000 843370993 0 402718720 0.2728461027 0.0441310331 0.4474837780 614 24.5200000000 0.8761476874 1.0609560966 1.7141482830 0.0168179497 0.0166230000 843373241 0 402718720 0.2720310688 0.0437216163 0.4432341456 615 24.5600000000 0.8710370064 1.0606472851 1.7141482830 0.0168054013 0.0165430000 843375489 0 402718720 0.2715660930 0.0436925143 0.4403544962 616 24.6000000000 0.8644666076 1.0603288100 1.7141482830 0.0167934848 0.0168470000 843377737 0 402718720 0.2709516287 0.0429137163 0.4366356730 617 24.6400000000 0.8578282595 1.0600006081 1.7141482830 0.0167821803 0.0168070000 843379985 0 402718720 0.2700587511 0.0426247269 0.4331446886 618 24.6800000000 0.8505569100 1.0596617025 1.7141482830 0.0167719383 0.0165240000 843382233 0 402718720 0.2695343792 0.0427000858 0.4286931455 619 24.7200000000 0.8418809772 1.0593098758 1.7141482830 0.0167611313 0.0213050000 843384481 0 402718720 0.2689131796 0.0425852798 0.4237431288 620 24.7600000000 0.8360484838 1.0589497767 1.7141482830 0.0167514582 0.1128530000 855705281 0 402718720 0.2679277062 0.0431465320 0.4206700623 621 24.8000000000 0.8301728964 1.0585813760 1.7141482830 0.0167413824 0.0248270000 859366737 0 402718720 0.2674403191 0.0435239263 0.4166997373 622 24.8400000000 0.8236269951 1.0582036358 1.7141482830 0.0167304514 0.0161030000 862561177 0 402718720 0.2666037083 0.0431780443 0.4131653905 623 24.8800000000 0.8170185685 1.0578165009 1.7141482830 0.0167197429 0.0156850000 862563425 0 402718720 0.2657077610 0.0434984937 0.4096966386 624 24.9200000000 0.8101072311 1.0574195309 1.7141482830 0.0167092719 0.0160700000 862565673 0 402718720 0.2644140720 0.0436403863 0.4060364366 625 24.9600000000 0.8037055135 1.0570135884 1.7141482830 0.0166993896 0.0151900000 862567921 0 402718720 0.2633732855 0.0433979258 0.4027451277 626 25.0000000000 0.7979255319 1.0565997098 1.7141482830 0.0166889963 0.0154100000 862570169 0 402718720 0.2626068294 0.0427457839 0.3996396065 627 25.0400000000 0.7914816141 1.0561768739 1.7141482830 0.0166794952 0.0156350000 862572417 0 402718720 0.2612376809 0.0424069241 0.3965853751 628 25.0800000000 0.7848928571 1.0557448930 1.7141482830 0.0166716897 0.1111990000 874891701 0 402718720 0.2598935366 0.0433645621 0.3934448659 629 25.1200000000 0.7807918191 1.0553077657 1.7141482830 0.0166651649 0.0165900000 878553157 0 402718720 0.2585525811 0.0432893224 0.3913176954 630 25.1600000000 0.7742901444 1.0548617059 1.7141482830 0.0166603400 0.0187110000 881747597 0 402718720 0.2571942210 0.0433080457 0.3880810738 631 25.2000000000 0.7683669329 1.0544076730 1.7141482830 0.0166581158 0.0141250000 881749845 0 402718720 0.2557638288 0.0434533954 0.3851674199 632 25.2400000000 0.7637601495 1.0539477877 1.7141482830 0.0166552454 0.0142090000 881752093 0 402718720 0.2543776333 0.0431425720 0.3833208382 633 25.2800000000 0.7567434907 1.0534782706 1.7141482830 0.0166514966 0.0139500000 881754341 0 402718720 0.2527850270 0.0433379114 0.3799079657 634 25.3200000000 0.7505005598 1.0530003878 1.7141482830 0.0166487212 0.0138620000 881756589 0 402718720 0.2507660985 0.0438627042 0.3775949776 635 25.3600000000 0.7459432483 1.0525168333 1.7141482830 0.0166488923 0.1130700000 894077889 0 402718720 0.2494570464 0.0435494147 0.3757547438 636 25.4000000000 0.7402077913 1.0520257813 1.7141482830 0.0166481564 0.0192640000 897739345 0 402718720 0.2482923716 0.0430169106 0.3720812798 637 25.4400000000 0.7347539067 1.0515277093 1.7141482830 0.0166416426 0.0140510000 900933785 0 402718720 0.2467291802 0.0430710092 0.3697063029 638 25.4800000000 0.7292386293 1.0510225540 1.7141482830 0.0166340030 0.0136650000 900936033 0 402718720 0.2454210371 0.0429503359 0.3671343923 639 25.5200000000 0.7240474224 1.0505108558 1.7141482830 0.0166261939 0.0135270000 900938281 0 402718720 0.2436634898 0.0423021279 0.3652579486 640 25.5600000000 0.7192202210 1.0499932142 1.7141482830 0.0166160821 0.0134660000 900940529 0 402718720 0.2422100455 0.0421480685 0.3633514047 641 25.6000000000 0.7138699293 1.0494688409 1.7141482830 0.0166063578 0.0136760000 900942777 0 402718720 0.2405162007 0.0420540646 0.3609462976 642 25.6400000000 0.7090978622 1.0489386681 1.7141482830 0.0165957787 0.0141180000 900945025 0 402718720 0.2386042029 0.0418740250 0.3593044877 643 25.6800000000 0.7034639716 1.0484013824 1.7141482830 0.0165850761 0.0142100000 900947273 0 402718720 0.2369054705 0.0414655060 0.3574716449 644 25.7200000000 0.6984283924 1.0478579460 1.7141482830 0.0165747569 0.0132210000 900949521 0 402718720 0.2349808663 0.0413934067 0.3559344709 645 25.7600000000 0.6930296421 1.0473078246 1.7141482830 0.0165650761 0.0154840000 900951769 0 402718720 0.2333293110 0.0411533825 0.3538365364 646 25.8000000000 0.6882805824 1.0467520549 1.7141482830 0.0165550351 0.0143030000 900954017 0 402718720 0.2311032116 0.0406815074 0.3526824415 647 25.8400000000 0.6820443273 1.0461883645 1.7141482830 0.0165455050 0.0140670000 900956265 0 402718720 0.2284844071 0.0408717282 0.3512124717 648 25.8800000000 0.6769251227 1.0456185138 1.7141482830 0.0165396538 0.1185190000 913280381 0 402718720 0.2263803631 0.0411338545 0.3496561944 649 25.9200000000 0.6717447042 1.0450424370 1.7141482830 0.0165337296 0.0186110000 916941837 0 402718720 0.2239361703 0.0410778485 0.3476180732 650 25.9600000000 0.6610072851 1.0444516137 1.7141482830 0.0165341458 0.0218730000 920136277 0 402718720 0.2193764597 0.0391281322 0.3447588682 651 26.0000000000 0.6485097408 1.0438434081 1.7141482830 0.0165340644 0.0169350000 920138525 0 402718720 0.2135181874 0.0394369401 0.3414459229 652 26.0400000000 0.6416130066 1.0432264903 1.7141482830 0.0165273195 0.0159930000 920140773 0 402718720 0.2101674676 0.0393970311 0.3398846984 653 26.0800000000 0.6351492405 1.0426015634 1.7141482830 0.0165258816 0.0159470000 920143021 0 402718720 0.2066907883 0.0402549841 0.3385983407 654 26.1200000000 0.6291089654 1.0419693117 1.7141482830 0.0165320289 0.0171240000 920145269 0 402718720 0.2032912076 0.0403224342 0.3374458551 655 26.1600000000 0.6219685674 1.0413280892 1.7141482830 0.0165262371 0.0166100000 920147517 0 402718720 0.1999920160 0.0399124064 0.3359123468 656 26.2000000000 0.6155394912 1.0406790212 1.7141482830 0.0165189581 0.0208610000 920149765 0 402718720 0.1963525265 0.0400572009 0.3344821036 657 26.2400000000 0.6092571020 1.0400223669 1.7141482830 0.0165110379 0.0195690000 920152013 0 402718720 0.1927005947 0.0401030257 0.3335979283 658 26.2800000000 0.6021892428 1.0393569670 1.7141482830 0.0165028161 0.0169110000 920154261 0 402718720 0.1888232529 0.0408895686 0.3324533999 659 26.3200000000 0.5959768295 1.0386841595 1.7141482830 0.0164952077 0.0187190000 920156509 0 402718720 0.1849292666 0.0417692252 0.3313875198 660 26.3600000000 0.5899654031 1.0380042826 1.7141482830 0.0164909728 0.0171910000 920158757 0 402718720 0.1812345684 0.0419719927 0.3301998377 661 26.4000000000 0.5831957459 1.0373162213 1.7141482830 0.0164876035 0.0175280000 920161005 0 402718720 0.1771941781 0.0424343385 0.3290947378 662 26.4400000000 0.5775553584 1.0366217184 1.7141482830 0.0164857376 0.0199190000 920163253 0 402718720 0.1732081920 0.0439476743 0.3291854858 663 26.4800000000 0.5713365078 1.0359199308 1.7141482830 0.0164945774 0.0189120000 920165501 0 402718720 0.1694654673 0.0445871875 0.3285123110 664 26.5200000000 0.5652554631 1.0352110988 1.7141482830 0.0165011530 0.0163880000 920167749 0 402718720 0.1658748835 0.0439972170 0.3256912529 665 26.5600000000 0.5595330596 1.0344957934 1.7141482830 0.0164953446 0.0157710000 920169997 0 402718720 0.1623477489 0.0442779213 0.3250890672 666 26.6000000000 0.5530725718 1.0337729358 1.7141482830 0.0164899320 0.0148730000 920172245 0 402718720 0.1585897505 0.0456219241 0.3245796859 667 26.6400000000 0.5489410162 1.0330460513 1.7141482830 0.0164942283 0.1022980000 932496841 0 402718720 0.1550159156 0.0465957187 0.3237097859 668 26.6800000000 0.5422518849 1.0323113295 1.7141482830 0.0165087701 0.0166750000 936158297 0 402718720 0.1505431682 0.0486490950 0.3245159090 669 26.7200000000 0.5369779468 1.0315709209 1.7141482830 0.0165418750 0.0159280000 939352737 0 402718720 0.1468323022 0.0490362868 0.3235446811 670 26.7600000000 0.5317507982 1.0308249207 1.7141482830 0.0165655265 0.0139910000 939354985 0 402718720 0.1435927749 0.0486148857 0.3229157925 671 26.8000000000 0.5263046026 1.0300730275 1.7141482830 0.0165719074 0.0140270000 939357233 0 402718720 0.1402802020 0.0482118875 0.3219023049 672 26.8400000000 0.5209966302 1.0293154734 1.7141482830 0.0165666264 0.0138290000 939359481 0 402718720 0.1370740980 0.0492572077 0.3204583824 673 26.8800000000 0.5158762932 1.0285525622 1.7141482830 0.0165592256 0.0131770000 939361729 0 402718720 0.1339913607 0.0498049483 0.3194174170 674 26.9200000000 0.5111693740 1.0277849314 1.7141482830 0.0165518973 0.0146280000 939363977 0 402718720 0.1310545802 0.0503305346 0.3178732097 675 26.9600000000 0.5064156651 1.0270125325 1.7141482830 0.0165434947 0.0134210000 939366225 0 402718720 0.1281089485 0.0508639328 0.3175735772 676 27.0000000000 0.5016972423 1.0262354389 1.7141482830 0.0165410528 0.0145270000 939368473 0 402718720 0.1251357049 0.0517894439 0.3165093958 677 27.0400000000 0.4983119071 1.0254556404 1.7141482830 0.0165489530 0.0147820000 939370721 0 402718720 0.1220998615 0.0523696765 0.3158916533 678 27.0800000000 0.4940843582 1.0246719070 1.7141482830 0.0165552413 0.0154960000 939372969 0 402718720 0.1192932948 0.0533928275 0.3148019016 679 27.1200000000 0.4893545508 1.0238835162 1.7141482830 0.0165626370 0.0156620000 939375217 0 402718720 0.1163187549 0.0540519133 0.3134838343 680 27.1600000000 0.4839729369 1.0230895300 1.7141482830 0.0165619219 0.0164860000 939377465 0 402718720 0.1136692464 0.0536371842 0.3122013211 681 27.2000000000 0.4794982076 1.0222913049 1.7141482830 0.0165538092 0.0145140000 939379713 0 402718720 0.1110632494 0.0541512817 0.3112381995 682 27.2400000000 0.4750674069 1.0214889238 1.7141482830 0.0165484705 0.0157300000 939381961 0 402718720 0.1082015336 0.0546839125 0.3099226356 683 27.2800000000 0.4702490866 1.0206818377 1.7141482830 0.0165479016 0.0160490000 939384209 0 402718720 0.1055374220 0.0552041344 0.3087631762 684 27.3200000000 0.4655376375 1.0198702233 1.7141482830 0.0165502526 0.0168990000 939386457 0 402718720 0.1027091891 0.0555625483 0.3073807061 685 27.3600000000 0.4602288008 1.0190532286 1.7141482830 0.0165479038 0.0165030000 939388705 0 402718720 0.1000936851 0.0558700785 0.3055906594 686 27.4000000000 0.4546523690 1.0182304868 1.7141482830 0.0165437042 0.0168110000 939390953 0 402718720 0.0972327143 0.0569854118 0.3041747510 687 27.4400000000 0.4494338632 1.0174025441 1.7141482830 0.0165512452 0.0196700000 939393201 0 402718720 0.0944508240 0.0577947386 0.3024137020 688 27.4800000000 0.4439633489 1.0165690569 1.7141482830 0.0165622085 0.0183390000 939395449 0 402718720 0.0916473418 0.0584837496 0.3008674979 689 27.5200000000 0.4385208189 1.0157300899 1.7141482830 0.0165715890 0.0180810000 939397697 0 402718720 0.0888159871 0.0585918054 0.2992294729 690 27.5600000000 0.4326393306 1.0148850309 1.7141482830 0.0165706826 0.0198520000 939399945 0 402718720 0.0861588195 0.0594007000 0.2969785035 691 27.6000000000 0.4270661473 1.0140343523 1.7141482830 0.0165737342 0.0208040000 939402193 0 402718720 0.0831651315 0.0604185537 0.2951563001 692 27.6400000000 0.4212782085 1.0131777683 1.7141482830 0.0165894504 0.0181190000 939404441 0 402718720 0.0802615210 0.0610631481 0.2934119403 693 27.6800000000 0.4148387611 1.0123143642 1.7141482830 0.0166147935 0.0185820000 939406689 0 402718720 0.0776422694 0.0607226528 0.2914036214 694 27.7200000000 0.4082133770 1.0114439017 1.7141482830 0.0166252583 0.0184320000 939408937 0 402718720 0.0750632510 0.0606427677 0.2885766625 695 27.7600000000 0.4019424319 1.0105669212 1.7141482830 0.0166245362 0.0182750000 939411185 0 402718720 0.0726991221 0.0601328909 0.2863543630 696 27.8000000000 0.3959295452 1.0096838215 1.7141482830 0.0166222481 0.0181390000 939413433 0 402718720 0.0701230466 0.0605401359 0.2840112746 697 27.8400000000 0.3901038766 1.0087948976 1.7141482830 0.0166247256 0.1053070000 951738029 0 402718720 0.0675194561 0.0607689321 0.2820536792 698 27.8800000000 0.3827132583 1.0078979325 1.7141482830 0.0166277460 0.0232090000 955399485 0 402718720 0.0646602362 0.0632328689 0.2819677591 699 27.9200000000 0.3777988255 1.0069965032 1.7141482830 0.0166423039 0.0165400000 958593925 0 402718720 0.0617723651 0.0640056580 0.2801451981 700 27.9600000000 0.3722847998 1.0060897722 1.7141482830 0.0166564409 0.0160560000 958596173 0 402718720 0.0588401556 0.0651149303 0.2780436575 701 28.0000000000 0.3671971858 1.0051783705 1.7141482830 0.0166744793 0.0162870000 958598421 0 402718720 0.0561620556 0.0653584898 0.2762950957 702 28.0400000000 0.3619425595 1.0042620802 1.7141482830 0.0166868620 0.0160620000 958600669 0 402718720 0.0535183884 0.0654844269 0.2745024562 703 28.0800000000 0.3577740192 1.0033424670 1.7141482830 0.0166918595 0.0161210000 958602917 0 402718720 0.0511196144 0.0656530783 0.2731754482 704 28.1200000000 0.3545088470 1.0024208283 1.7141482830 0.0166992732 0.0173580000 958605165 0 402718720 0.0482236370 0.0676624030 0.2719085813 705 28.1600000000 0.3511830866 1.0014970868 1.7141482830 0.0167174784 0.0175850000 958607413 0 402718720 0.0454471260 0.0689087808 0.2706644237 706 28.2000000000 0.3475885987 1.0005708708 1.7141482830 0.0167289551 0.0161320000 958609661 0 402718720 0.0429841876 0.0686318278 0.2694447339 707 28.2400000000 0.3447642922 0.9996432802 1.7141482830 0.0167289518 0.0190830000 958611909 0 402718720 0.0403429270 0.0699584410 0.2680943608 708 28.2800000000 0.3425602913 0.9987151969 1.7141482830 0.0167247162 0.0195070000 958614157 0 402718720 0.0375845395 0.0713042915 0.2672657371 709 28.3200000000 0.3392461240 0.9977850572 1.7141482830 0.0167168569 0.0912770000 970929617 0 402718720 0.0356301814 0.0699703693 0.2665027082 710 28.3600000000 0.3382112086 0.9968560799 1.7141482830 0.0167084613 0.0230750000 974591073 0 402718720 0.0333053768 0.0705109611 0.2636111677 711 28.4000000000 0.3373214304 0.9959284644 1.7141482830 0.0167007541 0.0200350000 977785513 0 402718720 0.0306859054 0.0723623037 0.2637234926 712 28.4400000000 0.3357170522 0.9950012011 1.7141482830 0.0166950625 0.0186060000 977787761 0 402718720 0.0280571096 0.0730770230 0.2628700435 713 28.4800000000 0.3341003954 0.9940742715 1.7141482830 0.0166854071 0.0166610000 977790009 0 402718720 0.0263991151 0.0719093159 0.2626287341 714 28.5200000000 0.3346895576 0.9931507635 1.7141482830 0.0166761355 0.0168110000 977792257 0 402718720 0.0236440171 0.0739889070 0.2626367509 715 28.5600000000 0.3352847695 0.9922306712 1.7141482830 0.0166658257 0.0184940000 977794505 0 402718720 0.0206825603 0.0764770508 0.2626480758 716 28.6000000000 0.3367781341 0.9913152347 1.7141482830 0.0166616425 0.0166810000 977796753 0 402718720 0.0184903741 0.0767374039 0.2633871734 717 28.6400000000 0.3385268748 0.9904047907 1.7141482830 0.0166534286 0.0183200000 977799001 0 402718720 0.0163193978 0.0774829835 0.2643560171 718 28.6800000000 0.3411382437 0.9895005198 1.7141482830 0.0166454406 0.0183060000 977801249 0 402718720 0.0139860287 0.0788832754 0.2654433250 719 28.7200000000 0.3429068327 0.9886012240 1.7141482830 0.0166405175 0.0184040000 977803497 0 402718720 0.0115349097 0.0798677728 0.2663114369 720 28.7600000000 0.3457325399 0.9877083508 1.7141482830 0.0166344400 0.0194590000 977805745 0 402718720 0.0090926420 0.0805535167 0.2676402628 721 28.8000000000 0.3489331901 0.9868223936 1.7141482830 0.0166261184 0.0171550000 977807993 0 402718720 0.0068425336 0.0806080922 0.2692394853 722 28.8400000000 0.3522363603 0.9859434655 1.7141482830 0.0166168823 0.0929460000 990124817 0 402718720 0.0043009738 0.0813509375 0.2707741261 723 28.8800000000 0.3562443852 0.9850725124 1.7141482830 0.0166107607 0.0209480000 993786273 0 402718720 0.0020085883 0.0799909756 0.2731518745 724 28.9200000000 0.3603815734 0.9842096797 1.7141482830 0.0166019101 0.0171520000 996980713 0 402718720 -0.0006859220 0.0806155577 0.2749752700 725 28.9600000000 0.3648778498 0.9833554289 1.7141482830 0.0165966245 0.0147520000 996982961 0 402718720 -0.0034601688 0.0813009962 0.2770523429 726 29.0000000000 0.3693479002 0.9825096885 1.7141482830 0.0165950858 0.0148370000 996985209 0 402718720 -0.0060298666 0.0817431584 0.2791174352 727 29.0400000000 0.3740916252 0.9816727998 1.7141482830 0.0165941199 0.0151430000 996987457 0 402718720 -0.0090889037 0.0823137611 0.2811920941 728 29.0800000000 0.3793992400 0.9808455009 1.7141482830 0.0165934546 0.0152380000 996989705 0 402718720 -0.0119063212 0.0829132050 0.2834907472 729 29.1200000000 0.3850840032 0.9800282698 1.7141482830 0.0165893368 0.0813750000 1009302637 0 402718720 -0.0148537243 0.0838733763 0.2858302593 730 29.1600000000 0.3901138306 0.9792201678 1.7141482830 0.0165809551 0.0203760000 1012964093 0 402718720 -0.0179210193 0.0852687731 0.2879578769 731 29.2000000000 0.3956065476 0.9784217908 1.7141482830 0.0165751153 0.0156000000 1016158533 0 402718720 -0.0209342316 0.0858498141 0.2902023792 732 29.2400000000 0.4016290009 0.9776338225 1.7141482830 0.0165710636 0.0147230000 1016160781 0 402718720 -0.0241540112 0.0870553851 0.2926235199 733 29.2800000000 0.4084666669 0.9768573325 1.7141482830 0.0165660606 0.0144720000 1016163029 0 402718720 -0.0273349825 0.0879630819 0.2954508364 734 29.3200000000 0.4159673154 0.9760931772 1.7141482830 0.0165588189 0.0142190000 1016165277 0 402718720 -0.0302775335 0.0890615657 0.2985940576 735 29.3600000000 0.4230984747 0.9753408034 1.7141482830 0.0165515270 0.0141980000 1016167525 0 402718720 -0.0331520773 0.0902732387 0.3015380204 736 29.4000000000 0.4307827055 0.9746009147 1.7141482830 0.0165446246 0.0822400000 1028486401 0 402718720 -0.0359780155 0.0915938467 0.3045378625 737 29.4400000000 0.4378301203 0.9738725961 1.7141482830 0.0165371640 0.0167810000 1032147857 0 402718720 -0.0386211090 0.0926261544 0.3075760007 738 29.4800000000 0.4451224208 0.9731561325 1.7141482830 0.0165350412 0.0149370000 1035342297 0 402718720 -0.0414197482 0.0936972722 0.3105881810 739 29.5200000000 0.4524050951 0.9724514626 1.7141482830 0.0165418666 0.0136570000 1035344545 0 402718720 -0.0439928174 0.0945958048 0.3135218024 740 29.5600000000 0.4592274427 0.9717579166 1.7141482830 0.0165485828 0.0137780000 1035346793 0 402718720 -0.0464075245 0.0955256745 0.3164667785 741 29.6000000000 0.4665703177 0.9710761520 1.7141482830 0.0165573834 0.0136670000 1035349041 0 402718720 -0.0486674048 0.0969609097 0.3194142878 742 29.6400000000 0.4738991559 0.9704061021 1.7141482830 0.0165623691 0.0135710000 1035351289 0 402718720 -0.0506737977 0.0980215818 0.3224816322 743 29.6800000000 0.4798995554 0.9697459318 1.7141482830 0.0165564516 0.0705580000 1047666045 0 402718720 -0.0523137264 0.0984994471 0.3252079785 744 29.7200000000 0.4854579866 0.9690950072 1.7141482830 0.0165481583 0.0142490000 1051327501 0 402718720 -0.0538628139 0.0995744020 0.3274017572 745 29.7600000000 0.4908882678 0.9684531189 1.7141482830 0.0165407788 0.0147260000 1054521941 0 402718720 -0.0556204356 0.1004573554 0.3295302987 746 29.8000000000 0.4959636033 0.9678197550 1.7141482830 0.0165329968 0.0131070000 1054524189 0 402718720 -0.0571826324 0.1011391953 0.3316403329 747 29.8400000000 0.5011090040 0.9671949748 1.7141482830 0.0165250547 0.0129490000 1054526437 0 402718720 -0.0589096658 0.1019704565 0.3336339891 748 29.8800000000 0.5063828230 0.9665789158 1.7141482830 0.0165182097 0.0133280000 1054528685 0 402718720 -0.0605848618 0.1031884402 0.3356158435 749 29.9200000000 0.5112177730 0.9659709570 1.7141482830 0.0165106091 0.0133040000 1054530933 0 402718720 -0.0618974231 0.1040583774 0.3376444578 750 29.9600000000 0.5157124400 0.9653706123 1.7141482830 0.0165032416 0.0136730000 1054533181 0 402718720 -0.0633137077 0.1050006598 0.3394294977 751 30.0000000000 0.5197397470 0.9647772290 1.7141482830 0.0164954189 0.0134820000 1054535429 0 402718720 -0.0645225048 0.1056951731 0.3410132825 752 30.0400000000 0.5235868692 0.9641905397 1.7141482830 0.0164871332 0.0780780000 1066857097 0 402718720 -0.0656911358 0.1066172272 0.3425110877 753 30.0800000000 0.5260421038 0.9636086693 1.7141482830 0.0164770552 0.0122250000 1070518553 0 402718720 -0.0670759678 0.1084079817 0.3442889452 754 30.1200000000 0.5292512178 0.9630325984 1.7141482830 0.0164719792 0.0162130000 1073712993 0 402718720 -0.0684386343 0.1091633588 0.3455206156 755 30.1600000000 0.5324122310 0.9624622403 1.7141482830 0.0164694653 0.0153760000 1073715241 0 402718720 -0.0697730482 0.1095453799 0.3466080427 756 30.2000000000 0.5360330939 0.9618981806 1.7141482830 0.0164671092 0.0149110000 1073717489 0 402718720 -0.0711933449 0.1104182005 0.3478668630 757 30.2400000000 0.5395634770 0.9613402747 1.7141482830 0.0164608626 0.0148770000 1073719737 0 402718720 -0.0726893172 0.1113907397 0.3489013314 758 30.2800000000 0.5430228114 0.9607884047 1.7141482830 0.0164552492 0.0147180000 1073721985 0 402718720 -0.0743529126 0.1118353829 0.3501904309 759 30.3200000000 0.5468806028 0.9602430717 1.7141482830 0.0164557456 0.0145220000 1073724233 0 402718720 -0.0760724843 0.1127679199 0.3515556157 760 30.3600000000 0.5512359142 0.9597049044 1.7141482830 0.0164553901 0.0148500000 1073726481 0 402718720 -0.0782861933 0.1144667789 0.3524477482 761 30.4000000000 0.5549482703 0.9591730297 1.7141482830 0.0164527659 0.0160090000 1073728729 0 402718720 -0.0802586228 0.1155128703 0.3535977900 762 30.4400000000 0.5586347580 0.9586473889 1.7141482830 0.0164471928 0.0147500000 1073730977 0 402718720 -0.0824472308 0.1166722551 0.3544057310 763 30.4800000000 0.5624739528 0.9581281577 1.7141482830 0.0164407021 0.0153460000 1073733225 0 402718720 -0.0848011971 0.1181129664 0.3552162051 764 30.5200000000 0.5664592385 0.9576155020 1.7141482830 0.0164352813 0.0153530000 1073735473 0 402718720 -0.0872373655 0.1192489490 0.3560463786 765 30.5600000000 0.5705292225 0.9571095069 1.7141482830 0.0164289359 0.0143980000 1073737721 0 402718720 -0.0898726583 0.1205462366 0.3567724526 766 30.6000000000 0.5746014714 0.9566101491 1.7141482830 0.0164233516 0.0159420000 1073739969 0 402718720 -0.0922137126 0.1215652302 0.3577006459 767 30.6400000000 0.5787588954 0.9561175138 1.7141482830 0.0164184307 0.0156420000 1073742217 0 402718720 -0.0951253474 0.1229362488 0.3582555950 768 30.6800000000 0.5828691721 0.9556315134 1.7141482830 0.0164152020 0.0158990000 1073744465 0 402718720 -0.0976879522 0.1240132302 0.3591347933 769 30.7200000000 0.5872347951 0.9551524539 1.7141482830 0.0164114947 0.0151330000 1073746713 0 402718720 -0.1004977003 0.1254693568 0.3598499298 770 30.7600000000 0.5916882753 0.9546804225 1.7141482830 0.0164059348 0.0155490000 1073748961 0 402718720 -0.1032223552 0.1268267035 0.3606291711 771 30.8000000000 0.5958136320 0.9542149663 1.7141482830 0.0163997491 0.0156610000 1073751209 0 402718720 -0.1058779955 0.1279823631 0.3613366485 772 30.8400000000 0.5996442437 0.9537556778 1.7141482830 0.0163945429 0.0790970000 1086074169 0 402718720 -0.1086353213 0.1287896782 0.3619424403 773 30.8800000000 0.6041033864 0.9533033462 1.7141482830 0.0163899369 0.0238640000 1089735625 0 402718720 -0.1111053452 0.1296950728 0.3623263240 774 30.9200000000 0.6080954671 0.9528573412 1.7141482830 0.0163882414 0.0199720000 1092930065 0 402718720 -0.1136570573 0.1304138899 0.3631032705 775 30.9600000000 0.6117644310 0.9524172213 1.7141482830 0.0163870081 0.0196050000 1092932313 0 402718720 -0.1162746251 0.1308208406 0.3636075854 776 31.0000000000 0.6155093312 0.9519830617 1.7141482830 0.0163862728 0.0182020000 1092934561 0 402718720 -0.1190010160 0.1314146668 0.3642467260 777 31.0400000000 0.6194855571 0.9515551369 1.7141482830 0.0163872727 0.0178050000 1092936809 0 402718720 -0.1217893139 0.1324576288 0.3647308350 778 31.0800000000 0.6233114600 0.9511332299 1.7141482830 0.0163833721 0.0175830000 1092939057 0 402718720 -0.1245099455 0.1335488409 0.3652593791 779 31.1200000000 0.6271682382 0.9507173570 1.7141482830 0.0163780575 0.0183290000 1092941305 0 402718720 -0.1270557195 0.1342226714 0.3657453656 780 31.1600000000 0.6309488416 0.9503073974 1.7141482830 0.0163730688 0.0184230000 1092943553 0 402718720 -0.1295304298 0.1350940317 0.3662529588 781 31.2000000000 0.6343979836 0.9499029039 1.7141482830 0.0163679542 0.0182640000 1092945801 0 402718720 -0.1320507377 0.1358316094 0.3666595221 782 31.2400000000 0.6376197934 0.9495035649 1.7141482830 0.0163611200 0.0203780000 1092948049 0 402718720 -0.1344267726 0.1362240613 0.3670808971 783 31.2800000000 0.6410258412 0.9491095959 1.7141482830 0.0163537099 0.0198850000 1092950297 0 402718720 -0.1367142648 0.1367454082 0.3676389754 784 31.3200000000 0.6441799998 0.9487206551 1.7141482830 0.0163464056 0.0191660000 1092952545 0 402718720 -0.1388657391 0.1371567398 0.3680821359 785 31.3600000000 0.6469928622 0.9483362884 1.7141482830 0.0163383940 0.0223430000 1092954793 0 402718720 -0.1408825368 0.1373265386 0.3685292602 786 31.4000000000 0.6499496698 0.9479566617 1.7141482830 0.0163304055 0.0218200000 1092957041 0 402718720 -0.1429333240 0.1375922263 0.3689959943 787 31.4400000000 0.6529295444 0.9475817861 1.7141482830 0.0163220159 0.0219650000 1092959289 0 402718720 -0.1447876394 0.1382336468 0.3694197536 788 31.4800000000 0.6557191610 0.9472114020 1.7141482830 0.0163140585 0.0217070000 1092961537 0 402718720 -0.1464653909 0.1384963542 0.3699880540 789 31.5200000000 0.6580874324 0.9468449585 1.7141482830 0.0163059270 0.0217320000 1092963785 0 402718720 -0.1481646299 0.1384663135 0.3703714609 790 31.5600000000 0.6605638266 0.9464825773 1.7141482830 0.0162977098 0.0223570000 1092966033 0 402718720 -0.1497811377 0.1385348588 0.3709253967 791 31.6000000000 0.6628895998 0.9461240527 1.7141482830 0.0162904389 0.0219440000 1092968281 0 402718720 -0.1513521373 0.1386676878 0.3712567091 792 31.6400000000 0.6649349332 0.9457690159 1.7141482830 0.0162824454 0.0218960000 1092970529 0 402718720 -0.1526566297 0.1384973973 0.3718142509 793 31.6800000000 0.6667262316 0.9454171335 1.7141482830 0.0162739942 0.0220140000 1092972777 0 402718720 -0.1538541168 0.1382257938 0.3722081482 794 31.7200000000 0.6683101058 0.9450681322 1.7141482830 0.0162664027 0.0208280000 1092975025 0 402718720 -0.1549024135 0.1378822923 0.3726395965 795 31.7600000000 0.6698190570 0.9447219069 1.7141482830 0.0162601087 0.0212800000 1092977273 0 402718720 -0.1559431106 0.1375724077 0.3730790019 796 31.8000000000 0.6714989543 0.9443786620 1.7141482830 0.0162571130 0.0209800000 1092979521 0 402718720 -0.1568644047 0.1372251809 0.3736435473 797 31.8400000000 0.6729165316 0.9440380571 1.7141482830 0.0162529994 0.0207610000 1092981769 0 402718720 -0.1576373130 0.1368158013 0.3741410077 798 31.8800000000 0.6741763353 0.9436998845 1.7141482830 0.0162477954 0.0929080000 1105315197 0 402718720 -0.1585368216 0.1362933517 0.3745650947 799 31.9200000000 0.6757732630 0.9433645570 1.7141482830 0.0162409485 0.0251400000 1108976653 0 402718720 -0.1591701657 0.1356951445 0.3746041954 800 31.9600000000 0.6769195795 0.9430315008 1.7141482830 0.0162332019 0.0169030000 1112171093 0 402718720 -0.1598752439 0.1350302249 0.3750709593 801 32.0000000000 0.6782552004 0.9427009436 1.7141482830 0.0162270040 0.0172730000 1112173341 0 402718720 -0.1605550349 0.1344509423 0.3756893873 802 32.0400000000 0.6794342995 0.9423726810 1.7141482830 0.0162200467 0.0174890000 1112175589 0 402718720 -0.1611641943 0.1337447166 0.3763175309 803 32.0800000000 0.6810064316 0.9420471938 1.7141482830 0.0162159840 0.0172810000 1112177837 0 402718720 -0.1613979340 0.1336392760 0.3771537244 804 32.1199999990 0.6822726727 0.9417240911 1.7141482830 0.0162139574 0.0182360000 1112180085 0 402718720 -0.1617276222 0.1334075928 0.3778098822 805 32.1600000000 0.6833851933 0.9414031732 1.7141482830 0.0162116259 0.0160760000 1112182333 0 402718720 -0.1620034128 0.1328492314 0.3785313964 806 32.2000000000 0.6843836308 0.9410842904 1.7141482830 0.0162077222 0.0163560000 1112184581 0 402718720 -0.1623822004 0.1322987974 0.3790816963 807 32.2400000000 0.6849430799 0.9407668912 1.7141482830 0.0162052323 0.0164140000 1112186829 0 402718720 -0.1625468731 0.1313029826 0.3797128201 808 32.2800000000 0.6860006452 0.9404515864 1.7141482830 0.0161991595 0.0197420000 1112189077 0 402718720 -0.1628883779 0.1305069625 0.3804347217 809 32.3200000000 0.6865575910 0.9401377496 1.7141482830 0.0161928048 0.0167700000 1112191325 0 402718720 -0.1629071087 0.1292869449 0.3811918199 810 32.3600000000 0.6874191761 0.9398257513 1.7141482830 0.0161855765 0.1075380000 1124521277 0 402718720 -0.1631258279 0.1284927726 0.3818922937 811 32.4000000000 0.6877459884 0.9395149255 1.7141482830 0.0161761214 0.0231370000 1128182733 0 402718720 -0.1637670249 0.1268354952 0.3828831315 812 32.4399999990 0.6885318756 0.9392058331 1.7141482830 0.0161672532 0.0180890000 1131377173 0 402718720 -0.1639717221 0.1257764250 0.3834300935 813 32.4800000000 0.6895598769 0.9388987655 1.7141482830 0.0161592588 0.0177640000 1131379421 0 402718720 -0.1640088111 0.1249126345 0.3845467567 814 32.5200000000 0.6907518506 0.9385939167 1.7141482830 0.0161510487 0.0177150000 1131381669 0 402718720 -0.1641517580 0.1240099892 0.3853661418 815 32.5600000000 0.6918714643 0.9382911897 1.7141482830 0.0161414881 0.0171600000 1131383917 0 402718720 -0.1643810421 0.1229533553 0.3862518668 816 32.6000000000 0.6928017139 0.9379903448 1.7141482830 0.0161322833 0.0171580000 1131386165 0 402718720 -0.1644457579 0.1215804443 0.3873364925 817 32.6400000000 0.6939430833 0.9376916333 1.7141482830 0.0161224506 0.0163510000 1131388413 0 402718720 -0.1645950824 0.1203914359 0.3882909119 818 32.6800000000 0.6954167485 0.9373954538 1.7141482830 0.0161126119 0.0161800000 1131390661 0 402718720 -0.1647426486 0.1192117035 0.3894564211 819 32.7200000000 0.6973812580 0.9371023961 1.7141482830 0.0161032562 0.1238370000 1143723313 0 402718720 -0.1647426188 0.1185899079 0.3908699453 820 32.7599999990 0.6994192600 0.9368125387 1.7141482830 0.0160943687 0.0216660000 1147384769 0 402718720 -0.1649492979 0.1179499477 0.3921606541 821 32.7999999990 0.7018371224 0.9365263323 1.7141482830 0.0160891375 0.0173710000 1150579209 0 402718720 -0.1645977795 0.1172770783 0.3940693736 822 32.8400000000 0.7040882111 0.9362435609 1.7141482830 0.0160913410 0.0164540000 1150581457 0 402718720 -0.1647150517 0.1164056361 0.3956258595 823 32.8800000000 0.7066217661 0.9359645550 1.7141482830 0.0160852757 0.0165480000 1150583705 0 402718720 -0.1648149341 0.1156813800 0.3973265886 824 32.9200000000 0.7097565532 0.9356900308 1.7141482830 0.0160773898 0.0164250000 1150585953 0 402718720 -0.1648950428 0.1153959781 0.3992303014 825 32.9600000000 0.7127135992 0.9354197563 1.7141482830 0.0160747966 0.0160340000 1150588201 0 402718720 -0.1649598032 0.1145708635 0.4011623561 826 33.0000000000 0.7160059214 0.9351541221 1.7141482830 0.0160698630 0.0159710000 1150590449 0 402718720 -0.1650312841 0.1141170859 0.4031714201 827 33.0400000000 0.7188625336 0.9348925845 1.7141482830 0.0160702329 0.0157780000 1150592697 0 402718720 -0.1651538759 0.1130697653 0.4050558507 828 33.0800000000 0.7213345170 0.9346346642 1.7141482830 0.0160717233 0.0157380000 1150594945 0 402718720 -0.1652265042 0.1117819920 0.4068852067 829 33.1199999990 0.7244522572 0.9343811269 1.7141482830 0.0160685464 0.0188390000 1150597193 0 402718720 -0.1653867960 0.1106968075 0.4088866413 830 33.1600000000 0.7272670865 0.9341315919 1.7141482830 0.0160629102 0.0173330000 1150599441 0 402718720 -0.1655609310 0.1095578969 0.4108189344 831 33.2000000000 0.7301272750 0.9338860993 1.7141482830 0.0160593862 0.1301610000 1162935177 0 402718720 -0.1654407531 0.1078775376 0.4130353332 832 33.2400000000 0.7332591414 0.9336449612 1.7141482830 0.0160523886 0.0242600000 1166596633 0 402718720 -0.1657911241 0.1065459773 0.4149845243 833 33.2800000000 0.7368453145 0.9334087071 1.7141482830 0.0160445165 0.0192060000 1169791073 0 402718720 -0.1660225540 0.1053319499 0.4172127843 834 33.3200000000 0.7399713397 0.9331767678 1.7141482830 0.0160385934 0.0184740000 1169793321 0 402718720 -0.1661850810 0.1036885083 0.4192766547 835 33.3600000000 0.7434002161 0.9329494905 1.7141482830 0.0160317047 0.0186420000 1169795569 0 402718720 -0.1665748358 0.1028180718 0.4213374853 836 33.4000000000 0.7468635440 0.9327268996 1.7141482830 0.0160258517 0.0174520000 1169797817 0 402718720 -0.1667397618 0.1015556678 0.4235119820 837 33.4399999990 0.7503999472 0.9325090658 1.7141482830 0.0160217173 0.0175180000 1169800065 0 402718720 -0.1670735776 0.1006903350 0.4256326854 838 33.4800000000 0.7532009482 0.9322950943 1.7141482830 0.0160230700 0.0166490000 1169802313 0 402718720 -0.1671939045 0.0991075784 0.4275248349 839 33.5200000000 0.7566481829 0.9320857416 1.7141482830 0.0160217719 0.0167920000 1169804561 0 402718720 -0.1672934741 0.0982753411 0.4296112955 840 33.5600000000 0.7595783472 0.9318803756 1.7141482830 0.0160169429 0.0174890000 1169806809 0 402718720 -0.1679819524 0.0973981321 0.4311353862 841 33.6000000000 0.7628117204 0.9316793427 1.7141482830 0.0160083381 0.0196220000 1169809057 0 402718720 -0.1684356332 0.0967021435 0.4328712523 842 33.6400000000 0.7658135295 0.9314823525 1.7141482830 0.0159993218 0.0184790000 1169811305 0 402718720 -0.1688872129 0.0959620178 0.4345464706 843 33.6800000000 0.7686182261 0.9312891566 1.7141482830 0.0159909189 0.0183530000 1169813553 0 402718720 -0.1692032367 0.0948252380 0.4362762272 844 33.7200000000 0.7709394693 0.9310991688 1.7141482830 0.0159845277 0.0209680000 1169815801 0 402718720 -0.1694190949 0.0932053030 0.4378491342 845 33.7599999990 0.7735298872 0.9309126963 1.7141482830 0.0159786980 0.1375780000 1182154693 0 402718720 -0.1694291383 0.0921644643 0.4394780695 846 33.7999999990 0.7762363553 0.9307298637 1.7141482830 0.0159707611 0.0221100000 1185816149 0 402718720 -0.1700247228 0.0916944593 0.4406892955 847 33.8400000000 0.7779431939 0.9305494780 1.7141482830 0.0159620413 0.0186270000 1189010589 0 402718720 -0.1702765226 0.0900984183 0.4418724775 848 33.8800000000 0.7800657749 0.9303720208 1.7141482830 0.0159528906 0.0179830000 1189012837 0 402718720 -0.1705094874 0.0889033601 0.4432614446 849 33.9200000000 0.7817466855 0.9301969616 1.7141482830 0.0159439198 0.0184400000 1189015085 0 402718720 -0.1708557010 0.0871119723 0.4442695081 850 33.9600000000 0.7836042643 0.9300244996 1.7141482830 0.0159355995 0.0171030000 1189017333 0 402718720 -0.1710843593 0.0858868435 0.4454933703 851 34.0000000000 0.7858408689 0.9298550711 1.7141482830 0.0159266210 0.0167340000 1189019581 0 402718720 -0.1713140011 0.0848806277 0.4467808902 852 34.0400000000 0.7874073982 0.9296878790 1.7141482830 0.0159173622 0.0157820000 1189021829 0 402718720 -0.1711950451 0.0832015872 0.4479855299 853 34.0800000000 0.7889720201 0.9295229131 1.7141482830 0.0159081907 0.0156870000 1189024077 0 402718720 -0.1714821011 0.0818768069 0.4489543140 854 34.1199999990 0.7907618880 0.9293604295 1.7141482830 0.0158991238 0.0169620000 1189026325 0 402718720 -0.1716070175 0.0810406953 0.4501146972 855 34.1600000000 0.7923589945 0.9292001939 1.7141482830 0.0158914344 0.0188630000 1189028573 0 402718720 -0.1714949161 0.0799644142 0.4511979222 856 34.2000000000 0.7937843204 0.9290419978 1.7141482830 0.0158831970 0.0173460000 1189030821 0 402718720 -0.1716017127 0.0790140256 0.4521961510 857 34.2400000000 0.7956806421 0.9288863836 1.7141482830 0.0158742264 0.0172710000 1189033069 0 402718720 -0.1720570475 0.0786688179 0.4530270994 858 34.2800000000 0.7972044349 0.9287329081 1.7141482830 0.0158653227 0.0198440000 1189035317 0 402718720 -0.1723644882 0.0779591724 0.4537995160 859 34.3200000000 0.7975661159 0.9285802111 1.7141482830 0.0158569664 0.0202970000 1189037565 0 402718720 -0.1722362638 0.0758889914 0.4545131028 860 34.3600000000 0.7981953025 0.9284286007 1.7141482830 0.0158478928 0.0187860000 1189039813 0 402718720 -0.1724607944 0.0743062496 0.4548965096 861 34.4000000000 0.7994133234 0.9282787572 1.7141482830 0.0158387523 0.0209720000 1189042061 0 402718720 -0.1725933552 0.0732257888 0.4556541741 862 34.4400000000 0.8002337217 0.9281302131 1.7141482830 0.0158295948 0.0217470000 1189044309 0 402718720 -0.1725696474 0.0719845742 0.4562529325 863 34.4800000000 0.8003836870 0.9279821870 1.7141482830 0.0158206088 0.1368570000 1201385909 0 402718720 -0.1725417972 0.0699018762 0.4566219449 864 34.5200000000 0.8009445667 0.9278351527 1.7141482830 0.0158114626 0.0249070000 1205047365 0 402718720 -0.1726380587 0.0689072534 0.4572221637 865 34.5600000000 0.8021214604 0.9276898189 1.7141482830 0.0158032873 0.0183460000 1208241805 0 402718720 -0.1733069271 0.0686291903 0.4575723410 866 34.6000000000 0.8030003309 0.9275458357 1.7141482830 0.0157966726 0.0161430000 1208244053 0 402718720 -0.1735878736 0.0681042448 0.4580342770 867 34.6400000000 0.8036226630 0.9274029024 1.7141482830 0.0157881710 0.0163190000 1208246301 0 402718720 -0.1735031158 0.0671878606 0.4586146772 868 34.6800000000 0.8039384484 0.9272606622 1.7141482830 0.0157794025 0.0162590000 1208248549 0 402718720 -0.1736893356 0.0659639090 0.4588408768 869 34.7200000000 0.8041508794 0.9271189939 1.7141482830 0.0157704316 0.0165810000 1208250797 0 402718720 -0.1734624654 0.0649008900 0.4591219127 870 34.7600000000 0.8045193553 0.9269780748 1.7141482830 0.0157614518 0.0159710000 1208253045 0 402718720 -0.1737769693 0.0639968887 0.4592843056 871 34.8000000000 0.8051309586 0.9268381814 1.7141482830 0.0157526096 0.0154880000 1208255293 0 402718720 -0.1740740389 0.0634046346 0.4594915509 872 34.8400000000 0.8056057692 0.9266991534 1.7141482830 0.0157436296 0.0151740000 1208257541 0 402718720 -0.1744307429 0.0624377280 0.4596814811 873 34.8800000000 0.8063524961 0.9265612993 1.7141482830 0.0157346314 0.0176440000 1208259789 0 402718720 -0.1745540351 0.0617216453 0.4601948261 874 34.9200000000 0.8071699739 0.9264246959 1.7141482830 0.0157256838 0.0163940000 1208262037 0 402718720 -0.1747270525 0.0613009147 0.4605919719 875 34.9600000000 0.8085588217 0.9262899921 1.7141482830 0.0157168077 0.0158120000 1208264285 0 402718720 -0.1751955748 0.0613913424 0.4610530138 876 35.0000000000 0.8094811440 0.9261566486 1.7141482830 0.0157081718 0.0181280000 1208266533 0 402718720 -0.1755143106 0.0610708967 0.4614892900 877 35.0400000000 0.8105827570 0.9260248654 1.7141482830 0.0156992550 0.0166710000 1208268781 0 402718720 -0.1758081019 0.0610408150 0.4619132876 878 35.0800000000 0.8116024733 0.9258945438 1.7141482830 0.0156904797 0.0152650000 1208271029 0 402718720 -0.1761238128 0.0610897988 0.4623003900 879 35.1200000000 0.8124369979 0.9257654681 1.7141482830 0.0156815987 0.0153420000 1208273277 0 402718720 -0.1763421744 0.0607357994 0.4626955092 880 35.1600000000 0.8135153055 0.9256379111 1.7141482830 0.0156730767 0.0158150000 1208275525 0 402718720 -0.1765481234 0.0610316992 0.4631204009 881 35.2000000000 0.8145935535 0.9255118675 1.7141482830 0.0156644627 0.0161370000 1208277773 0 402718720 -0.1768909395 0.0609774143 0.4635358453 882 35.2400000000 0.8145197630 0.9253860261 1.7141482830 0.0156557293 0.0167080000 1208280021 0 402718720 -0.1766933650 0.0596602820 0.4637457132 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:17:32 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0056030000 86960468 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0023723971 0.0011861986 0.0023723971 0.0020365117 0.0214050000 103513113 0 402718720 -0.0003054441 0.0014757760 0.0006587355 3 0.0800000000 0.0075691850 0.0033138607 0.0075691850 0.0079323241 0.0312060000 106785025 0 402718720 0.0011895829 0.0039806007 0.0004103031 4 0.1200000000 0.0050746803 0.0037540656 0.0075691850 0.0072586704 0.0225990000 106787673 0 402718720 0.0008525121 0.0019431015 -0.0002164341 5 0.1600000000 0.0045403787 0.0039113282 0.0075691850 0.0093035663 0.0190970000 106790337 0 402718720 -0.0011505795 0.0012552375 0.0010641003 6 0.2000000000 0.0107394103 0.0050493419 0.0107394103 0.0115809318 0.0239910000 106793385 0 402718720 0.0025179877 0.0054919636 0.0011177741 7 0.2400000000 0.0156047400 0.0065572559 0.0156047400 0.0114027896 0.0229900000 106795633 0 402718720 0.0043343510 0.0001796266 0.0011261269 8 0.2800000000 0.0071276785 0.0066285587 0.0156047400 0.0115250947 0.0213480000 106797881 0 402718720 0.0014554275 -0.0065962025 0.0005215094 9 0.3200000000 0.0013787150 0.0060452428 0.0156047400 0.0118079379 0.0220690000 106800961 0 402718720 0.0002118616 -0.0092189992 0.0017992882 10 0.3600000000 0.0089607453 0.0063367930 0.0156047400 0.0114591119 0.0218430000 106804809 0 402718720 0.0001490267 -0.0087568620 0.0011172433 11 0.4000000000 0.0053524454 0.0062473069 0.0156047400 0.0109658262 0.0229930000 106807057 0 402718720 -0.0006809584 -0.0086678565 0.0000849431 12 0.4400000000 0.0035602222 0.0060233832 0.0156047400 0.0111241675 0.0303270000 106809305 0 402718720 -0.0016053950 -0.0067963591 0.0014329145 13 0.4800000000 0.0023946834 0.0057442524 0.0156047400 0.0107321338 0.0270010000 106811553 0 402718720 -0.0021145863 -0.0039496189 0.0013870606 14 0.5200000000 0.0072235866 0.0058499191 0.0156047400 0.0105446153 0.0215370000 106813801 0 402718720 -0.0002715724 -0.0066024838 0.0002205954 15 0.5600000000 0.0086496836 0.0060365701 0.0156047400 0.0102317872 0.0257590000 106816049 0 402718720 0.0008570692 -0.0042437091 0.0002190928 16 0.6000000000 0.0079050986 0.0061533531 0.0156047400 0.0099577796 0.0236080000 106818297 0 402718720 -0.0001976052 -0.0062776310 0.0007391883 17 0.6400000000 0.0104799941 0.0064078614 0.0156047400 0.0097129554 0.0220220000 106822209 0 402718720 -0.0003681361 -0.0063507473 0.0002349041 18 0.6800000000 0.0102944402 0.0066237825 0.0156047400 0.0094923354 0.0233210000 106827657 0 402718720 0.0013833608 -0.0042402428 -0.0005683138 19 0.7200000000 0.0084943147 0.0067222315 0.0156047400 0.0093530691 0.0236610000 106829905 0 402718720 0.0024892942 -0.0017376237 -0.0007479358 20 0.7600000000 0.0097750882 0.0068748744 0.0156047400 0.0092489764 0.0216330000 106832153 0 402718720 0.0033047877 -0.0019579390 -0.0018459879 21 0.8000000000 0.0085109593 0.0069527832 0.0156047400 0.0093328940 0.0233840000 106834401 0 402718720 0.0017608216 -0.0036927930 -0.0016089744 22 0.8400000000 0.0092069069 0.0070552433 0.0156047400 0.0091976986 0.0250520000 106836649 0 402718720 0.0001361201 -0.0041835997 -0.0014255324 23 0.8800000000 0.0115362043 0.0072500677 0.0156047400 0.0093387480 0.0206880000 106838897 0 402718720 0.0055585620 -0.0032348079 -0.0027860685 24 0.9200000000 0.0135777453 0.0075137210 0.0156047400 0.0094544084 0.0252810000 106841145 0 402718720 0.0019088578 -0.0078892130 -0.0018509735 25 0.9600000000 0.0145845274 0.0077965532 0.0156047400 0.0095575800 0.0210530000 106843393 0 402718720 0.0052009416 -0.0038412288 -0.0039169365 26 1.0000000000 0.0145933498 0.0080579685 0.0156047400 0.0093700873 0.0189340000 106845641 0 402718720 0.0047008833 -0.0036399146 -0.0043042256 27 1.0400000000 0.0178085268 0.0084191003 0.0178085268 0.0092115753 0.0242100000 106847889 0 402718720 0.0056750784 -0.0046834429 -0.0050806426 28 1.0800000000 0.0181579869 0.0087669176 0.0181579869 0.0090671969 0.0226910000 106850137 0 402718720 0.0070685279 -0.0059882440 -0.0056880009 29 1.1200000000 0.0205221176 0.0091722694 0.0205221176 0.0089338370 0.0196580000 106852385 0 402718720 0.0075572217 -0.0059146821 -0.0058027431 30 1.1600000000 0.0187511630 0.0094915658 0.0205221176 0.0088052119 0.0219210000 106854633 0 402718720 0.0101756752 -0.0084996959 -0.0055551627 31 1.2000000000 0.0219969265 0.0098949645 0.0219969265 0.0086802152 0.0335650000 106856881 0 402718720 0.0098674735 -0.0058813458 -0.0063356026 32 1.2400000000 0.0214716159 0.0102567349 0.0219969265 0.0086484431 0.0241170000 106859129 0 402718720 0.0083667822 -0.0064608692 -0.0067705382 33 1.2800000000 0.0187835917 0.0105151245 0.0219969265 0.0087432023 0.0235040000 106864705 0 402718720 0.0108475797 -0.0084220245 -0.0071589341 34 1.3200000000 0.0255875606 0.0109584314 0.0255875606 0.0087119172 0.0245320000 106873353 0 402718720 0.0107098995 -0.0055036345 -0.0079689231 35 1.3600000000 0.0269468799 0.0114152443 0.0269468799 0.0085933855 0.0240030000 106875601 0 402718720 0.0096253743 -0.0049960068 -0.0083393529 36 1.4000000000 0.0284908507 0.0118895667 0.0284908507 0.0084975820 0.0254260000 106877849 0 402718720 0.0102029890 -0.0062788408 -0.0097042946 37 1.4400000000 0.0288019963 0.0123466594 0.0288019963 0.0083989930 0.0274790000 106880097 0 402718720 0.0135658700 -0.0073957681 -0.0107371714 38 1.4800000000 0.0280354377 0.0127595219 0.0288019963 0.0082864731 0.0260740000 106882345 0 402718720 0.0144551825 -0.0074080499 -0.0110264095 39 1.5200000000 0.0288629364 0.0131724300 0.0288629364 0.0081942259 0.0513710000 106884593 0 402718720 0.0143774496 -0.0083041228 -0.0111987786 40 1.5600000000 0.0299849920 0.0135927441 0.0299849920 0.0081785557 0.0440270000 119225833 0 402718720 0.0160107296 -0.0083251754 -0.0116562024 41 1.6000000000 0.0327200703 0.0140592642 0.0327200703 0.0082341944 0.0161480000 122887689 0 402718720 0.0178043675 -0.0091320835 -0.0117166769 42 1.6400000000 0.0336204469 0.0145250067 0.0336204469 0.0081396337 0.0228900000 126082129 0 402718720 0.0177312288 -0.0095001142 -0.0121478857 43 1.6800000000 0.0340868942 0.0149799343 0.0340868942 0.0080600602 0.0226310000 126084377 0 402718720 0.0196808670 -0.0101352856 -0.0128327087 44 1.7200000000 0.0360122919 0.0154579424 0.0360122919 0.0079811359 0.0188240000 126086625 0 402718720 0.0191096030 -0.0097550526 -0.0128436917 45 1.7600000000 0.0375191085 0.0159481905 0.0375191085 0.0080357427 0.0183460000 126088873 0 402718720 0.0195076112 -0.0102894707 -0.0134036969 46 1.8000000000 0.0389123969 0.0164474124 0.0389123969 0.0080311054 0.0181500000 126091121 0 402718720 0.0195905920 -0.0106591983 -0.0135818580 47 1.8400000000 0.0410146341 0.0169701193 0.0410146341 0.0080025734 0.0204480000 126093369 0 402718720 0.0191279650 -0.0111518744 -0.0138119310 48 1.8800000000 0.0426251739 0.0175045996 0.0426251739 0.0079456500 0.0213600000 126095617 0 402718720 0.0192698259 -0.0115870656 -0.0136410557 49 1.9200000000 0.0429281108 0.0180234467 0.0429281108 0.0079004083 0.0183810000 126097865 0 402718720 0.0206755437 -0.0117121069 -0.0142098339 50 1.9600000000 0.0419163257 0.0185013043 0.0429281108 0.0078771311 0.0210130000 126100113 0 402718720 0.0183630846 -0.0118034678 -0.0154409492 51 2.0000000000 0.0389957577 0.0189031563 0.0429281108 0.0078670299 0.0220740000 126102361 0 402718720 0.0200794879 -0.0076137227 -0.0162448138 52 2.0400000000 0.0418118872 0.0193437089 0.0429281108 0.0078366446 0.0605830000 144938249 0 402718720 0.0179077480 -0.0119739911 -0.0154688172 53 2.0800000000 0.0439443216 0.0198078714 0.0439443216 0.0077655256 0.0138760000 148599705 0 402718720 0.0168689657 -0.0145825269 -0.0155459922 54 2.1200000000 0.0441493280 0.0202586391 0.0441493280 0.0077494717 0.0152280000 151794145 0 402718720 0.0170015693 -0.0151071530 -0.0154551277 55 2.1600000000 0.0447079986 0.0207031729 0.0447079986 0.0077090089 0.0140000000 151796393 0 402718720 0.0174788851 -0.0149085987 -0.0157440845 56 2.2000000000 0.0457587540 0.0211505940 0.0457587540 0.0076618224 0.0153380000 151798641 0 402718720 0.0179423746 -0.0151632214 -0.0158862453 57 2.2400000000 0.0461880267 0.0215898472 0.0461880267 0.0076181874 0.0264770000 151800889 0 402718720 0.0188239813 -0.0167344138 -0.0165562425 58 2.2800000000 0.0363564044 0.0218444430 0.0461880267 0.0076385812 0.0199260000 151803137 0 402718720 0.0377509817 -0.0227379519 -0.0204594228 59 2.3200000000 0.0473934226 0.0222774765 0.0473934226 0.0078789032 0.0208600000 151805385 0 402718720 0.0267905183 -0.0202992968 -0.0178587399 60 2.3600000000 0.0494600944 0.0227305202 0.0494600944 0.0078463748 0.0196360000 151807633 0 402718720 0.0277569257 -0.0212967787 -0.0180052388 61 2.4000000000 0.0452306084 0.0230993741 0.0494600944 0.0078160088 0.0173960000 151809881 0 402718720 0.0325601399 -0.0222121645 -0.0199255813 62 2.4400000000 0.0484025143 0.0235074892 0.0494600944 0.0078282016 0.0193390000 151812129 0 402718720 0.0305541381 -0.0213635042 -0.0187710393 63 2.4800000000 0.0512698106 0.0239481610 0.0512698106 0.0078071684 0.0164160000 151814377 0 402718720 0.0343044735 -0.0234959144 -0.0189037155 64 2.5200000000 0.0545246191 0.0244259182 0.0545246191 0.0077697501 0.0186770000 151816625 0 402718720 0.0329486318 -0.0217125881 -0.0195031445 65 2.5600000000 0.0524864979 0.0248576194 0.0545246191 0.0077228844 0.0167130000 151825529 0 402718720 0.0369114093 -0.0241245665 -0.0204857737 66 2.6000000000 0.0532662533 0.0252880532 0.0545246191 0.0076811143 0.0223280000 151840577 0 402718720 0.0336072519 -0.0235629398 -0.0199564192 67 2.6400000000 0.0529306866 0.0257006299 0.0545246191 0.0076600976 0.0190360000 151842825 0 402718720 0.0352785885 -0.0245491304 -0.0206993893 68 2.6800000000 0.0568611585 0.0261588729 0.0568611585 0.0076498480 0.0205830000 151845073 0 402718720 0.0347290523 -0.0207787454 -0.0202053618 69 2.7200000000 0.0513588078 0.0265240894 0.0568611585 0.0076220161 0.0587240000 164154141 0 402718720 0.0433362871 -0.0237519592 -0.0225029420 70 2.7600000000 0.0497268774 0.0268555578 0.0568611585 0.0076157786 0.0266980000 167816413 0 402718720 0.0485101901 -0.0252334233 -0.0236943401 71 2.8000000000 0.0429020710 0.0270815650 0.0568611585 0.0076029679 0.0193030000 171010853 0 402718720 0.0634286925 -0.0310782231 -0.0276737493 72 2.8400000000 0.0463527292 0.0273492201 0.0568611585 0.0075796648 0.0476100000 171013101 0 402718720 0.0594518706 -0.0288685933 -0.0267760996 73 2.8800000000 0.0460403822 0.0276052634 0.0568611585 0.0076022999 0.0188940000 171015349 0 402718720 0.0657216311 -0.0312469248 -0.0291885231 74 2.9200000000 0.0464447699 0.0278598513 0.0568611585 0.0076403293 0.0185330000 171017597 0 402718720 0.0693486184 -0.0317282565 -0.0309013296 75 2.9600000000 0.0484557822 0.0281344637 0.0568611585 0.0076072819 0.0203090000 171019845 0 402718720 0.0747067928 -0.0347273052 -0.0314753838 76 3.0000000000 0.0592680350 0.0285441160 0.0592680350 0.0076879272 0.0198400000 171022093 0 402718720 0.0614176244 -0.0307808686 -0.0292692911 77 3.0400000000 0.0536450855 0.0288701026 0.0592680350 0.0076746606 0.0196850000 171024341 0 402718720 0.0747842491 -0.0348748863 -0.0323922820 78 3.0800000000 0.0558052920 0.0292154255 0.0592680350 0.0076393652 0.0194350000 171026589 0 402718720 0.0754289478 -0.0344176255 -0.0331761874 79 3.1200000000 0.0582037792 0.0295823667 0.0592680350 0.0076516888 0.0211710000 171028837 0 402718720 0.0759442374 -0.0341070890 -0.0332700685 80 3.1600000000 0.0633013323 0.0300038538 0.0633013323 0.0076129728 0.0238820000 171031085 0 402718720 0.0756276026 -0.0370728597 -0.0336943977 81 3.2000000000 0.0596279241 0.0303695831 0.0633013323 0.0076047020 0.0240080000 171033333 0 402718720 0.0882060081 -0.0405973122 -0.0364435948 82 3.2400000000 0.0660917684 0.0308052195 0.0660917684 0.0075648325 0.0257140000 171035581 0 402718720 0.0840642750 -0.0411923528 -0.0353654176 83 3.2800000000 0.0663624331 0.0312336196 0.0663624331 0.0075283369 0.0255800000 171037829 0 402718720 0.0876888782 -0.0432083793 -0.0368235298 84 3.3200000000 0.0650206879 0.0316358466 0.0663624331 0.0075073413 0.0272740000 171040077 0 402718720 0.1032387689 -0.0509534813 -0.0402867869 85 3.3600000000 0.0701665580 0.0320891491 0.0701665580 0.0074971162 0.0575440000 183347305 0 402718720 0.1068035215 -0.0512215383 -0.0401153006 86 3.4000000000 0.0769693777 0.0326110122 0.0769693777 0.0074791022 0.0259950000 187008761 0 402718720 0.0999135226 -0.0492838174 -0.0397980176 87 3.4400000000 0.0785678849 0.0331392522 0.0785678849 0.0074705219 0.0455950000 190203201 0 402718720 0.1027367115 -0.0516971685 -0.0411021076 88 3.4800000000 0.0811905563 0.0336852897 0.0811905563 0.0074526819 0.0182220000 190205449 0 402718720 0.1078960523 -0.0536194257 -0.0418499336 89 3.5200000000 0.0825281888 0.0342340863 0.0825281888 0.0074173314 0.0158940000 190207697 0 402718720 0.1114875004 -0.0557769276 -0.0426957272 90 3.5600000000 0.0839339420 0.0347863069 0.0839339420 0.0073788321 0.0160530000 190209945 0 402718720 0.1140951663 -0.0571427867 -0.0436974131 91 3.6000000000 0.0862679332 0.0353520391 0.0862679332 0.0073594347 0.0157530000 190212193 0 402718720 0.1186514720 -0.0586434491 -0.0440094136 92 3.6400000000 0.0899311006 0.0359452898 0.0899311006 0.0073646439 0.0180620000 190214441 0 402718720 0.1265479922 -0.0610372163 -0.0443579480 93 3.6800000000 0.0953022316 0.0365835365 0.0953022316 0.0073562598 0.0153720000 190216689 0 402718720 0.1355164051 -0.0657724664 -0.0457330681 94 3.7200000000 0.0981123969 0.0372380988 0.0981123969 0.0073561401 0.0156900000 190218937 0 402718720 0.1405538023 -0.0668782741 -0.0465042926 95 3.7600000000 0.1014515162 0.0379140295 0.1014515162 0.0073348882 0.0198060000 190221185 0 402718720 0.1456882358 -0.0697210804 -0.0472679548 96 3.8000000000 0.1040043235 0.0386024701 0.1040043235 0.0073434785 0.0194220000 190223433 0 402718720 0.1498331875 -0.0713013262 -0.0479306206 97 3.8400000000 0.1088721380 0.0393268996 0.1088721380 0.0073250050 0.0183010000 190225681 0 402718720 0.1572142988 -0.0750309303 -0.0490855426 98 3.8800000000 0.1117461845 0.0400658719 0.1117461845 0.0073165646 0.0237490000 190227929 0 402718720 0.1634206325 -0.0770329237 -0.0492686443 99 3.9200000000 0.1141498536 0.0408141950 0.1141498536 0.0073765652 0.0261610000 190230177 0 402718720 0.1719726771 -0.0803779215 -0.0498661213 100 3.9600000000 0.1160282344 0.0415663354 0.1160282344 0.0073654783 0.0502260000 202540761 0 402718720 0.1783362180 -0.0820221826 -0.0505689271 101 4.0000000000 0.1235711202 0.0423782639 0.1235711202 0.0073896107 0.0241290000 206202217 0 402718720 0.1784364581 -0.0834625214 -0.0502971560 102 4.0400000000 0.1243408099 0.0431818183 0.1243408099 0.0074193516 0.0183820000 209396657 0 402718720 0.1844839156 -0.0855590552 -0.0513597541 103 4.0800000000 0.1294785589 0.0440196507 0.1294785589 0.0074153519 0.0174040000 209398905 0 402718720 0.1900426894 -0.0879486725 -0.0509198420 104 4.1200000000 0.1341063380 0.0448858689 0.1341063380 0.0074273184 0.0522470000 209401153 0 402718720 0.1996047944 -0.0910541788 -0.0514336638 105 4.1600000000 0.1380064487 0.0457727316 0.1380064487 0.0074355614 0.0203260000 209403401 0 402718720 0.2035520226 -0.0930387601 -0.0512245893 106 4.2000000000 0.1402298212 0.0466638362 0.1402298212 0.0074799363 0.0168670000 209405649 0 402718720 0.2071671188 -0.0943986028 -0.0519099645 107 4.2400000000 0.1430941671 0.0475650542 0.1430941671 0.0074712012 0.0165840000 209407897 0 402718720 0.2117145211 -0.0958151147 -0.0515164621 108 4.2800000000 0.1467650533 0.0484835727 0.1467650533 0.0074890970 0.0189490000 209410145 0 402718720 0.2179428339 -0.0978076383 -0.0514790714 109 4.3200000000 0.1550069749 0.0494608516 0.1550069749 0.0075014113 0.0172240000 209412393 0 402718720 0.2251420170 -0.1004382148 -0.0513528176 110 4.3600000000 0.1601393074 0.0504670194 0.1601393074 0.0074801876 0.0255310000 209414641 0 402718720 0.2321161926 -0.1020309255 -0.0512256995 111 4.4000000000 0.1648035049 0.0514970779 0.1648035049 0.0074616006 0.0200660000 209416889 0 402718720 0.2356103063 -0.1030067131 -0.0510901809 112 4.4400000000 0.1645916998 0.0525068513 0.1648035049 0.0074437363 0.0293260000 209419137 0 402718720 0.2410109341 -0.1045407653 -0.0511611886 113 4.4800000000 0.1684661359 0.0535330396 0.1684661359 0.0074279763 0.0246650000 209421385 0 402718720 0.2453458458 -0.1059260815 -0.0505649410 114 4.5200000000 0.1744767278 0.0545939492 0.1744767278 0.0074128749 0.0248760000 209423633 0 402718720 0.2502593696 -0.1086502299 -0.0501793772 115 4.5600000000 0.1791644394 0.0556771708 0.1791644394 0.0073856001 0.0240080000 209425881 0 402718720 0.2522998452 -0.1087614819 -0.0500499308 116 4.6000000000 0.1794288456 0.0567439956 0.1794288456 0.0073764188 0.0238840000 209428129 0 402718720 0.2578325272 -0.1085686907 -0.0504201390 117 4.6400000000 0.1785686314 0.0577852318 0.1794288456 0.0073586380 0.0246650000 209430377 0 402718720 0.2672767341 -0.1106435806 -0.0500370339 118 4.6800000000 0.1840628386 0.0588553810 0.1840628386 0.0073397471 0.0529840000 209432625 0 402718720 0.2735053301 -0.1158608496 -0.0493704304 119 4.7200000000 0.1873811334 0.0599354294 0.1873811334 0.0073181707 0.0567360000 221738765 0 402718720 0.2830403149 -0.1165875271 -0.0486728474 120 4.7600000000 0.1995496750 0.0610988814 0.1995496750 0.0073327529 0.0224930000 225400221 0 402718720 0.2753111720 -0.1133103892 -0.0479578562 121 4.8000000000 0.2031952143 0.0622732313 0.2031952143 0.0073556735 0.0183850000 228594661 0 402718720 0.2801209688 -0.1151059940 -0.0478067175 122 4.8400000000 0.2067046016 0.0634570950 0.2067046016 0.0073972790 0.0171810000 228596909 0 402718720 0.2865688801 -0.1170498878 -0.0475199744 123 4.8800000000 0.2120552957 0.0646652104 0.2120552957 0.0074004749 0.0191220000 228599157 0 402718720 0.2929506898 -0.1183886603 -0.0462669469 124 4.9200000000 0.2152692676 0.0658797593 0.2152692676 0.0073869565 0.0169450000 228601405 0 402718720 0.2945698798 -0.1177076027 -0.0448475368 125 4.9600000000 0.2174091935 0.0670919947 0.2174091935 0.0073740596 0.0160900000 228603653 0 402718720 0.2950336635 -0.1182734147 -0.0439886190 126 5.0000000000 0.2216245681 0.0683184437 0.2216245681 0.0073522733 0.0159300000 228605901 0 402718720 0.2978636920 -0.1175009012 -0.0432094261 127 5.0400000000 0.2253115326 0.0695546098 0.2253115326 0.0073363298 0.0161040000 228608149 0 402718720 0.3030755520 -0.1181593463 -0.0421374887 128 5.0800000000 0.2313565463 0.0708186874 0.2313565463 0.0073247520 0.0166960000 228610397 0 402718720 0.3073665798 -0.1182998642 -0.0405059382 129 5.1200000000 0.2369430214 0.0721064729 0.2369430214 0.0073079080 0.0165060000 228625957 0 402718720 0.3103550971 -0.1164798737 -0.0388527289 130 5.1600000000 0.2390956283 0.0733910049 0.2390956283 0.0072942294 0.0165920000 228653805 0 402718720 0.3138122559 -0.1158538535 -0.0380358361 131 5.2000000000 0.2415834218 0.0746749165 0.2415834218 0.0073385869 0.0165350000 228656053 0 402718720 0.3157659471 -0.1150424927 -0.0366191380 132 5.2400000000 0.2461971790 0.0759743276 0.2461971790 0.0073554710 0.0187290000 228658301 0 402718720 0.3198703527 -0.1140888631 -0.0350900404 133 5.2800000000 0.2515600324 0.0772945208 0.2515600324 0.0073553486 0.0182500000 228660549 0 402718720 0.3231889904 -0.1132131442 -0.0332679078 134 5.3200000000 0.2572053671 0.0786371391 0.2572053671 0.0074411201 0.0494360000 240965733 0 402718720 0.3262070715 -0.1161092371 -0.0314705111 135 5.3600000000 0.2640596032 0.0800106388 0.2640596032 0.0074799143 0.0201650000 244628869 0 402718720 0.3249483705 -0.1110344306 -0.0311348420 136 5.4000000000 0.2736584842 0.0814345200 0.2736584842 0.0075096328 0.0176700000 247823309 0 402718720 0.3304771781 -0.1104125232 -0.0285769682 137 5.4400000000 0.2777723670 0.0828676430 0.2777723670 0.0075273994 0.0159610000 247825557 0 402718720 0.3326988220 -0.1112376377 -0.0272874683 138 5.4800000000 0.2781032622 0.0842823939 0.2781032622 0.0075657496 0.0162360000 247827805 0 402718720 0.3342796564 -0.1098750606 -0.0260580368 139 5.5200000000 0.2823747098 0.0857075185 0.2823747098 0.0075603931 0.0154630000 247830053 0 402718720 0.3372725546 -0.1087399051 -0.0244721267 140 5.5600000000 0.2868463993 0.0871442247 0.2868463993 0.0075462855 0.0151920000 247832301 0 402718720 0.3404137194 -0.1083470732 -0.0221820381 141 5.6000000000 0.2918043435 0.0885957149 0.2918043435 0.0075316552 0.0149610000 247834549 0 402718720 0.3416365981 -0.1049205735 -0.0207710862 142 5.6400000000 0.2975113988 0.0900669522 0.2975113988 0.0075562202 0.0153300000 247836797 0 402718720 0.3461257815 -0.1052871421 -0.0180733688 143 5.6800000000 0.3027767837 0.0915544335 0.3027767837 0.0075751050 0.0139620000 247839045 0 402718720 0.3495698273 -0.1051142290 -0.0161588769 144 5.7200000000 0.3052273989 0.0930382735 0.3052273989 0.0076054546 0.0177920000 247841293 0 402718720 0.3517411351 -0.1036256030 -0.0147273028 145 5.7600000000 0.3092934191 0.0945296883 0.3092934191 0.0076068593 0.0159500000 247843541 0 402718720 0.3547291756 -0.1030463204 -0.0128105190 146 5.8000000000 0.3153716028 0.0960423042 0.3153716028 0.0075950131 0.0160160000 247845789 0 402718720 0.3572168350 -0.1010779738 -0.0103273820 147 5.8400000000 0.3215015233 0.0975760404 0.3215015233 0.0076011169 0.0180010000 247848037 0 402718720 0.3605821729 -0.0996910483 -0.0081546567 148 5.8800000000 0.3233977258 0.0991018626 0.3233977258 0.0076198548 0.0182280000 247850285 0 402718720 0.3618714511 -0.0985301360 -0.0064224107 149 5.9200000000 0.3257770836 0.1006231728 0.3257770836 0.0076095905 0.0179860000 247852533 0 402718720 0.3644787967 -0.0982015952 -0.0050197975 150 5.9600000000 0.3307738006 0.1021575103 0.3307738006 0.0075936066 0.0184460000 247854781 0 402718720 0.3673084676 -0.0963873193 -0.0028592276 151 6.0000000000 0.3364855051 0.1037093513 0.3364855051 0.0075758243 0.0192320000 247857029 0 402718720 0.3693098724 -0.0954340994 -0.0008432408 152 6.0400000000 0.3433347046 0.1052858339 0.3433347046 0.0075587124 0.0190890000 247859277 0 402718720 0.3739230037 -0.0932851657 0.0025030754 153 6.0800000000 0.3476230800 0.1068697375 0.3476230800 0.0075457544 0.0186930000 247861525 0 402718720 0.3771121204 -0.0924436077 0.0043004877 154 6.1200000000 0.3504951000 0.1084517203 0.3504951000 0.0075345040 0.0487980000 247863773 0 402718720 0.3805195093 -0.0917186067 0.0059445002 155 6.1600000000 0.3526441753 0.1100271555 0.3526441753 0.0075308915 0.0214040000 247866021 0 402718720 0.3818582296 -0.0900866687 0.0070250975 156 6.2000000000 0.3583594263 0.1116190291 0.3583594263 0.0075791230 0.0186320000 247868269 0 402718720 0.3846874237 -0.0891598687 0.0093966015 157 6.2400000000 0.3622655571 0.1132155038 0.3622655571 0.0076030567 0.0201680000 247870517 0 402718720 0.3871503770 -0.0877077132 0.0115759689 158 6.2800000000 0.3649219573 0.1148085826 0.3649219573 0.0076183969 0.0203520000 247872765 0 402718720 0.3890975714 -0.0869922191 0.0135488538 159 6.3200000000 0.3696641326 0.1164114477 0.3696641326 0.0076723949 0.0212080000 247875013 0 402718720 0.3917484879 -0.0853226483 0.0158538427 160 6.3600000000 0.3777187169 0.1180446181 0.3777187169 0.0078128427 0.0201250000 247877261 0 402718720 0.3972159326 -0.0818399787 0.0205713939 161 6.4000000000 0.3802959323 0.1196735083 0.3802959323 0.0078398698 0.0202250000 247879509 0 402718720 0.3992242515 -0.0803682208 0.0226235166 162 6.4400000000 0.3835928738 0.1213026402 0.3835928738 0.0078377401 0.0200830000 247881757 0 402718720 0.4015086293 -0.0784869939 0.0251222495 163 6.4800000000 0.3874222934 0.1229352761 0.3874222934 0.0078611243 0.0215460000 247884005 0 402718720 0.4042155743 -0.0768488050 0.0281296372 164 6.5200000000 0.3921809196 0.1245770178 0.3921809196 0.0078992306 0.0200160000 247886253 0 402718720 0.4071654081 -0.0758484080 0.0311373565 165 6.5600000000 0.3978076577 0.1262329611 0.3978076577 0.0079345094 0.0217940000 247888501 0 402718720 0.4107633531 -0.0736066997 0.0341999605 166 6.6000000000 0.4042502642 0.1279077641 0.4042502642 0.0079922135 0.0220840000 247890749 0 402718720 0.4133479893 -0.0716560036 0.0376475863 167 6.6400000000 0.4070035815 0.1295789965 0.4070035815 0.0080473610 0.0214980000 247892997 0 402718720 0.4156170189 -0.0699153021 0.0405440629 168 6.6800000000 0.4121349156 0.1312608770 0.4121349156 0.0080798440 0.0198470000 247895245 0 402718720 0.4184595942 -0.0682423711 0.0435540415 169 6.7200000000 0.4190637767 0.1329638527 0.4190637767 0.0081032072 0.0517430000 247897493 0 402718720 0.4215716720 -0.0652430058 0.0473395996 170 6.7600000000 0.4232891798 0.1346716488 0.4232891798 0.0081350120 0.0241390000 247899741 0 402718720 0.4237067401 -0.0635312945 0.0501942523 171 6.8000000000 0.4311943054 0.1364056994 0.4311943054 0.0081320704 0.0243340000 247901989 0 402718720 0.4259649217 -0.0608009174 0.0540853031 172 6.8400000000 0.4375313520 0.1381564299 0.4375313520 0.0081390826 0.0232450000 247904237 0 402718720 0.4292466938 -0.0596058443 0.0574295856 173 6.8800000000 0.4398100078 0.1399000922 0.4398100078 0.0081198124 0.0231940000 247906485 0 402718720 0.4310639501 -0.0573376343 0.0598511957 174 6.9200000000 0.4472480118 0.1416664596 0.4472480118 0.0081030723 0.0238680000 247908733 0 402718720 0.4327721298 -0.0546348318 0.0636971891 175 6.9600000000 0.4551159739 0.1434575997 0.4551159739 0.0081014688 0.0229610000 247910981 0 402718720 0.4363986850 -0.0528997518 0.0673382580 176 7.0000000000 0.4619196653 0.1452670432 0.4619196653 0.0080889134 0.0750950000 260220901 0 402718720 0.4373549223 -0.0498614348 0.0711594298 177 7.0400000000 0.4820778966 0.1471699294 0.4820778966 0.0081167337 0.0218710000 263882357 0 402718720 0.4181877375 -0.0286419373 0.0673211813 178 7.0800000000 0.4861339927 0.1490742219 0.4861339927 0.0081463982 0.0208830000 267076797 0 402718720 0.4192047119 -0.0269630924 0.0702479333 179 7.1200000000 0.4907992184 0.1509833001 0.4907992184 0.0081376100 0.0205930000 267079045 0 402718720 0.4222258925 -0.0249986220 0.0732352734 180 7.1600000000 0.4969459176 0.1529053146 0.4969459176 0.0081384413 0.0193820000 267081293 0 402718720 0.4234732389 -0.0230023116 0.0769472271 181 7.2000000000 0.5007513762 0.1548271161 0.5007513762 0.0081216626 0.0517180000 267083541 0 402718720 0.4247012436 -0.0211678073 0.0802743807 182 7.2400000000 0.5064015388 0.1567588437 0.5064015388 0.0081151904 0.0219090000 267085789 0 402718720 0.4261856675 -0.0194102041 0.0836292431 183 7.2800000000 0.5114110112 0.1586968337 0.5114110112 0.0081025408 0.0202120000 267088037 0 402718720 0.4279577136 -0.0170591250 0.0872162804 184 7.3200000000 0.5157566667 0.1606373762 0.5157566667 0.0081036953 0.0201340000 267090285 0 402718720 0.4302916527 -0.0158177018 0.0899899676 185 7.3600000000 0.5186511874 0.1625725860 0.5186511874 0.0080975964 0.0199320000 267092533 0 402718720 0.4316943586 -0.0140933171 0.0925602391 186 7.4000000000 0.5234916210 0.1645130110 0.5234916210 0.0080892150 0.0226690000 267094781 0 402718720 0.4340708852 -0.0125798406 0.0959503725 187 7.4400000000 0.5282861590 0.1664583219 0.5282861590 0.0080970380 0.0205400000 267097029 0 402718720 0.4352314770 -0.0107404515 0.0989891812 188 7.4800000000 0.5319666862 0.1684025153 0.5319666862 0.0080822838 0.0223280000 267099277 0 402718720 0.4367783368 -0.0091778263 0.1015236676 189 7.5200000000 0.5349684954 0.1703420179 0.5349684954 0.0080648110 0.0238050000 267101525 0 402718720 0.4376986325 -0.0073708049 0.1040975302 190 7.5600000000 0.5385625362 0.1722800206 0.5385625362 0.0080445275 0.0224600000 267103773 0 402718720 0.4404399097 -0.0049115256 0.1074162200 191 7.6000000000 0.5429508090 0.1742207054 0.5429508090 0.0080368825 0.0223560000 267106021 0 402718720 0.4415824711 -0.0033496737 0.1103424355 192 7.6400000000 0.5464932323 0.1761596248 0.5464932323 0.0080215103 0.0227280000 267108269 0 402718720 0.4425663948 -0.0015807331 0.1135161519 193 7.6800000000 0.5520042181 0.1781070061 0.5520042181 0.0080084397 0.0224060000 267110517 0 402718720 0.4455085099 0.0023405370 0.1194283888 194 7.7200000000 0.5566090941 0.1800580478 0.5566090941 0.0079944187 0.0234460000 267112765 0 402718720 0.4466497600 0.0039731944 0.1225812435 195 7.7600000000 0.5636982322 0.1820254333 0.5636982322 0.0079861740 0.0240860000 267115013 0 402718720 0.4481149912 0.0077231312 0.1299324036 196 7.8000000000 0.5644931197 0.1839767991 0.5644931197 0.0079707336 0.0535450000 267117261 0 402718720 0.4494166374 0.0098513113 0.1333418041 197 7.8400000000 0.5687413216 0.1859299185 0.5687413216 0.0079536950 0.0237650000 267119509 0 402718720 0.4499636292 0.0121339355 0.1372173280 198 7.8800000000 0.5709832311 0.1878746322 0.5709832311 0.0079347740 0.0242270000 267121757 0 402718720 0.4521465600 0.0152254878 0.1418313682 199 7.9200000000 0.5738307834 0.1898141103 0.5738307834 0.0079229242 0.0234050000 267124005 0 402718720 0.4519044757 0.0174801014 0.1450988650 200 7.9600000000 0.5774128437 0.1917521040 0.5774128437 0.0079076761 0.0251870000 267126253 0 402718720 0.4528888166 0.0201533977 0.1497379541 201 8.0000000000 0.5815103650 0.1936911998 0.5815103650 0.0078913488 0.0250780000 267128501 0 402718720 0.4536748528 0.0230242889 0.1544482857 202 8.0400000000 0.5838167071 0.1956225142 0.5838167071 0.0078762647 0.0249610000 267130749 0 402718720 0.4537893236 0.0255751330 0.1584804952 203 8.0800000000 0.5863555074 0.1975473073 0.5863555074 0.0078607928 0.0247900000 267132997 0 402718720 0.4538355768 0.0284359399 0.1627370715 204 8.1200000000 0.5903226733 0.1994726767 0.5903226733 0.0078578319 0.0258910000 267135245 0 402718720 0.4531182945 0.0305422433 0.1665612310 205 8.1600000000 0.5947617888 0.2014009163 0.5947617888 0.0078635829 0.0243900000 267137493 0 402718720 0.4530406892 0.0331525989 0.1711459607 206 8.1999999990 0.6002747416 0.2033371970 0.6002747416 0.0078840180 0.1063250000 279463445 0 402718720 0.4517292678 0.0356856883 0.1755461246 207 8.2400000000 0.6114301682 0.2053086606 0.6114301682 0.0078742436 0.0269960000 283124901 0 402718720 0.4429059923 0.0443065129 0.1813221127 208 8.2799999990 0.6153350472 0.2072799413 0.6153350472 0.0078846194 0.0241930000 286319341 0 402718720 0.4425715506 0.0465342589 0.1855883449 209 8.3200000000 0.6197703481 0.2092535796 0.6197703481 0.0078822530 0.0584750000 286321589 0 402718720 0.4418675900 0.0483302027 0.1900125891 210 8.3599999990 0.6241856813 0.2112294468 0.6241856813 0.0078715505 0.0214770000 286323837 0 402718720 0.4418498278 0.0507108755 0.1946451962 211 8.4000000000 0.6292355657 0.2132105184 0.6292355657 0.0078783865 0.0198620000 286326085 0 402718720 0.4412955046 0.0527629890 0.1991437823 212 8.4399999990 0.6333928704 0.2151925107 0.6333928704 0.0078881593 0.0201490000 286328333 0 402718720 0.4404604137 0.0545986556 0.2036759555 213 8.4800000000 0.6377661824 0.2171764246 0.6377661824 0.0079006523 0.0200020000 286330581 0 402718720 0.4389022589 0.0560906865 0.2077965438 214 8.5200000000 0.6421849132 0.2191624456 0.6421849132 0.0079133811 0.0194740000 286332829 0 402718720 0.4378329515 0.0576572753 0.2118141949 215 8.5600000000 0.6481092572 0.2211575471 0.6481092572 0.0079302592 0.0195300000 286335077 0 402718720 0.4368230402 0.0587693937 0.2155699134 216 8.6000000000 0.6531415582 0.2231574730 0.6531415582 0.0079212383 0.0215490000 286337325 0 402718720 0.4363392889 0.0612066127 0.2207300514 217 8.6400000000 0.6575219631 0.2251591527 0.6575219631 0.0079261322 0.0210840000 286339573 0 402718720 0.4348106980 0.0616585463 0.2248300463 218 8.6800000000 0.6609743834 0.2271583051 0.6609743834 0.0079260076 0.0209980000 286341821 0 402718720 0.4339851141 0.0624925159 0.2285835594 219 8.7200000000 0.6641163826 0.2291535475 0.6641163826 0.0079292656 0.0249130000 286344069 0 402718720 0.4323918521 0.0628296509 0.2321782112 220 8.7600000000 0.6669497490 0.2311435302 0.6669497490 0.0079317653 0.0227190000 286346317 0 402718720 0.4301098883 0.0628119856 0.2357291430 221 8.8000000000 0.6721857190 0.2331391962 0.6721857190 0.0079270732 0.0221150000 286348565 0 402718720 0.4294644892 0.0651645735 0.2404791415 222 8.8400000000 0.6760749817 0.2351344025 0.6760749817 0.0079169230 0.0226900000 286350813 0 402718720 0.4278968275 0.0668941364 0.2446791530 223 8.8800000000 0.6791259646 0.2371253960 0.6791259646 0.0079156370 0.0217930000 286353061 0 402718720 0.4263074398 0.0667235479 0.2478978187 224 8.9200000000 0.6823419333 0.2391129699 0.6823419333 0.0079050000 0.0586700000 286355309 0 402718720 0.4250861108 0.0694810078 0.2522989810 225 8.9600000000 0.6872478724 0.2411046805 0.6872478724 0.0078962547 0.1203020000 298663241 0 402718720 0.4239414036 0.0715806559 0.2568915486 226 9.0000000000 0.6995551586 0.2431332225 0.6995551586 0.0079180737 0.0288440000 302324185 0 402718720 0.4203776121 0.0740839690 0.2649994195 227 9.0400000000 0.7044758201 0.2451655687 0.7044758201 0.0079087730 0.0240140000 305518625 0 402718720 0.4199080467 0.0755678043 0.2690141201 228 9.0800000000 0.7074856758 0.2471932885 0.7074856758 0.0079029446 0.0219880000 305520873 0 402718720 0.4184741378 0.0767883956 0.2723360658 229 9.1200000000 0.7128638029 0.2492267842 0.7128638029 0.0079145617 0.0208410000 305523121 0 402718720 0.4177615047 0.0777384192 0.2764903903 230 9.1600000000 0.7177575827 0.2512638746 0.7177575827 0.0079092066 0.0204590000 305525369 0 402718720 0.4175706208 0.0786370039 0.2803719640 231 9.2000000000 0.7260961533 0.2533194256 0.7260961533 0.0079186863 0.0202490000 305527617 0 402718720 0.4161417484 0.0799886063 0.2873706222 232 9.2400000000 0.7318689823 0.2553821392 0.7318689823 0.0079130654 0.0475260000 305529865 0 402718720 0.4158293307 0.0817419663 0.2919490635 233 9.2800000000 0.7378972173 0.2574530194 0.7378972173 0.0079148954 0.0204870000 305532113 0 402718720 0.4153614044 0.0833761916 0.2965578735 234 9.3200000000 0.7425984740 0.2595262906 0.7425984740 0.0079099290 0.0183680000 305534361 0 402718720 0.4143996835 0.0851378143 0.3006106019 235 9.3600000000 0.7476962805 0.2616036097 0.7476962805 0.0079087845 0.0221610000 305536609 0 402718720 0.4135790467 0.0862756446 0.3047610521 236 9.4000000000 0.7525929213 0.2636840728 0.7525929213 0.0079052939 0.0204900000 305538857 0 402718720 0.4137682319 0.0873771086 0.3084855676 237 9.4400000000 0.7581875920 0.2657705856 0.7581875920 0.0079099505 0.0204040000 305541105 0 402718720 0.4132396281 0.0892186612 0.3129108250 238 9.4800000000 0.7635815740 0.2678622284 0.7635815740 0.0079064390 0.0259140000 305543353 0 402718720 0.4129250050 0.0904490575 0.3171424270 239 9.5200000000 0.7693933845 0.2699606851 0.7693933845 0.0079097027 0.0253990000 305545601 0 402718720 0.4131086171 0.0922492892 0.3213373125 240 9.5600000000 0.7738728523 0.2720603191 0.7738728523 0.0079050634 0.0238330000 305547849 0 402718720 0.4124980569 0.0927380398 0.3249086440 241 9.6000000000 0.7779239416 0.2741593383 0.7779239416 0.0078982689 0.0247110000 305550097 0 402718720 0.4112471938 0.0935811251 0.3285490572 242 9.6400000000 0.7843964100 0.2762677560 0.7843964100 0.0079075473 0.0248250000 305552345 0 402718720 0.4110504985 0.0951152220 0.3331305981 243 9.6800000000 0.7921809554 0.2783908556 0.7921809554 0.0079053314 0.0245300000 305554593 0 402718720 0.4115374088 0.0966834053 0.3384402096 244 9.7200000000 0.7987207174 0.2805233550 0.7987207174 0.0078996835 0.0247060000 305556841 0 402718720 0.4115243554 0.0986008197 0.3429625630 245 9.7600000000 0.8032796979 0.2826570544 0.8032796979 0.0078891974 0.0252870000 305559089 0 402718720 0.4110547006 0.0994741768 0.3466779888 246 9.8000000000 0.8097078800 0.2847995374 0.8097078800 0.0078825012 0.1499840000 317869897 0 402718720 0.4111922383 0.1011454985 0.3511087000 247 9.8400000000 0.8202123642 0.2869672007 0.8202123642 0.0079003530 0.0344020000 321531353 0 402718720 0.4034331143 0.1033766121 0.3558466434 248 9.8800000000 0.8250902891 0.2891370518 0.8250902891 0.0078937919 0.0282140000 324725793 0 402718720 0.4030299783 0.1051465869 0.3597173095 249 9.9200000000 0.8309503794 0.2913130090 0.8309503794 0.0078851054 0.0242830000 324728041 0 402718720 0.4029535055 0.1058281362 0.3639104068 250 9.9600000000 0.8364646435 0.2934936155 0.8364646435 0.0078762809 0.0239710000 324730289 0 402718720 0.4026391804 0.1069141999 0.3681544960 251 10.0000000000 0.8408598304 0.2956743574 0.8408598304 0.0078674792 0.0224460000 324732537 0 402718720 0.4020357132 0.1073794812 0.3715245128 252 10.0400000000 0.8458191156 0.2978574715 0.8458191156 0.0078560130 0.0215420000 324734785 0 402718720 0.4017434120 0.1083210632 0.3752272427 253 10.0800000000 0.8505632281 0.3000420792 0.8505632281 0.0078454647 0.0209700000 324737033 0 402718720 0.4013434947 0.1093527451 0.3789159656 254 10.1200000000 0.8553311825 0.3022282568 0.8553311825 0.0078336451 0.0207400000 324739281 0 402718720 0.4009618759 0.1105533689 0.3825685382 255 10.1600000000 0.8596631289 0.3044142759 0.8596631289 0.0078220371 0.0207360000 324741529 0 402718720 0.4003230631 0.1115823165 0.3860293627 256 10.2000000000 0.8631616831 0.3065968830 0.8631616831 0.0078198008 0.0262570000 324743777 0 402718720 0.3996967971 0.1117419675 0.3887409866 257 10.2400000000 0.8672995567 0.3087786054 0.8672995567 0.0078257492 0.0474980000 324772649 0 402718720 0.3989866972 0.1125070974 0.3920455873 258 10.2800000000 0.8720955253 0.3109620044 0.8720955253 0.0078264795 0.0241570000 324826097 0 402718720 0.3984235525 0.1140900850 0.3960534930 259 10.3200000000 0.8759595752 0.3131434622 0.8759595752 0.0078315242 0.0286710000 324828345 0 402718720 0.3978470266 0.1145308092 0.3989647329 260 10.3600000000 0.8789044619 0.3153194660 0.8789044619 0.0078270202 0.0280020000 324830593 0 402718720 0.3965290785 0.1152540222 0.4018383920 261 10.4000000000 0.8833318353 0.3174957586 0.8833318353 0.0078197129 0.0262680000 324832841 0 402718720 0.3955802321 0.1162726060 0.4055920839 262 10.4400000000 0.8883885145 0.3196747386 0.8883885145 0.0078112588 0.0273250000 324835089 0 402718720 0.3954590559 0.1170168221 0.4090407789 263 10.4800000000 0.8930138946 0.3218547354 0.8930138946 0.0078001787 0.0286280000 324837337 0 402718720 0.3948144019 0.1182219461 0.4128320217 264 10.5200000000 0.8965314031 0.3240315409 0.8965314031 0.0077928600 0.1332890000 337156633 0 402718720 0.3936792314 0.1184473708 0.4158140719 265 10.5600000000 0.9007330537 0.3262077731 0.9007330537 0.0077929887 0.0368410000 340818089 0 402718720 0.3886632919 0.1174740642 0.4209595621 266 10.6000000000 0.9054043889 0.3283852039 0.9054043889 0.0077846323 0.0276690000 344012529 0 402718720 0.3884643614 0.1180563122 0.4243306220 267 10.6400000000 0.9094551802 0.3305614960 0.9094551802 0.0077753134 0.0270380000 344014777 0 402718720 0.3879348338 0.1188864708 0.4275869727 268 10.6800000000 0.9137308598 0.3327375011 0.9137308598 0.0077674509 0.0252440000 344017025 0 402718720 0.3872771561 0.1198818833 0.4312415123 269 10.7200000000 0.9180667400 0.3349134462 0.9180667400 0.0077605155 0.0520080000 344019273 0 402718720 0.3858326375 0.1203445047 0.4347308576 270 10.7600000000 0.9219358563 0.3370876033 0.9219358563 0.0077508764 0.0244690000 344021521 0 402718720 0.3849436641 0.1215372086 0.4381676316 271 10.8000000000 0.9264189005 0.3392622575 0.9264189005 0.0077420429 0.0234180000 344023769 0 402718720 0.3836882114 0.1224690750 0.4418902695 272 10.8400000000 0.9303403497 0.3414353387 0.9303403497 0.0077324169 0.0224170000 344026017 0 402718720 0.3821263909 0.1234230772 0.4453115761 273 10.8800000000 0.9336122274 0.3436044849 0.9336122274 0.0077252595 0.0223280000 344028265 0 402718720 0.3803191185 0.1237219051 0.4486706257 274 10.9200000000 0.9385462999 0.3457758053 0.9385462999 0.0077187645 0.0265030000 344030513 0 402718720 0.3793487251 0.1246879026 0.4526254833 275 10.9600000000 0.9426508546 0.3479462601 0.9426508546 0.0077141620 0.0252260000 344032761 0 402718720 0.3780953884 0.1264843047 0.4563314915 276 11.0000000000 0.9455515742 0.3501114967 0.9455515742 0.0077120009 0.0251540000 344035009 0 402718720 0.3759402931 0.1264016926 0.4593415260 277 11.0400000000 0.9512319565 0.3522816067 0.9512319565 0.0077123756 0.0311640000 344037257 0 402718720 0.3755022287 0.1275033057 0.4637627602 278 11.0800000000 0.9541591406 0.3544466338 0.9541591406 0.0077124727 0.1393020000 356352781 0 402718720 0.3731165528 0.1282140166 0.4671689868 279 11.1200000000 0.9576405883 0.3566086193 0.9576405883 0.0077074344 0.0384010000 360014237 0 402718720 0.3712396324 0.1280373186 0.4700876474 280 11.1600000000 0.9623845220 0.3587721046 0.9623845220 0.0077009170 0.0286590000 363208677 0 402718720 0.3697975278 0.1295555681 0.4744673371 281 11.2000000000 0.9668304324 0.3609360133 0.9668304324 0.0076983054 0.0291220000 363210925 0 402718720 0.3689047098 0.1310235709 0.4779185057 282 11.2400000000 0.9703585505 0.3630970861 0.9703585505 0.0076973519 0.0267910000 363213173 0 402718720 0.3671608269 0.1315149218 0.4812043905 283 11.2800000000 0.9744018912 0.3652571738 0.9744018912 0.0077009446 0.0243320000 363215421 0 402718720 0.3657930791 0.1329886615 0.4848361909 284 11.3200000000 0.9787893891 0.3674174985 0.9787893891 0.0077100020 0.0240950000 363217669 0 402718720 0.3635257483 0.1339793503 0.4888827205 285 11.3600000000 0.9820129871 0.3695739739 0.9820129871 0.0077065695 0.0239140000 363219917 0 402718720 0.3612512648 0.1343244016 0.4922020733 286 11.4000000000 0.9883488417 0.3717375224 0.9883488417 0.0077115683 0.0237740000 363222165 0 402718720 0.3613446951 0.1355341822 0.4962013066 287 11.4400000000 0.9924706221 0.3739003555 0.9924706221 0.0077114062 0.0250160000 363224413 0 402718720 0.3600908220 0.1369909346 0.4996563792 288 11.4800000000 0.9938125014 0.3760528282 0.9938125014 0.0077195909 0.0312820000 363226661 0 402718720 0.3571497202 0.1376075149 0.5021585822 289 11.5200000000 0.9957316518 0.3781970456 0.9957316518 0.0077197012 0.0287030000 363228909 0 402718720 0.3545839489 0.1372356266 0.5050265193 290 11.5600000000 0.9995965958 0.3803398026 0.9995965958 0.0077103722 0.0300480000 363231157 0 402718720 0.3531863391 0.1376758069 0.5084367990 291 11.6000000000 1.0034869909 0.3824812019 1.0034869909 0.0077013987 0.0478030000 363233405 0 402718720 0.3519687653 0.1388109624 0.5116258860 292 11.6400000000 1.0066928864 0.3846189132 1.0066928864 0.0076921804 0.0370460000 363235653 0 402718720 0.3505465090 0.1390643269 0.5145786405 293 11.6800000000 1.0097928047 0.3867526124 1.0097928047 0.0076819862 0.0358910000 363237901 0 402718720 0.3497453928 0.1399266720 0.5170422196 294 11.7200000000 1.0120210648 0.3888793759 1.0120210648 0.0076726436 0.0359900000 363240149 0 402718720 0.3479834199 0.1396028101 0.5194641352 295 11.7600000000 1.0158653259 0.3910047520 1.0158653259 0.0076677117 0.1676340000 375587653 0 402718720 0.3472014666 0.1398171782 0.5224754810 296 11.8000000000 1.0216610432 0.3931353476 1.0216610432 0.0077301604 0.0392230000 379249109 0 402718720 0.3452275693 0.1363234967 0.5236579776 297 11.8400000000 1.0242909193 0.3952604505 1.0242909193 0.0077338168 0.0255680000 382443549 0 402718720 0.3432364464 0.1363959759 0.5264254212 298 11.8800000000 1.0281840563 0.3973843552 1.0281840563 0.0077386005 0.0255210000 382445797 0 402718720 0.3417782187 0.1362419426 0.5298405290 299 11.9200000000 1.0320626497 0.3995070251 1.0320626497 0.0077373976 0.0242760000 382448045 0 402718720 0.3408492506 0.1360387504 0.5328795910 300 11.9600000000 1.0357375145 0.4016277934 1.0357375145 0.0077369656 0.0239650000 382450293 0 402718720 0.3399376273 0.1356489360 0.5357225537 301 12.0000000000 1.0408608913 0.4037514914 1.0408608913 0.0077388672 0.0227480000 382452541 0 402718720 0.3393118680 0.1357859820 0.5392699838 302 12.0400000000 1.0455150604 0.4058765363 1.0455150604 0.0077348893 0.0227910000 382454789 0 402718720 0.3388482332 0.1358423978 0.5424453616 303 12.0800000000 1.0491480827 0.4079995447 1.0491480827 0.0077284957 0.0229170000 382457037 0 402718720 0.3379267156 0.1353999078 0.5451236963 304 12.1200000000 1.0542378426 0.4101253286 1.0542378426 0.0077287366 0.0226530000 382459285 0 402718720 0.3373541832 0.1356233209 0.5486232042 305 12.1600000000 1.0594308376 0.4122541991 1.0594308376 0.0077221208 0.1102640000 394772705 0 402718720 0.3367629945 0.1358819902 0.5521694422 306 12.2000000000 1.0641654730 0.4143846281 1.0641654730 0.0077182955 0.0358640000 398434161 0 402718720 0.3341025710 0.1361975521 0.5556601286 307 12.2400000000 1.0689603090 0.4165167965 1.0689603090 0.0077178751 0.0254720000 401628601 0 402718720 0.3333285153 0.1368067265 0.5592050552 308 12.2800000000 1.0741397142 0.4186519358 1.0741397142 0.0077263143 0.0232510000 401630849 0 402718720 0.3326031864 0.1371335387 0.5628916025 309 12.3200000000 1.0788753033 0.4207885810 1.0788753033 0.0077324477 0.0226790000 401633097 0 402718720 0.3317846060 0.1373437047 0.5663427114 310 12.3600000000 1.0842646360 0.4229288264 1.0842646360 0.0077506859 0.0218390000 401635345 0 402718720 0.3312280178 0.1382321864 0.5701534152 311 12.4000000000 1.0897101164 0.4250728176 1.0897101164 0.0077791592 0.0225130000 401637593 0 402718720 0.3305443525 0.1389655173 0.5740700364 312 12.4400000000 1.0937594175 0.4272160439 1.0937594175 0.0078029287 0.0341040000 401639841 0 402718720 0.3299869895 0.1384029835 0.5768618584 313 12.4800000000 1.0989384651 0.4293621219 1.0989384651 0.0078119716 0.0223550000 401642089 0 402718720 0.3294022977 0.1386339813 0.5804787874 314 12.5200000000 1.1037334204 0.4315098012 1.1037334204 0.0078156666 0.0221710000 401644337 0 402718720 0.3286254406 0.1389994621 0.5839249492 315 12.5600000000 1.1080272198 0.4336574756 1.1080272198 0.0078147196 0.0294100000 401646585 0 402718720 0.3279702067 0.1392723769 0.5870149732 316 12.6000000000 1.1128659248 0.4358068694 1.1128659248 0.0078090142 0.1249730000 413967033 0 402718720 0.3281021714 0.1389001012 0.5899296999 317 12.6400000000 1.1183329821 0.4379599486 1.1183329821 0.0078092067 0.0356940000 417631801 0 402718720 0.3271599412 0.1388056129 0.5930706263 318 12.6800000000 1.1233700514 0.4401153263 1.1233700514 0.0078066191 0.0244610000 420826241 0 402718720 0.3269082904 0.1393605173 0.5964627266 319 12.7200000000 1.1286046505 0.4422736001 1.1286046505 0.0078001984 0.0234620000 420828489 0 402718720 0.3257575929 0.1403871924 0.6005059481 320 12.7600000000 1.1331611872 0.4444326238 1.1331611872 0.0078018408 0.0231040000 420830737 0 402718720 0.3247502446 0.1406431794 0.6038461924 321 12.8000000000 1.1379996538 0.4465932687 1.1379996538 0.0078220013 0.0226840000 420832985 0 402718720 0.3239051104 0.1413090378 0.6073669195 322 12.8400000000 1.1428529024 0.4487555657 1.1428529024 0.0078440739 0.0224320000 420835233 0 402718720 0.3233430088 0.1420735866 0.6107782125 323 12.8800000000 1.1471703053 0.4509178405 1.1471703053 0.0078789762 0.0223280000 420837481 0 402718720 0.3227573335 0.1424495876 0.6137126684 324 12.9200000000 1.1507813931 0.4530779131 1.1507813931 0.0079092052 0.0222430000 420839729 0 402718720 0.3221646845 0.1424364150 0.6163415909 325 12.9600000000 1.1548639536 0.4552372548 1.1548639536 0.0079437121 0.1602450000 433160421 0 402718720 0.3219235837 0.1424111724 0.6189987659 326 13.0000000000 1.1601324081 0.4573995099 1.1601324081 0.0079718867 0.0453050000 436821877 0 402718720 0.3214965761 0.1421993673 0.6210698485 327 13.0400000000 1.1704694033 0.4595801518 1.1704694033 0.0081633254 0.0285070000 440016317 0 402718720 0.3196671307 0.1438038647 0.6285634041 328 13.0800000000 1.1744824648 0.4617597320 1.1744824648 0.0082151871 0.0218560000 440018565 0 402718720 0.3188560605 0.1439456195 0.6315110326 329 13.1200000000 1.1784650087 0.4639381675 1.1784650087 0.0082410608 0.0575530000 440020813 0 402718720 0.3179129660 0.1442386955 0.6344906688 330 13.1600000000 1.1823022366 0.4661150283 1.1823022366 0.0082662209 0.0237600000 440023061 0 402718720 0.3172848225 0.1441988796 0.6372125745 331 13.2000000000 1.1859781742 0.4682898414 1.1859781742 0.0082946467 0.0238630000 440025309 0 402718720 0.3169071972 0.1440387815 0.6396737099 332 13.2400000000 1.1901687384 0.4704641754 1.1901687384 0.0083115614 0.2205360000 452357673 0 402718720 0.3163531721 0.1444359124 0.6425797343 333 13.2800000000 1.1995202303 0.4726535330 1.1995202303 0.0083583964 0.0345420000 456019129 0 402718720 0.3197761178 0.1408405602 0.6383481622 334 13.3200000000 1.2027432919 0.4748394304 1.2027432919 0.0083884071 0.0240270000 459213569 0 402718720 0.3195477724 0.1407551616 0.6407039762 335 13.3600000000 1.2073572874 0.4770260509 1.2073572874 0.0084202096 0.0244640000 459215817 0 402718720 0.3185079694 0.1417360604 0.6440477371 336 13.4000000000 1.2103602886 0.4792085933 1.2103602886 0.0084600387 0.0251700000 459218065 0 402718720 0.3175091445 0.1419717371 0.6463806033 337 13.4400000000 1.2129127979 0.4813857571 1.2129127979 0.0085141494 0.0239190000 459220313 0 402718720 0.3168465197 0.1415690631 0.6482170224 338 13.4800000000 1.2151826620 0.4835567539 1.2151826620 0.0085594969 0.0242420000 459222561 0 402718720 0.3154606521 0.1415015608 0.6502341032 339 13.5200000000 1.2192034721 0.4857268032 1.2192034721 0.0086011499 0.1553580000 471546893 0 402718720 0.3146068156 0.1419258118 0.6530809999 340 13.5600000000 1.2214176655 0.4878905998 1.2214176655 0.0086224679 0.0323230000 475208349 0 402718720 0.3125093579 0.1420570314 0.6552923918 341 13.6000000000 1.2247568369 0.4900514979 1.2247568369 0.0086453177 0.0232980000 478402789 0 402718720 0.3109808564 0.1423711926 0.6580449939 342 13.6400000000 1.2286144495 0.4922110387 1.2286144495 0.0086630115 0.0240110000 478405037 0 402718720 0.3094680309 0.1431846172 0.6611861587 343 13.6800000000 1.2325656414 0.4943695069 1.2325656414 0.0086865201 0.0585560000 478407285 0 402718720 0.3076879382 0.1444871277 0.6644816995 344 13.7200000000 1.2350784540 0.4965227306 1.2350784540 0.0087097257 0.0245930000 478409533 0 402718720 0.3061391115 0.1451858282 0.6667193174 345 13.7600000000 1.2375251055 0.4986705636 1.2375251055 0.0087420482 0.0228390000 478411781 0 402718720 0.3054620326 0.1445706785 0.6682676673 346 13.8000000000 1.2391424179 0.5008106556 1.2391424179 0.0087526020 0.1701230000 490741593 0 402718720 0.3045004010 0.1446619928 0.6698303819 347 13.8400000000 1.2417495251 0.5029459261 1.2417495251 0.0087628253 0.0287030000 494403049 0 402718720 0.3025344014 0.1443681270 0.6718799472 348 13.8800000000 1.2445482016 0.5050769672 1.2445482016 0.0087756891 0.0243250000 497597489 0 402718720 0.3007454276 0.1444643140 0.6743887663 349 13.9200000000 1.2473748922 0.5072038953 1.2473748922 0.0087810021 0.0233710000 497599737 0 402718720 0.2983711064 0.1445557624 0.6771660447 350 13.9600000000 1.2503628731 0.5093272067 1.2503628731 0.0087905294 0.0243370000 497601985 0 402718720 0.2961896062 0.1449568272 0.6801578403 351 14.0000000000 1.2529071569 0.5114456681 1.2529071569 0.0087936302 0.0220810000 497604233 0 402718720 0.2940454781 0.1455536336 0.6826985478 352 14.0400000000 1.2536979914 0.5135543395 1.2536979914 0.0087983998 0.0233830000 497606481 0 402718720 0.2921221852 0.1452981979 0.6841098070 353 14.0800000000 1.2566210032 0.5156593442 1.2566210032 0.0088055486 0.1467880000 509929945 0 402718720 0.2902490795 0.1446178108 0.6853581071 354 14.1200000000 1.2606127262 0.5177637323 1.2606127262 0.0088102664 0.0298590000 513590889 0 402718720 0.2874805927 0.1455671936 0.6890544891 355 14.1600000000 1.2623735666 0.5198612247 1.2623735666 0.0088078661 0.0246630000 516785329 0 402718720 0.2853025794 0.1458716840 0.6908883452 356 14.2000000000 1.2636990547 0.5219506569 1.2636990547 0.0088071918 0.0237760000 516787577 0 402718720 0.2829998732 0.1457968801 0.6924269795 357 14.2400000000 1.2658066750 0.5240342872 1.2658066750 0.0088006929 0.0544300000 516789825 0 402718720 0.2801356614 0.1462424695 0.6949075460 358 14.2800000000 1.2679643631 0.5261123041 1.2679643631 0.0087889424 0.0257270000 516792073 0 402718720 0.2780938148 0.1461640745 0.6969122887 359 14.3200000000 1.2706094980 0.5281861125 1.2706094980 0.0087795909 0.0248230000 516794321 0 402718720 0.2747743130 0.1473945081 0.6999065876 360 14.3600000000 1.2742344141 0.5302584689 1.2742344141 0.0087702578 0.1137910000 529164681 0 402718720 0.2690437436 0.1484981775 0.7045937777 361 14.4000000000 1.2773609161 0.5323280047 1.2773609161 0.0087592201 0.0365520000 532826137 0 402718720 0.2654361129 0.1500551403 0.7081849575 362 14.4400000000 1.2773122787 0.5343859723 1.2773609161 0.0087742836 0.0324990000 536020577 0 402718720 0.2594671547 0.1498852670 0.7107174993 363 14.4800000000 1.2785997391 0.5364361480 1.2785997391 0.0087633983 0.0293470000 536022825 0 402718720 0.2573333681 0.1493345350 0.7120282650 364 14.5200000000 1.2808552980 0.5384812556 1.2808552980 0.0087541041 0.0274460000 536025073 0 402718720 0.2545561790 0.1494025886 0.7141900659 365 14.5600000000 1.2824325562 0.5405194783 1.2824325562 0.0087434907 0.0279080000 536027321 0 402718720 0.2515255809 0.1493377984 0.7159862518 366 14.6000000000 1.2882941961 0.5425625786 1.2882941961 0.0087471141 0.0290390000 536029569 0 402718720 0.2456423491 0.1512954086 0.7215753198 367 14.6400000000 1.2896643877 0.5445982784 1.2896643877 0.0087352104 0.1496600000 548353933 0 402718720 0.2421501726 0.1527688503 0.7237085700 368 14.6800000000 1.2902417183 0.5466244834 1.2902417183 0.0087284227 0.0340180000 552015389 0 402718720 0.2390336990 0.1524043828 0.7253191471 369 14.7200000000 1.2893419266 0.5486372678 1.2902417183 0.0087291663 0.0667020000 555209829 0 402718720 0.2360537946 0.1517776102 0.7257983088 370 14.7600000000 1.2887740135 0.5506376373 1.2902417183 0.0087192998 0.0278660000 555212077 0 402718720 0.2332241535 0.1513743401 0.7263398170 371 14.8000000000 1.2913622856 0.5526341997 1.2913622856 0.0087097705 0.0280300000 555214325 0 402718720 0.2298858911 0.1520208418 0.7287219167 372 14.8400000000 1.2931348085 0.5546247928 1.2931348085 0.0086985688 0.0280490000 555216573 0 402718720 0.2267717421 0.1525149047 0.7306094766 373 14.8800000000 1.2943696976 0.5566080231 1.2943696976 0.0086881759 0.0278300000 555218821 0 402718720 0.2232896537 0.1529024541 0.7322559357 374 14.9200000000 1.2946187258 0.5585813137 1.2946187258 0.0086798392 0.1555730000 567545313 0 402718720 0.2194392979 0.1532906741 0.7333570719 375 14.9600000000 1.2942889929 0.5605432009 1.2946187258 0.0086702926 0.0377160000 571206769 0 402718720 0.2152017653 0.1528500915 0.7333961129 376 15.0000000000 1.2962619066 0.5624998996 1.2962619066 0.0086593591 0.0298750000 574401209 0 402718720 0.2119662911 0.1526647657 0.7351185679 377 15.0400000000 1.2975699902 0.5644496876 1.2975699902 0.0086593364 0.0294870000 574403457 0 402718720 0.2047615349 0.1529950202 0.7376173139 378 15.0800000000 1.2989081144 0.5663926993 1.2989081144 0.0086483253 0.0271460000 574405705 0 402718720 0.2017503530 0.1529948562 0.7387803197 379 15.1200000000 1.2997671366 0.5683277242 1.2997671366 0.0086372574 0.0586960000 574407953 0 402718720 0.1991664618 0.1528236717 0.7396551371 380 15.1600000000 1.3011407852 0.5702561796 1.3011407852 0.0086286675 0.0295560000 574410201 0 402718720 0.1966539919 0.1522834897 0.7406663895 381 15.2000000000 1.3041509390 0.5721824126 1.3041509390 0.0086326536 0.1231850000 586729353 0 402718720 0.1938812137 0.1524225026 0.7424714565 382 15.2400000000 1.3031605482 0.5740959679 1.3041509390 0.0086377507 0.0400490000 590390809 0 402718720 0.1908799559 0.1523904204 0.7428075075 383 15.2800000000 1.3037626743 0.5760011029 1.3041509390 0.0086440270 0.0298540000 593585249 0 402718720 0.1879844666 0.1522985995 0.7435917854 384 15.3200000000 1.3061847687 0.5779026229 1.3061847687 0.0086550833 0.0264400000 593587497 0 402718720 0.1850529015 0.1525298655 0.7452937961 385 15.3600000000 1.3070918322 0.5797966208 1.3070918322 0.0086556445 0.0268220000 593589745 0 402718720 0.1823773086 0.1524916887 0.7460817099 386 15.4000000000 1.3083025217 0.5816839418 1.3083025217 0.0086518866 0.0271770000 593591993 0 402718720 0.1799046844 0.1524411440 0.7469574809 387 15.4400000000 1.3101867437 0.5835663780 1.3101867437 0.0086579983 0.0271380000 593594241 0 402718720 0.1778078824 0.1524886638 0.7481548786 388 15.4800000000 1.3119664192 0.5854436977 1.3119664192 0.0086636582 0.0275190000 593596489 0 402718720 0.1756892055 0.1525962651 0.7492696643 389 15.5200000000 1.3138750792 0.5873162720 1.3138750792 0.0086629920 0.1285800000 605914465 0 402718720 0.1730321944 0.1528638899 0.7504794598 390 15.5600000000 1.3177785873 0.5891892522 1.3177785873 0.0086773398 0.0387560000 609575921 0 402718720 0.1713165343 0.1524385661 0.7485256195 391 15.6000000000 1.3193411827 0.5910566485 1.3193411827 0.0086788036 0.0281150000 612770361 0 402718720 0.1690673083 0.1524290740 0.7495799661 392 15.6400000000 1.3218717575 0.5929209727 1.3218717575 0.0086920739 0.0625750000 612772609 0 402718720 0.1667852700 0.1524878293 0.7511813641 393 15.6800000000 1.3231114149 0.5947789637 1.3231114149 0.0086867172 0.0229940000 612774857 0 402718720 0.1644687057 0.1523439586 0.7520336509 394 15.7200000000 1.3246943951 0.5966315409 1.3246943951 0.0086868870 0.0240910000 612777105 0 402718720 0.1622753888 0.1523168832 0.7530353665 395 15.7600000000 1.3281872272 0.5984835806 1.3281872272 0.0086943697 0.0231190000 612779353 0 402718720 0.1601262689 0.1523334533 0.7550081015 396 15.8000000000 1.3310725689 0.6003335528 1.3310725689 0.0086939636 0.1703860000 625090889 0 402718720 0.1577620357 0.1526695341 0.7566168904 397 15.8400000000 1.3320997953 0.6021767927 1.3320997953 0.0086895080 0.0530830000 628752345 0 402718720 0.1557924747 0.1524259597 0.7574002147 398 15.8800000000 1.3364511728 0.6040217032 1.3364511728 0.0086915588 0.0359920000 631946785 0 402718720 0.1541086733 0.1522986740 0.7597229481 399 15.9200000000 1.3381898403 0.6058617236 1.3381898403 0.0086882587 0.0329480000 631949033 0 402718720 0.1514493525 0.1527435780 0.7609056830 400 15.9600000000 1.3400064707 0.6076970855 1.3400064707 0.0086887185 0.0320670000 631951281 0 402718720 0.1496279836 0.1522590965 0.7618604898 401 16.0000000000 1.3423509598 0.6095291401 1.3423509598 0.0086850035 0.0336690000 631953529 0 402718720 0.1477256119 0.1518351585 0.7631512880 402 16.0400000000 1.3464465141 0.6113622679 1.3464465141 0.0086872639 0.0301990000 631955777 0 402718720 0.1459065974 0.1517462879 0.7653538585 403 16.0800000000 1.3501232862 0.6131954217 1.3501232862 0.0086822107 0.1805550000 644270213 0 402718720 0.1439060271 0.1517157257 0.7672730088 404 16.1200000000 1.3525410891 0.6150254853 1.3525410891 0.0086740078 0.0385630000 647931669 0 402718720 0.1417855173 0.1515048593 0.7685713172 405 16.1600000000 1.3549124002 0.6168523665 1.3549124002 0.0086701768 0.0258520000 651126109 0 402718720 0.1399300247 0.1511323452 0.7697492242 406 16.2000000000 1.3601903915 0.6186832484 1.3601903915 0.0086855327 0.0270640000 651128357 0 402718720 0.1379241049 0.1511688977 0.7724891901 407 16.2400000000 1.3633877039 0.6205129891 1.3633877039 0.0086859341 0.0260860000 651130605 0 402718720 0.1355258375 0.1516086757 0.7743045688 408 16.2800000000 1.3661527634 0.6223405375 1.3661527634 0.0086955015 0.0261680000 651132853 0 402718720 0.1337416172 0.1516465247 0.7757131457 409 16.3200000000 1.3703622818 0.6241694415 1.3703622818 0.0087020614 0.0257870000 651135101 0 402718720 0.1315094531 0.1516812891 0.7778797746 410 16.3600000000 1.3727546930 0.6259952592 1.3727546930 0.0086985701 0.1364010000 663448773 0 402718720 0.1298007071 0.1516419649 0.7790746689 411 16.3999999990 1.3746595383 0.6278168268 1.3746595383 0.0086895442 0.0419870000 667110229 0 402718720 0.1278466582 0.1517452002 0.7800015211 412 16.4400000000 1.3779164553 0.6296374570 1.3779164553 0.0086883764 0.0280430000 670304669 0 402718720 0.1260823160 0.1514456570 0.7816704512 413 16.4800000000 1.3825349808 0.6314604534 1.3825349808 0.0087043078 0.0253840000 670306917 0 402718720 0.1239933968 0.1516792476 0.7839025259 414 16.5200000000 1.3858579397 0.6332826696 1.3858579397 0.0087117017 0.0255890000 670309165 0 402718720 0.1218009740 0.1520534456 0.7856143713 415 16.5599999990 1.3902244568 0.6351066257 1.3902244568 0.0087333364 0.0623460000 670311413 0 402718720 0.1198912263 0.1525486559 0.7876974344 416 16.6000000000 1.3926575184 0.6369276615 1.3926575184 0.0087410303 0.0255060000 670313661 0 402718720 0.1179876626 0.1528966278 0.7889823914 417 16.6400000000 1.3951195478 0.6387458674 1.3951195478 0.0087470333 0.1455590000 682627285 0 402718720 0.1164032966 0.1528932899 0.7900615931 418 16.6800000000 1.3991891146 0.6405651097 1.3991891146 0.0088606832 0.0470400000 686288229 0 402718720 0.1204382554 0.1531377584 0.7939841747 419 16.7199999990 1.4039731026 0.6423870858 1.4039731026 0.0088776475 0.0444530000 689482669 0 402718720 0.1212478504 0.1528270692 0.7953302860 420 16.7600000000 1.4070606232 0.6442077371 1.4070606232 0.0089203593 0.0462110000 689484917 0 402718720 0.1235173866 0.1504564136 0.7981824875 421 16.8000000000 1.4083508253 0.6460228038 1.4083508253 0.0090635897 0.0666070000 689487165 0 402718720 0.1254752874 0.1517384946 0.8015170097 422 16.8400000000 1.4119361639 0.6478377643 1.4119361639 0.0091138286 0.0473500000 689489413 0 402718720 0.1273009330 0.1495311111 0.8026430011 423 16.8799999990 1.4149321318 0.6496512262 1.4149321318 0.0091746834 0.0463550000 689491661 0 402718720 0.1257966459 0.1497309059 0.8046617508 424 16.9200000000 1.4201821089 0.6514685160 1.4201821089 0.0093422636 0.2016250000 701813981 0 402718720 0.1284114867 0.1496902257 0.8086568117 425 16.9600000000 1.4258247614 0.6532905307 1.4258247614 0.0099411334 0.0428270000 705475437 0 402718720 0.1282943785 0.1447229981 0.8072061539 426 17.0000000000 1.4245052338 0.6551008939 1.4258247614 0.0108498054 0.0816320000 708669877 0 402718720 0.1309657991 0.1506851614 0.8126206398 427 17.0400000000 1.4276361465 0.6569101099 1.4276361465 0.0108917282 0.0372920000 708672125 0 402718720 0.1333531439 0.1483566165 0.8142939806 428 17.0800000000 1.4291467667 0.6587144012 1.4291467667 0.0110017075 0.0392450000 708674373 0 402718720 0.1340702027 0.1505856067 0.8165217042 429 17.1200000000 1.4315527678 0.6605158892 1.4315527678 0.0110352068 0.0421810000 708676621 0 402718720 0.1355984658 0.1494764388 0.8163968921 430 17.1600000000 1.4313122034 0.6623084388 1.4315527678 0.0111500906 0.0533650000 708678869 0 402718720 0.1377937198 0.1502252519 0.8199081421 431 17.2000000000 1.4341346025 0.6640992187 1.4341346025 0.0111640547 0.0461710000 708681117 0 402718720 0.1359391063 0.1498582363 0.8207024336 432 17.2400000000 1.4372471571 0.6658889130 1.4372471571 0.0111776363 0.0444730000 708683365 0 402718720 0.1342189163 0.1499947459 0.8220939636 433 17.2800000000 1.4399391413 0.6676765579 1.4399391413 0.0111836137 0.0440700000 708685613 0 402718720 0.1328730136 0.1502394527 0.8232899308 434 17.3200000000 1.4418927431 0.6694604662 1.4418927431 0.0111854784 0.0427980000 708687861 0 402718720 0.1311210394 0.1504078507 0.8238298893 435 17.3600000000 1.4426703453 0.6712379601 1.4426703453 0.0111967743 0.1247350000 721002821 0 402718720 0.1294120997 0.1503513008 0.8242788315 436 17.4000000000 1.4471199512 0.6730175060 1.4471199512 0.0112394860 0.0324720000 724664277 0 402718720 0.1215521619 0.1518843025 0.8222934008 437 17.4400000000 1.4497048855 0.6747948226 1.4497048855 0.0112446016 0.0572150000 727858717 0 402718720 0.1221788451 0.1513248831 0.8230001926 438 17.4800000000 1.4492614269 0.6765630112 1.4497048855 0.0113191323 0.0284210000 727860965 0 402718720 0.1237527803 0.1518999338 0.8254749775 439 17.5200000000 1.4510543346 0.6783272284 1.4510543346 0.0113208928 0.0297550000 727863213 0 402718720 0.1221213564 0.1518122554 0.8260297775 440 17.5600000000 1.4527329206 0.6800872413 1.4527329206 0.0113210725 0.0287930000 727865461 0 402718720 0.1204172075 0.1517230868 0.8263735175 441 17.6000000000 1.4540140629 0.6818421774 1.4540140629 0.0113201785 0.0261200000 727867709 0 402718720 0.1186303422 0.1514825821 0.8265289068 442 17.6400000000 1.4550321102 0.6835914759 1.4550321102 0.0113202221 0.1344260000 740175005 0 402718720 0.1170308515 0.1509045959 0.8265564442 443 17.6800000000 1.4569129944 0.6853371227 1.4569129944 0.0113270155 0.0321980000 743843805 0 402718720 0.1153274029 0.1512745619 0.8267291188 444 17.7200000000 1.4589073658 0.6870793980 1.4589073658 0.0113240299 0.0226750000 747038245 0 402718720 0.1134167835 0.1511005461 0.8271160722 445 17.7600000000 1.4603059292 0.6888169857 1.4603059292 0.0113204865 0.0213820000 747040493 0 402718720 0.1117432490 0.1509959698 0.8273656964 446 17.8000000000 1.4616690874 0.6905498380 1.4616690874 0.0113194296 0.0210440000 747042741 0 402718720 0.1098594591 0.1506201327 0.8275409341 447 17.8400000000 1.4642885923 0.6922807971 1.4642885923 0.0113202099 0.0499210000 747044989 0 402718720 0.1078056395 0.1504452378 0.8283830285 448 17.8800000000 1.4671189785 0.6940103467 1.4671189785 0.0113120988 0.0240710000 747047237 0 402718720 0.1083946154 0.1503331810 0.8276181221 449 17.9200000000 1.4654972553 0.6957285803 1.4671189785 0.0113394284 0.2071640000 759356165 0 402718720 0.1095232069 0.1498560905 0.8304417729 450 17.9600000000 1.4679185152 0.6974445579 1.4679185152 0.0113306277 0.0298730000 763017109 0 402718720 0.1079204902 0.1488474905 0.8295860887 451 18.0000000000 1.4704002142 0.6991584286 1.4704002142 0.0113337828 0.0253630000 766211549 0 402718720 0.1090362370 0.1481713802 0.8315492272 452 18.0400000000 1.4724802971 0.7008693177 1.4724802971 0.0113275361 0.0210630000 766213797 0 402718720 0.1070064977 0.1479747891 0.8320986032 453 18.0800000000 1.4741560221 0.7025763523 1.4741560221 0.0113233635 0.0224300000 766216045 0 402718720 0.1047440767 0.1474062651 0.8327214122 454 18.1200000000 1.4771418571 0.7042824437 1.4771418571 0.0113195531 0.0232300000 766218293 0 402718720 0.1022131145 0.1473096907 0.8334739804 455 18.1600000000 1.4799959660 0.7059873086 1.4799959660 0.0113100399 0.0227740000 766220541 0 402718720 0.0998075083 0.1472530365 0.8343034387 456 18.2000000000 1.4817968607 0.7076886454 1.4817968607 0.0112995095 0.1357360000 778529961 0 402718720 0.0980165228 0.1466350555 0.8342103958 457 18.2400000000 1.4834550619 0.7093861649 1.4834550619 0.0112904762 0.0271930000 782191417 0 402718720 0.0954449773 0.1468846947 0.8354373574 458 18.2800000000 1.4845751524 0.7110787173 1.4845751524 0.0112918741 0.0296410000 785385857 0 402718720 0.0951057225 0.1470269710 0.8365620375 459 18.3200000000 1.4857732058 0.7127665048 1.4857732058 0.0112958787 0.0208540000 785388105 0 402718720 0.0961930379 0.1462118328 0.8372718096 460 18.3600000000 1.4875485897 0.7144508137 1.4875485897 0.0112851991 0.0200690000 785390353 0 402718720 0.0943071619 0.1458074003 0.8373615742 461 18.4000000000 1.4899867773 0.7161331043 1.4899867773 0.0112750094 0.0468020000 785392601 0 402718720 0.0918843299 0.1453028321 0.8378120661 462 18.4400000000 1.4928816557 0.7178143782 1.4928816557 0.0112654025 0.0220140000 785394849 0 402718720 0.0895334855 0.1450522244 0.8383794427 463 18.4800000000 1.4939916134 0.7194907869 1.4939916134 0.0112556359 0.1661960000 797704665 0 402718720 0.0876874477 0.1451922953 0.8381635547 464 18.5200000000 1.4964504242 0.7211652689 1.4964504242 0.0112577288 0.0258450000 801366121 0 402718720 0.0863288566 0.1449289918 0.8366564512 465 18.5600000000 1.4975718260 0.7228349604 1.4975718260 0.0112659739 0.0196560000 804560561 0 402718720 0.0868986920 0.1438442469 0.8391442299 466 18.6000000000 1.5000810623 0.7245028705 1.5000810623 0.0112576755 0.0197640000 804562809 0 402718720 0.0847993270 0.1433796883 0.8396713138 467 18.6400000000 1.5017036200 0.7261671119 1.5017036200 0.0112530186 0.0183880000 804565057 0 402718720 0.0828131437 0.1435946226 0.8396525383 468 18.6800000000 1.5023804903 0.7278256875 1.5023804903 0.0112471440 0.0182610000 804567305 0 402718720 0.0812191889 0.1432906091 0.8389587402 469 18.7200000000 1.5049737692 0.7294827197 1.5049737692 0.0112415910 0.0180170000 804569553 0 402718720 0.0792077705 0.1432595253 0.8389908075 470 18.7600000000 1.5064920187 0.7311359310 1.5064920187 0.0112312462 0.1215090000 816875433 0 402718720 0.0773618519 0.1429145485 0.8384671807 471 18.8000000000 1.5193792582 0.7328094837 1.5193792582 0.0118010818 0.0280740000 820536889 0 402718720 0.0760079995 0.1413338631 0.8275505900 472 18.8400000000 1.5221790075 0.7344818767 1.5221790075 0.0118018002 0.0231710000 823731329 0 402718720 0.0764012709 0.1405712664 0.8267060518 473 18.8800000000 1.5237116814 0.7361504387 1.5237116814 0.0118144281 0.0235740000 823733577 0 402718720 0.0766577646 0.1394732296 0.8240287900 474 18.9200000000 1.5242604017 0.7378131179 1.5242604017 0.0118110429 0.0223780000 823735825 0 402718720 0.0757044405 0.1387248486 0.8237120509 475 18.9600000000 1.5252364874 0.7394708514 1.5252364874 0.0118104423 0.0492840000 823738073 0 402718720 0.0742620081 0.1384831071 0.8244507909 476 19.0000000000 1.5291315317 0.7411298024 1.5291315317 0.0118808645 0.0228410000 823740321 0 402718720 0.0749742910 0.1381226927 0.8211724758 477 19.0400000000 1.5306299925 0.7427849390 1.5306299925 0.0119076832 0.1315280000 836049273 0 402718720 0.0744154081 0.1377319247 0.8190370202 478 19.0800000000 1.5490909815 0.7444717718 1.5490909815 0.0126503554 0.0216780000 839710729 0 402718720 0.0772255957 0.1377744675 0.8071448207 479 19.1200000000 1.5493890047 0.7461521835 1.5493890047 0.0126543358 0.0179980000 842905169 0 402718720 0.0769222826 0.1379333287 0.8072796464 480 19.1600000000 1.5484585762 0.7478236552 1.5493890047 0.0126653709 0.0163260000 842907417 0 402718720 0.0767287984 0.1381899714 0.8073462248 481 19.2000000000 1.5494014025 0.7494901370 1.5494014025 0.0126748128 0.0162930000 842909665 0 402718720 0.0762127489 0.1376807392 0.8077685833 482 19.2400000000 1.5499311686 0.7511508030 1.5499311686 0.0126926282 0.0162750000 842911913 0 402718720 0.0760673657 0.1379938424 0.8077350855 483 19.2800000000 1.5510723591 0.7528069553 1.5510723591 0.0126999008 0.0160550000 842914161 0 402718720 0.0758243799 0.1373008192 0.8080369830 484 19.3200000000 1.5520759821 0.7544583376 1.5520759821 0.0127176332 0.0146550000 842916409 0 402718720 0.0761335641 0.1370704472 0.8079331517 485 19.3600000000 1.5525473356 0.7561038819 1.5525473356 0.0127568390 0.0143750000 842918657 0 402718720 0.0763078108 0.1372018158 0.8075619936 486 19.4000000000 1.5541139841 0.7577458780 1.5541139841 0.0127880726 0.0142900000 842920905 0 402718720 0.0758321956 0.1372226775 0.8090986013 487 19.4400000000 1.5568062067 0.7593866590 1.5568062067 0.0128224464 0.0138040000 842923153 0 402718720 0.0762546808 0.1370672882 0.8086073399 488 19.4800000000 1.5577313900 0.7610226113 1.5577313900 0.0128668527 0.0129750000 842925401 0 402718720 0.0760671943 0.1367966682 0.8102408051 489 19.5200000000 1.5634243488 0.7626635146 1.5634243488 0.0128963973 0.1082910000 855236609 0 402718720 0.0755453035 0.1365139186 0.8103356957 490 19.5600000000 1.5649710894 0.7643008770 1.5649710894 0.0129089233 0.0166980000 858898065 0 402718720 0.0752968937 0.1322039664 0.8104801774 491 19.6000000000 1.5678038597 0.7659373393 1.5678038597 0.0129268579 0.0153030000 862092505 0 402718720 0.0760669485 0.1320832223 0.8111071587 492 19.6400000000 1.5690114498 0.7675696038 1.5690114498 0.0129419786 0.0154180000 862094753 0 402718720 0.0767093301 0.1320948750 0.8129826784 493 19.6800000000 1.5687692165 0.7691947551 1.5690114498 0.0129691155 0.0147780000 862097001 0 402718720 0.0776141435 0.1328703314 0.8134546876 494 19.7200000000 1.5727676153 0.7708214208 1.5727676153 0.0129984821 0.0448390000 862099249 0 402718720 0.0781094804 0.1323264241 0.8146845698 495 19.7600000000 1.5773992538 0.7724508710 1.5773992538 0.0130154279 0.0174380000 862101497 0 402718720 0.0789418966 0.1317060888 0.8161080480 496 19.8000000000 1.5808651447 0.7740807385 1.5808651447 0.0130259503 0.0145430000 862103745 0 402718720 0.0799187273 0.1312770545 0.8173755407 497 19.8400000000 1.5817712545 0.7757058703 1.5817712545 0.0130462570 0.0145650000 862105993 0 402718720 0.0806492195 0.1316309124 0.8179842830 498 19.8800000000 1.5837565660 0.7773284621 1.5837565660 0.0130550695 0.0156740000 862108241 0 402718720 0.0816938579 0.1313638389 0.8188576698 499 19.9200000000 1.5871258974 0.7789513026 1.5871258974 0.0130570666 0.0161100000 862110489 0 402718720 0.0826992542 0.1306909472 0.8201475143 500 19.9600000000 1.5896592140 0.7805727184 1.5896592140 0.0130691512 0.0138010000 862112737 0 402718720 0.0827784315 0.1308941990 0.8205693364 501 20.0000000000 1.5913950205 0.7821911262 1.5913950205 0.0130795991 0.0140080000 862114985 0 402718720 0.0837820023 0.1306992471 0.8215356469 502 20.0400000000 1.5940132141 0.7838083017 1.5940132141 0.0130935705 0.0150660000 862117233 0 402718720 0.0847199038 0.1302177757 0.8224651814 503 20.0800000000 1.5965089798 0.7854240088 1.5965089798 0.0131133498 0.0161120000 862119481 0 402718720 0.0851266235 0.1303223073 0.8236293793 504 20.1200000000 1.5989586115 0.7870381648 1.5989586115 0.0131227671 0.0156270000 862121729 0 402718720 0.0859697163 0.1297409981 0.8246313334 505 20.1600000000 1.6008459330 0.7886496653 1.6008459330 0.0131410501 0.0164740000 862123977 0 402718720 0.0865113586 0.1296456456 0.8254369497 506 20.2000000000 1.6024351120 0.7902579369 1.6024351120 0.0131617158 0.0159880000 862126225 0 402718720 0.0873473659 0.1293273866 0.8262785673 507 20.2400000000 1.6044209003 0.7918637810 1.6044209003 0.0131732777 0.0159530000 862128473 0 402718720 0.0878343731 0.1286195368 0.8272632360 508 20.2800000000 1.6073594093 0.7934690874 1.6073594093 0.0131754795 0.0159120000 862130721 0 402718720 0.0880468860 0.1277128160 0.8282024264 509 20.3200000000 1.6094850302 0.7950722621 1.6094850302 0.0131761642 0.1020880000 874440905 0 402718720 0.0889855251 0.1266559064 0.8291558623 510 20.3600000000 1.5972676277 0.7966451942 1.6094850302 0.0139606342 0.0099460000 878102361 0 402718720 0.0824035257 0.1308212876 0.8399236798 511 20.4000000000 1.5989965200 0.7982153534 1.6094850302 0.0139756022 0.0147840000 881296801 0 402718720 0.0824756399 0.1302819550 0.8403733373 512 20.4400000000 1.6010230780 0.7997833372 1.6094850302 0.0139900725 0.0122980000 881299049 0 402718720 0.0823131651 0.1302045435 0.8408746719 513 20.4800000000 1.6007629633 0.8013447010 1.6094850302 0.0140139058 0.0118750000 881354545 0 402718720 0.0822019055 0.1304100901 0.8408213258 514 20.5200000000 1.6024960279 0.8029033612 1.6094850302 0.0140231799 0.0298890000 881459193 0 402718720 0.0820311457 0.1302341074 0.8413375616 515 20.5600000000 1.6031259298 0.8044571914 1.6094850302 0.0140282496 0.0177990000 881461441 0 402718720 0.0817920268 0.1300408542 0.8412780166 516 20.6000000000 1.6033113003 0.8060053583 1.6094850302 0.0140336310 0.0118400000 881463689 0 402718720 0.0811976641 0.1300385296 0.8409700394 517 20.6400000000 1.6028504372 0.8075466447 1.6094850302 0.0140393373 0.0103260000 881465937 0 402718720 0.0805790722 0.1300031245 0.8403866291 518 20.6800000000 1.6032210588 0.8090826957 1.6094850302 0.0140432492 0.0103500000 881468185 0 402718720 0.0801079571 0.1296829432 0.8400696516 519 20.7200000000 1.6044622660 0.8106152190 1.6094850302 0.0140504406 0.0108240000 881470433 0 402718720 0.0792881176 0.1298983246 0.8400750160 520 20.7600000000 1.6048405170 0.8121425753 1.6094850302 0.0140595942 0.0117710000 881472681 0 402718720 0.0787658170 0.1302123666 0.8400710225 521 20.8000000000 1.6035809517 0.8136616509 1.6094850302 0.0140542228 0.0105920000 881474929 0 402718720 0.0791349337 0.1297246069 0.8407000303 522 20.8400000000 1.6039013863 0.8151755201 1.6094850302 0.0140523702 0.0105760000 881477177 0 402718720 0.0787229091 0.1295037866 0.8407534361 523 20.8800000000 1.5998798609 0.8166759108 1.6094850302 0.0140511002 0.0185350000 881479425 0 402718720 0.0785994381 0.1294900030 0.8396654725 524 20.9200000000 1.5992044210 0.8181692858 1.6094850302 0.0140641473 0.0109540000 881481673 0 402718720 0.0782530606 0.1293199956 0.8395091891 525 20.9600000000 1.5996541977 0.8196578285 1.6094850302 0.0140608203 0.0099680000 881483921 0 402718720 0.0775657669 0.1289437264 0.8394764662 526 21.0000000000 1.5976834297 0.8211369646 1.6094850302 0.0140529372 0.0100620000 881486169 0 402718720 0.0771460161 0.1288517267 0.8388694525 527 21.0400000000 1.5948452950 0.8226051019 1.6094850302 0.0140490146 0.0097730000 881488417 0 402718720 0.0766138434 0.1287111342 0.8380756378 528 21.0800000000 1.5954215527 0.8240687694 1.6094850302 0.0140476713 0.0099350000 881490665 0 402718720 0.0758619308 0.1282487661 0.8379948139 529 21.1200000000 1.5944944620 0.8255251507 1.6094850302 0.0140419161 0.0101540000 881492913 0 402718720 0.0750391558 0.1279930323 0.8375920653 530 21.1600000000 1.5914236307 0.8269702422 1.6094850302 0.0140314997 0.0099700000 881495161 0 402718720 0.0746779516 0.1278339773 0.8367684484 531 21.2000000000 1.5895649195 0.8284063903 1.6094850302 0.0140223483 0.0098290000 881497409 0 402718720 0.0740586072 0.1275410056 0.8361755013 532 21.2400000000 1.5887638330 0.8298356336 1.6094850302 0.0140170776 0.0106440000 881499657 0 402718720 0.0732092187 0.1273917407 0.8357625604 533 21.2800000000 1.5874484777 0.8312570461 1.6094850302 0.0140095376 0.0101900000 881501905 0 402718720 0.0725176707 0.1271235943 0.8351843357 534 21.3200000000 1.5864957571 0.8326713508 1.6094850302 0.0140064720 0.0103730000 881504153 0 402718720 0.0717479810 0.1268401295 0.8348817229 535 21.3600000000 1.5872540474 0.8340817857 1.6094850302 0.0139978560 0.0111450000 881506401 0 402718720 0.0707897842 0.1263850182 0.8346483707 536 21.4000000000 1.5855423212 0.8354837644 1.6094850302 0.0139868612 0.0108450000 881508649 0 402718720 0.0700682402 0.1259863824 0.8340035081 537 21.4400000000 1.5828753710 0.8368755551 1.6094850302 0.0139744313 0.0108500000 881510897 0 402718720 0.0691020489 0.1256924272 0.8329015970 538 21.4800000000 1.5808323622 0.8382583744 1.6094850302 0.0139623607 0.0109480000 881513145 0 402718720 0.0682629496 0.1255362034 0.8321633339 539 21.5200000000 1.5798730850 0.8396342830 1.6094850302 0.0139532394 0.0796740000 893824537 0 402718720 0.0671734661 0.1253827065 0.8314965367 540 21.5600000000 1.5692470074 0.8409854176 1.6094850302 0.0147224999 0.0140110000 897485993 0 402718720 0.0562419035 0.1319458187 0.8383672237 541 21.6000000000 1.5688054562 0.8423307412 1.6094850302 0.0147136838 0.0121120000 900680433 0 402718720 0.0555541366 0.1316167712 0.8380542994 542 21.6400000000 1.5683130026 0.8436701918 1.6094850302 0.0147125985 0.0108500000 900682681 0 402718720 0.0548870005 0.1312662512 0.8377677202 543 21.6800000000 1.5663667917 0.8450011248 1.6094850302 0.0147093641 0.0108600000 900684929 0 402718720 0.0542544350 0.1307581067 0.8371871710 544 21.7200000000 1.5593183041 0.8463142079 1.6094850302 0.0147518973 0.0273840000 900687177 0 402718720 0.0531928055 0.1301034540 0.8354665041 545 21.7600000000 1.5555214882 0.8476155056 1.6094850302 0.0147453384 0.0188380000 900689425 0 402718720 0.0527408980 0.1299904138 0.8343794346 546 21.8000000000 1.5523875952 0.8489062970 1.6094850302 0.0147356555 0.0121280000 900691673 0 402718720 0.0522659570 0.1295399219 0.8334329724 547 21.8400000000 1.5494158268 0.8501869360 1.6094850302 0.0147347082 0.0101320000 900693921 0 402718720 0.0514942706 0.1293924004 0.8326349854 548 21.8800000000 1.5461006165 0.8514568515 1.6094850302 0.0147334282 0.0105720000 900696169 0 402718720 0.0511746891 0.1292393506 0.8313751221 549 21.9200000000 1.5431919098 0.8527168425 1.6094850302 0.0147209954 16.9930800000 913007641 0 402718720 0.0507337674 0.1292207390 0.8302677870 550 21.9600000000 1.5405751467 0.8539674939 1.6094850302 0.0148270968 0.0131380000 916669097 0 402718720 0.0468340665 0.1301502287 0.8288861513 551 22.0000000000 1.5360962152 0.8552054771 1.6094850302 0.0148284081 0.0112300000 919863537 0 402718720 0.0461868495 0.1301505864 0.8278304338 552 22.0400000000 1.5315928459 0.8564308165 1.6094850302 0.0148301072 0.0107440000 919865785 0 402718720 0.0460620970 0.1302406490 0.8262165189 553 22.0800000000 1.5283035040 0.8576457762 1.6094850302 0.0148212524 0.0111690000 919868033 0 402718720 0.0457177423 0.1294759065 0.8252841234 554 22.1200000000 1.5253043175 0.8588509360 1.6094850302 0.0148114679 0.0374790000 919870281 0 402718720 0.0449959822 0.1291202009 0.8244907856 555 22.1600000000 1.5209740400 0.8600439506 1.6094850302 0.0148000063 0.0167460000 919872529 0 402718720 0.0446018465 0.1290180087 0.8233867884 556 22.2000000000 1.5174219608 0.8612262852 1.6094850302 0.0147911753 0.0109490000 919874777 0 402718720 0.0440102071 0.1287695915 0.8225464821 557 22.2400000000 1.5131617785 0.8623967259 1.6094850302 0.0148185537 0.3159990000 932189461 0 402718720 0.0438551940 0.1261538118 0.8218573928 558 22.2800000000 1.5092402697 0.8635559437 1.6094850302 0.0149175572 0.0125000000 935850917 0 402718720 0.0450312383 0.1211512461 0.8215766549 559 22.3200000000 1.5046672821 0.8647028334 1.6094850302 0.0149179150 0.0112060000 939045357 0 402718720 0.0442385413 0.1217053309 0.8205234408 560 22.3600000000 1.4982391596 0.8658341483 1.6094850302 0.0149133833 0.0109070000 939047605 0 402718720 0.0437225886 0.1210731044 0.8195030689 561 22.4000000000 1.4932240248 0.8669524903 1.6094850302 0.0149036151 0.0111150000 939049853 0 402718720 0.0433269106 0.1206689924 0.8184957504 562 22.4400000000 1.4907165766 0.8680623908 1.6094850302 0.0149082727 0.0100290000 939052101 0 402718720 0.0422629826 0.1203454882 0.8179191947 563 22.4800000000 1.4861701727 0.8691602732 1.6094850302 0.0149042707 0.0102040000 939054349 0 402718720 0.0419375785 0.1200223491 0.8170732856 564 22.5200000000 1.4810122252 0.8702451171 1.6094850302 0.0149008278 0.0090440000 939056597 0 402718720 0.0412352718 0.1209247708 0.8159338832 565 22.5600000000 1.4714372158 0.8713091739 1.6094850302 0.0148936574 0.0783700000 951363573 0 402718720 0.0413408652 0.1199484691 0.8136096597 566 22.6000000000 1.4687855244 0.8723647858 1.6094850302 0.0149493636 0.0120570000 955025029 0 402718720 0.0389602259 0.1193795502 0.8099613786 567 22.6400000000 1.4636335373 0.8734075878 1.6094850302 0.0149466125 0.0095780000 958219469 0 402718720 0.0382853113 0.1195271090 0.8090841174 568 22.6800000000 1.4581339359 0.8744370356 1.6094850302 0.0149427873 0.0092130000 958221717 0 402718720 0.0377114750 0.1204008535 0.8079919815 569 22.7200000000 1.4518196583 0.8754517678 1.6094850302 0.0149353789 0.0217130000 969085853 0 402718720 0.0377114750 0.1204008535 0.8079919815 570 22.7600000000 1.4409387112 0.8764438502 1.6094850302 0.0159551207 0.0496380000 972433701 0 402718720 0.0467490517 0.1272857338 0.8163583279 571 22.8000000000 1.4313281775 0.8774156266 1.6094850302 0.0161244388 0.0130210000 961574765 0 402718720 0.0467028841 0.1274006367 0.8198021054 572 22.8400000000 1.4229328632 0.8783693281 1.6094850302 0.0162262602 0.0130360000 961577013 0 402718720 0.0476997383 0.1276656836 0.8220064044 573 22.8800000000 1.4193711281 0.8793134848 1.6094850302 0.0162372886 0.0126610000 961579261 0 402718720 0.0498321317 0.1275232881 0.8216064572 574 22.9200000000 1.4146739244 0.8802461685 1.6094850302 0.0162585101 0.0123050000 961581509 0 402718720 0.0494825542 0.1268563867 0.8207606673 575 22.9600000000 1.4055473804 0.8811597358 1.6094850302 0.0163593376 0.0127540000 961583757 0 402718720 0.0465517789 0.1266430169 0.8221079707 576 23.0000000000 1.3976832628 0.8820564780 1.6094850302 0.0165019120 0.0129170000 961586005 0 402718720 0.0434558913 0.1263259202 0.8241862059 577 23.0400000000 1.3892261982 0.8829354550 1.6094850302 0.0166036260 0.0123350000 961588253 0 402718720 0.0409022085 0.1239931211 0.8261904716 578 23.0800000000 1.3802045584 0.8837957822 1.6094850302 0.0167221935 0.0123130000 961591013 0 402718720 0.0384950154 0.1235548332 0.8281319141 579 23.1200000000 1.3697681427 0.8846351127 1.6094850302 0.0168544580 0.0124020000 961592749 0 402718720 0.0362731218 0.1229117960 0.8301573992 580 23.1600000000 1.3590558767 0.8854530795 1.6094850302 0.0170063893 0.0222000000 961594997 0 402718720 0.0331582502 0.1211499199 0.8337839842 581 23.2000000000 1.3522921801 0.8862565892 1.6094850302 0.0170628284 0.0137470000 961597245 0 402718720 0.0327070355 0.1204281673 0.8360778093 582 23.2400000000 1.3447637558 0.8870444022 1.6094850302 0.0171738514 0.0199860000 965088305 0 402718720 0.0303583164 0.1192177907 0.8389671445 583 23.2800000000 1.3389328718 0.8878195110 1.6094850302 0.0171696598 0.0229470000 972541761 0 402718720 0.0303583164 0.1192177907 0.8389671445 584 23.3200000000 1.3335763216 0.8885827932 1.6094850302 0.0171644645 0.0218460000 972740689 0 402718720 0.0303583164 0.1192177907 0.8389671445 585 23.3600000000 1.3287539482 0.8893352226 1.6094850302 0.0171578647 0.0206300000 972742697 0 402718720 0.0303583164 0.1192177907 0.8389671445 586 23.4000000000 1.3239721060 0.8900769237 1.6094850302 0.0171518564 0.0206280000 972744705 0 402718720 0.0303583164 0.1192177907 0.8389671445 587 23.4400000000 1.3196591139 0.8908087503 1.6094850302 0.0171496955 0.0209210000 972746713 0 402718720 0.0303583164 0.1192177907 0.8389671445 588 23.4800000000 1.3154495955 0.8915309286 1.6094850302 0.0171460265 0.0202480000 972748721 0 402718720 0.0303583164 0.1192177907 0.8389671445 589 23.5200000000 1.3104498386 0.8922421661 1.6094850302 0.0171388242 0.0187950000 972750729 0 402718720 0.0303583164 0.1192177907 0.8389671445 590 23.5600000000 1.3054045439 0.8929424414 1.6094850302 0.0171290598 0.0202410000 972752737 0 402718720 0.0303583164 0.1192177907 0.8389671445 591 23.6000000000 1.3008546829 0.8936326482 1.6094850302 0.0171180095 0.0481000000 972754745 0 402718720 0.0303583164 0.1192177907 0.8389671445 592 23.6400000000 1.2957401276 0.8943118838 1.6094850302 0.0171054583 0.0198240000 972756753 0 402718720 0.0303583164 0.1192177907 0.8389671445 593 23.6800000000 1.2908914089 0.8949806520 1.6094850302 0.0170954873 0.0199380000 972758761 0 402718720 0.0303583164 0.1192177907 0.8389671445 594 23.7200000000 1.2867039442 0.8956401188 1.6094850302 0.0170963166 0.0198760000 972760769 0 402718720 0.0303583164 0.1192177907 0.8389671445 595 23.7600000000 1.2824541330 0.8962902264 1.6094850302 0.0170995141 0.0193140000 972762777 0 402718720 0.0303583164 0.1192177907 0.8389671445 596 23.8000000000 1.3717951775 0.8970880535 1.6094850302 0.0781013338 0.0255750000 972764785 0 402718720 0.1299878508 0.1566082686 0.7764849663 597 23.8400000000 1.3699995279 0.8978802000 1.6094850302 0.0780503039 0.0463570000 961903537 0 402718720 0.1325477064 0.1593287438 0.7734044194 598 23.8800000000 1.3685781956 0.8986673204 1.6094850302 0.0779861041 0.0458950000 961905785 0 402718720 0.1360652149 0.1578703523 0.7729856968 599 23.9200000000 1.3670533895 0.8994492671 1.6094850302 0.0779212783 0.0449990000 961908033 0 402718720 0.1398436427 0.1565401405 0.7722547650 600 23.9600000000 1.3643974066 0.9002241807 1.6094850302 0.0778593692 0.0469110000 961910281 0 402718720 0.1444601715 0.1561893970 0.7727607489 601 24.0000000000 1.3617792130 0.9009921591 1.6094850302 0.0777971778 0.0481730000 961912529 0 402718720 0.1475272030 0.1572971940 0.7730869651 602 24.0400000000 1.3547086716 0.9017458410 1.6094850302 0.0777362110 0.0395010000 965404269 0 402718720 0.1511131972 0.1582720578 0.7749734521 603 24.0800000000 1.3524004221 0.9024931952 1.6094850302 0.0776733666 0.0407940000 972780901 0 402718720 0.1511131972 0.1582720578 0.7749734521 604 24.1200000000 1.3507095575 0.9032352753 1.6094850302 0.0776118909 0.0174470000 976008653 0 402718720 0.1511131972 0.1582720578 0.7749734521 605 24.1600000000 1.3468879461 0.9039685855 1.6094850302 0.0775502463 0.0098700000 976087485 0 402718720 0.1511131972 0.1582720578 0.7749734521 606 24.2000000000 1.3423434496 0.9046919763 1.6094850302 0.0774878943 0.0112980000 976166317 0 402718720 0.1511131972 0.1582720578 0.7749734521 607 24.2400000000 1.3385120630 0.9054066717 1.6094850302 0.0774250820 0.0117230000 976245149 0 402718720 0.1511131972 0.1582720578 0.7749734521 608 24.2800000000 1.3349540234 0.9061131641 1.6094850302 0.0773620423 0.0113430000 976323981 0 402718720 0.1511131972 0.1582720578 0.7749734521 609 24.3200000000 1.3323905468 0.9068131269 1.6094850302 0.0772992902 0.0117750000 976402813 0 402718720 0.1511131972 0.1582720578 0.7749734521 610 24.3600000000 1.3281302452 0.9075038107 1.6094850302 0.0772369205 0.0123330000 976481645 0 402718720 0.1511131972 0.1582720578 0.7749734521 611 24.4000000000 1.3235586882 0.9081847516 1.6094850302 0.0771747529 0.0103830000 976560477 0 402718720 0.1511131972 0.1582720578 0.7749734521 612 24.4400000000 1.3199737072 0.9088576094 1.6094850302 0.0771128069 0.0098040000 976639309 0 402718720 0.1511131972 0.1582720578 0.7749734521 613 24.4800000000 1.3164201975 0.9095224749 1.6094850302 0.0770507551 0.0191880000 976718141 0 402718720 0.1511131972 0.1582720578 0.7749734521 614 24.5200000000 1.3137793541 0.9101808737 1.6094850302 0.0769899950 0.0118830000 976796973 0 402718720 0.1511131972 0.1582720578 0.7749734521 615 24.5600000000 1.3097885847 0.9108306424 1.6094850302 0.0769287008 0.0102170000 976875805 0 402718720 0.1511131972 0.1582720578 0.7749734521 616 24.6000000000 1.3063621521 0.9114727390 1.6094850302 0.0768668222 0.0102460000 976954637 0 402718720 0.1511131972 0.1582720578 0.7749734521 617 24.6400000000 1.3030930758 0.9121074559 1.6094850302 0.0768048853 0.0104540000 977033469 0 402718720 0.1511131972 0.1582720578 0.7749734521 618 24.6800000000 1.2985163927 0.9127327131 1.6094850302 0.0767431134 0.0108000000 977112301 0 402718720 0.1511131972 0.1582720578 0.7749734521 619 24.7200000000 1.2944369316 0.9133493596 1.6094850302 0.0766815261 0.0114080000 977191133 0 402718720 0.1511131972 0.1582720578 0.7749734521 620 24.7600000000 1.2865101099 0.9139512318 1.6094850302 0.0766226161 0.0097790000 977269965 0 402718720 0.1511131972 0.1582720578 0.7749734521 621 24.8000000000 1.2826193571 0.9145449003 1.6094850302 0.0765619462 0.0105910000 977348797 0 402718720 0.1511131972 0.1582720578 0.7749734521 622 24.8400000000 1.2789919376 0.9151308280 1.6094850302 0.0765009160 0.0106030000 977427629 0 402718720 0.1511131972 0.1582720578 0.7749734521 623 24.8800000000 1.2750924826 0.9157086156 1.6094850302 0.0764399626 0.0213460000 977506461 0 402718720 0.1511131972 0.1582720578 0.7749734521 624 24.9200000000 1.2712568045 0.9162784043 1.6094850302 0.0763789690 0.0131080000 977585293 0 402718720 0.1511131972 0.1582720578 0.7749734521 625 24.9600000000 1.2666079998 0.9168389317 1.6094850302 0.0763178148 0.0107920000 977664125 0 402718720 0.1511131972 0.1582720578 0.7749734521 626 25.0000000000 1.2629073858 0.9173917567 1.6094850302 0.0762569334 0.0095540000 977742957 0 402718720 0.1511131972 0.1582720578 0.7749734521 627 25.0400000000 1.2585620880 0.9179358880 1.6094850302 0.0761966326 0.0102800000 977821789 0 402718720 0.1511131972 0.1582720578 0.7749734521 628 25.0800000000 1.2544679642 0.9184717671 1.6094850302 0.0761364084 0.0101360000 977900621 0 402718720 0.1511131972 0.1582720578 0.7749734521 629 25.1200000000 1.2496423721 0.9189982705 1.6094850302 0.0760767250 0.0095470000 977979453 0 402718720 0.1511131972 0.1582720578 0.7749734521 630 25.1600000000 1.2450376749 0.9195157933 1.6094850302 0.0760173733 0.0100270000 978058285 0 402718720 0.1511131972 0.1582720578 0.7749734521 631 25.2000000000 1.2397180796 0.9200232454 1.6094850302 0.0759580199 0.0099820000 978137117 0 402718720 0.1511131972 0.1582720578 0.7749734521 632 25.2400000000 1.2349654436 0.9205215717 1.6094850302 0.0758995730 0.0090960000 978215949 0 402718720 0.1511131972 0.1582720578 0.7749734521 633 25.2800000000 1.2305052280 0.9210112773 1.6094850302 0.0758415928 0.0091220000 978294781 0 402718720 0.1511131972 0.1582720578 0.7749734521 634 25.3200000000 1.2252724171 0.9214911845 1.6094850302 0.0757838028 0.0092110000 978373613 0 402718720 0.1511131972 0.1582720578 0.7749734521 635 25.3600000000 1.2197358608 0.9219608611 1.6094850302 0.0757247625 0.0192300000 978452445 0 402718720 0.1511131972 0.1582720578 0.7749734521 636 25.4000000000 1.2162171602 0.9224235283 1.6094850302 0.0756668487 0.0102600000 978531277 0 402718720 0.1511131972 0.1582720578 0.7749734521 637 25.4400000000 1.2127275467 0.9228792646 1.6094850302 0.0756092393 0.0089970000 978610109 0 402718720 0.1511131972 0.1582720578 0.7749734521 638 25.4800000000 1.2062425613 0.9233234077 1.6094850302 0.0755510438 0.0102580000 978612117 0 402718720 0.1511131972 0.1582720578 0.7749734521 639 25.5200000000 1.2014765739 0.9237587021 1.6094850302 0.0754926618 0.0097780000 978614125 0 402718720 0.1511131972 0.1582720578 0.7749734521 640 25.5600000000 1.1960568428 0.9241841680 1.6094850302 0.0754351277 0.0095700000 978692957 0 402718720 0.1511131972 0.1582720578 0.7749734521 641 25.6000000000 1.1903703213 0.9245994350 1.6094850302 0.0753770717 0.0200630000 978771789 0 402718720 0.1511131972 0.1582720578 0.7749734521 642 25.6400000000 1.1847969294 0.9250047270 1.6094850302 0.0753191582 0.0112100000 978850621 0 402718720 0.1511131972 0.1582720578 0.7749734521 643 25.6800000000 1.1790851355 0.9253998754 1.6094850302 0.0752616636 0.0094740000 978852629 0 402718720 0.1511131972 0.1582720578 0.7749734521 644 25.7200000000 1.1744165421 0.9257865473 1.6094850302 0.0752035282 0.0093500000 978854637 0 402718720 0.1511131972 0.1582720578 0.7749734521 645 25.7600000000 1.1704719067 0.9261659044 1.6094850302 0.0751454987 0.0095320000 978933469 0 402718720 0.1511131972 0.1582720578 0.7749734521 646 25.8000000000 1.1649607420 0.9265355559 1.6094850302 0.0750879281 0.0082300000 979012301 0 402718720 0.1511131972 0.1582720578 0.7749734521 647 25.8400000000 1.1596070528 0.9268957900 1.6094850302 0.0750302949 0.0176030000 979014309 0 402718720 0.1511131972 0.1582720578 0.7749734521 648 25.8800000000 1.1542518139 0.9272466481 1.6094850302 0.0749726407 0.0093320000 979093141 0 402718720 0.1511131972 0.1582720578 0.7749734521 649 25.9200000000 1.1502573490 0.9275902701 1.6094850302 0.0749147996 0.0086790000 979171973 0 402718720 0.1511131972 0.1582720578 0.7749734521 650 25.9600000000 1.1461207867 0.9279264709 1.6094850302 0.0748575420 0.0088070000 979250805 0 402718720 0.1511131972 0.1582720578 0.7749734521 651 26.0000000000 1.1418830156 0.9282551292 1.6094850302 0.0748011559 0.0079840000 979329637 0 402718720 0.1511131972 0.1582720578 0.7749734521 652 26.0400000000 1.1369309425 0.9285751841 1.6094850302 0.0747442691 0.0085090000 979408469 0 402718720 0.1511131972 0.1582720578 0.7749734521 653 26.0800000000 1.1334460974 0.9288889221 1.6094850302 0.0746876593 0.0077650000 979487301 0 402718720 0.1511131972 0.1582720578 0.7749734521 654 26.1200000000 1.1297208071 0.9291960045 1.6094850302 0.0746317045 0.0079980000 979566133 0 402718720 0.1511131972 0.1582720578 0.7749734521 655 26.1600000000 1.1261677742 0.9294967248 1.6094850302 0.0745757489 0.0076430000 979644965 0 402718720 0.1511131972 0.1582720578 0.7749734521 656 26.2000000000 1.1233646870 0.9297922552 1.6094850302 0.0745191715 0.0063460000 979646973 0 402718720 0.1511131972 0.1582720578 0.7749734521 657 26.2400000000 1.1213424206 0.9300838080 1.6094850302 0.0744629488 0.0065370000 979725805 0 402718720 0.1511131972 0.1582720578 0.7749734521 658 26.2800000000 1.1179401875 0.9303693040 1.6094850302 0.0744069875 0.0194420000 979804637 0 402718720 0.1511131972 0.1582720578 0.7749734521 659 26.3200000000 1.1152915955 0.9306499144 1.6094850302 0.0743506136 0.0064200000 979883469 0 402718720 0.1511131972 0.1582720578 0.7749734521 660 26.3600000000 1.1120730639 0.9309247980 1.6094850302 0.0742943297 0.0062120000 979962301 0 402718720 0.1511131972 0.1582720578 0.7749734521 661 26.4000000000 1.1094383001 0.9311948638 1.6094850302 0.0742381146 0.0069140000 980041133 0 402718720 0.1511131972 0.1582720578 0.7749734521 662 26.4400000000 1.1077979803 0.9314616359 1.6094850302 0.0741820555 0.0111250000 980119965 0 402718720 0.1511131972 0.1582720578 0.7749734521 663 26.4800000000 1.1056541204 0.9317243697 1.6094850302 0.0741260964 0.0065240000 980198797 0 402718720 0.1511131972 0.1582720578 0.7749734521 664 26.5200000000 1.1034417152 0.9319829801 1.6094850302 0.0740706837 0.0063140000 980277629 0 402718720 0.1511131972 0.1582720578 0.7749734521 665 26.5600000000 1.0991826057 0.9322344081 1.6094850302 0.0740153333 0.0139650000 980279637 0 402718720 0.1511131972 0.1582720578 0.7749734521 666 26.6000000000 1.0973012447 0.9324822562 1.6094850302 0.0739598336 0.0069580000 980358469 0 402718720 0.1511131972 0.1582720578 0.7749734521 667 26.6400000000 1.0949717760 0.9327258687 1.6094850302 0.0739043508 0.0068400000 980437301 0 402718720 0.1511131972 0.1582720578 0.7749734521 668 26.6800000000 1.0939841270 0.9329672733 1.6094850302 0.0738492538 0.0069610000 980516133 0 402718720 0.1511131972 0.1582720578 0.7749734521 669 26.7200000000 1.0916901827 0.9332045273 1.6094850302 0.0737943720 0.0184370000 980594965 0 402718720 0.1511131972 0.1582720578 0.7749734521 670 26.7600000000 1.0892052650 0.9334373642 1.6094850302 0.0737396262 0.0067410000 980673797 0 402718720 0.1511131972 0.1582720578 0.7749734521 671 26.8000000000 1.0890264511 0.9336692406 1.6094850302 0.0736848156 0.0061760000 980752629 0 402718720 0.1511131972 0.1582720578 0.7749734521 672 26.8400000000 1.0886723995 0.9338999001 1.6094850302 0.0736302456 0.0129560000 980831461 0 402718720 0.1511131972 0.1582720578 0.7749734521 673 26.8800000000 1.0873051882 0.9341278426 1.6094850302 0.0735767822 0.0087670000 980910293 0 402718720 0.1511131972 0.1582720578 0.7749734521 674 26.9200000000 1.0838862658 0.9343500361 1.6094850302 0.0735230032 0.0066750000 980989125 0 402718720 0.1511131972 0.1582720578 0.7749734521 675 26.9600000000 1.0809693336 0.9345672498 1.6094850302 0.0734696233 0.0064520000 981067957 0 402718720 0.1511131972 0.1582720578 0.7749734521 676 27.0000000000 1.0798178911 0.9347821176 1.6094850302 0.0734164313 0.0062660000 981146789 0 402718720 0.1511131972 0.1582720578 0.7749734521 677 27.0400000000 1.0790759325 0.9349952547 1.6094850302 0.0733636781 0.0237340000 981225621 0 402718720 0.1511131972 0.1582720578 0.7749734521 678 27.0800000000 1.0784388781 0.9352068235 1.6094850302 0.0733108320 0.0100390000 981304453 0 402718720 0.1511131972 0.1582720578 0.7749734521 679 27.1200000000 1.0776625872 0.9354166258 1.6094850302 0.0732590049 0.0076890000 981383285 0 402718720 0.1511131972 0.1582720578 0.7749734521 680 27.1600000000 1.0774468184 0.9356254937 1.6094850302 0.0732065279 0.0067770000 981462117 0 402718720 0.1511131972 0.1582720578 0.7749734521 681 27.2000000000 1.0770999193 0.9358332389 1.6094850302 0.0731534439 0.0062250000 981540949 0 402718720 0.1511131972 0.1582720578 0.7749734521 682 27.2400000000 1.0774496794 0.9360408876 1.6094850302 0.0730999142 0.0058820000 981619781 0 402718720 0.1511131972 0.1582720578 0.7749734521 683 27.2800000000 1.0791511536 0.9362504195 1.6094850302 0.0730464747 0.0154630000 981698613 0 402718720 0.1511131972 0.1582720578 0.7749734521 684 27.3200000000 1.0774654150 0.9364568741 1.6094850302 0.0729946082 0.0089320000 981777445 0 402718720 0.1511131972 0.1582720578 0.7749734521 685 27.3600000000 1.0753165483 0.9366595890 1.6094850302 0.0729415385 0.0070160000 981856277 0 402718720 0.1511131972 0.1582720578 0.7749734521 686 27.4000000000 1.0776705742 0.9368651444 1.6094850302 0.0728887081 0.0057150000 981858285 0 402718720 0.1511131972 0.1582720578 0.7749734521 687 27.4400000000 1.0787755251 0.9370717097 1.6094850302 0.0728365234 0.0145970000 981860293 0 402718720 0.1511131972 0.1582720578 0.7749734521 688 27.4800000000 1.0788756609 0.9372778201 1.6094850302 0.0727838536 0.0093440000 981939125 0 402718720 0.1511131972 0.1582720578 0.7749734521 689 27.5200000000 1.0811691284 0.9374866609 1.6094850302 0.0727312275 0.0070840000 982017957 0 402718720 0.1511131972 0.1582720578 0.7749734521 690 27.5600000000 1.0797311068 0.9376928123 1.6094850302 0.0726789028 0.0058250000 982096789 0 402718720 0.1511131972 0.1582720578 0.7749734521 691 27.6000000000 1.0795428753 0.9378980945 1.6094850302 0.0726262799 0.0060180000 982175621 0 402718720 0.1511131972 0.1582720578 0.7749734521 692 27.6400000000 1.0797880888 0.9381031379 1.6094850302 0.0725740453 0.0058380000 982254453 0 402718720 0.1511131972 0.1582720578 0.7749734521 693 27.6800000000 1.0798593760 0.9383076923 1.6094850302 0.0725224452 0.0214710000 982333285 0 402718720 0.1511131972 0.1582720578 0.7749734521 694 27.7200000000 1.0798202753 0.9385116010 1.6094850302 0.0724711318 0.0098850000 982412117 0 402718720 0.1511131972 0.1582720578 0.7749734521 695 27.7600000000 1.0804226398 0.9387157895 1.6094850302 0.0724208373 0.0075880000 982490949 0 402718720 0.1511131972 0.1582720578 0.7749734521 696 27.8000000000 1.0810446739 0.9389202850 1.6094850302 0.0723708955 0.0063470000 982569781 0 402718720 0.1511131972 0.1582720578 0.7749734521 697 27.8400000000 1.0824357271 0.9391261895 1.6094850302 0.0723276100 0.0059850000 982648613 0 402718720 0.1511131972 0.1582720578 0.7749734521 698 27.8800000000 1.0816004276 0.9393303074 1.6094850302 0.0722773082 0.0130410000 982727445 0 402718720 0.1511131972 0.1582720578 0.7749734521 699 27.9200000000 1.0830931664 0.9395359767 1.6094850302 0.0722264526 0.0083880000 982806277 0 402718720 0.1511131972 0.1582720578 0.7749734521 700 27.9600000000 1.0828346014 0.9397406890 1.6094850302 0.0721780853 0.0061900000 982885109 0 402718720 0.1511131972 0.1582720578 0.7749734521 701 28.0000000000 1.0803785324 0.9399413136 1.6094850302 0.0721293192 0.0060150000 982963941 0 402718720 0.1511131972 0.1582720578 0.7749734521 702 28.0400000000 1.0797588825 0.9401404839 1.6094850302 0.0720798617 0.0058390000 983042773 0 402718720 0.1511131972 0.1582720578 0.7749734521 703 28.0800000000 1.0824491978 0.9403429145 1.6094850302 0.0720306887 0.0054530000 983121605 0 402718720 0.1511131972 0.1582720578 0.7749734521 704 28.1200000000 1.0815826654 0.9405435392 1.6094850302 0.0719823736 0.0055720000 983200437 0 402718720 0.1511131972 0.1582720578 0.7749734521 705 28.1600000000 1.0818500519 0.9407439740 1.6094850302 0.0719331972 0.0054980000 983279269 0 402718720 0.1511131972 0.1582720578 0.7749734521 706 28.2000000000 1.0825015306 0.9409447637 1.6094850302 0.0718838691 0.0057130000 983358101 0 402718720 0.1511131972 0.1582720578 0.7749734521 707 28.2400000000 1.0827739239 0.9411453707 1.6094850302 0.0718335470 0.0056690000 983436933 0 402718720 0.1511131972 0.1582720578 0.7749734521 708 28.2800000000 1.0861601830 0.9413501939 1.6094850302 0.0717831779 0.0237240000 983515765 0 402718720 0.1511131972 0.1582720578 0.7749734521 709 28.3200000000 1.0871846676 0.9415558843 1.6094850302 0.0717359461 0.0101140000 983594597 0 402718720 0.1511131972 0.1582720578 0.7749734521 710 28.3600000000 1.0848039389 0.9417576421 1.6094850302 0.0716872891 0.0074860000 983673429 0 402718720 0.1511131972 0.1582720578 0.7749734521 711 28.4000000000 1.0869020224 0.9419617833 1.6094850302 0.0716378445 0.0060200000 983752261 0 402718720 0.1511131972 0.1582720578 0.7749734521 712 28.4400000000 1.0880748034 0.9421669982 1.6094850302 0.0715885050 0.0057570000 983831093 0 402718720 0.1511131972 0.1582720578 0.7749734521 713 28.4800000000 1.0873502493 0.9423706213 1.6094850302 0.0715390593 0.0058840000 983909925 0 402718720 0.1511131972 0.1582720578 0.7749734521 714 28.5200000000 1.0891269445 0.9425761623 1.6094850302 0.0714889475 0.0145090000 983988757 0 402718720 0.1511131972 0.1582720578 0.7749734521 715 28.5600000000 1.0924059153 0.9427857144 1.6094850302 0.0714392061 0.0056760000 984067589 0 402718720 0.1511131972 0.1582720578 0.7749734521 716 28.6000000000 1.0940937996 0.9429970386 1.6094850302 0.0713897564 0.0057810000 984146421 0 402718720 0.1511131972 0.1582720578 0.7749734521 717 28.6400000000 1.0939328671 0.9432075488 1.6094850302 0.0713422795 0.0055670000 984225253 0 402718720 0.1511131972 0.1582720578 0.7749734521 718 28.6800000000 1.0957634449 0.9434200222 1.6094850302 0.0712930064 0.0152540000 984304085 0 402718720 0.1511131972 0.1582720578 0.7749734521 719 28.7200000000 1.1004141569 0.9436383729 1.6094850302 0.0712436344 0.0055510000 984382917 0 402718720 0.1511131972 0.1582720578 0.7749734521 720 28.7600000000 1.1040859222 0.9438612167 1.6094850302 0.0711942337 0.0129300000 984461749 0 402718720 0.1511131972 0.1582720578 0.7749734521 721 28.8000000000 1.1047935486 0.9440844238 1.6094850302 0.0711448668 0.0079890000 984540581 0 402718720 0.1511131972 0.1582720578 0.7749734521 722 28.8400000000 1.1124889851 0.9443176711 1.6094850302 0.0710971022 0.0060650000 984619413 0 402718720 0.1511131972 0.1582720578 0.7749734521 723 28.8800000000 1.1203459501 0.9445611404 1.6094850302 0.0710485269 0.0053930000 984698245 0 402718720 0.1511131972 0.1582720578 0.7749734521 724 28.9200000000 1.1251525879 0.9448105761 1.6094850302 0.0709997929 0.0053970000 984777077 0 402718720 0.1511131972 0.1582720578 0.7749734521 725 28.9600000000 1.1318629980 0.9450685794 1.6094850302 0.0709516381 0.0053770000 984855909 0 402718720 0.1511131972 0.1582720578 0.7749734521 726 29.0000000000 1.1373771429 0.9453334672 1.6094850302 0.0709036069 0.0054890000 984934741 0 402718720 0.1511131972 0.1582720578 0.7749734521 727 29.0400000000 1.1521370411 0.9456179288 1.6094850302 0.0708578244 0.0054990000 985013573 0 402718720 0.1511131972 0.1582720578 0.7749734521 728 29.0800000000 1.1661189795 0.9459208149 1.6094850302 0.0708106928 0.0054670000 985092405 0 402718720 0.1511131972 0.1582720578 0.7749734521 729 29.1200000000 1.1712474823 0.9462299050 1.6094850302 0.0707655257 0.0058300000 985171237 0 402718720 0.1511131972 0.1582720578 0.7749734521 730 29.1600000000 1.1761939526 0.9465449242 1.6094850302 0.0707180944 0.0153150000 985250069 0 402718720 0.1511131972 0.1582720578 0.7749734521 731 29.2000000000 1.1880443096 0.9468752927 1.6094850302 0.0706706030 0.0056640000 985328901 0 402718720 0.1511131972 0.1582720578 0.7749734521 732 29.2400000000 1.1962417364 0.9472159573 1.6094850302 0.0706232063 0.0057420000 985407733 0 402718720 0.1511131972 0.1582720578 0.7749734521 733 29.2800000000 1.2022558451 0.9475638971 1.6094850302 0.0705759963 0.0161370000 985486565 0 402718720 0.1511131972 0.1582720578 0.7749734521 734 29.3200000000 1.2134437561 0.9479261312 1.6094850302 0.0705294301 0.0056080000 985565397 0 402718720 0.1511131972 0.1582720578 0.7749734521 735 29.3600000000 1.2210253477 0.9482976948 1.6094850302 0.0704833291 0.0056400000 985644229 0 402718720 0.1511131972 0.1582720578 0.7749734521 736 29.4000000000 1.2259112597 0.9486748871 1.6094850302 0.0704364660 0.0141670000 985723061 0 402718720 0.1511131972 0.1582720578 0.7749734521 737 29.4400000000 1.2345147133 0.9490627295 1.6094850302 0.0703896438 0.0084240000 985801893 0 402718720 0.1511131972 0.1582720578 0.7749734521 738 29.4800000000 1.2422968149 0.9494600657 1.6094850302 0.0703434178 0.0062020000 985880725 0 402718720 0.1511131972 0.1582720578 0.7749734521 739 29.5200000000 1.2445964813 0.9498594383 1.6094850302 0.0702967331 0.0056120000 985959557 0 402718720 0.1511131972 0.1582720578 0.7749734521 740 29.5600000000 1.2497540712 0.9502647014 1.6094850302 0.0702495859 0.0055790000 986038389 0 402718720 0.1511131972 0.1582720578 0.7749734521 741 29.6000000000 1.2552742958 0.9506763202 1.6094850302 0.0702026037 0.0057290000 986117221 0 402718720 0.1511131972 0.1582720578 0.7749734521 742 29.6400000000 1.2608817816 0.9510943869 1.6094850302 0.0701557069 0.0057520000 986196053 0 402718720 0.1511131972 0.1582720578 0.7749734521 743 29.6800000000 1.2667611837 0.9515192413 1.6094850302 0.0701092239 0.0218540000 986274885 0 402718720 0.1511131972 0.1582720578 0.7749734521 744 29.7200000000 1.2756875753 0.9519549514 1.6094850302 0.0700627977 0.0098490000 986353717 0 402718720 0.1511131972 0.1582720578 0.7749734521 745 29.7600000000 1.2805100679 0.9523959650 1.6094850302 0.0700162891 0.0072270000 986432549 0 402718720 0.1511131972 0.1582720578 0.7749734521 746 29.8000000000 1.2879284620 0.9528457404 1.6094850302 0.0699704611 0.0059690000 986511381 0 402718720 0.1511131972 0.1582720578 0.7749734521 747 29.8400000000 1.2853115797 0.9532908085 1.6094850302 0.0699254929 0.0054830000 986590213 0 402718720 0.1511131972 0.1582720578 0.7749734521 748 29.8800000000 1.2844531536 0.9537335389 1.6094850302 0.0698787504 0.0139790000 986669045 0 402718720 0.1511131972 0.1582720578 0.7749734521 749 29.9200000000 1.2912116051 0.9541841104 1.6094850302 0.0698328445 0.0083610000 986747877 0 402718720 0.1511131972 0.1582720578 0.7749734521 750 29.9600000000 1.2978597879 0.9546423447 1.6094850302 0.0697871198 0.0065380000 986826709 0 402718720 0.1511131972 0.1582720578 0.7749734521 751 30.0000000000 1.3009783030 0.9551035111 1.6094850302 0.0697406918 0.0055440000 986905541 0 402718720 0.1511131972 0.1582720578 0.7749734521 752 30.0400000000 1.3047842979 0.9555685121 1.6094850302 0.0696945103 0.0199350000 986984373 0 402718720 0.1511131972 0.1582720578 0.7749734521 753 30.0800000000 1.3122557402 0.9560422003 1.6094850302 0.0696486688 0.0096600000 987063205 0 402718720 0.1511131972 0.1582720578 0.7749734521 754 30.1200000000 1.3132491112 0.9565159495 1.6094850302 0.0696031446 0.0070160000 987142037 0 402718720 0.1511131972 0.1582720578 0.7749734521 755 30.1600000000 1.3102464676 0.9569844668 1.6094850302 0.0695573486 0.0058510000 987220869 0 402718720 0.1511131972 0.1582720578 0.7749734521 756 30.2000000000 1.3151642084 0.9574582495 1.6094850302 0.0695115821 0.0055610000 987299701 0 402718720 0.1511131972 0.1582720578 0.7749734521 757 30.2400000000 1.3197141886 0.9579367910 1.6094850302 0.0694657994 0.0181380000 987378533 0 402718720 0.1511131972 0.1582720578 0.7749734521 758 30.2800000000 1.3245574236 0.9584204594 1.6094850302 0.0694202014 0.0091680000 987457365 0 402718720 0.1511131972 0.1582720578 0.7749734521 759 30.3200000000 1.3296014071 0.9589094989 1.6094850302 0.0693748193 0.0070500000 987536197 0 402718720 0.1511131972 0.1582720578 0.7749734521 760 30.3600000000 1.3286370039 0.9593959824 1.6094850302 0.0693300726 0.0058730000 987615029 0 402718720 0.1511131972 0.1582720578 0.7749734521 761 30.4000000000 1.3302315474 0.9598832828 1.6094850302 0.0692845632 0.0056720000 987693861 0 402718720 0.1511131972 0.1582720578 0.7749734521 762 30.4400000000 1.3363023996 0.9603772711 1.6094850302 0.0692393996 0.0055390000 987772693 0 402718720 0.1511131972 0.1582720578 0.7749734521 763 30.4800000000 1.3399317265 0.9608747213 1.6094850302 0.0691943573 0.0218880000 987851525 0 402718720 0.1511131972 0.1582720578 0.7749734521 764 30.5200000000 1.3417676687 0.9613732722 1.6094850302 0.0691491437 0.0082720000 987930357 0 402718720 0.1511131972 0.1582720578 0.7749734521 765 30.5600000000 1.3448836803 0.9618745930 1.6094850302 0.0691042378 0.0054520000 988009189 0 402718720 0.1511131972 0.1582720578 0.7749734521 766 30.6000000000 1.3422785997 0.9623712040 1.6094850302 0.0690600257 0.0055800000 988088021 0 402718720 0.1511131972 0.1582720578 0.7749734521 767 30.6400000000 1.3466032743 0.9628721585 1.6094850302 0.0690150784 0.0054430000 988166853 0 402718720 0.1511131972 0.1582720578 0.7749734521 768 30.6800000000 1.3504277468 0.9633767881 1.6094850302 0.0689703660 0.0055930000 988245685 0 402718720 0.1511131972 0.1582720578 0.7749734521 769 30.7200000000 1.3460514545 0.9638744145 1.6094850302 0.0689272409 0.0057280000 988324517 0 402718720 0.1511131972 0.1582720578 0.7749734521 770 30.7600000000 1.3486607075 0.9643741370 1.6094850302 0.0688826649 0.0214620000 988403349 0 402718720 0.1511131972 0.1582720578 0.7749734521 771 30.8000000000 1.3532061577 0.9648784586 1.6094850302 0.0688382664 0.0098690000 988482181 0 402718720 0.1511131972 0.1582720578 0.7749734521 772 30.8400000000 1.3503211737 0.9653777368 1.6094850302 0.0687943398 0.0072160000 988561013 0 402718720 0.1511131972 0.1582720578 0.7749734521 773 30.8800000000 1.3485057354 0.9658733745 1.6094850302 0.0687506170 0.0058940000 988639845 0 402718720 0.1511131972 0.1582720578 0.7749734521 774 30.9200000000 1.3542627096 0.9663751696 1.6094850302 0.0687087003 0.0057210000 988718677 0 402718720 0.1511131972 0.1582720578 0.7749734521 775 30.9600000000 1.3599067926 0.9668829523 1.6094850302 0.0686659471 0.0056970000 988797509 0 402718720 0.1511131972 0.1582720578 0.7749734521 776 31.0000000000 1.3641468287 0.9673948903 1.6094850302 0.0686225918 0.0154470000 988876341 0 402718720 0.1511131972 0.1582720578 0.7749734521 777 31.0400000000 1.3638207912 0.9679050909 1.6094850302 0.0685786066 0.0095470000 988955173 0 402718720 0.1511131972 0.1582720578 0.7749734521 778 31.0800000000 1.3681422472 0.9684195346 1.6094850302 0.0685353170 0.0071480000 989034005 0 402718720 0.1511131972 0.1582720578 0.7749734521 779 31.1200000000 1.3716776371 0.9689371958 1.6094850302 0.0684919356 0.0060530000 989112837 0 402718720 0.1511131972 0.1582720578 0.7749734521 780 31.1600000000 1.3755609989 0.9694585084 1.6094850302 0.0684492326 0.0063460000 989191669 0 402718720 0.1511131972 0.1582720578 0.7749734521 781 31.2000000000 1.3750854731 0.9699778771 1.6094850302 0.0684054158 0.0159420000 989270501 0 402718720 0.1511131972 0.1582720578 0.7749734521 782 31.2400000000 1.3748244047 0.9704955836 1.6094850302 0.0683617362 0.0057070000 989349333 0 402718720 0.1511131972 0.1582720578 0.7749734521 783 31.2800000000 1.3730828762 0.9710097437 1.6094850302 0.0683189953 0.0055170000 989428165 0 402718720 0.1511131972 0.1582720578 0.7749734521 784 31.3200000000 1.3770877123 0.9715277003 1.6094850302 0.0682766221 0.0057080000 989506997 0 402718720 0.1511131972 0.1582720578 0.7749734521 785 31.3600000000 1.3812136650 0.9720495932 1.6094850302 0.0682345354 0.0210190000 989585829 0 402718720 0.1511131972 0.1582720578 0.7749734521 786 31.4000000000 1.3800318241 0.9725686546 1.6094850302 0.0681920528 0.0137680000 989664661 0 402718720 0.1511131972 0.1582720578 0.7749734521 787 31.4400000000 1.3795394897 0.9730857713 1.6094850302 0.0681497132 0.0087270000 989743493 0 402718720 0.1511131972 0.1582720578 0.7749734521 788 31.4800000000 1.3801891804 0.9736023999 1.6094850302 0.0681072165 0.0063720000 989822325 0 402718720 0.1511131972 0.1582720578 0.7749734521 789 31.5200000000 1.3822909594 0.9741203829 1.6094850302 0.0680648451 0.0058100000 989901157 0 402718720 0.1511131972 0.1582720578 0.7749734521 790 31.5600000000 1.3825176954 0.9746373415 1.6094850302 0.0680233848 0.0057150000 989979989 0 402718720 0.1511131972 0.1582720578 0.7749734521 791 31.6000000000 1.3870892525 0.9751587725 1.6094850302 0.0679830490 0.0246640000 990058821 0 402718720 0.1511131972 0.1582720578 0.7749734521 792 31.6400000000 1.3904070854 0.9756830759 1.6094850302 0.0679407633 0.0167030000 990137653 0 402718720 0.1511131972 0.1582720578 0.7749734521 793 31.6800000000 1.3888127804 0.9762040466 1.6094850302 0.0678982517 0.0087820000 990216485 0 402718720 0.1511131972 0.1582720578 0.7749734521 794 31.7200000000 1.3947387934 0.9767311684 1.6094850302 0.0678564229 0.0088390000 990295317 0 402718720 0.1511131972 0.1582720578 0.7749734521 795 31.7600000000 1.3988988400 0.9772621969 1.6094850302 0.0678141420 0.0088950000 990374149 0 402718720 0.1511131972 0.1582720578 0.7749734521 796 31.8000000000 1.3979917765 0.9777907517 1.6094850302 0.0677715741 0.0074340000 990452981 0 402718720 0.1511131972 0.1582720578 0.7749734521 797 31.8400000000 1.3989320993 0.9783191599 1.6094850302 0.0677292146 0.0066220000 990531813 0 402718720 0.1511131972 0.1582720578 0.7749734521 798 31.8800000000 1.4016078711 0.9788495969 1.6094850302 0.0676877724 0.0058510000 990610645 0 402718720 0.1511131972 0.1582720578 0.7749734521 799 31.9200000000 1.4085525274 0.9793873978 1.6094850302 0.0676472097 0.0058360000 990689477 0 402718720 0.1511131972 0.1582720578 0.7749734521 800 31.9600000000 1.4133970737 0.9799299099 1.6094850302 0.0676052368 0.0057710000 990768309 0 402718720 0.1511131972 0.1582720578 0.7749734521 801 32.0000000000 1.4072616100 0.9804634076 1.6094850302 0.0675654367 0.0058790000 990847141 0 402718720 0.1511131972 0.1582720578 0.7749734521 802 32.0400000000 1.4104837179 0.9809995926 1.6094850302 0.0675250600 0.0057920000 990925973 0 402718720 0.1511131972 0.1582720578 0.7749734521 803 32.0800000000 1.4160630703 0.9815413902 1.6094850302 0.0674838596 0.0057360000 991004805 0 402718720 0.1511131972 0.1582720578 0.7749734521 804 32.1199999990 1.4179238081 0.9820841544 1.6094850302 0.0674427024 0.0217260000 991083637 0 402718720 0.1511131972 0.1582720578 0.7749734521 805 32.1600000000 1.4212509394 0.9826297032 1.6094850302 0.0674021291 0.0101230000 991162469 0 402718720 0.1511131972 0.1582720578 0.7749734521 806 32.2000000000 1.4278273582 0.9831820576 1.6094850302 0.0673628344 0.0240790000 991241301 0 402718720 0.1511131972 0.1582720578 0.7749734521 807 32.2400000000 1.4310784340 0.9837370717 1.6094850302 0.0673231454 0.0108800000 991320133 0 402718720 0.1511131972 0.1582720578 0.7749734521 808 32.2800000000 1.4376672506 0.9842988665 1.6094850302 0.0672851688 0.0072040000 991398965 0 402718720 0.1511131972 0.1582720578 0.7749734521 809 32.3200000000 1.4459390640 0.9848694971 1.6094850302 0.0672478187 0.0061740000 991477797 0 402718720 0.1511131972 0.1582720578 0.7749734521 810 32.3600000000 1.4484376907 0.9854418035 1.6094850302 0.0672096907 0.0056450000 991556629 0 402718720 0.1511131972 0.1582720578 0.7749734521 811 32.4000000000 1.4555087090 0.9860214175 1.6094850302 0.0671728599 0.0055330000 991635461 0 402718720 0.1511131972 0.1582720578 0.7749734521 812 32.4399999990 1.4538012743 0.9865975010 1.6094850302 0.0671365966 0.0055530000 991714293 0 402718720 0.1511131972 0.1582720578 0.7749734521 813 32.4800000000 1.4612724781 0.9871813571 1.6094850302 0.0671000182 0.0169360000 991793125 0 402718720 0.1511131972 0.1582720578 0.7749734521 814 32.5200000000 1.4762862921 0.9877822231 1.6094850302 0.0670645728 0.0056880000 991871957 0 402718720 0.1511131972 0.1582720578 0.7749734521 815 32.5600000000 1.4794648886 0.9883855147 1.6094850302 0.0670256539 0.0055690000 991950789 0 402718720 0.1511131972 0.1582720578 0.7749734521 816 32.6000000000 1.4833278656 0.9889920617 1.6094850302 0.0669873369 0.0150780000 992029621 0 402718720 0.1511131972 0.1582720578 0.7749734521 817 32.6400000000 1.4910863638 0.9896066202 1.6094850302 0.0669499521 0.0054780000 992108453 0 402718720 0.1511131972 0.1582720578 0.7749734521 818 32.6800000000 1.5002663136 0.9902308986 1.6094850302 0.0669119985 0.0056640000 992187285 0 402718720 0.1511131972 0.1582720578 0.7749734521 819 32.7200000000 1.5051867962 0.9908596604 1.6094850302 0.0668725781 0.0056630000 992266117 0 402718720 0.1511131972 0.1582720578 0.7749734521 820 32.7599999990 1.5088512897 0.9914913575 1.6094850302 0.0668328115 0.0169490000 992344949 0 402718720 0.1511131972 0.1582720578 0.7749734521 821 32.7999999990 1.5170195103 0.9921314648 1.6094850302 0.0667937193 0.0057850000 992423781 0 402718720 0.1511131972 0.1582720578 0.7749734521 822 32.8400000000 1.5236872435 0.9927781264 1.6094850302 0.0667542543 0.0057010000 992502613 0 402718720 0.1511131972 0.1582720578 0.7749734521 823 32.8800000000 1.5289000273 0.9934295503 1.6094850302 0.0667155912 0.0057420000 992581445 0 402718720 0.1511131972 0.1582720578 0.7749734521 824 32.9200000000 1.5382586718 0.9940907507 1.6094850302 0.0666775910 0.0201390000 992660277 0 402718720 0.1511131972 0.1582720578 0.7749734521 825 32.9600000000 1.5410771370 0.9947537645 1.6094850302 0.0666386169 0.0055760000 992739109 0 402718720 0.1511131972 0.1582720578 0.7749734521 826 33.0000000000 1.5429968834 0.9954174971 1.6094850302 0.0665991572 0.0055880000 992817941 0 402718720 0.1511131972 0.1582720578 0.7749734521 827 33.0400000000 1.5531313419 0.9960918790 1.6094850302 0.0665608435 0.0055710000 992896773 0 402718720 0.1511131972 0.1582720578 0.7749734521 828 33.0800000000 1.5540288687 0.9967657160 1.6094850302 0.0665223505 0.0056060000 992975605 0 402718720 0.1511131972 0.1582720578 0.7749734521 829 33.1199999990 1.5568321943 0.9974413088 1.6094850302 0.0664843772 0.0055850000 993054437 0 402718720 0.1511131972 0.1582720578 0.7749734521 830 33.1600000000 1.5709794760 0.9981323186 1.6094850302 0.0664511054 0.0240010000 993133269 0 402718720 0.1511131972 0.1582720578 0.7749734521 831 33.2000000000 1.5757452250 0.9988274004 1.6094850302 0.0664128529 0.0106560000 993212101 0 402718720 0.1511131972 0.1582720578 0.7749734521 832 33.2400000000 1.5741227865 0.9995188612 1.6094850302 0.0663744306 0.0075140000 993290933 0 402718720 0.1511131972 0.1582720578 0.7749734521 833 33.2800000000 1.5783796310 1.0002137721 1.6094850302 0.0663364446 0.0062510000 993369765 0 402718720 0.1511131972 0.1582720578 0.7749734521 834 33.3200000000 1.5860995054 1.0009162729 1.6094850302 0.0663005484 0.0056580000 993448597 0 402718720 0.1511131972 0.1582720578 0.7749734521 835 33.3600000000 1.5930485725 1.0016254134 1.6094850302 0.0662638924 0.0056280000 993527429 0 402718720 0.1511131972 0.1582720578 0.7749734521 836 33.4000000000 1.5984201431 1.0023392827 1.6094850302 0.0662266035 0.0057340000 993606261 0 402718720 0.1511131972 0.1582720578 0.7749734521 837 33.4399999990 1.6026504040 1.0030565003 1.6094850302 0.0661888526 0.0057730000 993685093 0 402718720 0.1511131972 0.1582720578 0.7749734521 838 33.4800000000 1.6062277555 1.0037762751 1.6094850302 0.0661509148 0.0057100000 993763925 0 402718720 0.1511131972 0.1582720578 0.7749734521 839 33.5200000000 1.6113562584 1.0045004467 1.6113562584 0.0661122652 0.0057930000 993842757 0 402718720 0.1511131972 0.1582720578 0.7749734521 840 33.5600000000 1.6097149849 1.0052209402 1.6113562584 0.0660736309 0.0056990000 993921589 0 402718720 0.1511131972 0.1582720578 0.7749734521 841 33.6000000000 1.6118123531 1.0059422141 1.6118123531 0.0660355594 0.0058050000 994000421 0 402718720 0.1511131972 0.1582720578 0.7749734521 842 33.6400000000 1.6171115637 1.0066680685 1.6171115637 0.0659985789 0.0058960000 994079253 0 402718720 0.1511131972 0.1582720578 0.7749734521 843 33.6800000000 1.6227068901 1.0073988381 1.6227068901 0.0659660556 0.0057370000 994158085 0 402718720 0.1511131972 0.1582720578 0.7749734521 844 33.7200000000 1.6279234886 1.0081340569 1.6279234886 0.0659278669 0.0057930000 994236917 0 402718720 0.1511131972 0.1582720578 0.7749734521 845 33.7599999990 1.6353594065 1.0088763354 1.6353594065 0.0658902123 0.0056840000 994315749 0 402718720 0.1511131972 0.1582720578 0.7749734521 846 33.7999999990 1.6422818899 1.0096250418 1.6422818899 0.0658526458 0.0055800000 994394581 0 402718720 0.1511131972 0.1582720578 0.7749734521 847 33.8400000000 1.6462105513 1.0103766185 1.6462105513 0.0658142516 0.0058760000 994473413 0 402718720 0.1511131972 0.1582720578 0.7749734521 848 33.8800000000 1.6455218792 1.0111256106 1.6462105513 0.0657757148 0.0056000000 994552245 0 402718720 0.1511131972 0.1582720578 0.7749734521 849 33.9200000000 1.6504143476 1.0118786008 1.6504143476 0.0657371732 0.0058160000 994631077 0 402718720 0.1511131972 0.1582720578 0.7749734521 850 33.9600000000 1.6516748667 1.0126313023 1.6516748667 0.0656988446 0.0056820000 994709909 0 402718720 0.1511131972 0.1582720578 0.7749734521 851 34.0000000000 1.6521303654 1.0133827701 1.6521303654 0.0656604571 0.0199790000 994788741 0 402718720 0.1511131972 0.1582720578 0.7749734521 852 34.0400000000 1.6566941738 1.0141378304 1.6566941738 0.0656221861 0.0057920000 994867573 0 402718720 0.1511131972 0.1582720578 0.7749734521 853 34.0800000000 1.6598583460 1.0148948299 1.6598583460 0.0655839371 0.0059100000 994946405 0 402718720 0.1511131972 0.1582720578 0.7749734521 854 34.1199999990 1.6638746262 1.0156547594 1.6638746262 0.0655455732 0.0059390000 995025237 0 402718720 0.1511131972 0.1582720578 0.7749734521 855 34.1600000000 1.6667602062 1.0164162862 1.6667602062 0.0655073407 0.0056890000 995104069 0 402718720 0.1511131972 0.1582720578 0.7749734521 856 34.2000000000 1.6676037312 1.0171770192 1.6676037312 0.0654692420 0.0056840000 995182901 0 402718720 0.1511131972 0.1582720578 0.7749734521 857 34.2400000000 1.6708136797 1.0179397224 1.6708136797 0.0654313351 0.0058270000 995261733 0 402718720 0.1511131972 0.1582720578 0.7749734521 858 34.2800000000 1.6721092463 1.0187021578 1.6721092463 0.0653936072 0.0057530000 995340565 0 402718720 0.1511131972 0.1582720578 0.7749734521 859 34.3200000000 1.6764904261 1.0194679183 1.6764904261 0.0653564032 0.0058510000 995419397 0 402718720 0.1511131972 0.1582720578 0.7749734521 860 34.3600000000 1.6804836988 1.0202365413 1.6804836988 0.0653186611 0.0061930000 995498229 0 402718720 0.1511131972 0.1582720578 0.7749734521 861 34.4000000000 1.6824207306 1.0210056286 1.6824207306 0.0652808428 0.0059420000 995577061 0 402718720 0.1511131972 0.1582720578 0.7749734521 862 34.4400000000 1.6850783825 1.0217760146 1.6850783825 0.0652432580 0.0060290000 995655893 0 402718720 0.1511131972 0.1582720578 0.7749734521 863 34.4800000000 1.6867803335 1.0225465874 1.6867803335 0.0652055919 0.0230460000 995734725 0 402718720 0.1511131972 0.1582720578 0.7749734521 864 34.5200000000 1.6914029121 1.0233207267 1.6914029121 0.0651683538 0.0104920000 995813557 0 402718720 0.1511131972 0.1582720578 0.7749734521 865 34.5600000000 1.6926424503 1.0240945090 1.6926424503 0.0651310232 0.0078090000 995892389 0 402718720 0.1511131972 0.1582720578 0.7749734521 866 34.6000000000 1.6933346987 1.0248673037 1.6933346987 0.0650949633 0.0064900000 995971221 0 402718720 0.1511131972 0.1582720578 0.7749734521 867 34.6400000000 1.7038017511 1.0256503884 1.7038017511 0.0650706973 0.0058200000 996050053 0 402718720 0.1511131972 0.1582720578 0.7749734521 868 34.6800000000 1.7044286728 1.0264323910 1.7044286728 0.0650351998 0.0058170000 996128885 0 402718720 0.1511131972 0.1582720578 0.7749734521 869 34.7200000000 1.7099809647 1.0272189832 1.7099809647 0.0650015083 0.0159200000 996207717 0 402718720 0.1511131972 0.1582720578 0.7749734521 870 34.7600000000 1.7138788700 1.0280082474 1.7138788700 0.0649655709 0.0060500000 996286549 0 402718720 0.1511131972 0.1582720578 0.7749734521 871 34.8000000000 1.7139414549 1.0287957712 1.7139414549 0.0649289466 0.0061180000 996365381 0 402718720 0.1511131972 0.1582720578 0.7749734521 872 34.8400000000 1.7186349630 1.0295868712 1.7186349630 0.0648935794 0.0062040000 996444213 0 402718720 0.1511131972 0.1582720578 0.7749734521 873 34.8800000000 1.7199540138 1.0303776697 1.7199540138 0.0648571032 0.0059860000 996523045 0 402718720 0.1511131972 0.1582720578 0.7749734521 874 34.9200000000 1.7266277075 1.0311742945 1.7266277075 0.0648212847 0.0059600000 996601877 0 402718720 0.1511131972 0.1582720578 0.7749734521 875 34.9600000000 1.7295303345 1.0319724157 1.7295303345 0.0647848342 0.0241660000 996680709 0 402718720 0.1511131972 0.1582720578 0.7749734521 876 35.0000000000 1.7322356701 1.0327718030 1.7322356701 0.0647479752 0.0105390000 996759541 0 402718720 0.1511131972 0.1582720578 0.7749734521 877 35.0400000000 1.7300562859 1.0335668822 1.7322356701 0.0647113036 0.0078980000 996838373 0 402718720 0.1511131972 0.1582720578 0.7749734521 878 35.0800000000 1.7326475382 1.0343631016 1.7326475382 0.0646749341 0.0064960000 996917205 0 402718720 0.1511131972 0.1582720578 0.7749734521 879 35.1200000000 1.7390698195 1.0351648157 1.7390698195 0.0646392608 0.0062830000 996996037 0 402718720 0.1511131972 0.1582720578 0.7749734521 880 35.1600000000 1.7393354177 1.0359650096 1.7393354177 0.0646026222 0.0060690000 997074869 0 402718720 0.1511131972 0.1582720578 0.7749734521 881 35.2000000000 1.7402617931 1.0367644384 1.7402617931 0.0645663411 0.0061360000 997153701 0 402718720 0.1511131972 0.1582720578 0.7749734521 882 35.2400000000 1.7430506945 1.0375652165 1.7430506945 0.0645300934 0.0062360000 997232533 0 402718720 0.1511131972 0.1582720578 0.7749734521 883 35.2800000000 1.7497808933 1.0383718028 1.7497808933 0.0644947580 0.0205290000 997311365 0 402718720 0.1511131972 0.1582720578 0.7749734521 884 35.3200000000 1.7498198748 1.0391766083 1.7498198748 0.0644583163 0.0085820000 997390197 0 402718720 0.1511131972 0.1582720578 0.7749734521 885 35.3600000000 1.7495417595 1.0399792808 1.7498198748 0.0644218750 0.0061910000 997469029 0 402718720 0.1511131972 0.1582720578 0.7749734521 886 35.4000000000 1.7547943592 1.0407860698 1.7547943592 0.0643866583 0.0063840000 997547861 0 402718720 0.1511131972 0.1582720578 0.7749734521 887 35.4400000000 1.7621015310 1.0415992777 1.7621015310 0.0643515136 0.0063400000 997626693 0 402718720 0.1511131972 0.1582720578 0.7749734521 888 35.4800000000 1.7653850317 1.0424143518 1.7653850317 0.0643156682 0.0062920000 997705525 0 402718720 0.1511131972 0.1582720578 0.7749734521 889 35.5200000000 1.7693593502 1.0432320627 1.7693593502 0.0642804111 0.0066030000 997784357 0 402718720 0.1511131972 0.1582720578 0.7749734521 890 35.5600000000 1.7745203972 1.0440537350 1.7745203972 0.0642457230 0.0062900000 997863189 0 402718720 0.1511131972 0.1582720578 0.7749734521 891 35.6000000000 1.7811810970 1.0448810384 1.7811810970 0.0642106306 0.0063390000 997942021 0 402718720 0.1511131972 0.1582720578 0.7749734521 892 35.6400000000 1.7866357565 1.0457126020 1.7866357565 0.0641758687 0.0206880000 998020853 0 402718720 0.1511131972 0.1582720578 0.7749734521 893 35.6800000000 1.7880309820 1.0465438656 1.7880309820 0.0641410534 0.0063550000 998099685 0 402718720 0.1511131972 0.1582720578 0.7749734521 894 35.7200000000 1.7890272141 1.0473743839 1.7890272141 0.0641070583 0.0063220000 998178517 0 402718720 0.1511131972 0.1582720578 0.7749734521 895 35.7600000000 1.7951960564 1.0482099388 1.7951960564 0.0640729859 0.0063640000 998257349 0 402718720 0.1511131972 0.1582720578 0.7749734521 896 35.8000000000 1.7992269993 1.0490481275 1.7992269993 0.0640391537 0.0143450000 998336181 0 402718720 0.1511131972 0.1582720578 0.7749734521 897 35.8400000000 1.8042641878 1.0498900629 1.8042641878 0.0640053600 0.0090100000 998415013 0 402718720 0.1511131972 0.1582720578 0.7749734521 898 35.8800000000 1.8057171106 1.0507317411 1.8057171106 0.0639704290 0.0072730000 998493845 0 402718720 0.1511131972 0.1582720578 0.7749734521 899 35.9200000000 1.8087552786 1.0515749264 1.8087552786 0.0639366138 0.0067190000 998572677 0 402718720 0.1511131972 0.1582720578 0.7749734521 900 35.9600000000 1.8082964420 1.0524157281 1.8087552786 0.0639033962 0.0066780000 998651509 0 402718720 0.1511131972 0.1582720578 0.7749734521 901 36.0000000000 1.8115279675 1.0532582500 1.8115279675 0.0638736887 0.0066030000 998730341 0 402718720 0.1511131972 0.1582720578 0.7749734521 902 36.0400000000 1.8202556372 1.0541085797 1.8202556372 0.0638451121 0.0068040000 998809173 0 402718720 0.1511131972 0.1582720578 0.7749734521 903 36.0800000000 1.8236380816 1.0549607718 1.8236380816 0.0638151030 0.0065660000 998888005 0 402718720 0.1511131972 0.1582720578 0.7749734521 904 36.1200000000 1.8148155212 1.0558013191 1.8236380816 0.0637853822 0.0067500000 998966837 0 402718720 0.1511131972 0.1582720578 0.7749734521 905 36.1600000000 1.8269267082 1.0566533914 1.8269267082 0.0637858320 0.0068630000 999045669 0 402718720 0.1511131972 0.1582720578 0.7749734521 906 36.2000000000 1.8310606480 1.0575081455 1.8310606480 0.0637539107 0.0071330000 999124501 0 402718720 0.1511131972 0.1582720578 0.7749734521 907 36.2400000000 1.8331305981 1.0583632970 1.8331305981 0.0637228084 0.0068430000 999203333 0 402718720 0.1511131972 0.1582720578 0.7749734521 908 36.2800000000 1.8369584084 1.0592207807 1.8369584084 0.0636948413 0.0065520000 999205341 0 402718720 0.1511131972 0.1582720578 0.7749734521 909 36.3200000000 1.8355741501 1.0600748548 1.8369584084 0.0636633350 0.0218760000 999284173 0 402718720 0.1511131972 0.1582720578 0.7749734521 910 36.3600000000 1.8330107927 1.0609242349 1.8369584084 0.0636308303 0.0069700000 999363005 0 402718720 0.1511131972 0.1582720578 0.7749734521 911 36.4000000000 1.8330200911 1.0617717606 1.8369584084 0.0635991845 0.0070200000 999441837 0 402718720 0.1511131972 0.1582720578 0.7749734521 912 36.4400000000 1.8354811668 1.0626201261 1.8369584084 0.0635670357 0.0068890000 999520669 0 402718720 0.1511131972 0.1582720578 0.7749734521 913 36.4800000000 1.8367156982 1.0634679855 1.8369584084 0.0635342745 0.0070100000 999599501 0 402718720 0.1511131972 0.1582720578 0.7749734521 914 36.5200000000 1.8382302523 1.0643156466 1.8382302523 0.0635012333 0.0071120000 999678333 0 402718720 0.1511131972 0.1582720578 0.7749734521 915 36.5600000000 1.8361783028 1.0651592123 1.8382302523 0.0634679220 0.0164220000 999757165 0 402718720 0.1511131972 0.1582720578 0.7749734521 916 36.6000000000 1.8368014097 1.0660016165 1.8382302523 0.0634346941 0.0098490000 999835997 0 402718720 0.1511131972 0.1582720578 0.7749734521 917 36.6400000000 1.8376977444 1.0668431608 1.8382302523 0.0634011560 0.0075260000 999914829 0 402718720 0.1511131972 0.1582720578 0.7749734521 918 36.6800000000 1.8394982815 1.0676848330 1.8394982815 0.0633681027 0.0070880000 999993661 0 402718720 0.1511131972 0.1582720578 0.7749734521 919 36.7200000000 1.8394502401 1.0685246213 1.8394982815 0.0633350375 0.0070610000 1000072493 0 402718720 0.1511131972 0.1582720578 0.7749734521 920 36.7600000000 1.8427864313 1.0693662102 1.8427864313 0.0633016038 0.0069400000 1000151325 0 402718720 0.1511131972 0.1582720578 0.7749734521 921 36.8000000000 1.8390474319 1.0702019119 1.8427864313 0.0632676901 0.0136570000 1000230157 0 402718720 0.1511131972 0.1582720578 0.7749734521 922 36.8400000000 1.8370926380 1.0710336805 1.8427864313 0.0632334321 0.0065050000 1000308989 0 402718720 0.1511131972 0.1582720578 0.7749734521 923 36.8800000000 1.8361515999 1.0718626274 1.8427864313 0.0631995393 0.0064650000 1000387821 0 402718720 0.1511131972 0.1582720578 0.7749734521 924 36.9200000000 1.8379552364 1.0726917319 1.8427864313 0.0631663981 0.0073240000 1000466653 0 402718720 0.1511131972 0.1582720578 0.7749734521 925 36.9600000000 1.8386023045 1.0735197434 1.8427864313 0.0631324525 0.0073090000 1000545485 0 402718720 0.1511131972 0.1582720578 0.7749734521 926 37.0000000000 1.8393279314 1.0743467500 1.8427864313 0.0631018645 0.0204310000 1000624317 0 402718720 0.1511131972 0.1582720578 0.7749734521 927 37.0400000000 1.8369911909 1.0751694517 1.8427864313 0.0630682437 0.0070230000 1000703149 0 402718720 0.1511131972 0.1582720578 0.7749734521 928 37.0800000000 1.8376653194 1.0759911067 1.8427864313 0.0630350495 0.0070220000 1000781981 0 402718720 0.1511131972 0.1582720578 0.7749734521 929 37.1200000000 1.8375386000 1.0768108565 1.8427864313 0.0630022304 0.0072160000 1000860813 0 402718720 0.1511131972 0.1582720578 0.7749734521 930 37.1600000000 1.8370420933 1.0776283094 1.8427864313 0.0629696514 0.0074030000 1000939645 0 402718720 0.1511131972 0.1582720578 0.7749734521 931 37.2000000000 1.8392825127 1.0784464127 1.8427864313 0.0629369072 0.0176610000 1001018477 0 402718720 0.1511131972 0.1582720578 0.7749734521 932 37.2400000000 1.8356693983 1.0792588837 1.8427864313 0.0629043613 0.0086000000 1001097309 0 402718720 0.1511131972 0.1582720578 0.7749734521 933 37.2800000000 1.8362063169 1.0800701886 1.8427864313 0.0628710175 0.0085110000 1001176141 0 402718720 0.1511131972 0.1582720578 0.7749734521 934 37.3200000000 1.8368915319 1.0808804898 1.8427864313 0.0628377385 0.0075440000 1001254973 0 402718720 0.1511131972 0.1582720578 0.7749734521 935 37.3600000000 1.8343557119 1.0816863457 1.8427864313 0.0628046628 0.0081480000 1001333805 0 402718720 0.1511131972 0.1582720578 0.7749734521 936 37.4000000000 1.8303658962 1.0824862170 1.8427864313 0.0627717565 0.0168920000 1001412637 0 402718720 0.1511131972 0.1582720578 0.7749734521 937 37.4400000000 1.8278092146 1.0832816524 1.8427864313 0.0627388409 0.0099760000 1001491469 0 402718720 0.1511131972 0.1582720578 0.7749734521 938 37.4800000000 1.8291394711 1.0840768100 1.8427864313 0.0627065232 0.0077390000 1001570301 0 402718720 0.1511131972 0.1582720578 0.7749734521 939 37.5200000000 1.8288044930 1.0848699172 1.8427864313 0.0626746768 0.0080090000 1001649133 0 402718720 0.1511131972 0.1582720578 0.7749734521 940 37.5600000000 1.8247449398 1.0856570183 1.8427864313 0.0626423499 0.0158990000 1001727965 0 402718720 0.1511131972 0.1582720578 0.7749734521 941 37.6000000000 1.8247858286 1.0864424900 1.8427864313 0.0626102510 0.0109080000 1001806797 0 402718720 0.1511131972 0.1582720578 0.7749734521 942 37.6400000000 1.8258904219 1.0872274665 1.8427864313 0.0625785469 0.0086310000 1001885629 0 402718720 0.1511131972 0.1582720578 0.7749734521 943 37.6800000000 1.8229099512 1.0880076176 1.8427864313 0.0625465839 0.0160060000 1001964461 0 402718720 0.1511131972 0.1582720578 0.7749734521 944 37.7200000000 1.8200149536 1.0887830491 1.8427864313 0.0625147550 0.0083830000 1002043293 0 402718720 0.1511131972 0.1582720578 0.7749734521 945 37.7600000000 1.8156501055 1.0895522206 1.8427864313 0.0624832745 0.0084570000 1002122125 0 402718720 0.1511131972 0.1582720578 0.7749734521 946 37.8000000000 1.8145078421 1.0903185585 1.8427864313 0.0624521689 0.0150880000 1002200957 0 402718720 0.1511131972 0.1582720578 0.7749734521 947 37.8400000000 1.8636212349 1.0911351400 1.8636212349 0.0746851378 0.0127810000 1002279789 0 402718720 0.0428048931 0.1052218229 0.8567425609 948 37.8800000000 1.8614622355 1.0919477213 1.8636212349 0.0746502962 0.0204210000 997553933 0 402718720 0.0434706807 0.1065273434 0.8547376394 949 37.9200000000 1.8635243177 1.0927607630 1.8636212349 0.0746136052 0.0099450000 1010244333 0 402718720 0.0434706807 0.1065273434 0.8547376394 950 37.9600000000 1.8746584654 1.0935838132 1.8746584654 0.0745879970 0.0100600000 1011979309 0 402718720 0.0350162126 0.1098975167 0.8671765327 951 38.0000000000 1.8752802610 1.0944057864 1.8752802610 0.0745520224 0.0215650000 1012938069 0 402718720 0.0358327627 0.1117348745 0.8675987720 952 38.0400000000 1.8766651154 1.0952274873 1.8766651154 0.0745145214 0.0112740000 1026363109 0 402718720 0.0358327627 0.1117348745 0.8675987720 953 38.0800000000 1.8589953184 1.0960289226 1.8766651154 0.0745309306 0.0120870000 1028098085 0 402718720 0.0402113833 0.1048405468 0.8504289985 954 38.1200000000 1.8589336872 1.0968286132 1.8766651154 0.0744940951 0.0214360000 1029056749 0 402718720 0.0408411101 0.1060544997 0.8499907851 955 38.1600000000 1.8679951429 1.0976361174 1.8766651154 0.0746095812 0.0115860000 1042481885 0 402718720 0.0342801139 0.1059882715 0.8597372174 956 38.2000000000 1.8704298735 1.0984444791 1.8766651154 0.0745708071 0.0214850000 1045173453 0 402718720 0.0337258950 0.1058645174 0.8608238697 957 38.2400000000 1.8641961813 1.0992446376 1.8766651154 0.0745455703 0.0147370000 1058598653 0 402718720 0.0357139781 0.1081876531 0.8517861366 958 38.2800000000 1.8637003899 1.1000426081 1.8766651154 0.0745073196 0.0215300000 1061290157 0 402718720 0.0366300754 0.1083118767 0.8486143947 959 38.3200000000 1.8652710915 1.1008405523 1.8766651154 0.0744689447 0.0196580000 1074715421 0 402718720 0.0342640989 0.1086081788 0.8498999476 960 38.3600000000 1.8624634743 1.1016339095 1.8766651154 0.0744327468 0.0215400000 1077406861 0 402718720 0.0356554464 0.1089671478 0.8477648497 961 38.4000000000 0.9634594321 1.1014901275 1.8766651154 0.1101546501 0.0258370000 1090832189 0 402718720 0.1515295953 -0.0395420194 -0.0843710229 962 38.4400000000 0.9557434916 1.1013386237 1.8766651154 0.1100993303 0.0249010000 1084905333 0 402718720 0.1414829642 -0.0347863920 -0.0872103348 963 38.4800000000 0.9517294765 1.1011832664 1.8766651154 0.1100437158 0.0254210000 1084907581 0 402718720 0.1354781985 -0.0326766036 -0.0878226608 964 38.5200000000 0.9488175511 1.1010252107 1.8766651154 0.1099887315 0.0637540000 1084909829 0 402718720 0.1079520434 -0.0248347465 -0.0810781568 965 38.5600000000 0.9494476914 1.1008681355 1.8766651154 0.1099333059 0.0268550000 1084912077 0 402718720 0.1009754688 -0.0256375540 -0.0793722123 966 38.6000000000 0.9428360462 1.1007045412 1.8766651154 0.1098807425 0.0268330000 1084914325 0 402718720 0.0954102054 -0.0294625405 -0.0838188380 967 38.6400000000 0.9320099950 1.1005300898 1.8766651154 0.1098280212 0.0263700000 1084916573 0 402718720 0.1124481559 -0.0432685390 -0.0957988575 968 38.6800000000 0.9298243523 1.1003537409 1.8766651154 0.1097734497 0.0261840000 1084918821 0 402718720 0.1258331388 -0.0461977944 -0.1020030677 969 38.7200000000 0.9247006774 1.1001724683 1.8766651154 0.1097175014 0.0255280000 1084921581 0 402718720 0.1533254087 -0.0574322119 -0.1112333015 970 38.7600000000 0.9235968590 1.0999904316 1.8766651154 0.1096618102 0.0253590000 1084923317 0 402718720 0.1800536215 -0.0711978003 -0.1206917390 971 38.8000000000 0.9185678959 1.0998035907 1.8766651154 0.1096060036 0.0254590000 1084925565 0 402718720 0.1973685324 -0.0783600956 -0.1302381903 972 38.8400000000 0.9126798511 1.0996110766 1.8766651154 0.1095504110 0.0255490000 1084927813 0 402718720 0.2033789605 -0.0831739828 -0.1366356462 973 38.8800000000 0.9033142328 1.0994093326 1.8766651154 0.1094964946 0.0257920000 1084930061 0 402718720 0.1974217892 -0.0868209153 -0.1424494088 974 38.9200000000 0.8932141066 1.0991976332 1.8766651154 0.1094434599 0.0258980000 1084932309 0 402718720 0.1922516972 -0.0947273821 -0.1477299035 975 38.9600000000 0.8802899122 1.0989731125 1.8766651154 0.1093914985 0.0261830000 1084934557 0 402718720 0.1783414036 -0.0963829830 -0.1549202800 976 39.0000000000 0.8731130958 1.0987416985 1.8766651154 0.1093377471 0.0261190000 1084936805 0 402718720 0.1651162058 -0.0942258090 -0.1575654447 977 39.0400000000 0.8707750440 1.0985083652 1.8766651154 0.1092836721 0.0627930000 1084939053 0 402718720 0.1395030916 -0.0873450190 -0.1536369622 978 39.0800000000 0.8705878258 1.0982753176 1.8766651154 0.1092291356 0.0403370000 1084941301 0 402718720 0.0395184718 -0.0321653150 -0.1447667181 979 39.1200000000 0.8836922050 1.0980561316 1.8766651154 0.1091762212 0.0299340000 1088445105 0 402718720 0.0160685536 0.0029925776 -0.1384800673 980 39.1600000000 0.8852547407 1.0978389873 1.8766651154 0.1091230013 0.0144110000 1095821737 0 402718720 0.0160685536 0.0029925776 -0.1384800673 981 39.2000000000 1.7682621479 1.0985223953 1.8766651154 0.1237150927 0.0225080000 1095823745 0 402718720 0.2853178680 0.3677003682 0.6621055007 982 39.2400000000 1.7697396278 1.0992059159 1.8766651154 0.1236531584 0.0353210000 1088452993 0 402718720 0.2838933170 0.3676823080 0.6655792594 983 39.2800000000 1.7681325674 1.0998864109 1.8766651154 0.1235917748 0.0149940000 1095829625 0 402718720 0.2838933170 0.3676823080 0.6655792594 984 39.3200000000 1.7672010660 1.1005645762 1.8766651154 0.1235301934 0.0148530000 1095831633 0 402718720 0.2838933170 0.3676823080 0.6655792594 985 39.3600000000 1.0014570951 1.1004639595 1.8766651154 0.1358973152 0.0210830000 1095833641 0 402718720 0.2738133669 -0.0265329443 -0.0385282859 986 39.4000000000 0.9927623868 1.1003547287 1.8766651154 0.1358305792 0.0227580000 1084958529 0 402718720 0.2706752717 -0.0288972538 -0.0420080721 987 39.4400000000 0.9852066636 1.1002380640 1.8766651154 0.1357658642 0.0240340000 1084960777 0 402718720 0.2596280873 -0.0371790305 -0.0433312431 988 39.4800000000 0.9856240153 1.1001220579 1.8766651154 0.1356983102 0.0241060000 1084963025 0 402718720 0.2476582825 -0.0375317968 -0.0385462455 989 39.5200000000 0.9909195304 1.1000116407 1.8766651154 0.1356306384 0.0236440000 1084965273 0 402718720 0.2325972766 -0.0371799842 -0.0295474660 990 39.5600000000 0.9978736639 1.0999084711 1.8766651154 0.1355629227 0.0241540000 1084967521 0 402718720 0.2161889225 -0.0392697193 -0.0183174703 991 39.6000000000 0.9995348454 1.0998071859 1.8766651154 0.1354945757 0.0240740000 1084969769 0 402718720 0.2105600983 -0.0380813703 -0.0113872606 992 39.6400000000 1.0047811270 1.0997113935 1.8766651154 0.1354263302 0.0539670000 1084972017 0 402718720 0.2043086290 -0.0397414826 -0.0028606623 993 39.6800000000 1.0083712339 1.0996194094 1.8766651154 0.1353592592 0.0247160000 1084974265 0 402718720 0.1968083233 -0.0516397320 0.0080577815 994 39.7200000000 1.0202667713 1.0995395778 1.8766651154 0.1352966582 0.0212700000 1084976513 0 402718720 0.1867317706 -0.0843527392 0.0258128289 995 39.7600000000 1.0259050131 1.0994655732 1.8766651154 0.1352391730 0.0245540000 1084978761 0 402718720 0.1878393441 -0.1282526106 0.0353256278 996 39.8000000000 1.0318765640 1.0993977128 1.8766651154 0.1351779406 0.0254970000 1084981009 0 402718720 0.2061596513 -0.1669859439 0.0435734987 997 39.8400000000 1.0456585884 1.0993438119 1.8766651154 0.1351201672 0.0261150000 1084983257 0 402718720 0.2174438238 -0.2093956769 0.0579144098 998 39.8800000000 1.1524665356 1.0993970411 1.8766651154 0.1351338593 0.0414600000 1088487609 0 402718720 0.1901855022 -0.3187199235 0.1560045928 999 39.9200000000 0.9460508227 1.0992435414 1.8766651154 0.1355304852 0.0251860000 1095864241 0 402718720 0.2052464038 -0.0410596356 -0.0391504914 1000 39.9600000000 0.9604465365 1.0991047444 1.8766651154 0.1354632312 0.0236090000 1084990001 0 402718720 0.1929582059 -0.0514820851 -0.0232079886 1001 40.0000000000 0.9752050638 1.0989809685 1.8766651154 0.1353961523 0.0239190000 1084992249 0 402718720 0.1824248582 -0.0591796823 -0.0072664702 1002 40.0400000000 0.9908877611 1.0988730910 1.8766651154 0.1353299686 0.0236590000 1084994497 0 402718720 0.1667870283 -0.0643392056 0.0108962143 1003 40.0800000000 1.0078564882 1.0987823467 1.8766651154 0.1352632010 0.0237840000 1084996745 0 402718720 0.1544628143 -0.0687388256 0.0292133577 1004 40.1200000000 1.0247346163 1.0987085940 1.8766651154 0.1351964752 0.0513450000 1084999505 0 402718720 0.1394409090 -0.0752629265 0.0467581116 1005 40.1600000000 1.0405853987 1.0986507599 1.8766651154 0.1351316967 0.0301180000 1088504121 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1006 40.2000000000 1.0377248526 1.0985901974 1.8766651154 0.1350648724 0.0145120000 1095880753 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1007 40.2400000000 1.0352551937 1.0985273027 1.8766651154 0.1349979464 0.0132170000 1095882761 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1008 40.2800000000 1.0334290266 1.0984627210 1.8766651154 0.1349310158 0.0156340000 1095884769 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1009 40.3200000000 1.0311356783 1.0983959945 1.8766651154 0.1348643302 0.0153250000 1095886777 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1010 40.3600000000 1.0294169188 1.0983276984 1.8766651154 0.1347977702 0.0134420000 1095888785 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1011 40.4000000000 1.0291037560 1.0982592277 1.8766651154 0.1347312585 0.0153770000 1095890793 0 402718720 0.1181036010 -0.0817972124 0.0612249188 1012 40.4400000000 0.9441953301 1.0981069906 1.8766651154 0.1346910457 0.0183330000 1095892801 0 402718720 0.2279239446 -0.1662444323 -0.0072150994 1013 40.4800000000 0.9644005895 1.0979750001 1.8766651154 0.1346265138 0.0240770000 1085017633 0 402718720 0.2290895879 -0.1847239137 0.0166256092 1014 40.5200000000 0.9686199427 1.0978474310 1.8766651154 0.1345601508 0.0247400000 1085019881 0 402718720 0.2381146252 -0.1862583309 0.0241643041 1015 40.5600000000 0.9648868442 1.0977164353 1.8766651154 0.1344939591 0.0245010000 1085022129 0 402718720 0.2606979012 -0.1907648295 0.0226316079 1016 40.6000000000 0.9638308883 1.0975846582 1.8766651154 0.1344281736 0.0241830000 1085024377 0 402718720 0.2755016387 -0.2009672076 0.0230954643 1017 40.6400000000 0.9602729082 1.0974496417 1.8766651154 0.1343650512 0.0244150000 1085026625 0 402718720 0.2864454687 -0.2187771946 0.0228537712 1018 40.6800000000 0.9549040794 1.0973096166 1.8766651154 0.1342993560 0.0241680000 1085028873 0 402718720 0.2933658361 -0.2160984427 0.0207454786 1019 40.7200000000 0.9449536800 1.0971601015 1.8766651154 0.1342338487 0.0238770000 1085031121 0 402718720 0.3006793559 -0.2029521912 0.0161453243 1020 40.7600000000 0.9340557456 1.0970001953 1.8766651154 0.1341693175 0.0242200000 1085033369 0 402718720 0.3164579868 -0.2134288996 0.0093309395 1021 40.8000000000 0.9205859303 1.0968274095 1.8766651154 0.1341036504 0.0609720000 1085035617 0 402718720 0.3242548108 -0.2058932185 0.0009411978 1022 40.8400000000 0.9081266522 1.0966427708 1.8766651154 0.1340380643 0.0250690000 1085037865 0 402718720 0.3289848566 -0.1958011240 -0.0048375037 1023 40.8800000000 0.8991044164 1.0964496737 1.8766651154 0.1339726478 0.0248230000 1085040113 0 402718720 0.3297070563 -0.1914672107 -0.0088946559 1024 40.9200000000 0.8920263648 1.0962500415 1.8766651154 0.1339073808 0.0250820000 1085042361 0 402718720 0.3294017315 -0.1878496557 -0.0120363897 1025 40.9600000000 0.8824816346 1.0960414870 1.8766651154 0.1338424310 0.0248130000 1085155105 0 402718720 0.3394088745 -0.1920472831 -0.0159789175 1026 41.0000000000 0.8774675727 1.0958284520 1.8766651154 0.1337771691 0.0336250000 1085349961 0 402718720 0.3456928134 -0.1912508607 -0.0153204845 1027 41.0400000000 0.8787381053 1.0956170690 1.8766651154 0.1337123702 0.0249040000 1085352209 0 402718720 0.3411034346 -0.1862472594 -0.0131684747 1028 41.0800000000 0.8761438131 1.0954035736 1.8766651154 0.1336503444 0.0247020000 1085354457 0 402718720 0.3311003745 -0.1934652627 -0.0114555154 1029 41.1200000000 0.8767981529 1.0951911291 1.8766651154 0.1335872783 0.0246460000 1085356705 0 402718720 0.3242339492 -0.2022182643 -0.0110838888 1030 41.1600000000 0.8782389164 1.0949804958 1.8766651154 0.1335248651 0.0247000000 1085358953 0 402718720 0.3221174181 -0.2133880705 -0.0087413471 1031 41.2000000000 0.8870946765 1.0947788607 1.8766651154 0.1334615237 0.0247720000 1085361201 0 402718720 0.3256756663 -0.2237929553 0.0034599188 1032 41.2400000000 0.8984260559 1.0945885964 1.8766651154 0.1333991390 0.0248310000 1085363449 0 402718720 0.3235787451 -0.2328974009 0.0171439294 1033 41.2800000000 0.8968899250 1.0943972133 1.8766651154 0.1333353231 0.0248890000 1085365697 0 402718720 0.3293721974 -0.2367731631 0.0200576968 1034 41.3200000000 0.8818967938 1.0941917004 1.8766651154 0.1332708521 0.0630460000 1088772897 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1035 41.3600000000 0.8790693879 1.0939838527 1.8766651154 0.1332064811 0.0129900000 1096149529 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1036 41.4000000000 0.8767899275 1.0937742061 1.8766651154 0.1331423643 0.0115930000 1096151537 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1037 41.4400000000 0.8750670552 1.0935633024 1.8766651154 0.1330793927 0.0104690000 1096153545 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1038 41.4800000000 0.8714429736 1.0933493136 1.8766651154 0.1330163541 0.0112350000 1096155553 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1039 41.5200000000 0.8693046570 1.0931336787 1.8766651154 0.1329529147 0.0166810000 1096157561 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1040 41.5600000000 0.8665038347 1.0929157654 1.8766651154 0.1328894020 0.0127810000 1096159569 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1041 41.6000000000 0.8670045733 1.0926987518 1.8766651154 0.1328259492 0.0117350000 1096161577 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1042 41.6400000000 0.8637822866 1.0924790623 1.8766651154 0.1327627174 0.0125300000 1096163585 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1043 41.6800000000 0.8605611920 1.0922567057 1.8766651154 0.1326992311 0.0127260000 1096165593 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1044 41.7200000000 0.8595860004 1.0920338411 1.8766651154 0.1326358650 0.0125210000 1096167601 0 402718720 0.3575119376 -0.2375060916 0.0132703315 1045 41.7600000000 0.7825857997 1.0917377185 1.8766651154 0.1325773119 0.0159620000 1096169609 0 402718720 0.2342032790 -0.0912174657 -0.1101406515 1046 41.8000000000 0.5099183321 1.0911814858 1.8766651154 0.1331892935 0.0284830000 1088798837 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1047 41.8400000000 0.5130028129 1.0906292617 1.8766651154 0.1331261239 0.0138970000 1096175469 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1048 41.8800000000 0.5147410035 1.0900797500 1.8766651154 0.1330632854 0.0126360000 1096177477 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1049 41.9200000000 0.5172363520 1.0895336648 1.8766651154 0.1330002145 0.0122740000 1096179485 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1050 41.9600000000 0.5199750662 1.0889912280 1.8766651154 0.1329373917 0.0113510000 1096181493 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1051 42.0000000000 0.5234833360 1.0884531615 1.8766651154 0.1328745680 0.0114570000 1096183501 0 402718720 0.2342493534 -0.2342443913 -0.4563288689 1052 42.0400000000 0.8175315261 1.0881956315 1.8766651154 0.1335151094 0.0234800000 1096185509 0 402718720 0.2837904394 -0.0885788873 -0.0378960967 1053 42.0800000000 0.7924417853 1.0879147636 1.8766651154 0.1334561718 0.0233830000 1085410757 0 402718720 0.2969662249 -0.0980832502 -0.0581013002 1054 42.1200000000 0.7853111625 1.0876276634 1.8766651154 0.1333974389 0.0244330000 1085413005 0 402718720 0.2925534844 -0.1099202335 -0.0661162138 1055 42.1600000000 0.8040654063 1.0873588840 1.8766651154 0.1333480576 0.0243950000 1085413933 0 402718720 0.2545606792 -0.1210316494 -0.0641139597 1056 42.2000000000 0.8052042127 1.0870916921 1.8766651154 0.1332911356 0.0246500000 1085416181 0 402718720 0.2381381094 -0.1362542808 -0.0719972774 1057 42.2400000000 0.8088248372 1.0868284311 1.8766651154 0.1332341591 0.0248280000 1085418941 0 402718720 0.2158967704 -0.1470447779 -0.0807109103 1058 42.2800000000 0.8712537289 1.0866246743 1.8766651154 0.1331986652 0.0309230000 1088826909 0 402718720 0.1278022528 -0.1652556956 -0.0670696795 1059 42.3200000000 0.8448880911 1.0863964056 1.8766651154 0.1332658177 0.0522540000 1096203541 0 402718720 0.2398126125 -0.1143465340 -0.0160171594 1060 42.3600000000 0.8474301100 1.0861709657 1.8766651154 0.1332062734 0.0237300000 1085427005 0 402718720 0.2325864881 -0.1226893291 -0.0147500280 1061 42.4000000000 0.8460567594 1.0859446563 1.8766651154 0.1331463558 0.0245210000 1085429253 0 402718720 0.2240745276 -0.1267320216 -0.0200381726 1062 42.4400000000 0.8460500240 1.0857187669 1.8766651154 0.1330869492 0.0243320000 1085430989 0 402718720 0.2118335813 -0.1303785592 -0.0253007207 1063 42.4800000000 0.8362754583 1.0854841071 1.8766651154 0.1330269268 0.0242110000 1085433237 0 402718720 0.2086594999 -0.1350210011 -0.0375230573 1064 42.5200000000 0.8240168691 1.0852383672 1.8766651154 0.1329663474 0.0246950000 1085436805 0 402718720 0.2083194256 -0.1397324204 -0.0512047671 1065 42.5600000000 0.8050005436 1.0849752331 1.8766651154 0.1329052847 0.0249640000 1085439053 0 402718720 0.2161218971 -0.1432263106 -0.0674858019 1066 42.6000000000 0.7984141111 1.0847064141 1.8766651154 0.1328436956 0.0248620000 1085441301 0 402718720 0.2210622728 -0.1426728219 -0.0693483353 1067 42.6400000000 0.7959189415 1.0844357604 1.8766651154 0.1327821130 0.0244570000 1085443549 0 402718720 0.2220884264 -0.1439169347 -0.0702087134 1068 42.6800000000 0.7942965627 1.0841640945 1.8766651154 0.1327206312 0.0240680000 1085445797 0 402718720 0.2199071348 -0.1441972405 -0.0705104098 1069 42.7200000000 0.7911995649 1.0838900397 1.8766651154 0.1326593164 0.0242290000 1085448045 0 402718720 0.2186824232 -0.1446655989 -0.0747237280 1070 42.7600000000 0.7885574102 1.0836140279 1.8766651154 0.1325980095 0.0241270000 1085450293 0 402718720 0.2186003178 -0.1478857398 -0.0758617967 1071 42.8000000000 0.7786920071 1.0833293201 1.8766651154 0.1325367446 0.0218130000 1085452541 0 402718720 0.2231982350 -0.1513334215 -0.0813309178 1072 42.8400000000 0.7713764310 1.0830383193 1.8766651154 0.1324752103 0.0542210000 1085454789 0 402718720 0.2283595800 -0.1503841281 -0.0843235403 1073 42.8800000000 0.7662224174 1.0827430575 1.8766651154 0.1324136306 0.0253360000 1085457037 0 402718720 0.2305184603 -0.1490244120 -0.0839425176 1074 42.9200000000 0.7627050877 1.0824450706 1.8766651154 0.1323520823 0.0247950000 1085459285 0 402718720 0.2350736707 -0.1461569667 -0.0828509703 1075 42.9600000000 0.7557871342 1.0821412027 1.8766651154 0.1322906417 0.0247500000 1085461533 0 402718720 0.2408030778 -0.1443263292 -0.0821141377 1076 43.0000000000 0.7509365678 1.0818333917 1.8766651154 0.1322292985 0.0246860000 1085463781 0 402718720 0.2464923710 -0.1429291368 -0.0817855969 1077 43.0400000000 0.7479552627 1.0815233842 1.8766651154 0.1321680738 0.0245440000 1085466029 0 402718720 0.2514061034 -0.1393149197 -0.0807021633 1078 43.0800000000 0.7451882958 1.0812113850 1.8766651154 0.1321070155 0.0246060000 1085468277 0 402718720 0.2550085485 -0.1358922124 -0.0786653012 1079 43.1200000000 0.7436904907 1.0808985761 1.8766651154 0.1320460042 0.0244390000 1085470525 0 402718720 0.2596868277 -0.1310893446 -0.0738964230 1080 43.1600000000 0.7421793938 1.0805849472 1.8766651154 0.1319849499 0.0243960000 1085472773 0 402718720 0.2632369399 -0.1265257448 -0.0681760311 1081 43.2000000000 0.7416362762 1.0802713961 1.8766651154 0.1319238890 0.0244250000 1085475021 0 402718720 0.2650765181 -0.1235531047 -0.0630433932 1082 43.2400000000 0.7380399108 1.0799551009 1.8766651154 0.1318628773 0.0243570000 1085477269 0 402718720 0.2683267891 -0.1201063693 -0.0598659553 1083 43.2800000000 0.7328496575 1.0796345972 1.8766651154 0.1318019594 0.0242240000 1085479517 0 402718720 0.2730049193 -0.1161862984 -0.0569775440 1084 43.3200000000 0.7264202237 1.0793087537 1.8766651154 0.1317411145 0.0234950000 1085481765 0 402718720 0.2768447101 -0.1110964492 -0.0578339435 1085 43.3600000000 0.7185479403 1.0789762553 1.8766651154 0.1316804892 0.0243250000 1085484013 0 402718720 0.2819179595 -0.1050588191 -0.0608856641 1086 43.4000000000 0.7139470577 1.0786401326 1.8766651154 0.1316198007 0.0531170000 1085486261 0 402718720 0.2847426236 -0.1002168879 -0.0618888661 1087 43.4400000000 0.7071321607 1.0782983590 1.8766651154 0.1315592065 0.0242500000 1085488509 0 402718720 0.2884886563 -0.0957445577 -0.0629328117 1088 43.4800000000 0.6969788671 1.0779478815 1.8766651154 0.1314987875 0.0233000000 1085490757 0 402718720 0.2963554263 -0.0898822993 -0.0654134527 1089 43.5200000000 0.6877731085 1.0775895943 1.8766651154 0.1314384469 0.0236590000 1085493517 0 402718720 0.3019225895 -0.0869125277 -0.0696308166 1090 43.5600000000 0.6779985428 1.0772229970 1.8766651154 0.1313785982 0.0236610000 1085495765 0 402718720 0.3048343658 -0.0870419517 -0.0758481547 1091 43.6000000000 0.5214686394 1.0767135979 1.8766651154 0.1314722594 0.0383450000 1088904709 0 402718720 0.4823180437 0.0086025130 -0.1215873435 1092 43.6400000000 1.0287052393 1.0766696342 1.8766651154 0.1354363173 0.0351680000 1096281341 0 402718720 0.5370917916 0.4492152929 0.3407703340 1093 43.6800000000 1.0486217737 1.0766439729 1.8766651154 0.1353793948 0.0325970000 1088910589 0 402718720 0.5292160511 0.4629563987 0.3629490137 1094 43.7200000000 0.8488758206 1.0764357753 1.8766651154 0.1377903205 0.0287620000 1096287221 0 402718720 0.3663026690 0.0644387528 0.2138466537 1095 43.7600000000 0.8418122530 1.0762215072 1.8766651154 0.1377286425 0.0302120000 1085502453 0 402718720 0.3622266650 0.0634727180 0.2093791217 1096 43.8000000000 0.8195920587 1.0759873563 1.8766651154 0.1376692284 0.0326240000 1085504701 0 402718720 0.3629966080 0.0690688267 0.1880958825 1097 43.8400000000 0.7710622549 1.0757093936 1.8766651154 0.1376157761 0.0432780000 1088913917 0 402718720 0.3703396916 0.0750404671 0.1403090060 1098 43.8800000000 0.8881325722 1.0755385586 1.8766651154 0.1376102909 0.0601340000 1096290549 0 402718720 0.3826284707 -0.0072674896 0.3089589179 1099 43.9200000000 0.8817371726 1.0753622152 1.8766651154 0.1375478102 0.0321870000 1085514085 0 402718720 0.3797203004 -0.0011681026 0.3057559133 1100 43.9600000000 0.8739374876 1.0751791018 1.8766651154 0.1374853676 0.0284640000 1085516333 0 402718720 0.3765859902 0.0027567684 0.3018628061 1101 44.0000000000 0.8547924757 1.0749789323 1.8766651154 0.1374265330 0.0322880000 1085518581 0 402718720 0.3717809021 -0.0013430065 0.2827694118 1102 44.0400000000 0.8436549306 1.0747690194 1.8766651154 0.1373646714 0.0315480000 1085520829 0 402718720 0.3736614585 -0.0022582863 0.2785012424 1103 44.0800000000 0.8280369639 1.0745453276 1.8766651154 0.1373038754 0.0332870000 1085524397 0 402718720 0.3740112484 -0.0034355815 0.2680480778 1104 44.1200000000 0.8150567412 1.0743102836 1.8766651154 0.1372439486 0.0281950000 1085526645 0 402718720 0.3698260784 -0.0024598790 0.2588090301 1105 44.1600000000 0.8010060191 1.0740629494 1.8766651154 0.1371833279 0.0316490000 1085528893 0 402718720 0.3699846566 -0.0063378261 0.2508162856 1106 44.2000000000 0.7929682136 1.0738087950 1.8766651154 0.1371217781 0.0309020000 1085531141 0 402718720 0.3678333163 -0.0068055061 0.2476958930 1107 44.2400000000 0.7181182504 1.0734874847 1.8766651154 0.1370735476 0.0304860000 1085533389 0 402718720 0.3831345737 -0.0077531687 0.1719672382 1108 44.2800000000 0.6909657717 1.0731422485 1.8766651154 0.1370183175 0.0342600000 1088943177 0 402718720 0.3803807795 -0.0075970665 0.1403446347 1109 44.3200000000 0.9458017349 1.0730274239 1.8766651154 0.1370047947 0.0317980000 1096319809 0 402718720 0.2372713387 0.0432692543 0.3590870500 1110 44.3600000000 0.9350096583 1.0729030835 1.8766651154 0.1369433298 0.0628590000 1088949057 0 402718720 0.2389905006 0.0456852578 0.3544369936 1111 44.4000000000 0.9307579398 1.0727751401 1.8766651154 0.1368817078 0.0121940000 1085538673 0 402718720 0.2396901995 0.0465416536 0.3566021323 1112 44.4400000000 0.9262294769 1.0726433545 1.8766651154 0.1368201891 0.0182970000 1085540921 0 402718720 0.2404760271 0.0478009507 0.3594145179 1113 44.4800000000 0.9209019542 1.0725070190 1.8766651154 0.1367588811 0.0187150000 1085543169 0 402718720 0.2419841290 0.0491206385 0.3615596890 1114 44.5200000000 0.9170114994 1.0723674359 1.8766651154 0.1366975635 0.0189120000 1085545417 0 402718720 0.2426350117 0.0498680174 0.3635023534 1115 44.5600000000 0.9121062160 1.0722237039 1.8766651154 0.1366362706 0.0191170000 1085547665 0 402718720 0.2439669669 0.0507517532 0.3651878536 1116 44.6000000000 0.9078491926 1.0720764149 1.8766651154 0.1365751480 0.0191540000 1085549913 0 402718720 0.2452564389 0.0517291129 0.3677698374 1117 44.6400000000 0.9022960067 1.0719244181 1.8766651154 0.1365140827 0.0189850000 1085552161 0 402718720 0.2463423014 0.0524928607 0.3699167073 1118 44.6800000000 0.8986256719 1.0717694103 1.8766651154 0.1364530257 0.0184150000 1085554409 0 402718720 0.2473368198 0.0528451800 0.3716621399 1119 44.7200000000 0.8943294883 1.0716108402 1.8766651154 0.1363921183 0.0178070000 1085556657 0 402718720 0.2486528307 0.0534760132 0.3738913238 1120 44.7600000000 0.8894271851 1.0714481762 1.8766651154 0.1363313565 0.0169370000 1085558905 0 402718720 0.2497097105 0.0540352054 0.3762167394 1121 44.8000000000 0.8852863312 1.0712821086 1.8766651154 0.1362705626 0.0168380000 1085561153 0 402718720 0.2509300709 0.0548139326 0.3783085644 1122 44.8400000000 0.8812652230 1.0711127530 1.8766651154 0.1362097843 0.0164640000 1085563401 0 402718720 0.2516182065 0.0559578426 0.3802480102 1123 44.8800000000 0.8772115111 1.0709400894 1.8766651154 0.1361490989 0.0158910000 1085565649 0 402718720 0.2528786957 0.0571187958 0.3823192418 1124 44.9200000000 0.8731493354 1.0707641190 1.8766651154 0.1360885312 0.0174810000 1085567897 0 402718720 0.2539727986 0.0577489398 0.3842698634 1125 44.9600000000 0.8687611222 1.0705845608 1.8766651154 0.1360280272 0.0168210000 1085570145 0 402718720 0.2548609078 0.0588550717 0.3861544430 1126 45.0000000000 0.8649043441 1.0704018963 1.8766651154 0.1359676289 0.0172040000 1085572393 0 402718720 0.2555675507 0.0592514277 0.3879658282 1127 45.0400000000 0.8616608381 1.0702166780 1.8766651154 0.1359072635 0.0173190000 1085574641 0 402718720 0.2561762035 0.0601270273 0.3896692097 1128 45.0800000000 0.8582856059 1.0700287958 1.8766651154 0.1358470111 0.0171390000 1085576889 0 402718720 0.2571080029 0.0606233329 0.3914260864 1129 45.1200000000 0.8550384045 1.0698383703 1.8766651154 0.1357868486 0.0172510000 1085579137 0 402718720 0.2582490444 0.0611858070 0.3932864070 1130 45.1600000000 0.8519985676 1.0696455917 1.8766651154 0.1357267320 0.0178080000 1085581385 0 402718720 0.2590062916 0.0617708080 0.3950974643 1131 45.2000000000 0.8493263721 1.0694507914 1.8766651154 0.1356666748 0.0178730000 1085583633 0 402718720 0.2595565021 0.0623497143 0.3965701163 1132 45.2400000000 0.8472096920 1.0692544653 1.8766651154 0.1356067263 0.0176860000 1085585881 0 402718720 0.2604957819 0.0626441017 0.3980104327 1133 45.2800000000 0.8443787694 1.0690559872 1.8766651154 0.1355469138 0.0181400000 1085588129 0 402718720 0.2613039315 0.0629023165 0.3997408450 1134 45.3200000000 0.8421494365 1.0688558932 1.8766651154 0.1354871606 0.0175890000 1085590377 0 402718720 0.2621921897 0.0636320040 0.4015522599 1135 45.3600000000 0.8401516080 1.0686543917 1.8766651154 0.1354275058 0.0181000000 1085592625 0 402718720 0.2631823719 0.0639962852 0.4030142426 1136 45.4000000000 0.8376713991 1.0684510616 1.8766651154 0.1353678870 0.0185700000 1085594873 0 402718720 0.2643837929 0.0648057461 0.4045561850 1137 45.4400000000 0.8346514702 1.0682454331 1.8766651154 0.1353083209 0.0187300000 1085597121 0 402718720 0.2648974061 0.0656250268 0.4060367942 1138 45.4800000000 0.8319522738 1.0680377941 1.8766651154 0.1352488260 0.0182590000 1085599369 0 402718720 0.2659192681 0.0659657940 0.4074602723 1139 45.5200000000 0.8304499984 1.0678292008 1.8766651154 0.1351894407 0.0191930000 1085601617 0 402718720 0.2665996552 0.0670252144 0.4087588787 1140 45.5600000000 0.8276956081 1.0676185573 1.8766651154 0.1351301136 0.0194030000 1085603865 0 402718720 0.2667423785 0.0675534010 0.4097772241 1141 45.6000000000 0.8254942298 1.0674063536 1.8766651154 0.1350708391 0.0191840000 1085606113 0 402718720 0.2672694027 0.0679560751 0.4109969437 1142 45.6400000000 0.8237836957 1.0671930238 1.8766651154 0.1350116810 0.0190990000 1085608361 0 402718720 0.2684959769 0.0685608089 0.4124635160 1143 45.6800000000 0.8228386641 1.0669792405 1.8766651154 0.1349525945 0.0191260000 1085610609 0 402718720 0.2693159580 0.0690432265 0.4138332903 1144 45.7200000000 0.8212124109 1.0667644093 1.8766651154 0.1348935826 0.0188510000 1085612857 0 402718720 0.2701107264 0.0692224875 0.4150891006 1145 45.7600000000 0.8191995025 1.0665481954 1.8766651154 0.1348346694 0.0524200000 1085615105 0 402718720 0.2711132169 0.0696989894 0.4164055288 1146 45.8000000000 0.8179658055 1.0663312824 1.8766651154 0.1347758198 0.0206500000 1085617353 0 402718720 0.2720178664 0.0703274608 0.4179481268 1147 45.8400000000 0.8168300390 1.0661137573 1.8766651154 0.1347170399 0.0195220000 1085619601 0 402718720 0.2727516592 0.0705146194 0.4191735685 1148 45.8800000000 0.8152885437 1.0658952684 1.8766651154 0.1346583439 0.0199610000 1085621849 0 402718720 0.2735139728 0.0710005090 0.4206180871 1149 45.9200000000 0.8138932586 1.0656759455 1.8766651154 0.1345997384 0.0198020000 1085624097 0 402718720 0.2745551169 0.0713856593 0.4222169220 1150 45.9600000000 0.8123617768 1.0654556723 1.8766651154 0.1345412054 0.0179180000 1085626345 0 402718720 0.2751542032 0.0717604458 0.4237434268 1151 46.0000000000 0.8104137182 1.0652340894 1.8766651154 0.1344827870 0.0195430000 1085628593 0 402718720 0.2760920525 0.0720380023 0.4255070984 1152 46.0400000000 0.8083075285 1.0650110629 1.8766651154 0.1344245024 0.0198230000 1085630841 0 402718720 0.2770017684 0.0727089643 0.4274230003 1153 46.0800000000 0.8056800961 1.0647861444 1.8766651154 0.1343663342 0.0200210000 1085633089 0 402718720 0.2774666548 0.0730207860 0.4291561246 1154 46.1200000000 0.8029914498 1.0645592860 1.8766651154 0.1343081451 0.0215780000 1085635337 0 402718720 0.2779104710 0.0738091469 0.4309250712 1155 46.1600000000 0.7986885905 1.0643290949 1.8766651154 0.1342502896 0.0193740000 1085637585 0 402718720 0.2787322402 0.0741179511 0.4327920973 1156 46.2000000000 0.7962433100 1.0640971868 1.8766651154 0.1341922427 0.0197040000 1085639833 0 402718720 0.2793734968 0.0754166692 0.4348427653 1157 46.2400000000 0.7941450477 1.0638638660 1.8766651154 0.1341343192 0.0207940000 1085642081 0 402718720 0.2803145051 0.0764996409 0.4369671941 1158 46.2800000000 0.7879844904 1.0636256282 1.8766651154 0.1340770078 0.2421930000 1089440653 0 402718720 0.2818086147 0.0779500008 0.4410145581 1159 46.3200000000 0.7865461707 1.0633865605 1.8766651154 0.1340311553 0.0183600000 1089444221 0 402718720 0.2761474550 0.1127585098 0.4230506718 1160 46.3600000000 0.7825593352 1.0631444681 1.8766651154 0.1339735143 0.0214860000 1089446469 0 402718720 0.2766517401 0.1137088388 0.4250636995 1161 46.4000000000 0.7787101269 1.0628994772 1.8766651154 0.1339159877 0.0543660000 1089448717 0 402718720 0.2776834369 0.1147828847 0.4264680147 1162 46.4400000000 0.7762666941 1.0626528053 1.8766651154 0.1338585784 0.0210730000 1089450965 0 402718720 0.2779881358 0.1155043021 0.4288899601 1163 46.4800000000 0.7733212709 1.0624040250 1.8766651154 0.1338011280 0.0196560000 1089453213 0 402718720 0.2785835266 0.1163673624 0.4309365153 1164 46.5200000000 0.7707395554 1.0621534541 1.8766651154 0.1337438482 0.0194700000 1089455461 0 402718720 0.2792328000 0.1169476435 0.4327697158 1165 46.5600000000 0.7683499455 1.0619012623 1.8766651154 0.1336867389 0.0186070000 1089457709 0 402718720 0.2805734575 0.1177920625 0.4348074198 1166 46.6000000000 0.7649140954 1.0616465563 1.8766651154 0.1336295778 0.0292740000 1089459957 0 402718720 0.2807392478 0.1187050492 0.4370972514 1167 46.6400000000 0.7612623572 1.0613891577 1.8766651154 0.1335725567 0.0185950000 1089462205 0 402718720 0.2813775539 0.1193957776 0.4388435185 1168 46.6800000000 0.7589835525 1.0611302487 1.8766651154 0.1335154920 0.0184870000 1089464453 0 402718720 0.2817768455 0.1199832931 0.4409215152 1169 46.7200000000 0.7557533979 1.0608690196 1.8766651154 0.1334585202 0.0215420000 1089466701 0 402718720 0.2820596099 0.1206665859 0.4427757859 1170 46.7600000000 0.7518373132 1.0606048900 1.8766651154 0.1334017421 0.0203500000 1089468949 0 402718720 0.2823413312 0.1212655604 0.4444325566 1171 46.8000000000 0.7483854890 1.0603382637 1.8766651154 0.1333451691 0.0197200000 1089471197 0 402718720 0.2833293676 0.1223297939 0.4466815293 1172 46.8400000000 0.7447311282 1.0600689743 1.8766651154 0.1332885828 0.0220310000 1089473445 0 402718720 0.2832789719 0.1234327108 0.4486896694 1173 46.8800000000 0.7416421771 1.0597975107 1.8766651154 0.1332318439 0.0226680000 1089475693 0 402718720 0.2836036682 0.1240911335 0.4507439137 1174 46.9200000000 0.7392930984 1.0595245086 1.8766651154 0.1331752469 0.0196010000 1089477941 0 402718720 0.2838893235 0.1250679791 0.4528014362 1175 46.9600000000 0.7365952134 1.0592496752 1.8766651154 0.1331186388 0.0221700000 1089480189 0 402718720 0.2842524350 0.1251955628 0.4544501901 1176 47.0000000000 0.7312232852 1.0589707412 1.8766651154 0.1330627276 0.0224740000 1089482437 0 402718720 0.2849785089 0.1264904141 0.4582717121 1177 47.0400000000 0.7295971513 1.0586908996 1.8766651154 0.1330062835 0.0220250000 1089484685 0 402718720 0.2855719626 0.1272064447 0.4601831138 1178 47.0800000000 0.7281712890 1.0584103226 1.8766651154 0.1329498940 0.0223730000 1089486933 0 402718720 0.2863642871 0.1272961497 0.4622394443 1179 47.1200000000 0.7259883881 1.0581283702 1.8766651154 0.1328935885 0.0219120000 1089489181 0 402718720 0.2863462269 0.1276288778 0.4639534354 1180 47.1600000000 0.7236400247 1.0578449055 1.8766651154 0.1328376565 0.0218190000 1089491429 0 402718720 0.2870399058 0.1280057728 0.4659085870 1181 47.2000000000 0.7195222974 1.0575584342 1.8766651154 0.1327815524 0.0224510000 1089493677 0 402718720 0.2868197262 0.1285078824 0.4675750434 1182 47.2400000000 0.7152421474 1.0572688265 1.8766651154 0.1327254455 0.0297270000 1089495925 0 402718720 0.2852453887 0.1284879297 0.4688110948 1183 47.2800000000 0.7130160928 1.0569778267 1.8766651154 0.1326694797 0.0333590000 1089498173 0 402718720 0.2857730985 0.1291086525 0.4709557593 1184 47.3200000000 0.7135888934 1.0566878023 1.8766651154 0.1326136239 0.0237250000 1089500421 0 402718720 0.2872925699 0.1296250224 0.4734455049 1185 47.3600000000 0.7142180204 1.0563987983 1.8766651154 0.1325579264 0.0239160000 1089502669 0 402718720 0.2883975506 0.1295093745 0.4754818082 1186 47.4000000000 0.7125639915 1.0561088870 1.8766651154 0.1325022641 0.0224110000 1089504917 0 402718720 0.2889517248 0.1293918043 0.4771948457 1187 47.4400000000 0.7119393349 1.0558189379 1.8766651154 0.1324466237 0.0214580000 1089507165 0 402718720 0.2891162336 0.1299545020 0.4793247283 1188 47.4800000000 0.7101663947 1.0555279846 1.8766651154 0.1323910014 0.0224020000 1089509413 0 402718720 0.2891735435 0.1301172078 0.4813409448 1189 47.5200000000 0.7082734704 1.0552359286 1.8766651154 0.1323355684 0.0221530000 1089511661 0 402718720 0.2891592681 0.1303358525 0.4829729795 1190 47.5600000000 0.7079962492 1.0549441306 1.8766651154 0.1322800607 0.0581250000 1089513909 0 402718720 0.2899490893 0.1305878013 0.4850956500 1191 47.6000000000 0.7087675333 1.0546534701 1.8766651154 0.1322245934 0.0226220000 1089516157 0 402718720 0.2908917069 0.1301645339 0.4870183468 1192 47.6400000000 0.7118114233 1.0543658510 1.8766651154 0.1321692804 0.0224150000 1089518405 0 402718720 0.2920140028 0.1299306154 0.4891091287 1193 47.6800000000 0.7133603096 1.0540800123 1.8766651154 0.1321139410 0.0239650000 1089520653 0 402718720 0.2934261560 0.1304995120 0.4911144674 1194 47.7200000000 0.7122625709 1.0537937330 1.8766651154 0.1320587128 0.0232700000 1089522901 0 402718720 0.2936288714 0.1303096712 0.4927924871 1195 47.7600000000 0.7137120962 1.0535091459 1.8766651154 0.1320036332 0.0241780000 1089525149 0 402718720 0.2948711812 0.1303394437 0.4948805571 1196 47.8000000000 0.7174182534 1.0532281334 1.8766651154 0.1319486758 0.0231390000 1089527397 0 402718720 0.2961823642 0.1305077523 0.4971363544 1197 47.8400000000 0.7199770808 1.0529497282 1.8766651154 0.1318937758 0.0240130000 1089529645 0 402718720 0.2972368598 0.1309730858 0.4992845654 1198 47.8800000000 0.7211935520 1.0526728032 1.8766651154 0.1318390708 0.0227320000 1089531893 0 402718720 0.2979763150 0.1308984905 0.5013877749 1199 47.9200000000 0.7225835919 1.0523974994 1.8766651154 0.1317843180 0.0238510000 1089534141 0 402718720 0.2990653515 0.1313247681 0.5034729242 1200 47.9600000000 0.7223242521 1.0521224384 1.8766651154 0.1317295375 0.0248860000 1089536389 0 402718720 0.2994066775 0.1309756339 0.5049920678 1201 48.0000000000 0.7262581587 1.0518511109 1.8766651154 0.1316750296 0.1316980000 1093242453 0 402718720 0.3006621599 0.1315380335 0.5073651075 1202 48.0400000000 0.7301146984 1.0515834433 1.8766651154 0.1316207062 0.0286090000 1093246021 0 402718720 0.3021402359 0.1325504184 0.5101638436 1203 48.0800000000 0.7323002815 1.0513180376 1.8766651154 0.1315661677 0.0239190000 1093248269 0 402718720 0.3029021919 0.1332436055 0.5121978521 1204 48.1200000000 0.7346906662 1.0510550580 1.8766651154 0.1315120427 0.0601380000 1093250517 0 402718720 0.3038561046 0.1333330423 0.5144076347 1205 48.1600000000 0.7376913428 1.0507950051 1.8766651154 0.1314577751 0.0234730000 1093252765 0 402718720 0.3048582375 0.1339588612 0.5167161822 1206 48.2000000000 0.7406908870 1.0505378707 1.8766651154 0.1314034953 0.0216530000 1093255013 0 402718720 0.3059669137 0.1342886835 0.5187802315 1207 48.2400000000 0.7425968647 1.0502827415 1.8766651154 0.1313492235 0.0220250000 1093257261 0 402718720 0.3066283166 0.1343285590 0.5206599236 1208 48.2800000000 0.7458901405 1.0500307608 1.8766651154 0.1312950597 0.0214520000 1093259509 0 402718720 0.3077754974 0.1346344203 0.5225881934 1209 48.3200000000 0.7494061589 1.0497821052 1.8766651154 0.1312409542 0.0208080000 1093261757 0 402718720 0.3086820245 0.1356106251 0.5248854756 1210 48.3600000000 0.7501688004 1.0495344909 1.8766651154 0.1311868509 0.0198200000 1093264005 0 402718720 0.3088146448 0.1358310580 0.5267375708 1211 48.4000000000 0.7523882985 1.0492891184 1.8766651154 0.1311327517 0.0404050000 1093266253 0 402718720 0.3097442091 0.1360152215 0.5286048651 1212 48.4400000000 0.7585332990 1.0490492208 1.8766651154 0.1310792952 0.0226140000 1093268501 0 402718720 0.3113910258 0.1373078674 0.5328103304 1213 48.4800000000 0.7592874169 1.0488103405 1.8766651154 0.1310254332 0.0221700000 1093270749 0 402718720 0.3115634322 0.1377631277 0.5344728827 1214 48.5200000000 0.7593120337 1.0485718740 1.8766651154 0.1309715807 0.0249990000 1093272997 0 402718720 0.3119133413 0.1378499717 0.5359445810 1215 48.5600000000 0.7599945664 1.0483343619 1.8766651154 0.1309177647 0.0574500000 1093275245 0 402718720 0.3118837774 0.1380795985 0.5375642180 1216 48.6000000000 0.7618049383 1.0480987291 1.8766651154 0.1308644648 0.0230020000 1093277493 0 402718720 0.3131521046 0.1392610818 0.5406916738 1217 48.6400000000 0.7643145919 1.0478655458 1.8766651154 0.1308106996 0.0242040000 1093279741 0 402718720 0.3130669892 0.1394968480 0.5423986912 1218 48.6800000000 0.7662607431 1.0476343431 1.8766651154 0.1307571224 0.0239390000 1093281989 0 402718720 0.3135547638 0.1398115605 0.5440496802 1219 48.7200000000 0.7681758404 1.0474050909 1.8766651154 0.1307036529 0.0245080000 1093284237 0 402718720 0.3139522076 0.1397692710 0.5453656912 1220 48.7600000000 0.7687486410 1.0471766839 1.8766651154 0.1306501489 0.0250280000 1093286485 0 402718720 0.3138303161 0.1403473914 0.5468477607 1221 48.8000000000 0.7690638900 1.0469489093 1.8766651154 0.1305967338 0.0251200000 1093288733 0 402718720 0.3141346872 0.1406359524 0.5483245850 1222 48.8400000000 0.7688601613 1.0467213408 1.8766651154 0.1305433185 0.0251330000 1093290981 0 402718720 0.3139810860 0.1411462873 0.5497169495 1223 48.8800000000 0.7699663639 1.0464950489 1.8766651154 0.1304899347 0.0229370000 1093293229 0 402718720 0.3142041862 0.1413998157 0.5513385534 1224 48.9200000000 0.7710366249 1.0462700012 1.8766651154 0.1304366610 0.0234360000 1093295477 0 402718720 0.3148776293 0.1416262537 0.5528748631 1225 48.9600000000 0.7719397545 1.0460460581 1.8766651154 0.1303835367 0.0245930000 1093297725 0 402718720 0.3147510886 0.1418324113 0.5546418428 1226 49.0000000000 0.7724508047 1.0458228972 1.8766651154 0.1303304434 0.0257900000 1093299973 0 402718720 0.3143876195 0.1421009451 0.5561445951 1227 49.0400000000 0.7728136182 1.0456003958 1.8766651154 0.1302773599 0.0260720000 1093302221 0 402718720 0.3142054379 0.1422207654 0.5577424765 1228 49.0800000000 0.7729169726 1.0453783409 1.8766651154 0.1302243231 0.0256870000 1093304469 0 402718720 0.3141288757 0.1426658630 0.5593681931 1229 49.1200000000 0.7732196450 1.0451568936 1.8766651154 0.1301714250 0.1689290000 1097015497 0 402718720 0.3139651120 0.1427967101 0.5610326529 1230 49.1600000000 0.7740227580 1.0449364594 1.8766651154 0.1301186339 0.0255240000 1097019065 0 402718720 0.3137472570 0.1440928131 0.5636135936 1231 49.2000000000 0.7751467824 1.0447172963 1.8766651154 0.1300658520 0.0282600000 1097021313 0 402718720 0.3136670887 0.1443955004 0.5652331114 1232 49.2400000000 0.7755292654 1.0444987996 1.8766651154 0.1300131412 0.0256850000 1097023561 0 402718720 0.3134665191 0.1446943879 0.5668951869 1233 49.2800000000 0.7744138241 1.0442797525 1.8766651154 0.1299604312 0.0247440000 1097025809 0 402718720 0.3127838075 0.1450052112 0.5684784651 1234 49.3200000000 0.7742990255 1.0440609675 1.8766651154 0.1299078153 0.0247750000 1097028057 0 402718720 0.3121780753 0.1451759785 0.5703029037 1235 49.3600000000 0.7753168344 1.0438433609 1.8766651154 0.1298552750 0.0213610000 1097030305 0 402718720 0.3120219409 0.1455388963 0.5720815063 1236 49.4000000000 0.7754056454 1.0436261783 1.8766651154 0.1298027893 0.0230970000 1097032553 0 402718720 0.3115606904 0.1459204108 0.5737487078 1237 49.4400000000 0.7779770494 1.0434114256 1.8766651154 0.1297504380 0.0214120000 1097034801 0 402718720 0.3116520047 0.1460790038 0.5757282376 1238 49.4800000000 0.7794358134 1.0431981981 1.8766651154 0.1296980653 0.0220220000 1097037049 0 402718720 0.3116667271 0.1464529037 0.5773633718 1239 49.5200000000 0.7805917263 1.0429862478 1.8766651154 0.1296458564 0.0238350000 1097039297 0 402718720 0.3115316927 0.1469642818 0.5790464878 1240 49.5600000000 0.7825452089 1.0427762147 1.8766651154 0.1295937134 0.0248580000 1097041545 0 402718720 0.3115082383 0.1476171762 0.5809582472 1241 49.6000000000 0.7827004790 1.0425666452 1.8766651154 0.1295415400 0.0248160000 1097043793 0 402718720 0.3109906614 0.1482782513 0.5825322866 1242 49.6400000000 0.7837594151 1.0423582658 1.8766651154 0.1294894943 0.0351220000 1097046041 0 402718720 0.3108969927 0.1484725773 0.5838972330 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 10:18:29 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287480354 0.0606188439 0.0606188439 0.0606188439 -nan 0.0056280000 87406972 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644249916 0.0584248155 0.0595218297 0.0606188439 0.0380232558 0.0403390000 104353745 0 402718720 -0.0139900176 0.0028781511 0.0103880437 3 1305031229.5966000557 0.0752182528 0.0647539708 0.0752182528 0.0396648546 0.0391560000 107626553 0 402718720 -0.0274761934 -0.0215268061 0.0118602691 4 1305031229.6287529469 0.0634180382 0.0644199876 0.0752182528 0.0354669120 0.0360140000 107630041 0 402718720 -0.0128795030 0.0008030242 0.0091515575 5 1305031229.6646571159 0.0764097944 0.0668179490 0.0764097944 0.0337572874 0.0272410000 107633713 0 402718720 -0.0370338447 -0.0169226862 0.0191256125 6 1305031229.6968269348 0.0754901692 0.0682633190 0.0764097944 0.0302522567 0.0295220000 107637657 0 402718720 -0.0354010500 -0.0152470591 0.0189952180 7 1305031229.7290639877 0.0667777434 0.0680510939 0.0764097944 0.0294226463 0.0306300000 107640745 0 402718720 -0.0221805349 -0.0060968576 0.0176796578 8 1305031229.7648479939 0.0780076012 0.0692956573 0.0780076012 0.0287834270 0.0453240000 119984033 0 402718720 -0.0384170860 -0.0167276673 0.0202743374 9 1305031229.7969090939 0.0740306228 0.0698217646 0.0780076012 0.0273369309 0.0335660000 123647617 0 402718720 -0.0337364338 -0.0149254035 0.0220656097 10 1305031229.8256130219 0.0726564750 0.0701052357 0.0780076012 0.0271658917 0.0374490000 126844441 0 402718720 -0.0290202629 -0.0124114444 0.0198791493 11 1305031229.8630549908 0.0757242292 0.0706160532 0.0780076012 0.0259887531 0.0352990000 126847809 0 402718720 -0.0436535031 -0.0101156356 0.0233191997 12 1305031229.8969290257 0.0741436034 0.0709100158 0.0780076012 0.0257753206 0.0283940000 126850953 0 402718720 -0.0457052812 -0.0060933363 0.0238280836 13 1305031229.9262480736 0.0743852779 0.0711773436 0.0780076012 0.0254725708 0.0251570000 126854041 0 402718720 -0.0450940616 -0.0044373954 0.0216530655 14 1305031229.9661600590 0.1041255221 0.0735307849 0.1041255221 0.0293875722 0.0239820000 126857409 0 402718720 -0.0852057114 -0.0148850707 0.0179468282 15 1305031229.9979169369 0.1315160543 0.0773964696 0.1315160543 0.0291761506 0.0599890000 145693597 0 402718720 -0.1210066080 -0.0187076703 0.0168976001 16 1305031230.0299909115 0.1440818757 0.0815643074 0.1440818757 0.0292764703 0.0325140000 149355949 0 402718720 -0.1267245710 -0.0446159728 0.0186029132 17 1305031230.0656869411 0.1593517065 0.0861400368 0.1593517065 0.0297790761 0.0352510000 152553061 0 402718720 -0.1493032277 -0.0454850793 0.0191958994 18 1305031230.0982420444 0.1464217454 0.0894890206 0.1593517065 0.0297947831 0.0322810000 152559405 0 402718720 -0.1359266192 -0.0443930961 0.0188047644 19 1305031230.1299190521 0.1411728412 0.0922092217 0.1593517065 0.0291777960 0.0268650000 152562549 0 402718720 -0.1321636736 -0.0440290459 0.0195826944 20 1305031230.1657710075 0.1387285739 0.0945351893 0.1593517065 0.0284633460 0.0240620000 152565805 0 402718720 -0.1332128793 -0.0435367525 0.0202160329 21 1305031230.1977720261 0.1388257444 0.0966442634 0.1593517065 0.0279747998 0.0274210000 152568949 0 402718720 -0.1360283196 -0.0433840305 0.0198863670 22 1305031230.2298300266 0.1372964233 0.0984920888 0.1593517065 0.0274924075 0.0539150000 164880193 0 402718720 -0.1375014484 -0.0429847017 0.0205065198 23 1305031230.2655799389 0.1134492382 0.0991423997 0.1593517065 0.0282314596 0.0161420000 168543473 0 402718720 -0.1149446145 -0.0376318321 0.0262981653 24 1305031230.2979819775 0.1139528751 0.0997595028 0.1593517065 0.0276904495 0.0370870000 171738809 0 402718720 -0.1192660630 -0.0368246436 0.0261687543 25 1305031230.3256850243 0.1116639301 0.1002356799 0.1593517065 0.0272974365 0.0245170000 171741841 0 402718720 -0.1198579296 -0.0371925458 0.0276606139 26 1305031230.3656499386 0.1089651063 0.1005714271 0.1593517065 0.0269378135 0.0301090000 171745209 0 402718720 -0.1193153709 -0.0358843803 0.0272067636 27 1305031230.3972649574 0.1070606261 0.1008117678 0.1593517065 0.0265467935 0.0627630000 171748409 0 402718720 -0.1200095192 -0.0359475091 0.0286831614 28 1305031230.4256699085 0.1057022065 0.1009864263 0.1593517065 0.0261387480 0.0286900000 171751385 0 402718720 -0.1225092933 -0.0345529020 0.0292209089 29 1305031230.4652199745 0.1024164930 0.1010357389 0.1593517065 0.0261141195 0.0547050000 184058753 0 402718720 -0.1241494790 -0.0329444520 0.0301160328 30 1305031230.4972279072 0.0966034159 0.1008879948 0.1593517065 0.0260420154 0.0379150000 187721161 0 402718720 -0.1203404739 -0.0312354602 0.0311206635 31 1305031230.5267200470 0.0939587876 0.1006644720 0.1593517065 0.0261102258 0.0331060000 190916385 0 402718720 -0.1233202741 -0.0303918626 0.0333533138 32 1305031230.5660839081 0.0919473469 0.1003920619 0.1593517065 0.0260912657 0.0297810000 190919753 0 402718720 -0.1235274673 -0.0304514468 0.0316968299 33 1305031230.5988249779 0.0899353027 0.1000751904 0.1593517065 0.0260422225 0.0412950000 190926225 0 402718720 -0.1266914606 -0.0295643266 0.0328176208 34 1305031230.6260280609 0.0889827162 0.0997489411 0.1593517065 0.0258513642 0.0270920000 190935657 0 402718720 -0.1271230429 -0.0296710040 0.0314562768 35 1305031230.6657950878 0.0824181437 0.0992537755 0.1593517065 0.0255106245 0.0283230000 190939025 0 402718720 -0.1222020835 -0.0295383409 0.0347174034 36 1305031230.6979320049 0.0788700283 0.0986875603 0.1593517065 0.0254595676 0.0491720000 203247369 0 402718720 -0.1204979941 -0.0331095457 0.0418521762 37 1305031230.7256710529 0.0769765601 0.0981007765 0.1593517065 0.0251872375 0.0430960000 206909609 0 402718720 -0.1213161424 -0.0317779370 0.0414481610 38 1305031230.7658538818 0.0753397793 0.0975018029 0.1593517065 0.0249892320 0.0431440000 210105169 0 402718720 -0.1242952868 -0.0310696773 0.0411602631 39 1305031230.7973029613 0.0736976191 0.0968914392 0.1593517065 0.0250345003 0.0332800000 210108313 0 402718720 -0.1248950064 -0.0322243571 0.0427541174 40 1305031230.8257288933 0.0635252893 0.0960572855 0.1593517065 0.0261612598 0.0410040000 210111289 0 402718720 -0.1155022830 -0.0298310462 0.0507805720 41 1305031230.8655230999 0.0610565729 0.0952036095 0.1593517065 0.0322030483 0.0008600000 220907361 0 402718720 -0.1155022830 -0.0298310462 0.0507805720 42 1305031230.8973789215 0.0531816930 0.0942030877 0.1593517065 0.0397582354 0.0019680000 222643561 0 402718720 -0.1281188875 -0.0157830771 0.1000723988 43 1305031230.9258599281 0.1254279464 0.0949292472 0.1593517065 0.0463833130 0.0008490000 222724713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 44 1305031230.9649760723 0.1247301176 0.0956065397 0.1593517065 0.0463952268 0.0006950000 224383985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 45 1305031230.9970800877 0.1241264343 0.0962403152 0.1593517065 0.0459359987 0.0005620000 224386945 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 46 1305031231.0256528854 0.1237878352 0.0968391743 0.1593517065 0.0454254521 0.0012190000 224389681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 47 1305031231.0644218922 0.1235383749 0.0974072424 0.1593517065 0.0449570921 0.0012520000 224392753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 48 1305031231.0967750549 0.1234181672 0.0979491367 0.1593517065 0.0444889798 0.0012550000 224395713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 49 1305031231.1257278919 0.1230736300 0.0984618814 0.1593517065 0.0440323934 0.0012340000 224398505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 50 1305031231.1652410030 0.1234240234 0.0989611243 0.1593517065 0.0437170552 0.0012620000 224401633 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 51 1305031231.1977469921 0.1240868792 0.0994537861 0.1593517065 0.0437928284 0.0012960000 224404593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 52 1305031231.2257111073 0.1253752261 0.0999522754 0.1593517065 0.0444637642 0.0012420000 224407329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 53 1305031231.2655940056 0.1278738827 0.1004790981 0.1593517065 0.0478834812 0.0012250000 224410457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 54 1305031231.2978460789 0.1306889355 0.1010385396 0.1593517065 0.0502972368 0.0013540000 224413417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 55 1305031231.3257410526 0.1333709210 0.1016264011 0.1593517065 0.0523957996 0.0013060000 224416153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 56 1305031231.3650660515 0.1371637881 0.1022609973 0.1593517065 0.0557768276 0.0013190000 224419281 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 57 1305031231.3971281052 0.1401359141 0.1029254695 0.1593517065 0.0570481918 0.0012990000 224422241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 58 1305031231.4256880283 0.1432436854 0.1036206111 0.1593517065 0.0577281298 0.0012870000 224424977 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 59 1305031231.4649178982 0.1472122371 0.1043594522 0.1593517065 0.0589249684 0.0012810000 224428105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 60 1305031231.4936690331 0.1500485986 0.1051209380 0.1593517065 0.0592722712 0.0012880000 224430897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 61 1305031231.5257549286 0.1523594707 0.1058953402 0.1593517065 0.0593870219 0.0012840000 224433857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 62 1305031231.5650520325 0.1561431885 0.1067057894 0.1593517065 0.0600512712 0.0013320000 224436929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 63 1305031231.5937368870 0.1587611735 0.1075320653 0.1593517065 0.0602427782 0.0012870000 224439721 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 64 1305031231.6257040501 0.1614542603 0.1083745996 0.1614542603 0.0604151639 0.0013600000 224442625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 65 1305031231.6650450230 0.1645831913 0.1092393472 0.1645831913 0.0610562238 0.0013400000 224445753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 66 1305031231.6937019825 0.1673429012 0.1101197040 0.1673429012 0.0613238300 0.0013210000 224461345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 67 1305031231.7258861065 0.1699954271 0.1110133716 0.1699954271 0.0617536366 0.0013460000 224464249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 68 1305031231.7654778957 0.1734861434 0.1119320888 0.1734861434 0.0631524972 0.0013350000 224467377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 69 1305031231.7937231064 0.1759183407 0.1128594258 0.1759183407 0.0638416208 0.0013470000 224470225 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 70 1305031231.8256859779 0.1786033064 0.1137986241 0.1786033064 0.0646113166 0.0013320000 224473073 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 71 1305031231.8649399281 0.1820185781 0.1147594685 0.1820185781 0.0666629935 0.0013720000 224476201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 72 1305031231.8937270641 0.1843197197 0.1157255831 0.1843197197 0.0672382391 0.0013700000 224478993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 73 1305031231.9257059097 0.1867381036 0.1166983573 0.1867381036 0.0676913585 0.0013690000 224481897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 74 1305031231.9650099277 0.1897463799 0.1176854928 0.1897463799 0.0685071863 0.0014110000 224485025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 75 1305031231.9937260151 0.1921337694 0.1186781365 0.1921337694 0.0685520574 0.0013730000 224487817 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 76 1305031232.0257899761 0.1942956150 0.1196731033 0.1942956150 0.0687706997 0.0014080000 224490777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 77 1305031232.0651218891 0.1974329501 0.1206829714 0.1974329501 0.0694769431 0.0013730000 224493849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 78 1305031232.0937249660 0.1993151307 0.1216910760 0.1993151307 0.0695045247 0.0014470000 224496697 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 79 1305031232.1256620884 0.2009128034 0.1226938827 0.2009128034 0.0694619338 0.0013980000 224499545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 80 1305031232.1650319099 0.2026102096 0.1236928368 0.2026102096 0.0696773705 0.0014140000 224502673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 81 1305031232.1937160492 0.2041755021 0.1246864500 0.2041755021 0.0697132540 0.0013990000 224505521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 82 1305031232.2256829739 0.2056804150 0.1256741812 0.2056804150 0.0697216824 0.0014410000 224508369 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 83 1305031232.2626910210 0.2067120671 0.1266505413 0.2067120671 0.0697437299 0.0014580000 224511441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 84 1305031232.2938549519 0.2081399560 0.1276206534 0.2081399560 0.0702188261 0.0014290000 224514345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 85 1305031232.3256189823 0.2088367194 0.1285761365 0.2088367194 0.0701075992 0.0014540000 224517193 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 86 1305031232.3647379875 0.2097847164 0.1295204223 0.2097847164 0.0701315269 0.0014860000 224520265 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 87 1305031232.3937139511 0.2101049274 0.1304466810 0.2101049274 0.0698779791 0.0014510000 224523169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 88 1305031232.4257209301 0.2102880627 0.1313539694 0.2102880627 0.0695752462 0.0014650000 224526017 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 89 1305031232.4647030830 0.2104586065 0.1322427856 0.2104586065 0.0693254909 0.0014840000 224529089 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 90 1305031232.4936499596 0.2104608268 0.1331118749 0.2104608268 0.0690667545 0.0015720000 224531937 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 91 1305031232.5257809162 0.2103668153 0.1339608303 0.2104608268 0.0688780693 0.0014990000 224534841 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 92 1305031232.5647139549 0.2107940316 0.1347959738 0.2107940316 0.0687977986 0.0015060000 224537969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 93 1305031232.5937221050 0.2111166716 0.1356166265 0.2111166716 0.0686870041 0.0015290000 224540705 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 94 1305031232.6257829666 0.2113649696 0.1364224599 0.2113649696 0.0686664853 0.0015330000 224543665 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 95 1305031232.6646950245 0.2113495618 0.1372111662 0.2113649696 0.0686488919 0.0015410000 224546793 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 96 1305031232.6937010288 0.2111783922 0.1379816582 0.2113649696 0.0685009974 0.0015080000 224549641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 97 1305031232.7258760929 0.2115807831 0.1387404120 0.2115807831 0.0684815578 0.0015410000 224552489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 98 1305031232.7617189884 0.2120845020 0.1394888211 0.2120845020 0.0684916827 0.0015100000 224555505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 99 1305031232.7936720848 0.2122517228 0.1402237999 0.2122517228 0.0686298493 0.0015240000 224558465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 100 1305031232.8257670403 0.2125117779 0.1409466797 0.2125117779 0.0685057242 0.0015420000 224561313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 101 1305031232.8616659641 0.2128475159 0.1416585692 0.2128475159 0.0683136948 0.0015530000 224564329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 102 1305031232.8936829567 0.2131042480 0.1423590170 0.2131042480 0.0680426334 0.0015650000 224567289 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 103 1305031232.9257559776 0.2137784958 0.1430524100 0.2137784958 0.0677238722 0.0015420000 224570137 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 104 1305031232.9616620541 0.2138487548 0.1437331441 0.2138487548 0.0673999261 0.0016120000 224573153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 105 1305031232.9936408997 0.2141455114 0.1444037381 0.2141455114 0.0671275908 0.0015530000 224576057 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 106 1305031233.0257461071 0.2137023807 0.1450574988 0.2141455114 0.0672739864 0.0016220000 224578905 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 107 1305031233.0616970062 0.2127298266 0.1456899505 0.2141455114 0.0675747713 0.0015710000 224581921 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 108 1305031233.0937008858 0.2116965055 0.1463011223 0.2141455114 0.0691376888 0.0015780000 224584769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 109 1305031233.1258459091 0.2110586166 0.1468952278 0.2141455114 0.0691914576 0.0016150000 224587673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 110 1305031233.1617441177 0.2108138502 0.1474763062 0.2141455114 0.0689275893 0.0016090000 224590689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 111 1305031233.1937611103 0.2097517252 0.1480373460 0.2141455114 0.0686793007 0.0016330000 224593537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 112 1305031233.2257630825 0.2075484544 0.1485686951 0.2141455114 0.0685651773 0.0015890000 224596497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 113 1305031233.2616870403 0.2042125762 0.1490611189 0.2141455114 0.0689271095 0.0016450000 224599513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 114 1305031233.2938020229 0.1984577775 0.1494944229 0.2141455114 0.0713054210 0.0017270000 224602361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 115 1305031233.3257980347 0.1934345812 0.1498765112 0.2141455114 0.0733989835 0.0017550000 224605265 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 116 1305031233.3617999554 0.1889068335 0.1502129795 0.2141455114 0.0744516605 0.0016980000 224608281 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 117 1305031233.3936851025 0.1833699942 0.1504963728 0.2141455114 0.0764878001 0.0016570000 224611185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 118 1305031233.4257080555 0.1798091084 0.1507447858 0.2141455114 0.0771370774 0.0017150000 224614033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 119 1305031233.4618360996 0.1770265400 0.1509656409 0.2141455114 0.0770790409 0.0016380000 224617105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 120 1305031233.4936919212 0.1743371189 0.1511604032 0.2141455114 0.0769754716 0.0016850000 224620009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 121 1305031233.5257079601 0.1724785566 0.1513365863 0.2141455114 0.0768499427 0.0016850000 224622857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 122 1305031233.5617849827 0.1705464125 0.1514940439 0.2141455114 0.0768648877 0.0016450000 224625929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 123 1305031233.5937600136 0.1678912640 0.1516273546 0.2141455114 0.0776203463 0.0016780000 224628777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 124 1305031233.6257069111 0.1666711122 0.1517486753 0.2141455114 0.0778023814 0.0016750000 224631681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 125 1305031233.6617000103 0.1658145338 0.1518612021 0.2141455114 0.0778091448 0.0016970000 224634753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 126 1305031233.6937789917 0.1651975960 0.1519670465 0.2141455114 0.0777118122 0.0016750000 224637601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 127 1305031233.7255749702 0.1656397283 0.1520747054 0.2141455114 0.0774041924 0.0017020000 224640561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 128 1305031233.7616429329 0.1669210941 0.1521906928 0.2141455114 0.0771410835 0.0017120000 224643577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 129 1305031233.7937469482 0.1689541340 0.1523206420 0.2141455114 0.0769140653 0.0017140000 224646481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 130 1305031233.8256869316 0.1704455763 0.1524600646 0.2141455114 0.0766223391 0.0017480000 224674985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 131 1305031233.8616130352 0.1718608141 0.1526081619 0.2141455114 0.0763295790 0.0017040000 224678001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 132 1305031233.8937180042 0.1736245304 0.1527673768 0.2141455114 0.0760562582 0.0017520000 224680961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 133 1305031233.9258410931 0.1751337647 0.1529355451 0.2141455114 0.0757832219 0.0017240000 224683809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 134 1305031233.9617478848 0.1766036749 0.1531121730 0.2141455114 0.0755124869 0.0017680000 224686825 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 135 1305031233.9937219620 0.1782487780 0.1532983700 0.2141455114 0.0753548441 0.0017740000 224689785 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 136 1305031234.0257859230 0.1794983745 0.1534910171 0.2141455114 0.0751179558 0.0017400000 224692633 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 137 1305031234.0616750717 0.1808212548 0.1536905079 0.2141455114 0.0749199342 0.0017750000 224695649 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 138 1305031234.0937900543 0.1817760319 0.1538940262 0.2141455114 0.0747853196 0.0017450000 224698497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 139 1305031234.1296060085 0.1825009584 0.1540998315 0.2141455114 0.0746136589 0.0018000000 224701513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 140 1305031234.1617290974 0.1832699329 0.1543081893 0.2141455114 0.0743814107 0.0017980000 224704473 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 141 1305031234.1937100887 0.1840180606 0.1545188977 0.2141455114 0.0743139680 0.0017660000 224707321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 142 1305031234.2297461033 0.1846162826 0.1547308511 0.2141455114 0.0741114874 0.0018210000 224710337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 143 1305031234.2617518902 0.1852803677 0.1549444841 0.2141455114 0.0739002724 0.0018960000 224713297 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 144 1305031234.2936971188 0.1858895719 0.1551593805 0.2141455114 0.0737240525 0.0018690000 224716145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 145 1305031234.3296539783 0.1860924959 0.1553727123 0.2141455114 0.0735411451 0.0018190000 224719161 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 146 1305031234.3616120815 0.1861576587 0.1555835681 0.2141455114 0.0733487227 0.0018890000 224722121 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 147 1305031234.3937230110 0.1863503903 0.1557928662 0.2141455114 0.0732095298 0.0018060000 224725025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 148 1305031234.4297029972 0.1866887957 0.1560016225 0.2141455114 0.0730655289 0.0018710000 224727985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 149 1305031234.4616899490 0.1865282059 0.1562064989 0.2141455114 0.0729955729 0.0018270000 224730945 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 150 1305031234.4938309193 0.1865822673 0.1564090040 0.2141455114 0.0729113328 0.0018890000 224733793 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 151 1305031234.5296449661 0.1865346432 0.1566085116 0.2141455114 0.0728814302 0.0018790000 224736809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 152 1305031234.5616750717 0.1863601953 0.1568042463 0.2141455114 0.0727828566 0.0018360000 224739769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 153 1305031234.5937800407 0.1859620959 0.1569948205 0.2141455114 0.0727858263 0.0018880000 224742617 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 154 1305031234.6300129890 0.1859170645 0.1571826273 0.2141455114 0.0727024460 0.0019310000 224745689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 155 1305031234.6616179943 0.1854636371 0.1573650854 0.2141455114 0.0725831122 0.0018730000 224748593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 156 1305031234.6937499046 0.1844929457 0.1575389820 0.2141455114 0.0727355377 0.0018990000 224751441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 157 1305031234.7297639847 0.1837482154 0.1577059198 0.2141455114 0.0726278153 0.0018540000 224754457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 158 1305031234.7618150711 0.1831551790 0.1578669910 0.2141455114 0.0725946352 0.0018860000 224757417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 159 1305031234.7937159538 0.1823989898 0.1580212803 0.2141455114 0.0725336410 0.0019860000 224760265 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 160 1305031234.8297719955 0.1818062216 0.1581699362 0.2141455114 0.0723747544 0.0018790000 224763337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 161 1305031234.8618729115 0.1811808199 0.1583128609 0.2141455114 0.0722121597 0.0019000000 224766241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 162 1305031234.8937599659 0.1802201867 0.1584480914 0.2141455114 0.0720236975 0.0019530000 224769145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 163 1305031234.9296660423 0.1798701435 0.1585795150 0.2141455114 0.0718223472 0.0019060000 224772105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 164 1305031234.9616589546 0.1794493198 0.1587067699 0.2141455114 0.0716079172 0.0019090000 224775065 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 165 1305031234.9937489033 0.1792427450 0.1588312303 0.2141455114 0.0715360703 0.0019480000 224777969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 166 1305031235.0297009945 0.1796396673 0.1589565824 0.2141455114 0.0713499909 0.0019410000 224780929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 167 1305031235.0615909100 0.1803992689 0.1590849817 0.2141455114 0.0712922707 0.0019900000 224783889 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 168 1305031235.0936210155 0.1816201210 0.1592191194 0.2141455114 0.0712492126 0.0019620000 224786737 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 169 1305031235.1296789646 0.1825104505 0.1593569380 0.2141455114 0.0710644983 0.0019340000 224789753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 170 1305031235.1614909172 0.1836395860 0.1594997771 0.2141455114 0.0709520791 0.0019720000 224792713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 171 1305031235.1936049461 0.1853286624 0.1596508232 0.2141455114 0.0709477383 0.0019860000 224795561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 172 1305031235.2296350002 0.1865250468 0.1598070687 0.2141455114 0.0708308467 0.0019480000 224798521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 173 1305031235.2616291046 0.1880520433 0.1599703344 0.2141455114 0.0707753348 0.0019850000 224801425 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 174 1305031235.2936770916 0.1900379807 0.1601431370 0.2141455114 0.0708070913 0.0019700000 224804329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 175 1305031235.3296489716 0.1916455179 0.1603231506 0.2141455114 0.0707581048 0.0020010000 224807345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 176 1305031235.3616530895 0.1935118139 0.1605117225 0.2141455114 0.0706821685 0.0020230000 224810249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 177 1305031235.3936860561 0.1957089454 0.1607105769 0.2141455114 0.0707074762 0.0020020000 224813153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 178 1305031235.4296660423 0.1977116168 0.1609184479 0.2141455114 0.0707183617 0.0019850000 224816169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 179 1305031235.4616689682 0.1998688877 0.1611360481 0.2141455114 0.0707120092 0.0020490000 224819073 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 180 1305031235.4936649799 0.2024914473 0.1613658004 0.2141455114 0.0708162012 0.0020080000 224821977 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 181 1305031235.5297379494 0.2046430409 0.1616049011 0.2141455114 0.0707667029 0.0020550000 224824993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 182 1305031235.5616750717 0.2066955864 0.1618526521 0.2141455114 0.0707053078 0.0020540000 224827897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 183 1305031235.5937259197 0.2095489800 0.1621132878 0.2141455114 0.0709088732 0.0020540000 224830857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 184 1305031235.6297979355 0.2119142562 0.1623839453 0.2141455114 0.0708659068 0.0020900000 224833817 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 185 1305031235.6616690159 0.2140302658 0.1626631146 0.2141455114 0.0708573200 0.0020710000 224836777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 186 1305031235.6936979294 0.2171989828 0.1629563181 0.2171989828 0.0709906970 0.0020630000 224839625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 187 1305031235.7296609879 0.2196581066 0.1632595363 0.2196581066 0.0709795682 0.0020810000 224842641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 188 1305031235.7618179321 0.2223727703 0.1635739684 0.2223727703 0.0710060412 0.0020980000 224845601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 189 1305031235.7936279774 0.2259468734 0.1639039837 0.2259468734 0.0711075065 0.0020510000 224848561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 190 1305031235.8296630383 0.2286564559 0.1642447862 0.2286564559 0.0710500381 0.0020970000 224851577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 191 1305031235.8616030216 0.2312443852 0.1645955695 0.2312443852 0.0709827029 0.0021000000 224854593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 192 1305031235.8936979771 0.2347455770 0.1649609341 0.2347455770 0.0710188146 0.0020820000 224857553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 193 1305031235.9296638966 0.2369758040 0.1653340681 0.2369758040 0.0709011592 0.0021470000 224860569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 194 1305031235.9617040157 0.2393371314 0.1657155272 0.2393371314 0.0708310764 0.0020860000 224863585 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 195 1305031235.9936730862 0.2421312481 0.1661074027 0.2421312481 0.0707571281 0.0020880000 224866545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 196 1305031236.0296521187 0.2444131225 0.1665069217 0.2444131225 0.0706437956 0.0021480000 224869617 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 197 1305031236.0616300106 0.2464774698 0.1669128636 0.2464774698 0.0705217563 0.0021130000 224872577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 198 1305031236.0936880112 0.2488715500 0.1673267963 0.2488715500 0.0703785536 0.0020830000 224875537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 199 1305031236.1296598911 0.2504376471 0.1677444388 0.2504376471 0.0702246584 0.0021440000 224878553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 200 1305031236.1616699696 0.2521306574 0.1681663699 0.2521306574 0.0700597324 0.0021490000 224881569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 201 1305031236.1935970783 0.2538934350 0.1685928727 0.2538934350 0.0699133451 0.0021400000 224884585 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 202 1305031236.2297210693 0.2544421256 0.1690178690 0.2544421256 0.0697404772 0.0021490000 224887601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 203 1305031236.2616689205 0.2541698217 0.1694373367 0.2544421256 0.0695709317 0.0022850000 224890561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 204 1305031236.2936480045 0.2533344328 0.1698485970 0.2544421256 0.0694482976 0.0022470000 224893577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 205 1305031236.3296630383 0.2519287467 0.1702489880 0.2544421256 0.0693300775 0.0022290000 224896593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 206 1305031236.3615880013 0.2501243353 0.1706367324 0.2544421256 0.0692156726 0.0021690000 224899609 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 207 1305031236.3936851025 0.2471966594 0.1710065871 0.2544421256 0.0691592161 0.0022090000 224902513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 208 1305031236.4296619892 0.2446973622 0.1713608697 0.2544421256 0.0690816483 0.0022150000 224905641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 209 1305031236.4616539478 0.2419668734 0.1716986974 0.2544421256 0.0690010033 0.0021960000 224908601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 210 1305031236.4936580658 0.2379292846 0.1720140812 0.2544421256 0.0689583792 0.0022430000 224911561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 211 1305031236.5296950340 0.2346324921 0.1723108509 0.2544421256 0.0689001099 0.0021880000 224914633 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 212 1305031236.5616779327 0.2313123047 0.1725891597 0.2544421256 0.0688041596 0.0022060000 224917593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 213 1305031236.5936820507 0.2265453786 0.1728424752 0.2544421256 0.0688335024 0.0022430000 224920553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 214 1305031236.6296420097 0.2229335606 0.1730765457 0.2544421256 0.0687644233 0.0021930000 224923625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 215 1305031236.6616549492 0.2193032503 0.1732915537 0.2544421256 0.0687062386 0.0022140000 224926529 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 216 1305031236.6936669350 0.2147441208 0.1734834637 0.2544421256 0.0687364748 0.0022780000 224929433 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 217 1305031236.7296929359 0.2114398926 0.1736583781 0.2544421256 0.0686536132 0.0022170000 224932393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 218 1305031236.7617490292 0.2080083638 0.1738159469 0.2544421256 0.0685933780 0.0022550000 224935353 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 219 1305031236.7936749458 0.2031946778 0.1739500963 0.2544421256 0.0686340791 0.0023110000 224938201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 220 1305031236.8297049999 0.1998374164 0.1740677659 0.2544421256 0.0685743990 0.0022750000 224941217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 221 1305031236.8616170883 0.1965042353 0.1741692884 0.2544421256 0.0685334387 0.0022960000 224944177 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 222 1305031236.8935050964 0.1919682622 0.1742494640 0.2544421256 0.0685645806 0.0023130000 224947081 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 223 1305031236.9296689034 0.1890011132 0.1743156149 0.2544421256 0.0685270631 0.0023270000 224950097 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 224 1305031236.9616389275 0.1859809309 0.1743676922 0.2544421256 0.0685298183 0.0023260000 224953001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 225 1305031236.9936800003 0.1825494170 0.1744040554 0.2544421256 0.0685418650 0.0023110000 224955849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 226 1305031237.0297141075 0.1800010502 0.1744288209 0.2544421256 0.0685556236 0.0022750000 224958865 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 227 1305031237.0617289543 0.1782374829 0.1744455991 0.2544421256 0.0684998344 0.0023000000 224961825 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 228 1305031237.0936949253 0.1764050424 0.1744541932 0.2544421256 0.0685520756 0.0023530000 224964673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 229 1305031237.1297740936 0.1761380583 0.1744615463 0.2544421256 0.0685602280 0.0022970000 224967689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 230 1305031237.1616609097 0.1761606783 0.1744689338 0.2544421256 0.0685081221 0.0023400000 224970649 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 231 1305031237.1936419010 0.1766578257 0.1744784095 0.2544421256 0.0685322993 0.0023630000 224973553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 232 1305031237.2296910286 0.1770583540 0.1744895300 0.2544421256 0.0684817770 0.0023320000 224976569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 233 1305031237.2616629601 0.1777065545 0.1745033370 0.2544421256 0.0683843208 0.0025110000 224979473 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 234 1305031237.2937090397 0.1785281003 0.1745205368 0.2544421256 0.0683913462 0.0024210000 224982377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 235 1305031237.3296720982 0.1797024310 0.1745425874 0.2544421256 0.0683219616 0.0023850000 224985337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 236 1305031237.3616180420 0.1793605387 0.1745630025 0.2544421256 0.0683295795 0.0023960000 224988297 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 237 1305031237.3936710358 0.1803108156 0.1745872548 0.2544421256 0.0682816336 0.0024030000 224991145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 238 1305031237.4297928810 0.1813838035 0.1746158118 0.2544421256 0.0681670626 0.0023990000 224994161 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 239 1305031237.4616460800 0.1825130433 0.1746488546 0.2544421256 0.0681037687 0.0024110000 224997121 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 240 1305031237.4937019348 0.1832437068 0.1746846665 0.2544421256 0.0680357446 0.0023800000 224999969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 241 1305031237.5297350883 0.1842537969 0.1747243724 0.2544421256 0.0679243246 0.0024120000 225002985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 242 1305031237.5616691113 0.1854400486 0.1747686521 0.2544421256 0.0678185995 0.0024080000 225005945 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 243 1305031237.5936799049 0.1862200648 0.1748157772 0.2544421256 0.0676933604 0.0024070000 225008793 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 244 1305031237.6297049522 0.1868816018 0.1748652273 0.2544421256 0.0675655625 0.0024110000 225011809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 245 1305031237.6616559029 0.1871190220 0.1749152428 0.2544421256 0.0674272959 0.0024200000 225014769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 246 1305031237.6936929226 0.1873249412 0.1749656887 0.2544421256 0.0673096523 0.0024500000 225017673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 247 1305031237.7297520638 0.1871308386 0.1750149404 0.2544421256 0.0671810037 0.0024140000 225020689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 248 1305031237.7616539001 0.1871310472 0.1750637956 0.2544421256 0.0670454371 0.0024580000 225023593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 249 1305031237.7937250137 0.1875053793 0.1751137618 0.2544421256 0.0669326486 0.0024630000 225026441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 250 1305031237.8297688961 0.1870761365 0.1751616113 0.2544421256 0.0668130726 0.0024560000 225029457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 251 1305031237.8618359566 0.1874450147 0.1752105492 0.2544421256 0.0666823225 0.0024870000 225032417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 252 1305031237.8937709332 0.1879343241 0.1752610404 0.2544421256 0.0665849185 0.0024590000 225035265 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 253 1305031237.9298489094 0.1875197291 0.1753094937 0.2544421256 0.0664919420 0.0024730000 225038281 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 254 1305031237.9616580009 0.1868979633 0.1753551176 0.2544421256 0.0663842246 0.0024500000 225041185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 255 1305031237.9936830997 0.1856202185 0.1753953729 0.2544421256 0.0663733503 0.0025040000 225044033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 256 1305031238.0297091007 0.1841615885 0.1754296159 0.2544421256 0.0663243353 0.0025120000 225047049 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 257 1305031238.0616700649 0.1827169359 0.1754579712 0.2544421256 0.0663832570 0.0025490000 225050009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 258 1305031238.0936849117 0.1805262119 0.1754776156 0.2544421256 0.0666805549 0.0024970000 225104113 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 259 1305031238.1297469139 0.1792397350 0.1754921411 0.2544421256 0.0667256826 0.0025570000 225107129 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 260 1305031238.1616818905 0.1775201410 0.1754999411 0.2544421256 0.0669527069 0.0025580000 225110033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 261 1305031238.1937921047 0.1758208722 0.1755011707 0.2544421256 0.0672171119 0.0025100000 225112937 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 262 1305031238.2300119400 0.1743854731 0.1754969124 0.2544421256 0.0672494787 0.0025940000 225115953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 263 1305031238.2616040707 0.1734946519 0.1754892992 0.2544421256 0.0672979607 0.0026070000 225118857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 264 1305031238.2936708927 0.1729938537 0.1754798468 0.2544421256 0.0676652955 0.0025890000 225121761 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 265 1305031238.3296620846 0.1728190333 0.1754698059 0.2544421256 0.0677335922 0.0025940000 225124777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 266 1305031238.3616399765 0.1721626073 0.1754573729 0.2544421256 0.0677421427 0.0025370000 225127681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 267 1305031238.3936669827 0.1727374494 0.1754471859 0.2544421256 0.0679845412 0.0026010000 225130585 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 268 1305031238.4296729565 0.1731451452 0.1754385962 0.2544421256 0.0679811983 0.0025660000 225133601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 269 1305031238.4616849422 0.1739806533 0.1754331763 0.2544421256 0.0679778791 0.0025930000 225136505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 270 1305031238.4936790466 0.1746415645 0.1754302444 0.2544421256 0.0679815896 0.0026430000 225139409 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 271 1305031238.5296700001 0.1753986925 0.1754301280 0.2544421256 0.0678942160 0.0026150000 225142425 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 272 1305031238.5616240501 0.1762600541 0.1754331792 0.2544421256 0.0678412024 0.0026320000 225145329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 273 1305031238.5937409401 0.1780429035 0.1754427386 0.2544421256 0.0678437749 0.0025760000 225148177 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 274 1305031238.6297509670 0.1793171614 0.1754568789 0.2544421256 0.0677776441 0.0026220000 225151193 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 275 1305031238.6616280079 0.1805699021 0.1754754717 0.2544421256 0.0677195043 0.0025930000 225154153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 276 1305031238.6938550472 0.1823039204 0.1755002124 0.2544421256 0.0677258256 0.0026540000 225157057 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 277 1305031238.7297289371 0.1834849268 0.1755290381 0.2544421256 0.0676646316 0.0025910000 225160073 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 278 1305031238.7616579533 0.1847954094 0.1755623704 0.2544421256 0.0675725388 0.0026090000 225163033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 279 1305031238.7936909199 0.1863982528 0.1756012087 0.2544421256 0.0675515792 0.0026980000 225165881 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 280 1305031238.8297300339 0.1878071278 0.1756448012 0.2544421256 0.0674874285 0.0026860000 225169009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 281 1305031238.8618259430 0.1887213141 0.1756913369 0.2544421256 0.0673823108 0.0026670000 225171969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 282 1305031238.8937339783 0.1897505373 0.1757411922 0.2544421256 0.0672783976 0.0026600000 225174929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 283 1305031238.9298369884 0.1904512644 0.1757931712 0.2544421256 0.0671788666 0.0027580000 225178001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 284 1305031238.9616560936 0.1911436468 0.1758472222 0.2544421256 0.0670753286 0.0026600000 225180961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 285 1305031238.9937040806 0.1918684542 0.1759034371 0.2544421256 0.0669881865 0.0026960000 225183921 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 286 1305031239.0296700001 0.1924003959 0.1759611187 0.2544421256 0.0668872445 0.0027070000 225186993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 287 1305031239.0616769791 0.1927635968 0.1760196640 0.2544421256 0.0667720127 0.0026530000 225189953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 288 1305031239.0936889648 0.1928161681 0.1760779852 0.2544421256 0.0666560127 0.0027140000 225192969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 289 1305031239.1297380924 0.1928078830 0.1761358741 0.2544421256 0.0665416236 0.0026710000 225195985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 290 1305031239.1617560387 0.1925392747 0.1761924375 0.2544421256 0.0664454754 0.0027400000 225199001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 291 1305031239.1937060356 0.1920288056 0.1762468580 0.2544421256 0.0663360105 0.0030320000 225201961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 292 1305031239.2298820019 0.1916574240 0.1762996339 0.2544421256 0.0662321776 0.0028100000 225205033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 293 1305031239.2617208958 0.1910745203 0.1763500602 0.2544421256 0.0661438001 0.0026770000 225207993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 294 1305031239.2936739922 0.1902481765 0.1763973327 0.2544421256 0.0660840919 0.0027390000 225211009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 295 1305031239.3297049999 0.1894833297 0.1764416920 0.2544421256 0.0659993642 0.0007550000 225214025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 296 1305031239.3617150784 0.1888720542 0.1764836865 0.2544421256 0.0659286266 0.0007040000 225216985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 297 1305031239.3937180042 0.1878968775 0.1765221147 0.2544421256 0.0658830178 0.0006930000 225219889 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 298 1305031239.4297440052 0.1868570447 0.1765567957 0.2544421256 0.0658463268 0.0006790000 225222905 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 299 1305031239.4617080688 0.1858348101 0.1765878258 0.2544421256 0.0657850275 0.0006840000 225225865 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 300 1305031239.4937200546 0.1845793277 0.1766144642 0.2544421256 0.0657391696 0.0006500000 225228713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 301 1305031239.5296618938 0.1834994406 0.1766373378 0.2544421256 0.0656951752 0.0006380000 225231729 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 302 1305031239.5617330074 0.1823728532 0.1766563296 0.2544421256 0.0656397565 0.0006960000 225234689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 303 1305031239.5939209461 0.1809207201 0.1766704035 0.2544421256 0.0656319997 0.0006680000 225237537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 304 1305031239.6297230721 0.1796837300 0.1766803158 0.2544421256 0.0655969605 0.0006470000 225240553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 305 1305031239.6616590023 0.1785528958 0.1766864554 0.2544421256 0.0655344968 0.0007320000 225243513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 306 1305031239.6937329769 0.1773491800 0.1766886211 0.2544421256 0.0655359584 0.0009770000 225246417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 307 1305031239.7298939228 0.1757754982 0.1766856468 0.2544421256 0.0655292165 0.0015310000 225249377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 308 1305031239.7619130611 0.1746877134 0.1766791600 0.2544421256 0.0655416724 0.0027840000 225252337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 309 1305031239.7935850620 0.1729437411 0.1766670713 0.2544421256 0.0657008158 0.0028680000 225255241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 310 1305031239.8296658993 0.1716639251 0.1766509321 0.2544421256 0.0657290437 0.0028130000 225258145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 311 1305031239.8616919518 0.1700856388 0.1766298218 0.2544421256 0.0657502378 0.0028900000 225261049 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 312 1305031239.8937399387 0.1687016189 0.1766044109 0.2544421256 0.0657979729 0.0029940000 225263953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 313 1305031239.9297060966 0.1680942923 0.1765772220 0.2544421256 0.0657561477 0.0029660000 225266969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 314 1305031239.9617099762 0.1677568406 0.1765491317 0.2544421256 0.0657107267 0.0029630000 225269929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 315 1305031239.9936909676 0.1674306244 0.1765201840 0.2544421256 0.0657618176 0.0029260000 225272833 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 316 1305031240.0296199322 0.1673049033 0.1764910217 0.2544421256 0.0657405385 0.0029570000 225275849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 317 1305031240.0619289875 0.1671520025 0.1764615611 0.2544421256 0.0657119240 0.0028730000 225278753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 318 1305031240.0936510563 0.1681277901 0.1764353543 0.2544421256 0.0657813265 0.0029300000 225281601 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 319 1305031240.1296648979 0.1689350158 0.1764118422 0.2544421256 0.0658535640 0.0029220000 225284617 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 320 1305031240.1617228985 0.1696461737 0.1763906995 0.2544421256 0.0658169981 0.0029410000 225287521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 321 1305031240.1936759949 0.1713616252 0.1763750326 0.2544421256 0.0659590149 0.0029400000 225290425 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 322 1305031240.2296609879 0.1723776907 0.1763626185 0.2544421256 0.0660459067 0.0029130000 225293385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 323 1305031240.2616999149 0.1737108231 0.1763544086 0.2544421256 0.0659985165 0.0029390000 225296345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 324 1305031240.2936460972 0.1757882386 0.1763526612 0.2544421256 0.0661105418 0.0029160000 225299193 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 325 1305031240.3296699524 0.1773239821 0.1763556499 0.2544421256 0.0660823762 0.0029790000 225302209 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 326 1305031240.3616850376 0.1786924303 0.1763628179 0.2544421256 0.0660339755 0.0029680000 225305169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 327 1305031240.3936951160 0.1806137115 0.1763758176 0.2544421256 0.0660556880 0.0029200000 225308017 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 328 1305031240.4297070503 0.1813649535 0.1763910284 0.2544421256 0.0659877765 0.0029730000 225311033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 329 1305031240.4616730213 0.1818866134 0.1764077323 0.2544421256 0.0659066264 0.0029530000 225313993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 330 1305031240.4937129021 0.1830614507 0.1764278951 0.2544421256 0.0658292450 0.0029900000 225316897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 331 1305031240.5296719074 0.1836654097 0.1764497607 0.2544421256 0.0657367648 0.0029840000 225319857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 332 1305031240.5617480278 0.1834377795 0.1764708089 0.2544421256 0.0656402617 0.0029850000 225322817 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 333 1305031240.5936789513 0.1828490347 0.1764899627 0.2544421256 0.0655520051 0.0029840000 225325721 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 334 1305031240.6310579777 0.1817493588 0.1765057094 0.2544421256 0.0654806973 0.0029950000 225328737 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 335 1305031240.6616289616 0.1812996864 0.1765200198 0.2544421256 0.0654151534 0.0029760000 225331641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 336 1305031240.6937999725 0.1801913977 0.1765309465 0.2544421256 0.0653393885 0.0030160000 225334489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 337 1305031240.7296330929 0.1790081561 0.1765382973 0.2544421256 0.0653131135 0.0030200000 225337505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 338 1305031240.7616069317 0.1781772077 0.1765431462 0.2544421256 0.0652306977 0.0030070000 225340409 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 339 1305031240.7935900688 0.1769179255 0.1765442517 0.2544421256 0.0651958596 0.0030400000 225343313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 340 1305031240.8296198845 0.1760292202 0.1765427369 0.2544421256 0.0652166931 0.0030500000 225346329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 341 1305031240.8616340160 0.1749707013 0.1765381268 0.2544421256 0.0651862536 0.0030290000 225349233 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 342 1305031240.8936851025 0.1738864779 0.1765303735 0.2544421256 0.0652179552 0.0030610000 225352137 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 343 1305031240.9296729565 0.1729220450 0.1765198536 0.2544421256 0.0652934265 0.0030630000 225355153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 344 1305031240.9617090225 0.1727510691 0.1765088978 0.2544421256 0.0653738187 0.0030840000 225358001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 345 1305031240.9936430454 0.1718427241 0.1764953726 0.2544421256 0.0654675154 0.0031000000 225360849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 346 1305031241.0296230316 0.1727216244 0.1764844659 0.2544421256 0.0656215297 0.0030840000 225363921 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 347 1305031241.0619900227 0.1728761494 0.1764740673 0.2544421256 0.0656168358 0.0030860000 225366825 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 348 1305031241.0936150551 0.1733122021 0.1764649814 0.2544421256 0.0657767542 0.0031060000 225369729 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 349 1305031241.1297609806 0.1738228798 0.1764574109 0.2544421256 0.0657958297 0.0030820000 225372689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 350 1305031241.1617250443 0.1746389717 0.1764522154 0.2544421256 0.0658322657 0.0030840000 225375649 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 351 1305031241.1937139034 0.1761412323 0.1764513294 0.2544421256 0.0660647132 0.0031230000 225378497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 352 1305031241.2296020985 0.1770636141 0.1764530689 0.2544421256 0.0660771353 0.0030980000 225381513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 353 1305031241.2616620064 0.1781687886 0.1764579292 0.2544421256 0.0660349288 0.0031410000 225384417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 354 1305031241.2938039303 0.1806768626 0.1764698471 0.2544421256 0.0661439410 0.0031300000 225387321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 355 1305031241.3299100399 0.1830219477 0.1764883038 0.2544421256 0.0661724075 0.0031370000 225390337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 356 1305031241.3616580963 0.1855998188 0.1765138979 0.2544421256 0.0661703546 0.0030980000 225393297 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 357 1305031241.3937180042 0.1883980930 0.1765471870 0.2544421256 0.0661829450 0.0031690000 225396201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 358 1305031241.4296689034 0.1906751394 0.1765866505 0.2544421256 0.0661816193 0.0032430000 225399161 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 359 1305031241.4616780281 0.1922293007 0.1766302234 0.2544421256 0.0661131337 0.0031680000 225402065 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 360 1305031241.4937360287 0.1938324422 0.1766780073 0.2544421256 0.0660326588 0.0031740000 225404969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 361 1305031241.5297579765 0.1944626868 0.1767272723 0.2544421256 0.0659452354 0.0031700000 225407985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 362 1305031241.5616860390 0.1951305717 0.1767781102 0.2544421256 0.0658562147 0.0031830000 225410889 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 363 1305031241.5936799049 0.1954990774 0.1768296831 0.2544421256 0.0657702672 0.0032130000 225413737 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 364 1305031241.6297600269 0.1956163496 0.1768812948 0.2544421256 0.0656929653 0.0032000000 225416753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 365 1305031241.6616580486 0.1955292672 0.1769323852 0.2544421256 0.0656081995 0.0031980000 225419713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 366 1305031241.6936290264 0.1954062730 0.1769828603 0.2544421256 0.0655208033 0.0031800000 225422561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 367 1305031241.7297000885 0.1951939464 0.1770324817 0.2544421256 0.0654333455 0.0032530000 225425577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 368 1305031241.7616779804 0.1954063326 0.1770824107 0.2544421256 0.0653442468 0.0032540000 225428537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 369 1305031241.7936940193 0.1949015260 0.1771307010 0.2544421256 0.0652569059 0.0032250000 225431385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 370 1305031241.8297588825 0.1939385086 0.1771761275 0.2544421256 0.0651757592 0.0033140000 225434401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 371 1305031241.8616719246 0.1928522885 0.1772183813 0.2544421256 0.0651002193 0.0034960000 225437361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 372 1305031241.8936219215 0.1913282871 0.1772563111 0.2544421256 0.0650344530 0.0033470000 225440321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 373 1305031241.9296860695 0.1901505291 0.1772908801 0.2544421256 0.0649550228 0.0033280000 225443225 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 374 1305031241.9616849422 0.1884135753 0.1773206199 0.2544421256 0.0648692237 0.0033240000 225446185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 375 1305031241.9936869144 0.1863747686 0.1773447643 0.2544421256 0.0648265774 0.0032850000 225449033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 376 1305031242.0297560692 0.1849348992 0.1773649508 0.2544421256 0.0647655705 0.0033260000 225452049 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 377 1305031242.0616540909 0.1831900030 0.1773804019 0.2544421256 0.0647080305 0.0032920000 225455009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 378 1305031242.0937249660 0.1810218990 0.1773900355 0.2544421256 0.0646741213 0.0032720000 225457857 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 379 1305031242.1296820641 0.1796669513 0.1773960432 0.2544421256 0.0646314555 0.0033240000 225460873 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 380 1305031242.1616680622 0.1782795340 0.1773983682 0.2544421256 0.0645687757 0.0033140000 225463833 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 381 1305031242.1936829090 0.1767380983 0.1773966352 0.2544421256 0.0645149758 0.0033370000 225466681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 382 1305031242.2296719551 0.1756174713 0.1773919777 0.2544421256 0.0644381658 0.0033210000 225469697 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 383 1305031242.2618839741 0.1743613631 0.1773840648 0.2544421256 0.0643602839 0.0033500000 225472657 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 384 1305031242.2938199043 0.1730320901 0.1773727316 0.2544421256 0.0642885972 0.0033590000 225475505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 385 1305031242.3298890591 0.1720727086 0.1773589653 0.2544421256 0.0642091924 0.0033280000 225478577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 386 1305031242.3617289066 0.1712902039 0.1773432431 0.2544421256 0.0641354730 0.0033460000 225481481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 387 1305031242.3936789036 0.1700251848 0.1773243334 0.2544421256 0.0640622581 0.0033360000 225484441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 388 1305031242.4297111034 0.1687874794 0.1773023312 0.2544421256 0.0639857874 0.0033790000 225487401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 389 1305031242.4616949558 0.1674317569 0.1772769570 0.2544421256 0.0639173609 0.0033630000 225490361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 390 1305031242.4937419891 0.1652591825 0.1772461422 0.2544421256 0.0638452760 0.0033210000 225493321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 391 1305031242.5297100544 0.1633102894 0.1772105006 0.2544421256 0.0637822514 0.0033590000 225496337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 392 1305031242.5615689754 0.1614919901 0.1771704024 0.2544421256 0.0637236365 0.0033700000 225499241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 393 1305031242.5936930180 0.1596138924 0.1771257293 0.2544421256 0.0636885255 0.0033740000 225502201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 394 1305031242.6297109127 0.1578527540 0.1770768131 0.2544421256 0.0636266120 0.0034210000 225505217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 395 1305031242.6617820263 0.1557847857 0.1770229093 0.2544421256 0.0635695356 0.0033920000 225508177 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 396 1305031242.6936709881 0.1536138356 0.1769637954 0.2544421256 0.0635765267 0.0034000000 225511193 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 397 1305031242.7297909260 0.1523879617 0.1769018916 0.2544421256 0.0635391047 0.0033930000 225514209 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 398 1305031242.7619299889 0.1508652568 0.1768364729 0.2544421256 0.0634890321 0.0034250000 225517169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 399 1305031242.7936990261 0.1492767334 0.1767674009 0.2544421256 0.0634713919 0.0034150000 225520129 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 400 1305031242.8298120499 0.1486497819 0.1766971068 0.2544421256 0.0634452866 0.0034450000 225523201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 401 1305031242.8616819382 0.1487340033 0.1766273734 0.2544421256 0.0634124514 0.0036450000 225526161 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 402 1305031242.8936789036 0.1496967822 0.1765603819 0.2544421256 0.0634061417 0.0035090000 225529121 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 403 1305031242.9296770096 0.1509393007 0.1764968060 0.2544421256 0.0633578294 0.0034670000 225532249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 404 1305031242.9617309570 0.1525347382 0.1764374939 0.2544421256 0.0633324566 0.0034890000 225535209 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 405 1305031242.9939510822 0.1549023390 0.1763843207 0.2544421256 0.0633101918 0.0034570000 225538169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 406 1305031243.0296640396 0.1572124809 0.1763370994 0.2544421256 0.0632722568 0.0034890000 225541297 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 407 1305031243.0617039204 0.1593547910 0.1762953739 0.2544421256 0.0632220164 0.0034390000 225544313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 408 1305031243.0937390327 0.1619192511 0.1762601383 0.2544421256 0.0631636635 0.0034950000 225547273 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 409 1305031243.1296861172 0.1631636769 0.1762281176 0.2544421256 0.0630884039 0.0035220000 225550289 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 410 1305031243.1616430283 0.1633370966 0.1761966761 0.2544421256 0.0630201183 0.0035150000 225553305 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 411 1305031243.1936519146 0.1623180807 0.1761629082 0.2544421256 0.0629697024 0.0035110000 225556321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 412 1305031243.2297160625 0.1609116644 0.1761258906 0.2544421256 0.0629167153 0.0034740000 225559337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 413 1305031243.2617199421 0.1591012180 0.1760846686 0.2544421256 0.0629487666 0.0034770000 225562353 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 414 1305031243.2936539650 0.1571011394 0.1760388147 0.2544421256 0.0629731198 0.0008290000 225565313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 415 1305031243.3298029900 0.1564355642 0.1759915780 0.2544421256 0.0629381351 0.0010760000 225568385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 416 1305031243.3616859913 0.1553277820 0.1759419054 0.2544421256 0.0629614583 0.0015630000 225571345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 417 1305031243.3937079906 0.1548652202 0.1758913618 0.2544421256 0.0629463139 0.0027510000 225574361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 418 1305031243.4297819138 0.1545805186 0.1758403789 0.2544421256 0.0629310419 0.0034980000 225577377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 419 1305031243.4616219997 0.1543315649 0.1757890452 0.2544421256 0.0629246148 0.0035130000 225580393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 420 1305031243.4976289272 0.1547205597 0.1757388821 0.2544421256 0.0629052592 0.0035560000 225583465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 421 1305031243.5297050476 0.1548581868 0.1756892843 0.2544421256 0.0628864610 0.0035510000 225586425 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 422 1305031243.5617949963 0.1551628709 0.1756406435 0.2544421256 0.0628567945 0.0034740000 225589385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 423 1305031243.5976779461 0.1545950770 0.1755908904 0.2544421256 0.0628473272 0.0035650000 225592345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 424 1305031243.6296401024 0.1537452042 0.1755393675 0.2544421256 0.0628758879 0.0035770000 225595249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 425 1305031243.6617190838 0.1521552503 0.1754843461 0.2544421256 0.0629638434 0.0035460000 225598209 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 426 1305031243.6976819038 0.1507550627 0.1754262961 0.2544421256 0.0630001744 0.0035950000 225601225 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 427 1305031243.7296760082 0.1502230465 0.1753672721 0.2544421256 0.0630825678 0.0035960000 225604129 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 428 1305031243.7616670132 0.1497313976 0.1753073752 0.2544421256 0.0631534115 0.0036120000 225607033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 429 1305031243.7976500988 0.1498001069 0.1752479177 0.2544421256 0.0634187117 0.0035580000 225609993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 430 1305031243.8296658993 0.1507602781 0.1751909697 0.2544421256 0.0635208086 0.0036170000 225612897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 431 1305031243.8616569042 0.1523322016 0.1751379331 0.2544421256 0.0635927232 0.0036160000 225615801 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 432 1305031243.8976891041 0.1544741392 0.1750901003 0.2544421256 0.0637670037 0.0036040000 225618817 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 433 1305031243.9296560287 0.1567114890 0.1750476554 0.2544421256 0.0637785567 0.0036320000 225621665 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 434 1305031243.9616739750 0.1590656042 0.1750108304 0.2544421256 0.0637704192 0.0036180000 225624625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 435 1305031243.9976348877 0.1619778574 0.1749808696 0.2544421256 0.0638165958 0.0036770000 225627641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 436 1305031244.0295569897 0.1639932990 0.1749556687 0.2544421256 0.0637727256 0.0036610000 225630489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 437 1305031244.0617549419 0.1662419438 0.1749357289 0.2544421256 0.0637097477 0.0036670000 225633449 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 438 1305031244.0976209641 0.1693398207 0.1749229528 0.2544421256 0.0636789152 0.0036690000 225636465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 439 1305031244.1296620369 0.1714323908 0.1749150016 0.2544421256 0.0636496096 0.0036500000 225639369 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 440 1305031244.1617009640 0.1745059341 0.1749140719 0.2544421256 0.0635896381 0.0036590000 225642273 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 441 1305031244.1976718903 0.1791591197 0.1749236979 0.2544421256 0.0635400667 0.0036630000 225645289 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 442 1305031244.2296679020 0.1828249693 0.1749415741 0.2544421256 0.0634950554 0.0036920000 225648137 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 443 1305031244.2616760731 0.1872427464 0.1749693420 0.2544421256 0.0634426521 0.0037200000 225651097 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 444 1305031244.2976799011 0.1938647628 0.1750118992 0.2544421256 0.0634080486 0.0037360000 225654113 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 445 1305031244.3296849728 0.1993215829 0.1750665277 0.2544421256 0.0633558295 0.0037910000 225656961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 446 1305031244.3616650105 0.2045795172 0.1751327003 0.2544421256 0.0633057937 0.0037750000 225659921 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 447 1305031244.3976149559 0.2107810527 0.1752124506 0.2544421256 0.0632956274 0.0037420000 225662937 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 448 1305031244.4297399521 0.2150975317 0.1753014798 0.2544421256 0.0632496829 0.0037330000 225665785 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 449 1305031244.4617409706 0.2180772871 0.1753967488 0.2544421256 0.0631923366 0.0037630000 225668745 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 450 1305031244.4976789951 0.2204874605 0.1754969504 0.2544421256 0.0631507905 0.0037880000 225671761 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 451 1305031244.5296900272 0.2216829807 0.1755993585 0.2544421256 0.0630909598 0.0037160000 225674609 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 452 1305031244.5616719723 0.2229065299 0.1757040203 0.2544421256 0.0630229877 0.0037410000 225677569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 453 1305031244.5977001190 0.2246002257 0.1758119590 0.2544421256 0.0629736174 0.0037200000 225680585 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 454 1305031244.6297531128 0.2259443104 0.1759223827 0.2544421256 0.0629170368 0.0037780000 225683433 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 455 1305031244.6617109776 0.2275798917 0.1760359157 0.2544421256 0.0628528661 0.0037150000 225686393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 456 1305031244.6976668835 0.2296738625 0.1761535427 0.2544421256 0.0627909416 0.0040560000 225689409 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 457 1305031244.7297570705 0.2313964516 0.1762744244 0.2544421256 0.0627343667 0.0038090000 225692257 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 458 1305031244.7617380619 0.2334844768 0.1763993372 0.2544421256 0.0626868497 0.0038390000 225695217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 459 1305031244.7976291180 0.2364479154 0.1765301619 0.2544421256 0.0626891107 0.0037810000 225698233 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 460 1305031244.8296599388 0.2481609136 0.1766858810 0.2544421256 0.0629977239 0.0038280000 225701025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 461 1305031244.8616359234 0.2481609136 0.1768409244 0.2544421256 0.0629292108 0.0037880000 225703985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 462 1305031244.8976349831 0.2481609136 0.1769952967 0.2544421256 0.0628609208 0.0038070000 225707001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 463 1305031244.9296810627 0.2481609136 0.1771490021 0.2544421256 0.0627928527 0.0038040000 225709849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 464 1305031244.9616940022 0.2495619655 0.1773050645 0.2544421256 0.0627309494 0.0038290000 225712809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 465 1305031244.9976880550 0.2522445023 0.1774662246 0.2544421256 0.0626908514 0.0038320000 225715769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 466 1305031245.0296700001 0.2522445023 0.1776266930 0.2544421256 0.0626234056 0.0038410000 225718673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 467 1305031245.0617969036 0.2524021566 0.1777868118 0.2544421256 0.0625568131 0.0038260000 225721577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 468 1305031245.0979061127 0.2509586811 0.1779431620 0.2544421256 0.0624916996 0.0038650000 225724593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 469 1305031245.1299250126 0.2482963651 0.1780931688 0.2544421256 0.0624295443 0.0038960000 225727497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 470 1305031245.1617209911 0.2443726212 0.1782341889 0.2544421256 0.0623647296 0.0038640000 225730401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 471 1305031245.1976549625 0.2377061695 0.1783604564 0.2544421256 0.0623069462 0.0038670000 225733361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 472 1305031245.2296841145 0.2325169891 0.1784751948 0.2544421256 0.0622505441 0.0038870000 225736265 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 473 1305031245.2617490292 0.2271258235 0.1785780502 0.2544421256 0.0622039903 0.0038730000 225739169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 474 1305031245.2976479530 0.2202504128 0.1786659666 0.2544421256 0.0621791752 0.0038710000 225742185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 475 1305031245.3297359943 0.2151116580 0.1787426944 0.2544421256 0.0621842322 0.0039210000 225745089 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 476 1305031245.3617970943 0.2107520998 0.1788099410 0.2544421256 0.0622056709 0.0039050000 225747993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 477 1305031245.3976640701 0.2060187906 0.1788669826 0.2544421256 0.0623093398 0.0038840000 225750953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 478 1305031245.4296739101 0.2016109079 0.1789145641 0.2544421256 0.0622690736 0.0039010000 225753801 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 479 1305031245.4617340565 0.1977959722 0.1789539825 0.2544421256 0.0622236563 0.0039120000 225756705 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 480 1305031245.4976971149 0.1938189268 0.1789849511 0.2544421256 0.0622467664 0.0039380000 225759721 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 481 1305031245.5296850204 0.1910146624 0.1790099609 0.2544421256 0.0622265855 0.0039390000 225762569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 482 1305031245.5616409779 0.1890004575 0.1790306881 0.2544421256 0.0622331059 0.0039500000 225765529 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 483 1305031245.5975880623 0.1854181290 0.1790439126 0.2544421256 0.0622200310 0.0039070000 225768545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 484 1305031245.6296100616 0.1834749579 0.1790530676 0.2544421256 0.0621923459 0.0039360000 225771337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 485 1305031245.6616649628 0.1818969548 0.1790589313 0.2544421256 0.0622002631 0.0041850000 225774353 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 486 1305031245.6978080273 0.1798920035 0.1790606455 0.2544421256 0.0622040214 0.0039690000 225777313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 487 1305031245.7296969891 0.1787489802 0.1790600055 0.2544421256 0.0622002253 0.0040100000 225780217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 488 1305031245.7618420124 0.1779696643 0.1790577712 0.2544421256 0.0622397750 0.0039770000 225783177 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 489 1305031245.7975080013 0.1770805568 0.1790537278 0.2544421256 0.0623375935 0.0039640000 225786137 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 490 1305031245.8297789097 0.1766906530 0.1790489052 0.2544421256 0.0623857899 0.0039830000 225789041 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 491 1305031245.8617019653 0.1760640889 0.1790428261 0.2544421256 0.0623930946 0.0039810000 225791945 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 492 1305031245.8976840973 0.1752243936 0.1790350651 0.2544421256 0.0624529567 0.0040090000 225795017 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 493 1305031245.9296269417 0.1739030927 0.1790246554 0.2544421256 0.0624269319 0.0040040000 225797865 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 494 1305031245.9616880417 0.1726976633 0.1790118477 0.2544421256 0.0624039536 0.0040170000 225800769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 495 1305031245.9976129532 0.1708038300 0.1789952659 0.2544421256 0.0624221860 0.0040090000 225803841 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 496 1305031246.0296230316 0.1689240187 0.1789749610 0.2544421256 0.0623877117 0.0040860000 225806689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 497 1305031246.0616579056 0.1666200757 0.1789501020 0.2544421256 0.0623508451 0.0040420000 225809649 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 498 1305031246.0976560116 0.1630632877 0.1789182008 0.2544421256 0.0623547315 0.0040490000 225812665 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 499 1305031246.1295800209 0.1605584621 0.1788814077 0.2544421256 0.0623145129 0.0040270000 225815457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 500 1305031246.1616809368 0.1583305299 0.1788403060 0.2544421256 0.0623044632 0.0040400000 225818361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 501 1305031246.1976530552 0.1547167450 0.1787921552 0.2544421256 0.0622868695 0.0040760000 225821377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 502 1305031246.2296369076 0.1521010846 0.1787389857 0.2544421256 0.0622553400 0.0040500000 225824281 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 503 1305031246.2618930340 0.1497688591 0.1786813910 0.2544421256 0.0622163991 0.0040280000 225827241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 504 1305031246.2976129055 0.1469508260 0.1786184335 0.2544421256 0.0621942961 0.0040980000 225830257 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 505 1305031246.3297309875 0.1448374093 0.1785515404 0.2544421256 0.0621531921 0.0040720000 225833105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 506 1305031246.3615291119 0.1431964785 0.1784816688 0.2544421256 0.0621178519 0.0040960000 225836009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 507 1305031246.3977379799 0.1415817142 0.1784088878 0.2544421256 0.0621148108 0.0041000000 225839137 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 508 1305031246.4296538830 0.1408120692 0.1783348783 0.2544421256 0.0620792115 0.0041420000 225841985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 509 1305031246.4617550373 0.1403107792 0.1782601748 0.2544421256 0.0620496014 0.0040820000 225845001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 510 1305031246.4977169037 0.1402755976 0.1781856952 0.2544421256 0.0620314328 0.0041260000 225848073 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 511 1305031246.5297288895 0.1405618787 0.1781120674 0.2544421256 0.0619890186 0.0040950000 225851033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 512 1305031246.5616788864 0.1417521685 0.1780410520 0.2544421256 0.0619678319 0.0041420000 225853993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 513 1305031246.5975799561 0.1430490911 0.1779728415 0.2544421256 0.0619537863 0.0042030000 225857121 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 514 1305031246.6301050186 0.1441626102 0.1779070628 0.2544421256 0.0619198025 0.0042010000 225962481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 515 1305031246.6616840363 0.1457646489 0.1778446504 0.2544421256 0.0618907576 0.0041700000 225965497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 516 1305031246.6976709366 0.1492377520 0.1777892107 0.2544421256 0.0619152967 0.0041580000 225968625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 517 1305031246.7298250198 0.1520587206 0.1777394418 0.2544421256 0.0618895790 0.0041640000 225971529 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 518 1305031246.7617440224 0.1548049599 0.1776951668 0.2544421256 0.0618802789 0.0041940000 225974545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 519 1305031246.7976179123 0.1583322585 0.1776578587 0.2544421256 0.0618882213 0.0041790000 225977673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 520 1305031246.8296990395 0.1609124690 0.1776256560 0.2544421256 0.0618747071 0.0042280000 225980633 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 521 1305031246.8616819382 0.1636271179 0.1775987874 0.2544421256 0.0618506333 0.0041760000 225983705 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 522 1305031246.8976190090 0.1676225662 0.1775796759 0.2544421256 0.0618625522 0.0042440000 225986833 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 523 1305031246.9297189713 0.1709390879 0.1775669787 0.2544421256 0.0618662597 0.0042040000 225989793 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 524 1305031246.9615809917 0.1740690321 0.1775603033 0.2544421256 0.0618556915 0.0042810000 225992809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 525 1305031246.9976840019 0.1786365658 0.1775623533 0.2544421256 0.0619008490 0.0042240000 225995937 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 526 1305031247.0295639038 0.1811449975 0.1775691644 0.2544421256 0.0619206212 0.0042500000 225998953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 527 1305031247.0617609024 0.1831054240 0.1775796696 0.2544421256 0.0619104708 0.0042520000 226001969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 528 1305031247.0975708961 0.1844622940 0.1775927049 0.2544421256 0.0618695697 0.0042380000 226005097 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 529 1305031247.1296939850 0.1843819171 0.1776055390 0.2544421256 0.0618263414 0.0042410000 226008113 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 530 1305031247.1616880894 0.1845278293 0.1776185999 0.2544421256 0.0617764436 0.0042470000 226011129 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 531 1305031247.1976759434 0.1839182526 0.1776304636 0.2544421256 0.0617271618 0.0042450000 226014257 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 532 1305031247.2296841145 0.1825533211 0.1776397171 0.2544421256 0.0616719701 0.0042740000 226017273 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 533 1305031247.2616710663 0.1808068007 0.1776456591 0.2544421256 0.0616247856 0.0042760000 226020289 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 534 1305031247.2975540161 0.1794862896 0.1776491060 0.2544421256 0.0615768375 0.0042550000 226023417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 535 1305031247.3297290802 0.1787409186 0.1776511468 0.2544421256 0.0615317919 0.0042680000 226026377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 536 1305031247.3616259098 0.1783002466 0.1776523578 0.2544421256 0.0615064828 0.0043330000 226029393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 537 1305031247.3975400925 0.1787486970 0.1776543994 0.2544421256 0.0614833790 0.0043290000 226032577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 538 1305031247.4297029972 0.1797490269 0.1776582927 0.2544421256 0.0614336433 0.0043250000 226035537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 539 1305031247.4616940022 0.1804774106 0.1776635230 0.2544421256 0.0614069711 0.0043080000 226038553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 540 1305031247.4976270199 0.1815147102 0.1776706548 0.2544421256 0.0613979279 0.0042910000 226041737 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 541 1305031247.5296189785 0.1823908389 0.1776793798 0.2544421256 0.0613712212 0.0043650000 226044641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 542 1305031247.5617430210 0.1832285821 0.1776896182 0.2544421256 0.0613520702 0.0043730000 226047657 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 543 1305031247.5977010727 0.1835522652 0.1777004149 0.2544421256 0.0613398299 0.0043340000 226050785 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 544 1305031247.6297180653 0.1831841916 0.1777104954 0.2544421256 0.0613199863 0.0046270000 226053689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 545 1305031247.6616809368 0.1824586689 0.1777192076 0.2544421256 0.0613095580 0.0044590000 226056649 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 546 1305031247.6975688934 0.1801919639 0.1777237365 0.2544421256 0.0613443028 0.0044030000 226059721 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 547 1305031247.7296841145 0.1785325110 0.1777252151 0.2544421256 0.0613329906 0.0043510000 226062625 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 548 1305031247.7617230415 0.1771759242 0.1777242127 0.2544421256 0.0613465098 0.0043740000 226065585 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 549 1305031247.7976500988 0.1754670143 0.1777201012 0.2544421256 0.0614363806 0.0043080000 226068657 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 550 1305031247.8296570778 0.1742511243 0.1777137940 0.2544421256 0.0614639098 0.0043730000 226071449 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 551 1305031247.8616878986 0.1732437760 0.1777056814 0.2544421256 0.0615349968 0.0043900000 226074465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 552 1305031247.8976380825 0.1731839627 0.1776974899 0.2544421256 0.0616336635 0.0044680000 226077481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 553 1305031247.9298069477 0.1735600531 0.1776900081 0.2544421256 0.0616012420 0.0044120000 226080329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 554 1305031247.9616999626 0.1734536141 0.1776823612 0.2544421256 0.0616091358 0.0043940000 226083233 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 555 1305031247.9975569248 0.1739254296 0.1776755920 0.2544421256 0.0617041099 0.0043980000 226086249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 556 1305031248.0296840668 0.1744772047 0.1776698395 0.2544421256 0.0617044849 0.0043810000 226089153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 557 1305031248.0617458820 0.1751101464 0.1776652440 0.2544421256 0.0617170760 0.0043860000 226092057 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 558 1305031248.0981791019 0.1763113141 0.1776628176 0.2544421256 0.0618127747 0.0044350000 226095017 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 559 1305031248.1298580170 0.1775143445 0.1776625520 0.2544421256 0.0618198242 0.0044540000 226097921 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 560 1305031248.1617319584 0.1793332249 0.1776655353 0.2544421256 0.0617984079 0.0044910000 226100825 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 561 1305031248.1977460384 0.1809714586 0.1776714282 0.2544421256 0.0618623532 0.0044800000 226103841 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 562 1305031248.2296700478 0.1825506985 0.1776801102 0.2544421256 0.0618648048 0.0044900000 226106689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 563 1305031248.2616910934 0.1841095984 0.1776915302 0.2544421256 0.0618516941 0.0044240000 226109593 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 564 1305031248.2976450920 0.1864655018 0.1777070869 0.2544421256 0.0618107625 0.0044770000 226112665 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 565 1305031248.3296880722 0.1879599988 0.1777252337 0.2544421256 0.0617793554 0.0044580000 226115513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 566 1305031248.3617050648 0.1896148771 0.1777462401 0.2544421256 0.0617560405 0.0045320000 226118417 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 567 1305031248.3983058929 0.1919108331 0.1777712218 0.2544421256 0.0617301868 0.0044630000 226121489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 568 1305031248.4296898842 0.1932752430 0.1777985176 0.2544421256 0.0617035377 0.0044810000 226124337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 569 1305031248.4616739750 0.1950879842 0.1778289033 0.2544421256 0.0616759056 0.0045180000 226127241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 570 1305031248.4975969791 0.1973750889 0.1778631948 0.2544421256 0.0616466434 0.0044990000 226130257 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 571 1305031248.5296781063 0.1985785663 0.1778994739 0.2544421256 0.0616002317 0.0044920000 226133105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 572 1305031248.5616800785 0.2013099045 0.1779404013 0.2544421256 0.0615683421 0.0045350000 226136009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 573 1305031248.5975770950 0.2038497627 0.1779856183 0.2544421256 0.0615553204 0.0045210000 226139025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 574 1305031248.6297268867 0.2058855295 0.1780342244 0.2544421256 0.0615389897 0.0048370000 226141929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 575 1305031248.6616599560 0.2080954909 0.1780865049 0.2544421256 0.0615186783 0.0045830000 226144833 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 576 1305031248.7011339664 0.2113219202 0.1781442053 0.2544421256 0.0615248500 0.0045560000 226147961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 577 1305031248.7297689915 0.2141570151 0.1782066191 0.2544421256 0.0614941715 0.0045160000 226150753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 578 1305031248.7617149353 0.2169194818 0.1782735964 0.2544421256 0.0614955024 0.0045490000 226153657 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 579 1305031248.7978229523 0.2207703888 0.1783469933 0.2544421256 0.0614691616 0.0045450000 226156673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 580 1305031248.8297278881 0.2239390165 0.1784256002 0.2544421256 0.0614283084 0.0045960000 226159577 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 581 1305031248.8617119789 0.2271710187 0.1785094994 0.2544421256 0.0613932079 0.0046260000 226162537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 582 1305031248.8977398872 0.2318633348 0.1786011727 0.2544421256 0.0613583082 0.0046280000 226165553 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 583 1305031248.9297659397 0.2355283797 0.1786988179 0.2544421256 0.0613182258 0.0045720000 226168401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 584 1305031248.9617550373 0.2396615893 0.1788032063 0.2544421256 0.0612907797 0.0045640000 226171305 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 585 1305031248.9976139069 0.2439128608 0.1789145048 0.2544421256 0.0612434022 0.0045630000 226174377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 586 1305031249.0296969414 0.2461121231 0.1790291765 0.2544421256 0.0611984162 0.0046320000 226177225 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 587 1305031249.0623369217 0.2474239767 0.1791456924 0.2544421256 0.0611522225 0.0046350000 226180185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 588 1305031249.0976889133 0.2479656488 0.1792627331 0.2544421256 0.0611028375 0.0046160000 226183145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 589 1305031249.1297810078 0.2476846427 0.1793788993 0.2544421256 0.0610519065 0.0046190000 226186049 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 590 1305031249.1617488861 0.2467391491 0.1794930692 0.2544421256 0.0610119844 0.0047150000 226188953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 591 1305031249.1976730824 0.2455091029 0.1796047715 0.2544421256 0.0609704522 0.0046200000 226191969 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 592 1305031249.2297680378 0.2445003986 0.1797143925 0.2544421256 0.0609478253 0.0046370000 226194873 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 593 1305031249.2616090775 0.2433933318 0.1798217769 0.2544421256 0.0609275342 0.0046550000 226197777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 594 1305031249.2979500294 0.2420351207 0.1799265131 0.2544421256 0.0609081184 0.0046310000 226200849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 595 1305031249.3296790123 0.2415633947 0.1800301045 0.2544421256 0.0608695887 0.0046580000 226203641 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 596 1305031249.3617539406 0.2403807789 0.1801313641 0.2544421256 0.0608188562 0.0047160000 226206545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 597 1305031249.3977370262 0.2381954938 0.1802286239 0.2544421256 0.0607814290 0.0046680000 226209561 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 598 1305031249.4298510551 0.2366279811 0.1803229372 0.2544421256 0.0607621354 0.0046790000 226212465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 599 1305031249.4617938995 0.2337609380 0.1804121492 0.2544421256 0.0607469092 0.0046770000 226215369 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 600 1305031249.4976849556 0.2307252288 0.1804960044 0.2544421256 0.0608108752 0.0047490000 226218385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 601 1305031249.5296919346 0.2284884602 0.1805758587 0.2544421256 0.0608198079 0.0047370000 226221289 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 602 1305031249.5618629456 0.2266227454 0.1806523486 0.2544421256 0.0608341451 0.0046980000 226224193 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 603 1305031249.5978050232 0.2232245356 0.1807229492 0.2544421256 0.0609370648 0.0046980000 226227153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 604 1305031249.6297600269 0.2207682729 0.1807892494 0.2544421256 0.0609397097 0.0047140000 226230057 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 605 1305031249.6622838974 0.2183671594 0.1808513616 0.2544421256 0.0610150049 0.0047210000 226232961 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 606 1305031249.6976530552 0.2149137408 0.1809075702 0.2544421256 0.0612481804 0.0047200000 226235977 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 607 1305031249.7299690247 0.2124305964 0.1809595027 0.2544421256 0.0613378622 0.0047580000 226238769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 608 1305031249.7618219852 0.2098166496 0.1810069651 0.2544421256 0.0614666770 0.0047650000 226241673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 609 1305031249.7976670265 0.2062046379 0.1810483406 0.2544421256 0.0616655205 0.0047240000 226244689 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 610 1305031249.8297970295 0.2034912705 0.1810851323 0.2544421256 0.0617761435 0.0047660000 226247537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 611 1305031249.8617289066 0.2010117471 0.1811177454 0.2544421256 0.0619384857 0.0047640000 226250497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 612 1305031249.8975479603 0.1975631416 0.1811446170 0.2544421256 0.0620879598 0.0047630000 226253513 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 613 1305031249.9297540188 0.1949145496 0.1811670801 0.2544421256 0.0621059117 0.0048350000 226256361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 614 1305031249.9622321129 0.1921845227 0.1811850239 0.2544421256 0.0621095774 0.0047580000 226259377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 615 1305031249.9976871014 0.1889374852 0.1811976295 0.2544421256 0.0621733185 0.0047880000 226262337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 616 1305031250.0300250053 0.1858303547 0.1812051502 0.2544421256 0.0621918394 0.0047900000 226265241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 617 1305031250.0619239807 0.1823925376 0.1812070746 0.2544421256 0.0622088211 0.0047780000 226268145 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 618 1305031250.0976040363 0.1775380671 0.1812011377 0.2544421256 0.0622670121 0.0048140000 226271161 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 619 1305031250.1297800541 0.1734820902 0.1811886675 0.2544421256 0.0622926367 0.0048460000 226274009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 620 1305031250.1618089676 0.1691520512 0.1811692536 0.2544421256 0.0623803562 0.0048010000 226276913 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 621 1305031250.1976170540 0.1646717638 0.1811426876 0.2544421256 0.0624402887 0.0048070000 226279873 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 622 1305031250.2296700478 0.1616407335 0.1811113340 0.2544421256 0.0624620806 0.0049150000 226282777 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 623 1305031250.2619171143 0.1586930603 0.1810753496 0.2544421256 0.0624830113 0.0048520000 226285681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 624 1305031250.2981820107 0.1552062482 0.1810338927 0.2544421256 0.0625199071 0.0048610000 226288697 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 625 1305031250.3297090530 0.1534038484 0.1809896846 0.2544421256 0.0625291449 0.0048550000 226291489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 626 1305031250.3615961075 0.1517823189 0.1809430275 0.2544421256 0.0625260565 0.0048720000 226294393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 627 1305031250.3977839947 0.1491928101 0.1808923892 0.2544421256 0.0625112355 0.0048680000 226297409 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 628 1305031250.4297308922 0.1484921128 0.1808407964 0.2544421256 0.0625162595 0.0051340000 226300313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 629 1305031250.4617791176 0.1478236020 0.1807883048 0.2544421256 0.0625185575 0.0049090000 226303273 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 630 1305031250.4981379509 0.1471333355 0.1807348842 0.2544421256 0.0625274629 0.0048680000 226306345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 631 1305031250.5297000408 0.1472652406 0.1806818420 0.2544421256 0.0625217465 0.0048860000 226309249 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 632 1305031250.5618190765 0.1470217705 0.1806285824 0.2544421256 0.0624900711 0.0048700000 226312209 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 633 1305031250.5976500511 0.1474507749 0.1805761688 0.2544421256 0.0624775436 0.0048760000 226315337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 634 1305031250.6296610832 0.1478591412 0.1805245647 0.2544421256 0.0624457499 0.0048970000 226318297 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 635 1305031250.6619520187 0.1489586532 0.1804748546 0.2544421256 0.0624267742 0.0049020000 226321313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 636 1305031250.6977679729 0.1508760154 0.1804283155 0.2544421256 0.0624569535 0.0048970000 226324385 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 637 1305031250.7297470570 0.1522834003 0.1803841320 0.2544421256 0.0624216094 0.0049350000 226327345 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 638 1305031250.7617890835 0.1531433761 0.1803414349 0.2544421256 0.0623795755 0.0049590000 226330305 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 639 1305031250.7978379726 0.1545622945 0.1803010919 0.2544421256 0.0623464807 0.0049320000 226333377 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 640 1305031250.8297851086 0.1549421102 0.1802614685 0.2544421256 0.0623008987 0.0049220000 226336393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 641 1305031250.8618729115 0.1551163048 0.1802222405 0.2544421256 0.0622565199 0.0049320000 226339409 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 642 1305031250.8976039886 0.1552128494 0.1801832851 0.2544421256 0.0622300390 0.0049560000 226342481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 643 1305031250.9301199913 0.1550350785 0.1801441743 0.2544421256 0.0621818437 0.0049750000 226345441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 644 1305031250.9618170261 0.1543648243 0.1801041443 0.2544421256 0.0621398864 0.0050020000 226348457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 645 1305031250.9976119995 0.1531846672 0.1800624086 0.2544421256 0.0621173402 0.0049840000 226351529 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 646 1305031251.0297889709 0.1529141814 0.1800203835 0.2544421256 0.0620729540 0.0049890000 226354489 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 647 1305031251.0618538857 0.1515981108 0.1799764542 0.2544421256 0.0620435552 0.0049940000 226357449 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 648 1305031251.0976850986 0.1497100145 0.1799297467 0.2544421256 0.0620703557 0.0049980000 226360521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 649 1305031251.1297309399 0.1485216618 0.1798813521 0.2544421256 0.0620563761 0.0049670000 226363425 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 650 1305031251.1616990566 0.1471922696 0.1798310612 0.2544421256 0.0620646394 0.0050270000 226366441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 651 1305031251.1976718903 0.1457308978 0.1797786800 0.2544421256 0.0621496618 0.0050970000 226369569 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 652 1305031251.2298820019 0.1455704421 0.1797262134 0.2544421256 0.0621620839 0.0050520000 226372361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 653 1305031251.2618720531 0.1455744207 0.1796739136 0.2544421256 0.0621976031 0.0050070000 226375321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 654 1305031251.2977221012 0.1457322985 0.1796220151 0.2544421256 0.0623229277 0.0050260000 226378393 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 655 1305031251.3296079636 0.1468240172 0.1795719418 0.2544421256 0.0623536523 0.0050560000 226381241 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 656 1305031251.3618309498 0.1481626779 0.1795240618 0.2544421256 0.0623545111 0.0050440000 226384201 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 657 1305031251.3977360725 0.1495698541 0.1794784694 0.2544421256 0.0624258422 0.0050490000 226387217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 658 1305031251.4299569130 0.1508824676 0.1794350105 0.2544421256 0.0624489404 0.0053860000 226390065 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 659 1305031251.4622879028 0.1522862762 0.1793938136 0.2544421256 0.0624550723 0.0051350000 226393025 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 660 1305031251.4977610111 0.1549482346 0.1793567748 0.2544421256 0.0625019819 0.0051160000 226395985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 661 1305031251.5298271179 0.1572518349 0.1793233332 0.2544421256 0.0625057855 0.0050660000 226398889 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 662 1305031251.5617070198 0.1590387374 0.1792926918 0.2544421256 0.0625092838 0.0050920000 226401849 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 663 1305031251.5976569653 0.1614377499 0.1792657613 0.2544421256 0.0625434795 0.0050960000 226404865 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 664 1305031251.6297779083 0.1632358134 0.1792416198 0.2544421256 0.0625724341 0.0051250000 226407713 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 665 1305031251.6618139744 0.1649104208 0.1792200691 0.2544421256 0.0626108283 0.0051280000 226410617 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 666 1305031251.6983299255 0.1665052325 0.1792009778 0.2544421256 0.0627360010 0.0050840000 226413633 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 667 1305031251.7301750183 0.1682033837 0.1791844896 0.2544421256 0.0627769641 0.0051200000 226416537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 668 1305031251.7617549896 0.1699976623 0.1791707369 0.2544421256 0.0628342175 0.0051710000 226419497 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 669 1305031251.7976779938 0.1713926345 0.1791591104 0.2544421256 0.0629968660 0.0050780000 226422457 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 670 1305031251.8298690319 0.1727226526 0.1791495038 0.2544421256 0.0630730578 0.0051150000 226425361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 671 1305031251.8621430397 0.1743638963 0.1791423717 0.2544421256 0.0631441972 0.0052020000 226428321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 672 1305031251.8978729248 0.1760891080 0.1791378282 0.2544421256 0.0632522912 0.0051410000 226431337 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 673 1305031251.9298980236 0.1775797307 0.1791355130 0.2544421256 0.0632443429 0.0051470000 226434185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 674 1305031251.9619040489 0.1785555780 0.1791346526 0.2544421256 0.0632222988 0.0052050000 226437089 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 675 1305031251.9983429909 0.1812674850 0.1791378123 0.2544421256 0.0632267091 0.0051980000 226440105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 676 1305031252.0297839642 0.1841591001 0.1791452403 0.2544421256 0.0632202696 0.0051970000 226442953 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 677 1305031252.0620169640 0.1879252493 0.1791582093 0.2544421256 0.0632045255 0.0051850000 226445913 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 678 1305031252.0987350941 0.1939288974 0.1791799949 0.2544421256 0.0631879667 0.0052060000 226448873 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 679 1305031252.1297190189 0.1986925453 0.1792087321 0.2544421256 0.0631687559 0.0051940000 226451721 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 680 1305031252.1617779732 0.2038108408 0.1792449117 0.2544421256 0.0631484318 0.0052240000 226454681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 681 1305031252.1978518963 0.2095695436 0.1792894413 0.2544421256 0.0631054505 0.0051890000 226457753 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 682 1305031252.2298820019 0.2125269473 0.1793381766 0.2544421256 0.0630807224 0.0052830000 226460545 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 683 1305031252.2617468834 0.2157974541 0.1793915577 0.2544421256 0.0630351262 0.0052070000 226463449 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 684 1305031252.2976710796 0.2194465995 0.1794501177 0.2544421256 0.0629909992 0.0052570000 226466465 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 685 1305031252.3299539089 0.2214951813 0.1795114973 0.2544421256 0.0629477538 0.0052250000 226469313 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 686 1305031252.3616869450 0.2234786600 0.1795755894 0.2544421256 0.0629021421 0.0052440000 226472217 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 687 1305031252.3974940777 0.2246304154 0.1796411714 0.2544421256 0.0628847147 0.0052480000 226475233 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 688 1305031252.4296720028 0.2252034694 0.1797073957 0.2544421256 0.0628475017 0.0052610000 226478081 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 689 1305031252.4617218971 0.2252589017 0.1797735082 0.2544421256 0.0628052676 0.0053750000 226480985 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 690 1305031252.4976549149 0.2241501361 0.1798378221 0.2544421256 0.0627624844 0.0052570000 226484001 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 691 1305031252.5296919346 0.2238373905 0.1799014973 0.2544421256 0.0627191827 0.0053440000 226486905 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 692 1305031252.5618619919 0.2229772657 0.1799637455 0.2544421256 0.0626885430 0.0053070000 226489809 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 693 1305031252.5976469517 0.2220719904 0.1800245078 0.2544421256 0.0626548210 0.0052810000 226492769 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 694 1305031252.6298389435 0.2210267335 0.1800835888 0.2544421256 0.0626102665 0.0052870000 226495673 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 695 1305031252.6615939140 0.2188068777 0.1801393058 0.2544421256 0.0625785388 0.0052950000 226498521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 696 1305031252.6980121136 0.2146784365 0.1801889310 0.2544421256 0.0626327594 0.0052890000 226501537 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 697 1305031252.7298109531 0.2113545090 0.1802336449 0.2544421256 0.0627280682 0.0053100000 226504441 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 698 1305031252.7616798878 0.2089521438 0.1802747888 0.2544421256 0.0629290772 0.0054150000 226507401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 699 1305031252.7976830006 0.2061446309 0.1803117986 0.2544421256 0.0631457931 0.0053160000 226510361 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 700 1305031252.8310210705 0.2040995657 0.1803457811 0.2544421256 0.0631751494 0.0053450000 226513321 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 701 1305031252.8658039570 0.2017219067 0.1803762749 0.2544421256 0.0631975458 0.0053660000 226516281 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 702 1305031252.8975970745 0.1991899163 0.1804030750 0.2544421256 0.0631869885 0.0053730000 226519185 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 703 1305031252.9296870232 0.1961046606 0.1804254101 0.2544421256 0.0631923188 0.0053380000 226522033 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 704 1305031252.9657709599 0.1920057982 0.1804418595 0.2544421256 0.0632386399 0.0054440000 226525105 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 705 1305031252.9976520538 0.1883270144 0.1804530441 0.2544421256 0.0632577552 0.0053220000 226528009 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 706 1305031253.0298841000 0.1849104911 0.1804593578 0.2544421256 0.0632855462 0.0053570000 226530913 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 707 1305031253.0659010410 0.1808560938 0.1804599189 0.2544421256 0.0633044186 0.0053040000 226533929 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 708 1305031253.0979468822 0.1776841283 0.1804559983 0.2544421256 0.0632870594 0.0053640000 226536889 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 709 1305031253.1297280788 0.1748367995 0.1804480728 0.2544421256 0.0632530438 0.0053570000 226539681 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 710 1305031253.1659770012 0.1718439907 0.1804359544 0.2544421256 0.0632274169 0.0054010000 226542697 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 711 1305031253.1976099014 0.1701865494 0.1804215389 0.2544421256 0.0631906666 0.0054320000 226545657 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 712 1305031253.2299060822 0.1696738601 0.1804064438 0.2544421256 0.0631617446 0.0054120000 226548505 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 713 1305031253.2655360699 0.1690261811 0.1803904827 0.2544421256 0.0631621248 0.0053880000 226551521 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 714 1305031253.2976000309 0.1686275452 0.1803740080 0.2544421256 0.0631264138 0.0054180000 226554481 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 715 1305031253.3299720287 0.1685732007 0.1803575034 0.2544421256 0.0630902142 0.0054650000 226557329 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 716 1305031253.3662569523 0.1682801694 0.1803406356 0.2544421256 0.0630554684 0.0055230000 226560401 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 717 1305031253.3977351189 0.1678648442 0.1803232356 0.2544421256 0.0630169762 0.0054330000 226563305 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 718 1305031253.4297530651 0.1673180312 0.1803051225 0.2544421256 0.0629775893 0.0058160000 226566153 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 719 1305031253.4657158852 0.1657332927 0.1802848557 0.2544421256 0.0629388719 0.0055020000 226569169 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 720 1305031253.4976971149 0.1650894135 0.1802637510 0.2544421256 0.0628963920 0.0055180000 226572129 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 721 1305031253.5297060013 0.1641669571 0.1802414253 0.2544421256 0.0628573532 0.0054710000 226574977 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 722 1305031253.5656700134 0.1632163376 0.1802178449 0.2544421256 0.0628169654 0.0055110000 226577993 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 723 1305031253.5981209278 0.1626314223 0.1801935206 0.2544421256 0.0627750344 0.0054960000 226580897 0 402718720 -0.2109137326 -0.0284043625 0.1200023964 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 10:18:40 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 -nan 0.0057470000 87431964 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0280407500 0.0267197900 0.0280407500 0.0123610180 0.0638000000 104378801 0 402718720 -0.0006102596 0.0053527658 0.0072599053 3 1305031102.2432110310 0.0359877497 0.0298091099 0.0359877497 0.0133848368 0.0551250000 107651609 0 402718720 0.0004194458 0.0173057411 0.0178164560 4 1305031102.2753260136 0.0412028506 0.0326575451 0.0412028506 0.0132651174 0.0476670000 107655153 0 402718720 0.0000211365 0.0268275179 0.0280553307 5 1305031102.3112668991 0.0443283506 0.0349917062 0.0443283506 0.0117977273 0.0484510000 107658825 0 402718720 0.0009406107 0.0341121070 0.0394172221 6 1305031102.3432331085 0.0495279804 0.0374144185 0.0495279804 0.0105761117 0.0498150000 107662769 0 402718720 0.0022915448 0.0422457419 0.0488537997 7 1305031102.3753290176 0.0540746115 0.0397944461 0.0540746115 0.0105411838 0.0510900000 107665857 0 402718720 0.0059230397 0.0496612079 0.0601497181 8 1305031102.4112579823 0.0586649291 0.0421532565 0.0586649291 0.0129340755 0.0613350000 120013481 0 402718720 0.0049553243 0.0584522448 0.0682729930 9 1305031102.4432709217 0.0704898685 0.0453017689 0.0704898685 0.0146242397 0.0476040000 123677065 0 402718720 0.0050741229 0.0738898739 0.0760361999 10 1305031102.4753179550 0.0762629062 0.0483978827 0.0762629062 0.0141573711 0.0284220000 126873945 0 402718720 0.0062146815 0.0836995617 0.0879351348 11 1305031102.5112190247 0.0830353051 0.0515467392 0.0830353051 0.0140830349 0.0284310000 126877201 0 402718720 0.0077386550 0.0941172689 0.0989961103 12 1305031102.5432200432 0.0843316093 0.0542788118 0.0843316093 0.0136848388 0.0322420000 126880401 0 402718720 0.0083205430 0.0987327471 0.1106791869 13 1305031102.5752859116 0.0856415182 0.0566913276 0.0856415182 0.0131185346 0.0389040000 126883489 0 402718720 0.0097627239 0.1027626917 0.1229776442 14 1305031102.6112329960 0.0853053257 0.0587351846 0.0856415182 0.0130594939 0.0370660000 126886745 0 402718720 0.0153765269 0.1038177460 0.1367915124 15 1305031102.6432650089 0.0850614384 0.0604902682 0.0856415182 0.0130799104 0.0902740000 145728869 0 402718720 0.0110546015 0.1075219810 0.1413845271 16 1305031102.6752851009 0.0912551135 0.0624130710 0.0912551135 0.0130674289 0.0485290000 149391221 0 402718720 0.0123603279 0.1180814877 0.1526333839 17 1305031102.7112629414 0.0925445855 0.0641855131 0.0925445855 0.0127036961 0.0255110000 152588333 0 402718720 0.0136858150 0.1235799938 0.1651065350 18 1305031102.7432339191 0.1015146971 0.0662593566 0.1015146971 0.0133368923 0.0255890000 152594733 0 402718720 0.0135879796 0.1377731711 0.1747052372 19 1305031102.7754719257 0.1049139127 0.0682938069 0.1049139127 0.0135209185 0.0252230000 152597821 0 402718720 0.0129535068 0.1462031603 0.1865576804 20 1305031102.8112320900 0.1094070226 0.0703494677 0.1094070226 0.0140825338 0.0238620000 152601077 0 402718720 0.0120772310 0.1569755822 0.1973260343 21 1305031102.8432900906 0.1084311530 0.0721628813 0.1094070226 0.0138584698 0.0249430000 152604277 0 402718720 0.0111593269 0.1608595103 0.2093235999 22 1305031102.8753631115 0.1063702926 0.0737177636 0.1094070226 0.0137942501 0.0833710000 164918745 0 402718720 0.0104308417 0.1631685495 0.2200742811 23 1305031102.9111850262 0.1146244481 0.0754963151 0.1146244481 0.0143067284 0.0446170000 168582025 0 402718720 0.0090651698 0.1780308187 0.2322462648 24 1305031102.9432289600 0.1088038236 0.0768841280 0.1146244481 0.0141124763 0.0303290000 171777417 0 402718720 0.0072338865 0.1765102297 0.2431055307 25 1305031102.9752030373 0.1056082398 0.0780330925 0.1146244481 0.0138427280 0.0324250000 171780449 0 402718720 0.0047391839 0.1780687869 0.2527470887 26 1305031103.0112149715 0.1079732776 0.0791846380 0.1146244481 0.0136705679 0.0318470000 171783761 0 402718720 0.0050841048 0.1852789968 0.2632419169 27 1305031103.0432269573 0.1101318672 0.0803308317 0.1146244481 0.0135066010 0.0654780000 171786961 0 402718720 0.0045674075 0.1925454140 0.2736003101 28 1305031103.0753190517 0.1135129854 0.0815159086 0.1146244481 0.0134672691 0.0278300000 171790049 0 402718720 0.0039218431 0.2006983310 0.2832193375 29 1305031103.1112399101 0.1180882752 0.0827770247 0.1180882752 0.0138114390 0.0276530000 171793305 0 402718720 0.0042230864 0.2101671845 0.2907955647 30 1305031103.1433179379 0.1188290343 0.0839787584 0.1188290343 0.0136334472 0.0749630000 184105169 0 402718720 0.0031918592 0.2158424109 0.3000564277 31 1305031103.1754519939 0.1235089451 0.0852539257 0.1235089451 0.0136676576 0.0487670000 187767521 0 402718720 0.0030306263 0.2248962373 0.3078168333 32 1305031103.2112200260 0.1251145154 0.0864995691 0.1251145154 0.0140610391 0.0313300000 190962969 0 402718720 0.0022824784 0.2322718203 0.3156650364 33 1305031103.2432160378 0.1259934455 0.0876963533 0.1259934455 0.0139073767 0.0308130000 190969497 0 402718720 0.0038546077 0.2367155254 0.3235103488 34 1305031103.2753698826 0.1188641787 0.0886130540 0.1259934455 0.0137207471 0.0376790000 190978985 0 402718720 0.0034990076 0.2323241085 0.3310333788 35 1305031103.3112099171 0.1118982658 0.0892783458 0.1259934455 0.0142296978 0.0440420000 190982241 0 402718720 0.0038044788 0.2264609337 0.3356592655 36 1305031103.3432230949 0.1208121330 0.0901542843 0.1259934455 0.0142526138 0.0357710000 190985441 0 402718720 0.0053887991 0.2362810075 0.3368438482 37 1305031103.3753271103 0.1210652143 0.0909897148 0.1259934455 0.0140603080 0.0370900000 190988529 0 402718720 0.0067975759 0.2358537167 0.3376955092 38 1305031103.4112598896 0.1150760949 0.0916235669 0.1259934455 0.0141375822 0.0370150000 190991785 0 402718720 0.0072681811 0.2270482332 0.3367925882 39 1305031103.4432799816 0.1137927398 0.0921920073 0.1259934455 0.0139636590 0.0699650000 190994985 0 402718720 0.0067995572 0.2235123664 0.3330277205 40 1305031103.4752740860 0.1113864779 0.0926718690 0.1259934455 0.0139797372 0.0317280000 190998073 0 402718720 0.0076464671 0.2170925289 0.3286582828 41 1305031103.5113329887 0.1090673581 0.0930717590 0.1259934455 0.0140001004 0.0329500000 191001329 0 402718720 0.0084443679 0.2089691162 0.3226256371 42 1305031103.5434439182 0.1048180163 0.0933514318 0.1259934455 0.0141429454 0.0379110000 191004529 0 402718720 0.0078519415 0.1994651854 0.3135237694 43 1305031103.5754740238 0.1051680371 0.0936262366 0.1259934455 0.0140711526 0.0365870000 191007617 0 402718720 0.0060752486 0.1953454167 0.3035799861 44 1305031103.6112229824 0.1026506647 0.0938313372 0.1259934455 0.0141150602 0.0344870000 191010873 0 402718720 0.0061183004 0.1859174669 0.2942227423 45 1305031103.6434450150 0.1017945111 0.0940082966 0.1259934455 0.0141579248 0.0366250000 191014073 0 402718720 0.0071755745 0.1785941869 0.2838075161 46 1305031103.6755230427 0.1025259793 0.0941934637 0.1259934455 0.0141451340 0.0411300000 191017161 0 402718720 0.0080501568 0.1729303449 0.2727960646 47 1305031103.7116100788 0.1040680930 0.0944035622 0.1259934455 0.0141314043 0.0447250000 191020417 0 402718720 0.0084465425 0.1673890501 0.2607817650 48 1305031103.7433259487 0.1009035707 0.0945389790 0.1259934455 0.0141256606 0.0439820000 191023617 0 402718720 0.0097553832 0.1568675041 0.2492606491 49 1305031103.7753419876 0.1027519628 0.0947065909 0.1259934455 0.0140769427 0.0823670000 203339921 0 402718720 0.0110515617 0.1518424749 0.2359611988 50 1305031103.8112421036 0.1041075736 0.0948946106 0.1259934455 0.0139780194 0.0443080000 207002385 0 402718720 0.0096051116 0.1472040117 0.2229826599 51 1305031103.8432509899 0.1060815826 0.0951139630 0.1259934455 0.0139365606 0.0629970000 210197777 0 402718720 0.0073613361 0.1444643438 0.2100826651 52 1305031103.8753609657 0.0908251777 0.0950314863 0.1259934455 0.0150979931 0.0338070000 210200865 0 402718720 0.0130298026 0.1202255785 0.2027490735 53 1305031103.9112210274 0.0858493745 0.0948582389 0.1259934455 0.0156084922 0.0258790000 210204121 0 402718720 0.0134457732 0.1075796783 0.1908672750 54 1305031103.9432110786 0.0856102705 0.0946869803 0.1259934455 0.0155602586 0.0262020000 210207321 0 402718720 0.0138356434 0.1013505757 0.1771894991 55 1305031103.9753730297 0.0829477981 0.0944735406 0.1259934455 0.0154269220 0.0315690000 210210465 0 402718720 0.0135750715 0.0929036587 0.1646085083 56 1305031104.0112318993 0.0813207030 0.0942386685 0.1259934455 0.0154990018 0.0304930000 210213665 0 402718720 0.0123052802 0.0852836668 0.1517189592 57 1305031104.0432488918 0.0830168724 0.0940417949 0.1259934455 0.0153728018 0.0365120000 210216865 0 402718720 0.0128985615 0.0808742866 0.1369362026 58 1305031104.0754249096 0.0835988596 0.0938617443 0.1259934455 0.0152852824 0.0885390000 222528805 0 402718720 0.0088568432 0.0775666982 0.1222827584 59 1305031104.1112349033 0.0811070278 0.0936455626 0.1259934455 0.0153053179 0.0469510000 226191269 0 402718720 0.0111215292 0.0685695112 0.1120829433 60 1305031104.1432299614 0.0735548735 0.0933107178 0.1259934455 0.0153308512 0.0350730000 229386661 0 402718720 0.0133917946 0.0546301492 0.1015825570 61 1305031104.1754240990 0.0691831112 0.0929151833 0.1259934455 0.0152099582 0.0304010000 229389749 0 402718720 0.0132670384 0.0449992009 0.0898435265 62 1305031104.2112829685 0.0644259453 0.0924556794 0.1259934455 0.0152330122 0.0313580000 229393005 0 402718720 0.0145729743 0.0345612429 0.0799741969 63 1305031104.2431960106 0.0620691814 0.0919733541 0.1259934455 0.0151803397 0.0435280000 229396205 0 402718720 0.0157838650 0.0268647205 0.0695015714 64 1305031104.2755460739 0.0604686365 0.0914810929 0.1259934455 0.0150666286 0.0311740000 229399293 0 402718720 0.0146612199 0.0213810373 0.0582983568 65 1305031104.3112189770 0.0606378354 0.0910065812 0.1259934455 0.0149584342 0.0312170000 229409205 0 402718720 0.0108432714 0.0182183813 0.0469025224 66 1305031104.3433420658 0.0607453026 0.0905480770 0.1259934455 0.0148479442 0.0320540000 229425205 0 402718720 0.0094404407 0.0149159562 0.0360722132 67 1305031104.3758370876 0.0569499433 0.0900466123 0.1259934455 0.0149521460 0.0364460000 229428293 0 402718720 0.0092835398 0.0074374103 0.0274729673 68 1305031104.4115090370 0.0500030592 0.0894577365 0.1259934455 0.0148438801 0.0417870000 229431549 0 402718720 0.0093767038 -0.0025589222 0.0202609431 69 1305031104.4432880878 0.0390371494 0.0887270034 0.1259934455 0.0148440801 0.0943650000 241743709 0 402718720 0.0106625119 -0.0171390492 0.0144597106 70 1305031104.4754559994 0.0353277326 0.0879641566 0.1259934455 0.0147525275 0.0512100000 245407741 0 402718720 0.0063025360 -0.0215668920 0.0091337329 71 1305031104.5113289356 0.0291123297 0.0871352577 0.1259934455 0.0149564445 0.0391690000 248603189 0 402718720 0.0070838546 -0.0320962705 0.0042146379 72 1305031104.5433681011 0.0295338258 0.0863352378 0.1259934455 0.0148942664 0.0400600000 248606389 0 402718720 0.0083867451 -0.0352881104 -0.0029787393 73 1305031104.5753428936 0.0325272158 0.0855981416 0.1259934455 0.0148517224 0.0348290000 248609421 0 402718720 0.0107235163 -0.0367030576 -0.0073966025 74 1305031104.6113359928 0.0367150567 0.0849375594 0.1259934455 0.0149956153 0.0690820000 248612733 0 402718720 0.0180049501 -0.0466917120 -0.0097595369 75 1305031104.6432430744 0.0370500945 0.0842990598 0.1259934455 0.0149939328 0.0345550000 248615877 0 402718720 0.0210338943 -0.0508046523 -0.0197249111 76 1305031104.6755249500 0.0328741446 0.0836224162 0.1259934455 0.0148965083 0.0316250000 248619021 0 402718720 0.0176101141 -0.0589632876 -0.0264005866 77 1305031104.7112770081 0.0304538254 0.0829319150 0.1259934455 0.0149530864 0.1191090000 260936889 0 402718720 0.0163129531 -0.0676949695 -0.0358495265 78 1305031104.7432799339 0.0268301517 0.0822126617 0.1259934455 0.0149293034 0.0403240000 264599241 0 402718720 0.0151934903 -0.0668515339 -0.0475060493 79 1305031104.7753269672 0.0256870706 0.0814971478 0.1259934455 0.0148926794 0.0454830000 267794521 0 402718720 0.0148433885 -0.0674476624 -0.0551379360 80 1305031104.8114650249 0.0267674588 0.0808130267 0.1259934455 0.0148360871 0.0351860000 267797833 0 402718720 0.0158264767 -0.0648548827 -0.0630983561 81 1305031104.8432579041 0.0268078819 0.0801462965 0.1259934455 0.0147614728 0.0323410000 267800977 0 402718720 0.0161660649 -0.0627765507 -0.0687399656 82 1305031104.8753499985 0.0271708090 0.0795002540 0.1259934455 0.0147175690 0.0328010000 267804121 0 402718720 0.0131914457 -0.0586839952 -0.0745244771 83 1305031104.9115340710 0.0301862042 0.0789061088 0.1259934455 0.0146304407 0.0411700000 267807377 0 402718720 0.0139437933 -0.0539137386 -0.0759060234 84 1305031104.9432621002 0.0305687450 0.0783306640 0.1259934455 0.0145431289 0.1489030000 280136845 0 402718720 0.0149847474 -0.0521778688 -0.0752228871 85 1305031104.9752020836 0.0590918697 0.0781043253 0.1259934455 0.0150846636 0.0886040000 283799197 0 402718720 0.0009008758 -0.0221580174 -0.0759336501 86 1305031105.0112900734 0.0628423169 0.0779268601 0.1259934455 0.0150421658 0.0436810000 286994645 0 402718720 0.0010542298 -0.0153085208 -0.0714175180 87 1305031105.0433731079 0.0661045685 0.0777909717 0.1259934455 0.0149830662 0.0450600000 286997789 0 402718720 -0.0016171173 -0.0098340148 -0.0667018592 88 1305031105.0753200054 0.0683791563 0.0776840192 0.1259934455 0.0149158568 0.0435010000 287000933 0 402718720 -0.0026642326 -0.0048009627 -0.0588069111 89 1305031105.1112990379 0.0637674257 0.0775276530 0.1259934455 0.0148489363 0.0406770000 287004189 0 402718720 -0.0054048449 -0.0060952199 -0.0510576665 90 1305031105.1431059837 0.0709071383 0.0774540917 0.1259934455 0.0148207758 0.0384810000 287007333 0 402718720 -0.0117426962 0.0033481270 -0.0451060496 91 1305031105.1751589775 0.0799684972 0.0774817225 0.1259934455 0.0148915672 0.0417840000 287010477 0 402718720 -0.0161733069 0.0161263868 -0.0346010551 92 1305031105.2112679482 0.0710280314 0.0774115737 0.1259934455 0.0150257200 0.0392070000 287013733 0 402718720 -0.0217063725 0.0096084429 -0.0249894280 93 1305031105.2432699203 0.0726526156 0.0773604021 0.1259934455 0.0149751105 0.0369750000 287016877 0 402718720 -0.0271547213 0.0136828804 -0.0157305207 94 1305031105.2752881050 0.0757296383 0.0773430536 0.1259934455 0.0150593932 0.0413120000 287020021 0 402718720 -0.0335802585 0.0193306319 -0.0059191203 95 1305031105.3112900257 0.0721683130 0.0772885826 0.1259934455 0.0150290142 0.1206820000 299336441 0 402718720 -0.0367523991 0.0191879366 0.0048999838 96 1305031105.3433020115 0.0704629943 0.0772174827 0.1259934455 0.0149636027 0.0827930000 302998793 0 402718720 -0.0327603295 0.0236040596 0.0159076583 97 1305031105.3753380775 0.0693325177 0.0771361944 0.1259934455 0.0148932777 0.0345560000 306194129 0 402718720 -0.0308658164 0.0283059683 0.0302198865 98 1305031105.4112861156 0.0767122805 0.0771318688 0.1259934455 0.0149839394 0.0362640000 306197385 0 402718720 -0.0343128331 0.0386789255 0.0385027006 99 1305031105.4433159828 0.0737170875 0.0770973761 0.1259934455 0.0149167607 0.0353270000 306200529 0 402718720 -0.0300191715 0.0416294895 0.0524655320 100 1305031105.4752800465 0.0696006119 0.0770224084 0.1259934455 0.0148664669 0.0371280000 306203673 0 402718720 -0.0256321337 0.0410597883 0.0634432659 101 1305031105.5113320351 0.0716536939 0.0769692528 0.1259934455 0.0148645111 0.0371130000 306206929 0 402718720 -0.0228848681 0.0461408533 0.0741154104 102 1305031105.5432820320 0.0677570775 0.0768789374 0.1259934455 0.0148010982 0.2142720000 318527689 0 402718720 -0.0201587230 0.0455982313 0.0865785629 103 1305031105.5754489899 0.0733374208 0.0768445537 0.1259934455 0.0148083327 0.0440550000 322190041 0 402718720 -0.0105405422 0.0540605150 0.0988909230 104 1305031105.6113779545 0.0736348629 0.0768136913 0.1259934455 0.0147659781 0.0330240000 325385489 0 402718720 -0.0072994684 0.0571883954 0.1126800552 105 1305031105.6432731152 0.0743270516 0.0767900090 0.1259934455 0.0146959841 0.0337320000 325388633 0 402718720 -0.0074335230 0.0613086447 0.1239130422 106 1305031105.6751658916 0.0791477934 0.0768122523 0.1259934455 0.0147118014 0.0342420000 325391777 0 402718720 -0.0056068464 0.0707760975 0.1363479644 107 1305031105.7113089561 0.0791375116 0.0768339837 0.1259934455 0.0146902689 0.0696300000 325395033 0 402718720 -0.0005829360 0.0740422606 0.1518945843 108 1305031105.7433118820 0.0842254981 0.0769024236 0.1259934455 0.0147333270 0.0394030000 325398177 0 402718720 0.0003637776 0.0824330226 0.1607111990 109 1305031105.7753388882 0.0846669078 0.0769736574 0.1259934455 0.0146784939 0.0371470000 325401321 0 402718720 0.0057573784 0.0859469473 0.1744494885 110 1305031105.8112831116 0.0851642266 0.0770481171 0.1259934455 0.0146607492 0.0310070000 325404577 0 402718720 0.0063117947 0.0904993340 0.1868270338 111 1305031105.8432710171 0.0867697597 0.0771356995 0.1259934455 0.0146430006 0.0322130000 325407721 0 402718720 0.0089469496 0.0968882293 0.1990229785 112 1305031105.8753368855 0.0921327472 0.0772696017 0.1259934455 0.0147094284 0.2340480000 337727357 0 402718720 0.0097078672 0.1081909314 0.2093276680 113 1305031105.9112620354 0.0978663862 0.0774518741 0.1259934455 0.0150159369 0.0436210000 341389821 0 402718720 0.0199075248 0.1208276004 0.2286511064 114 1305031105.9432721138 0.1006553620 0.0776554135 0.1259934455 0.0150215013 0.0275960000 344585157 0 402718720 0.0217400566 0.1295041442 0.2400707901 115 1305031105.9753289223 0.1015709117 0.0778633744 0.1259934455 0.0150108211 0.0257340000 344588301 0 402718720 0.0225424170 0.1370640993 0.2517252564 116 1305031106.0112850666 0.1030804589 0.0780807630 0.1259934455 0.0150508750 0.0256020000 344591557 0 402718720 0.0244254749 0.1447157115 0.2629383504 117 1305031106.0433549881 0.1024291888 0.0782888692 0.1259934455 0.0150039549 0.0685310000 344594757 0 402718720 0.0245751068 0.1503445357 0.2746753991 118 1305031106.0753300190 0.1028048098 0.0784966314 0.1259934455 0.0149845680 0.0306310000 344597845 0 402718720 0.0241136048 0.1573332101 0.2854100168 119 1305031106.1113269329 0.1055895314 0.0787243029 0.1259934455 0.0150238747 0.2690910000 356923249 0 402718720 0.0230376106 0.1670540124 0.2956705093 120 1305031106.1433548927 0.1081794277 0.0789697622 0.1259934455 0.0151672244 0.0511580000 360585657 0 402718720 0.0150112947 0.1820288301 0.3111914992 121 1305031106.1755340099 0.1069434881 0.0792009501 0.1259934455 0.0151348555 0.0300700000 363780937 0 402718720 0.0146534601 0.1855522096 0.3203070462 122 1305031106.2112751007 0.1018062308 0.0793862392 0.1259934455 0.0150753222 0.0341680000 363784193 0 402718720 0.0136146285 0.1850240231 0.3291174471 123 1305031106.2432670593 0.1016187072 0.0795669910 0.1259934455 0.0150699524 0.0338960000 363787393 0 402718720 0.0120740850 0.1895533949 0.3358217180 124 1305031106.2763850689 0.1038519815 0.0797628377 0.1259934455 0.0150186966 0.0357520000 363790537 0 402718720 0.0103365779 0.1965187937 0.3409738839 125 1305031106.3112380505 0.1051263958 0.0799657462 0.1259934455 0.0149809482 0.0357420000 363793737 0 402718720 0.0094479145 0.2018782794 0.3467639685 126 1305031106.3432579041 0.1101582125 0.0802053689 0.1259934455 0.0149674610 0.0361420000 363796937 0 402718720 0.0106853340 0.2097122818 0.3510046601 127 1305031106.3753879070 0.1157219410 0.0804850270 0.1259934455 0.0149407394 0.0378990000 363800025 0 402718720 0.0129542742 0.2169087678 0.3547526300 128 1305031106.4113199711 0.1064183116 0.0806876308 0.1259934455 0.0149186246 0.0356710000 363803281 0 402718720 0.0123212868 0.2068126649 0.3554250300 129 1305031106.4432780743 0.0988492444 0.0808284185 0.1259934455 0.0149343138 0.0414840000 363819737 0 402718720 0.0097777853 0.1984348148 0.3536787927 130 1305031106.4753448963 0.0959823951 0.0809449875 0.1259934455 0.0149198116 0.0416100000 363848481 0 402718720 0.0093038650 0.1931274533 0.3499434292 131 1305031106.5111289024 0.0916813686 0.0810269446 0.1259934455 0.0149520535 0.0371990000 363851569 0 402718720 0.0091298353 0.1842804402 0.3442763984 132 1305031106.5433020592 0.0932213292 0.0811193263 0.1259934455 0.0149230821 0.0420830000 363854769 0 402718720 0.0100004785 0.1810603142 0.3357298374 133 1305031106.5752820969 0.0946864635 0.0812213349 0.1259934455 0.0148820730 0.0333210000 363857857 0 402718720 0.0098121893 0.1776070446 0.3259586394 134 1305031106.6111509800 0.0963016897 0.0813338748 0.1259934455 0.0148789932 0.0354180000 363861113 0 402718720 0.0075502740 0.1748267263 0.3155670464 135 1305031106.6432070732 0.0917358622 0.0814109266 0.1259934455 0.0149967363 0.0296850000 363864313 0 402718720 0.0070897597 0.1639801711 0.3046440482 136 1305031106.6752789021 0.0939259008 0.0815029485 0.1259934455 0.0149543231 0.0278760000 363867401 0 402718720 0.0029174511 0.1630436331 0.2922570407 137 1305031106.7115080357 0.0902652740 0.0815669070 0.1259934455 0.0150573139 0.0270660000 363870657 0 402718720 0.0036654307 0.1528193653 0.2810143828 138 1305031106.7433409691 0.0901678205 0.0816292325 0.1259934455 0.0150725712 0.0313670000 363873857 0 402718720 0.0025061474 0.1475842297 0.2677320540 139 1305031106.7753899097 0.0900219604 0.0816896118 0.1259934455 0.0150888986 0.0347050000 363876945 0 402718720 0.0023317188 0.1417954266 0.2536166608 140 1305031106.8112890720 0.0940119326 0.0817776284 0.1259934455 0.0150495541 0.0325120000 363880201 0 402718720 0.0024612942 0.1400503814 0.2389707267 141 1305031106.8434159756 0.0854763389 0.0818038604 0.1259934455 0.0152760613 0.3169710000 376237765 0 402718720 0.0038992108 0.1241226196 0.2267304957 142 1305031106.8759050369 0.0845267475 0.0818230357 0.1259934455 0.0153137349 0.0447780000 379900117 0 402718720 0.0030874177 0.1168969944 0.2119206786 143 1305031106.9112429619 0.0918347687 0.0818930478 0.1259934455 0.0152862967 0.0358010000 383095565 0 402718720 0.0026415684 0.1177418530 0.1943030357 144 1305031106.9434390068 0.0850018784 0.0819146369 0.1259934455 0.0154163398 0.0319930000 383098709 0 402718720 0.0004429915 0.1047277674 0.1803986430 145 1305031106.9755470753 0.0781401098 0.0818886057 0.1259934455 0.0153953774 0.0327030000 383101853 0 402718720 -0.0014853473 0.0915149972 0.1655051708 146 1305031107.0115759373 0.0877507925 0.0819287576 0.1259934455 0.0153632747 0.0446680000 383105165 0 402718720 -0.0023469881 0.0941392332 0.1459604502 147 1305031107.0432810783 0.0804793760 0.0819188979 0.1259934455 0.0153647183 0.0291720000 383108309 0 402718720 -0.0031432312 0.0809730366 0.1340616643 148 1305031107.0754320621 0.0697786659 0.0818368693 0.1259934455 0.0153915808 0.0295340000 383111397 0 402718720 -0.0047140345 0.0641708747 0.1222769022 149 1305031107.1112289429 0.0735335648 0.0817811424 0.1259934455 0.0153538637 0.2657550000 395444193 0 402718720 -0.0057137632 0.0619979836 0.1064296439 150 1305031107.1432600021 0.0776434094 0.0817535575 0.1259934455 0.0153025026 0.0444450000 399106601 0 402718720 -0.0051054894 0.0610127524 0.0917546451 151 1305031107.1753990650 0.0688606799 0.0816681742 0.1259934455 0.0153108562 0.0414050000 402301881 0 402718720 -0.0049601234 0.0470944643 0.0820869058 152 1305031107.2113580704 0.0650911182 0.0815591147 0.1259934455 0.0153157553 0.0716830000 402305137 0 402718720 -0.0058533056 0.0379562415 0.0701147094 153 1305031107.2433779240 0.0669588596 0.0814636882 0.1259934455 0.0152741935 0.0331430000 402308281 0 402718720 -0.0071749911 0.0355944186 0.0568907522 154 1305031107.2753980160 0.0631646588 0.0813448633 0.1259934455 0.0152350193 0.0335740000 402311425 0 402718720 -0.0066356310 0.0275793374 0.0467089973 155 1305031107.3112258911 0.0589286797 0.0812002428 0.1259934455 0.0152220322 0.0360330000 402314681 0 402718720 -0.0061631696 0.0186729077 0.0384153053 156 1305031107.3435089588 0.0553445816 0.0810345013 0.1259934455 0.0152031025 0.0340730000 402317881 0 402718720 -0.0080289664 0.0111053912 0.0277088452 157 1305031107.3754129410 0.0614471436 0.0809097411 0.1259934455 0.0152164081 0.0452990000 402320969 0 402718720 -0.0063092215 0.0135582685 0.0161259696 158 1305031107.4112710953 0.0618839040 0.0807893244 0.1259934455 0.0151757870 0.0331290000 402324225 0 402718720 -0.0043462720 0.0102735963 0.0095041525 159 1305031107.4434189796 0.0644192398 0.0806863679 0.1259934455 0.0151328608 0.3759960000 414667469 0 402718720 -0.0009465544 0.0097038522 0.0034047214 160 1305031107.4753770828 0.0652625561 0.0805899691 0.1259934455 0.0150958141 0.0448760000 418333133 0 402718720 0.0053922846 0.0084946500 0.0023420481 161 1305031107.5113520622 0.0727805272 0.0805414632 0.1259934455 0.0150674194 0.0392540000 421528525 0 402718720 0.0067759054 0.0147066973 -0.0026961567 162 1305031107.5436050892 0.0698068291 0.0804752000 0.1259934455 0.0150234715 0.0316300000 421531725 0 402718720 0.0107008768 0.0112184035 -0.0028455029 163 1305031107.5754539967 0.0654361024 0.0803829356 0.1259934455 0.0149952638 0.0721030000 421534813 0 402718720 0.0148697197 0.0076528629 0.0003964404 164 1305031107.6112709045 0.0723242909 0.0803337976 0.1259934455 0.0149688108 0.0334640000 421538069 0 402718720 0.0172811057 0.0147930253 -0.0036173973 165 1305031107.6433229446 0.0728498697 0.0802884404 0.1259934455 0.0149262715 0.0333770000 421541269 0 402718720 0.0161051452 0.0175390113 -0.0024836510 166 1305031107.6755681038 0.0725962445 0.0802421019 0.1259934455 0.0148826492 0.0415550000 421544357 0 402718720 0.0189839657 0.0197735913 0.0014779451 167 1305031107.7113070488 0.0752132908 0.0802119893 0.1259934455 0.0148475072 0.0434220000 421547613 0 402718720 0.0189607907 0.0256548226 0.0030499855 168 1305031107.7435379028 0.0799319670 0.0802103225 0.1259934455 0.0148170035 0.0454640000 421550757 0 402718720 0.0181525275 0.0332536213 0.0053890361 169 1305031107.7758018970 0.0753576830 0.0801816086 0.1259934455 0.0147797248 0.0442040000 421553901 0 402718720 0.0187128428 0.0307612997 0.0076669394 170 1305031107.8115959167 0.0769043788 0.0801623308 0.1259934455 0.0147404187 0.0416270000 421557157 0 402718720 0.0215875320 0.0341765545 0.0093233427 171 1305031107.8433320522 0.0759308264 0.0801375852 0.1259934455 0.0146997077 0.0357150000 421560301 0 402718720 0.0249031577 0.0340943784 0.0105440449 172 1305031107.8753581047 0.0705199614 0.0800816687 0.1259934455 0.0146767769 0.0403690000 421563445 0 402718720 0.0289162956 0.0290410426 0.0132795321 173 1305031107.9115409851 0.0697282553 0.0800218224 0.1259934455 0.0146661546 0.0374650000 421566701 0 402718720 0.0323636904 0.0301677026 0.0153966434 174 1305031107.9431219101 0.0684765205 0.0799554701 0.1259934455 0.0146385106 0.0751220000 421569845 0 402718720 0.0385205150 0.0288067702 0.0172254089 175 1305031107.9758069515 0.0669073313 0.0798809093 0.1259934455 0.0146219633 0.0367530000 421572989 0 402718720 0.0461628959 0.0281390510 0.0201028381 176 1305031108.0113201141 0.0675642788 0.0798109285 0.1259934455 0.0146006037 0.0411930000 421576245 0 402718720 0.0571275391 0.0281156320 0.0211447868 177 1305031108.0434179306 0.0730820745 0.0797729123 0.1259934455 0.0145850324 0.0410470000 421579389 0 402718720 0.0730104148 0.0322399512 0.0229802094 178 1305031108.0753519535 0.0715088025 0.0797264848 0.1259934455 0.0145738729 0.0463640000 421582477 0 402718720 0.0847197399 0.0307786223 0.0271545090 179 1305031108.1113779545 0.0668770596 0.0796547003 0.1259934455 0.0145430440 0.0436130000 421585733 0 402718720 0.0916400850 0.0293259118 0.0302113369 180 1305031108.1433339119 0.0721095726 0.0796127829 0.1259934455 0.0145179752 0.4041180000 433913201 0 402718720 0.1068767384 0.0331452899 0.0298676156 181 1305031108.1760580540 0.0840973705 0.0796375596 0.1259934455 0.0146183418 0.0559120000 437575553 0 402718720 0.1265500635 0.0464725122 0.0345628001 182 1305031108.2114748955 0.0815848187 0.0796482588 0.1259934455 0.0145821262 0.0456030000 440771001 0 402718720 0.1391662359 0.0448706411 0.0393645056 183 1305031108.2433469296 0.0753990188 0.0796250389 0.1259934455 0.0145451916 0.0454690000 440774145 0 402718720 0.1556317657 0.0382320695 0.0480996482 184 1305031108.2753579617 0.0809350088 0.0796321583 0.1259934455 0.0145131503 0.0429970000 440777289 0 402718720 0.1680023372 0.0446628444 0.0466280542 185 1305031108.3113319874 0.0808290020 0.0796386278 0.1259934455 0.0145112471 0.0437700000 440780545 0 402718720 0.1771396697 0.0498776883 0.0478261560 186 1305031108.3432779312 0.0815942734 0.0796491420 0.1259934455 0.0144750710 0.0422310000 440783745 0 402718720 0.1879514754 0.0534652732 0.0512828007 187 1305031108.3754100800 0.0800136179 0.0796510911 0.1259934455 0.0144409110 0.0454940000 440786833 0 402718720 0.1973941326 0.0554830804 0.0559242256 188 1305031108.4113609791 0.0767610744 0.0796357186 0.1259934455 0.0144271359 0.0421640000 440790089 0 402718720 0.2118888050 0.0552568547 0.0601712130 189 1305031108.4436099529 0.0772899315 0.0796233071 0.1259934455 0.0144098244 0.3300930000 453117661 0 402718720 0.2252521664 0.0578937680 0.0640154481 190 1305031108.4754710197 0.0991928205 0.0797263045 0.1259934455 0.0145541823 0.0389570000 456779957 0 402718720 0.2378999591 0.0860510767 0.0756895840 191 1305031108.5113780499 0.0970013812 0.0798167499 0.1259934455 0.0146411475 0.0290490000 459975405 0 402718720 0.2579109967 0.0840907767 0.0842735842 192 1305031108.5437369347 0.0967383459 0.0799048832 0.1259934455 0.0146549092 0.0307390000 459978605 0 402718720 0.2739346325 0.0828058422 0.0890431255 193 1305031108.5754139423 0.1010669097 0.0800145310 0.1259934455 0.0146554403 0.0273460000 459981693 0 402718720 0.2861658335 0.0891339257 0.0848649964 194 1305031108.6114070415 0.0996408090 0.0801156974 0.1259934455 0.0146695436 0.0295090000 459984949 0 402718720 0.3009988964 0.0902710110 0.0899434686 195 1305031108.6433029175 0.1006442159 0.0802209719 0.1259934455 0.0146610979 0.0299000000 459988149 0 402718720 0.3107068837 0.0941521227 0.0901707038 196 1305031108.6753749847 0.1059193537 0.0803520861 0.1259934455 0.0146599751 0.0270760000 459991237 0 402718720 0.3271974921 0.0993952453 0.0921117067 197 1305031108.7114109993 0.0997342691 0.0804504728 0.1259934455 0.0146548814 0.4273780000 472309109 0 402718720 0.3367668688 0.0969029441 0.0954638049 198 1305031108.7435019016 0.0800373554 0.0804483863 0.1259934455 0.0146405837 0.0393330000 475971517 0 402718720 0.3175799549 0.0883626342 0.0925946534 199 1305031108.7754929066 0.0811213329 0.0804517680 0.1259934455 0.0146070563 0.0291370000 479166797 0 402718720 0.3256962001 0.0906392410 0.0935591236 200 1305031108.8112440109 0.0770644844 0.0804348316 0.1259934455 0.0145766148 0.0285590000 479170053 0 402718720 0.3266756237 0.0893369615 0.0960262343 201 1305031108.8432641029 0.0761568844 0.0804135482 0.1259934455 0.0159233100 0.0272490000 479173253 0 402718720 0.3271056712 0.0863489136 0.0971574113 202 1305031108.8765149117 0.0753876045 0.0803886673 0.1259934455 0.0160014546 0.0286120000 479176397 0 402718720 0.3267016709 0.0857971162 0.0953308865 203 1305031108.9113640785 0.0723194405 0.0803489174 0.1259934455 0.0161317217 0.0288590000 479179597 0 402718720 0.3293765783 0.0825122669 0.0954904482 204 1305031108.9432430267 0.0712447166 0.0803042890 0.1259934455 0.0162074431 0.0296400000 479182797 0 402718720 0.3272711337 0.0818821862 0.0917739719 205 1305031108.9752678871 0.0769651607 0.0802880006 0.1259934455 0.0161719276 0.0283160000 479185941 0 402718720 0.3251245320 0.0867801607 0.0845015422 206 1305031109.0112690926 0.0798913762 0.0802860752 0.1259934455 0.0161341015 0.0278750000 479189141 0 402718720 0.3266971707 0.0878696740 0.0828861669 207 1305031109.0432770252 0.0783800408 0.0802768673 0.1259934455 0.0161042665 0.0356010000 479192341 0 402718720 0.3192021847 0.0857210308 0.0798067600 208 1305031109.0754098892 0.0849370286 0.0802992719 0.1259934455 0.0160729896 0.0306560000 479195429 0 402718720 0.3123411536 0.0914506912 0.0733406544 209 1305031109.1112821102 0.0841117501 0.0803175135 0.1259934455 0.0160619847 0.0457910000 479198685 0 402718720 0.3036362827 0.0898352712 0.0754599869 210 1305031109.1433339119 0.0779677480 0.0803063241 0.1259934455 0.0160575295 0.0398700000 479201885 0 402718720 0.2844482660 0.0841024220 0.0731616244 211 1305031109.1754639149 0.0848559663 0.0803278864 0.1259934455 0.0160384362 0.0313820000 479204973 0 402718720 0.2754325569 0.0905184001 0.0704221427 212 1305031109.2113790512 0.0931376517 0.0803883098 0.1259934455 0.0160136028 0.0295150000 479208229 0 402718720 0.2696999609 0.0983141586 0.0638934746 213 1305031109.2432899475 0.0922869444 0.0804441719 0.1259934455 0.0159807251 0.0285560000 479211429 0 402718720 0.2560471296 0.0988702178 0.0672131479 214 1305031109.2753078938 0.0815330669 0.0804492602 0.1259934455 0.0160294761 0.0287450000 479214517 0 402718720 0.2386410236 0.0883702487 0.0784085616 215 1305031109.3113288879 0.0849030167 0.0804699754 0.1259934455 0.0160445037 0.0249260000 479217773 0 402718720 0.2226447910 0.0911148787 0.0728935897 216 1305031109.3432478905 0.0905164480 0.0805164868 0.1259934455 0.0160092941 0.0298030000 479220973 0 402718720 0.2091018260 0.0964043438 0.0666152835 217 1305031109.3753969669 0.0863369182 0.0805433091 0.1259934455 0.0159966110 0.2014530000 491540081 0 402718720 0.1940887719 0.0919378698 0.0728593841 218 1305031109.4113290310 0.0907713324 0.0805902266 0.1259934455 0.0160932818 0.0382650000 495202545 0 402718720 0.1650775075 0.0958030969 0.0672687888 219 1305031109.4433019161 0.0942929089 0.0806527960 0.1259934455 0.0160587916 0.0337760000 498397881 0 402718720 0.1545479149 0.0989061520 0.0636006370 220 1305031109.4753630161 0.0924956724 0.0807066272 0.1259934455 0.0160358931 0.0298350000 498400969 0 402718720 0.1432207078 0.0963241756 0.0656991377 221 1305031109.5112729073 0.0912667587 0.0807544106 0.1259934455 0.0160188932 0.0286230000 498404225 0 402718720 0.1307957321 0.0935898349 0.0677246451 222 1305031109.5432939529 0.0919915959 0.0808050286 0.1259934455 0.0159873212 0.0651830000 498407425 0 402718720 0.1170472205 0.0933511406 0.0635368004 223 1305031109.5753619671 0.0953169316 0.0808701044 0.1259934455 0.0159535773 0.0271520000 498410569 0 402718720 0.1037781313 0.0959018171 0.0604534149 224 1305031109.6113100052 0.0957297161 0.0809364419 0.1259934455 0.0159371305 0.0308320000 498413769 0 402718720 0.0913730264 0.0952257738 0.0591614321 225 1305031109.6432290077 0.0984619260 0.0810143330 0.1259934455 0.0159015901 0.0301930000 498416969 0 402718720 0.0797058120 0.0980172828 0.0562067702 226 1305031109.6752629280 0.1019275337 0.0811068692 0.1259934455 0.0158702050 0.0305640000 498420057 0 402718720 0.0636094809 0.1015485600 0.0539243557 227 1305031109.7113120556 0.1018630788 0.0811983063 0.1259934455 0.0158504082 0.0313190000 498423313 0 402718720 0.0546793379 0.1020859703 0.0531158075 228 1305031109.7432739735 0.1025115326 0.0812917854 0.1259934455 0.0158206563 0.3641650000 510741821 0 402718720 0.0425367095 0.1033973247 0.0537460968 229 1305031109.7752768993 0.1055749059 0.0813978252 0.1259934455 0.0159408718 0.0416050000 514404117 0 402718720 0.0483533368 0.1037440896 0.0434201583 230 1305031109.8113710880 0.1081437021 0.0815141116 0.1259934455 0.0159266351 0.0345390000 517599565 0 402718720 0.0343712866 0.1064348146 0.0443067737 231 1305031109.8432960510 0.1079123989 0.0816283899 0.1259934455 0.0158959029 0.0318300000 517602765 0 402718720 0.0206752364 0.1073497012 0.0457767472 232 1305031109.8753058910 0.1080855131 0.0817424292 0.1259934455 0.0158780884 0.0337930000 517605853 0 402718720 0.0057534855 0.1086600572 0.0488942675 233 1305031109.9112648964 0.1055919752 0.0818447878 0.1259934455 0.0158556142 0.0637310000 517609109 0 402718720 -0.0070967521 0.1058567166 0.0533333905 234 1305031109.9432990551 0.1114557683 0.0819713304 0.1259934455 0.0158463513 0.0321950000 517612309 0 402718720 -0.0169214662 0.1118390486 0.0523439124 235 1305031109.9752581120 0.1091774181 0.0820871010 0.1259934455 0.0158414391 0.0308160000 517615397 0 402718720 -0.0303680785 0.1102244779 0.0570450313 236 1305031110.0112559795 0.1106794849 0.0822082552 0.1259934455 0.0158198707 0.0310800000 517618653 0 402718720 -0.0413920879 0.1106546670 0.0598883666 237 1305031110.0432989597 0.1108429879 0.0823290769 0.1259934455 0.0157940923 0.3194500000 529993297 0 402718720 -0.0526457988 0.1110147387 0.0629475117 238 1305031110.0753190517 0.1132570058 0.0824590261 0.1259934455 0.0157708965 0.0394860000 533655593 0 402718720 -0.0619807467 0.1133052260 0.0661655217 239 1305031110.1113250256 0.1132962927 0.0825880524 0.1259934455 0.0157742844 0.0322930000 536851041 0 402718720 -0.0760663450 0.1135768294 0.0694295838 240 1305031110.1434319019 0.1092924029 0.0826993205 0.1259934455 0.0157548909 0.0319690000 536854241 0 402718720 -0.0878178999 0.1099997833 0.0728492066 241 1305031110.1756410599 0.1134867296 0.0828270691 0.1259934455 0.0157248565 0.0319590000 536857329 0 402718720 -0.0979413465 0.1148221269 0.0714270994 242 1305031110.2116370201 0.1124751046 0.0829495816 0.1259934455 0.0157085232 0.0313520000 536860641 0 402718720 -0.1092526019 0.1133167148 0.0755004212 243 1305031110.2433230877 0.1107300445 0.0830639045 0.1259934455 0.0156800763 0.0332340000 536863785 0 402718720 -0.1192863435 0.1114747599 0.0776779726 244 1305031110.2793209553 0.1129611582 0.0831864342 0.1259934455 0.0156607376 0.0331590000 536867041 0 402718720 -0.1268540621 0.1109568849 0.0790015310 245 1305031110.3114039898 0.1129746139 0.0833080186 0.1259934455 0.0156316036 0.0662070000 536870129 0 402718720 -0.1385302395 0.1120719686 0.0781554729 246 1305031110.3433549404 0.1159151196 0.0834405678 0.1259934455 0.0156007709 0.0315460000 536873273 0 402718720 -0.1485653371 0.1152008101 0.0772906616 247 1305031110.3792810440 0.1170771942 0.0835767485 0.1259934455 0.0155965777 0.0368690000 536876529 0 402718720 -0.1591141522 0.1148876846 0.0773695484 248 1305031110.4114689827 0.1196143776 0.0837220615 0.1259934455 0.0155701556 0.0343440000 536879673 0 402718720 -0.1711219400 0.1187397316 0.0718965456 249 1305031110.4432599545 0.1214168891 0.0838734464 0.1259934455 0.0155605177 0.3383730000 549195709 0 402718720 -0.1813039780 0.1208273396 0.0725288242 250 1305031110.4793310165 0.1214628816 0.0840238041 0.1259934455 0.0155749549 0.0385100000 552858229 0 402718720 -0.1902266294 0.1182516739 0.0733177438 251 1305031110.5114290714 0.1219184026 0.0841747786 0.1259934455 0.0155506466 0.0293010000 556053509 0 402718720 -0.2004503906 0.1190178096 0.0734050646 252 1305031110.5434079170 0.1265934855 0.0843431068 0.1265934855 0.0155217134 0.0265240000 556056709 0 402718720 -0.2093922347 0.1243715510 0.0727257356 253 1305031110.5794260502 0.1310690045 0.0845277942 0.1310690045 0.0155069746 0.0251950000 556059965 0 402718720 -0.2174485177 0.1277979314 0.0732732117 254 1305031110.6113069057 0.1289691776 0.0847027602 0.1310690045 0.0155182859 0.0296610000 556063053 0 402718720 -0.2239821702 0.1233391985 0.0785913542 255 1305031110.6434180737 0.1280331016 0.0848726831 0.1310690045 0.0154939410 0.0312260000 556066253 0 402718720 -0.2326129228 0.1224631146 0.0790403858 256 1305031110.6796059608 0.1341629922 0.0850652234 0.1341629922 0.0154940752 0.0314180000 556069453 0 402718720 -0.2400169969 0.1293922514 0.0757340565 257 1305031110.7114119530 0.1337834597 0.0852547885 0.1341629922 0.0154662245 0.0279190000 556099221 0 402718720 -0.2451286465 0.1279422492 0.0788908601 258 1305031110.7432489395 0.1332755834 0.0854409156 0.1341629922 0.0154516605 0.0284090000 556153565 0 402718720 -0.2502771914 0.1272310913 0.0794572830 259 1305031110.7791929245 0.1360524148 0.0856363268 0.1360524148 0.0154233261 0.0311490000 556156821 0 402718720 -0.2528221607 0.1291337609 0.0790765136 260 1305031110.8113861084 0.1367749423 0.0858330138 0.1367749423 0.0153954830 0.0329380000 556159965 0 402718720 -0.2552465796 0.1300256550 0.0797474012 261 1305031110.8432180882 0.1352167875 0.0860222237 0.1367749423 0.0153735478 0.0329430000 556163109 0 402718720 -0.2587015033 0.1295824200 0.0799260214 262 1305031110.8793129921 0.1358208060 0.0862122946 0.1367749423 0.0153460985 0.0404800000 556166365 0 402718720 -0.2568336129 0.1294817030 0.0806333870 263 1305031110.9113330841 0.1355950683 0.0864000618 0.1367749423 0.0153222629 0.0380110000 556169509 0 402718720 -0.2562911808 0.1304070950 0.0803336501 264 1305031110.9438619614 0.1362679750 0.0865889554 0.1367749423 0.0153107190 0.0365610000 556172709 0 402718720 -0.2521578968 0.1309709400 0.0816758946 265 1305031110.9793450832 0.1393870264 0.0867881934 0.1393870264 0.0153112071 0.0372570000 556175853 0 402718720 -0.2436036170 0.1341550946 0.0830138996 266 1305031111.0114309788 0.1389990449 0.0869844748 0.1393870264 0.0152950039 0.0347550000 556179053 0 402718720 -0.2339777648 0.1315230429 0.0855769292 267 1305031111.0433270931 0.1371016949 0.0871721798 0.1393870264 0.0152743589 0.0318780000 556182197 0 402718720 -0.2290117741 0.1314987093 0.0841638148 268 1305031111.0792829990 0.1343636811 0.0873482675 0.1393870264 0.0152513918 0.0625310000 556185397 0 402718720 -0.2255353481 0.1339054555 0.0828846768 269 1305031111.1115078926 0.1320007890 0.0875142620 0.1393870264 0.0152445902 0.0325940000 556188597 0 402718720 -0.2133522034 0.1282223761 0.0857650861 270 1305031111.1432569027 0.1299767345 0.0876715304 0.1393870264 0.0152177424 0.0315510000 556191741 0 402718720 -0.2049663365 0.1259137243 0.0866492093 271 1305031111.1793260574 0.1317154914 0.0878340542 0.1393870264 0.0152577738 0.0314370000 556194997 0 402718720 -0.1913033873 0.1271203458 0.0888602808 272 1305031111.2114329338 0.1321180165 0.0879968629 0.1393870264 0.0152499014 0.0322000000 556198085 0 402718720 -0.1800380349 0.1267656535 0.0868798122 273 1305031111.2432360649 0.1237145588 0.0881276970 0.1393870264 0.0152517732 0.0285820000 556201229 0 402718720 -0.1779180020 0.1221768409 0.0849103928 274 1305031111.2793080807 0.1234289929 0.0882565338 0.1393870264 0.0153217507 0.0374970000 556204485 0 402718720 -0.1593218297 0.1177520305 0.0878212452 275 1305031111.3115470409 0.1231537387 0.0883834327 0.1393870264 0.0153931653 0.0317440000 556207629 0 402718720 -0.1576772481 0.1248975024 0.0820921957 276 1305031111.3433969021 0.1204697490 0.0884996875 0.1393870264 0.0153758408 0.0267490000 556210773 0 402718720 -0.1524313390 0.1257709116 0.0822400972 277 1305031111.3791339397 0.1141016483 0.0885921133 0.1393870264 0.0154568943 0.0275330000 556214029 0 402718720 -0.1342391968 0.1153630912 0.0880459920 278 1305031111.4112958908 0.1126999632 0.0886788322 0.1393870264 0.0154782543 0.0312330000 556217117 0 402718720 -0.1289837956 0.1183783561 0.0820905641 279 1305031111.4433860779 0.1180712655 0.0887841815 0.1393870264 0.0154710115 0.0313400000 556220317 0 402718720 -0.1128197834 0.1211866289 0.0911941305 280 1305031111.4792590141 0.1188813373 0.0888916713 0.1393870264 0.0156267407 0.0649000000 556223573 0 402718720 -0.0886965767 0.1153477505 0.1000146791 281 1305031111.5112640858 0.1147177443 0.0889835790 0.1393870264 0.0156836927 0.0303980000 556226661 0 402718720 -0.0808060244 0.1146951839 0.0938741043 282 1305031111.5432500839 0.1116102636 0.0890638155 0.1393870264 0.0156604988 0.0403430000 556229861 0 402718720 -0.0665803254 0.1093206853 0.0973172486 283 1305031111.5792369843 0.1109633595 0.0891411990 0.1393870264 0.0157071413 0.0365250000 556233117 0 402718720 -0.0540495105 0.1130494252 0.0916766748 284 1305031111.6112709045 0.1055550426 0.0891989943 0.1393870264 0.0157093445 0.0392630000 556236149 0 402718720 -0.0508476719 0.1127060056 0.0886840299 285 1305031111.6433949471 0.1028324291 0.0892468309 0.1393870264 0.0157769652 0.0523990000 556239349 0 402718720 -0.0305014160 0.1043041945 0.0969980806 286 1305031111.6793200970 0.1073133945 0.0893100007 0.1393870264 0.0158763543 0.0395170000 556242549 0 402718720 -0.0153245926 0.1115431860 0.0957475752 287 1305031111.7117600441 0.1061314568 0.0893686120 0.1393870264 0.0158566939 0.1612610000 568563817 0 402718720 -0.0035652569 0.1113159880 0.0963994786 288 1305031111.7433860302 0.1035064906 0.0894177019 0.1393870264 0.0158538671 0.0383980000 572226169 0 402718720 0.0134807723 0.1069205031 0.0964717343 289 1305031111.7794229984 0.1031425223 0.0894651926 0.1393870264 0.0159102761 0.0335450000 575421617 0 402718720 0.0272721183 0.1097103506 0.0935597718 290 1305031111.8114058971 0.0984408930 0.0894961433 0.1393870264 0.0159134599 0.0286160000 575424705 0 402718720 0.0341761485 0.1076977998 0.0961430296 291 1305031111.8432989120 0.0974565148 0.0895234985 0.1393870264 0.0159153550 0.0681400000 575427849 0 402718720 0.0457946807 0.1083708555 0.0938064456 292 1305031111.8794419765 0.0938275754 0.0895382385 0.1393870264 0.0158989477 0.0327340000 575431049 0 402718720 0.0509637669 0.1097032651 0.0934425890 293 1305031111.9113540649 0.0873427764 0.0895307455 0.1393870264 0.0158826833 0.0309170000 575434249 0 402718720 0.0548506454 0.1056188643 0.0969529375 294 1305031111.9433000088 0.0881428197 0.0895260246 0.1393870264 0.0158725836 0.3029250000 587756521 0 402718720 0.0688742846 0.1065228283 0.0956497118 295 1305031111.9794490337 0.0921227932 0.0895348273 0.1393870264 0.0160871071 0.0436060000 591418929 0 402718720 0.0995487049 0.1063027456 0.0975640640 296 1305031112.0114328861 0.0924924314 0.0895448192 0.1393870264 0.0160659109 0.0348540000 594614321 0 402718720 0.1144918576 0.1051949039 0.1012725160 297 1305031112.0432701111 0.0932908952 0.0895574322 0.1393870264 0.0160429359 0.0329230000 594617465 0 402718720 0.1304523498 0.1045609862 0.0988043323 298 1305031112.0793390274 0.0920125097 0.0895656707 0.1393870264 0.0160748406 0.0353880000 594620721 0 402718720 0.1459086239 0.1035182923 0.0998327807 299 1305031112.1114230156 0.0898276269 0.0895665468 0.1393870264 0.0161270695 0.0343680000 594623809 0 402718720 0.1490050107 0.1051714271 0.0959900990 300 1305031112.1443419456 0.0922453254 0.0895754761 0.1393870264 0.0161096471 0.0335240000 594626953 0 402718720 0.1686261594 0.1048382744 0.0932829157 301 1305031112.1793899536 0.0902242810 0.0895776316 0.1393870264 0.0161173954 0.3902290000 606956533 0 402718720 0.1828545183 0.1039623022 0.0952246860 302 1305031112.2112538815 0.1007869616 0.0896147486 0.1393870264 0.0161935803 0.0419780000 610618885 0 402718720 0.1906599700 0.1165450290 0.0963810533 303 1305031112.2433691025 0.0971445590 0.0896395994 0.1393870264 0.0161804641 0.0690690000 613814277 0 402718720 0.2006337643 0.1124904901 0.0981065333 304 1305031112.2793529034 0.0987706929 0.0896696359 0.1393870264 0.0161830803 0.0270340000 613817477 0 402718720 0.2058645487 0.1150436550 0.1006114036 305 1305031112.3113119602 0.1009764522 0.0897067075 0.1393870264 0.0161565341 0.0293460000 613820677 0 402718720 0.2188381106 0.1158866733 0.1000321954 306 1305031112.3433229923 0.1002452597 0.0897411472 0.1393870264 0.0161326799 0.0272080000 613823821 0 402718720 0.2243533283 0.1146792769 0.0994984359 307 1305031112.3793599606 0.1012270302 0.0897785605 0.1393870264 0.0161073996 0.0276980000 613827133 0 402718720 0.2347305566 0.1151288971 0.0976928622 308 1305031112.4114420414 0.1019075811 0.0898179404 0.1393870264 0.0160944941 0.2658870000 626141133 0 402718720 0.2452369630 0.1157217473 0.0964056104 309 1305031112.4433910847 0.1010056287 0.0898541465 0.1393870264 0.0160859135 0.0385600000 629803541 0 402718720 0.2583594024 0.1142437682 0.0977633744 310 1305031112.4794180393 0.1023504287 0.0898944571 0.1393870264 0.0160660057 0.0330880000 632998989 0 402718720 0.2642988265 0.1157358959 0.0972172469 311 1305031112.5115039349 0.1016834825 0.0899323639 0.1393870264 0.0160535565 0.0360800000 633002077 0 402718720 0.2733564675 0.1152424812 0.0958558694 312 1305031112.5432119370 0.1008995250 0.0899675151 0.1393870264 0.0160433707 0.0350110000 633005221 0 402718720 0.2836541533 0.1145452559 0.0950045884 313 1305031112.5792520046 0.1010541543 0.0900029357 0.1393870264 0.0160256894 0.0683710000 633008421 0 402718720 0.2914643586 0.1152860746 0.0945363343 314 1305031112.6112608910 0.1033292785 0.0900453763 0.1393870264 0.0160846083 0.0336690000 633011565 0 402718720 0.3084647655 0.1182540357 0.0917148069 315 1305031112.6432459354 0.1028330252 0.0900859720 0.1393870264 0.0160833730 0.0344100000 633014765 0 402718720 0.3174865842 0.1189032570 0.0925041288 316 1305031112.6799519062 0.0999655873 0.0901172366 0.1393870264 0.0160707907 0.0332200000 633018021 0 402718720 0.3204127848 0.1177565977 0.0926127508 317 1305031112.7112510204 0.0997023806 0.0901474736 0.1393870264 0.0160585459 0.0332360000 633021109 0 402718720 0.3222927749 0.1193641871 0.0923808888 318 1305031112.7432448864 0.1042355970 0.0901917759 0.1393870264 0.0160387456 0.0362940000 633024309 0 402718720 0.3249282241 0.1256885529 0.0898119584 319 1305031112.7793099880 0.0983216092 0.0902172613 0.1393870264 0.0160235138 0.0349430000 633027565 0 402718720 0.3234321773 0.1229396760 0.0946509987 320 1305031112.8113100529 0.0937390104 0.0902282667 0.1393870264 0.0160319865 0.0306610000 633030653 0 402718720 0.3133965731 0.1198511347 0.0969239399 321 1305031112.8432860374 0.0966077372 0.0902481405 0.1393870264 0.0160087961 0.0321340000 633033797 0 402718720 0.3106152415 0.1242399737 0.0964445397 322 1305031112.8794209957 0.0945017412 0.0902613504 0.1393870264 0.0160142726 0.0370820000 633037053 0 402718720 0.3088524640 0.1240481660 0.0987994149 323 1305031112.9114110470 0.0931815878 0.0902703914 0.1393870264 0.0159936984 0.0356980000 633040253 0 402718720 0.3012664616 0.1230679601 0.0997274444 324 1305031112.9433209896 0.0927175954 0.0902779445 0.1393870264 0.0159712121 0.0339380000 633043397 0 402718720 0.2948505282 0.1228968501 0.1013363078 325 1305031112.9792780876 0.0937056839 0.0902884914 0.1393870264 0.0160026344 0.0616570000 633046653 0 402718720 0.2907117903 0.1237349883 0.1009930670 326 1305031113.0113530159 0.0967823043 0.0903084111 0.1393870264 0.0159808679 0.0341350000 633049741 0 402718720 0.2873271108 0.1260042489 0.0981349498 327 1305031113.0432310104 0.0981809646 0.0903324861 0.1393870264 0.0159577480 0.0330410000 633052941 0 402718720 0.2800797522 0.1264028698 0.0976268426 328 1305031113.0792510509 0.0944260135 0.0903449664 0.1393870264 0.0159700246 0.0348730000 633056197 0 402718720 0.2688437700 0.1202398613 0.0997537002 329 1305031113.1113159657 0.0993317887 0.0903722820 0.1393870264 0.0159541172 0.0316010000 633059285 0 402718720 0.2585799098 0.1232094541 0.0947161764 330 1305031113.1433060169 0.1073534563 0.0904237401 0.1393870264 0.0159352247 0.0449530000 633062485 0 402718720 0.2510982156 0.1296647191 0.0937494040 331 1305031113.1793429852 0.1022737697 0.0904595408 0.1393870264 0.0159588915 0.0327240000 633065741 0 402718720 0.2362315953 0.1218006983 0.0941242799 332 1305031113.2112588882 0.1030157655 0.0904973607 0.1393870264 0.0159369162 0.0274120000 633068829 0 402718720 0.2219798118 0.1206513569 0.0912730098 333 1305031113.2432270050 0.1092897728 0.0905537944 0.1393870264 0.0159158856 0.3246520000 645387077 0 402718720 0.2120151669 0.1245409772 0.0846905932 334 1305031113.2793118954 0.1087215543 0.0906081889 0.1393870264 0.0159621232 0.0398730000 649049485 0 402718720 0.1988160461 0.1204331443 0.0803456753 335 1305031113.3114519119 0.1048801094 0.0906507916 0.1393870264 0.0159576099 0.0318580000 652244821 0 402718720 0.1806751192 0.1146996468 0.0829744488 336 1305031113.3432519436 0.1144533232 0.0907216325 0.1393870264 0.0159491897 0.0672080000 652247965 0 402718720 0.1671303511 0.1213647351 0.0742930472 337 1305031113.3793120384 0.1191992238 0.0908061357 0.1393870264 0.0159489285 0.0279570000 652251165 0 402718720 0.1522293687 0.1231061667 0.0738914162 338 1305031113.4116249084 0.1151818037 0.0908782531 0.1393870264 0.0159361317 0.0282270000 652254365 0 402718720 0.1377317309 0.1170125976 0.0801473334 339 1305031113.4432659149 0.1215827465 0.0909688268 0.1393870264 0.0159150302 0.0265710000 652257509 0 402718720 0.1237445772 0.1204622388 0.0750352591 340 1305031113.4793109894 0.1265905797 0.0910735967 0.1393870264 0.0159209143 0.0274880000 652260709 0 402718720 0.1088233069 0.1218094528 0.0729999691 341 1305031113.5115230083 0.1264006644 0.0911771951 0.1393870264 0.0159076933 0.4447320000 664577705 0 402718720 0.0946468189 0.1195475534 0.0734347329 342 1305031113.5432419777 0.1222828701 0.0912681474 0.1393870264 0.0159326865 0.0417460000 668240057 0 402718720 0.0851121247 0.1126269624 0.0766466185 343 1305031113.5793011189 0.1296443343 0.0913800313 0.1393870264 0.0159164769 0.0353230000 671435449 0 402718720 0.0749053136 0.1154801399 0.0744017363 344 1305031113.6112680435 0.1313830614 0.0914963192 0.1393870264 0.0158972590 0.0329840000 671438649 0 402718720 0.0637361258 0.1155837253 0.0740406290 345 1305031113.6432220936 0.1323099136 0.0916146195 0.1393870264 0.0158752069 0.0334710000 671441793 0 402718720 0.0518703870 0.1157356948 0.0737949833 346 1305031113.6792879105 0.1343296617 0.0917380734 0.1393870264 0.0158585023 0.0747610000 671445105 0 402718720 0.0398230590 0.1151382178 0.0752288401 347 1305031113.7119309902 0.1346659958 0.0918617849 0.1393870264 0.0158428071 0.0388050000 671448193 0 402718720 0.0293684937 0.1144071966 0.0765499920 348 1305031113.7435901165 0.1370708048 0.0919916959 0.1393870264 0.0158204790 0.0393260000 671451393 0 402718720 0.0194220692 0.1153429076 0.0760035068 349 1305031113.7793200016 0.1373597831 0.0921216904 0.1393870264 0.0158077676 0.0352220000 671454593 0 402718720 0.0061002481 0.1138594896 0.0766675919 350 1305031113.8112370968 0.1386910081 0.0922547456 0.1393870264 0.0157857139 0.0347630000 671457681 0 402718720 -0.0045573181 0.1147833765 0.0751512870 351 1305031113.8432950974 0.1411527991 0.0923940563 0.1411527991 0.0157691545 0.0475330000 671460881 0 402718720 -0.0163659062 0.1172192171 0.0755100548 352 1305031113.8792810440 0.1384521574 0.0925249032 0.1411527991 0.0157784033 0.0376720000 671464137 0 402718720 -0.0309164971 0.1133733466 0.0805685818 353 1305031113.9112899303 0.1409337372 0.0926620387 0.1411527991 0.0157614845 0.0388840000 671467281 0 402718720 -0.0403218940 0.1147801355 0.0766679272 354 1305031113.9432909489 0.1432452947 0.0928049293 0.1432452947 0.0157420762 0.5019880000 683804333 0 402718720 -0.0492564924 0.1155525222 0.0787853822 355 1305031113.9792931080 0.1390969455 0.0929353293 0.1432452947 0.0157423491 0.0449920000 687466797 0 402718720 -0.0691123679 0.1127043590 0.0817667544 356 1305031114.0112569332 0.1403246522 0.0930684454 0.1432452947 0.0157321344 0.0353210000 690662133 0 402718720 -0.0832948163 0.1149383262 0.0814569294 357 1305031114.0433011055 0.1390958130 0.0931973736 0.1432452947 0.0157177182 0.0434850000 690665277 0 402718720 -0.1004758626 0.1160321012 0.0818966851 358 1305031114.0792849064 0.1419504732 0.0933335554 0.1432452947 0.0157059075 0.0406900000 690668533 0 402718720 -0.1120870188 0.1159591898 0.0828656778 359 1305031114.1112630367 0.1451762915 0.0934779642 0.1451762915 0.0156843948 0.0426740000 690671677 0 402718720 -0.1233849823 0.1188846007 0.0817394555 360 1305031114.1432840824 0.1465011686 0.0936252508 0.1465011686 0.0156755264 0.0418170000 690674877 0 402718720 -0.1336707920 0.1193915308 0.0827159807 361 1305031114.1793370247 0.1479077935 0.0937756180 0.1479077935 0.0156762715 0.0415330000 690678133 0 402718720 -0.1405183375 0.1152722612 0.0834888071 362 1305031114.2113029957 0.1537845582 0.0939413886 0.1537845582 0.0156720409 0.0457680000 690681221 0 402718720 -0.1527702957 0.1230689734 0.0805802196 363 1305031114.2433369160 0.1508975178 0.0940982925 0.1537845582 0.0156598192 0.0412310000 690684365 0 402718720 -0.1672921628 0.1225428581 0.0835852176 364 1305031114.2793900967 0.1510037184 0.0942546261 0.1537845582 0.0156822386 0.0463070000 690687621 0 402718720 -0.1803279817 0.1214874163 0.0814996660 365 1305031114.3114290237 0.1531201899 0.0944159016 0.1537845582 0.0156621538 0.3956680000 703018221 0 402718720 -0.1896032542 0.1232857108 0.0820900500 366 1305031114.3433310986 0.1525369287 0.0945747022 0.1537845582 0.0156411031 0.0442200000 706680629 0 402718720 -0.1998004317 0.1227945983 0.0860862881 367 1305031114.3793199062 0.1555436254 0.0947408301 0.1555436254 0.0156253228 0.0320050000 709876077 0 402718720 -0.2064438611 0.1213498935 0.0878802016 368 1305031114.4113969803 0.1553206593 0.0949054492 0.1555436254 0.0156131516 0.0611070000 709879221 0 402718720 -0.2183755487 0.1221425161 0.0874081478 369 1305031114.4433450699 0.1558365673 0.0950705742 0.1558365673 0.0155940204 0.0301850000 709882365 0 402718720 -0.2296288610 0.1237074807 0.0872216448 370 1305031114.4793319702 0.1568060219 0.0952374267 0.1568060219 0.0155933479 0.0295960000 709885621 0 402718720 -0.2396166772 0.1223644838 0.0880734026 371 1305031114.5112659931 0.1611436605 0.0954150716 0.1611436605 0.0155752018 0.0302480000 709888709 0 402718720 -0.2442870885 0.1241757870 0.0877332166 372 1305031114.5432360172 0.1635389179 0.0955982002 0.1635389179 0.0155618602 0.0313430000 709891909 0 402718720 -0.2458327860 0.1222615764 0.0911511853 373 1305031114.5792369843 0.1651492417 0.0957846641 0.1651492417 0.0155450802 0.0413970000 709895165 0 402718720 -0.2501724660 0.1207172796 0.0918291137 374 1305031114.6113910675 0.1671100259 0.0959753736 0.1671100259 0.0155254627 0.0283140000 709898253 0 402718720 -0.2553839087 0.1225978136 0.0904231817 375 1305031114.6441359520 0.1652654707 0.0961601472 0.1671100259 0.0155075254 0.0361380000 709901397 0 402718720 -0.2626435459 0.1220249161 0.0915656760 376 1305031114.6792509556 0.1642519385 0.0963412424 0.1671100259 0.0154934562 0.0348580000 709904597 0 402718720 -0.2660205960 0.1187679693 0.0929629654 377 1305031114.7113060951 0.1650223881 0.0965234205 0.1671100259 0.0154825685 0.0334870000 709907685 0 402718720 -0.2658249736 0.1167971119 0.0951929465 378 1305031114.7432000637 0.1653494388 0.0967054999 0.1671100259 0.0154627133 0.0395670000 709910829 0 402718720 -0.2661312819 0.1156600118 0.0962281451 379 1305031114.7792890072 0.1672124416 0.0968915341 0.1672124416 0.0154446401 0.0405300000 709914141 0 402718720 -0.2648253739 0.1165222600 0.0950237960 380 1305031114.8113029003 0.1685044020 0.0970799890 0.1685044020 0.0154289869 0.0354130000 709917229 0 402718720 -0.2643615603 0.1191617623 0.0936010629 381 1305031114.8432080746 0.1669729054 0.0972634350 0.1685044020 0.0154096097 0.0395350000 709920429 0 402718720 -0.2631008923 0.1184622273 0.0937622637 382 1305031114.8792810440 0.1671617031 0.0974464147 0.1685044020 0.0153894993 0.0393750000 709923629 0 402718720 -0.2596174777 0.1210903227 0.0931244045 383 1305031114.9128789902 0.1661946774 0.0976259141 0.1685044020 0.0153717844 0.0382440000 709926885 0 402718720 -0.2569016516 0.1228382960 0.0928484425 384 1305031114.9432339668 0.1684116423 0.0978102519 0.1685044020 0.0153521758 0.0394260000 709929861 0 402718720 -0.2482933402 0.1255620122 0.0955276936 385 1305031114.9792799950 0.1647793353 0.0979841976 0.1685044020 0.0153380025 0.0364760000 709933173 0 402718720 -0.2436786741 0.1275837421 0.0960303843 386 1305031115.0113000870 0.1652746499 0.0981585252 0.1685044020 0.0153211692 0.0323930000 709936317 0 402718720 -0.2369496971 0.1317793578 0.0977429152 387 1305031115.0435080528 0.1627223045 0.0983253567 0.1685044020 0.0153118176 0.0324270000 709939461 0 402718720 -0.2248059809 0.1278775781 0.1027325988 388 1305031115.0792379379 0.1605723500 0.0984857871 0.1685044020 0.0153038032 0.0447760000 709942773 0 402718720 -0.2169360220 0.1318458319 0.1037730351 389 1305031115.1112298965 0.1626215428 0.0986506605 0.1685044020 0.0152988150 0.0337180000 709945861 0 402718720 -0.2013535947 0.1325964034 0.1116565391 390 1305031115.1432750225 0.1567996442 0.0987997604 0.1685044020 0.0152803036 0.0334490000 709949005 0 402718720 -0.1936263591 0.1292098761 0.1123012826 391 1305031115.1794400215 0.1491438448 0.0989285177 0.1685044020 0.0152759264 0.0322680000 709952317 0 402718720 -0.1902830005 0.1309925467 0.1124025807 392 1305031115.2113740444 0.1458407193 0.0990481917 0.1685044020 0.0152890951 0.0268750000 709955405 0 402718720 -0.1730189025 0.1238437891 0.1197695136 393 1305031115.2432971001 0.1407185495 0.0991542231 0.1685044020 0.0152707931 0.0297710000 709958605 0 402718720 -0.1614423245 0.1195220649 0.1219875440 394 1305031115.2799661160 0.1385717243 0.0992542675 0.1685044020 0.0152888502 0.0346100000 709961805 0 402718720 -0.1524588615 0.1266881824 0.1252574623 395 1305031115.3117039204 0.1361814886 0.0993477542 0.1685044020 0.0153199914 0.0298710000 709965005 0 402718720 -0.1310122013 0.1194501147 0.1355725974 396 1305031115.3432350159 0.1353749186 0.0994387318 0.1685044020 0.0153112082 0.0362180000 709968037 0 402718720 -0.1188705713 0.1224194542 0.1340716183 397 1305031115.3791658878 0.1263040453 0.0995064027 0.1685044020 0.0153909330 0.0361620000 709971293 0 402718720 -0.1201379895 0.1282272786 0.1277965456 398 1305031115.4112370014 0.1201799139 0.0995583462 0.1685044020 0.0153859308 0.0368430000 709974437 0 402718720 -0.1077226698 0.1251821220 0.1356852055 399 1305031115.4431591034 0.1187451929 0.0996064335 0.1685044020 0.0153893808 0.0460810000 709977581 0 402718720 -0.0886224359 0.1235138625 0.1433985978 400 1305031115.4792408943 0.1133284122 0.0996407384 0.1685044020 0.0153735735 0.0393430000 709980837 0 402718720 -0.0741600767 0.1238060594 0.1446591020 401 1305031115.5112531185 0.1130628958 0.0996742102 0.1685044020 0.0154268052 0.0422610000 709983925 0 402718720 -0.0519721508 0.1216791272 0.1564800590 402 1305031115.5436038971 0.1100428328 0.0997000027 0.1685044020 0.0154161382 0.2695340000 722325653 0 402718720 -0.0321475193 0.1172013804 0.1564368457 403 1305031115.5793149471 0.1012539342 0.0997038587 0.1685044020 0.0154090083 0.0416440000 725988173 0 402718720 -0.0261291917 0.1181178391 0.1524188370 404 1305031115.6114239693 0.0984734222 0.0997008130 0.1685044020 0.0153954806 0.0336480000 729183453 0 402718720 -0.0132187894 0.1176201180 0.1539477259 405 1305031115.6432540417 0.0960967541 0.0996919141 0.1685044020 0.0153849283 0.0629520000 729186597 0 402718720 0.0014314140 0.1158204973 0.1549535990 406 1305031115.6792409420 0.0898397714 0.0996676477 0.1685044020 0.0153669175 0.0311480000 729189853 0 402718720 0.0101372665 0.1148140207 0.1512705535 407 1305031115.7113199234 0.0927453339 0.0996506396 0.1685044020 0.0154000934 0.0290030000 729192997 0 402718720 0.0288763344 0.1173121482 0.1517935991 408 1305031115.7432498932 0.0924636424 0.0996330244 0.1685044020 0.0154023668 0.0292030000 729196197 0 402718720 0.0474859960 0.1161637306 0.1560862958 409 1305031115.7794249058 0.0883942768 0.0996055458 0.1685044020 0.0154108387 0.0287890000 729199453 0 402718720 0.0600537620 0.1156204045 0.1538360566 410 1305031115.8112769127 0.0895764828 0.0995810847 0.1685044020 0.0154117431 0.4510850000 741535837 0 402718720 0.0753415152 0.1174365133 0.1520228237 411 1305031115.8432240486 0.0901860818 0.0995582258 0.1685044020 0.0154215303 0.0366000000 745205589 0 402718720 0.0969324186 0.1166639030 0.1560341269 412 1305031115.8791980743 0.0820122883 0.0995156386 0.1685044020 0.0154080161 0.0301510000 748400925 0 402718720 0.1046635285 0.1134903356 0.1569666713 413 1305031115.9111180305 0.0841915235 0.0994785342 0.1685044020 0.0154062741 0.0287150000 748404069 0 402718720 0.1199909821 0.1167575270 0.1556765735 414 1305031115.9433109760 0.0838686675 0.0994408292 0.1685044020 0.0153976222 0.0276020000 748407157 0 402718720 0.1323136687 0.1185279042 0.1548060179 415 1305031115.9807400703 0.0804653689 0.0993951052 0.1685044020 0.0154041523 0.0629530000 748410413 0 402718720 0.1448479295 0.1193450540 0.1553520411 416 1305031116.0113790035 0.0802947059 0.0993491908 0.1685044020 0.0154286698 0.0273070000 748413501 0 402718720 0.1602139622 0.1204276234 0.1551498920 417 1305031116.0431640148 0.0767012909 0.0992948793 0.1685044020 0.0154109416 0.5000660000 760752645 0 402718720 0.1699324846 0.1199529693 0.1573849916 418 1305031116.0800299644 0.0745329335 0.0992356401 0.1685044020 0.0154209678 0.0347130000 764414597 0 402718720 0.1812552065 0.1228326559 0.1579118669 419 1305031116.1112999916 0.0712551549 0.0991688609 0.1685044020 0.0154037105 0.0295360000 767609877 0 402718720 0.1902440935 0.1226401776 0.1604366302 420 1305031116.1434409618 0.0663426071 0.0990907032 0.1685044020 0.0154109641 0.0657280000 767612965 0 402718720 0.1903840899 0.1225941256 0.1635021418 421 1305031116.1795721054 0.0646954253 0.0990090042 0.1685044020 0.0154079219 0.0276610000 767616277 0 402718720 0.1962764412 0.1241025701 0.1657249928 422 1305031116.2112989426 0.0649470612 0.0989282887 0.1685044020 0.0154016263 0.0225730000 767619365 0 402718720 0.2003521621 0.1263846457 0.1687065959 423 1305031116.2433199883 0.0608159602 0.0988381886 0.1685044020 0.0153881251 0.0228090000 767622565 0 402718720 0.2059623003 0.1232991517 0.1735289991 424 1305031116.2793850899 0.0605974607 0.0987479982 0.1685044020 0.0153796657 0.3150860000 779950437 0 402718720 0.2135593742 0.1232964769 0.1742523462 425 1305031116.3113360405 0.0647456944 0.0986679928 0.1685044020 0.0153713968 0.0294280000 783612733 0 402718720 0.2218316346 0.1273684502 0.1664814055 426 1305031116.3432919979 0.0660891011 0.0985915165 0.1685044020 0.0153759134 0.0375880000 786808069 0 402718720 0.2214991450 0.1269268543 0.1706442982 427 1305031116.3793840408 0.0721520409 0.0985295974 0.1685044020 0.0153602988 0.0253340000 786811269 0 402718720 0.2214982659 0.1293121874 0.1682201177 428 1305031116.4113330841 0.0753440410 0.0984754255 0.1685044020 0.0153427973 0.0234630000 786814469 0 402718720 0.2222221345 0.1307710707 0.1622292548 429 1305031116.4433689117 0.0786147267 0.0984291302 0.1685044020 0.0153430455 0.0229240000 786817669 0 402718720 0.2240176648 0.1343349069 0.1591554880 430 1305031116.4798500538 0.0779585391 0.0983815242 0.1685044020 0.0153286850 0.0227500000 786820925 0 402718720 0.2224542797 0.1330041438 0.1595203727 431 1305031116.5112049580 0.0816979483 0.0983428152 0.1685044020 0.0153132611 0.0221720000 786824013 0 402718720 0.2224668115 0.1374976784 0.1556636095 432 1305031116.5432620049 0.0830202177 0.0983073462 0.1685044020 0.0152963199 0.0467660000 786827157 0 402718720 0.2190206051 0.1382796317 0.1530975848 433 1305031116.5793130398 0.0860189199 0.0982789665 0.1685044020 0.0152828762 0.0254150000 786830413 0 402718720 0.2137822211 0.1415485740 0.1496759206 434 1305031116.6112608910 0.0938437507 0.0982687471 0.1685044020 0.0152879139 0.0269880000 786833501 0 402718720 0.2072342187 0.1494004726 0.1506722569 435 1305031116.6433548927 0.0941184089 0.0982592061 0.1685044020 0.0152834982 0.0281090000 786836645 0 402718720 0.2013850659 0.1496092081 0.1511279196 436 1305031116.6792809963 0.0929590687 0.0982470498 0.1685044020 0.0152722861 0.0292930000 786840013 0 402718720 0.1972247213 0.1479739398 0.1521054655 437 1305031116.7116339207 0.0948533267 0.0982392838 0.1685044020 0.0152598043 0.0307290000 786843101 0 402718720 0.1915073991 0.1482967585 0.1526224464 438 1305031116.7432909012 0.0987144113 0.0982403686 0.1685044020 0.0152438772 0.0311780000 786846245 0 402718720 0.1844840646 0.1504055858 0.1535403579 439 1305031116.7792980671 0.1005973071 0.0982457375 0.1685044020 0.0152479122 0.0290860000 786849501 0 402718720 0.1779854745 0.1482198536 0.1550157219 440 1305031116.8113179207 0.1073100045 0.0982663381 0.1685044020 0.0152439257 0.0314310000 786852589 0 402718720 0.1681854129 0.1520946622 0.1601383239 441 1305031116.8460888863 0.1146446168 0.0983034770 0.1685044020 0.0152732170 0.0303730000 786855845 0 402718720 0.1606279612 0.1541698873 0.1567968875 442 1305031116.8801651001 0.1173549592 0.0983465799 0.1685044020 0.0152781227 0.0292640000 786859045 0 402718720 0.1530154943 0.1527783424 0.1566870958 443 1305031116.9120440483 0.1246215329 0.0984058913 0.1685044020 0.0152613842 0.0286270000 786862189 0 402718720 0.1448793411 0.1558535248 0.1607497931 444 1305031116.9432959557 0.1294506788 0.0984758120 0.1685044020 0.0152622535 1.0791190000 799174297 0 402718720 0.1347444206 0.1578831077 0.1588475406 445 1305031116.9793510437 0.1236705109 0.0985324293 0.1685044020 0.0153253010 0.0330590000 802836705 0 402718720 0.1137715504 0.1522391737 0.1462920308 446 1305031117.0113821030 0.1299147159 0.0986027932 0.1685044020 0.0153236600 0.0299300000 806032097 0 402718720 0.1067702919 0.1546102911 0.1444289982 447 1305031117.0432610512 0.1353635192 0.0986850320 0.1685044020 0.0153193433 0.0286420000 806035241 0 402718720 0.1009049937 0.1557447910 0.1407311559 448 1305031117.0795199871 0.1449767351 0.0987883617 0.1685044020 0.0153370431 0.0288880000 806038497 0 402718720 0.0943895876 0.1601300687 0.1472691596 449 1305031117.1112380028 0.1492825598 0.0989008209 0.1685044020 0.0153467557 0.0272920000 806041585 0 402718720 0.0901411101 0.1602600366 0.1473425925 450 1305031117.1432180405 0.1569189131 0.0990297500 0.1685044020 0.0153512420 0.0280390000 806044785 0 402718720 0.0875405744 0.1642736942 0.1448782831 451 1305031117.1792640686 0.1665834039 0.0991795364 0.1685044020 0.0153365300 0.2382100000 818350445 0 402718720 0.0874655247 0.1668416411 0.1470235288 452 1305031117.2113609314 0.1678039134 0.0993313602 0.1685044020 0.0153631185 0.0402000000 822012797 0 402718720 0.0855041668 0.1646123528 0.1426976174 453 1305031117.2432770729 0.1712491214 0.0994901191 0.1712491214 0.0153546289 0.0415600000 825208133 0 402718720 0.0863374472 0.1631237119 0.1402499378 454 1305031117.2792990208 0.1727889627 0.0996515703 0.1727889627 0.0153382416 0.0405590000 825211389 0 402718720 0.0839214548 0.1625686884 0.1433478296 455 1305031117.3111999035 0.1736357659 0.0998141729 0.1736357659 0.0153265275 0.0362410000 825214477 0 402718720 0.0813309923 0.1630249321 0.1460433155 456 1305031117.3432428837 0.1741514802 0.0999771933 0.1741514802 0.0153113925 0.0753520000 825217677 0 402718720 0.0794541165 0.1627978384 0.1486686319 457 1305031117.3794538975 0.1752696186 0.1001419470 0.1752696186 0.0152981160 0.0332040000 825220933 0 402718720 0.0781646371 0.1614296287 0.1491523981 458 1305031117.4112210274 0.1767476946 0.1003092084 0.1767476946 0.0152845654 0.0315390000 825224077 0 402718720 0.0763845891 0.1613558531 0.1523193866 459 1305031117.4432740211 0.1777283102 0.1004778775 0.1777283102 0.0152695782 0.0305410000 825227221 0 402718720 0.0762404874 0.1591314226 0.1497724503 460 1305031117.4794030190 0.1785690933 0.1006476410 0.1785690933 0.0152616869 0.0316500000 825230477 0 402718720 0.0743047521 0.1558589637 0.1509530395 461 1305031117.5113248825 0.1807887107 0.1008214828 0.1807887107 0.0152474882 0.0333530000 825233621 0 402718720 0.0730028674 0.1543816924 0.1543904990 462 1305031117.5442850590 0.1825233251 0.1009983266 0.1825233251 0.0152357275 0.0344680000 825236709 0 402718720 0.0724993572 0.1516157985 0.1528920680 463 1305031117.5791549683 0.1862649322 0.1011824878 0.1862649322 0.0152213085 0.0347300000 825240021 0 402718720 0.0715163276 0.1498710960 0.1527293473 464 1305031117.6111590862 0.1874928772 0.1013685015 0.1874928772 0.0152055014 0.0359100000 825243109 0 402718720 0.0700599924 0.1467021108 0.1535521001 465 1305031117.6432518959 0.1883056313 0.1015554631 0.1883056313 0.0151896204 0.0356790000 825246253 0 402718720 0.0682095289 0.1432608068 0.1545456797 466 1305031117.6792619228 0.1920676231 0.1017496952 0.1920676231 0.0151754736 0.0368290000 825249565 0 402718720 0.0668883696 0.1409588903 0.1556973159 467 1305031117.7111840248 0.1922594607 0.1019435063 0.1922594607 0.0151597518 0.0387110000 825252597 0 402718720 0.0653574839 0.1360167712 0.1575699747 468 1305031117.7431840897 0.1934356987 0.1021390024 0.1934356987 0.0151443150 0.0779360000 825255797 0 402718720 0.0634019077 0.1318443120 0.1592466831 469 1305031117.7794671059 0.1986187994 0.1023447163 0.1986187994 0.0151297454 0.0368080000 825259053 0 402718720 0.0623788685 0.1292792559 0.1603816003 470 1305031117.8113200665 0.1991162300 0.1025506131 0.1991162300 0.0151172557 0.0380040000 825262197 0 402718720 0.0603555590 0.1230122298 0.1624652594 471 1305031117.8432910442 0.2021869719 0.1027621553 0.2021869719 0.0151059696 0.0389410000 825265173 0 402718720 0.0608217157 0.1179826409 0.1631811708 472 1305031117.8794510365 0.2084947526 0.1029861650 0.2084947526 0.0150912172 0.0390720000 825268429 0 402718720 0.0596840978 0.1150048003 0.1648532152 473 1305031117.9114069939 0.2094799429 0.1032113104 0.2094799429 0.0150797931 0.0390200000 825271573 0 402718720 0.0561881997 0.1097465232 0.1665870398 474 1305031117.9432530403 0.2140524238 0.1034451524 0.2140524238 0.0150679642 0.0377070000 825274661 0 402718720 0.0549667701 0.1071367562 0.1685752720 475 1305031117.9792280197 0.2196842134 0.1036898662 0.2196842134 0.0150636326 0.0380690000 825277917 0 402718720 0.0516361520 0.1042045653 0.1710883379 476 1305031118.0112280846 0.2201045007 0.1039344348 0.2201045007 0.0150504122 0.0385630000 825281061 0 402718720 0.0490370318 0.0974535719 0.1738246083 477 1305031118.0435209274 0.2240621001 0.1041862748 0.2240621001 0.0150377880 0.0383620000 825284205 0 402718720 0.0468100086 0.0939245224 0.1753183007 478 1305031118.0793340206 0.2301346064 0.1044497650 0.2301346064 0.0150230394 0.0391360000 825287461 0 402718720 0.0461584963 0.0892082900 0.1771851629 479 1305031118.1112170219 0.2329736203 0.1047180820 0.2329736203 0.0150096090 0.3030970000 837604369 0 402718720 0.0452883095 0.0839298517 0.1790501475 480 1305031118.1432559490 0.2287615538 0.1049765059 0.2329736203 0.0150242046 0.0476100000 841266777 0 402718720 0.0409698673 0.0728606284 0.1831314862 481 1305031118.1793229580 0.2330661267 0.1052428045 0.2330661267 0.0150087680 0.0327380000 844462225 0 402718720 0.0379177667 0.0676170439 0.1856445819 482 1305031118.2112019062 0.2358745039 0.1055138246 0.2358745039 0.0149966565 0.0272670000 844465313 0 402718720 0.0332838073 0.0639813021 0.1870567501 483 1305031118.2431728840 0.2398705781 0.1057919960 0.2398705781 0.0149897874 0.0330540000 844468457 0 402718720 0.0314956233 0.0604489185 0.1878126264 484 1305031118.2791941166 0.2447816879 0.1060791647 0.2447816879 0.0149865114 0.0701140000 844471713 0 402718720 0.0301535428 0.0549599864 0.1891439557 485 1305031118.3112990856 0.2495349795 0.1063749499 0.2495349795 0.0149737745 0.0311180000 844474857 0 402718720 0.0290259179 0.0518607534 0.1880390495 486 1305031118.3433239460 0.2540428936 0.1066787934 0.2540428936 0.0149659342 0.2078770000 856899901 0 402718720 0.0299892109 0.0489487723 0.1887748539 487 1305031118.3792080879 0.2579179704 0.1069893462 0.2579179704 0.0149542355 0.0442420000 860562365 0 402718720 0.0289628468 0.0459007844 0.1917580366 488 1305031118.4112958908 0.2615304589 0.1073060288 0.2615304589 0.0149416076 0.0328500000 863757701 0 402718720 0.0284823701 0.0450953767 0.1919174790 489 1305031118.4456920624 0.2632452548 0.1076249229 0.2632452548 0.0149285804 0.0700940000 863760845 0 402718720 0.0290189590 0.0436600819 0.1928765327 490 1305031118.4792850018 0.2636231780 0.1079432867 0.2636231780 0.0149139061 0.0289720000 863764045 0 402718720 0.0281052366 0.0420316905 0.1933887154 491 1305031118.5112550259 0.2656940520 0.1082645713 0.2656940520 0.0149028159 0.0305930000 863767189 0 402718720 0.0304016061 0.0432411097 0.1933929473 492 1305031118.5444140434 0.2656572759 0.1085844752 0.2656940520 0.0148887809 0.0283670000 863770333 0 402718720 0.0310537368 0.0450051576 0.1937381625 493 1305031118.5792849064 0.2618051767 0.1088952677 0.2656940520 0.0148742246 0.0293290000 863773645 0 402718720 0.0322314315 0.0448919944 0.1938422769 494 1305031118.6161420345 0.2580685318 0.1091972379 0.2656940520 0.0148619578 0.0304620000 863776901 0 402718720 0.0343427472 0.0470618047 0.1944355369 495 1305031118.6453249454 0.2584523261 0.1094987633 0.2656940520 0.0148474933 0.0506060000 863779933 0 402718720 0.0359340534 0.0516225286 0.1949015856 496 1305031118.6792950630 0.2513020039 0.1097846569 0.2656940520 0.0148353474 0.0367480000 863783245 0 402718720 0.0358457193 0.0535400249 0.1948287636 497 1305031118.7114210129 0.2445722520 0.1100558593 0.2656940520 0.0148299017 0.0287360000 863786333 0 402718720 0.0348660089 0.0545339361 0.1944388449 498 1305031118.7467699051 0.2396976054 0.1103161841 0.2656940520 0.0148155149 0.0371650000 863789533 0 402718720 0.0358751938 0.0609931983 0.1947036833 499 1305031118.7792770863 0.2389502525 0.1105739678 0.2656940520 0.0148078527 0.0382270000 863792789 0 402718720 0.0408383198 0.0680655688 0.1940054595 500 1305031118.8112208843 0.2284394056 0.1108096987 0.2656940520 0.0148358524 0.0314870000 863795877 0 402718720 0.0415149443 0.0660587102 0.1924796999 501 1305031118.8467528820 0.2215922475 0.1110308216 0.2656940520 0.0148374799 0.0288000000 863799077 0 402718720 0.0457752421 0.0698249713 0.1899615377 502 1305031118.8792080879 0.2225246578 0.1112529208 0.2656940520 0.0148443613 0.0315400000 863802333 0 402718720 0.0499626622 0.0796654373 0.1863487810 503 1305031118.9111769199 0.2154565603 0.1114600851 0.2656940520 0.0148598862 0.0302140000 863805421 0 402718720 0.0506796353 0.0820190981 0.1851166040 504 1305031118.9469740391 0.2095410526 0.1116546902 0.2656940520 0.0148526559 0.0313220000 863808621 0 402718720 0.0531234704 0.0878911689 0.1825322807 505 1305031118.9793739319 0.2081218213 0.1118457142 0.2656940520 0.0148429090 0.0348990000 863811821 0 402718720 0.0542990118 0.0957376510 0.1800458282 506 1305031119.0113630295 0.2043541223 0.1120285372 0.2656940520 0.0148368139 0.0395210000 863814965 0 402718720 0.0552841648 0.1008123532 0.1782488972 507 1305031119.0471720695 0.1978057474 0.1121977230 0.2656940520 0.0148249769 0.0360300000 863818165 0 402718720 0.0562004074 0.1049925685 0.1765809804 508 1305031119.0792229176 0.1949248314 0.1123605716 0.2656940520 0.0148121258 0.0496910000 863821309 0 402718720 0.0566770397 0.1100756451 0.1741453856 509 1305031119.1113278866 0.1930685192 0.1125191334 0.2656940520 0.0148056524 0.0397040000 863824509 0 402718720 0.0579023138 0.1151879355 0.1717043668 510 1305031119.1476159096 0.1905641556 0.1126721629 0.2656940520 0.0147925533 0.0390490000 863827709 0 402718720 0.0592468791 0.1212133244 0.1686007380 511 1305031119.1792259216 0.1881785393 0.1128199249 0.2656940520 0.0147971671 0.0398470000 863830853 0 402718720 0.0601510517 0.1246661767 0.1675797850 512 1305031119.2113640308 0.1888521016 0.1129684252 0.2656940520 0.0147894641 0.0396810000 863834053 0 402718720 0.0634430200 0.1300930232 0.1641813517 513 1305031119.2473990917 0.1868268400 0.1131123987 0.2656940520 0.0147764698 0.0401290000 863890501 0 402718720 0.0645335466 0.1353229135 0.1619955152 514 1305031119.2792119980 0.1865357161 0.1132552457 0.2656940520 0.0147637391 0.0395780000 863996045 0 402718720 0.0666552037 0.1398038715 0.1602213234 515 1305031119.3112120628 0.1853342950 0.1133952050 0.2656940520 0.0147513359 0.0450450000 863999245 0 402718720 0.0676226169 0.1440934837 0.1583897471 516 1305031119.3477408886 0.1825588495 0.1135292430 0.2656940520 0.0147371949 0.0401210000 864002445 0 402718720 0.0680572689 0.1481882036 0.1559956819 517 1305031119.3792390823 0.1834390759 0.1136644652 0.2656940520 0.0147254148 0.1706750000 876317861 0 402718720 0.0701918900 0.1535236984 0.1533911079 518 1305031119.4114840031 0.1832623333 0.1137988240 0.2656940520 0.0147193029 0.0470030000 879980157 0 402718720 0.0735438168 0.1558771729 0.1514399201 519 1305031119.4477059841 0.1818991154 0.1139300384 0.2656940520 0.0147058536 0.0371750000 883175661 0 402718720 0.0746182278 0.1601621360 0.1500612646 520 1305031119.4792668819 0.1818030030 0.1140605633 0.2656940520 0.0146970299 0.0360140000 883178749 0 402718720 0.0754519179 0.1653029621 0.1476206183 521 1305031119.5112400055 0.1816359162 0.1141902665 0.2656940520 0.0146843358 0.0643170000 883181837 0 402718720 0.0760614276 0.1701418906 0.1465759426 522 1305031119.5473821163 0.1813721508 0.1143189674 0.2656940520 0.0146717297 0.0352770000 883185149 0 402718720 0.0774099231 0.1751368493 0.1447036266 523 1305031119.5795590878 0.1835921705 0.1144514210 0.2656940520 0.0146645014 0.0331350000 883188293 0 402718720 0.0798787698 0.1813264191 0.1428430974 524 1305031119.6150169373 0.1825939119 0.1145814639 0.2656940520 0.0146620194 0.0336800000 883191549 0 402718720 0.0792973265 0.1849064082 0.1421350539 525 1305031119.6479029655 0.1835318357 0.1147127979 0.2656940520 0.0146607846 0.0354570000 883194749 0 402718720 0.0798904896 0.1908341348 0.1409475952 526 1305031119.6792080402 0.1852728128 0.1148469425 0.2656940520 0.0146488264 0.0305960000 883197837 0 402718720 0.0818631947 0.1955993623 0.1400884092 527 1305031119.7152318954 0.1854201257 0.1149808574 0.2656940520 0.0146384896 0.0356520000 883201037 0 402718720 0.0822181329 0.1992613524 0.1401622593 528 1305031119.7471930981 0.1843159050 0.1151121738 0.2656940520 0.0146259791 0.0352420000 883204293 0 402718720 0.0809189826 0.2028241158 0.1390743405 529 1305031119.7791690826 0.1847450435 0.1152438049 0.2656940520 0.0146146168 0.0343180000 883207437 0 402718720 0.0801734626 0.2070046812 0.1390775740 530 1305031119.8145370483 0.1868521869 0.1153789151 0.2656940520 0.0146114988 0.0396310000 883210525 0 402718720 0.0817060098 0.2117632329 0.1384925097 531 1305031119.8474290371 0.1879073977 0.1155155036 0.2656940520 0.0146018666 0.0386110000 883213781 0 402718720 0.0819272324 0.2158185691 0.1370682716 532 1305031119.8792140484 0.1901352406 0.1156557662 0.2656940520 0.0145957418 0.0383720000 883216869 0 402718720 0.0830584168 0.2179853767 0.1365539879 533 1305031119.9114010334 0.1923113167 0.1157995853 0.2656940520 0.0146010023 0.0376300000 883220013 0 402718720 0.0836974531 0.2250244170 0.1348989308 534 1305031119.9473919868 0.1953150630 0.1159484907 0.2656940520 0.0145958325 0.0518530000 883223325 0 402718720 0.0849166438 0.2280748338 0.1340263188 535 1305031119.9795370102 0.1969668567 0.1160999269 0.2656940520 0.0145837890 0.0368610000 883226469 0 402718720 0.0858496949 0.2303825021 0.1323267668 536 1305031120.0152640343 0.1951321363 0.1162473750 0.2656940520 0.0146013539 0.3959190000 895547157 0 402718720 0.0822992697 0.2382570505 0.1303817630 537 1305031120.0472900867 0.1974825114 0.1163986509 0.2656940520 0.0146325176 0.0417720000 899209565 0 402718720 0.0860331953 0.2386508286 0.1242656261 538 1305031120.0794179440 0.1972620189 0.1165489545 0.2656940520 0.0146243266 0.0377740000 902404957 0 402718720 0.0845740139 0.2387591749 0.1239162832 539 1305031120.1152319908 0.1989584863 0.1167018479 0.2656940520 0.0146208650 0.0398080000 902408101 0 402718720 0.0859223679 0.2411609739 0.1235073879 540 1305031120.1481568813 0.1985077709 0.1168533404 0.2656940520 0.0146311345 0.0466490000 902411301 0 402718720 0.0859062597 0.2381864488 0.1237603053 541 1305031120.1792459488 0.1977880001 0.1170029423 0.2656940520 0.0146214863 0.0408630000 902414389 0 402718720 0.0858935192 0.2349612266 0.1237206310 542 1305031120.2152490616 0.1957061291 0.1171481512 0.2656940520 0.0146091950 0.0384910000 902417645 0 402718720 0.0845338851 0.2313929647 0.1233682856 543 1305031120.2480030060 0.1949691176 0.1172914678 0.2656940520 0.0145982253 0.0392870000 902420845 0 402718720 0.0846529081 0.2307657301 0.1237275153 544 1305031120.2794299126 0.1933750361 0.1174313273 0.2656940520 0.0145878444 0.0383880000 902423989 0 402718720 0.0843178779 0.2270277143 0.1242131442 545 1305031120.3151960373 0.1910198182 0.1175663521 0.2656940520 0.0145756534 0.0365230000 902427189 0 402718720 0.0833467767 0.2227940410 0.1252667010 546 1305031120.3477869034 0.1888220310 0.1176968570 0.2656940520 0.0145650048 0.0402470000 902430389 0 402718720 0.0833012015 0.2198833376 0.1261988729 547 1305031120.3794369698 0.1859004647 0.1178215437 0.2656940520 0.0145538784 0.0378190000 902433533 0 402718720 0.0821718946 0.2137158364 0.1285652071 548 1305031120.4154450893 0.1825403124 0.1179396436 0.2656940520 0.0145472036 0.0407510000 902436733 0 402718720 0.0810735077 0.2066800743 0.1300507039 549 1305031120.4474170208 0.1809045523 0.1180543338 0.2656940520 0.0145446850 0.0445980000 902439933 0 402718720 0.0815068707 0.2051807791 0.1301828325 550 1305031120.4794321060 0.1771785468 0.1181618324 0.2656940520 0.0145328696 0.0401820000 902443133 0 402718720 0.0792935789 0.1980243474 0.1331473142 551 1305031120.5148189068 0.1741681695 0.1182634773 0.2656940520 0.0145213416 0.0397670000 902446277 0 402718720 0.0776349455 0.1931215823 0.1341890544 552 1305031120.5477359295 0.1719638854 0.1183607606 0.2656940520 0.0145130017 0.0445350000 902449477 0 402718720 0.0769195631 0.1879585832 0.1344391257 553 1305031120.5795509815 0.1695221961 0.1184532768 0.2656940520 0.0145030238 0.0459020000 902452621 0 402718720 0.0739883259 0.1839270592 0.1379765421 554 1305031120.6152360439 0.1689309776 0.1185443918 0.2656940520 0.0144941619 0.0374560000 902455765 0 402718720 0.0738849714 0.1779646277 0.1409097165 555 1305031120.6473538876 0.1688025743 0.1186349470 0.2656940520 0.0144828801 0.0332790000 902459021 0 402718720 0.0732322112 0.1739246696 0.1428944468 556 1305031120.6793179512 0.1682486534 0.1187241803 0.2656940520 0.0144884253 0.0350900000 902462109 0 402718720 0.0728628412 0.1699508429 0.1441831440 557 1305031120.7145218849 0.1672033221 0.1188112165 0.2656940520 0.0144758045 0.2653400000 914781925 0 402718720 0.0714520887 0.1656605899 0.1460999548 558 1305031120.7473690510 0.1725988984 0.1189076102 0.2656940520 0.0144662277 0.0405110000 918444333 0 402718720 0.0739425868 0.1631333381 0.1562747061 559 1305031120.7798941135 0.1727814227 0.1190039855 0.2656940520 0.0144548816 0.0310960000 921639725 0 402718720 0.0741760358 0.1574037671 0.1580446213 560 1305031120.8149440289 0.1742306799 0.1191026046 0.2656940520 0.0144561668 0.0311730000 921642981 0 402718720 0.0734441131 0.1551045924 0.1589646637 561 1305031120.8479208946 0.1745609790 0.1192014609 0.2656940520 0.0144489114 0.0301470000 921646125 0 402718720 0.0716369152 0.1496037990 0.1603066474 562 1305031120.8834350109 0.1757583320 0.1193020959 0.2656940520 0.0144371102 0.0646320000 921649325 0 402718720 0.0719851032 0.1441431940 0.1611316353 563 1305031120.9154438972 0.1773218066 0.1194051504 0.2656940520 0.0144350210 0.0288670000 921652469 0 402718720 0.0705161542 0.1415307075 0.1618292034 564 1305031120.9474880695 0.1789870858 0.1195107922 0.2656940520 0.0144239463 0.0334530000 921655613 0 402718720 0.0689557120 0.1362892985 0.1627160013 565 1305031120.9833660126 0.1796289980 0.1196171961 0.2656940520 0.0144152116 0.0275920000 921658869 0 402718720 0.0668283030 0.1317582130 0.1639829278 566 1305031121.0150189400 0.1805255562 0.1197248080 0.2656940520 0.0144047914 0.0260120000 921661957 0 402718720 0.0656965375 0.1268092692 0.1648410857 567 1305031121.0474979877 0.1847975403 0.1198395747 0.2656940520 0.0143930998 0.0428100000 921665157 0 402718720 0.0643425509 0.1239912510 0.1654797494 568 1305031121.0830988884 0.1841402650 0.1199527802 0.2656940520 0.0143842564 0.0331030000 921668413 0 402718720 0.0616711974 0.1171722114 0.1664653122 569 1305031121.1146960258 0.1872352958 0.1200710271 0.2656940520 0.0143728832 0.0307460000 921671501 0 402718720 0.0608879551 0.1139395609 0.1666288972 570 1305031121.1473309994 0.1913018823 0.1201959935 0.2656940520 0.0143626847 0.0369040000 921674701 0 402718720 0.0589484349 0.1098101437 0.1670969427 571 1305031121.1832709312 0.1937057972 0.1203247323 0.2656940520 0.0143504681 0.0378870000 921677957 0 402718720 0.0578560606 0.1052213833 0.1673868895 572 1305031121.2114200592 0.1967336684 0.1204583143 0.2656940520 0.0143397996 0.3608900000 933998521 0 402718720 0.0577912629 0.1001235545 0.1678192168 573 1305031121.2471940517 0.2019855529 0.1206005957 0.2656940520 0.0143285332 0.0822820000 937660985 0 402718720 0.0561289527 0.0974785835 0.1727615595 574 1305031121.2828760147 0.2031033337 0.1207443287 0.2656940520 0.0143163330 0.0353810000 940856489 0 402718720 0.0543240942 0.0916347057 0.1739677787 575 1305031121.3135681152 0.2051873505 0.1208911861 0.2656940520 0.0143045004 0.0300980000 940859521 0 402718720 0.0533015169 0.0860763639 0.1745397002 576 1305031121.3475170135 0.2110625952 0.1210477337 0.2656940520 0.0142934249 0.0300710000 940862721 0 402718720 0.0506644621 0.0833776519 0.1753679514 577 1305031121.3832259178 0.2131039798 0.1212072766 0.2656940520 0.0142862130 0.0286240000 940865977 0 402718720 0.0506069995 0.0764785782 0.1758539528 578 1305031121.4143180847 0.2175344825 0.1213739327 0.2656940520 0.0142761785 0.0277320000 940869065 0 402718720 0.0492733270 0.0731504783 0.1759703308 579 1305031121.4473190308 0.2241310477 0.1215514061 0.2656940520 0.0142669488 0.0255600000 940872321 0 402718720 0.0481379181 0.0698143840 0.1758017093 580 1305031121.4829640388 0.2254709601 0.1217305777 0.2656940520 0.0142588434 0.4120540000 953189941 0 402718720 0.0473539345 0.0629216507 0.1780221462 581 1305031121.5141069889 0.2319412082 0.1219202690 0.2656940520 0.0142577289 0.0425040000 956852237 0 402718720 0.0457818434 0.0617676005 0.1765804291 582 1305031121.5472700596 0.2390532643 0.1221215285 0.2656940520 0.0142470964 0.0314910000 960047741 0 402718720 0.0449248329 0.0589350387 0.1778792143 583 1305031121.5832040310 0.2408190370 0.1223251262 0.2656940520 0.0142353159 0.0301300000 960050941 0 402718720 0.0432688259 0.0528220907 0.1784033030 584 1305031121.6147000790 0.2443713844 0.1225341096 0.2656940520 0.0142251975 0.0263380000 960054029 0 402718720 0.0417444967 0.0490967035 0.1787193567 585 1305031121.6471829414 0.2521378994 0.1227556545 0.2656940520 0.0142202158 0.0255080000 960057229 0 402718720 0.0421050005 0.0467349887 0.1782598048 586 1305031121.6831998825 0.2540961802 0.1229797851 0.2656940520 0.0142178967 0.0257750000 960060485 0 402718720 0.0382076390 0.0431908853 0.1785593927 587 1305031121.7145199776 0.2559927702 0.1232063830 0.2656940520 0.0142082652 0.0277540000 960063573 0 402718720 0.0353069231 0.0392950177 0.1785574704 588 1305031121.7471449375 0.2614142597 0.1234414304 0.2656940520 0.0141965475 0.0253230000 960066773 0 402718720 0.0348211601 0.0371745527 0.1792002916 589 1305031121.7828350067 0.2619043291 0.1236765118 0.2656940520 0.0141845713 0.0251340000 960069973 0 402718720 0.0336503945 0.0327893160 0.1800443977 590 1305031121.8115398884 0.2644564509 0.1239151218 0.2656940520 0.0141758124 0.0316760000 960073005 0 402718720 0.0341107436 0.0309358593 0.1810989976 591 1305031121.8473351002 0.2659782171 0.1241554993 0.2659782171 0.0141666160 0.0300160000 960076317 0 402718720 0.0327377245 0.0293485597 0.1807320565 592 1305031121.8820600510 0.2654754221 0.1243942154 0.2659782171 0.0141555050 0.0319730000 960079461 0 402718720 0.0308313183 0.0277901217 0.1811452061 593 1305031121.9149310589 0.2645648122 0.1246305908 0.2659782171 0.0141441052 0.0367600000 960082661 0 402718720 0.0300280284 0.0273178387 0.1827407926 594 1305031121.9472880363 0.2636771798 0.1248646759 0.2659782171 0.0141346092 0.0409760000 960085805 0 402718720 0.0321864672 0.0267415065 0.1824373603 595 1305031121.9829258919 0.2638004422 0.1250981814 0.2659782171 0.0141229333 0.0349430000 960089061 0 402718720 0.0336897783 0.0289705079 0.1820023805 596 1305031122.0142560005 0.2600067854 0.1253245381 0.2659782171 0.0141121276 0.0350510000 960092205 0 402718720 0.0327128433 0.0298738182 0.1829148829 597 1305031122.0473060608 0.2558145821 0.1255431144 0.2659782171 0.0141011373 0.0352810000 960095405 0 402718720 0.0337261036 0.0325199738 0.1821935624 598 1305031122.0829589367 0.2529575825 0.1257561821 0.2659782171 0.0140896406 0.0326100000 960098605 0 402718720 0.0359175354 0.0358836949 0.1815815717 599 1305031122.1146719456 0.2514429986 0.1259660098 0.2659782171 0.0140794976 0.0316170000 960101693 0 402718720 0.0375197195 0.0414120182 0.1798269600 600 1305031122.1507248878 0.2441158146 0.1261629262 0.2659782171 0.0140701676 0.0643570000 960104949 0 402718720 0.0395646393 0.0458006188 0.1800947487 601 1305031122.1830420494 0.2410240471 0.1263540429 0.2659782171 0.0140654730 0.0304900000 960108149 0 402718720 0.0425658710 0.0508677028 0.1790867746 602 1305031122.2149589062 0.2410937697 0.1265446404 0.2659782171 0.0140676003 0.0335500000 960111237 0 402718720 0.0446170643 0.0613185875 0.1774573475 603 1305031122.2513189316 0.2287816107 0.1267141876 0.2659782171 0.0140620231 0.0299310000 960114549 0 402718720 0.0444558375 0.0628306419 0.1772134602 604 1305031122.2835600376 0.2268333584 0.1268799478 0.2659782171 0.0140531243 0.0462410000 960117749 0 402718720 0.0462329350 0.0718617067 0.1794905812 605 1305031122.3142890930 0.2253662348 0.1270427351 0.2659782171 0.0140462750 0.0322900000 960120781 0 402718720 0.0480329134 0.0813105255 0.1805773824 606 1305031122.3513269424 0.2161422968 0.1271897641 0.2659782171 0.0140425636 0.0317970000 960124037 0 402718720 0.0496121868 0.0836777464 0.1795553714 607 1305031122.3826301098 0.2134334892 0.1273318460 0.2659782171 0.0140347254 0.0303110000 960127181 0 402718720 0.0503057428 0.0901014507 0.1786552668 608 1305031122.4149971008 0.2085923105 0.1274654981 0.2659782171 0.0140372260 0.0377160000 960130269 0 402718720 0.0506739803 0.0934050754 0.1768661141 609 1305031122.4512569904 0.2050927728 0.1275929649 0.2659782171 0.0140261428 0.0329920000 960133581 0 402718720 0.0530642159 0.0993397683 0.1749953032 610 1305031122.4833600521 0.2028190643 0.1277162863 0.2659782171 0.0140260104 0.0295230000 960136725 0 402718720 0.0543025434 0.1037402600 0.1730981767 611 1305031122.5150969028 0.2021044940 0.1278380346 0.2659782171 0.0140224330 0.0282030000 960139869 0 402718720 0.0570102558 0.1085842624 0.1705064774 612 1305031122.5514900684 0.1999923438 0.1279559338 0.2659782171 0.0140149202 0.0627310000 960143125 0 402718720 0.0601440854 0.1136919037 0.1685691923 613 1305031122.5832080841 0.1982285678 0.1280705711 0.2659782171 0.0140054617 0.0328520000 960146269 0 402718720 0.0613597073 0.1181597561 0.1664876491 614 1305031122.6149799824 0.1948590726 0.1281793471 0.2659782171 0.0139983654 0.0356790000 960149357 0 402718720 0.0603022613 0.1222502515 0.1646765918 615 1305031122.6487879753 0.1929267347 0.1282846274 0.2659782171 0.0139876504 0.0343320000 960152613 0 402718720 0.0622027591 0.1277133673 0.1623013616 616 1305031122.6834020615 0.1913068742 0.1283869363 0.2659782171 0.0139783912 0.3249020000 972475925 0 402718720 0.0631895736 0.1324477643 0.1582013667 617 1305031122.7152080536 0.1918299347 0.1284897612 0.2659782171 0.0139737165 0.0438810000 976138221 0 402718720 0.0613863803 0.1424235404 0.1580631435 618 1305031122.7512979507 0.1915218830 0.1285917550 0.2659782171 0.0139669393 0.0365420000 979333725 0 402718720 0.0643977970 0.1486791521 0.1562074125 619 1305031122.7834229469 0.1924108863 0.1286948553 0.2659782171 0.0139561901 0.0348460000 979336869 0 402718720 0.0659941137 0.1549677104 0.1557546407 620 1305031122.8125550747 0.1920919269 0.1287971087 0.2659782171 0.0139491857 0.0329890000 979339957 0 402718720 0.0675456822 0.1585803777 0.1556074172 621 1305031122.8514180183 0.1919802427 0.1288988529 0.2659782171 0.0139494562 0.0357950000 979343269 0 402718720 0.0707044899 0.1625276655 0.1550107300 622 1305031122.8837540150 0.1912976205 0.1289991724 0.2659782171 0.0139431550 0.0348390000 979346469 0 402718720 0.0708035976 0.1675764024 0.1537622511 623 1305031122.9145710468 0.1886470765 0.1290949154 0.2659782171 0.0139361363 0.0660740000 979349501 0 402718720 0.0691766590 0.1706424206 0.1532173753 624 1305031122.9513409138 0.1880686879 0.1291894247 0.2659782171 0.0139266709 0.0325480000 979352813 0 402718720 0.0703754053 0.1739191711 0.1521729976 625 1305031122.9828150272 0.1885116994 0.1292843403 0.2659782171 0.0139159923 0.0284460000 979355957 0 402718720 0.0712201372 0.1783623099 0.1505979151 626 1305031123.0154500008 0.1879137307 0.1293779975 0.2659782171 0.0139070899 0.0365860000 979359045 0 402718720 0.0713691190 0.1805501729 0.1496059150 627 1305031123.0518269539 0.1881906241 0.1294717976 0.2659782171 0.0138992872 0.0362700000 979362357 0 402718720 0.0727331936 0.1833982766 0.1483552754 628 1305031123.0829749107 0.1897803396 0.1295678303 0.2659782171 0.0138915557 0.0357300000 979365501 0 402718720 0.0740208030 0.1894639283 0.1467868984 629 1305031123.1138730049 0.1895862222 0.1296632490 0.2659782171 0.0138811116 0.0406850000 979368533 0 402718720 0.0735645965 0.1943333298 0.1456712335 630 1305031123.1508219242 0.1895566583 0.1297583179 0.2659782171 0.0138704744 0.0404190000 979371845 0 402718720 0.0736869127 0.1979413033 0.1460859925 631 1305031123.1821548939 0.1908274293 0.1298550994 0.2659782171 0.0138683174 0.0397190000 979374989 0 402718720 0.0751414672 0.2031808496 0.1459368467 632 1305031123.2147040367 0.1900399029 0.1299503285 0.2659782171 0.0138590287 0.0379670000 979378133 0 402718720 0.0746457204 0.2076774985 0.1454425603 633 1305031123.2506179810 0.1884894222 0.1300428073 0.2659782171 0.0138655372 0.0387130000 979381389 0 402718720 0.0742608532 0.2142231166 0.1440659910 634 1305031123.2823469639 0.1906701773 0.1301384341 0.2659782171 0.0138695543 0.0787180000 979384533 0 402718720 0.0769525021 0.2187495828 0.1448210478 635 1305031123.3113269806 0.1914723814 0.1302350230 0.2659782171 0.0138612391 0.4189900000 991713081 0 402718720 0.0781647265 0.2225925177 0.1455474943 636 1305031123.3504810333 0.1913253516 0.1303310770 0.2659782171 0.0138606287 0.0392960000 995375657 0 402718720 0.0804492980 0.2257556915 0.1424268186 637 1305031123.3822550774 0.1933208555 0.1304299620 0.2659782171 0.0138527659 0.0297930000 998570993 0 402718720 0.0823997557 0.2305483669 0.1424546540 638 1305031123.4113628864 0.1928566396 0.1305278095 0.2659782171 0.0138472132 0.0285620000 998574025 0 402718720 0.0817076191 0.2335117459 0.1423008293 639 1305031123.4512550831 0.1943004876 0.1306276102 0.2659782171 0.0138503550 0.0293850000 998577337 0 402718720 0.0828732401 0.2394656092 0.1414212883 640 1305031123.4835939407 0.1959424615 0.1307296647 0.2659782171 0.0138475460 0.0281640000 998580537 0 402718720 0.0844512284 0.2442475855 0.1408562660 641 1305031123.5113599300 0.1967085004 0.1308325958 0.2659782171 0.0138381515 0.0287880000 998583569 0 402718720 0.0842981637 0.2482528389 0.1414115727 642 1305031123.5515129566 0.1974370480 0.1309363410 0.2659782171 0.0138282160 0.0272010000 998586937 0 402718720 0.0854494125 0.2525919080 0.1401919127 643 1305031123.5795829296 0.1983906776 0.1310412467 0.2659782171 0.0138213636 0.0270400000 998589913 0 402718720 0.0857598856 0.2563570738 0.1406535208 644 1305031123.6113350391 0.2006907165 0.1311493980 0.2659782171 0.0138115747 0.0267840000 998593001 0 402718720 0.0891177505 0.2621015012 0.1388619244 645 1305031123.6524109840 0.2016741931 0.1312587388 0.2659782171 0.0138097236 0.3662360000 1010917653 0 402718720 0.0894174725 0.2672713995 0.1394398212 646 1305031123.6837530136 0.2064677626 0.1313751614 0.2659782171 0.0138008964 0.0368320000 1014580005 0 402718720 0.0939298123 0.2720487416 0.1406159103 647 1305031123.7113230228 0.2073856294 0.1314926428 0.2659782171 0.0137915347 0.0606810000 1017775173 0 402718720 0.0950394198 0.2762631774 0.1399349868 648 1305031123.7517230511 0.2076532692 0.1316101747 0.2659782171 0.0137830955 0.0278210000 1017778597 0 402718720 0.0938686281 0.2768208086 0.1401995569 649 1305031123.7838580608 0.2085366994 0.1317287055 0.2659782171 0.0137783226 0.0269620000 1017781685 0 402718720 0.0944211558 0.2776496112 0.1400269121 650 1305031123.8116080761 0.2087798566 0.1318472458 0.2659782171 0.0137690500 0.0265160000 1017784773 0 402718720 0.0946299508 0.2790779471 0.1395593435 651 1305031123.8514440060 0.2078209370 0.1319639488 0.2659782171 0.0137602106 0.0276800000 1017788085 0 402718720 0.0938773677 0.2785298526 0.1385221928 652 1305031123.8837859631 0.2081844211 0.1320808514 0.2659782171 0.0137617665 0.0255810000 1017791285 0 402718720 0.0930378810 0.2741810083 0.1397042572 653 1305031123.9112429619 0.2067859620 0.1321952543 0.2659782171 0.0137515799 0.0279480000 1017794261 0 402718720 0.0931294039 0.2725889981 0.1378966421 654 1305031123.9514420033 0.2055476159 0.1323074139 0.2659782171 0.0137520198 0.0254170000 1017797629 0 402718720 0.0930321068 0.2738450170 0.1380954236 655 1305031123.9834148884 0.2024741322 0.1324145386 0.2659782171 0.0137823066 0.0288360000 1017800829 0 402718720 0.0886506066 0.2654470503 0.1402306557 656 1305031124.0113019943 0.2000702322 0.1325176723 0.2659782171 0.0137825636 0.0277780000 1017803805 0 402718720 0.0875991881 0.2588147223 0.1397883296 657 1305031124.0515050888 0.1981007606 0.1326174944 0.2659782171 0.0137913067 0.0230000000 1017807173 0 402718720 0.0882534161 0.2602668405 0.1404255033 658 1305031124.0838370323 0.1956427544 0.1327132775 0.2659782171 0.0137927202 0.0284860000 1017810317 0 402718720 0.0859331861 0.2543383539 0.1431546360 659 1305031124.1113309860 0.1941443384 0.1328064961 0.2659782171 0.0137855309 0.0272360000 1017813349 0 402718720 0.0864457637 0.2467280924 0.1438031495 660 1305031124.1474459171 0.1920030117 0.1328961877 0.2659782171 0.0137803419 0.0622320000 1017816661 0 402718720 0.0876806602 0.2448244095 0.1439824104 661 1305031124.1826939583 0.1894749552 0.1329817835 0.2659782171 0.0137734619 0.0296840000 1017819861 0 402718720 0.0859867260 0.2402101606 0.1471887082 662 1305031124.2113959789 0.1879981309 0.1330648897 0.2659782171 0.0137631868 0.0360440000 1017822893 0 402718720 0.0862618387 0.2343004197 0.1487271339 663 1305031124.2493269444 0.1849333644 0.1331431227 0.2659782171 0.0137709944 0.0326970000 1017826149 0 402718720 0.0857823789 0.2338011116 0.1494055837 664 1305031124.2825450897 0.1820898503 0.1332168377 0.2659782171 0.0137630121 0.0338230000 1017829349 0 402718720 0.0837487206 0.2295519710 0.1515763551 665 1305031124.3113610744 0.1806970686 0.1332882365 0.2659782171 0.0137586329 0.0322800000 1017832381 0 402718720 0.0838222802 0.2201990932 0.1531735659 666 1305031124.3503539562 0.1786430031 0.1333563368 0.2659782171 0.0137487863 0.0334590000 1017835693 0 402718720 0.0835542604 0.2161886394 0.1536519974 667 1305031124.3824200630 0.1759195477 0.1334201497 0.2659782171 0.0137404427 0.0342330000 1017838893 0 402718720 0.0821749419 0.2093935013 0.1543537229 668 1305031124.4114389420 0.1728574783 0.1334791876 0.2659782171 0.0137311067 0.0344310000 1017841925 0 402718720 0.0808094963 0.2014167160 0.1544865221 669 1305031124.4502449036 0.1722031534 0.1335370709 0.2659782171 0.0137241794 0.0373860000 1017845237 0 402718720 0.0813588798 0.1941693425 0.1549227834 670 1305031124.4800989628 0.1686330140 0.1335894530 0.2659782171 0.0137156440 0.0349420000 1017848381 0 402718720 0.0790739432 0.1862166673 0.1544805318 671 1305031124.5113239288 0.1673469394 0.1336397622 0.2659782171 0.0137077000 0.0350610000 1017851469 0 402718720 0.0781697109 0.1815895438 0.1543210894 672 1305031124.5504369736 0.1665685624 0.1336887634 0.2659782171 0.0136986815 0.0694550000 1017854837 0 402718720 0.0772817433 0.1762614995 0.1550687104 673 1305031124.5794041157 0.1649582684 0.1337352262 0.2659782171 0.0136893810 0.3298970000 1030181345 0 402718720 0.0755151436 0.1700778604 0.1567605585 674 1305031124.6113579273 0.1646426320 0.1337810829 0.2659782171 0.0136831952 0.0376070000 1033843129 0 402718720 0.0727298930 0.1687647849 0.1606191397 675 1305031124.6512711048 0.1647606939 0.1338269786 0.2659782171 0.0136741701 0.0304420000 1037038689 0 402718720 0.0716867894 0.1631627083 0.1618802100 676 1305031124.6793620586 0.1632065922 0.1338704396 0.2659782171 0.0136654582 0.0261110000 1037041777 0 402718720 0.0709285066 0.1546768844 0.1633859724 677 1305031124.7112510204 0.1630661190 0.1339135647 0.2659782171 0.0136558683 0.0286590000 1037044865 0 402718720 0.0702942163 0.1490340680 0.1640885621 678 1305031124.7498900890 0.1621545553 0.1339552181 0.2659782171 0.0136467258 0.0300830000 1037048233 0 402718720 0.0678797960 0.1415407062 0.1660339832 679 1305031124.7793650627 0.1613033712 0.1339954952 0.2659782171 0.0136376274 0.0313780000 1037051321 0 402718720 0.0659283996 0.1348708272 0.1681634635 680 1305031124.8113598824 0.1619080007 0.1340365430 0.2659782171 0.0136295676 0.0317200000 1037054409 0 402718720 0.0649857521 0.1291058660 0.1701838970 681 1305031124.8505349159 0.1620259136 0.1340776434 0.2659782171 0.0136253841 0.0310660000 1037057721 0 402718720 0.0626321062 0.1210231483 0.1721787155 682 1305031124.8793549538 0.1628761441 0.1341198699 0.2659782171 0.0136192732 0.0296180000 1037060809 0 402718720 0.0630469173 0.1130300462 0.1750720590 683 1305031124.9114480019 0.1647128016 0.1341646619 0.2659782171 0.0136177147 0.0350930000 1037063953 0 402718720 0.0618773140 0.1091156751 0.1765096933 684 1305031124.9507300854 0.1657004952 0.1342107669 0.2659782171 0.0136143800 0.0703170000 1037067265 0 402718720 0.0606259890 0.1014191657 0.1805721968 685 1305031124.9794380665 0.1623549610 0.1342518533 0.2659782171 0.0136132381 0.3539780000 1049380137 0 402718720 0.0575949885 0.0906480849 0.1831403226 686 1305031125.0114541054 0.1630892754 0.1342938904 0.2659782171 0.0136049387 0.0438750000 1053042489 0 402718720 0.0558188260 0.0845937505 0.1840576082 687 1305031125.0507628918 0.1698763818 0.1343456844 0.2659782171 0.0136040751 0.0340320000 1056237993 0 402718720 0.0580237210 0.0805469602 0.1861413419 688 1305031125.0793640614 0.1698780656 0.1343973303 0.2659782171 0.0135958028 0.0300810000 1056241081 0 402718720 0.0555916280 0.0742235705 0.1882674694 689 1305031125.1113638878 0.1693685949 0.1344480869 0.2659782171 0.0135897311 0.0293880000 1056244225 0 402718720 0.0525551736 0.0665678605 0.1900052875 690 1305031125.1510128975 0.1760172844 0.1345083321 0.2659782171 0.0135829296 0.0296550000 1056247537 0 402718720 0.0532758757 0.0617628805 0.1909654140 691 1305031125.1793529987 0.1803417206 0.1345746611 0.2659782171 0.0135807890 0.0302190000 1056250569 0 402718720 0.0514429137 0.0602481812 0.1914832592 692 1305031125.2113199234 0.1792895496 0.1346392780 0.2659782171 0.0135719500 0.0300480000 1056253769 0 402718720 0.0481356047 0.0525946245 0.1939267367 693 1305031125.2506320477 0.1821418554 0.1347078243 0.2659782171 0.0135666489 0.0282810000 1056257081 0 402718720 0.0453609601 0.0461402535 0.1958847791 694 1305031125.2794671059 0.1863579601 0.1347822481 0.2659782171 0.0135610750 0.4451990000 1068574533 0 402718720 0.0443404391 0.0433477461 0.1951866597 695 1305031125.3114929199 0.1878136098 0.1348585523 0.2659782171 0.0135701120 0.0448510000 1072236885 0 402718720 0.0496102199 0.0325119011 0.1977022886 696 1305031125.3488800526 0.1935138404 0.1349428271 0.2659782171 0.0135613359 0.0640220000 1075432333 0 402718720 0.0475267395 0.0297732390 0.1978176236 697 1305031125.3794009686 0.1973254681 0.1350323287 0.2659782171 0.0135533699 0.0329730000 1075435477 0 402718720 0.0487657040 0.0262809247 0.1989882588 698 1305031125.4113349915 0.1998518854 0.1351251934 0.2659782171 0.0135451012 0.0287770000 1075438565 0 402718720 0.0479657017 0.0229921471 0.1998247057 699 1305031125.4511950016 0.2011350691 0.1352196282 0.2659782171 0.0135485275 0.0306380000 1075441989 0 402718720 0.0448764265 0.0196416005 0.2016544640 700 1305031125.4794239998 0.2002240121 0.1353124916 0.2659782171 0.0135405349 0.0316400000 1075445021 0 402718720 0.0431101173 0.0147158010 0.2029281259 701 1305031125.5113160610 0.2028698623 0.1354088644 0.2659782171 0.0135410436 0.0399780000 1075448165 0 402718720 0.0423658267 0.0145214265 0.2022253871 702 1305031125.5510199070 0.2042917013 0.1355069881 0.2659782171 0.0135334971 0.0390450000 1075451533 0 402718720 0.0424669348 0.0125029692 0.2023054361 703 1305031125.5793080330 0.2036905736 0.1356039776 0.2659782171 0.0135251840 0.0266990000 1075454621 0 402718720 0.0423281528 0.0111099351 0.2030399144 704 1305031125.6115329266 0.2003503591 0.1356959469 0.2659782171 0.0135185941 0.0315190000 1075457709 0 402718720 0.0402227566 0.0083967196 0.2033386081 705 1305031125.6505749226 0.1972629428 0.1357832759 0.2659782171 0.0135100708 0.0299420000 1075461133 0 402718720 0.0369443446 0.0084029222 0.2017199844 706 1305031125.6793279648 0.1997809112 0.1358739242 0.2659782171 0.0135020340 0.0329860000 1075464165 0 402718720 0.0362084173 0.0132445395 0.1971801966 707 1305031125.7114429474 0.1971734315 0.1359606278 0.2659782171 0.0135280709 0.0740660000 1075467253 0 402718720 0.0382624567 0.0128097218 0.1974271834 708 1305031125.7512600422 0.2000018060 0.1360510815 0.2659782171 0.0135254217 0.0346340000 1075470621 0 402718720 0.0425473526 0.0193483233 0.1933258474 709 1305031125.7793478966 0.1990471482 0.1361399335 0.2659782171 0.0135162258 0.0295070000 1075473709 0 402718720 0.0446073115 0.0232458152 0.1921121478 710 1305031125.8115730286 0.1996342689 0.1362293621 0.2659782171 0.0135084021 0.0304350000 1075476853 0 402718720 0.0476003252 0.0289058592 0.1900410652 711 1305031125.8474121094 0.1944434047 0.1363112384 0.2659782171 0.0135030989 0.0364290000 1075480109 0 402718720 0.0481605493 0.0331849344 0.1894463152 712 1305031125.8793179989 0.1918990910 0.1363893112 0.2659782171 0.0134939164 0.0332700000 1075483253 0 402718720 0.0476491973 0.0385129601 0.1867742985 713 1305031125.9113049507 0.1899613142 0.1364644473 0.2659782171 0.0134945798 0.0302160000 1075486341 0 402718720 0.0466173887 0.0458606705 0.1834667176 714 1305031125.9473431110 0.1810843647 0.1365269402 0.2659782171 0.0134916422 0.0261440000 1075489653 0 402718720 0.0459235236 0.0481576398 0.1818859428 715 1305031125.9793241024 0.1807459891 0.1365887850 0.2659782171 0.0134868765 0.0276870000 1075492797 0 402718720 0.0491630435 0.0553469546 0.1809499264 716 1305031126.0113329887 0.1811779439 0.1366510604 0.2659782171 0.0134894095 0.0452130000 1075495885 0 402718720 0.0549064875 0.0631913766 0.1847604215 717 1305031126.0473239422 0.1790655553 0.1367102159 0.2659782171 0.0134913068 0.0421380000 1075499197 0 402718720 0.0611748435 0.0702617764 0.1855693907 718 1305031126.0793559551 0.1765886098 0.1367657568 0.2659782171 0.0134822391 0.0356540000 1075502285 0 402718720 0.0631468818 0.0770724267 0.1855481416 719 1305031126.1113700867 0.1726256013 0.1368156314 0.2659782171 0.0134824471 0.0574530000 1075505429 0 402718720 0.0646029934 0.0816165656 0.1857095957 720 1305031126.1474320889 0.1691434234 0.1368605311 0.2659782171 0.0134925213 0.0380340000 1075508741 0 402718720 0.0663277879 0.0906423852 0.1858161688 721 1305031126.1793839931 0.1670011431 0.1369023350 0.2659782171 0.0134868547 0.0395400000 1075511885 0 402718720 0.0669552609 0.0985680297 0.1858164817 722 1305031126.2113189697 0.1641486436 0.1369400723 0.2659782171 0.0134812507 0.0377390000 1075514973 0 402718720 0.0694456771 0.1025061682 0.1853008121 723 1305031126.2472980022 0.1613741815 0.1369738677 0.2659782171 0.0134803220 0.0412230000 1075518285 0 402718720 0.0707894489 0.1107968017 0.1841619015 724 1305031126.2793629169 0.1601420492 0.1370058680 0.2659782171 0.0134717200 0.0419580000 1075521429 0 402718720 0.0716371909 0.1176685467 0.1841631830 725 1305031126.3113319874 0.1602741778 0.1370379622 0.2659782171 0.0134651842 0.4015660000 1087839677 0 402718720 0.0729057342 0.1255716830 0.1837433875 726 1305031126.3473629951 0.1576754749 0.1370663885 0.2659782171 0.0134571616 0.0400750000 1091502197 0 402718720 0.0732479692 0.1304878891 0.1841232777 727 1305031126.3794229031 0.1571549177 0.1370940206 0.2659782171 0.0134500690 0.0312050000 1094697533 0 402718720 0.0730616450 0.1370346695 0.1831591427 728 1305031126.4114649296 0.1576076895 0.1371221987 0.2659782171 0.0134414406 0.0305940000 1094700621 0 402718720 0.0737901106 0.1436888576 0.1823472381 729 1305031126.4473609924 0.1561515927 0.1371483022 0.2659782171 0.0134398476 0.0266760000 1094703877 0 402718720 0.0744906813 0.1470332742 0.1810749322 730 1305031126.4795329571 0.1562067717 0.1371744097 0.2659782171 0.0134310282 0.0671600000 1094707077 0 402718720 0.0747783706 0.1526434124 0.1792800426 731 1305031126.5114099979 0.1576997489 0.1372024881 0.2659782171 0.0134226825 0.0304050000 1094710165 0 402718720 0.0759438574 0.1605530083 0.1778255701 732 1305031126.5473740101 0.1591389030 0.1372324559 0.2659782171 0.0134158344 0.0286810000 1094713421 0 402718720 0.0783857331 0.1652651280 0.1778843999 733 1305031126.5794539452 0.1602340192 0.1372638359 0.2659782171 0.0134082249 0.0297180000 1094716621 0 402718720 0.0798344985 0.1701850891 0.1770188510 734 1305031126.6115279198 0.1607940942 0.1372958935 0.2659782171 0.0133993030 0.0294060000 1094719709 0 402718720 0.0808980390 0.1746354401 0.1761354655 735 1305031126.6473760605 0.1604132801 0.1373273457 0.2659782171 0.0133913560 0.0345260000 1094722965 0 402718720 0.0815702155 0.1775883883 0.1759209335 736 1305031126.6794788837 0.1611992419 0.1373597803 0.2659782171 0.0133831229 0.0345950000 1094726109 0 402718720 0.0832329616 0.1804745197 0.1744607836 737 1305031126.7115828991 0.1615390331 0.1373925880 0.2659782171 0.0133753109 0.0338700000 1094729253 0 402718720 0.0837851018 0.1856599748 0.1733737737 738 1305031126.7473158836 0.1621941626 0.1374261945 0.2659782171 0.0133707590 0.0387010000 1094732509 0 402718720 0.0855488479 0.1851733476 0.1717909724 739 1305031126.7793788910 0.1633969396 0.1374613376 0.2659782171 0.0133643483 0.0379840000 1094735653 0 402718720 0.0870070532 0.1896690130 0.1705159247 740 1305031126.8116021156 0.1652128845 0.1374988397 0.2659782171 0.0133567245 0.0381160000 1094738797 0 402718720 0.0894862488 0.1918353140 0.1695732623 741 1305031126.8473429680 0.1654601842 0.1375365743 0.2659782171 0.0133484540 0.0382890000 1094742053 0 402718720 0.0906671882 0.1940726936 0.1675840765 742 1305031126.8793570995 0.1651608050 0.1375738037 0.2659782171 0.0133405175 0.0694960000 1094745197 0 402718720 0.0907125622 0.1961753815 0.1667920500 743 1305031126.9113640785 0.1657456160 0.1376117200 0.2659782171 0.0133315939 0.0374090000 1094748341 0 402718720 0.0918424428 0.1969236583 0.1660618484 744 1305031126.9474370480 0.1642701328 0.1376475512 0.2659782171 0.0133261462 0.4673070000 1107068933 0 402718720 0.0910954550 0.1982673109 0.1647775620 745 1305031126.9793369770 0.1665720344 0.1376863760 0.2659782171 0.0133188682 0.0194780000 1110731285 0 402718720 0.0936437398 0.2009123713 0.1638302654 746 1305031127.0113708973 0.1668253988 0.1377254364 0.2659782171 0.0133108530 0.0205630000 1113926565 0 402718720 0.0940318331 0.2007962465 0.1637248248 747 1305031127.0472970009 0.1670058668 0.1377646337 0.2659782171 0.0133052819 0.0323180000 1113929877 0 402718720 0.0945075303 0.2015406787 0.1632243693 748 1305031127.0792989731 0.1666105539 0.1378031978 0.2659782171 0.0132999772 0.0228680000 1113933021 0 402718720 0.0941764563 0.2007860392 0.1631695181 749 1305031127.1114349365 0.1644918919 0.1378388302 0.2659782171 0.0132990989 0.0460590000 1113936053 0 402718720 0.0922123268 0.1991054118 0.1629527360 750 1305031127.1473069191 0.1640618593 0.1378737943 0.2659782171 0.0132908014 0.0371340000 1113939365 0 402718720 0.0915111080 0.1970987767 0.1631295830 751 1305031127.1793489456 0.1644112915 0.1379091305 0.2659782171 0.0132832866 0.0327630000 1113942509 0 402718720 0.0918390304 0.1970832348 0.1633611023 752 1305031127.2116999626 0.1652734280 0.1379455192 0.2659782171 0.0132771286 0.0327390000 1113945653 0 402718720 0.0926944390 0.1958597451 0.1643759012 753 1305031127.2473740578 0.1645983905 0.1379809147 0.2659782171 0.0132727859 0.0317840000 1113948909 0 402718720 0.0922699124 0.1925749630 0.1649634391 754 1305031127.2794649601 0.1641985774 0.1380156862 0.2659782171 0.0132760719 0.0645800000 1113951997 0 402718720 0.0917186663 0.1929145157 0.1653355509 755 1305031127.3113620281 0.1630444527 0.1380488369 0.2659782171 0.0132679814 0.0308930000 1113955141 0 402718720 0.0904588774 0.1911061704 0.1663950682 756 1305031127.3473560810 0.1617420912 0.1380801772 0.2659782171 0.0132731783 0.0330890000 1113958453 0 402718720 0.0895816982 0.1866274327 0.1673985869 757 1305031127.3792619705 0.1618618518 0.1381115928 0.2659782171 0.0132695673 0.0305970000 1113961597 0 402718720 0.0895704105 0.1876122802 0.1678474396 758 1305031127.4113709927 0.1616652757 0.1381426663 0.2659782171 0.0132611376 0.0323260000 1113964685 0 402718720 0.0890341923 0.1865828931 0.1689572781 759 1305031127.4473330975 0.1605817378 0.1381722303 0.2659782171 0.0132626997 0.0325510000 1113967941 0 402718720 0.0879999250 0.1827731878 0.1702352762 760 1305031127.4793620110 0.1610349715 0.1382023128 0.2659782171 0.0132671584 0.0324280000 1113971085 0 402718720 0.0879456028 0.1842905581 0.1702528000 761 1305031127.5113561153 0.1607379019 0.1382319260 0.2659782171 0.0132598502 0.0370960000 1113974229 0 402718720 0.0872007161 0.1833864003 0.1715153307 762 1305031127.5473480225 0.1599200368 0.1382603881 0.2659782171 0.0132570963 0.0314160000 1113977541 0 402718720 0.0865253136 0.1801001281 0.1728893518 763 1305031127.5793449879 0.1601731181 0.1382891072 0.2659782171 0.0132519993 0.0317820000 1113980685 0 402718720 0.0866086558 0.1806701422 0.1730604172 764 1305031127.6112709045 0.1601535678 0.1383177256 0.2659782171 0.0132435089 0.0355840000 1113983773 0 402718720 0.0865760222 0.1811284274 0.1735025197 765 1305031127.6473579407 0.1591443717 0.1383449500 0.2659782171 0.0132370565 0.0315630000 1113987085 0 402718720 0.0860278606 0.1785257608 0.1747706532 766 1305031127.6792979240 0.1589156240 0.1383718047 0.2659782171 0.0132292941 0.0658640000 1113990173 0 402718720 0.0858780071 0.1779157519 0.1748929769 767 1305031127.7113749981 0.1595160365 0.1383993721 0.2659782171 0.0132218839 0.0372370000 1113993317 0 402718720 0.0859363750 0.1793824434 0.1746998876 768 1305031127.7473039627 0.1594849080 0.1384268272 0.2659782171 0.0132149637 0.0338430000 1113996629 0 402718720 0.0857569799 0.1775755882 0.1755809188 769 1305031127.7793459892 0.1591184884 0.1384537345 0.2659782171 0.0132094769 0.0309300000 1113999717 0 402718720 0.0851802453 0.1757202148 0.1757479012 770 1305031127.8118290901 0.1595399082 0.1384811191 0.2659782171 0.0132018898 0.0355990000 1114002917 0 402718720 0.0850165859 0.1770178229 0.1747879386 771 1305031127.8473660946 0.1602449417 0.1385093472 0.2659782171 0.0131933310 0.0335360000 1114006173 0 402718720 0.0848826393 0.1763712317 0.1751218140 772 1305031127.8793799877 0.1598094851 0.1385369380 0.2659782171 0.0131852922 0.0334280000 1114009261 0 402718720 0.0839647129 0.1756377965 0.1753566712 773 1305031127.9114758968 0.1596409380 0.1385642394 0.2659782171 0.0131768679 0.0367330000 1114012405 0 402718720 0.0834845752 0.1758555919 0.1753299087 774 1305031127.9473659992 0.1596996635 0.1385915462 0.2659782171 0.0131727670 0.0312940000 1114015661 0 402718720 0.0832974836 0.1766149551 0.1754679084 775 1305031127.9793710709 0.1594732553 0.1386184903 0.2659782171 0.0131656077 0.0343830000 1114018805 0 402718720 0.0831553340 0.1756725460 0.1767670810 776 1305031128.0114269257 0.1598781496 0.1386458868 0.2659782171 0.0131574562 0.0356200000 1114021949 0 402718720 0.0841232985 0.1756620109 0.1776953936 777 1305031128.0473690033 0.1586064845 0.1386715761 0.2659782171 0.0131506037 0.0329340000 1114025261 0 402718720 0.0837556049 0.1735694557 0.1799655408 778 1305031128.0793340206 0.1571785808 0.1386953640 0.2659782171 0.0131423783 0.0662130000 1114028405 0 402718720 0.0829688460 0.1717893183 0.1809607446 779 1305031128.1113910675 0.1567455530 0.1387185350 0.2659782171 0.0131344199 0.0357530000 1114031493 0 402718720 0.0831435993 0.1714813411 0.1814400256 780 1305031128.1474180222 0.1560461968 0.1387407500 0.2659782171 0.0131263316 0.0387860000 1114034805 0 402718720 0.0832990631 0.1709478796 0.1823690981 781 1305031128.1793498993 0.1553819478 0.1387620575 0.2659782171 0.0131222294 0.0356850000 1114037893 0 402718720 0.0833487660 0.1680040807 0.1835695207 782 1305031128.2114470005 0.1551085114 0.1387829609 0.2659782171 0.0131181383 0.0370500000 1114041037 0 402718720 0.0831950754 0.1692713797 0.1828894615 783 1305031128.2474799156 0.1550422907 0.1388037263 0.2659782171 0.0131102710 0.0393030000 1114044349 0 402718720 0.0830846950 0.1698168516 0.1831177324 784 1305031128.2793359756 0.1549322605 0.1388242984 0.2659782171 0.0131069664 0.0356720000 1114047493 0 402718720 0.0832676589 0.1674737632 0.1840299219 785 1305031128.3114829063 0.1552434117 0.1388452145 0.2659782171 0.0130999915 0.0359620000 1114050581 0 402718720 0.0832188278 0.1683360934 0.1834716797 786 1305031128.3474230766 0.1554907858 0.1388663921 0.2659782171 0.0130924987 0.0370230000 1114053893 0 402718720 0.0826325119 0.1685369015 0.1832890213 787 1305031128.3794040680 0.1557099521 0.1388877943 0.2659782171 0.0130859241 0.0362880000 1114056981 0 402718720 0.0822977126 0.1674712449 0.1835927069 788 1305031128.4113368988 0.1560349911 0.1389095547 0.2659782171 0.0130805121 0.0356180000 1114060125 0 402718720 0.0821593925 0.1670531780 0.1833638251 789 1305031128.4472959042 0.1562321186 0.1389315098 0.2659782171 0.0130733738 0.0360740000 1114063381 0 402718720 0.0816261545 0.1673818231 0.1827880889 790 1305031128.4792959690 0.1563175917 0.1389535175 0.2659782171 0.0130651951 0.0676900000 1114066525 0 402718720 0.0812552869 0.1666965485 0.1831008643 791 1305031128.5114328861 0.1566107273 0.1389758402 0.2659782171 0.0130570188 0.0358440000 1114069669 0 402718720 0.0814278722 0.1661533564 0.1828729063 792 1305031128.5473990440 0.1568297148 0.1389983829 0.2659782171 0.0130489237 0.0372310000 1114072925 0 402718720 0.0815736726 0.1659049988 0.1830603778 793 1305031128.5794548988 0.1560006142 0.1390198233 0.2659782171 0.0130424542 0.0373770000 1114076069 0 402718720 0.0811480135 0.1643454283 0.1830743104 794 1305031128.6113948822 0.1554545611 0.1390405220 0.2659782171 0.0130352430 0.0390670000 1114079213 0 402718720 0.0802904293 0.1644265205 0.1823762953 795 1305031128.6473519802 0.1554386169 0.1390611485 0.2659782171 0.0130286940 0.0397970000 1114082469 0 402718720 0.0797763839 0.1648166627 0.1817755401 796 1305031128.6792819500 0.1559087187 0.1390823138 0.2659782171 0.0130215198 0.0373750000 1114085613 0 402718720 0.0802193582 0.1638678163 0.1819802076 797 1305031128.7114570141 0.1568042040 0.1391045495 0.2659782171 0.0130139361 0.0323950000 1114088757 0 402718720 0.0810168758 0.1636044532 0.1816659123 798 1305031128.7473630905 0.1575566679 0.1391276725 0.2659782171 0.0130070179 0.0368020000 1114092013 0 402718720 0.0812694803 0.1641031802 0.1812471300 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 10:19:40 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6417100430 0.0019026520 0.0019026520 0.0019026520 -nan 0.0095740000 96119436 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0025787114 0.0022406817 0.0025787114 0.0020003670 0.0384650000 124862801 0 402718720 0.0009667081 -0.0003618203 0.0001371565 3 1311867718.7114160061 0.0043683243 0.0029498959 0.0043683243 0.0029345136 0.0646370000 128135609 0 402718720 0.0000204623 -0.0024267165 -0.0004448564 4 1311867718.7409899235 0.0023795757 0.0028073158 0.0043683243 0.0033240164 0.0375030000 128138985 0 402718720 -0.0006766718 0.0000693081 0.0006481900 5 1311867718.7767970562 0.0018157568 0.0026090040 0.0043683243 0.0029304006 0.0386140000 128142769 0 402718720 -0.0007965876 0.0002573971 0.0012053574 6 1311867718.8094038963 0.0045338483 0.0029298114 0.0045338483 0.0035562120 0.0458600000 128146657 0 402718720 -0.0004500575 -0.0028538953 0.0003420236 7 1311867718.8408079147 0.0035067166 0.0030122264 0.0045338483 0.0033355008 0.0365630000 128149801 0 402718720 -0.0004532582 -0.0009316847 0.0006166815 8 1311867718.8767778873 0.0044543929 0.0031924972 0.0045338483 0.0032268966 0.0460610000 128153057 0 402718720 -0.0012488646 -0.0023213874 0.0008718905 9 1311867718.9088499546 0.0060169622 0.0035063267 0.0060169622 0.0032655245 0.0473380000 128156921 0 402718720 -0.0029074054 -0.0033961411 0.0004109270 10 1311867718.9438269138 0.0051325820 0.0036689522 0.0060169622 0.0031465705 0.0460140000 128161777 0 402718720 -0.0036007499 -0.0020441518 0.0010832105 11 1311867718.9784109592 0.0032691231 0.0036326041 0.0060169622 0.0030231676 0.0389380000 128165089 0 402718720 -0.0015797990 -0.0000834646 0.0023592890 12 1311867719.0090429783 0.0038167459 0.0036479493 0.0060169622 0.0029253571 0.0381310000 128168065 0 402718720 -0.0015513987 -0.0004911855 0.0022568242 13 1311867719.0441069603 0.0051405421 0.0037627641 0.0060169622 0.0028122748 0.0444970000 128171321 0 402718720 -0.0031715741 -0.0025640153 0.0021453914 14 1311867719.0768620968 0.0055055576 0.0038872494 0.0060169622 0.0027598675 0.0402060000 128174521 0 402718720 -0.0032313683 -0.0032179249 0.0025505750 15 1311867719.1086890697 0.0062983162 0.0040479871 0.0062983162 0.0027849616 0.0506120000 128177665 0 402718720 -0.0014667853 -0.0039929636 0.0028271179 16 1311867719.1436860561 0.0059810006 0.0041688005 0.0062983162 0.0026931297 0.0390450000 128180865 0 402718720 -0.0021095306 -0.0036366438 0.0030035276 17 1311867719.1810290813 0.0057322686 0.0042607692 0.0062983162 0.0026162297 0.0676640000 140533233 0 402718720 -0.0032101516 -0.0035358195 0.0034539518 18 1311867719.2126939297 0.0042227493 0.0042586570 0.0062983162 0.0026451106 0.0434690000 144199129 0 402718720 -0.0021976635 -0.0017685959 0.0045106220 19 1311867719.2412030697 0.0057143979 0.0043352749 0.0062983162 0.0026014428 0.0224480000 147394353 0 402718720 -0.0029614512 -0.0041055218 0.0050521749 20 1311867719.2779400349 0.0055815261 0.0043975875 0.0062983162 0.0029547447 0.0272860000 147397553 0 402718720 -0.0039883922 -0.0044279443 0.0055653239 21 1311867719.3104751110 0.0056392183 0.0044567128 0.0062983162 0.0030048165 0.0624130000 147400753 0 402718720 -0.0051992559 -0.0043144245 0.0053358786 22 1311867719.3412981033 0.0045439759 0.0044606793 0.0062983162 0.0030145497 0.0264340000 147403897 0 402718720 -0.0044973935 -0.0031670157 0.0059047919 23 1311867719.3772559166 0.0040728804 0.0044438184 0.0062983162 0.0029761402 0.0245910000 147407097 0 402718720 -0.0049571120 -0.0032982936 0.0069637964 24 1311867719.4105629921 0.0051052836 0.0044713795 0.0062983162 0.0029515861 0.0279370000 147410297 0 402718720 -0.0055797505 -0.0043344693 0.0061044549 25 1311867719.4427659512 0.0019475059 0.0043704245 0.0062983162 0.0030100139 0.0309580000 147413497 0 402718720 -0.0055861529 -0.0010812253 0.0077665229 26 1311867719.4787509441 0.0008936314 0.0042367017 0.0062983162 0.0030168829 0.0337170000 147416697 0 402718720 -0.0076517244 -0.0000110957 0.0086204503 27 1311867719.5103800297 0.0049017933 0.0042613348 0.0062983162 0.0034205113 0.0273880000 147419841 0 402718720 -0.0047062850 -0.0044477922 0.0074816402 28 1311867719.5449209213 0.0028489376 0.0042108920 0.0062983162 0.0035144644 0.0313930000 147423041 0 402718720 -0.0069435057 -0.0022870644 0.0076177591 29 1311867719.5771799088 0.0026669998 0.0041576543 0.0062983162 0.0034696239 0.0325090000 147426241 0 402718720 -0.0065243798 -0.0006566491 0.0096179228 30 1311867719.6112289429 0.0037095775 0.0041427184 0.0062983162 0.0034615629 0.0320650000 147429441 0 402718720 -0.0065447045 -0.0026105247 0.0086085936 31 1311867719.6421790123 0.0036372254 0.0041264122 0.0062983162 0.0034079425 0.0881630000 166273309 0 402718720 -0.0077456520 -0.0027208531 0.0084339967 32 1311867719.6770379543 0.0027103024 0.0040821588 0.0062983162 0.0033843820 0.0212170000 169935773 0 402718720 -0.0095389299 -0.0030644615 0.0095465472 33 1311867719.7107799053 0.0058253552 0.0041349829 0.0062983162 0.0034125359 0.0869680000 173134437 0 402718720 -0.0109976307 -0.0059306417 0.0085708378 34 1311867719.7442409992 0.0055315057 0.0041760571 0.0062983162 0.0033646842 0.0360160000 173143981 0 402718720 -0.0115122143 -0.0047889450 0.0085624494 35 1311867719.7806169987 0.0061134566 0.0042314114 0.0062983162 0.0034624376 0.0296360000 173147293 0 402718720 -0.0128965760 -0.0050245142 0.0091498652 36 1311867719.8098258972 0.0038669950 0.0042212887 0.0062983162 0.0035489532 0.0246970000 173150325 0 402718720 -0.0109749353 -0.0028100221 0.0105934385 37 1311867719.8454849720 0.0029187333 0.0041860845 0.0062983162 0.0035224121 0.0278950000 173153581 0 402718720 -0.0110016353 -0.0016010641 0.0118549485 38 1311867719.8770980835 0.0035356025 0.0041689666 0.0062983162 0.0034863053 0.0251320000 173156725 0 402718720 -0.0111426208 -0.0024108132 0.0117328241 39 1311867719.9113459587 0.0033257937 0.0041473467 0.0062983162 0.0034937969 0.0258330000 173159981 0 402718720 -0.0114145437 -0.0019794803 0.0124583999 40 1311867719.9461910725 0.0035318527 0.0041319594 0.0062983162 0.0034569023 0.0300810000 173163181 0 402718720 -0.0109036788 -0.0015860815 0.0134030422 41 1311867719.9807810783 0.0045422013 0.0041419653 0.0062983162 0.0034340712 0.0273880000 173166437 0 402718720 -0.0108171143 -0.0028650032 0.0135697313 42 1311867720.0116190910 0.0055149412 0.0041746552 0.0062983162 0.0034391672 0.0298320000 173169469 0 402718720 -0.0116073908 -0.0047526117 0.0130116297 43 1311867720.0450179577 0.0060170037 0.0042175005 0.0062983162 0.0033999912 0.0311270000 173172669 0 402718720 -0.0103753060 -0.0036293666 0.0143138235 44 1311867720.0772368908 0.0047953054 0.0042306324 0.0062983162 0.0034413380 0.0294440000 173175869 0 402718720 -0.0114664789 -0.0002938686 0.0148716494 45 1311867720.1121330261 0.0052868323 0.0042541035 0.0062983162 0.0034276476 0.0316580000 173179069 0 402718720 -0.0112700062 0.0007235082 0.0147820348 46 1311867720.1451458931 0.0062933820 0.0042984357 0.0062983162 0.0034343415 0.0307970000 173182213 0 402718720 -0.0103457263 -0.0005575921 0.0146245752 47 1311867720.1781549454 0.0059701055 0.0043340031 0.0062983162 0.0033993765 0.0259950000 173185357 0 402718720 -0.0107705891 -0.0004811866 0.0146711944 48 1311867720.2094950676 0.0052674180 0.0043534493 0.0062983162 0.0033768251 0.0847400000 185499637 0 402718720 -0.0124520473 -0.0013686231 0.0138362423 49 1311867720.2421309948 0.0053377282 0.0043735366 0.0062983162 0.0033437080 0.0223120000 189162805 0 402718720 -0.0131109310 0.0000159422 0.0138083957 50 1311867720.2770709991 0.0061146654 0.0044083592 0.0062983162 0.0034169603 0.0195930000 192358197 0 402718720 -0.0133430883 -0.0017727989 0.0140711293 51 1311867720.3094489574 0.0073738620 0.0044665063 0.0073738620 0.0034149841 0.0300490000 192361341 0 402718720 -0.0133182341 -0.0023891788 0.0137895178 52 1311867720.3430650234 0.0064921151 0.0045054603 0.0073738620 0.0034955537 0.0326830000 192364541 0 402718720 -0.0121474881 0.0002414936 0.0156061370 53 1311867720.3779759407 0.0078365486 0.0045683110 0.0078365486 0.0035079536 0.0396210000 192367685 0 402718720 -0.0100077018 0.0008641140 0.0185780227 54 1311867720.4091560841 0.0085472427 0.0046419949 0.0085472427 0.0037044342 0.0452670000 192370829 0 402718720 -0.0107164420 -0.0004538779 0.0175462067 55 1311867720.4412200451 0.0080347322 0.0047036811 0.0085472427 0.0036923044 0.0347290000 192374029 0 402718720 -0.0119789857 0.0025273901 0.0173562784 56 1311867720.4798839092 0.0090858517 0.0047819341 0.0090858517 0.0036870898 0.0343430000 192377341 0 402718720 -0.0118626310 0.0052235411 0.0183861740 57 1311867720.5104320049 0.0078590410 0.0048359185 0.0090858517 0.0037777663 0.0282750000 192380429 0 402718720 -0.0119457124 0.0013477578 0.0179633740 58 1311867720.5410339832 0.0082631474 0.0048950086 0.0090858517 0.0037949906 0.0277300000 192383573 0 402718720 -0.0127115771 0.0009371510 0.0170840528 59 1311867720.5793080330 0.0095399255 0.0049737360 0.0095399255 0.0038161396 0.0270260000 192386885 0 402718720 -0.0112735974 0.0030496023 0.0194380023 60 1311867720.6121180058 0.0091444012 0.0050432471 0.0095399255 0.0037902488 0.0615730000 192390029 0 402718720 -0.0120587908 0.0013221672 0.0186293293 61 1311867720.6410660744 0.0094692539 0.0051158046 0.0095399255 0.0038045370 0.0269630000 192393117 0 402718720 -0.0127034113 0.0006977926 0.0181870032 62 1311867720.6797840595 0.0104718078 0.0052021917 0.0104718078 0.0038387605 0.0324600000 192396373 0 402718720 -0.0121651925 0.0023597979 0.0190616399 63 1311867720.7102301121 0.0109439436 0.0052933307 0.0109439436 0.0038105346 0.0304330000 192399517 0 402718720 -0.0120462542 0.0017350615 0.0201941170 64 1311867720.7411010265 0.0107464921 0.0053785363 0.0109439436 0.0038291689 0.0306460000 192402661 0 402718720 -0.0130038429 -0.0011111243 0.0181029122 65 1311867720.7789759636 0.0111375060 0.0054671358 0.0111375060 0.0038035960 0.0287350000 192412629 0 402718720 -0.0135458112 -0.0002426652 0.0179438703 66 1311867720.8115720749 0.0118402913 0.0055636988 0.0118402913 0.0037811254 0.0808290000 204735413 0 402718720 -0.0131552508 -0.0005509808 0.0191629324 67 1311867720.8408989906 0.0075322976 0.0055930809 0.0118402913 0.0039434899 0.0217230000 208397653 0 402718720 -0.0192024410 0.0021665774 0.0170704965 68 1311867720.8813259602 0.0074085845 0.0056197795 0.0118402913 0.0039207369 0.0183950000 211593269 0 402718720 -0.0197062697 0.0020187148 0.0168385543 69 1311867720.9105548859 0.0084337378 0.0056605615 0.0118402913 0.0039019229 0.0208500000 211596301 0 402718720 -0.0192737728 0.0036316649 0.0172378812 70 1311867720.9409220219 0.0085452301 0.0057017710 0.0118402913 0.0038984488 0.0216730000 211599389 0 402718720 -0.0189512596 0.0037003418 0.0173143111 71 1311867720.9797680378 0.0086548878 0.0057433642 0.0118402913 0.0038930969 0.0849990000 211602645 0 402718720 -0.0196672641 0.0045497050 0.0174253602 72 1311867721.0093820095 0.0069101094 0.0057595690 0.0118402913 0.0039175740 0.0374560000 211605733 0 402718720 -0.0205216203 0.0007008082 0.0169528648 73 1311867721.0410830975 0.0077440259 0.0057867533 0.0118402913 0.0039028185 0.0221270000 211608877 0 402718720 -0.0201482493 0.0028200680 0.0167983323 74 1311867721.0794250965 0.0082392851 0.0058198957 0.0118402913 0.0039076772 0.0262150000 211612189 0 402718720 -0.0201265980 0.0027916830 0.0165982079 75 1311867721.1103479862 0.0089807743 0.0058620407 0.0118402913 0.0038883529 0.0199110000 211615333 0 402718720 -0.0196049772 0.0038840855 0.0172578022 76 1311867721.1413290501 0.0077389255 0.0058867366 0.0118402913 0.0038967807 0.0313010000 211618421 0 402718720 -0.0206323061 -0.0005427846 0.0166389439 77 1311867721.1773610115 0.0080961129 0.0059154298 0.0118402913 0.0038750245 0.0356100000 211621733 0 402718720 -0.0210222714 -0.0022120811 0.0162507761 78 1311867721.2112181187 0.0085012475 0.0059485813 0.0118402913 0.0038574140 0.0275000000 211624877 0 402718720 -0.0202861018 0.0003796137 0.0163563248 79 1311867721.2409920692 0.0088488739 0.0059852938 0.0118402913 0.0038726902 0.0320220000 211627965 0 402718720 -0.0200780183 -0.0016651877 0.0170893427 80 1311867721.2799990177 0.0093470253 0.0060273155 0.0118402913 0.0038539062 0.0373640000 211631277 0 402718720 -0.0198973976 0.0001500706 0.0161955301 81 1311867721.3099579811 0.0093020275 0.0060677440 0.0118402913 0.0038326645 0.0281740000 211634421 0 402718720 -0.0199503973 0.0012836765 0.0166438445 82 1311867721.3409619331 0.0092844442 0.0061069721 0.0118402913 0.0038453940 0.0276360000 211637509 0 402718720 -0.0213229302 -0.0027408912 0.0155499913 83 1311867721.3789949417 0.0104648396 0.0061594765 0.0118402913 0.0038243735 0.0765620000 211640709 0 402718720 -0.0208927784 -0.0035691920 0.0154273678 84 1311867721.4092490673 0.0103319380 0.0062091487 0.0118402913 0.0038019930 0.0323960000 211643797 0 402718720 -0.0212205462 -0.0015474270 0.0142511148 85 1311867721.4412109852 0.0096217562 0.0062492970 0.0118402913 0.0037815466 0.0299960000 211646997 0 402718720 -0.0224149935 -0.0006790321 0.0139065534 86 1311867721.4768860340 0.0104225734 0.0062978235 0.0118402913 0.0037613105 0.0296860000 211650253 0 402718720 -0.0220802650 -0.0012580252 0.0140091367 87 1311867721.5093119144 0.0098655997 0.0063388324 0.0118402913 0.0037443040 0.0264940000 211653341 0 402718720 -0.0220025461 0.0005922876 0.0150039652 88 1311867721.5411579609 0.0106145581 0.0063874202 0.0118402913 0.0037294004 0.0270940000 211656541 0 402718720 -0.0218686722 -0.0001172745 0.0143620605 89 1311867721.5769670010 0.0105084246 0.0064337236 0.0118402913 0.0037130899 0.0312750000 211659629 0 402718720 -0.0238568429 -0.0019229817 0.0129072554 90 1311867721.6094360352 0.0092028752 0.0064644919 0.0118402913 0.0037283994 0.0252010000 211662717 0 402718720 -0.0231777411 0.0018817380 0.0147803603 91 1311867721.6409630775 0.0110762836 0.0065151710 0.0118402913 0.0037425231 0.0775760000 223975057 0 402718720 -0.0233669858 -0.0024013582 0.0134584736 92 1311867721.6800279617 0.0187599417 0.0066482663 0.0187599417 0.0038951968 0.0453450000 227637577 0 402718720 -0.0185291059 -0.0077949157 0.0119183734 93 1311867721.7089879513 0.0168619826 0.0067580912 0.0187599417 0.0038876009 0.0379910000 230832857 0 402718720 -0.0182221383 -0.0040783877 0.0138998022 94 1311867721.7410759926 0.0172354747 0.0068695527 0.0187599417 0.0038804584 0.0362490000 230836001 0 402718720 -0.0206065532 -0.0077825985 0.0139917471 95 1311867721.7786920071 0.0166885741 0.0069729109 0.0187599417 0.0038617072 0.0330100000 230839313 0 402718720 -0.0218889844 -0.0067090956 0.0117608411 96 1311867721.8090760708 0.0159954559 0.0070668957 0.0187599417 0.0038469423 0.0559820000 230842401 0 402718720 -0.0204735864 -0.0039724838 0.0132943997 97 1311867721.8409729004 0.0178947505 0.0071785231 0.0187599417 0.0038402808 0.0317800000 230845545 0 402718720 -0.0201212931 -0.0065562059 0.0135883549 98 1311867721.8778719902 0.0169925094 0.0072786658 0.0187599417 0.0038324843 0.0298980000 230848857 0 402718720 -0.0207374841 -0.0043571312 0.0113355648 99 1311867721.9089739323 0.0175332725 0.0073822477 0.0187599417 0.0038138181 0.0282860000 230851721 0 402718720 -0.0199411400 -0.0044124359 0.0122746564 100 1311867721.9409759045 0.0190626979 0.0074990522 0.0190626979 0.0038090961 0.0286890000 230854921 0 402718720 -0.0192293599 -0.0060190093 0.0124174450 101 1311867721.9773590565 0.0187769979 0.0076107150 0.0190626979 0.0038077659 0.0319040000 230858177 0 402718720 -0.0204606690 -0.0066620833 0.0108178044 102 1311867722.0090909004 0.0188732352 0.0077211319 0.0190626979 0.0038119647 0.0294620000 230861209 0 402718720 -0.0196910016 -0.0057166470 0.0121375909 103 1311867722.0409901142 0.0188974906 0.0078296402 0.0190626979 0.0038011599 0.0268850000 230864241 0 402718720 -0.0204581358 -0.0067601060 0.0113908788 104 1311867722.0800709724 0.0197491609 0.0079442510 0.0197491609 0.0037865945 0.0333980000 230867609 0 402718720 -0.0200751685 -0.0073449360 0.0110356854 105 1311867722.1090641022 0.0204551518 0.0080634024 0.0204551518 0.0037723411 0.0286440000 230870585 0 402718720 -0.0199403036 -0.0081072282 0.0117267082 106 1311867722.1409659386 0.0210538097 0.0081859534 0.0210538097 0.0037638883 0.0275730000 230873729 0 402718720 -0.0213013068 -0.0097961398 0.0100340331 107 1311867722.1798129082 0.0194901172 0.0082915998 0.0210538097 0.0037611528 0.0266720000 230877041 0 402718720 -0.0225193221 -0.0080219908 0.0089482982 108 1311867722.2090559006 0.0175183881 0.0083770330 0.0210538097 0.0037589050 0.0620670000 230880073 0 402718720 -0.0221540667 -0.0050119748 0.0108895730 109 1311867722.2409958839 0.0192867499 0.0084771222 0.0210538097 0.0037712351 0.0261420000 230883273 0 402718720 -0.0221121460 -0.0076302621 0.0098841880 110 1311867722.2778589725 0.0190764982 0.0085734802 0.0210538097 0.0037546404 0.0272810000 230886585 0 402718720 -0.0236974470 -0.0077477656 0.0079163034 111 1311867722.3090419769 0.0188385658 0.0086659584 0.0210538097 0.0037399266 0.0454870000 230889617 0 402718720 -0.0221419316 -0.0063447650 0.0102979457 112 1311867722.3409590721 0.0193935353 0.0087617403 0.0210538097 0.0037309524 0.0260330000 230892817 0 402718720 -0.0228394140 -0.0076890560 0.0100272102 113 1311867722.3777840137 0.0192814879 0.0088548355 0.0210538097 0.0037146550 0.0297210000 230896073 0 402718720 -0.0236031581 -0.0076879845 0.0085413596 114 1311867722.4089860916 0.0187616050 0.0089417369 0.0210538097 0.0037014743 0.0271490000 230899105 0 402718720 -0.0228403602 -0.0064170528 0.0104756560 115 1311867722.4409530163 0.0198050030 0.0090362001 0.0210538097 0.0037141268 0.0271490000 230902193 0 402718720 -0.0234599169 -0.0084365970 0.0105047813 116 1311867722.4777851105 0.0198940877 0.0091298026 0.0210538097 0.0037388061 0.0291880000 230905449 0 402718720 -0.0246323124 -0.0086364830 0.0085820323 117 1311867722.5090739727 0.0181758441 0.0092071192 0.0210538097 0.0038143665 0.0274250000 230908537 0 402718720 -0.0261047278 -0.0071973545 0.0091741541 118 1311867722.5411169529 0.0169354994 0.0092726139 0.0210538097 0.0038344488 0.0266910000 230911569 0 402718720 -0.0276324861 -0.0064926315 0.0081103444 119 1311867722.5802209377 0.0166925564 0.0093349664 0.0210538097 0.0038204686 0.0277820000 230914881 0 402718720 -0.0263116490 -0.0053949677 0.0092784613 120 1311867722.6091809273 0.0150682041 0.0093827434 0.0210538097 0.0038124630 0.0287550000 230917913 0 402718720 -0.0277954470 -0.0048552854 0.0096575739 121 1311867722.6411309242 0.0169239845 0.0094450677 0.0210538097 0.0038113401 0.0272310000 230921113 0 402718720 -0.0275745355 -0.0075500705 0.0100089675 122 1311867722.6778120995 0.0170622282 0.0095075034 0.0210538097 0.0038027817 0.0374390000 230924425 0 402718720 -0.0288927257 -0.0083420351 0.0086646033 123 1311867722.7090990543 0.0162096396 0.0095619923 0.0210538097 0.0038623952 0.0249950000 230927513 0 402718720 -0.0289528817 -0.0072298953 0.0095287059 124 1311867722.7411129475 0.0155110769 0.0096099688 0.0210538097 0.0038716550 0.0291260000 230930657 0 402718720 -0.0322823897 -0.0087216059 0.0088411737 125 1311867722.7770080566 0.0177642070 0.0096752027 0.0210538097 0.0038764365 0.0315180000 230933969 0 402718720 -0.0306150913 -0.0095208893 0.0070749871 126 1311867722.8090240955 0.0173767563 0.0097363262 0.0210538097 0.0038693540 0.0647980000 243240909 0 402718720 -0.0327897631 -0.0097579267 0.0067021195 127 1311867722.8412160873 0.0114190793 0.0097495762 0.0210538097 0.0039460535 0.0429680000 246903149 0 402718720 -0.0357040688 -0.0046925214 0.0087056514 128 1311867722.8771059513 0.0138958860 0.0097819692 0.0210538097 0.0039367399 0.0353970000 250098597 0 402718720 -0.0424852856 -0.0057677832 0.0049783178 129 1311867722.9092500210 0.0148289474 0.0098210931 0.0210538097 0.0039316780 0.0694840000 250114997 0 402718720 -0.0415885076 -0.0053540268 0.0036577790 130 1311867722.9413120747 0.0111168828 0.0098310607 0.0210538097 0.0039209226 0.0355160000 250143685 0 402718720 -0.0387953855 -0.0033578908 0.0074596726 131 1311867722.9771549702 0.0143447490 0.0098655164 0.0210538097 0.0039264009 0.0313340000 250146941 0 402718720 -0.0403459035 -0.0064053661 0.0060954974 132 1311867723.0092680454 0.0149954865 0.0099043798 0.0210538097 0.0039144489 0.0297610000 250150029 0 402718720 -0.0431968048 -0.0042840322 0.0035598562 133 1311867723.0411980152 0.0119243870 0.0099195678 0.0210538097 0.0039829259 0.0324110000 250153173 0 402718720 -0.0426817127 -0.0034892962 0.0066322815 134 1311867723.0773079395 0.0128664505 0.0099415595 0.0210538097 0.0041244500 0.0307310000 250156485 0 402718720 -0.0419373773 -0.0050954642 0.0073702456 135 1311867723.1091949940 0.0155850062 0.0099833628 0.0210538097 0.0041191382 0.0308000000 250159573 0 402718720 -0.0430605710 -0.0072248108 0.0057651107 136 1311867723.1411499977 0.0134597421 0.0100089244 0.0210538097 0.0041053130 0.0344540000 250162661 0 402718720 -0.0424709618 -0.0060686916 0.0075537772 137 1311867723.1769969463 0.0159328245 0.0100521645 0.0210538097 0.0040930939 0.0334140000 250165973 0 402718720 -0.0442027487 -0.0090785315 0.0068591689 138 1311867723.2092559338 0.0163516179 0.0100978127 0.0210538097 0.0040791593 0.0308220000 250169061 0 402718720 -0.0452689976 -0.0093874019 0.0060038250 139 1311867723.2410740852 0.0175271500 0.0101512612 0.0210538097 0.0040659290 0.0337480000 250172205 0 402718720 -0.0474915728 -0.0103566805 0.0049913637 140 1311867723.2773449421 0.0190911125 0.0102151173 0.0210538097 0.0040583630 0.0320870000 250175517 0 402718720 -0.0508055501 -0.0111632198 0.0039468342 141 1311867723.3093810081 0.0242802631 0.0103148701 0.0242802631 0.0040523096 0.0661140000 250178549 0 402718720 -0.0561317280 -0.0150176613 0.0024996707 142 1311867723.3412499428 0.0327628627 0.0104729545 0.0327628627 0.0040642290 0.0300570000 250181749 0 402718720 -0.0638222024 -0.0197889339 -0.0010033585 143 1311867723.3772110939 0.0406835414 0.0106842174 0.0406835414 0.0040680210 0.0292060000 250185005 0 402718720 -0.0718468502 -0.0237030555 -0.0030692131 144 1311867723.4093298912 0.0530202538 0.0109782176 0.0530202538 0.0040640188 0.0293350000 250188093 0 402718720 -0.0836662501 -0.0292554889 -0.0063423770 145 1311867723.4410910606 0.0671218708 0.0113654153 0.0671218708 0.0041090159 0.0296350000 250191293 0 402718720 -0.0952031687 -0.0367576033 -0.0102806976 146 1311867723.4770638943 0.0705980733 0.0117711184 0.0705980733 0.0041085402 0.0293380000 250194549 0 402718720 -0.0968343988 -0.0405233726 -0.0115461703 147 1311867723.5092871189 0.0748478472 0.0122002118 0.0748478472 0.0041184074 0.0290130000 250197637 0 402718720 -0.0978002995 -0.0446325876 -0.0142541993 148 1311867723.5412330627 0.0757035390 0.0126292883 0.0757035390 0.0042588740 0.0486540000 250200837 0 402718720 -0.1000106409 -0.0462073013 -0.0099456646 149 1311867723.5771219730 0.0755099505 0.0130513062 0.0757035390 0.0042709419 0.0302970000 250204093 0 402718720 -0.0996143296 -0.0458432995 -0.0113687115 150 1311867723.6092190742 0.0764966607 0.0134742752 0.0764966607 0.0042669045 0.0302150000 250207181 0 402718720 -0.0991484895 -0.0477495827 -0.0115420371 151 1311867723.6412839890 0.0775603577 0.0138986864 0.0775603577 0.0042576200 0.0619640000 262513677 0 402718720 -0.0997248068 -0.0482099950 -0.0125647876 152 1311867723.6771829128 0.0748074576 0.0142994020 0.0775603577 0.0042498246 0.0140750000 266177821 0 402718720 -0.0964073241 -0.0479987226 -0.0116475308 153 1311867723.7092189789 0.0757566914 0.0147010836 0.0775603577 0.0042402054 0.0456210000 269373157 0 402718720 -0.0969489813 -0.0488706008 -0.0121715572 154 1311867723.7412030697 0.0750795528 0.0150931516 0.0775603577 0.0042269301 0.0182750000 269376301 0 402718720 -0.0969816297 -0.0481132455 -0.0122168697 155 1311867723.7771170139 0.0749872178 0.0154795649 0.0775603577 0.0042132592 0.0146640000 269379557 0 402718720 -0.0970480368 -0.0486054309 -0.0115847010 156 1311867723.8093750477 0.0754827112 0.0158642005 0.0775603577 0.0042041789 0.0143480000 269382701 0 402718720 -0.0975546688 -0.0493154973 -0.0120224021 157 1311867723.8410520554 0.0767040178 0.0162517152 0.0775603577 0.0041937014 0.0326920000 269385845 0 402718720 -0.0984131843 -0.0499319546 -0.0132313622 158 1311867723.8770780563 0.0735201389 0.0166141736 0.0775603577 0.0042030972 0.0212830000 269389101 0 402718720 -0.0981844366 -0.0471107736 -0.0116300359 159 1311867723.9092159271 0.0770526007 0.0169942895 0.0775603577 0.0042184748 0.0429160000 269392133 0 402718720 -0.0988123864 -0.0507544987 -0.0137331318 160 1311867723.9411931038 0.0785425156 0.0173789659 0.0785425156 0.0042085165 0.0262380000 269395221 0 402718720 -0.0996290818 -0.0514522083 -0.0153347906 161 1311867723.9773468971 0.0761666819 0.0177441070 0.0785425156 0.0042024594 0.0243750000 269398533 0 402718720 -0.0988904685 -0.0505500995 -0.0121635264 162 1311867724.0091340542 0.0776644200 0.0181139855 0.0785425156 0.0042022930 0.0253280000 269401565 0 402718720 -0.0993055925 -0.0517843552 -0.0134936562 163 1311867724.0412750244 0.0779450908 0.0184810475 0.0785425156 0.0041905621 0.0233830000 269404765 0 402718720 -0.0996714309 -0.0515087321 -0.0141348606 164 1311867724.0771689415 0.0758264810 0.0188307147 0.0785425156 0.0041813549 0.0205820000 269408021 0 402718720 -0.0993707329 -0.0501411557 -0.0117945261 165 1311867724.1093120575 0.0766733363 0.0191812761 0.0785425156 0.0041707587 0.0215310000 269411165 0 402718720 -0.0997840762 -0.0508279391 -0.0125952074 166 1311867724.1413280964 0.0778569281 0.0195347439 0.0785425156 0.0041610453 0.0270800000 269414309 0 402718720 -0.1001799181 -0.0517013185 -0.0137698995 167 1311867724.1770989895 0.0763400868 0.0198748956 0.0785425156 0.0041539193 0.0222710000 269417565 0 402718720 -0.1001022682 -0.0505883619 -0.0120318076 168 1311867724.2094969749 0.0773311779 0.0202168973 0.0785425156 0.0041436444 0.0221160000 269420709 0 402718720 -0.1002166793 -0.0519968681 -0.0122568700 169 1311867724.2412230968 0.0783876702 0.0205611031 0.0785425156 0.0041343996 0.0262140000 269423853 0 402718720 -0.1004890352 -0.0528590940 -0.0130522568 170 1311867724.2771489620 0.0766532868 0.0208910571 0.0785425156 0.0041262172 0.0240420000 269427109 0 402718720 -0.1007510722 -0.0508715995 -0.0118540255 171 1311867724.3092370033 0.0764167383 0.0212157687 0.0785425156 0.0041140884 0.0217020000 269430253 0 402718720 -0.1007045582 -0.0511673614 -0.0110261701 172 1311867724.3412630558 0.0777062997 0.0215442020 0.0785425156 0.0041060295 0.0228980000 269433397 0 402718720 -0.1008481234 -0.0525414124 -0.0121366596 173 1311867724.3775219917 0.0770876780 0.0218652625 0.0785425156 0.0040947016 0.0329010000 269436709 0 402718720 -0.1011595726 -0.0518702380 -0.0117252870 174 1311867724.4092609882 0.0752540454 0.0221720946 0.0785425156 0.0040857405 0.0193970000 269439741 0 402718720 -0.1010258496 -0.0505340397 -0.0101034017 175 1311867724.4451010227 0.0756596252 0.0224777377 0.0785425156 0.0040757552 0.0223870000 269442997 0 402718720 -0.1014229283 -0.0514870696 -0.0102512948 176 1311867724.4770729542 0.0761025622 0.0227824242 0.0785425156 0.0040644535 0.0227290000 269446197 0 402718720 -0.1015655175 -0.0524957702 -0.0106030600 177 1311867724.5095100403 0.0760019571 0.0230830995 0.0785425156 0.0040550113 0.0210120000 269449341 0 402718720 -0.1020015255 -0.0523588993 -0.0112699969 178 1311867724.5453720093 0.0664059147 0.0233264861 0.0785425156 0.0040715014 0.0252280000 269452429 0 402718720 -0.0971754268 -0.0451251008 -0.0087501789 179 1311867724.5771729946 0.0681541786 0.0235769201 0.0785425156 0.0040608207 0.0631260000 281759409 0 402718720 -0.0993062183 -0.0465559252 -0.0086843651 180 1311867724.6092879772 0.1394937932 0.0242209028 0.1394937932 0.0059268437 0.0350430000 285421817 0 402718720 -0.1288684458 -0.1154852211 -0.0089025907 181 1311867724.6451389790 0.1399446279 0.0248602604 0.1399446279 0.0059121589 0.0269260000 288617209 0 402718720 -0.1289387494 -0.1162256747 -0.0095565850 182 1311867724.6771860123 0.1368102431 0.0254753702 0.1399446279 0.0059076996 0.0149780000 288620353 0 402718720 -0.1291134804 -0.1132443473 -0.0073329154 183 1311867724.7093029022 0.1407945901 0.0261055298 0.1407945901 0.0059100854 0.0266760000 288623497 0 402718720 -0.1296872199 -0.1174241155 -0.0098921107 184 1311867724.7452270985 0.1415939182 0.0267331841 0.1415939182 0.0058947505 0.0289230000 288626697 0 402718720 -0.1301544458 -0.1179698408 -0.0107617192 185 1311867724.7772819996 0.1401480734 0.0273462376 0.1415939182 0.0058803411 0.0255500000 288629897 0 402718720 -0.1305001974 -0.1164860576 -0.0091082165 186 1311867724.8093879223 0.1397994161 0.0279508245 0.1415939182 0.0058672892 0.0243320000 288633041 0 402718720 -0.1311063915 -0.1159402058 -0.0083310334 187 1311867724.8454389572 0.1403349787 0.0285518093 0.1415939182 0.0058532319 0.0231410000 288636185 0 402718720 -0.1306692362 -0.1169200912 -0.0093272487 188 1311867724.8771960735 0.1397879869 0.0291434911 0.1415939182 0.0058400792 0.0234280000 288639329 0 402718720 -0.1314897835 -0.1159540564 -0.0085326061 189 1311867724.9093389511 0.1389036328 0.0297242326 0.1415939182 0.0058368473 0.0262040000 288642417 0 402718720 -0.1312406361 -0.1158965081 -0.0074622757 190 1311867724.9453830719 0.1397473365 0.0303033016 0.1415939182 0.0058229947 0.0219680000 288645729 0 402718720 -0.1316261739 -0.1168402433 -0.0085865129 191 1311867724.9773509502 0.1389460266 0.0308721117 0.1415939182 0.0058081881 0.0200210000 288648873 0 402718720 -0.1315134764 -0.1162633002 -0.0078921299 192 1311867725.0094170570 0.1397236437 0.0314390467 0.1415939182 0.0058016133 0.0243260000 288652017 0 402718720 -0.1319875717 -0.1170682386 -0.0070470669 193 1311867725.0453710556 0.1398711056 0.0320008709 0.1415939182 0.0057886946 0.0213630000 288655273 0 402718720 -0.1324612796 -0.1172311381 -0.0079137869 194 1311867725.0771648884 0.1399088502 0.0325570976 0.1415939182 0.0057756872 0.0494470000 288658417 0 402718720 -0.1321445704 -0.1176926270 -0.0081725465 195 1311867725.1093239784 0.1386959702 0.0331013995 0.1415939182 0.0057643974 0.0229010000 288661505 0 402718720 -0.1327615678 -0.1165094972 -0.0064266361 196 1311867725.1454000473 0.1394774914 0.0336441346 0.1415939182 0.0057505955 0.0215390000 288664817 0 402718720 -0.1327231824 -0.1177163646 -0.0076996540 197 1311867725.1774249077 0.1401609778 0.0341848293 0.1415939182 0.0057360097 0.0207930000 288668017 0 402718720 -0.1331181973 -0.1187310070 -0.0073010488 198 1311867725.2095530033 0.1385337412 0.0347118440 0.1415939182 0.0057242710 0.0248540000 288671105 0 402718720 -0.1332879663 -0.1172727495 -0.0060952976 199 1311867725.2453670502 0.1403049231 0.0352424625 0.1415939182 0.0057123879 0.0212560000 288674361 0 402718720 -0.1339069605 -0.1192370206 -0.0072609778 200 1311867725.2774178982 0.1389257759 0.0357608790 0.1415939182 0.0056994236 0.0213610000 288677505 0 402718720 -0.1336826533 -0.1183225736 -0.0065882667 201 1311867725.3092849255 0.1395048201 0.0362770180 0.1415939182 0.0056852330 0.0246630000 288680593 0 402718720 -0.1341390908 -0.1191030741 -0.0058562220 202 1311867725.3453240395 0.1390317082 0.0367857046 0.1415939182 0.0056740200 0.0745500000 300994797 0 402718720 -0.1342488825 -0.1186455935 -0.0063038995 203 1311867725.3772640228 0.1319568008 0.0372545278 0.1415939182 0.0057204526 0.0312940000 304657149 0 402718720 -0.1307359636 -0.1118446290 -0.0079057030 204 1311867725.4093959332 0.1316575855 0.0377172878 0.1415939182 0.0057933049 0.0157870000 307852373 0 402718720 -0.1306423098 -0.1111721769 -0.0074424059 205 1311867725.4453248978 0.1315847486 0.0381751779 0.1415939182 0.0058155460 0.0217990000 307855629 0 402718720 -0.1305405051 -0.1115104482 -0.0087903561 206 1311867725.4772880077 0.1313189119 0.0386273319 0.1415939182 0.0058037621 0.0150460000 307858773 0 402718720 -0.1310379654 -0.1110124812 -0.0080820611 207 1311867725.5093019009 0.1302412897 0.0390699115 0.1415939182 0.0057963564 0.0462300000 307861861 0 402718720 -0.1312671155 -0.1101312935 -0.0067949127 208 1311867725.5453770161 0.1307353228 0.0395106105 0.1415939182 0.0057945701 0.0181080000 307865173 0 402718720 -0.1316349953 -0.1107017100 -0.0065245614 209 1311867725.5771839619 0.1315371096 0.0399509287 0.1415939182 0.0057908441 0.0239600000 307868317 0 402718720 -0.1320256740 -0.1117398292 -0.0072209178 210 1311867725.6094019413 0.1296721101 0.0403781724 0.1415939182 0.0057794155 0.0151900000 307871405 0 402718720 -0.1325329095 -0.1097697690 -0.0054605003 211 1311867725.6453518867 0.1303438097 0.0408045499 0.1415939182 0.0057777017 0.0182990000 307874717 0 402718720 -0.1330986619 -0.1108768135 -0.0047981520 212 1311867725.6771790981 0.1320163012 0.0412347940 0.1415939182 0.0057753525 0.0275570000 307877861 0 402718720 -0.1334796250 -0.1123959795 -0.0062102941 213 1311867725.7093379498 0.1303473115 0.0416531626 0.1415939182 0.0057632332 0.0194320000 307880949 0 402718720 -0.1338501871 -0.1106591150 -0.0052126534 214 1311867725.7453689575 0.1306066811 0.0420688333 0.1415939182 0.0057499358 0.0207370000 307884261 0 402718720 -0.1343778074 -0.1112545505 -0.0040280903 215 1311867725.7772219181 0.1318874806 0.0424865944 0.1415939182 0.0057387525 0.0265600000 307887405 0 402718720 -0.1345705092 -0.1127190143 -0.0059660086 216 1311867725.8093860149 0.1315866858 0.0428990948 0.1415939182 0.0057256505 0.0229790000 307890549 0 402718720 -0.1349596679 -0.1126297116 -0.0044020782 217 1311867725.8453550339 0.1325194687 0.0433120919 0.1415939182 0.0057183049 0.0223540000 307893805 0 402718720 -0.1357101947 -0.1135328859 -0.0040638661 218 1311867725.8772621155 0.1335122287 0.0437258540 0.1415939182 0.0057109115 0.0225160000 307896949 0 402718720 -0.1357250661 -0.1147910804 -0.0070999740 219 1311867725.9092769623 0.1337697804 0.0441370135 0.1415939182 0.0056988783 0.0860660000 320204845 0 402718720 -0.1366085708 -0.1149526164 -0.0046943505 220 1311867725.9454469681 0.1209806353 0.0444863027 0.1415939182 0.0057933081 0.0130060000 323867365 0 402718720 -0.1187598929 -0.1101474240 0.0084390482 221 1311867725.9772861004 0.1229950488 0.0448415459 0.1415939182 0.0057859459 0.0692870000 327062701 0 402718720 -0.1190567985 -0.1122199073 0.0068401108 222 1311867726.0092771053 0.1227145046 0.0451923250 0.1415939182 0.0057728758 0.0152090000 327065845 0 402718720 -0.1193602458 -0.1118376255 0.0076386798 223 1311867726.0452640057 0.1210607886 0.0455325423 0.1415939182 0.0057633016 0.0137540000 327069045 0 402718720 -0.1199201792 -0.1100931987 0.0095885471 224 1311867726.0773530006 0.1224589124 0.0458759636 0.1415939182 0.0057524164 0.0193010000 327072189 0 402718720 -0.1201346219 -0.1117363647 0.0082428809 225 1311867726.1094279289 0.1216183081 0.0462125963 0.1415939182 0.0057416461 0.0158640000 327075333 0 402718720 -0.1207028404 -0.1107630357 0.0093772840 226 1311867726.1454188824 0.1218409315 0.0465472349 0.1415939182 0.0057290462 0.0176160000 327078589 0 402718720 -0.1208808497 -0.1113277972 0.0097749047 227 1311867726.1773889065 0.1256983876 0.0468959184 0.1415939182 0.0057252840 0.0255110000 327081789 0 402718720 -0.1215655580 -0.1154276580 0.0079590976 228 1311867726.2094309330 0.1245097741 0.0472363301 0.1415939182 0.0057253300 0.0239640000 327084933 0 402718720 -0.1218936816 -0.1140326113 0.0085432054 229 1311867726.2453389168 0.1230916679 0.0475675761 0.1415939182 0.0057158004 0.0221010000 327088133 0 402718720 -0.1222811937 -0.1127948835 0.0099533685 230 1311867726.2772760391 0.1246628091 0.0479027727 0.1415939182 0.0057053830 0.0253750000 327091277 0 402718720 -0.1226502508 -0.1147139519 0.0093753450 231 1311867726.3095979691 0.1246443987 0.0482349876 0.1415939182 0.0056944750 0.0226970000 327094421 0 402718720 -0.1223825365 -0.1149098724 0.0085903434 232 1311867726.3454029560 0.1240571439 0.0485618072 0.1415939182 0.0056823933 0.0220010000 327097677 0 402718720 -0.1230240464 -0.1141398698 0.0090204952 233 1311867726.3772161007 0.1247909442 0.0488889709 0.1415939182 0.0056704943 0.0239770000 327100821 0 402718720 -0.1234931871 -0.1148025766 0.0092595639 234 1311867726.4093179703 0.1262313724 0.0492194940 0.1415939182 0.0056613990 0.0201040000 327103909 0 402718720 -0.1236021444 -0.1161463782 0.0086822463 235 1311867726.4452810287 0.1263711900 0.0495477991 0.1415939182 0.0056494721 0.0562020000 327107221 0 402718720 -0.1237858385 -0.1160670891 0.0088790702 236 1311867726.4774739742 0.1277539879 0.0498791812 0.1415939182 0.0056382651 0.0227130000 327110421 0 402718720 -0.1242404506 -0.1172376201 0.0095122848 237 1311867726.5095689297 0.1274002492 0.0502062743 0.1415939182 0.0056266669 0.0196660000 327113509 0 402718720 -0.1245215684 -0.1167309210 0.0098589584 238 1311867726.5453538895 0.1265416145 0.0505270110 0.1415939182 0.0056149091 0.0200300000 327116765 0 402718720 -0.1244719476 -0.1158896089 0.0101479171 239 1311867726.5773959160 0.1271801293 0.0508477354 0.1415939182 0.0056108891 0.0214230000 327119909 0 402718720 -0.1245595068 -0.1168173477 0.0099010020 240 1311867726.6093170643 0.1275544167 0.0511673466 0.1415939182 0.0056013450 0.0197340000 327123053 0 402718720 -0.1252399236 -0.1168227196 0.0103183333 241 1311867726.6452519894 0.1253848225 0.0514753029 0.1415939182 0.0055918429 0.0200390000 327126309 0 402718720 -0.1250904500 -0.1147572175 0.0107401321 242 1311867726.6773920059 0.1250987351 0.0517795320 0.1415939182 0.0055803526 0.0228460000 327129453 0 402718720 -0.1249831989 -0.1147034019 0.0103497133 243 1311867726.7095000744 0.1250502765 0.0520810577 0.1415939182 0.0055688476 0.0209580000 327132597 0 402718720 -0.1251326650 -0.1146437153 0.0101474868 244 1311867726.7453930378 0.1255769581 0.0523822704 0.1415939182 0.0055589091 0.0204340000 327135853 0 402718720 -0.1254975945 -0.1151316538 0.0115374057 245 1311867726.7774538994 0.1254606694 0.0526805495 0.1415939182 0.0055483537 0.0219420000 327138997 0 402718720 -0.1255738884 -0.1151811928 0.0109178247 246 1311867726.8095800877 0.1251512915 0.0529751461 0.1415939182 0.0055370717 0.0201450000 327142141 0 402718720 -0.1250077933 -0.1151836365 0.0100767445 247 1311867726.8453249931 0.1257956922 0.0532699661 0.1415939182 0.0055284649 0.0173190000 327145397 0 402718720 -0.1251406670 -0.1156579480 0.0106935054 248 1311867726.8773889542 0.1278504580 0.0535706939 0.1415939182 0.0055232725 0.0204600000 327148541 0 402718720 -0.1252323687 -0.1178625077 0.0103732171 249 1311867726.9094569683 0.1264910400 0.0538635467 0.1415939182 0.0055127503 0.0188980000 327151629 0 402718720 -0.1247756258 -0.1164382622 0.0099248132 250 1311867726.9454600811 0.1257103980 0.0541509341 0.1415939182 0.0055098739 0.0473390000 327154941 0 402718720 -0.1246188581 -0.1157689467 0.0105858892 251 1311867726.9773380756 0.1248045042 0.0544324224 0.1415939182 0.0054995701 0.0227070000 327158085 0 402718720 -0.1246248335 -0.1147773564 0.0103391390 252 1311867727.0096790791 0.1248259321 0.0547117617 0.1415939182 0.0054888705 0.0199740000 327161173 0 402718720 -0.1242946237 -0.1148473844 0.0102415793 253 1311867727.0456500053 0.1240021363 0.0549856367 0.1415939182 0.0054789004 0.0199590000 327164429 0 402718720 -0.1241468862 -0.1140706390 0.0106252395 254 1311867727.0772669315 0.1238371432 0.0552567056 0.1415939182 0.0054682296 0.0210070000 327167629 0 402718720 -0.1238954291 -0.1140094250 0.0102997897 255 1311867727.1094319820 0.1230344549 0.0555225007 0.1415939182 0.0054592716 0.0192630000 327170717 0 402718720 -0.1236992478 -0.1131711304 0.0104507413 256 1311867727.1452639103 0.1228486821 0.0557854936 0.1415939182 0.0054487436 0.0184040000 327173861 0 402718720 -0.1233107224 -0.1130046844 0.0103732115 257 1311867727.1773788929 0.1232575178 0.0560480307 0.1415939182 0.0054382643 0.0214870000 327203685 0 402718720 -0.1234065965 -0.1133409590 0.0092495894 258 1311867727.2096951008 0.1240120828 0.0563114572 0.1415939182 0.0054343468 0.0202190000 327257973 0 402718720 -0.1224341393 -0.1140258387 0.0078050438 259 1311867727.2453041077 0.1234603077 0.0565707192 0.1415939182 0.0054252646 0.0193350000 327261173 0 402718720 -0.1223202646 -0.1132302582 0.0093051279 260 1311867727.2773349285 0.1229777336 0.0568261308 0.1415939182 0.0054156518 0.0202620000 327264373 0 402718720 -0.1218274608 -0.1128229275 0.0083415182 261 1311867727.3093569279 0.1227078438 0.0570785512 0.1415939182 0.0054067076 0.0179120000 327267461 0 402718720 -0.1216045469 -0.1123775914 0.0091515547 262 1311867727.3453900814 0.1215978935 0.0573248082 0.1415939182 0.0053990928 0.0169220000 327270773 0 402718720 -0.1211419404 -0.1113526523 0.0100573171 263 1311867727.3774650097 0.1223841012 0.0575721819 0.1415939182 0.0053959731 0.0189960000 327273805 0 402718720 -0.1204591617 -0.1120294109 0.0079271030 264 1311867727.4095671177 0.1219176725 0.0578159149 0.1415939182 0.0053906382 0.0153580000 327276893 0 402718720 -0.1200150773 -0.1112466231 0.0075745927 265 1311867727.4455111027 0.1212079599 0.0580551301 0.1415939182 0.0053848838 0.0375750000 327280205 0 402718720 -0.1194699556 -0.1105510890 0.0079144137 266 1311867727.4774019718 0.1224275529 0.0582971317 0.1415939182 0.0053764004 0.0264670000 327283349 0 402718720 -0.1188260168 -0.1117666364 0.0054317238 267 1311867727.5093801022 0.1207967699 0.0585312128 0.1415939182 0.0053668612 0.0161980000 327286437 0 402718720 -0.1182163134 -0.1099871397 0.0060149943 268 1311867727.5455400944 0.1205229461 0.0587625252 0.1415939182 0.0053656604 0.0145890000 327289693 0 402718720 -0.1181554645 -0.1093812361 0.0074262130 269 1311867727.5773611069 0.1193896979 0.0589879050 0.1415939182 0.0053572058 0.0164190000 327292837 0 402718720 -0.1176500097 -0.1084912047 0.0074372408 270 1311867727.6094770432 0.1191742793 0.0592108175 0.1415939182 0.0053491214 0.0179350000 327295981 0 402718720 -0.1172548458 -0.1084868014 0.0066474141 271 1311867727.6453289986 0.1186118796 0.0594300096 0.1415939182 0.0053430254 0.0207570000 327299237 0 402718720 -0.1170917600 -0.1083357707 0.0064369049 272 1311867727.6773209572 0.1186895818 0.0596478757 0.1415939182 0.0053332541 0.0196510000 327302269 0 402718720 -0.1168553457 -0.1087220758 0.0062169428 273 1311867727.7094900608 0.1207513064 0.0598716978 0.1415939182 0.0053255883 0.0146440000 327305357 0 402718720 -0.1174986735 -0.1109258905 0.0056404714 274 1311867727.7455639839 0.1193967909 0.0600889427 0.1415939182 0.0053185762 0.0152320000 327308613 0 402718720 -0.1175248325 -0.1096616462 0.0072275163 275 1311867727.7773749828 0.1223797277 0.0603154546 0.1415939182 0.0053132635 0.0249940000 327311757 0 402718720 -0.1175126880 -0.1129802838 0.0057873484 276 1311867727.8096098900 0.1222241148 0.0605397613 0.1415939182 0.0053037964 0.0181950000 327314901 0 402718720 -0.1173588261 -0.1127663925 0.0051760380 277 1311867727.8454129696 0.1229182705 0.0607649545 0.1415939182 0.0052946066 0.0185160000 327318157 0 402718720 -0.1175062358 -0.1132899150 0.0055532823 278 1311867727.8773849010 0.1231684908 0.0609894277 0.1415939182 0.0052850690 0.0205230000 327321357 0 402718720 -0.1177994162 -0.1131518930 0.0049641207 279 1311867727.9093821049 0.1253982782 0.0612202838 0.1415939182 0.0052781756 0.0197970000 327324501 0 402718720 -0.1177196354 -0.1152803376 0.0043093446 280 1311867727.9453790188 0.1254693121 0.0614497446 0.1415939182 0.0052690177 0.0189480000 327327701 0 402718720 -0.1173250079 -0.1151404604 0.0047453246 281 1311867727.9773490429 0.1230662167 0.0616690203 0.1415939182 0.0052611114 0.0524840000 327330901 0 402718720 -0.1165073067 -0.1125635877 0.0042501725 282 1311867728.0096199512 0.1215712428 0.0618814395 0.1415939182 0.0052580740 0.0202850000 327333989 0 402718720 -0.1160937399 -0.1111717150 0.0038967056 283 1311867728.0455679893 0.1218745783 0.0620934294 0.1415939182 0.0052489638 0.0194060000 327337245 0 402718720 -0.1156041026 -0.1113131121 0.0031673284 284 1311867728.0775840282 0.1221017689 0.0623047264 0.1415939182 0.0052401604 0.0205560000 327340445 0 402718720 -0.1152751073 -0.1114661545 0.0027618816 285 1311867728.1093900204 0.1238442883 0.0625206547 0.1415939182 0.0052345092 0.0193630000 327343533 0 402718720 -0.1153633147 -0.1127005219 0.0025352398 286 1311867728.1453619003 0.1234373748 0.0627336502 0.1415939182 0.0052260687 0.0186290000 327346789 0 402718720 -0.1144507974 -0.1122966558 0.0017153560 287 1311867728.1773409843 0.1224185526 0.0629416115 0.1415939182 0.0052180314 0.0210520000 327349989 0 402718720 -0.1141874343 -0.1110529453 0.0013704731 288 1311867728.2095170021 0.1229169592 0.0631498592 0.1415939182 0.0052094506 0.0199260000 327353077 0 402718720 -0.1138563827 -0.1114106253 0.0010135163 289 1311867728.2453820705 0.1232553124 0.0633578366 0.1415939182 0.0052004746 0.0169550000 327356333 0 402718720 -0.1136632636 -0.1114366353 0.0011569321 290 1311867728.2773799896 0.1231776997 0.0635641120 0.1415939182 0.0051917996 0.0196410000 327359533 0 402718720 -0.1133653224 -0.1112314612 0.0011489097 291 1311867728.3094980717 0.1242996305 0.0637728251 0.1415939182 0.0051837026 0.0187490000 327362621 0 402718720 -0.1129873022 -0.1124103516 0.0001544447 292 1311867728.3455080986 0.1221400350 0.0639727128 0.1415939182 0.0051830170 0.0186490000 327365877 0 402718720 -0.1125173569 -0.1103967801 0.0002994089 293 1311867728.3773488998 0.1219385490 0.0641705484 0.1415939182 0.0051867432 0.0173540000 327369077 0 402718720 -0.1123102382 -0.1100245044 -0.0000911447 294 1311867728.4095909595 0.1216931045 0.0643662034 0.1415939182 0.0051871975 0.0191910000 327372165 0 402718720 -0.1122477576 -0.1092709005 -0.0001337419 295 1311867728.4456090927 0.1228718907 0.0645645277 0.1415939182 0.0051841444 0.0192970000 327375421 0 402718720 -0.1121178716 -0.1103453711 -0.0003165231 296 1311867728.4774570465 0.1240177378 0.0647653832 0.1415939182 0.0051803721 0.0212930000 327378565 0 402718720 -0.1117369235 -0.1117701381 -0.0015569000 297 1311867728.5095710754 0.1252696663 0.0649691013 0.1415939182 0.0051750036 0.0465180000 327381709 0 402718720 -0.1117574722 -0.1131391302 -0.0011748766 298 1311867728.5455050468 0.1243710294 0.0651684366 0.1415939182 0.0051664383 0.0209520000 327384965 0 402718720 -0.1114115566 -0.1122098491 -0.0023436774 299 1311867728.5774528980 0.1237112135 0.0653642319 0.1415939182 0.0051582053 0.0199430000 327388165 0 402718720 -0.1115075052 -0.1113579422 -0.0017759629 300 1311867728.6095349789 0.1247654632 0.0655622360 0.1415939182 0.0051502665 0.0187430000 327391253 0 402718720 -0.1113482714 -0.1125138551 -0.0022545517 301 1311867728.6454720497 0.1243425608 0.0657575195 0.1415939182 0.0051421541 0.0195800000 327394509 0 402718720 -0.1109366193 -0.1120369211 -0.0028684696 302 1311867728.6776139736 0.1241231635 0.0659507832 0.1415939182 0.0051340446 0.0198530000 327397653 0 402718720 -0.1109772027 -0.1116065532 -0.0024113369 303 1311867728.7094600201 0.1244384125 0.0661438117 0.1415939182 0.0051347489 0.0196040000 327400797 0 402718720 -0.1108627841 -0.1122840717 -0.0027244864 304 1311867728.7454140186 0.1254680157 0.0663389571 0.1415939182 0.0051267088 0.0185420000 327404053 0 402718720 -0.1108361036 -0.1132646054 -0.0036280141 305 1311867728.7775039673 0.1245731786 0.0665298889 0.1415939182 0.0051203379 0.0198140000 327407253 0 402718720 -0.1106061786 -0.1123330370 -0.0032078191 306 1311867728.8095550537 0.1243442670 0.0667188248 0.1415939182 0.0051122119 0.0202730000 327410341 0 402718720 -0.1104140207 -0.1121696085 -0.0032459060 307 1311867728.8454689980 0.1274430156 0.0669166235 0.1415939182 0.0051063974 0.0196040000 327413597 0 402718720 -0.1103167385 -0.1152960956 -0.0045933956 308 1311867728.8774468899 0.1257365346 0.0671075972 0.1415939182 0.0050991838 0.0193670000 327416797 0 402718720 -0.1099434942 -0.1134706140 -0.0047577717 309 1311867728.9095330238 0.1276832968 0.0673036351 0.1415939182 0.0050925261 0.0204390000 327419885 0 402718720 -0.1097754687 -0.1155534983 -0.0050035180 310 1311867728.9456429482 0.1242117658 0.0674872097 0.1415939182 0.0050901956 0.0206470000 327423141 0 402718720 -0.1091855690 -0.1117470935 -0.0051798108 311 1311867728.9774780273 0.1237930804 0.0676682575 0.1415939182 0.0050875040 0.0198800000 327426341 0 402718720 -0.1092076898 -0.1111636460 -0.0041139107 312 1311867729.0094010830 0.1253794134 0.0678532292 0.1415939182 0.0050924631 0.0190620000 327429429 0 402718720 -0.1086765602 -0.1129205152 -0.0062316633 313 1311867729.0454490185 0.1258419305 0.0680384966 0.1415939182 0.0050872263 0.0455420000 327432685 0 402718720 -0.1082954630 -0.1133100763 -0.0068055983 314 1311867729.0774519444 0.1282254457 0.0682301748 0.1415939182 0.0050832835 0.0210090000 327435885 0 402718720 -0.1082774177 -0.1157601476 -0.0068367226 315 1311867729.1096370220 0.1259865314 0.0684135283 0.1415939182 0.0050913703 0.0193240000 327438973 0 402718720 -0.1080832183 -0.1134269238 -0.0075732856 316 1311867729.1455519199 0.1265436262 0.0685974843 0.1415939182 0.0050850213 0.0192640000 327442229 0 402718720 -0.1084636748 -0.1138073131 -0.0077267098 317 1311867729.1775870323 0.1251432002 0.0687758619 0.1415939182 0.0051041594 0.0207860000 327445429 0 402718720 -0.1087679937 -0.1122909784 -0.0066503030 318 1311867729.2097380161 0.1249128655 0.0689523934 0.1415939182 0.0051133848 0.0185780000 327448517 0 402718720 -0.1088458225 -0.1123275310 -0.0065701031 319 1311867729.2454650402 0.1242008284 0.0691255860 0.1415939182 0.0051571262 0.0207080000 327451773 0 402718720 -0.1091317236 -0.1110047549 -0.0045568519 320 1311867729.2776589394 0.1238582954 0.0692966257 0.1415939182 0.0051506132 0.0209850000 327454973 0 402718720 -0.1092557088 -0.1107402444 -0.0038547195 321 1311867729.3094971180 0.1231927723 0.0694645265 0.1415939182 0.0051492355 0.0199750000 327458117 0 402718720 -0.1086105108 -0.1104291528 -0.0042775562 322 1311867729.3456869125 0.1219090074 0.0696273975 0.1415939182 0.0051462235 0.0192500000 327461317 0 402718720 -0.1082898527 -0.1093085781 -0.0044403621 323 1311867729.3774700165 0.1231744289 0.0697931778 0.1415939182 0.0051633524 0.0203660000 327464517 0 402718720 -0.1078381017 -0.1102738380 -0.0042165709 324 1311867729.4097099304 0.1218224317 0.0699537619 0.1415939182 0.0051573032 0.0206560000 327467605 0 402718720 -0.1067836806 -0.1090551987 -0.0047667185 325 1311867729.4455790520 0.1211545542 0.0701113028 0.1415939182 0.0051531288 0.0185300000 327470861 0 402718720 -0.1064763442 -0.1080475375 -0.0036508339 326 1311867729.4778299332 0.1217834279 0.0702698063 0.1415939182 0.0051617942 0.0211300000 327474061 0 402718720 -0.1062155887 -0.1091211885 -0.0042822775 327 1311867729.5097289085 0.1194212809 0.0704201166 0.1415939182 0.0051585216 0.0240910000 327477205 0 402718720 -0.1057804003 -0.1066580340 -0.0038027219 328 1311867729.5456240177 0.1190093458 0.0705682545 0.1415939182 0.0051510846 0.0536840000 327480405 0 402718720 -0.1051867306 -0.1066455543 -0.0044599012 329 1311867729.5778779984 0.1158385649 0.0707058542 0.1415939182 0.0051602615 0.0222770000 327483549 0 402718720 -0.1048282757 -0.1034761816 -0.0067475527 330 1311867729.6095120907 0.1187346652 0.0708513961 0.1415939182 0.0051704609 0.0188810000 327486693 0 402718720 -0.1041245908 -0.1073490530 -0.0049995705 331 1311867729.6454730034 0.1170599535 0.0709909990 0.1415939182 0.0051640943 0.0196170000 327489949 0 402718720 -0.1040875092 -0.1058303192 -0.0050016711 332 1311867729.6776039600 0.1164779738 0.0711280079 0.1415939182 0.0051568516 0.0226980000 327493093 0 402718720 -0.1041152552 -0.1054170802 -0.0042687301 333 1311867729.7095260620 0.1153926402 0.0712609347 0.1415939182 0.0051501240 0.0177580000 327496125 0 402718720 -0.1036561653 -0.1045822948 -0.0052815392 334 1311867729.7457098961 0.1163304225 0.0713958733 0.1415939182 0.0051430457 0.0185720000 327499437 0 402718720 -0.1034502387 -0.1058511660 -0.0042102481 335 1311867729.7775330544 0.1133215576 0.0715210246 0.1415939182 0.0051420951 0.0198960000 327502469 0 402718720 -0.1030021831 -0.1028043777 -0.0037448115 336 1311867729.8096089363 0.1138690114 0.0716470603 0.1415939182 0.0051356475 0.0190870000 327505613 0 402718720 -0.1028363407 -0.1034711748 -0.0047847186 337 1311867729.8455319405 0.1134495437 0.0717711033 0.1415939182 0.0051285889 0.0191550000 327508813 0 402718720 -0.1020864621 -0.1032941639 -0.0058147390 338 1311867729.8776299953 0.1126263216 0.0718919767 0.1415939182 0.0051234304 0.0248280000 327511957 0 402718720 -0.1022989303 -0.1022333503 -0.0045305896 339 1311867729.9097530842 0.1126356870 0.0720121646 0.1415939182 0.0051166068 0.0198520000 327515101 0 402718720 -0.1018951461 -0.1025671959 -0.0053831632 340 1311867729.9454579353 0.1125439554 0.0721313758 0.1415939182 0.0051092380 0.0190730000 327518301 0 402718720 -0.1015640274 -0.1024475396 -0.0067356904 341 1311867729.9775550365 0.1113643572 0.0722464285 0.1415939182 0.0051032986 0.0197410000 327521501 0 402718720 -0.1013538018 -0.1012533531 -0.0046927962 342 1311867730.0098500252 0.1117815673 0.0723620283 0.1415939182 0.0050962529 0.0184950000 327524589 0 402718720 -0.1017633602 -0.1014207453 -0.0042010914 343 1311867730.0455420017 0.1099913269 0.0724717348 0.1415939182 0.0050891846 0.0515240000 327527901 0 402718720 -0.1011049896 -0.0996056125 -0.0058513014 344 1311867730.0778129101 0.1109738350 0.0725836595 0.1415939182 0.0050820494 0.0215500000 327531101 0 402718720 -0.1009140015 -0.1006463692 -0.0056847660 345 1311867730.1098239422 0.1113388836 0.0726959934 0.1415939182 0.0050750762 0.0205940000 327534189 0 402718720 -0.1007034108 -0.1010001972 -0.0054157432 346 1311867730.1454300880 0.1112080365 0.0728072999 0.1415939182 0.0050677627 0.0177040000 327537389 0 402718720 -0.1006294712 -0.1005855054 -0.0059151212 347 1311867730.1775400639 0.1075779274 0.0729075035 0.1415939182 0.0050632535 0.0207200000 327540589 0 402718720 -0.1000513583 -0.0963898003 -0.0073222248 348 1311867730.2094900608 0.1084030569 0.0730095022 0.1415939182 0.0050583049 0.0212590000 327543677 0 402718720 -0.0995244533 -0.0975211933 -0.0066400035 349 1311867730.2456400394 0.1088424996 0.0731121755 0.1415939182 0.0050523367 0.0203760000 327546989 0 402718720 -0.0993516669 -0.0978657529 -0.0074631358 350 1311867730.2777209282 0.1093523279 0.0732157188 0.1415939182 0.0050456954 0.0207560000 327550133 0 402718720 -0.0991815403 -0.0981854647 -0.0081166001 351 1311867730.3096349239 0.1094743088 0.0733190196 0.1415939182 0.0050389856 0.0207280000 327553277 0 402718720 -0.0993734673 -0.0980397463 -0.0065874830 352 1311867730.3455030918 0.1069778651 0.0734146414 0.1415939182 0.0050324438 0.0211160000 327556477 0 402718720 -0.0986862183 -0.0951280966 -0.0083700921 353 1311867730.3779098988 0.1088156849 0.0735149276 0.1415939182 0.0050283538 0.0201810000 327559733 0 402718720 -0.0989115760 -0.0968223065 -0.0080144666 354 1311867730.4096369743 0.1103695408 0.0736190367 0.1415939182 0.0050227181 0.0196500000 327562765 0 402718720 -0.0986843035 -0.0983694270 -0.0087936968 355 1311867730.4455609322 0.1108410135 0.0737238873 0.1415939182 0.0050171690 0.0196860000 327566021 0 402718720 -0.0985452160 -0.0984655172 -0.0082682539 356 1311867730.4776659012 0.1099998876 0.0738257862 0.1415939182 0.0050114535 0.0198750000 327569221 0 402718720 -0.0988520533 -0.0969773233 -0.0074039078 357 1311867730.5096940994 0.1096379459 0.0739261004 0.1415939182 0.0050046061 0.0206000000 327572309 0 402718720 -0.0981157348 -0.0965024680 -0.0080701904 358 1311867730.5457289219 0.1100524068 0.0740270118 0.1415939182 0.0049976296 0.0527530000 327575565 0 402718720 -0.0984140933 -0.0963555425 -0.0071887271 359 1311867730.5776000023 0.1092784032 0.0741252051 0.1415939182 0.0049913565 0.0226680000 327578709 0 402718720 -0.0983606204 -0.0952726975 -0.0062480518 360 1311867730.6094939709 0.1082499996 0.0742199962 0.1415939182 0.0049879987 0.0206360000 327581797 0 402718720 -0.0977225378 -0.0940503404 -0.0078423545 361 1311867730.6456940174 0.1090344787 0.0743164352 0.1415939182 0.0049816426 0.0209830000 327585053 0 402718720 -0.0978523940 -0.0946960822 -0.0068943156 362 1311867730.6776220798 0.1089026928 0.0744119774 0.1415939182 0.0049749334 0.0203000000 327588197 0 402718720 -0.0975296348 -0.0944330022 -0.0071210512 363 1311867730.7097771168 0.1077201366 0.0745037354 0.1415939182 0.0049746694 0.0202370000 327591341 0 402718720 -0.0964618698 -0.0933498368 -0.0085717766 364 1311867730.7456669807 0.1091575548 0.0745989382 0.1415939182 0.0049697269 0.0209720000 327594597 0 402718720 -0.0967347845 -0.0944013745 -0.0082909949 365 1311867730.7776470184 0.1099933758 0.0746959093 0.1415939182 0.0049647847 0.0202130000 327597741 0 402718720 -0.0955872685 -0.0950014293 -0.0106760776 366 1311867730.8097639084 0.1083821356 0.0747879481 0.1415939182 0.0049634303 0.0210860000 327600885 0 402718720 -0.0954920277 -0.0926633626 -0.0081121456 367 1311867730.8457670212 0.1100475863 0.0748840234 0.1415939182 0.0049595208 0.0204340000 327604141 0 402718720 -0.0951659381 -0.0937618911 -0.0094961245 368 1311867730.8774909973 0.1097429320 0.0749787487 0.1415939182 0.0049544492 0.0196550000 327607173 0 402718720 -0.0942322835 -0.0929004401 -0.0110691730 369 1311867730.9097859859 0.1091306955 0.0750713014 0.1415939182 0.0049484392 0.0204470000 327610261 0 402718720 -0.0933989361 -0.0917819440 -0.0110843712 370 1311867730.9455358982 0.1101278961 0.0751660490 0.1415939182 0.0049439274 0.0193790000 327613517 0 402718720 -0.0923920572 -0.0922069922 -0.0136661129 371 1311867730.9775540829 0.1088937670 0.0752569593 0.1415939182 0.0049380064 0.0205410000 327616717 0 402718720 -0.0916251242 -0.0905990675 -0.0127677443 372 1311867731.0096011162 0.1078272313 0.0753445138 0.1415939182 0.0049345206 0.0199540000 327619805 0 402718720 -0.0915386379 -0.0891196057 -0.0118818590 373 1311867731.0456199646 0.1087021902 0.0754339445 0.1415939182 0.0049297073 0.0506500000 327623061 0 402718720 -0.0909050927 -0.0898756012 -0.0125794886 374 1311867731.0775210857 0.1068459824 0.0755179340 0.1415939182 0.0049258351 0.0219110000 327626205 0 402718720 -0.0904398263 -0.0876922011 -0.0113108801 375 1311867731.1096100807 0.1056163087 0.0755981963 0.1415939182 0.0049201563 0.0207200000 327629349 0 402718720 -0.0892927647 -0.0864278376 -0.0117091406 376 1311867731.1456789970 0.1077757031 0.0756837748 0.1415939182 0.0049179526 0.0205520000 327632605 0 402718720 -0.0892632827 -0.0881574005 -0.0132969040 377 1311867731.1777400970 0.1055907384 0.0757631036 0.1415939182 0.0049167440 0.0196210000 327635749 0 402718720 -0.0886577442 -0.0857110545 -0.0120260371 378 1311867731.2096519470 0.1051361188 0.0758408100 0.1415939182 0.0049106408 0.0226410000 327638837 0 402718720 -0.0881149992 -0.0850647166 -0.0117058344 379 1311867731.2455980778 0.1034965068 0.0759137801 0.1415939182 0.0049065593 0.0196220000 327642093 0 402718720 -0.0874234512 -0.0830432847 -0.0114748375 380 1311867731.2775490284 0.1026232541 0.0759840682 0.1415939182 0.0049011223 0.0238130000 327645293 0 402718720 -0.0872480720 -0.0818349570 -0.0105940914 381 1311867731.3097438812 0.1014088914 0.0760508001 0.1415939182 0.0049006207 0.0242860000 327648381 0 402718720 -0.0866077840 -0.0804965198 -0.0101838280 382 1311867731.3457999229 0.0995559171 0.0761123318 0.1415939182 0.0048958681 0.0229820000 327651637 0 402718720 -0.0856971890 -0.0787821934 -0.0104932208 383 1311867731.3777329922 0.0979761481 0.0761694175 0.1415939182 0.0048937235 0.0228140000 327654837 0 402718720 -0.0850951299 -0.0774319321 -0.0101448204 384 1311867731.4096930027 0.0985096544 0.0762275952 0.1415939182 0.0048885667 0.0245830000 327657925 0 402718720 -0.0851267129 -0.0781757608 -0.0099703427 385 1311867731.4455540180 0.0970264599 0.0762816182 0.1415939182 0.0048834281 0.0224680000 327661181 0 402718720 -0.0832927600 -0.0777956769 -0.0095021669 386 1311867731.4776530266 0.0953435451 0.0763310014 0.1415939182 0.0048835740 0.0222280000 327664381 0 402718720 -0.0834591836 -0.0753818080 -0.0108037358 387 1311867731.5096719265 0.0962188467 0.0763823912 0.1415939182 0.0048822669 0.0581550000 327667469 0 402718720 -0.0821689665 -0.0771011785 -0.0113874096 388 1311867731.5457088947 0.0960331485 0.0764330375 0.1415939182 0.0048838223 0.0916630000 339976037 0 402718720 -0.0822424218 -0.0763004720 -0.0121666556 389 1311867731.5777149200 0.1015728340 0.0764976642 0.1415939182 0.0048935164 0.0296340000 343638389 0 402718720 -0.0830572173 -0.0820259154 -0.0127421413 390 1311867731.6097021103 0.1004713178 0.0765591351 0.1415939182 0.0049178062 0.0134380000 346833669 0 402718720 -0.0825126022 -0.0810018852 -0.0121649848 391 1311867731.6456029415 0.0997365639 0.0766184124 0.1415939182 0.0049260821 0.0134410000 346836925 0 402718720 -0.0821443498 -0.0795898139 -0.0119965915 392 1311867731.6776618958 0.0986530483 0.0766746232 0.1415939182 0.0049201592 0.0240080000 346840125 0 402718720 -0.0814980268 -0.0782006085 -0.0121299205 393 1311867731.7099699974 0.0933253169 0.0767169914 0.1415939182 0.0049254334 0.0356140000 346843269 0 402718720 -0.0803536996 -0.0722506866 -0.0109198866 394 1311867731.7457799911 0.0970271155 0.0767685399 0.1415939182 0.0049271717 0.0335320000 346846525 0 402718720 -0.0807437450 -0.0762544125 -0.0112641333 395 1311867731.7777240276 0.0968333259 0.0768193369 0.1415939182 0.0049211154 0.0321290000 346849669 0 402718720 -0.0804054141 -0.0757339373 -0.0121101113 396 1311867731.8099861145 0.0954939723 0.0768664950 0.1415939182 0.0049170626 0.0313360000 346852813 0 402718720 -0.0799708292 -0.0746072829 -0.0102303969 397 1311867731.8457460403 0.0952940732 0.0769129121 0.1415939182 0.0049120573 0.0301820000 346856069 0 402718720 -0.0800950900 -0.0742205977 -0.0106446687 398 1311867731.8775570393 0.0948724970 0.0769580367 0.1415939182 0.0049061884 0.0320320000 346859213 0 402718720 -0.0798007920 -0.0739129260 -0.0108212056 399 1311867731.9097321033 0.0942706242 0.0770014266 0.1415939182 0.0049039155 0.0601040000 346862301 0 402718720 -0.0796560273 -0.0733519942 -0.0107279792 400 1311867731.9456660748 0.0936379284 0.0770430179 0.1415939182 0.0048986039 0.0287780000 346865557 0 402718720 -0.0795225650 -0.0728088841 -0.0105487425 401 1311867731.9777350426 0.0950455070 0.0770879119 0.1415939182 0.0048945280 0.0304850000 346868701 0 402718720 -0.0790029466 -0.0747241080 -0.0125077711 402 1311867732.0095889568 0.0940526873 0.0771301128 0.1415939182 0.0048921680 0.0285630000 346871789 0 402718720 -0.0791185871 -0.0734751970 -0.0109511670 403 1311867732.0458478928 0.0914328620 0.0771656035 0.1415939182 0.0048924532 0.0283640000 346875101 0 402718720 -0.0786759332 -0.0704556853 -0.0098954141 404 1311867732.0776910782 0.0950852036 0.0772099590 0.1415939182 0.0049103588 0.0276500000 346878245 0 402718720 -0.0782746449 -0.0748110041 -0.0126093682 405 1311867732.1098160744 0.0925904810 0.0772479356 0.1415939182 0.0049192194 0.0275850000 346881333 0 402718720 -0.0787756369 -0.0715317205 -0.0098859258 406 1311867732.1455659866 0.0947289914 0.0772909923 0.1415939182 0.0049271466 0.0278640000 346884645 0 402718720 -0.0783648342 -0.0748882294 -0.0113645112 407 1311867732.1777989864 0.0951455384 0.0773348610 0.1415939182 0.0049223281 0.0275010000 346887789 0 402718720 -0.0779243410 -0.0752643347 -0.0134897921 408 1311867732.2096500397 0.0942474753 0.0773763135 0.1415939182 0.0049209196 0.0261520000 346890933 0 402718720 -0.0779476613 -0.0742010921 -0.0116358856 409 1311867732.2458050251 0.0958721191 0.0774215355 0.1415939182 0.0049262669 0.0270490000 346894189 0 402718720 -0.0775962919 -0.0760004297 -0.0144570181 410 1311867732.2778968811 0.0963513851 0.0774677059 0.1415939182 0.0049304298 0.0276990000 346897389 0 402718720 -0.0773122162 -0.0761392713 -0.0146604851 411 1311867732.3097560406 0.0941144675 0.0775082089 0.1415939182 0.0049409798 0.0263000000 346900421 0 402718720 -0.0767416656 -0.0740310848 -0.0125851808 412 1311867732.3456790447 0.0949247554 0.0775504821 0.1415939182 0.0049369555 0.0620210000 346903677 0 402718720 -0.0765740871 -0.0745540187 -0.0147390990 413 1311867732.3777399063 0.0949773788 0.0775926780 0.1415939182 0.0049334296 0.0268560000 346906877 0 402718720 -0.0771762729 -0.0736697018 -0.0155051919 414 1311867732.4096240997 0.0934798196 0.0776310527 0.1415939182 0.0049288421 0.0262490000 346910021 0 402718720 -0.0751958936 -0.0736364424 -0.0131789455 415 1311867732.4456939697 0.0947059691 0.0776721971 0.1415939182 0.0049388888 0.0258120000 346913221 0 402718720 -0.0752463639 -0.0745286122 -0.0146949608 416 1311867732.4777801037 0.0934846476 0.0777102078 0.1415939182 0.0049381508 0.0239110000 346916421 0 402718720 -0.0748000145 -0.0728907138 -0.0147900069 417 1311867732.5097730160 0.0935206562 0.0777481225 0.1415939182 0.0049345440 0.0245820000 346919565 0 402718720 -0.0742299631 -0.0728919059 -0.0146343298 418 1311867732.5458118916 0.0945895761 0.0777884131 0.1415939182 0.0049298730 0.0357370000 346922765 0 402718720 -0.0745391399 -0.0730813220 -0.0171647426 419 1311867732.5782780647 0.0956166834 0.0778309627 0.1415939182 0.0049250908 0.0253600000 346925909 0 402718720 -0.0736218169 -0.0745614767 -0.0180736855 420 1311867732.6098470688 0.0953722671 0.0778727277 0.1415939182 0.0049199832 0.0250630000 346929109 0 402718720 -0.0729584992 -0.0747621879 -0.0163765494 421 1311867732.6457130909 0.0944801867 0.0779121753 0.1415939182 0.0049175878 0.0244970000 346932309 0 402718720 -0.0724521354 -0.0735240504 -0.0171210784 422 1311867732.6777091026 0.0951463431 0.0779530146 0.1415939182 0.0049136256 0.0248770000 346935509 0 402718720 -0.0728567913 -0.0730947182 -0.0202581454 423 1311867732.7097430229 0.0949760675 0.0779932582 0.1415939182 0.0049083253 0.0243410000 346938597 0 402718720 -0.0727746263 -0.0728761032 -0.0181783717 424 1311867732.7456200123 0.0960486233 0.0780358416 0.1415939182 0.0049048666 0.0241180000 346941853 0 402718720 -0.0724913031 -0.0744316131 -0.0175523944 425 1311867732.7777669430 0.0957633853 0.0780775535 0.1415939182 0.0049015108 0.0472240000 346944997 0 402718720 -0.0729989931 -0.0727421865 -0.0204749592 426 1311867732.8099739552 0.0958226770 0.0781192087 0.1415939182 0.0048963152 0.0239180000 346948141 0 402718720 -0.0721855164 -0.0734709278 -0.0193429235 427 1311867732.8458719254 0.0970792249 0.0781636116 0.1415939182 0.0048922769 0.0237910000 346951397 0 402718720 -0.0724535584 -0.0747193694 -0.0192007236 428 1311867732.8777840137 0.0967034325 0.0782069289 0.1415939182 0.0048913038 0.0237880000 346954541 0 402718720 -0.0735211670 -0.0726430789 -0.0210547112 429 1311867732.9097430706 0.0971392989 0.0782510603 0.1415939182 0.0048863296 0.0235760000 346957685 0 402718720 -0.0735624582 -0.0723887160 -0.0228021760 430 1311867732.9457380772 0.0957486182 0.0782917523 0.1415939182 0.0048810646 0.0232950000 346960941 0 402718720 -0.0725414306 -0.0717425495 -0.0191928465 431 1311867732.9777500629 0.0969393998 0.0783350183 0.1415939182 0.0048765044 0.0240050000 346964085 0 402718720 -0.0732862428 -0.0723630413 -0.0202067234 432 1311867733.0097920895 0.0975367352 0.0783794667 0.1415939182 0.0048716095 0.0230800000 346967285 0 402718720 -0.0728541389 -0.0731435120 -0.0213700570 433 1311867733.0458159447 0.0950290114 0.0784179183 0.1415939182 0.0048682800 0.0231070000 346970485 0 402718720 -0.0714981556 -0.0715975240 -0.0163107440 434 1311867733.0778040886 0.0953064188 0.0784568319 0.1415939182 0.0048627452 0.0233890000 346973685 0 402718720 -0.0718142092 -0.0713970736 -0.0179866962 435 1311867733.1097800732 0.0978668332 0.0785014526 0.1415939182 0.0048579932 0.0231340000 346976773 0 402718720 -0.0734357163 -0.0723563656 -0.0218877234 436 1311867733.1458189487 0.0957086235 0.0785409186 0.1415939182 0.0048534495 0.0228430000 346979973 0 402718720 -0.0719231218 -0.0718935654 -0.0154999308 437 1311867733.1777689457 0.0964995846 0.0785820139 0.1415939182 0.0048484392 0.1081940000 359284341 0 402718720 -0.0723938569 -0.0721446425 -0.0177921522 438 1311867733.2097411156 0.0967944637 0.0786235949 0.1415939182 0.0048470019 0.0176170000 362946637 0 402718720 -0.0735101551 -0.0704531968 -0.0212781299 439 1311867733.2458369732 0.0954626650 0.0786619527 0.1415939182 0.0048426314 0.0442480000 366142085 0 402718720 -0.0728441551 -0.0691571608 -0.0190642010 440 1311867733.2777390480 0.0952875391 0.0786997381 0.1415939182 0.0048372841 0.0165270000 366145285 0 402718720 -0.0727730915 -0.0687566623 -0.0183612313 441 1311867733.3098380566 0.0951666236 0.0787370780 0.1415939182 0.0048330801 0.0221910000 366148373 0 402718720 -0.0723253563 -0.0686323121 -0.0188824311 442 1311867733.3457000256 0.0924987420 0.0787682130 0.1415939182 0.0048296599 0.0409730000 366151629 0 402718720 -0.0709226727 -0.0664256886 -0.0151216313 443 1311867733.3779110909 0.0946907252 0.0788041554 0.1415939182 0.0048257006 0.0316420000 366154773 0 402718720 -0.0712282732 -0.0688854977 -0.0163572356 444 1311867733.4098379612 0.0950557739 0.0788407582 0.1415939182 0.0048219224 0.0320210000 366157917 0 402718720 -0.0710555241 -0.0685394406 -0.0197019614 445 1311867733.4457030296 0.0956683978 0.0788785731 0.1415939182 0.0048179290 0.0297230000 366161117 0 402718720 -0.0710923821 -0.0689934567 -0.0196105223 446 1311867733.4778809547 0.0958250761 0.0789165697 0.1415939182 0.0048131391 0.0290190000 366164261 0 402718720 -0.0705096051 -0.0696747974 -0.0191035438 447 1311867733.5098519325 0.0964080542 0.0789557006 0.1415939182 0.0048087273 0.0272720000 366167237 0 402718720 -0.0707209483 -0.0693513379 -0.0216237810 448 1311867733.5457990170 0.0961637273 0.0789941113 0.1415939182 0.0048083120 0.0295140000 366170493 0 402718720 -0.0703967437 -0.0693673417 -0.0205526128 449 1311867733.5777399540 0.0962163210 0.0790324682 0.1415939182 0.0048046503 0.0294950000 366173637 0 402718720 -0.0699298903 -0.0702482387 -0.0173884016 450 1311867733.6138761044 0.0960661545 0.0790703208 0.1415939182 0.0048305076 0.0280960000 366176949 0 402718720 -0.0702371746 -0.0697584376 -0.0187245402 451 1311867733.6456980705 0.0958001092 0.0791074157 0.1415939182 0.0048636355 0.0689250000 366179981 0 402718720 -0.0699850991 -0.0688179508 -0.0190147962 452 1311867733.6778860092 0.0962024406 0.0791452365 0.1415939182 0.0048583189 0.0301500000 366183181 0 402718720 -0.0702067688 -0.0691310465 -0.0183636639 453 1311867733.7137401104 0.0956228673 0.0791816110 0.1415939182 0.0048542542 0.0303060000 366186381 0 402718720 -0.0697824061 -0.0685682818 -0.0166293755 454 1311867733.7458200455 0.0957452208 0.0792180947 0.1415939182 0.0049023232 0.0293570000 366189525 0 402718720 -0.0692141876 -0.0693012327 -0.0165517926 455 1311867733.7778670788 0.0961417407 0.0792552895 0.1415939182 0.0049355777 0.0267250000 366192613 0 402718720 -0.0690283179 -0.0696711317 -0.0166702345 456 1311867733.8138499260 0.0943355858 0.0792883604 0.1415939182 0.0049334896 0.0285120000 366195869 0 402718720 -0.0687293485 -0.0675522462 -0.0124291610 457 1311867733.8457639217 0.0958877727 0.0793246829 0.1415939182 0.0049300081 0.0265500000 366198901 0 402718720 -0.0686591640 -0.0692915097 -0.0152386855 458 1311867733.8778181076 0.0954161510 0.0793598171 0.1415939182 0.0049298373 0.0284260000 366201989 0 402718720 -0.0686461776 -0.0681476295 -0.0152700655 459 1311867733.9139699936 0.0958637074 0.0793957733 0.1415939182 0.0049252441 0.0267850000 366205245 0 402718720 -0.0676455423 -0.0698022693 -0.0131616490 460 1311867733.9457590580 0.0968762562 0.0794337744 0.1415939182 0.0049217938 0.0272990000 366208333 0 402718720 -0.0665391833 -0.0723328590 -0.0139854811 461 1311867733.9777710438 0.0976878107 0.0794733710 0.1415939182 0.0049167577 0.0284280000 366211477 0 402718720 -0.0661940500 -0.0738653392 -0.0146042164 462 1311867734.0139269829 0.0972553715 0.0795118602 0.1415939182 0.0049162243 0.0267890000 366214733 0 402718720 -0.0659828261 -0.0734133869 -0.0130788349 463 1311867734.0458869934 0.0969257504 0.0795494711 0.1415939182 0.0049142876 0.0271200000 366217877 0 402718720 -0.0658938512 -0.0728111416 -0.0151898367 464 1311867734.0779299736 0.0968435705 0.0795867429 0.1415939182 0.0049093252 0.0614840000 366221077 0 402718720 -0.0649311095 -0.0736234188 -0.0155767417 465 1311867734.1137819290 0.0967993215 0.0796237592 0.1415939182 0.0049062340 0.0260480000 366224333 0 402718720 -0.0651867613 -0.0735412538 -0.0121970028 466 1311867734.1458649635 0.0979295298 0.0796630420 0.1415939182 0.0049063080 0.0258680000 366227421 0 402718720 -0.0652117804 -0.0748623163 -0.0156749673 467 1311867734.1778779030 0.0965929031 0.0796992944 0.1415939182 0.0049011214 0.1063450000 378537145 0 402718720 -0.0637881905 -0.0737890378 -0.0164267253 468 1311867734.2139220238 0.0945795104 0.0797310897 0.1415939182 0.0049343184 0.0206920000 382199665 0 402718720 -0.0566943735 -0.0787329078 -0.0080624325 469 1311867734.2458229065 0.0942650512 0.0797620789 0.1415939182 0.0049305396 0.0331260000 385394945 0 402718720 -0.0556543320 -0.0792986155 -0.0097892806 470 1311867734.2779779434 0.0950021073 0.0797945045 0.1415939182 0.0049302468 0.0355820000 385398089 0 402718720 -0.0550906509 -0.0804678947 -0.0119885691 471 1311867734.3137800694 0.0952791795 0.0798273807 0.1415939182 0.0049259362 0.0233140000 385401289 0 402718720 -0.0558669232 -0.0800810978 -0.0099750943 472 1311867734.3457100391 0.0947486013 0.0798589935 0.1415939182 0.0049212579 0.0349810000 385404377 0 402718720 -0.0547834039 -0.0803648084 -0.0106358230 473 1311867734.3778929710 0.0933282152 0.0798874696 0.1415939182 0.0049183736 0.0305570000 385407521 0 402718720 -0.0535896420 -0.0792350769 -0.0122223794 474 1311867734.4139640331 0.0957125798 0.0799208559 0.1415939182 0.0049156094 0.0358120000 385410833 0 402718720 -0.0533244982 -0.0827307552 -0.0100964569 475 1311867734.4458029270 0.0952455550 0.0799531185 0.1415939182 0.0049105172 0.0343330000 385413921 0 402718720 -0.0524081849 -0.0829587728 -0.0088691134 476 1311867734.4778079987 0.0962115824 0.0799872749 0.1415939182 0.0049059564 0.0693230000 385417121 0 402718720 -0.0539763011 -0.0827371404 -0.0112067796 477 1311867734.5140230656 0.0931594968 0.0800148896 0.1415939182 0.0049029004 0.0320220000 385420377 0 402718720 -0.0531705022 -0.0794619769 -0.0100141279 478 1311867734.5457649231 0.0944088623 0.0800450025 0.1415939182 0.0049015515 0.0339850000 385423465 0 402718720 -0.0521348342 -0.0821321532 -0.0084794480 479 1311867734.5780689716 0.0932518095 0.0800725741 0.1415939182 0.0049016562 0.0298010000 385426609 0 402718720 -0.0521664843 -0.0799960718 -0.0096828919 480 1311867734.6139369011 0.0955215991 0.0801047596 0.1415939182 0.0048997161 0.0337030000 385429921 0 402718720 -0.0532547049 -0.0820569992 -0.0102937603 481 1311867734.6459009647 0.0952302888 0.0801362056 0.1415939182 0.0048946973 0.0333800000 385433009 0 402718720 -0.0529890247 -0.0820590332 -0.0081121596 482 1311867734.6778221130 0.0957989618 0.0801687010 0.1415939182 0.0048923173 0.0317100000 385436097 0 402718720 -0.0525244959 -0.0830102786 -0.0081333760 483 1311867734.7139430046 0.0949675515 0.0801993404 0.1415939182 0.0048900771 0.0307900000 385439297 0 402718720 -0.0525934994 -0.0818096325 -0.0083313361 484 1311867734.7457649708 0.0936488509 0.0802271287 0.1415939182 0.0048890303 0.0291420000 385442497 0 402718720 -0.0524802022 -0.0797940493 -0.0085473191 485 1311867734.7778189182 0.0943511054 0.0802562503 0.1415939182 0.0048844298 0.0292390000 385445641 0 402718720 -0.0522443019 -0.0807344317 -0.0087667229 486 1311867734.8139710426 0.0944443643 0.0802854439 0.1415939182 0.0048810043 0.0301710000 385448841 0 402718720 -0.0512467846 -0.0813377351 -0.0102072358 487 1311867734.8457450867 0.0943467617 0.0803143172 0.1415939182 0.0048765093 0.0285190000 385451985 0 402718720 -0.0511695556 -0.0810877830 -0.0101092076 488 1311867734.8778049946 0.0940704495 0.0803425060 0.1415939182 0.0048723268 0.0588970000 385455185 0 402718720 -0.0510662086 -0.0807282776 -0.0077249217 489 1311867734.9138820171 0.0938538834 0.0803701367 0.1415939182 0.0048678323 0.0295920000 385458497 0 402718720 -0.0507059656 -0.0808766410 -0.0086985882 490 1311867734.9458339214 0.0938644037 0.0803976760 0.1415939182 0.0048630019 0.0280420000 385461529 0 402718720 -0.0500369631 -0.0809566677 -0.0088244434 491 1311867734.9778809547 0.0943665206 0.0804261258 0.1415939182 0.0048593395 0.0291360000 385464561 0 402718720 -0.0494141169 -0.0824515894 -0.0070815305 492 1311867735.0137929916 0.0946915224 0.0804551205 0.1415939182 0.0048548991 0.0299170000 385467817 0 402718720 -0.0498601831 -0.0825826153 -0.0090020401 493 1311867735.0459361076 0.0934716463 0.0804815232 0.1415939182 0.0048530262 0.0269100000 385470849 0 402718720 -0.0497033969 -0.0809471086 -0.0100330431 494 1311867735.0778191090 0.0942869931 0.0805094695 0.1415939182 0.0048498798 0.0280300000 385474049 0 402718720 -0.0493787043 -0.0825987607 -0.0076215547 495 1311867735.1139230728 0.0951316357 0.0805390092 0.1415939182 0.0048495847 0.0298010000 385477249 0 402718720 -0.0491075665 -0.0839641616 -0.0085648019 496 1311867735.1458799839 0.0947656780 0.0805676920 0.1415939182 0.0048468150 0.0285810000 385480393 0 402718720 -0.0497407913 -0.0828350559 -0.0085784905 497 1311867735.1779301167 0.0933869183 0.0805934852 0.1415939182 0.0048430340 0.0271420000 385483593 0 402718720 -0.0485160910 -0.0820897818 -0.0058394698 498 1311867735.2137629986 0.0937266126 0.0806198570 0.1415939182 0.0048390206 0.0281860000 385486793 0 402718720 -0.0484647751 -0.0825348496 -0.0084846234 499 1311867735.2458269596 0.0938493311 0.0806463689 0.1415939182 0.0048342924 0.0265690000 385489937 0 402718720 -0.0486770235 -0.0822770521 -0.0092338733 500 1311867735.2779319286 0.0940944552 0.0806732651 0.1415939182 0.0048327402 0.1173550000 397822445 0 402718720 -0.0484579988 -0.0834130347 -0.0067090034 501 1311867735.3140900135 0.0992031395 0.0807102509 0.1415939182 0.0048407183 0.0144350000 401484853 0 402718720 -0.0518585742 -0.0867483988 -0.0123375123 502 1311867735.3461539745 0.0978863463 0.0807444662 0.1415939182 0.0048373251 0.0412200000 404680133 0 402718720 -0.0516211540 -0.0847447142 -0.0111942478 503 1311867735.3780119419 0.0964282751 0.0807756467 0.1415939182 0.0048411878 0.0374690000 404683333 0 402718720 -0.0515616350 -0.0830375478 -0.0115430010 504 1311867735.4139440060 0.0980086178 0.0808098391 0.1415939182 0.0048446709 0.0289870000 404686477 0 402718720 -0.0511915945 -0.0854372606 -0.0122336568 505 1311867735.4463770390 0.0984256119 0.0808447219 0.1415939182 0.0048406306 0.0135160000 404689677 0 402718720 -0.0508051664 -0.0863962695 -0.0109532857 506 1311867735.4778969288 0.0978265554 0.0808782828 0.1415939182 0.0048360861 0.0339020000 404692821 0 402718720 -0.0505000092 -0.0856775790 -0.0106365951 507 1311867735.5137150288 0.0983471051 0.0809127381 0.1415939182 0.0048319480 0.0218870000 404696133 0 402718720 -0.0505901799 -0.0859952644 -0.0108597735 508 1311867735.5458450317 0.0984368846 0.0809472344 0.1415939182 0.0048360676 0.0330090000 404699165 0 402718720 -0.0504353419 -0.0853353441 -0.0098040681 509 1311867735.5778179169 0.0980918780 0.0809809174 0.1415939182 0.0048439440 0.0248580000 404702365 0 402718720 -0.0498112775 -0.0863829926 -0.0088881431 510 1311867735.6139240265 0.0963361561 0.0810110257 0.1415939182 0.0048410204 0.0353510000 404705677 0 402718720 -0.0496256463 -0.0839063451 -0.0092722718 511 1311867735.6459200382 0.0968468562 0.0810420156 0.1415939182 0.0048383295 0.0341980000 404708709 0 402718720 -0.0497270375 -0.0843947306 -0.0073029217 512 1311867735.6778628826 0.0964430422 0.0810720957 0.1415939182 0.0048357270 0.0310370000 404711909 0 402718720 -0.0495872498 -0.0843942910 -0.0059661930 513 1311867735.7137730122 0.0968450159 0.0811028422 0.1415939182 0.0048319303 0.0713170000 404768357 0 402718720 -0.0495177321 -0.0850197747 -0.0088657886 514 1311867735.7458720207 0.0978629291 0.0811354493 0.1415939182 0.0048280422 0.0327220000 404873901 0 402718720 -0.0493993163 -0.0863438696 -0.0097511793 515 1311867735.7779068947 0.0981898904 0.0811685648 0.1415939182 0.0048244941 0.0301510000 404877101 0 402718720 -0.0485887975 -0.0870385468 -0.0081012305 516 1311867735.8139519691 0.0980523005 0.0812012852 0.1415939182 0.0048231545 0.0282080000 404880301 0 402718720 -0.0484119095 -0.0871069506 -0.0106214173 517 1311867735.8461170197 0.0973161012 0.0812324550 0.1415939182 0.0048328419 0.0312470000 404883445 0 402718720 -0.0484924875 -0.0848609805 -0.0114006903 518 1311867735.8779520988 0.0975051969 0.0812638696 0.1415939182 0.0048316533 0.0429320000 404886477 0 402718720 -0.0489163771 -0.0848486274 -0.0111033879 519 1311867735.9139308929 0.0953182951 0.0812909494 0.1415939182 0.0048304126 0.0297210000 404889733 0 402718720 -0.0449445657 -0.0850925818 -0.0110547990 520 1311867735.9461469650 0.0954141617 0.0813181094 0.1415939182 0.0048259649 0.0822860000 417201145 0 402718720 -0.0458131768 -0.0843856558 -0.0105455946 521 1311867735.9778470993 0.0856572762 0.0813264380 0.1415939182 0.0048246905 0.0400240000 420863497 0 402718720 -0.0385172851 -0.0779072270 -0.0058998135 522 1311867736.0138840675 0.0831969306 0.0813300213 0.1415939182 0.0048317980 0.0377890000 424058945 0 402718720 -0.0389189720 -0.0742896125 -0.0073151826 523 1311867736.0458500385 0.0846746415 0.0813364164 0.1415939182 0.0048283488 0.0354410000 424062033 0 402718720 -0.0384254009 -0.0767546222 -0.0052924147 524 1311867736.0778849125 0.0872540101 0.0813477095 0.1415939182 0.0048253124 0.0531260000 424065233 0 402718720 -0.0396192223 -0.0793059468 -0.0058396212 525 1311867736.1139700413 0.0843806565 0.0813534865 0.1415939182 0.0048268136 0.0373630000 424068433 0 402718720 -0.0407385938 -0.0745169669 -0.0064385752 526 1311867736.1458110809 0.0869619176 0.0813641489 0.1415939182 0.0048338279 0.0126190000 424071577 0 402718720 -0.0395615548 -0.0794740170 -0.0065323804 527 1311867736.1779921055 0.0876008719 0.0813759833 0.1415939182 0.0048312986 0.0127890000 424074777 0 402718720 -0.0392671935 -0.0810360238 -0.0060663200 528 1311867736.2138609886 0.0880083963 0.0813885447 0.1415939182 0.0048319689 0.0310160000 424077977 0 402718720 -0.0407722890 -0.0802262500 -0.0061493753 529 1311867736.2459011078 0.0874837637 0.0814000669 0.1415939182 0.0048378897 0.0122830000 424081121 0 402718720 -0.0399169140 -0.0808914527 -0.0061893063 530 1311867736.2780930996 0.0883704647 0.0814132186 0.1415939182 0.0048334373 0.0260060000 424084209 0 402718720 -0.0401644930 -0.0818090439 -0.0045387270 531 1311867736.3138680458 0.0877392441 0.0814251320 0.1415939182 0.0048343129 0.0683760000 436395133 0 402718720 -0.0397822857 -0.0819510967 -0.0069701984 532 1311867736.3458290100 0.0935546532 0.0814479318 0.1415939182 0.0048880930 0.0361640000 440060797 0 402718720 -0.0512892604 -0.0788941756 -0.0075249043 533 1311867736.3779211044 0.0917004496 0.0814671673 0.1415939182 0.0048871323 0.0290690000 443256133 0 402718720 -0.0489659756 -0.0795489699 -0.0051550809 534 1311867736.4138979912 0.0912665948 0.0814855183 0.1415939182 0.0048839396 0.0311620000 443259333 0 402718720 -0.0479463637 -0.0800696239 -0.0085754115 535 1311867736.4458179474 0.0891481265 0.0814998409 0.1415939182 0.0048849376 0.0112140000 443262477 0 402718720 -0.0473315045 -0.0778236017 -0.0069105946 536 1311867736.4780380726 0.0949923173 0.0815250135 0.1415939182 0.0048815078 0.0740460000 443265677 0 402718720 -0.0501639061 -0.0832281113 -0.0065544997 537 1311867736.5138549805 0.0939103961 0.0815480775 0.1415939182 0.0048791450 0.0338740000 443268877 0 402718720 -0.0481467508 -0.0838798732 -0.0087678703 538 1311867736.5459420681 0.0905426666 0.0815647961 0.1415939182 0.0048810440 0.0114880000 443272077 0 402718720 -0.0479601398 -0.0797289014 -0.0088556996 539 1311867736.5779209137 0.0958654583 0.0815913279 0.1415939182 0.0048790705 0.0342950000 443275221 0 402718720 -0.0508837141 -0.0848510936 -0.0056091808 540 1311867736.6140410900 0.0960201323 0.0816180479 0.1415939182 0.0048778501 0.0335800000 443278533 0 402718720 -0.0497135893 -0.0864403695 -0.0078317868 541 1311867736.6459450722 0.0952771530 0.0816432958 0.1415939182 0.0048852274 0.0354110000 443281621 0 402718720 -0.0500517450 -0.0847556740 -0.0076410249 542 1311867736.6779170036 0.0969806686 0.0816715935 0.1415939182 0.0048844823 0.0348960000 443284765 0 402718720 -0.0532206073 -0.0844998211 -0.0047349748 543 1311867736.7140109539 0.0926750228 0.0816918577 0.1415939182 0.0048969610 0.0324890000 443287909 0 402718720 -0.0489616469 -0.0838026479 -0.0069984309 544 1311867736.7458450794 0.0948393941 0.0817160259 0.1415939182 0.0048940906 0.0331920000 443291053 0 402718720 -0.0494623333 -0.0858379304 -0.0084405020 545 1311867736.7780408859 0.1048462763 0.0817584668 0.1415939182 0.0049088281 0.0791590000 455602153 0 402718720 -0.0571788698 -0.0929366425 -0.0092292614 546 1311867736.8139879704 0.1125091761 0.0818147868 0.1415939182 0.0051667347 0.0403810000 459264105 0 402718720 -0.0447896421 -0.1125738770 -0.0065931240 547 1311867736.8458929062 0.1056376025 0.0818583385 0.1415939182 0.0051707172 0.0354110000 462459385 0 402718720 -0.0415560901 -0.1062576622 -0.0104959607 548 1311867736.8779690266 0.1057399660 0.0819019181 0.1415939182 0.0051674414 0.0676180000 462462529 0 402718720 -0.0419341885 -0.1059612483 -0.0079221725 549 1311867736.9140260220 0.1088840067 0.0819510658 0.1415939182 0.0051660788 0.0369890000 462465785 0 402718720 -0.0426396765 -0.1091242656 -0.0093360627 550 1311867736.9459569454 0.1091386825 0.0820004979 0.1415939182 0.0051625995 0.0354040000 462468929 0 402718720 -0.0420657694 -0.1092450470 -0.0136389295 551 1311867736.9779520035 0.1132237241 0.0820571643 0.1415939182 0.0051723539 0.0365280000 462472073 0 402718720 -0.0505412333 -0.1081558913 -0.0111719249 552 1311867737.0140330791 0.1111416146 0.0821098536 0.1415939182 0.0051837637 0.0369850000 474771797 0 402718720 -0.0437775329 -0.1106908321 -0.0088421740 553 1311867737.0459079742 0.1028928012 0.0821474357 0.1415939182 0.0051831288 0.0373590000 478434205 0 402718720 -0.0341149792 -0.1067027077 -0.0104104131 554 1311867737.0781080723 0.1040670425 0.0821870018 0.1415939182 0.0051805949 0.0112100000 481629541 0 402718720 -0.0369472392 -0.1064147279 -0.0089133335 555 1311867737.1139400005 0.1040791273 0.0822264471 0.1415939182 0.0051766110 0.0213220000 481632853 0 402718720 -0.0379726253 -0.1058535203 -0.0094793700 556 1311867737.1460459232 0.1047856733 0.0822670212 0.1415939182 0.0051730388 0.0255210000 481635941 0 402718720 -0.0386066847 -0.1061516255 -0.0114867343 557 1311867737.1779479980 0.1009263173 0.0823005209 0.1415939182 0.0051717611 0.0361990000 481639085 0 402718720 -0.0364631563 -0.1030664518 -0.0103958072 558 1311867737.2139670849 0.1073983312 0.0823454990 0.1415939182 0.0051738593 0.0300250000 481642397 0 402718720 -0.0397833958 -0.1085770279 -0.0105218980 559 1311867737.2461230755 0.1070434526 0.0823896814 0.1415939182 0.0051865687 0.0302880000 481645485 0 402718720 -0.0374298692 -0.1094200313 -0.0114090322 560 1311867737.2783720493 0.1054913178 0.0824309343 0.1415939182 0.0051833683 0.0263710000 481648629 0 402718720 -0.0362273864 -0.1079371050 -0.0124386251 561 1311867737.3138759136 0.1056084782 0.0824722490 0.1415939182 0.0051788550 0.0267380000 481651941 0 402718720 -0.0358285792 -0.1082551554 -0.0111360280 562 1311867737.3459680080 0.1051693410 0.0825126353 0.1415939182 0.0051746723 0.0622660000 481654973 0 402718720 -0.0358101092 -0.1077955067 -0.0121121937 563 1311867737.3780488968 0.1059646308 0.0825542907 0.1415939182 0.0051727790 0.0333580000 493954089 0 402718720 -0.0381476805 -0.1069730520 -0.0125939222 564 1311867737.4141969681 0.1072900370 0.0825981484 0.1415939182 0.0051749007 0.0122230000 497616497 0 402718720 -0.0365598425 -0.1094194353 -0.0127691645 565 1311867737.4462239742 0.1070165113 0.0826413668 0.1415939182 0.0051705020 0.0103200000 500811833 0 402718720 -0.0363610014 -0.1091806665 -0.0116556464 566 1311867737.4780650139 0.1101156846 0.0826899080 0.1415939182 0.0051843338 0.0332750000 500814977 0 402718720 -0.0437270142 -0.1078402176 -0.0123579586 567 1311867737.5141921043 0.1071454883 0.0827330395 0.1415939182 0.0051863422 0.0229330000 500818233 0 402718720 -0.0377255268 -0.1084570736 -0.0109297605 568 1311867737.5464630127 0.1098721325 0.0827808196 0.1415939182 0.0052013798 0.0327310000 500821377 0 402718720 -0.0444459543 -0.1066896543 -0.0120387170 569 1311867737.5780799389 0.1121821254 0.0828324915 0.1415939182 0.0052005184 0.0328270000 500824577 0 402718720 -0.0438635126 -0.1097046733 -0.0122693600 570 1311867737.6142530441 0.1201087758 0.0828978885 0.1415939182 0.0052240804 0.0386530000 513122905 0 402718720 -0.0571713857 -0.1088822260 -0.0160166398 571 1311867737.6460239887 0.1136426404 0.0829517322 0.1415939182 0.0052279780 0.0344160000 516785257 0 402718720 -0.0506789871 -0.1061693504 -0.0134257860 572 1311867737.6780090332 0.1194310635 0.0830155072 0.1415939182 0.0052306440 0.0475220000 519980593 0 402718720 -0.0526871607 -0.1122597307 -0.0124613782 573 1311867737.7139749527 0.1193219274 0.0830788692 0.1415939182 0.0052270691 0.0415290000 519983793 0 402718720 -0.0523138382 -0.1125459298 -0.0121220145 574 1311867737.7460410595 0.1194964647 0.0831423145 0.1415939182 0.0052233218 0.0696200000 519986937 0 402718720 -0.0522273667 -0.1126494855 -0.0120423855 575 1311867737.7782158852 0.1190058142 0.0832046858 0.1415939182 0.0052213233 0.0315780000 519990137 0 402718720 -0.0519386269 -0.1125019640 -0.0116670681 576 1311867737.8140470982 0.1189138815 0.0832666809 0.1415939182 0.0052170907 0.0326080000 519993393 0 402718720 -0.0517256670 -0.1126249507 -0.0114394259 577 1311867737.8460240364 0.1193344146 0.0833291900 0.1415939182 0.0052205733 0.0331150000 519996481 0 402718720 -0.0519356541 -0.1125783771 -0.0115202712 578 1311867737.8779919147 0.1190693602 0.0833910242 0.1415939182 0.0052161018 0.0298600000 519999681 0 402718720 -0.0514159389 -0.1126660779 -0.0109266434 579 1311867737.9140400887 0.1190688014 0.0834526439 0.1415939182 0.0052123547 0.0304340000 520002825 0 402718720 -0.0506376587 -0.1130387634 -0.0100842537 580 1311867737.9459939003 0.1190494448 0.0835140177 0.1415939182 0.0052097486 0.0317840000 520005969 0 402718720 -0.0507298745 -0.1129680723 -0.0101830997 581 1311867737.9781990051 0.1188590601 0.0835748525 0.1415939182 0.0052057754 0.0311900000 520009169 0 402718720 -0.0500564240 -0.1131931171 -0.0095126713 582 1311867738.0141079426 0.1186719090 0.0836351567 0.1415939182 0.0052013339 0.0288760000 520012425 0 402718720 -0.0496670865 -0.1130464971 -0.0089372369 583 1311867738.0460178852 0.1193453893 0.0836964093 0.1415939182 0.0051970364 0.0277730000 520015513 0 402718720 -0.0504518263 -0.1127437949 -0.0093938857 584 1311867738.0781040192 0.1195298955 0.0837577680 0.1415939182 0.0051937586 0.0292250000 520018657 0 402718720 -0.0493576750 -0.1133010760 -0.0084486706 585 1311867738.1140170097 0.1190507635 0.0838180979 0.1415939182 0.0051921298 0.0292510000 520021801 0 402718720 -0.0481337607 -0.1134880185 -0.0072524380 586 1311867738.1460049152 0.1187596768 0.0838777252 0.1415939182 0.0051891988 0.0666370000 520024945 0 402718720 -0.0474550277 -0.1136059463 -0.0063745296 587 1311867738.1779909134 0.1186947972 0.0839370387 0.1415939182 0.0051849808 0.0308450000 520028145 0 402718720 -0.0470708646 -0.1137479544 -0.0059148190 588 1311867738.2141749859 0.1182544753 0.0839954017 0.1415939182 0.0051820689 0.0302390000 520031401 0 402718720 -0.0461290367 -0.1140490696 -0.0049314755 589 1311867738.2461900711 0.1172979102 0.0840519425 0.1415939182 0.0051781206 0.0304160000 520034545 0 402718720 -0.0450419523 -0.1140443757 -0.0039744792 590 1311867738.2781438828 0.1166695654 0.0841072266 0.1415939182 0.0051741390 0.0304220000 520037689 0 402718720 -0.0444795191 -0.1137629002 -0.0034234154 591 1311867738.3141109943 0.1160123125 0.0841612115 0.1415939182 0.0051700446 0.0304740000 520040945 0 402718720 -0.0441562049 -0.1136448905 -0.0029819766 592 1311867738.3461089134 0.1160511374 0.0842150796 0.1415939182 0.0051682673 0.0329500000 520044089 0 402718720 -0.0445337407 -0.1134188101 -0.0033172166 593 1311867738.3781440258 0.1163453609 0.0842692622 0.1415939182 0.0051642123 0.0303770000 520047233 0 402718720 -0.0447226539 -0.1136055887 -0.0034785203 594 1311867738.4142370224 0.1178253144 0.0843257539 0.1415939182 0.0051627351 0.0315750000 520050433 0 402718720 -0.0460868292 -0.1140298173 -0.0047368580 595 1311867738.4462459087 0.1174858883 0.0843814852 0.1415939182 0.0051589641 0.0300860000 520053633 0 402718720 -0.0450254604 -0.1146646217 -0.0037243336 596 1311867738.4781920910 0.1178691238 0.0844376725 0.1415939182 0.0051555604 0.0305710000 520056833 0 402718720 -0.0452776030 -0.1144285128 -0.0038621982 597 1311867738.5140159130 0.1196316630 0.0844966239 0.1415939182 0.0051515018 0.0305670000 520060089 0 402718720 -0.0465721227 -0.1148733273 -0.0051340587 598 1311867738.5462310314 0.1205417290 0.0845569000 0.1415939182 0.0051475914 0.0601010000 520063177 0 402718720 -0.0465121716 -0.1156528220 -0.0049600448 599 1311867738.5779619217 0.1203160658 0.0846165981 0.1415939182 0.0051434131 0.0304630000 520066321 0 402718720 -0.0451183841 -0.1157307923 -0.0036788478 600 1311867738.6140589714 0.1211665496 0.0846775147 0.1415939182 0.0051414764 0.0321510000 520069521 0 402718720 -0.0461531915 -0.1153385043 -0.0044478490 601 1311867738.6460950375 0.1220389158 0.0847396801 0.1415939182 0.0051379015 0.0306540000 520072721 0 402718720 -0.0458357483 -0.1157943606 -0.0042343135 602 1311867738.6780719757 0.1218504459 0.0848013259 0.1415939182 0.0051348643 0.0330880000 520075865 0 402718720 -0.0449836440 -0.1159530133 -0.0033353376 603 1311867738.7142090797 0.1221096069 0.0848631970 0.1415939182 0.0051566266 0.0322410000 520079065 0 402718720 -0.0454760082 -0.1157121733 -0.0036312267 604 1311867738.7460970879 0.1233345792 0.0849268914 0.1415939182 0.0051636715 0.0324080000 520082265 0 402718720 -0.0460199229 -0.1158464476 -0.0041341088 605 1311867738.7783861160 0.1238121465 0.0849911645 0.1415939182 0.0051607867 0.0370630000 520085409 0 402718720 -0.0457742661 -0.1159107238 -0.0034139038 606 1311867738.8142549992 0.1237025708 0.0850550447 0.1415939182 0.0051582122 0.0321410000 520088609 0 402718720 -0.0450381376 -0.1158629954 -0.0028742824 607 1311867738.8462960720 0.1242171898 0.0851195623 0.1415939182 0.0051546486 0.0305760000 520091809 0 402718720 -0.0452509262 -0.1157816201 -0.0029600074 608 1311867738.8781909943 0.1257240772 0.0851863460 0.1415939182 0.0051513338 0.0322240000 520094953 0 402718720 -0.0464695431 -0.1160288751 -0.0043818122 609 1311867738.9141190052 0.1257192940 0.0852529026 0.1415939182 0.0051512941 0.0359630000 520098153 0 402718720 -0.0462493747 -0.1158124655 -0.0034101505 610 1311867738.9461998940 0.1257764697 0.0853193346 0.1415939182 0.0051485864 0.0656480000 520101353 0 402718720 -0.0456699096 -0.1160443351 -0.0034497504 611 1311867738.9781630039 0.1259385794 0.0853858146 0.1415939182 0.0051444496 0.0288180000 520104497 0 402718720 -0.0452431962 -0.1162272096 -0.0032794424 612 1311867739.0142040253 0.1251179427 0.0854507364 0.1415939182 0.0051412349 0.0300320000 520107809 0 402718720 -0.0438225456 -0.1162477732 -0.0019004471 613 1311867739.0461840630 0.1260051429 0.0855168936 0.1415939182 0.0051400593 0.0359790000 520110897 0 402718720 -0.0454433374 -0.1161827147 -0.0023248831 614 1311867739.0781500340 0.1262847781 0.0855832908 0.1415939182 0.0051424239 0.0299240000 520114041 0 402718720 -0.0449673645 -0.1162895784 -0.0023520400 615 1311867739.1145129204 0.1272565871 0.0856510523 0.1415939182 0.0051385436 0.0942340000 532428437 0 402718720 -0.0461702123 -0.1161119714 -0.0029485575 616 1311867739.1463479996 0.1250971854 0.0857150882 0.1415939182 0.0051619078 0.0191770000 536090677 0 402718720 -0.0404914692 -0.1182965711 0.0036340149 617 1311867739.1784689426 0.1250659376 0.0857788659 0.1415939182 0.0051589704 0.0180120000 539286013 0 402718720 -0.0405197926 -0.1183700711 0.0035560068 618 1311867739.2143969536 0.1247394383 0.0858419089 0.1415939182 0.0051548853 0.0203730000 539289213 0 402718720 -0.0402339771 -0.1184403971 0.0038144747 619 1311867739.2462329865 0.1242252886 0.0859039176 0.1415939182 0.0051511202 0.0176500000 539292413 0 402718720 -0.0396127701 -0.1186070144 0.0043077990 620 1311867739.2781720161 0.1235651448 0.0859646615 0.1415939182 0.0051517330 0.0480540000 539295557 0 402718720 -0.0391530059 -0.1186307818 0.0046662190 621 1311867739.3142199516 0.1239527017 0.0860258339 0.1415939182 0.0051485793 0.0206990000 539298869 0 402718720 -0.0404770523 -0.1183278784 0.0035140433 622 1311867739.3466510773 0.1236568168 0.0860863339 0.1415939182 0.0051445236 0.0206800000 539301957 0 402718720 -0.0403039679 -0.1183326319 0.0036758524 623 1311867739.3781549931 0.1234746501 0.0861463472 0.1415939182 0.0051409035 0.0207510000 539305101 0 402718720 -0.0400779620 -0.1186093092 0.0038643095 624 1311867739.4140689373 0.1237011850 0.0862065313 0.1415939182 0.0051378951 0.0207050000 539308301 0 402718720 -0.0406614281 -0.1185690910 0.0033265334 625 1311867739.4460690022 0.1231987104 0.0862657187 0.1415939182 0.0051341144 0.0195150000 539311445 0 402718720 -0.0402959101 -0.1183041036 0.0036968640 626 1311867739.4783449173 0.1223905087 0.0863234261 0.1415939182 0.0051358425 0.0208350000 539314645 0 402718720 -0.0392235070 -0.1184190661 0.0047519975 627 1311867739.5141808987 0.1229319274 0.0863818128 0.1415939182 0.0051320845 0.0212350000 539317845 0 402718720 -0.0399987660 -0.1185565218 0.0040137148 628 1311867739.5462429523 0.1230581775 0.0864402147 0.1415939182 0.0051293482 0.0208750000 539320989 0 402718720 -0.0403240286 -0.1183711216 0.0037208993 629 1311867739.5781390667 0.1220679656 0.0864968566 0.1415939182 0.0051254613 0.0218970000 539324133 0 402718720 -0.0389023498 -0.1185063198 0.0049678646 630 1311867739.6142079830 0.1223271340 0.0865537300 0.1415939182 0.0051216148 0.0194190000 539327389 0 402718720 -0.0397186838 -0.1183847636 0.0042906534 631 1311867739.6460380554 0.1215566248 0.0866092021 0.1415939182 0.0051177972 0.0220830000 539330477 0 402718720 -0.0387117639 -0.1185332760 0.0052204789 632 1311867739.6830139160 0.1212403774 0.0866639983 0.1415939182 0.0051148046 0.0210290000 539333845 0 402718720 -0.0387628786 -0.1184826121 0.0052193301 633 1311867739.7142000198 0.1215825081 0.0867191618 0.1415939182 0.0051115558 0.0194590000 539336877 0 402718720 -0.0397297442 -0.1184199527 0.0041712937 634 1311867739.7461159229 0.1208285093 0.0867729621 0.1415939182 0.0051076504 0.0222540000 539340077 0 402718720 -0.0385128111 -0.1186073944 0.0052603665 635 1311867739.7782371044 0.1197574660 0.0868249062 0.1415939182 0.0051038318 0.0573340000 539343221 0 402718720 -0.0371911563 -0.1188209876 0.0065622162 636 1311867739.8140680790 0.1203453541 0.0868776113 0.1415939182 0.0051000518 0.0200290000 539346421 0 402718720 -0.0388488173 -0.1185549125 0.0049353577 637 1311867739.8462030888 0.1199204475 0.0869294839 0.1415939182 0.0050963971 0.0186080000 539349621 0 402718720 -0.0386917107 -0.1185501739 0.0049056904 638 1311867739.8784179688 0.1178787649 0.0869779937 0.1415939182 0.0050928714 0.0290070000 539352765 0 402718720 -0.0359199792 -0.1190619767 0.0072381087 639 1311867739.9141149521 0.1177328378 0.0870261233 0.1415939182 0.0050890638 0.0240720000 539356077 0 402718720 -0.0372586697 -0.1188715324 0.0059633474 640 1311867739.9462161064 0.1183817461 0.0870751165 0.1415939182 0.0050851723 0.0185120000 539359165 0 402718720 -0.0392796397 -0.1185538247 0.0041609881 641 1311867739.9781019688 0.1169252545 0.0871216846 0.1415939182 0.0050822932 0.0271970000 539362309 0 402718720 -0.0374420434 -0.1188215911 0.0055350284 642 1311867740.0140759945 0.1155094728 0.0871659023 0.1415939182 0.0050787524 0.0295330000 539365621 0 402718720 -0.0362034105 -0.1190952659 0.0064183832 643 1311867740.0462660789 0.1163167059 0.0872112379 0.1415939182 0.0050748640 0.0235910000 539368709 0 402718720 -0.0384772345 -0.1187763885 0.0043741302 644 1311867740.0782411098 0.1162025258 0.0872562555 0.1415939182 0.0050713233 0.0215080000 539371853 0 402718720 -0.0387118571 -0.1186285540 0.0040650829 645 1311867740.1140639782 0.1141655445 0.0872979753 0.1415939182 0.0050679431 0.0305450000 539375053 0 402718720 -0.0357411169 -0.1191037148 0.0066386089 646 1311867740.1463708878 0.1150185391 0.0873408864 0.1415939182 0.0050642903 0.0218630000 539378253 0 402718720 -0.0384169035 -0.1186674610 0.0041281148 647 1311867740.1781940460 0.1153517962 0.0873841799 0.1415939182 0.0050603951 0.0199290000 539381397 0 402718720 -0.0392887257 -0.1185518354 0.0031547002 648 1311867740.2142000198 0.1137577668 0.0874248799 0.1415939182 0.0050567328 0.0667150000 539384597 0 402718720 -0.0368742719 -0.1189767569 0.0051261298 649 1311867740.2462930679 0.1140184030 0.0874658560 0.1415939182 0.0050530124 0.0276070000 539387797 0 402718720 -0.0381282382 -0.1188505888 0.0039182235 650 1311867740.2782120705 0.1148343235 0.0875079614 0.1415939182 0.0050493693 0.0229440000 539390941 0 402718720 -0.0395413786 -0.1186450496 0.0025660787 651 1311867740.3143200874 0.1137165800 0.0875482204 0.1415939182 0.0050456980 0.0344040000 539394141 0 402718720 -0.0378358997 -0.1188944206 0.0039483164 652 1311867740.3463900089 0.1140073985 0.0875888020 0.1415939182 0.0050421770 0.0283980000 539397341 0 402718720 -0.0387058295 -0.1188198999 0.0031926190 653 1311867740.3781099319 0.1142112091 0.0876295713 0.1415939182 0.0050383754 0.0278130000 539400485 0 402718720 -0.0390125141 -0.1187242270 0.0027689359 654 1311867740.4140830040 0.1145101488 0.0876706731 0.1415939182 0.0050346710 0.0244460000 539403741 0 402718720 -0.0395855010 -0.1186259985 0.0023133224 655 1311867740.4461269379 0.1145685464 0.0877117386 0.1415939182 0.0050320928 0.0254150000 539406885 0 402718720 -0.0396635197 -0.1186025664 0.0020966434 656 1311867740.4782450199 0.1147501022 0.0877529556 0.1415939182 0.0050287354 0.0254470000 539410029 0 402718720 -0.0399529748 -0.1185606271 0.0017999458 657 1311867740.5142049789 0.1151003838 0.0877945803 0.1415939182 0.0050263055 0.0265110000 539413285 0 402718720 -0.0408018418 -0.1181857809 0.0009499464 658 1311867740.5463099480 0.1155792996 0.0878368063 0.1415939182 0.0050226441 0.0247540000 539416429 0 402718720 -0.0410589054 -0.1184427589 0.0009365911 659 1311867740.5782189369 0.1160395369 0.0878796026 0.1415939182 0.0050193541 0.0421530000 539419573 0 402718720 -0.0415571518 -0.1183482483 0.0004595352 660 1311867740.6141209602 0.1163344234 0.0879227159 0.1415939182 0.0050156657 0.0253690000 539422829 0 402718720 -0.0417226106 -0.1183666587 0.0002259621 661 1311867740.6463210583 0.1160353795 0.0879652465 0.1415939182 0.0050133742 0.0587600000 539425973 0 402718720 -0.0413838178 -0.1183963642 0.0004921175 662 1311867740.6782870293 0.1155057847 0.0880068485 0.1415939182 0.0050097098 0.0237870000 539429117 0 402718720 -0.0410155430 -0.1184570938 0.0007590824 663 1311867740.7142190933 0.1156885102 0.0880486006 0.1415939182 0.0050062725 0.0223930000 539432373 0 402718720 -0.0414322019 -0.1183355451 0.0004516100 664 1311867740.7462959290 0.1159482747 0.0880906182 0.1415939182 0.0050030477 0.0264690000 539435349 0 402718720 -0.0422056094 -0.1182927489 -0.0001995364 665 1311867740.7784550190 0.1152611077 0.0881314761 0.1415939182 0.0049999409 0.0239860000 539438493 0 402718720 -0.0418271609 -0.1182250902 0.0000157295 666 1311867740.8142650127 0.1153420731 0.0881723328 0.1415939182 0.0049965013 0.0764960000 551746729 0 402718720 -0.0426533446 -0.1180224568 -0.0007480851 667 1311867740.8461530209 0.1151017547 0.0882127068 0.1415939182 0.0049929241 0.0184870000 555409081 0 402718720 -0.0426078774 -0.1181227565 -0.0000893894 668 1311867740.8782610893 0.1142573282 0.0882516957 0.1415939182 0.0049893078 0.0161280000 558604473 0 402718720 -0.0411796756 -0.1184686124 0.0011061799 669 1311867740.9145269394 0.1145336926 0.0882909812 0.1415939182 0.0049863894 0.0188480000 558607729 0 402718720 -0.0429736860 -0.1181153879 -0.0006669523 670 1311867740.9468269348 0.1144760549 0.0883300634 0.1415939182 0.0049829903 0.0242070000 558610873 0 402718720 -0.0434467718 -0.1179041117 -0.0011106074 671 1311867740.9783740044 0.1136230230 0.0883677578 0.1415939182 0.0049794002 0.0463820000 558614017 0 402718720 -0.0421789251 -0.1181838065 -0.0000010955 672 1311867741.0141980648 0.1135052145 0.0884051648 0.1415939182 0.0049760318 0.0207160000 558617217 0 402718720 -0.0428853780 -0.1179815754 -0.0006183046 673 1311867741.0462551117 0.1142540649 0.0884435732 0.1415939182 0.0049725551 0.0317520000 558620417 0 402718720 -0.0451203734 -0.1175627932 -0.0028921126 674 1311867741.0782248974 0.1134657338 0.0884806981 0.1415939182 0.0049694029 0.0232580000 558623561 0 402718720 -0.0434465930 -0.1180658489 -0.0014176209 675 1311867741.1144049168 0.1126168370 0.0885164553 0.1415939182 0.0049673830 0.0178030000 558626761 0 402718720 -0.0430888683 -0.1180632263 -0.0011396883 676 1311867741.1466870308 0.1131917164 0.0885529572 0.1415939182 0.0049638890 0.0254850000 558629961 0 402718720 -0.0445332974 -0.1180428118 -0.0026226917 677 1311867741.1783940792 0.1129357740 0.0885889732 0.1415939182 0.0049602844 0.0255810000 558633105 0 402718720 -0.0445485190 -0.1178343222 -0.0027574159 678 1311867741.2143990993 0.1123413146 0.0886240061 0.1415939182 0.0049572769 0.0232140000 558636305 0 402718720 -0.0436764024 -0.1179637834 -0.0019221223 679 1311867741.2465291023 0.1125036702 0.0886591750 0.1415939182 0.0049545170 0.0255420000 558639505 0 402718720 -0.0443462804 -0.1178594232 -0.0025196190 680 1311867741.2784590721 0.1130978763 0.0886951143 0.1415939182 0.0049521118 0.0255750000 558642649 0 402718720 -0.0453930199 -0.1176289842 -0.0034395626 681 1311867741.3143949509 0.1136254668 0.0887317227 0.1415939182 0.0049485616 0.0262840000 558645905 0 402718720 -0.0456911363 -0.1177972257 -0.0039241370 682 1311867741.3464109898 0.1144109890 0.0887693756 0.1415939182 0.0049454109 0.0308250000 558649049 0 402718720 -0.0467922986 -0.1174765453 -0.0049892850 683 1311867741.3783149719 0.1150408313 0.0888078404 0.1415939182 0.0049419530 0.0267840000 558652193 0 402718720 -0.0472126678 -0.1173501834 -0.0051777847 684 1311867741.4153189659 0.1153150648 0.0888465937 0.1415939182 0.0049383744 0.0579270000 558655505 0 402718720 -0.0472489782 -0.1169780120 -0.0051662149 685 1311867741.4480650425 0.1160320267 0.0888862804 0.1415939182 0.0049351475 0.0280470000 558658649 0 402718720 -0.0477081537 -0.1167257801 -0.0053280001 686 1311867741.4784660339 0.1168457195 0.0889270376 0.1415939182 0.0049316807 0.0254550000 558661737 0 402718720 -0.0477002747 -0.1170897558 -0.0055971807 687 1311867741.5143730640 0.1170236319 0.0889679351 0.1415939182 0.0049284305 0.0249440000 558664937 0 402718720 -0.0469531640 -0.1172795445 -0.0048993658 688 1311867741.5461940765 0.1176182479 0.0890095780 0.1415939182 0.0049251181 0.0246300000 558668081 0 402718720 -0.0475597344 -0.1170361862 -0.0052513569 689 1311867741.5782639980 0.1185383573 0.0890524355 0.1415939182 0.0049220266 0.0240450000 558671281 0 402718720 -0.0486338027 -0.1167135313 -0.0061636958 690 1311867741.6143341064 0.1184781194 0.0890950814 0.1415939182 0.0049241172 0.0235560000 558674537 0 402718720 -0.0474147461 -0.1171744913 -0.0048659560 691 1311867741.6464450359 0.1193321347 0.0891388398 0.1415939182 0.0049258544 0.0262280000 558677681 0 402718720 -0.0479890108 -0.1170608848 -0.0052261744 692 1311867741.6783308983 0.1198105663 0.0891831631 0.1415939182 0.0049223338 0.0209760000 558680825 0 402718720 -0.0481436513 -0.1169782951 -0.0053900476 693 1311867741.7144010067 0.1201690957 0.0892278758 0.1415939182 0.0049189595 0.0231560000 558684025 0 402718720 -0.0481746718 -0.1168198511 -0.0055442341 694 1311867741.7463901043 0.1206398532 0.0892731381 0.1415939182 0.0049154568 0.0262680000 558687225 0 402718720 -0.0479736142 -0.1169240475 -0.0051445570 695 1311867741.7783830166 0.1211909130 0.0893190629 0.1415939182 0.0049126160 0.0239480000 558690369 0 402718720 -0.0479602925 -0.1170204058 -0.0049651889 696 1311867741.8143899441 0.1219347715 0.0893659246 0.1415939182 0.0049100280 0.0240990000 558693569 0 402718720 -0.0484566838 -0.1169905141 -0.0051281676 697 1311867741.8486139774 0.1225956529 0.0894135999 0.1415939182 0.0049155879 0.0254810000 558696825 0 402718720 -0.0484253205 -0.1169857979 -0.0048594042 698 1311867741.8782730103 0.1230220348 0.0894617496 0.1415939182 0.0049155958 0.0588100000 558699913 0 402718720 -0.0476486497 -0.1173788756 -0.0041921842 699 1311867741.9144229889 0.1241530478 0.0895113794 0.1415939182 0.0049144063 0.0272320000 558703169 0 402718720 -0.0482955240 -0.1173628867 -0.0046623591 700 1311867741.9468739033 0.1245586425 0.0895614470 0.1415939182 0.0049125355 0.0259180000 558706313 0 402718720 -0.0479186811 -0.1174345836 -0.0042014862 701 1311867741.9784300327 0.1245718598 0.0896113905 0.1415939182 0.0049097274 0.0226810000 558709457 0 402718720 -0.0480558127 -0.1167659387 -0.0042554229 702 1311867742.0142560005 0.1257226616 0.0896628311 0.1415939182 0.0049071027 0.0232450000 558712713 0 402718720 -0.0486390963 -0.1165192276 -0.0045454693 703 1311867742.0462529659 0.1270131320 0.0897159609 0.1415939182 0.0049045817 0.0255980000 558715801 0 402718720 -0.0488561206 -0.1170800328 -0.0043341368 704 1311867742.0786769390 0.1278312802 0.0897701020 0.1415939182 0.0049011333 0.0244990000 558718945 0 402718720 -0.0488143191 -0.1169773489 -0.0043261838 705 1311867742.1144309044 0.1293147206 0.0898261937 0.1415939182 0.0048995621 0.0323240000 558722089 0 402718720 -0.0488076769 -0.1173451170 -0.0038716104 706 1311867742.1462900639 0.1299703121 0.0898830550 0.1415939182 0.0048971660 0.0361380000 558725233 0 402718720 -0.0491667837 -0.1172454730 -0.0039638872 707 1311867742.1782898903 0.1311071813 0.0899413635 0.1415939182 0.0048944293 0.0332250000 558728433 0 402718720 -0.0497110263 -0.1172633842 -0.0042306171 708 1311867742.2143509388 0.1323400289 0.0900012487 0.1415939182 0.0048913997 0.0363330000 558731633 0 402718720 -0.0501671880 -0.1173633188 -0.0043367865 709 1311867742.2463901043 0.1325943917 0.0900613236 0.1415939182 0.0048881093 0.0333220000 558734833 0 402718720 -0.0495876335 -0.1173026934 -0.0037220789 710 1311867742.2785389423 0.1327002794 0.0901213785 0.1415939182 0.0048847111 0.0258120000 558738033 0 402718720 -0.0490685627 -0.1172865480 -0.0032961117 711 1311867742.3143260479 0.1334988773 0.0901823876 0.1415939182 0.0048826985 0.0662290000 558741233 0 402718720 -0.0498979427 -0.1172235236 -0.0038917109 712 1311867742.3464210033 0.1333557516 0.0902430244 0.1415939182 0.0048799171 0.0271110000 558744377 0 402718720 -0.0492580570 -0.1171913669 -0.0034701556 713 1311867742.3784179688 0.1336912215 0.0903039615 0.1415939182 0.0048769348 0.0259480000 558747521 0 402718720 -0.0495082103 -0.1172601208 -0.0035961384 714 1311867742.4143109322 0.1340795904 0.0903652719 0.1415939182 0.0048736443 0.0235800000 558750777 0 402718720 -0.0498717912 -0.1171450019 -0.0038989338 715 1311867742.4462630749 0.1349075437 0.0904275688 0.1415939182 0.0048704201 0.0300640000 558753865 0 402718720 -0.0506121852 -0.1170504913 -0.0041652326 716 1311867742.4782900810 0.1348490417 0.0904896100 0.1415939182 0.0048671451 0.0265490000 558757065 0 402718720 -0.0500378013 -0.1171068773 -0.0037014089 717 1311867742.5144250393 0.1356921047 0.0905526539 0.1415939182 0.0048640117 0.0264210000 558760265 0 402718720 -0.0506549925 -0.1171551943 -0.0041650874 718 1311867742.5463809967 0.1364214420 0.0906165380 0.1415939182 0.0048606593 0.0277740000 558763465 0 402718720 -0.0514456443 -0.1170750186 -0.0048226970 719 1311867742.5783019066 0.1365393698 0.0906804084 0.1415939182 0.0048573630 0.0262490000 558766609 0 402718720 -0.0510472320 -0.1170961186 -0.0043210979 720 1311867742.6142919064 0.1372417212 0.0907450769 0.1415939182 0.0048547800 0.0313820000 558769809 0 402718720 -0.0514479950 -0.1171048358 -0.0044061346 721 1311867742.6462519169 0.1370775998 0.0908093384 0.1415939182 0.0048514126 0.0245800000 558772953 0 402718720 -0.0508481599 -0.1171990633 -0.0040783575 722 1311867742.6823589802 0.1367953569 0.0908730310 0.1415939182 0.0048496677 0.0242690000 558776265 0 402718720 -0.0503594056 -0.1171306521 -0.0037402443 723 1311867742.7143929005 0.1373705119 0.0909373428 0.1415939182 0.0048487004 0.0303240000 558779409 0 402718720 -0.0508256666 -0.1171624586 -0.0036426827 724 1311867742.7463440895 0.1378691941 0.0910021658 0.1415939182 0.0048457008 0.0677590000 558782553 0 402718720 -0.0511514209 -0.1171348393 -0.0036869210 725 1311867742.7823669910 0.1379574686 0.0910669318 0.1415939182 0.0048423772 0.0265210000 558785809 0 402718720 -0.0509078056 -0.1170888841 -0.0035618886 726 1311867742.8142659664 0.1379666924 0.0911315320 0.1415939182 0.0048419180 0.0275090000 558788953 0 402718720 -0.0511105768 -0.1170678437 -0.0036463146 727 1311867742.8464159966 0.1386290193 0.0911968655 0.1415939182 0.0048399207 0.0284590000 558792097 0 402718720 -0.0515077040 -0.1169799790 -0.0038779913 728 1311867742.8823649883 0.1387335062 0.0912621631 0.1415939182 0.0048369682 0.0248180000 558795353 0 402718720 -0.0513334386 -0.1168862209 -0.0038468621 729 1311867742.9142940044 0.1395338178 0.0913283794 0.1415939182 0.0048350688 0.0899990000 571102165 0 402718720 -0.0520683974 -0.1169219762 -0.0041222293 730 1311867742.9464008808 0.1393134147 0.0913941123 0.1415939182 0.0048385158 0.0170460000 574764573 0 402718720 -0.0513529964 -0.1173098981 -0.0037585315 731 1311867742.9822909832 0.1399838477 0.0914605825 0.1415939182 0.0048445242 0.0186480000 577960021 0 402718720 -0.0519188829 -0.1171936318 -0.0039948002 732 1311867743.0144410133 0.1404328644 0.0915274845 0.1415939182 0.0048412709 0.0170350000 577963109 0 402718720 -0.0524103455 -0.1170406416 -0.0044966820 733 1311867743.0463359356 0.1403005868 0.0915940236 0.1415939182 0.0048393131 0.0169610000 577966253 0 402718720 -0.0516143069 -0.1172591597 -0.0036093311 734 1311867743.0824029446 0.1409264952 0.0916612340 0.1415939182 0.0048374491 0.0479610000 577969509 0 402718720 -0.0521694720 -0.1170732602 -0.0040592696 735 1311867743.1142439842 0.1411838531 0.0917286117 0.1415939182 0.0048347264 0.0200960000 577972597 0 402718720 -0.0518936813 -0.1172530279 -0.0037712336 736 1311867743.1462910175 0.1413767934 0.0917960685 0.1415939182 0.0048318489 0.0177640000 577975741 0 402718720 -0.0518629067 -0.1171574593 -0.0036351345 737 1311867743.1824851036 0.1419629008 0.0918641375 0.1419629008 0.0048289132 0.0174730000 577979053 0 402718720 -0.0523352809 -0.1169660762 -0.0039674845 738 1311867743.2143781185 0.1425309032 0.0919327916 0.1425309032 0.0048260406 0.0179250000 577982085 0 402718720 -0.0522524044 -0.1169260442 -0.0037639251 739 1311867743.2463059425 0.1427388191 0.0920015413 0.1427388191 0.0048235457 0.0175400000 577985229 0 402718720 -0.0525035560 -0.1168535724 -0.0040049264 740 1311867743.2824048996 0.1430907547 0.0920705808 0.1430907547 0.0048206497 0.0168210000 577988541 0 402718720 -0.0527692698 -0.1169147268 -0.0041718408 741 1311867743.3143129349 0.1431836933 0.0921395594 0.1431836933 0.0048186799 0.0178740000 577991685 0 402718720 -0.0524062403 -0.1171739027 -0.0038103273 742 1311867743.3463358879 0.1433525234 0.0922085795 0.1433525234 0.0048169116 0.0212190000 577994773 0 402718720 -0.0533638336 -0.1166217402 -0.0043956819 743 1311867743.3822519779 0.1432983130 0.0922773409 0.1433525234 0.0048146200 0.0174750000 577998029 0 402718720 -0.0527985580 -0.1168275997 -0.0039125229 744 1311867743.4145960808 0.1430285126 0.0923455549 0.1433525234 0.0048125700 0.0175730000 578001285 0 402718720 -0.0524511151 -0.1168987602 -0.0036150513 745 1311867743.4463078976 0.1429487616 0.0924134786 0.1433525234 0.0048101478 0.0173340000 578004317 0 402718720 -0.0518182591 -0.1171782613 -0.0033835273 746 1311867743.4828910828 0.1435312033 0.0924820011 0.1435312033 0.0048071956 0.0173390000 578007629 0 402718720 -0.0524642840 -0.1170498133 -0.0038329309 747 1311867743.5145409107 0.1436170191 0.0925504549 0.1436170191 0.0048040311 0.0167340000 578010773 0 402718720 -0.0526915826 -0.1168921888 -0.0040423563 748 1311867743.5463149548 0.1439292580 0.0926191431 0.1439292580 0.0048010826 0.0183820000 578013861 0 402718720 -0.0527706072 -0.1168527231 -0.0039765304 749 1311867743.5824689865 0.1443830431 0.0926882538 0.1443830431 0.0048001036 0.0183460000 578017117 0 402718720 -0.0530859232 -0.1170053706 -0.0042594951 750 1311867743.6143229008 0.1446601450 0.0927575497 0.1446601450 0.0048037587 0.0176780000 578020205 0 402718720 -0.0528244227 -0.1169221550 -0.0040306370 751 1311867743.6465840340 0.1435859948 0.0928252307 0.1446601450 0.0048070276 0.0182140000 578023405 0 402718720 -0.0523281246 -0.1168515235 -0.0036283296 752 1311867743.6827230453 0.1437721997 0.0928929793 0.1446601450 0.0048041487 0.0516570000 578026661 0 402718720 -0.0528794080 -0.1168128625 -0.0041465634 753 1311867743.7143280506 0.1435814202 0.0929602947 0.1446601450 0.0048013797 0.0189500000 578029805 0 402718720 -0.0529042855 -0.1168355793 -0.0042101014 754 1311867743.7468709946 0.1433555633 0.0930271319 0.1446601450 0.0047987680 0.0167280000 578032949 0 402718720 -0.0525735691 -0.1168838292 -0.0039683329 755 1311867743.7823519707 0.1432333738 0.0930936302 0.1446601450 0.0047958467 0.0176810000 578036205 0 402718720 -0.0529718772 -0.1168157533 -0.0043845475 756 1311867743.8146069050 0.1428349018 0.0931594255 0.1446601450 0.0047935270 0.0173480000 578039293 0 402718720 -0.0526428744 -0.1168884709 -0.0041701929 757 1311867743.8466429710 0.1424953043 0.0932245984 0.1446601450 0.0047903699 0.0238760000 578042437 0 402718720 -0.0525450483 -0.1169630364 -0.0040481668 758 1311867743.8825910091 0.1428493559 0.0932900665 0.1446601450 0.0047875943 0.0198130000 578045749 0 402718720 -0.0533933043 -0.1168149263 -0.0048789480 759 1311867743.9143130779 0.1426790953 0.0933551376 0.1446601450 0.0047847826 0.0165770000 578048893 0 402718720 -0.0529611520 -0.1169540510 -0.0045910827 760 1311867743.9475100040 0.1425530612 0.0934198718 0.1446601450 0.0047816546 0.0181690000 578052037 0 402718720 -0.0531137101 -0.1168307737 -0.0046828729 761 1311867743.9825859070 0.1434196234 0.0934855744 0.1446601450 0.0047798172 0.0281560000 578055237 0 402718720 -0.0545926578 -0.1165886447 -0.0060746530 762 1311867744.0145549774 0.1432697028 0.0935509080 0.1446601450 0.0047775716 0.0222590000 578058325 0 402718720 -0.0543619357 -0.1165341064 -0.0060316953 763 1311867744.0465490818 0.1435937285 0.0936164949 0.1446601450 0.0047745826 0.0235210000 578061525 0 402718720 -0.0549461432 -0.1163816079 -0.0063657085 764 1311867744.0825159550 0.1431289166 0.0936813017 0.1446601450 0.0047717942 0.0217730000 578064781 0 402718720 -0.0544142686 -0.1164947152 -0.0061159227 765 1311867744.1155200005 0.1436411738 0.0937466087 0.1446601450 0.0047698524 0.0219750000 578067757 0 402718720 -0.0548831224 -0.1164556071 -0.0063920347 766 1311867744.1485710144 0.1444844455 0.0938128461 0.1446601450 0.0047668846 0.0245000000 578070957 0 402718720 -0.0560284443 -0.1162234023 -0.0073607648 767 1311867744.1825850010 0.1444570720 0.0938788751 0.1446601450 0.0047656422 0.0516100000 578074213 0 402718720 -0.0550881140 -0.1163618490 -0.0065777660 768 1311867744.2144110203 0.1439886838 0.0939441222 0.1446601450 0.0047646341 0.0208060000 578077301 0 402718720 -0.0543130450 -0.1165005341 -0.0058458219 769 1311867744.2465009689 0.1445899308 0.0940099815 0.1446601450 0.0047615888 0.0214690000 578080445 0 402718720 -0.0549233370 -0.1165755019 -0.0063193389 770 1311867744.2824139595 0.1446478069 0.0940757450 0.1446601450 0.0047600341 0.0222820000 578083701 0 402718720 -0.0547626577 -0.1165525094 -0.0063683386 771 1311867744.3143589497 0.1439653933 0.0941404527 0.1446601450 0.0047602212 0.0189860000 578086845 0 402718720 -0.0534989610 -0.1167061329 -0.0052429512 772 1311867744.3465039730 0.1443884820 0.0942055408 0.1446601450 0.0047576628 0.0196180000 578089989 0 402718720 -0.0542582385 -0.1164919212 -0.0058588712 773 1311867744.3825259209 0.1452538818 0.0942715800 0.1452538818 0.0047546713 0.0229300000 578093301 0 402718720 -0.0549121276 -0.1164747179 -0.0063999742 774 1311867744.4144279957 0.1450197697 0.0943371462 0.1452538818 0.0047517370 0.0198910000 578096389 0 402718720 -0.0542817898 -0.1165693924 -0.0057522114 775 1311867744.4466331005 0.1448351443 0.0944023049 0.1452538818 0.0047492338 0.0192050000 578099533 0 402718720 -0.0537442267 -0.1166177765 -0.0052807895 776 1311867744.4825220108 0.1456153095 0.0944683010 0.1456153095 0.0047463165 0.0202070000 578102789 0 402718720 -0.0549346842 -0.1163666695 -0.0063597490 777 1311867744.5144040585 0.1457853317 0.0945343461 0.1457853317 0.0047437985 0.0197820000 578105989 0 402718720 -0.0547903962 -0.1163893864 -0.0061465562 778 1311867744.5464859009 0.1455139518 0.0945998726 0.1457853317 0.0047408200 0.0196640000 578109077 0 402718720 -0.0541408546 -0.1164663881 -0.0054776650 779 1311867744.5825068951 0.1461749226 0.0946660793 0.1461749226 0.0047412675 0.0215960000 578112333 0 402718720 -0.0546121746 -0.1164217815 -0.0058420054 780 1311867744.6143949032 0.1458533704 0.0947317041 0.1461749226 0.0047411503 0.0183670000 578115477 0 402718720 -0.0545415282 -0.1164796054 -0.0057664090 781 1311867744.6464331150 0.1460670531 0.0947974343 0.1461749226 0.0047381353 0.0183720000 578118621 0 402718720 -0.0546935797 -0.1164811030 -0.0058873072 782 1311867744.6825749874 0.1465990245 0.0948636768 0.1465990245 0.0047376681 0.0530390000 578121933 0 402718720 -0.0546516478 -0.1165212095 -0.0058347294 783 1311867744.7144720554 0.1465257406 0.0949296564 0.1465990245 0.0047386718 0.0208330000 578125077 0 402718720 -0.0550637357 -0.1164902449 -0.0062211086 784 1311867744.7465579510 0.1467877477 0.0949958020 0.1467877477 0.0047356975 0.0189180000 578128165 0 402718720 -0.0551022366 -0.1166425124 -0.0063252673 785 1311867744.7823460102 0.1465200633 0.0950614380 0.1467877477 0.0047389285 0.0195470000 578131421 0 402718720 -0.0540593639 -0.1167058796 -0.0055099679 786 1311867744.8143870831 0.1460085511 0.0951262562 0.1467877477 0.0047430581 0.0195880000 578134621 0 402718720 -0.0547069982 -0.1163711697 -0.0061846478 787 1311867744.8480839729 0.1463134140 0.0951912970 0.1467877477 0.0047400707 0.0293150000 578137821 0 402718720 -0.0551027320 -0.1164154261 -0.0063619637 788 1311867744.8824019432 0.1462973952 0.0952561525 0.1467877477 0.0047431526 0.0197260000 578140965 0 402718720 -0.0540089570 -0.1166684106 -0.0054191169 789 1311867744.9143979549 0.1460069418 0.0953204754 0.1467877477 0.0047483810 0.0203880000 578144109 0 402718720 -0.0551239401 -0.1163203120 -0.0064335861 790 1311867744.9465999603 0.1463575959 0.0953850794 0.1467877477 0.0047455505 0.0202430000 578147253 0 402718720 -0.0558241718 -0.1159702316 -0.0069311000 791 1311867744.9824030399 0.1466398537 0.0954498768 0.1467877477 0.0047447055 0.0206190000 578150509 0 402718720 -0.0557277650 -0.1160505414 -0.0067906538 792 1311867745.0145809650 0.1463477314 0.0955141418 0.1467877477 0.0047431679 0.0197680000 578153597 0 402718720 -0.0551696271 -0.1161427200 -0.0063022515 793 1311867745.0466170311 0.1463204920 0.0955782103 0.1467877477 0.0047411803 0.0197080000 578156741 0 402718720 -0.0549083464 -0.1162372828 -0.0061891377 794 1311867745.0825409889 0.1467156112 0.0956426151 0.1467877477 0.0047417687 0.0224550000 578159997 0 402718720 -0.0553818680 -0.1162091196 -0.0066707651 795 1311867745.1145880222 0.1469839662 0.0957071954 0.1469839662 0.0047403524 0.0228750000 578163197 0 402718720 -0.0560954586 -0.1162330285 -0.0070901657 796 1311867745.1469609737 0.1467307210 0.0957712953 0.1469839662 0.0047384044 0.0542270000 578166285 0 402718720 -0.0555639751 -0.1161421686 -0.0066056233 797 1311867745.1825649738 0.1467638016 0.0958352759 0.1469839662 0.0047375115 0.0219680000 578169541 0 402718720 -0.0548886545 -0.1163541824 -0.0060570263 798 1311867745.2146100998 0.1472551972 0.0958997119 0.1472551972 0.0047379719 0.0224500000 578172629 0 402718720 -0.0563234910 -0.1160326749 -0.0072945748 799 1311867745.2490229607 0.1475501359 0.0959643557 0.1475501359 0.0047357692 0.0199380000 578175885 0 402718720 -0.0562929213 -0.1162899584 -0.0073951092 800 1311867745.2828390598 0.1473752409 0.0960286193 0.1475501359 0.0047328879 0.0214250000 578179085 0 402718720 -0.0557169989 -0.1162949800 -0.0068267812 801 1311867745.3148200512 0.1475424916 0.0960929313 0.1475501359 0.0047300985 0.0221510000 578182229 0 402718720 -0.0559456944 -0.1161668450 -0.0068718009 802 1311867745.3468639851 0.1477873325 0.0961573881 0.1477873325 0.0047273073 0.0204080000 578185317 0 402718720 -0.0558959506 -0.1161015406 -0.0067576193 803 1311867745.3826758862 0.1481737942 0.0962221657 0.1481737942 0.0047259970 0.0239800000 578188573 0 402718720 -0.0565053523 -0.1160318330 -0.0072437539 804 1311867745.4151210785 0.1483334303 0.0962869807 0.1483334303 0.0047231608 0.0215580000 578191717 0 402718720 -0.0563577674 -0.1160479039 -0.0071606464 805 1311867745.4468600750 0.1481612027 0.0963514207 0.1483334303 0.0047264235 0.0220710000 578194861 0 402718720 -0.0565577745 -0.1161533147 -0.0072926767 806 1311867745.4826099873 0.1489035934 0.0964166220 0.1489035934 0.0047302367 0.0225530000 578198117 0 402718720 -0.0568169504 -0.1160920411 -0.0075654690 807 1311867745.5146310329 0.1490601003 0.0964818555 0.1490601003 0.0047280041 0.0222040000 578201261 0 402718720 -0.0566975698 -0.1158656478 -0.0074398774 808 1311867745.5466570854 0.1489305347 0.0965467672 0.1490601003 0.0047267337 0.0218300000 578204405 0 402718720 -0.0567816235 -0.1155463085 -0.0077041122 809 1311867745.5826489925 0.1489078104 0.0966114904 0.1490601003 0.0047243491 0.0229660000 578207717 0 402718720 -0.0565469675 -0.1157846153 -0.0074184844 810 1311867745.6148099899 0.1492194384 0.0966764385 0.1492194384 0.0047221712 0.0582750000 578210805 0 402718720 -0.0571266711 -0.1156935915 -0.0079065384 811 1311867745.6478629112 0.1495718956 0.0967416610 0.1495718956 0.0047206864 0.0228660000 578214005 0 402718720 -0.0573292486 -0.1159271747 -0.0079687247 812 1311867745.6825740337 0.1499863565 0.0968072333 0.1499863565 0.0047235069 0.0226980000 578217205 0 402718720 -0.0577523857 -0.1158874258 -0.0083075780 813 1311867745.7146449089 0.1504857987 0.0968732586 0.1504857987 0.0047211047 0.0220260000 578220405 0 402718720 -0.0580199771 -0.1155054048 -0.0088385371 814 1311867745.7466299534 0.1503905505 0.0969390046 0.1504857987 0.0047189150 0.0202670000 578223493 0 402718720 -0.0573689155 -0.1159413382 -0.0079851318 815 1311867745.7826039791 0.1509861350 0.0970053201 0.1509861350 0.0047179297 0.0231560000 578226749 0 402718720 -0.0580694564 -0.1157373562 -0.0087477397 816 1311867745.8145930767 0.1515732557 0.0970721926 0.1515732557 0.0047154347 0.0222380000 578229949 0 402718720 -0.0589083917 -0.1155542657 -0.0096448902 817 1311867745.8465878963 0.1516657472 0.0971390146 0.1516657472 0.0047129928 0.0226100000 578233037 0 402718720 -0.0592759736 -0.1155046374 -0.0102461232 818 1311867745.8826999664 0.1519752443 0.0972060515 0.1519752443 0.0047126926 0.0237650000 578236349 0 402718720 -0.0602886602 -0.1153168082 -0.0113945873 819 1311867745.9146699905 0.1526158452 0.0972737070 0.1526158452 0.0047153624 0.0239350000 578239493 0 402718720 -0.0611768812 -0.1152863503 -0.0125290854 820 1311867745.9467720985 0.1524023861 0.0973409371 0.1526158452 0.0047132208 0.0238160000 578242525 0 402718720 -0.0611271746 -0.1152508408 -0.0128601044 821 1311867745.9827370644 0.1531462073 0.0974089094 0.1531462073 0.0047191345 0.0242830000 578245837 0 402718720 -0.0618548132 -0.1151780561 -0.0138164759 822 1311867746.0146980286 0.1529823393 0.0974765170 0.1531462073 0.0047192073 0.0833760000 590552573 0 402718720 -0.0627987310 -0.1149308830 -0.0152487177 823 1311867746.0465910435 0.1535711884 0.0975446757 0.1535711884 0.0047207849 0.0143060000 594214925 0 402718720 -0.0649980828 -0.1137773469 -0.0177786201 824 1311867746.0825810432 0.1543738395 0.0976136432 0.1543738395 0.0047185193 0.0577880000 597410373 0 402718720 -0.0659335852 -0.1135732234 -0.0187300593 825 1311867746.1145880222 0.1544159353 0.0976824944 0.1544159353 0.0047162023 0.0210560000 597413517 0 402718720 -0.0657600090 -0.1135981008 -0.0186994597 826 1311867746.1468839645 0.1543580592 0.0977511089 0.1544159353 0.0047136928 0.0184610000 597416661 0 402718720 -0.0655385703 -0.1136161834 -0.0184586234 827 1311867746.1826870441 0.1559240669 0.0978214511 0.1559240669 0.0047117577 0.0262850000 597419973 0 402718720 -0.0683920458 -0.1132228076 -0.0213417728 828 1311867746.2146589756 0.1557430476 0.0978914047 0.1559240669 0.0047096440 0.0255250000 597423117 0 402718720 -0.0682921112 -0.1131666005 -0.0214893743 829 1311867746.2467160225 0.1544272006 0.0979596023 0.1559240669 0.0047099491 0.0188380000 597426205 0 402718720 -0.0655585229 -0.1136114672 -0.0184850246 830 1311867746.2827060223 0.1548455060 0.0980281395 0.1559240669 0.0047115403 0.0220070000 597429517 0 402718720 -0.0678234622 -0.1131672189 -0.0209219456 831 1311867746.3147549629 0.1557765007 0.0980976321 0.1559240669 0.0047105425 0.0229780000 597432605 0 402718720 -0.0692373961 -0.1129863337 -0.0224968754 832 1311867746.3466849327 0.1552133262 0.0981662808 0.1559240669 0.0047114218 0.0227110000 597435749 0 402718720 -0.0686852112 -0.1131410748 -0.0223803725 833 1311867746.3826711178 0.1543171853 0.0982336888 0.1559240669 0.0047097372 0.0210980000 597439061 0 402718720 -0.0667794645 -0.1134616584 -0.0198646802 834 1311867746.4146850109 0.1547643989 0.0983014715 0.1559240669 0.0047119781 0.0214350000 597442149 0 402718720 -0.0687599331 -0.1132450104 -0.0218151845 835 1311867746.4467220306 0.1551293880 0.0983695288 0.1559240669 0.0047121380 0.0210390000 597445293 0 402718720 -0.0690934286 -0.1130471379 -0.0222365521 836 1311867746.4826610088 0.1546620131 0.0984368644 0.1559240669 0.0047096500 0.0219420000 597448549 0 402718720 -0.0686871558 -0.1131518632 -0.0219063815 837 1311867746.5145390034 0.1545048505 0.0985038512 0.1559240669 0.0047095312 0.0202130000 597451749 0 402718720 -0.0690996423 -0.1131162345 -0.0223090705 838 1311867746.5468180180 0.1547422409 0.0985709614 0.1559240669 0.0047074845 0.0198180000 597454837 0 402718720 -0.0692152828 -0.1130346581 -0.0224139914 839 1311867746.5825469494 0.1545151025 0.0986376410 0.1559240669 0.0047047596 0.0485110000 597458093 0 402718720 -0.0689843595 -0.1130741462 -0.0220141225 840 1311867746.6145970821 0.1542629153 0.0987038616 0.1559240669 0.0047081553 0.0216770000 597461237 0 402718720 -0.0688847899 -0.1130145416 -0.0220910814 841 1311867746.6467320919 0.1542257220 0.0987698804 0.1559240669 0.0047053983 0.0200380000 597464381 0 402718720 -0.0688970163 -0.1130523831 -0.0221075192 842 1311867746.6827459335 0.1540010571 0.0988354756 0.1559240669 0.0047061814 0.0201150000 597467693 0 402718720 -0.0685277730 -0.1131309643 -0.0218048766 843 1311867746.7145600319 0.1539035887 0.0989007996 0.1559240669 0.0047035969 0.0198380000 597470781 0 402718720 -0.0684274882 -0.1132267788 -0.0217551496 844 1311867746.7465538979 0.1537304223 0.0989657636 0.1559240669 0.0047018281 0.0280570000 597473925 0 402718720 -0.0685151070 -0.1131727695 -0.0217938982 845 1311867746.7827410698 0.1535642445 0.0990303772 0.1559240669 0.0046994327 0.0199340000 597477237 0 402718720 -0.0683536902 -0.1132423356 -0.0215942599 846 1311867746.8146500587 0.1535485983 0.0990948195 0.1559240669 0.0046967108 0.0186300000 597480381 0 402718720 -0.0681029409 -0.1133110747 -0.0213600285 847 1311867746.8467810154 0.1532622725 0.0991587717 0.1559240669 0.0046940857 0.0178960000 597483469 0 402718720 -0.0677403733 -0.1133820191 -0.0208392330 848 1311867746.8827800751 0.1539042592 0.0992233300 0.1559240669 0.0046927425 0.0196310000 597486781 0 402718720 -0.0687172636 -0.1131245568 -0.0218826998 849 1311867746.9145510197 0.1543418169 0.0992882517 0.1559240669 0.0046961752 0.0192200000 597489925 0 402718720 -0.0690317377 -0.1130150557 -0.0221781377 850 1311867746.9466409683 0.1539129913 0.0993525161 0.1559240669 0.0046954321 0.0187240000 597493013 0 402718720 -0.0683191121 -0.1131638661 -0.0214072932 851 1311867746.9826910496 0.1541650742 0.0994169257 0.1559240669 0.0046930754 0.0189970000 597496325 0 402718720 -0.0685938671 -0.1131157652 -0.0215893853 852 1311867747.0145750046 0.1545436978 0.0994816285 0.1559240669 0.0046959804 0.0185830000 597499413 0 402718720 -0.0681489855 -0.1131762862 -0.0211560335 853 1311867747.0465710163 0.1539709121 0.0995455080 0.1559240669 0.0046970309 0.0184840000 597502557 0 402718720 -0.0681652278 -0.1131499186 -0.0212756712 854 1311867747.0825779438 0.1541413963 0.0996094377 0.1559240669 0.0046942827 0.0446610000 597505813 0 402718720 -0.0683322772 -0.1131359115 -0.0214976929 855 1311867747.1146280766 0.1548030823 0.0996739916 0.1559240669 0.0046925617 0.0205620000 597508957 0 402718720 -0.0692188665 -0.1129606366 -0.0223329253 856 1311867747.1475419998 0.1551806927 0.0997388359 0.1559240669 0.0046899799 0.0189920000 597512157 0 402718720 -0.0695092231 -0.1128943339 -0.0226566028 857 1311867747.1825768948 0.1545218378 0.0998027601 0.1559240669 0.0046876046 0.0187440000 597515357 0 402718720 -0.0681559741 -0.1131739840 -0.0211794637 858 1311867747.2146298885 0.1544958651 0.0998665049 0.1559240669 0.0046865734 0.0182670000 597518501 0 402718720 -0.0680280551 -0.1132334843 -0.0210066680 859 1311867747.2468459606 0.1547480822 0.0999303950 0.1559240669 0.0046840765 0.0181830000 597521645 0 402718720 -0.0682848468 -0.1131071970 -0.0211581476 860 1311867747.2828319073 0.1547861546 0.0999941808 0.1559240669 0.0046957128 0.0185360000 597524901 0 402718720 -0.0684776604 -0.1130356938 -0.0215168186 861 1311867747.3145720959 0.1549452096 0.1000580031 0.1559240669 0.0046985219 0.0181130000 597527989 0 402718720 -0.0680079162 -0.1131493300 -0.0211244598 862 1311867747.3468389511 0.1549946368 0.1001217347 0.1559240669 0.0046970812 0.0182190000 597531189 0 402718720 -0.0684512481 -0.1132191643 -0.0215632562 863 1311867747.3826510906 0.1553969234 0.1001857848 0.1559240669 0.0046945481 0.0184880000 597534445 0 402718720 -0.0689673498 -0.1130843461 -0.0219907053 864 1311867747.4149589539 0.1557581872 0.1002501047 0.1559240669 0.0046924799 0.0184420000 597537589 0 402718720 -0.0692382008 -0.1129683629 -0.0223550610 865 1311867747.4467270374 0.1555668265 0.1003140546 0.1559240669 0.0046963001 0.0181130000 597540677 0 402718720 -0.0685298741 -0.1131835505 -0.0216465462 866 1311867747.4827909470 0.1554768980 0.1003777531 0.1559240669 0.0046945228 0.0183920000 597543989 0 402718720 -0.0686981753 -0.1130861938 -0.0217130128 867 1311867747.5157780647 0.1557337046 0.1004416008 0.1559240669 0.0046931934 0.0177790000 597547077 0 402718720 -0.0686495006 -0.1129842922 -0.0215545055 868 1311867747.5466940403 0.1557952762 0.1005053723 0.1559240669 0.0046943568 0.0180110000 597550221 0 402718720 -0.0687019974 -0.1129795238 -0.0216731206 869 1311867747.5828940868 0.1561266780 0.1005693784 0.1561266780 0.0046945576 0.0184850000 597553533 0 402718720 -0.0692153648 -0.1130076423 -0.0224277917 870 1311867747.6151599884 0.1560768187 0.1006331800 0.1561266780 0.0046951448 0.0181100000 597556621 0 402718720 -0.0690771341 -0.1130274907 -0.0221606791 871 1311867747.6474270821 0.1562611610 0.1006970468 0.1562611610 0.0046965322 0.1056110000 609860069 0 402718720 -0.0693175420 -0.1129209846 -0.0223040711 872 1311867747.6827778816 0.1569124311 0.1007615140 0.1569124311 0.0048454432 0.0128220000 613522477 0 402718720 -0.0693795532 -0.1219909862 -0.0393758677 873 1311867747.7146589756 0.1569123864 0.1008258335 0.1569124311 0.0048433531 0.0135170000 616717869 0 402718720 -0.0698573142 -0.1220223159 -0.0398073681 874 1311867747.7479619980 0.1571984738 0.1008903330 0.1571984738 0.0048427520 0.0127020000 616720957 0 402718720 -0.0705435127 -0.1218095124 -0.0404592492 875 1311867747.7826869488 0.1567544490 0.1009541778 0.1571984738 0.0048405104 0.0132070000 616724213 0 402718720 -0.0698801130 -0.1219960451 -0.0398200415 876 1311867747.8149020672 0.1563347280 0.1010173976 0.1571984738 0.0048392848 0.0116550000 616727357 0 402718720 -0.0696997195 -0.1220502928 -0.0396760479 877 1311867747.8466539383 0.1570643336 0.1010813051 0.1571984738 0.0048385775 0.0124260000 616730445 0 402718720 -0.0710310191 -0.1217940524 -0.0410606451 878 1311867747.8827810287 0.1571925730 0.1011452132 0.1571984738 0.0048376714 0.0126210000 616733757 0 402718720 -0.0710267201 -0.1219183132 -0.0408821292 879 1311867747.9150440693 0.1566236317 0.1012083286 0.1571984738 0.0048364185 0.0123670000 616736957 0 402718720 -0.0704630911 -0.1220696345 -0.0405677184 880 1311867747.9477820396 0.1566793919 0.1012713639 0.1571984738 0.0048353578 0.0123800000 616740101 0 402718720 -0.0709094107 -0.1220857799 -0.0411714204 881 1311867747.9826579094 0.1566658765 0.1013342407 0.1571984738 0.0048329904 0.0161570000 616743301 0 402718720 -0.0713709444 -0.1219177917 -0.0416601971 882 1311867748.0146598816 0.1561157256 0.1013963512 0.1571984738 0.0048307627 0.0154740000 616746445 0 402718720 -0.0711072460 -0.1218746454 -0.0415419415 883 1311867748.0469100475 0.1557826102 0.1014579438 0.1571984738 0.0048283735 0.0157310000 616749533 0 402718720 -0.0710392669 -0.1218914464 -0.0415392034 884 1311867748.0828750134 0.1558037996 0.1015194210 0.1571984738 0.0048258035 0.0151120000 616752901 0 402718720 -0.0712861642 -0.1220330894 -0.0416150801 885 1311867748.1150569916 0.1554274857 0.1015803341 0.1571984738 0.0048233563 0.0151040000 616755989 0 402718720 -0.0709772781 -0.1220873594 -0.0415877588 886 1311867748.1486010551 0.1555881500 0.1016412910 0.1571984738 0.0048217389 0.0166740000 616759189 0 402718720 -0.0712855533 -0.1219916493 -0.0418146662 887 1311867748.1831040382 0.1553770304 0.1017018725 0.1571984738 0.0048190592 0.0172990000 616762333 0 402718720 -0.0711139515 -0.1219416261 -0.0418471657 888 1311867748.2148320675 0.1555344611 0.1017624947 0.1571984738 0.0048166080 0.0160750000 616765533 0 402718720 -0.0714383647 -0.1218916029 -0.0418164022 889 1311867748.2466599941 0.1552060246 0.1018226112 0.1571984738 0.0048173075 0.0151710000 616768621 0 402718720 -0.0707694218 -0.1220841482 -0.0414233096 890 1311867748.2827599049 0.1553392112 0.1018827422 0.1571984738 0.0048153230 0.0178380000 616771877 0 402718720 -0.0712231696 -0.1219734922 -0.0420018211 891 1311867748.3148829937 0.1549344808 0.1019422840 0.1571984738 0.0048195271 0.0151930000 616775021 0 402718720 -0.0708504617 -0.1220083982 -0.0415110663 892 1311867748.3470869064 0.1545919329 0.1020013083 0.1571984738 0.0048242108 0.0144750000 616778165 0 402718720 -0.0703350082 -0.1222710311 -0.0412284806 893 1311867748.3826999664 0.1550427526 0.1020607052 0.1571984738 0.0048219878 0.0191750000 616781421 0 402718720 -0.0712561458 -0.1220068038 -0.0421268754 894 1311867748.4148259163 0.1549378186 0.1021198518 0.1571984738 0.0048201845 0.0197550000 616784509 0 402718720 -0.0709587708 -0.1221679822 -0.0419101119 895 1311867748.4520189762 0.1544692069 0.1021783427 0.1571984738 0.0048270186 0.0509030000 616787821 0 402718720 -0.0707004443 -0.1222774833 -0.0416582786 896 1311867748.4831318855 0.1551268995 0.1022374371 0.1571984738 0.0048245586 0.0220800000 616790965 0 402718720 -0.0715380758 -0.1221977249 -0.0423396379 897 1311867748.5149960518 0.1548356414 0.1022960750 0.1571984738 0.0048254963 0.0195460000 616794109 0 402718720 -0.0710009858 -0.1222208068 -0.0419012569 898 1311867748.5467929840 0.1542860568 0.1023539703 0.1571984738 0.0048241582 0.0162540000 616797197 0 402718720 -0.0701913759 -0.1223702058 -0.0412688926 899 1311867748.5827159882 0.1547896415 0.1024122970 0.1571984738 0.0048214929 0.0196150000 616800453 0 402718720 -0.0709520429 -0.1223120987 -0.0418651775 900 1311867748.6147999763 0.1546027362 0.1024702864 0.1571984738 0.0048191182 0.0201640000 616803653 0 402718720 -0.0707447305 -0.1223277226 -0.0419003479 901 1311867748.6469130516 0.1545915902 0.1025281347 0.1571984738 0.0048340828 0.0190660000 616806685 0 402718720 -0.0708651915 -0.1222700700 -0.0418002531 902 1311867748.6827559471 0.1542446613 0.1025854701 0.1571984738 0.0048315168 0.0158830000 616809997 0 402718720 -0.0705075711 -0.1222212985 -0.0415070429 903 1311867748.7147359848 0.1537336260 0.1026421125 0.1571984738 0.0048486533 0.0168650000 616813141 0 402718720 -0.0696180090 -0.1225833967 -0.0409669802 904 1311867748.7499361038 0.1537860185 0.1026986876 0.1571984738 0.0048463706 0.0153880000 616816341 0 402718720 -0.0701809824 -0.1224553138 -0.0412264690 905 1311867748.7828259468 0.1536912024 0.1027550330 0.1571984738 0.0048436975 0.0185410000 616819597 0 402718720 -0.0703237876 -0.1225530431 -0.0414344370 906 1311867748.8151469231 0.1536291540 0.1028111854 0.1571984738 0.0048411485 0.0204260000 616822685 0 402718720 -0.0704849511 -0.1226570606 -0.0415587276 907 1311867748.8466329575 0.1530609131 0.1028665875 0.1571984738 0.0048386202 0.0215800000 616825773 0 402718720 -0.0701590925 -0.1226507500 -0.0414887071 908 1311867748.8829579353 0.1529840678 0.1029217830 0.1571984738 0.0048368197 0.0209780000 616829029 0 402718720 -0.0705606043 -0.1226100624 -0.0418546684 909 1311867748.9149119854 0.1523574740 0.1029761677 0.1571984738 0.0048342871 0.0229650000 616832229 0 402718720 -0.0702086538 -0.1226989031 -0.0417124666 910 1311867748.9472498894 0.1518139243 0.1030298356 0.1571984738 0.0048321693 0.0258510000 616835373 0 402718720 -0.0699448884 -0.1226478443 -0.0417726710 911 1311867748.9829359055 0.1519584507 0.1030835443 0.1571984738 0.0048297452 0.0348910000 616838629 0 402718720 -0.0704521462 -0.1228201762 -0.0420066118 912 1311867749.0159759521 0.1521047205 0.1031372955 0.1571984738 0.0048288883 0.0217270000 616841717 0 402718720 -0.0708542317 -0.1226818413 -0.0423561744 913 1311867749.0467190742 0.1516795158 0.1031904634 0.1571984738 0.0048272409 0.0227430000 616844861 0 402718720 -0.0701920912 -0.1228231713 -0.0418432131 914 1311867749.0828969479 0.1515879482 0.1032434147 0.1571984738 0.0048245973 0.0222240000 616848117 0 402718720 -0.0705868527 -0.1228081658 -0.0422375426 915 1311867749.1158421040 0.1522910893 0.1032970187 0.1571984738 0.0048219867 0.0210570000 616851317 0 402718720 -0.0715577751 -0.1226568446 -0.0430359393 916 1311867749.1485249996 0.1519220471 0.1033501028 0.1571984738 0.0048196501 0.0208370000 616854517 0 402718720 -0.0709510744 -0.1227599010 -0.0425522700 917 1311867749.1829619408 0.1514604092 0.1034025677 0.1571984738 0.0048177071 0.0209120000 616857717 0 402718720 -0.0708049238 -0.1227395460 -0.0426114798 918 1311867749.2156000137 0.1514974087 0.1034549586 0.1571984738 0.0048155531 0.0235430000 616860805 0 402718720 -0.0708528236 -0.1228064522 -0.0427262187 919 1311867749.2468719482 0.1507001221 0.1035063679 0.1571984738 0.0048129869 0.0629340000 616863893 0 402718720 -0.0696167201 -0.1229318455 -0.0416500382 920 1311867749.2828478813 0.1510767043 0.1035580748 0.1571984738 0.0048138605 0.0218400000 616867149 0 402718720 -0.0703629330 -0.1231212243 -0.0421392769 921 1311867749.3148140907 0.1512369961 0.1036098434 0.1571984738 0.0048115207 0.0202260000 616870349 0 402718720 -0.0709565282 -0.1228288040 -0.0425397530 922 1311867749.3468968868 0.1503733397 0.1036605630 0.1571984738 0.0048098119 0.0269380000 616873437 0 402718720 -0.0700163692 -0.1230027005 -0.0423231609 923 1311867749.3828470707 0.1508540511 0.1037116936 0.1571984738 0.0048073429 0.0211050000 616876693 0 402718720 -0.0709662139 -0.1228733584 -0.0428768881 924 1311867749.4147930145 0.1513674706 0.1037632691 0.1571984738 0.0048058217 0.0208190000 616879893 0 402718720 -0.0717487037 -0.1228209808 -0.0438412055 925 1311867749.4467489719 0.1511860043 0.1038145369 0.1571984738 0.0048046167 0.0244630000 616882981 0 402718720 -0.0709667355 -0.1231401265 -0.0434859991 926 1311867749.4829080105 0.1504013389 0.1038648466 0.1571984738 0.0048026318 0.0204810000 616886237 0 402718720 -0.0706839636 -0.1227907985 -0.0427899249 927 1311867749.5159850121 0.1490794867 0.1039136219 0.1571984738 0.0048006055 0.0269830000 616889381 0 402718720 -0.0691167563 -0.1230865866 -0.0421290807 928 1311867749.5468530655 0.1488753259 0.1039620720 0.1571984738 0.0047982690 0.0308280000 616892525 0 402718720 -0.0692550465 -0.1232792661 -0.0425314717 929 1311867749.5830268860 0.1479469389 0.1040094184 0.1571984738 0.0047961994 0.0302020000 616895781 0 402718720 -0.0688123703 -0.1232246533 -0.0423981957 930 1311867749.6148250103 0.1476193964 0.1040563109 0.1571984738 0.0047939942 0.0285490000 616898869 0 402718720 -0.0696082935 -0.1229731217 -0.0431222953 931 1311867749.6469049454 0.1469350755 0.1041023676 0.1571984738 0.0047925168 0.0313100000 616902069 0 402718720 -0.0688650906 -0.1230291948 -0.0427047499 932 1311867749.6829149723 0.1464023590 0.1041477538 0.1571984738 0.0047969682 0.0224350000 616905325 0 402718720 -0.0689752549 -0.1233718619 -0.0422194749 933 1311867749.7160799503 0.1451348513 0.1041916843 0.1571984738 0.0048025889 0.0671750000 616908469 0 402718720 -0.0679277554 -0.1232505068 -0.0425675996 934 1311867749.7468609810 0.1452026367 0.1042355932 0.1571984738 0.0048016617 0.0296760000 616911613 0 402718720 -0.0684572384 -0.1230849400 -0.0430692397 935 1311867749.7828791142 0.1442475170 0.1042783867 0.1571984738 0.0048007876 0.0293640000 616914869 0 402718720 -0.0679741651 -0.1229243204 -0.0430394299 936 1311867749.8148949146 0.1447775364 0.1043216550 0.1571984738 0.0048037333 0.0298310000 616917957 0 402718720 -0.0691924468 -0.1231003627 -0.0439986475 937 1311867749.8469030857 0.1444649100 0.1043644973 0.1571984738 0.0048012331 0.0282700000 616921157 0 402718720 -0.0688651875 -0.1231191084 -0.0438441187 938 1311867749.8829030991 0.1436659545 0.1044063966 0.1571984738 0.0048150485 0.0294370000 616924413 0 402718720 -0.0676414371 -0.1233930439 -0.0431415848 939 1311867749.9149639606 0.1435727328 0.1044481072 0.1571984738 0.0048395629 0.0287060000 616927501 0 402718720 -0.0687085241 -0.1228468418 -0.0444218330 940 1311867749.9508650303 0.1434024274 0.1044895480 0.1571984738 0.0048370073 0.0279530000 616930701 0 402718720 -0.0688805580 -0.1227979511 -0.0446964949 941 1311867749.9827940464 0.1425806731 0.1045300274 0.1571984738 0.0048350222 0.0291780000 616933957 0 402718720 -0.0680301413 -0.1229490340 -0.0443893969 942 1311867750.0147750378 0.1429187953 0.1045707798 0.1571984738 0.0048324995 0.0285120000 616937101 0 402718720 -0.0689031556 -0.1228696480 -0.0448977835 943 1311867750.0470540524 0.1422510594 0.1046107377 0.1571984738 0.0048299722 0.0260890000 616940189 0 402718720 -0.0682320744 -0.1229009703 -0.0445080996 944 1311867750.0829339027 0.1423113793 0.1046506748 0.1571984738 0.0048274150 0.0289320000 616943501 0 402718720 -0.0684074908 -0.1229604930 -0.0447757542 945 1311867750.1156339645 0.1418226957 0.1046900103 0.1571984738 0.0048249544 0.0653220000 616946589 0 402718720 -0.0678674504 -0.1230483875 -0.0446756184 946 1311867750.1474790573 0.1420225650 0.1047294739 0.1571984738 0.0048226467 0.0282050000 616949789 0 402718720 -0.0682579428 -0.1230175719 -0.0449086651 947 1311867750.1828711033 0.1421947330 0.1047690359 0.1571984738 0.0048217176 0.0274620000 616953045 0 402718720 -0.0685967430 -0.1228756234 -0.0453445949 948 1311867750.2156400681 0.1418949515 0.1048081983 0.1571984738 0.0048202202 0.0268430000 616956133 0 402718720 -0.0681637600 -0.1230305880 -0.0452305898 949 1311867750.2469079494 0.1419653594 0.1048473523 0.1571984738 0.0048186909 0.0276490000 616959277 0 402718720 -0.0678705946 -0.1233492643 -0.0449591838 950 1311867750.2829968929 0.1421347409 0.1048866022 0.1571984738 0.0048169848 0.0282080000 616962533 0 402718720 -0.0682147890 -0.1231019050 -0.0454484746 951 1311867750.3150129318 0.1415660828 0.1049251716 0.1571984738 0.0048146729 0.0279510000 616965733 0 402718720 -0.0672987476 -0.1231590956 -0.0447566099 952 1311867750.3469090462 0.1417140067 0.1049638153 0.1571984738 0.0048127272 0.0266930000 616968821 0 402718720 -0.0675683543 -0.1231145784 -0.0449178889 953 1311867750.3828659058 0.1422178745 0.1050029067 0.1571984738 0.0048103685 0.0229130000 616972077 0 402718720 -0.0679401159 -0.1230552495 -0.0453696065 954 1311867750.4148640633 0.1410920322 0.1050407359 0.1571984738 0.0048083984 0.0263200000 616975277 0 402718720 -0.0660169870 -0.1234922260 -0.0439368337 955 1311867750.4469859600 0.1406609565 0.1050780346 0.1571984738 0.0048065349 0.0289590000 616978365 0 402718720 -0.0658296943 -0.1235075146 -0.0440375954 956 1311867750.4829618931 0.1414613277 0.1051160924 0.1571984738 0.0048042271 0.0260150000 616981565 0 402718720 -0.0669623166 -0.1234543398 -0.0447769314 957 1311867750.5148859024 0.1407270879 0.1051533035 0.1571984738 0.0048019969 0.0252900000 616984653 0 402718720 -0.0656402484 -0.1238079816 -0.0436295383 958 1311867750.5476069450 0.1428340375 0.1051926362 0.1571984738 0.0048251911 0.0449230000 616987853 0 402718720 -0.0688716918 -0.1236100718 -0.0444866568 959 1311867750.5827779770 0.1414028406 0.1052303945 0.1571984738 0.0048476861 0.0301100000 616991109 0 402718720 -0.0671107620 -0.1234368980 -0.0453259572 960 1311867750.6148650646 0.1411991715 0.1052678620 0.1571984738 0.0048452359 0.0262720000 616994141 0 402718720 -0.0664893314 -0.1235585362 -0.0449295230 961 1311867750.6469810009 0.1411367655 0.1053051865 0.1571984738 0.0048432312 0.0253480000 616997397 0 402718720 -0.0666193962 -0.1235997230 -0.0450681560 962 1311867750.6829319000 0.1413013041 0.1053426045 0.1571984738 0.0048408861 0.0257920000 617000653 0 402718720 -0.0664143786 -0.1238987222 -0.0449622460 963 1311867750.7149219513 0.1414947808 0.1053801457 0.1571984738 0.0048390890 0.0238090000 617003853 0 402718720 -0.0669226795 -0.1234528869 -0.0452495851 964 1311867750.7469151020 0.1403973401 0.1054164706 0.1571984738 0.0048404171 0.0232840000 617006941 0 402718720 -0.0649454817 -0.1240301654 -0.0438078232 965 1311867750.7832129002 0.1409333348 0.1054532757 0.1571984738 0.0048379595 0.0274310000 617010141 0 402718720 -0.0657181889 -0.1240494028 -0.0446643792 966 1311867750.8149549961 0.1415910423 0.1054906854 0.1571984738 0.0048360222 0.0243790000 617013173 0 402718720 -0.0665430203 -0.1238384992 -0.0453500226 967 1311867750.8468461037 0.1413941532 0.1055278141 0.1571984738 0.0048368626 0.0257170000 617016317 0 402718720 -0.0658446103 -0.1238472536 -0.0448299982 968 1311867750.8828840256 0.1413739026 0.1055648452 0.1571984738 0.0048355602 0.0227660000 617019629 0 402718720 -0.0656175464 -0.1239353269 -0.0446831696 969 1311867750.9147970676 0.1416525245 0.1056020874 0.1571984738 0.0048331942 0.0600920000 617022717 0 402718720 -0.0658870190 -0.1238977909 -0.0449673198 970 1311867750.9468770027 0.1415087134 0.1056391045 0.1571984738 0.0048325251 0.0256940000 617025861 0 402718720 -0.0648389235 -0.1242020950 -0.0441980772 971 1311867750.9830369949 0.1410159767 0.1056755379 0.1571984738 0.0048304075 0.0262000000 617029173 0 402718720 -0.0639435202 -0.1244780868 -0.0433534421 972 1311867751.0168409348 0.1409405172 0.1057118188 0.1571984738 0.0048287562 0.0253170000 617032373 0 402718720 -0.0637893155 -0.1247151718 -0.0433171950 973 1311867751.0470340252 0.1411459297 0.1057482362 0.1571984738 0.0048274424 0.0266780000 617035461 0 402718720 -0.0645523444 -0.1244036406 -0.0442731716 974 1311867751.0828599930 0.1410229951 0.1057844525 0.1571984738 0.0048250563 0.0335430000 617038661 0 402718720 -0.0645004064 -0.1244385242 -0.0440228172 975 1311867751.1174809933 0.1400558352 0.1058196027 0.1571984738 0.0048226459 0.0250570000 617041917 0 402718720 -0.0635626838 -0.1243715957 -0.0434619412 976 1311867751.1468789577 0.1407575309 0.1058553997 0.1571984738 0.0048235093 0.0249780000 617044949 0 402718720 -0.0643979907 -0.1246303841 -0.0441567823 977 1311867751.1834619045 0.1407655030 0.1058911317 0.1571984738 0.0048239077 0.0247940000 617048205 0 402718720 -0.0647051409 -0.1243843585 -0.0445496328 978 1311867751.2160820961 0.1396692842 0.1059256697 0.1571984738 0.0048232018 0.0253610000 617051349 0 402718720 -0.0628732145 -0.1248299330 -0.0429270156 979 1311867751.2468481064 0.1408101022 0.1059613024 0.1571984738 0.0048216714 0.0234090000 617054493 0 402718720 -0.0649787039 -0.1243807003 -0.0445008203 980 1311867751.2831590176 0.1420296133 0.1059981068 0.1571984738 0.0048196438 0.0260800000 617057749 0 402718720 -0.0659261346 -0.1246213689 -0.0454052128 981 1311867751.3149859905 0.1404042840 0.1060331793 0.1571984738 0.0048180658 0.0254380000 617060893 0 402718720 -0.0637728646 -0.1244816557 -0.0439159982 982 1311867751.3498549461 0.1399703175 0.1060677385 0.1571984738 0.0048159446 0.0577270000 617064093 0 402718720 -0.0632807612 -0.1247137114 -0.0435812362 983 1311867751.3834669590 0.1417475939 0.1061040354 0.1571984738 0.0048197427 0.0176990000 617067349 0 402718720 -0.0660714209 -0.1246352941 -0.0440913998 984 1311867751.4151160717 0.1405414939 0.1061390329 0.1571984738 0.0048320720 0.0257750000 617070493 0 402718720 -0.0639730096 -0.1247225329 -0.0438437387 985 1311867751.4513740540 0.1396526396 0.1061730568 0.1571984738 0.0048333263 0.0254000000 617073637 0 402718720 -0.0634358004 -0.1245099679 -0.0435449481 986 1311867751.4838130474 0.1408469975 0.1062082231 0.1571984738 0.0048313204 0.0195680000 617076893 0 402718720 -0.0647265539 -0.1246200949 -0.0443739407 987 1311867751.5149779320 0.1404453069 0.1062429111 0.1571984738 0.0048300868 0.0236960000 617080037 0 402718720 -0.0645450577 -0.1244275421 -0.0446193144 988 1311867751.5495579243 0.1401975006 0.1062772781 0.1571984738 0.0048278449 0.0247550000 617083181 0 402718720 -0.0643981397 -0.1244195774 -0.0444148742 989 1311867751.5829720497 0.1410327554 0.1063124202 0.1571984738 0.0048260654 0.0248330000 617086381 0 402718720 -0.0654380545 -0.1242975295 -0.0453441404 990 1311867751.6149520874 0.1403352320 0.1063467866 0.1571984738 0.0048239911 0.0250970000 617089525 0 402718720 -0.0642579421 -0.1245067492 -0.0444408879 991 1311867751.6501100063 0.1399453282 0.1063806903 0.1571984738 0.0048217060 0.0259990000 617092669 0 402718720 -0.0640460253 -0.1245089769 -0.0441339090 992 1311867751.6837968826 0.1407004893 0.1064152869 0.1571984738 0.0048225377 0.0171090000 617095925 0 402718720 -0.0656778812 -0.1241053343 -0.0443848148 993 1311867751.7150709629 0.1401164085 0.1064492256 0.1571984738 0.0048281090 0.0263980000 617099013 0 402718720 -0.0645026937 -0.1243280470 -0.0444703922 994 1311867751.7506999969 0.1394822598 0.1064824580 0.1571984738 0.0048263428 0.0240330000 617102213 0 402718720 -0.0638568699 -0.1244298890 -0.0440336242 995 1311867751.7830109596 0.1393970549 0.1065155380 0.1571984738 0.0048241636 0.0536460000 617105413 0 402718720 -0.0634491220 -0.1246892586 -0.0437642410 996 1311867751.8149600029 0.1395723075 0.1065487275 0.1571984738 0.0048239079 0.0254580000 617108557 0 402718720 -0.0641110316 -0.1245802566 -0.0443723835 997 1311867751.8509531021 0.1394889057 0.1065817668 0.1571984738 0.0048222200 0.0232510000 617111813 0 402718720 -0.0640389249 -0.1243692487 -0.0441891067 998 1311867751.8832330704 0.1387838125 0.1066140334 0.1571984738 0.0048210701 0.0246770000 617114957 0 402718720 -0.0631929263 -0.1245870441 -0.0438021719 999 1311867751.9149179459 0.1396757811 0.1066471282 0.1571984738 0.0048205858 0.0241170000 617118045 0 402718720 -0.0643812567 -0.1244125888 -0.0447145365 1000 1311867751.9530498981 0.1398216933 0.1066803028 0.1571984738 0.0048196400 0.0535880000 617121357 0 402718720 -0.0636048764 -0.1249387115 -0.0436774157 1001 1311867751.9829521179 0.1394495666 0.1067130393 0.1571984738 0.0048176739 0.0236690000 617124501 0 402718720 -0.0631077290 -0.1249489412 -0.0436819009 1002 1311867752.0153670311 0.1400712430 0.1067463310 0.1571984738 0.0048154029 0.0257950000 617127589 0 402718720 -0.0641169623 -0.1246961951 -0.0446061976 1003 1311867752.0510149002 0.1397746801 0.1067792605 0.1571984738 0.0048136164 0.0248470000 617130789 0 402718720 -0.0632715672 -0.1247173324 -0.0438729264 1004 1311867752.0828840733 0.1392307281 0.1068115827 0.1571984738 0.0048123669 0.0256800000 617133989 0 402718720 -0.0622461438 -0.1250250936 -0.0430737659 1005 1311867752.1150429249 0.1400214136 0.1068446273 0.1571984738 0.0048112858 0.0239100000 617137077 0 402718720 -0.0630657747 -0.1249627024 -0.0437306054 1006 1311867752.1509859562 0.1401957572 0.1068777795 0.1571984738 0.0048089955 0.0212590000 617140389 0 402718720 -0.0630506575 -0.1251919270 -0.0432588533 1007 1311867752.1829679012 0.1396750659 0.1069103488 0.1571984738 0.0048066681 0.0224530000 617143589 0 402718720 -0.0623166673 -0.1250997782 -0.0429926515 1008 1311867752.2150039673 0.1404184997 0.1069435910 0.1571984738 0.0048046662 0.0235450000 617146733 0 402718720 -0.0632252991 -0.1251000166 -0.0436254553 1009 1311867752.2512340546 0.1413440257 0.1069776846 0.1571984738 0.0048039037 0.0231270000 617149933 0 402718720 -0.0636168793 -0.1251281947 -0.0438905805 1010 1311867752.2833271027 0.1414102018 0.1070117762 0.1571984738 0.0048035534 0.0213960000 617153077 0 402718720 -0.0631942302 -0.1253668368 -0.0432691909 1011 1311867752.3150799274 0.1412511319 0.1070456431 0.1571984738 0.0048024942 0.0160120000 617156165 0 402718720 -0.0637270957 -0.1251997650 -0.0432492234 1012 1311867752.3509979248 0.1408234537 0.1070790203 0.1571984738 0.0048020974 0.0202830000 617159421 0 402718720 -0.0619054437 -0.1255832016 -0.0424391404 1013 1311867752.3829851151 0.1405557096 0.1071120674 0.1571984738 0.0047999114 0.0236590000 617162621 0 402718720 -0.0616584234 -0.1257124394 -0.0421992242 1014 1311867752.4160280228 0.1409949064 0.1071454824 0.1571984738 0.0047985402 0.0489010000 617165765 0 402718720 -0.0625045747 -0.1256300062 -0.0424992852 1015 1311867752.4510710239 0.1404465139 0.1071782913 0.1571984738 0.0048104297 0.0226000000 617169021 0 402718720 -0.0623213612 -0.1254702359 -0.0426878594 1016 1311867752.4829080105 0.1401704550 0.1072107639 0.1571984738 0.0048128628 0.0195300000 617172165 0 402718720 -0.0618245192 -0.1256185174 -0.0420823544 1017 1311867752.5179650784 0.1400703341 0.1072430742 0.1571984738 0.0048169509 0.0214700000 617175309 0 402718720 -0.0621438101 -0.1257609129 -0.0425449498 1018 1311867752.5511059761 0.1408963948 0.1072761325 0.1571984738 0.0048200721 0.0175570000 617178509 0 402718720 -0.0631725118 -0.1255538315 -0.0430255160 1019 1311867752.5830090046 0.1400362998 0.1073082818 0.1571984738 0.0048178740 0.0195720000 617181709 0 402718720 -0.0622816235 -0.1255216300 -0.0426463373 1020 1311867752.6157000065 0.1405969560 0.1073409178 0.1571984738 0.0048157456 0.0194730000 617184741 0 402718720 -0.0630104765 -0.1254379749 -0.0429704152 1021 1311867752.6514921188 0.1409746706 0.1073738598 0.1571984738 0.0048139939 0.0169960000 617188053 0 402718720 -0.0635941848 -0.1253255010 -0.0431702659 1022 1311867752.6830079556 0.1403195262 0.1074060962 0.1571984738 0.0048129488 0.0207040000 617191197 0 402718720 -0.0627115220 -0.1254392117 -0.0428187214 1023 1311867752.7152760029 0.1402725428 0.1074382237 0.1571984738 0.0048110147 0.0186600000 617194341 0 402718720 -0.0620888360 -0.1258297116 -0.0420724340 1024 1311867752.7510609627 0.1398332417 0.1074698595 0.1571984738 0.0048090471 0.0318970000 617197541 0 402718720 -0.0623610094 -0.1255203485 -0.0424798466 1025 1311867752.7830259800 0.1400488466 0.1075016439 0.1571984738 0.0048103711 0.0219440000 617307181 0 402718720 -0.0633925125 -0.1252344847 -0.0435900986 1026 1311867752.8162770271 0.1407631934 0.1075340625 0.1571984738 0.0048082483 0.0251770000 617515125 0 402718720 -0.0640858412 -0.1254168451 -0.0438244864 1027 1311867752.8511059284 0.1406528503 0.1075663106 0.1571984738 0.0048059706 0.0212340000 617518381 0 402718720 -0.0635638237 -0.1253731698 -0.0434793830 1028 1311867752.8833000660 0.1411622465 0.1075989915 0.1571984738 0.0048036700 0.0209580000 617521581 0 402718720 -0.0642319396 -0.1252886355 -0.0439413562 1029 1311867752.9183709621 0.1418651044 0.1076322919 0.1571984738 0.0048016442 0.0234070000 617524781 0 402718720 -0.0643146113 -0.1253655553 -0.0439023301 1030 1311867752.9511129856 0.1413945109 0.1076650708 0.1571984738 0.0048025672 0.0335520000 617527925 0 402718720 -0.0632732362 -0.1255044490 -0.0430729128 1031 1311867752.9828579426 0.1416321099 0.1076980165 0.1571984738 0.0048002778 0.0203550000 617531125 0 402718720 -0.0637614578 -0.1254394501 -0.0435473584 1032 1311867753.0168049335 0.1420752108 0.1077313277 0.1571984738 0.0047980055 0.0226350000 617534213 0 402718720 -0.0641441271 -0.1254053265 -0.0436386578 1033 1311867753.0510199070 0.1413421035 0.1077638648 0.1571984738 0.0047960328 0.0216260000 617537469 0 402718720 -0.0629681349 -0.1255355179 -0.0427428521 1034 1311867753.0829060078 0.1418305933 0.1077968113 0.1571984738 0.0047940513 0.0247610000 617540557 0 402718720 -0.0638603717 -0.1254925877 -0.0435773097 1035 1311867753.1184151173 0.1426126957 0.1078304499 0.1571984738 0.0047919018 0.0220960000 617543813 0 402718720 -0.0647585317 -0.1254475415 -0.0441073179 1036 1311867753.1510760784 0.1412100196 0.1078626695 0.1571984738 0.0047900805 0.0226240000 617546957 0 402718720 -0.0623649433 -0.1257583946 -0.0422885604 1037 1311867753.1830070019 0.1417115629 0.1078953107 0.1571984738 0.0047878722 0.0211690000 617550045 0 402718720 -0.0638971850 -0.1255128533 -0.0435280055 1038 1311867753.2186250687 0.1428706348 0.1079290056 0.1571984738 0.0047856224 0.0258690000 617553301 0 402718720 -0.0651498213 -0.1255505830 -0.0444376729 1039 1311867753.2520470619 0.1420799047 0.1079618746 0.1571984738 0.0047839378 0.0236740000 617556445 0 402718720 -0.0634891316 -0.1257721633 -0.0433131903 1040 1311867753.2829909325 0.1421413124 0.1079947395 0.1571984738 0.0047827477 0.0231330000 617559589 0 402718720 -0.0637590066 -0.1258092374 -0.0435581468 1041 1311867753.3178219795 0.1432688236 0.1080286243 0.1571984738 0.0047810990 0.0252160000 617562733 0 402718720 -0.0652207732 -0.1258536577 -0.0447481237 1042 1311867753.3509368896 0.1426991373 0.1080618973 0.1571984738 0.0047798475 0.0196520000 617565933 0 402718720 -0.0639508367 -0.1259435713 -0.0436197482 1043 1311867753.3829340935 0.1421136409 0.1080945452 0.1571984738 0.0047780898 0.0215150000 617569133 0 402718720 -0.0630350187 -0.1261533797 -0.0429850854 1044 1311867753.4181840420 0.1429793537 0.1081279598 0.1571984738 0.0047758722 0.0209330000 617572277 0 402718720 -0.0640668944 -0.1262698770 -0.0439298265 1045 1311867753.4511721134 0.1423389167 0.1081606975 0.1571984738 0.0047744315 0.0227750000 617575477 0 402718720 -0.0631445050 -0.1264453828 -0.0433158241 1046 1311867753.4831509590 0.1421038508 0.1081931479 0.1571984738 0.0047721503 0.0216760000 617578677 0 402718720 -0.0635185763 -0.1263420582 -0.0438565537 1047 1311867753.5199398994 0.1423239112 0.1082257466 0.1571984738 0.0047699470 0.0211540000 617581933 0 402718720 -0.0645341948 -0.1263093948 -0.0445685722 1048 1311867753.5532588959 0.1415498406 0.1082575444 0.1571984738 0.0047680576 0.0210070000 617585077 0 402718720 -0.0635045543 -0.1266234368 -0.0438728668 1049 1311867753.5832290649 0.1415101141 0.1082892437 0.1571984738 0.0047659225 0.0205480000 617588221 0 402718720 -0.0642146617 -0.1264090389 -0.0447114892 1050 1311867753.6183090210 0.1413578838 0.1083207376 0.1571984738 0.0047646776 0.0193480000 617591421 0 402718720 -0.0641951784 -0.1266062409 -0.0446541198 1051 1311867753.6509299278 0.1409048587 0.1083517406 0.1571984738 0.0047627447 0.0198700000 617594621 0 402718720 -0.0635066479 -0.1267807782 -0.0441697650 1052 1311867753.6830120087 0.1410205066 0.1083827946 0.1571984738 0.0047611732 0.0192970000 617597709 0 402718720 -0.0640525296 -0.1267532557 -0.0446081385 1053 1311867753.7204699516 0.1412939429 0.1084140492 0.1571984738 0.0047590811 0.0188560000 617601021 0 402718720 -0.0644138157 -0.1267754883 -0.0450606532 1054 1311867753.7510209084 0.1401496232 0.1084441589 0.1571984738 0.0047583314 0.0207940000 617604109 0 402718720 -0.0628209114 -0.1270447820 -0.0439432301 1055 1311867753.7865009308 0.1401864290 0.1084742463 0.1571984738 0.0047584455 0.0182860000 617607309 0 402718720 -0.0637414530 -0.1270268261 -0.0447796658 1056 1311867753.8151769638 0.1418871731 0.1085058873 0.1571984738 0.0047602226 0.0272970000 617610341 0 402718720 -0.0659434944 -0.1269287914 -0.0461615175 1057 1311867753.8510670662 0.1399056911 0.1085355939 0.1571984738 0.0047590247 0.0170790000 617613653 0 402718720 -0.0630785227 -0.1271519959 -0.0443310998 1058 1311867753.8831028938 0.1398833543 0.1085652231 0.1571984738 0.0047619341 0.0185660000 617616797 0 402718720 -0.0629471391 -0.1277720779 -0.0433429554 1059 1311867753.9155681133 0.1399484575 0.1085948579 0.1571984738 0.0047644594 0.0187090000 617619885 0 402718720 -0.0636625513 -0.1275390536 -0.0446982160 1060 1311867753.9511620998 0.1398791522 0.1086243714 0.1571984738 0.0047637046 0.0445390000 617623197 0 402718720 -0.0637136176 -0.1275508851 -0.0446450338 1061 1311867753.9858930111 0.1386633962 0.1086526834 0.1571984738 0.0047674946 0.0186870000 617626397 0 402718720 -0.0621325001 -0.1280557960 -0.0429431014 1062 1311867754.0151700974 0.1377936453 0.1086801231 0.1571984738 0.0047723528 0.0181400000 617629429 0 402718720 -0.0622352287 -0.1276806593 -0.0438901335 1063 1311867754.0510439873 0.1383647472 0.1087080484 0.1571984738 0.0047748332 0.0173190000 617632797 0 402718720 -0.0632184520 -0.1276992708 -0.0451981761 1064 1311867754.0839030743 0.1374900788 0.1087350992 0.1571984738 0.0047752661 0.0512070000 629973869 0 402718720 -0.0619041398 -0.1280426979 -0.0440209582 1065 1311867754.1166028976 0.1370922476 0.1087617256 0.1571984738 0.0047750120 0.0118970000 633636277 0 402718720 -0.0620704554 -0.1281305104 -0.0432784110 1066 1311867754.1511039734 0.1375706643 0.1087887509 0.1571984738 0.0047750721 0.0212910000 636831613 0 402718720 -0.0635640696 -0.1278533787 -0.0449802205 1067 1311867754.1832070351 0.1377203614 0.1088158658 0.1571984738 0.0047758446 0.0483300000 636834757 0 402718720 -0.0632167459 -0.1281657666 -0.0447944291 1068 1311867754.2166299820 0.1365364492 0.1088418214 0.1571984738 0.0047777772 0.0142420000 636837901 0 402718720 -0.0621939078 -0.1282987148 -0.0441964678 1069 1311867754.2522869110 0.1364287436 0.1088676277 0.1571984738 0.0047833142 0.0158350000 636841213 0 402718720 -0.0630059317 -0.1281994879 -0.0451282859 1070 1311867754.2873139381 0.1359097064 0.1088929007 0.1571984738 0.0047908386 0.0125390000 636844413 0 402718720 -0.0624333806 -0.1283151060 -0.0447562709 1071 1311867754.3174090385 0.1349558979 0.1089172359 0.1571984738 0.0047924000 0.0146770000 636847501 0 402718720 -0.0621174909 -0.1284128428 -0.0447516590 1072 1311867754.3511719704 0.1344934106 0.1089410943 0.1571984738 0.0047929049 0.0219240000 636850757 0 402718720 -0.0623168126 -0.1284490228 -0.0452542566 1073 1311867754.3868749142 0.1341608614 0.1089645982 0.1571984738 0.0047930231 0.0158270000 636853901 0 402718720 -0.0624619871 -0.1285247505 -0.0455191433 1074 1311867754.4159760475 0.1336651593 0.1089875969 0.1571984738 0.0047925594 0.0174200000 636857101 0 402718720 -0.0617671907 -0.1285320073 -0.0449372344 1075 1311867754.4545960426 0.1327000707 0.1090096550 0.1571984738 0.0048030113 0.0259560000 636860357 0 402718720 -0.0611514971 -0.1285704076 -0.0445062518 1076 1311867754.4863569736 0.1322645992 0.1090312674 0.1571984738 0.0048107452 0.0748170000 649164557 0 402718720 -0.0604871288 -0.1285943389 -0.0442697220 1077 1311867754.5159039497 0.1337853968 0.1090542517 0.1571984738 0.0048095846 0.0162630000 652826797 0 402718720 -0.0658522621 -0.1266160607 -0.0495988838 1078 1311867754.5513699055 0.1332806200 0.1090767252 0.1571984738 0.0048096651 0.0123170000 656022245 0 402718720 -0.0648809597 -0.1268307269 -0.0486198775 1079 1311867754.5835869312 0.1324003339 0.1090983411 0.1571984738 0.0048090723 0.0116480000 656025389 0 402718720 -0.0641998574 -0.1267074943 -0.0480033904 1080 1311867754.6154859066 0.1325166076 0.1091200247 0.1571984738 0.0048069592 0.0116850000 656028477 0 402718720 -0.0646892712 -0.1266867667 -0.0485600121 1081 1311867754.6510920525 0.1320931017 0.1091412764 0.1571984738 0.0048053622 0.0117170000 656031733 0 402718720 -0.0641679764 -0.1267719120 -0.0480519831 1082 1311867754.6872670650 0.1311822236 0.1091616470 0.1571984738 0.0048033146 0.0252310000 656034933 0 402718720 -0.0631536618 -0.1267477870 -0.0472508036 1083 1311867754.7162880898 0.1320256889 0.1091827587 0.1571984738 0.0048025364 0.0116040000 656037965 0 402718720 -0.0645257831 -0.1267244220 -0.0488891490 1084 1311867754.7516000271 0.1327488273 0.1092044986 0.1571984738 0.0048008447 0.0118230000 656041277 0 402718720 -0.0650082678 -0.1268503517 -0.0494558886 1085 1311867754.7865169048 0.1306054741 0.1092242230 0.1571984738 0.0047995127 0.0295340000 656044421 0 402718720 -0.0626468137 -0.1264398545 -0.0469655916 1086 1311867754.8154330254 0.1292112023 0.1092426273 0.1571984738 0.0047977727 0.0330320000 656047453 0 402718720 -0.0633635148 -0.1249190271 -0.0465523712 1087 1311867754.8510210514 0.1305112988 0.1092621937 0.1571984738 0.0048040728 0.0119170000 656050765 0 402718720 -0.0644593835 -0.1259853095 -0.0478006639 1088 1311867754.8877279758 0.1298052073 0.1092810751 0.1571984738 0.0048020021 0.0276950000 656054021 0 402718720 -0.0630029291 -0.1268467456 -0.0455810800 1089 1311867754.9201200008 0.1280850619 0.1092983423 0.1571984738 0.0048000332 0.0300310000 656057165 0 402718720 -0.0621411949 -0.1257795393 -0.0457721241 1090 1311867754.9510319233 0.1285694391 0.1093160222 0.1571984738 0.0048000447 0.0253320000 656060309 0 402718720 -0.0640591979 -0.1252404749 -0.0469814613 1091 1311867754.9837698936 0.1284485310 0.1093335589 0.1571984738 0.0047999328 0.0552060000 656063453 0 402718720 -0.0645513833 -0.1251548082 -0.0464421660 1092 1311867755.0183610916 0.1266893297 0.1093494524 0.1571984738 0.0047979690 0.0297880000 656066653 0 402718720 -0.0633490160 -0.1244368404 -0.0448300242 1093 1311867755.0540759563 0.1269036829 0.1093655130 0.1571984738 0.0048002988 0.0275280000 656069909 0 402718720 -0.0631673783 -0.1250191778 -0.0448023751 1094 1311867755.0850980282 0.1266498268 0.1093813122 0.1571984738 0.0048020335 0.0281860000 656073109 0 402718720 -0.0631280169 -0.1247622669 -0.0447770469 1095 1311867755.1156840324 0.1264913082 0.1093969378 0.1571984738 0.0048029036 0.0285720000 656076085 0 402718720 -0.0631895810 -0.1246797293 -0.0450068638 1096 1311867755.1555950642 0.1256453544 0.1094117630 0.1571984738 0.0048007651 0.0268870000 656079453 0 402718720 -0.0628610030 -0.1244895086 -0.0436140858 1097 1311867755.1846981049 0.1258890033 0.1094267833 0.1571984738 0.0047992409 0.0279510000 656082597 0 402718720 -0.0634234771 -0.1243375614 -0.0450801440 1098 1311867755.2151050568 0.1262205094 0.1094420781 0.1571984738 0.0047974921 0.0265450000 656085629 0 402718720 -0.0634012446 -0.1246668249 -0.0449572206 1099 1311867755.2512140274 0.1252222657 0.1094564368 0.1571984738 0.0047962137 0.0272000000 656088885 0 402718720 -0.0617768280 -0.1249468848 -0.0444583669 1100 1311867755.2832860947 0.1243249252 0.1094699536 0.1571984738 0.0047942795 0.0260390000 656092029 0 402718720 -0.0624775104 -0.1242749095 -0.0442429446 1101 1311867755.3191769123 0.1247396395 0.1094838225 0.1571984738 0.0047922368 0.0251100000 656095285 0 402718720 -0.0638493150 -0.1244610101 -0.0452246629 1102 1311867755.3552980423 0.1232172623 0.1094962848 0.1571984738 0.0047906108 0.0252790000 656098597 0 402718720 -0.0619455613 -0.1248728335 -0.0436309241 1103 1311867755.3900039196 0.1219155565 0.1095075443 0.1571984738 0.0047900746 0.0251600000 656101741 0 402718720 -0.0621627271 -0.1241423339 -0.0437386669 1104 1311867755.4156520367 0.1231442392 0.1095198964 0.1571984738 0.0047882810 0.0631600000 656104773 0 402718720 -0.0636934787 -0.1242847219 -0.0467149056 1105 1311867755.4548349380 0.1224821359 0.1095316270 0.1571984738 0.0047864605 0.0253400000 656108085 0 402718720 -0.0617500506 -0.1251032501 -0.0454029739 1106 1311867755.4860599041 0.1228690371 0.1095436861 0.1571984738 0.0047847820 0.0596150000 668408453 0 402718720 -0.0621866435 -0.1254421473 -0.0456941091 1107 1311867755.5161869526 0.1246042401 0.1095572909 0.1571984738 0.0047836103 0.0303030000 672070693 0 402718720 -0.0648499429 -0.1256633401 -0.0473956615 1108 1311867755.5550830364 0.1243193075 0.1095706141 0.1571984738 0.0047814893 0.0230790000 675266253 0 402718720 -0.0642965585 -0.1255795658 -0.0466938913 1109 1311867755.5853939056 0.1247766763 0.1095843256 0.1571984738 0.0047794978 0.0305250000 675269397 0 402718720 -0.0648731142 -0.1256513894 -0.0468154997 1110 1311867755.6171081066 0.1247052401 0.1095979480 0.1571984738 0.0047776309 0.0286370000 675272485 0 402718720 -0.0646532103 -0.1253097057 -0.0480014049 1111 1311867755.6542870998 0.1247003153 0.1096115415 0.1571984738 0.0047756213 0.0273300000 675275797 0 402718720 -0.0646941438 -0.1256979108 -0.0465839468 1112 1311867755.6831660271 0.1240743697 0.1096245476 0.1571984738 0.0047736909 0.0127860000 675278829 0 402718720 -0.0640710741 -0.1259016991 -0.0462047383 1113 1311867755.7182629108 0.1213707328 0.1096351013 0.1571984738 0.0047727253 0.0283630000 675282085 0 402718720 -0.0629168153 -0.1238949746 -0.0465845056 1114 1311867755.7511401176 0.1236336678 0.1096476673 0.1571984738 0.0047713880 0.0285290000 675285229 0 402718720 -0.0648856312 -0.1256872714 -0.0480463170 1115 1311867755.7863209248 0.1231506318 0.1096597776 0.1571984738 0.0047692952 0.0232900000 675288429 0 402718720 -0.0642570332 -0.1261136681 -0.0467480086 1116 1311867755.8156828880 0.1229461581 0.1096716829 0.1571984738 0.0047671757 0.0633930000 675291573 0 402718720 -0.0649621263 -0.1255229712 -0.0483410805 1117 1311867755.8553929329 0.1241947711 0.1096846848 0.1571984738 0.0047652181 0.0296750000 675294829 0 402718720 -0.0662398860 -0.1257119626 -0.0502213463 1118 1311867755.8848280907 0.1235436276 0.1096970810 0.1571984738 0.0047636730 0.0265310000 675297973 0 402718720 -0.0646457374 -0.1262703240 -0.0480755568 1119 1311867755.9156160355 0.1234342307 0.1097093573 0.1571984738 0.0047618355 0.0289540000 675301117 0 402718720 -0.0653355792 -0.1258945614 -0.0488931946 1120 1311867755.9550280571 0.1248998493 0.1097229202 0.1571984738 0.0047597611 0.0299880000 675304373 0 402718720 -0.0669531524 -0.1262740046 -0.0502756275 1121 1311867755.9855079651 0.1247870401 0.1097363583 0.1571984738 0.0047579778 0.0299200000 675307461 0 402718720 -0.0663458630 -0.1263604909 -0.0495059006 1122 1311867756.0173759460 0.1235196739 0.1097486429 0.1571984738 0.0047561020 0.0290860000 675310549 0 402718720 -0.0651524141 -0.1255817711 -0.0492417999 1123 1311867756.0554299355 0.1254228801 0.1097626004 0.1571984738 0.0047544161 0.0285680000 675313805 0 402718720 -0.0669961870 -0.1261804700 -0.0511027575 1124 1311867756.0835859776 0.1242449209 0.1097754850 0.1571984738 0.0047525334 0.0270190000 675316893 0 402718720 -0.0650799051 -0.1263889223 -0.0483023487 1125 1311867756.1196799278 0.1232986376 0.1097875056 0.1571984738 0.0047514120 0.0283390000 675320149 0 402718720 -0.0658481643 -0.1253813058 -0.0481439233 1126 1311867756.1518061161 0.1247880235 0.1098008275 0.1571984738 0.0047497765 0.0275940000 675323125 0 402718720 -0.0669115037 -0.1259244233 -0.0502648279 1127 1311867756.1836869717 0.1242245287 0.1098136259 0.1571984738 0.0047478379 0.0268230000 675326213 0 402718720 -0.0650624037 -0.1265439391 -0.0485887416 1128 1311867756.2153429985 0.1238597482 0.1098260781 0.1571984738 0.0047457930 0.0566800000 675329245 0 402718720 -0.0652870312 -0.1263782084 -0.0478268415 1129 1311867756.2550570965 0.1247044653 0.1098392565 0.1571984738 0.0047437319 0.0270520000 675332445 0 402718720 -0.0665390790 -0.1260520518 -0.0497965626 1130 1311867756.2851510048 0.1250099093 0.1098526818 0.1571984738 0.0047457522 0.0263880000 675335589 0 402718720 -0.0665940493 -0.1261200160 -0.0493435226 1131 1311867756.3154039383 0.1242364496 0.1098653996 0.1571984738 0.0047436797 0.0251290000 675338621 0 402718720 -0.0655195042 -0.1260260642 -0.0481191352 1132 1311867756.3546020985 0.1242256239 0.1098780853 0.1571984738 0.0047416330 0.0255110000 675342045 0 402718720 -0.0656410903 -0.1259884238 -0.0482468046 1133 1311867756.3842909336 0.1246433184 0.1098911173 0.1571984738 0.0047396901 0.0264310000 675345077 0 402718720 -0.0659479275 -0.1258058548 -0.0497795604 1134 1311867756.4153299332 0.1245944872 0.1099040832 0.1571984738 0.0047376666 0.0248300000 675348109 0 402718720 -0.0660211965 -0.1262111962 -0.0481451452 1135 1311867756.4510889053 0.1237614006 0.1099162923 0.1571984738 0.0047364283 0.0258580000 675351309 0 402718720 -0.0660463348 -0.1254577190 -0.0482223220 1136 1311867756.4865260124 0.1241515130 0.1099288233 0.1571984738 0.0047366177 0.0250630000 675354621 0 402718720 -0.0662692413 -0.1257762611 -0.0491818599 1137 1311867756.5153410435 0.1238818467 0.1099410951 0.1571984738 0.0047351917 0.0246090000 675357709 0 402718720 -0.0653641447 -0.1260201633 -0.0485279970 1138 1311867756.5525779724 0.1241082102 0.1099535442 0.1571984738 0.0047338344 0.0251570000 675361021 0 402718720 -0.0657015964 -0.1258131564 -0.0491516925 1139 1311867756.5897810459 0.1242909431 0.1099661319 0.1571984738 0.0047318068 0.0249920000 675364333 0 402718720 -0.0659694672 -0.1261176914 -0.0479737446 1140 1311867756.6152539253 0.1233039796 0.1099778318 0.1571984738 0.0047297931 0.0223520000 675367197 0 402718720 -0.0647057518 -0.1259695590 -0.0469674803 1141 1311867756.6518189907 0.1226896644 0.1099889727 0.1571984738 0.0047277753 0.0421500000 675370453 0 402718720 -0.0643516853 -0.1254254580 -0.0470029451 1142 1311867756.6838989258 0.1239094585 0.1100011623 0.1571984738 0.0047258641 0.0253730000 675373541 0 402718720 -0.0656205937 -0.1258694679 -0.0477520935 1143 1311867756.7151489258 0.1232777983 0.1100127779 0.1571984738 0.0047238838 0.0198010000 675376629 0 402718720 -0.0644615516 -0.1257744431 -0.0466348268 1144 1311867756.7516241074 0.1228523776 0.1100240013 0.1571984738 0.0047224464 0.0131490000 675379885 0 402718720 -0.0638065264 -0.1256046444 -0.0469592549 1145 1311867756.7839419842 0.1233693883 0.1100356567 0.1571984738 0.0047234812 0.0210570000 675383085 0 402718720 -0.0645427480 -0.1256903559 -0.0470387898 1146 1311867756.8152918816 0.1241000220 0.1100479293 0.1571984738 0.0047216116 0.0255920000 675386117 0 402718720 -0.0649394393 -0.1262388080 -0.0464130081 1147 1311867756.8541939259 0.1225943789 0.1100588678 0.1571984738 0.0047209326 0.0119060000 675389485 0 402718720 -0.0631859824 -0.1256035119 -0.0461660810 1148 1311867756.8841879368 0.1235006377 0.1100705766 0.1571984738 0.0047286759 0.0231280000 675392629 0 402718720 -0.0650070980 -0.1259030104 -0.0470998771 1149 1311867756.9152240753 0.1220728010 0.1100810224 0.1571984738 0.0047266353 0.0121140000 675395661 0 402718720 -0.0630622581 -0.1257437766 -0.0453589000 1150 1311867756.9552290440 0.1220679283 0.1100914458 0.1571984738 0.0047257825 0.0115650000 675399085 0 402718720 -0.0632052943 -0.1256205440 -0.0461325869 1151 1311867756.9841670990 0.1232281774 0.1101028591 0.1571984738 0.0047238338 0.0205610000 675402117 0 402718720 -0.0644150898 -0.1260398030 -0.0472679399 1152 1311867757.0153179169 0.1207656264 0.1101121150 0.1571984738 0.0047218751 0.0143110000 675405205 0 402718720 -0.0616997443 -0.1255417168 -0.0444015488 1153 1311867757.0552799702 0.1210735813 0.1101216219 0.1571984738 0.0047205200 0.0123420000 675408629 0 402718720 -0.0627162233 -0.1251673251 -0.0461023711 1154 1311867757.0858480930 0.1218811572 0.1101318122 0.1571984738 0.0047193140 0.0120640000 675411717 0 402718720 -0.0636306182 -0.1259447187 -0.0454228818 1155 1311867757.1154010296 0.1192009896 0.1101396643 0.1571984738 0.0047201879 0.0223440000 675414749 0 402718720 -0.0613371991 -0.1255093366 -0.0414706320 1156 1311867757.1521968842 0.1195585281 0.1101478121 0.1571984738 0.0047188714 0.0122410000 675417949 0 402718720 -0.0626239255 -0.1253480911 -0.0437675379 1157 1311867757.1851840019 0.1202715114 0.1101565620 0.1571984738 0.0047173636 0.0144500000 675421149 0 402718720 -0.0627900213 -0.1263845563 -0.0437982269 1158 1311867757.2152419090 0.1178364679 0.1101631941 0.1571984738 0.0047194321 0.0201430000 675424293 0 402718720 -0.0618291833 -0.1254633367 -0.0417615138 1159 1311867757.2523880005 0.1170976683 0.1101691772 0.1571984738 0.0047237518 0.0260110000 675427549 0 402718720 -0.0644188598 -0.1240967363 -0.0419692770 1160 1311867757.2835650444 0.1183409467 0.1101762219 0.1571984738 0.0047217820 0.0269210000 675430637 0 402718720 -0.0656398758 -0.1243569925 -0.0449671336 1161 1311867757.3154449463 0.1176744550 0.1101826803 0.1571984738 0.0047256920 0.0330880000 675433837 0 402718720 -0.0635159314 -0.1250952631 -0.0437170714 1162 1311867757.3555309772 0.1167389229 0.1101883225 0.1571984738 0.0047243242 0.0169340000 675437205 0 402718720 -0.0629159063 -0.1246035248 -0.0452045240 1163 1311867757.3833310604 0.1178066805 0.1101948731 0.1571984738 0.0047223347 0.0126480000 675440181 0 402718720 -0.0637848228 -0.1253941506 -0.0453034863 1164 1311867757.4153690338 0.1158922315 0.1101997677 0.1571984738 0.0047211268 0.0172980000 675443325 0 402718720 -0.0621150695 -0.1245606467 -0.0438752696 1165 1311867757.4546790123 0.1168861240 0.1102055071 0.1571984738 0.0047192763 0.0121170000 675446581 0 402718720 -0.0634936467 -0.1249363199 -0.0455289595 1166 1311867757.4831800461 0.1174006686 0.1102116779 0.1571984738 0.0047175386 0.0130220000 675449669 0 402718720 -0.0639729276 -0.1254198849 -0.0446461178 1167 1311867757.5153949261 0.1147570536 0.1102155728 0.1571984738 0.0047186519 0.0234330000 675452757 0 402718720 -0.0634093434 -0.1237461567 -0.0420124978 1168 1311867757.5554668903 0.1157142967 0.1102202806 0.1571984738 0.0047177154 0.0244730000 675456069 0 402718720 -0.0641375855 -0.1241910979 -0.0443790182 1169 1311867757.5836620331 0.1158182845 0.1102250693 0.1571984738 0.0047157444 0.0123420000 675459157 0 402718720 -0.0628464222 -0.1249133945 -0.0442685522 1170 1311867757.6154699326 0.1150412485 0.1102291857 0.1571984738 0.0047143286 0.0148870000 675462301 0 402718720 -0.0628631264 -0.1244629771 -0.0439981818 1171 1311867757.6560699940 0.1158064455 0.1102339486 0.1571984738 0.0047125510 0.0143410000 675465557 0 402718720 -0.0638840869 -0.1247674674 -0.0449769087 1172 1311867757.6913650036 0.1161410436 0.1102389887 0.1571984738 0.0047106673 0.0129270000 675468813 0 402718720 -0.0637434945 -0.1253855228 -0.0441519432 1173 1311867757.7153298855 0.1151459739 0.1102431720 0.1571984738 0.0047087220 0.0124300000 675471733 0 402718720 -0.0624134913 -0.1250835657 -0.0439492539 1174 1311867757.7554829121 0.1152344346 0.1102474235 0.1571984738 0.0047069462 0.0133080000 675475101 0 402718720 -0.0634441003 -0.1251038909 -0.0436386466 1175 1311867757.7834401131 0.1144139916 0.1102509695 0.1571984738 0.0047053372 0.0146190000 675478189 0 402718720 -0.0627753586 -0.1247883290 -0.0431925692 1176 1311867757.8152821064 0.1131524369 0.1102534368 0.1571984738 0.0047036067 0.0225600000 675481277 0 402718720 -0.0612305515 -0.1245270893 -0.0427868962 1177 1311867757.8555200100 0.1108611897 0.1102539531 0.1571984738 0.0047031706 0.0407180000 675484645 0 402718720 -0.0604071170 -0.1226652935 -0.0434800424 1178 1311867757.8833820820 0.1128389910 0.1102561476 0.1571984738 0.0047046515 0.0211620000 675487733 0 402718720 -0.0612568259 -0.1247606650 -0.0432705320 1179 1311867757.9155299664 0.1135345325 0.1102589282 0.1571984738 0.0047027953 0.0165400000 675490821 0 402718720 -0.0618549362 -0.1257320344 -0.0429884531 1180 1311867757.9554359913 0.1129389182 0.1102611994 0.1571984738 0.0047008290 0.0193050000 675494189 0 402718720 -0.0613682084 -0.1253633201 -0.0434967019 1181 1311867757.9833920002 0.1133257896 0.1102637943 0.1571984738 0.0047049470 0.0384790000 675497277 0 402718720 -0.0617033876 -0.1253253818 -0.0441014916 1182 1311867758.0154359341 0.1134794727 0.1102665148 0.1571984738 0.0047030795 0.0253440000 675500477 0 402718720 -0.0614171922 -0.1263273954 -0.0418748781 1183 1311867758.0557460785 0.1146706343 0.1102702377 0.1571984738 0.0047010977 0.0238290000 675503845 0 402718720 -0.0626684576 -0.1273888052 -0.0417748280 1184 1311867758.0834350586 0.1156676188 0.1102747963 0.1571984738 0.0046991505 0.0249690000 675506821 0 402718720 -0.0626841709 -0.1289695799 -0.0405265205 1185 1311867758.1154539585 0.1146430895 0.1102784826 0.1571984738 0.0046973225 0.0235350000 675509965 0 402718720 -0.0621590242 -0.1281104833 -0.0412412211 1186 1311867758.1526179314 0.1141798794 0.1102817721 0.1571984738 0.0046993947 0.0238100000 675513221 0 402718720 -0.0622990951 -0.1279892772 -0.0411335304 1187 1311867758.1833200455 0.1142192408 0.1102850893 0.1571984738 0.0046993352 0.0225030000 675516365 0 402718720 -0.0626491308 -0.1279933900 -0.0415421091 1188 1311867758.2153439522 0.1151124239 0.1102891527 0.1571984738 0.0046981406 0.0236460000 675519453 0 402718720 -0.0631695539 -0.1291914582 -0.0412190333 1189 1311867758.2562429905 0.1157473996 0.1102937433 0.1571984738 0.0046963132 0.0232180000 675522877 0 402718720 -0.0641796291 -0.1298009008 -0.0415115356 1190 1311867758.2836740017 0.1158110648 0.1102983797 0.1571984738 0.0046944507 0.0227130000 675525909 0 402718720 -0.0634011403 -0.1307650805 -0.0402572006 1191 1311867758.3153231144 0.1159498990 0.1103031249 0.1571984738 0.0046952727 0.0226210000 675529109 0 402718720 -0.0645797029 -0.1306716353 -0.0410495512 1192 1311867758.3539550304 0.1152798906 0.1103073001 0.1571984738 0.0046933303 0.0225200000 675532421 0 402718720 -0.0640894398 -0.1303487271 -0.0420014150 1193 1311867758.3832499981 0.1144130453 0.1103107416 0.1571984738 0.0046915518 0.0217700000 675535453 0 402718720 -0.0637906268 -0.1296547949 -0.0423093736 1194 1311867758.4155290127 0.1131111905 0.1103130870 0.1571984738 0.0046902222 0.0213740000 675538597 0 402718720 -0.0630855858 -0.1291992068 -0.0418286026 1195 1311867758.4536859989 0.1140507236 0.1103162148 0.1571984738 0.0046884388 0.0564160000 675541909 0 402718720 -0.0645747930 -0.1293331832 -0.0435654782 1196 1311867758.4834630489 0.1145215780 0.1103197309 0.1571984738 0.0046864927 0.0222980000 675544997 0 402718720 -0.0652926564 -0.1295203418 -0.0438030288 1197 1311867758.5152559280 0.1142352670 0.1103230021 0.1571984738 0.0046850570 0.0208240000 675548085 0 402718720 -0.0638776720 -0.1305051595 -0.0413168706 1198 1311867758.5528900623 0.1143864989 0.1103263940 0.1571984738 0.0046836298 0.0214180000 675551397 0 402718720 -0.0649454296 -0.1302721798 -0.0422553197 1199 1311867758.5836958885 0.1154608950 0.1103306763 0.1571984738 0.0046818121 0.0212450000 675554541 0 402718720 -0.0658958554 -0.1308424026 -0.0434411317 1200 1311867758.6154530048 0.1159031987 0.1103353201 0.1571984738 0.0046798907 0.0212060000 675557685 0 402718720 -0.0648991466 -0.1325630546 -0.0410307832 1201 1311867758.6534969807 0.1140710637 0.1103384306 0.1571984738 0.0046781704 0.0209630000 675560997 0 402718720 -0.0649458915 -0.1304343939 -0.0429368094 1202 1311867758.6834859848 0.1140479743 0.1103415167 0.1571984738 0.0046766880 0.0208670000 675564085 0 402718720 -0.0655166358 -0.1300981492 -0.0433647372 1203 1311867758.7153160572 0.1147851050 0.1103452105 0.1571984738 0.0046748487 0.0207040000 675567229 0 402718720 -0.0653495342 -0.1315293163 -0.0415983014 1204 1311867758.7513840199 0.1145860925 0.1103487328 0.1571984738 0.0046730153 0.0211730000 675570373 0 402718720 -0.0655763894 -0.1309920698 -0.0429765768 1205 1311867758.7833371162 0.1147360578 0.1103523737 0.1571984738 0.0046712943 0.0206410000 675573573 0 402718720 -0.0655909702 -0.1314525008 -0.0420914479 1206 1311867758.8154289722 0.1150195226 0.1103562437 0.1571984738 0.0046693869 0.0205910000 675576605 0 402718720 -0.0654126406 -0.1322419047 -0.0414731428 1207 1311867758.8514270782 0.1156589165 0.1103606370 0.1571984738 0.0046686604 0.0210700000 675579861 0 402718720 -0.0655677393 -0.1332127601 -0.0410104804 1208 1311867758.8837060928 0.1158178151 0.1103651545 0.1571984738 0.0046670919 0.0206730000 675583061 0 402718720 -0.0664720610 -0.1330132335 -0.0416786186 1209 1311867758.9153480530 0.1217979789 0.1103746109 0.1571984738 0.0046724087 0.0211270000 675586093 0 402718720 -0.0676812679 -0.1392521709 -0.0419199690 1210 1311867758.9514510632 0.1253321022 0.1103869725 0.1571984738 0.0046726187 0.0218240000 675589349 0 402718720 -0.0687452257 -0.1432532072 -0.0411635265 1211 1311867758.9835269451 0.1325180829 0.1104052476 0.1571984738 0.0046739187 0.0232910000 675592549 0 402718720 -0.0715178996 -0.1506043673 -0.0394112319 1212 1311867759.0155270100 0.1362609267 0.1104265806 0.1571984738 0.0046732819 0.0236740000 675595637 0 402718720 -0.0726718828 -0.1544007510 -0.0395200104 1213 1311867759.0514900684 0.1374008805 0.1104488183 0.1571984738 0.0046718697 0.0227260000 675598949 0 402718720 -0.0723938495 -0.1560190469 -0.0395618752 1214 1311867759.0835061073 0.1393627375 0.1104726354 0.1571984738 0.0046705437 0.0226550000 675602093 0 402718720 -0.0729578882 -0.1580553949 -0.0394854732 1215 1311867759.1153709888 0.1410394311 0.1104977932 0.1571984738 0.0046693584 0.0229540000 675605125 0 402718720 -0.0731955394 -0.1598445177 -0.0396110602 1216 1311867759.1514580250 0.1429643333 0.1105244927 0.1571984738 0.0046682066 0.0228210000 675608381 0 402718720 -0.0734785125 -0.1615029424 -0.0393782109 1217 1311867759.1834299564 0.1438664198 0.1105518895 0.1571984738 0.0046662916 0.0218830000 675611469 0 402718720 -0.0735834688 -0.1627481133 -0.0387492143 1218 1311867759.2154660225 0.1444935352 0.1105797562 0.1571984738 0.0046710759 0.0570270000 675614613 0 402718720 -0.0737745389 -0.1643567383 -0.0381411500 1219 1311867759.2515718937 0.1450644284 0.1106080455 0.1571984738 0.0046692599 0.0228520000 675617813 0 402718720 -0.0737118647 -0.1654285640 -0.0379711650 1220 1311867759.2835140228 0.1454796791 0.1106366288 0.1571984738 0.0046674035 0.0217320000 675621013 0 402718720 -0.0738090202 -0.1662857234 -0.0376650020 1221 1311867759.3154840469 0.1463852823 0.1106659070 0.1571984738 0.0046655224 0.0217300000 675624101 0 402718720 -0.0741264224 -0.1674323082 -0.0378525779 1222 1311867759.3515789509 0.1474035978 0.1106959706 0.1571984738 0.0046639870 0.0215360000 675627357 0 402718720 -0.0743780956 -0.1687596440 -0.0374363549 1223 1311867759.3834340572 0.1476721019 0.1107262045 0.1571984738 0.0046644486 0.0214020000 675630501 0 402718720 -0.0742853060 -0.1693428755 -0.0370889604 1224 1311867759.4153990746 0.1490580291 0.1107575214 0.1571984738 0.0046633589 0.0212080000 675633701 0 402718720 -0.0747298896 -0.1710135043 -0.0373039804 1225 1311867759.4514269829 0.1483688205 0.1107882245 0.1571984738 0.0046617324 0.0214480000 675636845 0 402718720 -0.0747859627 -0.1702534705 -0.0376717001 1226 1311867759.4834520817 0.1485383660 0.1108190158 0.1571984738 0.0046613583 0.0209920000 675640045 0 402718720 -0.0748816282 -0.1701930016 -0.0373882391 1227 1311867759.5152900219 0.1471346170 0.1108486129 0.1571984738 0.0046600404 0.0207610000 675643245 0 402718720 -0.0744978413 -0.1693682969 -0.0374869294 1228 1311867759.5514860153 0.1468524337 0.1108779319 0.1571984738 0.0046582551 0.0207760000 675646445 0 402718720 -0.0745132193 -0.1692568213 -0.0376642868 1229 1311867759.5836830139 0.1462707669 0.1109067300 0.1571984738 0.0046566130 0.0208010000 675649589 0 402718720 -0.0744256824 -0.1689272374 -0.0373878889 1230 1311867759.6155130863 0.1460238993 0.1109352805 0.1571984738 0.0046548404 0.0208370000 675652677 0 402718720 -0.0740716308 -0.1691736281 -0.0373232141 1231 1311867759.6515491009 0.1459634304 0.1109637356 0.1571984738 0.0046532871 0.0208710000 675655821 0 402718720 -0.0741836727 -0.1691278070 -0.0380451195 1232 1311867759.6835169792 0.1456347257 0.1109918776 0.1571984738 0.0046516570 0.0208140000 675659021 0 402718720 -0.0742852315 -0.1688940674 -0.0379274786 1233 1311867759.7156159878 0.1454956532 0.1110198612 0.1571984738 0.0046498158 0.0497550000 675662165 0 402718720 -0.0743112490 -0.1689307094 -0.0382119305 1234 1311867759.7515261173 0.1452438533 0.1110475954 0.1571984738 0.0046489766 0.0323100000 675665421 0 402718720 -0.0742545798 -0.1692404747 -0.0383531265 1235 1311867759.7835481167 0.1456731856 0.1110756323 0.1571984738 0.0046513947 0.0216260000 675668565 0 402718720 -0.0745807439 -0.1693224311 -0.0379656591 1236 1311867759.8155291080 0.1452540159 0.1111032847 0.1571984738 0.0046536796 0.0216980000 675671709 0 402718720 -0.0746606141 -0.1696262956 -0.0377248265 1237 1311867759.8514630795 0.1443816423 0.1111301872 0.1571984738 0.0046531745 0.0223440000 675674965 0 402718720 -0.0745885074 -0.1689659953 -0.0386228673 1238 1311867759.8835089207 0.1445892900 0.1111572139 0.1571984738 0.0046864166 0.0222670000 675678109 0 402718720 -0.0746875331 -0.1685840786 -0.0385158285 1239 1311867759.9155631065 0.1438939720 0.1111836359 0.1571984738 0.0047140703 0.0216220000 675681197 0 402718720 -0.0743840113 -0.1694085747 -0.0377172194 1240 1311867759.9514820576 0.1438686252 0.1112099947 0.1571984738 0.0047122584 0.0217210000 675684453 0 402718720 -0.0745469257 -0.1697516888 -0.0386972204 1241 1311867759.9835360050 0.1429877728 0.1112356013 0.1571984738 0.0047117057 0.0216930000 675687653 0 402718720 -0.0743618980 -0.1690598428 -0.0387948677 1242 1311867760.0155169964 0.1415018141 0.1112599702 0.1571984738 0.0047107114 0.0217640000 675690797 0 402718720 -0.0742480010 -0.1678403616 -0.0389302224 1243 1311867760.0515780449 0.1429750770 0.1112854852 0.1571984738 0.0047089415 0.0217120000 675693997 0 402718720 -0.0745681301 -0.1695764363 -0.0391565636 1244 1311867760.0833919048 0.1427948624 0.1113108143 0.1571984738 0.0047072808 0.0215770000 675697141 0 402718720 -0.0746506527 -0.1694452912 -0.0398046635 1245 1311867760.1155309677 0.1420299560 0.1113354883 0.1571984738 0.0047132697 0.0216610000 675700341 0 402718720 -0.0743561760 -0.1689507216 -0.0390472077 1246 1311867760.1515870094 0.1418910921 0.1113600113 0.1571984738 0.0047173303 0.0195740000 675703541 0 402718720 -0.0742672756 -0.1686530262 -0.0395947732 1247 1311867760.1835420132 0.1417770833 0.1113844035 0.1571984738 0.0047161042 0.0563590000 675706741 0 402718720 -0.0741625279 -0.1688002646 -0.0400257967 1248 1311867760.2154819965 0.1418386251 0.1114088059 0.1571984738 0.0047143862 0.0224600000 675709829 0 402718720 -0.0740024075 -0.1690097153 -0.0393978916 1249 1311867760.2515039444 0.1421771646 0.1114334403 0.1571984738 0.0047125719 0.0210380000 675713085 0 402718720 -0.0747000948 -0.1696511209 -0.0393065922 1250 1311867760.2838139534 0.1412440091 0.1114572887 0.1571984738 0.0047110005 0.0209250000 675716285 0 402718720 -0.0743410811 -0.1690266430 -0.0400817804 1251 1311867760.3155200481 0.1409247518 0.1114808439 0.1571984738 0.0047094071 0.0219640000 675719373 0 402718720 -0.0741393939 -0.1691773832 -0.0401182845 1252 1311867760.3515191078 0.1406132728 0.1115041126 0.1571984738 0.0047121881 0.0216970000 675722629 0 402718720 -0.0740549490 -0.1695191562 -0.0400637686 1253 1311867760.3835508823 0.1402977109 0.1115270923 0.1571984738 0.0047107756 0.0221980000 675725773 0 402718720 -0.0746141821 -0.1695120037 -0.0406282209 1254 1311867760.4155271053 0.1401606202 0.1115499261 0.1571984738 0.0047157752 0.0216040000 675728861 0 402718720 -0.0745378882 -0.1692683399 -0.0413164012 1255 1311867760.4515271187 0.1401053667 0.1115726794 0.1571984738 0.0047139179 0.0210170000 675732117 0 402718720 -0.0739702582 -0.1696511209 -0.0412495844 1256 1311867760.4837100506 0.1393872648 0.1115948248 0.1571984738 0.0047126206 0.0208180000 675735373 0 402718720 -0.0742665380 -0.1694170088 -0.0421459191 1257 1311867760.5156090260 0.1389977932 0.1116166251 0.1571984738 0.0047122064 0.0214080000 675738517 0 402718720 -0.0739371926 -0.1687978357 -0.0426807962 1258 1311867760.5515379906 0.1375937462 0.1116372746 0.1571984738 0.0047111948 0.0211980000 675741717 0 402718720 -0.0734949708 -0.1677716374 -0.0428712927 1259 1311867760.5836648941 0.1370068043 0.1116574251 0.1571984738 0.0047101915 0.0207340000 675744861 0 402718720 -0.0736149848 -0.1673481762 -0.0431392342 1260 1311867760.6154201031 0.1380616724 0.1116783809 0.1571984738 0.0047088457 0.0222000000 675748061 0 402718720 -0.0738635659 -0.1685782969 -0.0437113754 1261 1311867760.6512589455 0.1367197335 0.1116982392 0.1571984738 0.0047100070 0.0219510000 675751261 0 402718720 -0.0735718012 -0.1673562974 -0.0435370393 1262 1311867760.6834840775 0.1366568953 0.1117180163 0.1571984738 0.0047084453 0.0551450000 675754405 0 402718720 -0.0735171884 -0.1677929610 -0.0433690138 1263 1311867760.7154428959 0.1385912597 0.1117392936 0.1571984738 0.0047077184 0.0222330000 675757549 0 402718720 -0.0741788447 -0.1697452515 -0.0441003740 1264 1311867760.7515759468 0.1383555084 0.1117603507 0.1571984738 0.0047065356 0.0215520000 675760861 0 402718720 -0.0741706043 -0.1696752012 -0.0441106148 1265 1311867760.7836549282 0.1367928684 0.1117801393 0.1571984738 0.0047063595 0.0215970000 675764005 0 402718720 -0.0738209412 -0.1684002578 -0.0440992638 1266 1311867760.8155579567 0.1362262815 0.1117994490 0.1571984738 0.0047048260 0.0216260000 675767149 0 402718720 -0.0737694278 -0.1677118391 -0.0452777855 1267 1311867760.8514490128 0.1380906999 0.1118201998 0.1571984738 0.0047030988 0.0215210000 675770349 0 402718720 -0.0745257512 -0.1692775786 -0.0449231938 1268 1311867760.8834939003 0.1384164244 0.1118411748 0.1571984738 0.0047013250 0.0212620000 675773493 0 402718720 -0.0745476782 -0.1696234941 -0.0449797660 1269 1311867760.9194259644 0.1406576335 0.1118638828 0.1571984738 0.0047088309 0.0210390000 675776805 0 402718720 -0.0751660988 -0.1717568934 -0.0455746762 1270 1311867760.9515960217 0.1393798441 0.1118855489 0.1571984738 0.0047075181 0.0221130000 675779893 0 402718720 -0.0748063847 -0.1705178916 -0.0450399406 1271 1311867760.9834759235 0.1394176930 0.1119072107 0.1571984738 0.0047057265 0.0210400000 675783037 0 402718720 -0.0748840421 -0.1704757512 -0.0451248400 1272 1311867761.0197150707 0.1387482882 0.1119283121 0.1571984738 0.0047039532 0.0223180000 675786349 0 402718720 -0.0750447810 -0.1697197556 -0.0457238071 1273 1311867761.0516259670 0.1378171891 0.1119486491 0.1571984738 0.0047022112 0.1034800000 688091977 0 402718720 -0.0748680755 -0.1686062962 -0.0461804830 1274 1311867761.0834660530 0.1388521641 0.1119697664 0.1571984738 0.0047341282 0.0158940000 691754385 0 402718720 -0.0799218714 -0.1677830517 -0.0409730524 1275 1311867761.1196739674 0.1386490613 0.1119906913 0.1571984738 0.0047341074 0.0155470000 694949889 0 402718720 -0.0799330771 -0.1674892157 -0.0414389595 1276 1311867761.1515359879 0.1387615353 0.1120116716 0.1571984738 0.0047322669 0.0156190000 694952921 0 402718720 -0.0799753517 -0.1674930155 -0.0416377895 1277 1311867761.1834900379 0.1387852430 0.1120326376 0.1571984738 0.0047306952 0.0349020000 694956121 0 402718720 -0.0800126418 -0.1676628441 -0.0410114229 1278 1311867761.2197170258 0.1384399682 0.1120533006 0.1571984738 0.0047289080 0.0193470000 694959433 0 402718720 -0.0799812376 -0.1675641686 -0.0418477543 1279 1311867761.2516000271 0.1383696049 0.1120738763 0.1571984738 0.0047271869 0.0162630000 694962465 0 402718720 -0.0798111111 -0.1675533205 -0.0430470780 1280 1311867761.2837359905 0.1383345872 0.1120943925 0.1571984738 0.0047257256 0.0167030000 694965665 0 402718720 -0.0800521672 -0.1676254272 -0.0418739021 1281 1311867761.3195490837 0.1377597898 0.1121144279 0.1571984738 0.0047244160 0.0159490000 694968921 0 402718720 -0.0798528865 -0.1674323380 -0.0421061777 1282 1311867761.3516459465 0.1377462596 0.1121344216 0.1571984738 0.0047225914 0.0168680000 694972009 0 402718720 -0.0798477009 -0.1675563604 -0.0432230979 1283 1311867761.3834578991 0.1376481652 0.1121543076 0.1571984738 0.0047208756 0.0151840000 694975209 0 402718720 -0.0796510652 -0.1677529514 -0.0422329232 1284 1311867761.4195950031 0.1371447593 0.1121737705 0.1571984738 0.0047200016 0.0159940000 694978465 0 402718720 -0.0798356831 -0.1674859673 -0.0428126678 1285 1311867761.4516580105 0.1371984631 0.1121932450 0.1571984738 0.0047182354 0.0283500000 694981553 0 402718720 -0.0798306093 -0.1675927490 -0.0439224765 1286 1311867761.4836299419 0.1372441351 0.1122127247 0.1571984738 0.0047164302 0.0166390000 694984753 0 402718720 -0.0798349977 -0.1676995307 -0.0430896766 1287 1311867761.5195589066 0.1372333914 0.1122321658 0.1571984738 0.0047151693 0.0148670000 694988009 0 402718720 -0.0799476653 -0.1679925025 -0.0422484316 1288 1311867761.5516500473 0.1373268664 0.1122516493 0.1571984738 0.0047141088 0.0425840000 694991097 0 402718720 -0.0795990378 -0.1684778780 -0.0437109061 1289 1311867761.5835580826 0.1365225017 0.1122704785 0.1571984738 0.0047124137 0.0295030000 694994241 0 402718720 -0.0796179995 -0.1675012708 -0.0441088267 1290 1311867761.6195700169 0.1371055692 0.1122897305 0.1571984738 0.0047116644 0.0329230000 694997497 0 402718720 -0.0795420483 -0.1684070677 -0.0429512076 1291 1311867761.6516530514 0.1358187646 0.1123079559 0.1571984738 0.0047103638 0.0275030000 695000585 0 402718720 -0.0792611018 -0.1672124416 -0.0440635681 1292 1311867761.6837658882 0.1361859143 0.1123264373 0.1571984738 0.0047108964 0.0340740000 695003785 0 402718720 -0.0794086754 -0.1676529497 -0.0444181934 1293 1311867761.7196850777 0.1367914826 0.1123453584 0.1571984738 0.0047136124 0.0783220000 695007041 0 402718720 -0.0791245624 -0.1683162749 -0.0441608466 1294 1311867761.7515189648 0.1362612844 0.1123638406 0.1571984738 0.0047132051 0.0291630000 695010073 0 402718720 -0.0792904273 -0.1678187251 -0.0437268727 1295 1311867761.7835309505 0.1357945502 0.1123819338 0.1571984738 0.0047131868 0.1101840000 707317497 0 402718720 -0.0790549144 -0.1674680859 -0.0448873714 1296 1311867761.8194708824 0.1256374717 0.1123921619 0.1571984738 0.0049415753 0.0149480000 710980017 0 402718720 -0.0867814198 -0.1511497796 -0.0332345925 1297 1311867761.8517661095 0.1276202798 0.1124039029 0.1571984738 0.0049398439 0.0635170000 714175297 0 402718720 -0.0878844932 -0.1526913643 -0.0333318524 1298 1311867761.8837049007 0.1260116994 0.1124143866 0.1571984738 0.0049380185 0.0151020000 714178497 0 402718720 -0.0867730826 -0.1513217390 -0.0338066928 1299 1311867761.9197390079 0.1264169216 0.1124251660 0.1571984738 0.0049361333 0.0158020000 714181809 0 402718720 -0.0869715735 -0.1513372362 -0.0334329419 1300 1311867761.9517469406 0.1267196834 0.1124361618 0.1571984738 0.0049346144 0.0159340000 714184897 0 402718720 -0.0868590549 -0.1517537832 -0.0330616236 1301 1311867761.9835391045 0.1262199581 0.1124467566 0.1571984738 0.0049328690 0.0155950000 714188041 0 402718720 -0.0866457820 -0.1513252854 -0.0335321687 1302 1311867762.0195510387 0.1273413152 0.1124581963 0.1571984738 0.0049312575 0.0525750000 714191297 0 402718720 -0.0871075466 -0.1526591629 -0.0340235233 1303 1311867762.0515589714 0.1260901690 0.1124686583 0.1571984738 0.0049329731 0.0159120000 714194441 0 402718720 -0.0866394043 -0.1512007266 -0.0343514048 1304 1311867762.0835978985 0.1253687590 0.1124785510 0.1571984738 0.0049533376 0.0157400000 714197585 0 402718720 -0.0864937752 -0.1510995328 -0.0345796235 1305 1311867762.1195960045 0.1256490201 0.1124886434 0.1571984738 0.0049514902 0.0156190000 714200841 0 402718720 -0.0865080878 -0.1514322460 -0.0344643481 1306 1311867762.1518180370 0.1256582886 0.1124987273 0.1571984738 0.0049731718 0.0163950000 714203985 0 402718720 -0.0865741745 -0.1509080231 -0.0344124548 1307 1311867762.1837639809 0.1255450845 0.1125087092 0.1571984738 0.0049715161 0.0451690000 714207129 0 402718720 -0.0865844414 -0.1507066339 -0.0342558548 1308 1311867762.2196350098 0.1259962767 0.1125190208 0.1571984738 0.0049702123 0.0186380000 714210385 0 402718720 -0.0860734582 -0.1515159607 -0.0343987457 1309 1311867762.2519500256 0.1268586516 0.1125299755 0.1571984738 0.0049684504 0.0365930000 714213529 0 402718720 -0.0862868577 -0.1523367316 -0.0347845815 1310 1311867762.2837049961 0.1252749711 0.1125397045 0.1571984738 0.0049794425 0.1234470000 726519969 0 402718720 -0.0863035247 -0.1509524733 -0.0347077288 1311 1311867762.3196139336 0.1189175919 0.1125445694 0.1571984738 0.0050619206 0.0152110000 730182433 0 402718720 -0.0873745158 -0.1419268548 -0.0302036181 1312 1311867762.3514790535 0.1183353215 0.1125489831 0.1571984738 0.0050600412 0.0154020000 733377769 0 402718720 -0.0870782062 -0.1415958852 -0.0307589676 1313 1311867762.3839020729 0.1186549589 0.1125536335 0.1571984738 0.0050744122 0.0151380000 733380913 0 402718720 -0.0871074274 -0.1416747570 -0.0309541188 1314 1311867762.4199450016 0.1186255217 0.1125582544 0.1571984738 0.0050727911 0.0152190000 733384225 0 402718720 -0.0870012492 -0.1417191327 -0.0308057871 1315 1311867762.4516999722 0.1186448187 0.1125628829 0.1571984738 0.0050710635 0.0150270000 733387257 0 402718720 -0.0868263766 -0.1419927478 -0.0310616139 1316 1311867762.4838089943 0.1189073622 0.1125677040 0.1571984738 0.0050701020 0.0146730000 733390401 0 402718720 -0.0871551186 -0.1418663114 -0.0306408312 1317 1311867762.5197870731 0.1186606735 0.1125723304 0.1571984738 0.0050689804 0.0148310000 733393713 0 402718720 -0.0870322287 -0.1420190036 -0.0310187545 1318 1311867762.5516951084 0.1183688790 0.1125767284 0.1571984738 0.0050671267 0.0153110000 733396801 0 402718720 -0.0866194293 -0.1420637518 -0.0315660760 1319 1311867762.5837769508 0.1183758825 0.1125811250 0.1571984738 0.0050652718 0.0149800000 733400001 0 402718720 -0.0871355012 -0.1418118626 -0.0310778897 1320 1311867762.6196839809 0.1179476902 0.1125851906 0.1571984738 0.0050636996 0.0149340000 733403257 0 402718720 -0.0869353414 -0.1415739954 -0.0305496361 1321 1311867762.6516590118 0.1178119704 0.1125891473 0.1571984738 0.0050620213 0.0151800000 733406345 0 402718720 -0.0866697654 -0.1418186128 -0.0308520030 1322 1311867762.6835629940 0.1180134565 0.1125932504 0.1571984738 0.0050603094 0.0143270000 733409377 0 402718720 -0.0867247954 -0.1421986371 -0.0313103870 1323 1311867762.7196519375 0.1176056787 0.1125970390 0.1571984738 0.0050586371 0.0148190000 733412689 0 402718720 -0.0869223773 -0.1417811960 -0.0309313945 1324 1311867762.7517120838 0.1171370000 0.1126004680 0.1571984738 0.0050571845 0.0146090000 733415777 0 402718720 -0.0865773112 -0.1421532184 -0.0305915773 1325 1311867762.7836871147 0.1166498140 0.1126035241 0.1571984738 0.0050555371 0.0142070000 733418921 0 402718720 -0.0865551680 -0.1419821084 -0.0313409194 1326 1311867762.8195219040 0.1168070287 0.1126066942 0.1571984738 0.0050540460 0.0146170000 733422233 0 402718720 -0.0872630030 -0.1417626292 -0.0312387161 1327 1311867762.8518118858 0.1167868972 0.1126098443 0.1571984738 0.0050525658 0.0156150000 733425321 0 402718720 -0.0865251645 -0.1423364133 -0.0303596314 1328 1311867762.8836309910 0.1164702773 0.1126127513 0.1571984738 0.0050506855 0.0912300000 745735197 0 402718720 -0.0867467821 -0.1418475956 -0.0307756569 1329 1311867762.9196801186 0.1165453345 0.1126157103 0.1571984738 0.0050488966 0.0374970000 749397661 0 402718720 -0.0866366923 -0.1422577053 -0.0314047225 1330 1311867762.9516270161 0.1167272478 0.1126188017 0.1571984738 0.0050473550 0.0246860000 752592997 0 402718720 -0.0866791308 -0.1423803270 -0.0301541071 1331 1311867762.9838709831 0.1166249216 0.1126218116 0.1571984738 0.0050456809 0.0154150000 752596141 0 402718720 -0.0871930569 -0.1419810206 -0.0299274791 1332 1311867763.0196580887 0.1166861504 0.1126248629 0.1571984738 0.0050440845 0.0149130000 752599397 0 402718720 -0.0867905095 -0.1424662620 -0.0306101311 1333 1311867763.0518538952 0.1161547378 0.1126275109 0.1571984738 0.0050422986 0.0146330000 752602541 0 402718720 -0.0868154243 -0.1418583095 -0.0299154334 1334 1311867763.0837149620 0.1160237789 0.1126300569 0.1571984738 0.0050405908 0.0144990000 752605685 0 402718720 -0.0866637155 -0.1418374479 -0.0302494355 1335 1311867763.1196479797 0.1168266460 0.1126332004 0.1571984738 0.0050391309 0.0144470000 752608941 0 402718720 -0.0868424624 -0.1426211298 -0.0310164746 1336 1311867763.1515760422 0.1169137210 0.1126364044 0.1571984738 0.0050372776 0.0137160000 752612085 0 402718720 -0.0868511423 -0.1426629275 -0.0304665677 1337 1311867763.1837859154 0.1162462533 0.1126391043 0.1571984738 0.0050355777 0.0137040000 752615229 0 402718720 -0.0865379572 -0.1419617981 -0.0303961877 1338 1311867763.2197899818 0.1165981740 0.1126420633 0.1571984738 0.0050338883 0.0141670000 752618485 0 402718720 -0.0868629590 -0.1422725022 -0.0312148500 1339 1311867763.2517459393 0.1165379584 0.1126449728 0.1571984738 0.0050321893 0.0141000000 752621573 0 402718720 -0.0869800970 -0.1418973356 -0.0306505207 1340 1311867763.2835650444 0.1162699759 0.1126476780 0.1571984738 0.0050317329 0.0645490000 752624661 0 402718720 -0.0850732476 -0.1431050152 -0.0309615824 1341 1311867763.3197009563 0.1172097400 0.1126510800 0.1571984738 0.0050300091 0.0228970000 752627973 0 402718720 -0.0858994499 -0.1434525400 -0.0304023381 1342 1311867763.3516809940 0.1173467115 0.1126545790 0.1571984738 0.0050285188 0.0181940000 752631061 0 402718720 -0.0860596225 -0.1433107108 -0.0298510622 1343 1311867763.3838119507 0.1167882532 0.1126576569 0.1571984738 0.0050270907 0.0149750000 752634205 0 402718720 -0.0867269859 -0.1421653330 -0.0301231705 1344 1311867763.4195470810 0.1170832589 0.1126609498 0.1571984738 0.0050252427 0.0150230000 752637461 0 402718720 -0.0868597180 -0.1422248334 -0.0303241201 1345 1311867763.4517118931 0.1175529659 0.1126645870 0.1571984738 0.0050235059 0.0446440000 752640549 0 402718720 -0.0870608017 -0.1424669623 -0.0298842527 1346 1311867763.4839050770 0.1173695177 0.1126680825 0.1571984738 0.0050218236 0.0181490000 752643749 0 402718720 -0.0867774487 -0.1423045993 -0.0296217613 1347 1311867763.5196909904 0.1182587072 0.1126722329 0.1571984738 0.0050202994 0.0146330000 752647005 0 402718720 -0.0870652720 -0.1432207972 -0.0302366223 1348 1311867763.5518760681 0.1177939400 0.1126760324 0.1571984738 0.0050189792 0.0149210000 752650093 0 402718720 -0.0869489461 -0.1423908323 -0.0299225766 1349 1311867763.5838658810 0.1180363223 0.1126800059 0.1571984738 0.0050171900 0.0148350000 752653293 0 402718720 -0.0864373744 -0.1432384849 -0.0297758952 1350 1311867763.6197280884 0.1174036115 0.1126835049 0.1571984738 0.0050154566 0.0153720000 752656493 0 402718720 -0.0863021314 -0.1428621113 -0.0312863067 1351 1311867763.6517100334 0.1189582646 0.1126881494 0.1571984738 0.0050137576 0.0496760000 752659581 0 402718720 -0.0865280107 -0.1444950700 -0.0298885293 1352 1311867763.6836590767 0.1192640290 0.1126930132 0.1571984738 0.0050120750 0.0483270000 752662669 0 402718720 -0.0866782293 -0.1447608918 -0.0293994322 1353 1311867763.7195520401 0.1183049157 0.1126971610 0.1571984738 0.0050103413 0.0270870000 752665981 0 402718720 -0.0865464285 -0.1438869387 -0.0303618126 1354 1311867763.7518069744 0.1178426817 0.1127009612 0.1571984738 0.0050086100 0.0156690000 752669125 0 402718720 -0.0866206139 -0.1433120668 -0.0304244775 1355 1311867763.7836210728 0.1180810109 0.1127049317 0.1571984738 0.0050070979 0.0163110000 752672213 0 402718720 -0.0868778080 -0.1433691531 -0.0301184654 1356 1311867763.8196339607 0.1172000617 0.1127082467 0.1571984738 0.0050055556 0.1010100000 764984977 0 402718720 -0.0860057697 -0.1430974454 -0.0311674345 1357 1311867763.8519349098 0.1184434965 0.1127124731 0.1571984738 0.0050054152 0.0447000000 768654617 0 402718720 -0.0881828144 -0.1430559903 -0.0318241306 1358 1311867763.8837280273 0.1183183119 0.1127166012 0.1571984738 0.0050036308 0.0182490000 771849953 0 402718720 -0.0880992636 -0.1431218386 -0.0321601816 1359 1311867763.9194750786 0.1185341328 0.1127208819 0.1571984738 0.0050019594 0.0145880000 771853265 0 402718720 -0.0880074576 -0.1434831172 -0.0317895524 1360 1311867763.9519019127 0.1184793785 0.1127251161 0.1571984738 0.0050002952 0.0147260000 771856353 0 402718720 -0.0881507099 -0.1433247775 -0.0326595865 1361 1311867763.9839799404 0.1183547229 0.1127292525 0.1571984738 0.0049988417 0.0144920000 771859497 0 402718720 -0.0879441947 -0.1433594823 -0.0323342569 1362 1311867764.0198440552 0.1182843819 0.1127333311 0.1571984738 0.0050007593 0.0221290000 771862753 0 402718720 -0.0878869593 -0.1429964453 -0.0324273109 1363 1311867764.0517289639 0.1182988435 0.1127374144 0.1571984738 0.0050066926 0.0151110000 771865897 0 402718720 -0.0879797935 -0.1432523429 -0.0328874998 1364 1311867764.0837609768 0.1183125079 0.1127415017 0.1571984738 0.0050053184 0.0148640000 771868985 0 402718720 -0.0880403295 -0.1430869550 -0.0326611362 1365 1311867764.1196389198 0.1180012748 0.1127453550 0.1571984738 0.0050036980 0.0239940000 771872241 0 402718720 -0.0873930976 -0.1433509141 -0.0328420587 1366 1311867764.1517179012 0.1184795424 0.1127495528 0.1571984738 0.0050022103 0.0241260000 771875329 0 402718720 -0.0879215673 -0.1434583962 -0.0331595130 1367 1311867764.1837580204 0.1183017269 0.1127536144 0.1571984738 0.0050012375 0.0146820000 771878529 0 402718720 -0.0878380314 -0.1430662572 -0.0327866152 1368 1311867764.2197659016 0.1179119870 0.1127573851 0.1571984738 0.0049996301 0.0167000000 771881785 0 402718720 -0.0877122357 -0.1429773271 -0.0330709852 1369 1311867764.2517390251 0.1180522144 0.1127612528 0.1571984738 0.0049980556 0.0417450000 771884873 0 402718720 -0.0877837688 -0.1433041245 -0.0338698216 1370 1311867764.2836918831 0.1180674434 0.1127651259 0.1571984738 0.0049965417 0.0413720000 771888073 0 402718720 -0.0875917524 -0.1435052007 -0.0334506631 1371 1311867764.3198370934 0.1172202379 0.1127683755 0.1571984738 0.0049953103 0.0235940000 771891329 0 402718720 -0.0874916613 -0.1428124607 -0.0333543867 1372 1311867764.3518040180 0.1172591895 0.1127716487 0.1571984738 0.0049945946 0.0499940000 771894417 0 402718720 -0.0876083001 -0.1433677971 -0.0345399305 1373 1311867764.3837459087 0.1170906126 0.1127747943 0.1571984738 0.0049935396 0.0789220000 771897617 0 402718720 -0.0875900388 -0.1432205886 -0.0340607427 1374 1311867764.4197158813 0.1158957481 0.1127770657 0.1571984738 0.0049924507 0.0810770000 784210889 0 402718720 -0.0867809355 -0.1430068612 -0.0344660655 1375 1311867764.4518089294 0.1159394607 0.1127793657 0.1571984738 0.0049910082 0.0140370000 787873185 0 402718720 -0.0873972923 -0.1427126378 -0.0345753469 1376 1311867764.4837419987 0.1148026213 0.1127808360 0.1571984738 0.0049909141 0.0138400000 791068521 0 402718720 -0.0869380832 -0.1422070861 -0.0345390067 1377 1311867764.5198130608 0.1147891879 0.1127822945 0.1571984738 0.0050105812 0.0146970000 791071777 0 402718720 -0.0871801972 -0.1419001371 -0.0341248289 1378 1311867764.5516870022 0.1152471825 0.1127840833 0.1571984738 0.0050097771 0.0273380000 791074809 0 402718720 -0.0870336890 -0.1428793520 -0.0350193232 1379 1311867764.5840260983 0.1148776561 0.1127856015 0.1571984738 0.0050082435 0.0236610000 791078009 0 402718720 -0.0871879682 -0.1424432546 -0.0349060781 1380 1311867764.6197779179 0.1145846248 0.1127869051 0.1571984738 0.0050080609 0.0145040000 791081209 0 402718720 -0.0869295374 -0.1423169822 -0.0347789414 1381 1311867764.6517069340 0.1141510233 0.1127878929 0.1571984738 0.0050065162 0.0362380000 791084409 0 402718720 -0.0867816135 -0.1422788203 -0.0360488705 1382 1311867764.6838181019 0.1144725755 0.1127891119 0.1571984738 0.0050047405 0.0321950000 791087553 0 402718720 -0.0869227499 -0.1425273865 -0.0356546529 1383 1311867764.7197830677 0.1134588420 0.1127895962 0.1571984738 0.0050029462 0.0235180000 791090753 0 402718720 -0.0865324512 -0.1418592483 -0.0359713174 1384 1311867764.7516579628 0.1133630127 0.1127900105 0.1571984738 0.0050025225 0.0379030000 791093897 0 402718720 -0.0865158960 -0.1422510445 -0.0360966064 1385 1311867764.7837390900 0.1135289669 0.1127905440 0.1571984738 0.0050014437 0.0505710000 791097041 0 402718720 -0.0868590474 -0.1424555480 -0.0368393511 1386 1311867764.8197050095 0.1129664034 0.1127906709 0.1571984738 0.0049999190 0.0682700000 791100353 0 402718720 -0.0866320655 -0.1420440525 -0.0363847837 1387 1311867764.8517210484 0.1126402989 0.1127905625 0.1571984738 0.0049992755 0.0505560000 791103441 0 402718720 -0.0862431452 -0.1422693729 -0.0370419510 1388 1311867764.8839149475 0.1128384545 0.1127905970 0.1571984738 0.0049976167 0.0490140000 791106641 0 402718720 -0.0865134373 -0.1423738152 -0.0371737890 1389 1311867764.9198660851 0.1128562540 0.1127906443 0.1571984738 0.0049959269 0.0357220000 791109841 0 402718720 -0.0868934989 -0.1421888173 -0.0365119129 1390 1311867764.9517869949 0.1124350429 0.1127903884 0.1571984738 0.0049954985 0.0535070000 791113041 0 402718720 -0.0861018822 -0.1426390558 -0.0376363061 1391 1311867764.9839010239 0.1133865118 0.1127908170 0.1571984738 0.0049944476 0.0437590000 791116185 0 402718720 -0.0874774829 -0.1424700916 -0.0364751108 1392 1311867765.0197479725 0.1121755987 0.1127903750 0.1571984738 0.0049927041 0.0383010000 791119441 0 402718720 -0.0864333361 -0.1418801099 -0.0370304696 1393 1311867765.0517559052 0.1121669635 0.1127899275 0.1571984738 0.0049920702 0.0473140000 791122417 0 402718720 -0.0861480385 -0.1422971338 -0.0378553979 1394 1311867765.0838060379 0.1117834747 0.1127892055 0.1571984738 0.0049913703 0.0431890000 791125617 0 402718720 -0.0861371458 -0.1420189291 -0.0377455503 1395 1311867765.1196489334 0.1119724438 0.1127886200 0.1571984738 0.0049903462 0.0313320000 791128873 0 402718720 -0.0866684839 -0.1415470541 -0.0372959226 1396 1311867765.1517910957 0.1115998551 0.1127877685 0.1571984738 0.0049889102 0.0392370000 791131905 0 402718720 -0.0860716552 -0.1418037117 -0.0378248431 1397 1311867765.1837079525 0.1115111038 0.1127868546 0.1571984738 0.0049874324 0.0685460000 791135049 0 402718720 -0.0864718631 -0.1413893849 -0.0374062732 1398 1311867765.2198550701 0.1127535999 0.1127868308 0.1571984738 0.0049858306 0.0308500000 791138305 0 402718720 -0.0876916870 -0.1419507563 -0.0363029167 1399 1311867765.2517991066 0.1114125550 0.1127858485 0.1571984738 0.0049844872 0.0363210000 791141393 0 402718720 -0.0863590539 -0.1415778100 -0.0379439034 1400 1311867765.2838370800 0.1114757285 0.1127849127 0.1571984738 0.0049829634 0.0326680000 791144481 0 402718720 -0.0865298957 -0.1414022446 -0.0376297385 1401 1311867765.3199069500 0.1117715612 0.1127841894 0.1571984738 0.0049819416 0.0315680000 791147793 0 402718720 -0.0865684673 -0.1415544003 -0.0376206711 1402 1311867765.3518490791 0.1114724129 0.1127832537 0.1571984738 0.0049807072 0.0420320000 791150825 0 402718720 -0.0857399404 -0.1418621987 -0.0390938446 1403 1311867765.3838179111 0.1112766564 0.1127821799 0.1571984738 0.0049800286 0.0352840000 791154025 0 402718720 -0.0859089941 -0.1411528289 -0.0385147668 1404 1311867765.4199221134 0.1114080921 0.1127812012 0.1571984738 0.0049787623 0.0336410000 791157281 0 402718720 -0.0862954184 -0.1411540359 -0.0386355296 1405 1311867765.4520080090 0.1114667878 0.1127802657 0.1571984738 0.0049775879 0.0401430000 791160425 0 402718720 -0.0856919363 -0.1416840553 -0.0398496464 1406 1311867765.4839520454 0.1120695546 0.1127797602 0.1571984738 0.0049762703 0.0362690000 791163569 0 402718720 -0.0862330869 -0.1415983737 -0.0391585119 1407 1311867765.5197889805 0.1124576032 0.1127795312 0.1571984738 0.0049745515 0.0375540000 791166825 0 402718720 -0.0864848867 -0.1416771412 -0.0393713042 1408 1311867765.5518178940 0.1119583175 0.1127789480 0.1571984738 0.0049733095 0.0639800000 791169913 0 402718720 -0.0855943337 -0.1415850371 -0.0401648618 1409 1311867765.5838429928 0.1117803752 0.1127782393 0.1571984738 0.0049723949 0.0348970000 791173113 0 402718720 -0.0862387344 -0.1405075043 -0.0393803194 1410 1311867765.6197888851 0.1119500324 0.1127776519 0.1571984738 0.0049708678 0.0322440000 791176369 0 402718720 -0.0859957784 -0.1407493353 -0.0393954329 1411 1311867765.6518950462 0.1122738495 0.1127772948 0.1571984738 0.0049691405 0.0342180000 791179513 0 402718720 -0.0860963315 -0.1408824176 -0.0397387147 1412 1311867765.6838550568 0.1118920445 0.1127766679 0.1571984738 0.0049675578 0.0333690000 791182601 0 402718720 -0.0860457718 -0.1402196139 -0.0394145250 1413 1311867765.7197959423 0.1119316295 0.1127760698 0.1571984738 0.0049660901 0.0693850000 791185913 0 402718720 -0.0860234797 -0.1403461695 -0.0396590978 1414 1311867765.7517340183 0.1121154502 0.1127756026 0.1571984738 0.0049644270 0.0315500000 791189001 0 402718720 -0.0859252363 -0.1406783909 -0.0398226529 1415 1311867765.7840330601 0.1121392772 0.1127751529 0.1571984738 0.0049627008 0.0296140000 791192201 0 402718720 -0.0858306512 -0.1406769603 -0.0397474952 1416 1311867765.8199460506 0.1122692004 0.1127747956 0.1571984738 0.0049611547 0.0314060000 791195457 0 402718720 -0.0857197866 -0.1410221756 -0.0402037278 1417 1311867765.8518691063 0.1122844890 0.1127744496 0.1571984738 0.0049594129 0.0307210000 791198601 0 402718720 -0.0857615322 -0.1408975124 -0.0400318652 1418 1311867765.8839869499 0.1122203991 0.1127740589 0.1571984738 0.0049578217 0.0299200000 791201745 0 402718720 -0.0857462138 -0.1406934857 -0.0397876427 1419 1311867765.9198229313 0.1124884486 0.1127738576 0.1571984738 0.0049561060 0.0293690000 791205001 0 402718720 -0.0856832266 -0.1410519332 -0.0394613221 1420 1311867765.9519369602 0.1132370681 0.1127741838 0.1571984738 0.0049544367 0.0309160000 791208089 0 402718720 -0.0860620067 -0.1417179704 -0.0391776077 1421 1311867765.9839439392 0.1127421036 0.1127741612 0.1571984738 0.0049531670 0.0278170000 791211289 0 402718720 -0.0860446543 -0.1409468651 -0.0390511677 1422 1311867766.0199379921 0.1128102913 0.1127741866 0.1571984738 0.0049514512 0.0268490000 791214489 0 402718720 -0.0860635638 -0.1408733875 -0.0387567244 1423 1311867766.0519530773 0.1132519096 0.1127745224 0.1571984738 0.0049497531 0.0268220000 791217577 0 402718720 -0.0865914747 -0.1409214735 -0.0384931006 1424 1311867766.0839750767 0.1129097193 0.1127746173 0.1571984738 0.0049481926 0.0263320000 791220777 0 402718720 -0.0860319138 -0.1407572627 -0.0385948978 1425 1311867766.1199851036 0.1137291938 0.1127752872 0.1571984738 0.0049464879 0.0614320000 791224033 0 402718720 -0.0861321911 -0.1412741393 -0.0380644351 1426 1311867766.1517939568 0.1141898334 0.1127762791 0.1571984738 0.0049448510 0.0272100000 791227121 0 402718720 -0.0862693489 -0.1415511817 -0.0379024372 1427 1311867766.1838970184 0.1153080538 0.1127780533 0.1571984738 0.0049431971 0.0303670000 791230321 0 402718720 -0.0870980397 -0.1422092170 -0.0373714305 1428 1311867766.2199308872 0.1155035645 0.1127799620 0.1571984738 0.0049434929 0.0311720000 791233577 0 402718720 -0.0886982158 -0.1411027163 -0.0359158739 1429 1311867766.2519950867 0.1155838892 0.1127819241 0.1571984738 0.0049441785 0.0157390000 791236609 0 402718720 -0.0872860104 -0.1422118694 -0.0355202444 1430 1311867766.2839519978 0.1167214736 0.1127846791 0.1571984738 0.0049433182 0.0316430000 791239809 0 402718720 -0.0882740840 -0.1427173018 -0.0350671634 1431 1311867766.3199090958 0.1155874953 0.1127866377 0.1571984738 0.0049511455 0.0145830000 791243065 0 402718720 -0.0882063657 -0.1417968124 -0.0335846394 1432 1311867766.3520219326 0.1153623164 0.1127884364 0.1571984738 0.0049500629 0.0143220000 791246209 0 402718720 -0.0883905441 -0.1415711939 -0.0333653875 1433 1311867766.3839769363 0.1170496121 0.1127914100 0.1571984738 0.0049619756 0.0279630000 791249353 0 402718720 -0.0889876112 -0.1421979070 -0.0331942588 1434 1311867766.4199988842 0.1166549772 0.1127941042 0.1571984738 0.0049678390 0.0251980000 791252609 0 402718720 -0.0886835232 -0.1413339823 -0.0323983543 1435 1311867766.4519500732 0.1161838695 0.1127964664 0.1571984738 0.0049726563 0.0294420000 791255697 0 402718720 -0.0887987241 -0.1410200149 -0.0321942978 1436 1311867766.4838209152 0.1165614724 0.1127990883 0.1571984738 0.0049709545 0.0235390000 791258841 0 402718720 -0.0888343006 -0.1414316595 -0.0321983173 1437 1311867766.5200190544 0.1161950976 0.1128014516 0.1571984738 0.0049695933 0.0311460000 791262097 0 402718720 -0.0892211273 -0.1405874789 -0.0318627544 1438 1311867766.5519850254 0.1165263057 0.1128040419 0.1571984738 0.0049678824 0.0270030000 791265185 0 402718720 -0.0891831070 -0.1410139799 -0.0319069549 1439 1311867766.5838708878 0.1167136878 0.1128067588 0.1571984738 0.0049662161 0.0558300000 791268385 0 402718720 -0.0893351510 -0.1413841099 -0.0321194381 1440 1311867766.6198449135 0.1169317737 0.1128096234 0.1571984738 0.0049644949 0.0202150000 791271641 0 402718720 -0.0889491960 -0.1420533806 -0.0323477052 1441 1311867766.6519460678 0.1161842048 0.1128119652 0.1571984738 0.0049629376 0.0169590000 791274729 0 402718720 -0.0883909464 -0.1416977197 -0.0327989422 1442 1311867766.6838889122 0.1170291156 0.1128148897 0.1571984738 0.0049680022 0.0222490000 791277873 0 402718720 -0.0890330151 -0.1416736692 -0.0325624943 1443 1311867766.7198989391 0.1168831512 0.1128177090 0.1571984738 0.0049691518 0.0273430000 791281129 0 402718720 -0.0892319009 -0.1419181079 -0.0334105194 1444 1311867766.7519459724 0.1164398491 0.1128202174 0.1571984738 0.0049674572 0.0154870000 791284273 0 402718720 -0.0882281512 -0.1423384547 -0.0346616954 1445 1311867766.7838931084 0.1159638911 0.1128223930 0.1571984738 0.0049671111 0.0178780000 791287361 0 402718720 -0.0881465375 -0.1422132254 -0.0353789479 1446 1311867766.8198320866 0.1162450388 0.1128247600 0.1571984738 0.0049683274 0.0201090000 791290617 0 402718720 -0.0877535492 -0.1423788816 -0.0360647812 1447 1311867766.8519148827 0.1168001369 0.1128275073 0.1571984738 0.0049670318 0.0250530000 791293705 0 402718720 -0.0875123218 -0.1428434402 -0.0367659517 1448 1311867766.8839941025 0.1162387356 0.1128298631 0.1571984738 0.0049654586 0.0227180000 791296905 0 402718720 -0.0868381262 -0.1425749660 -0.0371854566 1449 1311867766.9198539257 0.1165468842 0.1128324283 0.1571984738 0.0049684804 0.0252620000 791300105 0 402718720 -0.0872203037 -0.1429495215 -0.0381277949 1450 1311867766.9520690441 0.1181279495 0.1128360804 0.1571984738 0.0049792714 0.0254740000 791303193 0 402718720 -0.0871786848 -0.1438876987 -0.0382744074 1451 1311867766.9839029312 0.1177308485 0.1128394538 0.1571984738 0.0049776653 0.0238200000 791306393 0 402718720 -0.0869867653 -0.1430984885 -0.0382238142 1452 1311867767.0202069283 0.1174297854 0.1128426152 0.1571984738 0.0049762546 0.0228150000 791309705 0 402718720 -0.0866905376 -0.1428277791 -0.0381540582 1453 1311867767.0520200729 0.1177729815 0.1128460084 0.1571984738 0.0049745574 0.0231850000 791312737 0 402718720 -0.0867806897 -0.1431779861 -0.0378249623 1454 1311867767.0840458870 0.1188743412 0.1128501544 0.1571984738 0.0049736803 0.0599830000 791315937 0 402718720 -0.0873847380 -0.1437421739 -0.0377982333 1455 1311867767.1200020313 0.1177681535 0.1128535345 0.1571984738 0.0049733936 0.0243900000 791319193 0 402718720 -0.0871791542 -0.1431193948 -0.0375337265 1456 1311867767.1522760391 0.1177004129 0.1128568634 0.1571984738 0.0049734233 0.0221140000 791322337 0 402718720 -0.0868456215 -0.1430135965 -0.0375556387 1457 1311867767.1838700771 0.1181414351 0.1128604904 0.1571984738 0.0049717536 0.0247530000 791325481 0 402718720 -0.0873971879 -0.1434291005 -0.0378411710 1458 1311867767.2198100090 0.1172264144 0.1128634849 0.1571984738 0.0049714489 0.0245710000 791328737 0 402718720 -0.0871468857 -0.1431569904 -0.0380223133 1459 1311867767.2522809505 0.1172941625 0.1128665217 0.1571984738 0.0049697886 0.0246810000 791331881 0 402718720 -0.0872049257 -0.1433688104 -0.0377382189 1460 1311867767.2837929726 0.1170910895 0.1128694152 0.1571984738 0.0049682598 0.0232520000 791335025 0 402718720 -0.0869122148 -0.1433847249 -0.0379522406 1461 1311867767.3198978901 0.1175375059 0.1128726104 0.1571984738 0.0049709543 0.0228760000 791338281 0 402718720 -0.0870504230 -0.1434988081 -0.0372823179 1462 1311867767.3518888950 0.1169784367 0.1128754187 0.1571984738 0.0049708189 0.0219890000 791341425 0 402718720 -0.0868995562 -0.1432207227 -0.0373193845 1463 1311867767.3843390942 0.1172332093 0.1128783974 0.1571984738 0.0049691598 0.0236370000 791344625 0 402718720 -0.0870241970 -0.1434964538 -0.0373762585 1464 1311867767.4202649593 0.1169349626 0.1128811683 0.1571984738 0.0049679469 0.0227120000 791347881 0 402718720 -0.0872817114 -0.1436415762 -0.0371682271 1465 1311867767.4520349503 0.1172265857 0.1128841344 0.1571984738 0.0049663130 0.0233380000 791351025 0 402718720 -0.0878294557 -0.1433012336 -0.0366084389 1466 1311867767.4839749336 0.1168418378 0.1128868341 0.1571984738 0.0049650490 0.0227960000 791354113 0 402718720 -0.0875650197 -0.1433064789 -0.0373396836 1467 1311867767.5203309059 0.1183336899 0.1128905470 0.1571984738 0.0049671479 0.0235730000 791357369 0 402718720 -0.0880078301 -0.1438244283 -0.0366416201 1468 1311867767.5521090031 0.1170498207 0.1128933803 0.1571984738 0.0049678022 0.0540120000 791360513 0 402718720 -0.0874666199 -0.1430018544 -0.0368242301 1469 1311867767.5838620663 0.1172074676 0.1128963171 0.1571984738 0.0049667877 0.0235880000 791363657 0 402718720 -0.0875507295 -0.1436622441 -0.0376609452 1470 1311867767.6201050282 0.1163422614 0.1128986612 0.1571984738 0.0049651500 0.0212360000 791366969 0 402718720 -0.0870750770 -0.1431832165 -0.0365784913 1471 1311867767.6520709991 0.1161060929 0.1129008417 0.1571984738 0.0049634984 0.0201270000 791370057 0 402718720 -0.0872442499 -0.1429722011 -0.0362672918 1472 1311867767.6840400696 0.1160066575 0.1129029516 0.1571984738 0.0049619034 0.0223100000 791373201 0 402718720 -0.0869925767 -0.1432970762 -0.0363401733 1473 1311867767.7200539112 0.1153826937 0.1129046351 0.1571984738 0.0049602890 0.0206180000 791376457 0 402718720 -0.0869342089 -0.1429293752 -0.0366445966 1474 1311867767.7519989014 0.1154447272 0.1129063583 0.1571984738 0.0049586123 0.0228920000 791379601 0 402718720 -0.0867934823 -0.1432538927 -0.0365274847 1475 1311867767.7841119766 0.1151695177 0.1129078927 0.1571984738 0.0049569813 0.0205000000 791382745 0 402718720 -0.0867496282 -0.1431118548 -0.0366287567 1476 1311867767.8199989796 0.1151578277 0.1129094170 0.1571984738 0.0049553097 0.0212540000 791386001 0 402718720 -0.0869313851 -0.1431567818 -0.0367761366 1477 1311867767.8520400524 0.1153081134 0.1129110411 0.1571984738 0.0049537518 0.0244740000 791389089 0 402718720 -0.0867368430 -0.1434656382 -0.0366045944 1478 1311867767.8839809895 0.1157106012 0.1129129352 0.1571984738 0.0049521627 0.0225700000 791392177 0 402718720 -0.0877640694 -0.1431829780 -0.0368251540 1479 1311867767.9199900627 0.1154521406 0.1129146521 0.1571984738 0.0049505886 0.0216000000 791395489 0 402718720 -0.0873930603 -0.1432317793 -0.0374210253 1480 1311867767.9521129131 0.1152946651 0.1129162602 0.1571984738 0.0049492820 0.0222230000 791398577 0 402718720 -0.0866196007 -0.1433693618 -0.0369571522 1481 1311867767.9841179848 0.1146160588 0.1129174079 0.1571984738 0.0049480901 0.0213890000 791401777 0 402718720 -0.0863831639 -0.1429080516 -0.0369659364 1482 1311867768.0200319290 0.1158414781 0.1129193810 0.1571984738 0.0049469492 0.0566320000 791405033 0 402718720 -0.0868774131 -0.1437043846 -0.0378718451 1483 1311867768.0519499779 0.1154927909 0.1129211162 0.1571984738 0.0049452975 0.0222380000 791408121 0 402718720 -0.0864950716 -0.1432268322 -0.0371514745 1484 1311867768.0842280388 0.1151847020 0.1129226416 0.1571984738 0.0049437031 0.0219450000 791411321 0 402718720 -0.0863029584 -0.1430225670 -0.0372698009 1485 1311867768.1199910641 0.1149529070 0.1129240087 0.1571984738 0.0049420448 0.0220810000 791414577 0 402718720 -0.0862256140 -0.1431179643 -0.0373801328 1486 1311867768.1520550251 0.1144966483 0.1129250670 0.1571984738 0.0049417281 0.0213490000 791417665 0 402718720 -0.0858453140 -0.1432201117 -0.0382883698 1487 1311867768.1840939522 0.1149888113 0.1129264549 0.1571984738 0.0049417306 0.0359420000 791420865 0 402718720 -0.0860259831 -0.1435222179 -0.0375511460 1488 1311867768.2199339867 0.1146243662 0.1129275960 0.1571984738 0.0049400864 0.0214310000 791424121 0 402718720 -0.0861269534 -0.1431363970 -0.0377961211 1489 1311867768.2520949841 0.1149986237 0.1129289869 0.1571984738 0.0049387824 0.0219190000 791427209 0 402718720 -0.0862242877 -0.1437381953 -0.0382425115 1490 1311867768.2839739323 0.1157130376 0.1129308553 0.1571984738 0.0049403697 0.0212370000 791430353 0 402718720 -0.0862383693 -0.1438707411 -0.0380611420 1491 1311867768.3201060295 0.1154610515 0.1129325523 0.1571984738 0.0049406439 0.0249850000 791433609 0 402718720 -0.0859400705 -0.1435589194 -0.0372610316 1492 1311867768.3521120548 0.1153267249 0.1129341570 0.1571984738 0.0049390348 0.0191910000 791436753 0 402718720 -0.0860798284 -0.1432881206 -0.0375067629 1493 1311867768.3840799332 0.1162592471 0.1129363841 0.1571984738 0.0049406974 0.0217960000 791439785 0 402718720 -0.0866700187 -0.1435880512 -0.0371354669 1494 1311867768.4199349880 0.1168000698 0.1129389703 0.1571984738 0.0049417985 0.0204630000 791442985 0 402718720 -0.0870294273 -0.1440118998 -0.0374176465 1495 1311867768.4519999027 0.1159083918 0.1129409565 0.1571984738 0.0049403923 0.0587050000 791446073 0 402718720 -0.0862922147 -0.1431611925 -0.0366966948 1496 1311867768.4840490818 0.1162164435 0.1129431460 0.1571984738 0.0049389334 0.0199500000 791449217 0 402718720 -0.0865841210 -0.1436190307 -0.0372124799 1497 1311867768.5200510025 0.1178235412 0.1129464061 0.1571984738 0.0049379130 0.0211700000 791452473 0 402718720 -0.0878267065 -0.1442623436 -0.0370282196 1498 1311867768.5521159172 0.1175093353 0.1129494521 0.1571984738 0.0049367011 0.0233180000 791455561 0 402718720 -0.0883506984 -0.1429726183 -0.0358745083 1499 1311867768.5839970112 0.1163152009 0.1129516974 0.1571984738 0.0049367060 0.0202500000 791458761 0 402718720 -0.0863078088 -0.1433264166 -0.0365651101 1500 1311867768.6199870110 0.1163881421 0.1129539884 0.1571984738 0.0049351100 0.0222720000 791461961 0 402718720 -0.0864491016 -0.1432605088 -0.0360624120 1501 1311867768.6521151066 0.1169793010 0.1129566702 0.1571984738 0.0049340130 0.0215010000 791465105 0 402718720 -0.0872476548 -0.1433924884 -0.0359236337 1502 1311867768.6839869022 0.1177066416 0.1129598326 0.1571984738 0.0049324844 0.0209980000 791468249 0 402718720 -0.0879826918 -0.1436344683 -0.0356545150 1503 1311867768.7200720310 0.1165455505 0.1129622183 0.1571984738 0.0049333417 0.0213890000 791471505 0 402718720 -0.0888079330 -0.1415638328 -0.0353594944 1504 1311867768.7521040440 0.1169196665 0.1129648496 0.1571984738 0.0049321697 0.0202710000 791474649 0 402718720 -0.0893343911 -0.1421102285 -0.0366924144 1505 1311867768.7842459679 0.1165378541 0.1129672237 0.1571984738 0.0049315233 0.0192980000 791477849 0 402718720 -0.0887487903 -0.1418832690 -0.0362873562 1506 1311867768.8200149536 0.1166852340 0.1129696925 0.1571984738 0.0049314532 0.0185110000 791481105 0 402718720 -0.0869733915 -0.1430566609 -0.0357024446 1507 1311867768.8521099091 0.1166643575 0.1129721441 0.1571984738 0.0049298398 0.0175380000 791484249 0 402718720 -0.0867484808 -0.1427556872 -0.0345235765 1508 1311867768.8839499950 0.1167653874 0.1129746596 0.1571984738 0.0049282994 0.0166920000 791487337 0 402718720 -0.0870051831 -0.1426848322 -0.0344891697 1509 1311867768.9199481010 0.1176128834 0.1129777333 0.1571984738 0.0049268603 0.0473120000 791490593 0 402718720 -0.0880481228 -0.1426212788 -0.0344880782 1510 1311867768.9520230293 0.1172224581 0.1129805443 0.1571984738 0.0049252592 0.0186190000 791493681 0 402718720 -0.0878060460 -0.1421363652 -0.0341405906 1511 1311867768.9840409756 0.1170391589 0.1129832304 0.1571984738 0.0049238001 0.0160880000 791496825 0 402718720 -0.0875198245 -0.1420601606 -0.0342939794 1512 1311867769.0200440884 0.1184683889 0.1129868581 0.1571984738 0.0049224787 0.0160190000 791500025 0 402718720 -0.0882102326 -0.1428406835 -0.0336790085 1513 1311867769.0519750118 0.1184970513 0.1129905000 0.1571984738 0.0049215585 0.0202510000 791503113 0 402718720 -0.0890412554 -0.1418204457 -0.0327193737 1514 1311867769.0840270519 0.1181235909 0.1129938905 0.1571984738 0.0049202030 0.0161880000 791506313 0 402718720 -0.0880117491 -0.1423303038 -0.0330800600 1515 1311867769.1200790405 0.1175636277 0.1129969068 0.1571984738 0.0049188676 0.0224110000 791509569 0 402718720 -0.0890382975 -0.1409884393 -0.0329721272 1516 1311867769.1520090103 0.1175983027 0.1129999420 0.1571984738 0.0049175450 0.0167670000 791512601 0 402718720 -0.0881238803 -0.1417119503 -0.0327033661 1517 1311867769.1839900017 0.1171901077 0.1130027041 0.1571984738 0.0049219043 0.0154490000 791515801 0 402718720 -0.0877257958 -0.1418945938 -0.0326799229 1518 1311867769.2200379372 0.1189666539 0.1130066330 0.1571984738 0.0049213421 0.0180840000 791519001 0 402718720 -0.0892505199 -0.1424982101 -0.0319631062 1519 1311867769.2519080639 0.1178216264 0.1130098028 0.1571984738 0.0049204192 0.0154760000 791522145 0 402718720 -0.0878495872 -0.1420912147 -0.0323880427 1520 1311867769.2839570045 0.1182066128 0.1130132218 0.1571984738 0.0049188605 0.0162290000 791525289 0 402718720 -0.0881585255 -0.1422313452 -0.0328682065 1521 1311867769.3199648857 0.1192190573 0.1130173019 0.1571984738 0.0049210387 0.0163530000 791528545 0 402718720 -0.0875743702 -0.1433339119 -0.0329381116 1522 1311867769.3521530628 0.1190636978 0.1130212745 0.1571984738 0.0049199041 0.0164800000 791531633 0 402718720 -0.0877819583 -0.1425619870 -0.0327260606 1523 1311867769.3839631081 0.1194319427 0.1130254838 0.1571984738 0.0049195916 0.0165870000 791534777 0 402718720 -0.0874825194 -0.1427618116 -0.0326655954 1524 1311867769.4200670719 0.1193750128 0.1130296501 0.1571984738 0.0049184746 0.0174990000 791538033 0 402718720 -0.0882299989 -0.1418378651 -0.0321876854 1525 1311867769.4519898891 0.1197578013 0.1130340620 0.1571984738 0.0049177186 0.0181630000 791541177 0 402718720 -0.0883796588 -0.1415774971 -0.0319466256 1526 1311867769.4840829372 0.1212524995 0.1130394476 0.1571984738 0.0049167762 0.0178950000 791544321 0 402718720 -0.0884458274 -0.1430899948 -0.0312245321 1527 1311867769.5200660229 0.1208568960 0.1130445671 0.1571984738 0.0049159522 0.0468730000 791547633 0 402718720 -0.0893444121 -0.1417029351 -0.0303268190 1528 1311867769.5519690514 0.1199060231 0.1130490576 0.1571984738 0.0049144899 0.0196450000 791550721 0 402718720 -0.0883667693 -0.1412400454 -0.0307745822 1529 1311867769.5839929581 0.1198444292 0.1130535019 0.1571984738 0.0049129597 0.0203450000 791553809 0 402718720 -0.0890508443 -0.1407743543 -0.0305857994 1530 1311867769.6199469566 0.1212376952 0.1130588511 0.1571984738 0.0049129846 0.0173950000 791557065 0 402718720 -0.0894738957 -0.1421352029 -0.0302379783 1531 1311867769.6519889832 0.1208388284 0.1130639327 0.1571984738 0.0049116228 0.0167750000 791560153 0 402718720 -0.0892168209 -0.1419575363 -0.0306006335 1532 1311867769.6843049526 0.1191747487 0.1130679215 0.1571984738 0.0049141620 0.0172770000 791563353 0 402718720 -0.0881601125 -0.1414050609 -0.0311377179 1533 1311867769.7200798988 0.1207152978 0.1130729100 0.1571984738 0.0049234867 0.0174550000 791566609 0 402718720 -0.0885723978 -0.1419620067 -0.0304778796 1534 1311867769.7519550323 0.1202512607 0.1130775895 0.1571984738 0.0049241183 0.0183700000 791569697 0 402718720 -0.0884060264 -0.1412716806 -0.0302679576 1535 1311867769.7839860916 0.1219031364 0.1130833390 0.1571984738 0.0049249962 0.0176120000 791572841 0 402718720 -0.0890864059 -0.1424424052 -0.0296766218 1536 1311867769.8201379776 0.1202541068 0.1130880075 0.1571984738 0.0049360734 0.0193440000 791576153 0 402718720 -0.0884340256 -0.1407753825 -0.0294259042 1537 1311867769.8521909714 0.1212431416 0.1130933134 0.1571984738 0.0049345183 0.0188730000 791579241 0 402718720 -0.0890480503 -0.1411218494 -0.0287344772 1538 1311867769.8842990398 0.1234498098 0.1131000471 0.1571984738 0.0049341438 0.0177720000 791582441 0 402718720 -0.0894123688 -0.1430196464 -0.0285444427 1539 1311867769.9201068878 0.1228179336 0.1131063615 0.1571984738 0.0049329374 0.0175380000 791585641 0 402718720 -0.0893423930 -0.1414614171 -0.0286424812 1540 1311867769.9521000385 0.1217977032 0.1131120053 0.1571984738 0.0049337071 0.0199930000 791588785 0 402718720 -0.0882691294 -0.1405970156 -0.0277576204 1541 1311867769.9839980602 0.1220366657 0.1131177967 0.1571984738 0.0049327559 0.0200470000 791591929 0 402718720 -0.0887034386 -0.1400620639 -0.0277462713 1542 1311867770.0201199055 0.1228102371 0.1131240824 0.1571984738 0.0049314508 0.0192350000 791595185 0 402718720 -0.0897150263 -0.1395017505 -0.0270532221 1543 1311867770.0521619320 0.1230301335 0.1131305024 0.1571984738 0.0049300520 0.0208260000 791598329 0 402718720 -0.0887610838 -0.1401212364 -0.0267200526 1544 1311867770.0879909992 0.1229342967 0.1131368520 0.1571984738 0.0049382483 0.0512550000 791601585 0 402718720 -0.0890684351 -0.1398653090 -0.0272015370 1545 1311867770.1201119423 0.1230689883 0.1131432805 0.1571984738 0.0049366703 0.0197210000 791604729 0 402718720 -0.0892797261 -0.1395856142 -0.0268692859 1546 1311867770.1520049572 0.1231726483 0.1131497678 0.1571984738 0.0049351253 0.0181330000 791607929 0 402718720 -0.0894203931 -0.1393871158 -0.0264682081 1547 1311867770.1881239414 0.1223811358 0.1131557351 0.1571984738 0.0049346428 0.0184380000 791611129 0 402718720 -0.0896025822 -0.1387402117 -0.0263722725 1548 1311867770.2201859951 0.1234197617 0.1131623656 0.1571984738 0.0049338657 0.0198670000 791614329 0 402718720 -0.0892866701 -0.1397054195 -0.0259005558 1549 1311867770.2522358894 0.1235918030 0.1131690986 0.1571984738 0.0049341649 0.0204590000 791617417 0 402718720 -0.0893948153 -0.1396499425 -0.0253507514 1550 1311867770.2880940437 0.1229650527 0.1131754186 0.1571984738 0.0049357424 0.0199030000 791620673 0 402718720 -0.0894360319 -0.1396037936 -0.0252370704 1551 1311867770.3203129768 0.1227652058 0.1131816016 0.1571984738 0.0049358906 0.0202010000 791623873 0 402718720 -0.0891185328 -0.1391356736 -0.0251455959 1552 1311867770.3523910046 0.1226088479 0.1131876758 0.1571984738 0.0049343129 0.0187210000 791626961 0 402718720 -0.0893469006 -0.1389975697 -0.0255735684 1553 1311867770.3881440163 0.1232564747 0.1131941593 0.1571984738 0.0049375553 0.0190780000 791630217 0 402718720 -0.0894982144 -0.1397451162 -0.0255879611 1554 1311867770.4200921059 0.1228327379 0.1132003617 0.1571984738 0.0049429139 0.0193290000 791633417 0 402718720 -0.0899737701 -0.1392895877 -0.0253133085 1555 1311867770.4521579742 0.1229038164 0.1132066019 0.1571984738 0.0049539118 0.0195530000 791636449 0 402718720 -0.0894929841 -0.1394687742 -0.0247017741 1556 1311867770.4881989956 0.1227209046 0.1132127165 0.1571984738 0.0049528788 0.0179660000 791639705 0 402718720 -0.0897972658 -0.1391520500 -0.0246299896 1557 1311867770.5201470852 0.1229097471 0.1132189445 0.1571984738 0.0049518834 0.0192150000 791642849 0 402718720 -0.0902556330 -0.1391368210 -0.0246590730 1558 1311867770.5520849228 0.1229044721 0.1132251611 0.1571984738 0.0049508784 0.0185310000 791645937 0 402718720 -0.0897610858 -0.1393296570 -0.0244740825 1559 1311867770.5883018970 0.1236507893 0.1132318485 0.1571984738 0.0049529132 0.0516550000 791649249 0 402718720 -0.0905162320 -0.1390819401 -0.0245522521 1560 1311867770.6200389862 0.1236917153 0.1132385535 0.1571984738 0.0049591248 0.0211400000 791652393 0 402718720 -0.0902876556 -0.1394191980 -0.0239696316 1561 1311867770.6522190571 0.1236965135 0.1132452531 0.1571984738 0.0049576103 0.0186880000 791655481 0 402718720 -0.0900797099 -0.1391922086 -0.0241305549 1562 1311867770.6882569790 0.1238827333 0.1132520632 0.1571984738 0.0049561463 0.0173250000 791658793 0 402718720 -0.0903717577 -0.1391403526 -0.0238410849 1563 1311867770.7201929092 0.1246334240 0.1132593450 0.1571984738 0.0049550475 0.0184010000 791661937 0 402718720 -0.0908347890 -0.1392674595 -0.0236454625 1564 1311867770.7521960735 0.1246056855 0.1132665997 0.1571984738 0.0049535004 0.0183300000 791665025 0 402718720 -0.0905822888 -0.1391330808 -0.0234383252 1565 1311867770.7880508900 0.1242719889 0.1132736319 0.1571984738 0.0049520808 0.0184950000 791668281 0 402718720 -0.0904913172 -0.1388564557 -0.0235579889 1566 1311867770.8202619553 0.1248282418 0.1132810103 0.1571984738 0.0049507295 0.0203230000 791671481 0 402718720 -0.0908492059 -0.1390881538 -0.0229144301 1567 1311867770.8520679474 0.1251384914 0.1132885773 0.1571984738 0.0049493427 0.0195040000 791674569 0 402718720 -0.0910129547 -0.1390615404 -0.0229250416 1568 1311867770.8883039951 0.1249339506 0.1132960042 0.1571984738 0.0049478036 0.0182790000 791677881 0 402718720 -0.0908463597 -0.1388628781 -0.0226282105 1569 1311867770.9202029705 0.1251464486 0.1133035570 0.1571984738 0.0049469331 0.0182130000 791681025 0 402718720 -0.0910075158 -0.1387750506 -0.0230278336 1570 1311867770.9521191120 0.1255760044 0.1133113739 0.1571984738 0.0049454153 0.0203800000 791684113 0 402718720 -0.0913033560 -0.1389118731 -0.0224774927 1571 1311867770.9881620407 0.1255165786 0.1133191430 0.1571984738 0.0049458808 0.0187450000 791687425 0 402718720 -0.0910788476 -0.1386680603 -0.0224267468 1572 1311867771.0200800896 0.1254669577 0.1133268706 0.1571984738 0.0049443772 0.0184590000 791690569 0 402718720 -0.0906070694 -0.1386548132 -0.0223468002 1573 1311867771.0521628857 0.1264470369 0.1133352114 0.1571984738 0.0049476091 0.0189650000 791693657 0 402718720 -0.0914992616 -0.1391033381 -0.0221296102 1574 1311867771.0882019997 0.1263319999 0.1133434686 0.1571984738 0.0049472882 0.0193580000 791696969 0 402718720 -0.0912010297 -0.1386339366 -0.0221522935 1575 1311867771.1203370094 0.1270079762 0.1133521445 0.1571984738 0.0049458209 0.0415040000 791700169 0 402718720 -0.0921195149 -0.1384516060 -0.0212726127 1576 1311867771.1521589756 0.1270212531 0.1133608178 0.1571984738 0.0049445478 0.0210930000 791703201 0 402718720 -0.0921009630 -0.1382270157 -0.0212888885 1577 1311867771.1880569458 0.1270047128 0.1133694696 0.1571984738 0.0049430176 0.0192480000 791706513 0 402718720 -0.0919893160 -0.1380970627 -0.0208938401 1578 1311867771.2202770710 0.1270486265 0.1133781382 0.1571984738 0.0049414612 0.0176010000 791709657 0 402718720 -0.0919563770 -0.1379826665 -0.0212426893 1579 1311867771.2524149418 0.1277671009 0.1133872510 0.1571984738 0.0049400818 0.0201970000 791712801 0 402718720 -0.0925126001 -0.1380185485 -0.0207377654 1580 1311867771.2882540226 0.1270775050 0.1133959157 0.1571984738 0.0049389168 0.0184250000 791716057 0 402718720 -0.0920662656 -0.1371284425 -0.0209624339 1581 1311867771.3202269077 0.1276275665 0.1134049173 0.1571984738 0.0049375245 0.0202360000 791719201 0 402718720 -0.0919241756 -0.1374944896 -0.0207643081 1582 1311867771.3521800041 0.1283968836 0.1134143939 0.1571984738 0.0049361581 0.0180690000 791722289 0 402718720 -0.0920616761 -0.1380780488 -0.0210235342 1583 1311867771.3881111145 0.1292710006 0.1134244107 0.1571984738 0.0049352794 0.0191890000 791725545 0 402718720 -0.0926642790 -0.1379302293 -0.0208297856 1584 1311867771.4203948975 0.1266160756 0.1134327388 0.1571984738 0.0049345081 0.0189060000 791728745 0 402718720 -0.0919798240 -0.1345744431 -0.0200405158 1585 1311867771.4521930218 0.1281300783 0.1134420116 0.1571984738 0.0049334233 0.0190940000 791731833 0 402718720 -0.0922698379 -0.1358359456 -0.0210265685 1586 1311867771.4881279469 0.1307674944 0.1134529356 0.1571984738 0.0049333693 0.0185170000 791735089 0 402718720 -0.0928192660 -0.1377668828 -0.0210145563 1587 1311867771.5202970505 0.1279520094 0.1134620718 0.1571984738 0.0049326555 0.0190510000 791738233 0 402718720 -0.0916402265 -0.1342890263 -0.0209297370 1588 1311867771.5521659851 0.1313795298 0.1134733548 0.1571984738 0.0049319118 0.0191640000 791741377 0 402718720 -0.0929092765 -0.1370842159 -0.0198121089 1589 1311867771.5883660316 0.1322363019 0.1134851628 0.1571984738 0.0049316657 0.0186890000 791744633 0 402718720 -0.0932934731 -0.1370301247 -0.0197505075 1590 1311867771.6201260090 0.1309373975 0.1134961391 0.1571984738 0.0049302919 0.0186380000 791747777 0 402718720 -0.0932619199 -0.1347737610 -0.0193917062 1591 1311867771.6522150040 0.1316649765 0.1135075588 0.1571984738 0.0049290209 0.0518380000 791750921 0 402718720 -0.0929665715 -0.1357794851 -0.0197972916 1592 1311867771.6883049011 0.1328264922 0.1135196938 0.1571984738 0.0049277180 0.0207520000 791754177 0 402718720 -0.0934154689 -0.1362050772 -0.0192641001 1593 1311867771.7201559544 0.1332879364 0.1135321033 0.1571984738 0.0049262672 0.0180090000 791757321 0 402718720 -0.0936313644 -0.1356587559 -0.0189762097 1594 1311867771.7525970936 0.1328360885 0.1135442137 0.1571984738 0.0049255033 0.0189430000 791760465 0 402718720 -0.0932729989 -0.1348456740 -0.0187133495 1595 1311867771.7882320881 0.1336198151 0.1135568003 0.1571984738 0.0049242679 0.0198530000 791763721 0 402718720 -0.0934618115 -0.1349539906 -0.0190448184 1596 1311867771.8203339577 0.1340243965 0.1135696246 0.1571984738 0.0049236149 0.0186870000 791766921 0 402718720 -0.0937853605 -0.1345520914 -0.0184401255 1597 1311867771.8522739410 0.1343701184 0.1135826493 0.1571984738 0.0049227344 0.0184730000 791770009 0 402718720 -0.0942809582 -0.1339408308 -0.0173128657 1598 1311867771.8881349564 0.1348201931 0.1135959394 0.1571984738 0.0049214062 0.0179700000 791773265 0 402718720 -0.0940718129 -0.1344299018 -0.0184265617 1599 1311867771.9202098846 0.1355324835 0.1136096583 0.1571984738 0.0049199130 0.0178700000 791776465 0 402718720 -0.0940996632 -0.1349218637 -0.0188461840 1600 1311867771.9522581100 0.1357071549 0.1136234692 0.1571984738 0.0049184568 0.0190520000 791779553 0 402718720 -0.0939252600 -0.1347861290 -0.0191619340 1601 1311867771.9881980419 0.1360995919 0.1136375080 0.1571984738 0.0049175875 0.0188230000 791782809 0 402718720 -0.0935546309 -0.1350944638 -0.0190645009 1602 1311867772.0202260017 0.1359950155 0.1136514640 0.1571984738 0.0049161044 0.0188270000 791786009 0 402718720 -0.0931050181 -0.1348967701 -0.0189387240 1603 1311867772.0522649288 0.1350825578 0.1136648334 0.1571984738 0.0049155083 0.0185660000 791789097 0 402718720 -0.0935641751 -0.1329789907 -0.0185821243 1604 1311867772.0881819725 0.1356214732 0.1136785221 0.1571984738 0.0049140540 0.0191120000 791792353 0 402718720 -0.0935073122 -0.1334921271 -0.0190274809 1605 1311867772.1202239990 0.1370478123 0.1136930824 0.1571984738 0.0049141303 0.0186740000 791795497 0 402718720 -0.0932073742 -0.1351923048 -0.0187840350 1606 1311867772.1522779465 0.1374232322 0.1137078583 0.1571984738 0.0049126628 0.0185840000 791798585 0 402718720 -0.0940540284 -0.1348343045 -0.0180902723 1607 1311867772.1884620190 0.1377583146 0.1137228244 0.1571984738 0.0049125568 0.0965030000 804114981 0 402718720 -0.0944419950 -0.1342898458 -0.0174945798 1608 1311867772.2202379704 0.1372266263 0.1137374412 0.1571984738 0.0049123042 0.0348040000 807777333 0 402718720 -0.0935294554 -0.1343065649 -0.0189830065 1609 1311867772.2522220612 0.1374785453 0.1137521963 0.1571984738 0.0049109724 0.0188710000 810972613 0 402718720 -0.0937790573 -0.1341782957 -0.0185952820 1610 1311867772.2883520126 0.1377035081 0.1137670729 0.1571984738 0.0049095478 0.0162010000 810975925 0 402718720 -0.0938597471 -0.1341666281 -0.0186627731 1611 1311867772.3202190399 0.1376260370 0.1137818830 0.1571984738 0.0049083595 0.0156750000 810979069 0 402718720 -0.0937050208 -0.1341836601 -0.0186977554 1612 1311867772.3522899151 0.1375164539 0.1137966067 0.1571984738 0.0049069028 0.0157710000 810982157 0 402718720 -0.0938024372 -0.1340416819 -0.0186418947 1613 1311867772.3883121014 0.1377256811 0.1138114418 0.1571984738 0.0049054441 0.0161470000 810985469 0 402718720 -0.0938057825 -0.1343565881 -0.0186796337 1614 1311867772.4202120304 0.1376014203 0.1138261815 0.1571984738 0.0049040587 0.0164950000 810988613 0 402718720 -0.0938332155 -0.1343026012 -0.0186014157 1615 1311867772.4521598816 0.1371160895 0.1138406025 0.1571984738 0.0049025707 0.0158640000 810991757 0 402718720 -0.0937565789 -0.1340037286 -0.0185933262 1616 1311867772.4881889820 0.1370456964 0.1138549621 0.1571984738 0.0049010611 0.0155110000 810994957 0 402718720 -0.0938303769 -0.1340668201 -0.0184336379 1617 1311867772.5203120708 0.1372722536 0.1138694441 0.1571984738 0.0048995928 0.0159120000 810998157 0 402718720 -0.0937872082 -0.1344727874 -0.0185159612 1618 1311867772.5525689125 0.1370716840 0.1138837841 0.1571984738 0.0048981071 0.0160140000 811001245 0 402718720 -0.0939613208 -0.1342145503 -0.0182413422 1619 1311867772.5885000229 0.1369979680 0.1138980610 0.1571984738 0.0048967246 0.0156660000 811004501 0 402718720 -0.0937973186 -0.1343740970 -0.0182845201 1620 1311867772.6203110218 0.1355294883 0.1139114137 0.1571984738 0.0048953695 0.0353640000 811007645 0 402718720 -0.0920908675 -0.1337740868 -0.0187769216 1621 1311867772.6522929668 0.1367893368 0.1139255272 0.1571984738 0.0048939862 0.0153040000 811010733 0 402718720 -0.0937028602 -0.1342219263 -0.0180167351 1622 1311867772.6882801056 0.1371688992 0.1139398572 0.1571984738 0.0048926428 0.0152210000 811013989 0 402718720 -0.0939209312 -0.1346368045 -0.0179060511 1623 1311867772.7202830315 0.1375295818 0.1139543919 0.1571984738 0.0048912762 0.0154660000 811017189 0 402718720 -0.0940552801 -0.1347843558 -0.0178308822 1624 1311867772.7522249222 0.1370370686 0.1139686053 0.1571984738 0.0048897902 0.0153220000 811020277 0 402718720 -0.0938040689 -0.1343830228 -0.0176826715 1625 1311867772.7881810665 0.1369343251 0.1139827381 0.1571984738 0.0048884892 0.0320800000 811023533 0 402718720 -0.0935521796 -0.1344642639 -0.0178769138 1626 1311867772.8202509880 0.1374880075 0.1139971940 0.1571984738 0.0048873495 0.0193870000 811026733 0 402718720 -0.0940763429 -0.1346160173 -0.0176193081 1627 1311867772.8523159027 0.1377882808 0.1140118167 0.1571984738 0.0048859327 0.0170780000 811029821 0 402718720 -0.0939381197 -0.1348176599 -0.0174409021 1628 1311867772.8883020878 0.1376694292 0.1140263484 0.1571984738 0.0048844497 0.0181790000 811033077 0 402718720 -0.0940809697 -0.1345231235 -0.0171265062 1629 1311867772.9202198982 0.1376701593 0.1140408627 0.1571984738 0.0048830007 0.0166730000 811036277 0 402718720 -0.0941334143 -0.1343484223 -0.0175472442 1630 1311867772.9523079395 0.1383344531 0.1140557667 0.1571984738 0.0048819599 0.0266620000 811039365 0 402718720 -0.0943858549 -0.1343595386 -0.0164118093 1631 1311867772.9882879257 0.1388623118 0.1140709761 0.1571984738 0.0048812147 0.1389350000 823341193 0 402718720 -0.0942247435 -0.1348642111 -0.0170239918 1632 1311867773.0206930637 0.1389738321 0.1140862352 0.1571984738 0.0048798902 0.0147700000 827003433 0 402718720 -0.0935894176 -0.1352339089 -0.0175990667 1633 1311867773.0522789955 0.1392301619 0.1141016326 0.1571984738 0.0048784259 0.0155420000 830198713 0 402718720 -0.0934490710 -0.1353710145 -0.0178065430 1634 1311867773.0882170200 0.1392644197 0.1141170321 0.1571984738 0.0048770564 0.0152080000 830202025 0 402718720 -0.0933276564 -0.1353596151 -0.0178410150 1635 1311867773.1201949120 0.1392210424 0.1141323862 0.1571984738 0.0048760220 0.0141140000 830205169 0 402718720 -0.0934586972 -0.1351094991 -0.0175197069 1636 1311867773.1522679329 0.1394756436 0.1141478772 0.1571984738 0.0048746681 0.0319280000 830208257 0 402718720 -0.0934913903 -0.1352176964 -0.0173746068 1637 1311867773.1883080006 0.1394907981 0.1141633586 0.1571984738 0.0048733047 0.0184870000 830211569 0 402718720 -0.0931090191 -0.1352216154 -0.0175434835 1638 1311867773.2203021049 0.1399798542 0.1141791195 0.1571984738 0.0048718391 0.0149820000 830214713 0 402718720 -0.0933983251 -0.1353750080 -0.0172453932 1639 1311867773.2523961067 0.1405797452 0.1141952273 0.1571984738 0.0048704601 0.0148950000 830217801 0 402718720 -0.0936483294 -0.1353394836 -0.0169664882 1640 1311867773.2882409096 0.1403998584 0.1142112057 0.1571984738 0.0048692957 0.0149140000 830221057 0 402718720 -0.0935433358 -0.1349339485 -0.0164200328 1641 1311867773.3202419281 0.1410366297 0.1142275527 0.1571984738 0.0048684085 0.0147530000 830224201 0 402718720 -0.0936535299 -0.1352791190 -0.0165446233 1642 1311867773.3524138927 0.1412408948 0.1142440042 0.1571984738 0.0048669959 0.0151490000 830227345 0 402718720 -0.0936599448 -0.1353856921 -0.0161237791 1643 1311867773.3883919716 0.1415993720 0.1142606539 0.1571984738 0.0048655228 0.0153440000 830230601 0 402718720 -0.0937463269 -0.1354986429 -0.0161161274 1644 1311867773.4205429554 0.1419667751 0.1142775067 0.1571984738 0.0048645909 0.1354130000 842532781 0 402718720 -0.0939059630 -0.1353401095 -0.0161682107 1645 1311867773.4524109364 0.1418113559 0.1142942446 0.1571984738 0.0048631273 0.0146350000 846195021 0 402718720 -0.0937285051 -0.1350749433 -0.0156437159 1646 1311867773.4882578850 0.1423146427 0.1143112680 0.1571984738 0.0048618377 0.0144080000 849390525 0 402718720 -0.0938747972 -0.1352789104 -0.0152010424 1647 1311867773.5204710960 0.1426335126 0.1143284642 0.1571984738 0.0048609125 0.0143150000 849393669 0 402718720 -0.0939175114 -0.1351595372 -0.0150923003 1648 1311867773.5523319244 0.1429580003 0.1143458365 0.1571984738 0.0048594614 0.0143590000 849396813 0 402718720 -0.0940320939 -0.1351522505 -0.0150123881 1649 1311867773.5883278847 0.1430227906 0.1143632270 0.1571984738 0.0048584208 0.0349440000 849400069 0 402718720 -0.0938740894 -0.1352795511 -0.0152699798 1650 1311867773.6206080914 0.1434548795 0.1143808583 0.1571984738 0.0048575814 0.0176780000 849403157 0 402718720 -0.0940808058 -0.1352046877 -0.0150027601 1651 1311867773.6522929668 0.1438232362 0.1143986914 0.1571984738 0.0048561176 0.0157660000 849406301 0 402718720 -0.0938593224 -0.1352165043 -0.0139652686 1652 1311867773.6884210110 0.1440087557 0.1144166152 0.1571984738 0.0048550858 0.0142000000 849409557 0 402718720 -0.0938023850 -0.1353939027 -0.0146562671 1653 1311867773.7203130722 0.1437100619 0.1144343366 0.1571984738 0.0048538078 0.0139780000 849412701 0 402718720 -0.0936584845 -0.1349040419 -0.0140788639 1654 1311867773.7523710728 0.1439918876 0.1144522069 0.1571984738 0.0048525938 0.1101000000 861716429 0 402718720 -0.0935564414 -0.1348954886 -0.0139556928 1655 1311867773.7883739471 0.1440396011 0.1144700845 0.1571984738 0.0048542999 0.0141250000 865378781 0 402718720 -0.0916622728 -0.1359169781 -0.0112763848 1656 1311867773.8203001022 0.1438727975 0.1144878397 0.1571984738 0.0048534516 0.0137630000 868574173 0 402718720 -0.0918045714 -0.1358860433 -0.0113111930 1657 1311867773.8524808884 0.1437039673 0.1145054717 0.1571984738 0.0048520838 0.0139510000 868577261 0 402718720 -0.0918485895 -0.1358700693 -0.0112348842 1658 1311867773.8882279396 0.1436506510 0.1145230502 0.1571984738 0.0048509031 0.0138290000 868580517 0 402718720 -0.0919644907 -0.1359002590 -0.0110810660 1659 1311867773.9203219414 0.1436348259 0.1145405980 0.1571984738 0.0048498981 0.0422340000 868583717 0 402718720 -0.0920686796 -0.1359268725 -0.0107585192 1660 1311867773.9523289204 0.1435299963 0.1145580615 0.1571984738 0.0048484680 0.0176640000 868586805 0 402718720 -0.0920371711 -0.1360809654 -0.0107323322 1661 1311867773.9883420467 0.1433613747 0.1145754024 0.1571984738 0.0048470976 0.0140580000 868590061 0 402718720 -0.0918816030 -0.1359677017 -0.0109191984 1662 1311867774.0203340054 0.1435839683 0.1145928564 0.1571984738 0.0048479939 0.0140820000 868593261 0 402718720 -0.0919062048 -0.1360625923 -0.0108160516 1663 1311867774.0524079800 0.1435686797 0.1146102803 0.1571984738 0.0048501232 0.0138320000 868596349 0 402718720 -0.0919601992 -0.1359868646 -0.0105028069 1664 1311867774.0885128975 0.1436728239 0.1146277457 0.1571984738 0.0048530065 0.0136470000 868599605 0 402718720 -0.0919250846 -0.1360402256 -0.0103203114 1665 1311867774.1246058941 0.1436586678 0.1146451817 0.1571984738 0.0048517462 0.1060310000 880903801 0 402718720 -0.0918649584 -0.1360455602 -0.0106709786 1666 1311867774.1523950100 0.1440711617 0.1146628444 0.1571984738 0.0048507031 0.0133840000 884565473 0 402718720 -0.0926176757 -0.1360383928 -0.0106787803 1667 1311867774.1882340908 0.1443566382 0.1146806571 0.1571984738 0.0048493817 0.0134570000 887760921 0 402718720 -0.0924682617 -0.1360577643 -0.0104854004 1668 1311867774.2202079296 0.1446586698 0.1146986295 0.1571984738 0.0048479856 0.0133530000 887764065 0 402718720 -0.0924008563 -0.1361259669 -0.0105474265 1669 1311867774.2527189255 0.1446567923 0.1147165793 0.1571984738 0.0048467073 0.0133460000 887767209 0 402718720 -0.0924191177 -0.1360515952 -0.0104960799 1670 1311867774.2883949280 0.1449147165 0.1147346620 0.1571984738 0.0048453559 0.0336230000 887770465 0 402718720 -0.0925422907 -0.1361766905 -0.0101869935 1671 1311867774.3202209473 0.1454287618 0.1147530307 0.1571984738 0.0048441711 0.0188540000 887773665 0 402718720 -0.0927247927 -0.1360899657 -0.0096046543 1672 1311867774.3524949551 0.1456221193 0.1147714931 0.1571984738 0.0048429098 0.0826750000 900072973 0 402718720 -0.0926492885 -0.1361959726 -0.0099005317 1673 1311867774.3882880211 0.1457817107 0.1147900288 0.1571984738 0.0048414898 0.0133550000 903735437 0 402718720 -0.0926553234 -0.1362142265 -0.0096104462 1674 1311867774.4203898907 0.1463263780 0.1148088677 0.1571984738 0.0048410540 0.0132350000 906930773 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1675 1311867774.4523808956 0.1464067549 0.1148277321 0.1571984738 0.0048408969 0.0079520000 914685181 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1676 1311867774.4882450104 0.1462278366 0.1148464672 0.1571984738 0.0048395525 0.0075760000 918034037 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1677 1311867774.5202300549 0.1462074816 0.1148651679 0.1571984738 0.0048392118 0.0121250000 918113821 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1678 1311867774.5524051189 0.1463013440 0.1148839022 0.1571984738 0.0048390705 0.0073260000 918193493 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1679 1311867774.5882558823 0.1465219855 0.1149027456 0.1571984738 0.0048388782 0.0073010000 918273333 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1680 1311867774.6202490330 0.1467431337 0.1149216982 0.1571984738 0.0048386551 0.0073890000 918353117 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1681 1311867774.6524269581 0.1470214427 0.1149407939 0.1571984738 0.0048408405 0.0134100000 918432789 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1682 1311867774.6884260178 0.1473004073 0.1149600326 0.1571984738 0.0048415430 0.0151070000 918512629 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1683 1311867774.7203860283 0.1476278305 0.1149794431 0.1571984738 0.0048423930 0.0090650000 918592413 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1684 1311867774.7526240349 0.1480157971 0.1149990609 0.1571984738 0.0048441459 0.0072370000 918672085 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1685 1311867774.7884149551 0.1482086927 0.1150187699 0.1571984738 0.0048438567 0.0067400000 918751925 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1686 1311867774.8204150200 0.1485701948 0.1150386699 0.1571984738 0.0048454561 0.0137650000 918831709 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1687 1311867774.8526229858 0.1487952322 0.1150586797 0.1571984738 0.0048472175 0.0084510000 918911437 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1688 1311867774.8884160519 0.1490766108 0.1150788325 0.1571984738 0.0048459264 0.0069330000 918991221 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1689 1311867774.9203650951 0.1492314041 0.1150990531 0.1571984738 0.0048444949 0.0066440000 919071005 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1690 1311867774.9526898861 0.1495425850 0.1151194339 0.1571984738 0.0048433201 0.0071330000 919150677 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1691 1311867774.9884328842 0.1497259885 0.1151398990 0.1571984738 0.0048420123 0.0116800000 919153725 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1692 1311867775.0203111172 0.1499380916 0.1151604653 0.1571984738 0.0048406958 0.0074270000 919156685 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1693 1311867775.0525069237 0.1501643360 0.1151811410 0.1571984738 0.0048395028 0.0060720000 919159533 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1694 1311867775.0902869701 0.1502915323 0.1152018673 0.1571984738 0.0048398720 0.0072490000 919239485 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1695 1311867775.1203780174 0.1503624320 0.1152226110 0.1571984738 0.0048384740 0.0142170000 919319101 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1696 1311867775.1541199684 0.1504187733 0.1152433634 0.1571984738 0.0048371162 0.0095480000 919398885 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1697 1311867775.1884870529 0.1504187733 0.1152640914 0.1571984738 0.0048357959 0.0068830000 919478669 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1698 1311867775.2203218937 0.1505605280 0.1152848785 0.1571984738 0.0048350538 0.0068680000 919558453 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1699 1311867775.2524089813 0.1507449001 0.1153057496 0.1571984738 0.0048351594 0.0072560000 919638125 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1700 1311867775.2884750366 0.1508172601 0.1153266387 0.1571984738 0.0048340091 0.0070440000 919717965 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1701 1311867775.3203940392 0.1509595811 0.1153475870 0.1571984738 0.0048329617 0.0073170000 919797749 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1702 1311867775.3524069786 0.1513721198 0.1153687530 0.1571984738 0.0048330599 0.0084980000 919877421 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1703 1311867775.3883419037 0.1514573842 0.1153899442 0.1571984738 0.0048317700 0.0069490000 919957317 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1704 1311867775.4204111099 0.1515672803 0.1154111750 0.1571984738 0.0048342042 0.0162640000 920037101 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1705 1311867775.4524068832 0.1519826055 0.1154326245 0.1571984738 0.0048329049 0.0091350000 920116829 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1706 1311867775.4885649681 0.1520837247 0.1154541082 0.1571984738 0.0048320249 0.0071290000 920196613 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1707 1311867775.5203950405 0.1521695852 0.1154756170 0.1571984738 0.0048316931 0.0065930000 920276397 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1708 1311867775.5525400639 0.1524304301 0.1154972533 0.1571984738 0.0048309320 0.0068620000 920356069 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1709 1311867775.5884749889 0.1527575552 0.1155190557 0.1571984738 0.0048300647 0.0124060000 920435909 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1710 1311867775.6203949451 0.1530130357 0.1155409820 0.1571984738 0.0048287597 0.0166990000 920515693 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1711 1311867775.6524128914 0.1532700807 0.1155630329 0.1571984738 0.0048283578 0.0090790000 920595365 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1712 1311867775.6885650158 0.1535579264 0.1155852261 0.1571984738 0.0048286992 0.0065090000 920675205 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1713 1311867775.7204198837 0.1537742019 0.1156075198 0.1571984738 0.0048283807 0.0061940000 920754933 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1714 1311867775.7524271011 0.1540629119 0.1156299558 0.1571984738 0.0048279821 0.0067910000 920834605 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1715 1311867775.7886290550 0.1543932557 0.1156525583 0.1571984738 0.0048303521 0.0075400000 920914501 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1716 1311867775.8203799725 0.1547240764 0.1156753273 0.1571984738 0.0048318556 0.0070700000 920994229 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1717 1311867775.8527259827 0.1550378799 0.1156982525 0.1571984738 0.0048311099 0.0065270000 921073957 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1718 1311867775.8883819580 0.1553281844 0.1157213200 0.1571984738 0.0048305201 0.0066120000 921153797 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1719 1311867775.9203379154 0.1554735303 0.1157444451 0.1571984738 0.0048295601 0.0067900000 921233525 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1720 1311867775.9524650574 0.1558194458 0.1157677446 0.1571984738 0.0048289266 0.0080820000 921313197 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1721 1311867775.9884839058 0.1559882015 0.1157911150 0.1571984738 0.0048276446 0.0078310000 921393093 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1722 1311867776.0209159851 0.1560751796 0.1158145087 0.1571984738 0.0048262681 0.0078630000 921472821 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1723 1311867776.0528860092 0.1563166380 0.1158380155 0.1571984738 0.0048255803 0.0079340000 921552493 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1724 1311867776.0888249874 0.1565581858 0.1158616351 0.1571984738 0.0048243285 0.0081820000 921632389 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1725 1311867776.1205348969 0.1567997485 0.1158853673 0.1571984738 0.0048232611 0.0079660000 921712117 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1726 1311867776.1527059078 0.1570004970 0.1159091884 0.1571984738 0.0048220675 0.0090010000 921791789 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1727 1311867776.1883540154 0.1571055204 0.1159330426 0.1571984738 0.0048207568 0.0078090000 921871685 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1728 1311867776.2204220295 0.1573470682 0.1159570091 0.1573470682 0.0048195972 0.0077510000 921951413 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1729 1311867776.2526340485 0.1575480103 0.1159810640 0.1575480103 0.0048184181 0.0072490000 922031141 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1730 1311867776.2885830402 0.1577347368 0.1160051991 0.1577347368 0.0048172563 0.0085170000 922110981 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1731 1311867776.3206388950 0.1579356641 0.1160294224 0.1579356641 0.0048162730 0.0076350000 922190765 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1732 1311867776.3524949551 0.1580087692 0.1160536599 0.1580087692 0.0048159784 0.0079240000 922270493 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1733 1311867776.3885569572 0.1581550688 0.1160779538 0.1581550688 0.0048153051 0.0078140000 922350333 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1734 1311867776.4204070568 0.1583784372 0.1161023485 0.1583784372 0.0048153830 0.0076530000 922430061 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1735 1311867776.4524679184 0.1584515870 0.1161267573 0.1584515870 0.0048155166 0.0078150000 922509733 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1736 1311867776.4886200428 0.1586122215 0.1161512305 0.1586122215 0.0048150258 0.0079640000 922589629 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1737 1311867776.5206589699 0.1587731540 0.1161757682 0.1587731540 0.0048152511 0.0089620000 922669413 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1738 1311867776.5527141094 0.1588392556 0.1162003156 0.1588392556 0.0048145518 0.0092100000 922749085 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1739 1311867776.5885510445 0.1590339541 0.1162249468 0.1590339541 0.0048142096 0.0077850000 922828925 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1740 1311867776.6204509735 0.1593578309 0.1162497359 0.1593578309 0.0048138935 0.0077370000 922908709 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1741 1311867776.6527190208 0.1595728695 0.1162746199 0.1595728695 0.0048128976 0.0076480000 922988437 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1742 1311867776.6886329651 0.1599366516 0.1162996842 0.1599366516 0.0048125647 0.0076350000 923068277 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1743 1311867776.7206139565 0.1602826267 0.1163249183 0.1602826267 0.0048119619 0.0075790000 923148061 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1744 1311867776.7525858879 0.1605053544 0.1163502511 0.1605053544 0.0048137248 0.0081580000 923227789 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1745 1311867776.7885699272 0.1608026326 0.1163757252 0.1608026326 0.0048154823 0.0077400000 923307685 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1746 1311867776.8208339214 0.1611546278 0.1164013718 0.1611546278 0.0048168062 0.0080190000 923387525 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1747 1311867776.8526189327 0.1614322811 0.1164271479 0.1614322811 0.0048162298 0.0077400000 923467253 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1748 1311867776.8885478973 0.1616172343 0.1164530004 0.1616172343 0.0048153836 0.0077040000 923547093 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1749 1311867776.9204618931 0.1617846340 0.1164789190 0.1617846340 0.0048157094 0.0090910000 923626933 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1750 1311867776.9528760910 0.1620821208 0.1165049779 0.1620821208 0.0048146617 0.0074720000 923706661 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1751 1311867776.9885330200 0.1623383015 0.1165311535 0.1623383015 0.0048135720 0.0077950000 923786557 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1752 1311867777.0207309723 0.1624281108 0.1165573504 0.1624281108 0.0048123749 0.0084540000 923866397 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1753 1311867777.0524590015 0.1625025719 0.1165835598 0.1625025719 0.0048110516 0.0078570000 923946069 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1754 1311867777.0885760784 0.1625397950 0.1166097607 0.1625397950 0.0048097343 0.0077250000 924025965 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1755 1311867777.1204578876 0.1624810100 0.1166358981 0.1625397950 0.0048085106 0.0091870000 924105805 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1756 1311867777.1528110504 0.1627022177 0.1166621318 0.1627022177 0.0048072751 0.0084350000 924185589 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1757 1311867777.1886088848 0.1628324687 0.1166884097 0.1628324687 0.0048062027 0.0082760000 924265429 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1758 1311867777.2239480019 0.1630002856 0.1167147532 0.1630002856 0.0048053339 0.0078980000 924345381 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1759 1311867777.2526159286 0.1630771011 0.1167411104 0.1630771011 0.0048043828 0.0060450000 924348061 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1760 1311867777.2885389328 0.1631157249 0.1167674597 0.1631157249 0.0048039587 0.0060260000 924351189 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1761 1311867777.3205959797 0.1631761193 0.1167938132 0.1631761193 0.0048046379 0.0075420000 924431029 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1762 1311867777.3526799679 0.1631243229 0.1168201075 0.1631761193 0.0048037679 0.0084880000 924510757 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1763 1311867777.3886039257 0.1630729288 0.1168463428 0.1631761193 0.0048035776 0.0067440000 924513829 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1764 1311867777.4204750061 0.1630977094 0.1168725624 0.1631761193 0.0048023916 0.0068460000 924516789 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1765 1311867777.4525530338 0.1630867720 0.1168987461 0.1631761193 0.0048011307 0.0067840000 924519749 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1766 1311867777.4885380268 0.1630993038 0.1169249072 0.1631761193 0.0047998899 0.0072110000 924599645 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1767 1311867777.5206110477 0.1632255316 0.1169511102 0.1632255316 0.0047996510 0.0067830000 924602661 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1768 1311867777.5525240898 0.1632408053 0.1169772921 0.1632408053 0.0047993207 0.0100120000 924682389 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1769 1311867777.5886271000 0.1632040739 0.1170034237 0.1632408053 0.0047992632 0.0095560000 924762285 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1770 1311867777.6205470562 0.1632991582 0.1170295795 0.1632991582 0.0047994606 0.0081830000 924842125 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1771 1311867777.6525719166 0.1631777585 0.1170556372 0.1632991582 0.0047988107 0.0080300000 924921909 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1772 1311867777.6886498928 0.1631216407 0.1170816338 0.1632991582 0.0047980296 0.0080230000 925001749 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1773 1311867777.7205779552 0.1630838811 0.1171075798 0.1632991582 0.0047970944 0.0080480000 925081589 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1774 1311867777.7526819706 0.1631420404 0.1171335293 0.1632991582 0.0047960596 0.0073660000 925161317 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1775 1311867777.7886629105 0.1631234288 0.1171594391 0.1632991582 0.0047950815 0.0087810000 925241269 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1776 1311867777.8204939365 0.1632616222 0.1171853976 0.1632991582 0.0047941065 0.0081480000 925321053 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1777 1311867777.8526470661 0.1634355634 0.1172114247 0.1634355634 0.0047933829 0.0081970000 925400837 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1778 1311867777.8886229992 0.1633504182 0.1172373746 0.1634355634 0.0047924484 0.0107070000 925480733 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1779 1311867777.9204709530 0.1632664949 0.1172632482 0.1634355634 0.0047915976 0.0092950000 925560517 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1780 1311867777.9525170326 0.1634887308 0.1172892176 0.1634887308 0.0047907274 0.0098790000 925640301 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1781 1311867777.9886510372 0.1636508107 0.1173152488 0.1636508107 0.0047909727 0.0098690000 925720197 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1782 1311867778.0204679966 0.1632996500 0.1173410537 0.1636508107 0.0047905967 0.0102050000 925800037 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1783 1311867778.0530679226 0.1631759554 0.1173667604 0.1636508107 0.0047894771 0.0089160000 925879765 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1784 1311867778.0887510777 0.1633365005 0.1173925282 0.1636508107 0.0047896294 0.0076520000 925959661 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1785 1311867778.1204960346 0.1631277204 0.1174181501 0.1636508107 0.0047887724 0.0076210000 926039445 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1786 1311867778.1528480053 0.1631910652 0.1174437788 0.1636508107 0.0047881381 0.0092030000 926119229 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1787 1311867778.1887469292 0.1630749106 0.1174693139 0.1636508107 0.0047874277 0.0080140000 926199125 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1788 1311867778.2207179070 0.1627813578 0.1174946562 0.1636508107 0.0047865209 0.0082060000 926278909 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1789 1311867778.2529089451 0.1626866460 0.1175199172 0.1636508107 0.0047852744 0.0072070000 926358693 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1790 1311867778.2887310982 0.1622291505 0.1175448945 0.1636508107 0.0047852490 0.0076630000 926438589 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1791 1311867778.3209760189 0.1617617905 0.1175695828 0.1636508107 0.0047844166 0.0108070000 926518429 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1792 1311867778.3526780605 0.1616674364 0.1175941910 0.1636508107 0.0047832114 0.0110980000 926598157 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1793 1311867778.3886349201 0.1613796949 0.1176186113 0.1636508107 0.0047829054 0.0109740000 926678053 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1794 1311867778.4206590652 0.1612213254 0.1176429160 0.1636508107 0.0047817184 0.0095560000 926757893 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1795 1311867778.4525859356 0.1611772180 0.1176671691 0.1636508107 0.0047804418 0.0093920000 926837621 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1796 1311867778.4886779785 0.1609902531 0.1176912911 0.1636508107 0.0047798500 0.0079830000 926917517 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1797 1311867778.5207109451 0.1606678218 0.1177152068 0.1636508107 0.0047797667 0.0077110000 926997357 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1798 1311867778.5527029037 0.1605235934 0.1177390157 0.1636508107 0.0047785951 0.0071410000 927077141 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1799 1311867778.5889399052 0.1602867395 0.1177626665 0.1636508107 0.0047779274 0.0070250000 927157037 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1800 1311867778.6209189892 0.1598502249 0.1177860484 0.1636508107 0.0047780032 0.0084150000 927236821 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1801 1311867778.6526169777 0.1596271992 0.1178092806 0.1636508107 0.0047768681 0.0083000000 927316549 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1802 1311867778.6887080669 0.1594980210 0.1178324153 0.1636508107 0.0047757494 0.0080180000 927396501 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1803 1311867778.7206969261 0.1591323018 0.1178553215 0.1636508107 0.0047759097 0.0064570000 927399517 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1804 1311867778.7526590824 0.1590534896 0.1178781586 0.1636508107 0.0047749445 0.0062420000 927402421 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1805 1311867778.7901639938 0.1588309705 0.1179008472 0.1636508107 0.0047739362 0.0085160000 927482429 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1806 1311867778.8206639290 0.1583009362 0.1179232171 0.1636508107 0.0047746132 0.0061400000 927485277 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1807 1311867778.8528640270 0.1579939127 0.1179453924 0.1636508107 0.0047763407 0.0062310000 927488237 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1808 1311867778.8888111115 0.1577517539 0.1179674092 0.1636508107 0.0047769805 0.0062030000 927491309 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1809 1311867778.9213368893 0.1573453248 0.1179891769 0.1636508107 0.0047772986 0.0070920000 927571149 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1810 1311867778.9526879787 0.1567382365 0.1180105853 0.1636508107 0.0047805175 0.0068430000 927650877 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1811 1311867778.9886820316 0.1563565433 0.1180317592 0.1636508107 0.0047816488 0.0268990000 927730773 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1812 1311867779.0207788944 0.1561685950 0.1180528060 0.1636508107 0.0047809629 0.0125780000 927733789 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1813 1311867779.0530660152 0.1558818668 0.1180736714 0.1636508107 0.0047815138 0.0088500000 927813517 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1814 1311867779.0886540413 0.1557369530 0.1180944340 0.1636508107 0.0047819090 0.0073640000 927893413 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1815 1311867779.1266849041 0.1558356583 0.1181152281 0.1636508107 0.0047822082 0.0075750000 927973085 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1816 1311867779.1527431011 0.1558465213 0.1181360052 0.1636508107 0.0047817239 0.0073450000 928052757 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1817 1311867779.1886849403 0.1558172107 0.1181567433 0.1636508107 0.0047828627 0.0078800000 928132597 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1818 1311867779.2209370136 0.1557769775 0.1181774365 0.1636508107 0.0047833841 0.0205230000 928212325 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1819 1311867779.2566668987 0.1557231843 0.1181980774 0.1636508107 0.0047833448 0.0099250000 928292165 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1820 1311867779.2885839939 0.1555707604 0.1182186119 0.1636508107 0.0047857253 0.0076140000 928371893 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1821 1311867779.3206019402 0.1556480229 0.1182391662 0.1636508107 0.0047856059 0.0088930000 928451733 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1822 1311867779.3566238880 0.1556496322 0.1182596988 0.1636508107 0.0047852767 0.0068100000 928531629 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1823 1311867779.3887670040 0.1555251628 0.1182801406 0.1636508107 0.0047861129 0.0072680000 928611301 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1824 1311867779.4207890034 0.1554153860 0.1183004999 0.1636508107 0.0047857276 0.0071590000 928691029 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1825 1311867779.4566130638 0.1553072333 0.1183207775 0.1636508107 0.0047868892 0.0070420000 928770869 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1826 1311867779.4888589382 0.1550493836 0.1183408918 0.1636508107 0.0047900566 0.0072100000 928850597 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1827 1311867779.5205628872 0.1548376530 0.1183608681 0.1636508107 0.0047916666 0.0070870000 928930325 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1828 1311867779.5566120148 0.1544540077 0.1183806127 0.1636508107 0.0047920735 0.0068130000 929010221 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1829 1311867779.5885720253 0.1541481018 0.1184001685 0.1636508107 0.0047948218 0.0069110000 929089893 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1830 1311867779.6208660603 0.1538984179 0.1184195664 0.1636508107 0.0047976392 0.0071790000 929169677 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1831 1311867779.6566789150 0.1538207978 0.1184389008 0.1636508107 0.0047974619 0.0073330000 929249517 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1832 1311867779.6888780594 0.1538730711 0.1184582426 0.1636508107 0.0047962872 0.0071030000 929329189 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1833 1311867779.7207460403 0.1537228972 0.1184774814 0.1636508107 0.0047965080 0.0071400000 929408973 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1834 1311867779.7566559315 0.1535901725 0.1184966268 0.1636508107 0.0048002190 0.0069060000 929488757 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1835 1311867779.7889020443 0.1535520256 0.1185157305 0.1636508107 0.0048011903 0.0068960000 929568485 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1836 1311867779.8206830025 0.1533664465 0.1185347124 0.1636508107 0.0048040104 0.0083190000 929648269 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1837 1311867779.8566269875 0.1532003731 0.1185535832 0.1636508107 0.0048062284 0.0071930000 929728053 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1838 1311867779.8887419701 0.1532024294 0.1185724346 0.1636508107 0.0048065712 0.0074740000 929807781 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1839 1311867779.9207589626 0.1530969888 0.1185912082 0.1636508107 0.0048084437 0.0073130000 929887565 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1840 1311867779.9566729069 0.1529152691 0.1186098625 0.1636508107 0.0048125115 0.0076490000 929967405 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1841 1311867779.9887890816 0.1527516246 0.1186284078 0.1636508107 0.0048147415 0.0070630000 930047077 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1842 1311867780.0206449032 0.1525935829 0.1186468470 0.1636508107 0.0048152314 0.0067660000 930126861 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1843 1311867780.0566689968 0.1526384503 0.1186652907 0.1636508107 0.0048146309 0.0079050000 930206701 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1844 1311867780.0889060497 0.1524766088 0.1186836265 0.1636508107 0.0048151865 0.0073430000 930286429 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1845 1311867780.1207270622 0.1522426307 0.1187018157 0.1636508107 0.0048151857 0.0079320000 930366157 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1846 1311867780.1567380428 0.1519371122 0.1187198196 0.1636508107 0.0048155787 0.0074770000 930445997 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1847 1311867780.1888298988 0.1517201960 0.1187376867 0.1636508107 0.0048144132 0.0076590000 930525725 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1848 1311867780.2208869457 0.1515454203 0.1187554398 0.1636508107 0.0048143047 0.0076580000 930605509 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1849 1311867780.2567040920 0.1512030512 0.1187729885 0.1636508107 0.0048140758 0.0068050000 930685293 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1850 1311867780.2891309261 0.1509156823 0.1187903629 0.1636508107 0.0048142579 0.0071180000 930765077 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1851 1311867780.3207230568 0.1506006718 0.1188075484 0.1636508107 0.0048150350 0.0070490000 930844805 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1852 1311867780.3567159176 0.1500107795 0.1188243968 0.1636508107 0.0048179187 0.0079040000 930924589 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1853 1311867780.3887569904 0.1495382786 0.1188409720 0.1636508107 0.0048183964 0.0083130000 931004373 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1854 1311867780.4208409786 0.1494314224 0.1188574717 0.1636508107 0.0048186432 0.0078510000 931084101 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1855 1311867780.4567840099 0.1491249800 0.1188737884 0.1636508107 0.0048245560 0.0077480000 931163885 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1856 1311867780.4890038967 0.1492472142 0.1188901534 0.1636508107 0.0048232709 0.0074880000 931243669 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1857 1311867780.5210270882 0.1491766572 0.1189064628 0.1636508107 0.0048244349 0.0076740000 931323453 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1858 1311867780.5566449165 0.1487461478 0.1189225229 0.1636508107 0.0048445070 0.0078360000 931403237 0 402718720 -0.0929348916 -0.1362512559 -0.0092597296 1859 1311867780.5886850357 0.1490577161 0.1189387333 0.1636508107 0.0049583058 0.0078070000 931483237 0 402718720 -0.0937378854 -0.1360897422 -0.0037837997 1860 1311867780.6208159924 0.1496388912 0.1189552388 0.1636508107 0.0049612423 0.0076490000 931564557 0 402718720 -0.0942796618 -0.1361846477 -0.0027367140 1861 1311867780.6567809582 0.1493431330 0.1189715676 0.1636508107 0.0049601890 0.0079670000 934915061 0 402718720 -0.0940698981 -0.1363329589 -0.0033272679 1862 1311867780.6887900829 0.1495385915 0.1189879838 0.1636508107 0.0049590595 0.0082370000 938265341 0 402718720 -0.0942602754 -0.1364360601 -0.0037450718 1863 1311867780.7208409309 0.1492183059 0.1190042105 0.1636508107 0.0049577305 0.0081500000 941615733 0 402718720 -0.0940680057 -0.1364371926 -0.0039329929 1864 1311867780.7567479610 0.1486930102 0.1190201380 0.1636508107 0.0049564521 0.0082630000 944966181 0 402718720 -0.0939677283 -0.1362181157 -0.0041718534 1865 1311867780.7888689041 0.1486984044 0.1190360513 0.1636508107 0.0049553177 0.0087300000 948316461 0 402718720 -0.0938332677 -0.1365952492 -0.0041523161 1866 1311867780.8206589222 0.1477904171 0.1190514609 0.1636508107 0.0049540449 0.0084040000 951666853 0 402718720 -0.0932594910 -0.1363363862 -0.0046300543 1867 1311867780.8571159840 0.1474191248 0.1190666551 0.1636508107 0.0049547690 0.0082380000 955017301 0 402718720 -0.0938173681 -0.1364032477 -0.0038949579 1868 1311867780.8887701035 0.1471854746 0.1190817080 0.1636508107 0.0049536912 0.0083500000 958367581 0 402718720 -0.0937871486 -0.1363672614 -0.0044784369 1869 1311867780.9208741188 0.1469907761 0.1190966407 0.1636508107 0.0049524400 0.0083970000 961717973 0 402718720 -0.0936965346 -0.1363513172 -0.0046843407 1870 1311867780.9568250179 0.1465341598 0.1191113131 0.1636508107 0.0049515049 0.0083230000 965068421 0 402718720 -0.0937508494 -0.1361880749 -0.0051100166 1871 1311867780.9889171124 0.1463848650 0.1191258901 0.1636508107 0.0049501848 0.0083510000 968418701 0 402718720 -0.0934871808 -0.1364050061 -0.0053018094 1872 1311867781.0207529068 0.1462188810 0.1191403629 0.1636508107 0.0049489633 0.0083770000 971769093 0 402718720 -0.0935810506 -0.1363348663 -0.0050715460 1873 1311867781.0569570065 0.1455400139 0.1191544577 0.1636508107 0.0049477256 0.0079960000 975119541 0 402718720 -0.0931957141 -0.1362419277 -0.0054235361 1874 1311867781.0887539387 0.1452925205 0.1191684055 0.1636508107 0.0049470991 0.0080930000 978469821 0 402718720 -0.0929530039 -0.1364331096 -0.0052707274 1875 1311867781.1210160255 0.1450189203 0.1191821924 0.1636508107 0.0049460319 0.0082520000 981820213 0 402718720 -0.0934790671 -0.1360984296 -0.0057135839 1876 1311867781.1568250656 0.1441135705 0.1191954821 0.1636508107 0.0049453217 0.0081300000 985170661 0 402718720 -0.0930814445 -0.1359022111 -0.0058607785 1877 1311867781.1895370483 0.1433585137 0.1192083553 0.1636508107 0.0049440686 0.0081030000 988520941 0 402718720 -0.0928294286 -0.1357699335 -0.0062634544 1878 1311867781.2208230495 0.1438362300 0.1192214692 0.1636508107 0.0049431420 0.0081420000 991871277 0 402718720 -0.0930530056 -0.1361839175 -0.0059418473 1879 1311867781.2568950653 0.1435706615 0.1192344278 0.1636508107 0.0049418920 0.0082900000 995221725 0 402718720 -0.0927064493 -0.1362042278 -0.0069810152 1880 1311867781.2888579369 0.1433700770 0.1192472659 0.1636508107 0.0049413382 0.0082190000 998572005 0 402718720 -0.0925980210 -0.1360186785 -0.0074195205 1881 1311867781.3207280636 0.1438103318 0.1192603244 0.1636508107 0.0049402223 0.0080840000 1001922909 0 402718720 -0.0925197452 -0.1365695447 -0.0073383446 1882 1311867781.3567550182 0.1433477998 0.1192731233 0.1636508107 0.0049416289 0.0081800000 1005273301 0 402718720 -0.0923506245 -0.1363932192 -0.0079818657 1883 1311867781.3888380527 0.1435764581 0.1192860300 0.1636508107 0.0049450919 0.0081930000 1008623637 0 402718720 -0.0924192369 -0.1366714239 -0.0082851062 1884 1311867781.4209051132 0.1429844648 0.1192986087 0.1636508107 0.0049438975 0.0084460000 1011974029 0 402718720 -0.0921984464 -0.1362351179 -0.0089473091 1885 1311867781.4569499493 0.1420183778 0.1193106617 0.1636508107 0.0049429319 0.0165470000 1015324421 0 402718720 -0.0919096693 -0.1358423382 -0.0090794284 1886 1311867781.4889099598 0.1421102732 0.1193227505 0.1636508107 0.0049419167 0.0099510000 1018674757 0 402718720 -0.0921885073 -0.1360920072 -0.0090395482 1887 1311867781.5207688808 0.1420083195 0.1193347726 0.1636508107 0.0049410119 0.0086510000 1022025149 0 402718720 -0.0918802768 -0.1365147680 -0.0097078178 1888 1311867781.5567240715 0.1409386098 0.1193462153 0.1636508107 0.0049399773 0.0080380000 1025375597 0 402718720 -0.0920335799 -0.1354484856 -0.0102430508 1889 1311867781.5888860226 0.1410038024 0.1193576804 0.1636508107 0.0049403807 0.0085220000 1028725877 0 402718720 -0.0909444988 -0.1369373500 -0.0113376854 1890 1311867781.6210539341 0.1407176256 0.1193689820 0.1636508107 0.0049391972 0.0084380000 1032076269 0 402718720 -0.0916544646 -0.1364995688 -0.0115222661 1891 1311867781.6568241119 0.1401402652 0.1193799662 0.1636508107 0.0049379747 0.0084160000 1035426717 0 402718720 -0.0914421827 -0.1364773363 -0.0116884494 1892 1311867781.6893630028 0.1402064413 0.1193909739 0.1636508107 0.0049373014 0.0082460000 1038777053 0 402718720 -0.0915175974 -0.1366980225 -0.0117565021 1893 1311867781.7209930420 0.1397843212 0.1194017469 0.1636508107 0.0049361003 0.0081960000 1042127389 0 402718720 -0.0913855880 -0.1367965341 -0.0122661730 1894 1311867781.7566950321 0.1405549049 0.1194129154 0.1636508107 0.0049351580 0.0086240000 1045477837 0 402718720 -0.0920568034 -0.1375663280 -0.0125150904 1895 1311867781.7888600826 0.1395965219 0.1194235664 0.1636508107 0.0049363816 0.0089750000 1048828117 0 402718720 -0.0915461853 -0.1377913207 -0.0126716709 1896 1311867781.8207869530 0.1388286650 0.1194338012 0.1636508107 0.0049358038 0.0086530000 1052178509 0 402718720 -0.0911230147 -0.1375827938 -0.0129510742 1897 1311867781.8568410873 0.1383335739 0.1194437641 0.1636508107 0.0049346554 0.0081530000 1055528957 0 402718720 -0.0912242606 -0.1374233514 -0.0133716641 1898 1311867781.8891510963 0.1379114091 0.1194534942 0.1636508107 0.0049335150 0.0087490000 1058879293 0 402718720 -0.0910755098 -0.1376363486 -0.0141473813 1899 1311867781.9208040237 0.1363444328 0.1194623888 0.1636508107 0.0049347062 0.0081570000 1062229629 0 402718720 -0.0913210064 -0.1364513636 -0.0145853879 1900 1311867781.9567589760 0.1371185929 0.1194716816 0.1636508107 0.0049334676 0.0090460000 1065580021 0 402718720 -0.0916135535 -0.1376838982 -0.0146160973 1901 1311867781.9888761044 0.1362884045 0.1194805278 0.1636508107 0.0049338821 0.0082020000 1068930301 0 402718720 -0.0914394706 -0.1374509782 -0.0153213786 1902 1311867782.0211238861 0.1365007311 0.1194894764 0.1636508107 0.0049327997 0.0080750000 1072280637 0 402718720 -0.0916735977 -0.1381930858 -0.0160483960 1903 1311867782.0568029881 0.1367633939 0.1194985536 0.1636508107 0.0049317753 0.0080860000 1075631085 0 402718720 -0.0915543437 -0.1389227808 -0.0167909730 1904 1311867782.0891990662 0.1358197778 0.1195071257 0.1636508107 0.0049312601 0.0086810000 1078981421 0 402718720 -0.0907952562 -0.1383445263 -0.0168345477 1905 1311867782.1212639809 0.1367314309 0.1195161673 0.1636508107 0.0049299839 0.0083470000 1082331813 0 402718720 -0.0915689841 -0.1392031312 -0.0175442789 1906 1311867782.1567890644 0.1358363479 0.1195247299 0.1636508107 0.0049291637 0.0089360000 1085682149 0 402718720 -0.0916407630 -0.1381622255 -0.0166219957 1907 1311867782.1890211105 0.1358796656 0.1195333061 0.1636508107 0.0049279973 0.0092540000 1089032541 0 402718720 -0.0914997235 -0.1382866055 -0.0165232904 1908 1311867782.2216010094 0.1356809437 0.1195417692 0.1636508107 0.0049275757 0.0080480000 1092382933 0 402718720 -0.0913588405 -0.1382315159 -0.0169939604 1909 1311867782.2568280697 0.1359910816 0.1195503860 0.1636508107 0.0049274747 0.0097500000 1095733269 0 402718720 -0.0916729197 -0.1386695504 -0.0172290858 1910 1311867782.2892999649 0.1359777302 0.1195589867 0.1636508107 0.0049262074 0.0193700000 1099083605 0 402718720 -0.0915607661 -0.1387043893 -0.0172143169 1911 1311867782.3211629391 0.1361703873 0.1195676792 0.1636508107 0.0049249422 0.0104570000 1102433941 0 402718720 -0.0915805921 -0.1388971657 -0.0174199268 1912 1311867782.3569149971 0.1355583817 0.1195760425 0.1636508107 0.0049241791 0.0086710000 1105784445 0 402718720 -0.0913294181 -0.1386241615 -0.0185195729 1913 1311867782.3891689777 0.1359679252 0.1195846112 0.1636508107 0.0049234780 0.0090170000 1109135237 0 402718720 -0.0913785547 -0.1389166117 -0.0177281518 1914 1311867782.4208400249 0.1364268512 0.1195934107 0.1636508107 0.0049222212 0.0103350000 1112485461 0 402718720 -0.0916551352 -0.1392262131 -0.0177401844 1915 1311867782.4571740627 0.1365829259 0.1196022825 0.1636508107 0.0049209404 0.0087500000 1115835965 0 402718720 -0.0916600078 -0.1394975334 -0.0182744246 1916 1311867782.4892749786 0.1363690943 0.1196110335 0.1636508107 0.0049197021 0.0084110000 1119186245 0 402718720 -0.0915137380 -0.1393212527 -0.0186843500 1917 1311867782.5210659504 0.1369407773 0.1196200735 0.1636508107 0.0049185034 0.0083950000 1122552621 0 402718720 -0.0915720612 -0.1397791654 -0.0194532089 1918 1311867782.5570800304 0.1361124218 0.1196286722 0.1636508107 0.0049173084 0.0083350000 1125903069 0 402718720 -0.0912187472 -0.1389472038 -0.0195321944 1919 1311867782.5892798901 0.1361666918 0.1196372902 0.1636508107 0.0049162425 0.0081470000 1129253349 0 402718720 -0.0912105888 -0.1388270706 -0.0195508897 1920 1311867782.6212170124 0.1358162612 0.1196457168 0.1636508107 0.0049150253 0.0085210000 1132603741 0 402718720 -0.0909505859 -0.1383904517 -0.0189888254 1921 1311867782.6568250656 0.1363021433 0.1196543875 0.1636508107 0.0049137504 0.0097670000 1135954189 0 402718720 -0.0911535174 -0.1387763470 -0.0184145607 1922 1311867782.6890439987 0.1373879910 0.1196636141 0.1636508107 0.0049147630 0.0085620000 1139304469 0 402718720 -0.0911756530 -0.1392586380 -0.0195576176 1923 1311867782.7211389542 0.1372308284 0.1196727495 0.1636508107 0.0049137216 0.0083910000 1142654861 0 402718720 -0.0910888538 -0.1392835826 -0.0198120661 1924 1311867782.7569899559 0.1357179880 0.1196810890 0.1636508107 0.0049148550 0.0087540000 1146005197 0 402718720 -0.0903503895 -0.1389982104 -0.0211755540 1925 1311867782.7890570164 0.1342862546 0.1196886761 0.1636508107 0.0049156285 0.0088830000 1149355589 0 402718720 -0.0896493345 -0.1371700913 -0.0217071176 1926 1311867782.8208789825 0.1363327801 0.1196973179 0.1636508107 0.0049153260 0.0097440000 1152705925 0 402718720 -0.0907594487 -0.1385084242 -0.0199704077 1927 1311867782.8570148945 0.1361700147 0.1197058662 0.1636508107 0.0049155088 0.0083850000 1156056429 0 402718720 -0.0902097970 -0.1394087672 -0.0228831861 1928 1311867782.8888878822 0.1364853382 0.1197145693 0.1636508107 0.0049154484 0.0102610000 1159406653 0 402718720 -0.0910921395 -0.1392719597 -0.0213585421 1929 1311867782.9209339619 0.1366037726 0.1197233247 0.1636508107 0.0049144818 0.0101850000 1162757045 0 402718720 -0.0910591409 -0.1394081265 -0.0214810111 1930 1311867782.9571130276 0.1359873116 0.1197317516 0.1636508107 0.0049135466 0.0085200000 1166107493 0 402718720 -0.0906892866 -0.1394578815 -0.0226639863 1931 1311867782.9888780117 0.1354926229 0.1197399137 0.1636508107 0.0049126227 0.0099910000 1169457829 0 402718720 -0.0905986130 -0.1392119378 -0.0226137023 1932 1311867783.0209629536 0.1360045373 0.1197483322 0.1636508107 0.0049114298 0.0106440000 1172808165 0 402718720 -0.0909862891 -0.1396276653 -0.0231602993 1933 1311867783.0574910641 0.1352784932 0.1197563664 0.1636508107 0.0049105134 0.0086370000 1176158557 0 402718720 -0.0905753896 -0.1393703669 -0.0235544723 1934 1311867783.0892550945 0.1353050023 0.1197644061 0.1636508107 0.0049094708 0.0086840000 1179508949 0 402718720 -0.0907006487 -0.1398453712 -0.0241300799 1935 1311867783.1210470200 0.1351489872 0.1197723567 0.1636508107 0.0049082521 0.0085630000 1182859285 0 402718720 -0.0907205418 -0.1397503167 -0.0246397667 1936 1311867783.1570010185 0.1347052902 0.1197800700 0.1636508107 0.0049070156 0.0089870000 1186209677 0 402718720 -0.0904304385 -0.1396206319 -0.0247034859 1937 1311867783.1893379688 0.1345822513 0.1197877118 0.1636508107 0.0049061559 0.0090980000 1189560069 0 402718720 -0.0902388915 -0.1400669515 -0.0275838859 1938 1311867783.2211608887 0.1346026212 0.1197953563 0.1636508107 0.0049052764 0.0085610000 1192910461 0 402718720 -0.0905315652 -0.1398447603 -0.0257923678 1939 1311867783.2568700314 0.1350601614 0.1198032288 0.1636508107 0.0049049218 0.0086460000 1196260853 0 402718720 -0.0907712728 -0.1400670558 -0.0251206737 1940 1311867783.2891080379 0.1345693022 0.1198108402 0.1636508107 0.0049037895 0.0085530000 1199611189 0 402718720 -0.0906947851 -0.1397669464 -0.0253596455 1941 1311867783.3210859299 0.1345694065 0.1198184438 0.1636508107 0.0049026461 0.0095410000 1202961525 0 402718720 -0.0907575414 -0.1397236586 -0.0246717483 1942 1311867783.3569769859 0.1348328143 0.1198261752 0.1636508107 0.0049014376 0.0086260000 1206311973 0 402718720 -0.0907104239 -0.1400781572 -0.0249506738 1943 1311867783.3890259266 0.1343352795 0.1198336425 0.1636508107 0.0049002643 0.0083680000 1209662253 0 402718720 -0.0904611945 -0.1399111301 -0.0258704070 1944 1311867783.4249539375 0.1346601546 0.1198412693 0.1636508107 0.0048990274 0.0087870000 1213012701 0 402718720 -0.0908134952 -0.1402503103 -0.0260470770 1945 1311867783.4569830894 0.1346753091 0.1198488961 0.1636508107 0.0048978738 0.0084690000 1216363549 0 402718720 -0.0906396061 -0.1406776160 -0.0262732487 1946 1311867783.4889791012 0.1332313418 0.1198557730 0.1636508107 0.0048968369 0.0098930000 1219713885 0 402718720 -0.0903066099 -0.1396258920 -0.0263464581 1947 1311867783.5228540897 0.1332979053 0.1198626770 0.1636508107 0.0048959570 0.0084060000 1223064277 0 402718720 -0.0903858244 -0.1398234218 -0.0269462224 1948 1311867783.5571069717 0.1334919184 0.1198696735 0.1636508107 0.0048950429 0.0084030000 1226414613 0 402718720 -0.0906012654 -0.1400783658 -0.0268929135 1949 1311867783.5898580551 0.1332086623 0.1198765176 0.1636508107 0.0048939347 0.0091590000 1229765005 0 402718720 -0.0903652683 -0.1400995851 -0.0270525608 1950 1311867783.6210260391 0.1330400407 0.1198832681 0.1636508107 0.0048927606 0.0095240000 1233115341 0 402718720 -0.0903949291 -0.1399634033 -0.0271138698 1951 1311867783.6572589874 0.1335594505 0.1198902779 0.1636508107 0.0048916176 0.0088310000 1236465789 0 402718720 -0.0905822217 -0.1405748725 -0.0278626941 1952 1311867783.6893589497 0.1334543079 0.1198972267 0.1636508107 0.0048904393 0.0090000000 1239816125 0 402718720 -0.0904449597 -0.1405029297 -0.0275275726 1953 1311867783.7211050987 0.1334722936 0.1199041776 0.1636508107 0.0048896109 0.0100150000 1243166461 0 402718720 -0.0905981138 -0.1404259801 -0.0269369315 1954 1311867783.7570610046 0.1347959042 0.1199117987 0.1636508107 0.0048887072 0.0091650000 1246516853 0 402718720 -0.0909702405 -0.1415131539 -0.0265258569 1955 1311867783.7890551090 0.1346108913 0.1199193174 0.1636508107 0.0048877116 0.0090790000 1249867133 0 402718720 -0.0907586217 -0.1413912624 -0.0270454641 1956 1311867783.8209390640 0.1339121014 0.1199264712 0.1636508107 0.0048865183 0.0082300000 1253217469 0 402718720 -0.0905035511 -0.1404817104 -0.0269851107 1957 1311867783.8570868969 0.1345666647 0.1199339522 0.1636508107 0.0048906254 0.0087480000 1256567917 0 402718720 -0.0906396732 -0.1410951614 -0.0281709805 1958 1311867783.8889739513 0.1345548481 0.1199414194 0.1636508107 0.0048966540 0.0088360000 1259918253 0 402718720 -0.0906103998 -0.1406733245 -0.0274093430 1959 1311867783.9210090637 0.1343523413 0.1199487757 0.1636508107 0.0048956645 0.0085480000 1263268589 0 402718720 -0.0906940997 -0.1403322220 -0.0265852995 1960 1311867783.9572629929 0.1345341057 0.1199562172 0.1636508107 0.0048944621 0.0083070000 1266617717 0 402718720 -0.0906111598 -0.1405432522 -0.0263405964 1961 1311867783.9889400005 0.1345965117 0.1199636829 0.1636508107 0.0048967281 0.0085320000 1266697717 0 402718720 -0.0908012316 -0.1407332122 -0.0262733083 1962 1311867784.0210440159 0.1340977401 0.1199708868 0.1636508107 0.0048982139 0.0087340000 1266777773 0 402718720 -0.0907150954 -0.1402574480 -0.0257907454 1963 1311867784.0570049286 0.1344275326 0.1199782514 0.1636508107 0.0048972775 0.0078360000 1266857885 0 402718720 -0.0908862650 -0.1407563984 -0.0263693165 1964 1311867784.0891489983 0.1348787546 0.1199858382 0.1636508107 0.0048963279 0.0085900000 1266937829 0 402718720 -0.0911348015 -0.1413405389 -0.0264060926 1965 1311867784.1209108829 0.1334941983 0.1199927127 0.1636508107 0.0048951609 0.0085650000 1267017829 0 402718720 -0.0907806531 -0.1406434029 -0.0266541559 1966 1311867784.1571660042 0.1329729706 0.1199993150 0.1636508107 0.0048940069 0.0076950000 1267097941 0 402718720 -0.0904658809 -0.1406285912 -0.0259674154 1967 1311867784.1889019012 0.1330889016 0.1200059696 0.1636508107 0.0048932340 0.0078390000 1267177941 0 402718720 -0.0908628553 -0.1408927888 -0.0261064358 1968 1311867784.2212319374 0.1323894262 0.1200122620 0.1636508107 0.0048925362 0.0188560000 1267257941 0 402718720 -0.0908997282 -0.1404721886 -0.0252632257 1969 1311867784.2569179535 0.1324331462 0.1200185703 0.1636508107 0.0048916907 0.0099620000 1267338053 0 402718720 -0.0908062980 -0.1409358084 -0.0254516508 1970 1311867784.2890079021 0.1332824826 0.1200253032 0.1636508107 0.0048909621 0.0085030000 1267418053 0 402718720 -0.0917571932 -0.1416867077 -0.0262324959 1971 1311867784.3210299015 0.1326304525 0.1200316985 0.1636508107 0.0048898537 0.0081860000 1267498109 0 402718720 -0.0915730074 -0.1412704140 -0.0249123573 1972 1311867784.3568980694 0.1325108260 0.1200380267 0.1636508107 0.0048887437 0.0076790000 1267578221 0 402718720 -0.0917191729 -0.1412297636 -0.0249787774 1973 1311867784.3890140057 0.1327121854 0.1200444505 0.1636508107 0.0048875658 0.0079760000 1267658165 0 402718720 -0.0916611031 -0.1417267621 -0.0251270756 1974 1311867784.4210159779 0.1321545541 0.1200505853 0.1636508107 0.0048864165 0.0085450000 1267738165 0 402718720 -0.0918291211 -0.1411984563 -0.0243296232 1975 1311867784.4572210312 0.1317738593 0.1200565211 0.1636508107 0.0048853245 0.0163590000 1267818277 0 402718720 -0.0913881510 -0.1409480572 -0.0245443173 1976 1311867784.4890739918 0.1322991252 0.1200627168 0.1636508107 0.0048842830 0.0101940000 1267898277 0 402718720 -0.0917988718 -0.1417170912 -0.0247295070 1977 1311867784.5209710598 0.1310942024 0.1200682967 0.1636508107 0.0048832066 0.0079010000 1267978277 0 402718720 -0.0913541764 -0.1409605592 -0.0247093085 1978 1311867784.5571429729 0.1312013119 0.1200739251 0.1636508107 0.0048821721 0.0076410000 1268058333 0 402718720 -0.0915626362 -0.1411088705 -0.0243161451 1979 1311867784.5900990963 0.1314232349 0.1200796600 0.1636508107 0.0048810373 0.0083080000 1268138389 0 402718720 -0.0918064564 -0.1415217370 -0.0239962786 1980 1311867784.6210629940 0.1310700327 0.1200852107 0.1636508107 0.0048798968 0.0082350000 1268218389 0 402718720 -0.0919299796 -0.1414769292 -0.0239167903 1981 1311867784.6585550308 0.1306000054 0.1200905185 0.1636508107 0.0048787022 0.0084370000 1268298501 0 402718720 -0.0917500108 -0.1414218098 -0.0243086182 1982 1311867784.6890010834 0.1311787665 0.1200961130 0.1636508107 0.0048777099 0.0084500000 1268378501 0 402718720 -0.0920965597 -0.1420872062 -0.0243423823 1983 1311867784.7210860252 0.1309251338 0.1201015739 0.1636508107 0.0048766551 0.0080010000 1268458501 0 402718720 -0.0920901150 -0.1421162635 -0.0241936482 1984 1311867784.7656979561 0.1298051178 0.1201064648 0.1636508107 0.0048777599 0.0153740000 1268538837 0 402718720 -0.0918923095 -0.1415512413 -0.0239174571 1985 1311867784.7897160053 0.1303748786 0.1201116378 0.1636508107 0.0048767940 0.0098390000 1268618613 0 402718720 -0.0923278481 -0.1422251761 -0.0239965152 1986 1311867784.8210480213 0.1289196312 0.1201160728 0.1636508107 0.0048760080 0.0087940000 1268698445 0 402718720 -0.0917159468 -0.1413617730 -0.0242794398 1987 1311867784.8570930958 0.1294331700 0.1201207619 0.1636508107 0.0048749915 0.0092920000 1268778613 0 402718720 -0.0921872109 -0.1418415606 -0.0231016502 1988 1311867784.8888559341 0.1298346221 0.1201256481 0.1636508107 0.0048740648 0.0077490000 1268858557 0 402718720 -0.0925250575 -0.1423871815 -0.0237778518 1989 1311867784.9211781025 0.1288978159 0.1201300585 0.1636508107 0.0048729699 0.0097690000 1268938557 0 402718720 -0.0921403393 -0.1419853568 -0.0238351673 1990 1311867784.9570379257 0.1285981983 0.1201343138 0.1636508107 0.0048718139 0.0096040000 1269018725 0 402718720 -0.0922086984 -0.1417986453 -0.0239590611 1991 1311867784.9890439510 0.1293265820 0.1201389307 0.1636508107 0.0048707086 0.0082920000 1269098613 0 402718720 -0.0927191824 -0.1425647289 -0.0238826796 1992 1311867785.0210449696 0.1293734312 0.1201435665 0.1636508107 0.0048697430 0.0102210000 1269178669 0 402718720 -0.0928172097 -0.1427756697 -0.0236168634 1993 1311867785.0570709705 0.1284109801 0.1201477147 0.1636508107 0.0048685896 0.0081150000 1269258837 0 402718720 -0.0925415680 -0.1422728449 -0.0240554065 1994 1311867785.0890560150 0.1288268715 0.1201520674 0.1636508107 0.0048675187 0.0083890000 1269338725 0 402718720 -0.0927005932 -0.1427903920 -0.0250840466 1995 1311867785.1211049557 0.1279400289 0.1201559711 0.1636508107 0.0048665811 0.0082740000 1269418781 0 402718720 -0.0923769549 -0.1421067417 -0.0246612430 1996 1311867785.1570410728 0.1286011487 0.1201602022 0.1636508107 0.0048653866 0.0087340000 1269498893 0 402718720 -0.0927255526 -0.1426928043 -0.0248368569 1997 1311867785.1892418861 0.1294087321 0.1201648334 0.1636508107 0.0048643542 0.0083920000 1269578893 0 402718720 -0.0930632651 -0.1434511691 -0.0249452870 1998 1311867785.2213380337 0.1283980161 0.1201689541 0.1636508107 0.0048633508 0.0083660000 1269658893 0 402718720 -0.0926503614 -0.1427077651 -0.0250075534 1999 1311867785.2570750713 0.1279551983 0.1201728492 0.1636508107 0.0048621696 0.0086130000 1269738949 0 402718720 -0.0925660804 -0.1422877461 -0.0242178515 2000 1311867785.2900719643 0.1290155053 0.1201772705 0.1636508107 0.0048613382 0.0086950000 1269819005 0 402718720 -0.0929907411 -0.1432866454 -0.0244675819 2001 1311867785.3214108944 0.1286216974 0.1201814906 0.1636508107 0.0048602605 0.0077240000 1269898949 0 402718720 -0.0930413231 -0.1430939287 -0.0247522350 2002 1311867785.3573219776 0.1280299574 0.1201854109 0.1636508107 0.0048592806 0.0089600000 1269979061 0 402718720 -0.0928320512 -0.1426392496 -0.0243012775 2003 1311867785.3893299103 0.1283947080 0.1201895094 0.1636508107 0.0048582057 0.0084040000 1270059061 0 402718720 -0.0930201262 -0.1430560797 -0.0249412004 2004 1311867785.4211249352 0.1279301047 0.1201933720 0.1636508107 0.0048572071 0.0162800000 1270139061 0 402718720 -0.0929037705 -0.1428319067 -0.0252769403 2005 1311867785.4570529461 0.1279728562 0.1201972520 0.1636508107 0.0048577261 0.0112800000 1270219173 0 402718720 -0.0932392925 -0.1426203698 -0.0247016419 2006 1311867785.4900350571 0.1285974681 0.1202014396 0.1636508107 0.0048573304 0.0085300000 1270299229 0 402718720 -0.0933711305 -0.1431100368 -0.0255620666 2007 1311867785.5211930275 0.1276972890 0.1202051744 0.1636508107 0.0048565843 0.0083340000 1270379173 0 402718720 -0.0929538533 -0.1426090449 -0.0266466234 2008 1311867785.5571260452 0.1264932007 0.1202083059 0.1636508107 0.0048565563 0.0076130000 1270459285 0 402718720 -0.0929014459 -0.1419367045 -0.0253897253 2009 1311867785.5891211033 0.1273438185 0.1202118577 0.1636508107 0.0048558407 0.0083770000 1270539285 0 402718720 -0.0933123380 -0.1426626444 -0.0255933553 2010 1311867785.6211590767 0.1281195879 0.1202157919 0.1636508107 0.0048682612 0.0081850000 1270619341 0 402718720 -0.0940210000 -0.1435182393 -0.0261866618 2011 1311867785.6570439339 0.1265108287 0.1202189222 0.1636508107 0.0048731293 0.0150900000 1270699453 0 402718720 -0.0932484567 -0.1422720104 -0.0251458138 2012 1311867785.6892280579 0.1266246289 0.1202221059 0.1636508107 0.0048719527 0.0127740000 1270779397 0 402718720 -0.0933536962 -0.1424637437 -0.0254100673 2013 1311867785.7214241028 0.1275623441 0.1202257523 0.1636508107 0.0048731895 0.0081910000 1270859397 0 402718720 -0.0939969048 -0.1435318291 -0.0260263756 2014 1311867785.7573668957 0.1261662245 0.1202287019 0.1636508107 0.0048724492 0.0087270000 1270939509 0 402718720 -0.0935474783 -0.1427244544 -0.0257305894 2015 1311867785.7892301083 0.1260244995 0.1202315782 0.1636508107 0.0048718752 0.0101850000 1271019509 0 402718720 -0.0936277211 -0.1428713351 -0.0258496907 2016 1311867785.8210389614 0.1260659844 0.1202344723 0.1636508107 0.0048706802 0.0083240000 1271099509 0 402718720 -0.0936880112 -0.1430255771 -0.0259696040 2017 1311867785.8574340343 0.1257309616 0.1202371974 0.1636508107 0.0048705101 0.0081450000 1271179621 0 402718720 -0.0941271409 -0.1427914798 -0.0259071309 2018 1311867785.8893110752 0.1254815012 0.1202397961 0.1636508107 0.0048696873 0.0079500000 1271259677 0 402718720 -0.0943350494 -0.1425984651 -0.0257956032 2019 1311867785.9211509228 0.1266428977 0.1202429676 0.1636508107 0.0048716512 0.0081260000 1271339677 0 402718720 -0.0941694155 -0.1445446461 -0.0272738859 2020 1311867785.9588449001 0.1264789104 0.1202460547 0.1636508107 0.0048729846 0.0086320000 1271419789 0 402718720 -0.0941598639 -0.1445925683 -0.0273075290 2021 1311867785.9892621040 0.1249546111 0.1202483845 0.1636508107 0.0048724470 0.0084730000 1271499789 0 402718720 -0.0937254056 -0.1433806419 -0.0266683102 2022 1311867786.0210618973 0.1261748075 0.1202513155 0.1636508107 0.0048727396 0.0082210000 1271579789 0 402718720 -0.0944156647 -0.1446537226 -0.0273337625 2023 1311867786.0572268963 0.1262940168 0.1202543025 0.1636508107 0.0048723097 0.0081930000 1271659845 0 402718720 -0.0946430936 -0.1453249007 -0.0278084185 2024 1311867786.0892500877 0.1242881566 0.1202562955 0.1636508107 0.0048746382 0.0084780000 1271739901 0 402718720 -0.0940551683 -0.1438300610 -0.0270232018 2025 1311867786.1211619377 0.1246739477 0.1202584770 0.1636508107 0.0048741432 0.0077780000 1271819957 0 402718720 -0.0945302993 -0.1446216702 -0.0277753696 2026 1311867786.1570990086 0.1250955313 0.1202608645 0.1636508107 0.0048742034 0.0081610000 1271900013 0 402718720 -0.0949737504 -0.1456164271 -0.0285904482 2027 1311867786.1891019344 0.1233102754 0.1202623689 0.1636508107 0.0048770132 0.0083440000 1271979957 0 402718720 -0.0944756866 -0.1444203258 -0.0271415785 2028 1311867786.2216470242 0.1223507747 0.1202633987 0.1636508107 0.0048759758 0.0084660000 1272059957 0 402718720 -0.0944751054 -0.1438278556 -0.0271920897 2029 1311867786.2570950985 0.1234192476 0.1202649541 0.1636508107 0.0048756270 0.0079110000 1272140125 0 402718720 -0.0949186385 -0.1454336345 -0.0282223113 2030 1311867786.2895779610 0.1220934093 0.1202658548 0.1636508107 0.0048747300 0.0139910000 1272220069 0 402718720 -0.0947855860 -0.1444370598 -0.0276086349 2031 1311867786.3211650848 0.1210726947 0.1202662520 0.1636508107 0.0048745778 0.0113010000 1272300013 0 402718720 -0.0946221724 -0.1435985416 -0.0275933761 2032 1311867786.3572299480 0.1226187572 0.1202674098 0.1636508107 0.0048744318 0.0078770000 1272380181 0 402718720 -0.0954490900 -0.1453311443 -0.0282232761 2033 1311867786.3891439438 0.1219547987 0.1202682398 0.1636508107 0.0048736546 0.0081720000 1272460125 0 402718720 -0.0952770784 -0.1451797783 -0.0281743817 2034 1311867786.4213869572 0.1202383563 0.1202682251 0.1636508107 0.0048729120 0.0104650000 1272540181 0 402718720 -0.0949255973 -0.1439647526 -0.0277296789 2035 1311867786.4573409557 0.1216762364 0.1202689170 0.1636508107 0.0048723394 0.0083710000 1272620293 0 402718720 -0.0953561142 -0.1455096006 -0.0284718536 2036 1311867786.4891700745 0.1211171374 0.1202693336 0.1636508107 0.0048715620 0.0080120000 1272700237 0 402718720 -0.0955309272 -0.1454415172 -0.0283005759 2037 1311867786.5217890739 0.1202386394 0.1202693185 0.1636508107 0.0048711965 0.0086320000 1272780237 0 402718720 -0.0952929184 -0.1451287866 -0.0282915346 2038 1311867786.5572519302 0.1213240698 0.1202698361 0.1636508107 0.0048703870 0.0087560000 1272860405 0 402718720 -0.0962829143 -0.1463206559 -0.0284510683 2039 1311867786.5895760059 0.1199505776 0.1202696795 0.1636508107 0.0048708336 0.0082620000 1272940405 0 402718720 -0.0957700536 -0.1457306147 -0.0281078015 2040 1311867786.6211080551 0.1183507890 0.1202687389 0.1636508107 0.0048698047 0.0084020000 1273020405 0 402718720 -0.0952629521 -0.1449109167 -0.0279829465 2041 1311867786.6573529243 0.1187621579 0.1202680007 0.1636508107 0.0048694290 0.0086230000 1273100517 0 402718720 -0.0955351517 -0.1457589865 -0.0292704199 2042 1311867786.6891629696 0.1193013936 0.1202675273 0.1636508107 0.0048685565 0.0085870000 1273180461 0 402718720 -0.0959602892 -0.1465172321 -0.0285219345 2043 1311867786.7210969925 0.1183204800 0.1202665743 0.1636508107 0.0048677423 0.0197120000 1273260461 0 402718720 -0.0960272402 -0.1458335370 -0.0278012287 2044 1311867786.7570719719 0.1189241707 0.1202659175 0.1636508107 0.0048667532 0.0103840000 1273340517 0 402718720 -0.0961587653 -0.1464842409 -0.0284543503 2045 1311867786.7892940044 0.1197257638 0.1202656534 0.1636508107 0.0048659852 0.0082970000 1273420573 0 402718720 -0.0968113169 -0.1475432813 -0.0284370463 2046 1311867786.8211419582 0.1182360128 0.1202646614 0.1636508107 0.0048654409 0.0088940000 1273500573 0 402718720 -0.0964740589 -0.1461900026 -0.0272229053 2047 1311867786.8575630188 0.1181788370 0.1202636424 0.1636508107 0.0048644763 0.0100910000 1273580629 0 402718720 -0.0965413451 -0.1464266330 -0.0273402855 2048 1311867786.8893759251 0.1197556704 0.1202633944 0.1636508107 0.0048662803 0.0081660000 1273660685 0 402718720 -0.0971962512 -0.1474843025 -0.0274190940 2049 1311867786.9211881161 0.1181763336 0.1202623758 0.1636508107 0.0048673105 0.0086790000 1273740685 0 402718720 -0.0968590528 -0.1466292739 -0.0268426836 2050 1311867786.9576020241 0.1181077510 0.1202613248 0.1636508107 0.0048662636 0.0084900000 1274230453 0 402718720 -0.0967851281 -0.1465272903 -0.0271845218 2051 1311867786.9892089367 0.1195426583 0.1202609744 0.1636508107 0.0048663421 0.0081600000 1274310341 0 402718720 -0.0975787491 -0.1480300725 -0.0275939237 2052 1311867787.0211400986 0.1179290786 0.1202598380 0.1636508107 0.0048659140 0.0085520000 1274390397 0 402718720 -0.0970028937 -0.1466946900 -0.0261463784 2053 1311867787.0571250916 0.1175348163 0.1202585107 0.1636508107 0.0048647674 0.0104110000 1274470565 0 402718720 -0.0968325660 -0.1467201561 -0.0264912676 2054 1311867787.0895950794 0.1190999299 0.1202579466 0.1636508107 0.0048644722 0.0082840000 1274550509 0 402718720 -0.0980928540 -0.1480369419 -0.0271394700 2055 1311867787.1239449978 0.1171942055 0.1202564557 0.1636508107 0.0048664595 0.0104600000 1274630509 0 402718720 -0.0973178968 -0.1469631791 -0.0254216511 2056 1311867787.1573429108 0.1163476110 0.1202545545 0.1636508107 0.0048658109 0.0110390000 1274710621 0 402718720 -0.0969178453 -0.1466972828 -0.0266515873 2057 1311867787.1892991066 0.1191587001 0.1202540218 0.1636508107 0.0048671759 0.0083050000 1274790621 0 402718720 -0.0992707387 -0.1485597789 -0.0278908424 2058 1311867787.2230091095 0.1175394654 0.1202527028 0.1636508107 0.0048663560 0.0081230000 1274870621 0 402718720 -0.0978354812 -0.1483059525 -0.0274918731 2059 1311867787.2571809292 0.1160424948 0.1202506580 0.1636508107 0.0048663073 0.0153750000 1274950733 0 402718720 -0.0973518044 -0.1470701396 -0.0266334563 2060 1311867787.2893400192 0.1168869436 0.1202490251 0.1636508107 0.0048652752 0.0097010000 1275030733 0 402718720 -0.0977780446 -0.1480766237 -0.0270805787 2061 1311867787.3217329979 0.1154791191 0.1202467107 0.1636508107 0.0048656529 0.0086890000 1275110677 0 402718720 -0.0976152942 -0.1469401270 -0.0260577984 2062 1311867787.3572421074 0.1154663116 0.1202443924 0.1636508107 0.0048656228 0.0110710000 1275190845 0 402718720 -0.0974142030 -0.1471571177 -0.0271266419 2063 1311867787.3892920017 0.1169910133 0.1202428154 0.1636508107 0.0048648273 0.0087030000 1275270845 0 402718720 -0.0981900170 -0.1487898082 -0.0283009280 2064 1311867787.4245340824 0.1156423762 0.1202405865 0.1636508107 0.0048641634 0.0088050000 1275350845 0 402718720 -0.0980250463 -0.1482016891 -0.0274365768 2065 1311867787.4572229385 0.1151618585 0.1202381271 0.1636508107 0.0048630608 0.0115760000 1275430957 0 402718720 -0.0981289521 -0.1479550153 -0.0278879236 2066 1311867787.4892969131 0.1161550730 0.1202361508 0.1636508107 0.0048623879 0.0081980000 1275510901 0 402718720 -0.0985527709 -0.1490773261 -0.0289103910 2067 1311867787.5220599174 0.1151053160 0.1202336685 0.1636508107 0.0048617487 0.0086520000 1275590845 0 402718720 -0.0984067321 -0.1485734284 -0.0282968283 2068 1311867787.5581040382 0.1135760993 0.1202304492 0.1636508107 0.0048608626 0.0090830000 1275671013 0 402718720 -0.0981237590 -0.1474857330 -0.0275336485 2069 1311867787.5897688866 0.1142403558 0.1202275540 0.1636508107 0.0048609035 0.0079790000 1275751069 0 402718720 -0.0983680859 -0.1484270543 -0.0288485121 2070 1311867787.6235349178 0.1142516509 0.1202246671 0.1636508107 0.0048602272 0.0086770000 1275831013 0 402718720 -0.0985691547 -0.1490081847 -0.0290912371 2071 1311867787.6574609280 0.1135454550 0.1202214420 0.1636508107 0.0048595724 0.0097950000 1275911125 0 402718720 -0.0986732766 -0.1485907286 -0.0286989715 2072 1311867787.6898610592 0.1133732349 0.1202181369 0.1636508107 0.0048602597 0.0089410000 1275991181 0 402718720 -0.0986794084 -0.1489048451 -0.0295748338 2073 1311867787.7212240696 0.1144214198 0.1202153406 0.1636508107 0.0048596609 0.0085910000 1276071181 0 402718720 -0.0992516503 -0.1500404626 -0.0299222525 2074 1311867787.7579810619 0.1131420508 0.1202119301 0.1636508107 0.0048609324 0.0086950000 1276151293 0 402718720 -0.0988136306 -0.1489859819 -0.0295129847 2075 1311867787.7901558876 0.1126765832 0.1202082986 0.1636508107 0.0048603276 0.0087080000 1276231293 0 402718720 -0.0984875262 -0.1489885002 -0.0303688962 2076 1311867787.8218519688 0.1132604182 0.1202049519 0.1636508107 0.0048591910 0.0081070000 1276311349 0 402718720 -0.0990749747 -0.1495893747 -0.0303552877 2077 1311867787.8573749065 0.1124525815 0.1202012194 0.1636508107 0.0048634108 0.0131230000 1276391077 0 402718720 -0.0990749747 -0.1495893747 -0.0303552877 2078 1311867787.8894400597 0.1141168103 0.1201982914 0.1636508107 0.0049350068 0.0264060000 1276393205 0 402718720 -0.1001788601 -0.1498685181 -0.0218114685 2079 1311867787.9213879108 0.1131775975 0.1201949144 0.1636508107 0.0049376369 0.0193840000 1276396381 0 402718720 -0.0987083688 -0.1504860669 -0.0257213730 2080 1311867787.9577279091 0.1159698144 0.1201928831 0.1636508107 0.0049381721 0.0244880000 1276399669 0 402718720 -0.1022820771 -0.1520513892 -0.0221923478 2081 1311867787.9892189503 0.1147828773 0.1201902834 0.1636508107 0.0049375145 0.0211850000 1276402789 0 402718720 -0.1016843766 -0.1509469599 -0.0205869693 2082 1311867788.0211091042 0.1136931702 0.1201871628 0.1636508107 0.0049383575 0.0194850000 1276482845 0 402718720 -0.1006042212 -0.1511340886 -0.0246930625 2083 1311867788.0577259064 0.1195980161 0.1201868800 0.1636508107 0.0049377252 0.0246860000 1276563013 0 402718720 -0.1044504270 -0.1557983905 -0.0241902731 2084 1311867788.0892241001 0.1209216788 0.1201872325 0.1636508107 0.0049369873 0.0217260000 1276642957 0 402718720 -0.1058938727 -0.1563184857 -0.0227098987 2085 1311867788.1240630150 0.1198685914 0.1201870797 0.1636508107 0.0049364724 0.0236050000 1276722957 0 402718720 -0.1057803929 -0.1551960111 -0.0219789054 2086 1311867788.1572849751 0.1174438596 0.1201857647 0.1636508107 0.0049361742 0.0191180000 1276803125 0 402718720 -0.1047970653 -0.1529012918 -0.0194476992 2087 1311867788.1904621124 0.1154360995 0.1201834888 0.1636508107 0.0049352844 0.0509740000 1276883125 0 402718720 -0.1043829992 -0.1514100730 -0.0198405758 2088 1311867788.2247090340 0.1142631471 0.1201806534 0.1636508107 0.0049347354 0.0208760000 1276963125 0 402718720 -0.1032191515 -0.1509373784 -0.0202939715 2089 1311867788.2583589554 0.1182701737 0.1201797389 0.1636508107 0.0049375340 0.0260550000 1277043125 0 402718720 -0.1061806008 -0.1545302719 -0.0225665048 2090 1311867788.2893440723 0.1240796968 0.1201816049 0.1636508107 0.0049376305 0.0249240000 1277123181 0 402718720 -0.1104638949 -0.1590409726 -0.0216155313 2091 1311867788.3251628876 0.1219556183 0.1201824533 0.1636508107 0.0049385179 0.0222920000 1277203293 0 402718720 -0.1085387394 -0.1582585424 -0.0232130773 2092 1311867788.3571081161 0.1204530671 0.1201825826 0.1636508107 0.0049415242 0.0223890000 1277283293 0 402718720 -0.1061111838 -0.1586101651 -0.0269537922 2093 1311867788.3910639286 0.1185868159 0.1201818202 0.1636508107 0.0049403590 0.0228100000 1277363293 0 402718720 -0.1050421298 -0.1575916857 -0.0264624394 2094 1311867788.4251430035 0.1168759167 0.1201802415 0.1636508107 0.0049404073 0.0209130000 1277443405 0 402718720 -0.1040606424 -0.1565297693 -0.0262030978 2095 1311867788.4573140144 0.1153044701 0.1201779141 0.1636508107 0.0049428768 0.0196450000 1277523405 0 402718720 -0.1013286561 -0.1569794267 -0.0304888561 2096 1311867788.4924240112 0.1160269156 0.1201759337 0.1636508107 0.0049430622 0.0238830000 1277603405 0 402718720 -0.1025685519 -0.1575144380 -0.0289010219 2097 1311867788.5262899399 0.1152630672 0.1201735909 0.1636508107 0.0049448240 0.0221940000 1277683517 0 402718720 -0.1053495631 -0.1552436650 -0.0258981735 2098 1311867788.5573079586 0.1168522760 0.1201720078 0.1636508107 0.0049440723 0.0222930000 1277763517 0 402718720 -0.1068757847 -0.1564726979 -0.0267665926 2099 1311867788.5915310383 0.1148313954 0.1201694634 0.1636508107 0.0049433094 0.0225860000 1277843517 0 402718720 -0.1050032228 -0.1556174904 -0.0274156723 2100 1311867788.6251940727 0.1163457930 0.1201676426 0.1636508107 0.0049525199 0.0240830000 1277923573 0 402718720 -0.1097645611 -0.1545844078 -0.0224764533 2101 1311867788.6593029499 0.1151448190 0.1201652519 0.1636508107 0.0049519659 0.0218690000 1278003629 0 402718720 -0.1095030084 -0.1532504857 -0.0202166047 2102 1311867788.6898009777 0.1199497133 0.1201651494 0.1636508107 0.0049532680 0.0244080000 1278083629 0 402718720 -0.1131774485 -0.1575681865 -0.0234220363 2103 1311867788.7262809277 0.1209859028 0.1201655397 0.1636508107 0.0049531535 0.0211550000 1278163797 0 402718720 -0.1131795570 -0.1589913964 -0.0193052944 2104 1311867788.7571070194 0.1197176650 0.1201653268 0.1636508107 0.0049521369 0.0210110000 1278243797 0 402718720 -0.1126586944 -0.1582179368 -0.0186006594 2105 1311867788.7899620533 0.1170114875 0.1201638286 0.1636508107 0.0049510941 0.0226980000 1278323685 0 402718720 -0.1119091958 -0.1559567004 -0.0190151297 2106 1311867788.8253190517 0.1147250533 0.1201612460 0.1636508107 0.0049515950 0.0200810000 1278403909 0 402718720 -0.1107848063 -0.1546487063 -0.0182222724 2107 1311867788.8572509289 0.1113081127 0.1201570443 0.1636508107 0.0049508971 0.0224010000 1278483909 0 402718720 -0.1094008386 -0.1522467136 -0.0191859305 2108 1311867788.8892819881 0.1094993576 0.1201519884 0.1636508107 0.0049498581 0.0192020000 1278563797 0 402718720 -0.1083647162 -0.1508999765 -0.0181999709 2109 1311867788.9253408909 0.1073859707 0.1201459353 0.1636508107 0.0049491920 0.0218330000 1278644021 0 402718720 -0.1073224023 -0.1497559249 -0.0174735524 2110 1311867788.9572029114 0.1062577516 0.1201393532 0.1636508107 0.0049481819 0.0215380000 1278724021 0 402718720 -0.1061014012 -0.1493490785 -0.0176319107 2111 1311867788.9899420738 0.1043175906 0.1201318583 0.1636508107 0.0049482910 0.0196890000 1278803965 0 402718720 -0.1048447192 -0.1485649794 -0.0180738959 2112 1311867789.0253350735 0.1023607925 0.1201234440 0.1636508107 0.0049473825 0.0194410000 1278884077 0 402718720 -0.1036565006 -0.1473702341 -0.0181156751 2113 1311867789.0572888851 0.1006393507 0.1201142229 0.1636508107 0.0049462762 0.0215360000 1278964077 0 402718720 -0.1024287343 -0.1463739127 -0.0181094222 2114 1311867789.0921199322 0.0981674939 0.1201038413 0.1636508107 0.0049453719 0.0215910000 1279044133 0 402718720 -0.1010821089 -0.1449267417 -0.0182727296 2115 1311867789.1266920567 0.0957436413 0.1200923235 0.1636508107 0.0049451741 0.0212070000 1279124301 0 402718720 -0.0989877805 -0.1439461410 -0.0197110511 2116 1311867789.1574180126 0.0932228416 0.1200796253 0.1636508107 0.0049460193 0.0221280000 1279204189 0 402718720 -0.0964396968 -0.1431294233 -0.0223518778 2117 1311867789.1895411015 0.0913539082 0.1200660562 0.1636508107 0.0049454060 0.0218250000 1279284189 0 402718720 -0.0944941118 -0.1424584687 -0.0230298229 2118 1311867789.2251811028 0.0893274173 0.1200515431 0.1636508107 0.0049446970 0.0224360000 1279364357 0 402718720 -0.0925926939 -0.1411564201 -0.0220118761 2119 1311867789.2573940754 0.0874566957 0.1200361610 0.1636508107 0.0049441057 0.0231030000 1279444301 0 402718720 -0.0897642002 -0.1387482733 -0.0153411319 2120 1311867789.2925870419 0.0859655440 0.1200200899 0.1636508107 0.0049430575 0.0337030000 1279524357 0 402718720 -0.0887122676 -0.1374692768 -0.0142662628 2121 1311867789.3252000809 0.0858785138 0.1200039930 0.1636508107 0.0049420383 0.0213060000 1279604469 0 402718720 -0.0891439766 -0.1375698000 -0.0148011688 2122 1311867789.3589100838 0.0855539069 0.1199877583 0.1636508107 0.0049409815 0.0214550000 1279684469 0 402718720 -0.0896381512 -0.1374763697 -0.0154134398 2123 1311867789.3897430897 0.0849890187 0.1199712728 0.1636508107 0.0049409579 0.0216300000 1279764413 0 402718720 -0.0894553512 -0.1370792389 -0.0155425789 2124 1311867789.4252359867 0.0804391876 0.1199526607 0.1636508107 0.0049912740 0.0226790000 1279844581 0 402718720 -0.0771024674 -0.1386278272 -0.0272057112 2125 1311867789.4577910900 0.0822900236 0.1199349371 0.1636508107 0.0049936153 0.0204910000 1279924525 0 402718720 -0.0805219486 -0.1391924918 -0.0229973625 2126 1311867789.4892499447 0.0825876296 0.1199173701 0.1636508107 0.0049951117 0.0186700000 1280004525 0 402718720 -0.0830649734 -0.1385192275 -0.0211506654 2127 1311867789.5256059170 0.0834048390 0.1199002039 0.1636508107 0.0049947356 0.0554400000 1280084637 0 402718720 -0.0849879161 -0.1379468888 -0.0179574378 2128 1311867789.5572779179 0.0840533748 0.1198833586 0.1636508107 0.0049948241 0.0435310000 1280164637 0 402718720 -0.0876514316 -0.1380317807 -0.0166860987 2129 1311867789.5892720222 0.0806595907 0.1198649350 0.1636508107 0.0050082597 0.0200430000 1280244581 0 402718720 -0.0837056339 -0.1384575367 -0.0274748858 2130 1311867789.6253700256 0.0800425932 0.1198462391 0.1636508107 0.0050076538 0.0216940000 1280324749 0 402718720 -0.0837174281 -0.1379495710 -0.0276626069 2131 1311867789.6574499607 0.0815803856 0.1198282824 0.1636508107 0.0050102986 0.0218300000 1280404749 0 402718720 -0.0845095962 -0.1373741925 -0.0199692864 2132 1311867789.6894960403 0.0832621977 0.1198111313 0.1636508107 0.0050106797 0.0215190000 1280484693 0 402718720 -0.0864609033 -0.1373647004 -0.0159066562 2133 1311867789.7253561020 0.0824029669 0.1197935935 0.1636508107 0.0050123824 0.0207540000 1280564805 0 402718720 -0.0881304368 -0.1354976743 -0.0155555811 2134 1311867789.7572050095 0.0818093494 0.1197757939 0.1636508107 0.0050302170 0.0210100000 1280644749 0 402718720 -0.0851714611 -0.1379535347 -0.0237112585 2135 1311867789.7893610001 0.0830767304 0.1197586047 0.1636508107 0.0050369103 0.0204810000 1280724805 0 402718720 -0.0892038494 -0.1364693344 -0.0163001791 2136 1311867789.8253350258 0.0840683058 0.1197418957 0.1636508107 0.0050360829 0.0208830000 1280804917 0 402718720 -0.0901736617 -0.1361566931 -0.0141354594 2137 1311867789.8573410511 0.0858881474 0.1197260540 0.1636508107 0.0050357146 0.0218360000 1280884917 0 402718720 -0.0907981694 -0.1363362074 -0.0100896200 2138 1311867789.8893530369 0.0870706663 0.1197107802 0.1636508107 0.0050346478 0.0217420000 1280964917 0 402718720 -0.0923563242 -0.1364430934 -0.0086345645 2139 1311867789.9253480434 0.0874895155 0.1196957165 0.1636508107 0.0050338725 0.0267860000 1281045029 0 402718720 -0.0940353796 -0.1362236887 -0.0074844793 2140 1311867789.9572958946 0.0871492252 0.1196805078 0.1636508107 0.0050331430 0.0223210000 1281124917 0 402718720 -0.0941058993 -0.1361716092 -0.0076904008 2141 1311867789.9892580509 0.0865001008 0.1196650102 0.1636508107 0.0050339030 0.0200620000 1281204973 0 402718720 -0.0926991329 -0.1357424110 -0.0082165021 2142 1311867790.0253860950 0.0841288567 0.1196484201 0.1636508107 0.0051130081 0.0195920000 1281285141 0 402718720 -0.0877100527 -0.1410914809 -0.0346922502 2143 1311867790.0572030544 0.0840278342 0.1196317982 0.1636508107 0.0051122946 0.0204790000 1281365029 0 402718720 -0.0884644836 -0.1407264769 -0.0360728242 2144 1311867790.0896821022 0.0856497884 0.1196159484 0.1636508107 0.0051202444 0.0259400000 1281445085 0 402718720 -0.0905698016 -0.1417351514 -0.0371328704 2145 1311867790.1257700920 0.0967432037 0.1196052851 0.1636508107 0.0051323097 0.0259200000 1281525253 0 402718720 -0.0989196897 -0.1511601508 -0.0349107236 2146 1311867790.1572160721 0.1024111882 0.1195972730 0.1636508107 0.0051465981 0.0279880000 1281605197 0 402718720 -0.1046910584 -0.1555341631 -0.0357686058 2147 1311867790.1892650127 0.1017939076 0.1195889808 0.1636508107 0.0051505644 0.0240570000 1281685141 0 402718720 -0.1031815782 -0.1552289426 -0.0385774970 2148 1311867790.2254109383 0.1007517576 0.1195802111 0.1636508107 0.0051526050 0.0195560000 1281765365 0 402718720 -0.1022054106 -0.1542624235 -0.0399701558 2149 1311867790.2574319839 0.1020963639 0.1195720753 0.1636508107 0.0051549105 0.0218460000 1281845365 0 402718720 -0.1053280011 -0.1548772305 -0.0381193534 2150 1311867790.2894361019 0.1014430746 0.1195636432 0.1636508107 0.0051542792 0.0217890000 1281925309 0 402718720 -0.1052454486 -0.1538006067 -0.0385705307 2151 1311867790.3254859447 0.0994959697 0.1195543137 0.1636508107 0.0051557093 0.0441870000 1282005477 0 402718720 -0.1039302945 -0.1525316983 -0.0400207788 2152 1311867790.3573629856 0.0997962728 0.1195451325 0.1636508107 0.0051599710 0.0237350000 1282085477 0 402718720 -0.1038230062 -0.1524317116 -0.0389935970 2153 1311867790.3896179199 0.0986655876 0.1195354346 0.1636508107 0.0051590861 0.0231380000 1282165421 0 402718720 -0.1034596041 -0.1518585533 -0.0384350754 2154 1311867790.4259679317 0.0998383835 0.1195262902 0.1636508107 0.0051588359 0.0232190000 1282245645 0 402718720 -0.1027432680 -0.1531423479 -0.0395581461 2155 1311867790.4603190422 0.1054220945 0.1195197453 0.1636508107 0.0051691501 0.0239730000 1282325645 0 402718720 -0.1060166731 -0.1577586681 -0.0379885957 2156 1311867790.4893760681 0.1039854065 0.1195125402 0.1636508107 0.0051692353 0.0216890000 1282405589 0 402718720 -0.1055143401 -0.1563750058 -0.0380365066 2157 1311867790.5260839462 0.1029810458 0.1195048760 0.1636508107 0.0051730346 0.0210200000 1282485701 0 402718720 -0.1037984267 -0.1556642205 -0.0397042707 2158 1311867790.5578069687 0.1017276943 0.1194966382 0.1636508107 0.0051773286 0.0226690000 1282565589 0 402718720 -0.1037827209 -0.1539780945 -0.0396447368 2159 1311867790.5941510201 0.1021443009 0.1194886010 0.1636508107 0.0051862979 0.0226220000 1282645701 0 402718720 -0.1032241061 -0.1532829851 -0.0406487249 2160 1311867790.6255199909 0.1054712236 0.1194821115 0.1636508107 0.0051969197 0.0276970000 1282725813 0 402718720 -0.1064154431 -0.1560678780 -0.0379300565 2161 1311867790.6573970318 0.1037022173 0.1194748094 0.1636508107 0.0052011049 0.0230260000 1282805701 0 402718720 -0.1042745337 -0.1558735520 -0.0399239175 2162 1311867790.6901741028 0.1038708910 0.1194675920 0.1636508107 0.0052000413 0.0222950000 1282885701 0 402718720 -0.1030259132 -0.1561665535 -0.0413392931 2163 1311867790.7253530025 0.1024860367 0.1194597411 0.1636508107 0.0051999781 0.0236030000 1282965813 0 402718720 -0.1020256281 -0.1548272222 -0.0402244702 2164 1311867790.7575750351 0.1012850776 0.1194513425 0.1636508107 0.0051992333 0.0216090000 1283045813 0 402718720 -0.1008793786 -0.1535647810 -0.0398375727 2165 1311867790.7912619114 0.1072397605 0.1194457020 0.1636508107 0.0052005368 0.0262530000 1283125813 0 402718720 -0.1060990170 -0.1585570872 -0.0410439149 2166 1311867790.8261721134 0.1048027724 0.1194389416 0.1636508107 0.0052055904 0.0215060000 1283205925 0 402718720 -0.1050725132 -0.1558875889 -0.0417631231 2167 1311867790.8573560715 0.1030151397 0.1194313626 0.1636508107 0.0052050943 0.0233340000 1283285925 0 402718720 -0.1039043963 -0.1538775414 -0.0409337431 2168 1311867790.8950359821 0.1047617495 0.1194245962 0.1636508107 0.0052039801 0.0226610000 1283366037 0 402718720 -0.1053827330 -0.1547453105 -0.0404202379 2169 1311867790.9258060455 0.1038795859 0.1194174293 0.1636508107 0.0052043252 0.0220070000 1283446037 0 402718720 -0.1043678522 -0.1534298062 -0.0429139361 2170 1311867790.9606111050 0.1055460945 0.1194110369 0.1636508107 0.0052033655 0.0228380000 1283526093 0 402718720 -0.1071295291 -0.1543263942 -0.0401746072 2171 1311867790.9944651127 0.1046112701 0.1194042199 0.1636508107 0.0052029112 0.0211280000 1283606205 0 402718720 -0.1056877524 -0.1532393694 -0.0393759571 2172 1311867791.0298559666 0.1053926647 0.1193977689 0.1636508107 0.0052034254 0.0205640000 1283686261 0 402718720 -0.1065878347 -0.1535812318 -0.0399241708 2173 1311867791.0577239990 0.1044107303 0.1193908720 0.1636508107 0.0052056626 0.0238020000 1283766037 0 402718720 -0.1045346037 -0.1528077871 -0.0396391004 2174 1311867791.0912530422 0.1040427163 0.1193838121 0.1636508107 0.0052058985 0.0251170000 1283846149 0 402718720 -0.1042963639 -0.1521572918 -0.0386818461 2175 1311867791.1254060268 0.1052886024 0.1193773316 0.1636508107 0.0052076815 0.0236290000 1283926261 0 402718720 -0.1039306521 -0.1530950665 -0.0415465124 2176 1311867791.1586070061 0.1060169488 0.1193711917 0.1636508107 0.0052069803 0.0248080000 1284006261 0 402718720 -0.1031473130 -0.1537145674 -0.0415157229 2177 1311867791.1905651093 0.1064589024 0.1193652605 0.1636508107 0.0052069199 0.0227420000 1284086317 0 402718720 -0.1065001935 -0.1537366509 -0.0395502001 2178 1311867791.2257239819 0.1065665409 0.1193593841 0.1636508107 0.0052107180 0.0222840000 1284166373 0 402718720 -0.1043039262 -0.1541708112 -0.0418078974 2179 1311867791.2578790188 0.1083316281 0.1193543232 0.1636508107 0.0052145594 0.0223080000 1284246317 0 402718720 -0.1021451205 -0.1563922018 -0.0426256135 2180 1311867791.2920079231 0.1155297756 0.1193525688 0.1636508107 0.0052190028 0.0249020000 1284326373 0 402718720 -0.1078451648 -0.1634687036 -0.0417726748 2181 1311867791.3277668953 0.1145149618 0.1193503507 0.1636508107 0.0052262469 0.0209280000 1284406485 0 402718720 -0.1054726690 -0.1627186239 -0.0432984829 2182 1311867791.3594648838 0.1143842041 0.1193480748 0.1636508107 0.0052343758 0.0230590000 1284486541 0 402718720 -0.1081859022 -0.1625540555 -0.0398221947 2183 1311867791.3896780014 0.1116937995 0.1193445684 0.1636508107 0.0052344526 0.0215540000 1284566541 0 402718720 -0.1060515046 -0.1600988060 -0.0413866341 2184 1311867791.4269950390 0.1128990874 0.1193416172 0.1636508107 0.0052394756 0.0252820000 1284646653 0 402718720 -0.1089171097 -0.1613239199 -0.0390589312 2185 1311867791.4574470520 0.1143169999 0.1193393176 0.1636508107 0.0052406172 0.0245350000 1284726653 0 402718720 -0.1079368219 -0.1629361212 -0.0406629480 2186 1311867791.4916360378 0.1124283969 0.1193361562 0.1636508107 0.0052477378 0.0200170000 1284806653 0 402718720 -0.1051570252 -0.1610646844 -0.0422465205 2187 1311867791.5275270939 0.1174620539 0.1193352993 0.1636508107 0.0052522605 0.0267770000 1284886765 0 402718720 -0.1085911617 -0.1658978462 -0.0411610417 2188 1311867791.5593578815 0.1149866655 0.1193333118 0.1636508107 0.0052564731 0.0227040000 1284966765 0 402718720 -0.1064317748 -0.1634641290 -0.0420501791 2189 1311867791.5894811153 0.1096368209 0.1193288821 0.1636508107 0.0052573135 0.0255340000 1285046765 0 402718720 -0.1058771387 -0.1581020802 -0.0412165299 2190 1311867791.6275360584 0.1070202440 0.1193232617 0.1636508107 0.0052581161 0.0200860000 1285126877 0 402718720 -0.1052582934 -0.1554885954 -0.0418209210 2191 1311867791.6574349403 0.1137765720 0.1193207302 0.1636508107 0.0052777113 0.0257830000 1285206933 0 402718720 -0.1094509512 -0.1619239300 -0.0398383513 2192 1311867791.6894969940 0.1130492017 0.1193178691 0.1636508107 0.0052816712 0.0216920000 1285286877 0 402718720 -0.1060301587 -0.1611272246 -0.0429349691 2193 1311867791.7263040543 0.1153278798 0.1193160496 0.1636508107 0.0052810329 0.0198490000 1285366989 0 402718720 -0.1086804196 -0.1630948633 -0.0418354124 2194 1311867791.7601580620 0.1173340529 0.1193151463 0.1636508107 0.0052808247 0.0243500000 1285447045 0 402718720 -0.1107186303 -0.1647707522 -0.0410054214 2195 1311867791.7896749973 0.1157317162 0.1193135137 0.1636508107 0.0052813214 0.0204300000 1285526933 0 402718720 -0.1096834242 -0.1629700661 -0.0410870388 2196 1311867791.8264999390 0.1152796671 0.1193116768 0.1636508107 0.0052850391 0.0233220000 1285607101 0 402718720 -0.1059055999 -0.1622980684 -0.0448390767 2197 1311867791.8574469090 0.1140158549 0.1193092663 0.1636508107 0.0052839410 0.0219440000 1285687157 0 402718720 -0.1044686958 -0.1610005498 -0.0441544056 2198 1311867791.8894960880 0.1134368703 0.1193065946 0.1636508107 0.0052829928 0.0224640000 1285767045 0 402718720 -0.1043076515 -0.1602273136 -0.0447070897 2199 1311867791.9275770187 0.1175555587 0.1193057983 0.1636508107 0.0052938517 0.0257220000 1285847213 0 402718720 -0.1101902053 -0.1640111059 -0.0430317409 2200 1311867791.9574968815 0.1152544841 0.1193039568 0.1636508107 0.0052956172 0.0193880000 1285927213 0 402718720 -0.1072810665 -0.1615816355 -0.0430588424 2201 1311867791.9917910099 0.1151567027 0.1193020726 0.1636508107 0.0052990623 0.0509520000 1286007101 0 402718720 -0.1106239185 -0.1612080187 -0.0410848409 2202 1311867792.0276811123 0.1143858656 0.1192998400 0.1636508107 0.0053043198 0.0209610000 1286087157 0 402718720 -0.1069782078 -0.1603949517 -0.0451621078 2203 1311867792.0615789890 0.1169493943 0.1192987730 0.1636508107 0.0053063737 0.0230490000 1286167381 0 402718720 -0.1107592881 -0.1627432108 -0.0420942232 2204 1311867792.0897018909 0.1198852956 0.1192990392 0.1636508107 0.0053081724 0.0269620000 1286247157 0 402718720 -0.1108891740 -0.1654766798 -0.0444678478 2205 1311867792.1256570816 0.1203154624 0.1192995001 0.1636508107 0.0053198108 0.0220570000 1286327269 0 402718720 -0.1068847850 -0.1657073200 -0.0494389869 2206 1311867792.1595649719 0.1218092963 0.1193006378 0.1636508107 0.0053203690 0.0244880000 1286407325 0 402718720 -0.1051122397 -0.1671824455 -0.0475812815 2207 1311867792.1895029545 0.1184645966 0.1193002590 0.1636508107 0.0053211909 0.0224430000 1286487269 0 402718720 -0.1045408249 -0.1637121439 -0.0459700637 2208 1311867792.2253580093 0.1174767390 0.1192994332 0.1636508107 0.0053222535 0.0205270000 1286567437 0 402718720 -0.1042687744 -0.1624942273 -0.0472310297 2209 1311867792.2575690746 0.1228529513 0.1193010418 0.1636508107 0.0053428882 0.0263040000 1286647381 0 402718720 -0.1119585782 -0.1679038256 -0.0445797294 2210 1311867792.2896258831 0.1206822693 0.1193016668 0.1636508107 0.0053434450 0.0200250000 1286727381 0 402718720 -0.1096009016 -0.1656223387 -0.0456686988 2211 1311867792.3314530849 0.1231745929 0.1193034185 0.1636508107 0.0053427671 0.0238860000 1286807717 0 402718720 -0.1115123630 -0.1679130793 -0.0449686907 2212 1311867792.3588991165 0.1235058755 0.1193053183 0.1636508107 0.0053470189 0.0219320000 1286887493 0 402718720 -0.1086474061 -0.1681814045 -0.0497483872 2213 1311867792.3897619247 0.1230143756 0.1193069943 0.1636508107 0.0053460509 0.0212890000 1286967493 0 402718720 -0.1083429903 -0.1677680165 -0.0488953926 2214 1311867792.4281799793 0.1196331233 0.1193071416 0.1636508107 0.0053488200 0.0214170000 1287047661 0 402718720 -0.1085571796 -0.1643252522 -0.0463432483 2215 1311867792.4589118958 0.1226818040 0.1193086652 0.1636508107 0.0053529432 0.0506280000 1287127605 0 402718720 -0.1125284210 -0.1674965918 -0.0475562625 2216 1311867792.4895460606 0.1223923638 0.1193100568 0.1636508107 0.0053567372 0.0233590000 1287207549 0 402718720 -0.1089298874 -0.1669526994 -0.0510416217 2217 1311867792.5256149769 0.1214936599 0.1193110417 0.1636508107 0.0053575609 0.0227510000 1287287773 0 402718720 -0.1073894650 -0.1660568118 -0.0510372445 2218 1311867792.5579569340 0.1215319186 0.1193120430 0.1636508107 0.0053577321 0.0212100000 1287367661 0 402718720 -0.1059690490 -0.1659773588 -0.0520756207 2219 1311867792.5898280144 0.1252897382 0.1193147369 0.1636508107 0.0053583982 0.0237580000 1287447605 0 402718720 -0.1067880988 -0.1694515795 -0.0554835200 2220 1311867792.6254990101 0.1244997755 0.1193170725 0.1636508107 0.0053605285 0.0204760000 1287527717 0 402718720 -0.1065951809 -0.1686228812 -0.0550938770 2221 1311867792.6587479115 0.1268922240 0.1193204831 0.1636508107 0.0053640642 0.0253530000 1287607717 0 402718720 -0.1069844589 -0.1705161780 -0.0598803014 2222 1311867792.6896479130 0.1269997209 0.1193239392 0.1636508107 0.0053629691 0.0235520000 1287687661 0 402718720 -0.1066125855 -0.1706970185 -0.0579939075 2223 1311867792.7254209518 0.1268963367 0.1193273455 0.1636508107 0.0053652838 0.0234360000 1287767829 0 402718720 -0.1067188233 -0.1707823277 -0.0574382506 2224 1311867792.7574810982 0.1272280961 0.1193308980 0.1636508107 0.0053641274 0.0201990000 1287847885 0 402718720 -0.1071194261 -0.1709319949 -0.0569587387 2225 1311867792.7895770073 0.1271136105 0.1193343959 0.1636508107 0.0053647783 0.0211450000 1287927773 0 402718720 -0.1081426889 -0.1708998978 -0.0580539592 2226 1311867792.8254449368 0.1263881177 0.1193375647 0.1636508107 0.0053645005 0.0204090000 1288007941 0 402718720 -0.1071459204 -0.1695006192 -0.0597122461 2227 1311867792.8578031063 0.1262895912 0.1193406864 0.1636508107 0.0053645274 0.0226830000 1288087941 0 402718720 -0.1059512645 -0.1690384895 -0.0627311468 2228 1311867792.8896510601 0.1259876937 0.1193436698 0.1636508107 0.0053641870 0.0544410000 1288167885 0 402718720 -0.1061745062 -0.1687999517 -0.0609000064 2229 1311867792.9254279137 0.1246529520 0.1193460517 0.1636508107 0.0053631145 0.0243210000 1288248053 0 402718720 -0.1067208946 -0.1672944427 -0.0608748272 2230 1311867792.9580109119 0.1252410710 0.1193486952 0.1636508107 0.0053630463 0.0210430000 1288328053 0 402718720 -0.1053605154 -0.1674909592 -0.0632419735 2231 1311867792.9896769524 0.1263374388 0.1193518277 0.1636508107 0.0053626300 0.0224040000 1288407997 0 402718720 -0.1047760770 -0.1682229191 -0.0644632280 2232 1311867793.0254170895 0.1267284900 0.1193551327 0.1636508107 0.0053614897 0.0211700000 1288488109 0 402718720 -0.1061641052 -0.1686922312 -0.0637963563 2233 1311867793.0575890541 0.1294916868 0.1193596721 0.1636508107 0.0053635141 0.0322940000 1288568165 0 402718720 -0.1044188291 -0.1706982255 -0.0672879741 2234 1311867793.0896120071 0.1315426677 0.1193651256 0.1636508107 0.0053664168 0.0212270000 1288664493 0 402718720 -0.1027423441 -0.1723255217 -0.0679447576 2235 1311867793.1253809929 0.1339398921 0.1193716467 0.1636508107 0.0053760208 0.0211710000 1288744605 0 402718720 -0.0998583138 -0.1736474931 -0.0708834082 2236 1311867793.1573770046 0.1356938332 0.1193789465 0.1636508107 0.0053873918 0.0219550000 1288824661 0 402718720 -0.0959642231 -0.1739938110 -0.0731487721 2237 1311867793.1896579266 0.1359365880 0.1193863482 0.1636508107 0.0053876253 0.0205750000 1288904605 0 402718720 -0.0965296626 -0.1744976938 -0.0701962784 2238 1311867793.2255470753 0.1353047192 0.1193934609 0.1636508107 0.0053940319 0.0227010000 1288984773 0 402718720 -0.0947813541 -0.1727459431 -0.0719894692 2239 1311867793.2574770451 0.1346634030 0.1194002809 0.1636508107 0.0053929781 0.0212880000 1289064717 0 402718720 -0.0936873928 -0.1720602512 -0.0700604171 2240 1311867793.2896931171 0.1345066875 0.1194070249 0.1636508107 0.0053976843 0.0200950000 1289144717 0 402718720 -0.0920688659 -0.1710032523 -0.0709727034 2241 1311867793.3254458904 0.1338373274 0.1194134641 0.1636508107 0.0054035894 0.0547210000 1289224885 0 402718720 -0.0927289799 -0.1705338508 -0.0683898255 2242 1311867793.3575859070 0.1346801519 0.1194202735 0.1636508107 0.0054069935 0.0202050000 1289304885 0 402718720 -0.0925422832 -0.1712210327 -0.0668161660 2243 1311867793.3896119595 0.1343256533 0.1194269188 0.1636508107 0.0054117150 0.0219770000 1289384829 0 402718720 -0.0919896960 -0.1703864485 -0.0666935965 2244 1311867793.4254410267 0.1337806284 0.1194333153 0.1636508107 0.0054144556 0.0203070000 1289464997 0 402718720 -0.0924583152 -0.1700170785 -0.0637571886 2245 1311867793.4576559067 0.1349842250 0.1194402422 0.1636508107 0.0054142536 0.0208580000 1289544997 0 402718720 -0.0921051502 -0.1707863361 -0.0646330789 2246 1311867793.4896628857 0.1347310394 0.1194470502 0.1636508107 0.0054156616 0.0401700000 1289624941 0 402718720 -0.0905611962 -0.1697444469 -0.0649810284 2247 1311867793.5258879662 0.1343122125 0.1194536657 0.1636508107 0.0054170422 0.0233080000 1289704941 0 402718720 -0.0938265771 -0.1703621149 -0.0589626916 2248 1311867793.5579180717 0.1328829378 0.1194596396 0.1636508107 0.0054167366 0.0237620000 1289784997 0 402718720 -0.0969343781 -0.1691488624 -0.0601951927 2249 1311867793.5898079872 0.1328719705 0.1194656033 0.1636508107 0.0054162431 0.0230680000 1289864941 0 402718720 -0.0967829153 -0.1687839031 -0.0597615130 2250 1311867793.6255509853 0.1326161921 0.1194714480 0.1636508107 0.0054170777 0.0213490000 1289944997 0 402718720 -0.0970821455 -0.1682264358 -0.0572435260 2251 1311867793.6576049328 0.1275084317 0.1194750184 0.1636508107 0.0054384250 0.0314720000 1290024941 0 402718720 -0.1029939130 -0.1639111340 -0.0509155728 2252 1311867793.6895890236 0.1261125505 0.1194779658 0.1636508107 0.0054408775 0.0219360000 1290104941 0 402718720 -0.1033339053 -0.1621894687 -0.0508123897 2253 1311867793.7268180847 0.1254783124 0.1194806291 0.1636508107 0.0054422893 0.0227950000 1290185165 0 402718720 -0.1045073196 -0.1611736119 -0.0482185818 2254 1311867793.7576351166 0.1224115118 0.1194819294 0.1636508107 0.0054450866 0.0210480000 1290265053 0 402718720 -0.1062797308 -0.1576481014 -0.0457037725 2255 1311867793.7896919250 0.1218165010 0.1194829647 0.1636508107 0.0054439169 0.0213610000 1290345053 0 402718720 -0.1067206040 -0.1567564160 -0.0466777086 2256 1311867793.8265030384 0.1219633296 0.1194840641 0.1636508107 0.0054428591 0.0221030000 1290425221 0 402718720 -0.1070934460 -0.1564283222 -0.0464863479 2257 1311867793.8576350212 0.1247595102 0.1194864015 0.1636508107 0.0054655080 0.0284620000 1290505221 0 402718720 -0.1107989624 -0.1594958901 -0.0437193885 2258 1311867793.8896689415 0.1249651462 0.1194888279 0.1636508107 0.0054659572 0.0244990000 1290585165 0 402718720 -0.1137373596 -0.1596857160 -0.0409552455 2259 1311867793.9268779755 0.1236274615 0.1194906599 0.1636508107 0.0054975132 0.0598270000 1290665389 0 402718720 -0.1240287647 -0.1572434306 -0.0264677238 2260 1311867793.9576759338 0.1232216433 0.1194923108 0.1636508107 0.0054979100 0.0203960000 1290745277 0 402718720 -0.1240123734 -0.1558253914 -0.0235356316 2261 1311867793.9897069931 0.1234975532 0.1194940822 0.1636508107 0.0054988481 0.0225850000 1290825277 0 402718720 -0.1239519939 -0.1548211426 -0.0203379262 2262 1311867794.0276429653 0.1242023855 0.1194961637 0.1636508107 0.0055057175 0.0198330000 1290905501 0 402718720 -0.1224288270 -0.1540947258 -0.0176959392 2263 1311867794.0576469898 0.1314802468 0.1195014594 0.1636508107 0.0055194615 0.0251060000 1290985389 0 402718720 -0.1213707104 -0.1605204940 -0.0166513845 2264 1311867794.0897390842 0.1301069707 0.1195061438 0.1636508107 0.0055224311 0.0206690000 1291065389 0 402718720 -0.1206346527 -0.1577542871 -0.0134603828 2265 1311867794.1268970966 0.1300551146 0.1195108012 0.1636508107 0.0055369501 0.0212660000 1291145613 0 402718720 -0.1196960807 -0.1554481983 -0.0100270696 2266 1311867794.1576809883 0.1277552247 0.1195144395 0.1636508107 0.0055446958 0.0239350000 1291225501 0 402718720 -0.1175650507 -0.1521799415 -0.0098176776 2267 1311867794.1896860600 0.1278339922 0.1195181093 0.1636508107 0.0055497977 0.0204540000 1291305501 0 402718720 -0.1199075207 -0.1511794478 -0.0073188064 2268 1311867794.2257699966 0.1276839226 0.1195217098 0.1636508107 0.0055689074 0.0231360000 1291385613 0 402718720 -0.1249307245 -0.1491347998 -0.0023604864 2269 1311867794.2577419281 0.1276295334 0.1195252831 0.1636508107 0.0055700232 0.0218240000 1291465613 0 402718720 -0.1246765330 -0.1478632987 -0.0013437062 2270 1311867794.2897291183 0.1276059151 0.1195288428 0.1636508107 0.0055725716 0.0227200000 1291545557 0 402718720 -0.1268668771 -0.1460112184 0.0025730117 2271 1311867794.3254759312 0.1275418252 0.1195323712 0.1636508107 0.0055866572 0.0258420000 1291625725 0 402718720 -0.1297096908 -0.1456771344 0.0011894718 2272 1311867794.3576920033 0.1283800751 0.1195362655 0.1636508107 0.0055979684 0.0264110000 1291705725 0 402718720 -0.1271142513 -0.1461415291 -0.0004226170 2273 1311867794.3898310661 0.1270051897 0.1195395514 0.1636508107 0.0055972466 0.0530910000 1291785725 0 402718720 -0.1260585040 -0.1448215246 -0.0034308827 2274 1311867794.4267508984 0.1269741803 0.1195428208 0.1636508107 0.0055989648 0.0225240000 1291865893 0 402718720 -0.1258825958 -0.1436027437 -0.0032696773 2275 1311867794.4577209949 0.1270714849 0.1195461301 0.1636508107 0.0055981985 0.0218770000 1291945781 0 402718720 -0.1255649924 -0.1430231333 -0.0028980959 2276 1311867794.4896879196 0.1275796145 0.1195496598 0.1636508107 0.0055978110 0.0221210000 1292025837 0 402718720 -0.1249060333 -0.1430188268 -0.0028445856 2277 1311867794.5258600712 0.1287203133 0.1195536873 0.1636508107 0.0055986520 0.0210980000 1292105949 0 402718720 -0.1249047890 -0.1436060667 -0.0026350608 2278 1311867794.5576190948 0.1367592365 0.1195612402 0.1636508107 0.0056221023 0.0244910000 1292185949 0 402718720 -0.1208861396 -0.1501916349 0.0001904849 2279 1311867794.5898959637 0.1381054074 0.1195693772 0.1636508107 0.0056220105 0.0203690000 1292265949 0 402718720 -0.1196913272 -0.1505870819 0.0010551988 2280 1311867794.6258609295 0.1514490545 0.1195833595 0.1636508107 0.0056746299 0.0211240000 1292346061 0 402718720 -0.1263807416 -0.1634047627 0.0054511833 2281 1311867794.6577029228 0.1596966088 0.1196009453 0.1636508107 0.0056821001 0.0231790000 1292426005 0 402718720 -0.1258871704 -0.1720366627 0.0033770613 2282 1311867794.6897399426 0.1602131724 0.1196187421 0.1636508107 0.0056842205 0.0230040000 1292506005 0 402718720 -0.1224368587 -0.1731869727 -0.0019914310 2283 1311867794.7255890369 0.1602939069 0.1196365586 0.1636508107 0.0056854351 0.0215330000 1292586117 0 402718720 -0.1213484555 -0.1730230004 -0.0036287757 2284 1311867794.7576520443 0.1605635881 0.1196544776 0.1636508107 0.0056872905 0.0198560000 1292666117 0 402718720 -0.1226663589 -0.1733721644 -0.0053968420 2285 1311867794.7897210121 0.1635507792 0.1196736883 0.1636508107 0.0056893000 0.0218460000 1292746117 0 402718720 -0.1244636774 -0.1755058914 -0.0028014181 2286 1311867794.8255579472 0.1625167876 0.1196924298 0.1636508107 0.0056881717 0.0209630000 1292826229 0 402718720 -0.1242522821 -0.1741658598 -0.0040008482 2287 1311867794.8576180935 0.1646582186 0.1197120913 0.1646582186 0.0056897458 0.0214920000 1292906173 0 402718720 -0.1236230955 -0.1752740592 -0.0022377062 2288 1311867794.8897540569 0.1638630629 0.1197313880 0.1646582186 0.0056889127 0.0212090000 1292986117 0 402718720 -0.1235736609 -0.1745175123 -0.0052774106 2289 1311867794.9255731106 0.1646389216 0.1197510069 0.1646582186 0.0056887170 0.0204050000 1293066229 0 402718720 -0.1244394034 -0.1738407314 -0.0020602213 2290 1311867794.9577300549 0.1652261466 0.1197708650 0.1652261466 0.0056888857 0.0205320000 1293146229 0 402718720 -0.1222005934 -0.1742225289 -0.0052944557 2291 1311867794.9897680283 0.1690721363 0.1197923845 0.1690721363 0.0056878713 0.0260010000 1293226229 0 402718720 -0.1225304604 -0.1770477295 -0.0027847858 2292 1311867795.0255720615 0.1690836251 0.1198138903 0.1690836251 0.0056876894 0.0240360000 1293306341 0 402718720 -0.1220403165 -0.1768838465 -0.0063964957 2293 1311867795.0578250885 0.1681013256 0.1198349489 0.1690836251 0.0056868588 0.0226400000 1293386341 0 402718720 -0.1224128231 -0.1750518531 -0.0059824311 2294 1311867795.0897150040 0.1671545804 0.1198555765 0.1690836251 0.0056857735 0.0219300000 1293466285 0 402718720 -0.1220426857 -0.1734542847 -0.0062353662 2295 1311867795.1257350445 0.1680196524 0.1198765630 0.1690836251 0.0056868050 0.0526700000 1293546453 0 402718720 -0.1213520244 -0.1741932780 -0.0086900974 2296 1311867795.1576890945 0.1694260687 0.1198981438 0.1694260687 0.0056860810 0.0212370000 1293626509 0 402718720 -0.1228844970 -0.1746691763 -0.0054685245 2297 1311867795.1897299290 0.1713130027 0.1199205273 0.1713130027 0.0056853269 0.0226930000 1293706453 0 402718720 -0.1216033995 -0.1762315929 -0.0060746190 2298 1311867795.2256801128 0.1697175950 0.1199421971 0.1713130027 0.0056846912 0.0203060000 1293786621 0 402718720 -0.1212707162 -0.1744062006 -0.0069495882 2299 1311867795.2576479912 0.1745078713 0.1199659316 0.1745078713 0.0056842884 0.0221900000 1293866621 0 402718720 -0.1229838654 -0.1775003076 -0.0002654512 2300 1311867795.2898659706 0.1729275435 0.1199889584 0.1745078713 0.0056832072 0.0247410000 1293946677 0 402718720 -0.1217057928 -0.1753766537 -0.0004263031 2301 1311867795.3256158829 0.1734531969 0.1200121936 0.1745078713 0.0056840949 0.0206550000 1294026733 0 402718720 -0.1224888861 -0.1764741540 -0.0036375218 2302 1311867795.3578639030 0.1754005253 0.1200362545 0.1754005253 0.0056848105 0.0214880000 1294106733 0 402718720 -0.1218768954 -0.1784870625 -0.0061784950 2303 1311867795.3898470402 0.1771230847 0.1200610426 0.1771230847 0.0056842376 0.0231050000 1294186733 0 402718720 -0.1219571605 -0.1786933690 -0.0014880326 2304 1311867795.4255919456 0.1754100770 0.1200850656 0.1771230847 0.0056839468 0.0228290000 1294266901 0 402718720 -0.1217920557 -0.1771177351 -0.0045523648 2305 1311867795.4576721191 0.1736703366 0.1201083130 0.1771230847 0.0056833100 0.0216130000 1294346957 0 402718720 -0.1229319647 -0.1756036133 -0.0072286278 2306 1311867795.4897990227 0.1726247519 0.1201310868 0.1771230847 0.0056823318 0.0201530000 1294427013 0 402718720 -0.1255343854 -0.1744107306 -0.0074303946 2307 1311867795.5256381035 0.1730479747 0.1201540244 0.1771230847 0.0056811601 0.0200030000 1294507237 0 402718720 -0.1254860610 -0.1740285009 -0.0074280184 2308 1311867795.5577650070 0.1740645021 0.1201773824 0.1771230847 0.0056830194 0.0205940000 1294587237 0 402718720 -0.1274323910 -0.1746210754 -0.0072347480 2309 1311867795.5897519588 0.1763880998 0.1202017266 0.1771230847 0.0056830455 0.0539670000 1294667349 0 402718720 -0.1292631775 -0.1768434346 -0.0093683312 2310 1311867795.6256320477 0.1747425795 0.1202253374 0.1771230847 0.0056822830 0.0217150000 1294747517 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2311 1311867795.6576409340 0.1756694019 0.1202493288 0.1771230847 0.0056826940 0.0165580000 1294828893 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2312 1311867795.6897289753 0.1767401695 0.1202737625 0.1771230847 0.0056828865 0.0100640000 1295062269 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2313 1311867795.7256000042 0.1777879596 0.1202986281 0.1777879596 0.0056844946 0.0103780000 1295142221 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2314 1311867795.7577409744 0.1787839830 0.1203239027 0.1787839830 0.0056852295 0.0113420000 1295222061 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2315 1311867795.7899758816 0.1795776039 0.1203494983 0.1795776039 0.0056845764 0.0092000000 1295301789 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2316 1311867795.8256490231 0.1803029478 0.1203753849 0.1803029478 0.0056840257 0.0109060000 1295381685 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2317 1311867795.8577339649 0.1806581616 0.1204014025 0.1806581616 0.0056829511 0.0111150000 1295461525 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2318 1311867795.8900279999 0.1809348911 0.1204275170 0.1809348911 0.0056817600 0.0097020000 1295541253 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2319 1311867795.9256370068 0.1810669154 0.1204536660 0.1810669154 0.0056805499 0.0097070000 1295621149 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2320 1311867795.9578189850 0.1811852455 0.1204798434 0.1811852455 0.0056794189 0.0096710000 1295700933 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2321 1311867795.9898440838 0.1813075542 0.1205060509 0.1813075542 0.0056784540 0.0103920000 1295780661 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2322 1311867796.0260059834 0.1815098524 0.1205323230 0.1815098524 0.0056773037 0.0099180000 1295860613 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2323 1311867796.0580320358 0.1817905605 0.1205586933 0.1817905605 0.0056764198 0.0099130000 1295940397 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2324 1311867796.0898818970 0.1820717007 0.1205851619 0.1820717007 0.0056754466 0.0097210000 1296020125 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2325 1311867796.1256868839 0.1824192405 0.1206117572 0.1824192405 0.0056744072 0.0101320000 1296099853 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2326 1311867796.1577088833 0.1827054769 0.1206384527 0.1827054769 0.0056734236 0.0151630000 1296179693 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2327 1311867796.1897110939 0.1830623150 0.1206652786 0.1830623150 0.0056723029 0.0108240000 1296259365 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2328 1311867796.2257421017 0.1832036674 0.1206921422 0.1832036674 0.0056712096 0.0102600000 1296339317 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2329 1311867796.2579491138 0.1834112704 0.1207190718 0.1834112704 0.0056700149 0.0102600000 1296419101 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2330 1311867796.2897720337 0.1836110502 0.1207460641 0.1836110502 0.0056688004 0.0100730000 1296498829 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2331 1311867796.3257079124 0.1836763620 0.1207730612 0.1836763620 0.0056676746 0.0093610000 1296578669 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2332 1311867796.3577558994 0.1836749315 0.1208000346 0.1836763620 0.0056664969 0.0103050000 1296658509 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2333 1311867796.3899080753 0.1837460995 0.1208270153 0.1837460995 0.0056653396 0.0098680000 1296738125 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2334 1311867796.4257209301 0.1837460995 0.1208539729 0.1837460995 0.0056642707 0.0111500000 1296818021 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2335 1311867796.4577751160 0.1838220060 0.1208809400 0.1838220060 0.0056630965 0.0098190000 1296897861 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2336 1311867796.4897890091 0.1838260889 0.1209078857 0.1838260889 0.0056620491 0.0098370000 1296977589 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2337 1311867796.5257179737 0.1838251203 0.1209348079 0.1838260889 0.0056608970 0.0092390000 1297057541 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2338 1311867796.5578780174 0.1838275492 0.1209617081 0.1838275492 0.0056597812 0.0095310000 1297137325 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2339 1311867796.5898189545 0.1838305891 0.1209885867 0.1838305891 0.0056591604 0.0102920000 1297217109 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2340 1311867796.6258490086 0.1837627441 0.1210154132 0.1838305891 0.0056584373 0.0099660000 1297297005 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2341 1311867796.6581339836 0.1836971045 0.1210421888 0.1838305891 0.0056585460 0.0097380000 1297376733 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2342 1311867796.6900939941 0.1837122291 0.1210689480 0.1838305891 0.0056608131 0.0107750000 1297456461 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2343 1311867796.7258830070 0.1836046576 0.1210956385 0.1838305891 0.0056611091 0.0115150000 1297536357 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2344 1311867796.7578020096 0.1836558878 0.1211223280 0.1838305891 0.0056605059 0.0101840000 1297616085 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2345 1311867796.7898418903 0.1837909967 0.1211490524 0.1838305891 0.0056608887 0.0102670000 1297695869 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2346 1311867796.8258030415 0.1838166416 0.1211757649 0.1838305891 0.0056623455 0.0100520000 1297775821 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2347 1311867796.8578920364 0.1838238239 0.1212024577 0.1838305891 0.0056623743 0.0098320000 1297855549 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2348 1311867796.8898460865 0.1838223040 0.1212291272 0.1838305891 0.0056625221 0.0097180000 1297935333 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2349 1311867796.9258139133 0.1837628782 0.1212557486 0.1838305891 0.0056649850 0.0100310000 1298015173 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2350 1311867796.9577209949 0.1834715456 0.1212822234 0.1838305891 0.0056667578 0.0098560000 1298095013 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2351 1311867796.9899380207 0.1833062619 0.1213086054 0.1838305891 0.0056679859 0.0099580000 1298174741 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2352 1311867797.0258600712 0.1830319166 0.1213348483 0.1838305891 0.0056718870 0.0099800000 1298254693 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2353 1311867797.0580129623 0.1827486008 0.1213609485 0.1838305891 0.0056736062 0.0094770000 1298334365 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2354 1311867797.0898609161 0.1826228350 0.1213869731 0.1838305891 0.0056740605 0.0094140000 1298414149 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2355 1311867797.1257379055 0.1825996786 0.1214129657 0.1838305891 0.0056747289 0.0094070000 1298494045 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2356 1311867797.1580839157 0.1826397628 0.1214389533 0.1838305891 0.0056747401 0.0102920000 1298573829 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2357 1311867797.1897549629 0.1827513278 0.1214649662 0.1838305891 0.0056743613 0.0101780000 1298653613 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2358 1311867797.2257120609 0.1831140816 0.1214911109 0.1838305891 0.0056740645 0.0098240000 1298733509 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2359 1311867797.2577331066 0.1832841784 0.1215173055 0.1838305891 0.0056743956 0.0097230000 1298813293 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2360 1311867797.2898819447 0.1834175140 0.1215435344 0.1838305891 0.0056735858 0.0097690000 1298893077 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2361 1311867797.3258180618 0.1834536642 0.1215697564 0.1838305891 0.0056733014 0.0101850000 1298972973 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2362 1311867797.3579130173 0.1834204644 0.1215959421 0.1838305891 0.0056729128 0.0098980000 1299052813 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2363 1311867797.3939859867 0.1833049059 0.1216220568 0.1838305891 0.0056721507 0.0103240000 1299132597 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2364 1311867797.4258830547 0.1833047271 0.1216481493 0.1838305891 0.0056714038 0.0094310000 1299212437 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2365 1311867797.4578499794 0.1833060235 0.1216742203 0.1838305891 0.0056715754 0.0101230000 1299292277 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2366 1311867797.4938659668 0.1833671182 0.1217002950 0.1838305891 0.0056712209 0.0099590000 1299372117 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2367 1311867797.5258159637 0.1833245754 0.1217263298 0.1838305891 0.0056702585 0.0102060000 1299451901 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2368 1311867797.5579218864 0.1832246035 0.1217523004 0.1838305891 0.0056695846 0.0102990000 1299531741 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2369 1311867797.5939559937 0.1830473989 0.1217781742 0.1838305891 0.0056685019 0.0107510000 1299611525 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2370 1311867797.6257979870 0.1828431338 0.1218039400 0.1838305891 0.0056673804 0.0114010000 1299691253 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2371 1311867797.6579689980 0.1824964136 0.1218295378 0.1838305891 0.0056665393 0.0106040000 1299771093 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2372 1311867797.6939730644 0.1821262538 0.1218549580 0.1838305891 0.0056655918 0.0107630000 1299850933 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2373 1311867797.7259180546 0.1818990856 0.1218802611 0.1838305891 0.0056647323 0.0109380000 1299930717 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2374 1311867797.7578690052 0.1815326661 0.1219053885 0.1838305891 0.0056638035 0.0121780000 1300010557 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2375 1311867797.7938480377 0.1810878813 0.1219303074 0.1838305891 0.0056631882 0.0136260000 1300090453 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2376 1311867797.8259179592 0.1807275862 0.1219550537 0.1838305891 0.0056627229 0.0117710000 1300170237 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2377 1311867797.8579020500 0.1802858114 0.1219795934 0.1838305891 0.0056625431 0.0098150000 1300250021 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2378 1311867797.8939969540 0.1798469722 0.1220039279 0.1838305891 0.0056628934 0.0096310000 1300329861 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2379 1311867797.9260621071 0.1794320494 0.1220280675 0.1838305891 0.0056625703 0.0094850000 1300409645 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2380 1311867797.9577860832 0.1792142689 0.1220520953 0.1838305891 0.0056619966 0.0096030000 1300489317 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2381 1311867797.9937651157 0.1787756383 0.1220759187 0.1838305891 0.0056619097 0.0094440000 1300569213 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2382 1311867798.0258378983 0.1783642322 0.1220995494 0.1838305891 0.0056613189 0.0095990000 1300648941 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2383 1311867798.0579879284 0.1779836714 0.1221230005 0.1838305891 0.0056608414 0.0114020000 1300728669 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2384 1311867798.0938220024 0.1774640232 0.1221462141 0.1838305891 0.0056619791 0.0105410000 1300808453 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2385 1311867798.1257269382 0.1771689206 0.1221692844 0.1838305891 0.0056619083 0.0091650000 1300888237 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2386 1311867798.1578359604 0.1769162863 0.1221922295 0.1838305891 0.0056617579 0.0111170000 1300967965 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2387 1311867798.1938939095 0.1767735332 0.1222150955 0.1838305891 0.0056624929 0.0103130000 1301047749 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2388 1311867798.2257430553 0.1765698493 0.1222378572 0.1838305891 0.0056621635 0.0107870000 1301127533 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2389 1311867798.2579889297 0.1765922457 0.1222606091 0.1838305891 0.0056617275 0.0094870000 1301207261 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2390 1311867798.2940459251 0.1765910536 0.1222833415 0.1838305891 0.0056624283 0.0103480000 1301287101 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2391 1311867798.3258190155 0.1764429212 0.1223059929 0.1838305891 0.0056621477 0.0093600000 1301366829 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2392 1311867798.3579709530 0.1765227765 0.1223286588 0.1838305891 0.0056617540 0.0092340000 1301446613 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2393 1311867798.3940150738 0.1765296906 0.1223513086 0.1838305891 0.0056616702 0.0096760000 1301526397 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2394 1311867798.4260239601 0.1765908152 0.1223739651 0.1838305891 0.0056615172 0.0125010000 1301606125 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2395 1311867798.4578919411 0.1765083224 0.1223965682 0.1838305891 0.0056619360 0.0109060000 1301685853 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2396 1311867798.4941060543 0.1765423417 0.1224191666 0.1838305891 0.0056627794 0.0099860000 1301765637 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2397 1311867798.5259160995 0.1764387637 0.1224417029 0.1838305891 0.0056633465 0.0101950000 1301845365 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2398 1311867798.5577950478 0.1764016598 0.1224642050 0.1838305891 0.0056639020 0.0094150000 1301925149 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2399 1311867798.5939269066 0.1765217185 0.1224867383 0.1838305891 0.0056656770 0.0097920000 1302004877 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2400 1311867798.6258640289 0.1766346395 0.1225092999 0.1838305891 0.0056660823 0.0105870000 1302084661 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2401 1311867798.6578669548 0.1769631505 0.1225319796 0.1838305891 0.0056657362 0.0098010000 1302164445 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2402 1311867798.6939270496 0.1772936732 0.1225547780 0.1838305891 0.0056666260 0.0098090000 1302244173 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2403 1311867798.7259819508 0.1776937544 0.1225777239 0.1838305891 0.0056666823 0.0096720000 1302323957 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2404 1311867798.7578179836 0.1781890988 0.1226008567 0.1838305891 0.0056659173 0.0100860000 1302403685 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2405 1311867798.7939379215 0.1786432415 0.1226241592 0.1838305891 0.0056668198 0.0190550000 1302483469 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2406 1311867798.8257730007 0.1791430116 0.1226476500 0.1838305891 0.0056668073 0.0123080000 1302563197 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2407 1311867798.8578929901 0.1800071746 0.1226714803 0.1838305891 0.0056664937 0.0114600000 1302642869 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2408 1311867798.8940010071 0.1807017773 0.1226955792 0.1838305891 0.0056678936 0.0119610000 1302722765 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2409 1311867798.9258499146 0.1813447028 0.1227199250 0.1838305891 0.0056679231 0.0138870000 1302802493 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2410 1311867798.9579989910 0.1820488721 0.1227445429 0.1838305891 0.0056673406 0.0110190000 1302882165 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2411 1311867798.9941298962 0.1825651675 0.1227693544 0.1838305891 0.0056670799 0.0119540000 1302962061 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2412 1311867799.0258600712 0.1829339266 0.1227942983 0.1838305891 0.0056672071 0.0125420000 1303041789 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2413 1311867799.0581009388 0.1833773553 0.1228194052 0.1838305891 0.0056673904 0.0101860000 1303121517 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2414 1311867799.0940489769 0.1836732775 0.1228446139 0.1838305891 0.0056682960 0.0101370000 1303201301 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2415 1311867799.1257948875 0.1840292960 0.1228699492 0.1840292960 0.0056673451 0.0101730000 1303281085 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2416 1311867799.1578299999 0.1844536811 0.1228954392 0.1844536811 0.0056688965 0.0101760000 1303360869 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2417 1311867799.1938738823 0.1847480834 0.1229210298 0.1847480834 0.0056694609 0.0096750000 1303440597 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2418 1311867799.2258329391 0.1852323562 0.1229467996 0.1852323562 0.0056720015 0.0099540000 1303520381 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2419 1311867799.2581300735 0.1856467277 0.1229727194 0.1856467277 0.0056722607 0.0098080000 1303600109 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2420 1311867799.2939600945 0.1860422045 0.1229987812 0.1860422045 0.0056720488 0.0092410000 1303679949 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2421 1311867799.3258109093 0.1864701062 0.1230249981 0.1864701062 0.0056722487 0.0092880000 1303759677 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2422 1311867799.3579640388 0.1868431121 0.1230513475 0.1868431121 0.0056724574 0.0099520000 1303839405 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2423 1311867799.3939919472 0.1873959452 0.1230779032 0.1873959452 0.0056718980 0.0095330000 1303919189 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2424 1311867799.4260330200 0.1881495267 0.1231047480 0.1881495267 0.0056715006 0.0102960000 1303998973 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2425 1311867799.4580349922 0.1885358691 0.1231317299 0.1885358691 0.0056704311 0.0101550000 1304078757 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2426 1311867799.4939210415 0.1892153174 0.1231589696 0.1892153174 0.0056693603 0.0099560000 1304158485 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2427 1311867799.5259048939 0.1897028387 0.1231863878 0.1897028387 0.0056688553 0.0095790000 1304238269 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2428 1311867799.5580170155 0.1903056204 0.1232140316 0.1903056204 0.0056689517 0.0096600000 1304317941 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2429 1311867799.5938620567 0.1910246015 0.1232419487 0.1910246015 0.0056689620 0.0098260000 1304397781 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2430 1311867799.6258950233 0.1915096641 0.1232700424 0.1915096641 0.0056688903 0.0096430000 1304477453 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2431 1311867799.6580491066 0.1921861321 0.1232983912 0.1921861321 0.0056692507 0.0097750000 1304557181 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2432 1311867799.6939530373 0.1927092373 0.1233269319 0.1927092373 0.0056687842 0.0097370000 1304637021 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2433 1311867799.7259850502 0.1930798739 0.1233556014 0.1930798739 0.0056691694 0.0094390000 1304716749 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2434 1311867799.7581601143 0.1932738125 0.1233843271 0.1932738125 0.0056704214 0.0094880000 1304796533 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2435 1311867799.7939600945 0.1937438101 0.1234132221 0.1937438101 0.0056714086 0.0095970000 1304876373 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2436 1311867799.8259379864 0.1941367686 0.1234422548 0.1941367686 0.0056713344 0.0097860000 1304956101 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2437 1311867799.8579449654 0.1947246045 0.1234715048 0.1947246045 0.0056717964 0.0093360000 1305035773 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2438 1311867799.8941950798 0.1953504384 0.1235009876 0.1953504384 0.0056719837 0.0095230000 1305115613 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2439 1311867799.9259500504 0.1957798451 0.1235306222 0.1957798451 0.0056724237 0.0094970000 1305195341 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2440 1311867799.9581398964 0.1963855475 0.1235604808 0.1963855475 0.0056741986 0.0096060000 1305275013 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2441 1311867799.9942190647 0.1969929934 0.1235905637 0.1969929934 0.0056736077 0.0097870000 1305354909 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2442 1311867800.0259680748 0.1974833757 0.1236208229 0.1974833757 0.0056725999 0.0097740000 1305434637 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2443 1311867800.0582239628 0.1982073039 0.1236513536 0.1982073039 0.0056741738 0.0097100000 1305514365 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2444 1311867800.0940160751 0.1988746375 0.1236821323 0.1988746375 0.0056751962 0.0106600000 1305594149 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2445 1311867800.1259961128 0.1993276328 0.1237130712 0.1993276328 0.0056746474 0.0112100000 1305673933 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2446 1311867800.1578819752 0.1998794079 0.1237442103 0.1998794079 0.0056749562 0.0105040000 1305753717 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2447 1311867800.1939439774 0.2004323602 0.1237755500 0.2004323602 0.0056751491 0.0110340000 1305833445 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2448 1311867800.2259080410 0.2008898556 0.1238070509 0.2008898556 0.0056741780 0.0106830000 1305913229 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2449 1311867800.2578909397 0.2015074342 0.1238387783 0.2015074342 0.0056731869 0.0135760000 1305992957 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2450 1311867800.2939751148 0.2020476013 0.1238707003 0.2020476013 0.0056734527 0.0140680000 1306072741 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2451 1311867800.3259909153 0.2024335712 0.1239027537 0.2024335712 0.0056728983 0.0141440000 1306152525 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2452 1311867800.3580579758 0.2030244470 0.1239350219 0.2030244470 0.0056720105 0.0139980000 1306232197 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2453 1311867800.3940989971 0.2037429363 0.1239675567 0.2037429363 0.0056719445 0.0114520000 1306311981 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2454 1311867800.4259541035 0.2042183578 0.1240002588 0.2042183578 0.0056717916 0.0111470000 1306391709 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2455 1311867800.4579350948 0.2046853453 0.1240331244 0.2046853453 0.0056714862 0.0112030000 1306471493 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2456 1311867800.4939179420 0.2053401768 0.1240662298 0.2053401768 0.0056707771 0.0147220000 1306551333 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2457 1311867800.5258879662 0.2056562752 0.1240994370 0.2056562752 0.0056710583 0.0093030000 1306631061 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2458 1311867800.5579628944 0.2062965184 0.1241328777 0.2062965184 0.0056723053 0.0119080000 1306710845 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2459 1311867800.5939168930 0.2067030668 0.1241664564 0.2067030668 0.0056733207 0.0111960000 1306790629 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2460 1311867800.6260008812 0.2071711272 0.1242001982 0.2071711272 0.0056736053 0.0113100000 1306870413 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2461 1311867800.6579699516 0.2073732316 0.1242339946 0.2073732316 0.0056750173 0.0109820000 1306950197 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2462 1311867800.6940650940 0.2078086138 0.1242679404 0.2078086138 0.0056755776 0.0111540000 1307029981 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2463 1311867800.7259409428 0.2078267783 0.1243018661 0.2078267783 0.0056786902 0.0117840000 1307109653 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2464 1311867800.7581260204 0.2080633640 0.1243358602 0.2080633640 0.0056805704 0.0115080000 1307189381 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2465 1311867800.7940680981 0.2083056271 0.1243699250 0.2083056271 0.0056808896 0.0140730000 1307269277 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2466 1311867800.8259088993 0.2084733695 0.1244040302 0.2084733695 0.0056800789 0.0104650000 1307348949 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2467 1311867800.8581299782 0.2087202221 0.1244382078 0.2087202221 0.0056797505 0.0127950000 1307428677 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2468 1311867800.8941609859 0.2090249956 0.1244724812 0.2090249956 0.0056797351 0.0106210000 1307508461 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2469 1311867800.9261739254 0.2090622634 0.1245067420 0.2090622634 0.0056790885 0.0101650000 1307588245 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2470 1311867800.9579699039 0.2092147171 0.1245410367 0.2092147171 0.0056789733 0.0131200000 1307667973 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2471 1311867800.9940919876 0.2091476172 0.1245752765 0.2092147171 0.0056801071 0.0117430000 1307747757 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2472 1311867801.0259308815 0.2089203745 0.1246093967 0.2092147171 0.0056820589 0.0115200000 1307827541 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2473 1311867801.0581130981 0.2088277936 0.1246434519 0.2092147171 0.0056819457 0.0107270000 1307907157 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2474 1311867801.0941119194 0.2087006420 0.1246774281 0.2092147171 0.0056819356 0.0105640000 1307986997 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2475 1311867801.1259539127 0.2085409611 0.1247113123 0.2092147171 0.0056821535 0.0110350000 1308066781 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2476 1311867801.1582169533 0.2084676623 0.1247451396 0.2092147171 0.0056820792 0.0100130000 1308146453 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2477 1311867801.1941869259 0.2080288529 0.1247787624 0.2092147171 0.0056829685 0.0100620000 1308226293 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2478 1311867801.2261569500 0.2077534944 0.1248122470 0.2092147171 0.0056842651 0.0099590000 1308305909 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2479 1311867801.2579801083 0.2074870020 0.1248455970 0.2092147171 0.0056841054 0.0099710000 1308385693 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2480 1311867801.2941079140 0.2071568519 0.1248787871 0.2092147171 0.0056846642 0.0101490000 1308465477 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2481 1311867801.3261170387 0.2070411593 0.1249119037 0.2092147171 0.0056839038 0.0105890000 1308545205 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2482 1311867801.3580710888 0.2070064545 0.1249449797 0.2092147171 0.0056833290 0.0105140000 1308624877 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2483 1311867801.3942770958 0.2070458978 0.1249780449 0.2092147171 0.0056831737 0.0106120000 1308704773 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2484 1311867801.4261291027 0.2070892304 0.1250111009 0.2092147171 0.0056823492 0.0097030000 1308784501 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2485 1311867801.4580080509 0.2071917802 0.1250441716 0.2092147171 0.0056826900 0.0100830000 1308864229 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2486 1311867801.4940950871 0.2077702135 0.1250774484 0.2092147171 0.0056824640 0.0102920000 1308944069 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2487 1311867801.5261139870 0.2084324062 0.1251109646 0.2092147171 0.0056813327 0.0100660000 1309023797 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2488 1311867801.5582149029 0.2087662816 0.1251445882 0.2092147171 0.0056823271 0.0101760000 1309103469 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2489 1311867801.5939800739 0.2090905607 0.1251783149 0.2092147171 0.0056822264 0.0101890000 1309183309 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2490 1311867801.6259629726 0.2095107585 0.1252121834 0.2095107585 0.0056817193 0.0102260000 1309263037 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2491 1311867801.6580629349 0.2094723433 0.1252460092 0.2095107585 0.0056883301 0.0106670000 1309342821 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2492 1311867801.6941089630 0.2094837129 0.1252798125 0.2095107585 0.0056967236 0.0101620000 1309422605 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2493 1311867801.7262461185 0.2097944021 0.1253137132 0.2097944021 0.0056958615 0.0100170000 1309502389 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2494 1311867801.7581400871 0.2102972716 0.1253477885 0.2102972716 0.0056968518 0.0101930000 1309582117 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2495 1311867801.7939970493 0.2101424336 0.1253817743 0.2102972716 0.0057003188 0.0099080000 1309661957 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2496 1311867801.8261160851 0.2101665139 0.1254157425 0.2102972716 0.0057176241 0.0103230000 1309741685 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2497 1311867801.8581449986 0.2104929090 0.1254498143 0.2104929090 0.0057167688 0.0109550000 1309821357 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2498 1311867801.8940670490 0.2107313871 0.1254839542 0.2107313871 0.0057216483 0.0104070000 1309901253 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2499 1311867801.9260439873 0.2110840380 0.1255182080 0.2110840380 0.0057280573 0.0101870000 1309980981 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2500 1311867801.9582340717 0.2117052972 0.1255526828 0.2117052972 0.0057326548 0.0102100000 1310060653 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2501 1311867801.9943699837 0.2129871249 0.1255876426 0.2129871249 0.0057371635 0.0107320000 1310140549 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2502 1311867802.0261719227 0.2131847590 0.1256226534 0.2131847590 0.0057499532 0.0104420000 1310220277 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2503 1311867802.0582029819 0.2147535533 0.1256582630 0.2147535533 0.0057548074 0.0106390000 1310299949 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2504 1311867802.0940859318 0.2155299932 0.1256941543 0.2155299932 0.0057713303 0.0108370000 1310379845 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2505 1311867802.1261429787 0.2169523835 0.1257305847 0.2169523835 0.0057779509 0.0118060000 1310459517 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2506 1311867802.1581521034 0.2184026092 0.1257675648 0.2184026092 0.0057851644 0.0109440000 1310539245 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2507 1311867802.1940410137 0.2192647159 0.1258048592 0.2192647159 0.0057925367 0.0109830000 1310619085 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2508 1311867802.2262279987 0.2199317366 0.1258423899 0.2199317366 0.0057964706 0.0109560000 1310698813 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2509 1311867802.2581429482 0.2207985669 0.1258802361 0.2207985669 0.0058065948 0.0111120000 1310778541 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2510 1311867802.2940258980 0.2214337736 0.1259183053 0.2214337736 0.0058112554 0.0104600000 1310858381 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2511 1311867802.3261590004 0.2217525542 0.1259564710 0.2217525542 0.0058389056 0.0103020000 1310938109 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2512 1311867802.3582010269 0.2220354378 0.1259947190 0.2220354378 0.0058442324 0.0098500000 1311017837 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2513 1311867802.3941359520 0.2225549519 0.1260331433 0.2225549519 0.0058538899 0.0100630000 1311097565 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2514 1311867802.4261798859 0.2227764279 0.1260716251 0.2227764279 0.0058664387 0.0101320000 1311177237 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2515 1311867802.4582099915 0.2232694626 0.1261102724 0.2232694626 0.0058788776 0.0103360000 1311256965 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2516 1311867802.4942219257 0.2243800312 0.1261493303 0.2243800312 0.0058863755 0.0104050000 1311336749 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2517 1311867802.5261681080 0.2246447504 0.1261884624 0.2246447504 0.0059098276 0.0133220000 1311416533 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2518 1311867802.5582580566 0.2256564200 0.1262279651 0.2256564200 0.0059185826 0.0179630000 1311419493 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2519 1311867802.5941689014 0.2274018973 0.1262681295 0.2274018973 0.0059270156 0.0141970000 1311576045 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2520 1311867802.6260979176 0.2284368426 0.1263086726 0.2284368426 0.0059317668 0.0207470000 1311579005 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2521 1311867802.6581749916 0.2298817933 0.1263497567 0.2298817933 0.0059360348 0.0227450000 1311581853 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2522 1311867802.6942789555 0.2311834991 0.1263913244 0.2311834991 0.0059380612 0.0210810000 1311661693 0 402718720 -0.1293978989 -0.1740829647 -0.0086263819 2523 1311867802.7262399197 0.1772588789 0.1264114860 0.2311834991 0.0346905273 0.0211100000 1311741365 0 402718720 -0.0649776086 -0.1449671835 -0.0384304523 2524 1311867802.7581510544 0.1796746403 0.1264325887 0.2311834991 0.0346837496 0.0077530000 1304117189 0 402718720 -0.0669677779 -0.1463520676 -0.0413589142 2525 1311867802.7943420410 0.1827292442 0.1264548844 0.2311834991 0.0346770654 0.0501610000 1304120389 0 402718720 -0.0686874539 -0.1481243819 -0.0424034558 2526 1311867802.8263640404 0.1852247715 0.1264781504 0.2311834991 0.0346704129 0.0510130000 1304123589 0 402718720 -0.0711236820 -0.1491088718 -0.0409116782 2527 1311867802.8581280708 0.1874559224 0.1265022809 0.2311834991 0.0346637494 0.0331540000 1304126677 0 402718720 -0.0723037571 -0.1503453255 -0.0408616662 2528 1311867802.8941819668 0.1891916394 0.1265270789 0.2311834991 0.0346569409 0.0604240000 1304129933 0 402718720 -0.0726402923 -0.1513908952 -0.0415665917 2529 1311867802.9261701107 0.1918535978 0.1265529098 0.2311834991 0.0346600958 0.0315440000 1304133077 0 402718720 -0.0640883446 -0.1598598212 -0.0759088248 2530 1311867802.9581580162 0.1928340197 0.1265791079 0.2311834991 0.0346535515 0.0298420000 1304136165 0 402718720 -0.0624122806 -0.1613174677 -0.0806393772 2531 1311867802.9941079617 0.1940314472 0.1266057584 0.2311834991 0.0346471723 0.0268050000 1304139421 0 402718720 -0.0605518036 -0.1624513417 -0.0845445395 2532 1311867803.0261418819 0.1948159337 0.1266326976 0.2311834991 0.0346405282 0.0262370000 1304142621 0 402718720 -0.0598468594 -0.1632140577 -0.0888688713 2533 1311867803.0580990314 0.1957385242 0.1266599798 0.2311834991 0.0346338322 0.0254540000 1304145709 0 402718720 -0.0578914285 -0.1643045843 -0.0931251869 2534 1311867803.0942358971 0.1950906962 0.1266869848 0.2311834991 0.0346272499 0.0254590000 1304148965 0 402718720 -0.0566597283 -0.1638898104 -0.0952951014 2535 1311867803.1262869835 0.1947263628 0.1267138248 0.2311834991 0.0346205384 0.0243070000 1304152109 0 402718720 -0.0554416813 -0.1635518819 -0.0983631536 2536 1311867803.1581799984 0.1943903714 0.1267405112 0.2311834991 0.0346138060 0.0235390000 1304155309 0 402718720 -0.0548330620 -0.1632651687 -0.0996929035 2537 1311867803.1945989132 0.1937639117 0.1267669295 0.2311834991 0.0346070553 0.0241650000 1304158509 0 402718720 -0.0542677455 -0.1624363661 -0.1035339087 2538 1311867803.2262599468 0.1934007108 0.1267931840 0.2311834991 0.0346002795 0.0235810000 1304161653 0 402718720 -0.0540233739 -0.1620977372 -0.1056155488 2539 1311867803.2581820488 0.1936961859 0.1268195341 0.2311834991 0.0345935641 0.0241460000 1304164797 0 402718720 -0.0549491905 -0.1621244848 -0.1089450791 2540 1311867803.2941761017 0.1921763271 0.1268452651 0.2311834991 0.0345869209 0.0234050000 1304168053 0 402718720 -0.0546886735 -0.1612118334 -0.1095194593 2541 1311867803.3261129856 0.1896204501 0.1268699700 0.2311834991 0.0345805194 0.0518450000 1304171197 0 402718720 -0.0541692600 -0.1587019116 -0.1121508107 2542 1311867803.3581609726 0.1880312413 0.1268940303 0.2311834991 0.0345742558 0.0240110000 1304174285 0 402718720 -0.0532138050 -0.1567888856 -0.1157262549 2543 1311867803.3942410946 0.1859814972 0.1269172657 0.2311834991 0.0345676794 0.0237830000 1304177541 0 402718720 -0.0519088991 -0.1548643559 -0.1187257692 2544 1311867803.4260959625 0.1845987737 0.1269399392 0.2311834991 0.0345611622 0.0227780000 1304180685 0 402718720 -0.0516738445 -0.1534308046 -0.1192927212 2545 1311867803.4581840038 0.1832558960 0.1269620673 0.2311834991 0.0345545999 0.0228470000 1304183885 0 402718720 -0.0499055162 -0.1519560367 -0.1233120561 2546 1311867803.4941740036 0.1825480610 0.1269839000 0.2311834991 0.0345481500 0.0256720000 1304187085 0 402718720 -0.0448443219 -0.1511375755 -0.1305913478 2547 1311867803.5264060497 0.1828806847 0.1270058461 0.2311834991 0.0345415542 0.0221060000 1304190285 0 402718720 -0.0441928320 -0.1512844265 -0.1330015957 2548 1311867803.5581879616 0.1850260049 0.1270286170 0.2311834991 0.0345352262 0.0235860000 1304193373 0 402718720 -0.0435656048 -0.1523310989 -0.1401242912 2549 1311867803.5942509174 0.1856115907 0.1270515997 0.2311834991 0.0345292438 0.0222780000 1304196629 0 402718720 -0.0426350348 -0.1526898891 -0.1428655088 2550 1311867803.6262500286 0.1892342567 0.1270759851 0.2311834991 0.0345234257 0.0228750000 1304199829 0 402718720 -0.0405878834 -0.1538992524 -0.1533271670 2551 1311867803.6582310200 0.1898650378 0.1271005986 0.2311834991 0.0345171055 0.0314060000 1304412729 0 402718720 -0.0357679538 -0.1524381936 -0.1616922170 2552 1311867803.6942009926 0.1905833185 0.1271254742 0.2311834991 0.0345103814 0.0164960000 1304209481 0 402718720 -0.0354931653 -0.1524408162 -0.1627229154 2553 1311867803.7263579369 0.1918040961 0.1271508086 0.2311834991 0.0345036806 0.0163500000 1304212625 0 402718720 -0.0358142257 -0.1527910233 -0.1637256145 2554 1311867803.7584290504 0.1930761039 0.1271766212 0.2311834991 0.0344970369 0.0436310000 1304215713 0 402718720 -0.0354250595 -0.1529305428 -0.1648473591 2555 1311867803.7943320274 0.1942596138 0.1272028767 0.2311834991 0.0344903188 0.0222480000 1304218969 0 402718720 -0.0359267481 -0.1529724896 -0.1652806997 2556 1311867803.8262629509 0.1956421286 0.1272296527 0.2311834991 0.0344836847 0.0333210000 1304222113 0 402718720 -0.0350952074 -0.1532472223 -0.1665728092 2557 1311867803.8581910133 0.1967013478 0.1272568219 0.2311834991 0.0344772503 0.0379510000 1304225313 0 402718720 -0.0350113474 -0.1529591680 -0.1674958467 2558 1311867803.8942449093 0.1975556612 0.1272843038 0.2311834991 0.0344705820 0.0343870000 1304228513 0 402718720 -0.0358413942 -0.1528988481 -0.1670102179 2559 1311867803.9263370037 0.1985512972 0.1273121534 0.2311834991 0.0344639234 0.0406160000 1304231713 0 402718720 -0.0351851098 -0.1527439654 -0.1689994633 2560 1311867803.9582469463 0.1993769258 0.1273403037 0.2311834991 0.0344573630 0.0445700000 1304234857 0 402718720 -0.0350118726 -0.1526019573 -0.1696977317 2561 1311867803.9942619801 0.2000190914 0.1273686828 0.2311834991 0.0344506605 0.0393360000 1304238057 0 402718720 -0.0360946283 -0.1527874023 -0.1686939299 2562 1311867804.0261850357 0.2005020976 0.1273972282 0.2311834991 0.0344441200 0.0338390000 1304241201 0 402718720 -0.0375283174 -0.1534117758 -0.1669942141 2563 1311867804.0582160950 0.2015743554 0.1274261697 0.2311834991 0.0344374094 0.0355300000 1304244345 0 402718720 -0.0365403071 -0.1537343860 -0.1687354147 2564 1311867804.0942809582 0.2012282759 0.1274549537 0.2311834991 0.0344307751 0.0770600000 1304247545 0 402718720 -0.0372772440 -0.1531354785 -0.1690826416 2565 1311867804.1263329983 0.2012328953 0.1274837170 0.2311834991 0.0344240685 0.0431420000 1304250745 0 402718720 -0.0378052182 -0.1526364088 -0.1711965948 2566 1311867804.1581940651 0.2012928426 0.1275124813 0.2311834991 0.0344173912 0.0420290000 1304253889 0 402718720 -0.0387196355 -0.1530792266 -0.1702637374 2567 1311867804.1943790913 0.2014982253 0.1275413032 0.2311834991 0.0344107568 0.0455090000 1304257145 0 402718720 -0.0405371152 -0.1538804919 -0.1689433753 2568 1311867804.2263710499 0.2014019340 0.1275700651 0.2311834991 0.0344042713 0.0434990000 1304260177 0 402718720 -0.0408583507 -0.1540466547 -0.1689200103 2569 1311867804.2581999302 0.2018611431 0.1275989834 0.2311834991 0.0343976181 0.0426670000 1304263321 0 402718720 -0.0406869575 -0.1542633027 -0.1697051078 2570 1311867804.2941830158 0.2021477073 0.1276279907 0.2311834991 0.0343910046 0.0466580000 1304266577 0 402718720 -0.0412330069 -0.1544200033 -0.1697228849 2571 1311867804.3262369633 0.2019627988 0.1276569035 0.2311834991 0.0343843397 0.0430680000 1304269665 0 402718720 -0.0419766121 -0.1543878615 -0.1690570563 2572 1311867804.3581929207 0.2028082013 0.1276861225 0.2311834991 0.0343776580 0.0437460000 1304272865 0 402718720 -0.0423006713 -0.1546138525 -0.1706469953 2573 1311867804.3942050934 0.2030100375 0.1277153972 0.2311834991 0.0343710420 0.0410260000 1304276065 0 402718720 -0.0426432975 -0.1546740234 -0.1708071679 2574 1311867804.4261929989 0.2033681124 0.1277447883 0.2311834991 0.0343644360 0.0406160000 1304279209 0 402718720 -0.0435611829 -0.1550605446 -0.1705847532 2575 1311867804.4583320618 0.2037392408 0.1277743007 0.2311834991 0.0343577645 0.0714230000 1304282297 0 402718720 -0.0437421016 -0.1550809145 -0.1715089530 2576 1311867804.4941980839 0.2042422742 0.1278039855 0.2311834991 0.0343512025 0.0417780000 1304285553 0 402718720 -0.0448543355 -0.1557711363 -0.1703207940 2577 1311867804.5261759758 0.2046497017 0.1278338053 0.2311834991 0.0343447187 0.0411240000 1304288753 0 402718720 -0.0455603637 -0.1559607536 -0.1700215489 2578 1311867804.5583539009 0.2049430609 0.1278637158 0.2311834991 0.0343380853 0.0399560000 1304291897 0 402718720 -0.0448625535 -0.1555127203 -0.1722903401 2579 1311867804.5943310261 0.2052457929 0.1278937205 0.2311834991 0.0343314819 0.0394080000 1304295097 0 402718720 -0.0457478240 -0.1560254991 -0.1711252481 2580 1311867804.6261529922 0.2052899301 0.1279237191 0.2311834991 0.0343249126 0.0378670000 1304298297 0 402718720 -0.0456060395 -0.1560010016 -0.1709274948 2581 1311867804.6584999561 0.2064735591 0.1279541529 0.2311834991 0.0343183222 0.0372880000 1304301497 0 402718720 -0.0456531197 -0.1569774151 -0.1696651131 2582 1311867804.6942880154 0.2071607560 0.1279848294 0.2311834991 0.0343116785 0.0360930000 1304304641 0 402718720 -0.0454542078 -0.1574233025 -0.1685262471 2583 1311867804.7263500690 0.2078989893 0.1280157679 0.2311834991 0.0343050620 0.0357330000 1304307841 0 402718720 -0.0455746017 -0.1572100818 -0.1699367613 2584 1311867804.7582890987 0.2089323103 0.1280470823 0.2311834991 0.0342984246 0.0348920000 1304310873 0 402718720 -0.0451273322 -0.1573994160 -0.1699001342 2585 1311867804.7942790985 0.2089517564 0.1280783801 0.2311834991 0.0342918256 0.0336050000 1304314129 0 402718720 -0.0452299230 -0.1568700671 -0.1696270555 2586 1311867804.8264510632 0.2102613449 0.1281101600 0.2311834991 0.0342852431 0.0615220000 1304317273 0 402718720 -0.0461896434 -0.1573488563 -0.1710928231 2587 1311867804.8582661152 0.2098300755 0.1281417487 0.2311834991 0.0342788718 0.0341190000 1304320473 0 402718720 -0.0453641079 -0.1560834944 -0.1713441163 2588 1311867804.8943779469 0.2096551955 0.1281732454 0.2311834991 0.0342723585 0.0337030000 1304323673 0 402718720 -0.0458065681 -0.1555065066 -0.1710147858 2589 1311867804.9262540340 0.2103214413 0.1282049751 0.2311834991 0.0342659021 0.0335340000 1304326817 0 402718720 -0.0452037975 -0.1557655185 -0.1719748825 2590 1311867804.9582290649 0.2094792575 0.1282363551 0.2311834991 0.0342592866 0.0343090000 1304330017 0 402718720 -0.0436885059 -0.1542158723 -0.1725287884 2591 1311867804.9942519665 0.2090266347 0.1282675363 0.2311834991 0.0342527017 0.0344790000 1304333217 0 402718720 -0.0442176051 -0.1535931081 -0.1716857255 2592 1311867805.0262200832 0.2080239058 0.1282983065 0.2311834991 0.0342461253 0.0351810000 1304336361 0 402718720 -0.0435828418 -0.1522635669 -0.1729281843 2593 1311867805.0583670139 0.2074374706 0.1283288268 0.2311834991 0.0342395364 0.0350160000 1304339505 0 402718720 -0.0436145104 -0.1511539072 -0.1733885407 2594 1311867805.0942080021 0.2074528337 0.1283593295 0.2311834991 0.0342329574 0.0343690000 1304342761 0 402718720 -0.0435931943 -0.1509923488 -0.1734242588 2595 1311867805.1264340878 0.2072328627 0.1283897239 0.2311834991 0.0342264559 0.0338920000 1304345905 0 402718720 -0.0435031876 -0.1504710615 -0.1736283749 2596 1311867805.1584761143 0.2078163475 0.1284203197 0.2311834991 0.0342199610 0.0331650000 1304349049 0 402718720 -0.0421836376 -0.1506987363 -0.1741232425 2597 1311867805.1942939758 0.2083288282 0.1284510892 0.2311834991 0.0342136688 0.0329860000 1304352249 0 402718720 -0.0416477360 -0.1505554020 -0.1742684096 2598 1311867805.2264149189 0.2082385123 0.1284818003 0.2311834991 0.0342070950 0.1569730000 1312968517 0 402718720 -0.0413517319 -0.1501474977 -0.1738045812 2599 1311867805.2582869530 0.1916020960 0.1285060867 0.2311834991 0.0342029377 0.0168150000 1312972925 0 402718720 -0.0112895807 -0.1271562874 -0.1945042908 2600 1311867805.2943079472 0.1915097237 0.1285303189 0.2311834991 0.0341964067 0.0173940000 1312976181 0 402718720 -0.0109735494 -0.1269271523 -0.1938899904 2601 1311867805.3262410164 0.1916432679 0.1285545837 0.2311834991 0.0341898881 0.0170620000 1312979325 0 402718720 -0.0107969744 -0.1270395517 -0.1935223192 2602 1311867805.3583950996 0.1922474951 0.1285790622 0.2311834991 0.0341835784 0.0175190000 1312982525 0 402718720 -0.0102650682 -0.1271593869 -0.1943759918 2603 1311867805.3943939209 0.1928086877 0.1286037374 0.2311834991 0.0341770985 0.0175260000 1312985725 0 402718720 -0.0100869332 -0.1273964942 -0.1944039911 2604 1311867805.4262869358 0.1927780658 0.1286283819 0.2311834991 0.0341705373 0.0172880000 1312988869 0 402718720 -0.0096806791 -0.1269243211 -0.1942957640 2605 1311867805.4583311081 0.1930010617 0.1286530931 0.2311834991 0.0341642189 0.0208480000 1312992013 0 402718720 -0.0095140720 -0.1270497888 -0.1938147098 2606 1311867805.4943571091 0.1933897287 0.1286779345 0.2311834991 0.0341577793 0.0178220000 1312995325 0 402718720 -0.0096693691 -0.1270081550 -0.1937991083 2607 1311867805.5262510777 0.1935753822 0.1287028281 0.2311834991 0.0341513346 0.0179390000 1312998413 0 402718720 -0.0099253189 -0.1271009743 -0.1934206933 2608 1311867805.5582799911 0.1938392073 0.1287278037 0.2311834991 0.0341449039 0.0345810000 1313001557 0 402718720 -0.0091579705 -0.1273635477 -0.1933232844 2609 1311867805.5944809914 0.1938087791 0.1287527485 0.2311834991 0.0341385338 0.0437200000 1313004813 0 402718720 -0.0088635795 -0.1277208477 -0.1929727495 2610 1311867805.6262350082 0.1937381029 0.1287776471 0.2311834991 0.0341322682 0.0508960000 1313007957 0 402718720 -0.0082921805 -0.1277382225 -0.1933137625 2611 1311867805.6582720280 0.1934712231 0.1288024244 0.2311834991 0.0341262534 0.0502560000 1313011157 0 402718720 -0.0081841759 -0.1277119070 -0.1932594031 2612 1311867805.6942389011 0.1930873245 0.1288270357 0.2311834991 0.0341198950 0.0486580000 1313014357 0 402718720 -0.0081868861 -0.1275126487 -0.1933357716 2613 1311867805.7263278961 0.1932496876 0.1288516904 0.2311834991 0.0341135402 0.0862850000 1313017557 0 402718720 -0.0077785198 -0.1275436282 -0.1936632842 2614 1311867805.7582681179 0.1930683404 0.1288762568 0.2311834991 0.0341071414 0.0475850000 1313020757 0 402718720 -0.0078233592 -0.1275763959 -0.1937321872 2615 1311867805.7943770885 0.1934520900 0.1289009512 0.2311834991 0.0341007367 0.0466330000 1313023901 0 402718720 -0.0078300303 -0.1277595609 -0.1940892786 2616 1311867805.8263409138 0.1932594031 0.1289255531 0.2311834991 0.0340946803 0.0442940000 1313027101 0 402718720 -0.0076792417 -0.1275887191 -0.1938339025 2617 1311867805.8582279682 0.1927637458 0.1289499467 0.2311834991 0.0340882652 0.0447810000 1313030133 0 402718720 -0.0077601178 -0.1271672696 -0.1936557740 2618 1311867805.8943729401 0.1935163289 0.1289746092 0.2311834991 0.0340819194 0.0440700000 1313033389 0 402718720 -0.0076212492 -0.1281496584 -0.1933778226 2619 1311867805.9263739586 0.1935839355 0.1289992787 0.2311834991 0.0340763413 0.0430580000 1313036589 0 402718720 -0.0076398947 -0.1283032298 -0.1937419772 2620 1311867805.9582509995 0.1930034906 0.1290237078 0.2311834991 0.0340700059 0.0429930000 1313039789 0 402718720 -0.0074783615 -0.1275704950 -0.1941972077 2621 1311867805.9945139885 0.1924654245 0.1290479129 0.2311834991 0.0340637314 0.0421640000 1313042933 0 402718720 -0.0075317444 -0.1272438020 -0.1938448995 2622 1311867806.0263969898 0.1934353113 0.1290724695 0.2311834991 0.0340573815 0.0401140000 1313046133 0 402718720 -0.0074064978 -0.1282431632 -0.1940213889 2623 1311867806.0583610535 0.1937872171 0.1290971416 0.2311834991 0.0340509875 0.0388980000 1313049333 0 402718720 -0.0071128411 -0.1283948570 -0.1942500621 2624 1311867806.0942509174 0.1933168918 0.1291216156 0.2311834991 0.0340453685 0.0760560000 1313052421 0 402718720 -0.0073237680 -0.1275534928 -0.1942851096 2625 1311867806.1263270378 0.1932510436 0.1291460458 0.2311834991 0.0340388997 0.0389130000 1313055621 0 402718720 -0.0068717496 -0.1272599399 -0.1942912042 2626 1311867806.1584138870 0.1937575340 0.1291706504 0.2311834991 0.0340325493 0.0378630000 1313058821 0 402718720 -0.0069587179 -0.1267982572 -0.1953085363 2627 1311867806.1945190430 0.1945615411 0.1291955422 0.2311834991 0.0340261616 0.0393850000 1313061965 0 402718720 -0.0059705917 -0.1270716935 -0.1953094602 2628 1311867806.2264339924 0.1953115463 0.1292207005 0.2311834991 0.0340197721 0.0378140000 1313065165 0 402718720 -0.0057198382 -0.1275342405 -0.1949723810 2629 1311867806.2584409714 0.1963824183 0.1292462470 0.2311834991 0.0340133167 0.0382830000 1313068365 0 402718720 -0.0060855537 -0.1276330650 -0.1955468953 2630 1311867806.2943649292 0.1970701814 0.1292720356 0.2311834991 0.0340068520 0.0378230000 1313071509 0 402718720 -0.0051026153 -0.1278595775 -0.1952840090 2631 1311867806.3262739182 0.1972569972 0.1292978755 0.2311834991 0.0340004720 0.0376380000 1313074709 0 402718720 -0.0049935025 -0.1277338266 -0.1952696592 2632 1311867806.3589589596 0.1979982853 0.1293239775 0.2311834991 0.0339940712 0.0366030000 1313077909 0 402718720 -0.0055453107 -0.1274728179 -0.1960206777 2633 1311867806.3944439888 0.1988984644 0.1293504015 0.2311834991 0.0339884673 0.0387110000 1313081053 0 402718720 -0.0042029978 -0.1281058341 -0.1956790090 2634 1311867806.4264400005 0.1987677068 0.1293767559 0.2311834991 0.0339822606 0.0362210000 1313084253 0 402718720 -0.0023039274 -0.1279597878 -0.1960405707 2635 1311867806.4583940506 0.1996612102 0.1294034293 0.2311834991 0.0339762681 0.0727950000 1313087341 0 402718720 -0.0038033514 -0.1288186610 -0.1958595067 2636 1311867806.4945209026 0.1997594386 0.1294301197 0.2311834991 0.0339698277 0.0375290000 1313090597 0 402718720 -0.0032498077 -0.1290479153 -0.1958131641 2637 1311867806.5264298916 0.2002450377 0.1294569741 0.2311834991 0.0339635363 0.0363190000 1313093797 0 402718720 -0.0020025175 -0.1294906288 -0.1963277161 2638 1311867806.5625119209 0.2002209276 0.1294837989 0.2311834991 0.0339571665 0.0368330000 1313097053 0 402718720 -0.0029384221 -0.1284850389 -0.1974933445 2639 1311867806.5945649147 0.2001195103 0.1295105650 0.2311834991 0.0339509591 0.0350150000 1313100141 0 402718720 -0.0013549892 -0.1281647235 -0.1974267811 2640 1311867806.6264998913 0.2011059374 0.1295376845 0.2311834991 0.0339445362 0.0370160000 1313103341 0 402718720 -0.0017025275 -0.1291456372 -0.1967357248 2641 1311867806.6623420715 0.2012446225 0.1295648359 0.2311834991 0.0339381909 0.0357130000 1313106597 0 402718720 -0.0029966454 -0.1281867623 -0.1970165819 2642 1311867806.6944510937 0.2010227144 0.1295918828 0.2311834991 0.0339317802 0.0341270000 1313109741 0 402718720 -0.0015496762 -0.1270628870 -0.1971919835 2643 1311867806.7264649868 0.2018357366 0.1296192168 0.2311834991 0.0339254082 0.0350950000 1313112885 0 402718720 -0.0021807214 -0.1278788596 -0.1959913671 2644 1311867806.7624690533 0.2013254762 0.1296463372 0.2311834991 0.0339191693 0.0334040000 1313116085 0 402718720 -0.0015116489 -0.1259072572 -0.1966663003 2645 1311867806.7944209576 0.2014841139 0.1296734970 0.2311834991 0.0339127752 0.0331750000 1313119229 0 402718720 -0.0005610050 -0.1256429702 -0.1963288337 2646 1311867806.8266720772 0.2032029778 0.1297012860 0.2311834991 0.0339063675 0.0354990000 1313122429 0 402718720 -0.0006836636 -0.1277028322 -0.1954048723 2647 1311867806.8626179695 0.2033352554 0.1297291039 0.2311834991 0.0339000799 0.0671000000 1313125685 0 402718720 -0.0015673972 -0.1274283230 -0.1954250485 2648 1311867806.8944139481 0.2028184980 0.1297567056 0.2311834991 0.0338936992 0.0355370000 1313128717 0 402718720 -0.0022032857 -0.1271239072 -0.1943792999 2649 1311867806.9264690876 0.2031374127 0.1297844069 0.2311834991 0.0338873319 0.0333140000 1313131917 0 402718720 -0.0006720253 -0.1275617182 -0.1949112713 2650 1311867806.9624679089 0.2031345665 0.1298120862 0.2311834991 0.0338809699 0.0352450000 1313135173 0 402718720 -0.0007357035 -0.1272097528 -0.1955613494 2651 1311867806.9944870472 0.2031415105 0.1298397472 0.2311834991 0.0338745901 0.0366020000 1313138261 0 402718720 -0.0004206100 -0.1271900982 -0.1947651207 2652 1311867807.0264599323 0.2033496052 0.1298674659 0.2311834991 0.0338682153 0.0346270000 1313141461 0 402718720 0.0010013982 -0.1277930886 -0.1942418367 2653 1311867807.0625779629 0.2035402358 0.1298952355 0.2311834991 0.0338624850 0.0344890000 1313144717 0 402718720 0.0028327040 -0.1276810616 -0.1942473054 2654 1311867807.0944859982 0.2034629136 0.1299229550 0.2311834991 0.0338564429 0.0338090000 1313147805 0 402718720 0.0017871876 -0.1264626086 -0.1949988604 2655 1311867807.1265521049 0.2046483457 0.1299511002 0.2311834991 0.0338503572 0.0345690000 1313151005 0 402718720 0.0025312575 -0.1278965175 -0.1944579929 2656 1311867807.1625890732 0.2034175843 0.1299787608 0.2311834991 0.0338441158 0.0332130000 1313154261 0 402718720 0.0036303229 -0.1257301867 -0.1954068393 2657 1311867807.1944069862 0.2040008605 0.1300066200 0.2311834991 0.0338381320 0.0326130000 1313157349 0 402718720 0.0018965546 -0.1248835549 -0.1964417398 2658 1311867807.2264180183 0.2044183612 0.1300346154 0.2311834991 0.0338318358 0.0316460000 1313160437 0 402718720 0.0014653072 -0.1255762130 -0.1953290850 2659 1311867807.2626419067 0.2049705535 0.1300627974 0.2311834991 0.0338255799 0.0699080000 1313163693 0 402718720 0.0038072639 -0.1268916130 -0.1946037859 2660 1311867807.2943201065 0.2047334909 0.1300908691 0.2311834991 0.0338193744 0.0333720000 1313166837 0 402718720 0.0044034431 -0.1265790313 -0.1953321695 2661 1311867807.3264720440 0.2046693563 0.1301188956 0.2311834991 0.0338131000 0.0337220000 1313169925 0 402718720 0.0050192443 -0.1267165542 -0.1951238513 2662 1311867807.3626739979 0.2052490562 0.1301471188 0.2311834991 0.0338069257 0.0350610000 1313173237 0 402718720 0.0058685760 -0.1280967891 -0.1946784258 2663 1311867807.3944509029 0.2042542845 0.1301749473 0.2311834991 0.0338008193 0.0341820000 1313176325 0 402718720 0.0066599096 -0.1270015687 -0.1952969134 2664 1311867807.4268391132 0.2044659257 0.1302028343 0.2311834991 0.0337945965 0.0329600000 1313179525 0 402718720 0.0061134920 -0.1265883893 -0.1965605468 2665 1311867807.4623839855 0.2044573873 0.1302306971 0.2311834991 0.0337882725 0.0335150000 1313182781 0 402718720 0.0062974258 -0.1266877204 -0.1965083182 2666 1311867807.4945991039 0.2042259425 0.1302584523 0.2311834991 0.0337821688 0.0342690000 1313185869 0 402718720 0.0072381366 -0.1275845021 -0.1955125928 2667 1311867807.5265519619 0.2046553344 0.1302863476 0.2311834991 0.0337760270 0.0328190000 1313189013 0 402718720 0.0076732789 -0.1277854294 -0.1968674362 2668 1311867807.5625879765 0.2038695663 0.1303139276 0.2311834991 0.0337703114 0.0329420000 1313192269 0 402718720 0.0082844310 -0.1279076636 -0.1965285093 2669 1311867807.5944519043 0.2032373548 0.1303412499 0.2311834991 0.0337642496 0.0329010000 1313195357 0 402718720 0.0084333308 -0.1276099980 -0.1971812546 2670 1311867807.6264500618 0.2026787996 0.1303683426 0.2311834991 0.0337590373 0.0324970000 1313198501 0 402718720 0.0075763850 -0.1276608407 -0.1974117309 2671 1311867807.6623620987 0.2020646483 0.1303951851 0.2311834991 0.0337527874 0.0671530000 1313201813 0 402718720 0.0080979215 -0.1276040673 -0.1977375746 2672 1311867807.6944880486 0.2026512027 0.1304222271 0.2311834991 0.0337469841 0.0347940000 1313204957 0 402718720 0.0106450105 -0.1289947629 -0.1982477307 2673 1311867807.7264440060 0.2018619180 0.1304489535 0.2311834991 0.0337412852 0.0330390000 1313208045 0 402718720 0.0106288902 -0.1279341131 -0.1993397921 2674 1311867807.7623479366 0.2006194592 0.1304751952 0.2311834991 0.0337356462 0.0326610000 1313211357 0 402718720 0.0079941601 -0.1261752695 -0.1991643906 2675 1311867807.7944710255 0.2007988542 0.1305014845 0.2311834991 0.0337295372 0.0328590000 1313214445 0 402718720 0.0072993767 -0.1270611733 -0.1977407336 2676 1311867807.8266680241 0.2007504702 0.1305277360 0.2311834991 0.0337235643 0.0314200000 1313217645 0 402718720 0.0072446079 -0.1269214898 -0.1979378462 2677 1311867807.8625950813 0.2004382759 0.1305538512 0.2311834991 0.0337174835 0.0320830000 1313220845 0 402718720 0.0071776640 -0.1260720938 -0.1986217499 2678 1311867807.8945229053 0.1998947710 0.1305797440 0.2311834991 0.0337113037 0.0322460000 1313223933 0 402718720 0.0071859593 -0.1262415946 -0.1973159462 2679 1311867807.9266500473 0.2007924765 0.1306059526 0.2311834991 0.0337051354 0.0323450000 1313227077 0 402718720 0.0075040907 -0.1276293546 -0.1971994191 2680 1311867807.9625189304 0.2009119838 0.1306321862 0.2311834991 0.0336989806 0.0326850000 1313230333 0 402718720 0.0084167430 -0.1282241493 -0.1971401721 2681 1311867807.9944739342 0.2004820257 0.1306582398 0.2311834991 0.0336928043 0.0329470000 1313233421 0 402718720 0.0090971133 -0.1276790053 -0.1973162293 2682 1311867808.0264410973 0.1999712437 0.1306840836 0.2311834991 0.0336872554 0.0323590000 1313236565 0 402718720 0.0077155451 -0.1262325794 -0.1983563453 2683 1311867808.0625820160 0.2006853372 0.1307101743 0.2311834991 0.0336837602 0.0681060000 1313239877 0 402718720 0.0066180411 -0.1264329702 -0.1985763162 2684 1311867808.0948560238 0.2008897066 0.1307363216 0.2311834991 0.0336776355 0.0316740000 1313242965 0 402718720 0.0070417351 -0.1268396676 -0.1988995671 2685 1311867808.1269919872 0.2016472965 0.1307627317 0.2311834991 0.0336713766 0.0320900000 1313246165 0 402718720 0.0083803078 -0.1284099519 -0.1987933218 2686 1311867808.1625170708 0.2009829879 0.1307888747 0.2311834991 0.0336654174 0.0321380000 1313249365 0 402718720 0.0079236561 -0.1277049333 -0.1995992810 2687 1311867808.1947059631 0.2007860690 0.1308149250 0.2311834991 0.0336595214 0.0320100000 1313252453 0 402718720 0.0070878300 -0.1279766560 -0.1999492794 2688 1311867808.2265629768 0.2010336965 0.1308410481 0.2311834991 0.0336549709 0.0321240000 1313255653 0 402718720 0.0079494277 -0.1288922727 -0.2002876848 2689 1311867808.2627909184 0.2006149143 0.1308669960 0.2311834991 0.0336491945 0.0318870000 1313258965 0 402718720 0.0079396255 -0.1281438470 -0.2020923793 2690 1311867808.2945060730 0.2019647211 0.1308934264 0.2311834991 0.0336431930 0.0324270000 1313261997 0 402718720 0.0098917447 -0.1300661266 -0.2026612908 2691 1311867808.3264529705 0.2009862512 0.1309194735 0.2311834991 0.0336373091 0.0317940000 1313265197 0 402718720 0.0098469285 -0.1290639788 -0.2031461746 2692 1311867808.3625059128 0.2011452764 0.1309455603 0.2311834991 0.0336311943 0.0320670000 1313268453 0 402718720 0.0089815119 -0.1289897263 -0.2040188611 2693 1311867808.3944981098 0.2009340078 0.1309715494 0.2311834991 0.0336249583 0.0335240000 1313271541 0 402718720 0.0089373374 -0.1280192286 -0.2058717608 2694 1311867808.4268999100 0.2007268816 0.1309974422 0.2311834991 0.0336187519 0.0320220000 1313274741 0 402718720 0.0093018888 -0.1277466416 -0.2063274682 2695 1311867808.4625270367 0.2003961504 0.1310231931 0.2311834991 0.0336126701 0.0666190000 1313277997 0 402718720 0.0077239443 -0.1265274137 -0.2073094398 2696 1311867808.4945490360 0.2003399730 0.1310489041 0.2311834991 0.0336065090 0.0325040000 1313281085 0 402718720 0.0088209594 -0.1271706372 -0.2068256885 2697 1311867808.5265080929 0.2004914582 0.1310746522 0.2311834991 0.0336003205 0.0293450000 1313284229 0 402718720 0.0085701179 -0.1267405748 -0.2080150098 2698 1311867808.5624849796 0.2002567947 0.1311002942 0.2311834991 0.0335941033 0.0322700000 1313287541 0 402718720 0.0081824465 -0.1265786439 -0.2077295035 2699 1311867808.5946409702 0.2005996108 0.1311260442 0.2311834991 0.0335883089 0.0326660000 1313290629 0 402718720 0.0083631845 -0.1268330514 -0.2082115710 2700 1311867808.6265110970 0.2001457065 0.1311516071 0.2311834991 0.0335821221 0.0325490000 1313293829 0 402718720 0.0085637365 -0.1265076548 -0.2082957178 2701 1311867808.6624469757 0.2000615001 0.1311771198 0.2311834991 0.0335760543 0.0312460000 1313297085 0 402718720 0.0082259662 -0.1267525107 -0.2084824741 2702 1311867808.6943540573 0.1995287389 0.1312024165 0.2311834991 0.0335701646 0.0316730000 1313300173 0 402718720 0.0082599651 -0.1262514740 -0.2086461633 2703 1311867808.7266330719 0.2007668465 0.1312281525 0.2311834991 0.0335640483 0.0308010000 1313303373 0 402718720 0.0091031995 -0.1274760365 -0.2096865624 2704 1311867808.7625389099 0.2013527304 0.1312540861 0.2311834991 0.0335579570 0.0306340000 1313306629 0 402718720 0.0101193339 -0.1280253679 -0.2111970484 2705 1311867808.7944979668 0.1994096041 0.1312792822 0.2311834991 0.0335522991 0.0333890000 1313309773 0 402718720 0.0090859467 -0.1265322715 -0.2110766321 2706 1311867808.8265590668 0.2000015974 0.1313046785 0.2311834991 0.0335461111 0.0318220000 1313312861 0 402718720 0.0098572206 -0.1278461069 -0.2106603682 2707 1311867808.8625400066 0.2010259330 0.1313304344 0.2311834991 0.0335403643 0.0612940000 1313316173 0 402718720 0.0101910420 -0.1297425628 -0.2115850002 2708 1311867808.8946299553 0.1996225715 0.1313556531 0.2311834991 0.0335343467 0.0308950000 1313319261 0 402718720 0.0108669689 -0.1282243878 -0.2128690481 2709 1311867808.9266169071 0.1993210763 0.1313807418 0.2311834991 0.0335281855 0.0327410000 1313322461 0 402718720 0.0118100746 -0.1288316697 -0.2128952146 2710 1311867808.9624459743 0.2005249113 0.1314062563 0.2311834991 0.0335222539 0.0309050000 1313325717 0 402718720 0.0109805828 -0.1302634180 -0.2144444287 2711 1311867808.9945740700 0.1978935152 0.1314307813 0.2311834991 0.0335163765 0.0321100000 1313328805 0 402718720 0.0090561006 -0.1270524710 -0.2151546329 2712 1311867809.0265669823 0.1979889721 0.1314553234 0.2311834991 0.0335105105 0.0392800000 1313331949 0 402718720 0.0107209813 -0.1284114122 -0.2142687738 2713 1311867809.0625400543 0.1998155266 0.1314805207 0.2311834991 0.0335046723 0.0303480000 1313335261 0 402718720 0.0113815051 -0.1302637309 -0.2161457241 2714 1311867809.0944750309 0.1981285214 0.1315050778 0.2311834991 0.0334987339 0.0314610000 1313338349 0 402718720 0.0099171093 -0.1275886893 -0.2170971483 2715 1311867809.1267240047 0.1990118325 0.1315299421 0.2311834991 0.0334926388 0.0296290000 1313341549 0 402718720 0.0092669539 -0.1287678629 -0.2170855403 2716 1311867809.1626551151 0.1992439777 0.1315548737 0.2311834991 0.0334865129 0.0293690000 1313344805 0 402718720 0.0104221897 -0.1288538426 -0.2179346979 2717 1311867809.1946709156 0.1985561848 0.1315795337 0.2311834991 0.0334805115 0.0313320000 1313347893 0 402718720 0.0108578280 -0.1277365088 -0.2184838653 2718 1311867809.2266631126 0.1985764652 0.1316041831 0.2311834991 0.0334752446 0.0278650000 1313351093 0 402718720 0.0095212469 -0.1275274307 -0.2184071690 2719 1311867809.2625770569 0.1987049729 0.1316288615 0.2311834991 0.0334690882 0.0677500000 1313354349 0 402718720 0.0108607952 -0.1275895238 -0.2185226381 2720 1311867809.2945480347 0.1988763660 0.1316535849 0.2311834991 0.0334629638 0.0315950000 1313357381 0 402718720 0.0111031961 -0.1273600906 -0.2191947252 2721 1311867809.3265650272 0.1989315748 0.1316783103 0.2311834991 0.0334569537 0.0308260000 1313360525 0 402718720 0.0114669800 -0.1272526681 -0.2194540501 2722 1311867809.3626379967 0.1996193826 0.1317032703 0.2311834991 0.0334508776 0.0326620000 1313363781 0 402718720 0.0121867443 -0.1280406415 -0.2196906805 2723 1311867809.3946878910 0.1998212487 0.1317282861 0.2311834991 0.0334451689 0.0323870000 1313366869 0 402718720 0.0128622390 -0.1282268018 -0.2203487754 2724 1311867809.4265389442 0.2000226974 0.1317533575 0.2311834991 0.0334390665 0.0335190000 1313370069 0 402718720 0.0135931913 -0.1282208860 -0.2211403698 2725 1311867809.4625649452 0.2006033361 0.1317786235 0.2311834991 0.0334329946 0.0316960000 1313373325 0 402718720 0.0144934151 -0.1288929284 -0.2217474133 2726 1311867809.4945108891 0.2011961937 0.1318040885 0.2311834991 0.0334272324 0.0325010000 1313376413 0 402718720 0.0145992870 -0.1288101524 -0.2229163796 2727 1311867809.5267250538 0.2010172307 0.1318294692 0.2311834991 0.0334211755 0.0311350000 1313379613 0 402718720 0.0147017101 -0.1279923022 -0.2237936854 2728 1311867809.5626490116 0.2019594312 0.1318551767 0.2311834991 0.0334150716 0.0310420000 1313382869 0 402718720 0.0154460575 -0.1283175498 -0.2246671170 2729 1311867809.5945498943 0.2024010122 0.1318810271 0.2311834991 0.0334090191 0.0326360000 1313386013 0 402718720 0.0156331602 -0.1281643212 -0.2254458368 2730 1311867809.6266670227 0.2025581598 0.1319069162 0.2311834991 0.0334029333 0.0327980000 1313389157 0 402718720 0.0155557347 -0.1275940835 -0.2261489928 2731 1311867809.6627209187 0.2030245215 0.1319329570 0.2311834991 0.0333968209 0.0698060000 1313392413 0 402718720 0.0160775129 -0.1274411976 -0.2268160731 2732 1311867809.6945800781 0.2039501816 0.1319593177 0.2311834991 0.0333907174 0.0331430000 1313395501 0 402718720 0.0171404015 -0.1277216524 -0.2279386073 2733 1311867809.7266449928 0.2052898705 0.1319861492 0.2311834991 0.0333846420 0.0331440000 1313398701 0 402718720 0.0187298506 -0.1292704940 -0.2288942337 2734 1311867809.7625420094 0.2052315027 0.1320129397 0.2311834991 0.0333787450 0.0317870000 1313401957 0 402718720 0.0182112549 -0.1294812709 -0.2292500287 2735 1311867809.7946650982 0.2057151645 0.1320398875 0.2311834991 0.0333727836 0.0343250000 1313405045 0 402718720 0.0209973715 -0.1297643036 -0.2317614853 2736 1311867809.8269000053 0.2064718008 0.1320670922 0.2311834991 0.0333668326 0.0382590000 1313408245 0 402718720 0.0195549820 -0.1307560056 -0.2326660007 2737 1311867809.8626399040 0.2071081400 0.1320945094 0.2311834991 0.0333609978 0.0321730000 1313411445 0 402718720 0.0195185356 -0.1314425170 -0.2344906479 2738 1311867809.8947119713 0.2065670788 0.1321217091 0.2311834991 0.0333553305 0.0320430000 1313414533 0 402718720 0.0197169017 -0.1310926825 -0.2354561687 2739 1311867809.9269809723 0.2071738839 0.1321491104 0.2311834991 0.0333493611 0.0319020000 1313417733 0 402718720 0.0209093560 -0.1320266426 -0.2369203418 2740 1311867809.9650070667 0.2074978054 0.1321766099 0.2311834991 0.0333440455 0.0320860000 1313420989 0 402718720 0.0199114215 -0.1321787983 -0.2383340746 2741 1311867809.9945650101 0.2072752416 0.1322040081 0.2311834991 0.0333385295 0.0319540000 1313423965 0 402718720 0.0200981069 -0.1315227449 -0.2395896763 2742 1311867810.0266020298 0.2066755593 0.1322311677 0.2311834991 0.0333325381 0.0320760000 1313427109 0 402718720 0.0219411943 -0.1308435947 -0.2405012399 2743 1311867810.0628039837 0.2064058483 0.1322582092 0.2311834991 0.0333265371 0.0606110000 1313430365 0 402718720 0.0216842201 -0.1297801435 -0.2418324351 2744 1311867810.0946829319 0.2064488083 0.1322852466 0.2311834991 0.0333205350 0.0358230000 1313433397 0 402718720 0.0211551227 -0.1294024140 -0.2420688868 2745 1311867810.1264948845 0.2063972056 0.1323122454 0.2311834991 0.0333145538 0.0334860000 1313436597 0 402718720 0.0211616494 -0.1298890263 -0.2408790439 2746 1311867810.1626379490 0.2069598436 0.1323394296 0.2311834991 0.0333085380 0.0341330000 1313439853 0 402718720 0.0218288247 -0.1302873939 -0.2414752543 2747 1311867810.1956560612 0.2068709582 0.1323665615 0.2311834991 0.0333025532 0.0334380000 1313442997 0 402718720 0.0218556821 -0.1297045797 -0.2422605753 2748 1311867810.2268519402 0.2065837085 0.1323935692 0.2311834991 0.0332965530 0.0438230000 1313446141 0 402718720 0.0217787456 -0.1292957813 -0.2423156500 2749 1311867810.2626368999 0.2070318758 0.1324207203 0.2311834991 0.0332905311 0.0341140000 1313449397 0 402718720 0.0224423781 -0.1295053512 -0.2435730994 2750 1311867810.2946639061 0.2071665227 0.1324479006 0.2311834991 0.0332844807 0.0335950000 1313452485 0 402718720 0.0219382457 -0.1295760423 -0.2442063838 2751 1311867810.3266611099 0.2072122991 0.1324750778 0.2311834991 0.0332784460 0.0340050000 1313455685 0 402718720 0.0227519888 -0.1299804151 -0.2445968390 2752 1311867810.3625960350 0.2074349523 0.1325023161 0.2311834991 0.0332724773 0.0334990000 1313458941 0 402718720 0.0227613579 -0.1300720274 -0.2458537221 2753 1311867810.3945519924 0.2075995803 0.1325295944 0.2311834991 0.0332665076 0.0335050000 1313462029 0 402718720 0.0225760322 -0.1304828376 -0.2462554574 2754 1311867810.4267599583 0.2075663507 0.1325568409 0.2311834991 0.0332605330 0.0637060000 1313465229 0 402718720 0.0225609504 -0.1307055205 -0.2466111928 2755 1311867810.4629039764 0.2074740231 0.1325840341 0.2311834991 0.0332545355 0.0309860000 1313468485 0 402718720 0.0230993386 -0.1303046495 -0.2477892488 2756 1311867810.4947199821 0.2071368098 0.1326110852 0.2311834991 0.0332485156 0.0332300000 1313471517 0 402718720 0.0220863633 -0.1292911619 -0.2487543374 2757 1311867810.5266370773 0.2074315995 0.1326382235 0.2311834991 0.0332425194 0.0334340000 1313474717 0 402718720 0.0224977508 -0.1295450181 -0.2490067333 2758 1311867810.5627439022 0.2079366148 0.1326655253 0.2311834991 0.0332365144 0.0339970000 1313477973 0 402718720 0.0221702233 -0.1295230538 -0.2499440014 2759 1311867810.5945401192 0.2080526650 0.1326928494 0.2311834991 0.0332305298 0.0343680000 1313481061 0 402718720 0.0216797758 -0.1289215833 -0.2506662607 2760 1311867810.6266601086 0.2086897790 0.1327203845 0.2311834991 0.0332245372 0.0337460000 1313484261 0 402718720 0.0219124649 -0.1296651065 -0.2507816851 2761 1311867810.6626698971 0.2086240798 0.1327478759 0.2311834991 0.0332185372 0.0329990000 1313487517 0 402718720 0.0216091629 -0.1291316599 -0.2515204847 2762 1311867810.6945540905 0.2087609470 0.1327753969 0.2311834991 0.0332125297 0.0330680000 1313490605 0 402718720 0.0205246098 -0.1291154474 -0.2512212396 2763 1311867810.7265870571 0.2097427547 0.1328032534 0.2311834991 0.0332066379 0.0343620000 1313493805 0 402718720 0.0220170133 -0.1295091659 -0.2527844012 2764 1311867810.7626090050 0.2101503611 0.1328312372 0.2311834991 0.0332006808 0.0323670000 1313497061 0 402718720 0.0210390501 -0.1290670037 -0.2537403405 2765 1311867810.7945539951 0.2105703056 0.1328593525 0.2311834991 0.0331947578 0.0323310000 1313500205 0 402718720 0.0214317776 -0.1292774081 -0.2537225187 2766 1311867810.8267080784 0.2110454291 0.1328876194 0.2311834991 0.0331887885 0.0599030000 1313503349 0 402718720 0.0213665012 -0.1290119588 -0.2546633482 2767 1311867810.8625860214 0.2106601745 0.1329157266 0.2311834991 0.0331831293 0.0329870000 1313506549 0 402718720 0.0209035967 -0.1281277239 -0.2551983297 2768 1311867810.8945980072 0.2109397203 0.1329439144 0.2311834991 0.0331771570 0.0334000000 1313509749 0 402718720 0.0199171919 -0.1282173842 -0.2545810044 2769 1311867810.9266018867 0.2119206339 0.1329724362 0.2311834991 0.0331715621 0.0329080000 1313512837 0 402718720 0.0205532182 -0.1285952628 -0.2550308108 2770 1311867810.9626278877 0.2131353617 0.1330013759 0.2311834991 0.0331655920 0.0324890000 1313516149 0 402718720 0.0210445020 -0.1283272654 -0.2574534714 2771 1311867810.9946360588 0.2133564651 0.1330303744 0.2311834991 0.0331597314 0.0370200000 1313519181 0 402718720 0.0210097041 -0.1281566322 -0.2577388287 2772 1311867811.0265769958 0.2128102183 0.1330591550 0.2311834991 0.0331540661 0.0352870000 1313522381 0 402718720 0.0210920461 -0.1274375468 -0.2581778765 2773 1311867811.0628690720 0.2131636888 0.1330880424 0.2311834991 0.0331483379 0.0336220000 1313525693 0 402718720 0.0201433636 -0.1272630990 -0.2579075098 2774 1311867811.0947070122 0.2138053030 0.1331171402 0.2311834991 0.0331425439 0.0335120000 1313528781 0 402718720 0.0198081210 -0.1273187697 -0.2583745718 2775 1311867811.1265530586 0.2145613581 0.1331464894 0.2311834991 0.0331367427 0.0333750000 1313531925 0 402718720 0.0195461102 -0.1270437837 -0.2592547238 2776 1311867811.1627330780 0.2156638354 0.1331762147 0.2311834991 0.0331309812 0.0332480000 1313535181 0 402718720 0.0191922504 -0.1268090010 -0.2601260543 2777 1311867811.1946280003 0.2162715644 0.1332061374 0.2311834991 0.0331250594 0.0329970000 1313538269 0 402718720 0.0196242407 -0.1268860847 -0.2604529560 2778 1311867811.2266359329 0.2167826444 0.1332362225 0.2311834991 0.0331191328 0.0727590000 1313541469 0 402718720 0.0205417406 -0.1263858378 -0.2614879310 2779 1311867811.2627420425 0.2175078839 0.1332665470 0.2311834991 0.0331132038 0.0333540000 1313544725 0 402718720 0.0205786489 -0.1258477271 -0.2625930607 2780 1311867811.2948620319 0.2184407860 0.1332971852 0.2311834991 0.0331072882 0.0358210000 1313547813 0 402718720 0.0205055922 -0.1261886805 -0.2632145286 2781 1311867811.3268361092 0.2186434567 0.1333278743 0.2311834991 0.0331016205 0.0335500000 1313551013 0 402718720 0.0206205677 -0.1261975616 -0.2632582784 2782 1311867811.3627378941 0.2188432366 0.1333586131 0.2311834991 0.0330957550 0.0337900000 1313554269 0 402718720 0.0209394507 -0.1253780872 -0.2642020285 2783 1311867811.3946509361 0.2193447053 0.1333895100 0.2311834991 0.0330898341 0.0347300000 1313557357 0 402718720 0.0201043412 -0.1251860559 -0.2642627060 2784 1311867811.4266130924 0.2204665244 0.1334207876 0.2311834991 0.0330839092 0.0346740000 1313560557 0 402718720 0.0199288018 -0.1252691746 -0.2655803561 2785 1311867811.4629108906 0.2210815251 0.1334522637 0.2311834991 0.0330780359 0.0349130000 1313563869 0 402718720 0.0198018253 -0.1248526350 -0.2662105262 2786 1311867811.4946630001 0.2217577547 0.1334839598 0.2311834991 0.0330723269 0.0348880000 1313566901 0 402718720 0.0196720287 -0.1240810230 -0.2670239806 2787 1311867811.5266239643 0.2227824032 0.1335160009 0.2311834991 0.0330665138 0.0349030000 1313570101 0 402718720 0.0202920847 -0.1244159266 -0.2672144473 2788 1311867811.5627589226 0.2254374027 0.1335489713 0.2311834991 0.0330606604 0.0351760000 1313573357 0 402718720 0.0195001103 -0.1248791963 -0.2700195014 2789 1311867811.5947530270 0.2270017117 0.1335824789 0.2311834991 0.0330553715 0.0352610000 1313576445 0 402718720 0.0198428351 -0.1246517822 -0.2714759409 2790 1311867811.6266360283 0.2255663723 0.1336154480 0.2311834991 0.0330500183 0.0716990000 1313579645 0 402718720 0.0205740537 -0.1243441328 -0.2684355080 2791 1311867811.6628940105 0.2248019278 0.1336481196 0.2311834991 0.0330441737 0.0354480000 1313582901 0 402718720 0.0228123982 -0.1242252439 -0.2671783566 2792 1311867811.6946609020 0.2258890420 0.1336811572 0.2311834991 0.0330383741 0.0345220000 1313586045 0 402718720 0.0227898285 -0.1237036586 -0.2698548138 2793 1311867811.7266740799 0.2268257737 0.1337145065 0.2311834991 0.0330326080 0.0350630000 1313589189 0 402718720 0.0226456933 -0.1238805726 -0.2710285783 2794 1311867811.7628300190 0.2277223766 0.1337481529 0.2311834991 0.0330267258 0.0369460000 1313592445 0 402718720 0.0221713129 -0.1250848323 -0.2706407011 2795 1311867811.7946500778 0.2274892032 0.1337816917 0.2311834991 0.0330209372 0.0344390000 1313595533 0 402718720 0.0212766863 -0.1248330623 -0.2701574564 2796 1311867811.8267040253 0.2274354100 0.1338151873 0.2311834991 0.0330150644 0.0351690000 1313598733 0 402718720 0.0217598341 -0.1247348785 -0.2703182995 2797 1311867811.8627619743 0.2279391289 0.1338488390 0.2311834991 0.0330091711 0.0396750000 1313601989 0 402718720 0.0228435639 -0.1250104457 -0.2712616920 2798 1311867811.8976778984 0.2285097837 0.1338826707 0.2311834991 0.0330034212 0.0358720000 1313605245 0 402718720 0.0217642356 -0.1253145486 -0.2715665996 2799 1311867811.9267039299 0.2277092785 0.1339161922 0.2311834991 0.0329976142 0.0356770000 1313608221 0 402718720 0.0220872574 -0.1248375997 -0.2710773349 2800 1311867811.9658520222 0.2278828025 0.1339497517 0.2311834991 0.0329917272 0.0399150000 1313611477 0 402718720 0.0235271044 -0.1247494519 -0.2720698416 2801 1311867811.9947099686 0.2277437299 0.1339832376 0.2311834991 0.0329858497 0.0360420000 1313614509 0 402718720 0.0236154143 -0.1247263551 -0.2721717656 2802 1311867812.0267429352 0.2286290973 0.1340170155 0.2311834991 0.0329799823 0.0710380000 1313617709 0 402718720 0.0235578176 -0.1249737293 -0.2734332085 2803 1311867812.0627388954 0.2277842760 0.1340504680 0.2311834991 0.0329741525 0.0352060000 1313620965 0 402718720 0.0236219354 -0.1244476885 -0.2728514373 2804 1311867812.0948400497 0.2283976823 0.1340841154 0.2311834991 0.0329682993 0.0360810000 1313624053 0 402718720 0.0240277983 -0.1248418838 -0.2736104727 2805 1311867812.1267719269 0.2283850908 0.1341177342 0.2311834991 0.0329624486 0.0350540000 1313627253 0 402718720 0.0242115650 -0.1243218854 -0.2742280662 2806 1311867812.1629879475 0.2282081544 0.1341512661 0.2311834991 0.0329565883 0.0382160000 1313630509 0 402718720 0.0244544148 -0.1237821504 -0.2743564546 2807 1311867812.1948130131 0.2287268788 0.1341849589 0.2311834991 0.0329518440 0.0353650000 1313633597 0 402718720 0.0251384620 -0.1237965748 -0.2745259106 2808 1311867812.2269930840 0.2296047211 0.1342189403 0.2311834991 0.0329459927 0.0346280000 1313636797 0 402718720 0.0245960113 -0.1241227686 -0.2749291062 2809 1311867812.2627549171 0.2302230000 0.1342531176 0.2311834991 0.0329401564 0.0382870000 1313640053 0 402718720 0.0246677734 -0.1240360588 -0.2752407193 2810 1311867812.2947599888 0.2298211753 0.1342871276 0.2311834991 0.0329350589 0.0351080000 1313643141 0 402718720 0.0250330865 -0.1236421615 -0.2748841345 2811 1311867812.3267819881 0.2303043753 0.1343212853 0.2311834991 0.0329306763 0.0382180000 1313646341 0 402718720 0.0258288365 -0.1238155290 -0.2747272253 2812 1311867812.3629970551 0.2312863618 0.1343557679 0.2312863618 0.0329249459 0.0384560000 1313649653 0 402718720 0.0257974416 -0.1241059750 -0.2754656374 2813 1311867812.3946900368 0.2307752073 0.1343900442 0.2312863618 0.0329191894 0.0383410000 1313652797 0 402718720 0.0262310077 -0.1233327612 -0.2751775980 2814 1311867812.4270770550 0.2309723794 0.1344243663 0.2312863618 0.0329133437 0.0671890000 1313655941 0 402718720 0.0271328613 -0.1231315434 -0.2757912576 2815 1311867812.4628291130 0.2321998477 0.1344591001 0.2321998477 0.0329075539 0.0367640000 1313659141 0 402718720 0.0269732457 -0.1240705028 -0.2764873207 2816 1311867812.4947719574 0.2317110449 0.1344936355 0.2321998477 0.0329017724 0.0367160000 1313662117 0 402718720 0.0269710645 -0.1234773472 -0.2764329016 2817 1311867812.5267369747 0.2321879268 0.1345283158 0.2321998477 0.0328964578 0.0367920000 1313665261 0 402718720 0.0275971014 -0.1234364063 -0.2773217261 2818 1311867812.5628769398 0.2326906323 0.1345631498 0.2326906323 0.0328907022 0.0367100000 1313668517 0 402718720 0.0276127458 -0.1238595545 -0.2775436640 2819 1311867812.5951690674 0.2326824516 0.1345979563 0.2326906323 0.0328849430 0.0367590000 1313671661 0 402718720 0.0273882374 -0.1237689033 -0.2775488198 2820 1311867812.6267569065 0.2327779979 0.1346327719 0.2327779979 0.0328791923 0.0486190000 1313674805 0 402718720 0.0273209214 -0.1235485300 -0.2778542340 2821 1311867812.6626958847 0.2327754498 0.1346675619 0.2327779979 0.0328733855 0.0364450000 1313678061 0 402718720 0.0278667286 -0.1232563779 -0.2782461643 2822 1311867812.6947379112 0.2334992290 0.1347025838 0.2334992290 0.0328680070 0.0366300000 1313681149 0 402718720 0.0280983262 -0.1233133078 -0.2791737616 2823 1311867812.7267460823 0.2336837798 0.1347376462 0.2336837798 0.0328636128 0.0367030000 1313684349 0 402718720 0.0273381993 -0.1234663799 -0.2787748873 2824 1311867812.7626740932 0.2338391542 0.1347727388 0.2338391542 0.0328578804 0.0363340000 1313687605 0 402718720 0.0279645622 -0.1236360669 -0.2788287699 2825 1311867812.7947490215 0.2337877601 0.1348077883 0.2338391542 0.0328521801 0.0616030000 1313690693 0 402718720 0.0277312230 -0.1229812279 -0.2791172564 2826 1311867812.8267059326 0.2336614728 0.1348427684 0.2338391542 0.0328488060 0.0362770000 1313693893 0 402718720 0.0286202244 -0.1225277558 -0.2793348730 2827 1311867812.8627510071 0.2345020175 0.1348780211 0.2345020175 0.0328431422 0.0358030000 1313697205 0 402718720 0.0275027268 -0.1227209046 -0.2798707783 2828 1311867812.8947339058 0.2343807220 0.1349132059 0.2345020175 0.0328376550 0.0363820000 1313700237 0 402718720 0.0275890790 -0.1221630573 -0.2803111374 2829 1311867812.9268128872 0.2340905070 0.1349482633 0.2345020175 0.0328319166 0.0361940000 1313703437 0 402718720 0.0277391430 -0.1220234558 -0.2793597281 2830 1311867812.9628400803 0.2344532460 0.1349834240 0.2345020175 0.0328261335 0.0382820000 1313706693 0 402718720 0.0273332633 -0.1219943017 -0.2793785632 2831 1311867812.9949660301 0.2342988104 0.1350185054 0.2345020175 0.0328204014 0.0385600000 1313709781 0 402718720 0.0268049277 -0.1211802587 -0.2796103954 2832 1311867813.0268700123 0.2343399674 0.1350535766 0.2345020175 0.0328146180 0.0381940000 1313712981 0 402718720 0.0266414471 -0.1210514009 -0.2793898582 2833 1311867813.0629560947 0.2344805449 0.1350886726 0.2345020175 0.0328088308 0.0383290000 1313716181 0 402718720 0.0261802785 -0.1208811626 -0.2791896164 2834 1311867813.0947699547 0.2342693359 0.1351236693 0.2345020175 0.0328039952 0.0356530000 1313719325 0 402718720 0.0263053197 -0.1204289496 -0.2791478932 2835 1311867813.1269049644 0.2342066914 0.1351586192 0.2345020175 0.0327986588 0.0355100000 1313722525 0 402718720 0.0269242041 -0.1206848323 -0.2786378264 2836 1311867813.1627039909 0.2349968702 0.1351938231 0.2349968702 0.0327930420 0.0726650000 1313725781 0 402718720 0.0273922123 -0.1207526475 -0.2800117135 2837 1311867813.1948559284 0.2349498123 0.1352289856 0.2349968702 0.0327875463 0.0377910000 1313728869 0 402718720 0.0257089660 -0.1199803129 -0.2801579535 2838 1311867813.2270860672 0.2351392955 0.1352641901 0.2351392955 0.0327818031 0.0379380000 1313732013 0 402718720 0.0252415482 -0.1201673672 -0.2798640728 2839 1311867813.2627971172 0.2348117381 0.1352992544 0.2351392955 0.0327761149 0.0369740000 1313735269 0 402718720 0.0251755230 -0.1203253865 -0.2785232365 2840 1311867813.2947239876 0.2360884696 0.1353347435 0.2360884696 0.0327712286 0.0344760000 1313738357 0 402718720 0.0245354697 -0.1198792905 -0.2798764408 2841 1311867813.3267738819 0.2361724526 0.1353702373 0.2361724526 0.0327660021 0.0453740000 1313741557 0 402718720 0.0251381900 -0.1197619438 -0.2802931070 2842 1311867813.3628640175 0.2368896753 0.1354059584 0.2368896753 0.0327628031 0.0360170000 1313744813 0 402718720 0.0252403133 -0.1204516888 -0.2791715860 2843 1311867813.3951508999 0.2377285957 0.1354419495 0.2377285957 0.0327570956 0.0398990000 1313747957 0 402718720 0.0249644890 -0.1203588843 -0.2799444497 2844 1311867813.4268410206 0.2383873463 0.1354781469 0.2383873463 0.0327514927 0.0359310000 1313751045 0 402718720 0.0248960927 -0.1204317808 -0.2800910771 2845 1311867813.4628620148 0.2381788343 0.1355142455 0.2383873463 0.0327473734 0.0360990000 1313754301 0 402718720 0.0248725340 -0.1195403114 -0.2799989879 2846 1311867813.4947509766 0.2391635478 0.1355506648 0.2391635478 0.0327420543 0.0360860000 1313757445 0 402718720 0.0243224818 -0.1196249947 -0.2801387608 2847 1311867813.5268170834 0.2382320613 0.1355867313 0.2391635478 0.0327365223 0.0707390000 1313760589 0 402718720 0.0240351483 -0.1177743748 -0.2798406780 2848 1311867813.5628690720 0.2385371923 0.1356228797 0.2391635478 0.0327308708 0.0364290000 1313763789 0 402718720 0.0234088339 -0.1167936176 -0.2809896469 2849 1311867813.5950860977 0.2386524230 0.1356590431 0.2391635478 0.0327251429 0.0365970000 1313766933 0 402718720 0.0236361753 -0.1164340377 -0.2805967927 2850 1311867813.6267769337 0.2388143390 0.1356952379 0.2391635478 0.0327195546 0.0382390000 1313770077 0 402718720 0.0236881766 -0.1167064756 -0.2792187035 2851 1311867813.6631219387 0.2393594831 0.1357315986 0.2393594831 0.0327140123 0.0368660000 1313773389 0 402718720 0.0241383743 -0.1166006997 -0.2797032297 2852 1311867813.6950340271 0.2406561822 0.1357683884 0.2406561822 0.0327082998 0.0358040000 1313776477 0 402718720 0.0247485619 -0.1166151613 -0.2815191746 2853 1311867813.7269608974 0.2420039773 0.1358056248 0.2420039773 0.0327025992 0.0365060000 1313779621 0 402718720 0.0248809438 -0.1170511022 -0.2826755345 2854 1311867813.7629001141 0.2420245260 0.1358428424 0.2420245260 0.0326970075 0.0384850000 1313782877 0 402718720 0.0243717395 -0.1167934239 -0.2819387317 2855 1311867813.7949750423 0.2429045439 0.1358803421 0.2429045439 0.0326912900 0.0363340000 1313785965 0 402718720 0.0256434921 -0.1164041236 -0.2835038304 2856 1311867813.8268949986 0.2435599118 0.1359180451 0.2435599118 0.0326856013 0.1125870000 1322407893 0 402718720 0.0254920144 -0.1160178334 -0.2845380008 2857 1311867813.8628180027 0.2506762147 0.1359582124 0.2506762147 0.0326825844 0.0237780000 1322412413 0 402718720 0.0253965948 -0.1200596243 -0.2901692986 2858 1311867813.8948259354 0.2530358136 0.1359991773 0.2530358136 0.0326768750 0.0545230000 1322415557 0 402718720 0.0252154730 -0.1209129170 -0.2918986380 2859 1311867813.9268898964 0.2524637282 0.1360399134 0.2530358136 0.0326713849 0.0231780000 1322418757 0 402718720 0.0260058623 -0.1196214855 -0.2917639911 2860 1311867813.9627499580 0.2523406148 0.1360805780 0.2530358136 0.0326658356 0.0387500000 1322421957 0 402718720 0.0266757589 -0.1178463474 -0.2925678194 2861 1311867813.9948139191 0.2536991835 0.1361216890 0.2536991835 0.0326604167 0.0361060000 1322425101 0 402718720 0.0261733923 -0.1176442280 -0.2937571704 2862 1311867814.0269160271 0.2544717193 0.1361630412 0.2544717193 0.0326547709 0.0426310000 1322428245 0 402718720 0.0270703360 -0.1176697835 -0.2943326533 2863 1311867814.0629019737 0.2563102841 0.1362050067 0.2563102841 0.0326492078 0.0415980000 1322431501 0 402718720 0.0265161339 -0.1178103611 -0.2964640558 2864 1311867814.0952699184 0.2569453120 0.1362471646 0.2569453120 0.0326435251 0.0417200000 1322434645 0 402718720 0.0265160147 -0.1177891642 -0.2969044745 2865 1311867814.1268849373 0.2557110786 0.1362888623 0.2569453120 0.0326378857 0.0519580000 1322437789 0 402718720 0.0289623365 -0.1167978123 -0.2963627279 2866 1311867814.1627750397 0.2576504946 0.1363312076 0.2576504946 0.0326326779 0.0476370000 1322441101 0 402718720 0.0285488144 -0.1175951958 -0.2983581722 2867 1311867814.1948819160 0.2589280605 0.1363739690 0.2589280605 0.0326270617 0.0443320000 1322444189 0 402718720 0.0284502096 -0.1181951463 -0.2993697524 2868 1311867814.2271249294 0.2597814202 0.1364169981 0.2597814202 0.0326214018 0.0449990000 1322447389 0 402718720 0.0281414874 -0.1182492375 -0.3004003763 2869 1311867814.2627561092 0.2591605484 0.1364597808 0.2597814202 0.0326158238 0.0814750000 1322450645 0 402718720 0.0286409408 -0.1175422072 -0.3001704514 2870 1311867814.2949120998 0.2594724596 0.1365026424 0.2597814202 0.0326103364 0.0423200000 1322453733 0 402718720 0.0289052762 -0.1173786893 -0.3008325994 2871 1311867814.3270928860 0.2609372139 0.1365459843 0.2609372139 0.0326046952 0.0417870000 1322456933 0 402718720 0.0287213344 -0.1178910434 -0.3025262356 2872 1311867814.3628859520 0.2620670795 0.1365896894 0.2620670795 0.0325993319 0.0446030000 1322460189 0 402718720 0.0288200472 -0.1184675246 -0.3035073280 2873 1311867814.3949089050 0.2616003752 0.1366332016 0.2620670795 0.0325937272 0.0402970000 1322463333 0 402718720 0.0291128550 -0.1176492125 -0.3036081791 2874 1311867814.4272339344 0.2626661360 0.1366770544 0.2626661360 0.0325881126 0.0743270000 1322466477 0 402718720 0.0282231774 -0.1177805141 -0.3048591316 2875 1311867814.4628870487 0.2635613978 0.1367211881 0.2635613978 0.0325824903 0.0480670000 1322469733 0 402718720 0.0286542289 -0.1177597195 -0.3059146404 2876 1311867814.4950520992 0.2652845681 0.1367658903 0.2652845681 0.0325777968 0.0508480000 1322472821 0 402718720 0.0287042223 -0.1186644882 -0.3071068227 2877 1311867814.5277280807 0.2656300068 0.1368106814 0.2656300068 0.0325721860 0.0520410000 1322476021 0 402718720 0.0287279207 -0.1188222170 -0.3072039485 2878 1311867814.5629379749 0.2665107548 0.1368557474 0.2665107548 0.0325665298 0.0524900000 1322479277 0 402718720 0.0282002930 -0.1191237345 -0.3079323173 2879 1311867814.5951159000 0.2683939040 0.1369014363 0.2683939040 0.0325609545 0.0534360000 1322482309 0 402718720 0.0271609239 -0.1200325266 -0.3097375929 2880 1311867814.6272609234 0.2667580843 0.1369465254 0.2683939040 0.0325554843 0.0467350000 1322485509 0 402718720 0.0262527317 -0.1185062677 -0.3084947169 2881 1311867814.6628389359 0.2660939097 0.1369913527 0.2683939040 0.0325499506 0.0523900000 1322488765 0 402718720 0.0257546026 -0.1174037382 -0.3077366352 2882 1311867814.6950368881 0.2649419010 0.1370357491 0.2683939040 0.0325444011 0.0444860000 1322491853 0 402718720 0.0250005964 -0.1163678542 -0.3059238493 2883 1311867814.7274229527 0.2664452791 0.1370806362 0.2683939040 0.0325387608 0.0491370000 1322495053 0 402718720 0.0240521543 -0.1163958088 -0.3071107864 2884 1311867814.7628688812 0.2649249732 0.1371249650 0.2683939040 0.0325331887 0.0502080000 1322498309 0 402718720 0.0239227358 -0.1149690449 -0.3054920137 2885 1311867814.7949450016 0.2644467950 0.1371690974 0.2683939040 0.0325275602 0.0481320000 1322501397 0 402718720 0.0242807232 -0.1143919602 -0.3043245375 2886 1311867814.8269948959 0.2644300163 0.1372131933 0.2683939040 0.0325219303 0.0471650000 1322504541 0 402718720 0.0239754859 -0.1138815284 -0.3039267957 2887 1311867814.8630340099 0.2670210302 0.1372581562 0.2683939040 0.0325163874 0.0466350000 1322507853 0 402718720 0.0242404174 -0.1147652939 -0.3061180115 2888 1311867814.8948700428 0.2688905597 0.1373037353 0.2688905597 0.0325107952 0.0463430000 1322510941 0 402718720 0.0231836643 -0.1148678437 -0.3075595498 2889 1311867814.9269781113 0.2687174082 0.1373492229 0.2688905597 0.0325052493 0.0455270000 1322514085 0 402718720 0.0244089663 -0.1145087630 -0.3067467213 2890 1311867814.9628489017 0.2683897614 0.1373945657 0.2688905597 0.0324997023 0.0453300000 1322517397 0 402718720 0.0239025801 -0.1135867909 -0.3059883118 2891 1311867814.9968919754 0.2696136534 0.1374403004 0.2696136534 0.0324946508 0.0462330000 1322520541 0 402718720 0.0244913101 -0.1129883528 -0.3075529635 2892 1311867815.0277309418 0.2684536874 0.1374856024 0.2696136534 0.0324894583 0.0399880000 1322523629 0 402718720 0.0232776403 -0.1120510474 -0.3063136041 2893 1311867815.0628190041 0.2669049203 0.1375303377 0.2696136534 0.0324838866 0.0469810000 1322526773 0 402718720 0.0242299456 -0.1108744144 -0.3044890463 2894 1311867815.0948209763 0.2684573829 0.1375755786 0.2696136534 0.0324784171 0.0365210000 1322529917 0 402718720 0.0246936847 -0.1113154441 -0.3059030771 2895 1311867815.1268870831 0.2688530087 0.1376209248 0.2696136534 0.0324729214 0.0324210000 1322533005 0 402718720 0.0252770502 -0.1101164892 -0.3078944981 2896 1311867815.1629879475 0.2703255117 0.1376667482 0.2703255117 0.0324674638 0.0714660000 1322536317 0 402718720 0.0271675549 -0.1116186529 -0.3077723086 2897 1311867815.1948618889 0.2713851035 0.1377129058 0.2713851035 0.0324619513 0.0327560000 1322539405 0 402718720 0.0262595546 -0.1115366518 -0.3087819815 2898 1311867815.2269918919 0.2716749609 0.1377591315 0.2716749609 0.0324563605 0.0336000000 1322542605 0 402718720 0.0268795360 -0.1105395034 -0.3100276291 2899 1311867815.2629880905 0.2725985646 0.1378056439 0.2725985646 0.0324507827 0.0368950000 1322545861 0 402718720 0.0275329277 -0.1107742563 -0.3106136620 2900 1311867815.2949490547 0.2736414373 0.1378524838 0.2736414373 0.0324452517 0.0332330000 1322549005 0 402718720 0.0278959740 -0.1106780469 -0.3116740584 2901 1311867815.3272631168 0.2748455703 0.1378997065 0.2748455703 0.0324397126 0.0341390000 1322552149 0 402718720 0.0273612067 -0.1103384122 -0.3134141564 2902 1311867815.3628649712 0.2745378911 0.1379467906 0.2748455703 0.0324341549 0.0344900000 1322555405 0 402718720 0.0285399389 -0.1097315624 -0.3129438460 2903 1311867815.3948969841 0.2776668668 0.1379949202 0.2776668668 0.0324286371 0.0332750000 1322558437 0 402718720 0.0277010985 -0.1111105084 -0.3153403699 2904 1311867815.4271960258 0.2773590088 0.1380429106 0.2776668668 0.0324231583 0.0331640000 1322561693 0 402718720 0.0274182521 -0.1100222245 -0.3150328994 2905 1311867815.4628670216 0.2769010663 0.1380907103 0.2776668668 0.0324177086 0.0343070000 1322564949 0 402718720 0.0280385409 -0.1089992300 -0.3143523037 2906 1311867815.4950129986 0.2794649899 0.1381393594 0.2794649899 0.0324122692 0.0319520000 1322568037 0 402718720 0.0287828594 -0.1098758504 -0.3163275123 2907 1311867815.5272490978 0.2810515165 0.1381885208 0.2810515165 0.0324067303 0.0360670000 1322571181 0 402718720 0.0282356329 -0.1105235592 -0.3169908822 2908 1311867815.5630159378 0.2788361311 0.1382368865 0.2810515165 0.0324013449 0.0626140000 1322574493 0 402718720 0.0291012824 -0.1089899912 -0.3141776621 2909 1311867815.5950109959 0.2791826129 0.1382853381 0.2810515165 0.0323958153 0.0333750000 1322577581 0 402718720 0.0288397465 -0.1091009155 -0.3136371672 2910 1311867815.6311800480 0.2802736461 0.1383341314 0.2810515165 0.0323904493 0.0315820000 1322580893 0 402718720 0.0281023160 -0.1082860678 -0.3155913651 2911 1311867815.6630020142 0.2778803110 0.1383820689 0.2810515165 0.0323849840 0.0327130000 1322584037 0 402718720 0.0299966503 -0.1076026186 -0.3123335242 2912 1311867815.6949920654 0.2789093554 0.1384303269 0.2810515165 0.0323795551 0.0406280000 1322587125 0 402718720 0.0293024499 -0.1081526205 -0.3127752841 2913 1311867815.7310440540 0.2782832086 0.1384783368 0.2810515165 0.0323740205 0.0328910000 1322590437 0 402718720 0.0290566944 -0.1065895781 -0.3132502735 2914 1311867815.7629330158 0.2786027193 0.1385264234 0.2810515165 0.0323703541 0.0309370000 1322593581 0 402718720 0.0299636424 -0.1065042466 -0.3132396638 2915 1311867815.7949600220 0.2792737186 0.1385747072 0.2810515165 0.0323649018 0.0332880000 1322596669 0 402718720 0.0295089651 -0.1062833518 -0.3140101433 2916 1311867815.8312530518 0.2796128690 0.1386230742 0.2810515165 0.0323614249 0.0291000000 1322599981 0 402718720 0.0300994068 -0.1066636294 -0.3136869371 2917 1311867815.8629798889 0.2795710862 0.1386713937 0.2810515165 0.0323558957 0.0360680000 1322603125 0 402718720 0.0310957618 -0.1069394276 -0.3128516972 2918 1311867815.8950190544 0.2795637548 0.1387196776 0.2810515165 0.0323504120 0.0336080000 1322606213 0 402718720 0.0303554218 -0.1058380380 -0.3130909801 2919 1311867815.9309890270 0.2810838223 0.1387684492 0.2810838223 0.0323449232 0.0316550000 1322609469 0 402718720 0.0305296425 -0.1057646796 -0.3147118986 2920 1311867815.9633390903 0.2809808552 0.1388171521 0.2810838223 0.0323399164 0.0589570000 1322612613 0 402718720 0.0311853644 -0.1052488238 -0.3144836426 2921 1311867815.9953269958 0.2820167243 0.1388661762 0.2820167243 0.0323346706 0.0333520000 1322615757 0 402718720 0.0311137941 -0.1051782370 -0.3153185546 2922 1311867816.0309410095 0.2808383405 0.1389147635 0.2820167243 0.0323291748 0.0307510000 1322619013 0 402718720 0.0314914584 -0.1036976129 -0.3140953183 2923 1311867816.0630259514 0.2825202644 0.1389638930 0.2825202644 0.0323237093 0.0314410000 1322622157 0 402718720 0.0324974768 -0.1045498550 -0.3150738180 2924 1311867816.0951631069 0.2834569216 0.1390133092 0.2834569216 0.0323181960 0.0339410000 1322625357 0 402718720 0.0324506909 -0.1041949764 -0.3160603046 2925 1311867816.1310849190 0.2837711871 0.1390627991 0.2837711871 0.0323126936 0.0446310000 1322628557 0 402718720 0.0326343328 -0.1031677127 -0.3167586327 2926 1311867816.1629989147 0.2838032246 0.1391122661 0.2838032246 0.0323071839 0.0309980000 1322631589 0 402718720 0.0327038281 -0.1023164466 -0.3167183697 2927 1311867816.1951410770 0.2851994038 0.1391621763 0.2851994038 0.0323016999 0.0302320000 1322634733 0 402718720 0.0334295146 -0.1024692431 -0.3181545734 2928 1311867816.2310938835 0.2871412635 0.1392127156 0.2871412635 0.0322961952 0.0295200000 1322637989 0 402718720 0.0326375104 -0.1032129675 -0.3192014992 2929 1311867816.2630169392 0.2855248749 0.1392626686 0.2871412635 0.0322907759 0.0345350000 1322641133 0 402718720 0.0330915190 -0.1015730873 -0.3182646632 2930 1311867816.2951760292 0.2864007652 0.1393128863 0.2871412635 0.0322853269 0.0363430000 1322644221 0 402718720 0.0344478153 -0.1024202034 -0.3186523914 2931 1311867816.3310940266 0.2864935994 0.1393631015 0.2871412635 0.0322798486 0.0666840000 1322647533 0 402718720 0.0351447016 -0.1031478271 -0.3183802068 2932 1311867816.3629589081 0.2871454954 0.1394135048 0.2871454954 0.0322743625 0.0472870000 1322650677 0 402718720 0.0352015197 -0.1039448604 -0.3188666701 2933 1311867816.3951370716 0.2884751260 0.1394643270 0.2884751260 0.0322688901 0.0518790000 1322653765 0 402718720 0.0348982327 -0.1051499620 -0.3202008307 2934 1311867816.4311180115 0.2862037420 0.1395143405 0.2884751260 0.0322634935 0.0458140000 1322657021 0 402718720 0.0356539339 -0.1042967141 -0.3186664879 2935 1311867816.4629940987 0.2894141972 0.1395654137 0.2894141972 0.0322582681 0.0292790000 1322660165 0 402718720 0.0359764583 -0.1072599068 -0.3210551441 2936 1311867816.4950900078 0.2893562913 0.1396164324 0.2894141972 0.0322533116 0.0334660000 1322663365 0 402718720 0.0351353325 -0.1068280041 -0.3215438426 2937 1311867816.5310220718 0.2885874212 0.1396671545 0.2894141972 0.0322481234 0.0331070000 1322666565 0 402718720 0.0358638912 -0.1070066690 -0.3211428821 2938 1311867816.5632600784 0.2890397310 0.1397179961 0.2894141972 0.0322432982 0.0344530000 1322669765 0 402718720 0.0365365185 -0.1086373851 -0.3211047351 2939 1311867816.5957059860 0.2865332067 0.1397679502 0.2894141972 0.0322379727 0.0482060000 1322672853 0 402718720 0.0343522131 -0.1065403447 -0.3202733696 2940 1311867816.6310799122 0.2873476446 0.1398181474 0.2894141972 0.0322326489 0.0330760000 1322676109 0 402718720 0.0347940028 -0.1076428816 -0.3214275241 2941 1311867816.6629660130 0.2859832346 0.1398678465 0.2894141972 0.0322272482 0.0422220000 1322679253 0 402718720 0.0331720673 -0.1072670743 -0.3203872442 2942 1311867816.6953299046 0.2871291339 0.1399179014 0.2894141972 0.0322218540 0.0293880000 1322682341 0 402718720 0.0330362171 -0.1077314913 -0.3227112293 2943 1311867816.7311360836 0.2870004773 0.1399678784 0.2894141972 0.0322167120 0.0586600000 1322685597 0 402718720 0.0318400711 -0.1083833873 -0.3224542141 2944 1311867816.7630920410 0.2840858102 0.1400168315 0.2894141972 0.0322112671 0.0328600000 1322688797 0 402718720 0.0319807678 -0.1073566303 -0.3198852539 2945 1311867816.7951140404 0.2834156752 0.1400655239 0.2894141972 0.0322058832 0.0344650000 1322691885 0 402718720 0.0319616906 -0.1073529050 -0.3200311959 2946 1311867816.8311979771 0.2829146087 0.1401140130 0.2894141972 0.0322005417 0.0329830000 1322695141 0 402718720 0.0318781622 -0.1084002778 -0.3193811476 2947 1311867816.8631730080 0.2815596163 0.1401620095 0.2894141972 0.0321951248 0.0355240000 1322698285 0 402718720 0.0312569737 -0.1089917496 -0.3175387979 2948 1311867816.8951439857 0.2798359692 0.1402093887 0.2894141972 0.0321896908 0.0412090000 1322701429 0 402718720 0.0319593325 -0.1090137437 -0.3164668679 2949 1311867816.9311048985 0.2813695073 0.1402572558 0.2894141972 0.0321852427 0.0287290000 1322704629 0 402718720 0.0308773778 -0.1100085080 -0.3190512657 2950 1311867816.9654729366 0.2805638313 0.1403048174 0.2894141972 0.0321807235 0.0336880000 1322707717 0 402718720 0.0299883485 -0.1098117307 -0.3188341558 2951 1311867816.9951689243 0.2792779505 0.1403519110 0.2894141972 0.0321753516 0.0326910000 1322710805 0 402718720 0.0311474651 -0.1105011851 -0.3171442449 2952 1311867817.0314610004 0.2792262137 0.1403989551 0.2894141972 0.0321699288 0.0384600000 1322714117 0 402718720 0.0302209295 -0.1113381237 -0.3170146346 2953 1311867817.0629920959 0.2792849839 0.1404459873 0.2894141972 0.0321659296 0.0325000000 1322717261 0 402718720 0.0290749390 -0.1104038507 -0.3185245395 2954 1311867817.0953140259 0.2778477371 0.1404925011 0.2894141972 0.0321606416 0.0318830000 1322720349 0 402718720 0.0295649692 -0.1105730161 -0.3170684874 2955 1311867817.1311180592 0.2774899006 0.1405388623 0.2894141972 0.0321578086 0.0625120000 1322723605 0 402718720 0.0291192383 -0.1112905219 -0.3163272142 2956 1311867817.1630349159 0.2752313018 0.1405844281 0.2894141972 0.0321524099 0.0323710000 1322726805 0 402718720 0.0283890646 -0.1095794439 -0.3154196441 2957 1311867817.1950340271 0.2734785378 0.1406293703 0.2894141972 0.0321472541 0.0343440000 1322729893 0 402718720 0.0297628585 -0.1095630303 -0.3136869073 2958 1311867817.2312440872 0.2745868564 0.1406746568 0.2894141972 0.0321420954 0.0326330000 1322733149 0 402718720 0.0300737917 -0.1117304564 -0.3143288493 2959 1311867817.2631859779 0.2746882141 0.1407199469 0.2894141972 0.0321366866 0.0311140000 1322736349 0 402718720 0.0305395089 -0.1132966354 -0.3141085207 2960 1311867817.2951490879 0.2738995552 0.1407649400 0.2894141972 0.0321312771 0.0324160000 1322739437 0 402718720 0.0305172876 -0.1135419980 -0.3142001927 2961 1311867817.3310010433 0.2729429901 0.1408095797 0.2894141972 0.0321263514 0.0316160000 1322742693 0 402718720 0.0295976792 -0.1140107736 -0.3142560124 2962 1311867817.3636391163 0.2728272974 0.1408541502 0.2894141972 0.0321209600 0.0345070000 1322745837 0 402718720 0.0297469459 -0.1153058484 -0.3138083220 2963 1311867817.3955860138 0.2712196112 0.1408981480 0.2894141972 0.0321156795 0.0325180000 1322748981 0 402718720 0.0293608811 -0.1152549684 -0.3131314516 2964 1311867817.4310679436 0.2701022625 0.1409417391 0.2894141972 0.0321103229 0.0327160000 1322752237 0 402718720 0.0289971270 -0.1157092378 -0.3128008544 2965 1311867817.4630908966 0.2683229446 0.1409847007 0.2894141972 0.0321049313 0.0321790000 1322755381 0 402718720 0.0288381167 -0.1156251281 -0.3113769591 2966 1311867817.4955279827 0.2662082613 0.1410269204 0.2894141972 0.0320995415 0.0305210000 1322758525 0 402718720 0.0285537280 -0.1152556241 -0.3102668226 2967 1311867817.5312108994 0.2663874924 0.1410691720 0.2894141972 0.0320942725 0.0665940000 1322761781 0 402718720 0.0279186778 -0.1166652068 -0.3107015491 2968 1311867817.5636010170 0.2660963237 0.1411112971 0.2894141972 0.0320889203 0.0317060000 1322764981 0 402718720 0.0282920543 -0.1178884134 -0.3100995719 2969 1311867817.5950961113 0.2643461525 0.1411528043 0.2894141972 0.0320835338 0.0339880000 1322768125 0 402718720 0.0275563113 -0.1177271977 -0.3090361655 2970 1311867817.6311480999 0.2626989484 0.1411937289 0.2894141972 0.0320781509 0.0317270000 1322771325 0 402718720 0.0266255848 -0.1178894490 -0.3076869845 2971 1311867817.6632049084 0.2611643076 0.1412341094 0.2894141972 0.0320727669 0.0338020000 1322774525 0 402718720 0.0264279079 -0.1182628423 -0.3063629866 2972 1311867817.6950769424 0.2610144317 0.1412744124 0.2894141972 0.0320675029 0.0337860000 1322777613 0 402718720 0.0259252116 -0.1195710152 -0.3059211969 2973 1311867817.7312018871 0.2578144372 0.1413136118 0.2894141972 0.0320621683 0.0312710000 1322780925 0 402718720 0.0267336927 -0.1191997603 -0.3035692573 2974 1311867817.7630031109 0.2561223507 0.1413522160 0.2894141972 0.0320568502 0.0333040000 1322784069 0 402718720 0.0269334428 -0.1191677079 -0.3028259575 2975 1311867817.7950661182 0.2570123672 0.1413910933 0.2894141972 0.0320522825 0.0319930000 1322787157 0 402718720 0.0248355772 -0.1202538833 -0.3039611876 2976 1311867817.8311879635 0.2556197345 0.1414294766 0.2894141972 0.0320471027 0.0314790000 1322790469 0 402718720 0.0247661956 -0.1214541569 -0.3016215563 2977 1311867817.8633050919 0.2539629042 0.1414672776 0.2894141972 0.0320420953 0.0338540000 1322793669 0 402718720 0.0260647237 -0.1212904975 -0.3007404208 2978 1311867817.8951950073 0.2541709840 0.1415051230 0.2894141972 0.0320368082 0.0317760000 1322796813 0 402718720 0.0251008272 -0.1222028360 -0.3010019660 2979 1311867817.9311769009 0.2534773648 0.1415427102 0.2894141972 0.0320314881 0.0591310000 1322800013 0 402718720 0.0240348149 -0.1225655600 -0.2999570072 2980 1311867817.9631450176 0.2531438470 0.1415801602 0.2894141972 0.0320262033 0.0341840000 1322803213 0 402718720 0.0246621408 -0.1231879145 -0.2996403873 2981 1311867817.9952929020 0.2527609766 0.1416174567 0.2894141972 0.0320208949 0.0342000000 1322806301 0 402718720 0.0243071001 -0.1239445359 -0.2991865277 2982 1311867818.0322449207 0.2514188588 0.1416542781 0.2894141972 0.0320158076 0.0325130000 1322809557 0 402718720 0.0247338954 -0.1239298135 -0.2982388139 2983 1311867818.0654659271 0.2513443828 0.1416910499 0.2894141972 0.0320105021 0.0319930000 1322812757 0 402718720 0.0246695932 -0.1246012077 -0.2980229855 2984 1311867818.0955450535 0.2518780828 0.1417279758 0.2894141972 0.0320051596 0.0319270000 1322815845 0 402718720 0.0238959473 -0.1253766268 -0.2988305092 2985 1311867818.1311609745 0.2505971193 0.1417644479 0.2894141972 0.0320001258 0.0301180000 1322819101 0 402718720 0.0238299649 -0.1255713850 -0.2981162667 2986 1311867818.1632380486 0.2497966290 0.1418006275 0.2894141972 0.0319950440 0.0333540000 1322822245 0 402718720 0.0246243794 -0.1258594394 -0.2973117232 2987 1311867818.1991639137 0.2503824234 0.1418369789 0.2894141972 0.0319900141 0.0317550000 1322825501 0 402718720 0.0237298477 -0.1265719384 -0.2983449697 2988 1311867818.2310791016 0.2499233186 0.1418731524 0.2894141972 0.0319867215 0.0334150000 1322828645 0 402718720 0.0233876128 -0.1269828826 -0.2980153561 2989 1311867818.2631750107 0.2486210763 0.1419088660 0.2894141972 0.0319815565 0.0298470000 1322831789 0 402718720 0.0242720321 -0.1273554415 -0.2967705429 2990 1311867818.2958960533 0.2484575063 0.1419445010 0.2894141972 0.0319762786 0.0322030000 1322834933 0 402718720 0.0238166284 -0.1272272766 -0.2979783416 2991 1311867818.3311960697 0.2481364310 0.1419800048 0.2894141972 0.0319710746 0.0608600000 1322838189 0 402718720 0.0233567376 -0.1275931150 -0.2980178297 2992 1311867818.3631889820 0.2470326871 0.1420151160 0.2894141972 0.0319657475 0.0294360000 1322841333 0 402718720 0.0241357237 -0.1279345304 -0.2967389524 2993 1311867818.3968179226 0.2465366721 0.1420500380 0.2894141972 0.0319626298 0.0316500000 1322844533 0 402718720 0.0241585467 -0.1289207786 -0.2963975966 2994 1311867818.4313120842 0.2470151782 0.1420850965 0.2894141972 0.0319602932 0.0320160000 1322847733 0 402718720 0.0230923872 -0.1291504204 -0.2977415025 2995 1311867818.4631240368 0.2461584508 0.1421198455 0.2894141972 0.0319553819 0.0343830000 1322850933 0 402718720 0.0238082409 -0.1294972599 -0.2969024479 2996 1311867818.4961380959 0.2452752590 0.1421542766 0.2894141972 0.0319501362 0.0323540000 1322854021 0 402718720 0.0236027762 -0.1296491325 -0.2965572178 2997 1311867818.5312669277 0.2450471967 0.1421886085 0.2894141972 0.0319448205 0.0314570000 1322857277 0 402718720 0.0223241914 -0.1298058927 -0.2972349524 2998 1311867818.5631868839 0.2449968010 0.1422229008 0.2894141972 0.0319399772 0.0333840000 1322860421 0 402718720 0.0215979293 -0.1307177842 -0.2962463498 2999 1311867818.5952920914 0.2442735136 0.1422569290 0.2894141972 0.0319347368 0.0310770000 1322863509 0 402718720 0.0215354525 -0.1309556216 -0.2957236469 3000 1311867818.6311600208 0.2436099946 0.1422907134 0.2894141972 0.0319296438 0.0406810000 1322866765 0 402718720 0.0209018327 -0.1308485419 -0.2956793010 3001 1311867818.6631069183 0.2428162843 0.1423242107 0.2894141972 0.0319243666 0.0359860000 1322869965 0 402718720 0.0203775950 -0.1312366426 -0.2947154045 3002 1311867818.6952610016 0.2421387881 0.1423574601 0.2894141972 0.0319191672 0.0312140000 1322873109 0 402718720 0.0198586080 -0.1317488998 -0.2934230864 3003 1311867818.7311699390 0.2413574308 0.1423904271 0.2894141972 0.0319141284 0.0669010000 1322876309 0 402718720 0.0187459942 -0.1319529861 -0.2926343381 3004 1311867818.7633459568 0.2404007316 0.1424230537 0.2894141972 0.0319088584 0.0321220000 1322879509 0 402718720 0.0188453682 -0.1318249404 -0.2917071283 3005 1311867818.7952179909 0.2397736609 0.1424554499 0.2894141972 0.0319037712 0.0326980000 1322882597 0 402718720 0.0183898453 -0.1319080442 -0.2909493744 3006 1311867818.8313419819 0.2385634184 0.1424874220 0.2894141972 0.0318986485 0.0337840000 1322885853 0 402718720 0.0181305818 -0.1310932189 -0.2902813256 3007 1311867818.8631989956 0.2376061380 0.1425190544 0.2894141972 0.0318933922 0.0338010000 1322889053 0 402718720 0.0189781673 -0.1315520555 -0.2895143628 3008 1311867818.8952059746 0.2365113348 0.1425503018 0.2894141972 0.0318904727 0.0411910000 1322892197 0 402718720 0.0179731045 -0.1319419295 -0.2882492244 3009 1311867818.9312291145 0.2345398217 0.1425808733 0.2894141972 0.0318853578 0.0336970000 1322895397 0 402718720 0.0180262141 -0.1321551353 -0.2868675292 3010 1311867818.9632639885 0.2333394736 0.1426110256 0.2894141972 0.0318803396 0.0335680000 1322898597 0 402718720 0.0189839508 -0.1318798214 -0.2866782546 3011 1311867818.9952731133 0.2322021574 0.1426407803 0.2894141972 0.0318764165 0.0306950000 1322901741 0 402718720 0.0179115888 -0.1324075162 -0.2858189046 3012 1311867819.0317270756 0.2320666313 0.1426704701 0.2894141972 0.0318711963 0.0332690000 1322904941 0 402718720 0.0187786389 -0.1342833042 -0.2850373387 3013 1311867819.0633409023 0.2317881286 0.1427000478 0.2894141972 0.0318659306 0.0339050000 1322908141 0 402718720 0.0183860380 -0.1357163489 -0.2840190232 3014 1311867819.0951960087 0.2300804853 0.1427290393 0.2894141972 0.0318607922 0.0641390000 1322911229 0 402718720 0.0172354169 -0.1354271024 -0.2836379409 3015 1311867819.1316080093 0.2290747017 0.1427576780 0.2894141972 0.0318559171 0.0303580000 1322914541 0 402718720 0.0173256285 -0.1364417523 -0.2828146815 3016 1311867819.1634290218 0.2284349799 0.1427860856 0.2894141972 0.0318509605 0.0317580000 1322917685 0 402718720 0.0167825688 -0.1381947696 -0.2808857560 3017 1311867819.1952009201 0.2269398868 0.1428139788 0.2894141972 0.0318471072 0.0317630000 1322920773 0 402718720 0.0172069687 -0.1388360560 -0.2801347077 3018 1311867819.2314460278 0.2257728428 0.1428414669 0.2894141972 0.0318419723 0.0344370000 1322924029 0 402718720 0.0178121347 -0.1390839368 -0.2805501521 3019 1311867819.2639720440 0.2245885134 0.1428685444 0.2894141972 0.0318368758 0.0316540000 1322927173 0 402718720 0.0176160857 -0.1396176517 -0.2796236575 3020 1311867819.2961781025 0.2244320214 0.1428955522 0.2894141972 0.0318317023 0.0322950000 1322930317 0 402718720 0.0168370381 -0.1410795003 -0.2788616717 3021 1311867819.3311860561 0.2241718471 0.1429224559 0.2894141972 0.0318273646 0.0320190000 1322933517 0 402718720 0.0165951531 -0.1411896199 -0.2796127796 3022 1311867819.3631401062 0.2231100947 0.1429489906 0.2894141972 0.0318221396 0.0300700000 1322936717 0 402718720 0.0165972300 -0.1409760416 -0.2793002725 3023 1311867819.3952360153 0.2228655964 0.1429754268 0.2894141972 0.0318177467 0.0328720000 1322939861 0 402718720 0.0154529279 -0.1414390653 -0.2791008055 3024 1311867819.4313340187 0.2223973870 0.1430016906 0.2894141972 0.0318125834 0.0358950000 1322943117 0 402718720 0.0162808057 -0.1409950107 -0.2801756859 3025 1311867819.4633119106 0.2216534615 0.1430276912 0.2894141972 0.0318073957 0.0361710000 1322946261 0 402718720 0.0180931333 -0.1414325684 -0.2794046104 3026 1311867819.4955739975 0.2212034166 0.1430535259 0.2894141972 0.0318021524 0.0691190000 1322949405 0 402718720 0.0173458848 -0.1417613178 -0.2785702944 3027 1311867819.5313119888 0.2213185579 0.1430793815 0.2894141972 0.0317970648 0.0331670000 1322952661 0 402718720 0.0156517252 -0.1416186839 -0.2792436779 3028 1311867819.5632400513 0.2207572460 0.1431050347 0.2894141972 0.0317918602 0.0315450000 1322955805 0 402718720 0.0154891983 -0.1423005164 -0.2772850394 3029 1311867819.5953240395 0.2202984840 0.1431305195 0.2894141972 0.0317868049 0.0362370000 1322958893 0 402718720 0.0170087311 -0.1426001340 -0.2768756449 3030 1311867819.6317999363 0.2198255658 0.1431558314 0.2894141972 0.0317823769 0.0326910000 1322962205 0 402718720 0.0166779421 -0.1416011453 -0.2785238624 3031 1311867819.6632640362 0.2198322266 0.1431811288 0.2894141972 0.0317771792 0.0338710000 1322965349 0 402718720 0.0157900844 -0.1422642767 -0.2778583467 3032 1311867819.6952939034 0.2200266868 0.1432064736 0.2894141972 0.0317719423 0.0336350000 1322968437 0 402718720 0.0160267968 -0.1450639069 -0.2742222846 3033 1311867819.7313659191 0.2190982550 0.1432314957 0.2894141972 0.0317667361 0.0332170000 1322971693 0 402718720 0.0169802215 -0.1439521015 -0.2757685184 3034 1311867819.7639379501 0.2193240076 0.1432565756 0.2894141972 0.0317615545 0.0360780000 1322974949 0 402718720 0.0164898690 -0.1435713023 -0.2774901986 3035 1311867819.7953739166 0.2191864550 0.1432815937 0.2894141972 0.0317563584 0.0340620000 1322977981 0 402718720 0.0177827720 -0.1450007707 -0.2760751545 3036 1311867819.8312380314 0.2190045863 0.1433065354 0.2894141972 0.0317511510 0.0332270000 1322981293 0 402718720 0.0169481654 -0.1455793381 -0.2755667567 3037 1311867819.8637769222 0.2181143314 0.1433311675 0.2894141972 0.0317459659 0.0382910000 1322984493 0 402718720 0.0166704115 -0.1440510750 -0.2768839300 3038 1311867819.8986899853 0.2188228369 0.1433560166 0.2894141972 0.0317407885 0.0654270000 1322987693 0 402718720 0.0179537982 -0.1456445307 -0.2762945294 3039 1311867819.9312291145 0.2181391418 0.1433806245 0.2894141972 0.0317357295 0.0335340000 1322990781 0 402718720 0.0172533654 -0.1462245882 -0.2745584249 3040 1311867819.9633669853 0.2174688131 0.1434049956 0.2894141972 0.0317305184 0.0395170000 1322993981 0 402718720 0.0170165673 -0.1449245512 -0.2757287920 3041 1311867819.9952859879 0.2181935608 0.1434295890 0.2894141972 0.0317253628 0.0392810000 1322997125 0 402718720 0.0176491924 -0.1458731741 -0.2754189074 3042 1311867820.0311710835 0.2178012878 0.1434540373 0.2894141972 0.0317201560 0.0318250000 1323000325 0 402718720 0.0174179114 -0.1457813680 -0.2747514844 3043 1311867820.0643200874 0.2177270204 0.1434784451 0.2894141972 0.0317149507 0.0392060000 1323003581 0 402718720 0.0175817814 -0.1455870718 -0.2747550905 3044 1311867820.0953049660 0.2175141871 0.1435027669 0.2894141972 0.0317097946 0.0394880000 1323006613 0 402718720 0.0181880090 -0.1453567743 -0.2746233642 3045 1311867820.1314449310 0.2169685662 0.1435268936 0.2894141972 0.0317045901 0.0343130000 1323009869 0 402718720 0.0178418327 -0.1454354376 -0.2737179101 3046 1311867820.1633670330 0.2170632035 0.1435510356 0.2894141972 0.0316993907 0.0313620000 1323013069 0 402718720 0.0183810182 -0.1457377225 -0.2738756537 3047 1311867820.1956179142 0.2170339078 0.1435751520 0.2894141972 0.0316942148 0.0385460000 1323016157 0 402718720 0.0185403712 -0.1459317356 -0.2734992802 3048 1311867820.2314419746 0.2174173892 0.1435993785 0.2894141972 0.0316891633 0.0336110000 1323019413 0 402718720 0.0187917408 -0.1469092518 -0.2729763091 3049 1311867820.2634580135 0.2167063951 0.1436233559 0.2894141972 0.0316839664 0.0625730000 1323022557 0 402718720 0.0185748953 -0.1467894912 -0.2723219097 3050 1311867820.2954239845 0.2159846276 0.1436470809 0.2894141972 0.0316788829 0.0354850000 1323025757 0 402718720 0.0192737244 -0.1460801363 -0.2726614475 3051 1311867820.3312399387 0.2160816491 0.1436708221 0.2894141972 0.0316737273 0.0330120000 1323028957 0 402718720 0.0193525422 -0.1472250968 -0.2716707885 3052 1311867820.3659369946 0.2159566730 0.1436945069 0.2894141972 0.0316685519 0.0348850000 1323032157 0 402718720 0.0194184706 -0.1479436010 -0.2711628377 3053 1311867820.3954350948 0.2155029476 0.1437180275 0.2894141972 0.0316633704 0.0309680000 1323035245 0 402718720 0.0196700450 -0.1479806155 -0.2710485756 3054 1311867820.4311659336 0.2152684033 0.1437414559 0.2894141972 0.0316584310 0.0338220000 1323038501 0 402718720 0.0200409777 -0.1493542194 -0.2693275213 3055 1311867820.4636130333 0.2150506377 0.1437647977 0.2894141972 0.0316532631 0.0352110000 1323041645 0 402718720 0.0198017042 -0.1493655741 -0.2695501149 3056 1311867820.4953510761 0.2149834782 0.1437881022 0.2894141972 0.0316481122 0.0328480000 1323044733 0 402718720 0.0200072043 -0.1496890336 -0.2695462704 3057 1311867820.5313849449 0.2145249993 0.1438112416 0.2894141972 0.0316430054 0.0340730000 1323048045 0 402718720 0.0194115639 -0.1500417590 -0.2683123648 3058 1311867820.5636560917 0.2136553973 0.1438340814 0.2894141972 0.0316378394 0.0334570000 1323051189 0 402718720 0.0192515384 -0.1490589529 -0.2685465217 3059 1311867820.5956280231 0.2126934230 0.1438565918 0.2894141972 0.0316326983 0.0308200000 1323054333 0 402718720 0.0191617645 -0.1483115405 -0.2681688964 3060 1311867820.6320679188 0.2123187333 0.1438789650 0.2894141972 0.0316275797 0.0344880000 1323057589 0 402718720 0.0187685415 -0.1495084763 -0.2659149766 3061 1311867820.6632380486 0.2121718079 0.1439012757 0.2894141972 0.0316224144 0.0667460000 1323060677 0 402718720 0.0187258646 -0.1501763314 -0.2650831044 3062 1311867820.6954100132 0.2122071385 0.1439235833 0.2894141972 0.0316172923 0.0358710000 1323063821 0 402718720 0.0191485398 -0.1501160860 -0.2658385634 3063 1311867820.7312459946 0.2124189585 0.1439459455 0.2894141972 0.0316122658 0.0375090000 1323067077 0 402718720 0.0199290514 -0.1513980478 -0.2649371028 3064 1311867820.7633619308 0.2121346742 0.1439682003 0.2894141972 0.0316071905 0.0344790000 1323070277 0 402718720 0.0199466739 -0.1523200423 -0.2635193467 3065 1311867820.7963910103 0.2114087939 0.1439902037 0.2894141972 0.0316020587 0.0334950000 1323073421 0 402718720 0.0190092418 -0.1513394117 -0.2642010450 3066 1311867820.8312530518 0.2105701268 0.1440119193 0.2894141972 0.0315969153 0.0416740000 1323076621 0 402718720 0.0191183146 -0.1517024934 -0.2624951303 3067 1311867820.8635599613 0.2110290229 0.1440337703 0.2894141972 0.0315918985 0.0346960000 1323079821 0 402718720 0.0200496390 -0.1528637260 -0.2623426020 3068 1311867820.8956539631 0.2107588202 0.1440555190 0.2894141972 0.0315867640 0.0342260000 1323082909 0 402718720 0.0196223017 -0.1528864801 -0.2623864710 3069 1311867820.9312889576 0.2105164975 0.1440771746 0.2894141972 0.0315816193 0.0364930000 1323086165 0 402718720 0.0182560924 -0.1530551314 -0.2617035210 3070 1311867820.9635450840 0.2099564075 0.1440986336 0.2894141972 0.0315764806 0.0354950000 1323089365 0 402718720 0.0189016853 -0.1533888727 -0.2604486942 3071 1311867820.9955151081 0.2092116326 0.1441198362 0.2894141972 0.0315713479 0.0357920000 1323092509 0 402718720 0.0188381132 -0.1520308405 -0.2614946067 3072 1311867821.0315189362 0.2094495595 0.1441411024 0.2894141972 0.0315663397 0.0704170000 1323095653 0 402718720 0.0178563222 -0.1527747214 -0.2601141334 3073 1311867821.0635919571 0.2088465840 0.1441621585 0.2894141972 0.0315612160 0.0344260000 1323098853 0 402718720 0.0175043121 -0.1527680159 -0.2591078579 3074 1311867821.0963261127 0.2069406807 0.1441825809 0.2894141972 0.0315561538 0.0355780000 1323101997 0 402718720 0.0167587455 -0.1504041702 -0.2590909600 3075 1311867821.1328949928 0.2072509229 0.1442030909 0.2894141972 0.0315512237 0.0331340000 1323105309 0 402718720 0.0163333006 -0.1506377310 -0.2589311004 3076 1311867821.1633639336 0.2082315534 0.1442239064 0.2894141972 0.0315462586 0.0327820000 1323108285 0 402718720 0.0181079172 -0.1529939324 -0.2574991286 3077 1311867821.1953179836 0.2087108046 0.1442448642 0.2894141972 0.0315413907 0.0346290000 1323111373 0 402718720 0.0188641269 -0.1544850767 -0.2567208111 3078 1311867821.2314000130 0.2076376826 0.1442654596 0.2894141972 0.0315363337 0.0330570000 1323114685 0 402718720 0.0181602649 -0.1535696685 -0.2568712831 3079 1311867821.2633080482 0.2078117728 0.1442860982 0.2894141972 0.0315312633 0.0336640000 1323117829 0 402718720 0.0179956108 -0.1549314857 -0.2555539608 3080 1311867821.2957510948 0.2086691260 0.1443070018 0.2894141972 0.0315262515 0.0365190000 1323120973 0 402718720 0.0188088454 -0.1570092142 -0.2543817759 3081 1311867821.3314800262 0.2071478218 0.1443273981 0.2894141972 0.0315211657 0.0329610000 1323124229 0 402718720 0.0178092793 -0.1555430591 -0.2545957565 3082 1311867821.3635981083 0.2080469579 0.1443480728 0.2894141972 0.0315161657 0.0321330000 1323127429 0 402718720 0.0183517374 -0.1581084728 -0.2529444695 3083 1311867821.3955659866 0.2098728567 0.1443693264 0.2894141972 0.0315113105 0.0337580000 1323130517 0 402718720 0.0190456770 -0.1614005566 -0.2518633902 3084 1311867821.4315030575 0.2082124501 0.1443900278 0.2894141972 0.0315062229 0.0763390000 1323133773 0 402718720 0.0176566988 -0.1600271314 -0.2520117164 3085 1311867821.4632000923 0.2083097994 0.1444107473 0.2894141972 0.0315011656 0.0356360000 1323136917 0 402718720 0.0184354838 -0.1610136330 -0.2514493763 3086 1311867821.4953439236 0.2088677883 0.1444316342 0.2894141972 0.0314961282 0.0365390000 1323140005 0 402718720 0.0186521988 -0.1627095491 -0.2506397069 3087 1311867821.5312869549 0.2068177760 0.1444518435 0.2894141972 0.0314910345 0.0394760000 1323143317 0 402718720 0.0171499122 -0.1606403887 -0.2511500716 3088 1311867821.5636770725 0.2057729065 0.1444717014 0.2894141972 0.0314859359 0.0370790000 1323146461 0 402718720 0.0159950424 -0.1601609439 -0.2499928623 3089 1311867821.5954399109 0.2070520222 0.1444919605 0.2894141972 0.0314810611 0.0728200000 1323149493 0 402718720 0.0173640065 -0.1620849669 -0.2498840988 3090 1311867821.6326320171 0.2055960745 0.1445117353 0.2894141972 0.0314760058 0.0362860000 1323152805 0 402718720 0.0167269614 -0.1599993408 -0.2506882250 3091 1311867821.6634519100 0.2045438588 0.1445311569 0.2894141972 0.0314709325 0.0415290000 1323155893 0 402718720 0.0148764085 -0.1598026305 -0.2484503388 3092 1311867821.6953229904 0.2061114013 0.1445510729 0.2894141972 0.0314659309 0.0349360000 1323159037 0 402718720 0.0154218618 -0.1624361873 -0.2469977140 3093 1311867821.7313649654 0.2057128400 0.1445708471 0.2894141972 0.0314609530 0.0344330000 1323162293 0 402718720 0.0157910213 -0.1623972654 -0.2468150258 3094 1311867821.7634460926 0.2039085180 0.1445900254 0.2894141972 0.0314558961 0.0380580000 1323165493 0 402718720 0.0145380739 -0.1608917862 -0.2463117242 3095 1311867821.7956120968 0.2053966820 0.1446096722 0.2894141972 0.0314508657 0.0352020000 1323168525 0 402718720 0.0149061903 -0.1637444943 -0.2448055744 3096 1311867821.8313920498 0.2047705203 0.1446291040 0.2894141972 0.0314458355 0.0376010000 1323171781 0 402718720 0.0144527135 -0.1635373384 -0.2448639870 3097 1311867821.8633379936 0.2028640956 0.1446479076 0.2894141972 0.0314408094 0.0378960000 1323174869 0 402718720 0.0143615520 -0.1618022621 -0.2448900044 3098 1311867821.8956110477 0.2039295286 0.1446670431 0.2894141972 0.0314358288 0.0375440000 1323178069 0 402718720 0.0138373990 -0.1645838469 -0.2428232133 3099 1311867821.9314410686 0.2061373889 0.1446868786 0.2894141972 0.0314308314 0.0368880000 1323181325 0 402718720 0.0151507016 -0.1682446599 -0.2423444241 3100 1311867821.9633870125 0.2048067302 0.1447062721 0.2894141972 0.0314258172 0.0431430000 1323184525 0 402718720 0.0144971348 -0.1675170213 -0.2429428995 3101 1311867821.9954171181 0.2043206096 0.1447254964 0.2894141972 0.0314207946 0.0355800000 1323187669 0 402718720 0.0139057506 -0.1684574932 -0.2413764149 3102 1311867822.0314009190 0.2052617818 0.1447450116 0.2894141972 0.0314158783 0.0386110000 1323190869 0 402718720 0.0140962759 -0.1703924239 -0.2411545068 3103 1311867822.0633769035 0.2037169486 0.1447640164 0.2894141972 0.0314108582 0.0372710000 1323194069 0 402718720 0.0133227808 -0.1692128927 -0.2410619855 3104 1311867822.0962209702 0.2022291869 0.1447825297 0.2894141972 0.0314058060 0.0387120000 1323197157 0 402718720 0.0125490129 -0.1679377705 -0.2405788004 3105 1311867822.1315379143 0.2013963312 0.1448007628 0.2894141972 0.0314009337 0.0474970000 1323200413 0 402718720 0.0126921088 -0.1673922837 -0.2406977266 3106 1311867822.1634409428 0.2010375410 0.1448188686 0.2894141972 0.0313959314 0.0354750000 1323203613 0 402718720 0.0127139520 -0.1665696800 -0.2412894815 3107 1311867822.1960899830 0.1998700798 0.1448365871 0.2894141972 0.0313909819 0.0377060000 1323206701 0 402718720 0.0110245058 -0.1661862731 -0.2392484248 3108 1311867822.2317450047 0.2016802281 0.1448548765 0.2894141972 0.0313859412 0.0352340000 1323209957 0 402718720 0.0112058241 -0.1693590432 -0.2373694479 3109 1311867822.2634150982 0.2027017325 0.1448734828 0.2894141972 0.0313812655 0.0368710000 1323213157 0 402718720 0.0122229382 -0.1704544425 -0.2379595935 3110 1311867822.2954349518 0.2015728354 0.1448917141 0.2894141972 0.0313765923 0.0368090000 1323216245 0 402718720 0.0134894270 -0.1692524254 -0.2392931432 3111 1311867822.3315870762 0.2004020065 0.1449095573 0.2894141972 0.0313715930 0.0636100000 1323219501 0 402718720 0.0118649071 -0.1690495163 -0.2378887981 3112 1311867822.3635189533 0.2001302987 0.1449273018 0.2894141972 0.0313665597 0.0391780000 1323222701 0 402718720 0.0114323776 -0.1692980230 -0.2371880561 3113 1311867822.3960089684 0.1992046535 0.1449447375 0.2894141972 0.0313615325 0.0393790000 1323225789 0 402718720 0.0114182075 -0.1685488075 -0.2372179031 3114 1311867822.4314260483 0.1993536651 0.1449622099 0.2894141972 0.0313565504 0.0390070000 1323229045 0 402718720 0.0118832616 -0.1693040282 -0.2367551029 3115 1311867822.4634740353 0.2007172704 0.1449801088 0.2894141972 0.0313517234 0.0380960000 1323232189 0 402718720 0.0124598881 -0.1711972803 -0.2368719727 3116 1311867822.4957718849 0.1991698295 0.1449974996 0.2894141972 0.0313467125 0.0365920000 1323235277 0 402718720 0.0108409068 -0.1709507704 -0.2345851511 3117 1311867822.5315260887 0.2023608685 0.1450159029 0.2894141972 0.0313418362 0.0384930000 1323238589 0 402718720 0.0124441534 -0.1756731868 -0.2333764434 3118 1311867822.5634500980 0.2037336975 0.1450347348 0.2894141972 0.0313372336 0.0393090000 1323241733 0 402718720 0.0134548899 -0.1787568480 -0.2317924798 3119 1311867822.5955328941 0.2029739618 0.1450533110 0.2894141972 0.0313325646 0.0390970000 1323244877 0 402718720 0.0123812072 -0.1807791144 -0.2294279635 3120 1311867822.6315131187 0.2004362345 0.1450710620 0.2894141972 0.0313275461 0.0375530000 1323248133 0 402718720 0.0126332268 -0.1798221916 -0.2308496386 3121 1311867822.6634640694 0.1990240365 0.1450883491 0.2894141972 0.0313227948 0.0406930000 1323251277 0 402718720 0.0132319164 -0.1792264879 -0.2318055183 3122 1311867822.6954870224 0.1980731040 0.1451053205 0.2894141972 0.0313178829 0.0721440000 1323254421 0 402718720 0.0121192383 -0.1796062142 -0.2315364629 3123 1311867822.7317390442 0.1962155402 0.1451216862 0.2894141972 0.0313129376 0.0422950000 1323257621 0 402718720 0.0114896353 -0.1782447100 -0.2322636396 3124 1311867822.7634871006 0.1953727305 0.1451377717 0.2894141972 0.0313082529 0.0405450000 1323260765 0 402718720 0.0112991929 -0.1777334958 -0.2325798124 3125 1311867822.7954308987 0.1953896880 0.1451538523 0.2894141972 0.0313033337 0.0385380000 1323263909 0 402718720 0.0107921390 -0.1780502349 -0.2315550148 3126 1311867822.8314750195 0.1940620095 0.1451694979 0.2894141972 0.0312983874 0.0393780000 1323267165 0 402718720 0.0093427403 -0.1763066798 -0.2318232059 3127 1311867822.8634629250 0.1949903518 0.1451854304 0.2894141972 0.0312938411 0.0387310000 1323270309 0 402718720 0.0096170176 -0.1765863895 -0.2316270024 3128 1311867822.8955349922 0.1953524500 0.1452014684 0.2894141972 0.0312889540 0.0362880000 1323273341 0 402718720 0.0102301510 -0.1764779091 -0.2318433076 3129 1311867822.9318330288 0.1956674457 0.1452175969 0.2894141972 0.0312841478 0.0391140000 1323276653 0 402718720 0.0088965921 -0.1763796508 -0.2312437147 3130 1311867822.9635109901 0.1949322373 0.1452334802 0.2894141972 0.0312793232 0.0357500000 1323279797 0 402718720 0.0083214743 -0.1759839058 -0.2295403033 3131 1311867822.9979970455 0.1956218481 0.1452495736 0.2894141972 0.0312744581 0.0395940000 1323283053 0 402718720 0.0082510812 -0.1762738973 -0.2291510403 3132 1311867823.0344979763 0.1960956752 0.1452658079 0.2894141972 0.0312696043 0.0384740000 1323286197 0 402718720 0.0080994545 -0.1766869873 -0.2286216468 3133 1311867823.0634639263 0.1959551871 0.1452819871 0.2894141972 0.0312647553 0.0679470000 1323289229 0 402718720 0.0083365608 -0.1766162366 -0.2284841985 3134 1311867823.0970849991 0.1953103095 0.1452979502 0.2894141972 0.0312597746 0.0381470000 1323292373 0 402718720 0.0069705630 -0.1765281558 -0.2267303616 3135 1311867823.1313869953 0.1962193102 0.1453141931 0.2894141972 0.0312550346 0.0410930000 1323295629 0 402718720 0.0074639246 -0.1777399331 -0.2262398601 3136 1311867823.1635200977 0.1961353272 0.1453303988 0.2894141972 0.0312505758 0.0402730000 1323298773 0 402718720 0.0072971215 -0.1779062152 -0.2264158279 3137 1311867823.1954009533 0.1957087368 0.1453464582 0.2894141972 0.0312466676 0.0367420000 1323301861 0 402718720 0.0060352469 -0.1775452942 -0.2256978154 3138 1311867823.2316908836 0.1962230653 0.1453626713 0.2894141972 0.0312417081 0.0405870000 1323305229 0 402718720 0.0056332299 -0.1789720058 -0.2237804979 3139 1311867823.2635869980 0.1959224641 0.1453787782 0.2894141972 0.0312372664 0.0400960000 1323308373 0 402718720 0.0056629898 -0.1784407049 -0.2242881507 3140 1311867823.2955200672 0.1953971237 0.1453947076 0.2894141972 0.0312326428 0.0368780000 1323311461 0 402718720 0.0056071333 -0.1774629951 -0.2257324010 3141 1311867823.3330919743 0.1954477727 0.1454106430 0.2894141972 0.0312276924 0.0397230000 1323314773 0 402718720 0.0043295599 -0.1784719676 -0.2229099423 3142 1311867823.3635790348 0.1957887709 0.1454266768 0.2894141972 0.0312227344 0.0403620000 1323317917 0 402718720 0.0037536293 -0.1788749099 -0.2228146046 3143 1311867823.3954129219 0.1949151456 0.1454424224 0.2894141972 0.0312178119 0.0369300000 1323321005 0 402718720 0.0040505514 -0.1771573126 -0.2243586630 3144 1311867823.4318161011 0.1948463768 0.1454581362 0.2894141972 0.0312130498 0.0740580000 1323324317 0 402718720 0.0035368805 -0.1773032546 -0.2231957614 3145 1311867823.4634220600 0.1949404180 0.1454738698 0.2894141972 0.0312086783 0.0386870000 1323327461 0 402718720 0.0024521684 -0.1772153825 -0.2222279459 3146 1311867823.4969649315 0.1936715692 0.1454891901 0.2894141972 0.0312040469 0.0389430000 1323330605 0 402718720 0.0015389229 -0.1755963266 -0.2223418802 3147 1311867823.5356218815 0.1954934448 0.1455050796 0.2894141972 0.0311992810 0.0418760000 1323333917 0 402718720 0.0025444473 -0.1772328466 -0.2221879810 3148 1311867823.5636498928 0.1955724508 0.1455209841 0.2894141972 0.0311947078 0.0386920000 1323337005 0 402718720 0.0027747257 -0.1773536205 -0.2217467278 3149 1311867823.5974490643 0.1945648789 0.1455365585 0.2894141972 0.0311897630 0.0691790000 1323340149 0 402718720 0.0015249093 -0.1760659069 -0.2215710431 3150 1311867823.6316640377 0.1937559843 0.1455518663 0.2894141972 0.0311872268 0.0367890000 1323343405 0 402718720 0.0005601851 -0.1743482500 -0.2220300585 3151 1311867823.6636750698 0.1946790665 0.1455674573 0.2894141972 0.0311834487 0.0373070000 1323346549 0 402718720 0.0005185080 -0.1752141118 -0.2212837934 3152 1311867823.6956110001 0.1945172697 0.1455829870 0.2894141972 0.0311785747 0.0370030000 1323349637 0 402718720 -0.0001116581 -0.1750834733 -0.2198673338 3153 1311867823.7316160202 0.1940605789 0.1455983621 0.2894141972 0.0311737319 0.0393810000 1323352949 0 402718720 -0.0004129607 -0.1736694276 -0.2207644284 3154 1311867823.7635159492 0.1943472028 0.1456138183 0.2894141972 0.0311688544 0.0484340000 1323356093 0 402718720 -0.0008186958 -0.1743144393 -0.2190718204 3155 1311867823.7964050770 0.1950325966 0.1456294819 0.2894141972 0.0311639270 0.0387990000 1323359181 0 402718720 -0.0003540850 -0.1750689000 -0.2183746845 3156 1311867823.8316709995 0.1948608160 0.1456450812 0.2894141972 0.0311590120 0.0382460000 1323362493 0 402718720 -0.0007814218 -0.1747888774 -0.2179590315 3157 1311867823.8635869026 0.1942159384 0.1456604664 0.2894141972 0.0311541285 0.0379250000 1323365637 0 402718720 -0.0013620307 -0.1736289710 -0.2185742259 3158 1311867823.8993189335 0.1953461766 0.1456761996 0.2894141972 0.0311494053 0.0371610000 1323368781 0 402718720 -0.0008199535 -0.1747054160 -0.2175439149 3159 1311867823.9316000938 0.1961648762 0.1456921821 0.2894141972 0.0311469708 0.0390260000 1323372037 0 402718720 -0.0004700341 -0.1752308756 -0.2177595049 3160 1311867823.9639530182 0.1955597997 0.1457079630 0.2894141972 0.0311430506 0.0505760000 1323375237 0 402718720 -0.0011253016 -0.1740732491 -0.2178947777 3161 1311867823.9956440926 0.1952764690 0.1457236443 0.2894141972 0.0311387123 0.0370370000 1323378269 0 402718720 -0.0016869444 -0.1737909466 -0.2170729935 3162 1311867824.0315599442 0.1961429119 0.1457395897 0.2894141972 0.0311339011 0.0352140000 1323381581 0 402718720 -0.0014032277 -0.1747776270 -0.2160340697 3163 1311867824.0634789467 0.1961552054 0.1457555288 0.2894141972 0.0311290465 0.0389060000 1323384725 0 402718720 -0.0016453889 -0.1741561145 -0.2166497260 3164 1311867824.0966229439 0.1957219094 0.1457713210 0.2894141972 0.0311241788 0.0371460000 1323387813 0 402718720 -0.0022369362 -0.1736450195 -0.2158902735 3165 1311867824.1315801144 0.1977812797 0.1457877538 0.2894141972 0.0311193609 0.0377900000 1323391125 0 402718720 -0.0024758249 -0.1763936877 -0.2138682902 3166 1311867824.1636250019 0.1966196150 0.1458038094 0.2894141972 0.0311144518 0.0693970000 1323394269 0 402718720 -0.0027004911 -0.1744883358 -0.2152534425 3167 1311867824.1974289417 0.1951310337 0.1458193848 0.2894141972 0.0311095722 0.0376390000 1323397413 0 402718720 -0.0035565931 -0.1723606139 -0.2154370248 3168 1311867824.2314341068 0.1953217536 0.1458350105 0.2894141972 0.0311052809 0.0366870000 1323400613 0 402718720 -0.0044331565 -0.1730289459 -0.2129236013 3169 1311867824.2667050362 0.1959314197 0.1458508188 0.2894141972 0.0311004823 0.0379890000 1323403813 0 402718720 -0.0034499902 -0.1720481664 -0.2155766934 3170 1311867824.3015079498 0.1966885030 0.1458668559 0.2894141972 0.0310957250 0.0375200000 1323407013 0 402718720 -0.0039521139 -0.1719145626 -0.2152102739 3171 1311867824.3329520226 0.1968308687 0.1458829278 0.2894141972 0.0310908822 0.0370920000 1323410269 0 402718720 -0.0050886841 -0.1721151769 -0.2128165215 3172 1311867824.3655250072 0.1967152953 0.1458989532 0.2894141972 0.0310863282 0.0392320000 1323413357 0 402718720 -0.0044171074 -0.1703221053 -0.2147383094 3173 1311867824.3960471153 0.1965660453 0.1459149214 0.2894141972 0.0310815775 0.0394420000 1323416445 0 402718720 -0.0049194335 -0.1688627899 -0.2152208686 3174 1311867824.4315910339 0.1987146139 0.1459315564 0.2894141972 0.0310768752 0.0366170000 1323419701 0 402718720 -0.0052769547 -0.1697860062 -0.2141391188 3175 1311867824.4656419754 0.1971508563 0.1459476885 0.2894141972 0.0310721393 0.0393420000 1323422901 0 402718720 -0.0058319801 -0.1664593071 -0.2146709412 3176 1311867824.4978239536 0.1989653856 0.1459643817 0.2894141972 0.0310678783 0.0355660000 1323426045 0 402718720 -0.0056970073 -0.1679231673 -0.2124808133 3177 1311867824.5316801071 0.2001944631 0.1459814513 0.2894141972 0.0310632411 0.0355310000 1323429245 0 402718720 -0.0054600397 -0.1676911414 -0.2125487030 3178 1311867824.5658240318 0.1988592297 0.1459980900 0.2894141972 0.0310584897 0.0394760000 1323432445 0 402718720 -0.0057449453 -0.1653941572 -0.2119423002 3179 1311867824.5956490040 0.2006177902 0.1460152714 0.2894141972 0.0310537233 0.0386030000 1323435533 0 402718720 -0.0062114047 -0.1678636968 -0.2083930671 3180 1311867824.6318910122 0.1993598044 0.1460320464 0.2894141972 0.0310488761 0.0387220000 1323438845 0 402718720 -0.0058855144 -0.1648420542 -0.2103550881 3181 1311867824.6661429405 0.1986728162 0.1460485949 0.2894141972 0.0310442053 0.0391800000 1323441933 0 402718720 -0.0063054259 -0.1635997146 -0.2094618380 3182 1311867824.6979811192 0.1967995018 0.1460645443 0.2894141972 0.0310404594 0.0386980000 1323445077 0 402718720 -0.0071582696 -0.1610945612 -0.2091599107 3183 1311867824.7314980030 0.1963302344 0.1460803362 0.2894141972 0.0310368992 0.0388710000 1323448221 0 402718720 -0.0078283586 -0.1604562551 -0.2081424594 3184 1311867824.7639679909 0.1958517283 0.1460959679 0.2894141972 0.0310322258 0.0385390000 1323451421 0 402718720 -0.0077199945 -0.1591046453 -0.2086088508 3185 1311867824.7997510433 0.1986418217 0.1461124658 0.2894141972 0.0310275162 0.0389200000 1323454621 0 402718720 -0.0076168571 -0.1623214781 -0.2061924487 3186 1311867824.8315179348 0.1963594705 0.1461282370 0.2894141972 0.0310232553 0.0387570000 1323457821 0 402718720 -0.0076233866 -0.1594983637 -0.2066417485 3187 1311867824.8635060787 0.1950184107 0.1461435775 0.2894141972 0.0310184432 0.0383490000 1323460965 0 402718720 -0.0087646563 -0.1579455286 -0.2057847977 3188 1311867824.8995370865 0.1952217519 0.1461589722 0.2894141972 0.0310141927 0.0396030000 1323464165 0 402718720 -0.0090208510 -0.1579044014 -0.2050750405 3189 1311867824.9316530228 0.1952692866 0.1461743721 0.2894141972 0.0310093539 0.0487230000 1323467365 0 402718720 -0.0087360917 -0.1575068235 -0.2050652653 3190 1311867824.9636321068 0.1945955604 0.1461895512 0.2894141972 0.0310048828 0.0392640000 1323470509 0 402718720 -0.0095979655 -0.1571096331 -0.2035078108 3191 1311867824.9996089935 0.1944132596 0.1462046636 0.2894141972 0.0310002678 0.0378370000 1323473821 0 402718720 -0.0099917343 -0.1572149843 -0.2019955665 3192 1311867825.0316529274 0.1943066865 0.1462197331 0.2894141972 0.0309954754 0.0399250000 1323476909 0 402718720 -0.0095743472 -0.1570062786 -0.2022033930 3193 1311867825.0644080639 0.1945358068 0.1462348650 0.2894141972 0.0309906729 0.0403020000 1323479941 0 402718720 -0.0096426653 -0.1578285098 -0.2010976076 3194 1311867825.0997018814 0.1936278790 0.1462497031 0.2894141972 0.0309858264 0.0406000000 1323483253 0 402718720 -0.0098394109 -0.1566571146 -0.2017205507 3195 1311867825.1316909790 0.1922545433 0.1462641021 0.2894141972 0.0309810041 0.0752480000 1323486453 0 402718720 -0.0113570187 -0.1563397795 -0.1995914280 3196 1311867825.1636679173 0.1953055859 0.1462794468 0.2894141972 0.0309761902 0.0417620000 1323489597 0 402718720 -0.0111816032 -0.1610666066 -0.1962577254 3197 1311867825.1996359825 0.1952905804 0.1462947771 0.2894141972 0.0309713816 0.0407530000 1323492797 0 402718720 -0.0105673140 -0.1601907015 -0.1989448220 3198 1311867825.2316811085 0.1925913692 0.1463092539 0.2894141972 0.0309670139 0.0412310000 1323495997 0 402718720 -0.0118634496 -0.1575093418 -0.1987158209 3199 1311867825.2669949532 0.1933271736 0.1463239516 0.2894141972 0.0309623131 0.0416470000 1323499197 0 402718720 -0.0124988863 -0.1591998488 -0.1967277229 3200 1311867825.2996079922 0.1941645890 0.1463389018 0.2894141972 0.0309576407 0.0493960000 1323502453 0 402718720 -0.0118801529 -0.1593723148 -0.1984140873 3201 1311867825.3316459656 0.1925477087 0.1463533375 0.2894141972 0.0309528857 0.0407410000 1323505541 0 402718720 -0.0137417922 -0.1576719284 -0.1975325942 3202 1311867825.3635549545 0.1921300292 0.1463676338 0.2894141972 0.0309480819 0.0439270000 1323508685 0 402718720 -0.0148430020 -0.1580881029 -0.1952077895 3203 1311867825.3995220661 0.1932187825 0.1463822611 0.2894141972 0.0309434405 0.0415610000 1323511997 0 402718720 -0.0137348026 -0.1582814157 -0.1970600188 3204 1311867825.4329130650 0.1935998052 0.1463969981 0.2894141972 0.0309386177 0.0430790000 1323515085 0 402718720 -0.0142697394 -0.1586976647 -0.1964672506 3205 1311867825.4655640125 0.1933998615 0.1464116636 0.2894141972 0.0309338019 0.0412840000 1323518173 0 402718720 -0.0151001792 -0.1593349129 -0.1939937174 3206 1311867825.4996039867 0.1942967176 0.1464265997 0.2894141972 0.0309289847 0.0752640000 1323521373 0 402718720 -0.0150689948 -0.1601589769 -0.1938608736 3207 1311867825.5338060856 0.1942843199 0.1464415226 0.2894141972 0.0309242160 0.0407230000 1323524573 0 402718720 -0.0147588206 -0.1591465026 -0.1956789941 3208 1311867825.5637249947 0.1929092407 0.1464560075 0.2894141972 0.0309194233 0.0412220000 1323527661 0 402718720 -0.0157117173 -0.1577153802 -0.1951424181 3209 1311867825.5995988846 0.1925493181 0.1464703713 0.2894141972 0.0309146546 0.0399490000 1323530917 0 402718720 -0.0164777935 -0.1574197859 -0.1943071932 3210 1311867825.6340339184 0.1929088980 0.1464848381 0.2894141972 0.0309098530 0.0400910000 1323534061 0 402718720 -0.0163661689 -0.1572511196 -0.1951377243 3211 1311867825.6636710167 0.1938013881 0.1464995739 0.2894141972 0.0309052200 0.0780890000 1323537149 0 402718720 -0.0165785588 -0.1583117843 -0.1947471052 3212 1311867825.6997060776 0.1942851990 0.1465144511 0.2894141972 0.0309006191 0.0394540000 1323540461 0 402718720 -0.0171612315 -0.1594783813 -0.1925775111 3213 1311867825.7345159054 0.1941664964 0.1465292821 0.2894141972 0.0308958144 0.0405090000 1323543605 0 402718720 -0.0171831697 -0.1587943584 -0.1936186403 3214 1311867825.7654080391 0.1925266981 0.1465435937 0.2894141972 0.0308910710 0.0418830000 1323546693 0 402718720 -0.0174295697 -0.1568744630 -0.1940931082 3215 1311867825.7998030186 0.1948017925 0.1465586040 0.2894141972 0.0308863179 0.0418240000 1323550061 0 402718720 -0.0176514052 -0.1603924930 -0.1917734742 3216 1311867825.8355770111 0.1957501471 0.1465738999 0.2894141972 0.0308816471 0.0415860000 1323553261 0 402718720 -0.0167839658 -0.1606780738 -0.1939704865 3217 1311867825.8656499386 0.1933077574 0.1465884270 0.2894141972 0.0308769779 0.0415380000 1323556349 0 402718720 -0.0175584462 -0.1579449028 -0.1942509264 3218 1311867825.8996019363 0.1938603073 0.1466031169 0.2894141972 0.0308721815 0.0393300000 1323559605 0 402718720 -0.0183733739 -0.1596676558 -0.1918044090 3219 1311867825.9338159561 0.1953274310 0.1466182534 0.2894141972 0.0308674207 0.0406000000 1323562749 0 402718720 -0.0176680796 -0.1604799181 -0.1935572326 3220 1311867825.9640550613 0.1937531978 0.1466328915 0.2894141972 0.0308627023 0.0409580000 1323565893 0 402718720 -0.0176776070 -0.1581605822 -0.1947824061 3221 1311867825.9996759892 0.1942517906 0.1466476754 0.2894141972 0.0308579382 0.0385290000 1323569093 0 402718720 -0.0188295636 -0.1597019881 -0.1921200007 3222 1311867826.0327780247 0.1948517710 0.1466626363 0.2894141972 0.0308532007 0.0395430000 1323572237 0 402718720 -0.0182218347 -0.1592226774 -0.1945449859 3223 1311867826.0636789799 0.1940671504 0.1466773445 0.2894141972 0.0308484485 0.0505900000 1323575381 0 402718720 -0.0187163502 -0.1575709134 -0.1957222670 3224 1311867826.1009249687 0.1941923052 0.1466920824 0.2894141972 0.0308437017 0.0415040000 1323578693 0 402718720 -0.0188448690 -0.1579100043 -0.1943833232 3225 1311867826.1333270073 0.1950744838 0.1467070847 0.2894141972 0.0308389295 0.0390820000 1323581837 0 402718720 -0.0189109668 -0.1585598439 -0.1946635693 3226 1311867826.1658940315 0.1938162595 0.1467216877 0.2894141972 0.0308341673 0.0413930000 1323585037 0 402718720 -0.0190414377 -0.1568141878 -0.1956137121 3227 1311867826.1998670101 0.1940889210 0.1467363661 0.2894141972 0.0308294311 0.0411880000 1323588237 0 402718720 -0.0194555521 -0.1577362567 -0.1943202913 3228 1311867826.2344970703 0.1958119422 0.1467515692 0.2894141972 0.0308247036 0.0381650000 1323591381 0 402718720 -0.0192258395 -0.1598335057 -0.1940744221 3229 1311867826.2638049126 0.1957328767 0.1467667384 0.2894141972 0.0308200801 0.0411950000 1323594469 0 402718720 -0.0194346868 -0.1602143943 -0.1935716867 3230 1311867826.3011031151 0.1962017566 0.1467820433 0.2894141972 0.0308154072 0.0541980000 1323597725 0 402718720 -0.0197573397 -0.1613434702 -0.1922827065 3231 1311867826.3321890831 0.1974025369 0.1467977105 0.2894141972 0.0308108525 0.0424760000 1323600645 0 402718720 -0.0194904320 -0.1628913432 -0.1921632737 3232 1311867826.3637928963 0.1973981708 0.1468133666 0.2894141972 0.0308061734 0.0416150000 1323603789 0 402718720 -0.0190942828 -0.1620393842 -0.1941857338 3233 1311867826.3997180462 0.1960527450 0.1468285968 0.2894141972 0.0308014204 0.0413140000 1323607045 0 402718720 -0.0196594410 -0.1608441621 -0.1938214302 3234 1311867826.4321649075 0.1964288056 0.1468439339 0.2894141972 0.0307966744 0.0410410000 1323610189 0 402718720 -0.0198909286 -0.1613291353 -0.1935521066 3235 1311867826.4641530514 0.1953687370 0.1468589338 0.2894141972 0.0307919447 0.0424080000 1323613389 0 402718720 -0.0202787146 -0.1596398801 -0.1947378069 3236 1311867826.5007300377 0.1945817769 0.1468736813 0.2894141972 0.0307872056 0.0418780000 1323616645 0 402718720 -0.0209461674 -0.1589263380 -0.1941201240 3237 1311867826.5319769382 0.1960729361 0.1468888804 0.2894141972 0.0307824960 0.0396290000 1323619733 0 402718720 -0.0202626847 -0.1599215418 -0.1951540112 3238 1311867826.5638489723 0.1954749823 0.1469038853 0.2894141972 0.0307777579 0.0379490000 1323622933 0 402718720 -0.0208081100 -0.1595132053 -0.1948894113 3239 1311867826.6006839275 0.1953087300 0.1469188297 0.2894141972 0.0307730387 0.0389190000 1323626189 0 402718720 -0.0213918872 -0.1597561985 -0.1934956908 3240 1311867826.6315939426 0.1957517117 0.1469339016 0.2894141972 0.0307682988 0.0400250000 1323629221 0 402718720 -0.0212184414 -0.1595429778 -0.1946796328 3241 1311867826.6638610363 0.1951161325 0.1469487681 0.2894141972 0.0307636051 0.0409230000 1323632365 0 402718720 -0.0214063246 -0.1588378400 -0.1951957047 3242 1311867826.6997880936 0.1944262832 0.1469634126 0.2894141972 0.0307588647 0.0791200000 1323635565 0 402718720 -0.0218073446 -0.1579440534 -0.1952596605 3243 1311867826.7349400520 0.1941985339 0.1469779778 0.2894141972 0.0307541430 0.0415910000 1323638821 0 402718720 -0.0230420437 -0.1590101272 -0.1923552305 3244 1311867826.7678170204 0.1959642619 0.1469930784 0.2894141972 0.0307494296 0.0399560000 1323641909 0 402718720 -0.0224358235 -0.1601788551 -0.1939433366 3245 1311867826.8019490242 0.1955094934 0.1470080295 0.2894141972 0.0307447377 0.0412920000 1323645221 0 402718720 -0.0222271420 -0.1601370722 -0.1941652596 3246 1311867826.8324730396 0.1970140785 0.1470234350 0.2894141972 0.0307408191 0.0425590000 1323648253 0 402718720 -0.0223613661 -0.1624414176 -0.1924860030 3247 1311867826.8645749092 0.1972553581 0.1470389052 0.2894141972 0.0307362799 0.0415490000 1323651341 0 402718720 -0.0224372949 -0.1630107015 -0.1922900528 3248 1311867826.9008030891 0.1974448413 0.1470544243 0.2894141972 0.0307315507 0.0418990000 1323654597 0 402718720 -0.0224169791 -0.1632203609 -0.1926617622 3249 1311867826.9319059849 0.1972603649 0.1470698770 0.2894141972 0.0307272120 0.0417880000 1323657629 0 402718720 -0.0221850220 -0.1627373546 -0.1937208921 3250 1311867826.9639348984 0.1966486275 0.1470851320 0.2894141972 0.0307225504 0.0405990000 1323660661 0 402718720 -0.0231665336 -0.1625520438 -0.1925206333 3251 1311867827.0005419254 0.1963723749 0.1471002927 0.2894141972 0.0307178521 0.0416360000 1323663861 0 402718720 -0.0230427627 -0.1618905216 -0.1938058734 3252 1311867827.0317308903 0.1964918375 0.1471154807 0.2894141972 0.0307132190 0.0414460000 1323666949 0 402718720 -0.0231317282 -0.1620119810 -0.1937787980 3253 1311867827.0653018951 0.1963928640 0.1471306290 0.2894141972 0.0307087351 0.0417530000 1323670037 0 402718720 -0.0237994511 -0.1620721072 -0.1933675110 3254 1311867827.0995659828 0.1968097836 0.1471458961 0.2894141972 0.0307042716 0.0405930000 1323673069 0 402718720 -0.0231812634 -0.1617820561 -0.1952661127 3255 1311867827.1319448948 0.1964937299 0.1471610567 0.2894141972 0.0306995777 0.0423240000 1323676045 0 402718720 -0.0234247018 -0.1615169048 -0.1952067316 3256 1311867827.1636159420 0.1965894550 0.1471762375 0.2894141972 0.0306949452 0.0411800000 1323679245 0 402718720 -0.0239864700 -0.1624361128 -0.1937775463 3257 1311867827.2006959915 0.1984404176 0.1471919771 0.2894141972 0.0306904600 0.0424780000 1323682557 0 402718720 -0.0234428383 -0.1642751843 -0.1940025836 3258 1311867827.2315700054 0.1982488632 0.1472076484 0.2894141972 0.0306857921 0.0430360000 1323685589 0 402718720 -0.0231420510 -0.1636800617 -0.1955043226 3259 1311867827.2655858994 0.1980546266 0.1472232504 0.2894141972 0.0306811798 0.0793720000 1323688565 0 402718720 -0.0233593807 -0.1633358896 -0.1950628459 3260 1311867827.2999041080 0.1991153657 0.1472391682 0.2894141972 0.0306767217 0.0416070000 1323691821 0 402718720 -0.0229442120 -0.1642134190 -0.1957522929 3261 1311867827.3331921101 0.1973782182 0.1472545436 0.2894141972 0.0306720484 0.0430910000 1323694909 0 402718720 -0.0228086431 -0.1610579640 -0.1984969079 3262 1311867827.3664519787 0.1968306899 0.1472697417 0.2894141972 0.0306673814 0.0414270000 1323698053 0 402718720 -0.0236463901 -0.1611069441 -0.1969725639 3263 1311867827.4022359848 0.1975883245 0.1472851626 0.2894141972 0.0306628634 0.0394380000 1323701365 0 402718720 -0.0235599075 -0.1620626152 -0.1964447945 3264 1311867827.4316461086 0.1965600550 0.1473002591 0.2894141972 0.0306582234 0.0411880000 1323704397 0 402718720 -0.0238081757 -0.1603420675 -0.1977579743 3265 1311867827.4660739899 0.1964781284 0.1473153212 0.2894141972 0.0306535570 0.0421490000 1323707597 0 402718720 -0.0240615830 -0.1602707356 -0.1971604824 3266 1311867827.5022079945 0.1984539032 0.1473309791 0.2894141972 0.0306490680 0.0420500000 1323710909 0 402718720 -0.0237598829 -0.1631314009 -0.1958725303 3267 1311867827.5346701145 0.1977239847 0.1473464040 0.2894141972 0.0306444143 0.0419550000 1323713997 0 402718720 -0.0234694798 -0.1616382301 -0.1980757117 3268 1311867827.5638930798 0.1964393258 0.1473614263 0.2894141972 0.0306397542 0.0412930000 1323717141 0 402718720 -0.0243860856 -0.1613203585 -0.1956945360 3269 1311867827.6014149189 0.1996500492 0.1473774216 0.2894141972 0.0306351669 0.0407580000 1323720397 0 402718720 -0.0233507659 -0.1646959186 -0.1954959184 3270 1311867827.6328229904 0.1987604201 0.1473931350 0.2894141972 0.0306305160 0.0775400000 1323723541 0 402718720 -0.0230085440 -0.1625128388 -0.1985077113 3271 1311867827.6636641026 0.1965107918 0.1474081511 0.2894141972 0.0306259147 0.0420200000 1323726741 0 402718720 -0.0244268794 -0.1607478559 -0.1967088580 3272 1311867827.7023220062 0.1981059164 0.1474236455 0.2894141972 0.0306212997 0.0409040000 1323729997 0 402718720 -0.0241097994 -0.1625714153 -0.1963755637 3273 1311867827.7343409061 0.1979081333 0.1474390701 0.2894141972 0.0306167083 0.0409970000 1323733141 0 402718720 -0.0236428585 -0.1612406522 -0.1988086700 3274 1311867827.7669200897 0.1965629458 0.1474540743 0.2894141972 0.0306124127 0.0387460000 1323736229 0 402718720 -0.0244625900 -0.1606794298 -0.1971040368 3275 1311867827.8009700775 0.1977171600 0.1474694218 0.2894141972 0.0306077453 0.0409440000 1323739429 0 402718720 -0.0245132502 -0.1624661833 -0.1953445673 3276 1311867827.8316879272 0.1979163587 0.1474848208 0.2894141972 0.0306030911 0.0400280000 1323742573 0 402718720 -0.0237855818 -0.1617370993 -0.1977934688 3277 1311867827.8644020557 0.1971943825 0.1474999900 0.2894141972 0.0305984334 0.0421410000 1323745773 0 402718720 -0.0239124633 -0.1612037569 -0.1974329501 3278 1311867827.9007890224 0.1984667480 0.1475155381 0.2894141972 0.0305940532 0.0413570000 1323748917 0 402718720 -0.0243597757 -0.1632150859 -0.1952102333 3279 1311867827.9316790104 0.1975828260 0.1475308072 0.2894141972 0.0305896328 0.0412550000 1323752117 0 402718720 -0.0241437927 -0.1621215940 -0.1966130584 3280 1311867827.9637460709 0.1973655522 0.1475460007 0.2894141972 0.0305855088 0.0412740000 1323755205 0 402718720 -0.0243616104 -0.1619990021 -0.1958080083 3281 1311867827.9999580383 0.1994471401 0.1475618194 0.2894141972 0.0305809580 0.0427010000 1323758517 0 402718720 -0.0237362646 -0.1645081937 -0.1954636723 3282 1311867828.0320019722 0.1990393996 0.1475775042 0.2894141972 0.0305763285 0.0414960000 1323761605 0 402718720 -0.0235745311 -0.1637370884 -0.1965250522 3283 1311867828.0638809204 0.1969618052 0.1475925467 0.2894141972 0.0305718552 0.0415040000 1323764749 0 402718720 -0.0245666280 -0.1623480022 -0.1952095032 3284 1311867828.1003139019 0.1983044297 0.1476079888 0.2894141972 0.0305672090 0.0415760000 1323768061 0 402718720 -0.0241848864 -0.1638108343 -0.1951941103 3285 1311867828.1317639351 0.1988629401 0.1476235915 0.2894141972 0.0305626569 0.0413140000 1323771205 0 402718720 -0.0230428819 -0.1635325551 -0.1977669448 3286 1311867828.1636569500 0.1970262080 0.1476386258 0.2894141972 0.0305582093 0.0399350000 1323774293 0 402718720 -0.0240671150 -0.1621649265 -0.1962137669 3287 1311867828.2014439106 0.1969762146 0.1476536357 0.2894141972 0.0305550152 0.0388650000 1323777605 0 402718720 -0.0247484110 -0.1622681469 -0.1948347092 3288 1311867828.2316999435 0.1970440000 0.1476686571 0.2894141972 0.0305506677 0.0413030000 1323780749 0 402718720 -0.0235654116 -0.1612429321 -0.1978035271 3289 1311867828.2639598846 0.1971383840 0.1476836980 0.2894141972 0.0305460881 0.0432200000 1323783837 0 402718720 -0.0240182262 -0.1616636813 -0.1963851452 3290 1311867828.3008370399 0.1977649182 0.1476989203 0.2894141972 0.0305415167 0.0397330000 1323787149 0 402718720 -0.0242799316 -0.1628662348 -0.1940449625 ================================================ FILE: icra2018_results/1080/violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 10:21:34 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 -nan 0.0170010000 96489748 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0611951873 0.0597236156 0.0611951873 0.0088799139 0.0399800000 125232913 0 402718720 -0.0043297815 0.0014842154 -0.0000169428 3 1311867170.5264289379 0.0625329837 0.0606600717 0.0625329837 0.0068035834 0.0386780000 128505777 0 402718720 -0.0085119465 0.0024628250 -0.0014092552 4 1311867170.5623490810 0.0622939393 0.0610685386 0.0625329837 0.0056811755 0.0276630000 128509433 0 402718720 -0.0138620259 0.0014397150 -0.0037232086 5 1311867170.5942170620 0.0655072331 0.0619562775 0.0655072331 0.0068681791 0.0325970000 128512937 0 402718720 -0.0167324785 0.0025816576 -0.0027470735 6 1311867170.6260869503 0.0637080818 0.0622482449 0.0655072331 0.0065573622 0.0363030000 128516881 0 402718720 -0.0160029121 0.0008914011 -0.0052572438 7 1311867170.6621398926 0.0643696859 0.0625513079 0.0655072331 0.0060801545 0.0316070000 128520193 0 402718720 -0.0173481070 0.0008073251 -0.0061638290 8 1311867170.6942050457 0.0630642474 0.0626154253 0.0655072331 0.0060168364 0.0320210000 128523281 0 402718720 -0.0195525996 -0.0026746783 -0.0083052265 9 1311867170.7263879776 0.0669780448 0.0631001608 0.0669780448 0.0067878896 0.0360290000 128527257 0 402718720 -0.0230517294 0.0008078270 -0.0076910476 10 1311867170.7620189190 0.0720820874 0.0639983535 0.0720820874 0.0072644236 0.0373470000 128532169 0 402718720 -0.0308083314 0.0007243438 -0.0061809635 11 1311867170.7941920757 0.0731963813 0.0648345378 0.0731963813 0.0070199748 0.0370800000 128535201 0 402718720 -0.0311646946 -0.0008255136 -0.0065222275 12 1311867170.8262820244 0.0743731856 0.0656294251 0.0743731856 0.0068392879 0.0380930000 128538401 0 402718720 -0.0356335901 -0.0066757249 -0.0075357012 13 1311867170.8622210026 0.0702481493 0.0659847116 0.0743731856 0.0085761807 0.0396100000 128541657 0 402718720 -0.0379895791 -0.0209692419 -0.0119389491 14 1311867170.8943779469 0.0707807615 0.0663272866 0.0743731856 0.0085043258 0.0496720000 140886357 0 402718720 -0.0410090275 -0.0297214016 -0.0145569192 15 1311867170.9263520241 0.0709713474 0.0666368907 0.0743731856 0.0082744733 0.0333440000 144549165 0 402718720 -0.0409427062 -0.0344403610 -0.0167431887 16 1311867170.9621469975 0.0737774819 0.0670831776 0.0743731856 0.0081058069 0.0260820000 147744613 0 402718720 -0.0462719798 -0.0369575806 -0.0185625441 17 1311867170.9942629337 0.0731934384 0.0674426047 0.0743731856 0.0079529208 0.0218900000 147749365 0 402718720 -0.0456465185 -0.0410738178 -0.0214083456 18 1311867171.0262739658 0.0743117705 0.0678242250 0.0743731856 0.0077355994 0.0232370000 147755765 0 402718720 -0.0465738960 -0.0459876359 -0.0232499503 19 1311867171.0623519421 0.0763340667 0.0682721114 0.0763340667 0.0079400082 0.0250550000 147759021 0 402718720 -0.0495061167 -0.0503235795 -0.0250858832 20 1311867171.0942349434 0.0749490187 0.0686059568 0.0763340667 0.0077689801 0.0204800000 147762109 0 402718720 -0.0463495478 -0.0516512245 -0.0273138136 21 1311867171.1262509823 0.0768921003 0.0690005351 0.0768921003 0.0075938342 0.0219090000 147765309 0 402718720 -0.0486747809 -0.0552867427 -0.0285563860 22 1311867171.1622469425 0.0770392567 0.0693659315 0.0770392567 0.0075736327 0.0220080000 147768565 0 402718720 -0.0471798033 -0.0560176037 -0.0297735911 23 1311867171.1942689419 0.0742472485 0.0695781627 0.0770392567 0.0081154970 0.0246480000 147771653 0 402718720 -0.0427074730 -0.0551667437 -0.0308411811 24 1311867171.2262530327 0.0747612640 0.0697941252 0.0770392567 0.0080552573 0.0309420000 147774853 0 402718720 -0.0390083753 -0.0576155335 -0.0319347046 25 1311867171.2622439861 0.0723201707 0.0698951671 0.0770392567 0.0078921074 0.0307590000 147778109 0 402718720 -0.0335536115 -0.0559857264 -0.0337400511 26 1311867171.2943410873 0.0699807033 0.0698984569 0.0770392567 0.0078273367 0.0297000000 147781141 0 402718720 -0.0279415287 -0.0559061058 -0.0354752131 27 1311867171.3263869286 0.0707499012 0.0699299919 0.0770392567 0.0078048296 0.0351130000 147784341 0 402718720 -0.0255335420 -0.0571478419 -0.0365507379 28 1311867171.3622460365 0.0701091513 0.0699363904 0.0770392567 0.0077212450 0.0305870000 147787597 0 402718720 -0.0248703640 -0.0546034649 -0.0377807766 29 1311867171.3941431046 0.0708027929 0.0699662664 0.0770392567 0.0076366893 0.0301690000 147790685 0 402718720 -0.0256463680 -0.0528603829 -0.0387396589 30 1311867171.4262878895 0.0757638067 0.0701595177 0.0770392567 0.0076153850 0.0288660000 147793885 0 402718720 -0.0312302541 -0.0568575487 -0.0384552740 31 1311867171.4622440338 0.0752899200 0.0703250146 0.0770392567 0.0075318090 0.0299330000 147797141 0 402718720 -0.0310276020 -0.0570071787 -0.0407782719 32 1311867171.4944040775 0.0756201297 0.0704904869 0.0770392567 0.0074284273 0.0273860000 147800229 0 402718720 -0.0315958448 -0.0569950268 -0.0423606113 33 1311867171.5261778831 0.0783102959 0.0707274508 0.0783102959 0.0073570791 0.0266050000 147806757 0 402718720 -0.0359661169 -0.0582591258 -0.0428717323 34 1311867171.5622971058 0.0758669823 0.0708786135 0.0783102959 0.0073033521 0.0257730000 147816413 0 402718720 -0.0341632999 -0.0567955300 -0.0449160933 35 1311867171.5942931175 0.0745458975 0.0709833931 0.0783102959 0.0072467840 0.0256550000 147819501 0 402718720 -0.0319016948 -0.0572407693 -0.0458617210 36 1311867171.6263399124 0.0767595544 0.0711438420 0.0783102959 0.0071648368 0.0245870000 147822701 0 402718720 -0.0365749635 -0.0578234605 -0.0458032154 37 1311867171.6622560024 0.0777161494 0.0713214719 0.0783102959 0.0070877837 0.0251430000 147825957 0 402718720 -0.0398722738 -0.0571330152 -0.0461695231 38 1311867171.6943440437 0.0787850991 0.0715178832 0.0787850991 0.0070855034 0.0254920000 147829045 0 402718720 -0.0421338491 -0.0565172583 -0.0457830988 39 1311867171.7262439728 0.0800679922 0.0717371167 0.0800679922 0.0070245672 0.0278350000 147832245 0 402718720 -0.0462787598 -0.0568481684 -0.0458018109 40 1311867171.7621190548 0.0815764293 0.0719830995 0.0815764293 0.0069478329 0.0232090000 147835501 0 402718720 -0.0494890325 -0.0580132939 -0.0457059778 41 1311867171.7941710949 0.0802326724 0.0721843086 0.0815764293 0.0069370489 0.0242190000 147838589 0 402718720 -0.0499786809 -0.0592764802 -0.0467998907 42 1311867171.8262550831 0.0800725967 0.0723721250 0.0815764293 0.0068624351 0.0256230000 147841789 0 402718720 -0.0513798594 -0.0601545908 -0.0478641130 43 1311867171.8623590469 0.0837573409 0.0726368975 0.0837573409 0.0068500017 0.0282140000 147845045 0 402718720 -0.0596070290 -0.0597576648 -0.0468740128 44 1311867171.8944430351 0.0843883455 0.0729039758 0.0843883455 0.0070121723 0.0306920000 147848189 0 402718720 -0.0642620474 -0.0578771345 -0.0475776494 45 1311867171.9262220860 0.0849432573 0.0731715154 0.0849432573 0.0069630560 0.0299350000 147851333 0 402718720 -0.0675552413 -0.0581274480 -0.0474875681 46 1311867171.9624669552 0.0846608803 0.0734212842 0.0849432573 0.0069622306 0.0312880000 147854589 0 402718720 -0.0711851716 -0.0562017560 -0.0478309579 47 1311867171.9946711063 0.0851720646 0.0736713008 0.0851720646 0.0069907511 0.0313800000 147857733 0 402718720 -0.0749432221 -0.0547620170 -0.0474770926 48 1311867172.0262680054 0.0855315402 0.0739183892 0.0855315402 0.0071380568 0.0309430000 147860877 0 402718720 -0.0790999457 -0.0530101433 -0.0470562279 49 1311867172.0622880459 0.0857881457 0.0741606291 0.0857881457 0.0070929494 0.0315780000 147864133 0 402718720 -0.0831968263 -0.0512748659 -0.0462008230 50 1311867172.0941960812 0.0872563273 0.0744225430 0.0872563273 0.0070313037 0.0326920000 147867277 0 402718720 -0.0884909332 -0.0512325726 -0.0449495688 51 1311867172.1263689995 0.0888916999 0.0747062520 0.0888916999 0.0070975720 0.0322820000 147870421 0 402718720 -0.0935319811 -0.0501836278 -0.0438879840 52 1311867172.1623349190 0.0889943093 0.0749810223 0.0889943093 0.0070597619 0.0335610000 147873677 0 402718720 -0.0973723009 -0.0492177643 -0.0433914401 53 1311867172.1944270134 0.0888062268 0.0752418753 0.0889943093 0.0069917191 0.0700700000 166713041 0 402718720 -0.1000631154 -0.0477769636 -0.0429404974 54 1311867172.2264409065 0.0850049630 0.0754226732 0.0889943093 0.0070288227 0.0350370000 170375393 0 402718720 -0.0963891074 -0.0454376228 -0.0435392074 55 1311867172.2622280121 0.0842055678 0.0755823622 0.0889943093 0.0069662083 0.0218230000 173570841 0 402718720 -0.0986094549 -0.0439809225 -0.0432531871 56 1311867172.2944829464 0.0848772526 0.0757483424 0.0889943093 0.0069056308 0.0223590000 173573985 0 402718720 -0.1016395912 -0.0428900756 -0.0423469134 57 1311867172.3263380527 0.0858315527 0.0759252408 0.0889943093 0.0068868288 0.0222860000 173577129 0 402718720 -0.1067502201 -0.0411936641 -0.0419528373 58 1311867172.3624010086 0.0878424048 0.0761307091 0.0889943093 0.0068549753 0.0218600000 173580385 0 402718720 -0.1113858894 -0.0403871760 -0.0404853337 59 1311867172.3942890167 0.0877584144 0.0763277889 0.0889943093 0.0068089805 0.0219260000 173583529 0 402718720 -0.1151293218 -0.0398391187 -0.0407212526 60 1311867172.4265220165 0.0906703994 0.0765668324 0.0906703994 0.0068562371 0.0230870000 173586673 0 402718720 -0.1195284352 -0.0397200137 -0.0393790789 61 1311867172.4623498917 0.0872871876 0.0767425759 0.0906703994 0.0068843242 0.0215620000 173589929 0 402718720 -0.1182159707 -0.0385833718 -0.0409772955 62 1311867172.4952669144 0.0892165527 0.0769437691 0.0906703994 0.0068734989 0.0226200000 173593017 0 402718720 -0.1214687824 -0.0393087827 -0.0400675423 63 1311867172.5263059139 0.0929648951 0.0771980727 0.0929648951 0.0068928564 0.0277200000 173596161 0 402718720 -0.1269822270 -0.0410280041 -0.0384640470 64 1311867172.5624930859 0.0905452967 0.0774066231 0.0929648951 0.0068512472 0.0242270000 173599417 0 402718720 -0.1271215379 -0.0396484584 -0.0404923111 65 1311867172.5945439339 0.0911529064 0.0776181043 0.0929648951 0.0068033276 0.0231920000 173609161 0 402718720 -0.1297828108 -0.0396780707 -0.0409086645 66 1311867172.6263699532 0.0925077200 0.0778437046 0.0929648951 0.0068139473 0.0319120000 173625161 0 402718720 -0.1336895674 -0.0389630161 -0.0414646268 67 1311867172.6624419689 0.0915153697 0.0780477593 0.0929648951 0.0067634592 0.0298490000 173628417 0 402718720 -0.1361292601 -0.0384332500 -0.0428076200 68 1311867172.6945450306 0.0924061909 0.0782589127 0.0929648951 0.0068369983 0.0287690000 173631561 0 402718720 -0.1388388872 -0.0370942131 -0.0428052917 69 1311867172.7263929844 0.0918960124 0.0784565518 0.0929648951 0.0068166652 0.0306850000 173634705 0 402718720 -0.1423047185 -0.0356843807 -0.0440043695 70 1311867172.7623739243 0.0934614763 0.0786709079 0.0934614763 0.0067787220 0.0325160000 173637961 0 402718720 -0.1482975036 -0.0341667309 -0.0438017733 71 1311867172.7944509983 0.0926329121 0.0788675558 0.0934614763 0.0067528007 0.0323130000 173641049 0 402718720 -0.1515183598 -0.0337428935 -0.0451979116 72 1311867172.8263089657 0.0922491029 0.0790534106 0.0934614763 0.0067400080 0.0321190000 173644249 0 402718720 -0.1543920934 -0.0337905362 -0.0466696844 73 1311867172.8632309437 0.0923173130 0.0792351079 0.0934614763 0.0066980928 0.0316190000 173647561 0 402718720 -0.1585760564 -0.0328900404 -0.0478744358 74 1311867172.8944649696 0.0928909183 0.0794196459 0.0934614763 0.0066556714 0.0326070000 173650593 0 402718720 -0.1616594344 -0.0330766477 -0.0481684171 75 1311867172.9263219833 0.0997578874 0.0796908225 0.0997578874 0.0066387879 0.0404420000 173653793 0 402718720 -0.1683888733 -0.0346184000 -0.0433423370 76 1311867172.9623310566 0.0982969254 0.0799356396 0.0997578874 0.0066005873 0.0320050000 173657049 0 402718720 -0.1689349264 -0.0331160203 -0.0452967323 77 1311867172.9945271015 0.0991052613 0.0801845957 0.0997578874 0.0065595589 0.0317080000 173660137 0 402718720 -0.1714790463 -0.0332214162 -0.0457963049 78 1311867173.0262629986 0.0985729620 0.0804203440 0.0997578874 0.0065221566 0.0329270000 173663281 0 402718720 -0.1723415703 -0.0340099521 -0.0465688445 79 1311867173.0624630451 0.0981543884 0.0806448256 0.0997578874 0.0064808275 0.0327780000 173666537 0 402718720 -0.1730518788 -0.0347113609 -0.0471608490 80 1311867173.0945179462 0.0999471769 0.0808861050 0.0999471769 0.0065088748 0.0330690000 173669681 0 402718720 -0.1756229252 -0.0348819867 -0.0465676896 81 1311867173.1267819405 0.0978423730 0.0810954416 0.0999471769 0.0065034939 0.0325560000 173672881 0 402718720 -0.1754915267 -0.0338214561 -0.0480747372 82 1311867173.1622309685 0.0976999328 0.0812979354 0.0999471769 0.0065005010 0.0330100000 173676137 0 402718720 -0.1771892458 -0.0331281647 -0.0486854278 83 1311867173.1943008900 0.0987719148 0.0815084653 0.0999471769 0.0064652435 0.0329610000 173679225 0 402718720 -0.1803708524 -0.0329284444 -0.0484980457 84 1311867173.2264449596 0.0972065777 0.0816953476 0.0999471769 0.0064466278 0.0329460000 173682369 0 402718720 -0.1811824590 -0.0315503776 -0.0492263697 85 1311867173.2622020245 0.0986577868 0.0818949057 0.0999471769 0.0064626873 0.0357020000 173685625 0 402718720 -0.1828111857 -0.0309722703 -0.0474287160 86 1311867173.2942678928 0.1000022888 0.0821054567 0.1000022888 0.0064385175 0.0638480000 185998153 0 402718720 -0.1870869845 -0.0302070323 -0.0473051891 87 1311867173.3262879848 0.1009575352 0.0823221472 0.1009575352 0.0064034863 0.0319780000 189661321 0 402718720 -0.1900668740 -0.0289708469 -0.0467408821 88 1311867173.3623280525 0.1025267988 0.0825517455 0.1025267988 0.0063729828 0.0302140000 192856825 0 402718720 -0.1940124035 -0.0281916372 -0.0462734923 89 1311867173.3942871094 0.1027506739 0.0827786998 0.1027506739 0.0063482661 0.0256890000 192859913 0 402718720 -0.1964121461 -0.0284061432 -0.0458453894 90 1311867173.4262790680 0.1045641825 0.0830207607 0.1045641825 0.0063162659 0.0266820000 192863057 0 402718720 -0.2003740966 -0.0284923911 -0.0448058769 91 1311867173.4622900486 0.1039388999 0.0832506304 0.1045641825 0.0063159580 0.0256080000 192866313 0 402718720 -0.2023551315 -0.0286197159 -0.0448661558 92 1311867173.4943389893 0.1052136645 0.0834893590 0.1052136645 0.0064073732 0.0255260000 192869457 0 402718720 -0.2041405886 -0.0287516713 -0.0445024185 93 1311867173.5263900757 0.1048387066 0.0837189219 0.1052136645 0.0063744740 0.0257690000 192872657 0 402718720 -0.2063069195 -0.0285410341 -0.0452131927 94 1311867173.5624370575 0.1041559055 0.0839363366 0.1052136645 0.0063750633 0.0258280000 192875913 0 402718720 -0.2081711590 -0.0283900443 -0.0455535203 95 1311867173.5943109989 0.1069029793 0.0841780907 0.1069029793 0.0064021800 0.0245420000 192879001 0 402718720 -0.2119658887 -0.0282045454 -0.0439841114 96 1311867173.6263959408 0.1079807580 0.0844260352 0.1079807580 0.0063814651 0.0295740000 192882145 0 402718720 -0.2154356241 -0.0290782172 -0.0435750745 97 1311867173.6623299122 0.1069623455 0.0846583683 0.1079807580 0.0063575428 0.0252220000 192885401 0 402718720 -0.2157969177 -0.0288252383 -0.0447588190 98 1311867173.6943540573 0.1090262011 0.0849070196 0.1090262011 0.0063276503 0.0259430000 192888545 0 402718720 -0.2188339978 -0.0292284675 -0.0438329391 99 1311867173.7267971039 0.1099369302 0.0851598470 0.1099369302 0.0063054212 0.0297860000 192891745 0 402718720 -0.2207934856 -0.0287767537 -0.0436461978 100 1311867173.7623970509 0.1069705412 0.0853779539 0.1099369302 0.0062792757 0.0303410000 192895001 0 402718720 -0.2203755081 -0.0283366647 -0.0467055887 101 1311867173.7943561077 0.1106111556 0.0856277876 0.1106111556 0.0062560415 0.0294670000 192898033 0 402718720 -0.2241096348 -0.0296109077 -0.0444630645 102 1311867173.8265669346 0.1110656634 0.0858771786 0.1110656634 0.0062258271 0.0284850000 192901233 0 402718720 -0.2268121541 -0.0295975488 -0.0453993417 103 1311867173.8635799885 0.1102969125 0.0861142634 0.1110656634 0.0062081401 0.0303750000 192904433 0 402718720 -0.2279886901 -0.0292964913 -0.0468148217 104 1311867173.8946080208 0.1144652739 0.0863868692 0.1144652739 0.0062003484 0.0293740000 192907577 0 402718720 -0.2322423160 -0.0295752920 -0.0446208455 105 1311867173.9266970158 0.1150581911 0.0866599294 0.1150581911 0.0061769935 0.0326060000 192910777 0 402718720 -0.2358259708 -0.0305981934 -0.0454414450 106 1311867173.9625461102 0.1119216979 0.0868982480 0.1150581911 0.0061681621 0.0344680000 192914033 0 402718720 -0.2354652435 -0.0288119018 -0.0482487492 107 1311867173.9944310188 0.1148932353 0.0871598834 0.1150581911 0.0061514502 0.0340120000 192917121 0 402718720 -0.2388755977 -0.0287972298 -0.0461902209 108 1311867174.0264260769 0.1150775105 0.0874183800 0.1150775105 0.0061417484 0.0326480000 192920265 0 402718720 -0.2402931452 -0.0290030893 -0.0467531234 109 1311867174.0624630451 0.1108191684 0.0876330661 0.1150775105 0.0061208623 0.0336020000 192923521 0 402718720 -0.2389188111 -0.0268262606 -0.0500955731 110 1311867174.0945188999 0.1139875650 0.0878726524 0.1150775105 0.0061316301 0.0349440000 192926665 0 402718720 -0.2420945615 -0.0263276417 -0.0481324084 111 1311867174.1264541149 0.1160409972 0.0881264213 0.1160409972 0.0061279433 0.0344670000 192929809 0 402718720 -0.2461038530 -0.0263152830 -0.0474951565 112 1311867174.1624329090 0.1134368703 0.0883524075 0.1160409972 0.0061146458 0.0357970000 192933065 0 402718720 -0.2467090636 -0.0261862352 -0.0503825992 113 1311867174.1943979263 0.1143941283 0.0885828652 0.1160409972 0.0060938120 0.0315870000 192936209 0 402718720 -0.2489028871 -0.0247797500 -0.0494009070 114 1311867174.2267580032 0.1170496196 0.0888325735 0.1170496196 0.0060736629 0.0345810000 192939409 0 402718720 -0.2525578141 -0.0243910346 -0.0471798778 115 1311867174.2626769543 0.1143544018 0.0890545025 0.1170496196 0.0060662411 0.0374260000 192942609 0 402718720 -0.2529339194 -0.0244370922 -0.0493762083 116 1311867174.2945280075 0.1161135435 0.0892877701 0.1170496196 0.0061135263 0.0341630000 192945753 0 402718720 -0.2540445626 -0.0237017758 -0.0477570221 117 1311867174.3265740871 0.1183725297 0.0895363578 0.1183725297 0.0060970703 0.0353380000 192948897 0 402718720 -0.2583820522 -0.0238733608 -0.0471324921 118 1311867174.3624329567 0.1170627549 0.0897696323 0.1183725297 0.0060748324 0.0368070000 192952209 0 402718720 -0.2601911426 -0.0234477762 -0.0487208739 119 1311867174.3946359158 0.1187011376 0.0900127542 0.1187011376 0.0060872356 0.0349160000 192955297 0 402718720 -0.2633838654 -0.0224616341 -0.0482297465 120 1311867174.4266788960 0.1220432296 0.0902796748 0.1220432296 0.0060934372 0.0358980000 192958497 0 402718720 -0.2665996850 -0.0206418987 -0.0453143939 121 1311867174.4630160332 0.1193316057 0.0905197734 0.1220432296 0.0061469461 0.0359020000 192961697 0 402718720 -0.2677772045 -0.0222228765 -0.0473667420 122 1311867174.4945669174 0.1189000756 0.0907523989 0.1220432296 0.0061285160 0.0371460000 192964841 0 402718720 -0.2681902945 -0.0211154390 -0.0473324060 123 1311867174.5267519951 0.1217186302 0.0910041568 0.1220432296 0.0061112450 0.0359020000 192968041 0 402718720 -0.2719627917 -0.0201441925 -0.0446586274 124 1311867174.5623500347 0.1193039417 0.0912323809 0.1220432296 0.0061061880 0.0362670000 192971297 0 402718720 -0.2727356255 -0.0208960138 -0.0468815006 125 1311867174.5944879055 0.1201414615 0.0914636536 0.1220432296 0.0060996816 0.0359290000 192974385 0 402718720 -0.2749876678 -0.0198833160 -0.0459929481 126 1311867174.6265459061 0.1220254153 0.0917062072 0.1220432296 0.0060950148 0.0346950000 192977529 0 402718720 -0.2782263160 -0.0187125895 -0.0440906137 127 1311867174.6624910831 0.1216207519 0.0919417548 0.1220432296 0.0060760420 0.0324980000 192980785 0 402718720 -0.2808533013 -0.0196761750 -0.0446901768 128 1311867174.6945910454 0.1187662259 0.0921513210 0.1220432296 0.0060628168 0.0363810000 192983929 0 402718720 -0.2817802131 -0.0186678339 -0.0474364497 129 1311867174.7265629768 0.1240813434 0.0923988406 0.1240813434 0.0061078006 0.0353820000 193000329 0 402718720 -0.2850208580 -0.0168592688 -0.0419815369 130 1311867174.7623760700 0.1232857257 0.0926364320 0.1240813434 0.0060983145 0.0351080000 193029241 0 402718720 -0.2867805660 -0.0170932058 -0.0426339209 131 1311867174.7944738865 0.1223501563 0.0928632543 0.1240813434 0.0060805616 0.0356510000 193032273 0 402718720 -0.2877075076 -0.0170110371 -0.0432289355 132 1311867174.8273301125 0.1241435856 0.0931002265 0.1241435856 0.0060625296 0.0773580000 205343037 0 402718720 -0.2905231416 -0.0175126940 -0.0417328067 133 1311867174.8624229431 0.1253195703 0.0933424772 0.1253195703 0.0062937701 0.0398410000 209005557 0 402718720 -0.2912786901 -0.0002775587 -0.0440497026 134 1311867174.8944199085 0.1246807054 0.0935763446 0.1253195703 0.0062719378 0.0291530000 212200837 0 402718720 -0.2919061482 -0.0007321457 -0.0439523980 135 1311867174.9269750118 0.1240446717 0.0938020359 0.1253195703 0.0062526413 0.0347650000 212203981 0 402718720 -0.2927924693 -0.0008793711 -0.0444074422 136 1311867174.9626429081 0.1270221919 0.0940463018 0.1270221919 0.0062413110 0.0336300000 212207293 0 402718720 -0.2970764935 -0.0009331534 -0.0425899774 137 1311867174.9943349361 0.1265604049 0.0942836310 0.1270221919 0.0062273616 0.0328350000 212210381 0 402718720 -0.2991862893 0.0014076459 -0.0445236638 138 1311867175.0265510082 0.1279556304 0.0945276310 0.1279556304 0.0062126059 0.0342300000 212213581 0 402718720 -0.3021907508 0.0027114938 -0.0437314436 139 1311867175.0633120537 0.1291243732 0.0947765284 0.1291243732 0.0061945164 0.0319110000 212216837 0 402718720 -0.3055398762 0.0028563747 -0.0429391265 140 1311867175.0947189331 0.1279763132 0.0950136697 0.1291243732 0.0061859214 0.0386850000 212219981 0 402718720 -0.3057405055 0.0043229917 -0.0433384739 141 1311867175.1265308857 0.1273984760 0.0952433492 0.1291243732 0.0061660695 0.0341800000 212223125 0 402718720 -0.3067465723 0.0042492924 -0.0430550836 142 1311867175.1625180244 0.1282181889 0.0954755664 0.1291243732 0.0061791987 0.0450550000 212226381 0 402718720 -0.3083694875 0.0052590361 -0.0422671027 143 1311867175.1946399212 0.1285160184 0.0957066185 0.1291243732 0.0061574603 0.0370100000 212229469 0 402718720 -0.3100869656 0.0056168949 -0.0420039631 144 1311867175.2270050049 0.1270397604 0.0959242098 0.1291243732 0.0061946408 0.0388680000 212232669 0 402718720 -0.3099575043 0.0082676383 -0.0419919677 145 1311867175.2624669075 0.1299034208 0.0961585491 0.1299034208 0.0062596845 0.0434710000 212235869 0 402718720 -0.3138527274 0.0085146027 -0.0398168564 146 1311867175.2944509983 0.1299725771 0.0963901521 0.1299725771 0.0062385498 0.0402310000 212239013 0 402718720 -0.3155487478 0.0101565858 -0.0394062065 147 1311867175.3267059326 0.1287575811 0.0966103387 0.1299725771 0.0062201459 0.0411890000 212242213 0 402718720 -0.3157557547 0.0126482397 -0.0390545875 148 1311867175.3625650406 0.1297769099 0.0968344371 0.1299725771 0.0062191191 0.0354710000 212245413 0 402718720 -0.3193438351 0.0104914010 -0.0377215967 149 1311867175.3945989609 0.1302981079 0.0970590255 0.1302981079 0.0061981537 0.0384020000 212248557 0 402718720 -0.3220710754 0.0112462472 -0.0370549001 150 1311867175.4266059399 0.1308285445 0.0972841556 0.1308285445 0.0061816573 0.0347300000 212251701 0 402718720 -0.3247738183 0.0134361656 -0.0364429913 151 1311867175.4625999928 0.1323579252 0.0975164323 0.1323579252 0.0061610210 0.0355580000 212255013 0 402718720 -0.3298231363 0.0132284295 -0.0347021557 152 1311867175.4945731163 0.1332010031 0.0977511992 0.1332010031 0.0061453516 0.0332040000 212258157 0 402718720 -0.3334969282 0.0145184183 -0.0340340026 153 1311867175.5264270306 0.1327044517 0.0979796518 0.1332010031 0.0061378660 0.0326950000 212261245 0 402718720 -0.3348444104 0.0155529836 -0.0339379162 154 1311867175.5625700951 0.1327624768 0.0982055143 0.1332010031 0.0061329675 0.0389560000 212264557 0 402718720 -0.3374302983 0.0174213387 -0.0332244933 155 1311867175.5946640968 0.1349949688 0.0984428656 0.1349949688 0.0061520891 0.0350790000 212267645 0 402718720 -0.3419210911 0.0167212095 -0.0316855721 156 1311867175.6264801025 0.1361943334 0.0986848622 0.1361943334 0.0061437530 0.0361980000 212270789 0 402718720 -0.3457980454 0.0192714538 -0.0310621243 157 1311867175.6624929905 0.1373972744 0.0989314381 0.1373972744 0.0061893440 0.0410950000 212274045 0 402718720 -0.3486475050 0.0206778701 -0.0303119142 158 1311867175.6947000027 0.1379033476 0.0991780957 0.1379033476 0.0061896040 0.0400340000 212277189 0 402718720 -0.3529250324 0.0191313606 -0.0294899400 159 1311867175.7273120880 0.1369699240 0.0994157802 0.1379033476 0.0061703376 0.0376080000 212280389 0 402718720 -0.3537003696 0.0204042140 -0.0299819335 160 1311867175.7624969482 0.1374297440 0.0996533675 0.1379033476 0.0061605349 0.0367370000 212283645 0 402718720 -0.3560978770 0.0211059470 -0.0296051539 161 1311867175.7948620319 0.1380632222 0.0998919380 0.1380632222 0.0061646455 0.0361640000 212286733 0 402718720 -0.3597150743 0.0188595243 -0.0284909308 162 1311867175.8287971020 0.1390189826 0.1001334630 0.1390189826 0.0061556391 0.0377790000 212289989 0 402718720 -0.3632184565 0.0207074266 -0.0287032668 163 1311867175.8625519276 0.1394143999 0.1003744503 0.1394143999 0.0061424507 0.0442730000 212293189 0 402718720 -0.3663162291 0.0221869741 -0.0285850093 164 1311867175.8946080208 0.1407055706 0.1006203718 0.1407055706 0.0061360847 0.0446970000 212296277 0 402718720 -0.3704423606 0.0210852176 -0.0278780870 165 1311867175.9282429218 0.1409130394 0.1008645698 0.1409130394 0.0061240130 0.0453320000 212299477 0 402718720 -0.3735798597 0.0201024897 -0.0273045804 166 1311867175.9629371166 0.1403107643 0.1011021974 0.1409130394 0.0061074456 0.0424130000 212302677 0 402718720 -0.3751848340 0.0226534009 -0.0284501724 167 1311867175.9983000755 0.1407231987 0.1013394489 0.1409130394 0.0060925939 0.0374190000 212305877 0 402718720 -0.3778113425 0.0222186614 -0.0279794373 168 1311867176.0268509388 0.1426050216 0.1015850773 0.1426050216 0.0060788435 0.0391690000 212308909 0 402718720 -0.3811662793 0.0196056683 -0.0263882969 169 1311867176.0627059937 0.1419799179 0.1018241001 0.1426050216 0.0061171855 0.0521530000 212312165 0 402718720 -0.3835584521 0.0214635935 -0.0281076469 170 1311867176.0946600437 0.1430441439 0.1020665709 0.1430441439 0.0061857354 0.0479610000 212315253 0 402718720 -0.3851465285 0.0229724459 -0.0284022707 171 1311867176.1268119812 0.1443176717 0.1023136534 0.1443176717 0.0061774477 0.0457200000 212318453 0 402718720 -0.3876623809 0.0234579463 -0.0282484200 172 1311867176.1625900269 0.1435637772 0.1025534797 0.1443176717 0.0062538941 0.0466590000 212321709 0 402718720 -0.3881140053 0.0230517741 -0.0282688662 173 1311867176.1946918964 0.1433757991 0.1027894468 0.1443176717 0.0062948104 0.0427020000 212324853 0 402718720 -0.3880424201 0.0251140092 -0.0293827187 174 1311867176.2265360355 0.1448576897 0.1030312184 0.1448576897 0.0062817912 0.0413940000 212327997 0 402718720 -0.3909574449 0.0248270594 -0.0284958351 175 1311867176.2625019550 0.1461350322 0.1032775259 0.1461350322 0.0062688195 0.0419560000 212331253 0 402718720 -0.3935378790 0.0246194713 -0.0279976130 176 1311867176.2946109772 0.1470056474 0.1035259811 0.1470056474 0.0062743895 0.0408990000 212334341 0 402718720 -0.3954415321 0.0305007324 -0.0295753349 177 1311867176.3266019821 0.1485312432 0.1037802481 0.1485312432 0.0062579279 0.0439300000 212337485 0 402718720 -0.3979699314 0.0292635970 -0.0283296090 178 1311867176.3624560833 0.1490440518 0.1040345391 0.1490440518 0.0062448412 0.0378080000 212340797 0 402718720 -0.4002805054 0.0305355806 -0.0292678438 179 1311867176.3952438831 0.1485377848 0.1042831606 0.1490440518 0.0062288303 0.0395520000 212343885 0 402718720 -0.4007324874 0.0315829851 -0.0300128181 180 1311867176.4268360138 0.1484079212 0.1045282982 0.1490440518 0.0062118877 0.0386970000 212347029 0 402718720 -0.4017932117 0.0329808779 -0.0305406656 181 1311867176.4629659653 0.1487411857 0.1047725683 0.1490440518 0.0062638325 0.0355780000 212350285 0 402718720 -0.4037682116 0.0318874680 -0.0298368353 182 1311867176.4945809841 0.1502253115 0.1050223086 0.1502253115 0.0062732574 0.0383710000 212353373 0 402718720 -0.4059556723 0.0338282958 -0.0307765584 183 1311867176.5266211033 0.1515406519 0.1052765072 0.1515406519 0.0063109084 0.0733480000 224667869 0 402718720 -0.4083006382 0.0356261432 -0.0308001488 184 1311867176.5636389256 0.1493367404 0.1055159650 0.1515406519 0.0063230436 0.0451580000 228330389 0 402718720 -0.4080303013 0.0328452624 -0.0318637937 185 1311867176.5946090221 0.1496746987 0.1057546609 0.1515406519 0.0063089310 0.0304250000 231525669 0 402718720 -0.4105137587 0.0346892029 -0.0329003446 186 1311867176.6283841133 0.1500228941 0.1059926621 0.1515406519 0.0062947620 0.0270320000 231528869 0 402718720 -0.4116313457 0.0352576002 -0.0324486978 187 1311867176.6625781059 0.1501402110 0.1062287453 0.1515406519 0.0062818624 0.0274890000 231532069 0 402718720 -0.4140940011 0.0353957303 -0.0326580517 188 1311867176.6945180893 0.1513256133 0.1064686222 0.1515406519 0.0062705089 0.0257270000 231535157 0 402718720 -0.4167357981 0.0361819342 -0.0321842283 189 1311867176.7265889645 0.1520691067 0.1067098946 0.1520691067 0.0062548104 0.0244140000 231538357 0 402718720 -0.4199601710 0.0366367400 -0.0323428623 190 1311867176.7632329464 0.1528990567 0.1069529955 0.1528990567 0.0062421215 0.0260670000 231541613 0 402718720 -0.4230574369 0.0376382731 -0.0320849977 191 1311867176.7947680950 0.1536940932 0.1071977133 0.1536940932 0.0062390823 0.0244850000 231544701 0 402718720 -0.4253330529 0.0378589146 -0.0314482339 192 1311867176.8266770840 0.1538399458 0.1074406416 0.1538399458 0.0062234963 0.0243760000 231547901 0 402718720 -0.4273529053 0.0377171561 -0.0314835832 193 1311867176.8627309799 0.1537030339 0.1076803431 0.1538399458 0.0062125373 0.0314920000 231551157 0 402718720 -0.4293375909 0.0391257368 -0.0322319195 194 1311867176.8949549198 0.1562545449 0.1079307256 0.1562545449 0.0061979328 0.0280000000 231554301 0 402718720 -0.4333115220 0.0385944694 -0.0301162843 195 1311867176.9268178940 0.1558628231 0.1081765312 0.1562545449 0.0061943422 0.0268350000 231557445 0 402718720 -0.4360966682 0.0392207839 -0.0307570770 196 1311867176.9650609493 0.1561940014 0.1084215183 0.1562545449 0.0062073247 0.0325780000 231560701 0 402718720 -0.4387720823 0.0410295501 -0.0312391575 197 1311867176.9947481155 0.1575009376 0.1086706524 0.1575009376 0.0061922836 0.0308940000 231563789 0 402718720 -0.4409220517 0.0399980433 -0.0295071881 198 1311867177.0267279148 0.1578647494 0.1089191074 0.1578647494 0.0061784955 0.0287730000 231566933 0 402718720 -0.4435319006 0.0398671366 -0.0295610875 199 1311867177.0626339912 0.1572892070 0.1091621733 0.1578647494 0.0061651185 0.0297930000 231570189 0 402718720 -0.4453511834 0.0414671153 -0.0306587052 200 1311867177.0946850777 0.1584734321 0.1094087296 0.1584734321 0.0061496708 0.0303160000 231573333 0 402718720 -0.4473752379 0.0405893400 -0.0292998552 201 1311867177.1266150475 0.1595761627 0.1096583188 0.1595761627 0.0061374525 0.0300680000 231576477 0 402718720 -0.4507916868 0.0412780270 -0.0290724710 202 1311867177.1627299786 0.1596605927 0.1099058548 0.1596605927 0.0061228413 0.0313710000 231579733 0 402718720 -0.4532252252 0.0421727560 -0.0291730855 203 1311867177.1946458817 0.1600516140 0.1101528782 0.1600516140 0.0061109839 0.0324970000 231582877 0 402718720 -0.4551068544 0.0426172204 -0.0289416686 204 1311867177.2264730930 0.1612889469 0.1104035452 0.1612889469 0.0060971921 0.0323610000 231586021 0 402718720 -0.4576091170 0.0422362387 -0.0278253313 205 1311867177.2638640404 0.1610563695 0.1106506322 0.1612889469 0.0060832076 0.0357070000 231589333 0 402718720 -0.4597363770 0.0433484875 -0.0287200902 206 1311867177.2946178913 0.1628940403 0.1109042410 0.1628940403 0.0060737983 0.0346000000 231592421 0 402718720 -0.4629602134 0.0431445427 -0.0269977842 207 1311867177.3276090622 0.1616656631 0.1111494652 0.1628940403 0.0060609174 0.0340860000 231595621 0 402718720 -0.4647337794 0.0445567146 -0.0289095137 208 1311867177.3627710342 0.1629611254 0.1113985597 0.1629611254 0.0060488191 0.0371520000 231598821 0 402718720 -0.4676209986 0.0450064428 -0.0282031558 209 1311867177.3946089745 0.1639093310 0.1116498075 0.1639093310 0.0060604736 0.0380410000 231601965 0 402718720 -0.4700315297 0.0456657112 -0.0280165710 210 1311867177.4267480373 0.1636936516 0.1118976353 0.1639093310 0.0060474492 0.0338960000 231605109 0 402718720 -0.4723629951 0.0460586399 -0.0286374521 211 1311867177.4626040459 0.1641487479 0.1121452709 0.1641487479 0.0060370317 0.0346320000 231608421 0 402718720 -0.4743770361 0.0465781949 -0.0283724461 212 1311867177.4946429729 0.1647945046 0.1123936163 0.1647945046 0.0060227976 0.0349840000 231611565 0 402718720 -0.4761787951 0.0470579453 -0.0278083812 213 1311867177.5276169777 0.1652421504 0.1126417315 0.1652421504 0.0060095853 0.0349840000 231614653 0 402718720 -0.4786443412 0.0488599911 -0.0283992104 214 1311867177.5626399517 0.1665554792 0.1128936649 0.1665554792 0.0060063038 0.0349640000 231617909 0 402718720 -0.4813936949 0.0483052917 -0.0274371188 215 1311867177.5947310925 0.1666634679 0.1131437570 0.1666634679 0.0059937482 0.0357900000 231621053 0 402718720 -0.4826082587 0.0494211093 -0.0278110188 216 1311867177.6311450005 0.1670266837 0.1133932150 0.1670266837 0.0059806886 0.0341600000 231624365 0 402718720 -0.4844700694 0.0500893667 -0.0278107915 217 1311867177.6624829769 0.1671731621 0.1136410489 0.1671731621 0.0059670043 0.0341310000 231627509 0 402718720 -0.4858267009 0.0511616915 -0.0280817132 218 1311867177.6945610046 0.1675593406 0.1138883805 0.1675593406 0.0059689039 0.0346190000 231630653 0 402718720 -0.4875743389 0.0515678339 -0.0278921630 219 1311867177.7305839062 0.1669309139 0.1141305838 0.1675593406 0.0059563772 0.0361600000 231633853 0 402718720 -0.4883520007 0.0527882092 -0.0290946048 220 1311867177.7625379562 0.1680356413 0.1143756068 0.1680356413 0.0059438455 0.0345470000 231636997 0 402718720 -0.4892339110 0.0526389852 -0.0282411296 221 1311867177.7945590019 0.1693509370 0.1146243640 0.1693509370 0.0059356711 0.0361530000 231640141 0 402718720 -0.4910964668 0.0532059781 -0.0281903502 222 1311867177.8309149742 0.1693748832 0.1148709879 0.1693748832 0.0059272700 0.0384750000 231643397 0 402718720 -0.4922946393 0.0529538542 -0.0288299769 223 1311867177.8625319004 0.1692364812 0.1151147794 0.1693748832 0.0059141338 0.0334840000 231646541 0 402718720 -0.4928895831 0.0537207648 -0.0295957010 224 1311867177.8946919441 0.1698903888 0.1153593134 0.1698903888 0.0059030812 0.0366860000 231649629 0 402718720 -0.4938890338 0.0546875782 -0.0297645070 225 1311867177.9317860603 0.1705764085 0.1156047227 0.1705764085 0.0058900794 0.0339250000 231652997 0 402718720 -0.4950661063 0.0546233095 -0.0294361338 226 1311867177.9627909660 0.1712290496 0.1158508480 0.1712290496 0.0058954070 0.0376400000 231656085 0 402718720 -0.4966006875 0.0559541546 -0.0299290661 227 1311867177.9947769642 0.1719813645 0.1160981190 0.1719813645 0.0058854522 0.0366360000 231659117 0 402718720 -0.4984586835 0.0568679981 -0.0304534901 228 1311867178.0306100845 0.1732127517 0.1163486218 0.1732127517 0.0058735063 0.0364780000 231662373 0 402718720 -0.5009163618 0.0562381744 -0.0298105851 229 1311867178.0634479523 0.1728173196 0.1165952100 0.1732127517 0.0058641239 0.0368490000 231665517 0 402718720 -0.5016040802 0.0579028614 -0.0309868455 230 1311867178.0951139927 0.1731000543 0.1168408832 0.1732127517 0.0058513752 0.0396930000 231668661 0 402718720 -0.5031024218 0.0581609942 -0.0311122723 231 1311867178.1307909489 0.1743338406 0.1170897705 0.1743338406 0.0058399292 0.0378290000 231671917 0 402718720 -0.5050322413 0.0571997352 -0.0297286082 232 1311867178.1627469063 0.1741356850 0.1173356580 0.1743338406 0.0058573223 0.0383550000 231675061 0 402718720 -0.5070524216 0.0585105345 -0.0311616808 233 1311867178.1950459480 0.1751095802 0.1175836148 0.1751095802 0.0058520553 0.0381650000 231678149 0 402718720 -0.5099089742 0.0592688844 -0.0311494153 234 1311867178.2307190895 0.1757891476 0.1178323564 0.1757891476 0.0058494528 0.0378980000 231681405 0 402718720 -0.5116397142 0.0580816381 -0.0302362610 235 1311867178.2628939152 0.1757938862 0.1180790012 0.1757938862 0.0058373260 0.0382440000 231684605 0 402718720 -0.5146425366 0.0595349595 -0.0313090980 236 1311867178.2954900265 0.1762143075 0.1183253372 0.1762143075 0.0058257075 0.0381910000 231687749 0 402718720 -0.5168023109 0.0596826896 -0.0311115962 237 1311867178.3306670189 0.1770769954 0.1185732345 0.1770769954 0.0058152102 0.0384170000 231690949 0 402718720 -0.5194832683 0.0585048459 -0.0299826432 238 1311867178.3627231121 0.1761861444 0.1188153056 0.1770769954 0.0058039608 0.0367250000 231694149 0 402718720 -0.5218645334 0.0598439276 -0.0313516967 239 1311867178.3949439526 0.1771455556 0.1190593652 0.1771455556 0.0057918871 0.0383210000 231697237 0 402718720 -0.5234765410 0.0592044517 -0.0298742596 240 1311867178.4306581020 0.1764757484 0.1192986001 0.1771455556 0.0057868875 0.0370980000 231700493 0 402718720 -0.5240168571 0.0608794130 -0.0302294753 241 1311867178.4628739357 0.1771900356 0.1195388136 0.1771900356 0.0057751308 0.0368020000 231703637 0 402718720 -0.5273262858 0.0599739477 -0.0297786146 242 1311867178.4946439266 0.1779536158 0.1197801970 0.1779536158 0.0057649543 0.0385110000 231706781 0 402718720 -0.5297050476 0.0603537895 -0.0292180553 243 1311867178.5306270123 0.1772940308 0.1200168795 0.1779536158 0.0057619893 0.0367970000 231710037 0 402718720 -0.5319280624 0.0618888661 -0.0304006692 244 1311867178.5626420975 0.1787900925 0.1202577533 0.1787900925 0.0057515303 0.0373130000 231713237 0 402718720 -0.5327005386 0.0623097494 -0.0280897375 245 1311867178.5947000980 0.1791749746 0.1204982318 0.1791749746 0.0057419636 0.0345580000 231716381 0 402718720 -0.5348803997 0.0614573769 -0.0277071465 246 1311867178.6306900978 0.1786891669 0.1207347803 0.1791749746 0.0057323875 0.0378880000 231719581 0 402718720 -0.5356051326 0.0622403920 -0.0281556882 247 1311867178.6626410484 0.1795323044 0.1209728269 0.1795323044 0.0057385537 0.0366200000 231722781 0 402718720 -0.5371366143 0.0618857294 -0.0269330703 248 1311867178.6946120262 0.1798077226 0.1212100644 0.1798077226 0.0057294446 0.0386230000 231725869 0 402718720 -0.5389467478 0.0614157021 -0.0270051062 249 1311867178.7307450771 0.1796346605 0.1214447013 0.1798077226 0.0057250154 0.0387840000 231729125 0 402718720 -0.5401876569 0.0637337118 -0.0282289181 250 1311867178.7632350922 0.1814799905 0.1216848425 0.1814799905 0.0057141227 0.0376100000 231732325 0 402718720 -0.5428577065 0.0635335669 -0.0270328410 251 1311867178.8006799221 0.1805844307 0.1219195022 0.1814799905 0.0057058759 0.0369300000 231735581 0 402718720 -0.5434468389 0.0624649115 -0.0278110597 252 1311867178.8309500217 0.1799230427 0.1221496750 0.1814799905 0.0056982153 0.0379790000 231738669 0 402718720 -0.5431976318 0.0651479736 -0.0291110054 253 1311867178.8627939224 0.1803813130 0.1223798396 0.1814799905 0.0056960184 0.0382650000 231741869 0 402718720 -0.5424650908 0.0631227791 -0.0273473859 254 1311867178.8950169086 0.1813653111 0.1226120658 0.1814799905 0.0056851707 0.0389650000 231744957 0 402718720 -0.5433534384 0.0611945502 -0.0264548659 255 1311867178.9306209087 0.1792132854 0.1228340314 0.1814799905 0.0056790402 0.0336950000 231748213 0 402718720 -0.5396445394 0.0632585436 -0.0285573881 256 1311867178.9627609253 0.1822330654 0.1230660589 0.1822330654 0.0056698458 0.0348090000 231751413 0 402718720 -0.5434508324 0.0626615509 -0.0271752235 257 1311867178.9946830273 0.1829453409 0.1232990522 0.1829453409 0.0056640840 0.0389600000 231781181 0 402718720 -0.5469111800 0.0639131293 -0.0285406727 258 1311867179.0309159756 0.1830884367 0.1235307940 0.1830884367 0.0056698403 0.0388560000 231835637 0 402718720 -0.5507302284 0.0660411865 -0.0309165958 259 1311867179.0628120899 0.1845900714 0.1237665441 0.1845900714 0.0056598094 0.0375990000 231838837 0 402718720 -0.5507180095 0.0644424707 -0.0285862200 260 1311867179.0968120098 0.1844066381 0.1239997752 0.1845900714 0.0056684489 0.0380910000 231841925 0 402718720 -0.5481875539 0.0611568391 -0.0272013564 261 1311867179.1310369968 0.1825822741 0.1242242292 0.1845900714 0.0056588504 0.0374900000 231845125 0 402718720 -0.5469238758 0.0638817698 -0.0303404070 262 1311867179.1627540588 0.1864006221 0.1244615437 0.1864006221 0.0056977141 0.0380170000 231848269 0 402718720 -0.5511801839 0.0609322414 -0.0284725670 263 1311867179.1956849098 0.1867505312 0.1246983840 0.1867505312 0.0056945958 0.0383120000 231851357 0 402718720 -0.5542957187 0.0630529076 -0.0307284594 264 1311867179.2307469845 0.1877705157 0.1249372936 0.1877705157 0.0056969186 0.0375020000 231854613 0 402718720 -0.5585169196 0.0650952160 -0.0325866677 265 1311867179.2634611130 0.1883839816 0.1251767150 0.1883839816 0.0056978404 0.0379130000 231857869 0 402718720 -0.5626264811 0.0626919568 -0.0329880714 266 1311867179.2959198952 0.1878063977 0.1254121650 0.1883839816 0.0056890319 0.1160410000 244167693 0 402718720 -0.5625844002 0.0644946620 -0.0339522846 267 1311867179.3307149410 0.1804060191 0.1256181345 0.1883839816 0.0057504403 0.0242180000 247830157 0 402718720 -0.5588805676 0.0606049858 -0.0392887741 268 1311867179.3629300594 0.1809304208 0.1258245236 0.1883839816 0.0057400867 0.0253180000 251025605 0 402718720 -0.5607022643 0.0606151968 -0.0392933339 269 1311867179.3948490620 0.1831914335 0.1260377835 0.1883839816 0.0057342809 0.0489910000 251028637 0 402718720 -0.5645467043 0.0608011223 -0.0382985920 270 1311867179.4308040142 0.1821565181 0.1262456306 0.1883839816 0.0057380783 0.0425900000 251031949 0 402718720 -0.5651490688 0.0641087219 -0.0397892259 271 1311867179.4637460709 0.1821981966 0.1264520977 0.1883839816 0.0057406146 0.0311730000 251035149 0 402718720 -0.5660329461 0.0634341463 -0.0388669185 272 1311867179.4949469566 0.1821158826 0.1266567439 0.1883839816 0.0057323948 0.0326740000 251038237 0 402718720 -0.5660277605 0.0629926249 -0.0381452069 273 1311867179.5307800770 0.1813883483 0.1268572260 0.1883839816 0.0057294040 0.0370950000 251041493 0 402718720 -0.5659849644 0.0655903667 -0.0384944938 274 1311867179.5627610683 0.1829088479 0.1270617940 0.1883839816 0.0057340433 0.0320000000 251044637 0 402718720 -0.5682009459 0.0647212416 -0.0365735255 275 1311867179.5946741104 0.1824765354 0.1272633021 0.1883839816 0.0057263357 0.0289680000 251047781 0 402718720 -0.5698571205 0.0672598407 -0.0378951505 276 1311867179.6306900978 0.1835332215 0.1274671786 0.1883839816 0.0057477709 0.0308930000 251050981 0 402718720 -0.5717214346 0.0684972256 -0.0371202864 277 1311867179.6625750065 0.1839441210 0.1276710665 0.1883839816 0.0057387479 0.0318260000 251054181 0 402718720 -0.5718553662 0.0674079657 -0.0358243138 278 1311867179.6946051121 0.1833973974 0.1278715210 0.1883839816 0.0057449519 0.0389790000 251057269 0 402718720 -0.5717151165 0.0687911287 -0.0361000970 279 1311867179.7309470177 0.1832491457 0.1280700071 0.1883839816 0.0057352764 0.0347410000 251060581 0 402718720 -0.5725647807 0.0683817789 -0.0360888578 280 1311867179.7627270222 0.1842606515 0.1282706879 0.1883839816 0.0057425166 0.0298550000 251063725 0 402718720 -0.5740143657 0.0680787712 -0.0348804854 281 1311867179.7948911190 0.1833847612 0.1284668234 0.1883839816 0.0057561392 0.0373700000 251066813 0 402718720 -0.5736767650 0.0709129199 -0.0360567793 282 1311867179.8307530880 0.1842676848 0.1286646988 0.1883839816 0.0057479781 0.0322470000 251070125 0 402718720 -0.5753148198 0.0708830804 -0.0351188406 283 1311867179.8627979755 0.1845695823 0.1288622426 0.1883839816 0.0057384694 0.0323420000 251073269 0 402718720 -0.5765010118 0.0692541748 -0.0341585502 284 1311867179.8948040009 0.1840051711 0.1290564078 0.1883839816 0.0057286057 0.0324130000 251076413 0 402718720 -0.5758498907 0.0699511841 -0.0341125540 285 1311867179.9309051037 0.1833252013 0.1292468246 0.1883839816 0.0057377729 0.0330650000 251079669 0 402718720 -0.5741010308 0.0711445734 -0.0338902324 286 1311867179.9634931087 0.1844891608 0.1294399797 0.1883839816 0.0057322133 0.0316520000 251082813 0 402718720 -0.5769471526 0.0689828172 -0.0326262675 287 1311867179.9958879948 0.1845851988 0.1296321233 0.1883839816 0.0057286767 0.0350740000 251085957 0 402718720 -0.5779616237 0.0722542405 -0.0332870446 288 1311867180.0309770107 0.1844452918 0.1298224468 0.1883839816 0.0057189065 0.0349180000 251089213 0 402718720 -0.5785226226 0.0734921247 -0.0332875550 289 1311867180.0626471043 0.1849619448 0.1300132409 0.1883839816 0.0057095627 0.0268600000 251092357 0 402718720 -0.5792030096 0.0729511902 -0.0324910469 290 1311867180.0947730541 0.1855585575 0.1302047765 0.1883839816 0.0057016138 0.0305140000 251095445 0 402718720 -0.5788160563 0.0750137568 -0.0322086439 291 1311867180.1307730675 0.1854965389 0.1303947825 0.1883839816 0.0056987138 0.0281730000 251098701 0 402718720 -0.5776280761 0.0730572492 -0.0317654945 292 1311867180.1636800766 0.1840099990 0.1305783963 0.1883839816 0.0057209221 0.0270230000 251101901 0 402718720 -0.5742993355 0.0723876879 -0.0323420130 293 1311867180.1949090958 0.1832500994 0.1307581632 0.1883839816 0.0057131465 0.0280830000 251104989 0 402718720 -0.5736972094 0.0714359283 -0.0334812328 294 1311867180.2308139801 0.1833080351 0.1309369042 0.1883839816 0.0057082662 0.0299050000 251108189 0 402718720 -0.5738293529 0.0713285729 -0.0346850194 295 1311867180.2637619972 0.1844426692 0.1311182797 0.1883839816 0.0057327252 0.0279070000 251111389 0 402718720 -0.5751642585 0.0718725249 -0.0349960364 296 1311867180.2947549820 0.1841088831 0.1312973020 0.1883839816 0.0057235482 0.0249720000 251114477 0 402718720 -0.5746001005 0.0719438717 -0.0356511585 297 1311867180.3308670521 0.1840398163 0.1314748863 0.1883839816 0.0057165126 0.0256700000 251117733 0 402718720 -0.5734286308 0.0717013702 -0.0359006636 298 1311867180.3658199310 0.1830421090 0.1316479306 0.1883839816 0.0057132058 0.0290450000 251120877 0 402718720 -0.5708572268 0.0713714138 -0.0366707742 299 1311867180.3961660862 0.1834394187 0.1318211463 0.1883839816 0.0057039603 0.0289110000 251123965 0 402718720 -0.5712104440 0.0705158040 -0.0369956754 300 1311867180.4309151173 0.1837827712 0.1319943517 0.1883839816 0.0056955174 0.0277590000 251127277 0 402718720 -0.5710802078 0.0711273327 -0.0374792702 301 1311867180.4670670033 0.1834615618 0.1321653391 0.1883839816 0.0056872614 0.0256350000 251130533 0 402718720 -0.5703271031 0.0719661266 -0.0384028330 302 1311867180.4947559834 0.1836860329 0.1323359375 0.1883839816 0.0056908809 0.0292670000 251133509 0 402718720 -0.5698222518 0.0708599612 -0.0383505337 303 1311867180.5308880806 0.1834352762 0.1325045821 0.1883839816 0.0056820374 0.0288390000 251136821 0 402718720 -0.5685468316 0.0716152787 -0.0386934020 304 1311867180.5629510880 0.1832904965 0.1326716411 0.1883839816 0.0056738138 0.0286070000 251139965 0 402718720 -0.5676234961 0.0713603795 -0.0386790410 305 1311867180.5946910381 0.1832555085 0.1328374898 0.1883839816 0.0056658741 0.0284820000 251143109 0 402718720 -0.5663394332 0.0717850700 -0.0385114588 306 1311867180.6308128834 0.1831752658 0.1330019923 0.1883839816 0.0056585174 0.0260690000 251146365 0 402718720 -0.5659914613 0.0709430873 -0.0384461507 307 1311867180.6640911102 0.1824928969 0.1331632005 0.1883839816 0.0056733973 0.0269280000 251149509 0 402718720 -0.5648530722 0.0715097040 -0.0387375131 308 1311867180.6957600117 0.1823380888 0.1333228592 0.1883839816 0.0056644247 0.0259410000 251152597 0 402718720 -0.5641951561 0.0709393844 -0.0386478417 309 1311867180.7309739590 0.1820809394 0.1334806524 0.1883839816 0.0056599736 0.0263380000 251155909 0 402718720 -0.5629755259 0.0722121969 -0.0390029289 310 1311867180.7650380135 0.1826158166 0.1336391529 0.1883839816 0.0056680615 0.0255290000 251159053 0 402718720 -0.5631687641 0.0708281323 -0.0385244898 311 1311867180.7949280739 0.1814879328 0.1337930075 0.1883839816 0.0056627346 0.0261340000 251162141 0 402718720 -0.5609256029 0.0718507320 -0.0390650146 312 1311867180.8309240341 0.1818954945 0.1339471821 0.1883839816 0.0056539422 0.0262860000 251165453 0 402718720 -0.5610539317 0.0715778992 -0.0388006493 313 1311867180.8652539253 0.1812715679 0.1340983783 0.1883839816 0.0056499803 0.0254970000 251168597 0 402718720 -0.5596134067 0.0710163191 -0.0387587845 314 1311867180.8966469765 0.1817012131 0.1342499796 0.1883839816 0.0056430767 0.0279220000 251171797 0 402718720 -0.5590828657 0.0711718202 -0.0388102010 315 1311867180.9306049347 0.1810322106 0.1343984947 0.1883839816 0.0056580905 0.0269000000 251174997 0 402718720 -0.5582052469 0.0709297583 -0.0391744263 316 1311867180.9631829262 0.1809309572 0.1345457493 0.1883839816 0.0056566104 0.0254510000 251178141 0 402718720 -0.5569121242 0.0721558928 -0.0395589210 317 1311867180.9948179722 0.1805653274 0.1346909215 0.1883839816 0.0056478337 0.0262170000 251181229 0 402718720 -0.5556091666 0.0720114931 -0.0397800729 318 1311867181.0308310986 0.1802524924 0.1348341968 0.1883839816 0.0056423071 0.0278350000 251184485 0 402718720 -0.5540288687 0.0708619207 -0.0397264473 319 1311867181.0627830029 0.1799419224 0.1349756004 0.1883839816 0.0056386992 0.0280920000 251187685 0 402718720 -0.5516638756 0.0710307881 -0.0402585194 320 1311867181.0948719978 0.1795234382 0.1351148124 0.1883839816 0.0056354992 0.0247040000 251190829 0 402718720 -0.5494466424 0.0719574615 -0.0404107943 321 1311867181.1311910152 0.1785957962 0.1352502671 0.1883839816 0.0056327414 0.0293050000 251194085 0 402718720 -0.5461879969 0.0707702711 -0.0407030880 322 1311867181.1629040241 0.1785449088 0.1353847225 0.1883839816 0.0056343903 0.0224990000 251197173 0 402718720 -0.5445495844 0.0698195100 -0.0410679132 323 1311867181.1972510815 0.1780292094 0.1355167488 0.1883839816 0.0056258189 0.0232320000 251200373 0 402718720 -0.5428218842 0.0698503181 -0.0418591201 324 1311867181.2342460155 0.1774366349 0.1356461312 0.1883839816 0.0056185852 0.0261330000 251203741 0 402718720 -0.5410872698 0.0687443092 -0.0428692549 325 1311867181.2629361153 0.1766041815 0.1357721560 0.1883839816 0.0056101178 0.0258570000 251206773 0 402718720 -0.5389861465 0.0692488179 -0.0438161008 326 1311867181.2948091030 0.1761747897 0.1358960904 0.1883839816 0.0056024417 0.0289270000 251209861 0 402718720 -0.5363310575 0.0691276118 -0.0437056795 327 1311867181.3316988945 0.1759497970 0.1360185788 0.1883839816 0.0055998207 0.0271020000 251213117 0 402718720 -0.5352565646 0.0686690733 -0.0440674759 328 1311867181.3626708984 0.1748615205 0.1361370024 0.1883839816 0.0055947719 0.0292340000 251216261 0 402718720 -0.5327634811 0.0701452121 -0.0449005999 329 1311867181.3948218822 0.1753314584 0.1362561345 0.1883839816 0.0055872059 0.0310680000 251219405 0 402718720 -0.5329912305 0.0685839057 -0.0446212664 330 1311867181.4308950901 0.1745640188 0.1363722190 0.1883839816 0.0055807859 0.0305240000 251222549 0 402718720 -0.5304518342 0.0692502633 -0.0452552065 331 1311867181.4628310204 0.1733103395 0.1364838145 0.1883839816 0.0055778720 0.0290160000 251225693 0 402718720 -0.5271303058 0.0687944070 -0.0458338186 332 1311867181.4963400364 0.1724817902 0.1365922422 0.1883839816 0.0055869961 0.0300900000 251228837 0 402718720 -0.5245434642 0.0685922578 -0.0460382923 333 1311867181.5359110832 0.1738038957 0.1367039889 0.1883839816 0.0055825647 0.0286250000 251232205 0 402718720 -0.5236451626 0.0670821294 -0.0449372344 334 1311867181.5632140636 0.1720952392 0.1368099507 0.1883839816 0.0055769101 0.0295800000 251235125 0 402718720 -0.5205647349 0.0663592741 -0.0462567285 335 1311867181.5948610306 0.1711716950 0.1369125231 0.1883839816 0.0055694277 0.0316570000 251238269 0 402718720 -0.5195045471 0.0676018000 -0.0480636694 336 1311867181.6309840679 0.1723648757 0.1370180360 0.1883839816 0.0055642366 0.0312040000 251241525 0 402718720 -0.5187274218 0.0666079670 -0.0472557992 337 1311867181.6628570557 0.1721171439 0.1371221877 0.1883839816 0.0055570933 0.0290290000 251244725 0 402718720 -0.5164763927 0.0649534687 -0.0476137996 338 1311867181.6949229240 0.1703761071 0.1372205721 0.1883839816 0.0055534898 0.0320900000 251247813 0 402718720 -0.5136967897 0.0660084337 -0.0494591109 339 1311867181.7310829163 0.1723272055 0.1373241315 0.1883839816 0.0055706389 0.0326750000 251251069 0 402718720 -0.5122157931 0.0635028183 -0.0478684194 340 1311867181.7634770870 0.1708872914 0.1374228466 0.1883839816 0.0055655867 0.0311060000 251254213 0 402718720 -0.5110737681 0.0636266619 -0.0501063727 341 1311867181.7948980331 0.1706901789 0.1375204048 0.1883839816 0.0055632972 0.0323230000 251257301 0 402718720 -0.5092437863 0.0641720593 -0.0512198545 342 1311867181.8308010101 0.1712767780 0.1376191076 0.1883839816 0.0055589094 0.0323420000 251260557 0 402718720 -0.5080230832 0.0622786395 -0.0505596697 343 1311867181.8627979755 0.1699854583 0.1377134702 0.1883839816 0.0055565223 0.0329430000 251263757 0 402718720 -0.5054888129 0.0622347035 -0.0512412414 344 1311867181.8949289322 0.1693361551 0.1378053966 0.1883839816 0.0055531374 0.0333270000 251266845 0 402718720 -0.5020891428 0.0618936978 -0.0512846112 345 1311867181.9307990074 0.1703172177 0.1378996337 0.1883839816 0.0055558768 0.0326990000 251270157 0 402718720 -0.5015087724 0.0604276024 -0.0507853031 346 1311867181.9629189968 0.1686358452 0.1379884667 0.1883839816 0.0055490725 0.0348800000 251273301 0 402718720 -0.4997715950 0.0612734444 -0.0529488511 347 1311867181.9955511093 0.1687092781 0.1380769993 0.1883839816 0.0055696702 0.0353120000 251276389 0 402718720 -0.4977296293 0.0596618168 -0.0515639707 348 1311867182.0319390297 0.1681444496 0.1381634000 0.1883839816 0.0055624487 0.0346740000 251279645 0 402718720 -0.4959190488 0.0590788946 -0.0518526062 349 1311867182.0629000664 0.1674640328 0.1382473560 0.1883839816 0.0055558891 0.0343660000 251282845 0 402718720 -0.4950636923 0.0588829368 -0.0528239124 350 1311867182.0948839188 0.1673385799 0.1383304738 0.1883839816 0.0055582811 0.0366230000 251285933 0 402718720 -0.4929217100 0.0590561405 -0.0527338088 351 1311867182.1314530373 0.1669929773 0.1384121333 0.1883839816 0.0055504861 0.0336560000 251289189 0 402718720 -0.4903979897 0.0586226173 -0.0524289496 352 1311867182.1629920006 0.1668274552 0.1384928587 0.1883839816 0.0055437453 0.0349620000 251292389 0 402718720 -0.4884161055 0.0585706681 -0.0521575771 353 1311867182.1994419098 0.1670349687 0.1385737145 0.1883839816 0.0055417663 0.0358130000 251295533 0 402718720 -0.4870916009 0.0575558618 -0.0516731590 354 1311867182.2307739258 0.1665914208 0.1386528606 0.1883839816 0.0055371398 0.0361480000 251298677 0 402718720 -0.4847292006 0.0568692498 -0.0513787158 355 1311867182.2629120350 0.1658209860 0.1387293905 0.1883839816 0.0055358703 0.0357020000 251301877 0 402718720 -0.4837445319 0.0564900078 -0.0523956083 356 1311867182.2973039150 0.1670039296 0.1388088134 0.1883839816 0.0055309296 0.0353300000 251305021 0 402718720 -0.4827716649 0.0553006604 -0.0511027388 357 1311867182.3308460712 0.1662760228 0.1388857523 0.1883839816 0.0055389817 0.0338320000 251308221 0 402718720 -0.4816488326 0.0556847006 -0.0521983393 358 1311867182.3629670143 0.1657290012 0.1389607335 0.1883839816 0.0055664442 0.0341030000 251311421 0 402718720 -0.4795826674 0.0550477840 -0.0520104803 359 1311867182.3990280628 0.1660447270 0.1390361764 0.1883839816 0.0055666733 0.0383660000 251314565 0 402718720 -0.4783697128 0.0544487685 -0.0516262054 360 1311867182.4308118820 0.1667881012 0.1391132650 0.1883839816 0.0055632585 0.0384740000 251317765 0 402718720 -0.4771644175 0.0532080419 -0.0509006493 361 1311867182.4629440308 0.1666489542 0.1391895412 0.1883839816 0.0055585982 0.0375550000 251320965 0 402718720 -0.4754085839 0.0533265136 -0.0514487326 362 1311867182.4969530106 0.1682685465 0.1392698699 0.1883839816 0.0055517528 0.0362530000 251324053 0 402718720 -0.4724429250 0.0516898856 -0.0493950397 363 1311867182.5309500694 0.1680316776 0.1393491036 0.1883839816 0.0055447513 0.0380660000 251327309 0 402718720 -0.4717323184 0.0510264561 -0.0510090142 364 1311867182.5629699230 0.1667221338 0.1394243042 0.1883839816 0.0055485416 0.0386320000 251330453 0 402718720 -0.4709841609 0.0504713468 -0.0541637316 365 1311867182.6036369801 0.1675721258 0.1395014215 0.1883839816 0.0055429164 0.0353940000 251333821 0 402718720 -0.4682566226 0.0496145003 -0.0533374548 366 1311867182.6308450699 0.1671598703 0.1395769911 0.1883839816 0.0055512229 0.0401470000 251336797 0 402718720 -0.4680425823 0.0491752923 -0.0553431734 367 1311867182.6635720730 0.1654828489 0.1396475792 0.1883839816 0.0055462265 0.0423990000 251339941 0 402718720 -0.4656838775 0.0487062298 -0.0569581948 368 1311867182.6969909668 0.1669730395 0.1397218332 0.1883839816 0.0055434418 0.0395950000 251343085 0 402718720 -0.4626604915 0.0478992090 -0.0556044504 369 1311867182.7330501080 0.1671096981 0.1397960550 0.1883839816 0.0055405321 0.0362760000 251346341 0 402718720 -0.4612310529 0.0465951897 -0.0563842580 370 1311867182.7631070614 0.1664981693 0.1398682229 0.1883839816 0.0055330856 0.0366580000 251349317 0 402718720 -0.4589011669 0.0464796573 -0.0575131997 371 1311867182.7970440388 0.1662369519 0.1399392977 0.1883839816 0.0055263222 0.0396780000 251352573 0 402718720 -0.4565814734 0.0451386273 -0.0578724071 372 1311867182.8306899071 0.1660903841 0.1400095963 0.1883839816 0.0055193504 0.0408830000 251355717 0 402718720 -0.4556881487 0.0450091027 -0.0592266731 373 1311867182.8640909195 0.1649697274 0.1400765135 0.1883839816 0.0055240505 0.0388770000 251358861 0 402718720 -0.4537809789 0.0445123129 -0.0603308491 374 1311867182.8969850540 0.1646494269 0.1401422165 0.1883839816 0.0055166946 0.0398250000 251362061 0 402718720 -0.4522985816 0.0448557958 -0.0610841736 375 1311867182.9318869114 0.1640836746 0.1402060604 0.1883839816 0.0055116465 0.0414890000 251365261 0 402718720 -0.4501312971 0.0452253670 -0.0616308711 376 1311867182.9630560875 0.1650754958 0.1402722025 0.1883839816 0.0055053904 0.0394780000 251368405 0 402718720 -0.4480534792 0.0452888012 -0.0600572526 377 1311867182.9983499050 0.1644222885 0.1403362611 0.1883839816 0.0055091259 0.0401880000 251371605 0 402718720 -0.4452382922 0.0438950509 -0.0598172508 378 1311867183.0308830738 0.1640892923 0.1403990998 0.1883839816 0.0055021705 0.0420560000 251374805 0 402718720 -0.4438545704 0.0442322716 -0.0603951812 379 1311867183.0628600121 0.1640945524 0.1404616208 0.1883839816 0.0054974750 0.0414900000 251378005 0 402718720 -0.4416214526 0.0444375798 -0.0601233989 380 1311867183.1000399590 0.1644017696 0.1405246212 0.1883839816 0.0055195252 0.0407300000 251381149 0 402718720 -0.4397308528 0.0430129319 -0.0588830113 381 1311867183.1344680786 0.1627522260 0.1405829613 0.1883839816 0.0055128684 0.0397080000 251384405 0 402718720 -0.4380214512 0.0441657454 -0.0609152727 382 1311867183.1673240662 0.1629080325 0.1406414039 0.1883839816 0.0055056987 0.0413780000 251387661 0 402718720 -0.4367272854 0.0439657569 -0.0604603551 383 1311867183.2004730701 0.1633516103 0.1407006995 0.1883839816 0.0054996181 0.0371050000 251390749 0 402718720 -0.4345341325 0.0424435474 -0.0587591976 384 1311867183.2311279774 0.1624573022 0.1407573573 0.1883839816 0.0054928326 0.0412120000 251393893 0 402718720 -0.4330258071 0.0429699495 -0.0598958023 385 1311867183.2633240223 0.1630255431 0.1408151968 0.1883839816 0.0054856937 0.0404060000 251397037 0 402718720 -0.4319151938 0.0425533429 -0.0591376051 386 1311867183.2990970612 0.1642059386 0.1408757946 0.1883839816 0.0054816921 0.0406610000 251400237 0 402718720 -0.4298389256 0.0412186496 -0.0567965023 387 1311867183.3320920467 0.1621219218 0.1409306941 0.1883839816 0.0054760623 0.0416780000 251403493 0 402718720 -0.4282950759 0.0415608287 -0.0595375933 388 1311867183.3695240021 0.1631086618 0.1409878538 0.1883839816 0.0054691023 0.0418800000 251406805 0 402718720 -0.4270351231 0.0410667509 -0.0586171187 389 1311867183.3985459805 0.1634753644 0.1410456623 0.1883839816 0.0054621400 0.0427320000 251409781 0 402718720 -0.4254939258 0.0394323245 -0.0576879084 390 1311867183.4311549664 0.1618901044 0.1410991096 0.1883839816 0.0054619478 0.0377370000 251412981 0 402718720 -0.4244436920 0.0401629470 -0.0604696013 391 1311867183.4667379856 0.1618659496 0.1411522217 0.1883839816 0.0054585186 0.0436570000 251416181 0 402718720 -0.4218952060 0.0400675014 -0.0602753051 392 1311867183.4988279343 0.1624165624 0.1412064675 0.1883839816 0.0054775644 0.0417290000 251419381 0 402718720 -0.4202894270 0.0380941853 -0.0587629117 393 1311867183.5321719646 0.1611555666 0.1412572286 0.1883839816 0.0054727710 0.0428630000 251422525 0 402718720 -0.4186427593 0.0386275165 -0.0601723418 394 1311867183.5661509037 0.1605922133 0.1413063021 0.1883839816 0.0054667635 0.0441580000 251425725 0 402718720 -0.4159622788 0.0389550701 -0.0603624508 395 1311867183.5985350609 0.1616085619 0.1413577003 0.1883839816 0.0054623927 0.0426980000 251428869 0 402718720 -0.4144835770 0.0365314782 -0.0586666130 396 1311867183.6310880184 0.1603099853 0.1414055596 0.1883839816 0.0054722506 0.0407910000 251432069 0 402718720 -0.4130565822 0.0374217145 -0.0606909730 397 1311867183.6648790836 0.1605289131 0.1414537292 0.1883839816 0.0054660516 0.0410900000 251435157 0 402718720 -0.4102375507 0.0369709097 -0.0595400929 398 1311867183.6993529797 0.1607254744 0.1415021507 0.1883839816 0.0054592624 0.0443350000 251438469 0 402718720 -0.4079142511 0.0358544216 -0.0585728697 399 1311867183.7308928967 0.1601506025 0.1415488887 0.1883839816 0.0054541109 0.0428230000 251441557 0 402718720 -0.4059925079 0.0355348848 -0.0591694340 400 1311867183.7676239014 0.1597925574 0.1415944978 0.1883839816 0.0054583532 0.0427750000 251444813 0 402718720 -0.4029322863 0.0354278684 -0.0586024635 401 1311867183.7971758842 0.1597923189 0.1416398789 0.1883839816 0.0054518230 0.0429640000 251447845 0 402718720 -0.4015372396 0.0345203429 -0.0582925305 402 1311867183.8309071064 0.1592366546 0.1416836520 0.1883839816 0.0054453484 0.0463900000 251451045 0 402718720 -0.3992410004 0.0338422023 -0.0582160726 403 1311867183.8654990196 0.1608092636 0.1417311101 0.1883839816 0.0054389602 0.0421810000 251454189 0 402718720 -0.3979915380 0.0326022953 -0.0562072434 404 1311867183.8970859051 0.1588087231 0.1417733814 0.1883839816 0.0054365190 0.0440890000 251457277 0 402718720 -0.3960396647 0.0324074365 -0.0582030118 405 1311867183.9314830303 0.1586328894 0.1418150098 0.1883839816 0.0054302862 0.0419950000 251460533 0 402718720 -0.3938620985 0.0315837339 -0.0575443283 406 1311867183.9658210278 0.1593067050 0.1418580928 0.1883839816 0.0054267246 0.0425690000 251463677 0 402718720 -0.3928329349 0.0309075415 -0.0564479306 407 1311867183.9966681004 0.1592515707 0.1419008287 0.1883839816 0.0054218664 0.0433700000 251466821 0 402718720 -0.3915108442 0.0307198633 -0.0565634258 408 1311867184.0309689045 0.1586794853 0.1419419528 0.1883839816 0.0054386102 0.0416980000 251470077 0 402718720 -0.3898760974 0.0303241964 -0.0570790134 409 1311867184.0647230148 0.1588782370 0.1419833618 0.1883839816 0.0054340008 0.0428980000 251473221 0 402718720 -0.3887943625 0.0288072228 -0.0559688210 410 1311867184.0968110561 0.1579447985 0.1420222922 0.1883839816 0.0054286359 0.0383130000 251476309 0 402718720 -0.3874838352 0.0290435571 -0.0569872484 411 1311867184.1312260628 0.1578408331 0.1420607801 0.1883839816 0.0054227800 0.0399430000 251479565 0 402718720 -0.3853092194 0.0287737325 -0.0563050583 412 1311867184.1650540829 0.1584119350 0.1421004674 0.1883839816 0.0054162046 0.0399640000 251482653 0 402718720 -0.3839500248 0.0277582817 -0.0551248863 413 1311867184.1969459057 0.1573340893 0.1421373526 0.1883839816 0.0054100577 0.0393450000 251485853 0 402718720 -0.3819603920 0.0294515323 -0.0567612872 414 1311867184.2309360504 0.1572468430 0.1421738490 0.1883839816 0.0054041338 0.0434190000 251489109 0 402718720 -0.3798870444 0.0281276423 -0.0559876859 415 1311867184.2681019306 0.1578421593 0.1422116040 0.1883839816 0.0053997070 0.0434200000 251492365 0 402718720 -0.3782748878 0.0263051111 -0.0549216643 416 1311867184.2983698845 0.1565411836 0.1422460501 0.1883839816 0.0053985917 0.0412500000 251495453 0 402718720 -0.3758988976 0.0284912754 -0.0566123389 417 1311867184.3314700127 0.1566037685 0.1422804810 0.1883839816 0.0053935788 0.0430980000 251498653 0 402718720 -0.3735393882 0.0278674215 -0.0556857213 418 1311867184.3697628975 0.1575407833 0.1423169889 0.1883839816 0.0053941439 0.0425820000 251501909 0 402718720 -0.3727394938 0.0260910299 -0.0549965017 419 1311867184.4000060558 0.1566541791 0.1423512066 0.1883839816 0.0054222885 0.0412820000 251504997 0 402718720 -0.3705164492 0.0282470230 -0.0572194830 420 1311867184.4310610294 0.1574867219 0.1423872435 0.1883839816 0.0054173828 0.0439160000 251508197 0 402718720 -0.3680353463 0.0288590621 -0.0559521690 421 1311867184.4655740261 0.1583925039 0.1424252608 0.1883839816 0.0054136046 0.0409110000 251511341 0 402718720 -0.3660090864 0.0254103355 -0.0540126525 422 1311867184.5037670135 0.1571685970 0.1424601976 0.1883839816 0.0054692970 0.0431860000 251514709 0 402718720 -0.3620211482 0.0248490274 -0.0551593564 423 1311867184.5310881138 0.1562514156 0.1424928009 0.1883839816 0.0054929234 0.0896550000 263823557 0 402718720 -0.3592001200 0.0262168720 -0.0573590621 424 1311867184.5682799816 0.1486583501 0.1425073423 0.1883839816 0.0055240415 0.0421050000 267487701 0 402718720 -0.3520328999 0.0208085403 -0.0625891760 425 1311867184.5979928970 0.1482194066 0.1425207825 0.1883839816 0.0055302029 0.0312400000 270682925 0 402718720 -0.3504236042 0.0191124734 -0.0629354864 426 1311867184.6355450153 0.1474072635 0.1425322531 0.1883839816 0.0055269926 0.0290340000 270686237 0 402718720 -0.3470292985 0.0200528204 -0.0639151633 427 1311867184.6662440300 0.1478850842 0.1425447890 0.1883839816 0.0055348015 0.0302430000 270689381 0 402718720 -0.3448696434 0.0176433641 -0.0625043511 428 1311867184.6994769573 0.1468173862 0.1425547717 0.1883839816 0.0055301756 0.0296840000 270692581 0 402718720 -0.3413172960 0.0164335221 -0.0624652877 429 1311867184.7359089851 0.1469697803 0.1425650631 0.1883839816 0.0055275107 0.0283800000 270695725 0 402718720 -0.3392489254 0.0166286305 -0.0628942549 430 1311867184.7690219879 0.1468720436 0.1425750793 0.1883839816 0.0055248773 0.0296600000 270698981 0 402718720 -0.3366753757 0.0140634971 -0.0617357492 431 1311867184.7995340824 0.1457972080 0.1425825553 0.1883839816 0.0055264247 0.0295490000 270702069 0 402718720 -0.3330411315 0.0146172838 -0.0619992614 432 1311867184.8348250389 0.1454392672 0.1425891680 0.1883839816 0.0055210138 0.0270820000 270705213 0 402718720 -0.3301167786 0.0142094148 -0.0617687032 433 1311867184.8685739040 0.1452452838 0.1425953022 0.1883839816 0.0055157284 0.0349420000 270708413 0 402718720 -0.3277812600 0.0119396923 -0.0606027618 434 1311867184.9055209160 0.1448723525 0.1426005489 0.1883839816 0.0055106408 0.0303980000 270711613 0 402718720 -0.3248371184 0.0123361293 -0.0604601391 435 1311867184.9332180023 0.1442688704 0.1426043841 0.1883839816 0.0055099674 0.0303400000 270714533 0 402718720 -0.3216037452 0.0121618500 -0.0597287230 436 1311867184.9656269550 0.1432866603 0.1426059490 0.1883839816 0.0055148680 0.0363340000 270717677 0 402718720 -0.3181315064 0.0092476523 -0.0579404160 437 1311867184.9983150959 0.1431215703 0.1426071289 0.1883839816 0.0055139241 0.0324140000 270720877 0 402718720 -0.3157220781 0.0092876805 -0.0574919172 438 1311867185.0360450745 0.1422696263 0.1426063583 0.1883839816 0.0055079044 0.0334890000 270724133 0 402718720 -0.3113076389 0.0087528117 -0.0563115440 439 1311867185.0652229786 0.1413953602 0.1426035998 0.1883839816 0.0055040154 0.0338640000 270727221 0 402718720 -0.3075223267 0.0064138705 -0.0546703227 440 1311867185.0991089344 0.1413536221 0.1426007589 0.1883839816 0.0055002629 0.0358160000 270730421 0 402718720 -0.3056291640 0.0074506234 -0.0545642413 441 1311867185.1360650063 0.1407848448 0.1425966412 0.1883839816 0.0054951201 0.0328840000 270733677 0 402718720 -0.3019584119 0.0069818692 -0.0531660318 442 1311867185.1648139954 0.1397703290 0.1425902468 0.1883839816 0.0054940272 0.0371630000 270736765 0 402718720 -0.2984000742 0.0048993533 -0.0517221987 443 1311867185.2000079155 0.1391012669 0.1425823710 0.1883839816 0.0054888655 0.0341350000 270739909 0 402718720 -0.2944964767 0.0058681881 -0.0514013171 444 1311867185.2342638969 0.1390746832 0.1425744708 0.1883839816 0.0054873284 0.0352400000 270743165 0 402718720 -0.2914199531 0.0049860291 -0.0499619730 445 1311867185.2663319111 0.1387934983 0.1425659743 0.1883839816 0.0054817338 0.0374660000 270746309 0 402718720 -0.2884058356 0.0021114715 -0.0480370335 446 1311867185.2970130444 0.1374586225 0.1425545228 0.1883839816 0.0055097886 0.0358060000 270749453 0 402718720 -0.2846925259 0.0032288989 -0.0480626598 447 1311867185.3359839916 0.1373363137 0.1425428490 0.1883839816 0.0055038457 0.0357570000 270752765 0 402718720 -0.2815481722 0.0025359751 -0.0466966629 448 1311867185.3681640625 0.1374094039 0.1425313904 0.1883839816 0.0054981086 0.0350590000 270755965 0 402718720 -0.2785035968 0.0010688531 -0.0449139513 449 1311867185.4036369324 0.1365916729 0.1425181616 0.1883839816 0.0054923836 0.0320000000 270759165 0 402718720 -0.2759867311 0.0008059868 -0.0453003719 450 1311867185.4373219013 0.1371888220 0.1425063186 0.1883839816 0.0054877103 0.0345790000 270762365 0 402718720 -0.2735214531 0.0023795818 -0.0444234200 451 1311867185.4654970169 0.1362264305 0.1424923943 0.1883839816 0.0054840117 0.0349460000 270765341 0 402718720 -0.2694363892 -0.0011015775 -0.0425218455 452 1311867185.5006229877 0.1356695592 0.1424772995 0.1883839816 0.0054959882 0.0360810000 270768541 0 402718720 -0.2670779228 -0.0017535826 -0.0428977944 453 1311867185.5336239338 0.1354540884 0.1424617957 0.1883839816 0.0055042174 0.0365800000 270771741 0 402718720 -0.2643564641 -0.0007704551 -0.0431316569 454 1311867185.5666689873 0.1360350996 0.1424476400 0.1883839816 0.0054985486 0.0364030000 270774941 0 402718720 -0.2615973949 -0.0031710765 -0.0412560776 455 1311867185.5969750881 0.1345254928 0.1424302287 0.1883839816 0.0054995331 0.0325370000 270778029 0 402718720 -0.2579513490 -0.0045678308 -0.0415681042 456 1311867185.6329400539 0.1347583383 0.1424134044 0.1883839816 0.0055085093 0.0363990000 270781285 0 402718720 -0.2551011443 -0.0039019966 -0.0419113711 457 1311867185.6664080620 0.1342105865 0.1423954551 0.1883839816 0.0055140858 0.0378660000 270784429 0 402718720 -0.2512180507 -0.0058767190 -0.0407559052 458 1311867185.6973319054 0.1338162273 0.1423767232 0.1883839816 0.0055083786 0.0379880000 270787573 0 402718720 -0.2488188893 -0.0067226379 -0.0406002812 459 1311867185.7351789474 0.1347814500 0.1423601757 0.1883839816 0.0055057950 0.0331970000 270790829 0 402718720 -0.2475048602 -0.0049871905 -0.0406711735 460 1311867185.7649710178 0.1340455413 0.1423421004 0.1883839816 0.0055036613 0.0372940000 270793973 0 402718720 -0.2434109896 -0.0086847525 -0.0382836536 461 1311867185.7989521027 0.1338106394 0.1423235940 0.1883839816 0.0055115109 0.0336820000 270797117 0 402718720 -0.2404696494 -0.0092878807 -0.0380943455 462 1311867185.8327920437 0.1336369514 0.1423047918 0.1883839816 0.0055055963 0.0383950000 270800373 0 402718720 -0.2380949855 -0.0092691621 -0.0378817990 463 1311867185.8649039268 0.1329944581 0.1422846830 0.1883839816 0.0055018251 0.0375030000 270803517 0 402718720 -0.2346362770 -0.0112303607 -0.0364007466 464 1311867185.8951730728 0.1333158016 0.1422653536 0.1883839816 0.0054965409 0.0355940000 270806549 0 402718720 -0.2333427370 -0.0116335209 -0.0358395986 465 1311867185.9359779358 0.1336628050 0.1422468535 0.1883839816 0.0054920092 0.0389200000 270809917 0 402718720 -0.2319090217 -0.0106251566 -0.0355893150 466 1311867185.9650509357 0.1320689768 0.1422250125 0.1883839816 0.0055105859 0.0388090000 270812949 0 402718720 -0.2275181860 -0.0146852983 -0.0331433527 467 1311867185.9952309132 0.1314209104 0.1422018774 0.1883839816 0.0055065294 0.0393440000 270816093 0 402718720 -0.2251461446 -0.0144703146 -0.0333297886 468 1311867186.0359640121 0.1321444809 0.1421803872 0.1883839816 0.0055045548 0.0392150000 270819461 0 402718720 -0.2251085341 -0.0135153774 -0.0335398614 469 1311867186.0653049946 0.1309120655 0.1421563610 0.1883839816 0.0055103738 0.0400600000 270822605 0 402718720 -0.2225115448 -0.0170221496 -0.0318167880 470 1311867186.0952839851 0.1306592524 0.1421318990 0.1883839816 0.0055059278 0.0378130000 270825581 0 402718720 -0.2214518040 -0.0178249422 -0.0314942449 471 1311867186.1361019611 0.1304337829 0.1421070623 0.1883839816 0.0055034532 0.0383100000 270829005 0 402718720 -0.2193346024 -0.0180296823 -0.0312744342 472 1311867186.1649360657 0.1298276931 0.1420810467 0.1883839816 0.0055009527 0.0410050000 270832093 0 402718720 -0.2170694768 -0.0202591531 -0.0302808993 473 1311867186.1951880455 0.1298074722 0.1420550983 0.1883839816 0.0054952237 0.0393930000 270835125 0 402718720 -0.2157984525 -0.0204586834 -0.0303274840 474 1311867186.2358930111 0.1292153746 0.1420280103 0.1883839816 0.0054905561 0.0414540000 270838549 0 402718720 -0.2132910639 -0.0205043517 -0.0303073321 475 1311867186.2674899101 0.1294483989 0.1420015269 0.1883839816 0.0054855608 0.0401060000 270841749 0 402718720 -0.2111948878 -0.0225302968 -0.0290531423 476 1311867186.2951989174 0.1289450526 0.1419740973 0.1883839816 0.0054803045 0.0385520000 270844669 0 402718720 -0.2092653960 -0.0220887307 -0.0292604566 477 1311867186.3349149227 0.1286730319 0.1419462125 0.1883839816 0.0054789442 0.0404360000 270848037 0 402718720 -0.2066981196 -0.0224256068 -0.0286524184 478 1311867186.3669641018 0.1281366199 0.1419173221 0.1883839816 0.0054843919 0.0404630000 270851125 0 402718720 -0.2041603029 -0.0264880434 -0.0267897733 479 1311867186.3951311111 0.1285350174 0.1418893841 0.1883839816 0.0054851823 0.0384970000 270854101 0 402718720 -0.2040201575 -0.0251950640 -0.0273313969 480 1311867186.4360098839 0.1287440062 0.1418619979 0.1883839816 0.0054867738 0.0362770000 270857525 0 402718720 -0.2019542009 -0.0240073279 -0.0267958883 481 1311867186.4659481049 0.1277567595 0.1418326731 0.1883839816 0.0054891817 0.0410110000 270860669 0 402718720 -0.1988286227 -0.0283090193 -0.0243651625 482 1311867186.4952139854 0.1276798099 0.1418033103 0.1883839816 0.0054837466 0.0373390000 270863645 0 402718720 -0.1978535354 -0.0281220879 -0.0245001763 483 1311867186.5362739563 0.1276766807 0.1417740626 0.1883839816 0.0054918504 0.0402470000 270867069 0 402718720 -0.1963844895 -0.0278277863 -0.0246035401 484 1311867186.5651071072 0.1271670163 0.1417438828 0.1883839816 0.0055095831 0.0396630000 270870157 0 402718720 -0.1935710609 -0.0302288067 -0.0225009937 485 1311867186.5951600075 0.1270268559 0.1417135384 0.1883839816 0.0055040539 0.0375400000 270873189 0 402718720 -0.1918750107 -0.0309751723 -0.0224058982 486 1311867186.6362359524 0.1267042309 0.1416826550 0.1883839816 0.0054984003 0.0370250000 270876613 0 402718720 -0.1892179847 -0.0306434743 -0.0228170138 487 1311867186.6650140285 0.1269871891 0.1416524795 0.1883839816 0.0054951055 0.0390530000 270879645 0 402718720 -0.1881264299 -0.0296004415 -0.0234955959 488 1311867186.7043650150 0.1269717962 0.1416223962 0.1883839816 0.0055134630 0.0402560000 270883069 0 402718720 -0.1862377375 -0.0314700566 -0.0229395349 489 1311867186.7337520123 0.1269182861 0.1415923264 0.1883839816 0.0055209785 0.0420280000 270886101 0 402718720 -0.1849146634 -0.0277115777 -0.0248110052 490 1311867186.7672879696 0.1277126223 0.1415640005 0.1883839816 0.0055156158 0.0406720000 270889301 0 402718720 -0.1842432767 -0.0285027809 -0.0241351351 491 1311867186.8047199249 0.1273479611 0.1415350473 0.1883839816 0.0055154049 0.1113230000 283204905 0 402718720 -0.1818064004 -0.0308435373 -0.0234351698 492 1311867186.8340680599 0.1212997437 0.1414939186 0.1883839816 0.0055159476 0.0406150000 286867145 0 402718720 -0.1760755628 -0.0314708799 -0.0279462896 493 1311867186.8691000938 0.1207941771 0.1414519313 0.1883839816 0.0055119222 0.0364520000 290062537 0 402718720 -0.1732463539 -0.0313511454 -0.0280907862 494 1311867186.9051868916 0.1214258671 0.1414113927 0.1883839816 0.0055079780 0.0319910000 290065793 0 402718720 -0.1720549762 -0.0319801718 -0.0279507786 495 1311867186.9334180355 0.1214653477 0.1413710976 0.1883839816 0.0055033359 0.0290620000 290068937 0 402718720 -0.1700969487 -0.0313419774 -0.0282673873 496 1311867186.9656929970 0.1210715547 0.1413301712 0.1883839816 0.0055024967 0.0317960000 290071969 0 402718720 -0.1659241915 -0.0279950630 -0.0284521990 497 1311867187.0017049313 0.1211725771 0.1412896126 0.1883839816 0.0055096046 0.0303220000 290075113 0 402718720 -0.1634610742 -0.0309089590 -0.0277015697 498 1311867187.0336399078 0.1216725782 0.1412502210 0.1883839816 0.0055162279 0.0299010000 290078257 0 402718720 -0.1616581529 -0.0288114194 -0.0288859140 499 1311867187.0632801056 0.1212713122 0.1412101831 0.1883839816 0.0055109883 0.0316050000 290081345 0 402718720 -0.1582292020 -0.0261013750 -0.0293098371 500 1311867187.1015949249 0.1213178858 0.1411703985 0.1883839816 0.0055090447 0.0297950000 290084713 0 402718720 -0.1554055810 -0.0279599298 -0.0287001673 501 1311867187.1339790821 0.1219880953 0.1411321105 0.1883839816 0.0055101441 0.0324830000 290087857 0 402718720 -0.1532946974 -0.0313573107 -0.0277513340 502 1311867187.1632618904 0.1216615960 0.1410933246 0.1883839816 0.0055114564 0.0314070000 290090945 0 402718720 -0.1510083228 -0.0272512399 -0.0297307149 503 1311867187.2041230202 0.1227295101 0.1410568160 0.1883839816 0.0055138627 0.0310660000 290094313 0 402718720 -0.1483132690 -0.0275691319 -0.0297067631 504 1311867187.2331590652 0.1226968393 0.1410203875 0.1883839816 0.0055130966 0.0354570000 290097401 0 402718720 -0.1466468275 -0.0298762489 -0.0295846891 505 1311867187.2633500099 0.1233438551 0.1409853844 0.1883839816 0.0055145434 0.0317500000 290100489 0 402718720 -0.1458277106 -0.0260778368 -0.0310081970 506 1311867187.3014860153 0.1230766848 0.1409499917 0.1883839816 0.0055182608 0.0298520000 290103745 0 402718720 -0.1440620124 -0.0282210801 -0.0304944031 507 1311867187.3336489201 0.1231957376 0.1409149735 0.1883839816 0.0055130611 0.0297930000 290106889 0 402718720 -0.1431526691 -0.0287519582 -0.0308905281 508 1311867187.3631711006 0.1230685934 0.1408798428 0.1883839816 0.0055081038 0.0316770000 290110033 0 402718720 -0.1419939250 -0.0281044077 -0.0314833447 509 1311867187.4033451080 0.1243258789 0.1408473203 0.1883839816 0.0055046559 0.0310950000 290113401 0 402718720 -0.1421985030 -0.0283516012 -0.0317853987 510 1311867187.4335799217 0.1239643767 0.1408142165 0.1883839816 0.0055035583 0.0315280000 290116489 0 402718720 -0.1400881708 -0.0284171514 -0.0321866348 511 1311867187.4631900787 0.1231267452 0.1407796030 0.1883839816 0.0054983181 0.0336390000 290119577 0 402718720 -0.1368032992 -0.0274206512 -0.0331564844 512 1311867187.5056259632 0.1243097633 0.1407474354 0.1883839816 0.0054952580 0.0332310000 290122945 0 402718720 -0.1342587024 -0.0296613425 -0.0329668522 513 1311867187.5341889858 0.1247382835 0.1407162285 0.1883839816 0.0054935188 0.0350380000 290179281 0 402718720 -0.1319250762 -0.0293287057 -0.0340419784 514 1311867187.5632169247 0.1245654523 0.1406848067 0.1883839816 0.0054882833 0.0342870000 290284769 0 402718720 -0.1285874546 -0.0297657512 -0.0347635485 515 1311867187.6045610905 0.1253129244 0.1406549584 0.1883839816 0.0055173104 0.0339890000 290288193 0 402718720 -0.1260539591 -0.0299244355 -0.0356334001 516 1311867187.6353919506 0.1254613698 0.1406255135 0.1883839816 0.0055134953 0.0350560000 290291337 0 402718720 -0.1229859442 -0.0312171746 -0.0359849893 517 1311867187.6632699966 0.1253151149 0.1405958995 0.1883839816 0.0055182761 0.0367210000 290294313 0 402718720 -0.1206982508 -0.0278106388 -0.0382704027 518 1311867187.7035639286 0.1272537559 0.1405701425 0.1883839816 0.0055214971 0.0328340000 290297681 0 402718720 -0.1195621789 -0.0294020195 -0.0380685180 519 1311867187.7345390320 0.1270141900 0.1405440231 0.1883839816 0.0055335486 0.0355150000 290300545 0 402718720 -0.1166950390 -0.0331885479 -0.0371020474 520 1311867187.7631900311 0.1264374405 0.1405168951 0.1883839816 0.0055379437 0.0345820000 290303633 0 402718720 -0.1150071099 -0.0274956040 -0.0405184850 521 1311867187.8017048836 0.1274037212 0.1404917259 0.1883839816 0.0055349521 0.0337640000 290306945 0 402718720 -0.1130481213 -0.0290466268 -0.0399488099 522 1311867187.8339490891 0.1274683177 0.1404667768 0.1883839816 0.0055308741 0.0358170000 290310089 0 402718720 -0.1110801846 -0.0285442378 -0.0407970175 523 1311867187.8634109497 0.1285870522 0.1404440622 0.1883839816 0.0055279686 0.0344300000 290313177 0 402718720 -0.1100875959 -0.0272811074 -0.0415941477 524 1311867187.9038710594 0.1280027181 0.1404203192 0.1883839816 0.0055261370 0.0344790000 290316601 0 402718720 -0.1070686281 -0.0259417277 -0.0423373431 525 1311867187.9332211018 0.1282725483 0.1403971806 0.1883839816 0.0055217484 0.0384260000 290319633 0 402718720 -0.1042386368 -0.0266686119 -0.0419736877 526 1311867187.9635341167 0.1281368732 0.1403738720 0.1883839816 0.0055329512 0.0383860000 290322777 0 402718720 -0.1010345444 -0.0283162054 -0.0417853966 527 1311867188.0047419071 0.1284860224 0.1403513144 0.1883839816 0.0055367980 0.0383770000 290326145 0 402718720 -0.0974071845 -0.0255790558 -0.0439742506 528 1311867188.0333039761 0.1290991455 0.1403300035 0.1883839816 0.0055403742 0.0390110000 290329177 0 402718720 -0.0948406979 -0.0265479106 -0.0439746790 529 1311867188.0634179115 0.1295633614 0.1403096507 0.1883839816 0.0055353693 0.0380150000 290332265 0 402718720 -0.0920660198 -0.0294027515 -0.0435289480 530 1311867188.1088800430 0.1304208189 0.1402909925 0.1883839816 0.0055342056 0.0380840000 290335857 0 402718720 -0.0890341923 -0.0281254742 -0.0454236194 531 1311867188.1359899044 0.1287720948 0.1402692997 0.1883839816 0.0055416726 0.0384610000 290338777 0 402718720 -0.0861210972 -0.0272438712 -0.0470242128 532 1311867188.1633601189 0.1309163570 0.1402517190 0.1883839816 0.0055515254 0.0384320000 290341809 0 402718720 -0.0837121159 -0.0302892197 -0.0462775268 533 1311867188.2026538849 0.1315013319 0.1402353017 0.1883839816 0.0055487043 0.0375910000 290345177 0 402718720 -0.0816747919 -0.0299874526 -0.0478872471 534 1311867188.2352008820 0.1310119182 0.1402180295 0.1883839816 0.0055547386 0.0379780000 290348265 0 402718720 -0.0787498057 -0.0288526099 -0.0494093969 535 1311867188.2632720470 0.1316438913 0.1402020030 0.1883839816 0.0055533345 0.0394250000 290351353 0 402718720 -0.0758801997 -0.0298079066 -0.0497526824 536 1311867188.3047189713 0.1328835785 0.1401883493 0.1883839816 0.0055494250 0.0397220000 290354777 0 402718720 -0.0728897974 -0.0298951063 -0.0505645722 537 1311867188.3314530849 0.1323265880 0.1401737091 0.1883839816 0.0055449973 0.0435680000 290357753 0 402718720 -0.0700744763 -0.0281307437 -0.0520484559 538 1311867188.3633821011 0.1328270882 0.1401600537 0.1883839816 0.0055437925 0.0406960000 290360897 0 402718720 -0.0682220906 -0.0269898064 -0.0533682071 539 1311867188.4020431042 0.1335028261 0.1401477026 0.1883839816 0.0055416372 0.0379970000 290364209 0 402718720 -0.0655865595 -0.0272828098 -0.0533191785 540 1311867188.4313850403 0.1325793266 0.1401336871 0.1883839816 0.0055375044 0.0405930000 290367297 0 402718720 -0.0608184002 -0.0273489710 -0.0529513024 541 1311867188.4632470608 0.1326948553 0.1401199369 0.1883839816 0.0055352778 0.0401250000 290370441 0 402718720 -0.0585745014 -0.0234792586 -0.0551775582 542 1311867188.5049009323 0.1344860792 0.1401095424 0.1883839816 0.0055365434 0.0381780000 290373809 0 402718720 -0.0569654927 -0.0246819351 -0.0543046631 543 1311867188.5314350128 0.1333674490 0.1400971260 0.1883839816 0.0055363530 0.0391370000 290376841 0 402718720 -0.0526725575 -0.0250781514 -0.0541335344 544 1311867188.5633320808 0.1333319843 0.1400846901 0.1883839816 0.0055560259 0.0398880000 290379985 0 402718720 -0.0504257269 -0.0203456171 -0.0564630441 545 1311867188.6045799255 0.1349114180 0.1400751978 0.1883839816 0.0055519077 0.0382710000 290383353 0 402718720 -0.0482429937 -0.0219525509 -0.0546149351 546 1311867188.6315000057 0.1341318637 0.1400643126 0.1883839816 0.0055493817 0.0395040000 290386329 0 402718720 -0.0447914004 -0.0228748508 -0.0544860438 547 1311867188.6633369923 0.1341143101 0.1400534351 0.1883839816 0.0055523191 0.0408170000 290389473 0 402718720 -0.0422454923 -0.0210226625 -0.0556665882 548 1311867188.7038140297 0.1347215772 0.1400437054 0.1883839816 0.0055560739 0.0408920000 290392841 0 402718720 -0.0386773460 -0.0227115974 -0.0551756360 549 1311867188.7315850258 0.1352946907 0.1400350551 0.1883839816 0.0055534574 0.0400620000 290395873 0 402718720 -0.0363031551 -0.0242224745 -0.0547320917 550 1311867188.7632939816 0.1349751949 0.1400258554 0.1883839816 0.0055526119 0.0398710000 290399017 0 402718720 -0.0326316245 -0.0216204785 -0.0570787601 551 1311867188.8045160770 0.1360177100 0.1400185811 0.1883839816 0.0055524137 0.1684420000 302725585 0 402718720 -0.0287460014 -0.0208874904 -0.0577557422 552 1311867188.8313500881 0.1377547532 0.1400144799 0.1883839816 0.0055524227 0.0410270000 306387769 0 402718720 -0.0304137673 -0.0214135665 -0.0606168434 553 1311867188.8635439873 0.1383627802 0.1400114931 0.1883839816 0.0055574257 0.0306690000 309583105 0 402718720 -0.0272977352 -0.0192453358 -0.0628893897 554 1311867188.9016199112 0.1398128271 0.1400111345 0.1883839816 0.0055571943 0.0276830000 309586417 0 402718720 -0.0250117294 -0.0180164371 -0.0643210486 555 1311867188.9314649105 0.1407848150 0.1400125285 0.1883839816 0.0055534774 0.0263720000 309589505 0 402718720 -0.0225654803 -0.0218709018 -0.0636585355 556 1311867188.9634439945 0.1413167566 0.1400148743 0.1883839816 0.0055540639 0.0282150000 309592705 0 402718720 -0.0198500901 -0.0202220753 -0.0655510351 557 1311867189.0052158833 0.1421735436 0.1400187498 0.1883839816 0.0055513279 0.0269640000 309596073 0 402718720 -0.0164022874 -0.0183138922 -0.0666618198 558 1311867189.0314381123 0.1412992328 0.1400210446 0.1883839816 0.0055482130 0.0267000000 309599049 0 402718720 -0.0112225525 -0.0193234086 -0.0659201667 559 1311867189.0635390282 0.1420474648 0.1400246697 0.1883839816 0.0055441085 0.0268400000 309602249 0 402718720 -0.0094101327 -0.0200291127 -0.0662007704 560 1311867189.1026289463 0.1423156708 0.1400287607 0.1883839816 0.0055415445 0.0250470000 309605561 0 402718720 -0.0072934520 -0.0183819029 -0.0670130178 561 1311867189.1313118935 0.1421874762 0.1400326087 0.1883839816 0.0055368094 0.0302260000 309608593 0 402718720 -0.0043836292 -0.0188803356 -0.0659542233 562 1311867189.1634199619 0.1426917166 0.1400373402 0.1883839816 0.0055340170 0.0279310000 309611793 0 402718720 -0.0038843665 -0.0197436884 -0.0657579005 563 1311867189.2018899918 0.1423945725 0.1400415271 0.1883839816 0.0055300168 0.0286530000 309615105 0 402718720 -0.0008650097 -0.0190482046 -0.0647938102 564 1311867189.2312850952 0.1426823139 0.1400462094 0.1883839816 0.0055252621 0.0321860000 309618137 0 402718720 0.0004153013 -0.0202399027 -0.0638800263 565 1311867189.2633450031 0.1438021809 0.1400528571 0.1883839816 0.0055221315 0.0313400000 309621281 0 402718720 0.0010527932 -0.0211016331 -0.0628444478 566 1311867189.3046789169 0.1438130885 0.1400595006 0.1883839816 0.0055187859 0.0258320000 309624761 0 402718720 0.0039932970 -0.0213169996 -0.0619877912 567 1311867189.3314049244 0.1441926807 0.1400667902 0.1883839816 0.0055142962 0.0288120000 309627681 0 402718720 0.0060082218 -0.0225697607 -0.0603256822 568 1311867189.3633348942 0.1438410431 0.1400734350 0.1883839816 0.0055095199 0.0291780000 309630825 0 402718720 0.0084628528 -0.0227237381 -0.0605030879 569 1311867189.4056839943 0.1441861689 0.1400806630 0.1883839816 0.0055053690 0.0290780000 309634249 0 402718720 0.0112590706 -0.0217103325 -0.0603965633 570 1311867189.4314579964 0.1446553171 0.1400886887 0.1883839816 0.0055028996 0.0303530000 309637225 0 402718720 0.0150608625 -0.0242611412 -0.0571627542 571 1311867189.4634540081 0.1445275992 0.1400964626 0.1883839816 0.0054997753 0.0291630000 309640369 0 402718720 0.0183622334 -0.0247751847 -0.0574454293 572 1311867189.5059370995 0.1458702236 0.1401065566 0.1883839816 0.0054958870 0.0292590000 309643793 0 402718720 0.0207794197 -0.0247461665 -0.0579423569 573 1311867189.5314168930 0.1460898817 0.1401169987 0.1883839816 0.0054938820 0.0311490000 309646769 0 402718720 0.0247612987 -0.0268349703 -0.0559054874 574 1311867189.5633189678 0.1465174258 0.1401281493 0.1883839816 0.0054906029 0.0305920000 309649913 0 402718720 0.0275110472 -0.0298592970 -0.0563973039 575 1311867189.5993690491 0.1467390507 0.1401396465 0.1883839816 0.0054864001 0.0308750000 309653225 0 402718720 0.0304461438 -0.0290923268 -0.0582983755 576 1311867189.6313779354 0.1473704726 0.1401522000 0.1883839816 0.0054834854 0.0316990000 309656313 0 402718720 0.0343806148 -0.0285285749 -0.0582815073 577 1311867189.6634690762 0.1476152688 0.1401651343 0.1883839816 0.0054879270 0.0397900000 309659457 0 402718720 0.0388303623 -0.0305050146 -0.0570041277 578 1311867189.6997840405 0.1490347534 0.1401804797 0.1883839816 0.0055003213 0.0315720000 309662657 0 402718720 0.0408836268 -0.0290722735 -0.0587453097 579 1311867189.7314579487 0.1488503069 0.1401954535 0.1883839816 0.0054956273 0.0309510000 309665801 0 402718720 0.0452658944 -0.0282144584 -0.0590148866 580 1311867189.7633609772 0.1488865614 0.1402104381 0.1883839816 0.0054928433 0.0324190000 309669001 0 402718720 0.0494337827 -0.0283056088 -0.0582101122 581 1311867189.7994859219 0.1499784440 0.1402272505 0.1883839816 0.0054957727 0.0330290000 309672201 0 402718720 0.0519312359 -0.0290324856 -0.0565266088 582 1311867189.8313660622 0.1503046602 0.1402445657 0.1883839816 0.0054914625 0.0304450000 309675345 0 402718720 0.0544744246 -0.0286140181 -0.0571537316 583 1311867189.8634099960 0.1511064321 0.1402631966 0.1883839816 0.0054880707 0.0333400000 309678545 0 402718720 0.0582550094 -0.0292816088 -0.0548055135 584 1311867189.8995211124 0.1528874934 0.1402848136 0.1883839816 0.0054840292 0.0337810000 309681801 0 402718720 0.0597465560 -0.0300994664 -0.0534431152 585 1311867189.9313640594 0.1529795676 0.1403065140 0.1883839816 0.0054808147 0.0342850000 309684889 0 402718720 0.0624427833 -0.0296057202 -0.0541932955 586 1311867189.9633400440 0.1534934342 0.1403290173 0.1883839816 0.0054768667 0.0331430000 309688089 0 402718720 0.0656920820 -0.0292653982 -0.0537231825 587 1311867189.9994339943 0.1537683904 0.1403519123 0.1883839816 0.0054730845 0.0330120000 309691289 0 402718720 0.0693578422 -0.0308810044 -0.0523180515 588 1311867190.0315160751 0.1538270265 0.1403748292 0.1883839816 0.0054689150 0.0337160000 309694433 0 402718720 0.0722851902 -0.0303001869 -0.0535088703 589 1311867190.0634539127 0.1562287658 0.1404017459 0.1883839816 0.0054670558 0.0315350000 309697577 0 402718720 0.0751908422 -0.0302497000 -0.0506998003 590 1311867190.0995900631 0.1569278389 0.1404297562 0.1883839816 0.0054627478 0.0333360000 309700777 0 402718720 0.0782111585 -0.0315462314 -0.0500162952 591 1311867190.1314220428 0.1561080813 0.1404562847 0.1883839816 0.0054584651 0.0877450000 322011653 0 402718720 0.0816535503 -0.0316063128 -0.0517452806 592 1311867190.1635251045 0.1570619494 0.1404843348 0.1883839816 0.0054602063 0.0271400000 325674061 0 402718720 0.0819941834 -0.0336280055 -0.0528331436 593 1311867190.1994919777 0.1573239714 0.1405127322 0.1883839816 0.0054574493 0.0363610000 328869509 0 402718720 0.0843412355 -0.0362694189 -0.0527665652 594 1311867190.2313890457 0.1571924090 0.1405408124 0.1883839816 0.0054681735 0.0275690000 328872541 0 402718720 0.0871864855 -0.0342432968 -0.0547834039 595 1311867190.2633810043 0.1580164433 0.1405701832 0.1883839816 0.0054636925 0.0238360000 328875741 0 402718720 0.0902315676 -0.0348286182 -0.0533127859 596 1311867190.2993760109 0.1587678194 0.1406007162 0.1883839816 0.0054598247 0.0246820000 328878941 0 402718720 0.0921786577 -0.0351728685 -0.0535631701 597 1311867190.3313589096 0.1591641158 0.1406318106 0.1883839816 0.0054566208 0.0259390000 328882085 0 402718720 0.0944637731 -0.0344601758 -0.0540690608 598 1311867190.3634369373 0.1590728611 0.1406626485 0.1883839816 0.0054580772 0.0256980000 328885285 0 402718720 0.0976121649 -0.0334175266 -0.0539976284 599 1311867190.3994669914 0.1589624733 0.1406931991 0.1883839816 0.0054539854 0.0232010000 328888485 0 402718720 0.1004957184 -0.0341510437 -0.0538750589 600 1311867190.4313740730 0.1586106271 0.1407230615 0.1883839816 0.0054523812 0.0250280000 328891685 0 402718720 0.1032264903 -0.0317110494 -0.0547672287 601 1311867190.4633409977 0.1601525396 0.1407553901 0.1883839816 0.0054522055 0.0256450000 328894829 0 402718720 0.1044653952 -0.0340890326 -0.0529977493 602 1311867190.4993569851 0.1600317210 0.1407874106 0.1883839816 0.0054490802 0.0274700000 328898141 0 402718720 0.1063990816 -0.0351107195 -0.0534286946 603 1311867190.5318090916 0.1599613130 0.1408192081 0.1883839816 0.0054469785 0.0260020000 328901229 0 402718720 0.1098337322 -0.0326932780 -0.0537539274 604 1311867190.5633530617 0.1603762805 0.1408515874 0.1883839816 0.0054427048 0.0252030000 328904373 0 402718720 0.1119033173 -0.0346352942 -0.0523815826 605 1311867190.5994510651 0.1607023478 0.1408843985 0.1883839816 0.0054387813 0.0270800000 328907629 0 402718720 0.1135232449 -0.0357594118 -0.0524994358 606 1311867190.6314210892 0.1612578928 0.1409180182 0.1883839816 0.0054355767 0.0277880000 328910717 0 402718720 0.1157112047 -0.0345874988 -0.0523369275 607 1311867190.6634240150 0.1614296585 0.1409518100 0.1883839816 0.0054341936 0.0269070000 328913917 0 402718720 0.1187500209 -0.0364836343 -0.0506046414 608 1311867190.6996390820 0.1620495468 0.1409865102 0.1883839816 0.0054310810 0.0265580000 328917117 0 402718720 0.1199133471 -0.0360212922 -0.0513768159 609 1311867190.7313809395 0.1625596732 0.1410219341 0.1883839816 0.0054270743 0.0265830000 328920205 0 402718720 0.1215593442 -0.0364677198 -0.0505925044 610 1311867190.7634749413 0.1618687361 0.1410561092 0.1883839816 0.0054240072 0.0279920000 328923405 0 402718720 0.1240676716 -0.0370435938 -0.0506559573 611 1311867190.7994329929 0.1622828543 0.1410908502 0.1883839816 0.0054199743 0.0274780000 328926605 0 402718720 0.1262262017 -0.0370415524 -0.0497441776 612 1311867190.8317101002 0.1636415124 0.1411276977 0.1883839816 0.0054158937 0.0295730000 328929805 0 402718720 0.1290333569 -0.0376435816 -0.0460592397 613 1311867190.8634259701 0.1636837125 0.1411644938 0.1883839816 0.0054121655 0.0271440000 328932949 0 402718720 0.1310041249 -0.0376644395 -0.0464814417 614 1311867190.8994319439 0.1644462347 0.1412024120 0.1883839816 0.0054081466 0.0301320000 328936261 0 402718720 0.1323768646 -0.0374821164 -0.0461460091 615 1311867190.9316470623 0.1649417281 0.1412410125 0.1883839816 0.0054043240 0.0298980000 328939349 0 402718720 0.1350986362 -0.0386327319 -0.0437984467 616 1311867190.9635319710 0.1652442217 0.1412799787 0.1883839816 0.0054003685 0.0313910000 328942549 0 402718720 0.1368685514 -0.0394130535 -0.0437398627 617 1311867190.9994399548 0.1641304344 0.1413170135 0.1883839816 0.0053960254 0.0303280000 328945805 0 402718720 0.1391844898 -0.0383305363 -0.0461935252 618 1311867191.0313270092 0.1660383344 0.1413570156 0.1883839816 0.0053933086 0.0304730000 328948837 0 402718720 0.1415643394 -0.0374872759 -0.0427494831 619 1311867191.0636270046 0.1662660092 0.1413972563 0.1883839816 0.0053907872 0.0309350000 328952037 0 402718720 0.1438828856 -0.0407083109 -0.0404206626 620 1311867191.0994319916 0.1659941524 0.1414369287 0.1883839816 0.0053880286 0.0301760000 328955349 0 402718720 0.1461735070 -0.0391658396 -0.0417987294 621 1311867191.1313030720 0.1666287482 0.1414774953 0.1883839816 0.0053842258 0.0306710000 328958437 0 402718720 0.1491329670 -0.0382731520 -0.0402234718 622 1311867191.1633949280 0.1677832454 0.1415197875 0.1883839816 0.0054089174 0.0318180000 328961581 0 402718720 0.1509933323 -0.0401334167 -0.0378750339 623 1311867191.1993889809 0.1670618355 0.1415607860 0.1883839816 0.0054161936 0.0318080000 328964781 0 402718720 0.1539584696 -0.0393021181 -0.0392983332 624 1311867191.2313950062 0.1677915901 0.1416028225 0.1883839816 0.0054120762 0.0313920000 328967925 0 402718720 0.1566960812 -0.0389243066 -0.0377484038 625 1311867191.2634680271 0.1683398783 0.1416456018 0.1883839816 0.0054080008 0.0317840000 328971125 0 402718720 0.1594341546 -0.0393013954 -0.0363968275 626 1311867191.2997128963 0.1673797518 0.1416867107 0.1883839816 0.0054052407 0.0316850000 328974381 0 402718720 0.1619681269 -0.0406460129 -0.0375623852 627 1311867191.3316600323 0.1697498560 0.1417314685 0.1883839816 0.0054104868 0.0314050000 328977357 0 402718720 0.1634912640 -0.0398429967 -0.0352423340 628 1311867191.3634359837 0.1713856161 0.1417786884 0.1883839816 0.0054072545 0.0329640000 328980501 0 402718720 0.1639341265 -0.0412421077 -0.0332033187 629 1311867191.3995709419 0.1709385812 0.1418250476 0.1883839816 0.0054037704 0.0290870000 328983757 0 402718720 0.1673825383 -0.0402899422 -0.0329985209 630 1311867191.4315879345 0.1693242192 0.1418686970 0.1883839816 0.0054021256 0.0322540000 328986845 0 402718720 0.1708076447 -0.0407279730 -0.0336666256 631 1311867191.4634139538 0.1711650193 0.1419151255 0.1883839816 0.0053988103 0.0326010000 328990045 0 402718720 0.1718136370 -0.0410380810 -0.0314324088 632 1311867191.4996531010 0.1717677414 0.1419623606 0.1883839816 0.0053951846 0.0335610000 328993133 0 402718720 0.1726103127 -0.0408428647 -0.0317635499 633 1311867191.5314459801 0.1717770994 0.1420094613 0.1883839816 0.0053944953 0.0358940000 328996277 0 402718720 0.1753462106 -0.0415578708 -0.0296250973 634 1311867191.5636389256 0.1712868363 0.1420556401 0.1883839816 0.0053931448 0.0318470000 328999421 0 402718720 0.1774030477 -0.0421257541 -0.0298170913 635 1311867191.5998470783 0.1721538901 0.1421030389 0.1883839816 0.0053975133 0.0321080000 329002677 0 402718720 0.1793171018 -0.0404058397 -0.0295791738 636 1311867191.6314690113 0.1729391068 0.1421515233 0.1883839816 0.0053987966 0.0332470000 329005765 0 402718720 0.1808677018 -0.0405083187 -0.0270935763 637 1311867191.6636199951 0.1731265187 0.1422001497 0.1883839816 0.0054029232 0.0336650000 329008965 0 402718720 0.1817148775 -0.0408061333 -0.0266666990 638 1311867191.6995730400 0.1717883945 0.1422465262 0.1883839816 0.0054047830 0.0363740000 329012277 0 402718720 0.1842664033 -0.0403894074 -0.0264130346 639 1311867191.7314870358 0.1727436930 0.1422942526 0.1883839816 0.0054043660 0.0429620000 329015253 0 402718720 0.1854503900 -0.0415329300 -0.0235870555 640 1311867191.7635788918 0.1729824096 0.1423422029 0.1883839816 0.0054005401 0.0333770000 329018397 0 402718720 0.1857441068 -0.0422197916 -0.0245243032 641 1311867191.7997710705 0.1741551906 0.1423918331 0.1883839816 0.0053987317 0.0327260000 329021709 0 402718720 0.1879934967 -0.0378148966 -0.0226487275 642 1311867191.8315110207 0.1738236994 0.1424407924 0.1883839816 0.0053978001 0.0416280000 329024797 0 402718720 0.1884364933 -0.0415623784 -0.0213051531 643 1311867191.8634710312 0.1739915907 0.1424898605 0.1883839816 0.0053944009 0.0329480000 329027941 0 402718720 0.1891334802 -0.0405823886 -0.0214336906 644 1311867191.8996229172 0.1748255789 0.1425400713 0.1883839816 0.0053953986 0.0317790000 329031197 0 402718720 0.1911926717 -0.0377781317 -0.0197241195 645 1311867191.9316298962 0.1746344417 0.1425898300 0.1883839816 0.0053943061 0.0363500000 329034341 0 402718720 0.1915076673 -0.0413624346 -0.0176870916 646 1311867191.9634699821 0.1743777394 0.1426390373 0.1883839816 0.0053917804 0.0325720000 329037485 0 402718720 0.1926239282 -0.0407862812 -0.0185667258 647 1311867191.9995260239 0.1750623584 0.1426891506 0.1883839816 0.0053908999 0.0335180000 329040685 0 402718720 0.1946297437 -0.0389971994 -0.0164827947 648 1311867192.0315270424 0.1764424145 0.1427412390 0.1883839816 0.0053876533 0.0340080000 329043829 0 402718720 0.1943268180 -0.0417388603 -0.0137093551 649 1311867192.0634949207 0.1756633669 0.1427919665 0.1883839816 0.0053862445 0.0290580000 329047029 0 402718720 0.1956513971 -0.0405329242 -0.0153270410 650 1311867192.0998060703 0.1752174199 0.1428418518 0.1883839816 0.0053874941 0.0317890000 329050285 0 402718720 0.1984910369 -0.0379561856 -0.0149243334 651 1311867192.1316659451 0.1773367077 0.1428948393 0.1883839816 0.0053868013 0.0319680000 329053373 0 402718720 0.1979785413 -0.0410429686 -0.0110249240 652 1311867192.1635160446 0.1757933050 0.1429452970 0.1883839816 0.0053834295 0.0362310000 329056573 0 402718720 0.1996740103 -0.0412987024 -0.0130481897 653 1311867192.1996529102 0.1776891649 0.1429985036 0.1883839816 0.0053848583 0.0332610000 329059773 0 402718720 0.2014269382 -0.0380261466 -0.0107270954 654 1311867192.2316989899 0.1783659011 0.1430525822 0.1883839816 0.0053815638 0.0346990000 329062917 0 402718720 0.2015239596 -0.0412519574 -0.0087542050 655 1311867192.2635419369 0.1760922819 0.1431030244 0.1883839816 0.0053828296 0.0331090000 329066117 0 402718720 0.2039741278 -0.0421633534 -0.0105351834 656 1311867192.2994730473 0.1774010062 0.1431553080 0.1883839816 0.0053789537 0.0348640000 329069317 0 402718720 0.2058072686 -0.0411810018 -0.0081605595 657 1311867192.3315188885 0.1783093810 0.1432088149 0.1883839816 0.0053750591 0.0342740000 329072461 0 402718720 0.2066321969 -0.0424167886 -0.0069639962 658 1311867192.3636200428 0.1774577647 0.1432608650 0.1883839816 0.0053713219 0.0348800000 329075661 0 402718720 0.2087980509 -0.0423104838 -0.0084079225 659 1311867192.3994910717 0.1789492667 0.1433150204 0.1883839816 0.0053733729 0.0350270000 329078917 0 402718720 0.2108623683 -0.0411621854 -0.0063703884 660 1311867192.4316198826 0.1798165143 0.1433703257 0.1883839816 0.0053703096 0.1349870000 341395129 0 402718720 0.2118196487 -0.0438039824 -0.0049244817 661 1311867192.4635419846 0.1952845305 0.1434488646 0.1952845305 0.0055543312 0.0391550000 345057481 0 402718720 0.1904550493 -0.0350901634 -0.0221057385 662 1311867192.4995899200 0.1959670633 0.1435281972 0.1959670633 0.0055504688 0.0262870000 348252929 0 402718720 0.1918406337 -0.0358149670 -0.0213115364 663 1311867192.5316200256 0.1967539936 0.1436084774 0.1967539936 0.0055463871 0.0248670000 348256073 0 402718720 0.1926626414 -0.0373708792 -0.0205355939 664 1311867192.5636320114 0.1967453063 0.1436885028 0.1967539936 0.0055424007 0.0246260000 348259217 0 402718720 0.1947495639 -0.0361903347 -0.0217667855 665 1311867192.5996320248 0.1971431226 0.1437688857 0.1971431226 0.0055382817 0.0246300000 348262473 0 402718720 0.1962631047 -0.0366984569 -0.0210085008 666 1311867192.6315209866 0.1978798360 0.1438501333 0.1978798360 0.0055381800 0.0237020000 348265561 0 402718720 0.1970253736 -0.0381261706 -0.0200069323 667 1311867192.6636250019 0.1978040189 0.1439310237 0.1978798360 0.0055344627 0.0227100000 348268761 0 402718720 0.1988758445 -0.0371754393 -0.0211286787 668 1311867192.6996068954 0.1980994791 0.1440121142 0.1980994791 0.0055303953 0.0229450000 348272017 0 402718720 0.2002509087 -0.0375104025 -0.0203799699 669 1311867192.7316179276 0.1990940422 0.1440944489 0.1990940422 0.0055268299 0.0225680000 348275105 0 402718720 0.2005462497 -0.0386953950 -0.0193491280 670 1311867192.7636420727 0.1984931529 0.1441756410 0.1990940422 0.0055233623 0.0260000000 348278305 0 402718720 0.2026007175 -0.0375436246 -0.0205078311 671 1311867192.7994999886 0.1991184354 0.1442575230 0.1991184354 0.0055196156 0.0240170000 348281505 0 402718720 0.2039228380 -0.0375758260 -0.0191303492 672 1311867192.8316929340 0.1999564320 0.1443404083 0.1999564320 0.0055157853 0.0240820000 348284705 0 402718720 0.2041365355 -0.0387553498 -0.0182320587 673 1311867192.8636040688 0.1995107532 0.1444223850 0.1999564320 0.0055121146 0.0271040000 348287849 0 402718720 0.2062580734 -0.0362728424 -0.0192723628 674 1311867192.8996539116 0.1997998059 0.1445045474 0.1999564320 0.0055083800 0.0245000000 348291105 0 402718720 0.2066411227 -0.0375496782 -0.0184948333 675 1311867192.9316558838 0.2006518543 0.1445877285 0.2006518543 0.0055045698 0.0243200000 348294249 0 402718720 0.2064949870 -0.0394008979 -0.0171860792 676 1311867192.9638249874 0.1994021386 0.1446688150 0.2006518543 0.0055013693 0.0225320000 348297449 0 402718720 0.2097373456 -0.0371655636 -0.0186738614 677 1311867192.9997138977 0.2004027069 0.1447511398 0.2006518543 0.0054976924 0.0226680000 348300593 0 402718720 0.2100814283 -0.0376769379 -0.0171642266 678 1311867193.0316529274 0.2018103749 0.1448352979 0.2018103749 0.0054950285 0.0235990000 348303737 0 402718720 0.2094065696 -0.0401333906 -0.0153034115 679 1311867193.0636160374 0.2000501454 0.1449166158 0.2018103749 0.0054924230 0.0254430000 348306881 0 402718720 0.2121063620 -0.0388706103 -0.0184640102 680 1311867193.0996270180 0.2010416240 0.1449991526 0.2018103749 0.0054894903 0.0254720000 348310081 0 402718720 0.2132544070 -0.0381492600 -0.0168595426 681 1311867193.1316359043 0.2013792992 0.1450819428 0.2018103749 0.0054875127 0.0235880000 348313281 0 402718720 0.2140126526 -0.0401183292 -0.0151511384 682 1311867193.1638090611 0.2006645799 0.1451634423 0.2018103749 0.0054850896 0.0270230000 348316425 0 402718720 0.2165282369 -0.0376566052 -0.0175411273 683 1311867193.1995921135 0.2027666569 0.1452477808 0.2027666569 0.0054828805 0.0241310000 348319625 0 402718720 0.2161477059 -0.0384146683 -0.0146884723 684 1311867193.2316339016 0.2019675672 0.1453307045 0.2027666569 0.0054820770 0.0230550000 348322825 0 402718720 0.2177961916 -0.0398850478 -0.0149540063 685 1311867193.2635540962 0.2015210539 0.1454127342 0.2027666569 0.0054788299 0.0251040000 348325969 0 402718720 0.2196195275 -0.0385352597 -0.0161671285 686 1311867193.2995169163 0.2030526251 0.1454967573 0.2030526251 0.0054748832 0.0249630000 348329225 0 402718720 0.2197649181 -0.0399628617 -0.0138570443 687 1311867193.3314299583 0.2025748491 0.1455798405 0.2030526251 0.0054711533 0.0234670000 348332313 0 402718720 0.2215537578 -0.0396901593 -0.0148071954 688 1311867193.3636779785 0.2024434507 0.1456624910 0.2030526251 0.0054682225 0.0256330000 348335457 0 402718720 0.2232198268 -0.0384041518 -0.0157083552 689 1311867193.3995571136 0.2033174634 0.1457461703 0.2033174634 0.0054674371 0.0261030000 348338657 0 402718720 0.2242746800 -0.0397029594 -0.0134102898 690 1311867193.4318170547 0.2033446431 0.1458296463 0.2033446431 0.0054636552 0.0218200000 348341857 0 402718720 0.2251992673 -0.0398900956 -0.0149072036 691 1311867193.4635589123 0.2032904327 0.1459128023 0.2033446431 0.0054599930 0.0255060000 348345001 0 402718720 0.2268516123 -0.0390855595 -0.0154827004 692 1311867193.4995489120 0.2040997893 0.1459968875 0.2040997893 0.0054562661 0.0251320000 348348201 0 402718720 0.2279319912 -0.0401034057 -0.0137468772 693 1311867193.5316190720 0.2037359178 0.1460802050 0.2040997893 0.0054531901 0.0241950000 348351401 0 402718720 0.2295321077 -0.0404687822 -0.0150665231 694 1311867193.5635840893 0.2036762536 0.1461631965 0.2040997893 0.0054493048 0.0273220000 348354545 0 402718720 0.2312110215 -0.0399412140 -0.0158045478 695 1311867193.5995330811 0.2055429667 0.1462486350 0.2055429667 0.0054477434 0.0275010000 348357801 0 402718720 0.2312913984 -0.0406883471 -0.0132841701 696 1311867193.6317420006 0.2045527250 0.1463324052 0.2055429667 0.0054443442 0.0246290000 348360945 0 402718720 0.2332999259 -0.0406429581 -0.0150747709 697 1311867193.6635909081 0.2045684308 0.1464159576 0.2055429667 0.0054406929 0.0270420000 348364089 0 402718720 0.2351918966 -0.0392896682 -0.0158718508 698 1311867193.6995389462 0.2057856321 0.1465010145 0.2057856321 0.0054382946 0.0260650000 348367345 0 402718720 0.2351990044 -0.0409766100 -0.0142283756 699 1311867193.7315680981 0.2050486952 0.1465847737 0.2057856321 0.0054354224 0.0257790000 348370433 0 402718720 0.2366196215 -0.0413257293 -0.0161913075 700 1311867193.7635669708 0.2048432231 0.1466680000 0.2057856321 0.0054318362 0.0272380000 348373577 0 402718720 0.2392809093 -0.0395749323 -0.0158169083 701 1311867193.7996909618 0.2061492950 0.1467528521 0.2061492950 0.0054283274 0.0276710000 348376889 0 402718720 0.2392821312 -0.0410437100 -0.0143609792 702 1311867193.8315539360 0.2058644444 0.1468370566 0.2061492950 0.0054310350 0.0262790000 348379977 0 402718720 0.2403309494 -0.0417358391 -0.0159742758 703 1311867193.8635230064 0.2058601230 0.1469210155 0.2061492950 0.0054273393 0.0282890000 348383121 0 402718720 0.2421817631 -0.0408642963 -0.0161374435 704 1311867193.8996899128 0.2063436359 0.1470054226 0.2063436359 0.0054241176 0.0249830000 348386377 0 402718720 0.2433586568 -0.0420909300 -0.0149448961 705 1311867193.9315669537 0.2065866888 0.1470899350 0.2065866888 0.0054202931 0.0290630000 348389521 0 402718720 0.2437621057 -0.0418760404 -0.0170704313 706 1311867193.9637041092 0.2068833262 0.1471746282 0.2068833262 0.0054165958 0.0270540000 348392665 0 402718720 0.2454583943 -0.0410621502 -0.0165311061 707 1311867193.9997029305 0.2072421908 0.1472595894 0.2072421908 0.0054131143 0.0283360000 348395921 0 402718720 0.2466036826 -0.0423751958 -0.0151762692 708 1311867194.0316889286 0.2068607211 0.1473437718 0.2072421908 0.0054097198 0.0280690000 348399065 0 402718720 0.2477352172 -0.0424541198 -0.0173608977 709 1311867194.0636529922 0.2069008499 0.1474277733 0.2072421908 0.0054059684 0.0274350000 348402209 0 402718720 0.2496306747 -0.0411611646 -0.0171207897 710 1311867194.0996799469 0.2071632892 0.1475119079 0.2072421908 0.0054099495 0.0282470000 348405521 0 402718720 0.2495253682 -0.0424450226 -0.0157573298 711 1311867194.1317200661 0.2073304653 0.1475960408 0.2073304653 0.0054138471 0.0288480000 348408609 0 402718720 0.2503515184 -0.0424489416 -0.0179927032 712 1311867194.1635859013 0.2073336542 0.1476799420 0.2073336542 0.0054115642 0.0303210000 348411753 0 402718720 0.2518724799 -0.0406789705 -0.0171060637 713 1311867194.1996850967 0.2086964548 0.1477655191 0.2086964548 0.0054134804 0.0303240000 348414953 0 402718720 0.2510628402 -0.0427719690 -0.0149555365 714 1311867194.2315490246 0.2079202384 0.1478497695 0.2086964548 0.0054107360 0.0295700000 348418097 0 402718720 0.2520739138 -0.0421184562 -0.0170618370 715 1311867194.2636189461 0.2082216889 0.1479342057 0.2086964548 0.0054074583 0.0286100000 348421185 0 402718720 0.2530262470 -0.0413055979 -0.0158018265 716 1311867194.2997159958 0.2086823434 0.1480190495 0.2086964548 0.0054037165 0.0291010000 348424385 0 402718720 0.2528275251 -0.0426425338 -0.0146839181 717 1311867194.3317608833 0.2088449895 0.1481038834 0.2088449895 0.0054043680 0.0295670000 348427585 0 402718720 0.2532149553 -0.0419307053 -0.0159461275 718 1311867194.3637061119 0.2084942907 0.1481879926 0.2088449895 0.0054049021 0.0277580000 348430729 0 402718720 0.2541794777 -0.0418766439 -0.0153197553 719 1311867194.3996109962 0.2092636824 0.1482729379 0.2092636824 0.0054061463 0.0297990000 348433985 0 402718720 0.2543397248 -0.0425362848 -0.0133425975 720 1311867194.4318029881 0.2086354494 0.1483567748 0.2092636824 0.0054030668 0.0288130000 348437073 0 402718720 0.2551183999 -0.0426836722 -0.0144590111 721 1311867194.4638750553 0.2091142684 0.1484410431 0.2092636824 0.0053997622 0.0285020000 348440273 0 402718720 0.2553212941 -0.0423325971 -0.0143826930 722 1311867194.4996290207 0.2094374746 0.1485255257 0.2094374746 0.0053962087 0.0275960000 348443417 0 402718720 0.2556587160 -0.0430019125 -0.0133574260 723 1311867194.5316059589 0.2085682899 0.1486085724 0.2094374746 0.0053937565 0.0266610000 348446561 0 402718720 0.2560911179 -0.0430392511 -0.0145365242 724 1311867194.5637359619 0.2092145085 0.1486922823 0.2094374746 0.0053919708 0.0277010000 348449705 0 402718720 0.2564837337 -0.0425743386 -0.0141453259 725 1311867194.5996220112 0.2092581540 0.1487758214 0.2094374746 0.0053883729 0.0276200000 348452961 0 402718720 0.2568115890 -0.0431324169 -0.0133320047 726 1311867194.6318879128 0.2093055397 0.1488591957 0.2094374746 0.0053929925 0.0295680000 348456049 0 402718720 0.2569152415 -0.0424265675 -0.0141322045 727 1311867194.6636140347 0.2087185532 0.1489415332 0.2094374746 0.0053907833 0.0276660000 348459193 0 402718720 0.2576715648 -0.0426221006 -0.0137730744 728 1311867194.6996710300 0.2089170963 0.1490239172 0.2094374746 0.0053871849 0.0294790000 348462449 0 402718720 0.2578187287 -0.0428120941 -0.0135228150 729 1311867194.7317550182 0.2088221461 0.1491059449 0.2094374746 0.0053841033 0.0286190000 348465593 0 402718720 0.2582943738 -0.0427095853 -0.0135445315 730 1311867194.7635860443 0.2090488076 0.1491880585 0.2094374746 0.0053804761 0.0271910000 348468737 0 402718720 0.2585537136 -0.0428111404 -0.0126392459 731 1311867194.7997260094 0.2090826482 0.1492699936 0.2094374746 0.0053851294 0.0278720000 348472049 0 402718720 0.2587959170 -0.0425408892 -0.0130105559 732 1311867194.8318910599 0.2090878338 0.1493517120 0.2094374746 0.0053815007 0.0293120000 348475137 0 402718720 0.2589996755 -0.0424838886 -0.0124990745 733 1311867194.8636679649 0.2090378851 0.1494331392 0.2094374746 0.0053778337 0.0276730000 348478281 0 402718720 0.2587978244 -0.0423548035 -0.0126194591 734 1311867194.8995881081 0.2087947428 0.1495140133 0.2094374746 0.0053856841 0.0289190000 348481593 0 402718720 0.2587997913 -0.0422230773 -0.0125027644 735 1311867194.9318230152 0.2098371238 0.1495960856 0.2098371238 0.0053826134 0.0289920000 348484681 0 402718720 0.2576265931 -0.0423524380 -0.0107592698 736 1311867194.9638640881 0.2096926570 0.1496777385 0.2098371238 0.0053790838 0.0287990000 348487825 0 402718720 0.2573595941 -0.0422529839 -0.0103526600 737 1311867194.9998569489 0.2093475759 0.1497587017 0.2098371238 0.0053755647 0.0269710000 348491081 0 402718720 0.2570289969 -0.0415851660 -0.0106829312 738 1311867195.0318229198 0.2106595784 0.1498412232 0.2106595784 0.0053759944 0.0288990000 348494225 0 402718720 0.2550244927 -0.0418620147 -0.0081169410 739 1311867195.0636589527 0.2091695517 0.1499215051 0.2106595784 0.0053738840 0.0297410000 348497369 0 402718720 0.2551460862 -0.0418280102 -0.0109319538 740 1311867195.0998389721 0.2082449645 0.1500003206 0.2106595784 0.0053758402 0.0277280000 348500569 0 402718720 0.2553965449 -0.0415368006 -0.0113571119 741 1311867195.1317551136 0.2086807936 0.1500795115 0.2106595784 0.0053728225 0.0289610000 348503769 0 402718720 0.2545219362 -0.0416740440 -0.0105814468 742 1311867195.1637389660 0.2082828581 0.1501579527 0.2106595784 0.0053696887 0.0281020000 348506913 0 402718720 0.2534159422 -0.0412526578 -0.0119071882 743 1311867195.1996819973 0.2087220103 0.1502367737 0.2106595784 0.0053687312 0.0269680000 348510169 0 402718720 0.2522030771 -0.0408693552 -0.0110574737 744 1311867195.2319529057 0.2075375766 0.1503137910 0.2106595784 0.0053662717 0.0285730000 348513313 0 402718720 0.2521209121 -0.0411337651 -0.0104474248 745 1311867195.2639589310 0.2071910053 0.1503901362 0.2106595784 0.0053634755 0.0264360000 348516513 0 402718720 0.2515521348 -0.0412751548 -0.0112653002 746 1311867195.2998430729 0.2076314241 0.1504668672 0.2106595784 0.0053605279 0.0276560000 348519713 0 402718720 0.2504152060 -0.0405977368 -0.0108696725 747 1311867195.3316628933 0.2086498141 0.1505447560 0.2106595784 0.0053573472 0.0291590000 348522801 0 402718720 0.2486256361 -0.0418406725 -0.0085221073 748 1311867195.3636600971 0.2068723589 0.1506200603 0.2106595784 0.0053550715 0.0274910000 348525945 0 402718720 0.2485323101 -0.0410815999 -0.0117161172 749 1311867195.3998188972 0.2069627345 0.1506952841 0.2106595784 0.0053621811 0.0272920000 348529201 0 402718720 0.2474882603 -0.0407250673 -0.0113878055 750 1311867195.4317750931 0.2074304223 0.1507709310 0.2106595784 0.0053600958 0.0277760000 348532345 0 402718720 0.2450634837 -0.0421008989 -0.0108525241 751 1311867195.4637739658 0.2062331736 0.1508447822 0.2106595784 0.0053625599 0.0275600000 348535489 0 402718720 0.2444806099 -0.0409198627 -0.0133326743 752 1311867195.4998610020 0.2062401921 0.1509184463 0.2106595784 0.0053592475 0.0262180000 348538745 0 402718720 0.2436970621 -0.0400750749 -0.0123701431 753 1311867195.5318269730 0.2063349783 0.1509920406 0.2106595784 0.0053569968 0.0285340000 348541889 0 402718720 0.2416751981 -0.0415024459 -0.0112413242 754 1311867195.5637209415 0.2054006904 0.1510642006 0.2106595784 0.0053536050 0.0277890000 348545089 0 402718720 0.2406474352 -0.0409021452 -0.0126725081 755 1311867195.5997560024 0.2052252591 0.1511359371 0.2106595784 0.0053501356 0.0275540000 348548345 0 402718720 0.2396064550 -0.0406610332 -0.0119144097 756 1311867195.6317939758 0.2049487084 0.1512071180 0.2106595784 0.0053483313 0.0276120000 348551433 0 402718720 0.2376688570 -0.0415321030 -0.0117693841 757 1311867195.6637549400 0.2047071159 0.1512777917 0.2106595784 0.0053460376 0.0275610000 348554577 0 402718720 0.2360583097 -0.0408941284 -0.0124138510 758 1311867195.6999230385 0.2046916932 0.1513482586 0.2106595784 0.0053588158 0.0273430000 348557833 0 402718720 0.2343496978 -0.0405143388 -0.0119927842 759 1311867195.7320320606 0.2046505511 0.1514184856 0.2106595784 0.0053566366 0.0283440000 348560977 0 402718720 0.2320672721 -0.0417688787 -0.0113712363 760 1311867195.7676620483 0.2036346793 0.1514871911 0.2106595784 0.0053532125 0.0251940000 348564177 0 402718720 0.2314271778 -0.0407638885 -0.0122806542 761 1311867195.7996349335 0.2042203397 0.1515564857 0.2106595784 0.0053504425 0.0276510000 348567377 0 402718720 0.2290635854 -0.0408177413 -0.0116069289 762 1311867195.8317549229 0.2038639337 0.1516251306 0.2106595784 0.0053470655 0.0279440000 348570465 0 402718720 0.2270669043 -0.0417797454 -0.0117423506 763 1311867195.8676300049 0.2025653869 0.1516918938 0.2106595784 0.0053447461 0.0257580000 348573777 0 402718720 0.2264410853 -0.0402024835 -0.0128928842 764 1311867195.8998401165 0.2029891163 0.1517590367 0.2106595784 0.0053423936 0.0285560000 348576921 0 402718720 0.2246537507 -0.0399717838 -0.0120466538 765 1311867195.9319150448 0.2023853660 0.1518252149 0.2106595784 0.0053394548 0.0243880000 348580065 0 402718720 0.2234524637 -0.0405171812 -0.0118330857 766 1311867195.9677369595 0.2022064924 0.1518909868 0.2106595784 0.0053366707 0.0253630000 348583321 0 402718720 0.2219574898 -0.0393883176 -0.0125844674 767 1311867195.9996581078 0.2023208886 0.1519567364 0.2106595784 0.0053332375 0.0281690000 348586521 0 402718720 0.2202603817 -0.0397747904 -0.0121195354 768 1311867196.0318861008 0.2013671398 0.1520210728 0.2106595784 0.0053308877 0.0252050000 348589609 0 402718720 0.2195355445 -0.0407983810 -0.0120445937 769 1311867196.0677540302 0.2010959685 0.1520848893 0.2106595784 0.0053286183 0.0249040000 348592865 0 402718720 0.2184513062 -0.0390262417 -0.0129619036 770 1311867196.0996539593 0.2016223073 0.1521492237 0.2106595784 0.0053259148 0.0290250000 348596065 0 402718720 0.2163319588 -0.0397371911 -0.0118311513 771 1311867196.1317958832 0.2013235241 0.1522130035 0.2106595784 0.0053227805 0.0295260000 348599153 0 402718720 0.2146032155 -0.0405910164 -0.0120659312 772 1311867196.1677470207 0.2001821250 0.1522751397 0.2106595784 0.0053254835 0.0246650000 348602409 0 402718720 0.2144643217 -0.0389936268 -0.0127246110 773 1311867196.1997110844 0.2000172138 0.1523369018 0.2106595784 0.0053235546 0.0255360000 348605609 0 402718720 0.2129341513 -0.0399218500 -0.0119731799 774 1311867196.2319200039 0.1993336380 0.1523976211 0.2106595784 0.0053210469 0.0247620000 348608697 0 402718720 0.2112946659 -0.0403827615 -0.0124462899 775 1311867196.2679240704 0.1992451847 0.1524580695 0.2106595784 0.0053184399 0.0245790000 348611953 0 402718720 0.2100938857 -0.0396087579 -0.0127735510 776 1311867196.2997319698 0.1995125115 0.1525187067 0.2106595784 0.0053154622 0.0249950000 348615097 0 402718720 0.2082269490 -0.0401879176 -0.0123023102 777 1311867196.3318328857 0.1988012642 0.1525782724 0.2106595784 0.0053134966 0.0250310000 348618185 0 402718720 0.2070726007 -0.0402481183 -0.0129405176 778 1311867196.3687291145 0.1984902173 0.1526372852 0.2106595784 0.0053105707 0.0266740000 348621497 0 402718720 0.2061046064 -0.0387549698 -0.0130304750 779 1311867196.3997390270 0.1988622844 0.1526966241 0.2106595784 0.0053074736 0.0272490000 348624585 0 402718720 0.2035643011 -0.0404311083 -0.0123132560 780 1311867196.4320199490 0.1977860034 0.1527544310 0.2106595784 0.0053049309 0.0259350000 348627729 0 402718720 0.2028731555 -0.0399924666 -0.0129861422 781 1311867196.4677999020 0.1978923231 0.1528122260 0.2106595784 0.0053025983 0.0254750000 348630985 0 402718720 0.2014416009 -0.0387395024 -0.0126473261 782 1311867196.4997680187 0.1980343908 0.1528700548 0.2106595784 0.0052996516 0.0261170000 348634129 0 402718720 0.1995897442 -0.0392581671 -0.0121697951 783 1311867196.5319259167 0.1972319931 0.1529267112 0.2106595784 0.0052965520 0.0258140000 348637273 0 402718720 0.1984107494 -0.0390789434 -0.0125970356 784 1311867196.5677669048 0.1969290823 0.1529828367 0.2106595784 0.0052933514 0.0242680000 348640529 0 402718720 0.1973588914 -0.0373531133 -0.0123635009 785 1311867196.5997130871 0.1963392198 0.1530380678 0.2106595784 0.0052938970 0.0268050000 348643617 0 402718720 0.1955485642 -0.0385568589 -0.0118197445 786 1311867196.6319940090 0.1958654374 0.1530925555 0.2106595784 0.0052913501 0.0260590000 348646817 0 402718720 0.1941140592 -0.0384956263 -0.0120797968 787 1311867196.6677370071 0.1953465790 0.1531462455 0.2106595784 0.0052917718 0.0238900000 348650073 0 402718720 0.1924953610 -0.0366043970 -0.0120327733 788 1311867196.6997001171 0.1951176375 0.1531995087 0.2106595784 0.0052910675 0.0275230000 348653161 0 402718720 0.1905774772 -0.0379913524 -0.0114210071 789 1311867196.7317600250 0.1943820119 0.1532517045 0.2106595784 0.0052878781 0.0250650000 348656305 0 402718720 0.1893687993 -0.0369782113 -0.0114436112 790 1311867196.7677071095 0.1944422424 0.1533038444 0.2106595784 0.0052848125 0.0273350000 348659617 0 402718720 0.1865914613 -0.0365247577 -0.0110997567 791 1311867196.7997360229 0.1936038882 0.1533547926 0.2106595784 0.0052825315 0.0275710000 348662705 0 402718720 0.1849988103 -0.0376684479 -0.0111951530 792 1311867196.8318669796 0.1926588416 0.1534044190 0.2106595784 0.0052794123 0.0251210000 348665849 0 402718720 0.1840178668 -0.0372269191 -0.0112385247 793 1311867196.8677489758 0.1931643635 0.1534545576 0.2106595784 0.0052798210 0.0261750000 348669105 0 402718720 0.1810224652 -0.0365518406 -0.0111483084 794 1311867196.8997149467 0.1930972636 0.1535044855 0.2106595784 0.0052778042 0.0270330000 348672305 0 402718720 0.1787731647 -0.0379157811 -0.0105231395 795 1311867196.9319748878 0.1924975216 0.1535535333 0.2106595784 0.0052748384 0.0267480000 348675393 0 402718720 0.1771180779 -0.0373427533 -0.0109517071 796 1311867196.9679110050 0.1915236861 0.1536012345 0.2106595784 0.0052717242 0.0261650000 348678649 0 402718720 0.1755937636 -0.0375455059 -0.0112077463 797 1311867196.9998660088 0.1912702024 0.1536484979 0.2106595784 0.0052690979 0.0258910000 348681849 0 402718720 0.1737153381 -0.0382836610 -0.0111222491 798 1311867197.0319790840 0.1911616921 0.1536955070 0.2106595784 0.0052671579 0.0285170000 348684937 0 402718720 0.1715909541 -0.0380827673 -0.0115474341 799 1311867197.0678169727 0.1904959530 0.1537415651 0.2106595784 0.0052639138 0.0268980000 348688081 0 402718720 0.1702259183 -0.0378482640 -0.0116761588 800 1311867197.0998361111 0.1903594881 0.1537873375 0.2106595784 0.0052608363 0.0277490000 348691225 0 402718720 0.1681312472 -0.0385432132 -0.0119406218 801 1311867197.1318700314 0.1899284273 0.1538324575 0.2106595784 0.0052577698 0.0257030000 348694425 0 402718720 0.1666050106 -0.0374114662 -0.0125376536 802 1311867197.1677129269 0.1894405335 0.1538768566 0.2106595784 0.0052545701 0.0269960000 348697681 0 402718720 0.1644989699 -0.0381842628 -0.0121766105 803 1311867197.1997759342 0.1887059510 0.1539202303 0.2106595784 0.0052524347 0.0265150000 348700769 0 402718720 0.1632217467 -0.0381544344 -0.0123665696 804 1311867197.2319281101 0.1890134364 0.1539638785 0.2106595784 0.0052497062 0.0267670000 348703913 0 402718720 0.1611841321 -0.0368279666 -0.0125509137 805 1311867197.2679190636 0.1885826290 0.1540068832 0.2106595784 0.0052471474 0.0267220000 348707225 0 402718720 0.1589329988 -0.0373271480 -0.0120751923 806 1311867197.2998099327 0.1878915131 0.1540489237 0.2106595784 0.0052440033 0.0263440000 348710425 0 402718720 0.1576031893 -0.0370331034 -0.0123443864 807 1311867197.3320178986 0.1877231598 0.1540906514 0.2106595784 0.0052409458 0.0287740000 348713513 0 402718720 0.1554041058 -0.0369650722 -0.0125645222 808 1311867197.3678550720 0.1872264892 0.1541316611 0.2106595784 0.0052384058 0.0271660000 348716713 0 402718720 0.1533692926 -0.0377125069 -0.0122708427 809 1311867197.3998820782 0.1872211546 0.1541725628 0.2106595784 0.0052365993 0.0268260000 348719801 0 402718720 0.1513902843 -0.0376636609 -0.0125648705 810 1311867197.4319560528 0.1865334958 0.1542125146 0.2106595784 0.0052338491 0.0265880000 348722945 0 402718720 0.1504693478 -0.0366140418 -0.0130758565 811 1311867197.4679911137 0.1865530312 0.1542523919 0.2106595784 0.0052307294 0.0272780000 348726145 0 402718720 0.1479658186 -0.0377876908 -0.0130609618 812 1311867197.4999949932 0.1862610132 0.1542918114 0.2106595784 0.0052277090 0.0264250000 348729289 0 402718720 0.1461525261 -0.0373030081 -0.0143002337 813 1311867197.5318820477 0.1855821013 0.1543302988 0.2106595784 0.0052245248 0.0278000000 348732377 0 402718720 0.1455756277 -0.0358914807 -0.0151936831 814 1311867197.5678689480 0.1854477823 0.1543685267 0.2106595784 0.0052215814 0.0280180000 348735633 0 402718720 0.1434531510 -0.0371670425 -0.0147981243 815 1311867197.5999100208 0.1849945039 0.1544061046 0.2106595784 0.0052186971 0.0310260000 348738777 0 402718720 0.1418024302 -0.0367309414 -0.0165780671 816 1311867197.6319630146 0.1846523732 0.1544431711 0.2106595784 0.0052167387 0.0346420000 348741921 0 402718720 0.1410698295 -0.0342349820 -0.0176948905 817 1311867197.6679289341 0.1847073883 0.1544802142 0.2106595784 0.0052184788 0.0317670000 348745177 0 402718720 0.1380272359 -0.0365939066 -0.0166831929 818 1311867197.6997439861 0.1838567704 0.1545161268 0.2106595784 0.0052153116 0.0281590000 348748321 0 402718720 0.1373649985 -0.0349708498 -0.0186518040 819 1311867197.7320039272 0.1836828142 0.1545517394 0.2106595784 0.0052122702 0.0328640000 348751465 0 402718720 0.1362377256 -0.0337835290 -0.0187103134 820 1311867197.7679040432 0.1844478250 0.1545881980 0.2106595784 0.0052097650 0.0333510000 348754721 0 402718720 0.1329900920 -0.0358228013 -0.0181732960 821 1311867197.7998349667 0.1831349581 0.1546229688 0.2106595784 0.0052068500 0.0331940000 348757865 0 402718720 0.1327835917 -0.0335359052 -0.0209937170 822 1311867197.8319869041 0.1838282794 0.1546584983 0.2106595784 0.0052042009 0.0330220000 348761009 0 402718720 0.1310032606 -0.0338918567 -0.0195948947 823 1311867197.8679409027 0.1832154393 0.1546931969 0.2106595784 0.0052011908 0.0336780000 348764265 0 402718720 0.1290248632 -0.0348080769 -0.0209614690 824 1311867197.8999540806 0.1826550514 0.1547271312 0.2106595784 0.0052035049 0.0278050000 348767465 0 402718720 0.1283080876 -0.0322649889 -0.0227086283 825 1311867197.9320459366 0.1830584705 0.1547614722 0.2106595784 0.0052017648 0.0331560000 348770497 0 402718720 0.1260160357 -0.0330005102 -0.0218879059 826 1311867197.9679460526 0.1824177951 0.1547949545 0.2106595784 0.0051991425 0.0288140000 348773809 0 402718720 0.1245391071 -0.0329031833 -0.0226510148 827 1311867197.9997749329 0.1820283830 0.1548278848 0.2106595784 0.0051961146 0.0311610000 348776953 0 402718720 0.1230381280 -0.0313896611 -0.0245013051 828 1311867198.0318191051 0.1822364479 0.1548609870 0.2106595784 0.0051930222 0.0363510000 348780041 0 402718720 0.1210006326 -0.0321686268 -0.0233758204 829 1311867198.0678160191 0.1816738099 0.1548933305 0.2106595784 0.0051910314 0.0306670000 348783353 0 402718720 0.1192764640 -0.0314810462 -0.0248068757 830 1311867198.0997960567 0.1811248213 0.1549249348 0.2106595784 0.0051881415 0.0292880000 348786553 0 402718720 0.1179786623 -0.0308692511 -0.0258944761 831 1311867198.1318290234 0.1816034168 0.1549570388 0.2106595784 0.0051853752 0.0298670000 348789585 0 402718720 0.1156867221 -0.0309154931 -0.0252046008 832 1311867198.1679520607 0.1805985570 0.1549878580 0.2106595784 0.0051831068 0.0288690000 348792897 0 402718720 0.1141019017 -0.0308140758 -0.0265547354 833 1311867198.1998140812 0.1804899871 0.1550184728 0.2106595784 0.0051815029 0.0291320000 348796041 0 402718720 0.1124727279 -0.0302833486 -0.0270297080 834 1311867198.2320029736 0.1807313412 0.1550493035 0.2106595784 0.0051784168 0.0292990000 348799185 0 402718720 0.1104592681 -0.0304572731 -0.0266454201 835 1311867198.2679619789 0.1797533035 0.1550788892 0.2106595784 0.0051756797 0.0291590000 348802441 0 402718720 0.1082570180 -0.0300264396 -0.0289245192 836 1311867198.2998640537 0.1798264682 0.1551084915 0.2106595784 0.0051727384 0.0297670000 348805585 0 402718720 0.1063653901 -0.0293724276 -0.0291428175 837 1311867198.3318629265 0.1800678372 0.1551383115 0.2106595784 0.0051755396 0.0303260000 348808673 0 402718720 0.1040512249 -0.0296003763 -0.0287157595 838 1311867198.3679699898 0.1787884235 0.1551665336 0.2106595784 0.0051728533 0.0290300000 348811929 0 402718720 0.1019292846 -0.0291668102 -0.0314498991 839 1311867198.3999059200 0.1788018346 0.1551947044 0.2106595784 0.0051700341 0.0295410000 348815073 0 402718720 0.0998256058 -0.0285675619 -0.0319859423 840 1311867198.4319880009 0.1791587621 0.1552232331 0.2106595784 0.0051837284 0.0293800000 348817881 0 402718720 0.0977852345 -0.0289784838 -0.0299773123 841 1311867198.4679210186 0.1780392677 0.1552503627 0.2106595784 0.0051892259 0.0306730000 348821137 0 402718720 0.0948864743 -0.0289086550 -0.0337845609 842 1311867198.5000751019 0.1787295640 0.1552782478 0.2106595784 0.0051922154 0.0299760000 348824281 0 402718720 0.0920857042 -0.0274634492 -0.0343176052 843 1311867198.5321249962 0.1790702790 0.1553064708 0.2106595784 0.0051911122 0.0305030000 348827369 0 402718720 0.0895165056 -0.0281061493 -0.0332727171 844 1311867198.5679900646 0.1772141904 0.1553324278 0.2106595784 0.0051884335 0.0307180000 348830625 0 402718720 0.0869807154 -0.0273839012 -0.0375549868 845 1311867198.5999510288 0.1768410355 0.1553578818 0.2106595784 0.0051864396 0.0311370000 348833769 0 402718720 0.0854832754 -0.0272171572 -0.0370698720 846 1311867198.6319661140 0.1756472290 0.1553818645 0.2106595784 0.0051847333 0.0300380000 348836913 0 402718720 0.0835559145 -0.0276766475 -0.0384316519 847 1311867198.6680729389 0.1753274947 0.1554054130 0.2106595784 0.0051824181 0.0330870000 348840169 0 402718720 0.0808015764 -0.0273760650 -0.0399565846 848 1311867198.6998438835 0.1751764119 0.1554287279 0.2106595784 0.0051793994 0.0314780000 348843201 0 402718720 0.0788762718 -0.0263029318 -0.0410062261 849 1311867198.7318739891 0.1751867086 0.1554519999 0.2106595784 0.0051766140 0.0299310000 348846345 0 402718720 0.0767324269 -0.0264162421 -0.0409724154 850 1311867198.7679109573 0.1737975925 0.1554735830 0.2106595784 0.0051754030 0.0343940000 348849601 0 402718720 0.0757283643 -0.0249011517 -0.0428582840 851 1311867198.7998390198 0.1743844450 0.1554958049 0.2106595784 0.0051724137 0.0315090000 348852633 0 402718720 0.0730064958 -0.0259344317 -0.0423471443 852 1311867198.8319530487 0.1741967946 0.1555177544 0.2106595784 0.0051695146 0.0314230000 348855777 0 402718720 0.0706984699 -0.0255921762 -0.0437443443 853 1311867198.8678910732 0.1734738201 0.1555388049 0.2106595784 0.0051668662 0.0330740000 348859033 0 402718720 0.0698393285 -0.0242687929 -0.0444789156 854 1311867198.8998548985 0.1737935543 0.1555601805 0.2106595784 0.0051638973 0.0356680000 348862121 0 402718720 0.0680586249 -0.0238023251 -0.0448332429 855 1311867198.9318809509 0.1734597832 0.1555811157 0.2106595784 0.0051609332 0.0315690000 348865265 0 402718720 0.0663928166 -0.0235325899 -0.0459165201 856 1311867198.9680769444 0.1722873747 0.1556006324 0.2106595784 0.0051587416 0.0332660000 348868577 0 402718720 0.0654789507 -0.0238802973 -0.0471717231 857 1311867199.0000500679 0.1733911783 0.1556213915 0.2106595784 0.0051638055 0.0337220000 348871721 0 402718720 0.0639122427 -0.0218320005 -0.0473148823 858 1311867199.0318429470 0.1727843881 0.1556413950 0.2106595784 0.0051622872 0.0352720000 348874809 0 402718720 0.0630414337 -0.0212135632 -0.0480544381 859 1311867199.0679919720 0.1733490825 0.1556620093 0.2106595784 0.0051596044 0.0408760000 348878121 0 402718720 0.0623900928 -0.0188609920 -0.0486146249 860 1311867199.0998599529 0.1731480062 0.1556823418 0.2106595784 0.0051581548 0.0327100000 348881209 0 402718720 0.0606456362 -0.0198641811 -0.0495056994 861 1311867199.1320021152 0.1735169888 0.1557030557 0.2106595784 0.0051661054 0.0378710000 348884409 0 402718720 0.0599945001 -0.0184130315 -0.0497900695 862 1311867199.1678910255 0.1729723066 0.1557230896 0.2106595784 0.0051687090 0.0394460000 348887665 0 402718720 0.0599209107 -0.0163937211 -0.0511725023 863 1311867199.2001259327 0.1736638993 0.1557438785 0.2106595784 0.0051678283 0.0344040000 348890809 0 402718720 0.0579429045 -0.0172987636 -0.0517599061 864 1311867199.2340989113 0.1738390177 0.1557648220 0.2106595784 0.0051653145 0.0403990000 348894065 0 402718720 0.0567127205 -0.0159209576 -0.0527086966 865 1311867199.2679419518 0.1731668711 0.1557849400 0.2106595784 0.0051624480 0.0341620000 348897209 0 402718720 0.0559735745 -0.0151436869 -0.0539212301 866 1311867199.3000299931 0.1742255837 0.1558062340 0.2106595784 0.0051599980 0.0338830000 348900353 0 402718720 0.0534833409 -0.0154343797 -0.0541013367 867 1311867199.3318800926 0.1742874086 0.1558275502 0.2106595784 0.0051585744 0.0407390000 348903385 0 402718720 0.0527743287 -0.0144556621 -0.0549666397 868 1311867199.3681409359 0.1741570681 0.1558486672 0.2106595784 0.0051556569 0.0343330000 348906697 0 402718720 0.0512267761 -0.0139404042 -0.0560197420 869 1311867199.3999199867 0.1742932647 0.1558698923 0.2106595784 0.0051528608 0.0366560000 348909785 0 402718720 0.0492203869 -0.0144020589 -0.0569426604 870 1311867199.4320480824 0.1741006076 0.1558908471 0.2106595784 0.0051505430 0.0342420000 348912929 0 402718720 0.0476612709 -0.0136832157 -0.0582759827 871 1311867199.4679720402 0.1733688116 0.1559109137 0.2106595784 0.0051481515 0.0353220000 348916185 0 402718720 0.0461566411 -0.0132776732 -0.0595920868 872 1311867199.5001809597 0.1733540148 0.1559309172 0.2106595784 0.0051453904 0.0343530000 348919385 0 402718720 0.0443266556 -0.0132821565 -0.0600191429 873 1311867199.5322530270 0.1729361713 0.1559503963 0.2106595784 0.0051440546 0.0344080000 348922473 0 402718720 0.0428437591 -0.0124210259 -0.0610437691 874 1311867199.5682659149 0.1731017083 0.1559700202 0.2106595784 0.0051412509 0.0350100000 348925785 0 402718720 0.0399875604 -0.0120019494 -0.0617422424 875 1311867199.6003990173 0.1729543805 0.1559894309 0.2106595784 0.0051383444 0.0350580000 348928873 0 402718720 0.0376571827 -0.0118432483 -0.0621179678 876 1311867199.6322081089 0.1729109883 0.1560087478 0.2106595784 0.0051368440 0.0387260000 348932017 0 402718720 0.0354613923 -0.0109604821 -0.0624589957 877 1311867199.6680541039 0.1723187268 0.1560273453 0.2106595784 0.0051344831 0.0379440000 348935273 0 402718720 0.0331030264 -0.0117348330 -0.0628199056 878 1311867199.6999409199 0.1713178605 0.1560447604 0.2106595784 0.0051319230 0.0354470000 348938473 0 402718720 0.0308360308 -0.0124365948 -0.0644508153 879 1311867199.7320048809 0.1714878082 0.1560623293 0.2106595784 0.0051422602 0.0331610000 348941561 0 402718720 0.0285241902 -0.0107162734 -0.0642908216 880 1311867199.7680690289 0.1710942686 0.1560794111 0.2106595784 0.0051531483 0.0369620000 348944817 0 402718720 0.0261179768 -0.0115551241 -0.0645042732 881 1311867199.8000559807 0.1717686504 0.1560972195 0.2106595784 0.0051550232 0.0364220000 348947905 0 402718720 0.0236197468 -0.0110998563 -0.0639823005 882 1311867199.8324799538 0.1703691781 0.1561134009 0.2106595784 0.0051524925 0.0368840000 348951105 0 402718720 0.0225130152 -0.0099179614 -0.0653816760 883 1311867199.8679389954 0.1707184762 0.1561299412 0.2106595784 0.0051498887 0.0359240000 348954361 0 402718720 0.0197053198 -0.0107972352 -0.0646451935 884 1311867199.8999218941 0.1709848493 0.1561467453 0.2106595784 0.0051472323 0.0373870000 348957505 0 402718720 0.0167706367 -0.0110966740 -0.0651457086 885 1311867199.9322059155 0.1704165936 0.1561628695 0.2106595784 0.0051452908 0.0387010000 348960649 0 402718720 0.0157356393 -0.0094177974 -0.0656122416 886 1311867199.9679698944 0.1696226895 0.1561780611 0.2106595784 0.0051433391 0.0373410000 348963905 0 402718720 0.0135599682 -0.0104281362 -0.0656914487 887 1311867200.0000519753 0.1695244610 0.1561931078 0.2106595784 0.0051407161 0.0373760000 348966993 0 402718720 0.0105145322 -0.0113721909 -0.0669022724 888 1311867200.0322039127 0.1689965427 0.1562075261 0.2106595784 0.0051384528 0.0378540000 348970193 0 402718720 0.0097695608 -0.0084979525 -0.0672151744 889 1311867200.0680060387 0.1687449217 0.1562216289 0.2106595784 0.0051366814 0.0372300000 348973449 0 402718720 0.0070696399 -0.0101523297 -0.0660543293 890 1311867200.1000580788 0.1685871333 0.1562355227 0.2106595784 0.0051362236 0.1654090000 361293289 0 402718720 0.0050201216 -0.0091870576 -0.0665259063 891 1311867200.1321730614 0.1813176423 0.1562636733 0.2106595784 0.0051754508 0.0194910000 364955641 0 402718720 -0.0168153178 -0.0067587243 -0.0747420043 892 1311867200.1680541039 0.1814557910 0.1562919155 0.2106595784 0.0051745884 0.0376200000 368151089 0 402718720 -0.0195993576 -0.0081085702 -0.0733907595 893 1311867200.2000620365 0.1811205447 0.1563197192 0.2106595784 0.0051738975 0.0284410000 368154177 0 402718720 -0.0211118497 -0.0064411610 -0.0746811703 894 1311867200.2321259975 0.1811662316 0.1563475117 0.2106595784 0.0051712497 0.0278670000 368157321 0 402718720 -0.0233247839 -0.0062762462 -0.0738198012 895 1311867200.2681920528 0.1811434031 0.1563752166 0.2106595784 0.0051687516 0.0269140000 368160633 0 402718720 -0.0261199810 -0.0069006560 -0.0727568343 896 1311867200.3000659943 0.1802227050 0.1564018321 0.2106595784 0.0051674460 0.0286020000 368163777 0 402718720 -0.0273254663 -0.0053081168 -0.0736938193 897 1311867200.3321170807 0.1801170260 0.1564282704 0.2106595784 0.0051687972 0.0280980000 368166865 0 402718720 -0.0299418252 -0.0069171777 -0.0713291168 898 1311867200.3681631088 0.1800915897 0.1564546216 0.2106595784 0.0051749778 0.0265760000 368170177 0 402718720 -0.0327361003 -0.0056262598 -0.0720356107 899 1311867200.4000649452 0.1801322550 0.1564809593 0.2106595784 0.0051722215 0.0266330000 368173265 0 402718720 -0.0348631851 -0.0052290815 -0.0712334141 900 1311867200.4321138859 0.1796447188 0.1565066968 0.2106595784 0.0051699707 0.0263440000 368176409 0 402718720 -0.0372511074 -0.0065158051 -0.0702563897 901 1311867200.4681320190 0.1786041856 0.1565312223 0.2106595784 0.0051677966 0.0318020000 368179665 0 402718720 -0.0391590595 -0.0058734361 -0.0706687793 902 1311867200.5000898838 0.1790387183 0.1565561752 0.2106595784 0.0051706871 0.0280670000 368182809 0 402718720 -0.0421531536 -0.0063433307 -0.0693705305 903 1311867200.5321609974 0.1787414700 0.1565807436 0.2106595784 0.0051766249 0.0266690000 368185953 0 402718720 -0.0446782038 -0.0063945344 -0.0689890012 904 1311867200.5682120323 0.1776099950 0.1566040061 0.2106595784 0.0051796011 0.0322970000 368189265 0 402718720 -0.0461853668 -0.0054100659 -0.0689241663 905 1311867200.6000909805 0.1777921170 0.1566274184 0.2106595784 0.0051777225 0.0292900000 368192409 0 402718720 -0.0486762114 -0.0062508383 -0.0675293058 906 1311867200.6320428848 0.1774690300 0.1566504224 0.2106595784 0.0051753323 0.0278960000 368195497 0 402718720 -0.0513833240 -0.0061659869 -0.0670176521 907 1311867200.6682040691 0.1770034879 0.1566728623 0.2106595784 0.0051732958 0.0275700000 368198809 0 402718720 -0.0537662804 -0.0057084220 -0.0663675889 908 1311867200.7001199722 0.1771275550 0.1566953895 0.2106595784 0.0051706926 0.0276830000 368201897 0 402718720 -0.0561572500 -0.0056598173 -0.0653845444 909 1311867200.7321701050 0.1760180742 0.1567166466 0.2106595784 0.0051720364 0.0276030000 368205041 0 402718720 -0.0574540347 -0.0050838026 -0.0655320287 910 1311867200.7680790424 0.1755095869 0.1567372982 0.2106595784 0.0051700830 0.0268910000 368208297 0 402718720 -0.0595886707 -0.0046307403 -0.0647533908 911 1311867200.8000760078 0.1753385365 0.1567577167 0.2106595784 0.0051682552 0.0291800000 368211385 0 402718720 -0.0620277785 -0.0053180712 -0.0634931326 912 1311867200.8321371078 0.1743886173 0.1567770488 0.2106595784 0.0051659228 0.0289050000 368214585 0 402718720 -0.0637733340 -0.0044298610 -0.0636229143 913 1311867200.8681581020 0.1734568179 0.1567953180 0.2106595784 0.0051655661 0.0328320000 368217841 0 402718720 -0.0655922368 -0.0045116292 -0.0627415404 914 1311867200.8999950886 0.1734909266 0.1568135845 0.2106595784 0.0051637724 0.0306810000 368221041 0 402718720 -0.0675655678 -0.0051806667 -0.0615832657 915 1311867200.9320290089 0.1726571918 0.1568308999 0.2106595784 0.0051624796 0.0287220000 368224073 0 402718720 -0.0688594729 -0.0054494734 -0.0611152798 916 1311867200.9681539536 0.1723106503 0.1568477992 0.2106595784 0.0051650062 0.0303360000 368227385 0 402718720 -0.0705356225 -0.0053528240 -0.0609371625 917 1311867201.0000619888 0.1729407907 0.1568653488 0.2106595784 0.0051627020 0.0309020000 368230473 0 402718720 -0.0727150217 -0.0058428114 -0.0603488237 918 1311867201.0321929455 0.1725999862 0.1568824890 0.2106595784 0.0051600141 0.0303250000 368233673 0 402718720 -0.0737654865 -0.0051104086 -0.0608966425 919 1311867201.0679559708 0.1728347987 0.1568998473 0.2106595784 0.0051579497 0.0310740000 368236929 0 402718720 -0.0755796209 -0.0057950644 -0.0602237172 920 1311867201.1002171040 0.1729598194 0.1569173038 0.2106595784 0.0051591061 0.0319380000 368240073 0 402718720 -0.0769971311 -0.0052095009 -0.0608893931 921 1311867201.1322419643 0.1717160642 0.1569333719 0.2106595784 0.0051563718 0.0288010000 368243217 0 402718720 -0.0767542720 -0.0051171249 -0.0613292381 922 1311867201.1681909561 0.1720724702 0.1569497918 0.2106595784 0.0051535732 0.0330860000 368246417 0 402718720 -0.0784094855 -0.0054692589 -0.0606780760 923 1311867201.2001469135 0.1727435291 0.1569669031 0.2106595784 0.0051508549 0.0310070000 368249561 0 402718720 -0.0804170296 -0.0055215536 -0.0606603511 924 1311867201.2320559025 0.1721842289 0.1569833721 0.2106595784 0.0051524656 0.0320160000 368252593 0 402718720 -0.0814573616 -0.0050364230 -0.0613209791 925 1311867201.2694900036 0.1717621386 0.1569993491 0.2106595784 0.0051497379 0.0327940000 368255961 0 402718720 -0.0824815258 -0.0044515771 -0.0612400733 926 1311867201.2998940945 0.1721034199 0.1570156602 0.2106595784 0.0051499816 0.0327480000 368259105 0 402718720 -0.0842991471 -0.0052916328 -0.0603778735 927 1311867201.3322761059 0.1721969247 0.1570320370 0.2106595784 0.0051472899 0.0323960000 368262193 0 402718720 -0.0865247250 -0.0047509582 -0.0611494444 928 1311867201.3682329655 0.1722122878 0.1570483950 0.2106595784 0.0051501824 0.0337090000 368265449 0 402718720 -0.0885479003 -0.0019617025 -0.0619353130 929 1311867201.4002270699 0.1728131622 0.1570653646 0.2106595784 0.0051577821 0.0343470000 368268537 0 402718720 -0.0915988088 -0.0038161343 -0.0600070320 930 1311867201.4327609539 0.1714392155 0.1570808204 0.2106595784 0.0051552400 0.0326120000 368271681 0 402718720 -0.0931030139 -0.0030262044 -0.0610178486 931 1311867201.4680800438 0.1713367850 0.1570961329 0.2106595784 0.0051550517 0.0328770000 368274769 0 402718720 -0.0950598568 -0.0000183265 -0.0611570217 932 1311867201.5000870228 0.1715045571 0.1571115926 0.2106595784 0.0051542305 0.0341730000 368277913 0 402718720 -0.0979777053 -0.0005831643 -0.0603622645 933 1311867201.5321950912 0.1709695458 0.1571264457 0.2106595784 0.0051527228 0.0331570000 368281057 0 402718720 -0.1001749262 -0.0007176033 -0.0599501543 934 1311867201.5681428909 0.1699395925 0.1571401643 0.2106595784 0.0051502019 0.0292580000 368284313 0 402718720 -0.1015686616 0.0002139087 -0.0601128712 935 1311867201.6001029015 0.1704290360 0.1571543769 0.2106595784 0.0051490680 0.0325870000 368287401 0 402718720 -0.1037843674 0.0006271712 -0.0594496951 936 1311867201.6320679188 0.1699784547 0.1571680779 0.2106595784 0.0051464612 0.0294820000 368290545 0 402718720 -0.1056284681 0.0003842255 -0.0593607277 937 1311867201.6680500507 0.1692260355 0.1571809466 0.2106595784 0.0051514305 0.0334160000 368293857 0 402718720 -0.1067620665 0.0008802487 -0.0590980686 938 1311867201.7002921104 0.1684914678 0.1571930047 0.2106595784 0.0051487370 0.0332880000 368297057 0 402718720 -0.1080740765 0.0023524824 -0.0603462644 939 1311867201.7321999073 0.1691966206 0.1572057881 0.2106595784 0.0051499120 0.0337250000 368300145 0 402718720 -0.1102773920 0.0020127341 -0.0595768280 940 1311867201.7682011127 0.1681945920 0.1572174783 0.2106595784 0.0051612778 0.0327740000 368303401 0 402718720 -0.1115035713 0.0019574147 -0.0593920648 941 1311867201.8002099991 0.1676640958 0.1572285799 0.2106595784 0.0051596410 0.0333820000 368306601 0 402718720 -0.1128077582 0.0044560442 -0.0607384779 942 1311867201.8321559429 0.1675334126 0.1572395192 0.2106595784 0.0051596746 0.0314180000 368309689 0 402718720 -0.1132121980 0.0047360277 -0.0590507872 943 1311867201.8682188988 0.1672982275 0.1572501860 0.2106595784 0.0051653166 0.0289080000 368312945 0 402718720 -0.1148550808 0.0034585714 -0.0591179542 944 1311867201.9000771046 0.1676496714 0.1572612024 0.2106595784 0.0051637702 0.0296150000 368315977 0 402718720 -0.1162142977 0.0054508587 -0.0600953735 945 1311867201.9322619438 0.1669768244 0.1572714834 0.2106595784 0.0051612245 0.0331520000 368319177 0 402718720 -0.1165657267 0.0050179446 -0.0597665645 946 1311867201.9681720734 0.1665365994 0.1572812774 0.2106595784 0.0051588292 0.0327180000 368322433 0 402718720 -0.1174136177 0.0044297543 -0.0601075999 947 1311867202.0001900196 0.1667067558 0.1572912304 0.2106595784 0.0051632754 0.0337180000 368325521 0 402718720 -0.1183961928 0.0051840101 -0.0606799573 948 1311867202.0322389603 0.1661144942 0.1573005377 0.2106595784 0.0051686690 0.0327240000 368328721 0 402718720 -0.1188031062 0.0053849122 -0.0613561533 949 1311867202.0681519508 0.1660808921 0.1573097899 0.2106595784 0.0051661129 0.0298740000 368331977 0 402718720 -0.1192101762 0.0056177899 -0.0612345710 950 1311867202.1003150940 0.1669446081 0.1573199318 0.2106595784 0.0051712119 0.0328290000 368335065 0 402718720 -0.1214738637 0.0059499345 -0.0615395047 951 1311867202.1324090958 0.1667441577 0.1573298416 0.2106595784 0.0051740783 0.0328280000 368338265 0 402718720 -0.1218343750 0.0079109352 -0.0617527030 952 1311867202.1682789326 0.1656536758 0.1573385851 0.2106595784 0.0051727830 0.0341360000 368341521 0 402718720 -0.1222089678 0.0073986999 -0.0616485737 953 1311867202.2001249790 0.1664015204 0.1573480950 0.2106595784 0.0051701284 0.0340290000 368344721 0 402718720 -0.1238861084 0.0070588384 -0.0607867911 954 1311867202.2323749065 0.1658805609 0.1573570389 0.2106595784 0.0051674179 0.0294610000 368347753 0 402718720 -0.1247110665 0.0078582102 -0.0613293089 955 1311867202.2681009769 0.1642396003 0.1573642458 0.2106595784 0.0051695727 0.0340720000 368351009 0 402718720 -0.1251208335 0.0089032659 -0.0628575087 956 1311867202.3001070023 0.1655090749 0.1573727655 0.2106595784 0.0051713490 0.0326370000 368354097 0 402718720 -0.1258558333 0.0089040753 -0.0596624911 957 1311867202.3323650360 0.1651524007 0.1573808947 0.2106595784 0.0051691638 0.0339660000 368357241 0 402718720 -0.1279095709 0.0078702969 -0.0605737716 958 1311867202.3683099747 0.1651625633 0.1573890175 0.2106595784 0.0051675828 0.0330730000 368360497 0 402718720 -0.1290205419 0.0099463724 -0.0606128648 959 1311867202.4002919197 0.1644694805 0.1573964007 0.2106595784 0.0051658704 0.0328150000 368363641 0 402718720 -0.1293652058 0.0093470570 -0.0601702109 960 1311867202.4321858883 0.1642550677 0.1574035451 0.2106595784 0.0051638109 0.0339590000 368366729 0 402718720 -0.1299890429 0.0079859626 -0.0593621768 961 1311867202.4681179523 0.1635145545 0.1574099041 0.2106595784 0.0051614746 0.0339100000 368370041 0 402718720 -0.1307253987 0.0092171868 -0.0611948669 962 1311867202.5002439022 0.1641294956 0.1574168891 0.2106595784 0.0051589484 0.0348050000 368373129 0 402718720 -0.1316661239 0.0091814036 -0.0602972545 963 1311867202.5322799683 0.1651701778 0.1574249403 0.2106595784 0.0051642958 0.0311160000 368376329 0 402718720 -0.1334592402 0.0099345241 -0.0596819520 964 1311867202.5681829453 0.1637796313 0.1574315323 0.2106595784 0.0051858706 0.0333050000 368379585 0 402718720 -0.1327363402 0.0096148252 -0.0598935708 965 1311867202.6002409458 0.1628812999 0.1574371798 0.2106595784 0.0051839197 0.0339610000 368382729 0 402718720 -0.1327455640 0.0085182153 -0.0602086522 966 1311867202.6324090958 0.1655631065 0.1574455917 0.2106595784 0.0051948180 0.0315290000 368385873 0 402718720 -0.1368227750 0.0093765818 -0.0600634739 967 1311867202.6682538986 0.1654584110 0.1574538779 0.2106595784 0.0052021746 0.0334170000 368389129 0 402718720 -0.1386953145 0.0096027348 -0.0612097271 968 1311867202.7002909184 0.1659281701 0.1574626324 0.2106595784 0.0052003010 0.0326730000 368392217 0 402718720 -0.1394453049 0.0096865790 -0.0602935068 969 1311867202.7322840691 0.1655721515 0.1574710013 0.2106595784 0.0051981947 0.0327890000 368395417 0 402718720 -0.1409500539 0.0075534526 -0.0609176718 970 1311867202.7681059837 0.1642441899 0.1574779840 0.2106595784 0.0051956310 0.0325270000 368398673 0 402718720 -0.1412966996 0.0086450800 -0.0633284003 971 1311867202.8002150059 0.1656068116 0.1574863556 0.2106595784 0.0051941768 0.0326880000 368401873 0 402718720 -0.1432279944 0.0086236065 -0.0626675040 972 1311867202.8323709965 0.1670171618 0.1574961610 0.2106595784 0.0051932026 0.0337700000 368404961 0 402718720 -0.1466423422 0.0080963233 -0.0630389377 973 1311867202.8681859970 0.1656264365 0.1575045169 0.2106595784 0.0051906118 0.0318430000 368408217 0 402718720 -0.1468022466 0.0091768773 -0.0648662522 974 1311867202.9003429413 0.1645395309 0.1575117397 0.2106595784 0.0051880373 0.0328770000 368411305 0 402718720 -0.1464681476 0.0104500009 -0.0659604222 975 1311867202.9321599007 0.1644285172 0.1575188338 0.2106595784 0.0051946636 0.0322030000 368414449 0 402718720 -0.1462647021 0.0094075818 -0.0651409626 976 1311867202.9681980610 0.1642387509 0.1575257190 0.2106595784 0.0051922211 0.0342290000 368417761 0 402718720 -0.1468266547 0.0093988543 -0.0656592250 977 1311867203.0002338886 0.1636814326 0.1575320196 0.2106595784 0.0051946282 0.0324690000 368420905 0 402718720 -0.1465541273 0.0113655627 -0.0663366467 978 1311867203.0322840214 0.1634324938 0.1575380528 0.2106595784 0.0051929572 0.0334470000 368424049 0 402718720 -0.1452531517 0.0098728603 -0.0640989691 979 1311867203.0681869984 0.1629832834 0.1575436148 0.2106595784 0.0051909281 0.0338520000 368427249 0 402718720 -0.1447434872 0.0092053283 -0.0647911429 980 1311867203.1003499031 0.1634788960 0.1575496712 0.2106595784 0.0052016818 0.0333700000 368430393 0 402718720 -0.1441097558 0.0083081704 -0.0648094565 981 1311867203.1324429512 0.1642613113 0.1575565129 0.2106595784 0.0052184561 0.0333360000 368433481 0 402718720 -0.1433543265 0.0076514287 -0.0628247857 982 1311867203.1682100296 0.1641413420 0.1575632184 0.2106595784 0.0052175706 0.0342680000 368436737 0 402718720 -0.1425910890 0.0056971959 -0.0630565137 983 1311867203.2002859116 0.1649828702 0.1575707664 0.2106595784 0.0052486601 0.0316810000 368439937 0 402718720 -0.1429602206 0.0069028069 -0.0648126975 984 1311867203.2322111130 0.1658545285 0.1575791848 0.2106595784 0.0052460602 0.0332750000 368443025 0 402718720 -0.1428519040 0.0061863465 -0.0641194880 985 1311867203.2681829929 0.1662763059 0.1575880144 0.2106595784 0.0052441533 0.0338580000 368446281 0 402718720 -0.1431306899 0.0040023960 -0.0639282838 986 1311867203.3002059460 0.1674772501 0.1575980440 0.2106595784 0.0052447712 0.0317360000 368449481 0 402718720 -0.1436846852 0.0054144547 -0.0646686181 987 1311867203.3322260380 0.1668079793 0.1576073753 0.2106595784 0.0052422456 0.0318630000 368452569 0 402718720 -0.1430513710 0.0052220118 -0.0662062988 988 1311867203.3681290150 0.1673861593 0.1576172728 0.2106595784 0.0052407280 0.0324970000 368455825 0 402718720 -0.1426073313 0.0056157368 -0.0656584576 989 1311867203.4001998901 0.1681274474 0.1576278999 0.2106595784 0.0052391592 0.0392510000 368459025 0 402718720 -0.1436518580 0.0005550156 -0.0634673014 990 1311867203.4322550297 0.1674325019 0.1576378035 0.2106595784 0.0052372655 0.0334720000 368462113 0 402718720 -0.1428339481 -0.0000613635 -0.0650742725 991 1311867203.4682049751 0.1676414609 0.1576478980 0.2106595784 0.0052355087 0.0364750000 368465369 0 402718720 -0.1426423639 0.0002268351 -0.0657339543 992 1311867203.5004940033 0.1681669056 0.1576585019 0.2106595784 0.0052339222 0.0372310000 368468569 0 402718720 -0.1431358159 -0.0030000180 -0.0646044239 993 1311867203.5322470665 0.1683666706 0.1576692855 0.2106595784 0.0052318780 0.0373840000 368471657 0 402718720 -0.1434722394 -0.0054639494 -0.0654078424 994 1311867203.5682868958 0.1683101952 0.1576799907 0.2106595784 0.0052293500 0.0338410000 368474969 0 402718720 -0.1430677027 -0.0053800740 -0.0669624284 995 1311867203.6002469063 0.1687200218 0.1576910862 0.2106595784 0.0052268497 0.0397350000 368478113 0 402718720 -0.1431282759 -0.0068332357 -0.0666742697 996 1311867203.6323809624 0.1690762788 0.1577025171 0.2106595784 0.0052244713 0.0394890000 368481201 0 402718720 -0.1436659098 -0.0096042696 -0.0666015148 997 1311867203.6683659554 0.1692706496 0.1577141200 0.2106595784 0.0052274449 0.0362640000 368484513 0 402718720 -0.1436632872 -0.0104803089 -0.0672937334 998 1311867203.7004671097 0.1688730568 0.1577253013 0.2106595784 0.0052322101 0.0364390000 368487545 0 402718720 -0.1431261301 -0.0123372525 -0.0677431077 999 1311867203.7322630882 0.1687759459 0.1577363630 0.2106595784 0.0052296411 0.0332790000 368490745 0 402718720 -0.1425060630 -0.0129632829 -0.0684079304 1000 1311867203.7681419849 0.1698370874 0.1577484638 0.2106595784 0.0052271607 0.0360840000 368494001 0 402718720 -0.1432607770 -0.0145291118 -0.0682475418 1001 1311867203.8001880646 0.1695237160 0.1577602273 0.2106595784 0.0052245600 0.0362850000 368497089 0 402718720 -0.1428012103 -0.0156140253 -0.0688227043 1002 1311867203.8324379921 0.1692180485 0.1577716622 0.2106595784 0.0052221964 0.0335750000 368500289 0 402718720 -0.1421634704 -0.0167340431 -0.0693982616 1003 1311867203.8681540489 0.1703192443 0.1577841723 0.2106595784 0.0052196752 0.0355650000 368503545 0 402718720 -0.1430234909 -0.0182689298 -0.0691218153 1004 1311867203.9002060890 0.1707984358 0.1577971347 0.2106595784 0.0052171260 0.0334560000 368506689 0 402718720 -0.1440081298 -0.0197857525 -0.0701334551 1005 1311867203.9324600697 0.1707516611 0.1578100248 0.2106595784 0.0052146069 0.0371160000 368509833 0 402718720 -0.1436787993 -0.0192747843 -0.0714928508 1006 1311867203.9682869911 0.1708448380 0.1578229818 0.2106595784 0.0052136524 0.0384010000 368513089 0 402718720 -0.1441394240 -0.0215317216 -0.0720448047 1007 1311867204.0003368855 0.1711220294 0.1578361884 0.2106595784 0.0052113317 0.0347210000 368516233 0 402718720 -0.1441686749 -0.0217278991 -0.0731877312 1008 1311867204.0323688984 0.1715556830 0.1578497990 0.2106595784 0.0052093025 0.0334600000 368519377 0 402718720 -0.1445950866 -0.0228116475 -0.0741224810 1009 1311867204.0682060719 0.1718463600 0.1578636708 0.2106595784 0.0052083615 0.0335360000 368522577 0 402718720 -0.1450406164 -0.0243830476 -0.0748293325 1010 1311867204.1003429890 0.1715376973 0.1578772094 0.2106595784 0.0052059342 0.0344830000 368525721 0 402718720 -0.1447784901 -0.0258340053 -0.0758610815 1011 1311867204.1322948933 0.1712660640 0.1578904526 0.2106595784 0.0052036361 0.0347450000 368528809 0 402718720 -0.1443781257 -0.0274246037 -0.0769906864 1012 1311867204.1682620049 0.1718147099 0.1579042117 0.2106595784 0.0052014846 0.0347420000 368532065 0 402718720 -0.1451928914 -0.0294273738 -0.0773141459 1013 1311867204.2003049850 0.1723243594 0.1579184468 0.2106595784 0.0051990297 0.2112130000 380855885 0 402718720 -0.1457390487 -0.0303948149 -0.0780517906 1014 1311867204.2324359417 0.1664570868 0.1579268676 0.2106595784 0.0052158946 0.0200370000 384518293 0 402718720 -0.1445016116 -0.0381720513 -0.0831173584 1015 1311867204.2681810856 0.1665446907 0.1579353580 0.2106595784 0.0052139677 0.0433330000 387713741 0 402718720 -0.1446251124 -0.0412489176 -0.0831574202 1016 1311867204.3003020287 0.1670506746 0.1579443298 0.2106595784 0.0052116313 0.0322710000 387716829 0 402718720 -0.1451507658 -0.0419832468 -0.0838241056 1017 1311867204.3325190544 0.1674598753 0.1579536863 0.2106595784 0.0052096493 0.0290280000 387720029 0 402718720 -0.1448508799 -0.0416510440 -0.0843490958 1018 1311867204.3683750629 0.1676949710 0.1579632553 0.2106595784 0.0052071712 0.0300780000 387723285 0 402718720 -0.1455649137 -0.0439992771 -0.0846459791 1019 1311867204.4002819061 0.1680519134 0.1579731559 0.2106595784 0.0052047008 0.0315000000 387726429 0 402718720 -0.1458937228 -0.0449556373 -0.0848919228 1020 1311867204.4324340820 0.1679522544 0.1579829393 0.2106595784 0.0052022523 0.0291190000 387729573 0 402718720 -0.1455371976 -0.0452546030 -0.0857533589 1021 1311867204.4682960510 0.1681084633 0.1579928566 0.2106595784 0.0051997926 0.0284170000 387732829 0 402718720 -0.1456154138 -0.0469143465 -0.0857927874 1022 1311867204.5002770424 0.1683807224 0.1580030208 0.2106595784 0.0051972489 0.0268070000 387735917 0 402718720 -0.1462673545 -0.0485776514 -0.0863455087 1023 1311867204.5324790478 0.1685761362 0.1580133562 0.2106595784 0.0051950096 0.0277480000 387739117 0 402718720 -0.1459155977 -0.0485669114 -0.0866993666 1024 1311867204.5682110786 0.1694793105 0.1580245534 0.2106595784 0.0051933917 0.0330220000 387742373 0 402718720 -0.1470661610 -0.0500247777 -0.0866101533 1025 1311867204.6002640724 0.1692474484 0.1580355026 0.2106595784 0.0051908625 0.0278900000 387851957 0 402718720 -0.1470923722 -0.0510093682 -0.0869687498 1026 1311867204.6324179173 0.1687296927 0.1580459258 0.2106595784 0.0051890207 0.0275560000 388059957 0 402718720 -0.1472719908 -0.0524797551 -0.0868438184 1027 1311867204.6684520245 0.1689895689 0.1580565817 0.2106595784 0.0051870336 0.0332500000 388063213 0 402718720 -0.1476988047 -0.0538127758 -0.0869271755 1028 1311867204.7002611160 0.1686269343 0.1580668642 0.2106595784 0.0051848242 0.0288160000 388066413 0 402718720 -0.1471335143 -0.0540252812 -0.0873850584 1029 1311867204.7322928905 0.1686604917 0.1580771592 0.2106595784 0.0051824807 0.0277920000 388069501 0 402718720 -0.1474773139 -0.0553977489 -0.0868992358 1030 1311867204.7683119774 0.1697663218 0.1580885079 0.2106595784 0.0051801548 0.0287050000 388072757 0 402718720 -0.1493011117 -0.0569795296 -0.0856685191 1031 1311867204.8004341125 0.1698133349 0.1580998802 0.2106595784 0.0051781162 0.0288740000 388075845 0 402718720 -0.1498862803 -0.0570949204 -0.0851410404 1032 1311867204.8324959278 0.1682449877 0.1581097108 0.2106595784 0.0051757763 0.0282710000 388079045 0 402718720 -0.1488222182 -0.0579911955 -0.0848652944 1033 1311867204.8682460785 0.1681491733 0.1581194295 0.2106595784 0.0051740712 0.0300730000 388082301 0 402718720 -0.1499484181 -0.0609311052 -0.0834499598 1034 1311867204.9002239704 0.1690149158 0.1581299667 0.2106595784 0.0051726569 0.0284310000 388085389 0 402718720 -0.1512744129 -0.0622705519 -0.0824478418 1035 1311867204.9363629818 0.1685153395 0.1581400009 0.2106595784 0.0051720210 0.0282580000 388088645 0 402718720 -0.1509515345 -0.0629538968 -0.0821558237 1036 1311867204.9682190418 0.1678752899 0.1581493979 0.2106595784 0.0051697113 0.0350020000 388091845 0 402718720 -0.1507846862 -0.0653351396 -0.0813647434 1037 1311867205.0003349781 0.1675935090 0.1581585050 0.2106595784 0.0051672539 0.0312240000 388095045 0 402718720 -0.1511813551 -0.0674851537 -0.0809823200 1038 1311867205.0363259315 0.1681897342 0.1581681690 0.2106595784 0.0051663014 0.0308960000 388098189 0 402718720 -0.1510194242 -0.0671898574 -0.0809863955 1039 1311867205.0686368942 0.1679344475 0.1581775687 0.2106595784 0.0051762618 0.0345590000 388101445 0 402718720 -0.1513741463 -0.0686911941 -0.0803377330 1040 1311867205.1007649899 0.1679676473 0.1581869823 0.2106595784 0.0051900344 0.0335200000 388104421 0 402718720 -0.1513800770 -0.0706089363 -0.0797578022 1041 1311867205.1363010406 0.1681971550 0.1581965982 0.2106595784 0.0051889387 0.0323500000 388107677 0 402718720 -0.1512885541 -0.0714323148 -0.0792201310 1042 1311867205.1682898998 0.1688577980 0.1582068297 0.2106595784 0.0051865079 0.0344000000 388110821 0 402718720 -0.1513636410 -0.0729930699 -0.0786999166 1043 1311867205.2003710270 0.1682478487 0.1582164567 0.2106595784 0.0051853752 0.0343990000 388113965 0 402718720 -0.1509205550 -0.0756731033 -0.0779009461 1044 1311867205.2364439964 0.1681551337 0.1582259765 0.2106595784 0.0051847085 0.0342250000 388117165 0 402718720 -0.1505798250 -0.0762602463 -0.0775273219 1045 1311867205.2683920860 0.1679987758 0.1582353285 0.2106595784 0.0051867615 0.0362970000 388120365 0 402718720 -0.1505956948 -0.0779313371 -0.0771447420 1046 1311867205.3004579544 0.1680993736 0.1582447587 0.2106595784 0.0051854081 0.0349780000 388123509 0 402718720 -0.1509883255 -0.0798776299 -0.0765721053 1047 1311867205.3362879753 0.1681031138 0.1582541745 0.2106595784 0.0051832161 0.0351900000 388126765 0 402718720 -0.1509205401 -0.0810663849 -0.0761269927 1048 1311867205.3684389591 0.1680562794 0.1582635277 0.2106595784 0.0051861506 0.0369450000 388129909 0 402718720 -0.1512003243 -0.0824673697 -0.0755162165 1049 1311867205.4004759789 0.1683735251 0.1582731655 0.2106595784 0.0051969608 0.0360950000 388132997 0 402718720 -0.1522440612 -0.0841145888 -0.0747947395 1050 1311867205.4362900257 0.1679322124 0.1582823645 0.2106595784 0.0051977636 0.0359180000 388136309 0 402718720 -0.1523652077 -0.0853074491 -0.0745791420 1051 1311867205.4683609009 0.1678824574 0.1582914988 0.2106595784 0.0051990787 0.0341940000 388139453 0 402718720 -0.1525637358 -0.0861283839 -0.0739761963 1052 1311867205.5002589226 0.1671915948 0.1582999590 0.2106595784 0.0052087902 0.0367650000 388142541 0 402718720 -0.1536107659 -0.0885354653 -0.0728490204 1053 1311867205.5362849236 0.1671895236 0.1583084011 0.2106595784 0.0052097674 0.0366550000 388145853 0 402718720 -0.1542815119 -0.0890146121 -0.0724325776 1054 1311867205.5683689117 0.1679627895 0.1583175608 0.2106595784 0.0052198793 0.0406400000 388148997 0 402718720 -0.1556608081 -0.0892400146 -0.0710124150 1055 1311867205.6003179550 0.1668971628 0.1583256932 0.2106595784 0.0052240227 0.0380040000 388152141 0 402718720 -0.1564707458 -0.0916542262 -0.0703991130 1056 1311867205.6363780499 0.1665141732 0.1583334474 0.2106595784 0.0052217633 0.0385420000 388155397 0 402718720 -0.1571000963 -0.0934358165 -0.0695258379 1057 1311867205.6686398983 0.1657117903 0.1583404279 0.2106595784 0.0052195054 0.0389990000 388158597 0 402718720 -0.1567812562 -0.0942569375 -0.0691695064 1058 1311867205.7002930641 0.1659796834 0.1583476483 0.2106595784 0.0052174151 0.0384440000 388161741 0 402718720 -0.1578934938 -0.0966887251 -0.0681572184 1059 1311867205.7364819050 0.1663611382 0.1583552154 0.2106595784 0.0052156639 0.0373710000 388164941 0 402718720 -0.1589270830 -0.0981863067 -0.0676923692 1060 1311867205.7683310509 0.1662369817 0.1583626510 0.2106595784 0.0052145859 0.0392840000 388168085 0 402718720 -0.1593825221 -0.0989255458 -0.0681208223 1061 1311867205.8002939224 0.1655103713 0.1583693878 0.2106595784 0.0052145944 0.0379000000 388171285 0 402718720 -0.1595985293 -0.1013795659 -0.0675227121 1062 1311867205.8363699913 0.1662942469 0.1583768500 0.2106595784 0.0052123343 0.0389470000 388174485 0 402718720 -0.1611704379 -0.1031801328 -0.0668758601 1063 1311867205.8685131073 0.1663748175 0.1583843739 0.2106595784 0.0052125650 0.0367210000 388177685 0 402718720 -0.1620038003 -0.1039114445 -0.0669768453 1064 1311867205.9003169537 0.1660287380 0.1583915585 0.2106595784 0.0052129376 0.0367560000 388180829 0 402718720 -0.1624459922 -0.1054053307 -0.0668696165 1065 1311867205.9363129139 0.1660236567 0.1583987248 0.2106595784 0.0052213908 0.0378090000 388184029 0 402718720 -0.1629331112 -0.1070948169 -0.0662525222 1066 1311867205.9685149193 0.1666395068 0.1584064553 0.2106595784 0.0052190080 0.0363460000 388187229 0 402718720 -0.1640985608 -0.1083641052 -0.0660649389 1067 1311867206.0006539822 0.1675530821 0.1584150276 0.2106595784 0.0052324492 0.0410680000 388190317 0 402718720 -0.1646553576 -0.1073628440 -0.0661972016 1068 1311867206.0367360115 0.1670103669 0.1584230757 0.2106595784 0.0052344168 0.0427890000 388193573 0 402718720 -0.1651767343 -0.1100565717 -0.0655682683 1069 1311867206.0684130192 0.1658767760 0.1584300483 0.2106595784 0.0052321075 0.0404820000 388196661 0 402718720 -0.1647067368 -0.1129933298 -0.0655857176 1070 1311867206.1004180908 0.1664130092 0.1584375090 0.2106595784 0.0052301079 0.0376930000 388199861 0 402718720 -0.1647268087 -0.1133028865 -0.0654992089 1071 1311867206.1364219189 0.1665695459 0.1584451019 0.2106595784 0.0052303561 0.0376040000 388203061 0 402718720 -0.1651368737 -0.1155429929 -0.0652400702 1072 1311867206.1682798862 0.1670186520 0.1584530997 0.2106595784 0.0052284615 0.0393970000 388206205 0 402718720 -0.1660193652 -0.1182454377 -0.0650377199 1073 1311867206.2004311085 0.1673155874 0.1584613592 0.2106595784 0.0052320123 0.0404140000 388209349 0 402718720 -0.1664158106 -0.1188445240 -0.0658054352 1074 1311867206.2363541126 0.1674776822 0.1584697543 0.2106595784 0.0052404080 0.0399760000 388212605 0 402718720 -0.1662242562 -0.1194396466 -0.0661079809 1075 1311867206.2685620785 0.1675464511 0.1584781977 0.2106595784 0.0052424827 0.0419720000 388215749 0 402718720 -0.1669339091 -0.1218256727 -0.0660364330 1076 1311867206.3004291058 0.1676074117 0.1584866821 0.2106595784 0.0052407889 0.0404100000 388218949 0 402718720 -0.1670941561 -0.1227155104 -0.0664721578 1077 1311867206.3366179466 0.1683476418 0.1584958381 0.2106595784 0.0052423242 0.0425090000 388222149 0 402718720 -0.1680600047 -0.1237293258 -0.0664773583 1078 1311867206.3684759140 0.1676382720 0.1585043190 0.2106595784 0.0052429577 0.0424830000 388225293 0 402718720 -0.1680127382 -0.1257287860 -0.0665764436 1079 1311867206.4004108906 0.1674622595 0.1585126211 0.2106595784 0.0052413859 0.0375360000 388228437 0 402718720 -0.1674998999 -0.1269076914 -0.0666925162 1080 1311867206.4365398884 0.1678415984 0.1585212590 0.2106595784 0.0052398028 0.0393800000 388231637 0 402718720 -0.1679371297 -0.1282473356 -0.0667286888 1081 1311867206.4684751034 0.1676520407 0.1585297056 0.2106595784 0.0052380165 0.0377340000 388234837 0 402718720 -0.1681868434 -0.1303276122 -0.0666608438 1082 1311867206.5005669594 0.1685426533 0.1585389597 0.2106595784 0.0052373045 0.0426900000 388237981 0 402718720 -0.1693831384 -0.1321999580 -0.0664244071 1083 1311867206.5365779400 0.1681617200 0.1585478450 0.2106595784 0.0052353565 0.0432180000 388241237 0 402718720 -0.1691296250 -0.1339140683 -0.0666242763 1084 1311867206.5683178902 0.1682922244 0.1585568343 0.2106595784 0.0052345388 0.0393160000 388244381 0 402718720 -0.1687008888 -0.1353040189 -0.0666870251 1085 1311867206.6004528999 0.1685062647 0.1585660043 0.2106595784 0.0052322141 0.0429240000 388247469 0 402718720 -0.1693878025 -0.1373495162 -0.0669844821 1086 1311867206.6364800930 0.1694024205 0.1585759826 0.2106595784 0.0052385273 0.0450740000 388250725 0 402718720 -0.1698703617 -0.1384836286 -0.0670495778 1087 1311867206.6685130596 0.1688080728 0.1585853957 0.2106595784 0.0052384092 0.0415410000 388253869 0 402718720 -0.1690709740 -0.1395276189 -0.0675570294 1088 1311867206.7005600929 0.1687928587 0.1585947776 0.2106595784 0.0052366869 0.0415710000 388257013 0 402718720 -0.1691385657 -0.1409838349 -0.0676347241 1089 1311867206.7363760471 0.1690361947 0.1586043656 0.2106595784 0.0052359201 0.0424730000 388260269 0 402718720 -0.1689960063 -0.1428647190 -0.0676104352 1090 1311867206.7683479786 0.1697607338 0.1586146008 0.2106595784 0.0052398158 0.0400120000 388263413 0 402718720 -0.1696863174 -0.1432614475 -0.0683624521 1091 1311867206.8005199432 0.1700531095 0.1586250853 0.2106595784 0.0052407581 0.0453110000 388266557 0 402718720 -0.1706289649 -0.1451648176 -0.0684013963 1092 1311867206.8364160061 0.1693899035 0.1586349432 0.2106595784 0.0052392557 0.0421430000 388269813 0 402718720 -0.1702442020 -0.1470970213 -0.0690933093 1093 1311867206.8685629368 0.1695545167 0.1586449336 0.2106595784 0.0052419764 0.0418720000 388273013 0 402718720 -0.1698547155 -0.1475071460 -0.0697863251 1094 1311867206.9005689621 0.1700600535 0.1586553679 0.2106595784 0.0052396500 0.0415180000 388276101 0 402718720 -0.1704836488 -0.1488729715 -0.0701128617 1095 1311867206.9364409447 0.1703629345 0.1586660598 0.2106595784 0.0052442063 0.0406710000 388279413 0 402718720 -0.1711916327 -0.1518468708 -0.0703801364 1096 1311867206.9686069489 0.1705789566 0.1586769292 0.2106595784 0.0052450122 0.0413850000 388282557 0 402718720 -0.1707461327 -0.1533267796 -0.0707787871 1097 1311867207.0006439686 0.1707626879 0.1586879463 0.2106595784 0.0052546271 0.0424080000 388285701 0 402718720 -0.1709236354 -0.1544685215 -0.0714526847 1098 1311867207.0365860462 0.1716495454 0.1586997510 0.2106595784 0.0052574168 0.0422190000 388288957 0 402718720 -0.1709441692 -0.1563363522 -0.0715024397 1099 1311867207.0684070587 0.1715067625 0.1587114044 0.2106595784 0.0052601432 0.0439560000 388292101 0 402718720 -0.1712205261 -0.1586268395 -0.0717787221 1100 1311867207.1005458832 0.1715273410 0.1587230552 0.2106595784 0.0052633684 0.0444210000 388295189 0 402718720 -0.1701884866 -0.1590570956 -0.0723608434 1101 1311867207.1364729404 0.1720673442 0.1587351754 0.2106595784 0.0052800881 0.0373180000 388298389 0 402718720 -0.1696352363 -0.1603024751 -0.0724556670 1102 1311867207.1687068939 0.1719929129 0.1587472060 0.2106595784 0.0052791842 0.0421420000 388301589 0 402718720 -0.1698478311 -0.1624955535 -0.0725039840 1103 1311867207.2006540298 0.1721296161 0.1587593387 0.2106595784 0.0052772805 0.0421880000 388304733 0 402718720 -0.1697588563 -0.1634629667 -0.0724252015 1104 1311867207.2365870476 0.1725399196 0.1587718211 0.2106595784 0.0052750301 0.0415070000 388307989 0 402718720 -0.1694130301 -0.1638054550 -0.0722701401 1105 1311867207.2686169147 0.1722209752 0.1587839923 0.2106595784 0.0052734171 0.0423550000 388311133 0 402718720 -0.1701343358 -0.1662731767 -0.0721690357 1106 1311867207.3004999161 0.1722563803 0.1587961735 0.2106595784 0.0052717352 0.0423190000 388314277 0 402718720 -0.1703257114 -0.1679663062 -0.0716029629 1107 1311867207.3366520405 0.1726049036 0.1588086475 0.2106595784 0.0052736877 0.0421580000 388317477 0 402718720 -0.1702472717 -0.1680963337 -0.0716099963 1108 1311867207.3685789108 0.1721566468 0.1588206944 0.2106595784 0.0052747432 0.0417170000 388320677 0 402718720 -0.1704105437 -0.1695881486 -0.0711235180 1109 1311867207.4006979465 0.1721281111 0.1588326939 0.2106595784 0.0052728419 0.0424710000 388323877 0 402718720 -0.1718624979 -0.1723423004 -0.0707151964 1110 1311867207.4365799427 0.1722860932 0.1588448141 0.2106595784 0.0052723811 0.0429660000 388327077 0 402718720 -0.1723439842 -0.1727297455 -0.0705401674 1111 1311867207.4686470032 0.1724758893 0.1588570833 0.2106595784 0.0052704212 0.0413730000 388330221 0 402718720 -0.1734418422 -0.1741487533 -0.0700071380 1112 1311867207.5006010532 0.1719893664 0.1588688929 0.2106595784 0.0052709669 0.0437910000 388333309 0 402718720 -0.1740551591 -0.1767247319 -0.0697164312 1113 1311867207.5365080833 0.1706638485 0.1588794903 0.2106595784 0.0052727228 0.0428120000 388336565 0 402718720 -0.1739412099 -0.1785644144 -0.0702126026 1114 1311867207.5687060356 0.1715919673 0.1588909019 0.2106595784 0.0052711498 0.0433040000 388339765 0 402718720 -0.1752663255 -0.1797619909 -0.0693547428 1115 1311867207.6005868912 0.1718232185 0.1589025004 0.2106595784 0.0052695138 0.0432910000 388342909 0 402718720 -0.1766339988 -0.1820875108 -0.0692537129 1116 1311867207.6364910603 0.1716106087 0.1589138876 0.2106595784 0.0052710975 0.0432680000 388346109 0 402718720 -0.1770939976 -0.1830388606 -0.0697393417 1117 1311867207.6687729359 0.1719582379 0.1589255656 0.2106595784 0.0052731760 0.0431540000 388349309 0 402718720 -0.1776309162 -0.1840949804 -0.0696808249 1118 1311867207.7005620003 0.1724832654 0.1589376923 0.2106595784 0.0052709268 0.0425670000 388352453 0 402718720 -0.1789815724 -0.1862266809 -0.0692767799 1119 1311867207.7365009785 0.1723863930 0.1589497108 0.2106595784 0.0052709462 0.0393190000 388355653 0 402718720 -0.1791838855 -0.1878859848 -0.0693090856 1120 1311867207.7686090469 0.1724736392 0.1589617858 0.2106595784 0.0052688419 0.0446830000 388358797 0 402718720 -0.1796081215 -0.1894166023 -0.0692367107 1121 1311867207.8009910583 0.1732777208 0.1589745565 0.2106595784 0.0052669492 0.0453880000 388361885 0 402718720 -0.1807575524 -0.1908670068 -0.0688793659 1122 1311867207.8365540504 0.1720083654 0.1589861730 0.2106595784 0.0052717356 0.0427080000 388365197 0 402718720 -0.1797826588 -0.1932041198 -0.0691380352 1123 1311867207.8687729836 0.1724437922 0.1589981567 0.2106595784 0.0052794566 0.0412270000 388368341 0 402718720 -0.1794570386 -0.1940139979 -0.0687949359 1124 1311867207.9008998871 0.1724580228 0.1590101316 0.2106595784 0.0052776483 0.0423050000 388371429 0 402718720 -0.1797392964 -0.1960111558 -0.0687403902 1125 1311867207.9365339279 0.1718801707 0.1590215717 0.2106595784 0.0052793191 0.0424310000 388374685 0 402718720 -0.1796413213 -0.1973733157 -0.0689587891 1126 1311867207.9684898853 0.1732565463 0.1590342138 0.2106595784 0.0052789245 0.0431570000 388377773 0 402718720 -0.1802026182 -0.1969936639 -0.0685498044 1127 1311867208.0006649494 0.1723977625 0.1590460714 0.2106595784 0.0052910579 0.1998890000 400720405 0 402718720 -0.1802276075 -0.2004367262 -0.0681437179 1128 1311867208.0367650986 0.1717833728 0.1590573633 0.2106595784 0.0053007300 0.0240240000 404382813 0 402718720 -0.1785223633 -0.2002827078 -0.0691390783 1129 1311867208.0699250698 0.1720078290 0.1590688341 0.2106595784 0.0052994523 0.0226840000 407578149 0 402718720 -0.1776695102 -0.1999906301 -0.0695562661 1130 1311867208.1011340618 0.1721372902 0.1590803991 0.2106595784 0.0052971955 0.0540720000 407581125 0 402718720 -0.1786383986 -0.2022815645 -0.0691122636 1131 1311867208.1366329193 0.1728093624 0.1590925378 0.2106595784 0.0052954004 0.0433380000 407584381 0 402718720 -0.1792888492 -0.2029722035 -0.0695146695 1132 1311867208.1686830521 0.1724909842 0.1591043739 0.2106595784 0.0052941648 0.0419780000 407587581 0 402718720 -0.1791779846 -0.2043135315 -0.0697760954 1133 1311867208.2005209923 0.1723294109 0.1591160465 0.2106595784 0.0052976839 0.0385510000 407590669 0 402718720 -0.1787363142 -0.2057748437 -0.0695795715 1134 1311867208.2365610600 0.1733670533 0.1591286135 0.2106595784 0.0052956350 0.0378600000 407593925 0 402718720 -0.1799939424 -0.2070137262 -0.0697597042 1135 1311867208.2684400082 0.1727920026 0.1591406518 0.2106595784 0.0052943771 0.0364540000 407597069 0 402718720 -0.1792954057 -0.2082446367 -0.0703963712 1136 1311867208.3005969524 0.1728954762 0.1591527599 0.2106595784 0.0052922902 0.0379610000 407600157 0 402718720 -0.1790100038 -0.2090306878 -0.0705709010 1137 1311867208.3365280628 0.1733528674 0.1591652490 0.2106595784 0.0052949789 0.0387390000 407603413 0 402718720 -0.1792333722 -0.2101748884 -0.0708580464 1138 1311867208.3685109615 0.1739746630 0.1591782625 0.2106595784 0.0052969718 0.0352350000 407606613 0 402718720 -0.1795905083 -0.2107903957 -0.0708621591 1139 1311867208.4005920887 0.1740131527 0.1591912870 0.2106595784 0.0052947541 0.0426950000 407609757 0 402718720 -0.1804401726 -0.2127697915 -0.0706472769 1140 1311867208.4364600182 0.1737714261 0.1592040766 0.2106595784 0.0052925333 0.0370830000 407613013 0 402718720 -0.1800831854 -0.2144950926 -0.0707766265 1141 1311867208.4686639309 0.1735511422 0.1592166507 0.2106595784 0.0052921772 0.0366580000 407616157 0 402718720 -0.1790348589 -0.2147849649 -0.0714555085 1142 1311867208.5005640984 0.1741833985 0.1592297565 0.2106595784 0.0052900176 0.0429900000 407619245 0 402718720 -0.1800530702 -0.2164079994 -0.0706517473 1143 1311867208.5365219116 0.1748373508 0.1592434114 0.2106595784 0.0052889045 0.0373420000 407622501 0 402718720 -0.1807377785 -0.2170775831 -0.0704107210 1144 1311867208.5686440468 0.1747084260 0.1592569298 0.2106595784 0.0052868826 0.0349160000 407625701 0 402718720 -0.1807091236 -0.2175880522 -0.0703149736 1145 1311867208.6005949974 0.1744493246 0.1592701982 0.2106595784 0.0052847429 0.0365430000 407628845 0 402718720 -0.1805724502 -0.2186249197 -0.0699210018 1146 1311867208.6364450455 0.1740608662 0.1592831046 0.2106595784 0.0052831064 0.0380360000 407632045 0 402718720 -0.1810300946 -0.2200205922 -0.0691686869 1147 1311867208.6684880257 0.1742158085 0.1592961235 0.2106595784 0.0052814834 0.0342170000 407635245 0 402718720 -0.1808885932 -0.2199903280 -0.0692053214 1148 1311867208.7006061077 0.1742929965 0.1593091870 0.2106595784 0.0052791945 0.0372610000 407638445 0 402718720 -0.1815320551 -0.2209902704 -0.0684283674 1149 1311867208.7367100716 0.1743083745 0.1593222411 0.2106595784 0.0052774934 0.0354080000 407641645 0 402718720 -0.1824653149 -0.2222642452 -0.0678021088 1150 1311867208.7688069344 0.1745005697 0.1593354397 0.2106595784 0.0052752479 0.0331910000 407644789 0 402718720 -0.1827776432 -0.2220457643 -0.0676363111 1151 1311867208.8006410599 0.1732446551 0.1593475241 0.2106595784 0.0052737243 0.0397890000 407647877 0 402718720 -0.1827360690 -0.2247408032 -0.0669600144 1152 1311867208.8368830681 0.1726258248 0.1593590504 0.2106595784 0.0052723202 0.0388430000 407651189 0 402718720 -0.1824956834 -0.2256570309 -0.0669588819 1153 1311867208.8684909344 0.1744652241 0.1593721520 0.2106595784 0.0052754012 0.0351490000 407654333 0 402718720 -0.1836468279 -0.2245715708 -0.0666954517 1154 1311867208.9008109570 0.1743085682 0.1593850952 0.2106595784 0.0052750898 0.0368420000 407657365 0 402718720 -0.1848646253 -0.2262133211 -0.0662840754 1155 1311867208.9365160465 0.1734225601 0.1593972489 0.2106595784 0.0052748604 0.0379430000 407660621 0 402718720 -0.1855762452 -0.2295396626 -0.0658423752 1156 1311867208.9687321186 0.1735882461 0.1594095248 0.2106595784 0.0052726685 0.0374570000 407663765 0 402718720 -0.1851638556 -0.2294313312 -0.0666910857 1157 1311867209.0007669926 0.1732193828 0.1594214607 0.2106595784 0.0052704545 0.0404850000 407666853 0 402718720 -0.1848146617 -0.2306322455 -0.0671691895 1158 1311867209.0365889072 0.1729859710 0.1594331745 0.2106595784 0.0052766930 0.0403070000 407670109 0 402718720 -0.1858845502 -0.2325839400 -0.0675048977 1159 1311867209.0688478947 0.1750041693 0.1594466093 0.2106595784 0.0052825639 0.0375340000 407673309 0 402718720 -0.1865649074 -0.2317436486 -0.0681048185 1160 1311867209.1008369923 0.1751620173 0.1594601571 0.2106595784 0.0052803483 0.0413780000 407676397 0 402718720 -0.1867602766 -0.2322243750 -0.0685617477 1161 1311867209.1452479362 0.1753287464 0.1594738251 0.2106595784 0.0052803668 0.0358290000 407679933 0 402718720 -0.1870872974 -0.2340730280 -0.0687442794 1162 1311867209.1686758995 0.1758166552 0.1594878895 0.2106595784 0.0052786719 0.0382210000 407682797 0 402718720 -0.1868426651 -0.2336602807 -0.0691035092 1163 1311867209.2006080151 0.1755508929 0.1595017012 0.2106595784 0.0052765193 0.0404890000 407685941 0 402718720 -0.1868794709 -0.2347633839 -0.0693381652 1164 1311867209.2365789413 0.1760190427 0.1595158914 0.2106595784 0.0052743269 0.0369780000 407689141 0 402718720 -0.1882186979 -0.2361761183 -0.0697078928 1165 1311867209.2686769962 0.1767381877 0.1595306745 0.2106595784 0.0052747440 0.0322050000 407692341 0 402718720 -0.1887808293 -0.2358916849 -0.0701760724 1166 1311867209.3005480766 0.1768042743 0.1595454889 0.2106595784 0.0052759596 0.0407040000 407695429 0 402718720 -0.1890466213 -0.2369986475 -0.0703737214 1167 1311867209.3366079330 0.1761247665 0.1595596956 0.2106595784 0.0052750001 0.0405610000 407698685 0 402718720 -0.1894827187 -0.2397434264 -0.0703916252 1168 1311867209.3686850071 0.1768358350 0.1595744868 0.2106595784 0.0052733983 0.0488940000 407701885 0 402718720 -0.1892123818 -0.2387192696 -0.0712371767 1169 1311867209.4006741047 0.1768301576 0.1595892479 0.2106595784 0.0052712597 0.0506820000 407705029 0 402718720 -0.1899288595 -0.2398752868 -0.0717020184 1170 1311867209.4366040230 0.1765130162 0.1596037126 0.2106595784 0.0052699355 0.0512210000 407708229 0 402718720 -0.1908729672 -0.2425026894 -0.0715534091 1171 1311867209.4685039520 0.1774861366 0.1596189837 0.2106595784 0.0052690068 0.0519270000 407711373 0 402718720 -0.1910180897 -0.2414105237 -0.0721351206 1172 1311867209.5011129379 0.1773277223 0.1596340936 0.2106595784 0.0052669219 0.0424220000 407714573 0 402718720 -0.1914525777 -0.2423637211 -0.0727110878 1173 1311867209.5369019508 0.1774725616 0.1596493011 0.2106595784 0.0052647892 0.0368560000 407717829 0 402718720 -0.1924258620 -0.2435362637 -0.0727020055 1174 1311867209.5686891079 0.1784265339 0.1596652954 0.2106595784 0.0052625919 0.0389560000 407720917 0 402718720 -0.1946866661 -0.2453003079 -0.0720361173 1175 1311867209.6007590294 0.1784286797 0.1596812642 0.2106595784 0.0052604631 0.0411950000 407724061 0 402718720 -0.1956461668 -0.2466256320 -0.0721315593 1176 1311867209.6365940571 0.1780450046 0.1596968796 0.2106595784 0.0052689890 0.0387070000 407727317 0 402718720 -0.1955366135 -0.2476457655 -0.0725654140 1177 1311867209.6685700417 0.1769318879 0.1597115228 0.2106595784 0.0052713384 0.0408660000 407730349 0 402718720 -0.1949197352 -0.2497811317 -0.0729207993 1178 1311867209.7012720108 0.1770971864 0.1597262814 0.2106595784 0.0052738298 0.0426310000 407733437 0 402718720 -0.1956206858 -0.2513266206 -0.0731612891 1179 1311867209.7365729809 0.1781146228 0.1597418780 0.2106595784 0.0052758622 0.0424080000 407736749 0 402718720 -0.1965987980 -0.2518881261 -0.0734649748 1180 1311867209.7686240673 0.1775599718 0.1597569781 0.2106595784 0.0052815452 0.0450900000 407739893 0 402718720 -0.1965486705 -0.2529228330 -0.0745449215 1181 1311867209.8014979362 0.1768258810 0.1597714310 0.2106595784 0.0052938523 0.0458700000 407743037 0 402718720 -0.1971517205 -0.2554366887 -0.0753770173 1182 1311867209.8365740776 0.1785474122 0.1597873159 0.2106595784 0.0052955637 0.0456600000 407746237 0 402718720 -0.1970148683 -0.2538728714 -0.0753597021 1183 1311867209.8685529232 0.1789653301 0.1598035272 0.2106595784 0.0052933471 0.0445480000 407749437 0 402718720 -0.1976206452 -0.2548494637 -0.0755925700 1184 1311867209.9006690979 0.1780742109 0.1598189586 0.2106595784 0.0052913716 0.0463210000 407752525 0 402718720 -0.1975300312 -0.2566181123 -0.0766389742 1185 1311867209.9365439415 0.1793203801 0.1598354155 0.2106595784 0.0052895895 0.0447140000 407755837 0 402718720 -0.1978892535 -0.2557342947 -0.0767742097 1186 1311867209.9689381123 0.1794055700 0.1598519164 0.2106595784 0.0052875872 0.0447560000 407758981 0 402718720 -0.1979721189 -0.2567749023 -0.0769806653 1187 1311867210.0007040501 0.1783284247 0.1598674821 0.2106595784 0.0052972358 0.0472350000 407762125 0 402718720 -0.1980078965 -0.2590539753 -0.0778197870 1188 1311867210.0366830826 0.1795608401 0.1598840590 0.2106595784 0.0053038051 0.0447320000 407765325 0 402718720 -0.1975253224 -0.2579003870 -0.0782827884 1189 1311867210.0688159466 0.1802570671 0.1599011936 0.2106595784 0.0053058677 0.0446520000 407768525 0 402718720 -0.1985106319 -0.2586508095 -0.0783136562 1190 1311867210.1006069183 0.1795951426 0.1599177432 0.2106595784 0.0053067527 0.0460110000 407771725 0 402718720 -0.1982574165 -0.2604966462 -0.0783030093 1191 1311867210.1367108822 0.1805352718 0.1599350543 0.2106595784 0.0053052343 0.0467810000 407774925 0 402718720 -0.1976182014 -0.2590635121 -0.0787096769 1192 1311867210.1686730385 0.1812171489 0.1599529084 0.2106595784 0.0053030602 0.0442220000 407778125 0 402718720 -0.1983583272 -0.2589130104 -0.0789811760 1193 1311867210.2006618977 0.1800238043 0.1599697323 0.2106595784 0.0053014149 0.0418090000 407781213 0 402718720 -0.1988251656 -0.2613846362 -0.0794364661 1194 1311867210.2366139889 0.1804637015 0.1599868964 0.2106595784 0.0052996994 0.0434220000 407784469 0 402718720 -0.1987610459 -0.2610810697 -0.0801934674 1195 1311867210.2687640190 0.1807788759 0.1600042955 0.2106595784 0.0052978748 0.0475970000 407787613 0 402718720 -0.1981129944 -0.2602589428 -0.0808332935 1196 1311867210.3006920815 0.1809400022 0.1600218003 0.2106595784 0.0052957190 0.0438840000 407790757 0 402718720 -0.1991386265 -0.2613000870 -0.0810696632 1197 1311867210.3366720676 0.1813050359 0.1600395808 0.2106595784 0.0052936585 0.0413910000 407794069 0 402718720 -0.1992141008 -0.2610070109 -0.0815625489 1198 1311867210.3689930439 0.1813343018 0.1600573560 0.2106595784 0.0052914846 0.0436650000 407797213 0 402718720 -0.1988817900 -0.2611932158 -0.0813599899 1199 1311867210.4007411003 0.1816093177 0.1600753310 0.2106595784 0.0052942795 0.0427440000 407800357 0 402718720 -0.1999546438 -0.2620776296 -0.0815933347 1200 1311867210.4366719723 0.1816835999 0.1600933379 0.2106595784 0.0052920753 0.0422120000 407803557 0 402718720 -0.2008463293 -0.2630074024 -0.0820634142 1201 1311867210.4690630436 0.1825136244 0.1601120059 0.2106595784 0.0052904319 0.0449190000 407806757 0 402718720 -0.1996992677 -0.2602114975 -0.0829625204 1202 1311867210.5006489754 0.1829482615 0.1601310044 0.2106595784 0.0052988890 0.0411820000 407809789 0 402718720 -0.2009663433 -0.2607932091 -0.0826586932 1203 1311867210.5366818905 0.1816807687 0.1601489178 0.2106595784 0.0052977117 0.0390340000 407813045 0 402718720 -0.2010386437 -0.2625464797 -0.0832064450 1204 1311867210.5690469742 0.1835548729 0.1601683579 0.2106595784 0.0052970062 0.0432290000 407816245 0 402718720 -0.2012998015 -0.2596360147 -0.0834939107 1205 1311867210.6008589268 0.1826939136 0.1601870513 0.2106595784 0.0052948704 0.0423770000 407819333 0 402718720 -0.2009519041 -0.2603489161 -0.0838118717 1206 1311867210.6367869377 0.1800538599 0.1602035246 0.2106595784 0.0052986193 0.0416160000 407822589 0 402718720 -0.2007158101 -0.2648716569 -0.0838585943 1207 1311867210.6738469601 0.1810986847 0.1602208363 0.2106595784 0.0052978957 0.0412510000 407825901 0 402718720 -0.2008653879 -0.2637303472 -0.0848529339 1208 1311867210.7007210255 0.1827016175 0.1602394462 0.2106595784 0.0052985230 0.0444150000 407828933 0 402718720 -0.2013400197 -0.2620565891 -0.0853262469 1209 1311867210.7366569042 0.1814953387 0.1602570276 0.2106595784 0.0052977287 0.0442810000 407832133 0 402718720 -0.2015806139 -0.2642115057 -0.0858488306 1210 1311867210.7690360546 0.1820855439 0.1602750677 0.2106595784 0.0053006645 0.0438110000 407835333 0 402718720 -0.2005720437 -0.2625200450 -0.0860421658 1211 1311867210.8006999493 0.1841511428 0.1602947837 0.2106595784 0.0053150706 0.0431200000 407838253 0 402718720 -0.2014088035 -0.2602545023 -0.0855313092 1212 1311867210.8368630409 0.1818260998 0.1603125488 0.2106595784 0.0053159401 0.0412230000 407841453 0 402718720 -0.2013726979 -0.2633194029 -0.0858404338 1213 1311867210.8688309193 0.1827860922 0.1603310760 0.2106595784 0.0053144589 0.0413660000 407844653 0 402718720 -0.2005766034 -0.2611642182 -0.0856739134 1214 1311867210.9007239342 0.1821405292 0.1603490410 0.2106595784 0.0053127281 0.0425340000 407847741 0 402718720 -0.2008182704 -0.2626391053 -0.0852827579 1215 1311867210.9367508888 0.1835307479 0.1603681206 0.2106595784 0.0053114943 0.0445010000 407850997 0 402718720 -0.2001764625 -0.2594189644 -0.0857223347 1216 1311867210.9692239761 0.1843917966 0.1603878769 0.2106595784 0.0053109060 0.0382420000 407854197 0 402718720 -0.2006669790 -0.2577013075 -0.0851204693 1217 1311867211.0011980534 0.1809527278 0.1604047749 0.2106595784 0.0053145773 0.0394400000 407857285 0 402718720 -0.2010412663 -0.2633744478 -0.0844758376 1218 1311867211.0367538929 0.1825985610 0.1604229964 0.2106595784 0.0053130520 0.0407490000 407860541 0 402718720 -0.2005144358 -0.2598471045 -0.0851699561 1219 1311867211.0691709518 0.1837615222 0.1604421420 0.2106595784 0.0053134315 0.0405620000 407863741 0 402718720 -0.2011496276 -0.2583295405 -0.0847132057 1220 1311867211.1013391018 0.1806747615 0.1604587261 0.2106595784 0.0053157620 0.0426090000 407866885 0 402718720 -0.2013445199 -0.2632360756 -0.0847245380 1221 1311867211.1368789673 0.1814326942 0.1604759038 0.2106595784 0.0053140005 0.0401100000 407870085 0 402718720 -0.2012886703 -0.2623079717 -0.0851368159 1222 1311867211.1695349216 0.1821501702 0.1604936405 0.2106595784 0.0053120967 0.0426580000 407873285 0 402718720 -0.2005525529 -0.2601068020 -0.0856839940 1223 1311867211.2007589340 0.1819701642 0.1605112011 0.2106595784 0.0053100198 0.0400080000 407876373 0 402718720 -0.2012709975 -0.2610933483 -0.0853252634 1224 1311867211.2369379997 0.1813188642 0.1605282008 0.2106595784 0.0053151350 0.0399380000 407879685 0 402718720 -0.2021574825 -0.2625163794 -0.0855755210 1225 1311867211.2689440250 0.1820959151 0.1605458071 0.2106595784 0.0053135608 0.0409840000 407882829 0 402718720 -0.2013170868 -0.2598836124 -0.0862863138 1226 1311867211.3010730743 0.1820518374 0.1605633487 0.2106595784 0.0053116520 0.0416360000 407885973 0 402718720 -0.2009870708 -0.2594493032 -0.0859623179 1227 1311867211.3368151188 0.1814296097 0.1605803546 0.2106595784 0.0053098785 0.0377030000 407889173 0 402718720 -0.2015474141 -0.2607413828 -0.0857367814 1228 1311867211.3688991070 0.1819569021 0.1605977623 0.2106595784 0.0053079214 0.0397180000 407892317 0 402718720 -0.2014354914 -0.2591089904 -0.0861006677 1229 1311867211.4011549950 0.1822059453 0.1606153442 0.2106595784 0.0053060454 0.0433650000 407895517 0 402718720 -0.2010109723 -0.2572691143 -0.0863462240 1230 1311867211.4367830753 0.1818553060 0.1606326124 0.2106595784 0.0053113438 0.0399050000 407898717 0 402718720 -0.2011388838 -0.2574832439 -0.0859014615 1231 1311867211.4687600136 0.1811133474 0.1606492499 0.2106595784 0.0053097782 0.0415950000 407901861 0 402718720 -0.2012181431 -0.2580365241 -0.0858834758 1232 1311867211.5007500648 0.1819299012 0.1606665232 0.2106595784 0.0053078690 0.0415890000 407905061 0 402718720 -0.2009129375 -0.2560401857 -0.0856253132 1233 1311867211.5369210243 0.1810333431 0.1606830413 0.2106595784 0.0053062292 0.0435700000 407908205 0 402718720 -0.2003311068 -0.2562355399 -0.0856760591 1234 1311867211.5693531036 0.1812081933 0.1606996743 0.2106595784 0.0053055438 0.0414320000 407911405 0 402718720 -0.2011162937 -0.2565347254 -0.0853766203 1235 1311867211.6009359360 0.1809513271 0.1607160724 0.2106595784 0.0053034432 0.0393810000 407914549 0 402718720 -0.2008795440 -0.2561646998 -0.0855563581 1236 1311867211.6367759705 0.1815560013 0.1607329332 0.2106595784 0.0053052336 0.0413290000 407917749 0 402718720 -0.2003338337 -0.2538570166 -0.0855114236 1237 1311867211.6694169044 0.1802883297 0.1607487419 0.2106595784 0.0053062907 0.0387240000 407921005 0 402718720 -0.2011133730 -0.2561286092 -0.0850820094 1238 1311867211.7007949352 0.1810747236 0.1607651603 0.2106595784 0.0053047097 0.0396020000 407924093 0 402718720 -0.2013876885 -0.2549561262 -0.0853309855 1239 1311867211.7367610931 0.1808352768 0.1607813589 0.2106595784 0.0053031261 0.0392970000 407927293 0 402718720 -0.2011697292 -0.2543180585 -0.0855842754 1240 1311867211.7698910236 0.1803633571 0.1607971509 0.2106595784 0.0053020339 0.0391690000 407930493 0 402718720 -0.2001738548 -0.2542122900 -0.0860313922 1241 1311867211.8010520935 0.1807738245 0.1608132481 0.2106595784 0.0053002511 0.0402040000 407933525 0 402718720 -0.1998413354 -0.2531923950 -0.0863477066 1242 1311867211.8382968903 0.1798948050 0.1608286117 0.2106595784 0.0052984189 0.0392580000 407936781 0 402718720 -0.1992452741 -0.2536389828 -0.0870813057 1243 1311867211.8687980175 0.1813898683 0.1608451533 0.2106595784 0.0052979862 0.0403240000 407939869 0 402718720 -0.1992902905 -0.2506558299 -0.0874796361 1244 1311867211.9011518955 0.1807637364 0.1608611651 0.2106595784 0.0052978929 0.0378710000 407943069 0 402718720 -0.1997748613 -0.2515517473 -0.0877453014 1245 1311867211.9373478889 0.1804928631 0.1608769335 0.2106595784 0.0052961223 0.0366280000 407946269 0 402718720 -0.1997428536 -0.2513935268 -0.0881540775 1246 1311867211.9710869789 0.1804476529 0.1608926403 0.2106595784 0.0052940350 0.0424210000 407949469 0 402718720 -0.1983899325 -0.2493907362 -0.0889139920 1247 1311867212.0010540485 0.1812358946 0.1609089541 0.2106595784 0.0052921497 0.0425930000 407952613 0 402718720 -0.1982361674 -0.2475929409 -0.0889241993 1248 1311867212.0373959541 0.1807301342 0.1609248364 0.2106595784 0.0052901633 0.0374130000 407955813 0 402718720 -0.1991294175 -0.2486234903 -0.0890850499 1249 1311867212.0689249039 0.1812484413 0.1609411083 0.2106595784 0.0052881895 0.0381350000 407959013 0 402718720 -0.1987120062 -0.2463490367 -0.0898882747 1250 1311867212.1008360386 0.1822561622 0.1609581604 0.2106595784 0.0052875828 0.0394440000 407962045 0 402718720 -0.1978932023 -0.2434300035 -0.0895584598 1251 1311867212.1371040344 0.1808058321 0.1609740258 0.2106595784 0.0052866827 0.0385510000 407965357 0 402718720 -0.1972256154 -0.2440116405 -0.0898246020 1252 1311867212.1688990593 0.1803414971 0.1609894951 0.2106595784 0.0052855288 0.0371650000 407968501 0 402718720 -0.1980014890 -0.2443766743 -0.0900257826 1253 1311867212.2012920380 0.1807343811 0.1610052531 0.2106595784 0.0052841338 0.0399110000 407971589 0 402718720 -0.1968615353 -0.2416580170 -0.0908569768 1254 1311867212.2368280888 0.1804392487 0.1610207507 0.2106595784 0.0052822311 0.0411590000 407974845 0 402718720 -0.1969868988 -0.2417776883 -0.0908720046 1255 1311867212.2696599960 0.1801262945 0.1610359743 0.2106595784 0.0052807164 0.0393040000 407977989 0 402718720 -0.1971318126 -0.2416662127 -0.0913918912 1256 1311867212.3007979393 0.1805961728 0.1610515477 0.2106595784 0.0052788172 0.0382540000 407981189 0 402718720 -0.1974722594 -0.2404234856 -0.0924437121 1257 1311867212.3369801044 0.1808975935 0.1610673361 0.2106595784 0.0052780628 0.0382120000 407984445 0 402718720 -0.1960054636 -0.2370325029 -0.0934846625 1258 1311867212.3691210747 0.1805745661 0.1610828427 0.2106595784 0.0052761363 0.0392450000 407987533 0 402718720 -0.1962123811 -0.2368675023 -0.0936425477 1259 1311867212.4008738995 0.1804778576 0.1610982478 0.2106595784 0.0052899204 0.0379420000 407990677 0 402718720 -0.1957891732 -0.2355411202 -0.0942402631 1260 1311867212.4372949600 0.1806447804 0.1611137609 0.2106595784 0.0053167852 0.0395880000 407993933 0 402718720 -0.1949680001 -0.2337865084 -0.0944637358 1261 1311867212.4688138962 0.1809436977 0.1611294864 0.2106595784 0.0053314024 0.0417300000 407997077 0 402718720 -0.1950879693 -0.2323108464 -0.0948323980 1262 1311867212.5009200573 0.1800781488 0.1611445012 0.2106595784 0.0053372206 0.0412950000 408000221 0 402718720 -0.1949342042 -0.2328423113 -0.0953406170 1263 1311867212.5369908810 0.1800229698 0.1611594485 0.2106595784 0.0053353105 0.0390540000 408003421 0 402718720 -0.1940097362 -0.2318154126 -0.0958862379 1264 1311867212.5687799454 0.1807769984 0.1611749688 0.2106595784 0.0053450243 0.0390090000 408006621 0 402718720 -0.1934973747 -0.2298887670 -0.0967058167 1265 1311867212.6007750034 0.1804147214 0.1611901781 0.2106595784 0.0053440946 0.0371750000 408009821 0 402718720 -0.1931847930 -0.2302926183 -0.0971667022 1266 1311867212.6369509697 0.1811069995 0.1612059101 0.2106595784 0.0053422967 0.0382440000 408012965 0 402718720 -0.1934569925 -0.2294858545 -0.0977042764 1267 1311867212.6688740253 0.1813864708 0.1612218380 0.2106595784 0.0053418114 0.0387040000 408016053 0 402718720 -0.1918875426 -0.2268460840 -0.0990405604 1268 1311867212.7010180950 0.1812041551 0.1612375969 0.2106595784 0.0053405595 0.0383290000 408019253 0 402718720 -0.1916783601 -0.2269319296 -0.0993701816 1269 1311867212.7369890213 0.1815875769 0.1612536331 0.2106595784 0.0053388877 0.0384930000 408022453 0 402718720 -0.1911978722 -0.2258144468 -0.1000496671 1270 1311867212.7689590454 0.1816208512 0.1612696703 0.2106595784 0.0053453802 0.0381960000 408025653 0 402718720 -0.1908891946 -0.2244692892 -0.1007310450 1271 1311867212.8008079529 0.1819303185 0.1612859257 0.2106595784 0.0053505788 0.0384100000 408028741 0 402718720 -0.1904841363 -0.2229902148 -0.1014750749 1272 1311867212.8378698826 0.1814601123 0.1613017859 0.2106595784 0.0053486602 0.0340350000 408032053 0 402718720 -0.1904440522 -0.2235687822 -0.1016468033 1273 1311867212.8690330982 0.1813440174 0.1613175300 0.2106595784 0.0053479317 0.0367580000 408035197 0 402718720 -0.1898391992 -0.2233519703 -0.1023589671 1274 1311867212.9008109570 0.1817854196 0.1613335959 0.2106595784 0.0053547198 0.0385560000 408038285 0 402718720 -0.1894429922 -0.2204491645 -0.1032977030 1275 1311867212.9369480610 0.1813231707 0.1613492740 0.2106595784 0.0053541870 0.0370830000 408041597 0 402718720 -0.1889611781 -0.2196884900 -0.1037615389 1276 1311867212.9690868855 0.1818813831 0.1613653650 0.2106595784 0.0053584184 0.0375100000 408044741 0 402718720 -0.1885255724 -0.2183792144 -0.1043185964 1277 1311867213.0010640621 0.1819114983 0.1613814544 0.2106595784 0.0053595249 0.0356580000 408047829 0 402718720 -0.1881075054 -0.2174329460 -0.1048200727 1278 1311867213.0369269848 0.1819005609 0.1613975100 0.2106595784 0.0053576356 0.0372090000 408051085 0 402718720 -0.1876678169 -0.2166213840 -0.1051014513 1279 1311867213.0690510273 0.1818350554 0.1614134893 0.2106595784 0.0053616495 0.0394470000 408054285 0 402718720 -0.1873794049 -0.2154904157 -0.1056871414 1280 1311867213.1010680199 0.1817102283 0.1614293461 0.2106595784 0.0053596356 0.0372290000 408057429 0 402718720 -0.1864439249 -0.2142323405 -0.1062544286 1281 1311867213.1370000839 0.1811685711 0.1614447554 0.2106595784 0.0053597683 0.0388540000 408060629 0 402718720 -0.1850579381 -0.2136867195 -0.1062884331 1282 1311867213.1691648960 0.1819270104 0.1614607322 0.2106595784 0.0053584740 0.0386240000 408063829 0 402718720 -0.1851302981 -0.2128434479 -0.1065929458 1283 1311867213.2014310360 0.1805861592 0.1614756390 0.2106595784 0.0053597591 0.0375360000 408066917 0 402718720 -0.1844341159 -0.2138389796 -0.1078872755 1284 1311867213.2368569374 0.1822142154 0.1614917905 0.2106595784 0.0053589210 0.0384740000 408070173 0 402718720 -0.1831780374 -0.2095244229 -0.1090081856 1285 1311867213.2692229748 0.1821624935 0.1615078767 0.2106595784 0.0053570390 0.0347850000 408073373 0 402718720 -0.1834720820 -0.2099354267 -0.1089841500 1286 1311867213.3014159203 0.1818753481 0.1615237145 0.2106595784 0.0053550219 0.0308440000 408076461 0 402718720 -0.1826090664 -0.2086092085 -0.1099664792 1287 1311867213.3368959427 0.1831311435 0.1615405035 0.2106595784 0.0053538950 0.0383660000 408079717 0 402718720 -0.1826644093 -0.2057198286 -0.1105401292 1288 1311867213.3690009117 0.1823933721 0.1615566936 0.2106595784 0.0053520062 0.0342470000 408082917 0 402718720 -0.1824614108 -0.2060119659 -0.1106231436 1289 1311867213.4013779163 0.1821107417 0.1615726393 0.2106595784 0.0053499722 0.0365980000 408086061 0 402718720 -0.1814334840 -0.2048068196 -0.1108447611 1290 1311867213.4371929169 0.1827012300 0.1615890181 0.2106595784 0.0053499692 0.0383380000 408089261 0 402718720 -0.1811531633 -0.2028390020 -0.1111329794 1291 1311867213.4690399170 0.1824341118 0.1616051646 0.2106595784 0.0053480331 0.0350830000 408092461 0 402718720 -0.1807488948 -0.2016742676 -0.1114640832 1292 1311867213.5009970665 0.1830140650 0.1616217349 0.2106595784 0.0053525631 0.0342810000 408095549 0 402718720 -0.1805287004 -0.1984087080 -0.1120735109 1293 1311867213.5368809700 0.1815835238 0.1616371733 0.2106595784 0.0053532160 0.0392090000 408098805 0 402718720 -0.1794614196 -0.1978772283 -0.1123295203 1294 1311867213.5690419674 0.1821130216 0.1616529970 0.2106595784 0.0053519887 0.0360640000 408102005 0 402718720 -0.1791332215 -0.1951300949 -0.1122450009 1295 1311867213.6010110378 0.1807958186 0.1616677791 0.2106595784 0.0053522661 0.0334140000 408105149 0 402718720 -0.1777386516 -0.1942233443 -0.1122314930 1296 1311867213.6369230747 0.1806959957 0.1616824613 0.2106595784 0.0053517146 0.0363620000 408108405 0 402718720 -0.1770448536 -0.1924523860 -0.1121573150 1297 1311867213.6689949036 0.1812212467 0.1616975259 0.2106595784 0.0053500313 0.0363430000 408111493 0 402718720 -0.1769276410 -0.1900846809 -0.1125574037 1298 1311867213.7012999058 0.1810159236 0.1617124091 0.2106595784 0.0053482946 0.0357070000 408114637 0 402718720 -0.1763293445 -0.1890730113 -0.1119725630 1299 1311867213.7371459007 0.1807590872 0.1617270717 0.2106595784 0.0053546569 0.0360780000 408117893 0 402718720 -0.1754521579 -0.1875726283 -0.1121095642 1300 1311867213.7690899372 0.1804149598 0.1617414470 0.2106595784 0.0053637542 0.0357750000 408121093 0 402718720 -0.1748205125 -0.1864290982 -0.1118034497 1301 1311867213.8016641140 0.1808340997 0.1617561224 0.2106595784 0.0053619064 0.0347930000 408124069 0 402718720 -0.1742457747 -0.1840793192 -0.1117704660 1302 1311867213.8373479843 0.1799709052 0.1617701122 0.2106595784 0.0053603337 0.0308410000 408127325 0 402718720 -0.1732290089 -0.1839313805 -0.1110555679 1303 1311867213.8689138889 0.1782971174 0.1617827960 0.2106595784 0.0053605374 0.0359280000 408130469 0 402718720 -0.1721628159 -0.1854456663 -0.1105597094 1304 1311867213.9009690285 0.1796138585 0.1617964701 0.2106595784 0.0053588141 0.0358340000 408133669 0 402718720 -0.1721896678 -0.1821175814 -0.1112252399 1305 1311867213.9370670319 0.1804146320 0.1618107369 0.2106595784 0.0053571366 0.0358270000 408136813 0 402718720 -0.1727785170 -0.1805725396 -0.1109501645 1306 1311867213.9689199924 0.1796166003 0.1618243708 0.2106595784 0.0053571598 0.0357380000 408140013 0 402718720 -0.1724759787 -0.1811296344 -0.1109702215 1307 1311867214.0051610470 0.1793830395 0.1618378052 0.2106595784 0.0053558505 0.0388230000 408143325 0 402718720 -0.1710978299 -0.1790231168 -0.1117611676 1308 1311867214.0371010303 0.1784685850 0.1618505198 0.2106595784 0.0053588552 0.0379700000 408146413 0 402718720 -0.1690603197 -0.1768684089 -0.1126063317 1309 1311867214.0689098835 0.1788414568 0.1618634999 0.2106595784 0.0053574246 0.0342340000 408149557 0 402718720 -0.1689205915 -0.1754630953 -0.1127559096 1310 1311867214.1048610210 0.1789066941 0.1618765100 0.2106595784 0.0053554966 0.0399240000 408152813 0 402718720 -0.1689308584 -0.1749701947 -0.1127113253 1311 1311867214.1382060051 0.1792384684 0.1618897533 0.2106595784 0.0053559974 0.0357060000 408155957 0 402718720 -0.1685372740 -0.1728277653 -0.1132972091 1312 1311867214.1696469784 0.1798839271 0.1619034684 0.2106595784 0.0053553364 0.0383690000 408159157 0 402718720 -0.1690932065 -0.1715748757 -0.1131871194 1313 1311867214.2052168846 0.1792780310 0.1619167011 0.2106595784 0.0053534855 0.0387340000 408162357 0 402718720 -0.1685228050 -0.1713240445 -0.1130126864 1314 1311867214.2398779392 0.1792801470 0.1619299153 0.2106595784 0.0053515827 0.0386000000 408165557 0 402718720 -0.1687949896 -0.1709032357 -0.1129066125 1315 1311867214.2705519199 0.1795612425 0.1619433231 0.2106595784 0.0053496241 0.0386850000 408168701 0 402718720 -0.1686951071 -0.1691806763 -0.1130741611 1316 1311867214.3057620525 0.1792248935 0.1619564550 0.2106595784 0.0053479754 0.0388860000 408171901 0 402718720 -0.1685205400 -0.1681068391 -0.1132140011 1317 1311867214.3376688957 0.1790098846 0.1619694037 0.2106595784 0.0053460968 0.0368540000 408175045 0 402718720 -0.1685877144 -0.1675493717 -0.1134443581 1318 1311867214.3690490723 0.1791978329 0.1619824753 0.2106595784 0.0053457265 0.0401590000 408178189 0 402718720 -0.1679351479 -0.1655221730 -0.1137715280 1319 1311867214.4050331116 0.1787545234 0.1619951911 0.2106595784 0.0053439475 0.0373450000 408181445 0 402718720 -0.1677034944 -0.1656225324 -0.1138073131 1320 1311867214.4373641014 0.1790338904 0.1620080992 0.2106595784 0.0053424394 0.0407170000 408184533 0 402718720 -0.1678554416 -0.1646619141 -0.1142844483 1321 1311867214.4697780609 0.1783414334 0.1620204636 0.2106595784 0.0053449487 0.0424770000 408187677 0 402718720 -0.1665188223 -0.1631273031 -0.1153751016 1322 1311867214.5059390068 0.1786004901 0.1620330052 0.2106595784 0.0053454143 0.0405190000 408190989 0 402718720 -0.1653836370 -0.1605125964 -0.1159818694 1323 1311867214.5373690128 0.1793956459 0.1620461289 0.2106595784 0.0053437514 0.0400150000 408194133 0 402718720 -0.1659212112 -0.1595163047 -0.1158063337 1324 1311867214.5691421032 0.1803257912 0.1620599353 0.2106595784 0.0053423743 0.0419160000 408197277 0 402718720 -0.1660815328 -0.1571281999 -0.1157963350 1325 1311867214.6048638821 0.1799108088 0.1620734076 0.2106595784 0.0053406339 0.0419510000 408200533 0 402718720 -0.1658212245 -0.1566909701 -0.1157927290 1326 1311867214.6369891167 0.1787830442 0.1620860092 0.2106595784 0.0053397838 0.0408630000 408203621 0 402718720 -0.1645155400 -0.1563872546 -0.1161155030 1327 1311867214.6691009998 0.1788547635 0.1620986457 0.2106595784 0.0053379622 0.0421300000 408206821 0 402718720 -0.1638908088 -0.1550038755 -0.1160998046 1328 1311867214.7048900127 0.1790220588 0.1621113893 0.2106595784 0.0053374492 0.0392030000 408210021 0 402718720 -0.1637729108 -0.1549752802 -0.1161725596 1329 1311867214.7369639874 0.1790981591 0.1621241709 0.2106595784 0.0053401733 0.0415940000 408213165 0 402718720 -0.1635428369 -0.1530124247 -0.1165144891 1330 1311867214.7695059776 0.1791182160 0.1621369484 0.2106595784 0.0053406597 0.0416190000 408216365 0 402718720 -0.1630861312 -0.1516520530 -0.1169422343 1331 1311867214.8049929142 0.1789411753 0.1621495736 0.2106595784 0.0053396005 0.0393320000 408219621 0 402718720 -0.1630487591 -0.1517549753 -0.1169239730 1332 1311867214.8369181156 0.1788854003 0.1621621381 0.2106595784 0.0053388045 0.0433130000 408222709 0 402718720 -0.1625707448 -0.1502047032 -0.1175046712 1333 1311867214.8699979782 0.1790483296 0.1621748059 0.2106595784 0.0053369933 0.0435860000 408225909 0 402718720 -0.1612924337 -0.1467857063 -0.1184585765 1334 1311867214.9049839973 0.1789355278 0.1621873701 0.2106595784 0.0053356662 0.0426410000 408229165 0 402718720 -0.1616605669 -0.1462175399 -0.1183926985 1335 1311867214.9372529984 0.1779714972 0.1621991935 0.2106595784 0.0053351993 0.0429450000 408232309 0 402718720 -0.1609189361 -0.1464643776 -0.1186758950 1336 1311867214.9693040848 0.1790136099 0.1622117791 0.2106595784 0.0053343415 0.0403220000 408235453 0 402718720 -0.1601753384 -0.1419343203 -0.1191873029 1337 1311867215.0050640106 0.1797085106 0.1622248657 0.2106595784 0.0053324962 0.0425920000 408238765 0 402718720 -0.1612251401 -0.1405534446 -0.1187083796 1338 1311867215.0371069908 0.1790272743 0.1622374235 0.2106595784 0.0053313735 0.0450730000 408241797 0 402718720 -0.1611219943 -0.1408280432 -0.1185053438 1339 1311867215.0692911148 0.1786931604 0.1622497131 0.2106595784 0.0053303459 0.0457430000 408244997 0 402718720 -0.1596193463 -0.1373597831 -0.1189661846 1340 1311867215.1050040722 0.1786062866 0.1622619195 0.2106595784 0.0053296320 0.0435660000 408248253 0 402718720 -0.1590060294 -0.1346919090 -0.1186666414 1341 1311867215.1369140148 0.1782241017 0.1622738227 0.2106595784 0.0053278388 0.0453640000 408251341 0 402718720 -0.1597429514 -0.1350226253 -0.1180485338 1342 1311867215.1694459915 0.1780506223 0.1622855789 0.2106595784 0.0053282963 0.0475060000 408254597 0 402718720 -0.1593985856 -0.1339292675 -0.1176872849 1343 1311867215.2049460411 0.1780628860 0.1622973267 0.2106595784 0.0053269687 0.0457410000 408257797 0 402718720 -0.1593234539 -0.1315016448 -0.1174112856 1344 1311867215.2369511127 0.1774791330 0.1623086227 0.2106595784 0.0053251979 0.0458520000 408260885 0 402718720 -0.1593191177 -0.1320970953 -0.1167974323 1345 1311867215.2690820694 0.1776044965 0.1623199951 0.2106595784 0.0053232571 0.0458450000 408264085 0 402718720 -0.1594999135 -0.1305543631 -0.1165673509 1346 1311867215.3049569130 0.1776560247 0.1623313888 0.2106595784 0.0053225887 0.0478700000 408267341 0 402718720 -0.1589464694 -0.1290960163 -0.1167464480 1347 1311867215.3369619846 0.1773924977 0.1623425701 0.2106595784 0.0053214540 0.0446200000 408270485 0 402718720 -0.1587063223 -0.1287732869 -0.1166305095 1348 1311867215.3691840172 0.1766379476 0.1623531749 0.2106595784 0.0053227501 0.0466480000 408273629 0 402718720 -0.1580933779 -0.1273771822 -0.1169932336 1349 1311867215.4049520493 0.1768391281 0.1623639132 0.2106595784 0.0053217189 0.0486240000 408276885 0 402718720 -0.1573685408 -0.1250522286 -0.1172969788 1350 1311867215.4370350838 0.1771436483 0.1623748612 0.2106595784 0.0053205391 0.0491760000 408279973 0 402718720 -0.1574427933 -0.1241756454 -0.1174601465 1351 1311867215.4690899849 0.1768139750 0.1623855489 0.2106595784 0.0053209974 0.0504350000 408283173 0 402718720 -0.1564172953 -0.1231610253 -0.1178621650 1352 1311867215.5049800873 0.1766812056 0.1623961226 0.2106595784 0.0053208391 0.0509010000 408286429 0 402718720 -0.1554985642 -0.1207840368 -0.1182809174 1353 1311867215.5371229649 0.1771291494 0.1624070118 0.2106595784 0.0053190638 0.0496640000 408289517 0 402718720 -0.1561104357 -0.1198637187 -0.1182516068 1354 1311867215.5690340996 0.1768441945 0.1624176744 0.2106595784 0.0053187114 0.0451570000 408292717 0 402718720 -0.1559663266 -0.1197378486 -0.1182598174 1355 1311867215.6050848961 0.1768452078 0.1624283220 0.2106595784 0.0053171927 0.0503740000 408295973 0 402718720 -0.1544552743 -0.1163628399 -0.1189098880 1356 1311867215.6370549202 0.1775615960 0.1624394822 0.2106595784 0.0053157121 0.0496110000 408299117 0 402718720 -0.1545481831 -0.1136830598 -0.1182192117 1357 1311867215.6689219475 0.1771920770 0.1624503537 0.2106595784 0.0053139331 0.0505230000 408302261 0 402718720 -0.1554770172 -0.1144955829 -0.1179250032 1358 1311867215.7049510479 0.1770568639 0.1624611096 0.2106595784 0.0053134503 0.0484990000 408305517 0 402718720 -0.1544917077 -0.1122066826 -0.1181198433 1359 1311867215.7388830185 0.1772645861 0.1624720025 0.2106595784 0.0053120945 0.0509220000 408308717 0 402718720 -0.1539489627 -0.1099417880 -0.1178772151 1360 1311867215.7691988945 0.1770272106 0.1624827049 0.2106595784 0.0053105488 0.0514040000 408311693 0 402718720 -0.1541954875 -0.1097579747 -0.1176890433 1361 1311867215.8048830032 0.1764052808 0.1624929346 0.2106595784 0.0053107805 0.0493950000 408314949 0 402718720 -0.1540143490 -0.1094884127 -0.1176962182 1362 1311867215.8373351097 0.1767863184 0.1625034290 0.2106595784 0.0053093701 0.0473590000 408318093 0 402718720 -0.1535556018 -0.1073712930 -0.1179441512 1363 1311867215.8691670895 0.1770292670 0.1625140862 0.2106595784 0.0053076832 0.0457950000 408321293 0 402718720 -0.1536882520 -0.1073938683 -0.1180255413 1364 1311867215.9052760601 0.1767590791 0.1625245298 0.2106595784 0.0053062142 0.0515050000 408324549 0 402718720 -0.1537235826 -0.1078623831 -0.1182229593 1365 1311867215.9370880127 0.1770064086 0.1625351392 0.2106595784 0.0053044502 0.0511100000 408327637 0 402718720 -0.1527815610 -0.1056893691 -0.1187016442 1366 1311867215.9702870846 0.1777072102 0.1625462461 0.2106595784 0.0053025613 0.0494000000 408330837 0 402718720 -0.1532113999 -0.1045188159 -0.1188888475 1367 1311867216.0050790310 0.1774459183 0.1625571457 0.2106595784 0.0053016300 0.0482710000 408334093 0 402718720 -0.1530924141 -0.1045194119 -0.1192460880 1368 1311867216.0369679928 0.1773779094 0.1625679796 0.2106595784 0.0052998095 0.0499730000 408337181 0 402718720 -0.1522737145 -0.1030070037 -0.1196146756 1369 1311867216.0694830418 0.1774117947 0.1625788224 0.2106595784 0.0052991983 0.0500090000 408340381 0 402718720 -0.1521371454 -0.1021078974 -0.1196210980 1370 1311867216.1050429344 0.1773100793 0.1625895751 0.2106595784 0.0052974589 0.0536690000 408343637 0 402718720 -0.1512482613 -0.0997871980 -0.1197297126 1371 1311867216.1392951012 0.1774932593 0.1626004458 0.2106595784 0.0052955898 0.0523360000 408346837 0 402718720 -0.1520143896 -0.0998862684 -0.1194330603 1372 1311867216.1692090034 0.1770480871 0.1626109761 0.2106595784 0.0052942428 0.0510800000 408349869 0 402718720 -0.1508806944 -0.0976719931 -0.1195236146 1373 1311867216.2049610615 0.1764576286 0.1626210611 0.2106595784 0.0052924222 0.0521510000 408353181 0 402718720 -0.1495906860 -0.0957466885 -0.1191138774 1374 1311867216.2370231152 0.1764397919 0.1626311184 0.2106595784 0.0052910087 0.0480210000 408356269 0 402718720 -0.1501909196 -0.0956867933 -0.1181314290 1375 1311867216.2706630230 0.1768971086 0.1626414937 0.2106595784 0.0052905023 0.0536950000 408359525 0 402718720 -0.1506373882 -0.0936350450 -0.1178339645 1376 1311867216.3050479889 0.1769276112 0.1626518760 0.2106595784 0.0052886247 0.0503190000 408362725 0 402718720 -0.1499215811 -0.0914311111 -0.1169659272 1377 1311867216.3395419121 0.1756680459 0.1626613286 0.2106595784 0.0052881435 0.0537460000 408365981 0 402718720 -0.1493551135 -0.0911901817 -0.1164710671 1378 1311867216.3694689274 0.1757736802 0.1626708441 0.2106595784 0.0052862591 0.0545500000 408369013 0 402718720 -0.1493029296 -0.0895976722 -0.1162116006 1379 1311867216.4055120945 0.1750909090 0.1626798506 0.2106595784 0.0052845070 0.0549300000 408372325 0 402718720 -0.1487871706 -0.0889543220 -0.1158333421 1380 1311867216.4373409748 0.1754649878 0.1626891152 0.2106595784 0.0052826247 0.0553370000 408375357 0 402718720 -0.1489659101 -0.0873720199 -0.1153306589 1381 1311867216.4697530270 0.1751671135 0.1626981507 0.2106595784 0.0052807525 0.0548760000 408378613 0 402718720 -0.1481772959 -0.0856702402 -0.1147474200 1382 1311867216.5049800873 0.1741945595 0.1627064694 0.2106595784 0.0052793052 0.0534690000 408381813 0 402718720 -0.1472650021 -0.0853089765 -0.1146954298 1383 1311867216.5372259617 0.1747848541 0.1627152029 0.2106595784 0.0052775972 0.0553270000 408384957 0 402718720 -0.1479702294 -0.0852960423 -0.1139613241 1384 1311867216.5693330765 0.1749975830 0.1627240774 0.2106595784 0.0052758531 0.0517780000 408388101 0 402718720 -0.1477230042 -0.0836103857 -0.1140421852 1385 1311867216.6050319672 0.1747009605 0.1627327250 0.2106595784 0.0052749415 0.0553780000 408391357 0 402718720 -0.1467391849 -0.0827697888 -0.1138976589 1386 1311867216.6373140812 0.1747268587 0.1627413788 0.2106595784 0.0052732592 0.0536730000 408394445 0 402718720 -0.1467633396 -0.0826740190 -0.1136196926 1387 1311867216.6691188812 0.1748273969 0.1627500925 0.2106595784 0.0052717786 0.0553670000 408397645 0 402718720 -0.1464889646 -0.0822997391 -0.1136206910 1388 1311867216.7052359581 0.1747869700 0.1627587646 0.2106595784 0.0052705966 0.0552620000 408400901 0 402718720 -0.1460606903 -0.0802218691 -0.1137538850 1389 1311867216.7372078896 0.1749437004 0.1627675371 0.2106595784 0.0052691992 0.0519160000 408403989 0 402718720 -0.1463320702 -0.0800299272 -0.1137888059 1390 1311867216.7691950798 0.1744886041 0.1627759695 0.2106595784 0.0052675528 0.0520640000 408407189 0 402718720 -0.1458014995 -0.0799788982 -0.1139032468 1391 1311867216.8050019741 0.1743324250 0.1627842775 0.2106595784 0.0052658232 0.0549380000 408410445 0 402718720 -0.1441704780 -0.0784694180 -0.1141569391 1392 1311867216.8379631042 0.1750091761 0.1627930598 0.2106595784 0.0052639419 0.0555240000 408413589 0 402718720 -0.1449812353 -0.0783071294 -0.1139012054 1393 1311867216.8703401089 0.1748334914 0.1628017033 0.2106595784 0.0052629265 0.0503880000 408416733 0 402718720 -0.1449860781 -0.0778382942 -0.1140552014 1394 1311867216.9049589634 0.1741265059 0.1628098273 0.2106595784 0.0052610635 0.0537880000 408419989 0 402718720 -0.1435303986 -0.0765265077 -0.1145765111 1395 1311867216.9374070168 0.1739500910 0.1628178131 0.2106595784 0.0052594865 0.0577960000 408423077 0 402718720 -0.1427446157 -0.0763655454 -0.1147538722 1396 1311867216.9691729546 0.1749203056 0.1628264825 0.2106595784 0.0052577644 0.0521570000 408426221 0 402718720 -0.1436120421 -0.0749847144 -0.1144755557 1397 1311867217.0053269863 0.1744074821 0.1628347724 0.2106595784 0.0052584735 0.0523590000 408429533 0 402718720 -0.1428412348 -0.0740865618 -0.1147169620 1398 1311867217.0373110771 0.1742545068 0.1628429411 0.2106595784 0.0052568887 0.0559010000 408432621 0 402718720 -0.1425895244 -0.0744114146 -0.1144527122 1399 1311867217.0691289902 0.1751152277 0.1628517133 0.2106595784 0.0052568285 0.0557040000 408435765 0 402718720 -0.1426675469 -0.0733628049 -0.1143998876 1400 1311867217.1052579880 0.1750682145 0.1628604393 0.2106595784 0.0052551536 0.0520370000 408439077 0 402718720 -0.1422368437 -0.0723818615 -0.1143933609 1401 1311867217.1370849609 0.1745700985 0.1628687974 0.2106595784 0.0052560120 0.0521980000 408442165 0 402718720 -0.1420932710 -0.0730752274 -0.1143834442 1402 1311867217.1691889763 0.1748008430 0.1628773081 0.2106595784 0.0052551816 0.0536430000 408445365 0 402718720 -0.1415278912 -0.0714763924 -0.1146847457 1403 1311867217.2057919502 0.1751804501 0.1628860773 0.2106595784 0.0052534056 0.0519450000 408448621 0 402718720 -0.1415299624 -0.0702623650 -0.1148186624 1404 1311867217.2371680737 0.1745926142 0.1628944153 0.2106595784 0.0052523732 0.0541130000 408451765 0 402718720 -0.1417195946 -0.0706133619 -0.1150424778 1405 1311867217.2692279816 0.1747249663 0.1629028356 0.2106595784 0.0052509352 0.0524310000 408454909 0 402718720 -0.1413098127 -0.0692043230 -0.1152337193 1406 1311867217.3051640987 0.1747987270 0.1629112964 0.2106595784 0.0052491883 0.0525120000 408458165 0 402718720 -0.1408770382 -0.0675887540 -0.1152880117 1407 1311867217.3374049664 0.1753537804 0.1629201397 0.2106595784 0.0052474855 0.0567100000 408461309 0 402718720 -0.1418619156 -0.0666077882 -0.1150549650 1408 1311867217.3695969582 0.1757788956 0.1629292723 0.2106595784 0.0052458511 0.0538310000 408464453 0 402718720 -0.1422482878 -0.0647518188 -0.1145477369 1409 1311867217.4120450020 0.1738667935 0.1629370349 0.2106595784 0.0052446828 0.0553080000 408467765 0 402718720 -0.1406963319 -0.0645117164 -0.1149679348 1410 1311867217.4372820854 0.1735461354 0.1629445591 0.2106595784 0.0052430129 0.0574910000 408470685 0 402718720 -0.1403690726 -0.0644567832 -0.1146070287 1411 1311867217.4694190025 0.1743355840 0.1629526321 0.2106595784 0.0052422586 0.0511210000 408473829 0 402718720 -0.1408136040 -0.0625032708 -0.1144400984 1412 1311867217.5050320625 0.1740900576 0.1629605198 0.2106595784 0.0052406335 0.0547150000 408477085 0 402718720 -0.1410421580 -0.0621639602 -0.1146532223 1413 1311867217.5370678902 0.1740612686 0.1629683760 0.2106595784 0.0052388466 0.0512230000 408480229 0 402718720 -0.1406403929 -0.0611701421 -0.1146854833 1414 1311867217.5691540241 0.1744166315 0.1629764724 0.2106595784 0.0052370442 0.0529030000 408483373 0 402718720 -0.1404591799 -0.0597128533 -0.1144686788 1415 1311867217.6050539017 0.1750713885 0.1629850200 0.2106595784 0.0052353493 0.0557650000 408486685 0 402718720 -0.1412497610 -0.0587976016 -0.1139545068 1416 1311867217.6370990276 0.1758577079 0.1629941109 0.2106595784 0.0052338074 0.0545850000 408489773 0 402718720 -0.1420945227 -0.0567187406 -0.1137015745 1417 1311867217.6691000462 0.1748677492 0.1630024903 0.2106595784 0.0052325550 0.0540130000 408492973 0 402718720 -0.1411131322 -0.0556074455 -0.1138579175 1418 1311867217.7050631046 0.1736812294 0.1630100211 0.2106595784 0.0052312636 0.0551450000 408496229 0 402718720 -0.1396923810 -0.0558182001 -0.1136407927 1419 1311867217.7371540070 0.1739089936 0.1630177019 0.2106595784 0.0052294669 0.0510870000 408499317 0 402718720 -0.1398463249 -0.0556845143 -0.1134119481 1420 1311867217.7694880962 0.1739136279 0.1630253751 0.2106595784 0.0052278660 0.0527240000 408502517 0 402718720 -0.1393924803 -0.0548239462 -0.1134202555 1421 1311867217.8051838875 0.1735732853 0.1630327980 0.2106595784 0.0052260557 0.0522760000 408505773 0 402718720 -0.1387981176 -0.0546105839 -0.1135485023 1422 1311867217.8372271061 0.1736235172 0.1630402457 0.2106595784 0.0052243190 0.0562640000 408508861 0 402718720 -0.1384288371 -0.0545492657 -0.1133633703 1423 1311867217.8690850735 0.1742383689 0.1630481151 0.2106595784 0.0052228342 0.0543810000 408512061 0 402718720 -0.1383262128 -0.0520609543 -0.1136029512 1424 1311867217.9056351185 0.1739104390 0.1630557431 0.2106595784 0.0052211471 0.0544530000 408515373 0 402718720 -0.1380767822 -0.0511543341 -0.1138482615 1425 1311867217.9372580051 0.1736882478 0.1630632045 0.2106595784 0.0052194090 0.0543450000 408518405 0 402718720 -0.1378889829 -0.0503131039 -0.1137103215 1426 1311867217.9710929394 0.1732040942 0.1630703160 0.2106595784 0.0052176459 0.0510940000 408521605 0 402718720 -0.1368515790 -0.0480387248 -0.1136702746 1427 1311867218.0052239895 0.1728691608 0.1630771827 0.2106595784 0.0052161902 0.0553590000 408524861 0 402718720 -0.1370336413 -0.0479971319 -0.1133678034 1428 1311867218.0371439457 0.1730249077 0.1630841489 0.2106595784 0.0052144088 0.0504050000 408527949 0 402718720 -0.1372516453 -0.0472196005 -0.1129060090 1429 1311867218.0710849762 0.1731386483 0.1630911849 0.2106595784 0.0052126031 0.0510230000 408530981 0 402718720 -0.1369406581 -0.0453083590 -0.1127926111 1430 1311867218.1050980091 0.1731918454 0.1630982483 0.2106595784 0.0052108935 0.0526580000 408534293 0 402718720 -0.1370850354 -0.0440062881 -0.1125623137 1431 1311867218.1371181011 0.1724941581 0.1631048143 0.2106595784 0.0052091163 0.0545120000 408537437 0 402718720 -0.1365251839 -0.0430941805 -0.1124903038 1432 1311867218.1712009907 0.1723275781 0.1631112548 0.2106595784 0.0052084889 0.0543320000 408540581 0 402718720 -0.1363803148 -0.0413682982 -0.1120091155 1433 1311867218.2050349712 0.1725500375 0.1631178415 0.2106595784 0.0052068323 0.0525730000 408543837 0 402718720 -0.1369887590 -0.0405680947 -0.1114982814 1434 1311867218.2372438908 0.1722179800 0.1631241875 0.2106595784 0.0052050646 0.0542190000 408546925 0 402718720 -0.1370648891 -0.0401392281 -0.1111977026 1435 1311867218.2715530396 0.1722867042 0.1631305725 0.2106595784 0.0052034437 0.0507490000 408550125 0 402718720 -0.1372585446 -0.0383906774 -0.1112023890 1436 1311867218.3051331043 0.1720537096 0.1631367864 0.2106595784 0.0052022248 0.0509140000 408553381 0 402718720 -0.1376863271 -0.0386480354 -0.1113780066 1437 1311867218.3373649120 0.1727416515 0.1631434704 0.2106595784 0.0052004503 0.0563010000 408556469 0 402718720 -0.1384201944 -0.0377465077 -0.1112557873 1438 1311867218.3734710217 0.1729095578 0.1631502618 0.2106595784 0.0051992567 0.0542150000 408559725 0 402718720 -0.1383235753 -0.0354760215 -0.1119685769 1439 1311867218.4052689075 0.1726152897 0.1631568393 0.2106595784 0.0051980647 0.0507720000 408562925 0 402718720 -0.1385347396 -0.0353447869 -0.1123018339 1440 1311867218.4372320175 0.1724286675 0.1631632781 0.2106595784 0.0051968204 0.0563070000 408566069 0 402718720 -0.1388076395 -0.0366881266 -0.1122773737 1441 1311867218.4729518890 0.1729564220 0.1631700742 0.2106595784 0.0051953593 0.0566520000 408569213 0 402718720 -0.1389468759 -0.0349528231 -0.1124256551 1442 1311867218.5051169395 0.1732238829 0.1631770463 0.2106595784 0.0051957083 0.0545260000 408572469 0 402718720 -0.1389979869 -0.0322923474 -0.1131179631 1443 1311867218.5372729301 0.1729007661 0.1631837848 0.2106595784 0.0051943585 0.0557000000 408575557 0 402718720 -0.1388163567 -0.0317718908 -0.1128173918 1444 1311867218.5714581013 0.1722397357 0.1631900563 0.2106595784 0.0051926025 0.0528480000 408578757 0 402718720 -0.1383585781 -0.0312119462 -0.1128448918 1445 1311867218.6059319973 0.1724267751 0.1631964485 0.2106595784 0.0051909808 0.0548720000 408582069 0 402718720 -0.1382214725 -0.0293315556 -0.1123929620 1446 1311867218.6372020245 0.1721513867 0.1632026414 0.2106595784 0.0051903741 0.0541420000 408585101 0 402718720 -0.1386913955 -0.0298816077 -0.1119060591 1447 1311867218.6710510254 0.1721197665 0.1632088039 0.2106595784 0.0051900650 0.0542350000 408588301 0 402718720 -0.1386280805 -0.0287401918 -0.1116049141 1448 1311867218.7058999538 0.1717216820 0.1632146829 0.2106595784 0.0051900519 0.0538670000 408591445 0 402718720 -0.1382833272 -0.0278452951 -0.1114372611 1449 1311867218.7378489971 0.1713611335 0.1632203050 0.2106595784 0.0051900924 0.0530230000 408594589 0 402718720 -0.1383453608 -0.0279787928 -0.1105762422 1450 1311867218.7715849876 0.1722321957 0.1632265201 0.2106595784 0.0051904345 0.0516120000 408597733 0 402718720 -0.1390206665 -0.0279180817 -0.1099595428 1451 1311867218.8052420616 0.1724290252 0.1632328623 0.2106595784 0.0051899281 0.0537480000 408601045 0 402718720 -0.1389708370 -0.0255868156 -0.1096450537 1452 1311867218.8379960060 0.1719010472 0.1632388321 0.2106595784 0.0051885096 0.0522640000 408604133 0 402718720 -0.1391577274 -0.0260317642 -0.1091266796 1453 1311867218.8727269173 0.1723457873 0.1632450998 0.2106595784 0.0051938706 0.0508680000 408607277 0 402718720 -0.1399250180 -0.0263206232 -0.1085729003 1454 1311867218.9054861069 0.1726384610 0.1632515602 0.2106595784 0.0051957361 0.0522680000 408610421 0 402718720 -0.1404768527 -0.0233239792 -0.1082952172 1455 1311867218.9372200966 0.1711437404 0.1632569844 0.2106595784 0.0051961304 0.0553640000 408613621 0 402718720 -0.1400719434 -0.0242970604 -0.1082087010 1456 1311867218.9731609821 0.1711925119 0.1632624346 0.2106595784 0.0051946809 0.0543090000 408616821 0 402718720 -0.1401910335 -0.0232757926 -0.1079309955 1457 1311867219.0051829815 0.1710897833 0.1632678068 0.2106595784 0.0051929148 0.0515900000 408620077 0 402718720 -0.1399939805 -0.0220978577 -0.1075144261 1458 1311867219.0371239185 0.1708716005 0.1632730221 0.2106595784 0.0051914010 0.0512710000 408623221 0 402718720 -0.1401851028 -0.0213454012 -0.1071915850 1459 1311867219.0738370419 0.1708987951 0.1632782488 0.2106595784 0.0051942978 0.2407970000 420941405 0 402718720 -0.1407252699 -0.0208442099 -0.1067300290 1460 1311867219.1050798893 0.1745654494 0.1632859797 0.2106595784 0.0052056374 0.0223940000 424603757 0 402718720 -0.1373833418 -0.0071814801 -0.1053728536 1461 1311867219.1383259296 0.1744933426 0.1632936507 0.2106595784 0.0052038683 0.0246360000 427799093 0 402718720 -0.1372226477 -0.0061374512 -0.1051956490 1462 1311867219.1708409786 0.1744660586 0.1633012926 0.2106595784 0.0052020968 0.0314570000 427802237 0 402718720 -0.1368821263 -0.0053367126 -0.1046224833 1463 1311867219.2052450180 0.1749473065 0.1633092530 0.2106595784 0.0052011454 0.0398890000 427805549 0 402718720 -0.1377232224 -0.0042500915 -0.1043514535 1464 1311867219.2391340733 0.1746929884 0.1633170288 0.2106595784 0.0052026480 0.0330590000 427808693 0 402718720 -0.1373805255 -0.0033485533 -0.1036977023 1465 1311867219.2709019184 0.1744448692 0.1633246245 0.2106595784 0.0052012281 0.0335090000 427811781 0 402718720 -0.1368141174 -0.0027786538 -0.1032502130 1466 1311867219.3052430153 0.1736087650 0.1633316397 0.2106595784 0.0052061433 0.0323740000 427815037 0 402718720 -0.1360999793 -0.0029289788 -0.1032277718 1467 1311867219.3401548862 0.1737902761 0.1633387689 0.2106595784 0.0052049217 0.0313330000 427818181 0 402718720 -0.1354351342 -0.0011509515 -0.1032943130 1468 1311867219.3714950085 0.1745295823 0.1633463921 0.2106595784 0.0052034795 0.0310360000 427821269 0 402718720 -0.1356942356 -0.0005718188 -0.1026273593 1469 1311867219.4051969051 0.1738914102 0.1633535705 0.2106595784 0.0052019951 0.0296490000 427824581 0 402718720 -0.1353305131 -0.0005120743 -0.1026011109 1470 1311867219.4394791126 0.1730810255 0.1633601878 0.2106595784 0.0052004045 0.0296460000 427827725 0 402718720 -0.1341670752 0.0004604708 -0.1028562188 1471 1311867219.4717090130 0.1729127616 0.1633666817 0.2106595784 0.0051987415 0.0329080000 427830869 0 402718720 -0.1336308569 0.0016429527 -0.1026949063 1472 1311867219.5051560402 0.1734077781 0.1633735031 0.2106595784 0.0051971087 0.0302940000 427834125 0 402718720 -0.1342965961 0.0017208442 -0.1020002812 1473 1311867219.5391800404 0.1735754609 0.1633804291 0.2106595784 0.0051961696 0.0286400000 427837213 0 402718720 -0.1339887232 0.0031449145 -0.1019862667 1474 1311867219.5743329525 0.1734211147 0.1633872409 0.2106595784 0.0051947987 0.0336180000 427840469 0 402718720 -0.1333929002 0.0040801778 -0.1016791463 1475 1311867219.6086039543 0.1721827835 0.1633932040 0.2106595784 0.0051933904 0.0342080000 427843613 0 402718720 -0.1322571933 0.0038398532 -0.1017360762 1476 1311867219.6423599720 0.1735587269 0.1634000912 0.2106595784 0.0052056539 0.0309460000 427846813 0 402718720 -0.1327608675 0.0051192236 -0.1014038697 1477 1311867219.6711030006 0.1731252968 0.1634066757 0.2106595784 0.0052236990 0.0286580000 427849845 0 402718720 -0.1324467510 0.0047825007 -0.1015444323 1478 1311867219.7052869797 0.1726669967 0.1634129411 0.2106595784 0.0052220231 0.0309620000 427853101 0 402718720 -0.1314571947 0.0043580658 -0.1016208604 1479 1311867219.7394990921 0.1728943586 0.1634193518 0.2106595784 0.0052213487 0.0337120000 427856245 0 402718720 -0.1310428083 0.0060116700 -0.1020960733 1480 1311867219.7739629745 0.1735144705 0.1634261728 0.2106595784 0.0052236237 0.0334110000 427859445 0 402718720 -0.1310024112 0.0067076222 -0.1018664315 1481 1311867219.8051769733 0.1739344895 0.1634332682 0.2106595784 0.0052232207 0.0308990000 427862645 0 402718720 -0.1310337782 0.0067683952 -0.1020091996 1482 1311867219.8397209644 0.1733811051 0.1634399807 0.2106595784 0.0052221568 0.0293040000 427865845 0 402718720 -0.1294204742 0.0085697286 -0.1022736132 1483 1311867219.8753080368 0.1734981835 0.1634467630 0.2106595784 0.0052329644 0.0329210000 427869045 0 402718720 -0.1291967928 0.0088232327 -0.1020046622 1484 1311867219.9108390808 0.1739735454 0.1634538565 0.2106595784 0.0052505991 0.0329720000 427872245 0 402718720 -0.1295750737 0.0096990149 -0.1017991379 1485 1311867219.9417629242 0.1736012846 0.1634606898 0.2106595784 0.0052523373 0.0304280000 427875333 0 402718720 -0.1291342527 0.0107701039 -0.1017844826 1486 1311867219.9732189178 0.1727088839 0.1634669134 0.2106595784 0.0052515798 0.0306190000 427878365 0 402718720 -0.1276263148 0.0109882625 -0.1017028242 1487 1311867220.0068678856 0.1733075231 0.1634735311 0.2106595784 0.0052536328 0.0332300000 427881677 0 402718720 -0.1281612515 0.0117023988 -0.1016222760 1488 1311867220.0421938896 0.1736280024 0.1634803554 0.2106595784 0.0052522205 0.0303160000 427884765 0 402718720 -0.1286308765 0.0130577656 -0.1013254970 1489 1311867220.0743649006 0.1738419086 0.1634873141 0.2106595784 0.0052507109 0.0308140000 427887965 0 402718720 -0.1282056272 0.0140211955 -0.1012351662 1490 1311867220.1052761078 0.1730969995 0.1634937636 0.2106595784 0.0052562122 0.0320160000 427891165 0 402718720 -0.1273829043 0.0150012635 -0.1013145745 1491 1311867220.1420929432 0.1735533476 0.1635005104 0.2106595784 0.0052546726 0.0319710000 427894309 0 402718720 -0.1277257651 0.0162184052 -0.1008316651 1492 1311867220.1714088917 0.1732737720 0.1635070609 0.2106595784 0.0052603076 0.0326840000 427897453 0 402718720 -0.1280058175 0.0170721691 -0.1006017253 1493 1311867220.2061769962 0.1736951470 0.1635138848 0.2106595784 0.0052647743 0.0323490000 427900709 0 402718720 -0.1282512844 0.0178014114 -0.1003965959 1494 1311867220.2421929836 0.1729704291 0.1635202145 0.2106595784 0.0052669386 0.0309300000 427903965 0 402718720 -0.1275560260 0.0180248618 -0.1005725116 1495 1311867220.2741110325 0.1734092236 0.1635268292 0.2106595784 0.0052655258 0.0331460000 427907053 0 402718720 -0.1278219074 0.0192604214 -0.1004633978 1496 1311867220.3064489365 0.1739019901 0.1635337644 0.2106595784 0.0052764257 0.0331210000 427910197 0 402718720 -0.1282486171 0.0200581066 -0.1003584936 1497 1311867220.3420529366 0.1730684042 0.1635401336 0.2106595784 0.0052792708 0.0300050000 427913341 0 402718720 -0.1276954710 0.0205340032 -0.1005938575 1498 1311867220.3714709282 0.1723034680 0.1635459836 0.2106595784 0.0053270879 0.0338340000 427916429 0 402718720 -0.1273370087 0.0212951414 -0.1004924104 1499 1311867220.4063699245 0.1730813533 0.1635523448 0.2106595784 0.0053266969 0.0340920000 427919741 0 402718720 -0.1276798248 0.0235187411 -0.1002587751 1500 1311867220.4408769608 0.1728752255 0.1635585600 0.2106595784 0.0053256108 0.0327110000 427922941 0 402718720 -0.1279401630 0.0245740470 -0.0998918489 1501 1311867220.4728679657 0.1724164486 0.1635644614 0.2106595784 0.0053276023 0.0338890000 427926029 0 402718720 -0.1273974627 0.0250309594 -0.0998215824 1502 1311867220.5090799332 0.1728715748 0.1635706578 0.2106595784 0.0053260839 0.0340740000 427929341 0 402718720 -0.1273614615 0.0256218668 -0.0996163115 1503 1311867220.5419750214 0.1727332622 0.1635767541 0.2106595784 0.0053243697 0.0326060000 427932429 0 402718720 -0.1272655725 0.0264482014 -0.0996046439 1504 1311867220.5716209412 0.1725032479 0.1635826892 0.2106595784 0.0053233504 0.0328040000 427935461 0 402718720 -0.1271108687 0.0261130705 -0.0997526348 1505 1311867220.6104190350 0.1728571057 0.1635888516 0.2106595784 0.0053233079 0.0332540000 427938773 0 402718720 -0.1269392371 0.0271109305 -0.0999748483 1506 1311867220.6396670341 0.1728637964 0.1635950103 0.2106595784 0.0053220039 0.0308510000 427941805 0 402718720 -0.1264741868 0.0275370702 -0.1003095582 1507 1311867220.6712789536 0.1724394411 0.1636008792 0.2106595784 0.0053204242 0.0326340000 427944949 0 402718720 -0.1256914288 0.0278323703 -0.1008726582 1508 1311867220.7073268890 0.1734401882 0.1636074039 0.2106595784 0.0053221281 0.0330940000 427948205 0 402718720 -0.1256212443 0.0283282567 -0.1012224853 1509 1311867220.7393379211 0.1730850339 0.1636136847 0.2106595784 0.0053217591 0.0318620000 427951349 0 402718720 -0.1252523214 0.0287712701 -0.1015427187 1510 1311867220.7719140053 0.1731494069 0.1636199997 0.2106595784 0.0053207578 0.0315340000 427954437 0 402718720 -0.1242588460 0.0299280398 -0.1018901095 1511 1311867220.8097269535 0.1736746132 0.1636266540 0.2106595784 0.0053209920 0.0347230000 427957805 0 402718720 -0.1242817268 0.0301136896 -0.1020473912 1512 1311867220.8414170742 0.1737651378 0.1636333593 0.2106595784 0.0053201949 0.0339770000 427960893 0 402718720 -0.1233006418 0.0319758207 -0.1023535430 1513 1311867220.8712399006 0.1736828536 0.1636400014 0.2106595784 0.0053238839 0.0335270000 427964037 0 402718720 -0.1226268709 0.0326049402 -0.1022302955 1514 1311867220.9075899124 0.1742111892 0.1636469837 0.2106595784 0.0053277454 0.0332430000 427967293 0 402718720 -0.1230025738 0.0326234214 -0.1020408794 1515 1311867220.9392800331 0.1740701795 0.1636538637 0.2106595784 0.0053260209 0.0338170000 427970437 0 402718720 -0.1224308461 0.0329331867 -0.1020511463 1516 1311867220.9713129997 0.1736906022 0.1636604843 0.2106595784 0.0053378663 0.0351450000 427973581 0 402718720 -0.1213074625 0.0337683745 -0.1020674482 1517 1311867221.0089550018 0.1737820059 0.1636671563 0.2106595784 0.0053362289 0.0346460000 427976893 0 402718720 -0.1210849360 0.0343565494 -0.1018055007 1518 1311867221.0392880440 0.1744236946 0.1636742423 0.2106595784 0.0053346041 0.0333340000 427979981 0 402718720 -0.1216785982 0.0341418348 -0.1014423370 1519 1311867221.0720989704 0.1739673018 0.1636810185 0.2106595784 0.0053328565 0.0349900000 427983181 0 402718720 -0.1204741001 0.0356088430 -0.1014899537 1520 1311867221.1077499390 0.1736853272 0.1636876003 0.2106595784 0.0053315484 0.0355650000 427986381 0 402718720 -0.1196972728 0.0368300900 -0.1013426930 1521 1311867221.1397659779 0.1738246232 0.1636942650 0.2106595784 0.0053304947 0.0317680000 427989581 0 402718720 -0.1194208562 0.0361721031 -0.1013000160 1522 1311867221.1716840267 0.1747967899 0.1637015597 0.2106595784 0.0053318371 0.0361380000 427992613 0 402718720 -0.1192965508 0.0377265066 -0.1010149494 1523 1311867221.2083969116 0.1746588200 0.1637087542 0.2106595784 0.0053315240 0.0355390000 427995925 0 402718720 -0.1183674186 0.0398879573 -0.1010908261 1524 1311867221.2397499084 0.1741088480 0.1637155784 0.2106595784 0.0053310189 0.0343290000 427999013 0 402718720 -0.1177251115 0.0392994992 -0.1010035574 1525 1311867221.2719800472 0.1745313853 0.1637226708 0.2106595784 0.0053294180 0.0365620000 428002213 0 402718720 -0.1177367195 0.0400910713 -0.1010524184 1526 1311867221.3075759411 0.1745644361 0.1637297755 0.2106595784 0.0053289875 0.0360620000 428005413 0 402718720 -0.1166115254 0.0423931815 -0.1014641449 1527 1311867221.3393330574 0.1742056608 0.1637366359 0.2106595784 0.0053273654 0.0356860000 428008557 0 402718720 -0.1157904342 0.0424030721 -0.1017593965 1528 1311867221.3714160919 0.1744086891 0.1637436202 0.2106595784 0.0053258004 0.0349490000 428011757 0 402718720 -0.1157255247 0.0423731320 -0.1021765545 1529 1311867221.4071469307 0.1741743535 0.1637504422 0.2106595784 0.0053241806 0.0370260000 428014901 0 402718720 -0.1140398160 0.0452100635 -0.1030065343 1530 1311867221.4400060177 0.1732888520 0.1637566764 0.2106595784 0.0053230508 0.0349340000 428018101 0 402718720 -0.1122673750 0.0459930263 -0.1036298349 1531 1311867221.4712278843 0.1737967432 0.1637632343 0.2106595784 0.0053214189 0.0358750000 428021189 0 402718720 -0.1121259108 0.0473848656 -0.1039054021 1532 1311867221.5081529617 0.1737699360 0.1637697661 0.2106595784 0.0053201129 0.0379430000 428024445 0 402718720 -0.1121603772 0.0476104878 -0.1043374017 1533 1311867221.5396749973 0.1742091328 0.1637765758 0.2106595784 0.0053184846 0.0372760000 428027645 0 402718720 -0.1121157408 0.0495074280 -0.1049086675 1534 1311867221.5712718964 0.1742303669 0.1637833906 0.2106595784 0.0053183997 0.0365430000 428030789 0 402718720 -0.1121328622 0.0503979176 -0.1055053473 1535 1311867221.6071679592 0.1740511954 0.1637900797 0.2106595784 0.0053169053 0.0381950000 428033989 0 402718720 -0.1122877225 0.0505523123 -0.1064017564 1536 1311867221.6403698921 0.1745501906 0.1637970850 0.2106595784 0.0053163614 0.0368250000 428037245 0 402718720 -0.1126186699 0.0538311116 -0.1072770655 1537 1311867221.6694529057 0.1752583236 0.1638045418 0.2106595784 0.0053160025 0.0362550000 428040277 0 402718720 -0.1134892851 0.0551070794 -0.1078876778 1538 1311867221.7071709633 0.1752969176 0.1638120141 0.2106595784 0.0053217960 0.0386320000 428043533 0 402718720 -0.1138990968 0.0568844378 -0.1085863784 1539 1311867221.7423820496 0.1751520634 0.1638193826 0.2106595784 0.0053203204 0.0379490000 428046789 0 402718720 -0.1140265018 0.0588227659 -0.1095138565 1540 1311867221.7693860531 0.1754787266 0.1638269536 0.2106595784 0.0053210734 0.0375780000 428049821 0 402718720 -0.1142415777 0.0614948235 -0.1102311611 1541 1311867221.8074219227 0.1761904955 0.1638349767 0.2106595784 0.0053231233 0.0380360000 428053021 0 402718720 -0.1152854711 0.0624071062 -0.1108499169 1542 1311867221.8396449089 0.1754943132 0.1638425378 0.2106595784 0.0053279190 0.0343720000 428056221 0 402718720 -0.1151398271 0.0618176945 -0.1121672839 1543 1311867221.8695800304 0.1759346128 0.1638503746 0.2106595784 0.0053303070 0.0371290000 428059309 0 402718720 -0.1152756512 0.0634807646 -0.1134145632 1544 1311867221.9077389240 0.1768590957 0.1638587999 0.2106595784 0.0053324350 0.0371640000 428062621 0 402718720 -0.1160212457 0.0651541576 -0.1144052669 1545 1311867221.9423611164 0.1768693477 0.1638672210 0.2106595784 0.0053324800 0.0364450000 428065821 0 402718720 -0.1166987419 0.0657706931 -0.1152646318 1546 1311867221.9695780277 0.1771980077 0.1638758437 0.2106595784 0.0053311657 0.0376050000 428068853 0 402718720 -0.1168392375 0.0680293292 -0.1161603481 1547 1311867222.0090060234 0.1770886183 0.1638843846 0.2106595784 0.0053305517 0.0389050000 428072277 0 402718720 -0.1169094220 0.0689026564 -0.1167508513 1548 1311867222.0428760052 0.1776918024 0.1638933041 0.2106595784 0.0053307171 0.0385630000 428075309 0 402718720 -0.1180969849 0.0693024620 -0.1171204522 1549 1311867222.0693619251 0.1777925044 0.1639022772 0.2106595784 0.0053291176 0.0376230000 428078173 0 402718720 -0.1182927936 0.0718263537 -0.1175173670 1550 1311867222.1110939980 0.1774550229 0.1639110209 0.2106595784 0.0053306658 0.0378420000 428081597 0 402718720 -0.1180317476 0.0743971318 -0.1176262423 1551 1311867222.1406829357 0.1769890785 0.1639194529 0.2106595784 0.0053503934 0.0383020000 428084629 0 402718720 -0.1187255606 0.0752091259 -0.1173731312 1552 1311867222.1693990231 0.1774998307 0.1639282031 0.2106595784 0.0053629803 0.0407710000 428087717 0 402718720 -0.1192627326 0.0762583464 -0.1172438711 1553 1311867222.2081599236 0.1772278547 0.1639367670 0.2106595784 0.0053661294 0.0397220000 428091029 0 402718720 -0.1190496981 0.0799604133 -0.1168176606 1554 1311867222.2400729656 0.1767421067 0.1639450072 0.2106595784 0.0053695577 0.0384230000 428094173 0 402718720 -0.1193150654 0.0806073546 -0.1162343025 1555 1311867222.2696809769 0.1767175794 0.1639532211 0.2106595784 0.0053684272 0.0395670000 428097261 0 402718720 -0.1206608191 0.0789172277 -0.1151884571 1556 1311867222.3077359200 0.1756015569 0.1639607072 0.2106595784 0.0053678459 0.0399230000 428100573 0 402718720 -0.1195600331 0.0822142288 -0.1146336794 1557 1311867222.3396298885 0.1741898507 0.1639672769 0.2106595784 0.0053713805 0.0394570000 428103717 0 402718720 -0.1196611822 0.0803636760 -0.1142593250 1558 1311867222.3694961071 0.1755382568 0.1639747038 0.2106595784 0.0053778867 0.0396790000 428106805 0 402718720 -0.1206144616 0.0826427415 -0.1134840623 1559 1311867222.4101901054 0.1755667329 0.1639821393 0.2106595784 0.0053773199 0.0372510000 428110173 0 402718720 -0.1208247840 0.0860533714 -0.1126822084 1560 1311867222.4436359406 0.1750108302 0.1639892090 0.2106595784 0.0053762793 0.0405550000 428113317 0 402718720 -0.1202471480 0.0882270560 -0.1119301766 1561 1311867222.4694089890 0.1745680422 0.1639959859 0.2106595784 0.0053761122 0.0399430000 428116293 0 402718720 -0.1205799803 0.0890099257 -0.1111986563 1562 1311867222.5086879730 0.1744367033 0.1640026701 0.2106595784 0.0053769097 0.0439320000 428119661 0 402718720 -0.1201193556 0.0917114466 -0.1102180332 1563 1311867222.5401670933 0.1738262922 0.1640089553 0.2106595784 0.0053757305 0.2426840000 440438941 0 402718720 -0.1197499782 0.0901845545 -0.1090198085 1564 1311867222.5696709156 0.1723769456 0.1640143056 0.2106595784 0.0053961845 0.0226740000 444104549 0 402718720 -0.1226116642 0.0813306794 -0.1102636606 1565 1311867222.6084239483 0.1712353826 0.1640189197 0.2106595784 0.0053952656 0.0232590000 447300053 0 402718720 -0.1218279153 0.0824798495 -0.1099557579 1566 1311867222.6432960033 0.1703176647 0.1640229419 0.2106595784 0.0053950502 0.0332600000 447303253 0 402718720 -0.1208684519 0.0834314078 -0.1097320691 1567 1311867222.6695740223 0.1710954309 0.1640274553 0.2106595784 0.0053965106 0.0263960000 447306229 0 402718720 -0.1215197071 0.0835755467 -0.1090105549 1568 1311867222.7080109119 0.1708776504 0.1640318241 0.2106595784 0.0053975252 0.0348100000 447309541 0 402718720 -0.1212546602 0.0852065012 -0.1083503887 1569 1311867222.7399919033 0.1709497273 0.1640362332 0.2106595784 0.0053995064 0.0319880000 447312741 0 402718720 -0.1210590154 0.0862730145 -0.1073831990 1570 1311867222.7694571018 0.1708955467 0.1640406022 0.2106595784 0.0054003193 0.0345270000 447315829 0 402718720 -0.1209783405 0.0861866325 -0.1068166718 1571 1311867222.8093209267 0.1707996577 0.1640449046 0.2106595784 0.0053996198 0.0314830000 447319029 0 402718720 -0.1209361702 0.0868430957 -0.1063884646 1572 1311867222.8402578831 0.1702443212 0.1640488482 0.2106595784 0.0053980706 0.0319840000 447322117 0 402718720 -0.1202812642 0.0882261768 -0.1060753092 1573 1311867222.8694989681 0.1703724861 0.1640528683 0.2106595784 0.0053982190 0.0312570000 447325149 0 402718720 -0.1207595617 0.0881695375 -0.1055392846 1574 1311867222.9082319736 0.1700410694 0.1640566728 0.2106595784 0.0053965357 0.0308700000 447328461 0 402718720 -0.1206166893 0.0887254700 -0.1051890180 1575 1311867222.9375910759 0.1699709296 0.1640604279 0.2106595784 0.0053955902 0.0346310000 447331493 0 402718720 -0.1202673912 0.0897605047 -0.1048039943 1576 1311867222.9694879055 0.1699214429 0.1640641468 0.2106595784 0.0053940043 0.0316820000 447334693 0 402718720 -0.1209389418 0.0897872448 -0.1043732762 1577 1311867223.0078239441 0.1696636826 0.1640676975 0.2106595784 0.0053961912 0.0313100000 447338005 0 402718720 -0.1210662872 0.0896729007 -0.1040502265 1578 1311867223.0374948978 0.1689227074 0.1640707742 0.2106595784 0.0053980300 0.0338250000 447341093 0 402718720 -0.1206448004 0.0908278227 -0.1037291661 1579 1311867223.0694169998 0.1693330705 0.1640741069 0.2106595784 0.0054029575 0.0319330000 447344237 0 402718720 -0.1211651042 0.0912613198 -0.1033164859 1580 1311867223.1094119549 0.1691086590 0.1640772933 0.2106595784 0.0054012797 0.0311470000 447347605 0 402718720 -0.1216689572 0.0916632563 -0.1030480936 1581 1311867223.1381359100 0.1693592668 0.1640806342 0.2106595784 0.0053996610 0.0295880000 447350637 0 402718720 -0.1215255186 0.0932281762 -0.1027911752 1582 1311867223.1758520603 0.1684895456 0.1640834211 0.2106595784 0.0054012563 0.0312290000 447353949 0 402718720 -0.1215720177 0.0940807387 -0.1024761945 1583 1311867223.2080020905 0.1689393222 0.1640864887 0.2106595784 0.0053996345 0.0299760000 447357093 0 402718720 -0.1230182797 0.0943641514 -0.1019032821 1584 1311867223.2374629974 0.1689335555 0.1640895487 0.2106595784 0.0054019140 0.0309810000 447360125 0 402718720 -0.1235730648 0.0959701687 -0.1013291180 1585 1311867223.2779359818 0.1678445488 0.1640919178 0.2106595784 0.0054015372 0.0294400000 447363605 0 402718720 -0.1227311566 0.0977793038 -0.1010973006 1586 1311867223.3085889816 0.1674236506 0.1640940185 0.2106595784 0.0054002469 0.0295340000 447366637 0 402718720 -0.1228306368 0.0985432789 -0.1007399037 1587 1311867223.3376250267 0.1680745631 0.1640965267 0.2106595784 0.0054004322 0.0341380000 447369669 0 402718720 -0.1237966195 0.1003812030 -0.1002261788 1588 1311867223.3754320145 0.1679244190 0.1640989372 0.2106595784 0.0053992003 0.0301220000 447373037 0 402718720 -0.1245584637 0.1013194770 -0.0996641889 1589 1311867223.4073610306 0.1677466184 0.1641012328 0.2106595784 0.0054005696 0.0303320000 447376069 0 402718720 -0.1248533502 0.1017250419 -0.0994990394 1590 1311867223.4375619888 0.1670449376 0.1641030842 0.2106595784 0.0054007649 0.0307760000 447379213 0 402718720 -0.1250238866 0.1022423804 -0.0995404348 1591 1311867223.4758250713 0.1673968583 0.1641051544 0.2106595784 0.0054045052 0.0297010000 447382525 0 402718720 -0.1254922897 0.1036298275 -0.0996757299 1592 1311867223.5077319145 0.1675989181 0.1641073490 0.2106595784 0.0054032235 0.0301080000 447385669 0 402718720 -0.1261883229 0.1047807038 -0.0998842642 1593 1311867223.5375499725 0.1674912572 0.1641094733 0.2106595784 0.0054016708 0.0282700000 447388701 0 402718720 -0.1267739236 0.1047606468 -0.1000569537 1594 1311867223.5759189129 0.1676551998 0.1641116977 0.2106595784 0.0054002072 0.0291000000 447392125 0 402718720 -0.1271986067 0.1064605862 -0.1003554612 1595 1311867223.6077899933 0.1675801277 0.1641138722 0.2106595784 0.0053985302 0.0288880000 447395157 0 402718720 -0.1275015175 0.1073791608 -0.1006504968 1596 1311867223.6374490261 0.1674634814 0.1641159710 0.2106595784 0.0053996896 0.0305980000 447398245 0 402718720 -0.1281514913 0.1071338877 -0.1008904874 1597 1311867223.6753818989 0.1674304456 0.1641180464 0.2106595784 0.0053981509 0.0288260000 447401557 0 402718720 -0.1283463985 0.1089345962 -0.1013688073 1598 1311867223.7088389397 0.1670485437 0.1641198803 0.2106595784 0.0053965152 0.0286340000 447404757 0 402718720 -0.1284859478 0.1107595563 -0.1018254533 1599 1311867223.7375938892 0.1674925685 0.1641219895 0.2106595784 0.0053950314 0.0301390000 447407845 0 402718720 -0.1290412545 0.1116385907 -0.1018727943 1600 1311867223.7760660648 0.1674685478 0.1641240811 0.2106595784 0.0053980999 0.0289320000 447411157 0 402718720 -0.1287901103 0.1133202985 -0.1021103859 1601 1311867223.8077499866 0.1673571914 0.1641261006 0.2106595784 0.0053964625 0.0290980000 447414245 0 402718720 -0.1285624653 0.1152690798 -0.1024613976 1602 1311867223.8374810219 0.1684451401 0.1641287966 0.2106595784 0.0053980799 0.0296540000 447417333 0 402718720 -0.1292695105 0.1158445776 -0.1022666469 1603 1311867223.8760769367 0.1682137102 0.1641313449 0.2106595784 0.0053971716 0.0288210000 447420701 0 402718720 -0.1287352145 0.1169055477 -0.1026520580 1604 1311867223.9078130722 0.1682953238 0.1641339409 0.2106595784 0.0053955853 0.0291090000 447423789 0 402718720 -0.1284728795 0.1190905645 -0.1030874252 1605 1311867223.9389259815 0.1684565097 0.1641366341 0.2106595784 0.0053940306 0.0303740000 447426933 0 402718720 -0.1283323765 0.1196445227 -0.1031189859 1606 1311867223.9760470390 0.1683651954 0.1641392670 0.2106595784 0.0053952718 0.0315800000 447430245 0 402718720 -0.1279199868 0.1209666282 -0.1035138592 1607 1311867224.0092129707 0.1689353883 0.1641422516 0.2106595784 0.0053970497 0.0295240000 447433389 0 402718720 -0.1278271228 0.1220704019 -0.1039023921 1608 1311867224.0375959873 0.1689955443 0.1641452698 0.2106595784 0.0053954832 0.0308110000 447436421 0 402718720 -0.1274340898 0.1235665828 -0.1042698100 1609 1311867224.0761330128 0.1691800356 0.1641483989 0.2106595784 0.0053942153 0.0300640000 447439789 0 402718720 -0.1271383613 0.1236461401 -0.1043763831 1610 1311867224.1081280708 0.1694849283 0.1641517135 0.2106595784 0.0053938335 0.0323280000 447442933 0 402718720 -0.1276406199 0.1221208870 -0.1054173484 1611 1311867224.1375260353 0.1692852527 0.1641549001 0.2106595784 0.0053944364 0.0333920000 447446021 0 402718720 -0.1268576980 0.1246064901 -0.1059869975 1612 1311867224.1768879890 0.1701669693 0.1641586297 0.2106595784 0.0054000528 0.0333270000 447449333 0 402718720 -0.1261252463 0.1283865720 -0.1060146019 1613 1311867224.2055120468 0.1701534241 0.1641623462 0.2106595784 0.0053984481 0.0308970000 447452421 0 402718720 -0.1256730407 0.1296893209 -0.1062076911 1614 1311867224.2377920151 0.1699890345 0.1641659563 0.2106595784 0.0053969303 0.0330610000 447455341 0 402718720 -0.1250492781 0.1315851659 -0.1070239246 1615 1311867224.2768549919 0.1702280343 0.1641697099 0.2106595784 0.0053974192 0.0312790000 447458653 0 402718720 -0.1245510280 0.1334328651 -0.1076304093 1616 1311867224.3054649830 0.1708680987 0.1641738549 0.2106595784 0.0053964387 0.0308720000 447461741 0 402718720 -0.1248702183 0.1335099936 -0.1078615412 1617 1311867224.3375461102 0.1710235924 0.1641780910 0.2106595784 0.0053949636 0.0349000000 447464941 0 402718720 -0.1247920096 0.1351571977 -0.1084106341 1618 1311867224.3769130707 0.1708353162 0.1641822055 0.2106595784 0.0053936215 0.0345540000 447468197 0 402718720 -0.1244973913 0.1368018985 -0.1091852114 1619 1311867224.4056029320 0.1713996679 0.1641866635 0.2106595784 0.0053944168 0.0328060000 447471285 0 402718720 -0.1247979179 0.1369834393 -0.1094834208 1620 1311867224.4375159740 0.1715785265 0.1641912264 0.2106595784 0.0053936211 0.0344640000 447474429 0 402718720 -0.1247943267 0.1382552534 -0.1104343385 1621 1311867224.4776859283 0.1716874093 0.1641958508 0.2106595784 0.0053920039 0.0350760000 447477797 0 402718720 -0.1246546805 0.1398890764 -0.1108762622 1622 1311867224.5056600571 0.1720018983 0.1642006634 0.2106595784 0.0053908055 0.0343570000 447480829 0 402718720 -0.1249851808 0.1392275244 -0.1113856584 1623 1311867224.5378088951 0.1719804853 0.1642054569 0.2106595784 0.0053899040 0.0347530000 447483917 0 402718720 -0.1246997118 0.1397923380 -0.1124484167 1624 1311867224.5859119892 0.1725154072 0.1642105738 0.2106595784 0.0053966561 0.0346700000 447487621 0 402718720 -0.1249274537 0.1442050785 -0.1132500470 1625 1311867224.6055970192 0.1725630611 0.1642157138 0.2106595784 0.0053953204 0.0314430000 447490373 0 402718720 -0.1250615716 0.1448354721 -0.1134561971 1626 1311867224.6378059387 0.1726313829 0.1642208895 0.2106595784 0.0053937058 0.0342200000 447493461 0 402718720 -0.1254132241 0.1447737068 -0.1135277450 1627 1311867224.6785008907 0.1721322238 0.1642257520 0.2106595784 0.0053930376 0.0351660000 447496829 0 402718720 -0.1253456026 0.1465958804 -0.1139917299 1628 1311867224.7054929733 0.1722027808 0.1642306519 0.2106595784 0.0053934872 0.0335310000 447499917 0 402718720 -0.1252570450 0.1485939771 -0.1139852107 1629 1311867224.7376120090 0.1729248017 0.1642359890 0.2106595784 0.0053926379 0.0359390000 447503005 0 402718720 -0.1259678006 0.1488385946 -0.1136269569 1630 1311867224.7866261005 0.1728819311 0.1642412933 0.2106595784 0.0053919575 0.0367250000 447506653 0 402718720 -0.1261976510 0.1499033570 -0.1136537045 1631 1311867224.8056540489 0.1723805070 0.1642462836 0.2106595784 0.0053923506 0.0339970000 447509461 0 402718720 -0.1257017404 0.1523575634 -0.1140069589 1632 1311867224.8378241062 0.1719759554 0.1642510199 0.2106595784 0.0054281920 0.0345010000 447512493 0 402718720 -0.1256927401 0.1535722613 -0.1136101708 1633 1311867224.8779430389 0.1727142930 0.1642562026 0.2106595784 0.0054399292 0.0335680000 447515861 0 402718720 -0.1261803955 0.1550229341 -0.1133435220 1634 1311867224.9056510925 0.1722737104 0.1642611093 0.2106595784 0.0054444665 0.0343580000 447518893 0 402718720 -0.1258178055 0.1568074226 -0.1132760867 1635 1311867224.9375700951 0.1725507528 0.1642661794 0.2106595784 0.0054450578 0.0348560000 447521981 0 402718720 -0.1257484853 0.1579175144 -0.1126386598 1636 1311867224.9797348976 0.1723800898 0.1642711390 0.2106595784 0.0054442180 0.0350840000 447525349 0 402718720 -0.1260874718 0.1579225361 -0.1124873906 1637 1311867225.0066180229 0.1723996848 0.1642761045 0.2106595784 0.0054432622 0.0378690000 447528325 0 402718720 -0.1260304600 0.1610330343 -0.1125667021 1638 1311867225.0376811028 0.1722974032 0.1642810015 0.2106595784 0.0054426032 0.0354290000 447531301 0 402718720 -0.1258633137 0.1632926166 -0.1121308431 1639 1311867225.0798690319 0.1721493900 0.1642858022 0.2106595784 0.0054411121 0.0351410000 447534781 0 402718720 -0.1258112490 0.1640115231 -0.1113612652 1640 1311867225.1055490971 0.1722878069 0.1642906815 0.2106595784 0.0054395563 0.0366730000 447537645 0 402718720 -0.1259686798 0.1662870497 -0.1109721884 1641 1311867225.1377630234 0.1720784009 0.1642954272 0.2106595784 0.0054381459 0.0334320000 447540789 0 402718720 -0.1257159263 0.1678396314 -0.1106891334 1642 1311867225.1808199883 0.1722678393 0.1643002825 0.2106595784 0.0054365910 0.0343160000 447544269 0 402718720 -0.1260226071 0.1688914448 -0.1101147979 1643 1311867225.2055571079 0.1725822240 0.1643053233 0.2106595784 0.0054350169 0.0358240000 447547245 0 402718720 -0.1257422715 0.1699202210 -0.1097995862 1644 1311867225.2376680374 0.1719995588 0.1643100035 0.2106595784 0.0054368402 0.0387530000 447550333 0 402718720 -0.1257231385 0.1706201583 -0.1097908989 1645 1311867225.2792549133 0.1716728657 0.1643144794 0.2106595784 0.0054358326 0.0386210000 447553757 0 402718720 -0.1257157773 0.1724120677 -0.1096470281 1646 1311867225.3057770729 0.1720849723 0.1643192002 0.2106595784 0.0054364573 0.0384240000 447556733 0 402718720 -0.1258195043 0.1726671755 -0.1091031060 1647 1311867225.3376760483 0.1725065857 0.1643241713 0.2106595784 0.0054351865 0.0352240000 447559821 0 402718720 -0.1263598502 0.1734464765 -0.1089954227 1648 1311867225.3736929893 0.1725355834 0.1643291539 0.2106595784 0.0054336745 0.0372890000 447563133 0 402718720 -0.1266103387 0.1749035865 -0.1088421792 1649 1311867225.4055819511 0.1724901199 0.1643341030 0.2106595784 0.0054321198 0.0373410000 447566277 0 402718720 -0.1269067973 0.1752464324 -0.1088325977 1650 1311867225.4376020432 0.1726854295 0.1643391644 0.2106595784 0.0054308890 0.0359130000 447569365 0 402718720 -0.1275231838 0.1768270284 -0.1091223359 1651 1311867225.4737141132 0.1724484712 0.1643440761 0.2106595784 0.0054298817 0.0365440000 447572677 0 402718720 -0.1276607364 0.1776688248 -0.1093301624 1652 1311867225.5056099892 0.1721684337 0.1643488124 0.2106595784 0.0054284013 0.0365610000 447575821 0 402718720 -0.1276834309 0.1780313998 -0.1097540036 1653 1311867225.5377950668 0.1729466468 0.1643540138 0.2106595784 0.0054325095 0.0359060000 447578909 0 402718720 -0.1287038475 0.1806301326 -0.1100350767 1654 1311867225.5737879276 0.1731966734 0.1643593600 0.2106595784 0.0054312193 0.0375370000 447582165 0 402718720 -0.1298114359 0.1821354628 -0.1101563945 1655 1311867225.6055200100 0.1738088131 0.1643650697 0.2106595784 0.0054402003 0.0387220000 447585365 0 402718720 -0.1310199946 0.1815216094 -0.1105059981 1656 1311867225.6376249790 0.1737063378 0.1643707105 0.2106595784 0.0054397882 0.0390270000 447588453 0 402718720 -0.1314805448 0.1827897280 -0.1115899086 1657 1311867225.6738059521 0.1733362526 0.1643761212 0.2106595784 0.0054381501 0.0387240000 447591709 0 402718720 -0.1319815367 0.1845423877 -0.1126928926 1658 1311867225.7056419849 0.1738144606 0.1643818138 0.2106595784 0.0054367226 0.0380650000 447594909 0 402718720 -0.1332646906 0.1843414456 -0.1130833030 1659 1311867225.7377469540 0.1740124971 0.1643876189 0.2106595784 0.0054364755 0.0365890000 447597997 0 402718720 -0.1342243254 0.1845987737 -0.1142810956 1660 1311867225.7736589909 0.1743335873 0.1643936105 0.2106595784 0.0054388945 0.0392810000 447601253 0 402718720 -0.1347641349 0.1881012619 -0.1150330156 1661 1311867225.8056180477 0.1747619808 0.1643998527 0.2106595784 0.0054401014 0.0347240000 447604397 0 402718720 -0.1358159930 0.1877907813 -0.1153511107 1662 1311867225.8378040791 0.1743622273 0.1644058469 0.2106595784 0.0054409691 0.0379940000 447607485 0 402718720 -0.1358398646 0.1893075109 -0.1161994040 1663 1311867225.8737781048 0.1742848456 0.1644117874 0.2106595784 0.0054396072 0.0381950000 447610741 0 402718720 -0.1358388662 0.1906434149 -0.1166542396 1664 1311867225.9056320190 0.1757551134 0.1644186043 0.2106595784 0.0054404496 0.0368660000 447613941 0 402718720 -0.1372255832 0.1913066655 -0.1163469627 1665 1311867225.9379038811 0.1757450104 0.1644254070 0.2106595784 0.0054404540 0.0385470000 447617029 0 402718720 -0.1376434565 0.1922513694 -0.1167414114 1666 1311867225.9735910892 0.1750734895 0.1644317984 0.2106595784 0.0054396960 0.0388610000 447620285 0 402718720 -0.1373624802 0.1939138323 -0.1175814494 1667 1311867226.0058701038 0.1758092940 0.1644386235 0.2106595784 0.0054384381 0.0371540000 447623485 0 402718720 -0.1379351467 0.1945782751 -0.1177828833 1668 1311867226.0378069878 0.1759485155 0.1644455239 0.2106595784 0.0054370603 0.0412110000 447626629 0 402718720 -0.1383995116 0.1963648200 -0.1184224710 1669 1311867226.0737369061 0.1757610887 0.1644523038 0.2106595784 0.0054372433 0.0383380000 447629829 0 402718720 -0.1385501921 0.1991620064 -0.1185297891 1670 1311867226.1055870056 0.1768640280 0.1644597359 0.2106595784 0.0054377471 0.0374610000 447633029 0 402718720 -0.1395182461 0.1986003667 -0.1183099896 1671 1311867226.1377019882 0.1761912405 0.1644667566 0.2106595784 0.0054363352 0.0399860000 447636117 0 402718720 -0.1393445283 0.2004052997 -0.1189225316 1672 1311867226.1737821102 0.1765628606 0.1644739911 0.2106595784 0.0054348070 0.0388570000 447639373 0 402718720 -0.1393592358 0.2027452141 -0.1189434677 1673 1311867226.2056519985 0.1766145229 0.1644812478 0.2106595784 0.0054343895 0.0377380000 447642573 0 402718720 -0.1392515749 0.2033244371 -0.1190671548 1674 1311867226.2378389835 0.1764076203 0.1644883723 0.2106595784 0.0054332653 0.0374430000 447645661 0 402718720 -0.1392789334 0.2046581060 -0.1195442826 1675 1311867226.2736389637 0.1766584665 0.1644956380 0.2106595784 0.0054317535 0.0394640000 447648917 0 402718720 -0.1388936639 0.2059644163 -0.1200239733 1676 1311867226.3056368828 0.1765694171 0.1645028420 0.2106595784 0.0054302945 0.0396190000 447652117 0 402718720 -0.1386428326 0.2074714303 -0.1204968467 1677 1311867226.3376090527 0.1771981716 0.1645104122 0.2106595784 0.0054294100 0.0378150000 447655205 0 402718720 -0.1390110850 0.2098346204 -0.1206727624 1678 1311867226.3737339973 0.1775012612 0.1645181541 0.2106595784 0.0054294653 0.0389280000 447658461 0 402718720 -0.1391642541 0.2105325311 -0.1209350899 1679 1311867226.4056019783 0.1775566489 0.1645259197 0.2106595784 0.0054293751 0.0382290000 447661661 0 402718720 -0.1391545236 0.2118841410 -0.1209208071 1680 1311867226.4376440048 0.1772923023 0.1645335188 0.2106595784 0.0054305277 0.0403720000 447664749 0 402718720 -0.1393225491 0.2135219425 -0.1214895919 1681 1311867226.4737169743 0.1770061553 0.1645409385 0.2106595784 0.0054291089 0.0389580000 447668005 0 402718720 -0.1388585418 0.2149261683 -0.1219498441 1682 1311867226.5057499409 0.1779263318 0.1645488966 0.2106595784 0.0054284638 0.0389110000 447671205 0 402718720 -0.1394978315 0.2156430632 -0.1219071150 1683 1311867226.5377409458 0.1780785322 0.1645569356 0.2106595784 0.0054269255 0.0405230000 447674293 0 402718720 -0.1395066082 0.2166675329 -0.1221888214 1684 1311867226.5737669468 0.1779243797 0.1645648735 0.2106595784 0.0054255039 0.0400840000 447677493 0 402718720 -0.1395905465 0.2182314992 -0.1226182207 1685 1311867226.6056129932 0.1783168614 0.1645730349 0.2106595784 0.0054247388 0.0388570000 447680693 0 402718720 -0.1399681419 0.2193333358 -0.1226095110 1686 1311867226.6377971172 0.1781150997 0.1645810670 0.2106595784 0.0054234954 0.0420820000 447683781 0 402718720 -0.1398009360 0.2201647460 -0.1227634177 1687 1311867226.6736760139 0.1778366119 0.1645889244 0.2106595784 0.0054229533 0.0387740000 447687037 0 402718720 -0.1396263987 0.2211166173 -0.1232366040 1688 1311867226.7056579590 0.1789261997 0.1645974181 0.2106595784 0.0054337000 0.0388490000 447690181 0 402718720 -0.1400873512 0.2218890637 -0.1233275756 1689 1311867226.7377281189 0.1795650721 0.1646062799 0.2106595784 0.0054435309 0.0381860000 447693325 0 402718720 -0.1404691488 0.2216543108 -0.1233637407 1690 1311867226.7738599777 0.1790800244 0.1646148443 0.2106595784 0.0054419699 0.0409790000 447696581 0 402718720 -0.1405269951 0.2238483578 -0.1243957579 1691 1311867226.8056368828 0.1792646945 0.1646235077 0.2106595784 0.0054406041 0.0386440000 447699725 0 402718720 -0.1407308280 0.2248107642 -0.1243449375 1692 1311867226.8377530575 0.1795579791 0.1646323342 0.2106595784 0.0054397022 0.0392000000 447702869 0 402718720 -0.1411662847 0.2248581648 -0.1243974343 1693 1311867226.8738210201 0.1792757511 0.1646409836 0.2106595784 0.0054411354 0.0379050000 447706125 0 402718720 -0.1412680298 0.2257692665 -0.1250438988 1694 1311867226.9057741165 0.1792196184 0.1646495896 0.2106595784 0.0054395949 0.0400580000 447709269 0 402718720 -0.1415053606 0.2267745584 -0.1255127341 1695 1311867226.9378130436 0.1793685853 0.1646582734 0.2106595784 0.0054380349 0.0378700000 447712469 0 402718720 -0.1416160464 0.2268404961 -0.1256901920 1696 1311867226.9736309052 0.1795837432 0.1646670738 0.2106595784 0.0054375298 0.0387550000 447715669 0 402718720 -0.1419262290 0.2280988842 -0.1261478364 1697 1311867227.0056760311 0.1793303937 0.1646757145 0.2106595784 0.0054360337 0.0389500000 447718869 0 402718720 -0.1418668628 0.2294944078 -0.1265246421 1698 1311867227.0378019810 0.1800360978 0.1646847607 0.2106595784 0.0054397641 0.0400720000 447721957 0 402718720 -0.1422248185 0.2296442688 -0.1263413280 1699 1311867227.0736589432 0.1798261106 0.1646936726 0.2106595784 0.0054402615 0.0392600000 447725213 0 402718720 -0.1425202936 0.2319398373 -0.1266608238 1700 1311867227.1056621075 0.1794875115 0.1647023749 0.2106595784 0.0054395518 0.0396060000 447728245 0 402718720 -0.1419205070 0.2332060337 -0.1267312467 1701 1311867227.1377930641 0.1797241867 0.1647112060 0.2106595784 0.0054379692 0.0417640000 447731333 0 402718720 -0.1419013888 0.2337284237 -0.1263689250 1702 1311867227.1738400459 0.1792443693 0.1647197449 0.2106595784 0.0054378168 0.0395360000 447734589 0 402718720 -0.1417946070 0.2359731346 -0.1264184117 1703 1311867227.2057490349 0.1799155772 0.1647286679 0.2106595784 0.0054366727 0.0400680000 447737733 0 402718720 -0.1422304064 0.2365650684 -0.1259026229 1704 1311867227.2379469872 0.1808901578 0.1647381523 0.2106595784 0.0054382917 0.0399540000 447740821 0 402718720 -0.1430059224 0.2366596460 -0.1254368424 1705 1311867227.2737090588 0.1807004511 0.1647475144 0.2106595784 0.0054418307 0.0415620000 447744077 0 402718720 -0.1433119923 0.2379230112 -0.1256540120 1706 1311867227.3058218956 0.1803470701 0.1647566583 0.2106595784 0.0054406943 0.0379320000 447747277 0 402718720 -0.1431135833 0.2393817157 -0.1254629046 1707 1311867227.3377470970 0.1803672314 0.1647658034 0.2106595784 0.0054420077 0.0393120000 447750421 0 402718720 -0.1437384039 0.2399995923 -0.1253111362 1708 1311867227.3737759590 0.1800939292 0.1647747777 0.2106595784 0.0054424191 0.0415550000 447753677 0 402718720 -0.1440507621 0.2407358438 -0.1252336949 1709 1311867227.4056999683 0.1798729300 0.1647836122 0.2106595784 0.0054476904 0.0393660000 447756821 0 402718720 -0.1440085471 0.2410366833 -0.1251932830 1710 1311867227.4377551079 0.1801420748 0.1647925937 0.2106595784 0.0054464901 0.0422510000 447759909 0 402718720 -0.1448693275 0.2428763658 -0.1250282675 1711 1311867227.4737389088 0.1804428399 0.1648017406 0.2106595784 0.0054462908 0.0416550000 447763221 0 402718720 -0.1449643075 0.2424269915 -0.1249206513 1712 1311867227.5057799816 0.1804715693 0.1648108935 0.2106595784 0.0054450488 0.0405890000 447766365 0 402718720 -0.1452968121 0.2426001877 -0.1251296848 1713 1311867227.5379340649 0.1806416810 0.1648201351 0.2106595784 0.0054437565 0.0387540000 447769453 0 402718720 -0.1457628608 0.2434869260 -0.1252588928 1714 1311867227.5737419128 0.1807085872 0.1648294049 0.2106595784 0.0054422735 0.0391750000 447772709 0 402718720 -0.1458714306 0.2438903004 -0.1251573563 1715 1311867227.6058499813 0.1807256192 0.1648386738 0.2106595784 0.0054453390 0.0392620000 447775909 0 402718720 -0.1462395191 0.2446629554 -0.1250229180 1716 1311867227.6379189491 0.1802978963 0.1648476827 0.2106595784 0.0054484680 0.0387460000 447778997 0 402718720 -0.1459594220 0.2450601608 -0.1249356344 1717 1311867227.6739299297 0.1806114912 0.1648568637 0.2106595784 0.0054515135 0.0401430000 447782309 0 402718720 -0.1460267305 0.2452928424 -0.1246829554 1718 1311867227.7059600353 0.1805206686 0.1648659811 0.2106595784 0.0054516695 0.0402370000 447785453 0 402718720 -0.1461947113 0.2463300526 -0.1247149929 1719 1311867227.7378249168 0.1800825745 0.1648748331 0.2106595784 0.0054500888 0.0408320000 447788541 0 402718720 -0.1459103376 0.2476721108 -0.1246442348 1720 1311867227.7737319469 0.1801827848 0.1648837331 0.2106595784 0.0054486887 0.0382500000 447791853 0 402718720 -0.1455822587 0.2478513420 -0.1241132170 1721 1311867227.8058609962 0.1802727431 0.1648926750 0.2106595784 0.0054480447 0.0397860000 447795053 0 402718720 -0.1459067613 0.2494239658 -0.1241484731 1722 1311867227.8377740383 0.1798985600 0.1649013892 0.2106595784 0.0054517135 0.0402520000 447798085 0 402718720 -0.1454110444 0.2506195605 -0.1240977049 1723 1311867227.8738338947 0.1799779087 0.1649101394 0.2106595784 0.0054509431 0.0395380000 447801397 0 402718720 -0.1447599977 0.2512899935 -0.1232557371 1724 1311867227.9057910442 0.1803079695 0.1649190709 0.2106595784 0.0054494558 0.0393290000 447804541 0 402718720 -0.1446997374 0.2516124249 -0.1230085492 1725 1311867227.9379739761 0.1798347384 0.1649277176 0.2106595784 0.0054479831 0.0396540000 447807629 0 402718720 -0.1440589875 0.2532403767 -0.1234577149 1726 1311867227.9737529755 0.1799926311 0.1649364458 0.2106595784 0.0054474995 0.0439280000 447810885 0 402718720 -0.1436419189 0.2530474365 -0.1236211658 1727 1311867228.0057229996 0.1804243028 0.1649454139 0.2106595784 0.0054469522 0.0428660000 447814085 0 402718720 -0.1436229199 0.2544283569 -0.1232361346 1728 1311867228.0379528999 0.1803070307 0.1649543037 0.2106595784 0.0054456346 0.0397960000 447817173 0 402718720 -0.1428176463 0.2563557029 -0.1230993941 1729 1311867228.0738921165 0.1808014065 0.1649634692 0.2106595784 0.0054447490 0.0406780000 447820485 0 402718720 -0.1426333338 0.2574138045 -0.1225478873 1730 1311867228.1058039665 0.1811447889 0.1649728226 0.2106595784 0.0054435138 0.0406260000 447823629 0 402718720 -0.1425334960 0.2581667900 -0.1223900095 1731 1311867228.1378440857 0.1809171885 0.1649820336 0.2106595784 0.0054421212 0.0405940000 447826717 0 402718720 -0.1419457644 0.2591435611 -0.1226310432 1732 1311867228.1738140583 0.1812636703 0.1649914341 0.2106595784 0.0054406665 0.0405270000 447830029 0 402718720 -0.1416417658 0.2603036165 -0.1226209104 1733 1311867228.2057390213 0.1820090264 0.1650012539 0.2106595784 0.0054398033 0.0391740000 447833173 0 402718720 -0.1413439959 0.2604798377 -0.1224349365 1734 1311867228.2379329205 0.1822855026 0.1650112217 0.2106595784 0.0054399918 0.2357390000 460154781 0 402718720 -0.1413392574 0.2616172433 -0.1226034686 1735 1311867228.2737610340 0.1809256375 0.1650203943 0.2106595784 0.0054391961 0.0205940000 463817301 0 402718720 -0.1416392177 0.2619647682 -0.1251689047 1736 1311867228.3059210777 0.1810248345 0.1650296134 0.2106595784 0.0054382712 0.0208740000 467012637 0 402718720 -0.1416032761 0.2625261843 -0.1252298057 1737 1311867228.3377981186 0.1808042377 0.1650386950 0.2106595784 0.0054367884 0.0471400000 467015725 0 402718720 -0.1413257122 0.2636205852 -0.1254990101 1738 1311867228.3738679886 0.1806869805 0.1650476986 0.2106595784 0.0054355439 0.0380060000 467019037 0 402718720 -0.1409153640 0.2648674548 -0.1255116463 1739 1311867228.4058170319 0.1813584268 0.1650570779 0.2106595784 0.0054340369 0.0371200000 467022181 0 402718720 -0.1413787454 0.2646798193 -0.1253122240 1740 1311867228.4377839565 0.1809120774 0.1650661900 0.2106595784 0.0054333469 0.0370930000 467025325 0 402718720 -0.1409966201 0.2660824060 -0.1254674941 1741 1311867228.4738910198 0.1812201738 0.1650754686 0.2106595784 0.0054319385 0.0348320000 467028525 0 402718720 -0.1410853118 0.2650352120 -0.1253995746 1742 1311867228.5058081150 0.1815179586 0.1650849074 0.2106595784 0.0054320833 0.0330450000 467031725 0 402718720 -0.1414077431 0.2650124431 -0.1253784150 1743 1311867228.5379021168 0.1817426980 0.1650944644 0.2106595784 0.0054305388 0.0332750000 467034813 0 402718720 -0.1416904032 0.2640173137 -0.1256337017 1744 1311867228.5739669800 0.1817183942 0.1651039965 0.2106595784 0.0054290301 0.0321040000 467038125 0 402718720 -0.1418321878 0.2640340626 -0.1259329617 1745 1311867228.6057848930 0.1819884181 0.1651136724 0.2106595784 0.0054275192 0.0254510000 467041269 0 402718720 -0.1423891187 0.2621101737 -0.1265860349 1746 1311867228.6382379532 0.1818198115 0.1651232406 0.2106595784 0.0054264113 0.0254950000 467044413 0 402718720 -0.1427436471 0.2614226043 -0.1270945966 1747 1311867228.6741480827 0.1819262207 0.1651328588 0.2106595784 0.0054255019 0.0322050000 467047669 0 402718720 -0.1431690454 0.2594671845 -0.1274119616 1748 1311867228.7059628963 0.1818041056 0.1651423961 0.2106595784 0.0054253043 0.0278780000 467050757 0 402718720 -0.1433967203 0.2597154975 -0.1279756874 1749 1311867228.7381000519 0.1809150428 0.1651514142 0.2106595784 0.0054254818 0.0326530000 467053789 0 402718720 -0.1436657310 0.2596197724 -0.1288627535 1750 1311867228.7738020420 0.1815730333 0.1651607980 0.2106595784 0.0054240346 0.0343350000 467056765 0 402718720 -0.1442588568 0.2577309906 -0.1288533211 1751 1311867228.8059840202 0.1814589351 0.1651701059 0.2106595784 0.0054252144 0.0311760000 467059853 0 402718720 -0.1445210427 0.2570853829 -0.1293040663 1752 1311867228.8385589123 0.1804458797 0.1651788249 0.2106595784 0.0054252778 0.0295550000 467062997 0 402718720 -0.1443083137 0.2582262754 -0.1299440265 1753 1311867228.8739609718 0.1810259670 0.1651878650 0.2106595784 0.0054244709 0.0300340000 467066253 0 402718720 -0.1446585953 0.2554742098 -0.1299824566 1754 1311867228.9060149193 0.1815434545 0.1651971897 0.2106595784 0.0054232981 0.0297630000 467069397 0 402718720 -0.1452373266 0.2537889481 -0.1304889917 1755 1311867228.9379169941 0.1804980338 0.1652059081 0.2106595784 0.0054218370 0.0310150000 467072597 0 402718720 -0.1448138505 0.2546407282 -0.1314352751 1756 1311867228.9740309715 0.1810141951 0.1652149106 0.2106595784 0.0054229171 0.0312390000 467075797 0 402718720 -0.1452143192 0.2520726323 -0.1313604265 1757 1311867229.0062179565 0.1816746294 0.1652242786 0.2106595784 0.0054215522 0.0289260000 467078941 0 402718720 -0.1461154372 0.2492707670 -0.1317341179 1758 1311867229.0378949642 0.1808329374 0.1652331573 0.2106595784 0.0054213472 0.0309460000 467082085 0 402718720 -0.1456021070 0.2502340078 -0.1325254738 1759 1311867229.0738630295 0.1803718209 0.1652417637 0.2106595784 0.0054206357 0.0324910000 467085341 0 402718720 -0.1452475041 0.2496062815 -0.1327087283 1760 1311867229.1060481071 0.1814691275 0.1652509838 0.2106595784 0.0054192879 0.0295890000 467088485 0 402718720 -0.1462593675 0.2461994290 -0.1325305700 1761 1311867229.1384150982 0.1808671951 0.1652598516 0.2106595784 0.0054205200 0.0314040000 467091685 0 402718720 -0.1456910074 0.2462490797 -0.1329312027 1762 1311867229.1738820076 0.1804126650 0.1652684514 0.2106595784 0.0054190213 0.0300140000 467094885 0 402718720 -0.1454642117 0.2457128763 -0.1333653927 1763 1311867229.2058811188 0.1810585558 0.1652774078 0.2106595784 0.0054200382 0.0288050000 467098085 0 402718720 -0.1460403502 0.2427212149 -0.1332324892 1764 1311867229.2379889488 0.1811176836 0.1652863875 0.2106595784 0.0054203344 0.0284960000 467101173 0 402718720 -0.1462936103 0.2410996854 -0.1335966885 1765 1311867229.2738459110 0.1807640046 0.1652951567 0.2106595784 0.0054192790 0.0315090000 467104429 0 402718720 -0.1464043111 0.2404374331 -0.1342000961 1766 1311867229.3058760166 0.1801978946 0.1653035954 0.2106595784 0.0054195880 0.0288320000 467107573 0 402718720 -0.1460514218 0.2391304970 -0.1346012503 1767 1311867229.3384299278 0.1807796061 0.1653123537 0.2106595784 0.0054183223 0.0301460000 467110717 0 402718720 -0.1466519088 0.2361957729 -0.1349452585 1768 1311867229.3738911152 0.1803120226 0.1653208377 0.2106595784 0.0054175907 0.0311520000 467113973 0 402718720 -0.1465406269 0.2356654853 -0.1357530057 1769 1311867229.4058239460 0.1800428927 0.1653291600 0.2106595784 0.0054166510 0.0305790000 467117117 0 402718720 -0.1462404877 0.2347898632 -0.1361627132 1770 1311867229.4387540817 0.1805691719 0.1653377701 0.2106595784 0.0054151556 0.0308310000 467120205 0 402718720 -0.1468084306 0.2319495976 -0.1363569349 1771 1311867229.4737799168 0.1805277914 0.1653463472 0.2106595784 0.0054137489 0.0316980000 467123461 0 402718720 -0.1470246762 0.2301982939 -0.1368973851 1772 1311867229.5059139729 0.1805795580 0.1653549439 0.2106595784 0.0054143151 0.0298880000 467126605 0 402718720 -0.1471536905 0.2286622375 -0.1372688413 1773 1311867229.5380439758 0.1810266674 0.1653637830 0.2106595784 0.0054130479 0.0310990000 467129693 0 402718720 -0.1477901042 0.2256491482 -0.1378130019 1774 1311867229.5739250183 0.1799060106 0.1653719804 0.2106595784 0.0054125561 0.0305690000 467132893 0 402718720 -0.1472268850 0.2261433601 -0.1388416439 1775 1311867229.6057729721 0.1800171733 0.1653802312 0.2106595784 0.0054112582 0.0306220000 467136093 0 402718720 -0.1476696581 0.2246708423 -0.1390022486 1776 1311867229.6379790306 0.1805484444 0.1653887718 0.2106595784 0.0054105824 0.0308300000 467139237 0 402718720 -0.1486444026 0.2226874232 -0.1394091696 1777 1311867229.6738181114 0.1798152328 0.1653968903 0.2106595784 0.0054095217 0.0338680000 467142437 0 402718720 -0.1483329535 0.2219292969 -0.1400974691 1778 1311867229.7057991028 0.1796062887 0.1654048821 0.2106595784 0.0054088673 0.0305790000 467145637 0 402718720 -0.1484209299 0.2219295055 -0.1403478384 1779 1311867229.7379260063 0.1799771935 0.1654130734 0.2106595784 0.0054075460 0.0312760000 467148725 0 402718720 -0.1487630606 0.2196007073 -0.1402963698 1780 1311867229.7739849091 0.1797140092 0.1654211076 0.2106595784 0.0054092937 0.0354670000 467151981 0 402718720 -0.1492007226 0.2186280638 -0.1410982460 1781 1311867229.8058290482 0.1796129644 0.1654290761 0.2106595784 0.0054108301 0.0327700000 467155125 0 402718720 -0.1489715427 0.2182667404 -0.1413576752 1782 1311867229.8378639221 0.1800152361 0.1654372614 0.2106595784 0.0054095556 0.0320950000 467158213 0 402718720 -0.1493031383 0.2160910964 -0.1415052861 1783 1311867229.8740329742 0.1800312102 0.1654454464 0.2106595784 0.0054081677 0.0325340000 467161525 0 402718720 -0.1498885602 0.2144593447 -0.1421240717 1784 1311867229.9058520794 0.1792489737 0.1654531838 0.2106595784 0.0054069116 0.0342320000 467164669 0 402718720 -0.1494547576 0.2142846882 -0.1429415792 1785 1311867229.9381949902 0.1795712858 0.1654610931 0.2106595784 0.0054055055 0.0327360000 467167813 0 402718720 -0.1494297087 0.2127896398 -0.1427305937 1786 1311867229.9739520550 0.1800003499 0.1654692338 0.2106595784 0.0054043829 0.0329210000 467171069 0 402718720 -0.1500379890 0.2099250853 -0.1431717724 1787 1311867230.0058848858 0.1796396375 0.1654771635 0.2106595784 0.0054033605 0.0341890000 467174269 0 402718720 -0.1502456814 0.2093244940 -0.1441131532 1788 1311867230.0378499031 0.1796097457 0.1654850676 0.2106595784 0.0054037978 0.0347110000 467177357 0 402718720 -0.1497780085 0.2087032050 -0.1446347982 1789 1311867230.0740690231 0.1801031083 0.1654932387 0.2106595784 0.0054048646 0.0341900000 467180613 0 402718720 -0.1509715915 0.2055035383 -0.1448334306 1790 1311867230.1059269905 0.1795923710 0.1655011153 0.2106595784 0.0054035739 0.0344200000 467183757 0 402718720 -0.1508600861 0.2051474899 -0.1457577497 1791 1311867230.1380810738 0.1794895977 0.1655089257 0.2106595784 0.0054031919 0.0355790000 467186957 0 402718720 -0.1503250301 0.2054184973 -0.1461172253 1792 1311867230.1738770008 0.1796768904 0.1655168320 0.2106595784 0.0054021901 0.0360610000 467190157 0 402718720 -0.1512348801 0.2029149979 -0.1468589157 1793 1311867230.2060499191 0.1798482239 0.1655248249 0.2106595784 0.0054007393 0.0334170000 467193357 0 402718720 -0.1517143250 0.2016005367 -0.1474179327 1794 1311867230.2381780148 0.1798036397 0.1655327841 0.2106595784 0.0053993721 0.0356160000 467196445 0 402718720 -0.1520488858 0.2000933290 -0.1483260989 1795 1311867230.2741019726 0.1798320711 0.1655407503 0.2106595784 0.0053980187 0.0357820000 467199701 0 402718720 -0.1515786797 0.2004224956 -0.1484338343 1796 1311867230.3059499264 0.1797826290 0.1655486801 0.2106595784 0.0053967413 0.0357160000 467202845 0 402718720 -0.1516710967 0.1992272884 -0.1489401013 1797 1311867230.3378720284 0.1796801686 0.1655565440 0.2106595784 0.0053952695 0.0354290000 467205933 0 402718720 -0.1517574340 0.1986965537 -0.1498544812 1798 1311867230.3740670681 0.1795175225 0.1655643088 0.2106595784 0.0054008659 0.0347940000 467209245 0 402718720 -0.1519743651 0.1972324103 -0.1501939297 1799 1311867230.4061839581 0.1799507141 0.1655723057 0.2106595784 0.0054056824 0.0349660000 467212445 0 402718720 -0.1518573910 0.1963619888 -0.1505949944 1800 1311867230.4379858971 0.1797628105 0.1655801893 0.2106595784 0.0054041933 0.0372750000 467215533 0 402718720 -0.1521406174 0.1955261827 -0.1513924897 1801 1311867230.4740281105 0.1799739748 0.1655881814 0.2106595784 0.0054027498 0.0359340000 467218789 0 402718720 -0.1523622274 0.1941672117 -0.1515571773 1802 1311867230.5060799122 0.1792550683 0.1655957657 0.2106595784 0.0054116915 0.0350630000 467221877 0 402718720 -0.1526907384 0.1931165755 -0.1521077305 1803 1311867230.5379009247 0.1797512174 0.1656036167 0.2106595784 0.0054197602 0.0358380000 467225077 0 402718720 -0.1529129446 0.1928377450 -0.1526664197 1804 1311867230.5740880966 0.1798916906 0.1656115369 0.2106595784 0.0054183072 0.0349220000 467228277 0 402718720 -0.1530264020 0.1919859797 -0.1528882682 1805 1311867230.6059589386 0.1801960766 0.1656196170 0.2106595784 0.0054169320 0.0334370000 467231477 0 402718720 -0.1535419226 0.1904086322 -0.1532389522 1806 1311867230.6380519867 0.1799857765 0.1656275717 0.2106595784 0.0054155593 0.0378180000 467234565 0 402718720 -0.1537748873 0.1894903779 -0.1537873596 1807 1311867230.6740579605 0.1799663156 0.1656355068 0.2106595784 0.0054144713 0.0366020000 467237821 0 402718720 -0.1541065127 0.1884123981 -0.1541120559 1808 1311867230.7059040070 0.1795267910 0.1656431900 0.2106595784 0.0054130382 0.0359540000 467241021 0 402718720 -0.1539323628 0.1878321618 -0.1545496881 1809 1311867230.7379570007 0.1793156415 0.1656507481 0.2106595784 0.0054116192 0.0347400000 467244109 0 402718720 -0.1537501514 0.1881082803 -0.1547165364 1810 1311867230.7741370201 0.1794657111 0.1656583806 0.2106595784 0.0054102048 0.0374220000 467247365 0 402718720 -0.1543350518 0.1869149655 -0.1547073126 1811 1311867230.8059010506 0.1793435663 0.1656659373 0.2106595784 0.0054088405 0.0356070000 467250565 0 402718720 -0.1545151025 0.1865360886 -0.1547800601 1812 1311867230.8381690979 0.1792344302 0.1656734255 0.2106595784 0.0054074572 0.0343880000 467253653 0 402718720 -0.1547605246 0.1862208247 -0.1549429148 1813 1311867230.8741331100 0.1792212874 0.1656808981 0.2106595784 0.0054061813 0.0351130000 467256909 0 402718720 -0.1550368965 0.1859905124 -0.1549624950 1814 1311867230.9059469700 0.1792497337 0.1656883781 0.2106595784 0.0054053947 0.0343170000 467260109 0 402718720 -0.1551276147 0.1859243661 -0.1550814807 1815 1311867230.9382989407 0.1791138351 0.1656957751 0.2106595784 0.0054039158 0.0361330000 467263197 0 402718720 -0.1554269791 0.1853763312 -0.1550781727 1816 1311867230.9739239216 0.1791666746 0.1657031930 0.2106595784 0.0054029067 0.0352550000 467266453 0 402718720 -0.1556770205 0.1851235926 -0.1552094519 1817 1311867231.0062189102 0.1794015765 0.1657107320 0.2106595784 0.0054014340 0.0361440000 467269653 0 402718720 -0.1558848172 0.1843844503 -0.1551641226 1818 1311867231.0381219387 0.1794638932 0.1657182970 0.2106595784 0.0054002412 0.0364770000 467272741 0 402718720 -0.1562380493 0.1835025698 -0.1555014402 1819 1311867231.0740990639 0.1791155338 0.1657256622 0.2106595784 0.0053987894 0.0351160000 467275885 0 402718720 -0.1564135998 0.1834238172 -0.1561322659 1820 1311867231.1059539318 0.1793560386 0.1657331514 0.2106595784 0.0053997136 0.0362080000 467279029 0 402718720 -0.1568727493 0.1822095513 -0.1561715007 1821 1311867231.1382420063 0.1798143387 0.1657408840 0.2106595784 0.0054045859 0.0366430000 467282173 0 402718720 -0.1576767266 0.1798518449 -0.1564124972 1822 1311867231.1742498875 0.1795205772 0.1657484470 0.2106595784 0.0054032375 0.0366430000 467285429 0 402718720 -0.1572501510 0.1805046797 -0.1569036841 1823 1311867231.2059180737 0.1799382269 0.1657562307 0.2106595784 0.0054023816 0.0366800000 467288573 0 402718720 -0.1579418778 0.1787169278 -0.1573534310 1824 1311867231.2381839752 0.1802133620 0.1657641568 0.2106595784 0.0054014045 0.0379600000 467291661 0 402718720 -0.1586137265 0.1771434546 -0.1574224383 1825 1311867231.2740900517 0.1801514924 0.1657720403 0.2106595784 0.0054007837 0.0379810000 467294973 0 402718720 -0.1586685777 0.1765773594 -0.1582184285 1826 1311867231.3060190678 0.1799457371 0.1657798024 0.2106595784 0.0053996283 0.0362020000 467298117 0 402718720 -0.1589346379 0.1755616069 -0.1585808992 1827 1311867231.3381490707 0.1798885018 0.1657875248 0.2106595784 0.0053991234 0.0369610000 467301205 0 402718720 -0.1599339694 0.1736046821 -0.1593817323 1828 1311867231.3741829395 0.1796468943 0.1657951065 0.2106595784 0.0053976725 0.0372800000 467304517 0 402718720 -0.1602117568 0.1732447743 -0.1598247290 1829 1311867231.4059898853 0.1793724597 0.1658025299 0.2106595784 0.0053963051 0.0353480000 467307661 0 402718720 -0.1602014452 0.1728042662 -0.1599250138 1830 1311867231.4380719662 0.1792999059 0.1658099055 0.2106595784 0.0053948628 0.0365740000 467310749 0 402718720 -0.1605293900 0.1719430536 -0.1600040793 1831 1311867231.4741399288 0.1786891669 0.1658169395 0.2106595784 0.0053936609 0.0356420000 467314061 0 402718720 -0.1606397033 0.1715382934 -0.1601686627 1832 1311867231.5059800148 0.1787832379 0.1658240171 0.2106595784 0.0053922389 0.0366100000 467317205 0 402718720 -0.1610868275 0.1718384326 -0.1600559801 1833 1311867231.5380959511 0.1790402234 0.1658312273 0.2106595784 0.0053908802 0.0366560000 467320349 0 402718720 -0.1616048962 0.1702802479 -0.1596939117 1834 1311867231.5741529465 0.1788900197 0.1658383477 0.2106595784 0.0053895402 0.0356830000 467323605 0 402718720 -0.1616737247 0.1693879813 -0.1598660648 1835 1311867231.6059548855 0.1786759198 0.1658453436 0.2106595784 0.0053884206 0.0366940000 467326749 0 402718720 -0.1615553349 0.1694573313 -0.1601774544 1836 1311867231.6381249428 0.1783738136 0.1658521674 0.2106595784 0.0053941099 0.0356400000 467329837 0 402718720 -0.1617129743 0.1683463454 -0.1600403041 1837 1311867231.6741418839 0.1788882762 0.1658592638 0.2106595784 0.0053982642 0.0368100000 467333149 0 402718720 -0.1620055884 0.1674335748 -0.1604178250 1838 1311867231.7059209347 0.1788716912 0.1658663435 0.2106595784 0.0053970053 0.0367890000 467336293 0 402718720 -0.1618543118 0.1675716937 -0.1608175039 1839 1311867231.7380108833 0.1789775640 0.1658734730 0.2106595784 0.0053956023 0.0379130000 467339381 0 402718720 -0.1617084891 0.1663713008 -0.1607129872 1840 1311867231.7741730213 0.1791392267 0.1658806827 0.2106595784 0.0053964195 0.0374660000 467342693 0 402718720 -0.1621225625 0.1642211825 -0.1612105817 1841 1311867231.8059310913 0.1789216548 0.1658877663 0.2106595784 0.0053950817 0.0379240000 467345837 0 402718720 -0.1619051993 0.1641488969 -0.1620270461 1842 1311867231.8380389214 0.1791679710 0.1658949760 0.2106595784 0.0053937387 0.0356720000 467348981 0 402718720 -0.1620686650 0.1629905701 -0.1623886824 1843 1311867231.8739199638 0.1792684346 0.1659022323 0.2106595784 0.0053925775 0.0375120000 467352181 0 402718720 -0.1622371227 0.1608877480 -0.1627336293 1844 1311867231.9059829712 0.1791637689 0.1659094241 0.2106595784 0.0053924872 0.0370950000 467355381 0 402718720 -0.1618113220 0.1609916836 -0.1631664485 1845 1311867231.9380280972 0.1792664528 0.1659166636 0.2106595784 0.0053920970 0.0369990000 467358469 0 402718720 -0.1619544029 0.1596947461 -0.1637724191 1846 1311867231.9740860462 0.1800291687 0.1659243086 0.2106595784 0.0053913980 0.0380280000 467361781 0 402718720 -0.1619036347 0.1584794670 -0.1637618393 1847 1311867232.0061240196 0.1796643436 0.1659317477 0.2106595784 0.0053911483 0.0375280000 467364925 0 402718720 -0.1620803624 0.1569175124 -0.1646671295 1848 1311867232.0380520821 0.1792295277 0.1659389434 0.2106595784 0.0053897293 0.0370490000 467368013 0 402718720 -0.1619453430 0.1567853242 -0.1652806550 1849 1311867232.0740749836 0.1796364486 0.1659463515 0.2106595784 0.0053883007 0.0363130000 467371269 0 402718720 -0.1620881110 0.1552117616 -0.1655038893 1850 1311867232.1061620712 0.1800455749 0.1659539727 0.2106595784 0.0053877448 0.0375660000 467374469 0 402718720 -0.1622066498 0.1541521549 -0.1661729515 1851 1311867232.1381609440 0.1792880744 0.1659611764 0.2106595784 0.0053866932 0.0383480000 467377557 0 402718720 -0.1618159413 0.1548016667 -0.1667461097 1852 1311867232.1739470959 0.1798983812 0.1659687019 0.2106595784 0.0053853383 0.0371270000 467380813 0 402718720 -0.1621813178 0.1527315527 -0.1664848775 1853 1311867232.2060608864 0.1799818128 0.1659762643 0.2106595784 0.0053840674 0.0374770000 467383957 0 402718720 -0.1626736969 0.1508840173 -0.1670872420 1854 1311867232.2419700623 0.1797168702 0.1659836756 0.2106595784 0.0053830228 0.0376100000 467387269 0 402718720 -0.1623948365 0.1512299329 -0.1677486300 1855 1311867232.2739861012 0.1801478565 0.1659913113 0.2106595784 0.0053818873 0.0376610000 467390357 0 402718720 -0.1626161337 0.1490770876 -0.1675553918 1856 1311867232.3059790134 0.1799097508 0.1659988105 0.2106595784 0.0053807279 0.0385540000 467393557 0 402718720 -0.1629157364 0.1487541944 -0.1683809459 1857 1311867232.3420848846 0.1797917783 0.1660062380 0.2106595784 0.0053793501 0.0371540000 467396701 0 402718720 -0.1627383828 0.1490604877 -0.1689135581 1858 1311867232.3740739822 0.1802223027 0.1660138893 0.2106595784 0.0053781756 0.0361060000 467399901 0 402718720 -0.1627818644 0.1472821683 -0.1688132882 1859 1311867232.4059638977 0.1802156568 0.1660215288 0.2106595784 0.0053769311 0.0377210000 467403045 0 402718720 -0.1632710248 0.1466274261 -0.1693877727 1860 1311867232.4421250820 0.1802164912 0.1660291605 0.2106595784 0.0053758191 0.0382760000 467406301 0 402718720 -0.1627184153 0.1469832808 -0.1698247045 1861 1311867232.4739580154 0.1803309172 0.1660368455 0.2106595784 0.0053748941 0.0372510000 467409389 0 402718720 -0.1625683457 0.1456771791 -0.1696769595 1862 1311867232.5059518814 0.1801489294 0.1660444244 0.2106595784 0.0053735871 0.0372720000 467412589 0 402718720 -0.1624193937 0.1452600509 -0.1700828969 1863 1311867232.5421218872 0.1800194234 0.1660519258 0.2106595784 0.0053721739 0.0383420000 467415789 0 402718720 -0.1625805944 0.1455223858 -0.1704668850 1864 1311867232.5739369392 0.1802702397 0.1660595536 0.2106595784 0.0053712410 0.0378130000 467418933 0 402718720 -0.1623971760 0.1436356604 -0.1700054854 1865 1311867232.6061329842 0.1804579049 0.1660672739 0.2106595784 0.0053699338 0.0378380000 467422077 0 402718720 -0.1624024957 0.1421887279 -0.1703264266 1866 1311867232.6421279907 0.1802018732 0.1660748487 0.2106595784 0.0053690400 0.0373930000 467425277 0 402718720 -0.1617841274 0.1428281367 -0.1708402932 1867 1311867232.6740040779 0.1804607064 0.1660825541 0.2106595784 0.0053676513 0.0363310000 467428309 0 402718720 -0.1618194431 0.1408257037 -0.1706488878 1868 1311867232.7060089111 0.1818653792 0.1660910031 0.2106595784 0.0053670686 0.0382120000 467431509 0 402718720 -0.1616519392 0.1414112002 -0.1694058776 1869 1311867232.7421109676 0.1806719303 0.1660988046 0.2106595784 0.0053659693 0.0388650000 467434709 0 402718720 -0.1615581214 0.1391630918 -0.1711676717 1870 1311867232.7740490437 0.1809291393 0.1661067352 0.2106595784 0.0053646641 0.0373910000 467437797 0 402718720 -0.1617763340 0.1375721991 -0.1712130159 1871 1311867232.8059849739 0.1827796251 0.1661156465 0.2106595784 0.0053641867 0.0369150000 467440997 0 402718720 -0.1621385217 0.1365718246 -0.1695604324 1872 1311867232.8421289921 0.1823186576 0.1661243019 0.2106595784 0.0053631285 0.0370200000 467444253 0 402718720 -0.1614524573 0.1370050907 -0.1702898294 1873 1311867232.8740520477 0.1826128960 0.1661331052 0.2106595784 0.0053618451 0.0381100000 467447341 0 402718720 -0.1617165208 0.1352533549 -0.1704057306 1874 1311867232.9061350822 0.1826444119 0.1661419160 0.2106595784 0.0053606620 0.0377780000 467450541 0 402718720 -0.1621102691 0.1327524930 -0.1707726121 1875 1311867232.9420969486 0.1826291233 0.1661507091 0.2106595784 0.0053604363 0.0380150000 467453797 0 402718720 -0.1617855579 0.1322720796 -0.1710092723 1876 1311867232.9742751122 0.1812927425 0.1661587806 0.2106595784 0.0053593457 0.0384640000 467456885 0 402718720 -0.1616340131 0.1300157756 -0.1727592498 1877 1311867233.0060579777 0.1811321676 0.1661667579 0.2106595784 0.0053580875 0.0376150000 467460029 0 402718720 -0.1615636647 0.1280559599 -0.1730246991 1878 1311867233.0422320366 0.1821593940 0.1661752737 0.2106595784 0.0053581924 0.0381990000 467463229 0 402718720 -0.1609434187 0.1297444552 -0.1719520837 1879 1311867233.0742039680 0.1812671423 0.1661833055 0.2106595784 0.0053568938 0.0383330000 467466429 0 402718720 -0.1611685306 0.1284394413 -0.1733298898 1880 1311867233.1088590622 0.1813432425 0.1661913693 0.2106595784 0.0053557607 0.0372650000 467469629 0 402718720 -0.1614260972 0.1255004853 -0.1731884181 1881 1311867233.1421349049 0.1813193709 0.1661994118 0.2106595784 0.0053557743 0.0378170000 467472773 0 402718720 -0.1615384817 0.1245040074 -0.1734123230 1882 1311867233.1740570068 0.1809652597 0.1662072577 0.2106595784 0.0053549521 0.0363520000 467475805 0 402718720 -0.1609808058 0.1245979816 -0.1736096740 1883 1311867233.2067739964 0.1811691821 0.1662152035 0.2106595784 0.0053535453 0.0363290000 467479061 0 402718720 -0.1610665619 0.1231138557 -0.1734562367 1884 1311867233.2422530651 0.1814174652 0.1662232726 0.2106595784 0.0053522685 0.0379820000 467482205 0 402718720 -0.1614757031 0.1204987764 -0.1734187752 1885 1311867233.2742159367 0.1810281575 0.1662311267 0.2106595784 0.0053509663 0.0389050000 467485405 0 402718720 -0.1611839831 0.1208106428 -0.1738458872 1886 1311867233.3060619831 0.1809787303 0.1662389462 0.2106595784 0.0053501830 0.0375100000 467488549 0 402718720 -0.1612180173 0.1195776537 -0.1736900657 1887 1311867233.3424530029 0.1819242835 0.1662472585 0.2106595784 0.0053490719 0.2030820000 479800033 0 402718720 -0.1611579210 0.1178266704 -0.1724018306 1888 1311867233.3740661144 0.1818418354 0.1662555183 0.2106595784 0.0053481996 0.0227990000 483462385 0 402718720 -0.1614176035 0.1183815300 -0.1733899415 1889 1311867233.4060258865 0.1819294691 0.1662638158 0.2106595784 0.0053468345 0.0236920000 486657721 0 402718720 -0.1615025848 0.1165979207 -0.1732088923 1890 1311867233.4421939850 0.1817326844 0.1662720004 0.2106595784 0.0053549586 0.0504460000 486660977 0 402718720 -0.1617169380 0.1134242415 -0.1732477248 1891 1311867233.4740760326 0.1821412444 0.1662803924 0.2106595784 0.0053597781 0.0393730000 486664121 0 402718720 -0.1617913693 0.1139226481 -0.1737850010 1892 1311867233.5066010952 0.1819523573 0.1662886757 0.2106595784 0.0053597209 0.0390680000 486667265 0 402718720 -0.1614392847 0.1134070233 -0.1739519238 1893 1311867233.5420820713 0.1815346777 0.1662967295 0.2106595784 0.0053587616 0.0378790000 486670577 0 402718720 -0.1616542786 0.1111695617 -0.1740303785 1894 1311867233.5742170811 0.1818980873 0.1663049668 0.2106595784 0.0053579855 0.0393080000 486673609 0 402718720 -0.1616846919 0.1117118895 -0.1744786352 1895 1311867233.6061730385 0.1817819029 0.1663131340 0.2106595784 0.0053579644 0.0376020000 486676809 0 402718720 -0.1615479141 0.1108120978 -0.1744117737 1896 1311867233.6422669888 0.1818421632 0.1663213245 0.2106595784 0.0053582804 0.0378500000 486680009 0 402718720 -0.1616579145 0.1094750911 -0.1743437648 1897 1311867233.6742019653 0.1818455309 0.1663295080 0.2106595784 0.0053569492 0.0364310000 486683209 0 402718720 -0.1615559459 0.1094709262 -0.1743732840 1898 1311867233.7064609528 0.1816688776 0.1663375899 0.2106595784 0.0053577053 0.0362240000 486686353 0 402718720 -0.1611186564 0.1099130586 -0.1744200587 1899 1311867233.7424199581 0.1818342060 0.1663457503 0.2106595784 0.0053578001 0.0410950000 486689609 0 402718720 -0.1616300195 0.1080794558 -0.1741918623 1900 1311867233.7740728855 0.1812082082 0.1663535726 0.2106595784 0.0053604106 0.0332570000 486692753 0 402718720 -0.1621572673 0.1073726416 -0.1743882596 1901 1311867233.8062269688 0.1814898551 0.1663615349 0.2106595784 0.0053755924 0.0341240000 486695897 0 402718720 -0.1619934142 0.1076581031 -0.1744367778 1902 1311867233.8421831131 0.1816553026 0.1663695758 0.2106595784 0.0053775864 0.0402420000 486699209 0 402718720 -0.1624555290 0.1053649709 -0.1739201248 1903 1311867233.8742289543 0.1818712652 0.1663777217 0.2106595784 0.0053789992 0.0358300000 486702297 0 402718720 -0.1630545408 0.1051542833 -0.1742253900 1904 1311867233.9060840607 0.1815018356 0.1663856651 0.2106595784 0.0053778731 0.0349230000 486705441 0 402718720 -0.1629400998 0.1050065905 -0.1742951423 1905 1311867233.9421920776 0.1813871562 0.1663935399 0.2106595784 0.0053773191 0.0348710000 486708753 0 402718720 -0.1631985456 0.1029737070 -0.1740355641 1906 1311867233.9742488861 0.1811321229 0.1664012726 0.2106595784 0.0053760479 0.0347540000 486711841 0 402718720 -0.1634987593 0.1021641195 -0.1743981242 1907 1311867234.0062050819 0.1810217351 0.1664089393 0.2106595784 0.0053752141 0.0347730000 486714985 0 402718720 -0.1633980870 0.1025482118 -0.1746035665 1908 1311867234.0422050953 0.1811859906 0.1664166841 0.2106595784 0.0053738594 0.0388390000 486718241 0 402718720 -0.1638633311 0.1008171886 -0.1744068712 1909 1311867234.0743489265 0.1814761013 0.1664245727 0.2106595784 0.0053724565 0.0356280000 486721385 0 402718720 -0.1644230932 0.0992233977 -0.1741438508 1910 1311867234.1061749458 0.1811043471 0.1664322585 0.2106595784 0.0053711311 0.0349670000 486724529 0 402718720 -0.1643897295 0.0987385660 -0.1746479124 1911 1311867234.1424729824 0.1811809242 0.1664399763 0.2106595784 0.0053697649 0.0376880000 486727729 0 402718720 -0.1644906700 0.0973008722 -0.1744267195 1912 1311867234.1743829250 0.1819862574 0.1664481072 0.2106595784 0.0053685050 0.0325870000 486730929 0 402718720 -0.1658959687 0.0952788964 -0.1742407084 1913 1311867234.2063119411 0.1819116026 0.1664561905 0.2106595784 0.0053678546 0.0332120000 486734129 0 402718720 -0.1658328921 0.0950362012 -0.1747852713 1914 1311867234.2422919273 0.1815642565 0.1664640840 0.2106595784 0.0053666218 0.0347180000 486737329 0 402718720 -0.1662699729 0.0944296420 -0.1749849916 1915 1311867234.2742938995 0.1819271445 0.1664721587 0.2106595784 0.0053653722 0.0342410000 486740473 0 402718720 -0.1672307402 0.0935671180 -0.1746440828 1916 1311867234.3064689636 0.1812785715 0.1664798865 0.2106595784 0.0053641254 0.0348270000 486743673 0 402718720 -0.1672196686 0.0932250172 -0.1748272032 1917 1311867234.3423550129 0.1809951514 0.1664874583 0.2106595784 0.0053659533 0.0341510000 486746929 0 402718720 -0.1677693278 0.0929957181 -0.1746216565 1918 1311867234.3741590977 0.1814947277 0.1664952828 0.2106595784 0.0053646172 0.0355260000 486750017 0 402718720 -0.1687355936 0.0916945636 -0.1738332212 1919 1311867234.4062600136 0.1808992624 0.1665027888 0.2106595784 0.0053634706 0.0321630000 486753161 0 402718720 -0.1688207537 0.0909634829 -0.1739315093 1920 1311867234.4422380924 0.1802290082 0.1665099378 0.2106595784 0.0053621702 0.0339130000 486756473 0 402718720 -0.1681888103 0.0913541466 -0.1739210486 1921 1311867234.4742479324 0.1811046451 0.1665175353 0.2106595784 0.0053663368 0.0347290000 486759561 0 402718720 -0.1692402363 0.0900607109 -0.1732611805 1922 1311867234.5063080788 0.1813495457 0.1665252522 0.2106595784 0.0053650853 0.0325050000 486762761 0 402718720 -0.1698619127 0.0890221223 -0.1729476601 1923 1311867234.5422930717 0.1807811409 0.1665326656 0.2106595784 0.0053643411 0.0359760000 486766017 0 402718720 -0.1689726859 0.0892264396 -0.1730029881 1924 1311867234.5741920471 0.1808482260 0.1665401061 0.2106595784 0.0053630304 0.0336880000 486769105 0 402718720 -0.1691617221 0.0882146209 -0.1725604236 1925 1311867234.6060979366 0.1809258312 0.1665475792 0.2106595784 0.0053624187 0.0353190000 486772305 0 402718720 -0.1696774662 0.0867287219 -0.1719019562 1926 1311867234.6422669888 0.1806526482 0.1665549027 0.2106595784 0.0053635525 0.0342280000 486775561 0 402718720 -0.1695527732 0.0870499983 -0.1722134203 1927 1311867234.6740961075 0.1806715727 0.1665622285 0.2106595784 0.0053647650 0.0341350000 486778649 0 402718720 -0.1689291894 0.0872287899 -0.1715423763 1928 1311867234.7060949802 0.1801851541 0.1665692943 0.2106595784 0.0053636234 0.0330420000 486781849 0 402718720 -0.1691614091 0.0856263638 -0.1710167527 1929 1311867234.7422869205 0.1803395748 0.1665764328 0.2106595784 0.0053646799 0.0348680000 486785105 0 402718720 -0.1687490493 0.0857012868 -0.1704812348 1930 1311867234.7741398811 0.1790542603 0.1665828980 0.2106595784 0.0053837417 0.0340670000 486788137 0 402718720 -0.1682433933 0.0860496834 -0.1699220538 1931 1311867234.8060719967 0.1798602939 0.1665897740 0.2106595784 0.0053858604 0.0347430000 486791337 0 402718720 -0.1686807871 0.0848799273 -0.1688277870 1932 1311867234.8423259258 0.1786239147 0.1665960028 0.2106595784 0.0053864386 0.0358190000 486794537 0 402718720 -0.1677009612 0.0856302530 -0.1686566323 1933 1311867234.8741569519 0.1786391884 0.1666022331 0.2106595784 0.0053859190 0.0343180000 486797681 0 402718720 -0.1669812351 0.0861509964 -0.1677794307 1934 1311867234.9061870575 0.1791981161 0.1666087460 0.2106595784 0.0053849290 0.0334080000 486800881 0 402718720 -0.1677274853 0.0846292973 -0.1669847965 1935 1311867234.9422700405 0.1790593863 0.1666151804 0.2106595784 0.0053839986 0.0380520000 486804137 0 402718720 -0.1672063023 0.0841932669 -0.1668100953 1936 1311867234.9741549492 0.1787108183 0.1666214282 0.2106595784 0.0053827176 0.0351610000 486807225 0 402718720 -0.1667383760 0.0840059817 -0.1665823460 1937 1311867235.0061750412 0.1789419353 0.1666277888 0.2106595784 0.0053814204 0.0339160000 486810425 0 402718720 -0.1672226936 0.0822015479 -0.1661295444 1938 1311867235.0423259735 0.1790020764 0.1666341739 0.2106595784 0.0053803236 0.0366370000 486813681 0 402718720 -0.1674751043 0.0809396580 -0.1663305312 1939 1311867235.0741820335 0.1789363325 0.1666405185 0.2106595784 0.0053790126 0.0369680000 486816769 0 402718720 -0.1674748361 0.0813464075 -0.1667175442 1940 1311867235.1062519550 0.1789262146 0.1666468513 0.2106595784 0.0053777376 0.0355810000 486819969 0 402718720 -0.1677997112 0.0800674483 -0.1666129082 1941 1311867235.1422450542 0.1788868904 0.1666531573 0.2106595784 0.0053786995 0.0373860000 486823225 0 402718720 -0.1682201922 0.0809747279 -0.1669694781 1942 1311867235.1743009090 0.1788935363 0.1666594603 0.2106595784 0.0053782067 0.0355230000 486826369 0 402718720 -0.1689696759 0.0804447234 -0.1663488746 1943 1311867235.2061970234 0.1783693135 0.1666654870 0.2106595784 0.0053772246 0.0370650000 486829513 0 402718720 -0.1696769446 0.0788542628 -0.1663067639 1944 1311867235.2422571182 0.1778191775 0.1666712245 0.2106595784 0.0053758627 0.0389110000 486832825 0 402718720 -0.1695978343 0.0796963945 -0.1663179249 1945 1311867235.2741830349 0.1782757044 0.1666771908 0.2106595784 0.0053746886 0.0360060000 486835801 0 402718720 -0.1704125255 0.0788861513 -0.1659511179 1946 1311867235.3062019348 0.1782533526 0.1666831395 0.2106595784 0.0053734388 0.0454320000 486839001 0 402718720 -0.1713126302 0.0781989619 -0.1657911092 1947 1311867235.3422889709 0.1768265218 0.1666883493 0.2106595784 0.0053903541 0.0456430000 486842201 0 402718720 -0.1711960137 0.0782035738 -0.1656846851 1948 1311867235.3743910789 0.1774090827 0.1666938527 0.2106595784 0.0054018013 0.0440380000 486845345 0 402718720 -0.1716545522 0.0778778195 -0.1654514819 1949 1311867235.4062139988 0.1775289178 0.1666994120 0.2106595784 0.0054004350 0.0438620000 486848545 0 402718720 -0.1722602695 0.0776064321 -0.1650219411 1950 1311867235.4422221184 0.1769091338 0.1667046478 0.2106595784 0.0053993824 0.0435450000 486851857 0 402718720 -0.1723883152 0.0783534944 -0.1648082882 1951 1311867235.4741671085 0.1770017594 0.1667099256 0.2106595784 0.0053983236 0.0437230000 486854889 0 402718720 -0.1721789390 0.0788162053 -0.1640305668 1952 1311867235.5061590672 0.1765731275 0.1667149785 0.2106595784 0.0053977244 0.0432780000 486858033 0 402718720 -0.1725779176 0.0776160285 -0.1632129997 1953 1311867235.5423209667 0.1761125326 0.1667197903 0.2106595784 0.0053963628 0.0424850000 486861345 0 402718720 -0.1724708080 0.0785513893 -0.1629083604 1954 1311867235.5741930008 0.1765062213 0.1667247988 0.2106595784 0.0053961027 0.0439250000 486864433 0 402718720 -0.1724552214 0.0785686225 -0.1621286273 1955 1311867235.6061949730 0.1766662598 0.1667298839 0.2106595784 0.0053948391 0.0419720000 486867633 0 402718720 -0.1729350835 0.0763600022 -0.1613279730 1956 1311867235.6424438953 0.1761351824 0.1667346923 0.2106595784 0.0053934940 0.0473180000 486870889 0 402718720 -0.1726221144 0.0772276223 -0.1619003266 1957 1311867235.6742379665 0.1763841808 0.1667396231 0.2106595784 0.0053921639 0.0421300000 486873977 0 402718720 -0.1727072299 0.0771021470 -0.1613150388 1958 1311867235.7063670158 0.1762238592 0.1667444669 0.2106595784 0.0053908674 0.0456560000 486877177 0 402718720 -0.1730723381 0.0762579888 -0.1613110155 1959 1311867235.7423110008 0.1758622676 0.1667491212 0.2106595784 0.0053896734 0.0415560000 486880433 0 402718720 -0.1727928668 0.0773469284 -0.1612998247 1960 1311867235.7743389606 0.1752941012 0.1667534809 0.2106595784 0.0053885977 0.0404040000 486883521 0 402718720 -0.1723126024 0.0760599971 -0.1603657603 1961 1311867235.8063130379 0.1753906161 0.1667578854 0.2106595784 0.0053873875 0.0451000000 486886665 0 402718720 -0.1730510890 0.0746919811 -0.1598764509 1962 1311867235.8422799110 0.1753468066 0.1667622630 0.2106595784 0.0053868630 0.0425920000 486889921 0 402718720 -0.1731386930 0.0767553970 -0.1597271264 1963 1311867235.8742089272 0.1760530919 0.1667669960 0.2106595784 0.0053857203 0.0426650000 486893065 0 402718720 -0.1739278734 0.0759761333 -0.1583092958 1964 1311867235.9063739777 0.1753839403 0.1667713834 0.2106595784 0.0053844058 0.0436360000 486896209 0 402718720 -0.1740261614 0.0750867277 -0.1580574065 1965 1311867235.9423429966 0.1746408939 0.1667753883 0.2106595784 0.0053832282 0.0443660000 486899465 0 402718720 -0.1734687090 0.0760595873 -0.1578769535 1966 1311867235.9741959572 0.1750797629 0.1667796123 0.2106595784 0.0053821672 0.0440270000 486902609 0 402718720 -0.1741859019 0.0748746991 -0.1569332331 1967 1311867236.0063738823 0.1748928130 0.1667837369 0.2106595784 0.0053809197 0.0454570000 486905753 0 402718720 -0.1745547652 0.0746530220 -0.1566443741 1968 1311867236.0423779488 0.1744408458 0.1667876277 0.2106595784 0.0053795594 0.0441590000 486909065 0 402718720 -0.1747038513 0.0752788112 -0.1563396901 1969 1311867236.0742259026 0.1747195125 0.1667916561 0.2106595784 0.0053784610 0.0375340000 486912097 0 402718720 -0.1755618751 0.0748229697 -0.1553672552 1970 1311867236.1063580513 0.1742877364 0.1667954612 0.2106595784 0.0053771321 0.0375720000 486915297 0 402718720 -0.1758736521 0.0746820420 -0.1548343301 1971 1311867236.1423580647 0.1738124043 0.1667990213 0.2106595784 0.0053759075 0.0387410000 486918497 0 402718720 -0.1753772199 0.0742132589 -0.1532934010 1972 1311867236.1742420197 0.1737843752 0.1668025636 0.2106595784 0.0053746557 0.0350590000 486921585 0 402718720 -0.1761458814 0.0743608326 -0.1527421623 1973 1311867236.2062220573 0.1735817492 0.1668059996 0.2106595784 0.0053733202 0.0360830000 486924785 0 402718720 -0.1769969463 0.0742055550 -0.1517523676 1974 1311867236.2423429489 0.1727959812 0.1668090340 0.2106595784 0.0053724141 0.0375760000 486927985 0 402718720 -0.1772418320 0.0742936954 -0.1509640366 1975 1311867236.2742660046 0.1727045476 0.1668120191 0.2106595784 0.0053711419 0.0349660000 486931129 0 402718720 -0.1777617931 0.0742036700 -0.1499392986 1976 1311867236.3064289093 0.1724957973 0.1668148955 0.2106595784 0.0053698265 0.0364350000 486934329 0 402718720 -0.1780869663 0.0742188022 -0.1490728557 1977 1311867236.3422911167 0.1718486547 0.1668174417 0.2106595784 0.0053690127 0.0360880000 486937529 0 402718720 -0.1778589040 0.0735882744 -0.1479206383 1978 1311867236.3742980957 0.1720274240 0.1668200756 0.2106595784 0.0053691662 0.0348730000 486940673 0 402718720 -0.1786075383 0.0731240436 -0.1469106972 1979 1311867236.4062509537 0.1711788923 0.1668222782 0.2106595784 0.0053691361 0.0337590000 486943873 0 402718720 -0.1787153035 0.0734599605 -0.1461146474 1980 1311867236.4423909187 0.1705015898 0.1668241364 0.2106595784 0.0053687830 0.0362790000 486947185 0 402718720 -0.1780512631 0.0731972679 -0.1450864524 1981 1311867236.4743850231 0.1707334816 0.1668261098 0.2106595784 0.0053681565 0.0348980000 486950273 0 402718720 -0.1785007566 0.0726771429 -0.1438157707 1982 1311867236.5063140392 0.1703609079 0.1668278933 0.2106595784 0.0053677787 0.0350610000 486953417 0 402718720 -0.1785337180 0.0730740130 -0.1428070664 1983 1311867236.5423541069 0.1698513031 0.1668294179 0.2106595784 0.0053677105 0.0343510000 486956729 0 402718720 -0.1784309447 0.0731604248 -0.1414479315 1984 1311867236.5742170811 0.1694825888 0.1668307552 0.2106595784 0.0053664134 0.0352220000 486959817 0 402718720 -0.1782139838 0.0721146837 -0.1399721503 1985 1311867236.6062879562 0.1692651063 0.1668319816 0.2106595784 0.0053651053 0.0326330000 486962905 0 402718720 -0.1781699508 0.0710988343 -0.1383178383 1986 1311867236.6423881054 0.1683476120 0.1668327447 0.2106595784 0.0053638834 0.0352970000 486966217 0 402718720 -0.1776537746 0.0719817057 -0.1374182552 1987 1311867236.6744780540 0.1682800949 0.1668334732 0.2106595784 0.0053627894 0.0370800000 486969305 0 402718720 -0.1775660813 0.0721047148 -0.1357193738 1988 1311867236.7065870762 0.1686380655 0.1668343809 0.2106595784 0.0053626828 0.0368290000 486972505 0 402718720 -0.1784921438 0.0717727840 -0.1338159740 1989 1311867236.7424709797 0.1671544462 0.1668345418 0.2106595784 0.0053631220 0.0380190000 486975761 0 402718720 -0.1773897409 0.0710267127 -0.1322903037 1990 1311867236.7744069099 0.1669420749 0.1668345958 0.2106595784 0.0053628730 0.0358380000 486978849 0 402718720 -0.1767667681 0.0713245794 -0.1308188289 1991 1311867236.8063890934 0.1673848182 0.1668348722 0.2106595784 0.0053616631 0.0351560000 486981993 0 402718720 -0.1780047119 0.0707141012 -0.1290687621 1992 1311867236.8423969746 0.1666025519 0.1668347556 0.2106595784 0.0053622731 0.0352020000 486985193 0 402718720 -0.1775403768 0.0710187256 -0.1274212897 1993 1311867236.8744750023 0.1662787646 0.1668344766 0.2106595784 0.0053610383 0.0333190000 486988393 0 402718720 -0.1774901003 0.0703332499 -0.1256939620 1994 1311867236.9062860012 0.1661744416 0.1668341456 0.2106595784 0.0053617188 0.0338440000 486991425 0 402718720 -0.1777690500 0.0695364475 -0.1240182295 1995 1311867236.9424860477 0.1651974767 0.1668333252 0.2106595784 0.0053612831 0.0362820000 486994737 0 402718720 -0.1776886433 0.0693094805 -0.1226691008 1996 1311867236.9743099213 0.1649283022 0.1668323708 0.2106595784 0.0053601237 0.0355760000 486997825 0 402718720 -0.1779092401 0.0706883669 -0.1214475483 1997 1311867237.0064570904 0.1650259346 0.1668314662 0.2106595784 0.0053598953 0.0370250000 487000969 0 402718720 -0.1788789183 0.0700998083 -0.1190439016 1998 1311867237.0423519611 0.1636044234 0.1668298511 0.2106595784 0.0053613235 0.0383420000 487004281 0 402718720 -0.1788591146 0.0697313026 -0.1178792566 1999 1311867237.0742869377 0.1633598357 0.1668281152 0.2106595784 0.0053614298 0.0365300000 487007369 0 402718720 -0.1785158813 0.0716409013 -0.1162825301 2000 1311867237.1063759327 0.1636371166 0.1668265197 0.2106595784 0.0053602035 0.0361290000 487010569 0 402718720 -0.1798837930 0.0703579634 -0.1139841825 2001 1311867237.1424009800 0.1627494693 0.1668244822 0.2106595784 0.0053593263 0.0368380000 487013769 0 402718720 -0.1803400815 0.0695200115 -0.1127643958 2002 1311867237.1743369102 0.1616882682 0.1668219167 0.2106595784 0.0053580320 0.0341980000 487016913 0 402718720 -0.1796000749 0.0705892444 -0.1117694676 2003 1311867237.2063510418 0.1623057276 0.1668196619 0.2106595784 0.0053573628 0.0334770000 487020057 0 402718720 -0.1805964559 0.0691285282 -0.1095990837 2004 1311867237.2423889637 0.1609675735 0.1668167417 0.2106595784 0.0053574538 0.0373980000 487023313 0 402718720 -0.1807350218 0.0679055452 -0.1086161807 2005 1311867237.2744851112 0.1605030000 0.1668135927 0.2106595784 0.0053561956 0.0360970000 487026457 0 402718720 -0.1809065640 0.0690587759 -0.1080701798 2006 1311867237.3068330288 0.1605361402 0.1668104634 0.2106595784 0.0053549240 0.0341440000 487029657 0 402718720 -0.1812503189 0.0689373910 -0.1063526124 2007 1311867237.3424780369 0.1602560580 0.1668071976 0.2106595784 0.0053536349 0.0383040000 487032857 0 402718720 -0.1820739508 0.0680283606 -0.1052226201 2008 1311867237.3744280338 0.1597320288 0.1668036741 0.2106595784 0.0053549297 0.0363630000 487036001 0 402718720 -0.1819056422 0.0689632520 -0.1044460610 2009 1311867237.4065289497 0.1596608460 0.1668001187 0.2106595784 0.0053538728 0.0361370000 487039201 0 402718720 -0.1825117767 0.0687384158 -0.1024005562 2010 1311867237.4425020218 0.1584434509 0.1667959612 0.2106595784 0.0053567224 0.0374050000 487042401 0 402718720 -0.1822351068 0.0667056218 -0.1010763794 2011 1311867237.4744338989 0.1585368514 0.1667918542 0.2106595784 0.0053562583 0.0368770000 487045545 0 402718720 -0.1826166660 0.0682173818 -0.1001341641 2012 1311867237.5063641071 0.1584827155 0.1667877244 0.2106595784 0.0053561282 0.0366790000 487048689 0 402718720 -0.1832113564 0.0674401000 -0.0979441926 2013 1311867237.5425050259 0.1573804766 0.1667830512 0.2106595784 0.0053552033 0.0377210000 487051945 0 402718720 -0.1829521954 0.0655774996 -0.0965324491 2014 1311867237.5743029118 0.1567468643 0.1667780680 0.2106595784 0.0053551018 0.0373090000 487055089 0 402718720 -0.1823274344 0.0669433624 -0.0956858620 2015 1311867237.6064100266 0.1573549360 0.1667733915 0.2106595784 0.0053541747 0.0367060000 487058289 0 402718720 -0.1829545200 0.0663822889 -0.0934187248 2016 1311867237.6423790455 0.1565361470 0.1667683135 0.2106595784 0.0053574678 0.0376100000 487061545 0 402718720 -0.1834308505 0.0647908375 -0.0919139981 2017 1311867237.6744120121 0.1558515280 0.1667629011 0.2106595784 0.0053568699 0.0349290000 487064633 0 402718720 -0.1828072518 0.0651187375 -0.0907156467 2018 1311867237.7063660622 0.1553175598 0.1667572295 0.2106595784 0.0053555521 0.0367240000 487067833 0 402718720 -0.1824358404 0.0650145188 -0.0891060159 2019 1311867237.7425839901 0.1552764177 0.1667515431 0.2106595784 0.0053544711 0.0375090000 487071089 0 402718720 -0.1832423359 0.0635059327 -0.0871269256 2020 1311867237.7745900154 0.1548961848 0.1667456741 0.2106595784 0.0053531719 0.0370310000 487074233 0 402718720 -0.1835288852 0.0643097833 -0.0859267935 2021 1311867237.8064579964 0.1547332853 0.1667397303 0.2106595784 0.0053520353 0.0358970000 487077377 0 402718720 -0.1839281917 0.0649173036 -0.0841112956 2022 1311867237.8425009251 0.1541164666 0.1667334873 0.2106595784 0.0053520773 0.0374770000 487080689 0 402718720 -0.1840304732 0.0639602989 -0.0818854719 2023 1311867237.8745510578 0.1529977918 0.1667266976 0.2106595784 0.0053587913 0.0373430000 487083777 0 402718720 -0.1833773702 0.0645574331 -0.0806439593 2024 1311867237.9064331055 0.1531381607 0.1667199839 0.2106595784 0.0053599303 0.0382850000 487086921 0 402718720 -0.1835722923 0.0647726655 -0.0784312859 2025 1311867237.9426600933 0.1525688171 0.1667129956 0.2106595784 0.0053593604 0.0362560000 487090065 0 402718720 -0.1837713271 0.0635634661 -0.0762787759 2026 1311867237.9744310379 0.1521345526 0.1667058000 0.2106595784 0.0053588458 0.0350260000 487093209 0 402718720 -0.1838862151 0.0631055683 -0.0747591406 2027 1311867238.0065000057 0.1513877362 0.1666982429 0.2106595784 0.0053604794 0.0358050000 487096409 0 402718720 -0.1831545830 0.0645421594 -0.0738193467 2028 1311867238.0425720215 0.1509719491 0.1666904884 0.2106595784 0.0053606863 0.0375130000 487099553 0 402718720 -0.1828379929 0.0635646507 -0.0713174716 2029 1311867238.0745151043 0.1511805207 0.1666828442 0.2106595784 0.0053595119 0.0362470000 487102753 0 402718720 -0.1832384914 0.0614019483 -0.0691475272 2030 1311867238.1064291000 0.1498269886 0.1666745408 0.2106595784 0.0053590505 0.0384180000 487105897 0 402718720 -0.1823588014 0.0616868474 -0.0686120242 2031 1311867238.1424019337 0.1492631137 0.1666659680 0.2106595784 0.0053599799 0.0375680000 487109209 0 402718720 -0.1815374941 0.0629968122 -0.0670883507 2032 1311867238.1745769978 0.1505594701 0.1666580416 0.2106595784 0.0053590895 0.0366460000 487112297 0 402718720 -0.1827632040 0.0617973134 -0.0644512028 2033 1311867238.2064669132 0.1494653374 0.1666495848 0.2106595784 0.0053738266 0.0367570000 487115441 0 402718720 -0.1824698746 0.0621898398 -0.0634753257 2034 1311867238.2424540520 0.1482605040 0.1666405439 0.2106595784 0.0053731774 0.0379200000 487118753 0 402718720 -0.1801409274 0.0630927235 -0.0616914332 2035 1311867238.2745521069 0.1483721286 0.1666315668 0.2106595784 0.0053723155 0.0352050000 487121841 0 402718720 -0.1792418510 0.0603665039 -0.0588725768 2036 1311867238.3063769341 0.1473726183 0.1666221076 0.2106595784 0.0053736480 0.0364900000 487124985 0 402718720 -0.1787280440 0.0598116815 -0.0578014851 2037 1311867238.3425319195 0.1478458792 0.1666128900 0.2106595784 0.0053803560 0.0369840000 487128297 0 402718720 -0.1787859052 0.0603732690 -0.0560753308 2038 1311867238.3744390011 0.1479353756 0.1666037254 0.2106595784 0.0053791089 0.0370190000 487131385 0 402718720 -0.1785417795 0.0590181090 -0.0539406165 2039 1311867238.4064741135 0.1467687935 0.1665939976 0.2106595784 0.0053786550 0.0366400000 487134585 0 402718720 -0.1770941317 0.0574462265 -0.0522425100 2040 1311867238.4424209595 0.1460071057 0.1665839060 0.2106595784 0.0053787972 0.0361110000 487137785 0 402718720 -0.1759151071 0.0576089919 -0.0511890352 2041 1311867238.4744260311 0.1467704475 0.1665741983 0.2106595784 0.0053782980 0.3131930000 499462121 0 402718720 -0.1768724918 0.0571518019 -0.0490211546 2042 1311867238.5064730644 0.1462184191 0.1665642297 0.2106595784 0.0053771597 0.0333530000 503124473 0 402718720 -0.1759233922 0.0562062785 -0.0472765751 2043 1311867238.5427029133 0.1447165310 0.1665535358 0.2106595784 0.0053793470 0.0366740000 506319921 0 402718720 -0.1742244959 0.0565841608 -0.0461465642 2044 1311867238.5746150017 0.1455492973 0.1665432598 0.2106595784 0.0053833137 0.0273220000 506323065 0 402718720 -0.1748748720 0.0556139983 -0.0437156819 2045 1311867238.6064128876 0.1458417326 0.1665331368 0.2106595784 0.0053822126 0.0288030000 506326209 0 402718720 -0.1752412021 0.0546833090 -0.0415235981 2046 1311867238.6423780918 0.1449133158 0.1665225699 0.2106595784 0.0053821063 0.0296350000 506329409 0 402718720 -0.1746881902 0.0546839163 -0.0398711525 2047 1311867238.6744050980 0.1437456310 0.1665114429 0.2106595784 0.0053810773 0.0297930000 506332553 0 402718720 -0.1731459498 0.0542443655 -0.0376138985 2048 1311867238.7064859867 0.1432315707 0.1665000758 0.2106595784 0.0053819142 0.0276770000 506335697 0 402718720 -0.1730854362 0.0532331653 -0.0353684053 2049 1311867238.7425220013 0.1434821486 0.1664888420 0.2106595784 0.0053820550 0.0293620000 506552001 0 402718720 -0.1737862825 0.0534424409 -0.0331511945 2050 1311867238.7743968964 0.1423139125 0.1664770494 0.2106595784 0.0053827665 0.0302710000 506964689 0 402718720 -0.1727264374 0.0538028441 -0.0309118573 2051 1311867238.8064219952 0.1415610760 0.1664649012 0.2106595784 0.0053829677 0.0318800000 506967889 0 402718720 -0.1718593985 0.0523932278 -0.0278250221 2052 1311867238.8425409794 0.1405805200 0.1664522870 0.2106595784 0.0053838350 0.0350520000 506971145 0 402718720 -0.1712533832 0.0523097552 -0.0257430580 2053 1311867238.8744180202 0.1402903497 0.1664395437 0.2106595784 0.0053846764 0.0302800000 506974233 0 402718720 -0.1712003797 0.0528265052 -0.0235916413 2054 1311867238.9064509869 0.1401609182 0.1664267498 0.2106595784 0.0053834217 0.0326110000 506977377 0 402718720 -0.1711034179 0.0520421043 -0.0203711353 2055 1311867238.9425098896 0.1393503845 0.1664135740 0.2106595784 0.0053848618 0.0359810000 506980633 0 402718720 -0.1711872220 0.0502228737 -0.0175156407 2056 1311867238.9745268822 0.1382939368 0.1663998971 0.2106595784 0.0053836643 0.0302490000 506983833 0 402718720 -0.1697824597 0.0496023819 -0.0156266727 2057 1311867239.0064051151 0.1379534900 0.1663860680 0.2106595784 0.0053853175 0.0313200000 506986977 0 402718720 -0.1696992666 0.0505122803 -0.0135318898 2058 1311867239.0425870419 0.1379437894 0.1663722477 0.2106595784 0.0053871839 0.0317340000 506990289 0 402718720 -0.1700772196 0.0484412573 -0.0101872236 2059 1311867239.0745921135 0.1377092749 0.1663583269 0.2106595784 0.0053900650 0.0302220000 506993377 0 402718720 -0.1699546278 0.0482724607 -0.0079517616 2060 1311867239.1064159870 0.1361863464 0.1663436803 0.2106595784 0.0053917677 0.0303790000 506996521 0 402718720 -0.1686974466 0.0483718477 -0.0059171543 2061 1311867239.1430389881 0.1355582029 0.1663287431 0.2106595784 0.0053937733 0.0313930000 506999777 0 402718720 -0.1680418402 0.0473236553 -0.0030755580 2062 1311867239.1745591164 0.1348499507 0.1663134770 0.2106595784 0.0053945421 0.0304910000 507002865 0 402718720 -0.1672689170 0.0464531444 -0.0003778846 2063 1311867239.2065069675 0.1346578449 0.1662981325 0.2106595784 0.0053933126 0.0332850000 507006009 0 402718720 -0.1668336838 0.0465890095 0.0019567034 2064 1311867239.2426149845 0.1345023811 0.1662827276 0.2106595784 0.0053935643 0.0344360000 507009265 0 402718720 -0.1667061746 0.0452550352 0.0049336348 2065 1311867239.2744660378 0.1333951503 0.1662668014 0.2106595784 0.0053964972 0.0307990000 507012353 0 402718720 -0.1652638912 0.0436893888 0.0078046555 2066 1311867239.3064088821 0.1329977065 0.1662506982 0.2106595784 0.0053954725 0.0319130000 507015553 0 402718720 -0.1641971022 0.0434417836 0.0099370955 2067 1311867239.3424859047 0.1322967112 0.1662342715 0.2106595784 0.0053944224 0.0334190000 507018753 0 402718720 -0.1635753661 0.0424435399 0.0124845728 2068 1311867239.3745620251 0.1319931597 0.1662177139 0.2106595784 0.0053936640 0.0312160000 507021897 0 402718720 -0.1629015505 0.0402431488 0.0153436419 2069 1311867239.4065918922 0.1319069564 0.1662011307 0.2106595784 0.0053942975 0.0310930000 507025097 0 402718720 -0.1623255163 0.0391421318 0.0174618587 2070 1311867239.4426341057 0.1310951561 0.1661841713 0.2106595784 0.0053936051 0.0335970000 507028353 0 402718720 -0.1614102721 0.0385495052 0.0193309933 2071 1311867239.4745171070 0.1311012357 0.1661672312 0.2106595784 0.0053924334 0.0318070000 507031441 0 402718720 -0.1607891023 0.0364910811 0.0219127983 2072 1311867239.5065560341 0.1301829517 0.1661498643 0.2106595784 0.0053915637 0.0332890000 507034641 0 402718720 -0.1594149023 0.0347725488 0.0240148809 2073 1311867239.5426371098 0.1302996129 0.1661325704 0.2106595784 0.0053904198 0.0347920000 507037841 0 402718720 -0.1589515507 0.0347963870 0.0255475715 2074 1311867239.5746030807 0.1299685091 0.1661151335 0.2106595784 0.0053898439 0.0343140000 507040985 0 402718720 -0.1586016715 0.0334972665 0.0279966965 2075 1311867239.6064119339 0.1294581443 0.1660974675 0.2106595784 0.0053912927 0.0346480000 507044185 0 402718720 -0.1571394056 0.0314813331 0.0305489376 2076 1311867239.6425809860 0.1282241791 0.1660792241 0.2106595784 0.0053947338 0.0357670000 507047385 0 402718720 -0.1557046920 0.0307841897 0.0321354195 2077 1311867239.6745851040 0.1287086457 0.1660612315 0.2106595784 0.0053999719 0.0353760000 507050529 0 402718720 -0.1553358138 0.0313439816 0.0339336544 2078 1311867239.7064199448 0.1292409301 0.1660435124 0.2106595784 0.0053994087 0.0362750000 507053729 0 402718720 -0.1556978226 0.0305856392 0.0362565257 2079 1311867239.7425320148 0.1280633211 0.1660252439 0.2106595784 0.0053992814 0.0353990000 507056985 0 402718720 -0.1544252485 0.0294063706 0.0387455039 2080 1311867239.7744889259 0.1274462640 0.1660066963 0.2106595784 0.0053985151 0.0354160000 507060129 0 402718720 -0.1536207497 0.0302346498 0.0400668979 2081 1311867239.8065121174 0.1281732023 0.1659885159 0.2106595784 0.0053982491 0.3701700000 519393273 0 402718720 -0.1541605443 0.0304043908 0.0431359857 2082 1311867239.8425819874 0.1274317503 0.1659699968 0.2106595784 0.0053980398 0.0276660000 523055225 0 402718720 -0.1540972292 0.0299978182 0.0452015065 2083 1311867239.8745760918 0.1261308193 0.1659508709 0.2106595784 0.0053968973 0.0370150000 526250561 0 402718720 -0.1525002271 0.0303142443 0.0473849513 2084 1311867239.9065690041 0.1260424405 0.1659317210 0.2106595784 0.0053959888 0.0325120000 526253705 0 402718720 -0.1526060849 0.0293891896 0.0499226302 2085 1311867239.9424080849 0.1257829070 0.1659124650 0.2106595784 0.0053980731 0.0291480000 526257017 0 402718720 -0.1530107856 0.0288179237 0.0521833338 2086 1311867239.9762129784 0.1252921969 0.1658929922 0.2106595784 0.0054013806 0.0276560000 526260161 0 402718720 -0.1526152492 0.0288797691 0.0544365346 2087 1311867240.0067460537 0.1240983158 0.1658729660 0.2106595784 0.0054006841 0.0272600000 526263305 0 402718720 -0.1519031525 0.0276343413 0.0566911921 2088 1311867240.0425059795 0.1236119047 0.1658527260 0.2106595784 0.0053998144 0.0288230000 526266505 0 402718720 -0.1515942663 0.0277483966 0.0584282428 2089 1311867240.0745980740 0.1237705797 0.1658325814 0.2106595784 0.0054014544 0.0285350000 526269593 0 402718720 -0.1516706944 0.0277418327 0.0607677810 2090 1311867240.1065590382 0.1226278171 0.1658119092 0.2106595784 0.0054089826 0.0299060000 526272793 0 402718720 -0.1507624984 0.0268851705 0.0628382638 2091 1311867240.1428439617 0.1221711561 0.1657910385 0.2106595784 0.0054109997 0.0307370000 526275993 0 402718720 -0.1496862024 0.0275801774 0.0650079250 2092 1311867240.1744658947 0.1225668862 0.1657703768 0.2106595784 0.0054099422 0.0324630000 526279193 0 402718720 -0.1504870802 0.0265673641 0.0676329136 2093 1311867240.2065520287 0.1218001395 0.1657493686 0.2106595784 0.0054086994 0.0321060000 526282337 0 402718720 -0.1491654217 0.0263083111 0.0694644675 2094 1311867240.2424330711 0.1210208759 0.1657280083 0.2106595784 0.0054075353 0.0294650000 526285649 0 402718720 -0.1477594972 0.0265109539 0.0714351237 2095 1311867240.2746770382 0.1213308945 0.1657068163 0.2106595784 0.0054063801 0.0329870000 526288737 0 402718720 -0.1477485746 0.0259657521 0.0738771781 2096 1311867240.3065440655 0.1212903857 0.1656856253 0.2106595784 0.0054052150 0.0327480000 526291825 0 402718720 -0.1474340707 0.0253613982 0.0757114515 2097 1311867240.3424808979 0.1208176240 0.1656642290 0.2106595784 0.0054058427 0.0287070000 526295081 0 402718720 -0.1472391486 0.0242586434 0.0779508129 2098 1311867240.3744659424 0.1204658672 0.1656426855 0.2106595784 0.0054047498 0.0308500000 526298169 0 402718720 -0.1463984698 0.0242394079 0.0794379264 2099 1311867240.4066619873 0.1202617884 0.1656210652 0.2106595784 0.0054049069 0.0324850000 526301257 0 402718720 -0.1461777687 0.0226946007 0.0814683810 2100 1311867240.4425981045 0.1197956800 0.1655992436 0.2106595784 0.0054043803 0.0295930000 526304401 0 402718720 -0.1459992826 0.0214401502 0.0835267082 2101 1311867240.4745359421 0.1199728996 0.1655775271 0.2106595784 0.0054070244 0.0308220000 526307545 0 402718720 -0.1458801180 0.0210292470 0.0850200877 2102 1311867240.5064690113 0.1193725616 0.1655555457 0.2106595784 0.0054072599 0.0305960000 526310745 0 402718720 -0.1454096287 0.0198428053 0.0865824744 2103 1311867240.5425899029 0.1191649213 0.1655334864 0.2106595784 0.0054065022 0.0328850000 526313945 0 402718720 -0.1453922242 0.0192113295 0.0876425877 2104 1311867240.5745110512 0.1190985069 0.1655114166 0.2106595784 0.0054065724 0.0332040000 526317089 0 402718720 -0.1454516649 0.0189844128 0.0890273973 2105 1311867240.6065568924 0.1186215207 0.1654891411 0.2106595784 0.0054056091 0.0344130000 526320289 0 402718720 -0.1448444575 0.0171302613 0.0905021578 2106 1311867240.6427950859 0.1183468476 0.1654667563 0.2106595784 0.0054099600 0.0322590000 526323545 0 402718720 -0.1446065903 0.0168952085 0.0914531127 2107 1311867240.6746129990 0.1187103763 0.1654445654 0.2106595784 0.0054116987 0.0325810000 526326633 0 402718720 -0.1455020458 0.0161680039 0.0924134403 2108 1311867240.7065620422 0.1177327186 0.1654219317 0.2106595784 0.0054110208 0.0325200000 526329777 0 402718720 -0.1451317221 0.0161911752 0.0931790322 2109 1311867240.7426309586 0.1176466644 0.1653992786 0.2106595784 0.0054099593 0.0318000000 526332977 0 402718720 -0.1454934776 0.0168064646 0.0941227749 2110 1311867240.7746779919 0.1179138198 0.1653767737 0.2106595784 0.0054087032 0.0314280000 526336177 0 402718720 -0.1463337690 0.0163836032 0.0957654789 2111 1311867240.8066051006 0.1171395481 0.1653539232 0.2106595784 0.0054074299 0.0325180000 526339321 0 402718720 -0.1462038308 0.0171950739 0.0966435596 2112 1311867240.8429400921 0.1166829467 0.1653308783 0.2106595784 0.0054064479 0.0314720000 526342521 0 402718720 -0.1470316350 0.0175076388 0.0982045159 2113 1311867240.8748428822 0.1158054024 0.1653074398 0.2106595784 0.0054053830 0.0317750000 526345721 0 402718720 -0.1468162388 0.0176395327 0.0999060422 2114 1311867240.9065480232 0.1150412112 0.1652836620 0.2106595784 0.0054050776 0.0322350000 526348865 0 402718720 -0.1471557170 0.0185407531 0.1014489606 2115 1311867240.9425590038 0.1144015715 0.1652596043 0.2106595784 0.0054038937 0.0319790000 526352121 0 402718720 -0.1477777958 0.0192087889 0.1032116488 2116 1311867240.9746220112 0.1137545705 0.1652352635 0.2106595784 0.0054027568 0.0321450000 526355265 0 402718720 -0.1478553563 0.0189236142 0.1054153368 2117 1311867241.0067160130 0.1134392470 0.1652107968 0.2106595784 0.0054016567 0.0324970000 526358465 0 402718720 -0.1485820711 0.0194023103 0.1073170155 2118 1311867241.0426230431 0.1125870869 0.1651859509 0.2106595784 0.0054004955 0.0329400000 526361721 0 402718720 -0.1490179896 0.0214521233 0.1089389026 2119 1311867241.0747919083 0.1120539159 0.1651608768 0.2106595784 0.0053994305 0.0319840000 526364809 0 402718720 -0.1493772119 0.0209663436 0.1114122719 2120 1311867241.1067790985 0.1115056276 0.1651355677 0.2106595784 0.0053989859 0.0311050000 526368009 0 402718720 -0.1500895917 0.0198526457 0.1137586087 2121 1311867241.1428539753 0.1108356044 0.1651099666 0.2106595784 0.0054007308 0.0327270000 526371153 0 402718720 -0.1508022547 0.0209365860 0.1153229252 2122 1311867241.1747300625 0.1093276888 0.1650836790 0.2106595784 0.0054014562 0.0322620000 526374353 0 402718720 -0.1503614485 0.0200896394 0.1175794825 2123 1311867241.2067210674 0.1092653498 0.1650573868 0.2106595784 0.0054002362 0.0326760000 526377497 0 402718720 -0.1512001008 0.0204381384 0.1193379611 2124 1311867241.2426309586 0.1094513834 0.1650312070 0.2106595784 0.0053991267 0.0327260000 526380809 0 402718720 -0.1519293338 0.0217218101 0.1206183136 2125 1311867241.2750689983 0.1087976769 0.1650047441 0.2106595784 0.0054008378 0.0327620000 526383897 0 402718720 -0.1522321105 0.0203748252 0.1225142553 2126 1311867241.3107690811 0.1086777300 0.1649782498 0.2106595784 0.0054000708 0.0333310000 526387153 0 402718720 -0.1531051844 0.0208683442 0.1237110272 2127 1311867241.3425819874 0.1086156145 0.1649517511 0.2106595784 0.0054029490 0.0341430000 526390241 0 402718720 -0.1542952210 0.0207868554 0.1252702773 2128 1311867241.3746769428 0.1078455374 0.1649249155 0.2106595784 0.0054037474 0.0360110000 526393441 0 402718720 -0.1546433121 0.0200981610 0.1268074811 2129 1311867241.4106349945 0.1074100509 0.1648979005 0.2106595784 0.0054025331 0.0334970000 526396697 0 402718720 -0.1554659605 0.0198827125 0.1281241626 2130 1311867241.4426200390 0.1076787338 0.1648710370 0.2106595784 0.0054017635 0.0343610000 526399785 0 402718720 -0.1566386521 0.0208040085 0.1291999519 2131 1311867241.4748959541 0.1074948758 0.1648441125 0.2106595784 0.0054028007 0.0329190000 526402929 0 402718720 -0.1574369520 0.0206059627 0.1308044493 2132 1311867241.5107510090 0.1067013666 0.1648168411 0.2106595784 0.0054018586 0.0323780000 526406185 0 402718720 -0.1581286341 0.0201790687 0.1321301311 2133 1311867241.5426020622 0.1062414497 0.1647893796 0.2106595784 0.0054016050 0.0338070000 526409329 0 402718720 -0.1587820947 0.0211344436 0.1329735816 2134 1311867241.5748229027 0.1064075083 0.1647620216 0.2106595784 0.0054014366 0.0333200000 526412473 0 402718720 -0.1598246992 0.0199719258 0.1345672458 2135 1311867241.6106040478 0.1055250093 0.1647342759 0.2106595784 0.0054007609 0.0337670000 526415785 0 402718720 -0.1598888934 0.0198686365 0.1352612227 2136 1311867241.6426270008 0.1053504571 0.1647064745 0.2106595784 0.0053996561 0.0326570000 526418873 0 402718720 -0.1600522548 0.0212282035 0.1354827285 2137 1311867241.6746680737 0.1054329798 0.1646787377 0.2106595784 0.0053984000 0.0326660000 526422017 0 402718720 -0.1609072536 0.0209679529 0.1366101950 2138 1311867241.7107570171 0.1044060364 0.1646505466 0.2106595784 0.0054101569 0.0326540000 526425273 0 402718720 -0.1611109525 0.0211232360 0.1373588294 2139 1311867241.7427489758 0.1046566591 0.1646224990 0.2106595784 0.0054247472 0.0342270000 526428361 0 402718720 -0.1613340676 0.0218992271 0.1378022581 2140 1311867241.7746200562 0.1045468897 0.1645944262 0.2106595784 0.0054236651 0.0339130000 526431561 0 402718720 -0.1617977470 0.0214074627 0.1388453245 2141 1311867241.8107140064 0.1039483622 0.1645661002 0.2106595784 0.0054229105 0.0334730000 526434817 0 402718720 -0.1622768342 0.0209253617 0.1398755163 2142 1311867241.8428399563 0.1031999514 0.1645374512 0.2106595784 0.0054246901 0.0348950000 526437905 0 402718720 -0.1626533866 0.0210981593 0.1406418532 2143 1311867241.8749659061 0.1030470952 0.1645087576 0.2106595784 0.0054238034 0.0338240000 526441105 0 402718720 -0.1631321162 0.0209814981 0.1418383420 2144 1311867241.9105970860 0.1032751128 0.1644801971 0.2106595784 0.0054245548 0.0337290000 526444361 0 402718720 -0.1636804342 0.0210911054 0.1432123035 2145 1311867241.9429340363 0.1026988700 0.1644513947 0.2106595784 0.0054245508 0.0344590000 526447505 0 402718720 -0.1639778018 0.0223044828 0.1445313692 2146 1311867241.9746549129 0.1021202952 0.1644223494 0.2106595784 0.0054298921 0.4047230000 538783273 0 402718720 -0.1647199839 0.0218060762 0.1464857012 2147 1311867242.0108060837 0.1003730595 0.1643925174 0.2106595784 0.0054298329 0.0251140000 542445737 0 402718720 -0.1637687236 0.0209071469 0.1479980201 2148 1311867242.0426700115 0.1002131626 0.1643626388 0.2106595784 0.0054315353 0.0364710000 545641017 0 402718720 -0.1639449149 0.0229370221 0.1486561894 2149 1311867242.0747869015 0.1003962532 0.1643328731 0.2106595784 0.0054317775 0.0322170000 545644161 0 402718720 -0.1650889814 0.0224970095 0.1505099833 2150 1311867242.1107320786 0.0998260230 0.1643028699 0.2106595784 0.0054306442 0.0305730000 545647417 0 402718720 -0.1655916274 0.0227621216 0.1517346948 2151 1311867242.1428799629 0.0989352763 0.1642724805 0.2106595784 0.0054299799 0.0324480000 545650449 0 402718720 -0.1654376537 0.0235933419 0.1525848806 2152 1311867242.1748840809 0.0988621339 0.1642420854 0.2106595784 0.0054334140 0.0308480000 545653593 0 402718720 -0.1661118418 0.0225203652 0.1541674584 2153 1311867242.2106430531 0.0985098928 0.1642115549 0.2106595784 0.0054321725 0.0285150000 545656849 0 402718720 -0.1665430069 0.0232288595 0.1550790519 2154 1311867242.2427189350 0.0981076807 0.1641808660 0.2106595784 0.0054323704 0.0281550000 545659993 0 402718720 -0.1666628569 0.0234757718 0.1564376056 2155 1311867242.2750279903 0.0978314877 0.1641500774 0.2106595784 0.0054314790 0.0303430000 545663137 0 402718720 -0.1668813080 0.0226705801 0.1578960866 2156 1311867242.3107559681 0.0976227894 0.1641192206 0.2106595784 0.0054311315 0.0284230000 545666393 0 402718720 -0.1672123224 0.0231445208 0.1592135727 2157 1311867242.3426249027 0.0971774757 0.1640881859 0.2106595784 0.0054310850 0.0317910000 545669537 0 402718720 -0.1674705297 0.0226945337 0.1606219411 2158 1311867242.3746280670 0.0970099643 0.1640571024 0.2106595784 0.0054298680 0.0302360000 545672681 0 402718720 -0.1674914062 0.0223686732 0.1618936658 2159 1311867242.4106009007 0.0966667607 0.1640258887 0.2106595784 0.0054293335 0.0277720000 545675937 0 402718720 -0.1675218791 0.0224323347 0.1629644930 2160 1311867242.4426701069 0.0965108946 0.1639946318 0.2106595784 0.0054288430 0.0325540000 545679081 0 402718720 -0.1677959710 0.0218776185 0.1642225981 2161 1311867242.4747939110 0.0960702151 0.1639631999 0.2106595784 0.0054282763 0.0294160000 545682225 0 402718720 -0.1677514911 0.0209135730 0.1653606296 2162 1311867242.5107450485 0.0962337628 0.1639318726 0.2106595784 0.0054272277 0.0269250000 545685481 0 402718720 -0.1681355834 0.0213173702 0.1662715524 2163 1311867242.5426769257 0.0953521878 0.1639001668 0.2106595784 0.0054263311 0.0282840000 545688681 0 402718720 -0.1676765680 0.0200104099 0.1674709320 2164 1311867242.5747549534 0.0954280794 0.1638685254 0.2106595784 0.0054283096 0.0285780000 545691769 0 402718720 -0.1679389328 0.0197198689 0.1685369164 2165 1311867242.6108400822 0.0945370942 0.1638365016 0.2106595784 0.0054278755 0.0282810000 545695081 0 402718720 -0.1671736687 0.0193901323 0.1693046689 2166 1311867242.6428620815 0.0945194736 0.1638044993 0.2106595784 0.0054286160 0.0298560000 545698169 0 402718720 -0.1672539264 0.0183978658 0.1706847996 2167 1311867242.6747550964 0.0949103460 0.1637727069 0.2106595784 0.0054276151 0.0273930000 545701313 0 402718720 -0.1679856181 0.0185400024 0.1719710976 2168 1311867242.7107698917 0.0945650488 0.1637407845 0.2106595784 0.0054286443 0.0283030000 545704569 0 402718720 -0.1676450521 0.0193185005 0.1730166376 2169 1311867242.7428359985 0.0937556848 0.1637085185 0.2106595784 0.0054301919 0.0293090000 545707769 0 402718720 -0.1673091352 0.0177711416 0.1748957485 2170 1311867242.7747418880 0.0942253470 0.1636764986 0.2106595784 0.0054289748 0.0281790000 545710857 0 402718720 -0.1678915918 0.0176793728 0.1763066649 2171 1311867242.8109219074 0.0942814648 0.1636445340 0.2106595784 0.0054280814 0.0268470000 545714169 0 402718720 -0.1680082977 0.0187371951 0.1775267422 2172 1311867242.8427250385 0.0932579860 0.1636121277 0.2106595784 0.0054287826 0.0308010000 545717313 0 402718720 -0.1673336625 0.0177184958 0.1790798455 2173 1311867242.8747160435 0.0935745090 0.1635798969 0.2106595784 0.0054284918 0.0295730000 545720401 0 402718720 -0.1672396362 0.0178105067 0.1804305315 2174 1311867242.9107770920 0.0932215229 0.1635475333 0.2106595784 0.0054290082 0.0283940000 545723657 0 402718720 -0.1675799340 0.0182115510 0.1820164323 2175 1311867242.9426360130 0.0934125632 0.1635152873 0.2106595784 0.0054288382 0.0291060000 545726801 0 402718720 -0.1679175496 0.0178251415 0.1837959886 2176 1311867242.9746561050 0.0933498889 0.1634830422 0.2106595784 0.0054276245 0.0289890000 545729945 0 402718720 -0.1681333929 0.0176127348 0.1851976067 2177 1311867243.0106649399 0.0924042687 0.1634503923 0.2106595784 0.0054280988 0.0297130000 545733201 0 402718720 -0.1676834077 0.0175359342 0.1862915605 2178 1311867243.0426819324 0.0921944082 0.1634176761 0.2106595784 0.0054276200 0.0300530000 545736289 0 402718720 -0.1680515260 0.0172331948 0.1879772842 2179 1311867243.0749440193 0.0922385827 0.1633850102 0.2106595784 0.0054265656 0.0284580000 545739489 0 402718720 -0.1684849709 0.0171584059 0.1894781142 2180 1311867243.1107599735 0.0914918929 0.1633520317 0.2106595784 0.0054254151 0.0275880000 545742745 0 402718720 -0.1687240452 0.0167245828 0.1909659058 2181 1311867243.1429419518 0.0908899158 0.1633188074 0.2106595784 0.0054300246 0.0318450000 545745833 0 402718720 -0.1691469848 0.0161230825 0.1924135238 2182 1311867243.1747920513 0.0909167081 0.1632856259 0.2106595784 0.0054387885 0.0312170000 545749033 0 402718720 -0.1695028394 0.0162104443 0.1937922984 2183 1311867243.2106709480 0.0907748863 0.1632524098 0.2106595784 0.0054378219 0.0289620000 545752233 0 402718720 -0.1702253520 0.0157126747 0.1956588328 2184 1311867243.2429230213 0.0903319195 0.1632190213 0.2106595784 0.0054367400 0.0307660000 545755377 0 402718720 -0.1706762463 0.0146956882 0.1971089095 2185 1311867243.2748720646 0.0899672210 0.1631854964 0.2106595784 0.0054354977 0.0304460000 545758465 0 402718720 -0.1707645208 0.0142668812 0.1983373016 2186 1311867243.3109090328 0.0897550434 0.1631519052 0.2106595784 0.0054343964 0.0297140000 545761777 0 402718720 -0.1713384539 0.0138523942 0.1997389346 2187 1311867243.3426809311 0.0896430239 0.1631182934 0.2106595784 0.0054331548 0.0304000000 545764921 0 402718720 -0.1717017591 0.0135714281 0.2012001425 2188 1311867243.3757870197 0.0894002765 0.1630846015 0.2106595784 0.0054321200 0.0306160000 545768065 0 402718720 -0.1720284671 0.0132863838 0.2026487589 2189 1311867243.4120819569 0.0887716413 0.1630506531 0.2106595784 0.0054311107 0.0302170000 545771321 0 402718720 -0.1718515158 0.0127221756 0.2037981004 2190 1311867243.4428861141 0.0888633952 0.1630167776 0.2106595784 0.0054304645 0.3920370000 558167841 0 402718720 -0.1721945107 0.0132624190 0.2050615400 2191 1311867243.4748840332 0.0871696770 0.1629821601 0.2106595784 0.0054308318 0.0258520000 561830193 0 402718720 -0.1709965169 0.0126166437 0.2073052377 2192 1311867243.5109860897 0.0864915550 0.1629472647 0.2106595784 0.0054303874 0.0324590000 565025697 0 402718720 -0.1709090471 0.0121011529 0.2086273581 2193 1311867243.5430259705 0.0860843509 0.1629122155 0.2106595784 0.0054292408 0.0312470000 565028841 0 402718720 -0.1708860099 0.0121566160 0.2098888755 2194 1311867243.5746970177 0.0857173279 0.1628770310 0.2106595784 0.0054282581 0.0291530000 565031929 0 402718720 -0.1710729152 0.0115294615 0.2112697065 2195 1311867243.6107759476 0.0856529996 0.1628418492 0.2106595784 0.0054270680 0.0288810000 565035185 0 402718720 -0.1711036414 0.0115994485 0.2124912590 2196 1311867243.6426849365 0.0855830014 0.1628066676 0.2106595784 0.0054275293 0.0291050000 565038329 0 402718720 -0.1707041413 0.0120089380 0.2134942114 2197 1311867243.6748669147 0.0858140662 0.1627716231 0.2106595784 0.0054263753 0.0276110000 565041473 0 402718720 -0.1711999625 0.0107882405 0.2148255408 2198 1311867243.7109019756 0.0853932798 0.1627364192 0.2106595784 0.0054261301 0.0279650000 565044729 0 402718720 -0.1703821123 0.0110400608 0.2159024775 2199 1311867243.7427608967 0.0847698823 0.1627009637 0.2106595784 0.0054249708 0.0247770000 565047929 0 402718720 -0.1694792211 0.0111344978 0.2169649154 2200 1311867243.7748370171 0.0853155255 0.1626657885 0.2106595784 0.0054249425 0.0270610000 565051017 0 402718720 -0.1697145551 0.0106247086 0.2187617123 2201 1311867243.8107550144 0.0848981962 0.1626304557 0.2106595784 0.0054242816 0.0290140000 565054273 0 402718720 -0.1690217406 0.0108019803 0.2198365778 2202 1311867243.8428249359 0.0848315060 0.1625951246 0.2106595784 0.0054233686 0.0291260000 565057473 0 402718720 -0.1681939960 0.0108047035 0.2213625312 2203 1311867243.8747949600 0.0851312876 0.1625599617 0.2106595784 0.0054222103 0.0298930000 565060561 0 402718720 -0.1682334095 0.0100226393 0.2228130400 2204 1311867243.9110100269 0.0846960396 0.1625246333 0.2106595784 0.0054210681 0.0293700000 565063873 0 402718720 -0.1674636751 0.0099660093 0.2237329185 2205 1311867243.9427649975 0.0851421878 0.1624895392 0.2106595784 0.0054202314 0.0301320000 565067017 0 402718720 -0.1674285233 0.0100072511 0.2253330499 2206 1311867243.9749391079 0.0850101858 0.1624544171 0.2106595784 0.0054193919 0.0288980000 565070105 0 402718720 -0.1671717912 0.0093613807 0.2263480425 2207 1311867244.0109379292 0.0848685130 0.1624192626 0.2106595784 0.0054183391 0.0275460000 565073417 0 402718720 -0.1666874886 0.0092644012 0.2274338007 2208 1311867244.0428740978 0.0849315897 0.1623841686 0.2106595784 0.0054171316 0.0297710000 565076505 0 402718720 -0.1664648503 0.0088255052 0.2288787365 2209 1311867244.0747289658 0.0848395452 0.1623490646 0.2106595784 0.0054159525 0.0276480000 565079649 0 402718720 -0.1662089676 0.0082701510 0.2300446481 2210 1311867244.1107370853 0.0846688822 0.1623139152 0.2106595784 0.0054147648 0.0291610000 565082905 0 402718720 -0.1658091545 0.0081879217 0.2313950211 2211 1311867244.1427519321 0.0845893100 0.1622787616 0.2106595784 0.0054141689 0.0295670000 565086105 0 402718720 -0.1654673815 0.0075841886 0.2329626828 2212 1311867244.1749598980 0.0844279677 0.1622435669 0.2106595784 0.0054129866 0.0280960000 565089193 0 402718720 -0.1649707556 0.0073344889 0.2343561798 2213 1311867244.2109980583 0.0840762183 0.1622082450 0.2106595784 0.0054122403 0.0274000000 565092505 0 402718720 -0.1644293815 0.0074972413 0.2359211445 2214 1311867244.2428369522 0.0842335075 0.1621730260 0.2106595784 0.0054116358 0.0283470000 565095593 0 402718720 -0.1642361283 0.0066970140 0.2378307730 2215 1311867244.2748489380 0.0833483860 0.1621374393 0.2106595784 0.0054144213 0.0293890000 565098737 0 402718720 -0.1637157798 0.0065916604 0.2391763180 2216 1311867244.3110189438 0.0843111649 0.1621023191 0.2106595784 0.0054143520 0.0287190000 565102049 0 402718720 -0.1635805517 0.0076249037 0.2408340126 2217 1311867244.3429450989 0.0836738646 0.1620669432 0.2106595784 0.0054135589 0.0290170000 565105137 0 402718720 -0.1629829556 0.0065592611 0.2427084595 2218 1311867244.3748068810 0.0838536397 0.1620316802 0.2106595784 0.0054148918 0.0304600000 565108281 0 402718720 -0.1627611667 0.0071176952 0.2439891547 2219 1311867244.4109170437 0.0841274709 0.1619965724 0.2106595784 0.0054137259 0.0294290000 565111593 0 402718720 -0.1624602526 0.0074235313 0.2459504902 2220 1311867244.4429390430 0.0839753821 0.1619614277 0.2106595784 0.0054147262 0.0292210000 565114737 0 402718720 -0.1620601714 0.0068768682 0.2477386445 2221 1311867244.4748449326 0.0829289928 0.1619258436 0.2106595784 0.0054142695 0.0296290000 565117825 0 402718720 -0.1605290622 0.0073377951 0.2489280850 2222 1311867244.5109090805 0.0824983269 0.1618900976 0.2106595784 0.0054139581 0.0306280000 565121081 0 402718720 -0.1592868268 0.0079343878 0.2504999638 2223 1311867244.5430870056 0.0825221092 0.1618543945 0.2106595784 0.0054134245 0.0300530000 565124225 0 402718720 -0.1589375734 0.0077336556 0.2524845600 2224 1311867244.5748798847 0.0827038512 0.1618188052 0.2106595784 0.0054122519 0.0305450000 565127313 0 402718720 -0.1584312618 0.0086602010 0.2541118264 2225 1311867244.6107940674 0.0824414492 0.1617831300 0.2106595784 0.0054128545 0.0312580000 565130513 0 402718720 -0.1573306471 0.0092156772 0.2558349371 2226 1311867244.6428279877 0.0823559612 0.1617474484 0.2106595784 0.0054141734 0.0305730000 565133601 0 402718720 -0.1568076462 0.0083767269 0.2580114603 2227 1311867244.6748380661 0.0822387636 0.1617117463 0.2106595784 0.0054129976 0.0307130000 565136689 0 402718720 -0.1558938324 0.0086630015 0.2596994936 2228 1311867244.7109699249 0.0824555233 0.1616761735 0.2106595784 0.0054121540 0.0311750000 565140001 0 402718720 -0.1556242257 0.0082292706 0.2615981102 2229 1311867244.7427959442 0.0822750404 0.1616405516 0.2106595784 0.0054110263 0.0308610000 565143089 0 402718720 -0.1547497958 0.0084315129 0.2629339099 2230 1311867244.7749741077 0.0820600167 0.1616048653 0.2106595784 0.0054099725 0.0312180000 565146233 0 402718720 -0.1538944244 0.0088417064 0.2645679116 2231 1311867244.8109099865 0.0821343958 0.1615692443 0.2106595784 0.0054089131 0.0314280000 565149545 0 402718720 -0.1536923498 0.0078165988 0.2665531337 2232 1311867244.8428199291 0.0818618312 0.1615335331 0.2106595784 0.0054077379 0.0312530000 565152689 0 402718720 -0.1529772878 0.0083714072 0.2676624656 2233 1311867244.8749020100 0.0817427412 0.1614978005 0.2106595784 0.0054073624 0.0310500000 565155777 0 402718720 -0.1526010484 0.0084006405 0.2692343593 2234 1311867244.9108049870 0.0816489980 0.1614620580 0.2106595784 0.0054064804 0.0317430000 565159033 0 402718720 -0.1524558365 0.0076556727 0.2710469067 2235 1311867244.9428389072 0.0821594894 0.1614265759 0.2106595784 0.0054054368 0.0315190000 565162177 0 402718720 -0.1524952501 0.0089772483 0.2725009918 2236 1311867244.9749879837 0.0815048739 0.1613908327 0.2106595784 0.0054053151 0.4237500000 577518517 0 402718720 -0.1521113664 0.0082018627 0.2743717730 2237 1311867245.0108718872 0.0800746679 0.1613544822 0.2106595784 0.0054043071 0.0237310000 581180981 0 402718720 -0.1509505361 0.0071566752 0.2751784921 2238 1311867245.0429930687 0.0801384524 0.1613181926 0.2106595784 0.0054041703 0.0330620000 584376261 0 402718720 -0.1508359611 0.0080595668 0.2765338421 2239 1311867245.0749199390 0.0803367496 0.1612820240 0.2106595784 0.0054035129 0.0294560000 584379405 0 402718720 -0.1511383355 0.0078915171 0.2782541513 2240 1311867245.1111159325 0.0799718276 0.1612457248 0.2106595784 0.0054026665 0.0333980000 584382717 0 402718720 -0.1511816829 0.0071604787 0.2798546553 2241 1311867245.1429200172 0.0794372186 0.1612092195 0.2106595784 0.0054017769 0.0277790000 584385805 0 402718720 -0.1506659091 0.0081465077 0.2808020711 2242 1311867245.1749129295 0.0792424679 0.1611726598 0.2106595784 0.0054010460 0.0279450000 584388893 0 402718720 -0.1510643065 0.0077029113 0.2827114463 2243 1311867245.2108979225 0.0798147321 0.1611363879 0.2106595784 0.0054000564 0.0275870000 584392205 0 402718720 -0.1519796997 0.0073403311 0.2847600579 2244 1311867245.2429010868 0.0788472816 0.1610997172 0.2106595784 0.0053991324 0.0254330000 584395405 0 402718720 -0.1511362046 0.0075561493 0.2859149873 2245 1311867245.2755670547 0.0790025517 0.1610631483 0.2106595784 0.0053988430 0.0267540000 584398549 0 402718720 -0.1518213004 0.0072384258 0.2880631983 2246 1311867245.3120090961 0.0788142532 0.1610265281 0.2106595784 0.0053976918 0.0268560000 584401805 0 402718720 -0.1522653401 0.0069860183 0.2898843884 2247 1311867245.3430099487 0.0783139542 0.1609897179 0.2106595784 0.0053965369 0.0297410000 584404949 0 402718720 -0.1524912864 0.0064237993 0.2916027606 2248 1311867245.3749370575 0.0781956539 0.1609528878 0.2106595784 0.0053956225 0.0270220000 584408037 0 402718720 -0.1527852267 0.0071733552 0.2931505442 2249 1311867245.4122350216 0.0769117922 0.1609155196 0.2106595784 0.0053957731 0.0273010000 584411405 0 402718720 -0.1528410912 0.0066229030 0.2950286865 2250 1311867245.4428830147 0.0774592534 0.1608784279 0.2106595784 0.0053987509 0.0311260000 584414381 0 402718720 -0.1532744765 0.0071405941 0.2965761721 2251 1311867245.4751451015 0.0778139234 0.1608415267 0.2106595784 0.0053976238 0.0265070000 584417581 0 402718720 -0.1539137363 0.0075534433 0.2985214889 2252 1311867245.5108819008 0.0773545057 0.1608044544 0.2106595784 0.0053967585 0.0287890000 584420837 0 402718720 -0.1540892869 0.0071974029 0.3006711602 2253 1311867245.5429608822 0.0766066089 0.1607670829 0.2106595784 0.0053956318 0.0260380000 584423981 0 402718720 -0.1535751820 0.0082065053 0.3020984530 2254 1311867245.5749409199 0.0768121555 0.1607298358 0.2106595784 0.0053948633 0.0272640000 584427125 0 402718720 -0.1545372158 0.0078171650 0.3046366870 2255 1311867245.6109130383 0.0760942847 0.1606923034 0.2106595784 0.0053956773 0.0289270000 584430381 0 402718720 -0.1548759639 0.0064377277 0.3066017628 2256 1311867245.6428189278 0.0756304637 0.1606545987 0.2106595784 0.0054023509 0.0276960000 584433469 0 402718720 -0.1546236873 0.0075289467 0.3077028394 2257 1311867245.6751749516 0.0761228800 0.1606171456 0.2106595784 0.0054015158 0.0280450000 584436669 0 402718720 -0.1556701511 0.0064739487 0.3099818528 2258 1311867245.7109169960 0.0761397630 0.1605797331 0.2106595784 0.0054015104 0.0279340000 584439925 0 402718720 -0.1560720652 0.0066799051 0.3114977181 2259 1311867245.7429819107 0.0759641528 0.1605422760 0.2106595784 0.0054003614 0.0295820000 584443013 0 402718720 -0.1563959420 0.0068275235 0.3130254447 2260 1311867245.7752521038 0.0752108693 0.1605045188 0.2106595784 0.0054039258 0.0296590000 584446213 0 402718720 -0.1560929716 0.0060737920 0.3145971298 2261 1311867245.8110349178 0.0750535429 0.1604667253 0.2106595784 0.0054044567 0.0298180000 584449469 0 402718720 -0.1564698964 0.0054657054 0.3161605299 2262 1311867245.8428230286 0.0752997026 0.1604290741 0.2106595784 0.0054038299 0.0295370000 584452669 0 402718720 -0.1569345444 0.0061244522 0.3173047006 2263 1311867245.8757770061 0.0750289708 0.1603913365 0.2106595784 0.0054031863 0.0295360000 584455757 0 402718720 -0.1572731584 0.0051944484 0.3188556433 2264 1311867245.9110751152 0.0745468363 0.1603534194 0.2106595784 0.0054024917 0.0303730000 584459013 0 402718720 -0.1573166251 0.0053038909 0.3199469745 2265 1311867245.9428870678 0.0744792223 0.1603155058 0.2106595784 0.0054019152 0.0287420000 584462157 0 402718720 -0.1579190791 0.0054625100 0.3213675618 2266 1311867245.9751350880 0.0743710920 0.1602775780 0.2106595784 0.0054007523 0.0283580000 584465301 0 402718720 -0.1584817171 0.0056442227 0.3228690326 2267 1311867246.0112419128 0.0735809729 0.1602393351 0.2106595784 0.0053997229 0.0289680000 584468557 0 402718720 -0.1588643938 0.0058591859 0.3243868947 2268 1311867246.0429229736 0.0736842453 0.1602011715 0.2106595784 0.0053985738 0.0296960000 584471645 0 402718720 -0.1597114652 0.0063567548 0.3261967599 2269 1311867246.0752329826 0.0730671883 0.1601627696 0.2106595784 0.0053975188 0.0293080000 584474789 0 402718720 -0.1598880589 0.0068997173 0.3277924359 2270 1311867246.1109249592 0.0729714334 0.1601243593 0.2106595784 0.0053965058 0.0295260000 584478045 0 402718720 -0.1608582586 0.0073523400 0.3297919333 2271 1311867246.1430890560 0.0724335834 0.1600857460 0.2106595784 0.0053954890 0.0299690000 584481245 0 402718720 -0.1612169147 0.0077638798 0.3313127160 2272 1311867246.1749811172 0.0720633715 0.1600470038 0.2106595784 0.0053951130 0.0309770000 584484333 0 402718720 -0.1613237113 0.0087134037 0.3328621984 2273 1311867246.2109639645 0.0715478286 0.1600080688 0.2106595784 0.0053943816 0.0309840000 584487589 0 402718720 -0.1614741236 0.0092758965 0.3345347643 2274 1311867246.2429399490 0.0716630742 0.1599692188 0.2106595784 0.0053935053 0.0307120000 584490733 0 402718720 -0.1620074064 0.0099508073 0.3362663984 2275 1311867246.2750649452 0.0713929608 0.1599302841 0.2106595784 0.0053924459 0.0309820000 584493877 0 402718720 -0.1622019559 0.0109314881 0.3377709389 2276 1311867246.3108720779 0.0711390078 0.1598912722 0.2106595784 0.0053922786 0.4305780000 596858361 0 402718720 -0.1624210179 0.0113427984 0.3394520283 2277 1311867246.3429319859 0.0720290244 0.1598526853 0.2106595784 0.0053916438 0.0288760000 600520713 0 402718720 -0.1634013355 0.0141593106 0.3415448964 2278 1311867246.3752970695 0.0714247376 0.1598138671 0.2106595784 0.0053905313 0.0309590000 603716049 0 402718720 -0.1630159616 0.0145302713 0.3428822160 2279 1311867246.4109311104 0.0714937598 0.1597751132 0.2106595784 0.0053898982 0.0288050000 603719305 0 402718720 -0.1633794308 0.0150193991 0.3443402648 2280 1311867246.4430770874 0.0714998618 0.1597363960 0.2106595784 0.0053890798 0.0271230000 603722449 0 402718720 -0.1638204306 0.0152208703 0.3459028602 2281 1311867246.4751329422 0.0713757649 0.1596976583 0.2106595784 0.0053879461 0.0277410000 603725593 0 402718720 -0.1638353169 0.0158573426 0.3470233083 2282 1311867246.5109679699 0.0712817386 0.1596589134 0.2106595784 0.0053872895 0.0260800000 603728849 0 402718720 -0.1640058905 0.0162459668 0.3482631147 2283 1311867246.5431129932 0.0713072345 0.1596202136 0.2106595784 0.0053862158 0.0275390000 603731937 0 402718720 -0.1644253582 0.0163700562 0.3495536447 2284 1311867246.5752038956 0.0709756240 0.1595814024 0.2106595784 0.0053851948 0.0258300000 603735137 0 402718720 -0.1644391268 0.0158414617 0.3503964245 2285 1311867246.6111249924 0.0707508698 0.1595425269 0.2106595784 0.0053841280 0.0258450000 603738393 0 402718720 -0.1640885472 0.0164884981 0.3510372043 2286 1311867246.6431870461 0.0711017847 0.1595038389 0.2106595784 0.0053834978 0.0284210000 603741537 0 402718720 -0.1647187024 0.0161273293 0.3520799577 2287 1311867246.6751689911 0.0708902553 0.1594650923 0.2106595784 0.0053825977 0.0282770000 603744681 0 402718720 -0.1646659374 0.0157144777 0.3527232707 2288 1311867246.7110559940 0.0708669126 0.1594263693 0.2106595784 0.0053814554 0.0266790000 603747937 0 402718720 -0.1646517068 0.0158163551 0.3532135487 2289 1311867246.7433049679 0.0708267912 0.1593876626 0.2106595784 0.0053802905 0.0308720000 603751137 0 402718720 -0.1650561094 0.0152267711 0.3538526297 2290 1311867246.7749860287 0.0706849098 0.1593489278 0.2106595784 0.0053794752 0.0281370000 603754225 0 402718720 -0.1649516523 0.0153918220 0.3541501462 2291 1311867246.8111929893 0.0704588965 0.1593101281 0.2106595784 0.0053783829 0.0272360000 603757481 0 402718720 -0.1649287790 0.0150145143 0.3546042442 2292 1311867246.8430919647 0.0705218315 0.1592713898 0.2106595784 0.0053772303 0.0264390000 603760681 0 402718720 -0.1651789844 0.0145841790 0.3550845981 2293 1311867246.8750779629 0.0706485212 0.1592327405 0.2106595784 0.0053762404 0.0258520000 603763769 0 402718720 -0.1651828289 0.0148510048 0.3553082049 2294 1311867246.9111549854 0.0704359785 0.1591940322 0.2106595784 0.0053753712 0.0270290000 603767025 0 402718720 -0.1652120352 0.0140036708 0.3557308018 2295 1311867246.9430611134 0.0704900175 0.1591553812 0.2106595784 0.0053742219 0.0265680000 603770113 0 402718720 -0.1654544324 0.0137665626 0.3560324311 2296 1311867246.9751238823 0.0703617409 0.1591167080 0.2106595784 0.0053730871 0.0272380000 603773313 0 402718720 -0.1651481539 0.0139948493 0.3560992479 2297 1311867247.0109090805 0.0704230592 0.1590780952 0.2106595784 0.0053720298 0.0263860000 603776569 0 402718720 -0.1654437333 0.0134923244 0.3566649556 2298 1311867247.0440731049 0.0704505071 0.1590395280 0.2106595784 0.0053708764 0.0275710000 603779769 0 402718720 -0.1654471606 0.0136226248 0.3569170237 2299 1311867247.0751919746 0.0704034343 0.1590009738 0.2106595784 0.0053697899 0.0283530000 603782857 0 402718720 -0.1655111164 0.0138457734 0.3573731780 2300 1311867247.1112151146 0.0704695135 0.1589624818 0.2106595784 0.0053686736 0.0254430000 603786113 0 402718720 -0.1658546925 0.0138434581 0.3578298092 2301 1311867247.1430439949 0.0704891384 0.1589240319 0.2106595784 0.0053676486 0.0276880000 603789257 0 402718720 -0.1658172458 0.0141321495 0.3581280410 2302 1311867247.1751630306 0.0706699118 0.1588856938 0.2106595784 0.0053665967 0.0265220000 603792401 0 402718720 -0.1662417650 0.0140383160 0.3586970568 2303 1311867247.2113189697 0.0708017796 0.1588474464 0.2106595784 0.0053654882 0.0273850000 603795657 0 402718720 -0.1671766490 0.0126433931 0.3593648672 2304 1311867247.2437279224 0.0700517297 0.1588089066 0.2106595784 0.0053643520 0.0272770000 603798801 0 402718720 -0.1667014062 0.0123765627 0.3587076962 2305 1311867247.2777190208 0.0701262802 0.1587704325 0.2106595784 0.0053634217 0.0282450000 603802057 0 402718720 -0.1671881974 0.0124596572 0.3582568169 2306 1311867247.3109691143 0.0705735832 0.1587321859 0.2106595784 0.0053625551 0.0276140000 603805145 0 402718720 -0.1683786064 0.0114758695 0.3581950665 2307 1311867247.3432049751 0.0707054660 0.1586940295 0.2106595784 0.0053620888 0.0277920000 603808289 0 402718720 -0.1686276495 0.0118737668 0.3572055101 2308 1311867247.3753070831 0.0704665259 0.1586558027 0.2106595784 0.0053609987 0.0265110000 603811433 0 402718720 -0.1687077433 0.0111019397 0.3567085862 2309 1311867247.4116749763 0.0701300800 0.1586174633 0.2106595784 0.0053602765 0.0271770000 603814745 0 402718720 -0.1688468754 0.0098101432 0.3558579981 2310 1311867247.4440929890 0.0704444423 0.1585792931 0.2106595784 0.0053600129 0.0285400000 603817833 0 402718720 -0.1690558344 0.0100262817 0.3546502590 2311 1311867247.4751029015 0.0702265278 0.1585410617 0.2106595784 0.0053588871 0.0282950000 603820977 0 402718720 -0.1689470708 0.0090052756 0.3536013067 2312 1311867247.5110449791 0.0701364875 0.1585028245 0.2106595784 0.0053598158 0.0284460000 603824233 0 402718720 -0.1688837260 0.0078677926 0.3522196412 2313 1311867247.5430850983 0.0703572258 0.1584647157 0.2106595784 0.0053619459 0.0294640000 603827377 0 402718720 -0.1687121689 0.0081054382 0.3507497907 2314 1311867247.5751209259 0.0701260418 0.1584265399 0.2106595784 0.0053674715 0.0264410000 603830465 0 402718720 -0.1684237272 0.0067186221 0.3493775725 2315 1311867247.6114599705 0.0708196461 0.1583886968 0.2106595784 0.0053712807 0.0276960000 603833777 0 402718720 -0.1682738513 0.0060479171 0.3478245735 2316 1311867247.6431109905 0.0712099969 0.1583510549 0.2106595784 0.0053701815 0.0309320000 603836865 0 402718720 -0.1680278629 0.0057564266 0.3460512161 2317 1311867247.6750760078 0.0714493841 0.1583135487 0.2106595784 0.0053718259 0.0328450000 603840009 0 402718720 -0.1681291312 0.0035889491 0.3440934420 2318 1311867247.7112369537 0.0713274702 0.1582760224 0.2106595784 0.0053714020 0.0304640000 603843321 0 402718720 -0.1673183590 0.0026744059 0.3412687778 2319 1311867247.7431221008 0.0710081235 0.1582383907 0.2106595784 0.0053703177 0.0347800000 603846409 0 402718720 -0.1662466824 0.0024608390 0.3384536803 2320 1311867247.7750411034 0.0715506226 0.1582010253 0.2106595784 0.0053693979 0.0348730000 603849553 0 402718720 -0.1661434770 0.0019500088 0.3363208175 2321 1311867247.8111629486 0.0721081570 0.1581639323 0.2106595784 0.0053685150 0.0348650000 603852809 0 402718720 -0.1660962552 0.0016407765 0.3344488144 2322 1311867247.8438889980 0.0725912377 0.1581270793 0.2106595784 0.0053682071 0.0327870000 603856009 0 402718720 -0.1657501757 0.0019608741 0.3327970803 2323 1311867247.8752439022 0.0731914937 0.1580905164 0.2106595784 0.0053671419 0.0328480000 603859097 0 402718720 -0.1656735986 0.0014176272 0.3316377401 2324 1311867247.9113290310 0.0734696388 0.1580541046 0.2106595784 0.0053663363 0.0329210000 603862353 0 402718720 -0.1651597619 0.0006487480 0.3300900459 2325 1311867247.9430620670 0.0739082992 0.1580179129 0.2106595784 0.0053658666 0.0335400000 603865553 0 402718720 -0.1645154208 0.0012361464 0.3281244934 2326 1311867247.9769830704 0.0742221326 0.1579818872 0.2106595784 0.0053648110 0.0335730000 603868753 0 402718720 -0.1644012630 0.0005067732 0.3268498480 2327 1311867248.0109910965 0.0745238885 0.1579460221 0.2106595784 0.0053638386 0.0347470000 603871897 0 402718720 -0.1643101573 -0.0005239084 0.3247912526 2328 1311867248.0431969166 0.0747064874 0.1579102663 0.2106595784 0.0053629390 0.0338860000 603875097 0 402718720 -0.1639051586 0.0000621246 0.3232339621 2329 1311867248.0751419067 0.0749635994 0.1578746516 0.2106595784 0.0053619999 0.0343100000 603878185 0 402718720 -0.1637501866 -0.0002714295 0.3215309083 2330 1311867248.1121830940 0.0752973333 0.1578392107 0.2106595784 0.0053611788 0.0346440000 603881497 0 402718720 -0.1637882590 -0.0007053307 0.3191682100 2331 1311867248.1431720257 0.0752569959 0.1578037829 0.2106595784 0.0053600530 0.0343080000 603884585 0 402718720 -0.1632801741 -0.0005718881 0.3173945546 2332 1311867248.1757500172 0.0755536854 0.1577685127 0.2106595784 0.0053589391 0.0338100000 603887673 0 402718720 -0.1633389890 -0.0008899407 0.3154631853 2333 1311867248.2111859322 0.0757181272 0.1577333432 0.2106595784 0.0053578387 0.0342230000 603890985 0 402718720 -0.1631610990 -0.0006833383 0.3135713339 2334 1311867248.2431430817 0.0757733956 0.1576982276 0.2106595784 0.0053567299 0.0345300000 603894129 0 402718720 -0.1628311574 -0.0006358637 0.3117016256 2335 1311867248.2755289078 0.0760794804 0.1576632731 0.2106595784 0.0053555933 0.0342560000 603897273 0 402718720 -0.1627380252 -0.0005847982 0.3099062145 2336 1311867248.3112230301 0.0761976242 0.1576283991 0.2106595784 0.0053554159 0.0343880000 603900473 0 402718720 -0.1623630226 -0.0006493769 0.3076409698 2337 1311867248.3434588909 0.0765687227 0.1575937137 0.2106595784 0.0053559720 0.0345920000 603903505 0 402718720 -0.1621054113 0.0004064461 0.3056205809 2338 1311867248.3752219677 0.0767210126 0.1575591232 0.2106595784 0.0053568872 0.0353460000 603906649 0 402718720 -0.1617465913 0.0009838394 0.3040124476 2339 1311867248.4115560055 0.0767603517 0.1575245790 0.2106595784 0.0053573366 0.0340190000 603909961 0 402718720 -0.1614655703 0.0008416945 0.3022668660 2340 1311867248.4431369305 0.0770729110 0.1574901980 0.2106595784 0.0053562507 0.0346440000 603913049 0 402718720 -0.1611808091 0.0011045545 0.3003000021 2341 1311867248.4759230614 0.0772290081 0.1574559130 0.2106595784 0.0053551686 0.0343100000 603916249 0 402718720 -0.1606354415 0.0013970865 0.2982526422 2342 1311867248.5111510754 0.0777871534 0.1574218956 0.2106595784 0.0053543455 0.0342940000 603919449 0 402718720 -0.1605412662 0.0016645174 0.2965902090 2343 1311867248.5431890488 0.0785356238 0.1573882266 0.2106595784 0.0053536752 0.0343210000 603922649 0 402718720 -0.1607688069 0.0017338247 0.2950858474 2344 1311867248.5751869678 0.0785182342 0.1573545790 0.2106595784 0.0053527944 0.0344880000 603925737 0 402718720 -0.1600675732 0.0021612064 0.2929070294 2345 1311867248.6114389896 0.0788762569 0.1573211128 0.2106595784 0.0053519940 0.0345680000 603929049 0 402718720 -0.1599489897 0.0020448384 0.2911164165 2346 1311867248.6432449818 0.0792234242 0.1572878231 0.2106595784 0.0053510254 0.0348790000 603932137 0 402718720 -0.1599260122 0.0022399183 0.2893271148 2347 1311867248.6753089428 0.0794656128 0.1572546649 0.2106595784 0.0053499108 0.0348400000 603935225 0 402718720 -0.1599294394 0.0029600537 0.2872071862 2348 1311867248.7112829685 0.0801714882 0.1572218356 0.2106595784 0.0053494772 0.0364010000 603938537 0 402718720 -0.1601812989 0.0035845528 0.2853193283 2349 1311867248.7432990074 0.0798538253 0.1571888990 0.2106595784 0.0053496545 0.0353760000 603941569 0 402718720 -0.1597029865 0.0031353207 0.2830613256 2350 1311867248.7762219906 0.0801822916 0.1571561303 0.2106595784 0.0053487858 0.0355760000 603944825 0 402718720 -0.1593708992 0.0041880668 0.2807110548 2351 1311867248.8111898899 0.0810864791 0.1571237740 0.2106595784 0.0053506270 0.0352610000 603948025 0 402718720 -0.1598781496 0.0046932637 0.2790566087 2352 1311867248.8433189392 0.0807001740 0.1570912809 0.2106595784 0.0053562130 0.0353030000 603951169 0 402718720 -0.1591458172 0.0041939635 0.2766900361 2353 1311867248.8755309582 0.0807600617 0.1570588410 0.2106595784 0.0053561296 0.0356520000 603954369 0 402718720 -0.1581422240 0.0045907227 0.2733452916 2354 1311867248.9111700058 0.0814348608 0.1570267153 0.2106595784 0.0053550466 0.0346450000 603957625 0 402718720 -0.1580215245 0.0048571420 0.2711958289 2355 1311867248.9430971146 0.0821445882 0.1569949182 0.2106595784 0.0053543101 0.0354010000 603960713 0 402718720 -0.1581503004 0.0039902702 0.2693042755 2356 1311867248.9765889645 0.0821336061 0.1569631434 0.2106595784 0.0053533399 0.0376770000 603963913 0 402718720 -0.1567369401 0.0045496896 0.2663604617 2357 1311867249.0112600327 0.0822218359 0.1569314331 0.2106595784 0.0053522082 0.0363070000 603967113 0 402718720 -0.1553747356 0.0049941461 0.2630431652 2358 1311867249.0432310104 0.0831351206 0.1569001369 0.2106595784 0.0053511171 0.0373690000 603970257 0 402718720 -0.1551913470 0.0045921453 0.2604636252 2359 1311867249.0799059868 0.0844010115 0.1568694039 0.2106595784 0.0053502227 0.0379340000 603973513 0 402718720 -0.1547484994 0.0055147484 0.2587947845 2360 1311867249.1120550632 0.0845527053 0.1568387613 0.2106595784 0.0053497644 0.0368170000 603976713 0 402718720 -0.1534967124 0.0062542572 0.2563795745 2361 1311867249.1435980797 0.0846623108 0.1568081910 0.2106595784 0.0053501765 0.2782800000 616317013 0 402718720 -0.1525263637 0.0053141136 0.2535498142 2362 1311867249.1785130501 0.0825282037 0.1567767431 0.2106595784 0.0053515146 0.0303130000 619979365 0 402718720 -0.1494584531 0.0034673773 0.2516861260 2363 1311867249.2113580704 0.0834920034 0.1567457296 0.2106595784 0.0053506962 0.0427620000 623174757 0 402718720 -0.1483320892 0.0051352377 0.2485887110 2364 1311867249.2432780266 0.0837397948 0.1567148472 0.2106595784 0.0053502460 0.0361360000 623177957 0 402718720 -0.1473277062 0.0042888918 0.2464333028 2365 1311867249.2773399353 0.0844064057 0.1566842729 0.2106595784 0.0053494261 0.0384890000 623181101 0 402718720 -0.1469392627 0.0034425624 0.2442049831 2366 1311867249.3112919331 0.0852253810 0.1566540704 0.2106595784 0.0053499080 0.0354990000 623184301 0 402718720 -0.1459910572 0.0053787171 0.2415000945 2367 1311867249.3437249660 0.0866245329 0.1566244847 0.2106595784 0.0053488849 0.0325580000 623187501 0 402718720 -0.1459406912 0.0052961144 0.2397513688 2368 1311867249.3768448830 0.0863474905 0.1565948069 0.2106595784 0.0053495309 0.0346050000 623190645 0 402718720 -0.1447817683 0.0039379629 0.2374595255 2369 1311867249.4112169743 0.0862854123 0.1565651280 0.2106595784 0.0053490613 0.0341940000 623193901 0 402718720 -0.1433090419 0.0048036757 0.2346687764 2370 1311867249.4432210922 0.0872206762 0.1565358687 0.2106595784 0.0053482451 0.0335120000 623196989 0 402718720 -0.1432953328 0.0053297919 0.2326668203 2371 1311867249.4764099121 0.0884658173 0.1565071593 0.2106595784 0.0053471908 0.0327590000 623200133 0 402718720 -0.1439452022 0.0038897984 0.2311392426 2372 1311867249.5111339092 0.0882244855 0.1564783723 0.2106595784 0.0053462902 0.0360510000 623203389 0 402718720 -0.1430101991 0.0043597454 0.2283256203 2373 1311867249.5432300568 0.0876732394 0.1564493773 0.2106595784 0.0053452769 0.0331240000 623206533 0 402718720 -0.1416438520 0.0053417557 0.2255071253 2374 1311867249.5759100914 0.0891081691 0.1564210112 0.2106595784 0.0053443846 0.0335130000 623209677 0 402718720 -0.1426594555 0.0041794861 0.2242695242 2375 1311867249.6112229824 0.0898868963 0.1563929968 0.2106595784 0.0053434595 0.0359250000 623212933 0 402718720 -0.1428100616 0.0045528747 0.2220745236 2376 1311867249.6433780193 0.0899090767 0.1563650154 0.2106595784 0.0053430470 0.0335600000 623216077 0 402718720 -0.1419114321 0.0059017921 0.2196211815 2377 1311867249.6751029491 0.0893405750 0.1563368183 0.2106595784 0.0053459792 0.0322850000 623219221 0 402718720 -0.1415966302 0.0045605809 0.2179877460 2378 1311867249.7111389637 0.0899914652 0.1563089186 0.2106595784 0.0053458774 0.0307740000 623222421 0 402718720 -0.1413817704 0.0048252163 0.2157395482 2379 1311867249.7432470322 0.0907452032 0.1562813593 0.2106595784 0.0053465061 0.0332020000 623225621 0 402718720 -0.1413547844 0.0067322315 0.2135553211 2380 1311867249.7751579285 0.0903813988 0.1562536702 0.2106595784 0.0053493708 0.0329070000 623228709 0 402718720 -0.1410620064 0.0068009510 0.2119021267 2381 1311867249.8111488819 0.0907924399 0.1562261771 0.2106595784 0.0053493313 0.0327540000 623232021 0 402718720 -0.1408524811 0.0071206270 0.2100459933 2382 1311867249.8433248997 0.0905308053 0.1561985971 0.2106595784 0.0053483180 0.0330950000 623235109 0 402718720 -0.1399551928 0.0085472073 0.2078487426 2383 1311867249.8783950806 0.0914545432 0.1561714280 0.2106595784 0.0053474323 0.0322080000 623238309 0 402718720 -0.1403399557 0.0091931745 0.2062244564 2384 1311867249.9112401009 0.0917108282 0.1561443892 0.2106595784 0.0053463512 0.0344230000 623241509 0 402718720 -0.1400716603 0.0090835290 0.2041548193 2385 1311867249.9432768822 0.0921707079 0.1561175658 0.2106595784 0.0053454050 0.0352620000 623244709 0 402718720 -0.1400720328 0.0095033757 0.2020816356 2386 1311867249.9751698971 0.0926162824 0.1560909517 0.2106595784 0.0053451211 0.0337010000 623247797 0 402718720 -0.1397513449 0.0102061722 0.1997297108 2387 1311867250.0117108822 0.0929897577 0.1560645163 0.2106595784 0.0053443024 0.0365180000 623251109 0 402718720 -0.1397673041 0.0106531177 0.1975930780 2388 1311867250.0434269905 0.0932928622 0.1560382300 0.2106595784 0.0053437633 0.0367530000 623254253 0 402718720 -0.1394184679 0.0102752969 0.1954838485 2389 1311867250.0766730309 0.0936540142 0.1560121169 0.2106595784 0.0053433254 0.0336020000 623257397 0 402718720 -0.1392380595 0.0103207128 0.1928265840 2390 1311867250.1116099358 0.0940717384 0.1559862005 0.2106595784 0.0053423523 0.0358700000 623260653 0 402718720 -0.1386088580 0.0112657864 0.1900281310 2391 1311867250.1432220936 0.0942738503 0.1559603902 0.2106595784 0.0053412563 0.0347720000 623263741 0 402718720 -0.1383390874 0.0105930297 0.1877540350 2392 1311867250.1758909225 0.0950400010 0.1559349218 0.2106595784 0.0053406519 0.0328290000 623266885 0 402718720 -0.1383343786 0.0106098512 0.1852822155 2393 1311867250.2133369446 0.0957003385 0.1559097506 0.2106595784 0.0053395710 0.0358410000 623270197 0 402718720 -0.1380040050 0.0113075422 0.1829115599 2394 1311867250.2456688881 0.0962241143 0.1558848193 0.2106595784 0.0053390553 0.0354720000 623273341 0 402718720 -0.1377084851 0.0119522326 0.1807551086 2395 1311867250.2751679420 0.0960847139 0.1558598506 0.2106595784 0.0053383540 0.0355160000 623276429 0 402718720 -0.1369568110 0.0119888736 0.1785866916 2396 1311867250.3114409447 0.0962915719 0.1558349890 0.2106595784 0.0053373628 0.0361150000 623279741 0 402718720 -0.1363791674 0.0125084165 0.1764976382 2397 1311867250.3431971073 0.0972701013 0.1558105564 0.2106595784 0.0053368383 0.0358250000 623282829 0 402718720 -0.1367703974 0.0131395934 0.1748539954 2398 1311867250.3780639172 0.0977761894 0.1557863553 0.2106595784 0.0053358689 0.0354610000 623286085 0 402718720 -0.1367385983 0.0131867416 0.1731662750 2399 1311867250.4116489887 0.0980340466 0.1557622818 0.2106595784 0.0053352070 0.0357600000 623289285 0 402718720 -0.1363053471 0.0129558956 0.1709497869 2400 1311867250.4441699982 0.0976337269 0.1557380616 0.2106595784 0.0053342599 0.0383430000 623292317 0 402718720 -0.1353854388 0.0138517199 0.1683074385 2401 1311867250.4793250561 0.0983750820 0.1557141703 0.2106595784 0.0053336343 0.0355360000 623295629 0 402718720 -0.1349855959 0.0148972841 0.1664917022 2402 1311867250.5113220215 0.0985217020 0.1556903599 0.2106595784 0.0053327380 0.0347520000 623298773 0 402718720 -0.1348043829 0.0136293387 0.1649896204 2403 1311867250.5443298817 0.0998709723 0.1556671309 0.2106595784 0.0053328379 0.0331600000 623301861 0 402718720 -0.1352431774 0.0148030370 0.1630811989 2404 1311867250.5793490410 0.0996802002 0.1556438418 0.2106595784 0.0053318847 0.0354900000 623305173 0 402718720 -0.1340592057 0.0160931610 0.1610288769 2405 1311867250.6114881039 0.0993069485 0.1556204169 0.2106595784 0.0053308456 0.0378940000 623308373 0 402718720 -0.1333026439 0.0146290427 0.1599914730 2406 1311867250.6433761120 0.0994952917 0.1555970898 0.2106595784 0.0053299668 0.0393350000 623311517 0 402718720 -0.1328156739 0.0149780801 0.1579221934 2407 1311867250.6795539856 0.1005543768 0.1555742220 0.2106595784 0.0053299513 0.0397500000 623314717 0 402718720 -0.1327079535 0.0163187664 0.1557540894 2408 1311867250.7112920284 0.1011222675 0.1555516091 0.2106595784 0.0053290408 0.0395180000 623317861 0 402718720 -0.1329034567 0.0159088243 0.1542481035 2409 1311867250.7445449829 0.1004852951 0.1555287505 0.2106595784 0.0053298256 0.0401030000 623321005 0 402718720 -0.1317638606 0.0151837068 0.1522731185 2410 1311867250.7792830467 0.1012875587 0.1555062438 0.2106595784 0.0053300005 0.0399580000 623324205 0 402718720 -0.1317970306 0.0157515090 0.1503399014 2411 1311867250.8145580292 0.1020095348 0.1554840552 0.2106595784 0.0053292198 0.3797240000 635673837 0 402718720 -0.1320662498 0.0158424545 0.1488093734 2412 1311867250.8433470726 0.1027806997 0.1554622047 0.2106595784 0.0053281567 0.0329000000 639336021 0 402718720 -0.1321578622 0.0148785310 0.1493960172 2413 1311867250.8792760372 0.1024717540 0.1554402443 0.2106595784 0.0053299594 0.0359540000 642531525 0 402718720 -0.1316746175 0.0148352683 0.1474020332 2414 1311867250.9116361141 0.1029286906 0.1554184914 0.2106595784 0.0053295807 0.0333750000 642534725 0 402718720 -0.1318264306 0.0146070989 0.1463414580 2415 1311867250.9433720112 0.1036776304 0.1553970666 0.2106595784 0.0053293494 0.0328530000 642537813 0 402718720 -0.1325307339 0.0147049576 0.1444845945 2416 1311867250.9793050289 0.1038244143 0.1553757203 0.2106595784 0.0053283848 0.0343030000 642541069 0 402718720 -0.1321889907 0.0155630819 0.1428030282 2417 1311867251.0112459660 0.1035111994 0.1553542620 0.2106595784 0.0053278432 0.0326080000 642544213 0 402718720 -0.1318242550 0.0153516335 0.1411596239 2418 1311867251.0437738895 0.1038906351 0.1553329785 0.2106595784 0.0053267871 0.0330380000 642547301 0 402718720 -0.1321746707 0.0143051576 0.1397621185 2419 1311867251.0793159008 0.1048409194 0.1553121054 0.2106595784 0.0053267987 0.0318990000 642550613 0 402718720 -0.1327941567 0.0151681062 0.1381623894 2420 1311867251.1115839481 0.1047709733 0.1552912206 0.2106595784 0.0053257079 0.0323760000 642553813 0 402718720 -0.1327058971 0.0161427148 0.1364950836 2421 1311867251.1432809830 0.1050850153 0.1552704828 0.2106595784 0.0053250615 0.0331700000 642556957 0 402718720 -0.1327843070 0.0145996772 0.1351616830 2422 1311867251.1794250011 0.1048289537 0.1552496564 0.2106595784 0.0053253283 0.0323970000 642560213 0 402718720 -0.1327830851 0.0148660420 0.1332433820 2423 1311867251.2113831043 0.1057229489 0.1552292162 0.2106595784 0.0053285661 0.0314090000 642563357 0 402718720 -0.1332172006 0.0163485259 0.1316803992 2424 1311867251.2472319603 0.1061114520 0.1552089531 0.2106595784 0.0053295039 0.0315980000 642566613 0 402718720 -0.1339265853 0.0145289423 0.1307328939 2425 1311867251.2793700695 0.1063787043 0.1551888169 0.2106595784 0.0053289797 0.0343740000 642569701 0 402718720 -0.1342549473 0.0144240186 0.1288845092 2426 1311867251.3133869171 0.1068283617 0.1551688827 0.2106595784 0.0053287076 0.0311340000 642572957 0 402718720 -0.1345248669 0.0152289439 0.1272237152 2427 1311867251.3432419300 0.1060021147 0.1551486244 0.2106595784 0.0053333877 0.0307970000 642575989 0 402718720 -0.1343987733 0.0140341064 0.1257143468 2428 1311867251.3801820278 0.1066336259 0.1551286429 0.2106595784 0.0053325493 0.0309840000 642579301 0 402718720 -0.1346394122 0.0141949495 0.1239523590 2429 1311867251.4113450050 0.1072269306 0.1551089222 0.2106595784 0.0053316098 0.0314530000 642582389 0 402718720 -0.1351295412 0.0145964427 0.1225773618 2430 1311867251.4433789253 0.1071226448 0.1550891748 0.2106595784 0.0053308186 0.0316790000 642585477 0 402718720 -0.1348784268 0.0142594725 0.1209578887 2431 1311867251.4793379307 0.1072549149 0.1550694980 0.2106595784 0.0053298135 0.0319300000 642588789 0 402718720 -0.1349077523 0.0141705368 0.1195680872 2432 1311867251.5136411190 0.1075249240 0.1550499484 0.2106595784 0.0053291040 0.0314120000 642591989 0 402718720 -0.1349256188 0.0141840661 0.1179824248 2433 1311867251.5431749821 0.1076489910 0.1550304659 0.2106595784 0.0053284656 0.0337580000 642595077 0 402718720 -0.1345994473 0.0142132780 0.1162884906 2434 1311867251.5795340538 0.1080703214 0.1550111725 0.2106595784 0.0053275881 0.0333770000 642598389 0 402718720 -0.1344954222 0.0142897610 0.1147136986 2435 1311867251.6119530201 0.1083440036 0.1549920073 0.2106595784 0.0053265283 0.0287140000 642601533 0 402718720 -0.1343703419 0.0143317739 0.1132571846 2436 1311867251.6432960033 0.1092115417 0.1549732140 0.2106595784 0.0053256215 0.0315540000 642604677 0 402718720 -0.1351562291 0.0138419364 0.1120425537 2437 1311867251.6797280312 0.1097224802 0.1549546458 0.2106595784 0.0053269430 0.0303920000 642607933 0 402718720 -0.1351942420 0.0139960004 0.1103527471 2438 1311867251.7122941017 0.1095772758 0.1549360333 0.2106595784 0.0053265457 0.0316860000 642611077 0 402718720 -0.1346173435 0.0152620990 0.1083140746 2439 1311867251.7434990406 0.1098242104 0.1549175372 0.2106595784 0.0053258437 0.0293320000 642614165 0 402718720 -0.1347793788 0.0151392976 0.1071060151 2440 1311867251.7797439098 0.1106463149 0.1548993933 0.2106595784 0.0053247628 0.0297460000 642617477 0 402718720 -0.1357758641 0.0133492118 0.1059536636 2441 1311867251.8112530708 0.1105502248 0.1548812248 0.2106595784 0.0053244348 0.0301830000 642620621 0 402718720 -0.1353266239 0.0149232307 0.1038766131 2442 1311867251.8433279991 0.1113122255 0.1548633833 0.2106595784 0.0053236843 0.0309990000 642623765 0 402718720 -0.1357951164 0.0156251211 0.1026644260 2443 1311867251.8805420399 0.1111097559 0.1548454735 0.2106595784 0.0053229720 0.0304750000 642626965 0 402718720 -0.1359585971 0.0144142592 0.1014922336 2444 1311867251.9112489223 0.1109825596 0.1548275263 0.2106595784 0.0053219830 0.0336790000 642630109 0 402718720 -0.1353780776 0.0159141365 0.0997377560 2445 1311867251.9432179928 0.1112641171 0.1548097090 0.2106595784 0.0053212478 0.0307160000 642633197 0 402718720 -0.1351393163 0.0164248534 0.0983445123 2446 1311867251.9800109863 0.1115988344 0.1547920431 0.2106595784 0.0053204955 0.0308930000 642636509 0 402718720 -0.1352383196 0.0158979017 0.0971628428 2447 1311867252.0118858814 0.1122200862 0.1547746455 0.2106595784 0.0053195070 0.0303670000 642639653 0 402718720 -0.1356193721 0.0162597708 0.0959402472 2448 1311867252.0441029072 0.1125131547 0.1547573818 0.2106595784 0.0053184841 0.0313680000 642642853 0 402718720 -0.1355127692 0.0159394965 0.0943259746 2449 1311867252.0794539452 0.1124885604 0.1547401222 0.2106595784 0.0053174856 0.0330920000 642645997 0 402718720 -0.1351057291 0.0159455631 0.0922420621 2450 1311867252.1122250557 0.1124990582 0.1547228809 0.2106595784 0.0053170660 0.0337930000 642649197 0 402718720 -0.1352393329 0.0153627535 0.0901307985 2451 1311867252.1432950497 0.1134053022 0.1547060235 0.2106595784 0.0053168786 0.0311670000 642652285 0 402718720 -0.1360085458 0.0145555688 0.0881610811 2452 1311867252.1794359684 0.1139103323 0.1546893857 0.2106595784 0.0053159144 0.0321950000 642655541 0 402718720 -0.1358535439 0.0148466630 0.0855227783 2453 1311867252.2113459110 0.1142498329 0.1546729000 0.2106595784 0.0053171527 0.0309550000 642658741 0 402718720 -0.1359061599 0.0145333437 0.0833081007 2454 1311867252.2432808876 0.1148824245 0.1546566855 0.2106595784 0.0053168629 0.0331020000 642661885 0 402718720 -0.1364359856 0.0123470547 0.0814510062 2455 1311867252.2794110775 0.1155525818 0.1546407571 0.2106595784 0.0053167917 0.0334360000 642665141 0 402718720 -0.1365516931 0.0118796444 0.0789473355 2456 1311867252.3112668991 0.1163769513 0.1546251774 0.2106595784 0.0053167942 0.0339090000 642668285 0 402718720 -0.1369023323 0.0120735513 0.0765784904 2457 1311867252.3450291157 0.1168631241 0.1546098082 0.2106595784 0.0053158046 0.0343120000 642671429 0 402718720 -0.1370994449 0.0108347805 0.0746691525 2458 1311867252.3794589043 0.1185086221 0.1545951210 0.2106595784 0.0053147660 0.0334400000 642674685 0 402718720 -0.1389762759 0.0084307753 0.0729280636 2459 1311867252.4111969471 0.1177168265 0.1545801237 0.2106595784 0.0053153407 0.0333600000 642677829 0 402718720 -0.1377672702 0.0084721586 0.0696925297 2460 1311867252.4455969334 0.1185275316 0.1545654682 0.2106595784 0.0053214803 0.0358240000 642680973 0 402718720 -0.1370103359 0.0090710279 0.0670918003 2461 1311867252.4792900085 0.1182206944 0.1545506999 0.2106595784 0.0053315934 0.0342460000 642684173 0 402718720 -0.1375622600 0.0067131557 0.0649608374 2462 1311867252.5112249851 0.1182356998 0.1545359497 0.2106595784 0.0053315082 0.0337510000 642687373 0 402718720 -0.1374437213 0.0063769030 0.0620821007 2463 1311867252.5432820320 0.1191131696 0.1545215677 0.2106595784 0.0053312921 0.0364850000 642690517 0 402718720 -0.1373559982 0.0069546541 0.0595323555 2464 1311867252.5791800022 0.1195412129 0.1545073711 0.2106595784 0.0053302276 0.0345790000 642693773 0 402718720 -0.1376939714 0.0058770673 0.0572275184 2465 1311867252.6112799644 0.1208518222 0.1544937178 0.2106595784 0.0053296354 0.0329240000 642696917 0 402718720 -0.1388873011 0.0043779295 0.0553905852 2466 1311867252.6432769299 0.1214404106 0.1544803142 0.2106595784 0.0053288036 0.0342270000 642700117 0 402718720 -0.1386629492 0.0050752824 0.0526581146 2467 1311867252.6792490482 0.1214561537 0.1544669278 0.2106595784 0.0053290280 0.0373750000 642703261 0 402718720 -0.1381722391 0.0041550118 0.0502869859 2468 1311867252.7112491131 0.1221166402 0.1544538199 0.2106595784 0.0053287036 0.0349780000 642706461 0 402718720 -0.1387529373 0.0030475070 0.0479925424 2469 1311867252.7432410717 0.1229970530 0.1544410792 0.2106595784 0.0053277209 0.0347080000 642709549 0 402718720 -0.1390611231 0.0021266828 0.0456230119 2470 1311867252.7792730331 0.1235989854 0.1544285925 0.2106595784 0.0053268269 0.0355250000 642712805 0 402718720 -0.1384554356 0.0033884873 0.0426268540 2471 1311867252.8112781048 0.1237231791 0.1544161662 0.2106595784 0.0053261279 0.0350140000 642716005 0 402718720 -0.1380885243 0.0028524797 0.0402228311 2472 1311867252.8433189392 0.1240388453 0.1544038777 0.2106595784 0.0053255209 0.0339520000 642719149 0 402718720 -0.1380846500 0.0014311039 0.0376451351 2473 1311867252.8792660236 0.1249399260 0.1543919634 0.2106595784 0.0053265726 0.0362090000 642722349 0 402718720 -0.1374212652 0.0032774806 0.0348975621 2474 1311867252.9112188816 0.1256270707 0.1543803365 0.2106595784 0.0053255412 0.0355200000 642725549 0 402718720 -0.1377731115 0.0031654176 0.0330678895 2475 1311867252.9446918964 0.1257188916 0.1543687562 0.2106595784 0.0053247777 0.5169740000 655094281 0 402718720 -0.1379147023 0.0008567924 0.0312388707 2476 1311867252.9806020260 0.1274373233 0.1543578792 0.2106595784 0.0053282995 0.0274520000 658756745 0 402718720 -0.1372119039 0.0036068289 0.0300399549 2477 1311867253.0113809109 0.1272871494 0.1543469503 0.2106595784 0.0053277528 0.0410890000 661952081 0 402718720 -0.1362195462 0.0048406064 0.0275048092 2478 1311867253.0434310436 0.1275399476 0.1543361323 0.2106595784 0.0053269143 0.0392670000 661955225 0 402718720 -0.1364857107 0.0015273929 0.0256422348 2479 1311867253.0799210072 0.1276024431 0.1543253483 0.2106595784 0.0053321018 0.0363970000 661958425 0 402718720 -0.1355849802 0.0023611363 0.0227240566 2480 1311867253.1113030910 0.1280284077 0.1543147447 0.2106595784 0.0053334765 0.0356390000 661961625 0 402718720 -0.1347152591 0.0036899038 0.0199737158 2481 1311867253.1440560818 0.1295711845 0.1543047714 0.2106595784 0.0053335655 0.0349350000 661964713 0 402718720 -0.1355498433 0.0022354464 0.0185197592 2482 1311867253.1794049740 0.1307952702 0.1542952994 0.2106595784 0.0053325487 0.0336470000 661967969 0 402718720 -0.1362471133 0.0016202041 0.0164779667 2483 1311867253.2112159729 0.1298985779 0.1542854739 0.2106595784 0.0053315985 0.0338800000 661971169 0 402718720 -0.1344794035 0.0018814811 0.0137083419 2484 1311867253.2458410263 0.1304848790 0.1542758924 0.2106595784 0.0053306632 0.0335480000 661974369 0 402718720 -0.1343661398 0.0020822445 0.0116216494 2485 1311867253.2793951035 0.1315508485 0.1542667475 0.2106595784 0.0053298953 0.0340320000 661977513 0 402718720 -0.1341931224 0.0016790921 0.0097927935 2486 1311867253.3114080429 0.1313001066 0.1542575091 0.2106595784 0.0053288568 0.0374640000 661980713 0 402718720 -0.1333508939 0.0015628041 0.0074170241 2487 1311867253.3445210457 0.1321071684 0.1542486027 0.2106595784 0.0053344544 0.0348760000 661983857 0 402718720 -0.1329840124 0.0016245915 0.0057271952 2488 1311867253.3794078827 0.1326601505 0.1542399256 0.2106595784 0.0053386084 0.0347560000 661987057 0 402718720 -0.1323730648 0.0008630180 0.0039307815 2489 1311867253.4129259586 0.1329651028 0.1542313781 0.2106595784 0.0053392414 0.0374660000 661990257 0 402718720 -0.1314398646 0.0008484508 0.0018289709 2490 1311867253.4444909096 0.1330266744 0.1542228621 0.2106595784 0.0053390306 0.0351990000 661993345 0 402718720 -0.1304857433 0.0013168865 -0.0004486504 2491 1311867253.4804780483 0.1329386681 0.1542143177 0.2106595784 0.0053384940 0.0344420000 661996601 0 402718720 -0.1288686991 0.0013190797 -0.0025915774 2492 1311867253.5113739967 0.1332772374 0.1542059160 0.2106595784 0.0053381744 0.0343790000 661999801 0 402718720 -0.1282183528 -0.0007756460 -0.0037742725 2493 1311867253.5441629887 0.1341389418 0.1541978667 0.2106595784 0.0053377389 0.0337430000 662002889 0 402718720 -0.1276424825 -0.0010856134 -0.0057837772 2494 1311867253.5794069767 0.1346553117 0.1541900308 0.2106595784 0.0053370088 0.0341020000 662006145 0 402718720 -0.1270329058 -0.0013249082 -0.0079070069 2495 1311867253.6118021011 0.1356031001 0.1541825812 0.2106595784 0.0053360308 0.0350380000 662009345 0 402718720 -0.1273127049 -0.0027546769 -0.0095883589 2496 1311867253.6444630623 0.1358737200 0.1541752459 0.2106595784 0.0053353414 0.0323010000 662012433 0 402718720 -0.1264884025 -0.0028963583 -0.0121490695 2497 1311867253.6799790859 0.1373398155 0.1541685036 0.2106595784 0.0053344590 0.0338730000 662015745 0 402718720 -0.1270515919 -0.0032343036 -0.0139223924 2498 1311867253.7115290165 0.1381672472 0.1541620980 0.2106595784 0.0053345037 0.0365630000 662018833 0 402718720 -0.1279427409 -0.0054197558 -0.0158060845 2499 1311867253.7435369492 0.1379402429 0.1541556066 0.2106595784 0.0053347768 0.0349790000 662021977 0 402718720 -0.1280237436 -0.0074325399 -0.0185694173 2500 1311867253.7804019451 0.1395269930 0.1541497552 0.2106595784 0.0053355879 0.0347000000 662025177 0 402718720 -0.1292633563 -0.0073013357 -0.0213650577 2501 1311867253.8113009930 0.1399970353 0.1541440964 0.2106595784 0.0053346484 0.0346120000 662028377 0 402718720 -0.1304070354 -0.0081613185 -0.0242162067 2502 1311867253.8466010094 0.1403801143 0.1541385952 0.2106595784 0.0053342839 0.0340570000 662031521 0 402718720 -0.1314452142 -0.0094273994 -0.0270668287 2503 1311867253.8792059422 0.1406742483 0.1541332159 0.2106595784 0.0053332476 0.0356840000 662034721 0 402718720 -0.1326095611 -0.0111976862 -0.0297993273 2504 1311867253.9114460945 0.1412305385 0.1541280631 0.2106595784 0.0053324872 0.0348740000 662037865 0 402718720 -0.1339171827 -0.0113566089 -0.0331749506 2505 1311867253.9461040497 0.1415521801 0.1541230428 0.2106595784 0.0053316185 0.0352550000 662041065 0 402718720 -0.1348571777 -0.0105058970 -0.0365709215 2506 1311867253.9794149399 0.1419802606 0.1541181973 0.2106595784 0.0053305916 0.0351380000 662044209 0 402718720 -0.1364554614 -0.0118739819 -0.0388936251 2507 1311867254.0119659901 0.1429588199 0.1541137460 0.2106595784 0.0053312291 0.0359860000 662047353 0 402718720 -0.1384461075 -0.0128221577 -0.0412893631 2508 1311867254.0457670689 0.1425019056 0.1541091161 0.2106595784 0.0053302291 0.0357650000 662050553 0 402718720 -0.1386822313 -0.0122610219 -0.0444082320 2509 1311867254.0793740749 0.1423999518 0.1541044492 0.2106595784 0.0053327131 0.0351030000 662053753 0 402718720 -0.1392582208 -0.0136750508 -0.0467562154 2510 1311867254.1113519669 0.1424771547 0.1540998168 0.2106595784 0.0053318748 0.0362620000 662056897 0 402718720 -0.1398813874 -0.0140180346 -0.0495005734 2511 1311867254.1476850510 0.1434068382 0.1540955584 0.2106595784 0.0053309594 0.0366850000 662060153 0 402718720 -0.1408664137 -0.0130055370 -0.0521840490 2512 1311867254.1795129776 0.1429256052 0.1540911117 0.2106595784 0.0053300487 0.0374430000 662063297 0 402718720 -0.1407499760 -0.0134872217 -0.0548669882 2513 1311867254.2114939690 0.1416205466 0.1540861493 0.2106595784 0.0053344366 0.0391760000 662066497 0 402718720 -0.1405254751 -0.0142585291 -0.0574945509 2514 1311867254.2469038963 0.1421335489 0.1540813949 0.2106595784 0.0053347115 0.0391810000 662069697 0 402718720 -0.1410398334 -0.0136228297 -0.0605050251 2515 1311867254.2798569202 0.1435005069 0.1540771878 0.2106595784 0.0053355175 0.0379430000 662072841 0 402718720 -0.1412154436 -0.0102428757 -0.0637704805 2516 1311867254.3114631176 0.1453542709 0.1540737208 0.2106595784 0.0053404547 0.0374190000 662075985 0 402718720 -0.1436307430 -0.0105653675 -0.0657497719 2517 1311867254.3475399017 0.1458484083 0.1540704529 0.2106595784 0.0053404297 0.0392480000 662079241 0 402718720 -0.1445363909 -0.0130782025 -0.0680380836 2518 1311867254.3794488907 0.1464447975 0.1540674244 0.2106595784 0.0053394022 0.0383730000 662082385 0 402718720 -0.1451986879 -0.0135086896 -0.0710949600 2519 1311867254.4115350246 0.1476403028 0.1540648730 0.2106595784 0.0053440060 0.0406360000 662085585 0 402718720 -0.1460263282 -0.0112085342 -0.0750813186 2520 1311867254.4483230114 0.1504657865 0.1540634448 0.2106595784 0.0053434485 0.0405740000 662088785 0 402718720 -0.1482112408 -0.0117032276 -0.0772861987 2521 1311867254.4794480801 0.1511743367 0.1540622988 0.2106595784 0.0053426019 0.0373420000 662091929 0 402718720 -0.1498115659 -0.0123926820 -0.0802982375 2522 1311867254.5114428997 0.1516007334 0.1540613227 0.2106595784 0.0053416599 0.0380890000 662095073 0 402718720 -0.1507045031 -0.0110573424 -0.0838418230 2523 1311867254.5500459671 0.1524787843 0.1540606955 0.2106595784 0.0053427750 0.0379440000 662098385 0 402718720 -0.1516628414 -0.0101210782 -0.0871371105 2524 1311867254.5794870853 0.1518676430 0.1540598266 0.2106595784 0.0053453503 0.0372960000 662101473 0 402718720 -0.1517665535 -0.0106382687 -0.0903024897 2525 1311867254.6114809513 0.1520825475 0.1540590435 0.2106595784 0.0053444058 0.0412450000 662104617 0 402718720 -0.1519902945 -0.0076745916 -0.0939546973 2526 1311867254.6452269554 0.1527184099 0.1540585128 0.2106595784 0.0053454393 0.0381090000 662107761 0 402718720 -0.1525477767 -0.0064871027 -0.0972781032 2527 1311867254.6794900894 0.1536637396 0.1540583566 0.2106595784 0.0053453484 0.0392030000 662111073 0 402718720 -0.1535497457 -0.0075423415 -0.0993771106 2528 1311867254.7113230228 0.1527997851 0.1540578587 0.2106595784 0.0053443786 0.0411590000 662114217 0 402718720 -0.1526518911 -0.0066469298 -0.1028587073 2529 1311867254.7452731133 0.1530468762 0.1540574589 0.2106595784 0.0053455102 0.0407090000 662117305 0 402718720 -0.1523419917 -0.0055693220 -0.1062371135 2530 1311867254.7794649601 0.1553045213 0.1540579519 0.2106595784 0.0053491796 0.0407260000 662120561 0 402718720 -0.1537299305 -0.0049471734 -0.1082842499 2531 1311867254.8115739822 0.1554101706 0.1540584861 0.2106595784 0.0053483481 0.0397400000 662123705 0 402718720 -0.1533252001 -0.0050097746 -0.1109181792 2532 1311867254.8482649326 0.1559942961 0.1540592507 0.2106595784 0.0053490341 0.0413600000 662127017 0 402718720 -0.1534817070 -0.0035759138 -0.1137679666 2533 1311867254.8794910908 0.1562496871 0.1540601154 0.2106595784 0.0053480894 0.0413670000 662130105 0 402718720 -0.1532383859 -0.0030436770 -0.1165565252 2534 1311867254.9138810635 0.1567699611 0.1540611848 0.2106595784 0.0053475205 0.5187450000 674578397 0 402718720 -0.1534789801 -0.0037275611 -0.1186030060 2535 1311867254.9490699768 0.1587744951 0.1540630441 0.2106595784 0.0053484509 0.0244540000 678240861 0 402718720 -0.1542713344 -0.0027856734 -0.1195577681 2536 1311867254.9819250107 0.1590409577 0.1540650070 0.2106595784 0.0053476720 0.0409130000 681436253 0 402718720 -0.1538120955 -0.0013444468 -0.1221473962 2537 1311867255.0154299736 0.1598456651 0.1540672855 0.2106595784 0.0053480665 0.0377620000 681439397 0 402718720 -0.1540409178 -0.0014042773 -0.1237579361 2538 1311867255.0494179726 0.1602007747 0.1540697022 0.2106595784 0.0053473214 0.0413480000 681442541 0 402718720 -0.1537209004 -0.0004272606 -0.1262073964 2539 1311867255.0821940899 0.1604997367 0.1540722347 0.2106595784 0.0053462930 0.0386010000 681445741 0 402718720 -0.1535788625 0.0007296883 -0.1281786114 2540 1311867255.1176838875 0.1613369882 0.1540750949 0.2106595784 0.0053453021 0.0373570000 681448941 0 402718720 -0.1536739618 0.0005778727 -0.1299775988 2541 1311867255.1510150433 0.1615408063 0.1540780330 0.2106595784 0.0053448865 0.0392110000 681452085 0 402718720 -0.1535366178 0.0003230344 -0.1318910569 2542 1311867255.1837830544 0.1617143750 0.1540810370 0.2106595784 0.0053447918 0.0377550000 681455061 0 402718720 -0.1529936939 0.0015369973 -0.1342551410 2543 1311867255.2169129848 0.1625038087 0.1540843492 0.2106595784 0.0053446084 0.0360970000 681458261 0 402718720 -0.1534529775 0.0027150183 -0.1364298165 2544 1311867255.2459061146 0.1631336063 0.1540879063 0.2106595784 0.0053441392 0.0359570000 681461293 0 402718720 -0.1541209221 0.0024276557 -0.1381745040 2545 1311867255.2793660164 0.1635365337 0.1540916189 0.2106595784 0.0053532535 0.0400950000 681464493 0 402718720 -0.1545883417 0.0023888021 -0.1403556913 2546 1311867255.3138470650 0.1635357440 0.1540953283 0.2106595784 0.0053528955 0.0367640000 681467637 0 402718720 -0.1535010785 0.0031158032 -0.1428042650 2547 1311867255.3468310833 0.1634323448 0.1540989942 0.2106595784 0.0053525120 0.0380690000 681470837 0 402718720 -0.1524401456 0.0027804021 -0.1449342370 2548 1311867255.3794751167 0.1646281779 0.1541031265 0.2106595784 0.0053519062 0.0372330000 681474037 0 402718720 -0.1530714035 0.0028954786 -0.1473762691 2549 1311867255.4137570858 0.1657718122 0.1541077043 0.2106595784 0.0053561590 0.0372710000 681477181 0 402718720 -0.1536156982 0.0030970322 -0.1497998089 2550 1311867255.4455399513 0.1655399501 0.1541121875 0.2106595784 0.0053552673 0.0371820000 681480325 0 402718720 -0.1525828689 0.0034673882 -0.1521832049 2551 1311867255.4794819355 0.1664375812 0.1541170191 0.2106595784 0.0053559509 0.0362860000 681483581 0 402718720 -0.1523870379 0.0037809380 -0.1547551751 2552 1311867255.5155849457 0.1673944443 0.1541222218 0.2106595784 0.0053574819 0.0356280000 681486781 0 402718720 -0.1522457749 0.0044615553 -0.1576181054 2553 1311867255.5457301140 0.1673015952 0.1541273841 0.2106595784 0.0053585529 0.0357300000 681489869 0 402718720 -0.1519372165 0.0046259197 -0.1599900872 2554 1311867255.5794420242 0.1683070809 0.1541329361 0.2106595784 0.0053576223 0.0370810000 681493069 0 402718720 -0.1515849680 0.0036679194 -0.1618630886 2555 1311867255.6153230667 0.1690469980 0.1541387733 0.2106595784 0.0053588189 0.0336150000 681496269 0 402718720 -0.1517741084 0.0049386248 -0.1647253335 2556 1311867255.6456420422 0.1694824547 0.1541447763 0.2106595784 0.0053581822 0.0359730000 681499413 0 402718720 -0.1515520662 0.0065066051 -0.1673702300 2557 1311867255.6800808907 0.1704099327 0.1541511373 0.2106595784 0.0053580922 0.0378650000 681502613 0 402718720 -0.1518165767 0.0055780411 -0.1692261994 2558 1311867255.7182691097 0.1714070588 0.1541578832 0.2106595784 0.0053588036 0.0364430000 681505925 0 402718720 -0.1519961208 0.0040837131 -0.1705956161 2559 1311867255.7457671165 0.1713583320 0.1541646048 0.2106595784 0.0053584191 0.0364320000 681508957 0 402718720 -0.1513109505 0.0067429226 -0.1739292443 2560 1311867255.7809960842 0.1721781492 0.1541716413 0.2106595784 0.0053627020 0.0349640000 681512157 0 402718720 -0.1510632336 0.0080718631 -0.1767359078 2561 1311867255.8175930977 0.1730046272 0.1541789951 0.2106595784 0.0053659946 0.0348970000 681515413 0 402718720 -0.1517370194 0.0059128171 -0.1782483757 2562 1311867255.8456869125 0.1737173647 0.1541866213 0.2106595784 0.0053659161 0.0350260000 681518445 0 402718720 -0.1523215026 0.0061741732 -0.1804205626 2563 1311867255.8793790340 0.1741445065 0.1541944082 0.2106595784 0.0053649936 0.0355850000 681521701 0 402718720 -0.1522212774 0.0079769362 -0.1831741631 2564 1311867255.9140241146 0.1747008562 0.1542024060 0.2106595784 0.0053641865 0.0357160000 681524901 0 402718720 -0.1525316387 0.0066863000 -0.1848888546 2565 1311867255.9459009171 0.1749462634 0.1542104933 0.2106595784 0.0053631985 0.0357960000 681528045 0 402718720 -0.1528738141 0.0046268287 -0.1864463389 2566 1311867255.9794859886 0.1755152941 0.1542187960 0.2106595784 0.0053622967 0.0380150000 681531245 0 402718720 -0.1526597887 0.0054259226 -0.1888890862 2567 1311867256.0177829266 0.1763007045 0.1542273983 0.2106595784 0.0053613094 0.0375430000 681534557 0 402718720 -0.1537189186 0.0059196586 -0.1914188117 2568 1311867256.0460040569 0.1772043854 0.1542363457 0.2106595784 0.0053607473 0.0374090000 681537589 0 402718720 -0.1551396400 0.0052095139 -0.1932486445 2569 1311867256.0795900822 0.1773439050 0.1542453405 0.2106595784 0.0053622779 0.0347560000 681540733 0 402718720 -0.1550214440 0.0053676781 -0.1958604902 2570 1311867256.1167299747 0.1773076206 0.1542543141 0.2106595784 0.0053620692 0.0366070000 681544101 0 402718720 -0.1544901431 0.0063171159 -0.1983165592 2571 1311867256.1452190876 0.1781862974 0.1542636225 0.2106595784 0.0053625138 0.0352920000 681547077 0 402718720 -0.1557176262 0.0068511087 -0.2002955228 2572 1311867256.1795060635 0.1800515950 0.1542736490 0.2106595784 0.0053639675 0.0364830000 681550389 0 402718720 -0.1577668786 0.0053349952 -0.2015400082 2573 1311867256.2177369595 0.1797088087 0.1542835344 0.2106595784 0.0053644072 0.0378140000 681553645 0 402718720 -0.1577121615 0.0054855309 -0.2044499367 2574 1311867256.2454619408 0.1794937849 0.1542933286 0.2106595784 0.0053639540 0.0382800000 681556621 0 402718720 -0.1572002918 0.0061499947 -0.2071009129 2575 1311867256.2846980095 0.1819246113 0.1543040592 0.2106595784 0.0053634212 0.0390410000 681559989 0 402718720 -0.1595918834 0.0053521125 -0.2086527050 2576 1311867256.3143339157 0.1821552068 0.1543148709 0.2106595784 0.0053655802 0.0389460000 681563021 0 402718720 -0.1604437828 0.0041133948 -0.2111300528 2577 1311867256.3471689224 0.1805937290 0.1543250684 0.2106595784 0.0053657851 0.0367140000 681566221 0 402718720 -0.1590311527 0.0048164781 -0.2153277993 2578 1311867256.3848030567 0.1816945821 0.1543356850 0.2106595784 0.0053654257 0.0401970000 681569477 0 402718720 -0.1594608426 0.0038619807 -0.2173747718 2579 1311867256.4158530235 0.1824381799 0.1543465816 0.2106595784 0.0053644330 0.0396390000 681572565 0 402718720 -0.1609974056 0.0031277116 -0.2205849439 2580 1311867256.4452829361 0.1837668866 0.1543579849 0.2106595784 0.0053662875 0.0402250000 681575653 0 402718720 -0.1616406590 0.0045510898 -0.2233904451 2581 1311867256.4843750000 0.1856273115 0.1543701001 0.2106595784 0.0053670664 0.0383700000 681578965 0 402718720 -0.1642978787 0.0051570670 -0.2263492942 2582 1311867256.5135769844 0.1865618825 0.1543825678 0.2106595784 0.0053663317 0.0415580000 681582109 0 402718720 -0.1659381390 0.0031952322 -0.2282447964 2583 1311867256.5478610992 0.1844508946 0.1543942087 0.2106595784 0.0053852518 0.0398440000 681585309 0 402718720 -0.1642010659 0.0023318385 -0.2317723930 2584 1311867256.5835909843 0.1849040836 0.1544060159 0.2106595784 0.0053973673 0.0406840000 681588621 0 402718720 -0.1633886397 0.0030370310 -0.2350513190 2585 1311867256.6160280704 0.1854965389 0.1544180432 0.2106595784 0.0053964781 0.0404840000 681591709 0 402718720 -0.1637837738 0.0021257901 -0.2372015715 2586 1311867256.6452250481 0.1861730963 0.1544303228 0.2106595784 0.0053958044 0.0348780000 681594797 0 402718720 -0.1646264493 0.0003490533 -0.2391082048 2587 1311867256.6832630634 0.1884900630 0.1544434885 0.2106595784 0.0053955939 0.0387440000 681598165 0 402718720 -0.1661373377 0.0016224835 -0.2417647839 2588 1311867256.7140181065 0.1889458746 0.1544568202 0.2106595784 0.0053954735 0.0383240000 681601197 0 402718720 -0.1659257412 0.0034351079 -0.2444547713 2589 1311867256.7463290691 0.1894315034 0.1544703292 0.2106595784 0.0053946847 0.0388900000 681604341 0 402718720 -0.1660585552 0.0026981316 -0.2462475151 2590 1311867256.7827351093 0.1888567954 0.1544836058 0.2106595784 0.0053944219 0.0417280000 681607653 0 402718720 -0.1637968123 0.0037930557 -0.2492936105 2591 1311867256.8140380383 0.1896036118 0.1544971604 0.2106595784 0.0053953020 0.0382070000 681610741 0 402718720 -0.1634352505 0.0033926573 -0.2511402965 2592 1311867256.8477220535 0.1926619560 0.1545118845 0.2106595784 0.0053944792 0.0402240000 681613941 0 402718720 -0.1660242677 0.0001723990 -0.2517390251 2593 1311867256.8838899136 0.1921724081 0.1545264084 0.2106595784 0.0053954597 0.0370240000 681617141 0 402718720 -0.1647212654 0.0009492996 -0.2551981509 2594 1311867256.9147980213 0.1913320273 0.1545405971 0.2106595784 0.0053946382 0.0381430000 681620285 0 402718720 -0.1623912454 0.0023635575 -0.2588892877 2595 1311867256.9465310574 0.1926631629 0.1545552879 0.2106595784 0.0053937752 0.0415680000 681623429 0 402718720 -0.1633952707 0.0011089811 -0.2618328631 2596 1311867256.9814469814 0.1928439736 0.1545700370 0.2106595784 0.0053929533 0.0391900000 681626629 0 402718720 -0.1633670628 -0.0010143006 -0.2647971511 2597 1311867257.0129880905 0.1924967021 0.1545846411 0.2106595784 0.0053921527 0.0407510000 681629829 0 402718720 -0.1621078402 -0.0013352862 -0.2681962848 2598 1311867257.0451850891 0.1934754252 0.1545996106 0.2106595784 0.0053936690 0.0416550000 681632917 0 402718720 -0.1624789685 0.0011911799 -0.2721076310 2599 1311867257.0841100216 0.1945866197 0.1546149961 0.2106595784 0.0053930840 0.0398430000 681636229 0 402718720 -0.1621397436 0.0029261236 -0.2751151919 2600 1311867257.1133849621 0.1954583675 0.1546307051 0.2106595784 0.0053921667 0.0406860000 681639373 0 402718720 -0.1633578092 0.0014712816 -0.2769956887 2601 1311867257.1474220753 0.1964771897 0.1546467937 0.2106595784 0.0053913403 0.0406310000 681642573 0 402718720 -0.1636102349 0.0024873011 -0.2793367505 2602 1311867257.1820690632 0.1970833093 0.1546631029 0.2106595784 0.0053905089 0.0404730000 681645773 0 402718720 -0.1631765962 0.0050957445 -0.2822568119 2603 1311867257.2147579193 0.1964023560 0.1546791379 0.2106595784 0.0053939598 0.0383250000 681648917 0 402718720 -0.1632496268 0.0019775033 -0.2841707468 2604 1311867257.2456970215 0.1974544972 0.1546955647 0.2106595784 0.0053965502 0.0427220000 681652005 0 402718720 -0.1635898799 0.0015874677 -0.2861412168 2605 1311867257.2824120522 0.1972352415 0.1547118947 0.2106595784 0.0053956091 0.0429440000 681655317 0 402718720 -0.1629421562 0.0041166744 -0.2902016938 2606 1311867257.3133339882 0.1974267364 0.1547282857 0.2106595784 0.0053946255 0.0405610000 681658405 0 402718720 -0.1614321321 0.0054393378 -0.2923564613 2607 1311867257.3452789783 0.1988269240 0.1547452012 0.2106595784 0.0053943164 0.0407540000 681661493 0 402718720 -0.1629507542 0.0042855991 -0.2939885557 2608 1311867257.3839509487 0.1986662447 0.1547620421 0.2106595784 0.0053942739 0.5705420000 694019069 0 402718720 -0.1625010818 0.0042613852 -0.2973415554 2609 1311867257.4160621166 0.2016254216 0.1547800043 0.2106595784 0.0053983784 0.0334510000 697681477 0 402718720 -0.1637194008 0.0054224506 -0.2982591987 2610 1311867257.4458520412 0.2025853246 0.1547983205 0.2106595784 0.0053977090 0.0326240000 700876701 0 402718720 -0.1638106406 0.0049893297 -0.2994292080 2611 1311867257.4851169586 0.2037105858 0.1548170536 0.2106595784 0.0053971995 0.0399680000 700880069 0 402718720 -0.1646295488 0.0052441116 -0.3021604419 2612 1311867257.5166110992 0.2037900239 0.1548358029 0.2106595784 0.0053965698 0.0439410000 700883213 0 402718720 -0.1631571203 0.0082778428 -0.3050715327 2613 1311867257.5437018871 0.2039754838 0.1548546087 0.2106595784 0.0053959909 0.0372990000 700886245 0 402718720 -0.1624784172 0.0075727035 -0.3065097034 2614 1311867257.5836091042 0.2052329779 0.1548738812 0.2106595784 0.0054048822 0.0375240000 700889557 0 402718720 -0.1625474691 0.0068929116 -0.3083315194 2615 1311867257.6154129505 0.2063204795 0.1548935549 0.2106595784 0.0054102642 0.0382830000 700892645 0 402718720 -0.1635968238 0.0087525146 -0.3114151955 2616 1311867257.6437489986 0.2065578103 0.1549133042 0.2106595784 0.0054093763 0.0367940000 700895677 0 402718720 -0.1626829356 0.0108396243 -0.3135146201 2617 1311867257.6842410564 0.2073256969 0.1549333319 0.2106595784 0.0054085494 0.0371780000 700899101 0 402718720 -0.1627468914 0.0104798703 -0.3152543306 2618 1311867257.7187778950 0.2079950273 0.1549535999 0.2106595784 0.0054077803 0.0367290000 700902413 0 402718720 -0.1620740294 0.0099644717 -0.3162926137 2619 1311867257.7437469959 0.2066498995 0.1549733389 0.2106595784 0.0054078971 0.0357850000 700905221 0 402718720 -0.1597575843 0.0089914212 -0.3179388046 2620 1311867257.7837998867 0.2081032097 0.1549936174 0.2106595784 0.0054074908 0.0375150000 700908701 0 402718720 -0.1596462429 0.0101765832 -0.3195065558 2621 1311867257.8180990219 0.2097436786 0.1550145064 0.2106595784 0.0054068272 0.0393060000 700911901 0 402718720 -0.1610373110 0.0100169498 -0.3207817078 2622 1311867257.8435750008 0.2095955312 0.1550353230 0.2106595784 0.0054059179 0.0366660000 700914765 0 402718720 -0.1605045199 0.0108292988 -0.3224784732 2623 1311867257.8854579926 0.2101597339 0.1550563388 0.2106595784 0.0054058993 0.0360880000 700918245 0 402718720 -0.1590919495 0.0100179585 -0.3240738213 2624 1311867257.9152350426 0.2098368406 0.1550772155 0.2106595784 0.0054061477 0.0382220000 700921277 0 402718720 -0.1577607244 0.0105656330 -0.3259561360 2625 1311867257.9437649250 0.2106607109 0.1550983902 0.2106607109 0.0054067179 0.0358090000 700924309 0 402718720 -0.1589123607 0.0098838350 -0.3267750144 2626 1311867257.9850618839 0.2121130675 0.1551201018 0.2121130675 0.0054080177 0.0345680000 700927733 0 402718720 -0.1591442376 0.0103488732 -0.3284805417 2627 1311867258.0135610104 0.2118049860 0.1551416796 0.2121130675 0.0054070334 0.0354310000 700930821 0 402718720 -0.1578211039 0.0089959577 -0.3292037249 2628 1311867258.0436229706 0.2128435671 0.1551636361 0.2128435671 0.0054124422 0.0362300000 700933909 0 402718720 -0.1583091170 0.0076736687 -0.3302263618 2629 1311867258.0836520195 0.2129741162 0.1551856257 0.2129741162 0.0054205866 0.0362670000 700937221 0 402718720 -0.1579919606 0.0070104031 -0.3315753043 2630 1311867258.1137819290 0.2127498239 0.1552075132 0.2129741162 0.0054200059 0.0357410000 700940365 0 402718720 -0.1574902087 0.0073994249 -0.3335880935 2631 1311867258.1437139511 0.2131490558 0.1552295358 0.2131490558 0.0054202752 0.0356440000 700943397 0 402718720 -0.1572166383 0.0081094299 -0.3351281881 2632 1311867258.1848330498 0.2138361335 0.1552518028 0.2138361335 0.0054196277 0.0356040000 700946765 0 402718720 -0.1568725258 0.0076258080 -0.3365397453 2633 1311867258.2162680626 0.2147033364 0.1552743822 0.2147033364 0.0054186152 0.0378410000 700949965 0 402718720 -0.1571487486 0.0068485495 -0.3371998966 2634 1311867258.2436239719 0.2143187672 0.1552967984 0.2147033364 0.0054193319 0.0354730000 700952997 0 402718720 -0.1569635272 0.0062255743 -0.3385101259 2635 1311867258.2850100994 0.2143829018 0.1553192220 0.2147033364 0.0054183135 0.0360650000 700956365 0 402718720 -0.1562201679 0.0057152007 -0.3394918740 2636 1311867258.3132739067 0.2141522169 0.1553415410 0.2147033364 0.0054173691 0.0366700000 700959453 0 402718720 -0.1555484980 0.0051711723 -0.3403726518 2637 1311867258.3436419964 0.2151370943 0.1553642166 0.2151370943 0.0054166110 0.0381810000 700962541 0 402718720 -0.1566890478 0.0048997323 -0.3412310779 2638 1311867258.3812050819 0.2158178389 0.1553871331 0.2158178389 0.0054159751 0.0344190000 700965741 0 402718720 -0.1569740623 0.0056512812 -0.3423309326 2639 1311867258.4142630100 0.2158661932 0.1554100505 0.2158661932 0.0054150205 0.0342080000 700968885 0 402718720 -0.1565099359 0.0055192779 -0.3427301943 2640 1311867258.4439070225 0.2166566104 0.1554332500 0.2166566104 0.0054141025 0.0342980000 700971973 0 402718720 -0.1573820561 0.0054214150 -0.3430378437 2641 1311867258.4825460911 0.2160555124 0.1554562042 0.2166566104 0.0054131832 0.0358520000 700975397 0 402718720 -0.1563343257 0.0045745540 -0.3437430561 2642 1311867258.5139799118 0.2168044746 0.1554794246 0.2168044746 0.0054135722 0.0367640000 700978485 0 402718720 -0.1563517302 0.0031303209 -0.3439263701 2643 1311867258.5435950756 0.2169332206 0.1555026762 0.2169332206 0.0054136685 0.0356360000 700981629 0 402718720 -0.1563154906 0.0024350449 -0.3447181880 2644 1311867258.5835978985 0.2177296579 0.1555262113 0.2177296579 0.0054128694 0.0350340000 700984885 0 402718720 -0.1564041078 0.0022904074 -0.3460775316 2645 1311867258.6141600609 0.2178522348 0.1555497750 0.2178522348 0.0054133581 0.0352950000 700987973 0 402718720 -0.1559408158 0.0017356350 -0.3472979665 2646 1311867258.6437780857 0.2183006406 0.1555734904 0.2183006406 0.0054147410 0.0341140000 700991117 0 402718720 -0.1556155831 0.0018004884 -0.3489237428 2647 1311867258.6852200031 0.2192665190 0.1555975528 0.2192665190 0.0054156210 0.0368380000 700994485 0 402718720 -0.1549191475 -0.0005613728 -0.3495020270 2648 1311867258.7134060860 0.2201601267 0.1556219344 0.2201601267 0.0054146665 0.0367530000 700997461 0 402718720 -0.1557486206 -0.0026436585 -0.3511523604 2649 1311867258.7436649799 0.2197013795 0.1556461244 0.2201601267 0.0054143025 0.0343780000 701000661 0 402718720 -0.1538580954 -0.0013530257 -0.3538708389 2650 1311867258.7843489647 0.2201282084 0.1556704573 0.2201601267 0.0054140118 0.0373220000 701003917 0 402718720 -0.1525222808 0.0000386160 -0.3555090725 2651 1311867258.8116900921 0.2210925221 0.1556951356 0.2210925221 0.0054130141 0.0360510000 701007005 0 402718720 -0.1536543965 -0.0024460230 -0.3559928238 2652 1311867258.8438930511 0.2207523286 0.1557196669 0.2210925221 0.0054123612 0.0334270000 701010149 0 402718720 -0.1531461775 -0.0025197316 -0.3584131002 2653 1311867258.8845601082 0.2208918482 0.1557442324 0.2210925221 0.0054125078 0.0377330000 701013461 0 402718720 -0.1512198150 -0.0024089294 -0.3599622846 2654 1311867258.9117500782 0.2212637663 0.1557689195 0.2212637663 0.0054115202 0.0352780000 701016493 0 402718720 -0.1511383206 -0.0038985971 -0.3608995378 2655 1311867258.9440000057 0.2222870439 0.1557939734 0.2222870439 0.0054115183 0.0350650000 701019693 0 402718720 -0.1521884203 -0.0051636877 -0.3625132143 2656 1311867258.9841549397 0.2235892862 0.1558194987 0.2235892862 0.0054122919 0.0353210000 701023061 0 402718720 -0.1516469866 -0.0033167684 -0.3652465343 2657 1311867259.0119071007 0.2234068364 0.1558449362 0.2235892862 0.0054114867 0.0366720000 701026037 0 402718720 -0.1500076950 -0.0049147005 -0.3662679791 2658 1311867259.0439701080 0.2228518724 0.1558701457 0.2235892862 0.0054160234 0.0350100000 701029125 0 402718720 -0.1482799798 -0.0069562611 -0.3683356643 2659 1311867259.0845470428 0.2244890034 0.1558959520 0.2244890034 0.0054165650 0.0349100000 701032549 0 402718720 -0.1479006708 -0.0055446797 -0.3714290261 2660 1311867259.1117339134 0.2251704335 0.1559219950 0.2251704335 0.0054156531 0.0379460000 701035581 0 402718720 -0.1469248682 -0.0040187575 -0.3733170331 2661 1311867259.1438770294 0.2251736820 0.1559480197 0.2251736820 0.0054154159 0.0368480000 701038781 0 402718720 -0.1454980820 -0.0064391638 -0.3741704524 2662 1311867259.1837639809 0.2267658859 0.1559746230 0.2267658859 0.0054152577 0.0352420000 701042037 0 402718720 -0.1450934261 -0.0061927345 -0.3766133189 2663 1311867259.2119510174 0.2268844694 0.1560012508 0.2268844694 0.0054143285 0.0377800000 701045125 0 402718720 -0.1432306916 -0.0054232175 -0.3781609535 2664 1311867259.2438530922 0.2279023975 0.1560282407 0.2279023975 0.0054137940 0.0407330000 701048269 0 402718720 -0.1415870637 -0.0070513743 -0.3790829480 2665 1311867259.2815868855 0.2286925018 0.1560555068 0.2286925018 0.0054128978 0.0380130000 701051581 0 402718720 -0.1404098421 -0.0074395123 -0.3817307651 2666 1311867259.3119280338 0.2285182774 0.1560826872 0.2286925018 0.0054125442 0.0366210000 701054725 0 402718720 -0.1386965960 -0.0055841976 -0.3850359321 2667 1311867259.3437619209 0.2305227667 0.1561105987 0.2305227667 0.0054125866 0.0376610000 701057869 0 402718720 -0.1394216716 -0.0055147759 -0.3871986568 2668 1311867259.3839108944 0.2315291613 0.1561388665 0.2315291613 0.0054116665 0.0382980000 701061181 0 402718720 -0.1380996406 -0.0070488434 -0.3891282678 2669 1311867259.4117219448 0.2301859856 0.1561666099 0.2315291613 0.0054113441 0.0391750000 701064213 0 402718720 -0.1356143653 -0.0070086978 -0.3924249709 2670 1311867259.4437930584 0.2307918668 0.1561945595 0.2315291613 0.0054107015 0.0384830000 701067357 0 402718720 -0.1344285309 -0.0054082023 -0.3953781426 2671 1311867259.4816150665 0.2324482203 0.1562231082 0.2324482203 0.0054098545 0.0382090000 701070613 0 402718720 -0.1340711713 -0.0059393658 -0.3974992037 2672 1311867259.5117299557 0.2337756902 0.1562521324 0.2337756902 0.0054092177 0.0391690000 701073701 0 402718720 -0.1349544227 -0.0071982834 -0.3999053240 2673 1311867259.5505781174 0.2349588424 0.1562815775 0.2349588424 0.0054135172 0.0376220000 701077013 0 402718720 -0.1344497055 -0.0069733313 -0.4028996527 2674 1311867259.5822160244 0.2335476428 0.1563104728 0.2349588424 0.0054129995 0.0396240000 701080213 0 402718720 -0.1313552707 -0.0073906290 -0.4061268866 2675 1311867259.6117389202 0.2348707318 0.1563398411 0.2349588424 0.0054132859 0.0399040000 701083245 0 402718720 -0.1316328049 -0.0067698271 -0.4090267122 2676 1311867259.6494710445 0.2370629460 0.1563700067 0.2370629460 0.0054127350 0.0395400000 701086445 0 402718720 -0.1330716014 -0.0053454065 -0.4124321043 2677 1311867259.6828489304 0.2373626083 0.1564002617 0.2373626083 0.0054131560 0.0351880000 701089645 0 402718720 -0.1321248263 -0.0029261843 -0.4159829915 2678 1311867259.7118270397 0.2367616594 0.1564302696 0.2373626083 0.0054122547 0.0383870000 701092733 0 402718720 -0.1302391142 -0.0026880968 -0.4178169966 2679 1311867259.7520070076 0.2379257530 0.1564606898 0.2379257530 0.0054117373 0.0388480000 701096101 0 402718720 -0.1302719265 -0.0038933021 -0.4191560149 2680 1311867259.7817800045 0.2387763560 0.1564914046 0.2387763560 0.0054108225 0.0358960000 701099189 0 402718720 -0.1313565075 -0.0036895205 -0.4215371311 2681 1311867259.8118169308 0.2386928797 0.1565220653 0.2387763560 0.0054099173 0.0398490000 701102277 0 402718720 -0.1302759200 -0.0017377215 -0.4239470959 2682 1311867259.8503990173 0.2383496016 0.1565525752 0.2387763560 0.0054089755 0.0389660000 701105589 0 402718720 -0.1280387044 -0.0017128950 -0.4254880548 2683 1311867259.8818349838 0.2398299277 0.1565836141 0.2398299277 0.0054083582 0.0389770000 701108733 0 402718720 -0.1298168302 -0.0038609831 -0.4265713096 2684 1311867259.9121129513 0.2404716909 0.1566148690 0.2404716909 0.0054075436 0.0393320000 701111821 0 402718720 -0.1306401640 -0.0020483891 -0.4295490384 2685 1311867259.9520030022 0.2402395904 0.1566460141 0.2404716909 0.0054077604 0.0377970000 701115189 0 402718720 -0.1280739605 -0.0004209517 -0.4312239885 2686 1311867259.9797670841 0.2410426736 0.1566774351 0.2410426736 0.0054070663 0.0418170000 701118221 0 402718720 -0.1290607899 -0.0035658297 -0.4320130646 2687 1311867260.0126910210 0.2410810590 0.1567088469 0.2410810590 0.0054061811 0.0388900000 701121365 0 402718720 -0.1287264675 -0.0018952710 -0.4349330962 2688 1311867260.0493149757 0.2415995598 0.1567404283 0.2415995598 0.0054052144 0.0412210000 701124565 0 402718720 -0.1273770779 0.0002158077 -0.4372053742 2689 1311867260.0799129009 0.2419236302 0.1567721067 0.2419236302 0.0054042671 0.0399230000 701127709 0 402718720 -0.1264718920 0.0004463253 -0.4390030503 2690 1311867260.1119410992 0.2428430468 0.1568041033 0.2428430468 0.0054042225 0.0418230000 701130853 0 402718720 -0.1265252382 0.0000830541 -0.4409700632 2691 1311867260.1513710022 0.2435419261 0.1568363359 0.2435419261 0.0054044012 0.0419250000 701134165 0 402718720 -0.1260707229 0.0008354866 -0.4436278343 2692 1311867260.1799340248 0.2440654784 0.1568687390 0.2440654784 0.0054038279 0.0400600000 701137197 0 402718720 -0.1254575402 0.0019005697 -0.4462340176 2693 1311867260.2119131088 0.2453936189 0.1569016112 0.2453936189 0.0054029123 0.0384580000 701140397 0 402718720 -0.1256123185 0.0026385542 -0.4481970072 2694 1311867260.2496368885 0.2464949340 0.1569348678 0.2464949340 0.0054019225 0.0393390000 701143709 0 402718720 -0.1254730821 0.0012571285 -0.4505707324 2695 1311867260.2798650265 0.2466905117 0.1569681723 0.2466905117 0.0054013639 0.0392560000 701146741 0 402718720 -0.1245694458 0.0048955400 -0.4549216628 2696 1311867260.3120679855 0.2464327216 0.1570013565 0.2466905117 0.0054003977 0.0398790000 701149941 0 402718720 -0.1223292351 0.0067628138 -0.4571708739 2697 1311867260.3505079746 0.2477958351 0.1570350215 0.2477958351 0.0054009261 0.0397510000 701153253 0 402718720 -0.1227749437 0.0050083301 -0.4588760436 2698 1311867260.3800020218 0.2485324293 0.1570689345 0.2485324293 0.0054017764 0.0424590000 701156285 0 402718720 -0.1228027344 0.0077267936 -0.4621998966 2699 1311867260.4119999409 0.2490261495 0.1571030054 0.2490261495 0.0054008434 0.0419940000 701159485 0 402718720 -0.1225300804 0.0100465855 -0.4649141133 2700 1311867260.4521689415 0.2500677109 0.1571374367 0.2500677109 0.0054009673 0.0418560000 701162741 0 402718720 -0.1223021150 0.0104813660 -0.4668150544 2701 1311867260.4797720909 0.2507029772 0.1571720778 0.2507029772 0.0054042509 0.0397240000 701165773 0 402718720 -0.1228102669 0.0105207674 -0.4689015746 2702 1311867260.5121018887 0.2502408028 0.1572065222 0.2507029772 0.0054060353 0.0423470000 701168917 0 402718720 -0.1207722574 0.0123063559 -0.4715448618 2703 1311867260.5527660847 0.2511074841 0.1572412617 0.2511074841 0.0054051515 0.0407370000 701172229 0 402718720 -0.1198828146 0.0140234185 -0.4739568233 2704 1311867260.5799050331 0.2533608675 0.1572768089 0.2533608675 0.0054050261 0.0405100000 701175205 0 402718720 -0.1218612641 0.0135568278 -0.4754208922 2705 1311867260.6120140553 0.2535167933 0.1573123875 0.2535167933 0.0054040842 0.0386980000 701178405 0 402718720 -0.1214479804 0.0123557225 -0.4773235023 2706 1311867260.6493339539 0.2536253333 0.1573479798 0.2536253333 0.0054031075 0.0405690000 701181661 0 402718720 -0.1195335686 0.0127331642 -0.4797994792 2707 1311867260.6798601151 0.2549467087 0.1573840340 0.2549467087 0.0054031939 0.0403130000 701184749 0 402718720 -0.1184181497 0.0108386567 -0.4812507629 2708 1311867260.7118670940 0.2561129332 0.1574204923 0.2561129332 0.0054025532 0.0409630000 701187893 0 402718720 -0.1195475683 0.0100158285 -0.4841205180 2709 1311867260.7493290901 0.2573669553 0.1574573865 0.2573669553 0.0054037071 0.0408950000 701191149 0 402718720 -0.1196262091 0.0120553467 -0.4876753390 2710 1311867260.7800350189 0.2584660947 0.1574946591 0.2584660947 0.0054045847 0.0417510000 701194293 0 402718720 -0.1200059876 0.0112898163 -0.4896553457 2711 1311867260.8121459484 0.2584313750 0.1575318914 0.2584660947 0.0054052547 0.0412290000 701197493 0 402718720 -0.1183577105 0.0089855595 -0.4915255308 2712 1311867260.8514161110 0.2590485811 0.1575693238 0.2590485811 0.0054078241 0.0408480000 701200805 0 402718720 -0.1171098426 0.0078980271 -0.4934622347 2713 1311867260.8798089027 0.2597948909 0.1576070037 0.2597948909 0.0054090968 0.0415260000 701203725 0 402718720 -0.1167080253 0.0068581658 -0.4964779615 2714 1311867260.9120171070 0.2606452703 0.1576449691 0.2606452703 0.0054091246 0.0420460000 701206925 0 402718720 -0.1170083880 0.0092863459 -0.5002256632 2715 1311867260.9494390488 0.2603336275 0.1576827919 0.2606452703 0.0054317806 0.0418140000 701210237 0 402718720 -0.1157637686 0.0084832981 -0.5022338629 2716 1311867260.9799499512 0.2624012530 0.1577213480 0.2624012530 0.0054451314 0.0420100000 701213269 0 402718720 -0.1165628061 0.0074441703 -0.5047036409 2717 1311867261.0118749142 0.2634620368 0.1577602662 0.2634620368 0.0054456630 0.0381420000 701216469 0 402718720 -0.1173737496 0.0053613638 -0.5068567395 2718 1311867261.0519499779 0.2652151585 0.1577998007 0.2652151585 0.0054477523 0.0418660000 701219837 0 402718720 -0.1180159450 0.0055439924 -0.5095327497 2719 1311867261.0798048973 0.2654725313 0.1578394008 0.2654725313 0.0054470333 0.0413700000 701222813 0 402718720 -0.1177843213 0.0039775316 -0.5119115710 2720 1311867261.1118710041 0.2653248310 0.1578789175 0.2654725313 0.0054461687 0.0428800000 701226013 0 402718720 -0.1174121052 0.0005490592 -0.5143441558 2721 1311867261.1530790329 0.2671520412 0.1579190767 0.2671520412 0.0054524415 0.0473200000 701229493 0 402718720 -0.1180020198 0.0024139497 -0.5180255175 2722 1311867261.1799860001 0.2686789334 0.1579597673 0.2686789334 0.0054569882 0.0505330000 701232413 0 402718720 -0.1194310784 0.0011738475 -0.5196552277 2723 1311867261.2119870186 0.2679597139 0.1580001639 0.2686789334 0.0054644023 0.0528030000 701235613 0 402718720 -0.1194136739 -0.0007241514 -0.5225815177 2724 1311867261.2477910519 0.2680181265 0.1580405523 0.2686789334 0.0054634832 0.7275000000 713600881 0 402718720 -0.1178619638 0.0006890796 -0.5255562663 2725 1311867261.2800118923 0.2716141045 0.1580822307 0.2716141045 0.0054632225 0.0347590000 717263177 0 402718720 -0.1182089075 0.0032576225 -0.5249454379 2726 1311867261.3120720387 0.2724571824 0.1581241878 0.2724571824 0.0054685513 0.0331620000 720458569 0 402718720 -0.1189048588 0.0043455823 -0.5273047686 2727 1311867261.3477809429 0.2738012075 0.1581666069 0.2738012075 0.0054686124 0.0487850000 720461825 0 402718720 -0.1206282899 0.0049440134 -0.5294694901 2728 1311867261.3799629211 0.2736065686 0.1582089236 0.2738012075 0.0054682520 0.0579310000 720464913 0 402718720 -0.1207706183 0.0076807956 -0.5326580405 2729 1311867261.4121179581 0.2737506330 0.1582512621 0.2738012075 0.0054673003 0.0404600000 720468057 0 402718720 -0.1204762831 0.0084373849 -0.5335023999 2730 1311867261.4480879307 0.2741999328 0.1582937341 0.2741999328 0.0054668351 0.0423770000 720471369 0 402718720 -0.1233870313 0.0054970947 -0.5342566967 2731 1311867261.4798569679 0.2749293447 0.1583364421 0.2749293447 0.0054693958 0.0371080000 720474513 0 402718720 -0.1237596571 0.0054683108 -0.5355356336 2732 1311867261.5122499466 0.2741592526 0.1583788370 0.2749293447 0.0054688899 0.0401990000 720477657 0 402718720 -0.1231839880 0.0064657563 -0.5372154117 2733 1311867261.5478630066 0.2748873234 0.1584214673 0.2749293447 0.0054682948 0.0393020000 720480913 0 402718720 -0.1238127798 0.0070975120 -0.5381071568 2734 1311867261.5799028873 0.2745262682 0.1584639343 0.2749293447 0.0054674667 0.0395520000 720484001 0 402718720 -0.1244128942 0.0047199936 -0.5390536189 2735 1311867261.6121311188 0.2759848535 0.1585069035 0.2759848535 0.0054730974 0.0379530000 720487201 0 402718720 -0.1265189648 0.0070777363 -0.5413419008 2736 1311867261.6480779648 0.2764535844 0.1585500127 0.2764535844 0.0054795796 0.0402290000 720490457 0 402718720 -0.1272129118 0.0066925902 -0.5422208905 2737 1311867261.6803009510 0.2760864794 0.1585929563 0.2764535844 0.0054825183 0.0397330000 720493601 0 402718720 -0.1268004924 0.0057840832 -0.5443948507 2738 1311867261.7123830318 0.2764966488 0.1586360182 0.2764966488 0.0054873589 0.0387070000 720496745 0 402718720 -0.1278142333 0.0067995666 -0.5471821427 2739 1311867261.7480850220 0.2777579725 0.1586795093 0.2777579725 0.0054885154 0.0434870000 720500001 0 402718720 -0.1288608462 0.0087497188 -0.5501702428 2740 1311867261.7799179554 0.2783083320 0.1587231694 0.2783083320 0.0054886904 0.0420800000 720502977 0 402718720 -0.1289091110 0.0118803242 -0.5531092286 2741 1311867261.8119559288 0.2785885632 0.1587669000 0.2785885632 0.0054959532 0.0385560000 720506121 0 402718720 -0.1288450956 0.0124793593 -0.5554514527 2742 1311867261.8480060101 0.2803072631 0.1588112254 0.2803072631 0.0054950174 0.0377270000 720509377 0 402718720 -0.1314897388 0.0127476035 -0.5577737689 2743 1311867261.8800730705 0.2802641988 0.1588555028 0.2803072631 0.0054984750 0.0389060000 720512521 0 402718720 -0.1303216964 0.0174129792 -0.5609130859 2744 1311867261.9121630192 0.2802883983 0.1588997568 0.2803072631 0.0055028403 0.0377190000 720515665 0 402718720 -0.1295888871 0.0172230583 -0.5623272061 2745 1311867261.9479999542 0.2811950445 0.1589443088 0.2811950445 0.0055019552 0.0382880000 720518921 0 402718720 -0.1305693388 0.0170860253 -0.5646461844 2746 1311867261.9802420139 0.2815639079 0.1589889627 0.2815639079 0.0055024689 0.0381950000 720522065 0 402718720 -0.1292377114 0.0197098218 -0.5670815110 2747 1311867262.0119619370 0.2826815844 0.1590339910 0.2826815844 0.0055026141 0.0370350000 720525209 0 402718720 -0.1305146813 0.0202886034 -0.5691680908 2748 1311867262.0479071140 0.2837603986 0.1590793790 0.2837603986 0.0055030691 0.0399400000 720528465 0 402718720 -0.1311255693 0.0202182084 -0.5716419816 2749 1311867262.0803010464 0.2837589979 0.1591247336 0.2837603986 0.0055024470 0.0394550000 720531609 0 402718720 -0.1299818754 0.0203374233 -0.5739345551 2750 1311867262.1179549694 0.2846260369 0.1591703704 0.2846260369 0.0055026021 0.0374390000 720534865 0 402718720 -0.1295635849 0.0233944356 -0.5771187544 2751 1311867262.1478600502 0.2855588794 0.1592163132 0.2855588794 0.0055028899 0.0394170000 720538009 0 402718720 -0.1303136647 0.0242664386 -0.5793296099 2752 1311867262.1801190376 0.2859835625 0.1592623768 0.2859835625 0.0055022343 0.0406510000 720541041 0 402718720 -0.1298549473 0.0240783952 -0.5817196965 2753 1311867262.2121670246 0.2860501111 0.1593084312 0.2860501111 0.0055015577 0.0370620000 720544241 0 402718720 -0.1293120235 0.0241772067 -0.5843889117 2754 1311867262.2478549480 0.2865518630 0.1593546344 0.2865518630 0.0055007510 0.0379770000 720547497 0 402718720 -0.1291220337 0.0254685059 -0.5881336331 2755 1311867262.2799088955 0.2872007489 0.1594010395 0.2872007489 0.0055058975 0.0342600000 720550585 0 402718720 -0.1285563856 0.0288597960 -0.5916649699 2756 1311867262.3122069836 0.2886247933 0.1594479276 0.2886247933 0.0055125939 0.0364590000 720553785 0 402718720 -0.1298581660 0.0292525496 -0.5948584676 2757 1311867262.3479030132 0.2900380492 0.1594952944 0.2900380492 0.0055118364 0.0390300000 720557041 0 402718720 -0.1303647459 0.0301522892 -0.5980611444 2758 1311867262.3799040318 0.2906844914 0.1595428612 0.2906844914 0.0055108968 0.0385480000 720560129 0 402718720 -0.1298252642 0.0333637260 -0.6021158695 2759 1311867262.4119610786 0.2922081947 0.1595909457 0.2922081947 0.0055099861 0.0395770000 720563273 0 402718720 -0.1316159517 0.0330338441 -0.6050875783 2760 1311867262.4480888844 0.2929913998 0.1596392792 0.2929913998 0.0055092906 0.0403830000 720566585 0 402718720 -0.1317673028 0.0342971459 -0.6097394824 2761 1311867262.4798719883 0.2926105857 0.1596874398 0.2929913998 0.0055172738 0.0401280000 720569729 0 402718720 -0.1308499873 0.0371498540 -0.6142231822 2762 1311867262.5121328831 0.2932902277 0.1597358116 0.2932902277 0.0055177284 0.0379320000 720572873 0 402718720 -0.1298375875 0.0363731496 -0.6169517040 2763 1311867262.5479118824 0.2961747050 0.1597851923 0.2961747050 0.0055174497 0.0378650000 720576129 0 402718720 -0.1325879544 0.0377432406 -0.6208148599 2764 1311867262.5798718929 0.2972120345 0.1598349125 0.2972120345 0.0055168639 0.0407830000 720579217 0 402718720 -0.1338657886 0.0410338230 -0.6254060864 2765 1311867262.6122241020 0.2974751890 0.1598846920 0.2974751890 0.0055160703 0.0392640000 720582417 0 402718720 -0.1335118711 0.0438086241 -0.6287976503 2766 1311867262.6478619576 0.2981983125 0.1599346969 0.2981983125 0.0055190461 0.0401630000 720585673 0 402718720 -0.1333637387 0.0437913500 -0.6314824820 2767 1311867262.6802380085 0.3010750711 0.1599857054 0.3010750711 0.0055194252 0.0369000000 720588761 0 402718720 -0.1364081353 0.0455353893 -0.6340061426 2768 1311867262.7120549679 0.3016215861 0.1600368744 0.3016215861 0.0055185870 0.0392220000 720591905 0 402718720 -0.1370136887 0.0464187562 -0.6366448998 2769 1311867262.7480130196 0.3006278276 0.1600876476 0.3016215861 0.0055241303 0.0414880000 720595217 0 402718720 -0.1345918328 0.0456412137 -0.6393445730 2770 1311867262.7800469398 0.3010318875 0.1601385300 0.3016215861 0.0055254647 0.0410850000 720598305 0 402718720 -0.1328796893 0.0458040684 -0.6418053508 2771 1311867262.8121180534 0.3014096320 0.1601895120 0.3016215861 0.0055257438 0.0401930000 720601505 0 402718720 -0.1322323978 0.0454802029 -0.6445728540 2772 1311867262.8479719162 0.3029496074 0.1602410128 0.3029496074 0.0055259911 0.0411890000 720604761 0 402718720 -0.1324364543 0.0462335460 -0.6469128728 2773 1311867262.8800830841 0.3042982519 0.1602929627 0.3042982519 0.0055266135 0.0420030000 720607849 0 402718720 -0.1321111619 0.0469048508 -0.6492262483 2774 1311867262.9120080471 0.3038689196 0.1603447205 0.3042982519 0.0055268761 0.0397080000 720610993 0 402718720 -0.1307435334 0.0475288182 -0.6519993544 2775 1311867262.9479789734 0.3050695062 0.1603968735 0.3050695062 0.0055261869 0.0409330000 720614305 0 402718720 -0.1304923594 0.0469634794 -0.6538694501 2776 1311867262.9799671173 0.3063818812 0.1604494618 0.3063818812 0.0055318162 0.0409750000 720617393 0 402718720 -0.1308222711 0.0475184843 -0.6557587385 2777 1311867263.0122909546 0.3071478903 0.1605022880 0.3071478903 0.0055367677 0.0400050000 720620593 0 402718720 -0.1310968548 0.0470182002 -0.6575917006 2778 1311867263.0480000973 0.3081066608 0.1605554213 0.3081066608 0.0055359523 0.0411950000 720623849 0 402718720 -0.1313790828 0.0466627181 -0.6599327922 2779 1311867263.0799300671 0.3087554574 0.1606087499 0.3087554574 0.0055351089 0.0418280000 720626993 0 402718720 -0.1315375715 0.0480560362 -0.6624587178 2780 1311867263.1119680405 0.3097813427 0.1606624091 0.3097813427 0.0055349117 0.0397660000 720630081 0 402718720 -0.1322575212 0.0490449034 -0.6645277143 2781 1311867263.1480429173 0.3097388744 0.1607160144 0.3097813427 0.0055412542 0.0412590000 720633393 0 402718720 -0.1311466992 0.0501472019 -0.6663842201 2782 1311867263.1800260544 0.3113394082 0.1607701566 0.3113394082 0.0055405863 0.0422410000 720636481 0 402718720 -0.1332485974 0.0516586602 -0.6684780717 2783 1311867263.2120881081 0.3123587370 0.1608246260 0.3123587370 0.0055399543 0.0422720000 720639681 0 402718720 -0.1343671829 0.0542871021 -0.6705936193 2784 1311867263.2480340004 0.3114990592 0.1608787476 0.3123587370 0.0055392278 0.0443440000 720642937 0 402718720 -0.1327154487 0.0544346869 -0.6723452806 2785 1311867263.2800021172 0.3125688434 0.1609332144 0.3125688434 0.0055385881 0.0447480000 720646025 0 402718720 -0.1334836781 0.0542918965 -0.6735571027 2786 1311867263.3120939732 0.3127026260 0.1609876902 0.3127026260 0.0055581177 0.0444980000 720649225 0 402718720 -0.1334824115 0.0550756119 -0.6758106947 2787 1311867263.3481199741 0.3130763471 0.1610422609 0.3130763471 0.0055573968 0.0451480000 720652481 0 402718720 -0.1330319345 0.0553837419 -0.6772632599 2788 1311867263.3800389767 0.3142477870 0.1610972127 0.3142477870 0.0055565055 0.0455820000 720655569 0 402718720 -0.1341363937 0.0537928008 -0.6782842875 2789 1311867263.4123749733 0.3143980205 0.1611521789 0.3143980205 0.0055556754 0.0444940000 720658769 0 402718720 -0.1339184046 0.0545753315 -0.6807271242 2790 1311867263.4481530190 0.3152155876 0.1612073988 0.3152155876 0.0055549973 0.0452000000 720662025 0 402718720 -0.1328295469 0.0561244301 -0.6828071475 2791 1311867263.4800179005 0.3161883950 0.1612629276 0.3161883950 0.0055540690 0.0452670000 720665057 0 402718720 -0.1332473606 0.0551513247 -0.6846475601 2792 1311867263.5119929314 0.3163729608 0.1613184828 0.3163729608 0.0055571586 0.0449650000 720668257 0 402718720 -0.1332615167 0.0563876852 -0.6876603961 2793 1311867263.5479769707 0.3169090748 0.1613741901 0.3169090748 0.0055568391 0.0438930000 720671513 0 402718720 -0.1312977523 0.0571276844 -0.6898527741 2794 1311867263.5800590515 0.3177286088 0.1614301509 0.3177286088 0.0055565469 0.0459220000 720674601 0 402718720 -0.1301835924 0.0567977615 -0.6917276382 2795 1311867263.6122050285 0.3190509081 0.1614865447 0.3190509081 0.0055610827 0.0415600000 720677801 0 402718720 -0.1302932799 0.0572944954 -0.6943873167 2796 1311867263.6480209827 0.3193809688 0.1615430163 0.3193809688 0.0055621433 0.0425740000 720681057 0 402718720 -0.1283957809 0.0579541773 -0.6971104145 2797 1311867263.6799559593 0.3198885918 0.1615996289 0.3198885918 0.0055624983 0.0443300000 720684145 0 402718720 -0.1273729503 0.0575012714 -0.6991913319 2798 1311867263.7122209072 0.3209606707 0.1616565843 0.3209606707 0.0055627274 0.0432550000 720687345 0 402718720 -0.1266697645 0.0588214099 -0.7020263076 2799 1311867263.7481000423 0.3221507370 0.1617139241 0.3221507370 0.0055628375 0.0426780000 720690601 0 402718720 -0.1260978431 0.0599282458 -0.7049461603 2800 1311867263.7803180218 0.3230691850 0.1617715510 0.3230691850 0.0055627929 0.0466220000 720693745 0 402718720 -0.1255945414 0.0605522171 -0.7079320550 2801 1311867263.8123180866 0.3232603371 0.1618292049 0.3232603371 0.0055625537 0.0541000000 720696833 0 402718720 -0.1240399182 0.0610438026 -0.7101532221 2802 1311867263.8481190205 0.3242555559 0.1618871729 0.3242555559 0.0055623924 0.0550240000 720700089 0 402718720 -0.1223131493 0.0614557266 -0.7126022577 2803 1311867263.8801500797 0.3251192570 0.1619454077 0.3251192570 0.0055618652 0.0549710000 720703177 0 402718720 -0.1217120811 0.0608460307 -0.7145491838 2804 1311867263.9123339653 0.3252446949 0.1620036457 0.3252446949 0.0055613360 0.0562000000 720706377 0 402718720 -0.1206547022 0.0619286411 -0.7182165384 2805 1311867263.9482059479 0.3261431456 0.1620621624 0.3261431456 0.0055609287 0.0574200000 720709633 0 402718720 -0.1190632358 0.0642818213 -0.7205021381 2806 1311867263.9799990654 0.3271038830 0.1621209799 0.3271038830 0.0055602548 0.0576240000 720712777 0 402718720 -0.1189795062 0.0638828278 -0.7223480344 2807 1311867264.0122311115 0.3275847435 0.1621799267 0.3275847435 0.0055593685 0.0542990000 720715921 0 402718720 -0.1187377051 0.0637775436 -0.7243897915 2808 1311867264.0481269360 0.3281272650 0.1622390248 0.3281272650 0.0055596818 0.0573630000 720719121 0 402718720 -0.1171847880 0.0657545924 -0.7270939350 2809 1311867264.0802099705 0.3281846046 0.1622981012 0.3281846046 0.0055588021 0.0525340000 720722265 0 402718720 -0.1159886196 0.0663281605 -0.7292144895 2810 1311867264.1122820377 0.3290481865 0.1623574428 0.3290481865 0.0055578879 0.0566340000 720725409 0 402718720 -0.1162590757 0.0650788695 -0.7304925919 2811 1311867264.1479830742 0.3299831152 0.1624170749 0.3299831152 0.0055581494 0.0559510000 720728721 0 402718720 -0.1162951887 0.0674331859 -0.7329289913 2812 1311867264.1801450253 0.3302106261 0.1624767454 0.3302106261 0.0055574871 0.0533440000 720731809 0 402718720 -0.1148733497 0.0687334836 -0.7349184155 2813 1311867264.2121090889 0.3308586180 0.1625366039 0.3308586180 0.0055571996 0.0530070000 720734953 0 402718720 -0.1146297306 0.0673872530 -0.7363376021 2814 1311867264.2480239868 0.3314312398 0.1625966233 0.3314312398 0.0055671185 0.0574070000 720738209 0 402718720 -0.1146007106 0.0677202195 -0.7384507656 2815 1311867264.2801690102 0.3316672146 0.1626566839 0.3316672146 0.0055663248 0.0577760000 720741297 0 402718720 -0.1137461886 0.0694159716 -0.7409134507 2816 1311867264.3120059967 0.3321296871 0.1627168661 0.3321296871 0.0055682660 0.0570340000 720744497 0 402718720 -0.1130154207 0.0690790191 -0.7423905730 2817 1311867264.3481919765 0.3336808681 0.1627775562 0.3336808681 0.0055675049 0.0512720000 720747753 0 402718720 -0.1139800996 0.0686721131 -0.7442172170 2818 1311867264.3802409172 0.3339691460 0.1628383055 0.3339691460 0.0055673640 0.0474440000 720750841 0 402718720 -0.1132131889 0.0713301003 -0.7466945648 2819 1311867264.4122140408 0.3345514834 0.1628992183 0.3345514834 0.0055667074 0.0468710000 720754041 0 402718720 -0.1135125905 0.0711058006 -0.7479748130 2820 1311867264.4480040073 0.3354043961 0.1629603903 0.3354043961 0.0055671428 0.0449810000 720757297 0 402718720 -0.1142566130 0.0718971118 -0.7498258948 2821 1311867264.4800739288 0.3351614475 0.1630214329 0.3354043961 0.0055672657 0.0478160000 720760385 0 402718720 -0.1131844670 0.0739027932 -0.7517257929 2822 1311867264.5122270584 0.3356257379 0.1630825967 0.3356257379 0.0055665402 0.0465290000 720763585 0 402718720 -0.1136018038 0.0729187429 -0.7527097464 2823 1311867264.5481550694 0.3363808393 0.1631439847 0.3363808393 0.0055667364 0.0467210000 720766841 0 402718720 -0.1133697480 0.0742331520 -0.7544330359 2824 1311867264.5800919533 0.3358977735 0.1632051581 0.3363808393 0.0055658906 0.0477800000 720769985 0 402718720 -0.1125831679 0.0749434754 -0.7564480901 2825 1311867264.6123299599 0.3363473415 0.1632664474 0.3363808393 0.0055650661 0.0473940000 720773129 0 402718720 -0.1123833358 0.0748593807 -0.7576690316 2826 1311867264.6480920315 0.3375344574 0.1633281134 0.3375344574 0.0055645849 0.0468290000 720776329 0 402718720 -0.1131304130 0.0747955814 -0.7591187358 2827 1311867264.6801989079 0.3372719288 0.1633896428 0.3375344574 0.0055660488 0.0476620000 720779473 0 402718720 -0.1121340394 0.0758801252 -0.7609763145 2828 1311867264.7124540806 0.3370221853 0.1634510405 0.3375344574 0.0055651119 0.0467770000 720782673 0 402718720 -0.1114926860 0.0754692107 -0.7619572878 2829 1311867264.7479650974 0.3379043043 0.1635127065 0.3379043043 0.0055642480 0.0425590000 720785929 0 402718720 -0.1120494679 0.0750516653 -0.7633043528 2830 1311867264.7801249027 0.3386242390 0.1635745834 0.3386242390 0.0055642602 0.0475790000 720789073 0 402718720 -0.1120551452 0.0771382079 -0.7652262449 2831 1311867264.8121149540 0.3376348019 0.1636360670 0.3386242390 0.0055636173 0.0473930000 720792161 0 402718720 -0.1106186584 0.0772824138 -0.7665529847 2832 1311867264.8481891155 0.3380594850 0.1636976572 0.3386242390 0.0055627474 0.0455630000 720795473 0 402718720 -0.1105511859 0.0769845545 -0.7672702074 2833 1311867264.8801410198 0.3387747109 0.1637594564 0.3387747109 0.0055618781 0.0439690000 720798505 0 402718720 -0.1108976677 0.0767765567 -0.7679518461 2834 1311867264.9122300148 0.3384348154 0.1638210920 0.3387747109 0.0055610034 0.0435940000 720801705 0 402718720 -0.1100970209 0.0774836838 -0.7690561414 2835 1311867264.9481859207 0.3383461833 0.1638826529 0.3387747109 0.0055600582 0.0440800000 720804961 0 402718720 -0.1090469062 0.0768692195 -0.7696163654 2836 1311867264.9804329872 0.3393273950 0.1639445164 0.3393273950 0.0055593154 0.0477970000 720808105 0 402718720 -0.1091941670 0.0772997364 -0.7702081203 2837 1311867265.0121920109 0.3394161165 0.1640063675 0.3394161165 0.0055585319 0.0417720000 720811249 0 402718720 -0.1088703945 0.0779656246 -0.7711773515 2838 1311867265.0481278896 0.3391863406 0.1640680940 0.3394161165 0.0055575673 0.0454110000 720814505 0 402718720 -0.1079448909 0.0779288486 -0.7721099854 2839 1311867265.0802099705 0.3400218487 0.1641300714 0.3400218487 0.0055568819 0.0440100000 720817593 0 402718720 -0.1083226800 0.0781180188 -0.7727438807 2840 1311867265.1121640205 0.3407908678 0.1641922759 0.3407908678 0.0055568938 0.0434130000 720820737 0 402718720 -0.1084234640 0.0783397928 -0.7734864950 2841 1311867265.1481039524 0.3407866061 0.1642544351 0.3407908678 0.0055561067 0.0435730000 720823937 0 402718720 -0.1075521111 0.0784842595 -0.7744765878 2842 1311867265.1803030968 0.3405818939 0.1643164786 0.3407908678 0.0055568022 0.0475250000 720827025 0 402718720 -0.1071148738 0.0788984224 -0.7756702304 2843 1311867265.2123000622 0.3409357965 0.1643786028 0.3409357965 0.0055560232 0.0472930000 720830225 0 402718720 -0.1065882668 0.0787773281 -0.7765049934 2844 1311867265.2482140064 0.3411728442 0.1644407668 0.3411728442 0.0055553508 0.0456660000 720833481 0 402718720 -0.1067838222 0.0778286159 -0.7782942653 2845 1311867265.2803180218 0.3425865769 0.1645033839 0.3425865769 0.0055557361 0.0472110000 720836569 0 402718720 -0.1072591245 0.0786025673 -0.7797887325 2846 1311867265.3123099804 0.3420706391 0.1645657758 0.3425865769 0.0055548836 0.0490280000 720839713 0 402718720 -0.1061256677 0.0780202076 -0.7811609507 2847 1311867265.3482000828 0.3425802886 0.1646283028 0.3425865769 0.0055542857 0.0460480000 720842969 0 402718720 -0.1062550098 0.0778664649 -0.7833947539 2848 1311867265.3801329136 0.3440244794 0.1646912931 0.3440244794 0.0055535413 0.0474070000 720846057 0 402718720 -0.1073163748 0.0797481984 -0.7848344445 2849 1311867265.4122068882 0.3450196087 0.1647545884 0.3450196087 0.0055553159 0.0438560000 720849257 0 402718720 -0.1078047529 0.0796172246 -0.7857109904 2850 1311867265.4481799603 0.3457174003 0.1648180841 0.3457174003 0.0055546377 0.0473630000 720852513 0 402718720 -0.1081844345 0.0788620487 -0.7873426080 2851 1311867265.4802310467 0.3457996249 0.1648815641 0.3457996249 0.0055536995 0.0459660000 720855601 0 402718720 -0.1076439694 0.0809562802 -0.7892921567 2852 1311867265.5122768879 0.3461610973 0.1649451264 0.3461610973 0.0055530340 0.0442750000 720858801 0 402718720 -0.1077521145 0.0816277638 -0.7907875180 2853 1311867265.5483779907 0.3467806578 0.1650088612 0.3467806578 0.0055521117 0.0460840000 720862113 0 402718720 -0.1078593507 0.0807952285 -0.7917164564 2854 1311867265.5802230835 0.3474545479 0.1650727875 0.3474545479 0.0055515809 0.0484060000 720865145 0 402718720 -0.1078061238 0.0807589889 -0.7927058935 2855 1311867265.6120650768 0.3476945758 0.1651367531 0.3476945758 0.0055506318 0.0478170000 720868345 0 402718720 -0.1073709130 0.0810308009 -0.7939404845 2856 1311867265.6482849121 0.3483327627 0.1652008974 0.3483327627 0.0055498463 0.0478250000 720871601 0 402718720 -0.1076634452 0.0820550621 -0.7960466743 2857 1311867265.6803050041 0.3483110368 0.1652649891 0.3483327627 0.0055492989 0.0478010000 720874633 0 402718720 -0.1065463647 0.0830755532 -0.7973818183 2858 1311867265.7121660709 0.3494611084 0.1653294385 0.3494611084 0.0055485563 0.0459570000 720877833 0 402718720 -0.1082118526 0.0830522627 -0.7982774973 2859 1311867265.7482249737 0.3488077521 0.1653936141 0.3494611084 0.0055478203 0.0427260000 720881089 0 402718720 -0.1075177938 0.0855216309 -0.8005238175 2860 1311867265.7806940079 0.3487558961 0.1654577268 0.3494611084 0.0055471076 0.0480450000 720884177 0 402718720 -0.1068670675 0.0869720131 -0.8012709022 2861 1311867265.8122780323 0.3487359881 0.1655217877 0.3494611084 0.0055462101 0.0481620000 720887377 0 402718720 -0.1074011996 0.0860610753 -0.8018490672 2862 1311867265.8481869698 0.3493360579 0.1655860136 0.3494611084 0.0055453486 0.0468470000 720890633 0 402718720 -0.1080751866 0.0870446488 -0.8026469946 2863 1311867265.8801929951 0.3498146236 0.1656503617 0.3498146236 0.0055443925 0.0479140000 720893721 0 402718720 -0.1076265797 0.0882855952 -0.8027660251 2864 1311867265.9123260975 0.3485499918 0.1657142233 0.3498146236 0.0055460119 0.0444320000 720896921 0 402718720 -0.1069961935 0.0868926048 -0.8034645319 2865 1311867265.9482591152 0.3507174551 0.1657787968 0.3507174551 0.0055477499 0.0460900000 720900177 0 402718720 -0.1078265682 0.0864402950 -0.8034334779 2866 1311867265.9805989265 0.3508488834 0.1658433712 0.3508488834 0.0055470023 0.0444170000 720903265 0 402718720 -0.1078904644 0.0877677277 -0.8053904176 2867 1311867266.0121800900 0.3507824838 0.1659078773 0.3508488834 0.0055460520 0.0427220000 720906409 0 402718720 -0.1075419933 0.0879853368 -0.8065310717 2868 1311867266.0483620167 0.3511784673 0.1659724765 0.3511784673 0.0055452068 0.0445690000 720909721 0 402718720 -0.1077404171 0.0878034383 -0.8074801564 2869 1311867266.0804510117 0.3518479764 0.1660372641 0.3518479764 0.0055448581 0.0462890000 720912809 0 402718720 -0.1082446575 0.0881909132 -0.8087631464 2870 1311867266.1122388840 0.3519552648 0.1661020439 0.3519552648 0.0055440033 0.0481300000 720915953 0 402718720 -0.1082703695 0.0883054361 -0.8096328378 2871 1311867266.1484639645 0.3515149355 0.1661666252 0.3519552648 0.0055435372 0.0462830000 720919265 0 402718720 -0.1074128821 0.0891035125 -0.8109533787 2872 1311867266.1802821159 0.3521470726 0.1662313816 0.3521470726 0.0055426999 0.0463930000 720922297 0 402718720 -0.1080340296 0.0892412961 -0.8117382526 2873 1311867266.2121810913 0.3527649045 0.1662963080 0.3527649045 0.0055418774 0.0460500000 720925497 0 402718720 -0.1091414765 0.0898228511 -0.8127879500 2874 1311867266.2482049465 0.3527700603 0.1663611910 0.3527700603 0.0055410253 0.0462460000 720928753 0 402718720 -0.1086962819 0.0898819789 -0.8135593534 2875 1311867266.2802269459 0.3533272743 0.1664262227 0.3533272743 0.0055401362 0.0485970000 720931841 0 402718720 -0.1090433151 0.0900332630 -0.8141713142 2876 1311867266.3123109341 0.3538140953 0.1664913784 0.3538140953 0.0055392104 0.0477330000 720934929 0 402718720 -0.1101629436 0.0900338218 -0.8152586818 2877 1311867266.3481750488 0.3538796008 0.1665565116 0.3538796008 0.0055386223 0.0436410000 720938241 0 402718720 -0.1102343649 0.0908546969 -0.8167361617 2878 1311867266.3803789616 0.3544879258 0.1666218109 0.3544879258 0.0055377035 0.0474190000 720941329 0 402718720 -0.1104516611 0.0905963704 -0.8174111247 2879 1311867266.4123229980 0.3547841907 0.1666871678 0.3547841907 0.0055368447 0.0459740000 720944529 0 402718720 -0.1114672199 0.0892091468 -0.8183569908 2880 1311867266.4484019279 0.3554096222 0.1667526964 0.3554096222 0.0055364850 0.0458990000 720947785 0 402718720 -0.1122273281 0.0904240012 -0.8197098970 2881 1311867266.4804720879 0.3553708494 0.1668181661 0.3554096222 0.0055367391 0.0484470000 720950873 0 402718720 -0.1110503823 0.0907559171 -0.8207089305 2882 1311867266.5125229359 0.3555543423 0.1668836540 0.3555543423 0.0055366141 0.0457140000 720954073 0 402718720 -0.1122416705 0.0886754617 -0.8214544058 2883 1311867266.5482330322 0.3559179008 0.1669492226 0.3559179008 0.0055367773 0.5915970000 733309925 0 402718720 -0.1126613542 0.0891417637 -0.8229905963 2884 1311867266.5803749561 0.3566962183 0.1670150156 0.3566962183 0.0055361329 0.0270370000 736972221 0 402718720 -0.1131529659 0.0870142579 -0.8226204515 2885 1311867266.6122500896 0.3574305475 0.1670810175 0.3574305475 0.0055360400 0.0284540000 740167613 0 402718720 -0.1137537658 0.0859923884 -0.8230489492 2886 1311867266.6482610703 0.3578675687 0.1671471251 0.3578675687 0.0055352814 0.0279260000 740170869 0 402718720 -0.1141172945 0.0875276253 -0.8242188692 2887 1311867266.6803109646 0.3579416573 0.1672132126 0.3579416573 0.0055343997 0.0297160000 740173957 0 402718720 -0.1132611856 0.0888047442 -0.8243891597 2888 1311867266.7121450901 0.3590448499 0.1672796363 0.3590448499 0.0055338690 0.0289240000 740177157 0 402718720 -0.1149283871 0.0860485435 -0.8238522410 2889 1311867266.7484281063 0.3585024476 0.1673458262 0.3590448499 0.0055335584 0.0287650000 740180469 0 402718720 -0.1149998382 0.0866898894 -0.8253603578 2890 1311867266.7803199291 0.3580736220 0.1674118220 0.3590448499 0.0055326772 0.0288420000 740183501 0 402718720 -0.1142056435 0.0878638253 -0.8259557486 2891 1311867266.8122820854 0.3586241603 0.1674779626 0.3590448499 0.0055317989 0.0287350000 740186701 0 402718720 -0.1148193032 0.0865360871 -0.8252657056 2892 1311867266.8481600285 0.3585442305 0.1675440297 0.3590448499 0.0055309522 0.0287490000 740189957 0 402718720 -0.1149252132 0.0866304561 -0.8253438473 2893 1311867266.8803179264 0.3578952253 0.1676098269 0.3590448499 0.0055300171 0.0275540000 740193101 0 402718720 -0.1140802875 0.0886887014 -0.8256142139 2894 1311867266.9121789932 0.3576823473 0.1676755050 0.3590448499 0.0055300140 0.0277250000 740196245 0 402718720 -0.1149313897 0.0877751037 -0.8247375488 2895 1311867266.9481709003 0.3578181863 0.1677411847 0.3590448499 0.0055296295 0.0287170000 740199501 0 402718720 -0.1149277613 0.0893400759 -0.8240962029 2896 1311867266.9803628922 0.3581016064 0.1678069169 0.3590448499 0.0055294312 0.0295540000 740202589 0 402718720 -0.1151381955 0.0908613354 -0.8228831887 2897 1311867267.0123710632 0.3571543992 0.1678722768 0.3590448499 0.0055287650 0.0316660000 740205789 0 402718720 -0.1156416833 0.0903002396 -0.8226751685 2898 1311867267.0483429432 0.3563719392 0.1679373215 0.3590448499 0.0055279445 0.0268620000 740209045 0 402718720 -0.1147848442 0.0897894055 -0.8209365010 2899 1311867267.0802459717 0.3565307856 0.1680023762 0.3590448499 0.0055275735 0.0272960000 740211853 0 402718720 -0.1166759431 0.0861561000 -0.8193516135 2900 1311867267.1123509407 0.3569092155 0.1680675165 0.3590448499 0.0055268048 0.0301930000 740215053 0 402718720 -0.1180995405 0.0861927047 -0.8191746473 2901 1311867267.1482639313 0.3561233878 0.1681323410 0.3590448499 0.0055262831 0.0291910000 740218309 0 402718720 -0.1173470765 0.0864540115 -0.8183724284 2902 1311867267.1802310944 0.3555415273 0.1681969203 0.3590448499 0.0055254514 0.0360050000 740221453 0 402718720 -0.1176728010 0.0835026726 -0.8174780011 2903 1311867267.2123370171 0.3553633392 0.1682613937 0.3590448499 0.0055246374 0.0317100000 740224597 0 402718720 -0.1177131683 0.0847971216 -0.8174991608 2904 1311867267.2482130527 0.3551252484 0.1683257408 0.3590448499 0.0055237747 0.0318250000 740227853 0 402718720 -0.1169301569 0.0864475295 -0.8167383671 2905 1311867267.2804589272 0.3547947109 0.1683899298 0.3590448499 0.0055231117 0.0331670000 740230997 0 402718720 -0.1171794236 0.0840876922 -0.8154432774 2906 1311867267.3122189045 0.3546659946 0.1684540303 0.3590448499 0.0055222507 0.0336830000 740234085 0 402718720 -0.1179415658 0.0826440826 -0.8147955537 2907 1311867267.3483910561 0.3551681340 0.1685182594 0.3590448499 0.0055213943 0.0364220000 740237341 0 402718720 -0.1185358092 0.0841060281 -0.8139590621 2908 1311867267.3804419041 0.3534798920 0.1685818638 0.3590448499 0.0055205750 0.0326200000 740240429 0 402718720 -0.1170605868 0.0844006464 -0.8141968846 2909 1311867267.4122920036 0.3534272015 0.1686454064 0.3590448499 0.0055197850 0.0339220000 740243629 0 402718720 -0.1174950525 0.0821350217 -0.8130088449 2910 1311867267.4481840134 0.3532482684 0.1687088438 0.3590448499 0.0055189271 0.0348760000 740246885 0 402718720 -0.1178278029 0.0816220120 -0.8125281930 2911 1311867267.4802930355 0.3538571298 0.1687724468 0.3590448499 0.0055180813 0.0374080000 740250029 0 402718720 -0.1189006418 0.0815296099 -0.8116580844 2912 1311867267.5123279095 0.3535254896 0.1688358922 0.3590448499 0.0055172931 0.0321390000 740253173 0 402718720 -0.1176418960 0.0834680125 -0.8109918833 2913 1311867267.5482549667 0.3525872231 0.1688989719 0.3590448499 0.0055221409 0.0325600000 740256429 0 402718720 -0.1162266955 0.0819669962 -0.8100541830 2914 1311867267.5802910328 0.3532404006 0.1689622326 0.3590448499 0.0055213025 0.0365070000 740259517 0 402718720 -0.1186178774 0.0804777071 -0.8091073632 2915 1311867267.6123609543 0.3537077308 0.1690256101 0.3590448499 0.0055226272 0.0385400000 740262661 0 402718720 -0.1191410646 0.0831698775 -0.8076866269 2916 1311867267.6484379768 0.3520370424 0.1690883712 0.3590448499 0.0055220767 0.0355480000 740265973 0 402718720 -0.1181458086 0.0802555978 -0.8062747717 2917 1311867267.6803209782 0.3519302607 0.1691510527 0.3590448499 0.0055218136 0.0362320000 740269061 0 402718720 -0.1188248843 0.0786483213 -0.8053686023 2918 1311867267.7125399113 0.3531720340 0.1692141168 0.3590448499 0.0055209623 0.0350240000 740272261 0 402718720 -0.1196696013 0.0813295990 -0.8038217425 2919 1311867267.7483849525 0.3518878818 0.1692766977 0.3590448499 0.0055215200 0.0380850000 740275461 0 402718720 -0.1204159036 0.0781195089 -0.8020052910 2920 1311867267.7803909779 0.3517057598 0.1693391734 0.3590448499 0.0055216713 0.0369130000 740278605 0 402718720 -0.1207928881 0.0768029764 -0.8009265065 2921 1311867267.8127250671 0.3519355953 0.1694016850 0.3590448499 0.0055208267 0.0358740000 740281805 0 402718720 -0.1205834299 0.0794461891 -0.7997387648 2922 1311867267.8483679295 0.3509617448 0.1694638206 0.3590448499 0.0055199066 0.0364060000 740285061 0 402718720 -0.1201983616 0.0799001753 -0.7986733317 2923 1311867267.8835940361 0.3496894836 0.1695254783 0.3590448499 0.0055192562 0.0382840000 740288261 0 402718720 -0.1210478619 0.0767690316 -0.7973073721 2924 1311867267.9127359390 0.3499117494 0.1695871700 0.3590448499 0.0055196775 0.0374070000 740291349 0 402718720 -0.1219932437 0.0759406611 -0.7955182791 2925 1311867267.9484510422 0.3497510254 0.1696487644 0.3590448499 0.0055189752 0.0362170000 740294605 0 402718720 -0.1215499490 0.0778066441 -0.7942164540 2926 1311867267.9803159237 0.3489205837 0.1697100330 0.3590448499 0.0055182386 0.0364160000 740297693 0 402718720 -0.1214054525 0.0759958401 -0.7926403880 2927 1311867268.0123000145 0.3482506871 0.1697710308 0.3590448499 0.0055173689 0.0385020000 740300837 0 402718720 -0.1216594726 0.0735156909 -0.7912994027 2928 1311867268.0484049320 0.3479516208 0.1698318849 0.3590448499 0.0055165620 0.0354020000 740304149 0 402718720 -0.1217290610 0.0753166303 -0.7903985977 2929 1311867268.0803129673 0.3473418951 0.1698924892 0.3590448499 0.0055192391 0.0379350000 740307237 0 402718720 -0.1217994988 0.0747390985 -0.7885103822 2930 1311867268.1124460697 0.3459662795 0.1699525826 0.3590448499 0.0055219517 0.0380650000 740310381 0 402718720 -0.1210186183 0.0724268332 -0.7868357897 2931 1311867268.1485071182 0.3457642794 0.1700125661 0.3590448499 0.0055212577 0.0357520000 740313637 0 402718720 -0.1217250004 0.0728154108 -0.7855629921 2932 1311867268.1805090904 0.3455754519 0.1700724443 0.3590448499 0.0055209339 0.0365660000 740316725 0 402718720 -0.1219123453 0.0739402473 -0.7837539315 2933 1311867268.2124528885 0.3453688025 0.1701322112 0.3590448499 0.0055208222 0.0344160000 740319925 0 402718720 -0.1221216545 0.0725348815 -0.7811002135 2934 1311867268.2483050823 0.3443834782 0.1701916016 0.3590448499 0.0055208361 0.0372690000 740323181 0 402718720 -0.1232155785 0.0703743026 -0.7793952823 2935 1311867268.2804999352 0.3437931240 0.1702507503 0.3590448499 0.0055200372 0.0371970000 740326269 0 402718720 -0.1238916293 0.0709829032 -0.7782818079 2936 1311867268.3125100136 0.3446128666 0.1703101380 0.3590448499 0.0055195770 0.0344510000 740329469 0 402718720 -0.1249301136 0.0689605623 -0.7749735117 2937 1311867268.3482699394 0.3437339664 0.1703691859 0.3590448499 0.0055198924 0.0349630000 740332725 0 402718720 -0.1250988394 0.0675593391 -0.7725933194 2938 1311867268.3804929256 0.3425180316 0.1704277798 0.3590448499 0.0055192397 0.0340330000 740335813 0 402718720 -0.1252417117 0.0688493252 -0.7722414136 2939 1311867268.4123690128 0.3425203264 0.1704863346 0.3590448499 0.0055186060 0.0345630000 740339013 0 402718720 -0.1265159994 0.0672690496 -0.7696018219 2940 1311867268.4486060143 0.3416710198 0.1705445607 0.3590448499 0.0055187853 0.0350810000 740342325 0 402718720 -0.1276022941 0.0667094812 -0.7682114244 2941 1311867268.4808580875 0.3411918581 0.1706025842 0.3590448499 0.0055178822 0.0347530000 740345413 0 402718720 -0.1274341792 0.0669218898 -0.7655363679 2942 1311867268.5125229359 0.3401211202 0.1706602044 0.3590448499 0.0055172073 0.0375880000 740348557 0 402718720 -0.1276973337 0.0649809912 -0.7636309266 2943 1311867268.5485060215 0.3390558958 0.1707174235 0.3590448499 0.0055178733 0.0362650000 740351813 0 402718720 -0.1289311796 0.0641416386 -0.7620074153 2944 1311867268.5804939270 0.3390151262 0.1707745898 0.3590448499 0.0055175822 0.0382540000 740354901 0 402718720 -0.1293306798 0.0647858754 -0.7598243356 2945 1311867268.6165308952 0.3386292160 0.1708315863 0.3590448499 0.0055167282 0.0335220000 740358213 0 402718720 -0.1302694082 0.0632017776 -0.7574511170 2946 1311867268.6483459473 0.3378214240 0.1708882699 0.3590448499 0.0055160453 0.0363470000 740361357 0 402718720 -0.1313255131 0.0626181662 -0.7559119463 2947 1311867268.6804459095 0.3373540640 0.1709447564 0.3590448499 0.0055152371 0.0383500000 740364445 0 402718720 -0.1323539317 0.0625302047 -0.7541738153 2948 1311867268.7164340019 0.3360320926 0.1710007562 0.3590448499 0.0055156403 0.0449490000 740367757 0 402718720 -0.1324239820 0.0606335811 -0.7521021962 2949 1311867268.7484660149 0.3361433446 0.1710567557 0.3590448499 0.0055174053 0.0411700000 740370957 0 402718720 -0.1332259923 0.0598779358 -0.7499203682 2950 1311867268.7805809975 0.3349366784 0.1711123082 0.3590448499 0.0055175267 0.0454420000 740374045 0 402718720 -0.1336063743 0.0606142171 -0.7485361695 2951 1311867268.8165960312 0.3348577023 0.1711677963 0.3590448499 0.0055169542 0.0419800000 740377301 0 402718720 -0.1347279251 0.0597309023 -0.7458626628 2952 1311867268.8486289978 0.3341773152 0.1712230163 0.3590448499 0.0055164674 0.0431020000 740380501 0 402718720 -0.1360979825 0.0585548617 -0.7433744073 2953 1311867268.8806419373 0.3329036534 0.1712777677 0.3590448499 0.0055171821 0.0444780000 740383589 0 402718720 -0.1359179616 0.0599476248 -0.7421383262 2954 1311867268.9164569378 0.3334189355 0.1713326563 0.3590448499 0.0055163340 0.0415100000 740386845 0 402718720 -0.1369136870 0.0594883934 -0.7382079959 2955 1311867268.9483659267 0.3319701254 0.1713870176 0.3590448499 0.0055161040 0.0429620000 740389989 0 402718720 -0.1375848949 0.0580107383 -0.7359181046 2956 1311867268.9805290699 0.3313899934 0.1714411458 0.3590448499 0.0055152130 0.0447650000 740393077 0 402718720 -0.1387227774 0.0583357625 -0.7335808277 2957 1311867269.0165810585 0.3306579888 0.1714949898 0.3590448499 0.0055144198 0.0436610000 740396389 0 402718720 -0.1393397003 0.0562709570 -0.7305966616 2958 1311867269.0483250618 0.3294244409 0.1715483804 0.3590448499 0.0055136890 0.0464540000 740399533 0 402718720 -0.1399290860 0.0551916808 -0.7283650041 2959 1311867269.0821349621 0.3288247883 0.1716015323 0.3590448499 0.0055132362 0.0445550000 740402621 0 402718720 -0.1406452060 0.0545733012 -0.7254385352 2960 1311867269.1165359020 0.3279038370 0.1716543372 0.3590448499 0.0055124220 0.0420240000 740405821 0 402718720 -0.1416165978 0.0531584732 -0.7231049538 2961 1311867269.1486270428 0.3272437155 0.1717068834 0.3590448499 0.0055116007 0.0430350000 740408965 0 402718720 -0.1417951882 0.0540711544 -0.7206152678 2962 1311867269.1804630756 0.3266790211 0.1717592035 0.3590448499 0.0055107537 0.0442790000 740412053 0 402718720 -0.1436064988 0.0527209044 -0.7179362774 2963 1311867269.2162868977 0.3258574903 0.1718112110 0.3590448499 0.0055098595 0.0442410000 740415309 0 402718720 -0.1443285495 0.0527487472 -0.7153390646 2964 1311867269.2483179569 0.3250161409 0.1718628996 0.3590448499 0.0055093122 0.0429790000 740418509 0 402718720 -0.1452486813 0.0518016070 -0.7129603028 2965 1311867269.2804639339 0.3245275915 0.1719143885 0.3590448499 0.0055084232 0.0374010000 740421653 0 402718720 -0.1467588246 0.0513757057 -0.7105586529 2966 1311867269.3163731098 0.3228614032 0.1719652810 0.3590448499 0.0055133946 0.0374180000 740424853 0 402718720 -0.1466964185 0.0516146272 -0.7080478072 2967 1311867269.3483450413 0.3219719529 0.1720158393 0.3590448499 0.0055145784 0.0365910000 740428053 0 402718720 -0.1467600465 0.0518920831 -0.7058611512 2968 1311867269.3804309368 0.3222137094 0.1720664451 0.3590448499 0.0055145430 0.0368560000 740431141 0 402718720 -0.1500326693 0.0513699166 -0.7028749585 2969 1311867269.4165520668 0.3216868639 0.1721168393 0.3590448499 0.0055330896 0.0363970000 740434397 0 402718720 -0.1503800303 0.0520344600 -0.7002395391 2970 1311867269.4483139515 0.3191626370 0.1721663497 0.3590448499 0.0055431127 0.0369720000 740437597 0 402718720 -0.1496428996 0.0515138842 -0.6976819038 2971 1311867269.4805910587 0.3193402290 0.1722158865 0.3590448499 0.0055433556 0.0374110000 740440685 0 402718720 -0.1505168825 0.0521683954 -0.6952083111 2972 1311867269.5165209770 0.3188196421 0.1722652148 0.3590448499 0.0055464118 0.0364780000 740443941 0 402718720 -0.1514406949 0.0524079315 -0.6923119426 2973 1311867269.5483479500 0.3170045614 0.1723138994 0.3590448499 0.0055568140 0.0361070000 740447085 0 402718720 -0.1517381519 0.0523424074 -0.6896390915 2974 1311867269.5804939270 0.3162256479 0.1723622894 0.3590448499 0.0055687416 0.0371730000 740450173 0 402718720 -0.1515667439 0.0514954515 -0.6869369149 2975 1311867269.6164290905 0.3161361814 0.1724106167 0.3590448499 0.0055678520 0.0369030000 740453485 0 402718720 -0.1533958018 0.0495599546 -0.6841141582 2976 1311867269.6484489441 0.3157966137 0.1724587975 0.3590448499 0.0055672454 0.0365230000 740456629 0 402718720 -0.1551779360 0.0494883470 -0.6821478009 2977 1311867269.6804831028 0.3153402507 0.1725067926 0.3590448499 0.0055726215 0.0372250000 740459773 0 402718720 -0.1553791910 0.0522972532 -0.6804330945 2978 1311867269.7164878845 0.3140152693 0.1725543106 0.3590448499 0.0055771352 0.0366460000 740463029 0 402718720 -0.1554579884 0.0496207103 -0.6778435707 2979 1311867269.7483329773 0.3140552640 0.1726018101 0.3590448499 0.0055784367 0.0366380000 740466173 0 402718720 -0.1577599645 0.0479998849 -0.6757858396 2980 1311867269.7803659439 0.3134425282 0.1726490720 0.3590448499 0.0055783513 0.0371870000 740469261 0 402718720 -0.1581115723 0.0482888669 -0.6741542220 2981 1311867269.8164548874 0.3128004074 0.1726960869 0.3590448499 0.0055831372 0.0369280000 740472573 0 402718720 -0.1580262184 0.0486626364 -0.6726079583 2982 1311867269.8484890461 0.3119357228 0.1727427803 0.3590448499 0.0055951291 0.0367650000 740475661 0 402718720 -0.1592286527 0.0464266241 -0.6704713106 2983 1311867269.8803648949 0.3114478886 0.1727892788 0.3590448499 0.0055944754 0.0375100000 740478805 0 402718720 -0.1596993208 0.0456052534 -0.6689466238 2984 1311867269.9165019989 0.3102484047 0.1728353442 0.3590448499 0.0055936673 0.0378440000 740482005 0 402718720 -0.1589272767 0.0458864532 -0.6677215099 2985 1311867269.9484469891 0.3102278709 0.1728813719 0.3590448499 0.0055932331 0.0374600000 740485205 0 402718720 -0.1600867063 0.0445884019 -0.6659722328 2986 1311867269.9807910919 0.3101320565 0.1729273366 0.3590448499 0.0055979344 0.0378050000 740488293 0 402718720 -0.1607077420 0.0439044423 -0.6643934846 2987 1311867270.0166060925 0.3092532158 0.1729729763 0.3590448499 0.0055976128 0.0376330000 740491549 0 402718720 -0.1599244624 0.0434022285 -0.6626279950 2988 1311867270.0484490395 0.3083486557 0.1730182828 0.3590448499 0.0055969150 0.0373380000 740494693 0 402718720 -0.1599790901 0.0421595462 -0.6612207890 2989 1311867270.0806090832 0.3080114126 0.1730634461 0.3590448499 0.0055961402 0.0376750000 740497837 0 402718720 -0.1599190533 0.0426389799 -0.6595270038 2990 1311867270.1166450977 0.3076066077 0.1731084438 0.3590448499 0.0055954304 0.0385490000 740501093 0 402718720 -0.1597848833 0.0423888154 -0.6574166417 2991 1311867270.1486420631 0.3074363470 0.1731533545 0.3590448499 0.0055948638 0.0368150000 740504237 0 402718720 -0.1604542583 0.0414959788 -0.6551706791 2992 1311867270.1805279255 0.3073236048 0.1731981975 0.3590448499 0.0055946832 0.0373240000 740507381 0 402718720 -0.1608692855 0.0413349271 -0.6529633999 2993 1311867270.2164371014 0.3067227602 0.1732428098 0.3590448499 0.0055939990 0.0371750000 740510581 0 402718720 -0.1611404419 0.0404225811 -0.6506828070 2994 1311867270.2483930588 0.3063522875 0.1732872685 0.3590448499 0.0055940505 0.0373950000 740513781 0 402718720 -0.1614414155 0.0390228406 -0.6482916474 2995 1311867270.2805550098 0.3062249720 0.1733316551 0.3590448499 0.0055953952 0.0379200000 740516869 0 402718720 -0.1621220261 0.0366646387 -0.6460102797 2996 1311867270.3166580200 0.3049553037 0.1733755882 0.3590448499 0.0055987482 0.0372820000 740520181 0 402718720 -0.1611381918 0.0380215682 -0.6442971826 2997 1311867270.3483610153 0.3035780191 0.1734190324 0.3590448499 0.0055990050 0.0390610000 740523325 0 402718720 -0.1598571241 0.0362783745 -0.6415638328 2998 1311867270.3805909157 0.3035198152 0.1734624283 0.3590448499 0.0055984181 0.0388490000 740526469 0 402718720 -0.1618068069 0.0336187556 -0.6394169331 2999 1311867270.4164109230 0.3041442335 0.1735060034 0.3590448499 0.0055994360 0.0386390000 740529725 0 402718720 -0.1620507389 0.0361807719 -0.6371165514 3000 1311867270.4483699799 0.3032508194 0.1735492517 0.3590448499 0.0056019211 0.0374930000 740532869 0 402718720 -0.1615896821 0.0345460139 -0.6341514587 3001 1311867270.4806110859 0.3018797338 0.1735920143 0.3590448499 0.0056034395 0.0379320000 740535957 0 402718720 -0.1612701863 0.0315736979 -0.6318203807 3002 1311867270.5165879726 0.3020485640 0.1736348046 0.3590448499 0.0056037406 0.0376450000 740539269 0 402718720 -0.1618660241 0.0321661346 -0.6293296218 3003 1311867270.5484349728 0.3018039167 0.1736774850 0.3590448499 0.0056028468 0.0389220000 740542413 0 402718720 -0.1613690704 0.0308543928 -0.6267978549 3004 1311867270.5808110237 0.3006613851 0.1737197566 0.3590448499 0.0056027860 0.0395310000 740545557 0 402718720 -0.1616094857 0.0275658239 -0.6247707009 3005 1311867270.6164429188 0.3004529178 0.1737619307 0.3590448499 0.0056038840 0.0382410000 740548757 0 402718720 -0.1610394716 0.0276962463 -0.6232361197 3006 1311867270.6485579014 0.2995338738 0.1738037710 0.3590448499 0.0056031643 0.0385110000 740551845 0 402718720 -0.1596866101 0.0267978348 -0.6212697029 3007 1311867270.6806249619 0.2988207638 0.1738453463 0.3590448499 0.0056035956 0.0386690000 740554989 0 402718720 -0.1594495326 0.0260453392 -0.6194208264 3008 1311867270.7164819241 0.2987465560 0.1738868693 0.3590448499 0.0056034540 0.0381520000 740558245 0 402718720 -0.1601139307 0.0249561891 -0.6178237200 3009 1311867270.7485640049 0.2982353270 0.1739281948 0.3590448499 0.0056025669 0.0390670000 740561389 0 402718720 -0.1587010622 0.0255833305 -0.6162110567 3010 1311867270.7805728912 0.2972064316 0.1739691510 0.3590448499 0.0056032968 0.0392230000 740564533 0 402718720 -0.1583488733 0.0238884613 -0.6141458750 3011 1311867270.8165240288 0.2977676988 0.1740102664 0.3590448499 0.0056033865 0.0376160000 740567789 0 402718720 -0.1590600759 0.0231526457 -0.6127568483 3012 1311867270.8484671116 0.2976788878 0.1740513251 0.3590448499 0.0056040559 0.0380590000 740570989 0 402718720 -0.1581778526 0.0246093143 -0.6109768748 3013 1311867270.8805739880 0.2968102694 0.1740920682 0.3590448499 0.0056033513 0.0384620000 740574077 0 402718720 -0.1577795744 0.0217987448 -0.6087722182 3014 1311867270.9164938927 0.2958493829 0.1741324654 0.3590448499 0.0056123100 0.0392350000 740577333 0 402718720 -0.1573800147 0.0205086414 -0.6075913310 3015 1311867270.9484250546 0.2961988449 0.1741729518 0.3590448499 0.0056192119 0.0384310000 740580477 0 402718720 -0.1560651809 0.0245573893 -0.6065186262 3016 1311867270.9805700779 0.2963311076 0.1742134552 0.3590448499 0.0056193114 0.0392160000 740583565 0 402718720 -0.1562692821 0.0216941703 -0.6034492254 3017 1311867271.0166149139 0.2959705889 0.1742538122 0.3590448499 0.0056185754 0.0388780000 740586877 0 402718720 -0.1573940068 0.0172986239 -0.6019302607 3018 1311867271.0485830307 0.2953708470 0.1742939437 0.3590448499 0.0056236316 0.0390880000 740589965 0 402718720 -0.1552869081 0.0194377936 -0.6010441780 3019 1311867271.0805909634 0.2943273783 0.1743337031 0.3590448499 0.0056244590 0.0397570000 740593109 0 402718720 -0.1536886692 0.0161039475 -0.5992116928 3020 1311867271.1165618896 0.2938074768 0.1743732639 0.3590448499 0.0056252899 0.0399560000 740596365 0 402718720 -0.1531634331 0.0143660298 -0.5981546640 3021 1311867271.1528968811 0.2941497862 0.1744129119 0.3590448499 0.0056256292 0.0382150000 740599621 0 402718720 -0.1525423974 0.0145261558 -0.5972381234 3022 1311867271.1805820465 0.2940090895 0.1744524871 0.3590448499 0.0056270737 0.0395590000 740602597 0 402718720 -0.1520353854 0.0143041369 -0.5954202414 3023 1311867271.2165699005 0.2929654717 0.1744916908 0.3590448499 0.0056269979 0.0397880000 740605853 0 402718720 -0.1513648182 0.0111734197 -0.5938689113 3024 1311867271.2484769821 0.2924473584 0.1745306973 0.3590448499 0.0056266621 0.0384130000 740608997 0 402718720 -0.1500381827 0.0127061373 -0.5926935077 3025 1311867271.2806289196 0.2931771874 0.1745699193 0.3590448499 0.0056286687 0.0396100000 740612085 0 402718720 -0.1501820385 0.0123771112 -0.5901612043 3026 1311867271.3166549206 0.2929727733 0.1746090478 0.3590448499 0.0056286262 0.0383100000 740615341 0 402718720 -0.1512183398 0.0088219400 -0.5875284672 3027 1311867271.3487799168 0.2927522063 0.1746480776 0.3590448499 0.0056278605 0.0397870000 740618541 0 402718720 -0.1507532150 0.0095563289 -0.5859209299 3028 1311867271.3806669712 0.2913061082 0.1746866040 0.3590448499 0.0056291711 0.0401690000 740621629 0 402718720 -0.1489584744 0.0073483232 -0.5832649469 3029 1311867271.4166629314 0.2909984291 0.1747250035 0.3590448499 0.0056300879 0.0399910000 740624885 0 402718720 -0.1494574398 0.0052728574 -0.5812557340 3030 1311867271.4487009048 0.2911157608 0.1747634162 0.3590448499 0.0056296717 0.0386590000 740628085 0 402718720 -0.1495456398 0.0038609037 -0.5787631273 3031 1311867271.4806230068 0.2899207175 0.1748014094 0.3590448499 0.0056304122 0.0404560000 740631173 0 402718720 -0.1488539726 0.0025377595 -0.5769384503 3032 1311867271.5165309906 0.2887404859 0.1748389883 0.3590448499 0.0056296130 0.0394060000 740634429 0 402718720 -0.1471127719 0.0021918828 -0.5746810436 3033 1311867271.5487699509 0.2879833281 0.1748762927 0.3590448499 0.0056294297 0.0389080000 740637629 0 402718720 -0.1473524868 -0.0009555197 -0.5719590783 3034 1311867271.5805718899 0.2880101502 0.1749135814 0.3590448499 0.0056292689 0.0390740000 740640661 0 402718720 -0.1475272477 -0.0004547671 -0.5697413683 3035 1311867271.6166501045 0.2871430516 0.1749505598 0.3590448499 0.0056285043 0.0392080000 740643917 0 402718720 -0.1471999884 -0.0014583080 -0.5668178797 3036 1311867271.6486690044 0.2858518362 0.1749870885 0.3590448499 0.0056281276 0.0397270000 740647117 0 402718720 -0.1459720284 -0.0026787156 -0.5636965036 3037 1311867271.6807179451 0.2847711742 0.1750232374 0.3590448499 0.0056273806 0.0395340000 740650261 0 402718720 -0.1457267404 -0.0025788930 -0.5603682399 3038 1311867271.7165880203 0.2844376564 0.1750592527 0.3590448499 0.0056266173 0.0404420000 740653461 0 402718720 -0.1465637684 -0.0044530537 -0.5564560890 3039 1311867271.7492449284 0.2835720479 0.1750949594 0.3590448499 0.0056258162 0.0397830000 740656717 0 402718720 -0.1482725739 -0.0070675770 -0.5524873137 3040 1311867271.7806129456 0.2828369141 0.1751304009 0.3590448499 0.0056262498 0.0398350000 740659749 0 402718720 -0.1486442089 -0.0076481444 -0.5486946702 3041 1311867271.8165030479 0.2817904055 0.1751654748 0.3590448499 0.0056258244 0.0401970000 740663005 0 402718720 -0.1485957354 -0.0086626904 -0.5447409153 3042 1311867271.8485109806 0.2809271514 0.1752002420 0.3590448499 0.0056250365 0.0396160000 740666205 0 402718720 -0.1499710083 -0.0126313232 -0.5403568745 3043 1311867271.8806529045 0.2793281078 0.1752344608 0.3590448499 0.0056243442 0.0398990000 740669293 0 402718720 -0.1500309110 -0.0144676780 -0.5366934538 3044 1311867271.9166769981 0.2769526541 0.1752678768 0.3590448499 0.0056234816 0.5640770000 753051677 0 402718720 -0.1471991092 -0.0137369344 -0.5332935452 3045 1311867271.9487230778 0.2766034007 0.1753011561 0.3590448499 0.0056227359 0.0303740000 756714085 0 402718720 -0.1467422545 -0.0177645963 -0.5264111757 3046 1311867271.9807260036 0.2764224112 0.1753343541 0.3590448499 0.0056223390 0.0411370000 759909253 0 402718720 -0.1476312876 -0.0190022103 -0.5219502449 3047 1311867272.0166780949 0.2753997445 0.1753671948 0.3590448499 0.0056216099 0.0394850000 759912565 0 402718720 -0.1477363259 -0.0180019867 -0.5186929703 3048 1311867272.0484859943 0.2734245062 0.1753993658 0.3590448499 0.0056238491 0.0438640000 759915709 0 402718720 -0.1460609883 -0.0209138058 -0.5138037801 3049 1311867272.0805869102 0.2713066936 0.1754308211 0.3590448499 0.0056243296 0.0356960000 759918797 0 402718720 -0.1444181353 -0.0234812927 -0.5100024939 3050 1311867272.1165699959 0.2713095844 0.1754622568 0.3590448499 0.0056252712 0.0331800000 759922109 0 402718720 -0.1442563236 -0.0244201086 -0.5065542459 3051 1311867272.1487190723 0.2712426186 0.1754936499 0.3590448499 0.0056253220 0.0337450000 759925309 0 402718720 -0.1441869736 -0.0269535910 -0.5028048158 3052 1311867272.1808199883 0.2698110640 0.1755245534 0.3590448499 0.0056272394 0.0348360000 759928397 0 402718720 -0.1428317875 -0.0280576404 -0.4997543693 3053 1311867272.2166140079 0.2680214047 0.1755548504 0.3590448499 0.0056296700 0.0334990000 759931653 0 402718720 -0.1420587152 -0.0314145386 -0.4966488183 3054 1311867272.2488400936 0.2687304914 0.1755853598 0.3590448499 0.0056337305 0.0323120000 759934797 0 402718720 -0.1408557147 -0.0303325132 -0.4944993854 3055 1311867272.2806749344 0.2685443461 0.1756157883 0.3590448499 0.0056334447 0.0408450000 759937997 0 402718720 -0.1410799176 -0.0313707255 -0.4922171831 3056 1311867272.3165800571 0.2679065466 0.1756459881 0.3590448499 0.0056333306 0.0391910000 759941197 0 402718720 -0.1400827914 -0.0337478966 -0.4892423749 3057 1311867272.3486170769 0.2672490776 0.1756759532 0.3590448499 0.0056326402 0.0364020000 759944397 0 402718720 -0.1391142756 -0.0342223942 -0.4870533049 3058 1311867272.3806040287 0.2671794891 0.1757058758 0.3590448499 0.0056367226 0.0419150000 759947485 0 402718720 -0.1397703886 -0.0351266898 -0.4848119020 3059 1311867272.4165749550 0.2672832608 0.1757358129 0.3590448499 0.0056384908 0.0370040000 759950741 0 402718720 -0.1401547045 -0.0365195423 -0.4819662273 3060 1311867272.4485790730 0.2658221722 0.1757652529 0.3590448499 0.0056377123 0.0415220000 759953885 0 402718720 -0.1387913376 -0.0372759514 -0.4803540409 3061 1311867272.4810869694 0.2654430866 0.1757945498 0.3590448499 0.0056368324 0.0398000000 759957029 0 402718720 -0.1387399137 -0.0389173143 -0.4778147638 3062 1311867272.5167770386 0.2650333047 0.1758236937 0.3590448499 0.0056359705 0.0387150000 759960285 0 402718720 -0.1386956424 -0.0396366753 -0.4753187299 3063 1311867272.5485880375 0.2639520764 0.1758524656 0.3590448499 0.0056351110 0.0382950000 759963429 0 402718720 -0.1375789493 -0.0399371013 -0.4735689163 3064 1311867272.5805819035 0.2636726201 0.1758811275 0.3590448499 0.0056343299 0.0393420000 759966517 0 402718720 -0.1372659653 -0.0402870625 -0.4713679552 3065 1311867272.6166520119 0.2629885972 0.1759095476 0.3590448499 0.0056336238 0.0387300000 759969829 0 402718720 -0.1365849823 -0.0415883362 -0.4689932466 3066 1311867272.6485888958 0.2622816563 0.1759377185 0.3590448499 0.0056331403 0.0380370000 759972973 0 402718720 -0.1359015852 -0.0413411371 -0.4671239853 3067 1311867272.6806919575 0.2624711692 0.1759659329 0.3590448499 0.0056324036 0.0379190000 759976061 0 402718720 -0.1355876327 -0.0410426520 -0.4645673037 3068 1311867272.7164890766 0.2618537247 0.1759939276 0.3590448499 0.0056320137 0.0394090000 759979317 0 402718720 -0.1356602609 -0.0428090170 -0.4626066685 3069 1311867272.7486550808 0.2607538104 0.1760215457 0.3590448499 0.0056312244 0.0414040000 759982517 0 402718720 -0.1338754445 -0.0437286273 -0.4602254927 3070 1311867272.7806560993 0.2603851557 0.1760490257 0.3590448499 0.0056334085 0.0356830000 759985605 0 402718720 -0.1327228099 -0.0438323393 -0.4578960836 3071 1311867272.8166229725 0.2603372931 0.1760764722 0.3590448499 0.0056328170 0.0367670000 759988861 0 402718720 -0.1317078471 -0.0431725681 -0.4561016560 3072 1311867272.8485050201 0.2605334818 0.1761039647 0.3590448499 0.0056319096 0.0403430000 759992061 0 402718720 -0.1316119879 -0.0436439440 -0.4540960789 3073 1311867272.8805370331 0.2595650554 0.1761311242 0.3590448499 0.0056314774 0.0402840000 759995149 0 402718720 -0.1298154593 -0.0432224199 -0.4526984394 3074 1311867272.9166030884 0.2592391670 0.1761581600 0.3590448499 0.0056322034 0.0392400000 759998405 0 402718720 -0.1275876462 -0.0446326956 -0.4504783154 3075 1311867272.9487431049 0.2591746747 0.1761851573 0.3590448499 0.0056330332 0.0368830000 760001605 0 402718720 -0.1264878660 -0.0455992818 -0.4486793876 3076 1311867272.9806759357 0.2590430379 0.1762120942 0.3590448499 0.0056323152 0.0382390000 760004749 0 402718720 -0.1249426305 -0.0445188545 -0.4476248622 3077 1311867273.0166079998 0.2593756020 0.1762391216 0.3590448499 0.0056314529 0.0398220000 760007949 0 402718720 -0.1241285354 -0.0453094654 -0.4460917711 3078 1311867273.0485780239 0.2587069571 0.1762659143 0.3590448499 0.0056305760 0.0375140000 760011149 0 402718720 -0.1220043153 -0.0458503291 -0.4450771511 3079 1311867273.0807540417 0.2581755221 0.1762925170 0.3590448499 0.0056300300 0.0392100000 760014237 0 402718720 -0.1199192852 -0.0450489335 -0.4446470439 3080 1311867273.1167309284 0.2586688697 0.1763192625 0.3590448499 0.0056291434 0.0375320000 760017493 0 402718720 -0.1192869395 -0.0438827313 -0.4438284934 3081 1311867273.1486411095 0.2596876621 0.1763463214 0.3590448499 0.0056327504 0.0369240000 760020693 0 402718720 -0.1195790172 -0.0436161049 -0.4420752525 3082 1311867273.1806969643 0.2589615583 0.1763731271 0.3590448499 0.0056409157 0.0383030000 760023837 0 402718720 -0.1185759380 -0.0440717600 -0.4411218464 3083 1311867273.2168378830 0.2576269507 0.1763994826 0.3590448499 0.0056403679 0.0405950000 760027037 0 402718720 -0.1169783771 -0.0453147776 -0.4397616386 3084 1311867273.2485439777 0.2582351267 0.1764260181 0.3590448499 0.0056395657 0.0363820000 760030237 0 402718720 -0.1171610206 -0.0472264737 -0.4374949634 3085 1311867273.2807140350 0.2577224374 0.1764523703 0.3590448499 0.0056413670 0.0380260000 760033325 0 402718720 -0.1167008057 -0.0453846119 -0.4370032549 3086 1311867273.3168380260 0.2565246820 0.1764783172 0.3590448499 0.0056407066 0.0363260000 760036581 0 402718720 -0.1143783256 -0.0449381731 -0.4354369044 3087 1311867273.3487319946 0.2560060918 0.1765040794 0.3590448499 0.0056417172 0.0398390000 760039781 0 402718720 -0.1136756614 -0.0464744419 -0.4332697988 3088 1311867273.3806970119 0.2555526495 0.1765296780 0.3590448499 0.0056408694 0.0393270000 760042925 0 402718720 -0.1128624231 -0.0460815839 -0.4313580096 3089 1311867273.4168300629 0.2544266284 0.1765548956 0.3590448499 0.0056401488 0.0363880000 760046125 0 402718720 -0.1112766117 -0.0439870581 -0.4303300679 3090 1311867273.4486439228 0.2536260188 0.1765798377 0.3590448499 0.0056394433 0.0386220000 760049325 0 402718720 -0.1099034324 -0.0444395356 -0.4277234674 3091 1311867273.4807689190 0.2534108162 0.1766046940 0.3590448499 0.0056386289 0.0393110000 760052413 0 402718720 -0.1096784025 -0.0446059071 -0.4253029823 3092 1311867273.5166900158 0.2510846853 0.1766287820 0.3590448499 0.0056391405 0.0390010000 760055669 0 402718720 -0.1077370644 -0.0438726805 -0.4234116077 3093 1311867273.5488069057 0.2511507273 0.1766528757 0.3590448499 0.0056383066 0.0389780000 760058869 0 402718720 -0.1074277312 -0.0431538746 -0.4206140935 3094 1311867273.5806310177 0.2504976690 0.1766767428 0.3590448499 0.0056378363 0.0390900000 760061957 0 402718720 -0.1063571200 -0.0455903485 -0.4163338244 3095 1311867273.6167418957 0.2493381053 0.1767002198 0.3590448499 0.0056384731 0.0389720000 760065213 0 402718720 -0.1055571735 -0.0474719703 -0.4135233462 3096 1311867273.6486740112 0.2497594655 0.1767238178 0.3590448499 0.0056394439 0.0395260000 760068413 0 402718720 -0.1052525192 -0.0462728813 -0.4109677970 3097 1311867273.6809740067 0.2489720881 0.1767471463 0.3590448499 0.0056392076 0.0401040000 760071557 0 402718720 -0.1040925756 -0.0471340008 -0.4078852832 3098 1311867273.7167069912 0.2473684996 0.1767699420 0.3590448499 0.0056421597 0.0379810000 760074757 0 402718720 -0.1036228091 -0.0467073284 -0.4057928920 3099 1311867273.7487111092 0.2462846935 0.1767923734 0.3590448499 0.0056420727 0.0388700000 760077957 0 402718720 -0.1006965935 -0.0449368022 -0.4034363627 3100 1311867273.7807350159 0.2467211634 0.1768149311 0.3590448499 0.0056519036 0.0407700000 760081101 0 402718720 -0.1002392843 -0.0466139503 -0.4001894295 3101 1311867273.8166389465 0.2455834448 0.1768371073 0.3590448499 0.0056513622 0.0388500000 760084301 0 402718720 -0.0989820063 -0.0478602126 -0.3973125219 3102 1311867273.8491230011 0.2459077537 0.1768593738 0.3590448499 0.0056517709 0.0405550000 760087557 0 402718720 -0.0993740410 -0.0491634086 -0.3943676353 3103 1311867273.8807370663 0.2455038279 0.1768814958 0.3590448499 0.0056509599 0.0424870000 760090645 0 402718720 -0.0993000045 -0.0496904813 -0.3918488324 3104 1311867273.9166181087 0.2449810505 0.1769034350 0.3590448499 0.0056508146 0.0420270000 760093901 0 402718720 -0.0991441235 -0.0504122004 -0.3894993365 3105 1311867273.9492130280 0.2446459383 0.1769252523 0.3590448499 0.0056499190 0.0422670000 760097101 0 402718720 -0.0996768773 -0.0496367067 -0.3876910210 3106 1311867273.9806659222 0.2449822724 0.1769471637 0.3590448499 0.0056490181 0.0440000000 760100133 0 402718720 -0.1017895415 -0.0510998964 -0.3848181069 3107 1311867274.0168220997 0.2440208346 0.1769687517 0.3590448499 0.0056481255 0.0405540000 760103445 0 402718720 -0.1023364142 -0.0505417138 -0.3822203875 3108 1311867274.0487558842 0.2439279258 0.1769902958 0.3590448499 0.0056476649 0.0406710000 760106589 0 402718720 -0.1031167209 -0.0497476533 -0.3790666461 3109 1311867274.0806779861 0.2428601384 0.1770114826 0.3590448499 0.0056469127 0.6540990000 772486573 0 402718720 -0.1042967290 -0.0518238805 -0.3753761053 3110 1311867274.1166191101 0.2386313528 0.1770312961 0.3590448499 0.0056486086 0.0312600000 776156381 0 402718720 -0.1046295688 -0.0513305552 -0.3766764998 3111 1311867274.1492240429 0.2379301488 0.1770508714 0.3590448499 0.0056480091 0.0388560000 779351773 0 402718720 -0.1054555401 -0.0517394766 -0.3731622994 3112 1311867274.1809189320 0.2369747758 0.1770701272 0.3590448499 0.0056497994 0.0423040000 779354805 0 402718720 -0.1062125936 -0.0542089343 -0.3688128293 3113 1311867274.2169539928 0.2351644784 0.1770887890 0.3590448499 0.0056579005 0.0405660000 779358117 0 402718720 -0.1076391265 -0.0572722144 -0.3648864329 3114 1311867274.2489650249 0.2339113206 0.1771070365 0.3590448499 0.0056574435 0.0353950000 779361317 0 402718720 -0.1075596884 -0.0560712516 -0.3623881638 3115 1311867274.2807838917 0.2331083119 0.1771250144 0.3590448499 0.0056569111 0.0379260000 779364349 0 402718720 -0.1084221229 -0.0564053021 -0.3592162430 3116 1311867274.3171210289 0.2325658649 0.1771428067 0.3590448499 0.0056564031 0.0347630000 779367661 0 402718720 -0.1103902161 -0.0584959462 -0.3547308445 3117 1311867274.3488299847 0.2310621887 0.1771601052 0.3590448499 0.0056568061 0.0350590000 779370805 0 402718720 -0.1104910076 -0.0594353862 -0.3518041372 3118 1311867274.3808619976 0.2300582081 0.1771770706 0.3590448499 0.0056605497 0.0366510000 779373893 0 402718720 -0.1107051671 -0.0595365874 -0.3484335244 3119 1311867274.4168369770 0.2295566499 0.1771938643 0.3590448499 0.0056650672 0.0359510000 779377205 0 402718720 -0.1120328829 -0.0619749390 -0.3448061347 3120 1311867274.4487800598 0.2283722907 0.1772102677 0.3590448499 0.0056641789 0.0384180000 779380349 0 402718720 -0.1119911224 -0.0621548593 -0.3420437276 3121 1311867274.4806609154 0.2282138765 0.1772266097 0.3590448499 0.0056646854 0.0410950000 779383381 0 402718720 -0.1129033640 -0.0633616671 -0.3385954797 3122 1311867274.5167980194 0.2275387347 0.1772427251 0.3590448499 0.0056641813 0.0374870000 779386637 0 402718720 -0.1137849838 -0.0654431060 -0.3354481757 3123 1311867274.5489439964 0.2264098823 0.1772584686 0.3590448499 0.0056635271 0.0398460000 779389837 0 402718720 -0.1145111844 -0.0680787563 -0.3329991400 3124 1311867274.5808830261 0.2254589796 0.1772738977 0.3590448499 0.0056631580 0.0417820000 779392869 0 402718720 -0.1144588813 -0.0683262348 -0.3313555121 3125 1311867274.6168630123 0.2242783308 0.1772889392 0.3590448499 0.0056650965 0.0395700000 779396125 0 402718720 -0.1145847514 -0.0698731914 -0.3287532926 3126 1311867274.6490099430 0.2233918905 0.1773036874 0.3590448499 0.0056644550 0.0383650000 779399325 0 402718720 -0.1147267446 -0.0705151409 -0.3263999522 3127 1311867274.6808040142 0.2225102186 0.1773181442 0.3590448499 0.0056636161 0.0382540000 779402413 0 402718720 -0.1148213968 -0.0706710219 -0.3243844807 3128 1311867274.7167110443 0.2220111191 0.1773324323 0.3590448499 0.0056629557 0.0377560000 779405669 0 402718720 -0.1150836125 -0.0710204765 -0.3218449652 3129 1311867274.7487630844 0.2210570574 0.1773464063 0.3590448499 0.0056641390 0.0377990000 779408869 0 402718720 -0.1160662472 -0.0727064908 -0.3195289671 3130 1311867274.7806460857 0.2202412784 0.1773601107 0.3590448499 0.0056645721 0.0391510000 779411957 0 402718720 -0.1164120510 -0.0728508532 -0.3172472417 3131 1311867274.8167018890 0.2191392779 0.1773734544 0.3590448499 0.0056637002 0.0383170000 779415213 0 402718720 -0.1165551022 -0.0738526657 -0.3145549297 3132 1311867274.8487939835 0.2185956687 0.1773866160 0.3590448499 0.0056640138 0.0385430000 779418413 0 402718720 -0.1171428934 -0.0738611966 -0.3115614653 3133 1311867274.8808209896 0.2179166675 0.1773995525 0.3590448499 0.0056633075 0.0400900000 779421501 0 402718720 -0.1180792451 -0.0747306123 -0.3085588813 3134 1311867274.9166278839 0.2175160795 0.1774123529 0.3590448499 0.0056634224 0.0394920000 779424757 0 402718720 -0.1189838722 -0.0741155446 -0.3056676090 3135 1311867274.9486460686 0.2159974575 0.1774246608 0.3590448499 0.0056628430 0.0379820000 779427901 0 402718720 -0.1183909252 -0.0737208650 -0.3027833402 3136 1311867274.9809029102 0.2150019258 0.1774366433 0.3590448499 0.0056622461 0.0395970000 779431045 0 402718720 -0.1188058928 -0.0765147656 -0.2990955710 3137 1311867275.0166749954 0.2155815512 0.1774488030 0.3590448499 0.0056634594 0.0390620000 779434301 0 402718720 -0.1204565242 -0.0757206008 -0.2958786786 3138 1311867275.0487210751 0.2145023346 0.1774606110 0.3590448499 0.0056650838 0.0380050000 779437501 0 402718720 -0.1209723800 -0.0753974989 -0.2930661440 3139 1311867275.0807540417 0.2122563422 0.1774716960 0.3590448499 0.0056752119 0.0385560000 779440645 0 402718720 -0.1205184013 -0.0768466219 -0.2899580002 3140 1311867275.1168329716 0.2120675147 0.1774827138 0.3590448499 0.0056803911 0.0389660000 779443845 0 402718720 -0.1212818548 -0.0790375322 -0.2862728834 3141 1311867275.1486890316 0.2124814540 0.1774938563 0.3590448499 0.0056795634 0.0395300000 779446989 0 402718720 -0.1226450950 -0.0790382177 -0.2829391658 3142 1311867275.1807010174 0.2113224119 0.1775046229 0.3590448499 0.0056790681 0.0396550000 779450133 0 402718720 -0.1226730868 -0.0790662616 -0.2806678712 3143 1311867275.2167370319 0.2100637555 0.1775149821 0.3590448499 0.0056796824 0.0396880000 779453389 0 402718720 -0.1227475181 -0.0803438798 -0.2778272629 3144 1311867275.2487349510 0.2092939764 0.1775250900 0.3590448499 0.0056790926 0.0396500000 779456533 0 402718720 -0.1227919236 -0.0802169591 -0.2753248811 3145 1311867275.2808110714 0.2080851346 0.1775348070 0.3590448499 0.0056783487 0.0407510000 779459677 0 402718720 -0.1226016805 -0.0794778839 -0.2728997767 3146 1311867275.3166658878 0.2086002827 0.1775446816 0.3590448499 0.0056777349 0.0408460000 779462933 0 402718720 -0.1242940724 -0.0792473629 -0.2692683935 3147 1311867275.3487091064 0.2079612315 0.1775543468 0.3590448499 0.0056814553 0.0394130000 779466133 0 402718720 -0.1253089607 -0.0802630410 -0.2658872604 3148 1311867275.3810400963 0.2061858326 0.1775634420 0.3590448499 0.0056807955 0.0402520000 779469221 0 402718720 -0.1246436015 -0.0796367377 -0.2631947994 3149 1311867275.4166951180 0.2056531608 0.1775723622 0.3590448499 0.0056846725 0.0408470000 779472365 0 402718720 -0.1254930347 -0.0807790235 -0.2593500912 3150 1311867275.4488511086 0.2051796466 0.1775811264 0.3590448499 0.0056888882 0.0401150000 779475565 0 402718720 -0.1268886477 -0.0824383572 -0.2557208836 3151 1311867275.4808599949 0.2045680583 0.1775896910 0.3590448499 0.0056891450 0.0407270000 779478653 0 402718720 -0.1280109286 -0.0820646584 -0.2528705597 3152 1311867275.5168170929 0.2031975091 0.1775978153 0.3590448499 0.0056886479 0.0412590000 779481909 0 402718720 -0.1281392127 -0.0819499418 -0.2498668581 3153 1311867275.5488140583 0.2022951692 0.1776056482 0.3590448499 0.0056897006 0.0408870000 779485109 0 402718720 -0.1295254678 -0.0837586150 -0.2462711781 3154 1311867275.5808739662 0.2016796768 0.1776132811 0.3590448499 0.0056889802 0.0413620000 779488197 0 402718720 -0.1308895350 -0.0843554735 -0.2432350218 3155 1311867275.6167941093 0.2012462020 0.1776207717 0.3590448499 0.0056883567 0.0417320000 779491453 0 402718720 -0.1324084103 -0.0843843147 -0.2404724509 3156 1311867275.6487329006 0.2001675516 0.1776279158 0.3590448499 0.0056906760 0.0411950000 779494597 0 402718720 -0.1331796497 -0.0859134048 -0.2374033779 3157 1311867275.6808829308 0.1997931600 0.1776349368 0.3590448499 0.0056930846 0.0404090000 779497685 0 402718720 -0.1347897649 -0.0872366056 -0.2343528271 3158 1311867275.7168269157 0.1989916414 0.1776416995 0.3590448499 0.0056924677 0.0415470000 779500997 0 402718720 -0.1355491728 -0.0873530507 -0.2320527732 3159 1311867275.7492160797 0.1980167925 0.1776481494 0.3590448499 0.0056918787 0.0403960000 779504197 0 402718720 -0.1364314407 -0.0882168561 -0.2294103503 3160 1311867275.7808101177 0.1970334500 0.1776542840 0.3590448499 0.0056924190 0.0408460000 779507285 0 402718720 -0.1374915242 -0.0893453360 -0.2268521786 3161 1311867275.8167719841 0.1963596642 0.1776602015 0.3590448499 0.0056927549 0.0411330000 779510485 0 402718720 -0.1384885460 -0.0886332467 -0.2247449905 3162 1311867275.8488399982 0.1961189210 0.1776660392 0.3590448499 0.0056928653 0.0422670000 779513685 0 402718720 -0.1400489062 -0.0878517181 -0.2222175300 3163 1311867275.8807599545 0.1954013556 0.1776716463 0.3590448499 0.0056929613 0.6041360000 791884133 0 402718720 -0.1415751129 -0.0891988873 -0.2190190405 3164 1311867275.9170610905 0.1926364154 0.1776763760 0.3590448499 0.0056924042 0.0294580000 795546653 0 402718720 -0.1415866315 -0.0898275524 -0.2173343748 3165 1311867275.9488210678 0.1921322197 0.1776809434 0.3590448499 0.0056917492 0.0334760000 798741989 0 402718720 -0.1418996602 -0.0887814313 -0.2149617821 3166 1311867275.9808959961 0.1927314699 0.1776856972 0.3590448499 0.0056909966 0.0443610000 798745077 0 402718720 -0.1443782002 -0.0880337581 -0.2121227831 3167 1311867276.0168170929 0.1911611259 0.1776899522 0.3590448499 0.0056917288 0.0417130000 798748333 0 402718720 -0.1454742700 -0.0904940963 -0.2092820406 3168 1311867276.0489850044 0.1890623868 0.1776935420 0.3590448499 0.0057065337 0.0376810000 798751533 0 402718720 -0.1455253065 -0.0898938179 -0.2075642943 3169 1311867276.0810608864 0.1892678440 0.1776971943 0.3590448499 0.0057158993 0.0386360000 798754677 0 402718720 -0.1463787854 -0.0890623704 -0.2046643943 3170 1311867276.1170461178 0.1881020665 0.1777004766 0.3590448499 0.0057182299 0.0389050000 798757877 0 402718720 -0.1478546262 -0.0917336345 -0.2016126364 3171 1311867276.1489109993 0.1877339035 0.1777036407 0.3590448499 0.0057210887 0.0362860000 798761077 0 402718720 -0.1483958960 -0.0921469927 -0.1990918368 3172 1311867276.1808259487 0.1869189441 0.1777065459 0.3590448499 0.0057227160 0.0345200000 798764165 0 402718720 -0.1483405679 -0.0912686065 -0.1970729530 3173 1311867276.2168269157 0.1866213679 0.1777093555 0.3590448499 0.0057220710 0.0353260000 798767421 0 402718720 -0.1488393545 -0.0911699980 -0.1944779754 3174 1311867276.2489540577 0.1861923486 0.1777120282 0.3590448499 0.0057217092 0.0362480000 798770621 0 402718720 -0.1495860368 -0.0908318162 -0.1921325326 3175 1311867276.2810339928 0.1851478964 0.1777143702 0.3590448499 0.0057212435 0.0365830000 798773709 0 402718720 -0.1493039280 -0.0912815705 -0.1897235215 3176 1311867276.3168470860 0.1852246523 0.1777167349 0.3590448499 0.0057212873 0.0367650000 798776965 0 402718720 -0.1500736326 -0.0917715058 -0.1872844696 3177 1311867276.3488230705 0.1844669878 0.1777188596 0.3590448499 0.0057211506 0.0354370000 798780109 0 402718720 -0.1508718282 -0.0927746892 -0.1850782335 3178 1311867276.3809969425 0.1832713038 0.1777206067 0.3590448499 0.0057210096 0.0384840000 798783197 0 402718720 -0.1508908421 -0.0938794911 -0.1831567585 3179 1311867276.4167599678 0.1829641610 0.1777222562 0.3590448499 0.0057203419 0.0378310000 798786453 0 402718720 -0.1519136727 -0.0948789045 -0.1811223924 3180 1311867276.4490129948 0.1823383421 0.1777237078 0.3590448499 0.0057194782 0.0348350000 798789653 0 402718720 -0.1525617540 -0.0954627246 -0.1792388707 3181 1311867276.4810450077 0.1822353452 0.1777251261 0.3590448499 0.0057189855 0.0347890000 798792741 0 402718720 -0.1532470882 -0.0950904265 -0.1776197851 3182 1311867276.5168120861 0.1809516251 0.1777261401 0.3590448499 0.0057181669 0.0354970000 798795997 0 402718720 -0.1528680623 -0.0948913917 -0.1762600839 3183 1311867276.5489749908 0.1808333546 0.1777271163 0.3590448499 0.0057174758 0.0331970000 798799197 0 402718720 -0.1538261920 -0.0953870267 -0.1743757427 3184 1311867276.5810070038 0.1804323792 0.1777279659 0.3590448499 0.0057166356 0.0345080000 798802285 0 402718720 -0.1537893713 -0.0937690213 -0.1727725267 3185 1311867276.6169550419 0.1800385714 0.1777286914 0.3590448499 0.0057159043 0.0335720000 798805541 0 402718720 -0.1547829658 -0.0952267870 -0.1699699908 3186 1311867276.6487970352 0.1795877814 0.1777292749 0.3590448499 0.0057157115 0.0346070000 798808629 0 402718720 -0.1554928124 -0.0956993103 -0.1678586304 3187 1311867276.6808810234 0.1792021841 0.1777297371 0.3590448499 0.0057162583 0.0358760000 798811717 0 402718720 -0.1557488292 -0.0951532423 -0.1659353077 3188 1311867276.7168340683 0.1786613017 0.1777300293 0.3590448499 0.0057171915 0.0354530000 798815029 0 402718720 -0.1565837562 -0.0962817073 -0.1633291245 3189 1311867276.7490069866 0.1781496853 0.1777301609 0.3590448499 0.0057186159 0.0351920000 798818173 0 402718720 -0.1576246023 -0.0976349935 -0.1612868309 3190 1311867276.7811739445 0.1773302853 0.1777300355 0.3590448499 0.0057179945 0.0353690000 798821317 0 402718720 -0.1580431461 -0.0973666683 -0.1601323485 3191 1311867276.8168849945 0.1765363961 0.1777296614 0.3590448499 0.0057193455 0.0354670000 798824573 0 402718720 -0.1580638736 -0.0977195427 -0.1587675661 3192 1311867276.8491539955 0.1767468303 0.1777293535 0.3590448499 0.0057188063 0.0333140000 798827773 0 402718720 -0.1595824212 -0.0993099958 -0.1562899798 3193 1311867276.8808639050 0.1769683510 0.1777291152 0.3590448499 0.0057199714 0.0344620000 798830805 0 402718720 -0.1607262492 -0.0983400941 -0.1553377062 3194 1311867276.9169609547 0.1761916876 0.1777286339 0.3590448499 0.0057192529 0.0344920000 798834117 0 402718720 -0.1605035812 -0.0981761590 -0.1537163854 3195 1311867276.9488658905 0.1754544228 0.1777279220 0.3590448499 0.0057195807 0.0354650000 798837261 0 402718720 -0.1614782512 -0.0997049734 -0.1513600945 3196 1311867276.9808659554 0.1756666601 0.1777272771 0.3590448499 0.0057191634 0.0356330000 798840349 0 402718720 -0.1631504297 -0.0994546637 -0.1493087560 3197 1311867277.0168800354 0.1745189428 0.1777262736 0.3590448499 0.0057182882 0.0359010000 798843661 0 402718720 -0.1624544710 -0.0979020521 -0.1479720175 3198 1311867277.0490090847 0.1740295291 0.1777251176 0.3590448499 0.0057176779 0.0358750000 798846805 0 402718720 -0.1627927125 -0.0981912017 -0.1454666108 3199 1311867277.0812649727 0.1733782291 0.1777237588 0.3590448499 0.0057171875 0.0365200000 798849949 0 402718720 -0.1635074615 -0.0998619720 -0.1421619803 3200 1311867277.1168239117 0.1724945754 0.1777221247 0.3590448499 0.0057164158 0.0378090000 798853149 0 402718720 -0.1635249704 -0.0989715680 -0.1406347007 3201 1311867277.1488339901 0.1717580110 0.1777202614 0.3590448499 0.0057169044 0.0363750000 798856349 0 402718720 -0.1634505987 -0.0975683331 -0.1384549886 3202 1311867277.1808309555 0.1708204001 0.1777181066 0.3590448499 0.0057164806 0.0367120000 798859493 0 402718720 -0.1636243165 -0.0978896320 -0.1353188604 3203 1311867277.2169671059 0.1705932319 0.1777158821 0.3590448499 0.0057158073 0.0372020000 798862749 0 402718720 -0.1647613496 -0.0988586023 -0.1319001168 3204 1311867277.2489259243 0.1700997949 0.1777135051 0.3590448499 0.0057149478 0.0378140000 798865893 0 402718720 -0.1652460098 -0.0991920903 -0.1293735057 3205 1311867277.2808489799 0.1683462709 0.1777105824 0.3590448499 0.0057160534 0.0372680000 798869037 0 402718720 -0.1643173397 -0.0987136662 -0.1271767914 3206 1311867277.3169291019 0.1672335565 0.1777073145 0.3590448499 0.0057157257 0.0376500000 798872293 0 402718720 -0.1636110544 -0.0982472822 -0.1249185801 3207 1311867277.3490509987 0.1671929061 0.1777040359 0.3590448499 0.0057154060 0.0366630000 798875437 0 402718720 -0.1641128510 -0.0986510664 -0.1218856946 3208 1311867277.3842089176 0.1654515117 0.1777002165 0.3590448499 0.0057164281 0.0380050000 798878637 0 402718720 -0.1634569615 -0.1005338654 -0.1190014184 3209 1311867277.4169220924 0.1665202081 0.1776967326 0.3590448499 0.0057156560 0.0379620000 798881725 0 402718720 -0.1652836204 -0.1007603034 -0.1160804927 3210 1311867277.4501609802 0.1665294766 0.1776932537 0.3590448499 0.0057148665 0.0373410000 798884925 0 402718720 -0.1658042967 -0.0988987535 -0.1142967194 3211 1311867277.4809010029 0.1663477123 0.1776897203 0.3590448499 0.0057156640 0.0375380000 798887957 0 402718720 -0.1656646729 -0.0986828357 -0.1118545458 3212 1311867277.5170779228 0.1660774946 0.1776861051 0.3590448499 0.0057183106 0.0384250000 798891269 0 402718720 -0.1677570641 -0.1013289392 -0.1083619073 3213 1311867277.5488278866 0.1651805341 0.1776822129 0.3590448499 0.0057184107 0.0409580000 798894413 0 402718720 -0.1666233093 -0.1007434949 -0.1070866957 3214 1311867277.5809199810 0.1632647365 0.1776777270 0.3590448499 0.0057243852 0.0375640000 798897501 0 402718720 -0.1653994322 -0.1001360416 -0.1059184894 3215 1311867277.6168971062 0.1636428088 0.1776733616 0.3590448499 0.0057278950 0.0388680000 798900757 0 402718720 -0.1661089063 -0.1022419482 -0.1033785194 3216 1311867277.6490759850 0.1629342437 0.1776687785 0.3590448499 0.0057278414 0.0386080000 798903957 0 402718720 -0.1663602889 -0.1041325852 -0.1014648601 3217 1311867277.6810569763 0.1624469012 0.1776640468 0.3590448499 0.0057274030 0.0395340000 798907045 0 402718720 -0.1648398787 -0.1017039046 -0.1010149121 3218 1311867277.7171390057 0.1618696004 0.1776591387 0.3590448499 0.0057265342 0.0392590000 798910301 0 402718720 -0.1645653844 -0.1009587198 -0.0991928428 3219 1311867277.7489089966 0.1623157859 0.1776543722 0.3590448499 0.0057261854 0.0377630000 798913445 0 402718720 -0.1648273468 -0.1018174514 -0.0962900370 3220 1311867277.7848179340 0.1610488296 0.1776492152 0.3590448499 0.0057254652 0.0378530000 798916645 0 402718720 -0.1638817638 -0.1016546562 -0.0941328630 3221 1311867277.8168680668 0.1598352790 0.1776436846 0.3590448499 0.0057249379 0.0390400000 798919789 0 402718720 -0.1624193788 -0.1007439569 -0.0919314474 3222 1311867277.8489060402 0.1598656774 0.1776381669 0.3590448499 0.0057255666 0.0381970000 798922989 0 402718720 -0.1634956151 -0.1029713750 -0.0876137540 3223 1311867277.8848960400 0.1589396000 0.1776323653 0.3590448499 0.0057247511 0.0387650000 798926189 0 402718720 -0.1631853282 -0.1044994444 -0.0845833048 3224 1311867277.9168579578 0.1580288261 0.1776262848 0.3590448499 0.0057239116 0.0397850000 798929333 0 402718720 -0.1614324003 -0.1029457524 -0.0829383880 3225 1311867277.9489328861 0.1579086781 0.1776201708 0.3590448499 0.0057236076 0.0392300000 798932533 0 402718720 -0.1609995216 -0.1031012982 -0.0796963573 3226 1311867277.9850919247 0.1579234302 0.1776140652 0.3590448499 0.0057234703 0.0395910000 798935733 0 402718720 -0.1613496244 -0.1046358123 -0.0762441978 3227 1311867278.0168480873 0.1570187658 0.1776076830 0.3590448499 0.0057227886 0.0400050000 798938877 0 402718720 -0.1598975956 -0.1055180877 -0.0737054124 3228 1311867278.0490009785 0.1565848589 0.1776011704 0.3590448499 0.0057219377 0.0401790000 798942077 0 402718720 -0.1586538404 -0.1053602099 -0.0713144243 3229 1311867278.0848259926 0.1564875990 0.1775946317 0.3590448499 0.0057211760 0.0421980000 798945277 0 402718720 -0.1577673703 -0.1047332585 -0.0688733310 3230 1311867278.1168620586 0.1560796946 0.1775879707 0.3590448499 0.0057204423 0.0423320000 798948421 0 402718720 -0.1573618203 -0.1066483557 -0.0652937442 3231 1311867278.1490180492 0.1555469185 0.1775811489 0.3590448499 0.0057203885 0.0407740000 798951621 0 402718720 -0.1562380344 -0.1058050692 -0.0630459338 3232 1311867278.1848649979 0.1553965956 0.1775742849 0.3590448499 0.0057203494 0.0410710000 798954877 0 402718720 -0.1559082866 -0.1054168567 -0.0601765700 3233 1311867278.2169399261 0.1547208279 0.1775672161 0.3590448499 0.0057197671 0.0417280000 798957965 0 402718720 -0.1552286595 -0.1058008894 -0.0571735241 3234 1311867278.2489399910 0.1540564150 0.1775599462 0.3590448499 0.0057201305 0.0416910000 798961109 0 402718720 -0.1547639519 -0.1067971587 -0.0542222261 3235 1311867278.2849080563 0.1533580124 0.1775524649 0.3590448499 0.0057196517 0.0407300000 798964365 0 402718720 -0.1535105556 -0.1052467152 -0.0525359623 3236 1311867278.3174040318 0.1522921622 0.1775446589 0.3590448499 0.0057203995 0.0407620000 798967565 0 402718720 -0.1527003795 -0.1053090617 -0.0497931615 3237 1311867278.3490109444 0.1526946127 0.1775369820 0.3590448499 0.0057203591 0.0405010000 798970653 0 402718720 -0.1533151120 -0.1072664708 -0.0463032573 3238 1311867278.3849310875 0.1520932317 0.1775291242 0.3590448499 0.0057201039 0.0429010000 798973909 0 402718720 -0.1527318507 -0.1070039719 -0.0442957319 3239 1311867278.4168560505 0.1519206017 0.1775212179 0.3590448499 0.0057192719 0.0419110000 798977053 0 402718720 -0.1518560499 -0.1056691259 -0.0423352458 3240 1311867278.4489140511 0.1515399069 0.1775131989 0.3590448499 0.0057189865 0.0427480000 798980197 0 402718720 -0.1519784778 -0.1069795713 -0.0392934531 3241 1311867278.4850320816 0.1506106555 0.1775048983 0.3590448499 0.0057203092 0.0439720000 798983453 0 402718720 -0.1524451971 -0.1096789092 -0.0363762788 3242 1311867278.5168991089 0.1500031203 0.1774964153 0.3590448499 0.0057194798 0.0438330000 798986597 0 402718720 -0.1519008577 -0.1103189066 -0.0342293307 3243 1311867278.5492649078 0.1488867998 0.1774875933 0.3590448499 0.0057188831 0.0428350000 798989797 0 402718720 -0.1500167102 -0.1082489267 -0.0329506285 3244 1311867278.5849230289 0.1488582194 0.1774787680 0.3590448499 0.0057180362 0.0428860000 798993053 0 402718720 -0.1499961019 -0.1083466187 -0.0300835259 3245 1311867278.6168739796 0.1495317519 0.1774701557 0.3590448499 0.0057179113 0.0436090000 798996141 0 402718720 -0.1508540362 -0.1095718816 -0.0270436537 3246 1311867278.6490800381 0.1486465484 0.1774612759 0.3590448499 0.0057177870 0.0434170000 798999285 0 402718720 -0.1500492990 -0.1085490286 -0.0252515916 3247 1311867278.6849050522 0.1470323503 0.1774519045 0.3590448499 0.0057169147 0.0452520000 799002541 0 402718720 -0.1475698799 -0.1071183309 -0.0234668162 3248 1311867278.7170519829 0.1471774876 0.1774425836 0.3590448499 0.0057165350 0.0457880000 799005685 0 402718720 -0.1481423974 -0.1090356186 -0.0195676778 3249 1311867278.7491168976 0.1464470178 0.1774330436 0.3590448499 0.0057157267 0.0432150000 799008829 0 402718720 -0.1482893229 -0.1116103753 -0.0165011045 3250 1311867278.7850129604 0.1455068439 0.1774232201 0.3590448499 0.0057157391 0.0436600000 799012141 0 402718720 -0.1462342292 -0.1088876799 -0.0158681646 3251 1311867278.8169329166 0.1457594484 0.1774134804 0.3590448499 0.0057165061 0.0436590000 799015229 0 402718720 -0.1453995258 -0.1083889306 -0.0132010765 3252 1311867278.8489089012 0.1453249454 0.1774036131 0.3590448499 0.0057168083 0.6636240000 811381617 0 402718720 -0.1462595016 -0.1119066104 -0.0094898567 3253 1311867278.8849530220 0.1448579133 0.1773936083 0.3590448499 0.0057160433 0.0350350000 815044081 0 402718720 -0.1460887641 -0.1107761189 -0.0088314712 3254 1311867278.9169590473 0.1457887292 0.1773838956 0.3590448499 0.0057175547 0.0609840000 818239361 0 402718720 -0.1441883594 -0.1055683121 -0.0074750651 3255 1311867278.9490818977 0.1462190896 0.1773743212 0.3590448499 0.0057169508 0.0425240000 818242505 0 402718720 -0.1459872723 -0.1075749993 -0.0036322640 3256 1311867278.9850499630 0.1443276256 0.1773641717 0.3590448499 0.0057183296 0.0398960000 818245761 0 402718720 -0.1465154141 -0.1115220040 -0.0006102061 3257 1311867279.0169510841 0.1428266168 0.1773535676 0.3590448499 0.0057177719 0.0351510000 818248905 0 402718720 -0.1437959075 -0.1094809845 0.0003973139 3258 1311867279.0492069721 0.1441491693 0.1773433760 0.3590448499 0.0057187552 0.0366770000 818252049 0 402718720 -0.1442319900 -0.1077206060 0.0031472503 3259 1311867279.0850000381 0.1436839849 0.1773330478 0.3590448499 0.0057231892 0.0365010000 818255361 0 402718720 -0.1456627399 -0.1100250483 0.0065011568 3260 1311867279.1170239449 0.1419305354 0.1773221882 0.3590448499 0.0057243426 0.0349400000 818258449 0 402718720 -0.1443487257 -0.1099368036 0.0083280029 3261 1311867279.1491520405 0.1414281279 0.1773111811 0.3590448499 0.0057283875 0.0378300000 818261649 0 402718720 -0.1427845508 -0.1081856564 0.0099145165 3262 1311867279.1850559711 0.1420940459 0.1773003849 0.3590448499 0.0057285591 0.0372340000 818264905 0 402718720 -0.1440238059 -0.1071487814 0.0127501637 3263 1311867279.2169098854 0.1415379941 0.1772894249 0.3590448499 0.0057302741 0.0428130000 818267993 0 402718720 -0.1455076933 -0.1097286120 0.0160159413 3264 1311867279.2492520809 0.1395940334 0.1772778761 0.3590448499 0.0057295115 0.0365380000 818271193 0 402718720 -0.1434260011 -0.1087642536 0.0173757337 3265 1311867279.2849819660 0.1385508329 0.1772660148 0.3590448499 0.0057286750 0.0417450000 818274393 0 402718720 -0.1419198513 -0.1068657786 0.0194995049 3266 1311867279.3170011044 0.1395287365 0.1772544603 0.3590448499 0.0057285399 0.0433220000 818277537 0 402718720 -0.1438659579 -0.1075847298 0.0224641617 3267 1311867279.3491089344 0.1384059787 0.1772425691 0.3590448499 0.0057278635 0.0366470000 818280681 0 402718720 -0.1434732378 -0.1077401191 0.0245505869 3268 1311867279.3853499889 0.1379459202 0.1772305444 0.3590448499 0.0057283310 0.0367290000 818283881 0 402718720 -0.1425285786 -0.1055557579 0.0264544282 3269 1311867279.4171319008 0.1380769610 0.1772185672 0.3590448499 0.0057280978 0.0382350000 818286969 0 402718720 -0.1431093514 -0.1051965058 0.0294143520 3270 1311867279.4489719868 0.1371019781 0.1772062991 0.3590448499 0.0057338502 0.0344230000 818290113 0 402718720 -0.1436924189 -0.1075157076 0.0325663351 3271 1311867279.4851779938 0.1357254982 0.1771936177 0.3590448499 0.0057362375 0.0383460000 818293425 0 402718720 -0.1424779743 -0.1066059843 0.0337437391 3272 1311867279.5173521042 0.1367483437 0.1771812567 0.3590448499 0.0057369970 0.0401040000 818296513 0 402718720 -0.1429560184 -0.1045323089 0.0364795737 3273 1311867279.5491120815 0.1358136684 0.1771686176 0.3590448499 0.0057363768 0.0358620000 818299601 0 402718720 -0.1435314715 -0.1071338058 0.0395090356 3274 1311867279.5850000381 0.1349263936 0.1771557153 0.3590448499 0.0057361685 0.0352870000 818302857 0 402718720 -0.1434590518 -0.1080804318 0.0415731259 3275 1311867279.6176578999 0.1348526031 0.1771427983 0.3590448499 0.0057357349 0.0441320000 818306057 0 402718720 -0.1425290704 -0.1055480242 0.0428225249 3276 1311867279.6491489410 0.1339834630 0.1771296239 0.3590448499 0.0057355561 0.0388680000 818309145 0 402718720 -0.1425467432 -0.1075182185 0.0455568694 3277 1311867279.6851220131 0.1332368106 0.1771162297 0.3590448499 0.0057356584 0.0365060000 818312401 0 402718720 -0.1423079371 -0.1078281403 0.0472810268 3278 1311867279.7176079750 0.1334897578 0.1771029209 0.3590448499 0.0057350573 0.0416260000 818315545 0 402718720 -0.1418480724 -0.1059510261 0.0490892231 3279 1311867279.7491679192 0.1328935474 0.1770894383 0.3590448499 0.0057342127 0.0391980000 818318689 0 402718720 -0.1413053721 -0.1060782000 0.0515180454 3280 1311867279.7851839066 0.1313922554 0.1770755062 0.3590448499 0.0057342616 0.0379840000 818322001 0 402718720 -0.1408931613 -0.1083718091 0.0540913604 3281 1311867279.8172769547 0.1309116185 0.1770614362 0.3590448499 0.0057337115 0.0424640000 818325089 0 402718720 -0.1395497918 -0.1073408872 0.0558389612 3282 1311867279.8492250443 0.1314678490 0.1770475441 0.3590448499 0.0057329142 0.0395030000 818328233 0 402718720 -0.1391728818 -0.1059753150 0.0580604412 3283 1311867279.8854300976 0.1295855194 0.1770330872 0.3590448499 0.0057335903 0.0386620000 818331433 0 402718720 -0.1384356320 -0.1079595387 0.0608848818 3284 1311867279.9173040390 0.1290344298 0.1770184713 0.3590448499 0.0057327974 0.0420880000 818334633 0 402718720 -0.1379558295 -0.1088551953 0.0631337240 3285 1311867279.9524009228 0.1294624656 0.1770039946 0.3590448499 0.0057323311 0.0411060000 818337833 0 402718720 -0.1363982111 -0.1057361290 0.0643673465 3286 1311867279.9852290154 0.1291309148 0.1769894258 0.3590448499 0.0057327033 0.0402430000 818340977 0 402718720 -0.1365609467 -0.1067647412 0.0676248670 3287 1311867280.0184810162 0.1286325455 0.1769747142 0.3590448499 0.0057333585 0.0428340000 818344121 0 402718720 -0.1362820715 -0.1074494272 0.0701153353 3288 1311867280.0492808819 0.1279114187 0.1769597923 0.3590448499 0.0057325844 0.0424560000 818347209 0 402718720 -0.1337337941 -0.1046106070 0.0712021515 3289 1311867280.0852999687 0.1272384375 0.1769446749 0.3590448499 0.0057319956 0.0406990000 818350465 0 402718720 -0.1337450892 -0.1065429226 0.0746005997 3290 1311867280.1177620888 0.1270535588 0.1769295104 0.3590448499 0.0057320257 0.0398430000 818353665 0 402718720 -0.1337829530 -0.1082069948 0.0773330331 3291 1311867280.1491429806 0.1274521202 0.1769144762 0.3590448499 0.0057313503 0.0413680000 818356809 0 402718720 -0.1328210831 -0.1057699621 0.0785121843 3292 1311867280.1852018833 0.1272826195 0.1768993997 0.3590448499 0.0057314833 0.0412950000 818360009 0 402718720 -0.1322455853 -0.1052420512 0.0808896795 3293 1311867280.2184669971 0.1261119843 0.1768839769 0.3590448499 0.0057335176 0.6812900000 830723785 0 402718720 -0.1323739737 -0.1085212752 0.0840191692 3294 1311867280.2491390705 0.1260726601 0.1768685515 0.3590448499 0.0057334334 0.0591690000 834386137 0 402718720 -0.1313316226 -0.1058275700 0.0838858783 3295 1311867280.2852349281 0.1267570108 0.1768533431 0.3590448499 0.0057338003 0.0423160000 837581529 0 402718720 -0.1317134649 -0.1057901010 0.0869130343 3296 1311867280.3171200752 0.1256840229 0.1768378184 0.3590448499 0.0057335775 0.0366040000 837584673 0 402718720 -0.1315715015 -0.1084597409 0.0895093828 3297 1311867280.3493640423 0.1252220720 0.1768221631 0.3590448499 0.0057332052 0.0396210000 837587817 0 402718720 -0.1293326467 -0.1052565426 0.0901258886 3298 1311867280.3849859238 0.1253027320 0.1768065417 0.3590448499 0.0057336838 0.0391810000 837591017 0 402718720 -0.1300051212 -0.1070067585 0.0934828669 3299 1311867280.4170889854 0.1246216744 0.1767907233 0.3590448499 0.0057330285 0.0386100000 837594161 0 402718720 -0.1295093298 -0.1067992821 0.0952795595 3300 1311867280.4493589401 0.1241241843 0.1767747637 0.3590448499 0.0057331861 0.0379550000 837597361 0 402718720 -0.1280301809 -0.1053913236 0.0968792215 3301 1311867280.4852430820 0.1235202849 0.1767586309 0.3590448499 0.0057338999 0.0358810000 837600617 0 402718720 -0.1277693212 -0.1057995111 0.0991349444 3302 1311867280.5171639919 0.1231597215 0.1767423986 0.3590448499 0.0057330433 0.0352380000 837603705 0 402718720 -0.1278062910 -0.1064535156 0.1016967446 3303 1311867280.5492091179 0.1233145148 0.1767262231 0.3590448499 0.0057322593 0.0415020000 837606905 0 402718720 -0.1274464577 -0.1046002582 0.1033766568 3304 1311867280.5850980282 0.1231698841 0.1767100135 0.3590448499 0.0057319342 0.0399750000 837610049 0 402718720 -0.1276929826 -0.1050212681 0.1058907062 3305 1311867280.6191129684 0.1220113188 0.1766934632 0.3590448499 0.0057318065 0.0370340000 837613305 0 402718720 -0.1273042411 -0.1067110300 0.1084518656 3306 1311867280.6491858959 0.1216488257 0.1766768133 0.3590448499 0.0057314111 0.0437970000 837616337 0 402718720 -0.1266503036 -0.1060187593 0.1098469645 3307 1311867280.6850759983 0.1212125197 0.1766600415 0.3590448499 0.0057309909 0.0366620000 837619593 0 402718720 -0.1261903495 -0.1058576554 0.1116054133 3308 1311867280.7172911167 0.1207976416 0.1766431545 0.3590448499 0.0057303334 0.0363130000 837622737 0 402718720 -0.1260464340 -0.1069144756 0.1138239279 3309 1311867280.7491559982 0.1208829805 0.1766263034 0.3590448499 0.0057305073 0.0351840000 837625881 0 402718720 -0.1258141845 -0.1062454432 0.1152243391 3310 1311867280.7850511074 0.1205052659 0.1766093484 0.3590448499 0.0057305820 0.0334840000 837629193 0 402718720 -0.1255502403 -0.1061344594 0.1169466004 3311 1311867280.8172440529 0.1203115359 0.1765923451 0.3590448499 0.0057298059 0.0346700000 837632281 0 402718720 -0.1255166829 -0.1059796959 0.1187988669 3312 1311867280.8493359089 0.1203804687 0.1765753729 0.3590448499 0.0057289447 0.0376630000 837635425 0 402718720 -0.1256991774 -0.1062059850 0.1210411713 3313 1311867280.8850319386 0.1198135167 0.1765582399 0.3590448499 0.0057281242 0.0360510000 837638737 0 402718720 -0.1253220439 -0.1060963646 0.1227702200 3314 1311867280.9171459675 0.1196374372 0.1765410640 0.3590448499 0.0057273107 0.0364100000 837641825 0 402718720 -0.1252749860 -0.1055846363 0.1248691007 3315 1311867280.9494290352 0.1190693900 0.1765237272 0.3590448499 0.0057265952 0.0384320000 837645025 0 402718720 -0.1247697398 -0.1055588499 0.1267443597 3316 1311867280.9850571156 0.1189723164 0.1765063715 0.3590448499 0.0057257471 0.0353040000 837648169 0 402718720 -0.1247141957 -0.1053384542 0.1289181262 3317 1311867281.0172550678 0.1188481078 0.1764889888 0.3590448499 0.0057249387 0.0367040000 837651313 0 402718720 -0.1249821037 -0.1062697619 0.1314882189 3318 1311867281.0491590500 0.1180064753 0.1764713630 0.3590448499 0.0057242647 0.0386010000 837654457 0 402718720 -0.1239832938 -0.1059298962 0.1329936087 3319 1311867281.0851469040 0.1172050685 0.1764535063 0.3590448499 0.0057234637 0.0391950000 837657713 0 402718720 -0.1230823100 -0.1055475622 0.1344463229 3320 1311867281.1171119213 0.1179788411 0.1764358935 0.3590448499 0.0057226132 0.0356580000 837660857 0 402718720 -0.1235540658 -0.1053303331 0.1369429082 3321 1311867281.1494300365 0.1172539890 0.1764180730 0.3590448499 0.0057225387 0.0381400000 837664057 0 402718720 -0.1231592596 -0.1065439433 0.1391159892 3322 1311867281.1850519180 0.1167938635 0.1764001247 0.3590448499 0.0057229341 0.0390500000 837667313 0 402718720 -0.1214931831 -0.1050306037 0.1399031132 3323 1311867281.2172520161 0.1164441928 0.1763820820 0.3590448499 0.0057226552 0.6437340000 850033521 0 402718720 -0.1210741699 -0.1060626954 0.1423274875 3324 1311867281.2501060963 0.1165906489 0.1763640942 0.3590448499 0.0057219723 0.0305600000 853695873 0 402718720 -0.1209696457 -0.1061454341 0.1442880630 3325 1311867281.2851018906 0.1167717129 0.1763461717 0.3590448499 0.0057216582 0.0362190000 856891265 0 402718720 -0.1204620451 -0.1053762138 0.1455289572 3326 1311867281.3172149658 0.1167242378 0.1763282456 0.3590448499 0.0057208837 0.0374910000 856894409 0 402718720 -0.1196382046 -0.1049586236 0.1474352181 3327 1311867281.3492169380 0.1164394841 0.1763102448 0.3590448499 0.0057201801 0.0427890000 856897609 0 402718720 -0.1196518838 -0.1069189012 0.1506670862 3328 1311867281.3851010799 0.1163372248 0.1762922241 0.3590448499 0.0057193860 0.0355870000 856900865 0 402718720 -0.1185886711 -0.1059123501 0.1514052451 3329 1311867281.4170739651 0.1157983467 0.1762740523 0.3590448499 0.0057185335 0.0357230000 856904009 0 402718720 -0.1173124164 -0.1055199504 0.1529210061 3330 1311867281.4491829872 0.1158531159 0.1762559079 0.3590448499 0.0057182177 0.0341830000 856907153 0 402718720 -0.1179225147 -0.1072320566 0.1560755074 3331 1311867281.4851069450 0.1158629507 0.1762377773 0.3590448499 0.0057175116 0.0340500000 856910409 0 402718720 -0.1173350886 -0.1062346101 0.1571287811 3332 1311867281.5171670914 0.1159128025 0.1762196725 0.3590448499 0.0057171235 0.0320010000 856913553 0 402718720 -0.1165488958 -0.1053450778 0.1584094763 3333 1311867281.5492069721 0.1154783592 0.1762014483 0.3590448499 0.0057170325 0.0332120000 856916697 0 402718720 -0.1167741939 -0.1073448211 0.1614147574 3334 1311867281.5851929188 0.1155167744 0.1761832466 0.3590448499 0.0057162793 0.0354470000 856919897 0 402718720 -0.1160043478 -0.1069898605 0.1624694765 3335 1311867281.6172859669 0.1154075265 0.1761650230 0.3590448499 0.0057155942 0.0351250000 856923097 0 402718720 -0.1152402461 -0.1064252555 0.1639146954 3336 1311867281.6492741108 0.1150914356 0.1761467155 0.3590448499 0.0057147461 0.0382900000 856926241 0 402718720 -0.1149094924 -0.1075643227 0.1662928015 3337 1311867281.6851420403 0.1146176383 0.1761282771 0.3590448499 0.0057144788 0.0388150000 856929553 0 402718720 -0.1141960993 -0.1085111573 0.1674538702 3338 1311867281.7171700001 0.1151432842 0.1761100072 0.3590448499 0.0057137281 0.0366260000 856932585 0 402718720 -0.1133550033 -0.1071424261 0.1677715778 3339 1311867281.7493090630 0.1153030768 0.1760917960 0.3590448499 0.0057129096 0.0370310000 856935785 0 402718720 -0.1133036315 -0.1083485410 0.1703033596 3340 1311867281.7851150036 0.1151276231 0.1760735433 0.3590448499 0.0057123640 0.0362190000 856939041 0 402718720 -0.1124065444 -0.1090829745 0.1714399606 3341 1311867281.8171050549 0.1148822308 0.1760552280 0.3590448499 0.0057118136 0.0369120000 856942129 0 402718720 -0.1109754816 -0.1086264327 0.1718202978 3342 1311867281.8491699696 0.1153809205 0.1760370729 0.3590448499 0.0057109735 0.0344410000 856945273 0 402718720 -0.1106884852 -0.1090257764 0.1733359993 3343 1311867281.8850789070 0.1148902848 0.1760187820 0.3590448499 0.0057101319 0.0342050000 856948529 0 402718720 -0.1094198674 -0.1095915511 0.1742862314 3344 1311867281.9171528816 0.1153466403 0.1760006384 0.3590448499 0.0057095978 0.0354330000 856951673 0 402718720 -0.1083128527 -0.1081408933 0.1743708998 3345 1311867281.9491980076 0.1151315644 0.1759824413 0.3590448499 0.0057097938 0.0341460000 856954817 0 402718720 -0.1079141498 -0.1091105714 0.1763251573 3346 1311867281.9850740433 0.1141044274 0.1759639482 0.3590448499 0.0057107267 0.0346760000 856957961 0 402718720 -0.1063405126 -0.1104657501 0.1775100827 3347 1311867282.0173199177 0.1146328524 0.1759456240 0.3590448499 0.0057099729 0.0356400000 856961161 0 402718720 -0.1051660180 -0.1087621599 0.1774749905 3348 1311867282.0491540432 0.1152118072 0.1759274837 0.3590448499 0.0057091890 0.0359450000 856964305 0 402718720 -0.1050109863 -0.1088997945 0.1792906076 3349 1311867282.0852119923 0.1147089526 0.1759092040 0.3590448499 0.0057151874 0.0362890000 856967561 0 402718720 -0.1042290181 -0.1099810973 0.1811337769 3350 1311867282.1175959110 0.1146799251 0.1758909266 0.3590448499 0.0057156029 0.0382940000 856970705 0 402718720 -0.1028509438 -0.1089531183 0.1815470159 3351 1311867282.1548640728 0.1147565991 0.1758726830 0.3590448499 0.0057176410 0.0376070000 856973961 0 402718720 -0.1020321921 -0.1083367243 0.1829392463 3352 1311867282.1884930134 0.1148614883 0.1758544816 0.3590448499 0.0057169324 0.0375360000 856977217 0 402718720 -0.1019790992 -0.1093998477 0.1853775680 3353 1311867282.2199079990 0.1144499630 0.1758361683 0.3590448499 0.0057161405 0.0373950000 856980305 0 402718720 -0.1008632183 -0.1092188433 0.1863691211 3354 1311867282.2531559467 0.1139086261 0.1758177045 0.3590448499 0.0057153620 0.0382220000 856983449 0 402718720 -0.0994191319 -0.1088864580 0.1873381138 3355 1311867282.2880699635 0.1142342016 0.1757993488 0.3590448499 0.0057150964 0.0386790000 856986593 0 402718720 -0.0993085429 -0.1097345948 0.1892064959 3356 1311867282.3224289417 0.1139461622 0.1757809181 0.3590448499 0.0057148166 0.0389600000 856989793 0 402718720 -0.0982424095 -0.1098603830 0.1902626902 3357 1311867282.3500831127 0.1135107279 0.1757623688 0.3590448499 0.0057140418 0.0392140000 856992769 0 402718720 -0.0970098376 -0.1095446125 0.1911872774 3358 1311867282.3907461166 0.1142187715 0.1757440413 0.3590448499 0.0057139314 0.0386960000 856996025 0 402718720 -0.0970001072 -0.1098321900 0.1928901225 3359 1311867282.4173719883 0.1134887487 0.1757255075 0.3590448499 0.0057137584 0.0395810000 856998945 0 402718720 -0.0960344449 -0.1104391664 0.1941935569 3360 1311867282.4492149353 0.1138093770 0.1757070800 0.3590448499 0.0057129672 0.0389550000 857002145 0 402718720 -0.0954843909 -0.1097889766 0.1950519681 3361 1311867282.4852509499 0.1141729429 0.1756887717 0.3590448499 0.0057123031 0.0396540000 857005401 0 402718720 -0.0955634862 -0.1106102318 0.1967965364 3362 1311867282.5173749924 0.1130300909 0.1756701344 0.3590448499 0.0057115157 0.0407980000 857008489 0 402718720 -0.0941379741 -0.1119490564 0.1984505504 3363 1311867282.5492420197 0.1133561730 0.1756516051 0.3590448499 0.0057107640 0.0401290000 857011633 0 402718720 -0.0933000818 -0.1109014675 0.1986661106 3364 1311867282.5851900578 0.1143495217 0.1756333822 0.3590448499 0.0057101665 0.0389170000 857014889 0 402718720 -0.0942739919 -0.1116684899 0.2003823519 3365 1311867282.6171879768 0.1138537973 0.1756150227 0.3590448499 0.0057096199 0.0399130000 857018033 0 402718720 -0.0937168375 -0.1124435440 0.2015652359 3366 1311867282.6492300034 0.1136790588 0.1755966222 0.3590448499 0.0057088387 0.0395110000 857021177 0 402718720 -0.0927610323 -0.1114744917 0.2013581246 3367 1311867282.6851720810 0.1137628108 0.1755782576 0.3590448499 0.0057088367 0.0385040000 857024433 0 402718720 -0.0932974517 -0.1121951118 0.2028027922 3368 1311867282.7173910141 0.1134912223 0.1755598232 0.3590448499 0.0057081038 0.0397420000 857027521 0 402718720 -0.0932909548 -0.1132943928 0.2037321031 3369 1311867282.7498550415 0.1130459234 0.1755412676 0.3590448499 0.0057074114 0.0403080000 857030721 0 402718720 -0.0928730220 -0.1127912328 0.2037152946 3370 1311867282.7851979733 0.1127264425 0.1755226282 0.3590448499 0.0057076286 0.0380400000 857033865 0 402718720 -0.0929456949 -0.1136088148 0.2046200782 3371 1311867282.8174340725 0.1134414002 0.1755042119 0.3590448499 0.0057074524 0.0397790000 857036897 0 402718720 -0.0940184593 -0.1134077683 0.2054546773 3372 1311867282.8491930962 0.1142420024 0.1754860440 0.3590448499 0.0057066515 0.0390990000 857040041 0 402718720 -0.0948040858 -0.1119961813 0.2055499405 3373 1311867282.8857340813 0.1131416261 0.1754675606 0.3590448499 0.0057061267 0.0377270000 857043297 0 402718720 -0.0945665166 -0.1122786850 0.2069578171 3374 1311867282.9173140526 0.1126661375 0.1754489473 0.3590448499 0.0057053888 0.0397870000 857046441 0 402718720 -0.0947874412 -0.1124506369 0.2083421499 3375 1311867282.9502348900 0.1128334105 0.1754303945 0.3590448499 0.0057050455 0.0386200000 857049697 0 402718720 -0.0952287838 -0.1113906056 0.2092526704 3376 1311867282.9854760170 0.1124273688 0.1754117325 0.3590448499 0.0057043119 0.0383000000 857052897 0 402718720 -0.0955057517 -0.1112512425 0.2105700225 3377 1311867283.0175549984 0.1112288162 0.1753927266 0.3590448499 0.0057036398 0.0385670000 857055985 0 402718720 -0.0955630988 -0.1125252619 0.2122725695 3378 1311867283.0493919849 0.1109602004 0.1753736524 0.3590448499 0.0057037269 0.0374660000 857059129 0 402718720 -0.0958826691 -0.1123032048 0.2130517066 3379 1311867283.0852580070 0.1112141684 0.1753546647 0.3590448499 0.0057029993 0.0387440000 857062385 0 402718720 -0.0959617943 -0.1109914109 0.2130155861 3380 1311867283.1174409389 0.1106031537 0.1753355074 0.3590448499 0.0057050730 0.0393460000 857065529 0 402718720 -0.0964468345 -0.1128526255 0.2148408294 3381 1311867283.1495320797 0.1111692190 0.1753165290 0.3590448499 0.0057068552 0.0379580000 857068673 0 402718720 -0.0966391191 -0.1129470468 0.2153406143 3382 1311867283.1854090691 0.1112505943 0.1752975857 0.3590448499 0.0057069279 0.0474900000 857071873 0 402718720 -0.0960540026 -0.1116020232 0.2148916423 3383 1311867283.2172861099 0.1111296713 0.1752786180 0.3590448499 0.0057061247 0.0471770000 857075017 0 402718720 -0.0966880843 -0.1134747788 0.2167138010 3384 1311867283.2493569851 0.1108227745 0.1752595708 0.3590448499 0.0057057960 0.0471680000 857078161 0 402718720 -0.0962324739 -0.1141675189 0.2174049765 3385 1311867283.2853751183 0.1106133461 0.1752404729 0.3590448499 0.0057053691 0.0497750000 857081473 0 402718720 -0.0953698307 -0.1131031364 0.2172617912 3386 1311867283.3176229000 0.1103173569 0.1752212989 0.3590448499 0.0057050967 0.0486410000 857084561 0 402718720 -0.0951375440 -0.1138572097 0.2184417993 3387 1311867283.3497960567 0.1101865247 0.1752020976 0.3590448499 0.0057043848 0.0469620000 857087705 0 402718720 -0.0953072309 -0.1144001186 0.2194758803 3388 1311867283.3852219582 0.1108687669 0.1751831090 0.3590448499 0.0057037501 0.0472220000 857091017 0 402718720 -0.0953656286 -0.1139300987 0.2198730558 3389 1311867283.4173080921 0.1105968505 0.1751640514 0.3590448499 0.0057030043 0.0479890000 857094105 0 402718720 -0.0946551338 -0.1136042252 0.2201012373 3390 1311867283.4492650032 0.1102857664 0.1751449133 0.3590448499 0.0057021938 0.0486910000 857097249 0 402718720 -0.0945661291 -0.1144384518 0.2213397622 3391 1311867283.4853370190 0.1100084111 0.1751257046 0.3590448499 0.0057014846 0.0490390000 857100505 0 402718720 -0.0943657085 -0.1153937578 0.2219393700 3392 1311867283.5172159672 0.1103307977 0.1751066024 0.3590448499 0.0057006562 0.0493570000 857103649 0 402718720 -0.0937373191 -0.1142962128 0.2214500010 3393 1311867283.5495610237 0.1105907857 0.1750875880 0.3590448499 0.0056998179 0.0482180000 857106793 0 402718720 -0.0940941274 -0.1150481850 0.2226867974 3394 1311867283.5853879452 0.1109593734 0.1750686934 0.3590448499 0.0056989963 0.0500910000 857109993 0 402718720 -0.0942064002 -0.1150745973 0.2230782211 3395 1311867283.6173179150 0.1112928912 0.1750499082 0.3590448499 0.0056981842 0.0493370000 857113137 0 402718720 -0.0940030664 -0.1139887571 0.2225919366 3396 1311867283.6493821144 0.1107852980 0.1750309846 0.3590448499 0.0056975092 0.0470130000 857116337 0 402718720 -0.0936653167 -0.1140575558 0.2233168930 3397 1311867283.6852879524 0.1103687212 0.1750119495 0.3590448499 0.0056969954 0.0462760000 857119593 0 402718720 -0.0932869092 -0.1139410883 0.2238450199 3398 1311867283.7179150581 0.1104356945 0.1749929453 0.3590448499 0.0056962343 0.0484960000 857122681 0 402718720 -0.0932285562 -0.1129148901 0.2238548100 3399 1311867283.7492079735 0.1107632071 0.1749740486 0.3590448499 0.0056955859 0.0482040000 857125825 0 402718720 -0.0941031948 -0.1127859652 0.2250496000 3400 1311867283.7853169441 0.1102333143 0.1749550072 0.3590448499 0.0056947676 0.0446350000 857129081 0 402718720 -0.0944955721 -0.1132871658 0.2260692120 3401 1311867283.8174130917 0.1096372604 0.1749358018 0.3590448499 0.0056939363 0.0381740000 857132169 0 402718720 -0.0939928293 -0.1123794764 0.2257895321 3402 1311867283.8494520187 0.1099393517 0.1749166964 0.3590448499 0.0056932012 0.0387160000 857135369 0 402718720 -0.0946906433 -0.1117614210 0.2262650579 3403 1311867283.8853459358 0.1096882746 0.1748975285 0.3590448499 0.0056923971 0.6029220000 869707861 0 402718720 -0.0955542326 -0.1125382781 0.2274222970 3404 1311867283.9175400734 0.1101509556 0.1748785077 0.3590448499 0.0056916815 0.0309260000 873370213 0 402718720 -0.0962126851 -0.1116676703 0.2278288305 3405 1311867283.9498898983 0.1098336130 0.1748594050 0.3590448499 0.0056908737 0.0298190000 876565549 0 402718720 -0.0963775739 -0.1116153970 0.2279074639 3406 1311867283.9856629372 0.1096614897 0.1748402629 0.3590448499 0.0056900907 0.0423840000 876568861 0 402718720 -0.0969966426 -0.1120899767 0.2288987339 3407 1311867284.0172998905 0.1096911654 0.1748211408 0.3590448499 0.0056892729 0.0425130000 876571949 0 402718720 -0.0975768194 -0.1123845205 0.2290695310 3408 1311867284.0497789383 0.1098559797 0.1748020782 0.3590448499 0.0056886790 0.0460830000 876575149 0 402718720 -0.0979054719 -0.1111823022 0.2281087488 3409 1311867284.0853729248 0.1092312634 0.1747828436 0.3590448499 0.0056879342 0.0419130000 876578349 0 402718720 -0.0984953791 -0.1117916703 0.2287233472 3410 1311867284.1175038815 0.1082798913 0.1747633413 0.3590448499 0.0056875100 0.0384400000 876581493 0 402718720 -0.0984161049 -0.1123768389 0.2289327979 3411 1311867284.1494109631 0.1079677641 0.1747437589 0.3590448499 0.0056867387 0.0371420000 876584637 0 402718720 -0.0985380560 -0.1118632033 0.2282741368 3412 1311867284.1874890327 0.1085028052 0.1747243448 0.3590448499 0.0056859429 0.0382900000 876587949 0 402718720 -0.0995613933 -0.1111232787 0.2298502773 3413 1311867284.2173368931 0.1081169248 0.1747048290 0.3590448499 0.0056851295 0.0363040000 876591037 0 402718720 -0.0995294750 -0.1110565960 0.2298698872 3414 1311867284.2494308949 0.1078523323 0.1746852471 0.3590448499 0.0056843109 0.0375630000 876594181 0 402718720 -0.0992274508 -0.1103017926 0.2297380418 3415 1311867284.2853159904 0.1078650430 0.1746656804 0.3590448499 0.0056835040 0.0391710000 876597381 0 402718720 -0.0997751206 -0.1105388030 0.2305818945 3416 1311867284.3178350925 0.1079095975 0.1746461382 0.3590448499 0.0056827085 0.0384710000 876600581 0 402718720 -0.0996263921 -0.1098791435 0.2303775996 3417 1311867284.3494238853 0.1084120423 0.1746267545 0.3590448499 0.0056820589 0.0446500000 876603725 0 402718720 -0.0991393402 -0.1075730994 0.2306904644 3418 1311867284.3854329586 0.1080195308 0.1746072674 0.3590448499 0.0056813502 0.0409380000 876606981 0 402718720 -0.0993318409 -0.1084594354 0.2314788103 3419 1311867284.4175798893 0.1076675206 0.1745876886 0.3590448499 0.0056805697 0.0417280000 876610125 0 402718720 -0.0984510258 -0.1077928394 0.2316084504 3420 1311867284.4495139122 0.1082758233 0.1745682992 0.3590448499 0.0056798687 0.0413160000 876613269 0 402718720 -0.0986001194 -0.1071678847 0.2322519273 3421 1311867284.4854190350 0.1082189530 0.1745489044 0.3590448499 0.0056792080 0.0380410000 876616469 0 402718720 -0.0985783339 -0.1077649668 0.2326087505 3422 1311867284.5177299976 0.1084353030 0.1745295843 0.3590448499 0.0056784188 0.0381730000 876619669 0 402718720 -0.0982359499 -0.1074945107 0.2328545749 3423 1311867284.5494539738 0.1086685136 0.1745103435 0.3590448499 0.0056778948 0.0380710000 876622813 0 402718720 -0.0977087244 -0.1066995487 0.2330571115 3424 1311867284.5854179859 0.1083419099 0.1744910186 0.3590448499 0.0056770873 0.0377090000 876626013 0 402718720 -0.0970867351 -0.1072959229 0.2334808260 3425 1311867284.6174941063 0.1085809693 0.1744717748 0.3590448499 0.0056762649 0.0379160000 876629157 0 402718720 -0.0968604758 -0.1071901917 0.2338286042 3426 1311867284.6495230198 0.1089123935 0.1744526390 0.3590448499 0.0056757843 0.0394430000 876632357 0 402718720 -0.0964261070 -0.1060890853 0.2339787930 3427 1311867284.6853780746 0.1081116945 0.1744332807 0.3590448499 0.0056752995 0.0389720000 876635557 0 402718720 -0.0955225751 -0.1067396477 0.2343270183 3428 1311867284.7174859047 0.1080779508 0.1744139238 0.3590448499 0.0056745891 0.0393920000 876638701 0 402718720 -0.0953219011 -0.1070292145 0.2348072529 3429 1311867284.7497510910 0.1087469831 0.1743947734 0.3590448499 0.0056748385 0.0396980000 876641845 0 402718720 -0.0950946882 -0.1053663865 0.2348180413 3430 1311867284.7854089737 0.1086080372 0.1743755935 0.3590448499 0.0056740191 0.0386880000 876645101 0 402718720 -0.0951688215 -0.1057578251 0.2355073094 3431 1311867284.8186919689 0.1079656929 0.1743562377 0.3590448499 0.0056736001 0.0386520000 876648301 0 402718720 -0.0945502743 -0.1062259078 0.2357344925 3432 1311867284.8492770195 0.1081411541 0.1743369443 0.3590448499 0.0056732970 0.0385410000 876651389 0 402718720 -0.0936316624 -0.1043410301 0.2355249524 3433 1311867284.8853850365 0.1081717983 0.1743176710 0.3590448499 0.0056725144 0.0378480000 876654589 0 402718720 -0.0942977220 -0.1054346338 0.2363889664 3434 1311867284.9174609184 0.1082560420 0.1742984335 0.3590448499 0.0056717258 0.0372520000 876657789 0 402718720 -0.0942668766 -0.1053202078 0.2361746430 3435 1311867284.9492468834 0.1081229448 0.1742791684 0.3590448499 0.0056709299 0.0364460000 876660933 0 402718720 -0.0939035118 -0.1048953384 0.2359788120 3436 1311867284.9852581024 0.1080928445 0.1742599058 0.3590448499 0.0056702743 0.0379580000 876664245 0 402718720 -0.0943559781 -0.1058784947 0.2362068146 3437 1311867285.0175390244 0.1082845777 0.1742407102 0.3590448499 0.0056697859 0.0392290000 876667333 0 402718720 -0.0947230682 -0.1064310744 0.2359683067 3438 1311867285.0493679047 0.1086611748 0.1742216353 0.3590448499 0.0056690141 0.0388950000 876670477 0 402718720 -0.0946477428 -0.1056746468 0.2353433669 3439 1311867285.0853259563 0.1086639762 0.1742025723 0.3590448499 0.0056682085 0.0385430000 876673733 0 402718720 -0.0952531919 -0.1066329852 0.2350300997 3440 1311867285.1177120209 0.1083868146 0.1741834398 0.3590448499 0.0056674810 0.0382160000 876676877 0 402718720 -0.0957310647 -0.1083293036 0.2346153408 3441 1311867285.1502120495 0.1086890846 0.1741644063 0.3590448499 0.0056670117 0.0385060000 876680021 0 402718720 -0.0957537591 -0.1075934917 0.2335855961 3442 1311867285.1855800152 0.1083787158 0.1741452936 0.3590448499 0.0056662160 0.0372530000 876683221 0 402718720 -0.0958941206 -0.1083342358 0.2331587672 3443 1311867285.2187609673 0.1084814519 0.1741262219 0.3590448499 0.0056654124 0.0385540000 876686477 0 402718720 -0.0965082273 -0.1093563512 0.2327006608 3444 1311867285.2493660450 0.1083824188 0.1741071326 0.3590448499 0.0056646078 0.0377870000 876689565 0 402718720 -0.0962281898 -0.1093856618 0.2315724343 3445 1311867285.2853620052 0.1086982638 0.1740881460 0.3590448499 0.0056639621 0.0366310000 876692821 0 402718720 -0.0964928120 -0.1092335954 0.2309059948 3446 1311867285.3175029755 0.1082425341 0.1740690381 0.3590448499 0.0056633420 0.0363200000 876695965 0 402718720 -0.0965816304 -0.1104381233 0.2306779772 3447 1311867285.3493449688 0.1088167652 0.1740501080 0.3590448499 0.0056626819 0.0355500000 876699109 0 402718720 -0.0968983248 -0.1096277535 0.2298432738 3448 1311867285.3855409622 0.1086826399 0.1740311499 0.3590448499 0.0056620143 0.0381890000 876702421 0 402718720 -0.0971874073 -0.1097593606 0.2291548997 3449 1311867285.4175810814 0.1083052605 0.1740120934 0.3590448499 0.0056614180 0.0376650000 876705509 0 402718720 -0.0974102318 -0.1103936285 0.2298101187 3450 1311867285.4492840767 0.1083732173 0.1739930676 0.3590448499 0.0056606207 0.0360480000 876708653 0 402718720 -0.0973068327 -0.1097895503 0.2294561416 3451 1311867285.4853799343 0.1086070165 0.1739741206 0.3590448499 0.0056600630 0.0377880000 876711853 0 402718720 -0.0977415666 -0.1093215346 0.2294726372 3452 1311867285.5176479816 0.1081999764 0.1739550667 0.3590448499 0.0056594598 0.0382530000 876715053 0 402718720 -0.0979505479 -0.1097396985 0.2308324128 3453 1311867285.5494511127 0.1078573689 0.1739359246 0.3590448499 0.0056588422 0.0371530000 876718141 0 402718720 -0.0975124612 -0.1089290455 0.2307264358 3454 1311867285.5855739117 0.1079870239 0.1739168311 0.3590448499 0.0056582599 0.0382230000 876721453 0 402718720 -0.0977403075 -0.1082812920 0.2309627682 3455 1311867285.6175510883 0.1077183336 0.1738976709 0.3590448499 0.0056576339 0.0376310000 876724597 0 402718720 -0.0981228724 -0.1087579727 0.2322730869 3456 1311867285.6494030952 0.1083405167 0.1738787018 0.3590448499 0.0056568674 0.0380250000 876727741 0 402718720 -0.0985667184 -0.1076639965 0.2323372662 3457 1311867285.6856529713 0.1078189239 0.1738595928 0.3590448499 0.0056561440 0.0381260000 876730997 0 402718720 -0.0983963311 -0.1076128557 0.2325761914 3458 1311867285.7177190781 0.1073063090 0.1738403466 0.3590448499 0.0056557247 0.0376750000 876734141 0 402718720 -0.0987043977 -0.1085333899 0.2335366160 3459 1311867285.7497079372 0.1078694984 0.1738212744 0.3590448499 0.0056551932 0.0382150000 876737229 0 402718720 -0.0990114138 -0.1073269770 0.2335012555 3460 1311867285.7854781151 0.1072005779 0.1738020199 0.3590448499 0.0056544266 0.0372860000 876740597 0 402718720 -0.0990611091 -0.1079966277 0.2337441295 3461 1311867285.8179709911 0.1072957888 0.1737828040 0.3590448499 0.0056536370 0.0385130000 876743685 0 402718720 -0.0997601449 -0.1087039858 0.2342004627 3462 1311867285.8496279716 0.1076094881 0.1737636898 0.3590448499 0.0056530445 0.0378280000 876746829 0 402718720 -0.1002487615 -0.1081862152 0.2339269221 3463 1311867285.8852860928 0.1071579605 0.1737444563 0.3590448499 0.0056522657 0.0373220000 876750141 0 402718720 -0.1003681347 -0.1089624912 0.2339361161 3464 1311867285.9187369347 0.1066966131 0.1737251006 0.3590448499 0.0056517067 0.0393390000 876753285 0 402718720 -0.1007099077 -0.1103500500 0.2348507941 3465 1311867285.9495129585 0.1074655280 0.1737059781 0.3590448499 0.0056514161 0.0389250000 876756317 0 402718720 -0.1010481194 -0.1092580110 0.2336515039 3466 1311867285.9858360291 0.1072745323 0.1736868115 0.3590448499 0.0056506496 0.0359640000 876759629 0 402718720 -0.1016003266 -0.1099992394 0.2338102609 3467 1311867286.0184559822 0.1070129275 0.1736675805 0.3590448499 0.0056500132 0.0375470000 876762717 0 402718720 -0.1018002182 -0.1108257100 0.2343406081 3468 1311867286.0494220257 0.1072599739 0.1736484318 0.3590448499 0.0056493710 0.0355030000 876765917 0 402718720 -0.1017595753 -0.1098685637 0.2339724153 3469 1311867286.0854020119 0.1072354093 0.1736292871 0.3590448499 0.0056499786 0.0372500000 876769117 0 402718720 -0.1020721048 -0.1100387797 0.2344191074 3470 1311867286.1240980625 0.1068071648 0.1736100300 0.3590448499 0.0056505857 0.0376460000 876772373 0 402718720 -0.1020366699 -0.1105098277 0.2349832952 3471 1311867286.1506319046 0.1071488932 0.1735908825 0.3590448499 0.0056506419 0.0373290000 876775349 0 402718720 -0.1021938920 -0.1098416895 0.2346475422 3472 1311867286.1857590675 0.1070368439 0.1735717137 0.3590448499 0.0056498307 0.0379610000 876778549 0 402718720 -0.1021473110 -0.1093641892 0.2352517843 3473 1311867286.2179830074 0.1069115847 0.1735525199 0.3590448499 0.0056496121 0.0377910000 876781693 0 402718720 -0.1023677513 -0.1095448807 0.2360194623 3474 1311867286.2525210381 0.1068191528 0.1735333105 0.3590448499 0.0056488355 0.0366380000 876784837 0 402718720 -0.1022368968 -0.1086878181 0.2360165417 3475 1311867286.2861630917 0.1066481769 0.1735140630 0.3590448499 0.0056480563 0.0378030000 876787981 0 402718720 -0.1022619456 -0.1083902791 0.2362308353 3476 1311867286.3203489780 0.1067443416 0.1734948542 0.3590448499 0.0056472987 0.0377150000 876791069 0 402718720 -0.1029849499 -0.1089042351 0.2370311469 3477 1311867286.3523778915 0.1067368537 0.1734756543 0.3590448499 0.0056466184 0.0388220000 876794213 0 402718720 -0.1029113308 -0.1082907543 0.2373504043 3478 1311867286.3855628967 0.1069712862 0.1734565329 0.3590448499 0.0056458573 0.0379430000 876797413 0 402718720 -0.1029322743 -0.1075040996 0.2371483445 3479 1311867286.4177770615 0.1080559790 0.1734377342 0.3590448499 0.0056450889 0.0399740000 876800613 0 402718720 -0.1043518111 -0.1075589284 0.2377844751 3480 1311867286.4494199753 0.1074332818 0.1734187674 0.3590448499 0.0056447827 0.0398430000 876803757 0 402718720 -0.1039504036 -0.1077662632 0.2380804718 3481 1311867286.4855709076 0.1064683348 0.1733995343 0.3590448499 0.0056446321 0.0380530000 876806957 0 402718720 -0.1025875285 -0.1073986590 0.2371344864 3482 1311867286.5190219879 0.1064842418 0.1733803168 0.3590448499 0.0056438311 0.0375890000 876810157 0 402718720 -0.1024313718 -0.1074745208 0.2370921969 3483 1311867286.5511989594 0.1064381227 0.1733610971 0.3590448499 0.0056430395 0.0390790000 876813245 0 402718720 -0.1023367271 -0.1078456864 0.2378904372 3484 1311867286.5855200291 0.1068785861 0.1733420149 0.3590448499 0.0056424994 0.0383540000 876816613 0 402718720 -0.1018958688 -0.1070133299 0.2371886522 3485 1311867286.6190729141 0.1070046648 0.1733229798 0.3590448499 0.0056417060 0.0375380000 876819701 0 402718720 -0.1018758640 -0.1072637439 0.2369642407 3486 1311867286.6499910355 0.1067223251 0.1733038746 0.3590448499 0.0056410741 0.0381610000 876822789 0 402718720 -0.1019642130 -0.1085180491 0.2379532307 3487 1311867286.6856429577 0.1061519086 0.1732846168 0.3590448499 0.0056403542 0.0400230000 876826045 0 402718720 -0.1008441970 -0.1084549874 0.2380525768 3488 1311867286.7176160812 0.1065039188 0.1732654710 0.3590448499 0.0056396102 0.0371680000 876829189 0 402718720 -0.1005311683 -0.1080604121 0.2368681133 3489 1311867286.7495489120 0.1066743657 0.1732463849 0.3590448499 0.0056394216 0.0370280000 876832389 0 402718720 -0.1006046236 -0.1086555123 0.2370701879 3490 1311867286.7856459618 0.1067788377 0.1732273398 0.3590448499 0.0056395438 0.0369010000 876835589 0 402718720 -0.1002688780 -0.1089002192 0.2370183766 3491 1311867286.8176259995 0.1069996879 0.1732083688 0.3590448499 0.0056388381 0.0370160000 876838789 0 402718720 -0.0997887701 -0.1087407321 0.2362748682 3492 1311867286.8535819054 0.1077617481 0.1731896270 0.3590448499 0.0056381438 0.0372080000 876842045 0 402718720 -0.1003767252 -0.1087816358 0.2373780757 3493 1311867286.8868150711 0.1080851555 0.1731709884 0.3590448499 0.0056373698 0.0400780000 876845189 0 402718720 -0.1006104276 -0.1088309735 0.2384494245 3494 1311867286.9174380302 0.1077217534 0.1731522565 0.3590448499 0.0056365891 0.0381680000 876848277 0 402718720 -0.0994713530 -0.1077020019 0.2375966907 3495 1311867286.9543609619 0.1074766740 0.1731334652 0.3590448499 0.0056358772 0.0410330000 876851589 0 402718720 -0.0986488461 -0.1065556481 0.2376378179 3496 1311867286.9854118824 0.1071780995 0.1731145993 0.3590448499 0.0056354689 0.0373400000 876854677 0 402718720 -0.0992882252 -0.1082352847 0.2383585125 3497 1311867287.0174310207 0.1069522128 0.1730956795 0.3590448499 0.0056347158 0.0371640000 876857821 0 402718720 -0.0987896174 -0.1079254448 0.2380793393 3498 1311867287.0547020435 0.1076853573 0.1730769802 0.3590448499 0.0056362260 0.0377580000 876861133 0 402718720 -0.0988624245 -0.1069274321 0.2371237129 3499 1311867287.0856859684 0.1082564220 0.1730584547 0.3590448499 0.0056357877 0.0401000000 876864277 0 402718720 -0.0990778953 -0.1059729010 0.2380370200 3500 1311867287.1178169250 0.1070720851 0.1730396014 0.3590448499 0.0056355090 0.0368210000 876867309 0 402718720 -0.0981647521 -0.1071100384 0.2379452735 3501 1311867287.1537048817 0.1072810963 0.1730208187 0.3590448499 0.0056347788 0.0374550000 876870621 0 402718720 -0.0978339016 -0.1062397882 0.2371661216 3502 1311867287.1874449253 0.1072754040 0.1730020450 0.3590448499 0.0056342608 0.0373030000 876873821 0 402718720 -0.0977116376 -0.1063994542 0.2374290377 3503 1311867287.2175579071 0.1066759974 0.1729831109 0.3590448499 0.0056344028 0.0378240000 876876909 0 402718720 -0.0972946882 -0.1072456539 0.2374279946 3504 1311867287.2536680698 0.1072986796 0.1729643654 0.3590448499 0.0056337985 0.0376320000 876880165 0 402718720 -0.0976344272 -0.1065823957 0.2371278107 3505 1311867287.2870109081 0.1076584831 0.1729457332 0.3590448499 0.0056331331 0.0373990000 876883309 0 402718720 -0.0978799537 -0.1066266745 0.2372295260 3506 1311867287.3175630569 0.1074449942 0.1729270507 0.3590448499 0.0056327966 0.0377010000 876886453 0 402718720 -0.0980226099 -0.1075570360 0.2376619577 3507 1311867287.3540940285 0.1074748784 0.1729083874 0.3590448499 0.0056321061 0.0377490000 876889765 0 402718720 -0.0977511257 -0.1068711132 0.2369973212 3508 1311867287.3855419159 0.1075586155 0.1728897586 0.3590448499 0.0056313646 0.0373440000 876892853 0 402718720 -0.0977550298 -0.1068371907 0.2367278188 3509 1311867287.4175760746 0.1075874344 0.1728711487 0.3590448499 0.0056305649 0.0370460000 876895997 0 402718720 -0.0980211794 -0.1076518893 0.2370452732 3510 1311867287.4535288811 0.1074320078 0.1728525050 0.3590448499 0.0056298003 0.0384360000 876899253 0 402718720 -0.0974945128 -0.1073723212 0.2365923673 3511 1311867287.4867200851 0.1078854278 0.1728340012 0.3590448499 0.0056322385 0.0374910000 876902341 0 402718720 -0.0976510048 -0.1071098149 0.2360913008 3512 1311867287.5174999237 0.1076521948 0.1728154414 0.3590448499 0.0056352368 0.0369900000 876905541 0 402718720 -0.0974669904 -0.1076368988 0.2361183912 3513 1311867287.5534870625 0.1079511121 0.1727969773 0.3590448499 0.0056344632 0.0377200000 876908797 0 402718720 -0.0975753069 -0.1072202697 0.2359688133 3514 1311867287.5868539810 0.1080871671 0.1727785625 0.3590448499 0.0056336772 0.0376550000 876911885 0 402718720 -0.0979513004 -0.1075305715 0.2364427149 3515 1311867287.6176569462 0.1068805084 0.1727598148 0.3590448499 0.0056332889 0.0380280000 876915085 0 402718720 -0.0969627202 -0.1078975648 0.2367303818 3516 1311867287.6539158821 0.1067488119 0.1727410404 0.3590448499 0.0056325436 0.0384270000 876918397 0 402718720 -0.0968448222 -0.1075934097 0.2359402478 3517 1311867287.6875660419 0.1072980240 0.1727224327 0.3590448499 0.0056326897 0.0380780000 876921541 0 402718720 -0.0976962969 -0.1067542359 0.2357734740 3518 1311867287.7176280022 0.1072322726 0.1727038170 0.3590448499 0.0056320474 0.0374150000 876924629 0 402718720 -0.0978391171 -0.1068858877 0.2362579554 3519 1311867287.7553908825 0.1071294844 0.1726851826 0.3590448499 0.0056317306 0.0383960000 876927941 0 402718720 -0.0977817476 -0.1068364903 0.2362937629 3520 1311867287.7872428894 0.1073369533 0.1726666178 0.3590448499 0.0056312760 0.0379880000 876931029 0 402718720 -0.0975523368 -0.1061169729 0.2356678843 3521 1311867287.8260099888 0.1075873673 0.1726481346 0.3590448499 0.0056304835 0.0378240000 876934341 0 402718720 -0.0973995104 -0.1058336347 0.2363524139 3522 1311867287.8536510468 0.1073169932 0.1726295852 0.3590448499 0.0056298952 0.0379280000 876937373 0 402718720 -0.0970714390 -0.1067419574 0.2372987568 3523 1311867287.8931109905 0.1078357697 0.1726111935 0.3590448499 0.0056292907 0.0381690000 876940629 0 402718720 -0.0963629261 -0.1056434661 0.2366921902 3524 1311867287.9175710678 0.1083880439 0.1725929690 0.3590448499 0.0056292532 0.0404030000 876943549 0 402718720 -0.0955114290 -0.1042194366 0.2373303324 3525 1311867287.9535610676 0.1075559407 0.1725745188 0.3590448499 0.0056347028 0.0385300000 876946749 0 402718720 -0.0953716040 -0.1072120816 0.2382481694 3526 1311867287.9868390560 0.1072532386 0.1725559932 0.3590448499 0.0056346139 0.0393490000 876949837 0 402718720 -0.0941349044 -0.1075826287 0.2376705557 3527 1311867288.0178821087 0.1082389504 0.1725377576 0.3590448499 0.0056354369 0.0382590000 876953037 0 402718720 -0.0936952233 -0.1066393703 0.2363951206 3528 1311867288.0536389351 0.1078806370 0.1725194307 0.3590448499 0.0056362000 0.0380730000 876956293 0 402718720 -0.0933937207 -0.1079744771 0.2372866720 3529 1311867288.0854179859 0.1086977422 0.1725013458 0.3590448499 0.0056355816 0.0387600000 876959381 0 402718720 -0.0940480232 -0.1085411385 0.2379032373 3530 1311867288.1175940037 0.1088469252 0.1724833134 0.3590448499 0.0056348508 0.0370570000 876962581 0 402718720 -0.0932266191 -0.1077972874 0.2367444485 3531 1311867288.1540820599 0.1082376465 0.1724651186 0.3590448499 0.0056352027 0.0377380000 876965837 0 402718720 -0.0929740891 -0.1096123755 0.2373745739 3532 1311867288.1854550838 0.1085496768 0.1724470225 0.3590448499 0.0056346271 0.0380230000 876968981 0 402718720 -0.0933383331 -0.1101650670 0.2373522371 3533 1311867288.2175340652 0.1091608778 0.1724291097 0.3590448499 0.0056342402 0.0372410000 876972013 0 402718720 -0.0932387263 -0.1086672992 0.2358652502 3534 1311867288.2535810471 0.1090368629 0.1724111718 0.3590448499 0.0056336078 0.0374420000 876975325 0 402718720 -0.0937967375 -0.1092401519 0.2358635813 3535 1311867288.2854719162 0.1084992290 0.1723930921 0.3590448499 0.0056331719 0.0380190000 876978413 0 402718720 -0.0940511152 -0.1108838543 0.2362309247 3536 1311867288.3175830841 0.1088769808 0.1723751294 0.3590448499 0.0056328664 0.0368650000 876981613 0 402718720 -0.0943028927 -0.1094929650 0.2353962362 3537 1311867288.3535211086 0.1087124497 0.1723571303 0.3590448499 0.0056321643 0.0370240000 876984869 0 402718720 -0.0947175249 -0.1098081917 0.2352826446 3538 1311867288.3858830929 0.1082702130 0.1723390164 0.3590448499 0.0056316990 0.0379400000 876987957 0 402718720 -0.0951848403 -0.1107058823 0.2358936071 3539 1311867288.4177610874 0.1085698977 0.1723209975 0.3590448499 0.0056310930 0.0353190000 876991157 0 402718720 -0.0956132561 -0.1096179932 0.2354347557 3540 1311867288.4560189247 0.1081128642 0.1723028596 0.3590448499 0.0056304641 0.0371860000 876994413 0 402718720 -0.0960986316 -0.1095605195 0.2353239208 3541 1311867288.4854650497 0.1075763404 0.1722845804 0.3590448499 0.0056298167 0.0377260000 876997613 0 402718720 -0.0965018421 -0.1101014912 0.2360070497 3542 1311867288.5176889896 0.1072757319 0.1722662267 0.3590448499 0.0056290657 0.0349190000 877000701 0 402718720 -0.0968299881 -0.1098251566 0.2356495708 3543 1311867288.5544719696 0.1075132191 0.1722479504 0.3590448499 0.0056284492 0.0369360000 877003901 0 402718720 -0.0977207869 -0.1095484793 0.2356312722 3544 1311867288.5866000652 0.1074947789 0.1722296792 0.3590448499 0.0056277140 0.0374350000 877007045 0 402718720 -0.0985752419 -0.1097788066 0.2361330837 3545 1311867288.6175410748 0.1070190519 0.1722112841 0.3590448499 0.0056269258 0.0351350000 877010189 0 402718720 -0.0984824598 -0.1096043289 0.2357071787 3546 1311867288.6551020145 0.1070142984 0.1721928980 0.3590448499 0.0056262554 0.0374480000 877013445 0 402718720 -0.0988854840 -0.1090334654 0.2350908369 3547 1311867288.6873788834 0.1071952134 0.1721745733 0.3590448499 0.0056255040 0.0377170000 877016589 0 402718720 -0.0998885110 -0.1092015728 0.2356611192 3548 1311867288.7177019119 0.1071472391 0.1721562454 0.3590448499 0.0056247717 0.0355670000 877019677 0 402718720 -0.1002029777 -0.1088802889 0.2353174537 3549 1311867288.7560219765 0.1067095175 0.1721378045 0.3590448499 0.0056240443 0.0372790000 877022989 0 402718720 -0.0999658406 -0.1087283269 0.2346259654 3550 1311867288.7855091095 0.1065910235 0.1721193407 0.3590448499 0.0056233225 0.0375320000 877026133 0 402718720 -0.1001850665 -0.1091722697 0.2350673676 3551 1311867288.8192229271 0.1069271266 0.1721009818 0.3590448499 0.0056226254 0.0371740000 877029333 0 402718720 -0.1003693044 -0.1086725891 0.2342639267 3552 1311867288.8543310165 0.1073153540 0.1720827426 0.3590448499 0.0056219728 0.0376190000 877032533 0 402718720 -0.1006438509 -0.1084424406 0.2338966876 3553 1311867288.8855559826 0.1071011648 0.1720644534 0.3590448499 0.0056212223 0.0376690000 877035733 0 402718720 -0.1004475355 -0.1084900051 0.2339734286 3554 1311867288.9176120758 0.1070504263 0.1720461602 0.3590448499 0.0056204381 0.0378130000 877038821 0 402718720 -0.1001070961 -0.1083022282 0.2336918116 3555 1311867288.9549388885 0.1075375751 0.1720280143 0.3590448499 0.0056197822 0.0386850000 877042077 0 402718720 -0.1003732458 -0.1079460680 0.2334868908 3556 1311867288.9855918884 0.1080025062 0.1720100094 0.3590448499 0.0056190238 0.0377160000 877045277 0 402718720 -0.1008659974 -0.1080493629 0.2339471877 3557 1311867289.0176560879 0.1075650528 0.1719918916 0.3590448499 0.0056183425 0.0369610000 877048365 0 402718720 -0.1001883149 -0.1081857458 0.2339088023 3558 1311867289.0535120964 0.1069219932 0.1719736033 0.3590448499 0.0056185490 0.0382980000 877051677 0 402718720 -0.0993408337 -0.1085166782 0.2337710857 3559 1311867289.0855109692 0.1077385843 0.1719555547 0.3590448499 0.0056179678 0.0383780000 877054765 0 402718720 -0.0996792763 -0.1078533828 0.2336040586 3560 1311867289.1175429821 0.1078217700 0.1719375396 0.3590448499 0.0056172047 0.0373630000 877057909 0 402718720 -0.0998021141 -0.1080477536 0.2338639051 3561 1311867289.1545829773 0.1078818142 0.1719195514 0.3590448499 0.0056164562 0.0373400000 877061221 0 402718720 -0.0998945609 -0.1083481908 0.2341412753 3562 1311867289.1856400967 0.1076480970 0.1719015078 0.3590448499 0.0056156780 0.0372500000 877064309 0 402718720 -0.0995544195 -0.1083176285 0.2341412008 3563 1311867289.2184820175 0.1076832190 0.1718834841 0.3590448499 0.0056150141 0.0367280000 877067453 0 402718720 -0.0995228812 -0.1081499830 0.2339258641 3564 1311867289.2550389767 0.1079777107 0.1718655532 0.3590448499 0.0056147935 0.0373920000 877070765 0 402718720 -0.1001301482 -0.1090066582 0.2344011813 3565 1311867289.2853870392 0.1077463478 0.1718475675 0.3590448499 0.0056140750 0.0371160000 877073965 0 402718720 -0.0997635573 -0.1090908423 0.2341605276 3566 1311867289.3176290989 0.1080410853 0.1718296745 0.3590448499 0.0056134600 0.0368470000 877077053 0 402718720 -0.1000387743 -0.1084682271 0.2337602228 3567 1311867289.3539090157 0.1079930663 0.1718117780 0.3590448499 0.0056127095 0.0373980000 877080253 0 402718720 -0.1007711887 -0.1091508791 0.2338595241 3568 1311867289.3861849308 0.1082031056 0.1717939505 0.3590448499 0.0056119689 0.0386040000 877083453 0 402718720 -0.1012717783 -0.1086715460 0.2343573123 3569 1311867289.4177041054 0.1076036245 0.1717759650 0.3590448499 0.0056117818 0.0371910000 877086597 0 402718720 -0.1008029282 -0.1080396399 0.2336528897 3570 1311867289.4536058903 0.1070606038 0.1717578374 0.3590448499 0.0056110661 0.0379510000 877089853 0 402718720 -0.1009319723 -0.1083535552 0.2339778990 3571 1311867289.4859609604 0.1069308221 0.1717396837 0.3590448499 0.0056104723 0.0380520000 877092997 0 402718720 -0.1013110355 -0.1085795313 0.2347213179 3572 1311867289.5183179379 0.1074966937 0.1717216985 0.3590448499 0.0056098998 0.0382690000 877096085 0 402718720 -0.1016295105 -0.1072734296 0.2342563272 3573 1311867289.5548689365 0.1075408086 0.1717037358 0.3590448499 0.0056093757 0.0403730000 877099397 0 402718720 -0.1021722704 -0.1071816161 0.2352280915 3574 1311867289.5856130123 0.1066744849 0.1716855407 0.3590448499 0.0056095096 0.0383030000 877102597 0 402718720 -0.1021927297 -0.1089291573 0.2358770370 3575 1311867289.6176490784 0.1068897694 0.1716674160 0.3590448499 0.0056088572 0.0362410000 877105685 0 402718720 -0.1018835008 -0.1073185503 0.2350925058 3576 1311867289.6536390781 0.1073458716 0.1716494290 0.3590448499 0.0056081394 0.0414100000 877108941 0 402718720 -0.1022142619 -0.1058975086 0.2355705053 3577 1311867289.6856849194 0.1070222110 0.1716313615 0.3590448499 0.0056077213 0.0382400000 877112085 0 402718720 -0.1029783189 -0.1070484817 0.2363536954 3578 1311867289.7204260826 0.1067772657 0.1716132357 0.3590448499 0.0056069881 0.0380680000 877115285 0 402718720 -0.1029177606 -0.1062379181 0.2365394384 3579 1311867289.7564079762 0.1068278328 0.1715951342 0.3590448499 0.0056065574 0.0380180000 877118485 0 402718720 -0.1031037346 -0.1050374359 0.2373044342 3580 1311867289.7855679989 0.1059231162 0.1715767901 0.3590448499 0.0056061352 0.0389940000 877121629 0 402718720 -0.1036512107 -0.1069080457 0.2384685725 3581 1311867289.8240261078 0.1061358526 0.1715585156 0.3590448499 0.0056054329 0.0373720000 877124885 0 402718720 -0.1042836681 -0.1065982804 0.2386834472 3582 1311867289.8541760445 0.1062071621 0.1715402712 0.3590448499 0.0056048923 0.0381400000 877128029 0 402718720 -0.1044181734 -0.1056321710 0.2385482639 3583 1311867289.8855679035 0.1055136174 0.1715218434 0.3590448499 0.0056046002 0.0382510000 877131173 0 402718720 -0.1045546308 -0.1069111153 0.2394671887 3584 1311867289.9200460911 0.1055961996 0.1715034490 0.3590448499 0.0056061987 0.0375890000 877134317 0 402718720 -0.1051418781 -0.1069921032 0.2398800254 3585 1311867289.9536409378 0.1059254482 0.1714851567 0.3590448499 0.0056065178 0.0364890000 877137573 0 402718720 -0.1054473743 -0.1063960269 0.2400078326 3586 1311867289.9855279922 0.1055774167 0.1714667775 0.3590448499 0.0056057688 0.0390670000 877140661 0 402718720 -0.1060251147 -0.1076157391 0.2408194691 3587 1311867290.0201530457 0.1046890095 0.1714481609 0.3590448499 0.0056056478 0.0394000000 877143861 0 402718720 -0.1056170762 -0.1090671420 0.2412977368 3588 1311867290.0535750389 0.1055314243 0.1714297895 0.3590448499 0.0056049838 0.0382390000 877147061 0 402718720 -0.1058344841 -0.1080259979 0.2402424961 3589 1311867290.0854740143 0.1054548025 0.1714114069 0.3590448499 0.0056045393 0.0385950000 877150317 0 402718720 -0.1061606631 -0.1090201959 0.2409522533 3590 1311867290.1248800755 0.1054652184 0.1713930375 0.3590448499 0.0056038909 0.0399440000 877153573 0 402718720 -0.1058751494 -0.1089292616 0.2413265109 3591 1311867290.1536118984 0.1055190191 0.1713746933 0.3590448499 0.0056031490 0.0382800000 877156661 0 402718720 -0.1054171324 -0.1081397682 0.2404746562 3592 1311867290.1856379509 0.1056525186 0.1713563965 0.3590448499 0.0056027737 0.0386390000 877159861 0 402718720 -0.1053561717 -0.1079831198 0.2412026674 3593 1311867290.2225289345 0.1057314947 0.1713381318 0.3590448499 0.0056020957 0.0378200000 877163005 0 402718720 -0.1055209413 -0.1079640612 0.2416675687 3594 1311867290.2540268898 0.1055858657 0.1713198368 0.3590448499 0.0056022067 0.0392320000 877166149 0 402718720 -0.1046737209 -0.1068205088 0.2414865643 3595 1311867290.2869939804 0.1053631529 0.1713014900 0.3590448499 0.0056016163 0.0385810000 877169293 0 402718720 -0.1051958874 -0.1076682582 0.2426694632 3596 1311867290.3220460415 0.1054584011 0.1712831799 0.3590448499 0.0056009307 0.0392320000 877172549 0 402718720 -0.1055957824 -0.1079637036 0.2432211190 3597 1311867290.3547770977 0.1056123003 0.1712649228 0.3590448499 0.0056004269 0.0381140000 877175749 0 402718720 -0.1053690165 -0.1070592776 0.2424651831 3598 1311867290.3864150047 0.1053968221 0.1712466159 0.3590448499 0.0055997063 0.0381090000 877178781 0 402718720 -0.1057170480 -0.1077320352 0.2428073436 3599 1311867290.4216198921 0.1055655628 0.1712283661 0.3590448499 0.0055989351 0.0383060000 877182093 0 402718720 -0.1067309678 -0.1081789061 0.2430962473 3600 1311867290.4576630592 0.1053156555 0.1712100571 0.3590448499 0.0055984383 0.0384090000 877185125 0 402718720 -0.1066728607 -0.1074716002 0.2423491776 3601 1311867290.4859840870 0.1047043949 0.1711915884 0.3590448499 0.0055977430 0.0383260000 877188157 0 402718720 -0.1067609563 -0.1083872840 0.2426190525 3602 1311867290.5223278999 0.1044949442 0.1711730718 0.3590448499 0.0055971073 0.0393720000 877191413 0 402718720 -0.1071337238 -0.1086667553 0.2426477820 3603 1311867290.5537059307 0.1049369052 0.1711546882 0.3590448499 0.0055965662 0.0371060000 877194613 0 402718720 -0.1073474735 -0.1077268198 0.2417025864 3604 1311867290.5855538845 0.1054291055 0.1711364514 0.3590448499 0.0055968919 0.0385220000 877197813 0 402718720 -0.1081363037 -0.1082218811 0.2420327663 3605 1311867290.6201550961 0.1049135029 0.1711180816 0.3590448499 0.0055962946 0.0381530000 877200901 0 402718720 -0.1080062166 -0.1082058847 0.2418398261 3606 1311867290.6536018848 0.1048466563 0.1710997035 0.3590448499 0.0055967742 0.0391050000 877204157 0 402718720 -0.1076063886 -0.1072168276 0.2408632189 3607 1311867290.6857180595 0.1048987210 0.1710813500 0.3590448499 0.0055960655 0.0391760000 877207189 0 402718720 -0.1077185050 -0.1075062081 0.2413202822 3608 1311867290.7256059647 0.1050238833 0.1710630414 0.3590448499 0.0055958427 0.0391960000 877210613 0 402718720 -0.1079909578 -0.1083898991 0.2415890545 3609 1311867290.7539739609 0.1055499688 0.1710448887 0.3590448499 0.0055955453 0.0388220000 877213701 0 402718720 -0.1079948097 -0.1072542965 0.2406831384 3610 1311867290.7865738869 0.1055030376 0.1710267331 0.3590448499 0.0055947845 0.0392360000 877216733 0 402718720 -0.1077549607 -0.1079184040 0.2406345606 3611 1311867290.8231279850 0.1051063836 0.1710084777 0.3590448499 0.0055941604 0.0401710000 877220045 0 402718720 -0.1074077412 -0.1085374355 0.2408772707 3612 1311867290.8555860519 0.1056909263 0.1709903942 0.3590448499 0.0055935319 0.0387890000 877223189 0 402718720 -0.1072728932 -0.1081329286 0.2398469448 3613 1311867290.8876779079 0.1057399213 0.1709723343 0.3590448499 0.0055959067 0.0370300000 877226333 0 402718720 -0.1070752367 -0.1084235609 0.2394191325 3614 1311867290.9226930141 0.1054795235 0.1709542123 0.3590448499 0.0055951650 0.0376170000 877229533 0 402718720 -0.1065088138 -0.1092172936 0.2392555624 3615 1311867290.9537110329 0.1054586396 0.1709360946 0.3590448499 0.0055970889 0.0390790000 877232733 0 402718720 -0.1060680524 -0.1095677540 0.2387984693 3616 1311867290.9906759262 0.1060655341 0.1709181547 0.3590448499 0.0055964647 0.0387390000 877235989 0 402718720 -0.1056486443 -0.1090802401 0.2380356938 3617 1311867291.0239100456 0.1058723554 0.1709001714 0.3590448499 0.0055960263 0.0385710000 877239189 0 402718720 -0.1050809771 -0.1099644229 0.2382548004 3618 1311867291.0558199883 0.1061552614 0.1708822761 0.3590448499 0.0055952926 0.0388950000 877242389 0 402718720 -0.1045911387 -0.1100315899 0.2374479324 3619 1311867291.0903379917 0.1065596789 0.1708645026 0.3590448499 0.0055947880 0.0387380000 877245477 0 402718720 -0.1040691361 -0.1094576046 0.2365484089 3620 1311867291.1202719212 0.1065190062 0.1708467276 0.3590448499 0.0055942581 0.0379710000 877248621 0 402718720 -0.1037669182 -0.1100405380 0.2373372912 3621 1311867291.1541819572 0.1068071127 0.1708290419 0.3590448499 0.0055955529 0.0377870000 877251709 0 402718720 -0.1033319384 -0.1096004844 0.2366302609 3622 1311867291.1891789436 0.1066537946 0.1708113238 0.3590448499 0.0055967191 0.0379040000 877254965 0 402718720 -0.1026355103 -0.1096409708 0.2359862030 3623 1311867291.2210741043 0.1071556881 0.1707937539 0.3590448499 0.0055960520 0.0375340000 877258109 0 402718720 -0.1027967781 -0.1099364161 0.2364715189 3624 1311867291.2543799877 0.1076440737 0.1707763285 0.3590448499 0.0055954052 0.0379860000 877261309 0 402718720 -0.1026336402 -0.1093079969 0.2359476984 3625 1311867291.2877910137 0.1075644121 0.1707588907 0.3590448499 0.0055946417 0.0378370000 877264453 0 402718720 -0.1022501811 -0.1094968766 0.2356481850 3626 1311867291.3210599422 0.1071594581 0.1707413509 0.3590448499 0.0055939996 0.0376680000 877267597 0 402718720 -0.1017920524 -0.1100986823 0.2357138395 3627 1311867291.3547840118 0.1075033322 0.1707239155 0.3590448499 0.0055933392 0.0377250000 877270853 0 402718720 -0.1017255709 -0.1097615287 0.2351913601 3628 1311867291.3878340721 0.1078831479 0.1707065945 0.3590448499 0.0055928524 0.0379120000 877273997 0 402718720 -0.1019317731 -0.1096084788 0.2348669171 3629 1311867291.4223160744 0.1075844690 0.1706892007 0.3590448499 0.0055922967 0.0376790000 877277197 0 402718720 -0.1017228141 -0.1103271991 0.2349283248 3630 1311867291.4536559582 0.1074172184 0.1706717704 0.3590448499 0.0055915624 0.0376210000 877280397 0 402718720 -0.1011853665 -0.1102269664 0.2343741208 3631 1311867291.4883809090 0.1079488695 0.1706544961 0.3590448499 0.0055911293 0.0367900000 877283541 0 402718720 -0.1013163775 -0.1095079333 0.2337788045 3632 1311867291.5201399326 0.1077269241 0.1706371702 0.3590448499 0.0055905261 0.0377530000 877286741 0 402718720 -0.1011836529 -0.1099887490 0.2339816242 3633 1311867291.5536448956 0.1077604592 0.1706198631 0.3590448499 0.0055898440 0.0363970000 877289941 0 402718720 -0.1009375751 -0.1097222269 0.2335660309 3634 1311867291.5894980431 0.1075488850 0.1706025073 0.3590448499 0.0055894890 0.0366580000 877293141 0 402718720 -0.1006992087 -0.1095541194 0.2330348492 3635 1311867291.6206729412 0.1077236235 0.1705852091 0.3590448499 0.0055893676 0.0372150000 877296229 0 402718720 -0.1010917202 -0.1101389229 0.2335814238 3636 1311867291.6539700031 0.1078815162 0.1705679639 0.3590448499 0.0055886701 0.0378570000 877299429 0 402718720 -0.1011418700 -0.1098005101 0.2332630605 3637 1311867291.6896469593 0.1073669568 0.1705505867 0.3590448499 0.0055879122 0.0399130000 877302685 0 402718720 -0.1006479487 -0.1100295410 0.2325806767 3638 1311867291.7202510834 0.1076498851 0.1705332967 0.3590448499 0.0055871856 0.0461560000 877305773 0 402718720 -0.1012584567 -0.1106558293 0.2330485582 3639 1311867291.7537178993 0.1083779708 0.1705162164 0.3590448499 0.0055870839 0.0413720000 877309029 0 402718720 -0.1015303135 -0.1096857935 0.2326500118 3640 1311867291.7889850140 0.1078404784 0.1704989978 0.3590448499 0.0055867195 0.0461310000 877312173 0 402718720 -0.1010547876 -0.1101375893 0.2319769859 3641 1311867291.8217189312 0.1070191413 0.1704815631 0.3590448499 0.0055865648 0.0466000000 877315373 0 402718720 -0.1004114896 -0.1110600904 0.2324542403 3642 1311867291.8538639545 0.1074574739 0.1704642583 0.3590448499 0.0055859147 0.0456810000 877318573 0 402718720 -0.1003039852 -0.1104662344 0.2315492183 3643 1311867291.8879430294 0.1076210067 0.1704470079 0.3590448499 0.0055857699 0.0462300000 877321661 0 402718720 -0.1002231464 -0.1106867641 0.2318679094 3644 1311867291.9206850529 0.1077522933 0.1704298029 0.3590448499 0.0055853581 0.0454240000 877324917 0 402718720 -0.1001595333 -0.1107513905 0.2318634391 3645 1311867291.9537200928 0.1073444933 0.1704124956 0.3590448499 0.0055851660 0.0459380000 877328061 0 402718720 -0.0993831158 -0.1107770130 0.2316127867 3646 1311867291.9900910854 0.1075246483 0.1703952471 0.3590448499 0.0055854562 0.0463520000 877331317 0 402718720 -0.0992503837 -0.1108027250 0.2320337743 3647 1311867292.0225200653 0.1079873666 0.1703781350 0.3590448499 0.0055880538 0.0460690000 877334461 0 402718720 -0.0993584916 -0.1106549278 0.2321951091 3648 1311867292.0536830425 0.1076838225 0.1703609491 0.3590448499 0.0055873825 0.0469870000 877337605 0 402718720 -0.0988323912 -0.1107860953 0.2322183847 3649 1311867292.0922539234 0.1080072597 0.1703438612 0.3590448499 0.0055890254 0.0459460000 877340861 0 402718720 -0.0989702493 -0.1106564701 0.2324511111 3650 1311867292.1243820190 0.1083725020 0.1703268827 0.3590448499 0.0055883521 0.0459850000 877343949 0 402718720 -0.0992787704 -0.1104519740 0.2325294465 3651 1311867292.1602489948 0.1082930341 0.1703098918 0.3590448499 0.0055876124 0.0463110000 877347205 0 402718720 -0.0992089957 -0.1102824286 0.2327073067 3652 1311867292.1899731159 0.1080358103 0.1702928398 0.3590448499 0.0055868827 0.0462600000 877350293 0 402718720 -0.0990856513 -0.1104809418 0.2331504673 3653 1311867292.2207319736 0.1080599725 0.1702758037 0.3590448499 0.0055861301 0.0421520000 877353325 0 402718720 -0.0993399993 -0.1106503531 0.2334100902 3654 1311867292.2576849461 0.1080847457 0.1702587837 0.3590448499 0.0055854172 0.0374650000 877356637 0 402718720 -0.0996113420 -0.1105781049 0.2335771471 3655 1311867292.2878160477 0.1081120074 0.1702417805 0.3590448499 0.0055846529 0.0379280000 877359725 0 402718720 -0.0999417230 -0.1107970551 0.2338788509 3656 1311867292.3213870525 0.1078967154 0.1702247277 0.3590448499 0.0055864609 0.0372220000 877362869 0 402718720 -0.0998953059 -0.1109263375 0.2339963913 3657 1311867292.3621599674 0.1077530682 0.1702076449 0.3590448499 0.0055881113 0.0376330000 877366293 0 402718720 -0.1000521407 -0.1110185087 0.2341127247 3658 1311867292.3953499794 0.1080094725 0.1701906416 0.3590448499 0.0055873859 0.0379790000 877369493 0 402718720 -0.1005366966 -0.1111206859 0.2343403101 3659 1311867292.4259300232 0.1078088805 0.1701735927 0.3590448499 0.0055866374 0.0378290000 877372637 0 402718720 -0.1005498618 -0.1113537848 0.2345818579 3660 1311867292.4564480782 0.1076547951 0.1701565111 0.3590448499 0.0055859099 0.0362390000 877375613 0 402718720 -0.1003994495 -0.1114344522 0.2345073372 3661 1311867292.4883511066 0.1076722443 0.1701394435 0.3590448499 0.0055851721 0.0381560000 877378813 0 402718720 -0.1007212475 -0.1117783636 0.2347816080 3662 1311867292.5228829384 0.1079073474 0.1701224495 0.3590448499 0.0055844268 0.0373250000 877382013 0 402718720 -0.1007667482 -0.1115231887 0.2346468568 3663 1311867292.5581040382 0.1078557819 0.1701054507 0.3590448499 0.0055836870 0.0373910000 877385213 0 402718720 -0.1006285474 -0.1110559627 0.2342474908 3664 1311867292.5882220268 0.1076309457 0.1700883998 0.3590448499 0.0055831134 0.0375120000 877388357 0 402718720 -0.1006623283 -0.1112805977 0.2346818596 3665 1311867292.6230759621 0.1076212674 0.1700713556 0.3590448499 0.0055823831 0.0373420000 877391557 0 402718720 -0.1006744877 -0.1111620516 0.2342966348 3666 1311867292.6595079899 0.1075834930 0.1700543103 0.3590448499 0.0055816374 0.0376920000 877394869 0 402718720 -0.1006041691 -0.1111598015 0.2346246541 3667 1311867292.6880149841 0.1076670587 0.1700372972 0.3590448499 0.0055810398 0.0383930000 877397845 0 402718720 -0.1009238660 -0.1118464842 0.2355228215 3668 1311867292.7206439972 0.1077681780 0.1700203208 0.3590448499 0.0055803057 0.0373880000 877401045 0 402718720 -0.1004300043 -0.1111859679 0.2349462062 3669 1311867292.7561779022 0.1073183790 0.1700032312 0.3590448499 0.0055797540 0.0379320000 877404301 0 402718720 -0.0998790637 -0.1117764711 0.2347981185 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:24:08 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0518880000 348455168 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0031691571 0.0015845785 0.0031691571 0.0051863687 0.0347600000 356793422 0 402718720 -0.0023924122 -0.0062225722 0.0031568736 3 0.0800000000 0.0032575948 0.0021422506 0.0032575948 0.0040403993 0.0335720000 356723787 0 402718720 -0.0005876704 -0.0129576828 0.0027188603 4 0.1200000000 0.0022392957 0.0021665119 0.0032575948 0.0051060712 0.0326370000 356696274 0 402718720 -0.0016820929 -0.0072146896 0.0021959895 5 0.1600000000 0.0024197169 0.0022171529 0.0032575948 0.0047697566 0.0318560000 356699494 0 402718720 -0.0014772897 -0.0044755987 0.0011858713 6 0.2000000000 0.0030112965 0.0023495102 0.0032575948 0.0043141388 0.0439860000 356703322 0 402718720 -0.0016677103 -0.0090322718 0.0020965193 7 0.2400000000 0.0032603887 0.0024796357 0.0032603887 0.0041382959 0.0325410000 356706634 0 402718720 -0.0015840792 -0.0092999684 0.0030944203 8 0.2800000000 0.0020307349 0.0024235231 0.0032603887 0.0040781388 0.0403710000 356709498 0 402718720 0.0001330527 -0.0071562878 0.0026867476 9 0.3200000000 0.0048305569 0.0026909713 0.0048305569 0.0040023498 0.0329660000 356717458 0 402718720 -0.0025527200 -0.0097141899 0.0020566385 10 0.3600000000 0.0035275193 0.0027746261 0.0048305569 0.0038945476 0.0436060000 356718462 0 402718720 -0.0000988426 -0.0087972973 0.0026473207 11 0.4000000000 0.0020459378 0.0027083817 0.0048305569 0.0038738860 0.0317050000 356723782 0 402718720 0.0038426071 -0.0081464006 0.0025021916 12 0.4400000000 0.0014956765 0.0026073229 0.0048305569 0.0038239942 0.0318800000 356726326 0 402718720 0.0032302567 -0.0088327974 0.0021845829 13 0.4800000000 0.0020366635 0.0025634260 0.0048305569 0.0037712771 0.0422970000 356728658 0 402718720 0.0019363483 -0.0073579000 0.0016214929 14 0.5200000000 0.0029011359 0.0025875482 0.0048305569 0.0038170467 0.0441810000 356731066 0 402718720 0.0007950410 -0.0070841941 0.0009699628 15 0.5600000000 0.0023513571 0.0025718021 0.0048305569 0.0036842350 0.0320600000 356732606 0 402718720 0.0015239402 -0.0061471160 0.0003294857 16 0.6000000000 0.0020348476 0.0025382425 0.0048305569 0.0036346178 0.0317420000 356735974 0 402718720 0.0038005807 -0.0043889992 0.0004537601 17 0.6400000000 0.0017492299 0.0024918300 0.0048305569 0.0035368474 0.0328540000 356739422 0 402718720 0.0028502382 -0.0050935401 0.0003173794 18 0.6800000000 0.0027932506 0.0025085755 0.0048305569 0.0034454200 0.0326880000 356743782 0 402718720 0.0036589415 -0.0062892972 0.0001091565 19 0.7200000000 0.0022312810 0.0024939811 0.0048305569 0.0037011900 0.0448810000 356751534 0 402718720 0.0032594628 -0.0044285599 -0.0002670800 20 0.7600000000 0.0013950723 0.0024390357 0.0048305569 0.0036085150 0.0324500000 356752498 0 402718720 0.0049360013 -0.0039332653 -0.0008952577 21 0.8000000000 0.0020564569 0.0024208176 0.0048305569 0.0035546086 0.0324160000 356755002 0 402718720 0.0023638208 -0.0037305125 -0.0016495946 22 0.8400000000 0.0010412314 0.0023581092 0.0048305569 0.0035022976 0.0331180000 356758122 0 402718720 0.0040238714 -0.0021965655 -0.0019998297 23 0.8800000000 0.0027164822 0.0023736906 0.0048305569 0.0034485408 0.0330910000 356761070 0 402718720 0.0017452374 -0.0031613582 -0.0017474974 24 0.9200000000 0.0020645580 0.0023608101 0.0048305569 0.0034242011 0.0327080000 356763482 0 402718720 0.0039973860 -0.0060002492 -0.0011371406 25 0.9600000000 0.0029643963 0.0023849535 0.0048305569 0.0034693571 0.0328040000 356768930 0 402718720 0.0048128506 -0.0030919116 0.0005931582 26 1.0000000000 0.0010623238 0.0023340831 0.0048305569 0.0034667220 0.0333300000 356772026 0 402718720 0.0056610564 -0.0057422169 -0.0010244150 27 1.0400000000 0.0041996571 0.0024031785 0.0048305569 0.0034257493 0.0340040000 356773986 0 402718720 0.0042856820 -0.0075971135 0.0002150144 28 1.0800000000 0.0039273058 0.0024576116 0.0048305569 0.0033741626 0.0439140000 356776950 0 402718720 0.0043761511 -0.0048996015 -0.0003916664 29 1.1200000000 0.0053236019 0.0025564388 0.0053236019 0.0034849281 0.0342480000 356783814 0 402718720 0.0045006680 -0.0035670856 0.0002448394 30 1.1600000000 0.0049033887 0.0026346705 0.0053236019 0.0037631362 0.0323390000 356784790 0 402718720 0.0040637129 -0.0074554770 0.0004201201 31 1.2000000000 0.0045607854 0.0026968032 0.0053236019 0.0039281419 0.0323030000 356790454 0 402718720 0.0064551379 -0.0058451900 0.0003498193 32 1.2400000000 0.0036362731 0.0027261617 0.0053236019 0.0043334528 0.0326940000 356795654 0 402718720 0.0095592532 -0.0032289436 0.0001649720 33 1.2800000000 0.0048063155 0.0027891966 0.0053236019 0.0047133932 0.0326840000 356801518 0 402718720 0.0083559472 -0.0046032174 0.0024746291 34 1.3200000000 0.0021153265 0.0027693769 0.0053236019 0.0049270646 0.0329100000 356813542 0 402718720 0.0106231589 -0.0043307170 0.0012924362 35 1.3600000000 0.0072285002 0.0028967805 0.0072285002 0.0052579136 0.0326310000 356820218 0 402718720 0.0057640574 -0.0034217339 0.0039128782 36 1.4000000000 0.0053688125 0.0029654480 0.0072285002 0.0056728850 0.0431250000 356824802 0 402718720 0.0106975455 -0.0029932575 0.0045921202 37 1.4400000000 0.0072750887 0.0030819248 0.0072750887 0.0060566230 0.0318770000 356832202 0 402718720 0.0089978455 -0.0029243992 0.0051273759 38 1.4800000000 0.0076185651 0.0032013101 0.0076185651 0.0081186856 0.0316650000 356842066 0 402718720 0.0101673529 -0.0044512814 0.0077478131 39 1.5200000000 0.0042695054 0.0032286997 0.0076185651 0.0085054733 0.0318210000 356849798 0 402718720 0.0148437917 -0.0056485566 0.0079282690 40 1.5600000000 0.0077680978 0.0033421846 0.0077680978 0.0086253462 0.0316800000 356852690 0 402718720 0.0167781822 -0.0009096849 0.0089763030 41 1.6000000000 0.0096607711 0.0034962965 0.0096607711 0.0087539062 0.0434070000 356863298 0 402718720 0.0134929409 -0.0059492639 0.0110944426 42 1.6400000000 0.0092263389 0.0036327261 0.0096607711 0.0088812933 0.0316130000 356867130 0 402718720 0.0168061722 -0.0046301782 0.0110068265 43 1.6800000000 0.0080313813 0.0037350204 0.0096607711 0.0091878474 0.0317150000 356873246 0 402718720 0.0180014055 -0.0050874557 0.0114367697 44 1.7200000000 0.0086384388 0.0038464617 0.0096607711 0.0094481624 0.0316470000 356880278 0 402718720 0.0197966881 -0.0025110613 0.0133023616 45 1.7600000000 0.0062117898 0.0038990246 0.0096607711 0.0098175251 0.0443570000 356886946 0 402718720 0.0232842956 -0.0060351300 0.0130133349 46 1.8000000000 0.0057716593 0.0039397340 0.0096607711 0.0110561268 0.0408260000 356892678 0 402718720 0.0502098091 -0.0090700174 0.0071856426 47 1.8400000000 0.0058253696 0.0039798539 0.0096607711 0.0109870757 0.0307120000 356897254 0 402718720 0.1118130386 -0.0094092172 -0.0034965985 48 1.8800000000 0.0069824113 0.0040424072 0.0096607711 0.0110971827 0.0305300000 356903554 0 402718720 0.1127955765 -0.0103643006 -0.0023507485 49 1.9200000000 0.0057139741 0.0040765208 0.0096607711 0.0112665651 0.0296280000 356910138 0 402718720 0.1157047004 -0.0130042257 -0.0046372833 50 1.9600000000 0.0067991270 0.0041309729 0.0096607711 0.0113482493 0.0300450000 356916254 0 402718720 0.1170473546 -0.0148006426 -0.0029189987 51 2.0000000000 0.0090381615 0.0042271923 0.0096607711 0.0114070400 0.0358180000 356919662 0 402718720 0.1204829067 -0.0095623583 -0.0011922121 52 2.0400000000 0.0030676373 0.0042048932 0.0096607711 0.0115596301 0.0295670000 356928490 0 402718720 0.1268332750 -0.0168895498 -0.0037203673 53 2.0800000000 0.0103213182 0.0043202974 0.0103213182 0.0116015218 0.0301380000 356933818 0 402718720 0.1288700551 -0.0074108485 -0.0024055578 54 2.1200000000 0.0094744219 0.0044157442 0.0103213182 0.0116239507 0.0291580000 356937618 0 402718720 0.1302679330 -0.0087224785 -0.0025226381 55 2.1600000000 0.0203153845 0.0047048285 0.0203153845 0.0116108334 0.0292740000 356943158 0 402718720 0.1260994822 -0.0001838846 0.0024074689 56 2.2000000000 0.0093971966 0.0047886208 0.0203153845 0.0117991572 0.0404230000 356946634 0 402718720 0.1323179007 -0.0104847178 -0.0032038447 57 2.2400000000 0.0028193502 0.0047540722 0.0203153845 0.0120455871 0.0294690000 357293867 0 402718720 0.1363249570 -0.0194871444 -0.0056377575 58 2.2800000000 0.0058449451 0.0047728804 0.0203153845 0.0121945636 0.0319850000 357739955 0 402718720 0.1369853318 -0.0230916422 -0.0082147829 59 2.3200000000 0.0073040524 0.0048157816 0.0203153845 0.0123512067 0.0786140000 359434106 0 402718720 0.1369658113 -0.0167112090 -0.0080144908 60 2.3600000000 0.0225708541 0.0051116995 0.0225708541 0.0128719511 0.0473080000 359378327 0 402718720 0.1668117642 -0.0137013113 -0.0103070624 61 2.4000000000 0.0210273508 0.0053726118 0.0225708541 0.0130728176 0.0278880000 357729350 0 402718720 0.1640213579 -0.0083502736 -0.0065148361 62 2.4400000000 0.0163640529 0.0055498931 0.0225708541 0.0132888689 0.0287210000 357736678 0 402718720 0.1648226976 -0.0129853301 -0.0055563450 63 2.4800000000 0.0227365848 0.0058226977 0.0227365848 0.0134634028 0.0290630000 357741286 0 402718720 0.1689995825 -0.0036984093 -0.0062070638 64 2.5200000000 0.0191486906 0.0060309164 0.0227365848 0.0136622938 0.0287630000 357746498 0 402718720 0.1741259098 -0.0121388426 -0.0104337819 65 2.5600000000 0.0223926231 0.0062826349 0.0227365848 0.0137629167 0.0290200000 357750962 0 402718720 0.1801887751 -0.0093241977 -0.0110533945 66 2.6000000000 0.0183932427 0.0064661290 0.0227365848 0.0138567810 0.0282100000 357764766 0 402718720 0.1832701266 -0.0152183315 -0.0161844082 67 2.6400000000 0.0188254099 0.0066505959 0.0227365848 0.0139101114 0.0281950000 357772018 0 402718720 0.1815161854 -0.0095237987 -0.0139794834 68 2.6800000000 0.0210657343 0.0068625832 0.0227365848 0.0140388601 0.0277790000 357776014 0 402718720 0.1878309548 -0.0076068467 -0.0174178742 69 2.7200000000 0.0260106008 0.0071400907 0.0260106008 0.0141352578 0.0274340000 357779322 0 402718720 0.1947335452 -0.0061433711 -0.0192589499 70 2.7600000000 0.0230600815 0.0073675191 0.0260106008 0.0142771220 0.0273110000 357784654 0 402718720 0.1925494224 -0.0080390107 -0.0199763961 71 2.8000000000 0.0169808995 0.0075029189 0.0260106008 0.0144083859 0.0264680000 357789710 0 402718720 0.1957174540 -0.0155449947 -0.0194644406 72 2.8400000000 0.0217728596 0.0077011125 0.0260106008 0.0145785105 0.0266110000 357795054 0 402718720 0.2023182511 -0.0118242251 -0.0226525143 73 2.8800000000 0.0201267395 0.0078713266 0.0260106008 0.0147020718 0.0266150000 357797938 0 402718720 0.2051215172 -0.0155737577 -0.0236667022 74 2.9200000000 0.0208800454 0.0080471200 0.0260106008 0.0147654513 0.0261970000 357802562 0 402718720 0.2114120126 -0.0167108383 -0.0290867016 75 2.9600000000 0.0230519865 0.0082471849 0.0260106008 0.0148515943 0.0275900000 358138314 0 402718720 0.2058302015 -0.0078054974 -0.0267359279 76 3.0000000000 0.0183424782 0.0083800177 0.0260106008 0.0149534138 0.0740280000 358951210 0 402718720 0.2157653570 -0.0204327423 -0.0334019028 77 3.0400000000 0.0230001565 0.0085698897 0.0260106008 0.0149996952 0.0355200000 360155426 0 402718720 0.2212416381 -0.0172462631 -0.0348182358 78 3.0800000000 0.0196790919 0.0087123153 0.0260106008 0.0150081083 0.0360370000 359821805 0 402718720 0.2200432867 -0.0175050590 -0.0361894257 79 3.1200000000 0.0243706945 0.0089105227 0.0260106008 0.0150618621 0.0267100000 358223274 0 402718720 0.2280147672 -0.0148964263 -0.0392653495 80 3.1600000000 0.0245198235 0.0091056389 0.0260106008 0.0154610055 0.0276980000 358226746 0 402718720 0.2354121059 -0.0149045400 -0.0453089550 81 3.2000000000 0.0166114978 0.0091983039 0.0260106008 0.0154653417 0.0313860000 358233266 0 402718720 0.2314077020 -0.0197100788 -0.0478302427 82 3.2400000000 0.0213662405 0.0093466933 0.0260106008 0.0154871647 0.0306710000 358237846 0 402718720 0.2400294840 -0.0201934092 -0.0503584445 83 3.2800000000 0.0202952363 0.0094786035 0.0260106008 0.0155331386 0.0297400000 358237438 0 402718720 0.2437128872 -0.0220519695 -0.0542125404 84 3.3200000000 0.0243703350 0.0096558860 0.0260106008 0.0155150723 0.0299410000 358242982 0 402718720 0.2437434793 -0.0190004576 -0.0531978346 85 3.3600000000 0.0212018099 0.0097917204 0.0260106008 0.0155240894 0.0296920000 358247714 0 402718720 0.2483598590 -0.0247963183 -0.0558411554 86 3.4000000000 0.0254576728 0.0099738826 0.0260106008 0.0155643051 0.0294090000 358250278 0 402718720 0.2520584762 -0.0217103828 -0.0583770983 87 3.4400000000 0.0252239089 0.0101491703 0.0260106008 0.0156110454 0.0290920000 358255842 0 402718720 0.2581399977 -0.0242694970 -0.0613066852 88 3.4800000000 0.0117759528 0.0101676565 0.0260106008 0.0156240810 0.0288360000 358259802 0 402718720 0.2510893047 -0.0328239240 -0.0620957017 89 3.5200000000 0.0243223198 0.0103266976 0.0260106008 0.0156668981 0.0248570000 358263590 0 402718720 0.2593017817 -0.0217823721 -0.0642620102 90 3.5600000000 0.0251685325 0.0104916069 0.0260106008 0.0156723582 0.0247170000 358265346 0 402718720 0.2654663622 -0.0252086800 -0.0664955676 91 3.6000000000 0.0207251236 0.0106040631 0.0260106008 0.0156761491 0.0244340000 358268402 0 402718720 0.2618546784 -0.0279088765 -0.0659670830 92 3.6400000000 0.0258614384 0.0107699042 0.0260106008 0.0156808000 0.0243570000 358271522 0 402718720 0.2695507109 -0.0236203019 -0.0684125349 93 3.6800000000 0.0192976035 0.0108615999 0.0260106008 0.0156742788 0.0240850000 358278286 0 402718720 0.2740110755 -0.0360524654 -0.0711287335 94 3.7200000000 0.0206895843 0.0109661529 0.0260106008 0.0156101245 0.0241920000 358281846 0 402718720 0.2702949345 -0.0291967262 -0.0722148120 95 3.7600000000 0.0309954919 0.0111769880 0.0309954919 0.0155912966 0.0242640000 358283654 0 402718720 0.2764009237 -0.0189137068 -0.0733173937 96 3.8000000000 0.0248603486 0.0113195230 0.0309954919 0.0155624544 0.0356600000 358285946 0 402718720 0.2810344398 -0.0272454955 -0.0777555332 97 3.8400000000 0.0212017540 0.0114214017 0.0309954919 0.0155160093 0.0237930000 358288942 0 402718720 0.2784081697 -0.0293873977 -0.0768544227 98 3.8800000000 0.0189250410 0.0114979695 0.0309954919 0.0154795541 0.0263070000 358687346 0 402718720 0.2828326225 -0.0351154357 -0.0811432078 99 3.9200000000 0.0166569296 0.0115500802 0.0309954919 0.0154273458 0.0799300000 358966622 0 402718720 0.2855377793 -0.0396728776 -0.0815353841 100 3.9600000000 0.0176356677 0.0116109360 0.0309954919 0.0153643291 0.0658750000 361371278 0 402718720 0.2829389870 -0.0365969092 -0.0807536766 101 4.0000000000 0.0233168397 0.0117268361 0.0309954919 0.0153659039 0.0533180000 361560411 0 402718720 0.2979952395 -0.0403869785 -0.0891194791 102 4.0400000000 0.0250979196 0.0118579251 0.0309954919 0.0153231676 0.0280870000 358906342 0 402718720 0.3006127477 -0.0372032076 -0.0930953845 103 4.0800000000 0.0280032121 0.0120146755 0.0309954919 0.0152857432 0.0372810000 358908202 0 402718720 0.3071329296 -0.0399101079 -0.0953898504 104 4.1200000000 0.0277441237 0.0121659202 0.0309954919 0.0152300414 0.0278570000 358911794 0 402718720 0.3080457151 -0.0365192480 -0.0939721689 105 4.1600000000 0.0273785144 0.0123108020 0.0309954919 0.0151771424 0.0394710000 358915842 0 402718720 0.3098068237 -0.0339068845 -0.0952493027 106 4.2000000000 0.0243956037 0.0124248096 0.0309954919 0.0151339749 0.0275810000 358918530 0 402718720 0.3104360700 -0.0414325967 -0.0989237055 107 4.2400000000 0.0259608887 0.0125513150 0.0309954919 0.0150712317 0.0273410000 358920774 0 402718720 0.3130368888 -0.0425808504 -0.0993498564 108 4.2800000000 0.0237206928 0.0126547352 0.0309954919 0.0150051214 0.0281390000 358926782 0 402718720 0.3143540025 -0.0406786725 -0.1028938293 109 4.3200000000 0.0254998039 0.0127725798 0.0309954919 0.0149373194 0.0389650000 358929646 0 402718720 0.3175023198 -0.0378254429 -0.1039933041 110 4.3600000000 0.0254735593 0.0128880433 0.0309954919 0.0148765989 0.0270930000 358932690 0 402718720 0.3168218136 -0.0307390932 -0.1029220670 111 4.4000000000 0.0255720988 0.0130023141 0.0309954919 0.0148406355 0.0267200000 358936578 0 402718720 0.3198260367 -0.0425548293 -0.1060756072 112 4.4400000000 0.0271537304 0.0131286660 0.0309954919 0.0148002081 0.0267580000 358940730 0 402718720 0.3227476478 -0.0279827397 -0.1083143651 113 4.4800000000 0.0324170515 0.0132993597 0.0324170515 0.0147391418 0.0270510000 358943434 0 402718720 0.3299726546 -0.0277151540 -0.1100109220 114 4.5200000000 0.0254141111 0.0134056294 0.0324170515 0.0146840010 0.0269180000 358947614 0 402718720 0.3245028853 -0.0313047282 -0.1103438810 115 4.5600000000 0.0219230689 0.0134796941 0.0324170515 0.0146281513 0.0265600000 358949942 0 402718720 0.3219406009 -0.0287106223 -0.1132025793 116 4.6000000000 0.0232884586 0.0135642524 0.0324170515 0.0145781386 0.0270040000 358953546 0 402718720 0.3235135376 -0.0222984999 -0.1110234633 117 4.6400000000 0.0227272715 0.0136425688 0.0324170515 0.0145318284 0.0272880000 358957890 0 402718720 0.3237760663 -0.0192967728 -0.1100833640 118 4.6800000000 0.0265156515 0.0137516627 0.0324170515 0.0144886848 0.0274100000 358958710 0 402718720 0.3275307119 -0.0168890301 -0.1128223687 119 4.7200000000 0.0214057006 0.0138159824 0.0324170515 0.0144623447 0.0272410000 358965570 0 402718720 0.3227751851 -0.0156096630 -0.1097983718 120 4.7600000000 0.0227665529 0.0138905705 0.0324170515 0.0144121105 0.0267390000 358966594 0 402718720 0.3246417344 -0.0157907531 -0.1131928712 121 4.8000000000 0.0224530008 0.0139613344 0.0324170515 0.0143679448 0.0267940000 358967210 0 402718720 0.3236351907 -0.0167852119 -0.1158904880 122 4.8400000000 0.0264289528 0.0140635280 0.0324170515 0.0143454229 0.0276020000 358972666 0 402718720 0.3256386817 -0.0061860690 -0.1147795096 123 4.8800000000 0.0233538747 0.0141390592 0.0324170515 0.0142976231 0.0268240000 358976410 0 402718720 0.3226359785 -0.0072411522 -0.1142128557 124 4.9200000000 0.0263511278 0.0142375437 0.0324170515 0.0142594924 0.0264540000 358978170 0 402718720 0.3238738775 -0.0030239709 -0.1156884804 125 4.9600000000 0.0217663292 0.0142977739 0.0324170515 0.0142151252 0.0267620000 358981598 0 402718720 0.3186938167 -0.0005796307 -0.1119641885 126 5.0000000000 0.0266631953 0.0143959122 0.0324170515 0.0141724370 0.0361850000 358985198 0 402718720 0.3242165148 -0.0016532843 -0.1163661480 127 5.0400000000 0.0234092288 0.0144668832 0.0324170515 0.0141663022 0.0269580000 358987570 0 402718720 0.3163503408 0.0075234068 -0.1099216044 128 5.0800000000 0.0235562585 0.0145378939 0.0324170515 0.0141374209 0.0391160000 358992322 0 402718720 0.3174616396 0.0057855351 -0.1131883711 129 5.1200000000 0.0254550315 0.0146225229 0.0324170515 0.0141009587 0.0393570000 358996390 0 402718720 0.3199804723 0.0076709064 -0.1128735840 130 5.1600000000 0.0265780166 0.0147144883 0.0324170515 0.0140772488 0.0268860000 359022326 0 402718720 0.3199753165 0.0036533256 -0.1158238277 131 5.2000000000 0.0204847418 0.0147585360 0.0324170515 0.0140797555 0.0271240000 359024922 0 402718720 0.3113594949 0.0062478879 -0.1124216020 132 5.2400000000 0.0236682687 0.0148260340 0.0324170515 0.0140454831 0.0270800000 359029814 0 402718720 0.3124189675 0.0076449434 -0.1116522402 133 5.2800000000 0.0239743832 0.0148948185 0.0324170515 0.0140099156 0.0471810000 359033030 0 402718720 0.3117510378 0.0077863927 -0.1097922549 134 5.3200000000 0.0221584495 0.0149490247 0.0324170515 0.0139815125 0.0276780000 359037322 0 402718720 0.3066909909 0.0130205648 -0.1044859141 135 5.3600000000 0.0253087077 0.0150257631 0.0324170515 0.0139376894 0.0272220000 359038190 0 402718720 0.3089900017 0.0093322080 -0.1045692414 136 5.4000000000 0.0272707827 0.0151158001 0.0324170515 0.0139072013 0.0276350000 359044922 0 402718720 0.3087027669 0.0125241252 -0.1063352227 137 5.4400000000 0.0274955425 0.0152061631 0.0324170515 0.0138666065 0.0278980000 359046678 0 402718720 0.3095019460 0.0086974679 -0.1033061445 138 5.4800000000 0.0284191668 0.0153019095 0.0324170515 0.0139431607 0.0278860000 359052434 0 402718720 0.3060190678 0.0131344711 -0.1013520211 139 5.5200000000 0.0215284955 0.0153467051 0.0324170515 0.0139181106 0.0281250000 359054270 0 402718720 0.2973412871 0.0113136945 -0.0984266698 140 5.5600000000 0.0234196354 0.0154043689 0.0324170515 0.0138957440 0.0389060000 359057146 0 402718720 0.2978801429 0.0147665590 -0.0974301621 141 5.6000000000 0.0224672705 0.0154544604 0.0324170515 0.0138719679 0.0279460000 359059834 0 402718720 0.2939242125 0.0208097361 -0.0914743245 142 5.6400000000 0.0242345668 0.0155162921 0.0324170515 0.0138530528 0.0282710000 359062634 0 402718720 0.2952315509 0.0195083730 -0.0954450443 143 5.6800000000 0.0220479425 0.0155619680 0.0324170515 0.0138345322 0.0281760000 359065718 0 402718720 0.2909153700 0.0209418163 -0.0892093033 144 5.7200000000 0.0231897645 0.0156149388 0.0324170515 0.0138016039 0.0283480000 359068678 0 402718720 0.2895120382 0.0210663006 -0.0888373479 145 5.7600000000 0.0248915609 0.0156789155 0.0324170515 0.0137717014 0.0280920000 359071102 0 402718720 0.2889698148 0.0253472626 -0.0889865682 146 5.8000000000 0.0213049930 0.0157174503 0.0324170515 0.0137539985 0.0276240000 359074098 0 402718720 0.2838722765 0.0200823080 -0.0896625817 147 5.8400000000 0.0217597298 0.0157585543 0.0324170515 0.0137315188 0.0376360000 359076986 0 402718720 0.2816188633 0.0239947047 -0.0836094171 148 5.8800000000 0.0201791152 0.0157884229 0.0324170515 0.0137188105 0.0279410000 359079346 0 402718720 0.2781927884 0.0257304423 -0.0836734623 149 5.9200000000 0.0242933910 0.0158455032 0.0324170515 0.0136924077 0.0282880000 359082274 0 402718720 0.2779142261 0.0290892497 -0.0835299492 150 5.9600000000 0.0233826265 0.0158957507 0.0324170515 0.0136650694 0.0284520000 359087126 0 402718720 0.2742708027 0.0247300956 -0.0809431225 151 6.0000000000 0.0218326990 0.0159350683 0.0324170515 0.0136461322 0.0280570000 359089578 0 402718720 0.2697280645 0.0228829049 -0.0766733363 152 6.0400000000 0.0180103444 0.0159487214 0.0324170515 0.0136377359 0.0283870000 359093422 0 402718720 0.2616174221 0.0245382134 -0.0747174770 153 6.0800000000 0.0218345355 0.0159871908 0.0324170515 0.0136091157 0.0279710000 359096654 0 402718720 0.2620943487 0.0215013213 -0.0741953924 154 6.1200000000 0.0259291064 0.0160517487 0.0324170515 0.0135989470 0.0401240000 359099346 0 402718720 0.2628385723 0.0266091097 -0.0734644532 155 6.1600000000 0.0177849811 0.0160629308 0.0324170515 0.0136173298 0.0283940000 359102542 0 402718720 0.2487087399 0.0307974294 -0.0644070581 156 6.2000000000 0.0187047441 0.0160798655 0.0324170515 0.0135996085 0.0291890000 359105734 0 402718720 0.2476722747 0.0243668407 -0.0624482259 157 6.2400000000 0.0184510760 0.0160949688 0.0324170515 0.0136067274 0.0287370000 359110134 0 402718720 0.2426727563 0.0288018808 -0.0625061542 158 6.2800000000 0.0212492570 0.0161275908 0.0324170515 0.0136136661 0.0290470000 359113658 0 402718720 0.2417667508 0.0330617428 -0.0614107698 159 6.3200000000 0.0195013713 0.0161488096 0.0324170515 0.0136202755 0.0289080000 359116038 0 402718720 0.2369415462 0.0307096113 -0.0591499247 160 6.3600000000 0.0168556497 0.0161532273 0.0324170515 0.0136227951 0.0416300000 359119194 0 402718720 0.2312640548 0.0315982737 -0.0561074950 161 6.4000000000 0.0185705200 0.0161682416 0.0324170515 0.0136227155 0.0382440000 359121762 0 402718720 0.2284688652 0.0367441401 -0.0539585575 162 6.4400000000 0.0194017012 0.0161882012 0.0324170515 0.0136211161 0.0402600000 359125526 0 402718720 0.2271708250 0.0268426463 -0.0540660955 163 6.4800000000 0.0214835461 0.0162206880 0.0324170515 0.0136241184 0.0285840000 359127798 0 402718720 0.2243613899 0.0302236713 -0.0559409820 164 6.5200000000 0.0171173662 0.0162261555 0.0324170515 0.0136221789 0.0291990000 359130498 0 402718720 0.2167848200 0.0307384059 -0.0515368432 165 6.5600000000 0.0159564428 0.0162245209 0.0324170515 0.0136083028 0.0293870000 359133974 0 402718720 0.2111001313 0.0349145308 -0.0469981208 166 6.6000000000 0.0189386848 0.0162408713 0.0324170515 0.0136192711 0.0289800000 359137066 0 402718720 0.2078419328 0.0357019268 -0.0465571508 167 6.6400000000 0.0159881562 0.0162393580 0.0324170515 0.0136316263 0.0388940000 359140506 0 402718720 0.2021160424 0.0313805193 -0.0449478552 168 6.6800000000 0.0219434705 0.0162733111 0.0324170515 0.0136175623 0.0295390000 359145302 0 402718720 0.2041508704 0.0290263053 -0.0470186733 169 6.7200000000 0.0137223704 0.0162582167 0.0324170515 0.0136886340 0.0294710000 359147750 0 402718720 0.1919037104 0.0333857797 -0.0387755223 170 6.7600000000 0.0186746400 0.0162724310 0.0324170515 0.0137022813 0.0375610000 359149854 0 402718720 0.1925294101 0.0343165062 -0.0399321169 171 6.8000000000 0.0177430511 0.0162810311 0.0324170515 0.0136977273 0.0296630000 359152162 0 402718720 0.1905221641 0.0310229566 -0.0386818796 172 6.8400000000 0.0179635808 0.0162908134 0.0324170515 0.0137273607 0.0292200000 359155614 0 402718720 0.1876382530 0.0366370566 -0.0349055827 173 6.8800000000 0.0197946131 0.0163110666 0.0324170515 0.0137484344 0.0295320000 359159206 0 402718720 0.1891503185 0.0330650285 -0.0397449397 174 6.9200000000 0.0163361318 0.0163112106 0.0324170515 0.0137880559 0.0293140000 359161178 0 402718720 0.1838636100 0.0344651975 -0.0337390155 175 6.9600000000 0.0188633464 0.0163257942 0.0324170515 0.0138076400 0.0293330000 359165722 0 402718720 0.1868739277 0.0329564027 -0.0363049693 176 7.0000000000 0.0140574500 0.0163129059 0.0324170515 0.0138385895 0.0293350000 359167990 0 402718720 0.1805345863 0.0377092548 -0.0329360887 177 7.0400000000 0.0129900910 0.0162941330 0.0324170515 0.0138744427 0.0421360000 359171490 0 402718720 0.1765922606 0.0398436487 -0.0308246408 178 7.0800000000 0.0144637097 0.0162838497 0.0324170515 0.0138950025 0.0289820000 359174930 0 402718720 0.1775932461 0.0365247279 -0.0306982249 179 7.1200000000 0.0153328702 0.0162785370 0.0324170515 0.0139686674 0.0293360000 359176978 0 402718720 0.1756011844 0.0386598259 -0.0311361812 180 7.1600000000 0.0126910508 0.0162586065 0.0324170515 0.0139951364 0.0316690000 359663603 0 402718720 0.1726976335 0.0377848521 -0.0322407857 181 7.2000000000 0.0141806044 0.0162471258 0.0324170515 0.0139777155 0.0907730000 359782574 0 402718720 0.1714617163 0.0381679982 -0.0317610651 182 7.2400000000 0.0141400462 0.0162355484 0.0324170515 0.0139724445 0.0841560000 363102962 0 402718720 0.1709949821 0.0392803513 -0.0329195969 183 7.2800000000 0.0145809874 0.0162265071 0.0324170515 0.0139558488 0.0447770000 363070230 0 402718720 0.1669698805 0.0399489738 -0.0317503959 184 7.3200000000 0.0141911181 0.0162154452 0.0324170515 0.0139776129 0.0483250000 361981373 0 402718720 0.1608426422 0.0444918051 -0.0279108845 185 7.3600000000 0.0116020162 0.0161905078 0.0324170515 0.0139599444 0.0339190000 359795114 0 402718720 0.1557476223 0.0407268628 -0.0263572261 186 7.4000000000 0.0126112616 0.0161712645 0.0324170515 0.0139679976 0.0337770000 359799102 0 402718720 0.1561520100 0.0418366864 -0.0271964706 187 7.4400000000 0.0139737437 0.0161595131 0.0324170515 0.0139889837 0.0341860000 359801702 0 402718720 0.1529560834 0.0425098911 -0.0253520124 188 7.4800000000 0.0122072026 0.0161384901 0.0324170515 0.0139900322 0.0332560000 359803770 0 402718720 0.1518552750 0.0364956819 -0.0253307968 189 7.5200000000 0.0120787742 0.0161170102 0.0324170515 0.0140330926 0.0335170000 359807226 0 402718720 0.1471378654 0.0412149206 -0.0251873527 190 7.5600000000 0.0123163182 0.0160970065 0.0324170515 0.0140731943 0.0326580000 359809938 0 402718720 0.1455396861 0.0386046246 -0.0242567025 191 7.6000000000 0.0133064035 0.0160823960 0.0324170515 0.0141023166 0.0325470000 359813094 0 402718720 0.1463227868 0.0390236266 -0.0248485021 192 7.6400000000 0.0102853021 0.0160522028 0.0324170515 0.0141395156 0.0325120000 359815546 0 402718720 0.1371134967 0.0407189056 -0.0215888768 193 7.6800000000 0.0105922520 0.0160239129 0.0324170515 0.0141514488 0.0431740000 359818106 0 402718720 0.1394631416 0.0376294404 -0.0218781456 194 7.7200000000 0.0132005429 0.0160093595 0.0324170515 0.0141562317 0.0314910000 359822878 0 402718720 0.1387016326 0.0390743725 -0.0229182020 195 7.7600000000 0.0105551258 0.0159813890 0.0324170515 0.0141503157 0.0409070000 359825010 0 402718720 0.1376976222 0.0380991921 -0.0225541033 196 7.8000000000 0.0125739491 0.0159640041 0.0324170515 0.0141400945 0.0311220000 359827842 0 402718720 0.1340944469 0.0413496085 -0.0229299888 197 7.8400000000 0.0090680951 0.0159289995 0.0324170515 0.0141414706 0.0436540000 359830498 0 402718720 0.1366578192 0.0360683538 -0.0219370499 198 7.8800000000 0.0127115492 0.0159127498 0.0324170515 0.0141562767 0.0308890000 359833626 0 402718720 0.1360062808 0.0418138281 -0.0215329640 199 7.9200000000 0.0121339485 0.0158937608 0.0324170515 0.0141743745 0.0411630000 359836694 0 402718720 0.1404346675 0.0431430787 -0.0224399157 200 7.9600000000 0.0090674385 0.0158596292 0.0324170515 0.0141857117 0.0300400000 359839422 0 402718720 0.1369087994 0.0423977636 -0.0232796613 201 8.0000000000 0.0126834735 0.0158438275 0.0324170515 0.0142023687 0.0403110000 359841326 0 402718720 0.1421011090 0.0446532331 -0.0221245065 202 8.0400000000 0.0141553860 0.0158354688 0.0324170515 0.0141923562 0.0298510000 359844822 0 402718720 0.1420157254 0.0451000929 -0.0216293428 203 8.0800000000 0.0130206756 0.0158216029 0.0324170515 0.0141765115 0.0306490000 359848318 0 402718720 0.1376699656 0.0461625122 -0.0210802425 204 8.1200000000 0.0105588846 0.0157958052 0.0324170515 0.0141487275 0.0306560000 359852102 0 402718720 0.1327051818 0.0487600304 -0.0204436854 205 8.1600000000 0.0155278957 0.0157944983 0.0324170515 0.0141233732 0.0307310000 359853158 0 402718720 0.1359201372 0.0490877926 -0.0204432495 206 8.1999999990 0.0124502834 0.0157782643 0.0324170515 0.0141007664 0.0300990000 359856874 0 402718720 0.1318502277 0.0430337042 -0.0180912353 207 8.2400000000 0.0169228129 0.0157837935 0.0324170515 0.0140936467 0.0426240000 359859550 0 402718720 0.1346689463 0.0458903536 -0.0171380229 208 8.2799999990 0.0154560963 0.0157822180 0.0324170515 0.0141149755 0.0298150000 359862442 0 402718720 0.1326114535 0.0440883227 -0.0150662754 209 8.3200000000 0.0101985848 0.0157555021 0.0324170515 0.0141212299 0.0297620000 359864714 0 402718720 0.1280694008 0.0405160449 -0.0164394155 210 8.3599999990 0.0143624591 0.0157488686 0.0324170515 0.0141392652 0.0295860000 359866266 0 402718720 0.1285533458 0.0463775992 -0.0145204272 211 8.4000000000 0.0106241507 0.0157245808 0.0324170515 0.0141751144 0.0293950000 359870738 0 402718720 0.1228416413 0.0456879660 -0.0142626977 212 8.4399999990 0.0138003416 0.0157155042 0.0324170515 0.0141963604 0.0291980000 359872934 0 402718720 0.1252793223 0.0453430563 -0.0106471851 213 8.4800000000 0.0163449682 0.0157184594 0.0324170515 0.0142157300 0.0287330000 359875442 0 402718720 0.1222070083 0.0504213125 -0.0114373611 214 8.5200000000 0.0122565934 0.0157022825 0.0324170515 0.0142249082 0.0291450000 359878038 0 402718720 0.1189702004 0.0460928753 -0.0094807493 215 8.5600000000 0.0182324685 0.0157140508 0.0324170515 0.0142501601 0.0283710000 359880426 0 402718720 0.1234127954 0.0460174270 -0.0074904365 216 8.6000000000 0.0153126279 0.0157121923 0.0324170515 0.0142661234 0.0281520000 359884078 0 402718720 0.1246973202 0.0462633893 -0.0065391343 217 8.6400000000 0.0102235349 0.0156868990 0.0324170515 0.0142719674 0.0280640000 359884918 0 402718720 0.1191515103 0.0473477542 -0.0050537270 218 8.6800000000 0.0127056679 0.0156732236 0.0324170515 0.0142815995 0.0269720000 359888002 0 402718720 0.1214975789 0.0513317883 -0.0021841750 219 8.7200000000 0.0131199202 0.0156615647 0.0324170515 0.0142953540 0.0319710000 360631611 0 402718720 0.1259813458 0.0480601527 0.0009647887 220 8.7600000000 0.0116828773 0.0156434798 0.0324170515 0.0143169632 0.1015720000 360622031 0 402718720 0.1227512434 0.0483550131 0.0049411207 221 8.8000000000 0.0103933783 0.0156197236 0.0324170515 0.0143376524 0.0865680000 362461591 0 402718720 0.1229608208 0.0480966792 0.0076122992 222 8.8400000000 0.0115199024 0.0156012560 0.0324170515 0.0143530753 0.0541720000 364587859 0 402718720 0.1250458807 0.0482383668 0.0089465678 223 8.8800000000 0.0115166744 0.0155829395 0.0324170515 0.0144061662 0.0642780000 364339333 0 402718720 0.1186290383 0.0516206697 0.0114250127 224 8.9200000000 0.0133967455 0.0155731797 0.0324170515 0.0144234081 0.0314830000 360637251 0 402718720 0.1169863939 0.0529126823 0.0107502565 225 8.9600000000 0.0159859825 0.0155750144 0.0324170515 0.0145739353 0.0313580000 360639967 0 402718720 0.0788012445 0.0477133989 -0.0032308586 226 9.0000000000 0.0188260768 0.0155893996 0.0324170515 0.0145792376 0.0306590000 360643823 0 402718720 0.0781377256 0.0506357960 -0.0061157625 227 9.0400000000 0.0170822535 0.0155959760 0.0324170515 0.0145838754 0.0298820000 360648075 0 402718720 0.0714487508 0.0504345074 -0.0047193142 228 9.0800000000 0.0163190309 0.0155991473 0.0324170515 0.0145838392 0.0401570000 360649255 0 402718720 0.0686166435 0.0485334396 -0.0045543481 229 9.1200000000 0.0152202351 0.0155974927 0.0324170515 0.0145944472 0.0292030000 360653495 0 402718720 0.0590148456 0.0505885519 -0.0037683593 230 9.1600000000 0.0181957763 0.0156087896 0.0324170515 0.0146132221 0.0456800000 361346215 0 402718720 0.0549486317 0.0540427044 -0.0040762760 231 9.2000000000 0.0181367770 0.0156197332 0.0324170515 0.0146118760 0.1067680000 361625063 0 402718720 0.0513058752 0.0533988252 -0.0040366985 232 9.2400000000 0.0176240839 0.0156283727 0.0324170515 0.0146158742 0.0989400000 366188599 0 402718720 0.0467226580 0.0524169393 -0.0027229823 233 9.2800000000 0.0192963760 0.0156441152 0.0324170515 0.0146291391 0.0392630000 366144599 0 402718720 0.0463056080 0.0543459058 -0.0044064438 234 9.3200000000 0.0157516692 0.0156445748 0.0324170515 0.0146318284 0.0755130000 366076059 0 402718720 0.0389397666 0.0522400476 -0.0073831510 235 9.3600000000 0.0140565829 0.0156378174 0.0324170515 0.0146438228 0.0350460000 361439267 0 402718720 0.0359272361 0.0497843958 -0.0064529357 236 9.4000000000 0.0142968735 0.0156321354 0.0324170515 0.0146831386 0.0348050000 361441735 0 402718720 0.0311575104 0.0496184789 -0.0063716788 237 9.4400000000 0.0169256199 0.0156375932 0.0324170515 0.0147264291 0.0341050000 361444703 0 402718720 0.0289876238 0.0493830070 -0.0068231756 238 9.4800000000 0.0168655254 0.0156427526 0.0324170515 0.0147429373 0.0338200000 361446999 0 402718720 0.0230812244 0.0457221866 -0.0070530633 239 9.5200000000 0.0171146337 0.0156489111 0.0324170515 0.0147511507 0.0449800000 361450011 0 402718720 0.0229718275 0.0460072681 -0.0076773204 240 9.5600000000 0.0183348861 0.0156601026 0.0324170515 0.0148971128 0.0324760000 361452175 0 402718720 0.0177158676 0.0413026102 -0.0056673810 241 9.6000000000 0.0201116595 0.0156785738 0.0324170515 0.0148952352 0.0313180000 361455415 0 402718720 0.0100538488 0.0427390225 -0.0058265096 242 9.6400000000 0.0194801427 0.0156942828 0.0324170515 0.0149066341 0.0308490000 361458867 0 402718720 0.0131150922 0.0402084477 -0.0061092414 243 9.6800000000 0.0171297230 0.0157001899 0.0324170515 0.0149202880 0.0309250000 361461143 0 402718720 0.0100704003 0.0350635052 -0.0057988176 244 9.7200000000 0.0183808170 0.0157111761 0.0324170515 0.0149249759 0.0298690000 361463719 0 402718720 0.0092285126 0.0355861001 -0.0048610684 245 9.7600000000 0.0197722558 0.0157277520 0.0324170515 0.0149281823 0.0345430000 362168727 0 402718720 0.0027508019 0.0370557606 -0.0042614904 246 9.8000000000 0.0221220888 0.0157537452 0.0324170515 0.0149502977 0.1150180000 362478439 0 402718720 0.0019248943 0.0384774059 -0.0047142305 247 9.8400000000 0.0208198801 0.0157742559 0.0324170515 0.0149489364 0.1028000000 367658091 0 402718720 -0.0018686304 0.0362442657 -0.0044722063 248 9.8800000000 0.0209111460 0.0157949691 0.0324170515 0.0149454980 0.0909690000 367538711 0 402718720 -0.0041741095 0.0330565497 -0.0045314552 249 9.9200000000 0.0221787430 0.0158206068 0.0324170515 0.0149489339 0.0375730000 362256071 0 402718720 -0.0097066555 0.0309903696 -0.0063767368 250 9.9600000000 0.0226205569 0.0158478066 0.0324170515 0.0149402351 0.0368450000 362258735 0 402718720 -0.0122125577 0.0316559412 -0.0072877361 251 10.0000000000 0.0211208798 0.0158688148 0.0324170515 0.0149344687 0.0563360000 362261363 0 402718720 -0.0120355478 0.0282526463 -0.0087000718 252 10.0400000000 0.0216795262 0.0158918732 0.0324170515 0.0149377333 0.0353160000 362263775 0 402718720 -0.0167671517 0.0266530011 -0.0100601399 253 10.0800000000 0.0202593263 0.0159091359 0.0324170515 0.0149229656 0.0352830000 362266267 0 402718720 -0.0193314422 0.0244741905 -0.0104669333 254 10.1200000000 0.0195630398 0.0159235213 0.0324170515 0.0149148634 0.0349180000 362268775 0 402718720 -0.0228484757 0.0218168758 -0.0111114513 255 10.1600000000 0.0214771591 0.0159453003 0.0324170515 0.0149257319 0.0339760000 362271051 0 402718720 -0.0251956098 0.0229585115 -0.0128376009 256 10.2000000000 0.0205974169 0.0159634726 0.0324170515 0.0149137634 0.0338120000 362273663 0 402718720 -0.0286594648 0.0207575113 -0.0133333961 257 10.2400000000 0.0224037431 0.0159885320 0.0324170515 0.0150309416 0.0459840000 362276047 0 402718720 -0.0355771929 0.0180820469 -0.0129903974 258 10.2800000000 0.0224737432 0.0160136685 0.0324170515 0.0150351498 0.0334210000 362330699 0 402718720 -0.0364894718 0.0179351065 -0.0152558982 259 10.3200000000 0.0209732093 0.0160328173 0.0324170515 0.0150168705 0.0435480000 362332759 0 402718720 -0.0385920741 0.0150820315 -0.0156729668 260 10.3600000000 0.0214643404 0.0160537078 0.0324170515 0.0150053494 0.0323350000 362335123 0 402718720 -0.0400865898 0.0139602832 -0.0166321900 261 10.4000000000 0.0197866503 0.0160680103 0.0324170515 0.0149824506 0.0321470000 362337615 0 402718720 -0.0398203321 0.0114699285 -0.0183602050 262 10.4400000000 0.0209783539 0.0160867520 0.0324170515 0.0149681790 0.0326220000 362340199 0 402718720 -0.0420601889 0.0108846379 -0.0190092288 263 10.4800000000 0.0210200287 0.0161055097 0.0324170515 0.0149505540 0.0407050000 362343535 0 402718720 -0.0428218246 0.0096947467 -0.0195835382 264 10.5200000000 0.0203185752 0.0161214683 0.0324170515 0.0149271960 0.0309800000 362345659 0 402718720 -0.0467112623 0.0076505621 -0.0206908267 265 10.5600000000 0.0201767311 0.0161367712 0.0324170515 0.0149099456 0.0432440000 362347887 0 402718720 -0.0474288762 0.0057406016 -0.0232841000 266 10.6000000000 0.0210950058 0.0161554112 0.0324170515 0.0149091871 0.0360770000 363052007 0 402718720 -0.0489874408 0.0045455988 -0.0247251820 267 10.6400000000 0.0212360006 0.0161744396 0.0324170515 0.0149115561 0.1202230000 363126196 0 402718720 -0.0501028299 0.0039116032 -0.0263868533 268 10.6800000000 0.0212542489 0.0161933941 0.0324170515 0.0149162590 0.1117830000 367084804 0 402718720 -0.0519268699 0.0020152058 -0.0277945716 269 10.7200000000 0.0222836901 0.0162160346 0.0324170515 0.0149366218 0.0840260000 368961040 0 402718720 -0.0551181212 0.0011671075 -0.0290103126 270 10.7600000000 0.0217252634 0.0162364392 0.0324170515 0.0149534838 0.0999230000 368947997 0 402718720 -0.0596008077 -0.0012894159 -0.0309429970 271 10.8000000000 0.0205247384 0.0162522631 0.0324170515 0.0149434157 0.0373070000 363133392 0 402718720 -0.0631680712 -0.0043237126 -0.0330198258 272 10.8400000000 0.0201096013 0.0162664445 0.0324170515 0.0149537999 0.0376680000 363135896 0 402718720 -0.0651143715 -0.0064850464 -0.0348834768 273 10.8800000000 0.0213450771 0.0162850476 0.0324170515 0.0149763770 0.0381490000 363138336 0 402718720 -0.0673665777 -0.0070599974 -0.0370751396 274 10.9200000000 0.0204634164 0.0163002971 0.0324170515 0.0149774699 0.0413130000 363140640 0 402718720 -0.0701743886 -0.0095166806 -0.0385681689 275 10.9600000000 0.0202957466 0.0163148260 0.0324170515 0.0149875371 0.0385770000 363143256 0 402718720 -0.0708712116 -0.0118816700 -0.0397296585 276 11.0000000000 0.0213404782 0.0163330349 0.0324170515 0.0149907408 0.0375310000 363145104 0 402718720 -0.0737539828 -0.0111507326 -0.0420948379 277 11.0400000000 0.0201270208 0.0163467316 0.0324170515 0.0152757938 0.0372060000 363147820 0 402718720 -0.0802785903 -0.0198681522 -0.0490035042 278 11.0800000000 0.0197349600 0.0163589195 0.0324170515 0.0152566125 0.0466630000 363150648 0 402718720 -0.0831828937 -0.0223443992 -0.0508261137 279 11.1200000000 0.0202866849 0.0163729975 0.0324170515 0.0152558548 0.0363670000 363153064 0 402718720 -0.0853489712 -0.0241143797 -0.0519904308 280 11.1600000000 0.0194429178 0.0163839615 0.0324170515 0.0152404008 0.0365650000 363155708 0 402718720 -0.0855229497 -0.0260025710 -0.0522078350 281 11.2000000000 0.0211422220 0.0164008948 0.0324170515 0.0152463575 0.0347460000 363157984 0 402718720 -0.0867697671 -0.0264521614 -0.0533104613 282 11.2400000000 0.0189800169 0.0164100406 0.0324170515 0.0152295572 0.0348380000 363160520 0 402718720 -0.0872248337 -0.0295083858 -0.0547117963 283 11.2800000000 0.0200086087 0.0164227564 0.0324170515 0.0152265732 0.0345390000 363162932 0 402718720 -0.0890230760 -0.0306681115 -0.0556403548 284 11.3200000000 0.0193436444 0.0164330412 0.0324170515 0.0152298299 0.0465810000 363165312 0 402718720 -0.0901607722 -0.0326998308 -0.0567423366 285 11.3600000000 0.0206044875 0.0164476779 0.0324170515 0.0152304639 0.0346520000 363167384 0 402718720 -0.0927744731 -0.0335752293 -0.0572727323 286 11.4000000000 0.0215744302 0.0164656036 0.0324170515 0.0152263274 0.0340920000 363170008 0 402718720 -0.0931225866 -0.0347871594 -0.0583947189 287 11.4400000000 0.0204517096 0.0164794925 0.0324170515 0.0152037912 0.0336630000 363172424 0 402718720 -0.0927516147 -0.0373457372 -0.0591774285 288 11.4800000000 0.0194758698 0.0164898965 0.0324170515 0.0151792836 0.0338040000 363174728 0 402718720 -0.0942550823 -0.0405098498 -0.0608800352 289 11.5200000000 0.0204123668 0.0165034691 0.0324170515 0.0151702023 0.0334410000 363177076 0 402718720 -0.0954176486 -0.0420116037 -0.0611292422 290 11.5600000000 0.0176292676 0.0165073512 0.0324170515 0.0151458063 0.0449180000 363179396 0 402718720 -0.0951368660 -0.0455062538 -0.0627210140 291 11.6000000000 0.0199662186 0.0165192373 0.0324170515 0.0151360727 0.0340150000 363181992 0 402718720 -0.0940323919 -0.0447986312 -0.0630870536 292 11.6400000000 0.0200176183 0.0165312181 0.0324170515 0.0151104521 0.0339270000 363184452 0 402718720 -0.0951306820 -0.0470531732 -0.0637846291 293 11.6800000000 0.0186038315 0.0165382918 0.0324170515 0.0150857222 0.0336330000 363186816 0 402718720 -0.0959804952 -0.0504303798 -0.0638795644 294 11.7200000000 0.0184211824 0.0165446962 0.0324170515 0.0150648855 0.0335410000 363189168 0 402718720 -0.0964716300 -0.0514804497 -0.0650073215 295 11.7600000000 0.0190821495 0.0165532978 0.0324170515 0.0150479397 0.0331250000 363191440 0 402718720 -0.0949223116 -0.0558764972 -0.0648985803 296 11.8000000000 0.0184929091 0.0165598505 0.0324170515 0.0150240370 0.0327190000 363193824 0 402718720 -0.0955644324 -0.0583745204 -0.0657565594 297 11.8400000000 0.0190792736 0.0165683334 0.0324170515 0.0150163114 0.0327220000 363196740 0 402718720 -0.0981098711 -0.0589751266 -0.0659874007 298 11.8800000000 0.0190333463 0.0165766053 0.0324170515 0.0150469334 0.0325710000 363198612 0 402718720 -0.0970936120 -0.0626986697 -0.0682177171 299 11.9200000000 0.0185144953 0.0165830865 0.0324170515 0.0150451703 0.0439060000 363201592 0 402718720 -0.0963551849 -0.0647432283 -0.0699272901 300 11.9600000000 0.0173247159 0.0165855586 0.0324170515 0.0150450350 0.0442510000 363203704 0 402718720 -0.0984119251 -0.0677575842 -0.0702916905 301 12.0000000000 0.0184189361 0.0165916496 0.0324170515 0.0150572014 0.0319380000 363205564 0 402718720 -0.1000821292 -0.0685605705 -0.0714896694 302 12.0400000000 0.0169945247 0.0165929836 0.0324170515 0.0150720061 0.0313980000 363207900 0 402718720 -0.1024205908 -0.0733821318 -0.0747177079 303 12.0800000000 0.0193274915 0.0166020084 0.0324170515 0.0150744195 0.0316210000 363210332 0 402718720 -0.1032216400 -0.0724755079 -0.0768712610 304 12.1200000000 0.0170709155 0.0166035508 0.0324170515 0.0150514416 0.0357400000 363985068 0 402718720 -0.1040852219 -0.0765696689 -0.0796787143 305 12.1600000000 0.0180667024 0.0166083480 0.0324170515 0.0150485805 0.1305330000 364061772 0 402718720 -0.1042927057 -0.0768999085 -0.0807222575 306 12.2000000000 0.0178632140 0.0166124489 0.0324170515 0.0150473153 0.1116580000 369869872 0 402718720 -0.1054348946 -0.0790143684 -0.0831474811 307 12.2400000000 0.0173337664 0.0166147985 0.0324170515 0.0150532441 0.0565050000 369795332 0 402718720 -0.1059590578 -0.0814157128 -0.0849358663 308 12.2800000000 0.0092788674 0.0165909805 0.0324170515 0.0150527970 0.0923650000 369726483 0 402718720 -0.1075036377 -0.0907914490 -0.0899233520 309 12.3200000000 0.0083554173 0.0165643282 0.0324170515 0.0150447510 0.0396950000 364071224 0 402718720 -0.1093328372 -0.0934082121 -0.0932169259 310 12.3600000000 0.0102560529 0.0165439789 0.0324170515 0.0150557322 0.0398830000 364073584 0 402718720 -0.1107740775 -0.0931066349 -0.0961330980 311 12.4000000000 0.0101222144 0.0165233302 0.0324170515 0.0150553782 0.0400170000 364075772 0 402718720 -0.1128292680 -0.0942876637 -0.0985689238 312 12.4400000000 0.0097946376 0.0165017638 0.0324170515 0.0150459196 0.0401710000 364077864 0 402718720 -0.1134079024 -0.0958756879 -0.1011512280 313 12.4800000000 0.0105795786 0.0164828431 0.0324170515 0.0150414327 0.0407030000 364082212 0 402718720 -0.1151945740 -0.0964291841 -0.1034378409 314 12.5200000000 0.0097537991 0.0164614131 0.0324170515 0.0150316942 0.0398000000 364083428 0 402718720 -0.1155379638 -0.0986273140 -0.1058071181 315 12.5600000000 0.0110445237 0.0164442166 0.0324170515 0.0150431812 0.0391480000 364085784 0 402718720 -0.1167210191 -0.0982266814 -0.1083180532 316 12.6000000000 0.0108333863 0.0164264608 0.0324170515 0.0150387396 0.0493510000 364088892 0 402718720 -0.1190391779 -0.0995929018 -0.1102454141 317 12.6400000000 0.0111265043 0.0164097417 0.0324170515 0.0150283674 0.0382550000 364091128 0 402718720 -0.1199430302 -0.1001105756 -0.1128559411 318 12.6800000000 0.0087989513 0.0163858084 0.0324170515 0.0150062004 0.0381310000 364093872 0 402718720 -0.1205991134 -0.1033180654 -0.1159902960 319 12.7200000000 0.0102063725 0.0163664371 0.0324170515 0.0150344184 0.0373250000 364095600 0 402718720 -0.1236949861 -0.1029628366 -0.1211742237 320 12.7600000000 0.0102917384 0.0163474537 0.0324170515 0.0150231082 0.0380800000 364099116 0 402718720 -0.1238811240 -0.1039319038 -0.1227887049 321 12.8000000000 0.0093291551 0.0163255898 0.0324170515 0.0150076522 0.0387800000 364100792 0 402718720 -0.1255560517 -0.1051421165 -0.1250444800 322 12.8400000000 0.0095066661 0.0163044130 0.0324170515 0.0149933653 0.0471300000 364104356 0 402718720 -0.1270877272 -0.1056518480 -0.1271195114 323 12.8800000000 0.0091799693 0.0162823559 0.0324170515 0.0149786240 0.0377900000 364106552 0 402718720 -0.1294450462 -0.1059067547 -0.1298668981 324 12.9200000000 0.0097853038 0.0162623033 0.0324170515 0.0149663478 0.0368670000 364109624 0 402718720 -0.1296675503 -0.1054713577 -0.1314554662 325 12.9600000000 0.0099185864 0.0162427842 0.0324170515 0.0149459123 0.0381480000 364112588 0 402718720 -0.1302981079 -0.1051912382 -0.1333735585 326 13.0000000000 0.0088120466 0.0162199905 0.0324170515 0.0149249154 0.0491160000 364114644 0 402718720 -0.1322669685 -0.1059825718 -0.1360813081 327 13.0400000000 0.0116019445 0.0162058680 0.0324170515 0.0149137676 0.0369070000 364116704 0 402718720 -0.1330433786 -0.1025002673 -0.1363130361 328 13.0800000000 0.0115881348 0.0161917896 0.0324170515 0.0148918703 0.0473110000 364119148 0 402718720 -0.1341163665 -0.1013214216 -0.1387770176 329 13.1200000000 0.0110859685 0.0161762704 0.0324170515 0.0148754087 0.0374300000 364122144 0 402718720 -0.1363637894 -0.0998093039 -0.1410573274 330 13.1600000000 0.0105796792 0.0161593110 0.0324170515 0.0148607063 0.0375350000 364124924 0 402718720 -0.1369793564 -0.0988674462 -0.1419955045 331 13.2000000000 0.0102458717 0.0161414456 0.0324170515 0.0148467189 0.0370400000 364126952 0 402718720 -0.1381730735 -0.0968572497 -0.1444455683 332 13.2400000000 0.0115484418 0.0161276113 0.0324170515 0.0148274879 0.0375910000 364129132 0 402718720 -0.1400903612 -0.0930711329 -0.1453577876 333 13.2800000000 0.0103728343 0.0161103297 0.0324170515 0.0148190513 0.0372810000 364131804 0 402718720 -0.1411954761 -0.0918175802 -0.1464462131 334 13.3200000000 0.0100301811 0.0160921256 0.0324170515 0.0148440024 0.0384560000 364134556 0 402718720 -0.1439026892 -0.0861856639 -0.1496550441 335 13.3600000000 0.0101660704 0.0160744359 0.0324170515 0.0148312796 0.0379390000 364136720 0 402718720 -0.1446413398 -0.0832488611 -0.1499864310 336 13.4000000000 0.0112393610 0.0160600458 0.0324170515 0.0148161825 0.0368990000 364139392 0 402718720 -0.1456597298 -0.0792026222 -0.1506364793 337 13.4400000000 0.0112779848 0.0160458557 0.0324170515 0.0148047529 0.0371700000 364141608 0 402718720 -0.1467790008 -0.0767554194 -0.1507592052 338 13.4800000000 0.0124107534 0.0160351010 0.0324170515 0.0147976021 0.0372960000 364143788 0 402718720 -0.1479064375 -0.0733743608 -0.1512502730 339 13.5200000000 0.0120955333 0.0160234798 0.0324170515 0.0148095059 0.0369250000 364146216 0 402718720 -0.1482900977 -0.0710509047 -0.1519296169 340 13.5600000000 0.0124402456 0.0160129409 0.0324170515 0.0148145362 0.0362650000 364148580 0 402718720 -0.1494800448 -0.0686295852 -0.1509114355 341 13.6000000000 0.0111624878 0.0159987167 0.0324170515 0.0148111940 0.0476010000 364151052 0 402718720 -0.1504929960 -0.0671412945 -0.1515320241 342 13.6400000000 0.0125511810 0.0159886362 0.0324170515 0.0147980473 0.0364630000 364153528 0 402718720 -0.1516484320 -0.0626610592 -0.1521636546 343 13.6800000000 0.0114390645 0.0159753721 0.0324170515 0.0148132812 0.0363020000 364156184 0 402718720 -0.1529259384 -0.0613924153 -0.1525931805 344 13.7200000000 0.0114512565 0.0159622206 0.0324170515 0.0148226746 0.0473950000 364158608 0 402718720 -0.1533621252 -0.0585670583 -0.1528608501 345 13.7600000000 0.0118851876 0.0159504031 0.0324170515 0.0149750953 0.0356930000 364160832 0 402718720 -0.1536877155 -0.0529704802 -0.1516078264 346 13.8000000000 0.0121203307 0.0159393336 0.0324170515 0.0149813330 0.0465560000 364163240 0 402718720 -0.1551723033 -0.0499560647 -0.1526202410 347 13.8400000000 0.0136062531 0.0159326100 0.0324170515 0.0149711403 0.0483710000 364165188 0 402718720 -0.1568487883 -0.0455437824 -0.1540934592 348 13.8800000000 0.0127778491 0.0159235446 0.0324170515 0.0149629897 0.0350120000 364167920 0 402718720 -0.1576805860 -0.0434607491 -0.1536266655 349 13.9200000000 0.0129703302 0.0159150827 0.0324170515 0.0149427557 0.0351300000 364170452 0 402718720 -0.1587193757 -0.0397571810 -0.1532686353 350 13.9600000000 0.0116987899 0.0159030361 0.0324170515 0.0149294419 0.0350230000 364172384 0 402718720 -0.1586957872 -0.0385400876 -0.1530607492 351 14.0000000000 0.0124193486 0.0158931111 0.0324170515 0.0149218025 0.0456910000 364174580 0 402718720 -0.1599852741 -0.0343936794 -0.1534324884 352 14.0400000000 0.0123618040 0.0158830789 0.0324170515 0.0149209743 0.0345440000 364177344 0 402718720 -0.1602377594 -0.0315131247 -0.1529207826 353 14.0800000000 0.0116053512 0.0158709607 0.0324170515 0.0149253758 0.0351500000 364179736 0 402718720 -0.1614636481 -0.0286701582 -0.1533628702 354 14.1200000000 0.0130623877 0.0158630269 0.0324170515 0.0149376043 0.0704090000 364182084 0 402718720 -0.1632773429 -0.0241007935 -0.1532915682 355 14.1600000000 0.0113427453 0.0158502937 0.0324170515 0.0149889717 0.0346120000 364184400 0 402718720 -0.1611422896 -0.0231103543 -0.1518343091 356 14.2000000000 0.0138080930 0.0158445572 0.0324170515 0.0150049343 0.0343240000 364186504 0 402718720 -0.1596533358 -0.0185896866 -0.1484460682 357 14.2400000000 0.0143795628 0.0158404536 0.0324170515 0.0149950186 0.0341770000 364189144 0 402718720 -0.1625142395 -0.0138605479 -0.1498050988 358 14.2800000000 0.0142652309 0.0158360535 0.0324170515 0.0150045193 0.0339150000 364191092 0 402718720 -0.1626632959 -0.0113483630 -0.1494494379 359 14.3200000000 0.0138544394 0.0158305337 0.0324170515 0.0150086221 0.0661890000 364193484 0 402718720 -0.1622182280 -0.0090919286 -0.1479821354 360 14.3600000000 0.0109848510 0.0158170735 0.0324170515 0.0150275781 0.0336630000 364195800 0 402718720 -0.1653858870 -0.0084364861 -0.1495226026 361 14.4000000000 0.0119371554 0.0158063258 0.0324170515 0.0150252872 0.0338010000 364198088 0 402718720 -0.1632602364 -0.0049119773 -0.1473466903 362 14.4400000000 0.0140305813 0.0158014204 0.0324170515 0.0150183342 0.0337030000 364200480 0 402718720 -0.1634113193 -0.0001553776 -0.1464955360 363 14.4800000000 0.0145352492 0.0157979323 0.0324170515 0.0150106500 0.0336340000 364202892 0 402718720 -0.1649182886 0.0025501736 -0.1465944052 364 14.5200000000 0.0157474168 0.0157977936 0.0324170515 0.0150048412 0.0338840000 364205576 0 402718720 -0.1642045528 0.0066394554 -0.1458857507 365 14.5600000000 0.0157204010 0.0157975815 0.0324170515 0.0150188206 0.0336180000 364207708 0 402718720 -0.1634332091 0.0082327919 -0.1438437551 366 14.6000000000 0.0150600607 0.0157955664 0.0324170515 0.0151045691 0.0333650000 364210148 0 402718720 -0.1618246585 0.0138479611 -0.1426643133 367 14.6400000000 0.0164642371 0.0157973884 0.0324170515 0.0151113386 0.0434470000 364212252 0 402718720 -0.1617651135 0.0182225909 -0.1417939365 368 14.6800000000 0.0127815092 0.0157891931 0.0324170515 0.0151508570 0.0444360000 364214644 0 402718720 -0.1625129879 0.0174754988 -0.1404910535 369 14.7200000000 0.0140165649 0.0157843892 0.0324170515 0.0151513644 0.0336110000 364216748 0 402718720 -0.1604205072 0.0259113144 -0.1374504417 370 14.7600000000 0.0159840621 0.0157849289 0.0324170515 0.0151495456 0.0466530000 364219004 0 402718720 -0.1577604711 0.0309893079 -0.1345722973 371 14.8000000000 0.0147650540 0.0157821799 0.0324170515 0.0151570940 0.0338650000 364221612 0 402718720 -0.1557600498 0.0320303440 -0.1317685843 372 14.8400000000 0.0134546850 0.0157759232 0.0324170515 0.0151624472 0.0337730000 364223960 0 402718720 -0.1556060016 0.0329241678 -0.1292673647 373 14.8800000000 0.0156790633 0.0157756635 0.0324170515 0.0151470659 0.0336100000 364226292 0 402718720 -0.1548320204 0.0382929184 -0.1267609298 374 14.9200000000 0.0148658482 0.0157732309 0.0324170515 0.0151404271 0.0338420000 364228992 0 402718720 -0.1524771899 0.0404565036 -0.1236529946 375 14.9600000000 0.0141049186 0.0157687820 0.0324170515 0.0151389040 0.0335690000 364231184 0 402718720 -0.1518511623 0.0424738303 -0.1205149665 376 15.0000000000 0.0150722181 0.0157669295 0.0324170515 0.0151378490 0.0454480000 364233440 0 402718720 -0.1495301872 0.0457315743 -0.1176861003 377 15.0400000000 0.0134163108 0.0157606944 0.0324170515 0.0151787957 0.0345230000 364235480 0 402718720 -0.1465433389 0.0461325273 -0.1149747819 378 15.0800000000 0.0135316746 0.0157547975 0.0324170515 0.0151815687 0.0349630000 364237964 0 402718720 -0.1454900205 0.0493544415 -0.1131591350 379 15.1200000000 0.0142827425 0.0157509135 0.0324170515 0.0151736746 0.0343560000 364240080 0 402718720 -0.1429327577 0.0527406596 -0.1112732813 380 15.1600000000 0.0158281848 0.0157511168 0.0324170515 0.0151738034 0.0345020000 364242920 0 402718720 -0.1406320333 0.0558927581 -0.1074941382 381 15.2000000000 0.0154749071 0.0157503919 0.0324170515 0.0151805924 0.0345780000 364244932 0 402718720 -0.1382209510 0.0571228899 -0.1055887640 382 15.2400000000 0.0166602358 0.0157527736 0.0324170515 0.0151713816 0.0406960000 365053560 0 402718720 -0.1345265955 0.0598495193 -0.1039409339 383 15.2800000000 0.0163979232 0.0157544581 0.0324170515 0.0151672955 0.1188870000 364994696 0 402718720 -0.1328610033 0.0612467006 -0.1019762307 384 15.3200000000 0.0163748022 0.0157560736 0.0324170515 0.0151858502 0.1169930000 370347232 0 402718720 -0.1305928826 0.0624766611 -0.1000569612 385 15.3600000000 0.0163640231 0.0157576527 0.0324170515 0.0151864643 0.0746230000 371365539 0 402718720 -0.1284486204 0.0631343126 -0.0980920494 386 15.4000000000 0.0160479173 0.0157584047 0.0324170515 0.0151777172 0.1017110000 371278785 0 402718720 -0.1231969073 0.0640703514 -0.0963713899 387 15.4400000000 0.0155453235 0.0157578541 0.0324170515 0.0151779377 0.0406170000 365001388 0 402718720 -0.1202946231 0.0642151684 -0.0935302973 388 15.4800000000 0.0132651422 0.0157514295 0.0324170515 0.0152054228 0.0391880000 365003444 0 402718720 -0.1188634411 0.0629782453 -0.0909745023 389 15.5200000000 0.0148402480 0.0157490872 0.0324170515 0.0152012029 0.0385710000 365005836 0 402718720 -0.1154556572 0.0659614429 -0.0894474089 390 15.5600000000 0.0138836280 0.0157443039 0.0324170515 0.0151994665 0.0396590000 365008276 0 402718720 -0.1128584072 0.0652967319 -0.0860980898 391 15.6000000000 0.0151837496 0.0157428703 0.0324170515 0.0151881362 0.0386400000 365010300 0 402718720 -0.1106292605 0.0675716624 -0.0841440782 392 15.6400000000 0.0159018394 0.0157432758 0.0324170515 0.0151847409 0.0378080000 365012540 0 402718720 -0.1077442244 0.0682647526 -0.0815835297 393 15.6800000000 0.0149358241 0.0157412213 0.0324170515 0.0151821867 0.0381600000 365015272 0 402718720 -0.1049614772 0.0674588829 -0.0792093277 394 15.7200000000 0.0153308343 0.0157401797 0.0324170515 0.0151854130 0.0476890000 365017464 0 402718720 -0.1020130292 0.0693286434 -0.0774730518 395 15.7600000000 0.0153588029 0.0157392142 0.0324170515 0.0151938566 0.0382080000 365019612 0 402718720 -0.0991758257 0.0692901835 -0.0754450113 396 15.8000000000 0.0150312856 0.0157374265 0.0324170515 0.0151897595 0.0377430000 365022020 0 402718720 -0.0951742530 0.0694130361 -0.0739161074 397 15.8400000000 0.0157300085 0.0157374078 0.0324170515 0.0151794859 0.0370830000 365024336 0 402718720 -0.0913143605 0.0714855716 -0.0715263486 398 15.8800000000 0.0151046682 0.0157358180 0.0324170515 0.0151739696 0.0373170000 365026744 0 402718720 -0.0899819359 0.0712132677 -0.0709902272 399 15.9200000000 0.0158493668 0.0157361026 0.0324170515 0.0151638048 0.0368110000 365028936 0 402718720 -0.0879653767 0.0737009048 -0.0690800920 400 15.9600000000 0.0155350948 0.0157356000 0.0324170515 0.0151579605 0.0367490000 365031360 0 402718720 -0.0867221206 0.0728786215 -0.0689740926 401 16.0000000000 0.0155767910 0.0157352040 0.0324170515 0.0151455988 0.0362910000 365033624 0 402718720 -0.0853175223 0.0725169182 -0.0678758547 402 16.0400000000 0.0143219680 0.0157316885 0.0324170515 0.0151463608 0.0357820000 365035848 0 402718720 -0.0822883472 0.0712362826 -0.0673201755 403 16.0800000000 0.0156842824 0.0157315709 0.0324170515 0.0151388947 0.0351360000 365038532 0 402718720 -0.0804259479 0.0708114058 -0.0664019957 404 16.1200000000 0.0168545637 0.0157343505 0.0324170515 0.0151378266 0.0346000000 365040540 0 402718720 -0.0777978599 0.0719098821 -0.0661940053 405 16.1600000000 0.0131189721 0.0157278928 0.0324170515 0.0151561625 0.0464680000 365043056 0 402718720 -0.0772875100 0.0697299242 -0.0642901137 406 16.2000000000 0.0153620951 0.0157269918 0.0324170515 0.0151482893 0.0335330000 365045064 0 402718720 -0.0743044093 0.0723055452 -0.0633875057 407 16.2400000000 0.0145716956 0.0157241533 0.0324170515 0.0151578722 0.0334760000 365047564 0 402718720 -0.0713928193 0.0713831633 -0.0613757707 408 16.2800000000 0.0140364608 0.0157200168 0.0324170515 0.0151688617 0.0338400000 365049696 0 402718720 -0.0676818937 0.0708402544 -0.0608035065 409 16.3200000000 0.0135661541 0.0157147506 0.0324170515 0.0151592931 0.0340990000 365052012 0 402718720 -0.0657108128 0.0709928870 -0.0588059351 410 16.3600000000 0.0140947141 0.0157107993 0.0324170515 0.0151563305 0.0456630000 365054296 0 402718720 -0.0629152209 0.0707603842 -0.0560466461 411 16.3999999990 0.0138759026 0.0157063348 0.0324170515 0.0151699471 0.0337310000 365056692 0 402718720 -0.0600806996 0.0693918541 -0.0556082539 412 16.4400000000 0.0141242575 0.0157024948 0.0324170515 0.0151718341 0.0326550000 365059160 0 402718720 -0.0581721887 0.0694247484 -0.0541151688 413 16.4800000000 0.0130100269 0.0156959755 0.0324170515 0.0151794365 0.0478610000 365061724 0 402718720 -0.0577271171 0.0671326593 -0.0520238727 414 16.5200000000 0.0125623783 0.0156884065 0.0324170515 0.0151741161 0.0336190000 365064188 0 402718720 -0.0547770821 0.0668411180 -0.0517116599 415 16.5599999990 0.0124933058 0.0156807074 0.0324170515 0.0151650957 0.0331040000 365066464 0 402718720 -0.0518858097 0.0671922415 -0.0508538000 416 16.6000000000 0.0131474938 0.0156746180 0.0324170515 0.0151501781 0.0332180000 365069104 0 402718720 -0.0519368052 0.0682109967 -0.0498801544 417 16.6400000000 0.0133532938 0.0156690512 0.0324170515 0.0151418273 0.0439570000 365071408 0 402718720 -0.0479811542 0.0688131079 -0.0492350347 418 16.6800000000 0.0128850099 0.0156623909 0.0324170515 0.0151360870 0.0336840000 365073664 0 402718720 -0.0454293936 0.0666930526 -0.0495487526 419 16.7199999990 0.0130703505 0.0156562046 0.0324170515 0.0151271113 0.0370430000 365707336 0 402718720 -0.0435647927 0.0665244162 -0.0488184355 420 16.7600000000 0.0134026352 0.0156508390 0.0324170515 0.0151219628 0.1270670000 365773344 0 402718720 -0.0419701301 0.0653655827 -0.0473892689 421 16.8000000000 0.0126928901 0.0156438130 0.0324170515 0.0151242029 0.1096820000 365783160 0 402718720 -0.0408537462 0.0631791651 -0.0455697775 422 16.8400000000 0.0130344564 0.0156376296 0.0324170515 0.0151177783 0.1080290000 371235960 0 402718720 -0.0389725268 0.0641567409 -0.0453738086 423 16.8799999990 0.0130605893 0.0156315374 0.0324170515 0.0151130745 0.0841960000 373154531 0 402718720 -0.0364402495 0.0629600510 -0.0438913442 424 16.9200000000 0.0124305747 0.0156239879 0.0324170515 0.0151039307 0.0427490000 373144876 0 402718720 -0.0346217677 0.0613102056 -0.0426006056 425 16.9600000000 0.0084366184 0.0156070765 0.0324170515 0.0151180300 0.1101820000 373076439 0 402718720 -0.0316740349 0.0566167161 -0.0403839685 426 17.0000000000 0.0085082240 0.0155904125 0.0324170515 0.0151116033 0.0371030000 365792540 0 402718720 -0.0310062449 0.0531397425 -0.0382964686 427 17.0400000000 0.0080489591 0.0155727510 0.0324170515 0.0151073097 0.0502350000 365794780 0 402718720 -0.0271471720 0.0513039976 -0.0372328758 428 17.0800000000 0.0071667456 0.0155531108 0.0324170515 0.0151025155 0.0379240000 365797008 0 402718720 -0.0261327028 0.0506651402 -0.0360541865 429 17.1200000000 0.0081725698 0.0155359067 0.0324170515 0.0150952258 0.0378060000 365799448 0 402718720 -0.0222897641 0.0508647636 -0.0349734575 430 17.1600000000 0.0089005921 0.0155204758 0.0324170515 0.0150844985 0.0369680000 365801464 0 402718720 -0.0185176432 0.0537914000 -0.0350412615 431 17.2000000000 0.0072604637 0.0155013110 0.0324170515 0.0150825928 0.0362480000 365803664 0 402718720 -0.0167618580 0.0518248193 -0.0342696495 432 17.2400000000 0.0078060394 0.0154834979 0.0324170515 0.0150866007 0.0359380000 365805968 0 402718720 -0.0108240135 0.0453259945 -0.0340794325 433 17.2800000000 0.0074645998 0.0154649785 0.0324170515 0.0150900267 0.0458100000 365807076 0 402718720 -0.0122377640 0.0431328677 -0.0320438705 434 17.3200000000 0.0072366428 0.0154460192 0.0324170515 0.0150947797 0.0343310000 365809768 0 402718720 -0.0090817977 0.0404025987 -0.0306889191 435 17.3600000000 0.0093434202 0.0154319902 0.0324170515 0.0150978518 0.0335300000 365810788 0 402718720 -0.0054886849 0.0387285538 -0.0300745592 436 17.4000000000 0.0086412616 0.0154164152 0.0324170515 0.0150970265 0.0334770000 365812756 0 402718720 -0.0045878682 0.0363707505 -0.0293366723 437 17.4400000000 0.0095102554 0.0154028999 0.0324170515 0.0150882845 0.0325290000 365815816 0 402718720 -0.0073575363 0.0377862975 -0.0272070989 438 17.4800000000 0.0127157969 0.0153967650 0.0324170515 0.0151006001 0.0325120000 365817644 0 402718720 -0.0041075181 0.0400657281 -0.0276191514 439 17.5200000000 0.0121856472 0.0153894504 0.0324170515 0.0151047169 0.0324080000 365818392 0 402718720 -0.0072656376 0.0393108837 -0.0272467248 440 17.5600000000 0.0106516099 0.0153786825 0.0324170515 0.0151141721 0.0424240000 365819528 0 402718720 -0.0083840881 0.0370907895 -0.0266069155 441 17.6000000000 0.0132971192 0.0153739624 0.0324170515 0.0151226934 0.0324650000 365823516 0 402718720 -0.0082152970 0.0387107432 -0.0254712775 442 17.6400000000 0.0075445245 0.0153562488 0.0324170515 0.0152215161 0.0328200000 365826148 0 402718720 -0.0175101869 0.0286354907 -0.0241717845 443 17.6800000000 0.0075068981 0.0153385302 0.0324170515 0.0152270711 0.0325860000 365831700 0 402718720 -0.0217447076 0.0294849407 -0.0254000723 444 17.7200000000 0.0039281514 0.0153128311 0.0324170515 0.0152361685 0.0331980000 365830788 0 402718720 -0.0261898693 0.0261581894 -0.0244499259 445 17.7600000000 0.0045143687 0.0152885649 0.0324170515 0.0152459564 0.0328140000 365834016 0 402718720 -0.0259384103 0.0194701068 -0.0246814378 446 17.8000000000 0.0040876074 0.0152634507 0.0324170515 0.0152555774 0.0428170000 365837888 0 402718720 -0.0282073673 0.0168059133 -0.0244149752 447 17.8400000000 0.0045249881 0.0152394272 0.0324170515 0.0152511581 0.0324200000 365838020 0 402718720 -0.0269712899 0.0135622043 -0.0236999597 448 17.8800000000 0.0029646992 0.0152120283 0.0324170515 0.0152427731 0.0317000000 365842996 0 402718720 -0.0276593696 0.0108740581 -0.0215932522 449 17.9200000000 0.0025147812 0.0151837494 0.0324170515 0.0152336158 0.0324510000 365846320 0 402718720 -0.0299045146 0.0074629365 -0.0192492027 450 17.9600000000 0.0016785369 0.0151537378 0.0324170515 0.0152186157 0.0332840000 365848012 0 402718720 -0.0308226980 0.0051306006 -0.0168609470 451 18.0000000000 0.0057866788 0.0151329682 0.0324170515 0.0152155367 0.0319830000 365852108 0 402718720 -0.0254881289 0.0036245594 -0.0143137127 452 18.0400000000 0.0038205527 0.0151079408 0.0324170515 0.0152066426 0.0313120000 365853988 0 402718720 -0.0281838961 0.0030249848 -0.0122541673 453 18.0800000000 0.0023458814 0.0150797685 0.0324170515 0.0151971485 0.0435000000 365856960 0 402718720 -0.0277761165 -0.0015135857 -0.0077035548 454 18.1200000000 0.0059079472 0.0150595662 0.0324170515 0.0151848303 0.0638870000 365860164 0 402718720 -0.0237636212 -0.0005250858 -0.0041572889 455 18.1600000000 0.0064253076 0.0150405898 0.0324170515 0.0151684617 0.0308740000 365861372 0 402718720 -0.0257745162 0.0029971928 -0.0001533205 456 18.2000000000 0.0029050112 0.0150139767 0.0324170515 0.0151619327 0.0320990000 365865008 0 402718720 -0.0246506371 -0.0023256212 0.0049857721 457 18.2400000000 0.0046167215 0.0149912256 0.0324170515 0.0151570895 0.0312410000 365866796 0 402718720 -0.0223631132 -0.0025411556 0.0092655933 458 18.2800000000 0.0032354447 0.0149655579 0.0324170515 0.0151437311 0.0327150000 365869368 0 402718720 -0.0228742436 0.0006522435 0.0145424381 459 18.3200000000 0.0044237687 0.0149425911 0.0324170515 0.0151290837 0.0319720000 365872228 0 402718720 -0.0190943107 0.0009973696 0.0215319712 460 18.3600000000 0.0026907821 0.0149159567 0.0324170515 0.0151153360 0.0319830000 365872716 0 402718720 -0.0192511473 0.0034013207 0.0278679579 461 18.4000000000 0.0059823175 0.0148965779 0.0324170515 0.0151011393 0.0322110000 365876932 0 402718720 -0.0151810218 0.0030783005 0.0353268422 462 18.4400000000 0.0056171394 0.0148764925 0.0324170515 0.0150850015 0.0321470000 365879272 0 402718720 -0.0147362622 0.0085267611 0.0436343066 463 18.4800000000 0.0043564280 0.0148537710 0.0324170515 0.0150723783 0.0322510000 365880708 0 402718720 -0.0132686282 0.0079341810 0.0509611070 464 18.5200000000 0.0075261290 0.0148379787 0.0324170515 0.0150591741 0.0321990000 365883088 0 402718720 -0.0107113346 0.0129215252 0.0605120026 465 18.5600000000 0.0038722444 0.0148143965 0.0324170515 0.0150488313 0.0321550000 365887396 0 402718720 -0.0094117010 0.0168558396 0.0806585178 466 18.6000000000 0.0026655782 0.0147883260 0.0324170515 0.0150344899 0.0326740000 365890004 0 402718720 -0.0073766722 0.0187732037 0.0914939642 467 18.6400000000 0.0064450847 0.0147704604 0.0324170515 0.0150199808 0.0328930000 365891220 0 402718720 -0.0015398005 0.0229965597 0.1016127840 468 18.6800000000 0.0041798688 0.0147478309 0.0324170515 0.0150058796 0.0320800000 365894844 0 402718720 -0.0013458955 0.0256318823 0.1140283495 469 18.7200000000 0.0041651796 0.0147252667 0.0324170515 0.0149948693 0.0316780000 365896008 0 402718720 -0.0006490453 0.0292703770 0.1265650690 470 18.7600000000 0.0055379034 0.0147057191 0.0324170515 0.0149870632 0.0430470000 365900016 0 402718720 0.0018493976 0.0369342864 0.1373687834 471 18.8000000000 0.0055858390 0.0146863563 0.0324170515 0.0149802182 0.0318790000 365902716 0 402718720 0.0035774228 0.0414844938 0.1513687074 472 18.8400000000 0.0073897694 0.0146708974 0.0324170515 0.0149644079 0.0319260000 365903284 0 402718720 0.0035364472 0.0511433445 0.1638488621 473 18.8800000000 0.0033249811 0.0146469103 0.0324170515 0.0149493209 0.0317170000 365906432 0 402718720 0.0076809563 0.0538604781 0.1742737591 474 18.9200000000 0.0052026995 0.0146269858 0.0324170515 0.0149358812 0.0312840000 365907920 0 402718720 0.0139433667 0.0599644817 0.1848519444 475 18.9600000000 0.0040307036 0.0146046778 0.0324170515 0.0149272416 0.0319530000 365908720 0 402718720 0.0161701590 0.0642851219 0.1980668008 476 19.0000000000 0.0063481685 0.0145873322 0.0324170515 0.0149164434 0.0316790000 365911360 0 402718720 0.0219034720 0.0687765479 0.2092714012 477 19.0400000000 0.0043586483 0.0145658884 0.0324170515 0.0149051471 0.0320000000 365914936 0 402718720 0.0202698074 0.0762747228 0.2212117761 478 19.0800000000 0.0050095404 0.0145458961 0.0324170515 0.0148903728 0.0318480000 365917072 0 402718720 0.0261942241 0.0791767910 0.2322165519 479 19.1200000000 0.0043416223 0.0145245928 0.0324170515 0.0148790803 0.0321550000 365920624 0 402718720 0.0291501731 0.0826800838 0.2437002808 480 19.1600000000 0.0078592505 0.0145107066 0.0324170515 0.0148741600 0.0309400000 365921436 0 402718720 0.0351625122 0.0925241336 0.2562725842 481 19.2000000000 0.0060229120 0.0144930605 0.0324170515 0.0148598265 0.0312690000 365924076 0 402718720 0.0352962799 0.1002487987 0.2664857507 482 19.2400000000 0.0042262524 0.0144717601 0.0324170515 0.0148608757 0.0317720000 365928224 0 402718720 0.0373581611 0.1043792590 0.2776205242 483 19.2800000000 0.0038074702 0.0144496808 0.0324170515 0.0148580872 0.0306620000 365928596 0 402718720 0.0396431871 0.1039134562 0.2892901897 484 19.3200000000 0.0064870156 0.0144332290 0.0324170515 0.0148601855 0.0310700000 365931268 0 402718720 0.0441932715 0.1086134538 0.3016412854 485 19.3600000000 0.0049239951 0.0144136223 0.0324170515 0.0148471163 0.0308540000 365932052 0 402718720 0.0453388914 0.1110486984 0.3121803105 486 19.4000000000 0.0045611197 0.0143933497 0.0324170515 0.0148322071 0.0308020000 365935584 0 402718720 0.0487985723 0.1147289798 0.3221721351 487 19.4400000000 0.0067462767 0.0143776473 0.0324170515 0.0148178603 0.0415470000 365937916 0 402718720 0.0449049510 0.1250287592 0.3351210058 488 19.4800000000 0.0047081560 0.0143578328 0.0324170515 0.0148042739 0.0416570000 365939776 0 402718720 0.0467646569 0.1226181164 0.3469469249 489 19.5200000000 0.0063260454 0.0143414078 0.0324170515 0.0147962212 0.0299400000 365942340 0 402718720 0.0484588966 0.1239616871 0.3550760746 490 19.5600000000 0.0025711667 0.0143173869 0.0324170515 0.0147821966 0.0311830000 365946496 0 402718720 0.0489086956 0.1344756186 0.3660984039 491 19.6000000000 0.0055773780 0.0142995865 0.0324170515 0.0147676677 0.0391530000 365948568 0 402718720 0.0488645360 0.1388681680 0.3781658411 492 19.6400000000 0.0054568113 0.0142816134 0.0324170515 0.0147556422 0.0303410000 365950348 0 402718720 0.0549862608 0.1494787037 0.3866549730 493 19.6800000000 0.0067724409 0.0142663818 0.0324170515 0.0147408996 0.0348520000 366638388 0 402718720 0.0542730801 0.1532779932 0.3993240595 494 19.7200000000 0.0064092507 0.0142504767 0.0324170515 0.0147261777 0.1194830000 366677004 0 402718720 0.0516825840 0.1540382802 0.4108235836 495 19.7600000000 0.0082094483 0.0142382726 0.0324170515 0.0147123495 0.1017170000 366679788 0 402718720 0.0525466241 0.1608126462 0.4225003421 496 19.8000000000 0.0055276179 0.0142207108 0.0324170515 0.0147024936 0.0962340000 370672468 0 402718720 0.0525475033 0.1630179286 0.4330916703 497 19.8400000000 0.0073002656 0.0142067863 0.0324170515 0.0146903211 0.0859640000 374082567 0 402718720 0.0543168150 0.1718532592 0.4444917738 498 19.8800000000 0.0081154639 0.0141945548 0.0324170515 0.0146795145 0.0418690000 374092148 0 402718720 0.0517116897 0.1798145175 0.4554573298 499 19.9200000000 0.0087210704 0.0141835859 0.0324170515 0.0146698852 0.1128820000 374022363 0 402718720 0.0490958691 0.1858978570 0.4678626955 500 19.9600000000 0.0084485533 0.0141721158 0.0324170515 0.0146594621 0.0372380000 366691944 0 402718720 0.0474511720 0.1880859435 0.4781664014 501 20.0000000000 0.0078992508 0.0141595951 0.0324170515 0.0146509809 0.0369710000 366693280 0 402718720 0.0455498472 0.1896430850 0.4892553091 502 20.0400000000 0.0082305083 0.0141477842 0.0324170515 0.0146398818 0.0476250000 366696348 0 402718720 0.0443570837 0.1960344762 0.4993306398 503 20.0800000000 0.0072391341 0.0141340493 0.0324170515 0.0146292989 0.0358880000 366698252 0 402718720 0.0443095192 0.2003632188 0.5112772584 504 20.1200000000 0.0059635537 0.0141178380 0.0324170515 0.0146149056 0.0474390000 366700968 0 402718720 0.0425311588 0.2028404772 0.5218580961 505 20.1600000000 0.0061421618 0.0141020446 0.0324170515 0.0146008977 0.0362230000 366700000 0 402718720 0.0409711786 0.2110138535 0.5319623947 506 20.2000000000 0.0073853489 0.0140887705 0.0324170515 0.0145883029 0.0358440000 366703560 0 402718720 0.0387946665 0.2224511206 0.5417023301 507 20.2400000000 0.0057929633 0.0140724079 0.0324170515 0.0145864120 0.0357960000 366706676 0 402718720 0.0344611444 0.2254394293 0.5517304540 508 20.2800000000 0.0051636351 0.0140548710 0.0324170515 0.0145847719 0.0365160000 366708672 0 402718720 0.0337609500 0.2303092033 0.5610122681 509 20.3200000000 0.0060985428 0.0140392397 0.0324170515 0.0145972120 0.0419320000 366711908 0 402718720 0.0282528624 0.2348767817 0.5719860792 510 20.3600000000 0.0068074227 0.0140250596 0.0324170515 0.0145949098 0.0350770000 366715164 0 402718720 0.0264754593 0.2428977787 0.5809233785 511 20.4000000000 0.0056624725 0.0140086945 0.0324170515 0.0145953844 0.0536410000 366715824 0 402718720 0.0240465533 0.2453774959 0.5898965001 512 20.4400000000 0.0061417408 0.0139933294 0.0324170515 0.0145983809 0.0344800000 366719664 0 402718720 0.0241715405 0.2534832358 0.5974758863 513 20.4800000000 0.0064716749 0.0139786673 0.0324170515 0.0145982892 0.0446830000 366721260 0 402718720 0.0202967562 0.2573352456 0.6057097912 514 20.5200000000 0.0068156333 0.0139647314 0.0324170515 0.0146016453 0.0351450000 366826364 0 402718720 0.0183182005 0.2582516968 0.6150319576 515 20.5600000000 0.0057617123 0.0139488032 0.0324170515 0.0146078252 0.0342020000 366828056 0 402718720 0.0206816401 0.2621538043 0.6203560233 516 20.6000000000 0.0065851775 0.0139345326 0.0324170515 0.0146239201 0.0516870000 366829460 0 402718720 0.0200536046 0.2657911777 0.6298502684 517 20.6400000000 0.0047361152 0.0139167407 0.0324170515 0.0146392640 0.0341900000 366834064 0 402718720 0.0189295895 0.2671341598 0.6342920065 518 20.6800000000 0.0052811881 0.0139000698 0.0324170515 0.0146611413 0.0330840000 366833124 0 402718720 0.0195283648 0.2685296834 0.6414378881 519 20.7200000000 0.0068779481 0.0138865397 0.0324170515 0.0146703296 0.0340680000 366839024 0 402718720 0.0202491917 0.2769957781 0.6475660205 520 20.7600000000 0.0067228400 0.0138727633 0.0324170515 0.0147020196 0.0335390000 366840368 0 402718720 0.0245548189 0.2810265720 0.6533209085 521 20.8000000000 0.0062700626 0.0138581708 0.0324170515 0.0147238637 0.0334200000 366841540 0 402718720 0.0249216035 0.2805044949 0.6585580707 522 20.8400000000 0.0083002038 0.0138475233 0.0324170515 0.0147468347 0.0436830000 366844920 0 402718720 0.0264772587 0.2834144533 0.6643435359 523 20.8800000000 0.0058277580 0.0138321892 0.0324170515 0.0147795605 0.0416490000 366847092 0 402718720 0.0280081071 0.2801993489 0.6676460505 524 20.9200000000 0.0062846025 0.0138177854 0.0324170515 0.0148131499 0.0338310000 366850948 0 402718720 0.0325130597 0.2844393849 0.6725424528 525 20.9600000000 0.0083040828 0.0138072831 0.0324170515 0.0148315774 0.0462100000 366851724 0 402718720 0.0357593074 0.2873241007 0.6780517697 526 21.0000000000 0.0087421145 0.0137976535 0.0324170515 0.0148383354 0.0327550000 366853780 0 402718720 0.0366684757 0.2865316272 0.6821048260 527 21.0400000000 0.0045803422 0.0137801634 0.0324170515 0.0148601994 0.0330280000 366856560 0 402718720 0.0405272879 0.2851375937 0.6825202107 528 21.0800000000 0.0013038800 0.0137565340 0.0324170515 0.0148727580 0.0327970000 366857556 0 402718720 0.0449325964 0.2852559686 0.6825574040 529 21.1200000000 0.0039815162 0.0137380557 0.0324170515 0.0148719839 0.0361720000 367460728 0 402718720 0.0477291718 0.2882341743 0.6870723367 530 21.1600000000 0.0021120778 0.0137161199 0.0324170515 0.0148786176 0.1147950000 367514504 0 402718720 0.0536096953 0.2864406407 0.6878926158 531 21.2000000000 0.0026834642 0.0136953428 0.0324170515 0.0148858301 0.0957790000 367746224 0 402718720 0.0553372242 0.2887252867 0.6915246248 532 21.2400000000 0.0028710039 0.0136749963 0.0324170515 0.0149018390 0.1014920000 372868744 0 402718720 0.0611585006 0.2874314785 0.6933779120 533 21.2800000000 0.0024804228 0.0136539933 0.0324170515 0.0149181882 0.0781450000 374349559 0 402718720 0.0649074614 0.2856673002 0.6955428123 534 21.3200000000 0.0012540428 0.0136307725 0.0324170515 0.0149396037 0.0409040000 374365124 0 402718720 0.0679128245 0.2860273123 0.6971939802 535 21.3600000000 0.0044454192 0.0136136036 0.0324170515 0.0149466458 0.1089830000 374294151 0 402718720 0.0707876533 0.2909569740 0.7002125382 536 21.4000000000 0.0056399852 0.0135987274 0.0324170515 0.0149651178 0.0347930000 367525292 0 402718720 0.0746119097 0.2923072278 0.7034347653 537 21.4400000000 0.0072617615 0.0135869267 0.0324170515 0.0149739751 0.0352870000 367530584 0 402718720 0.0768692791 0.2938193679 0.7069622874 538 21.4800000000 0.0015148337 0.0135644879 0.0324170515 0.0149948959 0.0352630000 367530264 0 402718720 0.0838713720 0.2899568975 0.7058686018 539 21.5200000000 0.0036011988 0.0135460031 0.0324170515 0.0150107627 0.0349480000 367534580 0 402718720 0.0901866108 0.2873498201 0.7051842213 540 21.5600000000 0.0057873842 0.0135316353 0.0324170515 0.0150067059 0.0360110000 367538652 0 402718720 0.0901252702 0.2950239480 0.7117459178 541 21.6000000000 0.0049103657 0.0135156995 0.0324170515 0.0150105515 0.0357530000 367537860 0 402718720 0.0943901613 0.2933830619 0.7141436934 542 21.6400000000 0.0038435734 0.0134978543 0.0324170515 0.0150267670 0.0455730000 367540520 0 402718720 0.1017334461 0.2892338336 0.7103530765 543 21.6800000000 0.0024179416 0.0134774493 0.0324170515 0.0150425884 0.0451110000 367542028 0 402718720 0.1046707034 0.2903749645 0.7138571739 544 21.7200000000 0.0051295385 0.0134621039 0.0324170515 0.0150499248 0.0465950000 367545932 0 402718720 0.1056506559 0.2973788381 0.7193846703 545 21.7600000000 0.0029564979 0.0134428275 0.0324170515 0.0150786657 0.0345470000 367547244 0 402718720 0.1118678898 0.2918885946 0.7190396190 546 21.8000000000 0.0060076094 0.0134292099 0.0324170515 0.0151341696 0.0354140000 367552900 0 402718720 0.1152592376 0.3003261387 0.7275429368 547 21.8400000000 0.0030050534 0.0134101529 0.0324170515 0.0151486783 0.0354620000 367555176 0 402718720 0.1223309860 0.2991464734 0.7271986008 548 21.8800000000 0.0024963361 0.0133902372 0.0324170515 0.0151620471 0.0463370000 367556820 0 402718720 0.1254915595 0.2999496162 0.7299686670 549 21.9200000000 0.0060294443 0.0133768296 0.0324170515 0.0151868948 0.0429810000 367561244 0 402718720 0.1331905425 0.2977239788 0.7276594639 550 21.9600000000 0.0026222456 0.0133572758 0.0324170515 0.0151972795 0.0343150000 367563060 0 402718720 0.1363677979 0.3016567230 0.7316381931 551 22.0000000000 0.0024321196 0.0133374479 0.0324170515 0.0152285473 0.0340410000 367565644 0 402718720 0.1392064095 0.3031983674 0.7334945202 552 22.0400000000 0.0032558376 0.0133191841 0.0324170515 0.0152323304 0.0338630000 367566696 0 402718720 0.1400045156 0.3086112440 0.7364892960 553 22.0800000000 0.0055809924 0.0133051910 0.0324170515 0.0152331958 0.0348720000 367571100 0 402718720 0.1511457562 0.3076066375 0.7344418764 554 22.1200000000 0.0036610879 0.0132877829 0.0324170515 0.0152293090 0.0342540000 367571632 0 402718720 0.1504822373 0.3020861745 0.7392592430 555 22.1600000000 0.0056449031 0.0132740119 0.0324170515 0.0152224752 0.0446370000 367575440 0 402718720 0.1605720520 0.3092594445 0.7398521900 556 22.2000000000 0.0046962472 0.0132585843 0.0324170515 0.0152192731 0.0332440000 367578168 0 402718720 0.1644325852 0.3119375110 0.7387551665 557 22.2400000000 0.0065176059 0.0132464820 0.0324170515 0.0152167422 0.0331750000 367579604 0 402718720 0.1699133962 0.3161861300 0.7435281873 558 22.2800000000 0.0160004254 0.0132514174 0.0324170515 0.0152395998 0.0332960000 367580948 0 402718720 0.1800567210 0.3049669862 0.7358028293 559 22.3200000000 0.0177680980 0.0132594973 0.0324170515 0.0152380458 0.0328530000 367582580 0 402718720 0.1846378148 0.3043674231 0.7371190190 560 22.3600000000 0.0053585926 0.0132453886 0.0324170515 0.0152373913 0.0331630000 367587240 0 402718720 0.1849386245 0.3193189204 0.7474602461 561 22.4000000000 0.0062340712 0.0132328907 0.0324170515 0.0152383513 0.0327760000 367589924 0 402718720 0.1886330694 0.3171117306 0.7473704219 562 22.4400000000 0.0032213691 0.0132150766 0.0324170515 0.0152344484 0.0327380000 367591904 0 402718720 0.1907363087 0.3245686889 0.7534394860 563 22.4800000000 0.0055934452 0.0132015390 0.0324170515 0.0152257520 0.0326790000 367595172 0 402718720 0.1952272952 0.3285099268 0.7567586899 564 22.5200000000 0.0055667688 0.0131880022 0.0324170515 0.0152211941 0.0430440000 367597336 0 402718720 0.2041768134 0.3262595534 0.7517450452 565 22.5600000000 0.0019626012 0.0131681342 0.0324170515 0.0152100177 0.0571000000 367598536 0 402718720 0.2044477463 0.3286863863 0.7546069622 566 22.6000000000 0.0079332609 0.0131588854 0.0324170515 0.0152026425 0.0316410000 367601192 0 402718720 0.2091592103 0.3395649791 0.7607914209 567 22.6400000000 0.0085024713 0.0131506730 0.0324170515 0.0151920605 0.0322360000 367604860 0 402718720 0.2135808915 0.3418254256 0.7626042962 568 22.6800000000 0.0070594959 0.0131399491 0.0324170515 0.0151837255 0.0448970000 367608820 0 402718720 0.2199393213 0.3421264291 0.7627998590 569 22.7200000000 0.0050876662 0.0131257974 0.0324170515 0.0151736589 0.0319470000 367608808 0 402718720 0.2275726646 0.3402566016 0.7589442134 570 22.7600000000 0.0059417938 0.0131131939 0.0324170515 0.0151627132 0.0325410000 367612232 0 402718720 0.2322586626 0.3437940776 0.7605246305 571 22.8000000000 0.0061595156 0.0131010159 0.0324170515 0.0151505278 0.0371780000 368237572 0 402718720 0.2327371091 0.3478496671 0.7653241158 572 22.8400000000 0.0048095398 0.0130865203 0.0324170515 0.0151399043 0.1086230000 368255844 0 402718720 0.2423455566 0.3458728790 0.7600033283 573 22.8800000000 0.0073899585 0.0130765786 0.0324170515 0.0151298768 0.0974740000 368255544 0 402718720 0.2474212050 0.3536643982 0.7630853653 574 22.9200000000 0.0042298129 0.0130611661 0.0324170515 0.0151185672 0.0992220000 373773344 0 402718720 0.2480702847 0.3546719551 0.7641054392 575 22.9600000000 0.0048491722 0.0130468844 0.0324170515 0.0151056995 0.0737620000 375373531 0 402718720 0.2528836727 0.3580839634 0.7645903826 576 23.0000000000 0.0074297106 0.0130371324 0.0324170515 0.0150930401 0.0398490000 375347280 0 402718720 0.2571890354 0.3644337058 0.7656254768 577 23.0400000000 0.0085686734 0.0130293881 0.0324170515 0.0150802183 0.1032370000 375275363 0 402718720 0.2646093369 0.3672111630 0.7638359070 578 23.0800000000 0.0075211539 0.0130198583 0.0324170515 0.0150689288 0.0340710000 368263060 0 402718720 0.2591510415 0.3682078421 0.7690620422 579 23.1200000000 0.0037781475 0.0130038968 0.0324170515 0.0150568729 0.0480850000 368264656 0 402718720 0.2671150863 0.3692468405 0.7647757530 580 23.1600000000 0.0024144633 0.0129856391 0.0324170515 0.0150443355 0.0350430000 368268320 0 402718720 0.2700923383 0.3748571277 0.7639878988 581 23.2000000000 0.0068585998 0.0129750934 0.0324170515 0.0150323057 0.0353470000 368271588 0 402718720 0.2740616798 0.3823787272 0.7673395872 582 23.2400000000 0.0057574413 0.0129626920 0.0324170515 0.0150195712 0.0353060000 368272604 0 402718720 0.2762928605 0.3848333657 0.7667806745 583 23.2800000000 0.0023901281 0.0129445572 0.0324170515 0.0150077263 0.0343910000 368274020 0 402718720 0.2796986401 0.3877692223 0.7635924816 584 23.3200000000 0.0045253439 0.0129301407 0.0324170515 0.0149968460 0.0339520000 368276812 0 402718720 0.2808033824 0.3920146227 0.7654357553 585 23.3600000000 0.0087232832 0.0129229495 0.0324170515 0.0149858842 0.0338920000 368280292 0 402718720 0.2844739854 0.3983323574 0.7665733695 586 23.4000000000 0.0078822747 0.0129143477 0.0324170515 0.0149735871 0.0345840000 368284928 0 402718720 0.2857114673 0.3990905881 0.7677065730 587 23.4400000000 0.0036597545 0.0128985818 0.0324170515 0.0149616613 0.0332640000 368284424 0 402718720 0.2898727953 0.3990507722 0.7636308074 588 23.4800000000 0.0062668794 0.0128873034 0.0324170515 0.0149497818 0.0335740000 368287508 0 402718720 0.2894385755 0.4046979249 0.7656416297 589 23.5200000000 0.0053686178 0.0128745382 0.0324170515 0.0149371008 0.0341280000 368292052 0 402718720 0.2943586707 0.4055638611 0.7653464079 590 23.5600000000 0.0094822077 0.0128687885 0.0324170515 0.0149253333 0.0330010000 368292408 0 402718720 0.2953984141 0.4115995467 0.7679567337 591 23.6000000000 0.0086025782 0.0128615699 0.0324170515 0.0149128815 0.0365340000 368840688 0 402718720 0.2974725664 0.4133965671 0.7681109309 592 23.6400000000 0.0085171415 0.0128542313 0.0324170515 0.0149014365 0.1105480000 368949700 0 402718720 0.2985213995 0.4167479277 0.7668848038 593 23.6800000000 0.0115521206 0.0128520355 0.0324170515 0.0148930539 0.0965790000 368952116 0 402718720 0.3031468689 0.4227761924 0.7689130306 594 23.7200000000 0.0085731931 0.0128448321 0.0324170515 0.0148812555 0.1006800000 373230340 0 402718720 0.3035478890 0.4193879068 0.7693232298 595 23.7600000000 0.0097449021 0.0128396221 0.0324170515 0.0148693848 0.0614740000 376560480 0 402718720 0.3060458899 0.4234849811 0.7693286538 596 23.8000000000 0.0127455387 0.0128394642 0.0324170515 0.0148576994 0.0598050000 376591621 0 402718720 0.3075370789 0.4285397828 0.7716037035 597 23.8400000000 0.0109144691 0.0128362398 0.0324170515 0.0148454589 0.1109930000 376492683 0 402718720 0.3100479245 0.4297382236 0.7699589133 598 23.8800000000 0.0118808439 0.0128346421 0.0324170515 0.0148340266 0.0343640000 368958144 0 402718720 0.3109914660 0.4308643937 0.7722661495 599 23.9200000000 0.0105559267 0.0128308379 0.0324170515 0.0148231313 0.0352100000 368963820 0 402718720 0.3123596609 0.4321132004 0.7714837790 600 23.9600000000 0.0095170941 0.0128253150 0.0324170515 0.0148140414 0.0347980000 368964788 0 402718720 0.3093720376 0.4313871861 0.7740275860 601 24.0000000000 0.0117083713 0.0128234566 0.0324170515 0.0148055733 0.0345930000 368964936 0 402718720 0.3135539889 0.4377730191 0.7754674554 602 24.0400000000 0.0146054411 0.0128264167 0.0324170515 0.0147954108 0.0344520000 368968144 0 402718720 0.3135846257 0.4410697818 0.7773786783 603 24.0800000000 0.0111998655 0.0128237192 0.0324170515 0.0147847156 0.0376370000 369470620 0 402718720 0.3142008483 0.4387793839 0.7769178748 604 24.1200000000 0.0128534855 0.0128237685 0.0324170515 0.0147730068 0.1107650000 369581940 0 402718720 0.3152282834 0.4415093362 0.7785060406 605 24.1600000000 0.0101822438 0.0128194024 0.0324170515 0.0147612041 0.1003960000 369581476 0 402718720 0.3153753281 0.4437245131 0.7783794999 606 24.2000000000 0.0107482728 0.0128159847 0.0324170515 0.0147490349 0.0960590000 372366884 0 402718720 0.3160442710 0.4456315339 0.7798242569 607 24.2400000000 0.0128873130 0.0128161022 0.0324170515 0.0147371421 0.0707430000 377263084 0 402718720 0.3165954649 0.4495809078 0.7808099985 608 24.2800000000 0.0098984120 0.0128113033 0.0324170515 0.0147253265 0.0762660000 377361047 0 402718720 0.3177134097 0.4475997984 0.7804307342 609 24.3200000000 0.0074513983 0.0128025022 0.0324170515 0.0147136583 0.1125570000 377108215 0 402718720 0.3176139295 0.4470105171 0.7794030309 610 24.3600000000 0.0068630539 0.0127927654 0.0324170515 0.0147019105 0.0351620000 369590784 0 402718720 0.3162896633 0.4477925897 0.7804106474 611 24.4000000000 0.0062825205 0.0127821103 0.0324170515 0.0146900237 0.0345610000 369593452 0 402718720 0.3200156093 0.4507342875 0.7793912888 612 24.4400000000 0.0087132799 0.0127754619 0.0324170515 0.0146782499 0.0343630000 369596536 0 402718720 0.3193475604 0.4555940032 0.7811275125 613 24.4800000000 0.0086804125 0.0127687816 0.0324170515 0.0146663229 0.0469060000 369599560 0 402718720 0.3194822669 0.4576706290 0.7820323110 614 24.5200000000 0.0093498118 0.0127632132 0.0324170515 0.0146551077 0.0450270000 369598764 0 402718720 0.3193468750 0.4606332779 0.7826443315 615 24.5600000000 0.0093719931 0.0127576990 0.0324170515 0.0146439882 0.0341210000 369601896 0 402718720 0.3177156448 0.4631389081 0.7841800451 616 24.6000000000 0.0076912362 0.0127494742 0.0324170515 0.0146328571 0.0343680000 369607860 0 402718720 0.3173795044 0.4623795152 0.7856018543 617 24.6400000000 0.0081405099 0.0127420043 0.0324170515 0.0146211659 0.0344660000 369609780 0 402718720 0.3172023296 0.4650682211 0.7866979837 618 24.6800000000 0.0103797391 0.0127381819 0.0324170515 0.0146117054 0.0343630000 369609628 0 402718720 0.3158914447 0.4692870378 0.7891061306 619 24.7200000000 0.0083349394 0.0127310684 0.0324170515 0.0146025099 0.0342980000 369611792 0 402718720 0.3148829639 0.4707432389 0.7889375091 620 24.7600000000 0.0083942488 0.0127240735 0.0324170515 0.0145936197 0.0430270000 369615596 0 402718720 0.3125524521 0.4719926715 0.7908002138 621 24.8000000000 0.0099443849 0.0127195974 0.0324170515 0.0145854936 0.0340870000 369615860 0 402718720 0.3112866282 0.4748439789 0.7937822342 622 24.8400000000 0.0102908127 0.0127156926 0.0324170515 0.0145778949 0.0336730000 369619436 0 402718720 0.3084925711 0.4778286219 0.7956117392 623 24.8800000000 0.0087547265 0.0127093347 0.0324170515 0.0145724666 0.0336230000 369619176 0 402718720 0.3086451888 0.4791862071 0.7969968915 624 24.9200000000 0.0083999950 0.0127024287 0.0324170515 0.0145662795 0.0334330000 369622752 0 402718720 0.3063663840 0.4797577858 0.7989956141 625 24.9600000000 0.0103748981 0.0126987046 0.0324170515 0.0145590352 0.0334130000 369625608 0 402718720 0.3045571744 0.4844371378 0.8017758131 626 25.0000000000 0.0068816948 0.0126894123 0.0324170515 0.0145518170 0.0447430000 369627852 0 402718720 0.3028863072 0.4848216772 0.8016819358 627 25.0400000000 0.0100622345 0.0126852222 0.0324170515 0.0145500862 0.0329300000 369630384 0 402718720 0.3015486896 0.4913047850 0.8044430017 628 25.0800000000 0.0071998625 0.0126764875 0.0324170515 0.0145475286 0.0329240000 369633640 0 402718720 0.2978945971 0.4909822047 0.8051229119 629 25.1200000000 0.0121268136 0.0126756137 0.0324170515 0.0145522936 0.0324090000 369635132 0 402718720 0.2975986004 0.4976199269 0.8086426258 630 25.1600000000 0.0084063504 0.0126688371 0.0324170515 0.0145476022 0.0325540000 369636316 0 402718720 0.2914039493 0.4947895706 0.8101952076 631 25.2000000000 0.0073645380 0.0126604309 0.0324170515 0.0145412284 0.0328360000 369640304 0 402718720 0.2922955751 0.4964003265 0.8106869459 632 25.2400000000 0.0086587081 0.0126540990 0.0324170515 0.0145344834 0.0425710000 369644756 0 402718720 0.2881966829 0.4981273115 0.8140919209 633 25.2800000000 0.0088640228 0.0126481116 0.0324170515 0.0145250220 0.0325300000 369646076 0 402718720 0.2843624055 0.4995674491 0.8166909814 634 25.3200000000 0.0097089345 0.0126434756 0.0324170515 0.0145176546 0.0330970000 369649284 0 402718720 0.2801147699 0.5035263896 0.8194296956 635 25.3600000000 0.0104817348 0.0126400713 0.0324170515 0.0145100255 0.0325890000 369651140 0 402718720 0.2776697278 0.5068413019 0.8219413757 636 25.4000000000 0.0114500439 0.0126382002 0.0324170515 0.0145026572 0.0332670000 369652308 0 402718720 0.2744444013 0.5094992518 0.8238363266 637 25.4400000000 0.0092184395 0.0126328317 0.0324170515 0.0144957624 0.0329700000 369654828 0 402718720 0.2675908804 0.5077481866 0.8271905780 638 25.4800000000 0.0090366565 0.0126271950 0.0324170515 0.0144883485 0.0323490000 369657208 0 402718720 0.2645211816 0.5083608627 0.8306103945 639 25.5200000000 0.0081864307 0.0126202455 0.0324170515 0.0144808657 0.0453750000 369661824 0 402718720 0.2604577243 0.5086483359 0.8324880600 640 25.5600000000 0.0080209188 0.0126130590 0.0324170515 0.0144724748 0.0327890000 369664480 0 402718720 0.2534199953 0.5061612725 0.8377584219 641 25.6000000000 0.0101660108 0.0126092415 0.0324170515 0.0144647357 0.0384120000 370365368 0 402718720 0.2493638098 0.5090177655 0.8415468335 642 25.6400000000 0.0104890317 0.0126059390 0.0324170515 0.0144594884 0.1182040000 370379336 0 402718720 0.2448124439 0.5118190050 0.8446213007 643 25.6800000000 0.0092175780 0.0126006694 0.0324170515 0.0144565615 0.1074520000 370381996 0 402718720 0.2394425869 0.5115092397 0.8473156095 644 25.7200000000 0.0093565267 0.0125956319 0.0324170515 0.0144521655 0.1032300000 373046572 0 402718720 0.2359685600 0.5111286640 0.8505439162 645 25.7600000000 0.0096191745 0.0125910172 0.0324170515 0.0144464327 0.0849230000 379249996 0 402718720 0.2319136113 0.5140268803 0.8525931835 646 25.8000000000 0.0100739822 0.0125871209 0.0324170515 0.0144401744 0.0863420000 379110193 0 402718720 0.2284803092 0.5168210268 0.8547681570 647 25.8400000000 0.0097765382 0.0125827768 0.0324170515 0.0144334224 0.0428580000 379174076 0 402718720 0.2231479436 0.5167129636 0.8579306602 648 25.8800000000 0.0113499109 0.0125808743 0.0324170515 0.0144264940 0.1213430000 379103543 0 402718720 0.2183925807 0.5205683708 0.8608640432 649 25.9200000000 0.0107329516 0.0125780269 0.0324170515 0.0144182812 0.0376240000 370396272 0 402718720 0.2150640488 0.5218173265 0.8631587029 650 25.9600000000 0.0125346109 0.0125779601 0.0324170515 0.0144116064 0.0370560000 370398928 0 402718720 0.2097398788 0.5267366171 0.8669229150 651 26.0000000000 0.0127383573 0.0125782065 0.0324170515 0.0144100653 0.0373120000 370401876 0 402718720 0.2073523998 0.5293555260 0.8684061170 652 26.0400000000 0.0110338414 0.0125758379 0.0324170515 0.0144062687 0.0378620000 370407336 0 402718720 0.2041872740 0.5295206308 0.8700163364 653 26.0800000000 0.0104901716 0.0125726439 0.0324170515 0.0144026075 0.0375510000 370409760 0 402718720 0.1999170184 0.5303325653 0.8722254038 654 26.1200000000 0.0117452145 0.0125713787 0.0324170515 0.0144034870 0.0375230000 370410900 0 402718720 0.1938536316 0.5322926641 0.8760361075 655 26.1600000000 0.0089323241 0.0125658229 0.0324170515 0.0143973319 0.0372980000 370412728 0 402718720 0.1920156777 0.5330985785 0.8761457205 656 26.2000000000 0.0119243274 0.0125648450 0.0324170515 0.0143953298 0.0366780000 370414032 0 402718720 0.1819445640 0.5406833887 0.8794499636 657 26.2400000000 0.0099440776 0.0125608560 0.0324170515 0.0143912948 0.0512830000 370417412 0 402718720 0.1799876243 0.5391315818 0.8802469969 658 26.2800000000 0.0104942899 0.0125577153 0.0324170515 0.0143842091 0.0358870000 370420296 0 402718720 0.1751921922 0.5418089628 0.8819783926 659 26.3200000000 0.0116178710 0.0125562892 0.0324170515 0.0143782572 0.0362320000 370422324 0 402718720 0.1732299179 0.5453154445 0.8853983283 660 26.3600000000 0.0114915567 0.0125546759 0.0324170515 0.0143759318 0.0364290000 370425808 0 402718720 0.1699232757 0.5469565392 0.8854963183 661 26.4000000000 0.0101161841 0.0125509868 0.0324170515 0.0143745336 0.0362660000 370427656 0 402718720 0.1666958183 0.5492535830 0.8862739205 662 26.4400000000 0.0094450163 0.0125462950 0.0324170515 0.0143671765 0.0363750000 370430464 0 402718720 0.1646182835 0.5510897636 0.8870953321 663 26.4800000000 0.0103785396 0.0125430254 0.0324170515 0.0143640310 0.0358370000 370433564 0 402718720 0.1599061787 0.5512981415 0.8897960782 664 26.5200000000 0.0093955258 0.0125382852 0.0324170515 0.0143624121 0.0421270000 371085568 0 402718720 0.1576052904 0.5526214838 0.8895547390 665 26.5600000000 0.0087616220 0.0125326060 0.0324170515 0.0143595937 0.1226840000 371161148 0 402718720 0.1543472558 0.5539563298 0.8907952905 666 26.6000000000 0.0108187525 0.0125300327 0.0324170515 0.0143552438 0.1105950000 371160772 0 402718720 0.1504947245 0.5574013591 0.8925647140 667 26.6400000000 0.0097793471 0.0125259087 0.0324170515 0.0143487143 0.1042290000 371493028 0 402718720 0.1487128139 0.5584765077 0.8922693133 668 26.6800000000 0.0094379568 0.0125212860 0.0324170515 0.0143441451 0.1127170000 379825244 0 402718720 0.1448234469 0.5606901646 0.8922693729 669 26.7200000000 0.0086106909 0.0125154406 0.0324170515 0.0143386259 0.0812740000 380923641 0 402718720 0.1390547156 0.5614699721 0.8940632343 670 26.7600000000 0.0095184743 0.0125109675 0.0324170515 0.0143320342 0.0473080000 380727509 0 402718720 0.1363283247 0.5611138344 0.8955243230 671 26.8000000000 0.0113029694 0.0125091672 0.0324170515 0.0143267938 0.1205860000 380593715 0 402718720 0.1311006844 0.5612187386 0.8993983269 672 26.8400000000 0.0119503271 0.0125083356 0.0324170515 0.0143188004 0.0436890000 371172572 0 402718720 0.1263091266 0.5618958473 0.9011431336 673 26.8800000000 0.0115158167 0.0125068608 0.0324170515 0.0143094179 0.0384140000 371176180 0 402718720 0.1226530224 0.5618922710 0.9017881751 674 26.9200000000 0.0105294269 0.0125039270 0.0324170515 0.0143048375 0.0388350000 371176180 0 402718720 0.1189354733 0.5603441000 0.9029233456 675 26.9600000000 0.0109624900 0.0125016433 0.0324170515 0.0143013816 0.0386150000 371177532 0 402718720 0.1138403565 0.5609414577 0.9039468765 676 27.0000000000 0.0111371446 0.0124996249 0.0324170515 0.0142940357 0.0384470000 371179424 0 402718720 0.1117641777 0.5616784692 0.9042450190 677 27.0400000000 0.0114241736 0.0124980363 0.0324170515 0.0142862794 0.0378360000 371181500 0 402718720 0.1081495583 0.5621419549 0.9046049714 678 27.0800000000 0.0118071157 0.0124970172 0.0324170515 0.0142783848 0.0382500000 371184896 0 402718720 0.0996796116 0.5612524748 0.9075289965 679 27.1200000000 0.0125880940 0.0124971514 0.0324170515 0.0142696723 0.0490510000 371187568 0 402718720 0.0944866985 0.5605076551 0.9093260169 680 27.1600000000 0.0113848336 0.0124955156 0.0324170515 0.0142629993 0.0371280000 371190244 0 402718720 0.0928823724 0.5593196154 0.9092236757 681 27.2000000000 0.0144413831 0.0124983730 0.0324170515 0.0142590564 0.0366430000 371193496 0 402718720 0.0862080157 0.5604770184 0.9130507708 682 27.2400000000 0.0109618008 0.0124961199 0.0324170515 0.0142536622 0.0368610000 371195444 0 402718720 0.0885355771 0.5584539175 0.9090462327 683 27.2800000000 0.0107525140 0.0124935671 0.0324170515 0.0142476659 0.0369220000 371198192 0 402718720 0.0862410218 0.5570585728 0.9097110033 684 27.3200000000 0.0124663487 0.0124935273 0.0324170515 0.0142383897 0.0365160000 371200108 0 402718720 0.0775061250 0.5592304468 0.9130662084 685 27.3600000000 0.0130015025 0.0124942689 0.0324170515 0.0142323842 0.0480080000 371204760 0 402718720 0.0758725628 0.5611063838 0.9132539630 686 27.4000000000 0.0115078278 0.0124928309 0.0324170515 0.0142266778 0.0353020000 371203792 0 402718720 0.0721189678 0.5585570931 0.9140691161 687 27.4400000000 0.0117374016 0.0124917313 0.0324170515 0.0142206293 0.0359250000 371207140 0 402718720 0.0659153759 0.5587024689 0.9170905948 688 27.4800000000 0.0130898179 0.0124926006 0.0324170515 0.0142189610 0.0354420000 371210368 0 402718720 0.0638713986 0.5602394342 0.9189648032 689 27.5200000000 0.0139137469 0.0124946632 0.0324170515 0.0142144527 0.0359790000 371210952 0 402718720 0.0602427050 0.5618779659 0.9199693799 690 27.5600000000 0.0126934443 0.0124949513 0.0324170515 0.0142077137 0.0395870000 371794952 0 402718720 0.0573831499 0.5617223978 0.9203804135 691 27.6000000000 0.0128180962 0.0124954190 0.0324170515 0.0142017305 0.1162640000 371874748 0 402718720 0.0546393991 0.5626751184 0.9205588698 692 27.6400000000 0.0131410118 0.0124963519 0.0324170515 0.0141963651 0.1049200000 371875768 0 402718720 0.0502608418 0.5637347102 0.9222666025 693 27.6800000000 0.0132306898 0.0124974116 0.0324170515 0.0141890140 0.1029410000 372218552 0 402718720 0.0469527803 0.5627503395 0.9237222672 694 27.7200000000 0.0115744034 0.0124960816 0.0324170515 0.0141815570 0.1080910000 379500968 0 402718720 0.0434316248 0.5619820356 0.9238908291 695 27.7600000000 0.0129784886 0.0124967757 0.0324170515 0.0141764004 0.0565470000 382457661 0 402718720 0.0415295213 0.5638539791 0.9250803590 696 27.8000000000 0.0124472324 0.0124967045 0.0324170515 0.0141697975 0.0725790000 382556577 0 402718720 0.0379395336 0.5611715317 0.9268624187 697 27.8400000000 0.0124157229 0.0124965883 0.0324170515 0.0141669300 0.0429490000 382355476 0 402718720 0.0336904302 0.5613058805 0.9284873605 698 27.8800000000 0.0165527109 0.0125023994 0.0324170515 0.0141634770 0.1239960000 382286615 0 402718720 0.0263959356 0.5640342236 0.9323551655 699 27.9200000000 0.0150928060 0.0125061053 0.0324170515 0.0141574437 0.0497050000 371887192 0 402718720 0.0227365866 0.5636897087 0.9324250817 700 27.9600000000 0.0163344573 0.0125115743 0.0324170515 0.0141551732 0.0367990000 371889068 0 402718720 0.0184382293 0.5644733906 0.9344680309 701 28.0000000000 0.0147952456 0.0125148321 0.0324170515 0.0141505649 0.0474460000 371891724 0 402718720 0.0147506585 0.5635111332 0.9345972538 702 28.0400000000 0.0167569816 0.0125208750 0.0324170515 0.0141488807 0.0366510000 371894256 0 402718720 0.0101514114 0.5684434175 0.9352838397 703 28.0800000000 0.0171175301 0.0125274136 0.0324170515 0.0141429411 0.0369070000 371897080 0 402718720 0.0065374523 0.5686717629 0.9369435310 704 28.1200000000 0.0148681933 0.0125307386 0.0324170515 0.0141373062 0.0363660000 371900352 0 402718720 0.0042649247 0.5666475296 0.9369235039 705 28.1600000000 0.0147655336 0.0125339085 0.0324170515 0.0141316459 0.0359660000 371901504 0 402718720 0.0015584994 0.5662492514 0.9385192990 706 28.2000000000 0.0156115117 0.0125382677 0.0324170515 0.0141272471 0.0522700000 372628708 0 402718720 0.0004507452 0.5666186213 0.9398154616 707 28.2400000000 0.0150080081 0.0125417610 0.0324170515 0.0141210507 0.1223460000 372608172 0 402718720 -0.0025343746 0.5663155317 0.9403257966 708 28.2800000000 0.0154283913 0.0125458382 0.0324170515 0.0141156585 0.1076480000 372618188 0 402718720 -0.0053168647 0.5652382970 0.9426100254 709 28.3200000000 0.0142583670 0.0125482536 0.0324170515 0.0141076263 0.1028330000 372985684 0 402718720 -0.0086344816 0.5655429959 0.9429987669 710 28.3600000000 0.0148386164 0.0125514794 0.0324170515 0.0141028501 0.1077340000 379623372 0 402718720 -0.0127821565 0.5664704442 0.9439932704 711 28.4000000000 0.0142962718 0.0125539334 0.0324170515 0.0140957996 0.0714460000 383970586 0 402718720 -0.0170985050 0.5653266907 0.9451491833 712 28.4400000000 0.0132897114 0.0125549668 0.0324170515 0.0140892463 0.0842490000 383915269 0 402718720 -0.0190234594 0.5650204420 0.9455137253 713 28.4800000000 0.0134072006 0.0125561621 0.0324170515 0.0140824083 0.0502960000 383794528 0 402718720 -0.0239250027 0.5656440258 0.9467690587 714 28.5200000000 0.0149857709 0.0125595649 0.0324170515 0.0140780361 0.1287680000 383725651 0 402718720 -0.0281023830 0.5670731068 0.9482227564 715 28.5600000000 0.0156957321 0.0125639512 0.0324170515 0.0140702224 0.0519700000 372629848 0 402718720 -0.0330031700 0.5679158568 0.9499927163 716 28.6000000000 0.0164964739 0.0125694435 0.0324170515 0.0140647610 0.0359410000 372632196 0 402718720 -0.0358860791 0.5674416423 0.9518496394 717 28.6400000000 0.0162602216 0.0125745911 0.0324170515 0.0140575038 0.0462520000 372634084 0 402718720 -0.0415834971 0.5674600005 0.9525331259 718 28.6800000000 0.0152114052 0.0125782635 0.0324170515 0.0140511133 0.0352120000 372636340 0 402718720 -0.0460501313 0.5675766468 0.9525033236 719 28.7200000000 0.0167217031 0.0125840263 0.0324170515 0.0140484061 0.0355110000 372640420 0 402718720 -0.0487681180 0.5670955777 0.9547476172 720 28.7600000000 0.0154576432 0.0125880174 0.0324170515 0.0140474267 0.0362160000 372642536 0 402718720 -0.0531832725 0.5662679672 0.9549061060 721 28.8000000000 0.0159536190 0.0125926854 0.0324170515 0.0140441141 0.0357250000 372644392 0 402718720 -0.0564474091 0.5657468438 0.9562896490 722 28.8400000000 0.0169140361 0.0125986706 0.0324170515 0.0140398042 0.0400600000 373298220 0 402718720 -0.0625898838 0.5660427809 0.9569864273 723 28.8800000000 0.0165014658 0.0126040687 0.0324170515 0.0140333098 0.1299180000 373374288 0 402718720 -0.0652427524 0.5659834146 0.9576580524 724 28.9200000000 0.0162078142 0.0126090462 0.0324170515 0.0140258405 0.1221660000 373375484 0 402718720 -0.0710481256 0.5646797419 0.9587548971 725 28.9600000000 0.0166150406 0.0126145717 0.0324170515 0.0140183317 0.1173550000 373736416 0 402718720 -0.0737896338 0.5646930933 0.9596499801 726 29.0000000000 0.0170373488 0.0126206637 0.0324170515 0.0140125322 0.1241220000 381355324 0 402718720 -0.0768467188 0.5652554631 0.9603607059 727 29.0400000000 0.0168398153 0.0126264672 0.0324170515 0.0140071133 0.0682880000 385512012 0 402718720 -0.0806567296 0.5647434592 0.9615051150 728 29.0800000000 0.0161564387 0.0126313161 0.0324170515 0.0140032346 0.1002260000 385691891 0 402718720 -0.0825446248 0.5630627871 0.9618976116 729 29.1200000000 0.0157833863 0.0126356399 0.0324170515 0.0140013424 0.0466510000 385404916 0 402718720 -0.0858502686 0.5625866652 0.9625265002 730 29.1600000000 0.0150148645 0.0126388991 0.0324170515 0.0139997283 0.1293560000 385336203 0 402718720 -0.0872714072 0.5613267422 0.9622576833 731 29.2000000000 0.0153681478 0.0126426327 0.0324170515 0.0139966246 0.0636090000 373384488 0 402718720 -0.0911629274 0.5602952838 0.9626971483 732 29.2400000000 0.0151202064 0.0126460174 0.0324170515 0.0139932770 0.0368200000 373385532 0 402718720 -0.0965385884 0.5599420667 0.9637877941 733 29.2800000000 0.0143641792 0.0126483614 0.0324170515 0.0139875451 0.0364740000 373389604 0 402718720 -0.0981677175 0.5582714677 0.9631839991 734 29.3200000000 0.0152802579 0.0126519471 0.0324170515 0.0139810626 0.0355040000 373391876 0 402718720 -0.0993205458 0.5581121445 0.9640659094 735 29.3600000000 0.0149988094 0.0126551401 0.0324170515 0.0139734938 0.0362320000 373393336 0 402718720 -0.1046388000 0.5573881269 0.9648174644 736 29.4000000000 0.0150300320 0.0126583669 0.0324170515 0.0139678267 0.0360920000 373395328 0 402718720 -0.1079929769 0.5561186075 0.9648057222 737 29.4400000000 0.0155029157 0.0126622265 0.0324170515 0.0139627676 0.0348750000 373397772 0 402718720 -0.1111724079 0.5553132296 0.9645474553 738 29.4800000000 0.0153313465 0.0126658432 0.0324170515 0.0139553492 0.0403710000 374125884 0 402718720 -0.1132803857 0.5531553030 0.9656691551 739 29.5200000000 0.0155550456 0.0126697528 0.0324170515 0.0139499730 0.1263570000 374100424 0 402718720 -0.1139187366 0.5515033007 0.9659066796 740 29.5600000000 0.0161524191 0.0126744591 0.0324170515 0.0139465632 0.1060570000 374101972 0 402718720 -0.1150463969 0.5501946211 0.9665370584 741 29.6000000000 0.0148283709 0.0126773659 0.0324170515 0.0139431403 0.1025370000 374453920 0 402718720 -0.1171382070 0.5479214787 0.9660611749 742 29.6400000000 0.0143041862 0.0126795583 0.0324170515 0.0139385373 0.1088260000 383214128 0 402718720 -0.1183963716 0.5462793112 0.9660741091 743 29.6800000000 0.0146865016 0.0126822595 0.0324170515 0.0139351483 0.0623770000 386690880 0 402718720 -0.1187843457 0.5448163748 0.9665277004 744 29.7200000000 0.0140191400 0.0126840564 0.0324170515 0.0139366464 0.1016310000 386530217 0 402718720 -0.1228102818 0.5404635072 0.9671154618 745 29.7600000000 0.0130406786 0.0126845350 0.0324170515 0.0139289226 0.0429670000 386581064 0 402718720 -0.1236832440 0.5377318859 0.9667196274 746 29.8000000000 0.0150898341 0.0126877593 0.0324170515 0.0139223566 0.1332940000 386510495 0 402718720 -0.1244321167 0.5384770036 0.9684520364 747 29.8400000000 0.0135782082 0.0126889513 0.0324170515 0.0139146841 0.0633880000 374113088 0 402718720 -0.1275122613 0.5357300043 0.9681940675 748 29.8800000000 0.0145583022 0.0126914505 0.0324170515 0.0139055516 0.0356920000 374113872 0 402718720 -0.1274735183 0.5352522135 0.9688761830 749 29.9200000000 0.0139749739 0.0126931641 0.0324170515 0.0138967759 0.0353410000 374115912 0 402718720 -0.1286053360 0.5324771404 0.9700205326 750 29.9600000000 0.0159300379 0.0126974800 0.0324170515 0.0138875794 0.0361770000 374119072 0 402718720 -0.1305087060 0.5343015194 0.9708381295 751 30.0000000000 0.0141443536 0.0126994065 0.0324170515 0.0138792712 0.0458400000 374117340 0 402718720 -0.1301830709 0.5293208957 0.9706894755 752 30.0400000000 0.0140253501 0.0127011698 0.0324170515 0.0138706143 0.0353170000 374116944 0 402718720 -0.1309477836 0.5276954174 0.9712406993 753 30.0800000000 0.0140571157 0.0127029705 0.0324170515 0.0138639934 0.0394540000 374663400 0 402718720 -0.1329118609 0.5267540216 0.9718806744 754 30.1200000000 0.0134089682 0.0127039068 0.0324170515 0.0138564102 0.1137590000 374722580 0 402718720 -0.1312786490 0.5239237547 0.9730533361 755 30.1600000000 0.0136101460 0.0127051071 0.0324170515 0.0138505671 0.1001290000 374724996 0 402718720 -0.1316390038 0.5229253173 0.9741506577 756 30.2000000000 0.0161742102 0.0127096959 0.0324170515 0.0138433595 0.0918330000 375021660 0 402718720 -0.1308667064 0.5241773725 0.9762009382 757 30.2400000000 0.0140224118 0.0127114300 0.0324170515 0.0138358013 0.0960760000 383385492 0 402718720 -0.1307586282 0.5203407407 0.9764754772 758 30.2800000000 0.0154590243 0.0127150548 0.0324170515 0.0138316111 0.0649800000 388035585 0 402718720 -0.1306213886 0.5230504870 0.9780504704 759 30.3200000000 0.0148536507 0.0127178725 0.0324170515 0.0138256955 0.0697990000 387552914 0 402718720 -0.1309185624 0.5212639570 0.9791971445 760 30.3600000000 0.0143495025 0.0127200193 0.0324170515 0.0138249781 0.0578290000 387637489 0 402718720 -0.1293199956 0.5190579295 0.9794751406 761 30.4000000000 0.0148114646 0.0127227676 0.0324170515 0.0138190826 0.0373860000 387333656 0 402718720 -0.1284041703 0.5186902881 0.9818012118 762 30.4400000000 0.0133530712 0.0127235948 0.0324170515 0.0138111738 0.1147040000 387420463 0 402718720 -0.1311991066 0.5168520808 0.9822656512 763 30.4800000000 0.0142998155 0.0127256606 0.0324170515 0.0138025963 0.0751420000 374734780 0 402718720 -0.1285422891 0.5151838660 0.9845551252 764 30.5200000000 0.0135229630 0.0127267042 0.0324170515 0.0137951609 0.0372640000 375268204 0 402718720 -0.1267476380 0.5125287175 0.9857760072 765 30.5600000000 0.0136521431 0.0127279139 0.0324170515 0.0137871705 0.1135420000 375326452 0 402718720 -0.1254059970 0.5105725527 0.9881058335 766 30.6000000000 0.0132374177 0.0127285791 0.0324170515 0.0137847355 0.0915880000 375320808 0 402718720 -0.1228955686 0.5091884136 0.9889060259 767 30.6400000000 0.0126868896 0.0127285247 0.0324170515 0.0137871583 0.0857960000 375374180 0 402718720 -0.1191069037 0.5049520135 0.9913281202 768 30.6800000000 0.0130862379 0.0127289905 0.0324170515 0.0137951076 0.0854650000 385008956 0 402718720 -0.1162395328 0.5051598549 0.9925593138 769 30.7200000000 0.0127310697 0.0127289932 0.0324170515 0.0138421232 0.0540620000 388391428 0 402718720 -0.1094781756 0.5021062493 0.9966408610 770 30.7600000000 0.0128089227 0.0127290970 0.0324170515 0.0138665277 0.0606280000 388659984 0 402718720 -0.1052716374 0.4966557026 0.9989321232 771 30.8000000000 0.0124232816 0.0127287004 0.0324170515 0.0138885310 0.0557920000 388121468 0 402718720 -0.1020042300 0.4943895936 0.9996262789 772 30.8400000000 0.0145302331 0.0127310339 0.0324170515 0.0139093809 0.0342250000 388122760 0 402718720 -0.0984490812 0.4950443208 1.0020542145 773 30.8800000000 0.0133437738 0.0127318266 0.0324170515 0.0139290396 0.1130640000 388211739 0 402718720 -0.0963589549 0.4903979301 1.0030264854 774 30.9200000000 0.0119645046 0.0127308353 0.0324170515 0.0139511557 0.0779130000 375871784 0 402718720 -0.0923975855 0.4853718877 1.0034605265 775 30.9600000000 0.0125985229 0.0127306645 0.0324170515 0.0139700193 0.1044070000 375921772 0 402718720 -0.0898612738 0.4840559363 1.0045527220 776 31.0000000000 0.0123427939 0.0127301647 0.0324170515 0.0139912236 0.0877520000 375926508 0 402718720 -0.0855492502 0.4813662767 1.0058391094 777 31.0400000000 0.0126119461 0.0127300125 0.0324170515 0.0140002861 0.0795340000 376189532 0 402718720 -0.0827429593 0.4792767167 1.0076066256 778 31.0800000000 0.0119126774 0.0127289620 0.0324170515 0.0140049299 0.0832480000 384293840 0 402718720 -0.0797074437 0.4753434360 1.0085254908 779 31.1200000000 0.0108909719 0.0127266026 0.0324170515 0.0140021360 0.0674700000 388803888 0 402718720 -0.0759435296 0.4698099494 1.0111224651 780 31.1600000000 0.0121964365 0.0127259229 0.0324170515 0.0140000760 0.0489670000 388731392 0 402718720 -0.0740270615 0.4693326354 1.0124523640 781 31.2000000000 0.0119841546 0.0127249731 0.0324170515 0.0139942239 0.0659690000 388761101 0 402718720 -0.0726754367 0.4643482268 1.0146105289 782 31.2400000000 0.0109111974 0.0127226537 0.0324170515 0.0139905128 0.0326750000 388531552 0 402718720 -0.0679045618 0.4600895047 1.0163875818 783 31.2800000000 0.0121286334 0.0127218950 0.0324170515 0.0139856234 0.1109040000 388620863 0 402718720 -0.0669057071 0.4568960667 1.0186736584 784 31.3200000000 0.0122345565 0.0127212734 0.0324170515 0.0139816233 0.0729140000 376470624 0 402718720 -0.0627745986 0.4524613619 1.0210157633 785 31.3600000000 0.0120423287 0.0127204085 0.0324170515 0.0139755564 0.1012020000 376518500 0 402718720 -0.0616419017 0.4478575587 1.0223188400 786 31.4000000000 0.0126801142 0.0127203573 0.0324170515 0.0139692104 0.0854930000 376512068 0 402718720 -0.0600897372 0.4454912543 1.0235109329 787 31.4400000000 0.0128438110 0.0127205141 0.0324170515 0.0139620371 0.0774810000 376770264 0 402718720 -0.0575642586 0.4392577112 1.0254958868 788 31.4800000000 0.0133195082 0.0127212743 0.0324170515 0.0139578242 0.0780250000 384745168 0 402718720 -0.0567193031 0.4344910085 1.0276409388 789 31.5200000000 0.0130403694 0.0127216787 0.0324170515 0.0139561737 0.0681980000 389596476 0 402718720 -0.0559965074 0.4288946688 1.0295226574 790 31.5600000000 0.0142831272 0.0127236552 0.0324170515 0.0139574142 0.0304470000 389892344 0 402718720 -0.0542615950 0.4242517948 1.0310795307 791 31.6000000000 0.0127641037 0.0127237064 0.0324170515 0.0139784291 0.0720460000 389835875 0 402718720 -0.0527303219 0.4140628576 1.0332664251 792 31.6400000000 0.0107807061 0.0127212531 0.0324170515 0.0139725115 0.0290260000 389945365 0 402718720 -0.0519714653 0.4072387516 1.0349793434 793 31.6800000000 0.0144744366 0.0127234639 0.0324170515 0.0139737758 0.0300470000 389783268 0 402718720 -0.0508256257 0.4047519863 1.0383710861 794 31.7200000000 0.0139940456 0.0127250641 0.0324170515 0.0139692209 0.0928800000 389698803 0 402718720 -0.0510455668 0.4039373398 1.0382531881 795 31.7600000000 0.0126636066 0.0127249868 0.0324170515 0.0139631596 0.0679910000 376740481 0 402718720 -0.0493793488 0.4013509750 1.0397803783 796 31.8000000000 0.0120025175 0.0127240792 0.0324170515 0.0139582918 0.0285080000 376894832 0 402718720 -0.0509713292 0.3942971528 1.0422718525 797 31.8400000000 0.0132664237 0.0127247597 0.0324170515 0.0139621778 0.0776740000 376922840 0 402718720 -0.0507843196 0.3907921612 1.0442173481 798 31.8800000000 0.0138810351 0.0127262087 0.0324170515 0.0140323307 0.0654120000 376920664 0 402718720 -0.0491552651 0.3731556833 1.0510666370 799 31.9200000000 0.0125324316 0.0127259661 0.0324170515 0.0140416678 0.0601370000 380311704 0 402718720 -0.0501693785 0.3624321818 1.0538197756 800 31.9600000000 0.0124135241 0.0127255756 0.0324170515 0.0140508300 0.0589920000 385952924 0 402718720 -0.0502782464 0.3584524095 1.0557612181 801 32.0000000000 0.0113798827 0.0127238956 0.0324170515 0.0140441063 0.0261600000 389923624 0 402718720 -0.0508844256 0.3532538712 1.0583564043 802 32.0400000000 0.0126953255 0.0127238599 0.0324170515 0.0140354126 0.0627610000 389999283 0 402718720 -0.0521619320 0.3467196226 1.0613226891 803 32.0800000000 0.0125442250 0.0127236362 0.0324170515 0.0140267860 0.0259090000 389899634 0 402718720 -0.0519865453 0.3369440436 1.0651557446 804 32.1199999990 0.0125269359 0.0127233916 0.0324170515 0.0140205493 0.0261240000 389815512 0 402718720 -0.0564127862 0.3202560842 1.0716184378 805 32.1600000000 0.0124954768 0.0127231085 0.0324170515 0.0140134191 0.0677360000 389726675 0 402718720 -0.0563717782 0.3171530962 1.0744901896 806 32.2000000000 0.0132260714 0.0127237325 0.0324170515 0.0140048802 0.0561540000 378566489 0 402718720 -0.0583349764 0.3130834401 1.0774242878 807 32.2400000000 0.0121224858 0.0127229874 0.0324170515 0.0139982451 0.0274230000 377186556 0 402718720 -0.0570293963 0.3041538000 1.0814226866 808 32.2800000000 0.0132486224 0.0127236380 0.0324170515 0.0139899168 0.0585050000 377210460 0 402718720 -0.0602525175 0.2992650270 1.0847121477 809 32.3200000000 0.0129740266 0.0127239475 0.0324170515 0.0139821916 0.0512700000 377211356 0 402718720 -0.0591048896 0.2859555483 1.0894750357 810 32.3600000000 0.0132620512 0.0127246118 0.0324170515 0.0139738567 0.0512700000 383242460 0 402718720 -0.0579138994 0.2745349407 1.0941854715 811 32.4000000000 0.0104332278 0.0127217864 0.0324170515 0.0139686260 0.0500070000 387544052 0 402718720 -0.0600635409 0.2674447000 1.0978441238 812 32.4399999990 0.0130075533 0.0127221384 0.0324170515 0.0139624942 0.0288110000 390150372 0 402718720 -0.0599703193 0.2645831406 1.1018683910 813 32.4800000000 0.0123306960 0.0127216569 0.0324170515 0.0139566931 0.0271600000 390058735 0 402718720 -0.0655566454 0.2524685562 1.1082178354 814 32.5200000000 0.0123683447 0.0127212228 0.0324170515 0.0139485621 0.0535210000 390322311 0 402718720 -0.0664468408 0.2418971062 1.1128027439 815 32.5600000000 0.0137650948 0.0127225037 0.0324170515 0.0139447535 0.0227850000 389950805 0 402718720 -0.0660386086 0.2348174155 1.1168614626 816 32.6000000000 0.0134477541 0.0127233924 0.0324170515 0.0139365431 0.0251710000 390053904 0 402718720 -0.0690299273 0.2266788483 1.1225352287 817 32.6400000000 0.0131568769 0.0127239230 0.0324170515 0.0139317245 0.0847890000 389964371 0 402718720 -0.0728730857 0.2117768228 1.1296585798 818 32.6800000000 0.0132277850 0.0127245390 0.0324170515 0.0139233281 0.0601010000 378116833 0 402718720 -0.0732108057 0.1960480809 1.1361238956 819 32.7200000000 0.0138259511 0.0127258838 0.0324170515 0.0139156009 0.0504390000 377508996 0 402718720 -0.0737233758 0.1862449199 1.1420298815 820 32.7599999990 0.0133123351 0.0127265990 0.0324170515 0.0139072163 0.0496750000 377509948 0 402718720 -0.0750280321 0.1799321622 1.1458055973 821 32.7999999990 0.0142493965 0.0127284538 0.0324170515 0.0138994683 0.0422500000 377623360 0 402718720 -0.0758366883 0.1722270399 1.1510753632 822 32.8400000000 0.0154203391 0.0127317286 0.0324170515 0.0138940423 0.0526820000 385789779 0 402718720 -0.0766168833 0.1624938250 1.1556515694 823 32.8800000000 0.0172952022 0.0127372735 0.0324170515 0.0138885556 0.0602820000 387238077 0 402718720 -0.0773652494 0.1519209743 1.1622388363 824 32.9200000000 0.0156025151 0.0127407508 0.0324170515 0.0138814776 0.0505160000 377750520 0 402718720 -0.0758899152 0.1401149929 1.1666963100 825 32.9600000000 0.0143601624 0.0127427137 0.0324170515 0.0138747276 0.0457810000 377784420 0 402718720 -0.0768769979 0.1288343519 1.1711468697 826 33.0000000000 0.0146486443 0.0127450211 0.0324170515 0.0138679091 0.0469300000 377786296 0 402718720 -0.0772339106 0.1200705469 1.1764049530 827 33.0400000000 0.0137679335 0.0127462580 0.0324170515 0.0138616089 0.0489760000 378036087 0 402718720 -0.0779793859 0.1088154167 1.1804318428 828 33.0800000000 0.0185512435 0.0127532689 0.0324170515 0.0138572319 0.0531830000 387356813 0 402718720 -0.0776787400 0.1067036241 1.1851142645 829 33.1199999990 0.0166556723 0.0127579762 0.0324170515 0.0138556101 0.0545050000 383683437 0 402718720 -0.0775695145 0.0938918442 1.1885836124 830 33.1600000000 0.0153228631 0.0127610665 0.0324170515 0.0138525761 0.0455850000 377995468 0 402718720 -0.0759528875 0.0796433538 1.1933268309 831 33.2000000000 0.0138825653 0.0127624160 0.0324170515 0.0138480003 0.0471940000 378194971 0 402718720 -0.0764867067 0.0661315769 1.1971390247 832 33.2400000000 0.0170177836 0.0127675307 0.0324170515 0.0138410193 0.0446530000 378281804 0 402718720 -0.0768615007 0.0614126958 1.2001024485 833 33.2800000000 0.0156508554 0.0127709920 0.0324170515 0.0138379405 0.0432020000 378218892 0 402718720 -0.0766965449 0.0491218716 1.2045899630 834 33.3200000000 0.0150761874 0.0127737561 0.0324170515 0.0138307245 0.0430190000 378480107 0 402718720 -0.0763227940 0.0396819860 1.2069833279 835 33.3600000000 0.0160048082 0.0127776256 0.0324170515 0.0138227724 0.0480430000 378583475 0 402718720 -0.0757256150 0.0334518366 1.2094578743 836 33.4000000000 0.0179732330 0.0127838404 0.0324170515 0.0138163645 0.0417480000 378654548 0 402718720 -0.0780156553 0.0255541019 1.2122118473 837 33.4399999990 0.0158110037 0.0127874571 0.0324170515 0.0138170459 0.0468170000 378775727 0 402718720 -0.0738810599 0.0144045856 1.2147567272 838 33.4800000000 0.0172786769 0.0127928166 0.0324170515 0.0138109816 0.0366030000 378794216 0 402718720 -0.0732192099 0.0059561133 1.2175947428 839 33.5200000000 0.0156681947 0.0127962437 0.0324170515 0.0138044597 0.0455890000 379007635 0 402718720 -0.0701726973 -0.0035016146 1.2195309401 840 33.5600000000 0.0142131094 0.0127979304 0.0324170515 0.0137981902 0.0460850000 379086651 0 402718720 -0.0705357194 -0.0125531759 1.2212893963 841 33.6000000000 0.0167766251 0.0128026614 0.0324170515 0.0137943125 0.0326550000 379102492 0 402718720 -0.0676799417 -0.0214024447 1.2250518799 842 33.6400000000 0.0166161880 0.0128071905 0.0324170515 0.0137867977 0.0425740000 379312087 0 402718720 -0.0638981760 -0.0336579233 1.2279047966 843 33.6800000000 0.0158516876 0.0128108020 0.0324170515 0.0137801533 0.0435800000 379290748 0 402718720 -0.0639722943 -0.0405803025 1.2283737659 844 33.7200000000 0.0153978812 0.0128138672 0.0324170515 0.0137807101 0.0438310000 381809321 0 402718720 -0.0640652180 -0.0487739034 1.2300934792 845 33.7599999990 0.0189004075 0.0128210703 0.0324170515 0.0137754166 0.0442750000 388182840 0 402718720 -0.0653769076 -0.0561312251 1.2318754196 846 33.7999999990 0.0155144790 0.0128242540 0.0324170515 0.0137797867 0.0457900000 385709013 0 402718720 -0.0614086092 -0.0637565553 1.2312347889 847 33.8400000000 0.0172595270 0.0128294904 0.0324170515 0.0137777743 0.0463310000 379538795 0 402718720 -0.0647235215 -0.0687866062 1.2320507765 848 33.8800000000 0.0162054282 0.0128334715 0.0324170515 0.0137767671 0.0414270000 379682516 0 402718720 -0.0606529415 -0.0802943259 1.2348915339 849 33.9200000000 0.0157465544 0.0128369027 0.0324170515 0.0137702031 0.0326660000 379719456 0 402718720 -0.0629164577 -0.0889850706 1.2359497547 850 33.9600000000 0.0160636939 0.0128406989 0.0324170515 0.0137645010 0.0429410000 379917051 0 402718720 -0.0653465986 -0.0931329355 1.2350202799 851 34.0000000000 0.0187383592 0.0128476291 0.0324170515 0.0137565021 0.0417360000 379893256 0 402718720 -0.0689466298 -0.0981727242 1.2348462343 852 34.0400000000 0.0161079783 0.0128514559 0.0324170515 0.0137511984 0.0416170000 384510207 0 402718720 -0.0647509098 -0.1033203900 1.2344321012 853 34.0800000000 0.0193078220 0.0128590249 0.0324170515 0.0137440103 0.0431740000 389218116 0 402718720 -0.0672194362 -0.1048886329 1.2339670658 854 34.1199999990 0.0167378914 0.0128635669 0.0324170515 0.0137510584 0.0499320000 391073737 0 402718720 -0.0659700334 -0.1145570874 1.2339234352 855 34.1600000000 0.0169503745 0.0128683468 0.0324170515 0.0137442317 0.0482530000 380310437 0 402718720 -0.0652720630 -0.1194614992 1.2345740795 856 34.2000000000 0.0166845284 0.0128728049 0.0324170515 0.0137382722 0.0412550000 380022535 0 402718720 -0.0651587844 -0.1217485219 1.2335593700 857 34.2400000000 0.0172760617 0.0128779429 0.0324170515 0.0137337170 0.0395050000 380043399 0 402718720 -0.0656895936 -0.1242626756 1.2329037189 858 34.2800000000 0.0181968603 0.0128841421 0.0324170515 0.0137339023 0.0399870000 385180755 0 402718720 -0.0623696446 -0.1251198351 1.2315658331 859 34.3200000000 0.0177970696 0.0128898615 0.0324170515 0.0137387011 0.0431940000 389942272 0 402718720 -0.0611850321 -0.1272265315 1.2296881676 860 34.3600000000 0.0145230219 0.0128917605 0.0324170515 0.0137434253 0.0500640000 390989053 0 402718720 -0.0592150688 -0.1328681111 1.2281413078 861 34.4000000000 0.0172774140 0.0128968542 0.0324170515 0.0137364567 0.0493810000 380339063 0 402718720 -0.0609728396 -0.1322799623 1.2273372412 862 34.4400000000 0.0163425691 0.0129008515 0.0324170515 0.0137503108 0.0414570000 380333920 0 402718720 -0.0571514666 -0.1356735379 1.2270467281 863 34.4800000000 0.0164055675 0.0129049126 0.0324170515 0.0137578612 0.0416900000 380386380 0 402718720 -0.0552817583 -0.1389380544 1.2259025574 864 34.5200000000 0.0167595465 0.0129093740 0.0324170515 0.0137642927 0.0444230000 380593043 0 402718720 -0.0585313439 -0.1402764320 1.2248879671 865 34.5600000000 0.0163181052 0.0129133147 0.0324170515 0.0137691277 0.0461990000 389076328 0 402718720 -0.0556361079 -0.1411747187 1.2234473228 866 34.6000000000 0.0159024838 0.0129167664 0.0324170515 0.0137675900 0.0526920000 390875249 0 402718720 -0.0554350615 -0.1458220631 1.2218219042 867 34.6400000000 0.0155062666 0.0129197531 0.0324170515 0.0137629324 0.0521690000 380672016 0 402718720 -0.0530144572 -0.1477799118 1.2220184803 868 34.6800000000 0.0161514841 0.0129234763 0.0324170515 0.0137573784 0.0414800000 380668268 0 402718720 -0.0537343025 -0.1486478895 1.2201372385 869 34.7200000000 0.0152604999 0.0129261657 0.0324170515 0.0137532082 0.0414960000 380722492 0 402718720 -0.0491090119 -0.1512989402 1.2206399441 870 34.7600000000 0.0186143424 0.0129327038 0.0324170515 0.0137455537 0.0432480000 385273811 0 402718720 -0.0510742664 -0.1504947394 1.2187774181 871 34.8000000000 0.0183242839 0.0129388939 0.0324170515 0.0137409468 0.0466600000 390320192 0 402718720 -0.0499379039 -0.1541505903 1.2182368040 872 34.8400000000 0.0169410892 0.0129434836 0.0324170515 0.0137373970 0.0517210000 391722393 0 402718720 -0.0509069264 -0.1601034701 1.2177100182 873 34.8800000000 0.0176679529 0.0129488953 0.0324170515 0.0137301870 0.0534670000 381025361 0 402718720 -0.0494716167 -0.1619135290 1.2184449434 874 34.9200000000 0.0165394451 0.0129530035 0.0324170515 0.0137236726 0.0444570000 381026844 0 402718720 -0.0496712625 -0.1649456918 1.2164913416 875 34.9600000000 0.0173301846 0.0129580060 0.0324170515 0.0137168192 0.0346000000 381204699 0 402718720 -0.0488361418 -0.1666686535 1.2157840729 876 35.0000000000 0.0195847284 0.0129655708 0.0324170515 0.0137093289 0.0426250000 381421123 0 402718720 -0.0498945415 -0.1675108671 1.2153874636 877 35.0400000000 0.0178697426 0.0129711627 0.0324170515 0.0137026272 0.0430130000 381522811 0 402718720 -0.0500268340 -0.1718334854 1.2144281864 878 35.0800000000 0.0193046443 0.0129783763 0.0324170515 0.0136953834 0.0392090000 381637967 0 402718720 -0.0491340160 -0.1734967530 1.2139484882 879 35.1200000000 0.0205896124 0.0129870352 0.0324170515 0.0136888127 0.0411230000 381688863 0 402718720 -0.0525684357 -0.1771485209 1.2133663893 880 35.1600000000 0.0182588380 0.0129930259 0.0324170515 0.0136818031 0.0421660000 381870215 0 402718720 -0.0518782139 -0.1841039658 1.2107758522 881 35.2000000000 0.0181571506 0.0129988876 0.0324170515 0.0136746510 0.0430770000 390564632 0 402718720 -0.0506356657 -0.1846426129 1.2090420723 882 35.2400000000 0.0181814246 0.0130047635 0.0324170515 0.0136695753 0.0457720000 388122949 0 402718720 -0.0496415496 -0.1868223399 1.2078878880 883 35.2800000000 0.0180760249 0.0130105067 0.0324170515 0.0136663555 0.0445790000 381776503 0 402718720 -0.0506241024 -0.1895307600 1.2055062056 884 35.3200000000 0.0167966858 0.0130147897 0.0324170515 0.0136618998 0.0380290000 381786007 0 402718720 -0.0512024164 -0.1936202645 1.2044699192 885 35.3600000000 0.0181133933 0.0130205508 0.0324170515 0.0136673909 0.0397000000 381949267 0 402718720 -0.0522714555 -0.1947459280 1.2035447359 886 35.4000000000 0.0184958410 0.0130267306 0.0324170515 0.0136712190 0.0353320000 381973435 0 402718720 -0.0541018546 -0.1964388788 1.2017781734 887 35.4400000000 0.0178367421 0.0130321534 0.0324170515 0.0136713300 0.0416750000 382166971 0 402718720 -0.0536334813 -0.1972421110 1.1994134188 888 35.4800000000 0.0189971048 0.0130388707 0.0324170515 0.0136761292 0.0409810000 391439695 0 402718720 -0.0592561662 -0.2013866007 1.1978430748 889 35.5200000000 0.0164390001 0.0130426954 0.0324170515 0.0136816682 0.0471400000 393580248 0 402718720 -0.0525390506 -0.2010689080 1.1962261200 890 35.5600000000 0.0171864480 0.0130473513 0.0324170515 0.0136873516 0.0471010000 383071205 0 402718720 -0.0545459390 -0.2009497285 1.1944662333 891 35.6000000000 0.0162206609 0.0130509128 0.0324170515 0.0136893063 0.0397180000 382108439 0 402718720 -0.0563950539 -0.2054620683 1.1933448315 892 35.6400000000 0.0177214947 0.0130561489 0.0324170515 0.0137060340 0.0370650000 382124747 0 402718720 -0.0588312149 -0.2050696313 1.1909749508 893 35.6800000000 0.0205623694 0.0130645545 0.0324170515 0.0137188504 0.0380550000 382316515 0 402718720 -0.0666725338 -0.2069416344 1.1898348331 894 35.7200000000 0.0198058672 0.0130720951 0.0324170515 0.0137312005 0.0386990000 391798539 0 402718720 -0.0662585497 -0.2084776163 1.1885913610 895 35.7600000000 0.0155971926 0.0130749164 0.0324170515 0.0137351520 0.0443210000 393179517 0 402718720 -0.0638317466 -0.2130677253 1.1870809793 896 35.8000000000 0.0213708654 0.0130841753 0.0324170515 0.0137769241 0.0421090000 382543381 0 402718720 -0.0707010031 -0.2101143301 1.1856814623 897 35.8400000000 0.0179868005 0.0130896409 0.0324170515 0.0137850228 0.0368740000 382268771 0 402718720 -0.0662132800 -0.2107605189 1.1855654716 898 35.8800000000 0.0188221969 0.0130960246 0.0324170515 0.0137943247 0.0374150000 382441739 0 402718720 -0.0689146817 -0.2115840614 1.1847350597 899 35.9200000000 0.0163905080 0.0130996892 0.0324170515 0.0137975136 0.0319250000 382466583 0 402718720 -0.0660619438 -0.2130104154 1.1845352650 900 35.9600000000 0.0206954181 0.0131081289 0.0324170515 0.0138143784 0.0379160000 382645623 0 402718720 -0.0695965588 -0.2098291814 1.1841635704 901 36.0000000000 0.0190666076 0.0131147421 0.0324170515 0.0138147943 0.0388560000 390990035 0 402718720 -0.0694782734 -0.2119285762 1.1832201481 902 36.0400000000 0.0202285722 0.0131226288 0.0324170515 0.0138290911 0.0461230000 393105572 0 402718720 -0.0696274340 -0.2103633732 1.1826529503 903 36.0800000000 0.0195582714 0.0131297558 0.0324170515 0.0138346051 0.0429070000 382939829 0 402718720 -0.0722483695 -0.2118848264 1.1809091568 904 36.1200000000 0.0205573346 0.0131379721 0.0324170515 0.0138482189 0.0362990000 382602463 0 402718720 -0.0766605139 -0.2142415941 1.1804299355 905 36.1600000000 0.0185778476 0.0131439830 0.0324170515 0.0138687081 0.0376330000 382811655 0 402718720 -0.0740763545 -0.2144574821 1.1796540022 906 36.2000000000 0.0196337793 0.0131511462 0.0324170515 0.0138976224 0.0386940000 392943819 0 402718720 -0.0754573345 -0.2129001617 1.1781286001 907 36.2400000000 0.0206704009 0.0131594364 0.0324170515 0.0139189279 0.0246660000 395003051 0 402718720 -0.0777958035 -0.2139987200 1.1782376766 908 36.2800000000 0.0165922008 0.0131632170 0.0324170515 0.0139252137 0.0588860000 395363203 0 402718720 -0.0762878060 -0.2167851627 1.1770943403 909 36.3200000000 0.0157455355 0.0131660578 0.0324170515 0.0139308232 0.0443700000 385666889 0 402718720 -0.0780655146 -0.2183077633 1.1764323711 910 36.3600000000 0.0177432485 0.0131710877 0.0324170515 0.0139454712 0.0294900000 382890915 0 402718720 -0.0822967291 -0.2177118957 1.1752901077 911 36.4000000000 0.0187757369 0.0131772399 0.0324170515 0.0139576552 0.0353010000 382961343 0 402718720 -0.0820774436 -0.2172981799 1.1765193939 912 36.4400000000 0.0169883575 0.0131814187 0.0324170515 0.0139583282 0.0362430000 388457531 0 402718720 -0.0831552744 -0.2202134430 1.1756887436 913 36.4800000000 0.0201512165 0.0131890527 0.0324170515 0.0140479888 0.0369940000 393404831 0 402718720 -0.0890660286 -0.2183239758 1.1750272512 914 36.5200000000 0.0157013107 0.0131918013 0.0324170515 0.0140520090 0.0218850000 396277714 0 402718720 -0.0873304605 -0.2223700434 1.1741383076 915 36.5600000000 0.0153979221 0.0131942124 0.0324170515 0.0140676599 0.0610810000 396083943 0 402718720 -0.0898500681 -0.2236743718 1.1741354465 916 36.6000000000 0.0143976659 0.0131955262 0.0324170515 0.0140772355 0.0446060000 386168177 0 402718720 -0.0912817717 -0.2249898612 1.1737419367 917 36.6400000000 0.0158187449 0.0131983869 0.0324170515 0.0140926922 0.0388140000 383076436 0 402718720 -0.0934513211 -0.2242801338 1.1745196581 918 36.6800000000 0.0143651785 0.0131996579 0.0324170515 0.0140996435 0.0386280000 383237991 0 402718720 -0.0941392779 -0.2257405668 1.1736639738 919 36.7200000000 0.0143188806 0.0132008758 0.0324170515 0.0141141128 0.0376360000 383261044 0 402718720 -0.0937666893 -0.2254776806 1.1743350029 920 36.7600000000 0.0130594149 0.0132007220 0.0324170515 0.0141273404 0.0405450000 387600943 0 402718720 -0.0965672135 -0.2274265736 1.1732151508 921 36.8000000000 0.0127380714 0.0132002197 0.0324170515 0.0141336635 0.0420050000 392535676 0 402718720 -0.0984416008 -0.2288439125 1.1733392477 922 36.8400000000 0.0128117884 0.0131997984 0.0324170515 0.0141410086 0.0477940000 388518497 0 402718720 -0.0992966890 -0.2288375944 1.1739772558 923 36.8800000000 0.0134237129 0.0132000410 0.0324170515 0.0141500606 0.0364260000 383414230 0 402718720 -0.1012974977 -0.2284157276 1.1746574640 924 36.9200000000 0.0133673316 0.0132002220 0.0324170515 0.0141516616 0.0415540000 383658307 0 402718720 -0.1030161977 -0.2294704467 1.1753842831 925 36.9600000000 0.0122754341 0.0131992222 0.0324170515 0.0141512119 0.0390800000 383632204 0 402718720 -0.1053142548 -0.2307114452 1.1743236780 926 37.0000000000 0.0134883896 0.0131995345 0.0324170515 0.0141603941 0.0411200000 392879935 0 402718720 -0.1070216894 -0.2297645211 1.1751786470 927 37.0400000000 0.0121740131 0.0131984282 0.0324170515 0.0141626403 0.0378300000 395863815 0 402718720 -0.1061011553 -0.2308070809 1.1756300926 928 37.0800000000 0.0136050563 0.0131988664 0.0324170515 0.0141823569 0.0198260000 398521649 0 402718720 -0.1110966206 -0.2300745547 1.1747543812 929 37.1200000000 0.0119954934 0.0131975711 0.0324170515 0.0141881722 0.0589860000 397030739 0 402718720 -0.1112826467 -0.2311215699 1.1747558117 930 37.1600000000 0.0111017097 0.0131953175 0.0324170515 0.0141922365 0.0461060000 386712761 0 402718720 -0.1124814749 -0.2317363471 1.1741380692 931 37.2000000000 0.0112472735 0.0131932250 0.0324170515 0.0141988963 0.0369480000 383773627 0 402718720 -0.1140493751 -0.2320704907 1.1742830276 932 37.2400000000 0.0125446236 0.0131925291 0.0324170515 0.0142215401 0.0365950000 391154879 0 402718720 -0.1170161366 -0.2316773832 1.1740505695 933 37.2800000000 0.0140967453 0.0131934983 0.0324170515 0.0142565346 0.0303040000 394283899 0 402718720 -0.1201454997 -0.2298069447 1.1729263067 934 37.3200000000 0.0106374938 0.0131907616 0.0324170515 0.0142635711 0.0176970000 396782093 0 402718720 -0.1191408634 -0.2311029136 1.1716512442 935 37.3600000000 0.0128010120 0.0131903448 0.0324170515 0.0142919260 0.0176810000 396498515 0 402718720 -0.1218625307 -0.2278873622 1.1706261635 936 37.4000000000 0.0114558842 0.0131884917 0.0324170515 0.0142957499 0.0351390000 396429439 0 402718720 -0.1228533983 -0.2300712615 1.1702625751 937 37.4400000000 0.0120248944 0.0131872499 0.0324170515 0.0143059721 0.0168030000 396733645 0 402718720 -0.1230699420 -0.2273760289 1.1705977917 938 37.4800000000 0.0124678416 0.0131864829 0.0324170515 0.0143106967 0.0153240000 396079863 0 402718720 -0.1269940138 -0.2266196907 1.1684216261 939 37.5200000000 0.0112455841 0.0131844160 0.0324170515 0.0143056589 0.0547860000 396140955 0 402718720 -0.1290080547 -0.2305736095 1.1676803827 940 37.5600000000 0.0130004240 0.0131842202 0.0324170515 0.0143265054 0.0327070000 383808519 0 402718720 -0.1280409694 -0.2259500921 1.1694624424 941 37.6000000000 0.0133098345 0.0131843537 0.0324170515 0.0143266650 0.0144830000 383928507 0 402718720 -0.1304582357 -0.2254797220 1.1679192781 942 37.6400000000 0.0133527303 0.0131845325 0.0324170515 0.0143274325 0.0318610000 385378675 0 402718720 -0.1319611073 -0.2252916843 1.1666376591 943 37.6800000000 0.0137472255 0.0131851292 0.0324170515 0.0143311337 0.0234080000 386469199 0 402718720 -0.1320482492 -0.2254830301 1.1670902967 944 37.7200000000 0.0139987795 0.0131859911 0.0324170515 0.0143308020 0.0313140000 386158477 0 402718720 -0.1362670660 -0.2267224491 1.1654388905 945 37.7600000000 0.0144289127 0.0131873063 0.0324170515 0.0143373528 0.0134930000 383947647 0 402718720 -0.1365188360 -0.2252435535 1.1677726507 946 37.8000000000 0.0137092331 0.0131878581 0.0324170515 0.0143385693 0.0133710000 383949839 0 402718720 -0.1377224326 -0.2261132896 1.1666567326 947 37.8400000000 0.0138368364 0.0131885434 0.0324170515 0.0143405970 0.0129370000 383951479 0 402718720 -0.1396964788 -0.2252155542 1.1656328440 948 37.8800000000 0.0136132427 0.0131889914 0.0324170515 0.0143401071 0.0127500000 383953579 0 402718720 -0.1395006776 -0.2254152447 1.1684969664 949 37.9200000000 0.0141731631 0.0131900284 0.0324170515 0.0143439081 0.0127400000 383955311 0 402718720 -0.1427663565 -0.2194207311 1.1764099598 950 37.9600000000 0.0133188944 0.0131901641 0.0324170515 0.0143400505 0.0127900000 383958607 0 402718720 -0.1441656947 -0.2166535556 1.1862379313 951 38.0000000000 0.0140098119 0.0131910259 0.0324170515 0.0143451066 0.0133770000 383960707 0 402718720 -0.1432123184 -0.2140262872 1.1916460991 952 38.0400000000 0.0135707436 0.0131914248 0.0324170515 0.0143445007 0.0128520000 383964003 0 402718720 -0.1451512277 -0.2137743384 1.1911902428 953 38.0800000000 0.0150938081 0.0131934210 0.0324170515 0.0143491312 0.0113370000 383966931 0 402718720 -0.1479687691 -0.2109220326 1.1902034283 954 38.1200000000 0.0127825933 0.0131929904 0.0324170515 0.0143422260 0.0117720000 383970319 0 402718720 -0.1495303810 -0.2145932764 1.1902538538 955 38.1600000000 0.0137529159 0.0131935767 0.0324170515 0.0143478103 0.0117800000 383971499 0 402718720 -0.1474639177 -0.2138332427 1.1915408373 956 38.2000000000 0.0133330002 0.0131937225 0.0324170515 0.0143458227 0.0118660000 383974307 0 402718720 -0.1499059498 -0.2143498212 1.1913204193 957 38.2400000000 0.0136562409 0.0131942058 0.0324170515 0.0143513875 0.0141200000 384129147 0 402718720 -0.1517709196 -0.2119480819 1.1892404556 958 38.2800000000 0.0140552027 0.0131951046 0.0324170515 0.0143513007 0.0258140000 385829018 0 402718720 -0.1531175971 -0.2125451118 1.1853010654 959 38.3200000000 0.0124936951 0.0131943732 0.0324170515 0.0143447257 0.0280460000 385717711 0 402718720 -0.1537467241 -0.2155301124 1.1845035553 960 38.3600000000 0.0130545627 0.0131942275 0.0324170515 0.0143489701 0.0121040000 384142535 0 402718720 -0.1549659669 -0.2123600692 1.1859700680 961 38.4000000000 0.0137917353 0.0131948493 0.0324170515 0.0143490031 0.0123910000 384146783 0 402718720 -0.1557902098 -0.2116585970 1.1847825050 962 38.4400000000 0.0126441317 0.0131942768 0.0324170515 0.0143424242 0.0120600000 384147747 0 402718720 -0.1572135687 -0.2143833041 1.1839135885 963 38.4800000000 0.0117861340 0.0131928146 0.0324170515 0.0143381834 0.0120590000 384149847 0 402718720 -0.1573822200 -0.2157449275 1.1807397604 964 38.5200000000 0.0138049405 0.0131934496 0.0324170515 0.0143514628 0.0205330000 384152991 0 402718720 -0.1607915759 -0.2111733258 1.1804175377 965 38.5600000000 0.0128098419 0.0131930520 0.0324170515 0.0143486303 0.0127480000 384155459 0 402718720 -0.1596198678 -0.2125526220 1.1804795265 966 38.6000000000 0.0130087091 0.0131928612 0.0324170515 0.0143479927 0.0164050000 384329483 0 402718720 -0.1616344154 -0.2125040144 1.1794983149 967 38.6400000000 0.0123904748 0.0131920314 0.0324170515 0.0143451195 0.0307000000 385645664 0 402718720 -0.1626517773 -0.2120518386 1.1816139221 968 38.6800000000 0.0134194717 0.0131922664 0.0324170515 0.0143518259 0.0184270000 386312051 0 402718720 -0.1633019447 -0.2122224569 1.1802964211 969 38.7200000000 0.0133539708 0.0131924333 0.0324170515 0.0143619237 0.0157590000 385057333 0 402718720 -0.1671630740 -0.2116940320 1.1782020330 970 38.7600000000 0.0132709211 0.0131925142 0.0324170515 0.0143651147 0.0128120000 384339443 0 402718720 -0.1676747203 -0.2112409323 1.1767679453 971 38.8000000000 0.0137387821 0.0131930768 0.0324170515 0.0143654161 0.0127240000 384341911 0 402718720 -0.1693395972 -0.2117049545 1.1746469736 972 38.8400000000 0.0128194243 0.0131926924 0.0324170515 0.0143628530 0.0130620000 384343643 0 402718720 -0.1703172922 -0.2121906281 1.1738708019 973 38.8800000000 0.0135465655 0.0131930561 0.0324170515 0.0143660435 0.0159800000 384502879 0 402718720 -0.1713732183 -0.2116868347 1.1731967926 974 38.9200000000 0.0131919887 0.0131930550 0.0324170515 0.0143646050 0.0294440000 386014564 0 402718720 -0.1713795960 -0.2108812183 1.1740248203 975 38.9600000000 0.0138427354 0.0131937213 0.0324170515 0.0143672847 0.0292840000 386208923 0 402718720 -0.1721868515 -0.2091040313 1.1740779877 976 39.0000000000 0.0136849452 0.0131942246 0.0324170515 0.0143640327 0.0352800000 384526655 0 402718720 -0.1728315949 -0.2106154859 1.1730008125 977 39.0400000000 0.0143345622 0.0131953918 0.0324170515 0.0143688235 0.0152000000 384686503 0 402718720 -0.1747213602 -0.2084428370 1.1718313694 978 39.0800000000 0.0142263481 0.0131964459 0.0324170515 0.0143659221 0.0293340000 385362724 0 402718720 -0.1749613583 -0.2086597532 1.1704192162 979 39.1200000000 0.0144673921 0.0131977441 0.0324170515 0.0143638179 0.0180250000 386641160 0 402718720 -0.1753335297 -0.2091977447 1.1679993868 980 39.1600000000 0.0144832693 0.0131990559 0.0324170515 0.0143619827 0.0174560000 385360297 0 402718720 -0.1765443087 -0.2083212286 1.1657818556 981 39.2000000000 0.0145899458 0.0132004737 0.0324170515 0.0143600049 0.0132200000 384704564 0 402718720 -0.1770714819 -0.2079310566 1.1652179956 982 39.2400000000 0.0150824320 0.0132023902 0.0324170515 0.0143649501 0.0131840000 384707768 0 402718720 -0.1791510284 -0.2062087804 1.1616010666 983 39.2800000000 0.0147640649 0.0132039789 0.0324170515 0.0143625785 0.0131390000 384709056 0 402718720 -0.1788513064 -0.2078789026 1.1625041962 984 39.3200000000 0.0153457345 0.0132061554 0.0324170515 0.0143627479 0.0378930000 384870987 0 402718720 -0.1785688698 -0.2063754797 1.1623468399 985 39.3600000000 0.0134748649 0.0132064282 0.0324170515 0.0143581383 0.0320320000 386122212 0 402718720 -0.1790756881 -0.2071130872 1.1575391293 986 39.4000000000 0.0132878860 0.0132065109 0.0324170515 0.0143557702 0.0186330000 386924904 0 402718720 -0.1789117157 -0.2071817368 1.1561411619 987 39.4400000000 0.0138035640 0.0132071158 0.0324170515 0.0143534084 0.0166880000 385637849 0 402718720 -0.1803258806 -0.2069168538 1.1534206867 988 39.4800000000 0.0151546765 0.0132090870 0.0324170515 0.0143568000 0.0130690000 384903184 0 402718720 -0.1801621318 -0.2069540620 1.1543905735 989 39.5200000000 0.0146772629 0.0132105715 0.0324170515 0.0143562316 0.0137390000 384904380 0 402718720 -0.1810303330 -0.2064804733 1.1499421597 990 39.5600000000 0.0161569212 0.0132135476 0.0324170515 0.0143598988 0.0129150000 384907340 0 402718720 -0.1814645380 -0.2051511705 1.1503117085 991 39.6000000000 0.0154581955 0.0132158126 0.0324170515 0.0143575486 0.0371340000 384910176 0 402718720 -0.1816626638 -0.2039174885 1.1453307867 992 39.6400000000 0.0137021225 0.0132163029 0.0324170515 0.0143531992 0.0151800000 384913796 0 402718720 -0.1808810681 -0.2069013715 1.1443362236 993 39.6800000000 0.0151661998 0.0132182665 0.0324170515 0.0143558185 0.0167380000 385129207 0 402718720 -0.1820441186 -0.2057359517 1.1430771351 994 39.7200000000 0.0146339983 0.0132196908 0.0324170515 0.0143518678 0.0329130000 386787808 0 402718720 -0.1820302010 -0.2065117061 1.1391944885 995 39.7600000000 0.0140266269 0.0132205018 0.0324170515 0.0143467293 0.0260460000 386803775 0 402718720 -0.1822342873 -0.2061114609 1.1361056566 996 39.8000000000 0.0143092051 0.0132215949 0.0324170515 0.0143443327 0.0147580000 385161072 0 402718720 -0.1825689077 -0.2042590976 1.1336916685 997 39.8400000000 0.0152195012 0.0132235988 0.0324170515 0.0143430732 0.0138780000 385161700 0 402718720 -0.1830743402 -0.2022346556 1.1326696873 998 39.8800000000 0.0148439556 0.0132252224 0.0324170515 0.0143379965 0.0138550000 385163984 0 402718720 -0.1834885180 -0.2021709383 1.1303563118 999 39.9200000000 0.0136643788 0.0132256620 0.0324170515 0.0143419576 0.0371110000 385168660 0 402718720 -0.1839531362 -0.2013431340 1.1241841316 1000 39.9600000000 0.0143531738 0.0132267895 0.0324170515 0.0143416662 0.0159400000 385173000 0 402718720 -0.1840889156 -0.2010605931 1.1241110563 1001 40.0000000000 0.0142530939 0.0132278148 0.0324170515 0.0143375372 0.0150010000 385176388 0 402718720 -0.1844665408 -0.1990895718 1.1210407019 1002 40.0400000000 0.0142600974 0.0132288450 0.0324170515 0.0143401508 0.0143150000 385175972 0 402718720 -0.1847701669 -0.1995655745 1.1194629669 1003 40.0800000000 0.0142695978 0.0132298826 0.0324170515 0.0143350781 0.0145630000 385179576 0 402718720 -0.1857178509 -0.1968155950 1.1156668663 1004 40.1200000000 0.0160284024 0.0132326700 0.0324170515 0.0143396130 0.0138720000 385180172 0 402718720 -0.1855402887 -0.1953206062 1.1146425009 1005 40.1600000000 0.0136256600 0.0132330610 0.0324170515 0.0143384777 0.0144330000 385185064 0 402718720 -0.1855281591 -0.1968370676 1.1111162901 1006 40.2000000000 0.0130369896 0.0132328661 0.0324170515 0.0143454232 0.0142440000 385187440 0 402718720 -0.1851442754 -0.1980081201 1.1089022160 1007 40.2400000000 0.0133441444 0.0132329766 0.0324170515 0.0143413756 0.0142700000 385190400 0 402718720 -0.1852900237 -0.1966340393 1.1047134399 1008 40.2800000000 0.0137285516 0.0132334683 0.0324170515 0.0143409374 0.0146950000 385193328 0 402718720 -0.1849952936 -0.1972747296 1.1039019823 1009 40.3200000000 0.0134725152 0.0132337052 0.0324170515 0.0143360144 0.0248550000 385194968 0 402718720 -0.1855482757 -0.1955455393 1.0992414951 1010 40.3600000000 0.0134471599 0.0132339165 0.0324170515 0.0143362934 0.0250010000 385196516 0 402718720 -0.1852516681 -0.1959948838 1.0968260765 1011 40.4000000000 0.0134220701 0.0132341026 0.0324170515 0.0143437253 0.0145830000 385199352 0 402718720 -0.1847569048 -0.1961153150 1.0939663649 1012 40.4400000000 0.0132007990 0.0132340697 0.0324170515 0.0143424465 0.0139170000 385203200 0 402718720 -0.1848283112 -0.1946115643 1.0902447701 1013 40.4800000000 0.0149682257 0.0132357816 0.0324170515 0.0143421919 0.0141570000 385204656 0 402718720 -0.1859375834 -0.1921104491 1.0879511833 1014 40.5200000000 0.0129373698 0.0132354873 0.0324170515 0.0143464095 0.0145150000 385210316 0 402718720 -0.1849490106 -0.1932650059 1.0851491690 1015 40.5600000000 0.0161346085 0.0132383436 0.0324170515 0.0143518197 0.0145300000 385211832 0 402718720 -0.1869946867 -0.1888495535 1.0845154524 1016 40.6000000000 0.0135026276 0.0132386037 0.0324170515 0.0143567467 0.0144760000 385214992 0 402718720 -0.1859090775 -0.1893444955 1.0814021826 1017 40.6400000000 0.0133631276 0.0132387262 0.0324170515 0.0143558446 0.0147450000 385221816 0 402718720 -0.1861132681 -0.1881784648 1.0785936117 1018 40.6800000000 0.0139566055 0.0132394314 0.0324170515 0.0143555644 0.0148120000 385224192 0 402718720 -0.1870067716 -0.1855949014 1.0759593248 1019 40.7200000000 0.0128098233 0.0132390098 0.0324170515 0.0143589674 0.0147960000 385227328 0 402718720 -0.1866625845 -0.1848343462 1.0736593008 1020 40.7600000000 0.0129592177 0.0132387355 0.0324170515 0.0143629043 0.0148250000 385229468 0 402718720 -0.1862637401 -0.1837775707 1.0737236738 1021 40.8000000000 0.0151685104 0.0132406255 0.0324170515 0.0143676075 0.0150070000 385234996 0 402718720 -0.1874176413 -0.1809945554 1.0735015869 1022 40.8400000000 0.0156884603 0.0132430207 0.0324170515 0.0143632933 0.0156270000 385238696 0 402718720 -0.1885981262 -0.1779828370 1.0716633797 1023 40.8800000000 0.0145994909 0.0132443467 0.0324170515 0.0143655549 0.0154830000 385244772 0 402718720 -0.1885450780 -0.1773452908 1.0703608990 1024 40.9200000000 0.0160310473 0.0132470681 0.0324170515 0.0143656506 0.0285490000 385703991 0 402718720 -0.1902850270 -0.1736617088 1.0682346821 1025 40.9600000000 0.0159612168 0.0132497160 0.0324170515 0.0143795782 0.0536630000 386617776 0 402718720 -0.1903514862 -0.1727806777 1.0672501326 1026 41.0000000000 0.0153532568 0.0132517662 0.0324170515 0.0143850344 0.0285170000 388192584 0 402718720 -0.1905691922 -0.1702113003 1.0641002655 1027 41.0400000000 0.0146274101 0.0132531057 0.0324170515 0.0143895289 0.0263680000 386652269 0 402718720 -0.1907339394 -0.1688910574 1.0609036684 1028 41.0800000000 0.0158268586 0.0132556094 0.0324170515 0.0143920476 0.0214990000 385977788 0 402718720 -0.1917323172 -0.1649867892 1.0593029261 1029 41.1200000000 0.0141575700 0.0132564859 0.0324170515 0.0143912919 0.0210940000 385982828 0 402718720 -0.1905253977 -0.1631928980 1.0565710068 1030 41.1600000000 0.0143549545 0.0132575524 0.0324170515 0.0143893769 0.0214240000 385988280 0 402718720 -0.1910852492 -0.1617617756 1.0543190241 1031 41.2000000000 0.0135318805 0.0132578185 0.0324170515 0.0143939690 0.0211500000 385992716 0 402718720 -0.1908653677 -0.1600733995 1.0522397757 1032 41.2400000000 0.0139829433 0.0132585211 0.0324170515 0.0143905603 0.0208870000 385995028 0 402718720 -0.1911363751 -0.1577588469 1.0506290197 1033 41.2800000000 0.0129310368 0.0132582041 0.0324170515 0.0143861582 0.0210330000 386001936 0 402718720 -0.1904377937 -0.1571301371 1.0494886637 1034 41.3200000000 0.0141448127 0.0132590615 0.0324170515 0.0143962631 0.0209540000 386009152 0 402718720 -0.1914404035 -0.1515294015 1.0468544960 1035 41.3600000000 0.0136535587 0.0132594427 0.0324170515 0.0143918738 0.0210870000 386012548 0 402718720 -0.1907875985 -0.1506648809 1.0464743376 1036 41.4000000000 0.0140724033 0.0132602274 0.0324170515 0.0143861728 0.0208720000 386018100 0 402718720 -0.1917487681 -0.1459835470 1.0430552959 1037 41.4400000000 0.0138783939 0.0132608235 0.0324170515 0.0143910247 0.0212970000 386024720 0 402718720 -0.1916475445 -0.1437022537 1.0424882174 1038 41.4800000000 0.0127820671 0.0132603623 0.0324170515 0.0143916852 0.0210620000 386026992 0 402718720 -0.1913270950 -0.1428029537 1.0406002998 1039 41.5200000000 0.0139417732 0.0132610181 0.0324170515 0.0143944608 0.0454890000 386031684 0 402718720 -0.1924510449 -0.1392391473 1.0394940376 1040 41.5600000000 0.0140007390 0.0132617294 0.0324170515 0.0143996096 0.0207690000 386035984 0 402718720 -0.1927402467 -0.1371587664 1.0382448435 1041 41.6000000000 0.0134658571 0.0132619255 0.0324170515 0.0144016481 0.0207190000 386039028 0 402718720 -0.1922763586 -0.1346101463 1.0373827219 1042 41.6400000000 0.0148004154 0.0132634020 0.0324170515 0.0144003286 0.0321540000 386044044 0 402718720 -0.1930290461 -0.1296467930 1.0360848904 1043 41.6800000000 0.0149252387 0.0132649953 0.0324170515 0.0144011391 0.0209670000 386047592 0 402718720 -0.1931827366 -0.1261487007 1.0333241224 1044 41.7200000000 0.0141221089 0.0132658163 0.0324170515 0.0144083464 0.0323060000 386048804 0 402718720 -0.1927248985 -0.1258867830 1.0335402489 1045 41.7600000000 0.0147535661 0.0132672399 0.0324170515 0.0144049142 0.0209440000 386053344 0 402718720 -0.1932233572 -0.1228094697 1.0332489014 1046 41.8000000000 0.0146756461 0.0132685864 0.0324170515 0.0144014633 0.0408250000 386055676 0 402718720 -0.1935975403 -0.1210759282 1.0317664146 1047 41.8400000000 0.0150345061 0.0132702731 0.0324170515 0.0143991516 0.0210820000 386058788 0 402718720 -0.1933877468 -0.1201402694 1.0323418379 1048 41.8800000000 0.0130821569 0.0132700936 0.0324170515 0.0143968403 0.0209310000 386060888 0 402718720 -0.1921941042 -0.1197267249 1.0309824944 1049 41.9200000000 0.0136711290 0.0132704759 0.0324170515 0.0143963711 0.0212640000 386063264 0 402718720 -0.1928333342 -0.1181662157 1.0301935673 1050 41.9600000000 0.0132553391 0.0132704615 0.0324170515 0.0143912702 0.0204180000 386066300 0 402718720 -0.1925313473 -0.1155384779 1.0281398296 1051 42.0000000000 0.0138943773 0.0132710551 0.0324170515 0.0143859049 0.0206750000 386069136 0 402718720 -0.1927332282 -0.1132514104 1.0270050764 1052 42.0400000000 0.0130889900 0.0132708820 0.0324170515 0.0143854413 0.0205730000 386070424 0 402718720 -0.1925721318 -0.1135059744 1.0269132853 1053 42.0800000000 0.0148459524 0.0132723778 0.0324170515 0.0143827403 0.0459070000 386073352 0 402718720 -0.1937784702 -0.1109210029 1.0270234346 1054 42.1200000000 0.0128099816 0.0132719391 0.0324170515 0.0143840949 0.0205740000 386075912 0 402718720 -0.1923251450 -0.1118320897 1.0263025761 1055 42.1600000000 0.0137886070 0.0132724288 0.0324170515 0.0143776336 0.0204690000 386078428 0 402718720 -0.1932592988 -0.1077831164 1.0257117748 1056 42.2000000000 0.0122846225 0.0132714934 0.0324170515 0.0143757081 0.0206690000 386081080 0 402718720 -0.1925441027 -0.1055860594 1.0238169432 1057 42.2400000000 0.0129647404 0.0132712032 0.0324170515 0.0143784754 0.0206510000 386083640 0 402718720 -0.1931536198 -0.1054783538 1.0249886513 1058 42.2800000000 0.0152161047 0.0132730415 0.0324170515 0.0143734481 0.0207710000 386086032 0 402718720 -0.1943841577 -0.1016691998 1.0265889168 1059 42.3200000000 0.0123817390 0.0132721998 0.0324170515 0.0143752115 0.0206100000 386088040 0 402718720 -0.1928631067 -0.1035411805 1.0259859562 1060 42.3600000000 0.0157328434 0.0132745212 0.0324170515 0.0143708448 0.0342010000 386090340 0 402718720 -0.1958110183 -0.0989431739 1.0255383253 1061 42.4000000000 0.0163552705 0.0132774248 0.0324170515 0.0143656829 0.0202540000 386092548 0 402718720 -0.1961487830 -0.0971703157 1.0271114111 1062 42.4400000000 0.0135599477 0.0132776909 0.0324170515 0.0143862423 0.0285240000 387053215 0 402718720 -0.1951625347 -0.0974377692 1.0288096666 1063 42.4800000000 0.0139448261 0.0132783185 0.0324170515 0.0143805140 0.1138240000 387308692 0 402718720 -0.1956439018 -0.0962142721 1.0298711061 1064 42.5200000000 0.0142192757 0.0132792028 0.0324170515 0.0143744610 0.0708300000 391197840 0 402718720 -0.1957940459 -0.0948823914 1.0310560465 1065 42.5600000000 0.0156576242 0.0132814361 0.0324170515 0.0143679841 0.0517920000 390861193 0 402718720 -0.1966137588 -0.0922031328 1.0325849056 1066 42.6000000000 0.0168058034 0.0132847422 0.0324170515 0.0143618384 0.0379570000 387144068 0 402718720 -0.1971381158 -0.0896329433 1.0344351530 1067 42.6400000000 0.0171246305 0.0132883410 0.0324170515 0.0143565102 0.0371300000 387146032 0 402718720 -0.1970399469 -0.0876968801 1.0354850292 1068 42.6800000000 0.0174258929 0.0132922151 0.0324170515 0.0143515436 0.0372030000 387148500 0 402718720 -0.1965123862 -0.0855150223 1.0360199213 1069 42.7200000000 0.0169619638 0.0132956480 0.0324170515 0.0143509503 0.0360090000 387150692 0 402718720 -0.1960690618 -0.0849970803 1.0363134146 1070 42.7600000000 0.0163421556 0.0132984952 0.0324170515 0.0143507590 0.0353650000 387153528 0 402718720 -0.1957456321 -0.0846615210 1.0369945765 1071 42.8000000000 0.0168207996 0.0133017840 0.0324170515 0.0143464971 0.0336030000 387155628 0 402718720 -0.1958409846 -0.0829319507 1.0390774012 1072 42.8400000000 0.0162563324 0.0133045401 0.0324170515 0.0143452582 0.0341010000 387157560 0 402718720 -0.1959696412 -0.0834997520 1.0405400991 1073 42.8800000000 0.0161615591 0.0133072028 0.0324170515 0.0143395624 0.0573870000 387160120 0 402718720 -0.1957209259 -0.0809190199 1.0402588844 1074 42.9200000000 0.0153044648 0.0133090624 0.0324170515 0.0143363569 0.0335830000 387162344 0 402718720 -0.1957778186 -0.0810391679 1.0399512053 1075 42.9600000000 0.0160985123 0.0133116572 0.0324170515 0.0143298537 0.0449460000 387164644 0 402718720 -0.1956204921 -0.0787515864 1.0414676666 1076 43.0000000000 0.0164175909 0.0133145438 0.0324170515 0.0143243245 0.0325240000 387166928 0 402718720 -0.1957984567 -0.0778201446 1.0431805849 1077 43.0400000000 0.0154200923 0.0133164988 0.0324170515 0.0143246770 0.0329210000 387169028 0 402718720 -0.1955138147 -0.0795434192 1.0464628935 1078 43.0800000000 0.0153610492 0.0133183954 0.0324170515 0.0143194738 0.0324570000 387171560 0 402718720 -0.1950602829 -0.0771999508 1.0478582382 1079 43.1200000000 0.0159855299 0.0133208673 0.0324170515 0.0143133610 0.0327390000 387173784 0 402718720 -0.1952486336 -0.0743845627 1.0503160954 1080 43.1600000000 0.0161410552 0.0133234786 0.0324170515 0.0143098774 0.0329390000 387176160 0 402718720 -0.1947817206 -0.0737216994 1.0537352562 1081 43.2000000000 0.0172784124 0.0133271372 0.0324170515 0.0143064331 0.0420480000 387178260 0 402718720 -0.1949658692 -0.0723344237 1.0564575195 1082 43.2400000000 0.0174952019 0.0133309893 0.0324170515 0.0143028348 0.0324960000 387180820 0 402718720 -0.1951871067 -0.0709996000 1.0583541393 1083 43.2800000000 0.0165209919 0.0133339349 0.0324170515 0.0143057442 0.0445530000 387183104 0 402718720 -0.1944550872 -0.0715053678 1.0601849556 1084 43.3200000000 0.0159841441 0.0133363797 0.0324170515 0.0143032110 0.0319880000 387185420 0 402718720 -0.1943962127 -0.0718378574 1.0618188381 1085 43.3600000000 0.0169312656 0.0133396930 0.0324170515 0.0142968674 0.0315020000 387187428 0 402718720 -0.1940037012 -0.0690114498 1.0630120039 1086 43.4000000000 0.0158674773 0.0133420206 0.0324170515 0.0142944784 0.0311170000 387189728 0 402718720 -0.1936396658 -0.0692015514 1.0640208721 1087 43.4400000000 0.0154060479 0.0133439194 0.0324170515 0.0142917100 0.0321530000 387192104 0 402718720 -0.1934589446 -0.0691623464 1.0659273863 1088 43.4800000000 0.0163346957 0.0133466683 0.0324170515 0.0142855248 0.0464050000 387194528 0 402718720 -0.1930933744 -0.0658711269 1.0674026012 1089 43.5200000000 0.0156244924 0.0133487600 0.0324170515 0.0142835094 0.0335150000 387196536 0 402718720 -0.1929757744 -0.0659968704 1.0689276457 1090 43.5600000000 0.0159585141 0.0133511542 0.0324170515 0.0142797357 0.0321010000 387199096 0 402718720 -0.1925017089 -0.0652914196 1.0712126493 1091 43.6000000000 0.0153668895 0.0133530018 0.0324170515 0.0142752715 0.0314490000 387201288 0 402718720 -0.1913759708 -0.0645289794 1.0730816126 1092 43.6400000000 0.0152900210 0.0133547757 0.0324170515 0.0142724392 0.0314730000 387203680 0 402718720 -0.1905302107 -0.0639889240 1.0752607584 1093 43.6800000000 0.0149965268 0.0133562777 0.0324170515 0.0142720781 0.0323400000 387205688 0 402718720 -0.1902458221 -0.0642376021 1.0784090757 1094 43.7200000000 0.0154231619 0.0133581670 0.0324170515 0.0142665670 0.0417870000 387207972 0 402718720 -0.1893478930 -0.0616849437 1.0796540976 1095 43.7600000000 0.0144349309 0.0133591503 0.0324170515 0.0142732650 0.0322670000 387210348 0 402718720 -0.1888232827 -0.0642484277 1.0836803913 1096 43.8000000000 0.0166139770 0.0133621201 0.0324170515 0.0142675395 0.0330870000 387212756 0 402718720 -0.1882961392 -0.0600059815 1.0870671272 1097 43.8400000000 0.0167279448 0.0133651883 0.0324170515 0.0142624383 0.0325970000 387214856 0 402718720 -0.1880150586 -0.0595339239 1.0888028145 1098 43.8800000000 0.0162077118 0.0133677771 0.0324170515 0.0142578376 0.0325770000 387217448 0 402718720 -0.1871504933 -0.0592846721 1.0913780928 1099 43.9200000000 0.0165833868 0.0133707030 0.0324170515 0.0142518661 0.0328830000 387219272 0 402718720 -0.1864646077 -0.0571935922 1.0933260918 1100 43.9600000000 0.0155109176 0.0133726487 0.0324170515 0.0142516668 0.0322280000 387221832 0 402718720 -0.1857755184 -0.0577597842 1.0953919888 1101 44.0000000000 0.0171506032 0.0133760801 0.0324170515 0.0142461378 0.0328420000 387224072 0 402718720 -0.1851290017 -0.0544781014 1.0973091125 1102 44.0400000000 0.0165516511 0.0133789617 0.0324170515 0.0142488971 0.0321430000 387225836 0 402718720 -0.1848731935 -0.0545847975 1.0993628502 1103 44.0800000000 0.0151842926 0.0133805985 0.0324170515 0.0142524486 0.0318180000 387228504 0 402718720 -0.1840527654 -0.0557658151 1.1018118858 1104 44.1200000000 0.0160295721 0.0133829979 0.0324170515 0.0142463390 0.0309540000 387230512 0 402718720 -0.1830891073 -0.0539183617 1.1050627232 1105 44.1600000000 0.0159454662 0.0133853169 0.0324170515 0.0142416006 0.0428330000 387232692 0 402718720 -0.1826709807 -0.0529591590 1.1074854136 1106 44.2000000000 0.0157141313 0.0133874225 0.0324170515 0.0142364124 0.0298370000 387235360 0 402718720 -0.1819855571 -0.0507166982 1.1075956821 1107 44.2400000000 0.0158366915 0.0133896350 0.0324170515 0.0142317909 0.0303610000 387237768 0 402718720 -0.1820290238 -0.0516023487 1.1109157801 1108 44.2800000000 0.0155571541 0.0133915913 0.0324170515 0.0142257089 0.0312550000 387240364 0 402718720 -0.1805276573 -0.0507588759 1.1137809753 1109 44.3200000000 0.0165022705 0.0133943962 0.0324170515 0.0142193481 0.0310990000 387241836 0 402718720 -0.1802064329 -0.0487751067 1.1163654327 1110 44.3600000000 0.0149556054 0.0133958027 0.0324170515 0.0142171866 0.0303090000 387243036 0 402718720 -0.1791835576 -0.0503194965 1.1175302267 1111 44.4000000000 0.0164156351 0.0133985208 0.0324170515 0.0142117038 0.0290660000 387245016 0 402718720 -0.1790279150 -0.0473651402 1.1190851927 1112 44.4400000000 0.0148026766 0.0133997836 0.0324170515 0.0142092035 0.0289580000 387247492 0 402718720 -0.1782869101 -0.0484988689 1.1203572750 1113 44.4800000000 0.0149155334 0.0134011454 0.0324170515 0.0142040828 0.0299210000 387249688 0 402718720 -0.1773006171 -0.0482620560 1.1231921911 1114 44.5200000000 0.0158080719 0.0134033060 0.0324170515 0.0141982121 0.0281630000 387250228 0 402718720 -0.1764159799 -0.0455393195 1.1260831356 1115 44.5600000000 0.0146913715 0.0134044613 0.0324170515 0.0141949923 0.0414200000 387253144 0 402718720 -0.1757113039 -0.0475016981 1.1277034283 1116 44.6000000000 0.0155572714 0.0134063903 0.0324170515 0.0141891558 0.0278350000 387254664 0 402718720 -0.1752152741 -0.0450174399 1.1296919584 1117 44.6400000000 0.0160512645 0.0134087581 0.0324170515 0.0141838190 0.0393000000 387257796 0 402718720 -0.1738162786 -0.0414340459 1.1313146353 1118 44.6800000000 0.0152503010 0.0134104053 0.0324170515 0.0141806061 0.0414350000 387259504 0 402718720 -0.1734482795 -0.0432428457 1.1343166828 1119 44.7200000000 0.0157221220 0.0134124712 0.0324170515 0.0141774295 0.0275550000 387261628 0 402718720 -0.1722812057 -0.0405857824 1.1372821331 1120 44.7600000000 0.0144659840 0.0134134118 0.0324170515 0.0141745145 0.0270290000 387262260 0 402718720 -0.1718751639 -0.0440656357 1.1408562660 1121 44.8000000000 0.0162319802 0.0134159262 0.0324170515 0.0141688019 0.0273170000 387262264 0 402718720 -0.1709462851 -0.0410326011 1.1439030170 1122 44.8400000000 0.0151771596 0.0134174959 0.0324170515 0.0141646652 0.0380450000 387261992 0 402718720 -0.1700468361 -0.0412260704 1.1458330154 1123 44.8800000000 0.0156614929 0.0134194941 0.0324170515 0.0141585878 0.0259890000 387265188 0 402718720 -0.1692219079 -0.0402803756 1.1493575573 1124 44.9200000000 0.0144991959 0.0134204547 0.0324170515 0.0141591115 0.0256410000 387264980 0 402718720 -0.1676987708 -0.0431306288 1.1530358791 1125 44.9600000000 0.0137724616 0.0134207676 0.0324170515 0.0141543971 0.0255840000 387265968 0 402718720 -0.1667595208 -0.0427129678 1.1545636654 1126 45.0000000000 0.0147640649 0.0134219606 0.0324170515 0.0141483894 0.0242130000 387265792 0 402718720 -0.1661532223 -0.0395083092 1.1573632956 1127 45.0400000000 0.0152151920 0.0134235517 0.0324170515 0.0141422847 0.0242490000 387266708 0 402718720 -0.1644119620 -0.0374407806 1.1608963013 1128 45.0800000000 0.0145701328 0.0134245682 0.0324170515 0.0141372493 0.0232090000 387266540 0 402718720 -0.1631678045 -0.0373608805 1.1635394096 1129 45.1200000000 0.0160511471 0.0134268947 0.0324170515 0.0141336252 0.0354770000 387268144 0 402718720 -0.1623928845 -0.0326820686 1.1663683653 1130 45.1600000000 0.0141310673 0.0134275178 0.0324170515 0.0141389411 0.0229900000 387265896 0 402718720 -0.1607129276 -0.0357872136 1.1699721813 1131 45.2000000000 0.0151312901 0.0134290242 0.0324170515 0.0141330951 0.0219010000 387270532 0 402718720 -0.1594785750 -0.0328911208 1.1733263731 1132 45.2400000000 0.0145763978 0.0134300378 0.0324170515 0.0141284195 0.0218400000 387269096 0 402718720 -0.1587617993 -0.0318239778 1.1743930578 1133 45.2800000000 0.0138024632 0.0134303665 0.0324170515 0.0141313583 0.0218230000 387270768 0 402718720 -0.1573865712 -0.0322972201 1.1769217253 1134 45.3200000000 0.0145008685 0.0134313105 0.0324170515 0.0141253844 0.0209070000 387269316 0 402718720 -0.1563500464 -0.0291022547 1.1790536642 1135 45.3600000000 0.0133717582 0.0134312581 0.0324170515 0.0141203389 0.0203640000 387265904 0 402718720 -0.1542671621 -0.0290501006 1.1826555729 1136 45.4000000000 0.0151714645 0.0134327899 0.0324170515 0.0141143164 0.0248900000 387797767 0 402718720 -0.1532820165 -0.0244508162 1.1857998371 1137 45.4400000000 0.0166177042 0.0134355911 0.0324170515 0.0141219309 0.0644390000 390972228 0 402718720 -0.1533282697 -0.0190077014 1.1866977215 1138 45.4800000000 0.0156042548 0.0134374968 0.0324170515 0.0141238297 0.0467700000 393070824 0 402718720 -0.1513454914 -0.0218520463 1.1872979403 1139 45.5200000000 0.0130598191 0.0134371652 0.0324170515 0.0141481288 0.0391600000 392756261 0 402718720 -0.1482153535 -0.0227006748 1.1894938946 1140 45.5600000000 0.0128786173 0.0134366752 0.0324170515 0.0141523695 0.0226460000 387768412 0 402718720 -0.1473511755 -0.0246124417 1.1909890175 1141 45.6000000000 0.0134462463 0.0134366836 0.0324170515 0.0141558500 0.0218410000 387771052 0 402718720 -0.1437803209 -0.0193747953 1.1948512793 1142 45.6400000000 0.0145853478 0.0134376895 0.0324170515 0.0141505648 0.0204050000 387770104 0 402718720 -0.1416285932 -0.0115451962 1.1952862740 1143 45.6800000000 0.0136219338 0.0134378507 0.0324170515 0.0141582700 0.0388390000 388037171 0 402718720 -0.1395086646 -0.0059314519 1.1969469786 1144 45.7200000000 0.0143772401 0.0134386718 0.0324170515 0.0141773263 0.0514840000 390192060 0 402718720 -0.1376990974 -0.0085206404 1.2000116110 1145 45.7600000000 0.0133765461 0.0134386175 0.0324170515 0.0141727446 0.0257510000 390863908 0 402718720 -0.1360839903 -0.0093561038 1.2015361786 1146 45.8000000000 0.0179566070 0.0134425599 0.0324170515 0.0141876524 0.0257190000 390547569 0 402718720 -0.1417888999 -0.0015741736 1.1941459179 1147 45.8400000000 0.0228807032 0.0134507885 0.0324170515 0.0142007653 0.0422950000 388215116 0 402718720 -0.1425115168 -0.0020933524 1.1922044754 1148 45.8800000000 0.0322498865 0.0134671640 0.0324170515 0.0142260009 0.0420330000 392129887 0 402718720 -0.1443386972 -0.0082550347 1.1914628744 1149 45.9200000000 0.0406806096 0.0134908485 0.0406806096 0.0142735894 0.0434380000 388495308 0 402718720 -0.1413159668 -0.0136039630 1.1966215372 1150 45.9600000000 0.0384569317 0.0135125581 0.0406806096 0.0142780829 0.0348020000 392643447 0 402718720 -0.1343366206 -0.0129494667 1.2044482231 1151 46.0000000000 0.0432322063 0.0135383788 0.0432322063 0.0142962254 0.0444760000 392230869 0 402718720 -0.1323120892 -0.0157467052 1.2067615986 1152 46.0400000000 0.0418471880 0.0135629524 0.0432322063 0.0142907497 0.0453060000 388721348 0 402718720 -0.1315985620 -0.0147955790 1.2070908546 1153 46.0800000000 0.0511669442 0.0135955665 0.0511669442 0.0143103329 0.0463850000 394669391 0 402718720 -0.1330233812 -0.0189321488 1.2101444006 1154 46.1200000000 0.0564245395 0.0136326800 0.0564245395 0.0143204135 0.0572880000 394476551 0 402718720 -0.1308914721 -0.0234571993 1.2143567801 1155 46.1600000000 0.0558752976 0.0136692537 0.0564245395 0.0143152229 0.0494260000 389157743 0 402718720 -0.1291318834 -0.0225837529 1.2156888247 1156 46.2000000000 0.0570992790 0.0137068229 0.0570992790 0.0143099827 0.0519800000 389096944 0 402718720 -0.1285226941 -0.0227851421 1.2176468372 1157 46.2400000000 0.0567242913 0.0137440031 0.0570992790 0.0143043662 0.0495730000 389132896 0 402718720 -0.1273702979 -0.0215121806 1.2186646461 1158 46.2800000000 0.0582703166 0.0137824541 0.0582703166 0.0143025534 0.0568160000 398252771 0 402718720 -0.1251682341 -0.0222406536 1.2228670120 1159 46.3200000000 0.0585338362 0.0138210662 0.0585338362 0.0143000320 0.0750410000 398027951 0 402718720 -0.1233970523 -0.0200991631 1.2242027521 1160 46.3600000000 0.0566808805 0.0138580143 0.0585338362 0.0142951392 0.0488130000 389270972 0 402718720 -0.1187558174 -0.0172060877 1.2278634310 1161 46.4000000000 0.0496329069 0.0138888282 0.0585338362 0.0142924372 0.0592780000 396999803 0 402718720 -0.1198900342 -0.0100944489 1.2296075821 1162 46.4400000000 0.0463141911 0.0139167330 0.0585338362 0.0142877459 0.0682870000 392311129 0 402718720 -0.1173488498 -0.0075113475 1.2288415432 1163 46.4800000000 0.0475007258 0.0139456100 0.0585338362 0.0142857483 0.0566770000 389534356 0 402718720 -0.1187877655 -0.0069065690 1.2304911613 1164 46.5200000000 0.0397426710 0.0139677724 0.0585338362 0.0142826747 0.0541440000 389641172 0 402718720 -0.1135619879 0.0003207773 1.2322976589 1165 46.5600000000 0.0436899215 0.0139932850 0.0585338362 0.0142820268 0.0583730000 399999900 0 402718720 -0.1128947735 -0.0026133209 1.2333359718 1166 46.6000000000 0.0384383276 0.0140142499 0.0585338362 0.0142770522 0.0597400000 404275179 0 402718720 -0.1094402671 0.0038756579 1.2337617874 1167 46.6400000000 0.0394804105 0.0140360718 0.0585338362 0.0142712469 0.1002800000 405818589 0 402718720 -0.1079524159 -0.0011074990 1.2354016304 1168 46.6800000000 0.0400204323 0.0140583187 0.0585338362 0.0142656882 0.0759370000 389836937 0 402718720 -0.1071344018 -0.0026991963 1.2366731167 1169 46.7200000000 0.0387721248 0.0140794596 0.0585338362 0.0142632210 0.0622240000 389855444 0 402718720 -0.1039735079 -0.0025835484 1.2387008667 1170 46.7600000000 0.0402717963 0.0141018462 0.0585338362 0.0142610981 0.0637250000 389860632 0 402718720 -0.1035104394 -0.0042096674 1.2402148247 1171 46.8000000000 0.0391189791 0.0141232102 0.0585338362 0.0142574204 0.0615260000 397357300 0 402718720 -0.1011438966 -0.0061398447 1.2401435375 1172 46.8400000000 0.0399796478 0.0141452720 0.0585338362 0.0142550497 0.0360690000 406649089 0 402718720 -0.1000831723 -0.0091250837 1.2422358990 1173 46.8800000000 0.0380514897 0.0141656524 0.0585338362 0.0142504214 0.0397630000 405294837 0 402718720 -0.0973459482 -0.0074073523 1.2426037788 1174 46.9200000000 0.0365438871 0.0141847139 0.0585338362 0.0142473135 0.0546330000 405581129 0 402718720 -0.0943799019 -0.0079751313 1.2449853420 1175 46.9600000000 0.0353629515 0.0142027379 0.0585338362 0.0142446514 0.0256820000 405058372 0 402718720 -0.0932429433 -0.0076879710 1.2437269688 1176 47.0000000000 0.0173647050 0.0142054267 0.0585338362 0.0142841949 0.0917270000 405133107 0 402718720 -0.0834124684 0.0099566728 1.2491943836 1177 47.0400000000 0.0173119958 0.0142080661 0.0585338362 0.0142812874 0.0696820000 389879192 0 402718720 -0.0820649862 0.0101968646 1.2506197691 1178 47.0800000000 0.0169069041 0.0142103571 0.0585338362 0.0142784312 0.0239930000 389882380 0 402718720 -0.0811368227 0.0120430291 1.2507565022 1179 47.1200000000 0.0169282854 0.0142126624 0.0585338362 0.0142733038 0.0276540000 390275888 0 402718720 -0.0798503160 0.0121697336 1.2512859106 1180 47.1600000000 0.0165739935 0.0142146635 0.0585338362 0.0142696419 0.0774570000 390331456 0 402718720 -0.0774376392 0.0113156885 1.2525964975 1181 47.2000000000 0.0168408044 0.0142168872 0.0585338362 0.0142643590 0.0768590000 390333872 0 402718720 -0.0771000385 0.0133087486 1.2533013821 1182 47.2400000000 0.0167901665 0.0142190642 0.0585338362 0.0142619598 0.0736380000 398986988 0 402718720 -0.0751996040 0.0123927891 1.2546319962 1183 47.2800000000 0.0170099102 0.0142214234 0.0585338362 0.0142568637 0.0654090000 403599126 0 402718720 -0.0735135674 0.0112389922 1.2563495636 1184 47.3200000000 0.0172422696 0.0142239747 0.0585338362 0.0142511159 0.0315250000 408270429 0 402718720 -0.0725224614 0.0104668885 1.2571488619 1185 47.3600000000 0.0165498406 0.0142259375 0.0585338362 0.0142456563 0.0744920000 406955275 0 402718720 -0.0710515380 0.0101497769 1.2577667236 1186 47.4000000000 0.0169701744 0.0142282514 0.0585338362 0.0142449517 0.0314860000 406743303 0 402718720 -0.0693843365 0.0099181235 1.2582302094 1187 47.4400000000 0.0152255530 0.0142290915 0.0585338362 0.0142415206 0.0994440000 406600807 0 402718720 -0.0678084493 0.0160306841 1.2600661516 1188 47.4800000000 0.0139911892 0.0142288913 0.0585338362 0.0142356318 0.0810330000 390313744 0 402718720 -0.0660027862 0.0162020028 1.2605684996 1189 47.5200000000 0.0138688786 0.0142285885 0.0585338362 0.0142299377 0.0257980000 390323668 0 402718720 -0.0648595095 0.0124040693 1.2615357637 1190 47.5600000000 0.0144227231 0.0142287516 0.0585338362 0.0142261844 0.0254780000 390321812 0 402718720 -0.0647364259 0.0118264258 1.2613821030 1191 47.6000000000 0.0157286450 0.0142300110 0.0585338362 0.0142209702 0.0260750000 390324456 0 402718720 -0.0657186508 0.0121384412 1.2621507645 1192 47.6400000000 0.0132411178 0.0142291814 0.0585338362 0.0142158417 0.0256890000 390328580 0 402718720 -0.0622090697 0.0122105777 1.2631399632 1193 47.6800000000 0.0147593394 0.0142296258 0.0585338362 0.0142121265 0.0249120000 390327844 0 402718720 -0.0642908216 0.0129278004 1.2627141476 1194 47.7200000000 0.0148848733 0.0142301746 0.0585338362 0.0142080191 0.0250650000 390328548 0 402718720 -0.0641207099 0.0134439319 1.2635762691 1195 47.7600000000 0.0157153178 0.0142314174 0.0585338362 0.0142065105 0.0248840000 390330544 0 402718720 -0.0639105439 0.0120175779 1.2652465105 1196 47.8000000000 0.0134410039 0.0142307565 0.0585338362 0.0142034845 0.0250820000 390334504 0 402718720 -0.0615093708 0.0147206485 1.2656866312 1197 47.8400000000 0.0128793940 0.0142296275 0.0585338362 0.0141994151 0.0244350000 390334308 0 402718720 -0.0610969067 0.0133398324 1.2658562660 1198 47.8800000000 0.0132881179 0.0142288416 0.0585338362 0.0141942779 0.0351400000 390338448 0 402718720 -0.0607601404 0.0110501647 1.2673859596 1199 47.9200000000 0.0146749979 0.0142292137 0.0585338362 0.0141933669 0.0243960000 390338436 0 402718720 -0.0621408820 0.0109174252 1.2680244446 1200 47.9600000000 0.0140916696 0.0142290991 0.0585338362 0.0141960591 0.0244340000 390344088 0 402718720 -0.0617017150 0.0110573769 1.2683061361 1201 48.0000000000 0.0146939391 0.0142294862 0.0585338362 0.0141936279 0.0243750000 390343292 0 402718720 -0.0614846945 0.0116714537 1.2693754435 1202 48.0400000000 0.0134541551 0.0142288411 0.0585338362 0.0141912168 0.0242140000 390346100 0 402718720 -0.0590343475 0.0098572075 1.2699675560 1203 48.0800000000 0.0150080724 0.0142294889 0.0585338362 0.0141870841 0.0246950000 390348432 0 402718720 -0.0608546734 0.0103518069 1.2702517509 1204 48.1200000000 0.0155047551 0.0142305481 0.0585338362 0.0141837475 0.0240950000 390351024 0 402718720 -0.0600320101 0.0109550506 1.2719082832 1205 48.1600000000 0.0149108404 0.0142311126 0.0585338362 0.0141797222 0.0266770000 390656832 0 402718720 -0.0591370463 0.0103703588 1.2718192339 1206 48.2000000000 0.0148292882 0.0142316086 0.0585338362 0.0141767218 0.0750360000 390705640 0 402718720 -0.0583463311 0.0099330842 1.2723296881 1207 48.2400000000 0.0150708891 0.0142323040 0.0585338362 0.0141746756 0.0704150000 398071524 0 402718720 -0.0577116609 0.0094290972 1.2725874186 1208 48.2800000000 0.0147360684 0.0142327210 0.0585338362 0.0141720665 0.0638420000 403205104 0 402718720 -0.0570496917 0.0084364265 1.2718296051 1209 48.3200000000 0.0153222028 0.0142336221 0.0585338362 0.0141713833 0.0300060000 407314037 0 402718720 -0.0559992790 0.0096426606 1.2727198601 1210 48.3600000000 0.0150241097 0.0142342754 0.0585338362 0.0141701153 0.0716880000 405433185 0 402718720 -0.0542044640 0.0097564161 1.2729611397 1211 48.4000000000 0.0134792877 0.0142336520 0.0585338362 0.0141694766 0.0310390000 406798569 0 402718720 -0.0501454473 0.0082803071 1.2737606764 1212 48.4400000000 0.0137633188 0.0142332639 0.0585338362 0.0141728928 0.1059690000 405294059 0 402718720 -0.0468345284 0.0077559948 1.2750240564 1213 48.4800000000 0.0129190516 0.0142321805 0.0585338362 0.0141677538 0.0614700000 390728080 0 402718720 -0.0443015397 0.0077019632 1.2744233608 1214 48.5200000000 0.0144829415 0.0142323870 0.0585338362 0.0141639472 0.0261700000 390732068 0 402718720 -0.0436937213 0.0078409612 1.2750470638 1215 48.5600000000 0.0135825425 0.0142318522 0.0585338362 0.0141634265 0.0265750000 390734936 0 402718720 -0.0418609679 0.0066370964 1.2739856243 1216 48.6000000000 0.0126680601 0.0142305662 0.0585338362 0.0141651051 0.0262150000 390738572 0 402718720 -0.0372261703 0.0059152246 1.2758029699 1217 48.6400000000 0.0134672485 0.0142299390 0.0585338362 0.0141653437 0.0278810000 390740856 0 402718720 -0.0363481045 0.0070626736 1.2753146887 1218 48.6800000000 0.0128381653 0.0142287963 0.0585338362 0.0141686235 0.0269520000 390743264 0 402718720 -0.0331040323 0.0071239769 1.2760103941 1219 48.7200000000 0.0125580179 0.0142274257 0.0585338362 0.0141672185 0.0266530000 390748176 0 402718720 -0.0311504304 0.0059834421 1.2756485939 1220 48.7600000000 0.0116985738 0.0142253528 0.0585338362 0.0141637114 0.0277770000 390746964 0 402718720 -0.0270447433 0.0068876743 1.2769309282 1221 48.8000000000 0.0126163671 0.0142240351 0.0585338362 0.0141709881 0.0264890000 390749172 0 402718720 -0.0247727633 0.0035443902 1.2790035009 1222 48.8400000000 0.0102855675 0.0142208121 0.0585338362 0.0141727078 0.0373600000 390753804 0 402718720 -0.0180341005 0.0055843294 1.2801271677 1223 48.8800000000 0.0109162088 0.0142181101 0.0585338362 0.0141769731 0.0264190000 390757776 0 402718720 -0.0172255933 0.0055337846 1.2804620266 1224 48.9200000000 0.0121115493 0.0142163890 0.0585338362 0.0141785389 0.0258230000 390760260 0 402718720 -0.0154551566 0.0058814287 1.2818043232 1225 48.9600000000 0.0122499568 0.0142147838 0.0585338362 0.0141811742 0.0376870000 390762116 0 402718720 -0.0129834712 0.0050574243 1.2823965549 1226 49.0000000000 0.0125773270 0.0142134482 0.0585338362 0.0141808631 0.0267260000 390764692 0 402718720 -0.0106875896 0.0077823400 1.2826930285 1227 49.0400000000 0.0126150046 0.0142121454 0.0585338362 0.0141837012 0.0271140000 390766180 0 402718720 -0.0069573522 0.0061742067 1.2847692966 1228 49.0800000000 0.0107337208 0.0142093128 0.0585338362 0.0141819964 0.0265820000 390766684 0 402718720 -0.0023080111 0.0076113045 1.2850151062 1229 49.1200000000 0.0118916221 0.0142074270 0.0585338362 0.0141801157 0.0272750000 390771484 0 402718720 0.0007206798 0.0086849034 1.2873082161 1230 49.1600000000 0.0129152751 0.0142063765 0.0585338362 0.0141822661 0.0268690000 390772972 0 402718720 0.0013998151 0.0062315166 1.2876890898 1231 49.2000000000 0.0113867763 0.0142040860 0.0585338362 0.0141783594 0.0272340000 390778616 0 402718720 0.0046280622 0.0106023252 1.2861802578 1232 49.2400000000 0.0120205646 0.0142023136 0.0585338362 0.0141765640 0.0263610000 390777972 0 402718720 0.0072900355 0.0098190308 1.2880904675 1233 49.2800000000 0.0122627681 0.0142007406 0.0585338362 0.0141726944 0.0388280000 390782772 0 402718720 0.0088702738 0.0086439550 1.2879260778 1234 49.3200000000 0.0117193786 0.0141987298 0.0585338362 0.0141681803 0.0262110000 390784244 0 402718720 0.0124440193 0.0088849962 1.2893702984 1235 49.3600000000 0.0115536842 0.0141965880 0.0585338362 0.0141674421 0.0272920000 390790268 0 402718720 0.0148573220 0.0100757182 1.2895088196 1236 49.4000000000 0.0105682975 0.0141936525 0.0585338362 0.0141793880 0.0277110000 390794684 0 402718720 0.0180232823 0.0095430911 1.2900769711 1237 49.4400000000 0.0120792752 0.0141919433 0.0585338362 0.0141856547 0.0271710000 390797448 0 402718720 0.0198460221 0.0108281970 1.2915978432 1238 49.4800000000 0.0128932185 0.0141908942 0.0585338362 0.0141918345 0.0265120000 390795100 0 402718720 0.0210788846 0.0141169727 1.2919168472 1239 49.5200000000 0.0114327157 0.0141886681 0.0585338362 0.0142042779 0.0381660000 390800744 0 402718720 0.0250724852 0.0153575838 1.2908586264 1240 49.5600000000 0.0112971356 0.0141863362 0.0585338362 0.0142145087 0.0337090000 391405144 0 402718720 0.0286063254 0.0134828389 1.2920874357 1241 49.6000000000 0.0121122589 0.0141846649 0.0585338362 0.0142149668 0.1108640000 391482664 0 402718720 0.0309149027 0.0133641958 1.2923130989 1242 49.6400000000 0.0119271390 0.0141828472 0.0585338362 0.0142125484 0.1024070000 391490156 0 402718720 0.0334054232 0.0135988891 1.2925257683 1243 49.6800000000 0.0129329944 0.0141818417 0.0585338362 0.0142076192 0.0964720000 391756108 0 402718720 0.0354869962 0.0129473805 1.2934473753 1244 49.7200000000 0.0121216886 0.0141801857 0.0585338362 0.0142019305 0.0992170000 403288568 0 402718720 0.0384879410 0.0153090954 1.2922635078 1245 49.7600000000 0.0127149820 0.0141790088 0.0585338362 0.0141962776 0.0930570000 410040628 0 402718720 0.0405092835 0.0174748003 1.2922029495 1246 49.8000000000 0.0122516146 0.0141774619 0.0585338362 0.0141914084 0.0382880000 414700649 0 402718720 0.0431824476 0.0161463916 1.2919021845 1247 49.8400000000 0.0120090060 0.0141757230 0.0585338362 0.0141871619 0.0850640000 412990699 0 402718720 0.0445205718 0.0189429522 1.2911654711 1248 49.8800000000 0.0126513503 0.0141745015 0.0585338362 0.0141827828 0.0497740000 414356849 0 402718720 0.0466993898 0.0200512707 1.2916646004 1249 49.9200000000 0.0124853877 0.0141731492 0.0585338362 0.0141776548 0.0348810000 412460873 0 402718720 0.0494873077 0.0160767734 1.2918373346 1250 49.9600000000 0.0121876756 0.0141715608 0.0585338362 0.0141721734 0.0385550000 412586521 0 402718720 0.0520524383 0.0186069906 1.2914183140 1251 50.0000000000 0.0133794043 0.0141709276 0.0585338362 0.0141666516 0.1314160000 412483747 0 402718720 0.0530598611 0.0189769268 1.2912775278 1252 50.0400000000 0.0120572476 0.0141692393 0.0585338362 0.0141621086 0.0946000000 391492332 0 402718720 0.0554572046 0.0219584405 1.2903919220 1253 50.0800000000 0.0123021314 0.0141677492 0.0585338362 0.0141566360 0.0322170000 391514640 0 402718720 0.0562303811 0.0234165788 1.2897846699 1254 50.1200000000 0.0113058584 0.0141654670 0.0585338362 0.0141513770 0.0319880000 391514092 0 402718720 0.0595208853 0.0243722200 1.2892501354 1255 50.1600000000 0.0113877356 0.0141632537 0.0585338362 0.0141460781 0.0316680000 391519460 0 402718720 0.0607031286 0.0249742270 1.2889387608 1256 50.2000000000 0.0127222268 0.0141621064 0.0585338362 0.0141416657 0.0317460000 391517588 0 402718720 0.0613235831 0.0248671174 1.2890236378 1257 50.2400000000 0.0113937249 0.0141599040 0.0585338362 0.0141363757 0.0310880000 391519184 0 402718720 0.0645977110 0.0244965553 1.2884061337 1258 50.2800000000 0.0119044967 0.0141581111 0.0585338362 0.0141310215 0.0341940000 391527680 0 402718720 0.0649331659 0.0279166698 1.2877416611 1259 50.3200000000 0.0130610419 0.0141572397 0.0585338362 0.0141260067 0.0314060000 391527804 0 402718720 0.0677429736 0.0266696513 1.2878923416 1260 50.3600000000 0.0114273652 0.0141550732 0.0585338362 0.0141221076 0.0328050000 391526836 0 402718720 0.0708104223 0.0298973620 1.2853600979 1261 50.4000000000 0.0118817352 0.0141532704 0.0585338362 0.0141172331 0.0433600000 391530472 0 402718720 0.0747605711 0.0301598907 1.2858575583 1262 50.4400000000 0.0110349627 0.0141507994 0.0585338362 0.0141116554 0.0327900000 391530424 0 402718720 0.0766866207 0.0331478715 1.2835656404 1263 50.4800000000 0.0106001738 0.0141479882 0.0585338362 0.0141060839 0.0309750000 391533372 0 402718720 0.0807736069 0.0350982845 1.2829498053 1264 50.5200000000 0.0105324360 0.0141451278 0.0585338362 0.0141008963 0.0432850000 391539140 0 402718720 0.0831116959 0.0376994312 1.2826743126 1265 50.5600000000 0.0111763999 0.0141427810 0.0585338362 0.0140969233 0.0329390000 391540260 0 402718720 0.0836695805 0.0357874334 1.2817078829 1266 50.6000000000 0.0108283730 0.0141401629 0.0585338362 0.0140921678 0.0325750000 391543112 0 402718720 0.0880214125 0.0366295576 1.2817542553 1267 50.6400000000 0.0104796588 0.0141372738 0.0585338362 0.0140868634 0.0306040000 391547176 0 402718720 0.0897922665 0.0412797630 1.2797503471 1268 50.6800000000 0.0116062826 0.0141352778 0.0585338362 0.0140830168 0.0323470000 391548296 0 402718720 0.0939232633 0.0412129760 1.2793817520 1269 50.7200000000 0.0103713358 0.0141323117 0.0585338362 0.0140784760 0.0369790000 392117616 0 402718720 0.0961172283 0.0409694910 1.2775565386 1270 50.7600000000 0.0102497702 0.0141292546 0.0585338362 0.0140734027 0.1108100000 392185756 0 402718720 0.0973478705 0.0420218706 1.2763507366 1271 50.8000000000 0.0121353120 0.0141276858 0.0585338362 0.0140690785 0.1019430000 392187392 0 402718720 0.0947644785 0.0412393212 1.2751859426 1272 50.8400000000 0.0087849824 0.0141234856 0.0585338362 0.0140654926 0.0976400000 392485644 0 402718720 0.0987624675 0.0448442698 1.2723468542 1273 50.8800000000 0.0104843220 0.0141206268 0.0585338362 0.0140603964 0.1009150000 403541976 0 402718720 0.0984334201 0.0448061228 1.2726080418 1274 50.9200000000 0.0096495934 0.0141171174 0.0585338362 0.0140557246 0.1016640000 410531664 0 402718720 0.1008372009 0.0487862229 1.2708930969 1275 50.9600000000 0.0107768979 0.0141144976 0.0585338362 0.0140503082 0.0386530000 413654721 0 402718720 0.1024971306 0.0498000681 1.2711844444 1276 51.0000000000 0.0110970503 0.0141121328 0.0585338362 0.0140450899 0.1061190000 411955835 0 402718720 0.1038530469 0.0482700169 1.2703732252 1277 51.0400000000 0.0109638767 0.0141096675 0.0585338362 0.0140403034 0.0392510000 413587589 0 402718720 0.1077136546 0.0496974885 1.2706813812 1278 51.0800000000 0.0107986573 0.0141070767 0.0585338362 0.0140349276 0.0408340000 411921876 0 402718720 0.1107177362 0.0474537313 1.2710984945 1279 51.1200000000 0.0123055233 0.0141056681 0.0585338362 0.0140297369 0.1432940000 411851171 0 402718720 0.1100794449 0.0463087857 1.2709182501 1280 51.1600000000 0.0113966586 0.0141035517 0.0585338362 0.0140256468 0.1038560000 392159772 0 402718720 0.1109319925 0.0460968614 1.2704585791 1281 51.2000000000 0.0122185769 0.0141020802 0.0585338362 0.0140213350 0.0346490000 392179988 0 402718720 0.1105315238 0.0484225154 1.2688918114 1282 51.2400000000 0.0123777706 0.0141007352 0.0585338362 0.0140159121 0.0331910000 392178932 0 402718720 0.1102717370 0.0494948924 1.2680088282 1283 51.2800000000 0.0121552451 0.0140992189 0.0585338362 0.0140106886 0.0325080000 392182676 0 402718720 0.1110966206 0.0471355915 1.2670737505 1284 51.3200000000 0.0136346631 0.0140988571 0.0585338362 0.0140052692 0.0330970000 392186972 0 402718720 0.1106296405 0.0491397083 1.2680935860 1285 51.3600000000 0.0122657781 0.0140974305 0.0585338362 0.0140000004 0.0329630000 392189320 0 402718720 0.1131789014 0.0511279404 1.2670248747 1286 51.4000000000 0.0128726102 0.0140964781 0.0585338362 0.0139946926 0.0600480000 392194048 0 402718720 0.1134123206 0.0532762408 1.2668631077 1287 51.4400000000 0.0116880545 0.0140946068 0.0585338362 0.0139899960 0.0323840000 392192008 0 402718720 0.1166221872 0.0505634248 1.2674552202 1288 51.4800000000 0.0104581974 0.0140917835 0.0585338362 0.0139860019 0.0558950000 392195152 0 402718720 0.1180112436 0.0495722592 1.2668834925 1289 51.5200000000 0.0116446540 0.0140898850 0.0585338362 0.0139811721 0.0330130000 392200980 0 402718720 0.1181620806 0.0514655113 1.2673397064 1290 51.5600000000 0.0122094145 0.0140884273 0.0585338362 0.0139797058 0.0327550000 392204892 0 402718720 0.1203882098 0.0546469092 1.2672940493 1291 51.6000000000 0.0115904100 0.0140864923 0.0585338362 0.0139817453 0.0350370000 392206028 0 402718720 0.1201369390 0.0528649390 1.2662403584 1292 51.6400000000 0.0106918383 0.0140838649 0.0585338362 0.0139818805 0.0326730000 392208208 0 402718720 0.1226630509 0.0553142130 1.2651804686 1293 51.6800000000 0.0099680843 0.0140806818 0.0585338362 0.0139821026 0.0322020000 392208532 0 402718720 0.1245938689 0.0528443456 1.2649911642 1294 51.7200000000 0.0105175627 0.0140779282 0.0585338362 0.0139774334 0.0349350000 392214820 0 402718720 0.1241396666 0.0539326668 1.2644854784 1295 51.7600000000 0.0086246468 0.0140737172 0.0585338362 0.0139770232 0.0350510000 392216736 0 402718720 0.1268288791 0.0534685850 1.2633849382 1296 51.8000000000 0.0104638049 0.0140709317 0.0585338362 0.0139891050 0.0507710000 392888216 0 402718720 0.1258303672 0.0560379922 1.2634164095 1297 51.8400000000 0.0108121838 0.0140684192 0.0585338362 0.0139889223 0.1149100000 392861580 0 402718720 0.1260601282 0.0546821058 1.2638078928 1298 51.8800000000 0.0099810520 0.0140652702 0.0585338362 0.0139871801 0.1005720000 392860100 0 402718720 0.1276256293 0.0580520928 1.2620503902 1299 51.9200000000 0.0106749618 0.0140626603 0.0585338362 0.0139891536 0.0997630000 392860932 0 402718720 0.1283060014 0.0599794686 1.2619570494 1300 51.9600000000 0.0109062511 0.0140602323 0.0585338362 0.0139948298 0.1043140000 392943053 0 402718720 0.1294315159 0.0604232550 1.2620711327 1301 52.0000000000 0.0111538582 0.0140579983 0.0585338362 0.0139974404 0.1099230000 407491377 0 402718720 0.1306760013 0.0623370707 1.2615644932 1302 52.0400000000 0.0117438491 0.0140562209 0.0585338362 0.0140052455 0.0453290000 411569977 0 402718720 0.1313775331 0.0652770698 1.2603756189 1303 52.0800000000 0.0113726156 0.0140541614 0.0585338362 0.0140096219 0.1063620000 411013341 0 402718720 0.1346227825 0.0691131949 1.2592602968 1304 52.1200000000 0.0124207502 0.0140529088 0.0585338362 0.0140114540 0.0406810000 411732061 0 402718720 0.1329506338 0.0735262036 1.2571696043 1305 52.1600000000 0.0132267782 0.0140522757 0.0585338362 0.0140116010 0.0425100000 410983468 0 402718720 0.1341964304 0.0771067739 1.2561365366 1306 52.2000000000 0.0110536311 0.0140499797 0.0585338362 0.0140105819 0.1201880000 402819341 0 402718720 0.1363767684 0.0780383945 1.2534677982 1307 52.2400000000 0.0114686238 0.0140480046 0.0585338362 0.0140054427 0.0648030000 392873884 0 402718720 0.1373982131 0.0800078809 1.2523014545 1308 52.2800000000 0.0101668313 0.0140450374 0.0585338362 0.0140003635 0.0353090000 392876540 0 402718720 0.1399106681 0.0814902186 1.2500805855 1309 52.3200000000 0.0105419122 0.0140423612 0.0585338362 0.0139958170 0.0359710000 392880160 0 402718720 0.1402829736 0.0854772329 1.2487862110 1310 52.3600000000 0.0119117759 0.0140407348 0.0585338362 0.0139952200 0.0354210000 392883996 0 402718720 0.1392253339 0.0884588361 1.2479668856 1311 52.4000000000 0.0114446413 0.0140387546 0.0585338362 0.0139962829 0.0360080000 392887540 0 402718720 0.1403186172 0.0926926732 1.2468987703 1312 52.4400000000 0.0100167533 0.0140356890 0.0585338362 0.0139946731 0.0368140000 392890024 0 402718720 0.1430367231 0.0971815884 1.2439465523 1313 52.4800000000 0.0120394472 0.0140341686 0.0585338362 0.0139912773 0.0332680000 392889748 0 402718720 0.1420719177 0.1028239280 1.2431892157 1314 52.5200000000 0.0129655255 0.0140333554 0.0585338362 0.0139885137 0.0334660000 392893000 0 402718720 0.1422260106 0.1103686243 1.2402845621 1315 52.5600000000 0.0117823901 0.0140316436 0.0585338362 0.0139835050 0.0342200000 392894888 0 402718720 0.1446320117 0.1154747754 1.2367649078 1316 52.6000000000 0.0110540735 0.0140293810 0.0585338362 0.0139784320 0.0346680000 392898816 0 402718720 0.1459855586 0.1222570539 1.2339501381 1317 52.6400000000 0.0110818595 0.0140271430 0.0585338362 0.0139749201 0.0342330000 392899888 0 402718720 0.1483869106 0.1296423525 1.2319110632 1318 52.6800000000 0.0100535732 0.0140241281 0.0585338362 0.0139714120 0.0345800000 392904336 0 402718720 0.1497053802 0.1375729740 1.2281247377 1319 52.7200000000 0.0105893593 0.0140215240 0.0585338362 0.0139672658 0.0366700000 392907724 0 402718720 0.1509143561 0.1456436664 1.2261605263 1320 52.7600000000 0.0114966333 0.0140196113 0.0585338362 0.0139634575 0.0338160000 392911176 0 402718720 0.1501607597 0.1553382277 1.2236831188 1321 52.8000000000 0.0137525620 0.0140194091 0.0585338362 0.0139620641 0.0379790000 392913828 0 402718720 0.1502925754 0.1676882505 1.2217977047 1322 52.8400000000 0.0125082880 0.0140182660 0.0585338362 0.0139571208 0.0371670000 392916296 0 402718720 0.1522683650 0.1787965000 1.2173384428 1323 52.8800000000 0.0119010620 0.0140166657 0.0585338362 0.0139538222 0.0367320000 392918736 0 402718720 0.1532312334 0.1843474358 1.2140914202 1324 52.9200000000 0.0118051264 0.0140149954 0.0585338362 0.0139534841 0.0342170000 392921204 0 402718720 0.1546071172 0.1963133216 1.2103586197 1325 52.9600000000 0.0105058616 0.0140123470 0.0585338362 0.0139515764 0.0361250000 392919964 0 402718720 0.1569860280 0.2063147724 1.2066949606 1326 53.0000000000 0.0108572785 0.0140099676 0.0585338362 0.0139496187 0.0337980000 392924364 0 402718720 0.1581318080 0.2179975808 1.2036750317 1327 53.0400000000 0.0094808135 0.0140065545 0.0585338362 0.0139466942 0.0341450000 392929148 0 402718720 0.1610352844 0.2280370146 1.2000479698 1328 53.0800000000 0.0113819269 0.0140045781 0.0585338362 0.0139473558 0.0346070000 392930328 0 402718720 0.1595570743 0.2388869226 1.1970589161 1329 53.1200000000 0.0112196710 0.0140024826 0.0585338362 0.0139428662 0.0367220000 392934300 0 402718720 0.1606679857 0.2504966557 1.1948469877 1330 53.1600000000 0.0106057758 0.0139999287 0.0585338362 0.0139379679 0.0368770000 392935220 0 402718720 0.1605953872 0.2569089830 1.1913673878 1331 53.2000000000 0.0114069069 0.0139979806 0.0585338362 0.0139410715 0.0351610000 392936600 0 402718720 0.1612952948 0.2683125436 1.1885712147 1332 53.2400000000 0.0107017867 0.0139955059 0.0585338362 0.0139395408 0.0349150000 392941124 0 402718720 0.1636838764 0.2843007445 1.1847302914 1333 53.2800000000 0.0106621981 0.0139930053 0.0585338362 0.0139346704 0.0350170000 392941736 0 402718720 0.1629782468 0.2931458652 1.1809340715 1334 53.3200000000 0.0101412283 0.0139901179 0.0585338362 0.0139307995 0.0365060000 392943376 0 402718720 0.1640491486 0.3046056628 1.1780349016 1335 53.3600000000 0.0088655269 0.0139862793 0.0585338362 0.0139268829 0.0367110000 392946120 0 402718720 0.1641909480 0.3143587410 1.1736490726 1336 53.4000000000 0.0100308191 0.0139833186 0.0585338362 0.0139218178 0.0368120000 392948496 0 402718720 0.1634160429 0.3258421421 1.1720666885 1337 53.4400000000 0.0121590169 0.0139819542 0.0585338362 0.0139167598 0.0347360000 392951240 0 402718720 0.1609637737 0.3333514631 1.1709566116 1338 53.4800000000 0.0111732110 0.0139798549 0.0585338362 0.0139123788 0.0344960000 392952300 0 402718720 0.1619335711 0.3442184031 1.1675151587 1339 53.5200000000 0.0115229478 0.0139780201 0.0585338362 0.0139165702 0.0599120000 392954600 0 402718720 0.1630004346 0.3568415344 1.1651276350 1340 53.5600000000 0.0105525441 0.0139754637 0.0585338362 0.0139274510 0.0364390000 392955904 0 402718720 0.1610915214 0.3748035729 1.1593708992 1341 53.6000000000 0.0109681599 0.0139732211 0.0585338362 0.0139263989 0.0364470000 392957728 0 402718720 0.1605778337 0.3881531656 1.1570827961 1342 53.6400000000 0.0079144193 0.0139687064 0.0585338362 0.0139218894 0.0343830000 392958556 0 402718720 0.1627785712 0.3964795172 1.1537203789 1343 53.6800000000 0.0107014598 0.0139662736 0.0585338362 0.0139176199 0.0363980000 392961392 0 402718720 0.1589247286 0.4039057195 1.1553894281 1344 53.7200000000 0.0122981248 0.0139650324 0.0585338362 0.0139126205 0.0366470000 392964980 0 402718720 0.1567406952 0.4102402627 1.1555643082 1345 53.7600000000 0.0095736617 0.0139617675 0.0585338362 0.0139099982 0.0459540000 392966528 0 402718720 0.1581216902 0.4172254801 1.1531299353 1346 53.8000000000 0.0084245335 0.0139576536 0.0585338362 0.0139082181 0.0360730000 392970700 0 402718720 0.1578319073 0.4233090878 1.1528024673 1347 53.8400000000 0.0093433121 0.0139542280 0.0585338362 0.0139474737 0.0361540000 392972892 0 402718720 0.1554929465 0.4392544031 1.1522935629 1348 53.8800000000 0.0097912615 0.0139511397 0.0585338362 0.0139465130 0.0466240000 392977340 0 402718720 0.1559436917 0.4479715526 1.1529070139 1349 53.9200000000 0.0105348807 0.0139486073 0.0585338362 0.0139419895 0.0370350000 392978796 0 402718720 0.1551769376 0.4543279409 1.1548562050 1350 53.9600000000 0.0089049181 0.0139448712 0.0585338362 0.0139369719 0.0345750000 392978504 0 402718720 0.1556463391 0.4587367773 1.1534811258 1351 54.0000000000 0.0084339799 0.0139407921 0.0585338362 0.0139319830 0.0563520000 392981448 0 402718720 0.1549632251 0.4611368179 1.1537978649 1352 54.0400000000 0.0100379651 0.0139379054 0.0585338362 0.0139271720 0.0340060000 392983380 0 402718720 0.1524075419 0.4664948583 1.1545711756 1353 54.0800000000 0.0120983524 0.0139365458 0.0585338362 0.0139311750 0.0339960000 392987228 0 402718720 0.1501914263 0.4696659446 1.1569415331 1354 54.1200000000 0.0117069799 0.0139348991 0.0585338362 0.0139312915 0.0359220000 392989160 0 402718720 0.1499316096 0.4743716717 1.1576036215 1355 54.1600000000 0.0091309519 0.0139313538 0.0585338362 0.0139337138 0.0338790000 392989728 0 402718720 0.1494560838 0.4757786989 1.1555240154 1356 54.2000000000 0.0106351580 0.0139289230 0.0585338362 0.0139354998 0.0340390000 392992304 0 402718720 0.1487700343 0.4826613963 1.1578742266 1357 54.2400000000 0.0089619430 0.0139252627 0.0585338362 0.0139372094 0.0456110000 392996628 0 402718720 0.1465885043 0.4849097729 1.1559979916 1358 54.2800000000 0.0104297576 0.0139226887 0.0585338362 0.0139336124 0.0359410000 392997212 0 402718720 0.1434462965 0.4864779711 1.1582063437 1359 54.3200000000 0.0088971118 0.0139189907 0.0585338362 0.0139292751 0.0353600000 393000280 0 402718720 0.1417131126 0.4898796678 1.1576071978 1360 54.3600000000 0.0070401975 0.0139139327 0.0585338362 0.0139306346 0.0342160000 393001920 0 402718720 0.1413458288 0.4932315350 1.1567978859 1361 54.4000000000 0.0130085051 0.0139132675 0.0585338362 0.0139261313 0.0356790000 393005648 0 402718720 0.1350879371 0.4982532263 1.1627922058 1362 54.4400000000 0.0127557125 0.0139124176 0.0585338362 0.0139222460 0.0334000000 393007380 0 402718720 0.1311073303 0.5012216568 1.1628770828 1363 54.4800000000 0.0107109994 0.0139100688 0.0585338362 0.0139178073 0.0348700000 393010584 0 402718720 0.1292747855 0.5044888854 1.1622591019 1364 54.5200000000 0.0132316407 0.0139095714 0.0585338362 0.0139133163 0.0458230000 393012132 0 402718720 0.1245710552 0.5074262023 1.1665025949 1365 54.5600000000 0.0090943361 0.0139060438 0.0585338362 0.0139096551 0.0348270000 393016380 0 402718720 0.1223827004 0.5061042309 1.1658008099 1366 54.6000000000 0.0112745101 0.0139041173 0.0585338362 0.0139097001 0.0341760000 393017652 0 402718720 0.1162123084 0.5077657104 1.1691006422 1367 54.6400000000 0.0110930828 0.0139020609 0.0585338362 0.0139192737 0.0351430000 393020152 0 402718720 0.1134119630 0.5125484467 1.1710598469 1368 54.6800000000 0.0116809988 0.0139004374 0.0585338362 0.0139177362 0.0348570000 393022252 0 402718720 0.1085281372 0.5169491172 1.1738876104 1369 54.7200000000 0.0103041502 0.0138978104 0.0585338362 0.0139207622 0.0344880000 393024844 0 402718720 0.1039908528 0.5205096602 1.1751819849 1370 54.7600000000 0.0095457938 0.0138946338 0.0585338362 0.0139237308 0.0570190000 393029552 0 402718720 0.1001133621 0.5256530046 1.1767084599 1371 54.8000000000 0.0095721558 0.0138914810 0.0585338362 0.0139206294 0.0350130000 393030380 0 402718720 0.0943120122 0.5290410519 1.1787924767 1372 54.8400000000 0.0117729232 0.0138899368 0.0585338362 0.0139199123 0.0343910000 393032404 0 402718720 0.0887275636 0.5374886990 1.1830540895 1373 54.8800000000 0.0100956019 0.0138871733 0.0585338362 0.0139183674 0.0335300000 393034888 0 402718720 0.0842092931 0.5441660881 1.1842745543 1374 54.9200000000 0.0117568448 0.0138856228 0.0585338362 0.0139189602 0.0335960000 393037896 0 402718720 0.0760023892 0.5457718968 1.1895596981 1375 54.9600000000 0.0137934554 0.0138855558 0.0585338362 0.0139194532 0.0336050000 393038952 0 402718720 0.0682397783 0.5523719788 1.1946412325 1376 55.0000000000 0.0099611329 0.0138827038 0.0585338362 0.0139256688 0.0465590000 393042556 0 402718720 0.0617552400 0.5561030507 1.1937109232 1377 55.0400000000 0.0109304450 0.0138805598 0.0585338362 0.0139302838 0.0411400000 393720080 0 402718720 0.0532057583 0.5605371594 1.1975749731 1378 55.0800000000 0.0116756856 0.0138789597 0.0585338362 0.0139358761 0.1268820000 393712888 0 402718720 0.0437262952 0.5650175214 1.2013791800 1379 55.1200000000 0.0103634521 0.0138764104 0.0585338362 0.0139404627 0.1161220000 393713492 0 402718720 0.0361551046 0.5688292384 1.2034872770 1380 55.1600000000 0.0094656069 0.0138732142 0.0585338362 0.0139525285 0.1101330000 394023612 0 402718720 0.0289076865 0.5732136965 1.2050387859 1381 55.2000000000 0.0090688132 0.0138697352 0.0585338362 0.0139637790 0.1155190000 406088984 0 402718720 0.0212856829 0.5779501200 1.2080616951 1382 55.2400000000 0.0117139723 0.0138681754 0.0585338362 0.0139741498 0.0464260000 412070453 0 402718720 0.0114947557 0.5821246505 1.2144985199 1383 55.2800000000 0.0109121501 0.0138660380 0.0585338362 0.0139911984 0.1043740000 411352375 0 402718720 0.0046253502 0.5873894691 1.2156102657 1384 55.3200000000 0.0112631945 0.0138641573 0.0585338362 0.0140020358 0.0450750000 411021004 0 402718720 -0.0021897554 0.5936009288 1.2190909386 1385 55.3600000000 0.0129128350 0.0138634704 0.0585338362 0.0140166309 0.1389530000 410949151 0 402718720 -0.0110526979 0.5972980261 1.2231184244 1386 55.4000000000 0.0104887765 0.0138610356 0.0585338362 0.0140305439 0.0895830000 393722488 0 402718720 -0.0175147057 0.5996145606 1.2227007151 1387 55.4400000000 0.0124110579 0.0138599902 0.0585338362 0.0140423688 0.0368260000 393724928 0 402718720 -0.0251124203 0.6037674546 1.2279998064 1388 55.4800000000 0.0118414424 0.0138585359 0.0585338362 0.0140538585 0.0374440000 393726740 0 402718720 -0.0329146087 0.6045233011 1.2308042049 1389 55.5200000000 0.0132973120 0.0138581318 0.0585338362 0.0140616838 0.0378020000 393729408 0 402718720 -0.0387994945 0.6089082956 1.2350623608 1390 55.5600000000 0.0109557118 0.0138560438 0.0585338362 0.0140779488 0.0382360000 393731816 0 402718720 -0.0447687209 0.6094248295 1.2357578278 1391 55.6000000000 0.0125172120 0.0138550813 0.0585338362 0.0140838093 0.0375280000 393734100 0 402718720 -0.0484934151 0.6151896715 1.2404894829 1392 55.6400000000 0.0114577366 0.0138533590 0.0585338362 0.0140860061 0.0369900000 393735036 0 402718720 -0.0544936061 0.6163756847 1.2426067591 1393 55.6800000000 0.0118145142 0.0138518954 0.0585338362 0.0140850312 0.0416880000 394276764 0 402718720 -0.0593574047 0.6198356748 1.2457349300 1394 55.7200000000 0.0107183270 0.0138496475 0.0585338362 0.0140849807 0.1232870000 394362812 0 402718720 -0.0643940568 0.6193181872 1.2467839718 1395 55.7600000000 0.0121356770 0.0138484189 0.0585338362 0.0140868581 0.1138500000 394363972 0 402718720 -0.0665600896 0.6232229471 1.2525625229 1396 55.8000000000 0.0107779065 0.0138462193 0.0585338362 0.0140974102 0.1121150000 394665924 0 402718720 -0.0676026344 0.6267257929 1.2539041042 1397 55.8400000000 0.0101709049 0.0138435885 0.0585338362 0.0141102833 0.1114990000 407994568 0 402718720 -0.0715093315 0.6271901131 1.2580361366 1398 55.8800000000 0.0100993905 0.0138409102 0.0585338362 0.0141162825 0.0690360000 412672041 0 402718720 -0.0751943588 0.6293959022 1.2629760504 1399 55.9200000000 0.0102419946 0.0138383377 0.0585338362 0.0141266887 0.0858950000 412299205 0 402718720 -0.0776959062 0.6320611238 1.2675073147 1400 55.9600000000 0.0110773453 0.0138363656 0.0585338362 0.0141301433 0.0532600000 412496105 0 402718720 -0.0767064989 0.6395140290 1.2739725113 1401 56.0000000000 0.0115284920 0.0138347183 0.0585338362 0.0141289100 0.0456480000 412195084 0 402718720 -0.0791282356 0.6422017217 1.2799019814 1402 56.0400000000 0.0140364030 0.0138348621 0.0585338362 0.0141288976 0.1456960000 412124267 0 402718720 -0.0822667181 0.6467618942 1.2879385948 1403 56.0800000000 0.0121747982 0.0138336789 0.0585338362 0.0141324425 0.0970810000 394379080 0 402718720 -0.0840022266 0.6487643719 1.2906460762 1404 56.1200000000 0.0131929778 0.0138332226 0.0585338362 0.0141411411 0.0363390000 394379156 0 402718720 -0.0856777132 0.6522952318 1.2966967821 1405 56.1600000000 0.0123907737 0.0138321959 0.0585338362 0.0141459969 0.0354960000 394381672 0 402718720 -0.0856896341 0.6565428972 1.3016450405 1406 56.2000000000 0.0124407709 0.0138312063 0.0585338362 0.0142030515 0.0482690000 394383868 0 402718720 -0.0878624022 0.6639996171 1.3151898384 1407 56.2400000000 0.0120344795 0.0138299293 0.0585338362 0.0142070124 0.0348340000 394386536 0 402718720 -0.0860916972 0.6730077267 1.3218621016 1408 56.2800000000 0.0123854382 0.0138289034 0.0585338362 0.0142083413 0.0398270000 394870060 0 402718720 -0.0897324085 0.6753488183 1.3299901485 1409 56.3200000000 0.0129008368 0.0138282447 0.0585338362 0.0142141471 0.1229400000 394975268 0 402718720 -0.0902212858 0.6789284945 1.3388787508 1410 56.3600000000 0.0114611406 0.0138265659 0.0585338362 0.0142390292 0.1154620000 394976972 0 402718720 -0.0914921463 0.6834096909 1.3433099985 1411 56.4000000000 0.0122837098 0.0138254725 0.0585338362 0.0142507091 0.1106940000 395277052 0 402718720 -0.0923694670 0.6898665428 1.3524541855 1412 56.4400000000 0.0115948115 0.0138238927 0.0585338362 0.0142590270 0.1155940000 407712460 0 402718720 -0.0938662589 0.6929404736 1.3609889746 1413 56.4800000000 0.0121688172 0.0138227214 0.0585338362 0.0142710105 0.0795220000 413347145 0 402718720 -0.0940850377 0.6996709108 1.3702354431 1414 56.5200000000 0.0119895237 0.0138214249 0.0585338362 0.0142775798 0.0791370000 412669095 0 402718720 -0.0954315364 0.7062219977 1.3762711287 1415 56.5600000000 0.0106884930 0.0138192108 0.0585338362 0.0142779442 0.0544400000 412924145 0 402718720 -0.0956147611 0.7117253542 1.3827183247 1416 56.6000000000 0.0114759430 0.0138175560 0.0585338362 0.0142827723 0.0439570000 412617360 0 402718720 -0.0954609811 0.7187708616 1.3901226521 1417 56.6400000000 0.0137308920 0.0138174948 0.0585338362 0.0142871580 0.1381080000 412545255 0 402718720 -0.0940176249 0.7272460461 1.3987474442 1418 56.6800000000 0.0131240543 0.0138170058 0.0585338362 0.0142934279 0.0960690000 395508772 0 402718720 -0.0985910892 0.7292828560 1.4028475285 1419 56.7200000000 0.0125169512 0.0138160896 0.0585338362 0.0143011028 0.1280320000 395620412 0 402718720 -0.0988257229 0.7344268560 1.4087135792 1420 56.7600000000 0.0116138384 0.0138145387 0.0585338362 0.0143098346 0.1194240000 395621696 0 402718720 -0.0996448398 0.7385725379 1.4134202003 1421 56.8000000000 0.0128373532 0.0138138510 0.0585338362 0.0143141508 0.1073660000 395924828 0 402718720 -0.1008218527 0.7436976433 1.4207763672 1422 56.8400000000 0.0126428111 0.0138130275 0.0585338362 0.0143219407 0.1088730000 405848476 0 402718720 -0.1021502316 0.7475869656 1.4255683422 1423 56.8800000000 0.0122196442 0.0138119078 0.0585338362 0.0143270876 0.0982150000 412961496 0 402718720 -0.1001928747 0.7532725334 1.4307479858 1424 56.9200000000 0.0116432160 0.0138103848 0.0585338362 0.0143282969 0.0401300000 414007261 0 402718720 -0.1001277566 0.7596451044 1.4352583885 1425 56.9600000000 0.0122069931 0.0138092596 0.0585338362 0.0143256643 0.1019110000 413571083 0 402718720 -0.1053602397 0.7593162060 1.4415436983 1426 57.0000000000 0.0131469555 0.0138087952 0.0585338362 0.0143287678 0.0394080000 413204800 0 402718720 -0.1039515436 0.7655803561 1.4487096071 1427 57.0400000000 0.0133274291 0.0138084579 0.0585338362 0.0143304255 0.1423440000 413174011 0 402718720 -0.1055437326 0.7705793381 1.4541789293 1428 57.0800000000 0.0139597356 0.0138085638 0.0585338362 0.0143324003 0.1065600000 396165064 0 402718720 -0.1064493954 0.7750309706 1.4623819590 1429 57.1200000000 0.0131469155 0.0138081008 0.0585338362 0.0143332645 0.1197910000 396176188 0 402718720 -0.1101799011 0.7768812180 1.4657689333 1430 57.1600000000 0.0132457949 0.0138077076 0.0585338362 0.0143347391 0.1079690000 396178024 0 402718720 -0.1088862717 0.7832205296 1.4740772247 1431 57.2000000000 0.0122957025 0.0138066510 0.0585338362 0.0143376864 0.1045990000 396458816 0 402718720 -0.1117433310 0.7857756019 1.4802187681 1432 57.2400000000 0.0137036331 0.0138065790 0.0585338362 0.0143419285 0.1011670000 407969556 0 402718720 -0.1121909916 0.7911908031 1.4887961149 1433 57.2800000000 0.0130551234 0.0138060546 0.0585338362 0.0143439806 0.0744320000 413219569 0 402718720 -0.1139611304 0.7953860760 1.4945418835 1434 57.3200000000 0.0130248154 0.0138055098 0.0585338362 0.0143512572 0.0664310000 413009376 0 402718720 -0.1152930856 0.7997296453 1.5023950338 1435 57.3600000000 0.0126803517 0.0138047258 0.0585338362 0.0143616703 0.0585810000 412795465 0 402718720 -0.1183351576 0.8033072352 1.5084840059 1436 57.4000000000 0.0123612294 0.0138037205 0.0585338362 0.0143739351 0.0420040000 412616152 0 402718720 -0.1204362363 0.8062071204 1.5151995420 1437 57.4400000000 0.0146751506 0.0138043270 0.0585338362 0.0143906615 0.1259480000 412535519 0 402718720 -0.1207628697 0.8141211867 1.5270276070 1438 57.4800000000 0.0141462954 0.0138045648 0.0585338362 0.0144047908 0.0897690000 396592416 0 402718720 -0.1239551008 0.8186135888 1.5325115919 1439 57.5200000000 0.0137104858 0.0138044994 0.0585338362 0.0144164953 0.1171230000 396723868 0 402718720 -0.1245175898 0.8264466524 1.5383964777 1440 57.5600000000 0.0143046584 0.0138048467 0.0585338362 0.0144222580 0.1110950000 396725264 0 402718720 -0.1251635402 0.8323665857 1.5465757847 1441 57.6000000000 0.0132543575 0.0138044647 0.0585338362 0.0144289981 0.1002810000 397020744 0 402718720 -0.1274667531 0.8359390497 1.5517266989 1442 57.6400000000 0.0137272840 0.0138044112 0.0585338362 0.0144324151 0.0542780000 412047860 0 402718720 -0.1268673539 0.8422486782 1.5577338934 1443 57.6800000000 0.0136653343 0.0138043148 0.0585338362 0.0144313859 0.0917800000 412071487 0 402718720 -0.1288283914 0.8454108834 1.5636972189 1444 57.7200000000 0.0139183002 0.0138043937 0.0585338362 0.0144288549 0.0386620000 412116345 0 402718720 -0.1293685287 0.8495794535 1.5697704554 1445 57.7600000000 0.0126088746 0.0138035664 0.0585338362 0.0144320338 0.1314430000 411758989 0 402718720 -0.1280829310 0.8533205986 1.5760921240 1446 57.8000000000 0.0131693222 0.0138031278 0.0585338362 0.0144310035 0.0781980000 397265424 0 402718720 -0.1262561381 0.8597997427 1.5822829008 1447 57.8400000000 0.0128095830 0.0138024411 0.0585338362 0.0144267329 0.1090330000 397288284 0 402718720 -0.1282280236 0.8612286448 1.5869109631 1448 57.8800000000 0.0133353472 0.0138021186 0.0585338362 0.0144253351 0.1035870000 397279360 0 402718720 -0.1293351352 0.8624659181 1.5931589603 1449 57.9200000000 0.0135713518 0.0138019593 0.0585338362 0.0144246967 0.0976350000 397594992 0 402718720 -0.1303068548 0.8666359186 1.5971484184 1450 57.9600000000 0.0134271914 0.0138017008 0.0585338362 0.0144232964 0.0974610000 408852900 0 402718720 -0.1313483417 0.8692151308 1.6009639502 1451 58.0000000000 0.0132157337 0.0138012970 0.0585338362 0.0144204346 0.0556970000 412222632 0 402718720 -0.1318244636 0.8714534640 1.6054883003 1452 58.0400000000 0.0119973319 0.0138000546 0.0585338362 0.0144182055 0.0852290000 412212139 0 402718720 -0.1299407482 0.8747915030 1.6105844975 1453 58.0800000000 0.0128274728 0.0137993852 0.0585338362 0.0144151091 0.0357840000 412201525 0 402718720 -0.1290896088 0.8786603808 1.6175318956 1454 58.1200000000 0.0139368633 0.0137994798 0.0585338362 0.0144107797 0.1211410000 412036179 0 402718720 -0.1278204620 0.8807159662 1.6240391731 1455 58.1600000000 0.0137957567 0.0137994772 0.0585338362 0.0144075790 0.0704600000 397691348 0 402718720 -0.1254736334 0.8825429082 1.6289389133 1456 58.2000000000 0.0138131790 0.0137994866 0.0585338362 0.0144046467 0.1043240000 397818584 0 402718720 -0.1243104115 0.8829594851 1.6317411661 1457 58.2400000000 0.0130233550 0.0137989540 0.0585338362 0.0144030289 0.0990080000 397817108 0 402718720 -0.1227505654 0.8850432634 1.6338926554 1458 58.2800000000 0.0135900956 0.0137988107 0.0585338362 0.0143998742 0.0932470000 409307628 0 402718720 -0.1187048703 0.8888452649 1.6393017769 1459 58.3200000000 0.0143494746 0.0137991881 0.0585338362 0.0143954312 0.0539860000 412701024 0 402718720 -0.1175832599 0.8898141980 1.6425144672 1460 58.3600000000 0.0134714497 0.0137989637 0.0585338362 0.0143905849 0.0747280000 412629415 0 402718720 -0.1149425954 0.8886457682 1.6438665390 1461 58.4000000000 0.0137970718 0.0137989624 0.0585338362 0.0143856914 0.0375060000 412778305 0 402718720 -0.1121052131 0.8916198611 1.6468919516 1462 58.4400000000 0.0137361968 0.0137989194 0.0585338362 0.0143809614 0.1095780000 412518215 0 402718720 -0.1062688380 0.8929030895 1.6527408361 1463 58.4800000000 0.0144954249 0.0137993955 0.0585338362 0.0143764895 0.0325920000 398158176 0 402718720 -0.1011464819 0.8937093019 1.6571469307 1464 58.5200000000 0.0147559522 0.0138000489 0.0585338362 0.0143719261 0.0856880000 398291836 0 402718720 -0.0948931724 0.8959010243 1.6620287895 1465 58.5600000000 0.0149504608 0.0138008342 0.0585338362 0.0143672907 0.0840500000 398288444 0 402718720 -0.0925391912 0.8957351446 1.6636080742 1466 58.6000000000 0.0141800661 0.0138010928 0.0585338362 0.0143625277 0.0791510000 404112220 0 402718720 -0.0870790258 0.8947908878 1.6662714481 1467 58.6400000000 0.0143489419 0.0138014663 0.0585338362 0.0143578455 0.0815030000 410671816 0 402718720 -0.0818498284 0.8982987404 1.6699354649 1468 58.6800000000 0.0140395146 0.0138016284 0.0585338362 0.0143534391 0.0388870000 413064852 0 402718720 -0.0756035745 0.9004688859 1.6732931137 1469 58.7200000000 0.0146809155 0.0138022270 0.0585338362 0.0143486180 0.0795020000 413122651 0 402718720 -0.0718002692 0.9021092057 1.6746255159 1470 58.7600000000 0.0145325437 0.0138027238 0.0585338362 0.0143451398 0.0315830000 413026745 0 402718720 -0.0653004646 0.9058600664 1.6765294075 1471 58.8000000000 0.0136924060 0.0138026488 0.0585338362 0.0143415176 0.1073090000 412886935 0 402718720 -0.0549124405 0.9108392000 1.6817774773 1472 58.8400000000 0.0146846417 0.0138032480 0.0585338362 0.0143377734 0.0760360000 398693704 0 402718720 -0.0535331070 0.9096736908 1.6834592819 1473 58.8800000000 0.0160809793 0.0138047943 0.0585338362 0.0143338640 0.0901470000 398792740 0 402718720 -0.0482951552 0.9127371907 1.6869201660 1474 58.9200000000 0.0150875505 0.0138056646 0.0585338362 0.0143310192 0.0809060000 399061080 0 402718720 -0.0396481454 0.9159168601 1.6888458729 1475 58.9600000000 0.0135147627 0.0138054674 0.0585338362 0.0143264746 0.0778420000 408756888 0 402718720 -0.0329048634 0.9188272357 1.6881241798 1476 59.0000000000 0.0123909386 0.0138045090 0.0585338362 0.0143217319 0.0579760000 412669364 0 402718720 -0.0271391124 0.9220772386 1.6875092983 1477 59.0400000000 0.0160932746 0.0138060586 0.0585338362 0.0143173927 0.0499790000 412847084 0 402718720 -0.0247908980 0.9259986281 1.6916515827 1478 59.0800000000 0.0143260788 0.0138064105 0.0585338362 0.0143129553 0.0581110000 412742125 0 402718720 -0.0207559764 0.9253100753 1.6902487278 1479 59.1200000000 0.0148811685 0.0138071371 0.0585338362 0.0143097213 0.1039510000 412578771 0 402718720 -0.0116870403 0.9318844676 1.6918138266 1480 59.1600000000 0.0143267997 0.0138074883 0.0585338362 0.0143058932 0.0621480000 398810512 0 402718720 -0.0061408579 0.9356365204 1.6927218437 1481 59.2000000000 0.0149460267 0.0138082570 0.0585338362 0.0143016144 0.0286370000 398814072 0 402718720 -0.0013087839 0.9386868477 1.6948242188 1482 59.2400000000 0.0151333790 0.0138091512 0.0585338362 0.0142971577 0.0278940000 398813752 0 402718720 0.0004242808 0.9413680434 1.6947048903 1483 59.2800000000 0.0133323753 0.0138088297 0.0585338362 0.0142926776 0.0289590000 398817784 0 402718720 0.0038802177 0.9447440505 1.6914255619 1484 59.3200000000 0.0144404136 0.0138092553 0.0585338362 0.0142885112 0.0285860000 398817468 0 402718720 0.0059343278 0.9450660348 1.6920492649 1485 59.3600000000 0.0137586826 0.0138092212 0.0585338362 0.0142848796 0.0318990000 399189368 0 402718720 0.0092556179 0.9471482635 1.6904569864 1486 59.4000000000 0.0146246841 0.0138097700 0.0585338362 0.0142803761 0.0946150000 399357780 0 402718720 0.0116157830 0.9486226439 1.6923755407 1487 59.4400000000 0.0153934574 0.0138108350 0.0585338362 0.0142757972 0.0811800000 399626288 0 402718720 0.0134129226 0.9501376152 1.6932808161 1488 59.4800000000 0.0142496778 0.0138111299 0.0585338362 0.0142712313 0.0840680000 409236384 0 402718720 0.0178175569 0.9540462494 1.6930966377 1489 59.5200000000 0.0161405541 0.0138126943 0.0585338362 0.0142668735 0.0658140000 413906516 0 402718720 0.0163707733 0.9534242749 1.6921221018 1490 59.5600000000 0.0160218626 0.0138141770 0.0585338362 0.0142640935 0.0382270000 414132272 0 402718720 0.0242584050 0.9598765969 1.6973915100 1491 59.6000000000 0.0175100248 0.0138166558 0.0585338362 0.0142604536 0.0452330000 414025673 0 402718720 0.0216011703 0.9602689147 1.6966298819 1492 59.6400000000 0.0132501703 0.0138162761 0.0585338362 0.0142571359 0.0319370000 413909680 0 402718720 0.0290144086 0.9656195045 1.6949706078 1493 59.6800000000 0.0145397522 0.0138167607 0.0585338362 0.0142525653 0.1059310000 414008375 0 402718720 0.0339049697 0.9710875154 1.6971411705 1494 59.7200000000 0.0160329062 0.0138182440 0.0585338362 0.0142479352 0.0627920000 399367048 0 402718720 0.0347920954 0.9707705379 1.7000495195 1495 59.7600000000 0.0137446709 0.0138181948 0.0585338362 0.0142446052 0.0281960000 399372052 0 402718720 0.0348372757 0.9708382487 1.6974329948 1496 59.8000000000 0.0157845579 0.0138195092 0.0585338362 0.0142422582 0.0284480000 399374416 0 402718720 0.0384541452 0.9743999243 1.7018690109 1497 59.8400000000 0.0152694071 0.0138204778 0.0585338362 0.0142397083 0.0279780000 399375288 0 402718720 0.0402911305 0.9766956568 1.7021687031 1498 59.8800000000 0.0162138920 0.0138220755 0.0585338362 0.0142352853 0.0281230000 399377176 0 402718720 0.0408367515 0.9816509485 1.7014193535 1499 59.9200000000 0.0135776959 0.0138219125 0.0585338362 0.0142305892 0.0285540000 399384360 0 402718720 0.0438654125 0.9815915823 1.7009967566 1500 59.9600000000 0.0121758040 0.0138208151 0.0585338362 0.0142260871 0.0276640000 399385500 0 402718720 0.0456089973 0.9825807214 1.6995334625 1501 60.0000000000 0.0149182267 0.0138215462 0.0585338362 0.0142223138 0.0278240000 399386068 0 402718720 0.0435066819 0.9795299768 1.7023782730 1502 60.0400000000 0.0123331128 0.0138205552 0.0585338362 0.0142182420 0.0282400000 399389172 0 402718720 0.0479830503 0.9841117263 1.7008719444 1503 60.0800000000 0.0150276748 0.0138213584 0.0585338362 0.0142139116 0.0279200000 399390140 0 402718720 0.0458731353 0.9844995737 1.7026815414 1504 60.1200000000 0.0164124817 0.0138230812 0.0585338362 0.0142101214 0.0282770000 399397688 0 402718720 0.0498264730 0.9862725735 1.7059748173 1505 60.1600000000 0.0168006327 0.0138250596 0.0585338362 0.0142059797 0.0281620000 399397124 0 402718720 0.0525936782 0.9884768724 1.7057303190 1506 60.2000000000 0.0150620947 0.0138258810 0.0585338362 0.0142018320 0.0283870000 399404240 0 402718720 0.0528217554 0.9871010780 1.7047169209 1507 60.2400000000 0.0163653158 0.0138275661 0.0585338362 0.0141981995 0.0276680000 399407232 0 402718720 0.0562269986 0.9878769517 1.7065702677 1508 60.2800000000 0.0137555543 0.0138275184 0.0585338362 0.0141938476 0.0278540000 399410688 0 402718720 0.0535842478 0.9881188273 1.7022132874 1509 60.3200000000 0.0180251636 0.0138303001 0.0585338362 0.0141911975 0.0276790000 399410336 0 402718720 0.0529386997 0.9831078053 1.7100577354 1510 60.3600000000 0.0146855237 0.0138308665 0.0585338362 0.0141868872 0.0275390000 399414376 0 402718720 0.0565997660 0.9853262901 1.7099882364 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:25:32 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0261510000 348350888 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0005108146 0.0002554073 0.0005108146 0.0015226468 0.0333380000 356492446 0 402718720 -0.0000594354 0.0004854501 -0.0003531830 3 0.0800000000 0.0020868427 0.0008658858 0.0020868427 0.0020907556 0.0460710000 356420407 0 402718720 -0.0001238014 -0.0043509970 -0.0009977624 4 0.1200000000 0.0031927279 0.0014475963 0.0031927279 0.0018769666 0.0304710000 356393322 0 402718720 -0.0017915192 -0.0041233529 -0.0006297382 5 0.1600000000 0.0006433089 0.0012867388 0.0031927279 0.0023354404 0.0317300000 356396422 0 402718720 -0.0006180372 -0.0010620592 -0.0001557913 6 0.2000000000 0.0008177909 0.0012085808 0.0031927279 0.0022805666 0.0321710000 356403826 0 402718720 -0.0004609817 -0.0028494056 -0.0005944842 7 0.2400000000 0.0031854103 0.0014909850 0.0031927279 0.0026223361 0.0324660000 356407502 0 402718720 -0.0020630020 -0.0049188170 -0.0011535360 8 0.2800000000 0.0012357500 0.0014590807 0.0031927279 0.0030324827 0.0318860000 356411878 0 402718720 -0.0012280287 -0.0005993557 -0.0000063740 9 0.3200000000 0.0008064040 0.0013865610 0.0031927279 0.0028786623 0.0309740000 356414386 0 402718720 0.0006615896 -0.0011242060 0.0000468528 10 0.3600000000 0.0011472784 0.0013626328 0.0031927279 0.0028246310 0.0320350000 356418922 0 402718720 -0.0009571188 -0.0022241727 -0.0010146159 11 0.4000000000 0.0023276450 0.0014503611 0.0031927279 0.0028066719 0.0310680000 356421094 0 402718720 0.0008272096 -0.0034014767 -0.0004539205 12 0.4400000000 0.0005571764 0.0013759291 0.0031927279 0.0027380653 0.0439310000 356424542 0 402718720 -0.0004179089 -0.0008191437 -0.0002935351 13 0.4800000000 0.0008432680 0.0013349552 0.0031927279 0.0027106273 0.0319310000 356426202 0 402718720 0.0003847232 -0.0001694088 0.0008670795 14 0.5200000000 0.0006660781 0.0012871782 0.0031927279 0.0026630288 0.0323310000 356428746 0 402718720 0.0006972097 -0.0000210414 0.0001424057 15 0.5600000000 0.0018968262 0.0013278214 0.0031927279 0.0026710538 0.0304130000 356431766 0 402718720 0.0000783210 -0.0015974896 0.0010363291 16 0.6000000000 0.0022020929 0.0013824634 0.0031927279 0.0026714860 0.0306730000 356434910 0 402718720 -0.0016495029 0.0010189792 0.0003116456 17 0.6400000000 0.0028206815 0.0014670645 0.0031927279 0.0028554155 0.0298900000 356436702 0 402718720 0.0000927539 -0.0028246897 0.0004507677 18 0.6800000000 0.0020664833 0.0015003655 0.0031927279 0.0027798385 0.0304630000 356443658 0 402718720 0.0007185166 -0.0026846870 -0.0001353372 19 0.7200000000 0.0011836004 0.0014836937 0.0031927279 0.0029287829 0.0431610000 356447458 0 402718720 -0.0008528299 -0.0012216894 -0.0000516183 20 0.7600000000 0.0021679783 0.0015179079 0.0031927279 0.0030238352 0.0413780000 356449234 0 402718720 -0.0013237392 -0.0025890185 -0.0002848991 21 0.8000000000 0.0018418727 0.0015333348 0.0031927279 0.0030224236 0.0302200000 356451222 0 402718720 -0.0002191772 -0.0027716039 -0.0005671419 22 0.8400000000 0.0007636592 0.0014983495 0.0031927279 0.0030141935 0.0305170000 356453826 0 402718720 0.0003858825 -0.0014345110 -0.0003024106 23 0.8800000000 0.0027505946 0.0015527950 0.0031927279 0.0030419866 0.0314510000 356456610 0 402718720 -0.0016829800 -0.0033557056 -0.0001999551 24 0.9200000000 0.0020923228 0.0015752753 0.0031927279 0.0030310679 0.0324620000 356460982 0 402718720 -0.0020509888 -0.0013439001 -0.0011736200 25 0.9600000000 0.0027233800 0.0016211995 0.0031927279 0.0029952990 0.0320230000 356462470 0 402718720 -0.0032028765 -0.0002189970 -0.0006708350 26 1.0000000000 0.0011629256 0.0016035736 0.0031927279 0.0029859153 0.0313730000 356465122 0 402718720 -0.0004473645 -0.0016666503 -0.0004050439 27 1.0400000000 0.0021211661 0.0016227437 0.0031927279 0.0029512550 0.0316520000 356468246 0 402718720 -0.0017183386 -0.0024232508 -0.0004209746 28 1.0800000000 0.0034736476 0.0016888474 0.0034736476 0.0029512187 0.0318600000 356470402 0 402718720 -0.0032903044 -0.0029794914 -0.0009014469 29 1.1200000000 0.0014424514 0.0016803510 0.0034736476 0.0029201852 0.0316240000 356473034 0 402718720 -0.0022267173 -0.0012750872 -0.0004500896 30 1.1600000000 0.0023203467 0.0017016841 0.0034736476 0.0029002613 0.0410970000 356475078 0 402718720 -0.0029409109 -0.0010935790 -0.0004828043 31 1.2000000000 0.0020408218 0.0017126241 0.0034736476 0.0028950421 0.0321510000 356476726 0 402718720 -0.0030850219 -0.0000384113 -0.0005322223 32 1.2400000000 0.0026791701 0.0017428286 0.0034736476 0.0028562954 0.0317920000 356479538 0 402718720 -0.0040309522 -0.0006841636 -0.0003481332 33 1.2800000000 0.0026926117 0.0017716099 0.0034736476 0.0028382082 0.0317120000 356484766 0 402718720 -0.0036769765 -0.0022646061 0.0001072756 34 1.3200000000 0.0032869661 0.0018161792 0.0034736476 0.0028320197 0.0314690000 356491878 0 402718720 -0.0048387768 -0.0026165340 0.0002067084 35 1.3600000000 0.0019896398 0.0018211353 0.0034736476 0.0028061716 0.0312210000 356495338 0 402718720 -0.0043177078 -0.0021733681 -0.0001995231 36 1.4000000000 0.0024531109 0.0018386901 0.0034736476 0.0027725006 0.0313130000 356497078 0 402718720 -0.0050823661 -0.0026266146 0.0000535268 37 1.4400000000 0.0037576861 0.0018905549 0.0037576861 0.0027902247 0.0415300000 356500886 0 402718720 -0.0032811740 -0.0051205540 0.0003423099 38 1.4800000000 0.0016915040 0.0018853167 0.0037576861 0.0027912936 0.0315360000 356503950 0 402718720 -0.0041634217 -0.0032337797 0.0002566347 39 1.5200000000 0.0014857230 0.0018750707 0.0037576861 0.0027702411 0.0321580000 356509986 0 402718720 -0.0041077686 -0.0048791212 0.0000699016 40 1.5600000000 0.0012158580 0.0018585904 0.0037576861 0.0028285838 0.0303880000 356510574 0 402718720 -0.0049403748 -0.0026713510 0.0007751366 41 1.6000000000 0.0027696299 0.0018808109 0.0037576861 0.0029875383 0.0420860000 356516110 0 402718720 -0.0055595268 -0.0042905048 0.0009435644 42 1.6400000000 0.0022404152 0.0018893729 0.0037576861 0.0030165074 0.0305160000 356519118 0 402718720 -0.0063630911 -0.0037676350 0.0010791444 43 1.6800000000 0.0010496551 0.0018698446 0.0037576861 0.0030917470 0.0309370000 356523302 0 402718720 -0.0040702056 -0.0024669371 0.0016050972 44 1.7200000000 0.0009315948 0.0018485207 0.0037576861 0.0030654751 0.0397060000 356523838 0 402718720 -0.0056957784 -0.0027705173 0.0023213644 45 1.7600000000 0.0021111851 0.0018543577 0.0037576861 0.0030926981 0.0304040000 356527530 0 402718720 -0.0078119705 -0.0030653968 0.0030245816 46 1.8000000000 0.0024745779 0.0018678407 0.0037576861 0.0030934171 0.0416880000 356530290 0 402718720 -0.0046475823 -0.0054965378 0.0036190860 47 1.8400000000 0.0019254313 0.0018690661 0.0037576861 0.0033488027 0.0301940000 356532254 0 402718720 -0.0076444088 -0.0050921869 0.0044094683 48 1.8800000000 0.0020163590 0.0018721347 0.0037576861 0.0035434307 0.0302470000 356537110 0 402718720 -0.0084595243 -0.0039819074 0.0063876980 49 1.9200000000 0.0022054103 0.0018789362 0.0037576861 0.0037179048 0.0305070000 356541922 0 402718720 -0.0065941885 -0.0075620851 0.0071460647 50 1.9600000000 0.0029324875 0.0019000072 0.0037576861 0.0039665529 0.0420080000 356547474 0 402718720 -0.0073400494 -0.0086452067 0.0079495441 51 2.0000000000 0.0014132062 0.0018904621 0.0037576861 0.0041339573 0.0423490000 356552198 0 402718720 -0.0073649902 -0.0066947029 0.0102816131 52 2.0400000000 0.0021657827 0.0018957568 0.0037576861 0.0042596583 0.0302450000 356556342 0 402718720 -0.0069666463 -0.0076379967 0.0126069281 53 2.0800000000 0.0025342298 0.0019078034 0.0037576861 0.0042708605 0.0305670000 356560302 0 402718720 -0.0046750726 -0.0093274917 0.0149043156 54 2.1200000000 0.0032656097 0.0019329480 0.0037576861 0.0043641477 0.0297020000 356562946 0 402718720 -0.0046188338 -0.0110694012 0.0157534573 55 2.1600000000 0.0022656650 0.0019389974 0.0037576861 0.0044012959 0.0302920000 356567338 0 402718720 -0.0058309082 -0.0087962858 0.0189311299 56 2.2000000000 0.0014865425 0.0019309178 0.0037576861 0.0043646360 0.0302430000 356568874 0 402718720 -0.0042798612 -0.0084094247 0.0214562621 57 2.2400000000 0.0026510647 0.0019435520 0.0037576861 0.0043454692 0.0297440000 356571530 0 402718720 -0.0004198348 -0.0089869546 0.0225006491 58 2.2800000000 0.0006426520 0.0019211227 0.0037576861 0.0044683072 0.0413270000 356577906 0 402718720 -0.0018608173 -0.0057720165 0.0258140657 59 2.3200000000 0.0013793492 0.0019119401 0.0037576861 0.0045927766 0.0295410000 356577810 0 402718720 -0.0016446100 -0.0071259760 0.0292383339 60 2.3600000000 0.0020279163 0.0019138730 0.0037576861 0.0047460565 0.0298900000 356586606 0 402718720 0.0022221287 -0.0088651488 0.0314474739 61 2.4000000000 0.0005088543 0.0018908399 0.0037576861 0.0050448694 0.0304110000 356590134 0 402718720 0.0015371199 -0.0081037264 0.0344675556 62 2.4400000000 0.0002062150 0.0018636685 0.0037576861 0.0052693984 0.0305690000 356592222 0 402718720 0.0030174798 -0.0078501534 0.0368774310 63 2.4800000000 0.0017437665 0.0018617653 0.0037576861 0.0054731659 0.0299760000 356593470 0 402718720 0.0031862152 -0.0098673366 0.0392481647 64 2.5200000000 0.0028459425 0.0018771431 0.0037576861 0.0056597350 0.0305710000 356600890 0 402718720 0.0033718504 -0.0072971024 0.0426328108 65 2.5600000000 0.0026003858 0.0018882699 0.0037576861 0.0058598957 0.0407800000 356604326 0 402718720 0.0049818191 -0.0097999526 0.0448181778 66 2.6000000000 0.0031925277 0.0019080314 0.0037576861 0.0061918077 0.0300720000 356619758 0 402718720 0.0065207873 -0.0116834911 0.0486052670 67 2.6400000000 0.0034034061 0.0019303504 0.0037576861 0.0064968260 0.0305780000 356625490 0 402718720 0.0100019882 -0.0050572790 0.0519034490 68 2.6800000000 0.0026497070 0.0019409292 0.0037576861 0.0069133218 0.0306250000 356629818 0 402718720 0.0090503795 -0.0090883188 0.0548089519 69 2.7200000000 0.0040767533 0.0019718832 0.0040767533 0.0071843332 0.0299290000 356632226 0 402718720 0.0097792922 -0.0067923050 0.0573497005 70 2.7600000000 0.0043697702 0.0020061387 0.0043697702 0.0073161373 0.0298630000 356637642 0 402718720 0.0106140636 -0.0106102470 0.0585103445 71 2.8000000000 0.0024790729 0.0020127997 0.0043697702 0.0073126501 0.0295170000 356639306 0 402718720 0.0135901542 -0.0085558230 0.0621074364 72 2.8400000000 0.0034003865 0.0020320718 0.0043697702 0.0073040446 0.0302540000 356645174 0 402718720 0.0141135771 -0.0095315464 0.0652139187 73 2.8800000000 0.0044633551 0.0020653770 0.0044633551 0.0073098312 0.0343930000 357263783 0 402718720 0.0151200797 -0.0072462838 0.0680997819 74 2.9200000000 0.0049365200 0.0021041763 0.0049365200 0.0073389851 0.0764690000 357817439 0 402718720 0.0156080723 -0.0073218485 0.0707794502 75 2.9600000000 0.0023057573 0.0021068640 0.0049365200 0.0073544551 0.1088770000 359267491 0 402718720 0.0193747543 -0.0081575634 0.0732941777 76 3.0000000000 0.0035520731 0.0021258799 0.0049365200 0.0075537947 0.0447060000 360476643 0 402718720 0.0196321085 -0.0092891306 0.0757491440 77 3.0400000000 0.0105245057 0.0022349530 0.0105245057 0.0075238511 0.0487510000 360319769 0 402718720 0.0344757438 -0.0085620061 0.0783599764 78 3.0800000000 0.0103480257 0.0023389667 0.0105245057 0.0077513600 0.0331650000 357903815 0 402718720 0.0356621966 -0.0072737196 0.0810429528 79 3.1200000000 0.0092448909 0.0024263835 0.0105245057 0.0079957742 0.0352680000 358372895 0 402718720 0.0356399715 -0.0116498722 0.0838237032 80 3.1600000000 0.0092969192 0.0025122652 0.0105245057 0.0081261203 0.0983690000 358455938 0 402718720 0.0367999524 -0.0126569299 0.0849011615 81 3.2000000000 0.0095941359 0.0025996957 0.0105245057 0.0082671923 0.0557050000 361125970 0 402718720 0.0385446250 -0.0119188596 0.0882521421 82 3.2400000000 0.0085030757 0.0026716881 0.0105245057 0.0084991881 0.0474220000 360966761 0 402718720 0.0373779461 -0.0083473017 0.0909293666 83 3.2800000000 0.0094361417 0.0027531876 0.0105245057 0.0086527463 0.0321030000 358435822 0 402718720 0.0399525352 -0.0112050027 0.0931482986 84 3.3200000000 0.0089097414 0.0028264799 0.0105245057 0.0087567084 0.0321560000 358441946 0 402718720 0.0402036197 -0.0136646172 0.0956874937 85 3.3600000000 0.0076126386 0.0028827876 0.0105245057 0.0088334283 0.0322880000 358446238 0 402718720 0.0395423211 -0.0126867946 0.0984692872 86 3.4000000000 0.0086897854 0.0029503109 0.0105245057 0.0089069000 0.0316260000 358451686 0 402718720 0.0408927239 -0.0094882166 0.1016135365 87 3.4400000000 0.0100340303 0.0030317329 0.0105245057 0.0089558541 0.0325280000 358455686 0 402718720 0.0434087850 -0.0101376753 0.1038186848 88 3.4800000000 0.0080232713 0.0030884549 0.0105245057 0.0090579812 0.0316690000 358458498 0 402718720 0.0423014164 -0.0119500207 0.1075387672 89 3.5200000000 0.0063955444 0.0031256133 0.0105245057 0.0091673385 0.0315950000 358463758 0 402718720 0.0413723886 -0.0108984895 0.1093389392 90 3.5600000000 0.0095965452 0.0031975125 0.0105245057 0.0092213104 0.0370620000 359034743 0 402718720 0.0451853685 -0.0135108419 0.1132663786 91 3.6000000000 0.0095395157 0.0032672048 0.0105245057 0.0093809331 0.1098320000 359183563 0 402718720 0.0461525321 -0.0109942704 0.1161171794 92 3.6400000000 0.0074406080 0.0033125679 0.0105245057 0.0094855887 0.0745030000 362253407 0 402718720 0.0448788889 -0.0137178283 0.1178333014 93 3.6800000000 0.0104593616 0.0033894152 0.0105245057 0.0094795989 0.0636350000 362225647 0 402718720 0.0481757112 -0.0120939463 0.1221422702 94 3.7200000000 0.0094894683 0.0034543093 0.0105245057 0.0094580640 0.0333320000 359119919 0 402718720 0.0479885861 -0.0122025255 0.1258082092 95 3.7600000000 0.0127418824 0.0035520733 0.0127418824 0.0094679948 0.0332930000 359121411 0 402718720 0.0503235608 -0.0072691413 0.1288834214 96 3.8000000000 0.0101767648 0.0036210805 0.0127418824 0.0094971759 0.0326390000 359126967 0 402718720 0.0497632548 -0.0096599711 0.1313470006 97 3.8400000000 0.0110328468 0.0036974904 0.0127418824 0.0096034619 0.0429670000 359132595 0 402718720 0.0517111495 -0.0095702186 0.1348396242 98 3.8800000000 0.0102109490 0.0037639543 0.0127418824 0.0097122522 0.0331130000 359137411 0 402718720 0.0516893305 -0.0105798766 0.1381757259 99 3.9200000000 0.0085806744 0.0038126080 0.0127418824 0.0098507100 0.0440080000 359139495 0 402718720 0.0512484610 -0.0118104666 0.1416024715 100 3.9600000000 0.0054765274 0.0038292472 0.0127418824 0.0100078811 0.0319690000 359144459 0 402718720 0.0481804833 -0.0093275737 0.1443720907 101 4.0000000000 0.0094913589 0.0038853077 0.0127418824 0.0100085711 0.0301690000 359143127 0 402718720 0.0529194847 -0.0093040485 0.1479465067 102 4.0400000000 0.0063459361 0.0039094316 0.0127418824 0.0100520742 0.0315960000 359153695 0 402718720 0.0504417457 -0.0107529052 0.1498299688 103 4.0800000000 0.0095085558 0.0039637920 0.0127418824 0.0100433114 0.0313590000 359156727 0 402718720 0.0539655462 -0.0086585749 0.1546077728 104 4.1200000000 0.0116767026 0.0040379546 0.0127418824 0.0100513911 0.0308660000 359161643 0 402718720 0.0563144088 -0.0055525457 0.1586348712 105 4.1600000000 0.0114410585 0.0041084603 0.0127418824 0.0100522531 0.0344140000 359843123 0 402718720 0.0570837222 -0.0075478540 0.1610133946 106 4.2000000000 0.0082638888 0.0041476625 0.0127418824 0.0100654115 0.1085610000 359818659 0 402718720 0.0541879684 -0.0086164437 0.1626525521 107 4.2400000000 0.0101755606 0.0042039980 0.0127418824 0.0100413133 0.0934940000 362042211 0 402718720 0.0565055944 -0.0074246395 0.1664802432 108 4.2800000000 0.0102095027 0.0042596045 0.0127418824 0.0100267819 0.0561450000 363461055 0 402718720 0.0567161329 -0.0066200416 0.1688879728 109 4.3200000000 0.0113579622 0.0043247271 0.0127418824 0.0099980196 0.0332080000 359830883 0 402718720 0.0579375066 -0.0050298814 0.1718294621 110 4.3600000000 0.0113854362 0.0043889153 0.0127418824 0.0099763383 0.0329930000 359833599 0 402718720 0.0572283007 -0.0015415591 0.1735966802 111 4.4000000000 0.0121444287 0.0044587848 0.0127418824 0.0099417480 0.0480960000 359837551 0 402718720 0.0593984909 -0.0034548733 0.1768057346 112 4.4400000000 0.0122024696 0.0045279249 0.0127418824 0.0099054928 0.0319580000 359842691 0 402718720 0.0600408278 -0.0035274411 0.1786060929 113 4.4800000000 0.0121037699 0.0045949677 0.0127418824 0.0098750877 0.0309300000 359848651 0 402718720 0.0595824979 -0.0029378841 0.1819123328 114 4.5200000000 0.0105992164 0.0046476366 0.0127418824 0.0098536007 0.0313130000 359854839 0 402718720 0.0576610044 -0.0012435354 0.1842085570 115 4.5600000000 0.0108978273 0.0047019861 0.0127418824 0.0098191560 0.0310380000 359858327 0 402718720 0.0586600266 -0.0019210717 0.1866066754 116 4.6000000000 0.0126320729 0.0047703489 0.0127418824 0.0097850300 0.0308220000 359862507 0 402718720 0.0607105121 -0.0025786159 0.1896943301 117 4.6400000000 0.0118568232 0.0048309170 0.0127418824 0.0097539937 0.0548850000 359867379 0 402718720 0.0601268336 -0.0028029517 0.1920252740 118 4.6800000000 0.0123472773 0.0048946150 0.0127418824 0.0097216580 0.0344050000 360622983 0 402718720 0.0607666746 -0.0031200331 0.1949605346 119 4.7200000000 0.0109685501 0.0049456565 0.0127418824 0.0096950193 0.1115240000 360597479 0 402718720 0.0597805455 -0.0023979687 0.1972989142 120 4.7600000000 0.0116430726 0.0050014683 0.0127418824 0.0096636093 0.0932000000 360747275 0 402718720 0.0607135370 -0.0029986559 0.1997343451 121 4.8000000000 0.0129442941 0.0050671115 0.0129442941 0.0096702954 0.0754770000 364950239 0 402718720 0.0610536262 0.0003243946 0.2038213313 122 4.8400000000 0.0123823173 0.0051270722 0.0129442941 0.0096709321 0.0392440000 364811959 0 402718720 0.0607334375 -0.0000729989 0.2065387964 123 4.8800000000 0.0131103294 0.0051919767 0.0131103294 0.0096501136 0.0589880000 364515941 0 402718720 0.0622022077 -0.0034066727 0.2119263560 124 4.9200000000 0.0150799314 0.0052717183 0.0150799314 0.0096320035 0.0304390000 360616975 0 402718720 0.0636684000 -0.0022364806 0.2165897489 125 4.9600000000 0.0136474166 0.0053387239 0.0150799314 0.0096041616 0.0300610000 360619807 0 402718720 0.0629530475 -0.0031027920 0.2189548314 126 5.0000000000 0.0129217748 0.0053989068 0.0150799314 0.0095918685 0.0305140000 360624043 0 402718720 0.0624800548 -0.0037029551 0.2221790850 127 5.0400000000 0.0127974190 0.0054571628 0.0150799314 0.0096164222 0.0301320000 360629523 0 402718720 0.0622509867 0.0002099574 0.2243306041 128 5.0800000000 0.0153084053 0.0055341256 0.0153084053 0.0096162567 0.0340600000 361373043 0 402718720 0.0647042096 -0.0003586563 0.2307002842 129 5.1200000000 0.0138597013 0.0055986650 0.0153084053 0.0096027575 0.1076100000 361341391 0 402718720 0.0640077516 0.0006447823 0.2320974171 130 5.1600000000 0.0159555823 0.0056783336 0.0159555823 0.0095911626 0.0930870000 361549971 0 402718720 0.0658746660 0.0015181943 0.2359444946 131 5.2000000000 0.0144192455 0.0057450581 0.0159555823 0.0095794507 0.0942090000 366185903 0 402718720 0.0655480549 0.0006209221 0.2378697395 132 5.2400000000 0.0144260293 0.0058108230 0.0159555823 0.0095539547 0.0707050000 366205899 0 402718720 0.0661491230 0.0001532021 0.2410812378 133 5.2800000000 0.0198152978 0.0059161198 0.0198152978 0.0096055363 0.0826350000 366151271 0 402718720 0.0683986172 0.0057404884 0.2472970486 134 5.3200000000 0.0173919704 0.0060017605 0.0198152978 0.0096245056 0.0311440000 361383691 0 402718720 0.0685484856 0.0036545033 0.2486413419 135 5.3600000000 0.0184162930 0.0060937200 0.0198152978 0.0096246630 0.0310450000 361386875 0 402718720 0.0694165900 0.0042517656 0.2516915500 136 5.4000000000 0.0190874543 0.0061892622 0.0198152978 0.0096286749 0.0306870000 361387711 0 402718720 0.0701628923 0.0033911066 0.2554757595 137 5.4400000000 0.0184744708 0.0062789352 0.0198152978 0.0096350182 0.0299690000 361392123 0 402718720 0.0701674893 0.0049489127 0.2559016943 138 5.4800000000 0.0196239632 0.0063756383 0.0198152978 0.0096129312 0.0297720000 361398035 0 402718720 0.0721052587 0.0042485367 0.2593554854 139 5.5200000000 0.0180051066 0.0064593036 0.0198152978 0.0095940987 0.0285560000 361394855 0 402718720 0.0716771036 0.0016946048 0.2617347240 140 5.5600000000 0.0179816596 0.0065416061 0.0198152978 0.0095784123 0.0310120000 361912955 0 402718720 0.0726054460 -0.0001138928 0.2638734579 141 5.6000000000 0.0196293890 0.0066344273 0.0198152978 0.0096404331 0.0943950000 361976235 0 402718720 0.0732555762 0.0013636732 0.2689838409 142 5.6400000000 0.0193455983 0.0067239426 0.0198152978 0.0096459302 0.0825870000 361978551 0 402718720 0.0729380324 0.0004065074 0.2711369991 143 5.6800000000 0.0171376429 0.0067967656 0.0198152978 0.0096290540 0.0762440000 364519131 0 402718720 0.0711417943 -0.0001346637 0.2711894810 144 5.7200000000 0.0176376160 0.0068720493 0.0198152978 0.0096302711 0.0539840000 367240283 0 402718720 0.0703612939 0.0019220263 0.2727826834 145 5.7600000000 0.0187595207 0.0069540319 0.0198152978 0.0096311249 0.0330180000 367294487 0 402718720 0.0704205856 0.0019019665 0.2759855390 146 5.8000000000 0.0217332561 0.0070552594 0.0217332561 0.0096600299 0.0682740000 367016933 0 402718720 0.0718204230 0.0029149726 0.2801639438 147 5.8400000000 0.0214211326 0.0071529865 0.0217332561 0.0096478983 0.0254140000 361987983 0 402718720 0.0708840266 0.0027516363 0.2806582749 148 5.8800000000 0.0209169220 0.0072459860 0.0217332561 0.0096233078 0.0275380000 362445927 0 402718720 0.0702052414 0.0018860828 0.2807983160 149 5.9200000000 0.0212975517 0.0073402918 0.0217332561 0.0096052327 0.0770890000 362496816 0 402718720 0.0694023967 0.0013836259 0.2836548984 150 5.9600000000 0.0211134702 0.0074321130 0.0217332561 0.0095811197 0.0640880000 362494084 0 402718720 0.0692654848 -0.0014247457 0.2861859202 151 6.0000000000 0.0199358538 0.0075149193 0.0217332561 0.0095714561 0.0641350000 367591604 0 402718720 0.0663189963 0.0009001615 0.2861460447 152 6.0400000000 0.0208951980 0.0076029474 0.0217332561 0.0095616221 0.0565200000 368157251 0 402718720 0.0657509491 0.0010198476 0.2889396250 153 6.0800000000 0.0200555753 0.0076843371 0.0217332561 0.0095434803 0.0257690000 368185784 0 402718720 0.0639798865 0.0011654841 0.2899121642 154 6.1200000000 0.0188045986 0.0077565466 0.0217332561 0.0095228890 0.0657190000 368101355 0 402718720 0.0618156716 -0.0003955793 0.2919281125 155 6.1600000000 0.0215687286 0.0078456575 0.0217332561 0.0095270783 0.0247380000 362868284 0 402718720 0.0602505580 0.0040412527 0.2942288816 156 6.2000000000 0.0201815795 0.0079247339 0.0217332561 0.0095296961 0.0661550000 362905756 0 402718720 0.0562435240 0.0014645122 0.2993183136 157 6.2400000000 0.0207321607 0.0080063099 0.0217332561 0.0095149024 0.0576860000 367201664 0 402718720 0.0550026372 0.0020753928 0.3016209006 158 6.2800000000 0.0210852493 0.0080890880 0.0217332561 0.0094925469 0.0389180000 368801738 0 402718720 0.0544532314 0.0018533012 0.3027552962 159 6.3200000000 0.0198490564 0.0081630500 0.0217332561 0.0094813991 0.0278390000 368697836 0 402718720 0.0513939783 0.0018618647 0.3034387827 160 6.3600000000 0.0201277491 0.0082378294 0.0217332561 0.0094594136 0.0614720000 368613867 0 402718720 0.0506550223 0.0010452997 0.3064877987 161 6.4000000000 0.0190072581 0.0083047203 0.0217332561 0.0094526186 0.0216490000 362912184 0 402718720 0.0475016758 0.0014560623 0.3070705235 162 6.4400000000 0.0193684045 0.0083730146 0.0217332561 0.0094589653 0.0197470000 362914968 0 402718720 0.0460383445 0.0007041916 0.3101950288 163 6.4800000000 0.0209067389 0.0084499086 0.0217332561 0.0094645518 0.0436730000 362916796 0 402718720 0.0438484624 0.0034483802 0.3117575347 164 6.5200000000 0.0199558642 0.0085200669 0.0217332561 0.0094408100 0.0194290000 362919028 0 402718720 0.0436475202 0.0009345608 0.3137772083 165 6.5600000000 0.0210142862 0.0085957894 0.0217332561 0.0094432067 0.0214210000 363284896 0 402718720 0.0412097275 0.0028910460 0.3158342838 166 6.6000000000 0.0197299607 0.0086628628 0.0217332561 0.0094227108 0.0602650000 363321348 0 402718720 0.0396322608 0.0011157412 0.3175849020 167 6.6400000000 0.0202455726 0.0087322203 0.0217332561 0.0094139142 0.0544270000 366613596 0 402718720 0.0375106707 0.0024271328 0.3201653957 168 6.6800000000 0.0197308790 0.0087976885 0.0217332561 0.0093932968 0.0465560000 367689550 0 402718720 0.0367907882 0.0002054721 0.3220739663 169 6.7200000000 0.0197309256 0.0088623822 0.0217332561 0.0093744343 0.0584750000 367606475 0 402718720 0.0355479047 -0.0008923551 0.3244741261 170 6.7600000000 0.0208792184 0.0089330695 0.0217332561 0.0093743579 0.0191990000 363326008 0 402718720 0.0332015380 0.0025222786 0.3247509897 171 6.8000000000 0.0212535299 0.0090051190 0.0217332561 0.0093596487 0.0317770000 363329968 0 402718720 0.0322552845 0.0021454096 0.3262857795 172 6.8400000000 0.0219210777 0.0090802117 0.0219210777 0.0093483853 0.0189540000 363339380 0 402718720 0.0297662169 0.0020006644 0.3295494616 173 6.8800000000 0.0229370613 0.0091603091 0.0229370613 0.0093330010 0.0218970000 363808344 0 402718720 0.0307488590 0.0016727429 0.3304522634 174 6.9200000000 0.0222780183 0.0092356983 0.0229370613 0.0093407378 0.0700920000 363971728 0 402718720 0.0294168703 0.0006884243 0.3313577771 175 6.9600000000 0.0227489006 0.0093129166 0.0229370613 0.0093539882 0.0684940000 368316820 0 402718720 0.0280061737 0.0006625438 0.3331214190 176 7.0000000000 0.0223420635 0.0093869458 0.0229370613 0.0093589042 0.0464400000 368668784 0 402718720 0.0272415504 -0.0000215610 0.3331205547 177 7.0400000000 0.0222485475 0.0094596102 0.0229370613 0.0093716269 0.0709420000 368663463 0 402718720 0.0272437222 -0.0004561325 0.3327803910 178 7.0800000000 0.0227232669 0.0095341252 0.0229370613 0.0093770011 0.0263620000 363893592 0 402718720 0.0268075578 -0.0006533270 0.3337389231 179 7.1200000000 0.0221876539 0.0096048153 0.0229370613 0.0094006775 0.0498710000 363896624 0 402718720 0.0272630304 -0.0040850639 0.3368264735 180 7.1600000000 0.0236583408 0.0096828904 0.0236583408 0.0094248335 0.0258240000 363904764 0 402718720 0.0260184631 -0.0013958644 0.3370476663 181 7.2000000000 0.0240889266 0.0097624818 0.0240889266 0.0094316113 0.0253440000 363909800 0 402718720 0.0243354850 0.0004446041 0.3357739449 182 7.2400000000 0.0220494699 0.0098299927 0.0240889266 0.0094558326 0.0257850000 363915764 0 402718720 0.0245266259 -0.0034212866 0.3372676373 183 7.2800000000 0.0201215465 0.0098862307 0.0240889266 0.0094601603 0.0249220000 363920284 0 402718720 0.0227611549 -0.0042476933 0.3354949951 184 7.3200000000 0.0274778903 0.0099818375 0.0274778903 0.0096413880 0.0247260000 363926064 0 402718720 0.0226323511 0.0034213061 0.3369652331 185 7.3600000000 0.0228743050 0.0100515265 0.0274778903 0.0096682969 0.0237370000 363931284 0 402718720 0.0219798647 -0.0020964125 0.3369891942 186 7.4000000000 0.0193725284 0.0101016395 0.0274778903 0.0096585714 0.0333290000 363935584 0 402718720 0.0220904220 -0.0066649187 0.3366441131 187 7.4400000000 0.0220065583 0.0101653021 0.0274778903 0.0096613036 0.0229600000 363938252 0 402718720 0.0208341368 -0.0032875920 0.3388052285 188 7.4800000000 0.0165826213 0.0101994368 0.0274778903 0.0096399235 0.0224380000 363942176 0 402718720 0.0210360829 -0.0084261140 0.3346525133 189 7.5200000000 0.0225542970 0.0102648064 0.0274778903 0.0096620596 0.0224780000 363945212 0 402718720 0.0216055885 -0.0033051225 0.3404938281 190 7.5600000000 0.0178116765 0.0103045268 0.0274778903 0.0096671316 0.0289390000 364946160 0 402718720 0.0207484365 -0.0083989687 0.3412672579 191 7.6000000000 0.0153304487 0.0103308405 0.0274778903 0.0096486020 0.1247820000 365138024 0 402718720 0.0213465877 -0.0115410378 0.3411285877 192 7.6400000000 0.0190242808 0.0103761189 0.0274778903 0.0096651206 0.0992830000 370348685 0 402718720 0.0199169461 -0.0068925084 0.3453538418 193 7.6800000000 0.0159369949 0.0104049317 0.0274778903 0.0096501915 0.0929810000 370393995 0 402718720 0.0197241474 -0.0112896068 0.3471590877 194 7.7200000000 0.0178997070 0.0104435646 0.0274778903 0.0096459545 0.0656900000 364964700 0 402718720 0.0214966517 -0.0075296666 0.3437729180 195 7.7600000000 0.0178643055 0.0104816196 0.0274778903 0.0096312073 0.0414950000 364967816 0 402718720 0.0219506882 -0.0082648611 0.3461538851 196 7.8000000000 0.0182693396 0.0105213529 0.0274778903 0.0096262701 0.0411840000 364971140 0 402718720 0.0206368938 -0.0080467779 0.3496429026 197 7.8400000000 0.0161736123 0.0105500446 0.0274778903 0.0096127731 0.0407080000 364974572 0 402718720 0.0206071548 -0.0106360847 0.3499379754 198 7.8800000000 0.0184566732 0.0105899770 0.0274778903 0.0095995969 0.0525930000 364976812 0 402718720 0.0211194605 -0.0075594746 0.3499949872 199 7.9200000000 0.0188857187 0.0106316642 0.0274778903 0.0095910667 0.0417260000 364981732 0 402718720 0.0218854733 -0.0081739128 0.3519015312 200 7.9600000000 0.0162483547 0.0106597476 0.0274778903 0.0095801432 0.0397960000 364983580 0 402718720 0.0234207399 -0.0122213047 0.3508271575 201 8.0000000000 0.0155370124 0.0106840126 0.0274778903 0.0095643278 0.0404570000 364986032 0 402718720 0.0240513980 -0.0134341363 0.3504121006 202 8.0400000000 0.0160268825 0.0107104625 0.0274778903 0.0095687766 0.0384750000 364989064 0 402718720 0.0238762125 -0.0140519179 0.3538819253 203 8.0800000000 0.0154535994 0.0107338277 0.0274778903 0.0095506208 0.0384500000 364992852 0 402718720 0.0271785110 -0.0169921890 0.3481570184 204 8.1200000000 0.0168412942 0.0107637663 0.0274778903 0.0095833964 0.0381070000 364995468 0 402718720 0.0253449008 -0.0139720496 0.3546712101 205 8.1600000000 0.0151852379 0.0107853344 0.0274778903 0.0096033777 0.0491940000 364997752 0 402718720 0.0274206549 -0.0218640808 0.3536699414 206 8.1999999990 0.0159554686 0.0108104322 0.0274778903 0.0096383933 0.0400640000 365000816 0 402718720 0.0232982710 -0.0153772589 0.3582147062 207 8.2400000000 0.0174930226 0.0108427152 0.0274778903 0.0096577700 0.0377070000 365003840 0 402718720 0.0223654956 -0.0111614671 0.3581227362 208 8.2799999990 0.0313148685 0.0109411390 0.0313148685 0.0098462541 0.0380360000 365007012 0 402718720 0.0133598968 0.0007614903 0.3694204390 209 8.3200000000 0.0154731367 0.0109628232 0.0313148685 0.0099802409 0.0378930000 365009984 0 402718720 0.0233556852 -0.0151669718 0.3577292562 210 8.3599999990 0.0213016178 0.0110120556 0.0313148685 0.0100376683 0.0374720000 365012248 0 402718720 0.0180561319 -0.0104734842 0.3656581044 211 8.4000000000 0.0166974012 0.0110390003 0.0313148685 0.0100157115 0.0369590000 365015816 0 402718720 0.0192752555 -0.0117720068 0.3599431813 212 8.4399999990 0.0205346867 0.0110837913 0.0313148685 0.0100210956 0.0368630000 365018964 0 402718720 0.0180559382 -0.0047258139 0.3575263023 213 8.4800000000 0.0290065482 0.0111679357 0.0313148685 0.0101206532 0.0368100000 365022280 0 402718720 0.0126655027 -0.0023848899 0.3689945042 214 8.5200000000 0.0194277726 0.0112065331 0.0313148685 0.0101436147 0.0368600000 365025204 0 402718720 0.0183632523 -0.0108971409 0.3623698354 215 8.5600000000 0.0191267431 0.0112433713 0.0313148685 0.0101276687 0.0362820000 365027328 0 402718720 0.0196535364 -0.0085095149 0.3590454459 216 8.6000000000 0.0174981672 0.0112723286 0.0313148685 0.0101407431 0.0360580000 365030484 0 402718720 0.0238991082 -0.0124343913 0.3567965627 217 8.6400000000 0.0135456426 0.0112828047 0.0313148685 0.0101331760 0.0356490000 365032996 0 402718720 0.0235582665 -0.0155534353 0.3522764742 218 8.6800000000 0.0194726624 0.0113203729 0.0313148685 0.0102124082 0.0465240000 365035808 0 402718720 0.0156192631 -0.0092666075 0.3609410822 219 8.7200000000 0.0126823857 0.0113265921 0.0313148685 0.0102098444 0.0462690000 365039724 0 402718720 0.0198356584 -0.0123488158 0.3517586589 220 8.7600000000 0.0216060057 0.0113733167 0.0313148685 0.0102782728 0.0352260000 365043456 0 402718720 0.0148625523 -0.0043764319 0.3591763973 221 8.8000000000 0.0332039744 0.0114720980 0.0332039744 0.0103579188 0.0353170000 365045040 0 402718720 0.0073422045 0.0016417280 0.3688668907 222 8.8400000000 0.0180358011 0.0115016642 0.0332039744 0.0104611790 0.0346850000 365048508 0 402718720 0.0151004791 -0.0142302234 0.3607048094 223 8.8800000000 0.0260456931 0.0115668841 0.0332039744 0.0105338112 0.0487950000 365051792 0 402718720 0.0127755851 0.0036947187 0.3556133211 224 8.9200000000 0.0249261726 0.0116265238 0.0332039744 0.0105686967 0.0397310000 365055052 0 402718720 0.0153391361 0.0018435083 0.3557979465 225 8.9600000000 0.0280218944 0.0116993921 0.0332039744 0.0106142787 0.0393430000 365058196 0 402718720 0.0135425031 0.0025139339 0.3602101505 226 9.0000000000 0.0260395836 0.0117628443 0.0332039744 0.0106974957 0.0394680000 365061160 0 402718720 0.0089034438 -0.0068116896 0.3641834259 227 9.0400000000 0.0347897261 0.0118642843 0.0347897261 0.0107497706 0.0394810000 365064132 0 402718720 0.0086193681 -0.0023477208 0.3711756766 228 9.0800000000 0.0161022581 0.0118828719 0.0347897261 0.0107694811 0.0389720000 365066640 0 402718720 0.0163968503 -0.0061544720 0.3493508697 229 9.1200000000 0.0218333881 0.0119263239 0.0347897261 0.0108110698 0.0385860000 365068952 0 402718720 0.0131568164 -0.0007294770 0.3524252176 230 9.1600000000 0.0277038608 0.0119949219 0.0347897261 0.0108567038 0.0385740000 365072848 0 402718720 0.0083926320 -0.0008399710 0.3599224687 231 9.2000000000 0.0132546062 0.0120003751 0.0347897261 0.0108948566 0.0376410000 365075860 0 402718720 0.0156627893 -0.0097144451 0.3457017839 232 9.2400000000 0.0239755027 0.0120519920 0.0347897261 0.0109699457 0.0385580000 365078176 0 402718720 0.0097895116 -0.0009574741 0.3541578650 233 9.2800000000 0.0147352712 0.0120635082 0.0347897261 0.0110745755 0.0378970000 365081084 0 402718720 0.0213930607 -0.0126222242 0.3398371339 234 9.3200000000 0.0192019194 0.0120940143 0.0347897261 0.0111717582 0.0378120000 365085588 0 402718720 0.0120999366 0.0009342432 0.3433820009 235 9.3600000000 0.0223481860 0.0121376490 0.0347897261 0.0112048005 0.0376620000 365087856 0 402718720 0.0080251992 0.0005587619 0.3488133550 236 9.4000000000 0.0160049666 0.0121540360 0.0347897261 0.0112164642 0.0371460000 365090656 0 402718720 0.0137637258 -0.0038174856 0.3409147263 237 9.4400000000 0.0192484036 0.0121839700 0.0347897261 0.0112219026 0.0379540000 365093708 0 402718720 0.0125799775 0.0014398489 0.3399737477 238 9.4800000000 0.0224081557 0.0122269288 0.0347897261 0.0112906307 0.0377330000 365097148 0 402718720 0.0133911520 0.0062314775 0.3371430933 239 9.5200000000 0.0134386215 0.0122319986 0.0347897261 0.0112949800 0.0372190000 365099160 0 402718720 0.0072770566 0.0002263561 0.3327467144 240 9.5600000000 0.0232469719 0.0122778943 0.0347897261 0.0113724350 0.0358430000 365102912 0 402718720 0.0051467121 0.0071257083 0.3411370218 241 9.6000000000 0.0199511889 0.0123097337 0.0347897261 0.0114360586 0.0310000000 365105676 0 402718720 0.0028736889 0.0025672019 0.3405479193 242 9.6400000000 0.0200758148 0.0123418250 0.0347897261 0.0114590315 0.0312160000 365108620 0 402718720 0.0075970590 0.0092369393 0.3297667503 243 9.6800000000 0.0152120283 0.0123536365 0.0347897261 0.0116269964 0.0308320000 365111032 0 402718720 0.0045050085 -0.0044890996 0.3352016211 244 9.7200000000 0.0166713148 0.0123713319 0.0347897261 0.0116452807 0.0310430000 365113984 0 402718720 0.0125301033 -0.0000957255 0.3177832663 245 9.7600000000 0.0187846776 0.0123975088 0.0347897261 0.0117644890 0.0302640000 365116436 0 402718720 0.0004297048 0.0094167516 0.3295371234 246 9.8000000000 0.0207014699 0.0124312648 0.0347897261 0.0118930306 0.0308480000 365119212 0 402718720 -0.0066607893 -0.0017684093 0.3378506601 247 9.8400000000 0.0122786714 0.0124306470 0.0347897261 0.0119273872 0.0305840000 365121720 0 402718720 -0.0011392087 -0.0077727158 0.3263959587 248 9.8800000000 0.0207223669 0.0124640813 0.0347897261 0.0120084499 0.0507740000 365124288 0 402718720 0.0036327988 0.0149649372 0.3173359036 249 9.9200000000 0.0166759770 0.0124809966 0.0347897261 0.0121978095 0.0304420000 365126876 0 402718720 0.0080602765 -0.0039747949 0.3160375953 250 9.9600000000 0.0432879627 0.0126042245 0.0432879627 0.0126853567 0.0303030000 365129372 0 402718720 -0.0049712062 0.0373418927 0.3311982453 251 10.0000000000 0.0307951123 0.0126766981 0.0432879627 0.0135981318 0.0301220000 365132396 0 402718720 -0.0037767738 -0.0240983330 0.3270110488 252 10.0400000000 0.0319130234 0.0127530327 0.0432879627 0.0136030012 0.0301640000 365135052 0 402718720 -0.0054475516 -0.0285822563 0.3168714643 253 10.0800000000 0.0204462018 0.0127834405 0.0432879627 0.0139252283 0.0298550000 365137684 0 402718720 -0.0064628720 0.0144068506 0.3219095469 254 10.1200000000 0.0271711592 0.0128400851 0.0432879627 0.0140470131 0.0399120000 365140540 0 402718720 -0.0116928965 0.0065902909 0.3316106796 255 10.1600000000 0.0167287439 0.0128553347 0.0432879627 0.0140435558 0.0298240000 365143208 0 402718720 -0.0077787787 0.0147079453 0.3148589432 256 10.2000000000 0.0129722357 0.0128557914 0.0432879627 0.0141058923 0.0293110000 365145552 0 402718720 -0.0080423206 0.0040644780 0.3124637604 257 10.2400000000 0.0267515071 0.0129098603 0.0432879627 0.0142017824 0.0288240000 365150120 0 402718720 -0.0118327588 0.0251524057 0.3188183904 258 10.2800000000 0.0249436423 0.0129565029 0.0432879627 0.0141997884 0.0284120000 365203328 0 402718720 -0.0131526887 0.0252485611 0.3154877722 259 10.3200000000 0.0197717696 0.0129828166 0.0432879627 0.0142887608 0.0281770000 365205920 0 402718720 0.0010883212 0.0144347632 0.2972323596 260 10.3600000000 0.0261443369 0.0130334379 0.0432879627 0.0142946534 0.0287670000 365208800 0 402718720 0.0063529611 0.0149150342 0.2902049720 261 10.4000000000 0.0238763113 0.0130749814 0.0432879627 0.0143936243 0.0370750000 365211144 0 402718720 -0.0070148855 0.0283598360 0.3027490973 262 10.4400000000 0.0186107904 0.0130961105 0.0432879627 0.0144151717 0.0284050000 365214024 0 402718720 -0.0125517994 0.0212104786 0.3054971695 263 10.4800000000 0.0209335852 0.0131259108 0.0432879627 0.0144099784 0.0282660000 365216428 0 402718720 -0.0158913583 0.0226763431 0.3076264262 264 10.5200000000 0.0218710471 0.0131590363 0.0432879627 0.0143939663 0.0280400000 365218672 0 402718720 -0.0173979849 0.0244509373 0.3067001104 265 10.5600000000 0.0237010941 0.0131988176 0.0432879627 0.0145294317 0.0282920000 365221580 0 402718720 -0.0178473145 0.0032063015 0.3087941408 266 10.6000000000 0.0294470955 0.0132599014 0.0432879627 0.0145875837 0.0283560000 365224364 0 402718720 -0.0273473263 0.0187908597 0.3147636652 267 10.6400000000 0.0228650477 0.0132958757 0.0432879627 0.0146238006 0.0281320000 365226736 0 402718720 -0.0194086134 0.0335094035 0.2947826684 268 10.6800000000 0.0235220827 0.0133340332 0.0432879627 0.0148172839 0.0399970000 365229108 0 402718720 -0.0237746835 0.0027721766 0.3030938804 269 10.7200000000 0.0233734325 0.0133713544 0.0432879627 0.0149521160 0.0406660000 365231492 0 402718720 -0.0251886025 0.0346919373 0.2929973602 270 10.7600000000 0.0230164248 0.0134070769 0.0432879627 0.0152648771 0.0277210000 365234216 0 402718720 -0.0114462376 -0.0011995323 0.2843796611 271 10.8000000000 0.0314109102 0.0134735117 0.0432879627 0.0154956461 0.0281750000 365236816 0 402718720 -0.0242966115 0.0261474513 0.3067792654 272 10.8400000000 0.0280731414 0.0135271868 0.0432879627 0.0155373094 0.0277460000 365239548 0 402718720 -0.0302401483 0.0052737929 0.3016768694 273 10.8800000000 0.0249104649 0.0135688838 0.0432879627 0.0156506746 0.0280460000 365241752 0 402718720 -0.0214065835 0.0371467695 0.2851838470 274 10.9200000000 0.0193480905 0.0135899758 0.0432879627 0.0156703214 0.0276120000 365244432 0 402718720 -0.0220964402 0.0264598597 0.2867339849 275 10.9600000000 0.0175216496 0.0136042728 0.0432879627 0.0156996044 0.0277400000 365247356 0 402718720 -0.0194141716 0.0105628297 0.2818997502 276 11.0000000000 0.0236669313 0.0136407317 0.0432879627 0.0156976793 0.0279480000 365249736 0 402718720 -0.0133372843 0.0033521261 0.2745885253 277 11.0400000000 0.0093985889 0.0136254171 0.0432879627 0.0157224545 0.0273870000 365252280 0 402718720 -0.0250071734 0.0172699317 0.2724824846 278 11.0800000000 0.0171319563 0.0136380305 0.0432879627 0.0157090445 0.0276690000 365254392 0 402718720 -0.0191095844 0.0263426676 0.2645375133 279 11.1200000000 0.0158598050 0.0136459939 0.0432879627 0.0157436740 0.0276510000 365257520 0 402718720 -0.0275121853 0.0213654451 0.2775369883 280 11.1600000000 0.0170017611 0.0136579788 0.0432879627 0.0157245712 0.0275400000 365259904 0 402718720 -0.0244235471 0.0262146443 0.2722418904 281 11.2000000000 0.0123105971 0.0136531838 0.0432879627 0.0157009719 0.0275630000 365262528 0 402718720 -0.0240675583 0.0212003980 0.2628124654 282 11.2400000000 0.0299100205 0.0137108322 0.0432879627 0.0157560499 0.0377400000 365265096 0 402718720 -0.0258722231 0.0456968918 0.2630074024 283 11.2800000000 0.0179215800 0.0137257111 0.0432879627 0.0157699471 0.0271060000 365267716 0 402718720 -0.0291436687 0.0312337056 0.2666378617 284 11.3200000000 0.0463192202 0.0138404770 0.0463192202 0.0159433423 0.0267860000 365270252 0 402718720 -0.0067104250 0.0421954691 0.2314577252 285 11.3600000000 0.0285433009 0.0138920659 0.0463192202 0.0159581144 0.0269850000 365272668 0 402718720 -0.0174766555 0.0358284637 0.2470293343 286 11.4000000000 0.0232758354 0.0139248763 0.0463192202 0.0160412181 0.0266940000 365275148 0 402718720 -0.0390384495 0.0358189717 0.2679469287 287 11.4400000000 0.0273496751 0.0139716526 0.0463192202 0.0161142961 0.0266670000 365277732 0 402718720 -0.0189233199 0.0343277156 0.2477129996 288 11.4800000000 0.0386605896 0.0140573780 0.0463192202 0.0162535127 0.0264660000 365280132 0 402718720 -0.0440550819 0.0513909236 0.2688281536 289 11.5200000000 0.0408258922 0.0141500027 0.0463192202 0.0162263474 0.0372720000 365282624 0 402718720 -0.0452996939 0.0508448072 0.2717973590 290 11.5600000000 0.0325956121 0.0142136082 0.0463192202 0.0162153354 0.0255760000 365285312 0 402718720 -0.0466036275 0.0414109603 0.2680331469 291 11.6000000000 0.0265739821 0.0142560837 0.0463192202 0.0163513715 0.0365180000 365287624 0 402718720 -0.0541926995 0.0071449317 0.2668762207 292 11.6400000000 0.0410352014 0.0143477930 0.0463192202 0.0165837609 0.0361240000 365290252 0 402718720 -0.0531695485 0.0504837930 0.2654733062 293 11.6800000000 0.0366833918 0.0144240237 0.0463192202 0.0166695118 0.0246340000 365292880 0 402718720 -0.0360688046 0.0501632765 0.2447704673 294 11.7200000000 0.0327170901 0.0144862451 0.0463192202 0.0166465554 0.0283690000 365866936 0 402718720 -0.0356060192 0.0446180478 0.2414391935 295 11.7600000000 0.0372405387 0.0145633782 0.0463192202 0.0166208013 0.0779450000 368194314 0 402718720 -0.0353306681 0.0484811105 0.2388775796 296 11.8000000000 0.3155526519 0.0155802339 0.3155526519 0.0253208645 0.0427270000 368100233 0 402718720 0.0827637762 0.0228292663 -0.0476345792 297 11.8400000000 0.3177318275 0.0165975793 0.3177318275 0.0252788985 0.0298590000 365926220 0 402718720 0.0816400796 0.0233200714 -0.0509816371 298 11.8800000000 0.3195070624 0.0176140541 0.3195070624 0.0252399200 0.0302040000 365928844 0 402718720 0.0808099061 0.0216310862 -0.0538973249 299 11.9200000000 0.3187468350 0.0186211872 0.3195070624 0.0252022002 0.0296530000 365930968 0 402718720 0.0768990964 0.0195308570 -0.0552172959 300 11.9600000000 0.3172225058 0.0196165249 0.3195070624 0.0251625738 0.0286780000 365933576 0 402718720 0.0727383345 0.0159669202 -0.0559135526 301 12.0000000000 0.3154614270 0.0205993983 0.3195070624 0.0251240356 0.0288820000 365935972 0 402718720 0.0695972443 0.0172322299 -0.0558058172 302 12.0400000000 0.3152073920 0.0215749215 0.3195070624 0.0250870192 0.0282840000 365938660 0 402718720 0.0674712434 0.0212985612 -0.0567248911 303 12.0800000000 0.3162967563 0.0225476008 0.3195070624 0.0250476292 0.0378510000 365940784 0 402718720 0.0663433000 0.0203779787 -0.0589587167 304 12.1200000000 0.3183864057 0.0235207548 0.3195070624 0.0250117911 0.0277130000 365943056 0 402718720 0.0643358156 0.0192421265 -0.0624322146 305 12.1600000000 0.3149068356 0.0244761190 0.3195070624 0.0249758168 0.0269810000 365945824 0 402718720 0.0597994439 0.0206430480 -0.0611162893 306 12.2000000000 0.3111540079 0.0254129748 0.3195070624 0.0249384181 0.0267260000 365948512 0 402718720 0.0529665016 0.0194887966 -0.0603537522 307 12.2400000000 0.3139628768 0.0263528768 0.3195070624 0.0248999643 0.0263990000 365950172 0 402718720 0.0545361079 0.0166323595 -0.0630657524 308 12.2800000000 0.3156621158 0.0272921925 0.3195070624 0.0248617834 0.0259840000 365952796 0 402718720 0.0506342091 0.0125368619 -0.0668976903 309 12.3200000000 0.3162426949 0.0282273074 0.3195070624 0.0248246515 0.0258470000 365955252 0 402718720 0.0508576259 0.0125262383 -0.0675599128 310 12.3600000000 0.3125815690 0.0291445792 0.3195070624 0.0247907931 0.0336570000 365957680 0 402718720 0.0441381223 0.0124199800 -0.0669013783 311 12.4000000000 0.3147688508 0.0300629852 0.3195070624 0.0247517563 0.0253690000 365960016 0 402718720 0.0435575880 0.0140050836 -0.0691779479 312 12.4400000000 0.3150008321 0.0309762475 0.3195070624 0.0247123636 0.0251290000 365962640 0 402718720 0.0425376147 0.0146934073 -0.0698953941 313 12.4800000000 0.3128783107 0.0318768931 0.3195070624 0.0246751765 0.0359380000 365964852 0 402718720 0.0376966745 0.0102185616 -0.0698041767 314 12.5200000000 0.3128806353 0.0327718095 0.3195070624 0.0246360708 0.0242620000 365967096 0 402718720 0.0361850113 0.0095920181 -0.0700332597 315 12.5600000000 0.3136883974 0.0336636082 0.3195070624 0.0246027986 0.0238610000 365969692 0 402718720 0.0372513644 0.0157731865 -0.0701241344 316 12.6000000000 0.3149907887 0.0345538841 0.3195070624 0.0245706035 0.0236330000 365971904 0 402718720 0.0328663252 0.0091162063 -0.0731918067 317 12.6400000000 0.3111282587 0.0354263584 0.3195070624 0.0245366960 0.0232660000 365974868 0 402718720 0.0299109183 0.0121063869 -0.0702703297 318 12.6800000000 0.3145408034 0.0363040768 0.3195070624 0.0245102162 0.0330150000 365977144 0 402718720 0.0292513892 0.0103720799 -0.0740891844 319 12.7200000000 0.3180868328 0.0371874083 0.3195070624 0.0244795470 0.0230110000 365979108 0 402718720 0.0309141967 0.0080907950 -0.0774150193 320 12.7600000000 0.3116068244 0.0380449690 0.3195070624 0.0244464479 0.0225450000 365981692 0 402718720 0.0218842234 0.0024565239 -0.0746637955 321 12.8000000000 0.3164410591 0.0389122465 0.3195070624 0.0244105305 0.0225730000 365984308 0 402718720 0.0265809167 0.0007936764 -0.0781960785 322 12.8400000000 0.3146583140 0.0397686008 0.3195070624 0.0243749761 0.0221810000 365986720 0 402718720 0.0217866153 -0.0022005388 -0.0787660480 323 12.8800000000 0.3169005811 0.0406265945 0.3195070624 0.0243452113 0.0220460000 365989176 0 402718720 0.0235273428 0.0010369138 -0.0809161216 324 12.9200000000 0.3122718334 0.0414650058 0.3195070624 0.0243110810 0.0216100000 365991476 0 402718720 0.0188358780 0.0034679445 -0.0788189098 325 12.9600000000 0.3107584417 0.0422936010 0.3195070624 0.0242750475 0.0215740000 365994376 0 402718720 0.0167819299 0.0027563169 -0.0787433907 326 13.0000000000 0.3108117878 0.0431172764 0.3195070624 0.0242421434 0.0471760000 365996524 0 402718720 0.0144097954 0.0024080547 -0.0808493868 327 13.0400000000 0.3131767809 0.0439431464 0.3195070624 0.0242092876 0.0210570000 365998780 0 402718720 0.0161632858 -0.0026697204 -0.0832816660 328 13.0800000000 0.3052272499 0.0447397443 0.3195070624 0.0241830003 0.0207930000 366000900 0 402718720 0.0047218874 0.0008965726 -0.0808102190 329 13.1200000000 0.3151183128 0.0455615637 0.3195070624 0.0241569648 0.0318630000 366003464 0 402718720 0.0130763575 -0.0029281313 -0.0886752009 330 13.1600000000 0.3104220331 0.0463641711 0.3195070624 0.0241311368 0.0206250000 366006120 0 402718720 0.0068404861 0.0041854093 -0.0876629874 331 13.2000000000 0.3083223701 0.0471555856 0.3195070624 0.0240948797 0.0206670000 366008268 0 402718720 0.0074517652 0.0038151988 -0.0863073915 332 13.2400000000 0.3053028286 0.0479331376 0.3195070624 0.0240627951 0.0204700000 366010432 0 402718720 0.0009028614 -0.0025106133 -0.0873533636 333 13.2800000000 0.3152714074 0.0487359552 0.3195070624 0.0240434700 0.0303230000 366013152 0 402718720 0.0095682666 0.0041198768 -0.0960601419 334 13.3200000000 0.3084665835 0.0495135918 0.3195070624 0.0240199311 0.0207630000 366015300 0 402718720 -0.0043803938 -0.0057055010 -0.0967962891 335 13.3600000000 0.3049592078 0.0502761160 0.3195070624 0.0239852460 0.0206660000 366017924 0 402718720 -0.0060044713 -0.0067079300 -0.0950380862 336 13.4000000000 0.3129864335 0.0510579920 0.3195070624 0.0239787555 0.0321410000 366020364 0 402718720 0.0013177022 -0.0050717634 -0.1024588421 337 13.4400000000 0.3113155067 0.0518302695 0.3195070624 0.0239609732 0.0206790000 366022268 0 402718720 -0.0003516227 0.0029969099 -0.1042153910 338 13.4800000000 0.3075906634 0.0525869570 0.3195070624 0.0239271125 0.0205650000 366024768 0 402718720 -0.0018632635 -0.0005612827 -0.1025569290 339 13.5200000000 0.3118114769 0.0533516311 0.3195070624 0.0239012232 0.0236380000 366504319 0 402718720 0.0007864311 0.0025249028 -0.1079687253 340 13.5600000000 0.3136241138 0.0541171384 0.3195070624 0.0238676255 0.0658310000 367824460 0 402718720 0.0020449162 -0.0003010361 -0.1114258766 341 13.6000000000 0.3061110377 0.0548561235 0.3195070624 0.0238392074 0.0282790000 366633784 0 402718720 -0.0062813312 -0.0081908526 -0.1088963673 342 13.6400000000 0.3044606149 0.0555859612 0.3195070624 0.0238049522 0.0273950000 366636468 0 402718720 -0.0093249083 -0.0063714748 -0.1106549352 343 13.6800000000 0.3067559898 0.0563182353 0.3195070624 0.0237715088 0.0269610000 366638924 0 402718720 -0.0077911466 -0.0107886298 -0.1143517494 344 13.7200000000 0.3060730994 0.0570442669 0.3195070624 0.0237398665 0.0267580000 366641180 0 402718720 -0.0095532462 -0.0110839782 -0.1172209531 345 13.7600000000 0.3043152988 0.0577609945 0.3195070624 0.0237098597 0.0268860000 366643776 0 402718720 -0.0142601058 -0.0097182933 -0.1202699691 346 13.8000000000 0.3048379123 0.0584750897 0.3195070624 0.0236758796 0.0536330000 366645540 0 402718720 -0.0134566687 -0.0090565728 -0.1227562726 347 13.8400000000 0.3055693507 0.0591871769 0.3195070624 0.0236417134 0.0271670000 366648424 0 402718720 -0.0146214664 -0.0091137821 -0.1265922040 348 13.8800000000 0.3050604463 0.0598937092 0.3195070624 0.0236083150 0.0260670000 366650724 0 402718720 -0.0156814568 -0.0127075706 -0.1284365058 349 13.9200000000 0.3064983189 0.0606003127 0.3195070624 0.0235753270 0.0458750000 366652580 0 402718720 -0.0151171200 -0.0143102752 -0.1320885122 350 13.9600000000 0.3058787882 0.0613011084 0.3195070624 0.0235437915 0.0263070000 366655064 0 402718720 -0.0152589306 -0.0116638569 -0.1344967186 351 14.0000000000 0.3053766787 0.0619964803 0.3195070624 0.0235128747 0.0264720000 366657396 0 402718720 -0.0173718706 -0.0100120232 -0.1374891698 352 14.0400000000 0.3033263981 0.0626820767 0.3195070624 0.0234815988 0.0259330000 366660036 0 402718720 -0.0207795240 -0.0115936380 -0.1395413578 353 14.0800000000 0.3046259582 0.0633674701 0.3195070624 0.0234516329 0.0260430000 366661832 0 402718720 -0.0205135532 -0.0109544257 -0.1433429420 354 14.1200000000 0.3082109690 0.0640591184 0.3195070624 0.0234210468 0.0256790000 366664688 0 402718720 -0.0181922391 -0.0108917793 -0.1485804319 355 14.1600000000 0.3036950231 0.0647341492 0.3195070624 0.0233899032 0.0261000000 366667220 0 402718720 -0.0231137648 -0.0108922329 -0.1480408609 356 14.2000000000 0.3030211926 0.0654034948 0.3195070624 0.0233575139 0.0260480000 366669552 0 402718720 -0.0244978480 -0.0121556781 -0.1502474993 357 14.2400000000 0.3058466613 0.0660770051 0.3195070624 0.0233264415 0.0252720000 366671516 0 402718720 -0.0213587731 -0.0141450576 -0.1540257335 358 14.2800000000 0.3014934957 0.0667345930 0.3195070624 0.0232984810 0.0248660000 366673816 0 402718720 -0.0281697810 -0.0135770589 -0.1541968584 359 14.3200000000 0.3018227518 0.0673894347 0.3195070624 0.0232682469 0.0249960000 366676104 0 402718720 -0.0270132013 -0.0123010520 -0.1563985795 360 14.3600000000 0.2984051406 0.0680311450 0.3195070624 0.0232394633 0.0246160000 366678516 0 402718720 -0.0330946967 -0.0111015756 -0.1578858644 361 14.4000000000 0.2992034554 0.0686715115 0.3195070624 0.0232108733 0.0245180000 366680864 0 402718720 -0.0316782631 -0.0134904813 -0.1600059122 362 14.4400000000 0.3026428223 0.0693178411 0.3195070624 0.0231825976 0.0241890000 366683368 0 402718720 -0.0297300704 -0.0127042485 -0.1655060202 363 14.4800000000 0.3024564683 0.0699600963 0.3195070624 0.0231518395 0.0247360000 366685716 0 402718720 -0.0313530862 -0.0137964217 -0.1678694487 364 14.5200000000 0.3028204441 0.0705998225 0.3195070624 0.0231250034 0.0494460000 366688140 0 402718720 -0.0304905288 -0.0111193256 -0.1702865213 365 14.5600000000 0.3042553663 0.0712399747 0.3195070624 0.0230956908 0.0241660000 366690060 0 402718720 -0.0286076292 -0.0155239496 -0.1729004383 366 14.6000000000 0.3011333346 0.0718680986 0.3195070624 0.0230672576 0.0241970000 366692928 0 402718720 -0.0319396369 -0.0134385312 -0.1733289212 367 14.6400000000 0.3027163446 0.0724971129 0.3195070624 0.0230362964 0.0242690000 366695292 0 402718720 -0.0327025577 -0.0128416400 -0.1778381467 368 14.6800000000 0.2999515831 0.0731151957 0.3195070624 0.0230070924 0.0246390000 366697392 0 402718720 -0.0348525345 -0.0153150791 -0.1780270636 369 14.7200000000 0.2986410260 0.0737263768 0.3195070624 0.0229787019 0.0239870000 366699676 0 402718720 -0.0361886248 -0.0147861922 -0.1792310476 370 14.7600000000 0.2972072959 0.0743303793 0.3195070624 0.0229560939 0.0241030000 366702564 0 402718720 -0.0408225320 -0.0097923167 -0.1819158792 371 14.8000000000 0.3003797233 0.0749396767 0.3195070624 0.0229257957 0.0233350000 366704512 0 402718720 -0.0372428522 -0.0109927850 -0.1861365139 372 14.8400000000 0.3003933132 0.0755457349 0.3195070624 0.0228969689 0.0239190000 366706968 0 402718720 -0.0364964418 -0.0117304455 -0.1885401905 373 14.8800000000 0.2973517478 0.0761403891 0.3195070624 0.0228704168 0.0238990000 366709056 0 402718720 -0.0387591720 -0.0095094154 -0.1888631880 374 14.9200000000 0.3017106056 0.0767435180 0.3195070624 0.0228442355 0.0240460000 366711328 0 402718720 -0.0370094255 -0.0115996804 -0.1947279572 375 14.9600000000 0.2953829765 0.0773265565 0.3195070624 0.0228311491 0.0238690000 366714196 0 402718720 -0.0453331918 -0.0088330908 -0.1933520138 376 15.0000000000 0.2965445817 0.0779095832 0.3195070624 0.0228010989 0.0235270000 366716532 0 402718720 -0.0445619598 -0.0085736383 -0.1964198947 377 15.0400000000 0.2922800481 0.0784782051 0.3195070624 0.0227758379 0.0230850000 366718820 0 402718720 -0.0512795821 -0.0100567061 -0.1966860592 378 15.0800000000 0.3033646643 0.0790731428 0.3195070624 0.0227605822 0.0230740000 366720892 0 402718720 -0.0383277759 -0.0138247879 -0.2054581493 379 15.1200000000 0.2997553647 0.0796554178 0.3195070624 0.0227361362 0.0340770000 366723316 0 402718720 -0.0428515077 -0.0152056767 -0.2057193220 380 15.1600000000 0.2975419462 0.0802288034 0.3195070624 0.0227067574 0.0476730000 366725800 0 402718720 -0.0450978726 -0.0140931774 -0.2069151700 381 15.2000000000 0.2999768853 0.0808055701 0.3195070624 0.0226794107 0.0226000000 366728424 0 402718720 -0.0427312031 -0.0185496546 -0.2099818736 382 15.2400000000 0.2921591699 0.0813588517 0.3195070624 0.0226565668 0.0229160000 366730588 0 402718720 -0.0504633933 -0.0147694834 -0.2078878433 383 15.2800000000 0.2936870754 0.0819132335 0.3195070624 0.0226276739 0.0231080000 366733088 0 402718720 -0.0506555289 -0.0169720128 -0.2113780230 384 15.3200000000 0.2939085960 0.0824653048 0.3195070624 0.0225984216 0.0223490000 366735328 0 402718720 -0.0526963808 -0.0141866598 -0.2147070169 385 15.3600000000 0.2960319221 0.0830200233 0.3195070624 0.0225693020 0.0229160000 366737032 0 402718720 -0.0513991006 -0.0120821334 -0.2182230949 386 15.4000000000 0.2980571985 0.0835771144 0.3195070624 0.0225403110 0.0227380000 366739720 0 402718720 -0.0518010370 -0.0133654494 -0.2231757045 387 15.4400000000 0.2963128090 0.0841268190 0.3195070624 0.0225142679 0.0221450000 366741948 0 402718720 -0.0540629327 -0.0165388528 -0.2243332416 388 15.4800000000 0.2972875535 0.0846762024 0.3195070624 0.0224861962 0.0220790000 366744744 0 402718720 -0.0551599264 -0.0157473274 -0.2272704244 389 15.5200000000 0.2876595557 0.0851980105 0.3195070624 0.0224711613 0.0221320000 366747308 0 402718720 -0.0649208426 -0.0097882245 -0.2236618102 390 15.5600000000 0.2908371389 0.0857252903 0.3195070624 0.0224438064 0.0222290000 366749136 0 402718720 -0.0644559115 -0.0111706238 -0.2284753323 391 15.6000000000 0.2912020385 0.0862508063 0.3195070624 0.0224165282 0.0221050000 366751512 0 402718720 -0.0624805652 -0.0074766539 -0.2297367752 392 15.6400000000 0.2897312939 0.0867698891 0.3195070624 0.0223970557 0.0224760000 366754196 0 402718720 -0.0669736862 -0.0111388797 -0.2319263518 393 15.6800000000 0.2922536433 0.0872927486 0.3195070624 0.0223745904 0.0254820000 367229384 0 402718720 -0.0657819510 -0.0148698604 -0.2359520048 394 15.7200000000 0.2897586524 0.0878066214 0.3195070624 0.0223509825 0.0754050000 368667764 0 402718720 -0.0686581731 -0.0136220725 -0.2362872213 395 15.7600000000 0.2906890810 0.0883202479 0.3195070624 0.0223287260 0.0562630000 369213201 0 402718720 -0.0675114021 -0.0169675238 -0.2383367121 396 15.8000000000 0.2887859643 0.0888264745 0.3195070624 0.0223053543 0.0331040000 367395932 0 402718720 -0.0708010197 -0.0176147390 -0.2400968820 397 15.8400000000 0.2903002203 0.0893339650 0.3195070624 0.0222821532 0.0330770000 367398048 0 402718720 -0.0707813650 -0.0154610630 -0.2433251888 398 15.8800000000 0.2915721536 0.0898421011 0.3195070624 0.0222597187 0.0327140000 367400380 0 402718720 -0.0709189177 -0.0110348463 -0.2470077872 399 15.9200000000 0.2900384963 0.0903438465 0.3195070624 0.0222361512 0.0325050000 367402760 0 402718720 -0.0733451545 -0.0147316977 -0.2479370534 400 15.9600000000 0.2884653807 0.0908391503 0.3195070624 0.0222092665 0.0331240000 367405096 0 402718720 -0.0768607929 -0.0121045429 -0.2498446554 401 16.0000000000 0.2872954607 0.0913290663 0.3195070624 0.0221891528 0.0330680000 367407828 0 402718720 -0.0770836249 -0.0118390527 -0.2505384982 402 16.0400000000 0.2883630693 0.0918192007 0.3195070624 0.0221650017 0.0325820000 367409808 0 402718720 -0.0792822093 -0.0139861032 -0.2541882396 403 16.0800000000 0.2900277376 0.0923110333 0.3195070624 0.0221424372 0.0326050000 367411972 0 402718720 -0.0778840184 -0.0139117241 -0.2571230233 404 16.1200000000 0.2900677919 0.0928005302 0.3195070624 0.0221240952 0.0319250000 367414272 0 402718720 -0.0776248500 -0.0103867594 -0.2597243488 405 16.1600000000 0.2895446420 0.0932863181 0.3195070624 0.0221079577 0.0311560000 367416756 0 402718720 -0.0818276778 -0.0098413285 -0.2623343170 406 16.2000000000 0.2908528149 0.0937729351 0.3195070624 0.0220826713 0.0309270000 367419304 0 402718720 -0.0809256285 -0.0088510625 -0.2655060887 407 16.2400000000 0.2931265831 0.0942627475 0.3195070624 0.0220649060 0.0318760000 367421496 0 402718720 -0.0784184635 -0.0075195264 -0.2682774961 408 16.2800000000 0.2885314226 0.0947388962 0.3195070624 0.0220497663 0.0318300000 367423616 0 402718720 -0.0839410573 -0.0082659591 -0.2675919235 409 16.3200000000 0.2888670862 0.0952135373 0.3195070624 0.0220237940 0.0314020000 367426100 0 402718720 -0.0848880932 -0.0068053287 -0.2702563107 410 16.3600000000 0.2874798179 0.0956824794 0.3195070624 0.0219986580 0.0310420000 367428496 0 402718720 -0.0863585472 -0.0068332702 -0.2713167965 411 16.3999999990 0.2897041738 0.0961545517 0.3195070624 0.0219794893 0.0303900000 367430720 0 402718720 -0.0855149254 -0.0081475526 -0.2751524746 412 16.4400000000 0.2870154977 0.0966178064 0.3195070624 0.0219629615 0.0310410000 367433176 0 402718720 -0.0879475772 -0.0085792989 -0.2751685381 413 16.4800000000 0.2848134935 0.0970734860 0.3195070624 0.0219410085 0.0307750000 367435660 0 402718720 -0.0895102322 -0.0035393089 -0.2754405439 414 16.5200000000 0.2899940014 0.0975394776 0.3195070624 0.0219168319 0.0307140000 367437748 0 402718720 -0.0871500969 -0.0070455186 -0.2819176316 415 16.5599999990 0.2877872884 0.0979979061 0.3195070624 0.0218908215 0.0307030000 367440096 0 402718720 -0.0885462314 -0.0035302602 -0.2826550901 416 16.6000000000 0.2885257602 0.0984559057 0.3195070624 0.0218677034 0.0299220000 367442488 0 402718720 -0.0878944173 -0.0052289180 -0.2850511372 417 16.6400000000 0.2866355479 0.0989071758 0.3195070624 0.0218470642 0.0266560000 367445020 0 402718720 -0.0904489532 -0.0067383274 -0.2860450447 418 16.6800000000 0.2842820883 0.0993506565 0.3195070624 0.0218253348 0.0254030000 367447552 0 402718720 -0.0928796530 -0.0029686987 -0.2867127359 419 16.7199999990 0.2879036367 0.0998006636 0.3195070624 0.0218054208 0.0257230000 367449428 0 402718720 -0.0918355882 -0.0019859932 -0.2927639484 420 16.7600000000 0.2878801227 0.1002484718 0.3195070624 0.0217949756 0.0256940000 367451544 0 402718720 -0.0920767635 -0.0033370629 -0.2952400744 421 16.8000000000 0.2858849168 0.1006894135 0.3195070624 0.0217763755 0.0255390000 367453860 0 402718720 -0.0964674056 -0.0061251782 -0.2973190546 422 16.8400000000 0.2839653790 0.1011237167 0.3195070624 0.0217540392 0.0255300000 367456040 0 402718720 -0.0946444720 -0.0021737181 -0.2976769805 423 16.8799999990 0.2819874287 0.1015512905 0.3195070624 0.0217317688 0.0251660000 367459276 0 402718720 -0.0966780931 -0.0009940267 -0.2986500263 424 16.9200000000 0.2863407731 0.1019871148 0.3195070624 0.0217076112 0.0250810000 367461624 0 402718720 -0.0938517749 -0.0005539395 -0.3050582707 425 16.9600000000 0.2830536067 0.1024131536 0.3195070624 0.0216955843 0.0368480000 367463188 0 402718720 -0.0992550477 0.0008799434 -0.3070323169 426 17.0000000000 0.2828948498 0.1028368195 0.3195070624 0.0216742209 0.0256110000 367465812 0 402718720 -0.1000419259 0.0014621094 -0.3102110624 427 17.0400000000 0.2854883969 0.1032645750 0.3195070624 0.0216496795 0.0256590000 367468420 0 402718720 -0.0967776254 -0.0008191951 -0.3143577874 428 17.0800000000 0.2855844498 0.1036905560 0.3195070624 0.0216246014 0.0255800000 367470676 0 402718720 -0.0953281373 0.0013690405 -0.3180057704 429 17.1200000000 0.2821697593 0.1041065914 0.3195070624 0.0216015845 0.0257280000 367472532 0 402718720 -0.0979919061 0.0018316321 -0.3188042641 430 17.1600000000 0.2875448167 0.1045331920 0.3195070624 0.0215788010 0.0257480000 367475276 0 402718720 -0.0937814564 0.0026314855 -0.3257057965 431 17.2000000000 0.2848591506 0.1049515817 0.3195070624 0.0215549716 0.0259750000 367477700 0 402718720 -0.0972158089 0.0063067935 -0.3280701041 432 17.2400000000 0.2804496288 0.1053578271 0.3195070624 0.0215395913 0.0255820000 367479892 0 402718720 -0.1000108123 0.0038813055 -0.3272829652 433 17.2800000000 0.2812206447 0.1057639768 0.3195070624 0.0215168625 0.0255940000 367482132 0 402718720 -0.1010932401 0.0060045607 -0.3318957984 434 17.3200000000 0.2787285149 0.1061625126 0.3195070624 0.0214978582 0.0256980000 367484356 0 402718720 -0.1017518640 0.0034941733 -0.3325182199 435 17.3600000000 0.2813434899 0.1065652275 0.3195070624 0.0214742510 0.0256120000 367487012 0 402718720 -0.1010839492 0.0026509501 -0.3383097947 436 17.4000000000 0.2805691957 0.1069643192 0.3195070624 0.0214570663 0.0259500000 367489344 0 402718720 -0.1025478169 0.0048732795 -0.3416677117 437 17.4400000000 0.2799747884 0.1073602242 0.3195070624 0.0214437043 0.0264460000 367491620 0 402718720 -0.1018203199 0.0069151148 -0.3439538479 438 17.4800000000 0.2795842290 0.1077534297 0.3195070624 0.0214249491 0.0258380000 367494152 0 402718720 -0.1019673198 0.0044232383 -0.3470862210 439 17.5200000000 0.2803376019 0.1081465599 0.3195070624 0.0214044514 0.0263560000 367496176 0 402718720 -0.0983161181 0.0045529380 -0.3504235744 440 17.5600000000 0.2794691324 0.1085359294 0.3195070624 0.0213876749 0.0364000000 367498692 0 402718720 -0.1015965343 0.0042435154 -0.3536162376 441 17.6000000000 0.2752737999 0.1089140198 0.3195070624 0.0213712001 0.0260100000 367500700 0 402718720 -0.1042558998 0.0087887347 -0.3532637954 442 17.6400000000 0.2770670950 0.1092944566 0.3195070624 0.0213580560 0.0259780000 367503492 0 402718720 -0.1010745615 0.0075283274 -0.3567413688 443 17.6800000000 0.2811392844 0.1096823682 0.3195070624 0.0213419614 0.0370020000 367505612 0 402718720 -0.0982212573 0.0029274523 -0.3622065187 444 17.7200000000 0.2785741687 0.1100627551 0.3195070624 0.0213201007 0.0256210000 367507852 0 402718720 -0.1011740714 0.0053511634 -0.3634318709 445 17.7600000000 0.2802914679 0.1104452915 0.3195070624 0.0212962169 0.0262190000 367510368 0 402718720 -0.1008499861 0.0059870705 -0.3678981662 446 17.8000000000 0.2792710960 0.1108238247 0.3195070624 0.0212728015 0.0262870000 367512868 0 402718720 -0.1004452631 0.0074109808 -0.3694738150 447 17.8400000000 0.2792282403 0.1112005684 0.3195070624 0.0212517909 0.0373790000 367514816 0 402718720 -0.1020268947 0.0092874840 -0.3725428879 448 17.8800000000 0.2767159641 0.1115700224 0.3195070624 0.0212299304 0.0258090000 367516932 0 402718720 -0.1047235131 0.0086422190 -0.3734694719 449 17.9200000000 0.2781705856 0.1119410704 0.3195070624 0.0212073574 0.0369530000 367519984 0 402718720 -0.1040163562 0.0074406490 -0.3771604598 450 17.9600000000 0.2767148018 0.1123072343 0.3195070624 0.0211837670 0.0256970000 367522148 0 402718720 -0.1050637737 0.0091871545 -0.3810096085 451 18.0000000000 0.2791251540 0.1126771188 0.3195070624 0.0211703945 0.0256010000 367524220 0 402718720 -0.1020158976 0.0063651726 -0.3848807812 452 18.0400000000 0.2831535935 0.1130542791 0.3195070624 0.0211513455 0.0260060000 367527312 0 402718720 -0.0987440795 0.0077243373 -0.3901273608 453 18.0800000000 0.2758383453 0.1134136259 0.3195070624 0.0211468601 0.0277820000 367529124 0 402718720 -0.1059933975 0.0046859980 -0.3871174753 454 18.1200000000 0.2771409452 0.1137742587 0.3195070624 0.0211251870 0.0298400000 367531700 0 402718720 -0.1050068066 0.0066531226 -0.3909040391 455 18.1600000000 0.2745428979 0.1141275964 0.3195070624 0.0211022973 0.0300390000 367533708 0 402718720 -0.1070842892 0.0088680014 -0.3917320371 456 18.2000000000 0.2740530372 0.1144783101 0.3195070624 0.0210804386 0.0298850000 367536024 0 402718720 -0.1113910899 0.0092593282 -0.3952533603 457 18.2400000000 0.2748087645 0.1148291426 0.3195070624 0.0210644644 0.0300880000 367538280 0 402718720 -0.1102957129 0.0079830810 -0.3979196846 458 18.2800000000 0.2740551233 0.1151767976 0.3195070624 0.0210477438 0.0299040000 367540704 0 402718720 -0.1121501923 0.0058729872 -0.4000996649 459 18.3200000000 0.2749093473 0.1155247988 0.3195070624 0.0210343036 0.0302930000 367542652 0 402718720 -0.1108307913 0.0091357529 -0.4030206501 460 18.3600000000 0.2721106410 0.1158652028 0.3195070624 0.0210177472 0.0304690000 367545612 0 402718720 -0.1129438207 0.0149141848 -0.4039031863 461 18.4000000000 0.2736623883 0.1162074960 0.3195070624 0.0210015562 0.0300260000 367547716 0 402718720 -0.1119611040 0.0108890086 -0.4075593948 462 18.4400000000 0.2722752392 0.1165453050 0.3195070624 0.0209943163 0.0299470000 367550156 0 402718720 -0.1150995046 0.0106820613 -0.4095762074 463 18.4800000000 0.2730575502 0.1168833444 0.3195070624 0.0209806443 0.0265420000 367552504 0 402718720 -0.1148027778 0.0089076459 -0.4129585028 464 18.5200000000 0.2752057612 0.1172245565 0.3195070624 0.0209618591 0.0258850000 367554992 0 402718720 -0.1153192073 0.0074426681 -0.4176184833 465 18.5600000000 0.2752520740 0.1175644006 0.3195070624 0.0209418432 0.0378260000 367557340 0 402718720 -0.1149076596 0.0128912255 -0.4206303656 466 18.6000000000 0.2686642110 0.1178886491 0.3195070624 0.0209251885 0.0262390000 367559596 0 402718720 -0.1223286688 0.0144121423 -0.4189968407 467 18.6400000000 0.2731799483 0.1182211787 0.3195070624 0.0209049999 0.0262740000 367561436 0 402718720 -0.1191257685 0.0120453835 -0.4252319038 468 18.6800000000 0.2744095027 0.1185549144 0.3195070624 0.0208828717 0.0345770000 367563736 0 402718720 -0.1222805604 0.0128760487 -0.4303438067 469 18.7200000000 0.2748050392 0.1188880703 0.3195070624 0.0208655520 0.0262100000 367566512 0 402718720 -0.1215007007 0.0132950470 -0.4331080019 470 18.7600000000 0.2730635703 0.1192161033 0.3195070624 0.0208441310 0.0258920000 367568552 0 402718720 -0.1241058856 0.0159428269 -0.4350206852 471 18.8000000000 0.2708058655 0.1195379499 0.3195070624 0.0208425430 0.0264130000 367570856 0 402718720 -0.1282777488 0.0171657652 -0.4366116524 472 18.8400000000 0.2704418898 0.1198576617 0.3195070624 0.0208734181 0.0262420000 367573172 0 402718720 -0.1273424029 0.0167309716 -0.4385976493 473 18.8800000000 0.2734145820 0.1201823063 0.3195070624 0.0208832159 0.0379120000 367575644 0 402718720 -0.1269048750 0.0157483518 -0.4442384839 474 18.9200000000 0.2691618502 0.1204966092 0.3195070624 0.0208695742 0.0269910000 367578440 0 402718720 -0.1334389001 0.0161455646 -0.4440629482 475 18.9600000000 0.2702974677 0.1208119794 0.3195070624 0.0208503862 0.0494230000 367580464 0 402718720 -0.1321250796 0.0176813379 -0.4472141862 476 19.0000000000 0.2711104751 0.1211277325 0.3195070624 0.0208383462 0.0265210000 367583012 0 402718720 -0.1340142488 0.0203119889 -0.4512644112 477 19.0400000000 0.2707594633 0.1214414259 0.3195070624 0.0208228685 0.0262950000 367585532 0 402718720 -0.1345528662 0.0203002766 -0.4537469745 478 19.0800000000 0.2688823938 0.1217498798 0.3195070624 0.0208020644 0.0264330000 367587864 0 402718720 -0.1366607845 0.0256555378 -0.4549145997 479 19.1200000000 0.2673836052 0.1220539168 0.3195070624 0.0207892801 0.0265720000 367590164 0 402718720 -0.1425545812 0.0234980285 -0.4571202397 480 19.1600000000 0.2639413774 0.1223495157 0.3195070624 0.0207729233 0.0265820000 367592864 0 402718720 -0.1450839490 0.0311039910 -0.4570002854 481 19.2000000000 0.2661907375 0.1226485619 0.3195070624 0.0207623034 0.0368040000 367594400 0 402718720 -0.1424055099 0.0252896845 -0.4602887332 482 19.2400000000 0.2702300847 0.1229547476 0.3195070624 0.0207424717 0.0262890000 367597024 0 402718720 -0.1392986774 0.0283553004 -0.4658745527 483 19.2800000000 0.2720711827 0.1232634773 0.3195070624 0.0207385180 0.0267370000 367599756 0 402718720 -0.1411320865 0.0242324471 -0.4700811803 484 19.3200000000 0.2683579326 0.1235632592 0.3195070624 0.0207225592 0.0259370000 367601780 0 402718720 -0.1427500546 0.0342446119 -0.4690308273 485 19.3600000000 0.2672583461 0.1238595378 0.3195070624 0.0207126533 0.0257560000 367603960 0 402718720 -0.1455952823 0.0253438503 -0.4700277448 486 19.4000000000 0.2654706240 0.1241509186 0.3195070624 0.0206953761 0.0262070000 367606600 0 402718720 -0.1463386118 0.0346174091 -0.4707541168 487 19.4400000000 0.2653453350 0.1244408455 0.3195070624 0.0206799562 0.0391320000 367608856 0 402718720 -0.1474374235 0.0307313353 -0.4726221263 488 19.4800000000 0.2670154572 0.1247330066 0.3195070624 0.0206616446 0.0382670000 367611128 0 402718720 -0.1463450789 0.0304874927 -0.4760396183 489 19.5200000000 0.2651488483 0.1250201556 0.3195070624 0.0206484451 0.0258060000 367613264 0 402718720 -0.1522983015 0.0298730433 -0.4776730537 490 19.5600000000 0.2645279169 0.1253048653 0.3195070624 0.0206280459 0.0257950000 367616056 0 402718720 -0.1540341973 0.0336539447 -0.4796456397 491 19.6000000000 0.2693881989 0.1255983140 0.3195070624 0.0206153365 0.0258120000 367617960 0 402718720 -0.1473935544 0.0269701630 -0.4840047956 492 19.6400000000 0.2691533267 0.1258900925 0.3195070624 0.0205943397 0.0260570000 367620556 0 402718720 -0.1480218470 0.0291361660 -0.4861302674 493 19.6800000000 0.2690123022 0.1261804013 0.3195070624 0.0205770776 0.0310030000 368282852 0 402718720 -0.1476265788 0.0266251415 -0.4875137508 494 19.7200000000 0.2703016400 0.1264721447 0.3195070624 0.0205570643 0.0886680000 369535680 0 402718720 -0.1450023949 0.0275854170 -0.4901450872 495 19.7600000000 0.2715382278 0.1267652075 0.3195070624 0.0205457449 0.0447070000 370368769 0 402718720 -0.1613330841 0.0257443786 -0.4978151321 496 19.8000000000 0.2728640735 0.1270597616 0.3195070624 0.0205275551 0.0653440000 368303768 0 402718720 -0.1597613394 0.0288757384 -0.5010680556 497 19.8400000000 0.2711925507 0.1273497672 0.3195070624 0.0205104627 0.0310300000 368306468 0 402718720 -0.1600264460 0.0280092508 -0.5012342334 498 19.8800000000 0.2712427974 0.1276387091 0.3195070624 0.0204918245 0.0306070000 368308772 0 402718720 -0.1606019437 0.0255442709 -0.5030337572 499 19.9200000000 0.2740179896 0.1279320543 0.3195070624 0.0204720711 0.0313190000 368311704 0 402718720 -0.1585672945 0.0236384124 -0.5075331926 500 19.9600000000 0.2726456523 0.1282214815 0.3195070624 0.0204520412 0.0312240000 368313852 0 402718720 -0.1593776941 0.0266958326 -0.5090423226 501 20.0000000000 0.2721880674 0.1285088400 0.3195070624 0.0204427188 0.0302690000 368315648 0 402718720 -0.1594604105 0.0253104866 -0.5108642578 502 20.0400000000 0.2727095485 0.1287960924 0.3195070624 0.0204391199 0.0302780000 368318044 0 402718720 -0.1593593359 0.0218597054 -0.5137434602 503 20.0800000000 0.2718863487 0.1290805660 0.3195070624 0.0204191376 0.0304330000 368320744 0 402718720 -0.1621817499 0.0231876820 -0.5165736675 504 20.1200000000 0.2734605074 0.1293670342 0.3195070624 0.0203993322 0.0306960000 368323060 0 402718720 -0.1592159569 0.0252761990 -0.5200020075 505 20.1600000000 0.2725249827 0.1296505153 0.3195070624 0.0203794175 0.0305020000 368325088 0 402718720 -0.1622581929 0.0251253247 -0.5224778652 506 20.2000000000 0.2721881270 0.1299322102 0.3195070624 0.0203594722 0.0302890000 368327820 0 402718720 -0.1618008018 0.0282493532 -0.5245392323 507 20.2400000000 0.2726404071 0.1302136859 0.3195070624 0.0203429048 0.0298130000 368329860 0 402718720 -0.1615792811 0.0246377438 -0.5271700621 508 20.2800000000 0.2714242935 0.1304916595 0.3195070624 0.0203233280 0.0387020000 368332380 0 402718720 -0.1625099033 0.0283152014 -0.5292382836 509 20.3200000000 0.2718959749 0.1307694676 0.3195070624 0.0203077700 0.0289830000 368334824 0 402718720 -0.1608319283 0.0257644653 -0.5315016508 510 20.3600000000 0.2707403004 0.1310439202 0.3195070624 0.0202935494 0.0289850000 368337280 0 402718720 -0.1624487936 0.0265116245 -0.5331083536 511 20.4000000000 0.2693479359 0.1313145739 0.3195070624 0.0202740720 0.0292530000 368339708 0 402718720 -0.1627852768 0.0288634896 -0.5345227718 512 20.4400000000 0.2704665959 0.1315863552 0.3195070624 0.0202552204 0.0289860000 368342136 0 402718720 -0.1619318426 0.0269138515 -0.5381771326 513 20.4800000000 0.2713147998 0.1318587303 0.3195070624 0.0202358379 0.0288100000 368344116 0 402718720 -0.1578099877 0.0305910707 -0.5417108536 514 20.5200000000 0.2717455924 0.1321308837 0.3195070624 0.0202201891 0.0284730000 368449200 0 402718720 -0.1599123478 0.0284255892 -0.5457939506 515 20.5600000000 0.2706889510 0.1323999285 0.3195070624 0.0202015552 0.0530200000 368451624 0 402718720 -0.1585421562 0.0307489634 -0.5476955175 516 20.6000000000 0.2708840370 0.1326683086 0.3195070624 0.0201850590 0.0276520000 368453956 0 402718720 -0.1561005861 0.0301251560 -0.5505319238 517 20.6400000000 0.2705897391 0.1329350812 0.3195070624 0.0201664949 0.0275350000 368456380 0 402718720 -0.1552636325 0.0310115367 -0.5529948473 518 20.6800000000 0.2710745633 0.1332017597 0.3195070624 0.0201491061 0.0278780000 368458880 0 402718720 -0.1523554623 0.0314497948 -0.5557373762 519 20.7200000000 0.2780888975 0.1334809257 0.3195070624 0.0201316713 0.0277060000 368460812 0 402718720 -0.1463044435 0.0300677717 -0.5643260479 520 20.7600000000 0.2718556523 0.1337470309 0.3195070624 0.0201196889 0.0276480000 368462776 0 402718720 -0.1545314789 0.0302267820 -0.5624897480 521 20.8000000000 0.2691636980 0.1340069477 0.3195070624 0.0201009778 0.0277980000 368465752 0 402718720 -0.1534751356 0.0335497111 -0.5620411038 522 20.8400000000 0.2706677616 0.1342687501 0.3195070624 0.0200828235 0.0278210000 368467624 0 402718720 -0.1504382342 0.0335555077 -0.5652663112 523 20.8800000000 0.2695385516 0.1345273921 0.3195070624 0.0200659459 0.0277620000 368470296 0 402718720 -0.1501182169 0.0403417051 -0.5668601990 524 20.9200000000 0.2710624337 0.1347879552 0.3195070624 0.0200493086 0.0387850000 368472736 0 402718720 -0.1487106532 0.0344094634 -0.5702574849 525 20.9600000000 0.2715631127 0.1350484793 0.3195070624 0.0200317297 0.0271800000 368474932 0 402718720 -0.1479554176 0.0338909328 -0.5729776621 526 21.0000000000 0.2709645927 0.1353068750 0.3195070624 0.0200171634 0.0271180000 368477268 0 402718720 -0.1467582434 0.0380687565 -0.5746380091 527 21.0400000000 0.2716493607 0.1355655893 0.3195070624 0.0199995557 0.0269880000 368479696 0 402718720 -0.1471860409 0.0343604088 -0.5771774650 528 21.0800000000 0.2734993398 0.1358268275 0.3195070624 0.0199879684 0.0267710000 368482212 0 402718720 -0.1460231543 0.0357835144 -0.5809287429 529 21.1200000000 0.2680779696 0.1360768297 0.3195070624 0.0199713370 0.0505530000 368484316 0 402718720 -0.1527312249 0.0329450220 -0.5787118077 530 21.1600000000 0.2723352313 0.1363339210 0.3195070624 0.0199698325 0.0258410000 368486724 0 402718720 -0.1458369046 0.0369648784 -0.5836674571 531 21.2000000000 0.2689491510 0.1365836672 0.3195070624 0.0199582840 0.0257970000 368488856 0 402718720 -0.1477440000 0.0394097567 -0.5827246904 532 21.2400000000 0.2712450624 0.1368367901 0.3195070624 0.0199474018 0.0310530000 369182036 0 402718720 -0.1445456445 0.0339789391 -0.5859016180 533 21.2800000000 0.2710760534 0.1370886461 0.3195070624 0.0199375133 0.0923130000 369277404 0 402718720 -0.1445607245 0.0342082679 -0.5874717236 534 21.3200000000 0.2719298303 0.1373411577 0.3195070624 0.0199200896 0.0708270000 372216440 0 402718720 -0.1442986131 0.0326622277 -0.5897824168 535 21.3600000000 0.2782756984 0.1376045868 0.3195070624 0.0199144240 0.0406700000 370908833 0 402718720 -0.1345643997 0.0314222872 -0.5953477621 536 21.4000000000 0.2781127095 0.1378667288 0.3195070624 0.0198987226 0.0323430000 369209088 0 402718720 -0.1347839981 0.0303321034 -0.5967793465 537 21.4400000000 0.2785064280 0.1381286277 0.3195070624 0.0198858454 0.0329690000 369211544 0 402718720 -0.1337772459 0.0319835693 -0.5983437300 538 21.4800000000 0.2800326645 0.1383923898 0.3195070624 0.0198789638 0.0325300000 369213820 0 402718720 -0.1341031790 0.0311661065 -0.6012771130 539 21.5200000000 0.2800180614 0.1386551462 0.3195070624 0.0198717037 0.0312480000 369215984 0 402718720 -0.1337577403 0.0286846906 -0.6024240255 540 21.5600000000 0.2796989977 0.1389163385 0.3195070624 0.0198634876 0.0319700000 369218240 0 402718720 -0.1344372630 0.0295610130 -0.6036362648 541 21.6000000000 0.2793375850 0.1391758972 0.3195070624 0.0198502817 0.0319930000 369221420 0 402718720 -0.1347239017 0.0280441493 -0.6044802666 542 21.6400000000 0.2784800529 0.1394329159 0.3195070624 0.0198354126 0.0526020000 369223340 0 402718720 -0.1350935996 0.0264825821 -0.6048419476 543 21.6800000000 0.2781437039 0.1396883686 0.3195070624 0.0198238469 0.0297720000 369225800 0 402718720 -0.1355282664 0.0271034539 -0.6056919098 544 21.7200000000 0.2789611816 0.1399443848 0.3195070624 0.0198085212 0.0298050000 369228472 0 402718720 -0.1365839243 0.0263216943 -0.6079278588 545 21.7600000000 0.2791028917 0.1401997215 0.3195070624 0.0197910889 0.0296070000 369230544 0 402718720 -0.1358732581 0.0232869983 -0.6087261438 546 21.8000000000 0.2774340808 0.1404510664 0.3195070624 0.0197812303 0.0301440000 369233096 0 402718720 -0.1374336183 0.0243270844 -0.6084200144 547 21.8400000000 0.2794223726 0.1407051273 0.3195070624 0.0197813026 0.0285530000 369235480 0 402718720 -0.1357835978 0.0214982480 -0.6109995246 548 21.8800000000 0.2782550454 0.1409561308 0.3195070624 0.0197767336 0.0405790000 369238020 0 402718720 -0.1368172467 0.0229307562 -0.6112822890 549 21.9200000000 0.2781327963 0.1412059973 0.3195070624 0.0197648519 0.0279450000 369240560 0 402718720 -0.1364299357 0.0170616359 -0.6117691994 550 21.9600000000 0.2775631845 0.1414539194 0.3195070624 0.0197623681 0.0279660000 369242884 0 402718720 -0.1365285516 0.0208990276 -0.6123616695 551 22.0000000000 0.2765600979 0.1416991212 0.3195070624 0.0197462216 0.0278990000 369245004 0 402718720 -0.1375791132 0.0206466913 -0.6125566959 552 22.0400000000 0.2764218450 0.1419431841 0.3195070624 0.0197315863 0.0279630000 369247660 0 402718720 -0.1398342401 0.0213873386 -0.6138114929 553 22.0800000000 0.2772186100 0.1421878051 0.3195070624 0.0197166768 0.0272490000 369250088 0 402718720 -0.1404533535 0.0171665400 -0.6153692603 554 22.1200000000 0.2785241008 0.1424338995 0.3195070624 0.0197077757 0.0397190000 369252440 0 402718720 -0.1390561014 0.0155330151 -0.6169916987 555 22.1600000000 0.2779213786 0.1426780211 0.3195070624 0.0196954670 0.0380410000 369254820 0 402718720 -0.1401889622 0.0168915540 -0.6176769733 556 22.2000000000 0.2754325569 0.1429167883 0.3195070624 0.0196844733 0.0259350000 369256840 0 402718720 -0.1438358575 0.0242480040 -0.6173019409 557 22.2400000000 0.2776136696 0.1431586139 0.3195070624 0.0196703920 0.0321470000 370138848 0 402718720 -0.1426762640 0.0161217451 -0.6196670532 558 22.2800000000 0.2771058977 0.1433986628 0.3195070624 0.0196555977 0.1168180000 370110944 0 402718720 -0.1432223469 0.0151662081 -0.6199222803 559 22.3200000000 0.2779396474 0.1436393443 0.3195070624 0.0196462878 0.0891910000 373722096 0 402718720 -0.1436030567 0.0158910453 -0.6217670441 560 22.3600000000 0.2794600725 0.1438818814 0.3195070624 0.0196322125 0.0713200000 373488311 0 402718720 -0.1449676156 0.0083219707 -0.6238183975 561 22.4000000000 0.2787847519 0.1441223499 0.3195070624 0.0196174720 0.0362720000 370121760 0 402718720 -0.1469598860 0.0080953836 -0.6244089603 562 22.4400000000 0.2783466578 0.1443611832 0.3195070624 0.0196026799 0.0595660000 370123824 0 402718720 -0.1459261477 0.0075580031 -0.6242932081 563 22.4800000000 0.2787730098 0.1445999254 0.3195070624 0.0195885286 0.0345830000 370125040 0 402718720 -0.1463983655 0.0072338581 -0.6255180836 564 22.5200000000 0.2793585360 0.1448388591 0.3195070624 0.0195760050 0.0343290000 370127500 0 402718720 -0.1453233808 0.0065761060 -0.6263338923 565 22.5600000000 0.2781604230 0.1450748264 0.3195070624 0.0195649436 0.0343540000 370129268 0 402718720 -0.1472352892 0.0072188377 -0.6262802482 566 22.6000000000 0.2779294848 0.1453095520 0.3195070624 0.0195518967 0.0341610000 370133420 0 402718720 -0.1482655108 0.0070218444 -0.6268344522 567 22.6400000000 0.2788547277 0.1455450814 0.3195070624 0.0195375441 0.0329410000 370132980 0 402718720 -0.1460995674 0.0047550350 -0.6279271245 568 22.6800000000 0.2777806818 0.1457778905 0.3195070624 0.0195243598 0.0430560000 370136268 0 402718720 -0.1475436240 0.0051099509 -0.6275092363 569 22.7200000000 0.2769926488 0.1460084964 0.3195070624 0.0195168050 0.0327650000 370137888 0 402718720 -0.1472082585 0.0066825077 -0.6273183227 570 22.7600000000 0.2775799930 0.1462393236 0.3195070624 0.0195054858 0.0315120000 370141008 0 402718720 -0.1488645673 0.0062712580 -0.6288095713 571 22.8000000000 0.2769812942 0.1464682938 0.3195070624 0.0194957929 0.0305440000 370140484 0 402718720 -0.1475630552 0.0059965253 -0.6286147237 572 22.8400000000 0.2763772309 0.1466954073 0.3195070624 0.0194864419 0.0302390000 370143312 0 402718720 -0.1484168172 0.0050785691 -0.6288149357 573 22.8800000000 0.2779806554 0.1469245264 0.3195070624 0.0194722763 0.0299370000 370143688 0 402718720 -0.1497724503 0.0002768263 -0.6312155724 574 22.9200000000 0.2796076536 0.1471556817 0.3195070624 0.0194614228 0.0289310000 370145072 0 402718720 -0.1490188092 0.0001251996 -0.6338444352 575 22.9600000000 0.2775456607 0.1473824469 0.3195070624 0.0194538000 0.0284520000 370148468 0 402718720 -0.1486224830 0.0026525557 -0.6327333450 576 23.0000000000 0.2766939402 0.1476069460 0.3195070624 0.0194457322 0.0279150000 370149272 0 402718720 -0.1499806046 0.0037505180 -0.6333096623 577 23.0400000000 0.2785118222 0.1478338176 0.3195070624 0.0194366306 0.0271970000 370150288 0 402718720 -0.1502902359 0.0009789243 -0.6360316277 578 23.0800000000 0.2770322859 0.1480573443 0.3195070624 0.0194270808 0.0270200000 370153624 0 402718720 -0.1497366279 -0.0006221756 -0.6351585984 579 23.1200000000 0.2765079737 0.1482791934 0.3195070624 0.0194201567 0.0272860000 370156404 0 402718720 -0.1531824470 0.0015850514 -0.6365230680 580 23.1600000000 0.2763418853 0.1484999912 0.3195070624 0.0194121649 0.0266420000 370158776 0 402718720 -0.1508661062 0.0010288879 -0.6365477443 581 23.2000000000 0.2749150097 0.1487175729 0.3195070624 0.0194013623 0.0352880000 370159704 0 402718720 -0.1473617107 -0.0010634884 -0.6346337199 582 23.2400000000 0.2765654624 0.1489372429 0.3195070624 0.0193907599 0.0263850000 370162252 0 402718720 -0.1511463821 -0.0028496012 -0.6378938556 583 23.2800000000 0.2761944532 0.1491555228 0.3195070624 0.0193859114 0.0250760000 370164504 0 402718720 -0.1469303668 -0.0007727370 -0.6374811530 584 23.3200000000 0.2771112621 0.1493746251 0.3195070624 0.0193740652 0.0251390000 370166060 0 402718720 -0.1500526667 -0.0021750703 -0.6397199631 585 23.3600000000 0.2765081525 0.1495919474 0.3195070624 0.0193655171 0.0307160000 370877180 0 402718720 -0.1463959515 -0.0061071813 -0.6382234097 586 23.4000000000 0.2779836059 0.1498110458 0.3195070624 0.0193625457 0.0870860000 370837996 0 402718720 -0.1455352455 -0.0071339980 -0.6400124431 587 23.4400000000 0.2768871486 0.1500275298 0.3195070624 0.0193551078 0.0721300000 374793428 0 402718720 -0.1493154168 -0.0045723021 -0.6405193806 588 23.4800000000 0.2759581804 0.1502416975 0.3195070624 0.0193459548 0.0637460000 374685259 0 402718720 -0.1417089701 -0.0092514828 -0.6373338699 589 23.5200000000 0.2760098577 0.1504552258 0.3195070624 0.0193377935 0.0298530000 370843728 0 402718720 -0.1432730258 -0.0093317404 -0.6382388473 590 23.5600000000 0.2766897380 0.1506691826 0.3195070624 0.0193299058 0.0296930000 370845860 0 402718720 -0.1437448710 -0.0079335719 -0.6395604610 591 23.6000000000 0.2765117288 0.1508821142 0.3195070624 0.0193173094 0.0306650000 370849076 0 402718720 -0.1414723247 -0.0105065778 -0.6386598349 592 23.6400000000 0.2771165669 0.1510953480 0.3195070624 0.0193107932 0.0295230000 370851012 0 402718720 -0.1436892897 -0.0112988427 -0.6401330829 593 23.6800000000 0.2768716514 0.1513074497 0.3195070624 0.0193024796 0.0290680000 370852048 0 402718720 -0.1434087306 -0.0111577809 -0.6399618387 594 23.7200000000 0.2769754529 0.1515190120 0.3195070624 0.0192890169 0.0397840000 370854204 0 402718720 -0.1430466175 -0.0132689998 -0.6403301954 595 23.7600000000 0.2764055431 0.1517289054 0.3195070624 0.0192762579 0.0290800000 370859384 0 402718720 -0.1420497000 -0.0157062486 -0.6394286156 596 23.8000000000 0.2754523456 0.1519364950 0.3195070624 0.0192708047 0.0396500000 370859944 0 402718720 -0.1424549520 -0.0122058988 -0.6389776468 597 23.8400000000 0.2764943838 0.1521451347 0.3195070624 0.0192591542 0.0282080000 370862988 0 402718720 -0.1450293213 -0.0128841437 -0.6405827999 598 23.8800000000 0.2755681872 0.1523515278 0.3195070624 0.0192461259 0.0270730000 370861092 0 402718720 -0.1432578117 -0.0125821903 -0.6393635273 599 23.9200000000 0.2761792541 0.1525582518 0.3195070624 0.0192315822 0.0387850000 370866416 0 402718720 -0.1426231414 -0.0138041042 -0.6397511363 600 23.9600000000 0.2760215402 0.1527640240 0.3195070624 0.0192168451 0.0264550000 370867156 0 402718720 -0.1415935755 -0.0149740353 -0.6394677162 601 24.0000000000 0.2765886188 0.1529700549 0.3195070624 0.0192030660 0.0257260000 370869200 0 402718720 -0.1424794793 -0.0173212737 -0.6401188374 602 24.0400000000 0.2761049271 0.1531745979 0.3195070624 0.0191899479 0.0258100000 370872136 0 402718720 -0.1434297115 -0.0204550326 -0.6396191120 603 24.0800000000 0.2742726207 0.1533754238 0.3195070624 0.0191838462 0.0258770000 370875656 0 402718720 -0.1419291347 -0.0185894109 -0.6373376846 604 24.1200000000 0.2764324248 0.1535791606 0.3195070624 0.0191750264 0.0253890000 370876864 0 402718720 -0.1411587000 -0.0204502977 -0.6390396953 605 24.1600000000 0.2735268474 0.1537774212 0.3195070624 0.0191631387 0.0255760000 370881968 0 402718720 -0.1428133547 -0.0173258372 -0.6367305517 606 24.2000000000 0.2759038210 0.1539789499 0.3195070624 0.0191494115 0.0249720000 370882052 0 402718720 -0.1447678208 -0.0172144994 -0.6397742033 607 24.2400000000 0.2744173110 0.1541773657 0.3195070624 0.0191343114 0.0251370000 370884288 0 402718720 -0.1414058208 -0.0218942985 -0.6370033026 608 24.2800000000 0.2768118978 0.1543790672 0.3195070624 0.0191249643 0.0257290000 370888552 0 402718720 -0.1414715648 -0.0149201863 -0.6401397586 609 24.3200000000 0.2748634219 0.1545769069 0.3195070624 0.0191098373 0.0282900000 370890720 0 402718720 -0.1417618692 -0.0206245482 -0.6377092600 610 24.3600000000 0.2773798108 0.1547782231 0.3195070624 0.0191044935 0.0284000000 370892340 0 402718720 -0.1434438825 -0.0157710984 -0.6414470673 611 24.4000000000 0.2771950662 0.1549785780 0.3195070624 0.0190898625 0.0292880000 370898716 0 402718720 -0.1408277750 -0.0221763551 -0.6400321126 612 24.4400000000 0.2758539915 0.1551760869 0.3195070624 0.0190752890 0.0289350000 370901548 0 402718720 -0.1414658427 -0.0246956982 -0.6389931440 613 24.4800000000 0.2743010521 0.1553704180 0.3195070624 0.0190614565 0.0284490000 370903432 0 402718720 -0.1409047246 -0.0219314210 -0.6374400854 614 24.5200000000 0.2765245736 0.1555677374 0.3195070624 0.0190466379 0.0283160000 370906876 0 402718720 -0.1419996023 -0.0195120201 -0.6402835846 615 24.5600000000 0.2759010494 0.1557634014 0.3195070624 0.0190324551 0.0281670000 370908104 0 402718720 -0.1390970349 -0.0266810134 -0.6384643316 616 24.6000000000 0.2758367658 0.1559583256 0.3195070624 0.0190222229 0.0278860000 370914944 0 402718720 -0.1423749030 -0.0251590386 -0.6399148703 617 24.6400000000 0.2770485282 0.1561545821 0.3195070624 0.0190140517 0.0286060000 370923472 0 402718720 -0.1448467076 -0.0242777206 -0.6419086456 618 24.6800000000 0.2739785016 0.1563452356 0.3195070624 0.0190036584 0.0281860000 370920496 0 402718720 -0.1414773464 -0.0230304897 -0.6382781267 619 24.7200000000 0.2745313346 0.1565361663 0.3195070624 0.0190032695 0.0287760000 370926116 0 402718720 -0.1406765878 -0.0214464441 -0.6392122507 620 24.7600000000 0.2727503181 0.1567236085 0.3195070624 0.0189924519 0.0284320000 370930340 0 402718720 -0.1393144280 -0.0227033906 -0.6378693581 621 24.8000000000 0.2775067091 0.1569181063 0.3195070624 0.0189806963 0.0279520000 370929004 0 402718720 -0.1417971104 -0.0252036043 -0.6436589956 622 24.8400000000 0.2734943926 0.1571055279 0.3195070624 0.0189659236 0.0281110000 370934336 0 402718720 -0.1401283592 -0.0260758679 -0.6393667459 623 24.8800000000 0.2753011584 0.1572952481 0.3195070624 0.0189512916 0.0280200000 370935388 0 402718720 -0.1355812401 -0.0272773094 -0.6401363015 624 24.9200000000 0.2752165794 0.1574842245 0.3195070624 0.0189386566 0.0282710000 370939584 0 402718720 -0.1383129954 -0.0232352745 -0.6417046785 625 24.9600000000 0.2746319175 0.1576716609 0.3195070624 0.0189241740 0.0281280000 370943492 0 402718720 -0.1369912773 -0.0255226959 -0.6406933069 626 25.0000000000 0.2755704522 0.1578599976 0.3195070624 0.0189097392 0.0280530000 370947228 0 402718720 -0.1369955987 -0.0236042961 -0.6420701146 627 25.0400000000 0.2774137259 0.1580506734 0.3195070624 0.0188950834 0.0279910000 370948228 0 402718720 -0.1346729696 -0.0267465897 -0.6435952187 628 25.0800000000 0.2763716578 0.1582390826 0.3195070624 0.0188868252 0.0280860000 370953884 0 402718720 -0.1332193911 -0.0201239083 -0.6429222226 629 25.1200000000 0.2781511545 0.1584297218 0.3195070624 0.0188746113 0.0280750000 370954760 0 402718720 -0.1296250820 -0.0266571157 -0.6441178322 630 25.1600000000 0.2759781778 0.1586163067 0.3195070624 0.0188626424 0.0282400000 370960876 0 402718720 -0.1318550259 -0.0217285678 -0.6430264711 631 25.2000000000 0.2772834897 0.1588043688 0.3195070624 0.0188491194 0.0279900000 370963364 0 402718720 -0.1307114512 -0.0237481426 -0.6440416574 632 25.2400000000 0.2784842253 0.1589937356 0.3195070624 0.0188345531 0.0277540000 370965888 0 402718720 -0.1268628836 -0.0256758686 -0.6445180178 633 25.2800000000 0.2827468216 0.1591892381 0.3195070624 0.0188226593 0.0259170000 370969336 0 402718720 -0.1278890222 -0.0247370787 -0.6495850682 634 25.3200000000 0.2783248425 0.1593771492 0.3195070624 0.0188162625 0.0243880000 370972784 0 402718720 -0.1256247908 -0.0303341243 -0.6438004375 635 25.3600000000 0.2823764086 0.1595708488 0.3195070624 0.0188023052 0.0247400000 370974424 0 402718720 -0.1253378242 -0.0257791914 -0.6481011510 636 25.4000000000 0.2805264592 0.1597610306 0.3195070624 0.0187883831 0.0244470000 370978512 0 402718720 -0.1234119236 -0.0227932874 -0.6466251612 637 25.4400000000 0.2797555327 0.1599494050 0.3195070624 0.0187751250 0.0244290000 370981964 0 402718720 -0.1171673983 -0.0248815063 -0.6441730857 638 25.4800000000 0.2786756456 0.1601354963 0.3195070624 0.0187624834 0.0240750000 370982508 0 402718720 -0.1175430417 -0.0222007055 -0.6433134079 639 25.5200000000 0.2822798193 0.1603266455 0.3195070624 0.0187485782 0.0393710000 371828152 0 402718720 -0.1174500287 -0.0224686880 -0.6474416256 640 25.5600000000 0.2848618925 0.1605212318 0.3195070624 0.0187357691 0.0913660000 371892148 0 402718720 -0.1162564307 -0.0247959532 -0.6495785117 641 25.6000000000 0.2839006782 0.1607137114 0.3195070624 0.0187215970 0.0763030000 375712648 0 402718720 -0.1119735986 -0.0214657299 -0.6477800608 642 25.6400000000 0.2810294628 0.1609011191 0.3195070624 0.0187083806 0.0711170000 375696175 0 402718720 -0.1089827567 -0.0209439304 -0.6445456147 643 25.6800000000 0.2849124372 0.1610939828 0.3195070624 0.0186946953 0.0337840000 371787260 0 402718720 -0.1071564257 -0.0212534815 -0.6484118700 644 25.7200000000 0.2866775990 0.1612889884 0.3195070624 0.0186808733 0.0332930000 371788156 0 402718720 -0.1058119535 -0.0212582219 -0.6497165561 645 25.7600000000 0.2848467231 0.1614805508 0.3195070624 0.0186667685 0.0481160000 371791892 0 402718720 -0.1015060693 -0.0214026850 -0.6467405558 646 25.8000000000 0.2854514718 0.1616724562 0.3195070624 0.0186533051 0.0329430000 371794704 0 402718720 -0.0997257829 -0.0216379184 -0.6470941305 647 25.8400000000 0.2849462926 0.1618629876 0.3195070624 0.0186393107 0.0355430000 371800504 0 402718720 -0.0962519348 -0.0185271036 -0.6456993818 648 25.8800000000 0.2868090570 0.1620558057 0.3195070624 0.0186270041 0.0328160000 371798532 0 402718720 -0.0940181166 -0.0225849003 -0.6466003656 649 25.9200000000 0.2874366939 0.1622489965 0.3195070624 0.0186128235 0.0342310000 371802876 0 402718720 -0.0919177681 -0.0223201364 -0.6469948888 650 25.9600000000 0.2872249484 0.1624412672 0.3195070624 0.0185990378 0.0439610000 371804540 0 402718720 -0.0882289857 -0.0214572940 -0.6458747983 651 26.0000000000 0.2875373363 0.1626334271 0.3195070624 0.0185854127 0.0421540000 371810616 0 402718720 -0.0852520317 -0.0173985120 -0.6457615495 652 26.0400000000 0.2871819139 0.1628244524 0.3195070624 0.0185715678 0.0339350000 371811876 0 402718720 -0.0832435638 -0.0187601261 -0.6455348730 653 26.0800000000 0.2864202559 0.1630137262 0.3195070624 0.0185574874 0.0336480000 371814848 0 402718720 -0.0805794001 -0.0197741389 -0.6444042921 654 26.1200000000 0.2883049846 0.1632053031 0.3195070624 0.0185438121 0.0452800000 371814760 0 402718720 -0.0742653608 -0.0202524550 -0.6441240311 655 26.1600000000 0.2886785269 0.1633968652 0.3195070624 0.0185300539 0.0327660000 371820068 0 402718720 -0.0737222284 -0.0208899193 -0.6445316076 656 26.2000000000 0.2907391489 0.1635909846 0.3195070624 0.0185163765 0.0327460000 371819752 0 402718720 -0.0715538114 -0.0207167771 -0.6457577944 657 26.2400000000 0.2874504328 0.1637795073 0.3195070624 0.0185036625 0.0489170000 371824384 0 402718720 -0.0662078559 -0.0190182477 -0.6406930685 658 26.2800000000 0.2867013514 0.1639663186 0.3195070624 0.0184896151 0.0319070000 371824772 0 402718720 -0.0636070073 -0.0194014404 -0.6392795444 659 26.3200000000 0.2879272401 0.1641544232 0.3195070624 0.0184763759 0.0324590000 371827676 0 402718720 -0.0611691773 -0.0187659487 -0.6404243708 660 26.3600000000 0.2891885340 0.1643438688 0.3195070624 0.0184624128 0.0316840000 371829424 0 402718720 -0.0590117574 -0.0192696285 -0.6409811974 661 26.4000000000 0.2888519168 0.1645322320 0.3195070624 0.0184489477 0.0319580000 371834224 0 402718720 -0.0553132594 -0.0192292295 -0.6391026974 662 26.4400000000 0.2906349003 0.1647227194 0.3195070624 0.0184358473 0.0316330000 371835488 0 402718720 -0.0519292355 -0.0217615012 -0.6399610043 663 26.4800000000 0.2917852104 0.1649143672 0.3195070624 0.0184221036 0.0418420000 371837576 0 402718720 -0.0513545871 -0.0214505456 -0.6411388516 664 26.5200000000 0.2903086245 0.1651032140 0.3195070624 0.0184094687 0.0309600000 371841596 0 402718720 -0.0471523106 -0.0211119354 -0.6383765936 665 26.5600000000 0.2926378250 0.1652949953 0.3195070624 0.0183980587 0.0423170000 371841048 0 402718720 -0.0473431647 -0.0215654001 -0.6411789656 666 26.6000000000 0.2914966941 0.1654844874 0.3195070624 0.0183904913 0.0306040000 371842728 0 402718720 -0.0415267050 -0.0216134395 -0.6387277842 667 26.6400000000 0.2928694189 0.1656754693 0.3195070624 0.0183802863 0.0306890000 371844944 0 402718720 -0.0434037447 -0.0281187519 -0.6407030821 668 26.6800000000 0.2926347256 0.1658655281 0.3195070624 0.0183715842 0.0309370000 371848952 0 402718720 -0.0384582579 -0.0250615627 -0.6395995021 669 26.7200000000 0.2921854258 0.1660543470 0.3195070624 0.0183609299 0.0308880000 371850260 0 402718720 -0.0340234637 -0.0245024506 -0.6387146711 670 26.7600000000 0.2932932079 0.1662442558 0.3195070624 0.0183506223 0.0405350000 371849300 0 402718720 -0.0345771313 -0.0263372250 -0.6406528950 671 26.8000000000 0.2934349179 0.1664338097 0.3195070624 0.0183388860 0.0304550000 371856112 0 402718720 -0.0311410725 -0.0281174071 -0.6408367157 672 26.8400000000 0.2939334214 0.1666235412 0.3195070624 0.0183262194 0.0296670000 371855780 0 402718720 -0.0282268822 -0.0276708789 -0.6415150762 673 26.8800000000 0.2956886590 0.1668153171 0.3195070624 0.0183182604 0.0298440000 371857216 0 402718720 -0.0284343660 -0.0286220927 -0.6441254616 674 26.9200000000 0.2938830853 0.1670038449 0.3195070624 0.0183130928 0.0295200000 371863388 0 402718720 -0.0221805573 -0.0291193984 -0.6416693330 675 26.9600000000 0.2962897718 0.1671953796 0.3195070624 0.0183018868 0.0289390000 371861640 0 402718720 -0.0234675407 -0.0307460167 -0.6460486650 676 27.0000000000 0.2940037251 0.1673829659 0.3195070624 0.0182889051 0.0288350000 371864924 0 402718720 -0.0190049112 -0.0327873267 -0.6431716084 677 27.0400000000 0.2963159382 0.1675734134 0.3195070624 0.0182793796 0.0520830000 371866000 0 402718720 -0.0166830122 -0.0319889784 -0.6468335390 678 27.0800000000 0.2945057452 0.1677606293 0.3195070624 0.0182680953 0.0285500000 371871464 0 402718720 -0.0144225359 -0.0291673653 -0.6459087729 679 27.1200000000 0.2955778837 0.1679488726 0.3195070624 0.0182562784 0.0283890000 371872072 0 402718720 -0.0117537379 -0.0340944268 -0.6477907896 680 27.1600000000 0.2951875329 0.1681359883 0.3195070624 0.0182489594 0.0281210000 371874736 0 402718720 -0.0085602403 -0.0288963206 -0.6488694549 681 27.2000000000 0.2972429693 0.1683255727 0.3195070624 0.0182374553 0.0281220000 371877548 0 402718720 -0.0080232918 -0.0315545984 -0.6525148153 682 27.2400000000 0.2958370149 0.1685125397 0.3195070624 0.0182242606 0.0394510000 371882420 0 402718720 -0.0055669844 -0.0306690875 -0.6527560353 683 27.2800000000 0.2981850207 0.1687023969 0.3195070624 0.0182129971 0.0387110000 371883572 0 402718720 -0.0024630129 -0.0291198008 -0.6564063430 684 27.3200000000 0.2977762222 0.1688911013 0.3195070624 0.0181999230 0.0280900000 371887556 0 402718720 -0.0006533563 -0.0298254099 -0.6579085588 685 27.3600000000 0.2968108058 0.1690778454 0.3195070624 0.0181870754 0.0281620000 371888756 0 402718720 0.0026578307 -0.0334699452 -0.6576856375 686 27.4000000000 0.2980254591 0.1692658157 0.3195070624 0.0181811011 0.0274160000 371886824 0 402718720 0.0064693093 -0.0307082310 -0.6605303288 687 27.4400000000 0.2984825075 0.1694539040 0.3195070624 0.0181718652 0.0275280000 371891212 0 402718720 0.0070274472 -0.0336485952 -0.6633439660 688 27.4800000000 0.3003819585 0.1696442064 0.3195070624 0.0181624173 0.0280220000 371898168 0 402718720 0.0094654858 -0.0345876776 -0.6673066616 689 27.5200000000 0.2987845540 0.1698316380 0.3195070624 0.0181515105 0.0277310000 371900372 0 402718720 0.0114452541 -0.0375087485 -0.6678023338 690 27.5600000000 0.3004747927 0.1700209759 0.3195070624 0.0181503298 0.0382590000 371897604 0 402718720 0.0124397576 -0.0325310826 -0.6725698709 691 27.6000000000 0.2996506989 0.1702085732 0.3195070624 0.0181384389 0.0278190000 371903272 0 402718720 0.0174171925 -0.0290739480 -0.6738549471 692 27.6400000000 0.3015629351 0.1703983916 0.3195070624 0.0181267413 0.0272430000 371905268 0 402718720 0.0205095112 -0.0282692350 -0.6783221960 693 27.6800000000 0.3013871312 0.1705874086 0.3195070624 0.0181162123 0.0270340000 371905824 0 402718720 0.0227604806 -0.0314411595 -0.6800784469 694 27.7200000000 0.3001000583 0.1707740262 0.3195070624 0.0181036118 0.0272120000 371909108 0 402718720 0.0250129104 -0.0344066434 -0.6809949875 695 27.7600000000 0.3015463948 0.1709621879 0.3195070624 0.0180909076 0.0499670000 371915108 0 402718720 0.0278130472 -0.0347442701 -0.6844398975 696 27.8000000000 0.3004810810 0.1711482783 0.3195070624 0.0180800217 0.0274830000 371914580 0 402718720 0.0313793421 -0.0337953568 -0.6848900318 697 27.8400000000 0.3015056252 0.1713353046 0.3195070624 0.0180704003 0.0269800000 371915768 0 402718720 0.0357206166 -0.0318328775 -0.6910983324 698 27.8800000000 0.3023835719 0.1715230528 0.3195070624 0.0180605724 0.0375580000 371915880 0 402718720 0.0380739570 -0.0396700278 -0.6932193041 699 27.9200000000 0.3011052310 0.1717084350 0.3195070624 0.0180869133 0.0270080000 371922624 0 402718720 0.0420163572 -0.0269843228 -0.6967928410 700 27.9600000000 0.3018499911 0.1718943515 0.3195070624 0.0180788141 0.0268900000 371921140 0 402718720 0.0436649621 -0.0385224372 -0.6991171837 701 28.0000000000 0.3034095168 0.1720819623 0.3195070624 0.0180695430 0.0264160000 371923232 0 402718720 0.0449919999 -0.0373897329 -0.7022974491 702 28.0400000000 0.3028046191 0.1722681770 0.3195070624 0.0180622598 0.0259690000 371924140 0 402718720 0.0480124950 -0.0393427312 -0.7029132843 703 28.0800000000 0.3047360182 0.1724566092 0.3195070624 0.0180722301 0.0254410000 371923656 0 402718720 0.0472694337 -0.0346352533 -0.7077019215 704 28.1200000000 0.3051969707 0.1726451608 0.3195070624 0.0180696037 0.0253880000 371928804 0 402718720 0.0512893200 -0.0330635682 -0.7093954086 705 28.1600000000 0.3034949005 0.1728307633 0.3195070624 0.0180599123 0.0373290000 371929620 0 402718720 0.0515835285 -0.0328028724 -0.7093834877 706 28.2000000000 0.3054921925 0.1730186690 0.3195070624 0.0180543115 0.0252910000 371931476 0 402718720 0.0523484349 -0.0356945917 -0.7129201293 707 28.2400000000 0.3076373935 0.1732090774 0.3195070624 0.0180491430 0.0250230000 371930912 0 402718720 0.0554493964 -0.0360236317 -0.7165296078 708 28.2800000000 0.3050604761 0.1733953082 0.3195070624 0.0180375638 0.0250290000 371934152 0 402718720 0.0595370233 -0.0393794477 -0.7149493098 709 28.3200000000 0.3086001575 0.1735860061 0.3195070624 0.0180258150 0.0243320000 371931776 0 402718720 0.0586133301 -0.0378735065 -0.7200737596 710 28.3600000000 0.3032666445 0.1737686549 0.3195070624 0.0180171880 0.0504910000 371936104 0 402718720 0.0635120571 -0.0374723002 -0.7148703933 711 28.4000000000 0.3101643920 0.1739604914 0.3195070624 0.0180124477 0.0251040000 371944256 0 402718720 0.0628411472 -0.0343258120 -0.7239172459 712 28.4400000000 0.3077925444 0.1741484577 0.3195070624 0.0180013588 0.0249740000 371943268 0 402718720 0.0668533146 -0.0388470702 -0.7213369608 713 28.4800000000 0.3088498414 0.1743373797 0.3195070624 0.0179933533 0.0253620000 371948116 0 402718720 0.0688022077 -0.0342866480 -0.7230796814 714 28.5200000000 0.3069406748 0.1745230986 0.3195070624 0.0179837267 0.0246420000 371946956 0 402718720 0.0729087889 -0.0349445157 -0.7215921879 715 28.5600000000 0.3064804673 0.1747076544 0.3195070624 0.0179718168 0.0240740000 371945244 0 402718720 0.0751761496 -0.0378733203 -0.7216495275 716 28.6000000000 0.3109332025 0.1748979135 0.3195070624 0.0179592906 0.0237420000 371944448 0 402718720 0.0767492652 -0.0354631804 -0.7267345190 717 28.6400000000 0.3088817894 0.1750847809 0.3195070624 0.0179500908 0.0354790000 371948300 0 402718720 0.0802837014 -0.0379738584 -0.7245174646 718 28.6800000000 0.3047996461 0.1752654422 0.3195070624 0.0179408279 0.0244390000 371955192 0 402718720 0.0832935572 -0.0423505232 -0.7199670672 719 28.7200000000 0.3092220724 0.1754517519 0.3195070624 0.0179302255 0.0244980000 371957432 0 402718720 0.0860391259 -0.0390235558 -0.7243334055 720 28.7600000000 0.3122124672 0.1756416973 0.3195070624 0.0179199995 0.0240670000 371955824 0 402718720 0.0862049460 -0.0383101739 -0.7272588611 721 28.8000000000 0.3114310205 0.1758300320 0.3195070624 0.0179171110 0.0242450000 371961872 0 402718720 0.0928041339 -0.0357631780 -0.7259217501 722 28.8400000000 0.3096673191 0.1760154022 0.3195070624 0.0179096825 0.0228020000 371956664 0 402718720 0.0977969170 -0.0293081477 -0.7234185934 723 28.8800000000 0.3091247678 0.1761995092 0.3195070624 0.0179036280 0.0232950000 371961712 0 402718720 0.1012468338 -0.0405570306 -0.7215714455 724 28.9200000000 0.3139789701 0.1763898124 0.3195070624 0.0178937100 0.0229090000 371960308 0 402718720 0.1035568416 -0.0362294167 -0.7260494232 725 28.9600000000 0.3115270436 0.1765762085 0.3195070624 0.0178820962 0.0431550000 371966124 0 402718720 0.1070556045 -0.0355509110 -0.7224469781 726 29.0000000000 0.3115296960 0.1767620949 0.3195070624 0.0178725840 0.0228910000 371970440 0 402718720 0.1127896905 -0.0357423276 -0.7211795449 727 29.0400000000 0.3153068423 0.1769526654 0.3195070624 0.0178648535 0.0220160000 371966396 0 402718720 0.1115950346 -0.0344422907 -0.7247790098 728 29.0800000000 0.3103225529 0.1771358658 0.3195070624 0.0178578001 0.0220410000 371967920 0 402718720 0.1197358966 -0.0321985446 -0.7179049253 729 29.1200000000 0.3137114942 0.1773232123 0.3195070624 0.0178468084 0.0221690000 371973772 0 402718720 0.1230912805 -0.0303662345 -0.7199929953 730 29.1600000000 0.3149453402 0.1775117358 0.3195070624 0.0178376435 0.0218350000 371973284 0 402718720 0.1252028048 -0.0348007716 -0.7200711370 731 29.2000000000 0.3176552355 0.1777034505 0.3195070624 0.0178402945 0.0210640000 371970340 0 402718720 0.1285420358 -0.0292521603 -0.7215780020 732 29.2400000000 0.3183716834 0.1778956203 0.3195070624 0.0178306504 0.0313060000 371975652 0 402718720 0.1329823136 -0.0321837738 -0.7207290530 733 29.2800000000 0.3153073192 0.1780830851 0.3195070624 0.0178212512 0.0264570000 372460172 0 402718720 0.1390211284 -0.0356235802 -0.7160766125 734 29.3200000000 0.3135406077 0.1782676321 0.3195070624 0.0178102092 0.0900060000 374121716 0 402718720 0.1415987015 -0.0366066396 -0.7130993605 735 29.3600000000 0.3151593506 0.1784538793 0.3195070624 0.0178002429 0.0626240000 376148748 0 402718720 0.1458533108 -0.0341366678 -0.7135886550 736 29.4000000000 0.3088324368 0.1786310241 0.3195070624 0.0178029173 0.0550790000 375900409 0 402718720 0.1587131321 -0.0444923379 -0.7029758692 737 29.4400000000 0.3098503649 0.1788090694 0.3195070624 0.0177921280 0.0247880000 372498188 0 402718720 0.1610555947 -0.0465086251 -0.7029167414 738 29.4800000000 0.3094910979 0.1789861453 0.3195070624 0.0177867994 0.0243320000 372498944 0 402718720 0.1646757722 -0.0401172787 -0.7018963099 739 29.5200000000 0.3101918697 0.1791636902 0.3195070624 0.0177762224 0.0336340000 372501272 0 402718720 0.1670757532 -0.0454085916 -0.7010701895 740 29.5600000000 0.3120505214 0.1793432670 0.3195070624 0.0177683075 0.0248610000 372507776 0 402718720 0.1676018238 -0.0446355119 -0.7022966146 741 29.6000000000 0.3089746237 0.1795182081 0.3195070624 0.0177696910 0.0239290000 372506900 0 402718720 0.1752967387 -0.0440235846 -0.6969371438 742 29.6400000000 0.3114494383 0.1796960130 0.3195070624 0.0177655427 0.0229860000 372507676 0 402718720 0.1753410995 -0.0426260754 -0.6992076039 743 29.6800000000 0.3090592027 0.1798701223 0.3195070624 0.0177564540 0.0229780000 372509604 0 402718720 0.1783130169 -0.0419973060 -0.6958273649 744 29.7200000000 0.3097841442 0.1800447379 0.3195070624 0.0177453434 0.0217370000 372505944 0 402718720 0.1802990884 -0.0436030030 -0.6955817938 745 29.7600000000 0.3124846816 0.1802225097 0.3195070624 0.0177349354 0.0218730000 372511008 0 402718720 0.1809402257 -0.0465097278 -0.6977701187 746 29.8000000000 0.3138998151 0.1804017018 0.3195070624 0.0177233570 0.0220170000 372514772 0 402718720 0.1825742573 -0.0420075879 -0.6993310452 747 29.8400000000 0.3132446110 0.1805795370 0.3195070624 0.0177145431 0.0315810000 372515696 0 402718720 0.1844660789 -0.0406715609 -0.6978341937 748 29.8800000000 0.3104215264 0.1807531225 0.3195070624 0.0177079519 0.0207120000 372514932 0 402718720 0.1904384345 -0.0453137048 -0.6922181845 749 29.9200000000 0.3141388595 0.1809312076 0.3195070624 0.0176977113 0.0205440000 372517404 0 402718720 0.1914138198 -0.0423434898 -0.6957975030 750 29.9600000000 0.3148597181 0.1811097790 0.3195070624 0.0176872199 0.0311210000 372520108 0 402718720 0.1954630613 -0.0388542078 -0.6956037879 751 30.0000000000 0.3138592839 0.1812865426 0.3195070624 0.0176771496 0.0209830000 372522764 0 402718720 0.1975672543 -0.0420523621 -0.6937282085 752 30.0400000000 0.3174759448 0.1814676455 0.3195070624 0.0176656718 0.0198620000 372521144 0 402718720 0.1964614838 -0.0389811322 -0.6978508234 753 30.0800000000 0.3136156797 0.1816431409 0.3195070624 0.0176579563 0.0205850000 372528616 0 402718720 0.1982984543 -0.0388859622 -0.6932553649 754 30.1200000000 0.3147397041 0.1818196616 0.3195070624 0.0176468063 0.0199980000 372526812 0 402718720 0.2008780837 -0.0402558371 -0.6936776638 755 30.1600000000 0.3179353178 0.1819999472 0.3195070624 0.0176370760 0.0277910000 372530984 0 402718720 0.2003478855 -0.0333850868 -0.6974058747 756 30.2000000000 0.3166334629 0.1821780339 0.3195070624 0.0176298763 0.0194570000 372531604 0 402718720 0.2024439573 -0.0409219638 -0.6947029829 757 30.2400000000 0.3151895404 0.1823537426 0.3195070624 0.0176325484 0.0190780000 372531380 0 402718720 0.2078592777 -0.0363811255 -0.6919258237 758 30.2800000000 0.3148797154 0.1825285790 0.3195070624 0.0176281835 0.0211090000 372829212 0 402718720 0.2107405663 -0.0451985933 -0.6904864311 759 30.3200000000 0.3157306015 0.1827040757 0.3195070624 0.0176365038 0.0446750000 372883448 0 402718720 0.2108372450 -0.0395221822 -0.6919049025 760 30.3600000000 0.3197349608 0.1828843795 0.3197349608 0.0176372199 0.0346640000 376174164 0 402718720 0.2108141631 -0.0360173471 -0.6960985065 761 30.4000000000 0.3175980151 0.1830614014 0.3197349608 0.0176300153 0.0232140000 376148296 0 402718720 0.2142052203 -0.0427189991 -0.6929076910 762 30.4400000000 0.3178863227 0.1832383370 0.3197349608 0.0176357229 0.0383090000 375903833 0 402718720 0.2211145312 -0.0427776203 -0.6914579272 763 30.4800000000 0.3208437860 0.1834186849 0.3208437860 0.0176390348 0.0198050000 373050500 0 402718720 0.2188077867 -0.0387558565 -0.6956418157 764 30.5200000000 0.3211366832 0.1835989440 0.3211366832 0.0176339739 0.0376070000 374793728 0 402718720 0.2219312191 -0.0415901020 -0.6951715946 765 30.5600000000 0.3204010129 0.1837777703 0.3211366832 0.0176452629 0.0281450000 375892704 0 402718720 0.2238744646 -0.0369075909 -0.6945241094 766 30.6000000000 0.3224761188 0.1839588386 0.3224761188 0.0176562203 0.0319000000 375578141 0 402718720 0.2248893976 -0.0314126462 -0.6971859336 767 30.6400000000 0.3241086006 0.1841415632 0.3241086006 0.0176480872 0.0223470000 376054912 0 402718720 0.2269459218 -0.0340577364 -0.6988355517 768 30.6800000000 0.3244158626 0.1843242120 0.3244158626 0.0176381497 0.0320230000 375740809 0 402718720 0.2289248407 -0.0393354222 -0.6987824440 769 30.7200000000 0.3238304853 0.1845056246 0.3244158626 0.0176423111 0.0398080000 374334568 0 402718720 0.2350017130 -0.0327156782 -0.6979757547 770 30.7600000000 0.3256393075 0.1846889151 0.3256393075 0.0176319268 0.0393730000 375135081 0 402718720 0.2343255877 -0.0326626897 -0.7007216811 771 30.8000000000 0.3254471123 0.1848714809 0.3256393075 0.0176264511 0.0300960000 376589308 0 402718720 0.2429891378 -0.0289655477 -0.6992644072 772 30.8400000000 0.3226820827 0.1850499920 0.3256393075 0.0176161614 0.0438040000 376507903 0 402718720 0.2453868389 -0.0329867974 -0.6963253021 773 30.8800000000 0.3247820437 0.1852307579 0.3256393075 0.0176101119 0.0168150000 373659556 0 402718720 0.2437368929 -0.0322039351 -0.6995638013 774 30.9200000000 0.3237129748 0.1854096755 0.3256393075 0.0175988103 0.0169410000 373660524 0 402718720 0.2464919388 -0.0329711363 -0.6983969212 775 30.9600000000 0.3241097629 0.1855886434 0.3256393075 0.0175916584 0.0168770000 373662104 0 402718720 0.2432176471 -0.0279688090 -0.7004409432 776 31.0000000000 0.3246225417 0.1857678108 0.3256393075 0.0175907334 0.0169800000 373667288 0 402718720 0.2500244975 -0.0351583511 -0.6996926665 777 31.0400000000 0.3255277276 0.1859476820 0.3256393075 0.0175820792 0.0168620000 373669176 0 402718720 0.2465272248 -0.0334076956 -0.7019078732 778 31.0800000000 0.3258562684 0.1861275130 0.3258562684 0.0175714416 0.0168040000 373670020 0 402718720 0.2521813512 -0.0328104421 -0.7020662427 779 31.1200000000 0.3272306919 0.1863086468 0.3272306919 0.0175724491 0.0166770000 373670788 0 402718720 0.2475439012 -0.0329886973 -0.7053913474 780 31.1600000000 0.3275760412 0.1864897588 0.3275760412 0.0175854442 0.0162430000 373671436 0 402718720 0.2478478253 -0.0334985256 -0.7061221600 781 31.2000000000 0.3255820870 0.1866678540 0.3275760412 0.0175976790 0.0183570000 373860768 0 402718720 0.2512088418 -0.0323664024 -0.7040121555 782 31.2400000000 0.3247014582 0.1868443675 0.3275760412 0.0176089478 0.0368510000 373956848 0 402718720 0.2541218698 -0.0332714245 -0.7029228806 783 31.2800000000 0.3251655996 0.1870210230 0.3275760412 0.0176233128 0.0284940000 376954972 0 402718720 0.2492396832 -0.0340286233 -0.7048739195 784 31.3200000000 0.3248460889 0.1871968203 0.3275760412 0.0176248306 0.0433720000 376820575 0 402718720 0.2576728463 -0.0331132710 -0.7031353116 785 31.3600000000 0.3261093795 0.1873737790 0.3275760412 0.0176175623 0.0166710000 373905532 0 402718720 0.2564534545 -0.0353728645 -0.7048410773 786 31.4000000000 0.3270260394 0.1875514536 0.3275760412 0.0176065692 0.0163420000 373904504 0 402718720 0.2577613592 -0.0317872502 -0.7062905431 787 31.4400000000 0.3241243660 0.1877249897 0.3275760412 0.0176000406 0.0170850000 374092416 0 402718720 0.2587846816 -0.0310549550 -0.7035591006 788 31.4800000000 0.3262822926 0.1879008238 0.3275760412 0.0175951647 0.0395750000 374185308 0 402718720 0.2548657060 -0.0302162804 -0.7069280744 789 31.5200000000 0.3276659250 0.1880779659 0.3276659250 0.0175930516 0.0327730000 377634328 0 402718720 0.2533957362 -0.0326560177 -0.7089322209 790 31.5600000000 0.3262643218 0.1882528854 0.3276659250 0.0176027590 0.0276250000 377719148 0 402718720 0.2570656240 -0.0297137909 -0.7071661949 791 31.6000000000 0.3256112635 0.1884265369 0.3276659250 0.0176151299 0.0390710000 377557869 0 402718720 0.2574775815 -0.0287285708 -0.7066742778 792 31.6400000000 0.3277103603 0.1886024003 0.3277103603 0.0176132387 0.0167300000 374133236 0 402718720 0.2593701780 -0.0286302790 -0.7084867954 793 31.6800000000 0.3268594146 0.1887767471 0.3277103603 0.0176101553 0.0202080000 374415848 0 402718720 0.2600963116 -0.0254030507 -0.7078266740 794 31.7200000000 0.3266326189 0.1889503691 0.3277103603 0.0176209104 0.0449900000 374426484 0 402718720 0.2605853081 -0.0264841411 -0.7075293660 795 31.7600000000 0.3262777328 0.1891231080 0.3277103603 0.0176294671 0.0424360000 377489308 0 402718720 0.2625222802 -0.0246809330 -0.7066054344 796 31.8000000000 0.3275915980 0.1892970633 0.3277103603 0.0176414361 0.0339060000 378245200 0 402718720 0.2621908784 -0.0246451274 -0.7079007626 797 31.8400000000 0.3260127306 0.1894686012 0.3277103603 0.0176821399 0.0494880000 378208055 0 402718720 0.2666681111 -0.0216015168 -0.7052896023 798 31.8800000000 0.3275805712 0.1896416738 0.3277103603 0.0177364894 0.0185170000 374439436 0 402718720 0.2613567412 -0.0217608213 -0.7079204917 799 31.9200000000 0.3278900981 0.1898147007 0.3278900981 0.0177562094 0.0189580000 374445080 0 402718720 0.2632808089 -0.0193359423 -0.7077291608 800 31.9600000000 0.3251284063 0.1899838428 0.3278900981 0.0177684854 0.0192770000 374452832 0 402718720 0.2659649849 -0.0223632306 -0.7040625215 801 32.0000000000 0.3263250887 0.1901540566 0.3278900981 0.0177609479 0.0299390000 374452380 0 402718720 0.2666078806 -0.0201005526 -0.7048832178 802 32.0400000000 0.3245618939 0.1903216474 0.3278900981 0.0177593836 0.0195230000 374457788 0 402718720 0.2675414085 -0.0226235203 -0.7024706006 803 32.0800000000 0.3258133233 0.1904903792 0.3278900981 0.0177493702 0.0194970000 374461136 0 402718720 0.2682595253 -0.0170787200 -0.7036036253 804 32.1199999990 0.3262076080 0.1906591818 0.3278900981 0.0177442106 0.0199430000 374464108 0 402718720 0.2668949068 -0.0187073126 -0.7036845088 805 32.1600000000 0.3278115690 0.1908295574 0.3278900981 0.0177365297 0.0203310000 374469004 0 402718720 0.2680181563 -0.0183809213 -0.7047693133 806 32.2000000000 0.3267580271 0.1909982032 0.3278900981 0.0177309934 0.0205670000 374472588 0 402718720 0.2703817487 -0.0199741498 -0.7026055455 807 32.2400000000 0.3267549574 0.1911664271 0.3278900981 0.0177215723 0.0315560000 374476272 0 402718720 0.2722310126 -0.0216858014 -0.7017216086 808 32.2800000000 0.3285136819 0.1913364114 0.3285136819 0.0177119546 0.0317770000 374481152 0 402718720 0.2719941735 -0.0166467130 -0.7033552527 809 32.3200000000 0.3282575011 0.1915056587 0.3285136819 0.0177050123 0.0210220000 374484608 0 402718720 0.2737889886 -0.0200836323 -0.7020881772 810 32.3600000000 0.3287515640 0.1916750981 0.3287515640 0.0176960124 0.0438190000 374970820 0 402718720 0.2721791863 -0.0176132061 -0.7023847103 811 32.4000000000 0.3280514777 0.1918432564 0.3287515640 0.0176852129 0.0767420000 375041512 0 402718720 0.2737683654 -0.0164743792 -0.7007571459 812 32.4399999990 0.3279451728 0.1920108696 0.3287515640 0.0176745723 0.0689440000 376603748 0 402718720 0.2747960091 -0.0169165097 -0.6996933222 813 32.4800000000 0.3294076622 0.1921798693 0.3294076622 0.0176649272 0.0520590000 380437812 0 402718720 0.2750844359 -0.0169472173 -0.7005335689 814 32.5200000000 0.3303147852 0.1923495682 0.3303147852 0.0176568670 0.0408890000 380446296 0 402718720 0.2754232287 -0.0171362981 -0.7005377412 815 32.5600000000 0.3275415003 0.1925154479 0.3303147852 0.0176488274 0.0727900000 380364991 0 402718720 0.2797905207 -0.0184583701 -0.6958938837 816 32.6000000000 0.3266855478 0.1926798720 0.3303147852 0.0176403426 0.0257400000 375028708 0 402718720 0.2820749283 -0.0225504711 -0.6936763525 817 32.6400000000 0.3279125690 0.1928453955 0.3303147852 0.0176390987 0.0255500000 375029344 0 402718720 0.2800534964 -0.0196707342 -0.6947106719 818 32.6800000000 0.3284187913 0.1930111332 0.3303147852 0.0176342796 0.0255360000 375032644 0 402718720 0.2826142907 -0.0206765514 -0.6938374639 819 32.7200000000 0.3281701207 0.1931761625 0.3303147852 0.0176299846 0.0249560000 375035992 0 402718720 0.2831372619 -0.0184923522 -0.6926119924 820 32.7599999990 0.3269912601 0.1933393516 0.3303147852 0.0176218801 0.0250620000 375042716 0 402718720 0.2844538987 -0.0212520286 -0.6901110411 821 32.7999999990 0.3291131258 0.1935047277 0.3303147852 0.0176177848 0.0248160000 375044360 0 402718720 0.2839134932 -0.0238390900 -0.6916023493 822 32.8400000000 0.3279397488 0.1936682740 0.3303147852 0.0176135316 0.0243350000 375042200 0 402718720 0.2846060395 -0.0228478927 -0.6893686056 823 32.8800000000 0.3301422894 0.1938340990 0.3303147852 0.0176243027 0.0237750000 375043920 0 402718720 0.2835509777 -0.0177040026 -0.6909630895 824 32.9200000000 0.3325949311 0.1940024981 0.3325949311 0.0176236274 0.0231480000 375045520 0 402718720 0.2805395722 -0.0207708012 -0.6930544376 825 32.9600000000 0.3328199387 0.1941707617 0.3328199387 0.0176258913 0.0230420000 375047532 0 402718720 0.2817100286 -0.0197827406 -0.6921471953 826 33.0000000000 0.3295542300 0.1943346642 0.3328199387 0.0176233660 0.0221870000 375055032 0 402718720 0.2830669880 -0.0197551101 -0.6878283024 827 33.0400000000 0.3299957216 0.1944987041 0.3328199387 0.0176171973 0.0328500000 375052872 0 402718720 0.2821105719 -0.0247732252 -0.6873927116 828 33.0800000000 0.3319306672 0.1946646848 0.3328199387 0.0176170320 0.0216960000 375058428 0 402718720 0.2815531492 -0.0259391218 -0.6887448430 829 33.1199999990 0.3289186656 0.1948266317 0.3328199387 0.0176143226 0.0216300000 375062264 0 402718720 0.2834100127 -0.0259531587 -0.6846058369 830 33.1600000000 0.3311870098 0.1949909213 0.3328199387 0.0176181332 0.0220880000 375066420 0 402718720 0.2787014842 -0.0182336196 -0.6870694160 831 33.2000000000 0.3285603821 0.1951516547 0.3328199387 0.0176095921 0.0220330000 375070284 0 402718720 0.2821393609 -0.0252099019 -0.6818490028 832 33.2400000000 0.3300188482 0.1953137547 0.3328199387 0.0176012266 0.0293360000 375069380 0 402718720 0.2817116380 -0.0225816052 -0.6823752522 833 33.2800000000 0.3319749832 0.1954778138 0.3328199387 0.0175931373 0.0212290000 375071088 0 402718720 0.2792530060 -0.0284370109 -0.6836649179 834 33.3200000000 0.3326326311 0.1956422680 0.3328199387 0.0175861203 0.0213250000 375072636 0 402718720 0.2771794498 -0.0256159399 -0.6839158535 835 33.3600000000 0.3298300207 0.1958029719 0.3328199387 0.0175757062 0.0215470000 375080032 0 402718720 0.2789948583 -0.0249646269 -0.6794579029 836 33.4000000000 0.3329155743 0.1959669822 0.3329155743 0.0175688188 0.0216590000 375081812 0 402718720 0.2752202451 -0.0220569149 -0.6824700236 837 33.4399999990 0.3310231864 0.1961283396 0.3329155743 0.0175586839 0.0211680000 375082104 0 402718720 0.2763658762 -0.0263667479 -0.6790276766 838 33.4800000000 0.3326681554 0.1962912750 0.3329155743 0.0175512053 0.0213810000 375086940 0 402718720 0.2757736444 -0.0238549747 -0.6800969839 839 33.5200000000 0.3292458355 0.1964497429 0.3329155743 0.0175411106 0.0220560000 375100140 0 402718720 0.2760864198 -0.0267315470 -0.6756956577 840 33.5600000000 0.3310331702 0.1966099612 0.3329155743 0.0175335838 0.0223290000 375104656 0 402718720 0.2731113434 -0.0232796036 -0.6773250103 841 33.6000000000 0.3300538659 0.1967686341 0.3329155743 0.0175253360 0.0459390000 375100768 0 402718720 0.2746452093 -0.0248212889 -0.6744072437 842 33.6400000000 0.3269719183 0.1969232699 0.3329155743 0.0175232713 0.0262030000 375737180 0 402718720 0.2773688436 -0.0238103829 -0.6696397066 843 33.6800000000 0.3289752603 0.1970799152 0.3329155743 0.0175197284 0.0906890000 375798400 0 402718720 0.2739973068 -0.0244189426 -0.6714994907 844 33.7200000000 0.3298190832 0.1972371891 0.3329155743 0.0175109182 0.0798450000 378404632 0 402718720 0.2730284929 -0.0299413279 -0.6710171700 845 33.7599999990 0.3279253542 0.1973918496 0.3329155743 0.0175050850 0.0636950000 380495901 0 402718720 0.2717643380 -0.0296037272 -0.6689013243 846 33.7999999990 0.3246818185 0.1975423106 0.3329155743 0.0175014326 0.0799730000 380323283 0 402718720 0.2721647620 -0.0249198638 -0.6647605300 847 33.8400000000 0.3255735040 0.1976934690 0.3329155743 0.0174929766 0.0309960000 375826856 0 402718720 0.2708147764 -0.0248548463 -0.6647515893 848 33.8800000000 0.3239866495 0.1978423996 0.3329155743 0.0174833907 0.0299210000 375819800 0 402718720 0.2708346248 -0.0279146805 -0.6620911360 849 33.9200000000 0.3240874410 0.1979910982 0.3329155743 0.0174741399 0.0291650000 375825208 0 402718720 0.2696928382 -0.0252333954 -0.6618188620 850 33.9600000000 0.3273753524 0.1981433149 0.3329155743 0.0174691373 0.0292920000 375827160 0 402718720 0.2658663690 -0.0253820345 -0.6646583080 851 34.0000000000 0.3262165487 0.1982938123 0.3329155743 0.0174667032 0.0288620000 375831224 0 402718720 0.2656819224 -0.0319241993 -0.6626726389 852 34.0400000000 0.3279026151 0.1984459353 0.3329155743 0.0174611451 0.0296840000 375837452 0 402718720 0.2640033364 -0.0209706984 -0.6652768254 853 34.0800000000 0.3264595866 0.1985960099 0.3329155743 0.0174523301 0.0297980000 375843868 0 402718720 0.2654667795 -0.0154364929 -0.6628065705 854 34.1199999990 0.3253138065 0.1987443914 0.3329155743 0.0174529560 0.0286920000 375844056 0 402718720 0.2594227791 -0.0214429870 -0.6617757678 855 34.1600000000 0.3272304833 0.1988946675 0.3329155743 0.0174456412 0.0280600000 375842296 0 402718720 0.2600110769 -0.0273956619 -0.6618269682 856 34.2000000000 0.3236640096 0.1990404261 0.3329155743 0.0174407308 0.0284730000 375848164 0 402718720 0.2627209425 -0.0237427726 -0.6556725502 857 34.2400000000 0.3268311918 0.1991895402 0.3329155743 0.0174383094 0.0279230000 375845176 0 402718720 0.2603495121 -0.0251607560 -0.6582313776 858 34.2800000000 0.3253680766 0.1993366014 0.3329155743 0.0174288150 0.0281600000 375850840 0 402718720 0.2592312694 -0.0295379087 -0.6551954150 859 34.3200000000 0.3286528885 0.1994871442 0.3329155743 0.0174293035 0.0276820000 375851720 0 402718720 0.2581285238 -0.0232091695 -0.6571226120 860 34.3600000000 0.3249838650 0.1996330707 0.3329155743 0.0174201082 0.0279560000 375855972 0 402718720 0.2603086233 -0.0292608216 -0.6508623958 861 34.4000000000 0.3264688551 0.1997803828 0.3329155743 0.0174111947 0.0278890000 375860872 0 402718720 0.2582793832 -0.0284350216 -0.6511377692 862 34.4400000000 0.3245386481 0.1999251140 0.3329155743 0.0174023171 0.0379970000 375868284 0 402718720 0.2543992996 -0.0274686664 -0.6480482817 863 34.4800000000 0.3241719902 0.2000690849 0.3329155743 0.0173930970 0.0275810000 375867244 0 402718720 0.2564222217 -0.0310208425 -0.6450118423 864 34.5200000000 0.3228414655 0.2002111826 0.3329155743 0.0173832523 0.0275880000 375871356 0 402718720 0.2562342882 -0.0304409973 -0.6411886215 865 34.5600000000 0.3257215023 0.2003562812 0.3329155743 0.0173821528 0.0378620000 375867648 0 402718720 0.2462976277 -0.0305557214 -0.6441507936 866 34.6000000000 0.3304646313 0.2005065218 0.3329155743 0.0173791515 0.0264990000 375871012 0 402718720 0.2430055887 -0.0216573589 -0.6473120451 867 34.6400000000 0.3220247328 0.2006466812 0.3329155743 0.0173754282 0.0262210000 375870772 0 402718720 0.2479125410 -0.0298104994 -0.6347506046 868 34.6800000000 0.3224985600 0.2007870635 0.3329155743 0.0173667526 0.0257210000 375872632 0 402718720 0.2444896102 -0.0275480598 -0.6335762739 869 34.7200000000 0.3236210048 0.2009284144 0.3329155743 0.0173578558 0.0257490000 375874476 0 402718720 0.2429758310 -0.0215803422 -0.6326175928 870 34.7600000000 0.3224546313 0.2010680998 0.3329155743 0.0173663824 0.0371600000 375881600 0 402718720 0.2394546717 -0.0294234827 -0.6289066076 871 34.8000000000 0.3212226927 0.2012060499 0.3329155743 0.0173641944 0.0263970000 375883612 0 402718720 0.2358979285 -0.0301104672 -0.6253673434 872 34.8400000000 0.3210583627 0.2013434952 0.3329155743 0.0173565328 0.0264760000 375885144 0 402718720 0.2385743707 -0.0263475701 -0.6210106611 873 34.8800000000 0.3198231459 0.2014792108 0.3329155743 0.0173476427 0.0266700000 375891632 0 402718720 0.2343160063 -0.0268099457 -0.6178801060 874 34.9200000000 0.3223526776 0.2016175099 0.3329155743 0.0173401368 0.0376100000 375891836 0 402718720 0.2280008793 -0.0206136480 -0.6195446253 875 34.9600000000 0.3211562634 0.2017541256 0.3329155743 0.0173384709 0.0301190000 376477864 0 402718720 0.2268382758 -0.0229868796 -0.6155093908 876 35.0000000000 0.3223420382 0.2018917831 0.3329155743 0.0173345484 0.0878730000 376695416 0 402718720 0.2234115005 -0.0232266970 -0.6145870686 877 35.0400000000 0.3203295469 0.2020268318 0.3329155743 0.0173289545 0.0712620000 380495425 0 402718720 0.2212284356 -0.0195805784 -0.6100960970 878 35.0800000000 0.3173472583 0.2021581763 0.3329155743 0.0173377183 0.0785250000 380641065 0 402718720 0.2283601761 -0.0272303149 -0.6012908220 879 35.1200000000 0.3155143857 0.2022871367 0.3329155743 0.0173297450 0.0316410000 376517960 0 402718720 0.2271380574 -0.0256443322 -0.5968939066 880 35.1600000000 0.3136345148 0.2024136678 0.3329155743 0.0173336869 0.0321100000 376522872 0 402718720 0.2244342566 -0.0291198157 -0.5921179056 881 35.2000000000 0.3136827052 0.2025399664 0.3329155743 0.0173361246 0.0420260000 376522476 0 402718720 0.2227548361 -0.0276357140 -0.5897254944 882 35.2400000000 0.3131928742 0.2026654232 0.3329155743 0.0173301786 0.0318050000 376524704 0 402718720 0.2191800624 -0.0258221962 -0.5870853662 883 35.2800000000 0.3125626743 0.2027898821 0.3329155743 0.0173238121 0.0318680000 376529596 0 402718720 0.2170051783 -0.0297177564 -0.5835829377 884 35.3200000000 0.3160364926 0.2029179892 0.3329155743 0.0173158665 0.0320560000 376532684 0 402718720 0.2123949379 -0.0259524863 -0.5861544609 885 35.3600000000 0.3146518171 0.2030442421 0.3329155743 0.0173078649 0.0435730000 376531472 0 402718720 0.2101195306 -0.0257925298 -0.5826081038 886 35.4000000000 0.3142086864 0.2031697098 0.3329155743 0.0173001011 0.0295390000 376527976 0 402718720 0.2075856328 -0.0284109563 -0.5796865821 887 35.4400000000 0.3156552911 0.2032965256 0.3329155743 0.0172913748 0.0425020000 376536908 0 402718720 0.2043673247 -0.0299285538 -0.5793325305 888 35.4800000000 0.3100276887 0.2034167184 0.3329155743 0.0172822596 0.0301720000 376535528 0 402718720 0.2022291720 -0.0287719276 -0.5713911057 889 35.5200000000 0.3092215061 0.2035357339 0.3329155743 0.0172736731 0.0300190000 376541680 0 402718720 0.2017406374 -0.0270550828 -0.5681455135 890 35.5600000000 0.3065993190 0.2036515356 0.3329155743 0.0172657246 0.0292550000 376543468 0 402718720 0.2009067237 -0.0218201838 -0.5632495880 891 35.6000000000 0.3040451109 0.2037642108 0.3329155743 0.0172561199 0.0292290000 376549704 0 402718720 0.2003485560 -0.0210293066 -0.5581309199 892 35.6400000000 0.3068423867 0.2038797693 0.3329155743 0.0172522952 0.0293530000 376551920 0 402718720 0.1950195283 -0.0242819674 -0.5603172183 893 35.6800000000 0.3131444156 0.2040021261 0.3329155743 0.0172464910 0.0295600000 376556692 0 402718720 0.1919355541 -0.0215535033 -0.5658503175 894 35.7200000000 0.3093494475 0.2041199643 0.3329155743 0.0172377129 0.0407780000 376556744 0 402718720 0.1914263219 -0.0207291767 -0.5597513914 895 35.7600000000 0.3090561628 0.2042372115 0.3329155743 0.0172299970 0.0280420000 376555800 0 402718720 0.1885321438 -0.0210887231 -0.5582369566 896 35.8000000000 0.3095304966 0.2043547263 0.3329155743 0.0172215223 0.0278240000 376558348 0 402718720 0.1858744919 -0.0184412524 -0.5575721264 897 35.8400000000 0.3104121685 0.2044729620 0.3329155743 0.0172157565 0.0272760000 376556384 0 402718720 0.1820743978 -0.0226323716 -0.5577028394 898 35.8800000000 0.3102424741 0.2045907454 0.3329155743 0.0172076412 0.0278930000 376565376 0 402718720 0.1788612157 -0.0214997977 -0.5567294359 899 35.9200000000 0.3013213575 0.2046983434 0.3329155743 0.0172080325 0.0278760000 376563540 0 402718720 0.1830114722 -0.0106039569 -0.5444982648 900 35.9600000000 0.3055148721 0.2048103618 0.3329155743 0.0172136982 0.0272300000 376566764 0 402718720 0.1753785014 -0.0214513876 -0.5497773290 901 36.0000000000 0.3039370179 0.2049203803 0.3329155743 0.0172086899 0.0382090000 376571088 0 402718720 0.1760337353 -0.0141807562 -0.5472933054 902 36.0400000000 0.3011075258 0.2050270179 0.3329155743 0.0172044153 0.0280990000 376576488 0 402718720 0.1719862074 -0.0228469055 -0.5441873670 903 36.0800000000 0.3038349450 0.2051364398 0.3329155743 0.0171971263 0.0278770000 376576840 0 402718720 0.1699412465 -0.0169275850 -0.5468730927 904 36.1200000000 0.2994705439 0.2052407917 0.3329155743 0.0171891244 0.0273120000 376574832 0 402718720 0.1703739911 -0.0122163165 -0.5412563682 905 36.1600000000 0.3033195734 0.2053491660 0.3329155743 0.0171914284 0.0278980000 376581828 0 402718720 0.1617254317 -0.0184182748 -0.5467271209 906 36.2000000000 0.3075509667 0.2054619715 0.3329155743 0.0171875761 0.0525390000 376579236 0 402718720 0.1597045511 -0.0241613612 -0.5505533814 907 36.2400000000 0.3026843369 0.2055691627 0.3329155743 0.0171807119 0.0264540000 376580404 0 402718720 0.1591196060 -0.0183913969 -0.5454099774 908 36.2800000000 0.3065936565 0.2056804231 0.3329155743 0.0171732881 0.0467350000 376585544 0 402718720 0.1564297974 -0.0200743675 -0.5499678850 909 36.3200000000 0.2987056971 0.2057827611 0.3329155743 0.0171655664 0.0265790000 376586832 0 402718720 0.1556249559 -0.0209445283 -0.5408003926 910 36.3600000000 0.2994973063 0.2058857442 0.3329155743 0.0171562445 0.0268000000 376592680 0 402718720 0.1544937491 -0.0206289366 -0.5410811901 911 36.4000000000 0.2946637571 0.2059831953 0.3329155743 0.0171489331 0.0274850000 376595400 0 402718720 0.1508614272 -0.0224313140 -0.5365252495 912 36.4400000000 0.2983218133 0.2060844438 0.3329155743 0.0171417223 0.0380110000 376597416 0 402718720 0.1473199725 -0.0185337178 -0.5409896970 913 36.4800000000 0.3018748164 0.2061893621 0.3329155743 0.0171420040 0.0263660000 376597248 0 402718720 0.1416348666 -0.0278760791 -0.5451019406 914 36.5200000000 0.3014197648 0.2062935529 0.3329155743 0.0171337714 0.0264740000 376601532 0 402718720 0.1393198371 -0.0248300117 -0.5447456241 915 36.5600000000 0.2986499667 0.2063944889 0.3329155743 0.0171262509 0.0380320000 376603144 0 402718720 0.1372212321 -0.0257686861 -0.5420150161 916 36.6000000000 0.2955736816 0.2064918461 0.3329155743 0.0171175170 0.0265950000 376606808 0 402718720 0.1362004727 -0.0239658393 -0.5383670330 917 36.6400000000 0.2982661724 0.2065919271 0.3329155743 0.0171109336 0.0369360000 376607748 0 402718720 0.1309049278 -0.0266221296 -0.5423634648 918 36.6800000000 0.3033696413 0.2066973495 0.3329155743 0.0171112685 0.0261620000 376609272 0 402718720 0.1326226443 -0.0143883424 -0.5469152331 919 36.7200000000 0.2976081073 0.2067962730 0.3329155743 0.0171038961 0.0267260000 376615196 0 402718720 0.1292590946 -0.0199270975 -0.5407685637 920 36.7600000000 0.2989779413 0.2068964705 0.3329155743 0.0170947615 0.0371410000 376614804 0 402718720 0.1303424090 -0.0210875385 -0.5409900546 921 36.8000000000 0.2970024645 0.2069943054 0.3329155743 0.0170862581 0.0259390000 376615892 0 402718720 0.1272102445 -0.0219109897 -0.5391531587 922 36.8400000000 0.2963952422 0.2070912696 0.3329155743 0.0170775812 0.0387650000 376619208 0 402718720 0.1281806231 -0.0186298639 -0.5372079015 923 36.8800000000 0.2988656759 0.2071907001 0.3329155743 0.0170700872 0.0262050000 376625836 0 402718720 0.1245417446 -0.0169657134 -0.5405551195 924 36.9200000000 0.3071808517 0.2072989146 0.3329155743 0.0170729946 0.0260800000 376626464 0 402718720 0.1188960522 -0.0238914639 -0.5506901145 925 36.9600000000 0.2980889678 0.2073970660 0.3329155743 0.0170682647 0.0260400000 376629944 0 402718720 0.1192994863 -0.0216987804 -0.5402857065 926 37.0000000000 0.3008435369 0.2074979801 0.3329155743 0.0170599021 0.0263550000 376631264 0 402718720 0.1166036949 -0.0183275957 -0.5438976288 927 37.0400000000 0.2979431152 0.2075955477 0.3329155743 0.0170518656 0.0261210000 376631712 0 402718720 0.1161586121 -0.0163841918 -0.5406288505 928 37.0800000000 0.2991335094 0.2076941877 0.3329155743 0.0170433509 0.0259540000 376633384 0 402718720 0.1159196794 -0.0151036726 -0.5409751534 929 37.1200000000 0.3015940487 0.2077952640 0.3329155743 0.0170357496 0.0380770000 376639444 0 402718720 0.1163878366 -0.0120863616 -0.5428728461 930 37.1600000000 0.2937501371 0.2078876886 0.3329155743 0.0170391094 0.0266120000 376643236 0 402718720 0.1160602942 -0.0212353189 -0.5334914327 931 37.2000000000 0.2984878719 0.2079850035 0.3329155743 0.0170304956 0.0261790000 376645952 0 402718720 0.1172431037 -0.0161990579 -0.5378234386 932 37.2400000000 0.2947076857 0.2080780536 0.3329155743 0.0170255753 0.0256290000 376642872 0 402718720 0.1157208085 -0.0201660711 -0.5337625146 933 37.2800000000 0.3009487987 0.2081775935 0.3329155743 0.0170186838 0.0264410000 376651600 0 402718720 0.1126672477 -0.0127652045 -0.5413238406 934 37.3200000000 0.3019022346 0.2082779411 0.3329155743 0.0170143934 0.0260410000 376651708 0 402718720 0.1108797342 -0.0171965715 -0.5420475602 935 37.3600000000 0.2967538238 0.2083725677 0.3329155743 0.0170122409 0.0260730000 376653348 0 402718720 0.1109935418 -0.0184982289 -0.5361254215 936 37.4000000000 0.2965096235 0.2084667312 0.3329155743 0.0170048273 0.0264430000 376658164 0 402718720 0.1103457212 -0.0181481708 -0.5359094739 937 37.4400000000 0.2942149639 0.2085582448 0.3329155743 0.0169988968 0.0257430000 376657428 0 402718720 0.1140438765 -0.0109794065 -0.5323043466 938 37.4800000000 0.2985372543 0.2086541713 0.3329155743 0.0169909346 0.0252760000 376654744 0 402718720 0.1124281436 -0.0086909011 -0.5375878215 939 37.5200000000 0.3028711677 0.2087545089 0.3329155743 0.0169880256 0.0254850000 376660884 0 402718720 0.1086857915 -0.0148390960 -0.5435742736 940 37.5600000000 0.3027654588 0.2088545205 0.3329155743 0.0169862910 0.0257490000 376667892 0 402718720 0.1054659039 -0.0240448229 -0.5439995527 941 37.6000000000 0.2964773774 0.2089476373 0.3329155743 0.0169807015 0.0254380000 376667324 0 402718720 0.1091043800 -0.0209366847 -0.5360660553 942 37.6400000000 0.3008885980 0.2090452391 0.3329155743 0.0169731759 0.0261790000 376672432 0 402718720 0.1114820391 -0.0123702493 -0.5405510068 943 37.6800000000 0.3062583804 0.2091483284 0.3329155743 0.0169777199 0.0262440000 376675208 0 402718720 0.1052669659 -0.0197155029 -0.5482625365 944 37.7200000000 0.3052894771 0.2092501728 0.3329155743 0.0169742176 0.0366280000 376674196 0 402718720 0.1088103652 -0.0073019397 -0.5468659401 945 37.7600000000 0.2969245017 0.2093429499 0.3329155743 0.0169741891 0.0258480000 376676176 0 402718720 0.1148071438 -0.0033121007 -0.5360502601 946 37.8000000000 0.2947845757 0.2094332687 0.3329155743 0.0169705031 0.0370590000 376679628 0 402718720 0.1154417992 -0.0100999391 -0.5333109498 947 37.8400000000 0.2902411819 0.2095185991 0.3329155743 0.0169648279 0.0262940000 376683768 0 402718720 0.1160476506 -0.0096635008 -0.5282017589 948 37.8800000000 0.2945378423 0.2096082819 0.3329155743 0.0169610573 0.0366390000 376683552 0 402718720 0.1199676394 0.0030037335 -0.5316802859 949 37.9200000000 0.2933180332 0.2096964903 0.3329155743 0.0169787750 0.0364790000 376687220 0 402718720 0.1140311807 -0.0151899140 -0.5323505998 950 37.9600000000 0.3009248078 0.2097925201 0.3329155743 0.0169718798 0.0368560000 376690808 0 402718720 0.1133142263 -0.0083796931 -0.5414686203 951 38.0000000000 0.3015127182 0.2098889661 0.3329155743 0.0169649204 0.0374730000 376692620 0 402718720 0.1124907658 -0.0119391810 -0.5423895717 952 38.0400000000 0.3004462719 0.2099840893 0.3329155743 0.0169584060 0.0253860000 376693956 0 402718720 0.1093440875 -0.0087033007 -0.5424825549 953 38.0800000000 0.3064248264 0.2100852863 0.3329155743 0.0169512307 0.0252430000 376693864 0 402718720 0.1135785431 -0.0023742677 -0.5480198264 954 38.1200000000 0.3081312776 0.2101880599 0.3329155743 0.0169580530 0.0252120000 376696992 0 402718720 0.1102729291 -0.0190544464 -0.5501884818 955 38.1600000000 0.2976552844 0.2102796486 0.3329155743 0.0169559924 0.0257150000 376703264 0 402718720 0.1128197908 -0.0130440202 -0.5386160016 956 38.2000000000 0.2931948304 0.2103663800 0.3329155743 0.0169488132 0.0253430000 376702236 0 402718720 0.1132153645 -0.0092022549 -0.5342789888 957 38.2400000000 0.2895430028 0.2104491142 0.3329155743 0.0169499163 0.0248200000 376703464 0 402718720 0.1199061573 0.0013628546 -0.5283311605 958 38.2800000000 0.2913907468 0.2105336044 0.3329155743 0.0169461173 0.0493620000 376708756 0 402718720 0.1164683774 -0.0078050662 -0.5314713717 959 38.3200000000 0.2929085195 0.2106195011 0.3329155743 0.0169411618 0.0250770000 376711224 0 402718720 0.1175272167 0.0006768205 -0.5333344340 960 38.3600000000 0.2912545502 0.2107034959 0.3329155743 0.0169332176 0.0250540000 376710060 0 402718720 0.1183625311 0.0029333849 -0.5312896967 961 38.4000000000 0.2947809398 0.2107909855 0.3329155743 0.0169310010 0.0246160000 376712208 0 402718720 0.1162631139 -0.0085610785 -0.5358027220 962 38.4400000000 0.3020882905 0.2108858891 0.3329155743 0.0169301635 0.0252270000 376716764 0 402718720 0.1121579260 0.0006282059 -0.5457670689 963 38.4800000000 0.2956373692 0.2109738969 0.3329155743 0.0169296064 0.0253470000 376717148 0 402718720 0.1155958250 -0.0113562755 -0.5373311043 964 38.5200000000 0.3009033501 0.2110671847 0.3329155743 0.0169335851 0.0258790000 376724296 0 402718720 0.1131604761 0.0051696212 -0.5446596146 965 38.5600000000 0.3053027391 0.2111648381 0.3329155743 0.0169255184 0.0249010000 376722272 0 402718720 0.1136545092 0.0025331355 -0.5492764115 966 38.6000000000 0.2939398885 0.2112505266 0.3329155743 0.0169239389 0.0252880000 376726168 0 402718720 0.1163422316 -0.0028732270 -0.5362765193 967 38.6400000000 0.2971555591 0.2113393632 0.3329155743 0.0169163867 0.0369340000 376728624 0 402718720 0.1215112135 -0.0034080260 -0.5379574895 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:26:18 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0234390000 348371200 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0015366985 0.0007683493 0.0015366985 0.0014142410 0.0341310000 356516126 0 402718720 0.0006963463 0.0000178619 -0.0003427534 3 0.0800000000 0.0016735863 0.0010700950 0.0016735863 0.0011899923 0.0329890000 356446883 0 402718720 -0.0042211143 0.0007406494 -0.0004876328 4 0.1200000000 0.0024419085 0.0014130483 0.0024419085 0.0014277847 0.0318700000 356416730 0 402718720 -0.0008867451 0.0010379477 -0.0008999060 5 0.1600000000 0.0039741946 0.0019252776 0.0039741946 0.0016265168 0.0315570000 356419874 0 402718720 -0.0042848135 -0.0013940356 0.0008131070 6 0.2000000000 0.0014003824 0.0018377951 0.0039741946 0.0019230322 0.0322600000 356427202 0 402718720 -0.0041308869 0.0017212915 -0.0003472701 7 0.2400000000 0.0010873142 0.0017305835 0.0039741946 0.0017641345 0.0322640000 356430022 0 402718720 -0.0050418065 0.0021759116 -0.0001017336 8 0.2800000000 0.0027016464 0.0018519664 0.0039741946 0.0017276818 0.0318960000 356432746 0 402718720 -0.0046347482 0.0026124960 -0.0001455753 9 0.3200000000 0.0015491414 0.0018183191 0.0039741946 0.0018703967 0.0322920000 356435798 0 402718720 -0.0078405319 0.0016512125 -0.0006178146 10 0.3600000000 0.0028334318 0.0019198304 0.0039741946 0.0018593079 0.0323790000 356439614 0 402718720 -0.0068665133 0.0035439760 -0.0001547314 11 0.4000000000 0.0011676110 0.0018514468 0.0039741946 0.0020431603 0.0322420000 356443014 0 402718720 -0.0089891246 0.0010386308 0.0009926157 12 0.4400000000 0.0008785391 0.0017703712 0.0039741946 0.0022557723 0.0319000000 356445430 0 402718720 -0.0096634757 0.0001935088 0.0000033209 13 0.4800000000 0.0022112497 0.0018042849 0.0039741946 0.0023560131 0.0318030000 356447906 0 402718720 -0.0106707150 -0.0000895370 0.0001798930 14 0.5200000000 0.0030858414 0.0018958247 0.0039741946 0.0022856067 0.0318380000 356451854 0 402718720 -0.0098020658 0.0009585606 -0.0008529733 15 0.5600000000 0.0014060595 0.0018631737 0.0039741946 0.0022711367 0.0324880000 356454530 0 402718720 -0.0156703815 0.0014727294 0.0008822269 16 0.6000000000 0.0016274810 0.0018484429 0.0039741946 0.0022656387 0.0318890000 356457014 0 402718720 -0.0132763758 0.0015437255 -0.0000447271 17 0.6400000000 0.0036871072 0.0019565996 0.0039741946 0.0022674515 0.0318880000 356459902 0 402718720 -0.0145988856 -0.0030452055 -0.0022173140 18 0.6800000000 0.0015628892 0.0019347268 0.0039741946 0.0022558057 0.0324070000 356465094 0 402718720 -0.0173929222 -0.0003607706 -0.0016158025 19 0.7200000000 0.0052115913 0.0021071933 0.0052115913 0.0022556278 0.0327720000 356468642 0 402718720 -0.0179517865 -0.0046272194 -0.0016029361 20 0.7600000000 0.0028862215 0.0021461447 0.0052115913 0.0023998337 0.0320360000 356472718 0 402718720 -0.0215866417 -0.0035259330 -0.0019827508 21 0.8000000000 0.0063275355 0.0023452586 0.0063275355 0.0023765011 0.0318510000 356477586 0 402718720 -0.0200570486 -0.0022941725 -0.0018668360 22 0.8400000000 0.0042913128 0.0024337156 0.0063275355 0.0023413879 0.0328050000 356482610 0 402718720 -0.0283920206 -0.0035139772 -0.0026809138 23 0.8800000000 0.0066685574 0.0026178392 0.0066685574 0.0023221498 0.0326010000 356485550 0 402718720 -0.0246901587 -0.0034089976 -0.0044475487 24 0.9200000000 0.0057054879 0.0027464912 0.0066685574 0.0023081019 0.0327730000 356491030 0 402718720 -0.0348994806 -0.0033104646 -0.0056543429 25 0.9600000000 0.0055181221 0.0028573564 0.0066685574 0.0022774061 0.0323620000 356494566 0 402718720 -0.0358598940 -0.0017885674 -0.0057806456 26 1.0000000000 0.0069222231 0.0030136975 0.0069222231 0.0022437816 0.0318870000 356496754 0 402718720 -0.0404531658 -0.0023146968 -0.0057929303 27 1.0400000000 0.0060039097 0.0031244461 0.0069222231 0.0022860279 0.0323930000 356501174 0 402718720 -0.0465699174 -0.0008327917 -0.0066495575 28 1.0800000000 0.0051015019 0.0031950552 0.0069222231 0.0025453202 0.0321210000 356506158 0 402718720 -0.0554234795 -0.0041456232 -0.0077031013 29 1.1200000000 0.0036743453 0.0032115824 0.0069222231 0.0026425882 0.0317430000 356510766 0 402718720 -0.0611919314 -0.0012619670 -0.0112496382 30 1.1600000000 0.0049112891 0.0032682393 0.0069222231 0.0027329887 0.0317880000 356515358 0 402718720 -0.0683106035 -0.0017751934 -0.0072918683 31 1.2000000000 0.0051721591 0.0033296561 0.0069222231 0.0027166468 0.0314360000 356519742 0 402718720 -0.0744710416 -0.0005747064 -0.0098682940 32 1.2400000000 0.0060897288 0.0034159084 0.0069222231 0.0027397648 0.0315750000 356523746 0 402718720 -0.0804964304 -0.0008306702 -0.0123685375 33 1.2800000000 0.0051692920 0.0034690412 0.0069222231 0.0027950972 0.0313730000 356528586 0 402718720 -0.0883311629 -0.0033667530 -0.0119779259 34 1.3200000000 0.0024701313 0.0034396615 0.0069222231 0.0028106863 0.0317860000 356537838 0 402718720 -0.1188199371 -0.0023373729 -0.0118304668 35 1.3600000000 0.0053815413 0.0034951438 0.0069222231 0.0031660482 0.0315830000 356541150 0 402718720 -0.1183462515 -0.0009737088 -0.0151321115 36 1.4000000000 0.0084955515 0.0036340440 0.0084955515 0.0037727239 0.0309160000 356543422 0 402718720 -0.1215044707 -0.0017551981 -0.0180687532 37 1.4400000000 0.0043734806 0.0036540288 0.0084955515 0.0037730877 0.0314170000 356547362 0 402718720 -0.1356615871 -0.0009988463 -0.0153372576 38 1.4800000000 0.0034748858 0.0036493145 0.0084955515 0.0037293748 0.0314620000 356551834 0 402718720 -0.1485827565 -0.0012805774 -0.0154172396 39 1.5200000000 0.0048651542 0.0036804899 0.0084955515 0.0037001453 0.0307650000 356555158 0 402718720 -0.1502835006 -0.0006866154 -0.0177778378 40 1.5600000000 0.0051729139 0.0037178005 0.0084955515 0.0037185529 0.0308860000 356558698 0 402718720 -0.1610693038 -0.0062329560 -0.0188449603 41 1.6000000000 0.0021421215 0.0036793693 0.0084955515 0.0038132693 0.0304960000 356562722 0 402718720 -0.1732441038 -0.0043079196 -0.0152004035 42 1.6400000000 0.0006390783 0.0036069814 0.0084955515 0.0037789036 0.0308250000 356568206 0 402718720 -0.1881743670 -0.0029992564 -0.0126480740 43 1.6800000000 0.0037401016 0.0036100772 0.0084955515 0.0037519153 0.0311720000 356570566 0 402718720 -0.1921056360 -0.0012040427 -0.0101364125 44 1.7200000000 0.0040937671 0.0036210702 0.0084955515 0.0037698529 0.0307330000 356574646 0 402718720 -0.1980177462 -0.0019157571 -0.0110754687 45 1.7600000000 0.0021833212 0.0035891202 0.0084955515 0.0038670744 0.0306140000 356577538 0 402718720 -0.2117488980 0.0000622829 -0.0072801579 46 1.8000000000 0.0027624040 0.0035711481 0.0084955515 0.0038641893 0.0314980000 356581406 0 402718720 -0.2168426514 0.0019075929 -0.0079961158 47 1.8400000000 0.0006985636 0.0035100293 0.0084955515 0.0039453864 0.0314120000 356583906 0 402718720 -0.2193665504 -0.0025282106 -0.0089463759 48 1.8800000000 0.0038367731 0.0035168364 0.0084955515 0.0039735882 0.0315300000 356586154 0 402718720 -0.2216939330 0.0003374711 -0.0076323636 49 1.9200000000 0.0014716848 0.0034750986 0.0084955515 0.0039411095 0.0317370000 356589034 0 402718720 -0.2295423597 -0.0015997561 -0.0065240506 50 1.9600000000 0.0012295777 0.0034301882 0.0084955515 0.0039093497 0.0313170000 356591986 0 402718720 -0.2458912283 -0.0012703732 -0.0008017588 51 2.0000000000 0.0042459159 0.0034461829 0.0084955515 0.0039111294 0.0307660000 356594038 0 402718720 -0.2402105927 0.0001845707 -0.0039967410 52 2.0400000000 0.0020325643 0.0034189979 0.0084955515 0.0039042217 0.0309130000 356597366 0 402718720 -0.2493748814 -0.0009195153 -0.0049255993 53 2.0800000000 0.0019934399 0.0033921006 0.0084955515 0.0039336280 0.0313630000 356599666 0 402718720 -0.2513683140 -0.0046455353 -0.0076894462 54 2.1200000000 0.0017977402 0.0033625754 0.0084955515 0.0039768574 0.0318400000 356602474 0 402718720 -0.2636341751 -0.0065296772 -0.0013560448 55 2.1600000000 0.0031251148 0.0033582579 0.0084955515 0.0040931827 0.0316200000 356604958 0 402718720 -0.2658417821 -0.0038843530 -0.0002574511 56 2.2000000000 0.0037599646 0.0033654313 0.0084955515 0.0041210097 0.0323510000 356608666 0 402718720 -0.2879450917 -0.0032014220 0.0078390613 57 2.2400000000 0.0034323053 0.0033666045 0.0084955515 0.0040981661 0.0323470000 356610074 0 402718720 -0.2906554639 -0.0046402756 0.0086647142 58 2.2800000000 0.0028763323 0.0033581515 0.0084955515 0.0041095225 0.0308040000 356611946 0 402718720 -0.3015157878 -0.0070214076 0.0108019002 59 2.3200000000 0.0040021837 0.0033690673 0.0084955515 0.0042301994 0.0310310000 356614702 0 402718720 -0.3163929284 -0.0062331343 0.0176663976 60 2.3600000000 0.0015174515 0.0033382071 0.0084955515 0.0043935692 0.0313310000 356616922 0 402718720 -0.3151232600 -0.0067201960 0.0128477588 61 2.4000000000 0.0024173113 0.0033231104 0.0084955515 0.0044820654 0.0314580000 356620814 0 402718720 -0.3227944672 -0.0067204200 0.0140594598 62 2.4400000000 0.0070320549 0.0033829321 0.0084955515 0.0046790310 0.0315890000 356625118 0 402718720 -0.3429005146 -0.0030578985 0.0256167036 63 2.4800000000 0.0032967173 0.0033815636 0.0084955515 0.0048443348 0.0305400000 356629382 0 402718720 -0.3562960625 -0.0098323328 0.0276399348 64 2.5200000000 0.0035684297 0.0033844834 0.0084955515 0.0051742759 0.0305170000 356634402 0 402718720 -0.3673578501 -0.0060384562 0.0316704437 65 2.5600000000 0.0084913699 0.0034630509 0.0084955515 0.0053284232 0.0303000000 356637418 0 402718720 -0.3869245052 -0.0020464021 0.0356581956 66 2.6000000000 0.0042739622 0.0034753374 0.0084955515 0.0055223569 0.0303430000 356654814 0 402718720 -0.3964269757 -0.0081052221 0.0365630388 67 2.6400000000 0.0017520259 0.0034496163 0.0084955515 0.0055664105 0.0302300000 356658966 0 402718720 -0.4037500322 -0.0040249578 0.0384061672 68 2.6800000000 0.0025226397 0.0034359843 0.0084955515 0.0055540705 0.0295520000 356662030 0 402718720 -0.4143118560 -0.0035463143 0.0383826233 69 2.7200000000 0.0021366219 0.0034171530 0.0084955515 0.0055190280 0.0294910000 356666686 0 402718720 -0.4237728715 -0.0024020730 0.0410566628 70 2.7600000000 0.0085287718 0.0034901761 0.0085287718 0.0055296827 0.0297500000 356671506 0 402718720 -0.4370636046 0.0018864945 0.0460007973 71 2.8000000000 0.0036221743 0.0034920352 0.0085287718 0.0055735422 0.0301130000 356674286 0 402718720 -0.4415324926 0.0009055622 0.0383058265 72 2.8400000000 0.0100167058 0.0035826557 0.0100167058 0.0062933864 0.0296140000 356677934 0 402718720 -0.4636234939 0.0027441371 0.0465906039 73 2.8800000000 0.0069056051 0.0036281755 0.0100167058 0.0063656488 0.0322940000 357092051 0 402718720 -0.4719093442 0.0047006076 0.0453056395 74 2.9200000000 0.0073690456 0.0036787278 0.0100167058 0.0064465350 0.0687810000 357620163 0 402718720 -0.4743598104 0.0045573488 0.0422142968 75 2.9600000000 0.0061031044 0.0037110528 0.0100167058 0.0064980087 0.0898970000 358851666 0 402718720 -0.4749307334 0.0097749233 0.0386183709 76 3.0000000000 0.0057909447 0.0037384198 0.0100167058 0.0065370097 0.0387140000 359650011 0 402718720 -0.4722983241 0.0140695013 0.0308060423 77 3.0400000000 0.0172208138 0.0039135159 0.0172208138 0.0067874421 0.0444520000 359330213 0 402718720 -0.4792052507 0.0009563460 0.0163593143 78 3.0800000000 0.0192016121 0.0041095171 0.0192016121 0.0067522098 0.0295690000 357610982 0 402718720 -0.4793631434 0.0011296439 0.0093622953 79 3.1200000000 0.0161556322 0.0042619996 0.0192016121 0.0067165714 0.0293920000 357616262 0 402718720 -0.4857347012 0.0082635973 0.0074804351 80 3.1600000000 0.0184241142 0.0044390260 0.0192016121 0.0066973475 0.0292670000 357621058 0 402718720 -0.4888948500 0.0075686085 0.0029587373 81 3.2000000000 0.0172043052 0.0045966220 0.0192016121 0.0066609706 0.0297510000 357627130 0 402718720 -0.4996130764 0.0076140622 0.0050039366 82 3.2400000000 0.0176329035 0.0047556011 0.0192016121 0.0066791982 0.0297330000 357632446 0 402718720 -0.5077912807 0.0072174710 0.0037622899 83 3.2800000000 0.0191594269 0.0049291412 0.0192016121 0.0067349424 0.0308740000 357636670 0 402718720 -0.5152910352 0.0067972750 0.0010796785 84 3.3200000000 0.0182344429 0.0050875376 0.0192016121 0.0067147560 0.0294720000 357641934 0 402718720 -0.5233977437 0.0072017112 -0.0034796447 85 3.3600000000 0.0183498878 0.0052435653 0.0192016121 0.0066970980 0.0286940000 357646786 0 402718720 -0.5416426063 0.0081223277 0.0011872500 86 3.4000000000 0.0194993727 0.0054093305 0.0194993727 0.0067248841 0.0281470000 357650698 0 402718720 -0.5590772033 0.0087484680 0.0072125047 87 3.4400000000 0.0171187744 0.0055439218 0.0194993727 0.0068378685 0.0290680000 357655990 0 402718720 -0.5672415495 0.0102170426 0.0054801852 88 3.4800000000 0.0218867362 0.0057296356 0.0218867362 0.0070135666 0.0285410000 357660046 0 402718720 -0.5821813941 0.0051346757 0.0066835582 89 3.5200000000 0.0202732459 0.0058930469 0.0218867362 0.0071312579 0.0283910000 357663930 0 402718720 -0.5927610397 0.0089647919 0.0067750514 90 3.5600000000 0.0216920972 0.0060685919 0.0218867362 0.0071937269 0.0292130000 357998802 0 402718720 -0.6020709276 0.0070137493 0.0056923181 91 3.6000000000 0.0188405830 0.0062089435 0.0218867362 0.0072497112 0.0820670000 358188598 0 402718720 -0.6129071116 0.0060010110 0.0086710006 92 3.6400000000 0.0218662880 0.0063791320 0.0218867362 0.0072683251 0.0663700000 360507982 0 402718720 -0.6275706291 0.0045795860 0.0111067742 93 3.6800000000 0.0193126686 0.0065182023 0.0218867362 0.0072575802 0.0553460000 360471723 0 402718720 -0.6371968389 0.0116218440 0.0138292164 94 3.7200000000 0.0180023983 0.0066403746 0.0218867362 0.0072213222 0.0295710000 358164458 0 402718720 -0.6430789232 0.0099460483 0.0119086951 95 3.7600000000 0.0183728803 0.0067638746 0.0218867362 0.0072262162 0.0290230000 358167938 0 402718720 -0.6546483636 0.0090755662 0.0159753412 96 3.8000000000 0.0187008083 0.0068882177 0.0218867362 0.0071947552 0.0296270000 358170578 0 402718720 -0.6652489901 0.0076937256 0.0174069107 97 3.8400000000 0.0197884031 0.0070212093 0.0218867362 0.0071668296 0.0292770000 358173714 0 402718720 -0.6688904762 0.0016463986 0.0176319480 98 3.8800000000 0.0205314327 0.0071590687 0.0218867362 0.0071314370 0.0295440000 358178462 0 402718720 -0.6878303289 0.0049005579 0.0229548961 99 3.9200000000 0.0199770536 0.0072885433 0.0218867362 0.0071016540 0.0292190000 358181686 0 402718720 -0.6911029816 0.0048904475 0.0239827186 100 3.9600000000 0.0192581825 0.0074082397 0.0218867362 0.0070754156 0.0289180000 358184238 0 402718720 -0.7017621398 0.0082325861 0.0322852731 101 4.0000000000 0.0190807544 0.0075238092 0.0218867362 0.0070430979 0.0307640000 358186694 0 402718720 -0.7106599212 0.0075862072 0.0388347358 102 4.0400000000 0.0213039238 0.0076589083 0.0218867362 0.0070243677 0.0279290000 358189518 0 402718720 -0.7168762088 0.0068639414 0.0422167927 103 4.0800000000 0.0203357730 0.0077819847 0.0218867362 0.0069912526 0.0280800000 358194794 0 402718720 -0.7257852554 0.0043864641 0.0467905104 104 4.1200000000 0.0191223137 0.0078910263 0.0218867362 0.0069750038 0.0282320000 358197590 0 402718720 -0.7345090508 -0.0006473400 0.0561002493 105 4.1600000000 0.0167009979 0.0079749308 0.0218867362 0.0069696365 0.0280260000 358200650 0 402718720 -0.7369595766 0.0023031412 0.0598113090 106 4.2000000000 0.0213093124 0.0081007269 0.0218867362 0.0069603393 0.0282840000 358206670 0 402718720 -0.7490872741 0.0038765678 0.0668576211 107 4.2400000000 0.0195494555 0.0082077243 0.0218867362 0.0069429913 0.0276550000 358208338 0 402718720 -0.7476130724 0.0008133147 0.0629905015 108 4.2800000000 0.0174122900 0.0082929518 0.0218867362 0.0069136235 0.0281740000 358212482 0 402718720 -0.7525116801 -0.0031245351 0.0676754564 109 4.3200000000 0.0189023968 0.0083902861 0.0218867362 0.0068942865 0.0273420000 358214438 0 402718720 -0.7568905950 -0.0027379282 0.0706405789 110 4.3600000000 0.0209206901 0.0085041989 0.0218867362 0.0068758372 0.0279110000 358219806 0 402718720 -0.7683027387 -0.0010952801 0.0815364420 111 4.4000000000 0.0197785590 0.0086057697 0.0218867362 0.0068798643 0.0278320000 358223286 0 402718720 -0.7729316950 -0.0035158470 0.0874681324 112 4.4400000000 0.0198049657 0.0087057625 0.0218867362 0.0068899443 0.0275950000 358228114 0 402718720 -0.7814931870 -0.0014734715 0.0960555226 113 4.4800000000 0.0191834960 0.0087984858 0.0218867362 0.0068963054 0.0284210000 358232738 0 402718720 -0.7842405438 -0.0031269481 0.0984223932 114 4.5200000000 0.0185212269 0.0088837730 0.0218867362 0.0069192236 0.0274540000 358235674 0 402718720 -0.7949827313 -0.0019797701 0.1118728667 115 4.5600000000 0.0232603755 0.0090087870 0.0232603755 0.0069831963 0.0273340000 358240110 0 402718720 -0.7982149124 -0.0068389867 0.1106975079 116 4.6000000000 0.0225876831 0.0091258464 0.0232603755 0.0069975469 0.0294520000 358648671 0 402718720 -0.8105459213 0.0012699533 0.1245578676 117 4.6400000000 0.0226327665 0.0092412902 0.0232603755 0.0070043588 0.0907060000 358856850 0 402718720 -0.8181381226 0.0038681142 0.1345725507 118 4.6800000000 0.0211660806 0.0093423477 0.0232603755 0.0069860613 0.0799470000 361736890 0 402718720 -0.8225556612 0.0027961936 0.1423145682 119 4.7200000000 0.0191619880 0.0094248657 0.0232603755 0.0069595702 0.0368960000 361671350 0 402718720 -0.8261202574 0.0010481067 0.1463185847 120 4.7600000000 0.0179011803 0.0094955017 0.0232603755 0.0069358900 0.0553010000 361445101 0 402718720 -0.8321690559 0.0035394318 0.1557785720 121 4.8000000000 0.0191301070 0.0095751265 0.0232603755 0.0069281187 0.0306770000 358798070 0 402718720 -0.8435511589 0.0058822911 0.1764411330 122 4.8400000000 0.0200305283 0.0096608265 0.0232603755 0.0069038516 0.0318290000 358802558 0 402718720 -0.8460354805 0.0069933590 0.1761627644 123 4.8800000000 0.0205537751 0.0097493871 0.0232603755 0.0068838152 0.0304410000 358805658 0 402718720 -0.8517357111 0.0090708751 0.1822730154 124 4.9200000000 0.0204139668 0.0098353918 0.0232603755 0.0068593501 0.0295360000 358807686 0 402718720 -0.8614283800 0.0126979854 0.1995327473 125 4.9600000000 0.0235403758 0.0099450316 0.0235403758 0.0068421511 0.0291030000 358811622 0 402718720 -0.8687881231 0.0145088732 0.2073381990 126 5.0000000000 0.0190803278 0.0100175340 0.0235403758 0.0068332526 0.0293240000 358816154 0 402718720 -0.8693075180 0.0135700535 0.2112699896 127 5.0400000000 0.0182033759 0.0100819894 0.0235403758 0.0068087241 0.0297510000 358819414 0 402718720 -0.8781980276 0.0177603308 0.2278483212 128 5.0800000000 0.0219295863 0.0101745488 0.0235403758 0.0067922500 0.0294100000 358823950 0 402718720 -0.8870802522 0.0165803134 0.2367873937 129 5.1200000000 0.0165803712 0.0102242063 0.0235403758 0.0067766114 0.0282720000 358825050 0 402718720 -0.8860445619 0.0173750669 0.2394305319 130 5.1600000000 0.0198009722 0.0102978737 0.0235403758 0.0067629425 0.0285190000 358855198 0 402718720 -0.8978469372 0.0164907314 0.2599932253 131 5.2000000000 0.0248728786 0.0104091333 0.0248728786 0.0067689718 0.0285620000 358860302 0 402718720 -0.9061581492 0.0197171718 0.2669060826 132 5.2400000000 0.0210628454 0.0104898433 0.0248728786 0.0067971709 0.0276640000 358861910 0 402718720 -0.9029677510 0.0147490706 0.2614316940 133 5.2800000000 0.0200289786 0.0105615661 0.0248728786 0.0067968177 0.0309140000 359298951 0 402718720 -0.9122647643 0.0164516699 0.2814889848 134 5.3200000000 0.0238151569 0.0106604735 0.0248728786 0.0068144088 0.1009700000 359443914 0 402718720 -0.9241211414 0.0202833787 0.3019657433 135 5.3600000000 0.0215664636 0.0107412586 0.0248728786 0.0068324094 0.0914920000 361851758 0 402718720 -0.9258333445 0.0210866369 0.3025899529 136 5.4000000000 0.0228411872 0.0108302287 0.0248728786 0.0068682146 0.0587330000 362864878 0 402718720 -0.9337023497 0.0195877980 0.3164574802 137 5.4400000000 0.0223112088 0.0109140314 0.0248728786 0.0068961082 0.0651180000 362716021 0 402718720 -0.9372844696 0.0261489060 0.3277897537 138 5.4800000000 0.0201032497 0.0109806200 0.0248728786 0.0069565397 0.0320330000 359454374 0 402718720 -0.9415277839 0.0209119283 0.3313702941 139 5.5200000000 0.0216735024 0.0110575472 0.0248728786 0.0069929858 0.0314850000 359459874 0 402718720 -0.9481036663 0.0227697864 0.3384838998 140 5.5600000000 0.0230178777 0.0111429781 0.0248728786 0.0070505783 0.0311030000 359463470 0 402718720 -0.9598448873 0.0227969792 0.3501377404 141 5.6000000000 0.0201100186 0.0112065741 0.0248728786 0.0070987264 0.0314090000 359466670 0 402718720 -0.9620903134 0.0244776532 0.3558573127 142 5.6400000000 0.0222025048 0.0112840103 0.0248728786 0.0071140455 0.0309670000 359473038 0 402718720 -0.9724363089 0.0272047557 0.3718032837 143 5.6800000000 0.0186915789 0.0113358115 0.0248728786 0.0071912450 0.0306180000 359475422 0 402718720 -0.9750223160 0.0279902518 0.3796508312 144 5.7200000000 0.0169187188 0.0113745816 0.0248728786 0.0072474916 0.0302370000 359480226 0 402718720 -0.9804469347 0.0282712504 0.3841472864 145 5.7600000000 0.0194761399 0.0114304545 0.0248728786 0.0072400266 0.0295400000 359483338 0 402718720 -0.9876809120 0.0293271914 0.3938350677 146 5.8000000000 0.0225255862 0.0115064485 0.0248728786 0.0072252079 0.0294420000 359487342 0 402718720 -0.9958580136 0.0290956423 0.4067015946 147 5.8400000000 0.0180931129 0.0115512558 0.0248728786 0.0072122990 0.0294000000 359488146 0 402718720 -1.0021792650 0.0280469619 0.4250745177 148 5.8800000000 0.0228472725 0.0116275802 0.0248728786 0.0071911293 0.0295790000 359494066 0 402718720 -1.0074231625 0.0285953768 0.4317147434 149 5.9200000000 0.0239552520 0.0117103162 0.0248728786 0.0071703097 0.0286960000 359495318 0 402718720 -1.0117688179 0.0331104137 0.4424601495 150 5.9600000000 0.0191945937 0.0117602114 0.0248728786 0.0071577443 0.0311810000 359952011 0 402718720 -1.0122524500 0.0311448909 0.4461118281 151 6.0000000000 0.0226692036 0.0118324564 0.0248728786 0.0071361877 0.0965850000 360077107 0 402718720 -1.0187989473 0.0318076350 0.4581975043 152 6.0400000000 0.0220106617 0.0118994183 0.0248728786 0.0071232744 0.0919880000 360220403 0 402718720 -1.0216413736 0.0314498320 0.4695594609 153 6.0800000000 0.0224909745 0.0119686441 0.0248728786 0.0071106446 0.0680270000 364101794 0 402718720 -1.0251456499 0.0303451344 0.4800981581 154 6.1200000000 0.0223129019 0.0120358146 0.0248728786 0.0071286046 0.0392640000 364039407 0 402718720 -1.0287567377 0.0317072459 0.4922805130 155 6.1600000000 0.0242507271 0.0121146205 0.0248728786 0.0071670210 0.0704660000 363968127 0 402718720 -1.0324178934 0.0299830996 0.5012360811 156 6.2000000000 0.0236736126 0.0121887166 0.0248728786 0.0072760359 0.0299680000 360086351 0 402718720 -1.0354130268 0.0321881697 0.5173493624 157 6.2400000000 0.0236964971 0.0122620146 0.0248728786 0.0073491910 0.0307310000 360089195 0 402718720 -1.0389716625 0.0328608006 0.5252460837 158 6.2800000000 0.0236302465 0.0123339654 0.0248728786 0.0074391542 0.0290630000 360092215 0 402718720 -1.0390541553 0.0384122021 0.5411679745 159 6.3200000000 0.0203283988 0.0123842449 0.0248728786 0.0074807103 0.0292210000 360096743 0 402718720 -1.0401375294 0.0313652307 0.5462148190 160 6.3600000000 0.0249855630 0.0124630031 0.0249855630 0.0075055769 0.0302620000 360509495 0 402718720 -1.0438132286 0.0352200903 0.5667779446 161 6.4000000000 0.0260925256 0.0125476586 0.0260925256 0.0074884172 0.0919540000 360679303 0 402718720 -1.0439193249 0.0372757800 0.5780738592 162 6.4400000000 0.0255950559 0.0126281980 0.0260925256 0.0074663186 0.0929150000 360855287 0 402718720 -1.0444542170 0.0351213142 0.5873109102 163 6.4800000000 0.0250308812 0.0127042881 0.0260925256 0.0074521027 0.0852300000 365135187 0 402718720 -1.0437401533 0.0375213772 0.6013258696 164 6.5200000000 0.0261728633 0.0127864136 0.0261728633 0.0074369809 0.0523630000 365106143 0 402718720 -1.0450643301 0.0383825712 0.6142656803 165 6.5600000000 0.0260680281 0.0128669082 0.0261728633 0.0074351519 0.0846220000 365101675 0 402718720 -1.0438995361 0.0419707336 0.6332695484 166 6.6000000000 0.0254250169 0.0129425595 0.0261728633 0.0074457514 0.0298390000 360694367 0 402718720 -1.0442613363 0.0394726805 0.6445760727 167 6.6400000000 0.0247498546 0.0130132618 0.0261728633 0.0074486402 0.0290040000 360697339 0 402718720 -1.0419688225 0.0436922386 0.6530545354 168 6.6800000000 0.0263730101 0.0130927841 0.0263730101 0.0074527401 0.0291780000 360699851 0 402718720 -1.0428706408 0.0439568236 0.6667002439 169 6.7200000000 0.0291606225 0.0131878601 0.0291606225 0.0074450294 0.0305180000 361106587 0 402718720 -1.0435899496 0.0430534482 0.6847023964 170 6.7600000000 0.0284572877 0.0132776803 0.0291606225 0.0074376062 0.0900360000 361261739 0 402718720 -1.0442895889 0.0461401679 0.7012917995 171 6.8000000000 0.0239182208 0.0133399057 0.0291606225 0.0074412330 0.0877140000 361264359 0 402718720 -1.0418589115 0.0457491539 0.7062609196 172 6.8400000000 0.0233388934 0.0133980393 0.0291606225 0.0074208711 0.0831190000 363610807 0 402718720 -1.0407401323 0.0477592014 0.7178317308 173 6.8800000000 0.0269767437 0.0134765289 0.0291606225 0.0074036069 0.0642260000 366083521 0 402718720 -1.0423929691 0.0521685965 0.7347450256 174 6.9200000000 0.0290072765 0.0135657861 0.0291606225 0.0073853349 0.0374880000 366280039 0 402718720 -1.0433156490 0.0557805635 0.7497754097 175 6.9600000000 0.0303896442 0.0136619224 0.0303896442 0.0073670371 0.0885650000 366208275 0 402718720 -1.0428082943 0.0569774583 0.7641344070 176 7.0000000000 0.0287843738 0.0137478455 0.0303896442 0.0073486457 0.0304900000 361274647 0 402718720 -1.0439666510 0.0557955466 0.7777643204 177 7.0400000000 0.0283002015 0.0138300622 0.0303896442 0.0073537182 0.0305440000 361278263 0 402718720 -1.0413990021 0.0540079623 0.7849416733 178 7.0800000000 0.0293664224 0.0139173451 0.0303896442 0.0073387121 0.0302390000 361280675 0 402718720 -1.0412020683 0.0549635552 0.7912699580 179 7.1200000000 0.0277955830 0.0139948771 0.0303896442 0.0073233580 0.0297290000 361282479 0 402718720 -1.0402845144 0.0577486977 0.8020321131 180 7.1600000000 0.0287105739 0.0140766310 0.0303896442 0.0073058225 0.0294470000 361284311 0 402718720 -1.0394877195 0.0595875122 0.8179405928 181 7.2000000000 0.0296473224 0.0141626569 0.0303896442 0.0072894883 0.0288490000 361285659 0 402718720 -1.0383104086 0.0593333133 0.8305397034 182 7.2400000000 0.0347642787 0.0142758526 0.0347642787 0.0072804577 0.0309770000 361689459 0 402718720 -1.0395520926 0.0649258792 0.8469324112 183 7.2800000000 0.0373836458 0.0144021247 0.0373836458 0.0072716291 0.0894840000 361825096 0 402718720 -1.0400220156 0.0687486082 0.8652818203 184 7.3200000000 0.0338335037 0.0145077301 0.0373836458 0.0072575061 0.0872130000 361826476 0 402718720 -1.0387663841 0.0637593195 0.8740098476 185 7.3600000000 0.0320389904 0.0146024936 0.0373836458 0.0072425601 0.0865210000 363013340 0 402718720 -1.0355541706 0.0630818903 0.8889756203 186 7.4000000000 0.0278018396 0.0146734579 0.0373836458 0.0072391569 0.0625590000 367235340 0 402718720 -1.0369545221 0.0585743263 0.9025979638 187 7.4400000000 0.0309691317 0.0147606005 0.0373836458 0.0072351681 0.0526720000 367101516 0 402718720 -1.0325713158 0.0624585561 0.9141449332 188 7.4800000000 0.0324145555 0.0148545045 0.0373836458 0.0072498459 0.0880930000 367108571 0 402718720 -1.0350873470 0.0616454408 0.9311523438 189 7.5200000000 0.0299408473 0.0149343264 0.0373836458 0.0072410152 0.0294760000 361837248 0 402718720 -1.0340267420 0.0579584688 0.9474598169 190 7.5600000000 0.0306657925 0.0150171236 0.0373836458 0.0072350981 0.0298930000 362205320 0 402718720 -1.0306429863 0.0608926862 0.9624044895 191 7.6000000000 0.0312897973 0.0151023209 0.0373836458 0.0072211117 0.0869890000 362372128 0 402718720 -1.0288058519 0.0655564293 0.9786288738 192 7.6400000000 0.0313593820 0.0151869931 0.0373836458 0.0072119135 0.0884630000 362374136 0 402718720 -1.0258951187 0.0710766017 0.9933657646 193 7.6800000000 0.0316107683 0.0152720903 0.0373836458 0.0072114180 0.0811190000 363573484 0 402718720 -1.0256031752 0.0724234432 1.0116699934 194 7.7200000000 0.0345286652 0.0153713510 0.0373836458 0.0072150357 0.0645750000 368240256 0 402718720 -1.0264911652 0.0703247264 1.0306947231 195 7.7600000000 0.0345993750 0.0154699563 0.0373836458 0.0072216739 0.0617780000 368304627 0 402718720 -1.0260102749 0.0660719275 1.0459548235 196 7.8000000000 0.0293755196 0.0155409030 0.0373836458 0.0072780506 0.0848960000 368020731 0 402718720 -1.0207790136 0.0687523112 1.0586764812 197 7.8400000000 0.0273609273 0.0156009032 0.0373836458 0.0073082904 0.0302240000 362787788 0 402718720 -1.0177515745 0.0717681572 1.0689972639 198 7.8800000000 0.0244292244 0.0156454906 0.0373836458 0.0073342582 0.0788820000 362863644 0 402718720 -1.0140752792 0.0777479559 1.0813839436 199 7.9200000000 0.0290090870 0.0157126444 0.0373836458 0.0073273386 0.0750490000 362861048 0 402718720 -1.0159211159 0.0754569694 1.1034364700 200 7.9600000000 0.0248418152 0.0157582902 0.0373836458 0.0073260756 0.0727640000 364104636 0 402718720 -1.0158371925 0.0684202984 1.1131862402 201 8.0000000000 0.0263619088 0.0158110446 0.0373836458 0.0073327890 0.0703180000 369084024 0 402718720 -1.0158376694 0.0715495795 1.1324658394 202 8.0400000000 0.0272809714 0.0158678264 0.0373836458 0.0073548171 0.0606560000 369039191 0 402718720 -1.0103081465 0.0757418647 1.1456097364 203 8.0800000000 0.0278748386 0.0159269742 0.0373836458 0.0073667572 0.0295890000 369027300 0 402718720 -1.0068132877 0.0813666508 1.1621439457 204 8.1200000000 0.0291670766 0.0159918767 0.0373836458 0.0073790957 0.0799850000 368952115 0 402718720 -0.9997738600 0.0845419541 1.1771600246 205 8.1600000000 0.0239839852 0.0160308626 0.0373836458 0.0073904688 0.0328790000 363161576 0 402718720 -0.9997330308 0.0754687265 1.1858081818 206 8.1999999990 0.0244818423 0.0160718868 0.0373836458 0.0073788805 0.0764970000 363339600 0 402718720 -0.9958869815 0.0778939724 1.1988068819 207 8.2400000000 0.0284816772 0.0161318374 0.0373836458 0.0073689485 0.0734660000 363339344 0 402718720 -0.9919357300 0.0798073485 1.2184429169 208 8.2799999990 0.0270325076 0.0161842445 0.0373836458 0.0073548182 0.0699170000 364973084 0 402718720 -0.9880033731 0.0803339407 1.2299107313 209 8.3200000000 0.0233926624 0.0162187345 0.0373836458 0.0073477723 0.0667310000 369874972 0 402718720 -0.9840617180 0.0803517625 1.2382582426 210 8.3599999990 0.0244321711 0.0162578461 0.0373836458 0.0073772270 0.0613950000 369800415 0 402718720 -0.9764937162 0.0860809684 1.2491134405 211 8.4000000000 0.0216298793 0.0162833060 0.0373836458 0.0073862880 0.0292940000 369719496 0 402718720 -0.9718401432 0.0809365585 1.2608535290 212 8.4399999990 0.0252269264 0.0163254929 0.0373836458 0.0073771561 0.0866590000 369741239 0 402718720 -0.9651902318 0.0790114179 1.2792816162 213 8.4800000000 0.0221242830 0.0163527173 0.0373836458 0.0073730222 0.0324350000 363354188 0 402718720 -0.9566973448 0.0848032907 1.2905805111 214 8.5200000000 0.0169791803 0.0163556447 0.0373836458 0.0074144311 0.0271090000 363679420 0 402718720 -0.9487178326 0.0821763501 1.2978911400 215 8.5600000000 0.0222141948 0.0163828937 0.0373836458 0.0074357575 0.0780350000 363875112 0 402718720 -0.9410415888 0.0855432749 1.3133369684 216 8.6000000000 0.0199999902 0.0163996396 0.0373836458 0.0074198594 0.0819760000 363877944 0 402718720 -0.9319806099 0.0875598341 1.3231252432 217 8.6400000000 0.0197496787 0.0164150775 0.0373836458 0.0074437462 0.0762660000 365562980 0 402718720 -0.9242485762 0.0884393007 1.3393383026 218 8.6800000000 0.0226854607 0.0164438408 0.0373836458 0.0075021440 0.0748770000 371104866 0 402718720 -0.9159647822 0.0905634165 1.3514965773 219 8.7200000000 0.0234337356 0.0164757581 0.0373836458 0.0075005178 0.0647290000 370796145 0 402718720 -0.9043428898 0.0946521014 1.3632004261 220 8.7600000000 0.0199988354 0.0164917721 0.0373836458 0.0075020915 0.0330900000 370793884 0 402718720 -0.8954944015 0.0971128866 1.3702168465 221 8.8000000000 0.0258710571 0.0165342123 0.0373836458 0.0075556844 0.0905060000 370722963 0 402718720 -0.8888438940 0.0951837450 1.3882020712 222 8.8400000000 0.0264972672 0.0165790909 0.0373836458 0.0075721128 0.0333720000 363901272 0 402718720 -0.8765695095 0.1020237356 1.4042346478 223 8.8800000000 0.0288781710 0.0166342437 0.0373836458 0.0075808197 0.0282740000 363905092 0 402718720 -0.8691099286 0.1027301848 1.4153366089 224 8.9200000000 0.0257341824 0.0166748684 0.0373836458 0.0075747700 0.0272280000 363905880 0 402718720 -0.8558477759 0.1031482071 1.4244832993 225 8.9600000000 0.0248623583 0.0167112573 0.0373836458 0.0075715532 0.0269240000 363909680 0 402718720 -0.8451867104 0.1072251052 1.4313406944 226 9.0000000000 0.0270111784 0.0167568322 0.0373836458 0.0075600451 0.0290120000 364278572 0 402718720 -0.8347550631 0.1146310344 1.4444969893 227 9.0400000000 0.0267001092 0.0168006351 0.0373836458 0.0075495345 0.0809150000 364466384 0 402718720 -0.8246014714 0.1166846305 1.4524282217 228 9.0800000000 0.0264497604 0.0168429559 0.0373836458 0.0075560634 0.0872560000 364470408 0 402718720 -0.8130306602 0.1216608733 1.4659767151 229 9.1200000000 0.0278325360 0.0168909453 0.0373836458 0.0076160926 0.0787060000 364748400 0 402718720 -0.8021985292 0.1274581999 1.4750307798 230 9.1600000000 0.0295594912 0.0169460259 0.0373836458 0.0077149782 0.0842370000 369776660 0 402718720 -0.7902030945 0.1328299642 1.4843182564 231 9.2000000000 0.0284579061 0.0169958609 0.0373836458 0.0078942007 0.0459590000 372088004 0 402718720 -0.7806744576 0.1329041719 1.4908145666 232 9.2400000000 0.0251551997 0.0170310305 0.0373836458 0.0080416754 0.0666310000 372125507 0 402718720 -0.7701296806 0.1366038471 1.4957026243 233 9.2800000000 0.0254394282 0.0170671180 0.0373836458 0.0081742777 0.0321790000 372012760 0 402718720 -0.7605466247 0.1399341226 1.5031733513 234 9.3200000000 0.0216561537 0.0170867293 0.0373836458 0.0082552607 0.0978490000 371943099 0 402718720 -0.7535899878 0.1388274282 1.5039631128 235 9.3600000000 0.0243930314 0.0171178199 0.0373836458 0.0083443521 0.0402650000 364919012 0 402718720 -0.7435361147 0.1440894306 1.5146125555 236 9.4000000000 0.0232162625 0.0171436608 0.0373836458 0.0083948608 0.0936910000 365121400 0 402718720 -0.7343528867 0.1474319994 1.5211629868 237 9.4400000000 0.0236143153 0.0171709631 0.0373836458 0.0084239019 0.0957260000 365124388 0 402718720 -0.7226868868 0.1523714662 1.5293056965 238 9.4800000000 0.0253318083 0.0172052524 0.0373836458 0.0084434549 0.0919210000 365407596 0 402718720 -0.7118258476 0.1585247815 1.5392519236 239 9.5200000000 0.0246229731 0.0172362889 0.0373836458 0.0084867714 0.0947700000 370950140 0 402718720 -0.7003897429 0.1656495035 1.5457540751 240 9.5600000000 0.0232261121 0.0172612465 0.0373836458 0.0085320259 0.0517030000 373464208 0 402718720 -0.6905282736 0.1680602431 1.5531826019 241 9.6000000000 0.0238607619 0.0172886304 0.0373836458 0.0085806830 0.0805690000 373575255 0 402718720 -0.6808329821 0.1699158549 1.5626494884 242 9.6400000000 0.0231939685 0.0173130326 0.0373836458 0.0085982815 0.0359600000 373386072 0 402718720 -0.6706083417 0.1724413037 1.5706419945 243 9.6800000000 0.0246999599 0.0173434315 0.0373836458 0.0086204510 0.1086870000 373315147 0 402718720 -0.6569101810 0.1829311550 1.5800997019 244 9.7200000000 0.0270859208 0.0173833597 0.0373836458 0.0086659897 0.0424240000 365640424 0 402718720 -0.6437996626 0.1906511337 1.5911586285 245 9.7600000000 0.0248968955 0.0174140272 0.0373836458 0.0087232355 0.0941890000 365689268 0 402718720 -0.6343743801 0.1913263798 1.5971386433 246 9.8000000000 0.0258465223 0.0174483056 0.0373836458 0.0087406870 0.0940320000 365692952 0 402718720 -0.6229812503 0.1949433088 1.6073044538 247 9.8400000000 0.0259877592 0.0174828783 0.0373836458 0.0087496987 0.0913710000 365705924 0 402718720 -0.6165215969 0.1940108836 1.6167175770 248 9.8800000000 0.0264403373 0.0175189971 0.0373836458 0.0087353759 0.0908450000 372254424 0 402718720 -0.6050184965 0.1977226734 1.6258897781 249 9.9200000000 0.0258582123 0.0175524879 0.0373836458 0.0087191576 0.0492280000 374513828 0 402718720 -0.5935791135 0.2000776082 1.6333533525 250 9.9600000000 0.0243886616 0.0175798326 0.0373836458 0.0087048052 0.0721810000 374555349 0 402718720 -0.5869753957 0.2009465098 1.6400157213 251 10.0000000000 0.0243671685 0.0176068738 0.0373836458 0.0086882166 0.0345730000 374425216 0 402718720 -0.5757445693 0.2042586952 1.6492551565 252 10.0400000000 0.0295104682 0.0176541103 0.0373836458 0.0086905765 0.1074170000 374355279 0 402718720 -0.5631080270 0.2095242441 1.6637367010 253 10.0800000000 0.0286230110 0.0176974656 0.0373836458 0.0086745275 0.0447000000 366129308 0 402718720 -0.5558565855 0.2046834677 1.6735744476 254 10.1200000000 0.0287708398 0.0177410616 0.0373836458 0.0086950858 0.0972730000 366262564 0 402718720 -0.5457973480 0.2072204351 1.6834257841 255 10.1600000000 0.0304072220 0.0177907328 0.0373836458 0.0087053302 0.0921270000 366265044 0 402718720 -0.5346500874 0.2150882185 1.6937829256 256 10.2000000000 0.0291830841 0.0178352342 0.0373836458 0.0086914678 0.0887340000 366290640 0 402718720 -0.5244746804 0.2217198312 1.6996576786 257 10.2400000000 0.0302265063 0.0178834492 0.0373836458 0.0086772247 0.0919920000 373161634 0 402718720 -0.5150237083 0.2204174697 1.7103925943 258 10.2800000000 0.0268400237 0.0179181646 0.0373836458 0.0086617898 0.0473890000 375620400 0 402718720 -0.5068385005 0.2254403532 1.7146074772 259 10.3200000000 0.0266874284 0.0179520228 0.0373836458 0.0086523717 0.0769770000 375748095 0 402718720 -0.4956751168 0.2279107720 1.7220133543 260 10.3600000000 0.0256294683 0.0179815514 0.0373836458 0.0086545618 0.0381080000 375530172 0 402718720 -0.4851499200 0.2299436033 1.7289226055 261 10.4000000000 0.0261737946 0.0180129394 0.0373836458 0.0086567829 0.1084030000 375459387 0 402718720 -0.4709367752 0.2306985706 1.7365701199 262 10.4400000000 0.0251967143 0.0180403583 0.0373836458 0.0086437472 0.0447250000 366290728 0 402718720 -0.4623982012 0.2302697599 1.7430393696 263 10.4800000000 0.0261997934 0.0180713828 0.0373836458 0.0086301331 0.0312690000 366294792 0 402718720 -0.4505186081 0.2330223471 1.7492100000 264 10.5200000000 0.0241638925 0.0180944605 0.0373836458 0.0086178498 0.0306640000 366294620 0 402718720 -0.4408193529 0.2321011424 1.7530280352 265 10.5600000000 0.0263389368 0.0181255717 0.0373836458 0.0086031160 0.0302870000 366296820 0 402718720 -0.4299966097 0.2330510169 1.7625379562 266 10.6000000000 0.0255610254 0.0181535246 0.0373836458 0.0085910638 0.0297470000 366298008 0 402718720 -0.4180326164 0.2359486371 1.7656366825 267 10.6400000000 0.0259053074 0.0181825575 0.0373836458 0.0085841437 0.0303550000 366303940 0 402718720 -0.4052794576 0.2332299948 1.7713865042 268 10.6800000000 0.0268380828 0.0182148542 0.0373836458 0.0085775377 0.0298680000 366307652 0 402718720 -0.3937565684 0.2344556451 1.7776150703 269 10.7200000000 0.0287003741 0.0182538338 0.0373836458 0.0085684142 0.0319350000 366735132 0 402718720 -0.3814517260 0.2375208139 1.7800203562 270 10.7600000000 0.0275527500 0.0182882742 0.0373836458 0.0085570615 0.0899210000 366853320 0 402718720 -0.3559473157 0.2414209843 1.7898361683 271 10.8000000000 0.0291434638 0.0183283303 0.0373836458 0.0085752017 0.0893870000 366854880 0 402718720 -0.3412952423 0.2447989434 1.7954446077 272 10.8400000000 0.0297473781 0.0183703121 0.0373836458 0.0086283592 0.0897550000 369445916 0 402718720 -0.3285531402 0.2435186207 1.7994015217 273 10.8800000000 0.0303046815 0.0184140277 0.0373836458 0.0086371222 0.0848390000 375366672 0 402718720 -0.3156858683 0.2445780635 1.8043992519 274 10.9200000000 0.0285760425 0.0184511154 0.0373836458 0.0086420038 0.0402520000 376357457 0 402718720 -0.3025853038 0.2452081591 1.8063902855 275 10.9600000000 0.0286707506 0.0184882777 0.0373836458 0.0086450918 0.0700230000 376063437 0 402718720 -0.2902900577 0.2459832430 1.8087419271 276 11.0000000000 0.0307085998 0.0185325542 0.0373836458 0.0086444010 0.0356440000 376026948 0 402718720 -0.2768834829 0.2485633790 1.8145859241 277 11.0400000000 0.0364258811 0.0185971511 0.0373836458 0.0086564863 0.1074470000 375957583 0 402718720 -0.2625402510 0.2490736842 1.8253737688 278 11.0800000000 0.0342006981 0.0186532789 0.0373836458 0.0086585382 0.0433600000 366867576 0 402718720 -0.2495261133 0.2476660013 1.8279131651 279 11.1200000000 0.0332486890 0.0187055922 0.0373836458 0.0086661123 0.0303250000 366871236 0 402718720 -0.2359144390 0.2509944141 1.8301060200 280 11.1600000000 0.0348660015 0.0187633080 0.0373836458 0.0086782493 0.0299710000 366873328 0 402718720 -0.2225824893 0.2546430230 1.8345931768 281 11.2000000000 0.0333578400 0.0188152458 0.0373836458 0.0086808682 0.0293710000 366876424 0 402718720 -0.2099788785 0.2536185682 1.8365193605 282 11.2400000000 0.0337950811 0.0188683658 0.0373836458 0.0086733243 0.0293930000 366878504 0 402718720 -0.1962890625 0.2523553669 1.8418443203 283 11.2800000000 0.0349545814 0.0189252075 0.0373836458 0.0086586777 0.0292390000 366880780 0 402718720 -0.1843016744 0.2548908591 1.8450540304 284 11.3200000000 0.0306577589 0.0189665193 0.0373836458 0.0086507589 0.0291040000 366880216 0 402718720 -0.1742621362 0.2521726489 1.8479167223 285 11.3600000000 0.0344299972 0.0190207772 0.0373836458 0.0086553727 0.0325770000 367342604 0 402718720 -0.1610104442 0.2584062219 1.8539793491 286 11.4000000000 0.0334345400 0.0190711749 0.0373836458 0.0086451233 0.0892380000 367440000 0 402718720 -0.1502378583 0.2572923601 1.8574616909 287 11.4400000000 0.0346520878 0.0191254638 0.0373836458 0.0086301742 0.0864130000 367439704 0 402718720 -0.1403834522 0.2572437525 1.8627703190 288 11.4800000000 0.0314819738 0.0191683684 0.0373836458 0.0086169757 0.0868330000 367465528 0 402718720 -0.1327431798 0.2565448582 1.8635206223 289 11.5200000000 0.0322131217 0.0192135059 0.0373836458 0.0086026706 0.0905010000 374382882 0 402718720 -0.1248013675 0.2572905123 1.8703373671 290 11.5600000000 0.0321532451 0.0192581257 0.0373836458 0.0085948860 0.0442730000 376706272 0 402718720 -0.1163155138 0.2560944259 1.8770061731 291 11.6000000000 0.0299952831 0.0192950232 0.0373836458 0.0085842665 0.0699790000 376777405 0 402718720 -0.1090352535 0.2546877563 1.8818843365 292 11.6400000000 0.0316339470 0.0193372798 0.0373836458 0.0085730936 0.0343350000 376649392 0 402718720 -0.0990824103 0.2570917606 1.8888415098 293 11.6800000000 0.0346765108 0.0193896321 0.0373836458 0.0085624535 0.1057310000 376578035 0 402718720 -0.0895100832 0.2582912147 1.8985379934 294 11.7200000000 0.0347574018 0.0194419034 0.0373836458 0.0085484115 0.0415430000 367452592 0 402718720 -0.0850326121 0.2591645718 1.9051305056 295 11.7600000000 0.0377910435 0.0195041039 0.0377910435 0.0085407992 0.0292240000 367456620 0 402718720 -0.0765483677 0.2602455616 1.9147808552 296 11.8000000000 0.0354789607 0.0195580730 0.0377910435 0.0085338126 0.0292930000 367458264 0 402718720 -0.0728634000 0.2576487660 1.9203548431 297 11.8400000000 0.0363651067 0.0196146623 0.0377910435 0.0085260741 0.0322310000 368000520 0 402718720 -0.0666256547 0.2595905662 1.9275372028 298 11.8800000000 0.0352732912 0.0196672081 0.0377910435 0.0085205735 0.0932770000 368019004 0 402718720 -0.0624051988 0.2578842342 1.9349350929 299 11.9200000000 0.0360117629 0.0197218721 0.0377910435 0.0085102985 0.0880640000 368021744 0 402718720 -0.0565139949 0.2588630021 1.9433768988 300 11.9600000000 0.0356096253 0.0197748313 0.0377910435 0.0084979840 0.0843650000 368032232 0 402718720 -0.0516859293 0.2583049238 1.9520257711 301 12.0000000000 0.0358974524 0.0198283948 0.0377910435 0.0084839261 0.0896290000 375136736 0 402718720 -0.0471140146 0.2594467998 1.9611021280 302 12.0400000000 0.0341150574 0.0198757017 0.0377910435 0.0084734084 0.0477940000 377216496 0 402718720 -0.0437665880 0.2590789199 1.9691324234 303 12.0800000000 0.0361194536 0.0199293114 0.0377910435 0.0084657216 0.0780350000 377345691 0 402718720 -0.0380547047 0.2595447600 1.9811571836 304 12.1200000000 0.0324440338 0.0199704783 0.0377910435 0.0084668414 0.0351770000 377125760 0 402718720 -0.0370245278 0.2573672235 1.9887659550 305 12.1600000000 0.0348361246 0.0200192181 0.0377910435 0.0084632034 0.1063840000 377055359 0 402718720 -0.0320725441 0.2584851384 2.0021610260 306 12.2000000000 0.0356913842 0.0200704343 0.0377910435 0.0084531377 0.0420570000 368039256 0 402718720 -0.0288563073 0.2587131858 2.0145535469 307 12.2400000000 0.0337590836 0.0201150227 0.0377910435 0.0084545990 0.0329850000 368505964 0 402718720 -0.0264646411 0.2591713965 2.0240819454 308 12.2800000000 0.0333509631 0.0201579966 0.0377910435 0.0084587314 0.0999200000 368628808 0 402718720 -0.0235366523 0.2588616908 2.0355439186 309 12.3200000000 0.0331500992 0.0202000422 0.0377910435 0.0084678426 0.0915440000 368628440 0 402718720 -0.0215503275 0.2584423125 2.0462586880 310 12.3600000000 0.0349443108 0.0202476044 0.0377910435 0.0084828048 0.0881250000 368905764 0 402718720 -0.0186867416 0.2580819726 2.0600397587 311 12.4000000000 0.0333046056 0.0202895883 0.0377910435 0.0084977570 0.0926630000 374660436 0 402718720 -0.0168835521 0.2576547861 2.0696368217 312 12.4400000000 0.0348111726 0.0203361318 0.0377910435 0.0085291563 0.0673210000 378299748 0 402718720 -0.0139761567 0.2597225606 2.0940468311 313 12.4800000000 0.0327844769 0.0203759029 0.0377910435 0.0085235066 0.0798540000 378228359 0 402718720 -0.0147517920 0.2579989135 2.1033985615 314 12.5200000000 0.0313447788 0.0204108356 0.0377910435 0.0085149659 0.0365230000 378349593 0 402718720 -0.0169194639 0.2566989958 2.1145076752 315 12.5600000000 0.0378325805 0.0204661428 0.0378325805 0.0085227623 0.1092700000 378131355 0 402718720 -0.0108239949 0.2624131441 2.1297283173 316 12.6000000000 0.0395929739 0.0205266707 0.0395929739 0.0085138320 0.0472590000 369074988 0 402718720 -0.0094119906 0.2612980008 2.1446769238 317 12.6400000000 0.0383782685 0.0205829849 0.0395929739 0.0085004906 0.1055530000 369177024 0 402718720 -0.0101761222 0.2606832981 2.1548738480 318 12.6800000000 0.0381925106 0.0206383608 0.0395929739 0.0084872371 0.1024430000 369167404 0 402718720 -0.0109275281 0.2607084513 2.1658909321 319 12.7200000000 0.0391838588 0.0206964971 0.0395929739 0.0084743099 0.0949720000 369431620 0 402718720 -0.0104251504 0.2607708871 2.1769568920 320 12.7600000000 0.0383802839 0.0207517590 0.0395929739 0.0084620358 0.0887540000 375714436 0 402718720 -0.0117966235 0.2620580792 2.1856877804 321 12.8000000000 0.0379816666 0.0208054347 0.0395929739 0.0084515966 0.0626890000 379269640 0 402718720 -0.0154140890 0.2611882687 2.1959545612 322 12.8400000000 0.0375072099 0.0208573035 0.0395929739 0.0084400205 0.0742600000 379195799 0 402718720 -0.0171522200 0.2607660294 2.2052502632 323 12.8800000000 0.0384923033 0.0209119011 0.0395929739 0.0084295130 0.0374980000 379471761 0 402718720 -0.0174165964 0.2599689662 2.2145254612 324 12.9200000000 0.0358230025 0.0209579230 0.0395929739 0.0084176732 0.1100930000 379098779 0 402718720 -0.0218977332 0.2593695521 2.2209002972 325 12.9600000000 0.0341483615 0.0209985090 0.0395929739 0.0084052726 0.0498340000 369684356 0 402718720 -0.0252422541 0.2586416602 2.2292032242 326 13.0000000000 0.0341671295 0.0210389035 0.0395929739 0.0083930979 0.0952650000 369695276 0 402718720 -0.0269251615 0.2587141395 2.2361290455 327 13.0400000000 0.0339581333 0.0210784118 0.0395929739 0.0083810915 0.0919230000 369690184 0 402718720 -0.0292919725 0.2588543296 2.2457356453 328 13.0800000000 0.0339419208 0.0211176299 0.0395929739 0.0083704461 0.0849940000 369950468 0 402718720 -0.0292470306 0.2613635361 2.2521145344 329 13.1200000000 0.0330900699 0.0211540203 0.0395929739 0.0083579697 0.0843140000 376587416 0 402718720 -0.0322226919 0.2617521584 2.2605006695 330 13.1600000000 0.0346852504 0.0211950240 0.0395929739 0.0083471836 0.0640990000 380234332 0 402718720 -0.0319090895 0.2628334165 2.2695784569 331 13.2000000000 0.0359752998 0.0212396774 0.0395929739 0.0083353919 0.0630810000 380161431 0 402718720 -0.0329844095 0.2644524872 2.2801444530 332 13.2400000000 0.0355050899 0.0212826455 0.0395929739 0.0083256157 0.0457950000 380006145 0 402718720 -0.0341661796 0.2650592029 2.2878015041 333 13.2800000000 0.0346048139 0.0213226520 0.0395929739 0.0083140385 0.0319600000 380128520 0 402718720 -0.0377033725 0.2650124431 2.2965629101 334 13.3200000000 0.0378580764 0.0213721593 0.0395929739 0.0083022552 0.1057280000 380054515 0 402718720 -0.0365725458 0.2641631663 2.3082337379 335 13.3600000000 0.0383945443 0.0214229724 0.0395929739 0.0082900735 0.0563680000 370316816 0 402718720 -0.0385347754 0.2651527822 2.3175671101 336 13.4000000000 0.0390918069 0.0214755582 0.0395929739 0.0082787244 0.0945910000 370377984 0 402718720 -0.0394336879 0.2679457366 2.3256208897 337 13.4400000000 0.0382742621 0.0215254060 0.0395929739 0.0082748106 0.0839530000 370378396 0 402718720 -0.0414908528 0.2700991035 2.3323876858 338 13.4800000000 0.0394275673 0.0215783709 0.0395929739 0.0082801718 0.0797230000 370629788 0 402718720 -0.0427201986 0.2727230489 2.3392822742 339 13.5200000000 0.0390749909 0.0216299834 0.0395929739 0.0082901063 0.0770850000 374048328 0 402718720 -0.0447303355 0.2719751894 2.3447086811 340 13.5600000000 0.0385119729 0.0216796363 0.0395929739 0.0082842858 0.0773410000 379212654 0 402718720 -0.0475801528 0.2721011043 2.3493251801 341 13.6000000000 0.0383628979 0.0217285608 0.0395929739 0.0082746825 0.0429340000 382070380 0 402718720 -0.0500322580 0.2718848288 2.3543272018 342 13.6400000000 0.0379281305 0.0217759280 0.0395929739 0.0082694069 0.0654270000 381994539 0 402718720 -0.0525551438 0.2729023099 2.3591992855 343 13.6800000000 0.0382983312 0.0218240982 0.0395929739 0.0082582538 0.0428160000 381813312 0 402718720 -0.0541526973 0.2733182907 2.3642451763 344 13.7200000000 0.0371916182 0.0218687713 0.0395929739 0.0082463702 0.0306730000 381970140 0 402718720 -0.0558178425 0.2743918002 2.3688919544 345 13.7600000000 0.0356267095 0.0219086494 0.0395929739 0.0082362646 0.0961760000 381888315 0 402718720 -0.0583027005 0.2715693712 2.3741014004 346 13.8000000000 0.0349801369 0.0219464282 0.0395929739 0.0082304800 0.0713960000 370618909 0 402718720 -0.0590853095 0.2710852027 2.3783824444 347 13.8400000000 0.0352045447 0.0219846360 0.0395929739 0.0082187433 0.0292590000 371087624 0 402718720 -0.0622674227 0.2692818642 2.3835484982 348 13.8800000000 0.0350976512 0.0220223171 0.0395929739 0.0082081493 0.0902670000 371061300 0 402718720 -0.0626387000 0.2711857557 2.3893084526 349 13.9200000000 0.0345750526 0.0220582848 0.0395929739 0.0082048175 0.0799990000 371069812 0 402718720 -0.0640844703 0.2710486352 2.3943631649 350 13.9600000000 0.0345299542 0.0220939182 0.0395929739 0.0081976208 0.0781090000 371364684 0 402718720 -0.0671902895 0.2688065767 2.4036955833 351 14.0000000000 0.0348610021 0.0221302916 0.0395929739 0.0081867424 0.0802700000 379143540 0 402718720 -0.0664569139 0.2699393630 2.4079351425 352 14.0400000000 0.0352780670 0.0221676433 0.0395929739 0.0081779171 0.0687740000 383606344 0 402718720 -0.0668270588 0.2705051899 2.4125747681 353 14.0800000000 0.0355948992 0.0222056808 0.0395929739 0.0081664669 0.0334130000 383633048 0 402718720 -0.0674497485 0.2692475021 2.4174194336 354 14.1200000000 0.0337286554 0.0222382316 0.0395929739 0.0081553041 0.0865200000 383858463 0 402718720 -0.0682692528 0.2682309747 2.4210290909 355 14.1600000000 0.0357363150 0.0222762544 0.0395929739 0.0081447316 0.0308350000 384130801 0 402718720 -0.0681118369 0.2684397101 2.4271540642 356 14.2000000000 0.0355376825 0.0223135056 0.0395929739 0.0081367634 0.0290870000 383590844 0 402718720 -0.0673121214 0.2691707909 2.4310843945 357 14.2400000000 0.0278651267 0.0223290563 0.0395929739 0.0081519808 0.1046690000 383513123 0 402718720 -0.0726795793 0.2626276314 2.4319114685 358 14.2800000000 0.0275978353 0.0223437736 0.0395929739 0.0081416695 0.0727870000 371071464 0 402718720 -0.0723221898 0.2615912557 2.4369077682 359 14.3200000000 0.0270738099 0.0223569492 0.0395929739 0.0081314040 0.0265600000 371090700 0 402718720 -0.0728572011 0.2607574165 2.4414761066 360 14.3600000000 0.0266696643 0.0223689290 0.0395929739 0.0081240110 0.0259720000 371093244 0 402718720 -0.0730341673 0.2587219775 2.4474720955 361 14.4000000000 0.0271970034 0.0223823031 0.0395929739 0.0081188503 0.0253810000 371095164 0 402718720 -0.0724712014 0.2586318851 2.4544241428 362 14.4400000000 0.0265609901 0.0223938465 0.0395929739 0.0081109784 0.0258450000 371098376 0 402718720 -0.0730916858 0.2594043612 2.4601283073 363 14.4800000000 0.0278756525 0.0224089478 0.0395929739 0.0081005132 0.0258180000 371100468 0 402718720 -0.0722036958 0.2619432807 2.4679951668 364 14.5200000000 0.0270788781 0.0224217773 0.0395929739 0.0080909506 0.0255640000 371100948 0 402718720 -0.0724279284 0.2594826221 2.4750804901 365 14.5600000000 0.0273485053 0.0224352752 0.0395929739 0.0080809293 0.0256020000 371106276 0 402718720 -0.0726574063 0.2593333125 2.4821095467 366 14.6000000000 0.0277937129 0.0224499158 0.0395929739 0.0080702610 0.0250100000 371108380 0 402718720 -0.0726103783 0.2615497410 2.4898486137 367 14.6400000000 0.0277675632 0.0224644053 0.0395929739 0.0080615185 0.0250530000 371109196 0 402718720 -0.0729070306 0.2610985935 2.4977364540 368 14.6800000000 0.0274401605 0.0224779263 0.0395929739 0.0080536265 0.0249800000 371112344 0 402718720 -0.0721216202 0.2627923191 2.5044040680 369 14.7200000000 0.0275950562 0.0224917939 0.0395929739 0.0080493688 0.0284660000 371681044 0 402718720 -0.0737507939 0.2627851963 2.5119850636 370 14.7600000000 0.0278685503 0.0225063257 0.0395929739 0.0080442707 0.0792610000 371711800 0 402718720 -0.0737463236 0.2631994486 2.5201513767 371 14.8000000000 0.0278411116 0.0225207051 0.0395929739 0.0080387502 0.0714600000 371712096 0 402718720 -0.0740209222 0.2634190321 2.5271546841 372 14.8400000000 0.0276176110 0.0225344065 0.0395929739 0.0080356003 0.0674640000 371982996 0 402718720 -0.0735805631 0.2622781992 2.5341694355 373 14.8800000000 0.0278257765 0.0225485925 0.0395929739 0.0080330494 0.0750290000 377930964 0 402718720 -0.0736201406 0.2621104419 2.5417010784 374 14.9200000000 0.0276800245 0.0225623129 0.0395929739 0.0080280469 0.0668620000 382173064 0 402718720 -0.0741159320 0.2614995837 2.5488760471 375 14.9600000000 0.0280028321 0.0225768209 0.0395929739 0.0080300188 0.0335210000 384024056 0 402718720 -0.0735417604 0.2609888613 2.5562059879 376 15.0000000000 0.0279733706 0.0225911735 0.0395929739 0.0080280783 0.0622550000 383887173 0 402718720 -0.0727128983 0.2618915141 2.5637776852 377 15.0400000000 0.0269307438 0.0226026843 0.0395929739 0.0080203350 0.0392650000 383766144 0 402718720 -0.0709552765 0.2630971372 2.5757772923 378 15.0800000000 0.0275918730 0.0226158832 0.0395929739 0.0080100987 0.0297520000 383927888 0 402718720 -0.0682769418 0.2644649446 2.5828337669 379 15.1200000000 0.0271760989 0.0226279154 0.0395929739 0.0080009491 0.1012710000 383849667 0 402718720 -0.0678274632 0.2645079195 2.5884096622 380 15.1600000000 0.0267631449 0.0226387976 0.0395929739 0.0079910958 0.0697910000 372520229 0 402718720 -0.0654528141 0.2656355798 2.5933284760 381 15.2000000000 0.0272633862 0.0226509356 0.0395929739 0.0079807380 0.0265510000 371741208 0 402718720 -0.0628420115 0.2669602931 2.5987839699 382 15.2400000000 0.0272649750 0.0226630143 0.0395929739 0.0079717920 0.0256500000 371742060 0 402718720 -0.0603757203 0.2669236362 2.6037647724 383 15.2800000000 0.0269491468 0.0226742052 0.0395929739 0.0079614271 0.0261310000 371743024 0 402718720 -0.0582050681 0.2680721283 2.6079139709 384 15.3200000000 0.0266369507 0.0226845248 0.0395929739 0.0079512643 0.0262460000 371747400 0 402718720 -0.0557246506 0.2687660754 2.6113965511 385 15.3600000000 0.0267366674 0.0226950499 0.0395929739 0.0079419785 0.0264640000 371750028 0 402718720 -0.0531702340 0.2683089674 2.6140911579 386 15.4000000000 0.0269434825 0.0227060562 0.0395929739 0.0079379640 0.0271830000 371757880 0 402718720 -0.0496970415 0.2689968944 2.6164236069 387 15.4400000000 0.0262053460 0.0227150983 0.0395929739 0.0079382901 0.0318150000 372277772 0 402718720 -0.0465801954 0.2700023949 2.6183102131 388 15.4800000000 0.0266523529 0.0227252458 0.0395929739 0.0079289589 0.0906720000 372320540 0 402718720 -0.0433067530 0.2710168660 2.6198320389 389 15.5200000000 0.0263884384 0.0227346628 0.0395929739 0.0079204726 0.0848550000 372324440 0 402718720 -0.0410059988 0.2716961801 2.6203374863 390 15.5600000000 0.0262389611 0.0227436482 0.0395929739 0.0079104516 0.0804060000 372598252 0 402718720 -0.0365755633 0.2751019001 2.6212296486 391 15.6000000000 0.0261694789 0.0227524099 0.0395929739 0.0079163294 0.0832070000 376918324 0 402718720 -0.0329279937 0.2752557993 2.6225616932 392 15.6400000000 0.0258847177 0.0227604005 0.0395929739 0.0079081566 0.0834290000 381844094 0 402718720 -0.0309874527 0.2749424279 2.6228377819 393 15.6800000000 0.0255296677 0.0227674470 0.0395929739 0.0078984632 0.0464300000 385636489 0 402718720 -0.0279429406 0.2737072706 2.6229355335 394 15.7200000000 0.0264438856 0.0227767780 0.0395929739 0.0078908483 0.0744400000 385248859 0 402718720 -0.0254364759 0.2718509734 2.6248755455 395 15.7600000000 0.0258700829 0.0227846092 0.0395929739 0.0078892450 0.0478800000 385494469 0 402718720 -0.0220130235 0.2725892365 2.6246209145 396 15.8000000000 0.0260834489 0.0227929396 0.0395929739 0.0078832617 0.0356490000 385211764 0 402718720 -0.0186504573 0.2729204893 2.6250362396 397 15.8400000000 0.0210927706 0.0227886570 0.0395929739 0.0078967494 0.1171330000 385140623 0 402718720 -0.0185637772 0.2698414624 2.6208186150 398 15.8800000000 0.0211234372 0.0227844731 0.0395929739 0.0078893152 0.0797030000 372350176 0 402718720 -0.0160098374 0.2683670819 2.6201035976 399 15.9200000000 0.0212816615 0.0227807066 0.0395929739 0.0078819424 0.0309450000 372351156 0 402718720 -0.0098433793 0.2709656954 2.6182885170 400 15.9600000000 0.0220181476 0.0227788002 0.0395929739 0.0078759211 0.0316150000 372356928 0 402718720 -0.0056423247 0.2716768384 2.6197986603 401 16.0000000000 0.0210128650 0.0227743964 0.0395929739 0.0078701429 0.0312950000 372358680 0 402718720 -0.0023863316 0.2716671824 2.6195297241 402 16.0400000000 0.0204981007 0.0227687340 0.0395929739 0.0078630937 0.0309400000 372360288 0 402718720 0.0017731190 0.2704840302 2.6200215816 403 16.0800000000 0.0217368547 0.0227661735 0.0395929739 0.0078576183 0.0341280000 372823624 0 402718720 0.0084824562 0.2719059885 2.6221456528 404 16.1200000000 0.0212714896 0.0227624738 0.0395929739 0.0078491095 0.0948610000 372903196 0 402718720 0.0128508806 0.2715978622 2.6211438179 405 16.1600000000 0.0215541441 0.0227594902 0.0395929739 0.0078404975 0.0917390000 372906800 0 402718720 0.0191876292 0.2735835612 2.6221637726 406 16.2000000000 0.0210783277 0.0227553494 0.0395929739 0.0078329892 0.0879350000 373179900 0 402718720 0.0240008831 0.2739742100 2.6249947548 407 16.2400000000 0.0218673758 0.0227531677 0.0395929739 0.0078247812 0.0907320000 378886624 0 402718720 0.0311910510 0.2754392922 2.6275019646 408 16.2800000000 0.0209053457 0.0227486387 0.0395929739 0.0078263919 0.0836370000 384574012 0 402718720 0.0341324210 0.2749945819 2.6298990250 409 16.3200000000 0.0208392106 0.0227439702 0.0395929739 0.0078264052 0.0459990000 385386653 0 402718720 0.0410224199 0.2794114053 2.6319746971 410 16.3600000000 0.0209589880 0.0227396166 0.0395929739 0.0078172601 0.0727560000 385175205 0 402718720 0.0480415821 0.2823031247 2.6366178989 411 16.3999999990 0.0217775665 0.0227372758 0.0395929739 0.0078097925 0.0361840000 384629356 0 402718720 0.0527703762 0.2819600701 2.6386249065 412 16.4400000000 0.0217533056 0.0227348875 0.0395929739 0.0078260516 0.1177740000 384716359 0 402718720 0.0569205284 0.2808759212 2.6454367638 413 16.4800000000 0.0216315594 0.0227322160 0.0395929739 0.0078371527 0.0687020000 372928240 0 402718720 0.0621384382 0.2821463048 2.6521525383 414 16.5200000000 0.0217137504 0.0227297560 0.0395929739 0.0078335660 0.0347170000 373488388 0 402718720 0.0687992573 0.2808421552 2.6552932262 415 16.5599999990 0.0215947293 0.0227270210 0.0395929739 0.0078459895 0.1022130000 373469020 0 402718720 0.0720285177 0.2751530707 2.6606442928 416 16.6000000000 0.0216329284 0.0227243909 0.0395929739 0.0079259280 0.0961860000 373472204 0 402718720 0.0776317120 0.2743391991 2.6668667793 417 16.6400000000 0.0226012468 0.0227240956 0.0395929739 0.0079571394 0.0895480000 373779624 0 402718720 0.0857292414 0.2769317925 2.6688294411 418 16.6800000000 0.0214681923 0.0227210911 0.0395929739 0.0079601765 0.0868320000 379070476 0 402718720 0.0865482092 0.2724880874 2.6677341461 419 16.7199999990 0.0223819911 0.0227202818 0.0395929739 0.0079909019 0.0806380000 384179664 0 402718720 0.0963624716 0.2761508822 2.6738095284 420 16.7600000000 0.0232932102 0.0227216459 0.0395929739 0.0079829649 0.0371570000 386512883 0 402718720 0.1007776260 0.2790728509 2.6749534607 421 16.8000000000 0.0218675938 0.0227196173 0.0395929739 0.0079891680 0.0827210000 385611387 0 402718720 0.1050688028 0.2723182440 2.6754021645 422 16.8400000000 0.0239910260 0.0227226301 0.0395929739 0.0079843567 0.0343490000 386256397 0 402718720 0.1120826006 0.2666211128 2.6792750359 423 16.8799999990 0.0239197649 0.0227254602 0.0395929739 0.0079933944 0.1028510000 385476431 0 402718720 0.1225242615 0.2725507021 2.6740922928 424 16.9200000000 0.0256572552 0.0227323748 0.0395929739 0.0079847528 0.0806570000 373649465 0 402718720 0.1306626797 0.2692528367 2.6744577885 425 16.9600000000 0.0270114467 0.0227424432 0.0395929739 0.0079842843 0.0318130000 373902624 0 402718720 0.1390775442 0.2686063647 2.6746506691 426 17.0000000000 0.0263194833 0.0227508400 0.0395929739 0.0079757523 0.0891450000 373994976 0 402718720 0.1477308273 0.2692974508 2.6725049019 427 17.0400000000 0.0267213713 0.0227601387 0.0395929739 0.0079744301 0.0876820000 373994760 0 402718720 0.1540359259 0.2649682760 2.6688740253 428 17.0800000000 0.0288171619 0.0227742906 0.0395929739 0.0079665484 0.0826400000 374290516 0 402718720 0.1641995907 0.2646692991 2.6670084000 429 17.1200000000 0.0273221806 0.0227848917 0.0395929739 0.0079588611 0.0803310000 380913424 0 402718720 0.1743752956 0.2635464072 2.6635613441 430 17.1600000000 0.0260915253 0.0227925816 0.0395929739 0.0079562890 0.0758360000 385424532 0 402718720 0.1823542118 0.2566415966 2.6576943398 431 17.2000000000 0.0264515802 0.0228010711 0.0395929739 0.0079470586 0.0356560000 386315657 0 402718720 0.1933760643 0.2521007061 2.6544046402 432 17.2400000000 0.0278782006 0.0228128237 0.0395929739 0.0079432543 0.0814320000 385905243 0 402718720 0.2059323788 0.2512528598 2.6509170532 433 17.2800000000 0.0273733251 0.0228233561 0.0395929739 0.0079373179 0.0315430000 386171257 0 402718720 0.2177559137 0.2516722977 2.6431484222 434 17.3200000000 0.0293700900 0.0228384407 0.0395929739 0.0079305872 0.0972240000 385414947 0 402718720 0.2293610573 0.2442871779 2.6384055614 435 17.3600000000 0.0288481414 0.0228522561 0.0395929739 0.0079430955 0.0846710000 374686313 0 402718720 0.2430075407 0.2413193285 2.6333715916 436 17.4000000000 0.0282239448 0.0228645765 0.0395929739 0.0079442040 0.0967550000 374682768 0 402718720 0.2556815147 0.2474876344 2.6254522800 437 17.4400000000 0.0285323057 0.0228775461 0.0395929739 0.0079415861 0.0971100000 374685124 0 402718720 0.2762452364 0.2531783581 2.6158680916 438 17.4800000000 0.0286760312 0.0228907847 0.0395929739 0.0080442972 0.0964170000 374689320 0 402718720 0.2886849642 0.2574512064 2.6063504219 439 17.5200000000 0.0279322341 0.0229022686 0.0395929739 0.0081895243 0.0885840000 378988084 0 402718720 0.2941491604 0.2465182841 2.5988559723 440 17.5600000000 0.0286205877 0.0229152648 0.0395929739 0.0082176730 0.0879330000 384472878 0 402718720 0.3002407551 0.2381960154 2.5911116600 441 17.6000000000 0.0300280247 0.0229313935 0.0395929739 0.0082158002 0.0476370000 387608541 0 402718720 0.3097329140 0.2340600342 2.5831484795 442 17.6400000000 0.0304275081 0.0229483531 0.0395929739 0.0082636534 0.0727200000 387161883 0 402718720 0.3205815554 0.2305548042 2.5775375366 443 17.6800000000 0.0300101023 0.0229642938 0.0395929739 0.0082846957 0.0462600000 387399681 0 402718720 0.3454300761 0.2336969972 2.5602593422 444 17.7200000000 0.0340060070 0.0229891625 0.0395929739 0.0082847862 0.0328820000 386969988 0 402718720 0.3556423187 0.2346819341 2.5531587601 445 17.7600000000 0.0316706300 0.0230086714 0.0395929739 0.0082792666 0.1115690000 387006883 0 402718720 0.3655869365 0.2309291512 2.5427939892 446 17.8000000000 0.0342323370 0.0230338366 0.0395929739 0.0082736097 0.0894850000 375375544 0 402718720 0.3749475479 0.2285355479 2.5373671055 447 17.8400000000 0.0337634832 0.0230578403 0.0395929739 0.0082698681 0.0693200000 375522472 0 402718720 0.3824743629 0.2282601893 2.5284595490 448 17.8800000000 0.0326779522 0.0230793138 0.0395929739 0.0082624857 0.0761250000 375550624 0 402718720 0.3880670071 0.2236515582 2.5209410191 449 17.9200000000 0.0317598842 0.0230986469 0.0395929739 0.0082554512 0.0736480000 375553192 0 402718720 0.3981954455 0.2237701565 2.5110540390 450 17.9600000000 0.0330874808 0.0231208443 0.0395929739 0.0082466261 0.0736720000 379285772 0 402718720 0.4054812193 0.2201374322 2.5065701008 451 18.0000000000 0.0298908688 0.0231358554 0.0395929739 0.0082551635 0.0673470000 384049368 0 402718720 0.4122937322 0.2181804925 2.4982886314 452 18.0400000000 0.0314616337 0.0231542753 0.0395929739 0.0082470806 0.0335510000 385472009 0 402718720 0.4215738773 0.2199194580 2.4928965569 453 18.0800000000 0.0314110592 0.0231725022 0.0395929739 0.0082382817 0.0636930000 385426092 0 402718720 0.4323060513 0.2169740498 2.4861197472 454 18.1200000000 0.0314285606 0.0231906873 0.0395929739 0.0082380257 0.0962990000 385357859 0 402718720 0.4378566742 0.2129405439 2.4817347527 455 18.1600000000 0.0299964175 0.0232056450 0.0395929739 0.0082322864 0.0597810000 375920020 0 402718720 0.4496220350 0.2135725915 2.4745798111 456 18.2000000000 0.0298648793 0.0232202486 0.0395929739 0.0082255363 0.0704700000 376011140 0 402718720 0.4571795464 0.2128658593 2.4669783115 457 18.2400000000 0.0286922995 0.0232322224 0.0395929739 0.0082271523 0.0723880000 376321000 0 402718720 0.4657666683 0.2076773345 2.4618005753 458 18.2800000000 0.0275937580 0.0232417454 0.0395929739 0.0082440533 0.0765000000 382717752 0 402718720 0.4774072170 0.2068805099 2.4584512711 459 18.3200000000 0.0280043110 0.0232521214 0.0395929739 0.0082368690 0.0844370000 383381393 0 402718720 0.4888491631 0.2094933689 2.4523491859 460 18.3600000000 0.0289181247 0.0232644388 0.0395929739 0.0082388331 0.0611270000 376441460 0 402718720 0.4950364828 0.2046937943 2.4493892193 461 18.4000000000 0.0263368282 0.0232711034 0.0395929739 0.0082356575 0.0756620000 376682208 0 402718720 0.5088797212 0.2051501274 2.4433593750 462 18.4400000000 0.0293663163 0.0232842965 0.0395929739 0.0082287296 0.0587270000 376928323 0 402718720 0.5211298466 0.2041142583 2.4415571690 463 18.4800000000 0.0296254680 0.0232979923 0.0395929739 0.0082272589 0.0819060000 377139968 0 402718720 0.5237653255 0.2063899338 2.4330234528 464 18.5200000000 0.0303967595 0.0233132914 0.0395929739 0.0082213759 0.0746550000 377438096 0 402718720 0.5287799835 0.2025587112 2.4300773144 465 18.5600000000 0.0310731828 0.0233299793 0.0395929739 0.0082177703 0.0694460000 377305884 0 402718720 0.5344568491 0.2003444731 2.4260489941 466 18.6000000000 0.0301514976 0.0233446178 0.0395929739 0.0082331488 0.0825540000 377546420 0 402718720 0.5498052835 0.1995002776 2.4242317677 467 18.6400000000 0.0293135531 0.0233573992 0.0395929739 0.0082319112 0.0671390000 377845836 0 402718720 0.5564969182 0.1956484616 2.4191303253 468 18.6800000000 0.0290897321 0.0233696478 0.0395929739 0.0082317207 0.0705040000 377964756 0 402718720 0.5679417849 0.1924331039 2.4188537598 469 18.7200000000 0.0269501694 0.0233772822 0.0395929739 0.0082560546 0.0831520000 378271328 0 402718720 0.5820233226 0.1895627677 2.4177198410 470 18.7600000000 0.0269724354 0.0233849315 0.0395929739 0.0082792988 0.0666220000 378581408 0 402718720 0.5921571255 0.1917990148 2.4152693748 471 18.8000000000 0.0253072083 0.0233890127 0.0395929739 0.0083353962 0.0681940000 378691004 0 402718720 0.6013445854 0.1889189929 2.4111418724 472 18.8400000000 0.0286709070 0.0234002032 0.0395929739 0.0083663726 0.0823420000 379029368 0 402718720 0.6108289957 0.1864810288 2.4129281044 473 18.8800000000 0.0295185838 0.0234131384 0.0395929739 0.0083722526 0.0753730000 379412364 0 402718720 0.6199019551 0.1874822676 2.4090974331 474 18.9200000000 0.0296381265 0.0234262713 0.0395929739 0.0083698178 0.0700870000 379446904 0 402718720 0.6229553223 0.1850325465 2.4007709026 475 18.9600000000 0.0299155489 0.0234399330 0.0395929739 0.0083676115 0.0834280000 379767068 0 402718720 0.6329786181 0.1825556010 2.3999125957 476 19.0000000000 0.0315948278 0.0234570651 0.0395929739 0.0083724456 0.0798630000 380095844 0 402718720 0.6393030882 0.1812684387 2.3975517750 477 19.0400000000 0.0300333723 0.0234708519 0.0395929739 0.0083741350 0.0706450000 380170736 0 402718720 0.6465456486 0.1801486462 2.3872756958 478 19.0800000000 0.0296487808 0.0234837764 0.0395929739 0.0083679141 0.0850690000 380540000 0 402718720 0.6604680419 0.1785837859 2.3910512924 479 19.1200000000 0.0282740016 0.0234937769 0.0395929739 0.0083606370 0.0891100000 381048996 0 402718720 0.6696852446 0.1772717088 2.3890697956 480 19.1600000000 0.0297915768 0.0235068973 0.0395929739 0.0083654792 0.0770310000 380988331 0 402718720 0.6772264838 0.1748469174 2.3911435604 481 19.2000000000 0.0299990494 0.0235203945 0.0395929739 0.0083804147 0.0790400000 381215216 0 402718720 0.6842432022 0.1789160520 2.3842999935 482 19.2400000000 0.0315325074 0.0235370172 0.0395929739 0.0083727388 0.0826470000 381632348 0 402718720 0.6944010258 0.1771756560 2.3882508278 483 19.2800000000 0.0328320190 0.0235562615 0.0395929739 0.0083647072 0.0930010000 381858760 0 402718720 0.7004425526 0.1765133440 2.3861365318 484 19.3200000000 0.0351905935 0.0235802994 0.0395929739 0.0083614899 0.0838630000 382163276 0 402718720 0.7055866718 0.1819875389 2.3819718361 485 19.3600000000 0.0421661697 0.0236186207 0.0421661697 0.0083599562 0.0698970000 382247604 0 402718720 0.7065495253 0.1828341186 2.3814096451 486 19.4000000000 0.0454402640 0.0236635212 0.0454402640 0.0083635839 0.0735760000 382580272 0 402718720 0.7112811804 0.1867909729 2.3788607121 487 19.4400000000 0.0385464616 0.0236940817 0.0454402640 0.0083952396 0.0758840000 382919112 0 402718720 0.7237535119 0.1800531894 2.3739581108 488 19.4800000000 0.0396660119 0.0237268111 0.0454402640 0.0083962218 0.0785580000 383022508 0 402718720 0.7229796648 0.1814292818 2.3657150269 489 19.5200000000 0.0448424667 0.0237699924 0.0454402640 0.0083899106 0.0913150000 383402008 0 402718720 0.7229527235 0.1804274619 2.3643090725 490 19.5600000000 0.0448517501 0.0238130163 0.0454402640 0.0083815693 0.0932760000 383952340 0 402718720 0.7259757519 0.1797724515 2.3544592857 491 19.6000000000 0.0470246524 0.0238602906 0.0470246524 0.0083745879 0.0801180000 383886059 0 402718720 0.7319440246 0.1792728156 2.3535563946 492 19.6400000000 0.0461439937 0.0239055826 0.0470246524 0.0083665824 0.0795970000 384067488 0 402718720 0.7321140766 0.1803125292 2.3400061131 493 19.6800000000 0.0467134714 0.0239518461 0.0470246524 0.0083631224 0.0823900000 384172652 0 402718720 0.7342315912 0.1797655374 2.3296639919 494 19.7200000000 0.0408936702 0.0239861413 0.0470246524 0.0083633915 0.0971560000 384464716 0 402718720 0.7417637110 0.1746687293 2.3200433254 495 19.7600000000 0.0411493964 0.0240208145 0.0470246524 0.0083570785 0.0945570000 384727728 0 402718720 0.7399755716 0.1695414335 2.3090670109 496 19.8000000000 0.0426629819 0.0240583996 0.0470246524 0.0083509961 0.0886130000 384560044 0 402718720 0.7388969064 0.1697413027 2.3041360378 497 19.8400000000 0.0426699668 0.0240958474 0.0470246524 0.0083449031 0.0967750000 384686944 0 402718720 0.7432035208 0.1706737876 2.2967584133 498 19.8800000000 0.0412249118 0.0241302431 0.0470246524 0.0083391516 0.0904030000 384950252 0 402718720 0.7421852350 0.1671685725 2.2854375839 499 19.9200000000 0.0396310277 0.0241613068 0.0470246524 0.0083320451 0.0917920000 390067052 0 402718720 0.7464267015 0.1681111306 2.2782056332 500 19.9600000000 0.0387898460 0.0241905639 0.0470246524 0.0083243261 0.1075910000 395494197 0 402718720 0.7456089258 0.1635494828 2.2676961422 501 20.0000000000 0.0450033098 0.0242321063 0.0470246524 0.0083212900 0.1037470000 390136149 0 402718720 0.7390321493 0.1648273021 2.2569596767 502 20.0400000000 0.0489049219 0.0242812553 0.0489049219 0.0083144621 0.0762980000 384620048 0 402718720 0.7380853891 0.1637385190 2.2512784004 503 20.0800000000 0.0486488007 0.0243296997 0.0489049219 0.0083076800 0.0991950000 385075084 0 402718720 0.7423942089 0.1623307765 2.2417819500 504 20.1200000000 0.0477760211 0.0243762202 0.0489049219 0.0083004123 0.0980020000 385300896 0 402718720 0.7424441576 0.1585434526 2.2314145565 505 20.1600000000 0.0441047885 0.0244152867 0.0489049219 0.0083008253 0.0785170000 385241367 0 402718720 0.7409282923 0.1556269675 2.2157945633 506 20.2000000000 0.0479728915 0.0244618432 0.0489049219 0.0082969498 0.1064070000 385586920 0 402718720 0.7383623719 0.1626490653 2.2077412605 507 20.2400000000 0.0482242331 0.0245087118 0.0489049219 0.0082934027 0.0992740000 385789312 0 402718720 0.7370274663 0.1620325148 2.1960132122 508 20.2800000000 0.0484946817 0.0245559283 0.0489049219 0.0082963749 0.0929710000 385695942 0 402718720 0.7295969725 0.1602925062 2.1863093376 509 20.3200000000 0.0486961566 0.0246033551 0.0489049219 0.0082902176 0.1088220000 385834548 0 402718720 0.7330761552 0.1581989825 2.1774225235 510 20.3600000000 0.0491266698 0.0246514400 0.0491266698 0.0082835824 0.0998850000 386012908 0 402718720 0.7369235158 0.1613183767 2.1611022949 511 20.4000000000 0.0519395918 0.0247048415 0.0519395918 0.0082767020 0.1015940000 395392416 0 402718720 0.7367048264 0.1662076116 2.1490108967 512 20.4400000000 0.0495063774 0.0247532820 0.0519395918 0.0082871517 0.0570180000 398817212 0 402718720 0.7354681492 0.1638793349 2.1363794804 513 20.4800000000 0.0628436580 0.0248275322 0.0628436580 0.0083433912 0.1340760000 398754991 0 402718720 0.7404890656 0.1774012148 2.1363091469 514 20.5200000000 0.0642411262 0.0249042124 0.0642411262 0.0083373241 0.0977700000 386310232 0 402718720 0.7395479083 0.1779522151 2.1253354549 515 20.5600000000 0.0687070787 0.0249892665 0.0687070787 0.0083389784 0.1069560000 386366996 0 402718720 0.7401409745 0.1805102527 2.1150248051 516 20.6000000000 0.0693626031 0.0250752613 0.0693626031 0.0083480732 0.1008860000 386568436 0 402718720 0.7419464588 0.1782875657 2.1022808552 517 20.6400000000 0.0668830127 0.0251561274 0.0693626031 0.0083485297 0.1053260000 394930340 0 402718720 0.7401505709 0.1753948629 2.1023206711 518 20.6800000000 0.0681070536 0.0252390442 0.0693626031 0.0083408004 0.0990990000 395149989 0 402718720 0.7539064288 0.1757894307 2.0828077793 519 20.7200000000 0.0711372793 0.0253274801 0.0711372793 0.0083362027 0.1046910000 386876124 0 402718720 0.7416474223 0.1816847473 2.0859580040 520 20.7600000000 0.0642437115 0.0254023190 0.0711372793 0.0083381092 0.1089580000 387067920 0 402718720 0.7407438755 0.1804825962 2.0835940838 521 20.8000000000 0.0650632009 0.0254784436 0.0711372793 0.0083494416 0.1001660000 391011540 0 402718720 0.7382230163 0.1800172031 2.0758819580 522 20.8400000000 0.0662720278 0.0255565922 0.0711372793 0.0083492126 0.0941110000 397863948 0 402718720 0.7379451394 0.1734253913 2.0712673664 523 20.8800000000 0.0613687895 0.0256250668 0.0711372793 0.0083468264 0.0343720000 400123069 0 402718720 0.7334384918 0.1734708101 2.0741276741 524 20.9200000000 0.0692026019 0.0257082300 0.0711372793 0.0083461824 0.0884130000 399234933 0 402718720 0.7417167425 0.1732151508 2.0568661690 525 20.9600000000 0.0644257516 0.0257819777 0.0711372793 0.0083402242 0.0322730000 399873641 0 402718720 0.7450280190 0.1697816253 2.0499050617 526 21.0000000000 0.0636929646 0.0258540518 0.0711372793 0.0083334381 0.0323420000 399142644 0 402718720 0.7524511218 0.1640542746 2.0367417336 527 21.0400000000 0.0417939685 0.0258842983 0.0711372793 0.0085242639 0.1272210000 399236915 0 402718720 0.7726342082 0.1720871031 1.9986100197 528 21.0800000000 0.0401915386 0.0259113953 0.0711372793 0.0085170272 0.0439610000 387209932 0 402718720 0.7757790685 0.1693904400 1.9946025610 529 21.1200000000 0.0424317084 0.0259426247 0.0711372793 0.0085105293 0.0981160000 387389224 0 402718720 0.7861613035 0.1681512594 1.9741909504 530 21.1600000000 0.0406234041 0.0259703242 0.0711372793 0.0085073419 0.1067990000 387388880 0 402718720 0.7876857519 0.1700152755 1.9714789391 531 21.2000000000 0.0432793535 0.0260029213 0.0711372793 0.0085004841 0.0990200000 387519935 0 402718720 0.7923315167 0.1690787971 1.9581065178 532 21.2400000000 0.0426441655 0.0260342018 0.0711372793 0.0084938364 0.1028040000 397532044 0 402718720 0.7920560837 0.1661312878 1.9505447149 533 21.2800000000 0.0420345925 0.0260642213 0.0711372793 0.0084872805 0.0459750000 400426385 0 402718720 0.7914521694 0.1652413905 1.9446775913 534 21.3200000000 0.0457568318 0.0261010989 0.0711372793 0.0084816347 0.0825950000 400114211 0 402718720 0.7969869375 0.1665762067 1.9307383299 535 21.3600000000 0.0475835092 0.0261412529 0.0711372793 0.0084785581 0.0384530000 400616624 0 402718720 0.8008588552 0.1700586081 1.9153423309 536 21.4000000000 0.0436765961 0.0261739681 0.0711372793 0.0084726918 0.0334310000 399947743 0 402718720 0.8000522852 0.1657441556 1.9102762938 537 21.4400000000 0.0370749161 0.0261942678 0.0711372793 0.0084706226 0.1242650000 400001747 0 402718720 0.8127753735 0.1590543091 1.8934730291 538 21.4800000000 0.0373353660 0.0262149762 0.0711372793 0.0084646719 0.0397220000 387783664 0 402718720 0.8141027689 0.1610276401 1.8828660250 539 21.5200000000 0.0421707928 0.0262445788 0.0711372793 0.0084586563 0.1044130000 387946836 0 402718720 0.8092330694 0.1640164554 1.8767398596 540 21.5600000000 0.0395704843 0.0262692564 0.0711372793 0.0084527421 0.1161230000 387948992 0 402718720 0.8124755621 0.1615934372 1.8633663654 541 21.6000000000 0.0407897793 0.0262960966 0.0711372793 0.0084453056 0.1046310000 391776688 0 402718720 0.8129374385 0.1648368090 1.8538157940 542 21.6400000000 0.0378449112 0.0263174043 0.0711372793 0.0084453699 0.1016830000 398487822 0 402718720 0.8214896917 0.1635028422 1.8392150402 543 21.6800000000 0.0382681936 0.0263394132 0.0711372793 0.0084387289 0.0445340000 401837841 0 402718720 0.8189850450 0.1591840833 1.8342322111 544 21.7200000000 0.0385035239 0.0263617737 0.0711372793 0.0084360290 0.0977340000 401457424 0 402718720 0.8183645606 0.1590048671 1.8252613544 545 21.7600000000 0.0358293504 0.0263791454 0.0711372793 0.0084323678 0.0348550000 401993021 0 402718720 0.8237258792 0.1566781253 1.8120027781 546 21.8000000000 0.0375531092 0.0263996105 0.0711372793 0.0084362766 0.0358760000 401376640 0 402718720 0.8247988224 0.1594090164 1.8055573702 547 21.8400000000 0.0303508211 0.0264068339 0.0711372793 0.0084453882 0.1320300000 401308271 0 402718720 0.8328674436 0.1575806439 1.7877557278 548 21.8800000000 0.0314254053 0.0264159919 0.0711372793 0.0084381321 0.0386400000 387912620 0 402718720 0.8293529749 0.1587629169 1.7840538025 549 21.9200000000 0.0311896224 0.0264246870 0.0711372793 0.0084305354 0.0307990000 387914676 0 402718720 0.8306755424 0.1575683504 1.7791914940 550 21.9600000000 0.0313158073 0.0264335800 0.0711372793 0.0084230919 0.0308220000 387917420 0 402718720 0.8301625252 0.1598557830 1.7732365131 551 22.0000000000 0.0312557034 0.0264423316 0.0711372793 0.0084169068 0.0317630000 387919244 0 402718720 0.8326492310 0.1610122472 1.7641025782 552 22.0400000000 0.0285270084 0.0264461081 0.0711372793 0.0084109160 0.0319150000 387921560 0 402718720 0.8377819061 0.1602022946 1.7558127642 553 22.0800000000 0.0331565738 0.0264582428 0.0711372793 0.0084081645 0.0300190000 387923968 0 402718720 0.8309542537 0.1627366841 1.7537118196 554 22.1200000000 0.0305676460 0.0264656605 0.0711372793 0.0084042939 0.0321800000 388330064 0 402718720 0.8354856968 0.1599104404 1.7467262745 555 22.1600000000 0.0304445457 0.0264728297 0.0711372793 0.0083989130 0.1079230000 388484268 0 402718720 0.8391642570 0.1639658213 1.7372328043 556 22.2000000000 0.0281963442 0.0264759295 0.0711372793 0.0083969435 0.1119130000 388485508 0 402718720 0.8367192745 0.1629721522 1.7300941944 557 22.2400000000 0.0310840607 0.0264842026 0.0711372793 0.0084031425 0.1088220000 391956192 0 402718720 0.8354393244 0.1631975770 1.7261308432 558 22.2800000000 0.0309551135 0.0264922150 0.0711372793 0.0083961288 0.1019150000 398924952 0 402718720 0.8331601024 0.1600056738 1.7212065458 559 22.3200000000 0.0315660425 0.0265012916 0.0711372793 0.0083909334 0.0385340000 401787373 0 402718720 0.8325512409 0.1633569598 1.7155067921 560 22.3600000000 0.0316894390 0.0265105562 0.0711372793 0.0083849559 0.0918290000 401162357 0 402718720 0.8332991600 0.1643271744 1.7115893364 561 22.4000000000 0.0343494676 0.0265245293 0.0711372793 0.0083793518 0.0363090000 400914624 0 402718720 0.8311928511 0.1642750502 1.7039858103 562 22.4400000000 0.0313203223 0.0265330627 0.0711372793 0.0083735825 0.0374590000 401078256 0 402718720 0.8322335482 0.1632810086 1.7004578114 563 22.4800000000 0.0303984433 0.0265399284 0.0711372793 0.0083709914 0.1308360000 401010683 0 402718720 0.8369585872 0.1632576138 1.6914813519 564 22.5200000000 0.0331817418 0.0265517047 0.0711372793 0.0083691257 0.0365760000 388499568 0 402718720 0.8344823122 0.1627057195 1.6876938343 565 22.5600000000 0.0339158401 0.0265647385 0.0711372793 0.0083618668 0.0308350000 388501884 0 402718720 0.8377833962 0.1610417515 1.6760363579 566 22.6000000000 0.0295810234 0.0265700677 0.0711372793 0.0083604085 0.0303620000 388504200 0 402718720 0.8430207968 0.1574212462 1.6674375534 567 22.6400000000 0.0337415449 0.0265827158 0.0711372793 0.0083567192 0.0309310000 388506208 0 402718720 0.8404773474 0.1600280404 1.6619162560 568 22.6800000000 0.0343315937 0.0265963582 0.0711372793 0.0083505758 0.0306570000 388508616 0 402718720 0.8465156555 0.1594473124 1.6534811258 569 22.7200000000 0.0392885692 0.0266186643 0.0711372793 0.0083526079 0.0315800000 388510824 0 402718720 0.8416053057 0.1605697423 1.6448299885 570 22.7600000000 0.0361254290 0.0266353429 0.0711372793 0.0083488900 0.0305880000 388513200 0 402718720 0.8406258821 0.1597234756 1.6346559525 571 22.8000000000 0.0338761695 0.0266480238 0.0711372793 0.0083466711 0.0323570000 388958388 0 402718720 0.8424246311 0.1593557149 1.6270868778 572 22.8400000000 0.0302153975 0.0266542605 0.0711372793 0.0083457680 0.1070950000 389098464 0 402718720 0.8458670378 0.1530310810 1.6158961058 573 22.8800000000 0.0327702798 0.0266649342 0.0711372793 0.0083421747 0.1096520000 389100812 0 402718720 0.8439745903 0.1545793861 1.6070404053 574 22.9200000000 0.0332647935 0.0266764322 0.0711372793 0.0083351077 0.1056710000 389122248 0 402718720 0.8399574161 0.1555144489 1.6018867493 575 22.9600000000 0.0322647430 0.0266861510 0.0711372793 0.0083291610 0.1000000000 399203644 0 402718720 0.8399208784 0.1519590020 1.5913836956 576 23.0000000000 0.0338610224 0.0266986074 0.0711372793 0.0083237436 0.0378070000 401465905 0 402718720 0.8380604386 0.1496371031 1.5849406719 577 23.0400000000 0.0306040682 0.0267053759 0.0711372793 0.0083260826 0.0858260000 401106739 0 402718720 0.8354817629 0.1475931406 1.5744946003 578 23.0800000000 0.0350308344 0.0267197798 0.0711372793 0.0083210668 0.0336190000 400909400 0 402718720 0.8356325626 0.1516155303 1.5666739941 579 23.1200000000 0.0322484635 0.0267293285 0.0711372793 0.0083150023 0.0339050000 401066488 0 402718720 0.8344323635 0.1455588341 1.5574553013 580 23.1600000000 0.0292582661 0.0267336887 0.0711372793 0.0083171394 0.1279470000 400998635 0 402718720 0.8418748379 0.1439530402 1.5443810225 581 23.2000000000 0.0333970152 0.0267451575 0.0711372793 0.0083134169 0.0317550000 389115624 0 402718720 0.8408097029 0.1487645358 1.5337474346 582 23.2400000000 0.0302411839 0.0267511644 0.0711372793 0.0083098464 0.0311240000 389118200 0 402718720 0.8415361643 0.1433479637 1.5229511261 583 23.2800000000 0.0302524418 0.0267571700 0.0711372793 0.0083039820 0.0324620000 389120316 0 402718720 0.8387295604 0.1399693042 1.5137245655 584 23.3200000000 0.0341557972 0.0267698389 0.0711372793 0.0083068835 0.0317530000 389122892 0 402718720 0.8346147537 0.1439875215 1.5030226707 585 23.3600000000 0.0287873931 0.0267732877 0.0711372793 0.0083040107 0.0316700000 389125224 0 402718720 0.8326935172 0.1368248761 1.4937179089 586 23.4000000000 0.0269859098 0.0267736505 0.0711372793 0.0083007910 0.0316520000 389127232 0 402718720 0.8350602388 0.1326535344 1.4808907509 587 23.4400000000 0.0292293541 0.0267778340 0.0711372793 0.0083058894 0.0296900000 389129900 0 402718720 0.8349918127 0.1346829534 1.4703174829 588 23.4800000000 0.0294698756 0.0267824123 0.0711372793 0.0083052451 0.0296890000 389132140 0 402718720 0.8311514854 0.1359455734 1.4462924004 589 23.5200000000 0.0243461914 0.0267782761 0.0711372793 0.0083057312 0.0340420000 389604320 0 402718720 0.8313634396 0.1317715645 1.4366505146 590 23.5600000000 0.0259616654 0.0267768920 0.0711372793 0.0083030639 0.1084670000 389740368 0 402718720 0.8265579939 0.1341874152 1.4268584251 591 23.6000000000 0.0273408592 0.0267778463 0.0711372793 0.0083046087 0.1093470000 389741868 0 402718720 0.8267358541 0.1338662952 1.4147504568 592 23.6400000000 0.0256699603 0.0267759749 0.0711372793 0.0083001497 0.1010020000 390057008 0 402718720 0.8276205063 0.1294253170 1.4012260437 593 23.6800000000 0.0261335075 0.0267748914 0.0711372793 0.0082960938 0.1041070000 399125940 0 402718720 0.8229995966 0.1294219494 1.3894940615 594 23.7200000000 0.0254030842 0.0267725820 0.0711372793 0.0082908207 0.0473940000 401619165 0 402718720 0.8189136982 0.1258459538 1.3806571960 595 23.7600000000 0.0249701105 0.0267695526 0.0711372793 0.0082894864 0.0891390000 401513363 0 402718720 0.8170299530 0.1256653219 1.3699407578 596 23.8000000000 0.0251975451 0.0267669150 0.0711372793 0.0082884769 0.0338720000 401590885 0 402718720 0.8183342218 0.1284815073 1.3557577133 597 23.8400000000 0.0229131710 0.0267604599 0.0711372793 0.0082838440 0.0349800000 401469452 0 402718720 0.8184407949 0.1289427578 1.3426969051 598 23.8800000000 0.0210777521 0.0267509570 0.0711372793 0.0082787248 0.1194950000 401401591 0 402718720 0.8125753999 0.1259495169 1.3302373886 599 23.9200000000 0.0222664978 0.0267434704 0.0711372793 0.0082721307 0.0332140000 389754704 0 402718720 0.8086452484 0.1296875179 1.3194975853 600 23.9600000000 0.0213628672 0.0267345028 0.0711372793 0.0082683813 0.0305220000 389757112 0 402718720 0.8065510988 0.1288985908 1.3078541756 601 24.0000000000 0.0263491143 0.0267338615 0.0711372793 0.0082686110 0.0303590000 389759076 0 402718720 0.8005642891 0.1303560138 1.3033856153 602 24.0400000000 0.0213730615 0.0267249565 0.0711372793 0.0082653446 0.0300980000 389761408 0 402718720 0.8006024361 0.1275458783 1.2868456841 603 24.0800000000 0.0250873957 0.0267222408 0.0711372793 0.0082618437 0.0298310000 389763708 0 402718720 0.7947950363 0.1314818561 1.2784563303 604 24.1200000000 0.0227293558 0.0267156301 0.0711372793 0.0082575425 0.0294410000 389766424 0 402718720 0.7949221730 0.1315439641 1.2678056955 605 24.1600000000 0.0211881083 0.0267064937 0.0711372793 0.0082537991 0.0293710000 389768480 0 402718720 0.7916189432 0.1270264238 1.2614947557 606 24.2000000000 0.0232377201 0.0267007697 0.0711372793 0.0082480918 0.0294650000 389770920 0 402718720 0.7895984650 0.1279900968 1.2526086569 607 24.2400000000 0.0215991382 0.0266923650 0.0711372793 0.0082419123 0.0294760000 389773344 0 402718720 0.7887792587 0.1253613085 1.2401583195 608 24.2800000000 0.0208959281 0.0266828314 0.0711372793 0.0082380180 0.0296870000 389775524 0 402718720 0.7892738581 0.1278005391 1.2284563780 609 24.3200000000 0.0236576535 0.0266778639 0.0711372793 0.0082331101 0.0303820000 389777904 0 402718720 0.7850831151 0.1277274638 1.2203283310 610 24.3600000000 0.0219496544 0.0266701128 0.0711372793 0.0082269033 0.0305720000 389780096 0 402718720 0.7831264138 0.1214670390 1.2128180265 611 24.4000000000 0.0217800457 0.0266621094 0.0711372793 0.0082235781 0.0304910000 389782552 0 402718720 0.7802165747 0.1194148064 1.2006710768 612 24.4400000000 0.0230701752 0.0266562402 0.0711372793 0.0082179736 0.0308230000 389785008 0 402718720 0.7765290737 0.1207670271 1.1923696995 613 24.4800000000 0.0263126213 0.0266556797 0.0711372793 0.0082128474 0.0296910000 389787080 0 402718720 0.7748606801 0.1229501516 1.1844315529 614 24.5200000000 0.0223707538 0.0266487009 0.0711372793 0.0082087439 0.0288840000 389789320 0 402718720 0.7728698254 0.1164292842 1.1707055569 615 24.5600000000 0.0220708214 0.0266412572 0.0711372793 0.0082021695 0.0285320000 389792348 0 402718720 0.7722448111 0.1138709560 1.1635327339 616 24.6000000000 0.0246936530 0.0266380955 0.0711372793 0.0081969974 0.0298170000 389794264 0 402718720 0.7704178095 0.1130658537 1.1541898251 617 24.6400000000 0.0232752413 0.0266326452 0.0711372793 0.0081928759 0.0295840000 389796748 0 402718720 0.7677317858 0.1091439873 1.1438422203 618 24.6800000000 0.0213219095 0.0266240518 0.0711372793 0.0081950881 0.0281280000 389798728 0 402718720 0.7684773803 0.1067144722 1.1288435459 619 24.7200000000 0.0221466385 0.0266168185 0.0711372793 0.0081971761 0.0279280000 389801168 0 402718720 0.7691467404 0.1075959355 1.1126880646 620 24.7600000000 0.0252568629 0.0266146250 0.0711372793 0.0081951094 0.0276310000 389803440 0 402718720 0.7623519897 0.1089044288 1.1079486609 621 24.8000000000 0.0264918413 0.0266144273 0.0711372793 0.0081924545 0.0283230000 389805848 0 402718720 0.7630077600 0.1123725325 1.0944787264 622 24.8400000000 0.0294168852 0.0266189329 0.0711372793 0.0081898094 0.0276910000 389808072 0 402718720 0.7559426427 0.1098024547 1.0886542797 623 24.8800000000 0.0235074330 0.0266139385 0.0711372793 0.0081913860 0.0276640000 389810436 0 402718720 0.7582038641 0.1050223708 1.0757979155 624 24.9200000000 0.0278808605 0.0266159688 0.0711372793 0.0081870138 0.0334430000 390512700 0 402718720 0.7549771070 0.1088135839 1.0678744316 625 24.9600000000 0.0283279140 0.0266187079 0.0711372793 0.0081824833 0.1332240000 390606976 0 402718720 0.7530770302 0.1099707782 1.0554410219 626 25.0000000000 0.0276026074 0.0266202796 0.0711372793 0.0081765518 0.1147770000 390609200 0 402718720 0.7520554066 0.1049441993 1.0482504368 627 25.0400000000 0.0266010966 0.0266202490 0.0711372793 0.0081751038 0.1071220000 393985652 0 402718720 0.7493122220 0.1052976921 1.0360685587 628 25.0800000000 0.0253524669 0.0266182303 0.0711372793 0.0081704793 0.1055790000 401250404 0 402718720 0.7464892864 0.1074004695 1.0239317417 629 25.1200000000 0.0268796775 0.0266186459 0.0711372793 0.0081667990 0.0456650000 402538749 0 402718720 0.7424349189 0.1065706015 1.0202584267 630 25.1600000000 0.0267090388 0.0266187894 0.0711372793 0.0081626761 0.0772350000 402578885 0 402718720 0.7387994528 0.1047178358 1.0122950077 631 25.2000000000 0.0286091734 0.0266219437 0.0711372793 0.0081582982 0.0401080000 402429680 0 402718720 0.7319587469 0.1057899669 1.0061758757 632 25.2400000000 0.0266984794 0.0266220648 0.0711372793 0.0081533155 0.1304190000 402361943 0 402718720 0.7222357392 0.1077094972 0.9918213487 633 25.2800000000 0.0301547106 0.0266276456 0.0711372793 0.0081479955 0.0338700000 390625172 0 402718720 0.7170886993 0.1123906523 0.9813169241 634 25.3200000000 0.0285445210 0.0266306691 0.0711372793 0.0081541812 0.0325290000 390627248 0 402718720 0.7096750140 0.1081665009 0.9775029421 635 25.3600000000 0.0300316941 0.0266360251 0.0711372793 0.0081524470 0.0317810000 390629752 0 402718720 0.7078860402 0.1136761904 0.9680113792 636 25.4000000000 0.0244696215 0.0266326188 0.0711372793 0.0081627234 0.0322670000 390632084 0 402718720 0.7049766779 0.1058474481 0.9582368731 637 25.4400000000 0.0278526936 0.0266345341 0.0711372793 0.0081577850 0.0319830000 390634432 0 402718720 0.7002372146 0.1106255949 0.9504430890 638 25.4800000000 0.0254557095 0.0266326864 0.0711372793 0.0081553771 0.0319010000 390637136 0 402718720 0.6979656219 0.1070331112 0.9415533543 639 25.5200000000 0.0322836414 0.0266415299 0.0711372793 0.0081561405 0.0314160000 390639224 0 402718720 0.6904531717 0.1093364730 0.9411670566 640 25.5600000000 0.0295137614 0.0266460177 0.0711372793 0.0081519589 0.0313530000 390641696 0 402718720 0.6862208843 0.1060044616 0.9329738021 641 25.6000000000 0.0324924625 0.0266551385 0.0711372793 0.0081484709 0.0311900000 390644000 0 402718720 0.6786665320 0.1043370664 0.9312281013 642 25.6400000000 0.0341676883 0.0266668403 0.0711372793 0.0081483866 0.0326920000 390646424 0 402718720 0.6749469042 0.1078031808 0.9237164259 643 25.6800000000 0.0309652034 0.0266735252 0.0711372793 0.0081437596 0.0325360000 390649072 0 402718720 0.6710855365 0.1020705998 0.9177491665 644 25.7200000000 0.0280729011 0.0266756981 0.0711372793 0.0081409827 0.0318930000 390651300 0 402718720 0.6675687432 0.1012065709 0.9079562426 645 25.7600000000 0.0328808017 0.0266853184 0.0711372793 0.0081431508 0.0309660000 390653648 0 402718720 0.6581802964 0.0987166613 0.9090452790 646 25.8000000000 0.0343038887 0.0266971119 0.0711372793 0.0081373893 0.0321120000 390656320 0 402718720 0.6526679397 0.0983866379 0.9067416787 647 25.8400000000 0.0389496423 0.0267160493 0.0711372793 0.0081404827 0.0303610000 390658672 0 402718720 0.6433571577 0.1057346314 0.8982408047 648 25.8800000000 0.0329591967 0.0267256838 0.0711372793 0.0081607414 0.0306800000 390661284 0 402718720 0.6405844688 0.0976359248 0.8960388899 649 25.9200000000 0.0337826833 0.0267365575 0.0711372793 0.0081551673 0.0302160000 390663312 0 402718720 0.6325471401 0.0968905911 0.8896146417 650 25.9600000000 0.0310558565 0.0267432026 0.0711372793 0.0081510409 0.0303120000 390665816 0 402718720 0.6170549393 0.0843755156 0.8821824789 651 26.0000000000 0.0369755775 0.0267589205 0.0711372793 0.0081647050 0.0289510000 390668228 0 402718720 0.5994026065 0.0910277963 0.8739473224 652 26.0400000000 0.0361653082 0.0267733475 0.0711372793 0.0081585865 0.0294400000 390670628 0 402718720 0.5892660022 0.0909506977 0.8675269485 653 26.0800000000 0.0330063626 0.0267828927 0.0711372793 0.0081614140 0.0292580000 390673068 0 402718720 0.5819211602 0.0916491002 0.8625215888 654 26.1200000000 0.0316647291 0.0267903572 0.0711372793 0.0081670235 0.0305220000 390675264 0 402718720 0.5717138052 0.0909515917 0.8573388457 655 26.1600000000 0.0296120569 0.0267946652 0.0711372793 0.0081723762 0.0300790000 390678120 0 402718720 0.5621595383 0.0823663473 0.8550536036 656 26.2000000000 0.0440034084 0.0268208980 0.0711372793 0.0082195863 0.0288120000 390680440 0 402718720 0.5484506488 0.0958806723 0.8581330776 657 26.2400000000 0.0471641906 0.0268518619 0.0711372793 0.0082208523 0.0285490000 390682592 0 402718720 0.5368986726 0.0974913388 0.8574858308 658 26.2800000000 0.0407018699 0.0268729106 0.0711372793 0.0082291959 0.0297040000 390684984 0 402718720 0.5264856815 0.0968672633 0.8453088999 659 26.3200000000 0.0467662252 0.0269030977 0.0711372793 0.0082361222 0.0288850000 390687376 0 402718720 0.5125769377 0.1047883630 0.8446745276 660 26.3600000000 0.0390463620 0.0269214966 0.0711372793 0.0082508219 0.0286290000 390689692 0 402718720 0.5049267411 0.0965353996 0.8410317302 661 26.4000000000 0.0487509742 0.0269545215 0.0711372793 0.0082633281 0.0287820000 390692300 0 402718720 0.4885419905 0.1025860012 0.8456633687 662 26.4400000000 0.0343591534 0.0269657068 0.0711372793 0.0083032102 0.0293610000 390694740 0 402718720 0.4824553728 0.1033557206 0.8274005651 663 26.4800000000 0.0345946774 0.0269772135 0.0711372793 0.0083405453 0.0293740000 390696596 0 402718720 0.4704550207 0.0978856161 0.8293853402 664 26.5200000000 0.0346129201 0.0269887131 0.0711372793 0.0083387656 0.0296310000 390699096 0 402718720 0.4618039429 0.0999511331 0.8188397884 665 26.5600000000 0.0412445478 0.0270101504 0.0711372793 0.0083451205 0.0334670000 391411360 0 402718720 0.4493748546 0.1019500047 0.8241410255 666 26.6000000000 0.0431271680 0.0270343501 0.0711372793 0.0083391938 0.1275520000 391488736 0 402718720 0.4373905957 0.1071960181 0.8196482658 667 26.6400000000 0.0425012410 0.0270575389 0.0711372793 0.0083418869 0.1075640000 391715360 0 402718720 0.4271670580 0.1093395576 0.8182209134 668 26.6800000000 0.0422739498 0.0270803179 0.0711372793 0.0083673194 0.1112110000 399515512 0 402718720 0.4157022536 0.1111131534 0.8170095682 669 26.7200000000 0.0410542674 0.0271012058 0.0711372793 0.0084082586 0.0679720000 401184188 0 402718720 0.4061174691 0.1122209430 0.8131703734 670 26.7600000000 0.0376415700 0.0271169376 0.0711372793 0.0084448131 0.0537170000 400888572 0 402718720 0.3969553411 0.1091654673 0.8080490232 671 26.8000000000 0.0132907741 0.0270963323 0.0711372793 0.0085889646 0.1224910000 400820963 0 402718720 0.3928387463 0.0955241919 0.7815800309 672 26.8400000000 0.0123100989 0.0270743290 0.0711372793 0.0085844013 0.0357450000 391509388 0 402718720 0.3832017183 0.0970637649 0.7771021128 673 26.8800000000 0.0110116452 0.0270504617 0.0711372793 0.0085802965 0.0354780000 391511600 0 402718720 0.3743525147 0.0961981639 0.7728890777 674 26.9200000000 0.0121180974 0.0270283069 0.0711372793 0.0085748855 0.0373500000 391514196 0 402718720 0.3652200699 0.0976603478 0.7715857625 675 26.9600000000 0.0133720944 0.0270080755 0.0711372793 0.0085687166 0.0358230000 391516528 0 402718720 0.3561114371 0.1004669219 0.7697768211 676 27.0000000000 0.0102077024 0.0269832228 0.0711372793 0.0085675664 0.0343430000 391518492 0 402718720 0.3470723629 0.1016884372 0.7638567686 677 27.0400000000 0.0148188742 0.0269652548 0.0711372793 0.0085672329 0.0335670000 391520824 0 402718720 0.3380211592 0.1102471054 0.7619184256 678 27.0800000000 0.0105064064 0.0269409792 0.0711372793 0.0085922388 0.0347400000 391523004 0 402718720 0.3317573965 0.1081110761 0.7590065002 679 27.1200000000 0.0096300738 0.0269154845 0.0711372793 0.0086012661 0.0344650000 391525704 0 402718720 0.3207134306 0.1075971946 0.7503988147 680 27.1600000000 0.0107967909 0.0268917806 0.0711372793 0.0086070342 0.0334690000 391527592 0 402718720 0.3142738938 0.1097114086 0.7507820725 681 27.2000000000 0.0108520668 0.0268682274 0.0711372793 0.0086015469 0.0336050000 391529972 0 402718720 0.3059480786 0.1114868075 0.7441098094 682 27.2400000000 0.0095012719 0.0268427626 0.0711372793 0.0085970442 0.0330530000 391532348 0 402718720 0.2965201735 0.1122561917 0.7395809889 683 27.2800000000 0.0106513510 0.0268190563 0.0711372793 0.0085960338 0.0325610000 391534848 0 402718720 0.2897440195 0.1172074378 0.7379188538 684 27.3200000000 0.0091271391 0.0267931909 0.0711372793 0.0086020208 0.0321100000 391536888 0 402718720 0.2819656730 0.1171536520 0.7314704061 685 27.3600000000 0.0104708700 0.0267693627 0.0711372793 0.0086053147 0.0334770000 391539464 0 402718720 0.2736125886 0.1182144955 0.7296516299 686 27.4000000000 0.0133083947 0.0267497403 0.0711372793 0.0086000316 0.0347030000 391541720 0 402718720 0.2660760880 0.1259609014 0.7237309813 687 27.4400000000 0.0129790911 0.0267296957 0.0711372793 0.0086033000 0.0326170000 391544036 0 402718720 0.2569121718 0.1289707124 0.7132372260 688 27.4800000000 0.0085650869 0.0267032937 0.0711372793 0.0086367944 0.0338800000 391546200 0 402718720 0.2488866150 0.1255442053 0.7103297114 689 27.5200000000 0.0088868160 0.0266774352 0.0711372793 0.0086463329 0.0338260000 391548824 0 402718720 0.2412642539 0.1275272369 0.7068843842 690 27.5600000000 0.0129151568 0.0266574899 0.0711372793 0.0086449229 0.0336780000 391551296 0 402718720 0.2324028462 0.1321070492 0.7029088140 691 27.6000000000 0.0092002722 0.0266322262 0.0711372793 0.0086515231 0.0310310000 391553844 0 402718720 0.2247215658 0.1332910508 0.6949034333 692 27.6400000000 0.0112007773 0.0266099264 0.0711372793 0.0086533492 0.0332070000 391555916 0 402718720 0.2158420384 0.1400197446 0.6867071390 693 27.6800000000 0.0119104916 0.0265887151 0.0711372793 0.0086981436 0.0307530000 391557972 0 402718720 0.2096779048 0.1387891173 0.6853064299 694 27.7200000000 0.0146209551 0.0265714705 0.0711372793 0.0087105691 0.0329680000 391560564 0 402718720 0.2021401376 0.1383505613 0.6805481315 695 27.7600000000 0.0151434820 0.0265550273 0.0711372793 0.0087181544 0.0307280000 391563080 0 402718720 0.1951916218 0.1341428012 0.6756371856 696 27.8000000000 0.0103153558 0.0265316945 0.0711372793 0.0087152860 0.0332320000 391565432 0 402718720 0.1858923733 0.1365672499 0.6617316008 697 27.8400000000 0.0100530889 0.0265080523 0.0711372793 0.0087179595 0.0330350000 391567796 0 402718720 0.1791362613 0.1373806447 0.6561788917 698 27.8800000000 0.0164649058 0.0264936638 0.0711372793 0.0087208543 0.0314900000 391569764 0 402718720 0.1682780534 0.1545140296 0.6429111362 699 27.9200000000 0.0120244706 0.0264729640 0.0711372793 0.0087494328 0.0301460000 391572608 0 402718720 0.1604519933 0.1531130373 0.6389147043 700 27.9600000000 0.0059178267 0.0264435995 0.0711372793 0.0087920851 0.0315830000 391574664 0 402718720 0.1523365676 0.1497573853 0.6277642846 701 28.0000000000 0.0066136802 0.0264153115 0.0711372793 0.0088243641 0.0301210000 391577504 0 402718720 0.1453637183 0.1495999992 0.6270638704 702 28.0400000000 0.0121038705 0.0263949248 0.0711372793 0.0088428681 0.0339860000 392277120 0 402718720 0.1399351358 0.1535860598 0.6268590093 703 28.0800000000 0.0123342331 0.0263749238 0.0711372793 0.0088522271 0.1307600000 392348268 0 402718720 0.1327857673 0.1528552324 0.6227458715 704 28.1200000000 0.0129849166 0.0263559039 0.0711372793 0.0088515947 0.1135580000 392565176 0 402718720 0.1258492023 0.1620804816 0.6181787848 705 28.1600000000 0.0151249282 0.0263399734 0.0711372793 0.0088734877 0.1075210000 401572552 0 402718720 0.1175356209 0.1660209000 0.6162292361 706 28.2000000000 0.0170719419 0.0263268459 0.0711372793 0.0088997343 0.0814290000 401616735 0 402718720 0.1117523313 0.1643070877 0.6144366264 707 28.2400000000 0.0090867551 0.0263024611 0.0711372793 0.0089985235 0.1198080000 401439712 0 402718720 0.0999500304 0.1630186290 0.5850981474 708 28.2800000000 0.0098928344 0.0262792836 0.0711372793 0.0089981144 0.0353510000 392360340 0 402718720 0.0934153199 0.1651544422 0.5816872716 709 28.3200000000 0.0080274353 0.0262535405 0.0711372793 0.0089936485 0.0351550000 392362736 0 402718720 0.0875264257 0.1661079526 0.5796017051 710 28.3600000000 0.0079238424 0.0262277241 0.0711372793 0.0089885760 0.0350420000 392365392 0 402718720 0.0822322220 0.1624312699 0.5783428550 711 28.4000000000 0.0089117521 0.0262033697 0.0711372793 0.0089826201 0.0348740000 392367524 0 402718720 0.0728688687 0.1712835133 0.5744038820 712 28.4400000000 0.0102828015 0.0261810093 0.0711372793 0.0089764020 0.0347290000 392369840 0 402718720 0.0632839501 0.1774135232 0.5695133805 713 28.4800000000 0.0093042292 0.0261573392 0.0711372793 0.0089712561 0.0348090000 392372524 0 402718720 0.0602576584 0.1694213450 0.5711821318 714 28.5200000000 0.0096156504 0.0261341716 0.0711372793 0.0089891926 0.0337530000 392374412 0 402718720 0.0497298539 0.1767210215 0.5702837706 715 28.5600000000 0.0095588919 0.0261109894 0.0711372793 0.0089836513 0.0333340000 392376944 0 402718720 0.0427755415 0.1844262779 0.5693609118 716 28.6000000000 0.0086234305 0.0260865654 0.0711372793 0.0089824967 0.0335510000 392379248 0 402718720 0.0367388725 0.1876011193 0.5719158649 717 28.6400000000 0.0130557250 0.0260683913 0.0711372793 0.0089783698 0.0310530000 392381396 0 402718720 0.0268102437 0.1916847229 0.5697342157 718 28.6800000000 0.0107997991 0.0260471259 0.0711372793 0.0089805103 0.0317760000 392383852 0 402718720 0.0213147402 0.1923664510 0.5756257772 719 28.7200000000 0.0112012671 0.0260264779 0.0711372793 0.0089755936 0.0312280000 392386184 0 402718720 0.0131320357 0.1974124163 0.5765907764 720 28.7600000000 0.0115875481 0.0260064239 0.0711372793 0.0089738931 0.0307560000 392388504 0 402718720 0.0061697364 0.1989089847 0.5801287293 721 28.8000000000 0.0110932188 0.0259857398 0.0711372793 0.0089678560 0.0306530000 392390164 0 402718720 -0.0010301471 0.2008553296 0.5849968195 722 28.8400000000 0.0096659632 0.0259631362 0.0711372793 0.0089624444 0.0302630000 392392112 0 402718720 -0.0078313649 0.2049222738 0.5904523134 723 28.8800000000 0.0116756987 0.0259433749 0.0711372793 0.0089567181 0.0295150000 392394552 0 402718720 -0.0161614120 0.2061319351 0.5938562155 724 28.9200000000 0.0112586506 0.0259230921 0.0711372793 0.0089511414 0.0343200000 393099640 0 402718720 -0.0264677107 0.2091552317 0.5997159481 725 28.9600000000 0.0111968815 0.0259027801 0.0711372793 0.0089486767 0.1221670000 393177408 0 402718720 -0.0343215168 0.2110705823 0.6053801775 726 29.0000000000 0.0112351989 0.0258825768 0.0711372793 0.0089512390 0.1018760000 394295429 0 402718720 -0.0421592295 0.2128695548 0.6112800241 727 29.0400000000 0.0122249825 0.0258637906 0.0711372793 0.0089500808 0.0959520000 402476496 0 402718720 -0.0525487661 0.2159049511 0.6163817644 728 29.0800000000 0.0102934102 0.0258424027 0.0711372793 0.0089619316 0.0806110000 402429807 0 402718720 -0.0598115921 0.2153814286 0.6250041723 729 29.1200000000 0.0154252583 0.0258281131 0.0711372793 0.0089632281 0.1131390000 402231663 0 402718720 -0.0725304186 0.2254569232 0.6281787753 730 29.1600000000 0.0160112772 0.0258146654 0.0711372793 0.0089582646 0.0343820000 393186508 0 402718720 -0.0809689462 0.2276785970 0.6346089840 731 29.2000000000 0.0151870092 0.0258001269 0.0711372793 0.0089543106 0.0333800000 393188520 0 402718720 -0.0913491845 0.2282790840 0.6416074038 732 29.2400000000 0.0160770416 0.0257868439 0.0711372793 0.0089485216 0.0326000000 393189532 0 402718720 -0.1005764902 0.2348873466 0.6476897597 733 29.2800000000 0.0168816410 0.0257746950 0.0711372793 0.0089433385 0.0314550000 393192344 0 402718720 -0.1092522442 0.2411205620 0.6561508179 734 29.3200000000 0.0158597529 0.0257611869 0.0711372793 0.0089374509 0.0310580000 393195428 0 402718720 -0.1185620427 0.2429600060 0.6653304100 735 29.3600000000 0.0153323719 0.0257469980 0.0711372793 0.0089332379 0.0292350000 393196640 0 402718720 -0.1260305643 0.2472547591 0.6745677590 736 29.4000000000 0.0147684338 0.0257320815 0.0711372793 0.0089292662 0.0290310000 393198904 0 402718720 -0.1330192983 0.2527170479 0.6847413182 737 29.4400000000 0.0155968266 0.0257183294 0.0711372793 0.0089240628 0.0284670000 393200736 0 402718720 -0.1405606866 0.2564993501 0.6925226450 738 29.4800000000 0.0172019936 0.0257067897 0.0711372793 0.0089197225 0.0275660000 393202612 0 402718720 -0.1497884393 0.2627073824 0.7014170885 739 29.5200000000 0.0164440069 0.0256942555 0.0711372793 0.0089365023 0.0264380000 393204180 0 402718720 -0.1582619846 0.2633511722 0.7091547847 740 29.5600000000 0.0171007141 0.0256826426 0.0711372793 0.0089516910 0.0326250000 393913384 0 402718720 -0.1647116542 0.2665275633 0.7171892524 741 29.6000000000 0.0166582912 0.0256704640 0.0711372793 0.0089736782 0.1105450000 393965232 0 402718720 -0.1716836095 0.2705098987 0.7260092497 742 29.6400000000 0.0167645682 0.0256584614 0.0711372793 0.0089856589 0.0903240000 396924316 0 402718720 -0.1767102778 0.2749463916 0.7354757786 743 29.6800000000 0.0157969594 0.0256451889 0.0711372793 0.0089865116 0.0634130000 401402816 0 402718720 -0.1832812130 0.2741596401 0.7435519695 744 29.7200000000 0.0157806296 0.0256319301 0.0711372793 0.0089807760 0.0507270000 401288297 0 402718720 -0.1876620352 0.2754093707 0.7500239611 745 29.7600000000 0.0100270696 0.0256109839 0.0711372793 0.0089840839 0.0940220000 401276647 0 402718720 -0.1937080026 0.2772585154 0.7634720206 746 29.8000000000 0.0099026691 0.0255899272 0.0711372793 0.0089785042 0.0277350000 393974800 0 402718720 -0.1985020339 0.2788102627 0.7695993781 747 29.8400000000 0.0090457415 0.0255677797 0.0711372793 0.0089728018 0.0277150000 393979180 0 402718720 -0.2024085224 0.2817463875 0.7762529850 748 29.8800000000 0.0106610106 0.0255478509 0.0711372793 0.0089680645 0.0265820000 393981328 0 402718720 -0.2064250410 0.2871927023 0.7820731401 749 29.9200000000 0.0112362765 0.0255287433 0.0711372793 0.0089630577 0.0259440000 393982624 0 402718720 -0.2110896409 0.2908605337 0.7878992558 750 29.9600000000 0.0093154637 0.0255071256 0.0711372793 0.0089599008 0.0256510000 393983688 0 402718720 -0.2145571113 0.2917057276 0.7936543226 751 30.0000000000 0.0099410722 0.0254863985 0.0711372793 0.0089557241 0.0258290000 393989300 0 402718720 -0.2205452025 0.2946174145 0.7985657454 752 30.0400000000 0.0092366226 0.0254647897 0.0711372793 0.0089544320 0.0258540000 393991172 0 402718720 -0.2240293324 0.2958107591 0.8019391298 753 30.0800000000 0.0109902099 0.0254455672 0.0711372793 0.0089504658 0.0252230000 393993276 0 402718720 -0.2264810503 0.3000650108 0.8057035208 754 30.1200000000 0.0105556985 0.0254258194 0.0711372793 0.0089546063 0.0248230000 393994112 0 402718720 -0.2303541601 0.3022199869 0.8103134632 755 30.1600000000 0.0118712243 0.0254078662 0.0711372793 0.0089597852 0.0246520000 393997532 0 402718720 -0.2383238673 0.3041625917 0.8135272861 756 30.2000000000 0.0109963259 0.0253888034 0.0711372793 0.0089685197 0.0250180000 394003772 0 402718720 -0.2400690913 0.3061842918 0.8162192106 757 30.2400000000 0.0120254466 0.0253711503 0.0711372793 0.0089687584 0.0241550000 394004652 0 402718720 -0.2454299331 0.3094205856 0.8177759051 758 30.2800000000 0.0108614666 0.0253520083 0.0711372793 0.0089732496 0.0241880000 394004556 0 402718720 -0.2481491268 0.3112871349 0.8232047558 759 30.3200000000 0.0115734134 0.0253338546 0.0711372793 0.0089829142 0.0239890000 394008212 0 402718720 -0.2546063662 0.3146434724 0.8259954453 760 30.3600000000 0.0112427827 0.0253153138 0.0711372793 0.0089968640 0.0280100000 394545268 0 402718720 -0.2601061463 0.3195384741 0.8297072649 761 30.4000000000 0.0115446206 0.0252972182 0.0711372793 0.0090026715 0.0820470000 394685308 0 402718720 -0.2662938833 0.3230849504 0.8319752216 762 30.4400000000 0.0101768477 0.0252773752 0.0711372793 0.0090049075 0.0763950000 399138620 0 402718720 -0.2731349766 0.3254288435 0.8347122669 763 30.4800000000 0.0120148696 0.0252599932 0.0711372793 0.0090005459 0.0455920000 399485544 0 402718720 -0.2786507010 0.3315511644 0.8372522593 764 30.5200000000 0.0108671905 0.0252411544 0.0711372793 0.0090038529 0.0739170000 399471643 0 402718720 -0.2892701328 0.3343677223 0.8398925066 765 30.5600000000 0.0122376299 0.0252241564 0.0711372793 0.0089991476 0.0256120000 394596268 0 402718720 -0.2945127785 0.3396323025 0.8415137529 766 30.6000000000 0.0126512758 0.0252077427 0.0711372793 0.0089973520 0.0269850000 394599324 0 402718720 -0.3030074239 0.3435571194 0.8435328007 767 30.6400000000 0.0131741157 0.0251920535 0.0711372793 0.0089936464 0.0263280000 394602060 0 402718720 -0.3106952906 0.3479448557 0.8450663090 768 30.6800000000 0.0120313847 0.0251749172 0.0711372793 0.0089954254 0.0256770000 394602664 0 402718720 -0.3188237548 0.3506284058 0.8478581309 769 30.7200000000 0.0117132422 0.0251574117 0.0711372793 0.0089956176 0.0258650000 394607252 0 402718720 -0.3274978697 0.3547146916 0.8503332138 770 30.7600000000 0.0144030331 0.0251434450 0.0711372793 0.0089901276 0.0257760000 394608468 0 402718720 -0.3354303539 0.3618939221 0.8526521921 771 30.8000000000 0.0135306492 0.0251283830 0.0711372793 0.0089866989 0.0246460000 394608640 0 402718720 -0.3423998356 0.3643854856 0.8540862799 772 30.8400000000 0.0127218589 0.0251123124 0.0711372793 0.0089862200 0.0250130000 394611636 0 402718720 -0.3536501527 0.3664764166 0.8559157848 773 30.8800000000 0.0125074117 0.0250960059 0.0711372793 0.0089832300 0.0242810000 394617272 0 402718720 -0.3593471050 0.3688545823 0.8574961424 774 30.9200000000 0.0130423084 0.0250804327 0.0711372793 0.0089895111 0.0243560000 394618072 0 402718720 -0.3718056679 0.3713983595 0.8579617739 775 30.9600000000 0.0129128657 0.0250647326 0.0711372793 0.0089926053 0.0241260000 394620040 0 402718720 -0.3791094422 0.3730516434 0.8598003387 776 31.0000000000 0.0127951764 0.0250489213 0.0711372793 0.0090001940 0.0238560000 394622632 0 402718720 -0.3882950842 0.3746507764 0.8609887958 777 31.0400000000 0.0144307977 0.0250352558 0.0711372793 0.0090024686 0.0286480000 395175420 0 402718720 -0.3957870901 0.3799286783 0.8627035618 778 31.0800000000 0.0152618280 0.0250226935 0.0711372793 0.0090006947 0.0819650000 395206992 0 402718720 -0.4039183259 0.3842122555 0.8639484644 779 31.1200000000 0.0141628273 0.0250087527 0.0711372793 0.0089995332 0.0767700000 398555100 0 402718720 -0.4115779996 0.3852821290 0.8655722141 780 31.1600000000 0.0147668244 0.0249956221 0.0711372793 0.0089972957 0.0480740000 399601967 0 402718720 -0.4191824794 0.3885182738 0.8669569492 781 31.2000000000 0.0137380101 0.0249812077 0.0711372793 0.0090007146 0.0729740000 399555059 0 402718720 -0.4286857843 0.3898468018 0.8681533337 782 31.2400000000 0.0127839660 0.0249656102 0.0711372793 0.0089955911 0.0272100000 395222608 0 402718720 -0.4344187081 0.3905186057 0.8700615168 783 31.2800000000 0.0132418443 0.0249506373 0.0711372793 0.0089901215 0.0276430000 395224172 0 402718720 -0.4408368468 0.3928679228 0.8720313907 784 31.3200000000 0.0138873598 0.0249365260 0.0711372793 0.0089844695 0.0266660000 395227564 0 402718720 -0.4480316639 0.3947808743 0.8732492924 785 31.3600000000 0.0142826056 0.0249229541 0.0711372793 0.0089790732 0.0276210000 395230924 0 402718720 -0.4532636404 0.3956872225 0.8742516041 786 31.4000000000 0.0145690525 0.0249097812 0.0711372793 0.0089745761 0.0276690000 395235080 0 402718720 -0.4599411488 0.3969500363 0.8755419850 787 31.4400000000 0.0148059754 0.0248969429 0.0711372793 0.0089713365 0.0263700000 395235220 0 402718720 -0.4645608664 0.3989116549 0.8763765693 788 31.4800000000 0.0151318656 0.0248845506 0.0711372793 0.0089676432 0.0266590000 395238876 0 402718720 -0.4705677330 0.4001990557 0.8777874708 789 31.5200000000 0.0149060609 0.0248719036 0.0711372793 0.0089637635 0.0267450000 395241992 0 402718720 -0.4761240184 0.4000962973 0.8790682554 790 31.5600000000 0.0154114580 0.0248599284 0.0711372793 0.0089587621 0.0258140000 395243072 0 402718720 -0.4818003476 0.4007743001 0.8802660704 791 31.6000000000 0.0147392442 0.0248471336 0.0711372793 0.0089531636 0.0254880000 395243028 0 402718720 -0.4847807586 0.4000876248 0.8813609481 792 31.6400000000 0.0156834275 0.0248355632 0.0711372793 0.0089476382 0.0253440000 395248136 0 402718720 -0.4896997809 0.4008766413 0.8828777075 793 31.6800000000 0.0165976454 0.0248251749 0.0711372793 0.0089433419 0.0259820000 395251312 0 402718720 -0.4940104485 0.4010128677 0.8837959766 794 31.7200000000 0.0162100513 0.0248143247 0.0711372793 0.0089449908 0.0256580000 395252924 0 402718720 -0.4966228604 0.3994575739 0.8852323294 795 31.7600000000 0.0161223728 0.0248033914 0.0711372793 0.0089494506 0.0250180000 395252728 0 402718720 -0.5009309649 0.3980810344 0.8854861259 796 31.8000000000 0.0159096494 0.0247922183 0.0711372793 0.0089658308 0.0241370000 395250384 0 402718720 -0.5027045012 0.3970131278 0.8881663084 797 31.8400000000 0.0155225983 0.0247805877 0.0711372793 0.0089778695 0.0250500000 395256028 0 402718720 -0.5060436130 0.3955987096 0.8897663355 798 31.8800000000 0.0161889438 0.0247698212 0.0711372793 0.0089938010 0.0246120000 395256980 0 402718720 -0.5083434582 0.3946666718 0.8906932473 799 31.9200000000 0.0156771224 0.0247584411 0.0711372793 0.0090024615 0.0245080000 395260524 0 402718720 -0.5108019114 0.3926124871 0.8929853439 800 31.9600000000 0.0169630926 0.0247486969 0.0711372793 0.0090065132 0.0245060000 395264528 0 402718720 -0.5135247707 0.3917065859 0.8933892250 801 32.0000000000 0.0167929344 0.0247387647 0.0711372793 0.0090186438 0.0256060000 395263868 0 402718720 -0.5148044825 0.3899189830 0.8958805203 802 32.0400000000 0.0170630068 0.0247291939 0.0711372793 0.0090193308 0.0248010000 395268456 0 402718720 -0.5180222988 0.3880397677 0.8970448971 803 32.0800000000 0.0173377115 0.0247199891 0.0711372793 0.0090284104 0.0241320000 395269640 0 402718720 -0.5189880133 0.3878672123 0.8991706371 804 32.1199999990 0.0166492201 0.0247099508 0.0711372793 0.0090404436 0.0258900000 395274948 0 402718720 -0.5200893283 0.3863368332 0.9011039734 805 32.1600000000 0.0168101676 0.0247001374 0.0711372793 0.0090528144 0.0247830000 395276208 0 402718720 -0.5214212537 0.3848469853 0.9033058882 806 32.2000000000 0.0175228883 0.0246912326 0.0711372793 0.0090658121 0.0294640000 395865820 0 402718720 -0.5222675204 0.3840958476 0.9052053094 807 32.2400000000 0.0178855862 0.0246827993 0.0711372793 0.0090798228 0.0845330000 395846000 0 402718720 -0.5231238008 0.3812948167 0.9068191648 808 32.2800000000 0.0174358618 0.0246738304 0.0711372793 0.0090846420 0.0756530000 398319696 0 402718720 -0.5250319242 0.3784383535 0.9091217518 809 32.3200000000 0.0178605057 0.0246654085 0.0711372793 0.0090904876 0.0609710000 400520592 0 402718720 -0.5240261555 0.3752132058 0.9116443992 810 32.3600000000 0.0200605001 0.0246597234 0.0711372793 0.0091048992 0.0754550000 400503587 0 402718720 -0.5244715214 0.3751327991 0.9136820436 811 32.4000000000 0.0190618820 0.0246528210 0.0711372793 0.0091016174 0.0280900000 395852972 0 402718720 -0.5251436830 0.3704223037 0.9162584543 812 32.4399999990 0.0190123878 0.0246458746 0.0711372793 0.0091004915 0.0267580000 395854600 0 402718720 -0.5263417363 0.3670554757 0.9190380573 813 32.4800000000 0.0198557395 0.0246399827 0.0711372793 0.0091006577 0.0262620000 395855832 0 402718720 -0.5257966518 0.3652861714 0.9218711853 814 32.5200000000 0.0190176256 0.0246330756 0.0711372793 0.0090978711 0.0261800000 395859852 0 402718720 -0.5261341333 0.3616614342 0.9251115322 815 32.5600000000 0.0199087877 0.0246272790 0.0711372793 0.0090962609 0.0260720000 395862632 0 402718720 -0.5275111794 0.3595766425 0.9274823666 816 32.6000000000 0.0187986512 0.0246201360 0.0711372793 0.0090912804 0.0256150000 395866508 0 402718720 -0.5282120705 0.3540868759 0.9304648638 817 32.6400000000 0.0193358269 0.0246136681 0.0711372793 0.0090895716 0.0254320000 395867292 0 402718720 -0.5281359553 0.3513848186 0.9340643883 818 32.6800000000 0.0190782789 0.0246069011 0.0711372793 0.0090841618 0.0256330000 395871668 0 402718720 -0.5291852951 0.3472951651 0.9368581772 819 32.7200000000 0.0201781709 0.0246014936 0.0711372793 0.0090797715 0.0245170000 395873004 0 402718720 -0.5307914615 0.3465248346 0.9410047531 820 32.7599999990 0.0186286606 0.0245942097 0.0711372793 0.0090759142 0.0249000000 395876108 0 402718720 -0.5329071879 0.3423711658 0.9450995326 821 32.7999999990 0.0188873541 0.0245872586 0.0711372793 0.0090771811 0.0245660000 395877968 0 402718720 -0.5319529176 0.3406854272 0.9505738616 822 32.8400000000 0.0195769556 0.0245811633 0.0711372793 0.0090943916 0.0244280000 395881560 0 402718720 -0.5331363082 0.3382892609 0.9541918039 823 32.8800000000 0.0191578586 0.0245745737 0.0711372793 0.0091043230 0.0245270000 395884984 0 402718720 -0.5332009196 0.3365651369 0.9611307383 824 32.9200000000 0.0211310294 0.0245703946 0.0711372793 0.0091120184 0.0237820000 395886400 0 402718720 -0.5350047350 0.3374561071 0.9665627480 825 32.9600000000 0.0214776006 0.0245666458 0.0711372793 0.0091249179 0.0250780000 395891160 0 402718720 -0.5352350473 0.3352743983 0.9718785882 826 33.0000000000 0.0205293931 0.0245617580 0.0711372793 0.0091267856 0.0240130000 395891532 0 402718720 -0.5357958674 0.3330489993 0.9781855345 827 33.0400000000 0.0216307621 0.0245582139 0.0711372793 0.0091484340 0.0237360000 395895416 0 402718720 -0.5358971953 0.3310284615 0.9836768508 828 33.0800000000 0.0217556134 0.0245548291 0.0711372793 0.0091673200 0.0238100000 395899408 0 402718720 -0.5371559262 0.3269992471 0.9884966612 829 33.1199999990 0.0209906418 0.0245505297 0.0711372793 0.0091780376 0.0244840000 395906100 0 402718720 -0.5381166935 0.3232093751 0.9953945875 830 33.1600000000 0.0211518444 0.0245464349 0.0711372793 0.0091907876 0.0252540000 395906792 0 402718720 -0.5386906266 0.3197046518 1.0003542900 831 33.2000000000 0.0207074303 0.0245418152 0.0711372793 0.0092053880 0.0238020000 395907636 0 402718720 -0.5388634801 0.3147719502 1.0087243319 832 33.2400000000 0.0195339117 0.0245357961 0.0711372793 0.0092108220 0.0286410000 396599692 0 402718720 -0.5394377708 0.3097677529 1.0160527229 833 33.2800000000 0.0194858108 0.0245297337 0.0711372793 0.0092133999 0.1053770000 396660204 0 402718720 -0.5390378833 0.3065821230 1.0226113796 834 33.3200000000 0.0215675812 0.0245261819 0.0711372793 0.0092181809 0.0924810000 398015248 0 402718720 -0.5408405662 0.3035332561 1.0291823149 835 33.3600000000 0.0223628283 0.0245235911 0.0711372793 0.0092234465 0.0615100000 402112464 0 402718720 -0.5409626961 0.3017992973 1.0347869396 836 33.4000000000 0.0216202959 0.0245201183 0.0711372793 0.0092281981 0.0449490000 402023544 0 402718720 -0.5429890156 0.2972728610 1.0413786173 837 33.4399999990 0.0200321488 0.0245147563 0.0711372793 0.0092352889 0.0864850000 401952427 0 402718720 -0.5464429259 0.2925076783 1.0479710102 838 33.4800000000 0.0193655062 0.0245086116 0.0711372793 0.0092589534 0.0312540000 396672088 0 402718720 -0.5475041270 0.2869731486 1.0549346209 839 33.5200000000 0.0195633192 0.0245027173 0.0711372793 0.0092827306 0.0302360000 396673320 0 402718720 -0.5486981869 0.2845271826 1.0615901947 840 33.5600000000 0.0189917851 0.0244961567 0.0711372793 0.0092975279 0.0300650000 396676332 0 402718720 -0.5499811172 0.2814724445 1.0648108721 841 33.6000000000 0.0193781592 0.0244900711 0.0711372793 0.0092998629 0.0299590000 396680996 0 402718720 -0.5495064259 0.2806771994 1.0707511902 842 33.6400000000 0.0193778835 0.0244839996 0.0711372793 0.0092984491 0.0297070000 396676180 0 402718720 -0.5522483587 0.2782628536 1.0761590004 843 33.6800000000 0.0202928204 0.0244790279 0.0711372793 0.0092977824 0.0300150000 396681040 0 402718720 -0.5543168187 0.2751673162 1.0800124407 844 33.7200000000 0.0200999007 0.0244738393 0.0711372793 0.0092990696 0.0289680000 396683524 0 402718720 -0.5558519363 0.2699656188 1.0855829716 845 33.7599999990 0.0208803508 0.0244695867 0.0711372793 0.0093107660 0.0279140000 396685920 0 402718720 -0.5561825633 0.2675950825 1.0906925201 846 33.7999999990 0.0209440961 0.0244654194 0.0711372793 0.0093144837 0.0285790000 396688804 0 402718720 -0.5576921701 0.2651343644 1.0945487022 847 33.8400000000 0.0199300386 0.0244600648 0.0711372793 0.0093122122 0.0274460000 396687424 0 402718720 -0.5589628220 0.2591193616 1.0982251167 848 33.8800000000 0.0217554811 0.0244568754 0.0711372793 0.0093074797 0.0272590000 396692056 0 402718720 -0.5590528250 0.2578363419 1.1011115313 849 33.9200000000 0.0212415271 0.0244530882 0.0711372793 0.0093021239 0.0275420000 396694360 0 402718720 -0.5605624914 0.2516757846 1.1048340797 850 33.9600000000 0.0196329504 0.0244474174 0.0711372793 0.0092970242 0.0269690000 396694160 0 402718720 -0.5610176325 0.2465436608 1.1089684963 851 34.0000000000 0.0207660794 0.0244430915 0.0711372793 0.0092915586 0.0268950000 396696260 0 402718720 -0.5625216961 0.2445732057 1.1122518778 852 34.0400000000 0.0206241403 0.0244386092 0.0711372793 0.0092864744 0.0276560000 396701876 0 402718720 -0.5637898445 0.2383659333 1.1160216331 853 34.0800000000 0.0211870670 0.0244347973 0.0711372793 0.0092835344 0.0281770000 396703564 0 402718720 -0.5641816854 0.2354301214 1.1185219288 854 34.1199999990 0.0213945862 0.0244312374 0.0711372793 0.0092811560 0.0263380000 396703380 0 402718720 -0.5648828149 0.2328571528 1.1216319799 855 34.1600000000 0.0219269004 0.0244283083 0.0711372793 0.0092814505 0.0267420000 396707720 0 402718720 -0.5634847283 0.2305444032 1.1243194342 856 34.2000000000 0.0204166844 0.0244236218 0.0711372793 0.0092805460 0.0267930000 396710204 0 402718720 -0.5643935204 0.2264926136 1.1289974451 857 34.2400000000 0.0188119002 0.0244170737 0.0711372793 0.0092755154 0.0319180000 397325616 0 402718720 -0.5660057068 0.2238593400 1.1336585283 858 34.2800000000 0.0191275217 0.0244109088 0.0711372793 0.0092704845 0.1069590000 397367292 0 402718720 -0.5662996173 0.2224471420 1.1355704069 859 34.3200000000 0.0208611228 0.0244067763 0.0711372793 0.0092655614 0.0893940000 397401612 0 402718720 -0.5667173862 0.2179085314 1.1368082762 860 34.3600000000 0.0206767824 0.0244024391 0.0711372793 0.0092607367 0.0667710000 403070808 0 402718720 -0.5668777227 0.2132054567 1.1383641958 861 34.4000000000 0.0214395411 0.0243989979 0.0711372793 0.0092566541 0.0447370000 403025444 0 402718720 -0.5666116476 0.2113136947 1.1417293549 862 34.4400000000 0.0180602521 0.0243916443 0.0711372793 0.0092521697 0.0869280000 402951055 0 402718720 -0.5665220022 0.2041125447 1.1461367607 863 34.4800000000 0.0179470628 0.0243841767 0.0711372793 0.0092470473 0.0301580000 397382808 0 402718720 -0.5666542053 0.1977816820 1.1468908787 864 34.5200000000 0.0188559722 0.0243777783 0.0711372793 0.0092424674 0.0288180000 397383052 0 402718720 -0.5664134026 0.1956790686 1.1492290497 865 34.5600000000 0.0176655930 0.0243700185 0.0711372793 0.0092380675 0.0280860000 397384740 0 402718720 -0.5682979226 0.1927131414 1.1500191689 866 34.6000000000 0.0181942154 0.0243628871 0.0711372793 0.0092336937 0.0275050000 397385508 0 402718720 -0.5690112114 0.1921920776 1.1509089470 867 34.6400000000 0.0187730324 0.0243564398 0.0711372793 0.0092298469 0.0281070000 397391688 0 402718720 -0.5703970790 0.1892184317 1.1520683765 868 34.6800000000 0.0192098729 0.0243505105 0.0711372793 0.0092256530 0.0284220000 397392532 0 402718720 -0.5700928569 0.1866066903 1.1533075571 869 34.7200000000 0.0186817702 0.0243439873 0.0711372793 0.0092209260 0.0287530000 397397992 0 402718720 -0.5685994029 0.1832705140 1.1547286510 870 34.7600000000 0.0178498086 0.0243365227 0.0711372793 0.0092161816 0.0271410000 397399436 0 402718720 -0.5709391832 0.1789425611 1.1548695564 871 34.8000000000 0.0198265072 0.0243313447 0.0711372793 0.0092111054 0.0268440000 397400708 0 402718720 -0.5731830597 0.1785666198 1.1548680067 872 34.8400000000 0.0198264122 0.0243261785 0.0711372793 0.0092073968 0.0271930000 397404836 0 402718720 -0.5725501776 0.1765937805 1.1560701132 873 34.8800000000 0.0197444260 0.0243209302 0.0711372793 0.0092025859 0.0265400000 397407136 0 402718720 -0.5743263960 0.1737263948 1.1571595669 874 34.9200000000 0.0194515307 0.0243153588 0.0711372793 0.0091992736 0.0255120000 397407732 0 402718720 -0.5727692246 0.1734618247 1.1591172218 875 34.9600000000 0.0205262210 0.0243110284 0.0711372793 0.0091950307 0.0262870000 397411244 0 402718720 -0.5763441920 0.1737025529 1.1598033905 876 35.0000000000 0.0192489177 0.0243052497 0.0711372793 0.0091907139 0.0262620000 397413608 0 402718720 -0.5773921609 0.1712269187 1.1619468927 877 35.0400000000 0.0191673730 0.0242993912 0.0711372793 0.0091854672 0.0260140000 397415480 0 402718720 -0.5780159235 0.1709832698 1.1628234386 878 35.0800000000 0.0183713548 0.0242926395 0.0711372793 0.0091805618 0.0258300000 397416812 0 402718720 -0.5782455206 0.1708425283 1.1648935080 879 35.1200000000 0.0192269459 0.0242868765 0.0711372793 0.0091753329 0.0260670000 397420508 0 402718720 -0.5794975758 0.1705345064 1.1656169891 880 35.1600000000 0.0190380849 0.0242809119 0.0711372793 0.0091704201 0.0257290000 397422056 0 402718720 -0.5789328218 0.1719164252 1.1667429209 881 35.2000000000 0.0191252381 0.0242750599 0.0711372793 0.0091671694 0.0258370000 397425996 0 402718720 -0.5817303658 0.1707520485 1.1677795649 882 35.2400000000 0.0189740267 0.0242690496 0.0711372793 0.0091626568 0.0259650000 397427636 0 402718720 -0.5805426240 0.1670260429 1.1681988239 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 10:27:13 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 -nan 0.0235300000 348487080 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0011752277 0.0005876138 0.0011752277 0.0017069353 0.0339920000 356822710 0 402718720 -0.0011171711 0.0044873329 0.0022394243 3 0.0800000000 0.0013529639 0.0008427305 0.0013529639 0.0016792189 0.0329320000 356754439 0 402718720 -0.0011656984 -0.0025572311 0.0020437317 4 0.1200000000 0.0019915185 0.0011299275 0.0019915185 0.0021173240 0.0300750000 356728910 0 402718720 -0.0017890255 0.0000652570 -0.0003379207 5 0.1600000000 0.0003839578 0.0009807336 0.0019915185 0.0043348509 0.0307950000 356735142 0 402718720 -0.0012349411 0.0050777872 0.0033282291 6 0.2000000000 0.0012222405 0.0010209847 0.0019915185 0.0043581382 0.0305610000 356737190 0 402718720 0.0018083173 -0.0039285920 0.0028685362 7 0.2400000000 0.0030026590 0.0013040811 0.0030026590 0.0044000149 0.0307120000 356744462 0 402718720 0.0032897096 -0.0125264423 0.0003950770 8 0.2800000000 0.0017833816 0.0013639936 0.0030026590 0.0041625007 0.0312810000 356745922 0 402718720 0.0007242310 -0.0117085772 -0.0013541335 9 0.3200000000 0.0035781697 0.0016100132 0.0035781697 0.0049569506 0.0316330000 356749746 0 402718720 0.0008094867 -0.0064601465 0.0010658921 10 0.3600000000 0.0030995267 0.0017589645 0.0035781697 0.0046823651 0.0408330000 356755886 0 402718720 -0.0008015962 -0.0150050167 -0.0007312616 11 0.4000000000 0.0040766192 0.0019696604 0.0040766192 0.0045239051 0.0300220000 356759442 0 402718720 -0.0002984827 -0.0102611007 -0.0012920911 12 0.4400000000 0.0004901149 0.0018463650 0.0040766192 0.0047416774 0.0426120000 356763306 0 402718720 -0.0023135638 -0.0028096270 0.0014207948 13 0.4800000000 0.0014052172 0.0018124305 0.0040766192 0.0045475017 0.0405420000 356764882 0 402718720 0.0011276806 -0.0051422217 0.0015721995 14 0.5200000000 0.0008524182 0.0017438582 0.0040766192 0.0045293450 0.0425470000 356767254 0 402718720 0.0022124227 -0.0125341555 -0.0007117439 15 0.5600000000 0.0034511855 0.0018576800 0.0040766192 0.0045532477 0.0299070000 356771386 0 402718720 0.0068165166 -0.0083294343 -0.0011562525 16 0.6000000000 0.0018769224 0.0018588827 0.0040766192 0.0044706514 0.0309450000 356775158 0 402718720 0.0050511821 -0.0095413970 -0.0000388827 17 0.6400000000 0.0028150713 0.0019151291 0.0040766192 0.0043761590 0.0420320000 356775046 0 402718720 0.0082809580 -0.0121771013 -0.0025329781 18 0.6800000000 0.0010636748 0.0018678261 0.0040766192 0.0043259733 0.0302410000 356782174 0 402718720 0.0046696211 -0.0123528205 -0.0049425233 19 0.7200000000 0.0029570477 0.0019251535 0.0040766192 0.0043868021 0.0416280000 356785506 0 402718720 0.0059572011 -0.0058433800 -0.0036215454 20 0.7600000000 0.0013199348 0.0018948926 0.0040766192 0.0046725139 0.0300660000 356786946 0 402718720 0.0042350735 -0.0095691765 -0.0065457742 21 0.8000000000 0.0026687873 0.0019317447 0.0040766192 0.0047762645 0.0300050000 356790234 0 402718720 0.0068982225 -0.0044190311 -0.0066046850 22 0.8400000000 0.0019824556 0.0019340497 0.0040766192 0.0047320826 0.0310760000 356793742 0 402718720 0.0091456827 -0.0026204486 -0.0056249010 23 0.8800000000 0.0014369432 0.0019124364 0.0040766192 0.0047063207 0.0325210000 356795426 0 402718720 0.0113394540 -0.0096932165 -0.0092278477 24 0.9200000000 0.0010196090 0.0018752353 0.0040766192 0.0046658995 0.0317340000 356799346 0 402718720 0.0120202843 -0.0090680793 -0.0092515806 25 0.9600000000 0.0015398579 0.0018618202 0.0040766192 0.0045818749 0.0320990000 356801526 0 402718720 0.0135258008 -0.0109128971 -0.0128214210 26 1.0000000000 0.0023403817 0.0018802264 0.0040766192 0.0044949408 0.0316430000 356807562 0 402718720 0.0120264851 -0.0129940696 -0.0120652877 27 1.0400000000 0.0012515986 0.0018569439 0.0040766192 0.0044141908 0.0321090000 356811938 0 402718720 0.0119756823 -0.0154701611 -0.0162418559 28 1.0800000000 0.0020819192 0.0018649787 0.0040766192 0.0043449199 0.0323350000 356815774 0 402718720 0.0100159980 -0.0169224553 -0.0177807081 29 1.1200000000 0.0024559866 0.0018853583 0.0040766192 0.0043822893 0.0319050000 356819286 0 402718720 0.0137492502 -0.0190950260 -0.0186210852 30 1.1600000000 0.0025036226 0.0019059671 0.0040766192 0.0043498668 0.0319370000 356825238 0 402718720 0.0168560278 -0.0182559732 -0.0183859263 31 1.2000000000 0.0026875043 0.0019311780 0.0040766192 0.0043409125 0.0313680000 356828262 0 402718720 0.0224942863 -0.0175315272 -0.0204079617 32 1.2400000000 0.0015598678 0.0019195745 0.0040766192 0.0043955487 0.0312650000 356833406 0 402718720 0.0214738436 -0.0142698474 -0.0222866610 33 1.2800000000 0.0029853862 0.0019518719 0.0040766192 0.0045977465 0.0426510000 356841230 0 402718720 0.0231464580 -0.0094548510 -0.0205193926 34 1.3200000000 0.0021151823 0.0019566751 0.0040766192 0.0047875195 0.0314850000 356854222 0 402718720 0.0309767015 -0.0080491621 -0.0229270943 35 1.3600000000 0.0018546736 0.0019537608 0.0040766192 0.0047275864 0.0312360000 356860310 0 402718720 0.0285170339 -0.0106102824 -0.0243559629 36 1.4000000000 0.0014304566 0.0019392246 0.0040766192 0.0046696073 0.0312520000 356865078 0 402718720 0.0287799872 -0.0126928119 -0.0283525866 37 1.4400000000 0.0015374440 0.0019283656 0.0040766192 0.0046096955 0.0311900000 356868654 0 402718720 0.0313198678 -0.0129097020 -0.0308505669 38 1.4800000000 0.0013672429 0.0019135992 0.0040766192 0.0045483886 0.0311730000 356874610 0 402718720 0.0316564627 -0.0138520170 -0.0306787658 39 1.5200000000 0.0021361124 0.0019193047 0.0040766192 0.0044992806 0.0307990000 356879910 0 402718720 0.0312338602 -0.0120516997 -0.0317844152 40 1.5600000000 0.0023602406 0.0019303281 0.0040766192 0.0046777156 0.0300520000 356883334 0 402718720 0.0363674909 -0.0107968710 -0.0324876644 41 1.6000000000 0.0040354012 0.0019816713 0.0040766192 0.0048653062 0.0302280000 356889522 0 402718720 0.0404085219 -0.0076628146 -0.0322456956 42 1.6400000000 0.0030578570 0.0020072948 0.0040766192 0.0048280920 0.0290600000 356897910 0 402718720 0.0406224616 -0.0087006725 -0.0340164714 43 1.6800000000 0.0036092896 0.0020445505 0.0040766192 0.0048136876 0.0298790000 356901934 0 402718720 0.0438185707 -0.0076933964 -0.0364256389 44 1.7200000000 0.0048421756 0.0021081329 0.0048421756 0.0047760444 0.0287670000 356907466 0 402718720 0.0419952460 -0.0073314421 -0.0356790051 45 1.7600000000 0.0047930270 0.0021677972 0.0048421756 0.0049508876 0.0289920000 356911426 0 402718720 0.0442531779 -0.0053792829 -0.0368862078 46 1.8000000000 0.0043502189 0.0022152412 0.0048421756 0.0050481650 0.0479810000 356916526 0 402718720 0.0464910530 -0.0051349648 -0.0366752446 47 1.8400000000 0.0068414379 0.0023136709 0.0068414379 0.0050342049 0.0287730000 356922562 0 402718720 0.0453881621 -0.0021636346 -0.0363551229 48 1.8800000000 0.0044005341 0.0023571472 0.0068414379 0.0050465036 0.0286460000 356926110 0 402718720 0.0489681363 -0.0030863367 -0.0369347036 49 1.9200000000 0.0030266584 0.0023708107 0.0068414379 0.0050665494 0.0420310000 356931154 0 402718720 0.0528634414 -0.0039608208 -0.0404556878 50 1.9600000000 0.0052403514 0.0024282015 0.0068414379 0.0050477371 0.0286110000 356936034 0 402718720 0.0442172661 -0.0046788529 -0.0407405421 51 2.0000000000 0.0032851808 0.0024450050 0.0068414379 0.0050900865 0.0283210000 356943430 0 402718720 0.0449828282 -0.0011032405 -0.0416421220 52 2.0400000000 0.0018008134 0.0024326167 0.0068414379 0.0050821976 0.0281740000 356946078 0 402718720 0.0485277474 -0.0006594849 -0.0418076143 53 2.0800000000 0.0033998878 0.0024508671 0.0068414379 0.0050447483 0.0417060000 356952090 0 402718720 0.0481691062 -0.0036252490 -0.0435600094 54 2.1200000000 0.0014186805 0.0024317525 0.0068414379 0.0050979445 0.0287430000 356956170 0 402718720 0.0499090999 -0.0056477273 -0.0452556871 55 2.1600000000 0.0032343925 0.0024463460 0.0068414379 0.0050803144 0.0283800000 356960718 0 402718720 0.0511680506 -0.0001871811 -0.0442292057 56 2.2000000000 0.0025019727 0.0024473393 0.0068414379 0.0050661460 0.0282550000 356965890 0 402718720 0.0511190295 -0.0013294895 -0.0454140417 57 2.2400000000 0.0008482377 0.0024192849 0.0068414379 0.0051178613 0.0281620000 356968794 0 402718720 0.0510662198 -0.0061930749 -0.0483539999 58 2.2800000000 0.0028467060 0.0024266542 0.0068414379 0.0053130275 0.0277460000 356974338 0 402718720 0.0550039224 -0.0077437200 -0.0480027311 59 2.3200000000 0.0011560402 0.0024051184 0.0068414379 0.0054265316 0.0280920000 356979578 0 402718720 0.0577090494 -0.0018583382 -0.0476594493 60 2.3600000000 0.0012295970 0.0023855264 0.0068414379 0.0054764848 0.0411140000 356985018 0 402718720 0.0611116588 -0.0066797584 -0.0511058569 61 2.4000000000 0.0035759846 0.0024050421 0.0068414379 0.0054844053 0.0306060000 357515467 0 402718720 0.0607032776 -0.0125138219 -0.0509019345 62 2.4400000000 0.0031066725 0.0024163587 0.0068414379 0.0054860000 0.0710840000 358123739 0 402718720 0.0608330667 -0.0085362634 -0.0506665409 63 2.4800000000 0.0025797419 0.0024189521 0.0068414379 0.0055357376 0.0973380000 359455646 0 402718720 0.0684902966 -0.0083994465 -0.0518828183 64 2.5200000000 0.0040941695 0.0024451274 0.0068414379 0.0055047125 0.0422580000 360356014 0 402718720 0.0687859356 -0.0105158556 -0.0538941808 65 2.5600000000 0.0100428453 0.0025620153 0.0100428453 0.0056149211 0.0330730000 358103958 0 402718720 0.0820249841 -0.0041482188 -0.0552708656 66 2.6000000000 0.0097982138 0.0026716547 0.0100428453 0.0055748269 0.0324940000 358122634 0 402718720 0.0790607631 -0.0092132585 -0.0585300848 67 2.6400000000 0.0115825776 0.0028046536 0.0115825776 0.0055951241 0.0316240000 358127330 0 402718720 0.0811773390 -0.0106915273 -0.0610964969 68 2.6800000000 0.0095694046 0.0029041352 0.0115825776 0.0056757302 0.0312330000 358131862 0 402718720 0.0851453021 -0.0151455002 -0.0599586889 69 2.7200000000 0.0111379055 0.0030234652 0.0115825776 0.0056806771 0.0319370000 358135414 0 402718720 0.0865562484 -0.0112050259 -0.0619892888 70 2.7600000000 0.0100461263 0.0031237889 0.0115825776 0.0057181403 0.0317570000 358139798 0 402718720 0.0886276662 -0.0109225679 -0.0623720810 71 2.8000000000 0.0108309072 0.0032323399 0.0115825776 0.0057606492 0.0320820000 358144650 0 402718720 0.0919606760 -0.0103059392 -0.0649779513 72 2.8400000000 0.0111449398 0.0033422371 0.0115825776 0.0057630668 0.0526380000 358148670 0 402718720 0.0942998901 -0.0109531162 -0.0654143840 73 2.8800000000 0.0101121999 0.0034349763 0.0115825776 0.0058346816 0.0314560000 358151318 0 402718720 0.0966563821 -0.0110143889 -0.0680468529 74 2.9200000000 0.0107847350 0.0035342974 0.0115825776 0.0059072234 0.0333180000 358564883 0 402718720 0.0984927490 -0.0087558730 -0.0705181807 75 2.9600000000 0.0116075017 0.0036419401 0.0116075017 0.0059476388 0.0897070000 358665406 0 402718720 0.1050582528 -0.0090015028 -0.0719599724 76 3.0000000000 0.0113632213 0.0037435359 0.0116075017 0.0059601663 0.0569240000 361030350 0 402718720 0.1077023894 -0.0069820043 -0.0748974383 77 3.0400000000 0.0120255742 0.0038510949 0.0120255742 0.0059786197 0.0448640000 360695817 0 402718720 0.1107989773 -0.0052986811 -0.0756093115 78 3.0800000000 0.0140629243 0.0039820158 0.0140629243 0.0059503046 0.0304750000 358637670 0 402718720 0.1167896092 -0.0096531734 -0.0801164433 79 3.1200000000 0.0129113700 0.0040950456 0.0140629243 0.0059566029 0.0429100000 358640250 0 402718720 0.1175355464 -0.0046538338 -0.0796528757 80 3.1600000000 0.0124600409 0.0041996080 0.0140629243 0.0059534312 0.0315970000 358643082 0 402718720 0.1228063479 -0.0087767048 -0.0829826742 81 3.2000000000 0.0109783560 0.0042832962 0.0140629243 0.0059246516 0.0324810000 359096431 0 402718720 0.1268993765 -0.0099763619 -0.0835245252 82 3.2400000000 0.0100793093 0.0043539793 0.0140629243 0.0059045129 0.0944660000 359237558 0 402718720 0.1305416524 -0.0144272493 -0.0870293975 83 3.2800000000 0.0116377268 0.0044417353 0.0140629243 0.0059317230 0.0682450000 361770853 0 402718720 0.1324431300 -0.0092125395 -0.0858481452 84 3.3200000000 0.0108887684 0.0045184857 0.0140629243 0.0059139983 0.0580100000 361977075 0 402718720 0.1388783604 -0.0118377777 -0.0909959227 85 3.3600000000 0.0121071935 0.0046077646 0.0140629243 0.0058808765 0.0305360000 359184298 0 402718720 0.1497346610 -0.0069774031 -0.0920918509 86 3.4000000000 0.0101547418 0.0046722644 0.0140629243 0.0059018740 0.0302990000 359190646 0 402718720 0.1501800269 -0.0043355837 -0.0919873267 87 3.4400000000 0.0123441359 0.0047604468 0.0140629243 0.0058806642 0.0303150000 359192570 0 402718720 0.1561290771 -0.0088265650 -0.0972353816 88 3.4800000000 0.0089140302 0.0048076466 0.0140629243 0.0058611963 0.0324580000 359712175 0 402718720 0.1576564014 -0.0049089780 -0.0971602798 89 3.5200000000 0.0125263799 0.0048943739 0.0140629243 0.0058577253 0.0934030000 359724726 0 402718720 0.1643835157 -0.0037163789 -0.0980342850 90 3.5600000000 0.0129865203 0.0049842867 0.0140629243 0.0058259721 0.0808350000 362703834 0 402718720 0.1665917486 -0.0013356772 -0.1003337502 91 3.6000000000 0.0104289567 0.0050441182 0.0140629243 0.0058466309 0.0420540000 363050306 0 402718720 0.1712127924 -0.0027384246 -0.0996738747 92 3.6400000000 0.0150010502 0.0051523457 0.0150010502 0.0059846919 0.0415380000 360799165 0 402718720 0.1846106946 0.0018163465 -0.1010486111 93 3.6800000000 0.0138514508 0.0052458845 0.0150010502 0.0059831868 0.0305870000 359740614 0 402718720 0.1921161562 0.0045264503 -0.1022412479 94 3.7200000000 0.0117997378 0.0053156064 0.0150010502 0.0059575762 0.0304580000 359741810 0 402718720 0.1986827105 0.0026383714 -0.1047955900 95 3.7600000000 0.0141807711 0.0054089239 0.0150010502 0.0059272063 0.0300620000 359748222 0 402718720 0.2073451579 0.0015738405 -0.1085804105 96 3.8000000000 0.0116724307 0.0054741687 0.0150010502 0.0059423490 0.0296180000 359752466 0 402718720 0.2104804963 0.0044462774 -0.1081294268 97 3.8400000000 0.0142365955 0.0055645030 0.0150010502 0.0059249778 0.0298310000 359755282 0 402718720 0.2222128510 0.0035131830 -0.1137290448 98 3.8800000000 0.0122766783 0.0056329946 0.0150010502 0.0059082929 0.0286980000 359757622 0 402718720 0.2286708653 0.0045596426 -0.1113359183 99 3.9200000000 0.0139029343 0.0057165294 0.0150010502 0.0059108838 0.0289070000 359761690 0 402718720 0.2379033417 0.0051524695 -0.1147245318 100 3.9600000000 0.0145459538 0.0058048236 0.0150010502 0.0058824080 0.0292340000 359766578 0 402718720 0.2468429208 0.0042524072 -0.1155019253 101 4.0000000000 0.0152070094 0.0058979146 0.0152070094 0.0058662249 0.0293150000 359769178 0 402718720 0.2561962605 0.0060607158 -0.1174583063 102 4.0400000000 0.0130679989 0.0059682095 0.0152070094 0.0058853538 0.0288590000 359773926 0 402718720 0.2586163282 0.0058233123 -0.1173877046 103 4.0800000000 0.0137208058 0.0060434774 0.0152070094 0.0058567558 0.0314110000 360239511 0 402718720 0.2675224245 0.0087062065 -0.1177425608 104 4.1200000000 0.0160128083 0.0061393364 0.0160128083 0.0058292042 0.1019900000 360399867 0 402718720 0.2798089683 0.0123570813 -0.1195652783 105 4.1600000000 0.0135437651 0.0062098547 0.0160128083 0.0058256226 0.0860920000 360413995 0 402718720 0.2850689888 0.0101586375 -0.1190706789 106 4.2000000000 0.0118924174 0.0062634638 0.0160128083 0.0058454036 0.0670650000 364285979 0 402718720 0.2896770835 0.0105558038 -0.1207175404 107 4.2400000000 0.0101961959 0.0063002183 0.0160128083 0.0058398168 0.0804730000 364272795 0 402718720 0.2963582873 0.0051959930 -0.1241683215 108 4.2800000000 0.0106339976 0.0063403459 0.0160128083 0.0058300111 0.0308680000 360409171 0 402718720 0.3050926626 0.0087937303 -0.1246111467 109 4.3200000000 0.0116044236 0.0063886402 0.0160128083 0.0058064946 0.0314860000 360412227 0 402718720 0.3230924010 0.0084543582 -0.1276280731 110 4.3600000000 0.0147085795 0.0064642760 0.0160128083 0.0058143501 0.0316430000 360414591 0 402718720 0.3377479017 0.0107725896 -0.1296644956 111 4.4000000000 0.0134039456 0.0065267956 0.0160128083 0.0057972039 0.0407200000 360415911 0 402718720 0.3465139866 0.0068819439 -0.1326298267 112 4.4400000000 0.0140186371 0.0065936870 0.0160128083 0.0057850431 0.0447930000 360864859 0 402718720 0.3527186215 0.0060685528 -0.1333020329 113 4.4800000000 0.0135516440 0.0066552619 0.0160128083 0.0057615885 0.1008290000 361005043 0 402718720 0.3599073291 0.0077833957 -0.1333110631 114 4.5200000000 0.0133617865 0.0067140910 0.0160128083 0.0057438763 0.0768930000 365519135 0 402718720 0.3711676300 0.0071571637 -0.1333473921 115 4.5600000000 0.0153929126 0.0067895590 0.0160128083 0.0057340221 0.0461120000 365467807 0 402718720 0.3825545609 0.0066044233 -0.1355157495 116 4.6000000000 0.0105147567 0.0068216728 0.0160128083 0.0057508944 0.0816520000 365319177 0 402718720 0.3871822953 -0.0028111790 -0.1390298158 117 4.6400000000 0.0096439384 0.0068457947 0.0160128083 0.0057502811 0.0303600000 361012415 0 402718720 0.3937403858 -0.0066257389 -0.1403715760 118 4.6800000000 0.0096442364 0.0068695103 0.0160128083 0.0057560827 0.0328680000 361476099 0 402718720 0.4031383991 -0.0051240535 -0.1397774667 119 4.7200000000 0.0101159494 0.0068967913 0.0160128083 0.0057933479 0.1005780000 361595243 0 402718720 0.4168260396 -0.0053026997 -0.1398053467 120 4.7600000000 0.0083156703 0.0069086153 0.0160128083 0.0057701731 0.0906740000 361597307 0 402718720 0.4265668690 -0.0028102659 -0.1371102333 121 4.8000000000 0.0109245824 0.0069418051 0.0160128083 0.0057746087 0.0849800000 365022831 0 402718720 0.4367566705 -0.0002981853 -0.1379238516 122 4.8400000000 0.0092639392 0.0069608390 0.0160128083 0.0057723848 0.0669020000 366627699 0 402718720 0.4448890686 -0.0018778369 -0.1385047883 123 4.8800000000 0.0099912714 0.0069854767 0.0160128083 0.0057522290 0.0315600000 366529255 0 402718720 0.4569660425 -0.0009142375 -0.1377131045 124 4.9200000000 0.0097392201 0.0070076843 0.0160128083 0.0057526730 0.0820520000 366256025 0 402718720 0.4635623693 0.0026590815 -0.1313126087 125 4.9600000000 0.0108437976 0.0070383732 0.0160128083 0.0057362052 0.0318260000 362137047 0 402718720 0.4682812095 0.0009967731 -0.1316186190 126 5.0000000000 0.0095435996 0.0070582560 0.0160128083 0.0057177403 0.0965200000 362180092 0 402718720 0.4765501320 0.0008468851 -0.1290045679 127 5.0400000000 0.0092303539 0.0070753591 0.0160128083 0.0056962343 0.0868800000 362180944 0 402718720 0.4855330288 0.0022584461 -0.1270768493 128 5.0800000000 0.0093839476 0.0070933949 0.0160128083 0.0056889872 0.0782700000 364054040 0 402718720 0.4979883432 0.0032961313 -0.1229424626 129 5.1200000000 0.0074737244 0.0070963432 0.0160128083 0.0056751589 0.0592840000 367587027 0 402718720 0.5067117214 0.0053255353 -0.1175332516 130 5.1600000000 0.0068531008 0.0070944721 0.0160128083 0.0056585963 0.0854490000 367464231 0 402718720 0.5136672258 0.0040678205 -0.1164110303 131 5.2000000000 0.0070452723 0.0070940966 0.0160128083 0.0056897223 0.0296250000 362213820 0 402718720 0.5201058388 0.0043511130 -0.1124908477 132 5.2400000000 0.0093423603 0.0071111289 0.0160128083 0.0056688048 0.0296100000 362217812 0 402718720 0.5329666138 0.0051928768 -0.1103305966 133 5.2800000000 0.0083784834 0.0071206578 0.0160128083 0.0056527917 0.0291110000 362220740 0 402718720 0.5414866209 0.0078444965 -0.1044103652 134 5.3200000000 0.0105116405 0.0071459637 0.0160128083 0.0056625048 0.0296730000 362225464 0 402718720 0.5530332923 0.0068951175 -0.1027066559 135 5.3600000000 0.0085672000 0.0071564914 0.0160128083 0.0056821440 0.0316700000 362651808 0 402718720 0.5620650053 0.0038372912 -0.0996641219 136 5.4000000000 0.0105046099 0.0071811099 0.0160128083 0.0057100191 0.0922580000 363017736 0 402718720 0.5769670010 0.0154304318 -0.0929597020 137 5.4400000000 0.0083948737 0.0071899695 0.0160128083 0.0057068642 0.0815910000 366832272 0 402718720 0.5805835724 0.0177181419 -0.0890063196 138 5.4800000000 0.0110877557 0.0072182143 0.0160128083 0.0057321317 0.0580230000 368613154 0 402718720 0.5866696835 0.0176464822 -0.0866089910 139 5.5200000000 0.0111237550 0.0072463117 0.0160128083 0.0057252661 0.0421880000 368614484 0 402718720 0.5960332155 0.0133334212 -0.0833664536 140 5.5600000000 0.0121894758 0.0072816200 0.0160128083 0.0057082685 0.0899800000 368540687 0 402718720 0.6047179699 0.0170244984 -0.0796969235 141 5.6000000000 0.0099523813 0.0073005616 0.0160128083 0.0056902574 0.0314350000 362792836 0 402718720 0.6116181612 0.0170293171 -0.0736164898 142 5.6400000000 0.0094964020 0.0073160253 0.0160128083 0.0056763836 0.0289170000 362795240 0 402718720 0.6217459440 0.0177789032 -0.0688605458 143 5.6800000000 0.0077644465 0.0073191611 0.0160128083 0.0056710954 0.0296200000 362799292 0 402718720 0.6293175817 0.0209724437 -0.0618819594 144 5.7200000000 0.0099840779 0.0073376674 0.0160128083 0.0056749040 0.0294660000 362801900 0 402718720 0.6369377375 0.0219896529 -0.0586555153 145 5.7600000000 0.0103988210 0.0073587788 0.0160128083 0.0056617637 0.0289230000 362804212 0 402718720 0.6455453038 0.0195591208 -0.0543406606 146 5.8000000000 0.0088768266 0.0073691764 0.0160128083 0.0056432981 0.0285650000 362805324 0 402718720 0.6538196802 0.0222762227 -0.0473369360 147 5.8400000000 0.0108002666 0.0073925172 0.0160128083 0.0056275239 0.0294080000 362810564 0 402718720 0.6652498245 0.0276924316 -0.0407465398 148 5.8800000000 0.0099252481 0.0074096302 0.0160128083 0.0056611653 0.0295910000 362812928 0 402718720 0.6687988639 0.0252432767 -0.0365306735 149 5.9200000000 0.0085327411 0.0074171679 0.0160128083 0.0056451092 0.0283980000 362815356 0 402718720 0.6730363369 0.0234768465 -0.0322528183 150 5.9600000000 0.0090610590 0.0074281272 0.0160128083 0.0056498055 0.0286740000 362819060 0 402718720 0.6819871664 0.0287012737 -0.0248206258 151 6.0000000000 0.0069047455 0.0074246611 0.0160128083 0.0056400237 0.0285980000 362818800 0 402718720 0.6878310442 0.0288631730 -0.0198812187 152 6.0400000000 0.0086404113 0.0074326594 0.0160128083 0.0056446411 0.0284270000 362820588 0 402718720 0.7026732564 0.0273724105 -0.0111919343 153 6.0800000000 0.0108722504 0.0074551404 0.0160128083 0.0056811854 0.0274980000 362821884 0 402718720 0.7126740813 0.0315981507 -0.0059208274 154 6.1200000000 0.0120613342 0.0074850507 0.0160128083 0.0056628095 0.0301500000 363340556 0 402718720 0.7194199562 0.0341633856 -0.0022087991 155 6.1600000000 0.0090442812 0.0074951103 0.0160128083 0.0056729182 0.0895160000 363369136 0 402718720 0.7206370831 0.0351294503 0.0040077567 156 6.2000000000 0.0118496995 0.0075230243 0.0160128083 0.0056719494 0.0850880000 363373728 0 402718720 0.7321604490 0.0346903168 0.0071460605 157 6.2400000000 0.0109767253 0.0075450224 0.0160128083 0.0056839555 0.0798450000 363611704 0 402718720 0.7380610704 0.0363982469 0.0139508843 158 6.2800000000 0.0147473039 0.0075906065 0.0160128083 0.0056801420 0.0757750000 369511864 0 402718720 0.7452840209 0.0397159606 0.0177896023 159 6.3200000000 0.0123539213 0.0076205644 0.0160128083 0.0057274179 0.0662860000 369492659 0 402718720 0.7510105968 0.0367830321 0.0247613192 160 6.3600000000 0.0128111169 0.0076530054 0.0160128083 0.0057880719 0.0305390000 369502848 0 402718720 0.7649351358 0.0453808233 0.0415410995 161 6.4000000000 0.0121998005 0.0076812464 0.0160128083 0.0058058177 0.0825200000 369212713 0 402718720 0.7690978050 0.0431508571 0.0475579500 162 6.4400000000 0.0119512426 0.0077076044 0.0160128083 0.0057984003 0.0288830000 363382000 0 402718720 0.7735496163 0.0486769229 0.0555281341 163 6.4800000000 0.0112694418 0.0077294561 0.0160128083 0.0058077816 0.0284630000 363384344 0 402718720 0.7800709009 0.0455954075 0.0639986992 164 6.5200000000 0.0132559836 0.0077631545 0.0160128083 0.0058230388 0.0287260000 363385184 0 402718720 0.7888155580 0.0513356104 0.0722920597 165 6.5600000000 0.0123797404 0.0077911338 0.0160128083 0.0058302560 0.0278670000 363390152 0 402718720 0.7971089482 0.0527101457 0.0812920332 166 6.6000000000 0.0130581129 0.0078228626 0.0160128083 0.0058448101 0.0276440000 363388420 0 402718720 0.8052705526 0.0567122065 0.0888417959 167 6.6400000000 0.0150935091 0.0078663994 0.0160128083 0.0058767228 0.0297660000 363824536 0 402718720 0.8113787174 0.0599757992 0.0969334543 168 6.6800000000 0.0119993864 0.0078910005 0.0160128083 0.0058921411 0.0940050000 363922424 0 402718720 0.8163814545 0.0596972816 0.1069906652 169 6.7200000000 0.0122495200 0.0079167905 0.0160128083 0.0058865899 0.0873320000 363923092 0 402718720 0.8250572681 0.0630707443 0.1162278652 170 6.7600000000 0.0109090060 0.0079343918 0.0160128083 0.0059000339 0.0829430000 364172924 0 402718720 0.8294961452 0.0668530837 0.1265437603 171 6.8000000000 0.0115411077 0.0079554837 0.0160128083 0.0058827317 0.0804750000 370309016 0 402718720 0.8398420811 0.0691377074 0.1371813715 172 6.8400000000 0.0121401371 0.0079798131 0.0160128083 0.0058740552 0.0718850000 370426635 0 402718720 0.8467479944 0.0758320242 0.1483078301 173 6.8800000000 0.0116252210 0.0080008848 0.0160128083 0.0058776802 0.0311810000 370434804 0 402718720 0.8511569500 0.0707421601 0.1520692110 174 6.9200000000 0.0107713938 0.0080168073 0.0160128083 0.0058645014 0.0950160000 370360287 0 402718720 0.8590708971 0.0733421147 0.1630752087 175 6.9600000000 0.0135281077 0.0080483004 0.0160128083 0.0058608107 0.0368700000 363940972 0 402718720 0.8712413311 0.0755569115 0.1716342866 176 7.0000000000 0.0133042540 0.0080781638 0.0160128083 0.0058495796 0.0323200000 363937240 0 402718720 0.8781893253 0.0805210769 0.1836387515 177 7.0400000000 0.0133538535 0.0081079699 0.0160128083 0.0058898622 0.0281660000 363942728 0 402718720 0.8833790421 0.0784915611 0.1918697059 178 7.0800000000 0.0107768560 0.0081229637 0.0160128083 0.0059290052 0.0278790000 363944672 0 402718720 0.8848760724 0.0804061890 0.2009422779 179 7.1200000000 0.0108676786 0.0081382973 0.0160128083 0.0059136336 0.0274600000 363947788 0 402718720 0.8909631968 0.0821057409 0.2092239857 180 7.1600000000 0.0125314137 0.0081627035 0.0160128083 0.0059037484 0.0316720000 364575068 0 402718720 0.8989429474 0.0806041956 0.2171432674 181 7.2000000000 0.0125039862 0.0081866885 0.0160128083 0.0058879324 0.1010730000 364580056 0 402718720 0.9026325941 0.0805915743 0.2259306014 182 7.2400000000 0.0103510693 0.0081985807 0.0160128083 0.0058815988 0.0898710000 364583596 0 402718720 0.9061132073 0.0864494890 0.2355101407 183 7.2800000000 0.0111974040 0.0082149677 0.0160128083 0.0058664033 0.0881700000 364586256 0 402718720 0.9126135111 0.0869751498 0.2447653413 184 7.3200000000 0.0125211105 0.0082383706 0.0160128083 0.0058558774 0.0840790000 366009304 0 402718720 0.9190019369 0.0895186216 0.2518268526 185 7.3600000000 0.0117810788 0.0082575204 0.0160128083 0.0058451763 0.0713070000 371713476 0 402718720 0.9219968319 0.0882643908 0.2576283813 186 7.4000000000 0.0128628314 0.0082822802 0.0160128083 0.0058318731 0.0719290000 371798271 0 402718720 0.9283416271 0.0915358886 0.2674014866 187 7.4400000000 0.0121775540 0.0083031105 0.0160128083 0.0058287426 0.0345390000 371636948 0 402718720 0.9329140186 0.0925266743 0.2757698596 188 7.4800000000 0.0087641077 0.0083055626 0.0160128083 0.0058190463 0.1041680000 371565591 0 402718720 0.9339414239 0.0927221403 0.2839509249 189 7.5200000000 0.0074702851 0.0083011432 0.0160128083 0.0058079877 0.0357760000 364602696 0 402718720 0.9361613393 0.0905961320 0.2899216115 190 7.5600000000 0.0065819677 0.0082920949 0.0160128083 0.0057975279 0.0305020000 364604212 0 402718720 0.9405127764 0.0921996310 0.3000518978 191 7.6000000000 0.0077576060 0.0082892965 0.0160128083 0.0057852892 0.0437540000 364607768 0 402718720 0.9451414347 0.0950826779 0.3077828288 192 7.6400000000 0.0073500243 0.0082844044 0.0160128083 0.0057732258 0.0308000000 364611248 0 402718720 0.9477512240 0.0952288210 0.3149764240 193 7.6800000000 0.0075251218 0.0082804703 0.0160128083 0.0057643166 0.0421750000 364613336 0 402718720 0.9526200294 0.0994531736 0.3319240212 194 7.7200000000 0.0068257013 0.0082729715 0.0160128083 0.0057499122 0.0330670000 365181180 0 402718720 0.9561106563 0.1007930189 0.3406288624 195 7.7600000000 0.0075797662 0.0082694166 0.0160128083 0.0057361726 0.1088790000 365264844 0 402718720 0.9615275264 0.1024968773 0.3583640158 196 7.8000000000 0.0064079599 0.0082599194 0.0160128083 0.0057294945 0.1031450000 365269164 0 402718720 0.9607383609 0.1010781676 0.3671104908 197 7.8400000000 0.0084309652 0.0082607877 0.0160128083 0.0057187940 0.1022770000 365273660 0 402718720 0.9649376869 0.1029846072 0.3766334653 198 7.8800000000 0.0074152895 0.0082565175 0.0160128083 0.0057089462 0.0641460000 372896316 0 402718720 0.9666223526 0.1006592512 0.3869895637 199 7.9200000000 0.0071735368 0.0082510753 0.0160128083 0.0057054463 0.0754040000 372991955 0 402718720 0.9662114382 0.1019602418 0.3981739283 200 7.9600000000 0.0083160903 0.0082514004 0.0160128083 0.0056934823 0.0356580000 372818296 0 402718720 0.9691336155 0.1028386354 0.4075285196 201 8.0000000000 0.0080827093 0.0082505612 0.0160128083 0.0056799804 0.1065070000 372748203 0 402718720 0.9718277454 0.1022685543 0.4204717875 202 8.0400000000 0.0095711732 0.0082570988 0.0160128083 0.0056668160 0.0424840000 365277264 0 402718720 0.9726606011 0.1039689630 0.4307660758 203 8.0800000000 0.0084046358 0.0082578256 0.0160128083 0.0056543474 0.0323370000 365285704 0 402718720 0.9713351727 0.1039552465 0.4413973093 204 8.1200000000 0.0075611970 0.0082544108 0.0160128083 0.0056457327 0.0424310000 365284760 0 402718720 0.9711277485 0.1030945927 0.4514245689 205 8.1600000000 0.0085684564 0.0082559427 0.0160128083 0.0056546382 0.0306550000 365288436 0 402718720 0.9730685949 0.1055885404 0.4628160894 206 8.1999999990 0.0085204663 0.0082572268 0.0160128083 0.0056611092 0.0418040000 365289872 0 402718720 0.9724028111 0.1109749526 0.4762295485 207 8.2400000000 0.0092191556 0.0082618738 0.0160128083 0.0056705572 0.0307330000 365291964 0 402718720 0.9752935171 0.1087137014 0.4872415960 208 8.2799999990 0.0074605094 0.0082580211 0.0160128083 0.0056653239 0.0369840000 365977992 0 402718720 0.9721338153 0.1151947528 0.4996236265 209 8.3200000000 0.0085621439 0.0082594762 0.0160128083 0.0056616318 0.1144990000 365959228 0 402718720 0.9724421501 0.1187552437 0.5124868155 210 8.3599999990 0.0080265868 0.0082583672 0.0160128083 0.0056525175 0.1061590000 365962192 0 402718720 0.9736160636 0.1184480786 0.5235801935 211 8.4000000000 0.0079784943 0.0082570408 0.0160128083 0.0056465358 0.1035020000 366262496 0 402718720 0.9744250774 0.1199737638 0.5362110734 212 8.4399999990 0.0081091691 0.0082563433 0.0160128083 0.0056405288 0.0970810000 370193892 0 402718720 0.9741742611 0.1195364520 0.5479886532 213 8.4800000000 0.0070054266 0.0082504705 0.0160128083 0.0056306964 0.0597750000 374138368 0 402718720 0.9711688161 0.1232295558 0.5596928596 214 8.5200000000 0.0070406678 0.0082448172 0.0160128083 0.0056220987 0.0764720000 374241847 0 402718720 0.9702689052 0.1263258308 0.5720365644 215 8.5600000000 0.0074691442 0.0082412094 0.0160128083 0.0056181237 0.0341680000 374045136 0 402718720 0.9715346098 0.1272484511 0.5828830004 216 8.6000000000 0.0063762506 0.0082325753 0.0160128083 0.0056109165 0.1015230000 373813005 0 402718720 0.9707834721 0.1294945180 0.5948730707 217 8.6400000000 0.0054462939 0.0082197353 0.0160128083 0.0056041903 0.0401430000 365971972 0 402718720 0.9687563181 0.1298736781 0.6057019234 218 8.6800000000 0.0068082763 0.0082132607 0.0160128083 0.0055956133 0.0344100000 366538740 0 402718720 0.9678989649 0.1319489479 0.6152779460 219 8.7200000000 0.0063919853 0.0082049444 0.0160128083 0.0055897847 0.1080700000 366613092 0 402718720 0.9647387266 0.1346808225 0.6266835928 220 8.7600000000 0.0059221028 0.0081945679 0.0160128083 0.0055799052 0.1017410000 366615004 0 402718720 0.9610484838 0.1341397017 0.6360163689 221 8.8000000000 0.0062251720 0.0081856566 0.0160128083 0.0055692040 0.0949550000 366915744 0 402718720 0.9616135359 0.1354015023 0.6474772692 222 8.8400000000 0.0068867034 0.0081798054 0.0160128083 0.0055594736 0.0929810000 371592400 0 402718720 0.9601622224 0.1380831450 0.6581943035 223 8.8800000000 0.0052142045 0.0081665068 0.0160128083 0.0055477538 0.0545700000 375347500 0 402718720 0.9565716982 0.1367943585 0.6688264608 224 8.9200000000 0.0056557418 0.0081552980 0.0160128083 0.0055363121 0.0828020000 375395055 0 402718720 0.9552253485 0.1373006999 0.6788552999 225 8.9600000000 0.0059978710 0.0081457094 0.0160128083 0.0055297088 0.0359160000 375205700 0 402718720 0.9558528662 0.1368149966 0.6906965971 226 9.0000000000 0.0057999929 0.0081353302 0.0160128083 0.0055239663 0.1025880000 374979637 0 402718720 0.9565021992 0.1423647553 0.7134891152 227 9.0400000000 0.0048706606 0.0081209484 0.0160128083 0.0055132085 0.0470170000 367170700 0 402718720 0.9561140537 0.1436801255 0.7244324088 228 9.0800000000 0.0066025900 0.0081142889 0.0160128083 0.0055047113 0.1123710000 367249828 0 402718720 0.9551066160 0.1459331959 0.7327820063 229 9.1200000000 0.0048028911 0.0080998286 0.0160128083 0.0055124306 0.0957620000 367242076 0 402718720 0.9535423517 0.1458807439 0.7435246706 230 9.1600000000 0.0053693554 0.0080879570 0.0160128083 0.0055091772 0.0916000000 367253972 0 402718720 0.9547427893 0.1487915218 0.7542118430 231 9.2000000000 0.0043328120 0.0080717010 0.0160128083 0.0055058862 0.0962740000 372071828 0 402718720 0.9530705214 0.1489410102 0.7726167440 232 9.2400000000 0.0057531628 0.0080617073 0.0160128083 0.0054949251 0.0654730000 376358252 0 402718720 0.9550694227 0.1508672088 0.7838629484 233 9.2800000000 0.0053527560 0.0080500809 0.0160128083 0.0054979405 0.0365460000 376253856 0 402718720 0.9555631876 0.1530963778 0.7962145209 234 9.3200000000 0.0051521072 0.0080376964 0.0160128083 0.0055061419 0.1105140000 376184119 0 402718720 0.9532520771 0.1596501470 0.8085768223 235 9.3600000000 0.0043451623 0.0080219835 0.0160128083 0.0055048492 0.0577870000 367261072 0 402718720 0.9530876875 0.1594615132 0.8188365698 236 9.4000000000 0.0049213986 0.0080088454 0.0160128083 0.0054969500 0.0352880000 367904596 0 402718720 0.9548228383 0.1611856222 0.8290681839 237 9.4400000000 0.0053813765 0.0079977590 0.0160128083 0.0055004850 0.1132070000 367889524 0 402718720 0.9568455815 0.1627075523 0.8397259712 238 9.4800000000 0.0047097825 0.0079839440 0.0160128083 0.0054976732 0.1011660000 367896648 0 402718720 0.9565241337 0.1647698283 0.8506109715 239 9.5200000000 0.0055707307 0.0079738469 0.0160128083 0.0054967362 0.0957960000 368175468 0 402718720 0.9594056606 0.1662901342 0.8603894711 240 9.5600000000 0.0055661229 0.0079638147 0.0160128083 0.0054980873 0.0963320000 375020578 0 402718720 0.9580864906 0.1692132205 0.8711628914 241 9.6000000000 0.0046608341 0.0079501094 0.0160128083 0.0054880412 0.0444830000 377709313 0 402718720 0.9562218189 0.1693630964 0.8805280924 242 9.6400000000 0.0058866013 0.0079415825 0.0160128083 0.0054920287 0.0499090000 377315161 0 402718720 0.9574673176 0.1736989319 0.8930760622 243 9.6800000000 0.0043589971 0.0079268393 0.0160128083 0.0054825507 0.0358840000 377393380 0 402718720 0.9593644142 0.1747722179 0.9062696695 244 9.7200000000 0.0056542750 0.0079175255 0.0160128083 0.0054734107 0.1148660000 377325175 0 402718720 0.9621239901 0.1794061959 0.9191542864 245 9.7600000000 0.0047079208 0.0079044251 0.0160128083 0.0054670367 0.0625350000 367912444 0 402718720 0.9608092904 0.1799591333 0.9289835691 246 9.8000000000 0.0048190625 0.0078918830 0.0160128083 0.0054580207 0.0324000000 367910528 0 402718720 0.9641776085 0.1811296046 0.9407509565 247 9.8400000000 0.0051269885 0.0078806891 0.0160128083 0.0054484494 0.0329190000 367914344 0 402718720 0.9631217718 0.1856111288 0.9524377584 248 9.8800000000 0.0045966459 0.0078674470 0.0160128083 0.0054422015 0.0321010000 367919128 0 402718720 0.9631628990 0.1880476624 0.9631287456 249 9.9200000000 0.0042862394 0.0078530646 0.0160128083 0.0054313387 0.0327200000 367920644 0 402718720 0.9642272592 0.1890221238 0.9733579755 250 9.9600000000 0.0043167686 0.0078389194 0.0160128083 0.0054211462 0.0314660000 367919088 0 402718720 0.9652043581 0.1905192286 0.9841479659 251 10.0000000000 0.0034279877 0.0078213460 0.0160128083 0.0054144628 0.0368610000 368630556 0 402718720 0.9640550613 0.1901635528 0.9922425747 252 10.0400000000 0.0049371738 0.0078099009 0.0160128083 0.0054058612 0.1186710000 368609044 0 402718720 0.9655783176 0.1933773905 1.0023438931 253 10.0800000000 0.0037445491 0.0077938323 0.0160128083 0.0053979574 0.1049670000 368612608 0 402718720 0.9653618932 0.1934774220 1.0114222765 254 10.1200000000 0.0042103780 0.0077797242 0.0160128083 0.0053900821 0.1020450000 368906804 0 402718720 0.9657103419 0.1962924749 1.0206969976 255 10.1600000000 0.0045401603 0.0077670200 0.0160128083 0.0053802833 0.0999730000 376211312 0 402718720 0.9656857252 0.1969238520 1.0291008949 256 10.2000000000 0.0037713863 0.0077514121 0.0160128083 0.0053843023 0.0492950000 378793796 0 402718720 0.9633936882 0.1984876394 1.0371400118 257 10.2400000000 0.0029535415 0.0077327433 0.0160128083 0.0053955492 0.0778270000 378805685 0 402718720 0.9621213675 0.1981645226 1.0457240343 258 10.2800000000 0.0030813597 0.0077147147 0.0160128083 0.0053980236 0.0395150000 378742084 0 402718720 0.9616026282 0.2022359222 1.0559841394 259 10.3200000000 0.0033426466 0.0076978341 0.0160128083 0.0054024959 0.1195210000 378670647 0 402718720 0.9623500705 0.2024254650 1.0643067360 260 10.3600000000 0.0041674976 0.0076842559 0.0160128083 0.0054007692 0.0448470000 368674820 0 402718720 0.9602366686 0.2049645334 1.0717600584 261 10.4000000000 0.0032395360 0.0076672263 0.0160128083 0.0053926865 0.0323540000 368672836 0 402718720 0.9579247236 0.2067466378 1.0820448399 262 10.4400000000 0.0028121015 0.0076486953 0.0160128083 0.0053824097 0.0319020000 368676516 0 402718720 0.9584736824 0.2079187483 1.0915237665 263 10.4800000000 0.0015595971 0.0076255429 0.0160128083 0.0053729363 0.0370990000 369337636 0 402718720 0.9565826654 0.2087314278 1.1011068821 264 10.5200000000 0.0020595053 0.0076044594 0.0160128083 0.0053653992 0.1076860000 369320836 0 402718720 0.9552347660 0.2095874697 1.1087855101 265 10.5600000000 0.0025749006 0.0075854799 0.0160128083 0.0053555019 0.0960370000 369325328 0 402718720 0.9551522732 0.2098110169 1.1164197922 266 10.6000000000 0.0018641561 0.0075639712 0.0160128083 0.0053461616 0.0878400000 371719876 0 402718720 0.9552012682 0.2105809003 1.1251903772 267 10.6400000000 0.0014183379 0.0075409538 0.0160128083 0.0053398196 0.0551080000 379931940 0 402718720 0.9539096355 0.2116207778 1.1335959435 268 10.6800000000 0.0016725274 0.0075190567 0.0160128083 0.0053311885 0.0891050000 379824941 0 402718720 0.9526751637 0.2141553164 1.1434018612 269 10.7200000000 0.0030661719 0.0075025032 0.0160128083 0.0053360464 0.0371780000 379768820 0 402718720 0.9480519295 0.2153439969 1.1530014277 270 10.7600000000 0.0040113931 0.0074895732 0.0160128083 0.0053300702 0.1178240000 379749519 0 402718720 0.9492924213 0.2196283638 1.1614830494 271 10.8000000000 0.0023113983 0.0074704655 0.0160128083 0.0053235795 0.0419510000 369339832 0 402718720 0.9477661848 0.2192629874 1.1711426973 272 10.8400000000 0.0033407642 0.0074552828 0.0160128083 0.0053143955 0.0352710000 369913268 0 402718720 0.9445588589 0.2223593146 1.1796412468 273 10.8800000000 0.0042180414 0.0074434248 0.0160128083 0.0053069859 0.1126640000 369977840 0 402718720 0.9431642294 0.2220124006 1.1889610291 274 10.9200000000 0.0041564624 0.0074314286 0.0160128083 0.0052978426 0.0996730000 369983876 0 402718720 0.9410738945 0.2246619761 1.1990834475 275 10.9600000000 0.0041995286 0.0074196762 0.0160128083 0.0052915483 0.0942750000 370248624 0 402718720 0.9389835596 0.2273427993 1.2082731724 276 11.0000000000 0.0034658718 0.0074053508 0.0160128083 0.0052828015 0.0905210000 376775396 0 402718720 0.9340764880 0.2269708216 1.2161068916 277 11.0400000000 0.0028897314 0.0073890490 0.0160128083 0.0052774905 0.0403570000 381079572 0 402718720 0.9336395264 0.2278472483 1.2272593975 278 11.0800000000 0.0025975516 0.0073718134 0.0160128083 0.0052687574 0.0912600000 380985005 0 402718720 0.9269279242 0.2301857919 1.2363662720 279 11.1200000000 0.0025218246 0.0073544299 0.0160128083 0.0052599910 0.0362820000 381098465 0 402718720 0.9232138395 0.2301442921 1.2464030981 280 11.1600000000 0.0034787434 0.0073405882 0.0160128083 0.0052553518 0.1210250000 380899135 0 402718720 0.9176915884 0.2338850051 1.2587728500 281 11.2000000000 0.0016520581 0.0073203443 0.0160128083 0.0052484768 0.0327910000 369994448 0 402718720 0.9163177609 0.2360507101 1.2672904730 282 11.2400000000 0.0015252606 0.0072997943 0.0160128083 0.0052414526 0.0361410000 370609156 0 402718720 0.9132916927 0.2371041775 1.2765910625 283 11.2800000000 0.0016381629 0.0072797886 0.0160128083 0.0052362341 0.1190170000 370696560 0 402718720 0.9120529890 0.2391786277 1.2853722572 284 11.3200000000 0.0022087928 0.0072619329 0.0160128083 0.0052285087 0.1061690000 370698912 0 402718720 0.9073156118 0.2427457571 1.2964893579 285 11.3600000000 0.0022968615 0.0072445116 0.0160128083 0.0052201117 0.0998940000 370980936 0 402718720 0.9025979042 0.2434036136 1.3051111698 286 11.4000000000 0.0015539087 0.0072246144 0.0160128083 0.0052209583 0.1010540000 379336648 0 402718720 0.9034725428 0.2457580119 1.3156472445 287 11.4400000000 0.0010580578 0.0072031282 0.0160128083 0.0052121385 0.0531900000 382646181 0 402718720 0.9003114700 0.2495916486 1.3248851299 288 11.4800000000 0.0011608739 0.0071821481 0.0160128083 0.0052032255 0.0947280000 382363245 0 402718720 0.8919348121 0.2507052124 1.3326251507 289 11.5200000000 0.0009888220 0.0071607179 0.0160128083 0.0051961001 0.0384030000 382496533 0 402718720 0.8872529268 0.2494249493 1.3390060663 290 11.5600000000 0.0047190380 0.0071522983 0.0160128083 0.0052005028 0.1209750000 382247023 0 402718720 0.8801521659 0.2520267367 1.3487772942 291 11.6000000000 0.0047860341 0.0071441668 0.0160128083 0.0051942750 0.0696550000 370709016 0 402718720 0.8790121078 0.2559022009 1.3570078611 292 11.6400000000 0.0029741516 0.0071298860 0.0160128083 0.0051893700 0.0332930000 370714004 0 402718720 0.8761945367 0.2542795241 1.3644447327 293 11.6800000000 0.0042408123 0.0071200257 0.0160128083 0.0051816831 0.0336250000 370717184 0 402718720 0.8739771843 0.2577657700 1.3705422878 294 11.7200000000 0.0032493544 0.0071068601 0.0160128083 0.0051749656 0.0324330000 370719876 0 402718720 0.8712678552 0.2566382885 1.3768455982 295 11.7600000000 0.0045771552 0.0070982848 0.0160128083 0.0051747228 0.0370620000 371340168 0 402718720 0.8699675798 0.2587864101 1.3848779202 296 11.8000000000 0.0041302224 0.0070882576 0.0160128083 0.0051893463 0.1200250000 371409120 0 402718720 0.8675938845 0.2587331533 1.3927719593 297 11.8400000000 0.0053672083 0.0070824628 0.0160128083 0.0052254241 0.1056950000 371411120 0 402718720 0.8617626429 0.2591811419 1.3999451399 298 11.8800000000 0.0035596811 0.0070706414 0.0160128083 0.0052244385 0.1005810000 371698188 0 402718720 0.8608229160 0.2577944100 1.4087337255 299 11.9200000000 0.0038793925 0.0070599683 0.0160128083 0.0052219925 0.0979700000 376901136 0 402718720 0.8586671352 0.2576742172 1.4166200161 300 11.9600000000 0.0025882404 0.0070450626 0.0160128083 0.0052166407 0.0528430000 383973729 0 402718720 0.8575922251 0.2559409738 1.4243263006 301 12.0000000000 0.0056765513 0.0070405160 0.0160128083 0.0052221685 0.0980150000 383657453 0 402718720 0.8542972207 0.2588448524 1.4347264767 302 12.0400000000 0.0033720878 0.0070283689 0.0160128083 0.0052150410 0.0393840000 384126249 0 402718720 0.8552424908 0.2574301660 1.4424136877 303 12.0800000000 0.0043877414 0.0070196540 0.0160128083 0.0052098377 0.0372550000 383617880 0 402718720 0.8534202576 0.2579434216 1.4501316547 304 12.1200000000 0.0058901645 0.0070159385 0.0160128083 0.0052092445 0.1272010000 383572669 0 402718720 0.8499368429 0.2591715753 1.4596310854 305 12.1600000000 0.0034335495 0.0070041930 0.0160128083 0.0052060674 0.0967730000 371406208 0 402718720 0.8511085510 0.2585009336 1.4688053131 306 12.2000000000 0.0031613151 0.0069916346 0.0160128083 0.0051975831 0.0329390000 371431852 0 402718720 0.8485227823 0.2592196465 1.4776153564 307 12.2400000000 0.0044386922 0.0069833188 0.0160128083 0.0051949991 0.0338260000 371438116 0 402718720 0.8454483747 0.2619961202 1.4879032373 308 12.2800000000 0.0041388841 0.0069740836 0.0160128083 0.0051905437 0.0329000000 371436804 0 402718720 0.8444893360 0.2623104155 1.4972215891 309 12.3200000000 0.0031203872 0.0069616121 0.0160128083 0.0051843948 0.0539180000 371441688 0 402718720 0.8440623879 0.2620621622 1.5056517124 310 12.3600000000 0.0022877175 0.0069465350 0.0160128083 0.0051882570 0.0367210000 372059592 0 402718720 0.8433630466 0.2640652061 1.5161782503 311 12.4000000000 0.0026042596 0.0069325727 0.0160128083 0.0052035532 0.1188240000 372127140 0 402718720 0.8426725864 0.2667619586 1.5260467529 312 12.4400000000 0.0026777566 0.0069189355 0.0160128083 0.0052130540 0.0994900000 372130584 0 402718720 0.8413203955 0.2655578256 1.5339382887 313 12.4800000000 0.0025957429 0.0069051234 0.0160128083 0.0052100281 0.0968810000 372403888 0 402718720 0.8404871225 0.2667486668 1.5438902378 314 12.5200000000 0.0028480720 0.0068922028 0.0160128083 0.0052076774 0.0971980000 378467212 0 402718720 0.8384585381 0.2680080533 1.5534709692 315 12.5600000000 0.0042740298 0.0068838912 0.0160128083 0.0052059297 0.0871750000 384612836 0 402718720 0.8360948563 0.2699045837 1.5617574453 316 12.6000000000 0.0034081899 0.0068728921 0.0160128083 0.0051986374 0.0752590000 384875427 0 402718720 0.8376084566 0.2687164843 1.5696295500 317 12.6400000000 0.0022020980 0.0068581578 0.0160128083 0.0051945710 0.0515460000 385083305 0 402718720 0.8379564881 0.2686903775 1.5777368546 318 12.6800000000 0.0022280784 0.0068435978 0.0160128083 0.0051875578 0.0379550000 384838008 0 402718720 0.8374758959 0.2702319026 1.5867580175 319 12.7200000000 0.0020769502 0.0068286553 0.0160128083 0.0051809403 0.1255230000 384767347 0 402718720 0.8350913525 0.2728850842 1.5973658562 320 12.7600000000 0.0024790636 0.0068150628 0.0160128083 0.0051818369 0.0975790000 372133096 0 402718720 0.8322764635 0.2742238343 1.6066948175 321 12.8000000000 0.0020511665 0.0068002220 0.0160128083 0.0051856302 0.0376760000 372149316 0 402718720 0.8306655884 0.2759239972 1.6161347628 322 12.8400000000 0.0024108791 0.0067865905 0.0160128083 0.0051930258 0.0349830000 372148480 0 402718720 0.8289406300 0.2777144313 1.6247888803 323 12.8800000000 0.0025695402 0.0067735346 0.0160128083 0.0052047675 0.0379690000 372894552 0 402718720 0.8279165626 0.2800180316 1.6331386566 324 12.9200000000 0.0032153288 0.0067625525 0.0160128083 0.0052156224 0.1193490000 372858552 0 402718720 0.8262982965 0.2807202041 1.6399942636 325 12.9600000000 0.0025893778 0.0067497120 0.0160128083 0.0052220978 0.1031280000 372860456 0 402718720 0.8266081810 0.2807152271 1.6469888687 326 13.0000000000 0.0020768309 0.0067353780 0.0160128083 0.0052263937 0.1019800000 373157180 0 402718720 0.8260015249 0.2809577584 1.6549427509 327 13.0400000000 0.0019451425 0.0067207290 0.0160128083 0.0053133963 0.1011380000 382407024 0 402718720 0.8227509856 0.2854248881 1.6742104292 328 13.0800000000 0.0019730511 0.0067062543 0.0160128083 0.0053279120 0.0438200000 387044853 0 402718720 0.8207712770 0.2856023014 1.6818739176 329 13.1200000000 0.0021733451 0.0066924765 0.0160128083 0.0053342168 0.0862680000 386610097 0 402718720 0.8185098171 0.2873706818 1.6900721788 330 13.1600000000 0.0021877512 0.0066788258 0.0160128083 0.0053327388 0.0377320000 386276028 0 402718720 0.8172810674 0.2877349257 1.6973320246 331 13.2000000000 0.0038478365 0.0066702730 0.0160128083 0.0053465801 0.1282720000 386205539 0 402718720 0.8154879808 0.2894729078 1.7052723169 332 13.2400000000 0.0040666945 0.0066624309 0.0160128083 0.0053417765 0.0940090000 372869704 0 402718720 0.8138349056 0.2907577455 1.7131097317 333 13.2800000000 0.0034675521 0.0066528366 0.0160128083 0.0053358684 0.0328610000 372887336 0 402718720 0.8132079244 0.2917283475 1.7203569412 334 13.3200000000 0.0035215716 0.0066434616 0.0160128083 0.0053358307 0.0311260000 372885964 0 402718720 0.8129484653 0.2922025025 1.7264946699 335 13.3600000000 0.0037834330 0.0066349242 0.0160128083 0.0053429998 0.0308720000 372888236 0 402718720 0.8104494214 0.2951397002 1.7353607416 336 13.4000000000 0.0032512911 0.0066248539 0.0160128083 0.0053443345 0.0370410000 373673500 0 402718720 0.8084625602 0.2955821455 1.7412798405 337 13.4400000000 0.0038725107 0.0066166867 0.0160128083 0.0053648265 0.1167180000 373647640 0 402718720 0.8063825369 0.2952440977 1.7465195656 338 13.4800000000 0.0031717164 0.0066064944 0.0160128083 0.0053786304 0.0994250000 373653088 0 402718720 0.8040915132 0.2952962816 1.7517879009 339 13.5200000000 0.0034854638 0.0065972879 0.0160128083 0.0054002953 0.0970480000 373700328 0 402718720 0.8012234569 0.2967136800 1.7595158815 340 13.5600000000 0.0035714067 0.0065883882 0.0160128083 0.0054177600 0.1024430000 384211444 0 402718720 0.7968908548 0.2971725166 1.7650132179 341 13.6000000000 0.0036486248 0.0065797672 0.0160128083 0.0054263661 0.0396040000 388697505 0 402718720 0.7932904959 0.2983678579 1.7721582651 342 13.6400000000 0.0028333752 0.0065688128 0.0160128083 0.0054278792 0.1019080000 388173607 0 402718720 0.7898899913 0.2997594774 1.7803180218 343 13.6800000000 0.0026485885 0.0065573836 0.0160128083 0.0054373821 0.0372780000 388452033 0 402718720 0.7857702971 0.3031018376 1.7887932062 344 13.7200000000 0.0030313907 0.0065471336 0.0160128083 0.0054406845 0.0342770000 387860092 0 402718720 0.7816818953 0.3054466248 1.7946784496 345 13.7600000000 0.0020944560 0.0065342273 0.0160128083 0.0054380236 0.1201240000 387790251 0 402718720 0.7807789445 0.3036924601 1.7988954782 346 13.8000000000 0.0022617856 0.0065218792 0.0160128083 0.0054371359 0.0847150000 373656712 0 402718720 0.7779811621 0.3040969670 1.8027887344 347 13.8400000000 0.0025007629 0.0065102910 0.0160128083 0.0054427966 0.0329540000 373670168 0 402718720 0.7741773129 0.3038315475 1.8087565899 348 13.8800000000 0.0019443892 0.0064971706 0.0160128083 0.0054494977 0.0298950000 373674528 0 402718720 0.7700508237 0.3037259281 1.8150360584 349 13.9200000000 0.0018529567 0.0064838634 0.0160128083 0.0054563120 0.0286200000 373672360 0 402718720 0.7639014125 0.3042680621 1.8228080273 350 13.9600000000 0.0020862585 0.0064712988 0.0160128083 0.0054668049 0.0330490000 374355668 0 402718720 0.7581001520 0.3058084548 1.8305153847 351 14.0000000000 0.0022055444 0.0064591457 0.0160128083 0.0054669456 0.1000270000 374403700 0 402718720 0.7530009151 0.3075961471 1.8369548321 352 14.0400000000 0.0020181283 0.0064465291 0.0160128083 0.0054646538 0.0861910000 374401724 0 402718720 0.7474576235 0.3069691956 1.8406013250 353 14.0800000000 0.0020279558 0.0064340119 0.0160128083 0.0054611130 0.0767020000 374700548 0 402718720 0.7431182861 0.3059310019 1.8458662033 354 14.1200000000 0.0018510825 0.0064210658 0.0160128083 0.0054605414 0.0798440000 385289048 0 402718720 0.7370615602 0.3079424798 1.8547854424 355 14.1600000000 0.0018490960 0.0064081870 0.0160128083 0.0054557404 0.0517240000 389150589 0 402718720 0.7315182686 0.3089862764 1.8603491783 356 14.2000000000 0.0019540091 0.0063956753 0.0160128083 0.0054519778 0.0336600000 388895892 0 402718720 0.7248417139 0.3089499176 1.8644188643 357 14.2400000000 0.0016947761 0.0063825075 0.0160128083 0.0054468381 0.0855180000 389123715 0 402718720 0.7172071934 0.3099924326 1.8710107803 358 14.2800000000 0.0021266879 0.0063706197 0.0160128083 0.0054406167 0.0299110000 389209993 0 402718720 0.7116848230 0.3106252253 1.8765043020 359 14.3200000000 0.0019328628 0.0063582583 0.0160128083 0.0054331958 0.0314310000 388807608 0 402718720 0.7029060125 0.3140560985 1.8841012716 360 14.3600000000 0.0018590551 0.0063457605 0.0160128083 0.0054289692 0.1038980000 388735931 0 402718720 0.6876347065 0.3163913488 1.8950823545 361 14.4000000000 0.0023780304 0.0063347696 0.0160128083 0.0054246724 0.0716080000 374681813 0 402718720 0.6769766808 0.3217538893 1.9033701420 362 14.4400000000 0.0020310285 0.0063228808 0.0160128083 0.0054202766 0.0384150000 374432304 0 402718720 0.6607565880 0.3208099902 1.9098758698 363 14.4800000000 0.0019750458 0.0063109033 0.0160128083 0.0054137048 0.0309750000 375185512 0 402718720 0.6550298929 0.3196537495 1.9139567614 364 14.5200000000 0.0021011850 0.0062993381 0.0160128083 0.0054072312 0.0995340000 375229220 0 402718720 0.6475245953 0.3206041455 1.9202840328 365 14.5600000000 0.0020912953 0.0062878092 0.0160128083 0.0053998567 0.0816050000 382170140 0 402718720 0.6391361952 0.3205745518 1.9252258539 366 14.6000000000 0.0021142755 0.0062764061 0.0160128083 0.0053927680 0.0520350000 382119784 0 402718720 0.6227561235 0.3268272877 1.9397866726 367 14.6400000000 0.0025738943 0.0062663175 0.0160128083 0.0053866703 0.0804180000 382044927 0 402718720 0.6138098240 0.3307477236 1.9445971251 368 14.6800000000 0.0025873398 0.0062563203 0.0160128083 0.0053801695 0.0294760000 375242852 0 402718720 0.6047849059 0.3313932717 1.9484603405 369 14.7200000000 0.0024432004 0.0062459867 0.0160128083 0.0053736568 0.0296180000 375247368 0 402718720 0.5960881710 0.3290241957 1.9498132467 370 14.7600000000 0.0026227927 0.0062361942 0.0160128083 0.0053665083 0.0407520000 375248588 0 402718720 0.5881778002 0.3275408447 1.9512284994 371 14.8000000000 0.0025158324 0.0062261663 0.0160128083 0.0053612832 0.0289990000 375251140 0 402718720 0.5785150528 0.3298542798 1.9577989578 372 14.8400000000 0.0026370254 0.0062165181 0.0160128083 0.0053557447 0.0284110000 375251892 0 402718720 0.5701104403 0.3314650655 1.9630613327 373 14.8800000000 0.0023665340 0.0062061964 0.0160128083 0.0053524689 0.0279700000 375254900 0 402718720 0.5602411032 0.3324859738 1.9679521322 374 14.9200000000 0.0026899339 0.0061967946 0.0160128083 0.0053526367 0.0276410000 375258000 0 402718720 0.5491292477 0.3339265287 1.9709231853 375 14.9600000000 0.0025392077 0.0061870411 0.0160128083 0.0053497866 0.0389360000 375260932 0 402718720 0.5387206078 0.3333371282 1.9725335836 376 15.0000000000 0.0026738276 0.0061776974 0.0160128083 0.0053428976 0.0265530000 375264648 0 402718720 0.5294293761 0.3328524828 1.9775383472 377 15.0400000000 0.0029098559 0.0061690294 0.0160128083 0.0053392959 0.0430490000 376054540 0 402718720 0.5082627535 0.3343380690 1.9843995571 378 15.0800000000 0.0029791561 0.0061605906 0.0160128083 0.0053328157 0.1004300000 378778932 0 402718720 0.4993073940 0.3348253667 1.9883350134 379 15.1200000000 0.0031132277 0.0061525500 0.0160128083 0.0053257877 0.0486570000 380491408 0 402718720 0.4917980433 0.3341459036 1.9910620451 380 15.1600000000 0.0028564828 0.0061438762 0.0160128083 0.0053219578 0.0480210000 380241797 0 402718720 0.4842397869 0.3331555724 1.9951734543 381 15.2000000000 0.0030113508 0.0061356543 0.0160128083 0.0053280622 0.0321900000 376098644 0 402718720 0.4764208496 0.3342943192 2.0011165142 382 15.2400000000 0.0030724003 0.0061276353 0.0160128083 0.0053372168 0.0313380000 376100608 0 402718720 0.4660701752 0.3338092864 2.0018587112 383 15.2800000000 0.0030058834 0.0061194846 0.0160128083 0.0053439228 0.0401850000 376104612 0 402718720 0.4576593041 0.3335683048 2.0046906471 384 15.3200000000 0.0030590629 0.0061115147 0.0160128083 0.0053538523 0.0307120000 376106796 0 402718720 0.4490261674 0.3345855474 2.0097715855 385 15.3600000000 0.0031180258 0.0061037394 0.0160128083 0.0053518090 0.0311330000 376109312 0 402718720 0.4412852526 0.3346728683 2.0126712322 386 15.4000000000 0.0029857266 0.0060956617 0.0160128083 0.0053501207 0.0413060000 376110708 0 402718720 0.4336003065 0.3349543214 2.0156860352 387 15.4400000000 0.0029206749 0.0060874576 0.0160128083 0.0053508091 0.0303630000 376114252 0 402718720 0.4275122285 0.3356532454 2.0199286938 388 15.4800000000 0.0032195647 0.0060800661 0.0160128083 0.0053607232 0.0297970000 376116276 0 402718720 0.4204685688 0.3363074362 2.0226979256 389 15.5200000000 0.0029073106 0.0060719099 0.0160128083 0.0053588557 0.0292550000 376118916 0 402718720 0.4130581021 0.3374854922 2.0274791718 390 15.5600000000 0.0026104553 0.0060630344 0.0160128083 0.0053708524 0.0399810000 376121064 0 402718720 0.4047525525 0.3379470706 2.0308320522 391 15.6000000000 0.0026351789 0.0060542675 0.0160128083 0.0053664825 0.0286710000 376123520 0 402718720 0.3977628946 0.3378446698 2.0338397026 392 15.6400000000 0.0029652738 0.0060463874 0.0160128083 0.0053699432 0.0290140000 376125408 0 402718720 0.3916708827 0.3385943770 2.0388245583 393 15.6800000000 0.0031283023 0.0060389622 0.0160128083 0.0053667660 0.0290530000 376128540 0 402718720 0.3851517439 0.3384065926 2.0418455601 394 15.7200000000 0.0031287032 0.0060315758 0.0160128083 0.0053636563 0.0282980000 376131808 0 402718720 0.3787990212 0.3386314511 2.0454335213 395 15.7600000000 0.0031474007 0.0060242741 0.0160128083 0.0053643778 0.0277340000 376135672 0 402718720 0.3721311688 0.3391825855 2.0513451099 396 15.8000000000 0.0031646211 0.0060170527 0.0160128083 0.0053659855 0.0273090000 376137332 0 402718720 0.3647567630 0.3414494693 2.0565338135 397 15.8400000000 0.0033943888 0.0060104465 0.0160128083 0.0053604410 0.0365050000 376141812 0 402718720 0.3587862849 0.3401984274 2.0586769581 398 15.8800000000 0.0032253757 0.0060034489 0.0160128083 0.0053590826 0.0266600000 376142932 0 402718720 0.3535262346 0.3409210443 2.0661466122 399 15.9200000000 0.0031615002 0.0059963262 0.0160128083 0.0053580872 0.0271990000 376145388 0 402718720 0.3456810117 0.3426390886 2.0701665878 400 15.9600000000 0.0034385340 0.0059899317 0.0160128083 0.0053538199 0.0266030000 376148644 0 402718720 0.3407936692 0.3413046002 2.0734827518 401 16.0000000000 0.0031064551 0.0059827410 0.0160128083 0.0053613054 0.0263080000 376151208 0 402718720 0.3339251280 0.3413937986 2.0778105259 402 16.0400000000 0.0037446094 0.0059771735 0.0160128083 0.0053563175 0.0266490000 376153832 0 402718720 0.3291072845 0.3410102129 2.0840673447 403 16.0800000000 0.0035719783 0.0059712053 0.0160128083 0.0053556480 0.0265100000 376157552 0 402718720 0.3220456243 0.3410792053 2.0894827843 404 16.1200000000 0.0031986921 0.0059643426 0.0160128083 0.0053565493 0.0380640000 376159192 0 402718720 0.3144422770 0.3415436745 2.0942010880 405 16.1600000000 0.0039449921 0.0059593566 0.0160128083 0.0053509765 0.0264460000 376161248 0 402718720 0.3107360601 0.3401177227 2.0985176563 406 16.2000000000 0.0028676167 0.0059517414 0.0160128083 0.0053739976 0.0266090000 376166096 0 402718720 0.3030287623 0.3418334723 2.1074013710 407 16.2400000000 0.0030046871 0.0059445005 0.0160128083 0.0053779010 0.0342670000 377129679 0 402718720 0.2951503396 0.3436951041 2.1123836040 408 16.2800000000 0.0028045299 0.0059368045 0.0160128083 0.0053820084 0.1246110000 380504590 0 402718720 0.2895792723 0.3443265855 2.1171593666 409 16.3200000000 0.0030216768 0.0059296771 0.0160128083 0.0053866862 0.0481960000 381440152 0 402718720 0.2826111317 0.3453068733 2.1237628460 410 16.3600000000 0.0045292485 0.0059262614 0.0160128083 0.0053963336 0.0485400000 381228113 0 402718720 0.2753773928 0.3467353582 2.1263232231 411 16.3999999990 0.0046921833 0.0059232588 0.0160128083 0.0053933420 0.0339980000 377177592 0 402718720 0.2694383860 0.3472566307 2.1295123100 412 16.4400000000 0.0047936663 0.0059205170 0.0160128083 0.0053919254 0.0343460000 377180264 0 402718720 0.2635695338 0.3471859992 2.1346733570 413 16.4800000000 0.0044296053 0.0059169071 0.0160128083 0.0053970506 0.0336740000 377182380 0 402718720 0.2575807571 0.3486472368 2.1422200203 414 16.5200000000 0.0045997426 0.0059137255 0.0160128083 0.0054071250 0.0336240000 377185004 0 402718720 0.2508796453 0.3504321575 2.1474370956 415 16.5599999990 0.0046606846 0.0059107061 0.0160128083 0.0054242090 0.0323630000 377187652 0 402718720 0.2444761395 0.3529507518 2.1541788578 416 16.6000000000 0.0041080643 0.0059063729 0.0160128083 0.0054204553 0.0313960000 377190284 0 402718720 0.2388992906 0.3537460566 2.1585092545 417 16.6400000000 0.0044217613 0.0059028127 0.0160128083 0.0054253226 0.0319460000 377192172 0 402718720 0.2338163257 0.3544747233 2.1620471478 418 16.6800000000 0.0046306392 0.0058997692 0.0160128083 0.0054399845 0.0410030000 377194828 0 402718720 0.2226384878 0.3564087451 2.1709930897 419 16.7199999990 0.0044743912 0.0058963673 0.0160128083 0.0054433007 0.0306660000 377197208 0 402718720 0.2165403962 0.3578399122 2.1774613857 420 16.7600000000 0.0044505973 0.0058929250 0.0160128083 0.0054451630 0.0292470000 377199324 0 402718720 0.2108486295 0.3596024811 2.1833226681 421 16.8000000000 0.0044232183 0.0058894340 0.0160128083 0.0054494484 0.0416450000 377201704 0 402718720 0.2055948973 0.3604737520 2.1885938644 422 16.8400000000 0.0041962434 0.0058854217 0.0160128083 0.0054571220 0.0290360000 377203700 0 402718720 0.2006639242 0.3607476354 2.1936891079 423 16.8799999990 0.0040490092 0.0058810803 0.0160128083 0.0054662686 0.0294690000 377207432 0 402718720 0.1960209012 0.3603606224 2.1989157200 424 16.9200000000 0.0044343891 0.0058776683 0.0160128083 0.0055653802 0.0281940000 377209304 0 402718720 0.1845358014 0.3627416492 2.2083892822 425 16.9600000000 0.0043264623 0.0058740184 0.0160128083 0.0055703426 0.0376700000 377211792 0 402718720 0.1801183224 0.3634276390 2.2119395733 426 17.0000000000 0.0043232995 0.0058703782 0.0160128083 0.0055873290 0.0277730000 377213740 0 402718720 0.1745958328 0.3648510575 2.2168915272 427 17.0400000000 0.0042550769 0.0058665953 0.0160128083 0.0056020813 0.0273130000 377216332 0 402718720 0.1688854098 0.3667177260 2.2214994431 428 17.0800000000 0.0039014535 0.0058620039 0.0160128083 0.0056088018 0.0274920000 377218804 0 402718720 0.1645004749 0.3686630726 2.2257957458 429 17.1200000000 0.0041400432 0.0058579900 0.0160128083 0.0056132629 0.0492300000 377220784 0 402718720 0.1595170498 0.3690373302 2.2277855873 430 17.1600000000 0.0040472145 0.0058537789 0.0160128083 0.0056131333 0.0278650000 377223284 0 402718720 0.1544375420 0.3691751659 2.2312178612 431 17.2000000000 0.0042557642 0.0058500712 0.0160128083 0.0056171549 0.0268320000 377225556 0 402718720 0.1499530077 0.3688414693 2.2347218990 432 17.2400000000 0.0042230464 0.0058463049 0.0160128083 0.0056182374 0.0264860000 377228244 0 402718720 0.1447106600 0.3693915308 2.2392625809 433 17.2800000000 0.0040307147 0.0058421119 0.0160128083 0.0056170438 0.0264940000 377230500 0 402718720 0.1412240267 0.3706441820 2.2431764603 434 17.3200000000 0.0045542335 0.0058391444 0.0160128083 0.0056180287 0.0344150000 378314631 0 402718720 0.1355009079 0.3720914721 2.2450978756 435 17.3600000000 0.0045500100 0.0058361809 0.0160128083 0.0056154956 0.1220970000 381782984 0 402718720 0.1302635670 0.3706230521 2.2465519905 436 17.4000000000 0.0051016496 0.0058344962 0.0160128083 0.0056543404 0.0682180000 381668923 0 402718720 0.1251510382 0.3715713620 2.2496581078 437 17.4400000000 0.0049181636 0.0058323993 0.0160128083 0.0056511637 0.0338880000 378257068 0 402718720 0.1189341545 0.3727120459 2.2528331280 438 17.4800000000 0.0050935862 0.0058307125 0.0160128083 0.0056507813 0.0341130000 378259556 0 402718720 0.1138083935 0.3714092374 2.2550249100 439 17.5200000000 0.0048428304 0.0058284622 0.0160128083 0.0056466612 0.0428810000 378262012 0 402718720 0.1089673042 0.3710744679 2.2574896812 440 17.5600000000 0.0049330471 0.0058264272 0.0160128083 0.0056452613 0.0344470000 378264360 0 402718720 0.1039216518 0.3708293438 2.2594697475 441 17.6000000000 0.0048221173 0.0058241498 0.0160128083 0.0056422203 0.0345120000 378266296 0 402718720 0.0981225967 0.3703584075 2.2609164715 442 17.6400000000 0.0049668164 0.0058222102 0.0160128083 0.0056442118 0.0330030000 378268736 0 402718720 0.0930826664 0.3692156374 2.2621333599 443 17.6800000000 0.0048165284 0.0058199400 0.0160128083 0.0056407142 0.0321680000 378271020 0 402718720 0.0876523256 0.3700240254 2.2639827728 444 17.7200000000 0.0048640012 0.0058177870 0.0160128083 0.0056397244 0.0311920000 378271880 0 402718720 0.0821965933 0.3696760535 2.2664680481 445 17.7600000000 0.0052115261 0.0058164246 0.0160128083 0.0056399847 0.0313150000 378275820 0 402718720 0.0773054361 0.3696794510 2.2678520679 446 17.8000000000 0.0048175994 0.0058141851 0.0160128083 0.0056374727 0.0314370000 378278276 0 402718720 0.0718981028 0.3683582246 2.2696182728 447 17.8400000000 0.0045751976 0.0058114133 0.0160128083 0.0056341094 0.0304460000 378277420 0 402718720 0.0662924051 0.3677857816 2.2732422352 448 17.8800000000 0.0048222560 0.0058092054 0.0160128083 0.0056311827 0.0295190000 378281928 0 402718720 0.0597847700 0.3675795794 2.2747189999 449 17.9200000000 0.0050171879 0.0058074414 0.0160128083 0.0056320806 0.0285620000 378284752 0 402718720 0.0543158054 0.3669437766 2.2757978439 450 17.9600000000 0.0044931942 0.0058045209 0.0160128083 0.0056294211 0.0283470000 378287192 0 402718720 0.0492581129 0.3650259376 2.2775490284 451 18.0000000000 0.0046037440 0.0058018584 0.0160128083 0.0056319246 0.0271400000 378289860 0 402718720 0.0360549688 0.3639120162 2.2815504074 452 18.0400000000 0.0048823431 0.0057998241 0.0160128083 0.0056310475 0.0354950000 378291412 0 402718720 0.0303224325 0.3638235927 2.2837607861 453 18.0800000000 0.0050537083 0.0057981770 0.0160128083 0.0056282780 0.0257440000 378293256 0 402718720 0.0241664648 0.3622813821 2.2859106064 454 18.1200000000 0.0046854154 0.0057957260 0.0160128083 0.0056282132 0.0330210000 379252891 0 402718720 0.0163073540 0.3621536493 2.2896809578 455 18.1600000000 0.0046844217 0.0057932836 0.0160128083 0.0056238774 0.1322590000 382416808 0 402718720 0.0095587969 0.3622052670 2.2931010723 456 18.2000000000 0.0042075277 0.0057898060 0.0160128083 0.0056221568 0.0686820000 382296667 0 402718720 0.0041722059 0.3603493869 2.2949895859 457 18.2400000000 0.0041252803 0.0057861637 0.0160128083 0.0056190452 0.0348290000 379284816 0 402718720 -0.0026373863 0.3599610925 2.2976579666 458 18.2800000000 0.0041861688 0.0057826703 0.0160128083 0.0056196045 0.0354460000 379287104 0 402718720 -0.0098054409 0.3603140116 2.2994735241 459 18.3200000000 0.0043702363 0.0057795931 0.0160128083 0.0056186747 0.0343910000 379287320 0 402718720 -0.0161483288 0.3594548106 2.3008003235 460 18.3600000000 0.0041720546 0.0057760984 0.0160128083 0.0056151074 0.0335150000 379287660 0 402718720 -0.0218769312 0.3581866920 2.3025841713 461 18.4000000000 0.0043532117 0.0057730119 0.0160128083 0.0056130693 0.0327700000 379292064 0 402718720 -0.0289553404 0.3571921587 2.3053159714 462 18.4400000000 0.0042823120 0.0057697853 0.0160128083 0.0056080765 0.0317370000 379292480 0 402718720 -0.0359994173 0.3564095497 2.3083984852 463 18.4800000000 0.0042748847 0.0057665566 0.0160128083 0.0056027210 0.0319790000 379298896 0 402718720 -0.0413560867 0.3565344810 2.3090207577 464 18.5200000000 0.0043488843 0.0057635012 0.0160128083 0.0055996223 0.0301420000 379298876 0 402718720 -0.0483388305 0.3552445173 2.3096508980 465 18.5600000000 0.0044840523 0.0057607497 0.0160128083 0.0055975545 0.0289710000 379303804 0 402718720 -0.0549830794 0.3540665507 2.3123934269 466 18.6000000000 0.0044142171 0.0057578602 0.0160128083 0.0055926519 0.0286480000 379304024 0 402718720 -0.0609588623 0.3527150154 2.3152511120 467 18.6400000000 0.0042462414 0.0057546233 0.0160128083 0.0055890855 0.0273990000 379308724 0 402718720 -0.0672094822 0.3531513512 2.3165988922 468 18.6800000000 0.0044628051 0.0057518630 0.0160128083 0.0055876767 0.0267350000 379310368 0 402718720 -0.0721023679 0.3523365259 2.3161752224 469 18.7200000000 0.0041920841 0.0057485373 0.0160128083 0.0055826161 0.0260950000 379313000 0 402718720 -0.0787525773 0.3523058891 2.3186922073 470 18.7600000000 0.0043457919 0.0057455527 0.0160128083 0.0055778510 0.0252900000 379316132 0 402718720 -0.0846131444 0.3515143991 2.3194060326 471 18.8000000000 0.0043945843 0.0057426844 0.0160128083 0.0055834737 0.0425820000 380261767 0 402718720 -0.0982244015 0.3470997512 2.3203005791 472 18.8400000000 0.0043752254 0.0057397872 0.0160128083 0.0055791000 0.1194510000 382532136 0 402718720 -0.1030281186 0.3459531963 2.3217909336 473 18.8800000000 0.0044660852 0.0057370944 0.0160128083 0.0055757196 0.0467740000 383186072 0 402718720 -0.1047822833 0.3438648582 2.3204622269 474 18.9200000000 0.0044592316 0.0057343985 0.0160128083 0.0055735161 0.0432440000 382129717 0 402718720 -0.1067639589 0.3421681821 2.3209705353 475 18.9600000000 0.0046368269 0.0057320878 0.0160128083 0.0055717785 0.0330180000 380276372 0 402718720 -0.1102638245 0.3414365053 2.3223628998 476 19.0000000000 0.0046863533 0.0057298909 0.0160128083 0.0055861076 0.0314770000 380277448 0 402718720 -0.1152369976 0.3387373984 2.3225808144 477 19.0400000000 0.0046891379 0.0057277090 0.0160128083 0.0055954394 0.0300960000 380275060 0 402718720 -0.1174084544 0.3364681005 2.3220698833 478 19.0800000000 0.0045746048 0.0057252967 0.0160128083 0.0056068622 0.0283320000 380277500 0 402718720 -0.1237010360 0.3340965807 2.3280568123 479 19.1200000000 0.0047158576 0.0057231893 0.0160128083 0.0056066347 0.0386460000 380281560 0 402718720 -0.1241915822 0.3342183232 2.3283684254 480 19.1600000000 0.0046017282 0.0057208529 0.0160128083 0.0056095719 0.0358700000 380278964 0 402718720 -0.1241572499 0.3334292471 2.3276448250 481 19.2000000000 0.0045501445 0.0057184190 0.0160128083 0.0056209724 0.0256900000 380277304 0 402718720 -0.1256977916 0.3327301741 2.3290627003 482 19.2400000000 0.0042757867 0.0057154260 0.0160128083 0.0056297354 0.0254790000 380282696 0 402718720 -0.1264562011 0.3328258693 2.3296871185 483 19.2800000000 0.0043010227 0.0057124976 0.0160128083 0.0056386482 0.0254500000 380282812 0 402718720 -0.1271867156 0.3315371275 2.3310835361 484 19.3200000000 0.0043587713 0.0057097007 0.0160128083 0.0056511524 0.0366750000 380280924 0 402718720 -0.1268386245 0.3312382102 2.3320829868 485 19.3600000000 0.0042368649 0.0057066639 0.0160128083 0.0056732241 0.0238180000 380282068 0 402718720 -0.1266305447 0.3311017156 2.3322830200 486 19.4000000000 0.0046708630 0.0057045326 0.0160128083 0.0056878179 0.0233120000 380282828 0 402718720 -0.1274545193 0.3312831521 2.3349127769 487 19.4400000000 0.0044968240 0.0057020527 0.0160128083 0.0056965325 0.0329560000 380285276 0 402718720 -0.1268855929 0.3312209845 2.3372018337 488 19.4800000000 0.0043676058 0.0056993182 0.0160128083 0.0057101572 0.0224360000 380282688 0 402718720 -0.1269007325 0.3302308321 2.3402264118 489 19.5200000000 0.0042671976 0.0056963895 0.0160128083 0.0057212348 0.0221160000 380285780 0 402718720 -0.1293731928 0.3306856155 2.3458213806 490 19.5600000000 0.0041788383 0.0056932925 0.0160128083 0.0057250248 0.0226140000 380290184 0 402718720 -0.1282179356 0.3313111961 2.3471236229 491 19.6000000000 0.0048154294 0.0056915046 0.0160128083 0.0057337638 0.0215900000 380288208 0 402718720 -0.1275054812 0.3317269087 2.3497841358 492 19.6400000000 0.0048412764 0.0056897765 0.0160128083 0.0057399776 0.0330970000 380293976 0 402718720 -0.1267157197 0.3321160972 2.3529934883 493 19.6800000000 0.0044190423 0.0056871989 0.0160128083 0.0057510267 0.0218090000 380295120 0 402718720 -0.1247580647 0.3335940242 2.3537483215 494 19.7200000000 0.0046958197 0.0056851921 0.0160128083 0.0057750196 0.0218780000 380298976 0 402718720 -0.1255918145 0.3333805799 2.3583998680 495 19.7600000000 0.0047953906 0.0056833945 0.0160128083 0.0057887486 0.0334080000 380299008 0 402718720 -0.1261432171 0.3331967592 2.3641591072 496 19.8000000000 0.0048099915 0.0056816336 0.0160128083 0.0058033018 0.0328100000 380302864 0 402718720 -0.1262656450 0.3340924382 2.3688054085 497 19.8400000000 0.0047503463 0.0056797598 0.0160128083 0.0058090549 0.0221940000 380307240 0 402718720 -0.1253619194 0.3353602886 2.3702394962 498 19.8800000000 0.0050452035 0.0056784856 0.0160128083 0.0058149863 0.0221020000 380309788 0 402718720 -0.1243292093 0.3360240459 2.3727159500 499 19.9200000000 0.0048970012 0.0056769195 0.0160128083 0.0058172177 0.0219750000 380312752 0 402718720 -0.1243842244 0.3354889750 2.3772845268 500 19.9600000000 0.0050300527 0.0056756258 0.0160128083 0.0058214556 0.0216360000 380312404 0 402718720 -0.1236807108 0.3366907537 2.3801743984 501 20.0000000000 0.0049546044 0.0056741866 0.0160128083 0.0058264669 0.0213730000 380314064 0 402718720 -0.1231000721 0.3371153474 2.3827555180 502 20.0400000000 0.0047962689 0.0056724378 0.0160128083 0.0058389289 0.0307470000 380314724 0 402718720 -0.1229237616 0.3375519514 2.3863685131 503 20.0800000000 0.0048336810 0.0056707702 0.0160128083 0.0058449888 0.0252340000 380866319 0 402718720 -0.1239210367 0.3384352326 2.3897497654 504 20.1200000000 0.0047631725 0.0056689695 0.0160128083 0.0058516273 0.0720300000 381726948 0 402718720 -0.1240142882 0.3384897411 2.3930425644 505 20.1600000000 0.0048904610 0.0056674279 0.0160128083 0.0058628045 0.0333980000 382976080 0 402718720 -0.1244914532 0.3393661976 2.3953857422 506 20.2000000000 0.0042458437 0.0056646184 0.0160128083 0.0058668353 0.0347520000 382651045 0 402718720 -0.1252381504 0.3393397331 2.3977961540 507 20.2400000000 0.0041938927 0.0056617176 0.0160128083 0.0058728448 0.0251010000 380847208 0 402718720 -0.1257527769 0.3388048410 2.4005782604 508 20.2800000000 0.0040803901 0.0056586047 0.0160128083 0.0058832799 0.0245770000 380845664 0 402718720 -0.1277216077 0.3382494152 2.4042596817 509 20.3200000000 0.0039876201 0.0056553218 0.0160128083 0.0058932353 0.0362360000 380848784 0 402718720 -0.1275080740 0.3375941813 2.4072721004 510 20.3600000000 0.0038543502 0.0056517905 0.0160128083 0.0059027509 0.0232000000 380846992 0 402718720 -0.1273083240 0.3383238912 2.4072084427 511 20.4000000000 0.0041483920 0.0056488484 0.0160128083 0.0059083079 0.0229800000 380850476 0 402718720 -0.1281731129 0.3378683329 2.4089524746 512 20.4400000000 0.0042146374 0.0056460473 0.0160128083 0.0059167832 0.0223100000 380853976 0 402718720 -0.1303569674 0.3383314312 2.4110684395 513 20.4800000000 0.0040614447 0.0056429584 0.0160128083 0.0059176525 0.0220810000 380853324 0 402718720 -0.1302887797 0.3383927345 2.4109020233 514 20.5200000000 0.0039943722 0.0056397510 0.0160128083 0.0059231404 0.0214880000 380958220 0 402718720 -0.1321813613 0.3385384977 2.4129383564 515 20.5600000000 0.0040047155 0.0056365762 0.0160128083 0.0059254680 0.0211840000 380960160 0 402718720 -0.1332249045 0.3383845091 2.4134349823 516 20.6000000000 0.0046156282 0.0056345976 0.0160128083 0.0059307909 0.0209550000 380962008 0 402718720 -0.1344947517 0.3385953903 2.4127316475 517 20.6400000000 0.0039255489 0.0056312919 0.0160128083 0.0059300058 0.0205630000 380963796 0 402718720 -0.1357661188 0.3375274539 2.4120497704 518 20.6800000000 0.0041748788 0.0056284803 0.0160128083 0.0059361568 0.0194910000 380962740 0 402718720 -0.1379477978 0.3371679187 2.4117028713 519 20.7200000000 0.0045266184 0.0056263572 0.0160128083 0.0059407871 0.0192010000 380966368 0 402718720 -0.1411021352 0.3371747136 2.4123237133 520 20.7600000000 0.0042887595 0.0056237849 0.0160128083 0.0059476292 0.0191290000 380965928 0 402718720 -0.1423330307 0.3356073499 2.4133174419 521 20.8000000000 0.0052485634 0.0056230647 0.0160128083 0.0059444045 0.0192370000 380971040 0 402718720 -0.1446720511 0.3336889744 2.4105010033 522 20.8400000000 0.0044835838 0.0056208818 0.0160128083 0.0059566791 0.0188240000 380971876 0 402718720 -0.1477897465 0.3327344060 2.4115216732 523 20.8800000000 0.0050909212 0.0056198685 0.0160128083 0.0059741018 0.0298980000 380976956 0 402718720 -0.1487534046 0.3357182443 2.4072053432 524 20.9200000000 0.0055320603 0.0056197009 0.0160128083 0.0059820744 0.0190200000 380977388 0 402718720 -0.1504601836 0.3336549997 2.4052805901 525 20.9600000000 0.0048323194 0.0056182012 0.0160128083 0.0059766013 0.0191160000 380980796 0 402718720 -0.1533928066 0.3292884529 2.4052438736 526 21.0000000000 0.0047415905 0.0056165346 0.0160128083 0.0059974544 0.0189910000 380982856 0 402718720 -0.1559575945 0.3319695592 2.4041481018 527 21.0400000000 0.0051346677 0.0056156202 0.0160128083 0.0060018840 0.0190950000 380986832 0 402718720 -0.1591744423 0.3324825168 2.4002516270 528 21.0800000000 0.0056393705 0.0056156652 0.0160128083 0.0060020695 0.0264040000 380988372 0 402718720 -0.1628414541 0.3305187821 2.3998823166 529 21.1200000000 0.0070814155 0.0056184360 0.0160128083 0.0060064922 0.0191170000 380989480 0 402718720 -0.1676561683 0.3304326534 2.3968279362 530 21.1600000000 0.0040588328 0.0056154934 0.0160128083 0.0060086407 0.0191700000 380992780 0 402718720 -0.1703391224 0.3271705806 2.3930413723 531 21.2000000000 0.0046486049 0.0056136725 0.0160128083 0.0060111639 0.0193510000 380995808 0 402718720 -0.1739672869 0.3269080520 2.3899559975 532 21.2400000000 0.0056248959 0.0056136936 0.0160128083 0.0060099883 0.0186330000 380995188 0 402718720 -0.1773204952 0.3266395628 2.3873057365 533 21.2800000000 0.0031601978 0.0056090904 0.0160128083 0.0060099851 0.0189990000 381000888 0 402718720 -0.1805250645 0.3237960041 2.3870456219 534 21.3200000000 0.0059824158 0.0056097895 0.0160128083 0.0060429170 0.0188600000 381002520 0 402718720 -0.1850532293 0.3253412545 2.3844807148 535 21.3600000000 0.0059483936 0.0056104224 0.0160128083 0.0060550980 0.0292590000 381003000 0 402718720 -0.1912839860 0.3250949085 2.3862385750 536 21.4000000000 0.0027051673 0.0056050022 0.0160128083 0.0060612012 0.0186500000 381007388 0 402718720 -0.1968008876 0.3184255362 2.3830718994 537 21.4400000000 0.0056787338 0.0056051395 0.0160128083 0.0060869700 0.0182890000 381008380 0 402718720 -0.1992415786 0.3240576684 2.3771913052 538 21.4800000000 0.0083899414 0.0056103157 0.0160128083 0.0060998393 0.0309870000 381393395 0 402718720 -0.2067164183 0.3275457621 2.3739957809 539 21.5200000000 0.0071909907 0.0056132483 0.0160128083 0.0060950116 0.0474590000 382021320 0 402718720 -0.2105581760 0.3248689175 2.3713827133 540 21.5600000000 0.0051540979 0.0056123980 0.0160128083 0.0060927501 0.0258690000 382897032 0 402718720 -0.2152083218 0.3229042590 2.3703832626 541 21.6000000000 0.0064446810 0.0056139364 0.0160128083 0.0061198160 0.0238570000 382187205 0 402718720 -0.2218417525 0.3231697679 2.3702869415 542 21.6400000000 0.0073663932 0.0056171697 0.0160128083 0.0061469898 0.0186830000 381334436 0 402718720 -0.2259786278 0.3213339448 2.3691430092 543 21.6800000000 0.0083567249 0.0056222150 0.0160128083 0.0061636687 0.0190400000 381337448 0 402718720 -0.2305655628 0.3199924231 2.3652622700 544 21.7200000000 0.0101817045 0.0056305964 0.0160128083 0.0062611257 0.0271760000 381335532 0 402718720 -0.2384456396 0.3183339238 2.3548073769 545 21.7600000000 0.0097692274 0.0056381902 0.0160128083 0.0062632654 0.0179590000 381338644 0 402718720 -0.2433187515 0.3203052878 2.3494362831 546 21.8000000000 0.0083641158 0.0056431827 0.0160128083 0.0062632354 0.0173820000 381340364 0 402718720 -0.2473157495 0.3181810975 2.3449602127 547 21.8400000000 0.0060603484 0.0056439454 0.0160128083 0.0062778469 0.0180030000 381345912 0 402718720 -0.2512726486 0.3134846687 2.3407993317 548 21.8800000000 0.0085838372 0.0056493101 0.0160128083 0.0062814975 0.0196490000 381635531 0 402718720 -0.2568163276 0.3206701279 2.3335943222 549 21.9200000000 0.0063508046 0.0056505879 0.0160128083 0.0062775027 0.0431790000 382506136 0 402718720 -0.2626655400 0.3209658563 2.3299016953 550 21.9600000000 0.0064468430 0.0056520356 0.0160128083 0.0062867494 0.0275400000 382788339 0 402718720 -0.2663037777 0.3132235408 2.3258213997 551 22.0000000000 0.0071214144 0.0056547024 0.0160128083 0.0062979227 0.0164150000 381607568 0 402718720 -0.2699403465 0.3128835559 2.3196415901 552 22.0400000000 0.0042786915 0.0056522096 0.0160128083 0.0062956960 0.0163880000 381611816 0 402718720 -0.2745983005 0.3165120780 2.3125143051 553 22.0800000000 0.0053941938 0.0056517430 0.0160128083 0.0062938207 0.0186150000 381858259 0 402718720 -0.2785367966 0.3188334405 2.3067440987 554 22.1200000000 0.0076262252 0.0056553071 0.0160128083 0.0063029233 0.0329950000 382888920 0 402718720 -0.2834966779 0.3187825978 2.3025572300 555 22.1600000000 0.0044478201 0.0056531314 0.0160128083 0.0063020038 0.0231140000 382866625 0 402718720 -0.2871057391 0.3156086206 2.2949082851 556 22.2000000000 0.0030218817 0.0056483990 0.0160128083 0.0063082183 0.0179140000 382044747 0 402718720 -0.2908701301 0.3121941388 2.2920324802 557 22.2400000000 0.0034146647 0.0056443887 0.0160128083 0.0063083925 0.0355460000 382801992 0 402718720 -0.2947467268 0.3153766692 2.2845370770 558 22.2800000000 0.0030022580 0.0056396537 0.0160128083 0.0063072505 0.0199740000 383473560 0 402718720 -0.2981984615 0.3136408925 2.2795629501 559 22.3200000000 0.0021594011 0.0056334278 0.0160128083 0.0063073304 0.0187080000 382457397 0 402718720 -0.3004809022 0.3082491755 2.2726926804 560 22.3600000000 0.0022824483 0.0056274439 0.0160128083 0.0063079220 0.0332720000 382276092 0 402718720 -0.3037177324 0.3071271777 2.2650766373 561 22.4000000000 0.0017530211 0.0056205377 0.0160128083 0.0063089570 0.0303600000 383966899 0 402718720 -0.3067294955 0.3081080914 2.2571783066 562 22.4400000000 0.0016991693 0.0056135601 0.0160128083 0.0063322133 0.0377570000 382473716 0 402718720 -0.3096995950 0.3055751026 2.2551593781 563 22.4800000000 0.0012877805 0.0056058767 0.0160128083 0.0063365755 0.0312360000 384166160 0 402718720 -0.3128409684 0.3021263182 2.2497332096 564 22.5200000000 0.0041361200 0.0056032707 0.0160128083 0.0063391897 0.0320900000 384107375 0 402718720 -0.3160104454 0.3009609282 2.2452671528 565 22.5600000000 0.0015976351 0.0055961811 0.0160128083 0.0063891956 0.0154320000 382639015 0 402718720 -0.3233633041 0.3058652878 2.2282452583 566 22.6000000000 0.0008200067 0.0055877426 0.0160128083 0.0063851342 0.0329790000 382669292 0 402718720 -0.3258110881 0.3018497825 2.2217030525 567 22.6400000000 0.0025331192 0.0055823553 0.0160128083 0.0063846301 0.0247290000 384687727 0 402718720 -0.3304105401 0.3009116650 2.2161808014 568 22.6800000000 0.0010093513 0.0055743042 0.0160128083 0.0063874972 0.0308290000 383812253 0 402718720 -0.3321327269 0.3023471832 2.2070250511 569 22.7200000000 0.0013713484 0.0055669177 0.0160128083 0.0063907325 0.0333270000 383374711 0 402718720 -0.3362597227 0.3040806949 2.1998126507 570 22.7600000000 0.0009701403 0.0055588531 0.0160128083 0.0063880738 0.0302420000 383475345 0 402718720 -0.3388470113 0.2985926867 2.1941633224 571 22.8000000000 0.0012319968 0.0055512755 0.0160128083 0.0063964221 0.0325390000 383271527 0 402718720 -0.3416126966 0.2955830693 2.1883704662 572 22.8400000000 0.0015061647 0.0055442036 0.0160128083 0.0064061546 0.0326940000 383242324 0 402718720 -0.3448582292 0.2996863723 2.1793136597 573 22.8800000000 0.0015205421 0.0055371815 0.0160128083 0.0064074023 0.0335820000 384184223 0 402718720 -0.3486196399 0.2990303040 2.1738708019 574 22.9200000000 0.0018660862 0.0055307859 0.0160128083 0.0064102335 0.0295390000 383938265 0 402718720 -0.3537973464 0.2983555496 2.1673433781 575 22.9600000000 0.0015923267 0.0055239364 0.0160128083 0.0064129529 0.0306600000 383611027 0 402718720 -0.3563491702 0.2985047400 2.1592133045 576 23.0000000000 0.0042945072 0.0055218019 0.0160128083 0.0064409873 0.0274410000 385333297 0 402718720 -0.3602670729 0.2969495058 2.1536874771 577 23.0400000000 0.0050394894 0.0055209660 0.0160128083 0.0064451211 0.0149050000 383727627 0 402718720 -0.3648768961 0.2947870493 2.1464865208 578 23.0800000000 0.0038908999 0.0055181459 0.0160128083 0.0064416673 0.0330050000 383755984 0 402718720 -0.3665352166 0.2945241928 2.1384625435 579 23.1200000000 0.0042636343 0.0055159792 0.0160128083 0.0064409825 0.0297530000 385451995 0 402718720 -0.3682507277 0.2936753929 2.1301658154 580 23.1600000000 0.0055005252 0.0055159525 0.0160128083 0.0064419368 0.0241570000 384689849 0 402718720 -0.3700615168 0.2941340506 2.1240229607 581 23.2000000000 0.0039130650 0.0055131937 0.0160128083 0.0064623016 0.0318500000 384078567 0 402718720 -0.3742355406 0.2931959629 2.1163558960 582 23.2400000000 0.0048018568 0.0055119715 0.0160128083 0.0064683344 0.0305600000 384240647 0 402718720 -0.3819658160 0.2885757685 2.1109182835 583 23.2800000000 0.0059117195 0.0055126571 0.0160128083 0.0064698082 0.0293530000 384388659 0 402718720 -0.3848169446 0.2887040079 2.1052172184 584 23.3200000000 0.0050785816 0.0055119138 0.0160128083 0.0064832322 0.0331450000 384440260 0 402718720 -0.3870094419 0.2885617018 2.0970084667 585 23.3600000000 0.0041676126 0.0055096159 0.0160128083 0.0064828925 0.0309960000 385922599 0 402718720 -0.3929342330 0.2854316235 2.0901260376 586 23.4000000000 0.0049972595 0.0055087416 0.0160128083 0.0064827524 0.0256680000 385080353 0 402718720 -0.3974198401 0.2839201689 2.0849456787 587 23.4400000000 0.0052891579 0.0055083675 0.0160128083 0.0064937905 0.0310730000 384760055 0 402718720 -0.4013756812 0.2843523622 2.0789470673 588 23.4800000000 0.0057485523 0.0055087760 0.0160128083 0.0065092973 0.0276610000 384785252 0 402718720 -0.4084552526 0.2834035158 2.0713152885 589 23.5200000000 0.0052202935 0.0055082862 0.0160128083 0.0065108416 0.0330010000 385053047 0 402718720 -0.4143730402 0.2802403569 2.0633387566 590 23.5600000000 0.0053720269 0.0055080552 0.0160128083 0.0065093091 0.0336250000 385024076 0 402718720 -0.4211781025 0.2779385149 2.0562283993 591 23.6000000000 0.0045659230 0.0055064611 0.0160128083 0.0065063587 0.0227930000 388523251 0 402718720 -0.4271963239 0.2751711011 2.0493645668 592 23.6400000000 0.0046938127 0.0055050884 0.0160128083 0.0065088395 0.0414410000 388208397 0 402718720 -0.4326128364 0.2754752636 2.0409467220 593 23.6800000000 0.0044917366 0.0055033795 0.0160128083 0.0065086185 0.0363900000 385274920 0 402718720 -0.4381921291 0.2755916119 2.0331885815 594 23.7200000000 0.0038373109 0.0055005747 0.0160128083 0.0065095416 0.0373810000 385283812 0 402718720 -0.4451751709 0.2720906138 2.0266921520 595 23.7600000000 0.0055402541 0.0055006414 0.0160128083 0.0065340486 0.0345920000 388147176 0 402718720 -0.4536305070 0.2703402042 2.0179016590 596 23.8000000000 0.0062150075 0.0055018400 0.0160128083 0.0065434836 0.0252930000 388359916 0 402718720 -0.4615246654 0.2682548761 2.0101954937 597 23.8400000000 0.0060252654 0.0055027168 0.0160128083 0.0065404475 0.0395590000 387997429 0 402718720 -0.4662180543 0.2682910860 2.0024538040 598 23.8800000000 0.0051506204 0.0055021280 0.0160128083 0.0065372881 0.0306870000 385704887 0 402718720 -0.4731882811 0.2669855058 1.9937112331 599 23.9200000000 0.0038426663 0.0054993576 0.0160128083 0.0065361600 0.0600110000 385753312 0 402718720 -0.4824183583 0.2651714981 1.9860250950 600 23.9600000000 0.0035544082 0.0054961160 0.0160128083 0.0065350970 0.0567040000 386748044 0 402718720 -0.4880543351 0.2637592554 1.9779132605 601 24.0000000000 0.0044549000 0.0054943835 0.0160128083 0.0065456183 0.0426680000 389573796 0 402718720 -0.4958993196 0.2634823322 1.9702057838 602 24.0400000000 0.0061784238 0.0054955198 0.0160128083 0.0065867270 0.0573240000 389272219 0 402718720 -0.5109447837 0.2636943460 1.9526245594 603 24.0800000000 0.0060614361 0.0054964583 0.0160128083 0.0065936504 0.0212470000 385776192 0 402718720 -0.5212104321 0.2625080347 1.9454886913 604 24.1200000000 0.0058860248 0.0054971033 0.0160128083 0.0065965601 0.0348740000 385779216 0 402718720 -0.5323712826 0.2600704432 1.9362692833 605 24.1600000000 0.0077359169 0.0055008038 0.0160128083 0.0066197839 0.0209130000 385787848 0 402718720 -0.5389025807 0.2617186308 1.9280576706 606 24.2000000000 0.0074684033 0.0055040507 0.0160128083 0.0066202747 0.0209890000 385792244 0 402718720 -0.5435871482 0.2611847520 1.9199801683 607 24.2400000000 0.0064749699 0.0055056502 0.0160128083 0.0066173920 0.0210300000 385798264 0 402718720 -0.5501388907 0.2587735057 1.9117578268 608 24.2800000000 0.0083071683 0.0055102580 0.0160128083 0.0066294046 0.0212940000 385804604 0 402718720 -0.5587826967 0.2592749596 1.9018509388 609 24.3200000000 0.0091479095 0.0055162311 0.0160128083 0.0066323401 0.0203360000 385805964 0 402718720 -0.5672775507 0.2597795129 1.8935728073 610 24.3600000000 0.0079044476 0.0055201462 0.0160128083 0.0066319127 0.0210100000 385813124 0 402718720 -0.5715271831 0.2577947080 1.8864593506 611 24.4000000000 0.0079043005 0.0055240483 0.0160128083 0.0066317048 0.0207730000 385814468 0 402718720 -0.5760897398 0.2570849657 1.8770878315 612 24.4400000000 0.0081495168 0.0055283383 0.0160128083 0.0066437998 0.0208280000 385819044 0 402718720 -0.5850043893 0.2556088567 1.8686621189 613 24.4800000000 0.0085453726 0.0055332600 0.0160128083 0.0066470978 0.0205570000 385823288 0 402718720 -0.5901973248 0.2556303740 1.8597836494 614 24.5200000000 0.0061674523 0.0055342929 0.0160128083 0.0066438440 0.0201100000 385825920 0 402718720 -0.5974811316 0.2523075342 1.8524129391 615 24.5600000000 0.0074955430 0.0055374819 0.0160128083 0.0066528025 0.0261400000 386635947 0 402718720 -0.6030597687 0.2529084086 1.8445780277 616 24.6000000000 0.0069647101 0.0055397989 0.0160128083 0.0066492705 0.1108020000 386859644 0 402718720 -0.6101233959 0.2512846291 1.8360886574 617 24.6400000000 0.0068336017 0.0055418958 0.0160128083 0.0066517391 0.0658590000 390329680 0 402718720 -0.6181160212 0.2502056956 1.8277695179 618 24.6800000000 0.0080068810 0.0055458844 0.0160128083 0.0066582868 0.0505990000 390037505 0 402718720 -0.6251509786 0.2499431074 1.8194466829 619 24.7200000000 0.0082868971 0.0055503126 0.0160128083 0.0066605683 0.0334930000 386721396 0 402718720 -0.6288017035 0.2503951788 1.8116850853 620 24.7600000000 0.0093334820 0.0055564144 0.0160128083 0.0066884332 0.0323260000 386727964 0 402718720 -0.6414612532 0.2498573959 1.7932823896 621 24.8000000000 0.0088141700 0.0055616604 0.0160128083 0.0066851231 0.0449640000 386727676 0 402718720 -0.6457489729 0.2470865548 1.7858974934 622 24.8400000000 0.0094747571 0.0055679516 0.0160128083 0.0066987847 0.0317940000 386731248 0 402718720 -0.6530880332 0.2466025651 1.7747561932 623 24.8800000000 0.0095042316 0.0055742698 0.0160128083 0.0066953840 0.0310250000 386734576 0 402718720 -0.6580251455 0.2454929054 1.7659029961 624 24.9200000000 0.0102340812 0.0055817375 0.0160128083 0.0067036849 0.0300350000 386735240 0 402718720 -0.6628761888 0.2459090948 1.7558805943 625 24.9600000000 0.0088090394 0.0055869012 0.0160128083 0.0066990305 0.0291670000 386737476 0 402718720 -0.6672008038 0.2434995472 1.7455779314 626 25.0000000000 0.0073318188 0.0055896886 0.0160128083 0.0067012143 0.0290680000 386741348 0 402718720 -0.6745939851 0.2393225133 1.7358183861 627 25.0400000000 0.0095714340 0.0055960391 0.0160128083 0.0067275049 0.0501970000 386743400 0 402718720 -0.6796396375 0.2422041297 1.7249300480 628 25.0800000000 0.0087529011 0.0056010659 0.0160128083 0.0067716870 0.0289060000 386745708 0 402718720 -0.6861014366 0.2354897559 1.7173234224 629 25.1200000000 0.0103261285 0.0056085779 0.0160128083 0.0068404818 0.0281220000 386749164 0 402718720 -0.6930493712 0.2402890921 1.7021704912 630 25.1600000000 0.0111811580 0.0056174233 0.0160128083 0.0068396893 0.0396360000 386753236 0 402718720 -0.6959450245 0.2413788140 1.6915295124 631 25.2000000000 0.0106056724 0.0056253286 0.0160128083 0.0068356005 0.0288710000 386756252 0 402718720 -0.6991198659 0.2395845205 1.6816046238 632 25.2400000000 0.0122594368 0.0056358256 0.0160128083 0.0068392931 0.0399010000 386757420 0 402718720 -0.7107324004 0.2367790192 1.6689763069 633 25.2800000000 0.0116404211 0.0056453115 0.0160128083 0.0068356814 0.0275310000 386758588 0 402718720 -0.7150071859 0.2361062467 1.6567609310 634 25.3200000000 0.0118241441 0.0056550573 0.0160128083 0.0068316144 0.0280690000 386762104 0 402718720 -0.7150372267 0.2363485843 1.6471350193 635 25.3600000000 0.0113484701 0.0056640233 0.0160128083 0.0068274764 0.0283080000 386764284 0 402718720 -0.7171061039 0.2343412489 1.6385221481 636 25.4000000000 0.0120811947 0.0056741132 0.0160128083 0.0068637638 0.0279020000 386766172 0 402718720 -0.7255864143 0.2344881296 1.6234545708 637 25.4400000000 0.0122223878 0.0056843931 0.0160128083 0.0068615276 0.0275920000 386767816 0 402718720 -0.7363049984 0.2336631417 1.6094739437 638 25.4800000000 0.0115223508 0.0056935435 0.0160128083 0.0068631827 0.0278920000 386772744 0 402718720 -0.7363874912 0.2331605852 1.5991773605 639 25.5200000000 0.0127504421 0.0057045872 0.0160128083 0.0068607675 0.0269530000 386771904 0 402718720 -0.7397587895 0.2342740893 1.5883572102 640 25.5600000000 0.0123861609 0.0057150271 0.0160128083 0.0068556237 0.0274260000 386779012 0 402718720 -0.7437040210 0.2331308126 1.5748338699 641 25.6000000000 0.0113882050 0.0057238776 0.0160128083 0.0068615503 0.0528980000 386780316 0 402718720 -0.7478067875 0.2295375615 1.5645959377 642 25.6400000000 0.0121277245 0.0057338525 0.0160128083 0.0068588346 0.0281650000 386783736 0 402718720 -0.7495374680 0.2297141105 1.5531318188 643 25.6800000000 0.0118929520 0.0057434312 0.0160128083 0.0068545447 0.0273990000 386785032 0 402718720 -0.7518218160 0.2283201367 1.5404912233 644 25.7200000000 0.0113113644 0.0057520770 0.0160128083 0.0068505639 0.0270480000 386787112 0 402718720 -0.7552143335 0.2255254984 1.5294332504 645 25.7600000000 0.0130794337 0.0057634373 0.0160128083 0.0068546487 0.0276330000 386791700 0 402718720 -0.7622787952 0.2252601385 1.5172991753 646 25.8000000000 0.0119298799 0.0057729828 0.0160128083 0.0068586245 0.0275850000 386793720 0 402718720 -0.7597826123 0.2235163450 1.5085895061 647 25.8400000000 0.0116886254 0.0057821260 0.0160128083 0.0068579927 0.0382390000 386796368 0 402718720 -0.7650028467 0.2230983824 1.4950797558 648 25.8800000000 0.0116219884 0.0057911382 0.0160128083 0.0068548096 0.0270310000 386799644 0 402718720 -0.7628350258 0.2210309654 1.4881676435 649 25.9200000000 0.0124575756 0.0058014100 0.0160128083 0.0068672671 0.0270850000 386802980 0 402718720 -0.7677110434 0.2208399922 1.4752454758 650 25.9600000000 0.0104910098 0.0058086248 0.0160128083 0.0068631819 0.0268950000 386804164 0 402718720 -0.7730155587 0.2162218541 1.4623649120 651 26.0000000000 0.0114072654 0.0058172249 0.0160128083 0.0068649037 0.0269000000 386808052 0 402718720 -0.7766234875 0.2141360790 1.4524877071 652 26.0400000000 0.0131647084 0.0058284940 0.0160128083 0.0068809919 0.0269330000 386810660 0 402718720 -0.7787895799 0.2147427648 1.4408376217 653 26.0800000000 0.0114616090 0.0058371205 0.0160128083 0.0068778536 0.0278020000 386815184 0 402718720 -0.7831351161 0.2102089822 1.4271786213 654 26.1200000000 0.0130590685 0.0058481632 0.0160128083 0.0068810117 0.0403410000 386815172 0 402718720 -0.7868053913 0.2080221474 1.4183883667 655 26.1600000000 0.0114510544 0.0058567173 0.0160128083 0.0068804370 0.0273180000 386819504 0 402718720 -0.7878510952 0.2037553489 1.4074885845 656 26.2000000000 0.0138879819 0.0058689601 0.0160128083 0.0068986671 0.0273670000 386821984 0 402718720 -0.7929693460 0.2041594088 1.3952577114 657 26.2400000000 0.0140623571 0.0058814310 0.0160128083 0.0069043051 0.0335880000 387617419 0 402718720 -0.7985166907 0.2013094723 1.3826737404 658 26.2800000000 0.0149893509 0.0058952728 0.0160128083 0.0069055295 0.1133940000 390495536 0 402718720 -0.8009703159 0.1994386613 1.3731768131 659 26.3200000000 0.0147256358 0.0059086724 0.0160128083 0.0069036685 0.0469070000 391044288 0 402718720 -0.8046998382 0.1972606629 1.3620920181 660 26.3600000000 0.0145265041 0.0059217298 0.0160128083 0.0068997345 0.0496240000 390801329 0 402718720 -0.8100626469 0.1935599148 1.3493366241 661 26.4000000000 0.0134606361 0.0059331351 0.0160128083 0.0068965727 0.0336540000 387669256 0 402718720 -0.8130611181 0.1907531619 1.3383269310 662 26.4400000000 0.0141226258 0.0059455059 0.0160128083 0.0068999107 0.0329750000 387671636 0 402718720 -0.8188366890 0.1894442290 1.3258734941 663 26.4800000000 0.0149304997 0.0059590579 0.0160128083 0.0069037857 0.0320470000 387673740 0 402718720 -0.8237293959 0.1894439459 1.3125710487 664 26.5200000000 0.0137650967 0.0059708140 0.0160128083 0.0069027749 0.0323280000 387677168 0 402718720 -0.8276793361 0.1858283281 1.3005223274 665 26.5600000000 0.0144077735 0.0059835012 0.0160128083 0.0069283894 0.0312750000 387679720 0 402718720 -0.8364547491 0.1842950135 1.2757740021 666 26.6000000000 0.0139022311 0.0059953912 0.0160128083 0.0069239916 0.0321220000 387682712 0 402718720 -0.8413473368 0.1835677177 1.2620670795 667 26.6400000000 0.0140590761 0.0060074806 0.0160128083 0.0069226852 0.0304880000 387685308 0 402718720 -0.8442622423 0.1834791750 1.2501051426 668 26.6800000000 0.0141578419 0.0060196818 0.0160128083 0.0069214134 0.0301750000 387686768 0 402718720 -0.8499978185 0.1825593859 1.2366826534 669 26.7200000000 0.0138530489 0.0060313908 0.0160128083 0.0069189817 0.0302710000 387690072 0 402718720 -0.8519492149 0.1828983426 1.2246693373 670 26.7600000000 0.0133190928 0.0060422680 0.0160128083 0.0069140946 0.0414930000 387692760 0 402718720 -0.8553080559 0.1828033030 1.2122142315 671 26.8000000000 0.0142180566 0.0060544525 0.0160128083 0.0069201796 0.0294390000 387695356 0 402718720 -0.8609577417 0.1822174639 1.1989228725 672 26.8400000000 0.0143973818 0.0060668676 0.0160128083 0.0069220634 0.0289910000 387697104 0 402718720 -0.8659952879 0.1802270859 1.1859505177 673 26.8800000000 0.0143127730 0.0060791200 0.0160128083 0.0069231555 0.0289500000 387700096 0 402718720 -0.8698086739 0.1777875274 1.1729941368 674 26.9200000000 0.0139917135 0.0060908598 0.0160128083 0.0069187527 0.0288610000 387703336 0 402718720 -0.8705656528 0.1756951213 1.1614129543 675 26.9600000000 0.0150609277 0.0061041488 0.0160128083 0.0069390782 0.0563560000 387704800 0 402718720 -0.8720703125 0.1746398211 1.1492557526 676 27.0000000000 0.0150597272 0.0061173967 0.0160128083 0.0069459274 0.0283940000 387707320 0 402718720 -0.8761137724 0.1730001867 1.1356394291 677 27.0400000000 0.0153003531 0.0061309609 0.0160128083 0.0069507194 0.0276230000 387709792 0 402718720 -0.8789154291 0.1724164784 1.1246786118 678 27.0800000000 0.0150889577 0.0061441732 0.0160128083 0.0069512935 0.0276190000 387712324 0 402718720 -0.8808630705 0.1721897870 1.1142476797 679 27.1200000000 0.0151041886 0.0061573691 0.0160128083 0.0069540651 0.0276990000 387714764 0 402718720 -0.8852672577 0.1697996557 1.1021615267 680 27.1600000000 0.0152658410 0.0061707640 0.0160128083 0.0069656577 0.0272290000 387717068 0 402718720 -0.8881286979 0.1692404002 1.0916357040 681 27.2000000000 0.0151122632 0.0061838939 0.0160128083 0.0069687035 0.0375500000 387719676 0 402718720 -0.8900045156 0.1688831151 1.0823434591 682 27.2400000000 0.0144923022 0.0061960763 0.0160128083 0.0069674926 0.0271400000 387722132 0 402718720 -0.8940597773 0.1678049266 1.0703938007 683 27.2800000000 0.0142587265 0.0062078811 0.0160128083 0.0069660694 0.0273990000 387724480 0 402718720 -0.8986511230 0.1675907820 1.0579894781 684 27.3200000000 0.0154192578 0.0062213480 0.0160128083 0.0069677776 0.0384980000 387726200 0 402718720 -0.8989944458 0.1665677279 1.0513987541 685 27.3600000000 0.0150326388 0.0062342112 0.0160128083 0.0069778941 0.0275690000 387729284 0 402718720 -0.8999775052 0.1653785110 1.0395181179 686 27.4000000000 0.0159787629 0.0062484161 0.0160128083 0.0069917654 0.0340280000 388621151 0 402718720 -0.9036271572 0.1663158238 1.0289177895 687 27.4400000000 0.0165782664 0.0062634523 0.0165782664 0.0069941045 0.1322740000 391383912 0 402718720 -0.9071973562 0.1645685583 1.0190296173 688 27.4800000000 0.0160562973 0.0062776861 0.0165782664 0.0069910194 0.0611370000 392238015 0 402718720 -0.9075983763 0.1638701260 1.0110311508 689 27.5200000000 0.0161401145 0.0062920002 0.0165782664 0.0069956291 0.0338920000 388678948 0 402718720 -0.9128658175 0.1634257734 0.9969089031 690 27.5600000000 0.0168604106 0.0063073167 0.0168604106 0.0069956305 0.0328510000 388680776 0 402718720 -0.9133757949 0.1636295170 0.9866968393 691 27.6000000000 0.0156985186 0.0063209075 0.0168604106 0.0069907967 0.0330670000 388683448 0 402718720 -0.9147943258 0.1613173932 0.9757722616 692 27.6400000000 0.0166290086 0.0063358036 0.0168604106 0.0069886209 0.0323920000 388685860 0 402718720 -0.9168536663 0.1592304707 0.9652097225 693 27.6800000000 0.0159767643 0.0063497155 0.0168604106 0.0069842364 0.0324210000 388688408 0 402718720 -0.9200043678 0.1581436247 0.9511690140 694 27.7200000000 0.0157412570 0.0063632480 0.0168604106 0.0069838280 0.0310520000 388690724 0 402718720 -0.9210450649 0.1553396434 0.9405084252 695 27.7600000000 0.0149282478 0.0063755717 0.0168604106 0.0069795500 0.0306630000 388693196 0 402718720 -0.9254158139 0.1515841484 0.9249554873 696 27.8000000000 0.0153024057 0.0063883976 0.0168604106 0.0069762621 0.0305220000 388695408 0 402718720 -0.9267790318 0.1500615478 0.9135907888 697 27.8400000000 0.0157338753 0.0064018058 0.0168604106 0.0069787395 0.0300130000 388697724 0 402718720 -0.9309465289 0.1429018378 0.8874699473 698 27.8800000000 0.0156370476 0.0064150368 0.0168604106 0.0069743273 0.0304120000 388700208 0 402718720 -0.9301828146 0.1392148733 0.8779946566 699 27.9200000000 0.0169021618 0.0064300398 0.0169021618 0.0069898324 0.0292790000 388702448 0 402718720 -0.9324991107 0.1418248713 0.8644726276 700 27.9600000000 0.0160865430 0.0064438348 0.0169021618 0.0069852084 0.0292900000 388704872 0 402718720 -0.9342708588 0.1419019401 0.8479404449 701 28.0000000000 0.0164056066 0.0064580456 0.0169021618 0.0069860659 0.0285490000 388707356 0 402718720 -0.9322127700 0.1411425173 0.8359335661 702 28.0400000000 0.0159471594 0.0064715629 0.0169021618 0.0069817039 0.0284250000 388709472 0 402718720 -0.9313745499 0.1409753412 0.8239903450 703 28.0800000000 0.0161312204 0.0064853035 0.0169021618 0.0069776903 0.0284320000 388711772 0 402718720 -0.9357168674 0.1392912865 0.8075178266 704 28.1200000000 0.0168687608 0.0065000527 0.0169021618 0.0069799833 0.0283170000 388714072 0 402718720 -0.9351285696 0.1364179105 0.7948793173 705 28.1600000000 0.0167271439 0.0065145592 0.0169021618 0.0069793431 0.0268870000 388716296 0 402718720 -0.9350604415 0.1317274719 0.7818428278 706 28.2000000000 0.0160817616 0.0065281105 0.0169021618 0.0069782188 0.0356600000 389710015 0 402718720 -0.9345530868 0.1273335963 0.7683638930 707 28.2400000000 0.0167830419 0.0065426154 0.0169021618 0.0069954508 0.0997190000 393550492 0 402718720 -0.9347188473 0.1280988157 0.7532124519 708 28.2800000000 0.0173048284 0.0065578162 0.0173048284 0.0070094744 0.0639410000 393353159 0 402718720 -0.9397239089 0.1297205985 0.7356350422 709 28.3200000000 0.0171477851 0.0065727527 0.0173048284 0.0070171933 0.0316930000 389636820 0 402718720 -0.9398748875 0.1264738739 0.7221964598 710 28.3600000000 0.0175816398 0.0065882582 0.0175816398 0.0070149371 0.0325470000 389639504 0 402718720 -0.9368233681 0.1258855164 0.7122800350 711 28.4000000000 0.0172768645 0.0066032914 0.0175816398 0.0070102704 0.0297400000 389642116 0 402718720 -0.9377706647 0.1243729517 0.6998549700 712 28.4400000000 0.0170352831 0.0066179431 0.0175816398 0.0070060471 0.0315870000 389644064 0 402718720 -0.9383620024 0.1216527820 0.6877478361 713 28.4800000000 0.0170139149 0.0066325237 0.0175816398 0.0070024635 0.0309970000 389646640 0 402718720 -0.9366012812 0.1184426919 0.6775816679 714 28.5200000000 0.0171319172 0.0066472287 0.0175816398 0.0070073174 0.0297050000 389648772 0 402718720 -0.9369090796 0.1180297360 0.6665406227 715 28.5600000000 0.0174881406 0.0066623908 0.0175816398 0.0070179099 0.0287660000 389650964 0 402718720 -0.9384348392 0.1204402745 0.6516710520 716 28.6000000000 0.0174256992 0.0066774234 0.0175816398 0.0070152111 0.0268430000 389653496 0 402718720 -0.9387532473 0.1196335480 0.6387997866 717 28.6400000000 0.0169529617 0.0066917547 0.0175816398 0.0070198345 0.0286230000 389655676 0 402718720 -0.9374299645 0.1148040518 0.6306465864 718 28.6800000000 0.0168620534 0.0067059194 0.0175816398 0.0070211669 0.0282230000 389658068 0 402718720 -0.9378930926 0.1138920859 0.6217737198 719 28.7200000000 0.0175551511 0.0067210088 0.0175816398 0.0070225489 0.0275060000 389660708 0 402718720 -0.9398485422 0.1138258576 0.6098974347 720 28.7600000000 0.0177543592 0.0067363329 0.0177543592 0.0070194235 0.0268440000 389662808 0 402718720 -0.9421333075 0.1125795543 0.5991367698 721 28.8000000000 0.0174559262 0.0067512005 0.0177543592 0.0070225596 0.0268460000 389665092 0 402718720 -0.9403258562 0.1140386686 0.5874724388 722 28.8400000000 0.0167736430 0.0067650820 0.0177543592 0.0070262149 0.0263040000 389667484 0 402718720 -0.9475106597 0.1152677312 0.5726132393 723 28.8800000000 0.0169858374 0.0067792186 0.0177543592 0.0070319900 0.0263670000 389669892 0 402718720 -0.9530425072 0.1147284433 0.5630031824 724 28.9200000000 0.0186472777 0.0067956110 0.0186472777 0.0070317440 0.0259980000 389672044 0 402718720 -0.9548192024 0.1169925928 0.5546368957 725 28.9600000000 0.0180197544 0.0068110925 0.0186472777 0.0070290864 0.0338300000 390689763 0 402718720 -0.9588191509 0.1167729199 0.5433201790 726 29.0000000000 0.0182626434 0.0068268660 0.0186472777 0.0070320582 0.1043090000 390705568 0 402718720 -0.9618675709 0.1147725806 0.5296401978 727 29.0400000000 0.0183562972 0.0068427249 0.0186472777 0.0070333302 0.0660910000 394856192 0 402718720 -0.9716579318 0.1136803403 0.5099397898 728 29.0800000000 0.0173309185 0.0068571318 0.0186472777 0.0070413219 0.0494650000 394756581 0 402718720 -0.9838243723 0.1111709252 0.4955630302 729 29.1200000000 0.0171706062 0.0068712792 0.0186472777 0.0070835514 0.0284510000 390627404 0 402718720 -0.9871082306 0.1052488014 0.4875498712 730 29.1600000000 0.0173096936 0.0068855784 0.0186472777 0.0070818962 0.0286980000 390630136 0 402718720 -0.9895369411 0.1051260903 0.4789007306 731 29.2000000000 0.0169750042 0.0068993807 0.0186472777 0.0070782233 0.0283640000 390632252 0 402718720 -0.9980809093 0.1073766202 0.4642169774 732 29.2400000000 0.0172005426 0.0069134533 0.0186472777 0.0070860807 0.0278020000 390634692 0 402718720 -1.0038889647 0.1086829752 0.4528911412 733 29.2800000000 0.0172455590 0.0069275489 0.0186472777 0.0070880594 0.0273510000 390637380 0 402718720 -1.0072680712 0.1114783362 0.4423483908 734 29.3200000000 0.0172356348 0.0069415926 0.0186472777 0.0070863566 0.0270330000 390640004 0 402718720 -1.0155146122 0.1154261604 0.4297006130 735 29.3600000000 0.0175967887 0.0069560895 0.0186472777 0.0071251364 0.0273320000 390641568 0 402718720 -1.0198988914 0.1139357612 0.4206262231 736 29.4000000000 0.0172044467 0.0069700139 0.0186472777 0.0071305845 0.0269860000 390644084 0 402718720 -1.0226019621 0.1144955084 0.4118208587 737 29.4400000000 0.0177568719 0.0069846501 0.0186472777 0.0071274880 0.0271090000 390646568 0 402718720 -1.0283515453 0.1196441948 0.3988689482 738 29.4800000000 0.0172735639 0.0069985917 0.0186472777 0.0071477961 0.0265470000 390649024 0 402718720 -1.0331726074 0.1204460114 0.3871253729 739 29.5200000000 0.0187592581 0.0070145060 0.0187592581 0.0071860784 0.0261040000 390651128 0 402718720 -1.0323137045 0.1196534038 0.3845106959 740 29.5600000000 0.0186880436 0.0070302810 0.0187592581 0.0071840325 0.0260560000 390653628 0 402718720 -1.0351767540 0.1192472801 0.3748243749 741 29.6000000000 0.0184711888 0.0070457209 0.0187592581 0.0071808801 0.0258040000 390655608 0 402718720 -1.0376759768 0.1192257106 0.3638277650 742 29.6400000000 0.0174602866 0.0070597567 0.0187592581 0.0071789206 0.0260210000 390658108 0 402718720 -1.0407367945 0.1192574501 0.3522746563 743 29.6800000000 0.0187368803 0.0070754728 0.0187592581 0.0071761659 0.0256150000 390660608 0 402718720 -1.0435831547 0.1223305613 0.3451576531 744 29.7200000000 0.0184595790 0.0070907741 0.0187592581 0.0071765708 0.0255230000 390663108 0 402718720 -1.0495814085 0.1241727024 0.3351939619 745 29.7600000000 0.0182364844 0.0071057347 0.0187592581 0.0071873360 0.0258700000 390665212 0 402718720 -1.0528929234 0.1248346567 0.3281490803 746 29.8000000000 0.0184371788 0.0071209243 0.0187592581 0.0072085915 0.0248700000 390667176 0 402718720 -1.0568559170 0.1256612092 0.3215355277 747 29.8400000000 0.0183158759 0.0071359109 0.0187592581 0.0072359992 0.0250540000 390669928 0 402718720 -1.0531636477 0.1240522712 0.3152621686 748 29.8800000000 0.0178353656 0.0071502150 0.0187592581 0.0072364647 0.0245220000 390672120 0 402718720 -1.0513747931 0.1204335317 0.3116870224 749 29.9200000000 0.0179717969 0.0071646630 0.0187592581 0.0072338400 0.0246030000 390674604 0 402718720 -1.0549845695 0.1202093363 0.3054324985 750 29.9600000000 0.0183070935 0.0071795196 0.0187592581 0.0072305520 0.0240890000 390676784 0 402718720 -1.0595215559 0.1233470440 0.2925143242 751 30.0000000000 0.0182152074 0.0071942143 0.0187592581 0.0072341480 0.0244340000 390679192 0 402718720 -1.0592671633 0.1223884150 0.2885882854 752 30.0400000000 0.0187242776 0.0072095468 0.0187592581 0.0072342771 0.0245380000 390681416 0 402718720 -1.0618721247 0.1216350272 0.2850952744 753 30.0800000000 0.0188689046 0.0072250307 0.0188689046 0.0072300188 0.0245260000 390683976 0 402718720 -1.0663967133 0.1253379136 0.2751578093 754 30.1200000000 0.0177150853 0.0072389432 0.0188689046 0.0072633447 0.0243240000 390686200 0 402718720 -1.0658500195 0.1207244769 0.2701644003 755 30.1600000000 0.0177771784 0.0072529011 0.0188689046 0.0072633492 0.0330360000 391629691 0 402718720 -1.0610685349 0.1185265034 0.2668069899 756 30.2000000000 0.0183941592 0.0072676382 0.0188689046 0.0072626486 0.1121950000 391765576 0 402718720 -1.0629466772 0.1187732667 0.2605852783 757 30.2400000000 0.0186493509 0.0072826735 0.0188689046 0.0072595870 0.0632820000 395227396 0 402718720 -1.0647364855 0.1181820258 0.2540545464 758 30.2800000000 0.0183099136 0.0072972213 0.0188689046 0.0072598680 0.0491840000 395096177 0 402718720 -1.0686638355 0.1177650988 0.2462420166 759 30.3200000000 0.0181391705 0.0073115059 0.0188689046 0.0072559815 0.0332610000 391662520 0 402718720 -1.0700683594 0.1201862916 0.2354699075 760 30.3600000000 0.0177411288 0.0073252290 0.0188689046 0.0072768593 0.0311900000 391664748 0 402718720 -1.0663629770 0.1171408072 0.2298582792 761 30.4000000000 0.0177790169 0.0073389659 0.0188689046 0.0072772475 0.0435510000 391666972 0 402718720 -1.0658603907 0.1157360524 0.2256577313 762 30.4400000000 0.0181449074 0.0073531470 0.0188689046 0.0072752716 0.0308430000 391669288 0 402718720 -1.0692362785 0.1160182208 0.2177697569 763 30.4800000000 0.0177485440 0.0073667713 0.0188689046 0.0072903265 0.0337790000 391672084 0 402718720 -1.0692820549 0.1129811406 0.2104277164 764 30.5200000000 0.0176133588 0.0073801831 0.0188689046 0.0072867924 0.0350160000 391674232 0 402718720 -1.0680665970 0.1140911058 0.2035770714 765 30.5600000000 0.0179659072 0.0073940207 0.0188689046 0.0072844532 0.0344200000 391676640 0 402718720 -1.0672405958 0.1133880913 0.1948981583 766 30.6000000000 0.0178676434 0.0074076938 0.0188689046 0.0072923778 0.0338260000 391678740 0 402718720 -1.0623247623 0.1077794507 0.1915152073 767 30.6400000000 0.0180108957 0.0074215180 0.0188689046 0.0072891782 0.0336910000 391681300 0 402718720 -1.0624520779 0.1080095470 0.1809978187 768 30.6800000000 0.0183634683 0.0074357654 0.0188689046 0.0072884073 0.0335690000 391683492 0 402718720 -1.0622704029 0.1070402712 0.1717018932 769 30.7200000000 0.0180153213 0.0074495229 0.0188689046 0.0072991748 0.0308690000 391685564 0 402718720 -1.0560233593 0.1005346030 0.1693847179 770 30.7600000000 0.0182670914 0.0074635717 0.0188689046 0.0073020622 0.0276120000 391688140 0 402718720 -1.0550980568 0.1003568321 0.1613095999 771 30.8000000000 0.0189383067 0.0074784546 0.0189383067 0.0072999274 0.0268700000 391690012 0 402718720 -1.0544154644 0.0992268845 0.1525747478 772 30.8400000000 0.0180805083 0.0074921879 0.0189383067 0.0072965317 0.0275800000 391692684 0 402718720 -1.0487060547 0.0937241912 0.1460190415 773 30.8800000000 0.0183880534 0.0075062834 0.0189383067 0.0073050705 0.0261400000 391695108 0 402718720 -1.0430498123 0.0921270922 0.1395519376 774 30.9200000000 0.0193876680 0.0075216341 0.0193876680 0.0073234449 0.0263360000 391697308 0 402718720 -1.0446978807 0.0941586792 0.1301869303 775 30.9600000000 0.0191868488 0.0075366859 0.0193876680 0.0073201030 0.0263270000 391699968 0 402718720 -1.0451452732 0.0935283527 0.1243068352 776 31.0000000000 0.0191734936 0.0075516818 0.0193876680 0.0073183873 0.0256090000 391702208 0 402718720 -1.0464797020 0.0927597061 0.1191649809 777 31.0400000000 0.0185975451 0.0075658979 0.0193876680 0.0073153282 0.0255170000 391704800 0 402718720 -1.0424900055 0.0908906460 0.1128428429 778 31.0800000000 0.0182907358 0.0075796830 0.0193876680 0.0073166417 0.0254550000 391706916 0 402718720 -1.0433691740 0.0910179615 0.1033927873 779 31.1200000000 0.0173665080 0.0075922463 0.0193876680 0.0073223727 0.0251660000 391708312 0 402718720 -1.0424875021 0.0936994329 0.0931477398 780 31.1600000000 0.0159961451 0.0076030206 0.0193876680 0.0073239916 0.0249620000 391711288 0 402718720 -1.0401868820 0.0981078595 0.0858541802 781 31.2000000000 0.0185301788 0.0076170118 0.0193876680 0.0073220009 0.0246280000 391713344 0 402718720 -1.0362346172 0.1008921713 0.0781181678 782 31.2400000000 0.0176456664 0.0076298362 0.0193876680 0.0073209379 0.0240310000 391714924 0 402718720 -1.0333119631 0.0976905525 0.0706055313 783 31.2800000000 0.0196043961 0.0076451293 0.0196043961 0.0073230901 0.0243670000 391717472 0 402718720 -1.0287392139 0.0992806852 0.0684326887 784 31.3200000000 0.0194259360 0.0076601559 0.0196043961 0.0073189723 0.0242350000 391720008 0 402718720 -1.0266550779 0.0996500552 0.0588701777 785 31.3600000000 0.0193439275 0.0076750397 0.0196043961 0.0073257576 0.0244410000 391721604 0 402718720 -1.0306241512 0.0962309688 0.0532925464 786 31.4000000000 0.0169977397 0.0076869006 0.0196043961 0.0073337536 0.0236610000 391722160 0 402718720 -1.0243504047 0.0889691636 0.0516688228 787 31.4400000000 0.0239221025 0.0077075298 0.0239221025 0.0073552356 0.0235470000 391720920 0 402718720 -1.0256627798 0.0923759192 0.0474149100 788 31.4800000000 0.0250224806 0.0077295031 0.0250224806 0.0073643982 0.0234630000 391723224 0 402718720 -1.0138708353 0.0925143212 0.0501511544 789 31.5200000000 0.0190560203 0.0077438587 0.0250224806 0.0073729601 0.0234710000 391725880 0 402718720 -1.0188528299 0.0886063278 0.0326113328 790 31.5600000000 0.0163350012 0.0077547335 0.0250224806 0.0073697745 0.0235100000 391726664 0 402718720 -1.0131984949 0.0866941065 0.0306967832 791 31.6000000000 0.0191538148 0.0077691445 0.0250224806 0.0073882331 0.0327810000 391728612 0 402718720 -1.0068186522 0.0914856344 0.0263512246 792 31.6400000000 0.0213465709 0.0077862877 0.0250224806 0.0073927023 0.0237970000 391733580 0 402718720 -1.0117274523 0.0919899344 0.0173489116 793 31.6800000000 0.0122417193 0.0077919062 0.0250224806 0.0074147531 0.0372690000 391735820 0 402718720 -1.0067846775 0.0791207924 0.0175641105 794 31.7200000000 0.0142056234 0.0077999839 0.0250224806 0.0074251591 0.0234030000 391736956 0 402718720 -1.0078865290 0.0830667913 0.0073108152 795 31.7600000000 0.0170814861 0.0078116587 0.0250224806 0.0074332959 0.0243330000 391740332 0 402718720 -1.0135657787 0.0844015330 0.0025533736 796 31.8000000000 0.0266338605 0.0078353047 0.0266338605 0.0074423196 0.0237840000 391742588 0 402718720 -1.0163059235 0.0906039849 -0.0006640404 797 31.8400000000 0.0243744142 0.0078560564 0.0266338605 0.0074768323 0.0236080000 391743784 0 402718720 -1.0026352406 0.0901849791 -0.0074730068 798 31.8800000000 0.0190019384 0.0078700237 0.0266338605 0.0075540692 0.0233850000 391745256 0 402718720 -1.0135709047 0.0778671131 -0.0027597994 799 31.9200000000 0.0232182276 0.0078892330 0.0266338605 0.0076275975 0.0232760000 391746868 0 402718720 -1.0112808943 0.0914161950 -0.0180037469 800 31.9600000000 0.0142387096 0.0078971698 0.0266338605 0.0076599691 0.0360060000 391750564 0 402718720 -1.0110552311 0.0772467926 -0.0225150213 801 32.0000000000 0.0278014094 0.0079220191 0.0278014094 0.0076911566 0.0341750000 391752420 0 402718720 -1.0120072365 0.0792613402 -0.0213688463 802 32.0400000000 0.0148269692 0.0079306287 0.0278014094 0.0076965819 0.0232510000 391753540 0 402718720 -1.0095748901 0.0638498291 -0.0196410716 803 32.0800000000 0.0179652367 0.0079431251 0.0278014094 0.0077158956 0.0231030000 391753308 0 402718720 -1.0097286701 0.0693043247 -0.0280001387 804 32.1199999990 0.0141514288 0.0079508469 0.0278014094 0.0077154656 0.0231070000 391755040 0 402718720 -1.0047765970 0.0620661825 -0.0304433182 805 32.1600000000 0.0163918212 0.0079613326 0.0278014094 0.0077267021 0.0233980000 391757416 0 402718720 -1.0075981617 0.0612863749 -0.0368166789 806 32.2000000000 0.0136264525 0.0079683613 0.0278014094 0.0077378833 0.0339030000 391758352 0 402718720 -1.0072275400 0.0600232556 -0.0532570779 807 32.2400000000 0.0237220004 0.0079878825 0.0278014094 0.0077962041 0.0227340000 391758396 0 402718720 -1.0074245930 0.0730779022 -0.0607413799 808 32.2800000000 0.0183534399 0.0080007112 0.0278014094 0.0077953945 0.0232310000 391761280 0 402718720 -1.0078430176 0.0734186769 -0.0692566782 809 32.3200000000 0.0148593485 0.0080091891 0.0278014094 0.0078014823 0.0231110000 391764960 0 402718720 -1.0090801716 0.0660583675 -0.0723949224 810 32.3600000000 0.0127221374 0.0080150075 0.0278014094 0.0078140518 0.0332640000 391767628 0 402718720 -1.0139348507 0.0630027801 -0.0836950168 811 32.4000000000 0.0181497354 0.0080275041 0.0278014094 0.0078186004 0.0229090000 391770220 0 402718720 -1.0095939636 0.0603117794 -0.0828390047 812 32.4399999990 0.0146736428 0.0080356890 0.0278014094 0.0078231529 0.0228300000 391770940 0 402718720 -1.0082036257 0.0501304381 -0.0849436894 813 32.4800000000 0.0159868244 0.0080454690 0.0278014094 0.0078769368 0.0229310000 391773716 0 402718720 -1.0111190081 0.0615566596 -0.0970681161 814 32.5200000000 0.0135475947 0.0080522284 0.0278014094 0.0078889952 0.0228620000 391775004 0 402718720 -1.0170741081 0.0697926432 -0.1156871095 815 32.5600000000 0.0202643834 0.0080672126 0.0278014094 0.0079771081 0.0298930000 392584823 0 402718720 -1.0257054567 0.0642489195 -0.1129847541 816 32.6000000000 0.0200494472 0.0080818967 0.0278014094 0.0079738714 0.0988470000 392707740 0 402718720 -1.0265666246 0.0606881492 -0.1179724112 817 32.6400000000 0.0195020624 0.0080958749 0.0278014094 0.0079737400 0.0723200000 396086892 0 402718720 -1.0300102234 0.0605493374 -0.1267703027 818 32.6800000000 0.0174018983 0.0081072514 0.0278014094 0.0079886619 0.0367460000 393294585 0 402718720 -1.0231013298 0.0544201471 -0.1335066408 819 32.7200000000 0.0169470552 0.0081180449 0.0278014094 0.0079894474 0.0314050000 392602548 0 402718720 -1.0256909132 0.0475672521 -0.1383473724 820 32.7599999990 0.0166492369 0.0081284488 0.0278014094 0.0079886001 0.0316430000 392607364 0 402718720 -1.0248117447 0.0484957509 -0.1456874311 821 32.7999999990 0.0163894165 0.0081385108 0.0278014094 0.0079864103 0.0319540000 392608744 0 402718720 -1.0290186405 0.0485959537 -0.1540330648 822 32.8400000000 0.0155974543 0.0081475850 0.0278014094 0.0079836344 0.0314730000 392611764 0 402718720 -1.0320620537 0.0464735255 -0.1617552191 823 32.8800000000 0.0183303040 0.0081599577 0.0278014094 0.0079840208 0.0309710000 392613680 0 402718720 -1.0327423811 0.0489750020 -0.1663317978 824 32.9200000000 0.0168018751 0.0081704454 0.0278014094 0.0079812575 0.0303620000 392615320 0 402718720 -1.0383120775 0.0494989604 -0.1770437509 825 32.9600000000 0.0157717541 0.0081796591 0.0278014094 0.0079860734 0.0311270000 392618156 0 402718720 -1.0386971235 0.0423484445 -0.1808568388 826 33.0000000000 0.0147603098 0.0081876260 0.0278014094 0.0079815910 0.0307530000 392620624 0 402718720 -1.0360254049 0.0418988056 -0.1865943521 827 33.0400000000 0.0141366841 0.0081948196 0.0278014094 0.0079812601 0.0308120000 392623368 0 402718720 -1.0419747829 0.0407909229 -0.1979367882 828 33.0800000000 0.0158304702 0.0082040414 0.0278014094 0.0079860835 0.0313430000 392625560 0 402718720 -1.0398001671 0.0306173302 -0.1965493411 829 33.1199999990 0.0181914363 0.0082160889 0.0278014094 0.0080012781 0.0299770000 392625912 0 402718720 -1.0382206440 0.0338930152 -0.2010416687 830 33.1600000000 0.0166275520 0.0082262232 0.0278014094 0.0080128557 0.0298620000 392630036 0 402718720 -1.0469319820 0.0380003527 -0.2154134512 831 33.2000000000 0.0143967737 0.0082336486 0.0278014094 0.0080144759 0.0298350000 392631508 0 402718720 -1.0497342348 0.0335374214 -0.2224982977 832 33.2400000000 0.0147210723 0.0082414460 0.0278014094 0.0080132173 0.0292850000 392633900 0 402718720 -1.0464656353 0.0291147120 -0.2231928408 833 33.2800000000 0.0168793388 0.0082518156 0.0278014094 0.0080259819 0.0294920000 392637120 0 402718720 -1.0448081493 0.0308590159 -0.2299152166 834 33.3200000000 0.0153710395 0.0082603519 0.0278014094 0.0080302932 0.0283560000 392637196 0 402718720 -1.0500848293 0.0296300128 -0.2397395521 835 33.3600000000 0.0132821472 0.0082663660 0.0278014094 0.0080266222 0.0284530000 392640492 0 402718720 -1.0517625809 0.0265527964 -0.2484643906 836 33.4000000000 0.0185582023 0.0082786768 0.0278014094 0.0080420808 0.0399550000 392641180 0 402718720 -1.0500020981 0.0327196755 -0.2546910048 837 33.4399999990 0.0186003782 0.0082910086 0.0278014094 0.0080433224 0.0288030000 392643772 0 402718720 -1.0505166054 0.0316132121 -0.2616814971 838 33.4800000000 0.0168780088 0.0083012556 0.0278014094 0.0080403282 0.0282280000 392645736 0 402718720 -1.0476531982 0.0239952579 -0.2664210498 839 33.5200000000 0.0142257176 0.0083083169 0.0278014094 0.0080403569 0.0405100000 392648160 0 402718720 -1.0479352474 0.0235207714 -0.2787725031 840 33.5600000000 0.0153559297 0.0083167070 0.0278014094 0.0080362873 0.0276220000 392650768 0 402718720 -1.0383813381 0.0177288093 -0.2826363146 841 33.6000000000 0.0159215201 0.0083257495 0.0278014094 0.0080345276 0.0276410000 392654480 0 402718720 -1.0358618498 0.0150791109 -0.2884691954 842 33.6400000000 0.0170361996 0.0083360945 0.0278014094 0.0080344852 0.0271570000 392655260 0 402718720 -1.0337743759 0.0113590136 -0.2948855162 843 33.6800000000 0.0162211731 0.0083454481 0.0278014094 0.0080617409 0.0270350000 392654540 0 402718720 -1.0290348530 0.0107741654 -0.3130511642 844 33.7200000000 0.0141676022 0.0083523464 0.0278014094 0.0080667661 0.0265330000 392657608 0 402718720 -1.0275464058 0.0088773407 -0.3247329295 845 33.7599999990 0.0129486062 0.0083577857 0.0278014094 0.0080720196 0.0267420000 392661272 0 402718720 -1.0272561312 0.0098840185 -0.3365814686 846 33.7999999990 0.0171866324 0.0083682217 0.0278014094 0.0080776424 0.0394750000 392661092 0 402718720 -1.0240796804 0.0158035457 -0.3436322808 847 33.8400000000 0.0157587789 0.0083769473 0.0278014094 0.0080753643 0.0265100000 392664020 0 402718720 -1.0205105543 0.0188011490 -0.3570193946 848 33.8800000000 0.0168672968 0.0083869595 0.0278014094 0.0080782605 0.0267120000 392668376 0 402718720 -1.0113779306 0.0176902525 -0.3639724553 849 33.9200000000 0.0171871819 0.0083973249 0.0278014094 0.0080754796 0.0264900000 392668176 0 402718720 -1.0101206303 0.0141966119 -0.3721961081 850 33.9600000000 0.0177135170 0.0084082851 0.0278014094 0.0080714850 0.0473040000 392671472 0 402718720 -1.0028816462 0.0138394758 -0.3828122020 851 34.0000000000 0.0194742773 0.0084212886 0.0278014094 0.0080682051 0.0259950000 392671488 0 402718720 -0.9948436618 0.0085827857 -0.3856392801 852 34.0400000000 0.0172682889 0.0084316724 0.0278014094 0.0080677690 0.0265090000 392675796 0 402718720 -0.9899805188 0.0026083738 -0.3950882554 853 34.0800000000 0.0144359879 0.0084387115 0.0278014094 0.0080709250 0.0474190000 392679016 0 402718720 -0.9883974791 0.0063729603 -0.4084503651 854 34.1199999990 0.0156373661 0.0084471408 0.0278014094 0.0080673867 0.0259860000 392680104 0 402718720 -0.9845268726 0.0064720884 -0.4156803489 855 34.1600000000 0.0125854686 0.0084519810 0.0278014094 0.0080646066 0.0262030000 392681376 0 402718720 -0.9818813205 0.0024251286 -0.4262858927 856 34.2000000000 0.0153035577 0.0084599852 0.0278014094 0.0080643778 0.0256460000 392683492 0 402718720 -0.9726274610 0.0025045276 -0.4311387837 857 34.2400000000 0.0211238638 0.0084747621 0.0278014094 0.0080656516 0.0258740000 392685884 0 402718720 -0.9673197269 0.0041377228 -0.4341818690 858 34.2800000000 0.0176064782 0.0084854052 0.0278014094 0.0080694111 0.0370590000 392689732 0 402718720 -0.9636091590 0.0039512273 -0.4464475513 859 34.3200000000 0.0179648716 0.0084964406 0.0278014094 0.0080716620 0.0256270000 392691052 0 402718720 -0.9610595107 0.0053903908 -0.4549016953 860 34.3600000000 0.0166718792 0.0085059470 0.0278014094 0.0080670307 0.0349980000 392692508 0 402718720 -0.9553686976 0.0023493357 -0.4633426070 861 34.4000000000 0.0186998397 0.0085177866 0.0278014094 0.0080651963 0.0253250000 392694516 0 402718720 -0.9501661658 0.0006578658 -0.4686160088 862 34.4400000000 0.0178750549 0.0085286419 0.0278014094 0.0080611918 0.0251180000 392696512 0 402718720 -0.9441460967 -0.0018808041 -0.4765382409 863 34.4800000000 0.0164458267 0.0085378159 0.0278014094 0.0080597052 0.0377550000 392697416 0 402718720 -0.9404011965 -0.0028337799 -0.4839234352 864 34.5200000000 0.0149811199 0.0085452734 0.0278014094 0.0080696441 0.0246960000 392700548 0 402718720 -0.9392497540 0.0013885200 -0.4965972304 865 34.5600000000 0.0158186089 0.0085536819 0.0278014094 0.0080702768 0.0250710000 392705256 0 402718720 -0.9328479767 -0.0028526969 -0.5023909211 866 34.6000000000 0.0179660209 0.0085645506 0.0278014094 0.0080712288 0.0359300000 392706728 0 402718720 -0.9283391833 -0.0133231580 -0.5021928549 867 34.6400000000 0.0149354199 0.0085718988 0.0278014094 0.0080917808 0.0246050000 392707020 0 402718720 -0.9256044626 -0.0208861995 -0.5190261006 868 34.6800000000 0.0138266729 0.0085779527 0.0278014094 0.0080911336 0.0424600000 393438840 0 402718720 -0.9199745655 -0.0225904658 -0.5265914798 869 34.7200000000 0.0166014582 0.0085871857 0.0278014094 0.0080914075 0.1079080000 393557628 0 402718720 -0.9161722064 -0.0236006845 -0.5313871503 870 34.7600000000 0.0150025897 0.0085945598 0.0278014094 0.0080942927 0.0710320000 396217492 0 402718720 -0.9121732712 -0.0247235429 -0.5420058966 871 34.8000000000 0.0181097109 0.0086054842 0.0278014094 0.0081744846 0.0494440000 395887121 0 402718720 -0.9171005487 -0.0213993043 -0.5564608574 872 34.8400000000 0.0189735126 0.0086173741 0.0278014094 0.0081811026 0.0292160000 393464484 0 402718720 -0.9160941243 -0.0224079769 -0.5647916794 873 34.8800000000 0.0198511016 0.0086302421 0.0278014094 0.0081956063 0.0267870000 393467476 0 402718720 -0.9061380029 -0.0161808655 -0.5707971454 874 34.9200000000 0.0199811496 0.0086432294 0.0278014094 0.0081933379 0.0397940000 393469532 0 402718720 -0.9061690569 -0.0164865069 -0.5780074000 875 34.9600000000 0.0193250794 0.0086554372 0.0278014094 0.0081966291 0.0271600000 393470820 0 402718720 -0.9004605412 -0.0124051087 -0.5881727934 876 35.0000000000 0.0190536883 0.0086673074 0.0278014094 0.0081938543 0.0260340000 393472432 0 402718720 -0.8962385654 -0.0146737285 -0.5946491957 877 35.0400000000 0.0191403143 0.0086792492 0.0278014094 0.0081905599 0.0254410000 393474304 0 402718720 -0.8880141377 -0.0186922029 -0.5985341668 878 35.0800000000 0.0214994401 0.0086938508 0.0278014094 0.0081938111 0.0259080000 393477896 0 402718720 -0.8813880086 -0.0191076770 -0.6003305316 879 35.1200000000 0.0215453822 0.0087084714 0.0278014094 0.0082088927 0.0261230000 393478432 0 402718720 -0.8790407777 -0.0144603588 -0.6137939692 880 35.1600000000 0.0208845939 0.0087223079 0.0278014094 0.0082105372 0.0243840000 393478376 0 402718720 -0.8733875751 -0.0184302200 -0.6228812337 881 35.2000000000 0.0192556344 0.0087342640 0.0278014094 0.0082106089 0.0345290000 393480016 0 402718720 -0.8652156591 -0.0234790705 -0.6208468676 882 35.2400000000 0.0191243403 0.0087460442 0.0278014094 0.0082139595 0.0246820000 393483624 0 402718720 -0.8594219089 -0.0226131435 -0.6324397922 883 35.2800000000 0.0211212263 0.0087600591 0.0278014094 0.0082115504 0.0243870000 393485436 0 402718720 -0.8576644659 -0.0212773141 -0.6408510804 884 35.3200000000 0.0167370941 0.0087690829 0.0278014094 0.0082240087 0.0244140000 393487032 0 402718720 -0.8535604477 -0.0295713376 -0.6514910460 885 35.3600000000 0.0176136903 0.0087790768 0.0278014094 0.0082230751 0.0235960000 393488436 0 402718720 -0.8458612561 -0.0355714411 -0.6551865935 886 35.4000000000 0.0154218478 0.0087865743 0.0278014094 0.0082242314 0.0236380000 393489468 0 402718720 -0.8449047208 -0.0471126437 -0.6615139246 887 35.4400000000 0.0149131157 0.0087934813 0.0278014094 0.0082206245 0.0231980000 393488856 0 402718720 -0.8426833749 -0.0508395806 -0.6705117822 888 35.4800000000 0.0128117399 0.0087980064 0.0278014094 0.0082171471 0.0236270000 393494808 0 402718720 -0.8345810771 -0.0541391261 -0.6765410304 889 35.5200000000 0.0136467116 0.0088034605 0.0278014094 0.0082170396 0.0350880000 393495620 0 402718720 -0.8310805559 -0.0586586818 -0.6815508604 890 35.5600000000 0.0146395564 0.0088100179 0.0278014094 0.0082258069 0.0232330000 393499492 0 402718720 -0.8295326233 -0.0609778278 -0.6938080788 891 35.6000000000 0.0163844526 0.0088185189 0.0278014094 0.0082667992 0.0342490000 393499200 0 402718720 -0.8183088303 -0.0493429899 -0.7014455199 892 35.6400000000 0.0167778023 0.0088274419 0.0278014094 0.0082716513 0.0227780000 393502100 0 402718720 -0.8184669614 -0.0566467866 -0.7083154917 893 35.6800000000 0.0206374973 0.0088406671 0.0278014094 0.0082823193 0.0230010000 393506720 0 402718720 -0.8079652786 -0.0491892621 -0.7128931880 894 35.7200000000 0.0205137152 0.0088537242 0.0278014094 0.0082787377 0.0227960000 393507184 0 402718720 -0.7997444272 -0.0508872755 -0.7162818909 895 35.7600000000 0.0232241657 0.0088697805 0.0278014094 0.0082784960 0.0224650000 393507752 0 402718720 -0.7930760384 -0.0508063845 -0.7221509814 896 35.8000000000 0.0192116871 0.0088813228 0.0278014094 0.0083176564 0.0531900000 393513380 0 402718720 -0.7963796258 -0.0579213239 -0.7405368686 897 35.8400000000 0.0175978169 0.0088910402 0.0278014094 0.0083295246 0.0233550000 393517260 0 402718720 -0.7799784541 -0.0471214838 -0.7463932037 898 35.8800000000 0.0173223075 0.0089004291 0.0278014094 0.0083620426 0.0226060000 393517044 0 402718720 -0.7763442397 -0.0525724143 -0.7553630471 899 35.9200000000 0.0207217578 0.0089135786 0.0278014094 0.0083686266 0.0234060000 393521480 0 402718720 -0.7696696520 -0.0475125201 -0.7598023415 900 35.9600000000 0.0205193646 0.0089264739 0.0278014094 0.0083726383 0.0234830000 393523320 0 402718720 -0.7602362037 -0.0517918766 -0.7653129697 901 36.0000000000 0.0201299395 0.0089389084 0.0278014094 0.0083749685 0.0228210000 393525268 0 402718720 -0.7570462823 -0.0563164651 -0.7726132870 902 36.0400000000 0.0201956593 0.0089513881 0.0278014094 0.0083762935 0.0327460000 393528828 0 402718720 -0.7508797646 -0.0596874170 -0.7825328708 903 36.0800000000 0.0195931327 0.0089631730 0.0278014094 0.0083794230 0.0219560000 393528492 0 402718720 -0.7407857776 -0.0597923361 -0.7902970314 904 36.1200000000 0.0192914940 0.0089745981 0.0278014094 0.0084030710 0.0221760000 393531900 0 402718720 -0.7345280647 -0.0653683469 -0.7898616195 905 36.1600000000 0.0175347961 0.0089840569 0.0278014094 0.0084356084 0.0220440000 393535016 0 402718720 -0.7093313336 -0.0665017292 -0.8177670836 906 36.2000000000 0.0211644173 0.0089975010 0.0278014094 0.0084415239 0.0218650000 393534972 0 402718720 -0.7026162148 -0.0648685843 -0.8233003616 907 36.2400000000 0.0217466019 0.0090115574 0.0278014094 0.0084433830 0.0217800000 393537504 0 402718720 -0.6981856227 -0.0701209232 -0.8295129538 908 36.2800000000 0.0184591711 0.0090219622 0.0278014094 0.0084426227 0.0216050000 393537812 0 402718720 -0.6920664907 -0.0751227885 -0.8350623846 909 36.3200000000 0.0198260508 0.0090338479 0.0278014094 0.0084641100 0.0216400000 393539100 0 402718720 -0.6770399809 -0.0637762994 -0.8386290669 910 36.3600000000 0.0206173658 0.0090465771 0.0278014094 0.0085087777 0.0218110000 393543900 0 402718720 -0.6757665277 -0.0766201615 -0.8389599323 911 36.4000000000 0.0178969260 0.0090562920 0.0278014094 0.0085191726 0.0332830000 393545404 0 402718720 -0.6641203165 -0.0669311807 -0.8471758962 912 36.4400000000 0.0230079498 0.0090715899 0.0278014094 0.0085271389 0.0213110000 393547704 0 402718720 -0.6610536575 -0.0657558888 -0.8488258123 913 36.4800000000 0.0253149401 0.0090893811 0.0278014094 0.0085408081 0.0252020000 394087427 0 402718720 -0.6492810249 -0.0757798851 -0.8423448801 914 36.5200000000 0.0271328595 0.0091091223 0.0278014094 0.0085414950 0.0892440000 396242416 0 402718720 -0.6457735300 -0.0776896477 -0.8455675840 915 36.5600000000 0.0216575265 0.0091228364 0.0278014094 0.0085691312 0.0531820000 396200355 0 402718720 -0.6424518228 -0.0744535625 -0.8620717525 916 36.6000000000 0.0175544564 0.0091320412 0.0278014094 0.0085738868 0.0270130000 394109704 0 402718720 -0.6292357445 -0.0719357878 -0.8696322441 917 36.6400000000 0.0220248420 0.0091461010 0.0278014094 0.0085804452 0.0269410000 394111284 0 402718720 -0.6271506548 -0.0734973699 -0.8748118877 918 36.6800000000 0.0245993678 0.0091629346 0.0278014094 0.0085781320 0.0360970000 394114276 0 402718720 -0.6230301261 -0.0771663412 -0.8767926693 919 36.7200000000 0.0239076968 0.0091789790 0.0278014094 0.0085774302 0.0262200000 394116612 0 402718720 -0.6157041192 -0.0761909932 -0.8813105822 920 36.7600000000 0.0219855439 0.0091928992 0.0278014094 0.0085765530 0.0247400000 394118960 0 402718720 -0.6082622409 -0.0751844794 -0.8912793994 921 36.8000000000 0.0207032859 0.0092053969 0.0278014094 0.0085755922 0.0255880000 394124268 0 402718720 -0.5958564281 -0.0747153983 -0.8891504407 922 36.8400000000 0.0231739357 0.0092205471 0.0278014094 0.0085757153 0.0251870000 394125836 0 402718720 -0.5860498548 -0.0747573525 -0.8920211196 923 36.8800000000 0.0224696696 0.0092349015 0.0278014094 0.0085769203 0.0366980000 394129564 0 402718720 -0.5810042024 -0.0806347728 -0.8956436515 924 36.9200000000 0.0215541236 0.0092482340 0.0278014094 0.0085752920 0.0251200000 394130532 0 402718720 -0.5714280605 -0.0867385790 -0.9001306295 925 36.9600000000 0.0210816897 0.0092610270 0.0278014094 0.0085744281 0.0350660000 394131988 0 402718720 -0.5571932793 -0.0804570988 -0.9021453857 926 37.0000000000 0.0203691460 0.0092730228 0.0278014094 0.0085841901 0.0259390000 394138956 0 402718720 -0.5413239002 -0.0815366507 -0.9100407958 927 37.0400000000 0.0227123648 0.0092875204 0.0278014094 0.0085887497 0.0367820000 394141228 0 402718720 -0.5305317044 -0.0766418651 -0.9154441357 928 37.0800000000 0.0212881342 0.0093004521 0.0278014094 0.0085863616 0.0254460000 394145204 0 402718720 -0.5188678503 -0.0797362551 -0.9151709676 929 37.1200000000 0.0194785185 0.0093114081 0.0278014094 0.0085850754 0.0253580000 394148968 0 402718720 -0.5095868707 -0.0848932490 -0.9205024242 930 37.1600000000 0.0216785278 0.0093247061 0.0278014094 0.0085859290 0.0248470000 394149936 0 402718720 -0.5013460517 -0.0835021958 -0.9250778556 931 37.2000000000 0.0205887649 0.0093368049 0.0278014094 0.0085823111 0.0248070000 394153556 0 402718720 -0.4922432601 -0.0877128541 -0.9263482690 932 37.2400000000 0.0221471246 0.0093505499 0.0278014094 0.0085870545 0.0253140000 394156180 0 402718720 -0.4843474627 -0.0850802884 -0.9325503111 933 37.2800000000 0.0198845677 0.0093618404 0.0278014094 0.0085844606 0.0245060000 394156472 0 402718720 -0.4707574248 -0.0831261724 -0.9380777478 934 37.3200000000 0.0208411440 0.0093741309 0.0278014094 0.0085841654 0.0238390000 394160600 0 402718720 -0.4601747394 -0.0827289224 -0.9370923638 935 37.3600000000 0.0193087570 0.0093847561 0.0278014094 0.0085819895 0.0242270000 394162520 0 402718720 -0.4467082024 -0.0805412233 -0.9416170120 936 37.4000000000 0.0224144496 0.0093986767 0.0278014094 0.0085834919 0.0242600000 394164528 0 402718720 -0.4375256002 -0.0790988579 -0.9425129294 937 37.4400000000 0.0200667363 0.0094100621 0.0278014094 0.0085848255 0.0249300000 394171032 0 402718720 -0.4262737632 -0.0854030624 -0.9413777590 938 37.4800000000 0.0211725533 0.0094226021 0.0278014094 0.0085807369 0.0248310000 394173352 0 402718720 -0.4189848304 -0.0870115533 -0.9446692467 939 37.5200000000 0.0214871392 0.0094354503 0.0278014094 0.0085773071 0.0247950000 394174536 0 402718720 -0.4068297744 -0.0859615803 -0.9431129098 940 37.5600000000 0.0225073453 0.0094493566 0.0278014094 0.0085771361 0.0347320000 394175488 0 402718720 -0.3970391750 -0.0822200924 -0.9460790753 941 37.6000000000 0.0218430907 0.0094625274 0.0278014094 0.0085810217 0.0247330000 394179036 0 402718720 -0.3865529597 -0.0816660598 -0.9527388811 942 37.6400000000 0.0218482036 0.0094756757 0.0278014094 0.0085768589 0.0244900000 394181216 0 402718720 -0.3784774840 -0.0860783607 -0.9520827532 943 37.6800000000 0.0181958415 0.0094849230 0.0278014094 0.0085755155 0.0243780000 394183764 0 402718720 -0.3657418191 -0.0901051760 -0.9546738267 944 37.7200000000 0.0197256245 0.0094957712 0.0278014094 0.0085776256 0.0246430000 394187048 0 402718720 -0.3588778377 -0.0902979672 -0.9553586841 945 37.7600000000 0.0198809914 0.0095067608 0.0278014094 0.0085769418 0.0248290000 394191144 0 402718720 -0.3464757800 -0.0903242305 -0.9553399682 946 37.8000000000 0.0220643897 0.0095200353 0.0278014094 0.0085821132 0.0240940000 394191988 0 402718720 -0.3367404938 -0.0887968317 -0.9568225145 947 37.8400000000 0.0210602116 0.0095322213 0.0278014094 0.0085829661 0.0242500000 394196588 0 402718720 -0.3257003427 -0.0911366343 -0.9636898041 948 37.8800000000 0.0252008475 0.0095487494 0.0278014094 0.0085925902 0.0338140000 394200624 0 402718720 -0.3205582500 -0.0919348449 -0.9633102417 949 37.9200000000 0.0230225176 0.0095629472 0.0278014094 0.0085964674 0.0288460000 394691871 0 402718720 -0.3120441437 -0.0982512757 -0.9591750503 950 37.9600000000 0.0243938621 0.0095785587 0.0278014094 0.0086028962 0.0957670000 396724404 0 402718720 -0.3013909459 -0.0953272879 -0.9610170722 951 38.0000000000 0.0208114218 0.0095903704 0.0278014094 0.0086355020 0.0543900000 396615643 0 402718720 -0.2814698815 -0.0930720493 -0.9635282755 952 38.0400000000 0.0184981972 0.0095997273 0.0278014094 0.0086318125 0.0263840000 394772064 0 402718720 -0.2738229334 -0.1009783149 -0.9625427127 953 38.0800000000 0.0205848701 0.0096112542 0.0278014094 0.0086437945 0.0259810000 394770760 0 402718720 -0.2621357143 -0.0963587910 -0.9674300551 954 38.1200000000 0.0190791488 0.0096211786 0.0278014094 0.0086422393 0.0244080000 394771544 0 402718720 -0.2529991269 -0.0994096696 -0.9702426791 955 38.1600000000 0.0189406145 0.0096309372 0.0278014094 0.0086449768 0.0236690000 394775980 0 402718720 -0.2421517521 -0.0979151502 -0.9732196331 956 38.2000000000 0.0203665141 0.0096421669 0.0278014094 0.0086430534 0.0231550000 394776656 0 402718720 -0.2340201735 -0.0993886292 -0.9726195931 957 38.2400000000 0.0175448041 0.0096504246 0.0278014094 0.0086396516 0.0221210000 394779172 0 402718720 -0.2205752730 -0.1008208692 -0.9791212082 958 38.2800000000 0.0201142374 0.0096613472 0.0278014094 0.0086384686 0.0332420000 394779196 0 402718720 -0.2130328268 -0.1004631370 -0.9815093875 959 38.3200000000 0.0206863023 0.0096728435 0.0278014094 0.0086351891 0.0258870000 395211744 0 402718720 -0.2026738822 -0.0979210809 -0.9823870659 960 38.3600000000 0.0196922421 0.0096832804 0.0278014094 0.0086338461 0.0807350000 396065552 0 402718720 -0.1884788573 -0.0943766534 -0.9849433899 961 38.4000000000 0.0207085051 0.0096947530 0.0278014094 0.0086492982 0.0433500000 397560212 0 402718720 -0.1808215678 -0.1005295664 -0.9834470153 962 38.4400000000 0.0208854377 0.0097063857 0.0278014094 0.0086516439 0.0351960000 397231933 0 402718720 -0.1715654731 -0.1030855402 -0.9846001863 963 38.4800000000 0.0204957239 0.0097175896 0.0278014094 0.0086538908 0.0222090000 395324884 0 402718720 -0.1596727669 -0.1057159156 -0.9860579371 964 38.5200000000 0.0215295926 0.0097298427 0.0278014094 0.0086553811 0.0259950000 395701568 0 402718720 -0.1501288712 -0.1069688350 -0.9860304594 965 38.5600000000 0.0219567791 0.0097425131 0.0278014094 0.0086535584 0.0697510000 396718988 0 402718720 -0.1394671351 -0.1089245752 -0.9891431928 966 38.6000000000 0.0191549864 0.0097522569 0.0278014094 0.0086507938 0.0403670000 397785888 0 402718720 -0.1284734458 -0.1130776405 -0.9919711947 967 38.6400000000 0.0204806458 0.0097633514 0.0278014094 0.0086592333 0.0573780000 397459501 0 402718720 -0.1160130054 -0.1113822386 -0.9956594706 968 38.6800000000 0.0306069534 0.0097848841 0.0306069534 0.0086634193 0.0486900000 397881524 0 402718720 -0.1088802591 -0.1065507308 -0.9872974157 969 38.7200000000 0.0172112361 0.0097925480 0.0306069534 0.0086655514 0.0467140000 397776327 0 402718720 -0.0947094262 -0.1204930469 -0.9902510643 970 38.7600000000 0.0259578153 0.0098092132 0.0306069534 0.0086636061 0.0506910000 398275376 0 402718720 -0.0915170610 -0.1256351471 -0.9831082225 971 38.8000000000 0.0206526704 0.0098203805 0.0306069534 0.0086671287 0.0456730000 398172795 0 402718720 -0.0788653344 -0.1209461540 -0.9948751330 972 38.8400000000 0.0253008790 0.0098363070 0.0306069534 0.0086750247 0.0194390000 396262368 0 402718720 -0.0720107928 -0.1251727343 -0.9891814590 973 38.8800000000 0.0295119397 0.0098565286 0.0306069534 0.0086947735 0.0189130000 396262080 0 402718720 -0.0652792677 -0.1273039877 -0.9865996242 974 38.9200000000 0.0103301667 0.0098570149 0.0306069534 0.0087038998 0.0195580000 396269352 0 402718720 -0.0474318676 -0.1347098500 -1.0011607409 975 38.9600000000 0.0197494589 0.0098671610 0.0306069534 0.0087082193 0.0193770000 396270740 0 402718720 -0.0425160900 -0.1289012134 -0.9951046109 976 39.0000000000 0.0230677836 0.0098806862 0.0306069534 0.0087068009 0.0194070000 396271632 0 402718720 -0.0307139009 -0.1223438978 -0.9970579743 977 39.0400000000 0.0287315529 0.0098999808 0.0306069534 0.0087079520 0.0190020000 396272040 0 402718720 -0.0261741206 -0.1309404373 -0.9863713980 978 39.0800000000 0.0300651621 0.0099205996 0.0306069534 0.0087063940 0.0194350000 396275692 0 402718720 -0.0202000942 -0.1342411339 -0.9841696620 979 39.1200000000 0.0148992287 0.0099256850 0.0306069534 0.0087226710 0.0190630000 396278440 0 402718720 -0.0031387843 -0.1349832267 -1.0018661022 980 39.1600000000 0.0279975012 0.0099441257 0.0306069534 0.0087239225 0.0194480000 396280604 0 402718720 0.0003069825 -0.1327460110 -0.9920907617 981 39.2000000000 0.0320233256 0.0099666325 0.0320233256 0.0087234990 0.0191490000 396283452 0 402718720 0.0102601424 -0.1396233290 -0.9856902361 982 39.2400000000 0.0326982178 0.0099897808 0.0326982178 0.0087246961 0.0189070000 396281700 0 402718720 0.0164424144 -0.1495189369 -0.9838815928 983 39.2800000000 0.0257754661 0.0100058394 0.0326982178 0.0087315932 0.0190120000 396286064 0 402718720 0.0269316658 -0.1433335543 -0.9911396503 984 39.3200000000 0.0302331187 0.0100263956 0.0326982178 0.0087280889 0.0193740000 396289660 0 402718720 0.0392348692 -0.1531810910 -0.9864426255 985 39.3600000000 0.0419612266 0.0100588168 0.0419612266 0.0087313925 0.0201850000 396296528 0 402718720 0.0429084003 -0.1503890902 -0.9744608998 986 39.4000000000 0.0418473035 0.0100910566 0.0419612266 0.0087276153 0.0204140000 396302548 0 402718720 0.0515518859 -0.1555994749 -0.9716517925 987 39.4400000000 0.0266705304 0.0101078545 0.0419612266 0.0087431929 0.0332160000 396302360 0 402718720 0.0660102889 -0.1469839215 -0.9845700264 988 39.4800000000 0.0291615631 0.0101271396 0.0419612266 0.0087394039 0.0207770000 396309192 0 402718720 0.0753142461 -0.1517198533 -0.9816268086 989 39.5200000000 0.0327364020 0.0101500003 0.0419612266 0.0087358400 0.0203430000 396307556 0 402718720 0.0831393600 -0.1586922705 -0.9787772894 990 39.5600000000 0.0245433040 0.0101645390 0.0419612266 0.0087371775 0.0203770000 396311200 0 402718720 0.0971524715 -0.1625658870 -0.9875614047 991 39.6000000000 0.0392455719 0.0101938842 0.0419612266 0.0087485742 0.0201160000 396310056 0 402718720 0.1014710963 -0.1506537795 -0.9664507508 992 39.6400000000 0.0369182192 0.0102208240 0.0419612266 0.0087535916 0.0196600000 396310704 0 402718720 0.1101822555 -0.1568125933 -0.9699193835 993 39.6800000000 0.0294919778 0.0102402310 0.0419612266 0.0087529651 0.0201120000 396319316 0 402718720 0.1229771376 -0.1450410932 -0.9699230790 994 39.7200000000 0.0255952608 0.0102556787 0.0419612266 0.0087570586 0.0202860000 396318876 0 402718720 0.1338022053 -0.1476611793 -0.9718190432 995 39.7600000000 0.0285528488 0.0102740678 0.0419612266 0.0087614992 0.0220480000 396525140 0 402718720 0.1402049959 -0.1405842006 -0.9676451683 996 39.8000000000 0.0204725806 0.0102843073 0.0419612266 0.0087614278 0.0699710000 396715408 0 402718720 0.1529047191 -0.1449516565 -0.9724006653 997 39.8400000000 0.0112643838 0.0102852903 0.0419612266 0.0087627153 0.0550620000 399085683 0 402718720 0.1688688993 -0.1396210939 -0.9813923836 998 39.8800000000 0.0227423385 0.0102977723 0.0419612266 0.0087649387 0.0232500000 396718036 0 402718720 0.1746639758 -0.1293408722 -0.9754579067 999 39.9200000000 0.0106409816 0.0102981159 0.0419612266 0.0087718241 0.0220240000 396717644 0 402718720 0.1897466034 -0.1378414482 -0.9808339477 1000 39.9600000000 0.0094307028 0.0102972485 0.0419612266 0.0087713604 0.0221240000 396716324 0 402718720 0.1994791925 -0.1393787116 -0.9795391560 1001 40.0000000000 0.0134829963 0.0103004311 0.0419612266 0.0087695191 0.0226210000 396720732 0 402718720 0.2065389603 -0.1366708279 -0.9754711986 1002 40.0400000000 0.0120857963 0.0103022129 0.0419612266 0.0087655728 0.0271410000 396912208 0 402718720 0.2176450044 -0.1380518377 -0.9707810879 1003 40.0800000000 0.0149470624 0.0103068438 0.0419612266 0.0087647684 0.0713490000 397099404 0 402718720 0.2323128581 -0.1276046187 -0.9709271193 1004 40.1200000000 0.0129409377 0.0103094674 0.0419612266 0.0087784119 0.0565280000 399706324 0 402718720 0.2376405448 -0.1336987168 -0.9706204534 1005 40.1600000000 0.0095630158 0.0103087247 0.0419612266 0.0087787931 0.0489900000 399471533 0 402718720 0.2479420453 -0.1401777118 -0.9706404209 1006 40.2000000000 0.0099559408 0.0103083740 0.0419612266 0.0087758250 0.0220080000 396999960 0 402718720 0.2602489889 -0.1356092840 -0.9701991081 1007 40.2400000000 0.0160542503 0.0103140799 0.0419612266 0.0087858134 0.0225430000 396998772 0 402718720 0.2683738172 -0.1512509286 -0.9618989229 1008 40.2800000000 0.0098019280 0.0103135718 0.0419612266 0.0087867739 0.0351320000 397010448 0 402718720 0.2780623138 -0.1360958666 -0.9637847543 1009 40.3200000000 0.0161748249 0.0103193808 0.0419612266 0.0087898410 0.0221750000 397003692 0 402718720 0.2891477048 -0.1401479542 -0.9688013196 1010 40.3600000000 0.0116812289 0.0103207292 0.0419612266 0.0087963701 0.0237210000 397218948 0 402718720 0.2972304225 -0.1284162104 -0.9549158812 1011 40.4000000000 0.0096846316 0.0103201000 0.0419612266 0.0087955561 0.0833630000 397394320 0 402718720 0.3035227358 -0.1320020556 -0.9498389363 1012 40.4400000000 0.0142757660 0.0103240088 0.0419612266 0.0087923952 0.0717450000 400221392 0 402718720 0.3066427708 -0.1344642937 -0.9413771629 1013 40.4800000000 0.0204044729 0.0103339599 0.0419612266 0.0087893468 0.0375820000 400393596 0 402718720 0.3100920022 -0.1320886910 -0.9341816306 1014 40.5200000000 0.0221631024 0.0103456257 0.0419612266 0.0088200614 0.0757550000 400069013 0 402718720 0.3304356039 -0.1438174993 -0.9594580531 1015 40.5600000000 0.0211136919 0.0103562346 0.0419612266 0.0088185061 0.0771520000 397806160 0 402718720 0.3397929072 -0.1447942555 -0.9577260613 1016 40.6000000000 0.0213582329 0.0103670634 0.0419612266 0.0088144452 0.0512280000 400757099 0 402718720 0.3477058411 -0.1493252516 -0.9560139179 1017 40.6400000000 0.0145899495 0.0103712156 0.0419612266 0.0088246940 0.0410340000 400422765 0 402718720 0.3574139476 -0.1384545267 -0.9459270835 1018 40.6800000000 0.0183515027 0.0103790548 0.0419612266 0.0088255775 0.0242880000 397724372 0 402718720 0.3635153174 -0.1463719457 -0.9461163878 1019 40.7200000000 0.0158948470 0.0103844678 0.0419612266 0.0088230534 0.0233060000 397725748 0 402718720 0.3712475300 -0.1410998404 -0.9398971200 1020 40.7600000000 0.0140664512 0.0103880776 0.0419612266 0.0088196174 0.0242620000 397729032 0 402718720 0.3770462275 -0.1395515203 -0.9330237508 1021 40.8000000000 0.0116328634 0.0103892967 0.0419612266 0.0088180861 0.0241350000 397734820 0 402718720 0.3801590502 -0.1361397952 -0.9208147526 1022 40.8400000000 0.0130415931 0.0103918919 0.0419612266 0.0088162273 0.0360840000 397739480 0 402718720 0.3906207085 -0.1370754540 -0.9201033115 1023 40.8800000000 0.0184213910 0.0103997409 0.0419612266 0.0088149578 0.0243130000 397742844 0 402718720 0.3997084498 -0.1389713734 -0.9214736819 1024 40.9200000000 0.0212633312 0.0104103499 0.0419612266 0.0088115040 0.0246590000 397748432 0 402718720 0.4123312831 -0.1398070157 -0.9200301170 1025 40.9600000000 0.0249148849 0.0104245007 0.0419612266 0.0088132383 0.0248790000 397749452 0 402718720 0.4209110737 -0.1457242966 -0.9165313840 1026 41.0000000000 0.0144840917 0.0104284574 0.0419612266 0.0088175109 0.0238870000 397954228 0 402718720 0.4283731282 -0.1377405375 -0.9017698169 1027 41.0400000000 0.0146155143 0.0104325344 0.0419612266 0.0088145907 0.0258130000 398198508 0 402718720 0.4325090051 -0.1395064592 -0.8995948434 1028 41.0800000000 0.0145891728 0.0104365778 0.0419612266 0.0088163092 0.0859360000 398321320 0 402718720 0.4367356598 -0.1296552122 -0.8844293356 1029 41.1200000000 0.0289049577 0.0104545257 0.0419612266 0.0088440009 0.0719850000 401027904 0 402718720 0.4571388364 -0.1463952214 -0.9031169415 1030 41.1600000000 0.0164130721 0.0104603107 0.0419612266 0.0088667247 0.0385580000 401734704 0 402718720 0.4607680738 -0.1274891496 -0.8843176961 1031 41.2000000000 0.0133831548 0.0104631456 0.0419612266 0.0088760891 0.0450850000 401419989 0 402718720 0.4642553627 -0.1320901215 -0.8753317595 1032 41.2400000000 0.0281704776 0.0104803039 0.0419612266 0.0088855272 0.0263620000 398336960 0 402718720 0.4866445959 -0.1357980222 -0.8897986412 1033 41.2800000000 0.0250831544 0.0104944402 0.0419612266 0.0088883788 0.0247930000 398335000 0 402718720 0.4946504235 -0.1374804527 -0.8813878894 1034 41.3200000000 0.0210222229 0.0105046219 0.0419612266 0.0089002473 0.0248450000 398338764 0 402718720 0.5040239096 -0.1224693283 -0.8657114506 1035 41.3600000000 0.0244124383 0.0105180594 0.0419612266 0.0089306973 0.0262120000 398347096 0 402718720 0.5114403963 -0.1361104250 -0.8711481094 1036 41.4000000000 0.0245269611 0.0105315815 0.0419612266 0.0089290390 0.0254820000 398348544 0 402718720 0.5184692740 -0.1382616311 -0.8679320812 1037 41.4400000000 0.0251340177 0.0105456629 0.0419612266 0.0089258256 0.0260180000 398347788 0 402718720 0.5262954831 -0.1382904798 -0.8653480411 1038 41.4800000000 0.0273570139 0.0105618588 0.0419612266 0.0089227191 0.0259170000 398351692 0 402718720 0.5368220806 -0.1400687844 -0.8616700768 1039 41.5200000000 0.0198730472 0.0105708205 0.0419612266 0.0089380884 0.0366990000 398351604 0 402718720 0.5410652757 -0.1222506389 -0.8437861800 1040 41.5600000000 0.0198886842 0.0105797800 0.0419612266 0.0089382539 0.0250160000 398355568 0 402718720 0.5523707271 -0.1274549663 -0.8438774347 1041 41.6000000000 0.0284303613 0.0105969275 0.0419612266 0.0089400056 0.0253630000 398356832 0 402718720 0.5628414154 -0.1286938488 -0.8513763547 1042 41.6400000000 0.0293926448 0.0106149656 0.0419612266 0.0089485238 0.0250560000 398362868 0 402718720 0.5713365674 -0.1336775720 -0.8472669125 1043 41.6800000000 0.0293030851 0.0106328833 0.0419612266 0.0089532610 0.0285970000 398692576 0 402718720 0.5782318115 -0.1241986454 -0.8410944343 1044 41.7200000000 0.0289162230 0.0106503960 0.0419612266 0.0089992006 0.0847570000 398805320 0 402718720 0.5915827751 -0.1230587140 -0.8358159065 1045 41.7600000000 0.0277232099 0.0106667337 0.0419612266 0.0090144729 0.0760990000 401966672 0 402718720 0.5983083844 -0.1291593611 -0.8318011165 1046 41.8000000000 0.0300726090 0.0106852861 0.0419612266 0.0090150585 0.0511470000 402763419 0 402718720 0.6063674688 -0.1205217019 -0.8255440593 1047 41.8400000000 0.0266382620 0.0107005230 0.0419612266 0.0090127841 0.0555470000 402418933 0 402718720 0.6129049659 -0.1222351566 -0.8197299242 1048 41.8800000000 0.0282090828 0.0107172296 0.0419612266 0.0090220152 0.0277070000 398819528 0 402718720 0.6184773445 -0.1320513934 -0.8165224195 1049 41.9200000000 0.0213662218 0.0107273812 0.0419612266 0.0090260453 0.0276790000 398822828 0 402718720 0.6241706610 -0.1209044009 -0.8042496443 1050 41.9600000000 0.0245014243 0.0107404993 0.0419612266 0.0090228143 0.0267460000 398822004 0 402718720 0.6322851181 -0.1170802116 -0.8028553128 1051 42.0000000000 0.0226495620 0.0107518305 0.0419612266 0.0090232123 0.0263540000 398821828 0 402718720 0.6383222342 -0.1250775754 -0.8003899455 1052 42.0400000000 0.0250254218 0.0107653985 0.0419612266 0.0090207711 0.0256630000 398817892 0 402718720 0.6464629769 -0.1257642359 -0.7968630195 1053 42.0800000000 0.0273747742 0.0107811719 0.0419612266 0.0090172587 0.0250810000 398822936 0 402718720 0.6555317044 -0.1194219515 -0.7937722802 1054 42.1200000000 0.0250103548 0.0107946721 0.0419612266 0.0090145435 0.0286120000 399281616 0 402718720 0.6600392461 -0.1186159551 -0.7867065668 1055 42.1600000000 0.0249275323 0.0108080682 0.0419612266 0.0090124463 0.0896280000 399396344 0 402718720 0.6704829335 -0.1175091118 -0.7789201140 1056 42.2000000000 0.0249622837 0.0108214718 0.0419612266 0.0090099694 0.0789840000 399399080 0 402718720 0.6754897833 -0.1223298684 -0.7757694721 1057 42.2400000000 0.0311654992 0.0108407187 0.0419612266 0.0090079933 0.0682100000 403940236 0 402718720 0.6878301501 -0.1266409159 -0.7744437456 1058 42.2800000000 0.0300875809 0.0108589105 0.0419612266 0.0090054571 0.0494960000 404086971 0 402718720 0.6938021779 -0.1222502440 -0.7658382058 1059 42.3200000000 0.0158594362 0.0108636324 0.0419612266 0.0090128985 0.0703650000 403941979 0 402718720 0.6845983863 -0.1187811941 -0.7492313385 1060 42.3600000000 0.0199170820 0.0108721734 0.0419612266 0.0090103865 0.0280250000 399732484 0 402718720 0.6935573816 -0.1183737442 -0.7475183606 1061 42.4000000000 0.0201109666 0.0108808810 0.0419612266 0.0090070789 0.0733100000 399820708 0 402718720 0.6992110610 -0.1137719452 -0.7417154312 1062 42.4400000000 0.0219345577 0.0108912894 0.0419612266 0.0090094467 0.0642020000 399839964 0 402718720 0.7031313777 -0.1188261062 -0.7379907966 1063 42.4800000000 0.0180692114 0.0108980419 0.0419612266 0.0090136676 0.0502780000 404790336 0 402718720 0.7043474913 -0.1189729944 -0.7281319499 1064 42.5200000000 0.0216669999 0.0109081631 0.0419612266 0.0090115306 0.0422830000 404746052 0 402718720 0.7143525481 -0.1119456366 -0.7253069282 1065 42.5600000000 0.0179773606 0.0109148009 0.0419612266 0.0090120933 0.0660760000 404669279 0 402718720 0.7138341665 -0.1076800823 -0.7158364058 1066 42.6000000000 0.0161323044 0.0109196953 0.0419612266 0.0090112372 0.0252320000 399838244 0 402718720 0.7150861621 -0.1077020988 -0.7081784606 1067 42.6400000000 0.0188671313 0.0109271437 0.0419612266 0.0090084000 0.0249770000 399845428 0 402718720 0.7234518528 -0.1026807129 -0.7042949796 1068 42.6800000000 0.0240847915 0.0109394636 0.0419612266 0.0090042860 0.0286360000 400221272 0 402718720 0.7320419550 -0.0983621627 -0.7019400597 1069 42.7200000000 0.0196267124 0.0109475901 0.0419612266 0.0090093891 0.0788120000 400337988 0 402718720 0.7339242101 -0.0978020877 -0.6926006079 1070 42.7600000000 0.0191394594 0.0109552461 0.0419612266 0.0090152302 0.0730840000 400513720 0 402718720 0.7390057445 -0.0932860821 -0.6847217083 1071 42.8000000000 0.0181206204 0.0109619364 0.0419612266 0.0090243700 0.0684900000 404356592 0 402718720 0.7427721024 -0.0942851231 -0.6770091057 1072 42.8400000000 0.0187902376 0.0109692390 0.0419612266 0.0090206251 0.0567180000 405719117 0 402718720 0.7468956709 -0.0887894481 -0.6698741317 1073 42.8800000000 0.0188136846 0.0109765497 0.0419612266 0.0090191392 0.0310650000 405741908 0 402718720 0.7502815723 -0.0909798443 -0.6637833118 1074 42.9200000000 0.0135120191 0.0109789105 0.0419612266 0.0090205043 0.0567620000 404300965 0 402718720 0.7509596348 -0.0868154243 -0.6497766376 1075 42.9600000000 0.0107215922 0.0109786711 0.0419612266 0.0090211686 0.0686010000 400575648 0 402718720 0.7656040192 -0.0916311592 -0.6382713914 1076 43.0000000000 0.0104329605 0.0109781640 0.0419612266 0.0090213760 0.0480760000 400575044 0 402718720 0.7683218718 -0.0828077868 -0.6308541298 1077 43.0400000000 0.0097969417 0.0109770672 0.0419612266 0.0090221254 0.0453800000 400554320 0 402718720 0.7745218277 -0.0839712098 -0.6257606149 1078 43.0800000000 0.0126786595 0.0109786457 0.0419612266 0.0090200405 0.0780860000 402686821 0 402718720 0.7800476551 -0.0806160346 -0.6215379834 1079 43.1200000000 0.0196472947 0.0109866796 0.0419612266 0.0090174998 0.0469970000 401599168 0 402718720 0.7892841697 -0.0798533633 -0.6209389567 1080 43.1600000000 0.0150858425 0.0109904751 0.0419612266 0.0090152154 0.1097580000 404654840 0 402718720 0.7913663387 -0.0785914734 -0.6084811687 1081 43.2000000000 0.0095612612 0.0109891530 0.0419612266 0.0090167507 0.0912490000 412373812 0 402718720 0.7898060679 -0.0768705308 -0.5980141163 1082 43.2400000000 0.0140395481 0.0109919722 0.0419612266 0.0090137542 0.0836690000 416857392 0 402718720 0.7962511182 -0.0731919482 -0.5924930573 1083 43.2800000000 0.0124591310 0.0109933270 0.0419612266 0.0090098206 0.0380700000 422754073 0 402718720 0.7990135550 -0.0720190480 -0.5822550654 1084 43.3200000000 0.0155895343 0.0109975670 0.0419612266 0.0090060084 0.0327080000 420152497 0 402718720 0.8077992797 -0.0728056580 -0.5744867325 1085 43.3600000000 0.0150136780 0.0110012685 0.0419612266 0.0090042187 0.0840220000 420390911 0 402718720 0.8083428741 -0.0629504621 -0.5662043095 1086 43.4000000000 0.0096485931 0.0110000229 0.0419612266 0.0090012547 0.0935220000 411465229 0 402718720 0.8076447845 -0.0629509091 -0.5562942624 1087 43.4400000000 0.0129536092 0.0110018202 0.0419612266 0.0090021957 0.0318730000 400765692 0 402718720 0.8139392734 -0.0690558106 -0.5543518066 1088 43.4800000000 0.0104340566 0.0110012983 0.0419612266 0.0089981133 0.0303420000 400771156 0 402718720 0.8128619790 -0.0686253235 -0.5473647118 1089 43.5200000000 0.0134255979 0.0110035245 0.0419612266 0.0089942852 0.0417760000 400770988 0 402718720 0.8194237351 -0.0659407303 -0.5419276357 1090 43.5600000000 0.0099974601 0.0110026015 0.0419612266 0.0089917366 0.0538770000 400770328 0 402718720 0.8195135593 -0.0614658892 -0.5299643874 1091 43.6000000000 0.0080924360 0.0109999341 0.0419612266 0.0089902853 0.0423030000 400782728 0 402718720 0.8230094910 -0.0630902052 -0.5202271342 1092 43.6400000000 0.0095393350 0.0109985965 0.0419612266 0.0089876354 0.0346100000 401229340 0 402718720 0.8267731071 -0.0576794818 -0.5125563741 1093 43.6800000000 0.0120982705 0.0109996026 0.0419612266 0.0089868606 0.0997110000 401274508 0 402718720 0.8327137232 -0.0608164966 -0.5052860379 1094 43.7200000000 0.0115981726 0.0110001498 0.0419612266 0.0089855671 0.1013430000 401275372 0 402718720 0.8325498700 -0.0551202670 -0.4985389709 1095 43.7600000000 0.0111749861 0.0110003094 0.0419612266 0.0089826324 0.0952670000 401514596 0 402718720 0.8322646022 -0.0528431125 -0.4914722145 1096 43.8000000000 0.0120530790 0.0110012700 0.0419612266 0.0089800727 0.0904770000 417730928 0 402718720 0.8345494270 -0.0559671260 -0.4853831232 1097 43.8400000000 0.0119434139 0.0110021288 0.0419612266 0.0089767497 0.0451990000 422807209 0 402718720 0.8375138044 -0.0508478284 -0.4747975469 1098 43.8800000000 0.0102160219 0.0110014129 0.0419612266 0.0089838331 0.0425700000 421552565 0 402718720 0.8396973610 -0.0500980616 -0.4629353583 1099 43.9200000000 0.0108386073 0.0110012647 0.0419612266 0.0089872404 0.1061550000 421842299 0 402718720 0.8421180248 -0.0515717976 -0.4552202225 1100 43.9600000000 0.0084215552 0.0109989196 0.0419612266 0.0089853528 0.0372980000 422753957 0 402718720 0.8405614495 -0.0473523736 -0.4466887712 1101 44.0000000000 0.0110658789 0.0109989804 0.0419612266 0.0089816393 0.0354000000 421178288 0 402718720 0.8447721601 -0.0448505878 -0.4410872757 1102 44.0400000000 0.0111464392 0.0109991142 0.0419612266 0.0089778904 0.1465820000 421338247 0 402718720 0.8471068144 -0.0429708585 -0.4312246144 1103 44.0800000000 0.0117388433 0.0109997848 0.0419612266 0.0089739327 0.1010060000 401277776 0 402718720 0.8490806818 -0.0424061753 -0.4228400588 1104 44.1200000000 0.0123411585 0.0110009998 0.0419612266 0.0089698792 0.0604780000 401288844 0 402718720 0.8508969545 -0.0422670245 -0.4124971330 1105 44.1600000000 0.0139832534 0.0110036987 0.0419612266 0.0089659591 0.0345480000 401291988 0 402718720 0.8550907373 -0.0397053435 -0.4017840624 1106 44.2000000000 0.0085262433 0.0110014587 0.0419612266 0.0089649569 0.0321540000 401299048 0 402718720 0.8527470231 -0.0431891307 -0.3894252181 1107 44.2400000000 0.0124246348 0.0110027443 0.0419612266 0.0089617920 0.0458780000 401304912 0 402718720 0.8610548377 -0.0389206447 -0.3779270351 1108 44.2800000000 0.0055457321 0.0109978192 0.0419612266 0.0089645899 0.0319660000 401303132 0 402718720 0.8567845225 -0.0428249128 -0.3663752675 1109 44.3200000000 0.0082963267 0.0109953832 0.0419612266 0.0089607363 0.0325540000 401308300 0 402718720 0.8618909121 -0.0393621549 -0.3566857576 1110 44.3600000000 0.0098893810 0.0109943868 0.0419612266 0.0089567649 0.0318460000 401308224 0 402718720 0.8654667735 -0.0358693078 -0.3469607234 1111 44.4000000000 0.0057940148 0.0109897060 0.0419612266 0.0089564952 0.0458520000 401314652 0 402718720 0.8638886213 -0.0377164632 -0.3360304236 1112 44.4400000000 0.0085387882 0.0109875020 0.0419612266 0.0089526541 0.0331030000 401317536 0 402718720 0.8708188534 -0.0343541056 -0.3246828616 1113 44.4800000000 0.0067169159 0.0109836650 0.0419612266 0.0089523140 0.0437460000 401317168 0 402718720 0.8747029901 -0.0334319249 -0.3109603524 1114 44.5200000000 0.0041537890 0.0109775340 0.0419612266 0.0089518641 0.0341110000 401318184 0 402718720 0.8730279207 -0.0326169431 -0.3014743328 1115 44.5600000000 0.0097857993 0.0109764652 0.0419612266 0.0089485743 0.0441990000 401323628 0 402718720 0.8821594715 -0.0326667130 -0.2946300507 1116 44.6000000000 0.0091984868 0.0109748720 0.0419612266 0.0089447941 0.0332790000 401323120 0 402718720 0.8877102137 -0.0297258496 -0.2807103395 1117 44.6400000000 0.0060430393 0.0109704568 0.0419612266 0.0089409948 0.0361890000 401790908 0 402718720 0.8853026628 -0.0277127102 -0.2703148425 1118 44.6800000000 0.0042516207 0.0109644471 0.0419612266 0.0089370249 0.1170250000 401917884 0 402718720 0.8859583735 -0.0286794640 -0.2607315779 1119 44.7200000000 0.0074068811 0.0109612679 0.0419612266 0.0089341734 0.1285760000 401919356 0 402718720 0.8931308985 -0.0263805091 -0.2513170838 1120 44.7600000000 0.0109761041 0.0109612811 0.0419612266 0.0089314729 0.1117480000 402189448 0 402718720 0.8986561894 -0.0259265900 -0.2425233424 1121 44.8000000000 0.0103234909 0.0109607122 0.0419612266 0.0089275276 0.1169990000 412024960 0 402718720 0.9017480016 -0.0234783702 -0.2314416170 1122 44.8400000000 0.0084492555 0.0109584738 0.0419612266 0.0089241498 0.1043180000 418626220 0 402718720 0.9033132792 -0.0233579651 -0.2201976925 1123 44.8800000000 0.0100203343 0.0109576384 0.0419612266 0.0089203526 0.0466460000 423664217 0 402718720 0.9074538946 -0.0184491929 -0.2109975517 1124 44.9200000000 0.0091227572 0.0109560059 0.0419612266 0.0089175972 0.0799700000 422353065 0 402718720 0.9115629196 -0.0175603610 -0.1988375783 1125 44.9600000000 0.0083600851 0.0109536985 0.0419612266 0.0089139872 0.0677100000 423552457 0 402718720 0.9139823318 -0.0152466083 -0.1876535565 1126 45.0000000000 0.0087507982 0.0109517421 0.0419612266 0.0089108373 0.0366830000 421997948 0 402718720 0.9155653715 -0.0121692726 -0.1793472022 1127 45.0400000000 0.0062358971 0.0109475576 0.0419612266 0.0089072980 0.0402210000 422240464 0 402718720 0.9154930115 -0.0158818737 -0.1689398736 1128 45.0800000000 0.0036740005 0.0109411094 0.0419612266 0.0089041845 0.1651470000 422166023 0 402718720 0.9162384272 -0.0104866838 -0.1583109051 1129 45.1200000000 0.0074480739 0.0109380155 0.0419612266 0.0089015097 0.1154220000 401915324 0 402718720 0.9237094522 -0.0062767984 -0.1473327428 1130 45.1600000000 0.0030762861 0.0109310582 0.0419612266 0.0088999336 0.0334900000 401939216 0 402718720 0.9201537967 -0.0095715653 -0.1401597857 1131 45.2000000000 0.0049849851 0.0109258009 0.0419612266 0.0088960525 0.0347170000 401940168 0 402718720 0.9238408804 -0.0082596084 -0.1342931986 1132 45.2400000000 0.0045633558 0.0109201804 0.0419612266 0.0088922489 0.0352960000 401944292 0 402718720 0.9268863201 -0.0104350075 -0.1267230362 1133 45.2800000000 0.0061642048 0.0109159827 0.0419612266 0.0088903718 0.0342650000 401946948 0 402718720 0.9276519418 -0.0057790354 -0.1171832830 1134 45.3200000000 0.0064487690 0.0109120433 0.0419612266 0.0088890630 0.0337050000 401947500 0 402718720 0.9346117973 -0.0127377659 -0.1093573421 1135 45.3600000000 0.0067058108 0.0109083374 0.0419612266 0.0088865775 0.0340550000 401952224 0 402718720 0.9386743307 -0.0109801954 -0.1020613760 1136 45.4000000000 0.0052605271 0.0109033657 0.0419612266 0.0088848729 0.0344760000 401949252 0 402718720 0.9381702542 -0.0015557036 -0.0914053470 1137 45.4400000000 0.0045330254 0.0108977630 0.0419612266 0.0088809918 0.0350690000 401953748 0 402718720 0.9400926828 0.0002935920 -0.0830416977 1138 45.4800000000 0.0077118338 0.0108949634 0.0419612266 0.0088772111 0.0351400000 401956264 0 402718720 0.9448709488 0.0040577296 -0.0768245608 1139 45.5200000000 0.0025782613 0.0108876616 0.0419612266 0.0088745412 0.0352260000 401958552 0 402718720 0.9456201196 0.0017401800 -0.0687402189 1140 45.5600000000 0.0048233150 0.0108823420 0.0419612266 0.0088713228 0.0350620000 401962800 0 402718720 0.9476805329 0.0025055017 -0.0647189617 1141 45.6000000000 0.0067436849 0.0108787148 0.0419612266 0.0088679780 0.0358550000 401967436 0 402718720 0.9499312639 0.0069988947 -0.0583145618 1142 45.6400000000 0.0047387336 0.0108733383 0.0419612266 0.0088661834 0.0342900000 401968048 0 402718720 0.9501305819 0.0030701924 -0.0511887670 1143 45.6800000000 0.0054600690 0.0108686023 0.0419612266 0.0088624684 0.0451640000 401971408 0 402718720 0.9548138380 0.0033448339 -0.0445238650 1144 45.7200000000 0.0062313476 0.0108645487 0.0419612266 0.0088595265 0.0350320000 401975964 0 402718720 0.9589042664 0.0092342179 -0.0378850847 1145 45.7600000000 0.0038207225 0.0108583969 0.0419612266 0.0088562066 0.0348960000 401974568 0 402718720 0.9592322111 0.0080495160 -0.0294722766 1146 45.8000000000 0.0039102300 0.0108523339 0.0419612266 0.0088526384 0.0454050000 401975752 0 402718720 0.9637997746 0.0105042569 -0.0210378915 1147 45.8400000000 0.0028538445 0.0108453605 0.0419612266 0.0088492408 0.0345960000 401980340 0 402718720 0.9641021490 0.0083019231 -0.0141052902 1148 45.8800000000 0.0048897504 0.0108401727 0.0419612266 0.0088463545 0.0435660000 401983240 0 402718720 0.9679453373 0.0138734467 -0.0077126920 1149 45.9200000000 0.0043179686 0.0108344963 0.0419612266 0.0088431719 0.0343120000 401986936 0 402718720 0.9732114077 0.0126808472 0.0019398630 1150 45.9600000000 0.0023112420 0.0108270848 0.0419612266 0.0088405774 0.0333540000 401988224 0 402718720 0.9702228904 0.0121731423 0.0095980763 1151 46.0000000000 0.0027599919 0.0108200760 0.0419612266 0.0088371549 0.0334130000 401991152 0 402718720 0.9754715562 0.0119837448 0.0169837177 1152 46.0400000000 0.0055437903 0.0108154959 0.0419612266 0.0088348596 0.0370270000 402478420 0 402718720 0.9783131480 0.0081837121 0.0242676139 1153 46.0800000000 0.0053230459 0.0108107323 0.0419612266 0.0088320364 0.1281500000 402571320 0 402718720 0.9822551012 0.0104988012 0.0331759453 1154 46.1200000000 0.0044062166 0.0108051824 0.0419612266 0.0088286443 0.1312250000 402575048 0 402718720 0.9799889922 0.0100654587 0.0409137309 1155 46.1600000000 0.0049134716 0.0108000814 0.0419612266 0.0088256154 0.1278020000 402865512 0 402718720 0.9803305268 0.0176236909 0.0514704585 1156 46.2000000000 0.0037437403 0.0107939773 0.0419612266 0.0088223110 0.1247790000 410026016 0 402718720 0.9829416275 0.0177848693 0.0619610995 1157 46.2400000000 0.0039916635 0.0107880980 0.0419612266 0.0088190343 0.1276020000 418777364 0 402718720 0.9846931696 0.0173049923 0.0728114992 1158 46.2800000000 0.0032319506 0.0107815729 0.0419612266 0.0088160705 0.0565280000 424211865 0 402718720 0.9895032048 0.0239078123 0.0940912664 1159 46.3200000000 0.0025411942 0.0107744630 0.0419612266 0.0088128780 0.1113340000 423053352 0 402718720 0.9907979369 0.0281592812 0.1038838327 1160 46.3600000000 0.0028994852 0.0107676742 0.0419612266 0.0088094634 0.0475200000 424237013 0 402718720 0.9912068844 0.0291347150 0.1134454012 1161 46.4000000000 0.0020029913 0.0107601249 0.0419612266 0.0088064344 0.0395630000 422819304 0 402718720 0.9900301099 0.0344041213 0.1239854842 1162 46.4400000000 0.0062226243 0.0107562200 0.0419612266 0.0088040263 0.1683630000 422731343 0 402718720 0.9948847890 0.0402218625 0.1307246387 1163 46.4800000000 0.0024027231 0.0107490373 0.0419612266 0.0088005379 0.1232490000 402527864 0 402718720 0.9946229458 0.0393940806 0.1440526098 1164 46.5200000000 0.0039667012 0.0107432106 0.0419612266 0.0087975089 0.0384970000 402544564 0 402718720 0.9956103563 0.0421070978 0.1516433507 1165 46.5600000000 0.0024345766 0.0107360787 0.0419612266 0.0087945004 0.0349190000 402545040 0 402718720 0.9985124469 0.0471717417 0.1650450826 1166 46.6000000000 0.0029888202 0.0107294344 0.0419612266 0.0087911192 0.0346670000 402549824 0 402718720 0.9971346855 0.0505902283 0.1754488349 1167 46.6400000000 0.0044204234 0.0107240282 0.0419612266 0.0087882813 0.0345840000 402550944 0 402718720 0.9997013807 0.0546240769 0.1855174005 1168 46.6800000000 0.0053468812 0.0107194245 0.0419612266 0.0087846855 0.0349340000 402554364 0 402718720 1.0000368357 0.0562810674 0.1942077130 1169 46.7200000000 0.0039216564 0.0107136094 0.0419612266 0.0087817832 0.0481880000 402556372 0 402718720 0.9972238541 0.0580810159 0.2043511868 1170 46.7600000000 0.0043779546 0.0107081944 0.0419612266 0.0087789593 0.0352360000 402559760 0 402718720 0.9975273609 0.0597639009 0.2126773149 1171 46.8000000000 0.0039314195 0.0107024072 0.0419612266 0.0087768077 0.0377780000 402561784 0 402718720 0.9980264902 0.0640549734 0.2241594046 1172 46.8400000000 0.0032244548 0.0106960267 0.0419612266 0.0087731247 0.0344440000 402563624 0 402718720 0.9951050282 0.0692523122 0.2356272340 1173 46.8800000000 0.0019459297 0.0106885671 0.0419612266 0.0087695164 0.0449590000 402564820 0 402718720 0.9941142797 0.0683172643 0.2459877729 1174 46.9200000000 0.0035218534 0.0106824626 0.0419612266 0.0087663371 0.0370460000 402569052 0 402718720 0.9959874153 0.0704676509 0.2545413375 1175 46.9600000000 0.0030591458 0.0106759746 0.0419612266 0.0087629738 0.0364140000 402571888 0 402718720 0.9960590005 0.0713920295 0.2640026212 1176 47.0000000000 0.0033360168 0.0106697332 0.0419612266 0.0087592681 0.0595210000 402574724 0 402718720 0.9939447641 0.0764261782 0.2831016779 1177 47.0400000000 0.0033515331 0.0106635155 0.0419612266 0.0087557628 0.0351180000 402576244 0 402718720 0.9944328666 0.0800255984 0.2944821119 1178 47.0800000000 0.0049507292 0.0106586659 0.0419612266 0.0087523663 0.0346680000 402577240 0 402718720 0.9967495203 0.0811408088 0.3053143322 1179 47.1200000000 0.0035301596 0.0106526197 0.0419612266 0.0087489886 0.0370980000 402582316 0 402718720 0.9946242571 0.0800253153 0.3131097257 1180 47.1600000000 0.0028185302 0.0106459807 0.0419612266 0.0087492022 0.0363440000 402583036 0 402718720 0.9964544773 0.0802340060 0.3212228417 1181 47.2000000000 0.0047343373 0.0106409750 0.0419612266 0.0087468133 0.0367800000 402585044 0 402718720 0.9926810265 0.0849937648 0.3314843178 1182 47.2400000000 0.0049659419 0.0106361738 0.0419612266 0.0087433217 0.0350870000 402588908 0 402718720 0.9888561368 0.0814963952 0.3347995877 1183 47.2800000000 0.0043736040 0.0106308800 0.0419612266 0.0087401818 0.0377480000 402592360 0 402718720 0.9857074022 0.0823482573 0.3460434973 1184 47.3200000000 0.0025050335 0.0106240170 0.0419612266 0.0087370615 0.0349900000 402592328 0 402718720 0.9898433089 0.0823099986 0.3595276475 1185 47.3600000000 0.0036715546 0.0106181499 0.0419612266 0.0087350388 0.0378310000 402596360 0 402718720 0.9922255278 0.0812949389 0.3696892262 1186 47.4000000000 0.0044374093 0.0106129385 0.0419612266 0.0087325962 0.0488680000 402597924 0 402718720 0.9940353632 0.0813264921 0.3783165812 1187 47.4400000000 0.0030299469 0.0106065501 0.0419612266 0.0087292157 0.0364180000 402598092 0 402718720 0.9935626984 0.0819646716 0.3894321322 1188 47.4800000000 0.0035656553 0.0106006234 0.0419612266 0.0087259121 0.0372840000 402599932 0 402718720 0.9938798547 0.0807147548 0.3967292607 1189 47.5200000000 0.0048435056 0.0105957815 0.0419612266 0.0087259553 0.0371740000 402602492 0 402718720 0.9936041832 0.0822824091 0.4061388969 1190 47.5600000000 0.0032150245 0.0105895791 0.0419612266 0.0087235979 0.0348080000 402606708 0 402718720 0.9943552017 0.0807891712 0.4164743423 1191 47.6000000000 0.0067185466 0.0105863289 0.0419612266 0.0087206187 0.0617780000 402609376 0 402718720 0.9985119104 0.0832410306 0.4268937707 1192 47.6400000000 0.0039466713 0.0105807587 0.0419612266 0.0087173643 0.0366110000 402610220 0 402718720 1.0016962290 0.0804613903 0.4377176762 1193 47.6800000000 0.0025338794 0.0105740136 0.0419612266 0.0087139011 0.0361860000 402614436 0 402718720 1.0039809942 0.0793766454 0.4488067627 1194 47.7200000000 0.0051369239 0.0105694600 0.0419612266 0.0087104188 0.0341610000 402614880 0 402718720 1.0060281754 0.0795043111 0.4572440684 1195 47.7600000000 0.0054805065 0.0105652014 0.0419612266 0.0087069095 0.0462420000 402614404 0 402718720 1.0065224171 0.0813592747 0.4678286612 1196 47.8000000000 0.0058109481 0.0105612263 0.0419612266 0.0087041893 0.0344250000 402618620 0 402718720 1.0131173134 0.0829008073 0.4796601534 1197 47.8400000000 0.0039439993 0.0105556981 0.0419612266 0.0087010050 0.0467380000 402619340 0 402718720 1.0164337158 0.0811273456 0.4904963374 1198 47.8800000000 0.0034263853 0.0105497471 0.0419612266 0.0086977961 0.0355890000 402623756 0 402718720 1.0174305439 0.0827404633 0.5022878647 1199 47.9200000000 0.0026176623 0.0105431315 0.0419612266 0.0086953702 0.0464180000 402626516 0 402718720 1.0193977356 0.0813068524 0.5122007132 1200 47.9600000000 0.0023105119 0.0105362710 0.0419612266 0.0086921206 0.0346960000 402629996 0 402718720 1.0200200081 0.0783139691 0.5199311376 1201 48.0000000000 0.0044808020 0.0105312290 0.0419612266 0.0086931991 0.0356770000 402632740 0 402718720 1.0270651579 0.0819137245 0.5315712690 1202 48.0400000000 0.0046187928 0.0105263102 0.0419612266 0.0086918427 0.0351890000 402631344 0 402718720 1.0303939581 0.0857445672 0.5462002158 1203 48.0800000000 0.0023285840 0.0105194958 0.0419612266 0.0086887903 0.0355390000 402634548 0 402718720 1.0318338871 0.0837560222 0.5560598373 1204 48.1200000000 0.0029454830 0.0105132051 0.0419612266 0.0086923696 0.0348610000 402635728 0 402718720 1.0364079475 0.0834480077 0.5658380985 1205 48.1600000000 0.0030965868 0.0105070502 0.0419612266 0.0086894568 0.0352510000 402639392 0 402718720 1.0387599468 0.0867358074 0.5776960850 1206 48.2000000000 0.0030246130 0.0105008458 0.0419612266 0.0086858673 0.0351400000 402640680 0 402718720 1.0408352613 0.0879874527 0.5886442661 1207 48.2400000000 0.0030777154 0.0104946958 0.0419612266 0.0086824020 0.0337720000 402642412 0 402718720 1.0449208021 0.0859683454 0.5967715979 1208 48.2800000000 0.0046295933 0.0104898406 0.0419612266 0.0086795946 0.0343070000 402647640 0 402718720 1.0485066175 0.0894012600 0.6078495979 1209 48.3200000000 0.0042588282 0.0104846867 0.0419612266 0.0086764931 0.0341450000 402650844 0 402718720 1.0516788960 0.0910586044 0.6186908484 1210 48.3600000000 0.0048914626 0.0104800642 0.0419612266 0.0086730954 0.0604000000 402652668 0 402718720 1.0515040159 0.0917979926 0.6269214153 1211 48.4000000000 0.0052867429 0.0104757757 0.0419612266 0.0086697642 0.0333710000 402652652 0 402718720 1.0540500879 0.0926640630 0.6373773813 1212 48.4400000000 0.0031685319 0.0104697467 0.0419612266 0.0086677489 0.0379470000 403192180 0 402718720 1.0584602356 0.0934581608 0.6573662758 1213 48.4800000000 0.0030549306 0.0104636339 0.0419612266 0.0086665195 0.1268460000 403275584 0 402718720 1.0581444502 0.0939822048 0.6650214791 1214 48.5200000000 0.0049464251 0.0104590892 0.0419612266 0.0086649793 0.1248760000 403274796 0 402718720 1.0584977865 0.0968163759 0.6734923124 1215 48.5600000000 0.0037367216 0.0104535564 0.0419612266 0.0086629969 0.1220450000 403589556 0 402718720 1.0582480431 0.0949628800 0.6808120608 1216 48.6000000000 0.0038957568 0.0104481635 0.0419612266 0.0086656847 0.1173210000 412069468 0 402718720 1.0576571226 0.0980142355 0.6962804794 1217 48.6400000000 0.0045949398 0.0104433539 0.0419612266 0.0086622101 0.1205140000 419092409 0 402718720 1.0581793785 0.1002644300 0.7045585513 1218 48.6800000000 0.0043701148 0.0104383677 0.0419612266 0.0086596590 0.0543670000 424766381 0 402718720 1.0605088472 0.1006730571 0.7121571898 1219 48.7200000000 0.0049476437 0.0104338634 0.0419612266 0.0086570751 0.0824150000 423861618 0 402718720 1.0631465912 0.0995623097 0.7183544636 1220 48.7600000000 0.0047323564 0.0104291900 0.0419612266 0.0086571383 0.0824180000 424824333 0 402718720 1.0570782423 0.1014607325 0.7263145447 1221 48.8000000000 0.0043166513 0.0104241839 0.0419612266 0.0086543085 0.0396060000 423237049 0 402718720 1.0586730242 0.1024165899 0.7331596017 1222 48.8400000000 0.0050897086 0.0104198185 0.0419612266 0.0086517117 0.0421470000 423380816 0 402718720 1.0559802055 0.1060629413 0.7409806252 1223 48.8800000000 0.0058472194 0.0104160797 0.0419612266 0.0086488287 0.1635120000 423309179 0 402718720 1.0526138544 0.1049930453 0.7485518456 1224 48.9200000000 0.0035310537 0.0104104546 0.0419612266 0.0086454998 0.1262860000 403277904 0 402718720 1.0560522079 0.1031813473 0.7556895018 1225 48.9600000000 0.0065401471 0.0104072952 0.0419612266 0.0086458512 0.0425680000 403292116 0 402718720 1.0503323078 0.1028566062 0.7636228204 1226 49.0000000000 0.0050204294 0.0104029013 0.0419612266 0.0086431260 0.0357950000 403294508 0 402718720 1.0515360832 0.1056247354 0.7719564438 1227 49.0400000000 0.0038995864 0.0103976012 0.0419612266 0.0086399582 0.0484760000 403296792 0 402718720 1.0519027710 0.1066363379 0.7809470892 1228 49.0800000000 0.0040765558 0.0103924537 0.0419612266 0.0086373843 0.0471930000 403296992 0 402718720 1.0503493547 0.1066127941 0.7878388762 1229 49.1200000000 0.0057185940 0.0103886508 0.0419612266 0.0086370455 0.0355090000 403301440 0 402718720 1.0442880392 0.1088385284 0.7971426249 1230 49.1600000000 0.0038756859 0.0103833557 0.0419612266 0.0086343827 0.0378450000 403301868 0 402718720 1.0449006557 0.1085638255 0.8069268465 1231 49.2000000000 0.0056315335 0.0103794955 0.0419612266 0.0086321325 0.0352390000 403308140 0 402718720 1.0460392237 0.1125749201 0.8160892725 1232 49.2400000000 0.0057398682 0.0103757296 0.0419612266 0.0086312624 0.0351940000 403308064 0 402718720 1.0414725542 0.1127723828 0.8242441416 1233 49.2800000000 0.0034332769 0.0103700991 0.0419612266 0.0086293810 0.0485740000 403315072 0 402718720 1.0388549566 0.1089119017 0.8304277658 1234 49.3200000000 0.0043839300 0.0103652480 0.0419612266 0.0086269080 0.0392870000 403317280 0 402718720 1.0347692966 0.1118211746 0.8402811885 1235 49.3600000000 0.0033278435 0.0103595497 0.0419612266 0.0086241544 0.0384780000 403319764 0 402718720 1.0327239037 0.1108878031 0.8493021131 1236 49.4000000000 0.0048452490 0.0103550883 0.0419612266 0.0086214671 0.0351190000 403321480 0 402718720 1.0308623314 0.1136486605 0.8580271602 1237 49.4400000000 0.0057401420 0.0103513576 0.0419612266 0.0086181492 0.0380020000 403321740 0 402718720 1.0300639868 0.1151843816 0.8675739765 1238 49.4800000000 0.0054356735 0.0103473869 0.0419612266 0.0086150317 0.0453310000 403326156 0 402718720 1.0314098597 0.1149987057 0.8748760223 1239 49.5200000000 0.0051897741 0.0103432242 0.0419612266 0.0086118127 0.0459270000 403328072 0 402718720 1.0265899897 0.1167652309 0.8837334514 1240 49.5600000000 0.0051273853 0.0103390179 0.0419612266 0.0086084831 0.0376830000 403327964 0 402718720 1.0270129442 0.1193528920 0.8930938244 1241 49.6000000000 0.0043447311 0.0103341877 0.0419612266 0.0086056663 0.0488140000 403331996 0 402718720 1.0235974789 0.1191499978 0.8995215297 1242 49.6400000000 0.0048276898 0.0103297541 0.0419612266 0.0086028929 0.0491210000 403330508 0 402718720 1.0213335752 0.1209754199 0.9072145224 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 10:28:22 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 -nan 0.0250960000 348433052 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644419193 0.0556058511 0.0581123475 0.0606188439 0.0475818031 0.0354360000 358129619 0 402718720 -0.0099586323 -0.0025173116 0.0135069182 3 1305031229.5966169834 0.0737615153 0.0633287368 0.0737615153 0.0541288422 0.0628230000 358812707 0 402718720 0.0084118284 -0.0178096127 -0.0016817056 4 1305031229.6287899017 0.0659968629 0.0639957683 0.0737615153 0.0461383543 0.0836320000 361648651 0 402718720 -0.0021653110 -0.0086757168 0.0068565337 5 1305031229.6646571159 0.0773454532 0.0666657053 0.0773454532 0.0443055257 0.0478570000 361473309 0 402718720 0.0114993537 -0.0286564864 0.0084087066 6 1305031229.6968429089 0.0783183947 0.0686078202 0.0783183947 0.0397542222 0.0993010000 359451671 0 402718720 0.0128723308 -0.0270604882 0.0088662934 7 1305031229.7290771008 0.0737695470 0.0693452097 0.0783183947 0.0369396624 0.0611310000 362087327 0 402718720 0.0001065880 -0.0188368782 0.0108455811 8 1305031229.7648689747 0.0827983543 0.0710268528 0.0827983543 0.0354873609 0.0456620000 361930809 0 402718720 0.0155074932 -0.0261063930 0.0084061781 9 1305031229.7969229221 0.0853163302 0.0726145725 0.0853163302 0.0337810758 0.0967310000 360145907 0 402718720 0.0109501760 -0.0281805508 0.0081933588 10 1305031229.8256299496 0.0878968686 0.0741428021 0.0878968686 0.0320587294 0.0477060000 363031423 0 402718720 0.0117937429 -0.0277567990 0.0065693757 11 1305031229.8630619049 0.0842519626 0.0750618167 0.0878968686 0.0307721541 0.0423190000 362304597 0 402718720 0.0114001296 -0.0250371918 0.0109658726 12 1305031229.8969380856 0.0853124186 0.0759160335 0.0878968686 0.0309766173 0.1071080000 360825335 0 402718720 0.0061810510 -0.0204437114 0.0077151945 13 1305031229.9262549877 0.0869945139 0.0767682243 0.0878968686 0.0301015004 0.0680380000 363997089 0 402718720 0.0121547515 -0.0230284315 0.0106786648 14 1305031229.9662408829 0.0892213434 0.0776577328 0.0892213434 0.0294788092 0.0630340000 364247351 0 402718720 0.0183373988 -0.0254111663 0.0145954881 15 1305031229.9979310036 0.0791571289 0.0777576926 0.0892213434 0.0297589478 0.0323410000 361521151 0 402718720 0.0224180203 -0.0165293794 0.0258600526 16 1305031230.0300021172 0.0829661638 0.0780832220 0.0892213434 0.0288575143 0.1010730000 361589575 0 402718720 0.0251075961 -0.0191797819 0.0268758815 17 1305031230.0656960011 0.0841552392 0.0784403995 0.0892213434 0.0282270745 0.0859830000 363708103 0 402718720 0.0233951770 -0.0183506869 0.0261707846 18 1305031230.0982739925 0.0830033123 0.0786938947 0.0892213434 0.0274882335 0.0436210000 365474563 0 402718720 0.0221094433 -0.0139718754 0.0260604117 19 1305031230.1299350262 0.0816997662 0.0788520984 0.0892213434 0.0267747841 0.0489100000 365138909 0 402718720 0.0218069628 -0.0129603138 0.0299133044 20 1305031230.1657800674 0.0861140415 0.0792151956 0.0892213434 0.0265073797 0.0296400000 361616667 0 402718720 0.0192897506 -0.0149495248 0.0261285007 21 1305031230.1977820396 0.0900633857 0.0797317761 0.0900633857 0.0259160263 0.0288080000 361623695 0 402718720 0.0205171015 -0.0161798075 0.0241812952 22 1305031230.2298529148 0.0904727951 0.0802200042 0.0904727951 0.0255200345 0.0286660000 361630359 0 402718720 0.0205538329 -0.0154471314 0.0269185640 23 1305031230.2655899525 0.0931149423 0.0807806537 0.0931149423 0.0254424377 0.0283360000 361636339 0 402718720 0.0143847289 -0.0158700980 0.0210014246 24 1305031230.2979929447 0.0913228840 0.0812199133 0.0931149423 0.0250764567 0.0276460000 361642295 0 402718720 0.0151254693 -0.0160178412 0.0276390202 25 1305031230.3351120949 0.0886663049 0.0815177689 0.0931149423 0.0249888605 0.0273440000 361648603 0 402718720 0.0048840856 -0.0160467140 0.0248531923 26 1305031230.3656799793 0.0947296619 0.0820259187 0.0947296619 0.0246534507 0.0315420000 362377167 0 402718720 0.0062026279 -0.0155270901 0.0203047972 27 1305031230.3973290920 0.0946464762 0.0824933467 0.0947296619 0.0241948795 0.1070190000 363231267 0 402718720 0.0041052066 -0.0162398983 0.0218487289 28 1305031230.4368140697 0.0945155099 0.0829227097 0.0947296619 0.0244629934 0.0689590000 366247291 0 402718720 0.0004230868 -0.0150667531 0.0223670490 29 1305031230.4653120041 0.0927117169 0.0832602617 0.0947296619 0.0242047491 0.0480480000 365955609 0 402718720 -0.0139261074 -0.0182180684 0.0186034255 30 1305031230.4972999096 0.0928940177 0.0835813869 0.0947296619 0.0238617012 0.0282850000 362449187 0 402718720 -0.0203089155 -0.0190580022 0.0179402512 31 1305031230.5301918983 0.0835626498 0.0835807825 0.0947296619 0.0237859431 0.0270590000 362454371 0 402718720 -0.0294169039 -0.0207419172 0.0280819647 32 1305031230.5661149025 0.0876144543 0.0837068347 0.0947296619 0.0244027220 0.0309690000 363089411 0 402718720 -0.0342520364 -0.0165833477 0.0198822226 33 1305031230.5988430977 0.0814730898 0.0836391455 0.0947296619 0.0241393035 0.0970820000 363247039 0 402718720 -0.0412776917 -0.0151465246 0.0246649627 34 1305031230.6319139004 0.0777807832 0.0834668407 0.0947296619 0.0239491755 0.0587480000 366604243 0 402718720 -0.0457618609 -0.0143738948 0.0284630992 35 1305031230.6660470963 0.0769037455 0.0832793237 0.0947296619 0.0240992106 0.0533390000 366485653 0 402718720 -0.0613660961 -0.0070429733 0.0189254582 36 1305031230.6979451180 0.0733045340 0.0830022462 0.0947296619 0.0238738023 0.0269220000 363169207 0 402718720 -0.0710816160 -0.0033884530 0.0184750725 37 1305031230.7336409092 0.0715664327 0.0826931702 0.0947296619 0.0238304932 0.0293040000 363711595 0 402718720 -0.0764026493 -0.0058612176 0.0203568358 38 1305031230.7659239769 0.0678717345 0.0823031324 0.0947296619 0.0235592209 0.0824710000 363872844 0 402718720 -0.0837025344 -0.0053222119 0.0220037699 39 1305031230.7973229885 0.0654645637 0.0818713742 0.0947296619 0.0233593715 0.0547960000 366901368 0 402718720 -0.0985614210 -0.0055969129 0.0217560865 40 1305031230.8317570686 0.0680145323 0.0815249532 0.0947296619 0.0230600597 0.0276070000 364197684 0 402718720 -0.1034376472 -0.0066142329 0.0175544173 41 1305031230.8655419350 0.0653295219 0.0811299426 0.0947296619 0.0231356436 0.0723480000 364351854 0 402718720 -0.1108177230 -0.0079424102 0.0188029502 42 1305031230.8973939419 0.0635020360 0.0807102306 0.0947296619 0.0231337318 0.0430680000 367036516 0 402718720 -0.1227991208 -0.0040697167 0.0191559140 43 1305031230.9373099804 0.0725070387 0.0805194587 0.0947296619 0.0229263681 0.0403450000 367067525 0 402718720 -0.1342517138 -0.0014691688 0.0091988845 44 1305031230.9650349617 0.0780114830 0.0804624592 0.0947296619 0.0231244998 0.0630490000 365154440 0 402718720 -0.1476893425 0.0031918157 0.0068525793 45 1305031230.9971239567 0.0795767754 0.0804427774 0.0947296619 0.0229099849 0.0667160000 365438888 0 402718720 -0.1484126747 0.0030746404 0.0050315298 46 1305031231.0367500782 0.0805421770 0.0804449382 0.0947296619 0.0227516873 0.0658530000 365673489 0 402718720 -0.1543502361 0.0096286628 0.0063584279 47 1305031231.0644741058 0.0803592801 0.0804431157 0.0947296619 0.0225588063 0.0531740000 367847518 0 402718720 -0.1516556144 0.0088560637 0.0056136390 48 1305031231.0967879295 0.0876007304 0.0805922327 0.0947296619 0.0224250860 0.0491720000 368179253 0 402718720 -0.1490322948 0.0053896252 -0.0024770261 49 1305031231.1347110271 0.0902872607 0.0807900904 0.0947296619 0.0222107848 0.0262360000 365689373 0 402718720 -0.1512798667 0.0101656280 -0.0036650351 50 1305031231.1652760506 0.0960229486 0.0810947476 0.0960229486 0.0220116282 0.0257610000 365628885 0 402718720 -0.1469554305 0.0161839742 -0.0112034408 51 1305031231.1977710724 0.0971851200 0.0814102451 0.0971851200 0.0221042177 0.0363390000 365849464 0 402718720 -0.1480690986 0.0334893987 -0.0090791993 52 1305031231.2344679832 0.0820342079 0.0814222443 0.0971851200 0.0222892184 0.0711000000 366302223 0 402718720 -0.1302678734 0.0264796559 0.0038349796 53 1305031231.2656350136 0.1032182276 0.0818334893 0.1032182276 0.0223781930 0.0789290000 366802623 0 402718720 -0.1180921644 0.0475612357 -0.0148084993 54 1305031231.2978610992 0.1064810306 0.0822899253 0.1064810306 0.0222012380 0.0669830000 367248220 0 402718720 -0.1083312407 0.0561523214 -0.0140552800 55 1305031231.3351519108 0.1054826379 0.0827116109 0.1064810306 0.0222325501 0.0903750000 367753872 0 402718720 -0.0903153718 0.0540222675 -0.0107840179 56 1305031231.3650770187 0.1022841856 0.0830611212 0.1064810306 0.0221069909 0.0904700000 368029296 0 402718720 -0.0830822140 0.0484891385 -0.0063352622 57 1305031231.3973300457 0.1058121249 0.0834602616 0.1064810306 0.0221176063 0.0730710000 368049329 0 402718720 -0.0646525174 0.0382451676 -0.0071454681 58 1305031231.4368579388 0.0933602676 0.0836309514 0.1064810306 0.0223121783 0.0785630000 367878076 0 402718720 -0.0665984452 0.0396062657 0.0068629170 59 1305031231.4649889469 0.0901535600 0.0837415041 0.1064810306 0.0222222557 0.0807810000 371184732 0 402718720 -0.0669633225 0.0342215821 0.0110927913 60 1305031231.4992439747 0.0636963397 0.0834074180 0.1064810306 0.0225840728 0.0452670000 372799629 0 402718720 -0.0835253298 0.0232023727 0.0398411974 61 1305031231.5331959724 0.0526138358 0.0829026052 0.1064810306 0.0224885898 0.0711120000 372633313 0 402718720 -0.0826842040 0.0361101218 0.0520172305 62 1305031231.5650680065 0.0568948016 0.0824831245 0.1064810306 0.0224275103 0.1069150000 368527792 0 402718720 -0.0761562586 0.0361517705 0.0483846106 63 1305031231.6013169289 0.0559424087 0.0820618433 0.1064810306 0.0222612302 0.0950350000 368523116 0 402718720 -0.0730893910 0.0371804088 0.0502245463 64 1305031231.6331589222 0.0566940270 0.0816654711 0.1064810306 0.0222452683 0.0897970000 368833000 0 402718720 -0.0655974895 0.0352743641 0.0504660308 65 1305031231.6650550365 0.0610484444 0.0813482861 0.1064810306 0.0221107797 0.0763980000 374886548 0 402718720 -0.0583133325 0.0323356465 0.0469994098 66 1305031231.7035079002 0.0572579615 0.0809832812 0.1064810306 0.0222801755 0.0492170000 374842521 0 402718720 -0.0569465123 0.0328965336 0.0515249856 67 1305031231.7339379787 0.0572508052 0.0806290651 0.1064810306 0.0223726276 0.0733020000 374647525 0 402718720 -0.0511249565 0.0325427651 0.0521272421 68 1305031231.7655088902 0.0563745163 0.0802723806 0.1064810306 0.0224135448 0.1078070000 369231280 0 402718720 -0.0526177995 0.0391187593 0.0523058288 69 1305031231.8011910915 0.0651512668 0.0800532340 0.1064810306 0.0224426241 0.0910230000 369236192 0 402718720 -0.0468911789 0.0329003148 0.0448614508 70 1305031231.8332920074 0.0668784231 0.0798650224 0.1064810306 0.0226426416 0.0908370000 371490300 0 402718720 -0.0433226191 0.0316018313 0.0438642465 71 1305031231.8649590015 0.0621759035 0.0796158799 0.1064810306 0.0225779799 0.0667500000 376761812 0 402718720 -0.0323784053 0.0266849585 0.0509335212 72 1305031231.9012699127 0.0716844350 0.0795057210 0.1064810306 0.0229188954 0.0612520000 376707581 0 402718720 -0.0324271172 0.0224484131 0.0414764173 73 1305031231.9330461025 0.0618156530 0.0792633913 0.1064810306 0.0228055560 0.0349430000 369870832 0 402718720 -0.0312963463 0.0223328304 0.0515765697 74 1305031231.9650299549 0.0623619109 0.0790349929 0.1064810306 0.0227847670 0.1133470000 369954024 0 402718720 -0.0297548641 0.0234933291 0.0494594909 75 1305031232.0007200241 0.0699269325 0.0789135521 0.1064810306 0.0227829739 0.0931480000 373797256 0 402718720 -0.0293069743 0.0194786265 0.0419182591 76 1305031232.0332028866 0.0667266548 0.0787531982 0.1064810306 0.0229239827 0.0658720000 378216516 0 402718720 -0.0313737169 0.0225744415 0.0426250920 77 1305031232.0651450157 0.0672784820 0.0786041759 0.1064810306 0.0229423780 0.0558770000 378148177 0 402718720 -0.0337027721 0.0268933102 0.0394513160 78 1305031232.1007990837 0.0568629056 0.0783254416 0.1064810306 0.0229158087 0.1033630000 378037763 0 402718720 -0.0263638645 0.0197454263 0.0522566959 79 1305031232.1328380108 0.0672933981 0.0781857955 0.1064810306 0.0231880186 0.0345340000 370628532 0 402718720 0.0002320949 0.0057575852 0.0538669303 80 1305031232.1650519371 0.0681181699 0.0780599502 0.1064810306 0.0231076765 0.1188520000 370693292 0 402718720 0.0018917918 0.0050726798 0.0512780957 81 1305031232.1992239952 0.0759450719 0.0780338406 0.1064810306 0.0229849775 0.0987840000 370697096 0 402718720 0.0084250076 -0.0018976770 0.0474125892 82 1305031232.2364680767 0.0681018457 0.0779127187 0.1064810306 0.0229211344 0.0908230000 374426700 0 402718720 0.0005957466 0.0043279640 0.0463749319 83 1305031232.2626979351 0.0760162249 0.0778898694 0.1064810306 0.0230207473 0.0602560000 378525848 0 402718720 0.0049437787 -0.0028533437 0.0419089645 84 1305031232.2980248928 0.0713479295 0.0778119891 0.1064810306 0.0231248556 0.0480050000 378561953 0 402718720 0.0022314684 0.0023554899 0.0400994793 85 1305031232.3321430683 0.0821707323 0.0778632685 0.1064810306 0.0233322964 0.0907330000 378406083 0 402718720 -0.0134422993 -0.0146368612 0.0354376733 86 1305031232.3647489548 0.1098748893 0.0782354966 0.1098748893 0.0233611816 0.0348380000 371308320 0 402718720 -0.0189746935 -0.0420226343 0.0228229854 87 1305031232.4008779526 0.1063096300 0.0785581878 0.1098748893 0.0232640849 0.1039230000 371372080 0 402718720 -0.0197647028 -0.0370427817 0.0212000962 88 1305031232.4331440926 0.1136041433 0.0789564373 0.1136041433 0.0231359569 0.0934850000 371375688 0 402718720 -0.0242849831 -0.0433737934 0.0161566325 89 1305031232.4647209644 0.1112184301 0.0793189316 0.1136041433 0.0230225564 0.0859930000 373884092 0 402718720 -0.0283596292 -0.0423082933 0.0181121528 90 1305031232.5015261173 0.1115038991 0.0796765423 0.1136041433 0.0229168023 0.0640450000 378252696 0 402718720 -0.0217080377 -0.0416483432 0.0142014809 91 1305031232.5324640274 0.1193976626 0.0801130382 0.1193976626 0.0228068256 0.0479460000 378252332 0 402718720 -0.0243087187 -0.0466570109 0.0066346745 92 1305031232.5647449493 0.1202498451 0.0805493078 0.1202498451 0.0227100016 0.0897380000 378184935 0 402718720 -0.0255201608 -0.0481523313 0.0051359041 93 1305031232.6003499031 0.1246914938 0.0810239550 0.1246914938 0.0225909990 0.0314120000 371389680 0 402718720 -0.0303064194 -0.0502168573 -0.0003063185 94 1305031232.6294269562 0.1306526959 0.0815519203 0.1306526959 0.0225245506 0.0432780000 371392984 0 402718720 -0.0309343841 -0.0533287711 -0.0074024061 95 1305031232.6647078991 0.1229864955 0.0819880737 0.1306526959 0.0224544814 0.0457700000 372011764 0 402718720 -0.0393358171 -0.0485662259 -0.0019514570 96 1305031232.7005090714 0.1226644143 0.0824117856 0.1306526959 0.0223649147 0.1104600000 372080540 0 402718720 -0.0395006165 -0.0462781377 -0.0056272638 97 1305031232.7327980995 0.1300606132 0.0829030106 0.1306526959 0.0222790201 0.0940120000 372083576 0 402718720 -0.0374023914 -0.0523894057 -0.0126129827 98 1305031232.7684600353 0.1310503036 0.0833943095 0.1310503036 0.0222098136 0.0899690000 375287852 0 402718720 -0.0420563146 -0.0556846000 -0.0120850680 99 1305031232.8045380116 0.1281307489 0.0838461928 0.1310503036 0.0221879349 0.0707710000 377646323 0 402718720 -0.0422484353 -0.0546693690 -0.0121985618 100 1305031232.8346450329 0.1282908767 0.0842906396 0.1310503036 0.0220920682 0.0869980000 377449271 0 402718720 -0.0363674462 -0.0573740974 -0.0140333567 101 1305031232.8685569763 0.1284515411 0.0847278763 0.1310503036 0.0220486177 0.0361230000 372708852 0 402718720 -0.0379890874 -0.0614955835 -0.0119754598 102 1305031232.9041829109 0.1170822680 0.0850450762 0.1310503036 0.0220093917 0.1089350000 372797968 0 402718720 -0.0407970324 -0.0522488728 -0.0073181000 103 1305031232.9330000877 0.1161819994 0.0853473764 0.1310503036 0.0219176760 0.0933390000 372799968 0 402718720 -0.0423041098 -0.0492570028 -0.0101198489 104 1305031232.9683640003 0.1148775965 0.0856313208 0.1310503036 0.0218137722 0.0883270000 375263384 0 402718720 -0.0424291603 -0.0465126596 -0.0134918028 105 1305031233.0011510849 0.1048568562 0.0858144212 0.1310503036 0.0217747193 0.0606270000 378948402 0 402718720 -0.0441062376 -0.0364864171 -0.0088516492 106 1305031233.0330219269 0.0959353149 0.0859099013 0.1310503036 0.0217827489 0.0404830000 378858760 0 402718720 -0.0491194129 -0.0198457371 -0.0086591216 107 1305031233.0688428879 0.0909404159 0.0859569154 0.1310503036 0.0217284964 0.0965320000 378791215 0 402718720 -0.0345047489 -0.0071390001 -0.0156557504 108 1305031233.1004469395 0.0866657495 0.0859634787 0.1310503036 0.0216377792 0.1133340000 373492516 0 402718720 -0.0358041413 0.0039016327 -0.0138693852 109 1305031233.1328918934 0.0970003605 0.0860647345 0.1310503036 0.0222052302 0.0929410000 373495948 0 402718720 -0.0302037485 -0.0065594381 -0.0204982497 110 1305031233.1684799194 0.1080572680 0.0862646666 0.1310503036 0.0222534563 0.0900250000 373755708 0 402718720 -0.0301918443 -0.0191422533 -0.0231514089 111 1305031233.2006340027 0.1068544015 0.0864501598 0.1310503036 0.0222107542 0.0881870000 379805400 0 402718720 -0.0264311489 -0.0164041314 -0.0212516524 112 1305031233.2330091000 0.0987263396 0.0865597685 0.1310503036 0.0221691009 0.0631640000 379867375 0 402718720 -0.0284529179 -0.0054707979 -0.0155596957 113 1305031233.2684679031 0.0883941725 0.0865760022 0.1310503036 0.0225711546 0.0998680000 379766335 0 402718720 -0.0356085524 0.0065053725 -0.0052176379 114 1305031233.3003950119 0.0978485942 0.0866748845 0.1310503036 0.0225505846 0.0361260000 374219303 0 402718720 -0.0301628038 0.0140456958 -0.0148643684 115 1305031233.3325300217 0.1001028791 0.0867916497 0.1310503036 0.0226146089 0.1104020000 374283204 0 402718720 -0.0462858342 0.0138376169 -0.0126706129 116 1305031233.3686299324 0.1024369895 0.0869265233 0.1310503036 0.0227204113 0.0948360000 374286548 0 402718720 -0.0564556383 0.0139214853 -0.0104493061 117 1305031233.4008929729 0.0980396941 0.0870215077 0.1310503036 0.0228036114 0.0927600000 374536864 0 402718720 -0.0570823401 0.0028746647 0.0017452165 118 1305031233.4330079556 0.1026604027 0.0871540407 0.1310503036 0.0232134527 0.0823360000 379167680 0 402718720 -0.0428360514 -0.0084086508 0.0052616308 119 1305031233.4687869549 0.0964370519 0.0872320492 0.1310503036 0.0233952486 0.0632210000 381285436 0 402718720 -0.0305782594 -0.0082205106 0.0182669032 120 1305031233.5007359982 0.0954548642 0.0873005727 0.1310503036 0.0233266827 0.0359650000 381119416 0 402718720 -0.0302911252 -0.0057432717 0.0202644989 121 1305031233.5341610909 0.1008582562 0.0874126196 0.1310503036 0.0233885022 0.0972570000 381051911 0 402718720 -0.0312897228 -0.0102634653 0.0192371793 122 1305031233.5697269440 0.1052782461 0.0875590592 0.1310503036 0.0234081168 0.0376670000 375064320 0 402718720 -0.0435216948 -0.0089108739 0.0115733836 123 1305031233.6012749672 0.1144700199 0.0877778475 0.1310503036 0.0234409111 0.1196180000 375038432 0 402718720 -0.0457278416 -0.0159487315 0.0063643809 124 1305031233.6330409050 0.1154606715 0.0880010961 0.1310503036 0.0233859056 0.0988590000 375045024 0 402718720 -0.0449620076 -0.0148467133 0.0054023713 125 1305031233.6717829704 0.1105265468 0.0881812997 0.1310503036 0.0232952807 0.0960020000 375048572 0 402718720 -0.0388235040 -0.0115609039 0.0117957210 126 1305031233.7022960186 0.1020530239 0.0882913927 0.1310503036 0.0234250441 0.0943460000 380101892 0 402718720 -0.0352274328 -0.0086810514 0.0223632120 127 1305031233.7312009335 0.0966651961 0.0883573282 0.1310503036 0.0235269865 0.0788590000 385842757 0 402718720 -0.0232850686 -0.0011786774 0.0300588459 128 1305031233.7691600323 0.0909952596 0.0883779370 0.1310503036 0.0235903763 0.0846230000 385733691 0 402718720 -0.0198195167 0.0016146121 0.0374381244 129 1305031233.7997679710 0.0878057778 0.0883735017 0.1310503036 0.0235181048 0.1132590000 385587279 0 402718720 -0.0259154532 0.0007170957 0.0380976945 130 1305031233.8338310719 0.0995996967 0.0884598570 0.1310503036 0.0235406638 0.0486180000 375734708 0 402718720 -0.0253030341 -0.0090173576 0.0279251356 131 1305031233.8655700684 0.1027638167 0.0885690476 0.1310503036 0.0234918122 0.1272200000 375863657 0 402718720 -0.0264254026 -0.0090201134 0.0228161421 132 1305031233.8986968994 0.1012501568 0.0886651166 0.1310503036 0.0234103498 0.1132300000 375837161 0 402718720 -0.0249054842 -0.0095307417 0.0253047161 133 1305031233.9320030212 0.0996791646 0.0887479290 0.1310503036 0.0233638616 0.1016210000 376074224 0 402718720 -0.0215486996 -0.0116571384 0.0300280992 134 1305031233.9681589603 0.0963462815 0.0888046331 0.1310503036 0.0232964083 0.1002470000 384097246 0 402718720 -0.0184810217 -0.0089435689 0.0324987434 135 1305031233.9989380836 0.0929819793 0.0888355764 0.1310503036 0.0233081855 0.1212190000 386469739 0 402718720 -0.0139467241 -0.0137325861 0.0439521670 136 1305031234.0370678902 0.0917189568 0.0888567777 0.1310503036 0.0232273501 0.0552350000 375788836 0 402718720 -0.0112652415 -0.0084080771 0.0404998101 137 1305031234.0687561035 0.0903303176 0.0888675335 0.1310503036 0.0231492644 0.0360900000 375791884 0 402718720 -0.0103538735 -0.0067488863 0.0400058888 138 1305031234.0997409821 0.0916093662 0.0888874018 0.1310503036 0.0230749666 0.0356920000 375795508 0 402718720 -0.0107438769 -0.0072583985 0.0375517532 139 1305031234.1350688934 0.0904984251 0.0888989919 0.1310503036 0.0230055934 0.0352040000 375799652 0 402718720 -0.0097413771 -0.0073081646 0.0394338593 140 1305031234.1659009457 0.0897726864 0.0889052326 0.1310503036 0.0229630201 0.0356660000 375803016 0 402718720 -0.0094588539 -0.0002649522 0.0345402770 141 1305031234.2010040283 0.0911868736 0.0889214145 0.1310503036 0.0229338555 0.0345060000 375806636 0 402718720 -0.0099568479 -0.0083164945 0.0389404520 142 1305031234.2385749817 0.0864204466 0.0889038020 0.1310503036 0.0228780327 0.0342400000 375810912 0 402718720 -0.0105604902 0.0024771523 0.0363360271 143 1305031234.2655100822 0.0847001374 0.0888744058 0.1310503036 0.0228007752 0.0434420000 375813992 0 402718720 -0.0092093255 0.0049909502 0.0385077856 144 1305031234.3024549484 0.0861287192 0.0888553385 0.1310503036 0.0227274589 0.0340500000 375817392 0 402718720 -0.0114771891 0.0022460865 0.0373513624 145 1305031234.3384580612 0.0863469765 0.0888380394 0.1310503036 0.0226659517 0.0383860000 376413724 0 402718720 -0.0117073907 0.0015735193 0.0379858986 146 1305031234.3661808968 0.0846348479 0.0888092505 0.1310503036 0.0226080581 0.1159870000 376483692 0 402718720 -0.0107574742 0.0061088800 0.0376374274 147 1305031234.4000349045 0.0850984454 0.0887840069 0.1310503036 0.0225330275 0.1013250000 376487612 0 402718720 -0.0100492705 0.0034570256 0.0393821932 148 1305031234.4367709160 0.0848878101 0.0887576812 0.1310503036 0.0224818017 0.0943940000 376491624 0 402718720 -0.0107069118 0.0026389603 0.0385820270 149 1305031234.4676060677 0.0842106566 0.0887271643 0.1310503036 0.0224168270 0.0905390000 381433260 0 402718720 -0.0081377514 0.0044903746 0.0385275409 150 1305031234.4977810383 0.0850188732 0.0887024423 0.1310503036 0.0223429939 0.0804220000 387471332 0 402718720 -0.0072977263 0.0030412208 0.0379316844 151 1305031234.5376710892 0.0839474648 0.0886709524 0.1310503036 0.0224007869 0.0813900000 387538751 0 402718720 -0.0039091157 0.0001369528 0.0402908847 152 1305031234.5690369606 0.0853596181 0.0886491673 0.1310503036 0.0223930196 0.0325400000 387356128 0 402718720 -0.0014609070 0.0034893332 0.0358953327 153 1305031234.5982480049 0.0840456784 0.0886190792 0.1310503036 0.0223439663 0.0848910000 387288915 0 402718720 0.0024530543 0.0063243872 0.0363509022 154 1305031234.6336491108 0.0888297111 0.0886204469 0.1310503036 0.0223328570 0.0469430000 376995244 0 402718720 0.0097901598 -0.0018131435 0.0377706736 155 1305031234.6658589840 0.0885496214 0.0886199900 0.1310503036 0.0222852268 0.0857800000 377058912 0 402718720 0.0106695248 -0.0001097526 0.0358367041 156 1305031234.6987318993 0.0961709544 0.0886683936 0.1310503036 0.0222521090 0.0757640000 377061928 0 402718720 0.0142744128 -0.0021891403 0.0279955752 157 1305031234.7344369888 0.0953519568 0.0887109641 0.1310503036 0.0221905872 0.0712340000 377095324 0 402718720 0.0164065268 -0.0001422209 0.0283183493 158 1305031234.7689719200 0.0974592417 0.0887663329 0.1310503036 0.0221203238 0.0598550000 386502484 0 402718720 0.0197635945 0.0044036061 0.0244270321 159 1305031234.8015530109 0.1032259986 0.0888572742 0.1310503036 0.0221213600 0.0642230000 386571379 0 402718720 0.0183035079 0.0061436440 0.0143703492 160 1305031234.8378078938 0.0943561047 0.0888916419 0.1310503036 0.0220759434 0.0821310000 386448675 0 402718720 0.0138559984 0.0053376919 0.0228421912 161 1305031234.8693211079 0.1009843200 0.0889667517 0.1310503036 0.0220272405 0.0406040000 377409908 0 402718720 0.0178355444 0.0122208390 0.0149312112 162 1305031234.9019980431 0.1039807722 0.0890594308 0.1310503036 0.0219605076 0.0652690000 377629964 0 402718720 0.0196621139 0.0147070000 0.0128751192 163 1305031234.9381608963 0.1025598198 0.0891422553 0.1310503036 0.0219788861 0.0505580000 381969524 0 402718720 0.0171517041 0.0175692998 0.0150174350 164 1305031234.9730799198 0.1002916545 0.0892102394 0.1310503036 0.0219209803 0.0639840000 381814711 0 402718720 0.0152665563 0.0166427009 0.0195387863 165 1305031235.0050830841 0.1019703001 0.0892875731 0.1310503036 0.0219137996 0.0277130000 377780104 0 402718720 0.0147669548 0.0137757137 0.0214540679 166 1305031235.0399720669 0.0977726579 0.0893386881 0.1310503036 0.0218540323 0.0712050000 377851968 0 402718720 0.0108317267 0.0171111505 0.0259572156 167 1305031235.0729401112 0.0946551189 0.0893705230 0.1310503036 0.0218124536 0.0566440000 383646288 0 402718720 0.0047743958 0.0251965486 0.0274671447 168 1305031235.0995910168 0.0887767076 0.0893669884 0.1310503036 0.0217678776 0.0415760000 383615949 0 402718720 0.0018405537 0.0282199513 0.0339361355 169 1305031235.1362709999 0.0938022956 0.0893932328 0.1310503036 0.0217518416 0.0713930000 383528743 0 402718720 0.0069399499 0.0156098558 0.0369151011 170 1305031235.1663711071 0.0846368149 0.0893652539 0.1310503036 0.0217571912 0.0276660000 377866752 0 402718720 -0.0034478088 0.0365914963 0.0402325541 171 1305031235.1998469830 0.0828815028 0.0893273372 0.1310503036 0.0217257972 0.0307150000 378244040 0 402718720 -0.0000738520 0.0323105492 0.0466741920 172 1305031235.2375700474 0.0841417611 0.0892971885 0.1310503036 0.0217559235 0.0849650000 378328316 0 402718720 -0.0031407950 0.0341225527 0.0455332845 173 1305031235.2690389156 0.0822683871 0.0892565596 0.1310503036 0.0216961528 0.0825500000 378331572 0 402718720 -0.0028216457 0.0338294357 0.0497627966 174 1305031235.3064870834 0.0769408867 0.0891857799 0.1310503036 0.0217770995 0.0805460000 383533712 0 402718720 -0.0122273825 0.0405991375 0.0535244197 175 1305031235.3380000591 0.0729150549 0.0890928043 0.1310503036 0.0217363716 0.0538800000 387409784 0 402718720 -0.0170926172 0.0445729569 0.0582030118 176 1305031235.3698880672 0.0769567862 0.0890238497 0.1310503036 0.0217441162 0.0528390000 387422509 0 402718720 -0.0150577752 0.0333651826 0.0592558272 177 1305031235.4060161114 0.0741462857 0.0889397956 0.1310503036 0.0218267659 0.1051140000 387345695 0 402718720 -0.0234069265 0.0405893028 0.0623055920 178 1305031235.4381530285 0.0712870732 0.0888406230 0.1310503036 0.0217858269 0.0409250000 378992044 0 402718720 -0.0264261272 0.0431743786 0.0660990328 179 1305031235.4700589180 0.0742917657 0.0887593445 0.1310503036 0.0217473730 0.1124310000 378993572 0 402718720 -0.0278897341 0.0380052328 0.0671300292 180 1305031235.5059850216 0.0767524242 0.0886926394 0.1310503036 0.0217073087 0.1065030000 378995752 0 402718720 -0.0304254331 0.0402866714 0.0680255890 181 1305031235.5385539532 0.0768610016 0.0886272712 0.1310503036 0.0216602971 0.1067730000 378999544 0 402718720 -0.0301115699 0.0414946973 0.0698948279 182 1305031235.5703649521 0.0763785541 0.0885599706 0.1310503036 0.0216021944 0.0987420000 384839060 0 402718720 -0.0311141796 0.0411994532 0.0736677945 183 1305031235.6060059071 0.0779404491 0.0885019404 0.1310503036 0.0216068956 0.0740030000 391018456 0 402718720 -0.0371371657 0.0454266332 0.0748160109 184 1305031235.6389510632 0.0803928003 0.0884578690 0.1310503036 0.0215660342 0.0923450000 390844493 0 402718720 -0.0394386426 0.0406190939 0.0783066526 185 1305031235.6705160141 0.0789558142 0.0884065065 0.1310503036 0.0215217667 0.0404660000 390900932 0 402718720 -0.0418430269 0.0415514670 0.0837929249 186 1305031235.7057778835 0.0848729759 0.0883875091 0.1310503036 0.0214754399 0.1194880000 390834015 0 402718720 -0.0475676656 0.0384869687 0.0859062150 187 1305031235.7387969494 0.0858278573 0.0883738211 0.1310503036 0.0214234602 0.0521020000 379655276 0 402718720 -0.0546567328 0.0437629409 0.0877333358 188 1305031235.7696299553 0.0840856284 0.0883510116 0.1310503036 0.0213759604 0.1247470000 379747608 0 402718720 -0.0568094142 0.0480272472 0.0922051370 189 1305031235.8072249889 0.0909254700 0.0883646330 0.1310503036 0.0213270382 0.1085230000 379752108 0 402718720 -0.0599076040 0.0413576439 0.0962563306 190 1305031235.8388121128 0.0893470868 0.0883698038 0.1310503036 0.0212975437 0.1034050000 379755956 0 402718720 -0.0612726994 0.0433382094 0.1025038287 191 1305031235.8700668812 0.0930876806 0.0883945048 0.1310503036 0.0212997234 0.0954250000 380065576 0 402718720 -0.0641872212 0.0415909737 0.1061056107 192 1305031235.9061110020 0.0948716253 0.0884282398 0.1310503036 0.0212459181 0.0901040000 389223404 0 402718720 -0.0662443489 0.0430219024 0.1101106927 193 1305031235.9382328987 0.1008896455 0.0884928066 0.1310503036 0.0212063918 0.0579510000 392672052 0 402718720 -0.0684763417 0.0384816006 0.1128344089 194 1305031235.9700109959 0.0979979560 0.0885418022 0.1310503036 0.0211995216 0.0821590000 392522385 0 402718720 -0.0692838356 0.0419513211 0.1204401106 195 1305031236.0068531036 0.1038952172 0.0886205377 0.1310503036 0.0211527708 0.0340420000 392543220 0 402718720 -0.0720410198 0.0385891981 0.1251545846 196 1305031236.0380480289 0.1076968983 0.0887178661 0.1310503036 0.0211022421 0.0965830000 392475611 0 402718720 -0.0736771673 0.0389632843 0.1243694499 197 1305031236.0698781013 0.1060412377 0.0888058020 0.1310503036 0.0211132196 0.0404600000 380723800 0 402718720 -0.0745615140 0.0439787731 0.1257682741 198 1305031236.1058719158 0.1058712900 0.0888919913 0.1310503036 0.0210640582 0.1151080000 380700464 0 402718720 -0.0765469819 0.0481383801 0.1272156090 199 1305031236.1383249760 0.1044611484 0.0889702283 0.1310503036 0.0210110719 0.0953010000 380704524 0 402718720 -0.0773313046 0.0523186922 0.1278497726 200 1305031236.1709330082 0.1054392755 0.0890525735 0.1310503036 0.0209588910 0.0911410000 380706004 0 402718720 -0.0768428519 0.0533496775 0.1276566237 201 1305031236.2071900368 0.1049799696 0.0891318143 0.1310503036 0.0209132995 0.0901170000 391051260 0 402718720 -0.0779115781 0.0565875024 0.1278411746 202 1305031236.2383749485 0.1009377465 0.0891902595 0.1310503036 0.0208647728 0.0699010000 392150383 0 402718720 -0.0779239535 0.0632263646 0.1248062626 203 1305031236.2699589729 0.0949476436 0.0892186210 0.1310503036 0.0208264819 0.0995270000 392074187 0 402718720 -0.0741607621 0.0661979616 0.1285735965 204 1305031236.3069939613 0.0935422778 0.0892398154 0.1310503036 0.0208147102 0.0372610000 380721436 0 402718720 -0.0750269368 0.0667609051 0.1281094849 205 1305031236.3392169476 0.0887806788 0.0892375757 0.1310503036 0.0207669765 0.0343260000 380724792 0 402718720 -0.0749321431 0.0697981343 0.1292350739 206 1305031236.3700959682 0.0877973065 0.0892305841 0.1310503036 0.0207260799 0.0352510000 380729244 0 402718720 -0.0733350217 0.0684669316 0.1256746650 207 1305031236.4058690071 0.0817837492 0.0891946091 0.1310503036 0.0206913784 0.0358560000 380735160 0 402718720 -0.0693327785 0.0713711828 0.1205068752 208 1305031236.4387879372 0.0827026740 0.0891633978 0.1310503036 0.0206436629 0.0353700000 380738796 0 402718720 -0.0695677623 0.0678948835 0.1167909279 209 1305031236.4751410484 0.0794332027 0.0891168419 0.1310503036 0.0205955217 0.0362470000 380742248 0 402718720 -0.0641904175 0.0634950101 0.1144022197 210 1305031236.5077209473 0.0774664059 0.0890613636 0.1310503036 0.0205504759 0.0496150000 380746084 0 402718720 -0.0615532510 0.0619107299 0.1098165959 211 1305031236.5386450291 0.0755404457 0.0889972834 0.1310503036 0.0205318283 0.0368130000 380749424 0 402718720 -0.0561757833 0.0564814694 0.1084553003 212 1305031236.5740950108 0.0748102143 0.0889303633 0.1310503036 0.0205064436 0.0374390000 380753196 0 402718720 -0.0533521809 0.0502939373 0.1045042798 213 1305031236.6057569981 0.0700326785 0.0888416418 0.1310503036 0.0204814190 0.0372140000 380756536 0 402718720 -0.0495417416 0.0512352102 0.1000629887 214 1305031236.6384010315 0.0769914091 0.0887862668 0.1310503036 0.0204379169 0.0374160000 380759700 0 402718720 -0.0434338897 0.0329617783 0.1024852991 215 1305031236.6751470566 0.0781497806 0.0887367948 0.1310503036 0.0204366820 0.0427700000 381441256 0 402718720 -0.0406792089 0.0254298411 0.0985205099 216 1305031236.7033619881 0.0778508708 0.0886863970 0.1310503036 0.0203912170 0.1253090000 381396860 0 402718720 -0.0356683172 0.0211754218 0.0950342342 217 1305031236.7339220047 0.0850049630 0.0886694319 0.1310503036 0.0203671884 0.1189090000 381399824 0 402718720 -0.0348998755 0.0124504715 0.0858489200 218 1305031236.7740409374 0.0897426754 0.0886743550 0.1310503036 0.0204200304 0.1210100000 381404244 0 402718720 -0.0302084945 0.0012484845 0.0820051730 219 1305031236.8025879860 0.0912833810 0.0886862684 0.1310503036 0.0205641297 0.1107020000 381751136 0 402718720 -0.0296412092 0.0005215053 0.0734822005 220 1305031236.8364150524 0.0878454223 0.0886824464 0.1310503036 0.0205184076 0.1094040000 392517784 0 402718720 -0.0258864071 -0.0002965268 0.0693162754 221 1305031236.8743979931 0.0878866091 0.0886788453 0.1310503036 0.0204947863 0.0599470000 395811933 0 402718720 -0.0222890414 -0.0028683841 0.0612973310 222 1305031236.9060690403 0.0851178095 0.0886628046 0.1310503036 0.0205275600 0.1015080000 395540527 0 402718720 -0.0222272109 -0.0006068943 0.0541069731 223 1305031236.9344370365 0.0852482021 0.0886474925 0.1310503036 0.0204894541 0.0422090000 395463656 0 402718720 -0.0216009468 -0.0027002306 0.0486343279 224 1305031236.9744000435 0.0826907605 0.0886208999 0.1310503036 0.0204479201 0.1328930000 395396163 0 402718720 -0.0170276500 -0.0037175100 0.0446517318 225 1305031237.0074260235 0.0860677660 0.0886095526 0.1310503036 0.0204054439 0.0398970000 381419000 0 402718720 -0.0104858521 -0.0080677997 0.0395743996 226 1305031237.0370240211 0.0849026069 0.0885931502 0.1310503036 0.0203859299 0.0381310000 381422276 0 402718720 -0.0076689487 -0.0035610304 0.0322424844 227 1305031237.0734269619 0.0866410136 0.0885845505 0.1310503036 0.0203476722 0.0374670000 381426036 0 402718720 -0.0018098271 -0.0042798808 0.0260312296 228 1305031237.1059679985 0.0900503695 0.0885909795 0.1310503036 0.0203099749 0.0404240000 381959804 0 402718720 0.0034072790 -0.0082045533 0.0224534180 229 1305031237.1378319263 0.0920547992 0.0886061054 0.1310503036 0.0202726815 0.1138910000 382031320 0 402718720 0.0089189913 -0.0077687898 0.0180275030 230 1305031237.1712269783 0.0946758166 0.0886324954 0.1310503036 0.0202788023 0.1026250000 382031988 0 402718720 0.0145806251 -0.0058084577 0.0127607277 231 1305031237.2042291164 0.0946394801 0.0886584997 0.1310503036 0.0202838862 0.0971030000 382035744 0 402718720 0.0162024088 -0.0112734111 0.0099797118 232 1305031237.2375690937 0.0957243741 0.0886889561 0.1310503036 0.0202762022 0.0903950000 387988668 0 402718720 0.0221403465 -0.0037148946 0.0066785933 233 1305031237.2746589184 0.0935890675 0.0887099866 0.1310503036 0.0202672061 0.0818680000 395665580 0 402718720 0.0249388274 -0.0035554972 0.0081319995 234 1305031237.3058099747 0.0983387530 0.0887511352 0.1310503036 0.0202354748 0.0558080000 396162804 0 402718720 0.0297113117 -0.0030489718 0.0019590426 235 1305031237.3371419907 0.1004246175 0.0888008095 0.1310503036 0.0202194573 0.0644790000 396294549 0 402718720 0.0341318175 -0.0030604932 0.0026013358 236 1305031237.3741660118 0.1043014154 0.0888664901 0.1310503036 0.0201920206 0.0338370000 395914368 0 402718720 0.0359191708 -0.0059193270 -0.0057376707 237 1305031237.4057340622 0.1011339203 0.0889182514 0.1310503036 0.0202117596 0.0985960000 395847347 0 402718720 0.0325068682 0.0003295420 -0.0106741013 238 1305031237.4377219677 0.1009273455 0.0889687098 0.1310503036 0.0202048800 0.0512400000 382512300 0 402718720 0.0351199545 -0.0003962833 -0.0078351023 239 1305031237.4741280079 0.1058083400 0.0890391685 0.1310503036 0.0202009037 0.0811070000 382525508 0 402718720 0.0386639126 -0.0057840524 -0.0140305208 240 1305031237.5060451031 0.1049522310 0.0891054729 0.1310503036 0.0201908435 0.0712380000 382829252 0 402718720 0.0384699665 0.0050239675 -0.0171983894 241 1305031237.5376501083 0.1042054147 0.0891681283 0.1310503036 0.0201515702 0.0749290000 390514208 0 402718720 0.0405992642 0.0013673287 -0.0140796900 242 1305031237.5739479065 0.1100720838 0.0892545082 0.1310503036 0.0201379703 0.0440200000 392758572 0 402718720 0.0426007621 0.0042367075 -0.0243018642 243 1305031237.6068129539 0.1104647964 0.0893417934 0.1310503036 0.0201020193 0.0888980000 392691123 0 402718720 0.0432534292 0.0090585658 -0.0263185725 244 1305031237.6378550529 0.1140112281 0.0894428976 0.1310503036 0.0200690548 0.0650070000 383180112 0 402718720 0.0455120057 0.0122323819 -0.0303354636 245 1305031237.6752760410 0.1119275093 0.0895346715 0.1310503036 0.0200489635 0.0796220000 383599272 0 402718720 0.0442591459 0.0121160354 -0.0286255926 246 1305031237.7071180344 0.1139986292 0.0896341185 0.1310503036 0.0200128782 0.0746790000 383973304 0 402718720 0.0453622602 0.0161007699 -0.0305777304 247 1305031237.7416670322 0.1164139211 0.0897425388 0.1310503036 0.0199813458 0.0754490000 384271408 0 402718720 0.0447100103 0.0184320677 -0.0354516543 248 1305031237.7743060589 0.1123726442 0.0898337892 0.1310503036 0.0199980003 0.0720080000 384255796 0 402718720 0.0439887047 0.0120706214 -0.0301763043 249 1305031237.8064959049 0.1169023290 0.0899424982 0.1310503036 0.0199753131 0.0723980000 384666980 0 402718720 0.0459550694 0.0104682241 -0.0364507250 250 1305031237.8430309296 0.1193704307 0.0900602099 0.1310503036 0.0199696791 0.0740050000 385159760 0 402718720 0.0438887775 0.0244460329 -0.0401096568 251 1305031237.8754220009 0.1161704510 0.0901642348 0.1310503036 0.0201625336 0.0707820000 385321976 0 402718720 0.0466371626 0.0111168288 -0.0341021046 252 1305031237.9077839851 0.1117030010 0.0902497061 0.1310503036 0.0201941364 0.0778460000 385689260 0 402718720 0.0433007851 0.0097303577 -0.0316512398 253 1305031237.9441869259 0.1197650433 0.0903663675 0.1310503036 0.0202393398 0.0635470000 386023644 0 402718720 0.0444305800 0.0199993271 -0.0412995219 254 1305031237.9738099575 0.1194226816 0.0904807624 0.1310503036 0.0202085722 0.0757700000 386180820 0 402718720 0.0451687835 0.0223507769 -0.0370570309 255 1305031238.0069320202 0.1153179780 0.0905781633 0.1310503036 0.0201789963 0.0818720000 386681132 0 402718720 0.0381055474 0.0252870284 -0.0361631922 256 1305031238.0431399345 0.1099334806 0.0906537700 0.1310503036 0.0203975009 0.0824780000 386567052 0 402718720 0.0344044417 0.0343429446 -0.0256974660 257 1305031238.0740320683 0.0979092494 0.0906820014 0.1310503036 0.0205018859 0.0890880000 387125460 0 402718720 0.0191558246 0.0503227413 -0.0121635702 258 1305031238.1065878868 0.0943517610 0.0906962253 0.1310503036 0.0205092117 0.0882400000 387043440 0 402718720 0.0177044198 0.0507003628 -0.0054560192 259 1305031238.1433279514 0.0939113647 0.0907086390 0.1310503036 0.0206003397 0.0890000000 387319336 0 402718720 0.0169426631 0.0420975052 -0.0061435588 260 1305031238.1723001003 0.0902259648 0.0907067825 0.1310503036 0.0205842707 0.0869850000 394620604 0 402718720 0.0085774809 0.0510044433 -0.0032029264 261 1305031238.2054259777 0.0923086032 0.0907129198 0.1310503036 0.0205785610 0.0653810000 402778045 0 402718720 0.0109375492 0.0339636803 -0.0068640467 262 1305031238.2401471138 0.0905833542 0.0907124252 0.1310503036 0.0205704479 0.0659570000 402141434 0 402718720 0.0060811602 0.0338516496 -0.0059708310 263 1305031238.2725269794 0.0899438635 0.0907095030 0.1310503036 0.0205343908 0.0557200000 402272409 0 402718720 0.0067461133 0.0341536887 -0.0009787288 264 1305031238.3060529232 0.0921995044 0.0907151469 0.1310503036 0.0206433743 0.0396200000 401774356 0 402718720 0.0032639578 0.0408483706 -0.0017242953 265 1305031238.3425960541 0.0887588933 0.0907077648 0.1310503036 0.0206510631 0.1300520000 401686491 0 402718720 0.0011931167 0.0345055871 0.0035875682 266 1305031238.3741040230 0.0873102993 0.0906949924 0.1310503036 0.0207114265 0.0683510000 386956116 0 402718720 -0.0053044502 0.0348400511 0.0049558035 267 1305031238.4060359001 0.0857688859 0.0906765426 0.1310503036 0.0206764708 0.0343290000 386959284 0 402718720 -0.0105612073 0.0395814627 0.0062972717 268 1305031238.4434239864 0.0859364718 0.0906588557 0.1310503036 0.0206419781 0.0339670000 386962588 0 402718720 -0.0120289400 0.0346637554 0.0090472177 269 1305031238.4740819931 0.0839560181 0.0906339381 0.1310503036 0.0206103895 0.0350080000 386966248 0 402718720 -0.0167168155 0.0324826799 0.0116898157 270 1305031238.5058109760 0.0882998183 0.0906252932 0.1310503036 0.0206535583 0.0344930000 386968988 0 402718720 -0.0210072510 0.0265281573 0.0083349813 271 1305031238.5432639122 0.0892901644 0.0906203665 0.1310503036 0.0206184552 0.0343540000 386972568 0 402718720 -0.0208933931 0.0167762749 0.0141464341 272 1305031238.5741839409 0.0878418237 0.0906101513 0.1310503036 0.0205924935 0.0336260000 386975728 0 402718720 -0.0241302755 0.0225536060 0.0141021134 273 1305031238.6058249474 0.0841061547 0.0905863272 0.1310503036 0.0205598171 0.0631870000 386979312 0 402718720 -0.0258898996 0.0238921158 0.0196895357 274 1305031238.6427590847 0.0823310167 0.0905561983 0.1310503036 0.0205249983 0.0331610000 386982724 0 402718720 -0.0264835637 0.0243001115 0.0237998385 275 1305031238.6738131046 0.0852427557 0.0905368767 0.1310503036 0.0204983550 0.0372590000 387675668 0 402718720 -0.0268312283 0.0218978506 0.0255678520 276 1305031238.7051889896 0.0834275559 0.0905111183 0.1310503036 0.0204647727 0.1280150000 387680360 0 402718720 -0.0300575700 0.0254748892 0.0271750931 277 1305031238.7413070202 0.0837117583 0.0904865718 0.1310503036 0.0204637973 0.1141990000 387683468 0 402718720 -0.0309522487 0.0205711704 0.0325003043 278 1305031238.7717959881 0.0862315744 0.0904712661 0.1310503036 0.0204469286 0.1076150000 387687608 0 402718720 -0.0328287669 0.0171400178 0.0339105092 279 1305031238.8070189953 0.0822446272 0.0904417799 0.1310503036 0.0204666744 0.0999390000 394199856 0 402718720 -0.0356933586 0.0237839445 0.0365153961 280 1305031238.8429400921 0.0814218670 0.0904095660 0.1310503036 0.0204323592 0.0991930000 401660920 0 402718720 -0.0388946496 0.0261096321 0.0366163701 281 1305031238.8737230301 0.0934949890 0.0904205461 0.1310503036 0.0205528699 0.0564450000 405363661 0 402718720 -0.0356940627 0.0051450413 0.0463319123 282 1305031238.9061720371 0.1053541526 0.0904735022 0.1310503036 0.0206198162 0.0657130000 405000645 0 402718720 -0.0342910513 -0.0114278551 0.0548054054 283 1305031238.9427859783 0.0960548297 0.0904932242 0.1310503036 0.0206205141 0.0439690000 405245805 0 402718720 -0.0384042338 0.0035447478 0.0481148027 284 1305031238.9723079205 0.0946098790 0.0905077194 0.1310503036 0.0205883391 0.1237830000 404753591 0 402718720 -0.0417988822 0.0053066341 0.0488076136 285 1305031239.0104830265 0.1067390591 0.0905646715 0.1310503036 0.0205540911 0.0633730000 388518456 0 402718720 -0.0408470929 -0.0093896296 0.0550088249 286 1305031239.0408790112 0.1046692505 0.0906139882 0.1310503036 0.0205219848 0.1250450000 388507852 0 402718720 -0.0422212221 -0.0066670384 0.0565116853 287 1305031239.0746610165 0.1008862779 0.0906497802 0.1310503036 0.0204959378 0.1071490000 388511392 0 402718720 -0.0431543738 -0.0011147894 0.0550504625 288 1305031239.1109058857 0.1000745669 0.0906825051 0.1310503036 0.0204634097 0.1027930000 388515332 0 402718720 -0.0436063185 -0.0001176801 0.0551359989 289 1305031239.1417789459 0.0963167325 0.0907020007 0.1310503036 0.0204305730 0.0987380000 396098372 0 402718720 -0.0444423519 0.0042687375 0.0528774336 290 1305031239.1757500172 0.0940304548 0.0907134781 0.1310503036 0.0203975817 0.0959920000 403169440 0 402718720 -0.0443872437 0.0066263182 0.0512737036 291 1305031239.2096450329 0.0948082656 0.0907275496 0.1310503036 0.0203633180 0.0695180000 404010700 0 402718720 -0.0407168046 0.0056745559 0.0513194092 292 1305031239.2417099476 0.0928137973 0.0907346943 0.1310503036 0.0203325892 0.0544140000 403875785 0 402718720 -0.0399106964 0.0065489113 0.0520615354 293 1305031239.2738199234 0.0925921947 0.0907410338 0.1310503036 0.0203229706 0.1313230000 403819295 0 402718720 -0.0395581648 0.0057122158 0.0505918115 294 1305031239.3101770878 0.0918835476 0.0907449199 0.1310503036 0.0202888939 0.0479960000 388531236 0 402718720 -0.0389057696 0.0057808748 0.0493000001 295 1305031239.3419699669 0.0932174921 0.0907533015 0.1310503036 0.0202553296 0.0348010000 388534688 0 402718720 -0.0354672521 0.0044239694 0.0474934988 296 1305031239.3750240803 0.0942939892 0.0907652633 0.1310503036 0.0202508102 0.0345050000 388537904 0 402718720 -0.0358657166 0.0007019425 0.0474982634 297 1305031239.4106309414 0.0954940394 0.0907811851 0.1310503036 0.0202218088 0.0350200000 388541788 0 402718720 -0.0326160267 -0.0010274909 0.0466183908 298 1305031239.4415419102 0.0939754695 0.0907919042 0.1310503036 0.0201887452 0.0466560000 388544916 0 402718720 -0.0303680487 0.0005014203 0.0449151732 299 1305031239.4733181000 0.0957961008 0.0908086407 0.1310503036 0.0201616165 0.0342310000 388548376 0 402718720 -0.0300040729 -0.0025189789 0.0424817801 300 1305031239.5097389221 0.0947922021 0.0908219192 0.1310503036 0.0201356682 0.0341910000 388551688 0 402718720 -0.0261632297 -0.0021997178 0.0428384915 301 1305031239.5438020229 0.0976313204 0.0908445418 0.1310503036 0.0201254008 0.0458620000 388555060 0 402718720 -0.0243054815 -0.0063779433 0.0406504124 302 1305031239.5761160851 0.0968135297 0.0908643066 0.1310503036 0.0201061404 0.0341850000 388558832 0 402718720 -0.0213219225 -0.0049707480 0.0389448516 303 1305031239.6111609936 0.0985121503 0.0908895471 0.1310503036 0.0200749517 0.0341810000 388562496 0 402718720 -0.0197493248 -0.0076442193 0.0373425856 304 1305031239.6414220333 0.0989622250 0.0909161019 0.1310503036 0.0200480839 0.0347790000 388565524 0 402718720 -0.0210968014 -0.0069398964 0.0308313146 305 1305031239.6710560322 0.0968136340 0.0909354381 0.1310503036 0.0200359325 0.0369470000 388568876 0 402718720 -0.0213751029 -0.0022508050 0.0252346434 306 1305031239.7075550556 0.0973052382 0.0909562544 0.1310503036 0.0200592353 0.0458620000 388572408 0 402718720 -0.0186052676 -0.0061718002 0.0257655308 307 1305031239.7417550087 0.0945718810 0.0909680317 0.1310503036 0.0200375449 0.0355720000 388575736 0 402718720 -0.0179236494 -0.0031752696 0.0229976401 308 1305031239.7712600231 0.0978511125 0.0909903794 0.1310503036 0.0200225497 0.0493380000 389116720 0 402718720 -0.0128908437 -0.0090208473 0.0228410605 309 1305031239.8060870171 0.0966881514 0.0910088188 0.1310503036 0.0200941510 0.1284470000 389199792 0 402718720 -0.0105762752 -0.0098216292 0.0199147910 310 1305031239.8392889500 0.0970693231 0.0910283688 0.1310503036 0.0200712375 0.1193670000 389200752 0 402718720 -0.0103212763 -0.0097546652 0.0144877173 311 1305031239.8744299412 0.0936780572 0.0910368887 0.1310503036 0.0200557566 0.1117480000 389203180 0 402718720 -0.0079218838 -0.0045691356 0.0127535574 312 1305031239.9090619087 0.0951027647 0.0910499203 0.1310503036 0.0200588053 0.1063520000 389448935 0 402718720 -0.0016584867 -0.0043894830 0.0119619304 313 1305031239.9403729439 0.0995621607 0.0910771160 0.1310503036 0.0200341294 0.1015580000 404243288 0 402718720 0.0033214986 -0.0060334764 0.0070476285 314 1305031239.9710669518 0.0978274345 0.0910986138 0.1310503036 0.0200529337 0.0652710000 410871941 0 402718720 0.0043814178 -0.0027297135 0.0052191820 315 1305031240.0088651180 0.1030048952 0.0911364115 0.1310503036 0.0201181284 0.0368380000 409556403 0 402718720 0.0074323621 -0.0102378139 -0.0006754452 316 1305031240.0396599770 0.1021835357 0.0911713708 0.1310503036 0.0200993525 0.0828750000 409563077 0 402718720 0.0111717647 -0.0075442805 -0.0005093473 317 1305031240.0711870193 0.1043192074 0.0912128466 0.1310503036 0.0200699969 0.0356880000 409044461 0 402718720 0.0123509690 -0.0090502650 -0.0053420514 318 1305031240.1093459129 0.1073209122 0.0912635009 0.1310503036 0.0200883033 0.1328890000 409112231 0 402718720 0.0166315399 -0.0160476323 -0.0071048029 319 1305031240.1435019970 0.1035247371 0.0913019374 0.1310503036 0.0201143230 0.0951080000 389167580 0 402718720 0.0220440887 -0.0118821422 -0.0002773032 320 1305031240.1775770187 0.1089929938 0.0913572219 0.1310503036 0.0200958808 0.0291170000 389145828 0 402718720 0.0275205635 -0.0054182019 -0.0085255764 321 1305031240.2093310356 0.1135122776 0.0914262408 0.1310503036 0.0201467275 0.0291800000 389524504 0 402718720 0.0337391607 -0.0200688057 -0.0053111827 322 1305031240.2410049438 0.1147140935 0.0914985633 0.1310503036 0.0201675829 0.0996580000 389618184 0 402718720 0.0360753387 -0.0140656456 -0.0117566334 323 1305031240.2774341106 0.1135579720 0.0915668587 0.1310503036 0.0201614791 0.0908280000 389620212 0 402718720 0.0381636657 -0.0039751902 -0.0144169945 324 1305031240.3089289665 0.1208157688 0.0916571331 0.1310503036 0.0201495770 0.0814840000 390232044 0 402718720 0.0432737656 -0.0125961211 -0.0216595195 325 1305031240.3422729969 0.1195177436 0.0917428581 0.1310503036 0.0201383625 0.0707440000 390227932 0 402718720 0.0433875546 -0.0012366548 -0.0251938961 326 1305031240.3774259090 0.1237251982 0.0918409634 0.1310503036 0.0201532168 0.0707050000 390473808 0 402718720 0.0488270000 0.0027384665 -0.0289356858 327 1305031240.4091110229 0.1225385442 0.0919348398 0.1310503036 0.0201294857 0.0534830000 390782860 0 402718720 0.0463159680 0.0048906878 -0.0343550146 328 1305031240.4417860508 0.1262426078 0.0920394367 0.1310503036 0.0201004548 0.0514590000 390956132 0 402718720 0.0481161997 0.0092001427 -0.0398520678 329 1305031240.4776389599 0.1243103519 0.0921375246 0.1310503036 0.0200711224 0.0660430000 391278332 0 402718720 0.0476080887 0.0135207344 -0.0386816040 330 1305031240.5084490776 0.1291341931 0.0922496357 0.1310503036 0.0200637332 0.0659740000 397232140 0 402718720 0.0511151999 0.0115782395 -0.0443488322 331 1305031240.5412700176 0.1290116608 0.0923606992 0.1310503036 0.0200771132 0.0730610000 398159637 0 402718720 0.0484524965 0.0158881880 -0.0481027141 332 1305031240.5759088993 0.1310649216 0.0924772782 0.1310649216 0.0200477332 0.0560590000 391136224 0 402718720 0.0485018864 0.0204013716 -0.0497249477 333 1305031240.6101338863 0.1263747364 0.0925790723 0.1310649216 0.0200229720 0.0606940000 391435152 0 402718720 0.0438723341 0.0205931850 -0.0468241684 334 1305031240.6398229599 0.1268540025 0.0926816919 0.1310649216 0.0200120396 0.0613050000 397232129 0 402718720 0.0439720526 0.0195932984 -0.0455245674 335 1305031240.6747570038 0.1224274188 0.0927704851 0.1310649216 0.0199872193 0.0565130000 394255557 0 402718720 0.0416515395 0.0212917216 -0.0391851477 336 1305031240.7079319954 0.1235309765 0.0928620342 0.1310649216 0.0200015402 0.0620950000 391797820 0 402718720 0.0418132469 0.0199436750 -0.0385405160 337 1305031240.7439579964 0.1210825294 0.0929457745 0.1310649216 0.0199797968 0.0641630000 393234317 0 402718720 0.0399464443 0.0207231026 -0.0342333354 338 1305031240.7768330574 0.1183375940 0.0930208983 0.1310649216 0.0199522509 0.0682040000 395514061 0 402718720 0.0373810083 0.0200795550 -0.0312596858 339 1305031240.8096249104 0.1178720370 0.0930942055 0.1310649216 0.0199522844 0.0583480000 392646144 0 402718720 0.0369946584 0.0199460797 -0.0278630462 340 1305031240.8425960541 0.1108253598 0.0931463559 0.1310649216 0.0199584504 0.0714060000 393009824 0 402718720 0.0322894901 0.0249829683 -0.0189200919 341 1305031240.8794100285 0.1085976735 0.0931916677 0.1310649216 0.0199408839 0.0674190000 393214567 0 402718720 0.0305201821 0.0234457627 -0.0148414029 342 1305031240.9084498882 0.0998748615 0.0932112092 0.1310649216 0.0199559467 0.0836650000 393412852 0 402718720 0.0219336227 0.0392720029 -0.0043845493 343 1305031240.9423189163 0.1069090068 0.0932511445 0.1310649216 0.0199475673 0.0841750000 402964842 0 402718720 0.0246730484 0.0492459685 -0.0056114569 344 1305031240.9779360294 0.0972531885 0.0932627783 0.1310649216 0.0199245397 0.1117970000 402646563 0 402718720 0.0204136204 0.0428850390 0.0049915556 345 1305031241.0083029270 0.0964981019 0.0932721561 0.1310649216 0.0200239830 0.0846350000 393440200 0 402718720 0.0082546789 0.0447482727 -0.0059489850 346 1305031241.0401480198 0.0917696133 0.0932678135 0.1310649216 0.0200304316 0.0945790000 393443124 0 402718720 0.0071676257 0.0408988968 0.0000191415 347 1305031241.0759329796 0.0895086676 0.0932569802 0.1310649216 0.0200304813 0.0906690000 393799772 0 402718720 0.0000293497 0.0385875814 -0.0013016602 348 1305031241.1065559387 0.0899274200 0.0932474125 0.1310649216 0.0200116826 0.0963800000 404897900 0 402718720 -0.0038083540 0.0408190191 -0.0016602925 349 1305031241.1400520802 0.0840841830 0.0932211568 0.1310649216 0.0200166959 0.0690450000 410981621 0 402718720 -0.0050391410 0.0385822095 0.0069796611 350 1305031241.1781818867 0.0837424248 0.0931940747 0.1310649216 0.0200287717 0.0679770000 409720619 0 402718720 -0.0071186488 0.0399622619 0.0088332603 351 1305031241.2106790543 0.0814157203 0.0931605182 0.1310649216 0.0200030003 0.0494550000 410506905 0 402718720 -0.0108295036 0.0470236242 0.0113658868 352 1305031241.2393150330 0.0825468525 0.0931303657 0.1310649216 0.0200171516 0.0360880000 409333600 0 402718720 -0.0113995560 0.0406779125 0.0119726546 353 1305031241.2768468857 0.0805676207 0.0930947772 0.1310649216 0.0200283768 0.1380210000 409253055 0 402718720 -0.0101420041 0.0359746516 0.0172331482 354 1305031241.3063299656 0.0792843178 0.0930557646 0.1310649216 0.0200053869 0.0569670000 393439596 0 402718720 -0.0131940991 0.0425195843 0.0174576733 355 1305031241.3424758911 0.0777435377 0.0930126315 0.1310649216 0.0199984226 0.0342530000 393443400 0 402718720 -0.0171829276 0.0509109199 0.0168923326 356 1305031241.3795149326 0.0808866248 0.0929785697 0.1310649216 0.0200917520 0.0314350000 393446664 0 402718720 -0.0214513950 0.0363265760 0.0168972425 357 1305031241.4096820354 0.0863253698 0.0929599333 0.1310649216 0.0200929616 0.0329580000 393449624 0 402718720 -0.0241524614 0.0296222679 0.0156593919 358 1305031241.4455459118 0.0833097771 0.0929329776 0.1310649216 0.0200789980 0.0322090000 393452932 0 402718720 -0.0267267302 0.0339397751 0.0198803581 359 1305031241.4775071144 0.0810923427 0.0928999953 0.1310649216 0.0203439099 0.0309380000 393456516 0 402718720 -0.0214410294 0.0274834502 0.0322024338 360 1305031241.5098490715 0.0833672881 0.0928735156 0.1310649216 0.0203322240 0.0462080000 393482233 0 402718720 -0.0200134963 0.0204101708 0.0384184010 361 1305031241.5477299690 0.0850792155 0.0928519247 0.1310649216 0.0203057606 0.0327450000 393463104 0 402718720 -0.0201212019 0.0158339702 0.0414394028 362 1305031241.5783948898 0.0863753110 0.0928340335 0.1310649216 0.0203030062 0.0326850000 393527657 0 402718720 -0.0201221779 0.0170790963 0.0371610187 363 1305031241.6092638969 0.0904664844 0.0928275113 0.1310649216 0.0203167462 0.0325410000 393469328 0 402718720 -0.0208226927 0.0104014613 0.0363962986 364 1305031241.6475839615 0.0921036005 0.0928255226 0.1310649216 0.0202888511 0.0318060000 393472720 0 402718720 -0.0200871062 0.0068496023 0.0355283655 365 1305031241.6783659458 0.0866592973 0.0928086288 0.1310649216 0.0203330120 0.0319180000 393524393 0 402718720 -0.0185501110 0.0166584961 0.0313348286 366 1305031241.7098269463 0.0869064704 0.0927925027 0.1310649216 0.0203095161 0.0566180000 393479188 0 402718720 -0.0173557755 0.0145211285 0.0323523469 367 1305031241.7471020222 0.0858898610 0.0927736944 0.1310649216 0.0202931499 0.0328080000 393540577 0 402718720 -0.0174502656 0.0169669129 0.0289879162 368 1305031241.7782680988 0.0889160708 0.0927632117 0.1310649216 0.0202769232 0.0416700000 393508661 0 402718720 -0.0166166518 0.0126070306 0.0282060858 369 1305031241.8098289967 0.0876647383 0.0927493947 0.1310649216 0.0202960234 0.0456490000 393554869 0 402718720 -0.0181549639 0.0189583544 0.0220878739 370 1305031241.8464360237 0.0892145336 0.0927398410 0.1310649216 0.0202915763 0.0323480000 393492424 0 402718720 -0.0186499283 0.0111363595 0.0259845089 371 1305031241.8787989616 0.0908962190 0.0927348717 0.1310649216 0.0204139383 0.0318650000 393495600 0 402718720 -0.0183667559 0.0136527484 0.0208854172 372 1305031241.9114871025 0.0850414634 0.0927141905 0.1310649216 0.0204405907 0.0312700000 393498968 0 402718720 -0.0176489130 0.0225616079 0.0219760481 373 1305031241.9477050304 0.0884445980 0.0927027439 0.1310649216 0.0204541667 0.0456230000 393502232 0 402718720 -0.0193677321 0.0164154414 0.0215026494 374 1305031241.9783430099 0.0861094967 0.0926851149 0.1310649216 0.0206318945 0.0448110000 393505428 0 402718720 -0.0195484981 0.0198753588 0.0219077058 375 1305031242.0105700493 0.0841855854 0.0926624495 0.1310649216 0.0207559181 0.0320370000 393508172 0 402718720 -0.0153518002 0.0254214294 0.0238392465 376 1305031242.0463600159 0.0851508901 0.0926424719 0.1310649216 0.0208574798 0.0407350000 393511556 0 402718720 -0.0157462507 0.0224833824 0.0256651975 377 1305031242.0795490742 0.0880155340 0.0926301989 0.1310649216 0.0210178144 0.0351610000 394099676 0 402718720 -0.0196399465 0.0195557214 0.0216753595 378 1305031242.1105840206 0.0894085914 0.0926216761 0.1310649216 0.0211428542 0.1327940000 394203636 0 402718720 -0.0196793787 0.0163809527 0.0224844739 379 1305031242.1466050148 0.0906876996 0.0926165733 0.1310649216 0.0213457729 0.1208190000 394207688 0 402718720 -0.0211895127 0.0155202942 0.0207148120 380 1305031242.1797080040 0.0923405141 0.0926158468 0.1310649216 0.0214970885 0.1209160000 394212168 0 402718720 -0.0261393320 0.0129521564 0.0170718841 381 1305031242.2087249756 0.0927767828 0.0926162692 0.1310649216 0.0215503504 0.1138120000 394484283 0 402718720 -0.0265624654 0.0099086436 0.0180015825 382 1305031242.2478089333 0.0949540138 0.0926223889 0.1310649216 0.0216628343 0.0933830000 413138800 0 402718720 -0.0321550071 0.0049090553 0.0148443161 383 1305031242.2794981003 0.0968566462 0.0926334444 0.1310649216 0.0217470545 0.0373100000 414882997 0 402718720 -0.0307782404 0.0027564140 0.0138417240 384 1305031242.3097639084 0.0944227204 0.0926381040 0.1310649216 0.0218192881 0.0873790000 414843849 0 402718720 -0.0306721628 0.0022045355 0.0162619390 385 1305031242.3471269608 0.0987247154 0.0926539134 0.1310649216 0.0219771585 0.0390090000 413569016 0 402718720 -0.0313164480 -0.0048016394 0.0137736658 386 1305031242.3784790039 0.0997599512 0.0926723228 0.1310649216 0.0221409732 0.1460440000 413509473 0 402718720 -0.0338698514 -0.0037671877 0.0082718227 387 1305031242.4109969139 0.0964828208 0.0926821691 0.1310649216 0.0222266292 0.0768580000 394227076 0 402718720 -0.0332612172 -0.0032656274 0.0108394884 388 1305031242.4470989704 0.0990009382 0.0926984545 0.1310649216 0.0224393429 0.0369040000 394764512 0 402718720 -0.0368279889 -0.0065889792 0.0058082137 389 1305031242.4776470661 0.1000692397 0.0927174026 0.1310649216 0.0225572917 0.1343630000 394861144 0 402718720 -0.0339243151 -0.0073104538 0.0045856796 390 1305031242.5097260475 0.1006259620 0.0927376809 0.1310649216 0.0229138355 0.1240860000 394864428 0 402718720 -0.0403004363 -0.0098240869 0.0004822668 391 1305031242.5485460758 0.1027752236 0.0927633524 0.1310649216 0.0234124577 0.1142400000 395162988 0 402718720 -0.0378611833 -0.0100538768 -0.0019992404 392 1305031242.5748429298 0.1031073928 0.0927897403 0.1310649216 0.0236258262 0.1151310000 407956188 0 402718720 -0.0337612927 -0.0057608187 -0.0034370841 393 1305031242.6061151028 0.1063429862 0.0928242269 0.1310649216 0.0237436553 0.0984190000 414298292 0 402718720 -0.0327936411 -0.0092949299 -0.0050946902 394 1305031242.6438109875 0.1080876216 0.0928629665 0.1310649216 0.0240471572 0.0393230000 416282017 0 402718720 -0.0325882882 -0.0101542007 -0.0057441369 395 1305031242.6752018929 0.1021648720 0.0928865156 0.1310649216 0.0244145768 0.1081090000 414756141 0 402718720 -0.0458455682 -0.0063422062 -0.0074328184 396 1305031242.7139821053 0.1025622860 0.0929109494 0.1310649216 0.0249880063 0.0372650000 415869709 0 402718720 -0.0492783785 -0.0012665644 -0.0113082360 397 1305031242.7452580929 0.1131098270 0.0929618282 0.1310649216 0.0250762538 0.1543950000 414644111 0 402718720 -0.0421133712 -0.0051194970 -0.0169116519 398 1305031242.7775399685 0.1151177585 0.0930174963 0.1310649216 0.0252346975 0.0540840000 395439552 0 402718720 -0.0461615995 -0.0095854681 -0.0170426778 399 1305031242.8140709400 0.1166886687 0.0930768226 0.1310649216 0.0254709478 0.1326580000 395526236 0 402718720 -0.0456619449 -0.0084498376 -0.0156573206 400 1305031242.8443179131 0.1218485534 0.0931487519 0.1310649216 0.0255280125 0.1161160000 395528144 0 402718720 -0.0460518934 -0.0092490539 -0.0192484111 401 1305031242.8740880489 0.1207604185 0.0932176089 0.1310649216 0.0256068731 0.1136240000 395532196 0 402718720 -0.0508807153 -0.0073099863 -0.0186812244 402 1305031242.9137070179 0.1219282970 0.0932890285 0.1310649216 0.0257636982 0.1084880000 395759727 0 402718720 -0.0489617810 -0.0043118354 -0.0165437330 403 1305031242.9444379807 0.1207070574 0.0933570633 0.1310649216 0.0260201847 0.1173530000 411431364 0 402718720 -0.0601036698 -0.0016648211 -0.0202151872 404 1305031242.9760620594 0.1204608530 0.0934241519 0.1310649216 0.0261067834 0.0500980000 416375217 0 402718720 -0.0563599579 0.0010293766 -0.0166169368 405 1305031243.0141661167 0.1206375659 0.0934913456 0.1310649216 0.0261975426 0.0940180000 415300957 0 402718720 -0.0585944727 0.0034475292 -0.0164129175 406 1305031243.0469100475 0.1162376702 0.0935473710 0.1310649216 0.0262252361 0.1498420000 415032391 0 402718720 -0.0666034892 0.0081681674 -0.0166072473 407 1305031243.0780448914 0.1148310900 0.0935996651 0.1310649216 0.0262226794 0.0938730000 396043736 0 402718720 -0.0673549473 0.0114602624 -0.0164115354 408 1305031243.1136150360 0.1121732518 0.0936451886 0.1310649216 0.0262405154 0.1295270000 396134908 0 402718720 -0.0685902536 0.0147153260 -0.0151929706 409 1305031243.1458160877 0.1103850603 0.0936861174 0.1310649216 0.0262087150 0.1183580000 396138104 0 402718720 -0.0678078756 0.0180073138 -0.0151963010 410 1305031243.1780760288 0.1056999117 0.0937154193 0.1310649216 0.0261928805 0.1163440000 396140796 0 402718720 -0.0654225200 0.0208382457 -0.0111396294 411 1305031243.2136580944 0.1071122438 0.0937480150 0.1310649216 0.0262438561 0.1078160000 406874068 0 402718720 -0.0639412925 0.0182933137 -0.0127974451 412 1305031243.2455608845 0.1067175716 0.0937794945 0.1310649216 0.0266303890 0.1067330000 414044472 0 402718720 -0.0617580228 0.0155517869 -0.0101087075 413 1305031243.2781798840 0.1052802205 0.0938073413 0.1310649216 0.0267312415 0.0380120000 417581221 0 402718720 -0.0665235296 0.0124798436 -0.0102691818 414 1305031243.3142709732 0.1101873741 0.0938469066 0.1310649216 0.0268408349 0.1055250000 415971669 0 402718720 -0.0597239546 0.0111430939 -0.0122160539 415 1305031243.3460359573 0.1111714467 0.0938886525 0.1310649216 0.0272259766 0.0378390000 417427349 0 402718720 -0.0627241880 0.0095759472 -0.0135391969 416 1305031243.3789350986 0.1140405387 0.0939370945 0.1310649216 0.0273032083 0.0366620000 415950788 0 402718720 -0.0613005720 0.0077413861 -0.0134865828 417 1305031243.4139740467 0.1154096350 0.0939885874 0.1310649216 0.0275010390 0.1555640000 415883875 0 402718720 -0.0595972650 0.0095605794 -0.0121489819 418 1305031243.4470911026 0.1182132661 0.0940465412 0.1310649216 0.0277247781 0.0747200000 396160280 0 402718720 -0.0660766736 0.0075857602 -0.0151497144 419 1305031243.4780371189 0.1185325980 0.0941049805 0.1310649216 0.0277998218 0.0343960000 396163508 0 402718720 -0.0664408356 0.0089085549 -0.0127288532 420 1305031243.5154008865 0.1205292642 0.0941678955 0.1310649216 0.0279630330 0.0346220000 396166728 0 402718720 -0.0663874894 0.0123066204 -0.0133060757 421 1305031243.5459430218 0.1201274693 0.0942295572 0.1310649216 0.0280555093 0.0342500000 396170104 0 402718720 -0.0668641403 0.0150858387 -0.0120071396 422 1305031243.5779840946 0.1186838374 0.0942875057 0.1310649216 0.0280814817 0.0376830000 396664056 0 402718720 -0.0732779056 0.0179327838 -0.0124779511 423 1305031243.6140549183 0.1202678978 0.0943489250 0.1310649216 0.0284212983 0.1372180000 396752364 0 402718720 -0.0710054114 0.0198304504 -0.0121761728 424 1305031243.6461870670 0.1233442575 0.0944173103 0.1310649216 0.0287890723 0.1250210000 396754500 0 402718720 -0.0693085343 0.0165491458 -0.0132832061 425 1305031243.6782801151 0.1238403246 0.0944865409 0.1310649216 0.0288551877 0.1194660000 397055376 0 402718720 -0.0772948712 0.0138295023 -0.0156124942 426 1305031243.7142961025 0.1230939105 0.0945536943 0.1310649216 0.0293012709 0.1126350000 406155476 0 402718720 -0.0655600205 0.0203466509 -0.0142914299 427 1305031243.7473781109 0.1211749315 0.0946160392 0.1310649216 0.0296663935 0.1131260000 413931580 0 402718720 -0.0608727038 0.0165220145 -0.0091462340 428 1305031243.7790360451 0.1109826863 0.0946542790 0.1310649216 0.0298629253 0.0397260000 419299709 0 402718720 -0.0682661459 0.0226300657 -0.0059882272 429 1305031243.8141930103 0.1138941497 0.0946991272 0.1310649216 0.0305150691 0.1113360000 417402389 0 402718720 -0.0603209957 0.0206759069 -0.0089535620 430 1305031243.8462920189 0.1123660356 0.0947402130 0.1310649216 0.0310276978 0.0367870000 417176037 0 402718720 -0.0452203229 0.0137288123 0.0029288027 431 1305031243.8788089752 0.1098491475 0.0947752685 0.1310649216 0.0311817575 0.1494360000 417297091 0 402718720 -0.0457731932 0.0187316760 -0.0008710809 432 1305031243.9140000343 0.1036668047 0.0947958508 0.1310649216 0.0315062395 0.1013520000 397214012 0 402718720 -0.0448127463 0.0190700926 0.0033227801 433 1305031243.9470779896 0.0977951661 0.0948027776 0.1310649216 0.0316665660 0.1189030000 397294672 0 402718720 -0.0381780416 0.0286304839 0.0071482630 434 1305031243.9816520214 0.1005995721 0.0948161343 0.1310649216 0.0318257455 0.1160540000 397297336 0 402718720 -0.0335810035 0.0227377154 0.0072895996 435 1305031244.0112700462 0.1026213691 0.0948340774 0.1310649216 0.0319215084 0.1120930000 397299820 0 402718720 -0.0262100622 0.0202021580 0.0094408672 436 1305031244.0438230038 0.0980236232 0.0948413928 0.1310649216 0.0319417608 0.1073560000 405677280 0 402718720 -0.0272658169 0.0295371003 0.0097106267 437 1305031244.0818090439 0.0933385193 0.0948379538 0.1310649216 0.0319907771 0.1156710000 414262520 0 402718720 -0.0274888091 0.0341223516 0.0136426706 438 1305031244.1127901077 0.0982059538 0.0948456433 0.1310649216 0.0320839156 0.0643380000 420711533 0 402718720 -0.0255940966 0.0302246474 0.0113056153 439 1305031244.1484949589 0.0979067385 0.0948526161 0.1310649216 0.0320878651 0.0372600000 419526480 0 402718720 -0.0264903978 0.0351416208 0.0101419594 440 1305031244.1824309826 0.0932884216 0.0948490612 0.1310649216 0.0321680231 0.1105030000 419352711 0 402718720 -0.0240397267 0.0421703160 0.0145859132 441 1305031244.2124009132 0.0925531164 0.0948438549 0.1310649216 0.0322843794 0.0379240000 421317063 0 402718720 -0.0231503025 0.0442408919 0.0163279343 442 1305031244.2473471165 0.0863754079 0.0948246955 0.1310649216 0.0324376448 0.0395570000 418965408 0 402718720 -0.0250159632 0.0513116419 0.0194201134 443 1305031244.2831470966 0.0820797980 0.0947959260 0.1310649216 0.0325829491 0.1474010000 418913245 0 402718720 -0.0244712047 0.0581772476 0.0206267685 444 1305031244.3137950897 0.0766512975 0.0947550597 0.1310649216 0.0327423146 0.0538720000 397804320 0 402718720 -0.0226274878 0.0650818050 0.0244099535 445 1305031244.3459599018 0.0695917755 0.0946985130 0.1310649216 0.0329396997 0.1249000000 397900304 0 402718720 -0.0217086449 0.0706526414 0.0309466943 446 1305031244.3808560371 0.0724214762 0.0946485645 0.1310649216 0.0331120930 0.1195690000 397899960 0 402718720 -0.0191338658 0.0724196658 0.0274468586 447 1305031244.4130189419 0.0690466687 0.0945912896 0.1310649216 0.0333529832 0.1142640000 397903364 0 402718720 -0.0172769614 0.0762785301 0.0316009186 448 1305031244.4451670647 0.0677141175 0.0945312959 0.1310649216 0.0334434284 0.1113710000 405869800 0 402718720 -0.0173683912 0.0808467045 0.0322750323 449 1305031244.4806590080 0.0675070658 0.0944711083 0.1310649216 0.0335006205 0.1198030000 414771548 0 402718720 -0.0210837014 0.0882864743 0.0279309414 450 1305031244.5142281055 0.0731637403 0.0944237586 0.1310649216 0.0336212751 0.0506570000 421030769 0 402718720 -0.0187009014 0.0871060491 0.0265862271 451 1305031244.5462141037 0.0710067824 0.0943718363 0.1310649216 0.0336139207 0.0759420000 419709441 0 402718720 -0.0222672448 0.0929827690 0.0272355936 452 1305031244.5808050632 0.0679725036 0.0943134307 0.1310649216 0.0336683245 0.0558430000 421032441 0 402718720 -0.0244680010 0.0954963118 0.0313018709 453 1305031244.6132769585 0.0712742582 0.0942625716 0.1310649216 0.0337562263 0.0368690000 419302481 0 402718720 -0.0254817531 0.0946774557 0.0303763580 454 1305031244.6428399086 0.0718801692 0.0942132711 0.1310649216 0.0337464994 0.1615790000 419256641 0 402718720 -0.0283046030 0.0982553884 0.0283338930 455 1305031244.6806099415 0.0705426708 0.0941612478 0.1310649216 0.0338273242 0.1099680000 398290944 0 402718720 -0.0292657167 0.0993632227 0.0323049724 456 1305031244.7152500153 0.0718010515 0.0941122123 0.1310649216 0.0338579192 0.1271360000 398417052 0 402718720 -0.0321282111 0.1025040522 0.0308668278 457 1305031244.7458879948 0.0735274330 0.0940671690 0.1310649216 0.0340737933 0.1264260000 398418916 0 402718720 -0.0291481819 0.1013789773 0.0321794115 458 1305031244.7818510532 0.0770071670 0.0940299201 0.1310649216 0.0341734136 0.1102980000 398760848 0 402718720 -0.0245130323 0.1003684253 0.0313249789 459 1305031244.8140940666 0.0719636977 0.0939818455 0.1310649216 0.0350474186 0.1163310000 412888864 0 402718720 -0.0255889669 0.1031339020 0.0377642326 460 1305031244.8418219090 0.0655171201 0.0939199657 0.1310649216 0.0350313012 0.0747250000 423540949 0 402718720 -0.0262536891 0.1080324724 0.0420556739 461 1305031244.8818008900 0.0699097887 0.0938678829 0.1310649216 0.0350000931 0.0375320000 420929333 0 402718720 -0.0226137377 0.1091564745 0.0365048721 462 1305031244.9149079323 0.0661509261 0.0938078895 0.1310649216 0.0349838162 0.1094690000 421007265 0 402718720 -0.0218174383 0.1122475266 0.0393517166 463 1305031244.9458680153 0.0687291324 0.0937537237 0.1310649216 0.0349484920 0.0404510000 423639277 0 402718720 -0.0184717476 0.1121742949 0.0381084010 464 1305031244.9818000793 0.0647921488 0.0936913065 0.1310649216 0.0349627496 0.0363120000 420644649 0 402718720 -0.0234746225 0.1155029684 0.0424886011 465 1305031245.0140550137 0.0561777540 0.0936106322 0.1310649216 0.0349329005 0.1358960000 420418627 0 402718720 -0.0219821557 0.1180309355 0.0523327440 466 1305031245.0464398861 0.0662808940 0.0935519847 0.1310649216 0.0349051680 0.1139940000 398385032 0 402718720 -0.0212793853 0.1200783402 0.0398705155 467 1305031245.0817689896 0.0561358817 0.0934718646 0.1310649216 0.0348967796 0.0362950000 398927860 0 402718720 -0.0265268274 0.1200270653 0.0518190041 468 1305031245.1143150330 0.0566759445 0.0933932408 0.1310649216 0.0349017787 0.1205120000 398931400 0 402718720 -0.0252659451 0.1180166304 0.0535975769 469 1305031245.1457099915 0.0608228408 0.0933237943 0.1310649216 0.0348846404 0.1236250000 398933968 0 402718720 -0.0275741853 0.1167022809 0.0489489064 470 1305031245.1818709373 0.0573352799 0.0932472230 0.1310649216 0.0348989059 0.1168920000 398937532 0 402718720 -0.0288095400 0.1121072024 0.0545694195 471 1305031245.2140939236 0.0584624819 0.0931733701 0.1310649216 0.0350062384 0.1090460000 399340828 0 402718720 -0.0282740407 0.1095028967 0.0521432012 472 1305031245.2487950325 0.0610544905 0.0931053216 0.1310649216 0.0353363918 0.1124790000 414051116 0 402718720 -0.0348462835 0.1073834524 0.0455343015 473 1305031245.2807950974 0.0620008484 0.0930395616 0.1310649216 0.0354076101 0.0669880000 424164877 0 402718720 -0.0390191227 0.1034490243 0.0426675901 474 1305031245.3143179417 0.0608769171 0.0929717079 0.1310649216 0.0355766493 0.0358480000 421471961 0 402718720 -0.0330319703 0.0992819145 0.0438160524 475 1305031245.3491809368 0.0629085675 0.0929084171 0.1310649216 0.0358432285 0.1084200000 421418711 0 402718720 -0.0337261520 0.1003797352 0.0362333693 476 1305031245.3806860447 0.0585639961 0.0928362650 0.1310649216 0.0361504409 0.0383470000 424601611 0 402718720 -0.0412084498 0.0975494906 0.0347547308 477 1305031245.4133110046 0.0696775466 0.0927877142 0.1310649216 0.0362703717 0.0365800000 421174943 0 402718720 -0.0346488729 0.0906599984 0.0235297568 478 1305031245.4489970207 0.0789008364 0.0927586621 0.1310649216 0.0362999169 0.1601370000 420990141 0 402718720 -0.0316436142 0.0801535845 0.0141483219 479 1305031245.4846711159 0.0754825696 0.0927225951 0.1310649216 0.0365995195 0.1147630000 398940892 0 402718720 -0.0324158370 0.0842193887 0.0125405611 480 1305031245.5124320984 0.0790211409 0.0926940504 0.1310649216 0.0366872875 0.0395240000 399514164 0 402718720 -0.0314096771 0.0806825310 0.0085237836 481 1305031245.5481460094 0.0823187679 0.0926724802 0.1310649216 0.0368689283 0.1251700000 399497868 0 402718720 -0.0330238342 0.0794226080 0.0019266377 482 1305031245.5786890984 0.0835329220 0.0926535185 0.1310649216 0.0368925024 0.1191560000 399500392 0 402718720 -0.0306228772 0.0776367337 0.0010796702 483 1305031245.6104750633 0.0879176632 0.0926437134 0.1310649216 0.0369654683 0.1120840000 399839228 0 402718720 -0.0293789469 0.0697341636 -0.0025035255 484 1305031245.6494629383 0.0893266723 0.0926368600 0.1310649216 0.0371791251 0.1148210000 412100548 0 402718720 -0.0295145866 0.0694388673 -0.0051955869 485 1305031245.6802349091 0.0933449343 0.0926383199 0.1310649216 0.0372078492 0.1016310000 418746808 0 402718720 -0.0284567550 0.0708955154 -0.0093426071 486 1305031245.7110319138 0.0956421271 0.0926445006 0.1310649216 0.0372150262 0.0426710000 424718221 0 402718720 -0.0261083022 0.0655082315 -0.0092695821 487 1305031245.7497749329 0.0966483876 0.0926527221 0.1310649216 0.0372985471 0.0748900000 422047305 0 402718720 -0.0256531369 0.0668801963 -0.0100437310 488 1305031245.7818500996 0.0971407518 0.0926619189 0.1310649216 0.0373766871 0.0697680000 424727705 0 402718720 -0.0256999992 0.0711555332 -0.0113972947 489 1305031245.8135690689 0.0944075584 0.0926654887 0.1310649216 0.0375312719 0.0359410000 421619273 0 402718720 -0.0269187056 0.0737012327 -0.0080892351 490 1305031245.8491089344 0.1006426290 0.0926817686 0.1310649216 0.0375505215 0.1525520000 421604933 0 402718720 -0.0252239183 0.0644430369 -0.0126419039 491 1305031245.8820281029 0.1043294743 0.0927054910 0.1310649216 0.0376046238 0.1181310000 399432307 0 402718720 -0.0280190799 0.0641820431 -0.0195816010 492 1305031245.9126079082 0.1026496664 0.0927257028 0.1310649216 0.0376255509 0.0417860000 399914768 0 402718720 -0.0324526355 0.0617904067 -0.0197453797 493 1305031245.9458959103 0.1016526669 0.0927438102 0.1310649216 0.0377002939 0.1279730000 400021280 0 402718720 -0.0386359766 0.0585104376 -0.0217760019 494 1305031245.9808180332 0.1056080461 0.0927698512 0.1310649216 0.0377389146 0.1235150000 400022020 0 402718720 -0.0358274430 0.0568960458 -0.0246526971 495 1305031246.0110030174 0.1027011871 0.0927899145 0.1310649216 0.0377593620 0.1207200000 400026600 0 402718720 -0.0404395275 0.0536328182 -0.0235902742 496 1305031246.0483930111 0.1040623710 0.0928126412 0.1310649216 0.0378648905 0.1157700000 400304087 0 402718720 -0.0440156087 0.0497795977 -0.0265989825 497 1305031246.0805249214 0.1061156169 0.0928394078 0.1310649216 0.0379434949 0.1131500000 417394338 0 402718720 -0.0526799113 0.0435201228 -0.0317455195 498 1305031246.1123559475 0.1071542799 0.0928681525 0.1310649216 0.0380685718 0.0567370000 425374317 0 402718720 -0.0557216629 0.0442803018 -0.0348398946 499 1305031246.1484489441 0.1129342765 0.0929083651 0.1310649216 0.0381726330 0.0390030000 422839071 0 402718720 -0.0500580147 0.0396417901 -0.0365220346 500 1305031246.1805961132 0.1176669002 0.0929578822 0.1310649216 0.0382261981 0.1197420000 422744135 0 402718720 -0.0430438444 0.0377666019 -0.0363973975 501 1305031246.2111370564 0.1149821356 0.0930018428 0.1310649216 0.0383497156 0.0393330000 425810069 0 402718720 -0.0541434847 0.0348162986 -0.0386559702 502 1305031246.2469689846 0.1163571551 0.0930483673 0.1310649216 0.0385023605 0.0396750000 422330565 0 402718720 -0.0562596656 0.0343121253 -0.0402683094 503 1305031246.2796959877 0.1198608801 0.0931016725 0.1310649216 0.0385824731 0.1632140000 422212983 0 402718720 -0.0608565882 0.0280462466 -0.0442950800 504 1305031246.3124730587 0.1277853400 0.0931704893 0.1310649216 0.0387149201 0.0965720000 400546184 0 402718720 -0.0565405078 0.0246724878 -0.0483683124 505 1305031246.3482720852 0.1299472600 0.0932433146 0.1310649216 0.0388457963 0.1330380000 400641328 0 402718720 -0.0618157126 0.0217359196 -0.0510455407 506 1305031246.3782060146 0.1291849464 0.0933143455 0.1310649216 0.0390367953 0.1292620000 400643972 0 402718720 -0.0596051328 0.0254234280 -0.0479198024 507 1305031246.4156370163 0.1256822348 0.0933781875 0.1310649216 0.0391971703 0.1207180000 400919912 0 402718720 -0.0624535345 0.0288401376 -0.0428873375 508 1305031246.4452888966 0.1237081438 0.0934378921 0.1310649216 0.0393212244 0.1178710000 412550136 0 402718720 -0.0660977140 0.0309485476 -0.0410188325 509 1305031246.4774649143 0.1277919412 0.0935053854 0.1310649216 0.0394450796 0.1002320000 421771388 0 402718720 -0.0677975640 0.0298028495 -0.0442781746 510 1305031246.5163950920 0.1223017722 0.0935618489 0.1310649216 0.0396109428 0.0719840000 423036108 0 402718720 -0.0758005753 0.0335181914 -0.0404264517 511 1305031246.5491750240 0.1213290766 0.0936161879 0.1310649216 0.0397489335 0.0825660000 424586797 0 402718720 -0.0735381767 0.0372848101 -0.0363620147 512 1305031246.5795109272 0.1176932454 0.0936632134 0.1310649216 0.0398485319 0.0384790000 422520597 0 402718720 -0.0761945471 0.0444592498 -0.0335970037 513 1305031246.6164529324 0.1261555701 0.0937265513 0.1310649216 0.0399504741 0.0389580000 422602919 0 402718720 -0.0824277624 0.0392385609 -0.0431108288 514 1305031246.6477630138 0.1270002425 0.0937912861 0.1310649216 0.0399884549 0.1397820000 422561977 0 402718720 -0.0788483694 0.0384091213 -0.0385073833 515 1305031246.6807579994 0.1194970980 0.0938412003 0.1310649216 0.0401134754 0.1163580000 400682619 0 402718720 -0.0883203745 0.0474856570 -0.0372961909 516 1305031246.7169740200 0.1254523098 0.0939024621 0.1310649216 0.0402661121 0.0373940000 401197748 0 402718720 -0.0767420158 0.0478225015 -0.0349522643 517 1305031246.7491660118 0.1239703670 0.0939606206 0.1310649216 0.0403687614 0.1283350000 401290264 0 402718720 -0.0784259588 0.0513552167 -0.0345377848 518 1305031246.7808170319 0.1224411055 0.0940156022 0.1310649216 0.0404491661 0.1235510000 401295448 0 402718720 -0.0772677958 0.0551165193 -0.0317745171 519 1305031246.8168079853 0.1352568418 0.0940950651 0.1352568418 0.0405176613 0.1166340000 401563496 0 402718720 -0.0752629638 0.0511224568 -0.0444801487 520 1305031246.8488121033 0.1396484822 0.0941826678 0.1396484822 0.0405593075 0.1129010000 411176924 0 402718720 -0.0757594407 0.0510242507 -0.0506501496 521 1305031246.8806428909 0.1258285940 0.0942434085 0.1396484822 0.0406389894 0.1148980000 418064244 0 402718720 -0.0820095837 0.0597657412 -0.0408395976 522 1305031246.9166710377 0.1261503696 0.0943045330 0.1396484822 0.0407293349 0.0422260000 423813065 0 402718720 -0.0761645883 0.0602897108 -0.0376153030 523 1305031246.9495339394 0.1343545765 0.0943811105 0.1396484822 0.0407544065 0.0851010000 422382881 0 402718720 -0.0796021819 0.0577458516 -0.0501965620 524 1305031246.9775969982 0.1363594979 0.0944612219 0.1396484822 0.0407547570 0.0456590000 423734525 0 402718720 -0.0808761343 0.0569273382 -0.0540656708 525 1305031247.0167899132 0.1300718039 0.0945290516 0.1396484822 0.0408638437 0.0363410000 422191696 0 402718720 -0.0817956850 0.0602633245 -0.0490675643 526 1305031247.0479340553 0.1285572648 0.0945937440 0.1396484822 0.0408427731 0.1663440000 421977731 0 402718720 -0.0860786065 0.0585172288 -0.0511700250 527 1305031247.0778899193 0.1331779510 0.0946669589 0.1396484822 0.0408444010 0.1072510000 401254732 0 402718720 -0.0836497024 0.0591865107 -0.0587754659 528 1305031247.1162130833 0.1276369542 0.0947294020 0.1396484822 0.0408370567 0.0394040000 401849520 0 402718720 -0.1004034653 0.0634826347 -0.0675625205 529 1305031247.1473660469 0.1284857243 0.0947932136 0.1396484822 0.0408302666 0.1285700000 401941924 0 402718720 -0.0990316644 0.0641749129 -0.0699274167 530 1305031247.1796920300 0.1289430261 0.0948576472 0.1396484822 0.0407944677 0.1297950000 401944744 0 402718720 -0.0993032753 0.0609489456 -0.0703999475 531 1305031247.2169430256 0.1278854609 0.0949198465 0.1396484822 0.0407694040 0.1198680000 402221360 0 402718720 -0.1000917181 0.0599754713 -0.0703858659 532 1305031247.2487928867 0.1269083470 0.0949799752 0.1396484822 0.0407457369 0.1217920000 415913296 0 402718720 -0.1004134789 0.0608439185 -0.0705664009 533 1305031247.2794220448 0.1295748502 0.0950448812 0.1396484822 0.0407249309 0.0855580000 423271498 0 402718720 -0.1013699397 0.0601022281 -0.0741330311 534 1305031247.3166429996 0.1291660815 0.0951087786 0.1396484822 0.0407301872 0.0423000000 421858933 0 402718720 -0.1016483456 0.0559596680 -0.0701064989 535 1305031247.3477900028 0.1317671984 0.0951772990 0.1396484822 0.0408004056 0.0992200000 421973907 0 402718720 -0.1068627834 0.0559613816 -0.0734452382 536 1305031247.3786110878 0.1359137744 0.0952532999 0.1396484822 0.0408254787 0.0390910000 421436173 0 402718720 -0.1016529351 0.0536266081 -0.0743308589 537 1305031247.4168620110 0.1389136910 0.0953346041 0.1396484822 0.0408883006 0.1610980000 421493047 0 402718720 -0.1003964394 0.0505062677 -0.0734198019 538 1305031247.4487700462 0.1432623565 0.0954236892 0.1432623565 0.0410773285 0.1110800000 401892060 0 402718720 -0.0997260734 0.0493182354 -0.0759052336 539 1305031247.4802629948 0.1424288750 0.0955108973 0.1432623565 0.0411497548 0.0382610000 402485192 0 402718720 -0.1014177874 0.0533082597 -0.0761730745 540 1305031247.5178461075 0.1467738003 0.0956058286 0.1467738003 0.0412552561 0.1358160000 402575980 0 402718720 -0.0996262506 0.0508624651 -0.0761588588 541 1305031247.5459010601 0.1439319104 0.0956951559 0.1467738003 0.0413723682 0.1298370000 402578596 0 402718720 -0.0998510197 0.0537991785 -0.0731494874 542 1305031247.5779209137 0.1476631165 0.0957910378 0.1476631165 0.0414712716 0.1226990000 402861572 0 402718720 -0.0949253663 0.0526004061 -0.0735104159 543 1305031247.6152799129 0.1490009278 0.0958890302 0.1490009278 0.0416504056 0.1185140000 412485364 0 402718720 -0.0952934027 0.0524423607 -0.0746101364 544 1305031247.6484000683 0.1462349594 0.0959815779 0.1490009278 0.0417873559 0.1072330000 419814296 0 402718720 -0.0922769606 0.0539093874 -0.0704754964 545 1305031247.6835579872 0.1431381106 0.0960681036 0.1490009278 0.0419756280 0.0394910000 423858617 0 402718720 -0.0902937129 0.0558286756 -0.0672824979 546 1305031247.7159609795 0.1452815831 0.0961582382 0.1490009278 0.0421853096 0.1123780000 422162079 0 402718720 -0.0847342461 0.0551844612 -0.0669775158 547 1305031247.7469019890 0.1420744359 0.0962421801 0.1490009278 0.0424869239 0.0397200000 421906709 0 402718720 -0.0746855587 0.0544175468 -0.0566529445 548 1305031247.7822608948 0.1443378180 0.0963299458 0.1490009278 0.0426921227 0.1566210000 421997099 0 402718720 -0.0869519711 0.0509283468 -0.0702706426 549 1305031247.8139829636 0.1421607882 0.0964134264 0.1490009278 0.0429817481 0.1084790000 403097868 0 402718720 -0.0869370326 0.0481157266 -0.0694483817 550 1305031247.8484420776 0.1494303197 0.0965098208 0.1494303197 0.0431970672 0.1413090000 403180644 0 402718720 -0.0672894344 0.0431638211 -0.0652578920 551 1305031247.8820719719 0.1493359953 0.0966056940 0.1494303197 0.0432744948 0.1285570000 403183268 0 402718720 -0.0742059648 0.0356196389 -0.0699853748 552 1305031247.9173319340 0.1412928998 0.0966866491 0.1494303197 0.0432449335 0.1298910000 403429820 0 402718720 -0.0788890794 0.0536380224 -0.0775994956 553 1305031247.9496860504 0.1482231468 0.0967798435 0.1494303197 0.0433340471 0.1439390000 415305296 0 402718720 -0.0645358488 0.0545970835 -0.0806762949 554 1305031247.9861450195 0.1488708705 0.0968738706 0.1494303197 0.0435505782 0.1286290000 423427544 0 402718720 -0.0553469658 0.0436110497 -0.0750809759 555 1305031248.0181560516 0.1462465823 0.0969628305 0.1494303197 0.0435277609 0.0558230000 426265513 0 402718720 -0.0564999320 0.0523828715 -0.0827318355 556 1305031248.0499138832 0.1430612803 0.0970457414 0.1494303197 0.0435657335 0.1279740000 424628661 0 402718720 -0.0534460060 0.0585865453 -0.0839719400 557 1305031248.0857460499 0.1457660347 0.0971332105 0.1494303197 0.0438181019 0.0578880000 426201137 0 402718720 -0.0380748436 0.0493101664 -0.0788810998 558 1305031248.1175789833 0.1438320577 0.0972169002 0.1494303197 0.0438431066 0.0546130000 424249904 0 402718720 -0.0354807787 0.0520004779 -0.0816071555 559 1305031248.1493461132 0.1386886835 0.0972910894 0.1494303197 0.0438483064 0.1744610000 424183131 0 402718720 -0.0338188633 0.0575428717 -0.0815864354 560 1305031248.1848630905 0.1434200406 0.0973734625 0.1494303197 0.0440327890 0.0780360000 403615308 0 402718720 -0.0223481022 0.0520239659 -0.0824923068 561 1305031248.2167689800 0.1426473409 0.0974541646 0.1494303197 0.0440697294 0.1323770000 403718364 0 402718720 -0.0158143342 0.0523663014 -0.0798519850 562 1305031248.2488510609 0.1384595484 0.0975271279 0.1494303197 0.0440940156 0.1228140000 403721096 0 402718720 -0.0221239142 0.0548543185 -0.0865811408 563 1305031248.2847399712 0.1406098753 0.0976036515 0.1494303197 0.0441532988 0.1165650000 404059252 0 402718720 -0.0111720003 0.0613555312 -0.0847193301 564 1305031248.3161809444 0.1438860595 0.0976857125 0.1494303197 0.0442311742 0.1150950000 413738916 0 402718720 -0.0039409287 0.0610406324 -0.0847528577 565 1305031248.3488430977 0.1381746083 0.0977573742 0.1494303197 0.0442980825 0.1139230000 419814757 0 402718720 -0.0060685873 0.0608732775 -0.0809541047 566 1305031248.3881969452 0.1343243271 0.0978219802 0.1494303197 0.0443000206 0.0612270000 427470809 0 402718720 -0.0098801143 0.0650379062 -0.0834548324 567 1305031248.4155070782 0.1367703676 0.0978906722 0.1494303197 0.0443371696 0.0605190000 424881501 0 402718720 -0.0058508627 0.0674213693 -0.0850928277 568 1305031248.4482519627 0.1351997256 0.0979563572 0.1494303197 0.0443488308 0.0958090000 426175897 0 402718720 -0.0053083003 0.0703302622 -0.0847487226 569 1305031248.4852969646 0.1385545731 0.0980277073 0.1494303197 0.0444039456 0.0512420000 424388341 0 402718720 -0.0007464662 0.0679286718 -0.0861736163 570 1305031248.5154309273 0.1378588825 0.0980975865 0.1494303197 0.0443764600 0.0499940000 424392953 0 402718720 0.0007074326 0.0727029443 -0.0849607140 571 1305031248.5470030308 0.1356675476 0.0981633833 0.1494303197 0.0444034310 0.1484840000 424284223 0 402718720 0.0038977191 0.0753283203 -0.0792225599 572 1305031248.5860579014 0.1352528334 0.0982282250 0.1494303197 0.0444710950 0.1109010000 403679620 0 402718720 0.0061514117 0.0736041814 -0.0791007429 573 1305031248.6180379391 0.1280933768 0.0982803457 0.1494303197 0.0445052574 0.0519730000 404064252 0 402718720 -0.0007309392 0.0746323615 -0.0770036727 574 1305031248.6494390965 0.1256676763 0.0983280588 0.1494303197 0.0444931878 0.1015770000 404203896 0 402718720 -0.0019344985 0.0803714320 -0.0772407576 575 1305031248.6860280037 0.1285461485 0.0983806120 0.1494303197 0.0445418762 0.1085060000 404205796 0 402718720 0.0010123402 0.0862835050 -0.0817571953 576 1305031248.7199230194 0.1262694150 0.0984290301 0.1494303197 0.0445556061 0.1033240000 404212548 0 402718720 0.0019322634 0.0876515657 -0.0790856332 577 1305031248.7498369217 0.1248521507 0.0984748240 0.1494303197 0.0446235558 0.0969730000 404547573 0 402718720 0.0023768246 0.0886206180 -0.0786699727 578 1305031248.7856750488 0.1152426526 0.0985038341 0.1494303197 0.0446619487 0.0940050000 420540894 0 402718720 -0.0005349666 0.0911310986 -0.0700867176 579 1305031248.8181409836 0.1066630036 0.0985179260 0.1494303197 0.0446324772 0.0515420000 426395509 0 402718720 -0.0039906800 0.1075023264 -0.0666201860 580 1305031248.8496789932 0.1043321267 0.0985279504 0.1494303197 0.0446692543 0.0321360000 425087465 0 402718720 -0.0012951046 0.1086561903 -0.0640669093 581 1305031248.8855929375 0.0970394909 0.0985253885 0.1494303197 0.0446660969 0.0808130000 424934721 0 402718720 -0.0034300648 0.1157299951 -0.0622176826 582 1305031248.9178819656 0.0999300107 0.0985278020 0.1494303197 0.0446411192 0.0479600000 426413169 0 402718720 0.0017904565 0.1186018139 -0.0654226094 583 1305031248.9526810646 0.0933001414 0.0985188352 0.1494303197 0.0446643723 0.0323410000 424613441 0 402718720 0.0044001937 0.1191863343 -0.0569895394 584 1305031248.9845540524 0.0922200084 0.0985080495 0.1494303197 0.0446613182 0.1347370000 424615837 0 402718720 0.0044019669 0.1209497228 -0.0619793162 585 1305031249.0169510841 0.0923204869 0.0984974725 0.1494303197 0.0446572087 0.1062710000 404552732 0 402718720 0.0080992281 0.1255440861 -0.0597822443 586 1305031249.0523660183 0.0911371782 0.0984849122 0.1494303197 0.0446361356 0.0906950000 404701032 0 402718720 0.0079829302 0.1257165223 -0.0596038848 587 1305031249.0845029354 0.0928265899 0.0984752728 0.1494303197 0.0446206494 0.1021490000 404704364 0 402718720 0.0070999935 0.1277419329 -0.0621070825 588 1305031249.1168839931 0.0897777006 0.0984604811 0.1494303197 0.0445883490 0.0971500000 404742317 0 402718720 0.0096913353 0.1268023700 -0.0528753810 589 1305031249.1534469128 0.0909871012 0.0984477928 0.1494303197 0.0445580151 0.0928420000 412235460 0 402718720 0.0061359406 0.1313181221 -0.0544761457 590 1305031249.1847391129 0.0950628370 0.0984420556 0.1494303197 0.0445439491 0.0902450000 423846436 0 402718720 0.0059903972 0.1275786906 -0.0575785190 591 1305031249.2168650627 0.0950172469 0.0984362607 0.1494303197 0.0445163576 0.0339760000 427002433 0 402718720 0.0076785460 0.1205908358 -0.0525688305 592 1305031249.2532238960 0.0976482406 0.0984349295 0.1494303197 0.0444896277 0.0760790000 425225611 0 402718720 0.0085237473 0.1226854101 -0.0525566377 593 1305031249.2848041058 0.0951851010 0.0984294492 0.1494303197 0.0444771055 0.0526630000 426540409 0 402718720 0.0120949410 0.1161671579 -0.0419410840 594 1305031249.3174340725 0.0950621292 0.0984237803 0.1494303197 0.0444495472 0.0337050000 424861591 0 402718720 0.0110231861 0.1170186996 -0.0413387232 595 1305031249.3527359962 0.0861626491 0.0984031734 0.1494303197 0.0444165900 0.0354740000 424770005 0 402718720 0.0019211434 0.1232264042 -0.0379093252 596 1305031249.3847539425 0.0851013064 0.0983808548 0.1494303197 0.0444090647 0.1259640000 424699289 0 402718720 0.0049185399 0.1146892905 -0.0296189953 597 1305031249.4178340435 0.0817590952 0.0983530127 0.1494303197 0.0444475961 0.0965180000 404669528 0 402718720 0.0036463439 0.1150270179 -0.0248069186 598 1305031249.4537220001 0.0850739852 0.0983308069 0.1494303197 0.0444897606 0.0358290000 405145120 0 402718720 0.0017848108 0.1182775125 -0.0316877775 599 1305031249.4859149456 0.0867927969 0.0983115448 0.1494303197 0.0445281656 0.1023970000 405176524 0 402718720 0.0000116415 0.1173049808 -0.0360041037 600 1305031249.5177340508 0.0904180259 0.0982983890 0.1494303197 0.0445355151 0.1000020000 405179184 0 402718720 0.0033053141 0.1154617667 -0.0372178033 601 1305031249.5543251038 0.0962693766 0.0982950129 0.1494303197 0.0446511546 0.0926360000 405539128 0 402718720 0.0070906281 0.1085680425 -0.0415313542 602 1305031249.5859050751 0.1000238582 0.0982978847 0.1494303197 0.0448277282 0.0964440000 417436636 0 402718720 0.0023331456 0.1137359217 -0.0530861393 603 1305031249.6180789471 0.0979332700 0.0982972801 0.1494303197 0.0448558862 0.0914330000 423807796 0 402718720 -0.0010875016 0.1059091687 -0.0532390177 604 1305031249.6542129517 0.0999194384 0.0982999658 0.1494303197 0.0450984310 0.0343810000 427072677 0 402718720 0.0013593696 0.1034530923 -0.0525719076 605 1305031249.6856739521 0.1126170307 0.0983236303 0.1494303197 0.0451979237 0.0667850000 425578493 0 402718720 0.0110568926 0.1029641926 -0.0587837100 606 1305031249.7177898884 0.1062357128 0.0983366866 0.1494303197 0.0453094509 0.0602790000 427176973 0 402718720 0.0015159547 0.1069591492 -0.0596812665 607 1305031249.7539620399 0.1138051376 0.0983621700 0.1494303197 0.0453907281 0.0343960000 425097017 0 402718720 0.0152397472 0.1021370739 -0.0505736917 608 1305031249.7854170799 0.1210734397 0.0983995241 0.1494303197 0.0454332213 0.0339150000 425227303 0 402718720 0.0159870405 0.0910215974 -0.0601170361 609 1305031249.8186020851 0.1222372577 0.0984386665 0.1494303197 0.0454449666 0.1288640000 425055315 0 402718720 0.0130433124 0.0857432783 -0.0625216141 610 1305031249.8537468910 0.1347332746 0.0984981659 0.1494303197 0.0455801754 0.1100910000 405646588 0 402718720 0.0282378532 0.0822068304 -0.0605290234 611 1305031249.8855249882 0.1341773123 0.0985565605 0.1494303197 0.0455984420 0.1055470000 405771900 0 402718720 0.0262467898 0.0799131915 -0.0604972392 612 1305031249.9170649052 0.1284699887 0.0986054387 0.1494303197 0.0456154162 0.1085730000 405775824 0 402718720 0.0160908699 0.0692133754 -0.0625931323 613 1305031249.9533979893 0.1304617077 0.0986574065 0.1494303197 0.0456260597 0.1053800000 405780312 0 402718720 0.0140264444 0.0656763986 -0.0660681054 614 1305031249.9851789474 0.1298885196 0.0987082715 0.1494303197 0.0456322261 0.0952640000 406124056 0 402718720 0.0093037169 0.0596758723 -0.0681081340 615 1305031250.0164399147 0.1352358460 0.0987676659 0.1494303197 0.0456279116 0.0971320000 419751860 0 402718720 0.0123162419 0.0630596876 -0.0708675012 616 1305031250.0531940460 0.1284432560 0.0988158406 0.1494303197 0.0457224555 0.0684390000 426738872 0 402718720 -0.0046073347 0.0513812378 -0.0729218274 617 1305031250.0845069885 0.1185234636 0.0988477816 0.1494303197 0.0458223200 0.0329150000 428197434 0 402718720 -0.0204746444 0.0512025431 -0.0700176582 618 1305031250.1208500862 0.1290470362 0.0988966477 0.1494303197 0.0459088885 0.1167640000 428020547 0 402718720 -0.0082747098 0.0560193136 -0.0681356564 619 1305031250.1532480717 0.1221075952 0.0989341452 0.1494303197 0.0461759654 0.0357330000 431764469 0 402718720 -0.0246787444 0.0544057041 -0.0651512295 620 1305031250.1853280067 0.1139029562 0.0989582885 0.1494303197 0.0462107363 0.1429560000 427963623 0 402718720 -0.0364464745 0.0622875430 -0.0596446656 621 1305031250.2214460373 0.1303750575 0.0990088791 0.1494303197 0.0462155799 0.1041200000 406224112 0 402718720 -0.0205045659 0.0553333424 -0.0621406883 622 1305031250.2537350655 0.1287594736 0.0990567096 0.1494303197 0.0463182924 0.1033490000 406356100 0 402718720 -0.0275025927 0.0578743443 -0.0599451885 623 1305031250.2852239609 0.1228561252 0.0990949109 0.1494303197 0.0463236269 0.1165000000 406357888 0 402718720 -0.0442633368 0.0412220433 -0.0595579259 624 1305031250.3208620548 0.1291784048 0.0991431217 0.1494303197 0.0463593988 0.1128630000 406361496 0 402718720 -0.0399283394 0.0451981351 -0.0606942326 625 1305031250.3517000675 0.1308153719 0.0991937973 0.1494303197 0.0463833751 0.1024790000 415359592 0 402718720 -0.0408992134 0.0410272330 -0.0590028316 626 1305031250.3851490021 0.1349243671 0.0992508748 0.1494303197 0.0464021037 0.1122170000 423267476 0 402718720 -0.0418299511 0.0372775532 -0.0589986816 627 1305031250.4215359688 0.1317605078 0.0993027243 0.1494303197 0.0464109594 0.0644140000 431396985 0 402718720 -0.0423300080 0.0379221216 -0.0516409874 628 1305031250.4540181160 0.1343954951 0.0993586046 0.1494303197 0.0465113814 0.0351840000 428559725 0 402718720 -0.0395027846 0.0394919254 -0.0477210358 629 1305031250.4856131077 0.1353059113 0.0994157545 0.1494303197 0.0465131120 0.1055220000 428209399 0 402718720 -0.0410445631 0.0423437171 -0.0468792468 630 1305031250.5215380192 0.1413680017 0.0994823454 0.1494303197 0.0464965828 0.0360440000 431558117 0 402718720 -0.0424740575 0.0365985706 -0.0509958267 631 1305031250.5536580086 0.1448140740 0.0995541864 0.1494303197 0.0464926351 0.0361440000 428188685 0 402718720 -0.0389967784 0.0378586575 -0.0479659736 632 1305031250.5853788853 0.1408137828 0.0996194706 0.1494303197 0.0464975906 0.1401000000 427957777 0 402718720 -0.0500203259 0.0388191752 -0.0491047278 633 1305031250.6213030815 0.1496103853 0.0996984452 0.1496103853 0.0464888906 0.1183120000 406326412 0 402718720 -0.0550828837 0.0350625515 -0.0592341796 634 1305031250.6535439491 0.1495087594 0.0997770104 0.1496103853 0.0465220892 0.0464100000 406816124 0 402718720 -0.0603240915 0.0362605527 -0.0586566851 635 1305031250.6852970123 0.1503956020 0.0998567247 0.1503956020 0.0465462209 0.1183600000 406906232 0 402718720 -0.0565723106 0.0394143201 -0.0544187464 636 1305031250.7216401100 0.1464809328 0.0999300332 0.1503956020 0.0465251430 0.1131180000 406910732 0 402718720 -0.0616761893 0.0429522730 -0.0510384403 637 1305031250.7534279823 0.1493505090 0.1000076164 0.1503956020 0.0465013398 0.1143640000 406930201 0 402718720 -0.0663877279 0.0409052372 -0.0532158501 638 1305031250.7853651047 0.1492982060 0.1000848743 0.1503956020 0.0464822225 0.1054490000 407297137 0 402718720 -0.0673544183 0.0449484810 -0.0532872006 639 1305031250.8217930794 0.1458089352 0.1001564300 0.1503956020 0.0464480689 0.1098660000 424140312 0 402718720 -0.0659723654 0.0472988784 -0.0475499146 640 1305031250.8538279533 0.1382028610 0.1002158775 0.1503956020 0.0464198102 0.0556770000 431792057 0 402718720 -0.0772768483 0.0501249619 -0.0454372540 641 1305031250.8820140362 0.1423910260 0.1002816734 0.1503956020 0.0463857280 0.0353600000 429304333 0 402718720 -0.0767310038 0.0476499237 -0.0485226661 642 1305031250.9217998981 0.1419417113 0.1003465644 0.1503956020 0.0463525052 0.1053340000 428948329 0 402718720 -0.0785357207 0.0507752188 -0.0505007319 643 1305031250.9535419941 0.1451978534 0.1004163176 0.1503956020 0.0463321356 0.0427350000 431937853 0 402718720 -0.0759074315 0.0471650064 -0.0525764525 644 1305031250.9853079319 0.1356588155 0.1004710420 0.1503956020 0.0463043088 0.0393030000 428841889 0 402718720 -0.0816886276 0.0479834676 -0.0450477749 645 1305031251.0214879513 0.1362972856 0.1005265865 0.1503956020 0.0462783987 0.1470340000 428684857 0 402718720 -0.0790580660 0.0491439588 -0.0462230891 646 1305031251.0534679890 0.1370512694 0.1005831263 0.1503956020 0.0462902684 0.1092640000 406972569 0 402718720 -0.0753736496 0.0472985432 -0.0469864644 647 1305031251.0851860046 0.1301716119 0.1006288581 0.1503956020 0.0462945417 0.0332540000 406935044 0 402718720 -0.0817071646 0.0445157737 -0.0443472043 648 1305031251.1214449406 0.1248015389 0.1006661616 0.1503956020 0.0462841861 0.0353800000 406938240 0 402718720 -0.0865929052 0.0450922698 -0.0441595502 649 1305031251.1537809372 0.1285527349 0.1007091301 0.1503956020 0.0464020575 0.0360110000 406941948 0 402718720 -0.0761035010 0.0425611287 -0.0472308025 650 1305031251.1851599216 0.1262486726 0.1007484218 0.1503956020 0.0464368711 0.0401620000 407434596 0 402718720 -0.0786307305 0.0397085398 -0.0493129045 651 1305031251.2204658985 0.1208860576 0.1007793551 0.1503956020 0.0464621946 0.1283280000 407527216 0 402718720 -0.0783801898 0.0386276357 -0.0469354019 652 1305031251.2524240017 0.1237047538 0.1008145168 0.1503956020 0.0465292206 0.1206930000 407530980 0 402718720 -0.0718856230 0.0367433988 -0.0505099148 653 1305031251.2844820023 0.1255414337 0.1008523834 0.1503956020 0.0467482932 0.1136890000 407805660 0 402718720 -0.0694955215 0.0344827883 -0.0562003776 654 1305031251.3190040588 0.1239565313 0.1008877109 0.1503956020 0.0468618120 0.1093420000 417680568 0 402718720 -0.0642417744 0.0336454771 -0.0553542003 655 1305031251.3532440662 0.1213890240 0.1009190106 0.1503956020 0.0469624762 0.1142780000 425039584 0 402718720 -0.0637707561 0.0309646670 -0.0565411821 656 1305031251.3870069981 0.1182624325 0.1009454487 0.1503956020 0.0470052107 0.0556820000 432592077 0 402718720 -0.0609543286 0.0345893167 -0.0554465428 657 1305031251.4210500717 0.1189821884 0.1009729019 0.1503956020 0.0471128560 0.0374240000 430068792 0 402718720 -0.0574910417 0.0327798314 -0.0574129336 658 1305031251.4496629238 0.1204658747 0.1010025265 0.1503956020 0.0472016536 0.1116560000 429875999 0 402718720 -0.0495012850 0.0292035770 -0.0559186116 659 1305031251.4890139103 0.1179047823 0.1010281748 0.1503956020 0.0472956813 0.0371490000 433011701 0 402718720 -0.0472347662 0.0319470689 -0.0565365180 660 1305031251.5207729340 0.1182948872 0.1010543365 0.1503956020 0.0474155556 0.0391740000 429595707 0 402718720 -0.0391821191 0.0295720883 -0.0540850274 661 1305031251.5530450344 0.1201626435 0.1010832447 0.1503956020 0.0475333881 0.1433260000 429362679 0 402718720 -0.0345651619 0.0294425003 -0.0574134812 662 1305031251.5887598991 0.1147037521 0.1011038195 0.1503956020 0.0475737670 0.1207070000 407498464 0 402718720 -0.0323221534 0.0328125767 -0.0516110770 663 1305031251.6208739281 0.1157482937 0.1011259077 0.1503956020 0.0476304958 0.0483340000 407515604 0 402718720 -0.0299423430 0.0327689014 -0.0539147034 664 1305031251.6528749466 0.1132815555 0.1011442144 0.1503956020 0.0477154258 0.0393680000 407518708 0 402718720 -0.0315494612 0.0318052471 -0.0550669953 665 1305031251.6897680759 0.1141531467 0.1011637767 0.1503956020 0.0477530572 0.0446090000 408069724 0 402718720 -0.0319447741 0.0363858193 -0.0592140108 666 1305031251.7204608917 0.1145973280 0.1011839472 0.1503956020 0.0478155664 0.1229530000 408067352 0 402718720 -0.0285175405 0.0372437797 -0.0589097179 667 1305031251.7531440258 0.1138830036 0.1012029862 0.1503956020 0.0479339792 0.1150830000 408068808 0 402718720 -0.0258599073 0.0352025963 -0.0581489019 668 1305031251.7892498970 0.1257797480 0.1012397778 0.1503956020 0.0480038217 0.1039030000 408417048 0 402718720 -0.0154351145 0.0347060151 -0.0652258769 669 1305031251.8209791183 0.1255266517 0.1012760811 0.1503956020 0.0480420844 0.1085960000 421170368 0 402718720 -0.0160644650 0.0388609767 -0.0675397068 670 1305031251.8537969589 0.1238214448 0.1013097309 0.1503956020 0.0481948664 0.1006760000 427793804 0 402718720 -0.0120358150 0.0359359607 -0.0628371760 671 1305031251.8896539211 0.1365243793 0.1013622117 0.1503956020 0.0482127243 0.0369060000 433396619 0 402718720 -0.0032196753 0.0289150067 -0.0708261281 672 1305031251.9219300747 0.1363203824 0.1014142328 0.1503956020 0.0482259333 0.0431740000 430260376 0 402718720 0.0044528134 0.0385108255 -0.0655374676 673 1305031251.9538369179 0.1289658844 0.1014551713 0.1503956020 0.0482494492 0.0858210000 430229373 0 402718720 0.0081271939 0.0522363074 -0.0528347157 674 1305031251.9898068905 0.1297275573 0.1014971185 0.1503956020 0.0482504996 0.0347980000 430022480 0 402718720 0.0079183150 0.0537996963 -0.0554033779 675 1305031252.0221600533 0.1262173355 0.1015337411 0.1503956020 0.0482780351 0.0367380000 429852449 0 402718720 0.0096510388 0.0567896366 -0.0497225486 676 1305031252.0537619591 0.1247810572 0.1015681306 0.1503956020 0.0482916987 0.1343070000 429725523 0 402718720 0.0085614733 0.0586982295 -0.0529860333 677 1305031252.0895619392 0.1194215640 0.1015945020 0.1503956020 0.0483484424 0.1074760000 408075360 0 402718720 0.0115210284 0.0694354624 -0.0463859625 678 1305031252.1221520901 0.1134475619 0.1016119844 0.1503956020 0.0484296269 0.0345030000 408459708 0 402718720 0.0128625687 0.0741195455 -0.0393617600 679 1305031252.1539709568 0.1041948795 0.1016157883 0.1503956020 0.0485705564 0.1070440000 408560416 0 402718720 0.0110110696 0.0776259154 -0.0325900540 680 1305031252.1897890568 0.0935005099 0.1016038541 0.1503956020 0.0485628997 0.1032860000 408562884 0 402718720 0.0040843189 0.0854040459 -0.0279483311 681 1305031252.2220859528 0.1122346222 0.1016194646 0.1503956020 0.0485673321 0.0974660000 408920828 0 402718720 0.0110917389 0.0985471979 -0.0492274016 682 1305031252.2530639172 0.0969333947 0.1016125935 0.1503956020 0.0486390480 0.0989850000 418715980 0 402718720 0.0008588843 0.0992131531 -0.0385867953 683 1305031252.2888779640 0.0837480947 0.1015864376 0.1503956020 0.0487082569 0.0906180000 424508376 0 402718720 -0.0010049716 0.0945665166 -0.0214597303 684 1305031252.3206090927 0.0860001370 0.1015636506 0.1503956020 0.0486826020 0.0441820000 431418969 0 402718720 0.0026074611 0.0982336923 -0.0211757664 685 1305031252.3528549671 0.0821198970 0.1015352656 0.1503956020 0.0486719260 0.0541230000 428913175 0 402718720 -0.0009509418 0.0996484607 -0.0196970105 686 1305031252.3893189430 0.0810576454 0.1015054148 0.1503956020 0.0486550400 0.0856090000 428810893 0 402718720 0.0000420399 0.1027618721 -0.0159808081 687 1305031252.4217019081 0.1000509411 0.1015032977 0.1503956020 0.0486635604 0.0371500000 428472661 0 402718720 0.0119736809 0.1066092774 -0.0303671695 688 1305031252.4538249969 0.0838001445 0.1014775664 0.1503956020 0.0486457758 0.1411930000 428453329 0 402718720 -0.0001615882 0.1037150174 -0.0165165607 689 1305031252.4895589352 0.0843168423 0.1014526597 0.1503956020 0.0486128128 0.1166530000 408614789 0 402718720 -0.0022860523 0.1047037095 -0.0177807584 690 1305031252.5221700668 0.0845383778 0.1014281462 0.1503956020 0.0485867729 0.0362550000 408637521 0 402718720 -0.0030933619 0.1055834591 -0.0173204355 691 1305031252.5537741184 0.0867188573 0.1014068592 0.1503956020 0.0485606136 0.0327500000 408592944 0 402718720 -0.0007673632 0.1045248508 -0.0147110820 692 1305031252.5897459984 0.0987446979 0.1014030122 0.1503956020 0.0485394594 0.0375450000 409057044 0 402718720 0.0055832155 0.1080655903 -0.0253327265 693 1305031252.6221249104 0.0849328712 0.1013792458 0.1503956020 0.0485256600 0.1078440000 409081536 0 402718720 -0.0023311879 0.1041684970 -0.0106218141 694 1305031252.6578559875 0.0830430016 0.1013528246 0.1503956020 0.0485103778 0.1085180000 409085856 0 402718720 -0.0059564710 0.1012635231 -0.0094284993 695 1305031252.6889979839 0.0808378011 0.1013233066 0.1503956020 0.0485316399 0.1003780000 409381712 0 402718720 -0.0086211953 0.1013274565 -0.0073817614 696 1305031252.7216539383 0.0871033221 0.1013028756 0.1503956020 0.0485931470 0.1045430000 421761392 0 402718720 -0.0061293095 0.1047132313 -0.0122151691 697 1305031252.7578220367 0.0882614329 0.1012841648 0.1503956020 0.0487481811 0.0867180000 427004444 0 402718720 -0.0088278521 0.1047461033 -0.0154718067 698 1305031252.7896919250 0.0762454122 0.1012482927 0.1503956020 0.0489328484 0.0463170000 434172821 0 402718720 -0.0164062921 0.1013137400 -0.0034261048 699 1305031252.8224050999 0.0973627046 0.1012427339 0.1503956020 0.0490558275 0.1562780000 431697527 0 402718720 -0.0083609410 0.1000165343 -0.0245391503 700 1305031252.8539779186 0.0963957235 0.1012358096 0.1503956020 0.0490506843 0.1143580000 409506888 0 402718720 -0.0116650537 0.0954411551 -0.0246645473 701 1305031252.8897290230 0.0928193182 0.1012238032 0.1503956020 0.0490906227 0.1045400000 409635656 0 402718720 -0.0178689379 0.0893095806 -0.0233501866 702 1305031252.9206719398 0.1026432365 0.1012258252 0.1503956020 0.0490920934 0.1182170000 409640024 0 402718720 -0.0165981464 0.0898867697 -0.0338038243 703 1305031252.9578649998 0.1084783450 0.1012361417 0.1503956020 0.0491737395 0.1083390000 409947820 0 402718720 -0.0127144530 0.0862201452 -0.0344638787 704 1305031252.9894239902 0.1071806923 0.1012445856 0.1503956020 0.0492380429 0.1056420000 420889308 0 402718720 -0.0167514253 0.0837831199 -0.0323731378 705 1305031253.0196959972 0.1060207039 0.1012513603 0.1503956020 0.0493296587 0.1027400000 427785062 0 402718720 -0.0217612982 0.0838669166 -0.0320182852 706 1305031253.0574259758 0.1074597314 0.1012601540 0.1503956020 0.0493858727 0.0529230000 436035381 0 402718720 -0.0278591737 0.0803096890 -0.0346107446 707 1305031253.0895500183 0.1102722734 0.1012729010 0.1503956020 0.0494311236 0.0364940000 433158581 0 402718720 -0.0311407093 0.0721110702 -0.0383017547 708 1305031253.1197240353 0.1146228462 0.1012917569 0.1503956020 0.0494369802 0.0968670000 433096189 0 402718720 -0.0323714428 0.0686738342 -0.0411465392 709 1305031253.1573839188 0.1145261228 0.1013104231 0.1503956020 0.0495600612 0.0383680000 436111521 0 402718720 -0.0419992246 0.0677514896 -0.0459610000 710 1305031253.1892180443 0.1164584383 0.1013317583 0.1503956020 0.0495944388 0.0352090000 432634417 0 402718720 -0.0433251858 0.0680097714 -0.0473778620 711 1305031253.2180271149 0.1166477650 0.1013532998 0.1503956020 0.0495872201 0.0372840000 432732675 0 402718720 -0.0422274396 0.0688180402 -0.0458503850 712 1305031253.2578470707 0.1180140525 0.1013766998 0.1503956020 0.0495763700 0.1490950000 432443995 0 402718720 -0.0459126271 0.0677180290 -0.0486921817 713 1305031253.2897419930 0.1259503663 0.1014111649 0.1503956020 0.0495452713 0.1445340000 409605392 0 402718720 -0.0406167656 0.0634377673 -0.0532599315 714 1305031253.3220069408 0.1207050830 0.1014381872 0.1503956020 0.0495271175 0.0479480000 409642557 0 402718720 -0.0401258469 0.0593434721 -0.0459589809 715 1305031253.3578300476 0.1242699772 0.1014701198 0.1503956020 0.0495023823 0.0346120000 409625332 0 402718720 -0.0335915051 0.0516195185 -0.0433906615 716 1305031253.3880970478 0.1233535931 0.1015006833 0.1503956020 0.0494690387 0.0357110000 409678741 0 402718720 -0.0331911370 0.0552050881 -0.0425692871 717 1305031253.4213519096 0.1225152686 0.1015299924 0.1503956020 0.0494368799 0.0345580000 409654021 0 402718720 -0.0344911739 0.0529152080 -0.0409216955 718 1305031253.4579629898 0.1153220981 0.1015492014 0.1503956020 0.0494128425 0.0350250000 409668965 0 402718720 -0.0382623598 0.0538562499 -0.0328119993 719 1305031253.4896900654 0.1149606183 0.1015678543 0.1503956020 0.0493801751 0.0330150000 409721605 0 402718720 -0.0402156711 0.0596530959 -0.0343032405 720 1305031253.5207340717 0.1141306907 0.1015853027 0.1503956020 0.0493480384 0.0344280000 409701689 0 402718720 -0.0415855646 0.0582669377 -0.0331778787 721 1305031253.5578539371 0.1209484339 0.1016121586 0.1503956020 0.0493177270 0.0341130000 409687361 0 402718720 -0.0395597294 0.0557049513 -0.0376671702 722 1305031253.5898048878 0.1280954182 0.1016488390 0.1503956020 0.0492888420 0.0346260000 409703821 0 402718720 -0.0393773578 0.0603907183 -0.0457787253 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 10:29:30 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 -nan 0.0271790000 348474212 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0281945895 0.0267967097 0.0281945895 0.0139591014 0.0343860000 357410062 0 402718720 -0.0009190498 0.0071610427 0.0117935762 3 1305031102.2432110310 0.0226332229 0.0254088808 0.0281945895 0.0101465295 0.0307740000 357482209 0 402718720 -0.0016632379 0.0054721385 0.0249857027 4 1305031102.2753260136 0.0196904503 0.0239792732 0.0281945895 0.0089562529 0.0300180000 357384845 0 402718720 -0.0023088544 0.0065494091 0.0368898436 5 1305031102.3112668991 0.0145338643 0.0220901914 0.0281945895 0.0079946935 0.0296700000 357447517 0 402718720 -0.0013972300 0.0047673602 0.0502083600 6 1305031102.3432331085 0.0125662116 0.0205028614 0.0281945895 0.0077827690 0.0296620000 357448525 0 402718720 -0.0023511546 0.0057779932 0.0617818683 7 1305031102.3753290176 0.0107157640 0.0191047047 0.0281945895 0.0072006736 0.0286830000 357449069 0 402718720 -0.0034278757 0.0062853843 0.0740186349 8 1305031102.4112579823 0.0084144687 0.0177684252 0.0281945895 0.0096177394 0.0285610000 357407793 0 402718720 -0.0077655455 0.0117006935 0.0844627470 9 1305031102.4432709217 0.0118218139 0.0171076906 0.0281945895 0.0102540312 0.0315610000 358082907 0 402718720 -0.0070502465 0.0181780979 0.0958909094 10 1305031102.4753179550 0.0123967556 0.0166365971 0.0281945895 0.0096683943 0.0660400000 358644155 0 402718720 -0.0047922716 0.0173527971 0.1098294184 11 1305031102.5112190247 0.0137826027 0.0163771431 0.0281945895 0.0093299108 0.1070280000 360332179 0 402718720 -0.0038494889 0.0181292593 0.1226156726 12 1305031102.5432200432 0.0141728390 0.0161934510 0.0281945895 0.0089587178 0.0428640000 361332089 0 402718720 -0.0065350113 0.0158126373 0.1344525814 13 1305031102.5752859116 0.0216550585 0.0166135747 0.0281945895 0.0090205372 0.0494550000 361298025 0 402718720 -0.0061552450 0.0105422940 0.1489438415 14 1305031102.6112329960 0.0233825464 0.0170970727 0.0281945895 0.0087286386 0.1061190000 359493133 0 402718720 -0.0098001622 0.0097544976 0.1605080962 15 1305031102.6432650089 0.0178339556 0.0171461982 0.0281945895 0.0091803352 0.0440030000 362460701 0 402718720 -0.0154288579 0.0177095924 0.1700599194 16 1305031102.6752851009 0.0219957232 0.0174492935 0.0281945895 0.0089503223 0.0498120000 362404869 0 402718720 -0.0139235854 0.0199111067 0.1838217378 17 1305031102.7112629414 0.0274652038 0.0180384647 0.0281945895 0.0089913558 0.0347420000 359487665 0 402718720 -0.0138164870 0.0196803156 0.1979268193 18 1305031102.7432339191 0.0253677741 0.0184456486 0.0281945895 0.0089392164 0.0336100000 359447477 0 402718720 -0.0147678275 0.0272511728 0.2093721628 19 1305031102.7754719257 0.0312774181 0.0191210049 0.0312774181 0.0087703221 0.0336120000 359440353 0 402718720 -0.0119112525 0.0282020606 0.2232962102 20 1305031102.8112320900 0.0321627147 0.0197730904 0.0321627147 0.0087218791 0.0330020000 359431185 0 402718720 -0.0147889387 0.0317061767 0.2349842787 21 1305031102.8432900906 0.0371886566 0.0206024030 0.0371886566 0.0085867343 0.0361530000 360092539 0 402718720 -0.0162255559 0.0315136723 0.2483152747 22 1305031102.8753631115 0.0386483185 0.0214226719 0.0386483185 0.0086078569 0.1098360000 360148761 0 402718720 -0.0203557722 0.0342292041 0.2599323094 23 1305031102.9111850262 0.0408348478 0.0222666796 0.0408348478 0.0084449189 0.0794170000 362949065 0 402718720 -0.0206758007 0.0378609858 0.2714959383 24 1305031102.9432289600 0.0428458601 0.0231241454 0.0428458601 0.0087542884 0.0657920000 363200397 0 402718720 -0.0281592887 0.0395282879 0.2826285362 25 1305031102.9752030373 0.0434274152 0.0239362762 0.0434274152 0.0087822463 0.0325890000 360075667 0 402718720 -0.0333446115 0.0442545265 0.2937889993 26 1305031103.0112149715 0.0457710512 0.0247760753 0.0457710512 0.0086376878 0.0322150000 360099761 0 402718720 -0.0320365354 0.0477356836 0.3044961691 27 1305031103.0432269573 0.0488790907 0.0256687795 0.0488790907 0.0084757617 0.0455980000 360138989 0 402718720 -0.0319060087 0.0509303734 0.3165468276 28 1305031103.0753190517 0.0553919300 0.0267303206 0.0553919300 0.0085886578 0.0336670000 360185717 0 402718720 -0.0273772404 0.0511881784 0.3286094368 29 1305031103.1112399101 0.0528836958 0.0276321611 0.0553919300 0.0087239190 0.0334320000 360168553 0 402718720 -0.0276483260 0.0584576577 0.3355342448 30 1305031103.1433179379 0.0568409562 0.0286057876 0.0568409562 0.0086352990 0.0368510000 360785135 0 402718720 -0.0265238360 0.0603884682 0.3462789357 31 1305031103.1754519939 0.0552575178 0.0294655209 0.0568409562 0.0085272497 0.1138460000 360790537 0 402718720 -0.0282171145 0.0660763159 0.3537838161 32 1305031103.2112200260 0.0550928712 0.0302663756 0.0568409562 0.0088806539 0.0983840000 363273963 0 402718720 -0.0295975842 0.0713381320 0.3620836139 33 1305031103.2432160378 0.0569779649 0.0310758177 0.0569779649 0.0087658427 0.0518720000 364400603 0 402718720 -0.0292744990 0.0742696747 0.3702485561 34 1305031103.2753698826 0.0581876934 0.0318732258 0.0581876934 0.0088928189 0.0525100000 364071365 0 402718720 -0.0354940034 0.0744531527 0.3753269613 35 1305031103.3112099171 0.0660470575 0.0328496210 0.0660470575 0.0093033291 0.1150810000 361490785 0 402718720 -0.0344144031 0.0697300285 0.3829342127 36 1305031103.3432230949 0.0659034625 0.0337677832 0.0660470575 0.0094741596 0.1020710000 361626550 0 402718720 -0.0282048732 0.0716573074 0.3843874335 37 1305031103.3753271103 0.0673694909 0.0346759375 0.0673694909 0.0093520551 0.0827710000 365627075 0 402718720 -0.0269459859 0.0696684122 0.3851179183 38 1305031103.4112598896 0.0686256364 0.0355693506 0.0686256364 0.0093656890 0.0798170000 365713021 0 402718720 -0.0294810012 0.0659574270 0.3845647871 39 1305031103.4432799816 0.0683861002 0.0364108057 0.0686256364 0.0093163021 0.0344000000 361556157 0 402718720 -0.0299792122 0.0634062812 0.3804676235 40 1305031103.4752740860 0.0682952851 0.0372079177 0.0686256364 0.0092555049 0.0481530000 362037639 0 402718720 -0.0300349109 0.0600095242 0.3757593930 41 1305031103.5113329887 0.0683495402 0.0379674695 0.0686256364 0.0091839889 0.1118510000 362115283 0 402718720 -0.0294836108 0.0551811606 0.3692665398 42 1305031103.5434439182 0.0658164695 0.0386305409 0.0686256364 0.0091203386 0.0990670000 362121431 0 402718720 -0.0296962913 0.0520487837 0.3609600365 43 1305031103.5754740238 0.0611966103 0.0391553332 0.0686256364 0.0090261124 0.0913550000 366518155 0 402718720 -0.0300145131 0.0507714041 0.3515915573 44 1305031103.6112229824 0.0597418696 0.0396232091 0.0686256364 0.0089613500 0.0557420000 366645895 0 402718720 -0.0294228811 0.0458789207 0.3421838880 45 1305031103.6434450150 0.0560499802 0.0399882484 0.0686256364 0.0089050426 0.0741050000 366486453 0 402718720 -0.0273603387 0.0426111966 0.3302041590 46 1305031103.6755230427 0.0529913679 0.0402709249 0.0686256364 0.0088534164 0.0600770000 362165737 0 402718720 -0.0242103692 0.0392209254 0.3184487522 47 1305031103.7116100788 0.0499476232 0.0404768121 0.0686256364 0.0087907257 0.0356830000 362189893 0 402718720 -0.0205433480 0.0354044475 0.3061889112 48 1305031103.7433259487 0.0481197573 0.0406360402 0.0686256364 0.0087241343 0.0353280000 362147627 0 402718720 -0.0188261662 0.0293120164 0.2929831445 49 1305031103.7753419876 0.0430084616 0.0406844569 0.0686256364 0.0086577675 0.0352980000 362229821 0 402718720 -0.0173099339 0.0266818665 0.2781387866 50 1305031103.8112421036 0.0369980633 0.0406107290 0.0686256364 0.0088058007 0.0353710000 362232097 0 402718720 -0.0163588841 0.0258875936 0.2643445134 51 1305031103.8432509899 0.0298614800 0.0403999595 0.0686256364 0.0087940391 0.0342410000 362159959 0 402718720 -0.0181508772 0.0258031972 0.2503883243 52 1305031103.8753609657 0.0334726721 0.0402667424 0.0686256364 0.0089903157 0.0466930000 362206369 0 402718720 -0.0192248709 0.0151119120 0.2399053276 53 1305031103.9112210274 0.0343586430 0.0401552688 0.0686256364 0.0093444177 0.0351610000 362168655 0 402718720 -0.0167931579 0.0070188437 0.2256650329 54 1305031103.9432110786 0.0301491208 0.0399699698 0.0686256364 0.0092738425 0.0343980000 362219461 0 402718720 -0.0149166221 0.0044121724 0.2099102288 55 1305031103.9753730297 0.0310769901 0.0398082792 0.0686256364 0.0093800133 0.0339350000 362197173 0 402718720 -0.0102062058 -0.0011876654 0.1975612044 56 1305031104.0112318993 0.0315320566 0.0396604896 0.0686256364 0.0095506890 0.0334880000 362181819 0 402718720 -0.0053116903 -0.0060836338 0.1844505668 57 1305031104.0432488918 0.0264429729 0.0394286033 0.0686256364 0.0095282973 0.0375660000 362751791 0 402718720 -0.0024690945 -0.0082994998 0.1666985005 58 1305031104.0754249096 0.0220542084 0.0391290448 0.0686256364 0.0094794017 0.1135760000 362862577 0 402718720 0.0000355989 -0.0081763361 0.1507869065 59 1305031104.1112349033 0.0237484798 0.0388683572 0.0686256364 0.0096242221 0.0982360000 362839279 0 402718720 0.0040893294 -0.0133885089 0.1401379704 60 1305031104.1432299614 0.0176504254 0.0385147250 0.0686256364 0.0096036327 0.0948580000 366327455 0 402718720 0.0016916096 -0.0184059590 0.1241804510 61 1305031104.1754240990 0.0141524952 0.0381153442 0.0686256364 0.0095502206 0.0630180000 367617113 0 402718720 0.0017212285 -0.0202263966 0.1100541726 62 1305031104.2112829685 0.0132805891 0.0377147836 0.0686256364 0.0096154505 0.0862840000 367631593 0 402718720 0.0028066053 -0.0252334010 0.0963251665 63 1305031104.2431960106 0.0126181142 0.0373164238 0.0686256364 0.0095676516 0.0349920000 362904549 0 402718720 0.0037970892 -0.0271356553 0.0830832571 64 1305031104.2755460739 0.0135862408 0.0369456397 0.0686256364 0.0094925159 0.0347620000 362903033 0 402718720 0.0046663261 -0.0276000649 0.0692026913 65 1305031104.3112189770 0.0152635574 0.0366120692 0.0686256364 0.0094816880 0.0343930000 362937353 0 402718720 0.0056466605 -0.0293591879 0.0575543121 66 1305031104.3433420658 0.0197508931 0.0363565968 0.0686256364 0.0094666105 0.0334020000 362949485 0 402718720 0.0088820420 -0.0294055473 0.0460119471 67 1305031104.3758370876 0.0211102143 0.0361290389 0.0686256364 0.0096165788 0.0343430000 362985893 0 402718720 0.0098818028 -0.0320739076 0.0347641483 68 1305031104.4115090370 0.0205002856 0.0358992043 0.0686256364 0.0096333288 0.0506700000 363505803 0 402718720 0.0061223796 -0.0330865085 0.0240518693 69 1305031104.4432880878 0.0216437392 0.0356926033 0.0686256364 0.0095704107 0.1128810000 363626481 0 402718720 0.0018132323 -0.0327476002 0.0143986326 70 1305031104.4754559994 0.0218790174 0.0354952664 0.0686256364 0.0095056932 0.1020260000 363700956 0 402718720 -0.0009553658 -0.0349789783 0.0038461396 71 1305031104.5113289356 0.0198532287 0.0352749560 0.0686256364 0.0096787206 0.0868960000 368586632 0 402718720 -0.0006765642 -0.0394799560 -0.0046000169 72 1305031104.5433681011 0.0225538164 0.0350982735 0.0686256364 0.0096513849 0.0529780000 368702069 0 402718720 -0.0005253058 -0.0392520577 -0.0140999742 73 1305031104.5753428936 0.0246701632 0.0349554227 0.0686256364 0.0097828517 0.0936250000 368476257 0 402718720 0.0081975842 -0.0432375856 -0.0216242336 74 1305031104.6113359928 0.0252643675 0.0348244625 0.0686256364 0.0100763314 0.1002430000 364111692 0 402718720 0.0152624091 -0.0518568307 -0.0307616927 75 1305031104.6432430744 0.0352332629 0.0348299132 0.0686256364 0.0102972553 0.0854430000 364115296 0 402718720 0.0199969504 -0.0436885618 -0.0399323218 76 1305031104.6755249500 0.0312114265 0.0347823015 0.0686256364 0.0102590512 0.0795380000 366456544 0 402718720 0.0196223464 -0.0501806177 -0.0511401445 77 1305031104.7112770081 0.0301011037 0.0347215067 0.0686256364 0.0104315180 0.0477650000 369696384 0 402718720 0.0183454007 -0.0519321598 -0.0639935136 78 1305031104.7432799339 0.0387639813 0.0347733333 0.0686256364 0.0104109335 0.0430150000 369631856 0 402718720 0.0207973309 -0.0440462716 -0.0755118430 79 1305031104.7753269672 0.0365773737 0.0347961693 0.0686256364 0.0103634264 0.0745050000 369565753 0 402718720 0.0200330038 -0.0469278619 -0.0849667788 80 1305031104.8114650249 0.0457804129 0.0349334723 0.0686256364 0.0103583675 0.0300080000 364667780 0 402718720 0.0179304965 -0.0368927419 -0.0940468162 81 1305031104.8432579041 0.0510508157 0.0351324519 0.0686256364 0.0102978353 0.0859290000 364767944 0 402718720 0.0162674133 -0.0321161933 -0.1009643674 82 1305031104.8753499985 0.0568418466 0.0353972006 0.0686256364 0.0102551187 0.0822880000 364835141 0 402718720 0.0132152801 -0.0264097210 -0.1059642434 83 1305031104.9115340710 0.0595989153 0.0356887875 0.0686256364 0.0101971063 0.0801910000 365906920 0 402718720 0.0159366671 -0.0227122661 -0.1055414304 84 1305031104.9432621002 0.0607132316 0.0359866975 0.0686256364 0.0101408248 0.0630480000 370757000 0 402718720 0.0145283183 -0.0210593585 -0.1045000032 85 1305031104.9752020836 0.0658096597 0.0363375559 0.0686256364 0.0101270244 0.0564620000 370785133 0 402718720 0.0122533850 -0.0146575440 -0.1011458114 86 1305031105.0112900734 0.0655314848 0.0366770202 0.0686256364 0.0100911138 0.0831730000 370714361 0 402718720 0.0188291185 -0.0128039271 -0.0952687413 87 1305031105.0433731079 0.0671642944 0.0370274487 0.0686256364 0.0100786909 0.0308200000 364791780 0 402718720 0.0143088456 -0.0087449187 -0.0879766643 88 1305031105.0753200054 0.0630888268 0.0373236007 0.0686256364 0.0100346035 0.0304670000 364796088 0 402718720 0.0143208364 -0.0099633839 -0.0781369582 89 1305031105.1112990379 0.0578677654 0.0375544340 0.0686256364 0.0099992473 0.0308050000 364822589 0 402718720 0.0100799650 -0.0124372691 -0.0671143308 90 1305031105.1431059837 0.0657125935 0.0378673024 0.0686256364 0.0100115310 0.0311340000 364805052 0 402718720 0.0040521817 -0.0013117944 -0.0571039096 91 1305031105.1751589775 0.0615751743 0.0381278285 0.0686256364 0.0100197956 0.0426510000 364809412 0 402718720 0.0057434412 -0.0004258412 -0.0411210321 92 1305031105.2112679482 0.0490498096 0.0382465457 0.0686256364 0.0101663854 0.0312140000 364813984 0 402718720 0.0012097086 -0.0091078039 -0.0258364268 93 1305031105.2432699203 0.0472923629 0.0383438125 0.0686256364 0.0101388477 0.0321400000 364818164 0 402718720 -0.0023309754 -0.0065933922 -0.0118572880 94 1305031105.2752881050 0.0460373200 0.0384256584 0.0686256364 0.0103354779 0.0356020000 365451400 0 402718720 -0.0087124165 -0.0032689655 0.0025278581 95 1305031105.3112900257 0.0370300785 0.0384109680 0.0686256364 0.0103907882 0.1069780000 365450396 0 402718720 -0.0096576652 -0.0070501729 0.0187748149 96 1305031105.3433020115 0.0259520821 0.0382811880 0.0686256364 0.0103478057 0.1035000000 365473013 0 402718720 -0.0097344201 -0.0138564296 0.0335531160 97 1305031105.3753380775 0.0223665331 0.0381171194 0.0686256364 0.0103291937 0.1013030000 365751228 0 402718720 -0.0116748447 -0.0138428733 0.0464777462 98 1305031105.4112861156 0.0261234585 0.0379947351 0.0686256364 0.0104286089 0.1017980000 370411720 0 402718720 -0.0135499965 -0.0056492328 0.0600656047 99 1305031105.4433159828 0.0175893176 0.0377886197 0.0686256364 0.0103762915 0.0801580000 371726427 0 402718720 -0.0141175743 -0.0102224154 0.0752122328 100 1305031105.4752800465 0.0155193945 0.0375659275 0.0686256364 0.0103270245 0.1139220000 371656957 0 402718720 -0.0148937227 -0.0090626953 0.0881957263 101 1305031105.5113320351 0.0161187220 0.0373535789 0.0686256364 0.0103617595 0.0366850000 365510649 0 402718720 -0.0131826978 -0.0071907518 0.1020163968 102 1305031105.5432820320 0.0124831330 0.0371097510 0.0686256364 0.0103155808 0.0368350000 365545725 0 402718720 -0.0145887332 -0.0086900927 0.1175409406 103 1305031105.5754489899 0.0110364938 0.0368566126 0.0686256364 0.0103022128 0.0494870000 365537737 0 402718720 -0.0167198014 -0.0061904620 0.1307394356 104 1305031105.6113779545 0.0146399550 0.0366429909 0.0686256364 0.0102718880 0.0362810000 365582509 0 402718720 -0.0144594703 -0.0083363177 0.1460968703 105 1305031105.6432731152 0.0134350397 0.0364219628 0.0686256364 0.0102318104 0.0366970000 365579505 0 402718720 -0.0173518322 -0.0060218805 0.1605628878 106 1305031105.6751658916 0.0160835180 0.0362300907 0.0686256364 0.0102053231 0.0359840000 365556593 0 402718720 -0.0157752503 -0.0026621427 0.1742579490 107 1305031105.7113089561 0.0239286050 0.0361151235 0.0686256364 0.0102360751 0.0358700000 365525197 0 402718720 -0.0113945734 -0.0044804784 0.1908962876 108 1305031105.7433118820 0.0209579989 0.0359747798 0.0686256364 0.0102488979 0.0359800000 365523873 0 402718720 -0.0126553718 0.0031934176 0.2030052245 109 1305031105.7753388882 0.0262223892 0.0358853083 0.0686256364 0.0102162076 0.0345870000 365514581 0 402718720 -0.0108931344 0.0014869049 0.2178808004 110 1305031105.8112831116 0.0260649882 0.0357960327 0.0686256364 0.0101767916 0.0345600000 365550377 0 402718720 -0.0130899651 0.0045681465 0.2312287241 111 1305031105.8432710171 0.0290994253 0.0357357029 0.0686256364 0.0101353541 0.0332240000 365532645 0 402718720 -0.0108736977 0.0069945129 0.2455426753 112 1305031105.8753368855 0.0271564089 0.0356591020 0.0686256364 0.0101327551 0.0328500000 365506176 0 402718720 -0.0100854300 0.0147801042 0.2584710121 113 1305031105.9112620354 0.0291758198 0.0356017278 0.0686256364 0.0101775498 0.0382840000 366233872 0 402718720 -0.0111994501 0.0183649901 0.2727401853 114 1305031105.9432721138 0.0295713879 0.0355488301 0.0686256364 0.0101452020 0.1453480000 366217820 0 402718720 -0.0117713111 0.0234056953 0.2849889696 115 1305031105.9753289223 0.0315199345 0.0355137963 0.0686256364 0.0101175957 0.1301890000 366222720 0 402718720 -0.0123150842 0.0277737342 0.2978928983 116 1305031106.0112850666 0.0355205648 0.0355138546 0.0686256364 0.0101229563 0.1005350000 366497688 0 402718720 -0.0116663119 0.0316483565 0.3107671738 117 1305031106.0433549881 0.0386976264 0.0355410663 0.0686256364 0.0100810794 0.0967200000 372871092 0 402718720 -0.0139610246 0.0337634608 0.3222751617 118 1305031106.0753300190 0.0402036086 0.0355805794 0.0686256364 0.0100555550 0.0721750000 372874453 0 402718720 -0.0160434861 0.0384377986 0.3338291049 119 1305031106.1113269329 0.0420647189 0.0356350680 0.0686256364 0.0100468857 0.1125760000 372807103 0 402718720 -0.0176096950 0.0440866053 0.3457374275 120 1305031106.1433548927 0.0470052473 0.0357298195 0.0686256364 0.0100178801 0.0348970000 366239776 0 402718720 -0.0199109837 0.0446060896 0.3564814925 121 1305031106.1755340099 0.0514513031 0.0358597491 0.0686256364 0.0099893116 0.0437050000 366264205 0 402718720 -0.0204177313 0.0463411622 0.3673638403 122 1305031106.2112751007 0.0582790673 0.0360435140 0.0686256364 0.0099538906 0.0348650000 366316157 0 402718720 -0.0210493002 0.0456423052 0.3776869476 123 1305031106.2432670593 0.0583999194 0.0362252734 0.0686256364 0.0099585345 0.0346870000 366335185 0 402718720 -0.0241465718 0.0499644727 0.3849135935 124 1305031106.2763850689 0.0580989122 0.0364016737 0.0686256364 0.0099212803 0.0358220000 366312077 0 402718720 -0.0236619804 0.0552413948 0.3908612132 125 1305031106.3112380505 0.0594104975 0.0365857443 0.0686256364 0.0098852490 0.0348010000 366257260 0 402718720 -0.0237901099 0.0577708595 0.3968233168 126 1305031106.3432579041 0.0556578971 0.0367371106 0.0686256364 0.0099257614 0.0377560000 366858472 0 402718720 -0.0247975923 0.0652353689 0.4013104141 127 1305031106.3753879070 0.0591617711 0.0369136827 0.0686256364 0.0098965909 0.1146370000 366948712 0 402718720 -0.0211466048 0.0648549348 0.4045579731 128 1305031106.4113199711 0.0685962364 0.0371612027 0.0686256364 0.0099255049 0.1024870000 366953120 0 402718720 -0.0195302796 0.0559087545 0.4059393704 129 1305031106.4432780743 0.0706223249 0.0374205912 0.0706223249 0.0099775690 0.1008960000 367021973 0 402718720 -0.0244522858 0.0515285730 0.4040665030 130 1305031106.4753448963 0.0703057721 0.0376735541 0.0706223249 0.0099675320 0.0999330000 369779220 0 402718720 -0.0273822788 0.0491543114 0.4005153477 131 1305031106.5111289024 0.0704001039 0.0379233751 0.0706223249 0.0099584134 0.0676800000 374213780 0 402718720 -0.0290460568 0.0448657125 0.3946655691 132 1305031106.5433020592 0.0674294457 0.0381469060 0.0706223249 0.0099254349 0.0482870000 374134652 0 402718720 -0.0265020113 0.0436229780 0.3861352503 133 1305031106.5752820969 0.0646305010 0.0383460307 0.0706223249 0.0098910928 0.1117800000 374178717 0 402718720 -0.0263558384 0.0406683087 0.3750917912 134 1305031106.6111509800 0.0586243011 0.0384973611 0.0706223249 0.0099074322 0.0383430000 367031437 0 402718720 -0.0278599747 0.0405326858 0.3640909791 135 1305031106.6432070732 0.0599187091 0.0386560378 0.0706223249 0.0099343807 0.0361940000 367036001 0 402718720 -0.0264061168 0.0334204137 0.3529562652 136 1305031106.6752789021 0.0540022142 0.0387688773 0.0706223249 0.0099012261 0.0363570000 367003784 0 402718720 -0.0281251706 0.0328377597 0.3389297426 137 1305031106.7115080357 0.0541987009 0.0388815037 0.0706223249 0.0099350513 0.0360860000 367007748 0 402718720 -0.0283667818 0.0272039287 0.3277892470 138 1305031106.7433409691 0.0478913076 0.0389467922 0.0706223249 0.0099063315 0.0395920000 367696776 0 402718720 -0.0296977274 0.0271957517 0.3132045269 139 1305031106.7753899097 0.0457420275 0.0389956788 0.0706223249 0.0098876924 0.1156980000 367699033 0 402718720 -0.0266223513 0.0236009210 0.2986814976 140 1305031106.8112890720 0.0417195447 0.0390151349 0.0706223249 0.0098581174 0.1079020000 367751957 0 402718720 -0.0238610562 0.0215668902 0.2821199298 141 1305031106.8434159756 0.0452781171 0.0390595533 0.0706223249 0.0099303761 0.1066580000 367691796 0 402718720 -0.0226311274 0.0118116438 0.2691279650 142 1305031106.8759050369 0.0432696491 0.0390892018 0.0706223249 0.0099739180 0.1037640000 367938031 0 402718720 -0.0175879803 0.0069252439 0.2503297329 143 1305031106.9112429619 0.0353163071 0.0390628179 0.0706223249 0.0099877963 0.0861770000 375240656 0 402718720 -0.0184217449 0.0074490272 0.2306941748 144 1305031106.9434390068 0.0353612751 0.0390371128 0.0706223249 0.0100487221 0.0790950000 375335243 0 402718720 -0.0174782872 0.0002044458 0.2149764001 145 1305031106.9755470753 0.0354710221 0.0390125191 0.0706223249 0.0100174699 0.1194350000 375077515 0 402718720 -0.0154301450 -0.0068116114 0.1982049346 146 1305031107.0115759373 0.0227288734 0.0389009872 0.0706223249 0.0100264379 0.0436410000 367756209 0 402718720 -0.0175841805 -0.0026164688 0.1757125556 147 1305031107.0432810783 0.0230917502 0.0387934414 0.0706223249 0.0100001133 0.0385850000 367763821 0 402718720 -0.0181595422 -0.0103858821 0.1610343009 148 1305031107.0754320621 0.0200049952 0.0386664924 0.0706223249 0.0099717574 0.0371480000 367711516 0 402718720 -0.0205829982 -0.0160660613 0.1452589780 149 1305031107.1112289429 0.0147344023 0.0385058744 0.0706223249 0.0099443464 0.0451920000 367773829 0 402718720 -0.0186809339 -0.0159098431 0.1280675977 150 1305031107.1432600021 0.0135263717 0.0383393444 0.0706223249 0.0099214434 0.0383960000 367849985 0 402718720 -0.0146526136 -0.0165278874 0.1124109030 151 1305031107.1753990650 0.0150769688 0.0381852889 0.0706223249 0.0099113731 0.0369900000 367749913 0 402718720 -0.0131459124 -0.0243455507 0.0999231339 152 1305031107.2113580704 0.0159152281 0.0380387753 0.0706223249 0.0099495042 0.0370590000 367725760 0 402718720 -0.0098409913 -0.0293635242 0.0862902105 153 1305031107.2433779240 0.0142597035 0.0378833566 0.0706223249 0.0099274410 0.0371580000 367766709 0 402718720 -0.0081775105 -0.0285992082 0.0722133368 154 1305031107.2753980160 0.0157028921 0.0377393276 0.0706223249 0.0099181934 0.0370140000 367732732 0 402718720 -0.0050782738 -0.0321489945 0.0602337345 155 1305031107.3112258911 0.0148493256 0.0375916502 0.0706223249 0.0099302427 0.0348520000 367736732 0 402718720 -0.0037794658 -0.0380172320 0.0488872230 156 1305031107.3435089588 0.0170035604 0.0374596752 0.0706223249 0.0099580277 0.0341840000 367740164 0 402718720 0.0009051081 -0.0422146209 0.0366941765 157 1305031107.3754129410 0.0197429173 0.0373468296 0.0706223249 0.0100114838 0.0344330000 367743964 0 402718720 0.0023632119 -0.0349315144 0.0255997162 158 1305031107.4112710953 0.0214157309 0.0372459999 0.0706223249 0.0100040808 0.0484020000 367747616 0 402718720 0.0053863395 -0.0354096107 0.0187055618 159 1305031107.4434189796 0.0247203521 0.0371672222 0.0706223249 0.0099848400 0.0342560000 367815305 0 402718720 0.0079150870 -0.0342444703 0.0104446523 160 1305031107.4753770828 0.0257376917 0.0370957877 0.0706223249 0.0099566541 0.0345940000 367835897 0 402718720 0.0100890724 -0.0342461467 0.0070646484 161 1305031107.5113520622 0.0301687326 0.0370527625 0.0706223249 0.0099458863 0.0342960000 367865141 0 402718720 0.0097170761 -0.0280282535 0.0054567712 162 1305031107.5436050892 0.0306013580 0.0370129390 0.0706223249 0.0099338078 0.0340760000 367882801 0 402718720 0.0146859046 -0.0284803510 0.0050475835 163 1305031107.5754539967 0.0241018012 0.0369337296 0.0706223249 0.0099243095 0.0340780000 367901261 0 402718720 0.0162388831 -0.0345981419 0.0056704450 164 1305031107.6112709045 0.0305033829 0.0368945201 0.0706223249 0.0099190104 0.0345770000 367885957 0 402718720 0.0161042400 -0.0264719892 0.0048877755 165 1305031107.6433229446 0.0275905766 0.0368381326 0.0706223249 0.0098924016 0.0343300000 367934421 0 402718720 0.0180350188 -0.0279440004 0.0056134965 166 1305031107.6755681038 0.0263245329 0.0367747977 0.0706223249 0.0098691124 0.0345050000 367957061 0 402718720 0.0154814208 -0.0262861196 0.0084149372 167 1305031107.7113070488 0.0263725929 0.0367125090 0.0706223249 0.0098434294 0.0344320000 367917689 0 402718720 0.0155608859 -0.0230222698 0.0102392826 168 1305031107.7435379028 0.0279345978 0.0366602595 0.0706223249 0.0098208162 0.0346490000 367881621 0 402718720 0.0133130904 -0.0188638438 0.0113321180 169 1305031107.7758018970 0.0237505287 0.0365838706 0.0706223249 0.0098004624 0.0445880000 367920677 0 402718720 0.0127889076 -0.0205184333 0.0149577642 170 1305031107.8115959167 0.0231174659 0.0365046564 0.0706223249 0.0097769905 0.0352980000 367927597 0 402718720 0.0146606695 -0.0186103005 0.0180961899 171 1305031107.8433320522 0.0229172315 0.0364251978 0.0706223249 0.0097494661 0.0355140000 367936929 0 402718720 0.0160359871 -0.0179245397 0.0185992830 172 1305031107.8753581047 0.0200689156 0.0363301032 0.0706223249 0.0097318069 0.0352980000 367917661 0 402718720 0.0204092041 -0.0205312762 0.0222491734 173 1305031107.9115409851 0.0182180889 0.0362254094 0.0706223249 0.0097593721 0.0352270000 367907081 0 402718720 0.0237786919 -0.0205392949 0.0249216836 174 1305031107.9431219101 0.0167899132 0.0361137112 0.0706223249 0.0097696959 0.0383240000 368348280 0 402718720 0.0295715537 -0.0233349930 0.0264260601 175 1305031107.9758069515 0.0149032148 0.0359925083 0.0706223249 0.0097730539 0.1089230000 368461577 0 402718720 0.0343767181 -0.0228794906 0.0292186979 176 1305031108.0113201141 0.0152964015 0.0358749168 0.0706223249 0.0097656105 0.0972020000 368424660 0 402718720 0.0409144834 -0.0217428710 0.0304221492 177 1305031108.0434179306 0.0193000752 0.0357812736 0.0706223249 0.0097539528 0.0870450000 368706700 0 402718720 0.0522766635 -0.0185788292 0.0307894759 178 1305031108.0753519535 0.0163920801 0.0356723456 0.0706223249 0.0097472770 0.0822890000 373471540 0 402718720 0.0591579713 -0.0212042425 0.0329718851 179 1305031108.1113779545 0.0141634913 0.0355521844 0.0706223249 0.0097388194 0.0458690000 375992684 0 402718720 0.0645151287 -0.0212279130 0.0382932648 180 1305031108.1433339119 0.0161955841 0.0354446477 0.0706223249 0.0097199582 0.0582980000 376080609 0 402718720 0.0771100074 -0.0174539164 0.0414890423 181 1305031108.1760580540 0.0232134294 0.0353770719 0.0706223249 0.0097535297 0.0954870000 375853541 0 402718720 0.0838704705 -0.0109224897 0.0444899760 182 1305031108.2114748955 0.0220648274 0.0353039277 0.0706223249 0.0097322047 0.0549480000 369002624 0 402718720 0.0942123607 -0.0129171107 0.0470327623 183 1305031108.2433469296 0.0154798394 0.0351955994 0.0706223249 0.0097131123 0.1080690000 369113356 0 402718720 0.1084574759 -0.0194369163 0.0518519096 184 1305031108.2753579617 0.0208710823 0.0351177488 0.0706223249 0.0097037507 0.0963930000 369117828 0 402718720 0.1144765988 -0.0122813405 0.0545672514 185 1305031108.3113319874 0.0251442287 0.0350638378 0.0706223249 0.0097780036 0.0946720000 369121084 0 402718720 0.1222451106 -0.0073667686 0.0605341420 186 1305031108.3432779312 0.0252573267 0.0350111147 0.0706223249 0.0097604724 0.0922880000 372164540 0 402718720 0.1311072260 -0.0088877911 0.0628220141 187 1305031108.3754100800 0.0272558983 0.0349696429 0.0706223249 0.0097355862 0.0670240000 377125996 0 402718720 0.1386676282 -0.0061020516 0.0668444633 188 1305031108.4113609791 0.0253211707 0.0349183212 0.0706223249 0.0097155759 0.0763020000 377161597 0 402718720 0.1527552605 -0.0059063612 0.0740869418 189 1305031108.4436099529 0.0203576293 0.0348412805 0.0706223249 0.0097215985 0.0359510000 377031924 0 402718720 0.1686398536 -0.0035196070 0.0766840056 190 1305031108.4754710197 0.0178053733 0.0347516179 0.0706223249 0.0097448164 0.1018710000 376977445 0 402718720 0.1820371002 -0.0062354300 0.0787858143 191 1305031108.5113780499 0.0195408873 0.0346719805 0.0706223249 0.0098337636 0.0350190000 369753088 0 402718720 0.1965659559 -0.0115659535 0.0852434784 192 1305031108.5437369347 0.0238636602 0.0346156872 0.0706223249 0.0098332943 0.1033070000 369857824 0 402718720 0.2058242112 -0.0147811864 0.0854587704 193 1305031108.5754139423 0.0244474914 0.0345630023 0.0706223249 0.0098964140 0.0984010000 369861920 0 402718720 0.2130979151 -0.0050754594 0.0848181248 194 1305031108.6114070415 0.0247452445 0.0345123953 0.0706223249 0.0099801142 0.0921280000 369865656 0 402718720 0.2287205756 -0.0045492286 0.0874264166 195 1305031108.6433029175 0.0288036633 0.0344831197 0.0706223249 0.0099698645 0.0860410000 370205468 0 402718720 0.2366132140 -0.0015638315 0.0835445672 196 1305031108.6753749847 0.0275706537 0.0344478520 0.0706223249 0.0099762175 0.0872790000 376107620 0 402718720 0.2498743087 0.0006279226 0.0830128267 197 1305031108.7114109993 0.0342999846 0.0344471014 0.0706223249 0.0100017148 0.0477840000 378418708 0 402718720 0.2566558123 -0.0010535684 0.0858316198 198 1305031108.7435019016 0.0410089456 0.0344802421 0.0706223249 0.0099819936 0.0691230000 378427537 0 402718720 0.2616896033 -0.0040416410 0.0828113332 199 1305031108.7754929066 0.0403174125 0.0345095746 0.0706223249 0.0099652438 0.0337990000 378316784 0 402718720 0.2707976401 -0.0018399111 0.0821389034 200 1305031108.8112440109 0.0498884246 0.0345864688 0.0706223249 0.0100091235 0.0956740000 378275709 0 402718720 0.2677635550 -0.0024528140 0.0914850682 201 1305031108.8432641029 0.0526806004 0.0346764894 0.0706223249 0.0115903846 0.0541400000 370564152 0 402718720 0.2722584903 -0.0024080882 0.0899818242 202 1305031108.8765149117 0.0521231517 0.0347628590 0.0706223249 0.0117235394 0.1056750000 370644456 0 402718720 0.2729590237 -0.0030305716 0.0879280344 203 1305031108.9113640785 0.0528437831 0.0348519276 0.0706223249 0.0118795861 0.0931670000 370649688 0 402718720 0.2733984292 -0.0068179546 0.0877029002 204 1305031108.9432430267 0.0568417795 0.0349597210 0.0706223249 0.0119675616 0.0900720000 370652872 0 402718720 0.2698294818 -0.0086823944 0.0868844092 205 1305031108.9752678871 0.0566475429 0.0350655152 0.0706223249 0.0119395934 0.0967120000 375448048 0 402718720 0.2655165792 -0.0029493235 0.0803651661 206 1305031109.0112690926 0.0488068573 0.0351322208 0.0706223249 0.0119110183 0.0658040000 379806032 0 402718720 0.2670691311 -0.0016833346 0.0792943537 207 1305031109.0432770252 0.0523803905 0.0352155453 0.0706223249 0.0119005843 0.0865320000 379806555 0 402718720 0.2573803067 -0.0040287711 0.0799729377 208 1305031109.0754098892 0.0480323918 0.0352771647 0.0706223249 0.0118741526 0.1231960000 379532187 0 402718720 0.2538845241 0.0040664608 0.0728723109 209 1305031109.1112821102 0.0410250761 0.0353046667 0.0706223249 0.0118537385 0.0489670000 370669452 0 402718720 0.2500419021 0.0002150731 0.0718506351 210 1305031109.1433339119 0.0491111502 0.0353704118 0.0706223249 0.0118505720 0.0348510000 370673116 0 402718720 0.2328845710 -0.0058105951 0.0714489967 211 1305031109.1754639149 0.0515880622 0.0354472728 0.0706223249 0.0118775993 0.0341120000 370676792 0 402718720 0.2186076045 0.0004408660 0.0726346150 212 1305031109.2113790512 0.0405275077 0.0354712361 0.0706223249 0.0119339788 0.0377240000 371261448 0 402718720 0.2158629149 0.0167834554 0.0750823766 213 1305031109.2432899475 0.0380588323 0.0354833845 0.0706223249 0.0119154743 0.1180920000 371331372 0 402718720 0.2057722509 0.0113790929 0.0762651265 214 1305031109.2753078938 0.0420980044 0.0355142939 0.0706223249 0.0119877508 0.1044980000 371334964 0 402718720 0.1918504536 -0.0063641081 0.0760032833 215 1305031109.3113288879 0.0436335430 0.0355520578 0.0706223249 0.0121104394 0.0997270000 371338220 0 402718720 0.1717092246 -0.0022723884 0.0741661489 216 1305031109.3432478905 0.0401949808 0.0355735529 0.0706223249 0.0120867901 0.0972400000 371588585 0 402718720 0.1611623317 0.0055768420 0.0719021484 217 1305031109.3753969669 0.0292204451 0.0355442759 0.0706223249 0.0121553908 0.0924580000 380405740 0 402718720 0.1603051424 -0.0028440310 0.0673205480 218 1305031109.4113290310 0.0256563518 0.0354989184 0.0706223249 0.0121838243 0.0873610000 380710727 0 402718720 0.1447654068 0.0019989670 0.0676372796 219 1305031109.4433019161 0.0195310432 0.0354260057 0.0706223249 0.0121576895 0.0410770000 380816845 0 402718720 0.1377164274 0.0054622460 0.0650854632 220 1305031109.4753630161 0.0164420400 0.0353397150 0.0706223249 0.0121457585 0.1199750000 380605983 0 402718720 0.1286987513 -0.0016522589 0.0661615580 221 1305031109.5112729073 0.0143421907 0.0352447036 0.0706223249 0.0121302613 0.0536780000 371998044 0 402718720 0.1183962747 -0.0083467215 0.0652602091 222 1305031109.5432939529 0.0094652753 0.0351285800 0.0706223249 0.0121031427 0.1174830000 371966132 0 402718720 0.1077555567 -0.0043254416 0.0620265603 223 1305031109.5753619671 0.0102262693 0.0350169105 0.0706223249 0.0120793957 0.1128680000 371990289 0 402718720 0.0928705931 -0.0012551439 0.0582348518 224 1305031109.6113100052 0.0078451922 0.0348956082 0.0706223249 0.0120768817 0.1087370000 371969232 0 402718720 0.0795678571 -0.0015123836 0.0552372821 225 1305031109.6432290077 0.0068711163 0.0347710549 0.0706223249 0.0120513087 0.1020430000 374971156 0 402718720 0.0696445927 0.0020817763 0.0544757247 226 1305031109.6752629280 0.0107610896 0.0346648161 0.0706223249 0.0120300399 0.0583930000 381474109 0 402718720 0.0549139641 0.0045495345 0.0520923287 227 1305031109.7113120556 0.0070690918 0.0345432490 0.0706223249 0.0120415465 0.0611640000 380962141 0 402718720 0.0443784595 0.0061084107 0.0522094704 228 1305031109.7432739735 0.0074573411 0.0344244512 0.0706223249 0.0120192775 0.1159550000 380928325 0 402718720 0.0320503861 0.0070032617 0.0517712496 229 1305031109.7752768993 0.0056159310 0.0342986498 0.0706223249 0.0119962612 0.0509780000 371949901 0 402718720 0.0220188592 0.0060831429 0.0532210432 230 1305031109.8113710880 0.0072246175 0.0341809366 0.0706223249 0.0119987484 0.0371230000 371934924 0 402718720 0.0076315086 0.0090685058 0.0531517640 231 1305031109.8432960510 0.0069479146 0.0340630447 0.0706223249 0.0119747662 0.0377940000 371938292 0 402718720 -0.0041836076 0.0094989277 0.0547540076 232 1305031109.8753058910 0.0064446353 0.0339439998 0.0706223249 0.0119628502 0.0401200000 372495948 0 402718720 -0.0166829452 0.0090634432 0.0575698838 233 1305031109.9112648964 0.0098083476 0.0338404134 0.0706223249 0.0119458349 0.1216690000 372597152 0 402718720 -0.0271637104 0.0059747687 0.0610737838 234 1305031109.9432990551 0.0135191446 0.0337535703 0.0706223249 0.0119731884 0.1111010000 372597560 0 402718720 -0.0398153812 0.0143645760 0.0619348139 235 1305031109.9752581120 0.0132358372 0.0336662608 0.0706223249 0.0119756176 0.1082530000 372599564 0 402718720 -0.0518163517 0.0114816474 0.0660385042 236 1305031110.0112559795 0.0184272174 0.0336016886 0.0706223249 0.0119671792 0.1043050000 375947356 0 402718720 -0.0639470369 0.0130235543 0.0696383342 237 1305031110.0432989597 0.0180121548 0.0335359100 0.0706223249 0.0119481221 0.0776190000 381588804 0 402718720 -0.0760363564 0.0108687822 0.0712489486 238 1305031110.0753190517 0.0196237117 0.0334774554 0.0706223249 0.0119284775 0.0682420000 381707669 0 402718720 -0.0884543434 0.0150451036 0.0752728954 239 1305031110.1113250256 0.0219059009 0.0334290388 0.0706223249 0.0119322926 0.1282650000 381416023 0 402718720 -0.1010321677 0.0135204419 0.0786514953 240 1305031110.1434319019 0.0196424145 0.0333715946 0.0706223249 0.0119283491 0.0534760000 373265724 0 402718720 -0.1151093543 0.0090500675 0.0812296867 241 1305031110.1756410599 0.0203806330 0.0333176901 0.0706223249 0.0119041993 0.1242800000 373264524 0 402718720 -0.1245790869 0.0148930224 0.0806464851 242 1305031110.2116370201 0.0239386111 0.0332789336 0.0706223249 0.0118967753 0.1198330000 373266200 0 402718720 -0.1350048184 0.0099776722 0.0840657577 243 1305031110.2433230877 0.0277820826 0.0332563128 0.0706223249 0.0118755541 0.1147460000 373270740 0 402718720 -0.1427193433 0.0086857183 0.0877277330 244 1305031110.2793209553 0.0349231400 0.0332631441 0.0706223249 0.0118671048 0.1037680000 376159032 0 402718720 -0.1482674032 0.0079397978 0.0890532583 245 1305031110.3114039898 0.0293872636 0.0332473242 0.0706223249 0.0118526219 0.0910400000 382972481 0 402718720 -0.1632142961 0.0080821309 0.0869861692 246 1305031110.3433549404 0.0307033304 0.0332369827 0.0706223249 0.0118301500 0.0939660000 382714351 0 402718720 -0.1725497991 0.0125334999 0.0873855576 247 1305031110.3792810440 0.0339468196 0.0332398566 0.0706223249 0.0118467022 0.0402340000 382817061 0 402718720 -0.1832846999 0.0148340473 0.0872261226 248 1305031110.4114689827 0.0362175405 0.0332518634 0.0706223249 0.0118308963 0.1111300000 382597457 0 402718720 -0.1917064339 0.0192812383 0.0848226696 249 1305031110.4432599545 0.0409315974 0.0332827057 0.0706223249 0.0118194081 0.0525140000 373803660 0 402718720 -0.2007665932 0.0235322174 0.0880286098 250 1305031110.4793310165 0.0468766317 0.0333370814 0.0706223249 0.0118541149 0.1168530000 373898852 0 402718720 -0.2114661634 0.0223473776 0.0924469605 251 1305031110.5114290714 0.0492868610 0.0334006263 0.0706223249 0.0118333497 0.1071990000 373900444 0 402718720 -0.2200762331 0.0241236016 0.0924995691 252 1305031110.5434079170 0.0485578589 0.0334607741 0.0706223249 0.0118170786 0.1025210000 373903500 0 402718720 -0.2308904827 0.0278758295 0.0893862695 253 1305031110.5794260502 0.0552143976 0.0335467568 0.0706223249 0.0118193988 0.0983200000 376911240 0 402718720 -0.2388766557 0.0336578749 0.0908257663 254 1305031110.6113069057 0.0583651401 0.0336444669 0.0706223249 0.0118426212 0.0872820000 383526961 0 402718720 -0.2461507916 0.0276206825 0.0963666439 255 1305031110.6434180737 0.0591501258 0.0337444891 0.0706223249 0.0118244429 0.0910480000 383353581 0 402718720 -0.2544212341 0.0286238361 0.0969591960 256 1305031110.6796059608 0.0599620640 0.0338469015 0.0706223249 0.0118438753 0.0410830000 383399909 0 402718720 -0.2628675103 0.0361367650 0.0928132087 257 1305031110.7114119530 0.0647911578 0.0339673072 0.0706223249 0.0118263570 0.1163240000 383348389 0 402718720 -0.2672027051 0.0342515931 0.0997980163 258 1305031110.7432489395 0.0674114749 0.0340969357 0.0706223249 0.0118196605 0.0422340000 374599780 0 402718720 -0.2709659338 0.0355548263 0.1018951535 259 1305031110.7791929245 0.0699281618 0.0342352802 0.0706223249 0.0118012198 0.1244550000 374754793 0 402718720 -0.2744575739 0.0398288257 0.1017265171 260 1305031110.8113861084 0.0687826276 0.0343681547 0.0706223249 0.0117804853 0.1179430000 374788329 0 402718720 -0.2776800990 0.0385507755 0.1014085561 261 1305031110.8432180882 0.0689387918 0.0345006092 0.0706223249 0.0117630607 0.1116110000 375025996 0 402718720 -0.2795979977 0.0381153449 0.1026070789 262 1305031110.8793129921 0.0710480958 0.0346401034 0.0710480958 0.0117448205 0.1077530000 380036704 0 402718720 -0.2784290612 0.0404257104 0.1038779914 263 1305031110.9113330841 0.0685204864 0.0347689262 0.0710480958 0.0117277747 0.0736340000 384822864 0 402718720 -0.2786294520 0.0391353704 0.1027716249 264 1305031110.9438619614 0.0716548786 0.0349086457 0.0716548786 0.0117232331 0.0929470000 384918105 0 402718720 -0.2746336758 0.0423427001 0.1057847887 265 1305031110.9793450832 0.0748082697 0.0350592103 0.0748082697 0.0117345049 0.0433270000 384715208 0 402718720 -0.2686004043 0.0491024666 0.1084359661 266 1305031111.0114309788 0.0772215873 0.0352177155 0.0772215873 0.0117264034 0.1244100000 384743677 0 402718720 -0.2609640956 0.0475159213 0.1128409058 267 1305031111.0433270931 0.0702051744 0.0353487547 0.0772215873 0.0117157696 0.0563840000 374724777 0 402718720 -0.2551515996 0.0423553474 0.1061392874 268 1305031111.0792829990 0.0674201995 0.0354684242 0.0772215873 0.0117038927 0.0374820000 374714616 0 402718720 -0.2491530627 0.0454120971 0.1062876359 269 1305031111.1115078926 0.0667511001 0.0355847167 0.0772215873 0.0116903090 0.0478570000 374739913 0 402718720 -0.2414929867 0.0409020036 0.1088679060 270 1305031111.1432569027 0.0636803061 0.0356887744 0.0772215873 0.0116694174 0.0504260000 374721136 0 402718720 -0.2350623012 0.0407734998 0.1069424450 271 1305031111.1793260574 0.0643391684 0.0357944955 0.0772215873 0.0117574733 0.0419920000 375427288 0 402718720 -0.2207159549 0.0385330319 0.1077945232 272 1305031111.2114329338 0.0608097613 0.0358864633 0.0772215873 0.0117560218 0.1259980000 375398392 0 402718720 -0.2101343870 0.0353655964 0.1022968441 273 1305031111.2432360649 0.0542170629 0.0359536084 0.0772215873 0.0117598557 0.1201860000 375438105 0 402718720 -0.2057006061 0.0301633179 0.1004597247 274 1305031111.2793080807 0.0571165793 0.0360308455 0.0772215873 0.0118250863 0.1117300000 375405692 0 402718720 -0.1895822734 0.0280263871 0.1043349728 275 1305031111.3115470409 0.0472526476 0.0360716521 0.0772215873 0.0118611349 0.1079770000 378510740 0 402718720 -0.1843944341 0.0302046109 0.0953450054 276 1305031111.3433969021 0.0499298386 0.0361218629 0.0772215873 0.0118401676 0.1027370000 385829088 0 402718720 -0.1713174582 0.0266208369 0.0993917063 277 1305031111.3791339397 0.0489891209 0.0361683151 0.0772215873 0.0118789615 0.0876460000 385995373 0 402718720 -0.1585165113 0.0207676310 0.1028540581 278 1305031111.4112958908 0.0395515710 0.0361804851 0.0772215873 0.0119215236 0.0456550000 386451013 0 402718720 -0.1535058767 0.0244125798 0.0963365734 279 1305031111.4433860779 0.0515716448 0.0362356505 0.0772215873 0.0119505275 0.1329820000 385888413 0 402718720 -0.1308172196 0.0229026023 0.1031825393 280 1305031111.4792590141 0.0571591482 0.0363103773 0.0772215873 0.0121184649 0.0444650000 375961284 0 402718720 -0.1065716967 0.0173376407 0.1031395346 281 1305031111.5112640858 0.0496864095 0.0363579788 0.0772215873 0.0121571435 0.1206820000 376041496 0 402718720 -0.0995298922 0.0121046463 0.0980865732 282 1305031111.5432500839 0.0438072160 0.0363843946 0.0772215873 0.0121367503 0.1156650000 376043848 0 402718720 -0.0913047791 0.0133281294 0.0968096703 283 1305031111.5792369843 0.0397648811 0.0363963398 0.0772215873 0.0122145996 0.1166830000 376046320 0 402718720 -0.0749873370 0.0168653429 0.0933147743 284 1305031111.6112709045 0.0313864909 0.0363786994 0.0772215873 0.0122246663 0.1097010000 380218644 0 402718720 -0.0726175308 0.0138865011 0.0965963006 285 1305031111.6433949471 0.0413413160 0.0363961121 0.0772215873 0.0122869071 0.0908090000 387294997 0 402718720 -0.0495812520 0.0069506019 0.0990581587 286 1305031111.6793200970 0.0407391824 0.0364112977 0.0772215873 0.0124168362 0.0959260000 386675573 0 402718720 -0.0283649825 0.0159363467 0.0961801559 287 1305031111.7117600441 0.0359001793 0.0364095168 0.0772215873 0.0123963664 0.0442700000 387186769 0 402718720 -0.0200898014 0.0121012926 0.0963105410 288 1305031111.7433860302 0.0387778170 0.0364177401 0.0772215873 0.0124282605 0.1300370000 386510999 0 402718720 -0.0025486401 0.0148642687 0.0984553993 289 1305031111.7794229984 0.0324198492 0.0364039065 0.0772215873 0.0125131185 0.0723050000 376591612 0 402718720 0.0093981847 0.0139286537 0.0979827419 290 1305031111.8114058971 0.0215768404 0.0363527787 0.0772215873 0.0125351345 0.1201780000 376681128 0 402718720 0.0106297303 0.0106487684 0.0965355337 291 1305031111.8432989120 0.0191809647 0.0362937690 0.0772215873 0.0125431874 0.1123950000 376681976 0 402718720 0.0216244683 0.0125575997 0.0966290534 292 1305031111.8794419765 0.0116020525 0.0362092084 0.0772215873 0.0125226618 0.1158900000 376685560 0 402718720 0.0290764514 0.0118001094 0.0938462466 293 1305031111.9113540649 0.0143175730 0.0361344929 0.0772215873 0.0125187574 0.1108380000 376917919 0 402718720 0.0307628475 0.0084992787 0.0965071023 294 1305031111.9433000088 0.0117864804 0.0360516765 0.0772215873 0.0125123304 0.1054810000 386575084 0 402718720 0.0473973639 0.0109743103 0.0974899977 295 1305031111.9794490337 0.0120779639 0.0359704097 0.0772215873 0.0126111612 0.0549810000 388130785 0 402718720 0.0697297230 0.0123984031 0.0977850556 296 1305031112.0114328861 0.0176405124 0.0359084844 0.0772215873 0.0125999667 0.0694010000 387646181 0 402718720 0.0858384818 0.0083200661 0.0985039696 297 1305031112.0432701111 0.0193877742 0.0358528591 0.0772215873 0.0125822805 0.0383120000 387371452 0 402718720 0.1001548320 0.0069337366 0.0969191417 298 1305031112.0793390274 0.0153627023 0.0357841002 0.0772215873 0.0126244209 0.1217520000 387304795 0 402718720 0.1135913432 0.0092836870 0.0966284722 299 1305031112.1114230156 0.0147751886 0.0357138362 0.0772215873 0.0126787594 0.0708870000 376696760 0 402718720 0.1133279055 0.0070036324 0.0955105349 300 1305031112.1443419456 0.0153808901 0.0356460598 0.0772215873 0.0126915514 0.0388150000 377411664 0 402718720 0.1322931796 0.0073263515 0.0906647593 301 1305031112.1793899536 0.0151653262 0.0355780175 0.0772215873 0.0127069627 0.1169820000 377382508 0 402718720 0.1420695484 0.0073554749 0.0938674584 302 1305031112.2112538815 0.0241643488 0.0355402239 0.0772215873 0.0127168142 0.1007110000 377386380 0 402718720 0.1450778842 0.0014974331 0.0988082513 303 1305031112.2433691025 0.0286726784 0.0355175587 0.0772215873 0.0127169860 0.0955890000 377389996 0 402718720 0.1637463868 -0.0071658213 0.0931234881 304 1305031112.2793529034 0.0375410877 0.0355242150 0.0772215873 0.0127525967 0.0900260000 377740864 0 402718720 0.1590771973 -0.0024708826 0.0950974897 305 1305031112.3113119602 0.0372358263 0.0355298269 0.0772215873 0.0127328942 0.0897810000 384995628 0 402718720 0.1712789088 -0.0030425014 0.0967364237 306 1305031112.3433229923 0.0416500010 0.0355498274 0.0772215873 0.0127150560 0.0510450000 388764865 0 402718720 0.1786626875 -0.0036460878 0.0927090943 307 1305031112.3793599606 0.0426991619 0.0355731152 0.0772215873 0.0127000708 0.0788310000 388495121 0 402718720 0.1916592419 -0.0007447335 0.0920052603 308 1305031112.4114420414 0.0430377796 0.0355973511 0.0772215873 0.0126856601 0.0385030000 389059925 0 402718720 0.2022810876 0.0007389886 0.0904676914 309 1305031112.4433910847 0.0419425368 0.0356178857 0.0772215873 0.0126705840 0.1172550000 388272809 0 402718720 0.2143605053 -0.0018088722 0.0931506008 310 1305031112.4794180393 0.0475975238 0.0356565297 0.0772215873 0.0126542441 0.0818890000 377349773 0 402718720 0.2212818563 0.0009670929 0.0903942287 311 1305031112.5115039349 0.0491265692 0.0356998417 0.0772215873 0.0126395819 0.0323240000 377392105 0 402718720 0.2292927206 -0.0010773290 0.0907684341 312 1305031112.5432119370 0.0498376638 0.0357451552 0.0772215873 0.0126236799 0.0434270000 377400273 0 402718720 0.2366052270 -0.0007435130 0.0942228436 313 1305031112.5792520046 0.0545479916 0.0358052282 0.0772215873 0.0126088530 0.0327450000 377406725 0 402718720 0.2432974428 -0.0006028848 0.0923655182 314 1305031112.6112608910 0.0461217649 0.0358380834 0.0772215873 0.0126330901 0.0317010000 377377272 0 402718720 0.2590957582 0.0053936131 0.0920410231 315 1305031112.6432459354 0.0407942459 0.0358538173 0.0772215873 0.0126816637 0.0311310000 377380604 0 402718720 0.2731536925 0.0060153101 0.0889586210 316 1305031112.6799519062 0.0502922349 0.0358995084 0.0772215873 0.0126660724 0.0316860000 377383824 0 402718720 0.2711420357 0.0033167908 0.0915858001 317 1305031112.7112510204 0.0513278656 0.0359481783 0.0772215873 0.0126757376 0.0312170000 377387140 0 402718720 0.2745266557 0.0054452843 0.0901619494 318 1305031112.7432448864 0.0480502546 0.0359862352 0.0772215873 0.0126718384 0.0367980000 378196468 0 402718720 0.2797287703 0.0145915784 0.0890657008 319 1305031112.7793099880 0.0509473905 0.0360331354 0.0772215873 0.0126602913 0.1259220000 378185064 0 402718720 0.2786081135 0.0090207150 0.0919960439 320 1305031112.8113100529 0.0649560466 0.0361235195 0.0772215873 0.0127161604 0.1086970000 378188372 0 402718720 0.2629667521 0.0034853788 0.0982700586 321 1305031112.8432860374 0.0618751049 0.0362037425 0.0772215873 0.0127045409 0.1032100000 378191772 0 402718720 0.2611699700 0.0108298212 0.0984893888 322 1305031112.8794209957 0.0528009683 0.0362552866 0.0772215873 0.0127245784 0.0973270000 380584232 0 402718720 0.2670522034 0.0111422297 0.0956107825 323 1305031112.9114110470 0.0568320714 0.0363189919 0.0772215873 0.0127188573 0.0914770000 387923368 0 402718720 0.2584812939 0.0089762863 0.0984563604 324 1305031112.9433209896 0.0590257868 0.0363890746 0.0772215873 0.0127017094 0.0818460000 388605189 0 402718720 0.2509327829 0.0060004741 0.1005163640 325 1305031112.9792780876 0.0553237200 0.0364473350 0.0772215873 0.0127793129 0.0399120000 388750853 0 402718720 0.2456409633 0.0053130863 0.1025457829 326 1305031113.0113530159 0.0465917960 0.0364784530 0.0772215873 0.0127830482 0.1195140000 388493971 0 402718720 0.2462261468 0.0093340576 0.0956916660 327 1305031113.0432310104 0.0465826131 0.0365093526 0.0772215873 0.0127690221 0.0640590000 378808228 0 402718720 0.2370831668 0.0076203989 0.0977770463 328 1305031113.0792510509 0.0467723534 0.0365406422 0.0772215873 0.0127711939 0.1222180000 378890000 0 402718720 0.2270487696 -0.0008493140 0.0987135321 329 1305031113.1113159657 0.0446710773 0.0365653548 0.0772215873 0.0127639546 0.1120000000 378893376 0 402718720 0.2155995816 0.0028654849 0.0952083692 330 1305031113.1433060169 0.0383267142 0.0365706922 0.0772215873 0.0127472033 0.1107380000 378897164 0 402718720 0.2086528093 0.0085218130 0.0934595615 331 1305031113.1793429852 0.0396238007 0.0365799161 0.0772215873 0.0127599594 0.1040390000 378931540 0 402718720 0.1951788366 -0.0006013811 0.0931899250 332 1305031113.2112588882 0.0381179340 0.0365845487 0.0772215873 0.0127439792 0.0976560000 387959608 0 402718720 0.1839043796 0.0000720257 0.0906816497 333 1305031113.2432270050 0.0369615555 0.0365856808 0.0772215873 0.0127262493 0.0442210000 391311799 0 402718720 0.1700667143 0.0044922759 0.0870934799 334 1305031113.2793118954 0.0307765324 0.0365682882 0.0772215873 0.0127549653 0.0637690000 390568821 0 402718720 0.1617856175 -0.0043470850 0.0897342414 335 1305031113.3114519119 0.0399063528 0.0365782526 0.0772215873 0.0127603778 0.1271460000 390199531 0 402718720 0.1414234936 -0.0132971564 0.0889863074 336 1305031113.3432519436 0.0251861215 0.0365443474 0.0772215873 0.0127573396 0.0777550000 379526924 0 402718720 0.1357389092 -0.0023365770 0.0851689652 337 1305031113.3793120384 0.0149105005 0.0364801520 0.0772215873 0.0127624717 0.1230930000 379604356 0 402718720 0.1255955547 -0.0022580200 0.0846902281 338 1305031113.4116249084 0.0151582118 0.0364170694 0.0772215873 0.0127468629 0.1170310000 379606616 0 402718720 0.1094028130 -0.0061525181 0.0870357528 339 1305031113.4432659149 0.0100951167 0.0363394235 0.0772215873 0.0127441111 0.1173410000 379609852 0 402718720 0.0944984630 -0.0000247741 0.0885509104 340 1305031113.4793109894 0.0018131598 0.0362378756 0.0772215873 0.0127533008 0.1112070000 382793204 0 402718720 0.0808449388 -0.0005922974 0.0895932987 341 1305031113.5115230083 0.0077134753 0.0361542264 0.0772215873 0.0127415203 0.1077180000 390897944 0 402718720 0.0595847368 0.0004872759 0.0892835781 342 1305031113.5432419777 0.0069592707 0.0360688610 0.0772215873 0.0127485382 0.0582850000 392257409 0 402718720 0.0451588854 -0.0036044838 0.0862951428 343 1305031113.5793011189 0.0076873419 0.0359861160 0.0772215873 0.0127580149 0.0782950000 391805265 0 402718720 0.0294040274 0.0006271368 0.0849887431 344 1305031113.6112680435 0.0064995978 0.0359003994 0.0772215873 0.0127425770 0.0464090000 391411512 0 402718720 0.0176762789 0.0002047149 0.0876493677 345 1305031113.6432220936 0.0064032362 0.0358149004 0.0772215873 0.0127270642 0.1423850000 391476765 0 402718720 0.0063412795 -0.0010870174 0.0885056257 346 1305031113.6792879105 0.0085266000 0.0357360325 0.0772215873 0.0127162793 0.0715890000 379600457 0 402718720 -0.0077801738 -0.0031146300 0.0881395340 347 1305031113.7119309902 0.0116380285 0.0356665858 0.0772215873 0.0127024015 0.0425920000 379653061 0 402718720 -0.0172287263 -0.0053040944 0.0888468847 348 1305031113.7435901165 0.0131919188 0.0356020034 0.0772215873 0.0126844347 0.0437880000 379679697 0 402718720 -0.0288536306 -0.0030503990 0.0889521092 349 1305031113.7793200016 0.0146477642 0.0355419626 0.0772215873 0.0126784061 0.0422370000 379637289 0 402718720 -0.0436720587 -0.0050403564 0.0899768099 350 1305031113.8112370968 0.0161607228 0.0354865876 0.0772215873 0.0126608359 0.0429000000 379676629 0 402718720 -0.0549001023 -0.0024156389 0.0902224258 351 1305031113.8432950974 0.0168407001 0.0354334655 0.0772215873 0.0126454412 0.0424360000 379656261 0 402718720 -0.0669863671 -0.0007685400 0.0896528736 352 1305031113.8792810440 0.0144121498 0.0353737458 0.0772215873 0.0126807655 0.0413930000 379596288 0 402718720 -0.0852137282 -0.0078001893 0.0909364074 353 1305031113.9112899303 0.0189106949 0.0353271083 0.0772215873 0.0126715241 0.0418020000 379652105 0 402718720 -0.0934589133 -0.0023094271 0.0916019529 354 1305031113.9432909489 0.0213448014 0.0352876102 0.0772215873 0.0126558729 0.0420630000 379657829 0 402718720 -0.1038062498 -0.0023969449 0.0923285261 355 1305031113.9792931080 0.0237313323 0.0352550573 0.0772215873 0.0126428147 0.0417750000 379643429 0 402718720 -0.1191465110 0.0002149912 0.0923505574 356 1305031114.0112569332 0.0218680818 0.0352174535 0.0772215873 0.0126386692 0.0514920000 379609748 0 402718720 -0.1347205490 0.0026081242 0.0916585997 357 1305031114.0433011055 0.0184930358 0.0351706064 0.0772215873 0.0126301545 0.0402540000 379613224 0 402718720 -0.1521672308 0.0038694120 0.0918670520 358 1305031114.0792849064 0.0176675543 0.0351217151 0.0772215873 0.0126315627 0.0446580000 380300040 0 402718720 -0.1693495363 0.0017640828 0.0918817818 359 1305031114.1112630367 0.0227870177 0.0350873567 0.0772215873 0.0126150847 0.1329210000 380257940 0 402718720 -0.1794197559 0.0070982650 0.0932210237 360 1305031114.1432840824 0.0253481437 0.0350603033 0.0772215873 0.0126100133 0.1253190000 380260232 0 402718720 -0.1888533682 0.0070296987 0.0946359634 361 1305031114.1793370247 0.0354398079 0.0350613546 0.0772215873 0.0126104265 0.1191360000 380262236 0 402718720 -0.1938511133 0.0057197576 0.0981293172 362 1305031114.2113029957 0.0374190547 0.0350678675 0.0772215873 0.0126143118 0.1149010000 384227480 0 402718720 -0.2069470286 0.0148801208 0.0960548371 363 1305031114.2433369160 0.0323330089 0.0350603335 0.0772215873 0.0126050506 0.0964370000 391881693 0 402718720 -0.2230856270 0.0124560753 0.0983394831 364 1305031114.2793900967 0.0316310264 0.0350509123 0.0772215873 0.0126514661 0.0835170000 391341783 0 402718720 -0.2379475534 0.0119962730 0.0964422226 365 1305031114.3114290237 0.0374750979 0.0350575539 0.0772215873 0.0126423070 0.0449870000 392127833 0 402718720 -0.2425406724 0.0122141708 0.0970450789 366 1305031114.3433310986 0.0446166359 0.0350836716 0.0772215873 0.0126292580 0.1304850000 391217475 0 402718720 -0.2454198450 0.0106334556 0.0996976644 367 1305031114.3793199062 0.0515455417 0.0351285269 0.0772215873 0.0126175311 0.0542560000 380291749 0 402718720 -0.2530171275 0.0124170128 0.1043423414 368 1305031114.4113969803 0.0519035980 0.0351741113 0.0772215873 0.0126056045 0.0371190000 380278320 0 402718720 -0.2629851997 0.0117084291 0.1066243723 369 1305031114.4433450699 0.0511429049 0.0352173872 0.0772215873 0.0125943142 0.0426000000 380962504 0 402718720 -0.2747265100 0.0139922975 0.1103105247 370 1305031114.4793319702 0.0518027246 0.0352622124 0.0772215873 0.0126055498 0.1323660000 380958660 0 402718720 -0.2855865955 0.0115828998 0.1114767641 371 1305031114.5112659931 0.0579339042 0.0353233221 0.0772215873 0.0125900633 0.1181730000 380961576 0 402718720 -0.2885467410 0.0149926674 0.1138957888 372 1305031114.5432360172 0.0637163818 0.0353996475 0.0772215873 0.0125760981 0.1176530000 380997849 0 402718720 -0.2914195359 0.0161892138 0.1204073131 373 1305031114.5792369843 0.0656623691 0.0354807808 0.0772215873 0.0125648586 0.1099550000 384235700 0 402718720 -0.2976061404 0.0158325098 0.1235484779 374 1305031114.6113910675 0.0662930757 0.0355631666 0.0772215873 0.0125501349 0.0988440000 392014224 0 402718720 -0.3013161719 0.0152472071 0.1231151968 375 1305031114.6441500187 0.0619522221 0.0356335374 0.0772215873 0.0125352073 0.0621220000 393153913 0 402718720 -0.3088669777 0.0110306302 0.1224130243 376 1305031114.6792509556 0.0657865182 0.0357137315 0.0772215873 0.0125241552 0.0668720000 392655793 0 402718720 -0.3112583756 0.0107688466 0.1266731471 377 1305031114.7113060951 0.0677207336 0.0357986307 0.0772215873 0.0125113046 0.1331720000 392253059 0 402718720 -0.3142153323 0.0114980014 0.1306349486 378 1305031114.7432758808 0.0673868656 0.0358821975 0.0772215873 0.0124968222 0.0674350000 381032569 0 402718720 -0.3154681921 0.0091122827 0.1295336932 379 1305031114.7792890072 0.0698717460 0.0359718797 0.0772215873 0.0124817379 0.0436340000 381691560 0 402718720 -0.3140376806 0.0121100824 0.1286772192 380 1305031114.8113029003 0.0691836849 0.0360592792 0.0772215873 0.0124688320 0.1375300000 381768709 0 402718720 -0.3134761155 0.0141427424 0.1259908229 381 1305031114.8432080746 0.0695066676 0.0361470676 0.0772215873 0.0124528516 0.1265990000 381784161 0 402718720 -0.3114016652 0.0140445335 0.1265006661 382 1305031114.8792810440 0.0693233609 0.0362339165 0.0772215873 0.0124368321 0.1262960000 381765021 0 402718720 -0.3080985546 0.0180939231 0.1258025467 383 1305031114.9128789902 0.0683616698 0.0363178010 0.0772215873 0.0124235548 0.1176710000 386657200 0 402718720 -0.3047525883 0.0190542117 0.1256140769 384 1305031114.9432640076 0.0711963028 0.0364086304 0.0772215873 0.0124087386 0.0952500000 394211257 0 402718720 -0.2981862426 0.0253810529 0.1273786724 385 1305031114.9792799950 0.0672547072 0.0364887501 0.0772215873 0.0123984959 0.1030470000 393602485 0 402718720 -0.2927553952 0.0258370899 0.1282635331 386 1305031115.0113000870 0.0655710846 0.0365640930 0.0772215873 0.0123851320 0.0451790000 393441948 0 402718720 -0.2861556411 0.0294022933 0.1267890334 387 1305031115.0435299873 0.0691380426 0.0366482634 0.0772215873 0.0123744042 0.1336920000 393481681 0 402718720 -0.2756462693 0.0298605021 0.1350873709 388 1305031115.0792379379 0.0631046742 0.0367164500 0.0772215873 0.0123661820 0.0942220000 381646944 0 402718720 -0.2671390176 0.0305912886 0.1336485893 389 1305031115.1112298965 0.0714343265 0.0368056990 0.0772215873 0.0123783147 0.0432660000 382298092 0 402718720 -0.2497966141 0.0324210338 0.1429115683 390 1305031115.1432940960 0.0671627223 0.0368835376 0.0772215873 0.0123633131 0.1302930000 382302716 0 402718720 -0.2399619818 0.0295965653 0.1416628063 391 1305031115.1794400215 0.0544560775 0.0369284801 0.0772215873 0.0123552801 0.1210250000 382305312 0 402718720 -0.2341720313 0.0280374009 0.1379649937 392 1305031115.2113740444 0.0599038750 0.0369870908 0.0772215873 0.0123880673 0.1182910000 382307548 0 402718720 -0.2145583630 0.0207268354 0.1436386853 393 1305031115.2432971001 0.0562086962 0.0370360007 0.0772215873 0.0123741186 0.1134540000 385320140 0 402718720 -0.2027299255 0.0169595908 0.1439393759 394 1305031115.2799661160 0.0496067964 0.0370679063 0.0772215873 0.0123859143 0.1082630000 393196320 0 402718720 -0.1884328574 0.0224004202 0.1433675587 395 1305031115.3117039204 0.0617136844 0.0371303007 0.0772215873 0.0124346352 0.0703670000 395287989 0 402718720 -0.1619239748 0.0123121925 0.1524111331 396 1305031115.3434259892 0.0529524684 0.0371702557 0.0772215873 0.0124278960 0.0647800000 394882761 0 402718720 -0.1537930965 0.0191305466 0.1505352855 397 1305031115.3791658878 0.0348584391 0.0371644324 0.0772215873 0.0125425171 0.1470990000 394413105 0 402718720 -0.1532033831 0.0280640963 0.1531606168 398 1305031115.4112370014 0.0346287750 0.0371580615 0.0772215873 0.0125407543 0.0427550000 382317216 0 402718720 -0.1388520896 0.0231257416 0.1598007977 399 1305031115.4431591034 0.0417173244 0.0371694882 0.0772215873 0.0125510208 0.0414070000 382320400 0 402718720 -0.1158455014 0.0246557705 0.1642955989 400 1305031115.4792408943 0.0345897898 0.0371630389 0.0772215873 0.0125392629 0.0415120000 382323700 0 402718720 -0.1020067930 0.0238580741 0.1670014411 401 1305031115.5112531185 0.0485354848 0.0371913991 0.0772215873 0.0126367982 0.0446270000 382869548 0 402718720 -0.0710730627 0.0170319956 0.1686411500 402 1305031115.5436201096 0.0482914001 0.0372190111 0.0772215873 0.0126279041 0.1234080000 382954272 0 402718720 -0.0544657037 0.0139879016 0.1691862047 403 1305031115.5793149471 0.0403030962 0.0372266639 0.0772215873 0.0126231039 0.1187610000 382954888 0 402718720 -0.0406590812 0.0147574004 0.1694864780 404 1305031115.6114239693 0.0371291190 0.0372264225 0.0772215873 0.0126084768 0.1179910000 382960216 0 402718720 -0.0283532441 0.0131849553 0.1688856333 405 1305031115.6432540417 0.0371515527 0.0372262376 0.0772215873 0.0125983644 0.1180160000 383276120 0 402718720 -0.0125255566 0.0116811246 0.1686578244 406 1305031115.6792409420 0.0230352618 0.0371912844 0.0772215873 0.0126018830 0.1176530000 391483236 0 402718720 -0.0095484694 0.0143888351 0.1682694256 407 1305031115.7113199234 0.0253318120 0.0371621457 0.0772215873 0.0126368007 0.0671940000 395853421 0 402718720 0.0120017556 0.0166645460 0.1679409295 408 1305031115.7432498932 0.0354459696 0.0371579394 0.0772215873 0.0126627339 0.1042230000 395399257 0 402718720 0.0374798328 0.0125141209 0.1695654541 409 1305031115.7794249058 0.0242491439 0.0371263775 0.0772215873 0.0126680915 0.0440600000 396019797 0 402718720 0.0457976684 0.0150305592 0.1655675769 410 1305031115.8112769127 0.0274230428 0.0371027109 0.0772215873 0.0126807334 0.1340160000 395193723 0 402718720 0.0652497560 0.0143327005 0.1639787257 411 1305031115.8432240486 0.0283448379 0.0370814022 0.0772215873 0.0126730993 0.0578390000 383620944 0 402718720 0.0784674287 0.0140822064 0.1664272994 412 1305031115.8791980743 0.0266463850 0.0370560745 0.0772215873 0.0126617515 0.1276270000 383607568 0 402718720 0.0807363018 0.0109939910 0.1676529646 413 1305031115.9111180305 0.0222974755 0.0370203394 0.0772215873 0.0126609349 0.1170740000 383610200 0 402718720 0.0982952341 0.0172779076 0.1663691998 414 1305031115.9433109760 0.0249175895 0.0369911057 0.0772215873 0.0126587100 0.1113500000 383613512 0 402718720 0.1124239862 0.0166752525 0.1673735380 415 1305031115.9807400703 0.0231209435 0.0369576836 0.0772215873 0.0126676119 0.1037750000 383905600 0 402718720 0.1237296835 0.0211100504 0.1705980003 416 1305031116.0113790035 0.0261316784 0.0369316595 0.0772215873 0.0127033689 0.0981710000 389658036 0 402718720 0.1422247440 0.0203391165 0.1672262847 417 1305031116.0431640148 0.0256432854 0.0369045891 0.0772215873 0.0126890441 0.0854330000 395740248 0 402718720 0.1499569714 0.0227178466 0.1709126085 418 1305031116.0800299644 0.0250929911 0.0368763317 0.0772215873 0.0127194384 0.0457780000 396132207 0 402718720 0.1488575935 0.0306505375 0.1738504618 419 1305031116.1112999916 0.0288940798 0.0368572810 0.0772215873 0.0127071456 0.0741430000 396799781 0 402718720 0.1541723311 0.0328302309 0.1762326062 420 1305031116.1434469223 0.0386248752 0.0368614895 0.0772215873 0.0126959827 0.0373590000 396055252 0 402718720 0.1658283174 0.0237774663 0.1806038767 421 1305031116.1795721054 0.0405410938 0.0368702297 0.0772215873 0.0127009070 0.1136440000 395988607 0 402718720 0.1744844317 0.0271947235 0.1801891178 422 1305031116.2113199234 0.0423028171 0.0368831031 0.0772215873 0.0126964967 0.0556640000 384347376 0 402718720 0.1888612360 0.0247682892 0.1795128882 423 1305031116.2433199883 0.0490016304 0.0369117521 0.0772215873 0.0126930578 0.1246720000 384443100 0 402718720 0.2021905184 0.0177507102 0.1819617599 424 1305031116.2793850899 0.0484980978 0.0369390784 0.0772215873 0.0127036680 0.1055990000 384449884 0 402718720 0.2111374438 0.0214835834 0.1814932227 425 1305031116.3113360405 0.0519266687 0.0369743433 0.0772215873 0.0127085858 0.1023420000 384453316 0 402718720 0.2123509794 0.0224680975 0.1810471267 426 1305031116.3432919979 0.0684692487 0.0370482750 0.0772215873 0.0127178413 0.1006430000 384456524 0 402718720 0.2128661126 0.0081936456 0.1875370443 427 1305031116.3793840408 0.0719872937 0.0371300994 0.0772215873 0.0127074850 0.0932590000 384827884 0 402718720 0.2130978107 0.0076340884 0.1843904704 428 1305031116.4113330841 0.0622556396 0.0371888039 0.0772215873 0.0127198916 0.0927700000 393384048 0 402718720 0.2141072601 0.0228465647 0.1801546067 429 1305031116.4433689117 0.0615443513 0.0372455768 0.0772215873 0.0127160399 0.0630260000 398156253 0 402718720 0.2166125774 0.0229896940 0.1776265800 430 1305031116.4798500538 0.0684180781 0.0373180710 0.0772215873 0.0127022839 0.0715060000 397797115 0 402718720 0.2139264792 0.0146044344 0.1798987985 431 1305031116.5112049580 0.0654053092 0.0373832386 0.0772215873 0.0126905630 0.0516470000 398033733 0 402718720 0.2138862610 0.0139709003 0.1747576594 432 1305031116.5432620049 0.0692530125 0.0374570112 0.0772215873 0.0126913311 0.0376500000 397559300 0 402718720 0.2012510598 0.0139832702 0.1739888191 433 1305031116.5793130398 0.0659974515 0.0375229245 0.0772215873 0.0127052587 0.1132710000 397492007 0 402718720 0.1892784238 0.0186820496 0.1729174852 434 1305031116.6112608910 0.0706435665 0.0375992393 0.0772215873 0.0127063923 0.0958260000 384478640 0 402718720 0.1780654788 0.0108280201 0.1709462851 435 1305031116.6433548927 0.0639600754 0.0376598389 0.0772215873 0.0127004694 0.0344960000 384481568 0 402718720 0.1699335724 0.0150225684 0.1673572212 436 1305031116.6792809963 0.0553677343 0.0377004534 0.0772215873 0.0127035537 0.0351030000 384485180 0 402718720 0.1603558064 0.0176851973 0.1658629775 437 1305031116.7116339207 0.0480142571 0.0377240547 0.0772215873 0.0126901379 0.0356520000 384488292 0 402718720 0.1516399980 0.0214182138 0.1630684137 438 1305031116.7432909012 0.0485829711 0.0377488468 0.0772215873 0.0126951013 0.0362180000 384491844 0 402718720 0.1341975927 0.0226657204 0.1595912576 439 1305031116.7792980671 0.0437930152 0.0377626148 0.0772215873 0.0127279625 0.0481840000 384495200 0 402718720 0.1184637770 0.0250981525 0.1606947333 440 1305031116.8113429546 0.0461075976 0.0377815807 0.0772215873 0.0127573226 0.0410380000 385135116 0 402718720 0.1038815007 0.0198184997 0.1591981947 441 1305031116.8460888863 0.0401562490 0.0377869654 0.0772215873 0.0128193374 0.1235490000 385135008 0 402718720 0.0914656669 0.0191498622 0.1579586864 442 1305031116.8801651001 0.0352139249 0.0377811441 0.0772215873 0.0128056788 0.1148720000 385138076 0 402718720 0.0788317993 0.0236880388 0.1575248539 443 1305031116.9120440483 0.0396442413 0.0377853497 0.0772215873 0.0128033208 0.1133670000 385141760 0 402718720 0.0560948029 0.0244531035 0.1566801816 444 1305031116.9432959557 0.0299016759 0.0377675937 0.0772215873 0.0127986816 0.1114500000 385538440 0 402718720 0.0460548997 0.0312452205 0.1530297995 445 1305031116.9793510437 0.0280181691 0.0377456849 0.0772215873 0.0128389768 0.1060230000 390482656 0 402718720 0.0373798683 0.0243963599 0.1496923566 446 1305031117.0113821030 0.0292840078 0.0377267125 0.0772215873 0.0128458213 0.1021870000 398232728 0 402718720 0.0123266894 0.0293271150 0.1481640488 447 1305031117.0432610512 0.0228788164 0.0376934957 0.0772215873 0.0128314153 0.0493040000 400304681 0 402718720 0.0040905727 0.0350719914 0.1478998214 448 1305031117.0795199871 0.0214918405 0.0376573313 0.0772215873 0.0128628418 0.0922010000 400073341 0 402718720 -0.0097651156 0.0362324677 0.1449126303 449 1305031117.1112380028 0.0246892795 0.0376284492 0.0772215873 0.0128637631 0.0425530000 398661872 0 402718720 -0.0226920936 0.0342366137 0.1430423111 450 1305031117.1432180405 0.0205543675 0.0375905068 0.0772215873 0.0128502778 0.1450640000 398595211 0 402718720 -0.0283965152 0.0406990722 0.1437668651 451 1305031117.1792640686 0.0239969045 0.0375603658 0.0772215873 0.0128484082 0.0971050000 385160560 0 402718720 -0.0350453146 0.0397303328 0.1447130293 452 1305031117.2113609314 0.0281150341 0.0375394691 0.0772215873 0.0128505009 0.0403660000 385163788 0 402718720 -0.0344786234 0.0420916602 0.1502951384 453 1305031117.2432770729 0.0299631022 0.0375227442 0.0772215873 0.0128474893 0.0396040000 385167248 0 402718720 -0.0338729694 0.0472040400 0.1528514922 454 1305031117.2792990208 0.0356295332 0.0375185741 0.0772215873 0.0128367608 0.0398570000 385233005 0 402718720 -0.0344439894 0.0429033190 0.1557405144 455 1305031117.3111999035 0.0365180783 0.0375163752 0.0772215873 0.0128279027 0.0401940000 385286981 0 402718720 -0.0391274579 0.0398625955 0.1573889554 456 1305031117.3432428837 0.0384716354 0.0375184701 0.0772215873 0.0128205600 0.0410480000 385288337 0 402718720 -0.0413976870 0.0355272628 0.1583802253 457 1305031117.3794538975 0.0398276784 0.0375235231 0.0772215873 0.0128126963 0.0411760000 385270837 0 402718720 -0.0429158397 0.0301050544 0.1583374739 458 1305031117.4112210274 0.0395852551 0.0375280247 0.0772215873 0.0127987136 0.0400580000 385204181 0 402718720 -0.0444377847 0.0261882376 0.1578693092 459 1305031117.4432740211 0.0375556387 0.0375280848 0.0772215873 0.0127857608 0.0401000000 385241417 0 402718720 -0.0439305678 0.0254679769 0.1577298641 460 1305031117.4794030190 0.0377599820 0.0375285890 0.0772215873 0.0127862768 0.0403750000 385211837 0 402718720 -0.0429787561 0.0173665360 0.1562750936 461 1305031117.5113248825 0.0386074856 0.0375309293 0.0772215873 0.0127735130 0.0509640000 385193424 0 402718720 -0.0432544537 0.0097837634 0.1563045830 462 1305031117.5442850590 0.0312510170 0.0375173364 0.0772215873 0.0127635164 0.0402350000 385196596 0 402718720 -0.0466695316 0.0097370446 0.1540711373 463 1305031117.5791549683 0.0286023952 0.0374980817 0.0772215873 0.0127504002 0.0403120000 385233289 0 402718720 -0.0458789319 0.0048078485 0.1549791545 464 1305031117.6111590862 0.0258882437 0.0374730605 0.0772215873 0.0127380463 0.0405830000 385237305 0 402718720 -0.0468804315 0.0017257482 0.1577394605 465 1305031117.6432840824 0.0260978341 0.0374485976 0.0772215873 0.0127275731 0.0406600000 385206388 0 402718720 -0.0474355519 -0.0073301867 0.1600165665 466 1305031117.6792619228 0.0202208199 0.0374116281 0.0772215873 0.0127162275 0.0414270000 385263773 0 402718720 -0.0486497134 -0.0116173327 0.1613421589 467 1305031117.7112150192 0.0216564108 0.0373778911 0.0772215873 0.0127041975 0.0503500000 385249697 0 402718720 -0.0470183678 -0.0194668099 0.1664391905 468 1305031117.7431840897 0.0218029078 0.0373446112 0.0772215873 0.0126944430 0.0400060000 385216172 0 402718720 -0.0474539772 -0.0297568627 0.1680171043 469 1305031117.7794671059 0.0179745369 0.0373033104 0.0772215873 0.0126817384 0.0410210000 385294389 0 402718720 -0.0465682521 -0.0330253094 0.1729118675 470 1305031117.8113200665 0.0235066246 0.0372739557 0.0772215873 0.0126813156 0.0395390000 385222372 0 402718720 -0.0448953956 -0.0486500710 0.1760155559 471 1305031117.8433070183 0.0240023099 0.0372457781 0.0772215873 0.0126775901 0.0397580000 385225628 0 402718720 -0.0412792936 -0.0527789555 0.1820260435 472 1305031117.8794670105 0.0234456286 0.0372165405 0.0772215873 0.0126684857 0.0398290000 385280829 0 402718720 -0.0406011641 -0.0597817376 0.1859679967 473 1305031117.9114069939 0.0218392462 0.0371840304 0.0772215873 0.0126559365 0.0398660000 385255473 0 402718720 -0.0442983508 -0.0708882809 0.1898118854 474 1305031117.9432721138 0.0216207076 0.0371511964 0.0772215873 0.0126433663 0.0509000000 385304737 0 402718720 -0.0448412001 -0.0760080069 0.1931071430 475 1305031117.9792630672 0.0215905849 0.0371184372 0.0772215873 0.0126357906 0.0392860000 385342297 0 402718720 -0.0485006869 -0.0831693783 0.1959749013 476 1305031118.0112280846 0.0224186853 0.0370875554 0.0772215873 0.0126292946 0.0388700000 385284601 0 402718720 -0.0481695719 -0.0967026204 0.2047414929 477 1305031118.0435490608 0.0235572699 0.0370591900 0.0772215873 0.0126169282 0.0419860000 385792312 0 402718720 -0.0501111448 -0.1041975990 0.2074262202 478 1305031118.0793690681 0.0254142080 0.0370348281 0.0772215873 0.0126072914 0.1222940000 385892309 0 402718720 -0.0487952754 -0.1110861599 0.2129702270 479 1305031118.1112170219 0.0281294025 0.0370162364 0.0772215873 0.0125973223 0.1183730000 385855872 0 402718720 -0.0463369414 -0.1213334873 0.2186236531 480 1305031118.1432559490 0.0282460749 0.0369979652 0.0772215873 0.0125881719 0.1116490000 385898505 0 402718720 -0.0509501770 -0.1284651905 0.2205930948 481 1305031118.1793229580 0.0308258478 0.0369851334 0.0772215873 0.0125843061 0.1031530000 386173776 0 402718720 -0.0503300168 -0.1409801543 0.2259027213 482 1305031118.2112019062 0.0321957655 0.0369751969 0.0772215873 0.0125719957 0.0992410000 391943680 0 402718720 -0.0546320155 -0.1508899331 0.2281858176 483 1305031118.2431728840 0.0315502286 0.0369639651 0.0772215873 0.0125650572 0.0936360000 398432276 0 402718720 -0.0580565631 -0.1579615176 0.2321754098 484 1305031118.2791941166 0.0341656879 0.0369581836 0.0772215873 0.0125847331 0.0445310000 399058245 0 402718720 -0.0536175370 -0.1689280719 0.2371805310 485 1305031118.3112990856 0.0363815092 0.0369569945 0.0772215873 0.0125727711 0.0673940000 400134181 0 402718720 -0.0530893952 -0.1722341925 0.2382103056 486 1305031118.3433239460 0.0379994884 0.0369591396 0.0772215873 0.0125607740 0.0383550000 398869979 0 402718720 -0.0520895906 -0.1781450957 0.2411499918 487 1305031118.3792080879 0.0400031656 0.0369653902 0.0772215873 0.0125483801 0.1169360000 398794735 0 402718720 -0.0566160083 -0.1825948209 0.2426204979 488 1305031118.4112958908 0.0426267311 0.0369769913 0.0772215873 0.0125370064 0.0969000000 385893029 0 402718720 -0.0556094125 -0.1834037900 0.2437397540 489 1305031118.4457030296 0.0427093208 0.0369887138 0.0772215873 0.0125243241 0.0410630000 386356184 0 402718720 -0.0539985299 -0.1841093451 0.2481635213 490 1305031118.4792850018 0.0425555147 0.0370000746 0.0772215873 0.0125124671 0.1135780000 386484073 0 402718720 -0.0531985871 -0.1874228865 0.2503288388 491 1305031118.5112550259 0.0439340957 0.0370141969 0.0772215873 0.0124999797 0.1124990000 386523349 0 402718720 -0.0526654050 -0.1849524230 0.2505218685 492 1305031118.5451989174 0.0464134850 0.0370333011 0.0772215873 0.0124890468 0.1089830000 386495845 0 402718720 -0.0518896729 -0.1801285148 0.2488762140 493 1305031118.5792849064 0.0441625752 0.0370477621 0.0772215873 0.0124784766 0.1034110000 386817176 0 402718720 -0.0520305783 -0.1779117286 0.2504037917 494 1305031118.6161420345 0.0434155203 0.0370606523 0.0772215873 0.0124684373 0.1033640000 394928980 0 402718720 -0.0513245724 -0.1732762456 0.2491236329 495 1305031118.6453309059 0.0438961610 0.0370744614 0.0772215873 0.0124589302 0.0524200000 399840213 0 402718720 -0.0529781431 -0.1669041365 0.2467102855 496 1305031118.6792950630 0.0416485928 0.0370836835 0.0772215873 0.0124506347 0.0940130000 399390008 0 402718720 -0.0541583486 -0.1594445705 0.2445879281 497 1305031118.7114210129 0.0373183377 0.0370841556 0.0772215873 0.0124435393 0.0387480000 400158777 0 402718720 -0.0538910478 -0.1572971940 0.2448935956 498 1305031118.7468008995 0.0394553021 0.0370889170 0.0772215873 0.0124453104 0.1342220000 399210013 0 402718720 -0.0587225780 -0.1501251608 0.2367718071 499 1305031118.7792770863 0.0386716500 0.0370920888 0.0772215873 0.0124610528 0.0836060000 386486100 0 402718720 -0.0552123450 -0.1287960410 0.2325448245 500 1305031118.8112208843 0.0309654083 0.0370798354 0.0772215873 0.0124795781 0.0351570000 386558073 0 402718720 -0.0514377765 -0.1318857670 0.2342438102 501 1305031118.8467741013 0.0283870585 0.0370624845 0.0772215873 0.0124727853 0.0602140000 386531021 0 402718720 -0.0474159271 -0.1229199246 0.2287407070 502 1305031118.8792080879 0.0306968335 0.0370498040 0.0772215873 0.0125031837 0.0349210000 386495944 0 402718720 -0.0473961011 -0.1007380709 0.2180893123 503 1305031118.9111769199 0.0253268238 0.0370264978 0.0772215873 0.0125234528 0.0361350000 386546917 0 402718720 -0.0470794216 -0.0984125957 0.2160341889 504 1305031118.9470090866 0.0219541807 0.0369965925 0.0772215873 0.0125224167 0.0355880000 386528237 0 402718720 -0.0486707985 -0.0863075256 0.2083741724 505 1305031118.9793939590 0.0223549027 0.0369675990 0.0772215873 0.0125184711 0.0357910000 386506132 0 402718720 -0.0495433733 -0.0696542040 0.2002396882 506 1305031119.0113630295 0.0183154475 0.0369307370 0.0772215873 0.0125138254 0.0358410000 386509520 0 402718720 -0.0509059653 -0.0629118234 0.1959602684 507 1305031119.0471799374 0.0141490353 0.0368858027 0.0772215873 0.0125040713 0.0375660000 386566429 0 402718720 -0.0533265769 -0.0570395514 0.1902751327 508 1305031119.0792229176 0.0115124276 0.0368358551 0.0772215873 0.0124950424 0.0372290000 386563085 0 402718720 -0.0561164469 -0.0471387580 0.1833952069 509 1305031119.1113278866 0.0107304920 0.0367845676 0.0772215873 0.0124856366 0.0371100000 386570101 0 402718720 -0.0546733215 -0.0375487730 0.1787665486 510 1305031119.1476290226 0.0087601766 0.0367296178 0.0772215873 0.0124827383 0.0367250000 386522700 0 402718720 -0.0570693538 -0.0261588488 0.1716237813 511 1305031119.1792619228 0.0157760158 0.0366886127 0.0772215873 0.0124927072 0.0385050000 386607889 0 402718720 -0.0534152202 -0.0243027750 0.1677623093 512 1305031119.2113640308 0.0161343236 0.0366484676 0.0772215873 0.0124813631 0.0369900000 386599581 0 402718720 -0.0517487042 -0.0122586954 0.1613813937 513 1305031119.2476599216 0.0167409591 0.0366096616 0.0772215873 0.0124730587 0.0376430000 386607985 0 402718720 -0.0534392968 -0.0023902003 0.1556131095 514 1305031119.2792439461 0.0183361433 0.0365741100 0.0772215873 0.0124628226 0.0516570000 386693825 0 402718720 -0.0522295311 0.0075164484 0.1508409381 515 1305031119.3112120628 0.0183672830 0.0365387569 0.0772215873 0.0124514316 0.0409630000 386686229 0 402718720 -0.0534542650 0.0152431456 0.1464146972 516 1305031119.3477499485 0.0233306065 0.0365131597 0.0772215873 0.0124404756 0.0375270000 386711637 0 402718720 -0.0529557765 0.0205739252 0.1429634392 517 1305031119.3792390823 0.0237054601 0.0364883866 0.0772215873 0.0124318073 0.0400560000 386681101 0 402718720 -0.0507615954 0.0334209837 0.1370053291 518 1305031119.4114921093 0.0300082900 0.0364758768 0.0772215873 0.0124271137 0.0363610000 386676865 0 402718720 -0.0469103381 0.0402356125 0.1359094381 519 1305031119.4477260113 0.0353439227 0.0364736957 0.0772215873 0.0124154711 0.0362060000 386708401 0 402718720 -0.0459131151 0.0470351428 0.1327985078 520 1305031119.4792668819 0.0318305530 0.0364647666 0.0772215873 0.0124185963 0.0455050000 386657516 0 402718720 -0.0507799089 0.0606524348 0.1284337342 521 1305031119.5112578869 0.0333889164 0.0364588629 0.0772215873 0.0124082703 0.0370530000 386660928 0 402718720 -0.0506729893 0.0678266138 0.1239466071 522 1305031119.5474140644 0.0372572616 0.0364603924 0.0772215873 0.0123977101 0.0350950000 386664004 0 402718720 -0.0515023991 0.0782575011 0.1215965226 523 1305031119.5795691013 0.0402404964 0.0364676201 0.0772215873 0.0123973178 0.0339800000 386667480 0 402718720 -0.0489424467 0.0905424729 0.1190038323 524 1305031119.6150240898 0.0438826680 0.0364817709 0.0772215873 0.0123966070 0.0350200000 386670896 0 402718720 -0.0502767488 0.0946193188 0.1176363006 525 1305031119.6488890648 0.0440666713 0.0364962184 0.0772215873 0.0124114083 0.0406940000 387231336 0 402718720 -0.0542025380 0.1100533679 0.1144226640 526 1305031119.6792080402 0.0473755896 0.0365169016 0.0772215873 0.0124021166 0.1222480000 387311316 0 402718720 -0.0523220487 0.1203058288 0.1131292209 527 1305031119.7152490616 0.0503777154 0.0365432029 0.0772215873 0.0123931696 0.1159750000 387315152 0 402718720 -0.0543150268 0.1246660724 0.1124637574 528 1305031119.7471930981 0.0542215854 0.0365766847 0.0772215873 0.0123882049 0.1138200000 387318396 0 402718720 -0.0590419061 0.1309149414 0.1120488644 529 1305031119.7791690826 0.0575046726 0.0366162461 0.0772215873 0.0123769001 0.1060080000 391149004 0 402718720 -0.0592341833 0.1390347779 0.1117225587 530 1305031119.8145709038 0.0601027943 0.0366605604 0.0772215873 0.0123696034 0.0977080000 398892560 0 402718720 -0.0574875921 0.1476827115 0.1103745848 531 1305031119.8474450111 0.0661960170 0.0367161827 0.0772215873 0.0123622871 0.0385560000 402107757 0 402718720 -0.0550905690 0.1548591405 0.1097029820 532 1305031119.8792319298 0.0699982643 0.0367787430 0.0772215873 0.0123577700 0.0845140000 401287644 0 402718720 -0.0562879518 0.1584643722 0.1091175899 533 1305031119.9114239216 0.0661007091 0.0368337561 0.0772215873 0.0123737649 0.1383920000 400483927 0 402718720 -0.0605871975 0.1723290682 0.1056904048 534 1305031119.9474620819 0.0734744072 0.0369023715 0.0772215873 0.0123716847 0.0959200000 387951944 0 402718720 -0.0579677671 0.1749381274 0.1056078896 535 1305031119.9795460701 0.0748779029 0.0369733538 0.0772215873 0.0123602520 0.1236750000 387933296 0 402718720 -0.0578322709 0.1801036745 0.1036532372 536 1305031120.0152831078 0.0757288858 0.0370456589 0.0772215873 0.0123572766 0.1101030000 387936020 0 402718720 -0.0591116324 0.1847951412 0.1021250188 537 1305031120.0473101139 0.0793309957 0.0371244026 0.0793309957 0.0123545352 0.1061820000 391399024 0 402718720 -0.0627500862 0.1888297498 0.1042140722 538 1305031120.0794179440 0.0831490979 0.0372099503 0.0831490979 0.0123542077 0.0978080000 398906832 0 402718720 -0.0637371838 0.1845994890 0.1039670110 539 1305031120.1152489185 0.0796716586 0.0372887290 0.0831490979 0.0123630896 0.0388870000 403279563 0 402718720 -0.0645011589 0.1942527890 0.1038610786 540 1305031120.1481750011 0.0822220668 0.0373719389 0.0831490979 0.0123802030 0.0897650000 402686666 0 402718720 -0.0639308169 0.1867200136 0.1041601300 541 1305031120.1792609692 0.0861947089 0.0374621843 0.0861947089 0.0123791548 0.0361760000 401338903 0 402718720 -0.0609856583 0.1775798351 0.1049737334 542 1305031120.2152600288 0.0845993608 0.0375491533 0.0861947089 0.0123681259 0.1303680000 401259867 0 402718720 -0.0617649630 0.1741317660 0.1051386744 543 1305031120.2480180264 0.0792915672 0.0376260270 0.0861947089 0.0123577695 0.0886140000 387949592 0 402718720 -0.0618117973 0.1731465608 0.1050543338 544 1305031120.2794411182 0.0786445215 0.0377014286 0.0861947089 0.0123478463 0.0336590000 387952512 0 402718720 -0.0595426336 0.1658731997 0.1060115322 545 1305031120.3152129650 0.0748276934 0.0377695502 0.0861947089 0.0123373687 0.0335450000 387955888 0 402718720 -0.0614316687 0.1601704508 0.1071408167 546 1305031120.3477969170 0.0693977475 0.0378274773 0.0861947089 0.0123269410 0.0343280000 387959064 0 402718720 -0.0604067184 0.1534057111 0.1087114140 547 1305031120.3794460297 0.0682489276 0.0378830924 0.0861947089 0.0123183208 0.0451870000 387962260 0 402718720 -0.0604191646 0.1447207928 0.1130618453 548 1305031120.4154899120 0.0721015707 0.0379455349 0.0861947089 0.0123242780 0.0435630000 387965852 0 402718720 -0.0570239313 0.1288723797 0.1181125268 549 1305031120.4474329948 0.0630176291 0.0379912035 0.0861947089 0.0123162799 0.0441620000 387968860 0 402718720 -0.0552835502 0.1251989305 0.1199680939 550 1305031120.4794321060 0.0635844469 0.0380377367 0.0861947089 0.0123088209 0.0338700000 387972396 0 402718720 -0.0542185977 0.1142386124 0.1251098812 551 1305031120.5148770809 0.0573578998 0.0380728005 0.0861947089 0.0122986198 0.0337810000 387975696 0 402718720 -0.0573295429 0.1086556315 0.1276869476 552 1305031120.5478069782 0.0486508012 0.0380919636 0.0861947089 0.0122916719 0.0336050000 387979272 0 402718720 -0.0581839234 0.1042370051 0.1301755607 553 1305031120.5795590878 0.0465556867 0.0381072687 0.0861947089 0.0122829809 0.0374480000 387982024 0 402718720 -0.0565475747 0.0978749022 0.1337609738 554 1305031120.6152710915 0.0490795933 0.0381270743 0.0861947089 0.0122766407 0.0363550000 387985512 0 402718720 -0.0540999658 0.0876489878 0.1403526217 555 1305031120.6473538876 0.0420746841 0.0381341871 0.0861947089 0.0122687960 0.0337080000 387988672 0 402718720 -0.0537873581 0.0827689469 0.1429616809 556 1305031120.6793179512 0.0424004756 0.0381418603 0.0861947089 0.0122786040 0.0342000000 387992104 0 402718720 -0.0501536541 0.0762795508 0.1478489637 557 1305031120.7145531178 0.0396157205 0.0381445064 0.0861947089 0.0122685432 0.0346230000 387994876 0 402718720 -0.0499461144 0.0685801432 0.1507036686 558 1305031120.7473959923 0.0354251973 0.0381396331 0.0861947089 0.0122619756 0.0367310000 387998328 0 402718720 -0.0505035408 0.0609165058 0.1555561721 559 1305031120.7799079418 0.0354237333 0.0381347746 0.0861947089 0.0122533457 0.0331810000 388001780 0 402718720 -0.0489205234 0.0527237728 0.1601720601 560 1305031120.8149440289 0.0324055217 0.0381245437 0.0861947089 0.0122492411 0.0348320000 388049813 0 402718720 -0.0485446453 0.0464955568 0.1615522951 561 1305031120.8479421139 0.0307493899 0.0381113973 0.0861947089 0.0122432839 0.0364300000 388008252 0 402718720 -0.0475319885 0.0380886719 0.1664257646 562 1305031120.8834540844 0.0320517831 0.0381006151 0.0861947089 0.0122340682 0.0443020000 388011244 0 402718720 -0.0452607945 0.0283689648 0.1697379351 563 1305031120.9154539108 0.0280547850 0.0380827717 0.0861947089 0.0122287148 0.0343290000 388081145 0 402718720 -0.0467150137 0.0233590715 0.1709863991 564 1305031120.9475090504 0.0285713691 0.0380659075 0.0861947089 0.0122187914 0.0377420000 388101285 0 402718720 -0.0448378101 0.0129689174 0.1747507453 565 1305031120.9833900928 0.0253343321 0.0380433737 0.0861947089 0.0122119901 0.0336890000 388076589 0 402718720 -0.0480544530 0.0048949975 0.1776335090 566 1305031121.0150289536 0.0245089196 0.0380194613 0.0861947089 0.0122071196 0.0338040000 388056593 0 402718720 -0.0487626418 -0.0038854908 0.1802723557 567 1305031121.0477550030 0.0191555955 0.0379861917 0.0861947089 0.0121972993 0.0366310000 388108385 0 402718720 -0.0508077405 -0.0081088506 0.1809330732 568 1305031121.0831170082 0.0204995405 0.0379554053 0.0861947089 0.0121906901 0.0358540000 388031096 0 402718720 -0.0514756292 -0.0215375014 0.1833838969 569 1305031121.1148779392 0.0207762942 0.0379252135 0.0861947089 0.0121825482 0.0352810000 388061937 0 402718720 -0.0495959669 -0.0268226266 0.1846175939 570 1305031121.1473550797 0.0203908738 0.0378944515 0.0861947089 0.0121773601 0.0327820000 388059541 0 402718720 -0.0504231378 -0.0358238518 0.1838101298 571 1305031121.1832809448 0.0208222698 0.0378645528 0.0861947089 0.0121672194 0.0329390000 388041864 0 402718720 -0.0504511818 -0.0452145338 0.1872629970 572 1305031121.2114310265 0.0239031315 0.0378401447 0.0861947089 0.0121600260 0.0410440000 388044280 0 402718720 -0.0465328284 -0.0529349893 0.1923014671 573 1305031121.2472009659 0.0220092107 0.0378125166 0.0861947089 0.0121563523 0.0423290000 388072685 0 402718720 -0.0528377071 -0.0597414449 0.1882177442 574 1305031121.2828760147 0.0241918638 0.0377887872 0.0861947089 0.0121496217 0.0332010000 388051016 0 402718720 -0.0505938083 -0.0714978129 0.1922671795 575 1305031121.3135879040 0.0252983570 0.0377670647 0.0861947089 0.0121410299 0.0328600000 388054128 0 402718720 -0.0494821444 -0.0806468129 0.1962854713 576 1305031121.3475399017 0.0312984623 0.0377558345 0.0861947089 0.0121360257 0.0484740000 388577620 0 402718720 -0.0518262871 -0.0878713951 0.1915210038 577 1305031121.3832480907 0.0322496295 0.0377462917 0.0861947089 0.0121363257 0.1078830000 388675716 0 402718720 -0.0486788116 -0.0976352394 0.1969273984 578 1305031121.4143280983 0.0332099497 0.0377384433 0.0861947089 0.0121261855 0.1112010000 388677348 0 402718720 -0.0495224446 -0.1052051857 0.1995663941 579 1305031121.4473190308 0.0341981873 0.0377323289 0.0861947089 0.0121189283 0.1073860000 388983612 0 402718720 -0.0493830219 -0.1112178788 0.2040268183 580 1305031121.4830150604 0.0333161987 0.0377247149 0.0861947089 0.0121168462 0.0968170000 393675448 0 402718720 -0.0477825254 -0.1215516403 0.2103321403 581 1305031121.5141639709 0.0377991237 0.0377248430 0.0861947089 0.0121132498 0.0888530000 400492664 0 402718720 -0.0521166101 -0.1279815882 0.2066402882 582 1305031121.5472700596 0.0420832261 0.0377323316 0.0861947089 0.0121053366 0.0382680000 403765769 0 402718720 -0.0521668978 -0.1320506781 0.2085106373 583 1305031121.5832130909 0.0404219292 0.0377369450 0.0861947089 0.0120967935 0.0919030000 402055415 0 402718720 -0.0513064861 -0.1445536315 0.2140545100 584 1305031121.6147189140 0.0411328897 0.0377427599 0.0861947089 0.0120876003 0.0375200000 401933684 0 402718720 -0.0502151027 -0.1506319195 0.2176777124 585 1305031121.6471829414 0.0436813682 0.0377529114 0.0861947089 0.0120834745 0.1201820000 401872089 0 402718720 -0.0488739759 -0.1542679220 0.2217649817 586 1305031121.6832110882 0.0449967496 0.0377652729 0.0861947089 0.0120759932 0.0972140000 388706861 0 402718720 -0.0523820966 -0.1632754505 0.2221292108 587 1305031121.7145280838 0.0456485003 0.0377787026 0.0861947089 0.0120668518 0.0365400000 389228012 0 402718720 -0.0561592281 -0.1725150496 0.2232844085 588 1305031121.7471449375 0.0485684685 0.0377970525 0.0861947089 0.0120568296 0.1129290000 389352597 0 402718720 -0.0560228899 -0.1760417074 0.2260765433 589 1305031121.7828710079 0.0491393842 0.0378163095 0.0861947089 0.0120469883 0.1142610000 389377193 0 402718720 -0.0551415309 -0.1834357828 0.2287991345 590 1305031121.8115448952 0.0482628644 0.0378340155 0.0861947089 0.0120410953 0.1081540000 389379597 0 402718720 -0.0543518141 -0.1861799955 0.2332736105 591 1305031121.8473351002 0.0507205725 0.0378558202 0.0861947089 0.0120334778 0.1032560000 393233636 0 402718720 -0.0549798086 -0.1898191124 0.2338866293 592 1305031121.8821229935 0.0498865470 0.0378761423 0.0861947089 0.0120251032 0.0967340000 400868152 0 402718720 -0.0550307371 -0.1934698820 0.2361632288 593 1305031121.9149429798 0.0515175313 0.0378991464 0.0861947089 0.0120150681 0.0379020000 404886537 0 402718720 -0.0562517494 -0.1940151006 0.2350474596 594 1305031121.9473180771 0.0493623801 0.0379184447 0.0861947089 0.0120055011 0.0981060000 403215797 0 402718720 -0.0543182269 -0.1937672347 0.2373746336 595 1305031121.9829349518 0.0496292338 0.0379381267 0.0861947089 0.0119959780 0.0397250000 403126549 0 402718720 -0.0529173240 -0.1892160475 0.2366781086 596 1305031122.0144240856 0.0472499952 0.0379537507 0.0861947089 0.0119869468 0.1337140000 403069985 0 402718720 -0.0531734228 -0.1866419613 0.2369172722 597 1305031122.0473060608 0.0456888229 0.0379667073 0.0861947089 0.0119776236 0.0932710000 389358220 0 402718720 -0.0531944856 -0.1820036918 0.2345481068 598 1305031122.0829689503 0.0442109667 0.0379771492 0.0861947089 0.0119678558 0.0340320000 389395753 0 402718720 -0.0515326634 -0.1762527823 0.2326444387 599 1305031122.1146879196 0.0452896729 0.0379893570 0.0861947089 0.0119608373 0.0332330000 389364824 0 402718720 -0.0538218096 -0.1664737314 0.2268693149 600 1305031122.1507480145 0.0400069766 0.0379927197 0.0861947089 0.0119546241 0.0331980000 389368224 0 402718720 -0.0544162542 -0.1580445319 0.2251197249 601 1305031122.1830520630 0.0391326360 0.0379946164 0.0861947089 0.0119529808 0.0332880000 389371200 0 402718720 -0.0535868183 -0.1474550962 0.2214952111 602 1305031122.2149689198 0.0433681943 0.0380035426 0.0861947089 0.0119662905 0.0373640000 389892916 0 402718720 -0.0571941808 -0.1272087693 0.2123471051 603 1305031122.2513549328 0.0340378806 0.0379969661 0.0861947089 0.0119584813 0.1309020000 389993244 0 402718720 -0.0564772300 -0.1248664111 0.2124412656 604 1305031122.2838659286 0.0323143713 0.0379875578 0.0861947089 0.0119527280 0.1209680000 389995456 0 402718720 -0.0580434389 -0.1122805923 0.2080580145 605 1305031122.3143088818 0.0340798199 0.0379810988 0.0861947089 0.0119576122 0.1134550000 389998484 0 402718720 -0.0630661026 -0.0929173082 0.2003749609 606 1305031122.3513510227 0.0264867786 0.0379621312 0.0861947089 0.0119494503 0.1066160000 390276287 0 402718720 -0.0596814677 -0.0885008425 0.1993701458 607 1305031122.3826780319 0.0250498578 0.0379408590 0.0861947089 0.0119460710 0.1070060000 401003624 0 402718720 -0.0643484592 -0.0774712190 0.1924435794 608 1305031122.4150080681 0.0224668123 0.0379154082 0.0861947089 0.0119422484 0.0413590000 406246421 0 402718720 -0.0639797151 -0.0728789866 0.1882698536 609 1305031122.4512720108 0.0207402147 0.0378872059 0.0861947089 0.0119382904 0.0976160000 404669519 0 402718720 -0.0637510270 -0.0633227229 0.1817497909 610 1305031122.4833879471 0.0191955492 0.0378565639 0.0861947089 0.0119328417 0.1451400000 404274813 0 402718720 -0.0610795692 -0.0531166717 0.1802328229 611 1305031122.5151350498 0.0192274787 0.0378260744 0.0861947089 0.0119250336 0.1016970000 390029009 0 402718720 -0.0597890690 -0.0432910472 0.1772147566 612 1305031122.5515100956 0.0212029759 0.0377989124 0.0861947089 0.0119197387 0.0361530000 390005401 0 402718720 -0.0580024719 -0.0335837156 0.1719824523 613 1305031122.5832169056 0.0193749666 0.0377688571 0.0861947089 0.0119121634 0.0363700000 390026349 0 402718720 -0.0602793917 -0.0237264652 0.1672886908 614 1305031122.6150169373 0.0175941158 0.0377359992 0.0861947089 0.0119059035 0.0520440000 390071233 0 402718720 -0.0634304807 -0.0177617352 0.1641101539 615 1305031122.6488099098 0.0228518285 0.0377117973 0.0861947089 0.0118963301 0.0358580000 390057917 0 402718720 -0.0603401810 -0.0086942352 0.1591667682 616 1305031122.6834199429 0.0221082997 0.0376864669 0.0861947089 0.0118872360 0.0456710000 390008673 0 402718720 -0.0616001002 0.0006708810 0.1526666135 617 1305031122.7152190208 0.0227271747 0.0376622217 0.0861947089 0.0118800211 0.0455430000 389992080 0 402718720 -0.0628655329 0.0094610304 0.1489968300 618 1305031122.7513089180 0.0273138918 0.0376454768 0.0861947089 0.0118825689 0.0345270000 389995368 0 402718720 -0.0608085766 0.0247265100 0.1472892612 619 1305031122.7834379673 0.0303218160 0.0376336454 0.0861947089 0.0118739220 0.0371550000 389998472 0 402718720 -0.0582095571 0.0358936265 0.1428660601 620 1305031122.8125650883 0.0331195854 0.0376263647 0.0861947089 0.0118654341 0.0368830000 390001336 0 402718720 -0.0589487962 0.0415585302 0.1419128478 621 1305031122.8514859676 0.0374490581 0.0376260791 0.0861947089 0.0118672288 0.0370520000 390005208 0 402718720 -0.0564441681 0.0529529527 0.1398603171 622 1305031122.8837749958 0.0390007868 0.0376282893 0.0861947089 0.0118621455 0.0366510000 390007908 0 402718720 -0.0558493845 0.0623760670 0.1371904165 623 1305031122.9145851135 0.0389787219 0.0376304569 0.0861947089 0.0118599242 0.0431810000 390011208 0 402718720 -0.0614747927 0.0623081289 0.1362711787 624 1305031122.9514129162 0.0424810238 0.0376382303 0.0861947089 0.0118509972 0.0350530000 390053669 0 402718720 -0.0621724650 0.0688888729 0.1344601959 625 1305031122.9830000401 0.0400722921 0.0376421248 0.0861947089 0.0118438225 0.0438540000 390017524 0 402718720 -0.0649760887 0.0780486614 0.1302001476 626 1305031123.0154619217 0.0453553572 0.0376544462 0.0861947089 0.0118349972 0.0343000000 390073565 0 402718720 -0.0642271489 0.0819386691 0.1306212246 627 1305031123.0518379211 0.0496840999 0.0376736323 0.0861947089 0.0118274215 0.0369560000 390100085 0 402718720 -0.0620615035 0.0881652087 0.1274370402 628 1305031123.0829920769 0.0474826396 0.0376892517 0.0861947089 0.0118241965 0.0339260000 390027764 0 402718720 -0.0637884513 0.1016136855 0.1242208779 629 1305031123.1139390469 0.0503023416 0.0377093043 0.0861947089 0.0118169145 0.0335870000 390030588 0 402718720 -0.0619935244 0.1082621515 0.1222769544 630 1305031123.1508400440 0.0558217876 0.0377380543 0.0861947089 0.0118078672 0.0362800000 390034000 0 402718720 -0.0619776025 0.1132048741 0.1219718009 631 1305031123.1821761131 0.0567803010 0.0377682322 0.0861947089 0.0118150806 0.0367200000 390037416 0 402718720 -0.0600648373 0.1256976873 0.1199580133 632 1305031123.2147240639 0.0584535636 0.0378009621 0.0861947089 0.0118070571 0.0405820000 390695496 0 402718720 -0.0602391288 0.1340875179 0.1190134063 633 1305031123.2506411076 0.0588759370 0.0378342559 0.0861947089 0.0118247217 0.1269920000 390669212 0 402718720 -0.0608445033 0.1473369151 0.1165945083 634 1305031123.2823629379 0.0643610507 0.0378760963 0.0861947089 0.0118212677 0.1227330000 390671496 0 402718720 -0.0607006736 0.1541294307 0.1197536290 635 1305031123.3209919930 0.0701826364 0.0379269727 0.0861947089 0.0118185510 0.1163400000 390674980 0 402718720 -0.0603849515 0.1607836187 0.1211828068 636 1305031123.3504929543 0.0730691776 0.0379822278 0.0861947089 0.0118124069 0.1052500000 391030676 0 402718720 -0.0598433577 0.1661135703 0.1206844822 637 1305031123.3822629452 0.0744070038 0.0380394095 0.0861947089 0.0118055713 0.0992650000 400290580 0 402718720 -0.0599083118 0.1754862517 0.1201676801 638 1305031123.4213430882 0.0803812444 0.0381057760 0.0861947089 0.0117979184 0.0540630000 406255889 0 402718720 -0.0610447228 0.1771840006 0.1194470525 639 1305031123.4512660503 0.0796048194 0.0381707198 0.0861947089 0.0118081371 0.0696940000 405070613 0 402718720 -0.0650746450 0.1871121824 0.1187501177 640 1305031123.4836049080 0.0826525763 0.0382402227 0.0861947089 0.0118033502 0.0373660000 406592629 0 402718720 -0.0639904216 0.1934329271 0.1185725108 641 1305031123.5197250843 0.0872729495 0.0383167168 0.0872729495 0.0117958082 0.1288910000 404755091 0 402718720 -0.0623170435 0.1967982352 0.1164938509 642 1305031123.5515730381 0.0878419504 0.0383938589 0.0878419504 0.0117894656 0.1013760000 390629324 0 402718720 -0.0636881739 0.2050894648 0.1162545606 643 1305031123.5796160698 0.0920848027 0.0384773596 0.0920848027 0.0117842063 0.0364280000 391276624 0 402718720 -0.0609910153 0.2089357376 0.1163916290 644 1305031123.6203870773 0.0954556316 0.0385658352 0.0954556316 0.0117784709 0.1189710000 391370032 0 402718720 -0.0599356592 0.2133313268 0.1146850735 645 1305031123.6524300575 0.0959707201 0.0386548350 0.0959707201 0.0117701612 0.1109690000 391372928 0 402718720 -0.0590345487 0.2215563953 0.1145046204 646 1305031123.6837849617 0.0982945934 0.0387471566 0.0982945934 0.0117621898 0.1047860000 391375704 0 402718720 -0.0586302355 0.2254661024 0.1143082529 647 1305031123.7199749947 0.0996941999 0.0388413560 0.0996941999 0.0117570038 0.1027070000 395405508 0 402718720 -0.0572076738 0.2343786061 0.1143653244 648 1305031123.7519800663 0.1009771451 0.0389372446 0.1009771451 0.0117487991 0.0894150000 403369276 0 402718720 -0.0556820855 0.2389576137 0.1144885570 649 1305031123.7841379642 0.1000047848 0.0390313394 0.1009771451 0.0117420944 0.0389450000 407897909 0 402718720 -0.0557512827 0.2430198342 0.1132715344 650 1305031123.8196959496 0.1002736017 0.0391255583 0.1009771451 0.0117337362 0.0917220000 406263981 0 402718720 -0.0565605648 0.2444102615 0.1126318276 651 1305031123.8515510559 0.1005556434 0.0392199209 0.1009771451 0.0117251730 0.0359470000 407947813 0 402718720 -0.0551028289 0.2460163236 0.1130502746 652 1305031123.8838191032 0.0956113338 0.0393064108 0.1009771451 0.0117173524 0.1324500000 405997535 0 402718720 -0.0556753874 0.2539927959 0.1114887446 653 1305031123.9157938957 0.0940830186 0.0393902954 0.1009771451 0.0117103633 0.0980470000 391331284 0 402718720 -0.0563419163 0.2515358329 0.1111669242 654 1305031123.9515299797 0.0963897854 0.0394774506 0.1009771451 0.0117040697 0.0317800000 391357512 0 402718720 -0.0534290746 0.2439656705 0.1125280112 655 1305031123.9834210873 0.0910460129 0.0395561812 0.1009771451 0.0116955550 0.0419440000 391361200 0 402718720 -0.0524653532 0.2501219511 0.1117700264 656 1305031124.0197370052 0.0887338892 0.0396311472 0.1009771451 0.0117014799 0.0313470000 391364480 0 402718720 -0.0513767153 0.2474511266 0.1137694493 657 1305031124.0515310764 0.0896224082 0.0397072374 0.1009771451 0.0116946200 0.0319310000 391367620 0 402718720 -0.0554064810 0.2326263636 0.1158682853 658 1305031124.0839018822 0.0861747861 0.0397778568 0.1009771451 0.0116887595 0.0328830000 391371048 0 402718720 -0.0519859716 0.2363839000 0.1178247631 659 1305031124.1196689606 0.0805944279 0.0398397939 0.1009771451 0.0116874375 0.0322840000 391374064 0 402718720 -0.0531139560 0.2333294153 0.1193033308 660 1305031124.1474580765 0.0826769546 0.0399046987 0.1009771451 0.0116798984 0.0337430000 391377528 0 402718720 -0.0552246720 0.2153163254 0.1225782111 661 1305031124.1827070713 0.0806683004 0.0399663683 0.1009771451 0.0116793245 0.0360590000 391380752 0 402718720 -0.0557717457 0.2076561004 0.1246774644 662 1305031124.2171790600 0.0744833276 0.0400185087 0.1009771451 0.0116724827 0.0506540000 391912508 0 402718720 -0.0545612201 0.2058969736 0.1261654198 663 1305031124.2493400574 0.0761362314 0.0400729849 0.1009771451 0.0116684184 0.1291410000 392009968 0 402718720 -0.0521309301 0.1910204589 0.1284353286 664 1305031124.2825551033 0.0755784661 0.0401264570 0.1009771451 0.0116690106 0.1203960000 392012476 0 402718720 -0.0524909683 0.1807425767 0.1309444308 665 1305031124.3167819977 0.0777799264 0.0401830788 0.1009771451 0.0116901848 0.1165630000 392014128 0 402718720 -0.0496323407 0.1639799476 0.1344542950 666 1305031124.3503708839 0.0756671950 0.0402363583 0.1009771451 0.0116849189 0.1138360000 397407776 0 402718720 -0.0485806279 0.1565884352 0.1355627179 667 1305031124.3824319839 0.0749761686 0.0402884419 0.1009771451 0.0116800456 0.1060730000 405905392 0 402718720 -0.0471066423 0.1471065581 0.1374182403 668 1305031124.4185550213 0.0721253753 0.0403361020 0.1009771451 0.0116802318 0.0414020000 408507789 0 402718720 -0.0462097079 0.1360549480 0.1390106529 669 1305031124.4502561092 0.0680392683 0.0403775118 0.1009771451 0.0116721336 0.1055200000 407063971 0 402718720 -0.0452794954 0.1300566941 0.1396316290 670 1305031124.4801259041 0.0650851130 0.0404143888 0.1009771451 0.0116639814 0.0408300000 406727112 0 402718720 -0.0454974808 0.1203454658 0.1398170888 671 1305031124.5167369843 0.0595861785 0.0404429608 0.1009771451 0.0116555214 0.1416930000 406659567 0 402718720 -0.0457955860 0.1132311523 0.1419391036 672 1305031124.5505030155 0.0553641729 0.0404651650 0.1009771451 0.0116475647 0.0934720000 392030648 0 402718720 -0.0451472327 0.1063054949 0.1423918158 673 1305031124.5846059322 0.0534811579 0.0404845052 0.1009771451 0.0116393307 0.0359080000 392033608 0 402718720 -0.0471202955 0.0946533382 0.1449487805 674 1305031124.6176528931 0.0493072048 0.0404975953 0.1009771451 0.0116462729 0.0356090000 392037028 0 402718720 -0.0458711386 0.0838581771 0.1478658170 675 1305031124.6513130665 0.0448258445 0.0405040075 0.1009771451 0.0116414435 0.0359960000 392040224 0 402718720 -0.0467478409 0.0753424615 0.1491858512 676 1305031124.6854729652 0.0459755585 0.0405121015 0.1009771451 0.0116384169 0.0480160000 392043232 0 402718720 -0.0426827744 0.0643822551 0.1532917023 677 1305031124.7157909870 0.0392908156 0.0405102976 0.1009771451 0.0116299011 0.0357150000 392046708 0 402718720 -0.0439824015 0.0572884902 0.1570739150 678 1305031124.7499411106 0.0375458561 0.0405059252 0.1009771451 0.0116219531 0.0350330000 392050208 0 402718720 -0.0447144285 0.0447357260 0.1609156132 679 1305031124.7851779461 0.0334176645 0.0404954860 0.1009771451 0.0116144872 0.0381870000 392053124 0 402718720 -0.0450996384 0.0355929211 0.1623526216 680 1305031124.8166410923 0.0287248194 0.0404781762 0.1009771451 0.0116065512 0.0354060000 392056672 0 402718720 -0.0449648760 0.0253628939 0.1661193520 681 1305031124.8505589962 0.0287999585 0.0404610275 0.1009771451 0.0115988129 0.0376510000 392060032 0 402718720 -0.0441446118 0.0148228733 0.1729666293 682 1305031124.8835940361 0.0314007998 0.0404477427 0.1009771451 0.0115956131 0.0346720000 392063076 0 402718720 -0.0410453081 0.0033302568 0.1808554232 683 1305031124.9187700748 0.0233659931 0.0404227329 0.1009771451 0.0115994965 0.0383200000 392110633 0 402718720 -0.0437329859 -0.0012493841 0.1829291135 684 1305031124.9507479668 0.0241513569 0.0403989443 0.1009771451 0.0116031866 0.0390670000 392107421 0 402718720 -0.0430344008 -0.0135814380 0.1901171058 685 1305031124.9864599705 0.0252334327 0.0403768049 0.1009771451 0.0116227152 0.0736020000 392072820 0 402718720 -0.0437352583 -0.0316319391 0.1963234693 686 1305031125.0194671154 0.0245509073 0.0403537350 0.1009771451 0.0116178710 0.0366060000 392076164 0 402718720 -0.0445212200 -0.0390215777 0.1963956654 687 1305031125.0507979393 0.0228943340 0.0403283211 0.1009771451 0.0116168067 0.0441330000 392142873 0 402718720 -0.0435383953 -0.0419309586 0.2030138969 688 1305031125.0834798813 0.0248225071 0.0403057836 0.1009771451 0.0116105152 0.0368650000 392082648 0 402718720 -0.0428246334 -0.0525674708 0.2067126185 689 1305031125.1190290451 0.0270947553 0.0402866093 0.1009771451 0.0116133237 0.0354410000 392085496 0 402718720 -0.0432086885 -0.0646417737 0.2098420709 690 1305031125.1510369778 0.0276161153 0.0402682463 0.1009771451 0.0116099735 0.0357950000 392088576 0 402718720 -0.0421880148 -0.0717262775 0.2160014957 691 1305031125.1870639324 0.0276035070 0.0402499182 0.1009771451 0.0116088549 0.0336410000 392150329 0 402718720 -0.0450250581 -0.0723946914 0.2173059285 692 1305031125.2190179825 0.0265292861 0.0402300907 0.1009771451 0.0116075004 0.0329880000 392095676 0 402718720 -0.0465998277 -0.0838017538 0.2230568081 693 1305031125.2506420612 0.0286961943 0.0402134472 0.1009771451 0.0116005306 0.0467340000 392098908 0 402718720 -0.0469822958 -0.0968061760 0.2263521552 694 1305031125.2863960266 0.0299133919 0.0401986057 0.1009771451 0.0115937872 0.0347120000 392142657 0 402718720 -0.0495843813 -0.1002211720 0.2266050875 695 1305031125.3191399574 0.0315993279 0.0401862326 0.1009771451 0.0115910491 0.0438630000 392105256 0 402718720 -0.0488652289 -0.1100900099 0.2305094153 696 1305031125.3488988876 0.0325730070 0.0401752941 0.1009771451 0.0115866294 0.0337390000 392129685 0 402718720 -0.0527351350 -0.1145744622 0.2306548059 697 1305031125.3867919445 0.0348412730 0.0401676412 0.1009771451 0.0115897932 0.0318790000 392111840 0 402718720 -0.0496934056 -0.1167917326 0.2359913737 698 1305031125.4195740223 0.0370848477 0.0401632246 0.1009771451 0.0115819228 0.0316170000 392115236 0 402718720 -0.0486201495 -0.1234584451 0.2387590259 699 1305031125.4512319565 0.0366067924 0.0401581367 0.1009771451 0.0115772974 0.0338200000 392118248 0 402718720 -0.0517640486 -0.1309706569 0.2402278781 700 1305031125.4869990349 0.0362433568 0.0401525442 0.1009771451 0.0115732791 0.0342190000 392121832 0 402718720 -0.0516568273 -0.1387573779 0.2444333881 701 1305031125.5193541050 0.0382813960 0.0401498749 0.1009771451 0.0115696591 0.0433520000 392163005 0 402718720 -0.0532462075 -0.1398858428 0.2432965040 702 1305031125.5510499477 0.0366259106 0.0401448551 0.1009771451 0.0115650822 0.0317850000 392165693 0 402718720 -0.0542161167 -0.1407398880 0.2454282343 703 1305031125.5853030682 0.0355376415 0.0401383014 0.1009771451 0.0115570421 0.0426200000 392165809 0 402718720 -0.0530351549 -0.1436919421 0.2472826093 704 1305031125.6178700924 0.0331826955 0.0401284213 0.1009771451 0.0115631360 0.0335730000 392134612 0 402718720 -0.0551245026 -0.1489454806 0.2476670295 705 1305031125.6505749226 0.0363127403 0.0401230090 0.1009771451 0.0115577572 0.0307020000 392138024 0 402718720 -0.0586636178 -0.1535507441 0.2416835278 706 1305031125.6846020222 0.0373455398 0.0401190749 0.1009771451 0.0115543549 0.0328460000 392140992 0 402718720 -0.0624170974 -0.1448971778 0.2351444662 707 1305031125.7156689167 0.0351994857 0.0401121165 0.1009771451 0.0115903589 0.0307950000 392144220 0 402718720 -0.0576042272 -0.1452920735 0.2351333350 708 1305031125.7512919903 0.0360543802 0.0401063852 0.1009771451 0.0115934333 0.0317350000 392175901 0 402718720 -0.0568123087 -0.1321261972 0.2291227430 709 1305031125.7868049145 0.0337721519 0.0400974512 0.1009771451 0.0115858118 0.0326240000 392189737 0 402718720 -0.0565797761 -0.1255757064 0.2258673161 710 1305031125.8194499016 0.0324088149 0.0400866221 0.1009771451 0.0115870442 0.0320640000 392153904 0 402718720 -0.0552776158 -0.1148246378 0.2231290191 711 1305031125.8547739983 0.0311531015 0.0400740574 0.1009771451 0.0115832374 0.0325290000 392157452 0 402718720 -0.0541471355 -0.1096667051 0.2203402668 712 1305031125.8866450787 0.0293205921 0.0400589542 0.1009771451 0.0115868969 0.0343040000 392160796 0 402718720 -0.0565808527 -0.1035798341 0.2143821120 713 1305031125.9193339348 0.0300496612 0.0400449159 0.1009771451 0.0115893527 0.0341910000 392163988 0 402718720 -0.0603193045 -0.0923762172 0.2073104680 714 1305031125.9552519321 0.0264950842 0.0400259386 0.1009771451 0.0115891272 0.0341850000 392167408 0 402718720 -0.0607859641 -0.0895284042 0.2062586099 715 1305031125.9870939255 0.0259380788 0.0400062353 0.1009771451 0.0115874354 0.0339880000 392170404 0 402718720 -0.0574571714 -0.0778094828 0.2016556859 716 1305031126.0195720196 0.0242497399 0.0399842290 0.1009771451 0.0115828244 0.0344040000 392173488 0 402718720 -0.0527830832 -0.0646887422 0.2016406506 717 1305031126.0550379753 0.0250573400 0.0399634105 0.1009771451 0.0115794888 0.0332720000 392177016 0 402718720 -0.0486329272 -0.0506975166 0.1992864013 718 1305031126.0870759487 0.0242572445 0.0399415356 0.1009771451 0.0115729179 0.0417740000 392180044 0 402718720 -0.0480687618 -0.0412594937 0.1966223121 719 1305031126.1194519997 0.0214261934 0.0399157840 0.1009771451 0.0115672651 0.0360810000 392183664 0 402718720 -0.0478443727 -0.0319070630 0.1993254274 720 1305031126.1549999714 0.0202094298 0.0398884141 0.1009771451 0.0115708103 0.0479740000 392187016 0 402718720 -0.0470623635 -0.0154428547 0.1973578930 721 1305031126.1871740818 0.0184586309 0.0398586918 0.1009771451 0.0115675011 0.0373020000 392189824 0 402718720 -0.0492485911 -0.0028421301 0.1941239387 722 1305031126.2194728851 0.0225023329 0.0398346525 0.1009771451 0.0115658363 0.0346930000 392193352 0 402718720 -0.0469958782 0.0050767418 0.1955578476 723 1305031126.2552359104 0.0230004787 0.0398113687 0.1009771451 0.0115795751 0.0371650000 392196308 0 402718720 -0.0458579212 0.0208781846 0.1939261556 724 1305031126.2871050835 0.0276812557 0.0397946144 0.1009771451 0.0115744860 0.0369670000 392199924 0 402718720 -0.0448805913 0.0311211236 0.1925032139 725 1305031126.3197870255 0.0325395502 0.0397846075 0.1009771451 0.0115721462 0.0364330000 392203192 0 402718720 -0.0409717113 0.0428794399 0.1908067614 726 1305031126.3554151058 0.0327637121 0.0397749368 0.1009771451 0.0115691079 0.0474800000 392206060 0 402718720 -0.0445262603 0.0504376739 0.1887338609 727 1305031126.3874828815 0.0364171341 0.0397703181 0.1009771451 0.0115666385 0.0361730000 392209588 0 402718720 -0.0464435555 0.0582259446 0.1861533374 728 1305031126.4197928905 0.0381465331 0.0397680876 0.1009771451 0.0115611949 0.0503630000 392212376 0 402718720 -0.0472839959 0.0667567253 0.1838281751 729 1305031126.4553799629 0.0425811335 0.0397719464 0.1009771451 0.0115639975 0.0377600000 392215796 0 402718720 -0.0480291545 0.0719867274 0.1829310954 730 1305031126.4903860092 0.0460935086 0.0397806061 0.1009771451 0.0115723869 0.0365050000 392219364 0 402718720 -0.0501496643 0.0803316534 0.1794816405 731 1305031126.5223209858 0.0441247039 0.0397865487 0.1009771451 0.0115741540 0.0371600000 392222024 0 402718720 -0.0488408431 0.0944408774 0.1751959026 732 1305031126.5582089424 0.0522695482 0.0398036020 0.1009771451 0.0115726675 0.0374380000 392225548 0 402718720 -0.0458877534 0.1006243080 0.1759277582 733 1305031126.5901761055 0.0538294464 0.0398227369 0.1009771451 0.0115666296 0.0357590000 392228836 0 402718720 -0.0455842093 0.1080494672 0.1745269895 734 1305031126.6186869144 0.0546686500 0.0398429629 0.1009771451 0.0115590945 0.0448260000 392231644 0 402718720 -0.0459116064 0.1150824279 0.1727620512 735 1305031126.6544740200 0.0614283867 0.0398723308 0.1009771451 0.0115698218 0.0482680000 392235472 0 402718720 -0.0423226282 0.1153207645 0.1731332392 736 1305031126.6900219917 0.0632355064 0.0399040743 0.1009771451 0.0115665704 0.0460940000 392238780 0 402718720 -0.0431704074 0.1211609542 0.1710120589 737 1305031126.7157700062 0.0635371581 0.0399361409 0.1009771451 0.0115603782 0.0369160000 392241292 0 402718720 -0.0435747094 0.1265714318 0.1691363156 738 1305031126.7553739548 0.0699756891 0.0399768449 0.1009771451 0.0115577468 0.0350970000 392290781 0 402718720 -0.0412261672 0.1222808734 0.1675841063 739 1305031126.7875649929 0.0676998571 0.0400143591 0.1009771451 0.0115559678 0.0360190000 392271553 0 402718720 -0.0408562198 0.1309649795 0.1642110944 740 1305031126.8199288845 0.0671130791 0.0400509790 0.1009771451 0.0115495532 0.0347750000 392251552 0 402718720 -0.0398389995 0.1359876394 0.1619231850 741 1305031126.8583779335 0.0703535229 0.0400918731 0.1009771451 0.0115433928 0.0354590000 392254620 0 402718720 -0.0375447758 0.1354607344 0.1597888172 742 1305031126.8881540298 0.0710661858 0.0401336175 0.1009771451 0.0115357013 0.0347570000 392291509 0 402718720 -0.0383717418 0.1355982125 0.1581044197 743 1305031126.9194090366 0.0709342882 0.0401750719 0.1009771451 0.0115280581 0.0350820000 392304109 0 402718720 -0.0369300693 0.1380664110 0.1572840810 744 1305031126.9555010796 0.0711537525 0.0402167100 0.1009771451 0.0115213307 0.0528500000 392318041 0 402718720 -0.0362424627 0.1378667504 0.1555565596 745 1305031126.9873158932 0.0720617473 0.0402594550 0.1009771451 0.0115139669 0.0487080000 392326321 0 402718720 -0.0353350639 0.1382824928 0.1555550098 746 1305031127.0195240974 0.0729746819 0.0403033092 0.1009771451 0.0115068173 0.0361410000 392321205 0 402718720 -0.0356627405 0.1368931830 0.1556398869 747 1305031127.0533180237 0.0727621540 0.0403467614 0.1009771451 0.0115021317 0.0353970000 392338689 0 402718720 -0.0341683999 0.1362628490 0.1545481682 748 1305031127.0886490345 0.0713107809 0.0403881572 0.1009771451 0.0114998821 0.0344630000 392326457 0 402718720 -0.0351865962 0.1365466118 0.1551095545 749 1305031127.1209630966 0.0717722848 0.0404300585 0.1009771451 0.0114965160 0.0347780000 392280960 0 402718720 -0.0342256725 0.1356661618 0.1561531723 750 1305031127.1576919556 0.0700500906 0.0404695519 0.1009771451 0.0114898538 0.0448280000 392284124 0 402718720 -0.0359472707 0.1345942318 0.1562764347 751 1305031127.1875000000 0.0694852993 0.0405081881 0.1009771451 0.0114858890 0.0353690000 392326893 0 402718720 -0.0337483212 0.1334015429 0.1559688896 752 1305031127.2218310833 0.0683779046 0.0405452489 0.1009771451 0.0114806077 0.0470050000 392328105 0 402718720 -0.0340764932 0.1323729306 0.1563863307 753 1305031127.2597610950 0.0689337850 0.0405829494 0.1009771451 0.0114775997 0.0350540000 392293620 0 402718720 -0.0338788778 0.1287149340 0.1589870751 754 1305031127.2870380878 0.0664485097 0.0406172539 0.1009771451 0.0114796518 0.0354310000 392356381 0 402718720 -0.0345203765 0.1279736906 0.1586908996 755 1305031127.3204679489 0.0663059205 0.0406512786 0.1009771451 0.0114740335 0.0364640000 392347433 0 402718720 -0.0352592766 0.1254151762 0.1606293917 756 1305031127.3534069061 0.0674890876 0.0406867784 0.1009771451 0.0114683035 0.0356590000 392303464 0 402718720 -0.0351216644 0.1212885529 0.1628913879 757 1305031127.3837130070 0.0647533759 0.0407185704 0.1009771451 0.0114625555 0.0358800000 392370481 0 402718720 -0.0356341191 0.1209234744 0.1628654599 758 1305031127.4196500778 0.0617560074 0.0407463243 0.1009771451 0.0114571672 0.0372910000 392386901 0 402718720 -0.0373562612 0.1206985563 0.1637468040 759 1305031127.4542460442 0.0647270754 0.0407779195 0.1009771451 0.0114603049 0.0362680000 392336557 0 402718720 -0.0363062359 0.1171762049 0.1680573225 760 1305031127.4872000217 0.0613778494 0.0408050247 0.1009771451 0.0114691724 0.0478980000 392397045 0 402718720 -0.0368498564 0.1182916984 0.1677912176 761 1305031127.5218999386 0.0610071234 0.0408315715 0.1009771451 0.0114639110 0.0366620000 392396001 0 402718720 -0.0377197824 0.1170174330 0.1689592898 762 1305031127.5537250042 0.0639356598 0.0408618918 0.1009771451 0.0114651350 0.0366310000 392376609 0 402718720 -0.0370320156 0.1130600274 0.1722667664 763 1305031127.5866320133 0.0607618727 0.0408879730 0.1009771451 0.0114611171 0.0370580000 392419801 0 402718720 -0.0383916162 0.1139170527 0.1715760827 764 1305031127.6206569672 0.0598315820 0.0409127683 0.1009771451 0.0114542160 0.0364550000 392408545 0 402718720 -0.0381651372 0.1147247404 0.1726114005 765 1305031127.6546559334 0.0622342713 0.0409406396 0.1009771451 0.0114479827 0.0380340000 392407349 0 402718720 -0.0373058505 0.1120067611 0.1749047637 766 1305031127.6871099472 0.0622710660 0.0409684861 0.1009771451 0.0114412748 0.0474260000 392417665 0 402718720 -0.0370080397 0.1107879728 0.1755312681 767 1305031127.7232100964 0.0590511896 0.0409920620 0.1009771451 0.0114350426 0.0374330000 392426637 0 402718720 -0.0390213504 0.1127036065 0.1747576296 768 1305031127.7546939850 0.0623078085 0.0410198168 0.1009771451 0.0114302834 0.0476070000 392437757 0 402718720 -0.0367754400 0.1103136912 0.1772351563 769 1305031127.7876410484 0.0622206479 0.0410473862 0.1009771451 0.0114277114 0.0359400000 392416141 0 402718720 -0.0376285240 0.1077544689 0.1768170893 770 1305031127.8201279640 0.0594333075 0.0410712640 0.1009771451 0.0114220085 0.0368900000 392447205 0 402718720 -0.0387937203 0.1099421382 0.1758904457 771 1305031127.8551321030 0.0602340698 0.0410961185 0.1009771451 0.0114149072 0.0374170000 392455673 0 402718720 -0.0384049639 0.1084553003 0.1758849472 772 1305031127.8871219158 0.0604165047 0.0411211449 0.1009771451 0.0114083247 0.0369310000 392443457 0 402718720 -0.0395491123 0.1068877801 0.1762841642 773 1305031127.9225599766 0.0596758910 0.0411451485 0.1009771451 0.0114030523 0.0372960000 392457109 0 402718720 -0.0405405536 0.1073998809 0.1768144220 774 1305031127.9550879002 0.0590108670 0.0411682308 0.1009771451 0.0113975959 0.0484370000 392444341 0 402718720 -0.0405627601 0.1083926931 0.1777115017 775 1305031127.9870929718 0.0585254692 0.0411906272 0.1009771451 0.0113907760 0.0482550000 392462745 0 402718720 -0.0404166989 0.1077713296 0.1790078580 776 1305031128.0217759609 0.0590114035 0.0412135921 0.1009771451 0.0113876301 0.0453200000 392443333 0 402718720 -0.0387816653 0.1075085551 0.1810045987 777 1305031128.0557179451 0.0612601116 0.0412393920 0.1009771451 0.0113877444 0.0365150000 392460513 0 402718720 -0.0383177027 0.1035917550 0.1844950765 778 1305031128.0872058868 0.0604556836 0.0412640916 0.1009771451 0.0113810504 0.0374290000 392468609 0 402718720 -0.0396265164 0.1023493707 0.1857205480 779 1305031128.1247460842 0.0599237382 0.0412880450 0.1009771451 0.0113749974 0.0372200000 392480129 0 402718720 -0.0393513218 0.1010202467 0.1862267852 780 1305031128.1577820778 0.0589747652 0.0413107202 0.1009771451 0.0113694709 0.0368410000 392472113 0 402718720 -0.0390587524 0.1011173278 0.1875752658 781 1305031128.1872210503 0.0618022457 0.0413369578 0.1009771451 0.0113649670 0.0368420000 392438985 0 402718720 -0.0379252322 0.0971954465 0.1894741952 782 1305031128.2254419327 0.0586727709 0.0413591264 0.1009771451 0.0113635671 0.0378350000 392486865 0 402718720 -0.0380926132 0.0993087962 0.1882218122 783 1305031128.2560069561 0.0581631884 0.0413805875 0.1009771451 0.0113576824 0.0379380000 392482385 0 402718720 -0.0374978036 0.1003685147 0.1892639995 784 1305031128.2912750244 0.0611153394 0.0414057594 0.1009771451 0.0113554889 0.0456160000 392459917 0 402718720 -0.0370506719 0.0965199545 0.1907817423 785 1305031128.3241701126 0.0582413338 0.0414272059 0.1009771451 0.0113504994 0.0381590000 392495481 0 402718720 -0.0386466160 0.0980213583 0.1890994757 786 1305031128.3552060127 0.0586933419 0.0414491730 0.1009771451 0.0113436496 0.0377810000 392496389 0 402718720 -0.0382401757 0.0983384550 0.1898871213 787 1305031128.3913969994 0.0585655980 0.0414709220 0.1009771451 0.0113366727 0.0377390000 392500241 0 402718720 -0.0396333262 0.0971536636 0.1898273826 788 1305031128.4236090183 0.0581500866 0.0414920884 0.1009771451 0.0113297145 0.0365030000 392491945 0 402718720 -0.0399887972 0.0968038291 0.1892705411 789 1305031128.4554989338 0.0582798496 0.0415133657 0.1009771451 0.0113239098 0.0376210000 392507165 0 402718720 -0.0397983715 0.0968345478 0.1895688772 790 1305031128.4895229340 0.0575497523 0.0415336649 0.1009771451 0.0113174175 0.0466310000 392511129 0 402718720 -0.0411029235 0.0961821079 0.1892101020 791 1305031128.5236039162 0.0573239066 0.0415536273 0.1009771451 0.0113105404 0.0374040000 392513817 0 402718720 -0.0409018323 0.0956586823 0.1891704500 792 1305031128.5556390285 0.0591148250 0.0415758005 0.1009771451 0.0113061231 0.0456130000 392513109 0 402718720 -0.0396079421 0.0929722339 0.1895800829 793 1305031128.5914599895 0.0584310703 0.0415970556 0.1009771451 0.0112998583 0.0377610000 392493837 0 402718720 -0.0405842215 0.0919462442 0.1890556067 794 1305031128.6233680248 0.0566758737 0.0416160466 0.1009771451 0.0112939588 0.0366210000 392520997 0 402718720 -0.0417345464 0.0919396579 0.1876852363 795 1305031128.6555540562 0.0551681109 0.0416330932 0.1009771451 0.0112894552 0.0371400000 392520437 0 402718720 -0.0428577662 0.0927308723 0.1870339811 796 1305031128.6904489994 0.0576340333 0.0416531949 0.1009771451 0.0112853932 0.0372270000 392524013 0 402718720 -0.0410253406 0.0904312804 0.1876853108 797 1305031128.7229759693 0.0573864020 0.0416729354 0.1009771451 0.0112789274 0.0372650000 392534897 0 402718720 -0.0399665087 0.0918515846 0.1879290342 798 1305031128.7546460629 0.0563658699 0.0416913476 0.1009771451 0.0112732150 0.0502510000 392536053 0 402718720 -0.0403743461 0.0919046253 0.1867680252 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 10:30:35 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 -nan 0.0296830000 356908440 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0018282804 0.0018654662 0.0019026520 0.0003878802 0.0328620000 376229881 0 402718720 0.0002941540 -0.0003399363 0.0006906437 3 1311867718.7114279270 0.0022995893 0.0020101739 0.0022995893 0.0034259688 0.0313020000 376124801 0 402718720 -0.0008103176 0.0016069799 0.0001284690 4 1311867718.7410299778 0.0028647545 0.0022238191 0.0028647545 0.0048913646 0.0292370000 376133437 0 402718720 0.0000611095 -0.0001215119 0.0004879458 5 1311867718.7767970562 0.0033965905 0.0024583733 0.0033965905 0.0042983263 0.0296360000 376140297 0 402718720 -0.0009076543 -0.0014286068 0.0001984128 6 1311867718.8094089031 0.0024911417 0.0024638347 0.0033965905 0.0040347562 0.0292690000 376148021 0 402718720 -0.0014430588 0.0004905288 0.0006064190 7 1311867718.8408079147 0.0032247365 0.0025725350 0.0033965905 0.0037898370 0.0290310000 376155257 0 402718720 -0.0023509325 0.0003903954 0.0002877516 8 1311867718.8767778873 0.0036838450 0.0027114487 0.0036838450 0.0035886187 0.0290560000 376163909 0 402718720 -0.0015761122 0.0003302753 0.0004468707 9 1311867718.9088680744 0.0050314683 0.0029692287 0.0050314683 0.0036313098 0.0288170000 376172617 0 402718720 -0.0015082086 -0.0001676934 -0.0002319141 10 1311867718.9438331127 0.0042593596 0.0030982418 0.0050314683 0.0034528888 0.0396730000 376182789 0 402718720 -0.0009231159 -0.0000981005 0.0011624083 11 1311867718.9784109592 0.0047456576 0.0032480069 0.0050314683 0.0033093662 0.0284480000 376189121 0 402718720 -0.0019414964 -0.0000363241 0.0007312592 12 1311867719.0091300011 0.0053912844 0.0034266133 0.0053912844 0.0031721118 0.0310540000 376770641 0 402718720 -0.0020458640 0.0000733527 0.0003596708 13 1311867719.0441620350 0.0055650747 0.0035911103 0.0055650747 0.0031165461 0.0648440000 377471789 0 402718720 -0.0017130073 0.0006918244 0.0003417007 14 1311867719.0776190758 0.0068039666 0.0038206001 0.0068039666 0.0031188369 0.1005460000 379630805 0 402718720 -0.0004387181 0.0004295880 -0.0002101053 15 1311867719.1086950302 0.0068761758 0.0040243051 0.0068761758 0.0030809390 0.0629000000 378620617 0 402718720 -0.0016762145 -0.0008287752 -0.0001570220 16 1311867719.1437010765 0.0061388481 0.0041564641 0.0068761758 0.0030709577 0.0332170000 377462929 0 402718720 -0.0018249736 0.0001344409 0.0007871772 17 1311867719.1810290813 0.0070055746 0.0043240588 0.0070055746 0.0029801781 0.0325360000 377470141 0 402718720 -0.0003239836 0.0013161605 0.0010380585 18 1311867719.2127099037 0.0063707321 0.0044377629 0.0070055746 0.0029048390 0.0325590000 377478457 0 402718720 -0.0015389310 -0.0006625094 0.0016862719 19 1311867719.2412090302 0.0059922943 0.0045195803 0.0070055746 0.0028877622 0.0450600000 378000081 0 402718720 -0.0015582121 -0.0001142553 0.0025711239 20 1311867719.2779469490 0.0072229784 0.0046547502 0.0072229784 0.0031367537 0.0931230000 378108209 0 402718720 -0.0023929582 -0.0003896932 0.0013884119 21 1311867719.3104898930 0.0066456511 0.0047495550 0.0072229784 0.0031923057 0.0584300000 380646297 0 402718720 -0.0017765902 0.0006323139 0.0027073217 22 1311867719.3413150311 0.0073457519 0.0048675640 0.0073457519 0.0032805470 0.0468770000 379059717 0 402718720 -0.0019508116 -0.0010854074 0.0024545076 23 1311867719.3772718906 0.0072949459 0.0049731023 0.0073457519 0.0032188732 0.0322350000 378081005 0 402718720 -0.0033897539 -0.0021769723 0.0023464141 24 1311867719.4105761051 0.0081919609 0.0051072214 0.0081919609 0.0031614991 0.0336930000 378087329 0 402718720 -0.0030024578 -0.0017668083 0.0016017040 25 1311867719.4427709579 0.0079277158 0.0052200412 0.0081919609 0.0031190461 0.0428520000 378092853 0 402718720 -0.0027235621 -0.0019006216 0.0023167382 26 1311867719.4787840843 0.0078261001 0.0053202742 0.0081919609 0.0030986780 0.0359730000 378607013 0 402718720 -0.0036994659 -0.0041201063 0.0028625708 27 1311867719.5104370117 0.0081038941 0.0054233713 0.0081919609 0.0032050254 0.0976030000 379611061 0 402718720 -0.0049495273 -0.0026999302 0.0018506919 28 1311867719.5449650288 0.0089081386 0.0055478272 0.0089081386 0.0032897412 0.0519390000 381676853 0 402718720 -0.0047793128 -0.0022452730 0.0017258785 29 1311867719.5771939754 0.0082801534 0.0056420454 0.0089081386 0.0032350090 0.0483540000 380090817 0 402718720 -0.0054166252 -0.0032087921 0.0027789422 30 1311867719.6112511158 0.0095568532 0.0057725390 0.0095568532 0.0031881769 0.0323070000 378701349 0 402718720 -0.0047352347 -0.0020727774 0.0022170083 31 1311867719.6421909332 0.0106952935 0.0059313375 0.0106952935 0.0031562386 0.0327530000 378706569 0 402718720 -0.0032794694 -0.0006180566 0.0027328350 32 1311867719.6770479679 0.0095242197 0.0060436151 0.0106952935 0.0031362991 0.0331190000 378711717 0 402718720 -0.0050851172 -0.0011290608 0.0036586777 33 1311867719.7107939720 0.0122157605 0.0062306498 0.0122157605 0.0031061898 0.0324640000 378719777 0 402718720 -0.0035531465 0.0000193917 0.0023218407 34 1311867719.7442650795 0.0120667201 0.0064022989 0.0122157605 0.0030722017 0.0322680000 378730973 0 402718720 -0.0044458755 0.0005772572 0.0026263455 35 1311867719.7861878872 0.0117570804 0.0065552927 0.0122157605 0.0030477974 0.0323640000 378735737 0 402718720 -0.0045487238 0.0000682396 0.0038034604 36 1311867719.8099169731 0.0117550185 0.0066997295 0.0122157605 0.0030192787 0.0319800000 378740509 0 402718720 -0.0047520986 -0.0005538679 0.0042808279 37 1311867719.8454990387 0.0116274534 0.0068329112 0.0122157605 0.0030041425 0.0316520000 378745529 0 402718720 -0.0056490968 -0.0020815206 0.0045687342 38 1311867719.8771090508 0.0114961304 0.0069556275 0.0122157605 0.0029686121 0.0425050000 378750037 0 402718720 -0.0064380481 -0.0018136461 0.0047346619 39 1311867719.9114089012 0.0121731646 0.0070894105 0.0122157605 0.0029498927 0.0313350000 378754849 0 402718720 -0.0069701392 -0.0030913271 0.0044020526 40 1311867719.9461970329 0.0115540056 0.0072010254 0.0122157605 0.0029273876 0.0308660000 378759813 0 402718720 -0.0075602736 -0.0042234827 0.0053102709 41 1311867719.9807810783 0.0139135327 0.0073647451 0.0139135327 0.0029113039 0.0340960000 379322301 0 402718720 -0.0067095403 -0.0032301005 0.0034692171 42 1311867720.0117020607 0.0121523021 0.0074787345 0.0139135327 0.0029309541 0.1064900000 379393173 0 402718720 -0.0085189929 -0.0022955618 0.0048652827 43 1311867720.0452380180 0.0151819838 0.0076578799 0.0151819838 0.0029355592 0.0846960000 382699105 0 402718720 -0.0081953872 -0.0025372480 0.0024222932 44 1311867720.0772819519 0.0164605286 0.0078579401 0.0164605286 0.0029434193 0.0688360000 381550665 0 402718720 -0.0054636155 -0.0042071734 0.0036435076 45 1311867720.1172130108 0.0166359209 0.0080530063 0.0166359209 0.0029924663 0.0321530000 379407425 0 402718720 -0.0039043501 -0.0024803979 0.0051704105 46 1311867720.1451559067 0.0171792153 0.0082514022 0.0171792153 0.0029659753 0.0317160000 379411077 0 402718720 -0.0034941786 -0.0020040667 0.0050787935 47 1311867720.1781630516 0.0154977562 0.0084055799 0.0171792153 0.0029881056 0.0326150000 379415377 0 402718720 -0.0060996786 -0.0008958947 0.0051365369 48 1311867720.2094950676 0.0168425310 0.0085813497 0.0171792153 0.0029682796 0.0324890000 379419837 0 402718720 -0.0048455140 0.0002815602 0.0050556073 49 1311867720.2421469688 0.0172861163 0.0087589980 0.0172861163 0.0029775807 0.0312210000 379424337 0 402718720 -0.0038040716 -0.0017472280 0.0062523158 50 1311867720.2770779133 0.0175607093 0.0089350322 0.0175607093 0.0029947951 0.0314320000 379428469 0 402718720 -0.0044665351 -0.0020440063 0.0064811818 51 1311867720.3094570637 0.0181440040 0.0091156003 0.0181440040 0.0030115455 0.0320490000 379433105 0 402718720 -0.0033301553 0.0024880120 0.0078608636 52 1311867720.3430728912 0.0162862726 0.0092534979 0.0181440040 0.0030720098 0.0311750000 379437349 0 402718720 -0.0048764949 0.0019138850 0.0090469057 53 1311867720.3779859543 0.0205355901 0.0094663675 0.0205355901 0.0033808900 0.0303510000 379442097 0 402718720 -0.0054844408 -0.0045719496 0.0047776615 54 1311867720.4096798897 0.0225423966 0.0097085162 0.0225423966 0.0036973754 0.0305780000 379447101 0 402718720 -0.0043119937 -0.0033897895 0.0040599820 55 1311867720.4461109638 0.0236494467 0.0099619877 0.0236494467 0.0036710708 0.0308290000 379451649 0 402718720 -0.0045302408 -0.0024586644 0.0024500394 56 1311867720.4799289703 0.0238991547 0.0102108657 0.0238991547 0.0036827472 0.0304300000 379455557 0 402718720 -0.0053825499 -0.0042987573 0.0021206490 57 1311867720.5104389191 0.0239042528 0.0104511005 0.0239042528 0.0037671433 0.0337340000 380048149 0 402718720 -0.0074537033 -0.0034695438 0.0003583548 58 1311867720.5467319489 0.0247814748 0.0106981759 0.0247814748 0.0037920055 0.1264190000 380119145 0 402718720 -0.0074017593 -0.0028252632 0.0000041816 59 1311867720.5793280602 0.0253621694 0.0109467182 0.0253621694 0.0038292148 0.1065350000 383920313 0 402718720 -0.0063327057 -0.0051333797 0.0002047332 60 1311867720.6121249199 0.0250649117 0.0111820214 0.0253621694 0.0038235250 0.0575050000 383944089 0 402718720 -0.0066803666 -0.0047079166 0.0005162142 61 1311867720.6463210583 0.0238323621 0.0113894041 0.0253621694 0.0038308506 0.0647050000 382752717 0 402718720 -0.0061783511 -0.0027312958 0.0024833353 62 1311867720.6798269749 0.0249337275 0.0116078609 0.0253621694 0.0038255703 0.0323800000 380137673 0 402718720 -0.0058187032 -0.0043817642 0.0020506675 63 1311867720.7102439404 0.0259115249 0.0118349032 0.0259115249 0.0038100312 0.0323310000 380141701 0 402718720 -0.0074101742 -0.0061357454 0.0003091929 64 1311867720.7451629639 0.0259769764 0.0120558731 0.0259769764 0.0038360550 0.0319970000 380145865 0 402718720 -0.0064899763 -0.0038652774 0.0012742631 65 1311867720.7790179253 0.0291149002 0.0123183196 0.0291149002 0.0038568743 0.0321650000 380157893 0 402718720 -0.0028658137 -0.0043115485 0.0014641141 66 1311867720.8115909100 0.0297918189 0.0125830696 0.0297918189 0.0038411769 0.0423520000 380174321 0 402718720 -0.0038923093 -0.0056398879 0.0004366325 67 1311867720.8467299938 0.0285552852 0.0128214609 0.0297918189 0.0038975614 0.0322690000 380178925 0 402718720 -0.0055000060 -0.0025912239 0.0004348319 68 1311867720.8813319206 0.0279080272 0.0130433222 0.0297918189 0.0039028634 0.0319000000 380182865 0 402718720 -0.0078016729 -0.0023444025 -0.0006364199 69 1311867720.9149661064 0.0301705468 0.0132915428 0.0301705468 0.0038970922 0.0323440000 380186877 0 402718720 -0.0042439448 -0.0027388255 -0.0000350174 70 1311867720.9500010014 0.0308969505 0.0135430486 0.0308969505 0.0038761201 0.0327460000 380191169 0 402718720 -0.0049109994 -0.0047573396 -0.0012679080 71 1311867720.9797990322 0.0321695842 0.0138053942 0.0321695842 0.0038576566 0.0320640000 380195309 0 402718720 -0.0045639197 -0.0039339862 -0.0028105937 72 1311867721.0093889236 0.0302030966 0.0140331401 0.0321695842 0.0038341884 0.0417740000 380198897 0 402718720 -0.0051326188 -0.0042183055 -0.0004560129 73 1311867721.0478379726 0.0340888910 0.0143078764 0.0340888910 0.0038339482 0.0405170000 380203293 0 402718720 -0.0032849472 -0.0036967329 -0.0039304625 74 1311867721.0794439316 0.0344412252 0.0145799487 0.0344412252 0.0038090123 0.0428830000 380206865 0 402718720 -0.0021209752 -0.0031450163 -0.0030833958 75 1311867721.1103579998 0.0311472397 0.0148008459 0.0344412252 0.0037932684 0.0411430000 380210733 0 402718720 -0.0040436843 -0.0035978775 0.0000561255 76 1311867721.1467890739 0.0345719382 0.0150609918 0.0345719382 0.0038247009 0.0298020000 380215017 0 402718720 -0.0028667829 -0.0028784701 -0.0031071999 77 1311867721.1774179935 0.0312345345 0.0152710379 0.0345719382 0.0040312871 0.0294520000 380218789 0 402718720 -0.0046120370 -0.0010735580 -0.0009719010 78 1311867721.2112360001 0.0355971977 0.0155316296 0.0355971977 0.0040762942 0.0326670000 380799825 0 402718720 -0.0049093678 -0.0031885596 -0.0069059450 79 1311867721.2469010353 0.0363001153 0.0157945219 0.0363001153 0.0040905175 0.1267590000 380865973 0 402718720 -0.0048487033 -0.0055327602 -0.0074256654 80 1311867721.2800450325 0.0380712859 0.0160729814 0.0380712859 0.0041069104 0.1020640000 382500517 0 402718720 -0.0021505139 -0.0044331793 -0.0073499512 81 1311867721.3099579811 0.0375413038 0.0163380224 0.0380712859 0.0040848602 0.0815300000 384946173 0 402718720 -0.0021565347 -0.0040162425 -0.0066157850 82 1311867721.3483059406 0.0376332290 0.0165977201 0.0380712859 0.0040767087 0.0797860000 383797945 0 402718720 -0.0017972267 -0.0036967094 -0.0064008357 83 1311867721.3790040016 0.0401192084 0.0168811115 0.0401192084 0.0040920218 0.0317550000 380881245 0 402718720 -0.0035463930 -0.0062955511 -0.0106408596 84 1311867721.4092550278 0.0382846780 0.0171359159 0.0401192084 0.0040919830 0.0322160000 380885425 0 402718720 -0.0044730250 -0.0033540863 -0.0092366561 85 1311867721.4478130341 0.0420290828 0.0174287767 0.0420290828 0.0040944133 0.0439150000 380889941 0 402718720 -0.0019565723 -0.0045383754 -0.0114716422 86 1311867721.4768960476 0.0395851992 0.0176864095 0.0420290828 0.0041092917 0.0314810000 380893953 0 402718720 -0.0031031382 -0.0018254316 -0.0092876256 87 1311867721.5093359947 0.0408988222 0.0179532188 0.0420290828 0.0041458207 0.0311490000 380897541 0 402718720 -0.0034818079 -0.0055827154 -0.0104949810 88 1311867721.5451331139 0.0399197787 0.0182028388 0.0420290828 0.0041410868 0.0318880000 380901593 0 402718720 -0.0040074582 -0.0035680828 -0.0099593997 89 1311867721.5769670010 0.0408963002 0.0184578215 0.0420290828 0.0041212059 0.0312480000 380905813 0 402718720 -0.0024196957 -0.0025412682 -0.0098519456 90 1311867721.6129651070 0.0413582772 0.0187122710 0.0420290828 0.0041139704 0.0308000000 380909385 0 402718720 -0.0016169876 -0.0028473791 -0.0094009498 91 1311867721.6496050358 0.0428605676 0.0189776369 0.0428605676 0.0041133970 0.0425650000 380913485 0 402718720 -0.0012321440 -0.0049909819 -0.0109056821 92 1311867721.6800351143 0.0424049236 0.0192322814 0.0428605676 0.0041231223 0.0311370000 380917137 0 402718720 -0.0035775790 -0.0014819013 -0.0130000375 93 1311867721.7162289619 0.0416445099 0.0194732731 0.0428605676 0.0041654263 0.0397800000 380921429 0 402718720 -0.0040080491 -0.0021964859 -0.0124062132 94 1311867721.7467949390 0.0444338098 0.0197388107 0.0444338098 0.0042578602 0.0302690000 380925257 0 402718720 -0.0006739465 -0.0040714536 -0.0118782418 95 1311867721.7787001133 0.0460954234 0.0200162487 0.0460954234 0.0042456059 0.0295540000 380928837 0 402718720 0.0001640702 -0.0027443608 -0.0134037286 96 1311867721.8154830933 0.0448693261 0.0202751349 0.0460954234 0.0042249635 0.0293880000 380933057 0 402718720 -0.0026847031 -0.0031595861 -0.0143474787 97 1311867721.8485159874 0.0436204672 0.0205158085 0.0460954234 0.0042072808 0.0293880000 380936741 0 402718720 -0.0028964975 -0.0031774994 -0.0127276666 98 1311867721.8778810501 0.0424698628 0.0207398294 0.0460954234 0.0041931112 0.0292950000 380940649 0 402718720 -0.0033290731 -0.0027284948 -0.0116569847 99 1311867721.9146931171 0.0432447679 0.0209671520 0.0460954234 0.0041796997 0.0292120000 380944037 0 402718720 -0.0010454212 -0.0012281945 -0.0106957220 100 1311867721.9467151165 0.0431883708 0.0211893642 0.0460954234 0.0041614261 0.0440670000 381487557 0 402718720 -0.0033033080 -0.0017653074 -0.0133412480 101 1311867721.9773728848 0.0425061695 0.0214004217 0.0460954234 0.0041693715 0.1145180000 381548529 0 402718720 -0.0030239997 -0.0009616798 -0.0126105985 102 1311867722.0166850090 0.0431181677 0.0216133408 0.0460954234 0.0041835260 0.0657790000 386043569 0 402718720 -0.0014492415 -0.0007499378 -0.0112668909 103 1311867722.0475180149 0.0445957072 0.0218364705 0.0460954234 0.0041832130 0.0371170000 385884753 0 402718720 -0.0000167601 -0.0003794344 -0.0126823634 104 1311867722.0800709724 0.0414243713 0.0220248157 0.0460954234 0.0041694086 0.0725080000 384682441 0 402718720 -0.0028045524 -0.0025876330 -0.0101223653 105 1311867722.1161251068 0.0426723249 0.0222214587 0.0460954234 0.0041525000 0.0310690000 381564157 0 402718720 -0.0022036007 -0.0030077517 -0.0112400129 106 1311867722.1479530334 0.0431104526 0.0224185247 0.0460954234 0.0041412720 0.0302720000 381567633 0 402718720 -0.0015977754 -0.0026123193 -0.0112267965 107 1311867722.1798410416 0.0428871997 0.0226098207 0.0460954234 0.0041241353 0.0307410000 381571629 0 402718720 -0.0018418636 -0.0012682175 -0.0115453983 108 1311867722.2146399021 0.0444653593 0.0228121868 0.0460954234 0.0041299153 0.0307460000 381575369 0 402718720 0.0001468300 -0.0015550536 -0.0114927758 109 1311867722.2469589710 0.0430340022 0.0229977080 0.0460954234 0.0041140104 0.0305620000 381579173 0 402718720 -0.0027413303 -0.0016005374 -0.0128577072 110 1311867722.2780389786 0.0446675830 0.0231947069 0.0460954234 0.0041074081 0.0307450000 381582545 0 402718720 -0.0012901630 -0.0020314238 -0.0132770594 111 1311867722.3154170513 0.0440234020 0.0233823528 0.0460954234 0.0040893296 0.0306410000 381586237 0 402718720 -0.0015987605 -0.0023273169 -0.0124985566 112 1311867722.3488469124 0.0423989594 0.0235521439 0.0460954234 0.0040789418 0.0304960000 381590073 0 402718720 -0.0020989140 -0.0017033122 -0.0102518797 113 1311867722.3777940273 0.0455305986 0.0237466435 0.0460954234 0.0040760338 0.0304450000 381593341 0 402718720 -0.0004547094 -0.0020925691 -0.0130363666 114 1311867722.4150679111 0.0452403016 0.0239351844 0.0460954234 0.0040596607 0.0301590000 381596993 0 402718720 -0.0007658992 -0.0025819966 -0.0121836998 115 1311867722.4467909336 0.0452116951 0.0241201975 0.0460954234 0.0040889971 0.0297880000 381600605 0 402718720 -0.0003206935 -0.0036053031 -0.0116790086 116 1311867722.4777851105 0.0471578687 0.0243187981 0.0471578687 0.0041408310 0.0298180000 381604673 0 402718720 -0.0006161402 -0.0036486792 -0.0137859909 117 1311867722.5147399902 0.0466014296 0.0245092480 0.0471578687 0.0041238077 0.0300310000 381608341 0 402718720 -0.0005642981 -0.0059732660 -0.0114040868 118 1311867722.5469911098 0.0469131693 0.0246991117 0.0471578687 0.0041121542 0.0295910000 381612337 0 402718720 0.0005904739 -0.0040587848 -0.0107899047 119 1311867722.5802359581 0.0462716557 0.0248803936 0.0471578687 0.0040962384 0.0297590000 381615773 0 402718720 0.0006729988 -0.0024287570 -0.0100166835 120 1311867722.6146309376 0.0468990728 0.0250638826 0.0471578687 0.0040803975 0.0294730000 381619697 0 402718720 0.0011832584 -0.0027504822 -0.0105201267 121 1311867722.6560258865 0.0498045906 0.0252683513 0.0498045906 0.0040842504 0.0291450000 381623445 0 402718720 0.0009034360 -0.0052189548 -0.0154954288 122 1311867722.6778230667 0.0485490561 0.0254591767 0.0498045906 0.0040732737 0.0289110000 381627073 0 402718720 0.0011864319 -0.0062974067 -0.0123621449 123 1311867722.7252709866 0.0487321690 0.0256483880 0.0498045906 0.0041629969 0.0289180000 381630997 0 402718720 0.0017287983 -0.0054604765 -0.0111312037 124 1311867722.7449109554 0.0508631580 0.0258517330 0.0508631580 0.0041696234 0.0286790000 381634649 0 402718720 0.0038030297 -0.0058903182 -0.0122081432 125 1311867722.7770080566 0.0502327159 0.0260467808 0.0508631580 0.0041944025 0.0287290000 381638301 0 402718720 0.0016356083 -0.0053374120 -0.0141668189 126 1311867722.8162860870 0.0522703864 0.0262549047 0.0522703864 0.0041901769 0.0289490000 381642761 0 402718720 -0.0006652465 -0.0069605596 -0.0189086068 127 1311867722.8466939926 0.0487691611 0.0264321823 0.0522703864 0.0041798767 0.0283200000 381646493 0 402718720 -0.0008286713 -0.0066405553 -0.0130349677 128 1311867722.8819770813 0.0516492315 0.0266291905 0.0522703864 0.0041892145 0.0290110000 381650265 0 402718720 0.0021268306 -0.0056161853 -0.0132853594 129 1311867722.9150629044 0.0536816604 0.0268388995 0.0536816604 0.0041892276 0.0293930000 381665837 0 402718720 0.0020503248 -0.0081666401 -0.0149610722 130 1311867722.9485991001 0.0520408414 0.0270327606 0.0536816604 0.0041818939 0.0291920000 381695193 0 402718720 0.0022261241 -0.0065892437 -0.0112780118 131 1311867722.9821140766 0.0556972697 0.0272515737 0.0556972697 0.0042070386 0.0292000000 381699237 0 402718720 0.0031392202 -0.0093504060 -0.0146251433 132 1311867723.0147259235 0.0549788028 0.0274616284 0.0556972697 0.0042151555 0.0285200000 381702609 0 402718720 0.0024506981 -0.0045285020 -0.0152194155 133 1311867723.0460629463 0.0552233048 0.0276703629 0.0556972697 0.0042332800 0.0284810000 381706373 0 402718720 0.0026459084 -0.0081049455 -0.0131208450 134 1311867723.0845439434 0.0555537269 0.0278784477 0.0556972697 0.0042222980 0.0318140000 382292389 0 402718720 0.0027501511 -0.0072017615 -0.0132110585 135 1311867723.1140980721 0.0580686778 0.0281020790 0.0580686778 0.0042212559 0.0890210000 382246401 0 402718720 0.0027611703 -0.0088083958 -0.0164471101 136 1311867723.1505160332 0.0568022616 0.0283131098 0.0580686778 0.0042098908 0.0760610000 382530621 0 402718720 -0.0005050572 -0.0104360096 -0.0173698477 137 1311867723.1811029911 0.0581540093 0.0285309265 0.0581540093 0.0041969322 0.0579940000 386787005 0 402718720 0.0018135910 -0.0104775131 -0.0161298104 138 1311867723.2201359272 0.0571496822 0.0287383088 0.0581540093 0.0041888544 0.0398930000 386792853 0 402718720 -0.0000207936 -0.0088473679 -0.0172024388 139 1311867723.2486810684 0.0549853556 0.0289271365 0.0581540093 0.0041829036 0.0719800000 385463129 0 402718720 -0.0012270929 -0.0082427608 -0.0148803983 140 1311867723.2846419811 0.0547080822 0.0291112861 0.0581540093 0.0041688247 0.0283800000 382265301 0 402718720 -0.0017722426 -0.0088378945 -0.0143859787 141 1311867723.3132460117 0.0544588566 0.0292910561 0.0581540093 0.0041541579 0.0370340000 382268993 0 402718720 -0.0022924584 -0.0085470993 -0.0144855045 142 1311867723.3499810696 0.0545143150 0.0294686847 0.0581540093 0.0041504012 0.0285790000 382272725 0 402718720 -0.0030380446 -0.0090359049 -0.0145360073 143 1311867723.3822429180 0.0542666689 0.0296420972 0.0581540093 0.0041385961 0.0365270000 382276521 0 402718720 -0.0023169117 -0.0076329508 -0.0130774789 144 1311867723.4193739891 0.0542203374 0.0298127794 0.0581540093 0.0041619841 0.0283650000 382280341 0 402718720 -0.0036850832 -0.0073677772 -0.0146980211 145 1311867723.4455900192 0.0545851327 0.0299836232 0.0581540093 0.0041524989 0.0280530000 382283993 0 402718720 -0.0024386295 -0.0086383047 -0.0125159044 146 1311867723.4825348854 0.0550754182 0.0301554848 0.0581540093 0.0041473284 0.0279780000 382287693 0 402718720 -0.0039965436 -0.0105115809 -0.0138902459 147 1311867723.5147960186 0.0568709522 0.0303372227 0.0581540093 0.0041343473 0.0275720000 382290913 0 402718720 -0.0027637570 -0.0095129786 -0.0150280036 148 1311867723.5451340675 0.0553655960 0.0305063333 0.0581540093 0.0041246281 0.0277760000 382294861 0 402718720 -0.0038082744 -0.0082658166 -0.0134994071 149 1311867723.5809938908 0.0581527129 0.0306918795 0.0581540093 0.0041297302 0.0275130000 382298489 0 402718720 -0.0035090046 -0.0100789405 -0.0167034026 150 1311867723.6132669449 0.0556727163 0.0308584184 0.0581540093 0.0041211490 0.0364730000 382302045 0 402718720 -0.0053095487 -0.0099619711 -0.0142377652 151 1311867723.6453940868 0.0540620461 0.0310120848 0.0581540093 0.0041108308 0.0408210000 382858053 0 402718720 -0.0069569019 -0.0093277600 -0.0136626158 152 1311867723.6809489727 0.0557212383 0.0311746450 0.0581540093 0.0040999700 0.0808260000 382815605 0 402718720 -0.0060074683 -0.0086362930 -0.0153019531 153 1311867723.7130429745 0.0553693324 0.0313327803 0.0581540093 0.0040925709 0.0738740000 382819713 0 402718720 -0.0066670598 -0.0111355027 -0.0140259098 154 1311867723.7471990585 0.0527746864 0.0314720134 0.0581540093 0.0040951326 0.0725700000 386253913 0 402718720 -0.0088512674 -0.0086081922 -0.0130734872 155 1311867723.7809250355 0.0586646721 0.0316474499 0.0586646721 0.0041462001 0.0614860000 387511417 0 402718720 -0.0055226884 -0.0116531318 -0.0171082951 156 1311867723.8157649040 0.0512141325 0.0317728774 0.0586646721 0.0042551865 0.0784440000 386243719 0 402718720 -0.0117494650 -0.0068612215 -0.0145095652 157 1311867723.8468959332 0.0518367998 0.0319006731 0.0586646721 0.0042464848 0.0280790000 382835841 0 402718720 -0.0109707359 -0.0059451330 -0.0146399550 158 1311867723.8826351166 0.0510648414 0.0320219653 0.0586646721 0.0042381399 0.0635120000 382839589 0 402718720 -0.0125458734 -0.0073762466 -0.0145532861 159 1311867723.9172909260 0.0528087132 0.0321526995 0.0586646721 0.0042267024 0.0274960000 382842937 0 402718720 -0.0117673744 -0.0076201232 -0.0160623826 160 1311867723.9490020275 0.0559754223 0.0323015915 0.0586646721 0.0042214487 0.0387390000 382846461 0 402718720 -0.0107693635 -0.0076228892 -0.0195565820 161 1311867723.9839010239 0.0507756695 0.0324163374 0.0586646721 0.0042376441 0.0273690000 382850201 0 402718720 -0.0139661524 -0.0063861022 -0.0153393112 162 1311867724.0132899284 0.0524876341 0.0325402343 0.0586646721 0.0042340618 0.0376900000 382853893 0 402718720 -0.0130984327 -0.0064395675 -0.0169906300 163 1311867724.0475380421 0.0527192727 0.0326640320 0.0586646721 0.0042219781 0.0266560000 382857793 0 402718720 -0.0124683883 -0.0071577337 -0.0159308817 164 1311867724.0824530125 0.0522712879 0.0327835885 0.0586646721 0.0042115962 0.0418100000 383359349 0 402718720 -0.0131115979 -0.0085814260 -0.0153204519 165 1311867724.1132431030 0.0527013354 0.0329043021 0.0586646721 0.0042014258 0.0800120000 383340829 0 402718720 -0.0143134501 -0.0082815355 -0.0175328832 166 1311867724.1547191143 0.0571241491 0.0330502048 0.0586646721 0.0041983842 0.0745600000 383344305 0 402718720 -0.0131427301 -0.0093953339 -0.0221459866 167 1311867724.1810541153 0.0531600043 0.0331706228 0.0586646721 0.0042079430 0.0707560000 384649113 0 402718720 -0.0135303168 -0.0072857612 -0.0166139640 168 1311867724.2139430046 0.0558816642 0.0333058075 0.0586646721 0.0042091605 0.0487790000 388409409 0 402718720 -0.0135493185 -0.0100395009 -0.0197772086 169 1311867724.2507870197 0.0565152094 0.0334431413 0.0586646721 0.0042004968 0.0354640000 388395565 0 402718720 -0.0130637614 -0.0099473065 -0.0195029080 170 1311867724.2855930328 0.0538907126 0.0335634211 0.0586646721 0.0041980027 0.0710020000 386967277 0 402718720 -0.0140774827 -0.0068500969 -0.0173863806 171 1311867724.3144888878 0.0533668585 0.0336792307 0.0586646721 0.0041868526 0.0358480000 383362445 0 402718720 -0.0155636566 -0.0074165603 -0.0180686917 172 1311867724.3517999649 0.0563888773 0.0338112635 0.0586646721 0.0041841645 0.0595540000 383366121 0 402718720 -0.0149462335 -0.0094249705 -0.0213504806 173 1311867724.3888330460 0.0546044558 0.0339314554 0.0586646721 0.0041755271 0.0260350000 383369837 0 402718720 -0.0157981385 -0.0082431277 -0.0198931005 174 1311867724.4160330296 0.0530731715 0.0340414652 0.0586646721 0.0041700830 0.0260680000 383373145 0 402718720 -0.0151112908 -0.0068894154 -0.0173668414 175 1311867724.4509639740 0.0539188758 0.0341550504 0.0586646721 0.0041620451 0.0257850000 383376381 0 402718720 -0.0155130830 -0.0091721062 -0.0188399255 176 1311867724.4830689430 0.0553386882 0.0342754120 0.0586646721 0.0041597664 0.0262550000 383379833 0 402718720 -0.0169804376 -0.0104496218 -0.0223703273 177 1311867724.5208630562 0.0529992506 0.0343811964 0.0586646721 0.0041629026 0.0256630000 383383389 0 402718720 -0.0171116740 -0.0098730782 -0.0191089697 178 1311867724.5523910522 0.0548577458 0.0344962332 0.0586646721 0.0041676027 0.0261700000 383386641 0 402718720 -0.0171515495 -0.0111373607 -0.0218317676 179 1311867724.5861799717 0.0544461422 0.0346076852 0.0586646721 0.0041767484 0.0258740000 383390077 0 402718720 -0.0173111260 -0.0106222555 -0.0212238338 180 1311867724.6193559170 0.0542207509 0.0347166467 0.0586646721 0.0042041541 0.0260180000 383393801 0 402718720 -0.0180288516 -0.0101371631 -0.0224002339 181 1311867724.6529819965 0.0543772094 0.0348252686 0.0586646721 0.0041928088 0.0257290000 383397085 0 402718720 -0.0180695169 -0.0111746844 -0.0218441840 182 1311867724.6818330288 0.0537898056 0.0349294693 0.0586646721 0.0041864175 0.0375480000 383400425 0 402718720 -0.0191041231 -0.0119846594 -0.0214831159 183 1311867724.7153129578 0.0565519296 0.0350476248 0.0586646721 0.0041774908 0.0255320000 383404205 0 402718720 -0.0193619430 -0.0111049153 -0.0256471932 184 1311867724.7518899441 0.0541226864 0.0351512937 0.0586646721 0.0041753877 0.0360260000 383407849 0 402718720 -0.0205541942 -0.0114799077 -0.0222079325 185 1311867724.7853860855 0.0532316007 0.0352490250 0.0586646721 0.0041663003 0.0257820000 383411245 0 402718720 -0.0235393960 -0.0111644743 -0.0237728432 186 1311867724.8179960251 0.0530565940 0.0353447647 0.0586646721 0.0041649559 0.0283090000 383934077 0 402718720 -0.0214231499 -0.0103377616 -0.0208954886 187 1311867724.8547580242 0.0532560796 0.0354405471 0.0586646721 0.0041765773 0.0763420000 383905297 0 402718720 -0.0220855065 -0.0117620965 -0.0213655159 188 1311867724.8830249310 0.0541118309 0.0355398624 0.0586646721 0.0041685889 0.0693520000 383908093 0 402718720 -0.0217483081 -0.0117562329 -0.0221967157 189 1311867724.9137279987 0.0532475524 0.0356335539 0.0586646721 0.0041798162 0.0672900000 385194773 0 402718720 -0.0220641345 -0.0097719794 -0.0212714057 190 1311867724.9535229206 0.0519330874 0.0357193409 0.0586646721 0.0041750281 0.0493710000 389307153 0 402718720 -0.0239442922 -0.0117986118 -0.0204286445 191 1311867724.9843940735 0.0522428975 0.0358058517 0.0586646721 0.0041693372 0.0289080000 389227633 0 402718720 -0.0244586915 -0.0106377378 -0.0219519250 192 1311867725.0159099102 0.0493159667 0.0358762169 0.0586646721 0.0041952867 0.0680610000 387814405 0 402718720 -0.0239878595 -0.0107063521 -0.0173341166 193 1311867725.0518310070 0.0513492972 0.0359563883 0.0586646721 0.0041891639 0.0263040000 383928529 0 402718720 -0.0235974919 -0.0123699075 -0.0193146169 194 1311867725.0813930035 0.0538168028 0.0360484523 0.0586646721 0.0041940129 0.0267530000 383931877 0 402718720 -0.0246093553 -0.0133804576 -0.0238486398 195 1311867725.1151220798 0.0521375686 0.0361309606 0.0586646721 0.0041838468 0.0267490000 383935801 0 402718720 -0.0244691484 -0.0148489950 -0.0202733893 196 1311867725.1557130814 0.0543981828 0.0362241607 0.0586646721 0.0041908561 0.0267100000 383939237 0 402718720 -0.0237557366 -0.0129669998 -0.0238016006 197 1311867725.1843969822 0.0546278469 0.0363175804 0.0586646721 0.0041830586 0.0264330000 383942417 0 402718720 -0.0237514451 -0.0138529856 -0.0236503724 198 1311867725.2150099277 0.0497133695 0.0363852359 0.0586646721 0.0041933538 0.0258370000 383946045 0 402718720 -0.0255253930 -0.0129536428 -0.0177418701 199 1311867725.2516539097 0.0520272851 0.0364638392 0.0586646721 0.0041891127 0.0257830000 383949377 0 402718720 -0.0278290454 -0.0136966230 -0.0232278109 200 1311867725.2816410065 0.0501492769 0.0365322664 0.0586646721 0.0041805541 0.0255150000 383953189 0 402718720 -0.0290614683 -0.0138924178 -0.0214358047 201 1311867725.3196239471 0.0519168861 0.0366088068 0.0586646721 0.0041713763 0.0388980000 383956385 0 402718720 -0.0271688048 -0.0138586015 -0.0217663441 202 1311867725.3517010212 0.0533087142 0.0366914796 0.0586646721 0.0041711543 0.0254140000 383959973 0 402718720 -0.0290665217 -0.0172162689 -0.0240357444 203 1311867725.3837459087 0.0505305491 0.0367596523 0.0586646721 0.0042131507 0.0587380000 383963217 0 402718720 -0.0283184387 -0.0121794101 -0.0213409886 204 1311867725.4178969860 0.0502719805 0.0368258892 0.0586646721 0.0042106490 0.0248530000 383966669 0 402718720 -0.0302057788 -0.0130448369 -0.0221184306 205 1311867725.4492449760 0.0566143692 0.0369224184 0.0586646721 0.0042359059 0.0247820000 383970113 0 402718720 -0.0293363892 -0.0164308455 -0.0284029786 206 1311867725.4836509228 0.0531730801 0.0370013051 0.0586646721 0.0042816053 0.0247460000 383974421 0 402718720 -0.0283457693 -0.0137875760 -0.0223561674 207 1311867725.5178139210 0.0520255417 0.0370738860 0.0586646721 0.0042823167 0.0251580000 383977705 0 402718720 -0.0301635992 -0.0136224469 -0.0218349379 208 1311867725.5497610569 0.0504570417 0.0371382280 0.0586646721 0.0042729956 0.0249950000 383980957 0 402718720 -0.0318059549 -0.0132456068 -0.0206059236 209 1311867725.5815479755 0.0549681298 0.0372235386 0.0586646721 0.0042990426 0.0375990000 384405445 0 402718720 -0.0299560651 -0.0147798657 -0.0236480180 210 1311867725.6194949150 0.0503370464 0.0372859839 0.0586646721 0.0042994742 0.0767180000 384477189 0 402718720 -0.0324759074 -0.0135495085 -0.0190131105 211 1311867725.6515610218 0.0499926805 0.0373462052 0.0586646721 0.0043519022 0.0677830000 386630401 0 402718720 -0.0326718912 -0.0133119961 -0.0188219808 212 1311867725.6834650040 0.0509472191 0.0374103609 0.0586646721 0.0043426022 0.0424800000 390004417 0 402718720 -0.0332137607 -0.0116757769 -0.0211600177 213 1311867725.7201809883 0.0484889485 0.0374623730 0.0586646721 0.0043352728 0.0426690000 390017317 0 402718720 -0.0353552401 -0.0127490936 -0.0187078118 214 1311867725.7515070438 0.0472137667 0.0375079403 0.0586646721 0.0043269701 0.0700490000 388682615 0 402718720 -0.0365733951 -0.0125174625 -0.0179759841 215 1311867725.7835409641 0.0486243479 0.0375596445 0.0586646721 0.0043181989 0.0399970000 384495189 0 402718720 -0.0360322297 -0.0119418101 -0.0195105057 216 1311867725.8211829662 0.0465841293 0.0376014245 0.0586646721 0.0043173617 0.0256580000 384498209 0 402718720 -0.0371213779 -0.0111605134 -0.0168696344 217 1311867725.8517971039 0.0471932702 0.0376456266 0.0586646721 0.0043146080 0.0251340000 384501181 0 402718720 -0.0364019424 -0.0129944878 -0.0153847057 218 1311867725.8837900162 0.0528231077 0.0377152481 0.0586646721 0.0043175974 0.0251220000 384505113 0 402718720 -0.0353599600 -0.0140060503 -0.0219536908 219 1311867725.9192690849 0.0497773141 0.0377703260 0.0586646721 0.0043119611 0.0245880000 384508357 0 402718720 -0.0369163603 -0.0135546997 -0.0182052813 220 1311867725.9511859417 0.0467971750 0.0378113571 0.0586646721 0.0043125746 0.0241900000 384511521 0 402718720 -0.0394867957 -0.0110591119 -0.0171448216 221 1311867725.9829630852 0.0526396669 0.0378784536 0.0586646721 0.0043315118 0.0365610000 384515493 0 402718720 -0.0369358324 -0.0132711604 -0.0220572222 222 1311867726.0219368935 0.0499643534 0.0379328945 0.0586646721 0.0043328276 0.0362110000 385013281 0 402718720 -0.0368615352 -0.0110070528 -0.0176677369 223 1311867726.0504179001 0.0486443192 0.0379809278 0.0586646721 0.0043243524 0.0703050000 384976617 0 402718720 -0.0379108638 -0.0097967377 -0.0169892348 224 1311867726.0845088959 0.0516323932 0.0380418719 0.0586646721 0.0043201048 0.0622220000 385364881 0 402718720 -0.0362404734 -0.0092457961 -0.0202541426 225 1311867726.1199669838 0.0486076549 0.0380888309 0.0586646721 0.0043183199 0.0593950000 390740277 0 402718720 -0.0363666937 -0.0083720237 -0.0147016840 226 1311867726.1506989002 0.0512376130 0.0381470114 0.0586646721 0.0043190550 0.0534580000 390605637 0 402718720 -0.0367028378 -0.0109731052 -0.0191262010 227 1311867726.1824700832 0.0518178418 0.0382072353 0.0586646721 0.0043112868 0.0703700000 389351811 0 402718720 -0.0396531038 -0.0118056750 -0.0235139523 228 1311867726.2198660374 0.0483157709 0.0382515710 0.0586646721 0.0043337261 0.0308510000 384995505 0 402718720 -0.0397068262 -0.0088725025 -0.0189151075 229 1311867726.2506690025 0.0479533561 0.0382939369 0.0586646721 0.0043248971 0.0236400000 384997741 0 402718720 -0.0411631241 -0.0098224059 -0.0196849070 230 1311867726.2845950127 0.0477467626 0.0383350361 0.0586646721 0.0043171244 0.0231690000 385000953 0 402718720 -0.0437330008 -0.0086344974 -0.0226784647 231 1311867726.3187239170 0.0520813912 0.0383945441 0.0586646721 0.0043326542 0.0233880000 385004981 0 402718720 -0.0402542539 -0.0116981231 -0.0236662664 232 1311867726.3524029255 0.0503007583 0.0384458640 0.0586646721 0.0043279940 0.0373760000 385008441 0 402718720 -0.0444571674 -0.0094725285 -0.0261873491 233 1311867726.3835608959 0.0507427379 0.0384986403 0.0586646721 0.0043213213 0.0229960000 385011517 0 402718720 -0.0447037928 -0.0130855888 -0.0250947867 234 1311867726.4218099117 0.0507164299 0.0385508531 0.0586646721 0.0043316226 0.0228220000 385014953 0 402718720 -0.0425879322 -0.0077145267 -0.0241405182 235 1311867726.4504199028 0.0526056699 0.0386106608 0.0586646721 0.0043366851 0.0228810000 385018549 0 402718720 -0.0443123989 -0.0084766997 -0.0284330174 236 1311867726.4843189716 0.0493864417 0.0386563209 0.0586646721 0.0043352020 0.0224950000 385021833 0 402718720 -0.0441155694 -0.0102952439 -0.0220243782 237 1311867726.5207901001 0.0497361645 0.0387030713 0.0586646721 0.0043300463 0.0247460000 385394925 0 402718720 -0.0441851653 -0.0074735959 -0.0233381987 238 1311867726.5524380207 0.0497195832 0.0387493592 0.0586646721 0.0043337941 0.0663910000 385468169 0 402718720 -0.0438699052 -0.0065257391 -0.0228358507 239 1311867726.5874860287 0.0533602200 0.0388104925 0.0586646721 0.0043491477 0.0599150000 385470825 0 402718720 -0.0459298790 -0.0088379243 -0.0293902569 240 1311867726.6204600334 0.0477078184 0.0388475647 0.0586646721 0.0043766753 0.0584940000 389820893 0 402718720 -0.0463250279 -0.0058082389 -0.0227182209 241 1311867726.6509370804 0.0487371162 0.0388886001 0.0586646721 0.0043802814 0.0493580000 390637261 0 402718720 -0.0472946502 -0.0030326634 -0.0261805654 242 1311867726.6916151047 0.0458228886 0.0389172542 0.0586646721 0.0043755435 0.0652950000 390007187 0 402718720 -0.0465482585 -0.0043339045 -0.0208045468 243 1311867726.7201170921 0.0465165116 0.0389485269 0.0586646721 0.0043676793 0.0341510000 385484725 0 402718720 -0.0479362942 -0.0026400241 -0.0243219063 244 1311867726.7513859272 0.0434317738 0.0389669008 0.0586646721 0.0043596008 0.0237190000 385489121 0 402718720 -0.0476521552 -0.0057762936 -0.0186851807 245 1311867726.7880010605 0.0451888554 0.0389922966 0.0586646721 0.0043549709 0.0239610000 385492693 0 402718720 -0.0482494384 -0.0068032616 -0.0227378085 246 1311867726.8198299408 0.0453106388 0.0390179809 0.0586646721 0.0043480847 0.0236120000 385496121 0 402718720 -0.0473587103 -0.0060526058 -0.0224033557 247 1311867726.8500390053 0.0463832468 0.0390477998 0.0586646721 0.0043408898 0.0346100000 385499037 0 402718720 -0.0445044711 -0.0039248774 -0.0212635845 248 1311867726.8927390575 0.0465187840 0.0390779247 0.0586646721 0.0043331191 0.0334670000 385502153 0 402718720 -0.0450016595 -0.0058556502 -0.0218766816 249 1311867726.9216780663 0.0450895056 0.0391020676 0.0586646721 0.0043252913 0.0345330000 385505397 0 402718720 -0.0477042124 -0.0071568936 -0.0227185637 250 1311867726.9543499947 0.0439968035 0.0391216466 0.0586646721 0.0043200713 0.0240960000 385508849 0 402718720 -0.0457046404 -0.0067210328 -0.0182332750 251 1311867726.9902989864 0.0433659926 0.0391385563 0.0586646721 0.0043117377 0.0236120000 385512117 0 402718720 -0.0466786735 -0.0094047803 -0.0176573843 252 1311867727.0208179951 0.0446875282 0.0391605760 0.0586646721 0.0043127623 0.0348730000 385514945 0 402718720 -0.0453240275 -0.0048201038 -0.0201732237 253 1311867727.0536949635 0.0434392765 0.0391774879 0.0586646721 0.0043044529 0.0237980000 385517965 0 402718720 -0.0462182462 -0.0051205889 -0.0198100656 254 1311867727.0911629200 0.0430570357 0.0391927617 0.0586646721 0.0043053717 0.0239930000 385522337 0 402718720 -0.0466541052 -0.0084791407 -0.0194146968 255 1311867727.1196689606 0.0432565026 0.0392086979 0.0586646721 0.0042979732 0.0247560000 385525469 0 402718720 -0.0451841317 -0.0090271635 -0.0180744044 256 1311867727.1514298916 0.0418682732 0.0392190869 0.0586646721 0.0042976128 0.0245140000 385528929 0 402718720 -0.0436058193 -0.0065154508 -0.0148239592 257 1311867727.1904149055 0.0421969891 0.0392306741 0.0586646721 0.0043183777 0.0239940000 385557181 0 402718720 -0.0433957353 -0.0078422362 -0.0163716637 258 1311867727.2208960056 0.0445403866 0.0392512544 0.0586646721 0.0043153304 0.0244440000 385610681 0 402718720 -0.0452366248 -0.0108576231 -0.0221374705 259 1311867727.2544560432 0.0440381356 0.0392697365 0.0586646721 0.0043092111 0.0246950000 385615029 0 402718720 -0.0445459969 -0.0093848454 -0.0216753352 260 1311867727.2870850563 0.0432321541 0.0392849766 0.0586646721 0.0043015791 0.0248260000 385618185 0 402718720 -0.0441668555 -0.0091742482 -0.0205850229 261 1311867727.3192501068 0.0434668064 0.0393009989 0.0586646721 0.0042938946 0.0247330000 385621541 0 402718720 -0.0425343998 -0.0081911944 -0.0202636141 262 1311867727.3502039909 0.0416125767 0.0393098217 0.0586646721 0.0042898891 0.0248570000 385624281 0 402718720 -0.0422710106 -0.0072623841 -0.0177982450 263 1311867727.3894629478 0.0422059149 0.0393208335 0.0586646721 0.0042874938 0.0249750000 385628629 0 402718720 -0.0422701500 -0.0067114746 -0.0202707127 264 1311867727.4182970524 0.0423176810 0.0393321852 0.0586646721 0.0042810482 0.0252730000 385631897 0 402718720 -0.0412881151 -0.0078682946 -0.0196827687 265 1311867727.4495580196 0.0447303280 0.0393525556 0.0586646721 0.0042830207 0.0254150000 385635253 0 402718720 -0.0402024016 -0.0110580334 -0.0216952711 266 1311867727.4858360291 0.0452861004 0.0393748621 0.0586646721 0.0042790865 0.0250390000 385638873 0 402718720 -0.0381849781 -0.0108448118 -0.0208951943 267 1311867727.5198891163 0.0447405688 0.0393949584 0.0586646721 0.0042720073 0.0358400000 385641893 0 402718720 -0.0380100347 -0.0094779255 -0.0212679431 268 1311867727.5494980812 0.0402310193 0.0393980780 0.0586646721 0.0042903292 0.0253490000 385644873 0 402718720 -0.0393775254 -0.0095756557 -0.0168165136 269 1311867727.5905909538 0.0411086269 0.0394044369 0.0586646721 0.0042851577 0.0375350000 385648653 0 402718720 -0.0362131372 -0.0069517316 -0.0171519630 270 1311867727.6176431179 0.0395934917 0.0394051371 0.0586646721 0.0042849115 0.0253970000 385651793 0 402718720 -0.0375769474 -0.0072750207 -0.0177683663 271 1311867727.6497650146 0.0401103422 0.0394077394 0.0586646721 0.0042816737 0.0254720000 385655149 0 402718720 -0.0365555547 -0.0083961664 -0.0175185688 272 1311867727.6884338856 0.0402312540 0.0394107670 0.0586646721 0.0042753485 0.0259890000 385659129 0 402718720 -0.0351575054 -0.0072836680 -0.0176892169 273 1311867727.7184689045 0.0435797758 0.0394260381 0.0586646721 0.0042810237 0.0260410000 385662357 0 402718720 -0.0347590968 -0.0103928279 -0.0228251200 274 1311867727.7523269653 0.0414136611 0.0394332922 0.0586646721 0.0042745247 0.0256700000 385665849 0 402718720 -0.0361519456 -0.0110491328 -0.0210292973 275 1311867727.7856590748 0.0449801832 0.0394534627 0.0586646721 0.0042723442 0.0256970000 385669317 0 402718720 -0.0349717364 -0.0114832260 -0.0256250016 276 1311867727.8181309700 0.0451586917 0.0394741338 0.0586646721 0.0042674669 0.0381180000 385672761 0 402718720 -0.0352847613 -0.0107042007 -0.0271056462 277 1311867727.8548729420 0.0435987674 0.0394890242 0.0586646721 0.0042610894 0.0256920000 385675877 0 402718720 -0.0366503485 -0.0101786153 -0.0265437961 278 1311867727.8882629871 0.0449931398 0.0395088232 0.0586646721 0.0042562139 0.0256240000 385679241 0 402718720 -0.0367507450 -0.0111045223 -0.0288435277 279 1311867727.9193139076 0.0442283377 0.0395257390 0.0586646721 0.0042540352 0.0263260000 385682781 0 402718720 -0.0356182717 -0.0079609426 -0.0276589971 280 1311867727.9556980133 0.0450115502 0.0395453312 0.0586646721 0.0042470631 0.0259270000 385685785 0 402718720 -0.0320618525 -0.0090082064 -0.0246818922 281 1311867727.9869389534 0.0435825810 0.0395596986 0.0586646721 0.0042398381 0.0263420000 385689149 0 402718720 -0.0345224440 -0.0093805054 -0.0262426548 282 1311867728.0179219246 0.0429652482 0.0395717750 0.0586646721 0.0042366255 0.0260020000 385692233 0 402718720 -0.0338978693 -0.0077780313 -0.0252836831 283 1311867728.0555219650 0.0444862805 0.0395891408 0.0586646721 0.0042298330 0.0261910000 385695901 0 402718720 -0.0318802036 -0.0060335998 -0.0266064480 284 1311867728.0892169476 0.0449385755 0.0396079768 0.0586646721 0.0042269162 0.0263660000 385699233 0 402718720 -0.0335265696 -0.0051598405 -0.0303325541 285 1311867728.1177880764 0.0444649309 0.0396250188 0.0586646721 0.0042279475 0.0264430000 385702389 0 402718720 -0.0304373764 -0.0066395914 -0.0266495068 286 1311867728.1556169987 0.0448858440 0.0396434133 0.0586646721 0.0042206588 0.0359670000 385705953 0 402718720 -0.0301030800 -0.0058728154 -0.0281377956 287 1311867728.1882989407 0.0429302752 0.0396548657 0.0586646721 0.0042161884 0.0260260000 385709389 0 402718720 -0.0298172720 -0.0064243400 -0.0251007918 288 1311867728.2182519436 0.0429589078 0.0396663381 0.0586646721 0.0042133636 0.0385740000 385712609 0 402718720 -0.0305606835 -0.0077021029 -0.0264774431 289 1311867728.2558999062 0.0442784578 0.0396822970 0.0586646721 0.0042095186 0.0259570000 385716125 0 402718720 -0.0285980143 -0.0089255096 -0.0264677946 290 1311867728.2875900269 0.0466786399 0.0397064223 0.0586646721 0.0042038006 0.0262380000 385719353 0 402718720 -0.0283848494 -0.0076169637 -0.0313177072 291 1311867728.3226509094 0.0463297293 0.0397291828 0.0586646721 0.0042087314 0.0265710000 385722549 0 402718720 -0.0281374678 -0.0081551000 -0.0302725378 292 1311867728.3597300053 0.0452015474 0.0397479238 0.0586646721 0.0042168798 0.0264750000 385725881 0 402718720 -0.0280425996 -0.0074381353 -0.0293179229 293 1311867728.3861401081 0.0449024327 0.0397655160 0.0586646721 0.0042115944 0.0263580000 385728853 0 402718720 -0.0272148531 -0.0064366544 -0.0286452137 294 1311867728.4175701141 0.0441919677 0.0397805719 0.0586646721 0.0042666624 0.0262730000 385732049 0 402718720 -0.0283316709 -0.0077266782 -0.0302205943 295 1311867728.4568250179 0.0441498198 0.0397953829 0.0586646721 0.0042632665 0.0263230000 385735493 0 402718720 -0.0262504257 -0.0074573397 -0.0280639809 296 1311867728.4875330925 0.0434935391 0.0398078767 0.0586646721 0.0042574974 0.0259770000 385738601 0 402718720 -0.0267420672 -0.0066423053 -0.0284694508 297 1311867728.5187420845 0.0466056764 0.0398307649 0.0586646721 0.0042691171 0.0379960000 385741789 0 402718720 -0.0258367378 -0.0089024864 -0.0323364735 298 1311867728.5550920963 0.0462600999 0.0398523399 0.0586646721 0.0042641722 0.0260890000 385745489 0 402718720 -0.0268897228 -0.0081646256 -0.0339755230 299 1311867728.5878560543 0.0451911390 0.0398701954 0.0586646721 0.0042590361 0.0263170000 385748645 0 402718720 -0.0248289369 -0.0069916761 -0.0307165403 300 1311867728.6187679768 0.0453981571 0.0398886219 0.0586646721 0.0042536030 0.0266660000 385751953 0 402718720 -0.0254560784 -0.0073386985 -0.0324248895 301 1311867728.6580820084 0.0476604253 0.0399144419 0.0586646721 0.0042494086 0.0266040000 385755293 0 402718720 -0.0237638280 -0.0074502546 -0.0346295983 302 1311867728.6893489361 0.0443641953 0.0399291762 0.0586646721 0.0042485689 0.0267750000 385758857 0 402718720 -0.0245083719 -0.0070469100 -0.0306206904 303 1311867728.7210168839 0.0436487459 0.0399414520 0.0586646721 0.0042454350 0.0266850000 385761669 0 402718720 -0.0257703662 -0.0062930505 -0.0315996185 304 1311867728.7584259510 0.0469237641 0.0399644201 0.0586646721 0.0042463010 0.0366870000 385765185 0 402718720 -0.0260394514 -0.0084773060 -0.0372961648 305 1311867728.7858450413 0.0452157632 0.0399816376 0.0586646721 0.0042409315 0.0268250000 385768229 0 402718720 -0.0241144039 -0.0092361812 -0.0325486511 306 1311867728.8203740120 0.0457487144 0.0400004843 0.0586646721 0.0042345576 0.0353560000 385771537 0 402718720 -0.0234949645 -0.0075627388 -0.0345551148 307 1311867728.8545160294 0.0449416302 0.0400165792 0.0586646721 0.0042296206 0.0261380000 385774837 0 402718720 -0.0235667061 -0.0075863064 -0.0340325758 308 1311867728.8860759735 0.0455904342 0.0400346761 0.0586646721 0.0042237189 0.0391700000 385778185 0 402718720 -0.0231318362 -0.0059924787 -0.0356500633 309 1311867728.9193949699 0.0452982634 0.0400517104 0.0586646721 0.0042174949 0.0267630000 385781293 0 402718720 -0.0229400881 -0.0054827491 -0.0359316915 310 1311867728.9585559368 0.0427587964 0.0400604429 0.0586646721 0.0042229454 0.0266400000 385784889 0 402718720 -0.0250578485 -0.0051104794 -0.0356137715 311 1311867728.9886839390 0.0447205678 0.0400754273 0.0586646721 0.0042279007 0.0265170000 385788189 0 402718720 -0.0212329645 -0.0067262133 -0.0342265479 312 1311867729.0231020451 0.0452911742 0.0400921444 0.0586646721 0.0042299948 0.0269300000 385791865 0 402718720 -0.0227986276 -0.0070466381 -0.0377623737 313 1311867729.0583839417 0.0451508202 0.0401083063 0.0586646721 0.0042263125 0.0368480000 385795013 0 402718720 -0.0215460826 -0.0062987269 -0.0363780633 314 1311867729.0882170200 0.0452427864 0.0401246582 0.0586646721 0.0042213946 0.0266030000 385797945 0 402718720 -0.0209748596 -0.0068990840 -0.0352421254 315 1311867729.1263229847 0.0467798822 0.0401457859 0.0586646721 0.0042298595 0.0391810000 385801437 0 402718720 -0.0210105740 -0.0048944503 -0.0374885611 316 1311867729.1556320190 0.0465670750 0.0401661064 0.0586646721 0.0042273572 0.0269880000 385804921 0 402718720 -0.0219211206 -0.0050177961 -0.0373407230 317 1311867729.1888830662 0.0471253321 0.0401880598 0.0586646721 0.0042570373 0.0269100000 385808077 0 402718720 -0.0213897396 -0.0054090181 -0.0364291631 318 1311867729.2240469456 0.0465503335 0.0402080669 0.0586646721 0.0042618878 0.0268450000 385811585 0 402718720 -0.0220065787 -0.0045428397 -0.0359226801 319 1311867729.2579979897 0.0432838760 0.0402177090 0.0586646721 0.0042587194 0.0267240000 385814861 0 402718720 -0.0231017414 -0.0047335224 -0.0318902917 320 1311867729.2880148888 0.0459225737 0.0402355367 0.0586646721 0.0042559040 0.0267920000 385818465 0 402718720 -0.0202269852 -0.0052083055 -0.0325518176 321 1311867729.3236539364 0.0445090123 0.0402488497 0.0586646721 0.0042520008 0.0267820000 385821749 0 402718720 -0.0214430131 -0.0041117244 -0.0327919163 322 1311867729.3580930233 0.0433390811 0.0402584467 0.0586646721 0.0042659756 0.0357730000 385825025 0 402718720 -0.0216599945 -0.0064137536 -0.0316296481 323 1311867729.3882780075 0.0439205803 0.0402697845 0.0586646721 0.0042606176 0.0272100000 385828365 0 402718720 -0.0194801334 -0.0043728859 -0.0310450941 324 1311867729.4253289700 0.0462215431 0.0402881542 0.0586646721 0.0042566768 0.0272150000 385831633 0 402718720 -0.0183134116 -0.0056394422 -0.0340349339 325 1311867729.4572670460 0.0460676476 0.0403059372 0.0586646721 0.0042524650 0.0269890000 385834861 0 402718720 -0.0168726407 -0.0055972869 -0.0330359265 326 1311867729.4887750149 0.0458528325 0.0403229522 0.0586646721 0.0042587414 0.0269030000 385838241 0 402718720 -0.0167987458 -0.0070302412 -0.0329731666 327 1311867729.5223650932 0.0491791479 0.0403500354 0.0586646721 0.0042599606 0.0396510000 385841501 0 402718720 -0.0144901797 -0.0082392246 -0.0358895734 328 1311867729.5603790283 0.0450560339 0.0403643830 0.0586646721 0.0042617737 0.0272560000 385845137 0 402718720 -0.0166683272 -0.0071162959 -0.0330010802 329 1311867729.5890150070 0.0449367054 0.0403782806 0.0586646721 0.0042559081 0.0271810000 385848077 0 402718720 -0.0147575410 -0.0070628989 -0.0308146663 330 1311867729.6254830360 0.0470200405 0.0403984071 0.0586646721 0.0042497242 0.0274400000 385851257 0 402718720 -0.0122678876 -0.0059766951 -0.0317194648 331 1311867729.6614611149 0.0460987985 0.0404156289 0.0586646721 0.0042442175 0.0272650000 385854805 0 402718720 -0.0136214765 -0.0075850836 -0.0320451260 332 1311867729.6888220310 0.0466995053 0.0404345562 0.0586646721 0.0042379185 0.0278030000 385857809 0 402718720 -0.0128280865 -0.0076927594 -0.0320991799 333 1311867729.7230739594 0.0472494364 0.0404550213 0.0586646721 0.0042323632 0.0276200000 385861373 0 402718720 -0.0120076872 -0.0085590184 -0.0320163257 334 1311867729.7570610046 0.0444598496 0.0404670118 0.0586646721 0.0042361222 0.0410190000 385864521 0 402718720 -0.0153367613 -0.0097304536 -0.0321414061 335 1311867729.7899730206 0.0434329398 0.0404758653 0.0586646721 0.0042321592 0.0273970000 385868237 0 402718720 -0.0133255133 -0.0095439591 -0.0283100065 336 1311867729.8264250755 0.0457881317 0.0404916757 0.0586646721 0.0042275726 0.0276420000 385871297 0 402718720 -0.0114688119 -0.0082944389 -0.0306268819 337 1311867729.8550031185 0.0452065691 0.0405056664 0.0586646721 0.0042225809 0.0278940000 385874637 0 402718720 -0.0116276424 -0.0095617343 -0.0299455002 338 1311867729.8881840706 0.0452806018 0.0405197935 0.0586646721 0.0042177476 0.0278610000 385877865 0 402718720 -0.0121240858 -0.0091821887 -0.0308557190 339 1311867729.9233629704 0.0432094522 0.0405277276 0.0586646721 0.0042198894 0.0279520000 385881245 0 402718720 -0.0123529769 -0.0070613506 -0.0282972679 340 1311867729.9569330215 0.0462423712 0.0405445353 0.0586646721 0.0042259990 0.0280790000 385884689 0 402718720 -0.0108460728 -0.0103670154 -0.0308459215 341 1311867729.9865698814 0.0435771234 0.0405534286 0.0586646721 0.0042249361 0.0279220000 385887917 0 402718720 -0.0123426178 -0.0085532162 -0.0290102251 342 1311867730.0230469704 0.0428533778 0.0405601536 0.0586646721 0.0042201652 0.0286840000 385891289 0 402718720 -0.0114947604 -0.0081964126 -0.0272232816 343 1311867730.0557899475 0.0431598052 0.0405677327 0.0586646721 0.0042140547 0.0415820000 385894893 0 402718720 -0.0110734943 -0.0084366873 -0.0274090134 344 1311867730.0871100426 0.0435920916 0.0405765245 0.0586646721 0.0042086852 0.0287790000 385897689 0 402718720 -0.0116338618 -0.0076755187 -0.0291717034 345 1311867730.1231229305 0.0435658023 0.0405851890 0.0586646721 0.0042041928 0.0291580000 385901253 0 402718720 -0.0125411730 -0.0094433287 -0.0302380547 346 1311867730.1568520069 0.0443883911 0.0405961809 0.0586646721 0.0041986008 0.0289640000 385904489 0 402718720 -0.0105599407 -0.0099247731 -0.0289389994 347 1311867730.1882419586 0.0427049324 0.0406022580 0.0586646721 0.0041951881 0.0284280000 385907853 0 402718720 -0.0115329847 -0.0072348341 -0.0279767606 348 1311867730.2224810123 0.0439419337 0.0406118548 0.0586646721 0.0041905372 0.0595890000 385911353 0 402718720 -0.0097934948 -0.0076850802 -0.0274920221 349 1311867730.2575879097 0.0449920706 0.0406244056 0.0586646721 0.0041852943 0.0287450000 385914797 0 402718720 -0.0098212454 -0.0052312925 -0.0293962751 350 1311867730.2914879322 0.0407662280 0.0406248108 0.0586646721 0.0041913189 0.0285790000 385918225 0 402718720 -0.0128012942 -0.0076321689 -0.0259517357 351 1311867730.3230810165 0.0470273122 0.0406430515 0.0586646721 0.0042129884 0.0293200000 385921597 0 402718720 -0.0085731288 -0.0072119599 -0.0306577887 352 1311867730.3554260731 0.0431930944 0.0406502960 0.0586646721 0.0042117241 0.0369960000 385924953 0 402718720 -0.0110411104 -0.0067718308 -0.0276024044 353 1311867730.3982920647 0.0421980768 0.0406546806 0.0586646721 0.0042081096 0.0289870000 385928717 0 402718720 -0.0094176894 -0.0049752626 -0.0239107981 354 1311867730.4225230217 0.0462693796 0.0406705413 0.0586646721 0.0042070478 0.0293910000 385931777 0 402718720 -0.0082999403 -0.0055378280 -0.0291796252 355 1311867730.4600110054 0.0465585738 0.0406871273 0.0586646721 0.0042032823 0.0294800000 385935325 0 402718720 -0.0086029936 -0.0072829472 -0.0295808725 356 1311867730.4948410988 0.0415404961 0.0406895244 0.0586646721 0.0042070274 0.0291670000 385938577 0 402718720 -0.0111174583 -0.0069894562 -0.0246427022 357 1311867730.5300729275 0.0439482741 0.0406986526 0.0586646721 0.0042025135 0.0287010000 385941941 0 402718720 -0.0092965951 -0.0061695911 -0.0265387036 358 1311867730.5597670078 0.0424335636 0.0407034987 0.0586646721 0.0041992498 0.0287050000 385945449 0 402718720 -0.0099838739 -0.0050910059 -0.0250210483 359 1311867730.5940020084 0.0439514928 0.0407125461 0.0586646721 0.0041976312 0.0407720000 385948661 0 402718720 -0.0089686969 -0.0052533140 -0.0262806714 360 1311867730.6230149269 0.0431962423 0.0407194452 0.0586646721 0.0041958289 0.0295500000 385951753 0 402718720 -0.0084041022 -0.0043692710 -0.0245974436 361 1311867730.6614060402 0.0424046889 0.0407241135 0.0586646721 0.0041900597 0.0457380000 385955325 0 402718720 -0.0091453744 -0.0052829431 -0.0249061845 362 1311867730.6922950745 0.0426521972 0.0407294397 0.0586646721 0.0041843967 0.0295170000 385958345 0 402718720 -0.0080602719 -0.0049629286 -0.0243525729 363 1311867730.7275629044 0.0404131338 0.0407285683 0.0586646721 0.0041814944 0.0295370000 385962237 0 402718720 -0.0094544701 -0.0035595056 -0.0233252048 364 1311867730.7572948933 0.0422656871 0.0407327912 0.0586646721 0.0041778628 0.0296140000 385965441 0 402718720 -0.0081355693 -0.0041117347 -0.0252664462 365 1311867730.7932779789 0.0410212390 0.0407335814 0.0586646721 0.0041767499 0.0296250000 385968837 0 402718720 -0.0085539725 -0.0017496090 -0.0247799717 366 1311867730.8240480423 0.0423861481 0.0407380966 0.0586646721 0.0041792547 0.0300290000 385972305 0 402718720 -0.0072082356 -0.0052254098 -0.0253430083 367 1311867730.8591129780 0.0433578715 0.0407452350 0.0586646721 0.0041738271 0.0394910000 385975293 0 402718720 -0.0065567233 -0.0031761490 -0.0268679820 368 1311867730.8922739029 0.0419585854 0.0407485321 0.0586646721 0.0041690213 0.0295940000 385978665 0 402718720 -0.0070882812 -0.0036770082 -0.0255068410 369 1311867730.9270720482 0.0405000485 0.0407478587 0.0586646721 0.0041859030 0.0380290000 385981941 0 402718720 -0.0065090777 -0.0001425326 -0.0234518945 370 1311867730.9611239433 0.0442369655 0.0407572888 0.0586646721 0.0041911369 0.0296910000 385985425 0 402718720 -0.0041921893 -0.0015938029 -0.0268983115 371 1311867730.9928169250 0.0404366404 0.0407564245 0.0586646721 0.0041922112 0.0296320000 385988397 0 402718720 -0.0044706455 0.0000620960 -0.0218507946 372 1311867731.0221049786 0.0386742391 0.0407508272 0.0586646721 0.0041875715 0.0295910000 385991953 0 402718720 -0.0049805194 -0.0000277677 -0.0202078428 373 1311867731.0609729290 0.0414573774 0.0407527214 0.0586646721 0.0041919880 0.0294920000 385994997 0 402718720 -0.0031281905 -0.0013123968 -0.0229449719 374 1311867731.0900061131 0.0372003801 0.0407432232 0.0586646721 0.0041939235 0.0298460000 385998337 0 402718720 -0.0050163018 -0.0012043815 -0.0189520605 375 1311867731.1276559830 0.0381862149 0.0407364045 0.0586646721 0.0041935884 0.0297560000 386002117 0 402718720 -0.0053554280 -0.0027990283 -0.0210433584 376 1311867731.1551880836 0.0385270007 0.0407305284 0.0586646721 0.0041933595 0.0398930000 386005057 0 402718720 -0.0032460559 0.0000988565 -0.0195910856 377 1311867731.1935870647 0.0391635559 0.0407263720 0.0586646721 0.0041896978 0.0299650000 386008589 0 402718720 -0.0014970480 -0.0001083517 -0.0184921622 378 1311867731.2235820293 0.0410191566 0.0407271466 0.0586646721 0.0041856624 0.0391550000 386011977 0 402718720 -0.0011835936 -0.0006658351 -0.0215140972 379 1311867731.2602028847 0.0392767824 0.0407233198 0.0586646721 0.0041840184 0.0302170000 386015181 0 402718720 -0.0011696802 -0.0019129260 -0.0192340463 380 1311867731.2900059223 0.0351214036 0.0407085779 0.0586646721 0.0042375726 0.0303130000 386018625 0 402718720 -0.0034807366 -0.0022191033 -0.0178366229 381 1311867731.3230779171 0.0365219489 0.0406975893 0.0586646721 0.0042541799 0.0300680000 386021989 0 402718720 0.0002791286 -0.0003151352 -0.0153521560 382 1311867731.3570859432 0.0365165472 0.0406866442 0.0586646721 0.0042500438 0.0306900000 386025169 0 402718720 -0.0000372739 0.0010828712 -0.0172441527 383 1311867731.3915760517 0.0384655483 0.0406808450 0.0586646721 0.0042596111 0.0302200000 386028765 0 402718720 0.0021406389 -0.0021790250 -0.0184069499 384 1311867731.4279849529 0.0362266265 0.0406692455 0.0586646721 0.0042628731 0.0299480000 386032529 0 402718720 0.0012798267 -0.0008679145 -0.0173002817 385 1311867731.4602010250 0.0354713202 0.0406557444 0.0586646721 0.0042597839 0.0387230000 386036253 0 402718720 -0.0002543782 -0.0025990801 -0.0189524833 386 1311867731.4926180840 0.0310908202 0.0406309648 0.0586646721 0.0042697766 0.0303050000 386039417 0 402718720 -0.0022413833 -0.0015613331 -0.0157264993 387 1311867731.5259540081 0.0347385556 0.0406157389 0.0586646721 0.0042683602 0.0382570000 386042645 0 402718720 0.0011370359 -0.0009814713 -0.0188108869 388 1311867731.5589148998 0.0362436771 0.0406044707 0.0586646721 0.0042649311 0.0303900000 386046257 0 402718720 0.0022099996 0.0017791216 -0.0210566744 389 1311867731.5967359543 0.0360910259 0.0405928680 0.0586646721 0.0042863944 0.0304800000 386049869 0 402718720 0.0027573640 -0.0008850978 -0.0198734924 390 1311867731.6247410774 0.0373022258 0.0405844305 0.0586646721 0.0042868918 0.0306950000 386052801 0 402718720 0.0029097693 -0.0002364845 -0.0225462578 391 1311867731.6616659164 0.0368126966 0.0405747841 0.0586646721 0.0042968104 0.0307880000 386056309 0 402718720 0.0016014967 -0.0030408869 -0.0235190131 392 1311867731.6925039291 0.0382759720 0.0405689198 0.0586646721 0.0043016266 0.0306270000 386059161 0 402718720 0.0022853529 -0.0026448704 -0.0246818867 393 1311867731.7299311161 0.0344333574 0.0405533077 0.0586646721 0.0042998044 0.0308250000 386062653 0 402718720 0.0019888822 -0.0025903054 -0.0198803507 394 1311867731.7615330219 0.0363109931 0.0405425404 0.0586646721 0.0042976005 0.0306800000 386065817 0 402718720 0.0024897563 -0.0036708205 -0.0224509202 395 1311867731.7939310074 0.0330971405 0.0405236913 0.0586646721 0.0042961327 0.0307030000 386069205 0 402718720 0.0012843008 -0.0025298358 -0.0199925844 396 1311867731.8252151012 0.0364508890 0.0405134064 0.0586646721 0.0043094572 0.0377160000 386072377 0 402718720 0.0037603811 -0.0033759091 -0.0228349715 397 1311867731.8593230247 0.0373424701 0.0405054192 0.0586646721 0.0043172728 0.0309030000 386075853 0 402718720 0.0040791221 -0.0041332436 -0.0252796765 398 1311867731.8910930157 0.0345028266 0.0404903373 0.0586646721 0.0043164937 0.0309820000 386079313 0 402718720 0.0038486086 -0.0065092668 -0.0214552879 399 1311867731.9224479198 0.0331315324 0.0404718942 0.0586646721 0.0043154134 0.0310420000 386082365 0 402718720 0.0033453703 -0.0045949351 -0.0213485658 400 1311867731.9598410130 0.0350400060 0.0404583144 0.0586646721 0.0043176856 0.0306730000 386085937 0 402718720 0.0054471297 -0.0061702738 -0.0229848847 401 1311867731.9915709496 0.0384426787 0.0404532879 0.0586646721 0.0043170582 0.0305690000 386089085 0 402718720 0.0072442391 -0.0068232762 -0.0267937202 402 1311867732.0239229202 0.0350243524 0.0404397831 0.0586646721 0.0043161748 0.0313430000 386092313 0 402718720 0.0052730269 -0.0063194097 -0.0249273404 403 1311867732.0619950294 0.0340205543 0.0404238545 0.0586646721 0.0043138461 0.0418670000 386096125 0 402718720 0.0051538567 -0.0051406333 -0.0251265168 404 1311867732.0918290615 0.0371977948 0.0404158692 0.0586646721 0.0043216504 0.0311650000 386098961 0 402718720 0.0080896253 -0.0071123890 -0.0277067013 405 1311867732.1221950054 0.0354803354 0.0404036827 0.0586646721 0.0043179590 0.0314980000 386102621 0 402718720 0.0061907191 -0.0082063256 -0.0276689585 406 1311867732.1605980396 0.0403880738 0.0404036442 0.0586646721 0.0043275998 0.0315800000 386105769 0 402718720 0.0084648691 -0.0108292187 -0.0326835103 407 1311867732.1931400299 0.0369132794 0.0403950684 0.0586646721 0.0043710300 0.0316270000 386108941 0 402718720 0.0058869533 -0.0058249482 -0.0325697251 408 1311867732.2232089043 0.0385077782 0.0403904427 0.0586646721 0.0044155864 0.0312510000 386112121 0 402718720 0.0103598060 -0.0072186952 -0.0306454189 409 1311867732.2590498924 0.0372008942 0.0403826443 0.0586646721 0.0045001639 0.0315550000 386115301 0 402718720 0.0088533377 -0.0062232013 -0.0324068926 410 1311867732.2903969288 0.0388200246 0.0403788330 0.0586646721 0.0045392796 0.0313600000 386118849 0 402718720 0.0095505556 -0.0064630429 -0.0337459445 411 1311867732.3218240738 0.0379975475 0.0403730391 0.0586646721 0.0045380383 0.0314240000 386121869 0 402718720 0.0100133233 -0.0080672279 -0.0330258906 412 1311867732.3607840538 0.0384474620 0.0403683654 0.0586646721 0.0045342873 0.0314990000 386125073 0 402718720 0.0108610541 -0.0072353962 -0.0344052799 413 1311867732.3899528980 0.0377235599 0.0403619615 0.0586646721 0.0045354183 0.0312390000 386128493 0 402718720 0.0090357345 -0.0055146245 -0.0359538756 414 1311867732.4218940735 0.0375100672 0.0403550729 0.0586646721 0.0045535950 0.0314080000 386131969 0 402718720 0.0097874086 -0.0081011606 -0.0361561030 415 1311867732.4593050480 0.0405009836 0.0403554245 0.0586646721 0.0045606227 0.0314080000 386135229 0 402718720 0.0116456328 -0.0095167328 -0.0390513204 416 1311867732.4918489456 0.0402989946 0.0403552888 0.0586646721 0.0045576704 0.0310720000 386138705 0 402718720 0.0128571521 -0.0064275991 -0.0392862149 417 1311867732.5229809284 0.0356827751 0.0403440838 0.0586646721 0.0045589441 0.0311760000 386141813 0 402718720 0.0112942131 -0.0058266018 -0.0356881209 418 1311867732.5698928833 0.0369661115 0.0403360025 0.0586646721 0.0045555248 0.0311860000 386145225 0 402718720 0.0099399108 -0.0067727948 -0.0389181674 419 1311867732.5926280022 0.0402516723 0.0403358012 0.0586646721 0.0045585311 0.0318060000 386148229 0 402718720 0.0128363278 -0.0070040622 -0.0412537791 420 1311867732.6242370605 0.0394871235 0.0403337806 0.0586646721 0.0045587191 0.0314810000 386151601 0 402718720 0.0149213243 -0.0077285124 -0.0392068550 421 1311867732.6630299091 0.0402131118 0.0403334939 0.0586646721 0.0045639498 0.0316330000 386154869 0 402718720 0.0157213882 -0.0088785263 -0.0399058908 422 1311867732.6922440529 0.0396125391 0.0403317855 0.0586646721 0.0045644913 0.0314610000 386158233 0 402718720 0.0122269262 -0.0064587849 -0.0417002402 423 1311867732.7260940075 0.0394286066 0.0403296503 0.0586646721 0.0045610738 0.0314970000 386161421 0 402718720 0.0140554337 -0.0081416145 -0.0406960547 424 1311867732.7601239681 0.0346243717 0.0403161945 0.0586646721 0.0045707916 0.0312000000 386164425 0 402718720 0.0123226456 -0.0070946314 -0.0365391299 425 1311867732.7919039726 0.0418993682 0.0403199196 0.0586646721 0.0045972752 0.0310170000 386168077 0 402718720 0.0168180801 -0.0102125350 -0.0423110761 426 1311867732.8280360699 0.0379321165 0.0403143144 0.0586646721 0.0046071834 0.0309230000 386171201 0 402718720 0.0147218136 -0.0067192856 -0.0397248305 427 1311867732.8589270115 0.0370606482 0.0403066946 0.0586646721 0.0046039263 0.0308530000 386174589 0 402718720 0.0141508449 -0.0067963516 -0.0392091088 428 1311867732.8912909031 0.0381979384 0.0403017676 0.0586646721 0.0045987203 0.0312400000 386177609 0 402718720 0.0144276004 -0.0063754115 -0.0403995216 429 1311867732.9262781143 0.0363151245 0.0402924747 0.0586646721 0.0045944831 0.0311100000 386181061 0 402718720 0.0135996807 -0.0066879285 -0.0385367870 430 1311867732.9602870941 0.0348668396 0.0402798570 0.0586646721 0.0045932396 0.0397590000 386184209 0 402718720 0.0142279491 -0.0077137360 -0.0360016301 431 1311867732.9987640381 0.0381143764 0.0402748327 0.0586646721 0.0045894655 0.0312900000 386188061 0 402718720 0.0139602870 -0.0080130063 -0.0397802740 432 1311867733.0276939869 0.0360135324 0.0402649685 0.0586646721 0.0045915053 0.0320150000 386191105 0 402718720 0.0124921678 -0.0061016306 -0.0381355435 433 1311867733.0607628822 0.0307493173 0.0402429924 0.0586646721 0.0045954260 0.0319180000 386194493 0 402718720 0.0109354053 -0.0070752800 -0.0328776948 434 1311867733.0977020264 0.0325721838 0.0402253178 0.0586646721 0.0045919104 0.0315490000 386197529 0 402718720 0.0110728880 -0.0063831336 -0.0349298269 435 1311867733.1263020039 0.0389969274 0.0402224939 0.0586646721 0.0046023232 0.0319940000 386200805 0 402718720 0.0168237742 -0.0058365311 -0.0388624407 436 1311867733.1625030041 0.0327156521 0.0402052764 0.0586646721 0.0046032603 0.0312540000 386204353 0 402718720 0.0121709500 -0.0080571836 -0.0344015881 437 1311867733.1926651001 0.0300928410 0.0401821358 0.0586646721 0.0046136124 0.0310540000 386207669 0 402718720 0.0082958601 -0.0067915916 -0.0336934812 438 1311867733.2259631157 0.0381932743 0.0401775950 0.0586646721 0.0046236028 0.0309380000 386210873 0 402718720 0.0144726094 -0.0069272639 -0.0397105142 439 1311867733.2618060112 0.0328827724 0.0401609781 0.0586646721 0.0046267657 0.0408390000 386214389 0 402718720 0.0105986856 -0.0056566186 -0.0358453467 440 1311867733.2919199467 0.0329960473 0.0401446941 0.0586646721 0.0046237543 0.0357730000 386901453 0 402718720 0.0100024212 -0.0071832733 -0.0360090062 441 1311867733.3300418854 0.0363742560 0.0401361444 0.0586646721 0.0046403038 0.1076490000 386882765 0 402718720 0.0129518351 -0.0075087361 -0.0382061005 442 1311867733.3602790833 0.0336467847 0.0401214626 0.0586646721 0.0046383961 0.0965150000 386887281 0 402718720 0.0136520490 -0.0076605901 -0.0350154564 443 1311867733.3923840523 0.0338322781 0.0401072658 0.0586646721 0.0046361182 0.0918130000 388441225 0 402718720 0.0115822982 -0.0071648094 -0.0368065983 444 1311867733.4289550781 0.0304653123 0.0400855497 0.0586646721 0.0046461418 0.0670460000 393416377 0 402718720 0.0104603749 -0.0048276642 -0.0341873989 445 1311867733.4588150978 0.0297618210 0.0400623503 0.0586646721 0.0046410142 0.0541990000 393292433 0 402718720 0.0104184300 -0.0052180183 -0.0335340239 446 1311867733.4956119061 0.0258404538 0.0400304626 0.0586646721 0.0046454292 0.0926170000 391673173 0 402718720 0.0076264902 -0.0057140454 -0.0305633284 447 1311867733.5290400982 0.0257638264 0.0399985462 0.0586646721 0.0046463971 0.0353040000 386901429 0 402718720 0.0106139928 -0.0049277255 -0.0289145391 448 1311867733.5630290508 0.0273722578 0.0399703625 0.0586646721 0.0046423793 0.0359190000 386904857 0 402718720 0.0100007411 -0.0049109920 -0.0311792754 449 1311867733.5922229290 0.0242255274 0.0399352961 0.0586646721 0.0046427852 0.0357650000 386908005 0 402718720 0.0095457099 -0.0054839849 -0.0281563867 450 1311867733.6283020973 0.0267228615 0.0399059351 0.0586646721 0.0046450745 0.0352740000 386911233 0 402718720 0.0113896187 -0.0055008726 -0.0300555006 451 1311867733.6601879597 0.0244528446 0.0398716711 0.0586646721 0.0046512705 0.0354050000 386914477 0 402718720 0.0099044014 -0.0018487704 -0.0280744229 452 1311867733.6917510033 0.0215488300 0.0398311338 0.0586646721 0.0046463384 0.0346950000 386917737 0 402718720 0.0088237980 -0.0049032741 -0.0255188067 453 1311867733.7288239002 0.0248891264 0.0397981492 0.0586646721 0.0046495973 0.0349230000 386921125 0 402718720 0.0109926285 -0.0069649634 -0.0282618012 454 1311867733.7597820759 0.0229689069 0.0397610804 0.0586646721 0.0046527390 0.0350970000 386924209 0 402718720 0.0095153917 -0.0032619145 -0.0268006884 455 1311867733.7924160957 0.0226797760 0.0397235391 0.0586646721 0.0046811102 0.0349900000 386927357 0 402718720 0.0094558392 -0.0059430394 -0.0259804856 456 1311867733.8282589912 0.0194145422 0.0396790018 0.0586646721 0.0046813106 0.0349370000 386930857 0 402718720 0.0103509277 -0.0071545518 -0.0231120810 457 1311867733.8608579636 0.0212157909 0.0396386009 0.0586646721 0.0046775766 0.0477380000 386933605 0 402718720 0.0120590515 -0.0053092148 -0.0245800056 458 1311867733.8918149471 0.0209110547 0.0395977111 0.0586646721 0.0046728694 0.0345510000 386936993 0 402718720 0.0123574594 -0.0055501154 -0.0245442614 459 1311867733.9289460182 0.0194677487 0.0395538550 0.0586646721 0.0046687079 0.0338150000 386940221 0 402718720 0.0134418812 -0.0073665045 -0.0229585655 460 1311867733.9595899582 0.0193905309 0.0395100216 0.0586646721 0.0046743188 0.0336610000 386943641 0 402718720 0.0115846079 -0.0066044498 -0.0239213333 461 1311867733.9941790104 0.0168399233 0.0394608457 0.0586646721 0.0046841663 0.0344880000 386946989 0 402718720 0.0129105868 -0.0055271634 -0.0210511386 462 1311867734.0275731087 0.0136298854 0.0394049346 0.0586646721 0.0046809531 0.0340100000 386950041 0 402718720 0.0111181289 -0.0058573023 -0.0182031598 463 1311867734.0599920750 0.0150295338 0.0393522879 0.0586646721 0.0046766365 0.0443750000 386953277 0 402718720 0.0131275207 -0.0064750533 -0.0193048511 464 1311867734.0956780910 0.0166401491 0.0393033393 0.0586646721 0.0046737962 0.0338400000 386956441 0 402718720 0.0145973219 -0.0073535750 -0.0208839569 465 1311867734.1274170876 0.0141771110 0.0392493044 0.0586646721 0.0046689327 0.0341120000 386960189 0 402718720 0.0133044906 -0.0103672817 -0.0193736609 466 1311867734.1618878841 0.0155557962 0.0391984600 0.0586646721 0.0046656567 0.0344130000 386963289 0 402718720 0.0158607960 -0.0091887685 -0.0201523397 467 1311867734.1942350864 0.0139089329 0.0391443068 0.0586646721 0.0046677353 0.0344750000 386966413 0 402718720 0.0140514709 -0.0066624256 -0.0194150507 468 1311867734.2291829586 0.0140420832 0.0390906696 0.0586646721 0.0046703927 0.0341680000 386969577 0 402718720 0.0150874676 -0.0081372093 -0.0196755975 469 1311867734.2607750893 0.0116859116 0.0390322373 0.0586646721 0.0046679628 0.0348750000 386972837 0 402718720 0.0130200647 -0.0091718901 -0.0181593914 470 1311867734.2941219807 0.0135099897 0.0389779346 0.0586646721 0.0046637300 0.0347320000 386975825 0 402718720 0.0136667322 -0.0091623403 -0.0197218563 471 1311867734.3263280392 0.0128509030 0.0389224632 0.0586646721 0.0046624091 0.0540330000 386979229 0 402718720 0.0155320195 -0.0102185644 -0.0183846336 472 1311867734.3610401154 0.0117724193 0.0388649419 0.0586646721 0.0046665654 0.0347300000 386982641 0 402718720 0.0141819566 -0.0092171803 -0.0178395398 473 1311867734.3941841125 0.0126524884 0.0388095245 0.0586646721 0.0046674944 0.0346060000 386985973 0 402718720 0.0143384617 -0.0085425479 -0.0185917541 474 1311867734.4276480675 0.0110466778 0.0387509531 0.0586646721 0.0046626856 0.0346310000 386989193 0 402718720 0.0130762644 -0.0100906771 -0.0174272247 475 1311867734.4586091042 0.0108787771 0.0386922748 0.0586646721 0.0046605937 0.0360410000 386992637 0 402718720 0.0129253631 -0.0115506845 -0.0170867965 476 1311867734.4938759804 0.0106923413 0.0386334514 0.0586646721 0.0046582540 0.0352130000 386996185 0 402718720 0.0148188919 -0.0086021004 -0.0157627556 477 1311867734.5300569534 0.0104318894 0.0385743287 0.0586646721 0.0046540880 0.0443540000 386999141 0 402718720 0.0134990662 -0.0087435395 -0.0157959070 478 1311867734.5595300198 0.0090464652 0.0385125549 0.0586646721 0.0046579841 0.0354710000 387002321 0 402718720 0.0139096370 -0.0104467506 -0.0146900238 479 1311867734.5953910351 0.0110164825 0.0384551518 0.0586646721 0.0046541953 0.0467030000 387005573 0 402718720 0.0128741218 -0.0107368920 -0.0165705103 480 1311867734.6285231113 0.0093130097 0.0383944390 0.0586646721 0.0046507424 0.0353930000 387008905 0 402718720 0.0140710315 -0.0107195005 -0.0147987744 481 1311867734.6593229771 0.0095803402 0.0383345344 0.0586646721 0.0046463353 0.0346490000 387011885 0 402718720 0.0127749201 -0.0107859308 -0.0153338211 482 1311867734.6947479248 0.0091527794 0.0382739914 0.0586646721 0.0046435681 0.0346640000 387015345 0 402718720 0.0106375692 -0.0101810033 -0.0145833995 483 1311867734.7310240269 0.0096059274 0.0382146372 0.0586646721 0.0046479379 0.0343040000 387018629 0 402718720 0.0142394081 -0.0099009834 -0.0149793010 484 1311867734.7607629299 0.0106555233 0.0381576969 0.0586646721 0.0046519787 0.0346840000 387021809 0 402718720 0.0151733030 -0.0143595366 -0.0161658172 485 1311867734.7976419926 0.0103599317 0.0381003819 0.0586646721 0.0046489955 0.0346940000 387025365 0 402718720 0.0151563678 -0.0134875774 -0.0158233717 486 1311867734.8298120499 0.0107300365 0.0380440643 0.0586646721 0.0046467839 0.0435820000 387028513 0 402718720 0.0152259637 -0.0120231062 -0.0160318948 487 1311867734.8645250797 0.0090443231 0.0379845166 0.0586646721 0.0046432731 0.0462110000 387031813 0 402718720 0.0159061681 -0.0105608739 -0.0137546025 488 1311867734.8943901062 0.0085991621 0.0379243007 0.0586646721 0.0046402647 0.0360640000 387034993 0 402718720 0.0164776519 -0.0120778568 -0.0133864824 489 1311867734.9263660908 0.0090901963 0.0378653353 0.0586646721 0.0046356426 0.0351320000 387038037 0 402718720 0.0161144082 -0.0130345998 -0.0141476262 490 1311867734.9631719589 0.0079782112 0.0378043411 0.0586646721 0.0046337610 0.0347260000 387041169 0 402718720 0.0160671622 -0.0130630201 -0.0135381045 491 1311867734.9948470592 0.0081073390 0.0377438584 0.0586646721 0.0046370834 0.0349420000 387044381 0 402718720 0.0148719698 -0.0130039845 -0.0137749556 492 1311867735.0292239189 0.0083618565 0.0376841389 0.0586646721 0.0046395638 0.0349800000 387047873 0 402718720 0.0167477634 -0.0139411362 -0.0139961783 493 1311867735.0596508980 0.0091985473 0.0376263588 0.0586646721 0.0046352202 0.0460660000 387050773 0 402718720 0.0172314364 -0.0127800703 -0.0146306539 494 1311867735.0952830315 0.0078183198 0.0375660187 0.0586646721 0.0046325828 0.0353250000 387054289 0 402718720 0.0173007492 -0.0146441543 -0.0132083185 495 1311867735.1313030720 0.0077403132 0.0375057647 0.0586646721 0.0046304969 0.0492770000 387057773 0 402718720 0.0158128515 -0.0145172020 -0.0134324841 496 1311867735.1603751183 0.0077053877 0.0374456833 0.0586646721 0.0046259739 0.0358980000 387060585 0 402718720 0.0154585298 -0.0139497817 -0.0134929474 497 1311867735.1994349957 0.0075809844 0.0373855934 0.0586646721 0.0046246432 0.0352150000 387063741 0 402718720 0.0147421723 -0.0151423682 -0.0132717695 498 1311867735.2263538837 0.0086940825 0.0373279799 0.0586646721 0.0046212117 0.0348760000 387067073 0 402718720 0.0163712297 -0.0164212044 -0.0136914775 499 1311867735.2655019760 0.0078354618 0.0372688766 0.0586646721 0.0046196690 0.0471770000 387070621 0 402718720 0.0159007721 -0.0137080699 -0.0127387028 500 1311867735.2961549759 0.0073334198 0.0372090057 0.0586646721 0.0046203166 0.0352090000 387073881 0 402718720 0.0150547884 -0.0159187242 -0.0118873138 501 1311867735.3321089745 0.0077186855 0.0371501428 0.0586646721 0.0046179268 0.0411690000 387076901 0 402718720 0.0166793931 -0.0134846726 -0.0118435351 502 1311867735.3666970730 0.0070549240 0.0370901922 0.0586646721 0.0046234203 0.0349610000 387080457 0 402718720 0.0175964255 -0.0148555376 -0.0111090885 503 1311867735.3943350315 0.0080592884 0.0370324767 0.0586646721 0.0046320901 0.0344550000 387083597 0 402718720 0.0187482554 -0.0145708472 -0.0122063160 504 1311867735.4322299957 0.0077555785 0.0369743876 0.0586646721 0.0046361445 0.0337570000 387086857 0 402718720 0.0166251920 -0.0142802037 -0.0122784534 505 1311867735.4628560543 0.0065603252 0.0369141617 0.0586646721 0.0046415499 0.0343280000 387090301 0 402718720 0.0164241120 -0.0151206236 -0.0109095098 506 1311867735.4973869324 0.0057563917 0.0368525851 0.0586646721 0.0046463034 0.0398340000 387756633 0 402718720 0.0166848768 -0.0155078033 -0.0095860679 507 1311867735.5293200016 0.0069403229 0.0367935866 0.0586646721 0.0046431154 0.1129720000 387719409 0 402718720 0.0160944145 -0.0159485713 -0.0103910100 508 1311867735.5632629395 0.0052817417 0.0367315554 0.0586646721 0.0046389535 0.1026740000 387722589 0 402718720 0.0177431833 -0.0156986974 -0.0086715808 509 1311867735.5976569653 0.0054484825 0.0366700955 0.0586646721 0.0046352317 0.0973930000 389593845 0 402718720 0.0157993808 -0.0160044432 -0.0086989496 510 1311867735.6363260746 0.0048437053 0.0366076908 0.0586646721 0.0046349002 0.0784610000 393650117 0 402718720 0.0186311230 -0.0155383889 -0.0086386716 511 1311867735.6626520157 0.0047900514 0.0365454254 0.0586646721 0.0046319141 0.0405350000 394451561 0 402718720 0.0191210601 -0.0175566394 -0.0081176832 512 1311867735.6952130795 0.0053137979 0.0364844261 0.0586646721 0.0046278933 0.0983530000 392834269 0 402718720 0.0186761282 -0.0189839173 -0.0085331565 513 1311867735.7291250229 0.0052535813 0.0364235473 0.0586646721 0.0046324342 0.0373540000 387787745 0 402718720 0.0171905421 -0.0178453047 -0.0096191820 514 1311867735.7631659508 0.0036427227 0.0363597713 0.0586646721 0.0046325787 0.0379540000 387893629 0 402718720 0.0171014145 -0.0165564623 -0.0086174821 515 1311867735.7963778973 0.0047093891 0.0362983143 0.0586646721 0.0046321466 0.0364620000 387897017 0 402718720 0.0163547210 -0.0182045475 -0.0086827837 516 1311867735.8277759552 0.0037329113 0.0362352030 0.0586646721 0.0046364132 0.0358300000 387899965 0 402718720 0.0174291227 -0.0155153647 -0.0091376035 517 1311867735.8638889790 0.0025059006 0.0361699626 0.0586646721 0.0046324640 0.0475930000 387902641 0 402718720 0.0186173078 -0.0151146241 -0.0079136407 518 1311867735.8951849937 0.0044752974 0.0361087760 0.0586646721 0.0046295487 0.0370350000 387906253 0 402718720 0.0188896563 -0.0167215671 -0.0089169424 519 1311867735.9322230816 0.0030686774 0.0360451149 0.0586646721 0.0046306051 0.0444150000 387909665 0 402718720 0.0183850918 -0.0136482399 -0.0076866997 520 1311867735.9623689651 0.0042224289 0.0359839174 0.0586646721 0.0046318766 0.0381450000 387913093 0 402718720 0.0174508840 -0.0150655732 -0.0082363030 521 1311867735.9945859909 0.0038059100 0.0359221554 0.0586646721 0.0046306283 0.0363450000 387915993 0 402718720 0.0179284494 -0.0151987467 -0.0074651679 522 1311867736.0290079117 0.0037571501 0.0358605366 0.0586646721 0.0046284169 0.0362150000 387919397 0 402718720 0.0189077128 -0.0161079876 -0.0064927661 523 1311867736.0642199516 0.0030632280 0.0357978267 0.0586646721 0.0046244582 0.0359160000 387922961 0 402718720 0.0178921856 -0.0153390402 -0.0061588543 524 1311867736.0946779251 0.0010678716 0.0357315482 0.0586646721 0.0046225636 0.0356520000 387925917 0 402718720 0.0181450211 -0.0148628233 -0.0039202999 525 1311867736.1299190521 0.0027271120 0.0356686826 0.0586646721 0.0046361304 0.0345870000 387929353 0 402718720 0.0187107753 -0.0158409495 -0.0049490188 526 1311867736.1631360054 0.0027740295 0.0356061452 0.0586646721 0.0046342002 0.0436340000 387932581 0 402718720 0.0189112946 -0.0164856315 -0.0037120578 527 1311867736.1942429543 0.0015078443 0.0355414425 0.0586646721 0.0046395176 0.0474280000 387935649 0 402718720 0.0174024235 -0.0154391043 -0.0040351464 528 1311867736.2298679352 0.0013078731 0.0354766062 0.0586646721 0.0046405761 0.0386900000 388502185 0 402718720 0.0159790646 -0.0152823916 -0.0025721753 529 1311867736.2633900642 0.0020649165 0.0354134461 0.0586646721 0.0046487150 0.1131660000 388585225 0 402718720 0.0180845466 -0.0158866514 -0.0032154778 530 1311867736.2995250225 0.0033592898 0.0353529666 0.0586646721 0.0046471052 0.1011170000 388587997 0 402718720 0.0177515838 -0.0176799633 -0.0027339477 531 1311867736.3304500580 0.0014122790 0.0352890482 0.0586646721 0.0046468424 0.0972330000 388608833 0 402718720 0.0157533810 -0.0159446374 -0.0037870719 532 1311867736.3637149334 0.0028345175 0.0352280434 0.0586646721 0.0046427905 0.0845740000 395921757 0 402718720 0.0176341999 -0.0163933914 -0.0017671498 533 1311867736.3943159580 0.0034753333 0.0351684698 0.0586646721 0.0046391264 0.0576540000 395844125 0 402718720 0.0159762595 -0.0179543644 -0.0020735830 534 1311867736.4313519001 0.0018359019 0.0351060493 0.0586646721 0.0046524591 0.1014220000 394431833 0 402718720 0.0168858431 -0.0161085837 -0.0030915933 535 1311867736.4625089169 0.0032787903 0.0350465591 0.0586646721 0.0046522111 0.0371440000 388552993 0 402718720 0.0168881528 -0.0178919323 -0.0028814720 536 1311867736.4987530708 0.0041490840 0.0349889146 0.0586646721 0.0046487281 0.0370570000 388556501 0 402718720 0.0167071745 -0.0190122481 -0.0025551408 537 1311867736.5321619511 0.0016411173 0.0349268144 0.0586646721 0.0046549837 0.0363110000 388559753 0 402718720 0.0159225874 -0.0169250686 -0.0039306488 538 1311867736.5634689331 0.0033285080 0.0348680815 0.0586646721 0.0046518102 0.0359230000 388563029 0 402718720 0.0167858470 -0.0156952236 -0.0016426590 539 1311867736.5958600044 0.0035528874 0.0348099828 0.0586646721 0.0046505715 0.0358670000 388566273 0 402718720 0.0160780065 -0.0171653368 -0.0018892597 540 1311867736.6320459843 0.0037330939 0.0347524330 0.0586646721 0.0046604876 0.0360630000 388569549 0 402718720 0.0149741974 -0.0186675694 -0.0028892874 541 1311867736.6635379791 0.0035205064 0.0346947030 0.0586646721 0.0046694558 0.0359960000 388572889 0 402718720 0.0156504363 -0.0180254672 -0.0020404584 542 1311867736.6945500374 0.0054312209 0.0346407113 0.0586646721 0.0046834304 0.0356630000 388576005 0 402718720 0.0165685005 -0.0218652152 -0.0028935054 543 1311867736.7332150936 0.0042485544 0.0345847405 0.0586646721 0.0046867018 0.0483520000 388579321 0 402718720 0.0142154191 -0.0199950188 -0.0028105462 544 1311867736.7636179924 0.0028374626 0.0345263815 0.0586646721 0.0046861218 0.0355050000 388582453 0 402718720 0.0143394722 -0.0196248163 -0.0057443529 545 1311867736.7952749729 0.0024559714 0.0344675367 0.0586646721 0.0046963710 0.0346060000 388585849 0 402718720 0.0159455054 -0.0204488244 -0.0053988085 546 1311867736.8325269222 0.0028361087 0.0344096037 0.0586646721 0.0047038175 0.0343050000 388589125 0 402718720 0.0143179148 -0.0180989634 -0.0052250884 547 1311867736.8640279770 0.0020480466 0.0343504418 0.0586646721 0.0047018444 0.0339310000 388592473 0 402718720 0.0150508564 -0.0177584775 -0.0080732917 548 1311867736.8945000172 0.0006130309 0.0342888772 0.0586646721 0.0047003459 0.0336560000 388595749 0 402718720 0.0164930783 -0.0184989292 -0.0070465803 549 1311867736.9362800121 0.0027914527 0.0342315049 0.0586646721 0.0047029655 0.0430810000 388599001 0 402718720 0.0161888637 -0.0200137999 -0.0056358441 550 1311867736.9632000923 0.0029618670 0.0341746510 0.0586646721 0.0047048791 0.0418420000 388602357 0 402718720 0.0146877151 -0.0167490821 -0.0066179791 551 1311867736.9954400063 0.0012765205 0.0341149447 0.0586646721 0.0047073768 0.0499160000 389309309 0 402718720 0.0166826174 -0.0181078110 -0.0061827600 552 1311867737.0307478905 0.0047880481 0.0340618163 0.0586646721 0.0047036302 0.1169480000 389266841 0 402718720 0.0144447647 -0.0208716653 -0.0049664639 553 1311867737.0629029274 0.0029789906 0.0340056087 0.0586646721 0.0046997818 0.1032330000 389271117 0 402718720 0.0150824953 -0.0186935756 -0.0059855226 554 1311867737.0977239609 0.0036070468 0.0339507376 0.0586646721 0.0046967632 0.0933530000 391987397 0 402718720 0.0148332808 -0.0195406545 -0.0058087157 555 1311867737.1300530434 0.0042550103 0.0338972318 0.0586646721 0.0046945680 0.0741770000 396557117 0 402718720 0.0152118234 -0.0188917648 -0.0040814313 556 1311867737.1655049324 0.0033434394 0.0338422789 0.0586646721 0.0046903501 0.0588310000 396335761 0 402718720 0.0154969385 -0.0182455610 -0.0051336014 557 1311867737.1952710152 0.0060407212 0.0337923659 0.0586646721 0.0046888272 0.0998000000 394770797 0 402718720 0.0144374762 -0.0186147671 -0.0027514771 558 1311867737.2333149910 0.0058587752 0.0337423057 0.0586646721 0.0046853100 0.0354570000 389242377 0 402718720 0.0142166205 -0.0192633215 -0.0036322274 559 1311867737.2693018913 0.0048427489 0.0336906070 0.0586646721 0.0046849800 0.0358560000 389245709 0 402718720 0.0153964087 -0.0178487077 -0.0040268940 560 1311867737.2957379818 0.0060102940 0.0336411779 0.0586646721 0.0046817963 0.0356570000 389248529 0 402718720 0.0136692664 -0.0183824841 -0.0047101364 561 1311867737.3316531181 0.0065962202 0.0335929694 0.0586646721 0.0046776672 0.0350670000 389252213 0 402718720 0.0133623686 -0.0191690009 -0.0044899443 562 1311867737.3659460545 0.0066821938 0.0335450855 0.0586646721 0.0046755798 0.0347800000 389255393 0 402718720 0.0134516107 -0.0188934542 -0.0036759130 563 1311867737.3967239857 0.0063469661 0.0334967762 0.0586646721 0.0046741863 0.0354360000 389258685 0 402718720 0.0144968424 -0.0198252629 -0.0031176375 564 1311867737.4355359077 0.0066174511 0.0334491178 0.0586646721 0.0046706168 0.0348170000 389262065 0 402718720 0.0139417117 -0.0192119852 -0.0029962054 565 1311867737.4691100121 0.0076937648 0.0334035331 0.0586646721 0.0046685920 0.0348900000 389265301 0 402718720 0.0137957819 -0.0193191469 -0.0012610065 566 1311867737.4959459305 0.0082538938 0.0333590991 0.0586646721 0.0046650552 0.0343390000 389268297 0 402718720 0.0141313933 -0.0194755141 0.0002607384 567 1311867737.5353999138 0.0095434887 0.0333170963 0.0586646721 0.0046635954 0.0343300000 389271525 0 402718720 0.0129147582 -0.0199463964 0.0008415089 568 1311867737.5654399395 0.0096259778 0.0332753866 0.0586646721 0.0046600751 0.0344490000 389274849 0 402718720 0.0140437074 -0.0191197842 0.0017529782 569 1311867737.5958089828 0.0094261309 0.0332334723 0.0586646721 0.0046573135 0.0455940000 389278141 0 402718720 0.0150888199 -0.0199880041 0.0021589780 570 1311867737.6330978870 0.0089304997 0.0331908355 0.0586646721 0.0046544105 0.0338820000 389281521 0 402718720 0.0147508811 -0.0199699290 0.0012603622 571 1311867737.6624519825 0.0094114840 0.0331491904 0.0586646721 0.0046508410 0.0458180000 389284821 0 402718720 0.0155010484 -0.0187403038 0.0027122898 572 1311867737.7032339573 0.0114673283 0.0331112850 0.0586646721 0.0046470873 0.0332590000 389288057 0 402718720 0.0140982093 -0.0201914795 0.0041736546 573 1311867737.7314720154 0.0111396862 0.0330729402 0.0586646721 0.0046449269 0.0331870000 389291253 0 402718720 0.0140811382 -0.0218722243 0.0034217793 574 1311867737.7658560276 0.0123419808 0.0330368235 0.0586646721 0.0046427447 0.0332520000 389294569 0 402718720 0.0138233136 -0.0211998429 0.0043119541 575 1311867737.8011269569 0.0111412471 0.0329987442 0.0586646721 0.0046401440 0.0371790000 389870185 0 402718720 0.0150166778 -0.0213532876 0.0044695353 576 1311867737.8323190212 0.0105245542 0.0329597265 0.0586646721 0.0046366630 0.1070400000 389939621 0 402718720 0.0165869463 -0.0208003819 0.0050471555 577 1311867737.8633110523 0.0116453171 0.0329227865 0.0586646721 0.0046410390 0.0953850000 390214797 0 402718720 0.0173825268 -0.0214442816 0.0066674263 578 1311867737.9004418850 0.0112127606 0.0328852259 0.0586646721 0.0046377961 0.0928350000 395250361 0 402718720 0.0171304513 -0.0220019110 0.0061001619 579 1311867737.9305500984 0.0119098984 0.0328489991 0.0586646721 0.0046361667 0.0808020000 397198713 0 402718720 0.0168854445 -0.0229829755 0.0075782868 580 1311867737.9630560875 0.0143020470 0.0328170216 0.0586646721 0.0046336346 0.0995010000 395606319 0 402718720 0.0135157807 -0.0233807750 0.0071140351 581 1311867737.9996941090 0.0136662126 0.0327840598 0.0586646721 0.0046305339 0.0365420000 389954441 0 402718720 0.0148535660 -0.0237642992 0.0076761269 582 1311867738.0315399170 0.0150632858 0.0327536117 0.0586646721 0.0046337291 0.0349560000 389957637 0 402718720 0.0153048774 -0.0234022550 0.0105976108 583 1311867738.0629770756 0.0149183096 0.0327230194 0.0586646721 0.0046300360 0.0352570000 389960993 0 402718720 0.0144555978 -0.0227300189 0.0096806549 584 1311867738.0998299122 0.0137899807 0.0326905998 0.0586646721 0.0046287402 0.0340720000 389964085 0 402718720 0.0167797096 -0.0238259137 0.0104658827 585 1311867738.1308510303 0.0166152492 0.0326631206 0.0586646721 0.0046255372 0.0344960000 389967049 0 402718720 0.0153442835 -0.0240979642 0.0131102111 586 1311867738.1635079384 0.0157914963 0.0326343294 0.0586646721 0.0046234981 0.0344910000 389970589 0 402718720 0.0162413549 -0.0255908538 0.0124342265 587 1311867738.1992070675 0.0147995474 0.0326039465 0.0586646721 0.0046198640 0.0339250000 389973665 0 402718720 0.0186714940 -0.0233898330 0.0136548709 588 1311867738.2306089401 0.0160108414 0.0325757269 0.0586646721 0.0046185342 0.0337890000 389976829 0 402718720 0.0189078171 -0.0248959027 0.0149863632 589 1311867738.2632689476 0.0169533771 0.0325492034 0.0586646721 0.0046198992 0.0338350000 389980449 0 402718720 0.0190369766 -0.0253888480 0.0157490764 590 1311867738.3008689880 0.0172579978 0.0325232861 0.0586646721 0.0046162480 0.0337680000 389983517 0 402718720 0.0198071897 -0.0248076562 0.0159778334 591 1311867738.3339769840 0.0183220375 0.0324992569 0.0586646721 0.0046162261 0.0340520000 389986617 0 402718720 0.0187547505 -0.0258958563 0.0157135166 592 1311867738.3651630878 0.0185467154 0.0324756885 0.0586646721 0.0046135503 0.0342000000 389990101 0 402718720 0.0189137496 -0.0260375831 0.0156055037 593 1311867738.3995900154 0.0176480822 0.0324506841 0.0586646721 0.0046103242 0.0451030000 389993233 0 402718720 0.0193819702 -0.0278127808 0.0137768323 594 1311867738.4334011078 0.0186764356 0.0324274951 0.0586646721 0.0046138311 0.0335240000 389996565 0 402718720 0.0194419958 -0.0258182902 0.0151660452 595 1311867738.4643430710 0.0192954652 0.0324054245 0.0586646721 0.0046122006 0.0416390000 389999641 0 402718720 0.0197336134 -0.0278105214 0.0151558043 596 1311867738.5000250340 0.0187655948 0.0323825388 0.0586646721 0.0046092063 0.0336500000 390003157 0 402718720 0.0202503875 -0.0266918559 0.0145331388 597 1311867738.5332009792 0.0183753148 0.0323590761 0.0586646721 0.0046061123 0.0334790000 390006369 0 402718720 0.0216783900 -0.0259437431 0.0147039173 598 1311867738.5634350777 0.0183983427 0.0323357304 0.0586646721 0.0046037566 0.0333220000 390009389 0 402718720 0.0225535035 -0.0256035905 0.0148424730 599 1311867738.6022439003 0.0219486896 0.0323183898 0.0586646721 0.0046008090 0.0330520000 390012689 0 402718720 0.0220105648 -0.0272787027 0.0178501084 600 1311867738.6328980923 0.0198845249 0.0322976667 0.0586646721 0.0045984290 0.0328210000 390016245 0 402718720 0.0226280410 -0.0271528792 0.0148607995 601 1311867738.6628730297 0.0172096267 0.0322725618 0.0586646721 0.0045964489 0.0447090000 390019121 0 402718720 0.0265053771 -0.0258238502 0.0137402769 602 1311867738.6996099949 0.0205130074 0.0322530277 0.0586646721 0.0045946538 0.0331810000 390022285 0 402718720 0.0257828590 -0.0280271266 0.0160945039 603 1311867738.7314729691 0.0199653618 0.0322326501 0.0586646721 0.0045976108 0.0470110000 390670805 0 402718720 0.0260967929 -0.0267401133 0.0149596352 604 1311867738.7626600266 0.0194057021 0.0322114134 0.0586646721 0.0046000800 0.0975760000 390621957 0 402718720 0.0266755726 -0.0271881837 0.0137048662 605 1311867738.8032259941 0.0210992042 0.0321930461 0.0586646721 0.0045992965 0.0867630000 390623889 0 402718720 0.0289075561 -0.0258451011 0.0164475907 606 1311867738.8306779861 0.0206277911 0.0321739616 0.0586646721 0.0045990266 0.0832810000 393066081 0 402718720 0.0277496129 -0.0268954430 0.0145180412 607 1311867738.8639259338 0.0193486102 0.0321528325 0.0586646721 0.0045953831 0.0668340000 398063557 0 402718720 0.0286510289 -0.0256797243 0.0127980392 608 1311867738.9000120163 0.0182294846 0.0321299322 0.0586646721 0.0045948337 0.0668250000 397928385 0 402718720 0.0310224611 -0.0254913829 0.0121413022 609 1311867738.9307610989 0.0221496914 0.0321135443 0.0586646721 0.0045950186 0.0894790000 396609529 0 402718720 0.0292359609 -0.0264260210 0.0153617952 610 1311867738.9664750099 0.0226478092 0.0320980267 0.0586646721 0.0045945946 0.0367480000 390590049 0 402718720 0.0294088013 -0.0247922707 0.0156459194 611 1311867738.9989941120 0.0220032576 0.0320815050 0.0586646721 0.0045923414 0.0330110000 390593541 0 402718720 0.0301744789 -0.0246555191 0.0146883316 612 1311867739.0329539776 0.0251918398 0.0320702474 0.0586646721 0.0045888194 0.0456860000 390596601 0 402718720 0.0289168153 -0.0271749757 0.0173334945 613 1311867739.0664470196 0.0233739018 0.0320560609 0.0586646721 0.0045886855 0.0330600000 390599749 0 402718720 0.0296004973 -0.0272276532 0.0150287822 614 1311867739.0997900963 0.0210157782 0.0320380799 0.0586646721 0.0045861658 0.0329090000 390602849 0 402718720 0.0310575608 -0.0247954987 0.0126868589 615 1311867739.1321549416 0.0235566050 0.0320242889 0.0586646721 0.0045828785 0.0331360000 390606197 0 402718720 0.0311746523 -0.0254884120 0.0157128181 616 1311867739.1687150002 0.0218717474 0.0320078075 0.0586646721 0.0045798738 0.0326530000 390609457 0 402718720 0.0321897864 -0.0250499453 0.0141371321 617 1311867739.1999289989 0.0226795897 0.0319926889 0.0586646721 0.0045782608 0.0434280000 390612661 0 402718720 0.0313080885 -0.0258501228 0.0145971775 618 1311867739.2313010693 0.0233260058 0.0319786651 0.0586646721 0.0045747894 0.0375040000 391207489 0 402718720 0.0321387798 -0.0250285529 0.0157378931 619 1311867739.2672259808 0.0224621613 0.0319632911 0.0586646721 0.0045716540 0.0955210000 391161173 0 402718720 0.0322622880 -0.0250407252 0.0147497114 620 1311867739.2996931076 0.0248952843 0.0319518911 0.0586646721 0.0045809928 0.0847260000 391443885 0 402718720 0.0314924791 -0.0256244782 0.0171548855 621 1311867739.3319859505 0.0237695128 0.0319387150 0.0586646721 0.0045781962 0.0858950000 397260461 0 402718720 0.0312212855 -0.0237270463 0.0154300462 622 1311867739.3670029640 0.0257292353 0.0319287319 0.0586646721 0.0045855543 0.0740760000 397870633 0 402718720 0.0304256082 -0.0235578623 0.0177413598 623 1311867739.3990058899 0.0278087519 0.0319221187 0.0586646721 0.0045838442 0.0961740000 396571943 0 402718720 0.0291487612 -0.0226175766 0.0197829865 624 1311867739.4311320782 0.0249611773 0.0319109634 0.0586646721 0.0045876395 0.0342360000 391174793 0 402718720 0.0302342717 -0.0230838656 0.0174955763 625 1311867739.4668490887 0.0240965243 0.0318984603 0.0586646721 0.0045844438 0.0332240000 391178389 0 402718720 0.0314869136 -0.0230262298 0.0174985081 626 1311867739.4988598824 0.0261612590 0.0318892954 0.0586646721 0.0045860822 0.0337260000 391181297 0 402718720 0.0307032671 -0.0237453897 0.0202462636 627 1311867739.5316400528 0.0243195817 0.0318772225 0.0586646721 0.0045831228 0.0330940000 391184357 0 402718720 0.0314874612 -0.0243853442 0.0189076755 628 1311867739.5670249462 0.0229719579 0.0318630422 0.0586646721 0.0045812199 0.0451250000 391187569 0 402718720 0.0326863229 -0.0232996158 0.0178845190 629 1311867739.5990490913 0.0242568199 0.0318509496 0.0586646721 0.0045777481 0.0320480000 391190941 0 402718720 0.0315825939 -0.0240461938 0.0193045009 630 1311867739.6325490475 0.0254253596 0.0318407502 0.0586646721 0.0045755252 0.0323840000 391193937 0 402718720 0.0313769728 -0.0232251603 0.0209086630 631 1311867739.6706740856 0.0245865397 0.0318292539 0.0586646721 0.0045741875 0.0320980000 391197525 0 402718720 0.0314352028 -0.0235654674 0.0206363443 632 1311867739.7001221180 0.0219236836 0.0318135805 0.0586646721 0.0045766798 0.0318580000 391200585 0 402718720 0.0319037400 -0.0241232030 0.0183657967 633 1311867739.7323939800 0.0215601511 0.0317973824 0.0586646721 0.0045746206 0.0435680000 391203541 0 402718720 0.0309133865 -0.0238858555 0.0177316330 634 1311867739.7662999630 0.0230544321 0.0317835922 0.0586646721 0.0045723512 0.0319230000 391207065 0 402718720 0.0315544456 -0.0227098595 0.0200031139 635 1311867739.8016180992 0.0220692419 0.0317682940 0.0586646721 0.0045748810 0.0435940000 391210309 0 402718720 0.0297857784 -0.0257930215 0.0188134909 636 1311867739.8325679302 0.0204742234 0.0317505360 0.0586646721 0.0045741902 0.0316080000 391213705 0 402718720 0.0302636139 -0.0246277023 0.0170322880 637 1311867739.8701560497 0.0207143072 0.0317332107 0.0586646721 0.0045715672 0.0325080000 391216597 0 402718720 0.0294183921 -0.0237731598 0.0168103538 638 1311867739.9036860466 0.0239604078 0.0317210277 0.0586646721 0.0045700939 0.0316000000 391219953 0 402718720 0.0296465997 -0.0253648479 0.0217860229 639 1311867739.9317240715 0.0225160904 0.0317066224 0.0586646721 0.0045668584 0.0314390000 391223133 0 402718720 0.0302459039 -0.0243338682 0.0202340782 640 1311867739.9668979645 0.0192188732 0.0316871103 0.0586646721 0.0045709878 0.0362110000 391834409 0 402718720 0.0281860344 -0.0245411620 0.0150704989 641 1311867739.9987080097 0.0200561564 0.0316689653 0.0586646721 0.0045682537 0.0948400000 391793981 0 402718720 0.0270228349 -0.0257422775 0.0163528435 642 1311867740.0328791142 0.0215645637 0.0316532264 0.0586646721 0.0045689087 0.0856980000 392085573 0 402718720 0.0266195089 -0.0249355119 0.0181511417 643 1311867740.0671849251 0.0201884788 0.0316353963 0.0586646721 0.0045664939 0.0814430000 398862561 0 402718720 0.0259200167 -0.0240314491 0.0155708212 644 1311867740.0992529392 0.0200455412 0.0316173996 0.0586646721 0.0045668643 0.0708170000 398834881 0 402718720 0.0268265009 -0.0242720246 0.0159931965 645 1311867740.1347720623 0.0229899678 0.0316040237 0.0586646721 0.0045633565 0.0959310000 397541895 0 402718720 0.0263419487 -0.0276685320 0.0205964781 646 1311867740.1666491032 0.0247618090 0.0315934321 0.0586646721 0.0045729645 0.0385530000 391808833 0 402718720 0.0258504320 -0.0241459366 0.0214344840 647 1311867740.1993310452 0.0226005595 0.0315795327 0.0586646721 0.0045708156 0.0334210000 391812293 0 402718720 0.0259930976 -0.0234611034 0.0184962880 648 1311867740.2383539677 0.0236142091 0.0315672406 0.0586646721 0.0045688898 0.0333170000 391816065 0 402718720 0.0252808966 -0.0248973407 0.0199805126 649 1311867740.2664349079 0.0225783698 0.0315533902 0.0586646721 0.0045672871 0.0329820000 391818837 0 402718720 0.0248224121 -0.0243244767 0.0181628503 650 1311867740.2981588840 0.0248479322 0.0315430741 0.0586646721 0.0045691956 0.0325390000 391821937 0 402718720 0.0232200660 -0.0219135638 0.0192855000 651 1311867740.3347120285 0.0242907405 0.0315319338 0.0586646721 0.0045671422 0.0327650000 391825077 0 402718720 0.0232616924 -0.0232846458 0.0192436818 652 1311867740.3665161133 0.0255973320 0.0315228317 0.0586646721 0.0045688183 0.0330480000 391828553 0 402718720 0.0224026106 -0.0230874605 0.0200503506 653 1311867740.3993780613 0.0235986281 0.0315106966 0.0586646721 0.0045714413 0.0329710000 391831605 0 402718720 0.0226775333 -0.0235806406 0.0177005287 654 1311867740.4346680641 0.0222111680 0.0314964772 0.0586646721 0.0045719495 0.0324590000 391834881 0 402718720 0.0228052679 -0.0245753545 0.0159751624 655 1311867740.4664289951 0.0232926533 0.0314839522 0.0586646721 0.0045723250 0.0321280000 391838093 0 402718720 0.0228385851 -0.0226900615 0.0161284432 656 1311867740.4993040562 0.0230596475 0.0314711103 0.0586646721 0.0045724918 0.0316770000 391841417 0 402718720 0.0242061596 -0.0231668670 0.0159725975 657 1311867740.5354259014 0.0221056640 0.0314568554 0.0586646721 0.0045751086 0.0314930000 391844757 0 402718720 0.0244556926 -0.0236430485 0.0145254768 658 1311867740.5666589737 0.0214505028 0.0314416482 0.0586646721 0.0045726161 0.0318320000 391848273 0 402718720 0.0232196692 -0.0251461510 0.0131711662 659 1311867740.6008880138 0.0231215972 0.0314290230 0.0586646721 0.0045701277 0.0316100000 391851173 0 402718720 0.0241464749 -0.0235939249 0.0147008300 660 1311867740.6346809864 0.0227135457 0.0314158177 0.0586646721 0.0045686614 0.0313060000 391854585 0 402718720 0.0241617095 -0.0234647561 0.0136009194 661 1311867740.6665890217 0.0232332665 0.0314034386 0.0586646721 0.0045668769 0.0317940000 391857557 0 402718720 0.0237387232 -0.0222567543 0.0130591430 662 1311867740.6994900703 0.0239553805 0.0313921878 0.0586646721 0.0045653294 0.0312220000 391860689 0 402718720 0.0218882449 -0.0244610198 0.0129678408 663 1311867740.7368240356 0.0238949265 0.0313808797 0.0586646721 0.0045633736 0.0316840000 391863949 0 402718720 0.0233541112 -0.0241109077 0.0131402602 664 1311867740.7668819427 0.0212955531 0.0313656910 0.0586646721 0.0045638994 0.0314620000 391866993 0 402718720 0.0220080838 -0.0245668516 0.0087459628 665 1311867740.7996399403 0.0247292407 0.0313557113 0.0586646721 0.0045648126 0.0313020000 391870277 0 402718720 0.0234643482 -0.0231761280 0.0127754826 666 1311867740.8349099159 0.0232171956 0.0313434913 0.0586646721 0.0045638860 0.0316650000 391873441 0 402718720 0.0226036441 -0.0242930166 0.0106593706 667 1311867740.8668210506 0.0233064760 0.0313314418 0.0586646721 0.0045615202 0.0319320000 391876981 0 402718720 0.0205596797 -0.0248614028 0.0095445486 668 1311867740.8993830681 0.0295669194 0.0313288003 0.0586646721 0.0045792654 0.0424070000 391879969 0 402718720 0.0221470073 -0.0226755664 0.0166934766 669 1311867740.9399120808 0.0283981562 0.0313244197 0.0586646721 0.0045779672 0.0319770000 391883285 0 402718720 0.0209461730 -0.0222323332 0.0144859422 670 1311867740.9665501118 0.0248621181 0.0313147745 0.0586646721 0.0045810486 0.0318930000 391886441 0 402718720 0.0192620270 -0.0227718707 0.0093762670 671 1311867741.0021579266 0.0268393997 0.0313081048 0.0586646721 0.0045776380 0.0320120000 391889861 0 402718720 0.0207701959 -0.0233758297 0.0121540641 672 1311867741.0367169380 0.0303433295 0.0313066691 0.0586646721 0.0045842058 0.0315950000 391893129 0 402718720 0.0202472731 -0.0218608622 0.0151274838 673 1311867741.0666699409 0.0257784110 0.0312984547 0.0586646721 0.0045837942 0.0315270000 391896061 0 402718720 0.0184068959 -0.0212541446 0.0083356081 674 1311867741.1009640694 0.0262391083 0.0312909483 0.0586646721 0.0045866439 0.0427920000 391899105 0 402718720 0.0182687622 -0.0236773882 0.0096904784 675 1311867741.1357901096 0.0319556482 0.0312919330 0.0586646721 0.0046006025 0.0314970000 391902469 0 402718720 0.0182158947 -0.0213017315 0.0149952369 676 1311867741.1675300598 0.0262146313 0.0312844222 0.0586646721 0.0046118706 0.0403680000 391905897 0 402718720 0.0164205432 -0.0237056687 0.0077490904 677 1311867741.2014830112 0.0239120200 0.0312735324 0.0586646721 0.0046232312 0.0316380000 391909077 0 402718720 0.0156844910 -0.0250341464 0.0037987544 678 1311867741.2411060333 0.0277411062 0.0312683224 0.0586646721 0.0046243410 0.0311860000 391912369 0 402718720 0.0178856738 -0.0246675909 0.0090275276 679 1311867741.2668209076 0.0280029792 0.0312635133 0.0586646721 0.0046274763 0.0313620000 391915397 0 402718720 0.0176059194 -0.0241680946 0.0082568647 680 1311867741.2997009754 0.0246166550 0.0312537385 0.0586646721 0.0046293395 0.0309560000 391918401 0 402718720 0.0157693066 -0.0246542003 0.0023822044 681 1311867741.3348419666 0.0251817498 0.0312448222 0.0586646721 0.0046276922 0.0311980000 391922029 0 402718720 0.0175268482 -0.0241112448 0.0033810898 682 1311867741.3701419830 0.0294157509 0.0312421403 0.0586646721 0.0046362654 0.0307100000 391925073 0 402718720 0.0171549525 -0.0210985690 0.0066967970 683 1311867741.4066278934 0.0278000273 0.0312371006 0.0586646721 0.0046364630 0.0422410000 391928469 0 402718720 0.0189744476 -0.0199000221 0.0047680396 684 1311867741.4393060207 0.0285240747 0.0312331342 0.0586646721 0.0046342050 0.0309200000 391931705 0 402718720 0.0178972371 -0.0202909634 0.0053477231 685 1311867741.4667329788 0.0273169000 0.0312274171 0.0586646721 0.0046330843 0.0315040000 391934701 0 402718720 0.0179019701 -0.0229787566 0.0045899595 686 1311867741.5025069714 0.0269672107 0.0312212069 0.0586646721 0.0046316628 0.0313920000 391938057 0 402718720 0.0192920677 -0.0199705251 0.0031808694 687 1311867741.5368049145 0.0264437553 0.0312142528 0.0586646721 0.0046309780 0.0312160000 391941245 0 402718720 0.0191490017 -0.0213773083 0.0027205697 688 1311867741.5688209534 0.0251230393 0.0312053993 0.0586646721 0.0046289609 0.0309950000 391944457 0 402718720 0.0176634304 -0.0224777982 0.0001835227 689 1311867741.6046030521 0.0258326922 0.0311976014 0.0586646721 0.0046386632 0.0309880000 391947773 0 402718720 0.0189769883 -0.0211012792 0.0003475850 690 1311867741.6355440617 0.0273470208 0.0311920209 0.0586646721 0.0046355781 0.0311550000 391951049 0 402718720 0.0205535330 -0.0217190851 0.0029360000 691 1311867741.6679561138 0.0286818314 0.0311883882 0.0586646721 0.0046347866 0.0358500000 392522737 0 402718720 0.0216761176 -0.0205638297 0.0040813852 692 1311867741.7048020363 0.0258828085 0.0311807212 0.0586646721 0.0046467713 0.0954560000 392470237 0 402718720 0.0214464087 -0.0212879684 0.0004449203 693 1311867741.7345991135 0.0299551524 0.0311789527 0.0586646721 0.0046470004 0.0831710000 392786357 0 402718720 0.0227828659 -0.0191222783 0.0045505222 694 1311867741.7702169418 0.0293336175 0.0311762937 0.0586646721 0.0046439808 0.0761770000 399290897 0 402718720 0.0224329326 -0.0210938267 0.0037564924 695 1311867741.8058650494 0.0326366909 0.0311783950 0.0586646721 0.0046469929 0.0692260000 399248973 0 402718720 0.0228932165 -0.0195418578 0.0064585591 696 1311867741.8388509750 0.0306551829 0.0311776432 0.0586646721 0.0046450464 0.0945530000 397956331 0 402718720 0.0259960983 -0.0193794668 0.0046301819 697 1311867741.8683021069 0.0292712599 0.0311749081 0.0586646721 0.0046473535 0.0373390000 392486113 0 402718720 0.0255115367 -0.0203878675 0.0027003018 698 1311867741.9065721035 0.0293934736 0.0311723559 0.0586646721 0.0046453004 0.0316340000 392489541 0 402718720 0.0270291325 -0.0207073390 0.0029777996 699 1311867741.9387769699 0.0306188203 0.0311715640 0.0586646721 0.0046423779 0.0428820000 392493001 0 402718720 0.0265947375 -0.0212037265 0.0035967790 700 1311867741.9665379524 0.0311417822 0.0311715215 0.0586646721 0.0046392954 0.0419770000 392496205 0 402718720 0.0276485458 -0.0201732833 0.0036141966 701 1311867742.0029959679 0.0325879715 0.0311735421 0.0586646721 0.0046362227 0.0419680000 392499337 0 402718720 0.0280720182 -0.0200459901 0.0045798849 702 1311867742.0344839096 0.0322350115 0.0311750542 0.0586646721 0.0046332153 0.0315940000 392502557 0 402718720 0.0300256684 -0.0199682750 0.0041155666 703 1311867742.0674400330 0.0324083865 0.0311768085 0.0586646721 0.0046305905 0.0318330000 392505721 0 402718720 0.0309371278 -0.0201803092 0.0041321535 704 1311867742.1030650139 0.0330521874 0.0311794724 0.0586646721 0.0046273748 0.0309790000 392508861 0 402718720 0.0310867243 -0.0201755967 0.0041852631 705 1311867742.1348879337 0.0355772115 0.0311857104 0.0586646721 0.0046246379 0.0310850000 392512049 0 402718720 0.0333964527 -0.0190908052 0.0067023914 706 1311867742.1672229767 0.0338956118 0.0311895487 0.0586646721 0.0046224960 0.0303390000 392515333 0 402718720 0.0336408317 -0.0205315072 0.0049855150 707 1311867742.2028279305 0.0343225449 0.0311939801 0.0586646721 0.0046202780 0.0394050000 392518953 0 402718720 0.0350188315 -0.0182059612 0.0045238491 708 1311867742.2362670898 0.0340233855 0.0311979765 0.0586646721 0.0046182382 0.0393320000 392521989 0 402718720 0.0375026017 -0.0175696518 0.0041309092 709 1311867742.2674059868 0.0343694724 0.0312024497 0.0586646721 0.0046156296 0.0391110000 392525185 0 402718720 0.0365941748 -0.0201086495 0.0043838480 710 1311867742.3028159142 0.0364872068 0.0312098930 0.0586646721 0.0046187169 0.0300720000 392528493 0 402718720 0.0381590724 -0.0187618732 0.0056386404 711 1311867742.3350739479 0.0406929068 0.0312232306 0.0586646721 0.0046262291 0.0301510000 392531649 0 402718720 0.0391005203 -0.0155674173 0.0088915396 712 1311867742.3694241047 0.0376879945 0.0312323103 0.0586646721 0.0046284932 0.0305950000 392535133 0 402718720 0.0379044786 -0.0187164899 0.0059423419 713 1311867742.4062991142 0.0380069390 0.0312418119 0.0586646721 0.0046258815 0.0303530000 392538393 0 402718720 0.0390125588 -0.0183763579 0.0062517868 714 1311867742.4346439838 0.0387396142 0.0312523130 0.0586646721 0.0046227703 0.0305020000 392541397 0 402718720 0.0399721824 -0.0167590044 0.0063710073 715 1311867742.4666969776 0.0364977345 0.0312596492 0.0586646721 0.0046235305 0.0309460000 392544545 0 402718720 0.0402730703 -0.0188527033 0.0043148808 716 1311867742.5047059059 0.0397346839 0.0312714859 0.0586646721 0.0046236679 0.0385460000 392548061 0 402718720 0.0396319889 -0.0186765678 0.0070349649 717 1311867742.5359389782 0.0360810235 0.0312781938 0.0586646721 0.0046212611 0.0300410000 392551289 0 402718720 0.0404446125 -0.0183500219 0.0030985782 718 1311867742.5678529739 0.0382551216 0.0312879109 0.0586646721 0.0046190150 0.0383970000 392554237 0 402718720 0.0421658158 -0.0154183507 0.0049264301 719 1311867742.6054639816 0.0399085991 0.0312999008 0.0586646721 0.0046160598 0.0302230000 392557497 0 402718720 0.0406040065 -0.0171067547 0.0062709423 720 1311867742.6347279549 0.0378604047 0.0313090126 0.0586646721 0.0046141527 0.0301250000 392560661 0 402718720 0.0405646935 -0.0186887830 0.0042595249 721 1311867742.6724960804 0.0367332473 0.0313165358 0.0586646721 0.0046127118 0.0299250000 392564257 0 402718720 0.0414930433 -0.0184347220 0.0032700635 722 1311867742.7046229839 0.0395910442 0.0313279963 0.0586646721 0.0046109783 0.0303240000 392567541 0 402718720 0.0412838683 -0.0190740209 0.0060529122 723 1311867742.7356119156 0.0375096202 0.0313365463 0.0586646721 0.0046089966 0.0299530000 392570577 0 402718720 0.0422303453 -0.0194459669 0.0037291814 724 1311867742.7726070881 0.0396931805 0.0313480886 0.0586646721 0.0046062212 0.0301930000 392574021 0 402718720 0.0425294489 -0.0197408777 0.0055920072 725 1311867742.8034689426 0.0382881798 0.0313576611 0.0586646721 0.0046044671 0.0397110000 392577121 0 402718720 0.0425147712 -0.0200853441 0.0037039537 726 1311867742.8352251053 0.0413159356 0.0313713778 0.0586646721 0.0046060668 0.0399320000 392580293 0 402718720 0.0432331786 -0.0176554173 0.0057495814 727 1311867742.8705639839 0.0397597216 0.0313829161 0.0586646721 0.0046036727 0.0384740000 392583417 0 402718720 0.0426307805 -0.0186441075 0.0038810950 728 1311867742.9046700001 0.0386454798 0.0313928921 0.0586646721 0.0046019374 0.0301900000 392586605 0 402718720 0.0434549525 -0.0201434363 0.0027327780 729 1311867742.9382069111 0.0398653746 0.0314045142 0.0586646721 0.0046093937 0.0301050000 392590249 0 402718720 0.0433401056 -0.0192863960 0.0043589380 730 1311867742.9707310200 0.0438068397 0.0314215037 0.0586646721 0.0046246376 0.0343680000 393146953 0 402718720 0.0453296714 -0.0169443525 0.0077352580 731 1311867743.0024189949 0.0444435924 0.0314393177 0.0586646721 0.0046244820 0.0860290000 393102153 0 402718720 0.0450186916 -0.0176545382 0.0087089706 732 1311867743.0345149040 0.0407131948 0.0314519870 0.0586646721 0.0046225337 0.0798060000 393104141 0 402718720 0.0440847576 -0.0184527095 0.0042565409 733 1311867743.0722420216 0.0448876843 0.0314703167 0.0586646721 0.0046210788 0.0747530000 395973229 0 402718720 0.0460986197 -0.0161794536 0.0078644119 734 1311867743.1045989990 0.0430056714 0.0314860324 0.0586646721 0.0046189988 0.0611650000 399665753 0 402718720 0.0466281921 -0.0190858170 0.0065317675 735 1311867743.1350400448 0.0447572879 0.0315040886 0.0586646721 0.0046186653 0.0350240000 399800165 0 402718720 0.0469246507 -0.0174208730 0.0074856132 736 1311867743.1704380512 0.0462084822 0.0315240674 0.0586646721 0.0046182814 0.0764090000 395694049 0 402718720 0.0491618179 -0.0166095663 0.0087551959 737 1311867743.2037980556 0.0449873134 0.0315423350 0.0586646721 0.0046158818 0.0295630000 393073933 0 402718720 0.0492496565 -0.0171573963 0.0073010772 738 1311867743.2358140945 0.0436575226 0.0315587512 0.0586646721 0.0046161083 0.0301940000 393077329 0 402718720 0.0488065705 -0.0177985560 0.0057778452 739 1311867743.2708129883 0.0445914008 0.0315763868 0.0586646721 0.0046150378 0.0300300000 393080429 0 402718720 0.0503379740 -0.0177492574 0.0075096451 740 1311867743.3032529354 0.0484042466 0.0315991271 0.0586646721 0.0046430610 0.0302910000 393083785 0 402718720 0.0507849753 -0.0144206081 0.0102703478 741 1311867743.3363931179 0.0457655489 0.0316182451 0.0586646721 0.0046436958 0.0297600000 393086821 0 402718720 0.0500368737 -0.0161144454 0.0082561001 742 1311867743.3707330227 0.0429169275 0.0316334724 0.0586646721 0.0046450482 0.0295220000 393089945 0 402718720 0.0524771549 -0.0154806254 0.0055188108 743 1311867743.4043838978 0.0467244498 0.0316537833 0.0586646721 0.0046439517 0.0377430000 393093245 0 402718720 0.0510137826 -0.0168940797 0.0096072685 744 1311867743.4352641106 0.0474870838 0.0316750646 0.0586646721 0.0046450670 0.0294700000 393096281 0 402718720 0.0526712984 -0.0168414321 0.0104189571 745 1311867743.4768960476 0.0489611849 0.0316982675 0.0586646721 0.0046478833 0.0290700000 393100149 0 402718720 0.0521906614 -0.0166569352 0.0113591347 746 1311867743.5035250187 0.0472177342 0.0317190710 0.0586646721 0.0046471393 0.0290930000 393103073 0 402718720 0.0511496179 -0.0157248005 0.0090512447 747 1311867743.5389750004 0.0465656854 0.0317389460 0.0586646721 0.0046494746 0.0290900000 393106325 0 402718720 0.0507549942 -0.0183677692 0.0089380760 748 1311867743.5749680996 0.0461510010 0.0317582135 0.0586646721 0.0046515443 0.0288860000 393109505 0 402718720 0.0517105311 -0.0186440758 0.0084491242 749 1311867743.6036109924 0.0472112671 0.0317788451 0.0586646721 0.0046602165 0.0287940000 393112621 0 402718720 0.0515049659 -0.0170217995 0.0090568718 750 1311867743.6354589462 0.0496613570 0.0318026884 0.0586646721 0.0046587817 0.0389930000 393115961 0 402718720 0.0511827171 -0.0168563910 0.0113167167 751 1311867743.6759150028 0.0468950644 0.0318227848 0.0586646721 0.0046577755 0.0397120000 393119365 0 402718720 0.0524832606 -0.0176083911 0.0083626155 752 1311867743.7034959793 0.0484756045 0.0318449295 0.0586646721 0.0046565896 0.0383600000 393122449 0 402718720 0.0513451546 -0.0178675409 0.0097595919 753 1311867743.7388861179 0.0486781448 0.0318672844 0.0586646721 0.0046545176 0.0285910000 393125661 0 402718720 0.0511582494 -0.0174270421 0.0093535949 754 1311867743.7733619213 0.0520362221 0.0318940336 0.0586646721 0.0046541006 0.0283940000 393128921 0 402718720 0.0507814921 -0.0170180406 0.0122935828 755 1311867743.8064749241 0.0464247167 0.0319132795 0.0586646721 0.0046562063 0.0285230000 393132029 0 402718720 0.0504550487 -0.0186291635 0.0063635260 756 1311867743.8391659260 0.0507216603 0.0319381584 0.0586646721 0.0046631129 0.0290040000 393135209 0 402718720 0.0496955886 -0.0170808844 0.0099380538 757 1311867743.8726658821 0.0499295518 0.0319619251 0.0586646721 0.0046608926 0.0289710000 393138309 0 402718720 0.0499868244 -0.0173069686 0.0087350346 758 1311867743.9031310081 0.0498581454 0.0319855348 0.0586646721 0.0046597904 0.0290810000 393141881 0 402718720 0.0497978106 -0.0167393759 0.0080289636 759 1311867743.9453630447 0.0502260402 0.0320095671 0.0586646721 0.0046575946 0.0374950000 393145197 0 402718720 0.0503075793 -0.0176708549 0.0083056577 760 1311867743.9741249084 0.0489858426 0.0320319043 0.0586646721 0.0046548497 0.0288210000 393147977 0 402718720 0.0495409518 -0.0183088817 0.0069632344 761 1311867744.0042529106 0.0468860641 0.0320514236 0.0586646721 0.0046544955 0.0377710000 393151477 0 402718720 0.0498716980 -0.0169865526 0.0042788442 762 1311867744.0407259464 0.0473899841 0.0320715529 0.0586646721 0.0046543886 0.0285060000 393154569 0 402718720 0.0491773859 -0.0171382464 0.0047001038 763 1311867744.0716118813 0.0471772477 0.0320913507 0.0586646721 0.0046529441 0.0281030000 393157725 0 402718720 0.0500064492 -0.0183452889 0.0048560146 764 1311867744.1111290455 0.0491668433 0.0321137008 0.0586646721 0.0046515942 0.0284760000 393161025 0 402718720 0.0496585965 -0.0166222639 0.0064193718 765 1311867744.1412119865 0.0474643223 0.0321337670 0.0586646721 0.0046490817 0.0287990000 393164117 0 402718720 0.0494027212 -0.0182774365 0.0050610006 766 1311867744.1734991074 0.0478141420 0.0321542375 0.0586646721 0.0046485785 0.0282550000 393167385 0 402718720 0.0511649065 -0.0147457337 0.0045513604 767 1311867744.2046771049 0.0504965447 0.0321781518 0.0586646721 0.0046465802 0.0287060000 393170541 0 402718720 0.0501954257 -0.0155163174 0.0075968374 768 1311867744.2400228977 0.0495640859 0.0322007898 0.0586646721 0.0046442109 0.0406510000 393173873 0 402718720 0.0494200327 -0.0183260087 0.0072924178 769 1311867744.2773048878 0.0488963127 0.0322225004 0.0586646721 0.0046429919 0.0290960000 393177341 0 402718720 0.0492369197 -0.0164112095 0.0062839948 770 1311867744.3032519817 0.0480285175 0.0322430277 0.0586646721 0.0046435429 0.0410460000 393180209 0 402718720 0.0490227640 -0.0165394749 0.0054931492 771 1311867744.3391230106 0.0504397191 0.0322666292 0.0586646721 0.0046468506 0.0286600000 393183357 0 402718720 0.0505429804 -0.0181135219 0.0086077135 772 1311867744.3707659245 0.0506076366 0.0322903869 0.0586646721 0.0046451243 0.0293610000 393186577 0 402718720 0.0500585511 -0.0161855780 0.0081003308 773 1311867744.4027431011 0.0450436100 0.0323068853 0.0586646721 0.0046610019 0.0285910000 393189861 0 402718720 0.0508239567 -0.0179353748 0.0027692150 774 1311867744.4383800030 0.0492683277 0.0323287993 0.0586646721 0.0046605923 0.0287120000 393193001 0 402718720 0.0506702363 -0.0169759020 0.0066712778 775 1311867744.4717690945 0.0497024246 0.0323512169 0.0586646721 0.0046580574 0.0289230000 393196397 0 402718720 0.0503551364 -0.0180639103 0.0072472822 776 1311867744.5026860237 0.0486251339 0.0323721884 0.0586646721 0.0046553670 0.0645620000 393199481 0 402718720 0.0499072336 -0.0161910281 0.0054643154 777 1311867744.5383169651 0.0470284410 0.0323910510 0.0586646721 0.0046598601 0.0285100000 393202629 0 402718720 0.0514290780 -0.0178569686 0.0041558500 778 1311867744.5726189613 0.0535636023 0.0324182651 0.0586646721 0.0046698870 0.0288730000 393205769 0 402718720 0.0502821282 -0.0162962973 0.0102731474 779 1311867744.6028740406 0.0522407778 0.0324437112 0.0586646721 0.0046699502 0.0396560000 393208973 0 402718720 0.0522694290 -0.0153162805 0.0086510740 780 1311867744.6386809349 0.0538191684 0.0324711156 0.0586646721 0.0046744092 0.0294030000 393212249 0 402718720 0.0496890992 -0.0163189080 0.0103023406 781 1311867744.6707758904 0.0498957485 0.0324934263 0.0586646721 0.0046766848 0.0286060000 393215493 0 402718720 0.0507304892 -0.0174366310 0.0066256877 782 1311867744.7029349804 0.0490786880 0.0325146351 0.0586646721 0.0046790652 0.0286340000 393218609 0 402718720 0.0499462858 -0.0173011292 0.0054150783 783 1311867744.7396171093 0.0472995676 0.0325335175 0.0586646721 0.0046799325 0.0282080000 393221821 0 402718720 0.0520066991 -0.0160157029 0.0037020016 784 1311867744.7705199718 0.0506336652 0.0325566044 0.0586646721 0.0046798855 0.0285460000 393225041 0 402718720 0.0500546806 -0.0147714708 0.0066393111 785 1311867744.8035891056 0.0520962700 0.0325814957 0.0586646721 0.0046818290 0.0287150000 393228133 0 402718720 0.0499899387 -0.0170713272 0.0084432457 786 1311867744.8424170017 0.0523374565 0.0326066305 0.0586646721 0.0046791560 0.0524510000 393231513 0 402718720 0.0508177318 -0.0166804381 0.0083289165 787 1311867744.8727390766 0.0516484939 0.0326308260 0.0586646721 0.0046794308 0.0290750000 393234741 0 402718720 0.0510975346 -0.0161377378 0.0073837508 788 1311867744.9029939175 0.0529994071 0.0326566745 0.0586646721 0.0046768446 0.0424070000 393237881 0 402718720 0.0503975824 -0.0165851265 0.0084669124 789 1311867744.9392940998 0.0474543944 0.0326754295 0.0586646721 0.0046888286 0.0286660000 393241277 0 402718720 0.0501604788 -0.0188396797 0.0027003195 790 1311867744.9708900452 0.0523823239 0.0327003750 0.0586646721 0.0047044896 0.0284900000 393244233 0 402718720 0.0517635122 -0.0160369892 0.0070033651 791 1311867745.0027489662 0.0493205711 0.0327213866 0.0586646721 0.0047213187 0.0285930000 393247253 0 402718720 0.0526428334 -0.0162235610 0.0032454897 792 1311867745.0384869576 0.0505871028 0.0327439443 0.0586646721 0.0047215265 0.0286900000 393250721 0 402718720 0.0511905327 -0.0183038730 0.0044608526 793 1311867745.0729780197 0.0487095155 0.0327640774 0.0586646721 0.0047239524 0.0283660000 393254085 0 402718720 0.0512507856 -0.0191254206 0.0023517516 794 1311867745.1118760109 0.0499126948 0.0327856752 0.0586646721 0.0047297787 0.0282990000 393257241 0 402718720 0.0523540750 -0.0191223547 0.0033390913 795 1311867745.1405589581 0.0520658605 0.0328099270 0.0586646721 0.0047284412 0.0366390000 393260245 0 402718720 0.0510679819 -0.0177731570 0.0049145017 796 1311867745.1729030609 0.0517836101 0.0328337633 0.0586646721 0.0047259676 0.0281040000 393263537 0 402718720 0.0531896912 -0.0177921057 0.0044306666 797 1311867745.2068369389 0.0522907935 0.0328581761 0.0586646721 0.0047248843 0.0444430000 393798161 0 402718720 0.0530467369 -0.0169925801 0.0043997448 798 1311867745.2430789471 0.0476198085 0.0328766744 0.0586646721 0.0047250037 0.0841580000 393760189 0 402718720 0.0539544336 -0.0179848839 -0.0005033668 799 1311867745.2729060650 0.0495749041 0.0328975733 0.0586646721 0.0047259324 0.0774890000 393762425 0 402718720 0.0532482341 -0.0175805446 0.0011484046 800 1311867745.3112850189 0.0514983535 0.0329208243 0.0586646721 0.0047231443 0.0764000000 398465065 0 402718720 0.0536199175 -0.0170685891 0.0026638210 801 1311867745.3395059109 0.0548887663 0.0329482499 0.0586646721 0.0047238536 0.0554880000 400393981 0 402718720 0.0542973578 -0.0157782771 0.0054264050 802 1311867745.3733940125 0.0513030365 0.0329711362 0.0586646721 0.0047302895 0.0350390000 400269997 0 402718720 0.0536031127 -0.0191600341 0.0021164715 803 1311867745.4102098942 0.0535640344 0.0329967812 0.0586646721 0.0047306481 0.0722490000 396694385 0 402718720 0.0549137592 -0.0162762702 0.0033164416 804 1311867745.4433169365 0.0553892441 0.0330246325 0.0586646721 0.0047290547 0.0277890000 393778061 0 402718720 0.0549385697 -0.0159761179 0.0048278216 805 1311867745.4708619118 0.0540248565 0.0330507197 0.0586646721 0.0047268469 0.0357340000 393781249 0 402718720 0.0553562231 -0.0161866564 0.0031944420 806 1311867745.5099780560 0.0527134910 0.0330751152 0.0586646721 0.0047266972 0.0279940000 393784685 0 402718720 0.0546759218 -0.0174098741 0.0015964080 807 1311867745.5417380333 0.0544311963 0.0331015788 0.0586646721 0.0047244157 0.0270230000 393787865 0 402718720 0.0557661280 -0.0171057191 0.0025922339 808 1311867745.5704059601 0.0560332313 0.0331299595 0.0586646721 0.0047224056 0.0272030000 393791093 0 402718720 0.0561243296 -0.0167493038 0.0034423806 809 1311867745.6133821011 0.0566612519 0.0331590464 0.0586646721 0.0047198063 0.0271880000 393794417 0 402718720 0.0567582026 -0.0166199282 0.0029735789 810 1311867745.6438291073 0.0559960455 0.0331872402 0.0586646721 0.0047192796 0.0270120000 393797709 0 402718720 0.0556978360 -0.0172965899 0.0021502580 811 1311867745.6709001064 0.0530774221 0.0332117657 0.0586646721 0.0047180250 0.0268370000 393800713 0 402718720 0.0562627763 -0.0172065888 -0.0015952382 812 1311867745.7088780403 0.0531364083 0.0332363035 0.0586646721 0.0047158175 0.0358140000 393803973 0 402718720 0.0556183271 -0.0164902117 -0.0023908205 813 1311867745.7423269749 0.0543763153 0.0332623059 0.0586646721 0.0047162984 0.0261910000 393807409 0 402718720 0.0558374897 -0.0163015239 -0.0015062541 814 1311867745.7760419846 0.0567144938 0.0332911170 0.0586646721 0.0047160547 0.0373730000 393810645 0 402718720 0.0571583658 -0.0153177129 0.0006522574 815 1311867745.8116889000 0.0583827235 0.0333219042 0.0586646721 0.0047237087 0.0258830000 393814049 0 402718720 0.0564613603 -0.0154595394 0.0018249210 816 1311867745.8389890194 0.0558027737 0.0333494543 0.0586646721 0.0047230951 0.0258500000 393816845 0 402718720 0.0568944365 -0.0162649918 -0.0009250995 817 1311867745.8709759712 0.0584253706 0.0333801470 0.0586646721 0.0047236048 0.0258360000 393819921 0 402718720 0.0578270331 -0.0165403169 0.0015148688 818 1311867745.9108459949 0.0548118725 0.0334063471 0.0586646721 0.0047284582 0.0260500000 393823597 0 402718720 0.0569087714 -0.0159530416 -0.0025304258 819 1311867745.9435789585 0.0561780557 0.0334341514 0.0586646721 0.0047268191 0.0254950000 393826865 0 402718720 0.0573830158 -0.0163492560 -0.0015427619 820 1311867745.9732220173 0.0611016303 0.0334678923 0.0611016303 0.0047291822 0.0258250000 393830029 0 402718720 0.0587158352 -0.0151726641 0.0026990678 821 1311867746.0083909035 0.0588184409 0.0334987699 0.0611016303 0.0047311550 0.0368150000 393833425 0 402718720 0.0584515966 -0.0161312260 -0.0000661481 822 1311867746.0391409397 0.0617830828 0.0335331790 0.0617830828 0.0047313333 0.0253740000 393836453 0 402718720 0.0602418184 -0.0157401189 0.0022352450 823 1311867746.0728518963 0.0600751378 0.0335654293 0.0617830828 0.0047300924 0.0349430000 393839809 0 402718720 0.0605682358 -0.0163888335 0.0002560839 824 1311867746.1113359928 0.0555805527 0.0335921467 0.0617830828 0.0047370882 0.0266640000 394190337 0 402718720 0.0600367710 -0.0165373608 -0.0048015732 825 1311867746.1412689686 0.0598118380 0.0336239281 0.0617830828 0.0047366310 0.0752090000 394262681 0 402718720 0.0607413240 -0.0157313850 -0.0011071935 826 1311867746.1721889973 0.0611233227 0.0336572204 0.0617830828 0.0047376594 0.0707120000 394604545 0 402718720 0.0611687638 -0.0151750613 -0.0003497675 827 1311867746.2066209316 0.0566623732 0.0336850380 0.0617830828 0.0047364578 0.0875950000 400700693 0 402718720 0.0605698451 -0.0150671918 -0.0055368561 828 1311867746.2386920452 0.0614448562 0.0337185643 0.0617830828 0.0047353744 0.0561600000 400755609 0 402718720 0.0626669452 -0.0129656699 -0.0016983617 829 1311867746.2704648972 0.0618430264 0.0337524901 0.0618430264 0.0047326766 0.0753960000 399370299 0 402718720 0.0618728511 -0.0159025285 -0.0007316954 830 1311867746.3068819046 0.0563756675 0.0337797469 0.0618430264 0.0047335799 0.0292650000 394281245 0 402718720 0.0615027212 -0.0165834222 -0.0064879172 831 1311867746.3393440247 0.0565920137 0.0338071985 0.0618430264 0.0047326127 0.0292720000 394284353 0 402718720 0.0629009753 -0.0163441431 -0.0067297611 832 1311867746.3797800541 0.0606518276 0.0338394637 0.0618430264 0.0047320857 0.0289190000 394287869 0 402718720 0.0631392449 -0.0164774638 -0.0025281403 833 1311867746.4078478813 0.0594110936 0.0338701619 0.0618430264 0.0047294797 0.0294420000 394291177 0 402718720 0.0623162091 -0.0170384087 -0.0043348130 834 1311867746.4389901161 0.0525349081 0.0338925417 0.0618430264 0.0047376790 0.0260130000 394294397 0 402718720 0.0623245016 -0.0187412780 -0.0104386173 835 1311867746.4774639606 0.0601421259 0.0339239783 0.0618430264 0.0047455342 0.0248870000 394297801 0 402718720 0.0630313084 -0.0160546005 -0.0034858100 836 1311867746.5066781044 0.0593606159 0.0339544049 0.0618430264 0.0047431880 0.0242090000 394300757 0 402718720 0.0627253652 -0.0172871947 -0.0039185751 837 1311867746.5406761169 0.0586479045 0.0339839073 0.0618430264 0.0047416491 0.0247510000 394303961 0 402718720 0.0621969663 -0.0178544149 -0.0045492109 838 1311867746.5748629570 0.0576747656 0.0340121780 0.0618430264 0.0047390640 0.0248800000 394307573 0 402718720 0.0629131719 -0.0154290088 -0.0063337963 839 1311867746.6067559719 0.0547698215 0.0340369190 0.0618430264 0.0047402716 0.0355210000 394310553 0 402718720 0.0626069456 -0.0182519052 -0.0084525608 840 1311867746.6396849155 0.0543065965 0.0340610496 0.0618430264 0.0047407738 0.0247690000 394313957 0 402718720 0.0622696206 -0.0185795873 -0.0090379752 841 1311867746.6749529839 0.0605827495 0.0340925855 0.0618430264 0.0047422716 0.0374810000 394317401 0 402718720 0.0633149594 -0.0175635945 -0.0027267318 842 1311867746.7095060349 0.0639671162 0.0341280659 0.0639671162 0.0047408102 0.0249140000 394320237 0 402718720 0.0643725321 -0.0166434236 0.0001348667 843 1311867746.7391049862 0.0607880428 0.0341596910 0.0639671162 0.0047386594 0.0247040000 394323497 0 402718720 0.0629547983 -0.0189564861 -0.0027060173 844 1311867746.7751340866 0.0555596687 0.0341850464 0.0639671162 0.0047416368 0.0248410000 394326797 0 402718720 0.0629674718 -0.0194413364 -0.0083767790 845 1311867746.8070099354 0.0596593358 0.0342151935 0.0639671162 0.0047420278 0.0247440000 394330073 0 402718720 0.0642316937 -0.0193487164 -0.0045712888 846 1311867746.8401610851 0.0592048727 0.0342447322 0.0639671162 0.0047396901 0.0248690000 394332981 0 402718720 0.0638537630 -0.0197379552 -0.0051183980 847 1311867746.8748359680 0.0623901375 0.0342779617 0.0639671162 0.0047439177 0.0248670000 394336561 0 402718720 0.0649079159 -0.0189470481 -0.0025687907 848 1311867746.9086029530 0.0511306934 0.0342978352 0.0639671162 0.0047720352 0.0345270000 394339469 0 402718720 0.0647895560 -0.0211388040 -0.0139855538 849 1311867746.9389610291 0.0559485182 0.0343233366 0.0639671162 0.0047738289 0.0243920000 394342713 0 402718720 0.0640358701 -0.0202313736 -0.0092324894 850 1311867746.9748229980 0.0599431582 0.0343534775 0.0639671162 0.0047751285 0.0336250000 394345989 0 402718720 0.0638132766 -0.0190139096 -0.0056062974 851 1311867747.0066559315 0.0553763807 0.0343781813 0.0639671162 0.0047776922 0.0245090000 394349033 0 402718720 0.0643891171 -0.0204892214 -0.0100039300 852 1311867747.0389339924 0.0554745086 0.0344029423 0.0639671162 0.0047754752 0.0242110000 394352181 0 402718720 0.0653554872 -0.0199064314 -0.0102696531 853 1311867747.0749640465 0.0541905388 0.0344261399 0.0639671162 0.0047763545 0.0267400000 394751253 0 402718720 0.0646245256 -0.0222787932 -0.0109741595 854 1311867747.1066820621 0.0576429702 0.0344533259 0.0639671162 0.0047864781 0.0682710000 394717677 0 402718720 0.0652328357 -0.0219309796 -0.0082273819 855 1311867747.1389479637 0.0535626747 0.0344756760 0.0639671162 0.0047849429 0.0634360000 394728725 0 402718720 0.0658408701 -0.0199019630 -0.0132169314 856 1311867747.1744880676 0.0596800745 0.0345051204 0.0639671162 0.0047916973 0.0581950000 401261325 0 402718720 0.0665672570 -0.0198149253 -0.0069178883 857 1311867747.2066030502 0.0639027059 0.0345394233 0.0639671162 0.0047905226 0.0475090000 401193129 0 402718720 0.0670983642 -0.0196865480 -0.0027738120 858 1311867747.2385439873 0.0626319945 0.0345721652 0.0639671162 0.0047900034 0.0682500000 399826213 0 402718720 0.0673528314 -0.0194345582 -0.0044534337 859 1311867747.2745490074 0.0627083853 0.0346049198 0.0639671162 0.0048041404 0.0247800000 394695061 0 402718720 0.0673054829 -0.0182428546 -0.0046510845 860 1311867747.3064720631 0.0630022213 0.0346379400 0.0639671162 0.0048104559 0.0246870000 394698129 0 402718720 0.0662823021 -0.0183900520 -0.0048458241 861 1311867747.3388469219 0.0634484589 0.0346714017 0.0639671162 0.0048273131 0.0244930000 394701213 0 402718720 0.0683180094 -0.0196830370 -0.0045849308 862 1311867747.3758800030 0.0619093888 0.0347030003 0.0639671162 0.0048323463 0.0243600000 394704513 0 402718720 0.0673047900 -0.0216206424 -0.0059051644 863 1311867747.4068729877 0.0639932230 0.0347369403 0.0639932230 0.0048320490 0.0246700000 394707821 0 402718720 0.0678713173 -0.0197441913 -0.0043389443 864 1311867747.4396450520 0.0607160926 0.0347670087 0.0639932230 0.0048318358 0.0242630000 394710945 0 402718720 0.0682701468 -0.0200945828 -0.0082665551 865 1311867747.4756069183 0.0628038347 0.0347994212 0.0639932230 0.0048342505 0.0243590000 394714077 0 402718720 0.0681514889 -0.0205852669 -0.0060384944 866 1311867747.5095520020 0.0653554499 0.0348347053 0.0653554499 0.0048359977 0.0239900000 394717449 0 402718720 0.0683527514 -0.0179454666 -0.0040575303 867 1311867747.5405330658 0.0641799718 0.0348685522 0.0653554499 0.0048417692 0.0244270000 394720557 0 402718720 0.0688293874 -0.0174532812 -0.0057109371 868 1311867747.5766739845 0.0601412877 0.0348976683 0.0653554499 0.0048479628 0.0356090000 394723833 0 402718720 0.0686280951 -0.0219068229 -0.0091713797 869 1311867747.6086390018 0.0587592423 0.0349251270 0.0653554499 0.0048477011 0.0374990000 394727061 0 402718720 0.0680537894 -0.0211414210 -0.0106764697 870 1311867747.6432039738 0.0600612462 0.0349540190 0.0653554499 0.0048459121 0.0243820000 394730481 0 402718720 0.0694170818 -0.0194591470 -0.0100626759 871 1311867747.6760280132 0.0562104024 0.0349784236 0.0653554499 0.0048590710 0.0246220000 394733629 0 402718720 0.0678678006 -0.0210963786 -0.0134064890 872 1311867747.7068400383 0.0654464364 0.0350133640 0.0654464364 0.0048748816 0.0241890000 394736481 0 402718720 0.0698666275 -0.0187031925 -0.0048844572 873 1311867747.7480750084 0.0615471452 0.0350437578 0.0654464364 0.0048734003 0.0247360000 394740021 0 402718720 0.0678431615 -0.0199829470 -0.0087935328 874 1311867747.7826869488 0.0643603504 0.0350773008 0.0654464364 0.0048720392 0.0242450000 394743625 0 402718720 0.0678919032 -0.0195378438 -0.0062235221 875 1311867747.8149020672 0.0670038015 0.0351137882 0.0670038015 0.0048766465 0.0245980000 394746565 0 402718720 0.0669192374 -0.0196226109 -0.0035104770 876 1311867747.8466539383 0.0617452264 0.0351441894 0.0670038015 0.0048825622 0.0425940000 395141013 0 402718720 0.0663338304 -0.0179956686 -0.0092436392 877 1311867747.8827810287 0.0620118231 0.0351748253 0.0670038015 0.0048806782 0.0670200000 395101989 0 402718720 0.0662728846 -0.0174819734 -0.0090436190 878 1311867747.9150440693 0.0651272386 0.0352089396 0.0670038015 0.0048821090 0.0600650000 397352373 0 402718720 0.0665311068 -0.0181645341 -0.0057142973 879 1311867747.9477820396 0.0635202825 0.0352411482 0.0670038015 0.0048811005 0.0500770000 401545409 0 402718720 0.0650216192 -0.0176460780 -0.0069435034 880 1311867747.9826579094 0.0663235933 0.0352764692 0.0670038015 0.0048827947 0.0484330000 401393165 0 402718720 0.0653840154 -0.0145493839 -0.0046016332 881 1311867748.0146598816 0.0594133362 0.0353038663 0.0670038015 0.0048914052 0.0720240000 400101903 0 402718720 0.0644987822 -0.0180806238 -0.0103346929 882 1311867748.0469269753 0.0619021170 0.0353340230 0.0670038015 0.0048899956 0.0342750000 395120497 0 402718720 0.0651623979 -0.0173723865 -0.0072659887 883 1311867748.0828750134 0.0636274591 0.0353660654 0.0670038015 0.0048896832 0.0250470000 395123893 0 402718720 0.0647178888 -0.0150708314 -0.0054928213 884 1311867748.1150569916 0.0654097348 0.0354000515 0.0670038015 0.0048878011 0.0256000000 395126873 0 402718720 0.0641214922 -0.0149428872 -0.0031449366 885 1311867748.1486010551 0.0620042719 0.0354301128 0.0670038015 0.0048904466 0.0251730000 395129837 0 402718720 0.0632795095 -0.0163185131 -0.0057815313 886 1311867748.1831040382 0.0621968657 0.0354603235 0.0670038015 0.0048878646 0.0249710000 395133241 0 402718720 0.0620392039 -0.0159869045 -0.0052849595 887 1311867748.2148320675 0.0599448904 0.0354879273 0.0670038015 0.0048869039 0.0248310000 395136285 0 402718720 0.0614952296 -0.0166343357 -0.0071155466 888 1311867748.2466599941 0.0634301156 0.0355193938 0.0670038015 0.0048961502 0.0249910000 395139633 0 402718720 0.0614917725 -0.0146309221 -0.0042563360 889 1311867748.2827599049 0.0597957596 0.0355467013 0.0670038015 0.0048957127 0.0247530000 395142909 0 402718720 0.0601565428 -0.0165784433 -0.0072120670 890 1311867748.3148829937 0.0632149503 0.0355777892 0.0670038015 0.0048954458 0.0250750000 395145929 0 402718720 0.0610560179 -0.0140640689 -0.0040953197 891 1311867748.3470869064 0.0621788353 0.0356076444 0.0670038015 0.0048979531 0.0250820000 395149221 0 402718720 0.0617869049 -0.0157750305 -0.0051986445 892 1311867748.3826999664 0.0592563748 0.0356341565 0.0670038015 0.0048957298 0.0252400000 395152449 0 402718720 0.0610833131 -0.0149627337 -0.0082465485 893 1311867748.4148259163 0.0616893284 0.0356633336 0.0670038015 0.0048950058 0.0254040000 395155605 0 402718720 0.0610538870 -0.0134134786 -0.0057004690 894 1311867748.4520189762 0.0597494505 0.0356902756 0.0670038015 0.0049072163 0.0380970000 395158937 0 402718720 0.0602644011 -0.0147877447 -0.0070497524 895 1311867748.4831318855 0.0580371879 0.0357152442 0.0670038015 0.0049071022 0.0250730000 395162101 0 402718720 0.0593861267 -0.0156501271 -0.0081035960 896 1311867748.5149960518 0.0585715845 0.0357407535 0.0670038015 0.0049089348 0.0252870000 395165265 0 402718720 0.0585104898 -0.0140335066 -0.0069541689 897 1311867748.5467929840 0.0598501191 0.0357676313 0.0670038015 0.0049079959 0.0253710000 395168533 0 402718720 0.0578493476 -0.0143524399 -0.0054594837 898 1311867748.5827159882 0.0601392128 0.0357947711 0.0670038015 0.0049062889 0.0442990000 395171745 0 402718720 0.0589995608 -0.0123718670 -0.0054485984 899 1311867748.6147999763 0.0610415824 0.0358228543 0.0670038015 0.0049047155 0.0253940000 395174885 0 402718720 0.0578634851 -0.0112563157 -0.0043673962 900 1311867748.6470849514 0.0577552877 0.0358472237 0.0670038015 0.0049306089 0.0538450000 395178185 0 402718720 0.0572375953 -0.0145525839 -0.0056324899 901 1311867748.6827559471 0.0577015579 0.0358714793 0.0670038015 0.0049279255 0.0254060000 395181653 0 402718720 0.0567292795 -0.0143448189 -0.0054168627 902 1311867748.7147359848 0.0585542433 0.0358966265 0.0670038015 0.0049468139 0.0258880000 395184417 0 402718720 0.0566678643 -0.0145493634 -0.0050662197 903 1311867748.7499361038 0.0592492186 0.0359224877 0.0670038015 0.0049444804 0.0255350000 395187621 0 402718720 0.0567195266 -0.0140564088 -0.0044356696 904 1311867748.7828259468 0.0588858984 0.0359478897 0.0670038015 0.0049417933 0.0262240000 395191201 0 402718720 0.0555334687 -0.0146062905 -0.0044259969 905 1311867748.8151619434 0.0550967716 0.0359690486 0.0670038015 0.0049413283 0.0503320000 395194461 0 402718720 0.0538545623 -0.0152920708 -0.0079297926 906 1311867748.8466329575 0.0553947650 0.0359904898 0.0670038015 0.0049390985 0.0253810000 395197561 0 402718720 0.0540788732 -0.0135006737 -0.0080435388 907 1311867748.8829579353 0.0589847118 0.0360158418 0.0670038015 0.0049420554 0.0261890000 395201077 0 402718720 0.0539348572 -0.0130265839 -0.0033356789 908 1311867748.9149119854 0.0593464747 0.0360415363 0.0670038015 0.0049396761 0.0259180000 395203849 0 402718720 0.0526884459 -0.0142410398 -0.0020291265 909 1311867748.9472498894 0.0573779829 0.0360650088 0.0670038015 0.0049387853 0.0255080000 395207333 0 402718720 0.0533564165 -0.0134691410 -0.0039300695 910 1311867748.9829359055 0.0558337197 0.0360867326 0.0670038015 0.0049366041 0.0259110000 395210385 0 402718720 0.0520959124 -0.0125237210 -0.0052842796 911 1311867749.0159859657 0.0550049618 0.0361074991 0.0670038015 0.0049348812 0.0261520000 395213869 0 402718720 0.0506274030 -0.0131856864 -0.0054200757 912 1311867749.0467190742 0.0561523028 0.0361294780 0.0670038015 0.0049323652 0.0261990000 395216769 0 402718720 0.0520830378 -0.0133141633 -0.0037948638 913 1311867749.0828969479 0.0568375997 0.0361521594 0.0670038015 0.0049309999 0.0263720000 395219965 0 402718720 0.0499350615 -0.0127285803 -0.0029547121 914 1311867749.1158421040 0.0525185317 0.0361700657 0.0670038015 0.0049308350 0.0258050000 395223505 0 402718720 0.0501852445 -0.0116586210 -0.0075707324 915 1311867749.1485249996 0.0551439896 0.0361908023 0.0670038015 0.0049295537 0.0260490000 395226389 0 402718720 0.0491723679 -0.0112261428 -0.0043764375 916 1311867749.1829619408 0.0536379851 0.0362098494 0.0670038015 0.0049272970 0.0259600000 395229561 0 402718720 0.0487431213 -0.0121145686 -0.0052769445 917 1311867749.2156000137 0.0527776256 0.0362279168 0.0670038015 0.0049269046 0.0260640000 395232749 0 402718720 0.0481576473 -0.0134336697 -0.0056628585 918 1311867749.2468719482 0.0541058481 0.0362473916 0.0670038015 0.0049243189 0.0262700000 395236081 0 402718720 0.0500327274 -0.0140230255 -0.0043031368 919 1311867749.2828478813 0.0525822714 0.0362651663 0.0670038015 0.0049231888 0.0260350000 395239293 0 402718720 0.0487695932 -0.0120109515 -0.0064327400 920 1311867749.3148140907 0.0526106879 0.0362829331 0.0670038015 0.0049211596 0.0390840000 395242785 0 402718720 0.0479711965 -0.0118210716 -0.0064640008 921 1311867749.3468968868 0.0567087270 0.0363051110 0.0670038015 0.0049212724 0.0264280000 395245813 0 402718720 0.0482677445 -0.0107632196 -0.0022687949 922 1311867749.3828470707 0.0520351566 0.0363221718 0.0670038015 0.0049247474 0.0261510000 395249201 0 402718720 0.0472673364 -0.0134149464 -0.0059850849 923 1311867749.4147930145 0.0512122102 0.0363383040 0.0670038015 0.0049228399 0.0255990000 395252181 0 402718720 0.0455584452 -0.0101517653 -0.0074604061 924 1311867749.4467489719 0.0518659353 0.0363551088 0.0670038015 0.0049201818 0.0257930000 395255401 0 402718720 0.0457542241 -0.0094099464 -0.0062954258 925 1311867749.4829080105 0.0510681495 0.0363710148 0.0670038015 0.0049181827 0.0261900000 395258757 0 402718720 0.0447367653 -0.0117274262 -0.0055368375 926 1311867749.5159850121 0.0543700941 0.0363904522 0.0670038015 0.0049198836 0.0260120000 395262289 0 402718720 0.0445758700 -0.0108984122 -0.0020107757 927 1311867749.5468530655 0.0542389117 0.0364097062 0.0670038015 0.0049174817 0.0261090000 395265245 0 402718720 0.0428655632 -0.0109913610 -0.0018966161 928 1311867749.5830268860 0.0562067144 0.0364310392 0.0670038015 0.0049156824 0.0261930000 395268553 0 402718720 0.0424868912 -0.0105233360 0.0002580602 929 1311867749.6148250103 0.0560713485 0.0364521805 0.0670038015 0.0049133504 0.0262510000 395271501 0 402718720 0.0411649980 -0.0109157702 0.0002199765 930 1311867749.6469049454 0.0545539185 0.0364716448 0.0670038015 0.0049109823 0.0263410000 395275009 0 402718720 0.0404483229 -0.0120619442 -0.0010796897 931 1311867749.6829149723 0.0544281900 0.0364909322 0.0670038015 0.0049087692 0.0263380000 395278029 0 402718720 0.0411672071 -0.0095599275 -0.0021362137 932 1311867749.7160799503 0.0562103242 0.0365120903 0.0670038015 0.0049072544 0.0260610000 395281609 0 402718720 0.0396244600 -0.0101529546 -0.0002853125 933 1311867749.7468609810 0.0522400849 0.0365289477 0.0670038015 0.0049051864 0.0257770000 395284645 0 402718720 0.0391222015 -0.0105485776 -0.0047831256 934 1311867749.7828791142 0.0531495959 0.0365467429 0.0670038015 0.0049039766 0.0265680000 395288081 0 402718720 0.0384289101 -0.0107674990 -0.0030223085 935 1311867749.8148949146 0.0523802973 0.0365636772 0.0670038015 0.0049073377 0.0262520000 395291317 0 402718720 0.0386049971 -0.0103035532 -0.0035601044 936 1311867749.8469030857 0.0474526323 0.0365753107 0.0670038015 0.0049090102 0.0388420000 395294393 0 402718720 0.0373746268 -0.0115144635 -0.0082972273 937 1311867749.8829030991 0.0526657328 0.0365924829 0.0670038015 0.0049435283 0.0263470000 395297717 0 402718720 0.0377696529 -0.0096580228 -0.0039555468 938 1311867749.9149639606 0.0526370071 0.0366095880 0.0670038015 0.0049575765 0.0259310000 395300905 0 402718720 0.0350171961 -0.0097289803 -0.0030547362 939 1311867749.9508709908 0.0480622947 0.0366217847 0.0670038015 0.0049587671 0.0258430000 395304197 0 402718720 0.0366298854 -0.0105340621 -0.0074414443 940 1311867749.9827940464 0.0488737859 0.0366348187 0.0670038015 0.0049593443 0.0262480000 395307433 0 402718720 0.0347478203 -0.0097595993 -0.0069472417 941 1311867750.0147750378 0.0484226197 0.0366473456 0.0670038015 0.0049580147 0.0263630000 395310789 0 402718720 0.0345278755 -0.0091215717 -0.0074402718 942 1311867750.0470709801 0.0453286059 0.0366565614 0.0670038015 0.0049574240 0.0261870000 395313633 0 402718720 0.0340732001 -0.0105917947 -0.0100416504 943 1311867750.0829339027 0.0486523621 0.0366692823 0.0670038015 0.0049588665 0.0261600000 395317213 0 402718720 0.0325757451 -0.0100403465 -0.0063292636 944 1311867750.1156458855 0.0469739698 0.0366801982 0.0670038015 0.0049563532 0.0357120000 395320345 0 402718720 0.0318754315 -0.0103344712 -0.0078271870 945 1311867750.1474790573 0.0458237305 0.0366898739 0.0670038015 0.0049541175 0.0263820000 395323573 0 402718720 0.0320625566 -0.0103554036 -0.0086309742 946 1311867750.1828711033 0.0439771041 0.0366975771 0.0670038015 0.0049532227 0.0269180000 395326641 0 402718720 0.0302451495 -0.0102065308 -0.0104978662 947 1311867750.2156589031 0.0459700897 0.0367073686 0.0670038015 0.0049521043 0.0267030000 395329917 0 402718720 0.0306651182 -0.0088236993 -0.0083579971 948 1311867750.2469079494 0.0435423180 0.0367145785 0.0670038015 0.0049504420 0.0268390000 395333345 0 402718720 0.0297005624 -0.0090395287 -0.0104761198 949 1311867750.2829968929 0.0423813164 0.0367205497 0.0670038015 0.0049492210 0.0269880000 395336253 0 402718720 0.0290791895 -0.0086182198 -0.0112497080 950 1311867750.3150129318 0.0436221808 0.0367278146 0.0670038015 0.0049468586 0.0271920000 395339601 0 402718720 0.0299103130 -0.0087717483 -0.0093315616 951 1311867750.3469090462 0.0443842895 0.0367358656 0.0670038015 0.0049442961 0.0270230000 395342725 0 402718720 0.0295427609 -0.0092845019 -0.0079824887 952 1311867750.3828659058 0.0424649715 0.0367418836 0.0670038015 0.0049425758 0.0273410000 395345729 0 402718720 0.0299142506 -0.0088075614 -0.0097851641 953 1311867750.4148640633 0.0438498743 0.0367493421 0.0670038015 0.0049409172 0.0272850000 395349365 0 402718720 0.0289495699 -0.0084241796 -0.0080840420 954 1311867750.4469859600 0.0437482558 0.0367566785 0.0670038015 0.0049385561 0.0269400000 395352409 0 402718720 0.0280449297 -0.0080236066 -0.0081155580 955 1311867750.4829618931 0.0420433506 0.0367622143 0.0670038015 0.0049372795 0.0265060000 395355837 0 402718720 0.0272030234 -0.0078440234 -0.0100410748 956 1311867750.5148859024 0.0430988967 0.0367688426 0.0670038015 0.0049349058 0.0266330000 395358769 0 402718720 0.0255217068 -0.0095179956 -0.0081287241 957 1311867750.5476069450 0.0396739244 0.0367718782 0.0670038015 0.0049348271 0.0269630000 395362213 0 402718720 0.0266781710 -0.0089120856 -0.0118499380 958 1311867750.5827779770 0.0398062207 0.0367750456 0.0670038015 0.0049343632 0.0271560000 395365441 0 402718720 0.0278472137 -0.0062729511 -0.0125342980 959 1311867750.6148829460 0.0368638150 0.0367751381 0.0670038015 0.0049327981 0.0267910000 395368613 0 402718720 0.0274015237 -0.0070409887 -0.0150648784 960 1311867750.6469810009 0.0397485234 0.0367782354 0.0670038015 0.0049320371 0.0375440000 395371929 0 402718720 0.0249792580 -0.0067735570 -0.0119323861 961 1311867750.6829319000 0.0402527042 0.0367818509 0.0670038015 0.0049326385 0.0270030000 395375173 0 402718720 0.0254144669 -0.0058555445 -0.0108016664 962 1311867750.7149219513 0.0386730283 0.0367838168 0.0670038015 0.0049318471 0.0275760000 395378409 0 402718720 0.0249482878 -0.0070105060 -0.0113108847 963 1311867750.7469151020 0.0390927941 0.0367862145 0.0670038015 0.0049341392 0.0270750000 395381341 0 402718720 0.0247942135 -0.0072321291 -0.0103504732 964 1311867750.7832129002 0.0395536572 0.0367890853 0.0670038015 0.0049325647 0.0272020000 395384737 0 402718720 0.0227310359 -0.0068509313 -0.0098198801 965 1311867750.8149549961 0.0360660665 0.0367883360 0.0670038015 0.0049333471 0.0275710000 395387693 0 402718720 0.0244016070 -0.0057901330 -0.0132104894 966 1311867750.8468461037 0.0341585502 0.0367856137 0.0670038015 0.0049350408 0.0270380000 395391065 0 402718720 0.0223732758 -0.0098580429 -0.0133483419 967 1311867750.8828840256 0.0366641991 0.0367854881 0.0670038015 0.0049360922 0.0274180000 395394557 0 402718720 0.0254136622 -0.0056106863 -0.0110568730 968 1311867750.9147970676 0.0354441330 0.0367841024 0.0670038015 0.0049336278 0.0273460000 395397665 0 402718720 0.0246199556 -0.0051307622 -0.0125844870 969 1311867750.9468770027 0.0354904607 0.0367827674 0.0670038015 0.0049321976 0.0274740000 395400717 0 402718720 0.0245263558 -0.0061490848 -0.0113407169 970 1311867750.9830369949 0.0343070440 0.0367802151 0.0670038015 0.0049313075 0.0270720000 395404113 0 402718720 0.0209358912 -0.0092017772 -0.0122777112 971 1311867751.0168409348 0.0398008786 0.0367833260 0.0670038015 0.0049412591 0.0270280000 395407157 0 402718720 0.0243828911 -0.0019521073 -0.0082830405 972 1311867751.0470340252 0.0335577168 0.0367800074 0.0670038015 0.0049483601 0.0269650000 395410457 0 402718720 0.0205798019 -0.0069824737 -0.0133128418 973 1311867751.0828599930 0.0342089012 0.0367773650 0.0670038015 0.0049486833 0.0266670000 395413549 0 402718720 0.0220896658 -0.0056330748 -0.0124900639 974 1311867751.1174809933 0.0292941406 0.0367696820 0.0670038015 0.0049514128 0.0263440000 395416713 0 402718720 0.0202234052 -0.0088459039 -0.0171080325 975 1311867751.1468789577 0.0319482498 0.0367647370 0.0670038015 0.0049517435 0.0269400000 395419973 0 402718720 0.0182759427 -0.0081286402 -0.0152440872 976 1311867751.1835930347 0.0268089157 0.0367545363 0.0670038015 0.0049545545 0.0368140000 395423529 0 402718720 0.0194701105 -0.0073420010 -0.0207456052 977 1311867751.2161049843 0.0296532009 0.0367472678 0.0670038015 0.0049530316 0.0271770000 395426677 0 402718720 0.0154661704 -0.0106272735 -0.0175349265 978 1311867751.2468481064 0.0293230340 0.0367396766 0.0670038015 0.0049517461 0.0272910000 395429657 0 402718720 0.0195350740 -0.0076973075 -0.0171949361 979 1311867751.2831909657 0.0290743969 0.0367318469 0.0670038015 0.0049522760 0.0271460000 395432845 0 402718720 0.0193449426 -0.0043391613 -0.0189528689 980 1311867751.3149859905 0.0293735918 0.0367243384 0.0670038015 0.0049499038 0.0268250000 395436321 0 402718720 0.0181741863 -0.0078108967 -0.0168483369 981 1311867751.3498640060 0.0295496788 0.0367170248 0.0670038015 0.0049473995 0.0268720000 395439485 0 402718720 0.0173451360 -0.0083770016 -0.0164949615 982 1311867751.3834669590 0.0240818895 0.0367041581 0.0670038015 0.0049563972 0.0268700000 395442561 0 402718720 0.0160998777 -0.0092081539 -0.0235458612 983 1311867751.4151160717 0.0242448933 0.0366914834 0.0670038015 0.0049549313 0.0272940000 395445773 0 402718720 0.0156808626 -0.0109132845 -0.0230137017 984 1311867751.4513890743 0.0251760017 0.0366797806 0.0670038015 0.0049583707 0.0269000000 395448993 0 402718720 0.0167286843 -0.0109061794 -0.0210522041 985 1311867751.4838130474 0.0234022271 0.0366663009 0.0670038015 0.0049575555 0.0271730000 395452197 0 402718720 0.0160148386 -0.0091847144 -0.0250218865 986 1311867751.5149779320 0.0239985753 0.0366534533 0.0670038015 0.0049564597 0.0386370000 395455425 0 402718720 0.0154619450 -0.0086916443 -0.0243844744 987 1311867751.5495769978 0.0263987165 0.0366430635 0.0670038015 0.0049579177 0.0273700000 395458533 0 402718720 0.0160490610 -0.0087978020 -0.0202700030 988 1311867751.5829720497 0.0247266460 0.0366310023 0.0670038015 0.0049559332 0.0268080000 395461889 0 402718720 0.0162586290 -0.0079084234 -0.0229173023 989 1311867751.6149520874 0.0258748252 0.0366201265 0.0670038015 0.0049560796 0.0271730000 395465165 0 402718720 0.0157783777 -0.0081727309 -0.0212705620 990 1311867751.6501350403 0.0224758908 0.0366058394 0.0670038015 0.0049561347 0.0273260000 395468113 0 402718720 0.0163953919 -0.0091074966 -0.0243201815 991 1311867751.6839730740 0.0244338010 0.0365935568 0.0670038015 0.0049548367 0.0272590000 395471517 0 402718720 0.0166668743 -0.0092836767 -0.0211450569 992 1311867751.7150709629 0.0222521797 0.0365790998 0.0670038015 0.0049558810 0.0274870000 395474585 0 402718720 0.0148828551 -0.0096494295 -0.0249552634 993 1311867751.7507519722 0.0208152905 0.0365632249 0.0670038015 0.0049555544 0.0272240000 395477893 0 402718720 0.0139630046 -0.0110490657 -0.0267839190 994 1311867751.7830109596 0.0225222316 0.0365490991 0.0670038015 0.0049549227 0.0270580000 395480657 0 402718720 0.0143902171 -0.0101436339 -0.0237142965 995 1311867751.8149600029 0.0260272641 0.0365385244 0.0670038015 0.0049554090 0.0273550000 395484157 0 402718720 0.0155136194 -0.0077640964 -0.0189629775 996 1311867751.8509531021 0.0209933054 0.0365229168 0.0670038015 0.0049638746 0.0395400000 395487545 0 402718720 0.0145783750 -0.0085097943 -0.0259844251 997 1311867751.8832330704 0.0251606777 0.0365115203 0.0670038015 0.0049702157 0.0272820000 395490677 0 402718720 0.0143679529 -0.0085233720 -0.0193114411 998 1311867751.9149179459 0.0207928345 0.0364957701 0.0670038015 0.0049744295 0.0274510000 395493849 0 402718720 0.0136694685 -0.0083152400 -0.0253171232 999 1311867751.9530611038 0.0196892302 0.0364789468 0.0670038015 0.0049727210 0.0270110000 395497429 0 402718720 0.0140135344 -0.0096716201 -0.0245809201 1000 1311867751.9829521179 0.0206682030 0.0364631360 0.0670038015 0.0049720515 0.0267700000 395500265 0 402718720 0.0140038971 -0.0078305127 -0.0236818269 1001 1311867752.0153670311 0.0240570772 0.0364507424 0.0670038015 0.0049778017 0.0272900000 395503629 0 402718720 0.0141861364 -0.0060735885 -0.0187411960 1002 1311867752.0510330200 0.0292766169 0.0364435826 0.0670038015 0.0049875909 0.0272280000 395506713 0 402718720 0.0141775198 -0.0064836545 -0.0114457728 1003 1311867752.0828928947 0.0247109309 0.0364318850 0.0670038015 0.0049912145 0.0269680000 395509885 0 402718720 0.0136836739 -0.0073943171 -0.0161106978 1004 1311867752.1150529385 0.0235755164 0.0364190799 0.0670038015 0.0049895025 0.0275490000 395513137 0 402718720 0.0152780870 -0.0050565763 -0.0174247902 1005 1311867752.1509859562 0.0248892978 0.0364076074 0.0670038015 0.0049926282 0.0390780000 395516701 0 402718720 0.0129291108 -0.0063850717 -0.0149496868 1006 1311867752.1829679012 0.0253243279 0.0363965903 0.0670038015 0.0049924840 0.0325360000 396071885 0 402718720 0.0140696447 -0.0070709912 -0.0126198782 1007 1311867752.2150039673 0.0221568774 0.0363824495 0.0670038015 0.0049913009 0.0902660000 396046013 0 402718720 0.0137209967 -0.0072229682 -0.0158613250 1008 1311867752.2512340546 0.0232453663 0.0363694167 0.0670038015 0.0049895415 0.0822000000 396050865 0 402718720 0.0129658226 -0.0062163360 -0.0144356675 1009 1311867752.2833271027 0.0223149210 0.0363554876 0.0670038015 0.0049882447 0.0774430000 399005369 0 402718720 0.0142305633 -0.0071986290 -0.0140468255 1010 1311867752.3150799274 0.0200961623 0.0363393892 0.0670038015 0.0049893112 0.0626880000 403982037 0 402718720 0.0133939516 -0.0087634139 -0.0163970217 1011 1311867752.3509979248 0.0214278027 0.0363246399 0.0670038015 0.0049886148 0.0673210000 403730533 0 402718720 0.0127845965 -0.0081030177 -0.0153052378 1012 1311867752.3829851151 0.0261679422 0.0363146036 0.0670038015 0.0049912144 0.0901340000 402458451 0 402718720 0.0127749294 -0.0072570588 -0.0100990087 1013 1311867752.4160280228 0.0230719354 0.0363015309 0.0670038015 0.0049914736 0.0404300000 396063317 0 402718720 0.0125945173 -0.0078310929 -0.0136329848 1014 1311867752.4510710239 0.0213300176 0.0362867661 0.0670038015 0.0049998365 0.0291680000 396066545 0 402718720 0.0123941768 -0.0089120846 -0.0152562987 1015 1311867752.4829080105 0.0230001789 0.0362736759 0.0670038015 0.0050005453 0.0290340000 396069885 0 402718720 0.0112503488 -0.0105040018 -0.0140363062 1016 1311867752.5181159973 0.0260466598 0.0362636099 0.0670038015 0.0049994705 0.0287120000 396072873 0 402718720 0.0101413224 -0.0084030712 -0.0114844367 1017 1311867752.5511059761 0.0228370018 0.0362504077 0.0670038015 0.0049980752 0.0402600000 396076149 0 402718720 0.0102237128 -0.0095212990 -0.0154380547 1018 1311867752.5830090046 0.0239401869 0.0362383152 0.0670038015 0.0049967561 0.0290730000 396079385 0 402718720 0.0112237902 -0.0084666638 -0.0137807112 1019 1311867752.6167891026 0.0233419333 0.0362256593 0.0670038015 0.0049945792 0.0299780000 396082885 0 402718720 0.0104795750 -0.0100960918 -0.0147870760 1020 1311867752.6514921188 0.0238575209 0.0362135336 0.0670038015 0.0049944319 0.0301950000 396085881 0 402718720 0.0096981991 -0.0100775845 -0.0148230633 1021 1311867752.6830079556 0.0261680260 0.0362036947 0.0670038015 0.0050001815 0.0300980000 396088965 0 402718720 0.0098237349 -0.0095712803 -0.0125621511 1022 1311867752.7152869701 0.0260541514 0.0361937637 0.0670038015 0.0049991788 0.0297090000 396092233 0 402718720 0.0105625791 -0.0101588601 -0.0127215115 1023 1311867752.7510609627 0.0253949407 0.0361832076 0.0670038015 0.0049967562 0.0300800000 396095381 0 402718720 0.0116455229 -0.0094585950 -0.0136475377 1024 1311867752.7830440998 0.0241143927 0.0361714217 0.0670038015 0.0049966018 0.0294490000 396098793 0 402718720 0.0112923803 -0.0086772349 -0.0161482636 1025 1311867752.8162839413 0.0255862009 0.0361610947 0.0670038015 0.0049943064 0.0302080000 396200245 0 402718720 0.0094784144 -0.0106041003 -0.0151728392 1026 1311867752.8511059284 0.0263671502 0.0361515489 0.0670038015 0.0049920588 0.0301500000 396408329 0 402718720 0.0094082002 -0.0101680141 -0.0145775499 1027 1311867752.8833000660 0.0268208981 0.0361424636 0.0670038015 0.0049898180 0.0294630000 396411661 0 402718720 0.0094424244 -0.0094843656 -0.0140243135 1028 1311867752.9183809757 0.0244192220 0.0361310596 0.0670038015 0.0049880235 0.0294210000 396414569 0 402718720 0.0120114889 -0.0075465036 -0.0161374174 1029 1311867752.9511129856 0.0256525781 0.0361208765 0.0670038015 0.0049877909 0.0295210000 396417741 0 402718720 0.0112761687 -0.0087401764 -0.0145220291 1030 1311867752.9828579426 0.0268600564 0.0361118854 0.0670038015 0.0049859792 0.0296750000 396421073 0 402718720 0.0112332776 -0.0083068768 -0.0133866426 1031 1311867753.0168170929 0.0223510135 0.0360985383 0.0670038015 0.0049872170 0.0297810000 396424093 0 402718720 0.0133787598 -0.0080613727 -0.0179040506 1032 1311867753.0510199070 0.0258511323 0.0360886086 0.0670038015 0.0049862383 0.0417480000 396427617 0 402718720 0.0102559952 -0.0105249677 -0.0152924042 1033 1311867753.0829060078 0.0235335901 0.0360764547 0.0670038015 0.0049840790 0.0305320000 396430485 0 402718720 0.0110266395 -0.0087377951 -0.0181487836 1034 1311867753.1184310913 0.0248013455 0.0360655503 0.0670038015 0.0049820461 0.0304250000 396433737 0 402718720 0.0099735381 -0.0090543674 -0.0172037333 1035 1311867753.1510760784 0.0271566845 0.0360569427 0.0670038015 0.0049802331 0.0302040000 396437037 0 402718720 0.0090563809 -0.0121545224 -0.0145424716 1036 1311867753.1830070019 0.0251872633 0.0360464507 0.0670038015 0.0049779726 0.0426880000 396440049 0 402718720 0.0090323836 -0.0098419674 -0.0170596801 1037 1311867753.2186999321 0.0233006384 0.0360341597 0.0670038015 0.0049757474 0.0303020000 396443397 0 402718720 0.0100313872 -0.0084268386 -0.0188410543 1038 1311867753.2520470619 0.0244401302 0.0360229901 0.0670038015 0.0049741958 0.0298640000 396446521 0 402718720 0.0097120441 -0.0080383513 -0.0173720513 1039 1311867753.2829909325 0.0229050424 0.0360103645 0.0670038015 0.0049752639 0.0417440000 396449661 0 402718720 0.0087129213 -0.0103807040 -0.0188002996 1040 1311867753.3196740150 0.0235482547 0.0359983817 0.0670038015 0.0049798236 0.0387530000 396453185 0 402718720 0.0085235341 -0.0072528902 -0.0178337935 1041 1311867753.3509368896 0.0213877615 0.0359843466 0.0670038015 0.0049783739 0.0384600000 396456317 0 402718720 0.0095052002 -0.0087185381 -0.0190748442 1042 1311867753.3829340935 0.0216508172 0.0359705908 0.0670038015 0.0049767215 0.0654520000 396459441 0 402718720 0.0088476967 -0.0105628055 -0.0186217502 1043 1311867753.4182109833 0.0215013996 0.0359567181 0.0670038015 0.0049745526 0.0301910000 396462477 0 402718720 0.0071792598 -0.0088126054 -0.0202230457 1044 1311867753.4511721134 0.0209964495 0.0359423884 0.0670038015 0.0049727505 0.0302640000 396465777 0 402718720 0.0062712952 -0.0113319512 -0.0212232154 1045 1311867753.4831509590 0.0207275115 0.0359278287 0.0670038015 0.0049710020 0.0306260000 396469093 0 402718720 0.0062520658 -0.0091448547 -0.0213976223 1046 1311867753.5199849606 0.0201880764 0.0359127811 0.0670038015 0.0049688807 0.0299410000 396472505 0 402718720 0.0062168292 -0.0091855302 -0.0217905734 1047 1311867753.5532789230 0.0203319564 0.0358978997 0.0670038015 0.0049670136 0.0554470000 396475653 0 402718720 0.0050077788 -0.0095568281 -0.0220607389 1048 1311867753.5832290649 0.0193351936 0.0358820956 0.0670038015 0.0049648164 0.0301650000 396478865 0 402718720 0.0046798787 -0.0093530556 -0.0232904088 1049 1311867753.6183180809 0.0186269134 0.0358656464 0.0670038015 0.0049629656 0.0303270000 396482125 0 402718720 0.0047224322 -0.0097501995 -0.0233283825 1050 1311867753.6509299278 0.0185233019 0.0358491299 0.0670038015 0.0049607514 0.0305370000 396485449 0 402718720 0.0043945350 -0.0104260975 -0.0230931584 1051 1311867753.6830120087 0.0173738636 0.0358315512 0.0670038015 0.0049589758 0.0301330000 396488413 0 402718720 0.0048002033 -0.0098344954 -0.0238226634 1052 1311867753.7204821110 0.0176891219 0.0358143055 0.0670038015 0.0049573866 0.0305930000 396491897 0 402718720 0.0045458032 -0.0079456819 -0.0232434757 1053 1311867753.7510209084 0.0178692974 0.0357972637 0.0670038015 0.0049586072 0.0410730000 396494917 0 402718720 0.0018120199 -0.0111888610 -0.0242265090 1054 1311867753.7865459919 0.0173981786 0.0357798073 0.0670038015 0.0049588556 0.0302000000 396498177 0 402718720 0.0012704115 -0.0092309471 -0.0244469363 1055 1311867753.8151860237 0.0149393426 0.0357600533 0.0670038015 0.0049584110 0.0392310000 396501421 0 402718720 0.0030254493 -0.0079246210 -0.0260877032 1056 1311867753.8510670662 0.0158769898 0.0357412246 0.0670038015 0.0049573930 0.0305180000 396504857 0 402718720 0.0016366513 -0.0094646364 -0.0246045273 1057 1311867753.8831698895 0.0165324807 0.0357230517 0.0670038015 0.0049606357 0.0305940000 396507709 0 402718720 -0.0004644701 -0.0128028523 -0.0252497643 1058 1311867753.9155960083 0.0147675341 0.0357032450 0.0670038015 0.0049595483 0.0309140000 396510929 0 402718720 0.0006901277 -0.0088047329 -0.0255707130 1059 1311867753.9511620998 0.0146897808 0.0356834023 0.0670038015 0.0049577989 0.0311020000 396514189 0 402718720 0.0004052450 -0.0082360581 -0.0249765888 1060 1311867753.9859020710 0.0146435406 0.0356635533 0.0670038015 0.0049572965 0.0311060000 396517609 0 402718720 -0.0001598634 -0.0112707298 -0.0242048800 1061 1311867754.0151760578 0.0138401669 0.0356429846 0.0670038015 0.0049555034 0.0313620000 396520597 0 402718720 -0.0017313838 -0.0115768388 -0.0255684592 1062 1311867754.0510439873 0.0145090725 0.0356230845 0.0670038015 0.0049581940 0.0472170000 396524249 0 402718720 -0.0031135525 -0.0091670621 -0.0252582021 1063 1311867754.0839149952 0.0146009084 0.0356033083 0.0670038015 0.0049564607 0.0312190000 396527253 0 402718720 -0.0030349363 -0.0097311419 -0.0236262381 1064 1311867754.1166028976 0.0128925890 0.0355819636 0.0670038015 0.0049567662 0.0313710000 396530257 0 402718720 -0.0031970718 -0.0107276160 -0.0250018686 1065 1311867754.1511039734 0.0133026177 0.0355610440 0.0670038015 0.0049610999 0.0316710000 396533637 0 402718720 -0.0037952468 -0.0094443504 -0.0238543376 1066 1311867754.1832261086 0.0113457823 0.0355383280 0.0670038015 0.0049633013 0.0315190000 396536857 0 402718720 -0.0033892053 -0.0093519129 -0.0250981841 1067 1311867754.2166349888 0.0122960135 0.0355165452 0.0670038015 0.0049658207 0.0314920000 396540101 0 402718720 -0.0050510634 -0.0094889458 -0.0234754086 1068 1311867754.2522869110 0.0115691293 0.0354941225 0.0670038015 0.0049721645 0.0414360000 396543377 0 402718720 -0.0065031890 -0.0102270860 -0.0248773135 1069 1311867754.2873370647 0.0100050271 0.0354702786 0.0670038015 0.0049789131 0.0316780000 396546941 0 402718720 -0.0051662093 -0.0086094681 -0.0235123206 1070 1311867754.3188319206 0.0115981959 0.0354479683 0.0670038015 0.0049771935 0.0427460000 396549961 0 402718720 -0.0079395799 -0.0090841586 -0.0224328022 1071 1311867754.3511719704 0.0101016695 0.0354243022 0.0670038015 0.0049765592 0.0320620000 396553333 0 402718720 -0.0070570908 -0.0106882332 -0.0223796107 1072 1311867754.3868899345 0.0088940775 0.0353995539 0.0670038015 0.0049759330 0.0324050000 396556513 0 402718720 -0.0070840297 -0.0094056074 -0.0227412321 1073 1311867754.4159760475 0.0088707842 0.0353748300 0.0670038015 0.0049740619 0.0328450000 396559485 0 402718720 -0.0075032972 -0.0110290106 -0.0222621094 1074 1311867754.4545960426 0.0072233034 0.0353486181 0.0670038015 0.0049828103 0.0326550000 396562617 0 402718720 -0.0065337946 -0.0104873478 -0.0213410333 1075 1311867754.4863700867 0.0079270573 0.0353231097 0.0670038015 0.0049884526 0.0443770000 396566053 0 402718720 -0.0068661943 -0.0126964282 -0.0203908496 1076 1311867754.5164580345 0.0066479575 0.0352964599 0.0670038015 0.0049862117 0.0414290000 396569249 0 402718720 -0.0064721862 -0.0113134887 -0.0209063105 1077 1311867754.5513699055 0.0057451646 0.0352690214 0.0670038015 0.0049857823 0.0323880000 396572557 0 402718720 -0.0048621427 -0.0110453535 -0.0199497063 1078 1311867754.5835940838 0.0065223235 0.0352423547 0.0670038015 0.0049850383 0.0324100000 396575425 0 402718720 -0.0044070752 -0.0124272201 -0.0186436716 1079 1311867754.6154909134 0.0054961634 0.0352147864 0.0670038015 0.0049830786 0.0322900000 396578773 0 402718720 -0.0034251655 -0.0104024541 -0.0190060902 1080 1311867754.6510920525 0.0043276884 0.0351861872 0.0670038015 0.0049820492 0.0328970000 396582009 0 402718720 -0.0046084197 -0.0120519856 -0.0193834994 1081 1311867754.6872758865 0.0057810531 0.0351589855 0.0670038015 0.0049800689 0.0316670000 396585253 0 402718720 -0.0068278648 -0.0132852104 -0.0177183058 1082 1311867754.7162959576 0.0044016438 0.0351305591 0.0670038015 0.0049779730 0.0319730000 396588337 0 402718720 -0.0049368087 -0.0117762424 -0.0177101754 1083 1311867754.7516000271 0.0051573208 0.0351028830 0.0670038015 0.0049766209 0.0425470000 396591885 0 402718720 -0.0069668568 -0.0106799984 -0.0164650921 1084 1311867754.7865269184 0.0046195406 0.0350747618 0.0670038015 0.0049765051 0.0425670000 396595025 0 402718720 -0.0078432383 -0.0127479360 -0.0164215397 1085 1311867754.8154470921 0.0027888520 0.0350450052 0.0670038015 0.0049759997 0.0455050000 396598029 0 402718720 -0.0074363127 -0.0124521675 -0.0173940863 1086 1311867754.8510210514 0.0034914867 0.0350159504 0.0670038015 0.0049867044 0.0327240000 396601113 0 402718720 -0.0081057344 -0.0109255696 -0.0165132266 1087 1311867754.8877389431 0.0042346367 0.0349876327 0.0670038015 0.0049845083 0.0320420000 396604749 0 402718720 -0.0099062128 -0.0135400547 -0.0155271105 1088 1311867754.9201259613 0.0044457479 0.0349595611 0.0670038015 0.0049827345 0.0329180000 396608057 0 402718720 -0.0110952081 -0.0150012868 -0.0158498716 1089 1311867754.9510319233 0.0026341828 0.0349298776 0.0670038015 0.0049805240 0.0316720000 396610941 0 402718720 -0.0102223782 -0.0126612429 -0.0157696642 1090 1311867754.9837870598 0.0020130854 0.0348996787 0.0670038015 0.0049802776 0.0327100000 396614273 0 402718720 -0.0099076694 -0.0134366369 -0.0152563043 1091 1311867755.0183880329 0.0039847121 0.0348713423 0.0670038015 0.0049789031 0.0422330000 396617829 0 402718720 -0.0069654286 -0.0141606908 -0.0152662303 1092 1311867755.0540831089 0.0019612077 0.0348412048 0.0670038015 0.0049831023 0.0425160000 396620961 0 402718720 -0.0103093116 -0.0134543162 -0.0144738909 1093 1311867755.0850980282 0.0027196335 0.0348118164 0.0670038015 0.0049828108 0.0449910000 396624301 0 402718720 -0.0116505772 -0.0129776550 -0.0129290251 1094 1311867755.1156959534 0.0021594451 0.0347819696 0.0670038015 0.0049831186 0.0334440000 396627305 0 402718720 -0.0122423517 -0.0146706915 -0.0145607572 1095 1311867755.1556220055 0.0025157188 0.0347525027 0.0670038015 0.0049809055 0.0330320000 396630709 0 402718720 -0.0123519907 -0.0139808729 -0.0132803451 1096 1311867755.1847031116 0.0033917904 0.0347238889 0.0670038015 0.0049803600 0.0330800000 396633825 0 402718720 -0.0121954530 -0.0155173857 -0.0137862377 1097 1311867755.2151238918 0.0021853398 0.0346942275 0.0670038015 0.0049781556 0.0330290000 396636973 0 402718720 -0.0130243888 -0.0144008594 -0.0142230494 1098 1311867755.2512340546 0.0032060933 0.0346655498 0.0670038015 0.0049763173 0.0328390000 396640297 0 402718720 -0.0139994044 -0.0149433184 -0.0125837680 1099 1311867755.2832889557 0.0026803503 0.0346364459 0.0670038015 0.0049753418 0.0330650000 396643349 0 402718720 -0.0156121748 -0.0152572067 -0.0132995369 1100 1311867755.3192110062 0.0024024346 0.0346071423 0.0670038015 0.0049736230 0.0419530000 396646689 0 402718720 -0.0129644126 -0.0138690202 -0.0156627391 1101 1311867755.3553090096 0.0022172183 0.0345777236 0.0670038015 0.0049717058 0.0332010000 396649941 0 402718720 -0.0153647335 -0.0161389280 -0.0150532462 1102 1311867755.3900220394 0.0029824178 0.0345490528 0.0670038015 0.0049696604 0.0330090000 396653457 0 402718720 -0.0162748527 -0.0176236778 -0.0156273432 1103 1311867755.4156589508 0.0015694022 0.0345191528 0.0670038015 0.0049685488 0.0338010000 396656413 0 402718720 -0.0150739439 -0.0142228873 -0.0162022673 1104 1311867755.4549160004 0.0012740055 0.0344890394 0.0670038015 0.0049666421 0.0331800000 396659681 0 402718720 -0.0170507841 -0.0158195738 -0.0149395093 1105 1311867755.4860870838 0.0015926404 0.0344592689 0.0670038015 0.0049645775 0.0330940000 396662645 0 402718720 -0.0176610947 -0.0165700931 -0.0157038718 1106 1311867755.5161950588 0.0002881851 0.0344283728 0.0670038015 0.0049625006 0.0326900000 396665761 0 402718720 -0.0175767709 -0.0148275532 -0.0157846883 1107 1311867755.5550999641 0.0025425463 0.0343995690 0.0670038015 0.0049610047 0.0326820000 396669085 0 402718720 -0.0161467381 -0.0143176932 -0.0171530955 1108 1311867755.5854589939 0.0013522995 0.0343697430 0.0670038015 0.0049593783 0.0431720000 396672137 0 402718720 -0.0171437748 -0.0137358326 -0.0161085315 1109 1311867755.6171119213 0.0027696968 0.0343412488 0.0670038015 0.0049572005 0.0333660000 396675293 0 402718720 -0.0163599942 -0.0126083065 -0.0164307673 1110 1311867755.6542940140 0.0030815429 0.0343130869 0.0670038015 0.0049553421 0.0324460000 396678785 0 402718720 -0.0156903304 -0.0145055326 -0.0157058071 1111 1311867755.6831719875 0.0026370515 0.0342845756 0.0670038015 0.0049531357 0.0320460000 396681693 0 402718720 -0.0171679072 -0.0155404070 -0.0176416077 1112 1311867755.7182741165 0.0014201698 0.0342550213 0.0670038015 0.0049520964 0.0325800000 396685113 0 402718720 -0.0185025316 -0.0156286377 -0.0170231704 1113 1311867755.7511448860 0.0010050813 0.0342251471 0.0670038015 0.0049502465 0.0327210000 396688053 0 402718720 -0.0187515784 -0.0149981380 -0.0171728171 1114 1311867755.7863750458 0.0012977563 0.0341955893 0.0670038015 0.0049482820 0.0328020000 396691513 0 402718720 -0.0196284577 -0.0161817297 -0.0178552549 1115 1311867755.8156878948 0.0019530813 0.0341666723 0.0670038015 0.0049462952 0.0324110000 396694629 0 402718720 -0.0185506400 -0.0152832847 -0.0186097268 1116 1311867755.8554079533 0.0033780332 0.0341390839 0.0670038015 0.0049446923 0.0329750000 396697697 0 402718720 -0.0177960806 -0.0139273116 -0.0193493497 1117 1311867755.8848359585 0.0013153426 0.0341096983 0.0670038015 0.0049426326 0.0419160000 396701117 0 402718720 -0.0203091558 -0.0149092069 -0.0186589342 1118 1311867755.9156229496 0.0010701880 0.0340801459 0.0670038015 0.0049409375 0.0329860000 396704345 0 402718720 -0.0199497230 -0.0154410880 -0.0170690585 1119 1311867755.9550359249 0.0033933125 0.0340527225 0.0670038015 0.0049389760 0.0331540000 396707509 0 402718720 -0.0191979520 -0.0127532929 -0.0189988557 1120 1311867755.9855198860 0.0019737033 0.0340240805 0.0670038015 0.0049377128 0.0324800000 396710489 0 402718720 -0.0196042415 -0.0144749787 -0.0180382729 1121 1311867756.0173881054 0.0016028032 0.0339951588 0.0670038015 0.0049356100 0.0324280000 396713581 0 402718720 -0.0200581066 -0.0144996420 -0.0177019238 1122 1311867756.0554430485 0.0034786523 0.0339679605 0.0670038015 0.0049335720 0.0327770000 396717033 0 402718720 -0.0192466490 -0.0128116459 -0.0188377146 1123 1311867756.0835959911 0.0023198829 0.0339397787 0.0670038015 0.0049316038 0.0332780000 396720157 0 402718720 -0.0196098313 -0.0135394828 -0.0173146538 1124 1311867756.1196908951 0.0024139495 0.0339117308 0.0670038015 0.0049304879 0.0329000000 396723481 0 402718720 -0.0197931230 -0.0159653481 -0.0171858706 1125 1311867756.1519339085 0.0037230679 0.0338848965 0.0670038015 0.0049283667 0.0331160000 396726525 0 402718720 -0.0189195871 -0.0134332050 -0.0190027952 1126 1311867756.1836869717 0.0039430158 0.0338583051 0.0670038015 0.0049262211 0.0330380000 396729433 0 402718720 -0.0182042755 -0.0140177384 -0.0184072293 1127 1311867756.2230648994 0.0029460113 0.0338308763 0.0670038015 0.0049274316 0.0327400000 396732901 0 402718720 -0.0191936102 -0.0159433577 -0.0178131089 1128 1311867756.2552509308 0.0025781682 0.0338031700 0.0670038015 0.0049296392 0.0330210000 396735617 0 402718720 -0.0196681246 -0.0145201115 -0.0181954335 1129 1311867756.2851591110 0.0031867046 0.0337760518 0.0670038015 0.0049298050 0.0451640000 396738813 0 402718720 -0.0191743132 -0.0127107399 -0.0179389734 1130 1311867756.3200058937 0.0023614010 0.0337482512 0.0670038015 0.0049280607 0.0324940000 396742225 0 402718720 -0.0195212699 -0.0155904861 -0.0172081161 1131 1311867756.3546419144 0.0021737919 0.0337203339 0.0670038015 0.0049261412 0.0323040000 396745421 0 402718720 -0.0195483696 -0.0136524057 -0.0174655076 1132 1311867756.3843090534 0.0027124526 0.0336929418 0.0670038015 0.0049242022 0.0331190000 396748409 0 402718720 -0.0192266963 -0.0133839371 -0.0177186765 1133 1311867756.4231688976 0.0025378852 0.0336654439 0.0670038015 0.0049224416 0.0326530000 396751749 0 402718720 -0.0186622273 -0.0144831613 -0.0169466659 1134 1311867756.4510979652 0.0034061675 0.0336387603 0.0670038015 0.0049209131 0.0448820000 396754665 0 402718720 -0.0182277933 -0.0153405834 -0.0178628676 1135 1311867756.4865350723 0.0051915129 0.0336136966 0.0670038015 0.0049227959 0.0327580000 396758125 0 402718720 -0.0166387297 -0.0133445328 -0.0180795267 1136 1311867756.5264549255 0.0031143303 0.0335868486 0.0670038015 0.0049213287 0.0331720000 396761393 0 402718720 -0.0178692304 -0.0147601608 -0.0167914610 1137 1311867756.5525779724 0.0049206987 0.0335616365 0.0670038015 0.0049198052 0.0323710000 396764381 0 402718720 -0.0162822288 -0.0143093076 -0.0176353324 1138 1311867756.5897810459 0.0037457030 0.0335354362 0.0670038015 0.0049176593 0.0327100000 396768049 0 402718720 -0.0172657706 -0.0160386972 -0.0170802176 1139 1311867756.6202929020 0.0033509640 0.0335089353 0.0670038015 0.0049157821 0.0335430000 396771037 0 402718720 -0.0179703962 -0.0157886464 -0.0175548960 1140 1311867756.6518390179 0.0020233740 0.0334813164 0.0670038015 0.0049140794 0.0332380000 396773961 0 402718720 -0.0189355556 -0.0161424875 -0.0163366422 1141 1311867756.6839349270 0.0036619061 0.0334551820 0.0670038015 0.0049122280 0.0329690000 396777261 0 402718720 -0.0169166364 -0.0153231900 -0.0155974980 1142 1311867756.7217059135 0.0034459541 0.0334289042 0.0670038015 0.0049125865 0.0328650000 396780777 0 402718720 -0.0172734261 -0.0152550433 -0.0153703894 1143 1311867756.7516939640 0.0019029814 0.0334013224 0.0670038015 0.0049108680 0.0428250000 396783677 0 402718720 -0.0191828888 -0.0158480890 -0.0154063758 1144 1311867756.7872660160 0.0039350032 0.0333755652 0.0670038015 0.0049091905 0.0422480000 396786905 0 402718720 -0.0170972832 -0.0153407287 -0.0159474406 1145 1311867756.8227219582 0.0033371833 0.0333493308 0.0670038015 0.0049070466 0.0445160000 396790101 0 402718720 -0.0179468337 -0.0158811193 -0.0157452915 1146 1311867756.8542120457 0.0033975181 0.0333231948 0.0670038015 0.0049118798 0.0328690000 396793337 0 402718720 -0.0186202712 -0.0172539614 -0.0153622972 1147 1311867756.8841960430 0.0026607672 0.0332964621 0.0670038015 0.0049187723 0.0331280000 396796437 0 402718720 -0.0186328348 -0.0159121733 -0.0148909204 1148 1311867756.9223539829 0.0030146267 0.0332700842 0.0670038015 0.0049173233 0.0329800000 396799873 0 402718720 -0.0203323085 -0.0184153188 -0.0143285906 1149 1311867756.9552440643 0.0034838945 0.0332441606 0.0670038015 0.0049155012 0.0325380000 396802917 0 402718720 -0.0190550163 -0.0175230429 -0.0154423062 1150 1311867756.9841780663 0.0031039915 0.0332179518 0.0670038015 0.0049138842 0.0328130000 396806161 0 402718720 -0.0186396241 -0.0158053543 -0.0148242973 1151 1311867757.0282740593 0.0036337394 0.0331922487 0.0670038015 0.0049146922 0.0409640000 396809533 0 402718720 -0.0193969961 -0.0185020547 -0.0148063730 1152 1311867757.0552940369 0.0047640973 0.0331675715 0.0670038015 0.0049127993 0.0331450000 396812793 0 402718720 -0.0186101310 -0.0188704543 -0.0156329442 1153 1311867757.0858569145 0.0044768574 0.0331426880 0.0670038015 0.0049109744 0.0422980000 396815773 0 402718720 -0.0177683104 -0.0171061121 -0.0151293706 1154 1311867757.1283040047 0.0054068444 0.0331186534 0.0670038015 0.0049145727 0.0327680000 396819097 0 402718720 -0.0191450380 -0.0214189608 -0.0147134215 1155 1311867757.1522068977 0.0053192163 0.0330945847 0.0670038015 0.0049151144 0.0324320000 396822029 0 402718720 -0.0198988039 -0.0219447855 -0.0150533272 1156 1311867757.1851921082 0.0044284854 0.0330697870 0.0670038015 0.0049135280 0.0326360000 396825169 0 402718720 -0.0179786738 -0.0194988605 -0.0156239141 1157 1311867757.2192370892 0.0029985646 0.0330437963 0.0670038015 0.0049125457 0.0329310000 396828637 0 402718720 -0.0199950300 -0.0210237652 -0.0146258753 1158 1311867757.2523930073 0.0039203856 0.0330186466 0.0670038015 0.0049251974 0.0324070000 396831673 0 402718720 -0.0198806860 -0.0222832598 -0.0160825029 1159 1311867757.2835690975 0.0035297589 0.0329932032 0.0670038015 0.0049238047 0.0326640000 396834669 0 402718720 -0.0193018913 -0.0201754905 -0.0182571448 1160 1311867757.3233768940 0.0021623410 0.0329666248 0.0670038015 0.0049307920 0.0415070000 396838425 0 402718720 -0.0188663453 -0.0203592721 -0.0175261758 1161 1311867757.3555359840 0.0026533662 0.0329405152 0.0670038015 0.0049288195 0.0438950000 396841389 0 402718720 -0.0190626998 -0.0218628049 -0.0175777376 1162 1311867757.3833439350 0.0033967802 0.0329150903 0.0670038015 0.0049271984 0.0332980000 396844353 0 402718720 -0.0171038564 -0.0195439197 -0.0176288411 1163 1311867757.4264349937 0.0025738159 0.0328890015 0.0670038015 0.0049254612 0.0323140000 396847805 0 402718720 -0.0188103970 -0.0224912856 -0.0171752516 1164 1311867757.4546940327 0.0010704934 0.0328616660 0.0670038015 0.0049250722 0.0329440000 396850713 0 402718720 -0.0190548431 -0.0204425249 -0.0170593392 1165 1311867757.4884710312 0.0026257872 0.0328357125 0.0670038015 0.0049237031 0.0319420000 396854101 0 402718720 -0.0175020676 -0.0216349512 -0.0172380190 1166 1311867757.5210690498 0.0029621569 0.0328100920 0.0670038015 0.0049233993 0.0551480000 396857225 0 402718720 -0.0178337898 -0.0230306424 -0.0171882380 1167 1311867757.5554831028 0.0037514861 0.0327851917 0.0670038015 0.0049214782 0.0509170000 396860389 0 402718720 -0.0160222147 -0.0214548949 -0.0173401181 1168 1311867757.5887749195 0.0024511097 0.0327592207 0.0670038015 0.0049202841 0.0330550000 396863801 0 402718720 -0.0170797557 -0.0210719649 -0.0165970679 1169 1311867757.6231749058 0.0019944059 0.0327329035 0.0670038015 0.0049191982 0.0425720000 396866845 0 402718720 -0.0177921280 -0.0217322502 -0.0167362858 1170 1311867757.6566219330 0.0046218121 0.0327088770 0.0670038015 0.0049177817 0.0329350000 396870249 0 402718720 -0.0155535163 -0.0206072498 -0.0179023333 1171 1311867757.6914329529 0.0026776863 0.0326832312 0.0670038015 0.0049168244 0.0330900000 396873277 0 402718720 -0.0179657247 -0.0198580232 -0.0165804420 1172 1311867757.7207450867 0.0026449058 0.0326576012 0.0670038015 0.0049149052 0.0327550000 396876505 0 402718720 -0.0178498551 -0.0207403675 -0.0170451272 1173 1311867757.7614738941 0.0029875697 0.0326323071 0.0670038015 0.0049133885 0.0320290000 396880077 0 402718720 -0.0168360230 -0.0225781146 -0.0162441395 1174 1311867757.7876570225 0.0027948418 0.0326068919 0.0670038015 0.0049117543 0.0318860000 396882889 0 402718720 -0.0171419084 -0.0218186509 -0.0165559873 1175 1311867757.8206570148 0.0028205982 0.0325815418 0.0670038015 0.0049101473 0.0436060000 396886269 0 402718720 -0.0177662820 -0.0235406067 -0.0178568121 1176 1311867757.8555610180 0.0025196765 0.0325559790 0.0670038015 0.0049089608 0.0432450000 396889641 0 402718720 -0.0174120143 -0.0225100722 -0.0163722299 1177 1311867757.8887560368 0.0026546509 0.0325305743 0.0670038015 0.0049098072 0.0455470000 396892733 0 402718720 -0.0172608439 -0.0229839832 -0.0172840245 1178 1311867757.9201729298 0.0026598177 0.0325052171 0.0670038015 0.0049079656 0.0320930000 396895809 0 402718720 -0.0172093995 -0.0228786618 -0.0162139945 1179 1311867757.9554479122 0.0025176343 0.0324797824 0.0670038015 0.0049060088 0.0325180000 396899357 0 402718720 -0.0176453087 -0.0232278630 -0.0181067567 1180 1311867757.9904439449 0.0016289901 0.0324536376 0.0670038015 0.0049091722 0.0324750000 396902385 0 402718720 -0.0184186213 -0.0228510965 -0.0175920799 1181 1311867758.0221159458 0.0039466913 0.0324294997 0.0670038015 0.0049085187 0.0324860000 396905605 0 402718720 -0.0158210862 -0.0229135454 -0.0183355976 1182 1311867758.0557579994 0.0039326963 0.0324053907 0.0670038015 0.0049065710 0.0323680000 396908865 0 402718720 -0.0160484985 -0.0232959259 -0.0190886110 1183 1311867758.0871500969 0.0033471773 0.0323808275 0.0670038015 0.0049047726 0.0408860000 396912061 0 402718720 -0.0171877947 -0.0227312651 -0.0193460230 1184 1311867758.1223280430 0.0027319500 0.0323557863 0.0670038015 0.0049028395 0.0326120000 396915257 0 402718720 -0.0171378851 -0.0237307753 -0.0191245452 1185 1311867758.1526539326 0.0033220809 0.0323312852 0.0670038015 0.0049055267 0.0325560000 396918429 0 402718720 -0.0166090690 -0.0231324378 -0.0189669076 1186 1311867758.1877539158 0.0030029158 0.0323065564 0.0670038015 0.0049045996 0.0317710000 396921657 0 402718720 -0.0180179887 -0.0226588175 -0.0197022129 1187 1311867758.2221779823 0.0020561975 0.0322810717 0.0670038015 0.0049045779 0.0314890000 396924973 0 402718720 -0.0195440408 -0.0235570092 -0.0198030565 1188 1311867758.2562980652 0.0033708930 0.0322567365 0.0670038015 0.0049026580 0.0322570000 396928305 0 402718720 -0.0174106453 -0.0228276383 -0.0194029529 1189 1311867758.2902839184 0.0027361417 0.0322319085 0.0670038015 0.0049017260 0.0320880000 396931645 0 402718720 -0.0172973536 -0.0244909059 -0.0201872103 1190 1311867758.3220090866 0.0025692808 0.0322069819 0.0670038015 0.0049014633 0.0320360000 396934929 0 402718720 -0.0186194479 -0.0239592735 -0.0201692190 1191 1311867758.3539829254 0.0042220331 0.0321834849 0.0670038015 0.0048996250 0.0320690000 396937957 0 402718720 -0.0162393209 -0.0240285229 -0.0204128418 1192 1311867758.3902978897 0.0043743537 0.0321601551 0.0670038015 0.0048976603 0.0399530000 396941337 0 402718720 -0.0166596659 -0.0237261634 -0.0206938777 1193 1311867758.4210340977 0.0027574373 0.0321355090 0.0670038015 0.0048956665 0.0429420000 396944389 0 402718720 -0.0182554517 -0.0255121812 -0.0216907542 1194 1311867758.4536960125 0.0063473466 0.0321139109 0.0670038015 0.0048936689 0.0421300000 396947553 0 402718720 -0.0154309599 -0.0229558162 -0.0217441283 1195 1311867758.4900159836 0.0083523635 0.0320940268 0.0670038015 0.0048916703 0.0373120000 396950837 0 402718720 -0.0141414842 -0.0218801294 -0.0228788015 1196 1311867758.5217890739 0.0063207690 0.0320724772 0.0670038015 0.0048904059 0.0322770000 396953809 0 402718720 -0.0148446383 -0.0250275098 -0.0226507150 1197 1311867758.5528969765 0.0068281852 0.0320513876 0.0670038015 0.0048885666 0.0316860000 396957037 0 402718720 -0.0150823211 -0.0235416237 -0.0224085841 1198 1311867758.5893049240 0.0068070902 0.0320303155 0.0670038015 0.0048881402 0.0317900000 396960489 0 402718720 -0.0176588465 -0.0214772746 -0.0225618277 1199 1311867758.6221299171 0.0063243425 0.0320088760 0.0670038015 0.0048890033 0.0318270000 396963525 0 402718720 -0.0156800095 -0.0242466517 -0.0221977662 1200 1311867758.6535029411 0.0025421546 0.0319843204 0.0670038015 0.0048873776 0.0322350000 396966777 0 402718720 -0.0197657738 -0.0261459909 -0.0220979732 1201 1311867758.6911680698 0.0068437555 0.0319633874 0.0670038015 0.0048857077 0.0330510000 396970421 0 402718720 -0.0172822215 -0.0225075558 -0.0228878483 1202 1311867758.7212190628 0.0069141388 0.0319425478 0.0670038015 0.0048861346 0.0324140000 396973129 0 402718720 -0.0155679621 -0.0245544035 -0.0230272338 1203 1311867758.7601859570 0.0061515230 0.0319211088 0.0670038015 0.0048864450 0.0315380000 396976653 0 402718720 -0.0189638380 -0.0229847338 -0.0229591280 1204 1311867758.7879199982 0.0043434803 0.0318982038 0.0670038015 0.0048845514 0.0441030000 396979577 0 402718720 -0.0195332747 -0.0246969890 -0.0222162884 1205 1311867758.8218998909 0.0034807965 0.0318746209 0.0670038015 0.0048831036 0.0317880000 396982677 0 402718720 -0.0203755293 -0.0254421588 -0.0218120012 1206 1311867758.8574860096 0.0053259069 0.0318526071 0.0670038015 0.0048815700 0.0321180000 396986049 0 402718720 -0.0179829542 -0.0250995029 -0.0224604215 1207 1311867758.8875849247 0.0047891568 0.0318301850 0.0670038015 0.0048798216 0.0316040000 396989173 0 402718720 -0.0187740847 -0.0248907600 -0.0219397489 1208 1311867758.9205179214 0.0070794136 0.0318096959 0.0670038015 0.0048785161 0.0314470000 396992417 0 402718720 -0.0149528105 -0.0253836513 -0.0207458753 1209 1311867758.9576990604 0.0061778985 0.0317884951 0.0670038015 0.0048777678 0.0320600000 396995853 0 402718720 -0.0161319599 -0.0258473121 -0.0217709560 1210 1311867758.9880809784 0.0060317344 0.0317672085 0.0670038015 0.0048760728 0.0318710000 396998929 0 402718720 -0.0164817329 -0.0265571158 -0.0232765507 1211 1311867759.0196750164 0.0081923362 0.0317477412 0.0670038015 0.0048741014 0.0323000000 397002093 0 402718720 -0.0137730045 -0.0259869378 -0.0217477567 1212 1311867759.0579299927 0.0068356572 0.0317271867 0.0670038015 0.0048720891 0.0315490000 397005489 0 402718720 -0.0149392039 -0.0271144845 -0.0216974691 1213 1311867759.0873589516 0.0085803941 0.0317081045 0.0670038015 0.0048710748 0.0446620000 397008429 0 402718720 -0.0151866563 -0.0240241494 -0.0217671338 1214 1311867759.1199090481 0.0090581235 0.0316894471 0.0670038015 0.0048696132 0.0323650000 397011705 0 402718720 -0.0146403760 -0.0245492253 -0.0232239962 1215 1311867759.1563479900 0.0062595699 0.0316685172 0.0670038015 0.0048679209 0.0419920000 397014853 0 402718720 -0.0173379593 -0.0257151108 -0.0220977738 1216 1311867759.1888740063 0.0056013931 0.0316470804 0.0670038015 0.0048664499 0.0323860000 397018137 0 402718720 -0.0183518305 -0.0258574206 -0.0211793482 1217 1311867759.2214748859 0.0079052420 0.0316275719 0.0670038015 0.0048646452 0.0373210000 397624665 0 402718720 -0.0179287512 -0.0239232518 -0.0216215514 1218 1311867759.2585420609 0.0069097956 0.0316072782 0.0670038015 0.0048629415 0.1146860000 397605729 0 402718720 -0.0187368263 -0.0250436496 -0.0217359997 1219 1311867759.2957389355 0.0073738554 0.0315873984 0.0670038015 0.0048618874 0.1046110000 397607941 0 402718720 -0.0170401428 -0.0259685218 -0.0219207779 1220 1311867759.3223690987 0.0071798167 0.0315673922 0.0670038015 0.0048598952 0.1000160000 401553173 0 402718720 -0.0176480152 -0.0261843521 -0.0226428360 1221 1311867759.3619010448 0.0086619081 0.0315486326 0.0670038015 0.0048583667 0.0562740000 407029865 0 402718720 -0.0152353588 -0.0260957107 -0.0231593512 1222 1311867759.3886260986 0.0074932519 0.0315289473 0.0670038015 0.0048566596 0.0541730000 406642513 0 402718720 -0.0166946594 -0.0272376034 -0.0235818438 1223 1311867759.4206190109 0.0084265079 0.0315100574 0.0670038015 0.0048552795 0.1122310000 405524921 0 402718720 -0.0158349257 -0.0265341364 -0.0227999426 1224 1311867759.4585750103 0.0084425528 0.0314912114 0.0670038015 0.0048536740 0.0510480000 397591557 0 402718720 -0.0173522364 -0.0257978439 -0.0235099513 1225 1311867759.4905979633 0.0093459627 0.0314731336 0.0670038015 0.0048529505 0.0352630000 397594769 0 402718720 -0.0148060108 -0.0264376290 -0.0224603806 1226 1311867759.5243968964 0.0086346809 0.0314545052 0.0670038015 0.0048519270 0.0348990000 397597957 0 402718720 -0.0166868176 -0.0259913821 -0.0225538798 1227 1311867759.5617649555 0.0085598081 0.0314358461 0.0670038015 0.0048504230 0.0463390000 397601345 0 402718720 -0.0165100023 -0.0270099286 -0.0239864644 1228 1311867759.5870699883 0.0097872885 0.0314182170 0.0670038015 0.0048488067 0.0452360000 397604141 0 402718720 -0.0148272635 -0.0261455216 -0.0220062193 1229 1311867759.6198399067 0.0052430038 0.0313969190 0.0670038015 0.0048470000 0.0468470000 397607145 0 402718720 -0.0181278381 -0.0297301561 -0.0220830273 1230 1311867759.6576719284 0.0083589638 0.0313781890 0.0670038015 0.0048454981 0.0348670000 397610805 0 402718720 -0.0153812477 -0.0281342324 -0.0238363631 1231 1311867759.6904048920 0.0088090077 0.0313598549 0.0670038015 0.0048436371 0.0335220000 397613849 0 402718720 -0.0135252159 -0.0289479643 -0.0228767842 1232 1311867759.7190918922 0.0096374499 0.0313422231 0.0670038015 0.0048427494 0.0333920000 397616917 0 402718720 -0.0119355908 -0.0297194514 -0.0231563710 1233 1311867759.7576398849 0.0110597229 0.0313257734 0.0670038015 0.0048413872 0.0336790000 397620313 0 402718720 -0.0115335854 -0.0283845011 -0.0243721753 1234 1311867759.7871410847 0.0096524702 0.0313082099 0.0670038015 0.0048445270 0.0346680000 397623565 0 402718720 -0.0136700226 -0.0277893282 -0.0232257284 1235 1311867759.8209869862 0.0078697419 0.0312892314 0.0670038015 0.0048488115 0.0343340000 397626713 0 402718720 -0.0138822952 -0.0308897514 -0.0220856629 1236 1311867759.8573861122 0.0088831736 0.0312711036 0.0670038015 0.0048513370 0.0351210000 397629885 0 402718720 -0.0124412924 -0.0307006817 -0.0221207775 1237 1311867759.8883268833 0.0093398169 0.0312533741 0.0670038015 0.0048565854 0.0350120000 397633121 0 402718720 -0.0115769478 -0.0316761434 -0.0229098909 1238 1311867759.9261589050 0.0067321435 0.0312335670 0.0670038015 0.0048552966 0.0347290000 397636453 0 402718720 -0.0144379269 -0.0329464525 -0.0217228662 1239 1311867759.9576280117 0.0094978930 0.0312160241 0.0670038015 0.0048555984 0.0339100000 397639457 0 402718720 -0.0152699584 -0.0291065536 -0.0232698377 1240 1311867759.9870700836 0.0088980142 0.0311980257 0.0670038015 0.0048546970 0.0342650000 397642845 0 402718720 -0.0128935883 -0.0318218805 -0.0235683341 1241 1311867760.0261199474 0.0071917484 0.0311786814 0.0670038015 0.0048554702 0.0394280000 398197705 0 402718720 -0.0145074418 -0.0334443897 -0.0257412568 1242 1311867760.0566520691 0.0103107858 0.0311618795 0.0670038015 0.0048543357 0.1070000000 398161361 0 402718720 -0.0122834183 -0.0314161219 -0.0260751583 1243 1311867760.0870590210 0.0118192369 0.0311463183 0.0670038015 0.0048528214 0.0988010000 398421045 0 402718720 -0.0132570369 -0.0287164450 -0.0262995586 1244 1311867760.1246991158 0.0087851407 0.0311283431 0.0670038015 0.0048519344 0.0958480000 405068173 0 402718720 -0.0141393663 -0.0320639759 -0.0256696697 1245 1311867760.1576859951 0.0100669572 0.0311114263 0.0670038015 0.0048518883 0.0486330000 407616821 0 402718720 -0.0139415348 -0.0306759514 -0.0264435485 1246 1311867760.1870229244 0.0120090805 0.0310960954 0.0670038015 0.0048506449 0.0550920000 407290569 0 402718720 -0.0127346022 -0.0295764413 -0.0280528311 1247 1311867760.2261290550 0.0080875326 0.0310776442 0.0670038015 0.0048489968 0.1089100000 406150533 0 402718720 -0.0153676597 -0.0321825184 -0.0251901112 1248 1311867760.2573459148 0.0093924617 0.0310602683 0.0670038015 0.0048471304 0.0547620000 398177673 0 402718720 -0.0140457600 -0.0320098661 -0.0260304362 1249 1311867760.2895119190 0.0106222415 0.0310439048 0.0670038015 0.0048453679 0.0346110000 398180973 0 402718720 -0.0128124356 -0.0319505706 -0.0263611991 1250 1311867760.3248739243 0.0087210173 0.0310260465 0.0670038015 0.0048434873 0.0351390000 398184297 0 402718720 -0.0144806998 -0.0335866287 -0.0276934300 1251 1311867760.3574841022 0.0082764747 0.0310078613 0.0670038015 0.0048501234 0.0347750000 398187421 0 402718720 -0.0139788436 -0.0352480933 -0.0267220568 1252 1311867760.3897368908 0.0089218831 0.0309902208 0.0670038015 0.0048484560 0.0340160000 398190465 0 402718720 -0.0137368385 -0.0349997804 -0.0279497765 1253 1311867760.4247770309 0.0108619072 0.0309741567 0.0670038015 0.0048501691 0.0332160000 398193573 0 402718720 -0.0129013220 -0.0334538072 -0.0281710848 1254 1311867760.4572839737 0.0086249942 0.0309563344 0.0670038015 0.0048489785 0.0331640000 398196697 0 402718720 -0.0152762877 -0.0341932327 -0.0294947531 1255 1311867760.4886090755 0.0112369154 0.0309406217 0.0670038015 0.0048476960 0.0329550000 398199885 0 402718720 -0.0117491083 -0.0342944376 -0.0284777023 1256 1311867760.5243430138 0.0104552479 0.0309243117 0.0670038015 0.0048471686 0.0328140000 398203689 0 402718720 -0.0124851586 -0.0348017588 -0.0311053526 1257 1311867760.5571060181 0.0086850468 0.0309066194 0.0670038015 0.0048463245 0.0334900000 398206357 0 402718720 -0.0144974990 -0.0352529362 -0.0311195459 1258 1311867760.5894339085 0.0085274410 0.0308888299 0.0670038015 0.0048446889 0.0327680000 398209641 0 402718720 -0.0138397831 -0.0366385393 -0.0324587189 1259 1311867760.6240029335 0.0109545942 0.0308729965 0.0670038015 0.0048429822 0.0366830000 398687945 0 402718720 -0.0117954565 -0.0350055024 -0.0320052505 1260 1311867760.6560370922 0.0099525424 0.0308563929 0.0670038015 0.0048414000 0.1025410000 398663557 0 402718720 -0.0120578315 -0.0366824418 -0.0297283679 1261 1311867760.6867549419 0.0091410391 0.0308391722 0.0670038015 0.0048402342 0.0904820000 398934717 0 402718720 -0.0129177710 -0.0371835940 -0.0306812748 1262 1311867760.7232599258 0.0118509112 0.0308241260 0.0670038015 0.0048384463 0.0907350000 404584837 0 402718720 -0.0111012887 -0.0349968933 -0.0322218649 1263 1311867760.7558701038 0.0096430369 0.0308073556 0.0670038015 0.0048375215 0.0536320000 408256713 0 402718720 -0.0117892576 -0.0380463749 -0.0327209607 1264 1311867760.7868170738 0.0089606857 0.0307900718 0.0670038015 0.0048357547 0.0532260000 407914289 0 402718720 -0.0124465665 -0.0383451879 -0.0329096727 1265 1311867760.8233850002 0.0103431875 0.0307739083 0.0670038015 0.0048353044 0.0984910000 406837953 0 402718720 -0.0131633114 -0.0353122987 -0.0334513076 1266 1311867760.8547210693 0.0115346890 0.0307587114 0.0670038015 0.0048334217 0.0458790000 398581661 0 402718720 -0.0118854754 -0.0345536955 -0.0340554342 1267 1311867760.8877849579 0.0077055269 0.0307405163 0.0670038015 0.0048319041 0.0320130000 398584681 0 402718720 -0.0142138377 -0.0376486406 -0.0339810029 1268 1311867760.9240860939 0.0097213117 0.0307239397 0.0670038015 0.0048331402 0.0354880000 399047081 0 402718720 -0.0151984179 -0.0343686417 -0.0351658165 1269 1311867760.9559810162 0.0103646563 0.0307078961 0.0670038015 0.0048320351 0.0968030000 399025993 0 402718720 -0.0121760257 -0.0358418934 -0.0338746607 1270 1311867760.9867389202 0.0080218585 0.0306900331 0.0670038015 0.0048305689 0.0864000000 400849153 0 402718720 -0.0143175106 -0.0370108113 -0.0356631279 1271 1311867761.0245900154 0.0102303429 0.0306739358 0.0670038015 0.0048288012 0.0500860000 407922237 0 402718720 -0.0134100141 -0.0349646769 -0.0354960002 1272 1311867761.0566051006 0.0122320978 0.0306594375 0.0670038015 0.0048272944 0.0769200000 407722385 0 402718720 -0.0116824415 -0.0336235873 -0.0348981917 1273 1311867761.0866270065 0.0089589087 0.0306423907 0.0670038015 0.0048255627 0.0359930000 407844021 0 402718720 -0.0134393396 -0.0365954563 -0.0345593579 1274 1311867761.1242640018 0.0092793861 0.0306256223 0.0670038015 0.0048254510 0.0960380000 406629649 0 402718720 -0.0137501163 -0.0358080827 -0.0348104574 1275 1311867761.1547141075 0.0090551125 0.0306087042 0.0670038015 0.0048235645 0.0511980000 399002573 0 402718720 -0.0146581484 -0.0352364145 -0.0367900282 1276 1311867761.1912519932 0.0090376902 0.0305917990 0.0670038015 0.0048219351 0.0314710000 399005793 0 402718720 -0.0146034779 -0.0356357619 -0.0354705453 1277 1311867761.2244689465 0.0108366013 0.0305763290 0.0670038015 0.0048204609 0.0416080000 399008877 0 402718720 -0.0137180416 -0.0343516804 -0.0369942039 1278 1311867761.2564349174 0.0111215888 0.0305611062 0.0670038015 0.0048190789 0.0438810000 399446709 0 402718720 -0.0134864058 -0.0341655314 -0.0370882228 1279 1311867761.2914810181 0.0094136074 0.0305445718 0.0670038015 0.0048173163 0.0946390000 399428953 0 402718720 -0.0140469233 -0.0364071652 -0.0361400358 1280 1311867761.3245120049 0.0094373096 0.0305280818 0.0670038015 0.0048157840 0.0885530000 399453493 0 402718720 -0.0147801097 -0.0361285843 -0.0364189446 1281 1311867761.3563210964 0.0108525418 0.0305127222 0.0670038015 0.0048143837 0.0806390000 407771689 0 402718720 -0.0126578547 -0.0362835266 -0.0374668315 1282 1311867761.3919639587 0.0101035871 0.0304968025 0.0670038015 0.0048128737 0.0576070000 407779757 0 402718720 -0.0141663216 -0.0361899622 -0.0372612849 1283 1311867761.4230949879 0.0088485917 0.0304799294 0.0670038015 0.0048114245 0.0392440000 407999685 0 402718720 -0.0155284414 -0.0369848423 -0.0379635245 1284 1311867761.4547801018 0.0098260734 0.0304638438 0.0670038015 0.0048108417 0.0905990000 406913281 0 402718720 -0.0163335074 -0.0354268178 -0.0370351300 1285 1311867761.4908668995 0.0090111662 0.0304471491 0.0670038015 0.0048095935 0.0460600000 399446657 0 402718720 -0.0151497470 -0.0372744799 -0.0383160561 1286 1311867761.5258040428 0.0068867700 0.0304288285 0.0670038015 0.0048079710 0.0306850000 399449501 0 402718720 -0.0164959989 -0.0401134714 -0.0375495888 1287 1311867761.5562748909 0.0082255341 0.0304115765 0.0670038015 0.0048064146 0.0308430000 399452545 0 402718720 -0.0169085395 -0.0373906083 -0.0389196649 1288 1311867761.5914149284 0.0078512793 0.0303940607 0.0670038015 0.0048048014 0.0307070000 399456229 0 402718720 -0.0163905416 -0.0381853282 -0.0392929129 1289 1311867761.6232030392 0.0067277262 0.0303757005 0.0670038015 0.0048033316 0.0302890000 399459241 0 402718720 -0.0175543725 -0.0396490283 -0.0383729041 1290 1311867761.6567790508 0.0087946821 0.0303589710 0.0670038015 0.0048051673 0.0303990000 399462693 0 402718720 -0.0157220755 -0.0379579477 -0.0399770699 1291 1311867761.6917459965 0.0081097158 0.0303417369 0.0670038015 0.0048036043 0.0343610000 399909089 0 402718720 -0.0154332491 -0.0388480499 -0.0410031527 1292 1311867761.7235610485 0.0067205708 0.0303234543 0.0670038015 0.0048050345 0.0913260000 399878961 0 402718720 -0.0170412362 -0.0399345234 -0.0390491374 1293 1311867761.7545659542 0.0076971711 0.0303059552 0.0670038015 0.0048037114 0.0851900000 399902997 0 402718720 -0.0155255664 -0.0409126282 -0.0382071584 1294 1311867761.7916970253 0.0107011460 0.0302908046 0.0670038015 0.0048064072 0.0773040000 407497701 0 402718720 -0.0118323807 -0.0388536155 -0.0409880765 1295 1311867761.8235230446 0.0103263967 0.0302753881 0.0670038015 0.0048046045 0.0693540000 407544681 0 402718720 -0.0118084922 -0.0395172946 -0.0405864902 1296 1311867761.8546519279 0.0095454110 0.0302593928 0.0670038015 0.0048029516 0.0353750000 408674829 0 402718720 -0.0138297081 -0.0378592014 -0.0420092642 1297 1311867761.8910980225 0.0102267247 0.0302439474 0.0670038015 0.0048013021 0.0899820000 407449793 0 402718720 -0.0126942480 -0.0378128812 -0.0411786363 1298 1311867761.9224560261 0.0099979183 0.0302283495 0.0670038015 0.0047996632 0.0477060000 399898697 0 402718720 -0.0127662728 -0.0379847214 -0.0408419594 1299 1311867761.9546790123 0.0092848977 0.0302122268 0.0670038015 0.0048006173 0.0324620000 400320001 0 402718720 -0.0115988310 -0.0405788422 -0.0417672768 1300 1311867761.9942779541 0.0088644112 0.0301958054 0.0670038015 0.0047992077 0.0923300000 400303193 0 402718720 -0.0129234642 -0.0396208502 -0.0418765098 1301 1311867762.0235669613 0.0095889997 0.0301799662 0.0670038015 0.0047986481 0.0835850000 402192985 0 402718720 -0.0117328325 -0.0395426452 -0.0423790701 1302 1311867762.0558550358 0.0085284710 0.0301633367 0.0670038015 0.0047975213 0.0519690000 409416753 0 402718720 -0.0132038957 -0.0399393700 -0.0417623855 1303 1311867762.0913889408 0.0107329180 0.0301484247 0.0670038015 0.0048183378 0.0725650000 409207233 0 402718720 -0.0105018197 -0.0401136428 -0.0412371382 1304 1311867762.1225299835 0.0108438469 0.0301336206 0.0670038015 0.0048165045 0.0976860000 408009557 0 402718720 -0.0103619341 -0.0398219228 -0.0417164117 1305 1311867762.1545391083 0.0086965682 0.0301171937 0.0670038015 0.0048377874 0.0569930000 400277941 0 402718720 -0.0119219162 -0.0412900560 -0.0416161194 1306 1311867762.1913030148 0.0090011507 0.0301010252 0.0670038015 0.0048361128 0.0297630000 400281369 0 402718720 -0.0118378568 -0.0411601067 -0.0412173197 1307 1311867762.2234869003 0.0094488161 0.0300852240 0.0670038015 0.0048345044 0.0289540000 400284621 0 402718720 -0.0119401719 -0.0403637141 -0.0410390422 1308 1311867762.2565600872 0.0078074653 0.0300681921 0.0670038015 0.0048328374 0.0293000000 400287841 0 402718720 -0.0132384133 -0.0403254107 -0.0429828502 1309 1311867762.2907900810 0.0100206044 0.0300528769 0.0670038015 0.0048313155 0.0318410000 400687625 0 402718720 -0.0106470510 -0.0408275314 -0.0411321223 1310 1311867762.3235380650 0.0083426749 0.0300363042 0.0670038015 0.0048556304 0.0879520000 400669941 0 402718720 -0.0109796571 -0.0424872674 -0.0428980291 1311 1311867762.3545570374 0.0079435771 0.0300194524 0.0670038015 0.0048545000 0.0781650000 402966853 0 402718720 -0.0115018338 -0.0431916714 -0.0420546085 1312 1311867762.3949799538 0.0082594976 0.0300028670 0.0670038015 0.0048681497 0.0716840000 409307517 0 402718720 -0.0112728188 -0.0432144552 -0.0423388779 1313 1311867762.4242470264 0.0088453740 0.0299867532 0.0670038015 0.0048663798 0.0653960000 408372553 0 402718720 -0.0106319264 -0.0426621363 -0.0428305417 1314 1311867762.4588010311 0.0092253964 0.0299709531 0.0670038015 0.0048645939 0.0358730000 409482657 0 402718720 -0.0102872280 -0.0413129441 -0.0446058773 1315 1311867762.4918160439 0.0068088369 0.0299533393 0.0670038015 0.0048632890 0.0840960000 408291529 0 402718720 -0.0113243842 -0.0447969548 -0.0440785512 1316 1311867762.5242910385 0.0088388193 0.0299372948 0.0670038015 0.0048616478 0.0496440000 401046673 0 402718720 -0.0096261669 -0.0439599343 -0.0437965430 1317 1311867762.5594940186 0.0085726334 0.0299210726 0.0670038015 0.0048598777 0.0853600000 401019581 0 402718720 -0.0103462394 -0.0427881926 -0.0447358042 1318 1311867762.5913679600 0.0074399761 0.0299040156 0.0670038015 0.0048581384 0.0754530000 405129261 0 402718720 -0.0114198048 -0.0446057506 -0.0434696600 1319 1311867762.6233699322 0.0078101368 0.0298872652 0.0670038015 0.0048564786 0.0511680000 409732785 0 402718720 -0.0111018810 -0.0449266285 -0.0434058458 1320 1311867762.6626110077 0.0076983585 0.0298704554 0.0670038015 0.0048557235 0.0656920000 409441001 0 402718720 -0.0108532291 -0.0447216444 -0.0452256091 1321 1311867762.6927230358 0.0082092984 0.0298540578 0.0670038015 0.0048542127 0.0905260000 408704605 0 402718720 -0.0103034684 -0.0450431034 -0.0451806113 1322 1311867762.7241640091 0.0086551020 0.0298380223 0.0670038015 0.0048524614 0.0463710000 400993181 0 402718720 -0.0104760015 -0.0448364764 -0.0442300364 1323 1311867762.7605299950 0.0087036686 0.0298220477 0.0670038015 0.0048522021 0.0283240000 400996577 0 402718720 -0.0096999127 -0.0459807552 -0.0464947782 1324 1311867762.7905199528 0.0076961555 0.0298053363 0.0670038015 0.0048514590 0.0622330000 401407385 0 402718720 -0.0114072692 -0.0455336981 -0.0450480655 1325 1311867762.8258841038 0.0073012430 0.0297883521 0.0670038015 0.0048498347 0.0846600000 401382261 0 402718720 -0.0118419481 -0.0458316468 -0.0446632951 1326 1311867762.8593358994 0.0076783421 0.0297716779 0.0670038015 0.0048485602 0.0783760000 403820469 0 402718720 -0.0112949554 -0.0459432900 -0.0449417084 1327 1311867762.8911890984 0.0086758286 0.0297557805 0.0670038015 0.0048474047 0.0634020000 410572605 0 402718720 -0.0109409494 -0.0453504510 -0.0435869060 1328 1311867762.9231870174 0.0081851045 0.0297395375 0.0670038015 0.0048459385 0.0636010000 409270777 0 402718720 -0.0107062934 -0.0463368297 -0.0444539562 1329 1311867762.9586219788 0.0080242213 0.0297231979 0.0670038015 0.0048441528 0.0353390000 409604109 0 402718720 -0.0111705940 -0.0456136689 -0.0451023504 1330 1311867762.9910819530 0.0089725833 0.0297075960 0.0670038015 0.0048424157 0.0817360000 407865441 0 402718720 -0.0106785456 -0.0452296957 -0.0444172323 1331 1311867763.0241999626 0.0102861309 0.0296930043 0.0670038015 0.0048407351 0.0343520000 401365013 0 402718720 -0.0096042100 -0.0446592234 -0.0433309227 1332 1311867763.0586409569 0.0085102273 0.0296771014 0.0670038015 0.0048420632 0.0361100000 401368593 0 402718720 -0.0100824172 -0.0472097993 -0.0444933251 1333 1311867763.0910348892 0.0089627355 0.0296615617 0.0670038015 0.0048404698 0.0272510000 401371685 0 402718720 -0.0094370767 -0.0470382310 -0.0455291830 1334 1311867763.1222279072 0.0094472384 0.0296464085 0.0670038015 0.0048389432 0.0276370000 401374857 0 402718720 -0.0088263191 -0.0466968752 -0.0452846140 1335 1311867763.1606709957 0.0084091742 0.0296305005 0.0670038015 0.0048374667 0.0318720000 401791625 0 402718720 -0.0101199467 -0.0459950753 -0.0454172119 1336 1311867763.1913530827 0.0081820721 0.0296144463 0.0670038015 0.0048363863 0.0816460000 401760189 0 402718720 -0.0101579893 -0.0463947542 -0.0450946763 1337 1311867763.2239060402 0.0083725946 0.0295985586 0.0670038015 0.0048346176 0.0758410000 401775737 0 402718720 -0.0095879827 -0.0463139042 -0.0455370992 1338 1311867763.2619409561 0.0090360884 0.0295831905 0.0670038015 0.0048328668 0.0692900000 409484337 0 402718720 -0.0089452323 -0.0458976403 -0.0443934910 1339 1311867763.2997210026 0.0079026120 0.0295669989 0.0670038015 0.0048323024 0.0634760000 409543945 0 402718720 -0.0088400934 -0.0481293313 -0.0447315313 1340 1311867763.3283360004 0.0084683383 0.0295512536 0.0670038015 0.0048306879 0.0870890000 408699733 0 402718720 -0.0078691980 -0.0475500561 -0.0462046564 1341 1311867763.3595879078 0.0085330773 0.0295355801 0.0670038015 0.0048300363 0.0293500000 401779361 0 402718720 -0.0084647937 -0.0473742783 -0.0430093259 1342 1311867763.3930239677 0.0076880162 0.0295193003 0.0670038015 0.0048284704 0.0282100000 401782805 0 402718720 -0.0086762803 -0.0474206358 -0.0444386750 1343 1311867763.4231410027 0.0093889860 0.0295043112 0.0670038015 0.0048268534 0.0285200000 401786105 0 402718720 -0.0067093456 -0.0467059463 -0.0448738262 1344 1311867763.4599080086 0.0100236302 0.0294898166 0.0670038015 0.0048250707 0.0542050000 401789229 0 402718720 -0.0055875634 -0.0466984808 -0.0451855659 1345 1311867763.4920830727 0.0066120476 0.0294728071 0.0670038015 0.0048235479 0.0313180000 402180861 0 402718720 -0.0085162073 -0.0485698134 -0.0443852693 1346 1311867763.5240089893 0.0075829593 0.0294565443 0.0670038015 0.0048220286 0.0794070000 402151225 0 402718720 -0.0068142014 -0.0484467000 -0.0464469306 1347 1311867763.5586268902 0.0076012411 0.0294403191 0.0670038015 0.0048204287 0.0723620000 404930577 0 402718720 -0.0064435452 -0.0490670875 -0.0444772094 1348 1311867763.5911428928 0.0069884383 0.0294236634 0.0670038015 0.0048188174 0.0508370000 409459701 0 402718720 -0.0074975053 -0.0486855060 -0.0445561782 1349 1311867763.6315419674 0.0077026212 0.0294075618 0.0670038015 0.0048171415 0.0815210000 408573357 0 402718720 -0.0071253479 -0.0475964434 -0.0473915040 1350 1311867763.6613171101 0.0073279636 0.0293912065 0.0670038015 0.0048155498 0.0312270000 402125317 0 402718720 -0.0064013498 -0.0496659875 -0.0447962210 1351 1311867763.6906011105 0.0080871340 0.0293754374 0.0670038015 0.0048138241 0.0286250000 402128417 0 402718720 -0.0058340132 -0.0488442630 -0.0461210795 1352 1311867763.7281720638 0.0071520004 0.0293590000 0.0670038015 0.0048122390 0.0279580000 402131909 0 402718720 -0.0068454603 -0.0490096286 -0.0459501520 1353 1311867763.7617700100 0.0067151166 0.0293422639 0.0670038015 0.0048106095 0.0280720000 402135137 0 402718720 -0.0069226585 -0.0497166067 -0.0461042672 1354 1311867763.7929420471 0.0081098936 0.0293265827 0.0670038015 0.0048090216 0.0279050000 402138157 0 402718720 -0.0057865591 -0.0496316031 -0.0450003482 1355 1311867763.8308730125 0.0060553215 0.0293094083 0.0670038015 0.0048087851 0.0318460000 402518557 0 402718720 -0.0087986067 -0.0491725020 -0.0456182100 1356 1311867763.8622579575 0.0093558803 0.0292946933 0.0670038015 0.0048083269 0.0793030000 402490209 0 402718720 -0.0069756303 -0.0469612852 -0.0441138670 1357 1311867763.8950018883 0.0075544906 0.0292786726 0.0670038015 0.0048100616 0.0701670000 408528225 0 402718720 -0.0066997050 -0.0488924831 -0.0475761518 1358 1311867763.9286549091 0.0064618434 0.0292618708 0.0670038015 0.0048083846 0.0477770000 410246317 0 402718720 -0.0076877610 -0.0497828498 -0.0473457277 1359 1311867763.9622230530 0.0073159062 0.0292457222 0.0670038015 0.0048067898 0.0757610000 409070497 0 402718720 -0.0063905064 -0.0497462265 -0.0494400933 1360 1311867763.9930698872 0.0069442401 0.0292293240 0.0670038015 0.0048051964 0.0429540000 402472465 0 402718720 -0.0069811689 -0.0500251874 -0.0480629988 1361 1311867764.0303530693 0.0067671598 0.0292128199 0.0670038015 0.0048040279 0.0275810000 402475589 0 402718720 -0.0069154389 -0.0505481102 -0.0486355238 1362 1311867764.0625600815 0.0082487492 0.0291974277 0.0670038015 0.0048031684 0.0275900000 402478617 0 402718720 -0.0058756284 -0.0493822321 -0.0479784347 1363 1311867764.0939369202 0.0062278775 0.0291805755 0.0670038015 0.0048019872 0.0282040000 402481797 0 402718720 -0.0072018234 -0.0505150631 -0.0494153574 1364 1311867764.1303229332 0.0074117007 0.0291646159 0.0670038015 0.0048004425 0.0375350000 402484945 0 402718720 -0.0070556202 -0.0490202382 -0.0496199951 1365 1311867764.1600530148 0.0069345660 0.0291483302 0.0670038015 0.0047997776 0.0307580000 402862113 0 402718720 -0.0076199821 -0.0491241850 -0.0491757989 1366 1311867764.1931879520 0.0061275251 0.0291314775 0.0670038015 0.0047980440 0.0753260000 403178809 0 402718720 -0.0084710428 -0.0495216921 -0.0492271408 1367 1311867764.2289299965 0.0081975833 0.0291161637 0.0670038015 0.0047966104 0.0692580000 408690901 0 402718720 -0.0082848277 -0.0471940450 -0.0502446368 1368 1311867764.2623479366 0.0071967328 0.0291001408 0.0670038015 0.0047956960 0.0397920000 410511217 0 402718720 -0.0070018857 -0.0507863350 -0.0485087782 1369 1311867764.2925939560 0.0071804961 0.0290841293 0.0670038015 0.0047944538 0.0463760000 410487501 0 402718720 -0.0064584534 -0.0515989587 -0.0498107225 1370 1311867764.3292350769 0.0064004431 0.0290675719 0.0670038015 0.0047946365 0.0752700000 409535249 0 402718720 -0.0092227580 -0.0504967757 -0.0496198423 1371 1311867764.3632280827 0.0080136340 0.0290522153 0.0670038015 0.0047934053 0.0318180000 402826045 0 402718720 -0.0071831835 -0.0504133478 -0.0499005914 1372 1311867764.3937499523 0.0074928477 0.0290365014 0.0670038015 0.0047921845 0.0273400000 402829137 0 402718720 -0.0099738603 -0.0488425717 -0.0500302613 1373 1311867764.4299139977 0.0073806974 0.0290207288 0.0670038015 0.0047927111 0.0416720000 402832685 0 402718720 -0.0095114717 -0.0499975085 -0.0504861251 1374 1311867764.4600350857 0.0089189606 0.0290060987 0.0670038015 0.0047924686 0.0316090000 403199301 0 402718720 -0.0084698591 -0.0493550301 -0.0500373915 1375 1311867764.4931490421 0.0078874268 0.0289907397 0.0670038015 0.0047943726 0.0729110000 403172677 0 402718720 -0.0090712067 -0.0500420034 -0.0517954081 1376 1311867764.5289220810 0.0067215641 0.0289745557 0.0670038015 0.0047985609 0.0674060000 407688621 0 402718720 -0.0095464177 -0.0515323728 -0.0541901141 1377 1311867764.5604650974 0.0070032929 0.0289585998 0.0670038015 0.0047993675 0.0423990000 410763653 0 402718720 -0.0109738475 -0.0495920628 -0.0556652099 1378 1311867764.5906419754 0.0090668527 0.0289441646 0.0670038015 0.0047980631 0.0737020000 409832257 0 402718720 -0.0098901624 -0.0487186275 -0.0524655841 1379 1311867764.6277070045 0.0071410723 0.0289283538 0.0670038015 0.0048080387 0.0733220000 403492821 0 402718720 -0.0124423727 -0.0490846708 -0.0546640120 1380 1311867764.6609039307 0.0085493149 0.0289135863 0.0670038015 0.0048139443 0.0690500000 406763045 0 402718720 -0.0103291292 -0.0489319637 -0.0547504798 1381 1311867764.6907351017 0.0069342828 0.0288976708 0.0670038015 0.0048128698 0.0470180000 410858821 0 402718720 -0.0104072280 -0.0515121296 -0.0557010695 1382 1311867764.7274560928 0.0076281866 0.0288822805 0.0670038015 0.0048123559 0.0401920000 410931645 0 402718720 -0.0127335424 -0.0489214398 -0.0555697046 1383 1311867764.7591719627 0.0065375054 0.0288661237 0.0670038015 0.0048112884 0.0777890000 410043481 0 402718720 -0.0126045253 -0.0513098836 -0.0555615015 1384 1311867764.7921779156 0.0076155490 0.0288507693 0.0670038015 0.0048097601 0.0638370000 403809589 0 402718720 -0.0114220167 -0.0506320968 -0.0568952411 1385 1311867764.8278260231 0.0065894960 0.0288346962 0.0670038015 0.0048086393 0.0697220000 406085153 0 402718720 -0.0134654883 -0.0507476404 -0.0562765673 1386 1311867764.8610520363 0.0061274660 0.0288183129 0.0670038015 0.0048076109 0.0737250000 408001161 0 402718720 -0.0147468271 -0.0503569320 -0.0571498722 1387 1311867764.8946199417 0.0072613573 0.0288027707 0.0670038015 0.0048061464 0.0735290000 404150929 0 402718720 -0.0132702515 -0.0501184128 -0.0575526133 1388 1311867764.9271790981 0.0068104859 0.0287869261 0.0670038015 0.0048051654 0.0692060000 409285369 0 402718720 -0.0139634646 -0.0505458042 -0.0571753159 1389 1311867764.9599800110 0.0080728466 0.0287720132 0.0670038015 0.0048036286 0.0560150000 410707493 0 402718720 -0.0135313123 -0.0492406860 -0.0579988658 1390 1311867764.9950439930 0.0070826863 0.0287564094 0.0670038015 0.0048025550 0.0801830000 410760037 0 402718720 -0.0152460486 -0.0488510430 -0.0576624125 1391 1311867765.0330669880 0.0068706051 0.0287406755 0.0670038015 0.0048028866 0.0618570000 404487001 0 402718720 -0.0143214585 -0.0509843938 -0.0568498150 1392 1311867765.0598719120 0.0076534040 0.0287255266 0.0670038015 0.0048013591 0.0731160000 404505365 0 402718720 -0.0138907181 -0.0498886518 -0.0576757863 1393 1311867765.0951199532 0.0068874462 0.0287098496 0.0670038015 0.0048001739 0.0622160000 412003785 0 402718720 -0.0152524430 -0.0494330004 -0.0562652685 1394 1311867765.1273620129 0.0068033147 0.0286941347 0.0670038015 0.0047989829 0.0556520000 411838165 0 402718720 -0.0158017091 -0.0492820665 -0.0564934015 1395 1311867765.1595649719 0.0078407228 0.0286791860 0.0670038015 0.0047974010 0.0823340000 410210857 0 402718720 -0.0149166808 -0.0490049273 -0.0566212237 1396 1311867765.1969060898 0.0081596607 0.0286644872 0.0670038015 0.0047961017 0.0740590000 404804509 0 402718720 -0.0165345818 -0.0469679721 -0.0571604595 1397 1311867765.2290871143 0.0058868481 0.0286481825 0.0670038015 0.0047953204 0.0718370000 409394133 0 402718720 -0.0165592879 -0.0508368090 -0.0572835095 1398 1311867765.2611060143 0.0051097618 0.0286313453 0.0670038015 0.0047939023 0.0501090000 412328001 0 402718720 -0.0178168844 -0.0501015335 -0.0589964911 1399 1311867765.2958459854 0.0071888096 0.0286160183 0.0670038015 0.0047928405 0.0507170000 412400205 0 402718720 -0.0172463767 -0.0481804684 -0.0577032268 1400 1311867765.3289039135 0.0074617052 0.0286009081 0.0670038015 0.0047913241 0.0739060000 411482909 0 402718720 -0.0160836037 -0.0492716506 -0.0584232509 1401 1311867765.3593490124 0.0071248570 0.0285855790 0.0670038015 0.0047898822 0.0376990000 404825321 0 402718720 -0.0167630650 -0.0486572385 -0.0591766015 1402 1311867765.3951449394 0.0073183626 0.0285704098 0.0670038015 0.0047886183 0.0363120000 405190057 0 402718720 -0.0174095631 -0.0495790690 -0.0572509915 1403 1311867765.4278709888 0.0052366783 0.0285537785 0.0670038015 0.0047879108 0.0744310000 405462473 0 402718720 -0.0195204131 -0.0492275655 -0.0595245324 1404 1311867765.4589679241 0.0078239692 0.0285390136 0.0670038015 0.0047869659 0.0646220000 411416553 0 402718720 -0.0182863139 -0.0473492481 -0.0580434874 1405 1311867765.4974000454 0.0068280622 0.0285235610 0.0670038015 0.0047852941 0.0725980000 410517277 0 402718720 -0.0191822629 -0.0473291725 -0.0589822009 1406 1311867765.5298929214 0.0068704481 0.0285081605 0.0670038015 0.0047836330 0.0655610000 405407985 0 402718720 -0.0191096589 -0.0471589118 -0.0590407401 1407 1311867765.5625720024 0.0055188080 0.0284918212 0.0670038015 0.0047825864 0.0677960000 407739189 0 402718720 -0.0189202446 -0.0483174399 -0.0605740026 1408 1311867765.5947990417 0.0067415228 0.0284763736 0.0670038015 0.0047812682 0.0539730000 412642493 0 402718720 -0.0185003448 -0.0466507636 -0.0608493276 1409 1311867765.6310911179 0.0066929264 0.0284609134 0.0670038015 0.0047799899 0.0724180000 411754101 0 402718720 -0.0190215502 -0.0463713184 -0.0601590127 1410 1311867765.6618249416 0.0070102047 0.0284457001 0.0670038015 0.0047786714 0.0713030000 405730201 0 402718720 -0.0180165712 -0.0469616689 -0.0610520393 1411 1311867765.6966838837 0.0080345441 0.0284312344 0.0670038015 0.0047778027 0.0664810000 410526997 0 402718720 -0.0185970273 -0.0459304564 -0.0587727875 1412 1311867765.7292089462 0.0083604557 0.0284170199 0.0670038015 0.0047762786 0.0589830000 411689569 0 402718720 -0.0190178417 -0.0445837006 -0.0593950115 1413 1311867765.7602009773 0.0063376604 0.0284013941 0.0670038015 0.0047757184 0.0723350000 411673001 0 402718720 -0.0198852941 -0.0462325737 -0.0610228553 1414 1311867765.7960450649 0.0070198691 0.0283862727 0.0670038015 0.0047756131 0.0362350000 405747621 0 402718720 -0.0205662064 -0.0460713580 -0.0590352714 1415 1311867765.8298408985 0.0063451286 0.0283706960 0.0670038015 0.0047747729 0.0311040000 406117121 0 402718720 -0.0200396813 -0.0465277992 -0.0608274601 1416 1311867765.8610999584 0.0066026924 0.0283553231 0.0670038015 0.0047731654 0.0750670000 406088261 0 402718720 -0.0197301935 -0.0454284064 -0.0621986166 1417 1311867765.8960449696 0.0064732856 0.0283398806 0.0670038015 0.0047715459 0.0676650000 411236605 0 402718720 -0.0195534620 -0.0461281650 -0.0621015280 1418 1311867765.9303019047 0.0053746551 0.0283236851 0.0670038015 0.0047704502 0.0579100000 413172589 0 402718720 -0.0212713834 -0.0453727804 -0.0616603419 1419 1311867765.9612519741 0.0067166784 0.0283084581 0.0670038015 0.0047690596 0.0766260000 412674913 0 402718720 -0.0196251217 -0.0450021513 -0.0617952012 1420 1311867765.9962689877 0.0069244504 0.0282933990 0.0670038015 0.0047676971 0.0749710000 406404905 0 402718720 -0.0184999816 -0.0461788923 -0.0610015094 1421 1311867766.0289440155 0.0069078142 0.0282783493 0.0670038015 0.0047664884 0.0690410000 410737861 0 402718720 -0.0183457974 -0.0460329466 -0.0612031892 1422 1311867766.0606811047 0.0076773637 0.0282638620 0.0670038015 0.0047648354 0.0443170000 413673129 0 402718720 -0.0175061524 -0.0455278382 -0.0614974052 1423 1311867766.0968139172 0.0075558219 0.0282493096 0.0670038015 0.0047632228 0.0465430000 413682141 0 402718720 -0.0171944611 -0.0454728305 -0.0611944944 1424 1311867766.1277561188 0.0077069155 0.0282348838 0.0670038015 0.0047619950 0.0605220000 406780329 0 402718720 -0.0176207609 -0.0440874510 -0.0595440418 1425 1311867766.1625239849 0.0091951946 0.0282215226 0.0670038015 0.0047603945 0.0759790000 408930797 0 402718720 -0.0162502658 -0.0429548398 -0.0601181686 1426 1311867766.1968889236 0.0079850759 0.0282073315 0.0670038015 0.0047588767 0.0576370000 414207953 0 402718720 -0.0169043969 -0.0436915159 -0.0591104738 1427 1311867766.2298009396 0.0075072660 0.0281928255 0.0670038015 0.0047573603 0.0420110000 414040293 0 402718720 -0.0166242477 -0.0446924940 -0.0583493710 1428 1311867766.2654640675 0.0088950358 0.0281793117 0.0670038015 0.0047558272 0.0785710000 413069825 0 402718720 -0.0159491207 -0.0433006734 -0.0579268783 1429 1311867766.2981679440 0.0083983038 0.0281654691 0.0670038015 0.0047556391 0.0361300000 406725161 0 402718720 -0.0172898285 -0.0422288254 -0.0570934862 1430 1311867766.3291699886 0.0094290329 0.0281523667 0.0670038015 0.0047746371 0.0282020000 406728485 0 402718720 -0.0154370172 -0.0432699919 -0.0559078902 1431 1311867766.3653209209 0.0082158260 0.0281384348 0.0670038015 0.0047910513 0.0331920000 407118005 0 402718720 -0.0157202911 -0.0435139164 -0.0546193756 1432 1311867766.3979220390 0.0071731019 0.0281237942 0.0670038015 0.0047959096 0.0810900000 407087105 0 402718720 -0.0168696046 -0.0433566906 -0.0545400828 1433 1311867766.4302849770 0.0072163981 0.0281092043 0.0670038015 0.0047964172 0.0634470000 414636441 0 402718720 -0.0160051305 -0.0439905152 -0.0531968661 1434 1311867766.4642350674 0.0069893315 0.0280944763 0.0670038015 0.0047999972 0.0616170000 414478053 0 402718720 -0.0164298173 -0.0441819914 -0.0537038967 1435 1311867766.4967210293 0.0076797255 0.0280802500 0.0670038015 0.0047985641 0.0846880000 413606341 0 402718720 -0.0153216738 -0.0442258865 -0.0537781343 1436 1311867766.5302040577 0.0084789749 0.0280666001 0.0670038015 0.0047971898 0.0436970000 407003281 0 402718720 -0.0139931375 -0.0440610796 -0.0531773716 1437 1311867766.5639820099 0.0084418776 0.0280529434 0.0670038015 0.0047955624 0.0285680000 407006805 0 402718720 -0.0135110915 -0.0441640429 -0.0520159081 1438 1311867766.5953519344 0.0077679022 0.0280388369 0.0670038015 0.0047948366 0.0494730000 407009825 0 402718720 -0.0139850918 -0.0443828776 -0.0513402298 1439 1311867766.6287128925 0.0070761177 0.0280242694 0.0670038015 0.0047934933 0.0283870000 407013157 0 402718720 -0.0138300555 -0.0456194356 -0.0526926666 1440 1311867766.6636400223 0.0081595853 0.0280104745 0.0670038015 0.0047927619 0.0318770000 407419989 0 402718720 -0.0115127852 -0.0467957668 -0.0529650450 1441 1311867766.6964800358 0.0072327191 0.0279960555 0.0670038015 0.0048064332 0.0848740000 407402129 0 402718720 -0.0111864414 -0.0483720452 -0.0542580001 1442 1311867766.7300829887 0.0070925597 0.0279815593 0.0670038015 0.0048134621 0.0768500000 411001629 0 402718720 -0.0113910260 -0.0483788066 -0.0557592958 1443 1311867766.7628269196 0.0099484101 0.0279690623 0.0670038015 0.0048120575 0.0453000000 415007529 0 402718720 -0.0083412714 -0.0476856455 -0.0556518435 1444 1311867766.7970418930 0.0078860847 0.0279551544 0.0670038015 0.0048123665 0.0449400000 414734637 0 402718720 -0.0100774951 -0.0488733537 -0.0551613420 1445 1311867766.8299551010 0.0094896099 0.0279423755 0.0670038015 0.0048109070 0.0819530000 413865745 0 402718720 -0.0083888089 -0.0480737835 -0.0558678657 1446 1311867766.8662180901 0.0103870351 0.0279302349 0.0670038015 0.0048102962 0.0288210000 407419161 0 402718720 -0.0082889544 -0.0468061641 -0.0562962852 1447 1311867766.8958721161 0.0079235034 0.0279164085 0.0670038015 0.0048096737 0.0285410000 407422301 0 402718720 -0.0097165769 -0.0483178161 -0.0581650920 1448 1311867766.9286260605 0.0076069981 0.0279023827 0.0670038015 0.0048189947 0.0293340000 407425521 0 402718720 -0.0104514034 -0.0483593717 -0.0591549948 1449 1311867766.9661469460 0.0092701055 0.0278895240 0.0670038015 0.0048316955 0.0287530000 407428789 0 402718720 -0.0079617705 -0.0467140637 -0.0613685586 1450 1311867766.9956479073 0.0068367394 0.0278750048 0.0670038015 0.0048308191 0.0416760000 407431873 0 402718720 -0.0090131359 -0.0489347950 -0.0608422160 1451 1311867767.0294270515 0.0069130696 0.0278605583 0.0670038015 0.0048299232 0.0293230000 407435149 0 402718720 -0.0085099367 -0.0490597486 -0.0609367192 1452 1311867767.0660951138 0.0070263823 0.0278462097 0.0670038015 0.0048285805 0.0287640000 407438241 0 402718720 -0.0093184812 -0.0480978377 -0.0612469763 1453 1311867767.0968320370 0.0088327499 0.0278331240 0.0670038015 0.0048271872 0.0406810000 407441709 0 402718720 -0.0073792594 -0.0472724661 -0.0607285723 1454 1311867767.1276900768 0.0080898069 0.0278195454 0.0670038015 0.0048273759 0.0284980000 407444369 0 402718720 -0.0086207958 -0.0479147211 -0.0592551827 1455 1311867767.1632909775 0.0070944997 0.0278053014 0.0670038015 0.0048261173 0.0331190000 407447965 0 402718720 -0.0088369576 -0.0491565056 -0.0606582649 1456 1311867767.1955349445 0.0085877078 0.0277921025 0.0670038015 0.0048249948 0.0293970000 407451241 0 402718720 -0.0071329991 -0.0490221828 -0.0611025169 1457 1311867767.2308650017 0.0075020972 0.0277781766 0.0670038015 0.0048235627 0.0288900000 407454109 0 402718720 -0.0086919367 -0.0492219105 -0.0612253398 1458 1311867767.2658200264 0.0097365454 0.0277658024 0.0670038015 0.0048221054 0.0285510000 407457697 0 402718720 -0.0074699474 -0.0475165024 -0.0615315214 1459 1311867767.2981290817 0.0093189515 0.0277531589 0.0670038015 0.0048218312 0.0286500000 407460733 0 402718720 -0.0078535201 -0.0480082668 -0.0591928586 1460 1311867767.3362140656 0.0082877260 0.0277398264 0.0670038015 0.0048234200 0.0287230000 407464113 0 402718720 -0.0092164641 -0.0480002686 -0.0605889335 1461 1311867767.3633511066 0.0086213937 0.0277267405 0.0670038015 0.0048217921 0.0289450000 407467229 0 402718720 -0.0083316956 -0.0488221534 -0.0584495068 1462 1311867767.3987689018 0.0096210008 0.0277143563 0.0670038015 0.0048208120 0.0373100000 407470425 0 402718720 -0.0095969429 -0.0469657183 -0.0614157766 1463 1311867767.4331369400 0.0097815515 0.0277020987 0.0670038015 0.0048201180 0.0290830000 407473437 0 402718720 -0.0078957435 -0.0479446128 -0.0617004037 1464 1311867767.4638109207 0.0096631711 0.0276897771 0.0670038015 0.0048191835 0.0295340000 407477025 0 402718720 -0.0093200682 -0.0466718003 -0.0593745857 1465 1311867767.4974899292 0.0100569343 0.0276777410 0.0670038015 0.0048175904 0.0291630000 407480053 0 402718720 -0.0090994602 -0.0463602766 -0.0594525672 1466 1311867767.5351889133 0.0089827450 0.0276649886 0.0670038015 0.0048195364 0.0294600000 407483385 0 402718720 -0.0093582654 -0.0468330383 -0.0608124658 1467 1311867767.5664100647 0.0086257048 0.0276520102 0.0670038015 0.0048199296 0.0294770000 407486533 0 402718720 -0.0107503161 -0.0464114137 -0.0588617548 1468 1311867767.5953979492 0.0108972127 0.0276405969 0.0670038015 0.0048185746 0.0291070000 407489377 0 402718720 -0.0088026421 -0.0454325452 -0.0603319108 1469 1311867767.6338059902 0.0103808586 0.0276288476 0.0670038015 0.0048177618 0.0407800000 407492853 0 402718720 -0.0110867983 -0.0448247865 -0.0599628948 1470 1311867767.6632149220 0.0097444691 0.0276166813 0.0670038015 0.0048164519 0.0295340000 407496025 0 402718720 -0.0106856236 -0.0460100695 -0.0593262687 1471 1311867767.6991050243 0.0102643417 0.0276048850 0.0670038015 0.0048151378 0.0378410000 407499253 0 402718720 -0.0107206516 -0.0457075424 -0.0599329546 1472 1311867767.7346129417 0.0107438555 0.0275934305 0.0670038015 0.0048139926 0.0293700000 407502265 0 402718720 -0.0106099285 -0.0455593169 -0.0589027964 1473 1311867767.7651679516 0.0114979092 0.0275825035 0.0670038015 0.0048124835 0.0296490000 407505781 0 402718720 -0.0095999725 -0.0457085408 -0.0602627993 1474 1311867767.7999849319 0.0091391467 0.0275699911 0.0670038015 0.0048113276 0.0298110000 407509033 0 402718720 -0.0136568313 -0.0459779538 -0.0610134862 1475 1311867767.8344929218 0.0094367731 0.0275576973 0.0670038015 0.0048111386 0.0297100000 407512133 0 402718720 -0.0117693814 -0.0471291877 -0.0622041672 1476 1311867767.8673300743 0.0102799153 0.0275459915 0.0670038015 0.0048103429 0.0298650000 407515345 0 402718720 -0.0116342045 -0.0459245965 -0.0606255680 1477 1311867767.8966870308 0.0111028887 0.0275348588 0.0670038015 0.0048087897 0.0298810000 407518589 0 402718720 -0.0107461112 -0.0454439297 -0.0606353283 1478 1311867767.9358460903 0.0105671166 0.0275233786 0.0670038015 0.0048074017 0.0389240000 407521977 0 402718720 -0.0126113221 -0.0447716378 -0.0618089288 1479 1311867767.9646739960 0.0111380694 0.0275122999 0.0670038015 0.0048064022 0.0296420000 407525085 0 402718720 -0.0127263935 -0.0437951162 -0.0597455874 1480 1311867767.9988079071 0.0100357076 0.0275004914 0.0670038015 0.0048048537 0.0301720000 407528401 0 402718720 -0.0127728283 -0.0449253172 -0.0602488592 1481 1311867768.0346310139 0.0108818188 0.0274892702 0.0670038015 0.0048032791 0.0295840000 407531533 0 402718720 -0.0129878735 -0.0435671546 -0.0613679066 1482 1311867768.0639820099 0.0108307488 0.0274780296 0.0670038015 0.0048016950 0.0424020000 407534729 0 402718720 -0.0129606621 -0.0436351784 -0.0604039580 1483 1311867768.0985600948 0.0091133201 0.0274656461 0.0670038015 0.0048002692 0.0301220000 407537925 0 402718720 -0.0138848145 -0.0452923961 -0.0608623698 1484 1311867768.1352849007 0.0092181573 0.0274533500 0.0670038015 0.0047987959 0.0337840000 407974569 0 402718720 -0.0143354023 -0.0451992676 -0.0611412078 1485 1311867768.1651999950 0.0124039892 0.0274432157 0.0670038015 0.0047979620 0.0895910000 407970785 0 402718720 -0.0132238995 -0.0423178002 -0.0611720532 1486 1311867768.1962070465 0.0115301935 0.0274325071 0.0670038015 0.0047965985 0.0846190000 408249689 0 402718720 -0.0138854515 -0.0429503173 -0.0609816723 1487 1311867768.2323460579 0.0089654988 0.0274200881 0.0670038015 0.0047953533 0.0652040000 416554569 0 402718720 -0.0153294029 -0.0451534465 -0.0605027825 1488 1311867768.2749121189 0.0119855646 0.0274097154 0.0670038015 0.0047938149 0.0682990000 417624945 0 402718720 -0.0141659752 -0.0421633124 -0.0626669452 1489 1311867768.2962079048 0.0105057303 0.0273983629 0.0670038015 0.0047925765 0.0968370000 415252949 0 402718720 -0.0166478865 -0.0424005874 -0.0630034432 1490 1311867768.3351829052 0.0100789350 0.0273867391 0.0670038015 0.0047952612 0.0455300000 407920849 0 402718720 -0.0153116779 -0.0427960455 -0.0626577362 1491 1311867768.3693380356 0.0091631766 0.0273745167 0.0670038015 0.0047937807 0.0311220000 407924261 0 402718720 -0.0158491321 -0.0434167013 -0.0610294193 1492 1311867768.4011199474 0.0126167592 0.0273646255 0.0670038015 0.0047937779 0.0320570000 407927193 0 402718720 -0.0136241447 -0.0406071022 -0.0616550148 1493 1311867768.4324789047 0.0119088087 0.0273542733 0.0670038015 0.0047922209 0.0314610000 407930021 0 402718720 -0.0147786131 -0.0404552519 -0.0618558936 1494 1311867768.4655070305 0.0101425471 0.0273427527 0.0670038015 0.0047909850 0.0318720000 407933665 0 402718720 -0.0169601161 -0.0413620397 -0.0601032339 1495 1311867768.4980540276 0.0105871782 0.0273315450 0.0670038015 0.0047904668 0.0315430000 407936645 0 402718720 -0.0182431601 -0.0402681679 -0.0608753748 1496 1311867768.5367710590 0.0129858144 0.0273219556 0.0670038015 0.0047893400 0.0319080000 407939825 0 402718720 -0.0162134822 -0.0384489335 -0.0638553277 1497 1311867768.5648899078 0.0124721900 0.0273120359 0.0670038015 0.0047891663 0.0322040000 407943413 0 402718720 -0.0150330076 -0.0390870683 -0.0612422116 1498 1311867768.5998411179 0.0116756251 0.0273015977 0.0670038015 0.0047879353 0.0326190000 407946361 0 402718720 -0.0158425644 -0.0395726748 -0.0601598248 1499 1311867768.6319470406 0.0112673305 0.0272909011 0.0670038015 0.0047864061 0.0318460000 407949589 0 402718720 -0.0163874328 -0.0396643952 -0.0600450560 1500 1311867768.6643230915 0.0140393171 0.0272820667 0.0670038015 0.0047851800 0.0318170000 407953177 0 402718720 -0.0138290310 -0.0378101692 -0.0601183400 1501 1311867768.7014238834 0.0120470431 0.0272719167 0.0670038015 0.0047838451 0.0316910000 407955837 0 402718720 -0.0158902314 -0.0391976051 -0.0617944375 1502 1311867768.7344141006 0.0093434304 0.0272599803 0.0670038015 0.0047824287 0.0326430000 407959305 0 402718720 -0.0191458315 -0.0409203582 -0.0604189895 1503 1311867768.7646389008 0.0126095703 0.0272502329 0.0670038015 0.0047817294 0.0320890000 407962429 0 402718720 -0.0160697885 -0.0383129120 -0.0601448193 1504 1311867768.8039369583 0.0124012474 0.0272403599 0.0670038015 0.0047812733 0.0323970000 407965665 0 402718720 -0.0173510555 -0.0376747698 -0.0588783547 1505 1311867768.8365039825 0.0116771851 0.0272300189 0.0670038015 0.0047800538 0.0319290000 407969029 0 402718720 -0.0181588642 -0.0381194390 -0.0591353104 1506 1311867768.8651020527 0.0099267317 0.0272185293 0.0670038015 0.0047789510 0.0327970000 407972081 0 402718720 -0.0183374044 -0.0397835262 -0.0580082126 1507 1311867768.9001519680 0.0109212259 0.0272077149 0.0670038015 0.0047778499 0.0330300000 407975213 0 402718720 -0.0167882834 -0.0393421948 -0.0594240129 1508 1311867768.9330470562 0.0107054068 0.0271967718 0.0670038015 0.0047771813 0.0328270000 407978657 0 402718720 -0.0174661931 -0.0387319401 -0.0576850809 1509 1311867768.9639101028 0.0096125994 0.0271851189 0.0670038015 0.0047757884 0.0330900000 407981621 0 402718720 -0.0185625032 -0.0397311822 -0.0583580844 1510 1311867768.9992640018 0.0108734751 0.0271743165 0.0670038015 0.0047751712 0.0328760000 407984961 0 402718720 -0.0155599853 -0.0389103554 -0.0568153337 1511 1311867769.0331530571 0.0116701247 0.0271640556 0.0670038015 0.0047743042 0.0324190000 407987877 0 402718720 -0.0163923148 -0.0373377129 -0.0571461916 1512 1311867769.0641028881 0.0104109095 0.0271529755 0.0670038015 0.0047730260 0.0444750000 407991233 0 402718720 -0.0170827452 -0.0382920504 -0.0566949770 1513 1311867769.0999929905 0.0095409919 0.0271413351 0.0670038015 0.0047716547 0.0435210000 407994237 0 402718720 -0.0192883592 -0.0390155837 -0.0571221709 1514 1311867769.1327989101 0.0099172024 0.0271299585 0.0670038015 0.0047702210 0.0425250000 407997809 0 402718720 -0.0178056546 -0.0389386266 -0.0575172901 1515 1311867769.1643240452 0.0106785493 0.0271190995 0.0670038015 0.0047740623 0.0318810000 408000669 0 402718720 -0.0169482920 -0.0386226103 -0.0564164445 1516 1311867769.2002429962 0.0113444347 0.0271086940 0.0670038015 0.0047751119 0.0320510000 408003697 0 402718720 -0.0175216328 -0.0373660624 -0.0559427813 1517 1311867769.2324860096 0.0107660992 0.0270979210 0.0670038015 0.0047765299 0.0321320000 408006973 0 402718720 -0.0174907576 -0.0381467342 -0.0557235032 1518 1311867769.2636189461 0.0107560325 0.0270871556 0.0670038015 0.0047763192 0.0319170000 408009993 0 402718720 -0.0175241344 -0.0377374738 -0.0555126816 1519 1311867769.3002018929 0.0104868039 0.0270762272 0.0670038015 0.0047802288 0.0321990000 408013389 0 402718720 -0.0172994807 -0.0377940908 -0.0560108796 1520 1311867769.3330841064 0.0116480421 0.0270660770 0.0670038015 0.0047799132 0.0325110000 408016441 0 402718720 -0.0166905783 -0.0362628549 -0.0557475947 1521 1311867769.3653230667 0.0128201051 0.0270567108 0.0670038015 0.0047785371 0.0317990000 408019797 0 402718720 -0.0169568863 -0.0346486457 -0.0560099706 1522 1311867769.3995320797 0.0118650785 0.0270467295 0.0670038015 0.0047769727 0.0323460000 408023097 0 402718720 -0.0173800830 -0.0347654223 -0.0547720939 1523 1311867769.4340240955 0.0112037221 0.0270363270 0.0670038015 0.0047755089 0.0451480000 408026357 0 402718720 -0.0167293213 -0.0352317691 -0.0544191003 1524 1311867769.4644269943 0.0123671843 0.0270267016 0.0670038015 0.0047823672 0.0320300000 408029313 0 402718720 -0.0149304112 -0.0348167457 -0.0547731221 1525 1311867769.4999239445 0.0119179338 0.0270167942 0.0670038015 0.0047844929 0.0320730000 408032685 0 402718720 -0.0179725867 -0.0338635221 -0.0555254743 1526 1311867769.5317490101 0.0096406601 0.0270054075 0.0670038015 0.0047830105 0.0329280000 408035841 0 402718720 -0.0179202650 -0.0357922465 -0.0535112917 1527 1311867769.5660109520 0.0106164431 0.0269946747 0.0670038015 0.0047815538 0.0328000000 408039013 0 402718720 -0.0169540960 -0.0354437120 -0.0549090728 1528 1311867769.6002509594 0.0120868431 0.0269849182 0.0670038015 0.0047812303 0.0692930000 408042169 0 402718720 -0.0194643624 -0.0333144888 -0.0544168241 1529 1311867769.6330249310 0.0088829799 0.0269730792 0.0670038015 0.0047845682 0.0322980000 408045373 0 402718720 -0.0186227914 -0.0364709161 -0.0540685803 1530 1311867769.6637229919 0.0095141167 0.0269616681 0.0670038015 0.0047832662 0.0327240000 408048465 0 402718720 -0.0179191008 -0.0360582471 -0.0534558930 1531 1311867769.7014029026 0.0116657345 0.0269516773 0.0670038015 0.0047858932 0.0324620000 408051981 0 402718720 -0.0164806321 -0.0344184302 -0.0548564196 1532 1311867769.7340829372 0.0114238458 0.0269415416 0.0670038015 0.0047844904 0.0322630000 408054817 0 402718720 -0.0164305642 -0.0340148099 -0.0529221110 1533 1311867769.7641069889 0.0120284213 0.0269318135 0.0670038015 0.0047899186 0.0658360000 408058061 0 402718720 -0.0181180462 -0.0326057300 -0.0521646254 1534 1311867769.8003458977 0.0099501768 0.0269207434 0.0670038015 0.0048115706 0.0323530000 408061217 0 402718720 -0.0172820594 -0.0344740003 -0.0504768528 1535 1311867769.8341090679 0.0108474717 0.0269102722 0.0670038015 0.0048102881 0.0458300000 408064501 0 402718720 -0.0176323093 -0.0332163759 -0.0509533063 1536 1311867769.8692820072 0.0098588169 0.0268991710 0.0670038015 0.0048089080 0.0326450000 408068017 0 402718720 -0.0157177486 -0.0342253633 -0.0491803512 1537 1311867769.9001140594 0.0097364141 0.0268880046 0.0670038015 0.0048075927 0.0327460000 408071037 0 402718720 -0.0181034282 -0.0328978784 -0.0490579978 1538 1311867769.9321451187 0.0114638275 0.0268779759 0.0670038015 0.0048062771 0.0328890000 408073953 0 402718720 -0.0180987660 -0.0307824202 -0.0497293137 1539 1311867769.9684319496 0.0084862616 0.0268660254 0.0670038015 0.0048049481 0.0332140000 408077565 0 402718720 -0.0197601132 -0.0330842994 -0.0486668348 1540 1311867770.0010259151 0.0095042977 0.0268547516 0.0670038015 0.0048040968 0.0328150000 408080505 0 402718720 -0.0180857275 -0.0315594077 -0.0478117280 1541 1311867770.0330319405 0.0093088923 0.0268433656 0.0670038015 0.0048026191 0.0330710000 408083565 0 402718720 -0.0183851495 -0.0312110856 -0.0476009138 1542 1311867770.0690810680 0.0081620608 0.0268312506 0.0670038015 0.0048034765 0.0332930000 408087161 0 402718720 -0.0183072221 -0.0320761353 -0.0468700752 1543 1311867770.1002650261 0.0070901653 0.0268184566 0.0670038015 0.0048027950 0.0332410000 408090181 0 402718720 -0.0189401601 -0.0328478403 -0.0470073409 1544 1311867770.1335709095 0.0077165226 0.0268060849 0.0670038015 0.0048023256 0.0334830000 408093393 0 402718720 -0.0179091077 -0.0330639184 -0.0487662330 1545 1311867770.1684958935 0.0074250214 0.0267935405 0.0670038015 0.0048009915 0.0419990000 408096749 0 402718720 -0.0191019494 -0.0323765874 -0.0475075468 1546 1311867770.2001299858 0.0069414671 0.0267806996 0.0670038015 0.0047995024 0.0332810000 408099673 0 402718720 -0.0184824746 -0.0329176299 -0.0470894575 1547 1311867770.2336180210 0.0072424947 0.0267680698 0.0670038015 0.0047995564 0.0423360000 408103269 0 402718720 -0.0201741476 -0.0333245881 -0.0484936796 1548 1311867770.2679719925 0.0058056409 0.0267545282 0.0670038015 0.0047996627 0.0328560000 408106265 0 402718720 -0.0190111492 -0.0334068872 -0.0458739698 1549 1311867770.3009040356 0.0066446192 0.0267415457 0.0670038015 0.0047990617 0.0324920000 408109669 0 402718720 -0.0182491802 -0.0332327373 -0.0461447574 1550 1311867770.3339090347 0.0052411570 0.0267276745 0.0670038015 0.0048002724 0.0332680000 408112569 0 402718720 -0.0195358656 -0.0337253287 -0.0450312532 1551 1311867770.3681850433 0.0068606613 0.0267148653 0.0670038015 0.0048119200 0.0332680000 408115581 0 402718720 -0.0213252995 -0.0323077627 -0.0455341414 1552 1311867770.4014930725 0.0064000515 0.0267017759 0.0670038015 0.0048145748 0.0335790000 408118809 0 402718720 -0.0191606861 -0.0330429114 -0.0455182567 1553 1311867770.4333899021 0.0071077552 0.0266891590 0.0670038015 0.0048156481 0.0435130000 408122189 0 402718720 -0.0204017237 -0.0320486426 -0.0456029363 1554 1311867770.4684588909 0.0054832217 0.0266755130 0.0670038015 0.0048141090 0.0328370000 408125553 0 402718720 -0.0212739706 -0.0331887193 -0.0442021377 1555 1311867770.5046019554 0.0045924648 0.0266613117 0.0670038015 0.0048135521 0.0416570000 408128621 0 402718720 -0.0197127573 -0.0351564474 -0.0447617881 1556 1311867770.5338129997 0.0050821742 0.0266474433 0.0670038015 0.0048122087 0.0331120000 408131785 0 402718720 -0.0218909755 -0.0343797840 -0.0456728265 1557 1311867770.5683600903 0.0059982887 0.0266341812 0.0670038015 0.0048164918 0.0331040000 408134733 0 402718720 -0.0206958000 -0.0332769491 -0.0443511717 1558 1311867770.6027359962 0.0058526546 0.0266208426 0.0670038015 0.0048184111 0.0326320000 408138081 0 402718720 -0.0223673321 -0.0328078680 -0.0447728597 1559 1311867770.6331069469 0.0068003866 0.0266081290 0.0670038015 0.0048171144 0.0333060000 408141013 0 402718720 -0.0208432693 -0.0318138376 -0.0439435616 1560 1311867770.6699299812 0.0054132594 0.0265945426 0.0670038015 0.0048157473 0.0335100000 408144729 0 402718720 -0.0210713334 -0.0333070271 -0.0442721657 1561 1311867770.7014191151 0.0045261192 0.0265804052 0.0670038015 0.0048142548 0.0332010000 408147749 0 402718720 -0.0201799814 -0.0338973142 -0.0432861745 1562 1311867770.7347331047 0.0070361132 0.0265678928 0.0670038015 0.0048130172 0.0331860000 408150761 0 402718720 -0.0191128328 -0.0314247608 -0.0439187139 1563 1311867770.7684218884 0.0044214954 0.0265537237 0.0670038015 0.0048116672 0.0458040000 408153909 0 402718720 -0.0217272732 -0.0337188505 -0.0430445969 1564 1311867770.8017508984 0.0038102649 0.0265391818 0.0670038015 0.0048103442 0.0328640000 408157089 0 402718720 -0.0223993380 -0.0344753340 -0.0423566476 1565 1311867770.8396499157 0.0047263447 0.0265252439 0.0670038015 0.0048093031 0.0332930000 408160413 0 402718720 -0.0200246815 -0.0326464288 -0.0416270234 1566 1311867770.8699400425 0.0051942877 0.0265116226 0.0670038015 0.0048096096 0.0331990000 408163569 0 402718720 -0.0184812900 -0.0332303979 -0.0424130149 1567 1311867770.9027009010 0.0035174149 0.0264969486 0.0670038015 0.0048098361 0.0333130000 408166845 0 402718720 -0.0207961351 -0.0335241854 -0.0411056057 1568 1311867770.9355690479 0.0050282404 0.0264832568 0.0670038015 0.0048094286 0.0329000000 408169921 0 402718720 -0.0208387114 -0.0317664444 -0.0412615538 1569 1311867770.9692869186 0.0039943731 0.0264689235 0.0670038015 0.0048093065 0.0335610000 408173237 0 402718720 -0.0193433370 -0.0330531858 -0.0411431938 1570 1311867771.0021619797 0.0047981511 0.0264551205 0.0670038015 0.0048110953 0.0421860000 408176705 0 402718720 -0.0176778045 -0.0331052542 -0.0409330316 1571 1311867771.0365509987 0.0044834744 0.0264411347 0.0670038015 0.0048210612 0.0332260000 408179277 0 402718720 -0.0205767695 -0.0327090770 -0.0416461825 1572 1311867771.0685739517 0.0049603833 0.0264274701 0.0670038015 0.0048198830 0.0334500000 408182833 0 402718720 -0.0193372127 -0.0312632136 -0.0407539494 1573 1311867771.1014111042 0.0035271752 0.0264129118 0.0670038015 0.0048212470 0.0337010000 408185925 0 402718720 -0.0193023067 -0.0323496573 -0.0396532863 1574 1311867771.1381099224 0.0036999946 0.0263984817 0.0670038015 0.0048200861 0.0332980000 408189265 0 402718720 -0.0195192248 -0.0327141955 -0.0403256752 1575 1311867771.1686840057 0.0047015790 0.0263847059 0.0670038015 0.0048203193 0.0331920000 408192309 0 402718720 -0.0201741848 -0.0299656391 -0.0388225764 1576 1311867771.2019159794 0.0033238397 0.0263700734 0.0670038015 0.0048190863 0.0329500000 408195585 0 402718720 -0.0200533047 -0.0312531851 -0.0382837318 1577 1311867771.2363801003 0.0044620959 0.0263561812 0.0670038015 0.0048178343 0.0331420000 408198805 0 402718720 -0.0217983015 -0.0307577662 -0.0394488610 1578 1311867771.2705540657 0.0054035280 0.0263429032 0.0670038015 0.0048164746 0.0445600000 408201697 0 402718720 -0.0181928854 -0.0298363771 -0.0394963287 1579 1311867771.3016860485 0.0034147711 0.0263283825 0.0670038015 0.0048150791 0.0338250000 408205317 0 402718720 -0.0193950422 -0.0305436440 -0.0377012268 1580 1311867771.3360719681 0.0020809867 0.0263130361 0.0670038015 0.0048136562 0.0454790000 408208217 0 402718720 -0.0201047789 -0.0326254442 -0.0377505012 1581 1311867771.3679900169 0.0032700982 0.0262984612 0.0670038015 0.0048123398 0.0333030000 408211701 0 402718720 -0.0202967469 -0.0320576020 -0.0386615731 1582 1311867771.4030399323 0.0059405314 0.0262855927 0.0670038015 0.0048112626 0.0329900000 408214745 0 402718720 -0.0188793782 -0.0276578795 -0.0389199406 1583 1311867771.4361710548 0.0036339404 0.0262712834 0.0670038015 0.0048099187 0.0332580000 408218013 0 402718720 -0.0188796669 -0.0296209045 -0.0377587639 1584 1311867771.4682569504 0.0042811199 0.0262574007 0.0670038015 0.0048086022 0.0333660000 408221225 0 402718720 -0.0168710351 -0.0289994311 -0.0376789533 1585 1311867771.5008640289 0.0046300334 0.0262437557 0.0670038015 0.0048090650 0.0332710000 408224325 0 402718720 -0.0185311846 -0.0270289965 -0.0369730666 1586 1311867771.5365910530 0.0029745221 0.0262290840 0.0670038015 0.0048076468 0.0448860000 408227713 0 402718720 -0.0171477068 -0.0280609410 -0.0357554741 1587 1311867771.5686171055 0.0040867901 0.0262151317 0.0670038015 0.0048062151 0.0439180000 408230853 0 402718720 -0.0209236238 -0.0292105712 -0.0362894274 1588 1311867771.6077210903 0.0029268679 0.0262004666 0.0670038015 0.0048057853 0.0435700000 408234185 0 402718720 -0.0183316208 -0.0294666924 -0.0363168865 1589 1311867771.6366779804 0.0044312952 0.0261867667 0.0670038015 0.0048046199 0.0337900000 408237093 0 402718720 -0.0203322917 -0.0287416149 -0.0365327187 1590 1311867771.6715440750 0.0041937320 0.0261729346 0.0670038015 0.0048036695 0.0342710000 408240641 0 402718720 -0.0204155929 -0.0302104987 -0.0351552293 1591 1311867771.7024850845 0.0025158857 0.0261580653 0.0670038015 0.0048028266 0.0334260000 408243469 0 402718720 -0.0181727484 -0.0267938096 -0.0343693011 1592 1311867771.7367300987 0.0024805043 0.0261431924 0.0670038015 0.0048022095 0.0334450000 408246937 0 402718720 -0.0172307622 -0.0266036987 -0.0344589688 1593 1311867771.7697410583 0.0020883817 0.0261280921 0.0670038015 0.0048018587 0.0329060000 408250093 0 402718720 -0.0156749301 -0.0266479179 -0.0341350175 1594 1311867771.8023030758 0.0025401129 0.0261132941 0.0670038015 0.0048009968 0.0433910000 408253177 0 402718720 -0.0156996530 -0.0274377801 -0.0344877988 1595 1311867771.8386220932 0.0025976067 0.0260985507 0.0670038015 0.0048005497 0.0420010000 408256253 0 402718720 -0.0143687008 -0.0257884078 -0.0338221006 1596 1311867771.8711829185 0.0027736577 0.0260839362 0.0670038015 0.0047992212 0.0417250000 408259793 0 402718720 -0.0156092076 -0.0277588852 -0.0337763764 1597 1311867771.9016489983 0.0026247806 0.0260692466 0.0670038015 0.0047981030 0.0331430000 408262685 0 402718720 -0.0146806538 -0.0276753027 -0.0337535739 1598 1311867771.9377520084 0.0035584695 0.0260551598 0.0670038015 0.0047995681 0.0330160000 408266329 0 402718720 -0.0169040412 -0.0257166736 -0.0335111097 1599 1311867771.9696009159 0.0019970068 0.0260401140 0.0670038015 0.0047991046 0.0329630000 408269429 0 402718720 -0.0146641722 -0.0266085751 -0.0330954120 1600 1311867772.0018649101 0.0033859021 0.0260259552 0.0670038015 0.0047996171 0.0329910000 408272585 0 402718720 -0.0110943466 -0.0274528302 -0.0337613113 1601 1311867772.0375399590 0.0028254001 0.0260114639 0.0670038015 0.0048002012 0.0331310000 408275629 0 402718720 -0.0117064957 -0.0255610105 -0.0340921506 1602 1311867772.0696671009 0.0019526733 0.0259964459 0.0670038015 0.0047988383 0.0334520000 408278977 0 402718720 -0.0118679022 -0.0259848684 -0.0329680070 1603 1311867772.1012299061 0.0033360831 0.0259823097 0.0670038015 0.0047981418 0.0426440000 408281829 0 402718720 -0.0104022808 -0.0254953653 -0.0335421152 1604 1311867772.1369819641 0.0031300357 0.0259680626 0.0670038015 0.0047966559 0.0327680000 408285169 0 402718720 -0.0115360301 -0.0258545689 -0.0335461013 1605 1311867772.1690549850 0.0018282830 0.0259530223 0.0670038015 0.0047958412 0.0431610000 408288389 0 402718720 -0.0121726198 -0.0257311575 -0.0318644531 1606 1311867772.2016880512 0.0034850175 0.0259390322 0.0670038015 0.0047946407 0.0327870000 408291785 0 402718720 -0.0126236035 -0.0270100050 -0.0325298421 1607 1311867772.2370250225 0.0019112609 0.0259240803 0.0670038015 0.0047935277 0.0329100000 408294853 0 402718720 -0.0119394725 -0.0258333161 -0.0310227647 1608 1311867772.2710011005 0.0028509533 0.0259097313 0.0670038015 0.0047923035 0.0332960000 408298385 0 402718720 -0.0112087736 -0.0257764384 -0.0318886265 1609 1311867772.3046050072 0.0031087704 0.0258955604 0.0670038015 0.0047908541 0.0328730000 408301269 0 402718720 -0.0124081755 -0.0257897414 -0.0323237479 1610 1311867772.3366808891 0.0013828960 0.0258803352 0.0670038015 0.0047896058 0.0330410000 408304297 0 402718720 -0.0129988156 -0.0247078352 -0.0308662672 1611 1311867772.3689630032 0.0028958239 0.0258660679 0.0670038015 0.0047885740 0.0423400000 408307693 0 402718720 -0.0114877289 -0.0252473075 -0.0319378823 1612 1311867772.4054839611 0.0032318318 0.0258520269 0.0670038015 0.0047874329 0.0419360000 408310881 0 402718720 -0.0112614231 -0.0247259773 -0.0322952643 1613 1311867772.4385271072 0.0032924102 0.0258380407 0.0670038015 0.0047859817 0.0327850000 408313965 0 402718720 -0.0115071526 -0.0259320661 -0.0314020328 1614 1311867772.4697830677 0.0038073245 0.0258243910 0.0670038015 0.0047848901 0.0327740000 408317265 0 402718720 -0.0114057185 -0.0260375533 -0.0318653360 1615 1311867772.5049729347 0.0027381110 0.0258100961 0.0670038015 0.0047844772 0.0324320000 408320205 0 402718720 -0.0122472616 -0.0250157714 -0.0313914455 1616 1311867772.5382430553 0.0033476406 0.0257961960 0.0670038015 0.0047830477 0.0329520000 408323497 0 402718720 -0.0117283473 -0.0235262532 -0.0318947881 1617 1311867772.5713028908 0.0038801876 0.0257826425 0.0670038015 0.0047817185 0.0328850000 408326765 0 402718720 -0.0132882390 -0.0263620466 -0.0315941758 1618 1311867772.6077790260 0.0032520657 0.0257687176 0.0670038015 0.0047822069 0.0330620000 408330161 0 402718720 -0.0145004708 -0.0255960692 -0.0309845842 1619 1311867772.6382429600 0.0017423390 0.0257538773 0.0670038015 0.0047815502 0.0324890000 408333157 0 402718720 -0.0153397974 -0.0243333839 -0.0291858502 1620 1311867772.6695280075 0.0019036428 0.0257391549 0.0670038015 0.0047807128 0.0420230000 408336241 0 402718720 -0.0169681963 -0.0238534212 -0.0293391310 1621 1311867772.7066609859 0.0041509797 0.0257258371 0.0670038015 0.0047807564 0.0419550000 408339549 0 402718720 -0.0164401066 -0.0262869578 -0.0296410862 1622 1311867772.7385280132 0.0021542816 0.0257113047 0.0670038015 0.0047799208 0.0437160000 408342969 0 402718720 -0.0147757204 -0.0231970027 -0.0298653133 1623 1311867772.7712020874 0.0025844146 0.0256970553 0.0670038015 0.0047785624 0.0325630000 408345917 0 402718720 -0.0173476413 -0.0242323279 -0.0287979003 1624 1311867772.8056819439 0.0046778768 0.0256841124 0.0670038015 0.0047774799 0.0323180000 408349193 0 402718720 -0.0179730095 -0.0261637904 -0.0280312840 1625 1311867772.8384070396 0.0035808808 0.0256705104 0.0670038015 0.0047760367 0.0320300000 408352157 0 402718720 -0.0159162544 -0.0250283554 -0.0277648773 1626 1311867772.8747529984 0.0052070939 0.0256579253 0.0670038015 0.0047748374 0.0328590000 408355873 0 402718720 -0.0160047673 -0.0265231226 -0.0279400107 1627 1311867772.9054989815 0.0047058617 0.0256450476 0.0670038015 0.0047742523 0.0326090000 408358741 0 402718720 -0.0168268085 -0.0259861387 -0.0276909657 1628 1311867772.9415910244 0.0044707726 0.0256320413 0.0670038015 0.0047741353 0.0441450000 408362025 0 402718720 -0.0141969416 -0.0248896945 -0.0279187709 1629 1311867772.9716000557 0.0017229456 0.0256173641 0.0670038015 0.0047744820 0.0322450000 408365101 0 402718720 -0.0165390689 -0.0223505329 -0.0272935238 1630 1311867773.0115981102 0.0052315774 0.0256048575 0.0670038015 0.0047740877 0.0326210000 408368417 0 402718720 -0.0167250801 -0.0257539265 -0.0272459425 1631 1311867773.0406711102 0.0049674567 0.0255922043 0.0670038015 0.0047729066 0.0319780000 408371733 0 402718720 -0.0146328826 -0.0252902694 -0.0268718507 1632 1311867773.0706710815 0.0046836762 0.0255793927 0.0670038015 0.0047715191 0.0320920000 408374593 0 402718720 -0.0121177053 -0.0234151538 -0.0274636224 1633 1311867773.1044468880 0.0034448041 0.0255658381 0.0670038015 0.0047706264 0.0444320000 408377733 0 402718720 -0.0150651364 -0.0236668773 -0.0254407488 1634 1311867773.1367809772 0.0063113519 0.0255540545 0.0670038015 0.0047700548 0.0319010000 408381057 0 402718720 -0.0163904615 -0.0264817271 -0.0256133303 1635 1311867773.1702499390 0.0054164934 0.0255417379 0.0670038015 0.0047690571 0.0320540000 408384277 0 402718720 -0.0118068745 -0.0243530888 -0.0272262767 1636 1311867773.2047750950 0.0033463710 0.0255281711 0.0670038015 0.0047696730 0.0318130000 408387353 0 402718720 -0.0142307505 -0.0232315175 -0.0245856233 1637 1311867773.2366468906 0.0056098448 0.0255160035 0.0670038015 0.0047688352 0.0434670000 408390757 0 402718720 -0.0109253665 -0.0240102392 -0.0244103260 1638 1311867773.2714850903 0.0049789906 0.0255034656 0.0670038015 0.0047681420 0.0422750000 408393761 0 402718720 -0.0114431661 -0.0229493733 -0.0245951042 1639 1311867773.3104391098 0.0049195788 0.0254909068 0.0670038015 0.0047672058 0.0419920000 408397173 0 402718720 -0.0114712389 -0.0230280273 -0.0240705349 1640 1311867773.3365778923 0.0069768261 0.0254796177 0.0670038015 0.0047660866 0.0321270000 408400161 0 402718720 -0.0095485412 -0.0239304751 -0.0223189294 1641 1311867773.3720550537 0.0050164117 0.0254671478 0.0670038015 0.0047647894 0.0315900000 408403501 0 402718720 -0.0119034452 -0.0231787451 -0.0231259596 1642 1311867773.4075679779 0.0080875019 0.0254565633 0.0670038015 0.0047641032 0.0321460000 408406593 0 402718720 -0.0119951703 -0.0262752771 -0.0229626596 1643 1311867773.4431231022 0.0045854910 0.0254438603 0.0670038015 0.0047675641 0.0318530000 408409853 0 402718720 -0.0115220034 -0.0219618175 -0.0220524576 1644 1311867773.4752271175 0.0059999041 0.0254320331 0.0670038015 0.0047664269 0.0315380000 408412889 0 402718720 -0.0129665565 -0.0236398838 -0.0204756502 1645 1311867773.5056390762 0.0078396341 0.0254213386 0.0670038015 0.0047657125 0.0318150000 408416173 0 402718720 -0.0139155313 -0.0255726315 -0.0217554383 1646 1311867773.5412580967 0.0067089470 0.0254099702 0.0670038015 0.0047660132 0.0318910000 408419369 0 402718720 -0.0127091445 -0.0236289538 -0.0198554564 1647 1311867773.5752460957 0.0064737527 0.0253984728 0.0670038015 0.0047649819 0.0394530000 408422797 0 402718720 -0.0132849859 -0.0234184321 -0.0195473470 1648 1311867773.6103789806 0.0062769619 0.0253868700 0.0670038015 0.0047635717 0.0316740000 408426025 0 402718720 -0.0130038941 -0.0231033694 -0.0196198132 1649 1311867773.6384060383 0.0067886100 0.0253755915 0.0670038015 0.0047629001 0.0316390000 408428893 0 402718720 -0.0139986360 -0.0228364132 -0.0188238677 1650 1311867773.6767098904 0.0069610490 0.0253644311 0.0670038015 0.0047638794 0.0311560000 408432337 0 402718720 -0.0103014326 -0.0217786748 -0.0173670799 1651 1311867773.7092239857 0.0083228815 0.0253541092 0.0670038015 0.0047640487 0.0313180000 408435373 0 402718720 -0.0102685755 -0.0237752013 -0.0180890001 1652 1311867773.7367770672 0.0078327945 0.0253435030 0.0670038015 0.0047645702 0.0311560000 408438241 0 402718720 -0.0126495007 -0.0232382528 -0.0173342079 1653 1311867773.7767388821 0.0083711157 0.0253332354 0.0670038015 0.0047636997 0.0395100000 409324905 0 402718720 -0.0117581412 -0.0234611481 -0.0182349384 1654 1311867773.8052179813 0.0077745342 0.0253226195 0.0670038015 0.0047630670 0.1241400000 409329193 0 402718720 -0.0108064488 -0.0225865655 -0.0173439458 1655 1311867773.8394160271 0.0079545025 0.0253121252 0.0670038015 0.0047623616 0.1084250000 409658425 0 402718720 -0.0124476291 -0.0229105148 -0.0164085720 1656 1311867773.8739800453 0.0087933056 0.0253021501 0.0670038015 0.0047613781 0.0822080000 419081533 0 402718720 -0.0129604759 -0.0241039973 -0.0160560906 1657 1311867773.9096889496 0.0069923042 0.0252911001 0.0670038015 0.0047604236 0.0839850000 419013125 0 402718720 -0.0123284226 -0.0226159245 -0.0168966278 1658 1311867773.9369859695 0.0112091862 0.0252826067 0.0670038015 0.0047611179 0.1203700000 417585237 0 402718720 -0.0125174280 -0.0271323025 -0.0165940039 1659 1311867773.9740200043 0.0097814081 0.0252732630 0.0670038015 0.0047597935 0.0497600000 409312717 0 402718720 -0.0114621390 -0.0259785950 -0.0172465593 1660 1311867774.0073120594 0.0098287193 0.0252639591 0.0670038015 0.0047592630 0.0358710000 409316041 0 402718720 -0.0139597962 -0.0260722898 -0.0168528929 1661 1311867774.0389740467 0.0078187976 0.0252534563 0.0670038015 0.0047609887 0.0468400000 409319053 0 402718720 -0.0128020309 -0.0239212140 -0.0161803104 1662 1311867774.0735630989 0.0102233645 0.0252444129 0.0670038015 0.0047616689 0.0355520000 409322337 0 402718720 -0.0126477471 -0.0264368393 -0.0158606283 1663 1311867774.1093399525 0.0117647862 0.0252363073 0.0670038015 0.0047633736 0.0531420000 409325677 0 402718720 -0.0119529199 -0.0281292610 -0.0160143189 1664 1311867774.1424911022 0.0098243924 0.0252270453 0.0670038015 0.0047628713 0.0354850000 409328817 0 402718720 -0.0115921134 -0.0259595904 -0.0149518056 1665 1311867774.1754300594 0.0126187168 0.0252194728 0.0670038015 0.0047627501 0.0355500000 409331901 0 402718720 -0.0119290771 -0.0285519678 -0.0139773050 1666 1311867774.2059481144 0.0127233667 0.0252119721 0.0670038015 0.0047617393 0.0366320000 409335049 0 402718720 -0.0117653282 -0.0287111737 -0.0154304076 1667 1311867774.2384989262 0.0112406937 0.0252035910 0.0670038015 0.0047606037 0.0350170000 409338125 0 402718720 -0.0114349276 -0.0269733574 -0.0147659238 1668 1311867774.2744109631 0.0099521251 0.0251944475 0.0670038015 0.0047595405 0.0349560000 409341569 0 402718720 -0.0113805691 -0.0253611840 -0.0135672968 1669 1311867774.3046739101 0.0126818186 0.0251869504 0.0670038015 0.0047587635 0.0527010000 409344613 0 402718720 -0.0131338732 -0.0279255286 -0.0134148896 1670 1311867774.3375370502 0.0118207345 0.0251789466 0.0670038015 0.0047574299 0.0344680000 409347969 0 402718720 -0.0129834786 -0.0270159021 -0.0144865708 1671 1311867774.3727159500 0.0125590507 0.0251713943 0.0670038015 0.0047563485 0.0352310000 409351397 0 402718720 -0.0118847201 -0.0271298066 -0.0123228431 1672 1311867774.4051818848 0.0130923511 0.0251641700 0.0670038015 0.0047554113 0.0354140000 409354553 0 402718720 -0.0123952022 -0.0276205782 -0.0129280034 1673 1311867774.4376831055 0.0143592199 0.0251577116 0.0670038015 0.0047542320 0.0353470000 409357333 0 402718720 -0.0124332346 -0.0283696558 -0.0121456496 1674 1311867774.4740140438 0.0128188720 0.0251503407 0.0670038015 0.0047535082 0.0339550000 409360737 0 402718720 -0.0131694460 -0.0263250098 -0.0106032938 1675 1311867774.5066258907 0.0125094792 0.0251427940 0.0670038015 0.0047522004 0.0480810000 409363877 0 402718720 -0.0136379795 -0.0261420347 -0.0107855480 1676 1311867774.5394051075 0.0126139661 0.0251353185 0.0670038015 0.0047510547 0.0441410000 409367121 0 402718720 -0.0130960485 -0.0264809337 -0.0120324884 1677 1311867774.5727870464 0.0127351498 0.0251279243 0.0670038015 0.0047499647 0.0429770000 409370205 0 402718720 -0.0134779690 -0.0262333676 -0.0112409340 1678 1311867774.6076970100 0.0127127981 0.0251205255 0.0670038015 0.0047487680 0.0345790000 409373465 0 402718720 -0.0117040304 -0.0259356573 -0.0109734843 1679 1311867774.6373310089 0.0145641295 0.0251142382 0.0670038015 0.0047478232 0.0346830000 409376557 0 402718720 -0.0121350260 -0.0275353752 -0.0102442354 1680 1311867774.6731650829 0.0141874524 0.0251077341 0.0670038015 0.0047465160 0.0344710000 409379649 0 402718720 -0.0120675135 -0.0271808337 -0.0097735599 1681 1311867774.7048470974 0.0138847511 0.0251010578 0.0670038015 0.0047451897 0.0462240000 409383253 0 402718720 -0.0127196871 -0.0260053240 -0.0090127662 1682 1311867774.7448370457 0.0143576320 0.0250946705 0.0670038015 0.0047463658 0.0333960000 409386561 0 402718720 -0.0122536672 -0.0255648550 -0.0077744047 1683 1311867774.7731618881 0.0152783124 0.0250888378 0.0670038015 0.0047450940 0.0341780000 409389669 0 402718720 -0.0148137212 -0.0264755767 -0.0087535083 1684 1311867774.8052101135 0.0124228578 0.0250813165 0.0670038015 0.0047451449 0.0347180000 409392441 0 402718720 -0.0132916942 -0.0236527845 -0.0087853493 1685 1311867774.8443410397 0.0141042918 0.0250748019 0.0670038015 0.0047440310 0.0443190000 409395885 0 402718720 -0.0116030490 -0.0248086788 -0.0076956642 1686 1311867774.8735189438 0.0143332314 0.0250684309 0.0670038015 0.0047431786 0.0333420000 409399169 0 402718720 -0.0113228476 -0.0249304641 -0.0077209347 1687 1311867774.9063620567 0.0146223530 0.0250622388 0.0670038015 0.0047420867 0.0336700000 409402445 0 402718720 -0.0133793103 -0.0245226175 -0.0060528433 1688 1311867774.9433379173 0.0116819264 0.0250543120 0.0670038015 0.0047407141 0.0324960000 409405521 0 402718720 -0.0119671207 -0.0218873862 -0.0076108850 1689 1311867774.9730870724 0.0139496187 0.0250477373 0.0670038015 0.0047396716 0.0330840000 409408621 0 402718720 -0.0102467760 -0.0238305368 -0.0070192595 1690 1311867775.0104990005 0.0131233009 0.0250406814 0.0670038015 0.0047400351 0.0340060000 409411993 0 402718720 -0.0134870559 -0.0220284350 -0.0056522735 1691 1311867775.0417571068 0.0124777760 0.0250332522 0.0670038015 0.0047387173 0.0449060000 409414957 0 402718720 -0.0134060793 -0.0214778967 -0.0060261674 1692 1311867775.0737869740 0.0148473755 0.0250272321 0.0670038015 0.0047380247 0.0427050000 409418105 0 402718720 -0.0133879445 -0.0240815505 -0.0065661087 1693 1311867775.1060369015 0.0157495141 0.0250217521 0.0670038015 0.0047370627 0.0441770000 409421397 0 402718720 -0.0130616920 -0.0248551872 -0.0060737026 1694 1311867775.1426749229 0.0119909970 0.0250140598 0.0670038015 0.0047359165 0.0329520000 409424785 0 402718720 -0.0115728574 -0.0212909058 -0.0069682649 1695 1311867775.1733469963 0.0125238188 0.0250066909 0.0670038015 0.0047346162 0.0328930000 409427877 0 402718720 -0.0121574309 -0.0214643925 -0.0061251102 1696 1311867775.2047309875 0.0129589429 0.0249995873 0.0670038015 0.0047335303 0.0331780000 409431177 0 402718720 -0.0113860900 -0.0222735908 -0.0069864020 1697 1311867775.2407341003 0.0142688323 0.0249932639 0.0670038015 0.0047326762 0.0324550000 409434245 0 402718720 -0.0119084250 -0.0233991928 -0.0069134654 1698 1311867775.2726259232 0.0154508641 0.0249876442 0.0670038015 0.0047315077 0.0326630000 409437305 0 402718720 -0.0133009907 -0.0237190239 -0.0050369278 1699 1311867775.3058989048 0.0144783203 0.0249814586 0.0670038015 0.0047309742 0.0415740000 409440701 0 402718720 -0.0108964331 -0.0226986036 -0.0048767859 1700 1311867775.3405869007 0.0153669501 0.0249758030 0.0670038015 0.0047310976 0.0320840000 409443833 0 402718720 -0.0111692781 -0.0236880239 -0.0055022207 1701 1311867775.3728890419 0.0159185547 0.0249704783 0.0670038015 0.0047301809 0.0321730000 409446973 0 402718720 -0.0120669995 -0.0238074530 -0.0050159497 1702 1311867775.4055740833 0.0133202421 0.0249636333 0.0670038015 0.0047308531 0.0326030000 409450121 0 402718720 -0.0132523961 -0.0204385649 -0.0039773574 1703 1311867775.4408710003 0.0131899100 0.0249567198 0.0670038015 0.0047319652 0.0410010000 410320929 0 402718720 -0.0105962828 -0.0208187401 -0.0051948205 1704 1311867775.4725620747 0.0135934874 0.0249500512 0.0670038015 0.0047313282 0.1210750000 410276497 0 402718720 -0.0116510242 -0.0213041231 -0.0056120795 1705 1311867775.5057229996 0.0137041304 0.0249434553 0.0670038015 0.0047304587 0.1048300000 410281857 0 402718720 -0.0114054931 -0.0205119085 -0.0036311150 1706 1311867775.5413000584 0.0138377454 0.0249369455 0.0670038015 0.0047299421 0.1002550000 410615329 0 402718720 -0.0105018551 -0.0207115225 -0.0038997140 1707 1311867775.5736858845 0.0148160458 0.0249310165 0.0670038015 0.0047286876 0.1004500000 418205317 0 402718720 -0.0104351509 -0.0215260908 -0.0037690140 1708 1311867775.6086819172 0.0146493958 0.0249249968 0.0670038015 0.0047275165 0.0790630000 419219757 0 402718720 -0.0116312206 -0.0210164748 -0.0034707417 1709 1311867775.6414420605 0.0145096369 0.0249189024 0.0670038015 0.0047264498 0.0455610000 420472493 0 402718720 -0.0089187017 -0.0208272804 -0.0038851090 1710 1311867775.6726739407 0.0152791599 0.0249132651 0.0670038015 0.0047263062 0.1107480000 418746161 0 402718720 -0.0114935981 -0.0212454610 -0.0035110707 1711 1311867775.7051100731 0.0136406813 0.0249066768 0.0670038015 0.0047252018 0.0383380000 410261009 0 402718720 -0.0120626707 -0.0190791897 -0.0033827131 1712 1311867775.7416241169 0.0140055055 0.0249003093 0.0670038015 0.0047241773 0.0366720000 410264333 0 402718720 -0.0111718560 -0.0185907632 -0.0017628586 1713 1311867775.7742578983 0.0146999443 0.0248943546 0.0670038015 0.0047244301 0.0350440000 410267417 0 402718720 -0.0123947719 -0.0191189069 -0.0019864258 1714 1311867775.8062939644 0.0158026591 0.0248890503 0.0670038015 0.0047233754 0.0351300000 410270709 0 402718720 -0.0112657296 -0.0201184954 -0.0021274309 1715 1311867775.8408269882 0.0139636025 0.0248826797 0.0670038015 0.0047224589 0.0351570000 410273729 0 402718720 -0.0125658736 -0.0175396111 -0.0021247808 1716 1311867775.8729701042 0.0151440762 0.0248770046 0.0670038015 0.0047215424 0.0352880000 410277093 0 402718720 -0.0117996344 -0.0184799004 -0.0015705996 1717 1311867775.9066479206 0.0147545524 0.0248711091 0.0670038015 0.0047202165 0.0448180000 410280225 0 402718720 -0.0114675937 -0.0177431218 -0.0011465074 1718 1311867775.9435749054 0.0150034018 0.0248653654 0.0670038015 0.0047193190 0.0352120000 410283365 0 402718720 -0.0125830946 -0.0174719337 -0.0008486258 1719 1311867775.9730579853 0.0145238712 0.0248593494 0.0670038015 0.0047187949 0.0350530000 410286585 0 402718720 -0.0102072200 -0.0169009548 -0.0007876800 1720 1311867776.0135231018 0.0128281545 0.0248523545 0.0670038015 0.0047174892 0.0345800000 410289829 0 402718720 -0.0096771391 -0.0147783356 -0.0006560823 1721 1311867776.0423479080 0.0133075723 0.0248456463 0.0670038015 0.0047167530 0.0346930000 410293001 0 402718720 -0.0105526401 -0.0151344147 -0.0004549874 1722 1311867776.0782909393 0.0150489118 0.0248399572 0.0670038015 0.0047159877 0.0342710000 410296189 0 402718720 -0.0093007833 -0.0170550756 -0.0005975091 1723 1311867776.1090068817 0.0138876047 0.0248336006 0.0670038015 0.0047151869 0.0360160000 410299545 0 402718720 -0.0110596977 -0.0158251263 -0.0014551068 1724 1311867776.1410119534 0.0149071934 0.0248278429 0.0670038015 0.0047140927 0.0348200000 410302501 0 402718720 -0.0132809281 -0.0160016939 -0.0004522945 1725 1311867776.1773319244 0.0147641944 0.0248220089 0.0670038015 0.0047127931 0.0482430000 410305809 0 402718720 -0.0126982825 -0.0155183580 0.0001704739 1726 1311867776.2094259262 0.0147145381 0.0248161528 0.0670038015 0.0047117674 0.0335620000 410309037 0 402718720 -0.0110417586 -0.0158390533 -0.0004182411 1727 1311867776.2407069206 0.0151412869 0.0248105507 0.0670038015 0.0047105791 0.0347690000 410312121 0 402718720 -0.0118744392 -0.0158831533 0.0000419714 1728 1311867776.2753469944 0.0146120265 0.0248046488 0.0670038015 0.0047093014 0.0346790000 410315445 0 402718720 -0.0115111331 -0.0154107697 -0.0003356007 1729 1311867776.3120670319 0.0143285822 0.0247985898 0.0670038015 0.0047079435 0.0334150000 410318585 0 402718720 -0.0104709258 -0.0147927161 0.0000348012 1730 1311867776.3407590389 0.0136516895 0.0247921465 0.0670038015 0.0047066614 0.0346910000 410321621 0 402718720 -0.0097257737 -0.0143789453 -0.0007147016 1731 1311867776.3730750084 0.0127281770 0.0247851771 0.0670038015 0.0047054847 0.0466600000 410325105 0 402718720 -0.0093940590 -0.0132215787 -0.0006163344 1732 1311867776.4097070694 0.0145459166 0.0247792653 0.0670038015 0.0047042543 0.0340870000 410328309 0 402718720 -0.0086011654 -0.0144350007 0.0007813782 1733 1311867776.4422268867 0.0151291573 0.0247736969 0.0670038015 0.0047030861 0.0340570000 410331281 0 402718720 -0.0092024459 -0.0152464258 0.0001871926 1734 1311867776.4727520943 0.0139037566 0.0247674281 0.0670038015 0.0047017843 0.0341240000 410334437 0 402718720 -0.0065928362 -0.0138787450 -0.0003843973 1735 1311867776.5105879307 0.0135805616 0.0247609804 0.0670038015 0.0047018571 0.0338320000 410337929 0 402718720 -0.0100761522 -0.0131101273 0.0005450239 1736 1311867776.5415630341 0.0144925825 0.0247550654 0.0670038015 0.0047007236 0.0336240000 410340893 0 402718720 -0.0104080793 -0.0139769698 0.0009586178 1737 1311867776.5743160248 0.0140661541 0.0247489117 0.0670038015 0.0046994760 0.0325730000 410343841 0 402718720 -0.0104540717 -0.0133404331 0.0012073112 1738 1311867776.6094930172 0.0141151994 0.0247427934 0.0670038015 0.0046982913 0.0335950000 410347773 0 402718720 -0.0096193254 -0.0138891432 0.0004106513 1739 1311867776.6413109303 0.0150902793 0.0247372428 0.0670038015 0.0046970519 0.0330450000 410350233 0 402718720 -0.0098536983 -0.0144914947 0.0013392796 1740 1311867776.6763460636 0.0149554955 0.0247316211 0.0670038015 0.0046957374 0.0423350000 410354125 0 402718720 -0.0085314587 -0.0138804894 0.0020569584 1741 1311867776.7134280205 0.0159971025 0.0247266041 0.0670038015 0.0046948625 0.0421840000 410357321 0 402718720 -0.0081090312 -0.0149669908 0.0018108645 1742 1311867776.7423970699 0.0162623990 0.0247217452 0.0670038015 0.0046940261 0.0445330000 410360069 0 402718720 -0.0093520014 -0.0147485482 0.0027338625 1743 1311867776.7739920616 0.0152498642 0.0247163110 0.0670038015 0.0046928483 0.0334860000 410363553 0 402718720 -0.0097828014 -0.0134642469 0.0023734258 1744 1311867776.8117430210 0.0144620845 0.0247104313 0.0670038015 0.0046919580 0.0319640000 410366669 0 402718720 -0.0079944627 -0.0123110944 0.0025580858 1745 1311867776.8449618816 0.0142598199 0.0247044424 0.0670038015 0.0046908573 0.0319120000 410370137 0 402718720 -0.0085236682 -0.0120946942 0.0021362328 1746 1311867776.8748989105 0.0125835342 0.0246975003 0.0670038015 0.0046908859 0.0329590000 410373149 0 402718720 -0.0116990861 -0.0095443074 0.0023337761 1747 1311867776.9104089737 0.0142385336 0.0246915135 0.0670038015 0.0046901373 0.0406590000 411222885 0 402718720 -0.0072764973 -0.0106560010 0.0043725143 1748 1311867776.9465129375 0.0130438153 0.0246848500 0.0670038015 0.0046891141 0.1139790000 411177589 0 402718720 -0.0067308391 -0.0098145837 0.0033212514 1749 1311867776.9780058861 0.0142920464 0.0246789079 0.0670038015 0.0046884031 0.1012980000 411181249 0 402718720 -0.0077893436 -0.0102733858 0.0052951439 1750 1311867777.0103049278 0.0131310308 0.0246723091 0.0670038015 0.0046873609 0.0983780000 417374637 0 402718720 -0.0086848354 -0.0088536032 0.0055183694 1751 1311867777.0430829525 0.0126234880 0.0246654280 0.0670038015 0.0046866657 0.0598450000 421339341 0 402718720 -0.0109263184 -0.0084016407 0.0050355722 1752 1311867777.0763421059 0.0114710471 0.0246578969 0.0670038015 0.0046858425 0.0706150000 421140381 0 402718720 -0.0085985614 -0.0073864846 0.0052214740 1753 1311867777.1087210178 0.0134014292 0.0246514757 0.0670038015 0.0046850508 0.0980070000 413878557 0 402718720 -0.0075237560 -0.0086520240 0.0071721245 1754 1311867777.1435770988 0.0144181130 0.0246456414 0.0670038015 0.0046839679 0.0358420000 411196073 0 402718720 -0.0084192036 -0.0093439780 0.0081742071 1755 1311867777.1783010960 0.0163790099 0.0246409310 0.0670038015 0.0046826777 0.0364500000 411199797 0 402718720 -0.0094411541 -0.0107282503 0.0094114207 1756 1311867777.2115299702 0.0147194080 0.0246352810 0.0670038015 0.0046814517 0.0363530000 411202601 0 402718720 -0.0076375934 -0.0098470133 0.0082162851 1757 1311867777.2420690060 0.0140036736 0.0246292300 0.0670038015 0.0046802632 0.0488130000 411205397 0 402718720 -0.0074462392 -0.0091731250 0.0079414034 1758 1311867777.2766950130 0.0138686094 0.0246231090 0.0670038015 0.0046794198 0.0346220000 411208977 0 402718720 -0.0067061139 -0.0088937366 0.0081473347 1759 1311867777.3093490601 0.0146636823 0.0246174471 0.0670038015 0.0046787190 0.0354010000 411212629 0 402718720 -0.0066698398 -0.0096184816 0.0085140895 1760 1311867777.3419890404 0.0126818689 0.0246106655 0.0670038015 0.0046775470 0.0345500000 411215641 0 402718720 -0.0075798063 -0.0080013508 0.0076727299 1761 1311867777.3780329227 0.0142671615 0.0246047918 0.0670038015 0.0046766197 0.0348090000 411218949 0 402718720 -0.0064500738 -0.0090657389 0.0089828474 1762 1311867777.4108960629 0.0132843629 0.0245983671 0.0670038015 0.0046755382 0.0343720000 411222601 0 402718720 -0.0086011058 -0.0081108091 0.0090537528 1763 1311867777.4411139488 0.0129086450 0.0245917365 0.0670038015 0.0046743450 0.0438520000 411226181 0 402718720 -0.0084193060 -0.0081731938 0.0085881781 1764 1311867777.4770240784 0.0139921838 0.0245857277 0.0670038015 0.0046730749 0.0344060000 411228609 0 402718720 -0.0073065693 -0.0085167587 0.0102079483 1765 1311867777.5098700523 0.0140919778 0.0245797822 0.0670038015 0.0046721762 0.0340870000 411231829 0 402718720 -0.0052013602 -0.0086430758 0.0096578188 1766 1311867777.5421240330 0.0133794788 0.0245734400 0.0670038015 0.0046708593 0.0343240000 411235537 0 402718720 -0.0068148882 -0.0086441385 0.0090347640 1767 1311867777.5777161121 0.0143053774 0.0245676290 0.0670038015 0.0046697131 0.0339560000 411238077 0 402718720 -0.0053293812 -0.0082394630 0.0110735539 1768 1311867777.6086440086 0.0154778222 0.0245624877 0.0670038015 0.0046685500 0.0339050000 411241481 0 402718720 -0.0068807476 -0.0098267701 0.0115016559 1769 1311867777.6407959461 0.0134577090 0.0245562103 0.0670038015 0.0046674946 0.0339680000 411245093 0 402718720 -0.0081502274 -0.0083311833 0.0106849037 1770 1311867777.6765840054 0.0137176868 0.0245500868 0.0670038015 0.0046662790 0.0334870000 411247897 0 402718720 -0.0070329718 -0.0078838989 0.0117793288 1771 1311867777.7086570263 0.0153069561 0.0245448676 0.0670038015 0.0046651335 0.0331120000 411250677 0 402718720 -0.0100108143 -0.0098492699 0.0123693142 1772 1311867777.7411170006 0.0120331561 0.0245378069 0.0670038015 0.0046638445 0.0340770000 411255049 0 402718720 -0.0080772918 -0.0065851808 0.0112114586 1773 1311867777.7797420025 0.0134663042 0.0245315624 0.0670038015 0.0046626917 0.0438560000 411257821 0 402718720 -0.0092699891 -0.0082551688 0.0114902984 1774 1311867777.8103909492 0.0138373608 0.0245255341 0.0670038015 0.0046614490 0.0444700000 411261889 0 402718720 -0.0100017032 -0.0078347884 0.0131707583 1775 1311867777.8421120644 0.0138262734 0.0245195063 0.0670038015 0.0046602042 0.0332020000 411264525 0 402718720 -0.0107327839 -0.0078348042 0.0128326677 1776 1311867777.8771729469 0.0134046571 0.0245132479 0.0670038015 0.0046589052 0.0339250000 411267649 0 402718720 -0.0116366213 -0.0073967082 0.0125145689 1777 1311867777.9091188908 0.0129694790 0.0245067517 0.0670038015 0.0046579975 0.0327610000 411270869 0 402718720 -0.0097771604 -0.0073420429 0.0114207584 1778 1311867777.9424149990 0.0125722336 0.0245000394 0.0670038015 0.0046568076 0.0331490000 411274473 0 402718720 -0.0092374478 -0.0067128139 0.0110399062 1779 1311867777.9770610332 0.0161445141 0.0244953426 0.0670038015 0.0046556822 0.0330300000 411277349 0 402718720 -0.0124060940 -0.0093231145 0.0139193311 1780 1311867778.0100560188 0.0147688035 0.0244898783 0.0670038015 0.0046566093 0.0325380000 411280809 0 402718720 -0.0115644345 -0.0077083944 0.0141642205 1781 1311867778.0413420200 0.0101226168 0.0244818113 0.0670038015 0.0046571207 0.0335330000 411284101 0 402718720 -0.0140351411 -0.0036620619 0.0120237991 1782 1311867778.0773630142 0.0145015530 0.0244762107 0.0670038015 0.0046573376 0.0430420000 411287737 0 402718720 -0.0132004991 -0.0074636932 0.0136709958 1783 1311867778.1094930172 0.0121859191 0.0244693177 0.0670038015 0.0046570588 0.0323880000 411290381 0 402718720 -0.0139417825 -0.0054630190 0.0123928459 1784 1311867778.1418550014 0.0115616731 0.0244620825 0.0670038015 0.0046558784 0.0330490000 411293705 0 402718720 -0.0134999715 -0.0044359174 0.0129661877 1785 1311867778.1826310158 0.0132432058 0.0244557974 0.0670038015 0.0046557668 0.0322990000 411297717 0 402718720 -0.0146743078 -0.0059381067 0.0133607918 1786 1311867778.2094058990 0.0113385003 0.0244484529 0.0670038015 0.0046565527 0.0331440000 411300233 0 402718720 -0.0123605188 -0.0045978525 0.0121194776 1787 1311867778.2432699203 0.0132244769 0.0244421720 0.0670038015 0.0046556039 0.0324640000 411303557 0 402718720 -0.0137493713 -0.0057795290 0.0140554542 1788 1311867778.2796919346 0.0122879418 0.0244353743 0.0670038015 0.0046553983 0.0414490000 411306633 0 402718720 -0.0169804599 -0.0058721718 0.0119491927 1789 1311867778.3125588894 0.0098635871 0.0244272291 0.0670038015 0.0046546301 0.0327810000 411309069 0 402718720 -0.0151241738 -0.0032814075 0.0123353899 1790 1311867778.3414309025 0.0127055617 0.0244206807 0.0670038015 0.0046539836 0.0429780000 411313113 0 402718720 -0.0150031270 -0.0070596980 0.0114952959 1791 1311867778.3782539368 0.0131798284 0.0244144044 0.0670038015 0.0046538552 0.0318990000 411316293 0 402718720 -0.0144698629 -0.0076101692 0.0118413633 1792 1311867778.4093298912 0.0110154096 0.0244069273 0.0670038015 0.0046534501 0.0319970000 411320161 0 402718720 -0.0134805562 -0.0043488778 0.0129374238 1793 1311867778.4445381165 0.0123190237 0.0244001855 0.0670038015 0.0046527453 0.0332900000 411323429 0 402718720 -0.0118642347 -0.0064556715 0.0118507631 1794 1311867778.4812810421 0.0118899215 0.0243932121 0.0670038015 0.0046517399 0.0335100000 411326929 0 402718720 -0.0133243101 -0.0060090395 0.0122751612 1795 1311867778.5097670555 0.0112578785 0.0243858944 0.0670038015 0.0046510218 0.0321240000 411329845 0 402718720 -0.0148034254 -0.0052661761 0.0127059603 1796 1311867778.5484840870 0.0101563092 0.0243779715 0.0670038015 0.0046500685 0.0449820000 411333521 0 402718720 -0.0136683052 -0.0045088166 0.0118639991 1797 1311867778.5830690861 0.0120255789 0.0243710976 0.0670038015 0.0046501694 0.0336710000 411336581 0 402718720 -0.0121005625 -0.0067359395 0.0117261615 1798 1311867778.6150701046 0.0113976244 0.0243638821 0.0670038015 0.0046492753 0.0435870000 411340249 0 402718720 -0.0143601242 -0.0065252976 0.0117466105 1799 1311867778.6452109814 0.0125425495 0.0243573110 0.0670038015 0.0046485534 0.0339410000 411343013 0 402718720 -0.0135544091 -0.0073103160 0.0127381869 1800 1311867778.6781129837 0.0128508015 0.0243509185 0.0670038015 0.0046477014 0.0322450000 411346681 0 402718720 -0.0135024758 -0.0080235312 0.0122344606 1801 1311867778.7125270367 0.0115614757 0.0243438172 0.0670038015 0.0046471703 0.0337360000 411349237 0 402718720 -0.0140688559 -0.0062771486 0.0126083801 1802 1311867778.7490179539 0.0126800137 0.0243373445 0.0670038015 0.0046460145 0.0340860000 411353057 0 402718720 -0.0154513987 -0.0079914741 0.0125611881 1803 1311867778.7815420628 0.0130445333 0.0243310812 0.0670038015 0.0046453335 0.0343210000 411356701 0 402718720 -0.0154783372 -0.0078362878 0.0132268574 1804 1311867778.8090119362 0.0126890549 0.0243246277 0.0670038015 0.0046443855 0.0344160000 411359289 0 402718720 -0.0143739693 -0.0070174849 0.0135652069 1805 1311867778.8465809822 0.0092613585 0.0243162824 0.0670038015 0.0046445905 0.0334310000 411362453 0 402718720 -0.0153189050 -0.0047868257 0.0112250885 1806 1311867778.8808300495 0.0127682118 0.0243098881 0.0670038015 0.0046433216 0.0424780000 411366177 0 402718720 -0.0173097067 -0.0080245947 0.0129078254 1807 1311867778.9117860794 0.0119242463 0.0243030339 0.0670038015 0.0046422821 0.0380890000 411369133 0 402718720 -0.0163302589 -0.0082147745 0.0116355987 1808 1311867778.9482150078 0.0100560356 0.0242951539 0.0670038015 0.0046421165 0.0403810000 411372121 0 402718720 -0.0168217979 -0.0058769286 0.0113387210 1809 1311867778.9777760506 0.0096574100 0.0242870623 0.0670038015 0.0046408842 0.0402730000 411375685 0 402718720 -0.0150932716 -0.0057505574 0.0108319689 1810 1311867779.0105700493 0.0134552233 0.0242810778 0.0670038015 0.0046402085 0.0386130000 411378313 0 402718720 -0.0163534079 -0.0094583472 0.0126735205 1811 1311867779.0471200943 0.0122526065 0.0242744360 0.0670038015 0.0046391435 0.0344590000 411382149 0 402718720 -0.0157655403 -0.0091086645 0.0114955436 1812 1311867779.0780360699 0.0097072767 0.0242663967 0.0670038015 0.0046382875 0.0432860000 411384617 0 402718720 -0.0165277570 -0.0069760941 0.0099028144 1813 1311867779.1124050617 0.0113318721 0.0242592624 0.0670038015 0.0046373549 0.0359090000 411388533 0 402718720 -0.0152796321 -0.0091365613 0.0100894524 1814 1311867779.1473538876 0.0118859326 0.0242524413 0.0670038015 0.0046363056 0.0455810000 411391809 0 402718720 -0.0133582503 -0.0094882036 0.0100506432 1815 1311867779.1777000427 0.0124055706 0.0242459141 0.0670038015 0.0046350636 0.0363050000 411394933 0 402718720 -0.0137174837 -0.0098672453 0.0104214922 1816 1311867779.2123599052 0.0108721834 0.0242385497 0.0670038015 0.0046346502 0.0356120000 411398409 0 402718720 -0.0140946470 -0.0077798925 0.0099221636 1817 1311867779.2447109222 0.0126583390 0.0242321765 0.0670038015 0.0046336931 0.0361300000 411401677 0 402718720 -0.0135088228 -0.0098043364 0.0103364568 1818 1311867779.2782809734 0.0109957214 0.0242248957 0.0670038015 0.0046338636 0.0358370000 411404761 0 402718720 -0.0153124789 -0.0095261754 0.0085466597 1819 1311867779.3104579449 0.0098126810 0.0242169726 0.0670038015 0.0046326864 0.0357750000 411408397 0 402718720 -0.0147870211 -0.0084139295 0.0078910254 1820 1311867779.3468949795 0.0137165310 0.0242112031 0.0670038015 0.0046317348 0.0436480000 411411409 0 402718720 -0.0154782105 -0.0120477397 0.0094034309 1821 1311867779.3772010803 0.0140000312 0.0242055956 0.0670038015 0.0046312181 0.0342320000 411414837 0 402718720 -0.0138954781 -0.0121333981 0.0099157896 1822 1311867779.4088799953 0.0125130368 0.0241991782 0.0670038015 0.0046300156 0.0451800000 411417857 0 402718720 -0.0129067171 -0.0109620430 0.0088718552 1823 1311867779.4446020126 0.0109468997 0.0241919087 0.0670038015 0.0046288346 0.0351410000 411420925 0 402718720 -0.0147142941 -0.0104477657 0.0071028313 1824 1311867779.4768970013 0.0118808169 0.0241851592 0.0670038015 0.0046281614 0.0352070000 411424289 0 402718720 -0.0158371199 -0.0102290940 0.0084202765 1825 1311867779.5098230839 0.0120248804 0.0241784960 0.0670038015 0.0046273059 0.0348960000 411427405 0 402718720 -0.0140749533 -0.0109461667 0.0084373122 1826 1311867779.5450038910 0.0107677216 0.0241711517 0.0670038015 0.0046263312 0.0355660000 411430953 0 402718720 -0.0144193992 -0.0113063194 0.0063890964 1827 1311867779.5777029991 0.0102810636 0.0241635490 0.0670038015 0.0046254358 0.0357700000 411433941 0 402718720 -0.0141589651 -0.0107425265 0.0061066179 1828 1311867779.6092689037 0.0131377708 0.0241575174 0.0670038015 0.0046243688 0.0355060000 411436961 0 402718720 -0.0152474679 -0.0121851470 0.0083526904 1829 1311867779.6482150555 0.0130402045 0.0241514391 0.0670038015 0.0046234383 0.0370170000 411440149 0 402718720 -0.0148736844 -0.0134143615 0.0072795860 1830 1311867779.6796278954 0.0121430503 0.0241448771 0.0670038015 0.0046226189 0.0352840000 411443825 0 402718720 -0.0132912351 -0.0138208969 0.0058222618 1831 1311867779.7129859924 0.0122536607 0.0241383827 0.0670038015 0.0046214540 0.0365910000 411446781 0 402718720 -0.0134031810 -0.0144517226 0.0052675703 1832 1311867779.7461729050 0.0103213964 0.0241308407 0.0670038015 0.0046212402 0.0369650000 411450233 0 402718720 -0.0122174518 -0.0118896961 0.0050708102 1833 1311867779.7771708965 0.0094933296 0.0241228551 0.0670038015 0.0046201022 0.0353560000 411453069 0 402718720 -0.0131139364 -0.0114820106 0.0041525303 1834 1311867779.8130059242 0.0115061626 0.0241159758 0.0670038015 0.0046199168 0.0364190000 411456337 0 402718720 -0.0129740825 -0.0145150609 0.0043690223 1835 1311867779.8454499245 0.0105137667 0.0241085632 0.0670038015 0.0046188167 0.0350350000 411459285 0 402718720 -0.0121026961 -0.0129831880 0.0045350040 1836 1311867779.8771400452 0.0090086916 0.0241003388 0.0670038015 0.0046177901 0.0364310000 411462569 0 402718720 -0.0104448218 -0.0122600980 0.0031978628 1837 1311867779.9128279686 0.0110546192 0.0240932372 0.0670038015 0.0046182447 0.0454840000 411465757 0 402718720 -0.0109683760 -0.0148346201 0.0035431932 1838 1311867779.9448599815 0.0106379827 0.0240859166 0.0670038015 0.0046176640 0.0359750000 411469225 0 402718720 -0.0128355669 -0.0134243518 0.0037943502 1839 1311867779.9769320488 0.0103866011 0.0240784673 0.0670038015 0.0046165437 0.0465120000 411472309 0 402718720 -0.0114896083 -0.0139541021 0.0034008301 1840 1311867780.0130739212 0.0116159813 0.0240716942 0.0670038015 0.0046154843 0.0362230000 411475585 0 402718720 -0.0117988680 -0.0150945000 0.0038243679 1841 1311867780.0448310375 0.0105705047 0.0240643606 0.0670038015 0.0046148552 0.0353790000 411478685 0 402718720 -0.0122861490 -0.0152859725 0.0020340809 1842 1311867780.0771219730 0.0117401890 0.0240576699 0.0670038015 0.0046139973 0.0356320000 411481641 0 402718720 -0.0130666709 -0.0157764796 0.0028424598 1843 1311867780.1143870354 0.0097712530 0.0240499182 0.0670038015 0.0046129389 0.0358500000 411484957 0 402718720 -0.0116900047 -0.0143634370 0.0018034764 1844 1311867780.1448268890 0.0095854634 0.0240420741 0.0670038015 0.0046136193 0.0363320000 411488001 0 402718720 -0.0123664159 -0.0143773435 0.0019039738 1845 1311867780.1773400307 0.0105245467 0.0240347476 0.0670038015 0.0046150232 0.0358390000 411491149 0 402718720 -0.0103330659 -0.0158539861 0.0019759736 1846 1311867780.2158250809 0.0098480657 0.0240270625 0.0670038015 0.0046172073 0.0467990000 411494649 0 402718720 -0.0104125226 -0.0165347960 0.0010103257 1847 1311867780.2454960346 0.0099937720 0.0240194646 0.0670038015 0.0046193609 0.0361740000 411497837 0 402718720 -0.0103482464 -0.0163602643 0.0009748600 1848 1311867780.2815570831 0.0091549866 0.0240114210 0.0670038015 0.0046182097 0.0353860000 411501193 0 402718720 -0.0117916586 -0.0162227675 -0.0001836629 1849 1311867780.3140099049 0.0101999696 0.0240039513 0.0670038015 0.0046171436 0.0356720000 411504405 0 402718720 -0.0127652939 -0.0169010032 0.0003053891 1850 1311867780.3464050293 0.0105521483 0.0239966801 0.0670038015 0.0046162259 0.0360240000 411507489 0 402718720 -0.0115762930 -0.0184582397 0.0000313055 1851 1311867780.3772649765 0.0090406006 0.0239886001 0.0670038015 0.0046153095 0.0353690000 411510453 0 402718720 -0.0108430414 -0.0170921925 0.0000763307 1852 1311867780.4132668972 0.0100729307 0.0239810862 0.0670038015 0.0046151602 0.0415820000 411513769 0 402718720 -0.0109829158 -0.0164208859 0.0006045103 1853 1311867780.4451050758 0.0097257644 0.0239733931 0.0670038015 0.0046141574 0.0409410000 411516917 0 402718720 -0.0101430267 -0.0184662547 -0.0007365658 1854 1311867780.4791510105 0.0080530811 0.0239648061 0.0670038015 0.0046166225 0.0419770000 411520137 0 402718720 -0.0096922582 -0.0191959906 -0.0024688528 1855 1311867780.5153009892 0.0102010043 0.0239573863 0.0670038015 0.0046168228 0.0422570000 411523581 0 402718720 -0.0106106112 -0.0200398602 -0.0015578209 1856 1311867780.5455119610 0.0076922532 0.0239486227 0.0670038015 0.0046201502 0.0351580000 411526417 0 402718720 -0.0113306325 -0.0177813675 -0.0025106762 1857 1311867780.5798339844 0.0078410823 0.0239399488 0.0670038015 0.0046202900 0.0356790000 411530005 0 402718720 -0.0105329296 -0.0183273610 -0.0023617353 1858 1311867780.6136929989 0.0098580047 0.0239323697 0.0670038015 0.0046244156 0.0357960000 411533105 0 402718720 -0.0116637331 -0.0193964597 -0.0022343700 1859 1311867780.6459660530 0.0084542148 0.0239240436 0.0670038015 0.0046239642 0.0358150000 411536437 0 402718720 -0.0111910440 -0.0171630476 -0.0024630208 1860 1311867780.6793959141 0.0103167845 0.0239167279 0.0670038015 0.0046238937 0.0355880000 411539385 0 402718720 -0.0116518401 -0.0210716389 -0.0030825669 1861 1311867780.7156999111 0.0091813114 0.0239088099 0.0670038015 0.0046230118 0.0355930000 411542773 0 402718720 -0.0125077497 -0.0203697942 -0.0046432051 1862 1311867780.7469029427 0.0079810414 0.0239002558 0.0670038015 0.0046219939 0.0362630000 411545801 0 402718720 -0.0116392598 -0.0187238138 -0.0043534557 1863 1311867780.7774689198 0.0078230677 0.0238916260 0.0670038015 0.0046210453 0.0475190000 411548773 0 402718720 -0.0107454620 -0.0197918080 -0.0049263379 1864 1311867780.8164570332 0.0081236372 0.0238831668 0.0670038015 0.0046200550 0.0363950000 411552337 0 402718720 -0.0109155579 -0.0207465217 -0.0054514147 1865 1311867780.8460350037 0.0089879362 0.0238751801 0.0670038015 0.0046196276 0.0362320000 411555245 0 402718720 -0.0112462463 -0.0218296070 -0.0052136681 1866 1311867780.8791809082 0.0082008364 0.0238667801 0.0670038015 0.0046187544 0.0362040000 411558449 0 402718720 -0.0098670945 -0.0208186619 -0.0052745356 1867 1311867780.9152340889 0.0087524932 0.0238586846 0.0670038015 0.0046187594 0.0355030000 411561725 0 402718720 -0.0085929511 -0.0235921852 -0.0070307478 1868 1311867780.9457290173 0.0078206090 0.0238500989 0.0670038015 0.0046178609 0.0484130000 411565025 0 402718720 -0.0102965487 -0.0227725636 -0.0076437523 1869 1311867780.9838399887 0.0082331458 0.0238417432 0.0670038015 0.0046172775 0.0467290000 411568293 0 402718720 -0.0097254589 -0.0240388103 -0.0082014613 1870 1311867781.0137300491 0.0072622094 0.0238328771 0.0670038015 0.0046161057 0.0738740000 411571401 0 402718720 -0.0099221785 -0.0229424220 -0.0086332392 1871 1311867781.0463659763 0.0080309575 0.0238244314 0.0670038015 0.0046153552 0.0361380000 411574421 0 402718720 -0.0122759640 -0.0230968297 -0.0089069977 1872 1311867781.0821859837 0.0079701357 0.0238159622 0.0670038015 0.0046144740 0.0356480000 411577809 0 402718720 -0.0121828672 -0.0241358522 -0.0099233733 1873 1311867781.1157560349 0.0065889740 0.0238067647 0.0670038015 0.0046139864 0.0361560000 411580821 0 402718720 -0.0109106265 -0.0223958772 -0.0095136417 1874 1311867781.1459479332 0.0066172336 0.0237975920 0.0670038015 0.0046140397 0.0367470000 411584009 0 402718720 -0.0107117165 -0.0242477618 -0.0104787163 1875 1311867781.1839950085 0.0084190574 0.0237893902 0.0670038015 0.0046154591 0.0366700000 411587389 0 402718720 -0.0097473748 -0.0269041713 -0.0102651110 1876 1311867781.2133030891 0.0072425525 0.0237805699 0.0670038015 0.0046147546 0.0367150000 411590617 0 402718720 -0.0094729681 -0.0262091588 -0.0113033028 1877 1311867781.2467529774 0.0083909957 0.0237723709 0.0670038015 0.0046140249 0.0480950000 411593637 0 402718720 -0.0103733679 -0.0278935339 -0.0124834254 1878 1311867781.2855589390 0.0077266591 0.0237638268 0.0670038015 0.0046130126 0.0459550000 411597009 0 402718720 -0.0079005370 -0.0273895655 -0.0123219267 1879 1311867781.3133049011 0.0101750595 0.0237565949 0.0670038015 0.0046135308 0.0455750000 411600005 0 402718720 -0.0107748313 -0.0301890522 -0.0143365618 1880 1311867781.3465669155 0.0079902513 0.0237482085 0.0670038015 0.0046136600 0.0360510000 411603265 0 402718720 -0.0109274201 -0.0278387051 -0.0150417965 1881 1311867781.3809239864 0.0071888571 0.0237394051 0.0670038015 0.0046129233 0.0364950000 411606469 0 402718720 -0.0114528844 -0.0260537919 -0.0147385374 1882 1311867781.4144830704 0.0071617733 0.0237305965 0.0670038015 0.0046123292 0.0367950000 411609761 0 402718720 -0.0095692761 -0.0278409198 -0.0155530497 1883 1311867781.4457330704 0.0088895261 0.0237227149 0.0670038015 0.0046132414 0.0359280000 411612781 0 402718720 -0.0129039949 -0.0287666712 -0.0157717019 1884 1311867781.4812419415 0.0068913563 0.0237137811 0.0670038015 0.0046132516 0.0363040000 411616041 0 402718720 -0.0062668989 -0.0287005547 -0.0160570703 1885 1311867781.5131030083 0.0073129018 0.0237050804 0.0670038015 0.0046142267 0.0364800000 411619165 0 402718720 -0.0099820485 -0.0291312505 -0.0174706671 1886 1311867781.5451910496 0.0053795292 0.0236953637 0.0670038015 0.0046139875 0.0371480000 411622561 0 402718720 -0.0086159073 -0.0279665887 -0.0182491988 1887 1311867781.5813419819 0.0054039136 0.0236856703 0.0670038015 0.0046152745 0.0475150000 411625597 0 402718720 -0.0085442727 -0.0289703906 -0.0190945007 1888 1311867781.6135890484 0.0064653549 0.0236765494 0.0670038015 0.0046149398 0.0368270000 411628817 0 402718720 -0.0117040444 -0.0275102928 -0.0183513816 1889 1311867781.6467020512 0.0058128568 0.0236670927 0.0670038015 0.0046151418 0.0367550000 411632165 0 402718720 -0.0093331756 -0.0298142228 -0.0194872692 1890 1311867781.6832339764 0.0039944747 0.0236566839 0.0670038015 0.0046141806 0.0365320000 411635361 0 402718720 -0.0085545694 -0.0286794621 -0.0205519758 1891 1311867781.7131800652 0.0043383897 0.0236464680 0.0670038015 0.0046130045 0.0362140000 411638501 0 402718720 -0.0084559321 -0.0295761414 -0.0207607169 1892 1311867781.7453010082 0.0066753631 0.0236374981 0.0670038015 0.0046121501 0.0364770000 411641753 0 402718720 -0.0117478091 -0.0306209084 -0.0216019191 1893 1311867781.7820630074 0.0053736856 0.0236278500 0.0670038015 0.0046119236 0.0447630000 411645077 0 402718720 -0.0113642849 -0.0293010026 -0.0216504820 1894 1311867781.8145859241 0.0038956662 0.0236174317 0.0670038015 0.0046149017 0.0367970000 411648097 0 402718720 -0.0098133404 -0.0298042558 -0.0215099249 1895 1311867781.8453550339 0.0040491913 0.0236071055 0.0670038015 0.0046140041 0.0368950000 411651245 0 402718720 -0.0093383985 -0.0310027562 -0.0238777921 1896 1311867781.8827259541 0.0021044568 0.0235957644 0.0670038015 0.0046139248 0.0379150000 411654441 0 402718720 -0.0085362503 -0.0300762467 -0.0236081090 1897 1311867781.9138391018 0.0039696204 0.0235854185 0.0670038015 0.0046143501 0.0376050000 411657653 0 402718720 -0.0090763830 -0.0327404216 -0.0234962776 1898 1311867781.9470670223 0.0033313285 0.0235747473 0.0670038015 0.0046132250 0.0371290000 411660937 0 402718720 -0.0083439890 -0.0331976488 -0.0242970213 1899 1311867781.9856810570 0.0030945975 0.0235639626 0.0670038015 0.0046140602 0.0369830000 411663973 0 402718720 -0.0080802338 -0.0336776190 -0.0250914805 1900 1311867782.0139210224 0.0039343373 0.0235536312 0.0670038015 0.0046152683 0.0361250000 411667089 0 402718720 -0.0078670876 -0.0350356475 -0.0266035572 1901 1311867782.0464830399 0.0056693759 0.0235442234 0.0670038015 0.0046147831 0.0367350000 411670357 0 402718720 -0.0101575479 -0.0363535620 -0.0269736424 1902 1311867782.0839829445 0.0037389065 0.0235338105 0.0670038015 0.0046152780 0.0371040000 411673689 0 402718720 -0.0087878201 -0.0347471088 -0.0280265156 1903 1311867782.1135599613 0.0036710724 0.0235233729 0.0670038015 0.0046151049 0.0450230000 411676653 0 402718720 -0.0096603837 -0.0329204164 -0.0291876942 1904 1311867782.1472380161 0.0032976314 0.0235127501 0.0670038015 0.0046139226 0.0372140000 411680049 0 402718720 -0.0098675750 -0.0331450738 -0.0285429414 1905 1311867782.1819090843 0.0025552467 0.0235017488 0.0670038015 0.0046130129 0.0372490000 411683245 0 402718720 -0.0077845356 -0.0338033028 -0.0286633410 1906 1311867782.2144429684 0.0038722181 0.0234914500 0.0670038015 0.0046127926 0.0367620000 411686329 0 402718720 -0.0093758935 -0.0324072540 -0.0303871986 1907 1311867782.2494089603 0.0043985499 0.0234814380 0.0670038015 0.0046139694 0.0368460000 411689533 0 402718720 -0.0103393486 -0.0348569266 -0.0295312461 1908 1311867782.2860810757 0.0027048900 0.0234705488 0.0670038015 0.0046127989 0.0363420000 411692849 0 402718720 -0.0082436996 -0.0329231247 -0.0302786957 1909 1311867782.3144040108 0.0030634790 0.0234598589 0.0670038015 0.0046121920 0.0487780000 411695893 0 402718720 -0.0086286692 -0.0324311741 -0.0305663012 1910 1311867782.3526129723 0.0031742393 0.0234492381 0.0670038015 0.0046129130 0.0372250000 411699201 0 402718720 -0.0083416281 -0.0328874476 -0.0311925951 1911 1311867782.3825540543 0.0036903387 0.0234388986 0.0670038015 0.0046119336 0.0448720000 411702173 0 402718720 -0.0086758193 -0.0339121334 -0.0316772312 1912 1311867782.4147620201 0.0042142733 0.0234288439 0.0670038015 0.0046117877 0.0375990000 411705593 0 402718720 -0.0094977552 -0.0331202410 -0.0319509171 1913 1311867782.4514210224 0.0033561173 0.0234183511 0.0670038015 0.0046108867 0.0372990000 411708533 0 402718720 -0.0083382484 -0.0347681455 -0.0314290933 1914 1311867782.4812099934 0.0034807597 0.0234079343 0.0670038015 0.0046097138 0.0375110000 411711761 0 402718720 -0.0083389198 -0.0344521739 -0.0317987874 1915 1311867782.5149359703 0.0038237558 0.0233977076 0.0670038015 0.0046095473 0.0370580000 411714781 0 402718720 -0.0080413381 -0.0329985544 -0.0325654931 1916 1311867782.5516130924 0.0037075237 0.0233874309 0.0670038015 0.0046091580 0.0369080000 411718041 0 402718720 -0.0075584273 -0.0324072391 -0.0326810367 1917 1311867782.5828690529 0.0027482663 0.0233766645 0.0670038015 0.0046081065 0.0368730000 411721197 0 402718720 -0.0071722222 -0.0327618681 -0.0320395157 1918 1311867782.6142859459 0.0039217318 0.0233665212 0.0670038015 0.0046079894 0.0371720000 411724545 0 402718720 -0.0091357967 -0.0325865448 -0.0318572931 1919 1311867782.6501080990 0.0039978269 0.0233564281 0.0670038015 0.0046078904 0.0470640000 411727693 0 402718720 -0.0082920641 -0.0316010714 -0.0328036696 1920 1311867782.6862080097 0.0033134008 0.0233459890 0.0670038015 0.0046085164 0.0366330000 411731081 0 402718720 -0.0076057669 -0.0330476984 -0.0331027806 1921 1311867782.7131700516 0.0020614269 0.0233349090 0.0670038015 0.0046081155 0.0360860000 411734077 0 402718720 -0.0058418401 -0.0317393690 -0.0328994989 1922 1311867782.7489991188 0.0032704654 0.0233244697 0.0670038015 0.0046082240 0.0364350000 411737369 0 402718720 -0.0077504078 -0.0330441967 -0.0331585258 1923 1311867782.7844688892 0.0036461924 0.0233142366 0.0670038015 0.0046077717 0.0362070000 411740517 0 402718720 -0.0075122444 -0.0353034586 -0.0336618684 1924 1311867782.8159070015 0.0025583101 0.0233034487 0.0670038015 0.0046069990 0.0366610000 411743665 0 402718720 -0.0073923352 -0.0329142660 -0.0336742401 1925 1311867782.8522670269 0.0019097367 0.0232923351 0.0670038015 0.0046061035 0.0479920000 411746821 0 402718720 -0.0070667258 -0.0333636664 -0.0345083028 1926 1311867782.8824830055 0.0027422511 0.0232816652 0.0670038015 0.0046051967 0.0368100000 411749969 0 402718720 -0.0077944021 -0.0350996368 -0.0347397625 1927 1311867782.9145979881 0.0020980807 0.0232706722 0.0670038015 0.0046056335 0.0443510000 411753341 0 402718720 -0.0066536362 -0.0337241404 -0.0363041535 1928 1311867782.9517209530 0.0023402520 0.0232598162 0.0670038015 0.0046046105 0.0371250000 411756785 0 402718720 -0.0064860084 -0.0326587670 -0.0371765867 1929 1311867782.9812240601 0.0020012720 0.0232487957 0.0670038015 0.0046037138 0.0367190000 411759517 0 402718720 -0.0080174888 -0.0343808085 -0.0363352448 1930 1311867783.0143089294 0.0027032392 0.0232381503 0.0670038015 0.0046030349 0.0369230000 411762929 0 402718720 -0.0072055701 -0.0345790572 -0.0386722647 1931 1311867783.0528459549 0.0023934785 0.0232273555 0.0670038015 0.0046019746 0.0368830000 411766189 0 402718720 -0.0066937553 -0.0328347646 -0.0386438780 1932 1311867783.0829811096 0.0031461339 0.0232169615 0.0670038015 0.0046024227 0.0366050000 411769337 0 402718720 -0.0080520092 -0.0351800099 -0.0395995639 1933 1311867783.1137030125 0.0025586425 0.0232062744 0.0670038015 0.0046014871 0.0458780000 411772253 0 402718720 -0.0066333828 -0.0347630680 -0.0399382748 1934 1311867783.1539480686 0.0019408491 0.0231952788 0.0670038015 0.0046004106 0.0366400000 411775881 0 402718720 -0.0074083665 -0.0346163698 -0.0394558087 1935 1311867783.1857850552 0.0020536012 0.0231843529 0.0670038015 0.0045993092 0.0447630000 411778901 0 402718720 -0.0066411281 -0.0342133343 -0.0399216078 1936 1311867783.2169439793 0.0026243899 0.0231737330 0.0670038015 0.0045991208 0.0375370000 411782249 0 402718720 -0.0086536966 -0.0346540846 -0.0401124172 1937 1311867783.2548489571 0.0029063404 0.0231632698 0.0670038015 0.0045980060 0.0371100000 411785429 0 402718720 -0.0075841206 -0.0336823277 -0.0408279188 1938 1311867783.2816879749 0.0017019071 0.0231521958 0.0670038015 0.0045970555 0.0434190000 411788337 0 402718720 -0.0072037424 -0.0346216634 -0.0401535071 1939 1311867783.3132228851 0.0020060549 0.0231412901 0.0670038015 0.0045962522 0.0423310000 411791501 0 402718720 -0.0068754437 -0.0349375904 -0.0407621004 1940 1311867783.3503270149 0.0025666011 0.0231306846 0.0670038015 0.0045956916 0.0429600000 411794689 0 402718720 -0.0067036436 -0.0345443897 -0.0413208194 1941 1311867783.3855919838 0.0023207923 0.0231199634 0.0670038015 0.0045949824 0.0424100000 411798013 0 402718720 -0.0073908661 -0.0334427431 -0.0403025374 1942 1311867783.4198501110 0.0018631131 0.0231090175 0.0670038015 0.0045942210 0.0369500000 411801137 0 402718720 -0.0087169120 -0.0360351726 -0.0404894836 1943 1311867783.4503099918 0.0028012895 0.0230985658 0.0670038015 0.0045931311 0.0451660000 411804485 0 402718720 -0.0082001472 -0.0348498337 -0.0421798341 1944 1311867783.4863688946 0.0028447036 0.0230881471 0.0670038015 0.0045927835 0.0372700000 411807777 0 402718720 -0.0078128977 -0.0348510146 -0.0422761701 1945 1311867783.5186200142 0.0020830154 0.0230773476 0.0670038015 0.0045921536 0.0371350000 411810693 0 402718720 -0.0082912268 -0.0362922177 -0.0418316610 1946 1311867783.5488419533 0.0028530578 0.0230669548 0.0670038015 0.0045931978 0.0373440000 411813849 0 402718720 -0.0084718252 -0.0343711376 -0.0418045484 1947 1311867783.5823969841 0.0032129153 0.0230567576 0.0670038015 0.0045920611 0.0373700000 411817109 0 402718720 -0.0082266396 -0.0340547636 -0.0420952924 1948 1311867783.6168529987 0.0022932298 0.0230460987 0.0670038015 0.0045912179 0.0373310000 411820129 0 402718720 -0.0090158992 -0.0355190001 -0.0415183455 1949 1311867783.6515829563 0.0027650138 0.0230356928 0.0670038015 0.0045908599 0.0497410000 411823397 0 402718720 -0.0065850839 -0.0359686650 -0.0433855280 1950 1311867783.6816630363 0.0041093831 0.0230259870 0.0670038015 0.0045916394 0.0473650000 411826561 0 402718720 -0.0090093091 -0.0342649259 -0.0434305817 1951 1311867783.7179610729 0.0020233938 0.0230152219 0.0670038015 0.0045919426 0.0435640000 411830029 0 402718720 -0.0073290337 -0.0357157253 -0.0424474925 1952 1311867783.7488200665 0.0030372343 0.0230049873 0.0670038015 0.0045915942 0.0364840000 411833249 0 402718720 -0.0082678217 -0.0355382636 -0.0427760370 1953 1311867783.7808690071 0.0044590216 0.0229954912 0.0670038015 0.0045911004 0.0367140000 411836397 0 402718720 -0.0065510799 -0.0336984843 -0.0431890339 1954 1311867783.8168580532 0.0016566085 0.0229845705 0.0670038015 0.0045926692 0.0366790000 411839153 0 402718720 -0.0076533086 -0.0370420888 -0.0412512459 1955 1311867783.8489229679 0.0045598708 0.0229751461 0.0670038015 0.0045934212 0.0358910000 411842493 0 402718720 -0.0071053645 -0.0342532247 -0.0425393507 1956 1311867783.8808929920 0.0064721582 0.0229667090 0.0670038015 0.0045924979 0.0363850000 411845577 0 402718720 -0.0071962564 -0.0317680836 -0.0426537022 1957 1311867783.9168200493 0.0037730627 0.0229569013 0.0670038015 0.0045945032 0.0489550000 411849109 0 402718720 -0.0068850699 -0.0345050544 -0.0420776568 1958 1311867783.9508318901 0.0033265159 0.0229468756 0.0670038015 0.0045939836 0.0462130000 411852185 0 402718720 -0.0069879536 -0.0343222804 -0.0410751440 1959 1311867783.9816930294 0.0049801627 0.0229377042 0.0670038015 0.0045947362 0.0384620000 411855149 0 402718720 -0.0060010101 -0.0329729170 -0.0414843224 1960 1311867784.0175230503 0.0027537409 0.0229274063 0.0670038015 0.0045940593 0.0370600000 411858529 0 402718720 -0.0062101353 -0.0349818282 -0.0404133201 1961 1311867784.0505928993 0.0035136254 0.0229175064 0.0670038015 0.0045947819 0.0369140000 411861861 0 402718720 -0.0094484836 -0.0348330438 -0.0398748666 1962 1311867784.0830729008 0.0048693526 0.0229083075 0.0670038015 0.0045939603 0.0368060000 411864697 0 402718720 -0.0078692827 -0.0325696245 -0.0406209305 1963 1311867784.1187570095 0.0035924378 0.0228984675 0.0670038015 0.0045951132 0.0375250000 411867973 0 402718720 -0.0072064227 -0.0349025577 -0.0405727923 1964 1311867784.1503119469 0.0042340877 0.0228889643 0.0670038015 0.0045955584 0.0366240000 411871185 0 402718720 -0.0106052300 -0.0361969173 -0.0399917439 1965 1311867784.1823339462 0.0054839291 0.0228801068 0.0670038015 0.0045944833 0.0481710000 411874341 0 402718720 -0.0075842901 -0.0325971618 -0.0394802801 1966 1311867784.2173891068 0.0025328412 0.0228697572 0.0670038015 0.0045951660 0.0370680000 411877489 0 402718720 -0.0082124332 -0.0358425528 -0.0383782089 1967 1311867784.2502059937 0.0023415177 0.0228593209 0.0670038015 0.0045944384 0.0466690000 411880821 0 402718720 -0.0094690798 -0.0373035483 -0.0388530195 1968 1311867784.2819900513 0.0035993583 0.0228495343 0.0670038015 0.0045956906 0.0371420000 411883785 0 402718720 -0.0097679356 -0.0351378918 -0.0383516625 1969 1311867784.3176920414 0.0041209050 0.0228400226 0.0670038015 0.0045963249 0.0369430000 411887165 0 402718720 -0.0097213974 -0.0349759348 -0.0385143794 1970 1311867784.3490819931 0.0021698377 0.0228295301 0.0670038015 0.0045965454 0.0371450000 411890465 0 402718720 -0.0103968047 -0.0383486636 -0.0371118635 1971 1311867784.3815689087 0.0035684886 0.0228197579 0.0670038015 0.0045970325 0.0371520000 411893349 0 402718720 -0.0095935296 -0.0363518223 -0.0381012410 1972 1311867784.4190580845 0.0047251205 0.0228105821 0.0670038015 0.0045960801 0.0370890000 411896769 0 402718720 -0.0123763196 -0.0368636176 -0.0369645618 1973 1311867784.4496140480 0.0017413265 0.0227999033 0.0670038015 0.0045964256 0.0468820000 411899981 0 402718720 -0.0087644272 -0.0380947478 -0.0367542692 1974 1311867784.4828379154 0.0033210251 0.0227900356 0.0670038015 0.0045965118 0.0367710000 411903185 0 402718720 -0.0087679969 -0.0365547687 -0.0369717181 1975 1311867784.5185639858 0.0030012582 0.0227800159 0.0670038015 0.0045955690 0.0505840000 411906301 0 402718720 -0.0104184961 -0.0388231017 -0.0372850746 1976 1311867784.5499279499 0.0033011693 0.0227701582 0.0670038015 0.0045944923 0.0376900000 411909513 0 402718720 -0.0115395132 -0.0394873396 -0.0367297269 1977 1311867784.5848410130 0.0025342379 0.0227599225 0.0670038015 0.0045937571 0.0371550000 411912837 0 402718720 -0.0094087850 -0.0378975384 -0.0358735360 1978 1311867784.6179790497 0.0027829432 0.0227498230 0.0670038015 0.0045941424 0.0374300000 411915793 0 402718720 -0.0091590937 -0.0385839678 -0.0369966812 1979 1311867784.6492750645 0.0020571637 0.0227393668 0.0670038015 0.0045930815 0.0368520000 411919037 0 402718720 -0.0092778746 -0.0393488333 -0.0363855921 1980 1311867784.6878700256 0.0033629630 0.0227295808 0.0670038015 0.0045928799 0.0369390000 411922705 0 402718720 -0.0088185556 -0.0383123644 -0.0368085615 1981 1311867784.7168869972 0.0034798412 0.0227198636 0.0670038015 0.0045919223 0.0540360000 411925501 0 402718720 -0.0092377691 -0.0380860008 -0.0363230221 1982 1311867784.7578089237 0.0021718317 0.0227094963 0.0670038015 0.0045940116 0.0372130000 411929049 0 402718720 -0.0114521533 -0.0402782448 -0.0354505219 1983 1311867784.7870030403 0.0033645155 0.0226997409 0.0670038015 0.0045930437 0.0364700000 411932085 0 402718720 -0.0096107889 -0.0390219204 -0.0368086956 1984 1311867784.8199620247 0.0032457544 0.0226899354 0.0670038015 0.0045932662 0.0373010000 411935121 0 402718720 -0.0109878890 -0.0388084464 -0.0354168601 1985 1311867784.8550779819 0.0015682349 0.0226792948 0.0670038015 0.0045922967 0.0365760000 411938293 0 402718720 -0.0115576647 -0.0409498774 -0.0351833291 1986 1311867784.8873779774 0.0029921434 0.0226693818 0.0670038015 0.0045912184 0.0372610000 411941377 0 402718720 -0.0109307924 -0.0399654210 -0.0366014689 1987 1311867784.9173130989 0.0019463855 0.0226589525 0.0670038015 0.0045902165 0.0371940000 411944461 0 402718720 -0.0113275750 -0.0407180898 -0.0355772376 1988 1311867784.9491391182 0.0028324206 0.0226489794 0.0670038015 0.0045892190 0.0372890000 411947553 0 402718720 -0.0137046631 -0.0413981266 -0.0353883877 1989 1311867784.9848570824 0.0027816219 0.0226389908 0.0670038015 0.0045885190 0.0459020000 411950749 0 402718720 -0.0129557038 -0.0405848958 -0.0358577222 1990 1311867785.0184569359 0.0020532073 0.0226286462 0.0670038015 0.0045877268 0.0375770000 411954169 0 402718720 -0.0117659783 -0.0412050076 -0.0362572074 1991 1311867785.0500280857 0.0015859157 0.0226180773 0.0670038015 0.0045867796 0.0451050000 411957437 0 402718720 -0.0123481741 -0.0417639017 -0.0355076417 1992 1311867785.0871460438 0.0032889710 0.0226083739 0.0670038015 0.0045856368 0.0375330000 411960649 0 402718720 -0.0112315444 -0.0400036350 -0.0359586552 1993 1311867785.1168398857 0.0034687410 0.0225987705 0.0670038015 0.0045845349 0.0374380000 411963861 0 402718720 -0.0117944330 -0.0401488245 -0.0366066359 1994 1311867785.1499750614 0.0029716471 0.0225889274 0.0670038015 0.0045841230 0.0377310000 411966825 0 402718720 -0.0141436774 -0.0417797379 -0.0347292162 1995 1311867785.1850368977 0.0031641538 0.0225791906 0.0670038015 0.0045831032 0.0376960000 411970085 0 402718720 -0.0126383398 -0.0405026078 -0.0360553898 1996 1311867785.2169620991 0.0048162001 0.0225702913 0.0670038015 0.0045821109 0.0374980000 411973193 0 402718720 -0.0125106359 -0.0390013121 -0.0366116725 1997 1311867785.2491741180 0.0025436855 0.0225602630 0.0670038015 0.0045814424 0.0471880000 411976341 0 402718720 -0.0105038239 -0.0413995869 -0.0354374908 1998 1311867785.2858769894 0.0029695891 0.0225504579 0.0670038015 0.0045804076 0.0366810000 411979849 0 402718720 -0.0117172077 -0.0409492329 -0.0368010215 1999 1311867785.3214280605 0.0027608157 0.0225405581 0.0670038015 0.0045808182 0.0476980000 411982965 0 402718720 -0.0144367442 -0.0421807542 -0.0362449400 2000 1311867785.3573219776 0.0033044345 0.0225309400 0.0670038015 0.0045802801 0.0374880000 411986313 0 402718720 -0.0131975729 -0.0403671153 -0.0352555998 2001 1311867785.3893299103 0.0045974152 0.0225219777 0.0670038015 0.0045792213 0.0376320000 411989333 0 402718720 -0.0127103822 -0.0391496718 -0.0369649194 2002 1311867785.4211249352 0.0022435999 0.0225118487 0.0670038015 0.0045782614 0.0376840000 411992673 0 402718720 -0.0132595226 -0.0414786860 -0.0361888930 2003 1311867785.4570529461 0.0044314396 0.0225028220 0.0670038015 0.0045787006 0.0372370000 411995933 0 402718720 -0.0145278294 -0.0401831493 -0.0378592424 2004 1311867785.4900350571 0.0045567700 0.0224938669 0.0670038015 0.0045781345 0.0378190000 411999201 0 402718720 -0.0150503432 -0.0389362425 -0.0357583538 2005 1311867785.5211930275 0.0031502014 0.0224842192 0.0670038015 0.0045774141 0.0374660000 412002293 0 402718720 -0.0140085183 -0.0398694836 -0.0355064422 2006 1311867785.5571260452 0.0034746469 0.0224747428 0.0670038015 0.0045773029 0.0373190000 412005329 0 402718720 -0.0146135651 -0.0398199037 -0.0354629569 2007 1311867785.5891211033 0.0041220910 0.0224655985 0.0670038015 0.0045761935 0.0364830000 412008621 0 402718720 -0.0151415784 -0.0389707647 -0.0357428193 2008 1311867785.6211590767 0.0025664063 0.0224556886 0.0670038015 0.0045874019 0.0371590000 412011761 0 402718720 -0.0148455370 -0.0404429920 -0.0354058594 2009 1311867785.6570439339 0.0021196459 0.0224455661 0.0670038015 0.0045892389 0.0366820000 412015229 0 402718720 -0.0163647681 -0.0409244932 -0.0349496529 2010 1311867785.6892280579 0.0040560961 0.0224364171 0.0670038015 0.0045881336 0.0368770000 412017937 0 402718720 -0.0149888359 -0.0390112475 -0.0359368213 2011 1311867785.7214241028 0.0028004143 0.0224266528 0.0670038015 0.0045892909 0.0376040000 412021277 0 402718720 -0.0158899333 -0.0402691513 -0.0357503369 2012 1311867785.7573668957 0.0005117388 0.0224157607 0.0670038015 0.0045883458 0.0488300000 412024537 0 402718720 -0.0165223442 -0.0428333841 -0.0348738432 2013 1311867785.7892301083 0.0021031771 0.0224056700 0.0670038015 0.0045879273 0.0365900000 412027781 0 402718720 -0.0165194776 -0.0416918769 -0.0361600965 2014 1311867785.8210389614 0.0034814884 0.0223962737 0.0670038015 0.0045869997 0.0369610000 412030881 0 402718720 -0.0156960413 -0.0403106771 -0.0351392105 2015 1311867785.8574340343 0.0025654193 0.0223864321 0.0670038015 0.0045864576 0.0370790000 412034285 0 402718720 -0.0162290614 -0.0417369679 -0.0361083075 2016 1311867785.8893110752 0.0021986093 0.0223764183 0.0670038015 0.0045853304 0.0367220000 412037297 0 402718720 -0.0167866368 -0.0422540233 -0.0360643640 2017 1311867785.9211509228 0.0040089157 0.0223673119 0.0670038015 0.0045845397 0.0372180000 412040829 0 402718720 -0.0160561167 -0.0406568497 -0.0363847837 2018 1311867785.9588449001 0.0017287256 0.0223570847 0.0670038015 0.0045847665 0.0496370000 412043769 0 402718720 -0.0177698527 -0.0428184494 -0.0353620350 2019 1311867785.9892621040 0.0035053180 0.0223477475 0.0670038015 0.0045842816 0.0369140000 412046869 0 402718720 -0.0156357028 -0.0419441536 -0.0357800312 2020 1311867786.0210618973 0.0031931929 0.0223382650 0.0670038015 0.0045832201 0.0375400000 412050161 0 402718720 -0.0163790435 -0.0419327542 -0.0354291461 2021 1311867786.0572268963 0.0020675771 0.0223282350 0.0670038015 0.0045827493 0.0369300000 412053173 0 402718720 -0.0177594740 -0.0439958423 -0.0361548625 2022 1311867786.0892500877 0.0029745705 0.0223186635 0.0670038015 0.0045819039 0.0373980000 412056569 0 402718720 -0.0175809208 -0.0432855077 -0.0364564806 2023 1311867786.1211619377 0.0039489348 0.0223095830 0.0670038015 0.0045810591 0.0371840000 412059773 0 402718720 -0.0194182768 -0.0422786437 -0.0370732620 2024 1311867786.1570990086 0.0024553500 0.0222997736 0.0670038015 0.0045800725 0.0485040000 412062785 0 402718720 -0.0198644139 -0.0433616154 -0.0347594880 2025 1311867786.1891019344 0.0028666998 0.0222901770 0.0670038015 0.0045791807 0.0378350000 412065973 0 402718720 -0.0208332539 -0.0438767299 -0.0329630561 2026 1311867786.2216470242 0.0060510035 0.0222821617 0.0670038015 0.0045795878 0.0376850000 412069265 0 402718720 -0.0202354975 -0.0420469344 -0.0388630889 2027 1311867786.2570950985 0.0037997935 0.0222730436 0.0670038015 0.0045788575 0.0377990000 412072453 0 402718720 -0.0200776272 -0.0432384349 -0.0359665267 2028 1311867786.2895779610 0.0027862280 0.0222634347 0.0670038015 0.0045786952 0.0377570000 412075481 0 402718720 -0.0216873791 -0.0440766849 -0.0343105458 2029 1311867786.3211650848 0.0040544192 0.0222544603 0.0670038015 0.0045800857 0.0377510000 412078797 0 402718720 -0.0226496384 -0.0444966815 -0.0379034989 2030 1311867786.3572299480 0.0040977867 0.0222455161 0.0670038015 0.0045789772 0.0375690000 412082113 0 402718720 -0.0224775653 -0.0443939194 -0.0377385095 2031 1311867786.3891439438 0.0025041464 0.0222357961 0.0670038015 0.0045802505 0.0377580000 412085221 0 402718720 -0.0235877018 -0.0452064872 -0.0349502116 2032 1311867786.4213869572 0.0043214583 0.0222269800 0.0670038015 0.0045795385 0.0378990000 412088425 0 402718720 -0.0229708217 -0.0440030582 -0.0362881534 2033 1311867786.4573409557 0.0041635106 0.0222180949 0.0670038015 0.0045787115 0.0489780000 412091813 0 402718720 -0.0231205970 -0.0440217778 -0.0362772271 2034 1311867786.4891700745 0.0028988258 0.0222085967 0.0670038015 0.0045780957 0.0369680000 412094937 0 402718720 -0.0241915546 -0.0457007252 -0.0339591578 2035 1311867786.5218079090 0.0032894239 0.0221992998 0.0670038015 0.0045773110 0.0371130000 412098077 0 402718720 -0.0241371151 -0.0454486571 -0.0348330513 2036 1311867786.5572519302 0.0045619183 0.0221906370 0.0670038015 0.0045763916 0.0369330000 412101225 0 402718720 -0.0243505854 -0.0446156971 -0.0353026055 2037 1311867786.5895760059 0.0028303531 0.0221811327 0.0670038015 0.0045759092 0.0367020000 412104469 0 402718720 -0.0247419011 -0.0467264056 -0.0345014557 2038 1311867786.6211080551 0.0034334457 0.0221719337 0.0670038015 0.0045759272 0.0365180000 412107777 0 402718720 -0.0243708938 -0.0472761318 -0.0365057439 2039 1311867786.6573529243 0.0041583460 0.0221630991 0.0670038015 0.0045751349 0.0375670000 412111005 0 402718720 -0.0232347585 -0.0467673279 -0.0356294848 2040 1311867786.6891629696 0.0037084033 0.0221540527 0.0670038015 0.0045742595 0.0370050000 412113905 0 402718720 -0.0237563215 -0.0474579111 -0.0337769911 2041 1311867786.7210969925 0.0036841591 0.0221450033 0.0670038015 0.0045733765 0.0367910000 412116989 0 402718720 -0.0250587575 -0.0478077047 -0.0332281142 2042 1311867786.7570719719 0.0055833082 0.0221368928 0.0670038015 0.0045725427 0.0367630000 412120193 0 402718720 -0.0239946600 -0.0455789380 -0.0340469591 2043 1311867786.7892940044 0.0064969729 0.0221292374 0.0670038015 0.0045715588 0.0368570000 412123541 0 402718720 -0.0244877245 -0.0453110449 -0.0321900286 2044 1311867786.8211419582 0.0040596891 0.0221203971 0.0670038015 0.0045708790 0.0373320000 412126881 0 402718720 -0.0257261563 -0.0479702055 -0.0318091884 2045 1311867786.8575630188 0.0069709644 0.0221129891 0.0670038015 0.0045709347 0.0374300000 412130021 0 402718720 -0.0258895736 -0.0443703979 -0.0326650143 2046 1311867786.8893759251 0.0047085760 0.0221044825 0.0670038015 0.0045724348 0.0479580000 412133113 0 402718720 -0.0264984686 -0.0463204831 -0.0325357728 2047 1311867786.9211881161 0.0048733526 0.0220960648 0.0670038015 0.0045731026 0.0372590000 412136453 0 402718720 -0.0253504664 -0.0471854471 -0.0306232199 2048 1311867786.9576020241 0.0057686721 0.0220880924 0.0670038015 0.0045722018 0.0371530000 412139657 0 402718720 -0.0253032316 -0.0458560400 -0.0321394876 2049 1311867786.9892089367 0.0056043747 0.0220800476 0.0670038015 0.0045724389 0.0373380000 412339493 0 402718720 -0.0243773311 -0.0468749441 -0.0301477406 2050 1311867787.0211400986 0.0040892754 0.0220712717 0.0670038015 0.0045715875 0.0369420000 412752041 0 402718720 -0.0257977825 -0.0495992564 -0.0286827069 2051 1311867787.0571250916 0.0054261331 0.0220631560 0.0670038015 0.0045710867 0.0370650000 412755501 0 402718720 -0.0257478915 -0.0468624122 -0.0323206522 2052 1311867787.0895950794 0.0051995525 0.0220549379 0.0670038015 0.0045702844 0.0373270000 412758737 0 402718720 -0.0267774314 -0.0471755862 -0.0304829441 2053 1311867787.1239550114 0.0053956294 0.0220468233 0.0670038015 0.0045692416 0.0378480000 412761749 0 402718720 -0.0262046214 -0.0490754507 -0.0282087959 2054 1311867787.1573429108 0.0070629269 0.0220395283 0.0670038015 0.0045688760 0.0369560000 412765145 0 402718720 -0.0255689435 -0.0465254560 -0.0330332369 2055 1311867787.1892991066 0.0061668600 0.0220318044 0.0670038015 0.0045683999 0.0373690000 412767909 0 402718720 -0.0277574621 -0.0467298254 -0.0315665901 2056 1311867787.2230238914 0.0051785340 0.0220236073 0.0670038015 0.0045675976 0.0374000000 412771193 0 402718720 -0.0287705343 -0.0486161821 -0.0295558833 2057 1311867787.2571809292 0.0065051541 0.0220160631 0.0670038015 0.0045667865 0.0371400000 412774589 0 402718720 -0.0266591515 -0.0473760627 -0.0313182212 2058 1311867787.2893400192 0.0052689495 0.0220079255 0.0670038015 0.0045659095 0.0499440000 412777545 0 402718720 -0.0279325079 -0.0486139432 -0.0299587119 2059 1311867787.3217399120 0.0059845890 0.0220001434 0.0670038015 0.0045650059 0.0372800000 412780821 0 402718720 -0.0276697874 -0.0507528596 -0.0272563472 2060 1311867787.3572421074 0.0052619576 0.0219920181 0.0670038015 0.0045642264 0.0463780000 412783905 0 402718720 -0.0280550309 -0.0487853885 -0.0315254033 2061 1311867787.3892920017 0.0043846080 0.0219834749 0.0670038015 0.0045633619 0.0372090000 412787181 0 402718720 -0.0299117640 -0.0494352728 -0.0313670412 2062 1311867787.4245440960 0.0048733414 0.0219751771 0.0670038015 0.0045623224 0.0375210000 412790193 0 402718720 -0.0300677251 -0.0502810366 -0.0297915600 2063 1311867787.4572229385 0.0065861717 0.0219677176 0.0670038015 0.0045612874 0.0373130000 412793477 0 402718720 -0.0283605885 -0.0493433550 -0.0295490697 2064 1311867787.4892969131 0.0050872932 0.0219595391 0.0670038015 0.0045603192 0.0376050000 412796697 0 402718720 -0.0308643021 -0.0495581590 -0.0331354067 2065 1311867787.5220890045 0.0049645337 0.0219513090 0.0670038015 0.0045595334 0.0369710000 412800101 0 402718720 -0.0331491902 -0.0505196452 -0.0318297744 2066 1311867787.5581040382 0.0052138679 0.0219432077 0.0670038015 0.0045595005 0.0471520000 412803233 0 402718720 -0.0300382134 -0.0506315455 -0.0329752192 2067 1311867787.5897688866 0.0064944830 0.0219357337 0.0670038015 0.0045583985 0.0377430000 412806309 0 402718720 -0.0314190015 -0.0496131778 -0.0361618213 2068 1311867787.6235499382 0.0036612519 0.0219268969 0.0670038015 0.0045573895 0.0376700000 412809393 0 402718720 -0.0321165659 -0.0522403456 -0.0337116122 2069 1311867787.6574609280 0.0035167155 0.0219179988 0.0670038015 0.0045563040 0.0371830000 412812789 0 402718720 -0.0322858281 -0.0527146421 -0.0344315581 2070 1311867787.6898610592 0.0061815772 0.0219103966 0.0670038015 0.0045552101 0.0372020000 412815737 0 402718720 -0.0296909828 -0.0514910892 -0.0331428610 2071 1311867787.7212240696 0.0065836948 0.0219029960 0.0670038015 0.0045543250 0.0369430000 412819029 0 402718720 -0.0308947843 -0.0506866314 -0.0330184288 2072 1311867787.7579810619 0.0071245297 0.0218958635 0.0670038015 0.0045541395 0.0624430000 412822289 0 402718720 -0.0315635577 -0.0506585017 -0.0312280320 2073 1311867787.7901558876 0.0062376377 0.0218883101 0.0670038015 0.0045545888 0.0373290000 412825501 0 402718720 -0.0312579945 -0.0510853007 -0.0347633027 2074 1311867787.8218519688 0.0061779702 0.0218807352 0.0670038015 0.0045544315 0.0375240000 412828481 0 402718720 -0.0305642541 -0.0519126356 -0.0352063999 2075 1311867787.8573749065 0.0055154595 0.0218728484 0.0670038015 0.0045541309 0.0377260000 412832173 0 402718720 -0.0327969491 -0.0530973487 -0.0321869180 2076 1311867787.8894400597 0.0052425382 0.0218648376 0.0670038015 0.0045538454 0.0372260000 412835345 0 402718720 -0.0324449278 -0.0526610725 -0.0359576643 2077 1311867787.9214320183 0.0052475026 0.0218568370 0.0670038015 0.0045529177 0.0370250000 412838453 0 402718720 -0.0342205018 -0.0520895123 -0.0353212506 2078 1311867787.9577279091 0.0065019787 0.0218494477 0.0670038015 0.0045522907 0.0542960000 413466221 0 402718720 -0.0377512276 -0.0516655482 -0.0347319357 2079 1311867787.9892189503 0.0060362173 0.0218418415 0.0670038015 0.0045520303 0.1270030000 413406981 0 402718720 -0.0366904102 -0.0517962724 -0.0374378785 2080 1311867788.0211091042 0.0074084639 0.0218349024 0.0670038015 0.0045512087 0.1158130000 413409589 0 402718720 -0.0361738689 -0.0510036834 -0.0395784639 2081 1311867788.0577259064 0.0057372120 0.0218271669 0.0670038015 0.0045514245 0.1083120000 416596297 0 402718720 -0.0388806053 -0.0519224219 -0.0364445150 2082 1311867788.0892241001 0.0061809528 0.0218196519 0.0670038015 0.0045504121 0.0981390000 423991377 0 402718720 -0.0382338911 -0.0512755439 -0.0384446569 2083 1311867788.1307280064 0.0068028742 0.0218124427 0.0670038015 0.0045509943 0.0950010000 423767549 0 402718720 -0.0381662399 -0.0501919575 -0.0366486646 2084 1311867788.1572849751 0.0073502720 0.0218055030 0.0670038015 0.0045506145 0.0493980000 423903969 0 402718720 -0.0408087038 -0.0500672981 -0.0341818668 2085 1311867788.1904621124 0.0061006155 0.0217979707 0.0670038015 0.0045514570 0.0442560000 413424253 0 402718720 -0.0404336862 -0.0507411025 -0.0357595757 2086 1311867788.2247180939 0.0065901880 0.0217906803 0.0670038015 0.0045505828 0.0408890000 413427521 0 402718720 -0.0398976058 -0.0500623956 -0.0372111946 2087 1311867788.2583730221 0.0049358504 0.0217826042 0.0670038015 0.0045496285 0.0406720000 413430413 0 402718720 -0.0416261181 -0.0513796993 -0.0358156189 2088 1311867788.2893440723 0.0036539021 0.0217739219 0.0670038015 0.0045486518 0.0406830000 413433625 0 402718720 -0.0431899428 -0.0528304875 -0.0346853882 2089 1311867788.3251628876 0.0052589406 0.0217660162 0.0670038015 0.0045477886 0.0398850000 413436901 0 402718720 -0.0420205258 -0.0513959639 -0.0372362994 2090 1311867788.3571081161 0.0046534454 0.0217578284 0.0670038015 0.0045468755 0.0398320000 413439873 0 402718720 -0.0421583019 -0.0516551696 -0.0349741802 2091 1311867788.3910779953 0.0051649651 0.0217498930 0.0670038015 0.0045462103 0.0389050000 413443525 0 402718720 -0.0447663963 -0.0513662435 -0.0333949663 2092 1311867788.4251430035 0.0046929228 0.0217417396 0.0670038015 0.0045462899 0.0395320000 413446665 0 402718720 -0.0440820567 -0.0516126864 -0.0354248136 2093 1311867788.4573140144 0.0048566656 0.0217336722 0.0670038015 0.0045452241 0.0399340000 413449573 0 402718720 -0.0455207676 -0.0516890213 -0.0364065915 2094 1311867788.4924380779 0.0055387681 0.0217259382 0.0670038015 0.0045456320 0.0510970000 413452649 0 402718720 -0.0473403782 -0.0519077815 -0.0328508914 2095 1311867788.5262899399 0.0061061219 0.0217184824 0.0670038015 0.0045448598 0.0386850000 413455869 0 402718720 -0.0481472351 -0.0508873463 -0.0344209149 2096 1311867788.5573079586 0.0052185329 0.0217106103 0.0670038015 0.0045450751 0.0510370000 413459481 0 402718720 -0.0459092446 -0.0514326133 -0.0364331082 2097 1311867788.5915369987 0.0048226528 0.0217025569 0.0670038015 0.0045445700 0.0403640000 413462429 0 402718720 -0.0481538884 -0.0517865419 -0.0350030251 2098 1311867788.6251940727 0.0059719426 0.0216950590 0.0670038015 0.0045438868 0.0476170000 413465449 0 402718720 -0.0490143634 -0.0517609268 -0.0330969654 2099 1311867788.6593029499 0.0050189178 0.0216871142 0.0670038015 0.0045440699 0.0394770000 413468589 0 402718720 -0.0484979004 -0.0516697541 -0.0376826823 2100 1311867788.6898009777 0.0055020270 0.0216794070 0.0670038015 0.0045430293 0.0375350000 413471897 0 402718720 -0.0483368859 -0.0515294187 -0.0357278585 2101 1311867788.7262809277 0.0073143123 0.0216725698 0.0670038015 0.0045433770 0.0392050000 413475549 0 402718720 -0.0507774837 -0.0512108840 -0.0330203623 2102 1311867788.7571070194 0.0058467225 0.0216650408 0.0670038015 0.0045427498 0.0502160000 413478825 0 402718720 -0.0506874323 -0.0517634079 -0.0356835388 2103 1311867788.7899940014 0.0059945658 0.0216575893 0.0670038015 0.0045417609 0.0387100000 413481613 0 402718720 -0.0521530621 -0.0515573658 -0.0364695117 2104 1311867788.8253190517 0.0068989382 0.0216505748 0.0670038015 0.0045413008 0.0495640000 413484929 0 402718720 -0.0536578298 -0.0530843362 -0.0335689783 2105 1311867788.8572509289 0.0062464420 0.0216432569 0.0670038015 0.0045407882 0.0387820000 413488205 0 402718720 -0.0534450635 -0.0526378900 -0.0359474421 2106 1311867788.8892900944 0.0065372377 0.0216360841 0.0670038015 0.0045399551 0.0379480000 413491105 0 402718720 -0.0527867600 -0.0521025993 -0.0374414288 2107 1311867788.9253408909 0.0068435729 0.0216290634 0.0670038015 0.0045391146 0.0393570000 413494565 0 402718720 -0.0549725071 -0.0525171421 -0.0366149954 2108 1311867788.9572029114 0.0050201844 0.0216211844 0.0670038015 0.0045389137 0.0377300000 413497649 0 402718720 -0.0563930571 -0.0543784872 -0.0379195251 2109 1311867788.9914720058 0.0065024253 0.0216140157 0.0670038015 0.0045395710 0.0381530000 413500597 0 402718720 -0.0550431386 -0.0526226908 -0.0390592068 2110 1311867789.0253350735 0.0069406070 0.0216070615 0.0670038015 0.0045386548 0.0378680000 413503809 0 402718720 -0.0560084656 -0.0525118001 -0.0378337391 2111 1311867789.0572888851 0.0065503228 0.0215999290 0.0670038015 0.0045375899 0.0389680000 413507293 0 402718720 -0.0567020178 -0.0527593531 -0.0386420265 2112 1311867789.0921590328 0.0070519792 0.0215930408 0.0670038015 0.0045367149 0.0372090000 413510393 0 402718720 -0.0581364110 -0.0524468049 -0.0391816944 2113 1311867789.1266920567 0.0054299748 0.0215853914 0.0670038015 0.0045362142 0.0390010000 413513525 0 402718720 -0.0564500690 -0.0544493049 -0.0389063805 2114 1311867789.1574180126 0.0066822749 0.0215783417 0.0670038015 0.0045367006 0.0383340000 413516769 0 402718720 -0.0576297082 -0.0532438718 -0.0381091759 2115 1311867789.1895699501 0.0068628415 0.0215713840 0.0670038015 0.0045357590 0.0383250000 413519973 0 402718720 -0.0594685413 -0.0534717627 -0.0373728871 2116 1311867789.2251811028 0.0069325967 0.0215644659 0.0670038015 0.0045349791 0.0377110000 413523297 0 402718720 -0.0597238913 -0.0536132157 -0.0369805917 2117 1311867789.2573940754 0.0061126752 0.0215571670 0.0670038015 0.0045349483 0.0494170000 413526517 0 402718720 -0.0584116541 -0.0544929095 -0.0380341038 2118 1311867789.2926049232 0.0054381201 0.0215495565 0.0670038015 0.0045340783 0.0479490000 413529665 0 402718720 -0.0589074679 -0.0555614382 -0.0380272679 2119 1311867789.3252000809 0.0070621804 0.0215427196 0.0670038015 0.0045340099 0.0485690000 413532933 0 402718720 -0.0612646416 -0.0543776937 -0.0365899540 2120 1311867789.3589100838 0.0060782433 0.0215354250 0.0670038015 0.0045332479 0.0377590000 413536033 0 402718720 -0.0618813075 -0.0546481535 -0.0391694829 2121 1311867789.3897531033 0.0064768312 0.0215283252 0.0670038015 0.0045324394 0.0473900000 414115357 0 402718720 -0.0603451133 -0.0546762310 -0.0398125164 2122 1311867789.4252359867 0.0078667579 0.0215218872 0.0670038015 0.0045326795 0.1197920000 414048425 0 402718720 -0.0627895445 -0.0543471500 -0.0369546451 2123 1311867789.4577910900 0.0081670601 0.0215155966 0.0670038015 0.0045316220 0.1130070000 414299925 0 402718720 -0.0632491112 -0.0539996438 -0.0375531912 2124 1311867789.4892559052 0.0070329476 0.0215087781 0.0670038015 0.0045305973 0.1000550000 421285717 0 402718720 -0.0637528151 -0.0544911399 -0.0394291990 2125 1311867789.5256059170 0.0073787454 0.0215021286 0.0670038015 0.0045297848 0.0593490000 424693033 0 402718720 -0.0638612062 -0.0548171885 -0.0389774740 2126 1311867789.5572779179 0.0066696517 0.0214951519 0.0670038015 0.0045287335 0.0980560000 424418949 0 402718720 -0.0655545741 -0.0568553805 -0.0381094068 2127 1311867789.5892720222 0.0072080856 0.0214884349 0.0670038015 0.0045279341 0.1097730000 423027273 0 402718720 -0.0659193322 -0.0548562035 -0.0400338359 2128 1311867789.6253700256 0.0065836417 0.0214814308 0.0670038015 0.0045268827 0.0552300000 414065177 0 402718720 -0.0670828670 -0.0554524139 -0.0401352681 2129 1311867789.6574499607 0.0059838262 0.0214741515 0.0670038015 0.0045259335 0.0397420000 414068149 0 402718720 -0.0667063296 -0.0558222830 -0.0411785915 2130 1311867789.6894960403 0.0074657709 0.0214675748 0.0670038015 0.0045252643 0.0382530000 414071193 0 402718720 -0.0687732249 -0.0548196584 -0.0393274464 2131 1311867789.7253561020 0.0084667187 0.0214614740 0.0670038015 0.0045255305 0.0494820000 414074261 0 402718720 -0.0671662688 -0.0528404452 -0.0409609154 2132 1311867789.7572269440 0.0078681260 0.0214550981 0.0670038015 0.0045245207 0.0467670000 414077665 0 402718720 -0.0682162791 -0.0526984148 -0.0415700860 2133 1311867789.7893610001 0.0069998549 0.0214483212 0.0670038015 0.0045245797 0.0498480000 414080685 0 402718720 -0.0697627813 -0.0536464229 -0.0401843116 2134 1311867789.8253350258 0.0053554601 0.0214407800 0.0670038015 0.0045238707 0.0516660000 414084089 0 402718720 -0.0705138072 -0.0545988008 -0.0410056934 2135 1311867789.8573670387 0.0059633260 0.0214335306 0.0670038015 0.0045231371 0.0385470000 414087245 0 402718720 -0.0709396675 -0.0538047440 -0.0405766740 2136 1311867789.8893530369 0.0074440720 0.0214269812 0.0670038015 0.0045221603 0.0380930000 414090081 0 402718720 -0.0710484460 -0.0522482470 -0.0400281511 2137 1311867789.9253480434 0.0067805159 0.0214201275 0.0670038015 0.0045217602 0.0385710000 414093565 0 402718720 -0.0716653764 -0.0526589975 -0.0404480807 2138 1311867789.9573481083 0.0074684019 0.0214136019 0.0670038015 0.0045216223 0.0371730000 414096657 0 402718720 -0.0732752830 -0.0519853868 -0.0393701605 2139 1311867789.9892580509 0.0058160117 0.0214063099 0.0670038015 0.0045234757 0.0492300000 414100141 0 402718720 -0.0738902315 -0.0526865944 -0.0412898995 2140 1311867790.0253860950 0.0056468337 0.0213989456 0.0670038015 0.0045224865 0.0386080000 414103201 0 402718720 -0.0747544020 -0.0528968610 -0.0406038426 2141 1311867790.0572309494 0.0063092969 0.0213918977 0.0670038015 0.0045214968 0.0370680000 414106357 0 402718720 -0.0746441856 -0.0518863648 -0.0416643843 2142 1311867790.0896899700 0.0056618471 0.0213845541 0.0670038015 0.0045208118 0.0373800000 414109625 0 402718720 -0.0760503113 -0.0518861450 -0.0410637744 2143 1311867790.1257700920 0.0065899775 0.0213776504 0.0670038015 0.0045201397 0.0371710000 414112821 0 402718720 -0.0767577663 -0.0508492142 -0.0397612341 2144 1311867790.1572160721 0.0068847225 0.0213708906 0.0670038015 0.0045191651 0.0370470000 414115977 0 402718720 -0.0774094909 -0.0501253940 -0.0398294702 2145 1311867790.1894400120 0.0053378637 0.0213634160 0.0670038015 0.0045183256 0.0470620000 414119181 0 402718720 -0.0784465820 -0.0511605218 -0.0404520482 2146 1311867790.2254109383 0.0052372967 0.0213559015 0.0670038015 0.0045177763 0.0371400000 414122153 0 402718720 -0.0788613930 -0.0509058945 -0.0412144512 2147 1311867790.2576739788 0.0059870509 0.0213487432 0.0670038015 0.0045171838 0.0382620000 414125757 0 402718720 -0.0794777572 -0.0502871685 -0.0395046026 2148 1311867790.2894508839 0.0051781409 0.0213412150 0.0670038015 0.0045166892 0.0366240000 414128721 0 402718720 -0.0797102228 -0.0508586988 -0.0395436138 2149 1311867790.3254859447 0.0067482297 0.0213344244 0.0670038015 0.0045163918 0.0368710000 414131901 0 402718720 -0.0803981200 -0.0496628322 -0.0382469296 2150 1311867790.3573629856 0.0060946508 0.0213273362 0.0670038015 0.0045169246 0.0366590000 414135193 0 402718720 -0.0802415088 -0.0502172299 -0.0389217138 2151 1311867790.3896288872 0.0065720840 0.0213204764 0.0670038015 0.0045163792 0.0467490000 414138421 0 402718720 -0.0813427046 -0.0495091528 -0.0390581489 2152 1311867790.4259679317 0.0054095807 0.0213130829 0.0670038015 0.0045175545 0.0381090000 414141625 0 402718720 -0.0818138868 -0.0505964272 -0.0393952653 2153 1311867790.4603750706 0.0056546591 0.0213058101 0.0670038015 0.0045182227 0.0379370000 414144781 0 402718720 -0.0828066170 -0.0502044447 -0.0386889540 2154 1311867790.4893760681 0.0046732933 0.0212980884 0.0670038015 0.0045176395 0.0378310000 414148041 0 402718720 -0.0832526982 -0.0510523431 -0.0391299538 2155 1311867790.5260839462 0.0059060180 0.0212909459 0.0670038015 0.0045173831 0.0476910000 414151141 0 402718720 -0.0826928243 -0.0495050810 -0.0395818241 2156 1311867790.5578188896 0.0068412665 0.0212842438 0.0670038015 0.0045181037 0.0359090000 414154041 0 402718720 -0.0845220909 -0.0482009165 -0.0383332744 2157 1311867790.5941619873 0.0049764328 0.0212766834 0.0670038015 0.0045203113 0.0489040000 414157621 0 402718720 -0.0853605717 -0.0495457314 -0.0394864455 2158 1311867790.6255199909 0.0054233237 0.0212693371 0.0670038015 0.0045195394 0.0375150000 414160729 0 402718720 -0.0859421641 -0.0495939404 -0.0389491245 2159 1311867790.6573970318 0.0055253892 0.0212620448 0.0670038015 0.0045189638 0.0378790000 414163893 0 402718720 -0.0850317925 -0.0492263138 -0.0395926200 2160 1311867790.6901810169 0.0052547595 0.0212546340 0.0670038015 0.0045183204 0.0380310000 414167289 0 402718720 -0.0856824219 -0.0491661094 -0.0405263752 2161 1311867790.7253530025 0.0068462673 0.0212479666 0.0670038015 0.0045184368 0.0367320000 414170189 0 402718720 -0.0868522152 -0.0493719541 -0.0376353078 2162 1311867790.7575750351 0.0071244240 0.0212414340 0.0670038015 0.0045175486 0.0429090000 414720921 0 402718720 -0.0874782950 -0.0469691157 -0.0396716520 2163 1311867790.7912769318 0.0065269149 0.0212346311 0.0670038015 0.0045169872 0.1134660000 414713157 0 402718720 -0.0877642557 -0.0464480519 -0.0417251214 2164 1311867790.8261909485 0.0063710902 0.0212277626 0.0670038015 0.0045161053 0.1049060000 415003177 0 402718720 -0.0872211531 -0.0467944555 -0.0404421575 2165 1311867790.8573698997 0.0058989124 0.0212206823 0.0670038015 0.0045152318 0.1037680000 422202185 0 402718720 -0.0884392709 -0.0469970182 -0.0393530503 2166 1311867790.8950428963 0.0064379927 0.0212138574 0.0670038015 0.0045148371 0.0569710000 425700817 0 402718720 -0.0879427493 -0.0452169515 -0.0411943942 2167 1311867790.9258179665 0.0067874100 0.0212072001 0.0670038015 0.0045139108 0.0907170000 425472861 0 402718720 -0.0884582549 -0.0442054719 -0.0402898937 2168 1311867790.9607090950 0.0061224713 0.0212002422 0.0670038015 0.0045131357 0.0468710000 425607465 0 402718720 -0.0892960429 -0.0445007645 -0.0392257273 2169 1311867790.9944651127 0.0053921170 0.0211929540 0.0670038015 0.0045121921 0.1162970000 424207661 0 402718720 -0.0891484171 -0.0451717228 -0.0388218313 2170 1311867791.0299000740 0.0060849981 0.0211859918 0.0670038015 0.0045112263 0.0592430000 414730545 0 402718720 -0.0896168873 -0.0439503044 -0.0383115225 2171 1311867791.0577330589 0.0080845663 0.0211799570 0.0670038015 0.0045108753 0.0494680000 414733405 0 402718720 -0.0889655352 -0.0425974019 -0.0367717482 2172 1311867791.0913140774 0.0060715354 0.0211730010 0.0670038015 0.0045100735 0.0380620000 414736921 0 402718720 -0.0909050927 -0.0434736088 -0.0375053436 2173 1311867791.1254060268 0.0052227024 0.0211656608 0.0670038015 0.0045104917 0.0381880000 414740077 0 402718720 -0.0908436179 -0.0437971950 -0.0394212119 2174 1311867791.1664540768 0.0073161549 0.0211592903 0.0670038015 0.0045106413 0.0392230000 414743185 0 402718720 -0.0903528109 -0.0419354029 -0.0378515907 2175 1311867791.1905651093 0.0040610097 0.0211514290 0.0670038015 0.0045113708 0.0426480000 414746189 0 402718720 -0.0928834900 -0.0450158417 -0.0373960808 2176 1311867791.2257969379 0.0032796594 0.0211432159 0.0670038015 0.0045111692 0.0420710000 414749833 0 402718720 -0.0946433246 -0.0448015407 -0.0397211760 2177 1311867791.2579009533 0.0028114319 0.0211347952 0.0670038015 0.0045109339 0.0437720000 414752813 0 402718720 -0.0953927636 -0.0458182730 -0.0384861752 2178 1311867791.2920219898 0.0043867873 0.0211271056 0.0670038015 0.0045099596 0.0404600000 414755905 0 402718720 -0.0955747813 -0.0443555824 -0.0387874618 2179 1311867791.3277790546 0.0044624149 0.0211194577 0.0670038015 0.0045097383 0.0499810000 414759053 0 402718720 -0.0952244848 -0.0446993671 -0.0381871052 2180 1311867791.3597049713 0.0059288396 0.0211124896 0.0670038015 0.0045105081 0.0387530000 414762129 0 402718720 -0.0949162841 -0.0444745943 -0.0364738926 2181 1311867791.3896780014 0.0048775724 0.0211050458 0.0670038015 0.0045103348 0.0384310000 414765413 0 402718720 -0.0951403230 -0.0450287759 -0.0379994139 2182 1311867791.4270040989 0.0057773902 0.0210980212 0.0670038015 0.0045094394 0.0381150000 414768665 0 402718720 -0.0959086642 -0.0442651324 -0.0377537757 2183 1311867791.4574470520 0.0043306672 0.0210903403 0.0670038015 0.0045087359 0.0388740000 414771949 0 402718720 -0.0967897624 -0.0456221402 -0.0385713726 2184 1311867791.4916520119 0.0053317910 0.0210831248 0.0670038015 0.0045119574 0.0373290000 414775345 0 402718720 -0.0985334069 -0.0451141261 -0.0366247632 2185 1311867791.5275359154 0.0056054057 0.0210760412 0.0670038015 0.0045116113 0.0491680000 414778605 0 402718720 -0.0971427262 -0.0440357737 -0.0393523574 2186 1311867791.5593819618 0.0079364767 0.0210700304 0.0670038015 0.0045110877 0.0382100000 414781433 0 402718720 -0.0957313478 -0.0432619825 -0.0368205756 2187 1311867791.5894811153 0.0072757984 0.0210637231 0.0670038015 0.0045103774 0.0374990000 414784653 0 402718720 -0.0984975547 -0.0425101817 -0.0367226005 2188 1311867791.6275899410 0.0051653846 0.0210564569 0.0670038015 0.0045114834 0.0381560000 414787969 0 402718720 -0.0974520668 -0.0450729728 -0.0394706652 2189 1311867791.6574349403 0.0053472435 0.0210492805 0.0670038015 0.0045108698 0.0379930000 414791213 0 402718720 -0.0984707996 -0.0445301086 -0.0377095006 2190 1311867791.6894969940 0.0037864996 0.0210413979 0.0670038015 0.0045100624 0.0364120000 414794561 0 402718720 -0.0994819179 -0.0464933366 -0.0375260785 2191 1311867791.7263259888 0.0048673409 0.0210340159 0.0670038015 0.0045093187 0.0380110000 414797813 0 402718720 -0.1004979238 -0.0449150875 -0.0365209952 2192 1311867791.7602820396 0.0064235451 0.0210273505 0.0670038015 0.0045083680 0.0383040000 414800873 0 402718720 -0.0995211005 -0.0439686850 -0.0357976593 2193 1311867791.7897930145 0.0048706122 0.0210199831 0.0670038015 0.0045076227 0.0498120000 414803901 0 402718720 -0.1007941067 -0.0439572521 -0.0372998118 2194 1311867791.8265190125 0.0051277722 0.0210127396 0.0670038015 0.0045067684 0.0371100000 414807481 0 402718720 -0.1006720066 -0.0447712354 -0.0363024771 2195 1311867791.8574469090 0.0056358371 0.0210057342 0.0670038015 0.0045058619 0.0463150000 414810501 0 402718720 -0.1012246087 -0.0433048904 -0.0366846584 2196 1311867791.8895421028 0.0036751742 0.0209978423 0.0670038015 0.0045054483 0.0380260000 414813593 0 402718720 -0.1011389494 -0.0437957831 -0.0399563909 2197 1311867791.9276258945 0.0042834147 0.0209902345 0.0670038015 0.0045048586 0.0377390000 414816717 0 402718720 -0.1035842896 -0.0446161255 -0.0370840281 2198 1311867791.9574968815 0.0064756926 0.0209836310 0.0670038015 0.0045042094 0.0377940000 414819937 0 402718720 -0.1024519578 -0.0434145704 -0.0354719460 2199 1311867791.9918000698 0.0039957413 0.0209759057 0.0670038015 0.0045037526 0.0380020000 414822965 0 402718720 -0.1030377299 -0.0432585515 -0.0388291404 2200 1311867792.0277240276 0.0046265083 0.0209684741 0.0670038015 0.0045028993 0.0379810000 414825993 0 402718720 -0.1032254919 -0.0443376936 -0.0374013409 2201 1311867792.0615789890 0.0087754820 0.0209629344 0.0670038015 0.0045034673 0.0366660000 414829453 0 402718720 -0.1028267890 -0.0429118983 -0.0337967351 2202 1311867792.0946090221 0.0031206934 0.0209548316 0.0670038015 0.0045064588 0.0374130000 414832545 0 402718720 -0.1029768139 -0.0453337878 -0.0395120606 2203 1311867792.1256630421 0.0025293422 0.0209464678 0.0670038015 0.0045056162 0.0377170000 414835757 0 402718720 -0.1053060889 -0.0437012836 -0.0406080484 2204 1311867792.1595768929 0.0082933446 0.0209407268 0.0670038015 0.0045063395 0.0370450000 414838897 0 402718720 -0.1049272120 -0.0439999104 -0.0343106501 2205 1311867792.1948819160 0.0064387145 0.0209341500 0.0670038015 0.0045064506 0.0378990000 414842125 0 402718720 -0.1036372781 -0.0416766703 -0.0386229381 2206 1311867792.2253580093 0.0034049023 0.0209262038 0.0670038015 0.0045173764 0.0451250000 415367693 0 402718720 -0.1045362428 -0.0434139669 -0.0405649990 2207 1311867792.2575860023 0.0058533391 0.0209193742 0.0670038015 0.0045173330 0.1198260000 415339317 0 402718720 -0.1055310220 -0.0432061292 -0.0377203487 2208 1311867792.2995440960 0.0061941976 0.0209127052 0.0670038015 0.0045163700 0.1089740000 415342337 0 402718720 -0.1074136868 -0.0428519994 -0.0373766795 2209 1311867792.3314530849 0.0044236956 0.0209052408 0.0670038015 0.0045174570 0.1011030000 421175713 0 402718720 -0.1057820022 -0.0435365401 -0.0400435552 2210 1311867792.3589100838 0.0040442846 0.0208976114 0.0670038015 0.0045165238 0.0688460000 426400605 0 402718720 -0.1069203615 -0.0431247205 -0.0403250940 2211 1311867792.3954761028 0.0072831619 0.0208914538 0.0670038015 0.0045162753 0.0834560000 426363769 0 402718720 -0.1064361259 -0.0426231697 -0.0375322066 2212 1311867792.4281890392 0.0065755164 0.0208849818 0.0670038015 0.0045159277 0.0463600000 426299969 0 402718720 -0.1056450382 -0.0422534645 -0.0396474674 2213 1311867792.4589219093 0.0043236460 0.0208774982 0.0670038015 0.0045153148 0.1153310000 424896785 0 402718720 -0.1074206084 -0.0444194749 -0.0410720482 2214 1311867792.4948880672 0.0055173757 0.0208705604 0.0670038015 0.0045146230 0.0757200000 415188069 0 402718720 -0.1083364412 -0.0441773348 -0.0397604108 2215 1311867792.5256149769 0.0074086431 0.0208644828 0.0670038015 0.0045139269 0.0390080000 415191057 0 402718720 -0.1078168228 -0.0428549796 -0.0385944434 2216 1311867792.5579619408 0.0057127997 0.0208576454 0.0670038015 0.0045138248 0.0501400000 415194789 0 402718720 -0.1088088602 -0.0445606001 -0.0401313640 2217 1311867792.5937440395 0.0064647160 0.0208511533 0.0670038015 0.0045133990 0.0376330000 415197545 0 402718720 -0.1096890047 -0.0433591940 -0.0394438989 2218 1311867792.6254990101 0.0062971306 0.0208445916 0.0670038015 0.0045125574 0.0488280000 415200797 0 402718720 -0.1093708426 -0.0438515469 -0.0403339379 2219 1311867792.6587610245 0.0058219624 0.0208378216 0.0670038015 0.0045116619 0.0366060000 415204209 0 402718720 -0.1113126799 -0.0431557037 -0.0408038460 2220 1311867792.6947619915 0.0056903223 0.0208309984 0.0670038015 0.0045107286 0.0441970000 415749013 0 402718720 -0.1124107912 -0.0442472771 -0.0409860946 2221 1311867792.7254660130 0.0062641832 0.0208244397 0.0670038015 0.0045109404 0.1188930000 415732313 0 402718720 -0.1120908856 -0.0440000817 -0.0407407135 2222 1311867792.7574810982 0.0054364512 0.0208175144 0.0670038015 0.0045109841 0.1117080000 415735001 0 402718720 -0.1118871495 -0.0445926301 -0.0417420045 2223 1311867792.7968890667 0.0060967738 0.0208108924 0.0670038015 0.0045108916 0.1005980000 421563373 0 402718720 -0.1129973903 -0.0429103076 -0.0412580073 2224 1311867792.8254449368 0.0063768877 0.0208044023 0.0670038015 0.0045101231 0.0596600000 425619133 0 402718720 -0.1143576801 -0.0446095355 -0.0408949517 2225 1311867792.8578031063 0.0059506870 0.0207977265 0.0670038015 0.0045107436 0.0623810000 425409041 0 402718720 -0.1130857468 -0.0450095758 -0.0415419601 2226 1311867792.8974819183 0.0084422072 0.0207921759 0.0670038015 0.0045106612 0.1170840000 424040117 0 402718720 -0.1143459976 -0.0435617678 -0.0389199629 2227 1311867792.9254279137 0.0088468203 0.0207868120 0.0670038015 0.0045097932 0.0555890000 415704625 0 402718720 -0.1153037250 -0.0427372344 -0.0386686660 2228 1311867792.9580180645 0.0076704351 0.0207809250 0.0670038015 0.0045092286 0.0378190000 415707957 0 402718720 -0.1150192618 -0.0428721271 -0.0401477814 2229 1311867792.9958879948 0.0085048703 0.0207754175 0.0670038015 0.0045086006 0.0370700000 415710889 0 402718720 -0.1163202822 -0.0427016951 -0.0392695293 2230 1311867793.0254249573 0.0073997122 0.0207694195 0.0670038015 0.0045078662 0.0475600000 415714117 0 402718720 -0.1168010831 -0.0435590409 -0.0404510088 2231 1311867793.0575890541 0.0081595434 0.0207637673 0.0670038015 0.0045070490 0.0379100000 415717233 0 402718720 -0.1173600107 -0.0444018655 -0.0398565046 2232 1311867793.0956139565 0.0069438354 0.0207575756 0.0670038015 0.0045066118 0.0442000000 416208501 0 402718720 -0.1194324493 -0.0447472632 -0.0411343016 2233 1311867793.1253910065 0.0076189726 0.0207516918 0.0670038015 0.0045057314 0.1141610000 416178437 0 402718720 -0.1198629662 -0.0440799892 -0.0403729565 2234 1311867793.1573770046 0.0093251374 0.0207465769 0.0670038015 0.0045048151 0.1150420000 416446485 0 402718720 -0.1175306290 -0.0421151221 -0.0394873768 2235 1311867793.1934790611 0.0111765796 0.0207422951 0.0670038015 0.0045040430 0.1101200000 423451169 0 402718720 -0.1179978326 -0.0437397659 -0.0377588794 2236 1311867793.2255470753 0.0096624140 0.0207373398 0.0670038015 0.0045036189 0.0778020000 425376513 0 402718720 -0.1193479747 -0.0435088649 -0.0391713083 2237 1311867793.2574770451 0.0110962503 0.0207330300 0.0670038015 0.0045028148 0.0459570000 425854777 0 402718720 -0.1180975065 -0.0428919345 -0.0383314565 2238 1311867793.2951428890 0.0125530642 0.0207293750 0.0670038015 0.0045026311 0.1084240000 424468133 0 402718720 -0.1202844977 -0.0436001159 -0.0362834856 2239 1311867793.3254458904 0.0122476639 0.0207255868 0.0670038015 0.0045025095 0.0516480000 416196485 0 402718720 -0.1204835698 -0.0434037633 -0.0366399586 2240 1311867793.3620529175 0.0097003812 0.0207206648 0.0670038015 0.0045036842 0.0383770000 416199481 0 402718720 -0.1200940534 -0.0438514166 -0.0401472747 2241 1311867793.3934969902 0.0123579130 0.0207169331 0.0670038015 0.0045044760 0.0484720000 416202589 0 402718720 -0.1207685396 -0.0422748663 -0.0368102118 2242 1311867793.4254410267 0.0121837268 0.0207131271 0.0670038015 0.0045039406 0.0362590000 416205801 0 402718720 -0.1208772138 -0.0435267016 -0.0371369272 2243 1311867793.4615969658 0.0107408576 0.0207086811 0.0670038015 0.0045040040 0.0365390000 416208997 0 402718720 -0.1207377762 -0.0434497595 -0.0389577821 2244 1311867793.4961650372 0.0138544533 0.0207056266 0.0670038015 0.0045041108 0.0373270000 416212345 0 402718720 -0.1207662001 -0.0422871187 -0.0351684764 2245 1311867793.5258960724 0.0144034019 0.0207028194 0.0670038015 0.0045032325 0.0375300000 416215181 0 402718720 -0.1220904887 -0.0424043462 -0.0340620019 2246 1311867793.5653350353 0.0136867156 0.0206996956 0.0670038015 0.0045025307 0.0375810000 416218521 0 402718720 -0.1224334091 -0.0424272418 -0.0347884409 2247 1311867793.5951368809 0.0115224039 0.0206956114 0.0670038015 0.0045019378 0.0375350000 416221821 0 402718720 -0.1238400936 -0.0421948135 -0.0366859175 2248 1311867793.6255569458 0.0160539243 0.0206935465 0.0670038015 0.0045038968 0.0433690000 416712429 0 402718720 -0.1225980446 -0.0403447226 -0.0322600231 2249 1311867793.6641399860 0.0143187605 0.0206907121 0.0670038015 0.0045032771 0.1092940000 416681149 0 402718720 -0.1237384900 -0.0394919142 -0.0336468257 2250 1311867793.6930859089 0.0139529584 0.0206877175 0.0670038015 0.0045031916 0.1026620000 416941641 0 402718720 -0.1233953685 -0.0388069749 -0.0345763117 2251 1311867793.7268340588 0.0145672606 0.0206849985 0.0670038015 0.0045033773 0.1011480000 424367525 0 402718720 -0.1238958910 -0.0387692377 -0.0335786641 2252 1311867793.7666549683 0.0145664541 0.0206822816 0.0670038015 0.0045025495 0.0535940000 426594213 0 402718720 -0.1235068962 -0.0386306681 -0.0343004093 2253 1311867793.7944359779 0.0130258659 0.0206788832 0.0670038015 0.0045027007 0.0507530000 426416441 0 402718720 -0.1240801811 -0.0374178886 -0.0358596742 2254 1311867793.8265230656 0.0144828232 0.0206761343 0.0670038015 0.0045025065 0.1043160000 425194789 0 402718720 -0.1252430230 -0.0371619239 -0.0339016467 2255 1311867793.8667359352 0.0145636033 0.0206734237 0.0670038015 0.0045021339 0.0373410000 416698145 0 402718720 -0.1268357486 -0.0368977152 -0.0336073823 2256 1311867793.8930900097 0.0155643951 0.0206711590 0.0670038015 0.0045012233 0.0370350000 416700869 0 402718720 -0.1255700290 -0.0356924981 -0.0331248567 2257 1311867793.9269030094 0.0143601438 0.0206683628 0.0670038015 0.0045003111 0.0363540000 416704137 0 402718720 -0.1262602955 -0.0349642448 -0.0343678296 2258 1311867793.9623370171 0.0143632991 0.0206655705 0.0670038015 0.0044994560 0.0560490000 416707173 0 402718720 -0.1273623407 -0.0358711518 -0.0341364332 2259 1311867793.9955279827 0.0130794570 0.0206622123 0.0670038015 0.0044984945 0.0373720000 416710449 0 402718720 -0.1285997331 -0.0347192585 -0.0351070166 2260 1311867794.0277070999 0.0127135795 0.0206586952 0.0670038015 0.0044980792 0.0432390000 417184885 0 402718720 -0.1279279590 -0.0353535414 -0.0360332727 2261 1311867794.0608921051 0.0108811781 0.0206543708 0.0670038015 0.0044975133 0.1092910000 417163625 0 402718720 -0.1267599612 -0.0341398753 -0.0391227640 2262 1311867794.0951509476 0.0116196107 0.0206503767 0.0670038015 0.0044971091 0.1013090000 420609145 0 402718720 -0.1273901612 -0.0321903229 -0.0375576876 2263 1311867794.1269369125 0.0140819950 0.0206474742 0.0670038015 0.0044984672 0.0756120000 427498733 0 402718720 -0.1267978698 -0.0305976048 -0.0348158628 2264 1311867794.1632831097 0.0089514283 0.0206423081 0.0670038015 0.0044985425 0.0858300000 427277545 0 402718720 -0.1289390177 -0.0299398378 -0.0392291956 2265 1311867794.1936271191 0.0104393028 0.0206378034 0.0670038015 0.0044981959 0.0456770000 427406661 0 402718720 -0.1280287206 -0.0286713894 -0.0374965370 2266 1311867794.2258520126 0.0074631032 0.0206319893 0.0670038015 0.0044977045 0.1121510000 426045601 0 402718720 -0.1301681697 -0.0282306150 -0.0392790288 2267 1311867794.2619779110 0.0083307372 0.0206265631 0.0670038015 0.0044969270 0.0511510000 417149109 0 402718720 -0.1288708299 -0.0270641185 -0.0391460657 2268 1311867794.2955250740 0.0097469846 0.0206217661 0.0670038015 0.0044960787 0.0474590000 417152321 0 402718720 -0.1273299903 -0.0270520318 -0.0385049917 2269 1311867794.3254759312 0.0104296869 0.0206172742 0.0670038015 0.0044966370 0.0361270000 417155157 0 402718720 -0.1295079142 -0.0253613368 -0.0351040289 2270 1311867794.3628959656 0.0088571310 0.0206120936 0.0670038015 0.0044958664 0.0363380000 417158409 0 402718720 -0.1298421323 -0.0248937868 -0.0367576331 2271 1311867794.3958311081 0.0071093258 0.0206061478 0.0670038015 0.0044958390 0.0457080000 417677441 0 402718720 -0.1303104162 -0.0249363631 -0.0396207683 2272 1311867794.4267809391 0.0080151996 0.0206006060 0.0670038015 0.0044950308 0.1133630000 417643925 0 402718720 -0.1303149909 -0.0235836133 -0.0382164419 2273 1311867794.4620559216 0.0083854180 0.0205952320 0.0670038015 0.0044942047 0.1113680000 417669993 0 402718720 -0.1308311671 -0.0215528421 -0.0374404006 2274 1311867794.4987208843 0.0077314228 0.0205895751 0.0670038015 0.0044936591 0.0844210000 428308865 0 402718720 -0.1315491498 -0.0228390042 -0.0380000696 2275 1311867794.5290880203 0.0080899401 0.0205840808 0.0670038015 0.0044937949 0.0905980000 428078405 0 402718720 -0.1337133795 -0.0218327548 -0.0357561819 2276 1311867794.5637059212 0.0088507645 0.0205789255 0.0670038015 0.0044932516 0.0463590000 428210289 0 402718720 -0.1343562454 -0.0212227330 -0.0350134447 2277 1311867794.5940639973 0.0080981851 0.0205734443 0.0670038015 0.0044925998 0.1149660000 426879157 0 402718720 -0.1343633682 -0.0202863440 -0.0363715254 2278 1311867794.6319000721 0.0075100893 0.0205677097 0.0670038015 0.0044919452 0.0558590000 417617965 0 402718720 -0.1355574131 -0.0201806184 -0.0363478549 2279 1311867794.6658101082 0.0105194990 0.0205633007 0.0670038015 0.0044913125 0.0387820000 417621169 0 402718720 -0.1340476274 -0.0203647688 -0.0340634435 2280 1311867794.6949920654 0.0098036267 0.0205585815 0.0670038015 0.0044916483 0.0373900000 417624325 0 402718720 -0.1338734925 -0.0198737923 -0.0354227982 2281 1311867794.7305591106 0.0075726537 0.0205528884 0.0670038015 0.0044916564 0.0370290000 417627585 0 402718720 -0.1350380927 -0.0201904140 -0.0376402065 2282 1311867794.7625899315 0.0096050641 0.0205480910 0.0670038015 0.0044910715 0.0385670000 417630741 0 402718720 -0.1349096149 -0.0194775276 -0.0347424336 2283 1311867794.7959010601 0.0103282910 0.0205436145 0.0670038015 0.0044911273 0.0381680000 417633817 0 402718720 -0.1354072094 -0.0176781099 -0.0336705409 2284 1311867794.8306028843 0.0108839972 0.0205393852 0.0670038015 0.0044902641 0.0379220000 417636765 0 402718720 -0.1370467544 -0.0176804550 -0.0324923620 2285 1311867794.8631660938 0.0105979582 0.0205350345 0.0670038015 0.0044895984 0.0377660000 417640201 0 402718720 -0.1357913166 -0.0171318483 -0.0339131877 2286 1311867794.8947780132 0.0107398722 0.0205307497 0.0670038015 0.0044895665 0.0382310000 417643157 0 402718720 -0.1343129277 -0.0180744883 -0.0357513800 2287 1311867794.9343950748 0.0120751923 0.0205270524 0.0670038015 0.0044898800 0.0380190000 417646785 0 402718720 -0.1363306940 -0.0162621345 -0.0330376029 2288 1311867794.9646499157 0.0105619123 0.0205226970 0.0670038015 0.0044891574 0.0364460000 417649941 0 402718720 -0.1372042000 -0.0157025568 -0.0345079117 2289 1311867794.9988350868 0.0106955543 0.0205184038 0.0670038015 0.0044884852 0.0363760000 417653201 0 402718720 -0.1367007047 -0.0152968857 -0.0348254330 2290 1311867795.0307559967 0.0109321997 0.0205142177 0.0670038015 0.0044876309 0.0364210000 417656101 0 402718720 -0.1361810416 -0.0144470995 -0.0351862274 2291 1311867795.0651550293 0.0100243473 0.0205096390 0.0670038015 0.0044869611 0.0469620000 418172033 0 402718720 -0.1388167590 -0.0124980938 -0.0345534235 2292 1311867795.0993340015 0.0100877397 0.0205050919 0.0670038015 0.0044868032 0.1353660000 418129221 0 402718720 -0.1374807060 -0.0127387205 -0.0357713439 2293 1311867795.1310648918 0.0101475567 0.0205005749 0.0670038015 0.0044858947 0.1233890000 418389901 0 402718720 -0.1374942213 -0.0128156850 -0.0360047594 2294 1311867795.1630289555 0.0124022253 0.0204970447 0.0670038015 0.0044863222 0.1240550000 427053065 0 402718720 -0.1377893835 -0.0116910674 -0.0332637355 2295 1311867795.1945760250 0.0119260959 0.0204933100 0.0670038015 0.0044859445 0.0745740000 428820229 0 402718720 -0.1384939104 -0.0120285647 -0.0339821689 2296 1311867795.2313210964 0.0101314876 0.0204887970 0.0670038015 0.0044852751 0.0759520000 428532701 0 402718720 -0.1400024742 -0.0118432045 -0.0356909521 2297 1311867795.2631359100 0.0122720273 0.0204852199 0.0670038015 0.0044848736 0.1380370000 427192089 0 402718720 -0.1396593601 -0.0108004799 -0.0338264033 2298 1311867795.2958068848 0.0135380933 0.0204821968 0.0670038015 0.0044843891 0.0584690000 418143805 0 402718720 -0.1415804178 -0.0111123025 -0.0320914499 2299 1311867795.3314220905 0.0115900300 0.0204783289 0.0670038015 0.0044841775 0.0390750000 418146753 0 402718720 -0.1410390139 -0.0107851271 -0.0347510166 2300 1311867795.3670549393 0.0113403210 0.0204743559 0.0670038015 0.0044834561 0.0444880000 418652037 0 402718720 -0.1404474229 -0.0107258381 -0.0355955772 2301 1311867795.3950240612 0.0138587588 0.0204714808 0.0670038015 0.0044835130 0.1138340000 418617185 0 402718720 -0.1402653605 -0.0090577686 -0.0323516577 2302 1311867795.4294250011 0.0106062554 0.0204671953 0.0670038015 0.0044855507 0.1088200000 418898665 0 402718720 -0.1396306306 -0.0101568867 -0.0364005268 2303 1311867795.4614660740 0.0110151600 0.0204630910 0.0670038015 0.0044853700 0.0983530000 424870157 0 402718720 -0.1388455331 -0.0092437603 -0.0369908363 2304 1311867795.4961009026 0.0129398257 0.0204598257 0.0670038015 0.0044850574 0.0590870000 429443077 0 402718720 -0.1381540000 -0.0071574999 -0.0345397703 2305 1311867795.5292580128 0.0100647658 0.0204553159 0.0670038015 0.0044842032 0.0718470000 429210965 0 402718720 -0.1408631355 -0.0076332269 -0.0358677208 2306 1311867795.5632829666 0.0098370947 0.0204507113 0.0670038015 0.0044852153 0.0455490000 429343977 0 402718720 -0.1390167475 -0.0086426334 -0.0378770232 2307 1311867795.5938069820 0.0085963123 0.0204455729 0.0670038015 0.0044855102 0.1057890000 427958497 0 402718720 -0.1403271109 -0.0055649038 -0.0368089639 2308 1311867795.6295180321 0.0109594949 0.0204414628 0.0670038015 0.0044847092 0.0490690000 418635733 0 402718720 -0.1401228309 -0.0046891272 -0.0334743261 2309 1311867795.6619150639 0.0102937324 0.0204370679 0.0670038015 0.0044852033 0.0380460000 418638697 0 402718720 -0.1377162188 -0.0042080441 -0.0356068686 2310 1311867795.6935899258 0.0097322837 0.0204324338 0.0670038015 0.0044845252 0.0449580000 419162017 0 402718720 -0.1379074752 -0.0011545890 -0.0352713689 2311 1311867795.7300128937 0.0084550017 0.0204272511 0.0670038015 0.0044840771 0.1169130000 419124153 0 402718720 -0.1378549188 -0.0009923796 -0.0365182012 2312 1311867795.7627360821 0.0086138556 0.0204221414 0.0670038015 0.0044831722 0.1063260000 419126733 0 402718720 -0.1377219260 0.0003970494 -0.0356715545 2313 1311867795.7993569374 0.0123595418 0.0204186557 0.0670038015 0.0044834840 0.1028520000 424419389 0 402718720 -0.1358219087 0.0007627420 -0.0318955518 2314 1311867795.8297359943 0.0122367637 0.0204151199 0.0670038015 0.0044825797 0.0561120000 430261561 0 402718720 -0.1364264786 0.0007960754 -0.0313912332 2315 1311867795.8630819321 0.0108246543 0.0204109771 0.0670038015 0.0044818169 0.0828190000 430025789 0 402718720 -0.1370264590 0.0020658760 -0.0323210694 2316 1311867795.9011631012 0.0107803140 0.0204068188 0.0670038015 0.0044810115 0.0478010000 430163473 0 402718720 -0.1373556405 0.0029995497 -0.0321733579 2317 1311867795.9300799370 0.0132577410 0.0204037333 0.0670038015 0.0044801993 0.1140090000 428796405 0 402718720 -0.1366322190 0.0032299468 -0.0298561975 2318 1311867795.9624390602 0.0099515608 0.0203992242 0.0670038015 0.0044798896 0.0653640000 419102945 0 402718720 -0.1384688467 0.0020534596 -0.0329069868 2319 1311867796.0000178814 0.0091472268 0.0203943721 0.0670038015 0.0044791588 0.0376140000 419106381 0 402718720 -0.1395666003 0.0013312907 -0.0336038396 2320 1311867796.0296399593 0.0104087926 0.0203900679 0.0670038015 0.0044782709 0.0477600000 419109633 0 402718720 -0.1369005144 0.0029987018 -0.0333807915 2321 1311867796.0617599487 0.0115603805 0.0203862637 0.0670038015 0.0044774802 0.0368160000 419112765 0 402718720 -0.1360896379 0.0032409634 -0.0323840529 2322 1311867796.0984148979 0.0099548008 0.0203817712 0.0670038015 0.0044768650 0.0511070000 419116089 0 402718720 -0.1361329854 0.0043343971 -0.0341038220 2323 1311867796.1296660900 0.0104034254 0.0203774758 0.0670038015 0.0044764862 0.0365110000 419119077 0 402718720 -0.1375690848 0.0030581155 -0.0326462761 2324 1311867796.1618049145 0.0102612181 0.0203731228 0.0670038015 0.0044757923 0.0385830000 419122409 0 402718720 -0.1380763650 0.0046919300 -0.0322195254 2325 1311867796.1990590096 0.0107511962 0.0203689844 0.0670038015 0.0044754724 0.0379600000 419125621 0 402718720 -0.1356011629 0.0045045284 -0.0329821520 2326 1311867796.2292931080 0.0111304894 0.0203650125 0.0670038015 0.0044747949 0.0378530000 419128897 0 402718720 -0.1357454062 0.0055817496 -0.0321190022 2327 1311867796.2631280422 0.0107427221 0.0203608775 0.0670038015 0.0044742155 0.0372290000 419132293 0 402718720 -0.1352262646 0.0042603491 -0.0329743698 2328 1311867796.3010690212 0.0105746491 0.0203566738 0.0670038015 0.0044739314 0.0749390000 419136073 0 402718720 -0.1356396228 0.0060138735 -0.0323802046 2329 1311867796.3299860954 0.0099714454 0.0203522147 0.0670038015 0.0044731943 0.0367000000 419138717 0 402718720 -0.1347492039 0.0054998491 -0.0333919860 2330 1311867796.3619849682 0.0124524161 0.0203488242 0.0670038015 0.0044723213 0.0370450000 419141913 0 402718720 -0.1325389296 0.0056270440 -0.0316104814 2331 1311867796.3998959064 0.0107554086 0.0203447086 0.0670038015 0.0044716752 0.0464120000 419653121 0 402718720 -0.1334090531 0.0044074892 -0.0327331536 2332 1311867796.4297831059 0.0104369260 0.0203404600 0.0670038015 0.0044711654 0.1110230000 419608261 0 402718720 -0.1333660632 0.0064400448 -0.0325402617 2333 1311867796.4618980885 0.0111972624 0.0203365409 0.0670038015 0.0044703948 0.1076520000 419610217 0 402718720 -0.1329140961 0.0066528390 -0.0315865837 2334 1311867796.5018439293 0.0107201329 0.0203324208 0.0670038015 0.0044694446 0.1023500000 424293689 0 402718720 -0.1338418126 0.0056945509 -0.0312499963 2335 1311867796.5301249027 0.0104642780 0.0203281946 0.0670038015 0.0044690975 0.0816340000 430576233 0 402718720 -0.1329242438 0.0044366042 -0.0321018174 2336 1311867796.5621480942 0.0118950661 0.0203245845 0.0670038015 0.0044689707 0.0929830000 430340217 0 402718720 -0.1328720450 0.0055519482 -0.0298608355 2337 1311867796.6018888950 0.0121903364 0.0203211039 0.0670038015 0.0044680492 0.0467300000 430475165 0 402718720 -0.1309809238 0.0059532006 -0.0302640460 2338 1311867796.6323978901 0.0104383780 0.0203168769 0.0670038015 0.0044673313 0.1127360000 428572017 0 402718720 -0.1332585514 0.0067111026 -0.0303655360 2339 1311867796.6659901142 0.0134479618 0.0203139402 0.0670038015 0.0044666738 0.0509900000 419542165 0 402718720 -0.1309874952 0.0070732972 -0.0276790541 2340 1311867796.7025029659 0.0141031491 0.0203112860 0.0670038015 0.0044658011 0.0374390000 419545481 0 402718720 -0.1289558858 0.0068544443 -0.0272724107 2341 1311867796.7335898876 0.0097798556 0.0203067873 0.0670038015 0.0044663133 0.0376770000 419548789 0 402718720 -0.1305935830 0.0066696568 -0.0301986728 2342 1311867796.7634348869 0.0084280195 0.0203017153 0.0670038015 0.0044655130 0.0370040000 419551929 0 402718720 -0.1291291863 0.0071007595 -0.0318399519 2343 1311867796.7990939617 0.0106000360 0.0202975746 0.0670038015 0.0044656693 0.0507180000 419555333 0 402718720 -0.1277411133 0.0070826844 -0.0287848637 2344 1311867796.8303010464 0.0099936584 0.0202931787 0.0670038015 0.0044647490 0.0365290000 419558489 0 402718720 -0.1273189187 0.0076250387 -0.0285046864 2345 1311867796.8626410961 0.0099857468 0.0202887832 0.0670038015 0.0044639353 0.0380450000 419561653 0 402718720 -0.1261238307 0.0079775732 -0.0282441303 2346 1311867796.8988420963 0.0098109115 0.0202843169 0.0670038015 0.0044631175 0.0364240000 419564841 0 402718720 -0.1258481294 0.0089528225 -0.0272454508 2347 1311867796.9308090210 0.0109933056 0.0202803582 0.0670038015 0.0044630324 0.0376050000 419568253 0 402718720 -0.1239550561 0.0081738010 -0.0260919426 2348 1311867796.9623529911 0.0091533558 0.0202756193 0.0670038015 0.0044624355 0.0367790000 419571153 0 402718720 -0.1261713356 0.0091645904 -0.0260363929 2349 1311867796.9994709492 0.0096061276 0.0202710772 0.0670038015 0.0044615840 0.0381460000 419574917 0 402718720 -0.1243559793 0.0076804026 -0.0257894881 2350 1311867797.0328159332 0.0105367349 0.0202669349 0.0670038015 0.0044609705 0.0369020000 419577761 0 402718720 -0.1237042546 0.0091401534 -0.0244537089 2351 1311867797.0733079910 0.0104621276 0.0202627644 0.0670038015 0.0044603302 0.0483020000 419581109 0 402718720 -0.1230318248 0.0084426729 -0.0237224810 2352 1311867797.0992720127 0.0094469618 0.0202581659 0.0670038015 0.0044601251 0.0469570000 419584345 0 402718720 -0.1225948036 0.0072605466 -0.0245033745 2353 1311867797.1336839199 0.0096706925 0.0202536663 0.0670038015 0.0044597112 0.0466940000 419587469 0 402718720 -0.1211785451 0.0084245652 -0.0243860856 2354 1311867797.1708030701 0.0109552089 0.0202497162 0.0670038015 0.0044589131 0.0385970000 419590737 0 402718720 -0.1199812591 0.0089102853 -0.0223745033 2355 1311867797.1996591091 0.0105317049 0.0202455897 0.0670038015 0.0044592195 0.0383920000 419593925 0 402718720 -0.1180951372 0.0080547519 -0.0243785102 2356 1311867797.2372090816 0.0105365822 0.0202414687 0.0670038015 0.0044607728 0.0383060000 419597481 0 402718720 -0.1196304485 0.0089921197 -0.0203907639 2357 1311867797.2708179951 0.0104351528 0.0202373082 0.0670038015 0.0044602101 0.0366680000 419600685 0 402718720 -0.1205042154 0.0095486473 -0.0188665465 2358 1311867797.3019850254 0.0092970151 0.0202326686 0.0670038015 0.0044600690 0.0382900000 419603825 0 402718720 -0.1199375540 0.0100617390 -0.0200074054 2359 1311867797.3296120167 0.0087692607 0.0202278091 0.0670038015 0.0044598581 0.0493780000 419607053 0 402718720 -0.1190879866 0.0088126017 -0.0209231377 2360 1311867797.3703179359 0.0082858410 0.0202227490 0.0670038015 0.0044591093 0.0365440000 419610481 0 402718720 -0.1197094321 0.0086399773 -0.0199948531 2361 1311867797.3999080658 0.0089037064 0.0202179548 0.0670038015 0.0044585531 0.0455820000 419613693 0 402718720 -0.1204853207 0.0098011848 -0.0181377418 2362 1311867797.4322440624 0.0101788323 0.0202137045 0.0670038015 0.0044576538 0.0378240000 419616457 0 402718720 -0.1185642481 0.0100230332 -0.0178185888 2363 1311867797.4688720703 0.0112799285 0.0202099238 0.0670038015 0.0044585238 0.0384020000 419620357 0 402718720 -0.1201219410 0.0107319774 -0.0147686880 2364 1311867797.5000469685 0.0089678727 0.0202051683 0.0670038015 0.0044581249 0.0374410000 419623177 0 402718720 -0.1205930039 0.0089135561 -0.0168167539 2365 1311867797.5296459198 0.0122633576 0.0202018103 0.0670038015 0.0044582497 0.0381260000 419626261 0 402718720 -0.1188713685 0.0104585718 -0.0140666105 2366 1311867797.5718441010 0.0107301604 0.0201978070 0.0670038015 0.0044575801 0.0371080000 419629769 0 402718720 -0.1213183776 0.0103607317 -0.0139684565 2367 1311867797.5997619629 0.0082096690 0.0201927423 0.0670038015 0.0044568264 0.0366960000 419632861 0 402718720 -0.1238640770 0.0095560057 -0.0152103547 2368 1311867797.6303300858 0.0097772134 0.0201883439 0.0670038015 0.0044559342 0.0372610000 419636137 0 402718720 -0.1225474104 0.0082494924 -0.0140557401 2369 1311867797.6706480980 0.0098244743 0.0201839691 0.0670038015 0.0044550145 0.0484460000 419639693 0 402718720 -0.1223599017 0.0091932341 -0.0143386535 2370 1311867797.7010281086 0.0090394691 0.0201792668 0.0670038015 0.0044542963 0.0379290000 419642713 0 402718720 -0.1243498921 0.0099540241 -0.0145114865 2371 1311867797.7299659252 0.0084213829 0.0201743077 0.0670038015 0.0044538829 0.0366820000 419645997 0 402718720 -0.1234099120 0.0080987364 -0.0154326875 2372 1311867797.7678339481 0.0093324380 0.0201697370 0.0670038015 0.0044529718 0.0374840000 419649241 0 402718720 -0.1226803511 0.0076534534 -0.0150884092 2373 1311867797.8001670837 0.0090349475 0.0201650447 0.0670038015 0.0044521941 0.0376110000 419652181 0 402718720 -0.1220072508 0.0073093837 -0.0160475299 2374 1311867797.8302230835 0.0098194703 0.0201606868 0.0670038015 0.0044514158 0.0371160000 419655393 0 402718720 -0.1226448342 0.0070761652 -0.0145341195 2375 1311867797.8681600094 0.0106059574 0.0201566638 0.0670038015 0.0044508299 0.0455180000 419658957 0 402718720 -0.1222289652 0.0083201136 -0.0141993165 2376 1311867797.8986220360 0.0098164957 0.0201523118 0.0670038015 0.0044500086 0.0374480000 419661921 0 402718720 -0.1230531856 0.0059133507 -0.0140782222 2377 1311867797.9362978935 0.0112225171 0.0201485551 0.0670038015 0.0044491584 0.0451000000 419665373 0 402718720 -0.1214070916 0.0067269849 -0.0135184955 2378 1311867797.9696850777 0.0106566157 0.0201445635 0.0670038015 0.0044483041 0.0371070000 419668649 0 402718720 -0.1210443452 0.0069084545 -0.0146923941 2379 1311867798.0026450157 0.0090292003 0.0201398912 0.0670038015 0.0044474597 0.0374230000 419672045 0 402718720 -0.1229948252 0.0056127990 -0.0149204805 2380 1311867798.0362720490 0.0093453145 0.0201353557 0.0670038015 0.0044466881 0.0373190000 419675137 0 402718720 -0.1217405200 0.0046002129 -0.0152532645 2381 1311867798.0708239079 0.0090934727 0.0201307182 0.0670038015 0.0044462957 0.0374290000 419677829 0 402718720 -0.1235618740 0.0040200045 -0.0143591333 2382 1311867798.1006710529 0.0109394453 0.0201268596 0.0670038015 0.0044458493 0.0373930000 419681305 0 402718720 -0.1238061786 0.0038433357 -0.0122763701 2383 1311867798.1315639019 0.0079091880 0.0201217326 0.0670038015 0.0044462296 0.0380890000 419684205 0 402718720 -0.1223938614 0.0029926952 -0.0164024383 2384 1311867798.1681389809 0.0110035380 0.0201179078 0.0670038015 0.0044461557 0.0373320000 419687465 0 402718720 -0.1212514117 0.0031457478 -0.0134478398 2385 1311867798.2041590214 0.0089968238 0.0201132449 0.0670038015 0.0044453833 0.0372400000 419690989 0 402718720 -0.1217311323 0.0024321647 -0.0153352208 2386 1311867798.2401928902 0.0094133914 0.0201087605 0.0670038015 0.0044446869 0.0375630000 419694185 0 402718720 -0.1209389567 0.0022311646 -0.0149973966 2387 1311867798.2742829323 0.0082756197 0.0201038031 0.0670038015 0.0044438160 0.0374930000 419697325 0 402718720 -0.1208741590 0.0021289696 -0.0159903895 2388 1311867798.3000180721 0.0114517715 0.0201001800 0.0670038015 0.0044433945 0.0377610000 419700177 0 402718720 -0.1170289665 0.0024661790 -0.0143811237 2389 1311867798.3389759064 0.0096998466 0.0200958266 0.0670038015 0.0044425330 0.0377010000 419703885 0 402718720 -0.1172409952 0.0024752351 -0.0156478677 2390 1311867798.3689808846 0.0098080877 0.0200915221 0.0670038015 0.0044420705 0.0378570000 419706921 0 402718720 -0.1189064085 0.0012675072 -0.0136045236 2391 1311867798.4016571045 0.0098590655 0.0200872425 0.0670038015 0.0044412864 0.0382130000 419710285 0 402718720 -0.1175739467 0.0034059151 -0.0139156505 2392 1311867798.4377439022 0.0094490545 0.0200827951 0.0670038015 0.0044405661 0.0376680000 419713369 0 402718720 -0.1174653098 0.0021445996 -0.0138441585 2393 1311867798.4722189903 0.0098095601 0.0200785021 0.0670038015 0.0044398623 0.0467380000 419716861 0 402718720 -0.1177526116 0.0020244217 -0.0128241777 2394 1311867798.4979979992 0.0106538069 0.0200745653 0.0670038015 0.0044390687 0.0379940000 419719729 0 402718720 -0.1167194173 0.0023393515 -0.0123190209 2395 1311867798.5371229649 0.0080713928 0.0200695535 0.0670038015 0.0044388247 0.0377970000 419722917 0 402718720 -0.1160691679 0.0027937768 -0.0152626261 2396 1311867798.5710020065 0.0083257658 0.0200646521 0.0670038015 0.0044379850 0.0373400000 419726345 0 402718720 -0.1164122447 0.0012811639 -0.0144523308 2397 1311867798.6058080196 0.0101272082 0.0200605063 0.0670038015 0.0044373779 0.0370390000 419729629 0 402718720 -0.1132532880 0.0028287396 -0.0138405710 2398 1311867798.6374750137 0.0082526375 0.0200555823 0.0670038015 0.0044375654 0.0368620000 419732465 0 402718720 -0.1138218194 0.0024572243 -0.0150917768 2399 1311867798.6689419746 0.0081558740 0.0200506220 0.0670038015 0.0044366812 0.0370170000 419735741 0 402718720 -0.1124956831 0.0031012641 -0.0154354572 2400 1311867798.7046790123 0.0097761042 0.0200463409 0.0670038015 0.0044370951 0.0373330000 419739049 0 402718720 -0.1143444106 0.0033586894 -0.0121771675 2401 1311867798.7372579575 0.0067344424 0.0200407966 0.0670038015 0.0044382997 0.0373050000 419742253 0 402718720 -0.1117944792 0.0030126499 -0.0162448790 2402 1311867798.7684650421 0.0077569233 0.0200356826 0.0670038015 0.0044378559 0.0377600000 419745409 0 402718720 -0.1102967933 0.0024069583 -0.0155616887 2403 1311867798.8009719849 0.0106963618 0.0200317961 0.0670038015 0.0044390125 0.0379810000 419748317 0 402718720 -0.1084873378 0.0052753040 -0.0126185026 2404 1311867798.8353779316 0.0067096106 0.0200262544 0.0670038015 0.0044393496 0.0384130000 419751809 0 402718720 -0.1095668152 0.0045523117 -0.0157115161 2405 1311867798.8719079494 0.0070164371 0.0200208449 0.0670038015 0.0044389795 0.0384690000 419754877 0 402718720 -0.1088278443 0.0053856582 -0.0149217844 2406 1311867798.9030900002 0.0095604043 0.0200164973 0.0670038015 0.0044385264 0.0384750000 419758113 0 402718720 -0.1066159531 0.0072052833 -0.0129103661 2407 1311867798.9344220161 0.0077844076 0.0200114154 0.0670038015 0.0044382221 0.0467940000 419761005 0 402718720 -0.1055083498 0.0077293315 -0.0152682271 2408 1311867798.9702930450 0.0082627293 0.0200065364 0.0670038015 0.0044375519 0.0379970000 419764473 0 402718720 -0.1053191647 0.0082820226 -0.0139477700 2409 1311867798.9996600151 0.0080929445 0.0200015909 0.0670038015 0.0044408135 0.0474490000 419767645 0 402718720 -0.1040312126 0.0088298079 -0.0148114134 2410 1311867799.0381140709 0.0068747983 0.0199961441 0.0670038015 0.0044435755 0.0383470000 419771273 0 402718720 -0.1032516733 0.0089709405 -0.0157026052 2411 1311867799.0688700676 0.0071463855 0.0199908145 0.0670038015 0.0044427576 0.0382640000 419774237 0 402718720 -0.1032340229 0.0084829843 -0.0144943595 2412 1311867799.1011309624 0.0080533866 0.0199858653 0.0670038015 0.0044428014 0.0384010000 419777129 0 402718720 -0.1016420797 0.0098657459 -0.0140078999 2413 1311867799.1368980408 0.0050862445 0.0199796906 0.0670038015 0.0044439446 0.0387960000 419780741 0 402718720 -0.1011913419 0.0081051281 -0.0173150115 2414 1311867799.1699140072 0.0073491829 0.0199744584 0.0670038015 0.0044444643 0.0388620000 419783649 0 402718720 -0.1027343273 0.0081815729 -0.0136851594 2415 1311867799.2040729523 0.0089564780 0.0199698961 0.0670038015 0.0044448491 0.0473430000 419786789 0 402718720 -0.1000245288 0.0098837381 -0.0132748093 2416 1311867799.2358450890 0.0073644398 0.0199646786 0.0670038015 0.0044443440 0.0471340000 419789937 0 402718720 -0.1009824648 0.0095420359 -0.0149124451 2417 1311867799.2801609039 0.0077827862 0.0199596385 0.0670038015 0.0044434463 0.0482850000 419794333 0 402718720 -0.1006706059 0.0094401063 -0.0152251367 2418 1311867799.2992970943 0.0056906249 0.0199537373 0.0670038015 0.0044429667 0.0388490000 419796673 0 402718720 -0.0992801338 0.0093125254 -0.0179806277 2419 1311867799.3363530636 0.0090788379 0.0199492417 0.0670038015 0.0044433297 0.0392070000 419799733 0 402718720 -0.0977861509 0.0106879380 -0.0153137967 2420 1311867799.3682019711 0.0059596160 0.0199434609 0.0670038015 0.0044433570 0.0507840000 419802889 0 402718720 -0.0985105038 0.0106400913 -0.0185710974 2421 1311867799.4002521038 0.0069436627 0.0199380913 0.0670038015 0.0044425747 0.0388960000 419806285 0 402718720 -0.0975578949 0.0100931395 -0.0179609209 2422 1311867799.4359819889 0.0082153445 0.0199332512 0.0670038015 0.0044417089 0.0390480000 419809449 0 402718720 -0.0961996540 0.0106170280 -0.0172931217 2423 1311867799.4694008827 0.0073399581 0.0199280538 0.0670038015 0.0044409635 0.0478350000 419812805 0 402718720 -0.0970271751 0.0111464355 -0.0178938955 2424 1311867799.5055029392 0.0063828211 0.0199224658 0.0670038015 0.0044401140 0.0389270000 419816001 0 402718720 -0.0953693539 0.0132861659 -0.0200208835 2425 1311867799.5358369350 0.0085757552 0.0199177867 0.0670038015 0.0044403043 0.0390020000 419819045 0 402718720 -0.0958062410 0.0136281895 -0.0174150839 2426 1311867799.5718040466 0.0093252184 0.0199134205 0.0670038015 0.0044395044 0.0512730000 419822193 0 402718720 -0.0949804410 0.0144127607 -0.0174780302 2427 1311867799.6046330929 0.0088289967 0.0199088533 0.0670038015 0.0044386975 0.0391330000 419825413 0 402718720 -0.0949379727 0.0143575454 -0.0184551366 2428 1311867799.6362400055 0.0094558373 0.0199045481 0.0670038015 0.0044378119 0.0605620000 419828681 0 402718720 -0.0944280252 0.0154882288 -0.0185371786 2429 1311867799.6706030369 0.0080133677 0.0198996526 0.0670038015 0.0044380183 0.0494660000 419831757 0 402718720 -0.0960879996 0.0154582262 -0.0200506747 2430 1311867799.7089800835 0.0069595110 0.0198943275 0.0670038015 0.0044372261 0.0386810000 419834945 0 402718720 -0.0959843993 0.0159255862 -0.0218073167 2431 1311867799.7397329807 0.0118505806 0.0198910187 0.0670038015 0.0044379206 0.0385680000 419838293 0 402718720 -0.0936080143 0.0178643689 -0.0181388725 2432 1311867799.7721259594 0.0086544296 0.0198863983 0.0670038015 0.0044382844 0.0385480000 419841689 0 402718720 -0.0933537334 0.0166124795 -0.0219544880 2433 1311867799.8072490692 0.0080952495 0.0198815520 0.0670038015 0.0044375376 0.0390700000 419844525 0 402718720 -0.0941368267 0.0171274003 -0.0225965045 2434 1311867799.8393049240 0.0087855207 0.0198769932 0.0670038015 0.0044374335 0.0386190000 419848057 0 402718720 -0.0953633338 0.0184564535 -0.0217550304 2435 1311867799.8678040504 0.0070774127 0.0198717367 0.0670038015 0.0044371957 0.0389260000 419851149 0 402718720 -0.0938678086 0.0188321453 -0.0240662359 2436 1311867799.9071669579 0.0057146666 0.0198659251 0.0670038015 0.0044364191 0.0467970000 419854137 0 402718720 -0.0942129195 0.0185744949 -0.0251023546 2437 1311867799.9347701073 0.0091024004 0.0198615084 0.0670038015 0.0044366427 0.0496260000 419857205 0 402718720 -0.0925001502 0.0211848598 -0.0223125480 2438 1311867799.9675478935 0.0073241531 0.0198563659 0.0670038015 0.0044362726 0.0379700000 419860345 0 402718720 -0.0922784209 0.0202964414 -0.0241962280 2439 1311867800.0074419975 0.0059323008 0.0198506570 0.0670038015 0.0044354074 0.0392180000 419863909 0 402718720 -0.0933824554 0.0205544513 -0.0248215757 2440 1311867800.0354819298 0.0067448774 0.0198452858 0.0670038015 0.0044351004 0.0387750000 419866513 0 402718720 -0.0920855850 0.0192525815 -0.0243641995 2441 1311867800.0715930462 0.0065998696 0.0198398596 0.0670038015 0.0044346612 0.0388660000 419870029 0 402718720 -0.0923075974 0.0203966778 -0.0242033079 2442 1311867800.1054389477 0.0068858326 0.0198345549 0.0670038015 0.0044338309 0.0379560000 419872977 0 402718720 -0.0914655253 0.0208719838 -0.0241654851 2443 1311867800.1350870132 0.0051336619 0.0198285373 0.0670038015 0.0044338025 0.0474430000 419876285 0 402718720 -0.0907606110 0.0206247699 -0.0265036374 2444 1311867800.1694350243 0.0073956959 0.0198234503 0.0670038015 0.0044343977 0.0472790000 419879425 0 402718720 -0.0901498124 0.0228179004 -0.0239166841 2445 1311867800.2077379227 0.0054100049 0.0198175552 0.0670038015 0.0044338274 0.0475340000 419883245 0 402718720 -0.0902979746 0.0211943761 -0.0255285352 2446 1311867800.2413349152 0.0043894551 0.0198112477 0.0670038015 0.0044336853 0.0483620000 420516181 0 402718720 -0.0898507684 0.0205308814 -0.0268375054 2447 1311867800.2718439102 0.0054282206 0.0198053699 0.0670038015 0.0044330206 0.1221170000 420483769 0 402718720 -0.0877390206 0.0221572276 -0.0259435736 2448 1311867800.3038680553 0.0065096011 0.0197999386 0.0670038015 0.0044325243 0.1166930000 420488069 0 402718720 -0.0884331912 0.0223497674 -0.0236864313 2449 1311867800.3359420300 0.0051468723 0.0197939553 0.0670038015 0.0044319009 0.1115870000 420515609 0 402718720 -0.0880981386 0.0226509795 -0.0249098465 2450 1311867800.3712899685 0.0056832670 0.0197881959 0.0670038015 0.0044310321 0.1005330000 433432245 0 402718720 -0.0865433291 0.0223706141 -0.0244618058 2451 1311867800.4036390781 0.0069069183 0.0197829403 0.0670038015 0.0044304450 0.0930360000 431436713 0 402718720 -0.0844115913 0.0239184815 -0.0233786218 2452 1311867800.4360520840 0.0060584941 0.0197773431 0.0670038015 0.0044298114 0.0518780000 431570157 0 402718720 -0.0849789307 0.0249258410 -0.0235745776 2453 1311867800.4683868885 0.0049478309 0.0197712976 0.0670038015 0.0044299233 0.1212650000 430150289 0 402718720 -0.0824661702 0.0243585967 -0.0257430244 2454 1311867800.5043759346 0.0061072414 0.0197657296 0.0670038015 0.0044296682 0.0481470000 420506685 0 402718720 -0.0810737312 0.0253598616 -0.0242762789 2455 1311867800.5355989933 0.0065937643 0.0197603642 0.0670038015 0.0044288404 0.0412020000 420509641 0 402718720 -0.0804411918 0.0254481137 -0.0232884903 2456 1311867800.5714819431 0.0044192718 0.0197541178 0.0670038015 0.0044285601 0.0410480000 420513085 0 402718720 -0.0794633627 0.0256811436 -0.0258198883 2457 1311867800.6043050289 0.0046910290 0.0197479871 0.0670038015 0.0044278049 0.0407300000 420516297 0 402718720 -0.0795185268 0.0250918921 -0.0247913245 2458 1311867800.6356160641 0.0058267722 0.0197423235 0.0670038015 0.0044271010 0.0404170000 420519333 0 402718720 -0.0779131129 0.0265055224 -0.0236572009 2459 1311867800.6704459190 0.0055830022 0.0197365653 0.0670038015 0.0044263686 0.0479680000 420522537 0 402718720 -0.0766212046 0.0268218629 -0.0240349844 2460 1311867800.7034249306 0.0044742269 0.0197303611 0.0670038015 0.0044254801 0.0489220000 420525621 0 402718720 -0.0769749582 0.0254306663 -0.0243727379 2461 1311867800.7352058887 0.0054987622 0.0197245783 0.0670038015 0.0044249761 0.0410650000 420529025 0 402718720 -0.0752997845 0.0267882179 -0.0231956821 2462 1311867800.7744410038 0.0070202476 0.0197194181 0.0670038015 0.0044248955 0.0394980000 420532277 0 402718720 -0.0741391703 0.0266867746 -0.0214740802 2463 1311867800.8084959984 0.0040140809 0.0197130416 0.0670038015 0.0044254872 0.0395920000 420535225 0 402718720 -0.0742726773 0.0263847876 -0.0244499072 2464 1311867800.8347818851 0.0046030609 0.0197069093 0.0670038015 0.0044247476 0.0396580000 420538205 0 402718720 -0.0735586584 0.0267236326 -0.0238685291 2465 1311867800.8741569519 0.0049901418 0.0197009390 0.0670038015 0.0044238969 0.0409880000 420541833 0 402718720 -0.0719140545 0.0267921630 -0.0238880757 2466 1311867800.9060831070 0.0061911014 0.0196954606 0.0670038015 0.0044230662 0.0505120000 420544861 0 402718720 -0.0709009245 0.0265100282 -0.0228750408 2467 1311867800.9397630692 0.0053653857 0.0196896519 0.0670038015 0.0044224055 0.0390330000 420548001 0 402718720 -0.0722220689 0.0271533430 -0.0229498073 2468 1311867800.9754400253 0.0061970712 0.0196841849 0.0670038015 0.0044215360 0.0486110000 420551405 0 402718720 -0.0708332434 0.0273950808 -0.0226166993 2469 1311867801.0043320656 0.0074574114 0.0196792327 0.0670038015 0.0044213430 0.0395950000 420554457 0 402718720 -0.0704559535 0.0264120139 -0.0214124862 2470 1311867801.0391418934 0.0060773725 0.0196737259 0.0670038015 0.0044216054 0.0387520000 420557717 0 402718720 -0.0697361976 0.0267066322 -0.0229464732 2471 1311867801.0742049217 0.0066294945 0.0196684470 0.0670038015 0.0044207833 0.0400560000 420560865 0 402718720 -0.0678279176 0.0266391784 -0.0233342331 2472 1311867801.1095008850 0.0075599421 0.0196635487 0.0670038015 0.0044203275 0.0391590000 420564141 0 402718720 -0.0675090849 0.0274337791 -0.0223220550 2473 1311867801.1356039047 0.0060053342 0.0196580258 0.0670038015 0.0044196133 0.0381560000 420566833 0 402718720 -0.0695828423 0.0271611735 -0.0226736367 2474 1311867801.1731019020 0.0068318122 0.0196528414 0.0670038015 0.0044188480 0.0385420000 420570277 0 402718720 -0.0688302591 0.0262277108 -0.0216622800 2475 1311867801.2059779167 0.0082502887 0.0196482343 0.0670038015 0.0044183523 0.0383660000 420573489 0 402718720 -0.0677707121 0.0253218263 -0.0205433108 2476 1311867801.2351169586 0.0068327915 0.0196430584 0.0670038015 0.0044176766 0.0399650000 420576285 0 402718720 -0.0688004047 0.0257726274 -0.0215396993 2477 1311867801.2740859985 0.0061375615 0.0196376061 0.0670038015 0.0044170065 0.0390380000 420579985 0 402718720 -0.0684394091 0.0251472015 -0.0226085633 2478 1311867801.3080420494 0.0080828862 0.0196329432 0.0670038015 0.0044169020 0.0388810000 420583085 0 402718720 -0.0679716840 0.0253877640 -0.0206884518 2479 1311867801.3364291191 0.0070196530 0.0196278551 0.0670038015 0.0044164669 0.0401300000 420585865 0 402718720 -0.0681265369 0.0258802380 -0.0221276246 2480 1311867801.3723030090 0.0077526970 0.0196230667 0.0670038015 0.0044158697 0.0394330000 420589589 0 402718720 -0.0682659894 0.0265537258 -0.0211428404 2481 1311867801.4048879147 0.0067843404 0.0196178919 0.0670038015 0.0044150627 0.0400270000 420592481 0 402718720 -0.0693917274 0.0252456311 -0.0209832005 2482 1311867801.4369940758 0.0065106526 0.0196126110 0.0670038015 0.0044151128 0.0484840000 420595813 0 402718720 -0.0685915649 0.0271126982 -0.0215534978 2483 1311867801.4725570679 0.0080183381 0.0196079415 0.0670038015 0.0044193109 0.0392260000 420599033 0 402718720 -0.0673533455 0.0275694579 -0.0207399763 2484 1311867801.5049059391 0.0066917711 0.0196027418 0.0670038015 0.0044198068 0.0477020000 420601933 0 402718720 -0.0665722564 0.0266162418 -0.0225894935 2485 1311867801.5366990566 0.0047937413 0.0195967824 0.0670038015 0.0044204146 0.0388040000 420605217 0 402718720 -0.0672260225 0.0264956113 -0.0236634538 2486 1311867801.5724411011 0.0060674264 0.0195913402 0.0670038015 0.0044212603 0.0391490000 420608477 0 402718720 -0.0672736615 0.0270631369 -0.0202252921 2487 1311867801.6040530205 0.0062789004 0.0195859874 0.0670038015 0.0044203821 0.0391840000 420611505 0 402718720 -0.0667607188 0.0272992179 -0.0196212903 2488 1311867801.6371319294 0.0038542487 0.0195796643 0.0670038015 0.0044198077 0.0390290000 420615045 0 402718720 -0.0671024397 0.0258845929 -0.0213748235 2489 1311867801.6713359356 0.0056765541 0.0195740785 0.0670038015 0.0044268435 0.0383310000 420618057 0 402718720 -0.0655405149 0.0265488625 -0.0186038390 2490 1311867801.7047519684 0.0066500120 0.0195688881 0.0670038015 0.0044267195 0.0472510000 420621069 0 402718720 -0.0650291294 0.0266307779 -0.0165695660 2491 1311867801.7362918854 0.0060820282 0.0195634739 0.0670038015 0.0044321209 0.0475950000 420624473 0 402718720 -0.0638845861 0.0278325267 -0.0186784789 2492 1311867801.7739040852 0.0064977622 0.0195582308 0.0670038015 0.0044319533 0.0485960000 420627757 0 402718720 -0.0624298304 0.0278989691 -0.0188749917 2493 1311867801.8057849407 0.0078902384 0.0195535505 0.0670038015 0.0044319081 0.0394210000 420630673 0 402718720 -0.0623369887 0.0277829561 -0.0170713626 2494 1311867801.8389480114 0.0067215888 0.0195484054 0.0670038015 0.0044316032 0.0395830000 420633773 0 402718720 -0.0618027374 0.0267423596 -0.0188423619 2495 1311867801.8715689182 0.0060225641 0.0195429842 0.0670038015 0.0044319336 0.0388940000 420637033 0 402718720 -0.0602518357 0.0251664221 -0.0208230168 2496 1311867801.9050290585 0.0089121992 0.0195387251 0.0670038015 0.0044345985 0.0389490000 420640437 0 402718720 -0.0599169917 0.0250694398 -0.0188872516 2497 1311867801.9403839111 0.0070895245 0.0195337394 0.0670038015 0.0044348227 0.0401350000 420643633 0 402718720 -0.0595702603 0.0247966126 -0.0214321688 2498 1311867801.9724469185 0.0077368394 0.0195290169 0.0670038015 0.0044344274 0.0482770000 420646717 0 402718720 -0.0567854494 0.0264814273 -0.0225048475 2499 1311867802.0031659603 0.0068227560 0.0195239324 0.0670038015 0.0044379817 0.0397970000 420650193 0 402718720 -0.0566455983 0.0260994267 -0.0245399401 2500 1311867802.0413680077 0.0052546165 0.0195182246 0.0670038015 0.0044419115 0.0511600000 420653309 0 402718720 -0.0542530864 0.0275298133 -0.0276534203 2501 1311867802.0717110634 0.0060735904 0.0195128489 0.0670038015 0.0044415911 0.0390200000 420656113 0 402718720 -0.0526858941 0.0280230623 -0.0277538747 2502 1311867802.1040730476 0.0059211403 0.0195074166 0.0670038015 0.0044415955 0.0395060000 420659589 0 402718720 -0.0505398586 0.0291149076 -0.0294515565 2503 1311867802.1390628815 0.0067240652 0.0195023094 0.0670038015 0.0044430470 0.0395360000 420662681 0 402718720 -0.0488594696 0.0292476639 -0.0309831426 2504 1311867802.1724100113 0.0053003314 0.0194966377 0.0670038015 0.0044463184 0.0394410000 420665885 0 402718720 -0.0480969623 0.0298342388 -0.0332002230 2505 1311867802.2056589127 0.0039118612 0.0194904162 0.0670038015 0.0044491786 0.0394170000 420668969 0 402718720 -0.0466684103 0.0295399223 -0.0369046330 2506 1311867802.2409839630 0.0035312104 0.0194840478 0.0670038015 0.0044522582 0.0395960000 420672485 0 402718720 -0.0452229492 0.0282584708 -0.0386475399 2507 1311867802.2706429958 0.0058666589 0.0194786161 0.0670038015 0.0044518661 0.0478820000 420675577 0 402718720 -0.0436065868 0.0285439380 -0.0389876887 2508 1311867802.3064510822 0.0046789222 0.0194727151 0.0670038015 0.0044520576 0.0482460000 420678925 0 402718720 -0.0428108685 0.0276886038 -0.0417624414 2509 1311867802.3400380611 0.0048814914 0.0194668995 0.0670038015 0.0044545884 0.0394680000 420681681 0 402718720 -0.0416781865 0.0273894109 -0.0434257984 2510 1311867802.3742809296 0.0056916433 0.0194614114 0.0670038015 0.0044543920 0.0395550000 420684981 0 402718720 -0.0412516445 0.0254594665 -0.0446919799 2511 1311867802.4052720070 0.0053532640 0.0194557928 0.0670038015 0.0044560289 0.0391690000 420688193 0 402718720 -0.0393807404 0.0252005626 -0.0477244370 2512 1311867802.4389400482 0.0057808161 0.0194503490 0.0670038015 0.0044561479 0.0397660000 420691229 0 402718720 -0.0366883762 0.0256929751 -0.0491721965 2513 1311867802.4714379311 0.0027068355 0.0194436862 0.0670038015 0.0044558475 0.0399380000 420694481 0 402718720 -0.0353828855 0.0241490994 -0.0550193861 2514 1311867802.5060200691 0.0054611880 0.0194381243 0.0670038015 0.0044574524 0.0480540000 420697813 0 402718720 -0.0362152532 0.0248504356 -0.0535572842 2515 1311867802.5389459133 0.0051783514 0.0194324545 0.0670038015 0.0044565749 0.0399720000 420700969 0 402718720 -0.0346352160 0.0249528643 -0.0558910966 2516 1311867802.5715909004 0.0026340061 0.0194257778 0.0670038015 0.0044587758 0.0484130000 420704293 0 402718720 -0.0318700150 0.0251943395 -0.0616362803 2517 1311867802.6031410694 0.0028092111 0.0194191761 0.0670038015 0.0044587460 0.0400430000 420707353 0 402718720 -0.0306394733 0.0255684070 -0.0627353117 2518 1311867802.6396369934 0.0033486825 0.0194127938 0.0670038015 0.0044583877 0.0396870000 420710421 0 402718720 -0.0302056745 0.0243537705 -0.0632428452 2519 1311867802.6727440357 0.0009827098 0.0194054774 0.0670038015 0.0044583217 0.0403620000 420713761 0 402718720 -0.0292258114 0.0239321608 -0.0675804839 2520 1311867802.7073149681 0.0010131253 0.0193981788 0.0670038015 0.0044577985 0.0404510000 420716757 0 402718720 -0.0272160936 0.0255678557 -0.0693382397 2521 1311867802.7416400909 0.0009937966 0.0193908784 0.0670038015 0.0044574194 0.0397820000 420720153 0 402718720 -0.0260931235 0.0259142779 -0.0723926350 2522 1311867802.7708799839 0.0011498790 0.0193836457 0.0670038015 0.0044567394 0.0406720000 420723325 0 402718720 -0.0244235061 0.0256300326 -0.0742817447 2523 1311867802.8048460484 0.0040977136 0.0193775870 0.0670038015 0.0044565766 0.0688860000 420726353 0 402718720 -0.0220582709 0.0263188612 -0.0784756392 2524 1311867802.8393790722 0.0017948634 0.0193706208 0.0670038015 0.0044561693 0.0513740000 420729485 0 402718720 -0.0219991617 0.0267774127 -0.0777937248 2525 1311867802.8706729412 0.0009092380 0.0193633094 0.0670038015 0.0044553388 0.0406480000 420732697 0 402718720 -0.0208455194 0.0269289277 -0.0782150924 2526 1311867802.9066920280 0.0011912733 0.0193561154 0.0670038015 0.0044548729 0.0404500000 420736085 0 402718720 -0.0199164022 0.0267429557 -0.0802096799 2527 1311867802.9404280186 0.0026149543 0.0193494905 0.0670038015 0.0044543709 0.0400450000 420739105 0 402718720 -0.0178770311 0.0255414639 -0.0832586735 2528 1311867802.9723958969 0.0014717268 0.0193424186 0.0670038015 0.0044542905 0.0401360000 420742269 0 402718720 -0.0180467367 0.0256024543 -0.0823570788 2529 1311867803.0042099953 0.0007852535 0.0193350808 0.0670038015 0.0044547706 0.0405340000 420745289 0 402718720 -0.0161664002 0.0265747979 -0.0839183033 2530 1311867803.0404539108 0.0021101967 0.0193282726 0.0670038015 0.0044546889 0.0486200000 420748933 0 402718720 -0.0144694652 0.0262376647 -0.0866450369 2531 1311867803.0710830688 0.0015888496 0.0193212637 0.0670038015 0.0044545352 0.0394300000 420751961 0 402718720 -0.0147247175 0.0266368948 -0.0868235230 2532 1311867803.1049640179 0.0015788468 0.0193142564 0.0670038015 0.0044539174 0.0488030000 420754917 0 402718720 -0.0142095201 0.0265533924 -0.0866952017 2533 1311867803.1399960518 0.0019996872 0.0193074208 0.0670038015 0.0044533217 0.0408080000 420758049 0 402718720 -0.0136109004 0.0260401815 -0.0893445611 2534 1311867803.1724820137 0.0022462488 0.0193006879 0.0670038015 0.0044526284 0.0402750000 420761533 0 402718720 -0.0123210326 0.0254381653 -0.0915876031 2535 1311867803.2086870670 0.0022474709 0.0192939608 0.0670038015 0.0044518941 0.0523830000 420764721 0 402718720 -0.0124034751 0.0267937221 -0.0922566056 2536 1311867803.2400670052 0.0018762264 0.0192870926 0.0670038015 0.0044534609 0.0401250000 420767621 0 402718720 -0.0124358013 0.0274055172 -0.0916344821 2537 1311867803.2704820633 0.0026753352 0.0192805448 0.0670038015 0.0044549096 0.0400530000 420770649 0 402718720 -0.0133164003 0.0264839809 -0.0931150094 2538 1311867803.3084690571 0.0044292221 0.0192746933 0.0670038015 0.0044567080 0.0500950000 420774341 0 402718720 -0.0138271004 0.0228242204 -0.0962540433 2539 1311867803.3390929699 0.0032748748 0.0192683916 0.0670038015 0.0044567911 0.0403780000 420777577 0 402718720 -0.0134784747 0.0247207452 -0.0968590006 2540 1311867803.3732869625 0.0019878901 0.0192615883 0.0670038015 0.0044562745 0.0404560000 420780613 0 402718720 -0.0123718763 0.0250468198 -0.0970205888 2541 1311867803.4067549706 0.0033343518 0.0192553202 0.0670038015 0.0044554504 0.0407920000 420783753 0 402718720 -0.0112633510 0.0257155709 -0.0992402062 2542 1311867803.4397881031 0.0030293977 0.0192489371 0.0670038015 0.0044546463 0.0404670000 420786853 0 402718720 -0.0127827087 0.0259327199 -0.0993597135 2543 1311867803.4707190990 0.0021781267 0.0192422242 0.0670038015 0.0044538136 0.0410270000 420789841 0 402718720 -0.0122888545 0.0250087008 -0.0995288119 2544 1311867803.5065801144 0.0034024159 0.0192359978 0.0670038015 0.0044533610 0.0408160000 420793309 0 402718720 -0.0124531975 0.0260094851 -0.1017482057 2545 1311867803.5397379398 0.0037467822 0.0192299117 0.0670038015 0.0044527152 0.0405570000 420796457 0 402718720 -0.0118144089 0.0260028522 -0.1030434668 2546 1311867803.5702500343 0.0037196584 0.0192238197 0.0670038015 0.0044518996 0.0510850000 420799357 0 402718720 -0.0119136851 0.0259982646 -0.1038258150 2547 1311867803.6121668816 0.0033959153 0.0192176054 0.0670038015 0.0044511515 0.0407060000 420802985 0 402718720 -0.0125551298 0.0248364732 -0.1044854075 2548 1311867803.6394500732 0.0055456385 0.0192122396 0.0670038015 0.0044510270 0.0404260000 420806173 0 402718720 -0.0107558072 0.0286173522 -0.1066667587 2549 1311867803.6726729870 0.0050316583 0.0192066764 0.0670038015 0.0044507933 0.0405300000 420809257 0 402718720 -0.0108560454 0.0288434755 -0.1066647545 2550 1311867803.7105441093 0.0036651250 0.0192005817 0.0670038015 0.0044513004 0.0405500000 420812261 0 402718720 -0.0124761239 0.0288144723 -0.1064904109 2551 1311867803.7378931046 0.0050228192 0.0191950240 0.0670038015 0.0044507620 0.0400770000 420815689 0 402718720 -0.0123602133 0.0306808278 -0.1080255881 2552 1311867803.7722349167 0.0053881616 0.0191896137 0.0670038015 0.0044501445 0.0398780000 420818885 0 402718720 -0.0114970040 0.0315287262 -0.1091572940 2553 1311867803.8064799309 0.0039702835 0.0191836524 0.0670038015 0.0044501967 0.0402660000 420822025 0 402718720 -0.0129318461 0.0332624987 -0.1079440489 2554 1311867803.8385739326 0.0035500473 0.0191775312 0.0670038015 0.0044511710 0.0398700000 420825245 0 402718720 -0.0130726714 0.0347567610 -0.1077205986 2555 1311867803.8737049103 0.0025156557 0.0191710099 0.0670038015 0.0044516781 0.0400930000 420828641 0 402718720 -0.0147544770 0.0340383910 -0.1081229895 2556 1311867803.9077479839 0.0042828387 0.0191651851 0.0670038015 0.0044527963 0.0403600000 420831589 0 402718720 -0.0155628556 0.0340313204 -0.1107580885 2557 1311867803.9400169849 0.0027109967 0.0191587501 0.0670038015 0.0044546406 0.0402790000 420834873 0 402718720 -0.0143671529 0.0355914161 -0.1104168445 2558 1311867803.9723939896 0.0029071260 0.0191523969 0.0670038015 0.0044547315 0.0407360000 420838141 0 402718720 -0.0123991463 0.0383970030 -0.1091080233 2559 1311867804.0064320564 0.0022082317 0.0191457755 0.0670038015 0.0044540245 0.0402380000 420841113 0 402718720 -0.0160025302 0.0384687595 -0.1091684625 2560 1311867804.0387020111 0.0021201500 0.0191391248 0.0670038015 0.0044533571 0.0403590000 420844325 0 402718720 -0.0160754491 0.0387079790 -0.1108580902 2561 1311867804.0722310543 0.0040698242 0.0191332407 0.0670038015 0.0044533374 0.0402460000 420847593 0 402718720 -0.0142849190 0.0393254645 -0.1138897538 2562 1311867804.1084001064 0.0012060003 0.0191262433 0.0670038015 0.0044532175 0.0504050000 420850733 0 402718720 -0.0174177960 0.0388276801 -0.1112744138 2563 1311867804.1399340630 0.0016601628 0.0191194286 0.0670038015 0.0044526433 0.0402410000 420853881 0 402718720 -0.0173105858 0.0391930975 -0.1131321117 2564 1311867804.1736989021 0.0022553983 0.0191128514 0.0670038015 0.0044525539 0.0402710000 420857021 0 402718720 -0.0168440454 0.0393697359 -0.1143356189 2565 1311867804.2092669010 0.0019519145 0.0191061610 0.0670038015 0.0044525922 0.0407400000 420860097 0 402718720 -0.0192493014 0.0370977037 -0.1140459031 2566 1311867804.2408709526 0.0015174705 0.0190993065 0.0670038015 0.0044528252 0.0400390000 420863253 0 402718720 -0.0173486192 0.0394666605 -0.1144173741 2567 1311867804.2707660198 0.0032677734 0.0190931391 0.0670038015 0.0044521870 0.0403030000 420866409 0 402718720 -0.0189202260 0.0397624858 -0.1178288311 2568 1311867804.3078389168 0.0017073513 0.0190863690 0.0670038015 0.0044517419 0.0548820000 420869741 0 402718720 -0.0204123184 0.0386424251 -0.1168603972 2569 1311867804.3404970169 0.0019632531 0.0190797037 0.0670038015 0.0044509540 0.0517940000 420872705 0 402718720 -0.0204727966 0.0408455096 -0.1173948646 2570 1311867804.3725171089 0.0024387930 0.0190732286 0.0670038015 0.0044504037 0.0398290000 420875981 0 402718720 -0.0208491459 0.0411986224 -0.1186880842 2571 1311867804.4121570587 0.0022310680 0.0190666778 0.0670038015 0.0044498716 0.0398380000 420879161 0 402718720 -0.0201763082 0.0410615690 -0.1195959151 2572 1311867804.4434490204 0.0007007082 0.0190595371 0.0670038015 0.0044490314 0.0400920000 420882437 0 402718720 -0.0208414905 0.0403070301 -0.1188923270 2573 1311867804.4745810032 0.0023464533 0.0190530415 0.0670038015 0.0044481819 0.0399400000 420885481 0 402718720 -0.0211975854 0.0416338965 -0.1209350675 2574 1311867804.5092110634 0.0022304819 0.0190465059 0.0670038015 0.0044479293 0.0491190000 420888941 0 402718720 -0.0217499882 0.0423466824 -0.1188153476 2575 1311867804.5393021107 0.0013583942 0.0190396368 0.0670038015 0.0044473289 0.0402880000 420891841 0 402718720 -0.0210316293 0.0420660488 -0.1216737702 2576 1311867804.5744440556 0.0025161807 0.0190332224 0.0670038015 0.0044470539 0.0402150000 420895173 0 402718720 -0.0206083208 0.0437751263 -0.1208694428 2577 1311867804.6065940857 0.0033989288 0.0190271555 0.0670038015 0.0044462187 0.0401730000 420898377 0 402718720 -0.0233928151 0.0404124632 -0.1201444343 2578 1311867804.6414110661 0.0032306546 0.0190210281 0.0670038015 0.0044455176 0.0399830000 420901325 0 402718720 -0.0234725010 0.0411795229 -0.1228745282 2579 1311867804.6758968830 0.0025037525 0.0190146236 0.0670038015 0.0044451869 0.0406010000 420904777 0 402718720 -0.0217909943 0.0444679260 -0.1235655919 2580 1311867804.7094891071 0.0042326818 0.0190088941 0.0670038015 0.0044444179 0.0525040000 420907989 0 402718720 -0.0241104178 0.0428603888 -0.1225943267 2581 1311867804.7431960106 0.0016042488 0.0190021508 0.0670038015 0.0044442912 0.0406670000 420911257 0 402718720 -0.0207473040 0.0450976826 -0.1232014820 2582 1311867804.7739880085 0.0031282848 0.0189960029 0.0670038015 0.0044440514 0.0485450000 420914053 0 402718720 -0.0220394582 0.0454695188 -0.1224943250 2583 1311867804.8113589287 0.0023971670 0.0189895767 0.0670038015 0.0044458817 0.0397660000 420917369 0 402718720 -0.0219204873 0.0465673953 -0.1235820800 2584 1311867804.8407669067 0.0039604674 0.0189837605 0.0670038015 0.0044458291 0.0401650000 420920541 0 402718720 -0.0226395167 0.0477846824 -0.1221239939 2585 1311867804.8758749962 0.0016028620 0.0189770367 0.0670038015 0.0044456018 0.0398730000 420923809 0 402718720 -0.0197777636 0.0481589548 -0.1231608987 2586 1311867804.9093499184 0.0057197427 0.0189719101 0.0670038015 0.0044455863 0.0401440000 420926885 0 402718720 -0.0243260954 0.0479278006 -0.1222452968 2587 1311867804.9418170452 0.0021262206 0.0189653985 0.0670038015 0.0044461406 0.0392190000 420930225 0 402718720 -0.0193334855 0.0493627191 -0.1248362884 2588 1311867804.9785380363 0.0031575200 0.0189592903 0.0670038015 0.0044458638 0.0400690000 420933109 0 402718720 -0.0199743081 0.0505979061 -0.1226456687 2589 1311867805.0090980530 0.0012482778 0.0189524495 0.0670038015 0.0044465806 0.0403980000 420936521 0 402718720 -0.0191058926 0.0486581475 -0.1232377589 2590 1311867805.0401790142 0.0023555399 0.0189460414 0.0670038015 0.0044460722 0.0529050000 420939861 0 402718720 -0.0190657265 0.0479029641 -0.1246237457 2591 1311867805.0801899433 0.0020733757 0.0189395294 0.0670038015 0.0044454958 0.0405710000 420942785 0 402718720 -0.0184391290 0.0493436307 -0.1230403930 2592 1311867805.1079609394 0.0026415947 0.0189332416 0.0670038015 0.0044454085 0.0510220000 420945877 0 402718720 -0.0183689184 0.0492315814 -0.1217847690 2593 1311867805.1444120407 0.0034129946 0.0189272561 0.0670038015 0.0044460353 0.0400090000 420949329 0 402718720 -0.0184361339 0.0471987128 -0.1218091473 2594 1311867805.1750040054 0.0027852319 0.0189210333 0.0670038015 0.0044455773 0.0402750000 420952045 0 402718720 -0.0173821971 0.0488939174 -0.1209942028 2595 1311867805.2100739479 0.0023688115 0.0189146548 0.0670038015 0.0044454702 0.0410250000 420955817 0 402718720 -0.0150456205 0.0504483916 -0.1224287674 2596 1311867805.2393519878 0.0033180949 0.0189086469 0.0670038015 0.0044448908 0.0402090000 420958525 0 402718720 -0.0166939255 0.0482043773 -0.1209004074 2597 1311867805.2741580009 0.0027501564 0.0189024249 0.0670038015 0.0044441388 0.0399710000 420961921 0 402718720 -0.0155741703 0.0490170680 -0.1203092560 2598 1311867805.3108520508 0.0024870869 0.0188961064 0.0670038015 0.0044433109 0.0487840000 420965373 0 402718720 -0.0145492395 0.0487955622 -0.1195020527 2599 1311867805.3395309448 0.0030188104 0.0188899974 0.0670038015 0.0044424851 0.0405620000 420968289 0 402718720 -0.0140933823 0.0481241569 -0.1181542575 2600 1311867805.3745789528 0.0049146838 0.0188846223 0.0670038015 0.0044452100 0.0404520000 420971365 0 402718720 -0.0154919401 0.0481791086 -0.1173207834 2601 1311867805.4084360600 0.0021461032 0.0188781869 0.0670038015 0.0044452671 0.0407030000 420974753 0 402718720 -0.0122286417 0.0486292094 -0.1186618954 2602 1311867805.4401900768 0.0038161515 0.0188723983 0.0670038015 0.0044444773 0.0400420000 420977845 0 402718720 -0.0127675021 0.0502431318 -0.1204614565 2603 1311867805.4747269154 0.0038582245 0.0188666302 0.0670038015 0.0044465438 0.0403810000 420980985 0 402718720 -0.0132886292 0.0483025238 -0.1178312078 2604 1311867805.5079410076 0.0019857995 0.0188601476 0.0670038015 0.0044465239 0.0403840000 420984189 0 402718720 -0.0109351529 0.0490536802 -0.1168453172 2605 1311867805.5406329632 0.0036198006 0.0188542972 0.0670038015 0.0044460190 0.0406940000 420987457 0 402718720 -0.0126036238 0.0500441641 -0.1166144684 2606 1311867805.5750451088 0.0040459167 0.0188486147 0.0670038015 0.0044456783 0.0513380000 420990733 0 402718720 -0.0110870702 0.0470674187 -0.1161034405 2607 1311867805.6078290939 0.0054074330 0.0188434589 0.0670038015 0.0044453487 0.0405620000 420993809 0 402718720 -0.0108466437 0.0453855097 -0.1152917072 2608 1311867805.6431670189 0.0028063818 0.0188373098 0.0670038015 0.0044463357 0.0506290000 420997005 0 402718720 -0.0086915288 0.0471342914 -0.1165866107 2609 1311867805.6750800610 0.0038962064 0.0188315830 0.0670038015 0.0044458416 0.0402860000 421000281 0 402718720 -0.0100795794 0.0465019085 -0.1160324290 2610 1311867805.7071790695 0.0039916700 0.0188258972 0.0670038015 0.0044457431 0.0401090000 421003421 0 402718720 -0.0105343973 0.0470423028 -0.1151895449 2611 1311867805.7425789833 0.0061183958 0.0188210303 0.0670038015 0.0044487418 0.0409640000 421006553 0 402718720 -0.0115104392 0.0454567187 -0.1166670546 2612 1311867805.7748079300 0.0046961121 0.0188156226 0.0670038015 0.0044480911 0.0406290000 421009709 0 402718720 -0.0101783564 0.0465124846 -0.1147421673 2613 1311867805.8089549541 0.0037136460 0.0188098430 0.0670038015 0.0044477298 0.0399860000 421012865 0 402718720 -0.0088714659 0.0468510799 -0.1149324030 2614 1311867805.8436930180 0.0023791885 0.0188035574 0.0670038015 0.0044495184 0.0509520000 421016397 0 402718720 -0.0076453728 0.0478874668 -0.1147920340 2615 1311867805.8754489422 0.0027055729 0.0187974014 0.0670038015 0.0044489796 0.0403760000 421019225 0 402718720 -0.0073166001 0.0472771078 -0.1153522730 2616 1311867805.9129049778 0.0028344879 0.0187912994 0.0670038015 0.0044528970 0.0406570000 421022477 0 402718720 -0.0072776778 0.0477260761 -0.1145991981 2617 1311867805.9434199333 0.0036477854 0.0187855128 0.0670038015 0.0044536354 0.0405250000 421025801 0 402718720 -0.0075985016 0.0471202210 -0.1148633659 2618 1311867805.9747679234 0.0026923295 0.0187793656 0.0670038015 0.0044529404 0.0400160000 421028893 0 402718720 -0.0060970751 0.0485870428 -0.1154368147 2619 1311867806.0099248886 0.0045078262 0.0187739164 0.0670038015 0.0044532024 0.0401870000 421032033 0 402718720 -0.0076988074 0.0479857773 -0.1138575003 2620 1311867806.0427870750 0.0037101244 0.0187681669 0.0670038015 0.0044526298 0.0407650000 421035485 0 402718720 -0.0060396385 0.0482277460 -0.1156681776 2621 1311867806.0743720531 0.0038202149 0.0187624637 0.0670038015 0.0044584107 0.0420450000 421038537 0 402718720 -0.0056188554 0.0493098162 -0.1153123826 2622 1311867806.1078710556 0.0032075401 0.0187565313 0.0670038015 0.0044578425 0.0491090000 421041709 0 402718720 -0.0036109868 0.0494259745 -0.1157743856 2623 1311867806.1461410522 0.0046448014 0.0187511513 0.0670038015 0.0044573004 0.0403390000 421044769 0 402718720 -0.0044455361 0.0503034778 -0.1144874096 2624 1311867806.1751658916 0.0049744765 0.0187459010 0.0670038015 0.0044570600 0.0405050000 421047949 0 402718720 -0.0015611085 0.0531927086 -0.1127201319 2625 1311867806.2106690407 0.0040223934 0.0187402920 0.0670038015 0.0044583887 0.0404810000 421051337 0 402718720 -0.0009403615 0.0515868180 -0.1138163209 2626 1311867806.2435200214 0.0040191533 0.0187346861 0.0670038015 0.0044580110 0.0578350000 421054477 0 402718720 -0.0010215379 0.0516931415 -0.1121343970 2627 1311867806.2773389816 0.0047530066 0.0187293638 0.0670038015 0.0044577655 0.0403870000 421057889 0 402718720 0.0000318852 0.0534303412 -0.1111437604 2628 1311867806.3098840714 0.0040271692 0.0187237694 0.0670038015 0.0044573373 0.0403510000 421061013 0 402718720 0.0017714244 0.0529752448 -0.1125612557 2629 1311867806.3459429741 0.0033338072 0.0187179155 0.0670038015 0.0044567785 0.0490470000 421064153 0 402718720 0.0019286983 0.0513504595 -0.1120202541 2630 1311867806.3760368824 0.0037454772 0.0187122225 0.0670038015 0.0044564023 0.0403940000 421067117 0 402718720 0.0030908561 0.0531814694 -0.1116358563 2631 1311867806.4090569019 0.0047020484 0.0187068975 0.0670038015 0.0044626101 0.0404640000 421070713 0 402718720 0.0017140131 0.0520615205 -0.1106304675 2632 1311867806.4434189796 0.0031390046 0.0187009826 0.0670038015 0.0044624313 0.0407850000 421073741 0 402718720 0.0038819462 0.0513752289 -0.1108044386 2633 1311867806.4748079777 0.0055254968 0.0186959786 0.0670038015 0.0044643894 0.0402730000 421076825 0 402718720 0.0028535551 0.0519416817 -0.1125723943 2634 1311867806.5103459358 0.0047369031 0.0186906791 0.0670038015 0.0044639571 0.0401780000 421080085 0 402718720 0.0044670994 0.0512939766 -0.1125921905 2635 1311867806.5426719189 0.0032103441 0.0186848042 0.0670038015 0.0044639649 0.0406020000 421083169 0 402718720 0.0061112549 0.0513252243 -0.1114245281 2636 1311867806.5787520409 0.0040756818 0.0186792620 0.0670038015 0.0044632661 0.0505980000 421086309 0 402718720 0.0087938141 0.0542609580 -0.1111955866 2637 1311867806.6116139889 0.0044224658 0.0186738556 0.0670038015 0.0044635580 0.0411760000 421089825 0 402718720 0.0061203688 0.0525533780 -0.1104512513 2638 1311867806.6448700428 0.0031188158 0.0186679591 0.0670038015 0.0044627478 0.0503150000 421092653 0 402718720 0.0085907318 0.0534593165 -0.1096249074 2639 1311867806.6744968891 0.0054216813 0.0186629396 0.0670038015 0.0044629915 0.0408030000 421096017 0 402718720 0.0074319458 0.0552696884 -0.1101924926 2640 1311867806.7064468861 0.0052512088 0.0186578594 0.0670038015 0.0044622240 0.0410630000 421099069 0 402718720 0.0078476258 0.0559582151 -0.1089673936 2641 1311867806.7427020073 0.0043573435 0.0186524446 0.0670038015 0.0044615889 0.0407990000 421102393 0 402718720 0.0082883015 0.0552651063 -0.1081331000 2642 1311867806.7790679932 0.0052755107 0.0186473814 0.0670038015 0.0044621533 0.0415310000 421105469 0 402718720 0.0077931890 0.0570940189 -0.1072883606 2643 1311867806.8067629337 0.0025717721 0.0186412991 0.0670038015 0.0044620130 0.0407940000 421108945 0 402718720 0.0102746021 0.0558387376 -0.1057377234 2644 1311867806.8439810276 0.0030629858 0.0186354071 0.0670038015 0.0044612144 0.0489070000 421111821 0 402718720 0.0089331195 0.0546690635 -0.1053277552 2645 1311867806.8763918877 0.0039818785 0.0186298671 0.0670038015 0.0044608672 0.0402040000 421115097 0 402718720 0.0103395609 0.0572602190 -0.1049090400 2646 1311867806.9124479294 0.0038303011 0.0186242739 0.0670038015 0.0044600893 0.0486720000 421118421 0 402718720 0.0102921464 0.0563512072 -0.1050183773 2647 1311867806.9446148872 0.0035691890 0.0186185863 0.0670038015 0.0044602662 0.0410700000 421121449 0 402718720 0.0107958056 0.0545554124 -0.1057216451 2648 1311867806.9770460129 0.0051123062 0.0186134857 0.0670038015 0.0044599655 0.0411440000 421124965 0 402718720 0.0125298724 0.0570083372 -0.1062403470 2649 1311867807.0138700008 0.0041975640 0.0186080437 0.0670038015 0.0044600866 0.0408200000 421127785 0 402718720 0.0106684277 0.0548175499 -0.1046057194 2650 1311867807.0428779125 0.0027382246 0.0186020551 0.0670038015 0.0044603029 0.0404480000 421130933 0 402718720 0.0132241324 0.0533195734 -0.1045475453 2651 1311867807.0794920921 0.0043309927 0.0185966718 0.0670038015 0.0044616714 0.0406010000 421134217 0 402718720 0.0125353355 0.0529967621 -0.1044548303 2652 1311867807.1121389866 0.0046751555 0.0185914224 0.0670038015 0.0044608628 0.0403030000 421137549 0 402718720 0.0134898592 0.0552501678 -0.1040851250 2653 1311867807.1428070068 0.0043880339 0.0185860687 0.0670038015 0.0044600373 0.0405500000 421140553 0 402718720 0.0136001455 0.0545295812 -0.1035526022 2654 1311867807.1802010536 0.0039424677 0.0185805511 0.0670038015 0.0044604031 0.0489190000 421143701 0 402718720 0.0139116002 0.0538600087 -0.1021728888 2655 1311867807.2105820179 0.0055820155 0.0185756552 0.0670038015 0.0044603218 0.0409940000 421146665 0 402718720 0.0161403604 0.0575675666 -0.1023205072 2656 1311867807.2429521084 0.0050388672 0.0185705585 0.0670038015 0.0044598346 0.0411640000 421149813 0 402718720 0.0159104764 0.0561192855 -0.1021450385 2657 1311867807.2808670998 0.0048314547 0.0185653876 0.0670038015 0.0044590909 0.0406770000 421153257 0 402718720 0.0152399102 0.0539129637 -0.1017173156 2658 1311867807.3107318878 0.0059848391 0.0185606545 0.0670038015 0.0044587054 0.0408450000 421156413 0 402718720 0.0158753004 0.0539593436 -0.1030250341 2659 1311867807.3434429169 0.0066807549 0.0185561867 0.0670038015 0.0044586315 0.0408270000 421159689 0 402718720 0.0179569609 0.0547824055 -0.1040324718 2660 1311867807.3776888847 0.0042032278 0.0185507909 0.0670038015 0.0044581339 0.0507550000 421162957 0 402718720 0.0174278505 0.0529942885 -0.1008633897 2661 1311867807.4111731052 0.0056683114 0.0185459497 0.0670038015 0.0044590197 0.0406250000 421166161 0 402718720 0.0189989805 0.0559005439 -0.1011762768 2662 1311867807.4426960945 0.0063129361 0.0185413542 0.0670038015 0.0044585120 0.0517420000 421169117 0 402718720 0.0205569658 0.0551370457 -0.1028495505 2663 1311867807.4781239033 0.0051413439 0.0185363223 0.0670038015 0.0044601744 0.0406450000 421172513 0 402718720 0.0187346973 0.0528358817 -0.1011336818 2664 1311867807.5104010105 0.0040988876 0.0185309029 0.0670038015 0.0044594929 0.0405560000 421175669 0 402718720 0.0204763692 0.0518668704 -0.1009065509 2665 1311867807.5430259705 0.0054318444 0.0185259876 0.0670038015 0.0044589652 0.0407060000 421178577 0 402718720 0.0210760906 0.0527935363 -0.1019532755 2666 1311867807.5746030807 0.0053289756 0.0185210375 0.0670038015 0.0044605199 0.0399180000 421182109 0 402718720 0.0218337234 0.0508686677 -0.1024187803 2667 1311867807.6121149063 0.0051717912 0.0185160322 0.0670038015 0.0044604405 0.0399690000 421185105 0 402718720 0.0220078472 0.0497249141 -0.1024658009 2668 1311867807.6434121132 0.0060391044 0.0185113557 0.0670038015 0.0044612185 0.0510360000 421188125 0 402718720 0.0229693782 0.0510767028 -0.1030792370 2669 1311867807.6772611141 0.0061259437 0.0185067152 0.0670038015 0.0044606784 0.0497380000 421191265 0 402718720 0.0215341020 0.0501182824 -0.1033593491 2670 1311867807.7112979889 0.0064528990 0.0185022007 0.0670038015 0.0044600388 0.0526230000 421194725 0 402718720 0.0202251021 0.0481628478 -0.1042450964 2671 1311867807.7441759109 0.0081248591 0.0184983155 0.0670038015 0.0044602755 0.0407590000 421197929 0 402718720 0.0217936020 0.0498988666 -0.1060005128 2672 1311867807.7760479450 0.0095460722 0.0184949651 0.0670038015 0.0044596743 0.0405160000 421200829 0 402718720 0.0217690896 0.0525226146 -0.1058938205 2673 1311867807.8105859756 0.0094473194 0.0184915803 0.0670038015 0.0044601897 0.0403810000 421204097 0 402718720 0.0207817089 0.0505385399 -0.1063917875 2674 1311867807.8429179192 0.0100186737 0.0184884116 0.0670038015 0.0044602833 0.0484730000 421752401 0 402718720 0.0207159277 0.0511443466 -0.1065322012 2675 1311867807.8800721169 0.0115885148 0.0184858322 0.0670038015 0.0044604329 0.1217570000 421751297 0 402718720 0.0206301194 0.0518546551 -0.1074234918 2676 1311867807.9118909836 0.0104624201 0.0184828340 0.0670038015 0.0044600786 0.1213950000 421755245 0 402718720 0.0192290042 0.0503419563 -0.1070089564 2677 1311867807.9477560520 0.0096168611 0.0184795220 0.0670038015 0.0044606051 0.1172870000 425293725 0 402718720 0.0211045314 0.0501971766 -0.1065088958 2678 1311867807.9757928848 0.0098162200 0.0184762871 0.0670038015 0.0044599148 0.0677840000 433316869 0 402718720 0.0217331145 0.0507342480 -0.1065740362 2679 1311867808.0103120804 0.0104212528 0.0184732803 0.0670038015 0.0044608290 0.0940540000 433307241 0 402718720 0.0204428583 0.0515137687 -0.1079240143 2680 1311867808.0437099934 0.0100327078 0.0184701309 0.0670038015 0.0044601656 0.0552550000 433205221 0 402718720 0.0204275027 0.0518353395 -0.1075053513 2681 1311867808.0799739361 0.0087066982 0.0184664891 0.0670038015 0.0044800632 0.1301850000 431746581 0 402718720 0.0192567594 0.0515364185 -0.1093488783 2682 1311867808.1118609905 0.0087504564 0.0184628665 0.0670038015 0.0044831527 0.0680100000 421729013 0 402718720 0.0210554041 0.0506824479 -0.1096475571 2683 1311867808.1470420361 0.0088972077 0.0184593012 0.0670038015 0.0044827148 0.0417660000 421732537 0 402718720 0.0214179866 0.0508650132 -0.1104096696 2684 1311867808.1792190075 0.0086734854 0.0184556552 0.0670038015 0.0044846310 0.0427980000 421735565 0 402718720 0.0200997740 0.0515391156 -0.1099267751 2685 1311867808.2112250328 0.0108926725 0.0184528384 0.0670038015 0.0045098678 0.0426780000 421738769 0 402718720 0.0207955763 0.0495263934 -0.1119520888 2686 1311867808.2432029247 0.0098755267 0.0184496451 0.0670038015 0.0045091966 0.0447890000 421741653 0 402718720 0.0219286699 0.0483945608 -0.1120788604 2687 1311867808.2811930180 0.0114505189 0.0184470403 0.0670038015 0.0045087558 0.0420240000 421745185 0 402718720 0.0227412991 0.0499236137 -0.1144513711 2688 1311867808.3112449646 0.0103531806 0.0184440292 0.0670038015 0.0045082888 0.0415340000 421748389 0 402718720 0.0228745006 0.0498032272 -0.1142440811 2689 1311867808.3454720974 0.0106444750 0.0184411286 0.0670038015 0.0045074845 0.0435860000 421751465 0 402718720 0.0244147573 0.0501213782 -0.1153966635 2690 1311867808.3792409897 0.0102669680 0.0184380899 0.0670038015 0.0045078173 0.0431960000 421754613 0 402718720 0.0232405160 0.0508230217 -0.1152957827 2691 1311867808.4111659527 0.0112606157 0.0184354227 0.0670038015 0.0045081733 0.0418300000 421757689 0 402718720 0.0224907491 0.0506749749 -0.1168773025 2692 1311867808.4447789192 0.0111779319 0.0184327268 0.0670038015 0.0045079663 0.0434770000 421761157 0 402718720 0.0247970130 0.0521282479 -0.1163837686 2693 1311867808.4827229977 0.0122493785 0.0184304307 0.0670038015 0.0045086012 0.0440810000 421764337 0 402718720 0.0219056141 0.0521861129 -0.1177931204 2694 1311867808.5103700161 0.0094236685 0.0184270874 0.0670038015 0.0045125419 0.0435110000 421767381 0 402718720 0.0229724552 0.0497295223 -0.1163309962 2695 1311867808.5431969166 0.0126739424 0.0184249527 0.0670038015 0.0045125317 0.0427400000 421770641 0 402718720 0.0230880864 0.0536806621 -0.1180761978 2696 1311867808.5788240433 0.0114969425 0.0184223829 0.0670038015 0.0045118819 0.0426960000 421773605 0 402718720 0.0235028267 0.0515104905 -0.1182827726 2697 1311867808.6111960411 0.0125683118 0.0184202123 0.0670038015 0.0045111527 0.0426430000 421776753 0 402718720 0.0227663852 0.0512304492 -0.1196670458 2698 1311867808.6424980164 0.0118602086 0.0184177809 0.0670038015 0.0045105798 0.0426080000 421779965 0 402718720 0.0226026494 0.0512713604 -0.1189810038 2699 1311867808.6796329021 0.0122875581 0.0184155096 0.0670038015 0.0045100213 0.0404880000 421783105 0 402718720 0.0223849341 0.0513908342 -0.1193922237 2700 1311867808.7121589184 0.0128213577 0.0184134377 0.0670038015 0.0045092682 0.0424600000 421786237 0 402718720 0.0230090395 0.0517798662 -0.1199966222 2701 1311867808.7424249649 0.0123979608 0.0184112106 0.0670038015 0.0045096577 0.0406170000 421789665 0 402718720 0.0234260447 0.0498264134 -0.1207253858 2702 1311867808.7797210217 0.0114647960 0.0184086397 0.0670038015 0.0045098072 0.0425320000 421793245 0 402718720 0.0229354985 0.0490757376 -0.1205625087 2703 1311867808.8102169037 0.0137123568 0.0184069023 0.0670038015 0.0045097133 0.0405940000 421796145 0 402718720 0.0234903973 0.0515702069 -0.1225661635 2704 1311867808.8426899910 0.0122760404 0.0184046350 0.0670038015 0.0045133662 0.0431840000 421798909 0 402718720 0.0255644564 0.0501489639 -0.1220841259 2705 1311867808.8811960220 0.0111694010 0.0184019602 0.0670038015 0.0045126632 0.0430460000 421802409 0 402718720 0.0270472132 0.0491103716 -0.1220624596 2706 1311867808.9101860523 0.0129338568 0.0183999395 0.0670038015 0.0045122420 0.0430220000 421805717 0 402718720 0.0266462285 0.0505764186 -0.1234320849 2707 1311867808.9424829483 0.0109272180 0.0183971790 0.0670038015 0.0045116653 0.0517830000 421808553 0 402718720 0.0261139162 0.0472830720 -0.1238084957 2708 1311867808.9811229706 0.0120898401 0.0183948498 0.0670038015 0.0045125161 0.0410720000 421812269 0 402718720 0.0251506697 0.0468756631 -0.1258153617 2709 1311867809.0102269650 0.0141394483 0.0183932790 0.0670038015 0.0045120756 0.0526920000 421815385 0 402718720 0.0245217551 0.0485744588 -0.1270353943 2710 1311867809.0425639153 0.0112533495 0.0183906443 0.0670038015 0.0045115392 0.0422560000 421818285 0 402718720 0.0270970426 0.0462714769 -0.1260307729 2711 1311867809.0782320499 0.0128428517 0.0183885979 0.0670038015 0.0045117360 0.0408710000 421821329 0 402718720 0.0249453280 0.0465462059 -0.1278546154 2712 1311867809.1110110283 0.0141197685 0.0183870239 0.0670038015 0.0045116518 0.0407400000 421824597 0 402718720 0.0245090928 0.0498092845 -0.1278211325 2713 1311867809.1425359249 0.0133901108 0.0183851820 0.0670038015 0.0045126207 0.0426950000 421828001 0 402718720 0.0273500383 0.0483825654 -0.1286056489 2714 1311867809.1801810265 0.0118362652 0.0183827690 0.0670038015 0.0045133946 0.0411850000 421831133 0 402718720 0.0262020063 0.0487958677 -0.1270287037 2715 1311867809.2120649815 0.0142357433 0.0183812416 0.0670038015 0.0045129617 0.0431230000 421834361 0 402718720 0.0284347329 0.0510611124 -0.1288533658 2716 1311867809.2422831059 0.0159462187 0.0183803450 0.0670038015 0.0045123481 0.0416910000 421837253 0 402718720 0.0258454625 0.0499302000 -0.1315254867 2717 1311867809.2790520191 0.0145917684 0.0183789506 0.0670038015 0.0045115584 0.0433710000 421840721 0 402718720 0.0246793069 0.0492408648 -0.1300668716 2718 1311867809.3103950024 0.0146008693 0.0183775606 0.0670038015 0.0045108543 0.0431210000 421843821 0 402718720 0.0271671098 0.0492252074 -0.1306809187 2719 1311867809.3436670303 0.0148593094 0.0183762666 0.0670038015 0.0045102795 0.0567450000 421846833 0 402718720 0.0282985680 0.0495348796 -0.1311395019 2720 1311867809.3787779808 0.0138576077 0.0183746054 0.0670038015 0.0045095087 0.0412100000 421850045 0 402718720 0.0281570312 0.0480743125 -0.1309797913 2721 1311867809.4101309776 0.0131057184 0.0183726690 0.0670038015 0.0045088839 0.0412850000 421853193 0 402718720 0.0284432285 0.0493413582 -0.1294298619 2722 1311867809.4475460052 0.0140398769 0.0183710772 0.0670038015 0.0045094214 0.0412110000 421856765 0 402718720 0.0302946121 0.0485649183 -0.1314821988 2723 1311867809.4785499573 0.0120015508 0.0183687381 0.0670038015 0.0045088624 0.0590340000 421859777 0 402718720 0.0324287899 0.0487329252 -0.1298010349 2724 1311867809.5100600719 0.0140028233 0.0183671353 0.0670038015 0.0045088109 0.0514710000 421863005 0 402718720 0.0334452316 0.0501601771 -0.1318891644 2725 1311867809.5460391045 0.0157146528 0.0183661619 0.0670038015 0.0045082477 0.0540390000 421866193 0 402718720 0.0335195065 0.0516898781 -0.1335693449 2726 1311867809.5791211128 0.0144123109 0.0183647115 0.0670038015 0.0045074779 0.0427640000 421869469 0 402718720 0.0340417735 0.0501219220 -0.1335324347 2727 1311867809.6122300625 0.0151821747 0.0183635444 0.0670038015 0.0045067530 0.0428430000 421872609 0 402718720 0.0340116099 0.0492125787 -0.1349852979 2728 1311867809.6463921070 0.0151405968 0.0183623630 0.0670038015 0.0045064470 0.0425530000 421875877 0 402718720 0.0338400975 0.0520904586 -0.1337436885 2729 1311867809.6796839237 0.0155104194 0.0183613180 0.0670038015 0.0045057763 0.0426890000 421878833 0 402718720 0.0367388725 0.0525603928 -0.1345663816 2730 1311867809.7111020088 0.0151758892 0.0183601511 0.0670038015 0.0045050988 0.0407420000 421882253 0 402718720 0.0376530774 0.0527908094 -0.1345384419 2731 1311867809.7464809418 0.0136538744 0.0183584279 0.0670038015 0.0045047634 0.0426100000 421885337 0 402718720 0.0383042581 0.0496477708 -0.1352248788 2732 1311867809.7800478935 0.0153432386 0.0183573242 0.0670038015 0.0045042472 0.0424490000 421888357 0 402718720 0.0390541852 0.0508057922 -0.1374322623 2733 1311867809.8107759953 0.0130717726 0.0183553902 0.0670038015 0.0045035731 0.0500850000 422368861 0 402718720 0.0395939574 0.0503807962 -0.1359961033 2734 1311867809.8470799923 0.0139259603 0.0183537701 0.0670038015 0.0045030364 0.1139530000 422366509 0 402718720 0.0401779525 0.0480631292 -0.1389239877 2735 1311867809.8791100979 0.0158602465 0.0183528584 0.0670038015 0.0045023690 0.1219780000 422368881 0 402718720 0.0402628146 0.0482445918 -0.1418254226 2736 1311867809.9124441147 0.0161637999 0.0183520583 0.0670038015 0.0045022824 0.1176050000 427129697 0 402718720 0.0397894457 0.0480988696 -0.1430225968 2737 1311867809.9469900131 0.0153000588 0.0183509432 0.0670038015 0.0045017122 0.0892240000 434193413 0 402718720 0.0431585461 0.0475176200 -0.1439401060 2738 1311867809.9805769920 0.0172935184 0.0183505570 0.0670038015 0.0045014812 0.1004030000 433698037 0 402718720 0.0418744646 0.0479714572 -0.1464155018 2739 1311867810.0119459629 0.0177727472 0.0183503460 0.0670038015 0.0045006805 0.0533850000 433835641 0 402718720 0.0418823920 0.0491152555 -0.1469972730 2740 1311867810.0470910072 0.0172619745 0.0183499488 0.0670038015 0.0045002196 0.1265420000 432462293 0 402718720 0.0403037779 0.0495350510 -0.1461972296 2741 1311867810.0808799267 0.0181634389 0.0183498808 0.0670038015 0.0045004054 0.0509220000 422343445 0 402718720 0.0400923267 0.0522260554 -0.1460386515 2742 1311867810.1118919849 0.0208290182 0.0183507849 0.0670038015 0.0045001953 0.0420500000 422346465 0 402718720 0.0395385101 0.0520371310 -0.1493709534 2743 1311867810.1474719048 0.0176291093 0.0183505218 0.0670038015 0.0044994758 0.0414670000 422349405 0 402718720 0.0417702720 0.0525971837 -0.1463692337 2744 1311867810.1817660332 0.0171975233 0.0183501016 0.0670038015 0.0044991040 0.0426260000 422352697 0 402718720 0.0431057289 0.0505718589 -0.1475907564 2745 1311867810.2106039524 0.0175193101 0.0183497990 0.0670038015 0.0044989794 0.0428090000 422356173 0 402718720 0.0403615832 0.0514170118 -0.1477115750 2746 1311867810.2471721172 0.0164191518 0.0183490959 0.0670038015 0.0044998524 0.0427130000 422358873 0 402718720 0.0423213765 0.0534088947 -0.1465992033 2747 1311867810.2785871029 0.0162807815 0.0183483430 0.0670038015 0.0044992275 0.0429270000 422362413 0 402718720 0.0428548194 0.0533050932 -0.1474207193 2748 1311867810.3111360073 0.0164228287 0.0183476423 0.0670038015 0.0044984908 0.0414660000 422365745 0 402718720 0.0424434766 0.0531857982 -0.1485372335 2749 1311867810.3463029861 0.0161741022 0.0183468516 0.0670038015 0.0044978096 0.0413300000 422369005 0 402718720 0.0421486497 0.0526948608 -0.1492886394 2750 1311867810.3784830570 0.0156177497 0.0183458592 0.0670038015 0.0044978507 0.0428240000 422372145 0 402718720 0.0419680923 0.0530480295 -0.1493142247 2751 1311867810.4100239277 0.0169845130 0.0183453643 0.0670038015 0.0044974415 0.0413630000 422375053 0 402718720 0.0400100984 0.0532871112 -0.1509986371 2752 1311867810.4462749958 0.0162679590 0.0183446095 0.0670038015 0.0044967507 0.0420420000 422378377 0 402718720 0.0400510654 0.0523786582 -0.1516320258 2753 1311867810.4781119823 0.0147435404 0.0183433014 0.0670038015 0.0044962870 0.0411110000 422381213 0 402718720 0.0424051620 0.0541441590 -0.1499778628 2754 1311867810.5101990700 0.0157123394 0.0183423461 0.0670038015 0.0044958388 0.0413310000 422384809 0 402718720 0.0405891985 0.0549805835 -0.1509189159 2755 1311867810.5459640026 0.0150541756 0.0183411526 0.0670038015 0.0044959418 0.0414780000 422388005 0 402718720 0.0409213714 0.0527800173 -0.1526825875 2756 1311867810.5791409016 0.0153732402 0.0183400757 0.0670038015 0.0044952064 0.0419990000 422390769 0 402718720 0.0406958275 0.0541584566 -0.1529751569 2757 1311867810.6141140461 0.0160695761 0.0183392521 0.0670038015 0.0044945732 0.0424170000 422394093 0 402718720 0.0400569551 0.0562194735 -0.1528983712 2758 1311867810.6471910477 0.0150572034 0.0183380621 0.0670038015 0.0044940058 0.0406790000 422397505 0 402718720 0.0403144285 0.0550906956 -0.1532076150 2759 1311867810.6781129837 0.0160251800 0.0183372238 0.0670038015 0.0044932523 0.0424420000 422400597 0 402718720 0.0396215320 0.0552298799 -0.1549667865 2760 1311867810.7146449089 0.0150434189 0.0183360304 0.0670038015 0.0044928480 0.0413210000 422403889 0 402718720 0.0396089777 0.0575198196 -0.1529590786 2761 1311867810.7468900681 0.0143228499 0.0183345769 0.0670038015 0.0044927144 0.0416710000 422407093 0 402718720 0.0406471454 0.0558686405 -0.1548597515 2762 1311867810.7789669037 0.0163676236 0.0183338647 0.0670038015 0.0044931203 0.0422210000 422409937 0 402718720 0.0381571278 0.0571281426 -0.1565452218 2763 1311867810.8146491051 0.0148166725 0.0183325918 0.0670038015 0.0044925649 0.0545450000 422413461 0 402718720 0.0403855518 0.0567967594 -0.1566600353 2764 1311867810.8460769653 0.0162204001 0.0183318276 0.0670038015 0.0044953658 0.0527190000 422416497 0 402718720 0.0392241403 0.0578559712 -0.1568689197 2765 1311867810.8793289661 0.0165266395 0.0183311747 0.0670038015 0.0044947177 0.0504550000 422419829 0 402718720 0.0389940813 0.0590572134 -0.1566112638 2766 1311867810.9141631126 0.0154902982 0.0183301477 0.0670038015 0.0044959656 0.0416580000 422423153 0 402718720 0.0408341773 0.0594030917 -0.1564907432 2767 1311867810.9458940029 0.0148982778 0.0183289074 0.0670038015 0.0045012795 0.0418740000 422426325 0 402718720 0.0412262119 0.0596955866 -0.1573697776 2768 1311867810.9796259403 0.0181570631 0.0183288453 0.0670038015 0.0045005822 0.0430790000 422429217 0 402718720 0.0385624245 0.0605560467 -0.1602869779 2769 1311867811.0151500702 0.0185188279 0.0183289139 0.0670038015 0.0045065876 0.0429090000 422432477 0 402718720 0.0405228920 0.0611098632 -0.1610130966 2770 1311867811.0469939709 0.0163604822 0.0183282033 0.0670038015 0.0045073041 0.0421970000 422435881 0 402718720 0.0408434421 0.0610947236 -0.1593045592 2771 1311867811.0785760880 0.0160112940 0.0183273672 0.0670038015 0.0045070392 0.0508310000 422438453 0 402718720 0.0414522402 0.0620686337 -0.1594458967 2772 1311867811.1144239902 0.0164152756 0.0183266774 0.0670038015 0.0045069918 0.0416270000 422442033 0 402718720 0.0421879701 0.0637047589 -0.1602084935 2773 1311867811.1461989880 0.0170015879 0.0183261995 0.0670038015 0.0045070758 0.0540340000 422445333 0 402718720 0.0414388739 0.0645956099 -0.1612705141 2774 1311867811.1786370277 0.0176442359 0.0183259537 0.0670038015 0.0045067242 0.0421520000 422448601 0 402718720 0.0416808352 0.0646803528 -0.1630288064 2775 1311867811.2142488956 0.0174069982 0.0183256225 0.0670038015 0.0045064932 0.0427480000 422451813 0 402718720 0.0424892008 0.0648372322 -0.1635390073 2776 1311867811.2464840412 0.0169667266 0.0183251330 0.0670038015 0.0045059984 0.0413280000 422454889 0 402718720 0.0413047858 0.0649046153 -0.1631459445 2777 1311867811.2798390388 0.0174715742 0.0183248256 0.0670038015 0.0045057251 0.0415290000 422457901 0 402718720 0.0410886332 0.0676699057 -0.1625961363 2778 1311867811.3147039413 0.0169421267 0.0183243279 0.0670038015 0.0045055893 0.0412820000 422461617 0 402718720 0.0426799357 0.0678127259 -0.1639576405 2779 1311867811.3470849991 0.0161723699 0.0183235535 0.0670038015 0.0045063657 0.0413960000 422464381 0 402718720 0.0434258729 0.0672271997 -0.1635806412 2780 1311867811.3799240589 0.0154163996 0.0183225078 0.0670038015 0.0045064902 0.0424780000 422467657 0 402718720 0.0434288345 0.0685124248 -0.1625681520 2781 1311867811.4141869545 0.0165949203 0.0183218866 0.0670038015 0.0045064681 0.0415040000 422470605 0 402718720 0.0429233089 0.0693064183 -0.1639394015 2782 1311867811.4464430809 0.0168752931 0.0183213666 0.0670038015 0.0045057271 0.0408190000 422474017 0 402718720 0.0444146059 0.0705598742 -0.1645188779 2783 1311867811.4788289070 0.0160803795 0.0183205614 0.0670038015 0.0045057990 0.0409070000 422477349 0 402718720 0.0435253605 0.0709387064 -0.1638500243 2784 1311867811.5141620636 0.0170106515 0.0183200908 0.0670038015 0.0045061201 0.0408630000 422480449 0 402718720 0.0459813625 0.0732921362 -0.1658537686 2785 1311867811.5465340614 0.0159463286 0.0183192385 0.0670038015 0.0045063917 0.0400590000 422483653 0 402718720 0.0455563739 0.0733184814 -0.1647735685 2786 1311867811.5787150860 0.0208312590 0.0183201402 0.0670038015 0.0045071778 0.0398750000 422486801 0 402718720 0.0446460806 0.0747009814 -0.1696350127 2787 1311867811.6143789291 0.0207841080 0.0183210243 0.0670038015 0.0045080849 0.0405510000 422489877 0 402718720 0.0433838479 0.0742294341 -0.1693164259 2788 1311867811.6465210915 0.0181035548 0.0183209463 0.0670038015 0.0045114910 0.0587230000 423001657 0 402718720 0.0445883460 0.0753460005 -0.1660092324 2789 1311867811.6790111065 0.0158787053 0.0183200706 0.0670038015 0.0045129995 0.1199410000 422994041 0 402718720 0.0481073447 0.0748407990 -0.1649755388 2790 1311867811.7141160965 0.0155108785 0.0183190637 0.0670038015 0.0045140776 0.1205010000 422997817 0 402718720 0.0468482561 0.0747159347 -0.1646498293 2791 1311867811.7471590042 0.0176536571 0.0183188253 0.0670038015 0.0045143005 0.1159920000 428402157 0 402718720 0.0457902178 0.0763883963 -0.1659885347 2792 1311867811.7787630558 0.0178119633 0.0183186438 0.0670038015 0.0045140693 0.0853240000 434455321 0 402718720 0.0462265164 0.0753831118 -0.1671857089 2793 1311867811.8140239716 0.0185193066 0.0183187156 0.0670038015 0.0045132895 0.0983720000 434214189 0 402718720 0.0460552797 0.0758508891 -0.1679098606 2794 1311867811.8467700481 0.0195461307 0.0183191549 0.0670038015 0.0045131900 0.0534660000 434353041 0 402718720 0.0470217317 0.0761505365 -0.1694882363 2795 1311867811.8873019218 0.0186361447 0.0183192683 0.0670038015 0.0045127758 0.1233870000 432982141 0 402718720 0.0472167246 0.0755650252 -0.1689607650 2796 1311867811.9162950516 0.0201817863 0.0183199345 0.0670038015 0.0045121425 0.0544870000 423013005 0 402718720 0.0467321798 0.0747428164 -0.1710473001 2797 1311867811.9480459690 0.0177866127 0.0183197438 0.0670038015 0.0045114329 0.0419240000 423016161 0 402718720 0.0478482582 0.0755312890 -0.1686303020 2798 1311867811.9825990200 0.0176564772 0.0183195067 0.0670038015 0.0045111076 0.0415920000 423019677 0 402718720 0.0487758107 0.0758106411 -0.1687880009 2799 1311867812.0155920982 0.0174149908 0.0183191836 0.0670038015 0.0045104430 0.0430130000 423022521 0 402718720 0.0488427430 0.0750160962 -0.1690958291 2800 1311867812.0471529961 0.0182547793 0.0183191606 0.0670038015 0.0045096750 0.0413460000 423025605 0 402718720 0.0486119762 0.0747561902 -0.1702989489 2801 1311867812.0860528946 0.0172200911 0.0183187682 0.0670038015 0.0045090792 0.0410170000 423028721 0 402718720 0.0490188599 0.0757836550 -0.1689062715 2802 1311867812.1176469326 0.0167204849 0.0183181978 0.0670038015 0.0045084561 0.0491300000 423031997 0 402718720 0.0485523567 0.0753152668 -0.1683503985 2803 1311867812.1501319408 0.0191543680 0.0183184961 0.0670038015 0.0045076944 0.0429780000 423035233 0 402718720 0.0481071100 0.0765023082 -0.1703491509 2804 1311867812.1841530800 0.0185584817 0.0183185817 0.0670038015 0.0045069528 0.0660860000 423038621 0 402718720 0.0494451448 0.0767704546 -0.1698450446 2805 1311867812.2161788940 0.0162509345 0.0183178445 0.0670038015 0.0045128502 0.0426230000 423041593 0 402718720 0.0499510989 0.0763514340 -0.1688848883 2806 1311867812.2469139099 0.0174090210 0.0183175207 0.0670038015 0.0045121988 0.0423200000 423044829 0 402718720 0.0494389683 0.0765008777 -0.1699945629 2807 1311867812.2830879688 0.0191449076 0.0183178154 0.0670038015 0.0045215871 0.0411950000 423047985 0 402718720 0.0493998602 0.0767277107 -0.1704368144 2808 1311867812.3143959045 0.0175583251 0.0183175449 0.0670038015 0.0045300950 0.0429830000 423051405 0 402718720 0.0492252335 0.0774305537 -0.1693187207 2809 1311867812.3466560841 0.0165950749 0.0183169318 0.0670038015 0.0045293381 0.0426520000 423054481 0 402718720 0.0515075885 0.0779162198 -0.1687393785 2810 1311867812.3833289146 0.0167454574 0.0183163725 0.0670038015 0.0045289207 0.0412450000 423057749 0 402718720 0.0508043356 0.0774660259 -0.1689989716 2811 1311867812.4177269936 0.0162630137 0.0183156420 0.0670038015 0.0045281484 0.0411890000 423060889 0 402718720 0.0510834008 0.0770906657 -0.1687085032 2812 1311867812.4586019516 0.0161035284 0.0183148554 0.0670038015 0.0045275804 0.0416200000 423064325 0 402718720 0.0513452999 0.0791840851 -0.1675756723 2813 1311867812.4830911160 0.0154643757 0.0183138420 0.0670038015 0.0045269230 0.0421910000 423067345 0 402718720 0.0521505140 0.0780942589 -0.1678307950 2814 1311867812.5157220364 0.0161731169 0.0183130813 0.0670038015 0.0045306157 0.0413110000 423070117 0 402718720 0.0533792153 0.0791279450 -0.1679243892 2815 1311867812.5469310284 0.0153464656 0.0183120274 0.0670038015 0.0045299861 0.0425190000 423073329 0 402718720 0.0541811995 0.0791354030 -0.1671767682 2816 1311867812.5857439041 0.0166277792 0.0183114293 0.0670038015 0.0045292913 0.0422050000 423076661 0 402718720 0.0528476834 0.0799974799 -0.1681400388 2817 1311867812.6147639751 0.0164350085 0.0183107632 0.0670038015 0.0045285654 0.0523400000 423564385 0 402718720 0.0526683331 0.0786504969 -0.1686469615 2818 1311867812.6462490559 0.0172003116 0.0183103692 0.0670038015 0.0045283668 0.1257030000 423519217 0 402718720 0.0533498004 0.0793542862 -0.1699751765 2819 1311867812.6821310520 0.0162313152 0.0183096317 0.0670038015 0.0045277809 0.1167990000 423811485 0 402718720 0.0535656214 0.0785371214 -0.1693861932 2820 1311867812.7141439915 0.0171645731 0.0183092256 0.0670038015 0.0045270411 0.1155030000 432060373 0 402718720 0.0538630858 0.0796182975 -0.1701670736 2821 1311867812.7468860149 0.0183791984 0.0183092504 0.0670038015 0.0045263088 0.0573680000 435060865 0 402718720 0.0523315631 0.0796388611 -0.1711582839 2822 1311867812.7839629650 0.0176493265 0.0183090166 0.0670038015 0.0045255656 0.0772480000 434814589 0 402718720 0.0533070527 0.0801895559 -0.1706274152 2823 1311867812.8143351078 0.0156710166 0.0183080821 0.0670038015 0.0045252217 0.0515760000 434954849 0 402718720 0.0531603284 0.0806606710 -0.1674848348 2824 1311867812.8463029861 0.0175456293 0.0183078121 0.0670038015 0.0045245610 0.1260080000 433597029 0 402718720 0.0527116880 0.0808258057 -0.1696741730 2825 1311867812.8841478825 0.0191013850 0.0183080930 0.0670038015 0.0045266980 0.0764250000 423537101 0 402718720 0.0516902208 0.0817743689 -0.1716108918 2826 1311867812.9142088890 0.0170835145 0.0183076597 0.0670038015 0.0045259081 0.0418530000 423540425 0 402718720 0.0523605794 0.0816781819 -0.1698420793 2827 1311867812.9470400810 0.0173545759 0.0183073226 0.0670038015 0.0045255480 0.0423060000 423543629 0 402718720 0.0524625666 0.0817664862 -0.1704328358 2828 1311867812.9833469391 0.0174833480 0.0183070312 0.0670038015 0.0045260593 0.0412110000 423546849 0 402718720 0.0506363772 0.0830543935 -0.1696408242 2829 1311867813.0143780708 0.0159427822 0.0183061955 0.0670038015 0.0045329683 0.0412980000 423550125 0 402718720 0.0497708209 0.0830181241 -0.1689401418 2830 1311867813.0462698936 0.0167199541 0.0183056350 0.0670038015 0.0045414374 0.0425000000 423552889 0 402718720 0.0502181090 0.0831158608 -0.1688880026 2831 1311867813.0825068951 0.0168755762 0.0183051298 0.0670038015 0.0045461998 0.0409890000 423556141 0 402718720 0.0494841747 0.0836319923 -0.1699554622 2832 1311867813.1142160892 0.0169265401 0.0183046430 0.0670038015 0.0045498850 0.0496830000 423559545 0 402718720 0.0483414382 0.0842666477 -0.1687043309 2833 1311867813.1504809856 0.0156840924 0.0183037180 0.0670038015 0.0045504350 0.0506500000 423562941 0 402718720 0.0487360507 0.0830171555 -0.1683349609 2834 1311867813.1829130650 0.0154574122 0.0183027137 0.0670038015 0.0045502831 0.0426340000 423566017 0 402718720 0.0498485416 0.0853638500 -0.1674459130 2835 1311867813.2166841030 0.0184345674 0.0183027602 0.0670038015 0.0045499194 0.0523190000 423569037 0 402718720 0.0469576903 0.0857592970 -0.1706030667 2836 1311867813.2536849976 0.0164105911 0.0183020930 0.0670038015 0.0045508396 0.0413200000 423572361 0 402718720 0.0479882136 0.0843138099 -0.1693580747 2837 1311867813.2831010818 0.0149980858 0.0183009284 0.0670038015 0.0045612686 0.0472470000 423575325 0 402718720 0.0465426408 0.0847215950 -0.1679112613 2838 1311867813.3142321110 0.0158179626 0.0183000535 0.0670038015 0.0045628441 0.0572190000 424064361 0 402718720 0.0462011918 0.0866718292 -0.1686975360 2839 1311867813.3517169952 0.0173329189 0.0182997128 0.0670038015 0.0045802605 0.1321090000 424039157 0 402718720 0.0445323624 0.0869335085 -0.1683393568 2840 1311867813.3851261139 0.0168196131 0.0182991917 0.0670038015 0.0045796322 0.1531960000 424348593 0 402718720 0.0455844179 0.0860145912 -0.1687875539 2841 1311867813.4148280621 0.0161159392 0.0182984232 0.0670038015 0.0045965097 0.1148540000 432733329 0 402718720 0.0457918122 0.0880995691 -0.1688839048 2842 1311867813.4501829147 0.0186323579 0.0182985407 0.0670038015 0.0046140441 0.0635390000 436004069 0 402718720 0.0458406024 0.0875236690 -0.1705907881 2843 1311867813.4843769073 0.0182666983 0.0182985295 0.0670038015 0.0046147234 0.0647440000 435715121 0 402718720 0.0451836959 0.0876728669 -0.1694384664 2844 1311867813.5152790546 0.0184385311 0.0182985787 0.0670038015 0.0046201924 0.0518830000 435860645 0 402718720 0.0454875045 0.0885721892 -0.1707103550 2845 1311867813.5519089699 0.0155599052 0.0182976161 0.0670038015 0.0046258571 0.1280470000 434537665 0 402718720 0.0459601134 0.0906304568 -0.1674806178 2846 1311867813.5863409042 0.0177702438 0.0182974308 0.0670038015 0.0046252110 0.0769200000 424011181 0 402718720 0.0444492027 0.0922399312 -0.1689465493 2847 1311867813.6168019772 0.0181460548 0.0182973776 0.0670038015 0.0046390151 0.0411880000 424014273 0 402718720 0.0438288189 0.0931304395 -0.1676858515 2848 1311867813.6515810490 0.0161115266 0.0182966101 0.0670038015 0.0046392746 0.0637930000 424017541 0 402718720 0.0441030189 0.0944046900 -0.1656552404 2849 1311867813.6860060692 0.0150472010 0.0182954696 0.0670038015 0.0046387108 0.0400960000 424020745 0 402718720 0.0466772988 0.0950154439 -0.1657171845 2850 1311867813.7184169292 0.0141330650 0.0182940091 0.0670038015 0.0046380246 0.0416870000 424023957 0 402718720 0.0458310060 0.0950126797 -0.1651536077 2851 1311867813.7506020069 0.0158830248 0.0182931634 0.0670038015 0.0046373563 0.0421490000 424027137 0 402718720 0.0443013459 0.0953595862 -0.1672281772 2852 1311867813.7827889919 0.0171834696 0.0182927743 0.0670038015 0.0046366265 0.0405940000 424030021 0 402718720 0.0437641926 0.0963852704 -0.1685097218 2853 1311867813.8147668839 0.0151098445 0.0182916587 0.0670038015 0.0046359204 0.0618930000 424033585 0 402718720 0.0460598394 0.0969417244 -0.1672967225 2854 1311867813.8517930508 0.0145119047 0.0182903343 0.0670038015 0.0046351560 0.0505530000 424516005 0 402718720 0.0466451868 0.0977143869 -0.1671709716 2855 1311867813.8838069439 0.0144800832 0.0182889997 0.0670038015 0.0046349089 0.1204960000 424493137 0 402718720 0.0466534905 0.0984472781 -0.1674624830 2856 1311867813.9144020081 0.0152870659 0.0182879486 0.0670038015 0.0046341382 0.1149260000 424814117 0 402718720 0.0461603962 0.0988370478 -0.1689967066 2857 1311867813.9523379803 0.0138090029 0.0182863809 0.0670038015 0.0046335473 0.1089920000 431116077 0 402718720 0.0500492267 0.1001164913 -0.1687318236 2858 1311867813.9825320244 0.0114516169 0.0182839895 0.0670038015 0.0046335363 0.0652680000 436279461 0 402718720 0.0493552536 0.1015101001 -0.1655042171 2859 1311867814.0155770779 0.0135538010 0.0182823350 0.0670038015 0.0046361941 0.0838430000 436034873 0 402718720 0.0474863499 0.1030913740 -0.1664472669 2860 1311867814.0528070927 0.0125357099 0.0182803257 0.0670038015 0.0046354278 0.0515860000 435955269 0 402718720 0.0504531264 0.1049946621 -0.1657432914 2861 1311867814.0849530697 0.0140307955 0.0182788403 0.0670038015 0.0046350575 0.1174720000 434645181 0 402718720 0.0485032685 0.1037457734 -0.1688074917 2862 1311867814.1153879166 0.0151856681 0.0182777596 0.0670038015 0.0046348645 0.0546570000 424508453 0 402718720 0.0487281010 0.1047893465 -0.1700213999 2863 1311867814.1526429653 0.0126954671 0.0182758097 0.0670038015 0.0046341674 0.0410960000 424511761 0 402718720 0.0500264727 0.1055010408 -0.1670356095 2864 1311867814.1845281124 0.0132676819 0.0182740611 0.0670038015 0.0046342812 0.0402400000 424514941 0 402718720 0.0514818653 0.1068831682 -0.1676521897 2865 1311867814.2153480053 0.0138831735 0.0182725285 0.0670038015 0.0046339913 0.0423870000 424518009 0 402718720 0.0507028140 0.1064473540 -0.1686467081 2866 1311867814.2520170212 0.0150720123 0.0182714118 0.0670038015 0.0046335339 0.0415960000 424521261 0 402718720 0.0506941564 0.1058873981 -0.1708114147 2867 1311867814.2834239006 0.0140932780 0.0182699545 0.0670038015 0.0046329419 0.0412840000 424524593 0 402718720 0.0514825396 0.1069823280 -0.1693762690 2868 1311867814.3181779385 0.0141343391 0.0182685125 0.0670038015 0.0046324101 0.0488550000 424527477 0 402718720 0.0519908592 0.1071128547 -0.1702330261 2869 1311867814.3510050774 0.0158936214 0.0182676847 0.0670038015 0.0046336801 0.0411120000 424530953 0 402718720 0.0502953827 0.1080517769 -0.1713384390 2870 1311867814.3861339092 0.0146612935 0.0182664281 0.0670038015 0.0046330618 0.0482410000 424993977 0 402718720 0.0527134538 0.1084192917 -0.1712996364 2871 1311867814.4182898998 0.0148015255 0.0182652213 0.0670038015 0.0046332026 0.1145640000 424976325 0 402718720 0.0527840517 0.1087846160 -0.1721066684 2872 1311867814.4512650967 0.0166315064 0.0182646524 0.0670038015 0.0046325324 0.1109400000 425308401 0 402718720 0.0509904027 0.1103313118 -0.1734142303 2873 1311867814.4847788811 0.0167761855 0.0182641343 0.0670038015 0.0046321002 0.1088680000 431890481 0 402718720 0.0501472577 0.1092356816 -0.1744379550 2874 1311867814.5201790333 0.0160776135 0.0182633735 0.0670038015 0.0046390754 0.0597840000 436904973 0 402718720 0.0500669740 0.1103945374 -0.1742695421 2875 1311867814.5517210960 0.0154129919 0.0182623821 0.0670038015 0.0046388237 0.1255580000 435347317 0 402718720 0.0515628085 0.1102424413 -0.1744092256 2876 1311867814.5848219395 0.0169229731 0.0182619164 0.0670038015 0.0046381210 0.0446790000 424948313 0 402718720 0.0497533269 0.1109461635 -0.1754016876 2877 1311867814.6200098991 0.0187080558 0.0182620714 0.0670038015 0.0046374583 0.0408620000 424951325 0 402718720 0.0497609079 0.1110621169 -0.1777555645 2878 1311867814.6503028870 0.0191755630 0.0182623889 0.0670038015 0.0046366851 0.0413520000 424954345 0 402718720 0.0488527305 0.1121881232 -0.1776840389 2879 1311867814.6833140850 0.0170065016 0.0182619526 0.0670038015 0.0046361854 0.0409780000 424957621 0 402718720 0.0483142585 0.1123571843 -0.1751312166 2880 1311867814.7211821079 0.0156726874 0.0182610536 0.0670038015 0.0046361869 0.0398630000 424960745 0 402718720 0.0479785465 0.1130599082 -0.1735124737 2881 1311867814.7502319813 0.0186879467 0.0182612018 0.0670038015 0.0046355121 0.0415730000 424964205 0 402718720 0.0456957743 0.1145446375 -0.1755722761 2882 1311867814.7828900814 0.0170576926 0.0182607842 0.0670038015 0.0046350919 0.0512400000 424967321 0 402718720 0.0451714136 0.1142842025 -0.1737742573 2883 1311867814.8186480999 0.0149633447 0.0182596404 0.0670038015 0.0046356486 0.0399430000 424970517 0 402718720 0.0459151566 0.1146512926 -0.1714290380 2884 1311867814.8526010513 0.0161406770 0.0182589057 0.0670038015 0.0046353365 0.0482600000 424973801 0 402718720 0.0464161448 0.1158253476 -0.1726113111 2885 1311867814.8852329254 0.0170015171 0.0182584698 0.0670038015 0.0046349479 0.0401520000 424977013 0 402718720 0.0460789539 0.1164308488 -0.1732634455 2886 1311867814.9202771187 0.0182853732 0.0182584792 0.0670038015 0.0046345436 0.0397570000 424979825 0 402718720 0.0450141467 0.1168961525 -0.1740469337 2887 1311867814.9503459930 0.0168785360 0.0182580012 0.0670038015 0.0046346541 0.0398000000 424983173 0 402718720 0.0455887578 0.1163885072 -0.1727536619 2888 1311867814.9839959145 0.0175206643 0.0182577459 0.0670038015 0.0046362220 0.0400490000 424986377 0 402718720 0.0458008386 0.1186233237 -0.1721125841 2889 1311867815.0193099976 0.0177070498 0.0182575552 0.0670038015 0.0046378306 0.0395640000 424989733 0 402718720 0.0450376906 0.1185266301 -0.1714637727 2890 1311867815.0509970188 0.0172183830 0.0182571957 0.0670038015 0.0046371731 0.0506800000 424992713 0 402718720 0.0450997315 0.1194832772 -0.1703493893 2891 1311867815.0835149288 0.0140316095 0.0182557340 0.0670038015 0.0046365570 0.0405840000 424995845 0 402718720 0.0478975028 0.1198112145 -0.1674316078 2892 1311867815.1192519665 0.0173629746 0.0182554253 0.0670038015 0.0046360667 0.0404020000 424999041 0 402718720 0.0479730219 0.1211582273 -0.1712031215 2893 1311867815.1505639553 0.0154963844 0.0182544716 0.0670038015 0.0046357422 0.0458270000 425002197 0 402718720 0.0487703010 0.1209044605 -0.1693032980 2894 1311867815.1827230453 0.0151222460 0.0182533893 0.0670038015 0.0046361503 0.0466630000 425005609 0 402718720 0.0525024049 0.1219815910 -0.1696531624 2895 1311867815.2192549706 0.0176537689 0.0182531822 0.0670038015 0.0046380468 0.0452800000 425008741 0 402718720 0.0489134230 0.1216440946 -0.1715891063 2896 1311867815.2503280640 0.0171408802 0.0182527981 0.0670038015 0.0046375235 0.0449220000 425011833 0 402718720 0.0504065305 0.1222887039 -0.1711852401 2897 1311867815.2826719284 0.0169373844 0.0182523441 0.0670038015 0.0046369444 0.0457430000 425014973 0 402718720 0.0508558191 0.1220854446 -0.1712652594 2898 1311867815.3188140392 0.0168805681 0.0182518707 0.0670038015 0.0046363393 0.0446070000 425018297 0 402718720 0.0520104580 0.1220744550 -0.1716184318 2899 1311867815.3506569862 0.0189522505 0.0182521123 0.0670038015 0.0046358452 0.0449900000 425021325 0 402718720 0.0516288057 0.1232142448 -0.1730867177 2900 1311867815.3841490746 0.0178344436 0.0182519683 0.0670038015 0.0046354222 0.0456330000 425024721 0 402718720 0.0535221696 0.1234383285 -0.1721150428 2901 1311867815.4187209606 0.0207334887 0.0182528237 0.0670038015 0.0046353237 0.0456910000 425027725 0 402718720 0.0532035157 0.1244556755 -0.1746310890 2902 1311867815.4505259991 0.0214290041 0.0182539182 0.0670038015 0.0046346087 0.0452460000 425030817 0 402718720 0.0516998097 0.1236121953 -0.1748819500 2903 1311867815.4827210903 0.0189540740 0.0182541593 0.0670038015 0.0046339426 0.0452140000 425033893 0 402718720 0.0530946143 0.1242753267 -0.1720403582 2904 1311867815.5188379288 0.0213807244 0.0182552360 0.0670038015 0.0046336417 0.0445320000 425037217 0 402718720 0.0545843244 0.1256003082 -0.1745702326 2905 1311867815.5508639812 0.0228682552 0.0182568239 0.0670038015 0.0046329952 0.0446720000 425040325 0 402718720 0.0528064445 0.1243350878 -0.1756083071 2906 1311867815.5879790783 0.0206440855 0.0182576454 0.0670038015 0.0046329710 0.0604630000 425583453 0 402718720 0.0532269180 0.1242602915 -0.1728130728 2907 1311867815.6201279163 0.0188507698 0.0182578495 0.0670038015 0.0046348788 0.1210810000 425542513 0 402718720 0.0538277030 0.1259170771 -0.1699657142 2908 1311867815.6522359848 0.0218684804 0.0182590911 0.0670038015 0.0046342701 0.1113830000 425860181 0 402718720 0.0524101965 0.1256317794 -0.1725344509 2909 1311867815.6869289875 0.0185967200 0.0182592072 0.0670038015 0.0046348234 0.1105530000 434402397 0 402718720 0.0560717434 0.1262780279 -0.1695587486 2910 1311867815.7186810970 0.0195931736 0.0182596656 0.0670038015 0.0046368227 0.0577110000 437732837 0 402718720 0.0564377643 0.1261138618 -0.1707221866 2911 1311867815.7527859211 0.0191800259 0.0182599817 0.0670038015 0.0046470582 0.0851450000 437482545 0 402718720 0.0546427220 0.1255869418 -0.1712072939 2912 1311867815.7881309986 0.0184957348 0.0182600627 0.0670038015 0.0046464046 0.0522320000 437392097 0 402718720 0.0562864617 0.1256649196 -0.1706338227 2913 1311867815.8185119629 0.0213050842 0.0182611080 0.0670038015 0.0046619438 0.1228020000 436063005 0 402718720 0.0543834120 0.1265619248 -0.1706412584 2914 1311867815.8516321182 0.0192188863 0.0182614367 0.0670038015 0.0046612778 0.0829080000 425470385 0 402718720 0.0559685081 0.1265102923 -0.1686752886 2915 1311867815.8881559372 0.0178955607 0.0182613112 0.0670038015 0.0046607877 0.0404650000 425473765 0 402718720 0.0573968515 0.1258897483 -0.1677649766 2916 1311867815.9183700085 0.0188408960 0.0182615099 0.0670038015 0.0046615468 0.0413640000 425476865 0 402718720 0.0566227026 0.1287095100 -0.1668834090 2917 1311867815.9544029236 0.0204829667 0.0182622715 0.0670038015 0.0046620051 0.0415450000 425480125 0 402718720 0.0565477982 0.1276215464 -0.1687218249 2918 1311867815.9880459309 0.0193344541 0.0182626389 0.0670038015 0.0046649893 0.0392300000 425483633 0 402718720 0.0577966347 0.1281819642 -0.1664764434 2919 1311867816.0232369900 0.0190402679 0.0182629053 0.0670038015 0.0046702350 0.0391500000 425486653 0 402718720 0.0573663190 0.1294114143 -0.1657178998 2920 1311867816.0513160229 0.0203529354 0.0182636211 0.0670038015 0.0046704741 0.0390580000 425489825 0 402718720 0.0574156940 0.1288002878 -0.1675816774 2921 1311867816.0872139931 0.0172881465 0.0182632871 0.0670038015 0.0046718117 0.0506500000 425493093 0 402718720 0.0594795495 0.1302212030 -0.1642725170 2922 1311867816.1192660332 0.0191889480 0.0182636039 0.0670038015 0.0046711513 0.0394480000 425496137 0 402718720 0.0598187447 0.1303458810 -0.1665396094 2923 1311867816.1530499458 0.0183512811 0.0182636339 0.0670038015 0.0046705881 0.0513470000 425499069 0 402718720 0.0611627512 0.1302248985 -0.1661870480 2924 1311867816.1877670288 0.0196454041 0.0182641065 0.0670038015 0.0046703090 0.0403120000 425502473 0 402718720 0.0597247630 0.1308341175 -0.1662485749 2925 1311867816.2185130119 0.0199253839 0.0182646744 0.0670038015 0.0046709046 0.0406760000 425505493 0 402718720 0.0619686097 0.1309336722 -0.1673339605 2926 1311867816.2509930134 0.0206912141 0.0182655037 0.0670038015 0.0046754851 0.0393600000 425508793 0 402718720 0.0592404231 0.1317923814 -0.1669179797 2927 1311867816.2875878811 0.0193889085 0.0182658876 0.0670038015 0.0046755411 0.0405820000 425512181 0 402718720 0.0602578893 0.1322049499 -0.1658669114 2928 1311867816.3221759796 0.0192051735 0.0182662083 0.0670038015 0.0046751274 0.0504780000 425515201 0 402718720 0.0633305311 0.1330303997 -0.1669044495 2929 1311867816.3515660763 0.0164501164 0.0182655883 0.0670038015 0.0046745180 0.0495150000 425518045 0 402718720 0.0644375160 0.1326017082 -0.1643995345 2930 1311867816.3902490139 0.0183172412 0.0182656059 0.0670038015 0.0046743144 0.0502030000 425521873 0 402718720 0.0638087243 0.1320442706 -0.1664564908 2931 1311867816.4188189507 0.0183147863 0.0182656227 0.0670038015 0.0046735788 0.0405080000 425524901 0 402718720 0.0652886182 0.1322482973 -0.1672866642 2932 1311867816.4527490139 0.0153469406 0.0182646273 0.0670038015 0.0046732645 0.0402850000 425528025 0 402718720 0.0650091842 0.1312773228 -0.1644126624 2933 1311867816.4875969887 0.0182855818 0.0182646344 0.0670038015 0.0046747064 0.0402150000 425531037 0 402718720 0.0637168139 0.1315076649 -0.1671669781 2934 1311867816.5199189186 0.0173035804 0.0182643068 0.0670038015 0.0046746216 0.0401920000 425534129 0 402718720 0.0641300231 0.1307481974 -0.1666293293 2935 1311867816.5529119968 0.0161567684 0.0182635888 0.0670038015 0.0046757075 0.0391650000 425537389 0 402718720 0.0657767355 0.1291783452 -0.1670043766 2936 1311867816.5888628960 0.0177730061 0.0182634217 0.0670038015 0.0046750319 0.0504870000 425540713 0 402718720 0.0649542883 0.1287786961 -0.1689188480 2937 1311867816.6194050312 0.0176655166 0.0182632181 0.0670038015 0.0046750503 0.0392320000 425543837 0 402718720 0.0645555556 0.1302566826 -0.1685075611 2938 1311867816.6509261131 0.0174067058 0.0182629266 0.0670038015 0.0046748557 0.0403890000 425547185 0 402718720 0.0627235621 0.1300601065 -0.1677983552 2939 1311867816.6893680096 0.0191908088 0.0182632423 0.0670038015 0.0046743532 0.0504590000 425550317 0 402718720 0.0626591146 0.1281475425 -0.1711606532 2940 1311867816.7204029560 0.0215282068 0.0182643528 0.0670038015 0.0046748086 0.0398640000 425553545 0 402718720 0.0613080077 0.1289569736 -0.1733119190 2941 1311867816.7523219585 0.0229276195 0.0182659384 0.0670038015 0.0046740560 0.0403130000 425556565 0 402718720 0.0592343956 0.1286694109 -0.1745462120 2942 1311867816.7867000103 0.0200516991 0.0182665454 0.0670038015 0.0046733631 0.0405850000 425559641 0 402718720 0.0589249730 0.1281217039 -0.1715762913 2943 1311867816.8192241192 0.0193702374 0.0182669204 0.0670038015 0.0046727236 0.0398860000 425562661 0 402718720 0.0589260310 0.1268209368 -0.1717428118 2944 1311867816.8584229946 0.0199247804 0.0182674836 0.0670038015 0.0046727159 0.0400840000 425566353 0 402718720 0.0586563572 0.1265113950 -0.1727031469 2945 1311867816.8891038895 0.0184503850 0.0182675457 0.0670038015 0.0046723190 0.0506540000 425569165 0 402718720 0.0577246100 0.1255300343 -0.1714137644 2946 1311867816.9194529057 0.0168394018 0.0182670609 0.0670038015 0.0046812492 0.0488300000 425572249 0 402718720 0.0573609695 0.1253991872 -0.1712366641 2947 1311867816.9566609859 0.0176516250 0.0182668521 0.0670038015 0.0046829083 0.0491150000 425575685 0 402718720 0.0565373451 0.1238553300 -0.1734492630 2948 1311867816.9880828857 0.0189648941 0.0182670889 0.0670038015 0.0046980379 0.0394960000 425578833 0 402718720 0.0555120893 0.1242385060 -0.1734268367 2949 1311867817.0196158886 0.0153067047 0.0182660850 0.0670038015 0.0046974958 0.0396100000 425581933 0 402718720 0.0579025447 0.1224772111 -0.1713880301 2950 1311867817.0547220707 0.0176292639 0.0182658691 0.0670038015 0.0046976459 0.0398170000 425585393 0 402718720 0.0551925078 0.1220790446 -0.1734069586 2951 1311867817.0868639946 0.0197493099 0.0182663718 0.0670038015 0.0046975141 0.0398390000 425588221 0 402718720 0.0542239174 0.1217831224 -0.1755001992 2952 1311867817.1189420223 0.0186105724 0.0182664884 0.0670038015 0.0046969529 0.0398690000 425591361 0 402718720 0.0547649004 0.1209362447 -0.1743918359 2953 1311867817.1549699306 0.0191437807 0.0182667855 0.0670038015 0.0046965942 0.0510960000 425594781 0 402718720 0.0538198054 0.1206648052 -0.1747681797 2954 1311867817.1863970757 0.0194582064 0.0182671888 0.0670038015 0.0046973865 0.0398210000 425597905 0 402718720 0.0540110506 0.1209085733 -0.1751397699 2955 1311867817.2202200890 0.0157833714 0.0182663483 0.0670038015 0.0046969438 0.0396770000 425601045 0 402718720 0.0546216518 0.1210860759 -0.1707296371 2956 1311867817.2567460537 0.0172361508 0.0182659998 0.0670038015 0.0046966662 0.0398450000 425604497 0 402718720 0.0551699214 0.1190373078 -0.1741549820 2957 1311867817.2865970135 0.0162259899 0.0182653099 0.0670038015 0.0046964657 0.0402750000 425607653 0 402718720 0.0565002486 0.1180107743 -0.1739550829 2958 1311867817.3192870617 0.0150030041 0.0182642070 0.0670038015 0.0046963391 0.0400820000 425610537 0 402718720 0.0552376397 0.1166697443 -0.1729104519 2959 1311867817.3578689098 0.0180237852 0.0182641257 0.0670038015 0.0046973135 0.0399270000 425613981 0 402718720 0.0529130585 0.1166196689 -0.1745741367 2960 1311867817.3868360519 0.0182640385 0.0182641257 0.0670038015 0.0046972307 0.0400780000 425617065 0 402718720 0.0532631539 0.1146943569 -0.1762999743 2961 1311867817.4206850529 0.0177567992 0.0182639544 0.0670038015 0.0046969193 0.0482990000 425620349 0 402718720 0.0526070967 0.1144658253 -0.1755093485 2962 1311867817.4551830292 0.0171593502 0.0182635815 0.0670038015 0.0046965921 0.0405230000 425623697 0 402718720 0.0520968139 0.1125637591 -0.1756442487 2963 1311867817.4888920784 0.0168454591 0.0182631028 0.0670038015 0.0046961539 0.0407690000 425626765 0 402718720 0.0518395714 0.1110393330 -0.1760684848 2964 1311867817.5194959641 0.0154989334 0.0182621703 0.0670038015 0.0046960533 0.0405010000 425629865 0 402718720 0.0511741079 0.1108261049 -0.1737743914 2965 1311867817.5576219559 0.0195162315 0.0182625932 0.0670038015 0.0046972867 0.0404080000 425633365 0 402718720 0.0497342683 0.1091837659 -0.1785219014 2966 1311867817.5864789486 0.0202433988 0.0182632611 0.0670038015 0.0046976221 0.0401020000 425636465 0 402718720 0.0505233668 0.1078796610 -0.1800100207 2967 1311867817.6205849648 0.0192909148 0.0182636074 0.0670038015 0.0046970400 0.0402010000 425639413 0 402718720 0.0498191454 0.1070691794 -0.1787534803 2968 1311867817.6566040516 0.0193736944 0.0182639814 0.0670038015 0.0046962964 0.0398270000 425642497 0 402718720 0.0488983952 0.1060100347 -0.1786832809 2969 1311867817.6880049706 0.0183061752 0.0182639956 0.0670038015 0.0046959937 0.0681090000 425645709 0 402718720 0.0478437915 0.1052823961 -0.1772061735 2970 1311867817.7194509506 0.0194927417 0.0182644094 0.0670038015 0.0046952802 0.0404590000 425649057 0 402718720 0.0473719612 0.1038571671 -0.1791093647 2971 1311867817.7552740574 0.0165598895 0.0182638356 0.0670038015 0.0046959982 0.0476280000 425652141 0 402718720 0.0476496518 0.1018869579 -0.1765173525 2972 1311867817.7872710228 0.0153328748 0.0182628495 0.0670038015 0.0046969791 0.0407200000 425655537 0 402718720 0.0483953431 0.1006863788 -0.1759867519 2973 1311867817.8201289177 0.0198423918 0.0182633808 0.0670038015 0.0046983190 0.0406700000 425658741 0 402718720 0.0451952405 0.0992837697 -0.1798902750 2974 1311867817.8596370220 0.0199801903 0.0182639580 0.0670038015 0.0046992658 0.0407800000 425662001 0 402718720 0.0446038507 0.0993510857 -0.1792150140 2975 1311867817.8866479397 0.0175612345 0.0182637218 0.0670038015 0.0046995149 0.0403620000 425665381 0 402718720 0.0456942767 0.0981201380 -0.1774437577 2976 1311867817.9203889370 0.0203427766 0.0182644204 0.0670038015 0.0046994087 0.0404500000 425668233 0 402718720 0.0432365015 0.0969777703 -0.1793969721 2977 1311867817.9569509029 0.0206556413 0.0182652237 0.0670038015 0.0046989082 0.0523080000 425671813 0 402718720 0.0445394441 0.0962787196 -0.1811957210 2978 1311867817.9865961075 0.0169139598 0.0182647699 0.0670038015 0.0046982902 0.0409410000 425674553 0 402718720 0.0456540659 0.0944122076 -0.1775658876 2979 1311867818.0255188942 0.0170501135 0.0182643622 0.0670038015 0.0046985732 0.0524250000 425678205 0 402718720 0.0441859737 0.0938054845 -0.1773236096 2980 1311867818.0579230785 0.0170798991 0.0182639647 0.0670038015 0.0046986104 0.0406250000 425680913 0 402718720 0.0451024175 0.0945469737 -0.1779047102 2981 1311867818.0892961025 0.0173329581 0.0182636524 0.0670038015 0.0046982552 0.0409630000 425684157 0 402718720 0.0442409888 0.0928795785 -0.1789084077 2982 1311867818.1228859425 0.0182079803 0.0182636337 0.0670038015 0.0047002387 0.0409400000 425687353 0 402718720 0.0437148660 0.0923749283 -0.1787973046 2983 1311867818.1594460011 0.0180698652 0.0182635688 0.0670038015 0.0047000942 0.0410810000 425690813 0 402718720 0.0428442024 0.0911547840 -0.1792295873 2984 1311867818.1912620068 0.0156745836 0.0182627011 0.0670038015 0.0047103482 0.0409780000 425694081 0 402718720 0.0446913615 0.0898102820 -0.1801918298 2985 1311867818.2233390808 0.0180898663 0.0182626432 0.0670038015 0.0047137217 0.0524740000 425697109 0 402718720 0.0441049375 0.0907482803 -0.1810429692 2986 1311867818.2556240559 0.0190724619 0.0182629144 0.0670038015 0.0047158064 0.0414880000 425700473 0 402718720 0.0438228324 0.0894654989 -0.1823950261 2987 1311867818.2891340256 0.0190054551 0.0182631630 0.0670038015 0.0047161353 0.0515770000 425703677 0 402718720 0.0439315848 0.0881018639 -0.1836853474 2988 1311867818.3256890774 0.0184993502 0.0182632421 0.0670038015 0.0047165391 0.0409510000 425706649 0 402718720 0.0436609387 0.0889440030 -0.1825974733 2989 1311867818.3582971096 0.0190000851 0.0182634886 0.0670038015 0.0047162576 0.0408280000 425710253 0 402718720 0.0436879769 0.0883581191 -0.1837875098 2990 1311867818.3892099857 0.0160608366 0.0182627519 0.0670038015 0.0047159065 0.0409180000 425713337 0 402718720 0.0438030809 0.0875732303 -0.1813023537 2991 1311867818.4233601093 0.0165322721 0.0182621734 0.0670038015 0.0047159385 0.0405980000 425716349 0 402718720 0.0451554395 0.0870652646 -0.1826000810 2992 1311867818.4555370808 0.0177338012 0.0182619968 0.0670038015 0.0047154007 0.0407230000 425719441 0 402718720 0.0423657633 0.0855796635 -0.1835900098 2993 1311867818.4896349907 0.0152464658 0.0182609892 0.0670038015 0.0047153333 0.0406500000 425722669 0 402718720 0.0431419574 0.0849991590 -0.1821452230 2994 1311867818.5246019363 0.0148942815 0.0182598647 0.0670038015 0.0047162671 0.0410440000 425725809 0 402718720 0.0431986973 0.0838073418 -0.1826206148 2995 1311867818.5566370487 0.0170972068 0.0182594766 0.0670038015 0.0047161469 0.0499350000 425729405 0 402718720 0.0409213379 0.0842802972 -0.1844213754 2996 1311867818.5892300606 0.0174429603 0.0182592040 0.0670038015 0.0047179927 0.0406080000 425731977 0 402718720 0.0397604853 0.0836956352 -0.1837627143 2997 1311867818.6233239174 0.0168604907 0.0182587373 0.0670038015 0.0047175146 0.0408820000 425735309 0 402718720 0.0405861214 0.0821962804 -0.1848020405 2998 1311867818.6555750370 0.0174047928 0.0182584525 0.0670038015 0.0047176633 0.0409740000 425738337 0 402718720 0.0377689116 0.0812496841 -0.1838701814 2999 1311867818.6877410412 0.0177386925 0.0182582792 0.0670038015 0.0047178607 0.0408640000 425741605 0 402718720 0.0385304056 0.0815742165 -0.1845403612 3000 1311867818.7238090038 0.0167746637 0.0182577846 0.0670038015 0.0047172075 0.0537910000 425745065 0 402718720 0.0388131291 0.0818429142 -0.1833728403 3001 1311867818.7561779022 0.0178108327 0.0182576357 0.0670038015 0.0047167769 0.0499810000 425748397 0 402718720 0.0375030860 0.0804140717 -0.1850579679 3002 1311867818.7870090008 0.0180750173 0.0182575749 0.0670038015 0.0047168837 0.0505910000 425751297 0 402718720 0.0350441411 0.0795193017 -0.1847419143 3003 1311867818.8250839710 0.0175455883 0.0182573378 0.0670038015 0.0047192299 0.0505620000 425754493 0 402718720 0.0341034457 0.0787625909 -0.1842075884 3004 1311867818.8546340466 0.0164735075 0.0182567439 0.0670038015 0.0047191741 0.0408360000 425757473 0 402718720 0.0345356502 0.0786403492 -0.1837968677 3005 1311867818.8872439861 0.0165246259 0.0182561675 0.0670038015 0.0047279802 0.0414600000 425760797 0 402718720 0.0339911319 0.0776825249 -0.1827367246 3006 1311867818.9249579906 0.0176795218 0.0182559757 0.0670038015 0.0047294547 0.0406590000 425764177 0 402718720 0.0345271975 0.0762917399 -0.1850380301 3007 1311867818.9544699192 0.0163151752 0.0182553303 0.0670038015 0.0047307600 0.0408460000 425767085 0 402718720 0.0329819880 0.0758369863 -0.1822086275 3008 1311867818.9864790440 0.0145311737 0.0182540922 0.0670038015 0.0047322460 0.0409830000 425770505 0 402718720 0.0330009274 0.0746549293 -0.1809281856 3009 1311867819.0252439976 0.0143713001 0.0182528018 0.0670038015 0.0047321329 0.0508650000 425773813 0 402718720 0.0325537436 0.0738816857 -0.1816537976 3010 1311867819.0550930500 0.0155059462 0.0182518892 0.0670038015 0.0047471985 0.0517100000 425776649 0 402718720 0.0310730860 0.0716930777 -0.1814606786 3011 1311867819.0875039101 0.0141030867 0.0182505113 0.0670038015 0.0047489514 0.0532380000 425780053 0 402718720 0.0319439806 0.0700285286 -0.1814357936 3012 1311867819.1251850128 0.0145448754 0.0182492810 0.0670038015 0.0047596455 0.0411510000 425783505 0 402718720 0.0298913028 0.0694911778 -0.1825899780 3013 1311867819.1578950882 0.0141769703 0.0182479295 0.0670038015 0.0047599312 0.0415460000 425786469 0 402718720 0.0299963877 0.0677183419 -0.1827669740 3014 1311867819.1891999245 0.0139129404 0.0182464912 0.0670038015 0.0047612740 0.0414540000 425789553 0 402718720 0.0303330421 0.0659002811 -0.1829396933 3015 1311867819.2251279354 0.0134666525 0.0182449058 0.0670038015 0.0047626194 0.0419990000 425792789 0 402718720 0.0305908173 0.0637253225 -0.1826729625 3016 1311867819.2586779594 0.0125170955 0.0182430067 0.0670038015 0.0047651709 0.0426370000 425796073 0 402718720 0.0283168852 0.0626852736 -0.1812471747 3017 1311867819.2937591076 0.0125181749 0.0182411092 0.0670038015 0.0047652380 0.0514440000 425799469 0 402718720 0.0296467133 0.0615329333 -0.1828282923 3018 1311867819.3250200748 0.0127786286 0.0182392992 0.0670038015 0.0047646620 0.0421560000 425802681 0 402718720 0.0281422511 0.0608252063 -0.1820409894 3019 1311867819.3568780422 0.0145878801 0.0182380897 0.0670038015 0.0047642368 0.0540000000 425805573 0 402718720 0.0270141847 0.0610159710 -0.1830001771 3020 1311867819.3930859566 0.0152302990 0.0182370938 0.0670038015 0.0047685773 0.0420230000 425808833 0 402718720 0.0275162384 0.0601840317 -0.1833307296 3021 1311867819.4237139225 0.0159297585 0.0182363300 0.0670038015 0.0047679660 0.0419470000 425811933 0 402718720 0.0262141526 0.0584195107 -0.1841233224 3022 1311867819.4571580887 0.0167570580 0.0182358405 0.0670038015 0.0047682315 0.0420600000 425814889 0 402718720 0.0248345621 0.0600853190 -0.1833536327 3023 1311867819.4921460152 0.0128806774 0.0182340690 0.0670038015 0.0047685408 0.0423730000 425818573 0 402718720 0.0273905583 0.0583561063 -0.1813773513 3024 1311867819.5226500034 0.0125001147 0.0182321729 0.0670038015 0.0047691385 0.0418350000 425821529 0 402718720 0.0272591133 0.0574673861 -0.1811720729 3025 1311867819.5550689697 0.0164850596 0.0182315953 0.0670038015 0.0047697228 0.0515900000 425824573 0 402718720 0.0257445574 0.0575756803 -0.1851030886 3026 1311867819.5923891068 0.0142292716 0.0182302727 0.0670038015 0.0047702961 0.0423260000 425828185 0 402718720 0.0269020014 0.0565889329 -0.1831084639 3027 1311867819.6253750324 0.0133254761 0.0182286523 0.0670038015 0.0047697792 0.0555390000 425831333 0 402718720 0.0276251510 0.0560065806 -0.1818291396 3028 1311867819.6557610035 0.0162432641 0.0182279966 0.0670038015 0.0047704202 0.0426380000 425834185 0 402718720 0.0260384306 0.0569030456 -0.1836841553 3029 1311867819.6919729710 0.0170154981 0.0182275963 0.0670038015 0.0047714861 0.0425880000 425837445 0 402718720 0.0264065750 0.0554207563 -0.1850939691 3030 1311867819.7227339745 0.0155794127 0.0182267224 0.0670038015 0.0047714114 0.0423650000 425840913 0 402718720 0.0255432688 0.0533735566 -0.1834887862 3031 1311867819.7567169666 0.0144364694 0.0182254719 0.0670038015 0.0047750993 0.0427190000 425843989 0 402718720 0.0262886286 0.0550302938 -0.1813907772 3032 1311867819.7913908958 0.0167567451 0.0182249875 0.0670038015 0.0047763594 0.0424160000 425847001 0 402718720 0.0256603807 0.0547152311 -0.1840054989 3033 1311867819.8285260201 0.0138980988 0.0182235609 0.0670038015 0.0047758401 0.0427080000 425850325 0 402718720 0.0263582636 0.0524302498 -0.1814963073 3034 1311867819.8552229404 0.0147318225 0.0182224100 0.0670038015 0.0047790728 0.0431310000 425853385 0 402718720 0.0269258469 0.0529078767 -0.1832000911 3035 1311867819.8941109180 0.0161518455 0.0182217278 0.0670038015 0.0047786179 0.0543830000 425856813 0 402718720 0.0254267640 0.0537253171 -0.1833713204 3036 1311867819.9237871170 0.0145296147 0.0182205116 0.0670038015 0.0047781839 0.0428150000 425859977 0 402718720 0.0256330930 0.0519882105 -0.1819117367 3037 1311867819.9576539993 0.0151498131 0.0182195005 0.0670038015 0.0047778683 0.0425440000 425863245 0 402718720 0.0256955661 0.0506123379 -0.1822830439 3038 1311867819.9939079285 0.0170458220 0.0182191142 0.0670038015 0.0047782606 0.0426120000 425866433 0 402718720 0.0260077976 0.0535643622 -0.1826137304 3039 1311867820.0229809284 0.0163589809 0.0182185021 0.0670038015 0.0047795445 0.0426010000 425869341 0 402718720 0.0263957717 0.0506763011 -0.1831518710 3040 1311867820.0577530861 0.0165454205 0.0182179518 0.0670038015 0.0047789886 0.0430500000 425872801 0 402718720 0.0268361922 0.0510158278 -0.1829089969 3041 1311867820.0944790840 0.0172611456 0.0182176371 0.0670038015 0.0047782335 0.0515320000 425875869 0 402718720 0.0265457220 0.0519074351 -0.1827595830 3042 1311867820.1251690388 0.0166948549 0.0182171365 0.0670038015 0.0047782248 0.0427130000 425879217 0 402718720 0.0264357384 0.0509741306 -0.1819529235 3043 1311867820.1551020145 0.0152663877 0.0182161669 0.0670038015 0.0047775551 0.0546100000 425882189 0 402718720 0.0276019312 0.0491592363 -0.1814186275 3044 1311867820.1938860416 0.0173231177 0.0182158735 0.0670038015 0.0047777854 0.0425050000 425885441 0 402718720 0.0254950710 0.0514205620 -0.1809735000 3045 1311867820.2262499332 0.0156691205 0.0182150371 0.0670038015 0.0047776839 0.0426190000 425888525 0 402718720 0.0259738881 0.0493417010 -0.1805002391 3046 1311867820.2557370663 0.0146548245 0.0182138683 0.0670038015 0.0047772424 0.0430620000 425891705 0 402718720 0.0271344353 0.0480737090 -0.1801780313 3047 1311867820.2941820621 0.0164744053 0.0182132974 0.0670038015 0.0047772900 0.0428440000 425895133 0 402718720 0.0274089631 0.0482216068 -0.1812810898 3048 1311867820.3227488995 0.0149663389 0.0182122321 0.0670038015 0.0047765588 0.0427520000 425897977 0 402718720 0.0282647647 0.0476890057 -0.1796719581 3049 1311867820.3565030098 0.0147317238 0.0182110906 0.0670038015 0.0047758214 0.0508180000 425901445 0 402718720 0.0281447805 0.0460961983 -0.1794752479 3050 1311867820.3936169147 0.0157639906 0.0182102883 0.0670038015 0.0047753400 0.0432140000 425904825 0 402718720 0.0280511845 0.0460394099 -0.1800925285 3051 1311867820.4230690002 0.0158434473 0.0182095125 0.0670038015 0.0047748096 0.0554310000 425907669 0 402718720 0.0273471233 0.0456396379 -0.1796505302 3052 1311867820.4605870247 0.0153876953 0.0182085880 0.0670038015 0.0047743114 0.0428390000 425911089 0 402718720 0.0289325006 0.0444642343 -0.1802476943 3053 1311867820.4940779209 0.0140153598 0.0182072145 0.0670038015 0.0047745809 0.0430410000 425914421 0 402718720 0.0281910729 0.0446073413 -0.1776782274 3054 1311867820.5266289711 0.0169619732 0.0182068067 0.0670038015 0.0047743889 0.0419260000 425917241 0 402718720 0.0268365461 0.0440388434 -0.1804412603 3055 1311867820.5596110821 0.0165872313 0.0182062766 0.0670038015 0.0047739140 0.0423810000 425920709 0 402718720 0.0262562893 0.0436726697 -0.1792687923 3056 1311867820.5906820297 0.0163904391 0.0182056824 0.0670038015 0.0047731789 0.0429290000 425923353 0 402718720 0.0266860556 0.0435883626 -0.1789255589 3057 1311867820.6261150837 0.0158511903 0.0182049122 0.0670038015 0.0047726745 0.0517630000 425926677 0 402718720 0.0268915147 0.0433639064 -0.1783869117 3058 1311867820.6602840424 0.0155733619 0.0182040517 0.0670038015 0.0047719485 0.0429160000 425929697 0 402718720 0.0262332074 0.0418330505 -0.1780075580 3059 1311867820.6933140755 0.0164952707 0.0182034931 0.0670038015 0.0047715884 0.0544610000 425933149 0 402718720 0.0261969157 0.0405105129 -0.1792376041 3060 1311867820.7232019901 0.0154242655 0.0182025848 0.0670038015 0.0047716120 0.0423030000 425936001 0 402718720 0.0253212061 0.0425809063 -0.1761488914 3061 1311867820.7605569363 0.0147500290 0.0182014569 0.0670038015 0.0047741197 0.0426300000 425939453 0 402718720 0.0270192400 0.0408834852 -0.1769393533 3062 1311867820.7916440964 0.0144793000 0.0182002413 0.0670038015 0.0047740369 0.0427930000 425942865 0 402718720 0.0253014173 0.0390810184 -0.1761786342 3063 1311867820.8228490353 0.0165519975 0.0181997032 0.0670038015 0.0047734543 0.0430530000 425946005 0 402718720 0.0243062004 0.0405379012 -0.1772885770 3064 1311867820.8588171005 0.0154138170 0.0181987940 0.0670038015 0.0047740393 0.0430060000 425949345 0 402718720 0.0251088999 0.0388820879 -0.1769264340 3065 1311867820.8911399841 0.0142715741 0.0181975126 0.0670038015 0.0047735217 0.0513970000 425952453 0 402718720 0.0255857017 0.0394243822 -0.1753977686 3066 1311867820.9231750965 0.0146318413 0.0181963497 0.0670038015 0.0047733012 0.0425630000 425955409 0 402718720 0.0252659582 0.0394128039 -0.1754948497 3067 1311867820.9593999386 0.0150507055 0.0181953240 0.0670038015 0.0047727159 0.0541460000 425958661 0 402718720 0.0231375061 0.0391248688 -0.1747365892 3068 1311867820.9930229187 0.0136587545 0.0181938454 0.0670038015 0.0047721099 0.0729470000 425962057 0 402718720 0.0250063315 0.0378903784 -0.1746587753 3069 1311867821.0258319378 0.0146214943 0.0181926813 0.0670038015 0.0047752433 0.0428360000 425964773 0 402718720 0.0237679593 0.0400580280 -0.1739666164 3070 1311867821.0608170033 0.0159228798 0.0181919420 0.0670038015 0.0047759693 0.0425710000 425968417 0 402718720 0.0235812794 0.0389114991 -0.1754522324 3071 1311867821.0909409523 0.0145105105 0.0181907432 0.0670038015 0.0047765808 0.0429950000 425971189 0 402718720 0.0224528909 0.0377426520 -0.1735094637 3072 1311867821.1260650158 0.0156004606 0.0181899000 0.0670038015 0.0047773565 0.0424920000 425974793 0 402718720 0.0220099650 0.0394806564 -0.1737125665 3073 1311867821.1620008945 0.0165574253 0.0181893688 0.0670038015 0.0047784001 0.0616190000 425977693 0 402718720 0.0210039578 0.0403042063 -0.1736043692 3074 1311867821.1925799847 0.0144852838 0.0181881638 0.0670038015 0.0047821964 0.0427040000 425981065 0 402718720 0.0223977994 0.0358704813 -0.1739344895 3075 1311867821.2257659435 0.0128361573 0.0181864233 0.0670038015 0.0047823976 0.0428360000 425983973 0 402718720 0.0222696289 0.0359099731 -0.1715889722 3076 1311867821.2620539665 0.0145884333 0.0181852536 0.0670038015 0.0047818863 0.0421980000 425987185 0 402718720 0.0211023223 0.0368695222 -0.1722679138 3077 1311867821.2933909893 0.0138406036 0.0181838417 0.0670038015 0.0047814117 0.0424370000 425990477 0 402718720 0.0209729765 0.0353182331 -0.1721121669 3078 1311867821.3235690594 0.0129263904 0.0181821336 0.0670038015 0.0047813195 0.0419590000 425993817 0 402718720 0.0213167127 0.0343757533 -0.1715086251 3079 1311867821.3590209484 0.0129472194 0.0181804334 0.0670038015 0.0047808963 0.0531840000 425996885 0 402718720 0.0208771303 0.0349352136 -0.1708857715 3080 1311867821.3907248974 0.0112220785 0.0181781742 0.0670038015 0.0047809438 0.0419950000 426000049 0 402718720 0.0206346679 0.0325978063 -0.1698423624 3081 1311867821.4246149063 0.0097714132 0.0181754456 0.0670038015 0.0047809306 0.0527200000 426003221 0 402718720 0.0212259963 0.0318914466 -0.1687055528 3082 1311867821.4626159668 0.0129034407 0.0181737350 0.0670038015 0.0047802616 0.0418760000 426006609 0 402718720 0.0179776512 0.0320953801 -0.1706444323 3083 1311867821.4939169884 0.0112414360 0.0181714865 0.0670038015 0.0047798647 0.0417020000 426009909 0 402718720 0.0189197492 0.0302670300 -0.1701848656 3084 1311867821.5273780823 0.0108195515 0.0181691026 0.0670038015 0.0047797190 0.0420450000 426012857 0 402718720 0.0201528333 0.0300188847 -0.1705332696 3085 1311867821.5590820312 0.0127125587 0.0181673338 0.0670038015 0.0047801900 0.0413250000 426016389 0 402718720 0.0179991964 0.0312278848 -0.1709650457 3086 1311867821.5928409100 0.0129599087 0.0181656464 0.0670038015 0.0047804596 0.0417140000 426018969 0 402718720 0.0160420798 0.0300336853 -0.1705961525 3087 1311867821.6260631084 0.0105018131 0.0181631638 0.0670038015 0.0047799677 0.0515030000 426022245 0 402718720 0.0179747678 0.0289453436 -0.1692267060 3088 1311867821.6634659767 0.0125793824 0.0181613556 0.0670038015 0.0047834442 0.0514760000 426025857 0 402718720 0.0151186697 0.0309107527 -0.1689036787 3089 1311867821.6953229904 0.0122180395 0.0181594315 0.0670038015 0.0047829244 0.0547780000 426028949 0 402718720 0.0140594784 0.0289419349 -0.1687106937 3090 1311867821.7313649654 0.0132208858 0.0181578333 0.0670038015 0.0047822998 0.0418830000 426031969 0 402718720 0.0131338071 0.0298304167 -0.1688700914 3091 1311867821.7634460926 0.0129216351 0.0181561393 0.0670038015 0.0047817231 0.0419910000 426035429 0 402718720 0.0136611462 0.0305980183 -0.1681562364 3092 1311867821.7956120968 0.0121665718 0.0181542022 0.0670038015 0.0047812875 0.0418040000 426038209 0 402718720 0.0124877738 0.0272468999 -0.1685698777 3093 1311867821.8313920498 0.0124108149 0.0181523453 0.0670038015 0.0047805841 0.0422990000 426041917 0 402718720 0.0123744626 0.0277052335 -0.1684640497 3094 1311867821.8633379936 0.0118508348 0.0181503086 0.0670038015 0.0047819865 0.0416190000 426044689 0 402718720 0.0111162681 0.0288971122 -0.1662978977 3095 1311867821.8956110477 0.0113686398 0.0181481174 0.0670038015 0.0047819616 0.0416790000 426048021 0 402718720 0.0099035241 0.0246858932 -0.1674453020 3096 1311867821.9314410686 0.0112146875 0.0181458779 0.0670038015 0.0047813193 0.0416480000 426051153 0 402718720 0.0113161653 0.0241167713 -0.1689829081 3097 1311867821.9633870125 0.0102743302 0.0181433363 0.0670038015 0.0047814904 0.0415080000 426054421 0 402718720 0.0103412131 0.0245319828 -0.1668033898 3098 1311867821.9954171181 0.0105748549 0.0181408932 0.0670038015 0.0047813229 0.0413070000 426057441 0 402718720 0.0103257708 0.0228538699 -0.1684191674 3099 1311867822.0314009190 0.0098496359 0.0181382178 0.0670038015 0.0047806540 0.0421070000 426060773 0 402718720 0.0102481311 0.0228919890 -0.1675266474 3100 1311867822.0633769035 0.0104238410 0.0181357293 0.0670038015 0.0047804449 0.0509110000 426064073 0 402718720 0.0096822176 0.0244717933 -0.1665472835 3101 1311867822.0962209702 0.0121331858 0.0181337936 0.0670038015 0.0047798262 0.0418920000 426067037 0 402718720 0.0079269456 0.0233451463 -0.1687371135 3102 1311867822.1315379143 0.0106275640 0.0181313738 0.0670038015 0.0047794234 0.0418300000 426070441 0 402718720 0.0086601572 0.0235140603 -0.1660636812 3103 1311867822.1634409428 0.0112916827 0.0181291696 0.0670038015 0.0047788646 0.0420830000 426073325 0 402718720 0.0077769486 0.0243307315 -0.1652106494 3104 1311867822.1960899830 0.0130164241 0.0181275224 0.0670038015 0.0047793945 0.0419510000 426076737 0 402718720 0.0065214662 0.0236362517 -0.1666958034 3105 1311867822.2317450047 0.0120582767 0.0181255678 0.0670038015 0.0047788283 0.0418690000 426080189 0 402718720 0.0060806666 0.0202553812 -0.1667889357 3106 1311867822.2634150982 0.0132987965 0.0181240137 0.0670038015 0.0047801253 0.0416950000 426083201 0 402718720 0.0061036120 0.0222406983 -0.1678861678 3107 1311867822.2954349518 0.0114193093 0.0181218558 0.0670038015 0.0047816485 0.0416940000 426086357 0 402718720 0.0075717825 0.0224162675 -0.1664372981 3108 1311867822.3315870762 0.0114889257 0.0181197217 0.0670038015 0.0047810416 0.0415800000 426089361 0 402718720 0.0065226979 0.0205077287 -0.1669138521 3109 1311867822.3635189533 0.0121927969 0.0181178153 0.0670038015 0.0047804954 0.0418940000 426092629 0 402718720 0.0060646622 0.0213957131 -0.1668988466 3110 1311867822.3960089684 0.0123413708 0.0181159579 0.0670038015 0.0047797584 0.0432550000 426096041 0 402718720 0.0073359082 0.0221212711 -0.1674323082 3111 1311867822.4314260483 0.0108878594 0.0181136345 0.0670038015 0.0047790364 0.0418040000 426099125 0 402718720 0.0061094295 0.0196722075 -0.1662312150 3112 1311867822.4634740353 0.0112156319 0.0181114179 0.0670038015 0.0047783199 0.0418640000 426102369 0 402718720 0.0059220199 0.0201097392 -0.1660424322 3113 1311867822.4957718849 0.0110548297 0.0181091511 0.0670038015 0.0047776528 0.0413130000 426105525 0 402718720 0.0046961471 0.0184883140 -0.1659329236 3114 1311867822.5315260887 0.0106844399 0.0181067668 0.0670038015 0.0047771029 0.0415860000 426108457 0 402718720 0.0029589031 0.0157936607 -0.1647535115 3115 1311867822.5634500980 0.0084608505 0.0181036702 0.0670038015 0.0047766684 0.0413510000 426111941 0 402718720 0.0051705819 0.0138752991 -0.1646534950 3116 1311867822.5955328941 0.0083473232 0.0181005392 0.0670038015 0.0047764854 0.0418040000 426115025 0 402718720 0.0052312012 0.0116105210 -0.1651661545 3117 1311867822.6315131187 0.0088878535 0.0180975835 0.0670038015 0.0047759865 0.0419730000 426118413 0 402718720 0.0044968347 0.0107711386 -0.1652216762 3118 1311867822.6634640694 0.0089944229 0.0180946640 0.0670038015 0.0047755205 0.0540620000 426121305 0 402718720 0.0048580496 0.0098571982 -0.1666069478 3119 1311867822.6954870224 0.0104173459 0.0180922025 0.0670038015 0.0047749048 0.0419610000 426124581 0 402718720 0.0040320931 0.0101866201 -0.1680169255 3120 1311867822.7317390442 0.0117196897 0.0180901600 0.0670038015 0.0047751374 0.0422210000 426127673 0 402718720 0.0014580432 0.0110010412 -0.1661609411 3121 1311867822.7634871006 0.0116710253 0.0180881033 0.0670038015 0.0047756883 0.0417210000 426131029 0 402718720 0.0035480801 0.0123910923 -0.1666157991 3122 1311867822.7954308987 0.0111590838 0.0180858839 0.0670038015 0.0047752498 0.0422990000 426133921 0 402718720 0.0029406780 0.0109328590 -0.1673098654 3123 1311867822.8314750195 0.0136847375 0.0180844746 0.0670038015 0.0047750953 0.0424790000 426137453 0 402718720 0.0004505422 0.0131795835 -0.1670023501 3124 1311867822.8634629250 0.0130343577 0.0180828580 0.0670038015 0.0047758845 0.0667540000 426140537 0 402718720 0.0002199793 0.0132287275 -0.1665745229 3125 1311867822.8955349922 0.0122105638 0.0180809789 0.0670038015 0.0047751864 0.0419780000 426143797 0 402718720 0.0022019921 0.0142445862 -0.1663512886 3126 1311867822.9318330288 0.0120199062 0.0180790400 0.0670038015 0.0047747228 0.0422970000 426146985 0 402718720 0.0004257858 0.0138937030 -0.1652735621 3127 1311867822.9635109901 0.0120066367 0.0180770981 0.0670038015 0.0047740721 0.0423350000 426150213 0 402718720 -0.0014598137 0.0130920261 -0.1636219621 3128 1311867822.9979970455 0.0106590195 0.0180747266 0.0670038015 0.0047738816 0.0424990000 426153297 0 402718720 -0.0007937197 0.0128768664 -0.1639338136 3129 1311867823.0344979763 0.0090128770 0.0180718305 0.0670038015 0.0047731282 0.0426290000 426156573 0 402718720 -0.0009763278 0.0120638264 -0.1621585041 3130 1311867823.0634639263 0.0094898725 0.0180690886 0.0670038015 0.0047725707 0.0537050000 426159481 0 402718720 -0.0022998122 0.0117971487 -0.1623066813 3131 1311867823.0971090794 0.0100090001 0.0180665143 0.0670038015 0.0047718205 0.0423040000 426162573 0 402718720 -0.0032484876 0.0121237729 -0.1625333577 3132 1311867823.1313869953 0.0092059514 0.0180636853 0.0670038015 0.0047720628 0.0528030000 426165841 0 402718720 -0.0031479741 0.0109396325 -0.1629232317 3133 1311867823.1635200977 0.0100099426 0.0180611147 0.0670038015 0.0047721109 0.0424790000 426169053 0 402718720 -0.0044029695 0.0106113907 -0.1629986465 3134 1311867823.1954131126 0.0111587234 0.0180589123 0.0670038015 0.0047754221 0.0426530000 426172281 0 402718720 -0.0058546336 0.0112776365 -0.1626820415 3135 1311867823.2316908836 0.0104405312 0.0180564822 0.0670038015 0.0047749991 0.0422660000 426175533 0 402718720 -0.0071769133 0.0086619128 -0.1630174369 3136 1311867823.2635869980 0.0092579424 0.0180536765 0.0670038015 0.0047798880 0.0417620000 426178745 0 402718720 -0.0062266719 0.0105674258 -0.1628402174 3137 1311867823.2955200672 0.0095520597 0.0180509664 0.0670038015 0.0047792214 0.0412590000 426181773 0 402718720 -0.0069021583 0.0110061700 -0.1618053317 3138 1311867823.3330919743 0.0097949831 0.0180483354 0.0670038015 0.0047786021 0.0498760000 426184897 0 402718720 -0.0079409257 0.0102741495 -0.1624829471 3139 1311867823.3635790348 0.0097635565 0.0180456961 0.0670038015 0.0047782198 0.0422160000 426188349 0 402718720 -0.0088643497 0.0105287805 -0.1616569757 3140 1311867823.3954129219 0.0114725139 0.0180436027 0.0670038015 0.0047775162 0.0420910000 426191377 0 402718720 -0.0095837153 0.0125419516 -0.1627932191 3141 1311867823.4318161011 0.0102738505 0.0180411291 0.0670038015 0.0047771578 0.0420650000 426194501 0 402718720 -0.0089837760 0.0118258912 -0.1627776474 3142 1311867823.4634220600 0.0105642453 0.0180387494 0.0670038015 0.0047818213 0.0430430000 426197777 0 402718720 -0.0118591813 0.0118448054 -0.1604571939 3143 1311867823.4969789982 0.0118195415 0.0180367707 0.0670038015 0.0047832147 0.0415430000 426201045 0 402718720 -0.0117840357 0.0140391821 -0.1606611758 3144 1311867823.5356218815 0.0099492418 0.0180341983 0.0670038015 0.0047829894 0.0533660000 426204241 0 402718720 -0.0101568326 0.0126003902 -0.1617340297 3145 1311867823.5636498928 0.0088118631 0.0180312659 0.0670038015 0.0047831186 0.0421120000 426207205 0 402718720 -0.0111387083 0.0108294887 -0.1604720354 3146 1311867823.5974569321 0.0097838845 0.0180286444 0.0670038015 0.0047835261 0.0412800000 426210473 0 402718720 -0.0119650969 0.0138459587 -0.1576583683 3147 1311867823.6316640377 0.0112051582 0.0180264761 0.0670038015 0.0047947599 0.0416240000 426213741 0 402718720 -0.0127617503 0.0157779381 -0.1599016637 3148 1311867823.6636750698 0.0102081662 0.0180239926 0.0670038015 0.0047974366 0.0425140000 426217273 0 402718720 -0.0125341741 0.0149628706 -0.1590177417 3149 1311867823.6956110001 0.0094890278 0.0180212822 0.0670038015 0.0047968459 0.0415480000 426220173 0 402718720 -0.0129461065 0.0144714219 -0.1580902934 3150 1311867823.7316160202 0.0103043066 0.0180188324 0.0670038015 0.0047961914 0.0530730000 426223553 0 402718720 -0.0124398265 0.0169859007 -0.1572106481 3151 1311867823.7635159492 0.0087459944 0.0180158895 0.0670038015 0.0047955674 0.0418110000 426226637 0 402718720 -0.0128328502 0.0153002478 -0.1566579342 3152 1311867823.7964189053 0.0068483013 0.0180123465 0.0670038015 0.0047949041 0.0417040000 426229657 0 402718720 -0.0127203129 0.0132810585 -0.1564281583 3153 1311867823.8316709995 0.0072349408 0.0180089284 0.0670038015 0.0047941613 0.0424540000 426232725 0 402718720 -0.0136958864 0.0136591811 -0.1556188017 3154 1311867823.8635869026 0.0091914814 0.0180061327 0.0670038015 0.0047942048 0.0423780000 426236337 0 402718720 -0.0142584210 0.0163794141 -0.1551122963 3155 1311867823.8993299007 0.0076905405 0.0180028631 0.0670038015 0.0047937313 0.0420300000 426239493 0 402718720 -0.0139147099 0.0150202280 -0.1550511867 3156 1311867823.9316000938 0.0080251405 0.0179997016 0.0670038015 0.0048039179 0.0415260000 426242569 0 402718720 -0.0141589120 0.0147913201 -0.1550941169 3157 1311867823.9639530182 0.0086749047 0.0179967479 0.0670038015 0.0048151599 0.0415070000 426245869 0 402718720 -0.0154331932 0.0162018817 -0.1546400338 3158 1311867823.9956440926 0.0086513180 0.0179937886 0.0670038015 0.0048166287 0.0418570000 426248841 0 402718720 -0.0154719595 0.0161971711 -0.1543981135 3159 1311867824.0315599442 0.0074074818 0.0179904375 0.0670038015 0.0048160225 0.0422930000 426252029 0 402718720 -0.0157638155 0.0146500468 -0.1541323811 3160 1311867824.0634789467 0.0078707617 0.0179872351 0.0670038015 0.0048169084 0.0415870000 426255561 0 402718720 -0.0162092000 0.0160300918 -0.1538516134 3161 1311867824.0966339111 0.0070430208 0.0179837728 0.0670038015 0.0048162603 0.0416490000 426258453 0 402718720 -0.0158813521 0.0163110606 -0.1522062272 3162 1311867824.1315801144 0.0056611178 0.0179798757 0.0670038015 0.0048174038 0.0419630000 426261713 0 402718720 -0.0169749111 0.0140367160 -0.1519636512 3163 1311867824.1636250019 0.0071105491 0.0179764393 0.0670038015 0.0048167473 0.0526990000 426265181 0 402718720 -0.0168723483 0.0166809782 -0.1522310674 3164 1311867824.1974411011 0.0072630765 0.0179730533 0.0670038015 0.0048161998 0.0417430000 426268065 0 402718720 -0.0169562940 0.0175422542 -0.1511807144 3165 1311867824.2314341068 0.0078661535 0.0179698599 0.0670038015 0.0048196653 0.0423880000 426271085 0 402718720 -0.0200348496 0.0154292462 -0.1519019008 3166 1311867824.2667160034 0.0073137279 0.0179664941 0.0670038015 0.0048190910 0.0419160000 426274537 0 402718720 -0.0175630134 0.0182430949 -0.1516010463 3167 1311867824.3015260696 0.0088260556 0.0179636080 0.0670038015 0.0048198319 0.0423720000 426277693 0 402718720 -0.0196087658 0.0198250096 -0.1511638910 3168 1311867824.3329520226 0.0086548971 0.0179606696 0.0670038015 0.0048191153 0.0417090000 426281121 0 402718720 -0.0215515457 0.0185022634 -0.1492540836 3169 1311867824.3655378819 0.0085470267 0.0179576991 0.0670038015 0.0048194977 0.0415830000 426284221 0 402718720 -0.0195582174 0.0214152411 -0.1492512822 3170 1311867824.3960471153 0.0089439703 0.0179548556 0.0670038015 0.0048188535 0.0418190000 426287193 0 402718720 -0.0205208249 0.0220483653 -0.1493730396 3171 1311867824.4315910339 0.0087283831 0.0179519460 0.0670038015 0.0048181126 0.0641860000 426290453 0 402718720 -0.0196546223 0.0238704234 -0.1487720162 3172 1311867824.4656479359 0.0093709547 0.0179492408 0.0670038015 0.0048174045 0.0416890000 426293969 0 402718720 -0.0198235642 0.0258043855 -0.1471151412 3173 1311867824.4978680611 0.0078397254 0.0179460547 0.0670038015 0.0048221828 0.0424950000 426296541 0 402718720 -0.0203931984 0.0247094929 -0.1461039633 3174 1311867824.5316801071 0.0086500067 0.0179431258 0.0670038015 0.0048215753 0.0416740000 426300025 0 402718720 -0.0208285861 0.0260730386 -0.1467611045 3175 1311867824.5658340454 0.0086775580 0.0179402076 0.0670038015 0.0048210036 0.0413090000 426303093 0 402718720 -0.0199355055 0.0281573646 -0.1441796273 3176 1311867824.5956490040 0.0095510902 0.0179375661 0.0670038015 0.0048210555 0.0415110000 426306513 0 402718720 -0.0233300589 0.0250334181 -0.1460410655 3177 1311867824.6318910122 0.0085371695 0.0179346073 0.0670038015 0.0048204603 0.0414900000 426309637 0 402718720 -0.0217288956 0.0270285551 -0.1440038532 3178 1311867824.6661880016 0.0083057536 0.0179315774 0.0670038015 0.0048200439 0.0420320000 426312737 0 402718720 -0.0207596496 0.0281721782 -0.1435268521 3179 1311867824.6979959011 0.0083067901 0.0179285498 0.0670038015 0.0048278325 0.0419260000 426315773 0 402718720 -0.0215605497 0.0287647881 -0.1428240687 3180 1311867824.7314980030 0.0092033530 0.0179258060 0.0670038015 0.0048343214 0.0416040000 426318929 0 402718720 -0.0221499968 0.0292034782 -0.1419836134 3181 1311867824.7639760971 0.0100393249 0.0179233268 0.0670038015 0.0048340723 0.0416170000 426322253 0 402718720 -0.0207326934 0.0317844450 -0.1422016323 3182 1311867824.7997510433 0.0079792636 0.0179202017 0.0670038015 0.0048349767 0.0519060000 426325529 0 402718720 -0.0207120571 0.0300492682 -0.1408087760 3183 1311867824.8315179348 0.0091148065 0.0179174353 0.0670038015 0.0048375819 0.0420710000 426328685 0 402718720 -0.0223443694 0.0290465299 -0.1404210329 3184 1311867824.8635060787 0.0078979647 0.0179142885 0.0670038015 0.0048373732 0.0417010000 426331513 0 402718720 -0.0210979655 0.0301049277 -0.1388063431 3185 1311867824.8995370865 0.0071939724 0.0179109226 0.0670038015 0.0048404127 0.0414550000 426334973 0 402718720 -0.0213882551 0.0294104218 -0.1387548298 3186 1311867824.9316530228 0.0071344725 0.0179075402 0.0670038015 0.0048398812 0.0420080000 426338433 0 402718720 -0.0227994099 0.0283014588 -0.1368827969 3187 1311867824.9636321068 0.0079338262 0.0179044107 0.0670038015 0.0048410450 0.0421920000 426341405 0 402718720 -0.0236614756 0.0290798433 -0.1354707181 3188 1311867824.9996089935 0.0064464998 0.0179008166 0.0670038015 0.0048414035 0.0512940000 426344737 0 402718720 -0.0221537836 0.0296497215 -0.1351003796 3189 1311867825.0316529274 0.0072572152 0.0178974790 0.0670038015 0.0048411581 0.0413470000 426347701 0 402718720 -0.0232658274 0.0296523497 -0.1363232434 3190 1311867825.0644180775 0.0082881916 0.0178944667 0.0670038015 0.0048404910 0.0417500000 426350857 0 402718720 -0.0252213851 0.0293082688 -0.1355268657 3191 1311867825.0997018814 0.0084797107 0.0178915163 0.0670038015 0.0048398478 0.0416350000 426353925 0 402718720 -0.0254383460 0.0299602970 -0.1355300993 3192 1311867825.1316909790 0.0070004496 0.0178881043 0.0670038015 0.0048392033 0.0418700000 426357129 0 402718720 -0.0258208774 0.0274961628 -0.1350027025 3193 1311867825.1636679173 0.0069374391 0.0178846747 0.0670038015 0.0048384543 0.0414420000 426360485 0 402718720 -0.0264407508 0.0272547435 -0.1354108006 3194 1311867825.1996359825 0.0076931142 0.0178814838 0.0670038015 0.0048380122 0.0421530000 426363929 0 402718720 -0.0258620251 0.0300111566 -0.1350603849 3195 1311867825.2316811085 0.0058413637 0.0178777154 0.0670038015 0.0048381657 0.0421690000 426367005 0 402718720 -0.0267326385 0.0279311873 -0.1349786669 3196 1311867825.2670049667 0.0064409738 0.0178741370 0.0670038015 0.0048376838 0.0423180000 426370329 0 402718720 -0.0295518115 0.0266105942 -0.1339211166 3197 1311867825.2996079922 0.0064100325 0.0178705511 0.0670038015 0.0048372855 0.0422320000 426373421 0 402718720 -0.0284826066 0.0283727739 -0.1352374852 3198 1311867825.3316459656 0.0076848329 0.0178673660 0.0670038015 0.0048386278 0.0421380000 426376641 0 402718720 -0.0314263478 0.0291262306 -0.1340114325 3199 1311867825.3635549545 0.0069649667 0.0178639580 0.0670038015 0.0048381969 0.0421610000 426379597 0 402718720 -0.0327873416 0.0270790402 -0.1341490597 3200 1311867825.3995220661 0.0064690444 0.0178603971 0.0670038015 0.0048374464 0.0510990000 426383041 0 402718720 -0.0317024589 0.0286000706 -0.1338114738 3201 1311867825.4329199791 0.0054356260 0.0178565155 0.0670038015 0.0048376104 0.0424880000 426386317 0 402718720 -0.0311637707 0.0283623151 -0.1332057118 3202 1311867825.4655759335 0.0060529043 0.0178528292 0.0670038015 0.0048368940 0.0423800000 426389217 0 402718720 -0.0345560163 0.0265325345 -0.1325168610 3203 1311867825.4996039867 0.0056490893 0.0178490191 0.0670038015 0.0048362258 0.0419420000 426392301 0 402718720 -0.0336081646 0.0277758427 -0.1341044456 3204 1311867825.5338120461 0.0063762660 0.0178454384 0.0670038015 0.0048355431 0.0423850000 426395385 0 402718720 -0.0338065960 0.0290054400 -0.1346196234 3205 1311867825.5637319088 0.0059165009 0.0178417164 0.0670038015 0.0048352237 0.0416780000 426398797 0 402718720 -0.0351268724 0.0281435307 -0.1327970773 3206 1311867825.5995988846 0.0069228346 0.0178383106 0.0670038015 0.0048346829 0.0538710000 426401809 0 402718720 -0.0363824517 0.0289587583 -0.1323969960 3207 1311867825.6372098923 0.0055607879 0.0178344823 0.0670038015 0.0048343245 0.0426720000 426405189 0 402718720 -0.0349121839 0.0290093478 -0.1332672089 3208 1311867825.6636829376 0.0057166647 0.0178307049 0.0670038015 0.0048336264 0.0533630000 426408425 0 402718720 -0.0354510583 0.0290291645 -0.1323474497 3209 1311867825.6997060776 0.0055358307 0.0178268735 0.0670038015 0.0048340456 0.0415780000 426411365 0 402718720 -0.0369895995 0.0275381766 -0.1319291294 3210 1311867825.7345299721 0.0072766668 0.0178235868 0.0670038015 0.0048333639 0.0417560000 426414569 0 402718720 -0.0368733928 0.0307969786 -0.1326192915 3211 1311867825.7654349804 0.0057086428 0.0178198139 0.0670038015 0.0048326626 0.0422190000 426417789 0 402718720 -0.0369150117 0.0288000517 -0.1319790334 3212 1311867825.7998030186 0.0061126989 0.0178161691 0.0670038015 0.0048319192 0.0419590000 426421297 0 402718720 -0.0383905061 0.0278697573 -0.1328957081 3213 1311867825.8355960846 0.0066306996 0.0178126878 0.0670038015 0.0048315200 0.0419760000 426424429 0 402718720 -0.0367965214 0.0303449687 -0.1331237555 3214 1311867825.8656499386 0.0072529889 0.0178094022 0.0670038015 0.0048312789 0.0512320000 426427481 0 402718720 -0.0377741121 0.0305885971 -0.1324529350 3215 1311867825.8996019363 0.0056057577 0.0178056064 0.0670038015 0.0048307567 0.0419650000 426430549 0 402718720 -0.0381135531 0.0280450545 -0.1329127401 3216 1311867825.9338490963 0.0056974604 0.0178018414 0.0670038015 0.0048305044 0.0422870000 426433753 0 402718720 -0.0381796435 0.0287593547 -0.1328785270 3217 1311867825.9640550613 0.0071947593 0.0177985442 0.0670038015 0.0048301920 0.0421400000 426436989 0 402718720 -0.0388872959 0.0301753003 -0.1344886571 3218 1311867825.9996759892 0.0068648038 0.0177951466 0.0670038015 0.0048294853 0.0419500000 426440193 0 402718720 -0.0400359109 0.0288580079 -0.1334971786 3219 1311867826.0327920914 0.0076596406 0.0177919979 0.0670038015 0.0048289285 0.0422840000 426443205 0 402718720 -0.0379066765 0.0320381708 -0.1334219575 3220 1311867826.0636880398 0.0069116363 0.0177886189 0.0670038015 0.0048282635 0.0430050000 426446481 0 402718720 -0.0389629863 0.0310369544 -0.1344245076 3221 1311867826.1009249687 0.0059135053 0.0177849321 0.0670038015 0.0048277334 0.0424070000 426449933 0 402718720 -0.0399818495 0.0289088301 -0.1345792860 3222 1311867826.1333520412 0.0063103996 0.0177813708 0.0670038015 0.0048276821 0.0424300000 426453009 0 402718720 -0.0388769433 0.0310864151 -0.1325851828 3223 1311867826.1658940315 0.0061906283 0.0177777746 0.0670038015 0.0048270836 0.0423190000 426456221 0 402718720 -0.0396526344 0.0306385346 -0.1334683448 3224 1311867826.1998670101 0.0058136373 0.0177740636 0.0670038015 0.0048268060 0.0417990000 426459489 0 402718720 -0.0394345075 0.0304169655 -0.1341152936 3225 1311867826.2345190048 0.0054875552 0.0177702538 0.0670038015 0.0048261169 0.0418490000 426462565 0 402718720 -0.0385917798 0.0304522067 -0.1331205219 3226 1311867826.2638120651 0.0050302339 0.0177663047 0.0670038015 0.0048260899 0.0512180000 426465657 0 402718720 -0.0397085138 0.0293924157 -0.1349749267 3227 1311867826.3011031151 0.0064265421 0.0177627906 0.0670038015 0.0048264350 0.0415620000 426469117 0 402718720 -0.0415646695 0.0292719156 -0.1341313720 3228 1311867826.3321969509 0.0067595420 0.0177593819 0.0670038015 0.0048265721 0.0420870000 426471841 0 402718720 -0.0426865518 0.0289682522 -0.1343908310 3229 1311867826.3637990952 0.0077364482 0.0177562779 0.0670038015 0.0048269862 0.0422170000 426474989 0 402718720 -0.0417354405 0.0314975232 -0.1343540400 3230 1311867826.3997180462 0.0074799522 0.0177530964 0.0670038015 0.0048263420 0.0420910000 426478257 0 402718720 -0.0427761078 0.0303881038 -0.1345032603 3231 1311867826.4321830273 0.0063981740 0.0177495820 0.0670038015 0.0048258857 0.0419870000 426481397 0 402718720 -0.0427631028 0.0289978571 -0.1358132958 3232 1311867826.4641919136 0.0084045958 0.0177466906 0.0670038015 0.0048257992 0.0531370000 426484409 0 402718720 -0.0422242135 0.0324848965 -0.1338784844 3233 1311867826.5007300377 0.0062992638 0.0177431498 0.0670038015 0.0048252687 0.0418120000 426487869 0 402718720 -0.0411530659 0.0309298746 -0.1341016591 3234 1311867826.5320169926 0.0059364215 0.0177394990 0.0670038015 0.0048246449 0.0421180000 426491273 0 402718720 -0.0408580787 0.0313000865 -0.1360816211 3235 1311867826.5638980865 0.0071517914 0.0177362261 0.0670038015 0.0048242156 0.0423920000 426494173 0 402718720 -0.0426392145 0.0312349927 -0.1342332661 3236 1311867826.6006839275 0.0074180467 0.0177330376 0.0670038015 0.0048235557 0.0427450000 426497377 0 402718720 -0.0427628197 0.0314646773 -0.1334122866 3237 1311867826.6315999031 0.0073548062 0.0177298315 0.0670038015 0.0048230664 0.0424980000 426500725 0 402718720 -0.0442679450 0.0312847123 -0.1353746355 3238 1311867826.6638810635 0.0085170269 0.0177269862 0.0670038015 0.0048225679 0.0519540000 426503553 0 402718720 -0.0435946807 0.0334120020 -0.1355899125 3239 1311867826.6997959614 0.0074792854 0.0177238224 0.0670038015 0.0048221264 0.0524650000 426506821 0 402718720 -0.0445577316 0.0314675458 -0.1334755570 3240 1311867826.7349510193 0.0072330353 0.0177205845 0.0670038015 0.0048214379 0.0509630000 426510017 0 402718720 -0.0445511825 0.0312323570 -0.1338403225 3241 1311867826.7678439617 0.0068502706 0.0177172305 0.0670038015 0.0048209074 0.0418150000 426512981 0 402718720 -0.0445011668 0.0318780020 -0.1364035606 3242 1311867826.8019490242 0.0068878010 0.0177138901 0.0670038015 0.0048203510 0.0425360000 426516497 0 402718720 -0.0454623029 0.0305041093 -0.1352324337 3243 1311867826.8324790001 0.0066950042 0.0177104924 0.0670038015 0.0048225647 0.0428320000 426519525 0 402718720 -0.0455338806 0.0299500749 -0.1345597357 3244 1311867826.8646159172 0.0086239036 0.0177076914 0.0670038015 0.0048220027 0.0426150000 426522617 0 402718720 -0.0474913605 0.0310911853 -0.1353633702 3245 1311867826.9008219242 0.0071414667 0.0177044352 0.0670038015 0.0048223099 0.0424530000 426525749 0 402718720 -0.0463657826 0.0303349793 -0.1357252449 3246 1311867826.9319140911 0.0065385504 0.0177009953 0.0670038015 0.0048246169 0.0525480000 426528721 0 402718720 -0.0455363095 0.0303750057 -0.1363440454 3247 1311867826.9639439583 0.0066572297 0.0176975941 0.0670038015 0.0048251011 0.0419930000 426531757 0 402718720 -0.0463166460 0.0301569700 -0.1368689984 3248 1311867827.0083661079 0.0071411533 0.0176943439 0.0670038015 0.0048259575 0.0424870000 426535121 0 402718720 -0.0467412546 0.0307883024 -0.1369863451 3249 1311867827.0334970951 0.0057006306 0.0176906524 0.0670038015 0.0048256005 0.0422940000 426538429 0 402718720 -0.0461222008 0.0296205133 -0.1384806186 3250 1311867827.0653018951 0.0087265996 0.0176878943 0.0670038015 0.0048262897 0.0424900000 426541281 0 402718720 -0.0478406027 0.0322767608 -0.1366514862 3251 1311867827.0995759964 0.0073653203 0.0176847191 0.0670038015 0.0048271772 0.0428290000 426544501 0 402718720 -0.0472695492 0.0309532247 -0.1373315752 3252 1311867827.1319890022 0.0073378198 0.0176815374 0.0670038015 0.0048264972 0.0420410000 426547289 0 402718720 -0.0471913591 0.0309546031 -0.1371704936 3253 1311867827.1636219025 0.0079710148 0.0176785523 0.0670038015 0.0048264537 0.0424310000 426550301 0 402718720 -0.0468677431 0.0316708386 -0.1372424811 3254 1311867827.2006959915 0.0055963374 0.0176748392 0.0670038015 0.0048267736 0.0498810000 426553817 0 402718720 -0.0461864248 0.0293201264 -0.1385802478 3255 1311867827.2315700054 0.0081021199 0.0176718983 0.0670038015 0.0048263404 0.0426760000 426556869 0 402718720 -0.0448218398 0.0331186205 -0.1401042044 3256 1311867827.2656030655 0.0070037427 0.0176686218 0.0670038015 0.0048258371 0.0435630000 426559841 0 402718720 -0.0464237109 0.0310787596 -0.1403159648 3257 1311867827.2999110222 0.0065817595 0.0176652178 0.0670038015 0.0048265010 0.0420780000 426563037 0 402718720 -0.0446321741 0.0318852440 -0.1399732083 3258 1311867827.3331999779 0.0080433469 0.0176622645 0.0670038015 0.0048257953 0.0420270000 426566145 0 402718720 -0.0450443998 0.0336603411 -0.1400417835 3259 1311867827.3665180206 0.0056797257 0.0176585878 0.0670038015 0.0048255377 0.0417840000 426569293 0 402718720 -0.0450161956 0.0309439655 -0.1386511773 3260 1311867827.4023349285 0.0078186905 0.0176555694 0.0670038015 0.0048255407 0.0524460000 426572609 0 402718720 -0.0461281538 0.0328031741 -0.1393985599 3261 1311867827.4316511154 0.0084710708 0.0176527529 0.0670038015 0.0048250676 0.0424870000 426575837 0 402718720 -0.0475478843 0.0327168033 -0.1381896734 3262 1311867827.4660930634 0.0068567675 0.0176494433 0.0670038015 0.0048246034 0.0519130000 426578929 0 402718720 -0.0465810113 0.0319959000 -0.1394440234 3263 1311867827.5022308826 0.0075453226 0.0176463467 0.0670038015 0.0048242803 0.0422110000 426582181 0 402718720 -0.0474197268 0.0317422152 -0.1393514425 3264 1311867827.5346870422 0.0080021517 0.0176433920 0.0670038015 0.0048236064 0.0427610000 426585401 0 402718720 -0.0458401032 0.0335865617 -0.1399387419 3265 1311867827.5639040470 0.0058842245 0.0176397904 0.0670038015 0.0048231992 0.0427760000 426588549 0 402718720 -0.0460668057 0.0307673439 -0.1400820911 3266 1311867827.6014358997 0.0067214160 0.0176364474 0.0670038015 0.0048231941 0.0424560000 426591745 0 402718720 -0.0483281910 0.0295288339 -0.1411198974 3267 1311867827.6328499317 0.0067574009 0.0176331174 0.0670038015 0.0048228621 0.0426660000 426594957 0 402718720 -0.0460019410 0.0323997363 -0.1409751624 3268 1311867827.6636641026 0.0061206012 0.0176295946 0.0670038015 0.0048221309 0.0428220000 426597977 0 402718720 -0.0477124937 0.0302936137 -0.1400656104 3269 1311867827.7023649216 0.0073825144 0.0176264600 0.0670038015 0.0048221717 0.0427650000 426601677 0 402718720 -0.0480826162 0.0313625224 -0.1387424320 3270 1311867827.7343521118 0.0080995047 0.0176235466 0.0670038015 0.0048222343 0.0423330000 426604569 0 402718720 -0.0472776927 0.0335145146 -0.1390688270 3271 1311867827.7669301033 0.0069524050 0.0176202842 0.0670038015 0.0048251010 0.0421810000 426607341 0 402718720 -0.0475105494 0.0316814482 -0.1395128518 3272 1311867827.8077390194 0.0067509012 0.0176169623 0.0670038015 0.0048263180 0.0422920000 426611153 0 402718720 -0.0483522639 0.0306966882 -0.1382202953 3273 1311867827.8316879272 0.0063575138 0.0176135222 0.0670038015 0.0048271576 0.0419820000 426613893 0 402718720 -0.0462595783 0.0319291726 -0.1391103119 3274 1311867827.8644089699 0.0072306823 0.0176103509 0.0670038015 0.0048264447 0.0610160000 426617281 0 402718720 -0.0478067398 0.0318267271 -0.1394715458 3275 1311867827.9007999897 0.0076991138 0.0176073245 0.0670038015 0.0048294416 0.0426990000 426620429 0 402718720 -0.0488871224 0.0312349126 -0.1384361535 3276 1311867827.9316790104 0.0089333402 0.0176046768 0.0670038015 0.0048315954 0.0426400000 426623385 0 402718720 -0.0490588024 0.0327838659 -0.1385432780 3277 1311867827.9717168808 0.0071527683 0.0176014873 0.0670038015 0.0048332649 0.0428490000 426626509 0 402718720 -0.0489192270 0.0304973535 -0.1389886737 3278 1311867827.9999699593 0.0059988452 0.0175979478 0.0670038015 0.0048326330 0.0420500000 426629913 0 402718720 -0.0478428826 0.0299219843 -0.1391103864 3279 1311867828.0320069790 0.0067972452 0.0175946539 0.0670038015 0.0048322047 0.0427110000 426633133 0 402718720 -0.0469388217 0.0319388248 -0.1405166686 3280 1311867828.0711700916 0.0081909401 0.0175917869 0.0670038015 0.0048332557 0.0425710000 426636273 0 402718720 -0.0495381951 0.0308909360 -0.1381704956 3281 1311867828.1003229618 0.0072438405 0.0175886330 0.0670038015 0.0048325985 0.0423810000 426639549 0 402718720 -0.0481023192 0.0310769919 -0.1387615204 3282 1311867828.1317639351 0.0084918514 0.0175858613 0.0670038015 0.0048335328 0.0420250000 426642673 0 402718720 -0.0483368970 0.0325534903 -0.1401879340 3283 1311867828.1714239120 0.0068307188 0.0175825853 0.0670038015 0.0048351873 0.0420780000 426645853 0 402718720 -0.0476648510 0.0308347251 -0.1400147676 3284 1311867828.2080869675 0.0075021787 0.0175795157 0.0670038015 0.0048431583 0.0535600000 426649105 0 402718720 -0.0487156436 0.0306673702 -0.1385174245 3285 1311867828.2316999435 0.0077566258 0.0175765255 0.0670038015 0.0048444703 0.0422170000 426652101 0 402718720 -0.0463709235 0.0328233615 -0.1386654675 3286 1311867828.2725389004 0.0079730293 0.0175736029 0.0670038015 0.0048439219 0.0424190000 426655409 0 402718720 -0.0476591401 0.0322251171 -0.1393955350 3287 1311867828.3008439541 0.0068265288 0.0175703334 0.0670038015 0.0048437751 0.0431190000 426658565 0 402718720 -0.0481625758 0.0300185308 -0.1383723915 ================================================ FILE: icra2018_results/1080/violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 10:33:28 Properties: ================= frame-limit: 0 log-file: out_paper//violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 -nan 0.0284400000 357245912 0 402718720 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0586377122 0.0584448781 0.0586377122 0.0034930480 0.0334920000 376635437 0 402718720 -0.0037594317 -0.0009100248 -0.0017881629 3 1311867170.5264289379 0.0586596653 0.0585164738 0.0586596653 0.0026708316 0.0306430000 376531569 0 402718720 -0.0066807531 -0.0008932950 -0.0038979272 4 1311867170.5623490810 0.0581764840 0.0584314764 0.0586596653 0.0037888070 0.0295510000 376541837 0 402718720 -0.0077551166 -0.0004883301 -0.0059200493 5 1311867170.5942170620 0.0571757704 0.0581803352 0.0586596653 0.0046060726 0.0412150000 376552513 0 402718720 -0.0106354402 -0.0026671742 -0.0082122963 6 1311867170.6260869503 0.0551324561 0.0576723553 0.0586596653 0.0045570799 0.0284130000 376561293 0 402718720 -0.0094366213 -0.0038628730 -0.0113154622 7 1311867170.6621398926 0.0557016879 0.0573908314 0.0586596653 0.0042465035 0.0286560000 376568001 0 402718720 -0.0114983134 -0.0040343115 -0.0124535887 8 1311867170.6942050457 0.0558096878 0.0571931885 0.0586596653 0.0039596769 0.0438220000 376573909 0 402718720 -0.0117391022 -0.0035084726 -0.0141921053 9 1311867170.7263879776 0.0567277037 0.0571414679 0.0586596653 0.0037870622 0.0283800000 376579905 0 402718720 -0.0150480336 -0.0052455575 -0.0145472027 10 1311867170.7620189190 0.0567436032 0.0571016815 0.0586596653 0.0036372208 0.0381720000 376588133 0 402718720 -0.0179191977 -0.0074015637 -0.0161056332 11 1311867170.7941920757 0.0556674302 0.0569712950 0.0586596653 0.0037485054 0.0459580000 376595713 0 402718720 -0.0188345294 -0.0093407044 -0.0189897064 12 1311867170.8262820244 0.0553181283 0.0568335311 0.0586596653 0.0037624658 0.0277110000 376603909 0 402718720 -0.0189414546 -0.0126334149 -0.0211648569 13 1311867170.8622210026 0.0536869094 0.0565914833 0.0586596653 0.0039922337 0.0283740000 376611345 0 402718720 -0.0181536600 -0.0145465583 -0.0251064487 14 1311867170.8943779469 0.0536736026 0.0563830632 0.0586596653 0.0038516264 0.0284400000 376618437 0 402718720 -0.0180233084 -0.0165607929 -0.0279384926 15 1311867170.9263520241 0.0534019023 0.0561843192 0.0586596653 0.0038760601 0.0279350000 376625801 0 402718720 -0.0189409163 -0.0195748992 -0.0310321432 16 1311867170.9621469975 0.0537196696 0.0560302786 0.0586596653 0.0038207535 0.0279350000 376632117 0 402718720 -0.0208582040 -0.0206948910 -0.0340314470 17 1311867170.9942629337 0.0532149039 0.0558646683 0.0586596653 0.0037264669 0.0362260000 376640457 0 402718720 -0.0204671975 -0.0211655367 -0.0378969610 18 1311867171.0262739658 0.0525083579 0.0556782066 0.0586596653 0.0036462947 0.0277850000 376648685 0 402718720 -0.0208106283 -0.0255436320 -0.0403674692 19 1311867171.0623519421 0.0528762229 0.0555307338 0.0586596653 0.0043709207 0.0278800000 376655897 0 402718720 -0.0228671134 -0.0273719244 -0.0431848019 20 1311867171.0942349434 0.0529052131 0.0553994577 0.0586596653 0.0044625653 0.0311860000 377291357 0 402718720 -0.0206900556 -0.0261449125 -0.0457031205 21 1311867171.1262509823 0.0534253046 0.0553054504 0.0586596653 0.0043757451 0.0615530000 377819477 0 402718720 -0.0215380527 -0.0280004907 -0.0469596162 22 1311867171.1622469425 0.0550597347 0.0552942815 0.0586596653 0.0047529889 0.0851770000 379992213 0 402718720 -0.0223019030 -0.0276895128 -0.0475389920 23 1311867171.1942689419 0.0533429049 0.0552094391 0.0586596653 0.0057345185 0.0411930000 378061733 0 402718720 -0.0175298415 -0.0263967644 -0.0493746065 24 1311867171.2262530327 0.0534160659 0.0551347152 0.0586596653 0.0058391788 0.0318300000 377818717 0 402718720 -0.0145371268 -0.0278202146 -0.0505317412 25 1311867171.2622439861 0.0521347895 0.0550147182 0.0586596653 0.0057263237 0.0310030000 377824041 0 402718720 -0.0100124888 -0.0260997359 -0.0531428717 26 1311867171.2943410873 0.0515194871 0.0548802862 0.0586596653 0.0056501446 0.0455010000 378421301 0 402718720 -0.0065691066 -0.0261033624 -0.0540730394 27 1311867171.3263869286 0.0528139547 0.0548037554 0.0586596653 0.0059245477 0.0919890000 378868561 0 402718720 -0.0073156361 -0.0269986279 -0.0540283956 28 1311867171.3622460365 0.0547091924 0.0548003782 0.0586596653 0.0058759172 0.0422210000 380830865 0 402718720 -0.0071561616 -0.0233981851 -0.0540554672 29 1311867171.3941431046 0.0556474961 0.0548295891 0.0586596653 0.0058471194 0.0421710000 378877661 0 402718720 -0.0088630449 -0.0226725303 -0.0546793714 30 1311867171.4262878895 0.0557210408 0.0548593042 0.0586596653 0.0058162463 0.0416270000 378394905 0 402718720 -0.0112854419 -0.0260976721 -0.0556972958 31 1311867171.4622440338 0.0549245514 0.0548614089 0.0586596653 0.0057835386 0.0318040000 378398885 0 402718720 -0.0102676172 -0.0247555543 -0.0589607544 32 1311867171.4944040775 0.0549498312 0.0548641721 0.0586596653 0.0057087944 0.0314430000 378402505 0 402718720 -0.0102700349 -0.0237972178 -0.0610881709 33 1311867171.5261778831 0.0561939962 0.0549044698 0.0586596653 0.0056453400 0.0307310000 378409405 0 402718720 -0.0126666790 -0.0240944456 -0.0614362657 34 1311867171.5622971058 0.0552380569 0.0549142812 0.0586596653 0.0056181815 0.0311610000 378419593 0 402718720 -0.0130429482 -0.0228178203 -0.0638013706 35 1311867171.5942931175 0.0534540676 0.0548725608 0.0586596653 0.0055997600 0.0413310000 378423229 0 402718720 -0.0114135426 -0.0237155110 -0.0656180978 36 1311867171.6263399124 0.0545632802 0.0548639697 0.0586596653 0.0055297115 0.0312200000 378427073 0 402718720 -0.0149715338 -0.0241402276 -0.0655139908 37 1311867171.6622560024 0.0549799576 0.0548671045 0.0586596653 0.0054593259 0.0309880000 378431165 0 402718720 -0.0165966190 -0.0232772287 -0.0662958696 38 1311867171.6943440437 0.0567715503 0.0549172215 0.0586596653 0.0055336295 0.0554820000 378434561 0 402718720 -0.0196146891 -0.0224566292 -0.0656255707 39 1311867171.7262439728 0.0556062050 0.0549348877 0.0586596653 0.0054649679 0.0315700000 378438853 0 402718720 -0.0220554154 -0.0234022047 -0.0672962517 40 1311867171.7621190548 0.0545473471 0.0549251992 0.0586596653 0.0054058917 0.0314150000 378442833 0 402718720 -0.0229129661 -0.0250809863 -0.0683970973 41 1311867171.7941710949 0.0542320646 0.0549082935 0.0586596653 0.0054026601 0.0316460000 378446613 0 402718720 -0.0234108306 -0.0253103413 -0.0692374706 42 1311867171.8262550831 0.0539140105 0.0548846201 0.0586596653 0.0053460689 0.0309350000 378450473 0 402718720 -0.0252144039 -0.0252506789 -0.0709946379 43 1311867171.8623590469 0.0538380705 0.0548602817 0.0586596653 0.0052904391 0.0305050000 378454933 0 402718720 -0.0295611620 -0.0263363887 -0.0719002560 44 1311867171.8944430351 0.0558128171 0.0548819303 0.0586596653 0.0055080057 0.0398690000 378459089 0 402718720 -0.0332723372 -0.0239123534 -0.0717916265 45 1311867171.9262220860 0.0545201898 0.0548738916 0.0586596653 0.0055165417 0.0330110000 379032945 0 402718720 -0.0361761004 -0.0244492311 -0.0733620971 46 1311867171.9624669552 0.0542419292 0.0548601533 0.0586596653 0.0054946669 0.0915960000 379081681 0 402718720 -0.0386306942 -0.0237663444 -0.0737511665 47 1311867171.9946711063 0.0547192469 0.0548571553 0.0586596653 0.0056105576 0.0582100000 381703957 0 402718720 -0.0415212959 -0.0228731949 -0.0733464211 48 1311867172.0262680054 0.0541142598 0.0548416783 0.0586596653 0.0057613632 0.0441350000 379748081 0 402718720 -0.0442501046 -0.0216948446 -0.0736130178 49 1311867172.0622880459 0.0535244867 0.0548147968 0.0586596653 0.0057087756 0.0305020000 379019309 0 402718720 -0.0478096940 -0.0216600951 -0.0731149763 50 1311867172.0941960812 0.0532437339 0.0547833756 0.0586596653 0.0057087148 0.0382370000 379024393 0 402718720 -0.0501032844 -0.0218695141 -0.0718796849 51 1311867172.1263689995 0.0537215471 0.0547625554 0.0586596653 0.0057848145 0.0448030000 379029077 0 402718720 -0.0544570796 -0.0210823491 -0.0711588189 52 1311867172.1623349190 0.0524390489 0.0547178726 0.0586596653 0.0058337205 0.0298960000 379034289 0 402718720 -0.0556888580 -0.0205751806 -0.0714441240 53 1311867172.1944270134 0.0520381965 0.0546673127 0.0586596653 0.0057870721 0.0378680000 379039293 0 402718720 -0.0585170276 -0.0211508293 -0.0706246868 54 1311867172.2264409065 0.0532145090 0.0546404089 0.0586596653 0.0060391589 0.0297860000 379044265 0 402718720 -0.0602071770 -0.0191878024 -0.0697553530 55 1311867172.2622280121 0.0523736328 0.0545991948 0.0586596653 0.0060102426 0.0379370000 379048885 0 402718720 -0.0613245480 -0.0196281280 -0.0689338222 56 1311867172.2944829464 0.0518795848 0.0545506303 0.0586596653 0.0059571661 0.0526440000 379052817 0 402718720 -0.0645054430 -0.0196792074 -0.0689548030 57 1311867172.3263380527 0.0523027368 0.0545111936 0.0586596653 0.0059748186 0.0430750000 379672157 0 402718720 -0.0679441169 -0.0181155633 -0.0683902353 58 1311867172.3624010086 0.0521289110 0.0544701197 0.0586596653 0.0059250940 0.0992550000 379772109 0 402718720 -0.0722022802 -0.0191505142 -0.0680087283 59 1311867172.3942890167 0.0515536107 0.0544206874 0.0586596653 0.0058919109 0.0644690000 382898417 0 402718720 -0.0737235844 -0.0182080325 -0.0682832375 60 1311867172.4265220165 0.0509167500 0.0543622884 0.0586596653 0.0059106793 0.0504440000 381139449 0 402718720 -0.0771932676 -0.0195068065 -0.0694155619 61 1311867172.4623498917 0.0521889329 0.0543266596 0.0586596653 0.0060996142 0.0332910000 379675013 0 402718720 -0.0773958191 -0.0163848288 -0.0692147389 62 1311867172.4952669144 0.0508223623 0.0542701387 0.0586596653 0.0061839349 0.0321010000 379678905 0 402718720 -0.0791006237 -0.0186503716 -0.0700086206 63 1311867172.5263059139 0.0518448055 0.0542316414 0.0586596653 0.0062037320 0.0321820000 379682741 0 402718720 -0.0837654918 -0.0190749783 -0.0698824525 64 1311867172.5624930859 0.0515709892 0.0541900687 0.0586596653 0.0061700135 0.0325990000 379686545 0 402718720 -0.0842702538 -0.0182715002 -0.0710706785 65 1311867172.5945439339 0.0516770184 0.0541514064 0.0586596653 0.0061316558 0.0322310000 379696421 0 402718720 -0.0871414840 -0.0182622392 -0.0716803968 66 1311867172.6263699532 0.0523018502 0.0541233828 0.0586596653 0.0061155388 0.0324500000 379712953 0 402718720 -0.0881958082 -0.0173735879 -0.0720227361 67 1311867172.6624419689 0.0526304096 0.0541010996 0.0586596653 0.0060713745 0.0313700000 379717205 0 402718720 -0.0900046378 -0.0167920962 -0.0721176192 68 1311867172.6945450306 0.0513200499 0.0540602018 0.0586596653 0.0061197815 0.0470780000 379721121 0 402718720 -0.0915000290 -0.0184212048 -0.0729859769 69 1311867172.7263929844 0.0513451695 0.0540208535 0.0586596653 0.0061511444 0.0307180000 379725277 0 402718720 -0.0940148234 -0.0168188084 -0.0740773529 70 1311867172.7623739243 0.0510257706 0.0539780666 0.0586596653 0.0061217500 0.0306180000 379729113 0 402718720 -0.0977091864 -0.0181643423 -0.0737871230 71 1311867172.7944509983 0.0521656796 0.0539525400 0.0586596653 0.0060891471 0.0606000000 380373441 0 402718720 -0.1044971645 -0.0171282478 -0.0737364590 72 1311867172.8263089657 0.0523731709 0.0539306044 0.0586596653 0.0060889394 0.1000890000 380360717 0 402718720 -0.1063854620 -0.0173431300 -0.0742689520 73 1311867172.8632309437 0.0523794442 0.0539093556 0.0586596653 0.0060490719 0.0921780000 382000381 0 402718720 -0.1098500639 -0.0177669954 -0.0747735649 74 1311867172.8944649696 0.0522331856 0.0538867047 0.0586596653 0.0060091505 0.0581300000 384063257 0 402718720 -0.1119013131 -0.0176126100 -0.0753949508 75 1311867172.9263219833 0.0515540689 0.0538556028 0.0586596653 0.0059773173 0.0573620000 382465573 0 402718720 -0.1133657917 -0.0189372208 -0.0761189535 76 1311867172.9623310566 0.0511025116 0.0538193780 0.0586596653 0.0059380655 0.0335910000 380377005 0 402718720 -0.1141531244 -0.0195606910 -0.0769984424 77 1311867172.9945271015 0.0516188294 0.0537907994 0.0586596653 0.0058997084 0.0335390000 380380593 0 402718720 -0.1158784628 -0.0199513491 -0.0767984837 78 1311867173.0262629986 0.0499320067 0.0537413277 0.0586596653 0.0058650358 0.0335560000 380384525 0 402718720 -0.1162831783 -0.0199628938 -0.0788544267 79 1311867173.0624630451 0.0506776422 0.0537025469 0.0586596653 0.0058312999 0.0331420000 380388185 0 402718720 -0.1164473668 -0.0198030435 -0.0783506036 80 1311867173.0945179462 0.0512865260 0.0536723466 0.0586596653 0.0058662828 0.0334750000 380391925 0 402718720 -0.1186777875 -0.0200943146 -0.0779940411 81 1311867173.1267819405 0.0512803458 0.0536428157 0.0586596653 0.0058781877 0.0329630000 380396025 0 402718720 -0.1196202114 -0.0193413440 -0.0782171786 82 1311867173.1622309685 0.0518386438 0.0536208136 0.0586596653 0.0058623295 0.0326370000 380399749 0 402718720 -0.1211456507 -0.0178294871 -0.0781078786 83 1311867173.1943008900 0.0519746244 0.0536009800 0.0586596653 0.0058324991 0.0319820000 380403737 0 402718720 -0.1240466088 -0.0172158815 -0.0782477558 84 1311867173.2264449596 0.0506779589 0.0535661822 0.0586596653 0.0058239725 0.0433800000 380408165 0 402718720 -0.1246820688 -0.0178644899 -0.0786622986 85 1311867173.2622020245 0.0503171720 0.0535279585 0.0586596653 0.0058269203 0.0423950000 380412433 0 402718720 -0.1260946989 -0.0171412397 -0.0794080794 86 1311867173.2942678928 0.0507456176 0.0534956057 0.0586596653 0.0058009435 0.0318520000 380416005 0 402718720 -0.1273392290 -0.0171507485 -0.0786760300 87 1311867173.3262879848 0.0505655967 0.0534619274 0.0586596653 0.0057815458 0.0314460000 380419921 0 402718720 -0.1299202740 -0.0183858871 -0.0782628432 88 1311867173.3623280525 0.0507933311 0.0534316025 0.0586596653 0.0057497088 0.0316040000 380423925 0 402718720 -0.1314381808 -0.0170453433 -0.0786691383 89 1311867173.3942871094 0.0500583425 0.0533937007 0.0586596653 0.0057291082 0.0310900000 380428217 0 402718720 -0.1350694299 -0.0176504776 -0.0792229325 90 1311867173.4262790680 0.0505135991 0.0533616996 0.0586596653 0.0057040893 0.0405110000 380431941 0 402718720 -0.1387626827 -0.0171818174 -0.0791708604 91 1311867173.4622900486 0.0497749150 0.0533222843 0.0586596653 0.0057466293 0.0402480000 380436097 0 402718720 -0.1389728040 -0.0185074154 -0.0791618526 92 1311867173.4943389893 0.0509528369 0.0532965295 0.0586596653 0.0058663205 0.0441360000 380439885 0 402718720 -0.1414817572 -0.0174780395 -0.0795871243 93 1311867173.5263900757 0.0507730432 0.0532693952 0.0586596653 0.0058350967 0.0421600000 380443713 0 402718720 -0.1429557949 -0.0176819246 -0.0799020976 94 1311867173.5624370575 0.0511147566 0.0532464735 0.0586596653 0.0058329346 0.0341910000 381078073 0 402718720 -0.1443582475 -0.0173763596 -0.0794244632 95 1311867173.5943109989 0.0513229445 0.0532262259 0.0586596653 0.0058355238 0.0989930000 381068625 0 402718720 -0.1479876339 -0.0187723991 -0.0790822357 96 1311867173.6263959408 0.0495226718 0.0531876472 0.0586596653 0.0058391101 0.0900650000 381264689 0 402718720 -0.1497473866 -0.0191550143 -0.0809070915 97 1311867173.6623299122 0.0506823026 0.0531618189 0.0586596653 0.0058214655 0.0499880000 385139337 0 402718720 -0.1482336372 -0.0175989717 -0.0809531361 98 1311867173.6943540573 0.0505076237 0.0531347353 0.0586596653 0.0057937917 0.0641710000 383478661 0 402718720 -0.1534190029 -0.0181142054 -0.0818635523 99 1311867173.7267971039 0.0495601892 0.0530986287 0.0586596653 0.0057671959 0.0350070000 381083505 0 402718720 -0.1538534909 -0.0193222184 -0.0830891505 100 1311867173.7623970509 0.0491553657 0.0530591961 0.0586596653 0.0057472049 0.0528970000 381086701 0 402718720 -0.1536043286 -0.0174740106 -0.0850189403 101 1311867173.7943561077 0.0489008352 0.0530180242 0.0586596653 0.0057484835 0.0342170000 381089945 0 402718720 -0.1566856205 -0.0211790521 -0.0844718069 102 1311867173.8265669346 0.0504588038 0.0529929338 0.0586596653 0.0057389966 0.0348380000 381093565 0 402718720 -0.1596865058 -0.0182679500 -0.0850744098 103 1311867173.8635799885 0.0499700569 0.0529635855 0.0586596653 0.0057299382 0.0349540000 381096785 0 402718720 -0.1594030559 -0.0183501560 -0.0863093883 104 1311867173.8946080208 0.0505279675 0.0529401661 0.0586596653 0.0057273365 0.0345070000 381100493 0 402718720 -0.1646064967 -0.0205358714 -0.0859073922 105 1311867173.9266970158 0.0501911156 0.0529139847 0.0586596653 0.0057108236 0.0338700000 381105025 0 402718720 -0.1666125506 -0.0187882166 -0.0877076760 106 1311867173.9625461102 0.0509665832 0.0528956129 0.0586596653 0.0057281352 0.0336550000 381109405 0 402718720 -0.1648854762 -0.0156000387 -0.0884903222 107 1311867173.9944310188 0.0501976088 0.0528703980 0.0586596653 0.0057273720 0.0449850000 381113249 0 402718720 -0.1692575067 -0.0184542704 -0.0884432495 108 1311867174.0264260769 0.0501637720 0.0528453366 0.0586596653 0.0057103355 0.0423680000 381116749 0 402718720 -0.1689428687 -0.0172445923 -0.0899960920 109 1311867174.0624630451 0.0499786474 0.0528190367 0.0586596653 0.0057053044 0.0461230000 381120585 0 402718720 -0.1661429107 -0.0157488249 -0.0909823701 110 1311867174.0945188999 0.0501612164 0.0527948747 0.0586596653 0.0057305611 0.0322540000 381124629 0 402718720 -0.1714103520 -0.0157543924 -0.0912131444 111 1311867174.1264541149 0.0496297777 0.0527663603 0.0586596653 0.0057252427 0.0320580000 381128177 0 402718720 -0.1738795936 -0.0165613834 -0.0917903706 112 1311867174.1624329090 0.0499565527 0.0527412727 0.0586596653 0.0057062511 0.0315860000 381131917 0 402718720 -0.1739124060 -0.0133212591 -0.0935684741 113 1311867174.1943979263 0.0506020226 0.0527223413 0.0586596653 0.0056894284 0.0317030000 381135945 0 402718720 -0.1775223017 -0.0138373766 -0.0922170952 114 1311867174.2267580032 0.0485505909 0.0526857470 0.0586596653 0.0056793458 0.0316950000 381139565 0 402718720 -0.1817338020 -0.0169575177 -0.0931103826 115 1311867174.2626769543 0.0494458973 0.0526575744 0.0586596653 0.0056942839 0.0424700000 381143793 0 402718720 -0.1782639474 -0.0142978244 -0.0933903754 116 1311867174.2945280075 0.0502213351 0.0526365724 0.0586596653 0.0057420543 0.0315880000 381147293 0 402718720 -0.1809325963 -0.0150974672 -0.0927438289 117 1311867174.3265740871 0.0495127365 0.0526098729 0.0586596653 0.0057296372 0.0319640000 381150905 0 402718720 -0.1863629818 -0.0152004771 -0.0938310698 118 1311867174.3624329567 0.0490325950 0.0525795570 0.0586596653 0.0057121348 0.0318500000 381154349 0 402718720 -0.1867174357 -0.0139406864 -0.0946352407 119 1311867174.3946359158 0.0495022535 0.0525536973 0.0586596653 0.0057096551 0.0311750000 381158097 0 402718720 -0.1901412457 -0.0136783645 -0.0942148864 120 1311867174.4266788960 0.0501608886 0.0525337572 0.0586596653 0.0056934467 0.0349210000 381807037 0 402718720 -0.1949647814 -0.0139584355 -0.0937059447 121 1311867174.4630160332 0.0493373796 0.0525073409 0.0586596653 0.0057383135 0.1024480000 381790409 0 402718720 -0.1946359277 -0.0137548558 -0.0941442549 122 1311867174.4945669174 0.0497997031 0.0524851471 0.0586596653 0.0057197388 0.0932170000 381794253 0 402718720 -0.1954422891 -0.0130748488 -0.0939991027 123 1311867174.5267519951 0.0491280779 0.0524578539 0.0586596653 0.0057076078 0.0831150000 386323217 0 402718720 -0.1993177831 -0.0148442667 -0.0937924460 124 1311867174.5623500347 0.0506702438 0.0524434377 0.0586596653 0.0056945382 0.0888440000 384659741 0 402718720 -0.1976737678 -0.0119827744 -0.0932214558 125 1311867174.5944879055 0.0512529723 0.0524339139 0.0586596653 0.0056905884 0.0341320000 381802945 0 402718720 -0.2015684247 -0.0108990651 -0.0927788988 126 1311867174.6265459061 0.0508668125 0.0524214766 0.0586596653 0.0056815467 0.0347470000 381806253 0 402718720 -0.2050312310 -0.0110056438 -0.0926953405 127 1311867174.6624910831 0.0519466363 0.0524177377 0.0586596653 0.0056594035 0.0447780000 381810057 0 402718720 -0.2058418542 -0.0099957949 -0.0916338414 128 1311867174.6945910454 0.0513836592 0.0524096590 0.0586596653 0.0056439607 0.0345560000 381813957 0 402718720 -0.2067679167 -0.0079026818 -0.0927959681 129 1311867174.7265629768 0.0505419970 0.0523951810 0.0586596653 0.0056541957 0.0430350000 381830009 0 402718720 -0.2099670768 -0.0119989086 -0.0917490423 130 1311867174.7623760700 0.0512664057 0.0523864981 0.0586596653 0.0056501145 0.0464480000 381859613 0 402718720 -0.2108357549 -0.0107604954 -0.0915204436 131 1311867174.7944738865 0.0503943264 0.0523712907 0.0586596653 0.0056377901 0.0337800000 381862905 0 402718720 -0.2110490203 -0.0112193543 -0.0921744630 132 1311867174.8273398876 0.0514316186 0.0523641720 0.0586596653 0.0056178444 0.0387240000 381866253 0 402718720 -0.2138962746 -0.0117984954 -0.0910329223 133 1311867174.8624229431 0.0507694036 0.0523521812 0.0586596653 0.0055982784 0.0378010000 381870201 0 402718720 -0.2168365568 -0.0109823253 -0.0924666077 134 1311867174.8944199085 0.0508903153 0.0523412718 0.0586596653 0.0055783515 0.0375610000 381873469 0 402718720 -0.2169745266 -0.0102554485 -0.0928792953 135 1311867174.9270179272 0.0518512651 0.0523376421 0.0586596653 0.0055593658 0.0383430000 381876961 0 402718720 -0.2183100581 -0.0102646919 -0.0921529606 136 1311867174.9626429081 0.0506287627 0.0523250768 0.0586596653 0.0055469404 0.0372350000 381880349 0 402718720 -0.2208662033 -0.0133074373 -0.0926759541 137 1311867174.9943349361 0.0513927154 0.0523182712 0.0586596653 0.0055563607 0.0371430000 381883697 0 402718720 -0.2235037386 -0.0084777055 -0.0944537148 138 1311867175.0265510082 0.0524799936 0.0523194432 0.0586596653 0.0055392898 0.0368980000 381887445 0 402718720 -0.2251725048 -0.0084026344 -0.0930493176 139 1311867175.0633120537 0.0512175336 0.0523115157 0.0586596653 0.0055206130 0.0362910000 381891393 0 402718720 -0.2295536846 -0.0084496476 -0.0941567123 140 1311867175.0947189331 0.0514117032 0.0523050885 0.0586596653 0.0055303191 0.0361780000 381895037 0 402718720 -0.2283255905 -0.0080444701 -0.0935766175 141 1311867175.1265308857 0.0521305017 0.0523038503 0.0586596653 0.0055136504 0.0361290000 381898921 0 402718720 -0.2302632779 -0.0063699293 -0.0929633155 142 1311867175.1625180244 0.0515118092 0.0522982726 0.0586596653 0.0055172935 0.0359710000 381902037 0 402718720 -0.2299450785 -0.0073245550 -0.0928938240 143 1311867175.1946399212 0.0512658171 0.0522910526 0.0586596653 0.0054985360 0.0360620000 381905545 0 402718720 -0.2308948338 -0.0067269849 -0.0930618197 144 1311867175.2270050049 0.0518632606 0.0522880818 0.0586596653 0.0055582321 0.0360090000 381909117 0 402718720 -0.2312885821 -0.0034694602 -0.0929889157 145 1311867175.2624669075 0.0512290969 0.0522807785 0.0586596653 0.0056149014 0.0362070000 381913025 0 402718720 -0.2363494486 -0.0051952172 -0.0918749943 146 1311867175.2944509983 0.0515103489 0.0522755015 0.0586596653 0.0055986055 0.0358580000 381916557 0 402718720 -0.2360939831 -0.0026703207 -0.0918912292 147 1311867175.3267059326 0.0524051823 0.0522763837 0.0586596653 0.0055868847 0.0307930000 381920417 0 402718720 -0.2385438085 -0.0007687001 -0.0904823542 148 1311867175.3625650406 0.0516139716 0.0522719080 0.0586596653 0.0055876963 0.0307960000 381923925 0 402718720 -0.2407038659 -0.0036176927 -0.0894656330 149 1311867175.3945989609 0.0529424138 0.0522764080 0.0586596653 0.0055699197 0.0390290000 381927489 0 402718720 -0.2432946861 -0.0018585296 -0.0883195996 150 1311867175.4266059399 0.0497989580 0.0522598917 0.0586596653 0.0055703427 0.0498300000 381931181 0 402718720 -0.2446331829 -0.0028765509 -0.0907423273 151 1311867175.4625999928 0.0529716946 0.0522646056 0.0586596653 0.0055645505 0.0309070000 381934625 0 402718720 -0.2511798441 -0.0008851988 -0.0872400552 152 1311867175.4945731163 0.0520824604 0.0522634073 0.0586596653 0.0055467949 0.0352060000 382624581 0 402718720 -0.2538061738 0.0008678329 -0.0886390954 153 1311867175.5264270306 0.0520121455 0.0522617650 0.0586596653 0.0055406924 0.1070650000 382608389 0 402718720 -0.2546397150 0.0016031316 -0.0892633423 154 1311867175.5625700951 0.0526101403 0.0522640272 0.0586596653 0.0055506101 0.0970390000 382613329 0 402718720 -0.2577403486 0.0025523277 -0.0881101340 155 1311867175.5946640968 0.0540418886 0.0522754973 0.0586596653 0.0055768177 0.0931870000 385319857 0 402718720 -0.2616107166 0.0023363987 -0.0866881832 156 1311867175.6264801025 0.0539492629 0.0522862266 0.0586596653 0.0055916399 0.0663370000 387468777 0 402718720 -0.2637859881 0.0036460264 -0.0866099820 157 1311867175.6624929905 0.0539024174 0.0522965208 0.0586596653 0.0056163734 0.0896730000 385821065 0 402718720 -0.2670752406 0.0031325570 -0.0863306075 158 1311867175.6947000027 0.0549526699 0.0523133318 0.0586596653 0.0056152754 0.0330440000 382624889 0 402718720 -0.2702355385 0.0021160021 -0.0843284428 159 1311867175.7273120880 0.0547467992 0.0523286367 0.0586596653 0.0056009292 0.0331060000 382628637 0 402718720 -0.2700570524 0.0036667166 -0.0855053887 160 1311867175.7624969482 0.0548586138 0.0523444490 0.0586596653 0.0055902444 0.0338920000 382632281 0 402718720 -0.2726135850 0.0039204229 -0.0855597109 161 1311867175.7948620319 0.0533294827 0.0523505672 0.0586596653 0.0056026171 0.0334910000 382635709 0 402718720 -0.2767905593 0.0023753373 -0.0864907801 162 1311867175.8287971020 0.0542373247 0.0523622139 0.0586596653 0.0055892827 0.0421500000 382639433 0 402718720 -0.2794516385 0.0038605612 -0.0864124894 163 1311867175.8625519276 0.0544604845 0.0523750867 0.0586596653 0.0055753995 0.0482310000 382642589 0 402718720 -0.2821754813 0.0035871021 -0.0862148926 164 1311867175.8946080208 0.0544544160 0.0523877656 0.0586596653 0.0055649081 0.0327700000 382646241 0 402718720 -0.2845769227 0.0039953035 -0.0869679153 165 1311867175.9282429218 0.0532742999 0.0523931385 0.0586596653 0.0055612491 0.0325500000 382649765 0 402718720 -0.2877841294 0.0028250259 -0.0878962576 166 1311867175.9629371166 0.0548704788 0.0524080622 0.0586596653 0.0055629673 0.0428760000 382653641 0 402718720 -0.2890951633 0.0070113535 -0.0884973109 167 1311867175.9983000755 0.0544506535 0.0524202933 0.0586596653 0.0055496517 0.0318820000 382657149 0 402718720 -0.2917381227 0.0057697990 -0.0884985551 168 1311867176.0268509388 0.0532050245 0.0524249643 0.0586596653 0.0055428797 0.0323250000 382660505 0 402718720 -0.2963249087 0.0028809183 -0.0891299397 169 1311867176.0627059937 0.0540377684 0.0524345076 0.0586596653 0.0056115609 0.0410100000 382664261 0 402718720 -0.2965603769 0.0065244897 -0.0902017802 170 1311867176.0946600437 0.0546425022 0.0524474958 0.0586596653 0.0056789644 0.0515810000 382667945 0 402718720 -0.2979760766 0.0069972277 -0.0905562565 171 1311867176.1268119812 0.0547070056 0.0524607093 0.0586596653 0.0056657705 0.0317590000 382671485 0 402718720 -0.3014323711 0.0068905568 -0.0909960717 172 1311867176.1625900269 0.0555025935 0.0524783946 0.0586596653 0.0057550670 0.0320780000 382675097 0 402718720 -0.3004809916 0.0074229394 -0.0909363627 173 1311867176.1946918964 0.0566046648 0.0525022459 0.0586596653 0.0057872214 0.0324080000 382678677 0 402718720 -0.2991899848 0.0087933550 -0.0915185809 174 1311867176.2265360355 0.0543763712 0.0525130168 0.0586596653 0.0057720677 0.0322720000 382682017 0 402718720 -0.3035917580 0.0079592559 -0.0932760537 175 1311867176.2625019550 0.0564007983 0.0525352326 0.0586596653 0.0057605136 0.0323580000 382685805 0 402718720 -0.3057788312 0.0092898980 -0.0921984017 176 1311867176.2946109772 0.0578205027 0.0525652626 0.0586596653 0.0057470370 0.0428330000 382688945 0 402718720 -0.3053137958 0.0137661248 -0.0933004916 177 1311867176.3266019821 0.0567515977 0.0525889142 0.0586596653 0.0057327483 0.0537760000 382692285 0 402718720 -0.3096355796 0.0120622981 -0.0937719494 178 1311867176.3624560833 0.0567402206 0.0526122361 0.0586596653 0.0057180561 0.0365700000 383415865 0 402718720 -0.3114301860 0.0140459519 -0.0952918008 179 1311867176.3952438831 0.0574710965 0.0526393806 0.0586596653 0.0057054510 0.1014150000 383380121 0 402718720 -0.3112925589 0.0158800706 -0.0959658548 180 1311867176.4268360138 0.0586650483 0.0526728565 0.0586650483 0.0056915460 0.0973610000 383383957 0 402718720 -0.3105485141 0.0165534019 -0.0954760611 181 1311867176.4629659653 0.0574147850 0.0526990550 0.0586650483 0.0057562558 0.0934540000 383684845 0 402718720 -0.3133848310 0.0153029766 -0.0963016823 182 1311867176.4945809841 0.0569104664 0.0527221947 0.0586650483 0.0057657128 0.0705320000 388817869 0 402718720 -0.3167957664 0.0168925636 -0.0986346453 183 1311867176.5266211033 0.0583922938 0.0527531788 0.0586650483 0.0058045831 0.0378650000 388734477 0 402718720 -0.3199057281 0.0182621572 -0.0982286036 184 1311867176.5636389256 0.0559031852 0.0527702984 0.0586650483 0.0058275662 0.0539000000 383982869 0 402718720 -0.3209290802 0.0148512702 -0.1003926843 185 1311867176.5946090221 0.0555130504 0.0527851241 0.0586650483 0.0058125667 0.0348340000 383399393 0 402718720 -0.3215431273 0.0162227657 -0.1022164822 186 1311867176.6283841133 0.0570941046 0.0528082907 0.0586650483 0.0058014354 0.0352620000 383402581 0 402718720 -0.3236538172 0.0179855451 -0.1019463167 187 1311867176.6625781059 0.0566042438 0.0528285899 0.0586650483 0.0057896191 0.0458910000 383406313 0 402718720 -0.3256338239 0.0175765529 -0.1029275209 188 1311867176.6945180893 0.0579311103 0.0528557309 0.0586650483 0.0057754875 0.0342340000 383409645 0 402718720 -0.3270101249 0.0175530352 -0.1021141186 189 1311867176.7265889645 0.0553029552 0.0528686792 0.0586650483 0.0057713715 0.0462530000 383413233 0 402718720 -0.3288136125 0.0160562135 -0.1050692797 190 1311867176.7632329464 0.0588242486 0.0529000243 0.0588242486 0.0057821811 0.0336700000 383416637 0 402718720 -0.3318533897 0.0201519392 -0.1032897979 191 1311867176.7947680950 0.0583970472 0.0529288046 0.0588242486 0.0057732778 0.0483420000 383420369 0 402718720 -0.3330294192 0.0197842773 -0.1042774320 192 1311867176.8266770840 0.0586836562 0.0529587777 0.0588242486 0.0057611795 0.0393030000 383423669 0 402718720 -0.3351506591 0.0207001455 -0.1050212830 193 1311867176.8627309799 0.0592790879 0.0529915255 0.0592790879 0.0057496672 0.0332770000 383427073 0 402718720 -0.3370054066 0.0216158815 -0.1053046286 194 1311867176.8949549198 0.0590175129 0.0530225872 0.0592790879 0.0057370761 0.0449230000 383430237 0 402718720 -0.3406977355 0.0215417072 -0.1056073606 195 1311867176.9268178940 0.0579717122 0.0530479674 0.0592790879 0.0057347355 0.0333680000 383433913 0 402718720 -0.3445070088 0.0221416168 -0.1067123860 196 1311867176.9650609493 0.0597672760 0.0530822496 0.0597672760 0.0057392527 0.0335850000 383437493 0 402718720 -0.3454422653 0.0236473475 -0.1060012877 197 1311867176.9947481155 0.0598042309 0.0531163713 0.0598042309 0.0057319314 0.0522370000 383440793 0 402718720 -0.3463177681 0.0207845736 -0.1051829159 198 1311867177.0267279148 0.0581983179 0.0531420377 0.0598042309 0.0057215752 0.0440210000 383444117 0 402718720 -0.3506561220 0.0219524540 -0.1074471921 199 1311867177.0626339912 0.0591025352 0.0531719899 0.0598042309 0.0057094764 0.0325270000 383447505 0 402718720 -0.3518118560 0.0232338533 -0.1075536236 200 1311867177.0946850777 0.0593552403 0.0532029062 0.0598042309 0.0056951368 0.0322100000 383450749 0 402718720 -0.3543375731 0.0228859074 -0.1071879864 201 1311867177.1266150475 0.0584179386 0.0532288516 0.0598042309 0.0056819829 0.0322840000 383454233 0 402718720 -0.3564019501 0.0230888017 -0.1086696610 202 1311867177.1627299786 0.0585338771 0.0532551141 0.0598042309 0.0056683068 0.0443430000 383457781 0 402718720 -0.3583442569 0.0231065471 -0.1088167578 203 1311867177.1946458817 0.0580188483 0.0532785808 0.0598042309 0.0056580056 0.0425690000 383460993 0 402718720 -0.3612731695 0.0238852091 -0.1096328795 204 1311867177.2264730930 0.0581118427 0.0533022733 0.0598042309 0.0056521765 0.0463350000 383464525 0 402718720 -0.3611179292 0.0218848791 -0.1098104045 205 1311867177.2638640404 0.0584046729 0.0533271630 0.0598042309 0.0056394704 0.0427130000 383467953 0 402718720 -0.3634828329 0.0234148894 -0.1107511222 206 1311867177.2946178913 0.0598452352 0.0533588041 0.0598452352 0.0056324358 0.0315400000 383471061 0 402718720 -0.3684622049 0.0245595407 -0.1089413315 207 1311867177.3276090622 0.0577891134 0.0533802066 0.0598452352 0.0056284627 0.0318820000 383474633 0 402718720 -0.3696038127 0.0257552676 -0.1124072671 208 1311867177.3627710342 0.0607439391 0.0534156092 0.0607439391 0.0056233879 0.0318140000 383477965 0 402718720 -0.3718509972 0.0275022220 -0.1101072580 209 1311867177.3946089745 0.0594593436 0.0534445266 0.0607439391 0.0056177675 0.0320190000 383481513 0 402718720 -0.3723793030 0.0264659356 -0.1119814366 210 1311867177.4312860966 0.0604278967 0.0534777807 0.0607439391 0.0056093183 0.0740850000 384118909 0 402718720 -0.3749344647 0.0272335708 -0.1113741100 211 1311867177.4626040459 0.0607303940 0.0535121533 0.0607439391 0.0055975651 0.1052980000 384086577 0 402718720 -0.3764172792 0.0281448457 -0.1118805259 212 1311867177.4946429729 0.0624414347 0.0535542725 0.0624414347 0.0055847831 0.0957270000 384090269 0 402718720 -0.3767455220 0.0298632719 -0.1113240048 213 1311867177.5276319981 0.0610775091 0.0535895929 0.0624414347 0.0055739005 0.0913410000 384414957 0 402718720 -0.3799659610 0.0300681237 -0.1126815528 214 1311867177.5626399517 0.0618803725 0.0536283348 0.0624414347 0.0055702973 0.0812870000 389723225 0 402718720 -0.3828480244 0.0286373179 -0.1113472134 215 1311867177.5947310925 0.0615660474 0.0536652544 0.0624414347 0.0055615416 0.0488850000 389649445 0 402718720 -0.3830589652 0.0291314628 -0.1125254333 216 1311867177.6311450005 0.0607738979 0.0536981648 0.0624414347 0.0055505167 0.0466510000 384100293 0 402718720 -0.3850867450 0.0307283346 -0.1145193502 217 1311867177.6624829769 0.0608116239 0.0537309457 0.0624414347 0.0055411000 0.0341780000 384103601 0 402718720 -0.3854374588 0.0312020518 -0.1152202934 218 1311867177.6945610046 0.0610975474 0.0537647375 0.0624414347 0.0055501520 0.0340480000 384107341 0 402718720 -0.3867949545 0.0312237050 -0.1150386482 219 1311867177.7305839062 0.0609723851 0.0537976491 0.0624414347 0.0055412646 0.0337220000 384110625 0 402718720 -0.3871236145 0.0323791318 -0.1164475977 220 1311867177.7625379562 0.0601508766 0.0538265274 0.0624414347 0.0055307886 0.0331460000 384113917 0 402718720 -0.3888365328 0.0333180279 -0.1180562899 221 1311867177.7945590019 0.0603524148 0.0538560563 0.0624414347 0.0055211732 0.0336580000 384116921 0 402718720 -0.3894143403 0.0330481045 -0.1183901727 222 1311867177.8309149742 0.0616103821 0.0538909857 0.0624414347 0.0055205044 0.0440770000 384120565 0 402718720 -0.3908969462 0.0340905264 -0.1181588471 223 1311867177.8625319004 0.0615985803 0.0539255489 0.0624414347 0.0055092544 0.0417380000 384123745 0 402718720 -0.3909403682 0.0345459618 -0.1192513406 224 1311867177.8946919441 0.0603565648 0.0539542588 0.0624414347 0.0055018026 0.0333820000 384126821 0 402718720 -0.3929214478 0.0350464918 -0.1210331619 225 1311867177.9317860603 0.0605041869 0.0539833696 0.0624414347 0.0054917491 0.0335760000 384130545 0 402718720 -0.3933942020 0.0343409590 -0.1213826835 226 1311867177.9627909660 0.0620253645 0.0540189537 0.0624414347 0.0055077995 0.0337000000 384133557 0 402718720 -0.3959717453 0.0366538689 -0.1210654825 227 1311867177.9947769642 0.0608143136 0.0540488892 0.0624414347 0.0054982162 0.0331490000 384136737 0 402718720 -0.3960101902 0.0359303243 -0.1231527925 228 1311867178.0306100845 0.0611013807 0.0540798212 0.0624414347 0.0054869776 0.0324700000 384140493 0 402718720 -0.3979056180 0.0360671021 -0.1234451830 229 1311867178.0634479523 0.0615515001 0.0541124486 0.0624414347 0.0054811365 0.0325030000 384144073 0 402718720 -0.4004631341 0.0380313657 -0.1240764558 230 1311867178.0951139927 0.0617366731 0.0541455974 0.0624414347 0.0054705477 0.0444440000 384147141 0 402718720 -0.4004227519 0.0380474925 -0.1247381121 231 1311867178.1307909489 0.0612832010 0.0541764961 0.0624414347 0.0054621487 0.0324450000 384150545 0 402718720 -0.4030692279 0.0360942185 -0.1248066872 232 1311867178.1627469063 0.0626938865 0.0542132090 0.0626938865 0.0054875393 0.0322040000 384154029 0 402718720 -0.4042172134 0.0380706079 -0.1251567006 233 1311867178.1950459480 0.0612369552 0.0542433538 0.0626938865 0.0054799572 0.0319770000 384157121 0 402718720 -0.4086354971 0.0389209054 -0.1268001497 234 1311867178.2307190895 0.0621544532 0.0542771619 0.0626938865 0.0054794171 0.0322220000 384160973 0 402718720 -0.4089931846 0.0370788798 -0.1265172064 235 1311867178.2628939152 0.0605673902 0.0543039289 0.0626938865 0.0054736334 0.0314330000 384164481 0 402718720 -0.4110079110 0.0380357169 -0.1290739924 236 1311867178.2954900265 0.0604322702 0.0543298964 0.0626938865 0.0054622564 0.0413510000 384167997 0 402718720 -0.4130470455 0.0379659161 -0.1293268651 237 1311867178.3306670189 0.0602083579 0.0543547000 0.0626938865 0.0054582442 0.0540760000 384171409 0 402718720 -0.4144744873 0.0371275470 -0.1299925894 238 1311867178.3627231121 0.0598169230 0.0543776506 0.0626938865 0.0054479223 0.0320080000 384174821 0 402718720 -0.4157023728 0.0383664966 -0.1316611767 239 1311867178.3949439526 0.0608290918 0.0544046440 0.0626938865 0.0054371068 0.0318530000 384178393 0 402718720 -0.4189833999 0.0376161151 -0.1296333075 240 1311867178.4306581020 0.0620980747 0.0544367000 0.0626938865 0.0054327400 0.0316560000 384181653 0 402718720 -0.4189951420 0.0396727063 -0.1302467585 241 1311867178.4628739357 0.0619455613 0.0544678571 0.0626938865 0.0054233958 0.0429140000 384185041 0 402718720 -0.4237477183 0.0398992561 -0.1292075217 242 1311867178.4946439266 0.0608673953 0.0544943015 0.0626938865 0.0054184385 0.0314930000 384188541 0 402718720 -0.4244000018 0.0392025188 -0.1304312646 243 1311867178.5306270123 0.0613580197 0.0545225472 0.0626938865 0.0054169906 0.0317470000 384191993 0 402718720 -0.4264192581 0.0402370319 -0.1303256005 244 1311867178.5626420975 0.0624034405 0.0545548460 0.0626938865 0.0054059693 0.0311460000 384195485 0 402718720 -0.4282428324 0.0411389135 -0.1295622140 245 1311867178.5947000980 0.0600855350 0.0545774202 0.0626938865 0.0054193097 0.0313730000 384199129 0 402718720 -0.4279198349 0.0395696834 -0.1326835454 246 1311867178.6306900978 0.0640578195 0.0546159584 0.0640578195 0.0054114998 0.0312280000 384202541 0 402718720 -0.4277763963 0.0414031744 -0.1298596561 247 1311867178.6626410484 0.0661545694 0.0546626734 0.0661545694 0.0054082543 0.0314940000 384206001 0 402718720 -0.4295189977 0.0420223698 -0.1271953583 248 1311867178.6946120262 0.0626352653 0.0546948210 0.0661545694 0.0054088972 0.0314650000 384209109 0 402718720 -0.4321807921 0.0404697321 -0.1304993033 249 1311867178.7307450771 0.0623858422 0.0547257086 0.0661545694 0.0053995751 0.0312540000 384212337 0 402718720 -0.4321404397 0.0427468978 -0.1328262091 250 1311867178.7632350922 0.0618733838 0.0547542993 0.0661545694 0.0053898807 0.0314190000 384215845 0 402718720 -0.4359921217 0.0418761149 -0.1317131370 251 1311867178.8006799221 0.0659794062 0.0547990209 0.0661545694 0.0053840210 0.0319120000 384219169 0 402718720 -0.4359752834 0.0426388159 -0.1278504431 252 1311867178.8309500217 0.0641521737 0.0548361366 0.0661545694 0.0053740711 0.0313530000 384222181 0 402718720 -0.4360356331 0.0453986339 -0.1319925338 253 1311867178.8627939224 0.0643289164 0.0548736574 0.0661545694 0.0053674252 0.0314480000 384225769 0 402718720 -0.4371516407 0.0419112928 -0.1299383491 254 1311867178.8952279091 0.0641947538 0.0549103547 0.0661545694 0.0053580776 0.0316600000 384228789 0 402718720 -0.4369679689 0.0411308818 -0.1307277679 255 1311867178.9306209087 0.0698473677 0.0549689312 0.0698473677 0.0053535028 0.0351970000 384856297 0 402718720 -0.4298852384 0.0427129231 -0.1297898889 256 1311867178.9627609253 0.0681607500 0.0550204617 0.0698473677 0.0053513250 0.1066370000 384935357 0 402718720 -0.4319680929 0.0411730371 -0.1309534609 257 1311867178.9946830273 0.0646417588 0.0550578987 0.0698473677 0.0053425061 0.0993490000 384964321 0 402718720 -0.4348213673 0.0399777628 -0.1342723370 258 1311867179.0309159756 0.0622785576 0.0550858857 0.0698473677 0.0053352114 0.0960130000 385356785 0 402718720 -0.4370648563 0.0411489271 -0.1378122121 259 1311867179.0628120899 0.0665167868 0.0551300205 0.0698473677 0.0053251142 0.0711100000 391170313 0 402718720 -0.4361317754 0.0400252268 -0.1339396834 260 1311867179.0968201160 0.0687873289 0.0551825486 0.0698473677 0.0053247199 0.0536380000 391125413 0 402718720 -0.4342576861 0.0389440358 -0.1338714063 261 1311867179.1310369968 0.0670524761 0.0552280272 0.0698473677 0.0053201546 0.0986940000 389401279 0 402718720 -0.4382214546 0.0403523669 -0.1359100044 262 1311867179.1627540588 0.0662586391 0.0552701288 0.0698473677 0.0053593306 0.0349000000 385030597 0 402718720 -0.4402883649 0.0358024910 -0.1365870833 263 1311867179.1957008839 0.0658351853 0.0553103001 0.0698473677 0.0053587316 0.0353300000 385034049 0 402718720 -0.4432684779 0.0402696915 -0.1393245012 264 1311867179.2307469845 0.0623150840 0.0553368334 0.0698473677 0.0053498915 0.0713300000 385037477 0 402718720 -0.4484724402 0.0399283357 -0.1428130269 265 1311867179.2634611130 0.0633239746 0.0553669736 0.0698473677 0.0053507064 0.0349340000 385040833 0 402718720 -0.4490544200 0.0384575017 -0.1422277987 266 1311867179.2959330082 0.0600566939 0.0553846041 0.0698473677 0.0053442967 0.0346830000 385044549 0 402718720 -0.4515074790 0.0404983349 -0.1474123150 267 1311867179.3307149410 0.0651154369 0.0554210491 0.0698473677 0.0053367628 0.0345210000 385047721 0 402718720 -0.4466609955 0.0395952463 -0.1449229121 268 1311867179.3629300594 0.0629756376 0.0554492379 0.0698473677 0.0053278887 0.0355100000 385051333 0 402718720 -0.4485360980 0.0393177606 -0.1473190933 269 1311867179.3948490620 0.0604200326 0.0554677167 0.0698473677 0.0053180951 0.0340000000 385054321 0 402718720 -0.4531576931 0.0382273421 -0.1480088234 270 1311867179.4308040142 0.0629948080 0.0554955948 0.0698473677 0.0053150897 0.0342740000 385058229 0 402718720 -0.4500406086 0.0410874858 -0.1490360200 271 1311867179.4637460709 0.0641264841 0.0555274431 0.0698473677 0.0053124612 0.0340230000 385061833 0 402718720 -0.4519518316 0.0404407829 -0.1463102698 272 1311867179.4949469566 0.0653442889 0.0555635345 0.0698473677 0.0053076921 0.0330540000 385065229 0 402718720 -0.4509442747 0.0396570005 -0.1458713114 273 1311867179.5307800770 0.0663960502 0.0556032140 0.0698473677 0.0053064183 0.0333360000 385068377 0 402718720 -0.4516812265 0.0433475748 -0.1465812325 274 1311867179.5627610683 0.0633713603 0.0556315649 0.0698473677 0.0053189728 0.0326570000 385071733 0 402718720 -0.4560718834 0.0431211889 -0.1478764713 275 1311867179.5946741104 0.0639967918 0.0556619839 0.0698473677 0.0053097136 0.0328670000 385074929 0 402718720 -0.4558012486 0.0443933271 -0.1483775973 276 1311867179.6306900978 0.0654127076 0.0556973126 0.0698473677 0.0053700502 0.0326150000 385078485 0 402718720 -0.4607520700 0.0469062254 -0.1447802931 277 1311867179.6625750065 0.0639265254 0.0557270210 0.0698473677 0.0053720570 0.0431930000 385082057 0 402718720 -0.4602450132 0.0448280126 -0.1464433670 278 1311867179.6946051121 0.0638226643 0.0557561420 0.0698473677 0.0053903575 0.0468070000 385085181 0 402718720 -0.4598199427 0.0454910509 -0.1476355195 279 1311867179.7309470177 0.0628349558 0.0557815141 0.0698473677 0.0053814137 0.0334280000 385088801 0 402718720 -0.4605395496 0.0454532132 -0.1487503350 280 1311867179.7627270222 0.0638425276 0.0558103034 0.0698473677 0.0054055495 0.0330600000 385091997 0 402718720 -0.4589473605 0.0441480055 -0.1481539607 281 1311867179.7948911190 0.0621055029 0.0558327063 0.0698473677 0.0054313798 0.0331560000 385095233 0 402718720 -0.4627004266 0.0478613339 -0.1495960355 282 1311867179.8307530880 0.0595661588 0.0558459455 0.0698473677 0.0054290660 0.0435530000 385098773 0 402718720 -0.4626624584 0.0463122725 -0.1524440050 283 1311867179.8627979755 0.0624034405 0.0558691168 0.0698473677 0.0054216452 0.0331320000 385102065 0 402718720 -0.4629639089 0.0460584648 -0.1487013102 284 1311867179.8948040009 0.0658473596 0.0559042515 0.0698473677 0.0054182809 0.0446210000 385105453 0 402718720 -0.4630820155 0.0480168164 -0.1453508139 285 1311867179.9309051037 0.0632656813 0.0559300810 0.0698473677 0.0054236874 0.0404280000 385108793 0 402718720 -0.4652189016 0.0489399545 -0.1481683403 286 1311867179.9635379314 0.0639316663 0.0559580586 0.0698473677 0.0054210384 0.0332240000 385111773 0 402718720 -0.4643513262 0.0470318869 -0.1471581459 287 1311867179.9958879948 0.0629440919 0.0559824002 0.0698473677 0.0054154884 0.0333930000 385115281 0 402718720 -0.4675030708 0.0491014980 -0.1471967101 288 1311867180.0309770107 0.0646139011 0.0560123707 0.0698473677 0.0054071277 0.0336590000 385118621 0 402718720 -0.4666072726 0.0504946113 -0.1459319890 289 1311867180.0626471043 0.0641654059 0.0560405819 0.0698473677 0.0053985392 0.0331810000 385121897 0 402718720 -0.4678416252 0.0499819964 -0.1453319937 290 1311867180.0947730541 0.0612216517 0.0560584476 0.0698473677 0.0054011204 0.0442250000 385125181 0 402718720 -0.4667245746 0.0488419011 -0.1493071318 291 1311867180.1307730675 0.0658605769 0.0560921319 0.0698473677 0.0054022577 0.0433390000 385128409 0 402718720 -0.4662893414 0.0508985892 -0.1441223323 292 1311867180.1636900902 0.0643133149 0.0561202867 0.0698473677 0.0054170164 0.0391940000 385131845 0 402718720 -0.4665034413 0.0494201258 -0.1446393728 293 1311867180.1949090958 0.0663929656 0.0561553470 0.0698473677 0.0054082937 0.0328270000 385134833 0 402718720 -0.4625799954 0.0506958030 -0.1450631171 294 1311867180.2308139801 0.0667886883 0.0561915148 0.0698473677 0.0054051729 0.0331730000 385138277 0 402718720 -0.4627648592 0.0507426932 -0.1443305612 295 1311867180.2637619972 0.0659188032 0.0562244887 0.0698473677 0.0054209532 0.0337210000 385141657 0 402718720 -0.4628170431 0.0505036190 -0.1453589499 296 1311867180.2947549820 0.0656852499 0.0562564507 0.0698473677 0.0054121351 0.0497950000 385144477 0 402718720 -0.4638585746 0.0507165194 -0.1449914873 297 1311867180.3308670521 0.0634122118 0.0562805442 0.0698473677 0.0054096508 0.0332400000 385148009 0 402718720 -0.4640900195 0.0500398763 -0.1473154128 298 1311867180.3658289909 0.0662134364 0.0563138761 0.0698473677 0.0054012386 0.0333960000 385151613 0 402718720 -0.4606042802 0.0515949875 -0.1466239691 299 1311867180.3964109421 0.0648453161 0.0563424093 0.0698473677 0.0053940785 0.0334370000 385154809 0 402718720 -0.4611372352 0.0506128743 -0.1473138034 300 1311867180.4309151173 0.0634040162 0.0563659480 0.0698473677 0.0053854180 0.0336380000 385158093 0 402718720 -0.4618234634 0.0494852625 -0.1479361057 301 1311867180.4670670033 0.0638368055 0.0563907681 0.0698473677 0.0053784292 0.0335570000 385161369 0 402718720 -0.4603637159 0.0506579429 -0.1483542472 302 1311867180.4947559834 0.0671088099 0.0564262583 0.0698473677 0.0053898808 0.0523990000 385164685 0 402718720 -0.4575528204 0.0506831221 -0.1459276378 303 1311867180.5308880806 0.0673631802 0.0564623538 0.0698473677 0.0053825766 0.0563950000 385168001 0 402718720 -0.4562102556 0.0516221561 -0.1459833980 304 1311867180.5629510880 0.0671263412 0.0564974327 0.0698473677 0.0053748647 0.0323050000 385171389 0 402718720 -0.4559017718 0.0513714477 -0.1454454362 305 1311867180.5946910381 0.0652626753 0.0565261712 0.0698473677 0.0053672042 0.0530540000 385174697 0 402718720 -0.4559050798 0.0506703071 -0.1464887410 306 1311867180.6308128834 0.0647565350 0.0565530678 0.0698473677 0.0053606619 0.0336220000 385178181 0 402718720 -0.4549902976 0.0493796878 -0.1462068707 307 1311867180.6640911102 0.0657774583 0.0565831147 0.0698473677 0.0053711748 0.0337000000 385181249 0 402718720 -0.4525401890 0.0506531857 -0.1456622779 308 1311867180.6957859993 0.0630056858 0.0566039672 0.0698473677 0.0053640347 0.0337540000 385184333 0 402718720 -0.4535495639 0.0491530560 -0.1469766498 309 1311867180.7309739590 0.0660087466 0.0566344033 0.0698473677 0.0053607217 0.0336440000 385187577 0 402718720 -0.4493353367 0.0495755486 -0.1448269188 310 1311867180.7650830746 0.0643607974 0.0566593272 0.0698473677 0.0053690672 0.0334920000 385191021 0 402718720 -0.4513531625 0.0492665507 -0.1453390419 311 1311867180.7949280739 0.0650103167 0.0566861793 0.0698473677 0.0053676688 0.0707260000 385194025 0 402718720 -0.4469292462 0.0497513786 -0.1471855938 312 1311867180.8309240341 0.0642339066 0.0567103707 0.0698473677 0.0053595084 0.0330610000 385197357 0 402718720 -0.4479408562 0.0492782891 -0.1465088874 313 1311867180.8652698994 0.0654304177 0.0567382303 0.0698473677 0.0053521943 0.0329570000 385200353 0 402718720 -0.4473254979 0.0499117672 -0.1445482075 314 1311867180.8966469765 0.0663658604 0.0567688915 0.0698473677 0.0053469364 0.0332760000 385203981 0 402718720 -0.4442212582 0.0488374308 -0.1439370215 315 1311867180.9306049347 0.0655469224 0.0567967583 0.0698473677 0.0053527657 0.0335580000 385207265 0 402718720 -0.4454074204 0.0491592772 -0.1439976692 316 1311867180.9631829262 0.0631019026 0.0568167113 0.0698473677 0.0053479984 0.0440200000 385210509 0 402718720 -0.4459066093 0.0492758676 -0.1459330022 317 1311867180.9948179722 0.0630735382 0.0568364489 0.0698473677 0.0053414853 0.0333710000 385213361 0 402718720 -0.4423711896 0.0487744249 -0.1469457895 318 1311867181.0308310986 0.0633573681 0.0568569549 0.0698473677 0.0053355030 0.0336570000 385217037 0 402718720 -0.4414945245 0.0472975522 -0.1456466615 319 1311867181.0627830029 0.0643536970 0.0568804557 0.0698473677 0.0053355327 0.0337600000 385220273 0 402718720 -0.4395547211 0.0483704135 -0.1448330432 320 1311867181.0948719978 0.0651683807 0.0569063554 0.0698473677 0.0053405638 0.0334660000 385223373 0 402718720 -0.4341572523 0.0485289507 -0.1454051137 321 1311867181.1311910152 0.0653314814 0.0569326019 0.0698473677 0.0053337065 0.0338270000 385226601 0 402718720 -0.4334571660 0.0491248369 -0.1438218355 322 1311867181.1629528999 0.0653811619 0.0569588397 0.0698473677 0.0053379524 0.0340150000 385229797 0 402718720 -0.4308174849 0.0483563058 -0.1442013979 323 1311867181.1972830296 0.0635271519 0.0569791750 0.0698473677 0.0053308165 0.0343660000 385233225 0 402718720 -0.4289898872 0.0468631387 -0.1455557346 324 1311867181.2342460155 0.0617432967 0.0569938791 0.0698473677 0.0053257855 0.0718790000 385236749 0 402718720 -0.4288848937 0.0472302102 -0.1468948722 325 1311867181.2629361153 0.0633623600 0.0570134744 0.0698473677 0.0053181831 0.0343830000 385239753 0 402718720 -0.4262891412 0.0475950539 -0.1455215812 326 1311867181.2948091030 0.0627831295 0.0570311728 0.0698473677 0.0053107406 0.0337920000 385242493 0 402718720 -0.4244842529 0.0482583195 -0.1465572417 327 1311867181.3317139149 0.0639613643 0.0570523660 0.0698473677 0.0053039931 0.0345780000 385246097 0 402718720 -0.4230680466 0.0487237573 -0.1448318064 328 1311867181.3626708984 0.0624238141 0.0570687424 0.0698473677 0.0052982839 0.0344690000 385249269 0 402718720 -0.4214416444 0.0483670123 -0.1465151012 329 1311867181.3948218822 0.0607030727 0.0570797890 0.0698473677 0.0052943481 0.0343660000 385252513 0 402718720 -0.4225095212 0.0469616875 -0.1463362277 330 1311867181.4308950901 0.0607277192 0.0570908433 0.0698473677 0.0052907440 0.0350500000 385255581 0 402718720 -0.4203138053 0.0476816371 -0.1466062516 331 1311867181.4628310204 0.0630432963 0.0571088266 0.0698473677 0.0052868445 0.0345260000 385258937 0 402718720 -0.4192630053 0.0488450192 -0.1434485465 332 1311867181.4963610172 0.0623302795 0.0571245538 0.0698473677 0.0052989561 0.0344030000 385262221 0 402718720 -0.4162844419 0.0481710881 -0.1435115039 333 1311867181.5359110832 0.0595949516 0.0571319724 0.0698473677 0.0052966912 0.0344820000 385265409 0 402718720 -0.4189658761 0.0480568334 -0.1444201767 334 1311867181.5671720505 0.0605253205 0.0571421322 0.0698473677 0.0052925031 0.0345120000 385268485 0 402718720 -0.4140402377 0.0467039645 -0.1445564628 335 1311867181.5948610306 0.0616169795 0.0571554899 0.0698473677 0.0052882496 0.0345580000 385271673 0 402718720 -0.4117935896 0.0478684865 -0.1442455649 336 1311867181.6313591003 0.0592679158 0.0571617769 0.0698473677 0.0052847137 0.0347930000 385275197 0 402718720 -0.4124927521 0.0471188463 -0.1460508704 337 1311867181.6628570557 0.0611815043 0.0571737049 0.0698473677 0.0052788396 0.0731020000 385278281 0 402718720 -0.4110342562 0.0461045541 -0.1436891407 338 1311867181.6949229240 0.0612526909 0.0571857729 0.0698473677 0.0052783168 0.0342300000 385281341 0 402718720 -0.4064408243 0.0462945625 -0.1459255517 339 1311867181.7310829163 0.0597142950 0.0571932316 0.0698473677 0.0053039398 0.0346970000 385284665 0 402718720 -0.4088422358 0.0453192182 -0.1458884180 340 1311867181.7634840012 0.0596108176 0.0572003422 0.0698473677 0.0052985159 0.0348000000 385288029 0 402718720 -0.4057171941 0.0447859541 -0.1469893157 341 1311867181.7948980331 0.0597649142 0.0572078629 0.0698473677 0.0052998289 0.0346200000 385291097 0 402718720 -0.4044077098 0.0457655117 -0.1471999139 342 1311867181.8308010101 0.0599053353 0.0572157503 0.0698473677 0.0052962555 0.0442700000 385294501 0 402718720 -0.4025749266 0.0445345007 -0.1465799063 343 1311867181.8627979755 0.0590863414 0.0572212039 0.0698473677 0.0052993834 0.0343150000 385297817 0 402718720 -0.3989252746 0.0425071381 -0.1480246186 344 1311867181.8949289322 0.0579573065 0.0572233437 0.0698473677 0.0052959486 0.0343830000 385300845 0 402718720 -0.3964690566 0.0424656905 -0.1493679136 345 1311867181.9307990074 0.0595699176 0.0572301454 0.0698473677 0.0053172100 0.0342910000 385304193 0 402718720 -0.3973747194 0.0426310413 -0.1462792307 346 1311867181.9629189968 0.0586737432 0.0572343176 0.0698473677 0.0053122092 0.0341720000 385307421 0 402718720 -0.3973335028 0.0432636365 -0.1466471404 347 1311867181.9955599308 0.0594290681 0.0572406426 0.0698473677 0.0053361080 0.0335690000 385310633 0 402718720 -0.3938764930 0.0428549647 -0.1455585659 348 1311867182.0320639610 0.0562055558 0.0572376682 0.0698473677 0.0053443642 0.0342000000 385314117 0 402718720 -0.3911918998 0.0400213823 -0.1480897665 349 1311867182.0629000664 0.0583534576 0.0572408653 0.0698473677 0.0053471216 0.0342670000 385317217 0 402718720 -0.3918424547 0.0413418524 -0.1447042674 350 1311867182.0948839188 0.0589854941 0.0572458499 0.0698473677 0.0053462718 0.0344080000 385320501 0 402718720 -0.3883478642 0.0417972617 -0.1452288628 351 1311867182.1314840317 0.0590728261 0.0572510550 0.0698473677 0.0053389392 0.0340390000 385323593 0 402718720 -0.3864719570 0.0408203676 -0.1445948780 352 1311867182.1629920006 0.0599678010 0.0572587730 0.0698473677 0.0053322867 0.0340360000 385326757 0 402718720 -0.3841691911 0.0414815284 -0.1437571049 353 1311867182.1994500160 0.0573590025 0.0572590570 0.0698473677 0.0053390008 0.0344060000 385330009 0 402718720 -0.3830043077 0.0388957597 -0.1454688311 354 1311867182.2307739258 0.0600443669 0.0572669251 0.0698473677 0.0053400907 0.0347070000 385332989 0 402718720 -0.3796823919 0.0392676368 -0.1432845294 355 1311867182.2629120350 0.0596104003 0.0572735264 0.0698473677 0.0053371103 0.0346990000 385336305 0 402718720 -0.3781774938 0.0383263752 -0.1433562189 356 1311867182.2973539829 0.0572384745 0.0572734279 0.0698473677 0.0053342268 0.0348330000 385339733 0 402718720 -0.3785136640 0.0376355760 -0.1453109086 357 1311867182.3308460712 0.0585646667 0.0572770449 0.0698473677 0.0053557849 0.0714330000 385342881 0 402718720 -0.3779481351 0.0378969163 -0.1434985250 358 1311867182.3629670143 0.0592500456 0.0572825560 0.0698473677 0.0053847073 0.0344540000 385346245 0 402718720 -0.3742966354 0.0362036712 -0.1427448392 359 1311867182.3990368843 0.0578614436 0.0572841685 0.0698473677 0.0053834995 0.0348270000 385349401 0 402718720 -0.3732701838 0.0346987247 -0.1434578300 360 1311867182.4308118820 0.0597611107 0.0572910489 0.0698473677 0.0053795280 0.0343430000 385352677 0 402718720 -0.3719080389 0.0353061184 -0.1420929134 361 1311867182.4629440308 0.0598366298 0.0572981004 0.0698473677 0.0053753798 0.0351620000 385356073 0 402718720 -0.3693482578 0.0344715714 -0.1424183846 362 1311867182.4969599247 0.0592376217 0.0573034582 0.0698473677 0.0053718305 0.0728790000 385359221 0 402718720 -0.3665215373 0.0329749659 -0.1440948248 363 1311867182.5309500694 0.0589861758 0.0573080938 0.0698473677 0.0053711205 0.0340290000 385362777 0 402718720 -0.3675976396 0.0323214903 -0.1436762810 364 1311867182.5629699230 0.0598493703 0.0573150753 0.0698473677 0.0053684457 0.0347280000 385366181 0 402718720 -0.3646927178 0.0313531682 -0.1435607970 365 1311867182.6036369801 0.0586951450 0.0573188563 0.0698473677 0.0053658714 0.0346850000 385369569 0 402718720 -0.3634396791 0.0304493476 -0.1446168125 366 1311867182.6308450699 0.0585103519 0.0573221118 0.0698473677 0.0053813406 0.0455460000 385372645 0 402718720 -0.3628346622 0.0301356073 -0.1452566981 367 1311867182.6635921001 0.0586411096 0.0573257058 0.0698473677 0.0053753333 0.0490860000 385375865 0 402718720 -0.3618026674 0.0308276452 -0.1456073076 368 1311867182.6970019341 0.0589852147 0.0573302153 0.0698473677 0.0053711821 0.0347860000 385379493 0 402718720 -0.3573468626 0.0294689499 -0.1462433189 369 1311867182.7330639362 0.0590172186 0.0573347871 0.0698473677 0.0053652700 0.0350730000 385382721 0 402718720 -0.3563783467 0.0277700257 -0.1452179402 370 1311867182.7631130219 0.0594625957 0.0573405380 0.0698473677 0.0053617958 0.0346160000 385385701 0 402718720 -0.3552620113 0.0286216475 -0.1453395486 371 1311867182.7970550060 0.0582084395 0.0573428773 0.0698473677 0.0053560913 0.0345730000 385389217 0 402718720 -0.3533506095 0.0270851608 -0.1465489864 372 1311867182.8306989670 0.0583726801 0.0573456456 0.0698473677 0.0053532246 0.0345790000 385392381 0 402718720 -0.3533467948 0.0280973651 -0.1465526372 373 1311867182.8641169071 0.0576777123 0.0573465359 0.0698473677 0.0053512249 0.0442250000 385395673 0 402718720 -0.3529865444 0.0282730982 -0.1465380192 374 1311867182.8969969749 0.0576761700 0.0573474172 0.0698473677 0.0053451818 0.0346580000 385399053 0 402718720 -0.3491546512 0.0278587025 -0.1469338387 375 1311867182.9318990707 0.0569623001 0.0573463903 0.0698473677 0.0053401623 0.0345820000 385402193 0 402718720 -0.3473812640 0.0285013914 -0.1477020532 376 1311867182.9630720615 0.0590862595 0.0573510176 0.0698473677 0.0053339853 0.0344770000 385405389 0 402718720 -0.3435124159 0.0281762592 -0.1452560127 377 1311867182.9983949661 0.0579006299 0.0573524754 0.0698473677 0.0053420168 0.0346110000 385408929 0 402718720 -0.3425984383 0.0264328159 -0.1454794556 378 1311867183.0308830738 0.0561611950 0.0573493239 0.0698473677 0.0053366040 0.0347680000 385411997 0 402718720 -0.3412715495 0.0255505498 -0.1464823782 379 1311867183.0628600121 0.0573758259 0.0573493938 0.0698473677 0.0053308969 0.0344530000 385415313 0 402718720 -0.3396405280 0.0271750912 -0.1456331313 380 1311867183.1000499725 0.0573421307 0.0573493747 0.0698473677 0.0053509174 0.0713160000 385418565 0 402718720 -0.3374933600 0.0257149898 -0.1442475617 381 1311867183.1344780922 0.0578673109 0.0573507341 0.0698473677 0.0053448083 0.0340980000 385421585 0 402718720 -0.3343167603 0.0276203230 -0.1448357701 382 1311867183.1673240662 0.0561862364 0.0573476857 0.0698473677 0.0053381940 0.0339080000 385425269 0 402718720 -0.3343268931 0.0266094320 -0.1452054828 383 1311867183.2004919052 0.0553475879 0.0573424635 0.0698473677 0.0053342850 0.0343380000 385428129 0 402718720 -0.3330927789 0.0248586014 -0.1448262334 384 1311867183.2311279774 0.0563922599 0.0573399890 0.0698473677 0.0053294217 0.0349060000 385431429 0 402718720 -0.3311706781 0.0256236028 -0.1440720260 385 1311867183.2633349895 0.0549253263 0.0573337172 0.0698473677 0.0053229211 0.0347390000 385434553 0 402718720 -0.3312711418 0.0243173484 -0.1444101185 386 1311867183.2991099358 0.0550650284 0.0573278397 0.0698473677 0.0053182059 0.0347010000 385437901 0 402718720 -0.3297426701 0.0232652742 -0.1438416690 387 1311867183.3320920467 0.0542297736 0.0573198344 0.0698473677 0.0053143189 0.0352870000 385441121 0 402718720 -0.3261535764 0.0224028528 -0.1453392655 388 1311867183.3695240021 0.0559570491 0.0573163221 0.0698473677 0.0053083688 0.0350180000 385444789 0 402718720 -0.3250587285 0.0218561627 -0.1429874301 389 1311867183.3986210823 0.0543279797 0.0573086400 0.0698473677 0.0053019188 0.0349860000 385447665 0 402718720 -0.3249232769 0.0205651987 -0.1442656815 390 1311867183.4311549664 0.0574899428 0.0573091048 0.0698473677 0.0053214393 0.0343360000 385450765 0 402718720 -0.3229163289 0.0233229231 -0.1424366534 391 1311867183.4667448997 0.0559628531 0.0573056617 0.0698473677 0.0053187406 0.0353080000 385454329 0 402718720 -0.3210011423 0.0223892517 -0.1437617540 392 1311867183.4988338947 0.0554018728 0.0573008051 0.0698473677 0.0053396367 0.0346170000 385457325 0 402718720 -0.3190134764 0.0192316771 -0.1422830820 393 1311867183.5321829319 0.0562607124 0.0572981586 0.0698473677 0.0053362396 0.0354390000 385460681 0 402718720 -0.3172677755 0.0207372867 -0.1419508159 394 1311867183.5661609173 0.0556212328 0.0572939024 0.0698473677 0.0053294782 0.0354700000 385464205 0 402718720 -0.3157922328 0.0203351788 -0.1421339214 395 1311867183.5985479355 0.0559816062 0.0572905802 0.0698473677 0.0053234758 0.0351320000 385467641 0 402718720 -0.3148305118 0.0187890343 -0.1403664500 396 1311867183.6310880184 0.0564786829 0.0572885299 0.0698473677 0.0053319243 0.0348460000 385470613 0 402718720 -0.3106589317 0.0192905068 -0.1406868100 397 1311867183.6649260521 0.0572825372 0.0572885148 0.0698473677 0.0053264476 0.0349140000 385473833 0 402718720 -0.3083866835 0.0187071003 -0.1389781982 398 1311867183.6993949413 0.0555605814 0.0572841733 0.0698473677 0.0053201803 0.0450160000 385477205 0 402718720 -0.3072635829 0.0164644048 -0.1394836009 399 1311867183.7308928967 0.0563956872 0.0572819465 0.0698473677 0.0053161601 0.0552420000 385480289 0 402718720 -0.3038608730 0.0164775439 -0.1386334151 400 1311867183.7676479816 0.0541389473 0.0572740890 0.0698473677 0.0053200887 0.0351980000 385483829 0 402718720 -0.3047832549 0.0166466925 -0.1398797929 401 1311867183.7971870899 0.0541109890 0.0572662010 0.0698473677 0.0053140727 0.0349080000 385486753 0 402718720 -0.3026118875 0.0141227646 -0.1383258104 402 1311867183.8309071064 0.0553812794 0.0572615121 0.0698473677 0.0053087865 0.0348200000 385489949 0 402718720 -0.3011094928 0.0146714672 -0.1367861927 403 1311867183.8655049801 0.0562355407 0.0572589663 0.0698473677 0.0053026904 0.0349710000 385493137 0 402718720 -0.2980902195 0.0139330123 -0.1357914209 404 1311867183.8970971107 0.0557355843 0.0572551955 0.0698473677 0.0052979826 0.0350410000 385496293 0 402718720 -0.2964963317 0.0133111011 -0.1360010505 405 1311867183.9314939976 0.0550301075 0.0572497015 0.0698473677 0.0052922138 0.0501660000 386127033 0 402718720 -0.2958473861 0.0141097996 -0.1368473172 406 1311867183.9658319950 0.0542791225 0.0572423848 0.0698473677 0.0052897897 0.1074540000 386093717 0 402718720 -0.2951831520 0.0118960310 -0.1359434128 407 1311867183.9966781139 0.0534636304 0.0572331004 0.0698473677 0.0052836867 0.0998250000 386097105 0 402718720 -0.2935056090 0.0117346030 -0.1369437873 408 1311867184.0309689045 0.0543137752 0.0572259452 0.0698473677 0.0053114959 0.0987910000 386099893 0 402718720 -0.2921863794 0.0111879110 -0.1358065158 409 1311867184.0647850037 0.0533262007 0.0572164103 0.0698473677 0.0053062060 0.0971080000 390456669 0 402718720 -0.2919847071 0.0101458812 -0.1357639879 410 1311867184.0968890190 0.0528053083 0.0572056516 0.0698473677 0.0053006357 0.0836760000 392212545 0 402718720 -0.2906292975 0.0094702411 -0.1355752498 411 1311867184.1312260628 0.0523179844 0.0571937594 0.0698473677 0.0052956394 0.1090870000 390591153 0 402718720 -0.2890530527 0.0090224408 -0.1356000602 412 1311867184.1650640965 0.0527360998 0.0571829399 0.0698473677 0.0052897521 0.0369220000 386108701 0 402718720 -0.2861586511 0.0076284986 -0.1342772692 413 1311867184.1969559193 0.0526128262 0.0571718742 0.0698473677 0.0052843598 0.0376120000 386111793 0 402718720 -0.2844718397 0.0093978317 -0.1350930184 414 1311867184.2309360504 0.0523159802 0.0571601450 0.0698473677 0.0052791333 0.0370690000 386115189 0 402718720 -0.2832852006 0.0081812060 -0.1341490448 415 1311867184.2681369781 0.0522892512 0.0571484079 0.0698473677 0.0052740254 0.0378130000 386119017 0 402718720 -0.2810155153 0.0065470021 -0.1331471801 416 1311867184.2983899117 0.0523639433 0.0571369068 0.0698473677 0.0052725313 0.0741000000 386121885 0 402718720 -0.2793058157 0.0087949606 -0.1338626742 417 1311867184.3314700127 0.0519655310 0.0571245054 0.0698473677 0.0052693713 0.0372790000 386125257 0 402718720 -0.2755082846 0.0065337936 -0.1327991486 418 1311867184.3697841167 0.0513119511 0.0571105998 0.0698473677 0.0052659423 0.0367420000 386128461 0 402718720 -0.2773342431 0.0051850975 -0.1319168508 419 1311867184.4000220299 0.0520009920 0.0570984050 0.0698473677 0.0052897031 0.0367960000 386131633 0 402718720 -0.2737204731 0.0086765643 -0.1331560612 420 1311867184.4310610294 0.0520505868 0.0570863864 0.0698473677 0.0052861674 0.0367950000 386135229 0 402718720 -0.2704016566 0.0078824777 -0.1330506802 421 1311867184.4655809402 0.0514335148 0.0570729591 0.0698473677 0.0052840952 0.0719010000 386138401 0 402718720 -0.2697142661 0.0040580858 -0.1315720081 422 1311867184.5037670135 0.0503052063 0.0570569218 0.0698473677 0.0053530031 0.0371910000 386142069 0 402718720 -0.2644487321 0.0034724898 -0.1337015331 423 1311867184.5310881138 0.0525870547 0.0570463548 0.0698473677 0.0053966892 0.0371260000 386145057 0 402718720 -0.2619958222 0.0059484411 -0.1337315589 424 1311867184.5682930946 0.0509785488 0.0570320439 0.0698473677 0.0053925041 0.0367630000 386148373 0 402718720 -0.2615881562 0.0037162886 -0.1345113218 425 1311867184.6018071175 0.0500244610 0.0570155555 0.0698473677 0.0053866853 0.0365970000 386151793 0 402718720 -0.2604414225 0.0012781648 -0.1342529655 426 1311867184.6367399693 0.0502676331 0.0569997153 0.0698473677 0.0053811933 0.0747350000 386154877 0 402718720 -0.2566248178 0.0025309375 -0.1347066164 427 1311867184.6662440300 0.0492461473 0.0569815570 0.0698473677 0.0053888657 0.0356570000 386158105 0 402718720 -0.2540075183 -0.0002151444 -0.1341402829 428 1311867184.6994929314 0.0511646532 0.0569679661 0.0698473677 0.0053841705 0.0364660000 386161461 0 402718720 -0.2491421700 0.0007475023 -0.1327979267 429 1311867184.7359158993 0.0508636758 0.0569537370 0.0698473677 0.0053857388 0.0351490000 386164641 0 402718720 -0.2485246658 0.0001945314 -0.1323124319 430 1311867184.7690689564 0.0497990511 0.0569370982 0.0698473677 0.0053841212 0.0352250000 386168141 0 402718720 -0.2465701699 -0.0017979578 -0.1322672069 431 1311867184.8001279831 0.0497115776 0.0569203337 0.0698473677 0.0053856834 0.0350300000 386171361 0 402718720 -0.2424715459 -0.0028342158 -0.1314840019 432 1311867184.8348441124 0.0503792018 0.0569051922 0.0698473677 0.0053801275 0.0358160000 386174685 0 402718720 -0.2401162982 -0.0028212126 -0.1301205158 433 1311867184.8690660000 0.0496752486 0.0568884948 0.0698473677 0.0053741109 0.0359810000 386177905 0 402718720 -0.2389392257 -0.0052613229 -0.1285305619 434 1311867184.9055209160 0.0493040830 0.0568710192 0.0698473677 0.0053691548 0.0359150000 386181437 0 402718720 -0.2359022796 -0.0051313378 -0.1280912161 435 1311867184.9332280159 0.0489981323 0.0568529206 0.0698473677 0.0053679398 0.0412870000 386184417 0 402718720 -0.2317114174 -0.0050805639 -0.1274865270 436 1311867184.9656410217 0.0476219356 0.0568317486 0.0698473677 0.0053682130 0.0412730000 386187789 0 402718720 -0.2296629250 -0.0076451609 -0.1263770312 437 1311867184.9983251095 0.0488619395 0.0568135111 0.0698473677 0.0053753486 0.0407280000 386190945 0 402718720 -0.2281991243 -0.0071736923 -0.1238319576 438 1311867185.0360550880 0.0479876660 0.0567933608 0.0698473677 0.0053697774 0.0404320000 386194109 0 402718720 -0.2237167954 -0.0082998034 -0.1228935719 439 1311867185.0652348995 0.0466998331 0.0567703687 0.0698473677 0.0053658120 0.0402580000 386197537 0 402718720 -0.2204109579 -0.0112203769 -0.1218038350 440 1311867185.0991280079 0.0484828092 0.0567515333 0.0698473677 0.0053638815 0.0406510000 386201061 0 402718720 -0.2202867717 -0.0090048984 -0.1193478703 441 1311867185.1360778809 0.0470513739 0.0567295375 0.0698473677 0.0053589492 0.0410020000 386204625 0 402718720 -0.2163334191 -0.0107639823 -0.1183354855 442 1311867185.1648709774 0.0480436496 0.0567098862 0.0698473677 0.0053532441 0.0362670000 386207701 0 402718720 -0.2127890438 -0.0122685395 -0.1149173379 443 1311867185.2000720501 0.0465398058 0.0566869289 0.0698473677 0.0053479577 0.0357650000 386210913 0 402718720 -0.2083257884 -0.0131191919 -0.1147525162 444 1311867185.2342920303 0.0453537107 0.0566614036 0.0698473677 0.0053464229 0.0483160000 386214253 0 402718720 -0.2050918043 -0.0146573987 -0.1139629930 445 1311867185.2663950920 0.0466518216 0.0566389102 0.0698473677 0.0053435873 0.0361240000 386217537 0 402718720 -0.2022202909 -0.0160336122 -0.1104926094 446 1311867185.2970550060 0.0467001051 0.0566166258 0.0698473677 0.0053722815 0.0366250000 386220805 0 402718720 -0.1986725926 -0.0153052192 -0.1092981026 447 1311867185.3360140324 0.0465181284 0.0565940341 0.0698473677 0.0053665470 0.0364720000 386224409 0 402718720 -0.1962347925 -0.0157701094 -0.1078999043 448 1311867185.3681778908 0.0459527634 0.0565702813 0.0698473677 0.0053607395 0.0360240000 386227517 0 402718720 -0.1942713559 -0.0183167253 -0.1061314046 449 1311867185.4036509991 0.0470217727 0.0565490151 0.0698473677 0.0053569967 0.0361830000 386230897 0 402718720 -0.1907317340 -0.0177509338 -0.1042330712 450 1311867185.4386389256 0.0452106372 0.0565238187 0.0698473677 0.0053527303 0.0447960000 386234053 0 402718720 -0.1862707287 -0.0181267988 -0.1051847488 451 1311867185.4655449390 0.0454614311 0.0564992901 0.0698473677 0.0053506053 0.0366280000 386237001 0 402718720 -0.1863439232 -0.0199246518 -0.1037309840 452 1311867185.5013909340 0.0457720831 0.0564755574 0.0698473677 0.0053658372 0.0360310000 386240485 0 402718720 -0.1807589382 -0.0205774084 -0.1025764570 453 1311867185.5336329937 0.0457512960 0.0564518835 0.0698473677 0.0053764082 0.0359310000 386243793 0 402718720 -0.1778648496 -0.0194308981 -0.1026638970 454 1311867185.5666799545 0.0457081571 0.0564282189 0.0698473677 0.0053738626 0.0360910000 386246997 0 402718720 -0.1786089092 -0.0218344033 -0.1010483727 455 1311867185.5970540047 0.0464040078 0.0564061877 0.0698473677 0.0053740961 0.0362640000 386250169 0 402718720 -0.1724204868 -0.0213483274 -0.1005360037 456 1311867185.6329469681 0.0467771627 0.0563850714 0.0698473677 0.0053883492 0.0432660000 386253445 0 402718720 -0.1706063449 -0.0223604962 -0.0991877913 457 1311867185.6664180756 0.0461186804 0.0563626067 0.0698473677 0.0053891934 0.0473850000 386256945 0 402718720 -0.1679426879 -0.0233092904 -0.0989797637 458 1311867185.6973390579 0.0450368226 0.0563378779 0.0698473677 0.0053837720 0.0364830000 386260189 0 402718720 -0.1645356864 -0.0249880217 -0.0987308174 459 1311867185.7351899147 0.0469273478 0.0563173756 0.0698473677 0.0053821479 0.0368990000 386263465 0 402718720 -0.1629850417 -0.0227796286 -0.0967454612 460 1311867185.7649769783 0.0468458310 0.0562967853 0.0698473677 0.0053821958 0.0369390000 386267045 0 402718720 -0.1576286554 -0.0276950896 -0.0934637934 461 1311867185.7989649773 0.0472857505 0.0562772386 0.0698473677 0.0053959319 0.0363840000 386270193 0 402718720 -0.1550205648 -0.0268276203 -0.0932769626 462 1311867185.8327999115 0.0470978022 0.0562573697 0.0698473677 0.0053902719 0.0454570000 386273677 0 402718720 -0.1530511379 -0.0275653657 -0.0922595337 463 1311867185.8649098873 0.0465009287 0.0562362975 0.0698473677 0.0053847660 0.0368020000 386276953 0 402718720 -0.1513292640 -0.0292050559 -0.0912635624 464 1311867185.9030420780 0.0466100797 0.0562155513 0.0698473677 0.0053796025 0.0365940000 386279973 0 402718720 -0.1491135955 -0.0291686170 -0.0901643783 465 1311867185.9396789074 0.0459195487 0.0561934094 0.0698473677 0.0053739355 0.0370500000 386283497 0 402718720 -0.1488232911 -0.0299847126 -0.0894008130 466 1311867185.9650609493 0.0430679210 0.0561652431 0.0698473677 0.0053889884 0.0367730000 386286301 0 402718720 -0.1456046849 -0.0346351862 -0.0895150006 467 1311867186.0039470196 0.0448270515 0.0561409643 0.0698473677 0.0053940170 0.0474440000 386289945 0 402718720 -0.1438264996 -0.0326787010 -0.0882591084 468 1311867186.0396919250 0.0449604765 0.0561170744 0.0698473677 0.0053906960 0.0369240000 386292901 0 402718720 -0.1411332637 -0.0333323702 -0.0867854133 469 1311867186.0653240681 0.0442442745 0.0560917592 0.0698473677 0.0053882964 0.0367130000 386296177 0 402718720 -0.1419282407 -0.0360522419 -0.0857047662 470 1311867186.1047339439 0.0451918989 0.0560685680 0.0698473677 0.0053837405 0.0366920000 386299605 0 402718720 -0.1390087157 -0.0356566831 -0.0842851624 471 1311867186.1361179352 0.0444541387 0.0560439089 0.0698473677 0.0053806207 0.0367510000 386302553 0 402718720 -0.1373919100 -0.0362027399 -0.0847918913 472 1311867186.1649448872 0.0439802222 0.0560183503 0.0698473677 0.0053756464 0.0362990000 386305773 0 402718720 -0.1362954974 -0.0376877747 -0.0843884498 473 1311867186.2044749260 0.0437020473 0.0559923116 0.0698473677 0.0053699731 0.0360740000 386308921 0 402718720 -0.1340080947 -0.0386379398 -0.0839822143 474 1311867186.2359659672 0.0444090478 0.0559678743 0.0698473677 0.0053655430 0.0361400000 386312285 0 402718720 -0.1309129894 -0.0384317078 -0.0830306113 475 1311867186.2674899101 0.0430096537 0.0559405939 0.0698473677 0.0053605183 0.0362410000 386315417 0 402718720 -0.1300736666 -0.0404583104 -0.0833784938 476 1311867186.3030838966 0.0435763486 0.0559146186 0.0698473677 0.0053563940 0.0360960000 386318757 0 402718720 -0.1277534664 -0.0407410748 -0.0820546523 477 1311867186.3349270821 0.0405424088 0.0558823917 0.0698473677 0.0053638749 0.0356760000 386321689 0 402718720 -0.1231351048 -0.0415231176 -0.0843697041 478 1311867186.3670160770 0.0424453206 0.0558542807 0.0698473677 0.0053604697 0.0358790000 386324877 0 402718720 -0.1225112975 -0.0443384014 -0.0800502971 479 1311867186.4019849300 0.0449325219 0.0558314795 0.0698473677 0.0053686430 0.0363690000 386328113 0 402718720 -0.1209794581 -0.0407242440 -0.0788197443 480 1311867186.4360210896 0.0443144999 0.0558074858 0.0698473677 0.0053666613 0.0362030000 386331429 0 402718720 -0.1200536266 -0.0428158566 -0.0771126747 481 1311867186.4659481049 0.0440294072 0.0557829992 0.0698473677 0.0053613557 0.0365550000 386334761 0 402718720 -0.1195087209 -0.0456040353 -0.0753836036 482 1311867186.5031139851 0.0436316766 0.0557577889 0.0698473677 0.0053575943 0.0451270000 386337869 0 402718720 -0.1180971712 -0.0447742194 -0.0756167695 483 1311867186.5363171101 0.0438559018 0.0557331474 0.0698473677 0.0053526205 0.0363920000 386341417 0 402718720 -0.1150329933 -0.0445111096 -0.0744884312 484 1311867186.5651130676 0.0445062742 0.0557099513 0.0698473677 0.0053504711 0.0470820000 386344445 0 402718720 -0.1130277663 -0.0475501753 -0.0717013478 485 1311867186.6014220715 0.0451463088 0.0556881706 0.0698473677 0.0053466000 0.0366060000 386347913 0 402718720 -0.1130980402 -0.0473266989 -0.0714625269 486 1311867186.6362628937 0.0433520265 0.0556627876 0.0698473677 0.0053440969 0.0365260000 386351101 0 402718720 -0.1082769632 -0.0479527414 -0.0731060803 487 1311867186.6650478840 0.0426340550 0.0556360346 0.0698473677 0.0053395356 0.0361040000 386353881 0 402718720 -0.1075027585 -0.0471245088 -0.0746289343 488 1311867186.7043809891 0.0429125093 0.0556099618 0.0698473677 0.0053478694 0.0463580000 386357661 0 402718720 -0.1061887816 -0.0479627624 -0.0738705844 489 1311867186.7337749004 0.0439155027 0.0555860467 0.0698473677 0.0053510105 0.0484880000 386360841 0 402718720 -0.1031967252 -0.0443180129 -0.0747917593 490 1311867186.7673180103 0.0436954796 0.0555617803 0.0698473677 0.0053468287 0.0361380000 386364221 0 402718720 -0.1033376902 -0.0449154973 -0.0746167228 491 1311867186.8047299385 0.0411413051 0.0555324107 0.0698473677 0.0053532895 0.0363150000 386367569 0 402718720 -0.1002970859 -0.0485063307 -0.0757747144 492 1311867186.8340749741 0.0429548249 0.0555068465 0.0698473677 0.0053552854 0.0361670000 386370413 0 402718720 -0.0990559533 -0.0442211255 -0.0760060549 493 1311867186.8775999546 0.0429426357 0.0554813612 0.0698473677 0.0053504810 0.0412570000 387049137 0 402718720 -0.0969718918 -0.0446673855 -0.0755461603 494 1311867186.9052100182 0.0432799049 0.0554566619 0.0698473677 0.0053454821 0.1169990000 387011157 0 402718720 -0.0959699303 -0.0442104191 -0.0753571913 495 1311867186.9334239960 0.0432063155 0.0554319138 0.0698473677 0.0053406298 0.1066480000 387326141 0 402718720 -0.0937444419 -0.0432662331 -0.0757216364 496 1311867186.9663379192 0.0440739878 0.0554090147 0.0698473677 0.0053382218 0.1021720000 393237881 0 402718720 -0.0888322368 -0.0401667655 -0.0760726035 497 1311867187.0017139912 0.0431730039 0.0553843950 0.0698473677 0.0053437118 0.0773340000 393265481 0 402718720 -0.0865748972 -0.0439331979 -0.0752400160 498 1311867187.0336461067 0.0437115431 0.0553609555 0.0698473677 0.0053544887 0.1216050000 391651613 0 402718720 -0.0860330015 -0.0418777317 -0.0759325624 499 1311867187.0749349594 0.0448824242 0.0553399565 0.0698473677 0.0053503770 0.0388570000 387022345 0 402718720 -0.0833515078 -0.0399966240 -0.0752581209 500 1311867187.1016030312 0.0443890467 0.0553180546 0.0698473677 0.0053477309 0.0378410000 387025541 0 402718720 -0.0806478709 -0.0413350463 -0.0750513747 501 1311867187.1342070103 0.0439776070 0.0552954190 0.0698473677 0.0053468548 0.0375190000 387028849 0 402718720 -0.0791463554 -0.0440996736 -0.0749225989 502 1311867187.1710209846 0.0454926081 0.0552758915 0.0698473677 0.0053573991 0.0369830000 387032445 0 402718720 -0.0781217068 -0.0398091897 -0.0755729303 503 1311867187.2041370869 0.0452373549 0.0552559342 0.0698473677 0.0053633254 0.0378870000 387035873 0 402718720 -0.0746016055 -0.0414863303 -0.0755882859 504 1311867187.2331659794 0.0460813306 0.0552377306 0.0698473677 0.0053602658 0.0382940000 387039125 0 402718720 -0.0737103373 -0.0417769440 -0.0751376674 505 1311867187.2707629204 0.0462062731 0.0552198465 0.0698473677 0.0053589739 0.0377610000 387042305 0 402718720 -0.0724632889 -0.0403494760 -0.0758083388 506 1311867187.3015060425 0.0458753295 0.0552013791 0.0698473677 0.0053617322 0.0376500000 387045885 0 402718720 -0.0700637549 -0.0407054499 -0.0759082362 507 1311867187.3336570263 0.0461966991 0.0551836184 0.0698473677 0.0053570852 0.0379670000 387049009 0 402718720 -0.0696724728 -0.0416406356 -0.0758303553 508 1311867187.3707590103 0.0456304811 0.0551648130 0.0698473677 0.0053530225 0.0377310000 387052213 0 402718720 -0.0688892528 -0.0410167910 -0.0773596391 509 1311867187.4033529758 0.0453077666 0.0551454475 0.0698473677 0.0053499524 0.0383070000 387055769 0 402718720 -0.0692194551 -0.0416139886 -0.0782910809 510 1311867187.4335899353 0.0447851866 0.0551251332 0.0698473677 0.0053482266 0.0378620000 387058525 0 402718720 -0.0665087998 -0.0406921357 -0.0794665888 511 1311867187.4763159752 0.0449618995 0.0551052443 0.0698473677 0.0053434551 0.0376450000 387062081 0 402718720 -0.0612550043 -0.0401838049 -0.0799007639 512 1311867187.5056400299 0.0447406508 0.0550850010 0.0698473677 0.0053397013 0.0374590000 387065293 0 402718720 -0.0587663986 -0.0428489968 -0.0800291002 513 1311867187.5342190266 0.0451275781 0.0550655908 0.0698473677 0.0053392319 0.0371710000 387117633 0 402718720 -0.0565742813 -0.0410709381 -0.0816355348 514 1311867187.5709679127 0.0448308289 0.0550456788 0.0698473677 0.0053350551 0.0365920000 387223357 0 402718720 -0.0533270501 -0.0431891531 -0.0822396427 515 1311867187.6045789719 0.0448933132 0.0550259655 0.0698473677 0.0053595981 0.0366670000 387226713 0 402718720 -0.0505647510 -0.0425303802 -0.0831356198 516 1311867187.6353919506 0.0453216285 0.0550071586 0.0698473677 0.0053575793 0.0366070000 387229725 0 402718720 -0.0486646742 -0.0427818522 -0.0841249898 517 1311867187.6707689762 0.0440786183 0.0549860203 0.0698473677 0.0053577548 0.0362320000 387232993 0 402718720 -0.0447248891 -0.0418462120 -0.0865552053 518 1311867187.7035770416 0.0458330810 0.0549683505 0.0698473677 0.0053591685 0.0366020000 387236773 0 402718720 -0.0432408080 -0.0422549918 -0.0857621133 519 1311867187.7345480919 0.0445316881 0.0549482413 0.0698473677 0.0053658838 0.0474780000 387239401 0 402718720 -0.0429118611 -0.0458456725 -0.0870004594 520 1311867187.7707819939 0.0444442108 0.0549280413 0.0698473677 0.0053663265 0.0355630000 387242517 0 402718720 -0.0378384478 -0.0399574190 -0.0893530622 521 1311867187.8017508984 0.0429992266 0.0549051453 0.0698473677 0.0053679591 0.0359390000 387245905 0 402718720 -0.0370772295 -0.0428764224 -0.0907473490 522 1311867187.8339610100 0.0440847315 0.0548844165 0.0698473677 0.0053647687 0.0488650000 387248957 0 402718720 -0.0342474841 -0.0404520780 -0.0909532011 523 1311867187.8708090782 0.0433835648 0.0548624263 0.0698473677 0.0053647078 0.0361550000 387252265 0 402718720 -0.0322447047 -0.0409595259 -0.0916676745 524 1311867187.9038810730 0.0439540297 0.0548416088 0.0698473677 0.0053639745 0.0358100000 387255765 0 402718720 -0.0284252763 -0.0394391716 -0.0917270184 525 1311867187.9363000393 0.0433294140 0.0548196808 0.0698473677 0.0053605890 0.0479150000 387259017 0 402718720 -0.0284388363 -0.0406956077 -0.0930355862 526 1311867187.9713420868 0.0433638580 0.0547979017 0.0698473677 0.0053614312 0.0361290000 387262261 0 402718720 -0.0245855041 -0.0420639589 -0.0933142826 527 1311867188.0047569275 0.0433271416 0.0547761355 0.0698473677 0.0053902736 0.0359450000 387265657 0 402718720 -0.0205257721 -0.0389158279 -0.0955692083 528 1311867188.0333108902 0.0427241921 0.0547533099 0.0698473677 0.0053918172 0.0365620000 387268725 0 402718720 -0.0164784342 -0.0411546603 -0.0958502516 529 1311867188.0698699951 0.0442339368 0.0547334245 0.0698473677 0.0053895112 0.0482770000 387271817 0 402718720 -0.0154095190 -0.0424888916 -0.0956839025 530 1311867188.1088800430 0.0432461984 0.0547117505 0.0698473677 0.0053951091 0.0358070000 387275597 0 402718720 -0.0094759436 -0.0413835272 -0.0979469717 531 1311867188.1359970570 0.0412985831 0.0546864903 0.0698473677 0.0054042128 0.0452950000 387278593 0 402718720 -0.0069362447 -0.0404768027 -0.1002223641 532 1311867188.1703350544 0.0428238846 0.0546641921 0.0698473677 0.0054038878 0.0358600000 387282405 0 402718720 -0.0068902085 -0.0424849652 -0.1012336761 533 1311867188.2026720047 0.0430923179 0.0546424813 0.0698473677 0.0054054023 0.0484510000 387285689 0 402718720 -0.0029883189 -0.0434668884 -0.1015630811 534 1311867188.2352449894 0.0421862192 0.0546191550 0.0698473677 0.0054138414 0.0364320000 387288717 0 402718720 0.0008167457 -0.0418674238 -0.1034969464 535 1311867188.2706460953 0.0422376506 0.0545960120 0.0698473677 0.0054118954 0.0364350000 387292025 0 402718720 0.0033462280 -0.0426113904 -0.1051281616 536 1311867188.3047339916 0.0430871546 0.0545745402 0.0698473677 0.0054081820 0.0479790000 387295269 0 402718720 0.0073424168 -0.0430797935 -0.1050474867 537 1311867188.3398799896 0.0431942046 0.0545533478 0.0698473677 0.0054045322 0.0473760000 387298801 0 402718720 0.0088429833 -0.0410384163 -0.1072008014 538 1311867188.3718800545 0.0429370701 0.0545317562 0.0698473677 0.0054022761 0.0363870000 387302021 0 402718720 0.0122680310 -0.0389293842 -0.1085756198 539 1311867188.4054470062 0.0419907272 0.0545084890 0.0698473677 0.0054086635 0.0363340000 387304897 0 402718720 0.0170405991 -0.0404226407 -0.1085422859 540 1311867188.4398789406 0.0420298837 0.0544853804 0.0698473677 0.0054045352 0.0363350000 387308445 0 402718720 0.0207102410 -0.0400624573 -0.1089711785 541 1311867188.4724500179 0.0426474251 0.0544634988 0.0698473677 0.0054051291 0.0364870000 387311545 0 402718720 0.0227750130 -0.0374067202 -0.1098093390 542 1311867188.5049159527 0.0421290174 0.0544407415 0.0698473677 0.0054102789 0.0370750000 387314677 0 402718720 0.0248601437 -0.0375831872 -0.1105496809 543 1311867188.5389990807 0.0426243506 0.0544189802 0.0698473677 0.0054087154 0.0531590000 387991093 0 402718720 0.0295584276 -0.0377104655 -0.1096515059 544 1311867188.5723888874 0.0424788855 0.0543970315 0.0698473677 0.0054162176 0.1231080000 387985501 0 402718720 0.0328905731 -0.0328455418 -0.1118984818 545 1311867188.6045958996 0.0420294367 0.0543743386 0.0698473677 0.0054119149 0.1118290000 387987513 0 402718720 0.0337407738 -0.0348853692 -0.1119673848 546 1311867188.6398339272 0.0427931920 0.0543531277 0.0698473677 0.0054079242 0.1077150000 388272225 0 402718720 0.0357918926 -0.0370255932 -0.1108520329 547 1311867188.6715080738 0.0429126397 0.0543322128 0.0698473677 0.0054048831 0.0988180000 394852053 0 402718720 0.0420161635 -0.0343873017 -0.1117905602 548 1311867188.7038300037 0.0427485481 0.0543110747 0.0698473677 0.0054027543 0.0763120000 394677601 0 402718720 0.0416777506 -0.0352726690 -0.1132287979 549 1311867188.7393829823 0.0438434556 0.0542920080 0.0698473677 0.0054032151 0.1113060000 393006015 0 402718720 0.0427839346 -0.0369641669 -0.1130138114 550 1311867188.7721049786 0.0437524877 0.0542728452 0.0698473677 0.0054025221 0.0433900000 388000925 0 402718720 0.0492408425 -0.0355087258 -0.1142247543 551 1311867188.8045220375 0.0449050590 0.0542558438 0.0698473677 0.0054015760 0.0436610000 388004465 0 402718720 0.0529215895 -0.0348718390 -0.1145794317 552 1311867188.8402431011 0.0463950224 0.0542416032 0.0698473677 0.0054031154 0.0438660000 388007957 0 402718720 0.0547412485 -0.0359464735 -0.1149172112 553 1311867188.8705990314 0.0456824601 0.0542261255 0.0698473677 0.0053987668 0.0429140000 388010953 0 402718720 0.0575142056 -0.0363598131 -0.1170482337 554 1311867188.9016311169 0.0460144877 0.0542113031 0.0698473677 0.0053958911 0.0427830000 388014213 0 402718720 0.0602692477 -0.0341857821 -0.1187218651 555 1311867188.9401769638 0.0484447852 0.0542009130 0.0698473677 0.0053932670 0.0426780000 388017841 0 402718720 0.0619807914 -0.0365134031 -0.1175116599 556 1311867188.9709990025 0.0475727767 0.0541889919 0.0698473677 0.0053911369 0.0422400000 388020813 0 402718720 0.0665309355 -0.0362740979 -0.1190327778 557 1311867189.0052258968 0.0467736833 0.0541756789 0.0698473677 0.0053863719 0.0428040000 388024457 0 402718720 0.0718263909 -0.0343392119 -0.1209382787 558 1311867189.0400099754 0.0476722606 0.0541640240 0.0698473677 0.0053869183 0.0421850000 388027685 0 402718720 0.0768373758 -0.0358176604 -0.1196760461 559 1311867189.0724329948 0.0486454889 0.0541541519 0.0698473677 0.0053885123 0.0420460000 388031025 0 402718720 0.0776667967 -0.0363146365 -0.1189978421 560 1311867189.1026360989 0.0472258963 0.0541417800 0.0698473677 0.0053849405 0.0418500000 388033909 0 402718720 0.0812169239 -0.0356506519 -0.1202498376 561 1311867189.1417639256 0.0485449396 0.0541318035 0.0698473677 0.0053842012 0.0401270000 388037281 0 402718720 0.0816714913 -0.0352175348 -0.1191306338 562 1311867189.1717920303 0.0487250201 0.0541221828 0.0698473677 0.0053851650 0.0478380000 388040421 0 402718720 0.0853034705 -0.0351629108 -0.1174503863 563 1311867189.2019069195 0.0479170308 0.0541111613 0.0698473677 0.0053820255 0.0357500000 388043769 0 402718720 0.0877355933 -0.0356470309 -0.1171813458 564 1311867189.2390630245 0.0473678745 0.0540992051 0.0698473677 0.0053787259 0.0353910000 388046965 0 402718720 0.0906281322 -0.0365673415 -0.1163482442 565 1311867189.2722640038 0.0480094925 0.0540884268 0.0698473677 0.0053761133 0.0403440000 388694569 0 402718720 0.0884160995 -0.0379578099 -0.1156599894 566 1311867189.3046789169 0.0488122404 0.0540791049 0.0698473677 0.0053717048 0.1157600000 388941781 0 402718720 0.0920426771 -0.0379428342 -0.1137585863 567 1311867189.3397970200 0.0470189042 0.0540666531 0.0698473677 0.0053810988 0.1038260000 395839545 0 402718720 0.0941439345 -0.0404686891 -0.1139015257 568 1311867189.3720359802 0.0469445996 0.0540541143 0.0698473677 0.0054181106 0.0772270000 395659193 0 402718720 0.0974697396 -0.0411841720 -0.1135577783 569 1311867189.4056949615 0.0482744426 0.0540439567 0.0698473677 0.0054190620 0.1306030000 393993295 0 402718720 0.1006613970 -0.0398501307 -0.1115690321 570 1311867189.4405019283 0.0481774025 0.0540336645 0.0698473677 0.0054210524 0.0381100000 388633437 0 402718720 0.1034462899 -0.0424740762 -0.1104187146 571 1311867189.4729130268 0.0484465845 0.0540238797 0.0698473677 0.0054174379 0.0378030000 388636945 0 402718720 0.1069542393 -0.0429085270 -0.1105850339 572 1311867189.5060400963 0.0479840189 0.0540133205 0.0698473677 0.0054152056 0.0371120000 388640093 0 402718720 0.1109407842 -0.0437960029 -0.1102362126 573 1311867189.5394289494 0.0482331440 0.0540032330 0.0698473677 0.0054112163 0.0376910000 388643225 0 402718720 0.1152031347 -0.0462301634 -0.1093275771 574 1311867189.5720269680 0.0475969464 0.0539920722 0.0698473677 0.0054086619 0.0366660000 388646893 0 402718720 0.1179344505 -0.0490706041 -0.1102828532 575 1311867189.6112909317 0.0493049733 0.0539839207 0.0698473677 0.0054087775 0.0367950000 388650177 0 402718720 0.1216937304 -0.0477319807 -0.1104935482 576 1311867189.6424219608 0.0483494326 0.0539741386 0.0698473677 0.0054044545 0.0369180000 388653597 0 402718720 0.1267053485 -0.0495387465 -0.1107615009 577 1311867189.6728401184 0.0474461131 0.0539628249 0.0698473677 0.0054005412 0.0746940000 388656841 0 402718720 0.1309024096 -0.0523287840 -0.1108479202 578 1311867189.7065870762 0.0487580448 0.0539538201 0.0698473677 0.0053986311 0.0366020000 388659973 0 402718720 0.1353908181 -0.0522167757 -0.1097744629 579 1311867189.7401719093 0.0488780513 0.0539450536 0.0698473677 0.0053944437 0.0369920000 388663369 0 402718720 0.1395535618 -0.0516503565 -0.1094349697 580 1311867189.7729759216 0.0471926071 0.0539334115 0.0698473677 0.0053908954 0.0370450000 388666581 0 402718720 0.1438239664 -0.0520192683 -0.1108135432 581 1311867189.8073968887 0.0483656377 0.0539238284 0.0698473677 0.0053944135 0.0372860000 388669833 0 402718720 0.1460921913 -0.0544826426 -0.1076995283 582 1311867189.8405311108 0.0488592796 0.0539151264 0.0698473677 0.0053920617 0.0453590000 388672949 0 402718720 0.1497681737 -0.0538634211 -0.1068517715 583 1311867189.8713529110 0.0470579043 0.0539033645 0.0698473677 0.0053915755 0.0411150000 389305725 0 402718720 0.1541774124 -0.0568115003 -0.1065332144 584 1311867189.9102680683 0.0487761274 0.0538945850 0.0698473677 0.0053901402 0.1192550000 389278233 0 402718720 0.1554565430 -0.0568105280 -0.1052820608 585 1311867189.9402260780 0.0478210449 0.0538842028 0.0698473677 0.0053862109 0.1059830000 393601273 0 402718720 0.1597400457 -0.0565310009 -0.1057103425 586 1311867189.9727621078 0.0485385321 0.0538750805 0.0698473677 0.0053820391 0.0895900000 394931845 0 402718720 0.1634099185 -0.0562095903 -0.1046721935 587 1311867190.0107009411 0.0481313504 0.0538652956 0.0698473677 0.0053810907 0.0504830000 396382785 0 402718720 0.1667671353 -0.0582768433 -0.1045927256 588 1311867190.0402929783 0.0481130145 0.0538555128 0.0698473677 0.0053782898 0.1066000000 394351661 0 402718720 0.1712231338 -0.0586354323 -0.1040818021 589 1311867190.0719039440 0.0492926352 0.0538477660 0.0698473677 0.0053755169 0.0380700000 389292333 0 402718720 0.1730917245 -0.0589865148 -0.1034564376 590 1311867190.1096539497 0.0492283069 0.0538399364 0.0698473677 0.0053735836 0.0384870000 389295601 0 402718720 0.1761959791 -0.0613000207 -0.1034888923 591 1311867190.1396369934 0.0494393148 0.0538324904 0.0698473677 0.0053696479 0.0386120000 389298829 0 402718720 0.1808867455 -0.0607703738 -0.1033312753 592 1311867190.1706380844 0.0489483289 0.0538242401 0.0698473677 0.0053772806 0.0375320000 389301833 0 402718720 0.1821532547 -0.0630259067 -0.1039768606 593 1311867190.2096021175 0.0496645942 0.0538172255 0.0698473677 0.0053739748 0.0501710000 389305541 0 402718720 0.1854721308 -0.0659615099 -0.1028844267 594 1311867190.2394330502 0.0504587926 0.0538115716 0.0698473677 0.0053810337 0.0372350000 389308801 0 402718720 0.1879212707 -0.0631245002 -0.1038345918 595 1311867190.2714810371 0.0503403433 0.0538057376 0.0698473677 0.0053851548 0.0368750000 389311941 0 402718720 0.1909091175 -0.0644429326 -0.1035178453 596 1311867190.3072700500 0.0486963317 0.0537971648 0.0698473677 0.0053820403 0.0370970000 389315329 0 402718720 0.1935003698 -0.0660924539 -0.1051861793 597 1311867190.3414731026 0.0495759994 0.0537900941 0.0698473677 0.0053802682 0.0369880000 389318437 0 402718720 0.1969640702 -0.0648464411 -0.1044638231 598 1311867190.3716828823 0.0503526665 0.0537843459 0.0698473677 0.0053819292 0.0363170000 389321449 0 402718720 0.1999678165 -0.0630815402 -0.1037829369 599 1311867190.4101090431 0.0488779955 0.0537761550 0.0698473677 0.0053794556 0.0480910000 389325109 0 402718720 0.2034862936 -0.0646471232 -0.1044995636 600 1311867190.4394960403 0.0496325046 0.0537692489 0.0698473677 0.0053788523 0.0362000000 389328697 0 402718720 0.2074566931 -0.0618063956 -0.1039680243 601 1311867190.4708199501 0.0503539667 0.0537635663 0.0698473677 0.0053756408 0.0364410000 389331573 0 402718720 0.2083938718 -0.0645871684 -0.1021431163 602 1311867190.5097529888 0.0499260388 0.0537571917 0.0698473677 0.0053717274 0.0359590000 389335113 0 402718720 0.2109051794 -0.0651041940 -0.1021813825 603 1311867190.5405189991 0.0490732342 0.0537494239 0.0698473677 0.0053693488 0.0362400000 389338277 0 402718720 0.2149825543 -0.0637617037 -0.1030163243 604 1311867190.5708439350 0.0493845791 0.0537421973 0.0698473677 0.0053674279 0.0360500000 389341321 0 402718720 0.2163525224 -0.0648198873 -0.1023279279 605 1311867190.6067750454 0.0491105653 0.0537345417 0.0698473677 0.0053639074 0.0460050000 389344645 0 402718720 0.2200436145 -0.0658905953 -0.1013600677 606 1311867190.6389939785 0.0494046323 0.0537273967 0.0698473677 0.0053609259 0.0409490000 389992713 0 402718720 0.2218083888 -0.0654334873 -0.1009574682 607 1311867190.6723659039 0.0499049462 0.0537210994 0.0698473677 0.0053567995 0.1181290000 389972157 0 402718720 0.2260159254 -0.0668302178 -0.0990099832 608 1311867190.7114980221 0.0506293885 0.0537160143 0.0698473677 0.0053570490 0.1117330000 389973473 0 402718720 0.2271656394 -0.0666644946 -0.0984207615 609 1311867190.7392649651 0.0520771369 0.0537133232 0.0698473677 0.0053529646 0.1097210000 390281629 0 402718720 0.2279250622 -0.0663801208 -0.0967647135 610 1311867190.7751801014 0.0504020341 0.0537078949 0.0698473677 0.0053498075 0.1090260000 396151065 0 402718720 0.2318555117 -0.0676130801 -0.0967626795 611 1311867190.8070900440 0.0513882637 0.0537040985 0.0698473677 0.0053477763 0.0824060000 397404605 0 402718720 0.2339211106 -0.0673965886 -0.0952732638 612 1311867190.8414280415 0.0511008352 0.0536998448 0.0698473677 0.0053481577 0.1203690000 395582041 0 402718720 0.2356768250 -0.0688163340 -0.0947431996 613 1311867190.8739249706 0.0508212410 0.0536951488 0.0698473677 0.0053451940 0.0400760000 389941813 0 402718720 0.2378812879 -0.0693833902 -0.0945816413 614 1311867190.9076139927 0.0509591289 0.0536906928 0.0698473677 0.0053410668 0.0385970000 389945161 0 402718720 0.2408171147 -0.0690321252 -0.0936340839 615 1311867190.9393599033 0.0511234067 0.0536865183 0.0698473677 0.0053373315 0.0392870000 389948109 0 402718720 0.2426911741 -0.0716511086 -0.0922074616 616 1311867190.9741609097 0.0497053936 0.0536800555 0.0698473677 0.0053330814 0.0382210000 389951705 0 402718720 0.2452982068 -0.0731311888 -0.0928690135 617 1311867191.0085949898 0.0506651886 0.0536751691 0.0698473677 0.0053351171 0.0371990000 389954909 0 402718720 0.2485273778 -0.0699571595 -0.0920931771 618 1311867191.0396919250 0.0500032455 0.0536692275 0.0698473677 0.0053363529 0.0374120000 389958153 0 402718720 0.2527330816 -0.0723240376 -0.0900441557 619 1311867191.0764329433 0.0503488481 0.0536638634 0.0698473677 0.0053348783 0.0376170000 389961509 0 402718720 0.2542934418 -0.0747719184 -0.0886451900 620 1311867191.1103041172 0.0507376455 0.0536591437 0.0698473677 0.0053411478 0.0376490000 389964793 0 402718720 0.2569206357 -0.0730381012 -0.0885776505 621 1311867191.1388139725 0.0498903804 0.0536530748 0.0698473677 0.0053557845 0.0372760000 389967997 0 402718720 0.2600618601 -0.0744184107 -0.0878169090 622 1311867191.1742820740 0.0506678596 0.0536482754 0.0698473677 0.0053522687 0.0370880000 389970993 0 402718720 0.2617903948 -0.0762141198 -0.0859678015 623 1311867191.2077920437 0.0506109521 0.0536434001 0.0698473677 0.0053481295 0.0463720000 389974197 0 402718720 0.2654139400 -0.0750003830 -0.0853786841 624 1311867191.2408421040 0.0520780385 0.0536408915 0.0698473677 0.0053456439 0.0362210000 389977801 0 402718720 0.2682268620 -0.0753779337 -0.0829315931 625 1311867191.2769579887 0.0518689305 0.0536380564 0.0698473677 0.0053442208 0.0362570000 389980749 0 402718720 0.2705272138 -0.0762940496 -0.0827636048 626 1311867191.3085029125 0.0505445339 0.0536331147 0.0698473677 0.0053412794 0.0357410000 389983745 0 402718720 0.2750601172 -0.0747848898 -0.0833489448 627 1311867191.3404779434 0.0511326976 0.0536291268 0.0698473677 0.0053380912 0.0358920000 389987389 0 402718720 0.2761137187 -0.0764280483 -0.0819482729 628 1311867191.3794629574 0.0524209477 0.0536272029 0.0698473677 0.0053340541 0.0360960000 389990665 0 402718720 0.2778347135 -0.0777399838 -0.0796060562 629 1311867191.4091579914 0.0519889668 0.0536245984 0.0698473677 0.0053312408 0.0470330000 389993861 0 402718720 0.2803621888 -0.0785055459 -0.0793175101 630 1311867191.4415969849 0.0505024195 0.0536196426 0.0698473677 0.0053289545 0.0361800000 389996945 0 402718720 0.2857481241 -0.0773371309 -0.0794554502 631 1311867191.4775309563 0.0522506572 0.0536174730 0.0698473677 0.0053260392 0.0357860000 390000005 0 402718720 0.2852592468 -0.0796675235 -0.0768496171 632 1311867191.5075590611 0.0538095012 0.0536177769 0.0698473677 0.0053227779 0.0362940000 390003345 0 402718720 0.2860200703 -0.0779093206 -0.0751536191 633 1311867191.5390620232 0.0516668446 0.0536146948 0.0698473677 0.0053212070 0.0353210000 390006541 0 402718720 0.2902679741 -0.0800579637 -0.0751619786 634 1311867191.5764698982 0.0517452657 0.0536117462 0.0698473677 0.0053173233 0.0352040000 390009705 0 402718720 0.2928004861 -0.0796489492 -0.0743366778 635 1311867191.6118669510 0.0532738939 0.0536112141 0.0698473677 0.0053478574 0.0484670000 390664405 0 402718720 0.2938925624 -0.0782746524 -0.0726185963 636 1311867191.6451880932 0.0527940020 0.0536099292 0.0698473677 0.0053464895 0.1173600000 390660645 0 402718720 0.2956084311 -0.0798173845 -0.0715102851 637 1311867191.6827919483 0.0521706603 0.0536076698 0.0698473677 0.0053469863 0.1124310000 390663145 0 402718720 0.2972377241 -0.0807437375 -0.0709243938 638 1311867191.7119400501 0.0509415939 0.0536034910 0.0698473677 0.0053456756 0.1116600000 390957373 0 402718720 0.3004257679 -0.0794197470 -0.0713168159 639 1311867191.7457199097 0.0517950244 0.0536006608 0.0698473677 0.0053581380 0.1049450000 396224885 0 402718720 0.3013643920 -0.0809068531 -0.0682762861 640 1311867191.7763800621 0.0527339056 0.0535993065 0.0698473677 0.0053643116 0.0748870000 397155585 0 402718720 0.3020785153 -0.0815489441 -0.0666419417 641 1311867191.8097250462 0.0508918054 0.0535950826 0.0698473677 0.0053632115 0.0432410000 398257925 0 402718720 0.3039520085 -0.0806480721 -0.0679457337 642 1311867191.8395779133 0.0513202138 0.0535915392 0.0698473677 0.0053655022 0.1140550000 396496319 0 402718720 0.3055126965 -0.0814061686 -0.0661628917 643 1311867191.8745219707 0.0510397442 0.0535875706 0.0698473677 0.0053662999 0.0392650000 390679257 0 402718720 0.3063443601 -0.0810075477 -0.0658086091 644 1311867191.9077119827 0.0509709604 0.0535835076 0.0698473677 0.0053623586 0.0386060000 390682509 0 402718720 0.3085901737 -0.0801876485 -0.0645776242 645 1311867191.9391601086 0.0512484387 0.0535798873 0.0698473677 0.0053584745 0.0384580000 390685913 0 402718720 0.3089395761 -0.0822721720 -0.0633732527 646 1311867191.9755239487 0.0516470075 0.0535768953 0.0698473677 0.0053595830 0.0385070000 390688941 0 402718720 0.3104411960 -0.0807836503 -0.0623516738 647 1311867192.0076289177 0.0518409573 0.0535742122 0.0698473677 0.0053563659 0.0383890000 390692041 0 402718720 0.3115043044 -0.0821523219 -0.0607648194 648 1311867192.0447950363 0.0517766140 0.0535714381 0.0698473677 0.0053642543 0.0389920000 390695421 0 402718720 0.3113642931 -0.0854858160 -0.0593901388 649 1311867192.0751929283 0.0515187867 0.0535682753 0.0698473677 0.0053637173 0.0385690000 390698729 0 402718720 0.3133814335 -0.0833684877 -0.0592950843 650 1311867192.1073920727 0.0521892719 0.0535661538 0.0698473677 0.0053622547 0.0383200000 390701757 0 402718720 0.3157934844 -0.0817511156 -0.0581013933 651 1311867192.1433029175 0.0518575646 0.0535635292 0.0698473677 0.0053679860 0.0374450000 390704985 0 402718720 0.3153278828 -0.0860806033 -0.0569482408 652 1311867192.1754670143 0.0515794083 0.0535604861 0.0698473677 0.0053713734 0.0367800000 390708197 0 402718720 0.3186198473 -0.0836699456 -0.0565542094 653 1311867192.2077538967 0.0527725779 0.0535592795 0.0698473677 0.0053691137 0.0369510000 390711433 0 402718720 0.3201581240 -0.0843040496 -0.0541214682 654 1311867192.2451250553 0.0524728000 0.0535576182 0.0698473677 0.0053736191 0.0365850000 390715069 0 402718720 0.3204027414 -0.0866938829 -0.0532480292 655 1311867192.2744629383 0.0514641851 0.0535544221 0.0698473677 0.0053695279 0.0485700000 390717961 0 402718720 0.3238070011 -0.0842930973 -0.0537035204 656 1311867192.3067719936 0.0515161268 0.0535513150 0.0698473677 0.0053681287 0.0366780000 390721061 0 402718720 0.3254938722 -0.0860213041 -0.0524237677 657 1311867192.3427391052 0.0527259149 0.0535500587 0.0698473677 0.0053642841 0.0365250000 390724753 0 402718720 0.3263043165 -0.0879709646 -0.0503893942 658 1311867192.3755910397 0.0530087538 0.0535492360 0.0698473677 0.0053665217 0.0367770000 390728037 0 402718720 0.3289611638 -0.0859300718 -0.0502590723 659 1311867192.4059340954 0.0531503484 0.0535486307 0.0698473677 0.0053634987 0.0367070000 390731105 0 402718720 0.3314701319 -0.0872515142 -0.0490711257 660 1311867192.4447100163 0.0544766225 0.0535500368 0.0698473677 0.0053625750 0.0460370000 390734541 0 402718720 0.3320533335 -0.0892182738 -0.0479948111 661 1311867192.4748210907 0.0558718368 0.0535535493 0.0698473677 0.0053635006 0.0487260000 390737649 0 402718720 0.3345522881 -0.0867218077 -0.0470694713 662 1311867192.5077190399 0.0553559586 0.0535562720 0.0698473677 0.0053614604 0.0369520000 390741021 0 402718720 0.3358235657 -0.0897755548 -0.0468489379 663 1311867192.5427820683 0.0535087883 0.0535562004 0.0698473677 0.0053623108 0.0364300000 390744233 0 402718720 0.3389387429 -0.0921206921 -0.0475061014 664 1311867192.5787169933 0.0554067828 0.0535589874 0.0698473677 0.0053665517 0.0362060000 390747613 0 402718720 0.3392543793 -0.0896830782 -0.0470149219 665 1311867192.6109929085 0.0553898774 0.0535617406 0.0698473677 0.0053641657 0.0361710000 390751017 0 402718720 0.3415942788 -0.0899107829 -0.0464116894 666 1311867192.6435210705 0.0558702238 0.0535652068 0.0698473677 0.0053634217 0.0475530000 390754365 0 402718720 0.3422545493 -0.0926553607 -0.0454332754 667 1311867192.6790139675 0.0547532625 0.0535669880 0.0698473677 0.0053599380 0.0460670000 390757753 0 402718720 0.3462653756 -0.0909665599 -0.0460896753 668 1311867192.7113289833 0.0551130287 0.0535693024 0.0698473677 0.0053571563 0.0362660000 390760813 0 402718720 0.3464849591 -0.0912701190 -0.0459372327 669 1311867192.7439620495 0.0549211614 0.0535713231 0.0698473677 0.0053571015 0.0355350000 390764225 0 402718720 0.3468699753 -0.0934201032 -0.0456787422 670 1311867192.7760629654 0.0545774214 0.0535728248 0.0698473677 0.0053552186 0.0355590000 390767405 0 402718720 0.3499558568 -0.0905779153 -0.0458093062 671 1311867192.8091869354 0.0550090633 0.0535749652 0.0698473677 0.0053516007 0.0357880000 390770529 0 402718720 0.3518960774 -0.0920684338 -0.0441227108 672 1311867192.8422288895 0.0558159947 0.0535783001 0.0698473677 0.0053494504 0.0458400000 390773853 0 402718720 0.3504782319 -0.0930683613 -0.0438399278 673 1311867192.8792889118 0.0556216091 0.0535813362 0.0698473677 0.0053475662 0.0352950000 390777057 0 402718720 0.3527781069 -0.0918478817 -0.0434668101 674 1311867192.9092190266 0.0573778339 0.0535869690 0.0698473677 0.0053441596 0.0356880000 390780221 0 402718720 0.3529770374 -0.0922956467 -0.0412785038 675 1311867192.9434111118 0.0562446900 0.0535909064 0.0698473677 0.0053415751 0.0482410000 390783769 0 402718720 0.3543768525 -0.0942044407 -0.0417762995 676 1311867192.9776289463 0.0550341867 0.0535930414 0.0698473677 0.0053405121 0.0360430000 390786661 0 402718720 0.3568977118 -0.0922024325 -0.0431155115 677 1311867193.0086810589 0.0556274801 0.0535960465 0.0698473677 0.0053402399 0.0356960000 390790289 0 402718720 0.3578564525 -0.0931183845 -0.0415016338 678 1311867193.0430600643 0.0562638640 0.0535999813 0.0698473677 0.0053376104 0.0555110000 390793221 0 402718720 0.3572658598 -0.0969510302 -0.0402634293 679 1311867193.0767369270 0.0559663996 0.0536034665 0.0698473677 0.0053415658 0.0358480000 390796529 0 402718720 0.3591558933 -0.0950195044 -0.0408863127 680 1311867193.1105849743 0.0542505607 0.0536044181 0.0698473677 0.0053427429 0.0402350000 391476297 0 402718720 0.3612156212 -0.0949155912 -0.0423394404 681 1311867193.1429219246 0.0550299659 0.0536065114 0.0698473677 0.0053397280 0.1198930000 391466217 0 402718720 0.3618056476 -0.0970476419 -0.0402992778 682 1311867193.1767370701 0.0550191887 0.0536085828 0.0698473677 0.0053505087 0.1127580000 391466837 0 402718720 0.3636824787 -0.0933462232 -0.0416098423 683 1311867193.2122681141 0.0559896044 0.0536120689 0.0698473677 0.0053530114 0.1094880000 391758725 0 402718720 0.3646489680 -0.0950035974 -0.0397810116 684 1311867193.2432429790 0.0549683608 0.0536140518 0.0698473677 0.0053515361 0.1008620000 399420617 0 402718720 0.3667866588 -0.0965385363 -0.0397603139 685 1311867193.2773900032 0.0551186353 0.0536162482 0.0698473677 0.0053487674 0.0916990000 399444637 0 402718720 0.3683045805 -0.0946064144 -0.0400450863 686 1311867193.3139379025 0.0564167462 0.0536203306 0.0698473677 0.0053492039 0.0446700000 399552905 0 402718720 0.3686100245 -0.0976563171 -0.0380195603 687 1311867193.3426671028 0.0560398512 0.0536238525 0.0698473677 0.0053554590 0.1157450000 397792959 0 402718720 0.3703482151 -0.0951176807 -0.0389994606 688 1311867193.3788230419 0.0558400527 0.0536270737 0.0698473677 0.0053516910 0.0478820000 391439017 0 402718720 0.3723326921 -0.0941876918 -0.0391625687 689 1311867193.4126739502 0.0570588410 0.0536320545 0.0698473677 0.0053569825 0.0387460000 391441989 0 402718720 0.3730094731 -0.0966883227 -0.0373140462 690 1311867193.4440810680 0.0562550463 0.0536358559 0.0698473677 0.0053568607 0.0389360000 391445577 0 402718720 0.3744941652 -0.0962416306 -0.0385638550 691 1311867193.4782969952 0.0569037758 0.0536405852 0.0698473677 0.0053537006 0.0388700000 391448573 0 402718720 0.3763227165 -0.0941104814 -0.0385100953 692 1311867193.5199069977 0.0567554086 0.0536450864 0.0698473677 0.0053518730 0.0386360000 391452001 0 402718720 0.3776326180 -0.0965890363 -0.0384244733 693 1311867193.5431120396 0.0570999496 0.0536500717 0.0698473677 0.0053500422 0.0376360000 391455125 0 402718720 0.3790271580 -0.0954799131 -0.0382041447 694 1311867193.5765709877 0.0570510142 0.0536549722 0.0698473677 0.0053471054 0.0381780000 391458401 0 402718720 0.3810228109 -0.0943884626 -0.0384761766 695 1311867193.6127800941 0.0589319319 0.0536625650 0.0698473677 0.0053433344 0.0474720000 391461509 0 402718720 0.3805618882 -0.0981882215 -0.0362721160 696 1311867193.6461451054 0.0572990887 0.0536677899 0.0698473677 0.0053408948 0.0376670000 391464673 0 402718720 0.3837745488 -0.0967186466 -0.0377661251 697 1311867193.6757860184 0.0574556552 0.0536732244 0.0698473677 0.0053373279 0.0381620000 391467909 0 402718720 0.3854436576 -0.0946273059 -0.0383392721 698 1311867193.7122890949 0.0585824922 0.0536802577 0.0698473677 0.0053337628 0.0376430000 391471297 0 402718720 0.3856381774 -0.0974030942 -0.0366419517 699 1311867193.7430191040 0.0582611784 0.0536868113 0.0698473677 0.0053307143 0.0370530000 391474661 0 402718720 0.3871142268 -0.0973217785 -0.0368627980 700 1311867193.7760169506 0.0558129847 0.0536898487 0.0698473677 0.0053278511 0.0369060000 391477537 0 402718720 0.3906484544 -0.0959020853 -0.0391243361 701 1311867193.8139710426 0.0573198348 0.0536950270 0.0698473677 0.0053245636 0.0471690000 391481069 0 402718720 0.3903614879 -0.0992702544 -0.0374270976 702 1311867193.8436760902 0.0587345921 0.0537022058 0.0698473677 0.0053227141 0.0366320000 391483881 0 402718720 0.3915794790 -0.0965823010 -0.0367103815 703 1311867193.8771181107 0.0585388392 0.0537090858 0.0698473677 0.0053191397 0.0364260000 391487501 0 402718720 0.3933978379 -0.0967408866 -0.0370152593 704 1311867193.9151229858 0.0591973551 0.0537168817 0.0698473677 0.0053160387 0.0366450000 391490617 0 402718720 0.3947066665 -0.0985913947 -0.0359532870 705 1311867193.9425311089 0.0586026423 0.0537238118 0.0698473677 0.0053145599 0.0365990000 391493997 0 402718720 0.3958080709 -0.0962692425 -0.0375019126 706 1311867193.9781770706 0.0581075847 0.0537300211 0.0698473677 0.0053126674 0.0368380000 391497033 0 402718720 0.3983286917 -0.0965866297 -0.0375168361 707 1311867194.0148570538 0.0581516214 0.0537362751 0.0698473677 0.0053090816 0.0358320000 391500685 0 402718720 0.3999258280 -0.0982352123 -0.0371549353 708 1311867194.0433440208 0.0590510182 0.0537437818 0.0698473677 0.0053102509 0.0361250000 391503441 0 402718720 0.4000548124 -0.0974178761 -0.0371646248 709 1311867194.0746119022 0.0591221228 0.0537513677 0.0698473677 0.0053075983 0.0358610000 391506821 0 402718720 0.4012223780 -0.0976113677 -0.0369126499 710 1311867194.1131060123 0.0612630174 0.0537619474 0.0698473677 0.0053042403 0.0352630000 391510145 0 402718720 0.4011989236 -0.0982976854 -0.0346553586 711 1311867194.1428558826 0.0591920689 0.0537695848 0.0698473677 0.0053008830 0.0363790000 391513461 0 402718720 0.4030202627 -0.0971397385 -0.0367946997 712 1311867194.1758549213 0.0579881743 0.0537755097 0.0698473677 0.0053074610 0.0361660000 391516225 0 402718720 0.4046120644 -0.0977168083 -0.0365004390 713 1311867194.2138450146 0.0586623922 0.0537823637 0.0698473677 0.0053043591 0.0364430000 391519781 0 402718720 0.4047335088 -0.0988562629 -0.0355233736 714 1311867194.2451140881 0.0575783551 0.0537876802 0.0698473677 0.0053013174 0.0364900000 391523057 0 402718720 0.4065118432 -0.0973653272 -0.0364126936 715 1311867194.2760241032 0.0581390709 0.0537937661 0.0698473677 0.0052980270 0.0357510000 391526197 0 402718720 0.4065424204 -0.0966194421 -0.0360446423 716 1311867194.3139200211 0.0592193790 0.0538013438 0.0698473677 0.0052957867 0.0359090000 391529417 0 402718720 0.4070993066 -0.0982924178 -0.0344002396 717 1311867194.3447821140 0.0584353171 0.0538078068 0.0698473677 0.0052956879 0.0364260000 391532693 0 402718720 0.4075635970 -0.0963757411 -0.0356035121 718 1311867194.3802230358 0.0584926791 0.0538143317 0.0698473677 0.0052935387 0.0361180000 391535657 0 402718720 0.4081534743 -0.0970792547 -0.0349318609 719 1311867194.4124519825 0.0598987862 0.0538227940 0.0698473677 0.0052910163 0.0363820000 391538941 0 402718720 0.4069199860 -0.0999131426 -0.0329889022 720 1311867194.4447510242 0.0584118851 0.0538291678 0.0698473677 0.0052878175 0.0360380000 391541969 0 402718720 0.4091901183 -0.0976807624 -0.0345500745 721 1311867194.4805839062 0.0602852330 0.0538381221 0.0698473677 0.0052868675 0.0359780000 391545197 0 402718720 0.4087108672 -0.0970949158 -0.0331185870 722 1311867194.5174930096 0.0585542656 0.0538446541 0.0698473677 0.0052885192 0.0362670000 391548761 0 402718720 0.4101168513 -0.0985278860 -0.0341130234 723 1311867194.5439500809 0.0588602982 0.0538515914 0.0698473677 0.0052879432 0.0364980000 391551653 0 402718720 0.4106119275 -0.0982457623 -0.0335575715 724 1311867194.5795979500 0.0593321994 0.0538591613 0.0698473677 0.0052848116 0.0362520000 391555065 0 402718720 0.4099508524 -0.0991031528 -0.0330649987 725 1311867194.6129479408 0.0587187298 0.0538658642 0.0698473677 0.0052814321 0.0357380000 391558205 0 402718720 0.4107384384 -0.0995809436 -0.0332147591 726 1311867194.6493880749 0.0575976335 0.0538710043 0.0698473677 0.0052891214 0.0358490000 391561089 0 402718720 0.4120761454 -0.0981257856 -0.0338419490 727 1311867194.6784319878 0.0589856580 0.0538780396 0.0698473677 0.0052863161 0.0360250000 391564669 0 402718720 0.4124257267 -0.0978393704 -0.0317863971 728 1311867194.7133309841 0.0579058342 0.0538835723 0.0698473677 0.0052880630 0.0361040000 391567713 0 402718720 0.4129187465 -0.0995211303 -0.0321446471 729 1311867194.7475099564 0.0578669086 0.0538890364 0.0698473677 0.0052846279 0.0361110000 391570869 0 402718720 0.4137340486 -0.0987816900 -0.0319198072 730 1311867194.7784450054 0.0600797236 0.0538975168 0.0698473677 0.0052820577 0.0417710000 392272293 0 402718720 0.4125506580 -0.0990712792 -0.0299000293 731 1311867194.8130390644 0.0598680377 0.0539056844 0.0698473677 0.0052785455 0.1185470000 392246037 0 402718720 0.4127975404 -0.0990812033 -0.0298904479 732 1311867194.8476719856 0.0600018576 0.0539140125 0.0698473677 0.0052750466 0.1077570000 392248509 0 402718720 0.4126109481 -0.0988776088 -0.0298198164 733 1311867194.8814148903 0.0582887679 0.0539199808 0.0698473677 0.0052717405 0.1065220000 396052045 0 402718720 0.4135488570 -0.0988851041 -0.0308395997 734 1311867194.9104089737 0.0597542264 0.0539279294 0.0698473677 0.0052840308 0.0652690000 400408321 0 402718720 0.4131653309 -0.0976715237 -0.0293111838 735 1311867194.9451448917 0.0610212311 0.0539375801 0.0698473677 0.0052809189 0.0658360000 400254289 0 402718720 0.4118064940 -0.0975606367 -0.0279007144 736 1311867194.9787399769 0.0611821152 0.0539474233 0.0698473677 0.0052773971 0.1262300000 398599287 0 402718720 0.4108305871 -0.0981896594 -0.0275630467 737 1311867195.0132799149 0.0600585826 0.0539557152 0.0698473677 0.0052752899 0.0425690000 392260449 0 402718720 0.4101469815 -0.0975669399 -0.0284019820 738 1311867195.0464940071 0.0615430996 0.0539659962 0.0698473677 0.0052720115 0.0577490000 392263725 0 402718720 0.4074743092 -0.0998634472 -0.0273712277 739 1311867195.0781710148 0.0598944873 0.0539740185 0.0698473677 0.0052720796 0.0511450000 392266809 0 402718720 0.4087513089 -0.0982363820 -0.0286547467 740 1311867195.1115310192 0.0593441911 0.0539812755 0.0698473677 0.0052699891 0.0392590000 392269989 0 402718720 0.4094242454 -0.0978578478 -0.0287921056 741 1311867195.1458311081 0.0603963025 0.0539899328 0.0698473677 0.0052671400 0.0389140000 392273361 0 402718720 0.4071108103 -0.0983515680 -0.0283128992 742 1311867195.1780319214 0.0597642921 0.0539977149 0.0698473677 0.0052648216 0.0387810000 392276429 0 402718720 0.4069994688 -0.0962770358 -0.0290661417 743 1311867195.2114748955 0.0599970408 0.0540057894 0.0698473677 0.0052619937 0.0388390000 392279849 0 402718720 0.4052956700 -0.0961897373 -0.0286960863 744 1311867195.2436800003 0.0593607910 0.0540129870 0.0698473677 0.0052617902 0.0514910000 392282845 0 402718720 0.4047375917 -0.0984435305 -0.0288548805 745 1311867195.2780399323 0.0586392097 0.0540191967 0.0698473677 0.0052584256 0.0389940000 392286113 0 402718720 0.4043869972 -0.0977660716 -0.0295024887 746 1311867195.3123180866 0.0592456423 0.0540262026 0.0698473677 0.0052554250 0.0393860000 392289573 0 402718720 0.4027334750 -0.0974174514 -0.0294957496 747 1311867195.3425979614 0.0591971539 0.0540331249 0.0698473677 0.0052552330 0.0510460000 392292665 0 402718720 0.4015322924 -0.0987201408 -0.0296180658 748 1311867195.3782711029 0.0600401089 0.0540411556 0.0698473677 0.0052546944 0.0392650000 392295637 0 402718720 0.3996705115 -0.0974593014 -0.0297676735 749 1311867195.4119830132 0.0587359816 0.0540474238 0.0698473677 0.0052523692 0.0377360000 392299073 0 402718720 0.3991448283 -0.0977724940 -0.0310570747 750 1311867195.4435520172 0.0603380054 0.0540558112 0.0698473677 0.0052493381 0.0375620000 392302229 0 402718720 0.3970496356 -0.0965631679 -0.0300913267 751 1311867195.4788239002 0.0588428788 0.0540621855 0.0698473677 0.0052475848 0.0379600000 392305305 0 402718720 0.3959802687 -0.0957741439 -0.0319469236 752 1311867195.5113179684 0.0582335219 0.0540677325 0.0698473677 0.0052457759 0.0373080000 392308549 0 402718720 0.3955954313 -0.0966986194 -0.0320726894 753 1311867195.5439620018 0.0579857044 0.0540729356 0.0698473677 0.0052427573 0.0372810000 392312025 0 402718720 0.3931799531 -0.0980140492 -0.0320694782 754 1311867195.5782160759 0.0584833212 0.0540787849 0.0698473677 0.0052420326 0.0372140000 392315037 0 402718720 0.3911893964 -0.0966433510 -0.0323612317 755 1311867195.6119859219 0.0586367212 0.0540848219 0.0698473677 0.0052411069 0.0498680000 392318225 0 402718720 0.3895787299 -0.0967510268 -0.0321802311 756 1311867195.6430909634 0.0589251332 0.0540912245 0.0698473677 0.0052382371 0.0372650000 392321461 0 402718720 0.3868390620 -0.0975745767 -0.0321018323 757 1311867195.6779129505 0.0579013228 0.0540962576 0.0698473677 0.0052355839 0.0497330000 392324689 0 402718720 0.3856192529 -0.0964763388 -0.0336394534 758 1311867195.7107300758 0.0575954318 0.0541008739 0.0698473677 0.0052346447 0.0498570000 392327909 0 402718720 0.3843228221 -0.0970128551 -0.0333383307 759 1311867195.7458300591 0.0588978939 0.0541071941 0.0698473677 0.0052316099 0.0382040000 392330929 0 402718720 0.3818291426 -0.0973266214 -0.0319160111 760 1311867195.7821879387 0.0579104349 0.0541121984 0.0698473677 0.0052282072 0.0482690000 392334101 0 402718720 0.3806202412 -0.0964450464 -0.0331661515 761 1311867195.8100500107 0.0591541938 0.0541188239 0.0698473677 0.0052254931 0.0377300000 392337393 0 402718720 0.3774441779 -0.0968118086 -0.0325210020 762 1311867195.8458549976 0.0590038970 0.0541252347 0.0698473677 0.0052222495 0.0381330000 392340653 0 402718720 0.3751288652 -0.0978368819 -0.0326404423 763 1311867195.8778660297 0.0581723712 0.0541305390 0.0698473677 0.0052203642 0.0481540000 392343985 0 402718720 0.3744013309 -0.0955656320 -0.0336320028 764 1311867195.9098269939 0.0588282906 0.0541366879 0.0698473677 0.0052179998 0.0381400000 392347277 0 402718720 0.3721270263 -0.0957642868 -0.0330456123 765 1311867195.9458460808 0.0576983802 0.0541413437 0.0698473677 0.0052157867 0.0385220000 392350177 0 402718720 0.3706591129 -0.0966774449 -0.0337447524 766 1311867195.9778430462 0.0579706542 0.0541463428 0.0698473677 0.0052140701 0.0376430000 392353429 0 402718720 0.3701089323 -0.0941458866 -0.0336295776 767 1311867196.0100569725 0.0579173751 0.0541512594 0.0698473677 0.0052124813 0.0401180000 392356625 0 402718720 0.3674964309 -0.0959247500 -0.0336868539 768 1311867196.0498790741 0.0575907566 0.0541557379 0.0698473677 0.0052093544 0.0529370000 392360125 0 402718720 0.3659972847 -0.0968663022 -0.0337508023 769 1311867196.0793108940 0.0567352697 0.0541590923 0.0698473677 0.0052089548 0.0520190000 392363481 0 402718720 0.3658460379 -0.0940067396 -0.0349522531 770 1311867196.1113979816 0.0567306764 0.0541624320 0.0698473677 0.0052070596 0.0503300000 392366357 0 402718720 0.3632836044 -0.0958394781 -0.0347876027 771 1311867196.1473290920 0.0570873246 0.0541662256 0.0698473677 0.0052040360 0.0380490000 392369545 0 402718720 0.3623652160 -0.0953693092 -0.0342242718 772 1311867196.1811769009 0.0574921630 0.0541705338 0.0698473677 0.0052055328 0.0391620000 392372701 0 402718720 0.3606387079 -0.0949078798 -0.0337986536 773 1311867196.2114949226 0.0577040613 0.0541751050 0.0698473677 0.0052034744 0.0390960000 392376265 0 402718720 0.3589408696 -0.0961268619 -0.0335063525 774 1311867196.2462599277 0.0575696230 0.0541794907 0.0698473677 0.0052002256 0.0382350000 392379109 0 402718720 0.3572046459 -0.0954909548 -0.0340179577 775 1311867196.2800569534 0.0571938455 0.0541833802 0.0698473677 0.0051971892 0.0487320000 392382425 0 402718720 0.3552919924 -0.0950380415 -0.0346981883 776 1311867196.3111600876 0.0569833480 0.0541869884 0.0698473677 0.0051945674 0.0387810000 392385661 0 402718720 0.3537334204 -0.0963388979 -0.0344227850 777 1311867196.3484730721 0.0574919544 0.0541912419 0.0698473677 0.0051919479 0.0378720000 392388769 0 402718720 0.3514480591 -0.0956434831 -0.0344521031 778 1311867196.3842670918 0.0570220314 0.0541948804 0.0698473677 0.0051889834 0.0383190000 392392437 0 402718720 0.3512640297 -0.0940879807 -0.0345050655 779 1311867196.4107549191 0.0575095862 0.0541991355 0.0698473677 0.0051864769 0.0391020000 392395257 0 402718720 0.3484448493 -0.0950889140 -0.0341848843 780 1311867196.4463150501 0.0579931438 0.0542039996 0.0698473677 0.0051876352 0.0382580000 392398597 0 402718720 0.3468357027 -0.0944169611 -0.0338295847 781 1311867196.4798319340 0.0573174804 0.0542079862 0.0698473677 0.0051844481 0.0501460000 392401625 0 402718720 0.3457635641 -0.0943754539 -0.0341543145 782 1311867196.5113470554 0.0572437383 0.0542118682 0.0698473677 0.0051818753 0.0385040000 392404749 0 402718720 0.3438756764 -0.0949413702 -0.0338232778 783 1311867196.5468420982 0.0562542118 0.0542144766 0.0698473677 0.0051798785 0.0384160000 392408121 0 402718720 0.3431685269 -0.0931697637 -0.0340661928 784 1311867196.5795550346 0.0574359260 0.0542185856 0.0698473677 0.0051782861 0.0384030000 392411453 0 402718720 0.3409258425 -0.0920754597 -0.0334879793 785 1311867196.6108930111 0.0568358079 0.0542219196 0.0698473677 0.0051772396 0.0388350000 392414529 0 402718720 0.3392297924 -0.0933230519 -0.0333807059 786 1311867196.6521809101 0.0568302721 0.0542252381 0.0698473677 0.0051796844 0.0383730000 392417941 0 402718720 0.3364910781 -0.0925352871 -0.0332934260 787 1311867196.6805100441 0.0563790537 0.0542279748 0.0698473677 0.0051887531 0.0504190000 392421409 0 402718720 0.3358467221 -0.0903475359 -0.0330074206 788 1311867196.7112100124 0.0564827099 0.0542308362 0.0698473677 0.0051866662 0.0385720000 392424581 0 402718720 0.3333436251 -0.0921475887 -0.0325872973 789 1311867196.7464900017 0.0559400097 0.0542330024 0.0698473677 0.0051835502 0.0384690000 392427617 0 402718720 0.3317810595 -0.0911552832 -0.0328304209 790 1311867196.7783749104 0.0565836579 0.0542359780 0.0698473677 0.0051810036 0.0381170000 392431109 0 402718720 0.3279634714 -0.0910304040 -0.0326956846 791 1311867196.8109180927 0.0559377670 0.0542381294 0.0698473677 0.0051799281 0.0385020000 392434177 0 402718720 0.3275334537 -0.0903757364 -0.0326408036 792 1311867196.8488750458 0.0576729588 0.0542424663 0.0698473677 0.0051821611 0.0381590000 392437613 0 402718720 0.3245279789 -0.0898183584 -0.0309392698 793 1311867196.8821749687 0.0558329411 0.0542444719 0.0698473677 0.0051797409 0.0381010000 392440761 0 402718720 0.3230832517 -0.0896505117 -0.0326232985 794 1311867196.9115700722 0.0570708402 0.0542480316 0.0698473677 0.0051766523 0.0379320000 392443717 0 402718720 0.3206444681 -0.0897864848 -0.0314478874 795 1311867196.9482440948 0.0555603914 0.0542496824 0.0698473677 0.0051738532 0.0507890000 392447369 0 402718720 0.3188636601 -0.0898715854 -0.0328758471 796 1311867196.9809880257 0.0563155748 0.0542522777 0.0698473677 0.0051729401 0.0382290000 392450493 0 402718720 0.3162469566 -0.0902005136 -0.0322024748 797 1311867197.0154891014 0.0570146367 0.0542557437 0.0698473677 0.0051708596 0.0376510000 392453657 0 402718720 0.3139878213 -0.0907767266 -0.0316828899 798 1311867197.0490679741 0.0565783419 0.0542586542 0.0698473677 0.0051682031 0.0382710000 392456989 0 402718720 0.3110407293 -0.0901195109 -0.0329244286 799 1311867197.0806479454 0.0570516102 0.0542621497 0.0698473677 0.0051656599 0.0392410000 392459881 0 402718720 0.3095418513 -0.0898708999 -0.0325374901 800 1311867197.1148109436 0.0547327735 0.0542627380 0.0698473677 0.0051654029 0.0472340000 392463237 0 402718720 0.3080817461 -0.0917430148 -0.0343161523 801 1311867197.1468429565 0.0549931116 0.0542636499 0.0698473677 0.0051632360 0.0380120000 392466593 0 402718720 0.3058193028 -0.0902184248 -0.0348362066 802 1311867197.1792430878 0.0546517558 0.0542641338 0.0698473677 0.0051613953 0.0379430000 392469781 0 402718720 0.3033070266 -0.0913072973 -0.0349391401 803 1311867197.2143619061 0.0539148375 0.0542636988 0.0698473677 0.0051605285 0.0377910000 392473289 0 402718720 0.3014847338 -0.0912882984 -0.0356009714 804 1311867197.2459290028 0.0544665977 0.0542639511 0.0698473677 0.0051579818 0.0380200000 392476085 0 402718720 0.2988489568 -0.0897257254 -0.0358590856 805 1311867197.2799959183 0.0553182773 0.0542652609 0.0698473677 0.0051553473 0.0385020000 392479441 0 402718720 0.2973864377 -0.0889165327 -0.0347447917 806 1311867197.3157260418 0.0546074547 0.0542656854 0.0698473677 0.0051527332 0.0772160000 392482813 0 402718720 0.2953989506 -0.0891124606 -0.0352719910 807 1311867197.3468708992 0.0556044988 0.0542673444 0.0698473677 0.0051501946 0.0378630000 392486057 0 402718720 0.2921390533 -0.0888031572 -0.0347785577 808 1311867197.3784019947 0.0547101945 0.0542678925 0.0698473677 0.0051485338 0.0384020000 392489037 0 402718720 0.2910348177 -0.0893612579 -0.0354129374 809 1311867197.4155099392 0.0536955670 0.0542671851 0.0698473677 0.0051458319 0.0498730000 392492201 0 402718720 0.2879692912 -0.0902165025 -0.0370660312 810 1311867197.4478878975 0.0540823974 0.0542669569 0.0698473677 0.0051431365 0.0384200000 392495541 0 402718720 0.2865248919 -0.0888858587 -0.0376130939 811 1311867197.4793179035 0.0539715625 0.0542665927 0.0698473677 0.0051412127 0.0631720000 392498913 0 402718720 0.2837632298 -0.0905055553 -0.0378870443 812 1311867197.5150759220 0.0541500635 0.0542664492 0.0698473677 0.0051392069 0.0381670000 392501869 0 402718720 0.2807601392 -0.0898134261 -0.0390419029 813 1311867197.5469260216 0.0540050901 0.0542661277 0.0698473677 0.0051361124 0.0390210000 392504961 0 402718720 0.2811487615 -0.0880904645 -0.0395413376 814 1311867197.5802750587 0.0532299690 0.0542648548 0.0698473677 0.0051371779 0.0503890000 392508421 0 402718720 0.2783996463 -0.0901794955 -0.0410103947 815 1311867197.6152749062 0.0543249995 0.0542649286 0.0698473677 0.0051385878 0.0380300000 392511561 0 402718720 0.2762119472 -0.0890067071 -0.0410590470 816 1311867197.6470439434 0.0532736368 0.0542637138 0.0698473677 0.0051376583 0.0387830000 392514773 0 402718720 0.2757695317 -0.0862670168 -0.0432028100 817 1311867197.6800849438 0.0544990711 0.0542640018 0.0698473677 0.0051360389 0.0745640000 392517673 0 402718720 0.2714084387 -0.0883477032 -0.0425871797 818 1311867197.7143290043 0.0537854508 0.0542634168 0.0698473677 0.0051352261 0.0377940000 392521069 0 402718720 0.2711319625 -0.0862557292 -0.0439979210 819 1311867197.7463419437 0.0551446378 0.0542644928 0.0698473677 0.0051330339 0.0386320000 392524313 0 402718720 0.2693984807 -0.0850326642 -0.0433754437 820 1311867197.7793009281 0.0564186573 0.0542671198 0.0698473677 0.0051304469 0.0382030000 392527405 0 402718720 0.2648636103 -0.0873553753 -0.0427380875 821 1311867197.8146750927 0.0547214113 0.0542676732 0.0698473677 0.0051305681 0.0377300000 392530681 0 402718720 0.2640910447 -0.0856411308 -0.0457023606 822 1311867197.8467919827 0.0540163927 0.0542673675 0.0698473677 0.0051303184 0.0374620000 392533853 0 402718720 0.2630769610 -0.0862811580 -0.0469453633 823 1311867197.8802978992 0.0545077063 0.0542676595 0.0698473677 0.0051288519 0.0377220000 392537081 0 402718720 0.2611743808 -0.0865811557 -0.0470272899 824 1311867197.9148609638 0.0541664995 0.0542675367 0.0698473677 0.0051320150 0.0374920000 392540021 0 402718720 0.2592100203 -0.0838748217 -0.0493328683 825 1311867197.9470140934 0.0536206216 0.0542667526 0.0698473677 0.0051388891 0.0378780000 392543377 0 402718720 0.2565801144 -0.0854385048 -0.0500840023 826 1311867197.9812700748 0.0530901849 0.0542653282 0.0698473677 0.0051360955 0.0371620000 392546645 0 402718720 0.2558009624 -0.0847670212 -0.0510287620 827 1311867198.0145471096 0.0537730269 0.0542647329 0.0698473677 0.0051353623 0.0375740000 392550241 0 402718720 0.2534732521 -0.0825795382 -0.0516796634 828 1311867198.0463368893 0.0540459305 0.0542644686 0.0698473677 0.0051334452 0.0753360000 392553253 0 402718720 0.2521144450 -0.0834096596 -0.0512411855 829 1311867198.0787069798 0.0540381819 0.0542641957 0.0698473677 0.0051331282 0.0375580000 392556153 0 402718720 0.2495618314 -0.0830122456 -0.0524411425 830 1311867198.1143770218 0.0529878400 0.0542626579 0.0698473677 0.0051300453 0.0374770000 392559581 0 402718720 0.2485052943 -0.0816601366 -0.0540374890 831 1311867198.1463611126 0.0545013696 0.0542629451 0.0698473677 0.0051281316 0.0383130000 392562777 0 402718720 0.2441052943 -0.0822186917 -0.0536035709 832 1311867198.1822519302 0.0539266430 0.0542625409 0.0698473677 0.0051254595 0.0377360000 392566325 0 402718720 0.2435790449 -0.0810104832 -0.0545800030 833 1311867198.2144989967 0.0536300540 0.0542617816 0.0698473677 0.0051294115 0.0483150000 392569601 0 402718720 0.2414425015 -0.0806057081 -0.0558260530 834 1311867198.2464120388 0.0519744344 0.0542590390 0.0698473677 0.0051288792 0.0373180000 392572557 0 402718720 0.2401624471 -0.0814546198 -0.0578977913 835 1311867198.2821578979 0.0530139729 0.0542575479 0.0698473677 0.0051291441 0.0378250000 392575705 0 402718720 0.2376694381 -0.0788539797 -0.0582580492 836 1311867198.3159120083 0.0550489835 0.0542584946 0.0698473677 0.0051345886 0.0376120000 392579173 0 402718720 0.2338382155 -0.0788792893 -0.0573407561 837 1311867198.3481218815 0.0533761531 0.0542574404 0.0698473677 0.0051324791 0.0375910000 392582129 0 402718720 0.2323055118 -0.0784929022 -0.0600019544 838 1311867198.3828320503 0.0516941287 0.0542543816 0.0698473677 0.0051398817 0.0495340000 392585565 0 402718720 0.2314033061 -0.0770962462 -0.0620995760 839 1311867198.4242680073 0.0520310178 0.0542517316 0.0698473677 0.0051434345 0.0733660000 392588785 0 402718720 0.2282984257 -0.0764021575 -0.0628532693 840 1311867198.4497859478 0.0523892678 0.0542495144 0.0698473677 0.0051419002 0.0373630000 392591669 0 402718720 0.2246632576 -0.0787665844 -0.0634637102 841 1311867198.4856219292 0.0517063141 0.0542464903 0.0698473677 0.0051467726 0.0380960000 392594865 0 402718720 0.2224727571 -0.0767766982 -0.0659594983 842 1311867198.5190339088 0.0520798080 0.0542439171 0.0698473677 0.0051447956 0.0380830000 392598229 0 402718720 0.2198728919 -0.0750509351 -0.0670696348 843 1311867198.5499279499 0.0528195910 0.0542422275 0.0698473677 0.0051437119 0.0373990000 392601425 0 402718720 0.2171371877 -0.0755749345 -0.0668555945 844 1311867198.5824239254 0.0509828664 0.0542383657 0.0698473677 0.0051408966 0.0372100000 392604653 0 402718720 0.2142316699 -0.0745399818 -0.0700815320 845 1311867198.6147489548 0.0505823083 0.0542340390 0.0698473677 0.0051427773 0.0376710000 392607801 0 402718720 0.2126763910 -0.0742176473 -0.0709063485 846 1311867198.6482009888 0.0503311567 0.0542294257 0.0698473677 0.0051428315 0.0371420000 392610901 0 402718720 0.2099452913 -0.0739464834 -0.0718815178 847 1311867198.6827540398 0.0506852977 0.0542252413 0.0698473677 0.0051417767 0.0381110000 392614153 0 402718720 0.2062382549 -0.0730527565 -0.0729522780 848 1311867198.7146520615 0.0500300340 0.0542202942 0.0698473677 0.0051390874 0.0499900000 392617357 0 402718720 0.2057213038 -0.0716243535 -0.0742941797 849 1311867198.7467699051 0.0499422625 0.0542152553 0.0698473677 0.0051365245 0.0373700000 392620577 0 402718720 0.2033726722 -0.0722264275 -0.0751729459 850 1311867198.7842700481 0.0502290390 0.0542105656 0.0698473677 0.0051339270 0.0502670000 392623965 0 402718720 0.2008649409 -0.0699475408 -0.0762689859 851 1311867198.8149418831 0.0510600619 0.0542068635 0.0698473677 0.0051320532 0.0382160000 392626961 0 402718720 0.1989469826 -0.0701207221 -0.0758668035 852 1311867198.8464009762 0.0508962795 0.0542029778 0.0698473677 0.0051301139 0.0375090000 392630269 0 402718720 0.1961635202 -0.0697904900 -0.0769151896 853 1311867198.8845369816 0.0504417308 0.0541985684 0.0698473677 0.0051290784 0.0384150000 392633489 0 402718720 0.1957440823 -0.0688384771 -0.0781098083 854 1311867198.9147930145 0.0522785112 0.0541963201 0.0698473677 0.0051269155 0.0381740000 392636709 0 402718720 0.1934679449 -0.0668900982 -0.0777035877 855 1311867198.9465179443 0.0519350804 0.0541936753 0.0698473677 0.0051241701 0.0380200000 392639617 0 402718720 0.1907371134 -0.0662487075 -0.0792168826 856 1311867198.9839329720 0.0526593141 0.0541918829 0.0698473677 0.0051213524 0.0483100000 392643261 0 402718720 0.1901393831 -0.0645129234 -0.0790585726 857 1311867199.0148730278 0.0527849272 0.0541902411 0.0698473677 0.0051250620 0.0382310000 392646161 0 402718720 0.1872247756 -0.0640228391 -0.0800074413 858 1311867199.0468010902 0.0524208620 0.0541881789 0.0698473677 0.0051241877 0.0380180000 392649197 0 402718720 0.1868049204 -0.0638536587 -0.0815481693 859 1311867199.0849320889 0.0519420169 0.0541855641 0.0698473677 0.0051233112 0.0484770000 392652761 0 402718720 0.1865703613 -0.0626701638 -0.0829269886 860 1311867199.1149818897 0.0527962968 0.0541839486 0.0698473677 0.0051209991 0.0381310000 392655797 0 402718720 0.1850244105 -0.0613582358 -0.0834511071 861 1311867199.1465420723 0.0523083806 0.0541817703 0.0698473677 0.0051182986 0.0383140000 392659025 0 402718720 0.1839433759 -0.0611706227 -0.0850762054 862 1311867199.1823658943 0.0526800267 0.0541800281 0.0698473677 0.0051176701 0.0500310000 392662109 0 402718720 0.1830897927 -0.0587634891 -0.0863987580 863 1311867199.2146680355 0.0540088117 0.0541798297 0.0698473677 0.0051147365 0.0381880000 392665505 0 402718720 0.1823037416 -0.0580979437 -0.0861494541 864 1311867199.2467749119 0.0542340800 0.0541798925 0.0698473677 0.0051122292 0.0383780000 392668421 0 402718720 0.1801051199 -0.0571337193 -0.0873764157 865 1311867199.2833590508 0.0529776663 0.0541785027 0.0698473677 0.0051097850 0.0486590000 392671817 0 402718720 0.1789116412 -0.0570065007 -0.0896730497 866 1311867199.3159129620 0.0535569340 0.0541777849 0.0698473677 0.0051094849 0.0384330000 392675013 0 402718720 0.1769297570 -0.0563463829 -0.0907041803 867 1311867199.3465209007 0.0543472804 0.0541779804 0.0698473677 0.0051067026 0.0387750000 392677865 0 402718720 0.1751722246 -0.0554400906 -0.0914193988 868 1311867199.3829050064 0.0543159358 0.0541781393 0.0698473677 0.0051044714 0.0623130000 392681373 0 402718720 0.1725828946 -0.0547915548 -0.0931363478 869 1311867199.4147589207 0.0537236594 0.0541776163 0.0698473677 0.0051019247 0.0381440000 392684561 0 402718720 0.1713643670 -0.0552551635 -0.0945426375 870 1311867199.4512910843 0.0553475954 0.0541789611 0.0698473677 0.0051021922 0.0379660000 392687781 0 402718720 0.1693408638 -0.0529422015 -0.0946352258 871 1311867199.4837360382 0.0531480536 0.0541777776 0.0698473677 0.0051037522 0.0390110000 392690993 0 402718720 0.1686319411 -0.0539112873 -0.0972440243 872 1311867199.5150198936 0.0535793789 0.0541770913 0.0698473677 0.0051008602 0.0384920000 392693965 0 402718720 0.1654940248 -0.0539395288 -0.0979987979 873 1311867199.5544059277 0.0550933145 0.0541781408 0.0698473677 0.0051028748 0.0385870000 392697545 0 402718720 0.1633834541 -0.0517159402 -0.0978840664 874 1311867199.5835030079 0.0533895865 0.0541772386 0.0698473677 0.0051013309 0.0480860000 392700621 0 402718720 0.1613093317 -0.0515525751 -0.1002417058 875 1311867199.6158308983 0.0518719256 0.0541746040 0.0698473677 0.0051005213 0.0385430000 392703545 0 402718720 0.1594253480 -0.0513996743 -0.1020361036 876 1311867199.6538460255 0.0532576554 0.0541735572 0.0698473677 0.0050990954 0.0381880000 392707253 0 402718720 0.1564595848 -0.0508846305 -0.1011324301 877 1311867199.6824479103 0.0524152406 0.0541715523 0.0698473677 0.0050964895 0.0483060000 392710321 0 402718720 0.1523603052 -0.0513554737 -0.1030057669 878 1311867199.7146759033 0.0529256575 0.0541701333 0.0698473677 0.0050962107 0.0375210000 392713573 0 402718720 0.1502745897 -0.0504604876 -0.1029239148 879 1311867199.7511539459 0.0517562069 0.0541673871 0.0698473677 0.0050972875 0.0381510000 392716745 0 402718720 0.1483024806 -0.0503441952 -0.1043436751 880 1311867199.7826020718 0.0520243384 0.0541649518 0.0698473677 0.0050951327 0.0379370000 392719877 0 402718720 0.1453208923 -0.0500159934 -0.1048101038 881 1311867199.8150150776 0.0522716530 0.0541628027 0.0698473677 0.0051005252 0.0475860000 392723313 0 402718720 0.1415168494 -0.0502374172 -0.1052174866 882 1311867199.8519051075 0.0519578047 0.0541603027 0.0698473677 0.0050979763 0.0500620000 392726349 0 402718720 0.1400451064 -0.0495658293 -0.1057773083 883 1311867199.8839609623 0.0518591180 0.0541576966 0.0698473677 0.0050993866 0.0506050000 392729585 0 402718720 0.1375970840 -0.0503909774 -0.1059741974 884 1311867199.9148159027 0.0515205003 0.0541547134 0.0698473677 0.0050984503 0.0383000000 392732845 0 402718720 0.1350856721 -0.0503363460 -0.1066743359 885 1311867199.9520709515 0.0510077514 0.0541511575 0.0698473677 0.0050969279 0.0374770000 392736121 0 402718720 0.1333951652 -0.0492929220 -0.1079472825 886 1311867199.9828410149 0.0518880151 0.0541486032 0.0698473677 0.0050944014 0.0488420000 392739277 0 402718720 0.1313508302 -0.0494282469 -0.1071026325 887 1311867200.0144031048 0.0514263511 0.0541455341 0.0698473677 0.0050919717 0.0379720000 392742473 0 402718720 0.1287732422 -0.0490036793 -0.1079600230 888 1311867200.0539638996 0.0502874218 0.0541411894 0.0698473677 0.0050902753 0.0375970000 392746021 0 402718720 0.1267745048 -0.0469082594 -0.1099850833 889 1311867200.0830330849 0.0514446124 0.0541381561 0.0698473677 0.0050878231 0.0382870000 392748865 0 402718720 0.1234233975 -0.0481642000 -0.1085309610 890 1311867200.1174468994 0.0498865210 0.0541333790 0.0698473677 0.0050866627 0.0381360000 392752309 0 402718720 0.1216226742 -0.0478524603 -0.1097931415 891 1311867200.1517000198 0.0502743497 0.0541290479 0.0698473677 0.0050858859 0.0378250000 392755641 0 402718720 0.1203594729 -0.0469565913 -0.1090948731 892 1311867200.1853220463 0.0504238233 0.0541248940 0.0698473677 0.0050863538 0.0500340000 392758901 0 402718720 0.1169927418 -0.0481802821 -0.1089400351 893 1311867200.2179059982 0.0504517183 0.0541207807 0.0698473677 0.0050871392 0.0374570000 392761905 0 402718720 0.1148916930 -0.0465933494 -0.1091201752 894 1311867200.2522649765 0.0506097376 0.0541168534 0.0698473677 0.0050842946 0.0378420000 392765301 0 402718720 0.1124395058 -0.0460474938 -0.1086855382 895 1311867200.2825429440 0.0500323921 0.0541122898 0.0698473677 0.0050826777 0.0498700000 392768441 0 402718720 0.1095130444 -0.0465009883 -0.1087576374 896 1311867200.3148880005 0.0500614047 0.0541077687 0.0698473677 0.0050804835 0.0384170000 392772029 0 402718720 0.1081835479 -0.0446887985 -0.1086550653 897 1311867200.3514990807 0.0512567610 0.0541045903 0.0698473677 0.0050797670 0.0379840000 392774961 0 402718720 0.1055485457 -0.0455304161 -0.1066148952 898 1311867200.3837759495 0.0497084968 0.0540996949 0.0698473677 0.0050885849 0.0477360000 392778613 0 402718720 0.1022163853 -0.0455130562 -0.1081698537 899 1311867200.4162800312 0.0496516116 0.0540947471 0.0698473677 0.0050862184 0.0377490000 392781273 0 402718720 0.0995213091 -0.0451180153 -0.1082653776 900 1311867200.4522490501 0.0484700762 0.0540884974 0.0698473677 0.0050858883 0.0386790000 392784725 0 402718720 0.0959329009 -0.0470578820 -0.1086966693 901 1311867200.4850699902 0.0494791158 0.0540833816 0.0698473677 0.0050895353 0.0377400000 392787681 0 402718720 0.0940518305 -0.0456429496 -0.1074690372 902 1311867200.5143918991 0.0497814380 0.0540786122 0.0698473677 0.0050889188 0.0384670000 392791293 0 402718720 0.0909927487 -0.0466877744 -0.1063695550 903 1311867200.5505030155 0.0490658842 0.0540730610 0.0698473677 0.0050964693 0.0375930000 392794441 0 402718720 0.0883359909 -0.0460447297 -0.1063788384 904 1311867200.5832219124 0.0486238487 0.0540670331 0.0698473677 0.0050976566 0.0484270000 392797941 0 402718720 0.0878435820 -0.0458661467 -0.1062473208 905 1311867200.6145610809 0.0485678874 0.0540609567 0.0698473677 0.0050965539 0.0381130000 392800729 0 402718720 0.0840886086 -0.0462396368 -0.1058916226 906 1311867200.6504778862 0.0481604524 0.0540544440 0.0698473677 0.0050962544 0.0385270000 392804165 0 402718720 0.0808501691 -0.0468586162 -0.1052262932 907 1311867200.6851279736 0.0485804863 0.0540484088 0.0698473677 0.0050934945 0.0387760000 392807553 0 402718720 0.0791165903 -0.0452663042 -0.1045801044 908 1311867200.7189719677 0.0482341722 0.0540420055 0.0698473677 0.0050934798 0.0384840000 392810485 0 402718720 0.0748798847 -0.0461962707 -0.1043958962 909 1311867200.7503669262 0.0477976836 0.0540351360 0.0698473677 0.0050936623 0.0385520000 392813545 0 402718720 0.0746928379 -0.0468782522 -0.1032497510 910 1311867200.7832930088 0.0480507687 0.0540285598 0.0698473677 0.0051044784 0.0374570000 392816909 0 402718720 0.0703534931 -0.0452684760 -0.1036506146 911 1311867200.8181068897 0.0487575717 0.0540227739 0.0698473677 0.0051042194 0.0380830000 392820225 0 402718720 0.0671375617 -0.0456963629 -0.1018296927 912 1311867200.8501501083 0.0489260852 0.0540171854 0.0698473677 0.0051016937 0.0499000000 392823141 0 402718720 0.0659264177 -0.0432826355 -0.1018484235 913 1311867200.8845369816 0.0485986508 0.0540112505 0.0698473677 0.0051007998 0.0375620000 392826649 0 402718720 0.0643443316 -0.0444665402 -0.1008520797 914 1311867200.9194929600 0.0486176275 0.0540053494 0.0698473677 0.0051025097 0.0376880000 392829693 0 402718720 0.0607383549 -0.0452932194 -0.1005208194 915 1311867200.9512679577 0.0490934737 0.0539999812 0.0698473677 0.0051024244 0.0377750000 392832961 0 402718720 0.0594210103 -0.0451929048 -0.0991973504 916 1311867200.9856009483 0.0495666414 0.0539951413 0.0698473677 0.0051071735 0.0377610000 392836477 0 402718720 0.0571431071 -0.0455975495 -0.0992194489 917 1311867201.0184400082 0.0497419685 0.0539905032 0.0698473677 0.0051048007 0.0488990000 392839481 0 402718720 0.0546324775 -0.0459876731 -0.0992993712 918 1311867201.0555179119 0.0503393635 0.0539865259 0.0698473677 0.0051037115 0.0502020000 392842813 0 402718720 0.0540259257 -0.0444985479 -0.0992496461 919 1311867201.0825428963 0.0491654798 0.0539812800 0.0698473677 0.0051027348 0.0498910000 392845937 0 402718720 0.0504795313 -0.0465299487 -0.1005505696 920 1311867201.1193449497 0.0490100272 0.0539758764 0.0698473677 0.0051005435 0.0375390000 392849333 0 402718720 0.0507167503 -0.0458029583 -0.1008706614 921 1311867201.1506710052 0.0492551029 0.0539707507 0.0698473677 0.0050978646 0.0383730000 392852369 0 402718720 0.0497314557 -0.0448385365 -0.1012183204 922 1311867201.1830160618 0.0492579266 0.0539656392 0.0698473677 0.0050964072 0.0376770000 392855341 0 402718720 0.0486533232 -0.0457488000 -0.1009052098 923 1311867201.2196528912 0.0501806587 0.0539615385 0.0698473677 0.0050958919 0.0471190000 392858705 0 402718720 0.0455907620 -0.0460058786 -0.1001585722 924 1311867201.2503149509 0.0494827516 0.0539566913 0.0698473677 0.0050931985 0.0380950000 392861933 0 402718720 0.0450972915 -0.0449508354 -0.1011953279 925 1311867201.2824099064 0.0497648381 0.0539521595 0.0698473677 0.0050912573 0.0383160000 392864889 0 402718720 0.0438444950 -0.0446603186 -0.1009819657 926 1311867201.3180539608 0.0495423563 0.0539473973 0.0698473677 0.0050905469 0.0389880000 392868341 0 402718720 0.0413406864 -0.0461769998 -0.1009384468 927 1311867201.3522200584 0.0499758758 0.0539431131 0.0698473677 0.0050904989 0.0383030000 392871481 0 402718720 0.0386459790 -0.0447569080 -0.1013180688 928 1311867201.3842790127 0.0503220782 0.0539392111 0.0698473677 0.0050934016 0.0379100000 392874917 0 402718720 0.0359148085 -0.0417424887 -0.1021639258 929 1311867201.4198760986 0.0502875783 0.0539352804 0.0698473677 0.0051167400 0.0381600000 392877905 0 402718720 0.0339341797 -0.0431119017 -0.1008274406 930 1311867201.4558579922 0.0491097383 0.0539300916 0.0698473677 0.0051169491 0.0373790000 392881037 0 402718720 0.0317489803 -0.0423923507 -0.1020936370 931 1311867201.4853110313 0.0506287217 0.0539265456 0.0698473677 0.0051183992 0.0382740000 392884225 0 402718720 0.0290982239 -0.0395059399 -0.1014206111 932 1311867201.5198690891 0.0491250344 0.0539213937 0.0698473677 0.0051184984 0.0376120000 392887629 0 402718720 0.0258377977 -0.0402313806 -0.1023701578 933 1311867201.5527739525 0.0503802896 0.0539175983 0.0698473677 0.0051173592 0.0381270000 392890705 0 402718720 0.0226195715 -0.0399562381 -0.1008571014 934 1311867201.5840220451 0.0498854816 0.0539132813 0.0698473677 0.0051148297 0.0383780000 392893837 0 402718720 0.0212462991 -0.0393576026 -0.1015229151 935 1311867201.6197049618 0.0498049930 0.0539088874 0.0698473677 0.0051130700 0.0500350000 392897257 0 402718720 0.0186514743 -0.0390124395 -0.1020748168 936 1311867201.6515579224 0.0497717112 0.0539044673 0.0698473677 0.0051138288 0.0492200000 392900317 0 402718720 0.0174066909 -0.0385856852 -0.1021240205 937 1311867201.6839449406 0.0493781865 0.0538996367 0.0698473677 0.0051115776 0.0376920000 392903809 0 402718720 0.0144395325 -0.0388042368 -0.1026117355 938 1311867201.7189009190 0.0493898876 0.0538948289 0.0698473677 0.0051105205 0.0376370000 392906765 0 402718720 0.0126778241 -0.0375303775 -0.1031866521 939 1311867201.7507290840 0.0492415428 0.0538898733 0.0698473677 0.0051088995 0.0378160000 392909865 0 402718720 0.0110241538 -0.0367145240 -0.1035074741 940 1311867201.7858049870 0.0484254882 0.0538840602 0.0698473677 0.0051155224 0.0375270000 392913285 0 402718720 0.0093964310 -0.0363878049 -0.1037184820 941 1311867201.8190178871 0.0487688370 0.0538786242 0.0698473677 0.0051224261 0.0371550000 392916657 0 402718720 0.0085510612 -0.0342349559 -0.1041727215 942 1311867201.8505740166 0.0497416966 0.0538742326 0.0698473677 0.0051230443 0.0504250000 392919733 0 402718720 0.0064573144 -0.0338663384 -0.1032389104 943 1311867201.8862850666 0.0495716855 0.0538696700 0.0698473677 0.0051207764 0.0372150000 392922825 0 402718720 0.0054015717 -0.0347647630 -0.1030085981 944 1311867201.9195730686 0.0487189069 0.0538642136 0.0698473677 0.0051246378 0.0481760000 392926085 0 402718720 0.0038568741 -0.0333760418 -0.1047438234 945 1311867201.9516520500 0.0484321564 0.0538584654 0.0698473677 0.0051235428 0.0366690000 392929105 0 402718720 0.0038822806 -0.0335330144 -0.1050607041 946 1311867201.9894599915 0.0488438047 0.0538531645 0.0698473677 0.0051211313 0.0369200000 392932605 0 402718720 0.0014815424 -0.0332199931 -0.1053916737 947 1311867202.0184879303 0.0487423316 0.0538477676 0.0698473677 0.0051185909 0.0372240000 392935769 0 402718720 0.0004714234 -0.0334482491 -0.1057076678 948 1311867202.0507359505 0.0483807921 0.0538420008 0.0698473677 0.0051163265 0.0490970000 392938853 0 402718720 0.0005723294 -0.0325304121 -0.1066985950 949 1311867202.0866351128 0.0487159267 0.0538365992 0.0698473677 0.0051136928 0.0498430000 392942033 0 402718720 -0.0006992389 -0.0326401629 -0.1065765321 950 1311867202.1185920238 0.0496263430 0.0538321674 0.0698473677 0.0051141401 0.0363900000 392945293 0 402718720 -0.0014530038 -0.0312980898 -0.1058256030 951 1311867202.1516621113 0.0489435866 0.0538270269 0.0698473677 0.0051119016 0.0369510000 392948641 0 402718720 -0.0018691281 -0.0302839745 -0.1067603230 952 1311867202.1866259575 0.0488505214 0.0538217995 0.0698473677 0.0051093655 0.0372260000 392952117 0 402718720 -0.0038450267 -0.0300167874 -0.1069509536 953 1311867202.2191269398 0.0490341820 0.0538167758 0.0698473677 0.0051067091 0.0374440000 392954977 0 402718720 -0.0051103141 -0.0302219279 -0.1065221578 954 1311867202.2513220310 0.0489881746 0.0538117143 0.0698473677 0.0051044697 0.0479320000 392958437 0 402718720 -0.0068457089 -0.0293618776 -0.1065913215 955 1311867202.2868280411 0.0487330332 0.0538063964 0.0698473677 0.0051039844 0.0368960000 392961729 0 402718720 -0.0063516861 -0.0266840160 -0.1075833887 956 1311867202.3199880123 0.0493872352 0.0538017738 0.0698473677 0.0051031953 0.0479040000 392964749 0 402718720 -0.0093779368 -0.0285694264 -0.1063533649 957 1311867202.3523900509 0.0482115112 0.0537959324 0.0698473677 0.0051009859 0.0375350000 392967897 0 402718720 -0.0095322793 -0.0289631449 -0.1070274264 958 1311867202.3883628845 0.0488729402 0.0537907935 0.0698473677 0.0050990193 0.0374660000 392971093 0 402718720 -0.0133223943 -0.0277854614 -0.1067715213 959 1311867202.4196391106 0.0484704375 0.0537852457 0.0698473677 0.0050998068 0.0373310000 392974529 0 402718720 -0.0121234125 -0.0270832293 -0.1073091924 960 1311867202.4529430866 0.0485878475 0.0537798318 0.0698473677 0.0050987432 0.0474550000 392977501 0 402718720 -0.0129102888 -0.0287399627 -0.1065374017 961 1311867202.4875710011 0.0483526774 0.0537741844 0.0698473677 0.0050996506 0.0370490000 392980721 0 402718720 -0.0134746926 -0.0268324539 -0.1075375006 962 1311867202.5206449032 0.0493804999 0.0537696171 0.0698473677 0.0051177270 0.0370860000 392983869 0 402718720 -0.0151618402 -0.0271927677 -0.1065083668 963 1311867202.5508940220 0.0491333343 0.0537648027 0.0698473677 0.0051151567 0.0370200000 392987025 0 402718720 -0.0173729472 -0.0271929204 -0.1071987301 964 1311867202.5864949226 0.0483420305 0.0537591774 0.0698473677 0.0051351538 0.0366220000 392990501 0 402718720 -0.0164975896 -0.0273570083 -0.1082673520 965 1311867202.6185030937 0.0482874252 0.0537535072 0.0698473677 0.0051370304 0.0478960000 392993649 0 402718720 -0.0166094266 -0.0287626348 -0.1082426086 966 1311867202.6514449120 0.0490453504 0.0537486333 0.0698473677 0.0051417383 0.0481020000 392996717 0 402718720 -0.0212351717 -0.0277142525 -0.1087142825 967 1311867202.6866559982 0.0493950732 0.0537441312 0.0698473677 0.0051401070 0.0366170000 393000585 0 402718720 -0.0231035464 -0.0270543564 -0.1092737019 968 1311867202.7185359001 0.0502239987 0.0537404947 0.0698473677 0.0051377343 0.0360830000 393003349 0 402718720 -0.0246718712 -0.0270195100 -0.1095840409 969 1311867202.7507350445 0.0489066727 0.0537355063 0.0698473677 0.0051387142 0.0478570000 393006353 0 402718720 -0.0250730403 -0.0303104836 -0.1107163653 970 1311867202.7897169590 0.0494168028 0.0537310540 0.0698473677 0.0051375652 0.0369420000 393010253 0 402718720 -0.0260438882 -0.0267496873 -0.1127807498 971 1311867202.8190000057 0.0488978587 0.0537260764 0.0698473677 0.0051356058 0.0369190000 393013345 0 402718720 -0.0280209184 -0.0279086921 -0.1135965213 972 1311867202.8527579308 0.0505246334 0.0537227828 0.0698473677 0.0051341784 0.0479530000 393016493 0 402718720 -0.0319042951 -0.0284668840 -0.1123295650 973 1311867202.8873219490 0.0496033728 0.0537185490 0.0698473677 0.0051331649 0.0367260000 393019617 0 402718720 -0.0323980637 -0.0268852338 -0.1139979735 974 1311867202.9199879169 0.0493832491 0.0537140980 0.0698473677 0.0051316552 0.0363940000 393022973 0 402718720 -0.0310795642 -0.0254264995 -0.1146183982 975 1311867202.9525690079 0.0493256152 0.0537095970 0.0698473677 0.0051327430 0.0372890000 393025937 0 402718720 -0.0313787572 -0.0266247448 -0.1142174751 976 1311867202.9868710041 0.0493025556 0.0537050816 0.0698473677 0.0051356955 0.0373260000 393029397 0 402718720 -0.0316527560 -0.0265174434 -0.1139520183 977 1311867203.0202019215 0.0492070243 0.0537004777 0.0698473677 0.0051331384 0.0367220000 393032689 0 402718720 -0.0308690052 -0.0252210572 -0.1143664941 978 1311867203.0560851097 0.0487822257 0.0536954488 0.0698473677 0.0051343143 0.0663340000 393036013 0 402718720 -0.0308625754 -0.0279125795 -0.1136538908 979 1311867203.0865778923 0.0488196164 0.0536904683 0.0698473677 0.0051328986 0.0361680000 393039217 0 402718720 -0.0294621121 -0.0286892019 -0.1134712398 980 1311867203.1189930439 0.0483468883 0.0536850157 0.0698473677 0.0051397518 0.0361590000 393042445 0 402718720 -0.0276726652 -0.0292112976 -0.1138320491 981 1311867203.1549820900 0.0484889150 0.0536797190 0.0698473677 0.0051478917 0.0368160000 393045673 0 402718720 -0.0281666163 -0.0321328789 -0.1131403148 982 1311867203.1877939701 0.0488966070 0.0536748482 0.0698473677 0.0051839320 0.0364460000 393048741 0 402718720 -0.0287290849 -0.0331467576 -0.1136231720 983 1311867203.2185909748 0.0497548282 0.0536708604 0.0698473677 0.0051843544 0.0369090000 393052113 0 402718720 -0.0286443718 -0.0317447707 -0.1140142530 984 1311867203.2552030087 0.0495668799 0.0536666897 0.0698473677 0.0051847225 0.0471600000 393055309 0 402718720 -0.0278176107 -0.0338426046 -0.1139568985 985 1311867203.2864799500 0.0501038656 0.0536630726 0.0698473677 0.0051834781 0.0361180000 393058417 0 402718720 -0.0293359272 -0.0350646898 -0.1138236001 986 1311867203.3194670677 0.0500871614 0.0536594459 0.0698473677 0.0051812121 0.0363490000 393061741 0 402718720 -0.0290739238 -0.0343808383 -0.1148188338 987 1311867203.3547461033 0.0498106182 0.0536555464 0.0698473677 0.0051798664 0.0470950000 393064825 0 402718720 -0.0282141399 -0.0345118977 -0.1155309156 988 1311867203.3865599632 0.0496738143 0.0536515163 0.0698473677 0.0051842855 0.0364830000 393068037 0 402718720 -0.0267400648 -0.0352627560 -0.1156013384 989 1311867203.4183609486 0.0490632579 0.0536468770 0.0698473677 0.0051889471 0.0363060000 393071305 0 402718720 -0.0291779302 -0.0403532982 -0.1156503335 990 1311867203.4545118809 0.0493773706 0.0536425644 0.0698473677 0.0051868503 0.0463730000 393074309 0 402718720 -0.0283340886 -0.0406841077 -0.1158005521 991 1311867203.4864439964 0.0492410511 0.0536381229 0.0698473677 0.0051863403 0.0360840000 393077593 0 402718720 -0.0271308683 -0.0405924246 -0.1168319508 992 1311867203.5185539722 0.0490685217 0.0536335164 0.0698473677 0.0051904772 0.0347160000 393080829 0 402718720 -0.0274608210 -0.0446688905 -0.1164929569 993 1311867203.5560259819 0.0488337055 0.0536286828 0.0698473677 0.0051880603 0.0355840000 393084121 0 402718720 -0.0275746714 -0.0477626063 -0.1169610545 994 1311867203.5876550674 0.0490547493 0.0536240812 0.0698473677 0.0051867178 0.0351410000 393087205 0 402718720 -0.0267361030 -0.0476755984 -0.1179006770 995 1311867203.6191980839 0.0490925200 0.0536195269 0.0698473677 0.0051856666 0.0350800000 393090369 0 402718720 -0.0265277848 -0.0492647476 -0.1182733551 996 1311867203.6557719707 0.0487663895 0.0536146543 0.0698473677 0.0051831388 0.0351410000 393093589 0 402718720 -0.0278738029 -0.0530096143 -0.1184903309 997 1311867203.6866750717 0.0485986695 0.0536096232 0.0698473677 0.0051806521 0.0347320000 393096929 0 402718720 -0.0282683056 -0.0537883118 -0.1194461137 998 1311867203.7195260525 0.0475124866 0.0536035138 0.0698473677 0.0051798824 0.0345520000 393099949 0 402718720 -0.0275428686 -0.0560988933 -0.1204822436 999 1311867203.7566421032 0.0483745039 0.0535982796 0.0698473677 0.0051777325 0.0349380000 393103137 0 402718720 -0.0258864108 -0.0566836894 -0.1201895550 1000 1311867203.7867228985 0.0483087488 0.0535929901 0.0698473677 0.0051751933 0.0347310000 393106309 0 402718720 -0.0266677886 -0.0582171418 -0.1207591221 1001 1311867203.8193860054 0.0481825024 0.0535875850 0.0698473677 0.0051734527 0.0346790000 393109329 0 402718720 -0.0261062868 -0.0599290431 -0.1212100759 1002 1311867203.8572859764 0.0482729040 0.0535822809 0.0698473677 0.0051718428 0.0349890000 393112949 0 402718720 -0.0260199979 -0.0613616705 -0.1217639968 1003 1311867203.8891890049 0.0479722247 0.0535766876 0.0698473677 0.0051703363 0.0715290000 393116241 0 402718720 -0.0270721689 -0.0635159388 -0.1226496547 1004 1311867203.9188020229 0.0475736670 0.0535707085 0.0698473677 0.0051682348 0.0351190000 393119269 0 402718720 -0.0265598726 -0.0649555326 -0.1235636026 1005 1311867203.9553489685 0.0491761081 0.0535663358 0.0698473677 0.0051670513 0.0355040000 393122289 0 402718720 -0.0283174887 -0.0634729713 -0.1245319471 1006 1311867203.9866371155 0.0486129373 0.0535614119 0.0698473677 0.0051676938 0.0350800000 393125421 0 402718720 -0.0270873662 -0.0661439821 -0.1249421909 1007 1311867204.0199849606 0.0489206612 0.0535568034 0.0698473677 0.0051670439 0.0354040000 393128921 0 402718720 -0.0269749612 -0.0663525462 -0.1262737215 1008 1311867204.0551509857 0.0491622388 0.0535524438 0.0698473677 0.0051649115 0.0579210000 393132069 0 402718720 -0.0280754976 -0.0682915971 -0.1270055622 1009 1311867204.0867509842 0.0491184220 0.0535480493 0.0698473677 0.0051634059 0.0354760000 393135329 0 402718720 -0.0282835364 -0.0693265870 -0.1279736161 1010 1311867204.1191530228 0.0487319306 0.0535432809 0.0698473677 0.0051612373 0.0350960000 393138477 0 402718720 -0.0274592806 -0.0718481764 -0.1288766265 1011 1311867204.1555769444 0.0483931266 0.0535381867 0.0698473677 0.0051590565 0.0353780000 393141681 0 402718720 -0.0282845423 -0.0730851442 -0.1305278093 1012 1311867204.1876530647 0.0487113446 0.0535334171 0.0698473677 0.0051578455 0.0342710000 393144925 0 402718720 -0.0283548292 -0.0752790496 -0.1303068995 1013 1311867204.2187769413 0.0481231138 0.0535280763 0.0698473677 0.0051558404 0.0348710000 393148217 0 402718720 -0.0291472971 -0.0768077001 -0.1315474808 1014 1311867204.2566440105 0.0480180457 0.0535226423 0.0698473677 0.0051538931 0.0726010000 393151661 0 402718720 -0.0286189970 -0.0777312815 -0.1328216195 1015 1311867204.2867140770 0.0491758175 0.0535183597 0.0698473677 0.0051514384 0.0350660000 393154881 0 402718720 -0.0283653159 -0.0792907849 -0.1319149733 1016 1311867204.3204538822 0.0493769683 0.0535142835 0.0698473677 0.0051490463 0.0352330000 393158045 0 402718720 -0.0285211261 -0.0805165023 -0.1325303316 1017 1311867204.3625741005 0.0500541776 0.0535108813 0.0698473677 0.0051467273 0.0351350000 393161401 0 402718720 -0.0280329250 -0.0805337578 -0.1332387626 1018 1311867204.3869600296 0.0488014668 0.0535062551 0.0698473677 0.0051445417 0.0347610000 393164421 0 402718720 -0.0285818484 -0.0831767470 -0.1342568696 1019 1311867204.4240970612 0.0500430353 0.0535028565 0.0698473677 0.0051423186 0.0507100000 393745269 0 402718720 -0.0291123204 -0.0844952688 -0.1337950975 1020 1311867204.4549949169 0.0496805832 0.0534991092 0.0698473677 0.0051404704 0.1168280000 393718281 0 402718720 -0.0289786998 -0.0850526094 -0.1350233853 1021 1311867204.4872748852 0.0505646840 0.0534962351 0.0698473677 0.0051387916 0.1125900000 393719309 0 402718720 -0.0293167122 -0.0871152729 -0.1341954768 1022 1311867204.5237219334 0.0498903990 0.0534927069 0.0698473677 0.0051365114 0.1078940000 393995725 0 402718720 -0.0289912168 -0.0887669474 -0.1353365183 1023 1311867204.5581860542 0.0517333634 0.0534909871 0.0698473677 0.0051350310 0.1035480000 401777885 0 402718720 -0.0294925831 -0.0882358551 -0.1347641945 1024 1311867204.5878469944 0.0520747006 0.0534896040 0.0698473677 0.0051330047 0.0811610000 401571457 0 402718720 -0.0317286700 -0.0901051313 -0.1345012784 1025 1311867204.6241528988 0.0508513115 0.0534870300 0.0698473677 0.0051316588 0.0749980000 393826157 0 402718720 -0.0302485190 -0.0911971852 -0.1356237978 1026 1311867204.6541819572 0.0502922907 0.0534839163 0.0698473677 0.0051296541 0.0378310000 394033809 0 402718720 -0.0309722219 -0.0941743329 -0.1355631202 1027 1311867204.6871540546 0.0506865382 0.0534811924 0.0698473677 0.0051279015 0.0372330000 394037021 0 402718720 -0.0311162490 -0.0950035155 -0.1354840100 1028 1311867204.7225689888 0.0511876643 0.0534789614 0.0698473677 0.0051273536 0.0370280000 394040281 0 402718720 -0.0300478041 -0.0944899097 -0.1357026547 1029 1311867204.7539510727 0.0511208065 0.0534766697 0.0698473677 0.0051251951 0.0365620000 394043493 0 402718720 -0.0302914754 -0.0962494016 -0.1348268837 1030 1311867204.7878720760 0.0513728708 0.0534746272 0.0698473677 0.0051252278 0.0492210000 394046937 0 402718720 -0.0323061980 -0.0984166488 -0.1333714426 1031 1311867204.8227200508 0.0517886952 0.0534729919 0.0698473677 0.0051233840 0.0360040000 394050013 0 402718720 -0.0335106701 -0.0982902274 -0.1329496354 1032 1311867204.8542668819 0.0502929874 0.0534699105 0.0698473677 0.0051249605 0.0365040000 394053433 0 402718720 -0.0323638506 -0.0997921750 -0.1332152933 1033 1311867204.8864960670 0.0502861850 0.0534668285 0.0698473677 0.0051234401 0.0369960000 394056597 0 402718720 -0.0330706872 -0.1037049219 -0.1307768971 1034 1311867204.9220221043 0.0512950867 0.0534647282 0.0698473677 0.0051216999 0.0367780000 394059697 0 402718720 -0.0356473662 -0.1051676199 -0.1291164458 1035 1311867204.9542920589 0.0517382286 0.0534630600 0.0698473677 0.0051200182 0.0369450000 394062877 0 402718720 -0.0352157168 -0.1054817140 -0.1284261942 1036 1311867204.9865999222 0.0511475056 0.0534608250 0.0698473677 0.0051184141 0.0754160000 394065881 0 402718720 -0.0352735929 -0.1080625206 -0.1279765517 1037 1311867205.0227239132 0.0506214127 0.0534580869 0.0698473677 0.0051206367 0.0386500000 394069381 0 402718720 -0.0356763601 -0.1116426736 -0.1269780695 1038 1311867205.0550808907 0.0510781892 0.0534557941 0.0698473677 0.0051345110 0.0386720000 394072521 0 402718720 -0.0359258614 -0.1118425950 -0.1257818639 1039 1311867205.0880999565 0.0509901866 0.0534534210 0.0698473677 0.0051324088 0.0349660000 394075741 0 402718720 -0.0363638066 -0.1140633002 -0.1247727200 1040 1311867205.1232450008 0.0508284159 0.0534508970 0.0698473677 0.0051306303 0.0374300000 394078921 0 402718720 -0.0354626887 -0.1163924560 -0.1240102351 1041 1311867205.1545319557 0.0516507588 0.0534491677 0.0698473677 0.0051438900 0.0536670000 394082093 0 402718720 -0.0353718400 -0.1158172786 -0.1243037358 1042 1311867205.1863510609 0.0518992469 0.0534476803 0.0698473677 0.0051495991 0.0474840000 394085545 0 402718720 -0.0365794897 -0.1182675362 -0.1228183359 1043 1311867205.2223129272 0.0513108820 0.0534456316 0.0698473677 0.0051510983 0.0483710000 394088597 0 402718720 -0.0361112133 -0.1215357557 -0.1218954623 1044 1311867205.2541849613 0.0505441204 0.0534428524 0.0698473677 0.0051513513 0.0365160000 394091777 0 402718720 -0.0357190780 -0.1223212630 -0.1226240247 1045 1311867205.2880499363 0.0513055176 0.0534408071 0.0698473677 0.0051490704 0.0341740000 394095381 0 402718720 -0.0349412151 -0.1232333034 -0.1215400174 1046 1311867205.3218879700 0.0511222482 0.0534385905 0.0698473677 0.0051487239 0.0376510000 394098513 0 402718720 -0.0358152315 -0.1262241751 -0.1205799580 1047 1311867205.3542900085 0.0521726795 0.0534373814 0.0698473677 0.0051530639 0.0535790000 394665121 0 402718720 -0.0354389176 -0.1271717995 -0.1188928410 1048 1311867205.3862779140 0.0514015481 0.0534354388 0.0698473677 0.0051581260 0.1155380000 394644241 0 402718720 -0.0350539088 -0.1287281364 -0.1191287488 1049 1311867205.4225649834 0.0517493449 0.0534338315 0.0698473677 0.0051595411 0.1199490000 394645313 0 402718720 -0.0386830121 -0.1311483383 -0.1180010885 1050 1311867205.4540419579 0.0522897877 0.0534327419 0.0698473677 0.0051632581 0.1102640000 394936785 0 402718720 -0.0379302949 -0.1318951994 -0.1169172823 1051 1311867205.4865119457 0.0518302955 0.0534312172 0.0698473677 0.0051674866 0.0946150000 403146921 0 402718720 -0.0370038375 -0.1319232881 -0.1168688536 1052 1311867205.5230340958 0.0515073724 0.0534293885 0.0698473677 0.0051758317 0.0821960000 402933197 0 402718720 -0.0387313031 -0.1356977969 -0.1147566289 1053 1311867205.5542900562 0.0507248789 0.0534268201 0.0698473677 0.0051956176 0.1268670000 401173813 0 402718720 -0.0411105081 -0.1366302669 -0.1153401732 1054 1311867205.5866839886 0.0511847436 0.0534246929 0.0698473677 0.0051932704 0.0467490000 394611201 0 402718720 -0.0411731452 -0.1363904327 -0.1144554466 1055 1311867205.6226179600 0.0510246567 0.0534224180 0.0698473677 0.0051979883 0.0376120000 394614829 0 402718720 -0.0426574871 -0.1391570419 -0.1126149222 1056 1311867205.6555979252 0.0501313023 0.0534193014 0.0698473677 0.0051966419 0.0355790000 394618073 0 402718720 -0.0429835506 -0.1416970640 -0.1121811345 1057 1311867205.6902959347 0.0509131886 0.0534169304 0.0698473677 0.0051941907 0.0355900000 394621205 0 402718720 -0.0429002643 -0.1423191130 -0.1112981662 1058 1311867205.7222061157 0.0509668812 0.0534146147 0.0698473677 0.0051918446 0.0351200000 394624609 0 402718720 -0.0449570566 -0.1454430968 -0.1104178205 1059 1311867205.7548348904 0.0510778986 0.0534124081 0.0698473677 0.0051896160 0.0348670000 394627733 0 402718720 -0.0467840694 -0.1478498876 -0.1099622771 1060 1311867205.7906379700 0.0515093878 0.0534106128 0.0698473677 0.0051878023 0.0341410000 394630969 0 402718720 -0.0466878563 -0.1472613066 -0.1109557375 1061 1311867205.8232109547 0.0509592928 0.0534083024 0.0698473677 0.0052005852 0.0347850000 394634253 0 402718720 -0.0467280932 -0.1512109488 -0.1094690710 1062 1311867205.8554759026 0.0518811010 0.0534068644 0.0698473677 0.0052053170 0.0341380000 394637729 0 402718720 -0.0479313694 -0.1523536146 -0.1085511893 1063 1311867205.8905880451 0.0516913757 0.0534052506 0.0698473677 0.0052055664 0.0346080000 394640973 0 402718720 -0.0500381365 -0.1532842219 -0.1094004512 1064 1311867205.9223020077 0.0520129763 0.0534039421 0.0698473677 0.0052137024 0.0350520000 394644249 0 402718720 -0.0496681407 -0.1542184800 -0.1088301763 1065 1311867205.9544939995 0.0518052951 0.0534024410 0.0698473677 0.0052115397 0.0339150000 394647365 0 402718720 -0.0504406728 -0.1569458842 -0.1080572829 1066 1311867205.9905850887 0.0516791753 0.0534008244 0.0698473677 0.0052197472 0.0344970000 394650745 0 402718720 -0.0523274541 -0.1580846757 -0.1084036455 1067 1311867206.0259850025 0.0531315356 0.0534005720 0.0698473677 0.0052256072 0.0350020000 394654141 0 402718720 -0.0540683642 -0.1575457603 -0.1080383807 1068 1311867206.0604250431 0.0535679534 0.0534007288 0.0698473677 0.0052370861 0.0348690000 394657033 0 402718720 -0.0532896072 -0.1598432064 -0.1065478474 1069 1311867206.0903289318 0.0513727628 0.0533988317 0.0698473677 0.0052370572 0.0351490000 394659917 0 402718720 -0.0528078489 -0.1640551835 -0.1070933640 1070 1311867206.1227540970 0.0526632071 0.0533981442 0.0698473677 0.0052353168 0.0370670000 394663225 0 402718720 -0.0530588925 -0.1642813683 -0.1066274121 1071 1311867206.1546130180 0.0526869148 0.0533974801 0.0698473677 0.0052329225 0.0346510000 394666645 0 402718720 -0.0530117899 -0.1667687446 -0.1066862345 1072 1311867206.1903800964 0.0524440445 0.0533965907 0.0698473677 0.0052338504 0.0429410000 394670057 0 402718720 -0.0555793382 -0.1702988744 -0.1063539386 1073 1311867206.2239561081 0.0525744781 0.0533958245 0.0698473677 0.0052315680 0.0370480000 394673117 0 402718720 -0.0545437410 -0.1698293984 -0.1079452783 1074 1311867206.2553579807 0.0529802106 0.0533954375 0.0698473677 0.0052303157 0.0367970000 394676257 0 402718720 -0.0538135767 -0.1710600108 -0.1076557711 1075 1311867206.2904770374 0.0521209985 0.0533942520 0.0698473677 0.0052279818 0.0366350000 394679589 0 402718720 -0.0558968186 -0.1739099622 -0.1084435433 1076 1311867206.3222041130 0.0530341901 0.0533939174 0.0698473677 0.0052258655 0.0342050000 394682793 0 402718720 -0.0564931184 -0.1744933724 -0.1081985086 1077 1311867206.3542530537 0.0525605902 0.0533931436 0.0698473677 0.0052242280 0.0344540000 394686109 0 402718720 -0.0570289977 -0.1756303012 -0.1093093157 1078 1311867206.3900070190 0.0524541289 0.0533922726 0.0698473677 0.0052238078 0.0458270000 394689553 0 402718720 -0.0568806045 -0.1785774380 -0.1083642021 1079 1311867206.4220259190 0.0513947234 0.0533904213 0.0698473677 0.0052222299 0.0337010000 394692285 0 402718720 -0.0558314174 -0.1805211902 -0.1093508080 1080 1311867206.4542310238 0.0516834594 0.0533888408 0.0698473677 0.0052208580 0.0344900000 394695697 0 402718720 -0.0565467998 -0.1817020774 -0.1095524356 1081 1311867206.4905378819 0.0514343493 0.0533870327 0.0698473677 0.0052304635 0.0364040000 394699509 0 402718720 -0.0564269945 -0.1841281503 -0.1093472540 1082 1311867206.5250329971 0.0522723608 0.0533860025 0.0698473677 0.0052353304 0.0336340000 394702513 0 402718720 -0.0599230379 -0.1860126853 -0.1091603488 1083 1311867206.5539300442 0.0513202734 0.0533840951 0.0698473677 0.0052405177 0.0344630000 394705669 0 402718720 -0.0587063879 -0.1882974952 -0.1098008901 1084 1311867206.5921130180 0.0520216748 0.0533828383 0.0698473677 0.0052399855 0.0338360000 394709137 0 402718720 -0.0572129413 -0.1891501844 -0.1098759994 1085 1311867206.6226360798 0.0515445471 0.0533811440 0.0698473677 0.0052523538 0.0336720000 394712165 0 402718720 -0.0582442693 -0.1923601031 -0.1099519134 1086 1311867206.6566751003 0.0504434742 0.0533784389 0.0698473677 0.0052514339 0.0337220000 394715481 0 402718720 -0.0590671860 -0.1951601952 -0.1101595536 1087 1311867206.6945209503 0.0503991805 0.0533756981 0.0698473677 0.0052501762 0.0390910000 395275129 0 402718720 -0.0580282584 -0.1958888322 -0.1111510396 1088 1311867206.7248480320 0.0509264171 0.0533734470 0.0698473677 0.0052560448 0.1165430000 395262509 0 402718720 -0.0582343340 -0.1968373358 -0.1110716164 1089 1311867206.7587969303 0.0517016314 0.0533719118 0.0698473677 0.0052982347 0.1188710000 395265129 0 402718720 -0.0587495714 -0.1994222254 -0.1103354543 1090 1311867206.7902839184 0.0525212400 0.0533711313 0.0698473677 0.0053104309 0.1084470000 395558629 0 402718720 -0.0588280037 -0.1983501613 -0.1114577651 1091 1311867206.8229770660 0.0515871681 0.0533694962 0.0698473677 0.0053103645 0.0744510000 403623677 0 402718720 -0.0603460036 -0.2015425563 -0.1120117009 1092 1311867206.8605449200 0.0511903539 0.0533675006 0.0698473677 0.0053081746 0.0739220000 403411649 0 402718720 -0.0604398511 -0.2045435458 -0.1125386730 1093 1311867206.8907771111 0.0520501472 0.0533662954 0.0698473677 0.0053061562 0.1199880000 401755653 0 402718720 -0.0587361902 -0.2036911994 -0.1137786806 1094 1311867206.9225020409 0.0518135987 0.0533648761 0.0698473677 0.0053038292 0.0427450000 395277205 0 402718720 -0.0594431907 -0.2051716447 -0.1148567274 1095 1311867206.9592480659 0.0526550896 0.0533642279 0.0698473677 0.0053023585 0.0348150000 395280649 0 402718720 -0.0608182959 -0.2081895620 -0.1142200753 1096 1311867206.9948680401 0.0522676632 0.0533632274 0.0698473677 0.0053107778 0.0346770000 395284013 0 402718720 -0.0624521971 -0.2113435566 -0.1145898253 1097 1311867207.0247550011 0.0523449332 0.0533622991 0.0698473677 0.0053127138 0.0348980000 395287305 0 402718720 -0.0621296018 -0.2124895751 -0.1157586202 1098 1311867207.0597259998 0.0528189838 0.0533618043 0.0698473677 0.0053106809 0.0509490000 395290661 0 402718720 -0.0614268109 -0.2140715867 -0.1155437678 1099 1311867207.0942800045 0.0534190275 0.0533618563 0.0698473677 0.0053146083 0.0344370000 395293697 0 402718720 -0.0614875890 -0.2150961608 -0.1160462648 1100 1311867207.1229140759 0.0522481352 0.0533608439 0.0698473677 0.0053189286 0.0331800000 395296701 0 402718720 -0.0597544909 -0.2171643823 -0.1169153899 1101 1311867207.1583549976 0.0530229062 0.0533605369 0.0698473677 0.0053209156 0.0339760000 395300489 0 402718720 -0.0595811568 -0.2184809148 -0.1172869503 1102 1311867207.1904919147 0.0521017425 0.0533593947 0.0698473677 0.0053201554 0.0364240000 395303565 0 402718720 -0.0599802881 -0.2206672430 -0.1177681535 1103 1311867207.2226181030 0.0515936390 0.0533577938 0.0698473677 0.0053203351 0.0489140000 395306641 0 402718720 -0.0594714321 -0.2225043178 -0.1177518219 1104 1311867207.2604830265 0.0536561348 0.0533580640 0.0698473677 0.0053222083 0.0340430000 395310229 0 402718720 -0.0587266535 -0.2222081870 -0.1163740680 1105 1311867207.2926900387 0.0520573743 0.0533568869 0.0698473677 0.0053239855 0.0338820000 395313217 0 402718720 -0.0598603413 -0.2256609052 -0.1167065948 1106 1311867207.3235239983 0.0513831638 0.0533551024 0.0698473677 0.0053272134 0.0361390000 395316405 0 402718720 -0.0597181544 -0.2279416919 -0.1167532504 1107 1311867207.3597478867 0.0526420139 0.0533544582 0.0698473677 0.0053255179 0.0356440000 395319465 0 402718720 -0.0603926480 -0.2281175703 -0.1158467904 1108 1311867207.3901309967 0.0518305637 0.0533530829 0.0698473677 0.0053266382 0.0361430000 395322637 0 402718720 -0.0626583695 -0.2310802788 -0.1151384711 1109 1311867207.4227840900 0.0509188585 0.0533508879 0.0698473677 0.0053250455 0.0461540000 395326201 0 402718720 -0.0637630522 -0.2332385778 -0.1155788004 1110 1311867207.4586789608 0.0510904416 0.0533488514 0.0698473677 0.0053260435 0.0334830000 395329125 0 402718720 -0.0630568936 -0.2348346263 -0.1143713817 1111 1311867207.4927639961 0.0513755344 0.0533470753 0.0698473677 0.0053254879 0.0363060000 395332665 0 402718720 -0.0646782815 -0.2361410260 -0.1146637499 1112 1311867207.5237300396 0.0511618219 0.0533451101 0.0698473677 0.0053298458 0.0335350000 395335957 0 402718720 -0.0650766417 -0.2384768128 -0.1138492897 1113 1311867207.5598409176 0.0507573150 0.0533427851 0.0698473677 0.0053290075 0.0363020000 395339113 0 402718720 -0.0646378100 -0.2395585179 -0.1149961948 1114 1311867207.5944800377 0.0522057414 0.0533417644 0.0698473677 0.0053284369 0.0461570000 395342245 0 402718720 -0.0667673722 -0.2411416918 -0.1135240421 1115 1311867207.6259219646 0.0505381860 0.0533392500 0.0698473677 0.0053264250 0.0457100000 395345577 0 402718720 -0.0685665235 -0.2445789725 -0.1140961200 1116 1311867207.6592938900 0.0520179085 0.0533380660 0.0698473677 0.0053265114 0.0331350000 395348917 0 402718720 -0.0683432594 -0.2454198599 -0.1129055247 1117 1311867207.6923089027 0.0517744683 0.0533366661 0.0698473677 0.0053253466 0.0351790000 395352033 0 402718720 -0.0690969154 -0.2475873232 -0.1129913926 1118 1311867207.7238640785 0.0517881960 0.0533352811 0.0698473677 0.0053259164 0.0329040000 395355437 0 402718720 -0.0701141730 -0.2499339879 -0.1126169562 1119 1311867207.7588050365 0.0516260415 0.0533337536 0.0698473677 0.0053245421 0.0331410000 395358513 0 402718720 -0.0708934143 -0.2522491813 -0.1127185822 1120 1311867207.7921919823 0.0532280058 0.0533336592 0.0698473677 0.0053228488 0.0383790000 395920989 0 402718720 -0.0734598786 -0.2527807653 -0.1122661307 1121 1311867207.8237760067 0.0521745123 0.0533326252 0.0698473677 0.0053213968 0.1118950000 395901081 0 402718720 -0.0735724121 -0.2550367713 -0.1132725328 1122 1311867207.8608479500 0.0521240495 0.0533315480 0.0698473677 0.0053197334 0.1084110000 395902165 0 402718720 -0.0727052540 -0.2576081753 -0.1125009209 1123 1311867207.8937089443 0.0533490106 0.0533315636 0.0698473677 0.0053180381 0.1052530000 396205937 0 402718720 -0.0736932382 -0.2575163245 -0.1127858460 1124 1311867207.9244139194 0.0534233227 0.0533316452 0.0698473677 0.0053174584 0.1026690000 403427581 0 402718720 -0.0739286244 -0.2588585317 -0.1128028929 1125 1311867207.9614970684 0.0532795526 0.0533315989 0.0698473677 0.0053168569 0.0719960000 403092581 0 402718720 -0.0737343356 -0.2603146732 -0.1125461981 1126 1311867207.9914131165 0.0528251044 0.0533311491 0.0698473677 0.0053307657 0.0430840000 404545889 0 402718720 -0.0726245046 -0.2611577809 -0.1137065887 1127 1311867208.0248498917 0.0527389832 0.0533306237 0.0698473677 0.0053485164 0.1079030000 399584653 0 402718720 -0.0732873380 -0.2638723254 -0.1122241765 1128 1311867208.0618500710 0.0512066074 0.0533287407 0.0698473677 0.0053469085 0.0347320000 395918381 0 402718720 -0.0732436180 -0.2674890757 -0.1122672558 1129 1311867208.0924620628 0.0519420803 0.0533275124 0.0698473677 0.0053447384 0.0372870000 395921809 0 402718720 -0.0719423741 -0.2670894563 -0.1129241809 1130 1311867208.1276559830 0.0526840761 0.0533269430 0.0698473677 0.0053426674 0.0348290000 395924901 0 402718720 -0.0735960901 -0.2693350315 -0.1112760603 1131 1311867208.1596069336 0.0526530147 0.0533263472 0.0698473677 0.0053405340 0.0363700000 395928001 0 402718720 -0.0741709694 -0.2699286342 -0.1124226600 1132 1311867208.1905009747 0.0510292090 0.0533243179 0.0698473677 0.0053417204 0.0420300000 395930893 0 402718720 -0.0734463483 -0.2723193765 -0.1136574075 1133 1311867208.2280850410 0.0520496480 0.0533231928 0.0698473677 0.0053397904 0.0364400000 395934777 0 402718720 -0.0727732480 -0.2731370628 -0.1134507433 1134 1311867208.2581789494 0.0515467264 0.0533216263 0.0698473677 0.0053375255 0.0375460000 395937645 0 402718720 -0.0743488818 -0.2754995823 -0.1134176999 1135 1311867208.2901990414 0.0522297546 0.0533206643 0.0698473677 0.0053352057 0.0344570000 395940961 0 402718720 -0.0736728907 -0.2766562700 -0.1125819609 1136 1311867208.3270208836 0.0531316511 0.0533204979 0.0698473677 0.0053355930 0.0334900000 395944293 0 402718720 -0.0733752102 -0.2771666944 -0.1131886020 1137 1311867208.3580970764 0.0529530495 0.0533201747 0.0698473677 0.0053361567 0.0335100000 395947441 0 402718720 -0.0720331073 -0.2779845893 -0.1138622090 1138 1311867208.3910560608 0.0536320545 0.0533204488 0.0698473677 0.0053349465 0.0339610000 395950789 0 402718720 -0.0736726075 -0.2787330449 -0.1139649078 1139 1311867208.4260230064 0.0534700751 0.0533205802 0.0698473677 0.0053329111 0.0448080000 395953777 0 402718720 -0.0745381340 -0.2814579010 -0.1129698306 1140 1311867208.4577419758 0.0512823761 0.0533187923 0.0698473677 0.0053315092 0.0358100000 395957117 0 402718720 -0.0737744272 -0.2840454578 -0.1151986718 1141 1311867208.4907650948 0.0521813072 0.0533177953 0.0698473677 0.0053292600 0.0351390000 395960337 0 402718720 -0.0725560114 -0.2841425240 -0.1149412543 1142 1311867208.5257411003 0.0517495610 0.0533164221 0.0698473677 0.0053280232 0.0352480000 395963693 0 402718720 -0.0726873130 -0.2863178849 -0.1141524985 1143 1311867208.5583798885 0.0520684123 0.0533153302 0.0698473677 0.0053262329 0.0331810000 395966777 0 402718720 -0.0750722662 -0.2872700393 -0.1138096303 1144 1311867208.5904500484 0.0521146916 0.0533142807 0.0698473677 0.0053260972 0.0359800000 395970173 0 402718720 -0.0743246228 -0.2876144648 -0.1141043901 1145 1311867208.6259779930 0.0528505147 0.0533138757 0.0698473677 0.0053246521 0.0723570000 395973385 0 402718720 -0.0742843598 -0.2884469926 -0.1122846827 1146 1311867208.6582078934 0.0525878258 0.0533132421 0.0698473677 0.0053225305 0.0406080000 395976557 0 402718720 -0.0751946047 -0.2896924615 -0.1117356718 1147 1311867208.6910300255 0.0521901399 0.0533122630 0.0698473677 0.0053264206 0.0384470000 395979753 0 402718720 -0.0741138384 -0.2895075977 -0.1123787388 1148 1311867208.7262260914 0.0532444715 0.0533122039 0.0698473677 0.0053270358 0.0406900000 395982949 0 402718720 -0.0753500611 -0.2900781035 -0.1110262573 1149 1311867208.7591009140 0.0525883809 0.0533115740 0.0698473677 0.0053248019 0.0402310000 395986209 0 402718720 -0.0777541250 -0.2917390764 -0.1108025238 1150 1311867208.7909750938 0.0542179458 0.0533123621 0.0698473677 0.0053226539 0.0454070000 396522293 0 402718720 -0.0776703283 -0.2915990055 -0.1085037887 1151 1311867208.8259930611 0.0534655415 0.0533124952 0.0698473677 0.0053227659 0.1170560000 396507909 0 402718720 -0.0776967779 -0.2941460311 -0.1077012569 1152 1311867208.8588190079 0.0525672995 0.0533118483 0.0698473677 0.0053271769 0.1159040000 396509969 0 402718720 -0.0777779073 -0.2953263819 -0.1086650491 1153 1311867208.8916258812 0.0538076833 0.0533122784 0.0698473677 0.0053391676 0.1102730000 396859777 0 402718720 -0.0784632042 -0.2944158316 -0.1083221287 1154 1311867208.9275119305 0.0543043278 0.0533131380 0.0698473677 0.0053411351 0.1127150000 403652309 0 402718720 -0.0796550959 -0.2962679863 -0.1075765640 1155 1311867208.9577760696 0.0531298071 0.0533129793 0.0698473677 0.0053397169 0.0860770000 405421481 0 402718720 -0.0801101327 -0.2994541228 -0.1073024645 1156 1311867208.9911639690 0.0530474074 0.0533127496 0.0698473677 0.0053382722 0.0543770000 396476309 0 402718720 -0.0806984454 -0.3000400066 -0.1088053510 1157 1311867209.0270779133 0.0531020127 0.0533125674 0.0698473677 0.0053394371 0.0403420000 396479521 0 402718720 -0.0800691769 -0.3022558689 -0.1078644246 1158 1311867209.0579569340 0.0535515994 0.0533127738 0.0698473677 0.0053379458 0.0393940000 396482805 0 402718720 -0.0819765851 -0.3026155531 -0.1093711257 1159 1311867209.0906980038 0.0537741370 0.0533131719 0.0698473677 0.0053374379 0.0392690000 396486185 0 402718720 -0.0822492391 -0.3029555380 -0.1101382300 1160 1311867209.1260778904 0.0546017438 0.0533142827 0.0698473677 0.0053356554 0.0387880000 396489365 0 402718720 -0.0826272890 -0.3028469682 -0.1108708531 1161 1311867209.1600620747 0.0538736358 0.0533147645 0.0698473677 0.0053347687 0.0410710000 396492705 0 402718720 -0.0832146630 -0.3059777617 -0.1102007851 1162 1311867209.1917839050 0.0540849678 0.0533154274 0.0698473677 0.0053328725 0.0323980000 396495981 0 402718720 -0.0830391049 -0.3057944477 -0.1116958857 1163 1311867209.2259531021 0.0547639690 0.0533166729 0.0698473677 0.0053305872 0.0329940000 396499113 0 402718720 -0.0828683376 -0.3063522875 -0.1114909053 1164 1311867209.2580060959 0.0531248748 0.0533165081 0.0698473677 0.0053287119 0.0337990000 396502749 0 402718720 -0.0833436921 -0.3083829582 -0.1133438051 1165 1311867209.2903130054 0.0562743917 0.0533190471 0.0698473677 0.0053300116 0.0323580000 396505417 0 402718720 -0.0857611746 -0.3070772290 -0.1118174195 1166 1311867209.3274219036 0.0551879071 0.0533206499 0.0698473677 0.0053340892 0.0320100000 396508965 0 402718720 -0.0839278400 -0.3085789979 -0.1137481779 1167 1311867209.3581039906 0.0526679754 0.0533200906 0.0698473677 0.0053332572 0.0344310000 396512025 0 402718720 -0.0856598541 -0.3127766550 -0.1144968048 1168 1311867209.3937969208 0.0547284000 0.0533212963 0.0698473677 0.0053354019 0.0342640000 396515301 0 402718720 -0.0855700895 -0.3111296892 -0.1150806099 1169 1311867209.4258151054 0.0549063608 0.0533226522 0.0698473677 0.0053336868 0.0323550000 396518857 0 402718720 -0.0879697427 -0.3124214113 -0.1156371236 1170 1311867209.4581329823 0.0538527966 0.0533231054 0.0698473677 0.0053316125 0.0318750000 396521693 0 402718720 -0.0886352211 -0.3154260814 -0.1154864654 1171 1311867209.4940650463 0.0558243282 0.0533252413 0.0698473677 0.0053309347 0.0343140000 396525313 0 402718720 -0.0867436901 -0.3139952421 -0.1156348288 1172 1311867209.5258729458 0.0546495207 0.0533263713 0.0698473677 0.0053300843 0.0342430000 396528197 0 402718720 -0.0888972059 -0.3164333403 -0.1157457605 1173 1311867209.5580699444 0.0569042526 0.0533294215 0.0698473677 0.0053281339 0.0322710000 396531489 0 402718720 -0.0894803554 -0.3157067895 -0.1151360273 1174 1311867209.5939540863 0.0546773486 0.0533305696 0.0698473677 0.0053265658 0.0321570000 396535021 0 402718720 -0.0910872966 -0.3187154531 -0.1171747297 1175 1311867209.6262791157 0.0551821552 0.0533321454 0.0698473677 0.0053243245 0.0444270000 396538433 0 402718720 -0.0926720574 -0.3198666573 -0.1170453280 1176 1311867209.6582019329 0.0552736893 0.0533337964 0.0698473677 0.0053232236 0.0336260000 396541141 0 402718720 -0.0899414122 -0.3212848902 -0.1166220903 1177 1311867209.6967020035 0.0534760095 0.0533339172 0.0698473677 0.0053336949 0.0318030000 396544657 0 402718720 -0.0903749838 -0.3246149719 -0.1180960461 1178 1311867209.7262639999 0.0556657277 0.0533358967 0.0698473677 0.0053485874 0.0321620000 396547813 0 402718720 -0.0924754813 -0.3251106143 -0.1159530208 1179 1311867209.7583460808 0.0554101430 0.0533376560 0.0698473677 0.0053507571 0.0340170000 396551145 0 402718720 -0.0936596245 -0.3263589740 -0.1174446493 1180 1311867209.7959320545 0.0565005094 0.0533403364 0.0698473677 0.0053491344 0.0448510000 396554429 0 402718720 -0.0951517224 -0.3269825578 -0.1176389158 1181 1311867209.8262419701 0.0566906966 0.0533431733 0.0698473677 0.0053477455 0.0333780000 396557905 0 402718720 -0.0948804766 -0.3290202022 -0.1163863167 1182 1311867209.8588960171 0.0569995940 0.0533462667 0.0698473677 0.0053459871 0.0417980000 396560957 0 402718720 -0.0937744454 -0.3274891078 -0.1196993217 1183 1311867209.8946969509 0.0562915765 0.0533487564 0.0698473677 0.0053452986 0.0335020000 396564313 0 402718720 -0.0933939740 -0.3295292258 -0.1203236207 1184 1311867209.9268450737 0.0547033809 0.0533499005 0.0698473677 0.0053432059 0.0338320000 396567565 0 402718720 -0.0940264314 -0.3315381408 -0.1218679249 1185 1311867209.9588210583 0.0547879115 0.0533511140 0.0698473677 0.0053410746 0.0316810000 396570785 0 402718720 -0.0942353457 -0.3320510983 -0.1223741174 1186 1311867209.9942541122 0.0557759367 0.0533531586 0.0698473677 0.0053415180 0.0350590000 397082717 0 402718720 -0.0947732776 -0.3325593770 -0.1225323007 1187 1311867210.0261061192 0.0544479489 0.0533540809 0.0698473677 0.0053396934 0.1106510000 397085333 0 402718720 -0.0941266418 -0.3344559669 -0.1237268597 1188 1311867210.0603590012 0.0559690185 0.0533562820 0.0698473677 0.0053387540 0.1102050000 397088417 0 402718720 -0.0932268500 -0.3334816992 -0.1237856299 1189 1311867210.0942480564 0.0571417660 0.0533594658 0.0698473677 0.0053392871 0.0997790000 400533577 0 402718720 -0.0944733918 -0.3335447311 -0.1233566701 1190 1311867210.1280341148 0.0557152368 0.0533614454 0.0698473677 0.0053379079 0.0713900000 406193565 0 402718720 -0.0931932926 -0.3355539441 -0.1238589138 1191 1311867210.1578240395 0.0561227538 0.0533637639 0.0698473677 0.0053386722 0.0807350000 405984269 0 402718720 -0.0937993154 -0.3346175551 -0.1250866503 1192 1311867210.1943209171 0.0565937981 0.0533664736 0.0698473677 0.0053369678 0.0397040000 406105441 0 402718720 -0.0930337012 -0.3345541656 -0.1251674742 1193 1311867210.2258129120 0.0550346859 0.0533678720 0.0698473677 0.0053357503 0.1124730000 404443629 0 402718720 -0.0957380906 -0.3377015889 -0.1249852777 1194 1311867210.2579770088 0.0552359447 0.0533694365 0.0698473677 0.0053340831 0.0334260000 397062877 0 402718720 -0.0954471156 -0.3367931545 -0.1268937588 1195 1311867210.2953989506 0.0565212481 0.0533720740 0.0698473677 0.0053319664 0.0337160000 397066273 0 402718720 -0.0935927629 -0.3359831572 -0.1267268360 1196 1311867210.3271369934 0.0558685549 0.0533741614 0.0698473677 0.0053350136 0.0341310000 397069301 0 402718720 -0.0945829451 -0.3367097378 -0.1276541352 1197 1311867210.3582420349 0.0563566685 0.0533766530 0.0698473677 0.0053413466 0.0329710000 397072481 0 402718720 -0.0952428356 -0.3369751871 -0.1277076304 1198 1311867210.3937919140 0.0554845370 0.0533784125 0.0698473677 0.0053391715 0.0347640000 397075741 0 402718720 -0.0949822366 -0.3375275135 -0.1295517981 1199 1311867210.4260039330 0.0540738218 0.0533789925 0.0698473677 0.0053445921 0.0348720000 397078897 0 402718720 -0.0956137478 -0.3393090069 -0.1304906309 1200 1311867210.4581708908 0.0549070165 0.0533802659 0.0698473677 0.0053425320 0.0327230000 397082453 0 402718720 -0.0962401107 -0.3395053744 -0.1294066906 1201 1311867210.4943509102 0.0571451262 0.0533834006 0.0698473677 0.0053689784 0.0427270000 397085529 0 402718720 -0.0963339359 -0.3365462124 -0.1301391870 1202 1311867210.5261299610 0.0558261238 0.0533854329 0.0698473677 0.0053717429 0.0347890000 397088645 0 402718720 -0.0980884880 -0.3382999599 -0.1305020452 1203 1311867210.5634729862 0.0559706688 0.0533875818 0.0698473677 0.0053715600 0.0347220000 397091913 0 402718720 -0.0986054465 -0.3383028805 -0.1308388859 1204 1311867210.5943870544 0.0569892414 0.0533905733 0.0698473677 0.0053715870 0.0327790000 397095173 0 402718720 -0.0978661701 -0.3358588219 -0.1324168593 1205 1311867210.6260209084 0.0556823835 0.0533924752 0.0698473677 0.0053843406 0.0331790000 397098097 0 402718720 -0.0983270705 -0.3376282454 -0.1332583725 1206 1311867210.6675710678 0.0528430603 0.0533920196 0.0698473677 0.0053962854 0.0323480000 397101741 0 402718720 -0.0973397791 -0.3427065611 -0.1321404278 1207 1311867210.6952280998 0.0554091893 0.0533936908 0.0698473677 0.0054060098 0.0322470000 397104593 0 402718720 -0.0981521085 -0.3399310112 -0.1327161193 1208 1311867210.7260899544 0.0559439324 0.0533958020 0.0698473677 0.0054040175 0.0323410000 397107973 0 402718720 -0.0974503905 -0.3385231197 -0.1342669874 1209 1311867210.7620921135 0.0543858148 0.0533966208 0.0698473677 0.0054044041 0.0347010000 397111353 0 402718720 -0.0979173928 -0.3404288590 -0.1348247677 1210 1311867210.7943489552 0.0554902740 0.0533983511 0.0698473677 0.0054118782 0.0342780000 397114149 0 402718720 -0.0968499929 -0.3388911784 -0.1346713603 1211 1311867210.8263258934 0.0563774854 0.0534008112 0.0698473677 0.0054105151 0.0348230000 397117569 0 402718720 -0.0970805436 -0.3373086751 -0.1351267546 1212 1311867210.8623979092 0.0533454604 0.0534007655 0.0698473677 0.0054096847 0.0343570000 397120509 0 402718720 -0.0973995924 -0.3403723836 -0.1356105804 1213 1311867210.8942279816 0.0561705679 0.0534030489 0.0698473677 0.0054084982 0.0329510000 397123793 0 402718720 -0.0962253064 -0.3372071087 -0.1346648782 1214 1311867210.9288311005 0.0542056747 0.0534037101 0.0698473677 0.0054065682 0.0347770000 397127077 0 402718720 -0.0959905535 -0.3388909400 -0.1350790560 1215 1311867210.9653480053 0.0566194355 0.0534063568 0.0698473677 0.0054267355 0.0450710000 397130337 0 402718720 -0.0960464254 -0.3348835707 -0.1348698735 1216 1311867210.9945580959 0.0573811643 0.0534096255 0.0698473677 0.0054365377 0.0348830000 397133269 0 402718720 -0.0966138244 -0.3342118263 -0.1344064176 1217 1311867211.0263500214 0.0538615771 0.0534099969 0.0698473677 0.0054368478 0.0350020000 397136305 0 402718720 -0.0987816304 -0.3393559456 -0.1329334974 1218 1311867211.0651569366 0.0563510545 0.0534124116 0.0698473677 0.0054506452 0.0330680000 397139877 0 402718720 -0.0970294699 -0.3352195323 -0.1337403208 1219 1311867211.0940821171 0.0560149141 0.0534145465 0.0698473677 0.0054554094 0.0333700000 397143089 0 402718720 -0.0971313715 -0.3352838755 -0.1345453709 1220 1311867211.1266880035 0.0543519594 0.0534153149 0.0698473677 0.0054562533 0.0342640000 397146285 0 402718720 -0.0971401483 -0.3381742239 -0.1334687620 1221 1311867211.1646990776 0.0539833903 0.0534157801 0.0698473677 0.0054547761 0.0325740000 397149673 0 402718720 -0.0969400182 -0.3379859030 -0.1346532404 1222 1311867211.1946630478 0.0564184636 0.0534182373 0.0698473677 0.0054532419 0.0462580000 397152829 0 402718720 -0.0962491035 -0.3348939419 -0.1349808276 1223 1311867211.2270209789 0.0539687164 0.0534186874 0.0698473677 0.0054650404 0.0337400000 397155785 0 402718720 -0.0970252678 -0.3373866379 -0.1353073865 1224 1311867211.2645599842 0.0540374704 0.0534191930 0.0698473677 0.0054642634 0.0330560000 397159101 0 402718720 -0.0977143645 -0.3378573954 -0.1341606975 1225 1311867211.2953100204 0.0548631325 0.0534203717 0.0698473677 0.0054624775 0.0329190000 397162313 0 402718720 -0.0968284234 -0.3354830146 -0.1357676238 1226 1311867211.3262948990 0.0558455847 0.0534223498 0.0698473677 0.0054608450 0.0328460000 397165789 0 402718720 -0.0968220457 -0.3341853023 -0.1354912072 1227 1311867211.3653290272 0.0542580262 0.0534230309 0.0698473677 0.0054590387 0.0328600000 397168761 0 402718720 -0.0971185267 -0.3364607096 -0.1342748106 1228 1311867211.3949019909 0.0544616058 0.0534238767 0.0698473677 0.0054584664 0.0326660000 397171981 0 402718720 -0.0960321426 -0.3347753882 -0.1351251453 1229 1311867211.4295680523 0.0562302098 0.0534261601 0.0698473677 0.0054671776 0.0430930000 397175145 0 402718720 -0.0953046307 -0.3316355646 -0.1354768574 1230 1311867211.4645059109 0.0551848747 0.0534275899 0.0698473677 0.0054667801 0.0326430000 397178349 0 402718720 -0.0960587114 -0.3322156072 -0.1354846358 1231 1311867211.4942829609 0.0542556606 0.0534282626 0.0698473677 0.0054647477 0.0327990000 397181249 0 402718720 -0.0966298804 -0.3332677186 -0.1345389336 1232 1311867211.5279569626 0.0547754467 0.0534293561 0.0698473677 0.0054639823 0.0321320000 397184461 0 402718720 -0.0959501714 -0.3311755657 -0.1350865811 1233 1311867211.5646700859 0.0546747223 0.0534303661 0.0698473677 0.0054667020 0.0330100000 397188065 0 402718720 -0.0960535109 -0.3312701285 -0.1346045136 1234 1311867211.5967590809 0.0531341918 0.0534301261 0.0698473677 0.0054726440 0.0333600000 397191181 0 402718720 -0.0969863683 -0.3322316706 -0.1354087144 1235 1311867211.6269431114 0.0545046106 0.0534309962 0.0698473677 0.0054825194 0.0329680000 397194145 0 402718720 -0.0975821987 -0.3308373392 -0.1341461837 1236 1311867211.6620280743 0.0558496863 0.0534329530 0.0698473677 0.0054904620 0.0325000000 397197421 0 402718720 -0.0962271169 -0.3282493949 -0.1337397397 1237 1311867211.6944348812 0.0542031564 0.0534335757 0.0698473677 0.0054965671 0.0322940000 397200569 0 402718720 -0.0978316888 -0.3308394253 -0.1328557730 1238 1311867211.7267570496 0.0547345541 0.0534346265 0.0698473677 0.0054981510 0.0326720000 397203725 0 402718720 -0.0977451503 -0.3290563822 -0.1337631643 1239 1311867211.7642099857 0.0542797074 0.0534353086 0.0698473677 0.0054976140 0.0324720000 397207097 0 402718720 -0.0971080884 -0.3294958174 -0.1334977746 1240 1311867211.7948160172 0.0547257513 0.0534363493 0.0698473677 0.0054967666 0.0325120000 397210013 0 402718720 -0.0959354043 -0.3283906281 -0.1340801120 1241 1311867211.8337268829 0.0549789257 0.0534375923 0.0698473677 0.0054958417 0.0332880000 397213649 0 402718720 -0.0966915116 -0.3275578916 -0.1349003315 1242 1311867211.8630928993 0.0534252860 0.0534375824 0.0698473677 0.0054937747 0.0331270000 397216549 0 402718720 -0.0959456712 -0.3279895782 -0.1365204602 1243 1311867211.8967690468 0.0562760308 0.0534398659 0.0698473677 0.0054929459 0.0426270000 397219505 0 402718720 -0.0939761996 -0.3239119053 -0.1361730993 1244 1311867211.9324300289 0.0554290116 0.0534414649 0.0698473677 0.0054956786 0.0331470000 397223101 0 402718720 -0.0955093056 -0.3250744939 -0.1358094066 1245 1311867211.9653239250 0.0533233657 0.0534413701 0.0698473677 0.0054938237 0.0324710000 397226209 0 402718720 -0.0942975432 -0.3259167373 -0.1372948289 1246 1311867211.9972860813 0.0545304902 0.0534422442 0.0698473677 0.0054922740 0.0336630000 397229365 0 402718720 -0.0944649279 -0.3237556517 -0.1375010163 1247 1311867212.0317659378 0.0561869778 0.0534444452 0.0698473677 0.0054909121 0.0337180000 397232561 0 402718720 -0.0926802829 -0.3208839595 -0.1373098791 1248 1311867212.0621519089 0.0548687503 0.0534455865 0.0698473677 0.0054889224 0.0333810000 397235749 0 402718720 -0.0943750739 -0.3217258155 -0.1377979666 1249 1311867212.0954549313 0.0554565825 0.0534471966 0.0698473677 0.0054922436 0.0333650000 397238961 0 402718720 -0.0941537768 -0.3192271888 -0.1385202855 1250 1311867212.1331028938 0.0554616451 0.0534488081 0.0698473677 0.0054922749 0.0449840000 397242469 0 402718720 -0.0933899060 -0.3172355890 -0.1394470334 1251 1311867212.1668488979 0.0552051477 0.0534502121 0.0698473677 0.0054925814 0.0330740000 397245377 0 402718720 -0.0921543762 -0.3167638481 -0.1391005367 1252 1311867212.1945068836 0.0541729219 0.0534507893 0.0698473677 0.0054909035 0.0328060000 397248221 0 402718720 -0.0928099677 -0.3176393509 -0.1387555003 1253 1311867212.2301759720 0.0547962710 0.0534518631 0.0698473677 0.0054933349 0.0330500000 397251697 0 402718720 -0.0920993537 -0.3144454360 -0.1405114233 1254 1311867212.2647190094 0.0547186732 0.0534528734 0.0698473677 0.0054964017 0.0334080000 397254957 0 402718720 -0.0919038653 -0.3138510585 -0.1407662928 1255 1311867212.2944819927 0.0546677597 0.0534538414 0.0698473677 0.0054943044 0.0329810000 397257985 0 402718720 -0.0925435275 -0.3136268258 -0.1407744139 1256 1311867212.3326430321 0.0552294590 0.0534552551 0.0698473677 0.0054952761 0.0324750000 397261237 0 402718720 -0.0930330530 -0.3119240701 -0.1408337802 1257 1311867212.3653640747 0.0551724881 0.0534566212 0.0698473677 0.0054934063 0.0327490000 397264769 0 402718720 -0.0921097249 -0.3091691136 -0.1429304332 1258 1311867212.3955509663 0.0548530072 0.0534577312 0.0698473677 0.0055058683 0.0331390000 397267797 0 402718720 -0.0915007517 -0.3087683618 -0.1427468956 1259 1311867212.4329519272 0.0541487075 0.0534582801 0.0698473677 0.0055257950 0.0329480000 397270985 0 402718720 -0.0892543122 -0.3074268699 -0.1436480880 1260 1311867212.4622640610 0.0557508059 0.0534600995 0.0698473677 0.0055355095 0.0329890000 397274013 0 402718720 -0.0901693106 -0.3045402169 -0.1438848376 1261 1311867212.4944300652 0.0551245324 0.0534614195 0.0698473677 0.0055407140 0.0331800000 397277097 0 402718720 -0.0899186581 -0.3033436537 -0.1454813778 1262 1311867212.5300269127 0.0549388528 0.0534625902 0.0698473677 0.0055415218 0.0332070000 397280229 0 402718720 -0.0888208300 -0.3033168018 -0.1449657977 1263 1311867212.5625970364 0.0550526753 0.0534638492 0.0698473677 0.0055528234 0.0331360000 397283585 0 402718720 -0.0884297118 -0.3020684719 -0.1461723745 1264 1311867212.5948359966 0.0559655353 0.0534658283 0.0698473677 0.0055513546 0.0428360000 397286925 0 402718720 -0.0866502225 -0.2997256219 -0.1469756365 1265 1311867212.6323919296 0.0548078790 0.0534668892 0.0698473677 0.0055521741 0.0331560000 397290001 0 402718720 -0.0880156979 -0.3007561266 -0.1479676664 1266 1311867212.6629829407 0.0552252643 0.0534682782 0.0698473677 0.0055585474 0.0330960000 397292853 0 402718720 -0.0896863863 -0.2995283902 -0.1490375996 1267 1311867212.6944150925 0.0565824695 0.0534707361 0.0698473677 0.0055572221 0.0331450000 397296633 0 402718720 -0.0852437168 -0.2963635623 -0.1494674832 1268 1311867212.7323219776 0.0565365106 0.0534731539 0.0698473677 0.0055560376 0.0605420000 397299413 0 402718720 -0.0853627175 -0.2960959673 -0.1498182714 1269 1311867212.7618949413 0.0552744158 0.0534745733 0.0698473677 0.0055544629 0.0324970000 397302769 0 402718720 -0.0856119543 -0.2956612110 -0.1516559273 1270 1311867212.7951610088 0.0560898632 0.0534766326 0.0698473677 0.0055526797 0.0329620000 397305717 0 402718720 -0.0849389955 -0.2936679423 -0.1519983560 1271 1311867212.8303771019 0.0570383482 0.0534794349 0.0698473677 0.0055510222 0.0443610000 397309097 0 402718720 -0.0842910707 -0.2915348411 -0.1526065767 1272 1311867212.8625240326 0.0558586530 0.0534813054 0.0698473677 0.0055493037 0.0454250000 397312317 0 402718720 -0.0834197924 -0.2921369672 -0.1533840597 1273 1311867212.8941800594 0.0553085990 0.0534827408 0.0698473677 0.0055577399 0.0323030000 397315209 0 402718720 -0.0835852996 -0.2917144597 -0.1538691819 1274 1311867212.9306590557 0.0559449568 0.0534846735 0.0698473677 0.0055628034 0.0433740000 397318629 0 402718720 -0.0827914178 -0.2897371948 -0.1542808414 1275 1311867212.9621579647 0.0557079054 0.0534864172 0.0698473677 0.0055764567 0.0322830000 397321969 0 402718720 -0.0808387250 -0.2882333696 -0.1556353867 1276 1311867212.9971981049 0.0566983186 0.0534889343 0.0698473677 0.0055817069 0.0329800000 397324917 0 402718720 -0.0824287534 -0.2862085998 -0.1559585035 1277 1311867213.0305559635 0.0556226224 0.0534906052 0.0698473677 0.0055852119 0.0449120000 397328049 0 402718720 -0.0822872594 -0.2858833373 -0.1571704894 1278 1311867213.0622329712 0.0559123233 0.0534925001 0.0698473677 0.0055849064 0.0323470000 397331429 0 402718720 -0.0805057958 -0.2844598293 -0.1572616547 1279 1311867213.0985310078 0.0560160726 0.0534944732 0.0698473677 0.0055836602 0.0323580000 397334689 0 402718720 -0.0792515203 -0.2827358246 -0.1579510421 1280 1311867213.1321671009 0.0555969775 0.0534961158 0.0698473677 0.0055824931 0.0323360000 397337829 0 402718720 -0.0778951719 -0.2819272578 -0.1588876694 1281 1311867213.1642329693 0.0554314442 0.0534976266 0.0698473677 0.0055804932 0.0325430000 397341057 0 402718720 -0.0783283040 -0.2812500000 -0.1596874744 1282 1311867213.1981649399 0.0554304942 0.0534991343 0.0698473677 0.0055836753 0.0326700000 397344389 0 402718720 -0.0759469196 -0.2799793482 -0.1606618762 1283 1311867213.2303979397 0.0550064594 0.0535003091 0.0698473677 0.0055821585 0.0322430000 397347297 0 402718720 -0.0779422447 -0.2801403105 -0.1612906605 1284 1311867213.2621340752 0.0559226535 0.0535021957 0.0698473677 0.0055815614 0.0326460000 397350605 0 402718720 -0.0750190541 -0.2770015001 -0.1625827253 1285 1311867213.2983639240 0.0551085137 0.0535034457 0.0698473677 0.0055811487 0.0326390000 397353881 0 402718720 -0.0751333982 -0.2777931988 -0.1621290445 1286 1311867213.3312969208 0.0551855080 0.0535047537 0.0698473677 0.0055827019 0.0322220000 397357085 0 402718720 -0.0744845867 -0.2759848237 -0.1626825333 1287 1311867213.3622069359 0.0574027449 0.0535077825 0.0698473677 0.0055812224 0.0324770000 397360129 0 402718720 -0.0749114901 -0.2721413076 -0.1628464013 1288 1311867213.3980619907 0.0558324009 0.0535095873 0.0698473677 0.0055799986 0.0325550000 397363453 0 402718720 -0.0740857944 -0.2723679543 -0.1636674404 1289 1311867213.4303960800 0.0547818318 0.0535105743 0.0698473677 0.0055786743 0.0328060000 397366769 0 402718720 -0.0718491301 -0.2710678577 -0.1651551723 1290 1311867213.4620630741 0.0564352982 0.0535128415 0.0698473677 0.0055772514 0.0324300000 397370053 0 402718720 -0.0719300658 -0.2687372863 -0.1637834311 1291 1311867213.4981389046 0.0564685725 0.0535151310 0.0698473677 0.0055777055 0.0423880000 397373057 0 402718720 -0.0727115721 -0.2666136920 -0.1638339460 1292 1311867213.5318338871 0.0564323887 0.0535173889 0.0698473677 0.0055777288 0.0441480000 397376341 0 402718720 -0.0717392564 -0.2636543214 -0.1649655402 1293 1311867213.5621318817 0.0561220013 0.0535194033 0.0698473677 0.0055756008 0.0327820000 397379545 0 402718720 -0.0708734989 -0.2619330585 -0.1651364118 1294 1311867213.5989580154 0.0557155311 0.0535211005 0.0698473677 0.0055778507 0.0325510000 397382877 0 402718720 -0.0712311342 -0.2602064908 -0.1653231978 1295 1311867213.6327760220 0.0547255948 0.0535220306 0.0698473677 0.0055766501 0.0323130000 397385961 0 402718720 -0.0695763901 -0.2580395341 -0.1671330631 1296 1311867213.6623249054 0.0549929626 0.0535231656 0.0698473677 0.0055757949 0.0324590000 397389037 0 402718720 -0.0667074621 -0.2566261888 -0.1658692509 1297 1311867213.6987268925 0.0570624806 0.0535258944 0.0698473677 0.0055784488 0.0459790000 397392137 0 402718720 -0.0676643699 -0.2533364892 -0.1642370969 1298 1311867213.7312800884 0.0553536080 0.0535273025 0.0698473677 0.0055819112 0.0452280000 397395757 0 402718720 -0.0674308240 -0.2534150481 -0.1646533012 1299 1311867213.7623159885 0.0553804338 0.0535287291 0.0698473677 0.0055910376 0.0330030000 397398929 0 402718720 -0.0660985932 -0.2511439025 -0.1650196016 1300 1311867213.7984969616 0.0558211394 0.0535304925 0.0698473677 0.0055896885 0.0328240000 397401917 0 402718720 -0.0660768598 -0.2492863983 -0.1640102714 1301 1311867213.8303530216 0.0559980124 0.0535323891 0.0698473677 0.0055877541 0.0327160000 397405257 0 402718720 -0.0649294406 -0.2467933893 -0.1644210368 1302 1311867213.8669381142 0.0550736450 0.0535335729 0.0698473677 0.0055931615 0.0334310000 397408965 0 402718720 -0.0640603006 -0.2472661734 -0.1630682796 1303 1311867213.8988749981 0.0545187481 0.0535343290 0.0698473677 0.0055920037 0.0455080000 397411905 0 402718720 -0.0627673194 -0.2470497638 -0.1626305133 1304 1311867213.9324591160 0.0552836508 0.0535356705 0.0698473677 0.0055949007 0.0335240000 397415021 0 402718720 -0.0625589490 -0.2439879179 -0.1629534513 1305 1311867213.9625511169 0.0557599925 0.0535373749 0.0698473677 0.0055931846 0.0463930000 397417921 0 402718720 -0.0629945248 -0.2429627776 -0.1622376442 1306 1311867214.0014989376 0.0536195599 0.0535374379 0.0698473677 0.0055927790 0.0335890000 397421509 0 402718720 -0.0611745492 -0.2438760847 -0.1628239751 1307 1311867214.0316550732 0.0557714030 0.0535391471 0.0698473677 0.0055924091 0.0335150000 397424241 0 402718720 -0.0612078719 -0.2399368137 -0.1626479924 1308 1311867214.0640029907 0.0547387414 0.0535400642 0.0698473677 0.0055920942 0.0442760000 397427861 0 402718720 -0.0590228103 -0.2382119596 -0.1645961106 1309 1311867214.0984749794 0.0555148460 0.0535415728 0.0698473677 0.0055902730 0.0332690000 397431241 0 402718720 -0.0574229099 -0.2367522866 -0.1636365801 1310 1311867214.1326990128 0.0553474426 0.0535429514 0.0698473677 0.0055895596 0.0443140000 397434053 0 402718720 -0.0578045510 -0.2352709770 -0.1644811332 1311 1311867214.1643800735 0.0558972806 0.0535447472 0.0698473677 0.0055919756 0.0335130000 397437497 0 402718720 -0.0576267093 -0.2332753688 -0.1644849926 1312 1311867214.2013020515 0.0563762709 0.0535469054 0.0698473677 0.0055905018 0.0335610000 397440925 0 402718720 -0.0585121401 -0.2322420031 -0.1639234126 1313 1311867214.2338430882 0.0556127317 0.0535484787 0.0698473677 0.0055885471 0.0336440000 397444065 0 402718720 -0.0566626266 -0.2323722690 -0.1635064483 1314 1311867214.2674899101 0.0554258674 0.0535499075 0.0698473677 0.0055866639 0.0344640000 397447333 0 402718720 -0.0572832935 -0.2314071953 -0.1636856943 1315 1311867214.3004720211 0.0550373644 0.0535510386 0.0698473677 0.0055846591 0.0335650000 397450545 0 402718720 -0.0571705326 -0.2295760661 -0.1648077369 1316 1311867214.3310549259 0.0551810786 0.0535522773 0.0698473677 0.0055826863 0.0337980000 397453525 0 402718720 -0.0566991344 -0.2285148203 -0.1644248962 1317 1311867214.3663671017 0.0557100512 0.0535539157 0.0698473677 0.0055838161 0.0533390000 397456849 0 402718720 -0.0576368161 -0.2269451618 -0.1643318534 1318 1311867214.3980031013 0.0557404049 0.0535555746 0.0698473677 0.0055817276 0.0333660000 397460221 0 402718720 -0.0571402833 -0.2253397256 -0.1651407331 1319 1311867214.4332211018 0.0548576862 0.0535565618 0.0698473677 0.0055817400 0.0446440000 397463281 0 402718720 -0.0560814887 -0.2246666253 -0.1662205160 1320 1311867214.4698181152 0.0563694313 0.0535586928 0.0698473677 0.0055824383 0.0338980000 397466677 0 402718720 -0.0542571768 -0.2214568555 -0.1663518250 1321 1311867214.5059390068 0.0562984683 0.0535607668 0.0698473677 0.0055818213 0.0404530000 397964917 0 402718720 -0.0524705052 -0.2190984040 -0.1676183790 1322 1311867214.5373690128 0.0566513501 0.0535631046 0.0698473677 0.0055802309 0.1434980000 397953837 0 402718720 -0.0543127581 -0.2180999964 -0.1674595028 1323 1311867214.5691421032 0.0578762740 0.0535663647 0.0698473677 0.0055792036 0.1298180000 400828933 0 402718720 -0.0548119992 -0.2151298374 -0.1675546318 1324 1311867214.6048638821 0.0561178736 0.0535682919 0.0698473677 0.0055774785 0.0766430000 406890617 0 402718720 -0.0547093488 -0.2155852616 -0.1679437757 1325 1311867214.6369891167 0.0553261302 0.0535696185 0.0698473677 0.0055766081 0.0675710000 406679489 0 402718720 -0.0530458540 -0.2140991092 -0.1693970561 1326 1311867214.6691009998 0.0551831536 0.0535708354 0.0698473677 0.0055753949 0.1489010000 405210205 0 402718720 -0.0542372316 -0.2137448341 -0.1689518094 1327 1311867214.7048900127 0.0557138808 0.0535724503 0.0698473677 0.0055747653 0.0425780000 397924989 0 402718720 -0.0520456918 -0.2132886648 -0.1674515456 1328 1311867214.7369639874 0.0562020503 0.0535744305 0.0698473677 0.0055775638 0.0357000000 397928537 0 402718720 -0.0514726937 -0.2106854767 -0.1678574979 1329 1311867214.7695059776 0.0561985746 0.0535764050 0.0698473677 0.0055779387 0.0359490000 397931773 0 402718720 -0.0523412637 -0.2085511237 -0.1693580449 1330 1311867214.8049929142 0.0556679927 0.0535779776 0.0698473677 0.0055765013 0.0450050000 397935225 0 402718720 -0.0525894687 -0.2091888189 -0.1685773730 1331 1311867214.8369181156 0.0555479564 0.0535794577 0.0698473677 0.0055766410 0.0482370000 397938029 0 402718720 -0.0491332337 -0.2071354538 -0.1692289710 1332 1311867214.8699979782 0.0561527722 0.0535813896 0.0698473677 0.0055750432 0.0348230000 397941457 0 402718720 -0.0502522141 -0.2035349458 -0.1712830663 1333 1311867214.9049839973 0.0551756956 0.0535825856 0.0698473677 0.0055733779 0.0352200000 397944637 0 402718720 -0.0510950089 -0.2036308944 -0.1710654795 1334 1311867214.9372529984 0.0553660057 0.0535839225 0.0698473677 0.0055718391 0.0368220000 397948185 0 402718720 -0.0497254580 -0.2021774501 -0.1711204499 1335 1311867214.9693040848 0.0572398566 0.0535866611 0.0698473677 0.0055706816 0.0372700000 397951221 0 402718720 -0.0485078283 -0.1973887533 -0.1716632098 1336 1311867215.0050640106 0.0560826398 0.0535885293 0.0698473677 0.0055693336 0.0339600000 397954441 0 402718720 -0.0490079410 -0.1968675256 -0.1716038138 1337 1311867215.0371069908 0.0549599603 0.0535895551 0.0698473677 0.0055679628 0.0343870000 397957541 0 402718720 -0.0495208092 -0.1975735426 -0.1712830216 1338 1311867215.0692911148 0.0562166348 0.0535915185 0.0698473677 0.0055673759 0.0510200000 397960633 0 402718720 -0.0479259901 -0.1929295510 -0.1718928963 1339 1311867215.1050040722 0.0568034872 0.0535939173 0.0698473677 0.0055664793 0.0374880000 397963973 0 402718720 -0.0475561991 -0.1897648871 -0.1714533269 1340 1311867215.1369140148 0.0559982769 0.0535957116 0.0698473677 0.0055645064 0.0354240000 397966953 0 402718720 -0.0481291711 -0.1900156140 -0.1703012139 1341 1311867215.1694459915 0.0561471805 0.0535976142 0.0698473677 0.0055643544 0.0354570000 397970357 0 402718720 -0.0467843004 -0.1883119047 -0.1697606444 1342 1311867215.2049460411 0.0561974458 0.0535995515 0.0698473677 0.0055631359 0.0350240000 397973721 0 402718720 -0.0475156009 -0.1860367209 -0.1695067883 1343 1311867215.2369511127 0.0547244437 0.0536003891 0.0698473677 0.0055613318 0.0383480000 397977005 0 402718720 -0.0467016622 -0.1864982992 -0.1694771349 1344 1311867215.2690820694 0.0557001382 0.0536019514 0.0698473677 0.0055594576 0.0357790000 397979841 0 402718720 -0.0468362346 -0.1838536859 -0.1688720435 1345 1311867215.3049569130 0.0557031445 0.0536035136 0.0698473677 0.0055584412 0.0712080000 397983165 0 402718720 -0.0458064042 -0.1828756928 -0.1682870090 1346 1311867215.3369619846 0.0568191521 0.0536059027 0.0698473677 0.0055569975 0.0375770000 397986297 0 402718720 -0.0467059016 -0.1810259819 -0.1677814424 1347 1311867215.3691840172 0.0570990033 0.0536084959 0.0698473677 0.0055580839 0.0376660000 397989541 0 402718720 -0.0449825004 -0.1788502187 -0.1674895138 1348 1311867215.4049520493 0.0548691265 0.0536094311 0.0698473677 0.0055562466 0.0381950000 397992913 0 402718720 -0.0448148698 -0.1776960045 -0.1704033315 1349 1311867215.4370350838 0.0542215332 0.0536098849 0.0698473677 0.0055549014 0.0377080000 397995909 0 402718720 -0.0443415195 -0.1767532378 -0.1713155508 1350 1311867215.4690899849 0.0547747985 0.0536107478 0.0698473677 0.0055541985 0.0460720000 397999257 0 402718720 -0.0441712439 -0.1749616861 -0.1714055538 1351 1311867215.5049800873 0.0556657612 0.0536122689 0.0698473677 0.0055539954 0.0487590000 398002469 0 402718720 -0.0417332724 -0.1723763943 -0.1708667576 1352 1311867215.5371229649 0.0547256581 0.0536130924 0.0698473677 0.0055524038 0.0373790000 398005561 0 402718720 -0.0427544191 -0.1724905372 -0.1708535403 1353 1311867215.5690340996 0.0542182773 0.0536135397 0.0698473677 0.0055518363 0.0382460000 398008845 0 402718720 -0.0427291617 -0.1725742370 -0.1704698652 1354 1311867215.6050848961 0.0555896796 0.0536149991 0.0698473677 0.0055501076 0.0361010000 398012057 0 402718720 -0.0398380458 -0.1672143042 -0.1717131883 1355 1311867215.6370549202 0.0560669303 0.0536168087 0.0698473677 0.0055484013 0.0479660000 398015477 0 402718720 -0.0409291498 -0.1651308537 -0.1710487157 1356 1311867215.6689219475 0.0552106202 0.0536179841 0.0698473677 0.0055464412 0.0502180000 398018545 0 402718720 -0.0425581746 -0.1660009921 -0.1700233519 1357 1311867215.7049510479 0.0549058504 0.0536189331 0.0698473677 0.0055459434 0.0376690000 398021901 0 402718720 -0.0397649631 -0.1623883545 -0.1716200411 1358 1311867215.7388830185 0.0542711988 0.0536194134 0.0698473677 0.0055451009 0.0357110000 398025057 0 402718720 -0.0403847694 -0.1608115882 -0.1725524962 1359 1311867215.7691988945 0.0542542078 0.0536198805 0.0698473677 0.0055430922 0.0479180000 398028005 0 402718720 -0.0405501872 -0.1599692702 -0.1721102595 1360 1311867215.8048830032 0.0538154468 0.0536200243 0.0698473677 0.0055428299 0.0376380000 398031409 0 402718720 -0.0396751501 -0.1600622237 -0.1710192561 1361 1311867215.8373351097 0.0546433330 0.0536207762 0.0698473677 0.0055412424 0.0489880000 398034621 0 402718720 -0.0388373360 -0.1570405960 -0.1719598919 1362 1311867215.8691670895 0.0538057983 0.0536209121 0.0698473677 0.0055396568 0.0536020000 398037777 0 402718720 -0.0388813429 -0.1583317071 -0.1715246886 1363 1311867215.9052760601 0.0528726876 0.0536203631 0.0698473677 0.0055378274 0.0371760000 398041117 0 402718720 -0.0388136581 -0.1583450288 -0.1727659851 1364 1311867215.9370880127 0.0547784828 0.0536212122 0.0698473677 0.0055363262 0.0368840000 398044225 0 402718720 -0.0377491042 -0.1549638659 -0.1729649305 1365 1311867215.9702870846 0.0535677820 0.0536211730 0.0698473677 0.0055348082 0.0372940000 398047429 0 402718720 -0.0393310860 -0.1548790038 -0.1746536642 1366 1311867216.0050790310 0.0549388491 0.0536221377 0.0698473677 0.0055336391 0.0461420000 398050577 0 402718720 -0.0386265405 -0.1541684270 -0.1728433073 1367 1311867216.0369679928 0.0543474369 0.0536226682 0.0698473677 0.0055319406 0.0539690000 398053797 0 402718720 -0.0376552343 -0.1528833956 -0.1741144508 1368 1311867216.0694830418 0.0552546903 0.0536238612 0.0698473677 0.0055308560 0.0398310000 398056953 0 402718720 -0.0366915762 -0.1504815966 -0.1740036160 1369 1311867216.1050429344 0.0551250577 0.0536249578 0.0698473677 0.0055290558 0.0599770000 398060597 0 402718720 -0.0365129896 -0.1491668224 -0.1736382842 1370 1311867216.1392951012 0.0549213141 0.0536259040 0.0698473677 0.0055272217 0.0483280000 398063561 0 402718720 -0.0365357548 -0.1484838724 -0.1732443571 1371 1311867216.1692190170 0.0558126420 0.0536274990 0.0698473677 0.0055257548 0.0351760000 398066397 0 402718720 -0.0352086425 -0.1456784457 -0.1727188230 1372 1311867216.2049610615 0.0552921817 0.0536287124 0.0698473677 0.0055240077 0.0353800000 398069977 0 402718720 -0.0346072353 -0.1437874436 -0.1728759408 1373 1311867216.2370231152 0.0548435599 0.0536295972 0.0698473677 0.0055226420 0.0357300000 398073181 0 402718720 -0.0362894721 -0.1440861970 -0.1715842187 1374 1311867216.2706630230 0.0562900230 0.0536315334 0.0698473677 0.0055220549 0.0373800000 398076713 0 402718720 -0.0351077542 -0.1399735957 -0.1710697114 1375 1311867216.3050479889 0.0548318215 0.0536324064 0.0698473677 0.0055203427 0.0459730000 398079709 0 402718720 -0.0339639634 -0.1390684247 -0.1712007523 1376 1311867216.3395419121 0.0538429283 0.0536325594 0.0698473677 0.0055203190 0.0535860000 398083241 0 402718720 -0.0351661071 -0.1381226778 -0.1712221503 1377 1311867216.3694689274 0.0536916517 0.0536326023 0.0698473677 0.0055185241 0.0361340000 398085957 0 402718720 -0.0339803062 -0.1366690248 -0.1706167608 1378 1311867216.4055120945 0.0533702336 0.0536324119 0.0698473677 0.0055166686 0.0375140000 398089465 0 402718720 -0.0343075842 -0.1352331340 -0.1702457815 1379 1311867216.4373409748 0.0555016920 0.0536337674 0.0698473677 0.0055152122 0.0361750000 398092581 0 402718720 -0.0349863656 -0.1330484152 -0.1677232087 1380 1311867216.4697530270 0.0525573492 0.0536329874 0.0698473677 0.0055146926 0.0361790000 398096177 0 402718720 -0.0330541991 -0.1323170513 -0.1700935364 1381 1311867216.5049800873 0.0528005660 0.0536323846 0.0698473677 0.0055131544 0.0360150000 398099205 0 402718720 -0.0317073651 -0.1314548552 -0.1685899198 1382 1311867216.5372259617 0.0508897640 0.0536304001 0.0698473677 0.0055119841 0.0474880000 398102433 0 402718720 -0.0326191448 -0.1325520128 -0.1693601608 1383 1311867216.5693330765 0.0522294529 0.0536293871 0.0698473677 0.0055102915 0.0510690000 398105533 0 402718720 -0.0318816155 -0.1305113584 -0.1681069881 1384 1311867216.6050319672 0.0519789346 0.0536281946 0.0698473677 0.0055089454 0.0362480000 398108809 0 402718720 -0.0307161994 -0.1287706196 -0.1691984087 1385 1311867216.6373488903 0.0524632260 0.0536273535 0.0698473677 0.0055073540 0.0363080000 398111909 0 402718720 -0.0320289284 -0.1288745105 -0.1679683328 1386 1311867216.6691188812 0.0524761789 0.0536265229 0.0698473677 0.0055055423 0.0364640000 398115281 0 402718720 -0.0310908295 -0.1289004534 -0.1673526317 1387 1311867216.7052359581 0.0529336184 0.0536260233 0.0698473677 0.0055044453 0.0367380000 398118653 0 402718720 -0.0305176154 -0.1266442686 -0.1673136503 1388 1311867216.7372078896 0.0528419763 0.0536254585 0.0698473677 0.0055030636 0.0366870000 398121745 0 402718720 -0.0320001915 -0.1257651448 -0.1679528058 1389 1311867216.7691950798 0.0526426621 0.0536247509 0.0698473677 0.0055014339 0.0464030000 398124821 0 402718720 -0.0301261321 -0.1261734664 -0.1668523997 1390 1311867216.8050019741 0.0534419939 0.0536246194 0.0698473677 0.0054996313 0.0505970000 398128273 0 402718720 -0.0292639956 -0.1237420440 -0.1675612330 1391 1311867216.8379631042 0.0533426777 0.0536244167 0.0698473677 0.0054977029 0.0358080000 398131325 0 402718720 -0.0290277936 -0.1238187924 -0.1670445949 1392 1311867216.8703401089 0.0530838035 0.0536240284 0.0698473677 0.0054967756 0.0361570000 398134425 0 402718720 -0.0286186188 -0.1234463230 -0.1669790745 1393 1311867216.9049589634 0.0532798171 0.0536237813 0.0698473677 0.0054948016 0.0361570000 398137685 0 402718720 -0.0266308337 -0.1214385629 -0.1675218046 1394 1311867216.9374070168 0.0529626533 0.0536233070 0.0698473677 0.0054931348 0.0355190000 398140601 0 402718720 -0.0268107373 -0.1217983291 -0.1674391329 1395 1311867216.9691729546 0.0539877489 0.0536235682 0.0698473677 0.0054913615 0.0364160000 398143797 0 402718720 -0.0277688056 -0.1203147173 -0.1665708423 1396 1311867217.0053269863 0.0529330857 0.0536230736 0.0698473677 0.0054924295 0.0473160000 398147177 0 402718720 -0.0278968364 -0.1192305908 -0.1679966003 1397 1311867217.0373110771 0.0524840206 0.0536222583 0.0698473677 0.0054909135 0.0564310000 398150557 0 402718720 -0.0251017921 -0.1191894785 -0.1675384939 1398 1311867217.0691289902 0.0536312461 0.0536222647 0.0698473677 0.0054914898 0.0353920000 398153673 0 402718720 -0.0266769156 -0.1182627305 -0.1670251340 1399 1311867217.1052579880 0.0538741201 0.0536224447 0.0698473677 0.0054899414 0.0359720000 398156861 0 402718720 -0.0265045874 -0.1170586273 -0.1669103354 1400 1311867217.1370849609 0.0534675531 0.0536223341 0.0698473677 0.0054910364 0.0481610000 398159921 0 402718720 -0.0266064480 -0.1179565415 -0.1664822400 1401 1311867217.1691889763 0.0539244600 0.0536225497 0.0698473677 0.0054899949 0.0358560000 398162997 0 402718720 -0.0265155435 -0.1157228649 -0.1673386395 1402 1311867217.2057919502 0.0544939116 0.0536231712 0.0698473677 0.0054881766 0.0365050000 398166481 0 402718720 -0.0257982947 -0.1148083657 -0.1666670293 1403 1311867217.2371680737 0.0534761362 0.0536230664 0.0698473677 0.0054869635 0.0448060000 398169821 0 402718720 -0.0252663326 -0.1141312718 -0.1677748859 1404 1311867217.2692279816 0.0541760735 0.0536234603 0.0698473677 0.0054853679 0.0530420000 398172841 0 402718720 -0.0246717148 -0.1124689728 -0.1676890552 1405 1311867217.3051640987 0.0543179810 0.0536239546 0.0698473677 0.0054835916 0.0357770000 398176341 0 402718720 -0.0247620493 -0.1111800820 -0.1676677316 1406 1311867217.3374049664 0.0545623116 0.0536246220 0.0698473677 0.0054818522 0.0362720000 398179233 0 402718720 -0.0265853740 -0.1100073382 -0.1674674153 1407 1311867217.3695969582 0.0543526597 0.0536251395 0.0698473677 0.0054803196 0.0361240000 398182557 0 402718720 -0.0256229769 -0.1077152342 -0.1679348201 1408 1311867217.4120450020 0.0530308709 0.0536247174 0.0698473677 0.0054788422 0.0358430000 398185633 0 402718720 -0.0227770247 -0.1074176952 -0.1679633111 1409 1311867217.4372820854 0.0531970449 0.0536244139 0.0698473677 0.0054769012 0.0367350000 398188557 0 402718720 -0.0241400264 -0.1074258313 -0.1673347950 1410 1311867217.4694299698 0.0533927418 0.0536242496 0.0698473677 0.0054756308 0.0480020000 398191745 0 402718720 -0.0242448896 -0.1051432341 -0.1680886745 1411 1311867217.5050430298 0.0530963652 0.0536238755 0.0698473677 0.0054740022 0.0493780000 398195261 0 402718720 -0.0249052830 -0.1050150990 -0.1677344590 1412 1311867217.5370678902 0.0520198159 0.0536227394 0.0698473677 0.0054725545 0.0362540000 398198417 0 402718720 -0.0236714166 -0.1040575355 -0.1691773087 1413 1311867217.5691540241 0.0537625812 0.0536228384 0.0698473677 0.0054708946 0.0359490000 398201773 0 402718720 -0.0240554474 -0.1018652394 -0.1679289788 1414 1311867217.6050539017 0.0537776724 0.0536229479 0.0698473677 0.0054692092 0.0356820000 398204593 0 402718720 -0.0263735075 -0.1016554087 -0.1673289537 1415 1311867217.6370990276 0.0530534051 0.0536225454 0.0698473677 0.0054674044 0.0356070000 398207957 0 402718720 -0.0256661102 -0.0990755111 -0.1688115001 1416 1311867217.6691000462 0.0517133586 0.0536211971 0.0698473677 0.0054664509 0.0495660000 398211145 0 402718720 -0.0241071489 -0.0981793478 -0.1694540679 1417 1311867217.7050631046 0.0505463742 0.0536190272 0.0698473677 0.0054651069 0.0364640000 398214405 0 402718720 -0.0235283524 -0.0986255407 -0.1694642007 1418 1311867217.7371540070 0.0502419062 0.0536166455 0.0698473677 0.0054632475 0.0358040000 398217625 0 402718720 -0.0233986843 -0.0985732675 -0.1692003459 1419 1311867217.7694880962 0.0514506400 0.0536151191 0.0698473677 0.0054619626 0.0509330000 398220781 0 402718720 -0.0226371344 -0.0975065529 -0.1677570641 1420 1311867217.8051838875 0.0500155948 0.0536125842 0.0698473677 0.0054604208 0.0363170000 398224297 0 402718720 -0.0212884974 -0.0975024700 -0.1688957065 1421 1311867217.8372271061 0.0506361425 0.0536104896 0.0698473677 0.0054585333 0.0367620000 398227325 0 402718720 -0.0214501098 -0.0973219275 -0.1680821925 1422 1311867217.8690850735 0.0510254316 0.0536086717 0.0698473677 0.0054568865 0.0370930000 398230481 0 402718720 -0.0224645250 -0.0938282982 -0.1697994471 1423 1311867217.9056351185 0.0512029193 0.0536069811 0.0698473677 0.0054551083 0.0362520000 398233813 0 402718720 -0.0211750437 -0.0929604694 -0.1687664688 1424 1311867217.9372580051 0.0509348996 0.0536051046 0.0698473677 0.0054534303 0.0358390000 398237009 0 402718720 -0.0196863879 -0.0919903070 -0.1684399545 1425 1311867217.9711000919 0.0511841550 0.0536034057 0.0698473677 0.0054517817 0.0726860000 398240317 0 402718720 -0.0200227909 -0.0894410685 -0.1686703563 1426 1311867218.0052239895 0.0508823432 0.0536014976 0.0698473677 0.0054500091 0.0363680000 398243329 0 402718720 -0.0203133523 -0.0895185173 -0.1674503982 1427 1311867218.0371439457 0.0515406504 0.0536000534 0.0698473677 0.0054481911 0.0368780000 398246565 0 402718720 -0.0215092078 -0.0882435217 -0.1667216569 1428 1311867218.0710949898 0.0505703352 0.0535979317 0.0698473677 0.0054469066 0.0488770000 398249737 0 402718720 -0.0193108376 -0.0869537219 -0.1672178209 1429 1311867218.1050980091 0.0513054095 0.0535963274 0.0698473677 0.0054451736 0.0361960000 398252869 0 402718720 -0.0191335492 -0.0844755545 -0.1667076945 1430 1311867218.1371181011 0.0506133772 0.0535942415 0.0698473677 0.0054433190 0.0364500000 398255761 0 402718720 -0.0190517940 -0.0839030221 -0.1667037457 1431 1311867218.1712090969 0.0511837751 0.0535925570 0.0698473677 0.0054427226 0.0485830000 398259365 0 402718720 -0.0195745453 -0.0818065777 -0.1660377383 1432 1311867218.2050349712 0.0503686629 0.0535903057 0.0698473677 0.0054413464 0.0370250000 398262697 0 402718720 -0.0200104788 -0.0813203305 -0.1661743373 1433 1311867218.2372438908 0.0504969321 0.0535881470 0.0698473677 0.0054395191 0.0369010000 398265357 0 402718720 -0.0198220834 -0.0801752061 -0.1657308042 1434 1311867218.2715640068 0.0509327985 0.0535862953 0.0698473677 0.0054377656 0.0369850000 398268745 0 402718720 -0.0197191723 -0.0781760886 -0.1656356752 1435 1311867218.3051331043 0.0499988385 0.0535837953 0.0698473677 0.0054364558 0.0370260000 398272269 0 402718720 -0.0202762038 -0.0791824311 -0.1658366174 1436 1311867218.3373649120 0.0507850870 0.0535818464 0.0698473677 0.0054348557 0.0363740000 398275297 0 402718720 -0.0209667254 -0.0769519359 -0.1663522869 1437 1311867218.3734769821 0.0512863286 0.0535802489 0.0698473677 0.0054340435 0.0372630000 398278485 0 402718720 -0.0222519860 -0.0751425400 -0.1669334769 1438 1311867218.4052689075 0.0504791960 0.0535780924 0.0698473677 0.0054332023 0.0370680000 398281633 0 402718720 -0.0206765309 -0.0756211057 -0.1670273989 1439 1311867218.4372320175 0.0505168587 0.0535759651 0.0698473677 0.0054315848 0.0367320000 398284557 0 402718720 -0.0225240700 -0.0754707381 -0.1676322967 1440 1311867218.4729750156 0.0511339642 0.0535742693 0.0698473677 0.0054299958 0.0358270000 398287761 0 402718720 -0.0225475114 -0.0735203251 -0.1680638492 1441 1311867218.5051169395 0.0525871441 0.0535735842 0.0698473677 0.0054297984 0.0363630000 398291365 0 402718720 -0.0223216973 -0.0705908015 -0.1676252931 1442 1311867218.5372729301 0.0512671396 0.0535719847 0.0698473677 0.0054285540 0.0472200000 398294537 0 402718720 -0.0218071863 -0.0703299567 -0.1683998406 1443 1311867218.5714759827 0.0513134375 0.0535704196 0.0698473677 0.0054269665 0.0741940000 398297365 0 402718720 -0.0202509593 -0.0698500797 -0.1673599035 1444 1311867218.6059319973 0.0519502275 0.0535692976 0.0698473677 0.0054255917 0.0365100000 398300913 0 402718720 -0.0207709204 -0.0680236444 -0.1666837484 1445 1311867218.6372020245 0.0511988699 0.0535676571 0.0698473677 0.0054249388 0.0369070000 398303773 0 402718720 -0.0232014321 -0.0686752349 -0.1667984575 1446 1311867218.6710820198 0.0517663173 0.0535664114 0.0698473677 0.0054243723 0.0369200000 398307177 0 402718720 -0.0215914138 -0.0668349862 -0.1658836901 1447 1311867218.7058999538 0.0498986132 0.0535638766 0.0698473677 0.0054235007 0.0362470000 398310525 0 402718720 -0.0207373369 -0.0667745769 -0.1671207249 1448 1311867218.7378489971 0.0506406128 0.0535618578 0.0698473677 0.0054221711 0.0464490000 398313353 0 402718720 -0.0209347792 -0.0664086565 -0.1652075201 1449 1311867218.7715899944 0.0522293523 0.0535609382 0.0698473677 0.0054232023 0.0374290000 398316661 0 402718720 -0.0235582516 -0.0647758543 -0.1644881964 1450 1311867218.8052420616 0.0525940098 0.0535602713 0.0698473677 0.0054221456 0.0375690000 398319809 0 402718720 -0.0215338469 -0.0628571734 -0.1635724306 1451 1311867218.8379960060 0.0515965968 0.0535589180 0.0698473677 0.0054204889 0.0372990000 398323109 0 402718720 -0.0226026550 -0.0637151822 -0.1634003520 1452 1311867218.8727340698 0.0515576303 0.0535575397 0.0698473677 0.0054257742 0.0370180000 398326057 0 402718720 -0.0240521487 -0.0642545074 -0.1631545126 1453 1311867218.9054861069 0.0519141369 0.0535564087 0.0698473677 0.0054275581 0.0372230000 398329085 0 402718720 -0.0234959535 -0.0610677153 -0.1628310680 1454 1311867218.9372200966 0.0494094305 0.0535535566 0.0698473677 0.0054292551 0.0372610000 398332609 0 402718720 -0.0226933733 -0.0626324713 -0.1636091322 1455 1311867218.9731678963 0.0502178334 0.0535512640 0.0698473677 0.0054287290 0.0372740000 398335757 0 402718720 -0.0235734899 -0.0606417321 -0.1633048356 1456 1311867219.0051829815 0.0502867959 0.0535490219 0.0698473677 0.0054271400 0.0371280000 398338913 0 402718720 -0.0237590149 -0.0590975583 -0.1633525789 1457 1311867219.0371239185 0.0502127744 0.0535467321 0.0698473677 0.0054254930 0.0372890000 398342285 0 402718720 -0.0233787410 -0.0584994219 -0.1626483649 1458 1311867219.0738430023 0.0504275523 0.0535445927 0.0698473677 0.0054291876 0.0364660000 398345353 0 402718720 -0.0249570236 -0.0572616681 -0.1622670293 1459 1311867219.1050798893 0.0498357080 0.0535420507 0.0698473677 0.0054329688 0.0367720000 398348525 0 402718720 -0.0230104364 -0.0571873635 -0.1617551744 1460 1311867219.1383259296 0.0511203259 0.0535403919 0.0698473677 0.0054314131 0.0368300000 398351833 0 402718720 -0.0223650560 -0.0559412166 -0.1598948389 1461 1311867219.1708459854 0.0508772060 0.0535385691 0.0698473677 0.0054295662 0.0743190000 398355165 0 402718720 -0.0230182279 -0.0552681573 -0.1598909050 1462 1311867219.2052450180 0.0505045243 0.0535364938 0.0698473677 0.0054279831 0.0367910000 398358313 0 402718720 -0.0234892331 -0.0542665422 -0.1598583311 1463 1311867219.2391340733 0.0506872796 0.0535345463 0.0698473677 0.0054297689 0.0373180000 398361365 0 402718720 -0.0243112445 -0.0531297475 -0.1591779739 1464 1311867219.2709059715 0.0502769426 0.0535323212 0.0698473677 0.0054284091 0.0364300000 398364449 0 402718720 -0.0245166104 -0.0521060750 -0.1595633328 1465 1311867219.3052430153 0.0498655327 0.0535298182 0.0698473677 0.0054324902 0.0364620000 398367605 0 402718720 -0.0230486970 -0.0525154099 -0.1585554481 1466 1311867219.3401598930 0.0504062995 0.0535276876 0.0698473677 0.0054310773 0.0522130000 398371001 0 402718720 -0.0210368242 -0.0499756746 -0.1584191918 1467 1311867219.3715050220 0.0497038327 0.0535250810 0.0698473677 0.0054295303 0.0369540000 398374381 0 402718720 -0.0224128626 -0.0498872101 -0.1589378119 1468 1311867219.4051969051 0.0500005707 0.0535226801 0.0698473677 0.0054280031 0.0374720000 398377577 0 402718720 -0.0218368135 -0.0492841378 -0.1580113173 1469 1311867219.4394860268 0.0495099872 0.0535199485 0.0698473677 0.0054262929 0.0364140000 398380349 0 402718720 -0.0201640241 -0.0485018864 -0.1579931676 1470 1311867219.4717299938 0.0488747582 0.0535167885 0.0698473677 0.0054245520 0.0588230000 398383593 0 402718720 -0.0195815973 -0.0472975783 -0.1584770083 1471 1311867219.5051560402 0.0497998931 0.0535142618 0.0698473677 0.0054227649 0.0369300000 398386813 0 402718720 -0.0203049853 -0.0472447388 -0.1566721499 1472 1311867219.5391950607 0.0494985767 0.0535115337 0.0698473677 0.0054214531 0.0744410000 398390281 0 402718720 -0.0200636126 -0.0451048017 -0.1576853245 1473 1311867219.5743470192 0.0495948829 0.0535088748 0.0698473677 0.0054198415 0.0364040000 398393221 0 402718720 -0.0197841264 -0.0439532772 -0.1572677046 1474 1311867219.6086258888 0.0484759249 0.0535054603 0.0698473677 0.0054183702 0.0367840000 398396513 0 402718720 -0.0194056071 -0.0446658395 -0.1572588235 1475 1311867219.6425020695 0.0497690961 0.0535029271 0.0698473677 0.0054285626 0.0366310000 398399637 0 402718720 -0.0191278029 -0.0430881679 -0.1568259001 1476 1311867219.6711170673 0.0498231910 0.0535004341 0.0698473677 0.0054444333 0.0364800000 398402801 0 402718720 -0.0180169716 -0.0431008376 -0.1560298055 1477 1311867219.7052869797 0.0502840318 0.0534982564 0.0698473677 0.0054427381 0.0458810000 398405957 0 402718720 -0.0174926315 -0.0433998108 -0.1554885358 1478 1311867219.7395179272 0.0500997454 0.0534959570 0.0698473677 0.0054425846 0.0370020000 398409369 0 402718720 -0.0166221224 -0.0416118056 -0.1562735885 1479 1311867219.7772109509 0.0505595170 0.0534939716 0.0698473677 0.0054542514 0.0477190000 398412757 0 402718720 -0.0164423529 -0.0410859585 -0.1562182456 1480 1311867219.8051769733 0.0497248136 0.0534914249 0.0698473677 0.0054532788 0.0495230000 398415737 0 402718720 -0.0165889487 -0.0405695960 -0.1575380862 1481 1311867219.8397340775 0.0491165891 0.0534884709 0.0698473677 0.0054518382 0.0363900000 398418869 0 402718720 -0.0149249174 -0.0389821418 -0.1583749801 1482 1311867219.8753221035 0.0497952774 0.0534859789 0.0698473677 0.0054630551 0.0369310000 398422025 0 402718720 -0.0141685773 -0.0387299471 -0.1571845263 1483 1311867219.9108390808 0.0502903387 0.0534838240 0.0698473677 0.0054787875 0.0739590000 398424981 0 402718720 -0.0147482613 -0.0367128663 -0.1570266187 1484 1311867219.9417819977 0.0502573401 0.0534816499 0.0698473677 0.0054806436 0.0362450000 398428321 0 402718720 -0.0141189350 -0.0357828587 -0.1563396901 1485 1311867219.9732298851 0.0495565347 0.0534790067 0.0698473677 0.0054795990 0.0374330000 398431469 0 402718720 -0.0122978454 -0.0355769470 -0.1566019356 1486 1311867220.0068678856 0.0499287285 0.0534766175 0.0698473677 0.0054817902 0.0368770000 398434553 0 402718720 -0.0127263274 -0.0341491178 -0.1566130221 1487 1311867220.0422430038 0.0503498763 0.0534745148 0.0698473677 0.0054804017 0.0375230000 398438349 0 402718720 -0.0134928664 -0.0328693576 -0.1559160501 1488 1311867220.0743820667 0.0505127534 0.0534725244 0.0698473677 0.0054786066 0.0745050000 398441097 0 402718720 -0.0137786120 -0.0320517644 -0.1561172903 1489 1311867220.1052761078 0.0508522056 0.0534707646 0.0698473677 0.0054844474 0.0361310000 398444437 0 402718720 -0.0131967403 -0.0310228728 -0.1554343998 1490 1311867220.1421229839 0.0509763919 0.0534690905 0.0698473677 0.0054827318 0.0363360000 398447545 0 402718720 -0.0134205157 -0.0293705650 -0.1554041505 1491 1311867220.1714730263 0.0505952835 0.0534671631 0.0698473677 0.0054874548 0.0366120000 398450661 0 402718720 -0.0134842461 -0.0274001434 -0.1555814147 1492 1311867220.2061989307 0.0508134142 0.0534653844 0.0698473677 0.0054908202 0.0367770000 398454049 0 402718720 -0.0137006575 -0.0270200372 -0.1553936303 1493 1311867220.2422249317 0.0505693890 0.0534634447 0.0698473677 0.0054925211 0.0554330000 398456989 0 402718720 -0.0127445152 -0.0270317569 -0.1548991650 1494 1311867220.2741279602 0.0508384816 0.0534616877 0.0698473677 0.0054912030 0.0374480000 398460209 0 402718720 -0.0127188386 -0.0256939959 -0.1550302356 1495 1311867220.3064579964 0.0523322709 0.0534609322 0.0698473677 0.0055057524 0.0362090000 398463373 0 402718720 -0.0157789551 -0.0248397626 -0.1545270979 1496 1311867220.3420999050 0.0506675169 0.0534590650 0.0698473677 0.0055076773 0.0360300000 398466601 0 402718720 -0.0136256106 -0.0245515071 -0.1554773748 1497 1311867220.3714869022 0.0503885150 0.0534570139 0.0698473677 0.0055522731 0.0374810000 398469997 0 402718720 -0.0130717866 -0.0237338673 -0.1546151042 1498 1311867220.4063799381 0.0507793352 0.0534552264 0.0698473677 0.0055513952 0.0365230000 398473025 0 402718720 -0.0127168735 -0.0215651356 -0.1545100957 1499 1311867220.4408841133 0.0498403385 0.0534528148 0.0698473677 0.0055500546 0.0489500000 398476325 0 402718720 -0.0127641940 -0.0197775401 -0.1553542614 1500 1311867220.4728751183 0.0499502420 0.0534504798 0.0698473677 0.0055515303 0.0370280000 398479417 0 402718720 -0.0122730294 -0.0199383870 -0.1544601470 1501 1311867220.5091059208 0.0510171764 0.0534488587 0.0698473677 0.0055503033 0.0366330000 398482701 0 402718720 -0.0134272855 -0.0182229038 -0.1543011814 1502 1311867220.5419850349 0.0489868484 0.0534458879 0.0698473677 0.0055491594 0.0363810000 398486017 0 402718720 -0.0121311210 -0.0177758485 -0.1558543593 1503 1311867220.5716400146 0.0498764925 0.0534435131 0.0698473677 0.0055479779 0.0375540000 398488893 0 402718720 -0.0120951217 -0.0168704838 -0.1551812291 1504 1311867220.6104249954 0.0489881784 0.0534405508 0.0698473677 0.0055472017 0.0371070000 398492481 0 402718720 -0.0111165969 -0.0173935462 -0.1558857262 1505 1311867220.6415500641 0.0492572226 0.0534377711 0.0698473677 0.0055456435 0.0749190000 398495645 0 402718720 -0.0112845190 -0.0161267538 -0.1563000530 1506 1311867220.6713089943 0.0507281087 0.0534359719 0.0698473677 0.0055445771 0.0366200000 398498601 0 402718720 -0.0100030312 -0.0145567134 -0.1554632336 1507 1311867220.7073359489 0.0502743647 0.0534338740 0.0698473677 0.0055473527 0.0363170000 398501861 0 402718720 -0.0104025220 -0.0151212374 -0.1564769745 1508 1311867220.7393438816 0.0499333926 0.0534315527 0.0698473677 0.0055468344 0.0369900000 398504817 0 402718720 -0.0095827440 -0.0145159224 -0.1568827778 1509 1311867220.7719850540 0.0500369519 0.0534293031 0.0698473677 0.0055462453 0.0364900000 398507909 0 402718720 -0.0096778292 -0.0129824113 -0.1578393579 1510 1311867220.8097529411 0.0507179573 0.0534275075 0.0698473677 0.0055461792 0.0366930000 398511729 0 402718720 -0.0094296914 -0.0123972734 -0.1575149596 1511 1311867220.8415019512 0.0494974330 0.0534249065 0.0698473677 0.0055448668 0.0362790000 398514645 0 402718720 -0.0066806087 -0.0110288952 -0.1587591767 1512 1311867220.8712480068 0.0502361618 0.0534227976 0.0698473677 0.0055477161 0.0357160000 398517553 0 402718720 -0.0067120409 -0.0100180078 -0.1579477787 1513 1311867220.9075961113 0.0493525155 0.0534201074 0.0698473677 0.0055500908 0.0361210000 398520813 0 402718720 -0.0067982459 -0.0100628659 -0.1588263214 1514 1311867220.9392969608 0.0500552803 0.0534178849 0.0698473677 0.0055484019 0.0372660000 398523961 0 402718720 -0.0055851061 -0.0094330320 -0.1577411890 1515 1311867220.9713189602 0.0498638190 0.0534155390 0.0698473677 0.0055592340 0.0366940000 398527125 0 402718720 -0.0055975206 -0.0088135805 -0.1577699780 1516 1311867221.0090179443 0.0496042594 0.0534130249 0.0698473677 0.0055575111 0.0373750000 398530713 0 402718720 -0.0044594975 -0.0084469803 -0.1573138982 1517 1311867221.0392940044 0.0491450466 0.0534102115 0.0698473677 0.0055560645 0.0765710000 398533805 0 402718720 -0.0032498725 -0.0076073352 -0.1576249599 1518 1311867221.0720989704 0.0485272035 0.0534069948 0.0698473677 0.0055542728 0.0362670000 398536729 0 402718720 -0.0036360333 -0.0059485896 -0.1588121057 1519 1311867221.1077580452 0.0501470156 0.0534048486 0.0698473677 0.0055535110 0.0361600000 398540069 0 402718720 -0.0035578702 -0.0050641391 -0.1567599773 1520 1311867221.1397790909 0.0497465841 0.0534024419 0.0698473677 0.0055522378 0.0375710000 398543289 0 402718720 -0.0033385074 -0.0057755280 -0.1567831635 1521 1311867221.1716909409 0.0497787409 0.0534000594 0.0698473677 0.0055530621 0.0367950000 398546133 0 402718720 -0.0031555155 -0.0042011403 -0.1573201418 1522 1311867221.2083969116 0.0498724096 0.0533977417 0.0698473677 0.0055522674 0.0470860000 398549585 0 402718720 -0.0012440830 -0.0015383568 -0.1574601978 1523 1311867221.2398130894 0.0490416996 0.0533948815 0.0698473677 0.0055517045 0.0373850000 398552597 0 402718720 0.0000413274 -0.0024062018 -0.1571991444 1524 1311867221.2721240520 0.0481645837 0.0533914495 0.0698473677 0.0055503748 0.0370150000 398556001 0 402718720 0.0002411166 -0.0017726752 -0.1581664979 1525 1311867221.3075931072 0.0500539765 0.0533892610 0.0698473677 0.0055508159 0.0370600000 398559269 0 402718720 0.0016566589 0.0026809685 -0.1578941047 1526 1311867221.3393449783 0.0480397344 0.0533857555 0.0698473677 0.0055497391 0.0376410000 398562353 0 402718720 0.0029732259 0.0015777750 -0.1593775451 1527 1311867221.3714220524 0.0489624664 0.0533828587 0.0698473677 0.0055480041 0.0376650000 398565493 0 402718720 0.0021613510 0.0016186838 -0.1589822769 1528 1311867221.4073879719 0.0502896868 0.0533808344 0.0698473677 0.0055464650 0.0373840000 398568641 0 402718720 0.0043197516 0.0058379397 -0.1592574567 1529 1311867221.4400680065 0.0489559621 0.0533779404 0.0698473677 0.0055457516 0.0373250000 398571861 0 402718720 0.0060247360 0.0061026909 -0.1608373970 1530 1311867221.4712409973 0.0502954610 0.0533759257 0.0698473677 0.0055441000 0.0369180000 398575433 0 402718720 0.0056070369 0.0080029378 -0.1603991985 1531 1311867221.5081720352 0.0503169410 0.0533739277 0.0698473677 0.0055428627 0.0359020000 398578133 0 402718720 0.0061974833 0.0083514731 -0.1603859365 1532 1311867221.5396909714 0.0495974012 0.0533714626 0.0698473677 0.0055410711 0.0362470000 398581417 0 402718720 0.0062676165 0.0104785264 -0.1623625904 1533 1311867221.5712790489 0.0491833277 0.0533687306 0.0698473677 0.0055408439 0.0363630000 398584629 0 402718720 0.0064318520 0.0111315316 -0.1634484679 1534 1311867221.6073110104 0.0485529080 0.0533655912 0.0698473677 0.0055396262 0.0366280000 398587849 0 402718720 0.0068525206 0.0113697657 -0.1648343205 1535 1311867221.6403770447 0.0504812226 0.0533637122 0.0698473677 0.0055396871 0.0467480000 398591253 0 402718720 0.0067043388 0.0155986901 -0.1647264510 1536 1311867221.6771481037 0.0511630550 0.0533622795 0.0698473677 0.0055386132 0.0448200000 399253385 0 402718720 0.0058912146 0.0173453335 -0.1653137058 1537 1311867221.7072019577 0.0502527058 0.0533602563 0.0698473677 0.0055413465 0.1478300000 399223289 0 402718720 0.0041950140 0.0183328316 -0.1673492044 1538 1311867221.7423930168 0.0507883541 0.0533585841 0.0698473677 0.0055400006 0.1456660000 399226741 0 402718720 0.0057184072 0.0215443708 -0.1680419594 1539 1311867221.7773499489 0.0509503447 0.0533570193 0.0698473677 0.0055389308 0.1432180000 399515861 0 402718720 0.0053034192 0.0242721327 -0.1693740040 1540 1311867221.8074541092 0.0522901192 0.0533563265 0.0698473677 0.0055375501 0.1280460000 408228325 0 402718720 0.0022499915 0.0259253439 -0.1695705652 1541 1311867221.8396520615 0.0513980053 0.0533550557 0.0698473677 0.0055428859 0.1070650000 408014221 0 402718720 0.0036138687 0.0253881365 -0.1709326506 1542 1311867221.8777329922 0.0513106063 0.0533537298 0.0698473677 0.0055456137 0.1547760000 406316317 0 402718720 0.0032174541 0.0263623502 -0.1730139852 1543 1311867221.9077489376 0.0525029115 0.0533531784 0.0698473677 0.0055475600 0.0458770000 399235241 0 402718720 0.0013558306 0.0295226928 -0.1743236631 1544 1311867221.9424629211 0.0525478907 0.0533526569 0.0698473677 0.0055479653 0.0385130000 399238141 0 402718720 0.0008843038 0.0299002454 -0.1748742908 1545 1311867221.9775359631 0.0530563854 0.0533524651 0.0698473677 0.0055473622 0.0388430000 399241305 0 402718720 0.0006643329 0.0319185518 -0.1758815199 1546 1311867222.0090060234 0.0533007309 0.0533524316 0.0698473677 0.0055459581 0.0737900000 399244517 0 402718720 0.0016634027 0.0337396115 -0.1763363183 1547 1311867222.0428760052 0.0518316925 0.0533514486 0.0698473677 0.0055473601 0.0377170000 399247633 0 402718720 0.0014153793 0.0338860974 -0.1781398058 1548 1311867222.0782530308 0.0536941141 0.0533516700 0.0698473677 0.0055524168 0.0372690000 399250717 0 402718720 -0.0009946944 0.0382160135 -0.1783881634 1549 1311867222.1110939980 0.0522199459 0.0533509394 0.0698473677 0.0055524146 0.0371840000 399254057 0 402718720 0.0008508023 0.0397016406 -0.1792014390 1550 1311867222.1406900883 0.0509040095 0.0533493607 0.0698473677 0.0055712617 0.0490020000 399257229 0 402718720 -0.0006312197 0.0406137146 -0.1796818227 1551 1311867222.1797990799 0.0514094383 0.0533481099 0.0698473677 0.0055877066 0.0617390000 399260569 0 402718720 0.0000103666 0.0424278677 -0.1792717576 1552 1311867222.2081730366 0.0512302257 0.0533467453 0.0698473677 0.0055870750 0.0395090000 399263621 0 402718720 -0.0000784965 0.0459717661 -0.1796618253 1553 1311867222.2400839329 0.0519355126 0.0533458366 0.0698473677 0.0055880811 0.0391280000 399266673 0 402718720 -0.0010884926 0.0474718511 -0.1781073213 1554 1311867222.2760300636 0.0512839518 0.0533445098 0.0698473677 0.0055892089 0.0396550000 399270061 0 402718720 -0.0038746512 0.0470869914 -0.1780756265 1555 1311867222.3077421188 0.0505435355 0.0533427085 0.0698473677 0.0055898936 0.0570610000 399273049 0 402718720 -0.0010988982 0.0511120595 -0.1780587733 1556 1311867222.3396389484 0.0507871397 0.0533410661 0.0698473677 0.0055889587 0.0382730000 399276501 0 402718720 -0.0009416826 0.0525652654 -0.1767667383 1557 1311867222.3792359829 0.0512373224 0.0533397150 0.0698473677 0.0055950252 0.0451220000 399279753 0 402718720 -0.0032222234 0.0532645248 -0.1760599017 1558 1311867222.4102001190 0.0509955883 0.0533382104 0.0698473677 0.0055933530 0.0381140000 399282997 0 402718720 -0.0028514834 0.0568799749 -0.1760741472 1559 1311867222.4436430931 0.0504596420 0.0533363640 0.0698473677 0.0055920174 0.0388090000 399286417 0 402718720 -0.0026509352 0.0573861748 -0.1753793657 1560 1311867222.4781119823 0.0509758592 0.0533348508 0.0698473677 0.0055903509 0.0363570000 399289629 0 402718720 -0.0046762256 0.0601303875 -0.1740160137 1561 1311867222.5087089539 0.0507677644 0.0533332063 0.0698473677 0.0055890956 0.0455920000 399987577 0 402718720 -0.0047992347 0.0613667592 -0.1732858866 1562 1311867222.5401790142 0.0515815131 0.0533320849 0.0698473677 0.0055884914 0.1283250000 399969537 0 402718720 -0.0040105889 0.0636426955 -0.1721960306 1563 1311867222.5774040222 0.0515831932 0.0533309659 0.0698473677 0.0055869840 0.1188490000 399972721 0 402718720 -0.0041489489 0.0641528666 -0.1709286124 1564 1311867222.6084389687 0.0515826009 0.0533298481 0.0698473677 0.0055854661 0.1188190000 402523161 0 402718720 -0.0035939803 0.0653061867 -0.1693523973 1565 1311867222.6433119774 0.0506752133 0.0533281518 0.0698473677 0.0055854748 0.0929480000 409693165 0 402718720 -0.0029352400 0.0666429698 -0.1695304960 1566 1311867222.6796491146 0.0512286387 0.0533268111 0.0698473677 0.0055871895 0.0935580000 409460233 0 402718720 -0.0045829769 0.0670557395 -0.1686669737 1567 1311867222.7080249786 0.0508849621 0.0533252528 0.0698473677 0.0055887095 0.0464330000 409584101 0 402718720 -0.0017054370 0.0687294602 -0.1674449295 1568 1311867222.7400081158 0.0502482615 0.0533232905 0.0698473677 0.0055897941 0.1223210000 403927769 0 402718720 -0.0007564481 0.0706122816 -0.1676257849 1569 1311867222.7793939114 0.0514235273 0.0533220796 0.0698473677 0.0055895595 0.0384760000 399941357 0 402718720 -0.0011059036 0.0710213631 -0.1654704958 1570 1311867222.8093209267 0.0513362549 0.0533208148 0.0698473677 0.0055885671 0.0386610000 399944457 0 402718720 -0.0009484207 0.0711506009 -0.1650842577 1571 1311867222.8402760029 0.0515849628 0.0533197098 0.0698473677 0.0055870165 0.0386340000 399947477 0 402718720 -0.0017972356 0.0730567947 -0.1648889929 1572 1311867222.8812980652 0.0508791395 0.0533181573 0.0698473677 0.0055864090 0.0508570000 399950937 0 402718720 -0.0012120688 0.0724801943 -0.1642593890 1573 1311867222.9082360268 0.0507674888 0.0533165358 0.0698473677 0.0055846376 0.0504000000 399953909 0 402718720 -0.0010608518 0.0734407231 -0.1642831117 1574 1311867222.9470820427 0.0505852401 0.0533148005 0.0698473677 0.0055836637 0.0382080000 399957265 0 402718720 -0.0010242676 0.0739890561 -0.1636424512 1575 1311867222.9831020832 0.0510735996 0.0533133775 0.0698473677 0.0055822477 0.0387000000 399960765 0 402718720 -0.0021211319 0.0747578666 -0.1627928019 1576 1311867223.0078310966 0.0507559255 0.0533117548 0.0698473677 0.0055837718 0.0386470000 399963753 0 402718720 -0.0020993063 0.0749040395 -0.1627698988 1577 1311867223.0454061031 0.0500528701 0.0533096883 0.0698473677 0.0055821395 0.0377440000 399967005 0 402718720 -0.0012745140 0.0755532607 -0.1627551168 1578 1311867223.0808250904 0.0500875935 0.0533076464 0.0698473677 0.0055817402 0.0409010000 399970009 0 402718720 -0.0024158983 0.0763503686 -0.1624988914 1579 1311867223.1094229221 0.0505830497 0.0533059209 0.0698473677 0.0055815685 0.0398490000 399973269 0 402718720 -0.0029533105 0.0772305056 -0.1616829336 1580 1311867223.1473770142 0.0502899103 0.0533040120 0.0698473677 0.0055803003 0.0399140000 399976361 0 402718720 -0.0033302307 0.0785644874 -0.1619473398 1581 1311867223.1758580208 0.0512432605 0.0533027086 0.0698473677 0.0055807227 0.0386980000 399979477 0 402718720 -0.0035541132 0.0796375051 -0.1606845111 1582 1311867223.2080020905 0.0503388643 0.0533008351 0.0698473677 0.0055790719 0.0363870000 399982585 0 402718720 -0.0044288775 0.0794886723 -0.1606634259 1583 1311867223.2450079918 0.0507286042 0.0532992102 0.0698473677 0.0055787067 0.0369620000 399986253 0 402718720 -0.0047301752 0.0816668868 -0.1597483456 1584 1311867223.2779359818 0.0505726337 0.0532974889 0.0698473677 0.0055769547 0.0390460000 399989329 0 402718720 -0.0052003032 0.0834747553 -0.1597394943 1585 1311867223.3085999489 0.0512026474 0.0532961672 0.0698473677 0.0055762139 0.0385550000 399992357 0 402718720 -0.0060101543 0.0842429176 -0.1586748362 1586 1311867223.3452420235 0.0509012491 0.0532946572 0.0698473677 0.0055747840 0.0391100000 399995385 0 402718720 -0.0063608307 0.0852548033 -0.1581967622 1587 1311867223.3794689178 0.0496390611 0.0532923537 0.0698473677 0.0055779998 0.0358140000 399998677 0 402718720 -0.0083798813 0.0870176181 -0.1582630724 1588 1311867223.4074239731 0.0515184440 0.0532912366 0.0698473677 0.0055775606 0.0490300000 400001817 0 402718720 -0.0064667929 0.0886403471 -0.1573297977 1589 1311867223.4458000660 0.0524086133 0.0532906812 0.0698473677 0.0055764752 0.0394500000 400005133 0 402718720 -0.0075301137 0.0891813561 -0.1564828753 1590 1311867223.4758329391 0.0518590249 0.0532897807 0.0698473677 0.0055748587 0.0390630000 400008169 0 402718720 -0.0071360534 0.0907608941 -0.1573963612 1591 1311867223.5077428818 0.0518131033 0.0532888526 0.0698473677 0.0055735272 0.0368200000 400011605 0 402718720 -0.0088165486 0.0941812694 -0.1586738974 1592 1311867223.5466530323 0.0509934798 0.0532874108 0.0698473677 0.0055784694 0.0471370000 400015033 0 402718720 -0.0097256452 0.0928114653 -0.1591193229 1593 1311867223.5759539604 0.0536633246 0.0532876468 0.0698473677 0.0055829906 0.0491710000 400018117 0 402718720 -0.0117505761 0.0943354890 -0.1574800164 1594 1311867223.6078069210 0.0527782962 0.0532873272 0.0698473677 0.0055814322 0.0387460000 400021041 0 402718720 -0.0129833054 0.0962068737 -0.1593702137 1595 1311867223.6502039433 0.0531559289 0.0532872448 0.0698473677 0.0055837569 0.0374900000 400024589 0 402718720 -0.0122271730 0.0958755389 -0.1585941017 1596 1311867223.6753880978 0.0512371883 0.0532859603 0.0698473677 0.0055826328 0.0394650000 400027289 0 402718720 -0.0120223146 0.0966820866 -0.1609318107 1597 1311867223.7088580132 0.0509509146 0.0532844982 0.0698473677 0.0055809870 0.0470390000 400030765 0 402718720 -0.0119301779 0.0989738554 -0.1617327034 1598 1311867223.7452809811 0.0511810258 0.0532831819 0.0698473677 0.0055801691 0.0359980000 400034289 0 402718720 -0.0123604527 0.0997254476 -0.1615684628 1599 1311867223.7760720253 0.0522219241 0.0532825182 0.0698473677 0.0055809537 0.0357050000 400037077 0 402718720 -0.0118136676 0.1029958278 -0.1614719778 1600 1311867223.8077559471 0.0522218011 0.0532818552 0.0698473677 0.0055792192 0.0376390000 400040249 0 402718720 -0.0130205574 0.1043387949 -0.1620573997 1601 1311867223.8438520432 0.0538307130 0.0532821981 0.0698473677 0.0055821741 0.0355340000 400043757 0 402718720 -0.0128801791 0.1063578948 -0.1610718817 1602 1311867223.8760919571 0.0523968600 0.0532816454 0.0698473677 0.0055813909 0.0462520000 400046857 0 402718720 -0.0129010845 0.1076898798 -0.1628642678 1603 1311867223.9078280926 0.0525535606 0.0532811912 0.0698473677 0.0055797580 0.0373040000 400049757 0 402718720 -0.0120600807 0.1088254303 -0.1628550291 1604 1311867223.9491670132 0.0546189696 0.0532820252 0.0698473677 0.0055788362 0.0369930000 400053457 0 402718720 -0.0128512327 0.1101000085 -0.1613302082 1605 1311867223.9760739803 0.0537080429 0.0532822907 0.0698473677 0.0055807780 0.0443390000 400780525 0 402718720 -0.0122584151 0.1113492697 -0.1623931229 1606 1311867224.0093441010 0.0540923774 0.0532827951 0.0698473677 0.0055816583 0.1310450000 400738077 0 402718720 -0.0112639302 0.1121444553 -0.1626048088 1607 1311867224.0470440388 0.0537439771 0.0532830821 0.0698473677 0.0055800109 0.1262770000 400738329 0 402718720 -0.0116778892 0.1138063222 -0.1635574996 1608 1311867224.0761411190 0.0560662560 0.0532848129 0.0698473677 0.0055794189 0.1147220000 404939097 0 402718720 -0.0112729799 0.1171604693 -0.1620500684 1609 1311867224.1081349850 0.0562559329 0.0532866595 0.0698473677 0.0055780428 0.0789590000 410536817 0 402718720 -0.0113907242 0.1174572408 -0.1624271870 1610 1311867224.1458990574 0.0552035533 0.0532878501 0.0698473677 0.0055823587 0.0926980000 410422073 0 402718720 -0.0087706549 0.1195971891 -0.1637260765 1611 1311867224.1768929958 0.0559165590 0.0532894818 0.0698473677 0.0055881763 0.1360210000 408718177 0 402718720 -0.0090855677 0.1215821877 -0.1641763896 1612 1311867224.2143769264 0.0561378188 0.0532912488 0.0698473677 0.0055868013 0.0479650000 400748917 0 402718720 -0.0073719965 0.1221560463 -0.1640280932 1613 1311867224.2470428944 0.0552997999 0.0532924940 0.0698473677 0.0055851870 0.0385550000 400752033 0 402718720 -0.0086938506 0.1231309250 -0.1657252014 1614 1311867224.2768630981 0.0564578995 0.0532944552 0.0698473677 0.0055847617 0.0377550000 400755165 0 402718720 -0.0072619515 0.1273011565 -0.1657257676 1615 1311867224.3146169186 0.0578472391 0.0532972743 0.0698473677 0.0055832709 0.0379120000 400758505 0 402718720 -0.0060328273 0.1290734857 -0.1651935726 1616 1311867224.3456730843 0.0568164997 0.0532994520 0.0698473677 0.0055815773 0.0378120000 400761461 0 402718720 -0.0060074897 0.1307485551 -0.1668892354 1617 1311867224.3769209385 0.0572539829 0.0533018976 0.0698473677 0.0055803092 0.0392720000 400764721 0 402718720 -0.0074984292 0.1320152879 -0.1672920287 1618 1311867224.4141020775 0.0580679812 0.0533048433 0.0698473677 0.0055809648 0.0378920000 400768373 0 402718720 -0.0064368248 0.1345110238 -0.1677044481 1619 1311867224.4464271069 0.0573132560 0.0533073191 0.0698473677 0.0055802952 0.0380100000 400771217 0 402718720 -0.0068424204 0.1345474571 -0.1688357443 1620 1311867224.4776859283 0.0577549450 0.0533100646 0.0698473677 0.0055811988 0.0383420000 400774245 0 402718720 -0.0059070522 0.1362667680 -0.1691886038 1621 1311867224.5181219578 0.0582240149 0.0533130960 0.0698473677 0.0055868404 0.0382950000 400777985 0 402718720 -0.0054619089 0.1377420872 -0.1699821502 1622 1311867224.5470569134 0.0587703623 0.0533164605 0.0698473677 0.0055884204 0.0373870000 400781077 0 402718720 -0.0063680708 0.1390567571 -0.1705944687 1623 1311867224.5859119892 0.0579801314 0.0533193340 0.0698473677 0.0055890294 0.0374890000 400784593 0 402718720 -0.0059725931 0.1413336247 -0.1722633392 1624 1311867224.6181120872 0.0582764708 0.0533223864 0.0698473677 0.0055874431 0.0371860000 400787397 0 402718720 -0.0068475446 0.1423297077 -0.1722997725 1625 1311867224.6502161026 0.0589418449 0.0533258446 0.0698473677 0.0055860682 0.0397270000 400790537 0 402718720 -0.0061513791 0.1430818439 -0.1716379672 1626 1311867224.6785190105 0.0577830411 0.0533285858 0.0698473677 0.0055873908 0.0523550000 400793885 0 402718720 -0.0080095930 0.1440746635 -0.1730033159 1627 1311867224.7173650265 0.0573457517 0.0533310548 0.0698473677 0.0055882001 0.0477090000 400797001 0 402718720 -0.0070467610 0.1463612467 -0.1737546474 1628 1311867224.7520918846 0.0590302907 0.0533345556 0.0698473677 0.0055866978 0.0497280000 400800453 0 402718720 -0.0070540681 0.1479479522 -0.1722105443 1629 1311867224.7866261005 0.0582268536 0.0533375588 0.0698473677 0.0055862535 0.0404380000 400803425 0 402718720 -0.0071197487 0.1488815546 -0.1729451716 1630 1311867224.8123459816 0.0581039451 0.0533404830 0.0698473677 0.0055874619 0.0407530000 400806653 0 402718720 -0.0090933349 0.1516951025 -0.1738599688 1631 1311867224.8458189964 0.0574936718 0.0533430294 0.0698473677 0.0056158102 0.0397940000 400809649 0 402718720 -0.0071601178 0.1528706849 -0.1735408008 1632 1311867224.8779430389 0.0581915230 0.0533460003 0.0698473677 0.0056210415 0.0513670000 400812869 0 402718720 -0.0078875562 0.1539004147 -0.1725381315 1633 1311867224.9142448902 0.0577330664 0.0533486868 0.0698473677 0.0056250770 0.0477260000 400816057 0 402718720 -0.0070339339 0.1557161659 -0.1726803929 1634 1311867224.9471449852 0.0597141981 0.0533525825 0.0698473677 0.0056270299 0.0528340000 400819221 0 402718720 -0.0061892793 0.1597991437 -0.1710308790 1635 1311867224.9800488949 0.0598559491 0.0533565601 0.0698473677 0.0056255837 0.0395310000 400822625 0 402718720 -0.0051989555 0.1607184708 -0.1698867828 1636 1311867225.0142920017 0.0574851446 0.0533590837 0.0698473677 0.0056243611 0.0395480000 400825557 0 402718720 -0.0061446717 0.1619487256 -0.1717763841 1637 1311867225.0493879318 0.0572976097 0.0533614896 0.0698473677 0.0056247397 0.0755830000 400828785 0 402718720 -0.0080004483 0.1648202240 -0.1715428233 1638 1311867225.0798690319 0.0578338727 0.0533642200 0.0698473677 0.0056255939 0.0422870000 400831805 0 402718720 -0.0062484778 0.1642241478 -0.1703696549 1639 1311867225.1138188839 0.0584636480 0.0533673313 0.0698473677 0.0056262229 0.0465330000 400834761 0 402718720 -0.0077327630 0.1675518155 -0.1699785888 1640 1311867225.1472380161 0.0583892614 0.0533703934 0.0698473677 0.0056249482 0.0432010000 400838005 0 402718720 -0.0074099069 0.1684722304 -0.1691877693 1641 1311867225.1810939312 0.0596604645 0.0533742265 0.0698473677 0.0056235704 0.0433990000 400841345 0 402718720 -0.0060434267 0.1712756604 -0.1675889492 1642 1311867225.2153220177 0.0604226589 0.0533785191 0.0698473677 0.0056218959 0.0459610000 400844613 0 402718720 -0.0078757601 0.1723367423 -0.1668985486 1643 1311867225.2483470440 0.0593604073 0.0533821599 0.0698473677 0.0056223993 0.0462160000 400847905 0 402718720 -0.0073567731 0.1741070449 -0.1676563323 1644 1311867225.2792909145 0.0593481325 0.0533857889 0.0698473677 0.0056207664 0.0425490000 400850797 0 402718720 -0.0077422997 0.1764951646 -0.1676529944 1645 1311867225.3207540512 0.0614202581 0.0533906731 0.0698473677 0.0056200796 0.0454630000 400854353 0 402718720 -0.0059480080 0.1774777621 -0.1653539240 1646 1311867225.3462350368 0.0614502691 0.0533955695 0.0698473677 0.0056186422 0.0364180000 400857141 0 402718720 -0.0089093512 0.1778165698 -0.1656070948 1647 1311867225.3852069378 0.0602809936 0.0533997501 0.0698473677 0.0056171185 0.0406210000 400860649 0 402718720 -0.0077866931 0.1810052693 -0.1668678820 1648 1311867225.4130129814 0.0611828864 0.0534044729 0.0698473677 0.0056155433 0.0498060000 400863629 0 402718720 -0.0084938006 0.1817988902 -0.1660931855 1649 1311867225.4504270554 0.0616146252 0.0534094518 0.0698473677 0.0056138977 0.0406530000 400867065 0 402718720 -0.0089855026 0.1829283237 -0.1658328474 1650 1311867225.4842948914 0.0616667643 0.0534144562 0.0698473677 0.0056130554 0.0405560000 400870037 0 402718720 -0.0097476523 0.1845639795 -0.1663160771 1651 1311867225.5163919926 0.0618548468 0.0534195685 0.0698473677 0.0056128502 0.0525380000 400873385 0 402718720 -0.0098156985 0.1849632114 -0.1666819900 1652 1311867225.5493750572 0.0617307536 0.0534245995 0.0698473677 0.0056147659 0.0393680000 400876501 0 402718720 -0.0120028742 0.1878973693 -0.1679289788 1653 1311867225.5882349014 0.0621325187 0.0534298674 0.0698473677 0.0056142282 0.0402830000 400879881 0 402718720 -0.0115839122 0.1908366531 -0.1680928171 1654 1311867225.6179010868 0.0640940592 0.0534363149 0.0698473677 0.0056127982 0.0497570000 400882909 0 402718720 -0.0141936243 0.1922629029 -0.1679305434 1655 1311867225.6461288929 0.0638093203 0.0534425826 0.0698473677 0.0056117498 0.0368560000 400886105 0 402718720 -0.0158298314 0.1937036812 -0.1697396785 1656 1311867225.6847119331 0.0643527284 0.0534491709 0.0698473677 0.0056102798 0.0369280000 400889557 0 402718720 -0.0166493803 0.1952180564 -0.1702214926 1657 1311867225.7160770893 0.0641205013 0.0534556110 0.0698473677 0.0056093125 0.0367810000 400892513 0 402718720 -0.0162983220 0.1967741102 -0.1717473567 1658 1311867225.7506299019 0.0638766065 0.0534618963 0.0698473677 0.0056110253 0.0395070000 400895797 0 402718720 -0.0173994526 0.1947767735 -0.1729236543 1659 1311867225.7872900963 0.0612235032 0.0534665748 0.0698473677 0.0056094830 0.0401020000 400898889 0 402718720 -0.0159879103 0.1967057288 -0.1764540970 1660 1311867225.8170781136 0.0633884966 0.0534725518 0.0698473677 0.0056096877 0.0402000000 400901877 0 402718720 -0.0178558324 0.1992164850 -0.1752635390 1661 1311867225.8520019054 0.0623394959 0.0534778902 0.0698473677 0.0056114922 0.0391670000 400905257 0 402718720 -0.0187204555 0.2002216429 -0.1773218960 1662 1311867225.8862910271 0.0614553355 0.0534826901 0.0698473677 0.0056166994 0.0393830000 400908525 0 402718720 -0.0169250481 0.2014757097 -0.1785395443 1663 1311867225.9177930355 0.0613576919 0.0534874255 0.0698473677 0.0056154653 0.0366150000 400911617 0 402718720 -0.0162557699 0.2008288950 -0.1785676777 1664 1311867225.9504909515 0.0623095185 0.0534927272 0.0698473677 0.0056150430 0.0391590000 400914821 0 402718720 -0.0192698948 0.2044581473 -0.1787525266 1665 1311867225.9852480888 0.0609228313 0.0534971897 0.0698473677 0.0056137369 0.0511190000 400918209 0 402718720 -0.0200311001 0.2041212320 -0.1807012856 1666 1311867226.0173718929 0.0623991601 0.0535025331 0.0698473677 0.0056125799 0.0483000000 400921245 0 402718720 -0.0177571680 0.2091507912 -0.1806470603 1667 1311867226.0511479378 0.0604508892 0.0535067012 0.0698473677 0.0056116678 0.0386330000 400924585 0 402718720 -0.0194444936 0.2070195824 -0.1823801696 1668 1311867226.0877819061 0.0601149909 0.0535106630 0.0698473677 0.0056120072 0.0384990000 400927845 0 402718720 -0.0198622718 0.2096937001 -0.1832658052 1669 1311867226.1182270050 0.0626847148 0.0535161598 0.0698473677 0.0056146241 0.0391880000 400930801 0 402718720 -0.0191692337 0.2131054848 -0.1812846065 1670 1311867226.1477489471 0.0601313151 0.0535201210 0.0698473677 0.0056137531 0.0375660000 400934093 0 402718720 -0.0207435507 0.2106106579 -0.1835058630 1671 1311867226.1833140850 0.0603182092 0.0535241892 0.0698473677 0.0056134540 0.0371820000 400937305 0 402718720 -0.0198898315 0.2147404850 -0.1838163137 1672 1311867226.2166810036 0.0619288906 0.0535292160 0.0698473677 0.0056126682 0.0458800000 401639117 0 402718720 -0.0215298366 0.2188328505 -0.1834947318 1673 1311867226.2487111092 0.0610034689 0.0535336835 0.0698473677 0.0056115101 0.1273680000 401601105 0 402718720 -0.0212965775 0.2196146250 -0.1846044660 1674 1311867226.2829930782 0.0612999201 0.0535383229 0.0698473677 0.0056109044 0.1266170000 401606053 0 402718720 -0.0210128557 0.2200893313 -0.1848719418 1675 1311867226.3211309910 0.0617022291 0.0535431968 0.0698473677 0.0056099225 0.1209240000 401910773 0 402718720 -0.0217487942 0.2231574208 -0.1855258942 1676 1311867226.3455820084 0.0598679855 0.0535469706 0.0698473677 0.0056089630 0.1173480000 410515577 0 402718720 -0.0209646709 0.2224890292 -0.1869846880 1677 1311867226.3873078823 0.0606021173 0.0535511776 0.0698473677 0.0056079463 0.0886860000 410559417 0 402718720 -0.0199345406 0.2265251279 -0.1867776811 1678 1311867226.4188749790 0.0619749203 0.0535561977 0.0698473677 0.0056076628 0.0497220000 411649029 0 402718720 -0.0222339258 0.2300608754 -0.1863306314 1679 1311867226.4472739697 0.0593772568 0.0535596647 0.0698473677 0.0056065336 0.1342780000 409942281 0 402718720 -0.0228181221 0.2291438580 -0.1888781935 1680 1311867226.4849569798 0.0588173456 0.0535627942 0.0698473677 0.0056052010 0.0533170000 401614637 0 402718720 -0.0209496524 0.2302117050 -0.1897447556 1681 1311867226.5167839527 0.0598742366 0.0535665488 0.0698473677 0.0056041932 0.0394990000 401617889 0 402718720 -0.0200094692 0.2316848785 -0.1893142015 1682 1311867226.5462191105 0.0592708439 0.0535699402 0.0698473677 0.0056029857 0.0403680000 401621173 0 402718720 -0.0196089633 0.2329673320 -0.1902542114 1683 1311867226.5842289925 0.0594111793 0.0535734109 0.0698473677 0.0056015681 0.0388830000 401623977 0 402718720 -0.0208783150 0.2345268875 -0.1904971004 1684 1311867226.6149599552 0.0592201054 0.0535767641 0.0698473677 0.0056000495 0.0498000000 401627277 0 402718720 -0.0210774224 0.2357944846 -0.1909497976 1685 1311867226.6545290947 0.0600990131 0.0535806348 0.0698473677 0.0055989205 0.0402300000 401630729 0 402718720 -0.0204504952 0.2371455282 -0.1906350404 1686 1311867226.6802148819 0.0593229197 0.0535840407 0.0698473677 0.0055978879 0.0399160000 401633901 0 402718720 -0.0216633901 0.2385251224 -0.1918019056 1687 1311867226.7142350674 0.0611788370 0.0535885427 0.0698473677 0.0055982896 0.0390470000 401636785 0 402718720 -0.0220162347 0.2393581569 -0.1910350025 1688 1311867226.7506589890 0.0616934299 0.0535933441 0.0698473677 0.0055994962 0.0395250000 401640173 0 402718720 -0.0220304523 0.2407220155 -0.1912082583 1689 1311867226.7818078995 0.0603294894 0.0535973324 0.0698473677 0.0055983003 0.0394570000 401643129 0 402718720 -0.0216091014 0.2410638183 -0.1928513050 1690 1311867226.8133080006 0.0609080568 0.0536016583 0.0698473677 0.0055994571 0.0381960000 401646285 0 402718720 -0.0207809899 0.2443252802 -0.1927385181 1691 1311867226.8513610363 0.0614001565 0.0536062700 0.0698473677 0.0055980327 0.0402630000 401649745 0 402718720 -0.0220288336 0.2428035140 -0.1923534721 1692 1311867226.8838679790 0.0606990866 0.0536104620 0.0698473677 0.0056016243 0.0411250000 401652941 0 402718720 -0.0237675328 0.2441906482 -0.1939268261 1693 1311867226.9181559086 0.0594605543 0.0536139174 0.0698473677 0.0056001254 0.0418740000 401656017 0 402718720 -0.0232760794 0.2446869016 -0.1955797076 1694 1311867226.9514899254 0.0611241534 0.0536183509 0.0698473677 0.0055986674 0.0372160000 401659349 0 402718720 -0.0240313448 0.2458868325 -0.1947921067 1695 1311867226.9810149670 0.0601605475 0.0536222106 0.0698473677 0.0055971853 0.0413630000 401662513 0 402718720 -0.0241453052 0.2460469306 -0.1959100366 1696 1311867227.0125620365 0.0608061552 0.0536264464 0.0698473677 0.0055961123 0.0378020000 401665485 0 402718720 -0.0223508663 0.2480676770 -0.1953508258 1697 1311867227.0480670929 0.0615400709 0.0536311097 0.0698473677 0.0055963744 0.0503630000 401668689 0 402718720 -0.0236880705 0.2497719377 -0.1950258315 1698 1311867227.0861930847 0.0592277199 0.0536344057 0.0698473677 0.0055960823 0.0409690000 401672109 0 402718720 -0.0236934442 0.2511662543 -0.1970763505 1699 1311867227.1158189774 0.0597564131 0.0536380090 0.0698473677 0.0055953224 0.0380380000 401674985 0 402718720 -0.0252068192 0.2524154782 -0.1965932250 1700 1311867227.1503999233 0.0621389970 0.0536430096 0.0698473677 0.0055987805 0.0400200000 401678149 0 402718720 -0.0234841369 0.2533309162 -0.1938626170 1701 1311867227.1841590405 0.0604147576 0.0536469906 0.0698473677 0.0055973288 0.0372300000 401681785 0 402718720 -0.0252196565 0.2544963062 -0.1954385191 1702 1311867227.2148449421 0.0620621368 0.0536519349 0.0698473677 0.0055961499 0.0370070000 401684789 0 402718720 -0.0230076648 0.2581901252 -0.1940891296 1703 1311867227.2480258942 0.0627856404 0.0536572982 0.0698473677 0.0055978655 0.0453520000 401688105 0 402718720 -0.0251099728 0.2568181753 -0.1932926923 1704 1311867227.2819800377 0.0632316694 0.0536629170 0.0698473677 0.0056003437 0.0511040000 401691133 0 402718720 -0.0259482358 0.2603026927 -0.1931174994 1705 1311867227.3152499199 0.0619074479 0.0536677525 0.0698473677 0.0055995724 0.0376210000 401694497 0 402718720 -0.0254888944 0.2612124681 -0.1944055408 1706 1311867227.3479840755 0.0621352009 0.0536727158 0.0698473677 0.0055981469 0.0516320000 401697645 0 402718720 -0.0252253339 0.2615723014 -0.1938221306 1707 1311867227.3841071129 0.0613304265 0.0536772019 0.0698473677 0.0056011187 0.0372340000 401701001 0 402718720 -0.0263373908 0.2605312169 -0.1941020191 1708 1311867227.4141440392 0.0617002286 0.0536818992 0.0698473677 0.0056025323 0.0403390000 401703853 0 402718720 -0.0270660780 0.2633509636 -0.1940262318 1709 1311867227.4479200840 0.0610994846 0.0536862395 0.0698473677 0.0056031122 0.0490580000 401707025 0 402718720 -0.0274235830 0.2650555968 -0.1948536634 1710 1311867227.4818758965 0.0650023594 0.0536928571 0.0698473677 0.0056019124 0.0376960000 401710429 0 402718720 -0.0303445943 0.2645018101 -0.1912998855 1711 1311867227.5169329643 0.0627086088 0.0536981264 0.0698473677 0.0056004814 0.0371860000 401713705 0 402718720 -0.0276515856 0.2662968040 -0.1936923265 1712 1311867227.5501220226 0.0629005879 0.0537035017 0.0698473677 0.0055989948 0.0533620000 401716829 0 402718720 -0.0278815776 0.2671798170 -0.1936628819 1713 1311867227.5819540024 0.0627185330 0.0537087644 0.0698473677 0.0055973863 0.0400740000 401719905 0 402718720 -0.0284019057 0.2671997547 -0.1938192099 1714 1311867227.6162750721 0.0637507960 0.0537146232 0.0698473677 0.0056001428 0.0381680000 401723245 0 402718720 -0.0288600326 0.2677672505 -0.1926631778 1715 1311867227.6503078938 0.0627824739 0.0537199106 0.0698473677 0.0056132618 0.0514850000 401726697 0 402718720 -0.0315920934 0.2680529058 -0.1934524477 1716 1311867227.6823980808 0.0626164526 0.0537250950 0.0698473677 0.0056119467 0.0406200000 401729525 0 402718720 -0.0291811768 0.2703807354 -0.1935348809 1717 1311867227.7135930061 0.0618394241 0.0537298209 0.0698473677 0.0056119741 0.0537200000 401732769 0 402718720 -0.0294154119 0.2702140510 -0.1939561367 1718 1311867227.7496368885 0.0616611764 0.0537344375 0.0698473677 0.0056104843 0.0406130000 401736165 0 402718720 -0.0279954504 0.2709836662 -0.1934380680 1719 1311867227.7827620506 0.0631280765 0.0537399021 0.0698473677 0.0056089507 0.0406730000 401739113 0 402718720 -0.0290102176 0.2719119489 -0.1917731315 1720 1311867227.8141551018 0.0624461882 0.0537449639 0.0698473677 0.0056086530 0.0379840000 401742205 0 402718720 -0.0293038283 0.2724836767 -0.1921709627 1721 1311867227.8497691154 0.0605757944 0.0537489330 0.0698473677 0.0056140368 0.0499100000 401745625 0 402718720 -0.0281443466 0.2721366286 -0.1930490881 1722 1311867227.8832869530 0.0634612069 0.0537545732 0.0698473677 0.0056153151 0.0378110000 401748453 0 402718720 -0.0299455021 0.2783242464 -0.1910180300 1723 1311867227.9196939468 0.0632613152 0.0537600907 0.0698473677 0.0056139493 0.0382470000 401752169 0 402718720 -0.0290346909 0.2779745162 -0.1907652617 1724 1311867227.9516780376 0.0615998283 0.0537646381 0.0698473677 0.0056126904 0.0371610000 401755253 0 402718720 -0.0281457864 0.2773385048 -0.1921433359 1725 1311867227.9828588963 0.0619120225 0.0537693612 0.0698473677 0.0056112708 0.0396340000 401758353 0 402718720 -0.0267596412 0.2795903981 -0.1918097436 1726 1311867228.0181910992 0.0622709468 0.0537742868 0.0698473677 0.0056101840 0.0444930000 402502637 0 402718720 -0.0271167178 0.2806689441 -0.1910712719 1727 1311867228.0516328812 0.0619580559 0.0537790256 0.0698473677 0.0056087246 0.1360220000 402470857 0 402718720 -0.0259157103 0.2822161317 -0.1911520958 1728 1311867228.0825328827 0.0621101670 0.0537838468 0.0698473677 0.0056075051 0.1283610000 402473845 0 402718720 -0.0256097261 0.2821229994 -0.1907027662 1729 1311867228.1179840565 0.0633923188 0.0537894041 0.0698473677 0.0056061281 0.1200760000 402504443 0 402718720 -0.0260901563 0.2844342589 -0.1896820217 1730 1311867228.1511390209 0.0636247769 0.0537950892 0.0698473677 0.0056061359 0.1053690000 413155401 0 402718720 -0.0253513083 0.2864354849 -0.1898709536 1731 1311867228.1828610897 0.0642682761 0.0538011396 0.0698473677 0.0056047219 0.1079510000 412913449 0 402718720 -0.0238813478 0.2873102427 -0.1893402636 1732 1311867228.2179419994 0.0659564435 0.0538081577 0.0698473677 0.0056086987 0.1316870000 407935965 0 402718720 -0.0235817358 0.2899571061 -0.1880935580 1733 1311867228.2541251183 0.0645931661 0.0538143810 0.0698473677 0.0056131886 0.0408150000 402439253 0 402718720 -0.0237006061 0.2901241779 -0.1899548471 1734 1311867228.2826519012 0.0645278618 0.0538205595 0.0698473677 0.0056116541 0.0416860000 402442161 0 402718720 -0.0222713314 0.2916037738 -0.1899973005 1735 1311867228.3181738853 0.0645935610 0.0538267687 0.0698473677 0.0056103165 0.0397520000 402445549 0 402718720 -0.0220670160 0.2920792997 -0.1901141703 1736 1311867228.3504519463 0.0640607476 0.0538326639 0.0698473677 0.0056088309 0.0408780000 402448633 0 402718720 -0.0234044641 0.2923913002 -0.1908714473 1737 1311867228.3824779987 0.0642594323 0.0538386666 0.0698473677 0.0056073899 0.0492270000 402451741 0 402718720 -0.0218722634 0.2943488955 -0.1907093078 1738 1311867228.4176759720 0.0649626926 0.0538450671 0.0698473677 0.0056058526 0.0396450000 402454761 0 402718720 -0.0231154487 0.2951152623 -0.1901985109 1739 1311867228.4483039379 0.0653943121 0.0538517084 0.0698473677 0.0056049374 0.0403450000 402458133 0 402718720 -0.0231466591 0.2955896854 -0.1896179914 1740 1311867228.4835319519 0.0649405047 0.0538580813 0.0698473677 0.0056036120 0.0387090000 402461385 0 402718720 -0.0228073485 0.2950781882 -0.1901733577 1741 1311867228.5177900791 0.0662785023 0.0538652153 0.0698473677 0.0056049389 0.0385130000 402464461 0 402718720 -0.0244227964 0.2960666120 -0.1897581369 1742 1311867228.5529639721 0.0661803260 0.0538722849 0.0698473677 0.0056034150 0.0403200000 402467657 0 402718720 -0.0231757350 0.2952418923 -0.1901006550 1743 1311867228.5834119320 0.0667489842 0.0538796725 0.0698473677 0.0056019462 0.0505920000 402470877 0 402718720 -0.0238162894 0.2953231633 -0.1902331561 1744 1311867228.6168839931 0.0661716387 0.0538867207 0.0698473677 0.0056011178 0.0397180000 402474025 0 402718720 -0.0228864141 0.2945875525 -0.1913659722 1745 1311867228.6513540745 0.0655695051 0.0538934157 0.0698473677 0.0055997225 0.0392330000 402477541 0 402718720 -0.0236530509 0.2927464843 -0.1925037354 1746 1311867228.6960909367 0.0670448989 0.0539009480 0.0698473677 0.0055988413 0.0388710000 402480953 0 402718720 -0.0248485897 0.2918921411 -0.1923936307 1747 1311867228.7251129150 0.0671823174 0.0539085504 0.0698473677 0.0055983027 0.0395600000 402483917 0 402718720 -0.0264485702 0.2932037711 -0.1930131316 1748 1311867228.7533209324 0.0641904846 0.0539144325 0.0698473677 0.0055984082 0.0392090000 402486985 0 402718720 -0.0242390148 0.2888742089 -0.1953556389 1749 1311867228.7872729301 0.0654031113 0.0539210012 0.0698473677 0.0056037088 0.0428880000 402489845 0 402718720 -0.0241853353 0.2889055610 -0.1945870519 1750 1311867228.8184990883 0.0651489422 0.0539274172 0.0698473677 0.0056069832 0.0392630000 402492873 0 402718720 -0.0250169039 0.2861582637 -0.1955987811 1751 1311867228.8512189388 0.0621731728 0.0539321264 0.0698473677 0.0056060266 0.0496530000 402496285 0 402718720 -0.0260854736 0.2854922116 -0.1984231323 1752 1311867228.8835051060 0.0655635372 0.0539387653 0.0698473677 0.0056049950 0.0526560000 402499441 0 402718720 -0.0268828087 0.2857525647 -0.1960690767 1753 1311867228.9181449413 0.0648882836 0.0539450115 0.0698473677 0.0056034647 0.0416400000 402502541 0 402718720 -0.0255736783 0.2843642831 -0.1972931921 1754 1311867228.9496490955 0.0634036213 0.0539504041 0.0698473677 0.0056025154 0.0421420000 402505753 0 402718720 -0.0270131528 0.2822594345 -0.1988623291 1755 1311867228.9844760895 0.0652012229 0.0539568148 0.0698473677 0.0056013486 0.0528190000 402508797 0 402718720 -0.0265818574 0.2814000547 -0.1975918114 1756 1311867229.0238449574 0.0647426099 0.0539629570 0.0698473677 0.0056001888 0.0543510000 402512425 0 402718720 -0.0262342021 0.2800272107 -0.1989555508 1757 1311867229.0509281158 0.0629943013 0.0539680972 0.0698473677 0.0055991916 0.0393740000 402515333 0 402718720 -0.0262835268 0.2778131962 -0.2006111294 1758 1311867229.0874319077 0.0643792450 0.0539740194 0.0698473677 0.0055980887 0.0429920000 402518617 0 402718720 -0.0275368541 0.2778227031 -0.1997039318 1759 1311867229.1218080521 0.0652353540 0.0539804215 0.0698473677 0.0055969914 0.0428190000 402521813 0 402718720 -0.0265583359 0.2753292024 -0.1988583803 1760 1311867229.1517140865 0.0628484413 0.0539854602 0.0698473677 0.0055969587 0.0431100000 402525153 0 402718720 -0.0276259314 0.2719986737 -0.2013148814 1761 1311867229.1890540123 0.0635007396 0.0539908635 0.0698473677 0.0055961371 0.0427050000 402528573 0 402718720 -0.0277149081 0.2711222470 -0.2008742988 1762 1311867229.2214341164 0.0648781583 0.0539970425 0.0698473677 0.0055957150 0.0399290000 402531465 0 402718720 -0.0264596790 0.2718246877 -0.2001209259 1763 1311867229.2532980442 0.0648223683 0.0540031827 0.0698473677 0.0055996350 0.0428600000 402534501 0 402718720 -0.0283816941 0.2700869441 -0.2011973411 1764 1311867229.2841351032 0.0631747618 0.0540083820 0.0698473677 0.0055983931 0.0414500000 402537721 0 402718720 -0.0289263930 0.2657616436 -0.2025789917 1765 1311867229.3193020821 0.0634596124 0.0540137368 0.0698473677 0.0056015114 0.0428040000 402540933 0 402718720 -0.0285454635 0.2653878331 -0.2028698325 1766 1311867229.3502240181 0.0628711656 0.0540187524 0.0698473677 0.0056020340 0.0427200000 402543961 0 402718720 -0.0270696133 0.2612650692 -0.2033898979 1767 1311867229.3850710392 0.0625329539 0.0540235708 0.0698473677 0.0056008714 0.0422090000 402547309 0 402718720 -0.0282277223 0.2606995106 -0.2047712803 1768 1311867229.4180469513 0.0619246848 0.0540280398 0.0698473677 0.0056010622 0.0430580000 402550585 0 402718720 -0.0273434576 0.2575702369 -0.2053579688 1769 1311867229.4483740330 0.0635952950 0.0540334481 0.0698473677 0.0056005614 0.0428840000 402553453 0 402718720 -0.0285551194 0.2564703524 -0.2045486718 1770 1311867229.4843358994 0.0630451366 0.0540385394 0.0698473677 0.0056042033 0.0432210000 402556841 0 402718720 -0.0287342239 0.2546256185 -0.2055775523 1771 1311867229.5189929008 0.0626686737 0.0540434125 0.0698473677 0.0056028057 0.0435250000 402560005 0 402718720 -0.0283095334 0.2517561018 -0.2065880448 1772 1311867229.5504579544 0.0629960969 0.0540484648 0.0698473677 0.0056012992 0.0392190000 402563153 0 402718720 -0.0286015943 0.2508733869 -0.2068909258 1773 1311867229.5853381157 0.0604986362 0.0540521028 0.0698473677 0.0056008553 0.0521360000 402566373 0 402718720 -0.0280663818 0.2482871413 -0.2094044089 1774 1311867229.6182799339 0.0606144220 0.0540558019 0.0698473677 0.0055994583 0.0394970000 402569777 0 402718720 -0.0290857628 0.2466078103 -0.2097719461 1775 1311867229.6503160000 0.0619063526 0.0540602248 0.0698473677 0.0055985770 0.0427400000 402572725 0 402718720 -0.0292484798 0.2449022084 -0.2088659555 1776 1311867229.6876978874 0.0605672933 0.0540638887 0.0698473677 0.0055980360 0.0416970000 402576241 0 402718720 -0.0295059998 0.2445025146 -0.2108562142 1777 1311867229.7184219360 0.0597177520 0.0540670703 0.0698473677 0.0055970502 0.0507020000 402579013 0 402718720 -0.0282590855 0.2427301705 -0.2118616253 1778 1311867229.7500000000 0.0605515540 0.0540707174 0.0698473677 0.0055956670 0.0423750000 402582321 0 402718720 -0.0298820008 0.2387453169 -0.2106269598 1779 1311867229.7854330540 0.0604300424 0.0540742921 0.0698473677 0.0055943660 0.0529950000 402585533 0 402718720 -0.0288893003 0.2392275184 -0.2118038088 1780 1311867229.8184831142 0.0608863011 0.0540781190 0.0698473677 0.0055928442 0.0425410000 402588617 0 402718720 -0.0295354929 0.2383937240 -0.2120359093 1781 1311867229.8494279385 0.0606509969 0.0540818096 0.0698473677 0.0055916680 0.0393530000 402591829 0 402718720 -0.0295810942 0.2367106825 -0.2125116587 1782 1311867229.8853340149 0.0593758486 0.0540847804 0.0698473677 0.0055902073 0.0389960000 402595057 0 402718720 -0.0289694518 0.2345592082 -0.2141742110 1783 1311867229.9183139801 0.0588158667 0.0540874339 0.0698473677 0.0055895241 0.0493520000 402598221 0 402718720 -0.0316485986 0.2335864455 -0.2157593817 1784 1311867229.9534161091 0.0601251461 0.0540908183 0.0698473677 0.0055903364 0.0392990000 402601753 0 402718720 -0.0305958111 0.2311655581 -0.2145281881 1785 1311867229.9877750874 0.0612702966 0.0540948404 0.0698473677 0.0055891909 0.0529950000 402604869 0 402718720 -0.0298329853 0.2316370606 -0.2144300491 1786 1311867230.0194880962 0.0598983169 0.0540980898 0.0698473677 0.0055877335 0.0413200000 402607913 0 402718720 -0.0312469956 0.2291232646 -0.2163864225 1787 1311867230.0512609482 0.0593658276 0.0541010376 0.0698473677 0.0055862898 0.0394380000 402611181 0 402718720 -0.0311901867 0.2271144688 -0.2172065228 1788 1311867230.0876040459 0.0617345497 0.0541053069 0.0698473677 0.0055854297 0.0381680000 402614249 0 402718720 -0.0323154032 0.2267077714 -0.2160478383 1789 1311867230.1212029457 0.0598064847 0.0541084937 0.0698473677 0.0055843793 0.0415580000 402617709 0 402718720 -0.0328604877 0.2227514833 -0.2178766876 1790 1311867230.1508131027 0.0599261299 0.0541117438 0.0698473677 0.0055828598 0.0421770000 402620825 0 402718720 -0.0328842625 0.2210136354 -0.2182471007 1791 1311867230.1872301102 0.0581668951 0.0541140080 0.0698473677 0.0055885118 0.0513030000 402624085 0 402718720 -0.0322073959 0.2194457948 -0.2203786820 1792 1311867230.2194790840 0.0576798096 0.0541159978 0.0698473677 0.0055958949 0.0414400000 402627297 0 402718720 -0.0333518609 0.2180368602 -0.2222386897 1793 1311867230.2494208813 0.0584134012 0.0541183946 0.0698473677 0.0056003817 0.0500360000 402630597 0 402718720 -0.0340337306 0.2171318978 -0.2217605114 1794 1311867230.2894790173 0.0593053065 0.0541212858 0.0698473677 0.0056049880 0.0413880000 402633697 0 402718720 -0.0342709348 0.2150744349 -0.2219965011 1795 1311867230.3189430237 0.0584975816 0.0541237239 0.0698473677 0.0056035195 0.0412170000 402636813 0 402718720 -0.0348470509 0.2133701891 -0.2234526575 1796 1311867230.3552010059 0.0591252260 0.0541265087 0.0698473677 0.0056020821 0.0516500000 402640065 0 402718720 -0.0329550728 0.2128338814 -0.2236016989 1797 1311867230.3913140297 0.0588988326 0.0541291644 0.0698473677 0.0056007784 0.0507520000 402643413 0 402718720 -0.0353450365 0.2107806653 -0.2245411724 1798 1311867230.4169929028 0.0588817596 0.0541318077 0.0698473677 0.0055993480 0.0403760000 402646313 0 402718720 -0.0344848745 0.2099236846 -0.2250586003 1799 1311867230.4538938999 0.0586620122 0.0541343258 0.0698473677 0.0055978754 0.0408950000 402649901 0 402718720 -0.0346348956 0.2095075846 -0.2261323184 1800 1311867230.4892110825 0.0574773364 0.0541361831 0.0698473677 0.0056089555 0.0465490000 403298909 0 402718720 -0.0343638994 0.2076196969 -0.2273250222 1801 1311867230.5216429234 0.0571886227 0.0541378779 0.0698473677 0.0056077779 0.1401030000 403263497 0 402718720 -0.0345874205 0.2060075998 -0.2277166545 1802 1311867230.5564150810 0.0559771508 0.0541388986 0.0698473677 0.0056175186 0.1350260000 403266325 0 402718720 -0.0354095921 0.2053017765 -0.2300011516 1803 1311867230.5930590630 0.0572260432 0.0541406108 0.0698473677 0.0056160476 0.1242420000 403296089 0 402718720 -0.0355607606 0.2052396685 -0.2296350896 1804 1311867230.6184151173 0.0569047146 0.0541421430 0.0698473677 0.0056146668 0.1056450000 413779793 0 402718720 -0.0352050476 0.2021919042 -0.2295544147 1805 1311867230.6534399986 0.0563009866 0.0541433391 0.0698473677 0.0056133420 0.1041890000 413527065 0 402718720 -0.0355041772 0.2019177377 -0.2308346629 1806 1311867230.6920781136 0.0571745224 0.0541450175 0.0698473677 0.0056121092 0.0525680000 413653261 0 402718720 -0.0372207612 0.2008287013 -0.2305006236 1807 1311867230.7185189724 0.0546890795 0.0541453186 0.0698473677 0.0056112131 0.1395370000 411954865 0 402718720 -0.0356906801 0.1982508451 -0.2323800027 1808 1311867230.7529120445 0.0545742959 0.0541455558 0.0698473677 0.0056100552 0.0436880000 403274333 0 402718720 -0.0377754197 0.1979402751 -0.2331080735 1809 1311867230.7871611118 0.0543709472 0.0541456804 0.0698473677 0.0056171359 0.0416930000 403278089 0 402718720 -0.0388997868 0.1969193071 -0.2326350510 1810 1311867230.8195741177 0.0547569990 0.0541460182 0.0698473677 0.0056230667 0.0409880000 403280797 0 402718720 -0.0378038064 0.1968402565 -0.2330360115 1811 1311867230.8534181118 0.0545754358 0.0541462553 0.0698473677 0.0056216073 0.0511420000 403284193 0 402718720 -0.0378681049 0.1965674758 -0.2333022952 1812 1311867230.8890159130 0.0540259182 0.0541461889 0.0698473677 0.0056203841 0.0407400000 403287565 0 402718720 -0.0393328220 0.1948132515 -0.2336320281 1813 1311867230.9176509380 0.0539685711 0.0541460909 0.0698473677 0.0056189723 0.0404860000 403290593 0 402718720 -0.0389963016 0.1951097250 -0.2338316888 1814 1311867230.9559168816 0.0550699495 0.0541466002 0.0698473677 0.0056176174 0.0601570000 403293789 0 402718720 -0.0399410278 0.1947072297 -0.2330151647 1815 1311867230.9881010056 0.0549345240 0.0541470343 0.0698473677 0.0056167703 0.0407090000 403296969 0 402718720 -0.0419655405 0.1949098110 -0.2341025323 1816 1311867231.0166280270 0.0549843200 0.0541474954 0.0698473677 0.0056160385 0.0523130000 403300253 0 402718720 -0.0401807353 0.1932031512 -0.2336378247 1817 1311867231.0603969097 0.0553410500 0.0541481523 0.0698473677 0.0056148512 0.0446830000 403303385 0 402718720 -0.0407406688 0.1922389567 -0.2338915765 1818 1311867231.0868620872 0.0547599345 0.0541484888 0.0698473677 0.0056136656 0.0514050000 403306501 0 402718720 -0.0404132977 0.1912891120 -0.2346694469 1819 1311867231.1221020222 0.0540287085 0.0541484229 0.0698473677 0.0056122350 0.0409980000 403309753 0 402718720 -0.0408741012 0.1896802634 -0.2360263616 1820 1311867231.1523799896 0.0552522428 0.0541490294 0.0698473677 0.0056144343 0.0558650000 403312789 0 402718720 -0.0417002812 0.1883929521 -0.2352333516 1821 1311867231.1860070229 0.0547823459 0.0541493772 0.0698473677 0.0056129160 0.0399210000 403316057 0 402718720 -0.0420371592 0.1873637885 -0.2364325523 1822 1311867231.2188270092 0.0549815483 0.0541498339 0.0698473677 0.0056121739 0.0519790000 403319077 0 402718720 -0.0417497493 0.1861527413 -0.2368209660 1823 1311867231.2522621155 0.0548969135 0.0541502437 0.0698473677 0.0056126030 0.0537700000 403322265 0 402718720 -0.0431895778 0.1853361577 -0.2378988564 1824 1311867231.2864110470 0.0550560765 0.0541507404 0.0698473677 0.0056120574 0.0398140000 403325405 0 402718720 -0.0424216911 0.1832913011 -0.2381017208 1825 1311867231.3215939999 0.0551520400 0.0541512890 0.0698473677 0.0056107044 0.0391610000 403328953 0 402718720 -0.0437825099 0.1819545180 -0.2385710627 1826 1311867231.3525509834 0.0552913211 0.0541519134 0.0698473677 0.0056094747 0.0423550000 403331997 0 402718720 -0.0443599783 0.1805544645 -0.2386926413 1827 1311867231.3874650002 0.0537868142 0.0541517135 0.0698473677 0.0056082936 0.0432230000 403335233 0 402718720 -0.0445104018 0.1794657260 -0.2405383438 1828 1311867231.4187040329 0.0545105524 0.0541519098 0.0698473677 0.0056072370 0.0534440000 403338253 0 402718720 -0.0438516736 0.1797355711 -0.2401815355 1829 1311867231.4542400837 0.0541799888 0.0541519252 0.0698473677 0.0056058778 0.0411170000 403341593 0 402718720 -0.0439036228 0.1782346368 -0.2401483357 1830 1311867231.4867990017 0.0535298698 0.0541515853 0.0698473677 0.0056045475 0.0528960000 403344949 0 402718720 -0.0436037406 0.1769279391 -0.2401985824 1831 1311867231.5193030834 0.0536463335 0.0541513093 0.0698473677 0.0056035750 0.0393050000 403347777 0 402718720 -0.0464337021 0.1771897078 -0.2406740636 1832 1311867231.5524148941 0.0539907739 0.0541512217 0.0698473677 0.0056026348 0.0474490000 403351085 0 402718720 -0.0457142815 0.1761907786 -0.2401558608 1833 1311867231.5855851173 0.0527031124 0.0541504317 0.0698473677 0.0056076436 0.0396740000 403354409 0 402718720 -0.0463230535 0.1748570055 -0.2409326732 1834 1311867231.6210820675 0.0532135479 0.0541499208 0.0698473677 0.0056187637 0.0425000000 403357677 0 402718720 -0.0479361713 0.1747158468 -0.2416656762 1835 1311867231.6522169113 0.0537390411 0.0541496969 0.0698473677 0.0056176467 0.0424350000 403361049 0 402718720 -0.0460306555 0.1725029498 -0.2404641956 1836 1311867231.6880500317 0.0537618920 0.0541494857 0.0698473677 0.0056162602 0.0427550000 403363877 0 402718720 -0.0468716621 0.1712460965 -0.2405162454 1837 1311867231.7208089828 0.0522242561 0.0541484377 0.0698473677 0.0056156999 0.0397010000 403367017 0 402718720 -0.0470554307 0.1703065038 -0.2424999177 1838 1311867231.7523078918 0.0535972416 0.0541481378 0.0698473677 0.0056176270 0.0508910000 403370565 0 402718720 -0.0466131717 0.1691282541 -0.2415913343 1839 1311867231.7860589027 0.0531658344 0.0541476036 0.0698473677 0.0056161493 0.0523810000 403373649 0 402718720 -0.0470437817 0.1681989133 -0.2429502010 1840 1311867231.8202130795 0.0532081872 0.0541470931 0.0698473677 0.0056155563 0.0417690000 403376533 0 402718720 -0.0463757217 0.1681830585 -0.2439206839 1841 1311867231.8521840572 0.0542855226 0.0541471683 0.0698473677 0.0056143490 0.0422720000 403380073 0 402718720 -0.0468606576 0.1679652333 -0.2438442856 1842 1311867231.8857500553 0.0531833097 0.0541466450 0.0698473677 0.0056137795 0.0394980000 403383013 0 402718720 -0.0474355593 0.1641648114 -0.2442916781 1843 1311867231.9208559990 0.0532742701 0.0541461716 0.0698473677 0.0056124453 0.0424660000 403386465 0 402718720 -0.0474176481 0.1624662876 -0.2446645498 1844 1311867231.9533181190 0.0530627295 0.0541455841 0.0698473677 0.0056112849 0.0535900000 403389813 0 402718720 -0.0473143458 0.1618878394 -0.2457367629 1845 1311867231.9870491028 0.0535414256 0.0541452566 0.0698473677 0.0056099900 0.0521880000 403392761 0 402718720 -0.0480296947 0.1603033841 -0.2458837032 1846 1311867232.0202860832 0.0529534258 0.0541446110 0.0698473677 0.0056089516 0.0392630000 403395725 0 402718720 -0.0454177782 0.1586970985 -0.2465752959 1847 1311867232.0522420406 0.0524127670 0.0541436734 0.0698473677 0.0056076483 0.0411700000 403399209 0 402718720 -0.0467490330 0.1581313014 -0.2479243129 1848 1311867232.0878489017 0.0522548147 0.0541426512 0.0698473677 0.0056063091 0.0427980000 403402341 0 402718720 -0.0458702967 0.1566365510 -0.2482898235 1849 1311867232.1203238964 0.0528802127 0.0541419685 0.0698473677 0.0056074731 0.0537530000 403405473 0 402718720 -0.0475993529 0.1547329575 -0.2483837754 1850 1311867232.1545510292 0.0535627306 0.0541416554 0.0698473677 0.0056065188 0.0393320000 403408773 0 402718720 -0.0470369458 0.1552073509 -0.2481818795 1851 1311867232.1846179962 0.0531599857 0.0541411250 0.0698473677 0.0056058716 0.0517760000 403411817 0 402718720 -0.0452137776 0.1540976763 -0.2487774789 1852 1311867232.2209780216 0.0531530418 0.0541405915 0.0698473677 0.0056048479 0.0387410000 403415093 0 402718720 -0.0458043329 0.1519093663 -0.2489588410 1853 1311867232.2531120777 0.0525643006 0.0541397408 0.0698473677 0.0056034225 0.0395160000 403418553 0 402718720 -0.0476265550 0.1514807940 -0.2505397797 1854 1311867232.2844479084 0.0529807396 0.0541391157 0.0698473677 0.0056025987 0.0407830000 403421437 0 402718720 -0.0483669713 0.1495210379 -0.2501856983 1855 1311867232.3209791183 0.0524557903 0.0541382082 0.0698473677 0.0056012542 0.0423590000 403424697 0 402718720 -0.0476757288 0.1493964195 -0.2514111698 1856 1311867232.3544659615 0.0518955849 0.0541369999 0.0698473677 0.0056002381 0.0426210000 403428005 0 402718720 -0.0457209907 0.1508190036 -0.2533090413 1857 1311867232.3858909607 0.0529497191 0.0541363606 0.0698473677 0.0055989022 0.0542450000 403431089 0 402718720 -0.0468431450 0.1475121081 -0.2516911924 1858 1311867232.4203910828 0.0525278077 0.0541354948 0.0698473677 0.0055980640 0.0428460000 403434437 0 402718720 -0.0483750664 0.1466230154 -0.2528379858 1859 1311867232.4544560909 0.0514107794 0.0541340291 0.0698473677 0.0055969575 0.0403190000 403437345 0 402718720 -0.0463180467 0.1463587433 -0.2542689741 1860 1311867232.4846010208 0.0513662063 0.0541325411 0.0698473677 0.0056006322 0.0401750000 403440693 0 402718720 -0.0478498489 0.1452849805 -0.2538415790 1861 1311867232.5203030109 0.0515257455 0.0541311403 0.0698473677 0.0056003649 0.0427920000 403443953 0 402718720 -0.0467981622 0.1445809454 -0.2542230189 1862 1311867232.5550050735 0.0495905951 0.0541287018 0.0698473677 0.0056019311 0.0395470000 403447093 0 402718720 -0.0467962399 0.1437697113 -0.2555312812 1863 1311867232.5844318867 0.0515895896 0.0541273389 0.0698473677 0.0056025591 0.0493900000 403450065 0 402718720 -0.0458242744 0.1428235471 -0.2541467547 1864 1311867232.6201601028 0.0520809814 0.0541262410 0.0698473677 0.0056011838 0.0429180000 403453549 0 402718720 -0.0461310148 0.1418330967 -0.2540231645 1865 1311867232.6554861069 0.0522090420 0.0541252131 0.0698473677 0.0056011142 0.0422320000 403456705 0 402718720 -0.0467017069 0.1421127617 -0.2548491359 1866 1311867232.6850490570 0.0515721589 0.0541238449 0.0698473677 0.0056005745 0.0428260000 403459541 0 402718720 -0.0448426902 0.1388779581 -0.2544782758 1867 1311867232.7210319042 0.0529069602 0.0541231931 0.0698473677 0.0055995742 0.0393490000 403462993 0 402718720 -0.0457868278 0.1386494488 -0.2539644241 1868 1311867232.7539520264 0.0514946096 0.0541217859 0.0698473677 0.0055982822 0.0539160000 403465797 0 402718720 -0.0448180847 0.1372974515 -0.2554218173 1869 1311867232.7885808945 0.0524841510 0.0541209097 0.0698473677 0.0055969104 0.0414050000 403469193 0 402718720 -0.0460137427 0.1363969445 -0.2551597953 1870 1311867232.8206169605 0.0518337637 0.0541196866 0.0698473677 0.0055958963 0.0417550000 403472349 0 402718720 -0.0473085344 0.1319221705 -0.2549862266 1871 1311867232.8539369106 0.0516328253 0.0541183575 0.0698473677 0.0055945338 0.0390090000 403475753 0 402718720 -0.0456504785 0.1315592378 -0.2556361854 1872 1311867232.8882710934 0.0515508093 0.0541169859 0.0698473677 0.0055932276 0.0419950000 403478717 0 402718720 -0.0452426001 0.1316674203 -0.2568944991 1873 1311867232.9203770161 0.0513149612 0.0541154899 0.0698473677 0.0055925971 0.0415200000 403482065 0 402718720 -0.0457291231 0.1275474578 -0.2562312782 1874 1311867232.9559900761 0.0509700254 0.0541138114 0.0698473677 0.0055914287 0.0409310000 403485325 0 402718720 -0.0446165390 0.1273756176 -0.2574895024 1875 1311867232.9890038967 0.0508421808 0.0541120666 0.0698473677 0.0055905446 0.0511180000 403488689 0 402718720 -0.0430667475 0.1280549467 -0.2587619424 1876 1311867233.0212259293 0.0516163930 0.0541107362 0.0698473677 0.0055898327 0.0394180000 403491733 0 402718720 -0.0438332893 0.1256581843 -0.2573407888 1877 1311867233.0569291115 0.0502594262 0.0541086844 0.0698473677 0.0055888077 0.0384540000 403494617 0 402718720 -0.0446519405 0.1239762157 -0.2587060928 1878 1311867233.0943200588 0.0517340153 0.0541074199 0.0698473677 0.0055882308 0.0414500000 403498445 0 402718720 -0.0429938883 0.1246396154 -0.2577178180 1879 1311867233.1241600513 0.0506728478 0.0541055921 0.0698473677 0.0055875902 0.0392080000 403501057 0 402718720 -0.0444501340 0.1224768087 -0.2585844100 1880 1311867233.1530799866 0.0498509966 0.0541033290 0.0698473677 0.0055880828 0.0410040000 403504045 0 402718720 -0.0441190638 0.1210035086 -0.2589995563 1881 1311867233.1887679100 0.0502221957 0.0541012656 0.0698473677 0.0055877995 0.0537840000 403507833 0 402718720 -0.0432371870 0.1211715564 -0.2595399618 1882 1311867233.2210481167 0.0505875535 0.0540993986 0.0698473677 0.0055863288 0.0392470000 403510725 0 402718720 -0.0427856110 0.1197008342 -0.2588368952 1883 1311867233.2590179443 0.0518505424 0.0540982043 0.0698473677 0.0055852140 0.0406650000 403514057 0 402718720 -0.0435282700 0.1165010855 -0.2568543553 1884 1311867233.2899589539 0.0497364365 0.0540958892 0.0698473677 0.0055841268 0.0405390000 403517045 0 402718720 -0.0443976857 0.1162036955 -0.2598243654 1885 1311867233.3212211132 0.0517688580 0.0540946547 0.0698473677 0.0055832270 0.0405190000 403520257 0 402718720 -0.0441879258 0.1152921543 -0.2573282123 1886 1311867233.3533849716 0.0506243445 0.0540928146 0.0698473677 0.0055823700 0.0519610000 403523413 0 402718720 -0.0451926589 0.1115514785 -0.2581585646 1887 1311867233.3884561062 0.0511870272 0.0540912747 0.0698473677 0.0055837936 0.0514900000 403526609 0 402718720 -0.0443827212 0.1113148332 -0.2584382892 1888 1311867233.4236669540 0.0497785024 0.0540889904 0.0698473677 0.0055907265 0.0399110000 403529813 0 402718720 -0.0433865972 0.1100729555 -0.2601038218 1889 1311867233.4522700310 0.0505745299 0.0540871299 0.0698473677 0.0055909681 0.0469260000 404110237 0 402718720 -0.0449181572 0.1070621088 -0.2589984238 1890 1311867233.4881610870 0.0506653227 0.0540853195 0.0698473677 0.0055941912 0.1335050000 404057493 0 402718720 -0.0437489264 0.1061230153 -0.2591557503 1891 1311867233.5201199055 0.0508951843 0.0540836325 0.0698473677 0.0055950084 0.1306580000 404058085 0 402718720 -0.0432219133 0.1069336385 -0.2603244185 1892 1311867233.5526270866 0.0498930216 0.0540814175 0.0698473677 0.0055948852 0.1197920000 404367265 0 402718720 -0.0431044176 0.1035155803 -0.2600551844 1893 1311867233.5890851021 0.0503365956 0.0540794393 0.0698473677 0.0055936510 0.1156070000 413954873 0 402718720 -0.0438690968 0.1037194803 -0.2603740990 1894 1311867233.6202619076 0.0505849570 0.0540775943 0.0698473677 0.0055921977 0.0992080000 414081009 0 402718720 -0.0432919040 0.1022074074 -0.2595628798 1895 1311867233.6539080143 0.0495164692 0.0540751873 0.0698473677 0.0055927351 0.0513140000 414221301 0 402718720 -0.0449106880 0.1008024290 -0.2608965337 1896 1311867233.6879289150 0.0492454395 0.0540726400 0.0698473677 0.0055914756 0.1377090000 412532057 0 402718720 -0.0444269814 0.1002746671 -0.2611643672 1897 1311867233.7197790146 0.0484957173 0.0540697001 0.0698473677 0.0055901425 0.0561080000 404070941 0 402718720 -0.0431709737 0.1000989377 -0.2622164786 1898 1311867233.7577540874 0.0490596071 0.0540670605 0.0698473677 0.0055892042 0.0423680000 404074721 0 402718720 -0.0448113345 0.0988683403 -0.2614452243 1899 1311867233.7896089554 0.0497464798 0.0540647853 0.0698473677 0.0055887664 0.0415830000 404077501 0 402718720 -0.0448892117 0.0986359343 -0.2609237134 1900 1311867233.8221189976 0.0501421466 0.0540627207 0.0698473677 0.0055888962 0.0412130000 404081025 0 402718720 -0.0448575616 0.0977662802 -0.2602748275 1901 1311867233.8562450409 0.0499639027 0.0540605646 0.0698473677 0.0055875930 0.0416280000 404083981 0 402718720 -0.0454077385 0.0954099447 -0.2596473694 1902 1311867233.8885691166 0.0490661673 0.0540579387 0.0698473677 0.0055864427 0.0409180000 404087273 0 402718720 -0.0453388803 0.0959931165 -0.2618083954 1903 1311867233.9203450680 0.0493320785 0.0540554554 0.0698473677 0.0055855877 0.0408180000 404090613 0 402718720 -0.0448625311 0.0953160226 -0.2613135874 1904 1311867233.9552910328 0.0470520705 0.0540517771 0.0698473677 0.0055847374 0.0561920000 404093937 0 402718720 -0.0469267815 0.0926589146 -0.2633798420 1905 1311867233.9885900021 0.0486524925 0.0540489428 0.0698473677 0.0055835688 0.0400040000 404096749 0 402718720 -0.0465339348 0.0919620693 -0.2614472806 1906 1311867234.0205829144 0.0490320437 0.0540463107 0.0698473677 0.0055822210 0.0398690000 404099705 0 402718720 -0.0470859520 0.0923558325 -0.2619768381 1907 1311867234.0566239357 0.0489343591 0.0540436301 0.0698473677 0.0055808886 0.0418580000 404103213 0 402718720 -0.0473819152 0.0901403055 -0.2615780532 1908 1311867234.0907170773 0.0487596616 0.0540408607 0.0698473677 0.0055797034 0.0419890000 404106345 0 402718720 -0.0463906042 0.0887351185 -0.2616290450 1909 1311867234.1214520931 0.0490491204 0.0540382458 0.0698473677 0.0055783949 0.0515590000 404109573 0 402718720 -0.0466013253 0.0880270749 -0.2616868913 1910 1311867234.1561689377 0.0507288575 0.0540365132 0.0698473677 0.0055769771 0.0543700000 404113001 0 402718720 -0.0456567518 0.0859133080 -0.2593967915 1911 1311867234.1892559528 0.0515209846 0.0540351968 0.0698473677 0.0055760459 0.0388390000 404115717 0 402718720 -0.0492662489 0.0846688896 -0.2590651214 1912 1311867234.2203600407 0.0508005805 0.0540335051 0.0698473677 0.0055751023 0.0419300000 404119473 0 402718720 -0.0477430522 0.0844983682 -0.2606508434 1913 1311867234.2588930130 0.0517914966 0.0540323331 0.0698473677 0.0055740000 0.0390570000 404122341 0 402718720 -0.0481666327 0.0848447233 -0.2605840564 1914 1311867234.2895319462 0.0499137528 0.0540301813 0.0698473677 0.0055726906 0.0415880000 404125569 0 402718720 -0.0510375090 0.0814490318 -0.2612099648 1915 1311867234.3213200569 0.0487930067 0.0540274465 0.0698473677 0.0055761073 0.0598640000 404128861 0 402718720 -0.0491716936 0.0811098069 -0.2620295584 1916 1311867234.3570129871 0.0494868234 0.0540250766 0.0698473677 0.0055748588 0.0625370000 404132193 0 402718720 -0.0504242517 0.0809179544 -0.2613600791 1917 1311867234.3885769844 0.0496222563 0.0540227799 0.0698473677 0.0055735884 0.0386090000 404135277 0 402718720 -0.0524467863 0.0788734779 -0.2601094246 1918 1311867234.4204909801 0.0492992029 0.0540203171 0.0698473677 0.0055722034 0.0420250000 404138481 0 402718720 -0.0519464649 0.0790276527 -0.2606647611 1919 1311867234.4579920769 0.0512449443 0.0540188709 0.0698473677 0.0055716872 0.0393030000 404141621 0 402718720 -0.0505402312 0.0802680477 -0.2591398954 1920 1311867234.4878959656 0.0513550714 0.0540174835 0.0698473677 0.0055759959 0.0426300000 404144897 0 402718720 -0.0525468960 0.0765788108 -0.2571332455 1921 1311867234.5201239586 0.0490067154 0.0540148751 0.0698473677 0.0055747059 0.0481070000 404147805 0 402718720 -0.0539472923 0.0764046460 -0.2605129778 1922 1311867234.5594279766 0.0498380028 0.0540127019 0.0698473677 0.0055738215 0.0481920000 404151241 0 402718720 -0.0512806959 0.0771696866 -0.2600222826 1923 1311867234.5882380009 0.0498008132 0.0540105116 0.0698473677 0.0055733804 0.0464420000 404154461 0 402718720 -0.0516616441 0.0762318149 -0.2594461739 1924 1311867234.6204199791 0.0490835831 0.0540079508 0.0698473677 0.0055720485 0.0384050000 404157449 0 402718720 -0.0521288924 0.0733679309 -0.2586452067 1925 1311867234.6590909958 0.0519040413 0.0540068579 0.0698473677 0.0055725193 0.0394020000 404161005 0 402718720 -0.0534530990 0.0744913965 -0.2557987571 1926 1311867234.6880459785 0.0498013198 0.0540046743 0.0698473677 0.0055717316 0.0392590000 404163785 0 402718720 -0.0525336787 0.0736362562 -0.2574732900 1927 1311867234.7198779583 0.0489571318 0.0540020549 0.0698473677 0.0055708416 0.0420380000 404167205 0 402718720 -0.0528986305 0.0718644708 -0.2571673989 1928 1311867234.7586181164 0.0476743281 0.0539987729 0.0698473677 0.0055695041 0.0668640000 404170289 0 402718720 -0.0517173670 0.0716160536 -0.2574942410 1929 1311867234.7882609367 0.0479574725 0.0539956411 0.0698473677 0.0055750353 0.0420770000 404173437 0 402718720 -0.0515493713 0.0718472302 -0.2559613287 1930 1311867234.8206560612 0.0480783321 0.0539925751 0.0698473677 0.0055737724 0.0414430000 404176841 0 402718720 -0.0523216166 0.0710740760 -0.2542528808 1931 1311867234.8590250015 0.0492859818 0.0539901378 0.0698473677 0.0055729101 0.0516170000 404179717 0 402718720 -0.0523181669 0.0724774525 -0.2528733909 1932 1311867234.8881230354 0.0493930988 0.0539877583 0.0698473677 0.0055715211 0.0390980000 404182777 0 402718720 -0.0494807772 0.0734716654 -0.2525251210 1933 1311867234.9204928875 0.0477438904 0.0539845282 0.0698473677 0.0055708121 0.0586170000 404186397 0 402718720 -0.0501049496 0.0710416436 -0.2525900602 1934 1311867234.9566090107 0.0487611555 0.0539818274 0.0698473677 0.0055695659 0.0419320000 404189529 0 402718720 -0.0493495427 0.0700209960 -0.2506819367 1935 1311867234.9904088974 0.0516381338 0.0539806162 0.0698473677 0.0055691174 0.0521130000 404192813 0 402718720 -0.0511010401 0.0711428970 -0.2485591471 1936 1311867235.0205988884 0.0492808037 0.0539781886 0.0698473677 0.0055691478 0.0387000000 404195841 0 402718720 -0.0505848527 0.0681092292 -0.2501435876 1937 1311867235.0563809872 0.0494494140 0.0539758505 0.0698473677 0.0055685168 0.0417400000 404199101 0 402718720 -0.0509584770 0.0679681897 -0.2507031858 1938 1311867235.0911149979 0.0496261716 0.0539736061 0.0698473677 0.0055671477 0.0387910000 404202385 0 402718720 -0.0505913720 0.0674627945 -0.2506092191 1939 1311867235.1208140850 0.0497095473 0.0539714070 0.0698473677 0.0055658631 0.0398710000 404205597 0 402718720 -0.0514068417 0.0654126704 -0.2497121394 1940 1311867235.1564071178 0.0505930483 0.0539696656 0.0698473677 0.0055665026 0.0396700000 404208545 0 402718720 -0.0515365340 0.0668647364 -0.2495742142 1941 1311867235.1885681152 0.0497695096 0.0539675017 0.0698473677 0.0055662154 0.0399190000 404211885 0 402718720 -0.0527997650 0.0660142452 -0.2502021194 1942 1311867235.2202088833 0.0504320860 0.0539656812 0.0698473677 0.0055648160 0.0397690000 404215033 0 402718720 -0.0537825748 0.0648949295 -0.2487547696 1943 1311867235.2576260567 0.0491436906 0.0539631995 0.0698473677 0.0055639552 0.0399240000 404217989 0 402718720 -0.0528469756 0.0653687194 -0.2507891059 1944 1311867235.2899661064 0.0503778458 0.0539613551 0.0698473677 0.0055640982 0.0397590000 404221321 0 402718720 -0.0540232360 0.0646524355 -0.2486789525 1945 1311867235.3247830868 0.0504823662 0.0539595665 0.0698473677 0.0055630086 0.0391990000 404224645 0 402718720 -0.0556310751 0.0646219254 -0.2487144917 1946 1311867235.3567800522 0.0483703166 0.0539566943 0.0698473677 0.0055784319 0.0408550000 404228049 0 402718720 -0.0555001870 0.0632740930 -0.2498764098 1947 1311867235.3886280060 0.0506659001 0.0539550041 0.0698473677 0.0055918813 0.0418450000 404230941 0 402718720 -0.0552789271 0.0635026842 -0.2472261935 1948 1311867235.4246189594 0.0499463268 0.0539529463 0.0698473677 0.0055914442 0.0391020000 404234009 0 402718720 -0.0559117422 0.0628272668 -0.2469119877 1949 1311867235.4564850330 0.0489504226 0.0539503795 0.0698473677 0.0055911148 0.0396810000 404237285 0 402718720 -0.0567487702 0.0634627491 -0.2480057329 1950 1311867235.4897930622 0.0492115989 0.0539479494 0.0698473677 0.0055912376 0.0394190000 404240625 0 402718720 -0.0568935424 0.0630025864 -0.2461511344 1951 1311867235.5240719318 0.0497019142 0.0539457731 0.0698473677 0.0055901390 0.0416350000 404243701 0 402718720 -0.0573328957 0.0635725185 -0.2452345639 1952 1311867235.5577290058 0.0496794730 0.0539435875 0.0698473677 0.0055892298 0.0418530000 404246593 0 402718720 -0.0564669631 0.0640383735 -0.2446315885 1953 1311867235.5880639553 0.0499597490 0.0539415476 0.0698473677 0.0055879246 0.0786040000 404249933 0 402718720 -0.0565817393 0.0648584068 -0.2445171773 1954 1311867235.6249940395 0.0492861308 0.0539391651 0.0698473677 0.0055870222 0.0394910000 404253521 0 402718720 -0.0573017262 0.0611349717 -0.2430157661 1955 1311867235.6563270092 0.0500971638 0.0539371999 0.0698473677 0.0055863152 0.0394730000 404256165 0 402718720 -0.0569639094 0.0625658557 -0.2429073751 1956 1311867235.6885619164 0.0495289192 0.0539349462 0.0698473677 0.0055856013 0.0423390000 404259329 0 402718720 -0.0566531084 0.0627508685 -0.2438941449 1957 1311867235.7241950035 0.0506307781 0.0539332578 0.0698473677 0.0055848415 0.0417970000 404262717 0 402718720 -0.0596177205 0.0606304966 -0.2412864268 1958 1311867235.7561719418 0.0494922698 0.0539309896 0.0698473677 0.0055842246 0.0640370000 404266049 0 402718720 -0.0583901480 0.0627333969 -0.2435305566 1959 1311867235.7903280258 0.0498537458 0.0539289084 0.0698473677 0.0055839637 0.0515630000 404269197 0 402718720 -0.0582197085 0.0610425845 -0.2415632457 1960 1311867235.8249480724 0.0494067706 0.0539266011 0.0698473677 0.0055828280 0.0413800000 404272337 0 402718720 -0.0584580451 0.0588934049 -0.2401685715 1961 1311867235.8562169075 0.0511420034 0.0539251812 0.0698473677 0.0055842854 0.0397510000 404275413 0 402718720 -0.0586165562 0.0618098527 -0.2391830534 1962 1311867235.8881049156 0.0505674966 0.0539234698 0.0698473677 0.0055828921 0.0396690000 404278577 0 402718720 -0.0609855503 0.0608745068 -0.2388265133 1963 1311867235.9239900112 0.0503454804 0.0539216471 0.0698473677 0.0055818692 0.0392080000 404281717 0 402718720 -0.0582733229 0.0603419580 -0.2377157807 1964 1311867235.9563760757 0.0516310073 0.0539204808 0.0698473677 0.0055826172 0.0780320000 404285049 0 402718720 -0.0596398190 0.0619657859 -0.2369847745 1965 1311867235.9890949726 0.0502462611 0.0539186109 0.0698473677 0.0055827632 0.0403470000 404288221 0 402718720 -0.0603948385 0.0598748922 -0.2367446572 1966 1311867236.0250449181 0.0505463332 0.0539168956 0.0698473677 0.0055814106 0.0499450000 404291481 0 402718720 -0.0599143878 0.0593057051 -0.2353983372 1967 1311867236.0599400997 0.0507928729 0.0539153074 0.0698473677 0.0055800152 0.0397030000 404294621 0 402718720 -0.0599451810 0.0609865561 -0.2353948951 1968 1311867236.0884859562 0.0515560992 0.0539141086 0.0698473677 0.0055786360 0.0511530000 404297593 0 402718720 -0.0617741495 0.0601187870 -0.2332517058 1969 1311867236.1247038841 0.0510536954 0.0539126559 0.0698473677 0.0055772557 0.0500130000 404301101 0 402718720 -0.0612294823 0.0596565902 -0.2325087786 1970 1311867236.1581289768 0.0518218912 0.0539115946 0.0698473677 0.0055766504 0.0396580000 404304121 0 402718720 -0.0613064989 0.0597364753 -0.2308396101 1971 1311867236.1901528835 0.0516512245 0.0539104478 0.0698473677 0.0055755316 0.0402390000 404307549 0 402718720 -0.0632804260 0.0603931881 -0.2301644832 1972 1311867236.2242329121 0.0505563915 0.0539087470 0.0698473677 0.0055742075 0.0402680000 404310625 0 402718720 -0.0650665462 0.0595509708 -0.2297527492 1973 1311867236.2599489689 0.0507832244 0.0539071628 0.0698473677 0.0055734181 0.0387570000 404313629 0 402718720 -0.0643660799 0.0612227060 -0.2290446162 1974 1311867236.2890419960 0.0491023846 0.0539047288 0.0698473677 0.0055721211 0.0393870000 404316985 0 402718720 -0.0647175759 0.0599709153 -0.2292793989 1975 1311867236.3262441158 0.0503756516 0.0539029419 0.0698473677 0.0055708042 0.0756090000 404319917 0 402718720 -0.0653486997 0.0594956540 -0.2261999398 1976 1311867236.3568809032 0.0509770624 0.0539014612 0.0698473677 0.0055699624 0.0391850000 404323385 0 402718720 -0.0645252243 0.0599978864 -0.2249588370 1977 1311867236.3897418976 0.0486052260 0.0538987823 0.0698473677 0.0055687218 0.0391610000 404326277 0 402718720 -0.0658342689 0.0581313558 -0.2254912555 1978 1311867236.4243390560 0.0488573126 0.0538962335 0.0698473677 0.0055692994 0.0395190000 404329481 0 402718720 -0.0656958744 0.0588757060 -0.2239030004 1979 1311867236.4566040039 0.0500849783 0.0538943076 0.0698473677 0.0055680056 0.0398200000 404332621 0 402718720 -0.0650936514 0.0587752871 -0.2209357619 1980 1311867236.4936130047 0.0504941531 0.0538925904 0.0698473677 0.0055730396 0.0467250000 404336089 0 402718720 -0.0658568069 0.0573472790 -0.2183889896 1981 1311867236.5246999264 0.0526837148 0.0538919802 0.0698473677 0.0055723179 0.0393310000 404339189 0 402718720 -0.0664788708 0.0595019497 -0.2157897502 1982 1311867236.5602099895 0.0509674177 0.0538905046 0.0698473677 0.0055733722 0.0390470000 404342625 0 402718720 -0.0664306805 0.0578342006 -0.2149136066 1983 1311867236.5972909927 0.0489417277 0.0538880090 0.0698473677 0.0055721399 0.0391540000 404345693 0 402718720 -0.0660566315 0.0572172366 -0.2153107077 1984 1311867236.6246581078 0.0499524847 0.0538860254 0.0698473677 0.0055711230 0.0385270000 404348817 0 402718720 -0.0671449602 0.0558400676 -0.2118206173 1985 1311867236.6600480080 0.0509230383 0.0538845327 0.0698473677 0.0055701511 0.0397770000 404352029 0 402718720 -0.0659546182 0.0576768555 -0.2095187753 1986 1311867236.6956660748 0.0484530069 0.0538817978 0.0698473677 0.0055697177 0.0390860000 404355481 0 402718720 -0.0651755929 0.0558813699 -0.2088188082 1987 1311867236.7276370525 0.0493568517 0.0538795205 0.0698473677 0.0055683485 0.0390400000 404358461 0 402718720 -0.0650852025 0.0559462011 -0.2057411075 1988 1311867236.7619268894 0.0495718755 0.0538773537 0.0698473677 0.0055677795 0.0395740000 404361601 0 402718720 -0.0647703707 0.0548751391 -0.2025276273 1989 1311867236.7923469543 0.0489194542 0.0538748610 0.0698473677 0.0055678594 0.0396150000 404364629 0 402718720 -0.0632904470 0.0557357594 -0.2023305595 1990 1311867236.8255391121 0.0489437059 0.0538723830 0.0698473677 0.0055667240 0.0396030000 404368081 0 402718720 -0.0661945641 0.0548877753 -0.1998552829 1991 1311867236.8583440781 0.0505585447 0.0538707186 0.0698473677 0.0055659161 0.0391630000 404371125 0 402718720 -0.0653691739 0.0555859357 -0.1965423375 1992 1311867236.8928480148 0.0505865477 0.0538690700 0.0698473677 0.0055660962 0.0394440000 404374425 0 402718720 -0.0658320859 0.0554679446 -0.1944382042 1993 1311867236.9255330563 0.0505632758 0.0538674113 0.0698473677 0.0055652029 0.0521280000 404377445 0 402718720 -0.0669867918 0.0543707758 -0.1920346916 1994 1311867236.9581959248 0.0489153899 0.0538649278 0.0698473677 0.0055648868 0.0396660000 404380721 0 402718720 -0.0663519949 0.0544122718 -0.1921501011 1995 1311867236.9937291145 0.0512550212 0.0538636196 0.0698473677 0.0055705276 0.0399620000 404383981 0 402718720 -0.0683782399 0.0557935871 -0.1874576360 1996 1311867237.0244200230 0.0493249260 0.0538613457 0.0698473677 0.0055714469 0.0396160000 404387009 0 402718720 -0.0673497543 0.0548454151 -0.1868293136 1997 1311867237.0603060722 0.0496785715 0.0538592511 0.0698473677 0.0055736067 0.0403900000 404390269 0 402718720 -0.0685166344 0.0549337715 -0.1840493679 1998 1311867237.0927588940 0.0506741069 0.0538576570 0.0698473677 0.0055884002 0.0493670000 404393425 0 402718720 -0.0687618777 0.0564202592 -0.1816888899 1999 1311867237.1276650429 0.0492011048 0.0538553275 0.0698473677 0.0055888993 0.0498240000 404396629 0 402718720 -0.0688862577 0.0544705205 -0.1803150624 2000 1311867237.1566579342 0.0488365591 0.0538528182 0.0698473677 0.0055882453 0.0401400000 404399729 0 402718720 -0.0711185262 0.0539963059 -0.1789144576 2001 1311867237.1925950050 0.0503006540 0.0538510430 0.0698473677 0.0055883339 0.0402260000 404402989 0 402718720 -0.0701354742 0.0556245223 -0.1760615855 2002 1311867237.2254281044 0.0511958338 0.0538497167 0.0698473677 0.0055870677 0.0399350000 404406001 0 402718720 -0.0710766166 0.0537272058 -0.1729619652 2003 1311867237.2569580078 0.0496361107 0.0538476130 0.0698473677 0.0055878608 0.0396780000 404409341 0 402718720 -0.0715248883 0.0531123169 -0.1728997827 2004 1311867237.2944281101 0.0496348962 0.0538455109 0.0698473677 0.0055866687 0.0404870000 404412601 0 402718720 -0.0722634867 0.0541816466 -0.1718695760 2005 1311867237.3250501156 0.0496059395 0.0538433964 0.0698473677 0.0055852902 0.0491290000 404415701 0 402718720 -0.0722290128 0.0539758317 -0.1704748273 2006 1311867237.3565309048 0.0493979119 0.0538411803 0.0698473677 0.0055860435 0.0400790000 404419185 0 402718720 -0.0746627897 0.0538472123 -0.1697457582 2007 1311867237.3934979439 0.0500011295 0.0538392670 0.0698473677 0.0055850894 0.0400950000 404422261 0 402718720 -0.0732389390 0.0539268777 -0.1666899174 2008 1311867237.4248709679 0.0501985475 0.0538374539 0.0698473677 0.0055838219 0.0397510000 404425273 0 402718720 -0.0745506659 0.0539857112 -0.1651325524 2009 1311867237.4579510689 0.0492094830 0.0538351502 0.0698473677 0.0055830218 0.0402850000 404428677 0 402718720 -0.0748555660 0.0514419302 -0.1633600742 2010 1311867237.4933559895 0.0496774837 0.0538330817 0.0698473677 0.0055835296 0.0391580000 404431969 0 402718720 -0.0748303682 0.0533728711 -0.1618692577 2011 1311867237.5253219604 0.0494466983 0.0538309005 0.0698473677 0.0055843470 0.0690800000 404435149 0 402718720 -0.0759090260 0.0521711223 -0.1595741957 2012 1311867237.5581231117 0.0504329540 0.0538292117 0.0698473677 0.0055833771 0.0398820000 404438161 0 402718720 -0.0759185404 0.0504761115 -0.1561430544 2013 1311867237.5925350189 0.0484437905 0.0538265364 0.0698473677 0.0055831320 0.0400070000 404441181 0 402718720 -0.0742272735 0.0512614027 -0.1568624377 2014 1311867237.6261129379 0.0491185635 0.0538241988 0.0698473677 0.0055819233 0.0390920000 404444441 0 402718720 -0.0751460344 0.0503187329 -0.1537379473 2015 1311867237.6569290161 0.0488311164 0.0538217208 0.0698473677 0.0055812543 0.0402780000 404447565 0 402718720 -0.0750434697 0.0492314957 -0.1518285573 2016 1311867237.6925010681 0.0489960872 0.0538193271 0.0698473677 0.0055802036 0.0588980000 404450961 0 402718720 -0.0763706267 0.0494469032 -0.1499544084 2017 1311867237.7243609428 0.0507062860 0.0538177837 0.0698473677 0.0055788975 0.0399310000 404454173 0 402718720 -0.0747825578 0.0491720960 -0.1461628675 2018 1311867237.7617940903 0.0495669134 0.0538156773 0.0698473677 0.0055777327 0.0395240000 404457609 0 402718720 -0.0770754963 0.0470222160 -0.1443189234 2019 1311867237.7926809788 0.0498570204 0.0538137166 0.0698473677 0.0055768921 0.0519830000 404460389 0 402718720 -0.0766916424 0.0477683023 -0.1417327225 2020 1311867237.8255820274 0.0509432293 0.0538122955 0.0698473677 0.0055768285 0.0395310000 404463481 0 402718720 -0.0786889493 0.0495524295 -0.1393390000 2021 1311867237.8612699509 0.0498747379 0.0538103472 0.0698473677 0.0055764826 0.0396910000 404466941 0 402718720 -0.0776958466 0.0476063266 -0.1370394826 2022 1311867237.8926060200 0.0497761667 0.0538083521 0.0698473677 0.0055756689 0.0494060000 404469921 0 402718720 -0.0776038244 0.0491462164 -0.1352085471 2023 1311867237.9253590107 0.0503305830 0.0538066329 0.0698473677 0.0055745799 0.0389190000 404473301 0 402718720 -0.0781768113 0.0487456359 -0.1323281825 2024 1311867237.9613509178 0.0504596196 0.0538049793 0.0698473677 0.0055739969 0.0400290000 404476385 0 402718720 -0.0775480568 0.0477570035 -0.1291332096 2025 1311867237.9928910732 0.0502940305 0.0538032455 0.0698473677 0.0055731517 0.0391340000 404479597 0 402718720 -0.0783196911 0.0472610518 -0.1271088868 2026 1311867238.0245919228 0.0500577018 0.0538013967 0.0698473677 0.0055727885 0.0396550000 404482625 0 402718720 -0.0775126219 0.0481578298 -0.1257778853 2027 1311867238.0607950687 0.0501365699 0.0537995887 0.0698473677 0.0055724338 0.0388720000 404486141 0 402718720 -0.0774135590 0.0473696142 -0.1234283149 2028 1311867238.0932629108 0.0497336276 0.0537975838 0.0698473677 0.0055711706 0.0515030000 404489289 0 402718720 -0.0791428164 0.0446950309 -0.1207436472 2029 1311867238.1251931190 0.0492933020 0.0537953639 0.0698473677 0.0055703907 0.0397290000 404492325 0 402718720 -0.0777671412 0.0460135303 -0.1201531738 2030 1311867238.1608469486 0.0506771915 0.0537938278 0.0698473677 0.0055777542 0.0399310000 404495521 0 402718720 -0.0763248876 0.0474089943 -0.1168277264 2031 1311867238.1928510666 0.0501242280 0.0537920210 0.0698473677 0.0055835952 0.0502030000 404498877 0 402718720 -0.0775475651 0.0454302803 -0.1140130758 2032 1311867238.2246770859 0.0507390983 0.0537905186 0.0698473677 0.0055827063 0.0398310000 404501641 0 402718720 -0.0767718181 0.0466411225 -0.1116542667 2033 1311867238.2605938911 0.0490452535 0.0537881845 0.0698473677 0.0055842331 0.0507510000 404505413 0 402718720 -0.0739197209 0.0468513817 -0.1111552119 2034 1311867238.2926790714 0.0503689572 0.0537865035 0.0698473677 0.0055867604 0.0399240000 404508313 0 402718720 -0.0739718080 0.0447431877 -0.1066497564 2035 1311867238.3257811069 0.0496779606 0.0537844845 0.0698473677 0.0055947428 0.0394160000 404511397 0 402718720 -0.0739739910 0.0436818451 -0.1048984230 2036 1311867238.3604390621 0.0508906916 0.0537830632 0.0698473677 0.0055960364 0.0395070000 404514681 0 402718720 -0.0740446150 0.0443984307 -0.1021757945 2037 1311867238.3936378956 0.0505615026 0.0537814817 0.0698473677 0.0055979605 0.0399770000 404517901 0 402718720 -0.0732638463 0.0423189476 -0.0994772017 2038 1311867238.4264049530 0.0503452830 0.0537797956 0.0698473677 0.0056012034 0.0398610000 404520937 0 402718720 -0.0729238167 0.0412259996 -0.0975759774 2039 1311867238.4616210461 0.0494858958 0.0537776897 0.0698473677 0.0056000366 0.0393430000 404524597 0 402718720 -0.0713402182 0.0407758132 -0.0961184129 2040 1311867238.4932549000 0.0507825091 0.0537762215 0.0698473677 0.0056066674 0.0519440000 404527249 0 402718720 -0.0719927922 0.0402741656 -0.0925505012 2041 1311867238.5248661041 0.0510436445 0.0537748827 0.0698473677 0.0056058799 0.0491320000 404530773 0 402718720 -0.0719830245 0.0385552719 -0.0899408236 2042 1311867238.5605928898 0.0499079525 0.0537729890 0.0698473677 0.0056106760 0.0398820000 404533921 0 402718720 -0.0700783059 0.0388804227 -0.0886077806 2043 1311867238.5929119587 0.0502608083 0.0537712698 0.0698473677 0.0056157621 0.0398300000 404537141 0 402718720 -0.0702085197 0.0368864909 -0.0852903873 2044 1311867238.6249868870 0.0505077802 0.0537696732 0.0698473677 0.0056145262 0.0403700000 404540249 0 402718720 -0.0713483617 0.0368135534 -0.0827023312 2045 1311867238.6608479023 0.0508844368 0.0537682623 0.0698473677 0.0056134833 0.0396920000 404543381 0 402718720 -0.0699093044 0.0356334262 -0.0788630843 2046 1311867238.6929359436 0.0490817912 0.0537659718 0.0698473677 0.0056130778 0.0396260000 404546737 0 402718720 -0.0681538954 0.0359774269 -0.0778807104 2047 1311867238.7246360779 0.0502682440 0.0537642631 0.0698473677 0.0056141342 0.0393170000 404549781 0 402718720 -0.0680410191 0.0353270583 -0.0740878806 2048 1311867238.7627971172 0.0492718853 0.0537620695 0.0698473677 0.0056130396 0.0399180000 404553161 0 402718720 -0.0688195899 0.0354075655 -0.0712703392 2049 1311867238.7949919701 0.0506425835 0.0537605471 0.0698473677 0.0056123386 0.0400520000 404752973 0 402718720 -0.0682970732 0.0360652134 -0.0673701689 2050 1311867238.8246819973 0.0508006848 0.0537591033 0.0698473677 0.0056155810 0.0395670000 405165561 0 402718720 -0.0683753118 0.0338447355 -0.0632700473 2051 1311867238.8630580902 0.0495419949 0.0537570471 0.0698473677 0.0056146504 0.0395710000 405169125 0 402718720 -0.0686713159 0.0341983214 -0.0610268526 2052 1311867238.8933889866 0.0498385131 0.0537551375 0.0698473677 0.0056136075 0.0397770000 405171961 0 402718720 -0.0676771700 0.0346907005 -0.0578439981 2053 1311867238.9278979301 0.0503054559 0.0537534572 0.0698473677 0.0056124089 0.0513430000 405175157 0 402718720 -0.0665704757 0.0335833542 -0.0538958572 2054 1311867238.9628050327 0.0508610010 0.0537520490 0.0698473677 0.0056116017 0.0399520000 405178545 0 402718720 -0.0677713007 0.0319013111 -0.0495323651 2055 1311867238.9937820435 0.0495380014 0.0537499984 0.0698473677 0.0056106247 0.0400410000 405181661 0 402718720 -0.0654711947 0.0310725346 -0.0478490368 2056 1311867239.0287299156 0.0508180223 0.0537485723 0.0698473677 0.0056122353 0.0399740000 405184873 0 402718720 -0.0661361068 0.0327450335 -0.0441847742 2057 1311867239.0619978905 0.0497304760 0.0537466189 0.0698473677 0.0056135939 0.0405450000 405188261 0 402718720 -0.0672979504 0.0301182829 -0.0410466753 2058 1311867239.0939240456 0.0500046648 0.0537448007 0.0698473677 0.0056153039 0.0399340000 405191105 0 402718720 -0.0665211752 0.0296118483 -0.0374190211 2059 1311867239.1358110905 0.0491826683 0.0537425850 0.0698473677 0.0056146707 0.0508440000 405194677 0 402718720 -0.0641282722 0.0296586733 -0.0342491828 2060 1311867239.1620550156 0.0491190664 0.0537403406 0.0698473677 0.0056144066 0.0408110000 405197801 0 402718720 -0.0638974309 0.0283174589 -0.0311721712 2061 1311867239.1936569214 0.0500323959 0.0537385415 0.0698473677 0.0056134976 0.0398350000 405201021 0 402718720 -0.0633210838 0.0278328303 -0.0272153206 2062 1311867239.2294950485 0.0488551892 0.0537361732 0.0698473677 0.0056125027 0.0404190000 405204137 0 402718720 -0.0625430793 0.0273465980 -0.0247792304 2063 1311867239.2609150410 0.0490170792 0.0537338857 0.0698473677 0.0056115495 0.0395610000 405207285 0 402718720 -0.0639767721 0.0256991703 -0.0212334450 2064 1311867239.2928791046 0.0490470678 0.0537316150 0.0698473677 0.0056107195 0.0396610000 405210537 0 402718720 -0.0624743439 0.0242618117 -0.0176298842 2065 1311867239.3295290470 0.0497842133 0.0537297034 0.0698473677 0.0056107696 0.0511310000 405213661 0 402718720 -0.0621943325 0.0246888250 -0.0138113461 2066 1311867239.3615000248 0.0504181907 0.0537281005 0.0698473677 0.0056107169 0.0500630000 405217001 0 402718720 -0.0618146472 0.0231113061 -0.0100878952 2067 1311867239.3928411007 0.0492053255 0.0537259124 0.0698473677 0.0056120631 0.0393270000 405220149 0 402718720 -0.0606509112 0.0199314021 -0.0075859018 2068 1311867239.4293289185 0.0516293123 0.0537248986 0.0698473677 0.0056190612 0.0392650000 405223241 0 402718720 -0.0594789088 0.0193148050 -0.0020290678 2069 1311867239.4619059563 0.0508355908 0.0537235021 0.0698473677 0.0056216522 0.0395530000 405226645 0 402718720 -0.0595125556 0.0183646288 -0.0002379245 2070 1311867239.4938249588 0.0509331971 0.0537221542 0.0698473677 0.0056208105 0.0398380000 405229865 0 402718720 -0.0579959676 0.0161301661 0.0028966544 2071 1311867239.5295019150 0.0510864109 0.0537208815 0.0698473677 0.0056227836 0.0485480000 405233237 0 402718720 -0.0568451099 0.0143249007 0.0062638796 2072 1311867239.5617070198 0.0496933721 0.0537189377 0.0698473677 0.0056275360 0.0395120000 405236081 0 402718720 -0.0574242435 0.0137047879 0.0074987905 2073 1311867239.5944910049 0.0499724708 0.0537171304 0.0698473677 0.0056263776 0.0395900000 405239485 0 402718720 -0.0571903549 0.0124831628 0.0103713591 2074 1311867239.6284430027 0.0492498577 0.0537149765 0.0698473677 0.0056370651 0.0400730000 405242385 0 402718720 -0.0560423397 0.0099788699 0.0131945927 2075 1311867239.6623089314 0.0498526953 0.0537131151 0.0698473677 0.0056360952 0.0497810000 405245901 0 402718720 -0.0529989675 0.0092031583 0.0169708561 2076 1311867239.6931240559 0.0503466241 0.0537114935 0.0698473677 0.0056497261 0.0498510000 405248809 0 402718720 -0.0526032858 0.0104967980 0.0193544105 2077 1311867239.7284948826 0.0510241054 0.0537101996 0.0698473677 0.0056497116 0.0487710000 405252341 0 402718720 -0.0526457205 0.0089552682 0.0234103762 2078 1311867239.7614610195 0.0507362075 0.0537087685 0.0698473677 0.0056495920 0.0395280000 405255345 0 402718720 -0.0520272106 0.0077528362 0.0261240918 2079 1311867239.7926149368 0.0510399491 0.0537074848 0.0698473677 0.0056488322 0.0396110000 405258701 0 402718720 -0.0503046438 0.0100554423 0.0288600065 2080 1311867239.8308320045 0.0515481420 0.0537064466 0.0698473677 0.0056507847 0.0393120000 405261625 0 402718720 -0.0515384674 0.0102366237 0.0324648507 2081 1311867239.8608438969 0.0498540513 0.0537045954 0.0698473677 0.0056604982 0.0505640000 405264861 0 402718720 -0.0512647182 0.0084619215 0.0345011167 2082 1311867239.8929069042 0.0495495945 0.0537025997 0.0698473677 0.0056609526 0.0389330000 405267945 0 402718720 -0.0496157706 0.0090182200 0.0367732085 2083 1311867239.9306600094 0.0506047420 0.0537011125 0.0698473677 0.0056610399 0.0390250000 405271389 0 402718720 -0.0510855839 0.0088030985 0.0412016138 2084 1311867239.9613699913 0.0496823043 0.0536991841 0.0698473677 0.0056614483 0.0385520000 405274489 0 402718720 -0.0505322777 0.0082569132 0.0428889506 2085 1311867239.9948220253 0.0512229130 0.0536979964 0.0698473677 0.0056610453 0.0390170000 405277861 0 402718720 -0.0511026084 0.0078926487 0.0473471284 2086 1311867240.0292289257 0.0514875762 0.0536969368 0.0698473677 0.0056613506 0.0389730000 405280937 0 402718720 -0.0512674861 0.0070440890 0.0509127229 2087 1311867240.0618810654 0.0509567559 0.0536956238 0.0698473677 0.0056601411 0.0388550000 405284013 0 402718720 -0.0504145920 0.0065098600 0.0527986921 2088 1311867240.0945510864 0.0511859730 0.0536944219 0.0698473677 0.0056591728 0.0469560000 405969961 0 402718720 -0.0497812703 0.0071459357 0.0558676608 2089 1311867240.1297509670 0.0512887277 0.0536932703 0.0698473677 0.0056583042 0.1310350000 405941245 0 402718720 -0.0486934632 0.0057270951 0.0595406592 2090 1311867240.1617240906 0.0508954190 0.0536919316 0.0698473677 0.0056580798 0.1314730000 405943161 0 402718720 -0.0486954823 0.0067076120 0.0616860688 2091 1311867240.1963129044 0.0511654764 0.0536907233 0.0698473677 0.0056575953 0.1210960000 406227285 0 402718720 -0.0501539148 0.0060102083 0.0650142133 2092 1311867240.2291030884 0.0502618290 0.0536890843 0.0698473677 0.0056564718 0.1198150000 415662269 0 402718720 -0.0486986935 0.0048911939 0.0668750554 2093 1311867240.2612760067 0.0511455908 0.0536878690 0.0698473677 0.0056554579 0.0807390000 416143529 0 402718720 -0.0471395254 0.0056496994 0.0703174472 2094 1311867240.2981250286 0.0512446985 0.0536867023 0.0698473677 0.0056542111 0.0551380000 416484277 0 402718720 -0.0473421738 0.0046905396 0.0733376220 2095 1311867240.3289160728 0.0500465110 0.0536849647 0.0698473677 0.0056535973 0.1329670000 411382885 0 402718720 -0.0470627472 0.0032603908 0.0748169720 2096 1311867240.3609399796 0.0505415425 0.0536834650 0.0698473677 0.0056525474 0.0420160000 405957017 0 402718720 -0.0463538393 0.0026537604 0.0778481513 2097 1311867240.3967890739 0.0494624078 0.0536814521 0.0698473677 0.0056516158 0.0418290000 405960053 0 402718720 -0.0454801172 0.0023319907 0.0789219588 2098 1311867240.4286890030 0.0503810123 0.0536798790 0.0698473677 0.0056503289 0.0413420000 405963425 0 402718720 -0.0468773022 0.0001260067 0.0823448300 2099 1311867240.4650850296 0.0505875498 0.0536784057 0.0698473677 0.0056535903 0.0423070000 405966485 0 402718720 -0.0460116751 -0.0011302866 0.0852122679 2100 1311867240.4972898960 0.0503355525 0.0536768139 0.0698473677 0.0056560526 0.0417920000 405969761 0 402718720 -0.0450221486 -0.0019105441 0.0867299736 2101 1311867240.5309979916 0.0500650667 0.0536750948 0.0698473677 0.0056574054 0.0541140000 405972917 0 402718720 -0.0447566211 -0.0017345560 0.0878718272 2102 1311867240.5608210564 0.0492318310 0.0536729810 0.0698473677 0.0056561524 0.0506060000 405976137 0 402718720 -0.0449483395 -0.0038668658 0.0893338397 2103 1311867240.5965991020 0.0515460148 0.0536719696 0.0698473677 0.0056559432 0.0408010000 405979493 0 402718720 -0.0442933664 -0.0037287385 0.0929232910 2104 1311867240.6290791035 0.0506267473 0.0536705223 0.0698473677 0.0056568482 0.0403530000 405982657 0 402718720 -0.0452781543 -0.0064775026 0.0936623290 2105 1311867240.6622560024 0.0505149551 0.0536690232 0.0698473677 0.0056597036 0.0557740000 405985549 0 402718720 -0.0456599146 -0.0060449610 0.0948145464 2106 1311867240.6968801022 0.0497407541 0.0536671579 0.0698473677 0.0056585543 0.0426370000 405988977 0 402718720 -0.0467289574 -0.0069413157 0.0955995619 2107 1311867240.7291979790 0.0496722348 0.0536652619 0.0698473677 0.0056597373 0.0418210000 405992077 0 402718720 -0.0450653769 -0.0062997439 0.0966382623 2108 1311867240.7625629902 0.0507288724 0.0536638689 0.0698473677 0.0056593145 0.0391800000 405995305 0 402718720 -0.0460923575 -0.0057025887 0.0989197120 2109 1311867240.7965719700 0.0492439009 0.0536617731 0.0698473677 0.0056588369 0.0431900000 405998405 0 402718720 -0.0467011444 -0.0066332412 0.0993119553 2110 1311867240.8293309212 0.0498811901 0.0536599814 0.0698473677 0.0056576263 0.0541070000 406001905 0 402718720 -0.0463889167 -0.0048198318 0.1017436162 2111 1311867240.8621098995 0.0485699512 0.0536575702 0.0698473677 0.0056571420 0.0418980000 406004853 0 402718720 -0.0474104807 -0.0050092386 0.1024573296 2112 1311867240.8973500729 0.0480913743 0.0536549347 0.0698473677 0.0056570049 0.0426660000 406008385 0 402718720 -0.0471624881 -0.0055327974 0.1045206487 2113 1311867240.9290270805 0.0485538207 0.0536525205 0.0698473677 0.0056558779 0.0403280000 406011221 0 402718720 -0.0480420329 -0.0034987417 0.1068908200 2114 1311867240.9614369869 0.0495458506 0.0536505779 0.0698473677 0.0056546202 0.0530550000 406014625 0 402718720 -0.0484341495 -0.0024354355 0.1098756790 2115 1311867240.9968450069 0.0490521714 0.0536484037 0.0698473677 0.0056537468 0.0422440000 406017941 0 402718720 -0.0493828207 -0.0034257751 0.1122918651 2116 1311867241.0315620899 0.0491020717 0.0536462552 0.0698473677 0.0056549372 0.0426960000 406020793 0 402718720 -0.0497917198 -0.0021519377 0.1153439134 2117 1311867241.0633668900 0.0490329266 0.0536440760 0.0698473677 0.0056614110 0.0400280000 406024037 0 402718720 -0.0499069691 -0.0000511897 0.1170034632 2118 1311867241.0990099907 0.0501536280 0.0536424280 0.0698473677 0.0056624041 0.0425990000 406027289 0 402718720 -0.0514488667 -0.0012986814 0.1215935275 2119 1311867241.1285290718 0.0498781912 0.0536406516 0.0698473677 0.0056647787 0.0433500000 406030549 0 402718720 -0.0522288159 -0.0030529369 0.1235291585 2120 1311867241.1641499996 0.0505565256 0.0536391968 0.0698473677 0.0056701877 0.0401650000 406033993 0 402718720 -0.0517776385 -0.0002494976 0.1263221651 2121 1311867241.1980121136 0.0499344394 0.0536374501 0.0698473677 0.0056721534 0.0390890000 406036965 0 402718720 -0.0524867587 -0.0020093583 0.1282529831 2122 1311867241.2313330173 0.0505950972 0.0536360164 0.0698473677 0.0056747645 0.0428600000 406040289 0 402718720 -0.0549220145 -0.0007355316 0.1306116581 2123 1311867241.2640700340 0.0517994203 0.0536351513 0.0698473677 0.0056734669 0.0540840000 406043381 0 402718720 -0.0545319393 0.0008237977 0.1333517283 2124 1311867241.3000609875 0.0507935584 0.0536338134 0.0698473677 0.0056793987 0.0389120000 406046505 0 402718720 -0.0552608892 -0.0007448415 0.1349299103 2125 1311867241.3294849396 0.0513998456 0.0536327622 0.0698473677 0.0056831813 0.0387500000 406049893 0 402718720 -0.0579374768 0.0003505088 0.1367519647 2126 1311867241.3612549305 0.0513668507 0.0536316964 0.0698473677 0.0056826893 0.0527730000 406052745 0 402718720 -0.0588633791 -0.0004599765 0.1384199560 2127 1311867241.3981139660 0.0518469028 0.0536308572 0.0698473677 0.0056860655 0.0414780000 406056285 0 402718720 -0.0595006496 -0.0017188089 0.1407616884 2128 1311867241.4300589561 0.0525639467 0.0536303559 0.0698473677 0.0057009749 0.0417620000 406059169 0 402718720 -0.0604879856 -0.0006787432 0.1427836120 2129 1311867241.4652009010 0.0527386405 0.0536299370 0.0698473677 0.0057025428 0.0419630000 406062325 0 402718720 -0.0621559061 0.0001302096 0.1446312964 2130 1311867241.4969789982 0.0527127460 0.0536295064 0.0698473677 0.0057072661 0.0424670000 406065705 0 402718720 -0.0623765327 0.0008496703 0.1466248333 2131 1311867241.5331718922 0.0521432124 0.0536288090 0.0698473677 0.0057082446 0.0412320000 406068893 0 402718720 -0.0640351027 -0.0004342534 0.1475863606 2132 1311867241.5656960011 0.0518499687 0.0536279746 0.0698473677 0.0057086508 0.0395080000 406072249 0 402718720 -0.0644539371 -0.0004918422 0.1491326243 2133 1311867241.6002480984 0.0524120592 0.0536274046 0.0698473677 0.0057090574 0.0509400000 406075293 0 402718720 -0.0661346540 -0.0009851260 0.1506131887 2134 1311867241.6291201115 0.0528001934 0.0536270169 0.0698473677 0.0057079657 0.0419990000 406078513 0 402718720 -0.0659093708 -0.0014643855 0.1517384648 2135 1311867241.6646790504 0.0517622493 0.0536261435 0.0698473677 0.0057137757 0.0420120000 406081717 0 402718720 -0.0652603805 0.0006809342 0.1518200040 2136 1311867241.6999258995 0.0521646626 0.0536254593 0.0698473677 0.0057134058 0.0416430000 406084913 0 402718720 -0.0670019016 0.0006646947 0.1534676552 2137 1311867241.7297649384 0.0527729020 0.0536250603 0.0698473677 0.0057242867 0.0504370000 406765853 0 402718720 -0.0667565167 0.0006726398 0.1541862041 2138 1311867241.7676639557 0.0521397144 0.0536243656 0.0698473677 0.0057233014 0.1379200000 406745129 0 402718720 -0.0678128228 0.0011469549 0.1547093689 2139 1311867241.7974851131 0.0520552322 0.0536236320 0.0698473677 0.0057228654 0.1335050000 406746705 0 402718720 -0.0686157048 0.0004332708 0.1556915641 2140 1311867241.8296549320 0.0522587895 0.0536229942 0.0698473677 0.0057234472 0.1247440000 406782433 0 402718720 -0.0688086003 0.0000065980 0.1571491361 2141 1311867241.8668920994 0.0522091053 0.0536223339 0.0698473677 0.0057222444 0.1130260000 417586869 0 402718720 -0.0690647811 0.0003522262 0.1582684815 2142 1311867241.8979690075 0.0525401495 0.0536218286 0.0698473677 0.0057210178 0.0914670000 416115473 0 402718720 -0.0694765374 0.0002137749 0.1598592252 2143 1311867241.9292619228 0.0520615987 0.0536211006 0.0698473677 0.0057207999 0.0495950000 417781049 0 402718720 -0.0707050413 -0.0004062718 0.1616877317 2144 1311867241.9654040337 0.0508569814 0.0536198113 0.0698473677 0.0057200741 0.1374730000 415642965 0 402718720 -0.0709181353 0.0008384581 0.1628465205 2145 1311867241.9974029064 0.0516832620 0.0536189085 0.0698473677 0.0057208214 0.0508000000 406761197 0 402718720 -0.0710489452 0.0004183725 0.1652924716 2146 1311867242.0296339989 0.0518861823 0.0536181011 0.0698473677 0.0057214995 0.0407300000 406764377 0 402718720 -0.0711491778 -0.0002054116 0.1673364788 2147 1311867242.0670061111 0.0513103828 0.0536170262 0.0698473677 0.0057216038 0.0418350000 406767853 0 402718720 -0.0720084310 0.0025303918 0.1683905274 2148 1311867242.0972509384 0.0512626730 0.0536159302 0.0698473677 0.0057215956 0.0412300000 406770753 0 402718720 -0.0749126077 0.0019982900 0.1700207591 2149 1311867242.1308040619 0.0521246307 0.0536152362 0.0698473677 0.0057227417 0.0522310000 406773837 0 402718720 -0.0745844990 0.0015437775 0.1720628291 2150 1311867242.1670179367 0.0517690629 0.0536143775 0.0698473677 0.0057233498 0.0409670000 406776993 0 402718720 -0.0736830682 0.0028879181 0.1730086952 2151 1311867242.1982409954 0.0521860048 0.0536137135 0.0698473677 0.0057240862 0.0533100000 406780357 0 402718720 -0.0752327666 0.0008205054 0.1752541363 2152 1311867242.2334370613 0.0522368848 0.0536130737 0.0698473677 0.0057274623 0.0406000000 406783425 0 402718720 -0.0759117305 0.0030084737 0.1767544597 2153 1311867242.2696599960 0.0520282984 0.0536123376 0.0698473677 0.0057263172 0.0428730000 406786957 0 402718720 -0.0757518411 0.0031046378 0.1782282889 2154 1311867242.2982430458 0.0523844436 0.0536117676 0.0698473677 0.0057250868 0.0396340000 406789945 0 402718720 -0.0771717131 0.0025069881 0.1802054346 2155 1311867242.3293490410 0.0526773147 0.0536113339 0.0698473677 0.0057242988 0.0425800000 406792965 0 402718720 -0.0769338086 0.0022517177 0.1824008375 2156 1311867242.3659460545 0.0531288125 0.0536111101 0.0698473677 0.0057249621 0.0439480000 406796225 0 402718720 -0.0776293129 0.0021615922 0.1843915582 2157 1311867242.3974800110 0.0538574271 0.0536112243 0.0698473677 0.0057242638 0.0518870000 406799245 0 402718720 -0.0770484060 0.0019663908 0.1862463355 2158 1311867242.4322769642 0.0529843494 0.0536109338 0.0698473677 0.0057231106 0.0422050000 406802713 0 402718720 -0.0782046914 0.0018747281 0.1869720966 2159 1311867242.4648990631 0.0533545204 0.0536108151 0.0698473677 0.0057233660 0.0413100000 406805421 0 402718720 -0.0780249387 0.0011521894 0.1885750294 2160 1311867242.4975609779 0.0540032089 0.0536109967 0.0698473677 0.0057222763 0.0546900000 406808953 0 402718720 -0.0784588456 0.0002155788 0.1907445341 2161 1311867242.5292570591 0.0540877320 0.0536112174 0.0698473677 0.0057214122 0.0589260000 407499305 0 402718720 -0.0790642798 0.0013897922 0.1919990480 2162 1311867242.5650939941 0.0540419444 0.0536114166 0.0698473677 0.0057203287 0.1436900000 407481961 0 402718720 -0.0790729970 -0.0001241416 0.1936485916 2163 1311867242.5985031128 0.0539359488 0.0536115666 0.0698473677 0.0057192609 0.1403890000 407485633 0 402718720 -0.0799261108 -0.0005336152 0.1950124353 2164 1311867242.6305589676 0.0538645312 0.0536116835 0.0698473677 0.0057180838 0.1324030000 407801273 0 402718720 -0.0789165422 -0.0004539462 0.1960361004 2165 1311867242.6692740917 0.0532998294 0.0536115395 0.0698473677 0.0057181287 0.1465890000 416340421 0 402718720 -0.0791086704 -0.0018778862 0.1981596798 2166 1311867242.6981039047 0.0531140491 0.0536113098 0.0698473677 0.0057170906 0.0544810000 419354893 0 402718720 -0.0812157169 -0.0019036597 0.1997526586 2167 1311867242.7372829914 0.0533491075 0.0536111888 0.0698473677 0.0057171064 0.0862660000 419098029 0 402718720 -0.0791876093 -0.0011026356 0.2018001229 2168 1311867242.7656900883 0.0535573810 0.0536111640 0.0698473677 0.0057167925 0.0517070000 419247073 0 402718720 -0.0801629424 -0.0026114229 0.2040441781 2169 1311867242.7994089127 0.0544835329 0.0536115662 0.0698473677 0.0057190884 0.1439540000 417239847 0 402718720 -0.0800952688 -0.0028563449 0.2071054131 2170 1311867242.8355538845 0.0541467629 0.0536118128 0.0698473677 0.0057190061 0.0766470000 407503365 0 402718720 -0.0808218122 -0.0011044145 0.2086578161 2171 1311867242.8666720390 0.0543283746 0.0536121429 0.0698473677 0.0057198031 0.0408040000 407506321 0 402718720 -0.0803025812 -0.0022332892 0.2105657309 2172 1311867242.8980929852 0.0546157137 0.0536126049 0.0698473677 0.0057374777 0.0524360000 407509349 0 402718720 -0.0790779069 -0.0032670470 0.2118847817 2173 1311867242.9335498810 0.0544725880 0.0536130007 0.0698473677 0.0057582406 0.0444020000 407512865 0 402718720 -0.0800217912 -0.0011557331 0.2145158350 2174 1311867242.9649999142 0.0553587899 0.0536138037 0.0698473677 0.0057610670 0.0418450000 407515997 0 402718720 -0.0812586024 -0.0020667529 0.2169912905 2175 1311867242.9970819950 0.0559353381 0.0536148711 0.0698473677 0.0057600275 0.0399580000 407518897 0 402718720 -0.0811204091 -0.0019948985 0.2191373259 2176 1311867243.0332529545 0.0565463305 0.0536162183 0.0698473677 0.0057588427 0.0531220000 407522157 0 402718720 -0.0798864365 -0.0024970789 0.2208554000 2177 1311867243.0648689270 0.0558001883 0.0536172215 0.0698473677 0.0057575839 0.0395110000 407525257 0 402718720 -0.0811190158 -0.0025947709 0.2227593660 2178 1311867243.0972158909 0.0552280061 0.0536179610 0.0698473677 0.0057566973 0.0402540000 407528565 0 402718720 -0.0830901712 -0.0029092301 0.2240382582 2179 1311867243.1357100010 0.0548222326 0.0536185137 0.0698473677 0.0057628715 0.0423280000 407531881 0 402718720 -0.0828571543 -0.0026204018 0.2263056040 2180 1311867243.1655960083 0.0556749739 0.0536194570 0.0698473677 0.0057689289 0.0402980000 407535117 0 402718720 -0.0840065926 -0.0045102118 0.2282814384 2181 1311867243.1977169514 0.0560926944 0.0536205910 0.0698473677 0.0057691545 0.0395790000 407538209 0 402718720 -0.0841529667 -0.0043199696 0.2300989032 2182 1311867243.2358860970 0.0566172786 0.0536219644 0.0698473677 0.0057694615 0.0422280000 407541549 0 402718720 -0.0849241465 -0.0037472770 0.2327407748 2183 1311867243.2649240494 0.0561695285 0.0536231314 0.0698473677 0.0057688801 0.0413030000 407544465 0 402718720 -0.0857161433 -0.0063545285 0.2339830697 2184 1311867243.2970221043 0.0565250106 0.0536244601 0.0698473677 0.0057680798 0.0550770000 407548117 0 402718720 -0.0864107534 -0.0064998874 0.2361355573 2185 1311867243.3327538967 0.0563582890 0.0536257113 0.0698473677 0.0057675060 0.0468050000 407551017 0 402718720 -0.0880236104 -0.0079403836 0.2381065339 2186 1311867243.3681559563 0.0567472279 0.0536271392 0.0698473677 0.0057669429 0.0397210000 407554325 0 402718720 -0.0879204050 -0.0074256836 0.2400069237 2187 1311867243.4021821022 0.0571037084 0.0536287289 0.0698473677 0.0057656514 0.0394160000 407557593 0 402718720 -0.0890591368 -0.0076059978 0.2418154180 2188 1311867243.4344329834 0.0570244864 0.0536302809 0.0698473677 0.0057656021 0.0393110000 407560629 0 402718720 -0.0886390656 -0.0075000022 0.2431743443 2189 1311867243.4665510654 0.0566904470 0.0536316788 0.0698473677 0.0057643636 0.0545410000 407563905 0 402718720 -0.0886684880 -0.0070673060 0.2451138645 2190 1311867243.4982140064 0.0572834425 0.0536333463 0.0698473677 0.0057639158 0.0391220000 407566869 0 402718720 -0.0890776664 -0.0076683089 0.2473928034 2191 1311867243.5339779854 0.0573360287 0.0536350363 0.0698473677 0.0057628270 0.0424570000 407570489 0 402718720 -0.0894979388 -0.0079955719 0.2491302937 2192 1311867243.5669720173 0.0574702807 0.0536367859 0.0698473677 0.0057617178 0.0388950000 407573437 0 402718720 -0.0881082341 -0.0073174424 0.2511003017 2193 1311867243.5978341103 0.0579691827 0.0536387615 0.0698473677 0.0057605626 0.0398300000 407576401 0 402718720 -0.0897989720 -0.0086931121 0.2532816827 2194 1311867243.6333720684 0.0582456924 0.0536408613 0.0698473677 0.0057617667 0.0396000000 407580117 0 402718720 -0.0891028047 -0.0087047182 0.2547489107 2195 1311867243.6661529541 0.0575162619 0.0536426268 0.0698473677 0.0057604872 0.0515590000 407583129 0 402718720 -0.0898832828 -0.0087892562 0.2554583549 2196 1311867243.6981849670 0.0588706583 0.0536450075 0.0698473677 0.0057594216 0.0402390000 407586173 0 402718720 -0.0900841132 -0.0088156629 0.2582296431 2197 1311867243.7344710827 0.0572992340 0.0536466708 0.0698473677 0.0057589089 0.0414670000 407589441 0 402718720 -0.0891840830 -0.0091655757 0.2589531243 2198 1311867243.7666299343 0.0574783981 0.0536484141 0.0698473677 0.0057582592 0.0399820000 407592741 0 402718720 -0.0873465240 -0.0090629533 0.2606439292 2199 1311867243.7979769707 0.0583389103 0.0536505471 0.0698473677 0.0057572548 0.0402470000 407595785 0 402718720 -0.0888067558 -0.0091964453 0.2631552219 2200 1311867243.8330240250 0.0566709004 0.0536519200 0.0698473677 0.0057567977 0.0415520000 407599053 0 402718720 -0.0880291313 -0.0096458606 0.2637435794 2201 1311867243.8647689819 0.0580018125 0.0536538963 0.0698473677 0.0057565299 0.0388450000 407602153 0 402718720 -0.0876763240 -0.0093558058 0.2665768862 2202 1311867243.8968739510 0.0584835410 0.0536560896 0.0698473677 0.0057553114 0.0413300000 407605757 0 402718720 -0.0871924609 -0.0098099299 0.2686420977 2203 1311867243.9329960346 0.0575118922 0.0536578399 0.0698473677 0.0057543246 0.0388570000 407608481 0 402718720 -0.0868681520 -0.0106556304 0.2691931427 2204 1311867243.9660589695 0.0575844198 0.0536596214 0.0698473677 0.0057533733 0.0465880000 408333061 0 402718720 -0.0864816904 -0.0106608272 0.2706773877 2205 1311867244.0016739368 0.0578735024 0.0536615325 0.0698473677 0.0057528077 0.1373100000 408322653 0 402718720 -0.0857248604 -0.0105930213 0.2726759017 2206 1311867244.0341379642 0.0579614528 0.0536634817 0.0698473677 0.0057521034 0.1246430000 408325257 0 402718720 -0.0854130015 -0.0111539084 0.2744506299 2207 1311867244.0655789375 0.0580575652 0.0536654727 0.0698473677 0.0057509127 0.1231120000 408626961 0 402718720 -0.0859564990 -0.0116606168 0.2760495245 2208 1311867244.1010930538 0.0578968115 0.0536673890 0.0698473677 0.0057497371 0.1188510000 418180401 0 402718720 -0.0855961889 -0.0123220067 0.2779448926 2209 1311867244.1353089809 0.0577686243 0.0536692456 0.0698473677 0.0057495279 0.0569540000 420756933 0 402718720 -0.0856539756 -0.0121779945 0.2795812786 2210 1311867244.1648418903 0.0584968068 0.0536714301 0.0698473677 0.0057482967 0.0826870000 420571733 0 402718720 -0.0855609253 -0.0132541396 0.2821303010 2211 1311867244.2024741173 0.0573716722 0.0536731036 0.0698473677 0.0057470936 0.0518780000 420725633 0 402718720 -0.0852070078 -0.0132865813 0.2838172317 2212 1311867244.2330279350 0.0588046908 0.0536754235 0.0698473677 0.0057458213 0.1442720000 418719919 0 402718720 -0.0844804421 -0.0131128784 0.2869355679 2213 1311867244.2649021149 0.0584366098 0.0536775750 0.0698473677 0.0057448479 0.0539770000 408341933 0 402718720 -0.0852485970 -0.0134057105 0.2884996831 2214 1311867244.3010311127 0.0580303967 0.0536795410 0.0698473677 0.0057442814 0.0408200000 408345473 0 402718720 -0.0846206099 -0.0138639826 0.2906191051 2215 1311867244.3355190754 0.0578071177 0.0536814045 0.0698473677 0.0057435161 0.0410840000 408348485 0 402718720 -0.0836083889 -0.0131813250 0.2926037312 2216 1311867244.3649079800 0.0592055917 0.0536838973 0.0698473677 0.0057426866 0.0411140000 408351601 0 402718720 -0.0831688121 -0.0139084216 0.2954173684 2217 1311867244.4008760452 0.0587574355 0.0536861858 0.0698473677 0.0057425506 0.0407610000 408355053 0 402718720 -0.0825719759 -0.0131550971 0.2970649302 2218 1311867244.4329938889 0.0585649200 0.0536883854 0.0698473677 0.0057422492 0.0408410000 408358009 0 402718720 -0.0832424909 -0.0127445981 0.2992537022 2219 1311867244.4654510021 0.0589262359 0.0536907459 0.0698473677 0.0057418677 0.0483910000 408361005 0 402718720 -0.0828492343 -0.0139782019 0.3016983867 2220 1311867244.5052490234 0.0582699664 0.0536928086 0.0698473677 0.0057408033 0.0403360000 408364569 0 402718720 -0.0808683634 -0.0127580836 0.3037723303 2221 1311867244.5330989361 0.0585144311 0.0536949795 0.0698473677 0.0057400959 0.0400510000 408367501 0 402718720 -0.0790448785 -0.0124747232 0.3060834706 2222 1311867244.5669400692 0.0589577779 0.0536973480 0.0698473677 0.0057388666 0.0418440000 408370641 0 402718720 -0.0797599256 -0.0121045485 0.3088869452 2223 1311867244.6027030945 0.0584462546 0.0536994843 0.0698473677 0.0057423392 0.0527590000 408373933 0 402718720 -0.0792399123 -0.0117716063 0.3108629584 2224 1311867244.6328020096 0.0586590432 0.0537017143 0.0698473677 0.0057426155 0.0417350000 408377001 0 402718720 -0.0780405402 -0.0106730144 0.3132802546 2225 1311867244.6672449112 0.0587430485 0.0537039801 0.0698473677 0.0057427743 0.0383410000 408380213 0 402718720 -0.0771123767 -0.0114108641 0.3157688379 2226 1311867244.7012600899 0.0588663109 0.0537062992 0.0698473677 0.0057421028 0.0412200000 408383369 0 402718720 -0.0764708966 -0.0108646322 0.3180775046 2227 1311867244.7346320152 0.0600871891 0.0537091644 0.0698473677 0.0057413850 0.0412520000 408386965 0 402718720 -0.0768829286 -0.0113737416 0.3213321865 2228 1311867244.7650001049 0.0599980652 0.0537119871 0.0698473677 0.0057406316 0.0414290000 408389737 0 402718720 -0.0751283616 -0.0114348456 0.3233807683 2229 1311867244.8015320301 0.0599541552 0.0537147875 0.0698473677 0.0057401924 0.0383450000 408392957 0 402718720 -0.0744967684 -0.0100720208 0.3255048990 2230 1311867244.8331909180 0.0606091805 0.0537178792 0.0698473677 0.0057398337 0.0386950000 408396337 0 402718720 -0.0740276277 -0.0122065246 0.3282085955 2231 1311867244.8651568890 0.0599258319 0.0537206617 0.0698473677 0.0057385877 0.0517210000 408399701 0 402718720 -0.0730474368 -0.0111455768 0.3294745684 2232 1311867244.9013550282 0.0605485886 0.0537237208 0.0698473677 0.0057373638 0.0414320000 408402849 0 402718720 -0.0727783218 -0.0106416494 0.3322600722 2233 1311867244.9328739643 0.0609801486 0.0537269705 0.0698473677 0.0057363192 0.0385850000 408405677 0 402718720 -0.0731853992 -0.0119935013 0.3347914219 2234 1311867244.9652509689 0.0609977953 0.0537302251 0.0698473677 0.0057356096 0.0423220000 408409009 0 402718720 -0.0728504360 -0.0107276849 0.3371479213 2235 1311867245.0022718906 0.0608491786 0.0537334103 0.0698473677 0.0057358798 0.0408650000 408412605 0 402718720 -0.0721649528 -0.0107896067 0.3389921486 2236 1311867245.0349979401 0.0611577481 0.0537367307 0.0698473677 0.0057360296 0.0388270000 408415441 0 402718720 -0.0733628422 -0.0115815178 0.3410578966 2237 1311867245.0664730072 0.0601298213 0.0537395886 0.0698473677 0.0057349482 0.0493760000 408418589 0 402718720 -0.0726408958 -0.0109784715 0.3422975838 2238 1311867245.1041638851 0.0608905330 0.0537427838 0.0698473677 0.0057339082 0.0393050000 408422121 0 402718720 -0.0728454143 -0.0105168484 0.3451002240 2239 1311867245.1338050365 0.0619874001 0.0537464661 0.0698473677 0.0057328831 0.0388610000 408424957 0 402718720 -0.0732041076 -0.0109624788 0.3475587964 2240 1311867245.1749250889 0.0635206029 0.0537508295 0.0698473677 0.0057316084 0.0506830000 408428313 0 402718720 -0.0731953084 -0.0107812099 0.3517026007 2241 1311867245.2108979225 0.0632346869 0.0537550615 0.0698473677 0.0057307909 0.0386810000 408431781 0 402718720 -0.0750196800 -0.0109122694 0.3538773656 2242 1311867245.2429010868 0.0636205524 0.0537594618 0.0698473677 0.0057303619 0.0400780000 408435001 0 402718720 -0.0738587677 -0.0113548897 0.3559611142 2243 1311867245.2755670547 0.0632049665 0.0537636729 0.0698473677 0.0057297072 0.0638370000 408438101 0 402718720 -0.0759495497 -0.0117871873 0.3577660620 2244 1311867245.3120090961 0.0635433272 0.0537680311 0.0698473677 0.0057285203 0.0405820000 408441377 0 402718720 -0.0759544447 -0.0121051557 0.3605144620 2245 1311867245.3430099487 0.0633396879 0.0537722946 0.0698473677 0.0057273364 0.0569630000 408444541 0 402718720 -0.0760285929 -0.0126997456 0.3623647988 2246 1311867245.3749370575 0.0641185120 0.0537769011 0.0698473677 0.0057267328 0.0404330000 408447889 0 402718720 -0.0773635283 -0.0112138577 0.3651588559 2247 1311867245.4122350216 0.0638279095 0.0537813742 0.0698473677 0.0057262026 0.0385780000 408451389 0 402718720 -0.0784974843 -0.0118909776 0.3678917587 2248 1311867245.4428830147 0.0635952353 0.0537857398 0.0698473677 0.0057280581 0.0474090000 409208745 0 402718720 -0.0782044157 -0.0114301480 0.3692212105 2249 1311867245.4751451015 0.0640265048 0.0537902933 0.0698473677 0.0057268085 0.1376260000 409176725 0 402718720 -0.0789737701 -0.0105238780 0.3718308210 2250 1311867245.5108819008 0.0640551224 0.0537948554 0.0698473677 0.0057258597 0.1265970000 409181121 0 402718720 -0.0791905001 -0.0112194866 0.3747090399 2251 1311867245.5429608822 0.0638322905 0.0537993145 0.0698473677 0.0057248891 0.1405180000 409506689 0 402718720 -0.0798025653 -0.0100753941 0.3768838644 2252 1311867245.5749409199 0.0642787814 0.0538039679 0.0698473677 0.0057243260 0.0975340000 422351553 0 402718720 -0.0801997408 -0.0109771304 0.3795931041 2253 1311867245.6109130383 0.0654140413 0.0538091211 0.0698473677 0.0057262566 0.0933740000 420557647 0 402718720 -0.0815438032 -0.0122008547 0.3822748959 2254 1311867245.6428189278 0.0636215732 0.0538134744 0.0698473677 0.0057326166 0.0489990000 422083457 0 402718720 -0.0811974555 -0.0110868216 0.3837128580 2255 1311867245.6751749516 0.0656871498 0.0538187399 0.0698473677 0.0057331483 0.1516700000 420238175 0 402718720 -0.0836028308 -0.0115663856 0.3873997331 2256 1311867245.7109169960 0.0665088370 0.0538243650 0.0698473677 0.0057327222 0.0943430000 409196537 0 402718720 -0.0831768066 -0.0114301480 0.3902489245 2257 1311867245.7429819107 0.0655121729 0.0538295434 0.0698473677 0.0057315955 0.0402090000 409199901 0 402718720 -0.0828558356 -0.0116823949 0.3913042843 2258 1311867245.7752521038 0.0658816770 0.0538348810 0.0698473677 0.0057335630 0.0604410000 409202705 0 402718720 -0.0830572918 -0.0124785267 0.3938645422 2259 1311867245.8110349178 0.0662788004 0.0538403895 0.0698473677 0.0057343978 0.0394010000 409206237 0 402718720 -0.0841456354 -0.0135956705 0.3956961930 2260 1311867245.8428230286 0.0662373453 0.0538458749 0.0698473677 0.0057340932 0.0400000000 409209249 0 402718720 -0.0846383348 -0.0120432079 0.3974236250 2261 1311867245.8757770061 0.0669598505 0.0538516750 0.0698473677 0.0057334735 0.0399050000 409212613 0 402718720 -0.0848442465 -0.0136143826 0.3995748460 2262 1311867245.9110751152 0.0661488399 0.0538571114 0.0698473677 0.0057322952 0.0398720000 409215825 0 402718720 -0.0865425467 -0.0132048875 0.4006045163 2263 1311867245.9428870678 0.0662947148 0.0538626075 0.0698473677 0.0057316794 0.0391520000 409219053 0 402718720 -0.0864568949 -0.0122191720 0.4024160802 2264 1311867245.9751350880 0.0669622347 0.0538683935 0.0698473677 0.0057304743 0.0484410000 409222201 0 402718720 -0.0872084051 -0.0124317072 0.4046972990 2265 1311867246.0112419128 0.0664623156 0.0538739538 0.0698473677 0.0057292529 0.0758650000 409225525 0 402718720 -0.0881008804 -0.0123509802 0.4066212773 2266 1311867246.0429229736 0.0669344068 0.0538797174 0.0698473677 0.0057280447 0.0387240000 409228425 0 402718720 -0.0889342651 -0.0113399066 0.4092101455 2267 1311867246.0752329826 0.0669522732 0.0538854839 0.0698473677 0.0057275582 0.0386450000 409231701 0 402718720 -0.0884654745 -0.0116510764 0.4111581147 2268 1311867246.1109249592 0.0675634816 0.0538915147 0.0698473677 0.0057275458 0.0403590000 409234961 0 402718720 -0.0912678614 -0.0104760751 0.4139737189 2269 1311867246.1430890560 0.0681748092 0.0538978097 0.0698473677 0.0057264989 0.0770310000 409238069 0 402718720 -0.0913743079 -0.0103073306 0.4161869586 2270 1311867246.1749811172 0.0672718957 0.0539037014 0.0698473677 0.0057253945 0.0379670000 409241177 0 402718720 -0.0930260569 -0.0081526749 0.4175419509 2271 1311867246.2109639645 0.0672390610 0.0539095734 0.0698473677 0.0057255837 0.0401920000 409244677 0 402718720 -0.0916835219 -0.0083956644 0.4197963476 2272 1311867246.2429399490 0.0678055435 0.0539156896 0.0698473677 0.0057248488 0.0380540000 409247665 0 402718720 -0.0928281546 -0.0073761679 0.4221922159 2273 1311867246.2750649452 0.0682934821 0.0539220151 0.0698473677 0.0057239140 0.0385650000 409250733 0 402718720 -0.0927626342 -0.0057172328 0.4244230390 2274 1311867246.3108720779 0.0683690608 0.0539283682 0.0698473677 0.0057241272 0.0454200000 409254409 0 402718720 -0.0933012664 -0.0062866919 0.4266964197 2275 1311867246.3429319859 0.0686013699 0.0539348179 0.0698473677 0.0057229826 0.0524610000 409257301 0 402718720 -0.0947513431 -0.0053322278 0.4288814962 2276 1311867246.3752970695 0.0688419193 0.0539413676 0.0698473677 0.0057219419 0.0375760000 409260673 0 402718720 -0.0951598957 -0.0046429373 0.4307445288 2277 1311867246.4109311104 0.0690519586 0.0539480038 0.0698473677 0.0057210508 0.0378270000 409264013 0 402718720 -0.0942874849 -0.0044499747 0.4328282475 2278 1311867246.4430770874 0.0699505731 0.0539550286 0.0699505731 0.0057198665 0.0399080000 409266681 0 402718720 -0.0961794406 -0.0036806725 0.4354224503 2279 1311867246.4751329422 0.0695974976 0.0539618923 0.0699505731 0.0057187176 0.0382460000 409270293 0 402718720 -0.0965142474 -0.0031316467 0.4365051389 2280 1311867246.5109679699 0.0703674629 0.0539690878 0.0703674629 0.0057179546 0.0381360000 409273649 0 402718720 -0.0961904526 -0.0030790120 0.4386760294 2281 1311867246.5431129932 0.0704507083 0.0539763134 0.0704507083 0.0057168392 0.0375860000 409276645 0 402718720 -0.0969527066 -0.0033288673 0.4397951663 2282 1311867246.5752038956 0.0705421269 0.0539835727 0.0705421269 0.0057156163 0.0372380000 409279785 0 402718720 -0.0969537199 -0.0029387474 0.4408729970 2283 1311867246.6111249924 0.0702821910 0.0539907118 0.0705421269 0.0057144834 0.0390020000 409282917 0 402718720 -0.0963067114 -0.0033456832 0.4417208433 2284 1311867246.6431870461 0.0704746395 0.0539979290 0.0705421269 0.0057135181 0.0385960000 409286193 0 402718720 -0.0972459167 -0.0030736327 0.4433192611 2285 1311867246.6751689911 0.0701880679 0.0540050144 0.0705421269 0.0057126081 0.0498670000 409289341 0 402718720 -0.0968340263 -0.0033155680 0.4438058436 2286 1311867246.7110559940 0.0699919090 0.0540120078 0.0705421269 0.0057115146 0.0375810000 409292793 0 402718720 -0.0973090529 -0.0036845133 0.4443505406 2287 1311867246.7433049679 0.0703018308 0.0540191305 0.0705421269 0.0057104105 0.0482780000 410053761 0 402718720 -0.0985757411 -0.0037453398 0.4452805221 2288 1311867246.7749860287 0.0699553117 0.0540260957 0.0705421269 0.0057095338 0.1348100000 410020377 0 402718720 -0.0987690091 -0.0034335926 0.4453061223 2289 1311867246.8111929893 0.0706087798 0.0540333402 0.0706087798 0.0057083906 0.1228180000 410023837 0 402718720 -0.0984618664 -0.0038653761 0.4462845922 2290 1311867246.8430919647 0.0706696287 0.0540406049 0.0706696287 0.0057071781 0.1156070000 415745637 0 402718720 -0.0986873135 -0.0044222325 0.4468038976 2291 1311867246.8750779629 0.0706534237 0.0540478563 0.0706696287 0.0057061894 0.1045800000 424826713 0 402718720 -0.0989465639 -0.0040132329 0.4473077655 2292 1311867246.9111549854 0.0707954466 0.0540551632 0.0707954466 0.0057055998 0.0836630000 423210057 0 402718720 -0.0983802974 -0.0054262802 0.4478442669 2293 1311867246.9430611134 0.0709275827 0.0540625215 0.0709275827 0.0057045472 0.0604080000 423598929 0 402718720 -0.0987756401 -0.0049090758 0.4484966695 2294 1311867246.9751238823 0.0708950311 0.0540698591 0.0709275827 0.0057034201 0.1468740000 421762655 0 402718720 -0.0996483713 -0.0047283843 0.4491942227 2295 1311867247.0109090805 0.0708325431 0.0540771631 0.0709275827 0.0057023220 0.0497100000 410041205 0 402718720 -0.0994209200 -0.0051052645 0.4496401846 2296 1311867247.0440731049 0.0707914457 0.0540844428 0.0709275827 0.0057011852 0.0416200000 410044665 0 402718720 -0.0994393751 -0.0054608732 0.4501976073 2297 1311867247.0751919746 0.0707794651 0.0540917110 0.0709275827 0.0057001703 0.0508650000 410047821 0 402718720 -0.0998257324 -0.0049294233 0.4506092668 2298 1311867247.1112151146 0.0710085779 0.0540990726 0.0710085779 0.0056991060 0.0405130000 410050889 0 402718720 -0.1005201116 -0.0046806708 0.4512842596 2299 1311867247.1430439949 0.0710151643 0.0541064306 0.0710151643 0.0056980321 0.0413350000 410054117 0 402718720 -0.0999165177 -0.0050371364 0.4516675472 2300 1311867247.1751630306 0.0716490149 0.0541140578 0.0716490149 0.0056970714 0.0529860000 410057201 0 402718720 -0.1009079665 -0.0050752461 0.4525687993 2301 1311867247.2113189697 0.0722873509 0.0541219558 0.0722873509 0.0056958556 0.0519430000 410060349 0 402718720 -0.1017109007 -0.0063746199 0.4530745745 2302 1311867247.2437279224 0.0714140460 0.0541294676 0.0722873509 0.0056946805 0.0528970000 410063625 0 402718720 -0.1010216027 -0.0066825151 0.4518879950 2303 1311867247.2777190208 0.0718073994 0.0541371436 0.0722873509 0.0056936974 0.0405160000 410067141 0 402718720 -0.1015041247 -0.0066712722 0.4517622292 2304 1311867247.3109691143 0.0720032305 0.0541448980 0.0722873509 0.0056926785 0.0405570000 410069881 0 402718720 -0.1030164883 -0.0075660497 0.4512248337 2305 1311867247.3432049751 0.0715457201 0.0541524472 0.0722873509 0.0056916297 0.0395450000 410073157 0 402718720 -0.1028601229 -0.0074624009 0.4499901235 2306 1311867247.3753070831 0.0717060715 0.0541600593 0.0722873509 0.0056905166 0.0400700000 410076305 0 402718720 -0.1024824232 -0.0080889314 0.4493474662 2307 1311867247.4116749763 0.0709976628 0.0541673578 0.0722873509 0.0056896941 0.0406580000 410079621 0 402718720 -0.1032203883 -0.0096709020 0.4473887086 2308 1311867247.4440929890 0.0709794611 0.0541746421 0.0722873509 0.0056891340 0.0501600000 410082777 0 402718720 -0.1032114178 -0.0093453713 0.4460465908 2309 1311867247.4751029015 0.0706727132 0.0541817872 0.0722873509 0.0056885860 0.0536470000 410085925 0 402718720 -0.1021440551 -0.0112939104 0.4443848729 2310 1311867247.5110449791 0.0710130632 0.0541890735 0.0722873509 0.0056893857 0.0398050000 410089121 0 402718720 -0.1020628437 -0.0123035833 0.4431698918 2311 1311867247.5430850983 0.0703265294 0.0541960563 0.0722873509 0.0056912922 0.0410780000 410092237 0 402718720 -0.1021934599 -0.0118476599 0.4406122863 2312 1311867247.5751209259 0.0700760335 0.0542029249 0.0722873509 0.0056985220 0.0394880000 410095345 0 402718720 -0.1014891863 -0.0143011883 0.4391286373 2313 1311867247.6114599705 0.0706317797 0.0542100277 0.0722873509 0.0057027247 0.0411370000 410098853 0 402718720 -0.1015347913 -0.0144264735 0.4370635152 2314 1311867247.6431109905 0.0699930191 0.0542168483 0.0722873509 0.0057019176 0.0422220000 410101769 0 402718720 -0.1004699543 -0.0153522603 0.4343639016 2315 1311867247.6750760078 0.0693230703 0.0542233737 0.0722873509 0.0057030983 0.0520100000 410105061 0 402718720 -0.1005596519 -0.0174761079 0.4315801859 2316 1311867247.7112369537 0.0696858391 0.0542300501 0.0722873509 0.0057020596 0.0619580000 410108713 0 402718720 -0.0985370055 -0.0188896172 0.4282944202 2317 1311867247.7431221008 0.0690105110 0.0542364292 0.0722873509 0.0057010462 0.0417650000 410111437 0 402718720 -0.0976067260 -0.0182546042 0.4249445200 2318 1311867247.7750411034 0.0686704740 0.0542426561 0.0722873509 0.0056999137 0.0399620000 410114489 0 402718720 -0.0980850607 -0.0187737830 0.4225017130 2319 1311867247.8111629486 0.0687084571 0.0542488941 0.0722873509 0.0056988106 0.0421320000 410117717 0 402718720 -0.0970453471 -0.0199229605 0.4197666049 2320 1311867247.8438889980 0.0685664937 0.0542550655 0.0722873509 0.0056988636 0.0422300000 410121177 0 402718720 -0.0966438204 -0.0188475884 0.4174748957 2321 1311867247.8752439022 0.0681788549 0.0542610645 0.0722873509 0.0056977134 0.0400410000 410124141 0 402718720 -0.0973892137 -0.0195301510 0.4153926075 2322 1311867247.9113290310 0.0681156889 0.0542670312 0.0722873509 0.0056974909 0.0505080000 410127465 0 402718720 -0.0953198001 -0.0207296312 0.4130346179 2323 1311867247.9430620670 0.0676700696 0.0542728009 0.0722873509 0.0056970755 0.0398440000 410130765 0 402718720 -0.0946745202 -0.0195721425 0.4107758999 2324 1311867247.9769830704 0.0683746934 0.0542788689 0.0722873509 0.0056959724 0.0426730000 410134177 0 402718720 -0.0945239961 -0.0206805207 0.4095862806 2325 1311867248.0109910965 0.0685055330 0.0542849878 0.0722873509 0.0056951358 0.0426840000 410137229 0 402718720 -0.0935488045 -0.0223633423 0.4074145257 2326 1311867248.0431969166 0.0677516684 0.0542907775 0.0722873509 0.0056940307 0.0407050000 410140369 0 402718720 -0.0925306305 -0.0211330652 0.4045432806 2327 1311867248.0751419067 0.0679529235 0.0542966486 0.0722873509 0.0056937027 0.0423370000 410143437 0 402718720 -0.0918390825 -0.0222887173 0.4024279416 2328 1311867248.1121830940 0.0677805021 0.0543024407 0.0722873509 0.0056930893 0.0428600000 410146689 0 402718720 -0.0925232619 -0.0223355368 0.3996307850 2329 1311867248.1431720257 0.0673096627 0.0543080255 0.0722873509 0.0056919967 0.0508940000 410150053 0 402718720 -0.0916303843 -0.0223775469 0.3967588544 2330 1311867248.1757500172 0.0676871315 0.0543137677 0.0722873509 0.0056908634 0.0423940000 410153273 0 402718720 -0.0903414190 -0.0227623135 0.3945790231 2331 1311867248.2111859322 0.0666653961 0.0543190665 0.0722873509 0.0056896630 0.0432140000 410156349 0 402718720 -0.0908960402 -0.0230755210 0.3914652467 2332 1311867248.2431430817 0.0666281506 0.0543243448 0.0722873509 0.0056885752 0.0413700000 410159417 0 402718720 -0.0903482065 -0.0222899802 0.3889960647 2333 1311867248.2755289078 0.0667615980 0.0543296759 0.0722873509 0.0056873964 0.0411030000 410162757 0 402718720 -0.0894798562 -0.0221008658 0.3867297769 2334 1311867248.3112230301 0.0663589984 0.0543348298 0.0722873509 0.0056870411 0.0420290000 410165705 0 402718720 -0.0894273221 -0.0225883685 0.3842048347 2335 1311867248.3434588909 0.0665567070 0.0543400640 0.0722873509 0.0056866853 0.0432000000 410168821 0 402718720 -0.0886082277 -0.0215193070 0.3817937076 2336 1311867248.3752219677 0.0664377138 0.0543452428 0.0722873509 0.0056865690 0.0520860000 410171921 0 402718720 -0.0879814625 -0.0208898373 0.3793151081 2337 1311867248.4115560055 0.0656910762 0.0543500977 0.0722873509 0.0056866092 0.0527870000 410175365 0 402718720 -0.0878718793 -0.0208576769 0.3766866624 2338 1311867248.4431369305 0.0660359859 0.0543550959 0.0722873509 0.0056854047 0.0425460000 410178329 0 402718720 -0.0867348909 -0.0203530155 0.3744398355 2339 1311867248.4759230614 0.0659070164 0.0543600347 0.0722873509 0.0056843234 0.0402560000 410181789 0 402718720 -0.0867636502 -0.0201671496 0.3720360398 2340 1311867248.5111510754 0.0657878816 0.0543649184 0.0722873509 0.0056834730 0.0430770000 410184833 0 402718720 -0.0863217413 -0.0197166316 0.3700740933 2341 1311867248.5431890488 0.0663743392 0.0543700485 0.0722873509 0.0056823007 0.0428730000 410188165 0 402718720 -0.0861032978 -0.0206302442 0.3679980934 2342 1311867248.5751869678 0.0653656125 0.0543747434 0.0722873509 0.0056811938 0.0411140000 410191145 0 402718720 -0.0846965611 -0.0200581774 0.3650017381 2343 1311867248.6114389896 0.0657415688 0.0543795948 0.0722873509 0.0056803015 0.0427700000 410194397 0 402718720 -0.0840527564 -0.0199164487 0.3631242514 2344 1311867248.6432449818 0.0658599809 0.0543844926 0.0722873509 0.0056791569 0.0641060000 410197569 0 402718720 -0.0848545730 -0.0203489549 0.3605695665 2345 1311867248.6753089428 0.0650172606 0.0543890268 0.0722873509 0.0056780262 0.0421140000 410200725 0 402718720 -0.0835151225 -0.0189246684 0.3574686646 2346 1311867248.7112829685 0.0649511069 0.0543935290 0.0722873509 0.0056771448 0.0419210000 410203977 0 402718720 -0.0835297108 -0.0181794241 0.3545048833 2347 1311867248.7433049679 0.0644893870 0.0543978306 0.0722873509 0.0056768832 0.0420760000 410207149 0 402718720 -0.0838465914 -0.0188940689 0.3514566123 2348 1311867248.7762219906 0.0647569671 0.0544022425 0.0722873509 0.0056759066 0.0402830000 410210305 0 402718720 -0.0823696405 -0.0170000568 0.3492832184 2349 1311867248.8111898899 0.0649598837 0.0544067370 0.0722873509 0.0056754626 0.0408040000 410213589 0 402718720 -0.0819211081 -0.0173020437 0.3466271460 2350 1311867248.8433189392 0.0644635037 0.0544110165 0.0722873509 0.0056800877 0.0562420000 410216737 0 402718720 -0.0813109130 -0.0181500502 0.3436634243 2351 1311867248.8755309582 0.0635838062 0.0544149181 0.0722873509 0.0056799313 0.0408990000 410219829 0 402718720 -0.0796926916 -0.0174300820 0.3397277594 2352 1311867248.9111700058 0.0639845356 0.0544189869 0.0722873509 0.0056787310 0.0669010000 410223217 0 402718720 -0.0794745237 -0.0173874274 0.3369359374 2353 1311867248.9430971146 0.0644016936 0.0544232294 0.0722873509 0.0056777515 0.0402300000 410226053 0 402718720 -0.0794553980 -0.0184875391 0.3344045877 2354 1311867248.9766070843 0.0636613369 0.0544271538 0.0722873509 0.0056768137 0.0540510000 410229697 0 402718720 -0.0774203613 -0.0177392326 0.3305500448 2355 1311867249.0112600327 0.0629719421 0.0544307822 0.0722873509 0.0056757464 0.0412340000 410232861 0 402718720 -0.0752720833 -0.0169456936 0.3267808259 2356 1311867249.0432310104 0.0634984076 0.0544346309 0.0722873509 0.0056745858 0.0545210000 410235817 0 402718720 -0.0743509680 -0.0174420774 0.3241280317 2357 1311867249.0799250603 0.0642126203 0.0544387794 0.0722873509 0.0056736209 0.0588540000 410239069 0 402718720 -0.0753164142 -0.0169222131 0.3220651448 2358 1311867249.1120550632 0.0627526194 0.0544423052 0.0722873509 0.0056725291 0.0402950000 410242617 0 402718720 -0.0723368600 -0.0160159394 0.3178533018 2359 1311867249.1435980797 0.0631104335 0.0544459797 0.0722873509 0.0056720925 0.0398130000 410245493 0 402718720 -0.0706903338 -0.0162840560 0.3155048490 2360 1311867249.1785130501 0.0635825321 0.0544498511 0.0722873509 0.0056711331 0.0532650000 410248865 0 402718720 -0.0703058019 -0.0170702245 0.3130721152 2361 1311867249.2113580704 0.0630041212 0.0544534743 0.0722873509 0.0056702365 0.0400290000 410252021 0 402718720 -0.0688625425 -0.0148336273 0.3098099828 2362 1311867249.2432780266 0.0627706945 0.0544569956 0.0722873509 0.0056695737 0.0413930000 410255081 0 402718720 -0.0669167191 -0.0152900815 0.3065883219 2363 1311867249.2773559093 0.0626353100 0.0544604565 0.0722873509 0.0056691850 0.0779830000 410258365 0 402718720 -0.0666587949 -0.0173663497 0.3036392331 2364 1311867249.3112919331 0.0621234253 0.0544636981 0.0722873509 0.0056691846 0.0410340000 410261513 0 402718720 -0.0651654899 -0.0148805790 0.3004160821 2365 1311867249.3437249660 0.0626539439 0.0544671612 0.0722873509 0.0056684003 0.0412860000 410264717 0 402718720 -0.0656741485 -0.0141549204 0.2981700599 2366 1311867249.3768579960 0.0625764206 0.0544705886 0.0722873509 0.0056704755 0.0403650000 410267937 0 402718720 -0.0626258254 -0.0163127221 0.2958046794 2367 1311867249.4112169743 0.0617536306 0.0544736655 0.0722873509 0.0056699030 0.0402310000 410271077 0 402718720 -0.0615318976 -0.0150692835 0.2919342220 2368 1311867249.4432210922 0.0618863367 0.0544767959 0.0722873509 0.0056687124 0.0492630000 410274249 0 402718720 -0.0607293658 -0.0153024867 0.2894814014 2369 1311867249.4764440060 0.0627048388 0.0544802691 0.0722873509 0.0056676282 0.0400850000 410277453 0 402718720 -0.0610565506 -0.0159210805 0.2875502408 2370 1311867249.5111339092 0.0619142130 0.0544834057 0.0722873509 0.0056671489 0.0401860000 410280737 0 402718720 -0.0593510084 -0.0159106590 0.2840143740 2371 1311867249.5432300568 0.0610224828 0.0544861637 0.0722873509 0.0056661849 0.0405080000 410283885 0 402718720 -0.0577814803 -0.0145432837 0.2804445028 2372 1311867249.5759820938 0.0623519123 0.0544894798 0.0722873509 0.0056652906 0.0406030000 410287089 0 402718720 -0.0593663119 -0.0160499606 0.2790665627 2373 1311867249.6112229824 0.0615894981 0.0544924718 0.0722873509 0.0056642252 0.0518210000 410290485 0 402718720 -0.0584868118 -0.0166451912 0.2757617533 2374 1311867249.6433780193 0.0607524998 0.0544951087 0.0722873509 0.0056635316 0.0761620000 410293569 0 402718720 -0.0574421920 -0.0146904532 0.2725208700 2375 1311867249.6751029491 0.0616555996 0.0544981236 0.0722873509 0.0056647509 0.0404240000 410296589 0 402718720 -0.0577236004 -0.0152453277 0.2713454366 2376 1311867249.7111389637 0.0611527711 0.0545009244 0.0722873509 0.0056640941 0.0402150000 410299537 0 402718720 -0.0567583367 -0.0154077616 0.2678591311 2377 1311867249.7432470322 0.0607286580 0.0545035444 0.0722873509 0.0056638806 0.0412040000 410302997 0 402718720 -0.0561212040 -0.0132411402 0.2649414837 2378 1311867249.7751579285 0.0595682561 0.0545056742 0.0722873509 0.0056666663 0.0407590000 410306041 0 402718720 -0.0558537915 -0.0133479163 0.2622851431 2379 1311867249.8111488819 0.0604985170 0.0545081933 0.0722873509 0.0056661507 0.0470470000 410309517 0 402718720 -0.0545077845 -0.0129529089 0.2602981627 2380 1311867249.8433248997 0.0598497242 0.0545104376 0.0722873509 0.0056651026 0.0409760000 410312481 0 402718720 -0.0541836694 -0.0115428083 0.2573189735 2381 1311867249.8784089088 0.0605656877 0.0545129808 0.0722873509 0.0056643510 0.0408260000 410315613 0 402718720 -0.0549881943 -0.0104240943 0.2555428147 2382 1311867249.9112401009 0.0607465319 0.0545155977 0.0722873509 0.0056632140 0.0406750000 410319145 0 402718720 -0.0545994304 -0.0105168018 0.2528547347 2383 1311867249.9432768822 0.0602548160 0.0545180061 0.0722873509 0.0056624431 0.0414630000 410322109 0 402718720 -0.0539133102 -0.0103441868 0.2499503642 2384 1311867249.9751698971 0.0604411624 0.0545204907 0.0722873509 0.0056619840 0.0416680000 410325329 0 402718720 -0.0538111143 -0.0094813518 0.2472671717 2385 1311867250.0117108822 0.0603313074 0.0545229271 0.0722873509 0.0056620485 0.0510330000 410328469 0 402718720 -0.0518734381 -0.0090456735 0.2443037480 2386 1311867250.0434269905 0.0595902577 0.0545250508 0.0722873509 0.0056614270 0.0414240000 410331633 0 402718720 -0.0522673056 -0.0094880890 0.2404019982 2387 1311867250.0767190456 0.0591947027 0.0545270071 0.0722873509 0.0056612104 0.0416080000 410334869 0 402718720 -0.0525268130 -0.0102502499 0.2373040020 2388 1311867250.1116099358 0.0594941825 0.0545290872 0.0722873509 0.0056604569 0.0410780000 410338473 0 402718720 -0.0513405949 -0.0081269164 0.2345893234 2389 1311867250.1432220936 0.0598672219 0.0545313216 0.0722873509 0.0056593485 0.0411830000 410341181 0 402718720 -0.0502694361 -0.0088576861 0.2319018394 2390 1311867250.1758980751 0.0594006628 0.0545333590 0.0722873509 0.0056585074 0.0418780000 410344321 0 402718720 -0.0502846763 -0.0092561841 0.2285582572 2391 1311867250.2133369446 0.0593280867 0.0545353644 0.0722873509 0.0056574298 0.0411800000 410347789 0 402718720 -0.0498517938 -0.0085545927 0.2252186686 2392 1311867250.2457129955 0.0594377182 0.0545374138 0.0722873509 0.0056571409 0.0411850000 410351009 0 402718720 -0.0500136167 -0.0072644949 0.2227718532 2393 1311867250.2751679420 0.0589098483 0.0545392410 0.0722873509 0.0056561710 0.0787980000 410353789 0 402718720 -0.0481329858 -0.0071248449 0.2198430449 2394 1311867250.3114409447 0.0594057217 0.0545412738 0.0722873509 0.0056551157 0.0411770000 410357297 0 402718720 -0.0477224439 -0.0065939259 0.2174782753 2395 1311867250.3431971073 0.0598239154 0.0545434795 0.0722873509 0.0056542264 0.0419060000 410360453 0 402718720 -0.0474699736 -0.0061635841 0.2155969441 2396 1311867250.3780639172 0.0592763908 0.0545454548 0.0722873509 0.0056534199 0.0408070000 410363601 0 402718720 -0.0483580381 -0.0064133406 0.2127917409 2397 1311867250.4116489887 0.0595200621 0.0545475302 0.0722873509 0.0056530864 0.0529110000 410366693 0 402718720 -0.0468847193 -0.0063046385 0.2103289664 2398 1311867250.4441781044 0.0585266203 0.0545491895 0.0722873509 0.0056520976 0.0802990000 410369865 0 402718720 -0.0459428988 -0.0044961516 0.2072017193 2399 1311867250.4793250561 0.0593586974 0.0545511943 0.0722873509 0.0056511046 0.0414550000 410373253 0 402718720 -0.0454215370 -0.0038129557 0.2053258717 2400 1311867250.5113220215 0.0586516559 0.0545529028 0.0722873509 0.0056506136 0.0417080000 410376401 0 402718720 -0.0446535498 -0.0056517702 0.2026115209 2401 1311867250.5443398952 0.0593981221 0.0545549208 0.0722873509 0.0056507395 0.0418790000 410379901 0 402718720 -0.0454639830 -0.0039166678 0.2008177936 2402 1311867250.5793490410 0.0583872460 0.0545565163 0.0722873509 0.0056500489 0.0420850000 410383097 0 402718720 -0.0432295427 -0.0026890263 0.1975622326 2403 1311867250.6114881039 0.0590937510 0.0545584045 0.0722873509 0.0056489746 0.0473700000 410386125 0 402718720 -0.0435043164 -0.0053095818 0.1960399598 2404 1311867250.6433761120 0.0582923181 0.0545599577 0.0722873509 0.0056479748 0.0416780000 410389177 0 402718720 -0.0436641611 -0.0035810005 0.1928421408 2405 1311867250.6795539856 0.0591215789 0.0545618544 0.0722873509 0.0056471466 0.0421030000 410392669 0 402718720 -0.0423749462 -0.0025902260 0.1909188926 2406 1311867250.7112920284 0.0593162179 0.0545638304 0.0722873509 0.0056461027 0.0423680000 410395497 0 402718720 -0.0427896306 -0.0035196058 0.1889588237 2407 1311867250.7445890903 0.0585438013 0.0545654839 0.0722873509 0.0056467447 0.0539840000 410398909 0 402718720 -0.0411535017 -0.0039867163 0.1862113774 2408 1311867250.7792830467 0.0588111244 0.0545672471 0.0722873509 0.0056462351 0.0424740000 410402153 0 402718720 -0.0403029248 -0.0036281245 0.1839450449 2409 1311867250.8145580292 0.0594297461 0.0545692655 0.0722873509 0.0056455136 0.0522170000 410405349 0 402718720 -0.0413553938 -0.0032073818 0.1824868619 2410 1311867250.8433599472 0.0586529672 0.0545709600 0.0722873509 0.0056446215 0.0422970000 410408273 0 402718720 -0.0411544889 -0.0052756481 0.1800730228 2411 1311867250.8792760372 0.0578517057 0.0545723208 0.0722873509 0.0056469739 0.0426320000 410411597 0 402718720 -0.0394380614 -0.0047011999 0.1776053607 2412 1311867250.9116361141 0.0580545999 0.0545737645 0.0722873509 0.0056462327 0.0421790000 410414817 0 402718720 -0.0398066491 -0.0055913199 0.1757201850 2413 1311867250.9433720112 0.0585183389 0.0545753992 0.0722873509 0.0056456163 0.0522720000 410417845 0 402718720 -0.0407211185 -0.0056903632 0.1739608049 2414 1311867250.9793050289 0.0582766347 0.0545769325 0.0722873509 0.0056445584 0.0538790000 410421041 0 402718720 -0.0399198569 -0.0041821925 0.1716005057 2415 1311867251.0112459660 0.0577997528 0.0545782670 0.0722873509 0.0056441673 0.0533110000 410424397 0 402718720 -0.0392583050 -0.0045044636 0.1696624011 2416 1311867251.0437910557 0.0583402067 0.0545798241 0.0722873509 0.0056430304 0.0416440000 410427353 0 402718720 -0.0400313772 -0.0059773801 0.1680163294 2417 1311867251.0793159008 0.0584308133 0.0545814173 0.0722873509 0.0056422092 0.0418730000 410430677 0 402718720 -0.0395305753 -0.0051941480 0.1658505052 2418 1311867251.1115839481 0.0575471073 0.0545826438 0.0722873509 0.0056410561 0.0421470000 410433753 0 402718720 -0.0393446535 -0.0036449870 0.1633269042 2419 1311867251.1432809830 0.0578065068 0.0545839766 0.0722873509 0.0056400882 0.0423450000 410437029 0 402718720 -0.0403575897 -0.0056553483 0.1617290378 2420 1311867251.1794250011 0.0569258705 0.0545849443 0.0722873509 0.0056402128 0.0427890000 410440481 0 402718720 -0.0400434956 -0.0052087782 0.1586916298 2421 1311867251.2113831043 0.0579278395 0.0545863251 0.0722873509 0.0056422926 0.0510140000 410443693 0 402718720 -0.0399348959 -0.0038551334 0.1574128270 2422 1311867251.2472319603 0.0572987162 0.0545874450 0.0722873509 0.0056429919 0.0514040000 410446777 0 402718720 -0.0418888070 -0.0063016107 0.1552253813 2423 1311867251.2793700695 0.0582917891 0.0545889738 0.0722873509 0.0056421803 0.0421590000 410449933 0 402718720 -0.0407926068 -0.0060460586 0.1538961232 2424 1311867251.3133869171 0.0582034178 0.0545904649 0.0722873509 0.0056418881 0.0419440000 410453257 0 402718720 -0.0416882709 -0.0051501654 0.1515448987 2425 1311867251.3432419300 0.0564763173 0.0545912426 0.0722873509 0.0056470824 0.0417600000 410456165 0 402718720 -0.0409339927 -0.0064205937 0.1489876658 2426 1311867251.3801820278 0.0574249551 0.0545924107 0.0722873509 0.0056462358 0.0418630000 410459673 0 402718720 -0.0410678945 -0.0058912281 0.1473444998 2427 1311867251.4113550186 0.0568420626 0.0545933376 0.0722873509 0.0056450758 0.0417470000 410462885 0 402718720 -0.0413735583 -0.0060023563 0.1450693905 2428 1311867251.4433960915 0.0566752926 0.0545941951 0.0722873509 0.0056443408 0.0726890000 410465609 0 402718720 -0.0410471894 -0.0058391551 0.1427647322 2429 1311867251.4793379307 0.0568651520 0.0545951300 0.0722873509 0.0056432220 0.0420070000 410469061 0 402718720 -0.0410354137 -0.0062766522 0.1411435902 2430 1311867251.5175099373 0.0562961437 0.0545958300 0.0722873509 0.0056423528 0.0422820000 410472305 0 402718720 -0.0420410372 -0.0064078122 0.1389438212 2431 1311867251.5431749821 0.0572516769 0.0545969225 0.0722873509 0.0056415614 0.0414990000 410475421 0 402718720 -0.0413925089 -0.0065389685 0.1379000396 2432 1311867251.5795340538 0.0570400506 0.0545979271 0.0722873509 0.0056404427 0.0421060000 410478673 0 402718720 -0.0400090553 -0.0060096029 0.1355349123 2433 1311867251.6119680405 0.0571658760 0.0545989825 0.0722873509 0.0056393305 0.0808900000 410481685 0 402718720 -0.0400959216 -0.0058633052 0.1339461505 2434 1311867251.6432960033 0.0575120635 0.0546001794 0.0722873509 0.0056382110 0.0416630000 410484873 0 402718720 -0.0413224995 -0.0070086708 0.1325345039 2435 1311867251.6797280312 0.0567551628 0.0546010644 0.0722873509 0.0056400983 0.0416550000 410488261 0 402718720 -0.0409100056 -0.0064399494 0.1296245307 2436 1311867251.7123379707 0.0559912622 0.0546016350 0.0722873509 0.0056392399 0.0427480000 410491481 0 402718720 -0.0406376049 -0.0060235551 0.1270079017 2437 1311867251.7434990406 0.0565622039 0.0546024396 0.0722873509 0.0056384175 0.0427610000 410494453 0 402718720 -0.0401088595 -0.0063278330 0.1258289665 2438 1311867251.7797439098 0.0564475134 0.0546031963 0.0722873509 0.0056372679 0.0509620000 410497513 0 402718720 -0.0420466475 -0.0080307079 0.1234115362 2439 1311867251.8112530708 0.0557457432 0.0546036648 0.0722873509 0.0056366804 0.0565040000 410500661 0 402718720 -0.0409808382 -0.0061744656 0.1207682118 2440 1311867251.8433279991 0.0565925390 0.0546044799 0.0722873509 0.0056357944 0.0727770000 410504161 0 402718720 -0.0411292501 -0.0053651715 0.1200495288 2441 1311867251.8805420399 0.0556349643 0.0546049021 0.0722873509 0.0056350248 0.0423770000 410507573 0 402718720 -0.0422147885 -0.0070572039 0.1176573858 2442 1311867251.9112489223 0.0558588542 0.0546054156 0.0722873509 0.0056340030 0.0428910000 410510529 0 402718720 -0.0402084365 -0.0048875688 0.1161564067 2443 1311867251.9432179928 0.0552443825 0.0546056771 0.0722873509 0.0056329780 0.0435220000 410513989 0 402718720 -0.0401254222 -0.0051932558 0.1138455123 2444 1311867251.9800109863 0.0551634617 0.0546059053 0.0722873509 0.0056320836 0.0426600000 410516937 0 402718720 -0.0399762690 -0.0051974393 0.1122104600 2445 1311867252.0119040012 0.0551878028 0.0546061433 0.0722873509 0.0056309593 0.0568300000 410520237 0 402718720 -0.0397018716 -0.0044051101 0.1106206104 2446 1311867252.0441029072 0.0545267202 0.0546061109 0.0722873509 0.0056299966 0.0431660000 410523401 0 402718720 -0.0391846225 -0.0043531070 0.1076900885 2447 1311867252.0794539452 0.0558501370 0.0546066192 0.0722873509 0.0056289164 0.0440320000 410526693 0 402718720 -0.0382938012 -0.0048635239 0.1062790379 2448 1311867252.1122460365 0.0559479855 0.0546071672 0.0722873509 0.0056291932 0.0432550000 410529825 0 402718720 -0.0402643271 -0.0051039150 0.1037995592 2449 1311867252.1432950497 0.0548235029 0.0546072555 0.0722873509 0.0056302912 0.0437520000 410533053 0 402718720 -0.0396313742 -0.0066259070 0.1002716273 2450 1311867252.1794359684 0.0549976677 0.0546074149 0.0722873509 0.0056292360 0.0430670000 410536121 0 402718720 -0.0399176143 -0.0065417793 0.0970952958 2451 1311867252.2113459110 0.0550807267 0.0546076080 0.0722873509 0.0056299006 0.0435800000 410539261 0 402718720 -0.0397865362 -0.0071448986 0.0944868997 2452 1311867252.2432808876 0.0546002425 0.0546076050 0.0722873509 0.0056294787 0.0419980000 410542537 0 402718720 -0.0417594574 -0.0098045105 0.0912441239 2453 1311867252.2794110775 0.0542647727 0.0546074652 0.0722873509 0.0056296069 0.0433570000 410545813 0 402718720 -0.0407175273 -0.0101169832 0.0879939422 2454 1311867252.3112668991 0.0536904149 0.0546070915 0.0722873509 0.0056293465 0.0430600000 410548961 0 402718720 -0.0409122594 -0.0101649836 0.0847059116 2455 1311867252.3450291157 0.0543332659 0.0546069800 0.0722873509 0.0056283535 0.0432860000 410551981 0 402718720 -0.0405240394 -0.0107609779 0.0825403333 2456 1311867252.3794589043 0.0544831604 0.0546069296 0.0722873509 0.0056273516 0.0429400000 410555321 0 402718720 -0.0435127579 -0.0146365669 0.0800780877 2457 1311867252.4111969471 0.0543567762 0.0546068278 0.0722873509 0.0056276442 0.0432180000 410558533 0 402718720 -0.0405557789 -0.0133532640 0.0764954388 2458 1311867252.4456050396 0.0537911803 0.0546064959 0.0722873509 0.0056330656 0.0789680000 410561577 0 402718720 -0.0398165807 -0.0140120545 0.0726093426 2459 1311867252.4792900085 0.0528682806 0.0546057891 0.0722873509 0.0056420871 0.0432620000 410564773 0 402718720 -0.0403196178 -0.0163191017 0.0699013770 2460 1311867252.5112249851 0.0529407598 0.0546051122 0.0722873509 0.0056417289 0.0438900000 410568169 0 402718720 -0.0394500680 -0.0166159589 0.0666515157 2461 1311867252.5432820320 0.0531698875 0.0546045290 0.0722873509 0.0056413393 0.0432590000 410571125 0 402718720 -0.0398781113 -0.0160584152 0.0633832961 2462 1311867252.5791800022 0.0524265468 0.0546036444 0.0722873509 0.0056403534 0.0432590000 410574385 0 402718720 -0.0397485830 -0.0176363103 0.0600495003 2463 1311867252.6112799644 0.0532330796 0.0546030879 0.0722873509 0.0056398442 0.0517450000 410577533 0 402718720 -0.0420348421 -0.0194188673 0.0578040183 2464 1311867252.6432769299 0.0527806319 0.0546023483 0.0722873509 0.0056390184 0.0610780000 410580801 0 402718720 -0.0411929935 -0.0189192947 0.0538382567 2465 1311867252.6792490482 0.0527442321 0.0546015945 0.0722873509 0.0056393793 0.0432310000 410584013 0 402718720 -0.0399218090 -0.0193765629 0.0508280322 2466 1311867252.7112491131 0.0523539819 0.0546006830 0.0722873509 0.0056387703 0.0436320000 410587281 0 402718720 -0.0405444838 -0.0212155357 0.0479944386 2467 1311867252.7432410717 0.0520024709 0.0545996299 0.0722873509 0.0056376523 0.0421830000 410590245 0 402718720 -0.0401540361 -0.0219971966 0.0442710966 2468 1311867252.7792730331 0.0523064733 0.0545987007 0.0722873509 0.0056366765 0.0438370000 410593569 0 402718720 -0.0387321226 -0.0206113495 0.0408241861 2469 1311867252.8112781048 0.0518032797 0.0545975685 0.0722873509 0.0056359782 0.0431920000 410596773 0 402718720 -0.0391721986 -0.0214168318 0.0371577218 2470 1311867252.8433189392 0.0508844703 0.0545960652 0.0722873509 0.0056352177 0.0545130000 410600049 0 402718720 -0.0388608240 -0.0227089934 0.0334090739 2471 1311867252.8792660236 0.0509769768 0.0545946006 0.0722873509 0.0056354690 0.0438140000 410602997 0 402718720 -0.0386087671 -0.0214798339 0.0296020769 2472 1311867252.9112188816 0.0515749268 0.0545933790 0.0722873509 0.0056343508 0.0550340000 410606153 0 402718720 -0.0374749452 -0.0207701921 0.0278139561 2473 1311867252.9446918964 0.0510491543 0.0545919459 0.0722873509 0.0056337241 0.0439410000 410609429 0 402718720 -0.0373293944 -0.0240112003 0.0255122464 2474 1311867252.9806020260 0.0517587438 0.0545908007 0.0722873509 0.0056340322 0.0438820000 410612625 0 402718720 -0.0363519751 -0.0230321642 0.0226292033 2475 1311867253.0113809109 0.0503986403 0.0545891069 0.0722873509 0.0056336084 0.0438300000 410615965 0 402718720 -0.0355021097 -0.0215812828 0.0185136907 2476 1311867253.0434310436 0.0495171137 0.0545870584 0.0722873509 0.0056328128 0.0437680000 410619241 0 402718720 -0.0351181589 -0.0252919905 0.0156447701 2477 1311867253.0799300671 0.0495909043 0.0545850414 0.0722873509 0.0056374463 0.0802710000 410622245 0 402718720 -0.0345709436 -0.0248863343 0.0127305612 2478 1311867253.1113030910 0.0497740097 0.0545830999 0.0722873509 0.0056385131 0.0428900000 410625649 0 402718720 -0.0336173698 -0.0229288843 0.0092760418 2479 1311867253.1440761089 0.0494648218 0.0545810353 0.0722873509 0.0056380798 0.0440750000 410628733 0 402718720 -0.0347124524 -0.0252223909 0.0063728462 2480 1311867253.1794049740 0.0496059060 0.0545790291 0.0722873509 0.0056371332 0.0436230000 410631889 0 402718720 -0.0339869820 -0.0253430512 0.0035768461 2481 1311867253.2112159729 0.0496900342 0.0545770586 0.0722873509 0.0056362302 0.0428860000 410635029 0 402718720 -0.0328114033 -0.0246050321 0.0008185252 2482 1311867253.2458410263 0.0487659723 0.0545747173 0.0722873509 0.0056355156 0.0432070000 410638297 0 402718720 -0.0321750455 -0.0255209710 -0.0022710050 2483 1311867253.2793951035 0.0491797961 0.0545725445 0.0722873509 0.0056346100 0.0836690000 410641573 0 402718720 -0.0320237391 -0.0260061678 -0.0046733646 2484 1311867253.3114080429 0.0485832021 0.0545701334 0.0722873509 0.0056334974 0.0434370000 410644665 0 402718720 -0.0302046239 -0.0258295517 -0.0072967838 2485 1311867253.3445611000 0.0483524725 0.0545676313 0.0722873509 0.0056386996 0.0442020000 410647741 0 402718720 -0.0307302475 -0.0262903627 -0.0097403992 2486 1311867253.3794078827 0.0481155366 0.0545650359 0.0722873509 0.0056412973 0.0436600000 410651145 0 402718720 -0.0289202537 -0.0281016883 -0.0119647859 2487 1311867253.4129528999 0.0476821549 0.0545622684 0.0722873509 0.0056420680 0.0437570000 410654213 0 402718720 -0.0272544231 -0.0278164465 -0.0147854732 2488 1311867253.4444990158 0.0477885455 0.0545595458 0.0722873509 0.0056417021 0.0523330000 410657305 0 402718720 -0.0262993183 -0.0269925799 -0.0173028503 2489 1311867253.4804859161 0.0481725931 0.0545569798 0.0722873509 0.0056418478 0.0427030000 410660709 0 402718720 -0.0251462199 -0.0257660802 -0.0200298391 2490 1311867253.5113739967 0.0476996340 0.0545542258 0.0722873509 0.0056411298 0.0437310000 410663649 0 402718720 -0.0240045376 -0.0290662348 -0.0216328762 2491 1311867253.5441629887 0.0476019420 0.0545514348 0.0722873509 0.0056407297 0.0437990000 410667141 0 402718720 -0.0237684548 -0.0292595048 -0.0243153013 2492 1311867253.5794069767 0.0484919697 0.0545490033 0.0722873509 0.0056403235 0.0434300000 410670353 0 402718720 -0.0225826502 -0.0301528890 -0.0256864540 2493 1311867253.6118021011 0.0480402485 0.0545463925 0.0722873509 0.0056393258 0.0444000000 410673381 0 402718720 -0.0219646990 -0.0313310400 -0.0284473356 2494 1311867253.6447649002 0.0484574512 0.0545439510 0.0722873509 0.0056386917 0.0530420000 410676401 0 402718720 -0.0218169782 -0.0314199999 -0.0311337095 2495 1311867253.6799790859 0.0492414907 0.0545418258 0.0722873509 0.0056376705 0.0446380000 410679853 0 402718720 -0.0219886806 -0.0322304331 -0.0332566798 2496 1311867253.7115769386 0.0493602641 0.0545397498 0.0722873509 0.0056374666 0.0540490000 410682937 0 402718720 -0.0220473949 -0.0345513970 -0.0357893631 2497 1311867253.7435369492 0.0482975841 0.0545372500 0.0722873509 0.0056376299 0.0417890000 410685965 0 402718720 -0.0226940475 -0.0368692093 -0.0398549587 2498 1311867253.7806150913 0.0477520302 0.0545345337 0.0722873509 0.0056368522 0.0435300000 410689449 0 402718720 -0.0239014737 -0.0382368825 -0.0445286259 2499 1311867253.8113009930 0.0482141711 0.0545320046 0.0722873509 0.0056358205 0.0429200000 410692485 0 402718720 -0.0259679351 -0.0383798108 -0.0478085391 2500 1311867253.8469560146 0.0480201505 0.0545293998 0.0722873509 0.0056362030 0.0786330000 410695937 0 402718720 -0.0258773826 -0.0393831953 -0.0518308803 2501 1311867253.8792059422 0.0462789759 0.0545261010 0.0722873509 0.0056355713 0.0435520000 410698837 0 402718720 -0.0278492570 -0.0422613919 -0.0567436963 2502 1311867253.9114460945 0.0457850322 0.0545226073 0.0722873509 0.0056345710 0.0430730000 410702177 0 402718720 -0.0295487270 -0.0431183837 -0.0610701479 2503 1311867253.9461600780 0.0463819616 0.0545193550 0.0722873509 0.0056334498 0.0434340000 410705341 0 402718720 -0.0290426649 -0.0421369895 -0.0648808107 2504 1311867253.9794149399 0.0463265739 0.0545160831 0.0722873509 0.0056325233 0.0426270000 410708497 0 402718720 -0.0305563714 -0.0442002527 -0.0677431226 2505 1311867254.0119979382 0.0467138961 0.0545129685 0.0722873509 0.0056331017 0.0643340000 410711701 0 402718720 -0.0333722718 -0.0441672988 -0.0712259784 2506 1311867254.0457749367 0.0459327251 0.0545095446 0.0722873509 0.0056322772 0.0429540000 410715161 0 402718720 -0.0326156691 -0.0436218530 -0.0752843693 2507 1311867254.0793740749 0.0462031178 0.0545062313 0.0722873509 0.0056352699 0.0429880000 410717877 0 402718720 -0.0341463014 -0.0458807014 -0.0778601691 2508 1311867254.1113519669 0.0454954915 0.0545026385 0.0722873509 0.0056344015 0.0438130000 410721025 0 402718720 -0.0350449830 -0.0463938862 -0.0815004185 2509 1311867254.1476950645 0.0456115305 0.0544990948 0.0722873509 0.0056333123 0.0434760000 410724533 0 402718720 -0.0354522131 -0.0455439650 -0.0852465853 2510 1311867254.1795129776 0.0462228581 0.0544957975 0.0722873509 0.0056323036 0.0799160000 410727385 0 402718720 -0.0349430442 -0.0454798862 -0.0876962841 2511 1311867254.2114939690 0.0456597805 0.0544922786 0.0722873509 0.0056358270 0.0430110000 410730717 0 402718720 -0.0357890055 -0.0449411720 -0.0906881839 2512 1311867254.2469160557 0.0455944501 0.0544887364 0.0722873509 0.0056355702 0.0432700000 410734169 0 402718720 -0.0349438563 -0.0445996374 -0.0946602374 2513 1311867254.2798569202 0.0488164797 0.0544864793 0.0722873509 0.0056360446 0.0429940000 410737197 0 402718720 -0.0350753665 -0.0404025875 -0.0968536139 2514 1311867254.3114631176 0.0479546748 0.0544838811 0.0722873509 0.0056398199 0.0437890000 410740233 0 402718720 -0.0379633978 -0.0403845385 -0.1010813937 2515 1311867254.3475589752 0.0485064238 0.0544815044 0.0722873509 0.0056394872 0.0808720000 410743741 0 402718720 -0.0395345055 -0.0436408445 -0.1031770781 2516 1311867254.3794488907 0.0493695587 0.0544794726 0.0722873509 0.0056384762 0.0439800000 410747025 0 402718720 -0.0410370454 -0.0432301126 -0.1066865474 2517 1311867254.4115350246 0.0485356525 0.0544771111 0.0722873509 0.0056400190 0.0440140000 410749877 0 402718720 -0.0407359451 -0.0421040729 -0.1123280451 2518 1311867254.4483439922 0.0490995161 0.0544749755 0.0722873509 0.0056393245 0.0438460000 410753329 0 402718720 -0.0421116911 -0.0422682613 -0.1166119128 2519 1311867254.4794480801 0.0491875857 0.0544728765 0.0722873509 0.0056384860 0.0440600000 410756485 0 402718720 -0.0447597876 -0.0443845838 -0.1195985377 2520 1311867254.5114428997 0.0479373857 0.0544702830 0.0722873509 0.0056374629 0.0427050000 410759649 0 402718720 -0.0447805375 -0.0423443429 -0.1254656017 2521 1311867254.5500459671 0.0490500405 0.0544681330 0.0722873509 0.0056380169 0.0572610000 411420585 0 402718720 -0.0460716151 -0.0416506752 -0.1292524785 2522 1311867254.5794870853 0.0475688241 0.0544653973 0.0722873509 0.0056410449 0.1727660000 411346741 0 402718720 -0.0461391769 -0.0423218906 -0.1337350905 2523 1311867254.6114809513 0.0472312719 0.0544625301 0.0722873509 0.0056402694 0.1691010000 411350033 0 402718720 -0.0459585562 -0.0385142751 -0.1389092356 2524 1311867254.6452929974 0.0470021330 0.0544595743 0.0722873509 0.0056405783 0.1538890000 411639517 0 402718720 -0.0456433594 -0.0377140529 -0.1431006491 2525 1311867254.6794900894 0.0473991819 0.0544567781 0.0722873509 0.0056402312 0.1647650000 421287029 0 402718720 -0.0476481020 -0.0388011374 -0.1458943486 2526 1311867254.7113230228 0.0463559739 0.0544535711 0.0722873509 0.0056393514 0.0995930000 424868853 0 402718720 -0.0462922007 -0.0381372236 -0.1500150710 2527 1311867254.7453329563 0.0468871817 0.0544505769 0.0722873509 0.0056405281 0.0998700000 424505089 0 402718720 -0.0451752618 -0.0362684913 -0.1536132097 2528 1311867254.7794649601 0.0482982583 0.0544481432 0.0722873509 0.0056441411 0.1960830000 422883785 0 402718720 -0.0473718494 -0.0355396494 -0.1563898474 2529 1311867254.8115739822 0.0464244895 0.0544449706 0.0722873509 0.0056434299 0.1266350000 411358945 0 402718720 -0.0464485809 -0.0361254103 -0.1610929668 2530 1311867254.8482780457 0.0468707904 0.0544419768 0.0722873509 0.0056440480 0.0468790000 411362189 0 402718720 -0.0460882857 -0.0349587575 -0.1640574336 2531 1311867254.8794910908 0.0471616872 0.0544391004 0.0722873509 0.0056431238 0.0550330000 411365289 0 402718720 -0.0452303849 -0.0334533788 -0.1673868299 2532 1311867254.9138929844 0.0474351272 0.0544363342 0.0722873509 0.0056424445 0.0467910000 411368429 0 402718720 -0.0452370234 -0.0339001641 -0.1696325690 2533 1311867254.9490759373 0.0478389896 0.0544337296 0.0722873509 0.0056420682 0.0462360000 411371881 0 402718720 -0.0462988392 -0.0331659764 -0.1726188362 2534 1311867254.9819579124 0.0479859114 0.0544311851 0.0722873509 0.0056414991 0.0455900000 411374829 0 402718720 -0.0448342711 -0.0319323316 -0.1754730493 2535 1311867255.0154359341 0.0478260517 0.0544285795 0.0722873509 0.0056421732 0.0464690000 411378169 0 402718720 -0.0455840752 -0.0328651667 -0.1777597070 2536 1311867255.0494379997 0.0478832126 0.0544259986 0.0722873509 0.0056411444 0.0561710000 411381309 0 402718720 -0.0443547331 -0.0312900767 -0.1810512394 2537 1311867255.0822079182 0.0470805727 0.0544231032 0.0722873509 0.0056401696 0.0824990000 411384329 0 402718720 -0.0444901288 -0.0303519871 -0.1843241900 2538 1311867255.1176838875 0.0467134453 0.0544200655 0.0722873509 0.0056391114 0.0460440000 411387765 0 402718720 -0.0442929715 -0.0307537615 -0.1872134209 2539 1311867255.1510150433 0.0464535318 0.0544169279 0.0722873509 0.0056386321 0.0455170000 411390785 0 402718720 -0.0445896983 -0.0308560636 -0.1898114830 2540 1311867255.1838800907 0.0471568145 0.0544140696 0.0722873509 0.0056386374 0.0464730000 411393757 0 402718720 -0.0441203043 -0.0300631076 -0.1917716265 2541 1311867255.2169129848 0.0485826135 0.0544117746 0.0722873509 0.0056383992 0.0453350000 411396857 0 402718720 -0.0439863876 -0.0274484176 -0.1939427853 2542 1311867255.2459371090 0.0475975871 0.0544090940 0.0722873509 0.0056376234 0.0838640000 411400077 0 402718720 -0.0442251042 -0.0283006951 -0.1967277676 2543 1311867255.2793660164 0.0465214774 0.0544059923 0.0722873509 0.0056478952 0.0436380000 411403321 0 402718720 -0.0451792181 -0.0286216345 -0.2002869993 2544 1311867255.3138630390 0.0463670753 0.0544028323 0.0722873509 0.0056474400 0.0436220000 411406461 0 402718720 -0.0426907465 -0.0288585033 -0.2028497010 2545 1311867255.3468410969 0.0469572656 0.0543999068 0.0722873509 0.0056468349 0.0473010000 411409617 0 402718720 -0.0414513834 -0.0281094760 -0.2054433972 2546 1311867255.3794751167 0.0482312068 0.0543974839 0.0722873509 0.0056461242 0.0474370000 411413085 0 402718720 -0.0420584977 -0.0279423874 -0.2074585557 2547 1311867255.4137639999 0.0483423732 0.0543951065 0.0722873509 0.0056500822 0.0576800000 411415905 0 402718720 -0.0430681109 -0.0274446700 -0.2108135223 2548 1311867255.4455530643 0.0467999987 0.0543921257 0.0722873509 0.0056490237 0.0472520000 411419197 0 402718720 -0.0413608626 -0.0274538640 -0.2148461342 2549 1311867255.4794819355 0.0485391617 0.0543898295 0.0722873509 0.0056498260 0.0440870000 411422145 0 402718720 -0.0410458222 -0.0268107969 -0.2166918516 2550 1311867255.5156099796 0.0484442599 0.0543874979 0.0722873509 0.0056508337 0.0441350000 411425789 0 402718720 -0.0401970148 -0.0261169001 -0.2206157446 2551 1311867255.5457780361 0.0477551334 0.0543848980 0.0722873509 0.0056519087 0.0442550000 411428817 0 402718720 -0.0406206772 -0.0261651259 -0.2235884368 2552 1311867255.5794420242 0.0495017543 0.0543829846 0.0722873509 0.0056510494 0.0435710000 411431645 0 402718720 -0.0400772989 -0.0264647081 -0.2248812616 2553 1311867255.6153330803 0.0496198237 0.0543811189 0.0722873509 0.0056517706 0.0539990000 411434905 0 402718720 -0.0401453972 -0.0252281204 -0.2284701169 2554 1311867255.6456480026 0.0501342267 0.0543794560 0.0722873509 0.0056516205 0.0441660000 411438373 0 402718720 -0.0389842540 -0.0237473194 -0.2309243083 2555 1311867255.6801021099 0.0497353077 0.0543776383 0.0722873509 0.0056516063 0.0470370000 411441465 0 402718720 -0.0395843610 -0.0249365028 -0.2338233292 2556 1311867255.7182919979 0.0493203774 0.0543756598 0.0722873509 0.0056523955 0.0439360000 411444717 0 402718720 -0.0404879451 -0.0266677663 -0.2368350029 2557 1311867255.7457749844 0.0489279814 0.0543735293 0.0722873509 0.0056513914 0.0465600000 411447753 0 402718720 -0.0375872292 -0.0241755899 -0.2409058511 2558 1311867255.7810928822 0.0502832346 0.0543719302 0.0722873509 0.0056552244 0.0580050000 411451165 0 402718720 -0.0377461091 -0.0226523317 -0.2436783463 2559 1311867255.8176100254 0.0491510071 0.0543698900 0.0722873509 0.0056587688 0.0550030000 411454425 0 402718720 -0.0383826867 -0.0256454702 -0.2459177822 2560 1311867255.8457250595 0.0498406291 0.0543681208 0.0722873509 0.0056587008 0.0461420000 411457461 0 402718720 -0.0377979502 -0.0243981481 -0.2481663823 2561 1311867255.8793790340 0.0507859848 0.0543667221 0.0722873509 0.0056579399 0.0471760000 411460697 0 402718720 -0.0375819132 -0.0222526342 -0.2514178157 2562 1311867255.9140310287 0.0497230962 0.0543649096 0.0722873509 0.0056570250 0.0472580000 411464085 0 402718720 -0.0397128388 -0.0240555629 -0.2549798787 2563 1311867255.9459080696 0.0484255999 0.0543625922 0.0722873509 0.0056561272 0.0427160000 411466785 0 402718720 -0.0402257405 -0.0270666722 -0.2571834326 2564 1311867255.9794859886 0.0482639708 0.0543602137 0.0722873509 0.0056550281 0.0467940000 411470125 0 402718720 -0.0393860862 -0.0260844193 -0.2612757981 2565 1311867256.0177969933 0.0490225479 0.0543581327 0.0722873509 0.0056539906 0.0432110000 411473561 0 402718720 -0.0396694690 -0.0252939537 -0.2637498677 2566 1311867256.0460140705 0.0493945591 0.0543561983 0.0722873509 0.0056533535 0.0465780000 411476421 0 402718720 -0.0404451713 -0.0256634876 -0.2655281723 2567 1311867256.0856881142 0.0476444028 0.0543535837 0.0722873509 0.0056586766 0.0466220000 411479993 0 402718720 -0.0410551503 -0.0265726708 -0.2702862620 2568 1311867256.1167299747 0.0488353819 0.0543514349 0.0722873509 0.0056599936 0.0461690000 411482965 0 402718720 -0.0414459221 -0.0249402206 -0.2729949653 2569 1311867256.1452269554 0.0499298871 0.0543497137 0.0722873509 0.0056602969 0.0440910000 411486257 0 402718720 -0.0424041823 -0.0242347512 -0.2741886079 2570 1311867256.1795060635 0.0495577157 0.0543478492 0.0722873509 0.0056608405 0.0440990000 411489325 0 402718720 -0.0444014668 -0.0257734712 -0.2773974538 2571 1311867256.2177491188 0.0477963239 0.0543453009 0.0722873509 0.0056617796 0.0573120000 411492769 0 402718720 -0.0425373316 -0.0262465179 -0.2816621065 2572 1311867256.2454690933 0.0484565124 0.0543430113 0.0722873509 0.0056612787 0.0588480000 411495861 0 402718720 -0.0418124422 -0.0251789242 -0.2844051719 2573 1311867256.2847039700 0.0498587899 0.0543412685 0.0722873509 0.0056605528 0.0430370000 411498865 0 402718720 -0.0452929512 -0.0261169020 -0.2867145240 2574 1311867256.3143420219 0.0486753993 0.0543390674 0.0722873509 0.0056615292 0.0422980000 411502221 0 402718720 -0.0465399548 -0.0272942446 -0.2910829186 2575 1311867256.3471789360 0.0479356349 0.0543365806 0.0722873509 0.0056620254 0.0436400000 411505681 0 402718720 -0.0440706350 -0.0264754146 -0.2958250642 2576 1311867256.3848650455 0.0484497398 0.0543342953 0.0722873509 0.0056614234 0.0456520000 411508621 0 402718720 -0.0459432527 -0.0277857333 -0.2993029058 2577 1311867256.4158649445 0.0485574454 0.0543320536 0.0722873509 0.0056604207 0.0429680000 411511745 0 402718720 -0.0454415679 -0.0279350560 -0.3028114438 2578 1311867256.4452838898 0.0476688445 0.0543294690 0.0722873509 0.0056608173 0.0459160000 411514853 0 402718720 -0.0468189456 -0.0283402484 -0.3081247211 2579 1311867256.4844601154 0.0489121638 0.0543273684 0.0722873509 0.0056621184 0.0459220000 411518233 0 402718720 -0.0476846732 -0.0274866074 -0.3115041852 2580 1311867256.5135829449 0.0489090309 0.0543252683 0.0722873509 0.0056618129 0.0595570000 412134637 0 402718720 -0.0518368147 -0.0285893679 -0.3153409362 2581 1311867256.5478789806 0.0465165451 0.0543222428 0.0722873509 0.0056830939 0.1613090000 412084985 0 402718720 -0.0483910106 -0.0305749755 -0.3192558885 2582 1311867256.5836489201 0.0480982475 0.0543198323 0.0722873509 0.0056940609 0.1539020000 412089405 0 402718720 -0.0449525118 -0.0294895098 -0.3217346072 2583 1311867256.6160368919 0.0468741097 0.0543169497 0.0722873509 0.0056931141 0.1577200000 412115493 0 402718720 -0.0488763712 -0.0307704397 -0.3260660172 2584 1311867256.6452310085 0.0464442968 0.0543139030 0.0722873509 0.0056924189 0.1483930000 425139221 0 402718720 -0.0494094342 -0.0323008001 -0.3286185861 2585 1311867256.6832759380 0.0482152067 0.0543115438 0.0722873509 0.0056916886 0.1170630000 425258633 0 402718720 -0.0502183288 -0.0308022685 -0.3316985667 2586 1311867256.7140300274 0.0489192344 0.0543094586 0.0722873509 0.0056912806 0.0839400000 425597337 0 402718720 -0.0494644754 -0.0286292769 -0.3349614739 2587 1311867256.7463369370 0.0474102236 0.0543067917 0.0722873509 0.0056903249 0.0573470000 425512769 0 402718720 -0.0490021557 -0.0304284170 -0.3378453255 2588 1311867256.7827401161 0.0480038077 0.0543043562 0.0722873509 0.0056905227 0.1461290000 423676505 0 402718720 -0.0466297381 -0.0295793246 -0.3405396342 2589 1311867256.8140430450 0.0471131466 0.0543015786 0.0722873509 0.0056917461 0.1161660000 412099669 0 402718720 -0.0472615734 -0.0300891567 -0.3446245492 2590 1311867256.8477399349 0.0462697521 0.0542984775 0.0722873509 0.0056913363 0.0437720000 412103217 0 402718720 -0.0506103039 -0.0330005735 -0.3484166265 2591 1311867256.8838980198 0.0467271358 0.0542955554 0.0722873509 0.0056916979 0.0440160000 412106149 0 402718720 -0.0483470298 -0.0337145440 -0.3505555689 2592 1311867256.9148108959 0.0459651425 0.0542923415 0.0722873509 0.0056912552 0.0440670000 412109649 0 402718720 -0.0458984338 -0.0320134126 -0.3566284180 2593 1311867256.9465379715 0.0471272990 0.0542895782 0.0722873509 0.0056903101 0.0436530000 412112605 0 402718720 -0.0476150997 -0.0331826396 -0.3589093089 2594 1311867256.9814610481 0.0466083251 0.0542866171 0.0722873509 0.0056896084 0.0459230000 412116001 0 402718720 -0.0462782308 -0.0340564549 -0.3628600240 2595 1311867257.0129959583 0.0450556390 0.0542830599 0.0722873509 0.0056893561 0.0429710000 412119221 0 402718720 -0.0443025418 -0.0356871933 -0.3672278225 2596 1311867257.0451910496 0.0479744524 0.0542806297 0.0722873509 0.0056913058 0.0429890000 412122313 0 402718720 -0.0443601534 -0.0324127227 -0.3700586855 2597 1311867257.0841369629 0.0499321893 0.0542789553 0.0722873509 0.0056905300 0.0453790000 412125645 0 402718720 -0.0440192670 -0.0306624398 -0.3727948070 2598 1311867257.1134428978 0.0489558689 0.0542769064 0.0722873509 0.0056895041 0.0427320000 412128601 0 402718720 -0.0448286682 -0.0319446474 -0.3756788075 2599 1311867257.1474308968 0.0480594449 0.0542745142 0.0722873509 0.0056888504 0.0451440000 412131805 0 402718720 -0.0450532436 -0.0315181203 -0.3806364238 2600 1311867257.1821229458 0.0490870662 0.0542725190 0.0722873509 0.0056878850 0.0455580000 412135009 0 402718720 -0.0437792875 -0.0294554215 -0.3836816847 2601 1311867257.2147839069 0.0480416231 0.0542701234 0.0722873509 0.0056898118 0.0429550000 412138493 0 402718720 -0.0452570356 -0.0307277422 -0.3867897689 2602 1311867257.2457039356 0.0461165272 0.0542669898 0.0722873509 0.0056915894 0.0447450000 412141265 0 402718720 -0.0464239269 -0.0334424488 -0.3900362849 2603 1311867257.2824490070 0.0480696894 0.0542646090 0.0722873509 0.0056905680 0.0444720000 412144805 0 402718720 -0.0429113396 -0.0294183027 -0.3932368755 2604 1311867257.3133430481 0.0455359221 0.0542612570 0.0722873509 0.0056902774 0.0453820000 412147897 0 402718720 -0.0410944410 -0.0307583194 -0.3976018727 2605 1311867257.3452849388 0.0457724929 0.0542579983 0.0722873509 0.0056898127 0.0450330000 412150973 0 402718720 -0.0411292389 -0.0306451712 -0.3998790085 2606 1311867257.3839631081 0.0478579067 0.0542555424 0.0722873509 0.0056892743 0.0447890000 412154433 0 402718720 -0.0430959128 -0.0289168563 -0.4021416306 2607 1311867257.4198129177 0.0485963151 0.0542533716 0.0722873509 0.0056904651 0.0452520000 412157629 0 402718720 -0.0408962257 -0.0271041337 -0.4053349495 2608 1311867257.4458611012 0.0478346162 0.0542509104 0.0722873509 0.0056901829 0.0432850000 412160417 0 402718720 -0.0398087502 -0.0276282411 -0.4072125256 2609 1311867257.4851269722 0.0488261022 0.0542488312 0.0722873509 0.0056896801 0.0454620000 412163997 0 402718720 -0.0434619561 -0.0272503160 -0.4102714658 2610 1311867257.5166249275 0.0507737435 0.0542474997 0.0722873509 0.0056890906 0.0447830000 412167177 0 402718720 -0.0412706695 -0.0232240111 -0.4133431017 2611 1311867257.5537879467 0.0480172560 0.0542451136 0.0722873509 0.0056892935 0.0533110000 412170245 0 402718720 -0.0392844975 -0.0255658682 -0.4171682894 2612 1311867257.5836200714 0.0503301211 0.0542436147 0.0722873509 0.0056964584 0.0447040000 412173673 0 402718720 -0.0402072519 -0.0249676015 -0.4166759253 2613 1311867257.6154460907 0.0509316362 0.0542423472 0.0722873509 0.0056998163 0.0458340000 412176413 0 402718720 -0.0397881977 -0.0231107734 -0.4199779332 2614 1311867257.6519720554 0.0516841486 0.0542413686 0.0722873509 0.0056987740 0.0453930000 412180113 0 402718720 -0.0387898907 -0.0207227226 -0.4229175448 2615 1311867257.6842958927 0.0518547148 0.0542404559 0.0722873509 0.0056982244 0.0539850000 412183133 0 402718720 -0.0370812416 -0.0203847028 -0.4245486259 2616 1311867257.7187778950 0.0504240282 0.0542389970 0.0722873509 0.0056971621 0.0432740000 412186137 0 402718720 -0.0387549996 -0.0218000580 -0.4276514053 2617 1311867257.7527809143 0.0483999811 0.0542367658 0.0722873509 0.0056980482 0.0784180000 412189341 0 402718720 -0.0354904048 -0.0230449960 -0.4302690625 2618 1311867257.7838430405 0.0491667576 0.0542348292 0.0722873509 0.0056975226 0.0457270000 412192889 0 402718720 -0.0357537493 -0.0221058987 -0.4322939813 2619 1311867257.8181409836 0.0507755838 0.0542335084 0.0722873509 0.0056965798 0.0438090000 412196045 0 402718720 -0.0359599739 -0.0222245529 -0.4315741658 2620 1311867257.8530700207 0.0501020253 0.0542319315 0.0722873509 0.0057019092 0.0448140000 412199249 0 402718720 -0.0356098227 -0.0220461171 -0.4352864325 2621 1311867257.8854579926 0.0504554138 0.0542304906 0.0722873509 0.0057032958 0.0419060000 412201925 0 402718720 -0.0338453539 -0.0218436606 -0.4366380870 2622 1311867257.9152529240 0.0510357432 0.0542292722 0.0722873509 0.0057032678 0.0607140000 412205337 0 402718720 -0.0330467708 -0.0210171435 -0.4385571480 2623 1311867257.9559030533 0.0524357781 0.0542285884 0.0722873509 0.0057023914 0.0445890000 412208957 0 402718720 -0.0342747569 -0.0216657538 -0.4387570620 2624 1311867257.9850780964 0.0518435389 0.0542276795 0.0722873509 0.0057013695 0.0427940000 412211801 0 402718720 -0.0354125984 -0.0219039787 -0.4421022236 2625 1311867258.0135710239 0.0515131168 0.0542266454 0.0722873509 0.0057003066 0.0447890000 412214973 0 402718720 -0.0330497213 -0.0226682015 -0.4428642094 2626 1311867258.0526609421 0.0501584522 0.0542250962 0.0722873509 0.0057003652 0.0447880000 412218129 0 402718720 -0.0348072238 -0.0252585765 -0.4459646940 2627 1311867258.0836610794 0.0501203202 0.0542235337 0.0722873509 0.0057022024 0.0427880000 412221301 0 402718720 -0.0317997038 -0.0251323879 -0.4474164546 2628 1311867258.1137859821 0.0506651029 0.0542221796 0.0722873509 0.0057012554 0.0818010000 412224513 0 402718720 -0.0333642997 -0.0255338345 -0.4490352273 2629 1311867258.1501069069 0.0515368581 0.0542211582 0.0722873509 0.0057018716 0.0446140000 412227685 0 402718720 -0.0313890390 -0.0244468823 -0.4507595599 2630 1311867258.1848480701 0.0518265329 0.0542202477 0.0722873509 0.0057009171 0.0428340000 412230889 0 402718720 -0.0301145017 -0.0247045103 -0.4520869851 2631 1311867258.2162730694 0.0510215908 0.0542190319 0.0722873509 0.0056999468 0.0433870000 412234157 0 402718720 -0.0302960202 -0.0256619528 -0.4548192322 2632 1311867258.2524979115 0.0515583567 0.0542180210 0.0722873509 0.0057005458 0.0448080000 412237417 0 402718720 -0.0295819528 -0.0264964011 -0.4546749592 2633 1311867258.2857830524 0.0515335537 0.0542170015 0.0722873509 0.0056996278 0.0425630000 412240405 0 402718720 -0.0299297236 -0.0266850740 -0.4567017853 2634 1311867258.3132910728 0.0513866059 0.0542159269 0.0722873509 0.0056987304 0.0426560000 412243497 0 402718720 -0.0294054821 -0.0273768343 -0.4575809538 2635 1311867258.3510708809 0.0509130880 0.0542146735 0.0722873509 0.0056991176 0.0421950000 412246981 0 402718720 -0.0295891911 -0.0285005700 -0.4592269957 2636 1311867258.3812119961 0.0517983474 0.0542137568 0.0722873509 0.0056982750 0.0427060000 412249777 0 402718720 -0.0295263529 -0.0280425549 -0.4594176412 2637 1311867258.4142711163 0.0529822111 0.0542132898 0.0722873509 0.0056973505 0.0532350000 412253181 0 402718720 -0.0296567045 -0.0273374803 -0.4596741796 2638 1311867258.4507009983 0.0528271049 0.0542127643 0.0722873509 0.0056975042 0.0434190000 412256177 0 402718720 -0.0306974761 -0.0284474660 -0.4602215886 2639 1311867258.4826059341 0.0513953418 0.0542116967 0.0722873509 0.0056973585 0.0786160000 412259701 0 402718720 -0.0298163779 -0.0292769037 -0.4624499381 2640 1311867258.5139899254 0.0521697514 0.0542109232 0.0722873509 0.0056980985 0.0442590000 412262985 0 402718720 -0.0297190323 -0.0300089363 -0.4617766142 2641 1311867258.5500509739 0.0504126437 0.0542094850 0.0722873509 0.0057111992 0.0542610000 412842169 0 402718720 -0.0290239118 -0.0319717377 -0.4637884200 2642 1311867258.5836040974 0.0508232228 0.0542082033 0.0722873509 0.0057187240 0.1536240000 412816029 0 402718720 -0.0295424685 -0.0328608975 -0.4649823010 2643 1311867258.6141679287 0.0510995202 0.0542070271 0.0722873509 0.0057196336 0.1599580000 412813965 0 402718720 -0.0277137458 -0.0324774384 -0.4667551517 2644 1311867258.6506860256 0.0511596240 0.0542058746 0.0722873509 0.0057190925 0.1318460000 418103221 0 402718720 -0.0279965252 -0.0328624249 -0.4696318805 2645 1311867258.6856470108 0.0511529632 0.0542047204 0.0722873509 0.0057186187 0.1183460000 426541449 0 402718720 -0.0269748829 -0.0345046967 -0.4705839753 2646 1311867258.7134239674 0.0512085930 0.0542035880 0.0722873509 0.0057177372 0.1088550000 426590845 0 402718720 -0.0284555443 -0.0370665863 -0.4716859758 2647 1311867258.7543559074 0.0516773388 0.0542026336 0.0722873509 0.0057177143 0.0791730000 426417073 0 402718720 -0.0248735026 -0.0358521417 -0.4753721952 2648 1311867258.7843589783 0.0527093709 0.0542020697 0.0722873509 0.0057183795 0.0552070000 426591117 0 402718720 -0.0236173123 -0.0340660028 -0.4784861505 2649 1311867258.8193690777 0.0515295491 0.0542010608 0.0722873509 0.0057174834 0.1472560000 424768465 0 402718720 -0.0238676704 -0.0372129828 -0.4793931544 2650 1311867258.8514409065 0.0524522774 0.0542004009 0.0722873509 0.0057165149 0.1243110000 412761733 0 402718720 -0.0244177468 -0.0370624624 -0.4811879396 2651 1311867258.8846011162 0.0526565574 0.0541998186 0.0722873509 0.0057158087 0.0436120000 412788457 0 402718720 -0.0208389908 -0.0367465839 -0.4828252494 2652 1311867258.9178969860 0.0513077937 0.0541987281 0.0722873509 0.0057149391 0.0440310000 412792109 0 402718720 -0.0206047483 -0.0391496979 -0.4846944511 2653 1311867258.9506199360 0.0501572825 0.0541972047 0.0722873509 0.0057150051 0.0440960000 412795209 0 402718720 -0.0228937604 -0.0418981835 -0.4875499308 2654 1311867258.9841670990 0.0535424091 0.0541969580 0.0722873509 0.0057157102 0.0438300000 412798309 0 402718720 -0.0206277706 -0.0383102968 -0.4892683029 2655 1311867259.0194389820 0.0515219234 0.0541959504 0.0722873509 0.0057149059 0.0427560000 412801473 0 402718720 -0.0184943639 -0.0404996760 -0.4925912917 2656 1311867259.0497961044 0.0497651771 0.0541942822 0.0722873509 0.0057168810 0.0428500000 412804365 0 402718720 -0.0168102123 -0.0432165042 -0.4950120449 2657 1311867259.0845470428 0.0530793928 0.0541938626 0.0722873509 0.0057178200 0.0447030000 412807721 0 402718720 -0.0166462325 -0.0409179404 -0.4961059093 2658 1311867259.1189930439 0.0527838357 0.0541933321 0.0722873509 0.0057170146 0.0421110000 412810853 0 402718720 -0.0135449357 -0.0406457707 -0.4986618459 2659 1311867259.1506030560 0.0509630106 0.0541921173 0.0722873509 0.0057187495 0.0445030000 412813937 0 402718720 -0.0130212530 -0.0427920297 -0.5020422339 2660 1311867259.1837821007 0.0531320088 0.0541917187 0.0722873509 0.0057193375 0.0447540000 412817213 0 402718720 -0.0126889311 -0.0413189977 -0.5031987429 2661 1311867259.2191979885 0.0520952195 0.0541909309 0.0722873509 0.0057184118 0.0453890000 412820737 0 402718720 -0.0086264834 -0.0408799425 -0.5068244338 2662 1311867259.2532899380 0.0495134592 0.0541891738 0.0722873509 0.0057178680 0.0430600000 412823781 0 402718720 -0.0072893277 -0.0442689583 -0.5107644796 2663 1311867259.2815980911 0.0503269620 0.0541877234 0.0722873509 0.0057169426 0.0426690000 412826705 0 402718720 -0.0053943545 -0.0434096158 -0.5120576024 2664 1311867259.3212718964 0.0511119142 0.0541865688 0.0722873509 0.0057171505 0.0450040000 412830397 0 402718720 -0.0041802898 -0.0422292836 -0.5154228210 2665 1311867259.3519039154 0.0524157844 0.0541859044 0.0722873509 0.0057171179 0.0428460000 412833305 0 402718720 -0.0037294403 -0.0410466716 -0.5183499455 2666 1311867259.3840188980 0.0512155443 0.0541847902 0.0722873509 0.0057160706 0.0513620000 412836349 0 402718720 -0.0030698851 -0.0428843945 -0.5217367411 2667 1311867259.4204289913 0.0513417944 0.0541837242 0.0722873509 0.0057178045 0.0435280000 412839801 0 402718720 0.0001455322 -0.0426078588 -0.5252761841 2668 1311867259.4579179287 0.0536598712 0.0541835279 0.0722873509 0.0057168437 0.0413930000 412843245 0 402718720 0.0028072298 -0.0408957824 -0.5265731812 2669 1311867259.4850549698 0.0529602990 0.0541830696 0.0722873509 0.0057177856 0.0608900000 412845977 0 402718720 0.0021414310 -0.0414461456 -0.5317342281 2670 1311867259.5189819336 0.0529423729 0.0541826049 0.0722873509 0.0057169218 0.0418580000 412849197 0 402718720 0.0018987320 -0.0436889306 -0.5330189466 2671 1311867259.5505928993 0.0546422824 0.0541827770 0.0722873509 0.0057160619 0.0417570000 412852281 0 402718720 0.0015497059 -0.0426849574 -0.5364565253 2672 1311867259.5823240280 0.0525879897 0.0541821801 0.0722873509 0.0057164957 0.0821830000 412855421 0 402718720 0.0055180229 -0.0431622416 -0.5424364209 2673 1311867259.6192719936 0.0548675619 0.0541824366 0.0722873509 0.0057182417 0.0410950000 412858769 0 402718720 0.0059755594 -0.0415839069 -0.5453970432 2674 1311867259.6494839191 0.0562616475 0.0541832141 0.0722873509 0.0057175707 0.0413640000 412861933 0 402718720 0.0024991482 -0.0415701345 -0.5484513640 2675 1311867259.6828589439 0.0580951422 0.0541846765 0.0722873509 0.0057179793 0.0418470000 412865025 0 402718720 0.0063032322 -0.0384933986 -0.5505811572 2676 1311867259.7201991081 0.0559453331 0.0541853345 0.0722873509 0.0057176328 0.0414310000 412867989 0 402718720 0.0085705034 -0.0395158045 -0.5554962754 2677 1311867259.7557690144 0.0557273701 0.0541859105 0.0722873509 0.0057174188 0.0431960000 412871633 0 402718720 0.0086277239 -0.0404898599 -0.5572892427 2678 1311867259.7817859650 0.0556715019 0.0541864652 0.0722873509 0.0057167591 0.0544370000 412874693 0 402718720 0.0080308244 -0.0402994901 -0.5598791242 2679 1311867259.8177011013 0.0575385205 0.0541877165 0.0722873509 0.0057159881 0.0428480000 412877761 0 402718720 0.0087348595 -0.0379427187 -0.5621964931 2680 1311867259.8548939228 0.0548750237 0.0541879729 0.0722873509 0.0057156727 0.0429710000 412881229 0 402718720 0.0108384341 -0.0393338613 -0.5661201477 2681 1311867259.8818409443 0.0569510534 0.0541890035 0.0722873509 0.0057157883 0.0411430000 412884297 0 402718720 0.0091102384 -0.0397673994 -0.5635511279 2682 1311867259.9219179153 0.0562186092 0.0541897603 0.0722873509 0.0057147892 0.0428540000 412887701 0 402718720 0.0095898099 -0.0384673066 -0.5692283511 2683 1311867259.9520130157 0.0559909604 0.0541904316 0.0722873509 0.0057137695 0.0820580000 412890793 0 402718720 0.0123708062 -0.0367611200 -0.5725760460 2684 1311867259.9923639297 0.0533866882 0.0541901322 0.0722873509 0.0057133869 0.0439050000 412894037 0 402718720 0.0115943812 -0.0406083427 -0.5737457871 2685 1311867260.0219469070 0.0560734682 0.0541908336 0.0722873509 0.0057133290 0.0413330000 412896945 0 402718720 0.0112490728 -0.0373171791 -0.5760395527 2686 1311867260.0493209362 0.0559795350 0.0541914995 0.0722873509 0.0057125152 0.0417430000 412900197 0 402718720 0.0127069503 -0.0362039432 -0.5784896016 2687 1311867260.0888080597 0.0531684868 0.0541911188 0.0722873509 0.0057128481 0.0537200000 412903505 0 402718720 0.0148678832 -0.0369436257 -0.5838505030 2688 1311867260.1210498810 0.0536641702 0.0541909228 0.0722873509 0.0057165486 0.0525790000 412906605 0 402718720 0.0155138597 -0.0370123088 -0.5844155550 2689 1311867260.1513869762 0.0540391468 0.0541908663 0.0722873509 0.0057179620 0.0421560000 412909697 0 402718720 0.0154192522 -0.0355211459 -0.5884096622 2690 1311867260.1908860207 0.0548395813 0.0541911075 0.0722873509 0.0057175673 0.0414050000 412913013 0 402718720 0.0157761015 -0.0345588401 -0.5906223655 2691 1311867260.2204439640 0.0562871136 0.0541918864 0.0722873509 0.0057169225 0.0427630000 412916121 0 402718720 0.0166420601 -0.0326039866 -0.5931337476 2692 1311867260.2496669292 0.0530115217 0.0541914479 0.0722873509 0.0057161499 0.0411420000 412919493 0 402718720 0.0154915303 -0.0360750332 -0.5974751711 2693 1311867260.2869880199 0.0557459705 0.0541920252 0.0722873509 0.0057156155 0.0423340000 412922881 0 402718720 0.0186915696 -0.0311028697 -0.6015448570 2694 1311867260.3195590973 0.0573338196 0.0541931914 0.0722873509 0.0057146446 0.0796910000 412925837 0 402718720 0.0191869065 -0.0292238407 -0.6030030251 2695 1311867260.3505260944 0.0548402853 0.0541934315 0.0722873509 0.0057152454 0.0417090000 412928857 0 402718720 0.0192540661 -0.0312580168 -0.6070588827 2696 1311867260.3868899345 0.0566803776 0.0541943539 0.0722873509 0.0057163678 0.0416870000 412932085 0 402718720 0.0210500695 -0.0276105441 -0.6108098626 2697 1311867260.4211299419 0.0574630946 0.0541955659 0.0722873509 0.0057154095 0.0422910000 412935121 0 402718720 0.0233439468 -0.0254584346 -0.6130455136 2698 1311867260.4521770477 0.0561274029 0.0541962820 0.0722873509 0.0057144880 0.0411650000 412938405 0 402718720 0.0225607976 -0.0257225726 -0.6169781089 2699 1311867260.4867470264 0.0568252504 0.0541972560 0.0722873509 0.0057157954 0.0415160000 412941545 0 402718720 0.0227176175 -0.0252359901 -0.6180689931 2700 1311867260.5192930698 0.0573319532 0.0541984170 0.0722873509 0.0057174733 0.0405410000 412944661 0 402718720 0.0253353789 -0.0223006867 -0.6224874854 2701 1311867260.5527870655 0.0573937893 0.0541996000 0.0722873509 0.0057170732 0.0406960000 412947857 0 402718720 0.0250136033 -0.0219274852 -0.6243497133 2702 1311867260.5880448818 0.0580386221 0.0542010209 0.0722873509 0.0057178134 0.0460370000 412951309 0 402718720 0.0241347700 -0.0220546685 -0.6258208156 2703 1311867260.6196188927 0.0567278899 0.0542019557 0.0722873509 0.0057174490 0.0473390000 412954169 0 402718720 0.0248675682 -0.0233490877 -0.6292635202 2704 1311867260.6493411064 0.0555779189 0.0542024646 0.0722873509 0.0057167065 0.0484570000 412957413 0 402718720 0.0263225771 -0.0232484229 -0.6343441010 2705 1311867260.6865339279 0.0571890771 0.0542035687 0.0722873509 0.0057172596 0.0475460000 412960857 0 402718720 0.0268794820 -0.0245324466 -0.6348637938 2706 1311867260.7188229561 0.0580678508 0.0542049967 0.0722873509 0.0057168693 0.0480440000 412964037 0 402718720 0.0247827508 -0.0254044365 -0.6374876499 2707 1311867260.7493369579 0.0592429973 0.0542068578 0.0722873509 0.0057170697 0.0477600000 412966945 0 402718720 0.0268685967 -0.0232992843 -0.6416049004 2708 1311867260.7859649658 0.0582961217 0.0542083679 0.0722873509 0.0057186745 0.0470830000 412970261 0 402718720 0.0277760662 -0.0250626057 -0.6447592378 2709 1311867260.8179080486 0.0560591221 0.0542090511 0.0722873509 0.0057193976 0.0405350000 412973529 0 402718720 0.0300712101 -0.0277290177 -0.6487143636 2710 1311867260.8514599800 0.0564058721 0.0542098617 0.0722873509 0.0057220387 0.0416120000 412976757 0 402718720 0.0301046818 -0.0283356048 -0.6512111425 2711 1311867260.8867430687 0.0553503111 0.0542102824 0.0722873509 0.0057218400 0.0414810000 412979697 0 402718720 0.0326292850 -0.0297299735 -0.6553563476 2712 1311867260.9177849293 0.0582438298 0.0542117697 0.0722873509 0.0057215841 0.0415030000 412983117 0 402718720 0.0324062929 -0.0268665478 -0.6591406465 2713 1311867260.9494459629 0.0597383790 0.0542138067 0.0722873509 0.0057328310 0.0536080000 412986473 0 402718720 0.0318934284 -0.0270365253 -0.6604723334 2714 1311867260.9869680405 0.0570342168 0.0542148460 0.0722873509 0.0057413314 0.0415550000 412989501 0 402718720 0.0332507305 -0.0296656601 -0.6665508747 2715 1311867261.0202260017 0.0576474927 0.0542161103 0.0722873509 0.0057418288 0.0525280000 412992713 0 402718720 0.0328673758 -0.0309137926 -0.6686004400 2716 1311867261.0519640446 0.0572108589 0.0542172129 0.0722873509 0.0057426856 0.0795550000 412995733 0 402718720 0.0338033214 -0.0320216082 -0.6724817753 2717 1311867261.0871579647 0.0564762875 0.0542180444 0.0722873509 0.0057417285 0.0407600000 412999009 0 402718720 0.0331962928 -0.0342173129 -0.6773496270 2718 1311867261.1197659969 0.0556652881 0.0542185768 0.0722873509 0.0057419686 0.0504090000 413519033 0 402718720 0.0322154909 -0.0376821011 -0.6809691787 2719 1311867261.1530790329 0.0588247962 0.0542202709 0.0722873509 0.0057439686 0.1264930000 413492761 0 402718720 0.0324114822 -0.0353644304 -0.6845521331 2720 1311867261.1872630119 0.0586731136 0.0542219080 0.0722873509 0.0057461615 0.1333690000 413807797 0 402718720 0.0307235867 -0.0374439880 -0.6875118017 2721 1311867261.2191090584 0.0571804903 0.0542229953 0.0722873509 0.0057517700 0.1203940000 421172773 0 402718720 0.0310993418 -0.0397943556 -0.6907893419 2722 1311867261.2548229694 0.0578063428 0.0542243118 0.0722873509 0.0057508292 0.0814720000 427196873 0 402718720 0.0330169946 -0.0391588658 -0.6940701008 2723 1311867261.2879600525 0.0597048886 0.0542263245 0.0722873509 0.0057500682 0.1015660000 425425637 0 402718720 0.0333175361 -0.0371485390 -0.6971178055 2724 1311867261.3185029030 0.0609145090 0.0542287797 0.0722873509 0.0057564419 0.0474500000 427051920 0 402718720 0.0331500061 -0.0362577811 -0.6983711720 2725 1311867261.3546299934 0.0612871200 0.0542313700 0.0722873509 0.0057578949 0.0550730000 427071157 0 402718720 0.0324195325 -0.0359738916 -0.7013439536 2726 1311867261.3858330250 0.0632756427 0.0542346877 0.0722873509 0.0057570522 0.1520000000 425278757 0 402718720 0.0314683318 -0.0339668244 -0.7034046054 2727 1311867261.4186379910 0.0628124326 0.0542378332 0.0722873509 0.0057563028 0.1288480000 413489465 0 402718720 0.0313139185 -0.0337313861 -0.7069572806 2728 1311867261.4558680058 0.0609302968 0.0542402865 0.0722873509 0.0057567571 0.0412610000 413516189 0 402718720 0.0306801684 -0.0362825356 -0.7074243426 2729 1311867261.4862189293 0.0615534447 0.0542429663 0.0722873509 0.0057594015 0.0427090000 413519281 0 402718720 0.0260901861 -0.0364474282 -0.7099550962 2730 1311867261.5178630352 0.0623075776 0.0542459203 0.0722873509 0.0057591078 0.0411490000 413522613 0 402718720 0.0263141692 -0.0353220813 -0.7121627331 2731 1311867261.5556519032 0.0609897040 0.0542483897 0.0722873509 0.0057582087 0.0424610000 413525857 0 402718720 0.0290123262 -0.0355040543 -0.7135177851 2732 1311867261.5857899189 0.0603501350 0.0542506231 0.0722873509 0.0057614052 0.0429280000 413528757 0 402718720 0.0273292586 -0.0367129147 -0.7143434882 2733 1311867261.6174640656 0.0614890605 0.0542532716 0.0722873509 0.0057604689 0.0433390000 413532089 0 402718720 0.0253890455 -0.0344770700 -0.7180446982 2734 1311867261.6652009487 0.0612108707 0.0542558165 0.0722873509 0.0057597559 0.0437140000 413535629 0 402718720 0.0222293101 -0.0363649949 -0.7170162797 2735 1311867261.6889929771 0.0588884391 0.0542575103 0.0722873509 0.0057593184 0.0536190000 413538489 0 402718720 0.0245192274 -0.0364891589 -0.7220461965 2736 1311867261.7193109989 0.0600543991 0.0542596291 0.0722873509 0.0057612328 0.0433460000 413541525 0 402718720 0.0223823115 -0.0350425541 -0.7246546149 2737 1311867261.7601549625 0.0614003055 0.0542622380 0.0722873509 0.0057634064 0.0509070000 413544969 0 402718720 0.0229699910 -0.0317335799 -0.7294846773 2738 1311867261.7876880169 0.0628929436 0.0542653902 0.0722873509 0.0057655765 0.0553760000 413548021 0 402718720 0.0223166086 -0.0291234180 -0.7325210571 2739 1311867261.8213939667 0.0616961680 0.0542681032 0.0722873509 0.0057687657 0.0433990000 413551097 0 402718720 0.0225686431 -0.0285767615 -0.7374562025 2740 1311867261.8598148823 0.0630404577 0.0542713047 0.0722873509 0.0057688818 0.0417080000 413554629 0 402718720 0.0191002786 -0.0271836519 -0.7393992543 2741 1311867261.8885459900 0.0637229532 0.0542747530 0.0722873509 0.0057746296 0.0430460000 413557657 0 402718720 0.0229798481 -0.0233349949 -0.7430984378 2742 1311867261.9212360382 0.0620917454 0.0542776038 0.0722873509 0.0057798677 0.0418690000 413560677 0 402718720 0.0237197131 -0.0243674107 -0.7436057329 2743 1311867261.9592299461 0.0606459528 0.0542799255 0.0722873509 0.0057793592 0.0515910000 413563985 0 402718720 0.0213696137 -0.0243997350 -0.7503103614 2744 1311867261.9886140823 0.0639210790 0.0542834390 0.0722873509 0.0057815006 0.0417260000 413567149 0 402718720 0.0232647955 -0.0201031417 -0.7489020824 2745 1311867262.0219531059 0.0627762377 0.0542865330 0.0722873509 0.0057816331 0.0430960000 413570449 0 402718720 0.0232353993 -0.0203406587 -0.7528373599 2746 1311867262.0576629639 0.0622464344 0.0542894317 0.0722873509 0.0057808017 0.0429160000 413573469 0 402718720 0.0224854089 -0.0206644833 -0.7549955249 2747 1311867262.0944681168 0.0600783974 0.0542915391 0.0722873509 0.0057800066 0.0553630000 413576561 0 402718720 0.0240753889 -0.0206428468 -0.7608528733 2748 1311867262.1180479527 0.0615926236 0.0542941959 0.0722873509 0.0057789842 0.0673880000 413579933 0 402718720 0.0254023224 -0.0173857249 -0.7645375133 2749 1311867262.1539878845 0.0633670688 0.0542974964 0.0722873509 0.0057793341 0.0552780000 413583129 0 402718720 0.0238933153 -0.0148613937 -0.7666921020 2750 1311867262.1906540394 0.0631825775 0.0543007273 0.0722873509 0.0057784203 0.0417910000 413586269 0 402718720 0.0235136896 -0.0150288567 -0.7678533792 2751 1311867262.2200620174 0.0611205548 0.0543032063 0.0722873509 0.0057780629 0.0425680000 413589417 0 402718720 0.0246812776 -0.0152586065 -0.7729274035 2752 1311867262.2557590008 0.0611452833 0.0543056926 0.0722873509 0.0057770456 0.0414020000 413592573 0 402718720 0.0241064616 -0.0136294477 -0.7782560587 2753 1311867262.2893559933 0.0650996193 0.0543096133 0.0722873509 0.0057785778 0.0419030000 413595841 0 402718720 0.0241952464 -0.0091033131 -0.7795360088 2754 1311867262.3192830086 0.0619213805 0.0543123772 0.0722873509 0.0057788260 0.0530500000 413598541 0 402718720 0.0242768563 -0.0098831505 -0.7873671651 2755 1311867262.3543510437 0.0634111539 0.0543156799 0.0722873509 0.0057827294 0.0543210000 413602225 0 402718720 0.0232435651 -0.0069600940 -0.7917760015 2756 1311867262.3862760067 0.0646098703 0.0543194151 0.0722873509 0.0057817180 0.0421180000 413605349 0 402718720 0.0249883868 -0.0041695982 -0.7945283055 2757 1311867262.4192481041 0.0639368072 0.0543229034 0.0722873509 0.0057810004 0.0408580000 413608553 0 402718720 0.0239831209 -0.0029976293 -0.8025258183 2758 1311867262.4579370022 0.0627623722 0.0543259634 0.0722873509 0.0057805196 0.0410490000 413611933 0 402718720 0.0242447481 -0.0033491030 -0.8062400222 2759 1311867262.4882910252 0.0639601424 0.0543294553 0.0722873509 0.0057837494 0.0408560000 413614793 0 402718720 0.0262301750 -0.0009817481 -0.8089457154 2760 1311867262.5228719711 0.0616247691 0.0543320986 0.0722873509 0.0057828828 0.0404990000 413618189 0 402718720 0.0259042792 -0.0028257743 -0.8137570024 2761 1311867262.5554070473 0.0645449013 0.0543357975 0.0722873509 0.0057836060 0.0517630000 413621593 0 402718720 0.0210553370 -0.0002196804 -0.8179661632 2762 1311867262.5873200893 0.0674940944 0.0543405616 0.0722873509 0.0057941788 0.0406240000 413624733 0 402718720 0.0212026387 0.0046461299 -0.8227624297 2763 1311867262.6235508919 0.0665922537 0.0543449958 0.0722873509 0.0057982390 0.0533480000 413627881 0 402718720 0.0237233527 0.0065056607 -0.8274739385 2764 1311867262.6548008919 0.0673054829 0.0543496848 0.0722873509 0.0057980937 0.0409320000 413630909 0 402718720 0.0229382999 0.0088979229 -0.8338230848 2765 1311867262.6901140213 0.0666984692 0.0543541509 0.0722873509 0.0058004015 0.0408850000 413634065 0 402718720 0.0199804232 0.0074609369 -0.8350379467 2766 1311867262.7234799862 0.0684146211 0.0543592342 0.0722873509 0.0057995002 0.0404540000 413637333 0 402718720 0.0202204101 0.0101664215 -0.8383799195 2767 1311867262.7550880909 0.0647209883 0.0543629790 0.0722873509 0.0058058629 0.0502610000 413640385 0 402718720 0.0232720710 0.0074289665 -0.8424490094 2768 1311867262.7890789509 0.0644690320 0.0543666300 0.0722873509 0.0058063846 0.0407640000 413643853 0 402718720 0.0262750983 0.0082537979 -0.8459368348 2769 1311867262.8232269287 0.0631140396 0.0543697891 0.0722873509 0.0058072710 0.0518220000 413647105 0 402718720 0.0266951583 0.0075358301 -0.8522049189 2770 1311867262.8561139107 0.0659830049 0.0543739816 0.0722873509 0.0058081248 0.0510280000 413650565 0 402718720 0.0255059153 0.0095867515 -0.8526434302 2771 1311867262.8878281116 0.0674796328 0.0543787111 0.0722873509 0.0058081113 0.0409090000 413653601 0 402718720 0.0228404813 0.0098501816 -0.8562322259 2772 1311867262.9221930504 0.0656832382 0.0543827892 0.0722873509 0.0058104311 0.0530620000 413656669 0 402718720 0.0276207328 0.0096972808 -0.8602195382 2773 1311867262.9539968967 0.0646160319 0.0543864796 0.0722873509 0.0058125486 0.0569510000 414132313 0 402718720 0.0274819899 0.0078342333 -0.8629132509 2774 1311867262.9877319336 0.0663491413 0.0543907920 0.0722873509 0.0058136279 0.1131740000 414121517 0 402718720 0.0275376327 0.0095492005 -0.8639924526 2775 1311867263.0238440037 0.0651857555 0.0543946821 0.0722873509 0.0058126719 0.1175080000 414125105 0 402718720 0.0271250159 0.0075289980 -0.8654123545 2776 1311867263.0552799702 0.0653151870 0.0543986160 0.0722873509 0.0058119487 0.1101710000 419096985 0 402718720 0.0278484188 0.0084087178 -0.8691138625 2777 1311867263.0870039463 0.0660944954 0.0544028277 0.0722873509 0.0058109524 0.1040970000 427315361 0 402718720 0.0275751501 0.0101792216 -0.8727228045 2778 1311867263.1226899624 0.0660198033 0.0544070094 0.0722873509 0.0058101725 0.0505520000 428097133 0 402718720 0.0290032458 0.0114551261 -0.8756053448 2779 1311867263.1537079811 0.0668812692 0.0544114982 0.0722873509 0.0058128980 0.0831740000 427799989 0 402718720 0.0291348808 0.0126964748 -0.8771260977 2780 1311867263.1884229183 0.0717885792 0.0544177489 0.0722873509 0.0058137440 0.0530970000 427975281 0 402718720 0.0276356712 0.0168171301 -0.8752290010 2781 1311867263.2225809097 0.0716533735 0.0544239466 0.0722873509 0.0058129534 0.1368970000 426214993 0 402718720 0.0282428004 0.0174343213 -0.8774293661 2782 1311867263.2536139488 0.0697022974 0.0544294384 0.0722873509 0.0058136365 0.1206760000 414084565 0 402718720 0.0288970210 0.0169797540 -0.8829857111 2783 1311867263.2884469032 0.0694170371 0.0544348238 0.0722873509 0.0058136727 0.0420390000 414101225 0 402718720 0.0294143856 0.0166508704 -0.8844267130 2784 1311867263.3236269951 0.0705607235 0.0544406162 0.0722873509 0.0058335732 0.0610000000 414104373 0 402718720 0.0288293250 0.0177423656 -0.8862002492 2785 1311867263.3539469242 0.0696934834 0.0544460930 0.0722873509 0.0058344290 0.0421980000 414107641 0 402718720 0.0280558988 0.0170001239 -0.8898449540 2786 1311867263.3856530190 0.0683261380 0.0544510751 0.0722873509 0.0058335551 0.0412460000 414110485 0 402718720 0.0288805105 0.0153837726 -0.8906782866 2787 1311867263.4221460819 0.0679459572 0.0544559171 0.0722873509 0.0058327375 0.0420390000 414113889 0 402718720 0.0307035595 0.0159159973 -0.8944106698 2788 1311867263.4549560547 0.0699748993 0.0544614835 0.0722873509 0.0058322313 0.0421780000 414117077 0 402718720 0.0311905704 0.0184587315 -0.8967431188 2789 1311867263.4876389503 0.0673655197 0.0544661102 0.0722873509 0.0058325745 0.0540090000 414120625 0 402718720 0.0306186005 0.0157318786 -0.9012926221 2790 1311867263.5235950947 0.0720019564 0.0544723955 0.0722873509 0.0058378164 0.0612950000 414568349 0 402718720 0.0292300098 0.0200560093 -0.9051162004 2791 1311867263.5535099506 0.0700110942 0.0544779629 0.0722873509 0.0058382948 0.1215960000 414548981 0 402718720 0.0325935185 0.0190913379 -0.9082496762 2792 1311867263.5855040550 0.0695924684 0.0544833764 0.0722873509 0.0058382552 0.1113730000 414876553 0 402718720 0.0338784680 0.0187441781 -0.9115929604 2793 1311867263.6236140728 0.0705787241 0.0544891392 0.0722873509 0.0058425755 0.1075460000 421430505 0 402718720 0.0341669992 0.0186023116 -0.9124854803 2794 1311867263.6543920040 0.0717664734 0.0544953229 0.0722873509 0.0058436613 0.0888630000 430277861 0 402718720 0.0351811424 0.0205127299 -0.9176000953 2795 1311867263.6903779507 0.0703418702 0.0545009925 0.0722873509 0.0058427431 0.0732250000 428506373 0 402718720 0.0383601971 0.0199506879 -0.9210430384 2796 1311867263.7227630615 0.0722836480 0.0545073525 0.0722873509 0.0058454128 0.0609830000 428258237 0 402718720 0.0389136411 0.0219178200 -0.9219077826 2797 1311867263.7559669018 0.0711121261 0.0545132892 0.0722873509 0.0058448363 0.0531890000 428148405 0 402718720 0.0386985093 0.0206597149 -0.9249590635 2798 1311867263.7911560535 0.0705682412 0.0545190272 0.0722873509 0.0058451784 0.1419150000 426391229 0 402718720 0.0414721705 0.0212864354 -0.9281602502 2799 1311867263.8235189915 0.0710736960 0.0545249417 0.0722873509 0.0058441762 0.1288850000 414556797 0 402718720 0.0419087186 0.0218569636 -0.9306571484 2800 1311867263.8555519581 0.0716759488 0.0545310670 0.0722873509 0.0058437588 0.0413200000 414573617 0 402718720 0.0433628894 0.0234096497 -0.9352582693 2801 1311867263.8925390244 0.0708339065 0.0545368874 0.0722873509 0.0058428066 0.0412740000 414576677 0 402718720 0.0429549441 0.0218943805 -0.9380720854 2802 1311867263.9255890846 0.0709921047 0.0545427601 0.0722873509 0.0058419878 0.0407410000 414579761 0 402718720 0.0463819429 0.0238739699 -0.9425277710 2803 1311867263.9557209015 0.0728119835 0.0545492778 0.0728119835 0.0058409759 0.0388900000 414582981 0 402718720 0.0508728400 0.0277957618 -0.9464973807 2804 1311867263.9913449287 0.0718137547 0.0545554349 0.0728119835 0.0058401512 0.0409310000 414586257 0 402718720 0.0506273210 0.0261817873 -0.9480100870 2805 1311867264.0265080929 0.0718855634 0.0545616132 0.0728119835 0.0058395547 0.0397120000 414589645 0 402718720 0.0495221168 0.0253959224 -0.9502230287 2806 1311867264.0539839268 0.0725906044 0.0545680384 0.0728119835 0.0058387052 0.0393370000 414592521 0 402718720 0.0537970215 0.0284018666 -0.9541447163 2807 1311867264.0935840607 0.0722048134 0.0545743215 0.0728119835 0.0058378988 0.0410820000 414595957 0 402718720 0.0549938567 0.0282981694 -0.9560142159 2808 1311867264.1232929230 0.0711848587 0.0545802369 0.0728119835 0.0058369862 0.0519140000 414599145 0 402718720 0.0546483323 0.0271320269 -0.9580000043 2809 1311867264.1547811031 0.0728693828 0.0545867478 0.0728693828 0.0058371071 0.0413340000 414602373 0 402718720 0.0557007566 0.0298646763 -0.9606324434 2810 1311867264.1908740997 0.0734906495 0.0545934752 0.0734906495 0.0058377017 0.0411980000 414605313 0 402718720 0.0565795638 0.0316063315 -0.9628759027 2811 1311867264.2230439186 0.0725889653 0.0545998770 0.0734906495 0.0058388023 0.0404570000 414608533 0 402718720 0.0559236966 0.0305338204 -0.9648033381 2812 1311867264.2549281120 0.0714917034 0.0546058841 0.0734906495 0.0058417301 0.0406940000 414611561 0 402718720 0.0564517006 0.0299160630 -0.9689851999 2813 1311867264.2910940647 0.0736827850 0.0546126658 0.0736827850 0.0058490813 0.0407520000 414614949 0 402718720 0.0563968383 0.0328681171 -0.9707859755 2814 1311867264.3223540783 0.0705808327 0.0546183403 0.0736827850 0.0058525785 0.0776950000 414618161 0 402718720 0.0582304448 0.0308720395 -0.9737898111 2815 1311867264.3539710045 0.0689343289 0.0546234259 0.0736827850 0.0058572818 0.0406860000 414621205 0 402718720 0.0584839284 0.0293374211 -0.9772722125 2816 1311867264.3903570175 0.0726333484 0.0546298215 0.0736827850 0.0058601724 0.0408150000 414624401 0 402718720 0.0583536550 0.0338466391 -0.9793143868 2817 1311867264.4247128963 0.0710821897 0.0546356619 0.0736827850 0.0058642387 0.0397710000 414627853 0 402718720 0.0588205308 0.0327826813 -0.9816929102 2818 1311867264.4536709785 0.0721723065 0.0546418850 0.0736827850 0.0058647755 0.0412610000 414630761 0 402718720 0.0583400987 0.0346235931 -0.9846535325 2819 1311867264.4911220074 0.0724037439 0.0546481857 0.0736827850 0.0058638635 0.0404360000 414634269 0 402718720 0.0622659661 0.0375363156 -0.9875105619 2820 1311867264.5220930576 0.0728348717 0.0546546349 0.0736827850 0.0058639789 0.0401580000 414637041 0 402718720 0.0607325882 0.0376869217 -0.9884343147 2821 1311867264.5544660091 0.0720083341 0.0546607865 0.0736827850 0.0058646243 0.0402440000 414640253 0 402718720 0.0614942014 0.0380658507 -0.9932588339 2822 1311867264.5919189453 0.0714496151 0.0546667358 0.0736827850 0.0058666359 0.0399990000 414643569 0 402718720 0.0610713065 0.0371365249 -0.9949430227 2823 1311867264.6239540577 0.0709270835 0.0546724957 0.0736827850 0.0058683880 0.0397470000 414646925 0 402718720 0.0631984621 0.0376217142 -0.9974575043 2824 1311867264.6537890434 0.0704269111 0.0546780745 0.0736827850 0.0058676165 0.0396090000 414649977 0 402718720 0.0614159629 0.0367215201 -0.9995096326 2825 1311867264.6908979416 0.0704816580 0.0546836687 0.0736827850 0.0058669163 0.0518180000 414653181 0 402718720 0.0623851158 0.0373896062 -1.0015310049 2826 1311867264.7228040695 0.0695430562 0.0546889268 0.0736827850 0.0058667621 0.0712460000 414656449 0 402718720 0.0640130565 0.0366963670 -1.0023053885 2827 1311867264.7547140121 0.0724860430 0.0546952222 0.0736827850 0.0058672803 0.0398840000 414659477 0 402718720 0.0628672689 0.0388048291 -1.0019189119 2828 1311867264.7909140587 0.0736196637 0.0547019140 0.0736827850 0.0058667223 0.0392420000 414662881 0 402718720 0.0656141192 0.0414265245 -1.0069593191 2829 1311867264.8233439922 0.0729215443 0.0547083543 0.0736827850 0.0058662981 0.0389690000 414665845 0 402718720 0.0667026192 0.0411599427 -1.0090062618 2830 1311867264.8540790081 0.0736316070 0.0547150410 0.0736827850 0.0058658594 0.0391170000 414669129 0 402718720 0.0630944073 0.0399937630 -1.0063986778 2831 1311867264.8904409409 0.0706911609 0.0547206842 0.0736827850 0.0058653703 0.0398290000 414672325 0 402718720 0.0671408623 0.0387810692 -1.0094780922 2832 1311867264.9235579967 0.0709421337 0.0547264122 0.0736827850 0.0058643665 0.0398550000 414675913 0 402718720 0.0679740012 0.0395135283 -1.0105820894 2833 1311867264.9598839283 0.0695460811 0.0547316432 0.0736827850 0.0058639389 0.0394670000 414678853 0 402718720 0.0690035596 0.0387245566 -1.0123391151 2834 1311867264.9916839600 0.0710922033 0.0547374162 0.0736827850 0.0058633194 0.0392900000 414681873 0 402718720 0.0669978037 0.0392663404 -1.0130158663 2835 1311867265.0220029354 0.0749147534 0.0547445334 0.0749147534 0.0058631765 0.0385460000 414685413 0 402718720 0.0653156489 0.0424223095 -1.0113140345 2836 1311867265.0581490993 0.0723971352 0.0547507579 0.0749147534 0.0058634340 0.0479580000 414688497 0 402718720 0.0700889379 0.0419869572 -1.0150727034 2837 1311867265.0911719799 0.0708134249 0.0547564197 0.0749147534 0.0058624560 0.0390800000 414691461 0 402718720 0.0692054331 0.0405450612 -1.0165793896 2838 1311867265.1217110157 0.0711019263 0.0547621793 0.0749147534 0.0058623950 0.0395520000 414694489 0 402718720 0.0686679706 0.0407405123 -1.0172566175 2839 1311867265.1582090855 0.0711629540 0.0547679562 0.0749147534 0.0058615965 0.0390750000 414697893 0 402718720 0.0715719387 0.0425376147 -1.0209527016 2840 1311867265.1899518967 0.0703433901 0.0547734405 0.0749147534 0.0058619703 0.0390050000 414701177 0 402718720 0.0707087666 0.0413460359 -1.0215939283 2841 1311867265.2225220203 0.0705006048 0.0547789763 0.0749147534 0.0058625556 0.0381720000 414704061 0 402718720 0.0701022521 0.0415278450 -1.0242785215 2842 1311867265.2581849098 0.0683225021 0.0547837418 0.0749147534 0.0058655284 0.0558610000 415156509 0 402718720 0.0723284557 0.0394930020 -1.0245976448 2843 1311867265.2915129662 0.0687108859 0.0547886405 0.0749147534 0.0058654441 0.1126360000 415163269 0 402718720 0.0706594810 0.0389476195 -1.0276335478 2844 1311867265.3220860958 0.0694245249 0.0547937868 0.0749147534 0.0058663988 0.1038760000 415501365 0 402718720 0.0719054490 0.0394534394 -1.0276024342 2845 1311867265.3585588932 0.0706597939 0.0547993636 0.0749147534 0.0058656987 0.1063200000 425095969 0 402718720 0.0694583133 0.0397751480 -1.0287883282 2846 1311867265.3912470341 0.0719185695 0.0548053788 0.0749147534 0.0058647940 0.0648820000 429546973 0 402718720 0.0696536973 0.0406074524 -1.0291126966 2847 1311867265.4244530201 0.0701414868 0.0548107655 0.0749147534 0.0058647718 0.0813440000 428316969 0 402718720 0.0692776293 0.0387267768 -1.0328325033 2848 1311867265.4604411125 0.0712677762 0.0548165440 0.0749147534 0.0058641458 0.0553060000 428960045 0 402718720 0.0696886182 0.0398040116 -1.0337729454 2849 1311867265.4902420044 0.0727340952 0.0548228330 0.0749147534 0.0058637087 0.0517120000 429137225 0 402718720 0.0688395724 0.0415641218 -1.0372302532 2850 1311867265.5230569839 0.0729423314 0.0548291908 0.0749147534 0.0058630990 0.1375310000 427389265 0 402718720 0.0724096596 0.0433363914 -1.0385825634 2851 1311867265.5594520569 0.0704895258 0.0548346837 0.0749147534 0.0058623507 0.0929150000 415184685 0 402718720 0.0702196881 0.0402452350 -1.0411332846 2852 1311867265.5932300091 0.0715479106 0.0548405439 0.0749147534 0.0058616248 0.0410630000 415187913 0 402718720 0.0684962124 0.0404739231 -1.0421521664 2853 1311867265.6250700951 0.0738196746 0.0548471962 0.0749147534 0.0058606578 0.0397310000 415190741 0 402718720 0.0695888251 0.0434661955 -1.0443627834 2854 1311867265.6610729694 0.0732256025 0.0548536357 0.0749147534 0.0058601899 0.0409160000 415194321 0 402718720 0.0690246671 0.0427111834 -1.0446681976 2855 1311867265.6956009865 0.0741756856 0.0548604035 0.0749147534 0.0058591940 0.0399680000 415197413 0 402718720 0.0711677745 0.0449090302 -1.0454961061 2856 1311867265.7221889496 0.0741182268 0.0548671465 0.0749147534 0.0058582634 0.0401320000 415200769 0 402718720 0.0693417042 0.0442240089 -1.0454857349 2857 1311867265.7626268864 0.0773061812 0.0548750005 0.0773061812 0.0058593098 0.0485710000 415619405 0 402718720 0.0694703609 0.0487392247 -1.0464854240 2858 1311867265.7925920486 0.0763213784 0.0548825045 0.0773061812 0.0058594943 0.1095910000 415596385 0 402718720 0.0709541515 0.0493435860 -1.0492144823 2859 1311867265.8224210739 0.0735512823 0.0548890343 0.0773061812 0.0058590181 0.1054040000 415938105 0 402718720 0.0707819015 0.0472196192 -1.0520138741 2860 1311867265.8593389988 0.0771860555 0.0548968305 0.0773061812 0.0058586818 0.1051770000 424742421 0 402718720 0.0706766397 0.0512146354 -1.0503954887 2861 1311867265.8943600655 0.0754152611 0.0549040023 0.0773061812 0.0058580451 0.0719860000 429875029 0 402718720 0.0722805709 0.0507258773 -1.0522583723 2862 1311867265.9256451130 0.0736217871 0.0549105424 0.0773061812 0.0058573409 0.0832440000 429769049 0 402718720 0.0721896216 0.0489480197 -1.0529264212 2863 1311867265.9620978832 0.0730763376 0.0549168874 0.0773061812 0.0058567056 0.0443920000 429821049 0 402718720 0.0707707182 0.0474020541 -1.0526198149 2864 1311867265.9908990860 0.0733127221 0.0549233105 0.0773061812 0.0058568824 0.1440670000 427841101 0 402718720 0.0706980973 0.0482029915 -1.0550073385 2865 1311867266.0233469009 0.0759752244 0.0549306585 0.0773061812 0.0058561349 0.1140900000 415603221 0 402718720 0.0711128414 0.0511327833 -1.0551759005 2866 1311867266.0634260178 0.0752195194 0.0549377376 0.0773061812 0.0058551352 0.0458640000 415619889 0 402718720 0.0698951632 0.0502743721 -1.0574615002 2867 1311867266.0954639912 0.0734558031 0.0549441967 0.0773061812 0.0058542259 0.0408750000 415622853 0 402718720 0.0702252686 0.0489051938 -1.0593563318 2868 1311867266.1241600513 0.0748621598 0.0549511416 0.0773061812 0.0058539715 0.0510950000 415626153 0 402718720 0.0699019879 0.0503812283 -1.0590162277 2869 1311867266.1634809971 0.0748652369 0.0549580827 0.0773061812 0.0058542596 0.0404120000 415629413 0 402718720 0.0708994046 0.0511770248 -1.0610727072 2870 1311867266.1922690868 0.0744174272 0.0549648629 0.0773061812 0.0058533469 0.0407690000 415632449 0 402718720 0.0703429058 0.0506438017 -1.0612521172 2871 1311867266.2255198956 0.0757660121 0.0549721082 0.0773061812 0.0058526748 0.0535710000 415635733 0 402718720 0.0683254302 0.0522166044 -1.0637507439 2872 1311867266.2597849369 0.0759846568 0.0549794246 0.0773061812 0.0058517449 0.0412250000 415638881 0 402718720 0.0681712329 0.0528218001 -1.0647505522 2873 1311867266.2915120125 0.0730832517 0.0549857259 0.0773061812 0.0058512810 0.0505660000 415641837 0 402718720 0.0685081929 0.0507329106 -1.0679095984 2874 1311867266.3258039951 0.0757740512 0.0549929592 0.0773061812 0.0058506004 0.0401120000 415644985 0 402718720 0.0676108301 0.0532307923 -1.0674282312 2875 1311867266.3601551056 0.0746804327 0.0549998070 0.0773061812 0.0058498507 0.0401550000 415648381 0 402718720 0.0668314993 0.0515657961 -1.0676292181 2876 1311867266.3913159370 0.0764763430 0.0550072745 0.0773061812 0.0058489000 0.0405490000 415651289 0 402718720 0.0675606281 0.0538141578 -1.0687062740 2877 1311867266.4254870415 0.0726213902 0.0550133969 0.0773061812 0.0058501419 0.0509090000 415654749 0 402718720 0.0675438344 0.0496099591 -1.0707900524 2878 1311867266.4612910748 0.0758939683 0.0550206521 0.0773061812 0.0058494331 0.0401770000 415657769 0 402718720 0.0658474416 0.0524687320 -1.0727471113 2879 1311867266.4912600517 0.0740328282 0.0550272559 0.0773061812 0.0058487840 0.0404090000 415660821 0 402718720 0.0673832297 0.0511905849 -1.0749650002 2880 1311867266.5284929276 0.0717534795 0.0550330636 0.0773061812 0.0058479311 0.0399250000 415664481 0 402718720 0.0676242113 0.0485584140 -1.0767589808 2881 1311867266.5587360859 0.0732789114 0.0550393967 0.0773061812 0.0058479480 0.0397340000 415667517 0 402718720 0.0654957220 0.0490775406 -1.0781975985 2882 1311867266.5906820297 0.0739867166 0.0550459711 0.0773061812 0.0058470019 0.0490940000 416087465 0 402718720 0.0664874613 0.0499095917 -1.0785828829 2883 1311867266.6256470680 0.0748500898 0.0550528404 0.0773061812 0.0058474353 0.1203320000 416072217 0 402718720 0.0653333887 0.0500467420 -1.0789636374 2884 1311867266.6596419811 0.0734886676 0.0550592328 0.0773061812 0.0058465976 0.1115200000 416408413 0 402718720 0.0664643422 0.0490219742 -1.0803693533 2885 1311867266.6914939880 0.0753780603 0.0550662757 0.0773061812 0.0058458039 0.1078630000 426542629 0 402718720 0.0660945177 0.0503926873 -1.0793676376 2886 1311867266.7260789871 0.0733032078 0.0550725948 0.0773061812 0.0058451077 0.0639560000 430678197 0 402718720 0.0644522309 0.0471581519 -1.0806639194 2887 1311867266.7576239109 0.0741838589 0.0550792146 0.0773061812 0.0058441109 0.0673250000 430766913 0 402718720 0.0657809824 0.0485813469 -1.0821359158 2888 1311867266.7898240089 0.0751134381 0.0550861517 0.0773061812 0.0058438750 0.0441720000 430611537 0 402718720 0.0661997572 0.0494233519 -1.0823497772 2889 1311867266.8257129192 0.0742769390 0.0550927944 0.0773061812 0.0058433531 0.1410500000 428827797 0 402718720 0.0664122701 0.0489596277 -1.0842962265 2890 1311867266.8575000763 0.0762249455 0.0551001065 0.0773061812 0.0058425669 0.1211720000 416079613 0 402718720 0.0640283227 0.0496124029 -1.0825835466 2891 1311867266.8898739815 0.0759779960 0.0551073282 0.0773061812 0.0058418111 0.0413720000 416096081 0 402718720 0.0664833263 0.0504953563 -1.0828474760 2892 1311867266.9266190529 0.0748159438 0.0551141431 0.0773061812 0.0058409009 0.0402900000 416099341 0 402718720 0.0652059391 0.0483876169 -1.0808860064 2893 1311867266.9576549530 0.0772327334 0.0551217887 0.0773061812 0.0058399457 0.0405160000 416102633 0 402718720 0.0656862408 0.0513216108 -1.0812466145 2894 1311867266.9920771122 0.0791890547 0.0551301049 0.0791890547 0.0058405367 0.0517040000 416105709 0 402718720 0.0655101910 0.0536669642 -1.0796664953 2895 1311867267.0259480476 0.0770425051 0.0551376740 0.0791890547 0.0058405502 0.0407390000 416108937 0 402718720 0.0647088736 0.0514909029 -1.0792253017 2896 1311867267.0603609085 0.0772735924 0.0551453176 0.0791890547 0.0058396772 0.0405080000 416111957 0 402718720 0.0656510442 0.0523302108 -1.0792585611 2897 1311867267.0929799080 0.0778296068 0.0551531479 0.0791890547 0.0058391119 0.0406280000 416114929 0 402718720 0.0624940321 0.0508597046 -1.0745193958 2898 1311867267.1266899109 0.0768160820 0.0551606230 0.0791890547 0.0058417389 0.0404130000 416118077 0 402718720 0.0609383881 0.0498706698 -1.0749340057 2899 1311867267.1586909294 0.0762407184 0.0551678945 0.0791890547 0.0058419965 0.0508040000 416121297 0 402718720 0.0619671196 0.0493347645 -1.0758228302 2900 1311867267.1916129589 0.0733259916 0.0551741559 0.0791890547 0.0058417137 0.0508130000 416124701 0 402718720 0.0623244122 0.0460501462 -1.0756732225 2901 1311867267.2262039185 0.0760769174 0.0551813613 0.0791890547 0.0058412805 0.0470780000 416127785 0 402718720 0.0612740219 0.0482432544 -1.0735393763 2902 1311867267.2587449551 0.0761602968 0.0551885904 0.0791890547 0.0058403205 0.0398020000 416130869 0 402718720 0.0632149130 0.0494134575 -1.0742516518 2903 1311867267.2920761108 0.0742627457 0.0551951609 0.0791890547 0.0058400069 0.0505070000 416134009 0 402718720 0.0628404319 0.0471524894 -1.0738741159 2904 1311867267.3265810013 0.0753257573 0.0552020929 0.0791890547 0.0058394364 0.0398730000 416137461 0 402718720 0.0606275760 0.0466710776 -1.0703020096 2905 1311867267.3609950542 0.0757881775 0.0552091794 0.0791890547 0.0058387028 0.0627100000 416140641 0 402718720 0.0593350902 0.0466720313 -1.0698472261 2906 1311867267.3945980072 0.0743206963 0.0552157559 0.0791890547 0.0058379596 0.0402100000 416143725 0 402718720 0.0605994873 0.0455733389 -1.0703097582 2907 1311867267.4286189079 0.0738295689 0.0552221590 0.0791890547 0.0058370442 0.0391880000 416147177 0 402718720 0.0610592924 0.0443009585 -1.0670677423 2908 1311867267.4595789909 0.0748110786 0.0552288952 0.0791890547 0.0058360653 0.0397940000 416149821 0 402718720 0.0600685365 0.0451975465 -1.0689895153 2909 1311867267.4935429096 0.0744854212 0.0552355149 0.0791890547 0.0058355695 0.0525360000 416153361 0 402718720 0.0601465888 0.0444451123 -1.0672281981 2910 1311867267.5264101028 0.0770056173 0.0552429960 0.0791890547 0.0058350677 0.0499840000 416156509 0 402718720 0.0592253134 0.0465210974 -1.0652472973 2911 1311867267.5577969551 0.0751517713 0.0552498352 0.0791890547 0.0058378349 0.0523300000 416159841 0 402718720 0.0597860888 0.0438691080 -1.0623471737 2912 1311867267.5954480171 0.0755072758 0.0552567917 0.0791890547 0.0058392368 0.0400290000 416162989 0 402718720 0.0586527064 0.0433434248 -1.0593161583 2913 1311867267.6272020340 0.0776266158 0.0552644710 0.0791890547 0.0058386001 0.0397000000 416166025 0 402718720 0.0574746281 0.0459396839 -1.0607389212 2914 1311867267.6608970165 0.0749268085 0.0552712186 0.0791890547 0.0058379124 0.0392960000 416169253 0 402718720 0.0583581775 0.0430595428 -1.0588924885 2915 1311867267.6955730915 0.0738424137 0.0552775895 0.0791890547 0.0058371409 0.0398710000 416172449 0 402718720 0.0586545505 0.0415949821 -1.0568702221 2916 1311867267.7264549732 0.0760554075 0.0552847149 0.0791890547 0.0058460397 0.0507440000 416175557 0 402718720 0.0579497777 0.0441797376 -1.0557078123 2917 1311867267.7624979019 0.0743506476 0.0552912511 0.0791890547 0.0058521831 0.0501340000 416178937 0 402718720 0.0570525266 0.0410553813 -1.0524601936 2918 1311867267.7957980633 0.0736036077 0.0552975267 0.0791890547 0.0058515022 0.0404610000 416182165 0 402718720 0.0557152554 0.0401479900 -1.0533218384 2919 1311867267.8323969841 0.0757131428 0.0553045208 0.0791890547 0.0058509878 0.0523710000 416185481 0 402718720 0.0564901829 0.0428741425 -1.0527336597 2920 1311867267.8601078987 0.0758896917 0.0553115705 0.0791890547 0.0058505744 0.0394880000 416188493 0 402718720 0.0564672239 0.0429883003 -1.0507630110 2921 1311867267.8989579678 0.0724359080 0.0553174330 0.0791890547 0.0058522653 0.0506910000 416191737 0 402718720 0.0545623153 0.0380197465 -1.0482168198 2922 1311867267.9282948971 0.0734306723 0.0553236319 0.0791890547 0.0058514409 0.0402660000 416194917 0 402718720 0.0549241304 0.0390154570 -1.0464053154 2923 1311867267.9643011093 0.0764582679 0.0553308623 0.0791890547 0.0058517320 0.0779210000 416198241 0 402718720 0.0529566668 0.0413451046 -1.0444855690 2924 1311867267.9947459698 0.0753668919 0.0553377146 0.0791890547 0.0058507544 0.0404780000 416201133 0 402718720 0.0533745736 0.0395219699 -1.0407009125 2925 1311867268.0287120342 0.0736871883 0.0553439879 0.0791890547 0.0058501904 0.0510730000 416204217 0 402718720 0.0507865883 0.0363204330 -1.0402956009 2926 1311867268.0588328838 0.0742975324 0.0553504656 0.0791890547 0.0058495107 0.0402220000 416207365 0 402718720 0.0525001064 0.0376877189 -1.0395375490 2927 1311867268.0946080685 0.0752108768 0.0553572508 0.0791890547 0.0058488732 0.0404320000 416210817 0 402718720 0.0517336875 0.0375416949 -1.0361652374 2928 1311867268.1253910065 0.0751122907 0.0553639978 0.0791890547 0.0058484693 0.0400440000 416213861 0 402718720 0.0520362705 0.0368303210 -1.0341897011 2929 1311867268.1606659889 0.0739470273 0.0553703422 0.0791890547 0.0058500125 0.0408050000 416217193 0 402718720 0.0524965562 0.0358861834 -1.0332843065 2930 1311867268.1981959343 0.0740351975 0.0553767125 0.0791890547 0.0058491985 0.0403580000 416220525 0 402718720 0.0503237695 0.0350461826 -1.0312772989 2931 1311867268.2290298939 0.0739981532 0.0553830658 0.0791890547 0.0058482472 0.0407700000 416224025 0 402718720 0.0511077717 0.0345924050 -1.0274107456 2932 1311867268.2579200268 0.0751884431 0.0553898207 0.0791890547 0.0058478239 0.0525200000 416226741 0 402718720 0.0495296605 0.0339818224 -1.0221230984 2933 1311867268.2951550484 0.0744813085 0.0553963299 0.0791890547 0.0058486179 0.0405730000 416230081 0 402718720 0.0485072359 0.0327940583 -1.0209906101 2934 1311867268.3274168968 0.0742500946 0.0554027558 0.0791890547 0.0058486866 0.0790370000 416233229 0 402718720 0.0463467054 0.0309222862 -1.0178940296 2935 1311867268.3586890697 0.0734394118 0.0554089012 0.0791890547 0.0058480793 0.0411090000 416236257 0 402718720 0.0465495065 0.0299064517 -1.0166877508 2936 1311867268.3934800625 0.0741150975 0.0554152725 0.0791890547 0.0058474861 0.0412570000 416239349 0 402718720 0.0460079052 0.0306787640 -1.0154181719 2937 1311867268.4261479378 0.0726817772 0.0554211515 0.0791890547 0.0058465640 0.0415330000 416242689 0 402718720 0.0460836105 0.0288347080 -1.0126662254 2938 1311867268.4581170082 0.0731184408 0.0554271751 0.0791890547 0.0058467370 0.0413510000 416245773 0 402718720 0.0463134460 0.0294701532 -1.0107903481 2939 1311867268.4943540096 0.0739092156 0.0554334636 0.0791890547 0.0058460804 0.0502770000 416249113 0 402718720 0.0433793329 0.0289153829 -1.0068244934 2940 1311867268.5280330181 0.0741136000 0.0554398174 0.0791890547 0.0058451233 0.0414760000 416252253 0 402718720 0.0420064218 0.0281683803 -1.0033222437 2941 1311867268.5616149902 0.0721047744 0.0554454838 0.0791890547 0.0058456171 0.0414310000 416255393 0 402718720 0.0399701297 0.0250170678 -1.0016672611 2942 1311867268.5949339867 0.0729089454 0.0554514198 0.0791890547 0.0058468776 0.0413300000 416258685 0 402718720 0.0403606109 0.0261551961 -0.9995334148 2943 1311867268.6294579506 0.0733614787 0.0554575054 0.0791890547 0.0058503776 0.0416000000 416261881 0 402718720 0.0392321497 0.0260479972 -0.9972612858 2944 1311867268.6639370918 0.0729671493 0.0554634530 0.0791890547 0.0058516619 0.0411790000 416265333 0 402718720 0.0382531136 0.0246658325 -0.9928478599 2945 1311867268.6937808990 0.0737090707 0.0554696484 0.0791890547 0.0058513021 0.0810410000 416268369 0 402718720 0.0368547030 0.0245494246 -0.9898305535 2946 1311867268.7282569408 0.0700624436 0.0554746019 0.0791890547 0.0058510332 0.0420120000 416271397 0 402718720 0.0350600332 0.0202150643 -0.9898046255 2947 1311867268.7629311085 0.0707075521 0.0554797708 0.0791890547 0.0058513545 0.0421120000 416274785 0 402718720 0.0345146917 0.0205518305 -0.9884967804 2948 1311867268.7951219082 0.0723984912 0.0554855099 0.0791890547 0.0058510342 0.0415850000 416277685 0 402718720 0.0336084180 0.0222444236 -0.9855536819 2949 1311867268.8264629841 0.0720031485 0.0554911110 0.0791890547 0.0058507063 0.0418630000 416281089 0 402718720 0.0327855945 0.0207287818 -0.9797176719 2950 1311867268.8615820408 0.0725905895 0.0554969074 0.0791890547 0.0058506114 0.0503890000 416284245 0 402718720 0.0302888751 0.0213341191 -0.9787473083 2951 1311867268.8947710991 0.0722583458 0.0555025873 0.0791890547 0.0058575249 0.0416730000 416287649 0 402718720 0.0305863321 0.0213928372 -0.9768702984 2952 1311867268.9271900654 0.0728227049 0.0555084546 0.0791890547 0.0058646755 0.0412580000 416290213 0 402718720 0.0287411585 0.0212122351 -0.9730978608 2953 1311867268.9633738995 0.0712632909 0.0555137898 0.0791890547 0.0058638699 0.0413070000 416293721 0 402718720 0.0289718807 0.0192249864 -0.9688481688 2954 1311867268.9942259789 0.0727127716 0.0555196120 0.0791890547 0.0058636956 0.0413160000 416296965 0 402718720 0.0268339962 0.0201564580 -0.9667309523 2955 1311867269.0293419361 0.0719201639 0.0555251621 0.0791890547 0.0058634808 0.0414720000 416300217 0 402718720 0.0236985981 0.0174480975 -0.9624371529 2956 1311867269.0628340244 0.0726470575 0.0555309544 0.0791890547 0.0058627146 0.0544750000 416303485 0 402718720 0.0228742138 0.0173613504 -0.9576502442 2957 1311867269.0942130089 0.0698878914 0.0555358096 0.0791890547 0.0058624603 0.0537250000 416306417 0 402718720 0.0232193060 0.0147340074 -0.9571692944 2958 1311867269.1263980865 0.0709443167 0.0555410187 0.0791890547 0.0058617997 0.0423520000 416309661 0 402718720 0.0218029320 0.0148590580 -0.9533891678 2959 1311867269.1618270874 0.0716599301 0.0555464661 0.0791890547 0.0058609323 0.0422950000 416312673 0 402718720 0.0209047869 0.0155300274 -0.9504205585 2960 1311867269.1941618919 0.0712662786 0.0555517769 0.0791890547 0.0058605842 0.0413650000 416315821 0 402718720 0.0182796419 0.0139102489 -0.9464820027 2961 1311867269.2266249657 0.0702140555 0.0555567287 0.0791890547 0.0058622607 0.0413670000 416319225 0 402718720 0.0188021660 0.0133806914 -0.9443877339 2962 1311867269.2623720169 0.0693916753 0.0555613995 0.0791890547 0.0058624038 0.0541260000 416322485 0 402718720 0.0169427320 0.0122392178 -0.9421383739 2963 1311867269.2948200703 0.0715182871 0.0555667849 0.0791890547 0.0058889129 0.0418650000 416325257 0 402718720 0.0146114714 0.0129696205 -0.9358882904 2964 1311867269.3261830807 0.0697945207 0.0555715851 0.0791890547 0.0058950264 0.0415310000 416328669 0 402718720 0.0157835223 0.0121676177 -0.9348654151 2965 1311867269.3641560078 0.0711929873 0.0555768537 0.0791890547 0.0058968083 0.0417820000 416331921 0 402718720 0.0163804106 0.0146424621 -0.9312981963 2966 1311867269.3967740536 0.0712408796 0.0555821349 0.0791890547 0.0058977373 0.0416780000 416335341 0 402718720 0.0119757876 0.0133389011 -0.9278712273 2967 1311867269.4275820255 0.0714540407 0.0555874843 0.0791890547 0.0058987963 0.0419270000 416338489 0 402718720 0.0106737763 0.0140415952 -0.9256383777 2968 1311867269.4626441002 0.0692371801 0.0555920833 0.0791890547 0.0058989272 0.0416500000 416341645 0 402718720 0.0110009834 0.0133678615 -0.9237302542 2969 1311867269.4938280582 0.0705807060 0.0555971317 0.0791890547 0.0059182269 0.0415130000 416344753 0 402718720 0.0102123432 0.0144803524 -0.9185742736 2970 1311867269.5278589725 0.0705460384 0.0556021650 0.0791890547 0.0059362490 0.0420950000 416347885 0 402718720 0.0061062239 0.0138455778 -0.9147208333 2971 1311867269.5634589195 0.0677233040 0.0556062448 0.0791890547 0.0059358633 0.0418950000 416351145 0 402718720 0.0068754740 0.0128221065 -0.9148898721 2972 1311867269.5962390900 0.0679705888 0.0556104051 0.0791890547 0.0059351175 0.0417270000 416354309 0 402718720 0.0067931004 0.0127397329 -0.9093148708 2973 1311867269.6306080818 0.0684558749 0.0556147258 0.0791890547 0.0059347997 0.0420280000 416357513 0 402718720 0.0018387809 0.0112134591 -0.9034572244 2974 1311867269.6631560326 0.0699657798 0.0556195513 0.0791890547 0.0059340116 0.0498260000 416360557 0 402718720 -0.0002903342 0.0117995739 -0.8991151452 2975 1311867269.6964600086 0.0694851354 0.0556242120 0.0791890547 0.0059372719 0.0400720000 416363761 0 402718720 0.0017927401 0.0138574243 -0.9005246758 2976 1311867269.7280869484 0.0679112449 0.0556283407 0.0791890547 0.0059367033 0.0414150000 416367397 0 402718720 0.0001502074 0.0114336461 -0.8971378803 2977 1311867269.7622261047 0.0665282011 0.0556320020 0.0791890547 0.0059358689 0.0412620000 416370489 0 402718720 -0.0011609979 0.0098962858 -0.8968777061 2978 1311867269.7974090576 0.0681878775 0.0556362183 0.0791890547 0.0059361077 0.0417310000 416373837 0 402718720 -0.0038746744 0.0100081190 -0.8918967843 2979 1311867269.8295869827 0.0682339594 0.0556404471 0.0791890547 0.0059477349 0.0412510000 416376617 0 402718720 -0.0047682002 0.0095470026 -0.8889484406 2980 1311867269.8676230907 0.0684030429 0.0556447299 0.0791890547 0.0059471506 0.0501680000 416380085 0 402718720 -0.0055539906 0.0095266700 -0.8882099390 2981 1311867269.8953619003 0.0673379228 0.0556486524 0.0791890547 0.0059463920 0.0418170000 416383201 0 402718720 -0.0061321966 0.0081492290 -0.8873004913 2982 1311867269.9344720840 0.0677593276 0.0556527137 0.0791890547 0.0059455578 0.0416040000 416386389 0 402718720 -0.0068532601 0.0078902617 -0.8838453889 2983 1311867269.9627900124 0.0687203482 0.0556570944 0.0791890547 0.0059515122 0.0419220000 416389737 0 402718720 -0.0089652576 0.0074785501 -0.8811118007 2984 1311867269.9987258911 0.0679502711 0.0556612141 0.0791890547 0.0059508187 0.0415670000 416392741 0 402718720 -0.0084359981 0.0062451474 -0.8790626526 2985 1311867270.0306990147 0.0669048429 0.0556649808 0.0791890547 0.0059511805 0.0420000000 416395801 0 402718720 -0.0055949353 0.0057305358 -0.8771107197 2986 1311867270.0660951138 0.0665536672 0.0556686274 0.0791890547 0.0059502467 0.0537660000 416399285 0 402718720 -0.0077069625 0.0040632710 -0.8750523329 2987 1311867270.0948200226 0.0664919764 0.0556722509 0.0791890547 0.0059494894 0.0416610000 416402537 0 402718720 -0.0076268986 0.0036194548 -0.8732733130 2988 1311867270.1336340904 0.0674004927 0.0556761760 0.0791890547 0.0059486299 0.0417040000 416405773 0 402718720 -0.0092921481 0.0032598823 -0.8698747754 2989 1311867270.1624090672 0.0677412972 0.0556802125 0.0791890547 0.0059478243 0.0421300000 416408505 0 402718720 -0.0088675283 0.0033991002 -0.8675388098 2990 1311867270.1943540573 0.0678199753 0.0556842726 0.0791890547 0.0059474881 0.0420130000 416411845 0 402718720 -0.0094200931 0.0025847554 -0.8644949794 2991 1311867270.2323369980 0.0682084635 0.0556884599 0.0791890547 0.0059494166 0.0415750000 416414985 0 402718720 -0.0096642040 0.0025724992 -0.8620890975 2992 1311867270.2655749321 0.0673934072 0.0556923720 0.0791890547 0.0059505038 0.0429310000 416418069 0 402718720 -0.0091535039 0.0012465790 -0.8598598242 2993 1311867270.2960460186 0.0654434860 0.0556956300 0.0791890547 0.0059496559 0.0416750000 416421497 0 402718720 -0.0097092204 -0.0017911904 -0.8574445844 2994 1311867270.3346099854 0.0676178262 0.0556996120 0.0791890547 0.0059489651 0.0420710000 416424645 0 402718720 -0.0106681623 -0.0006486624 -0.8527541757 2995 1311867270.3624660969 0.0666650757 0.0557032732 0.0791890547 0.0059483285 0.0421020000 416428001 0 402718720 -0.0094678774 -0.0024102181 -0.8492246270 2996 1311867270.3957469463 0.0653280690 0.0557064858 0.0791890547 0.0059494726 0.0587670000 416430957 0 402718720 -0.0105493777 -0.0049755350 -0.8470075727 2997 1311867270.4334359169 0.0688853785 0.0557108831 0.0791890547 0.0059555860 0.0416550000 416434137 0 402718720 -0.0112070814 -0.0012760200 -0.8454713225 2998 1311867270.4641909599 0.0665611401 0.0557145023 0.0791890547 0.0059549411 0.0607240000 416437541 0 402718720 -0.0099394657 -0.0043958277 -0.8419288397 2999 1311867270.4954609871 0.0649847910 0.0557175934 0.0791890547 0.0059546812 0.0417520000 416440513 0 402718720 -0.0111411884 -0.0075921454 -0.8392723203 3000 1311867270.5331869125 0.0667447820 0.0557212692 0.0791890547 0.0059539942 0.0542830000 416444029 0 402718720 -0.0113626048 -0.0074674599 -0.8346748948 3001 1311867270.5629880428 0.0670707151 0.0557250511 0.0791890547 0.0059531319 0.0422640000 416447121 0 402718720 -0.0117693655 -0.0090117864 -0.8305018544 3002 1311867270.5944859982 0.0641007200 0.0557278411 0.0791890547 0.0059523755 0.0528490000 416449837 0 402718720 -0.0108794868 -0.0131702051 -0.8287600875 3003 1311867270.6312110424 0.0651819110 0.0557309893 0.0791890547 0.0059517432 0.0423360000 416453609 0 402718720 -0.0103622042 -0.0117429011 -0.8291755915 3004 1311867270.6644439697 0.0646212623 0.0557339488 0.0791890547 0.0059530936 0.0511760000 416456501 0 402718720 -0.0103878230 -0.0139770433 -0.8251457214 3005 1311867270.6950180531 0.0636968240 0.0557365986 0.0791890547 0.0059531215 0.0421210000 416459593 0 402718720 -0.0085371733 -0.0150098763 -0.8230253458 3006 1311867270.7318449020 0.0665052608 0.0557401810 0.0791890547 0.0059533401 0.0417110000 416462973 0 402718720 -0.0103049241 -0.0141280703 -0.8192466497 3007 1311867270.7623898983 0.0656721443 0.0557434840 0.0791890547 0.0059524647 0.0419880000 416465809 0 402718720 -0.0091643408 -0.0150884092 -0.8166291118 3008 1311867270.7960500717 0.0629785433 0.0557458893 0.0791890547 0.0059527247 0.0417200000 416469141 0 402718720 -0.0074971206 -0.0175591558 -0.8168397546 3009 1311867270.8322730064 0.0641556010 0.0557486841 0.0791890547 0.0059555745 0.0421660000 416472401 0 402718720 -0.0078481734 -0.0170756616 -0.8145599365 3010 1311867270.8635489941 0.0655142292 0.0557519285 0.0791890547 0.0059563861 0.0523280000 416475677 0 402718720 -0.0077633411 -0.0162677467 -0.8112843037 3011 1311867270.8945889473 0.0634953082 0.0557545002 0.0791890547 0.0059565270 0.0422350000 416478705 0 402718720 -0.0088077784 -0.0198131204 -0.8099320531 3012 1311867270.9326179028 0.0657382607 0.0557578148 0.0791890547 0.0059585085 0.0417380000 416482085 0 402718720 -0.0091620386 -0.0194836371 -0.8049649000 3013 1311867270.9624550343 0.0669705942 0.0557615363 0.0791890547 0.0059616122 0.0417960000 416485113 0 402718720 -0.0073104128 -0.0174369179 -0.8039937615 3014 1311867270.9944560528 0.0671036914 0.0557652995 0.0791890547 0.0059610983 0.0420690000 416488229 0 402718720 -0.0064837448 -0.0187949184 -0.7999827862 3015 1311867271.0306649208 0.0639778301 0.0557680233 0.0791890547 0.0059604782 0.0422040000 416491369 0 402718720 -0.0075472556 -0.0239336491 -0.7988976240 3016 1311867271.0623910427 0.0655985996 0.0557712828 0.0791890547 0.0059604659 0.0532520000 416494501 0 402718720 -0.0053652227 -0.0223017354 -0.7973822951 3017 1311867271.0983459949 0.0621000603 0.0557733805 0.0791890547 0.0059654592 0.0421360000 416497969 0 402718720 -0.0038772225 -0.0264407247 -0.7975061536 3018 1311867271.1322019100 0.0630655587 0.0557757968 0.0791890547 0.0059648776 0.0417560000 416501181 0 402718720 -0.0033719055 -0.0270008817 -0.7941408157 3019 1311867271.1643741131 0.0638364702 0.0557784667 0.0791890547 0.0059648628 0.0421530000 416504297 0 402718720 -0.0021674111 -0.0270411987 -0.7919656038 3020 1311867271.1988029480 0.0623769276 0.0557806517 0.0791890547 0.0059640404 0.0427000000 416507557 0 402718720 -0.0017023198 -0.0293367077 -0.7912643552 3021 1311867271.2320818901 0.0618686639 0.0557826669 0.0791890547 0.0059641858 0.0420300000 416510393 0 402718720 -0.0011995584 -0.0310645346 -0.7886332273 3022 1311867271.2645740509 0.0638073459 0.0557853223 0.0791890547 0.0059673987 0.0424670000 416513637 0 402718720 0.0013993792 -0.0291328020 -0.7854321599 3023 1311867271.2998549938 0.0635895059 0.0557879039 0.0791890547 0.0059689019 0.0418610000 416516897 0 402718720 0.0000318624 -0.0309870299 -0.7831307054 3024 1311867271.3354289532 0.0632556453 0.0557903734 0.0791890547 0.0059713362 0.0431140000 416520165 0 402718720 -0.0014536791 -0.0335767083 -0.7803788185 3025 1311867271.3673670292 0.0637804642 0.0557930148 0.0791890547 0.0059704557 0.0531690000 416523433 0 402718720 -0.0010809377 -0.0341193080 -0.7776936293 3026 1311867271.3988809586 0.0629585162 0.0557953827 0.0791890547 0.0059703869 0.0425160000 416526453 0 402718720 0.0004470870 -0.0359834433 -0.7740708590 3027 1311867271.4355340004 0.0628810450 0.0557977236 0.0791890547 0.0059697975 0.0417990000 416529841 0 402718720 0.0000336096 -0.0380436070 -0.7715213299 3028 1311867271.4657170773 0.0614189655 0.0557995800 0.0791890547 0.0059736058 0.0506010000 416533037 0 402718720 0.0000468604 -0.0408702940 -0.7694591880 3029 1311867271.4997088909 0.0612402186 0.0558013762 0.0791890547 0.0059760657 0.0422170000 416536361 0 402718720 0.0029414669 -0.0409702547 -0.7678936124 3030 1311867271.5323960781 0.0617828555 0.0558033502 0.0791890547 0.0059757056 0.0424310000 416539381 0 402718720 0.0026257075 -0.0419654436 -0.7647455335 3031 1311867271.5676190853 0.0629447401 0.0558057064 0.0791890547 0.0059761166 0.0418730000 416542585 0 402718720 0.0008719675 -0.0446672849 -0.7575997114 3032 1311867271.5991230011 0.0629755706 0.0558080711 0.0791890547 0.0059752435 0.0426100000 416545861 0 402718720 0.0011095069 -0.0444710553 -0.7575503588 3033 1311867271.6349890232 0.0620303340 0.0558101226 0.0791890547 0.0059747966 0.0423940000 416549113 0 402718720 0.0026169233 -0.0463668890 -0.7532952428 3034 1311867271.6658320427 0.0613160022 0.0558119373 0.0791890547 0.0059743325 0.0430000000 416552261 0 402718720 0.0039709993 -0.0475407243 -0.7497387528 3035 1311867271.7005228996 0.0617714338 0.0558139009 0.0791890547 0.0059764785 0.0433600000 416555417 0 402718720 0.0033019036 -0.0481169038 -0.7460886836 3036 1311867271.7349541187 0.0626661032 0.0558161579 0.0791890547 0.0059764331 0.0433350000 416558549 0 402718720 0.0014355257 -0.0489586443 -0.7409330606 3037 1311867271.7661850452 0.0620283149 0.0558182034 0.0791890547 0.0059765625 0.0421100000 416561881 0 402718720 0.0006872416 -0.0515010841 -0.7341171503 3038 1311867271.7994530201 0.0609070063 0.0558198785 0.0791890547 0.0059783847 0.0423260000 416564949 0 402718720 0.0004034378 -0.0531307682 -0.7322865725 3039 1311867271.8341000080 0.0629193932 0.0558222146 0.0791890547 0.0059777914 0.0421370000 416568177 0 402718720 -0.0026787408 -0.0542941317 -0.7236833572 3040 1311867271.8629150391 0.0582685471 0.0558230193 0.0791890547 0.0059803735 0.0533110000 416571285 0 402718720 -0.0005105995 -0.0592332408 -0.7216046453 3041 1311867271.9009630680 0.0578238443 0.0558236773 0.0791890547 0.0059796435 0.0425450000 416574425 0 402718720 -0.0012376681 -0.0608475879 -0.7174848914 3042 1311867271.9304800034 0.0581465773 0.0558244409 0.0791890547 0.0059796075 0.0429620000 416577645 0 402718720 0.0017290898 -0.0602104515 -0.7132115960 3043 1311867271.9669768810 0.0600601994 0.0558258328 0.0791890547 0.0059799586 0.0425640000 416580913 0 402718720 -0.0010452829 -0.0606816672 -0.7064032555 3044 1311867271.9994390011 0.0599579178 0.0558271903 0.0791890547 0.0059793571 0.0551000000 416584205 0 402718720 -0.0026682280 -0.0627015233 -0.6999048591 3045 1311867272.0337600708 0.0618139394 0.0558291564 0.0791890547 0.0059792629 0.0423050000 416587025 0 402718720 -0.0018980950 -0.0609118491 -0.6944688559 3046 1311867272.0626399517 0.0578209423 0.0558298103 0.0791890547 0.0059808877 0.0543270000 416590245 0 402718720 0.0015936457 -0.0645469278 -0.6925228238 3047 1311867272.0988030434 0.0579397865 0.0558305028 0.0791890547 0.0059808234 0.0430130000 416593617 0 402718720 0.0031292811 -0.0661220029 -0.6854035258 3048 1311867272.1336209774 0.0588794723 0.0558315031 0.0791890547 0.0059802921 0.0554190000 416597005 0 402718720 0.0011886805 -0.0679784864 -0.6798970699 3049 1311867272.1659350395 0.0578853749 0.0558321767 0.0791890547 0.0059822036 0.0431080000 416600089 0 402718720 0.0022083484 -0.0701370910 -0.6766575575 3050 1311867272.1987910271 0.0582493097 0.0558329692 0.0791890547 0.0059825271 0.0430870000 416603293 0 402718720 0.0022631586 -0.0725153834 -0.6704452634 3051 1311867272.2319760323 0.0553305671 0.0558328045 0.0791890547 0.0059832932 0.0432930000 416606441 0 402718720 0.0029599629 -0.0766400173 -0.6687034369 3052 1311867272.2655110359 0.0563761853 0.0558329826 0.0791890547 0.0059865359 0.0433590000 416609517 0 402718720 0.0051222965 -0.0760932043 -0.6656039357 3053 1311867272.2982270718 0.0592252687 0.0558340937 0.0791890547 0.0059861232 0.0428360000 416612529 0 402718720 0.0031599179 -0.0756701976 -0.6612496972 3054 1311867272.3315019608 0.0570133254 0.0558344798 0.0791890547 0.0059892899 0.0532310000 416616077 0 402718720 0.0059695765 -0.0793218166 -0.6563042402 3055 1311867272.3696749210 0.0586390570 0.0558353979 0.0791890547 0.0059904198 0.0434650000 416619329 0 402718720 0.0067712404 -0.0787689835 -0.6529033780 3056 1311867272.3987050056 0.0582055077 0.0558361734 0.0791890547 0.0059896700 0.0436200000 416622301 0 402718720 0.0053376928 -0.0809497163 -0.6505747437 3057 1311867272.4335730076 0.0603866987 0.0558376620 0.0791890547 0.0059897018 0.0431290000 416625753 0 402718720 0.0040875189 -0.0814250708 -0.6440812945 3058 1311867272.4686141014 0.0582708865 0.0558384577 0.0791890547 0.0059899085 0.0551610000 416629085 0 402718720 0.0072789900 -0.0826417208 -0.6433631778 3059 1311867272.5011420250 0.0579356588 0.0558391433 0.0791890547 0.0059889472 0.0429970000 416631849 0 402718720 0.0057201423 -0.0841019824 -0.6415152550 3060 1311867272.5325479507 0.0577222109 0.0558397586 0.0791890547 0.0059880208 0.0430140000 416635205 0 402718720 0.0062977672 -0.0851702690 -0.6382761002 3061 1311867272.5676600933 0.0568553843 0.0558400904 0.0791890547 0.0059873636 0.0531920000 416638281 0 402718720 0.0070403405 -0.0861566067 -0.6364760399 3062 1311867272.5996229649 0.0570352376 0.0558404807 0.0791890547 0.0059865460 0.0434470000 416641693 0 402718720 0.0071101226 -0.0871107653 -0.6324329376 3063 1311867272.6315360069 0.0571498945 0.0558409082 0.0791890547 0.0059856599 0.0435510000 416644657 0 402718720 0.0070125461 -0.0878989846 -0.6292431355 3064 1311867272.6661291122 0.0567047596 0.0558411902 0.0791890547 0.0059848017 0.0430900000 416647925 0 402718720 0.0101248920 -0.0870728418 -0.6274735332 3065 1311867272.6987280846 0.0577933453 0.0558418271 0.0791890547 0.0059842059 0.0432060000 416650953 0 402718720 0.0100926831 -0.0860815942 -0.6245282888 3066 1311867272.7307109833 0.0560369007 0.0558418907 0.0791890547 0.0059836680 0.0427150000 416654101 0 402718720 0.0087892599 -0.0887767524 -0.6218817234 3067 1311867272.7686150074 0.0545112155 0.0558414568 0.0791890547 0.0059884331 0.0434730000 416657425 0 402718720 0.0119719207 -0.0895945057 -0.6197921634 3068 1311867272.7996079922 0.0557014495 0.0558414112 0.0791890547 0.0059879091 0.0564900000 416660389 0 402718720 0.0120139979 -0.0896412581 -0.6160658598 3069 1311867272.8310160637 0.0560351722 0.0558414743 0.0791890547 0.0059876937 0.0432940000 416663617 0 402718720 0.0139435567 -0.0891320407 -0.6128139496 3070 1311867272.8674850464 0.0565615334 0.0558417089 0.0791890547 0.0059871489 0.0520530000 416667013 0 402718720 0.0136069022 -0.0895754024 -0.6101350188 3071 1311867272.8996291161 0.0552712455 0.0558415231 0.0791890547 0.0059865205 0.0440480000 416670169 0 402718720 0.0164053291 -0.0897176117 -0.6095315814 3072 1311867272.9314110279 0.0542427227 0.0558410027 0.0791890547 0.0059865231 0.0433760000 416673317 0 402718720 0.0190088861 -0.0913334787 -0.6068620682 3073 1311867272.9664669037 0.0551331639 0.0558407724 0.0791890547 0.0059855846 0.0436270000 416676833 0 402718720 0.0194881521 -0.0916995853 -0.6031233668 3074 1311867272.9987599850 0.0559679456 0.0558408137 0.0791890547 0.0059848871 0.0437000000 416679469 0 402718720 0.0213359259 -0.0902552381 -0.6022813916 3075 1311867273.0328490734 0.0554870181 0.0558406987 0.0791890547 0.0059839374 0.0438790000 416682985 0 402718720 0.0233391635 -0.0910341963 -0.6003302932 3076 1311867273.0662739277 0.0549312308 0.0558404030 0.0791890547 0.0059832146 0.0546090000 416685941 0 402718720 0.0241244137 -0.0920274779 -0.5993875861 3077 1311867273.0999150276 0.0557496138 0.0558403735 0.0791890547 0.0059823572 0.0434840000 416689281 0 402718720 0.0275073126 -0.0905408785 -0.5977510214 3078 1311867273.1310710907 0.0573521480 0.0558408647 0.0791890547 0.0059820239 0.0556220000 416692365 0 402718720 0.0275085345 -0.0891674459 -0.5960029960 3079 1311867273.1665740013 0.0568439141 0.0558411904 0.0791890547 0.0059812769 0.0428620000 416695625 0 402718720 0.0283512250 -0.0893579274 -0.5951892138 3080 1311867273.1997520924 0.0560274236 0.0558412509 0.0791890547 0.0059803792 0.0431100000 416699029 0 402718720 0.0294774435 -0.0899727270 -0.5944896340 3081 1311867273.2331819534 0.0551133752 0.0558410146 0.0791890547 0.0059803710 0.0428060000 416701985 0 402718720 0.0311223790 -0.0910777375 -0.5927806497 3082 1311867273.2668380737 0.0537609942 0.0558403397 0.0791890547 0.0059805257 0.0520040000 416705197 0 402718720 0.0305575617 -0.0932870880 -0.5916860104 3083 1311867273.2985589504 0.0536966920 0.0558396444 0.0791890547 0.0059796235 0.0435280000 416708465 0 402718720 0.0319496803 -0.0923181102 -0.5909957290 3084 1311867273.3308010101 0.0558693893 0.0558396541 0.0791890547 0.0059800363 0.0433610000 416711573 0 402718720 0.0327229351 -0.0902938843 -0.5875834227 3085 1311867273.3663508892 0.0529640839 0.0558387220 0.0791890547 0.0059794212 0.0429450000 416714769 0 402718720 0.0345417000 -0.0926941559 -0.5857772231 3086 1311867273.3992459774 0.0530291274 0.0558378115 0.0791890547 0.0059791530 0.0432030000 416717661 0 402718720 0.0354241282 -0.0927702338 -0.5827136636 3087 1311867273.4308409691 0.0538263693 0.0558371600 0.0791890547 0.0059782496 0.0431340000 416721441 0 402718720 0.0363782346 -0.0904687196 -0.5814739466 3088 1311867273.4663250446 0.0530197062 0.0558362476 0.0791890547 0.0059787715 0.0546130000 416724341 0 402718720 0.0383198783 -0.0915412083 -0.5772355795 3089 1311867273.4997849464 0.0530854724 0.0558353571 0.0791890547 0.0059785252 0.0431340000 416727553 0 402718720 0.0383156575 -0.0910805911 -0.5749372244 3090 1311867273.5318419933 0.0538273863 0.0558347072 0.0791890547 0.0059796474 0.0429550000 416730821 0 402718720 0.0399607494 -0.0898363292 -0.5698619485 3091 1311867273.5687909126 0.0536862314 0.0558340122 0.0791890547 0.0059793940 0.0435050000 416733753 0 402718720 0.0400921702 -0.0892339796 -0.5678255558 3092 1311867273.6000390053 0.0524829887 0.0558329284 0.0791890547 0.0059786863 0.0433020000 416737061 0 402718720 0.0409227908 -0.0918753147 -0.5621464849 3093 1311867273.6349599361 0.0514258929 0.0558315035 0.0791890547 0.0059781366 0.0433900000 416740209 0 402718720 0.0412874408 -0.0936523080 -0.5583437681 3094 1311867273.6673769951 0.0536223575 0.0558307895 0.0791890547 0.0059774960 0.0547950000 416743413 0 402718720 0.0408636928 -0.0925642252 -0.5532960892 3095 1311867273.6987860203 0.0532331727 0.0558299502 0.0791890547 0.0059774483 0.0432870000 416746761 0 402718720 0.0434655547 -0.0930259526 -0.5489042401 3096 1311867273.7346739769 0.0541899763 0.0558294205 0.0791890547 0.0059777084 0.0431760000 416750149 0 402718720 0.0420297645 -0.0924191028 -0.5448355079 3097 1311867273.7665960789 0.0543840192 0.0558289538 0.0791890547 0.0059790831 0.0560600000 416753185 0 402718720 0.0456479415 -0.0908711404 -0.5429822206 3098 1311867273.7990698814 0.0526337735 0.0558279224 0.0791890547 0.0059787597 0.0435190000 416756533 0 402718720 0.0458528213 -0.0931638852 -0.5401321650 3099 1311867273.8358130455 0.0524815656 0.0558268426 0.0791890547 0.0059788873 0.0581240000 416759537 0 402718720 0.0457090512 -0.0945500135 -0.5353633761 3100 1311867273.8668060303 0.0527738854 0.0558258578 0.0791890547 0.0059799311 0.0438510000 416762781 0 402718720 0.0451350361 -0.0952305049 -0.5316621065 3101 1311867273.8990719318 0.0523719713 0.0558247440 0.0791890547 0.0059826469 0.0435590000 416765793 0 402718720 0.0472342260 -0.0962359160 -0.5276108384 3102 1311867273.9384820461 0.0531245396 0.0558238735 0.0791890547 0.0059818313 0.0438010000 416769301 0 402718720 0.0452772081 -0.0960193202 -0.5250051022 3103 1311867273.9669051170 0.0537471138 0.0558232043 0.0791890547 0.0059815096 0.0444580000 416772593 0 402718720 0.0443227328 -0.0956090093 -0.5216990709 3104 1311867273.9996581078 0.0526584759 0.0558221847 0.0791890547 0.0059805700 0.0440650000 416775365 0 402718720 0.0419620126 -0.0985679403 -0.5177512765 3105 1311867274.0348489285 0.0524180382 0.0558210884 0.0791890547 0.0059797148 0.0562040000 416778785 0 402718720 0.0411022305 -0.0975799337 -0.5160415173 3106 1311867274.0670020580 0.0540402085 0.0558205150 0.0791890547 0.0059803127 0.0442060000 416781733 0 402718720 0.0397285074 -0.0960120857 -0.5117732286 3107 1311867274.1025679111 0.0515159480 0.0558191295 0.0791890547 0.0059803342 0.0440580000 416785249 0 402718720 0.0387318693 -0.0992100164 -0.5079797506 3108 1311867274.1350569725 0.0528825186 0.0558181847 0.0791890547 0.0059794378 0.0445290000 416788389 0 402718720 0.0369392633 -0.0987131894 -0.5024261475 3109 1311867274.1667969227 0.0519349240 0.0558169356 0.0791890547 0.0059795092 0.0443410000 416791497 0 402718720 0.0358148888 -0.0996039584 -0.4996713996 3110 1311867274.2008550167 0.0500879958 0.0558150935 0.0791890547 0.0059841896 0.0436620000 416794597 0 402718720 0.0346638039 -0.1018754393 -0.4956297576 3111 1311867274.2389180660 0.0487754568 0.0558128307 0.0791890547 0.0059844005 0.0546110000 416798033 0 402718720 0.0337688774 -0.1040080413 -0.4911430776 3112 1311867274.2668540478 0.0502338111 0.0558110380 0.0791890547 0.0059837221 0.0443770000 416801261 0 402718720 0.0327921882 -0.1030945405 -0.4865919054 3113 1311867274.3018939495 0.0498313271 0.0558091171 0.0791890547 0.0059843221 0.0446300000 416804353 0 402718720 0.0315485820 -0.1035765931 -0.4832673669 3114 1311867274.3358139992 0.0494525693 0.0558070758 0.0791890547 0.0059844381 0.0442020000 416807685 0 402718720 0.0281032100 -0.1065218374 -0.4773433805 3115 1311867274.3679759502 0.0501913428 0.0558052730 0.0791890547 0.0059835611 0.0549920000 416810505 0 402718720 0.0274494849 -0.1066973582 -0.4722932577 3116 1311867274.4007549286 0.0519637838 0.0558040402 0.0791890547 0.0059831143 0.0452020000 416813853 0 402718720 0.0273905396 -0.1062560678 -0.4661456347 3117 1311867274.4357678890 0.0508071221 0.0558024371 0.0791890547 0.0059844163 0.0557530000 416816857 0 402718720 0.0240828265 -0.1088301092 -0.4642366171 3118 1311867274.4689209461 0.0501570068 0.0558006265 0.0791890547 0.0059872295 0.0546490000 416820509 0 402718720 0.0249111727 -0.1100141779 -0.4601757526 3119 1311867274.4997699261 0.0495082252 0.0557986090 0.0791890547 0.0059866372 0.0435880000 416823161 0 402718720 0.0249978509 -0.1117921919 -0.4567132592 3120 1311867274.5345981121 0.0505514890 0.0557969273 0.0791890547 0.0059868795 0.0434900000 416826573 0 402718720 0.0220946912 -0.1130917892 -0.4523736537 3121 1311867274.5686841011 0.0492261536 0.0557948219 0.0791890547 0.0059865944 0.0437810000 416829865 0 402718720 0.0215795543 -0.1160849705 -0.4486571550 3122 1311867274.6001191139 0.0496314876 0.0557928478 0.0791890547 0.0059863668 0.0438890000 416832773 0 402718720 0.0216810424 -0.1157536581 -0.4467665553 3123 1311867274.6349270344 0.0504287183 0.0557911301 0.0791890547 0.0059861857 0.0441030000 416836097 0 402718720 0.0204560757 -0.1167953387 -0.4419250786 3124 1311867274.6665649414 0.0497520976 0.0557891970 0.0791890547 0.0059878413 0.0441640000 416839397 0 402718720 0.0199546274 -0.1189812869 -0.4383029640 3125 1311867274.6988699436 0.0510742404 0.0557876882 0.0791890547 0.0059871821 0.0445310000 416842489 0 402718720 0.0194135178 -0.1178724617 -0.4351386726 3126 1311867274.7355759144 0.0507471524 0.0557860758 0.0791890547 0.0059906639 0.0439710000 416845821 0 402718720 0.0184859019 -0.1179512814 -0.4333818257 3127 1311867274.7669000626 0.0495452061 0.0557840800 0.0791890547 0.0059900152 0.0440240000 416848969 0 402718720 0.0180354714 -0.1209002957 -0.4287192822 3128 1311867274.8040020466 0.0511676483 0.0557826041 0.0791890547 0.0059901295 0.0440770000 416852109 0 402718720 0.0183482897 -0.1193268299 -0.4242649972 3129 1311867274.8350889683 0.0491578802 0.0557804869 0.0791890547 0.0059898987 0.0448470000 416855321 0 402718720 0.0172011871 -0.1219220757 -0.4221003354 3130 1311867274.8671360016 0.0502392016 0.0557787166 0.0791890547 0.0059893049 0.0447820000 416858533 0 402718720 0.0164678153 -0.1217250377 -0.4170397520 3131 1311867274.9044289589 0.0503066406 0.0557769689 0.0791890547 0.0059884864 0.0443900000 416861633 0 402718720 0.0135698915 -0.1224259436 -0.4136829376 3132 1311867274.9350550175 0.0510240570 0.0557754513 0.0791890547 0.0059882308 0.0439630000 416864861 0 402718720 0.0129845962 -0.1215038225 -0.4098615646 3133 1311867274.9666490555 0.0524340011 0.0557743848 0.0791890547 0.0059874162 0.0447160000 416867889 0 402718720 0.0125546940 -0.1209570915 -0.4048063755 3134 1311867275.0030829906 0.0493624583 0.0557723389 0.0791890547 0.0059900199 0.0443940000 416871205 0 402718720 0.0135089178 -0.1242576987 -0.4010656178 3135 1311867275.0368080139 0.0524339378 0.0557712740 0.0791890547 0.0059971351 0.0445880000 416874737 0 402718720 0.0097221192 -0.1221533343 -0.3962437809 3136 1311867275.0664451122 0.0519908741 0.0557700685 0.0791890547 0.0059981634 0.0445380000 416877509 0 402718720 0.0093667116 -0.1227183789 -0.3932836354 3137 1311867275.1023271084 0.0516562350 0.0557687571 0.0791890547 0.0059975852 0.0452480000 416880897 0 402718720 0.0092584528 -0.1239685193 -0.3891192079 3138 1311867275.1351230145 0.0512051582 0.0557673028 0.0791890547 0.0059968601 0.0443440000 416884173 0 402718720 0.0088197999 -0.1268928498 -0.3831624091 3139 1311867275.1667180061 0.0523414239 0.0557662114 0.0791890547 0.0059959980 0.0447970000 416886937 0 402718720 0.0061319508 -0.1267475337 -0.3796180487 3140 1311867275.2041749954 0.0532703176 0.0557654165 0.0791890547 0.0059959864 0.0436220000 416890317 0 402718720 0.0065657273 -0.1256218106 -0.3755042553 3141 1311867275.2371780872 0.0513149463 0.0557639996 0.0791890547 0.0059952666 0.0817820000 416893729 0 402718720 0.0063871332 -0.1273606271 -0.3734686673 3142 1311867275.2668180466 0.0523232482 0.0557629046 0.0791890547 0.0059964191 0.0451870000 416896637 0 402718720 0.0059118867 -0.1271796823 -0.3689067662 3143 1311867275.3026800156 0.0519413203 0.0557616887 0.0791890547 0.0059986935 0.0439960000 416900025 0 402718720 0.0071025044 -0.1264142990 -0.3659941852 3144 1311867275.3351879120 0.0526155345 0.0557606880 0.0791890547 0.0059988912 0.0443160000 416903461 0 402718720 0.0040449686 -0.1266701818 -0.3615197837 3145 1311867275.3669109344 0.0523413643 0.0557596008 0.0791890547 0.0060000456 0.0447430000 416906193 0 402718720 0.0032214299 -0.1277357340 -0.3569336832 3146 1311867275.4038369656 0.0514809005 0.0557582407 0.0791890547 0.0059995004 0.0624910000 416909525 0 402718720 0.0021092333 -0.1274384856 -0.3548075855 3147 1311867275.4349598885 0.0531354062 0.0557574073 0.0791890547 0.0060027007 0.0452770000 416912689 0 402718720 0.0015788339 -0.1286975443 -0.3475303948 3148 1311867275.4669399261 0.0526672713 0.0557564256 0.0791890547 0.0060021998 0.0445250000 416915909 0 402718720 -0.0012742430 -0.1301591098 -0.3431108296 3149 1311867275.5037291050 0.0530807190 0.0557555759 0.0791890547 0.0060014979 0.0447520000 416919225 0 402718720 -0.0031245388 -0.1290776730 -0.3398456275 3150 1311867275.5353329182 0.0524497777 0.0557545265 0.0791890547 0.0060029378 0.0563010000 416922117 0 402718720 -0.0034112073 -0.1297562569 -0.3363855481 3151 1311867275.5668909550 0.0515923873 0.0557532056 0.0791890547 0.0060062447 0.0443650000 416925529 0 402718720 -0.0046646371 -0.1320385337 -0.3320687115 3152 1311867275.6028299332 0.0518402010 0.0557519642 0.0791890547 0.0060071990 0.0821430000 416928653 0 402718720 -0.0072670169 -0.1319503188 -0.3288378119 3153 1311867275.6383280754 0.0507261269 0.0557503702 0.0791890547 0.0060074033 0.0449650000 416932105 0 402718720 -0.0096200705 -0.1335195005 -0.3256544471 3154 1311867275.6682209969 0.0506916419 0.0557487663 0.0791890547 0.0060069654 0.0450320000 416934885 0 402718720 -0.0101259071 -0.1348027587 -0.3217178285 3155 1311867275.7045888901 0.0504829027 0.0557470972 0.0791890547 0.0060066005 0.0449540000 416937953 0 402718720 -0.0123859774 -0.1353193074 -0.3191457689 3156 1311867275.7349820137 0.0520056151 0.0557459117 0.0791890547 0.0060057310 0.0554680000 416940925 0 402718720 -0.0135546476 -0.1349690259 -0.3148715198 3157 1311867275.7792279720 0.0502409190 0.0557441680 0.0791890547 0.0060059529 0.0447960000 416944793 0 402718720 -0.0143153332 -0.1362879276 -0.3123358786 3158 1311867275.8028490543 0.0508841500 0.0557426290 0.0791890547 0.0060057229 0.0444150000 416947725 0 402718720 -0.0162300151 -0.1375044435 -0.3080054522 3159 1311867275.8355960846 0.0518813804 0.0557414067 0.0791890547 0.0060066918 0.0447050000 416950881 0 402718720 -0.0170439780 -0.1361218691 -0.3045826852 3160 1311867275.8701560497 0.0514624119 0.0557400526 0.0791890547 0.0060059174 0.0447550000 416954013 0 402718720 -0.0196583793 -0.1363406330 -0.3021440506 3161 1311867275.9032120705 0.0495757386 0.0557381025 0.0791890547 0.0060055467 0.0438900000 416957361 0 402718720 -0.0225204881 -0.1388691962 -0.2995156646 3162 1311867275.9371318817 0.0498578064 0.0557362428 0.0791890547 0.0060047821 0.0439880000 416960501 0 402718720 -0.0224345867 -0.1383872628 -0.2954053581 3163 1311867275.9683859348 0.0502016693 0.0557344930 0.0791890547 0.0060039457 0.0820700000 416963473 0 402718720 -0.0230804179 -0.1366646588 -0.2934774160 3164 1311867276.0048470497 0.0521983355 0.0557333754 0.0791890547 0.0060071838 0.0449830000 416966685 0 402718720 -0.0254341848 -0.1361091882 -0.2879121006 3165 1311867276.0387539864 0.0504826866 0.0557317164 0.0791890547 0.0060083793 0.0443030000 416970273 0 402718720 -0.0283813253 -0.1388545632 -0.2847695053 3166 1311867276.0739030838 0.0513730720 0.0557303397 0.0791890547 0.0060104013 0.0448140000 416973661 0 402718720 -0.0283108037 -0.1373866647 -0.2814224362 3167 1311867276.1051371098 0.0516834632 0.0557290619 0.0791890547 0.0060112993 0.0445870000 416976297 0 402718720 -0.0295819938 -0.1372484118 -0.2782317400 3168 1311867276.1382379532 0.0496887490 0.0557271552 0.0791890547 0.0060120598 0.0452480000 416979773 0 402718720 -0.0316887945 -0.1398001313 -0.2762778997 3169 1311867276.1709389687 0.0497255400 0.0557252614 0.0791890547 0.0060135083 0.0448860000 416982793 0 402718720 -0.0320668966 -0.1412230283 -0.2716179192 3170 1311867276.2042279243 0.0505871177 0.0557236405 0.0791890547 0.0060128453 0.0447420000 416986181 0 402718720 -0.0323930420 -0.1396493912 -0.2690179944 3171 1311867276.2357859612 0.0513245463 0.0557222532 0.0791890547 0.0060119778 0.0552360000 416989033 0 402718720 -0.0325563625 -0.1389382631 -0.2658107579 3172 1311867276.2747719288 0.0493204482 0.0557202350 0.0791890547 0.0060111997 0.0449760000 416992661 0 402718720 -0.0332754701 -0.1396957040 -0.2645492852 3173 1311867276.3027520180 0.0504998751 0.0557185897 0.0791890547 0.0060123823 0.0452890000 416995721 0 402718720 -0.0345556512 -0.1405786872 -0.2602077425 3174 1311867276.3387188911 0.0504984148 0.0557169451 0.0791890547 0.0060119189 0.0517120000 416998837 0 402718720 -0.0348738544 -0.1404317915 -0.2573128939 3175 1311867276.3729600906 0.0498973615 0.0557151121 0.0791890547 0.0060112324 0.0514710000 417002121 0 402718720 -0.0364510976 -0.1420779973 -0.2547410131 3176 1311867276.4031929970 0.0498919673 0.0557132786 0.0791890547 0.0060116938 0.0517850000 417005229 0 402718720 -0.0368479565 -0.1426167190 -0.2525618970 3177 1311867276.4360129833 0.0501224101 0.0557115188 0.0791890547 0.0060117144 0.0517290000 417008201 0 402718720 -0.0384804681 -0.1437033117 -0.2492523640 3178 1311867276.4737091064 0.0496300235 0.0557096052 0.0791890547 0.0060131616 0.0509970000 417011461 0 402718720 -0.0405586101 -0.1452511847 -0.2469499707 3179 1311867276.5048420429 0.0504039600 0.0557079363 0.0791890547 0.0060129107 0.0514200000 417014809 0 402718720 -0.0412189960 -0.1436470896 -0.2449087948 3180 1311867276.5387470722 0.0509403460 0.0557064370 0.0791890547 0.0060126522 0.0457660000 417018141 0 402718720 -0.0399112403 -0.1429912001 -0.2425307482 3181 1311867276.5746779442 0.0500510782 0.0557046592 0.0791890547 0.0060118392 0.0446360000 417021481 0 402718720 -0.0412004925 -0.1442303956 -0.2397707552 3182 1311867276.6041920185 0.0496680550 0.0557027620 0.0791890547 0.0060109421 0.0445930000 417024269 0 402718720 -0.0417266823 -0.1421248913 -0.2398931682 3183 1311867276.6361470222 0.0499525256 0.0557009555 0.0791890547 0.0060100320 0.0444560000 417027169 0 402718720 -0.0439872332 -0.1439586729 -0.2359675318 3184 1311867276.6710920334 0.0489560738 0.0556988371 0.0791890547 0.0060098358 0.0550160000 417030429 0 402718720 -0.0442337692 -0.1449329406 -0.2330911160 3185 1311867276.7029719353 0.0507353172 0.0556972787 0.0791890547 0.0060118533 0.0671720000 417033577 0 402718720 -0.0436024070 -0.1431673169 -0.2303914577 3186 1311867276.7360780239 0.0495809615 0.0556953590 0.0791890547 0.0060114327 0.0557540000 417036741 0 402718720 -0.0464349091 -0.1454471052 -0.2283002436 3187 1311867276.7721960545 0.0497500524 0.0556934935 0.0791890547 0.0060153386 0.0449680000 417040185 0 402718720 -0.0476496816 -0.1465515643 -0.2242712080 3188 1311867276.8029088974 0.0511553437 0.0556920700 0.0791890547 0.0060235871 0.0558040000 417638641 0 402718720 -0.0476892963 -0.1450740099 -0.2225397825 3189 1311867276.8375699520 0.0496227816 0.0556901668 0.0791890547 0.0060258217 0.1462260000 417644153 0 402718720 -0.0475759171 -0.1465543956 -0.2209664434 3190 1311867276.8740971088 0.0491403081 0.0556881135 0.0791890547 0.0060255765 0.1503590000 417646261 0 402718720 -0.0494297370 -0.1488743722 -0.2184011936 3191 1311867276.9029750824 0.0509721749 0.0556866357 0.0791890547 0.0060280103 0.1410920000 417962057 0 402718720 -0.0506865829 -0.1462579221 -0.2170730680 3192 1311867276.9374980927 0.0499905758 0.0556848512 0.0791890547 0.0060308423 0.1381030000 428372497 0 402718720 -0.0511208847 -0.1472605169 -0.2148428708 3193 1311867276.9726910591 0.0492654629 0.0556828407 0.0791890547 0.0060301739 0.0783330000 433141673 0 402718720 -0.0527068377 -0.1492331922 -0.2118657380 3194 1311867277.0050029755 0.0502247028 0.0556811318 0.0791890547 0.0060312222 0.1269060000 431870925 0 402718720 -0.0542916432 -0.1478092521 -0.2092907280 3195 1311867277.0356070995 0.0503130853 0.0556794517 0.0791890547 0.0060303560 0.0536190000 433119733 0 402718720 -0.0545156561 -0.1463579237 -0.2075693458 3196 1311867277.0711610317 0.0499732420 0.0556776663 0.0791890547 0.0060294589 0.1728510000 431112237 0 402718720 -0.0550458245 -0.1463576257 -0.2049363554 3197 1311867277.1039769650 0.0490360595 0.0556755888 0.0791890547 0.0060296791 0.1114650000 417614529 0 402718720 -0.0553780273 -0.1481454819 -0.2013782114 3198 1311867277.1350269318 0.0491963290 0.0556735628 0.0791890547 0.0060312571 0.0479780000 417617565 0 402718720 -0.0554048605 -0.1473312676 -0.1986515522 3199 1311867277.1708490849 0.0485248938 0.0556713281 0.0791890547 0.0060317834 0.0478100000 417620697 0 402718720 -0.0552597046 -0.1459862441 -0.1958560795 3200 1311867277.2029759884 0.0490889251 0.0556692711 0.0791890547 0.0060311212 0.0471610000 417623741 0 402718720 -0.0558969341 -0.1455106884 -0.1920602173 3201 1311867277.2351000309 0.0480285324 0.0556668842 0.0791890547 0.0060305128 0.0474690000 417627209 0 402718720 -0.0582870990 -0.1482729167 -0.1884566993 3202 1311867277.2733149529 0.0482567064 0.0556645699 0.0791890547 0.0060299739 0.0670970000 417630517 0 402718720 -0.0578906238 -0.1473297477 -0.1847418100 3203 1311867277.3063778877 0.0469415523 0.0556618465 0.0791890547 0.0060291850 0.0464470000 417633793 0 402718720 -0.0573461764 -0.1476241052 -0.1824172139 3204 1311867277.3396029472 0.0474580415 0.0556592860 0.0791890547 0.0060286045 0.0468300000 417636837 0 402718720 -0.0570679866 -0.1469706446 -0.1787017584 3205 1311867277.3773889542 0.0473376103 0.0556566896 0.0791890547 0.0060284692 0.0491430000 417640305 0 402718720 -0.0586802736 -0.1463377178 -0.1763674319 3206 1311867277.4055531025 0.0466223098 0.0556538716 0.0791890547 0.0060277313 0.0471080000 417643029 0 402718720 -0.0583599731 -0.1490232646 -0.1725630313 3207 1311867277.4425079823 0.0484609008 0.0556516287 0.0791890547 0.0060288980 0.0602040000 417646625 0 402718720 -0.0596648082 -0.1487235874 -0.1669704765 3208 1311867277.4723749161 0.0493129492 0.0556496528 0.0791890547 0.0060370409 0.0499710000 417649669 0 402718720 -0.0610398091 -0.1465719044 -0.1660876423 3209 1311867277.5057780743 0.0491587408 0.0556476301 0.0791890547 0.0060395081 0.0611510000 417652697 0 402718720 -0.0604318157 -0.1467329264 -0.1623233557 3210 1311867277.5401940346 0.0482847020 0.0556453364 0.0791890547 0.0060462163 0.0494870000 417655637 0 402718720 -0.0628185198 -0.1500081122 -0.1583429724 3211 1311867277.5715351105 0.0481284857 0.0556429954 0.0791890547 0.0060496686 0.0477430000 417658737 0 402718720 -0.0618535541 -0.1490564644 -0.1573169380 3212 1311867277.6027710438 0.0484350696 0.0556407513 0.0791890547 0.0060488735 0.0475110000 417661957 0 402718720 -0.0605534948 -0.1486244053 -0.1554526240 3213 1311867277.6416130066 0.0484884493 0.0556385253 0.0791890547 0.0060498847 0.0476280000 417665209 0 402718720 -0.0613918304 -0.1506851465 -0.1517982632 3214 1311867277.6713008881 0.0478563048 0.0556361039 0.0791890547 0.0060490781 0.0488200000 417668629 0 402718720 -0.0630035847 -0.1532348841 -0.1497337520 3215 1311867277.7063589096 0.0474496819 0.0556335576 0.0791890547 0.0060494479 0.0583080000 417671969 0 402718720 -0.0604553670 -0.1507419199 -0.1489079297 3216 1311867277.7401409149 0.0479216427 0.0556311596 0.0791890547 0.0060487085 0.0471090000 417675125 0 402718720 -0.0596161857 -0.1488824189 -0.1462956220 3217 1311867277.7720079422 0.0478702448 0.0556287471 0.0791890547 0.0060477781 0.0486500000 417678097 0 402718720 -0.0610184968 -0.1497680694 -0.1430337727 3218 1311867277.8036880493 0.0470678210 0.0556260868 0.0791890547 0.0060472431 0.0479320000 417681245 0 402718720 -0.0599596724 -0.1496181786 -0.1404137909 3219 1311867277.8400499821 0.0476228707 0.0556236006 0.0791890547 0.0060463951 0.0473100000 417684361 0 402718720 -0.0577725843 -0.1483897865 -0.1368917227 3220 1311867277.8711171150 0.0468973257 0.0556208906 0.0791890547 0.0060468437 0.0573580000 417687445 0 402718720 -0.0596713573 -0.1521293521 -0.1318114102 3221 1311867277.9031610489 0.0474510305 0.0556183541 0.0791890547 0.0060459682 0.0477630000 417690849 0 402718720 -0.0599573217 -0.1527820230 -0.1278282404 3222 1311867277.9393019676 0.0469211191 0.0556156548 0.0791890547 0.0060460198 0.0469390000 417694045 0 402718720 -0.0592178106 -0.1513795704 -0.1254475564 3223 1311867277.9714229107 0.0486423858 0.0556134912 0.0791890547 0.0060466797 0.0476220000 417697449 0 402718720 -0.0575854070 -0.1506311297 -0.1202928424 3224 1311867278.0041360855 0.0476579741 0.0556110236 0.0791890547 0.0060458801 0.0463240000 417700453 0 402718720 -0.0584729016 -0.1529838443 -0.1172180250 3225 1311867278.0394210815 0.0469317771 0.0556083324 0.0791890547 0.0060465573 0.0577620000 417703753 0 402718720 -0.0560076274 -0.1536627412 -0.1140235141 3226 1311867278.0712630749 0.0474971719 0.0556058181 0.0791890547 0.0060459246 0.0573750000 417706901 0 402718720 -0.0555550531 -0.1537990421 -0.1102393344 3227 1311867278.1056289673 0.0484310277 0.0556035947 0.0791890547 0.0060450519 0.0465260000 417710001 0 402718720 -0.0545904264 -0.1525021195 -0.1065036207 3228 1311867278.1391980648 0.0480752438 0.0556012625 0.0791890547 0.0060442779 0.0460500000 417713213 0 402718720 -0.0546980612 -0.1550814360 -0.1019156948 3229 1311867278.1710369587 0.0492602885 0.0555992987 0.0791890547 0.0060434827 0.0503440000 417716425 0 402718720 -0.0536807664 -0.1538875550 -0.0973936468 3230 1311867278.2038609982 0.0490049385 0.0555972571 0.0791890547 0.0060447349 0.0529850000 417719821 0 402718720 -0.0527578220 -0.1530993581 -0.0945591927 3231 1311867278.2388060093 0.0489074066 0.0555951866 0.0791890547 0.0060502367 0.0532660000 417722825 0 402718720 -0.0527705066 -0.1535838693 -0.0905605257 3232 1311867278.2707629204 0.0491433926 0.0555931904 0.0791890547 0.0060513010 0.0535960000 417725997 0 402718720 -0.0529699251 -0.1547742933 -0.0867039561 3233 1311867278.3027629852 0.0490881056 0.0555911783 0.0791890547 0.0060506083 0.0532830000 417729145 0 402718720 -0.0513788536 -0.1523386985 -0.0849132389 3234 1311867278.3421599865 0.0492607020 0.0555892208 0.0791890547 0.0060502824 0.0527450000 417732773 0 402718720 -0.0506189540 -0.1525161862 -0.0805928856 3235 1311867278.3714361191 0.0493059941 0.0555872786 0.0791890547 0.0060493933 0.0513480000 417735361 0 402718720 -0.0516738333 -0.1549016684 -0.0766109601 3236 1311867278.4035348892 0.0499881245 0.0555855483 0.0791890547 0.0060486090 0.0525300000 417738933 0 402718720 -0.0522826463 -0.1541346014 -0.0738266259 3237 1311867278.4391169548 0.0492954850 0.0555836051 0.0791890547 0.0060478349 0.0498250000 417742217 0 402718720 -0.0506010354 -0.1525765061 -0.0718847960 3238 1311867278.4713339806 0.0496352725 0.0555817681 0.0791890547 0.0060473848 0.0459710000 417745165 0 402718720 -0.0511042476 -0.1543716341 -0.0677756816 3239 1311867278.5041239262 0.0488771759 0.0555796981 0.0791890547 0.0060474120 0.0453930000 417748377 0 402718720 -0.0518228076 -0.1575212181 -0.0642654076 3240 1311867278.5423910618 0.0478128009 0.0555773009 0.0791890547 0.0060470008 0.0452410000 417751789 0 402718720 -0.0522303320 -0.1574585438 -0.0624130331 3241 1311867278.5710260868 0.0483090803 0.0555750583 0.0791890547 0.0060472832 0.0582270000 417754665 0 402718720 -0.0491043963 -0.1555806249 -0.0596085191 3242 1311867278.6069030762 0.0480232276 0.0555727290 0.0791890547 0.0060475115 0.0449370000 417757989 0 402718720 -0.0490265563 -0.1558250785 -0.0565867350 3243 1311867278.6393239498 0.0483007617 0.0555704866 0.0791890547 0.0060469526 0.0449120000 417761009 0 402718720 -0.0498430617 -0.1569126099 -0.0527936816 3244 1311867278.6709709167 0.0490495265 0.0555684765 0.0791890547 0.0060497820 0.0575240000 417764293 0 402718720 -0.0486190654 -0.1549141854 -0.0496738255 3245 1311867278.7069129944 0.0500983745 0.0555667908 0.0791890547 0.0060489455 0.0455840000 417767561 0 402718720 -0.0463711061 -0.1523759514 -0.0465744026 3246 1311867278.7390680313 0.0499934182 0.0555650738 0.0791890547 0.0060498509 0.0462610000 417770645 0 402718720 -0.0476364233 -0.1554761082 -0.0418273918 3247 1311867278.7718300819 0.0494448729 0.0555631889 0.0791890547 0.0060496576 0.0458130000 417773953 0 402718720 -0.0477119610 -0.1579120755 -0.0384865627 3248 1311867278.8068239689 0.0497385338 0.0555613956 0.0791890547 0.0060490466 0.0455950000 417777245 0 402718720 -0.0457355678 -0.1544772238 -0.0369272158 3249 1311867278.8386530876 0.0496277995 0.0555595693 0.0791890547 0.0060491104 0.0455510000 417780321 0 402718720 -0.0435534865 -0.1541698277 -0.0344122835 3250 1311867278.8741700649 0.0493806563 0.0555576681 0.0791890547 0.0060490088 0.0813370000 417783541 0 402718720 -0.0454404242 -0.1579307765 -0.0296142399 3251 1311867278.9090650082 0.0486271568 0.0555555363 0.0791890547 0.0060487176 0.0452990000 417786809 0 402718720 -0.0448902361 -0.1572982967 -0.0276992917 3252 1311867278.9392769337 0.0491801463 0.0555535758 0.0791890547 0.0060494546 0.0450390000 417789829 0 402718720 -0.0416046903 -0.1526241750 -0.0267219655 3253 1311867278.9711430073 0.0496507883 0.0555517613 0.0791890547 0.0060486974 0.0452620000 417792977 0 402718720 -0.0444210358 -0.1549196243 -0.0218921769 3254 1311867279.0073111057 0.0479570031 0.0555494273 0.0791890547 0.0060514992 0.0452720000 417796365 0 402718720 -0.0453065112 -0.1582925171 -0.0184194669 3255 1311867279.0397729874 0.0466735885 0.0555467004 0.0791890547 0.0060517494 0.0446390000 417799417 0 402718720 -0.0424324013 -0.1570160836 -0.0173849631 3256 1311867279.0738539696 0.0479315966 0.0555443617 0.0791890547 0.0060509057 0.0454870000 417802893 0 402718720 -0.0432037972 -0.1553617865 -0.0132981706 3257 1311867279.1068439484 0.0484960787 0.0555421976 0.0791890547 0.0060507803 0.0453110000 417806297 0 402718720 -0.0456324778 -0.1565464586 -0.0096959025 3258 1311867279.1392490864 0.0475477539 0.0555397438 0.0791890547 0.0060501443 0.0455020000 417809133 0 402718720 -0.0445169210 -0.1573928595 -0.0064662285 3259 1311867279.1712040901 0.0477820672 0.0555373634 0.0791890547 0.0060565640 0.0450550000 417812545 0 402718720 -0.0421681292 -0.1550863534 -0.0047391644 3260 1311867279.2070438862 0.0485683642 0.0555352257 0.0791890547 0.0060569489 0.0439060000 417815501 0 402718720 -0.0439057313 -0.1545526683 -0.0005568583 3261 1311867279.2411210537 0.0471772775 0.0555326627 0.0791890547 0.0060576528 0.0833040000 417818833 0 402718720 -0.0455731675 -0.1570407301 0.0024929051 3262 1311867279.2717759609 0.0463059023 0.0555298341 0.0791890547 0.0060572819 0.0456680000 417821685 0 402718720 -0.0436969772 -0.1562048048 0.0044913460 3263 1311867279.3067219257 0.0477422550 0.0555274475 0.0791890547 0.0060575238 0.0451230000 417825073 0 402718720 -0.0425394066 -0.1534318030 0.0074767321 3264 1311867279.3388090134 0.0478935800 0.0555251087 0.0791890547 0.0060587503 0.0453320000 417828301 0 402718720 -0.0445471890 -0.1546015590 0.0111767789 3265 1311867279.3804929256 0.0467538126 0.0555224222 0.0791890547 0.0060603714 0.0455190000 417831729 0 402718720 -0.0442364104 -0.1541598290 0.0142539181 3266 1311867279.4089910984 0.0471989438 0.0555198737 0.0791890547 0.0060611089 0.0521040000 417834973 0 402718720 -0.0442594141 -0.1522708088 0.0161826983 3267 1311867279.4410970211 0.0467961319 0.0555172035 0.0791890547 0.0060615272 0.0448250000 417837673 0 402718720 -0.0448225662 -0.1527495086 0.0195428394 3268 1311867279.4725570679 0.0473292731 0.0555146980 0.0791890547 0.0060606761 0.0456690000 417841093 0 402718720 -0.0460691415 -0.1551409811 0.0239075832 3269 1311867279.5095710754 0.0467287488 0.0555120103 0.0791890547 0.0060601296 0.0582500000 418452957 0 402718720 -0.0435070060 -0.1532283723 0.0261177998 3270 1311867279.5407390594 0.0476695634 0.0555096120 0.0791890547 0.0060613258 0.1446980000 418430593 0 402718720 -0.0442865044 -0.1514008641 0.0288578365 3271 1311867279.5734229088 0.0476737730 0.0555072165 0.0791890547 0.0060616300 0.1458610000 418431909 0 402718720 -0.0452214628 -0.1536218524 0.0321908742 3272 1311867279.6121640205 0.0469455346 0.0555045998 0.0791890547 0.0060612664 0.1405650000 418750265 0 402718720 -0.0455880053 -0.1541200131 0.0351682305 3273 1311867279.6389439106 0.0478033051 0.0555022468 0.0791890547 0.0060632717 0.1371910000 428939553 0 402718720 -0.0443848707 -0.1518245637 0.0368740223 3274 1311867279.6749770641 0.0469074063 0.0554996217 0.0791890547 0.0060663000 0.0851940000 434078813 0 402718720 -0.0451866426 -0.1546182036 0.0402608067 3275 1311867279.7107980251 0.0458171852 0.0554966652 0.0791890547 0.0060658016 0.1345980000 432722649 0 402718720 -0.0444314629 -0.1549765617 0.0423818491 3276 1311867279.7410199642 0.0469206534 0.0554940474 0.0791890547 0.0060656851 0.0546710000 434057745 0 402718720 -0.0444124155 -0.1527572423 0.0451235101 3277 1311867279.7777059078 0.0462022610 0.0554912119 0.0791890547 0.0060653882 0.1753870000 432133585 0 402718720 -0.0445798784 -0.1529789418 0.0478157736 3278 1311867279.8118851185 0.0465149805 0.0554884736 0.0791890547 0.0060650253 0.1518010000 418390889 0 402718720 -0.0439265519 -0.1545957178 0.0517390445 3279 1311867279.8438251019 0.0449617654 0.0554852632 0.0791890547 0.0060644899 0.0481610000 418407293 0 402718720 -0.0419800878 -0.1541105658 0.0535911508 3280 1311867279.8808829784 0.0452892110 0.0554821547 0.0791890547 0.0060668103 0.0473210000 418410681 0 402718720 -0.0419765115 -0.1524066180 0.0564884134 3281 1311867279.9088180065 0.0451595113 0.0554790085 0.0791890547 0.0060676892 0.0477180000 418413901 0 402718720 -0.0417111441 -0.1550255716 0.0601714402 3282 1311867279.9440410137 0.0446922705 0.0554757219 0.0791890547 0.0060673162 0.0570640000 418417225 0 402718720 -0.0408669263 -0.1555619538 0.0631585568 3283 1311867279.9795188904 0.0455346219 0.0554726938 0.0791890547 0.0060723338 0.0496570000 418420045 0 402718720 -0.0390677191 -0.1519293189 0.0655106083 3284 1311867280.0113790035 0.0463742539 0.0554699233 0.0791890547 0.0060734321 0.0499480000 418423345 0 402718720 -0.0404515043 -0.1535721868 0.0704385862 3285 1311867280.0401859283 0.0460210331 0.0554670469 0.0791890547 0.0060736389 0.0595500000 418426589 0 402718720 -0.0396221168 -0.1539470106 0.0732481107 3286 1311867280.0785079002 0.0460102409 0.0554641690 0.0791890547 0.0060747282 0.0489250000 418429649 0 402718720 -0.0366498567 -0.1501781344 0.0752197728 3287 1311867280.1111929417 0.0464665443 0.0554614317 0.0791890547 0.0060740011 0.0491570000 418432701 0 402718720 -0.0382555984 -0.1526110768 0.0791838765 3288 1311867280.1450068951 0.0461749546 0.0554586073 0.0791890547 0.0060731110 0.0485420000 418436089 0 402718720 -0.0383396149 -0.1542506665 0.0823863298 3289 1311867280.1753098965 0.0460052043 0.0554557331 0.0791890547 0.0060756504 0.0460180000 418439189 0 402718720 -0.0367638208 -0.1520795822 0.0839891881 3290 1311867280.2123339176 0.0459508412 0.0554528440 0.0791890547 0.0060766539 0.0491120000 418442441 0 402718720 -0.0364261717 -0.1513079554 0.0864070803 3291 1311867280.2422859669 0.0459065549 0.0554499433 0.0791890547 0.0060761533 0.0594600000 418445213 0 402718720 -0.0367585421 -0.1549370289 0.0906282067 3292 1311867280.2794580460 0.0464987867 0.0554472242 0.0791890547 0.0060823425 0.0463770000 418448961 0 402718720 -0.0346962400 -0.1511985660 0.0926748589 3293 1311867280.3114728928 0.0473767184 0.0554447734 0.0791890547 0.0060828367 0.0469790000 418452173 0 402718720 -0.0348145813 -0.1512968391 0.0962929279 3294 1311867280.3445079327 0.0468268543 0.0554421572 0.0791890547 0.0060830061 0.0580160000 418455137 0 402718720 -0.0348620713 -0.1540320516 0.0996797904 3295 1311867280.3755340576 0.0466844589 0.0554394993 0.0791890547 0.0060824411 0.0485020000 418458253 0 402718720 -0.0318534896 -0.1508720219 0.1008226648 3296 1311867280.4071900845 0.0478753336 0.0554372044 0.0791890547 0.0060820265 0.0459820000 418461537 0 402718720 -0.0330160633 -0.1523747891 0.1052831635 3297 1311867280.4424109459 0.0480832905 0.0554349739 0.0791890547 0.0060840208 0.0457540000 418464413 0 402718720 -0.0335554406 -0.1514936984 0.1078889519 3298 1311867280.4782869816 0.0461099744 0.0554321464 0.0791890547 0.0060845093 0.0483860000 418467881 0 402718720 -0.0321230814 -0.1509233564 0.1091425419 3299 1311867280.5091259480 0.0465874560 0.0554294654 0.0791890547 0.0060839715 0.0454790000 418471221 0 402718720 -0.0319447815 -0.1517056227 0.1125888005 3300 1311867280.5455989838 0.0468914881 0.0554268781 0.0791890547 0.0060832015 0.0582760000 418474377 0 402718720 -0.0315103978 -0.1515394151 0.1160925329 3301 1311867280.5782079697 0.0460599102 0.0554240405 0.0791890547 0.0060841062 0.0583180000 418477141 0 402718720 -0.0310845990 -0.1497682631 0.1172307283 3302 1311867280.6130499840 0.0468295701 0.0554214377 0.0791890547 0.0060840784 0.0466230000 418480937 0 402718720 -0.0327037238 -0.1502808034 0.1207307652 3303 1311867280.6422739029 0.0471418165 0.0554189310 0.0791890547 0.0060852325 0.0490880000 418483997 0 402718720 -0.0318409018 -0.1523279101 0.1240301132 3304 1311867280.6755290031 0.0473002084 0.0554164738 0.0791890547 0.0060856546 0.0482640000 418487009 0 402718720 -0.0302537158 -0.1502560824 0.1260449737 3305 1311867280.7094879150 0.0472409427 0.0554140001 0.0791890547 0.0060848173 0.0478950000 418490277 0 402718720 -0.0304891989 -0.1511932611 0.1284429431 3306 1311867280.7411808968 0.0464647785 0.0554112931 0.0791890547 0.0060855044 0.0586020000 418493177 0 402718720 -0.0309713781 -0.1522024274 0.1309090257 3307 1311867280.7752668858 0.0471752994 0.0554088026 0.0791890547 0.0060865574 0.0482610000 418496445 0 402718720 -0.0310212970 -0.1514652520 0.1330644339 3308 1311867280.8076250553 0.0466705151 0.0554061611 0.0791890547 0.0060857162 0.0478540000 418499721 0 402718720 -0.0303709377 -0.1516722739 0.1350488216 3309 1311867280.8401010036 0.0476896279 0.0554038291 0.0791890547 0.0060850247 0.0613780000 419197709 0 402718720 -0.0308581777 -0.1513553411 0.1381169409 3310 1311867280.8754839897 0.0475589149 0.0554014590 0.0791890547 0.0060841572 0.1518730000 419159969 0 402718720 -0.0318443440 -0.1519196630 0.1407724619 3311 1311867280.9079110622 0.0475120954 0.0553990762 0.0791890547 0.0060833526 0.1474980000 419163269 0 402718720 -0.0321474299 -0.1508215964 0.1429663897 3312 1311867280.9394528866 0.0480543151 0.0553968586 0.0791890547 0.0060824590 0.1347810000 419484565 0 402718720 -0.0311810579 -0.1498698592 0.1458703578 3313 1311867280.9766991138 0.0480298996 0.0553946350 0.0791890547 0.0060815971 0.1349260000 429691321 0 402718720 -0.0314456671 -0.1498978585 0.1488676518 3314 1311867281.0075190067 0.0481755659 0.0553924566 0.0791890547 0.0060807762 0.0869210000 435612909 0 402718720 -0.0312366933 -0.1501555443 0.1515766382 3315 1311867281.0433430672 0.0485487171 0.0553903921 0.0791890547 0.0060801339 0.1048460000 433549421 0 402718720 -0.0309478939 -0.1511358619 0.1549959034 3316 1311867281.0752780437 0.0473905057 0.0553879796 0.0791890547 0.0060793868 0.0635810000 434971025 0 402718720 -0.0305141378 -0.1513829231 0.1564817727 3317 1311867281.1074900627 0.0478659198 0.0553857119 0.0791890547 0.0060793753 0.1733430000 433278101 0 402718720 -0.0291206576 -0.1503952593 0.1593832523 3318 1311867281.1451520920 0.0482726581 0.0553835681 0.0791890547 0.0060786693 0.1417180000 419167113 0 402718720 -0.0307371076 -0.1507400572 0.1625017077 3319 1311867281.1786689758 0.0488266833 0.0553815926 0.0791890547 0.0060787716 0.0475240000 419183437 0 402718720 -0.0296823978 -0.1514709443 0.1655505598 3320 1311867281.2083299160 0.0487508066 0.0553795953 0.0791890547 0.0060782638 0.0483660000 419186225 0 402718720 -0.0291756503 -0.1495270878 0.1668600291 3321 1311867281.2457950115 0.0481889173 0.0553774301 0.0791890547 0.0060798591 0.0508570000 419189677 0 402718720 -0.0286902525 -0.1508400440 0.1695141047 3322 1311867281.2754399776 0.0492987968 0.0553756003 0.0791890547 0.0060792651 0.0616120000 419192649 0 402718720 -0.0284679737 -0.1511821002 0.1726814806 3323 1311867281.3072988987 0.0491760038 0.0553737346 0.0791890547 0.0060833134 0.0462070000 419195853 0 402718720 -0.0274869800 -0.1490746737 0.1744212508 3324 1311867281.3465099335 0.0493070967 0.0553719095 0.0791890547 0.0060853496 0.0488690000 419199377 0 402718720 -0.0260132328 -0.1487338096 0.1770711392 3325 1311867281.3751530647 0.0501040742 0.0553703252 0.0791890547 0.0060846103 0.0495190000 419202301 0 402718720 -0.0272141881 -0.1522597075 0.1807310581 3326 1311867281.4080700874 0.0497998782 0.0553686504 0.0791890547 0.0060839549 0.0720880000 419205313 0 402718720 -0.0252795368 -0.1505980194 0.1824553758 3327 1311867281.4434111118 0.0496317968 0.0553669261 0.0791890547 0.0060833549 0.0466740000 419208637 0 402718720 -0.0252533555 -0.1503956318 0.1846221238 3328 1311867281.4753720760 0.0495754778 0.0553651859 0.0791890547 0.0060828918 0.0594850000 419211473 0 402718720 -0.0251649618 -0.1529607177 0.1874324530 3329 1311867281.5101969242 0.0495134853 0.0553634281 0.0791890547 0.0060832751 0.0490220000 419215245 0 402718720 -0.0253560729 -0.1512050629 0.1893937588 3330 1311867281.5435659885 0.0495425686 0.0553616801 0.0791890547 0.0060830284 0.0602750000 419218337 0 402718720 -0.0240061320 -0.1503469646 0.1917123497 3331 1311867281.5754749775 0.0495998636 0.0553599503 0.0791890547 0.0060825750 0.0492420000 419221421 0 402718720 -0.0234417263 -0.1523694098 0.1941986680 3332 1311867281.6111190319 0.0495672561 0.0553582118 0.0791890547 0.0060833424 0.0485640000 419224513 0 402718720 -0.0240637213 -0.1512570083 0.1960055977 3333 1311867281.6435608864 0.0489531234 0.0553562901 0.0791890547 0.0060824431 0.0456480000 419227909 0 402718720 -0.0219848026 -0.1508703828 0.1972245574 3334 1311867281.6755120754 0.0495078713 0.0553545359 0.0791890547 0.0060823048 0.0479790000 419231137 0 402718720 -0.0211062599 -0.1525060683 0.2000189722 3335 1311867281.7089190483 0.0505808219 0.0553531045 0.0791890547 0.0060815626 0.0485330000 419234477 0 402718720 -0.0226904768 -0.1537895203 0.2028409392 3336 1311867281.7452239990 0.0495074168 0.0553513522 0.0791890547 0.0060811494 0.0480530000 419237409 0 402718720 -0.0212588198 -0.1518921256 0.2030122876 3337 1311867281.7755289078 0.0510347895 0.0553500587 0.0791890547 0.0060809124 0.0459440000 419240589 0 402718720 -0.0211034976 -0.1530882567 0.2062118649 3338 1311867281.8075580597 0.0499595739 0.0553484438 0.0791890547 0.0060809482 0.0478860000 419243625 0 402718720 -0.0188350938 -0.1547511518 0.2072933763 3339 1311867281.8447821140 0.0488376021 0.0553464938 0.0791890547 0.0060800514 0.0473970000 419246877 0 402718720 -0.0172733217 -0.1542946249 0.2077073455 3340 1311867281.8756659031 0.0503487326 0.0553449975 0.0791890547 0.0060793654 0.0569090000 419249977 0 402718720 -0.0175050646 -0.1543452889 0.2102925479 3341 1311867281.9077229500 0.0496257395 0.0553432857 0.0791890547 0.0060785986 0.0470310000 419253253 0 402718720 -0.0166396834 -0.1551953256 0.2112249285 3342 1311867281.9444870949 0.0497297868 0.0553416060 0.0791890547 0.0060802713 0.0469790000 419256393 0 402718720 -0.0129458616 -0.1520928741 0.2122711837 3343 1311867281.9785399437 0.0497703254 0.0553399394 0.0791890547 0.0060822043 0.0474540000 419259789 0 402718720 -0.0138527611 -0.1545458734 0.2140286267 3344 1311867282.0098121166 0.0494223684 0.0553381698 0.0791890547 0.0060815702 0.0546030000 419262809 0 402718720 -0.0128260450 -0.1557990611 0.2153317034 3345 1311867282.0436799526 0.0488502346 0.0553362302 0.0791890547 0.0060814399 0.0523400000 419266085 0 402718720 -0.0104699545 -0.1537259519 0.2161441743 3346 1311867282.0755469799 0.0492195748 0.0553344022 0.0791890547 0.0060806960 0.0538540000 419269297 0 402718720 -0.0111862160 -0.1533293426 0.2178938538 3347 1311867282.1077909470 0.0486284830 0.0553323986 0.0791890547 0.0060802372 0.0532450000 419272253 0 402718720 -0.0097421436 -0.1559220701 0.2195025980 3348 1311867282.1464140415 0.0481300354 0.0553302474 0.0791890547 0.0060795370 0.0544840000 419275761 0 402718720 -0.0078727305 -0.1543834955 0.2211486399 3349 1311867282.1797480583 0.0486556962 0.0553282544 0.0791890547 0.0060786513 0.0528480000 419279029 0 402718720 -0.0072163073 -0.1535870284 0.2234532535 3350 1311867282.2136330605 0.0490636118 0.0553263843 0.0791890547 0.0060777640 0.0681450000 420010101 0 402718720 -0.0079702428 -0.1546097398 0.2256511301 3351 1311867282.2453169823 0.0490305126 0.0553245055 0.0791890547 0.0060770102 0.1443540000 419956209 0 402718720 -0.0061587272 -0.1541210711 0.2273631692 3352 1311867282.2844099998 0.0481749773 0.0553223726 0.0791890547 0.0060765878 0.1407780000 419957273 0 402718720 -0.0050483327 -0.1538559794 0.2284099758 3353 1311867282.3187301159 0.0482665971 0.0553202683 0.0791890547 0.0060766162 0.1363960000 420291917 0 402718720 -0.0061561307 -0.1562616378 0.2306525409 3354 1311867282.3445549011 0.0485592559 0.0553182525 0.0791890547 0.0060758720 0.1304060000 428507005 0 402718720 -0.0036160676 -0.1548113227 0.2322831899 3355 1311867282.3837130070 0.0482968614 0.0553161597 0.0791890547 0.0060762845 0.1114890000 435820677 0 402718720 -0.0026857788 -0.1546867192 0.2335088849 3356 1311867282.4114849567 0.0492512360 0.0553143525 0.0791890547 0.0060758810 0.0672900000 436307889 0 402718720 -0.0033263126 -0.1559673250 0.2361163497 3357 1311867282.4437038898 0.0489172526 0.0553124469 0.0791890547 0.0060752861 0.0766860000 436272273 0 402718720 -0.0015923930 -0.1558465660 0.2376326770 3358 1311867282.4754569530 0.0486627445 0.0553104666 0.0791890547 0.0060751121 0.0619160000 436415709 0 402718720 -0.0007720841 -0.1550678760 0.2390433699 3359 1311867282.5128560066 0.0498377122 0.0553088374 0.0791890547 0.0060745583 0.1607470000 434565029 0 402718720 -0.0007529082 -0.1562969387 0.2416746616 3360 1311867282.5435400009 0.0496989228 0.0553071677 0.0791890547 0.0060742166 0.1380960000 419923453 0 402718720 0.0018010279 -0.1585432887 0.2433552742 3361 1311867282.5755639076 0.0491185077 0.0553053264 0.0791890547 0.0060740785 0.0466600000 419939641 0 402718720 0.0019503674 -0.1566871703 0.2440799624 3362 1311867282.6112899780 0.0504375361 0.0553038785 0.0791890547 0.0060742717 0.0481590000 419942973 0 402718720 -0.0000111368 -0.1568247676 0.2465268970 3363 1311867282.6437261105 0.0505487956 0.0553024646 0.0791890547 0.0060737467 0.0471960000 419946377 0 402718720 0.0014576623 -0.1586404592 0.2480343729 3364 1311867282.6766591072 0.0498653725 0.0553008483 0.0791890547 0.0060730364 0.0473390000 419949205 0 402718720 0.0025012344 -0.1576589346 0.2479912490 3365 1311867282.7147250175 0.0499303527 0.0552992523 0.0791890547 0.0060721765 0.0496670000 419952457 0 402718720 0.0010585841 -0.1582883447 0.2488649487 3366 1311867282.7462520599 0.0508311726 0.0552979249 0.0791890547 0.0060714552 0.0467350000 419955733 0 402718720 0.0012943465 -0.1594941765 0.2503941953 3367 1311867282.7754290104 0.0503303222 0.0552964496 0.0791890547 0.0060707534 0.0494470000 419958705 0 402718720 0.0020596609 -0.1584483087 0.2504315376 3368 1311867282.8116350174 0.0508060083 0.0552951163 0.0791890547 0.0060699649 0.0568980000 419961989 0 402718720 0.0016097594 -0.1604419053 0.2522386611 3369 1311867282.8475370407 0.0497419946 0.0552934680 0.0791890547 0.0060704660 0.0581640000 419964929 0 402718720 0.0012887679 -0.1596640348 0.2528428733 3370 1311867282.8757910728 0.0495249853 0.0552917563 0.0791890547 0.0060699824 0.0482240000 419968277 0 402718720 -0.0004790816 -0.1570343971 0.2534248233 3371 1311867282.9114630222 0.0493928008 0.0552900064 0.0791890547 0.0060693406 0.0587180000 419971561 0 402718720 0.0000760481 -0.1575092077 0.2550418079 3372 1311867282.9456479549 0.0492836162 0.0552882251 0.0791890547 0.0060686767 0.0479330000 419974701 0 402718720 -0.0002119038 -0.1578870714 0.2564115524 3373 1311867282.9811890125 0.0495062284 0.0552865109 0.0791890547 0.0060684031 0.0480940000 419977857 0 402718720 -0.0015111864 -0.1566820741 0.2580619454 3374 1311867283.0114879608 0.0501270965 0.0552849817 0.0791890547 0.0060677783 0.0476230000 419981133 0 402718720 -0.0025094207 -0.1572225392 0.2597452402 3375 1311867283.0462460518 0.0501776747 0.0552834685 0.0791890547 0.0060687447 0.0482420000 419984209 0 402718720 -0.0020814054 -0.1584781557 0.2609865963 3376 1311867283.0752930641 0.0501793958 0.0552819566 0.0791890547 0.0060686313 0.0482710000 419987237 0 402718720 -0.0023768377 -0.1578998864 0.2619801462 3377 1311867283.1116878986 0.0491153039 0.0552801305 0.0791890547 0.0060696082 0.0478170000 419990745 0 402718720 -0.0019026119 -0.1568881422 0.2628854513 3378 1311867283.1435511112 0.0494921617 0.0552784171 0.0791890547 0.0060696034 0.0598700000 419993845 0 402718720 -0.0031445064 -0.1592752784 0.2640538812 3379 1311867283.1788220406 0.0502598248 0.0552769319 0.0791890547 0.0060727976 0.0452540000 419997313 0 402718720 -0.0048848595 -0.1587718427 0.2650173604 3380 1311867283.2158269882 0.0501936600 0.0552754279 0.0791890547 0.0060728409 0.0594120000 420000357 0 402718720 -0.0037836172 -0.1569579840 0.2648486495 3381 1311867283.2441749573 0.0510638207 0.0552741823 0.0791890547 0.0060739521 0.0474500000 420003457 0 402718720 -0.0033839345 -0.1600984335 0.2668448687 3382 1311867283.2776839733 0.0509407483 0.0552729009 0.0791890547 0.0060736633 0.0483790000 420006869 0 402718720 -0.0032156855 -0.1603928506 0.2676814198 3383 1311867283.3134660721 0.0504730158 0.0552714821 0.0791890547 0.0060729723 0.0491660000 420009809 0 402718720 -0.0019909088 -0.1585881710 0.2681405544 3384 1311867283.3498029709 0.0513037443 0.0552703096 0.0791890547 0.0060722229 0.0459250000 420013117 0 402718720 -0.0028024223 -0.1608936936 0.2702885866 3385 1311867283.3852219582 0.0515564308 0.0552692125 0.0791890547 0.0060717238 0.0461420000 420016569 0 402718720 -0.0021708794 -0.1596887857 0.2715006471 3386 1311867283.4173080921 0.0516367517 0.0552681397 0.0791890547 0.0060709370 0.0700870000 420019725 0 402718720 -0.0014746431 -0.1594427824 0.2722399831 3387 1311867283.4492650032 0.0518650673 0.0552671349 0.0791890547 0.0060701212 0.0456490000 420022553 0 402718720 -0.0010687578 -0.1601255536 0.2731240988 3388 1311867283.4853370190 0.0517774113 0.0552661049 0.0791890547 0.0060694045 0.0613060000 420025941 0 402718720 -0.0015418194 -0.1618482769 0.2736790776 3389 1311867283.5172159672 0.0510907546 0.0552648729 0.0791890547 0.0060685473 0.0455240000 420029281 0 402718720 -0.0005651768 -0.1600005031 0.2734624445 3390 1311867283.5495610237 0.0512029566 0.0552636747 0.0791890547 0.0060677509 0.0488920000 420032429 0 402718720 -0.0005990919 -0.1615173221 0.2743381262 3391 1311867283.5853879452 0.0516831912 0.0552626188 0.0791890547 0.0060669361 0.0476950000 420035441 0 402718720 -0.0008857399 -0.1615382433 0.2754110098 3392 1311867283.6173179150 0.0515257753 0.0552615171 0.0791890547 0.0060660928 0.0479260000 420038397 0 402718720 -0.0004174281 -0.1602983028 0.2758161724 3393 1311867283.6493821144 0.0517165400 0.0552604723 0.0791890547 0.0060652044 0.0475900000 420041857 0 402718720 -0.0007765219 -0.1596474797 0.2765730023 3394 1311867283.6852879524 0.0511438437 0.0552592594 0.0791890547 0.0060647530 0.0553000000 420045117 0 402718720 -0.0010270290 -0.1604004353 0.2769373655 3395 1311867283.7179150581 0.0508247204 0.0552579532 0.0791890547 0.0060640786 0.0449980000 420048273 0 402718720 -0.0000852142 -0.1575648636 0.2770192921 3396 1311867283.7492079735 0.0518638529 0.0552569538 0.0791890547 0.0060633211 0.0478500000 420051293 0 402718720 -0.0013083145 -0.1580092758 0.2786525190 3397 1311867283.7853169441 0.0527162068 0.0552562058 0.0791890547 0.0060624500 0.0480560000 420054553 0 402718720 -0.0019793995 -0.1587103158 0.2800447345 3398 1311867283.8174130917 0.0523734093 0.0552553575 0.0791890547 0.0060615761 0.0476080000 420057709 0 402718720 -0.0010938216 -0.1570550501 0.2801097035 3399 1311867283.8494520187 0.0522574447 0.0552544755 0.0791890547 0.0060607400 0.0455380000 420060977 0 402718720 -0.0024318323 -0.1568975300 0.2804713547 3400 1311867283.8853459358 0.0525460690 0.0552536789 0.0791890547 0.0060599135 0.0454670000 420064373 0 402718720 -0.0028480049 -0.1575091630 0.2812560797 3401 1311867283.9175400734 0.0519989654 0.0552527219 0.0791890547 0.0060590407 0.0572330000 420067329 0 402718720 -0.0035798606 -0.1565905809 0.2809480429 3402 1311867283.9498898983 0.0523288250 0.0552518624 0.0791890547 0.0060582227 0.0849910000 420070733 0 402718720 -0.0032910630 -0.1566347033 0.2816814184 3403 1311867283.9856629372 0.0523095578 0.0552509978 0.0791890547 0.0060575094 0.0455900000 420073665 0 402718720 -0.0049579907 -0.1585846394 0.2822145820 3404 1311867284.0172998905 0.0528913476 0.0552503046 0.0791890547 0.0060570126 0.0480800000 420076773 0 402718720 -0.0055891331 -0.1572174281 0.2827137411 3405 1311867284.0497789383 0.0518228672 0.0552492980 0.0791890547 0.0060565369 0.0455350000 420080377 0 402718720 -0.0065482389 -0.1552832574 0.2815957665 3406 1311867284.0853729248 0.0519704558 0.0552483353 0.0791890547 0.0060558876 0.0696590000 420083133 0 402718720 -0.0069749542 -0.1568673402 0.2824819386 3407 1311867284.1175038815 0.0518183187 0.0552473286 0.0791890547 0.0060550502 0.0453410000 420086345 0 402718720 -0.0066831950 -0.1561871767 0.2827639282 3408 1311867284.1494109631 0.0516391136 0.0552462698 0.0791890547 0.0060544886 0.0453890000 420089445 0 402718720 -0.0075075235 -0.1530709863 0.2827920914 3409 1311867284.1874890327 0.0523190200 0.0552454112 0.0791890547 0.0060541397 0.0479210000 420092937 0 402718720 -0.0080397148 -0.1559486091 0.2846325636 3410 1311867284.2173368931 0.0520166308 0.0552444643 0.0791890547 0.0060533102 0.0479740000 420095965 0 402718720 -0.0084198192 -0.1552477181 0.2846071720 3411 1311867284.2494308949 0.0522686951 0.0552435919 0.0791890547 0.0060524765 0.0476360000 420099177 0 402718720 -0.0067568291 -0.1533128470 0.2850005627 3412 1311867284.2853159904 0.0527341999 0.0552428564 0.0791890547 0.0060516035 0.0483280000 420102573 0 402718720 -0.0087985024 -0.1540224850 0.2857557237 3413 1311867284.3178350925 0.0518881679 0.0552418735 0.0791890547 0.0060507680 0.0593410000 420105585 0 402718720 -0.0081812553 -0.1530365646 0.2850781083 3414 1311867284.3494238853 0.0522050373 0.0552409840 0.0791890547 0.0060500149 0.0474590000 420108733 0 402718720 -0.0072714258 -0.1504494548 0.2854959667 3415 1311867284.3854329586 0.0523317382 0.0552401321 0.0791890547 0.0060495119 0.0476880000 420112057 0 402718720 -0.0077941492 -0.1529939026 0.2864841819 3416 1311867284.4175798893 0.0516292863 0.0552390751 0.0791890547 0.0060486646 0.0447380000 420115269 0 402718720 -0.0056717210 -0.1513872743 0.2860898972 3417 1311867284.4495139122 0.0525095277 0.0552382762 0.0791890547 0.0060479135 0.0473550000 420118353 0 402718720 -0.0068805218 -0.1513080001 0.2872905135 3418 1311867284.4854190350 0.0521623008 0.0552373763 0.0791890547 0.0060470702 0.0472760000 420121429 0 402718720 -0.0075832084 -0.1518071890 0.2873435616 3419 1311867284.5177299976 0.0523729138 0.0552365385 0.0791890547 0.0060462083 0.0451060000 420124953 0 402718720 -0.0065421015 -0.1509804279 0.2879454494 3420 1311867284.5494539738 0.0529992506 0.0552358843 0.0791890547 0.0060455042 0.0446860000 420127717 0 402718720 -0.0051402263 -0.1498340815 0.2888261676 3421 1311867284.5854179859 0.0529610030 0.0552352193 0.0791890547 0.0060447074 0.0591670000 420131369 0 402718720 -0.0050147828 -0.1510642469 0.2892868817 3422 1311867284.6174941063 0.0528075248 0.0552345099 0.0791890547 0.0060438862 0.0456710000 420134069 0 402718720 -0.0041635893 -0.1514256299 0.2896527648 3423 1311867284.6495230198 0.0522031002 0.0552336243 0.0791890547 0.0060432344 0.0465610000 420137465 0 402718720 -0.0045988262 -0.1504772753 0.2892615795 3424 1311867284.6853780746 0.0526839122 0.0552328796 0.0791890547 0.0060424677 0.0578670000 420140829 0 402718720 -0.0030434541 -0.1507680267 0.2903473675 3425 1311867284.7174859047 0.0526052341 0.0552321125 0.0791890547 0.0060416472 0.0569100000 420143913 0 402718720 -0.0031624399 -0.1518111974 0.2907092571 3426 1311867284.7498660088 0.0526545644 0.0552313601 0.0791890547 0.0060420262 0.0462130000 420146989 0 402718720 -0.0024805572 -0.1481093317 0.2908437252 3427 1311867284.7854089737 0.0523564778 0.0552305212 0.0791890547 0.0060413114 0.0845110000 420150001 0 402718720 -0.0027760155 -0.1500551850 0.2913119793 3428 1311867284.8186919689 0.0526242703 0.0552297609 0.0791890547 0.0060405089 0.0467390000 420153477 0 402718720 -0.0036954395 -0.1511699855 0.2918135822 3429 1311867284.8492770195 0.0524313524 0.0552289448 0.0791890547 0.0060402034 0.0465580000 420156601 0 402718720 -0.0011195820 -0.1473947763 0.2916259170 3430 1311867284.8853850365 0.0528145470 0.0552282409 0.0791890547 0.0060393955 0.0454270000 420159997 0 402718720 -0.0023239683 -0.1492658854 0.2923703790 3431 1311867284.9174609184 0.0527972430 0.0552275324 0.0791890547 0.0060385178 0.0455190000 420163073 0 402718720 -0.0035405550 -0.1497471929 0.2923260033 3432 1311867284.9492468834 0.0530424863 0.0552268957 0.0791890547 0.0060377442 0.0546080000 420165965 0 402718720 -0.0017463248 -0.1477801651 0.2923891544 3433 1311867284.9852581024 0.0532271750 0.0552263132 0.0791890547 0.0060374611 0.0448580000 420169345 0 402718720 -0.0025270265 -0.1507551670 0.2925593853 3434 1311867285.0175390244 0.0530757010 0.0552256869 0.0791890547 0.0060368738 0.0576960000 420172501 0 402718720 -0.0032633580 -0.1518380344 0.2920866013 3435 1311867285.0493679047 0.0524743311 0.0552248860 0.0791890547 0.0060362816 0.0455530000 420175649 0 402718720 -0.0028140210 -0.1490340680 0.2908144295 3436 1311867285.0853259563 0.0532890074 0.0552243226 0.0791890547 0.0060357369 0.0456000000 420179053 0 402718720 -0.0044107381 -0.1526468396 0.2911689281 3437 1311867285.1177120209 0.0528107248 0.0552236203 0.0791890547 0.0060351041 0.0567560000 420182025 0 402718720 -0.0034990292 -0.1536582708 0.2897763550 3438 1311867285.1502749920 0.0517980903 0.0552226239 0.0791890547 0.0060349511 0.0444760000 420185181 0 402718720 -0.0044817701 -0.1518840790 0.2877536416 3439 1311867285.1855800152 0.0527391508 0.0552219018 0.0791890547 0.0060341399 0.0807790000 420188521 0 402718720 -0.0031918194 -0.1529228389 0.2878552973 3440 1311867285.2187609673 0.0526990145 0.0552211684 0.0791890547 0.0060333105 0.0455780000 420191749 0 402718720 -0.0039976072 -0.1546156555 0.2870439887 3441 1311867285.2493660450 0.0526240543 0.0552204136 0.0791890547 0.0060324794 0.0450970000 420194633 0 402718720 -0.0029210541 -0.1538548619 0.2861520946 3442 1311867285.2853620052 0.0526343547 0.0552196623 0.0791890547 0.0060317829 0.0454530000 420198021 0 402718720 -0.0036912486 -0.1534981132 0.2852514088 3443 1311867285.3175029755 0.0530493334 0.0552190320 0.0791890547 0.0060310148 0.0451150000 420201233 0 402718720 -0.0046468433 -0.1553687751 0.2851839066 3444 1311867285.3493449688 0.0521523170 0.0552181415 0.0791890547 0.0060301942 0.0451330000 420204637 0 402718720 -0.0055824127 -0.1548899114 0.2838135362 3445 1311867285.3855409622 0.0519067086 0.0552171803 0.0791890547 0.0060295120 0.0632540000 420207697 0 402718720 -0.0042480808 -0.1530659795 0.2833055258 3446 1311867285.4175810814 0.0525949895 0.0552164193 0.0791890547 0.0060289568 0.0462030000 420210853 0 402718720 -0.0052813292 -0.1547791511 0.2842571139 3447 1311867285.4492840767 0.0521319620 0.0552155245 0.0791890547 0.0060281222 0.0456990000 420214065 0 402718720 -0.0044316947 -0.1534687728 0.2839474976 3448 1311867285.4853799343 0.0519277118 0.0552145710 0.0791890547 0.0060273611 0.0448210000 420217205 0 402718720 -0.0048852675 -0.1532838047 0.2842142880 3449 1311867285.5176479816 0.0523837060 0.0552137502 0.0791890547 0.0060267084 0.0445420000 420220409 0 402718720 -0.0052271243 -0.1538282931 0.2852926254 3450 1311867285.5494589806 0.0518169887 0.0552127656 0.0791890547 0.0060259043 0.0831350000 420223749 0 402718720 -0.0047543496 -0.1527792662 0.2852439582 3451 1311867285.5855739117 0.0519476756 0.0552118195 0.0791890547 0.0060252522 0.0450370000 420226897 0 402718720 -0.0054856725 -0.1521721631 0.2860414088 3452 1311867285.6175510883 0.0523136146 0.0552109799 0.0791890547 0.0060246394 0.0449460000 420230237 0 402718720 -0.0063746069 -0.1534930915 0.2871755958 3453 1311867285.6494030952 0.0524503700 0.0552101804 0.0791890547 0.0060239848 0.0455230000 420233065 0 402718720 -0.0058263429 -0.1508265138 0.2876825035 3454 1311867285.6856529713 0.0520856269 0.0552092758 0.0791890547 0.0060234195 0.0446810000 420236661 0 402718720 -0.0058825184 -0.1514865756 0.2880785465 3455 1311867285.7177190781 0.0524157062 0.0552084673 0.0791890547 0.0060228107 0.0589160000 420239553 0 402718720 -0.0071877297 -0.1534653604 0.2888261080 3456 1311867285.7497379780 0.0525831059 0.0552077076 0.0791890547 0.0060223475 0.0449380000 420242781 0 402718720 -0.0071174987 -0.1512267590 0.2889432907 3457 1311867285.7854781151 0.0520183668 0.0552067850 0.0791890547 0.0060216014 0.0449840000 420245905 0 402718720 -0.0074056908 -0.1526496261 0.2886839807 3458 1311867285.8179709911 0.0527655445 0.0552060791 0.0791890547 0.0060207431 0.0448910000 420249077 0 402718720 -0.0081621222 -0.1529251039 0.2894406319 3459 1311867285.8496279716 0.0529671796 0.0552054318 0.0791890547 0.0060199797 0.0561190000 420252353 0 402718720 -0.0088751595 -0.1527332515 0.2895427644 3460 1311867285.8852860928 0.0528398268 0.0552047481 0.0791890547 0.0060191974 0.0510610000 420255541 0 402718720 -0.0088580269 -0.1535897702 0.2894491553 3461 1311867285.9187369347 0.0532260872 0.0552041764 0.0791890547 0.0060184323 0.0448240000 420258561 0 402718720 -0.0100913942 -0.1554235220 0.2899481058 3462 1311867285.9496929646 0.0522999987 0.0552033375 0.0791890547 0.0060178793 0.0446610000 420261901 0 402718720 -0.0091523919 -0.1538468599 0.2888972461 3463 1311867285.9858360291 0.0526029766 0.0552025866 0.0791890547 0.0060172892 0.0448130000 420265249 0 402718720 -0.0108193904 -0.1539199054 0.2893641889 3464 1311867286.0184700489 0.0523979813 0.0552017770 0.0791890547 0.0060166872 0.0443480000 420268269 0 402718720 -0.0108463243 -0.1553949118 0.2896357775 3465 1311867286.0494220257 0.0528501011 0.0552010983 0.0791890547 0.0060161928 0.0442270000 420271353 0 402718720 -0.0100251678 -0.1532575190 0.2900661230 3466 1311867286.0854020119 0.0527816899 0.0552004002 0.0791890547 0.0060164881 0.0554300000 420274813 0 402718720 -0.0114114694 -0.1537347287 0.2901742458 3467 1311867286.1240980625 0.0528525859 0.0551997231 0.0791890547 0.0060163055 0.0618790000 420277817 0 402718720 -0.0113301016 -0.1537141651 0.2908968329 3468 1311867286.1506319046 0.0525429249 0.0551989570 0.0791890547 0.0060159982 0.0443700000 420280877 0 402718720 -0.0110841841 -0.1528961360 0.2905800641 3469 1311867286.1857590675 0.0533020124 0.0551984101 0.0791890547 0.0060152332 0.0447110000 420284081 0 402718720 -0.0104683079 -0.1532085836 0.2919487953 3470 1311867286.2179830074 0.0526140556 0.0551976654 0.0791890547 0.0060149764 0.0452550000 420287053 0 402718720 -0.0109976344 -0.1538366526 0.2919292450 3471 1311867286.2525210381 0.0529219322 0.0551970097 0.0791890547 0.0060145036 0.0460120000 420290521 0 402718720 -0.0110859144 -0.1514229774 0.2923446894 3472 1311867286.2861630917 0.0524946041 0.0551962314 0.0791890547 0.0060138450 0.0453560000 420293749 0 402718720 -0.0111214854 -0.1518572271 0.2922563255 3473 1311867286.3203520775 0.0530341528 0.0551956088 0.0791890547 0.0060130899 0.0450440000 420296769 0 402718720 -0.0125645399 -0.1534510255 0.2929328382 3474 1311867286.3524320126 0.0528444052 0.0551949320 0.0791890547 0.0060123806 0.0451480000 420299789 0 402718720 -0.0125229843 -0.1524911225 0.2929552197 3475 1311867286.3855628967 0.0532750525 0.0551943796 0.0791890547 0.0060115191 0.0559840000 420303273 0 402718720 -0.0123369191 -0.1517634094 0.2934680283 3476 1311867286.4177770615 0.0538115539 0.0551939817 0.0791890547 0.0060107364 0.0549800000 420306029 0 402718720 -0.0143081062 -0.1515149027 0.2939002514 3477 1311867286.4494199753 0.0532004535 0.0551934084 0.0791890547 0.0060104990 0.0444900000 420309385 0 402718720 -0.0141348671 -0.1522391587 0.2932476103 3478 1311867286.4855709076 0.0526837371 0.0551926868 0.0791890547 0.0060100945 0.0524510000 420312653 0 402718720 -0.0105643198 -0.1502322853 0.2929597795 3479 1311867286.5190370083 0.0533755086 0.0551921645 0.0791890547 0.0060092441 0.0490430000 420315737 0 402718720 -0.0106410962 -0.1509136558 0.2937840223 3480 1311867286.5512158871 0.0533452518 0.0551916338 0.0791890547 0.0060084272 0.0453810000 420319037 0 402718720 -0.0119320080 -0.1515413821 0.2937763631 3481 1311867286.5855200291 0.0524212345 0.0551908379 0.0791890547 0.0060078218 0.0451010000 420322417 0 402718720 -0.0108378939 -0.1503443271 0.2927485704 3482 1311867286.6190819740 0.0519668460 0.0551899120 0.0791890547 0.0060070051 0.0452230000 420325245 0 402718720 -0.0106996931 -0.1500633061 0.2926198542 3483 1311867286.6500060558 0.0526088588 0.0551891710 0.0791890547 0.0060063562 0.0452360000 420328593 0 402718720 -0.0108521543 -0.1527739465 0.2935040593 3484 1311867286.6856429577 0.0523218438 0.0551883480 0.0791890547 0.0060057036 0.0815850000 420331733 0 402718720 -0.0087335482 -0.1530164778 0.2932300270 3485 1311867286.7176160812 0.0516911894 0.0551873445 0.0791890547 0.0060051368 0.0740160000 420334945 0 402718720 -0.0082842968 -0.1519141793 0.2923982143 3486 1311867286.7495489120 0.0524411164 0.0551865567 0.0791890547 0.0060054939 0.0447060000 420338085 0 402718720 -0.0096438769 -0.1521722376 0.2932241261 3487 1311867286.7856459618 0.0518199950 0.0551855912 0.0791890547 0.0060055803 0.0449550000 420341289 0 402718720 -0.0088243615 -0.1522743702 0.2929396331 3488 1311867286.8176259995 0.0516627580 0.0551845812 0.0791890547 0.0060048584 0.0556920000 420344621 0 402718720 -0.0079184715 -0.1520806551 0.2929459214 3489 1311867286.8535819054 0.0527849011 0.0551838934 0.0791890547 0.0060041204 0.0444360000 420347753 0 402718720 -0.0093447529 -0.1523042470 0.2942187190 3490 1311867286.8868150711 0.0523588695 0.0551830840 0.0791890547 0.0060036110 0.0451870000 420350773 0 402718720 -0.0087905638 -0.1533059776 0.2941707373 3491 1311867286.9174380302 0.0521786436 0.0551822234 0.0791890547 0.0060030420 0.0450010000 420354057 0 402718720 -0.0075833742 -0.1504431963 0.2938534915 3492 1311867286.9543609619 0.0521284640 0.0551813489 0.0791890547 0.0060023456 0.0555310000 420357325 0 402718720 -0.0060256030 -0.1503983438 0.2940733135 3493 1311867286.9854118824 0.0523764715 0.0551805459 0.0791890547 0.0060016812 0.0453320000 420360545 0 402718720 -0.0078192018 -0.1518537402 0.2944982350 3494 1311867287.0174310207 0.0515628085 0.0551795104 0.0791890547 0.0060009866 0.0448730000 420363565 0 402718720 -0.0057583824 -0.1516596228 0.2935842574 3495 1311867287.0547020435 0.0523526184 0.0551787016 0.0791890547 0.0060028907 0.0533830000 420366769 0 402718720 -0.0056145862 -0.1496636420 0.2935930789 3496 1311867287.0856859684 0.0527663603 0.0551780116 0.0791890547 0.0060024645 0.0456810000 420369981 0 402718720 -0.0070586391 -0.1493171453 0.2942574620 3497 1311867287.1178219318 0.0526203401 0.0551772802 0.0791890547 0.0060019860 0.0581410000 421091441 0 402718720 -0.0060642045 -0.1505223364 0.2941664457 3498 1311867287.1537048817 0.0524492934 0.0551765003 0.0791890547 0.0060014093 0.1523810000 421049317 0 402718720 -0.0052678790 -0.1486221999 0.2936450839 3499 1311867287.1874449253 0.0523903556 0.0551757040 0.0791890547 0.0060006968 0.1496080000 421051293 0 402718720 -0.0049913675 -0.1496931911 0.2937935293 3500 1311867287.2175579071 0.0521135889 0.0551748292 0.0791890547 0.0060001768 0.1391620000 421368833 0 402718720 -0.0054615866 -0.1507511884 0.2935056090 3501 1311867287.2536680698 0.0522287674 0.0551739877 0.0791890547 0.0059995123 0.1424270000 431684113 0 402718720 -0.0055263657 -0.1496900767 0.2932648659 3502 1311867287.2870221138 0.0524262488 0.0551732030 0.0791890547 0.0059987354 0.1344890000 437357293 0 402718720 -0.0069155190 -0.1498720050 0.2933104038 3503 1311867287.3175630569 0.0525097661 0.0551724427 0.0791890547 0.0059987552 0.0616660000 437562497 0 402718720 -0.0060894173 -0.1516353488 0.2934847474 3504 1311867287.3540940285 0.0527493842 0.0551717512 0.0791890547 0.0059981213 0.1725720000 435752629 0 402718720 -0.0057981145 -0.1507696211 0.2932880521 3505 1311867287.3855540752 0.0528479256 0.0551710882 0.0791890547 0.0059973005 0.1398600000 421050637 0 402718720 -0.0060245916 -0.1506879628 0.2931650281 3506 1311867287.4175760746 0.0532051846 0.0551705275 0.0791890547 0.0059964700 0.0497280000 421067201 0 402718720 -0.0061633419 -0.1520504057 0.2934088111 3507 1311867287.4535288811 0.0527206548 0.0551698289 0.0791890547 0.0059956156 0.0579660000 421070589 0 402718720 -0.0052741747 -0.1518133730 0.2926138937 3508 1311867287.4867310524 0.0519044660 0.0551688981 0.0791890547 0.0059976392 0.0505350000 421073625 0 402718720 -0.0050477982 -0.1505647153 0.2925071716 3509 1311867287.5174999237 0.0527407713 0.0551682061 0.0791890547 0.0060005460 0.0479300000 421076965 0 402718720 -0.0053725317 -0.1511940062 0.2927002907 3510 1311867287.5534870625 0.0522494577 0.0551673746 0.0791890547 0.0059997786 0.0477450000 421080033 0 402718720 -0.0056269802 -0.1498131305 0.2922657430 3511 1311867287.5869519711 0.0531944893 0.0551668126 0.0791890547 0.0059990424 0.0474560000 421083109 0 402718720 -0.0060451142 -0.1512615383 0.2934318781 3512 1311867287.6176569462 0.0524804555 0.0551660477 0.0791890547 0.0059984390 0.0480970000 421086457 0 402718720 -0.0050925408 -0.1515418887 0.2927494645 3513 1311867287.6539158821 0.0528400205 0.0551653856 0.0791890547 0.0059975982 0.0574210000 421089901 0 402718720 -0.0041995198 -0.1505808532 0.2927331030 3514 1311867287.6875660419 0.0526048355 0.0551646569 0.0791890547 0.0059976430 0.0474780000 421092857 0 402718720 -0.0059233904 -0.1495279074 0.2925082743 3515 1311867287.7176280022 0.0519912206 0.0551637541 0.0791890547 0.0059976924 0.0598690000 421096029 0 402718720 -0.0056332685 -0.1509149075 0.2922177315 3516 1311867287.7553908825 0.0526918694 0.0551630511 0.0791890547 0.0059972302 0.0610720000 421099089 0 402718720 -0.0050989930 -0.1509857625 0.2928138971 3517 1311867287.7872428894 0.0525427610 0.0551623060 0.0791890547 0.0059968095 0.0566730000 421102501 0 402718720 -0.0052554812 -0.1481201649 0.2925596535 3518 1311867287.8260099888 0.0520478822 0.0551614208 0.0791890547 0.0059960524 0.0487500000 421105753 0 402718720 -0.0053662416 -0.1490060389 0.2927047908 3519 1311867287.8536510468 0.0526633933 0.0551607109 0.0791890547 0.0059954902 0.0498850000 421108853 0 402718720 -0.0052438211 -0.1508311033 0.2936201692 3520 1311867287.8931109905 0.0525677912 0.0551599743 0.0791890547 0.0059948846 0.0606870000 421112113 0 402718720 -0.0034832042 -0.1498652399 0.2938404381 3521 1311867287.9175710678 0.0526092686 0.0551592498 0.0791890547 0.0059946051 0.0494190000 421115101 0 402718720 -0.0031902958 -0.1479421407 0.2937757671 3522 1311867287.9535610676 0.0528598689 0.0551585970 0.0791890547 0.0059986864 0.0496780000 421118241 0 402718720 -0.0038027074 -0.1517377496 0.2947651744 3523 1311867287.9868519306 0.0531138331 0.0551580166 0.0791890547 0.0059981922 0.0496170000 421121197 0 402718720 -0.0013907515 -0.1525478214 0.2944039702 3524 1311867288.0178821087 0.0524446294 0.0551572466 0.0791890547 0.0059991905 0.0490360000 421124377 0 402718720 -0.0002586935 -0.1499052793 0.2933656573 3525 1311867288.0536389351 0.0534109399 0.0551567512 0.0791890547 0.0059993744 0.0474800000 421127701 0 402718720 -0.0010884516 -0.1526732892 0.2946323454 3526 1311867288.0854179859 0.0535488538 0.0551562952 0.0791890547 0.0059985913 0.0470660000 421130985 0 402718720 -0.0017780978 -0.1534532756 0.2946209311 3527 1311867288.1175940037 0.0523917116 0.0551555113 0.0791890547 0.0059977806 0.0468190000 421134317 0 402718720 0.0007265601 -0.1519597173 0.2933631241 3528 1311867288.1540820599 0.0534746423 0.0551550349 0.0791890547 0.0059973889 0.0481260000 421137513 0 402718720 -0.0009137560 -0.1547358781 0.2944985628 3529 1311867288.1854550838 0.0534343421 0.0551545473 0.0791890547 0.0059965934 0.0486600000 421140421 0 402718720 -0.0013315640 -0.1552348584 0.2938315272 3530 1311867288.2175340652 0.0527601577 0.0551538690 0.0791890547 0.0059962453 0.0491530000 421143601 0 402718720 -0.0004772823 -0.1523714662 0.2925881147 3531 1311867288.2535810471 0.0534426570 0.0551533844 0.0791890547 0.0059954623 0.0492780000 421146917 0 402718720 -0.0018468201 -0.1539396495 0.2930285633 3532 1311867288.2854719162 0.0528026894 0.0551527189 0.0791890547 0.0059946641 0.0491320000 421149945 0 402718720 -0.0027187429 -0.1556442827 0.2920657098 3533 1311867288.3175830841 0.0528462827 0.0551520660 0.0791890547 0.0059940272 0.0487310000 421153213 0 402718720 -0.0017759055 -0.1529622376 0.2917758822 3534 1311867288.3535211086 0.0523944795 0.0551512857 0.0791890547 0.0059932633 0.0596840000 421156473 0 402718720 -0.0028933212 -0.1540119946 0.2915336490 3535 1311867288.3858890533 0.0529696532 0.0551506686 0.0791890547 0.0059926942 0.0537550000 421159557 0 402718720 -0.0032527503 -0.1552199423 0.2922334075 3536 1311867288.4177610874 0.0533244498 0.0551501521 0.0791890547 0.0059923392 0.0469550000 421162769 0 402718720 -0.0034697205 -0.1525849849 0.2924278378 3537 1311867288.4560298920 0.0526164956 0.0551494358 0.0791890547 0.0059917650 0.0494860000 421166277 0 402718720 -0.0041378327 -0.1543175578 0.2921780050 3538 1311867288.4854650497 0.0526106730 0.0551487182 0.0791890547 0.0059909465 0.0469620000 421169041 0 402718720 -0.0053792093 -0.1544554234 0.2922754586 3539 1311867288.5176889896 0.0524512492 0.0551479560 0.0791890547 0.0059901036 0.0585310000 421172389 0 402718720 -0.0056038164 -0.1538165063 0.2920250893 3540 1311867288.5544929504 0.0533167012 0.0551474387 0.0791890547 0.0059895194 0.0588600000 421175585 0 402718720 -0.0059246272 -0.1526470333 0.2927782238 3541 1311867288.5874340534 0.0531061925 0.0551468622 0.0791890547 0.0059888561 0.0813140000 421178749 0 402718720 -0.0073891971 -0.1539275050 0.2926520109 3542 1311867288.6175410748 0.0529352352 0.0551462378 0.0791890547 0.0059880487 0.0492720000 421181969 0 402718720 -0.0072438512 -0.1542567313 0.2923637033 3543 1311867288.6551198959 0.0527016483 0.0551455479 0.0791890547 0.0059873439 0.0493190000 421185093 0 402718720 -0.0063551143 -0.1525761783 0.2916730046 3544 1311867288.6874110699 0.0534457527 0.0551450682 0.0791890547 0.0059865371 0.0485280000 421188113 0 402718720 -0.0086552668 -0.1531915069 0.2921495438 3545 1311867288.7177178860 0.0532080680 0.0551445218 0.0791890547 0.0059857292 0.0495210000 421191525 0 402718720 -0.0088204034 -0.1537857801 0.2915808856 3546 1311867288.7560660839 0.0530231670 0.0551439236 0.0791890547 0.0059849309 0.0881330000 421194585 0 402718720 -0.0091844872 -0.1526201367 0.2909861207 3547 1311867288.7855091095 0.0538577288 0.0551435610 0.0791890547 0.0059841510 0.0492300000 421197869 0 402718720 -0.0097123440 -0.1539319903 0.2914711535 3548 1311867288.8192400932 0.0536297113 0.0551431343 0.0791890547 0.0059834527 0.0490710000 421201065 0 402718720 -0.0090279002 -0.1525993496 0.2908973694 3549 1311867288.8543450832 0.0530459657 0.0551425434 0.0791890547 0.0059826346 0.0491750000 421204141 0 402718720 -0.0095557328 -0.1525317132 0.2899427414 3550 1311867288.8855559826 0.0534904338 0.0551420780 0.0791890547 0.0059818094 0.0467640000 421207561 0 402718720 -0.0094102565 -0.1523236483 0.2902915776 3551 1311867288.9176120758 0.0532210693 0.0551415370 0.0791890547 0.0059809747 0.0578640000 421210525 0 402718720 -0.0085713007 -0.1522415131 0.2898911536 3552 1311867288.9599480629 0.0530255549 0.0551409413 0.0791890547 0.0059803801 0.0490120000 421214073 0 402718720 -0.0095290393 -0.1513592452 0.2895308435 3553 1311867288.9855918884 0.0538646057 0.0551405821 0.0791890547 0.0059795485 0.0494470000 421217181 0 402718720 -0.0097349230 -0.1521319300 0.2904440761 3554 1311867289.0176560879 0.0536353886 0.0551401586 0.0791890547 0.0059787592 0.0494260000 421220081 0 402718720 -0.0087345727 -0.1517581493 0.2902089357 3555 1311867289.0535120964 0.0534413345 0.0551396807 0.0791890547 0.0059788267 0.0479420000 421223333 0 402718720 -0.0071951449 -0.1525702775 0.2903379798 3556 1311867289.0855109692 0.0530495681 0.0551390929 0.0791890547 0.0059783617 0.0659340000 421226441 0 402718720 -0.0080160443 -0.1512433738 0.2898114920 3557 1311867289.1175429821 0.0535362959 0.0551386423 0.0791890547 0.0059775667 0.0716940000 421229845 0 402718720 -0.0083388425 -0.1523588449 0.2903474569 3558 1311867289.1545929909 0.0536440909 0.0551382223 0.0791890547 0.0059769304 0.0488390000 421233089 0 402718720 -0.0089021120 -0.1518563628 0.2902906239 3559 1311867289.1856400967 0.0535823032 0.0551377851 0.0791890547 0.0059761995 0.0483770000 421235933 0 402718720 -0.0086674038 -0.1526171565 0.2903656662 3560 1311867289.2185060978 0.0529103465 0.0551371594 0.0791890547 0.0059754308 0.0486060000 421239265 0 402718720 -0.0082669947 -0.1522593945 0.2897772193 3561 1311867289.2550480366 0.0533563979 0.0551366593 0.0791890547 0.0059751813 0.0477370000 421242341 0 402718720 -0.0093284398 -0.1537863612 0.2902621329 3562 1311867289.2853870392 0.0530027524 0.0551360602 0.0791890547 0.0059743647 0.0846520000 421245809 0 402718720 -0.0086956136 -0.1530511528 0.2897746265 3563 1311867289.3176290989 0.0531602353 0.0551355057 0.0791890547 0.0059737696 0.0488740000 421248773 0 402718720 -0.0088922512 -0.1515924037 0.2895714939 3564 1311867289.3539168835 0.0530836582 0.0551349300 0.0791890547 0.0059730119 0.0480210000 421252161 0 402718720 -0.0098099280 -0.1528710425 0.2896177769 3565 1311867289.3861899376 0.0532902218 0.0551344125 0.0791890547 0.0059721761 0.0483200000 421255173 0 402718720 -0.0094475616 -0.1526856124 0.2899177969 3566 1311867289.4177041054 0.0532382242 0.0551338808 0.0791890547 0.0059720741 0.0507530000 421258265 0 402718720 -0.0093759410 -0.1516441107 0.2897405624 3567 1311867289.4536058903 0.0532999188 0.0551333667 0.0791890547 0.0059712608 0.0538210000 421261589 0 402718720 -0.0101792160 -0.1515309364 0.2900628150 3568 1311867289.4859669209 0.0537662730 0.0551329835 0.0791890547 0.0059707650 0.0550040000 421264665 0 402718720 -0.0104303453 -0.1531501561 0.2908929586 3569 1311867289.5183238983 0.0534715392 0.0551325180 0.0791890547 0.0059702681 0.0464240000 421267885 0 402718720 -0.0102079511 -0.1504560858 0.2906213999 3570 1311867289.5548820496 0.0532411635 0.0551319882 0.0791890547 0.0059697740 0.0483780000 421271201 0 402718720 -0.0114474501 -0.1512882710 0.2910414338 3571 1311867289.5856130123 0.0539644212 0.0551316612 0.0791890547 0.0059696709 0.0466490000 421274285 0 402718720 -0.0115691535 -0.1535572708 0.2920192480 3572 1311867289.6176490784 0.0524584241 0.0551309128 0.0791890547 0.0059689590 0.0475440000 421277409 0 402718720 -0.0112076066 -0.1511691362 0.2906378210 3573 1311867289.6536390781 0.0528045595 0.0551302617 0.0791890547 0.0059681762 0.0479480000 421280669 0 402718720 -0.0119062550 -0.1496804357 0.2915345430 3574 1311867289.6856849194 0.0523726270 0.0551294902 0.0791890547 0.0059676912 0.0667990000 421283753 0 402718720 -0.0126129333 -0.1510770768 0.2922069132 3575 1311867289.7204349041 0.0520688705 0.0551286340 0.0791890547 0.0059669609 0.0466250000 421287013 0 402718720 -0.0128522422 -0.1497536302 0.2925509810 3576 1311867289.7564179897 0.0525312498 0.0551279077 0.0791890547 0.0059666669 0.0462180000 421290441 0 402718720 -0.0128853414 -0.1490195543 0.2935789227 3577 1311867289.7855679989 0.0532557368 0.0551273843 0.0791890547 0.0059662816 0.0465850000 421293469 0 402718720 -0.0130548291 -0.1512825489 0.2949025333 3578 1311867289.8240370750 0.0531803556 0.0551268402 0.0791890547 0.0059655200 0.0466840000 421296977 0 402718720 -0.0141230598 -0.1511353701 0.2950789928 3579 1311867289.8541870117 0.0529125445 0.0551262215 0.0791890547 0.0059648296 0.0860160000 421300061 0 402718720 -0.0142704714 -0.1498886198 0.2951024771 3580 1311867289.8855679035 0.0534558184 0.0551257549 0.0791890547 0.0059641317 0.0472860000 421302897 0 402718720 -0.0152957607 -0.1512975991 0.2960610390 3581 1311867289.9200530052 0.0541869588 0.0551254927 0.0791890547 0.0059654413 0.0464630000 421306485 0 402718720 -0.0162416492 -0.1519383043 0.2964347005 3582 1311867289.9536409378 0.0534488186 0.0551250246 0.0791890547 0.0059655575 0.0469280000 421309625 0 402718720 -0.0162998661 -0.1501139551 0.2964735031 3583 1311867289.9855279922 0.0543966368 0.0551248213 0.0791890547 0.0059648862 0.0470790000 421312525 0 402718720 -0.0165175386 -0.1524789631 0.2980489433 3584 1311867290.0232169628 0.0541105419 0.0551245383 0.0791890547 0.0059646852 0.0571000000 421316153 0 402718720 -0.0161612239 -0.1536797285 0.2980581224 3585 1311867290.0535910130 0.0534851477 0.0551240810 0.0791890547 0.0059644015 0.0465470000 421319053 0 402718720 -0.0160748456 -0.1516243815 0.2975345850 3586 1311867290.0854740143 0.0540170372 0.0551237723 0.0791890547 0.0059639345 0.0465600000 421322065 0 402718720 -0.0170004573 -0.1532009840 0.2986426950 3587 1311867290.1248800755 0.0530108847 0.0551231833 0.0791890547 0.0059637427 0.0595010000 421325581 0 402718720 -0.0160353445 -0.1537406147 0.2982162833 3588 1311867290.1536118984 0.0529544689 0.0551225789 0.0791890547 0.0059632286 0.0469990000 421328673 0 402718720 -0.0157913677 -0.1512403190 0.2983190119 3589 1311867290.1856379509 0.0533773713 0.0551220926 0.0791890547 0.0059626283 0.0468970000 421331813 0 402718720 -0.0165027883 -0.1519571543 0.2991203368 3590 1311867290.2225489616 0.0534350388 0.0551216227 0.0791890547 0.0059620408 0.0472720000 421335017 0 402718720 -0.0161298420 -0.1523576528 0.2997068763 3591 1311867290.2540318966 0.0533373840 0.0551211258 0.0791890547 0.0059621235 0.0472090000 421337973 0 402718720 -0.0150500685 -0.1503956020 0.2996566296 3592 1311867290.2892379761 0.0532820784 0.0551206138 0.0791890547 0.0059620755 0.0468970000 421341569 0 402718720 -0.0158976205 -0.1526998580 0.3002215326 3593 1311867290.3220748901 0.0540634990 0.0551203196 0.0791890547 0.0059617954 0.0470520000 421344525 0 402718720 -0.0165450685 -0.1528918147 0.3008741140 3594 1311867290.3587789536 0.0531987101 0.0551197849 0.0791890547 0.0059612408 0.0472280000 421347657 0 402718720 -0.0157190356 -0.1509177536 0.2997511923 3595 1311867290.3864240646 0.0537658148 0.0551194083 0.0791890547 0.0059604369 0.0475780000 421350509 0 402718720 -0.0170935653 -0.1519290954 0.3003260791 3596 1311867290.4216320515 0.0537098460 0.0551190163 0.0791890547 0.0059596261 0.0581550000 421354273 0 402718720 -0.0184075013 -0.1527206302 0.3002587557 3597 1311867290.4578390121 0.0528480001 0.0551183849 0.0791890547 0.0059593416 0.0472020000 421356989 0 402718720 -0.0178524330 -0.1503316164 0.2992334366 3598 1311867290.4859950542 0.0534859970 0.0551179313 0.0791890547 0.0059587300 0.0472670000 421359961 0 402718720 -0.0179526061 -0.1523821801 0.2998663187 3599 1311867290.5223400593 0.0535209104 0.0551174875 0.0791890547 0.0059580290 0.0471480000 421363349 0 402718720 -0.0184051041 -0.1529658437 0.2997401357 3600 1311867290.5537059307 0.0531613752 0.0551169442 0.0791890547 0.0059574858 0.0474920000 421366369 0 402718720 -0.0181442592 -0.1513439566 0.2989494205 3601 1311867290.5855538845 0.0538795516 0.0551166005 0.0791890547 0.0059577864 0.0579850000 421369717 0 402718720 -0.0200522933 -0.1519763768 0.2996196151 3602 1311867290.6221020222 0.0528221764 0.0551159635 0.0791890547 0.0059573684 0.0851210000 421372857 0 402718720 -0.0186069366 -0.1522719264 0.2983908653 3603 1311867290.6536018848 0.0530293770 0.0551153844 0.0791890547 0.0059579511 0.0463790000 421376261 0 402718720 -0.0187112838 -0.1504446268 0.2980479300 3604 1311867290.6857531071 0.0531455614 0.0551148379 0.0791890547 0.0059572864 0.0469630000 421379161 0 402718720 -0.0194640085 -0.1527233422 0.2980223000 3605 1311867290.7256150246 0.0538647287 0.0551144911 0.0791890547 0.0059568707 0.0470430000 421382909 0 402718720 -0.0181793589 -0.1532423794 0.2983409166 3606 1311867290.7539739609 0.0535173193 0.0551140482 0.0791890547 0.0059566471 0.0481160000 421385881 0 402718720 -0.0185129866 -0.1514213830 0.2975649238 3607 1311867290.7866060734 0.0537815802 0.0551136787 0.0791890547 0.0059558574 0.0586480000 421388845 0 402718720 -0.0189861059 -0.1525996029 0.2975316644 3608 1311867290.8231720924 0.0536934733 0.0551132851 0.0791890547 0.0059553313 0.0466510000 421391969 0 402718720 -0.0180375148 -0.1535775065 0.2969840765 3609 1311867290.8556039333 0.0536692031 0.0551128850 0.0791890547 0.0059550027 0.0463910000 421395181 0 402718720 -0.0175899230 -0.1520919651 0.2964363098 3610 1311867290.8876988888 0.0541990064 0.0551126318 0.0791890547 0.0059569967 0.0474330000 421398521 0 402718720 -0.0178860351 -0.1524880528 0.2959063649 3611 1311867290.9227120876 0.0543881506 0.0551124312 0.0791890547 0.0059562103 0.0473970000 421401597 0 402718720 -0.0166950505 -0.1535008550 0.2958296239 3612 1311867290.9537110329 0.0538099520 0.0551120706 0.0791890547 0.0059573822 0.0469260000 421404553 0 402718720 -0.0167734586 -0.1534673870 0.2955377400 3613 1311867290.9906909466 0.0533711091 0.0551115887 0.0791890547 0.0059566258 0.0577560000 421408125 0 402718720 -0.0158801768 -0.1529873312 0.2947511077 3614 1311867291.0239291191 0.0536075719 0.0551111726 0.0791890547 0.0059561953 0.0478410000 421411265 0 402718720 -0.0152339749 -0.1542615145 0.2949219942 3615 1311867291.0558199883 0.0529523678 0.0551105754 0.0791890547 0.0059553913 0.0472690000 421414221 0 402718720 -0.0137896687 -0.1536638439 0.2939363122 3616 1311867291.0934820175 0.0530960374 0.0551100183 0.0791890547 0.0059549369 0.0467350000 421417737 0 402718720 -0.0135109518 -0.1520914584 0.2936157584 3617 1311867291.1203110218 0.0532574281 0.0551095061 0.0791890547 0.0059547550 0.0465590000 421420773 0 402718720 -0.0135387424 -0.1543940455 0.2938181162 3618 1311867291.1541891098 0.0535103753 0.0551090641 0.0791890547 0.0059552164 0.0472440000 421423673 0 402718720 -0.0114230197 -0.1544742733 0.2931416035 3619 1311867291.1891989708 0.0529868752 0.0551084777 0.0791890547 0.0059554465 0.0577280000 421427061 0 402718720 -0.0119164083 -0.1528030038 0.2926082313 3620 1311867291.2211010456 0.0531229600 0.0551079292 0.0791890547 0.0059549455 0.0589640000 421430209 0 402718720 -0.0119377263 -0.1544702500 0.2925323546 3621 1311867291.2543909550 0.0526946224 0.0551072627 0.0791890547 0.0059542034 0.0599420000 421433349 0 402718720 -0.0110483244 -0.1528860033 0.2917060852 3622 1311867291.2877960205 0.0528824441 0.0551066485 0.0791890547 0.0059534082 0.0471440000 421436497 0 402718720 -0.0108086038 -0.1538068056 0.2916455865 3623 1311867291.3210899830 0.0526581071 0.0551059727 0.0791890547 0.0059530044 0.0471260000 421439837 0 402718720 -0.0098470487 -0.1554278582 0.2909511328 3624 1311867291.3547959328 0.0525743440 0.0551052741 0.0791890547 0.0059527160 0.0581370000 421442777 0 402718720 -0.0106915571 -0.1538995206 0.2901410758 3625 1311867291.3878760338 0.0536534712 0.0551048736 0.0791890547 0.0059521996 0.0572930000 421446117 0 402718720 -0.0108002052 -0.1533730626 0.2907894254 3626 1311867291.4223349094 0.0527793691 0.0551042322 0.0791890547 0.0059518555 0.0468570000 421449257 0 402718720 -0.0101642888 -0.1546810418 0.2898309827 3627 1311867291.4536559582 0.0530472286 0.0551036651 0.0791890547 0.0059510913 0.0461770000 421452597 0 402718720 -0.0089530423 -0.1538267732 0.2896420658 3628 1311867291.4883999825 0.0527386516 0.0551030132 0.0791890547 0.0059504966 0.0474980000 421455673 0 402718720 -0.0093285721 -0.1530697197 0.2890422642 3629 1311867291.5201730728 0.0529433377 0.0551024181 0.0791890547 0.0059498355 0.0471500000 421458813 0 402718720 -0.0094609614 -0.1536018699 0.2892570496 3630 1311867291.5536448956 0.0524526536 0.0551016881 0.0791890547 0.0059491286 0.0471060000 421462121 0 402718720 -0.0086030755 -0.1529796720 0.2885751128 3631 1311867291.5895080566 0.0529069118 0.0551010837 0.0791890547 0.0059488667 0.0577610000 421465253 0 402718720 -0.0089973900 -0.1526465714 0.2884800732 3632 1311867291.6206870079 0.0522859581 0.0551003086 0.0791890547 0.0059489409 0.0469120000 421468281 0 402718720 -0.0097491574 -0.1545101255 0.2881867886 3633 1311867291.6539781094 0.0513840392 0.0550992857 0.0791890547 0.0059483718 0.0470990000 421471485 0 402718720 -0.0094053447 -0.1547411829 0.2872692049 3634 1311867291.6896810532 0.0518070385 0.0550983797 0.0791890547 0.0059477648 0.0469680000 421474873 0 402718720 -0.0088525601 -0.1538961828 0.2871718109 3635 1311867291.7202739716 0.0521697290 0.0550975740 0.0791890547 0.0059470940 0.0476480000 421477965 0 402718720 -0.0099244248 -0.1555126011 0.2874403596 3636 1311867291.7537178993 0.0514159761 0.0550965615 0.0791890547 0.0059465387 0.0473010000 421481057 0 402718720 -0.0096957982 -0.1548363268 0.2863994539 3637 1311867291.7890019417 0.0514804944 0.0550955673 0.0791890547 0.0059459332 0.0861620000 421484525 0 402718720 -0.0086352173 -0.1540079117 0.2863628566 3638 1311867291.8217189312 0.0517371744 0.0550946441 0.0791890547 0.0059454584 0.0471480000 421487617 0 402718720 -0.0083548855 -0.1556237489 0.2868964970 3639 1311867291.8538639545 0.0517105535 0.0550937142 0.0791890547 0.0059448981 0.0477440000 421490949 0 402718720 -0.0080640242 -0.1543561816 0.2866548300 3640 1311867291.8879489899 0.0522929728 0.0550929447 0.0791890547 0.0059444523 0.0472500000 421494161 0 402718720 -0.0078926962 -0.1552671194 0.2870404720 3641 1311867291.9206929207 0.0521649048 0.0550921405 0.0791890547 0.0059438326 0.0476590000 421497117 0 402718720 -0.0081105977 -0.1544216275 0.2869876921 3642 1311867291.9537200928 0.0525459759 0.0550914414 0.0791890547 0.0059436722 0.0470510000 421500529 0 402718720 -0.0072667841 -0.1540475935 0.2871370018 3643 1311867291.9902889729 0.0523590185 0.0550906914 0.0791890547 0.0059441081 0.0475430000 421503461 0 402718720 -0.0072663482 -0.1549504250 0.2875896990 3644 1311867292.0225260258 0.0529052280 0.0550900916 0.0791890547 0.0059465048 0.0463230000 421506929 0 402718720 -0.0080867298 -0.1548140645 0.2874876857 3645 1311867292.0536830425 0.0531742685 0.0550895660 0.0791890547 0.0059457165 0.0470960000 421509765 0 402718720 -0.0066230651 -0.1550933570 0.2878609598 3646 1311867292.0922849178 0.0522035323 0.0550887745 0.0791890547 0.0059469856 0.0473460000 421513401 0 402718720 -0.0081705060 -0.1552771926 0.2878366113 3647 1311867292.1243879795 0.0529053546 0.0550881758 0.0791890547 0.0059465862 0.0469550000 421516045 0 402718720 -0.0083189886 -0.1535329521 0.2885455787 3648 1311867292.1602649689 0.0521798581 0.0550873786 0.0791890547 0.0059461055 0.0572540000 421519625 0 402718720 -0.0071416385 -0.1543339491 0.2882797122 3649 1311867292.1899850368 0.0529936254 0.0550868048 0.0791890547 0.0059452965 0.0469470000 421522541 0 402718720 -0.0070618279 -0.1545947045 0.2894251943 3650 1311867292.2207419872 0.0526497066 0.0550861371 0.0791890547 0.0059444828 0.0474110000 421525897 0 402718720 -0.0073181372 -0.1547037065 0.2892172933 3651 1311867292.2576909065 0.0524817519 0.0550854237 0.0791890547 0.0059437352 0.0469260000 421529021 0 402718720 -0.0085338801 -0.1550402790 0.2891702056 3652 1311867292.2878270149 0.0529554300 0.0550848405 0.0791890547 0.0059429470 0.0583760000 421532241 0 402718720 -0.0089547392 -0.1547843516 0.2897513211 3653 1311867292.3217270374 0.0524761863 0.0550841264 0.0791890547 0.0059448843 0.0477630000 421535389 0 402718720 -0.0085860379 -0.1552560925 0.2901819646 3654 1311867292.3621709347 0.0533537678 0.0550836528 0.0791890547 0.0059469177 0.0841520000 421538497 0 402718720 -0.0092298035 -0.1548852921 0.2904720604 3655 1311867292.3953619003 0.0531658195 0.0550831281 0.0791890547 0.0059461437 0.0479760000 421541957 0 402718720 -0.0092840977 -0.1551220119 0.2904168367 3656 1311867292.4259300232 0.0532214120 0.0550826189 0.0791890547 0.0059453409 0.0477840000 421545113 0 402718720 -0.0091574807 -0.1549242735 0.2904184759 3657 1311867292.4565210342 0.0528569669 0.0550820103 0.0791890547 0.0059446026 0.0473650000 421547893 0 402718720 -0.0083912984 -0.1550142616 0.2901484966 3658 1311867292.4883699417 0.0529694632 0.0550814328 0.0791890547 0.0059438521 0.0468430000 421551225 0 402718720 -0.0098600779 -0.1557211876 0.2902331948 3659 1311867292.5229649544 0.0529815070 0.0550808589 0.0791890547 0.0059430675 0.0684840000 421554445 0 402718720 -0.0089958515 -0.1557122171 0.2904034853 3660 1311867292.5581150055 0.0524809323 0.0550801485 0.0791890547 0.0059423297 0.0477590000 421557713 0 402718720 -0.0088566802 -0.1542659402 0.2900271118 3661 1311867292.5882439613 0.0526001193 0.0550794711 0.0791890547 0.0059420002 0.0604280000 421560941 0 402718720 -0.0089311432 -0.1555974633 0.2906303108 3662 1311867292.6230869293 0.0518863276 0.0550785991 0.0791890547 0.0059411985 0.0475110000 421563905 0 402718720 -0.0088032857 -0.1550675631 0.2901016474 3663 1311867292.6595211029 0.0527034476 0.0550779507 0.0791890547 0.0059403877 0.0477580000 421567285 0 402718720 -0.0087457094 -0.1549642384 0.2911193669 3664 1311867292.6880218983 0.0528328717 0.0550773380 0.0791890547 0.0059397573 0.0592980000 421570393 0 402718720 -0.0092920344 -0.1565531939 0.2915310562 3665 1311867292.7206969261 0.0522969142 0.0550765793 0.0791890547 0.0059392291 0.0593950000 421573725 0 402718720 -0.0088565052 -0.1543760896 0.2907934189 3666 1311867292.7561879158 0.0522721075 0.0550758143 0.0791890547 0.0059387085 0.0471140000 421576985 0 402718720 -0.0078370403 -0.1557367295 0.2911868691 ================================================ FILE: icra2018_results/Makefile ================================================ run: mkdir output -p ./paper_run.sh output report.pdf : 1080_violins.pdf tegra_violins.pdf pdfunite 1080_violins.pdf tegra_violins.pdf $@ %_violins.pdf : % ./*.py ./violins.py $*/violons_* --plot $*_violins.pdf pdflatex $*_report.tex clean : rm *.aux *.pdf *.tex *.log -f ================================================ FILE: icra2018_results/paper_run.sh ================================================ #!/bin/bash set -x if [ -z ${1+x} ]; then echo "This command requires one argument, the directory to store log files"; exit 1; fi if [ -z ${2+x} ]; then echo "Execute the full benchmark with no extra arguments." ; DEBUG_ARGUMENTS=""; else echo "Execute the debug mode with extra arguments '$2'."; DEBUG_ARGUMENTS=$2; fi LOG_DIRECTORY=$1 if [ -z ${DISPLAY+x} ]; then echo "DISPLAY is not set"; else echo "DISPLAY is set to '$DISPLAY'"; fi datasets=( "datasets/ICL_NUIM/living_room_traj0_loop.slam" "datasets/ICL_NUIM/living_room_traj1_loop.slam" "datasets/ICL_NUIM/living_room_traj2_loop.slam" "datasets/ICL_NUIM/living_room_traj3_loop.slam" "datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam" "datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam" "datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam" "datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam" ) run_prepare () { if [ -z ${SKIP_CLEAN+x} ]; then make clean make cleandatasets else echo "WARNING !! We will skip the cleaning step."; fi make slambench make benchmark APPS=kfusion,efusion,orbslam2,lsdslam,infinitam make ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt for i in "${datasets[@]}" do make $i done } run_memory () { if [ -z ${1+x} ]; then echo "run_memory requires one argument."; exit 1 ; fi dataset=$1 dataset_name=`basename -s .slam ${dataset}` if [ ! -f ${dataset} ]; then continue ; fi ./build/bin/benchmark_loader -i ${dataset} -load build/lib/liblsdslam-cpp-library.so -o ${LOG_DIRECTORY}/memory_lsdslam_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 ./build/bin/benchmark_loader -i ${dataset} -load build/lib/libkfusion-cpp-library.so -o ${LOG_DIRECTORY}/memory_kfusion_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 ./build/bin/benchmark_loader -i ${dataset} -load build/lib/libinfinitam-cpp-library.so -o ${LOG_DIRECTORY}/memory_infinitam_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 ./build/bin/benchmark_loader -i ${dataset} -load build/lib/liborbslam2-original-library.so -voc ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt -o ${LOG_DIRECTORY}/memory_orbslam2_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 if [ -f build/lib/libkfusion-cuda-library.so ]; then ./build/bin/benchmark_loader -i ${dataset} -load build/lib/libkfusion-cuda-library.so -o ${LOG_DIRECTORY}/memory_kfusion_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 fi if [ -f build/lib/libefusion-cuda-library.so ]; then ./build/bin/benchmark_loader -i ${dataset} -load build/lib/libefusion-cuda-library.so --textureDim 512 --nodeTextureDim 2048 -o ${LOG_DIRECTORY}/memory_efusion_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 fi if [ -f build/lib/libinfinitam-cuda-library.so ]; then ./build/bin/benchmark_loader -i ${dataset} -load build/lib/libinfinitam-cuda-library.so -o ${LOG_DIRECTORY}/memory_infinitam_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 fi } run_violins () { if [ -z ${2+x} ]; then echo "run_violins requires two arguments."; exit 1 ; fi for i in "${datasets[@]}" do dataset=$i dataset_name=`basename -s .slam ${dataset}` library=$1 library_name=`basename -s -library.so ${library}` arguments=$2 output_log=${LOG_DIRECTORY}/violons_${library_name}_${dataset_name}.log if [ ! -f ${library} ]; then continue ; fi if [ ! -f ${dataset} ]; then continue ; fi if [ -f ${output_log} ]; then rm ${output_log} ; fi ./build/bin/benchmark_loader -i ${dataset} -load ${library} ${arguments} -o ${LOG_DIRECTORY}/violons_${library_name}_${dataset_name}.log ${DEBUG_ARGUMENTS} || exit 1 done } run_prepare run_memory datasets/ICL_NUIM/living_room_traj2_loop.slam run_violins "build/lib/liblsdslam-cpp-library.so" "" run_violins "build/lib/liborbslam2-original-library.so" "-voc ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt" run_violins "build/lib/libkfusion-cpp-library.so" "" run_violins "build/lib/libinfinitam-cpp-library.so" "" run_violins "build/lib/libkfusion-cuda-library.so" "" run_violins "build/lib/libefusion-cuda-library.so" "--textureDim 512 --nodeTextureDim 2048" run_violins "build/lib/libinfinitam-cuda-library.so" "" ================================================ FILE: icra2018_results/plotutils.py ================================================ #!/usr/bin/python2 # DO not use DISPLAY within matplotlib #import matplotlib as mpl #mpl.use('Agg') import matplotlib.pyplot as plt # End of BugFix import matplotlib import pylab as plot from slamlog import * ######################################################################################### # UTILS PLOT ######################################################################################### matplotlib.rcParams['pdf.fonttype'] = 42 matplotlib.rcParams['ps.fonttype'] = 42 params = {'legend.fontsize': 22, 'xtick.labelsize' : 20, 'ytick.labelsize' : 20, 'figure.titlesize': 20, #'legend.linewidth': 2, # 'font.size' : 8, } plot.rcParams.update(params) #font = { # 'size' : 18} #matplotlib.rc('font', **font) ######################################################################################### # UTILS ALGO ######################################################################################### labels = { 'kfusion-cuda' : "KF-CUDA", 'kfusion-opencl' : "KF-OCL", 'kfusion-openmp' : "KF-OMP", 'kfusion-cpp' : "KF-CPP", 'kfusion-notoon' : "KF-NOT", 'kfusion-octree-openmp' : "KO-OMP", 'kfusion-octree-cpp' : "KO-CPP", 'efusion-cuda' : "EF-CUDA", 'orbslam2-original' : "OS2-CPP", 'infinitam-cpp' : "IT-CPP", 'infinitam-openmp' : "IT-OMP", 'infinitam-cuda' : "IT-CUDA", 'lsdslam-cpp' : "LS-CPP", 'lsdslam-original_mp' : "LS-PTH", 'ptam-original_mp' : "PT-PTH", 'svo-original' : "SV-ORI", 'okvis-original' : "OK-ORI", 'monoslam-sequential' : "MO-CPP", } def getlabel(name) : for lab in labels.keys() : if lab in name : return labels[lab] printerr("Name '%s' not found in labels '%s'\n" % (name,labels)) exit(1) short_list = [ "living_room_traj0_loop.slam", "living_room_traj1_loop.slam", "living_room_traj2_loop.slam", "living_room_traj3_loop.slam", "rgbd_dataset_freiburg1_rpy.slam" , "rgbd_dataset_freiburg2_rpy.slam" , "rgbd_dataset_freiburg1_xyz.slam" , "rgbd_dataset_freiburg2_xyz.slam" , ] ############################################################################################# ######## VISUALIZATION ############################################################################################# def generate_violins (data) : violins = {} datasets = [] for a in data : datasets = list ( set ( datasets + data[a].keys() ) ) algorithms = data.keys() for algorithm in data : for dataset in data[algorithm] : for it in data[algorithm][dataset] : if not STATISTICS_SECTION in it.keys() : printerr ("Invalid data (%s,%s), no STATISTICS_SECTION.\n" % (algorithm,dataset)) exit(1) if not ATE_COLUMN in it[STATISTICS_SECTION].keys() : printerr ("Invalid data(%s,%s), no ATE_COLUMN.\n" % (algorithm,dataset)) exit(1) for algorithm in data : MeanATE = [] FPS = [] Memory = [] for dataset in data[algorithm] : for it in data[algorithm][dataset] : MeanATE += [it[STATISTICS_SECTION][ATE_COLUMN][MEAN_FIELD]] Memory += [it[STATISTICS_SECTION][CPU_MEMORY_COLUMN][MAX_FIELD] / 1000000] FPS += [1 / it[STATISTICS_SECTION][DURATION_COLUMN][MEAN_FIELD]] violins[algorithm] = { ATE_COLUMN : MeanATE , FPS_COLUMN : FPS , CPU_MEMORY_COLUMN : Memory } return violins def plot_violins (data, filename , order) : violins = data ## PLOT DATA ## algo_long_name = [x for x in violins.keys() if getlabel(x) in order] algo_short_name = [getlabel(x) for x in violins.keys() if getlabel(x) in order] algo_position = [order.index(x) for x in algo_short_name] algo_ordered = [x for _,x in sorted(zip(algo_position,algo_long_name))] algos = algo_ordered pos = [x for x in xrange(len(algos))] if len(pos) == 0 : printerr("Empty data, cannot draw anything.\n") return False fig, axes = plt.subplots(nrows=1, ncols=3, figsize=(18, 5)) FPS_DATA = [ violins[algo][FPS_COLUMN] for algo in algos ] ATE_DATA = [ violins[algo][ATE_COLUMN] for algo in algos ] MEM_DATA = [ violins[algo][CPU_MEMORY_COLUMN] for algo in algos ] LABELS = [ getlabel(algo) for algo in algos ] axes[0].violinplot(FPS_DATA, pos, points=60, widths=0.7, showmeans=True, showextrema=True, showmedians=True, bw_method='silverman') axes[0].set_title('Speed (FPS)' , fontsize = 20) axes[1].violinplot(ATE_DATA, pos, points=60, widths=0.7, showmeans=True, showextrema=True, showmedians=True, bw_method='silverman') axes[1].set_title('Accuracy (ATE in meters)', fontsize = 20) axes[2].violinplot(MEM_DATA, pos, points=60, widths=0.7, showmeans=True, showextrema=True, showmedians=True, bw_method='silverman') axes[2].set_title('Memory CPU (MB)', fontsize = 14 ) for ax in axes.flatten(): ax.set_xticks(pos) ax.set_xticklabels(LABELS) for label in ax.get_xmajorticklabels(): label.set_rotation(30) label.set_horizontalalignment("right") if filename : fig.subplots_adjust(hspace=0.4) plt.savefig(filename, bbox_inches='tight') else : plt.show() return True ================================================ FILE: icra2018_results/slamlog.py ================================================ #!/usr/bin/python2 import os import time import re import math import numpy as np from utils import * LIBRARY_NAME_PROPERTY = "load-slam-library" PROPERTIES_SECTION = "Properties" STATISTICS_SECTION = "Statistics" FRAME_NUMBER_COLUMN = "Frame Number" ATE_COLUMN = "AbsoluteError" CPU_MEMORY_COLUMN = "CPU_Memory" DURATION_COLUMN = "Duration_Frame" FPS_COLUMN = "FPS" MAX_FIELD = "MAX" MIN_FIELD = "MIN" MEAN_FIELD = "MEAN" COUNT_FIELD = "COUNT" MEDIAN_FIELD = "MEDIAN" MAX_SUFFIX = "_MAX" MIN_SUFFIX = "_MIN" MEAN_SUFFIX = "_MEAN" COUNT_SUFFIX = "_COUNT" MEDIAN_SUFFIX = "_MEDIAN" ############################################################################################# ######## PARSERS ############################################################################################# def load_data_from_input_dirs ( input_dirs ) : filelist = [] for dirname in input_dirs : try : filelist += [os.path.join(dirname, f) for f in os.listdir(dirname) if f[-4:] == ".log" and os.path.isfile(os.path.join(dirname, f))] except OSError : printerr("Working directory %s not found.\n" % dirname ) return None printinfo("%d files to load ...\n" % len(filelist)) data = load_data_from_files (filelist) return data def load_data_from_file(filename) : start_time = time.time() f = open(filename) raw = f.read() f.close() inside = None headers = None data = {"date" : None , STATISTICS_SECTION : {} , PROPERTIES_SECTION : {}} lines = raw.split("\n") load_time = time.time() for line in lines : if line == "Process every frame mode enabled" : continue if line[0:len("SLAMBench Report run started:")] == "SLAMBench Report run started:" : matching_header = re.match("SLAMBench Report run started:\s+(.*)",line) assert(matching_header) data["date"] = str(matching_header.group(1)) continue if re.match(PROPERTIES_SECTION + ":",line) : inside = PROPERTIES_SECTION continue if re.match(STATISTICS_SECTION + ":",line) : inside = STATISTICS_SECTION continue if line == "" : continue if re.match("=+",line) : if inside != None : continue else : printerr ("Error unknow section.\n") return None if inside == PROPERTIES_SECTION : matching_arguments = re.match("\s*(.*):\s+(.*)\s*",line) if matching_arguments : data[PROPERTIES_SECTION][matching_arguments.group(1)] = matching_arguments.group(2) continue if inside == STATISTICS_SECTION : matching_fields = line.split("\t") if matching_fields : if headers and len(headers) == len(matching_fields): for i in xrange (len(matching_fields)) : current_value = float("NaN") try : current_value = float(matching_fields[i]) except ValueError: current_value = float("NaN") data[STATISTICS_SECTION][headers[i]] += [current_value] #if math.isnan(float(matching_fields[i])) : # printerr ( INVALID + " %s : Error while parsing the file, NaN found.\n" % filename ) # return None continue else : if headers : printerr ("New \n") headers = matching_fields[:] for k in headers : if not k in data[STATISTICS_SECTION].keys(): data[STATISTICS_SECTION][k] = [] continue printerr ("[load_data_from_file('%s')] Error line not parsed inside '%s': '%s'\n" % (filename,inside,line)) return None loop_time = time.time() if headers == None : return None #print "load = %f" % (1000 * (load_time - start_time) ) #print "loop = %f" % (1000 * (loop_time - load_time) ) return data def turn_data_to_stats(data) : stats = {} if not data or not STATISTICS_SECTION in data.keys() : printerr("no data or no STATISTICS_SECTION in data.keys()\n") return None if not FRAME_NUMBER_COLUMN in data[STATISTICS_SECTION].keys() : printerr("no '%s' in data[STATISTICS_SECTION].keys()\n" % FRAME_NUMBER_COLUMN ) printerr("data[STATISTICS_SECTION].keys() = %s\n" % data[STATISTICS_SECTION].keys() ) return None frame_count = len(data[STATISTICS_SECTION][FRAME_NUMBER_COLUMN]) last_algorithm_name = None ## FIRST PASS TO FIND ALGO SPECIFIC FIELDS for k in data[STATISTICS_SECTION].keys() : matching_key = re.match("^((.+)-)?(.+)$",k) if not matching_key : printerr ("Error with '%s' does not match any known field names.\n" % k) printerr ("Statistics header was :\n%s\n" % data[STATISTICS_SECTION].keys() ) return None algorithm_name = matching_key.group(2) row_name = matching_key.group(3) if not algorithm_name and not row_name in ["Frame Number", "Timestamp"] : algorithm_name = "unnamed" if (algorithm_name) : if not algorithm_name in stats.keys() : stats[algorithm_name] = {} if not row_name in stats[algorithm_name].keys() : stats[algorithm_name][row_name] = {} valid_numbers = [ x for x in data[STATISTICS_SECTION][k] if not math.isnan(float(x)) ] if len(valid_numbers) > 0 : stats[algorithm_name][row_name] = { COUNT_FIELD: len(valid_numbers), MIN_FIELD: min(valid_numbers), MAX_FIELD: max(valid_numbers), MEDIAN_FIELD: np.median(valid_numbers), MEAN_FIELD: np.mean(valid_numbers) } else : stats[algorithm_name][row_name] = { COUNT_FIELD: len(valid_numbers), MIN_FIELD: float("NaN"), MAX_FIELD: float("NaN"), MEDIAN_FIELD: float("NaN"), MEAN_FIELD: float("NaN"), } if not last_algorithm_name : last_algorithm_name = algorithm_name else : if algorithm_name != last_algorithm_name : printerr ("More than one algo used, current algorithm name is '%s', new algorithm name is '%s' unsupported case." % ( last_algorithm_name, algorithm_name ) ) exit(1) return stats def load_data_from_files (filelist) : data = {} for filename in filelist : start_time = time.time() temp = load_data_from_file(filename) load_time = (time.time() - start_time) * 1000 if temp and STATISTICS_SECTION in temp.keys()and PROPERTIES_SECTION in temp.keys() : stats = turn_data_to_stats(temp) if not "input" in temp[PROPERTIES_SECTION].keys() : printerr (" %s : input argument not found.\n" % filename ) continue dataset = temp[PROPERTIES_SECTION]["input"] #dataset = dataset.split("/")[-1] libraryname = temp[PROPERTIES_SECTION][LIBRARY_NAME_PROPERTY] if stats == None : printerr (" %s : stats == None.\n" % filename ) continue if len(stats.keys()) != 1 : printerr("This file has more than one algorithm or no algorithm\n") continue if not libraryname in data.keys() : data[libraryname] = {} if not dataset in data[libraryname].keys() : data[libraryname][dataset] = [] data[libraryname][dataset] += [{PROPERTIES_SECTION : temp[PROPERTIES_SECTION] , "date" : temp["date"], STATISTICS_SECTION : stats.values()[0]}] printinfo (" %s loaded in %f ms : len of stats = %d\n" % (filename,load_time,len(stats.keys()))) else : printerr (" %s : Error while loading the file. \n" % (filename)) return data def flat_data (data_array, Xcols, Ycols) : main = {} for run in data_array : wee = {} for col in run[PROPERTIES_SECTION] : if col in Xcols : wee[col] = run[PROPERTIES_SECTION][col] for col in run[STATISTICS_SECTION] : for subcol in run[STATISTICS_SECTION][col].keys() : if col + "_" + subcol in Ycols : wee[col + "_" + subcol] = run[STATISTICS_SECTION][col][subcol] if len(main.keys()) != 0 and len(main.keys()) != len(wee.keys()) : printerr("Invalid datapoint.\n") exit(1) for x in Xcols + Ycols : if not x in wee.keys() : printerr("%s not found in the log.\n" % x) exit(1) for row in wee.keys() : if not row in main : main [row] = [] main [row] += [wee[row]] return main ================================================ FILE: icra2018_results/tegra/memory_efusion_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 05:42:01 Properties: ================= frame-limit: 0 log-file: output//memory_efusion_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.2031840000 88427038 95654128 1762373632 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0026374757 0.0013187379 0.0026374757 0.0017024400 0.9474030000 88630210 95654128 1764880384 -0.0024953254 -0.0007021125 0.0006995602 3 0.0800000000 0.0101173818 0.0042516192 0.0101173818 0.0039606649 0.8080910000 88632228 95654128 1766785024 -0.0043978756 -0.0079790503 0.0020776484 4 0.1200000000 0.0064746188 0.0048073691 0.0101173818 0.0045292216 0.8297310000 88632990 95654128 1768689664 -0.0073182695 -0.0036471700 0.0007300427 5 0.1600000000 0.0057244324 0.0049907818 0.0101173818 0.0042780893 0.8271450000 88635120 95654128 1770340352 -0.0100418907 -0.0023229974 0.0015760884 6 0.2000000000 0.0113287689 0.0060471129 0.0113287689 0.0041826629 0.8321950000 88637470 95654128 1771974656 -0.0072733378 -0.0091877244 0.0032580164 7 0.2400000000 0.0137613313 0.0071491441 0.0137613313 0.0039205636 0.9063320000 88637904 95654128 1773711360 -0.0084408261 -0.0116500510 0.0038376036 8 0.2800000000 0.0109567223 0.0076250914 0.0137613313 0.0037287651 1.2978830000 88639598 95654128 1774829568 -0.0091288676 -0.0088033425 0.0031799795 9 0.3200000000 0.0101161199 0.0079018724 0.0137613313 0.0035643689 1.6133170000 88641932 95654128 1776844800 -0.0096302973 -0.0089874156 0.0023234256 10 0.3600000000 0.0064781415 0.0077594993 0.0137613313 0.0034957043 1.6552660000 88643678 95654128 1778597888 -0.0094802184 -0.0044326806 0.0014241862 11 0.4000000000 0.0061003678 0.0076086691 0.0137613313 0.0038332496 1.8122720000 88645372 95654128 1780088832 -0.0113054272 -0.0049017230 0.0014363085 12 0.4400000000 0.0057260180 0.0074517815 0.0137613313 0.0037279963 1.5530590000 88647182 95654128 1781739520 -0.0091215577 -0.0047794878 0.0001811116 13 0.4800000000 0.0093538854 0.0075980972 0.0137613313 0.0035729087 1.6520310000 88647616 95654128 1783390208 -0.0064525381 -0.0063047465 -0.0000028049 14 0.5200000000 0.0097767208 0.0077537132 0.0137613313 0.0034581787 1.8234030000 88649310 95654128 1785016320 -0.0058873254 -0.0053321063 -0.0006355807 15 0.5600000000 0.0114299888 0.0079987982 0.0137613313 0.0033448731 1.8961130000 88651004 95654128 1786793984 -0.0082499012 -0.0058251023 0.0007048107 16 0.6000000000 0.0188821405 0.0086790071 0.0188821405 0.0034238047 1.6572270000 88651438 95654128 1785524224 -0.0077722063 -0.0163366795 0.0019653698 17 0.6400000000 0.0165153481 0.0091399684 0.0188821405 0.0034398740 2.2489750000 88654412 95654128 1786896384 -0.0106976377 -0.0154727967 0.0002382895 18 0.6800000000 0.0189564284 0.0096853272 0.0189564284 0.0034203341 1.8637490000 88658730 95654128 1784737792 -0.0070967162 -0.0152675295 0.0006038457 19 0.7200000000 0.0173973534 0.0100912234 0.0189564284 0.0034630097 2.2296280000 88659164 95654128 1786007552 -0.0088220974 -0.0132348388 -0.0007003625 20 0.7600000000 0.0186653025 0.0105199273 0.0189564284 0.0034202548 1.5727450000 88660858 95654128 1787760640 -0.0128809717 -0.0167293735 0.0001345953 21 0.8000000000 0.0249640271 0.0112077416 0.0249640271 0.0033981273 1.1015940000 88662668 95654128 1784713216 -0.0109311007 -0.0200380180 0.0010270901 22 0.8400000000 0.0286661051 0.0120013036 0.0286661051 0.0034129316 1.9831890000 88663022 95654128 1785982976 -0.0121446857 -0.0219160989 0.0007911119 23 0.8800000000 0.0292122103 0.0127496039 0.0292122103 0.0033463056 2.2179940000 88664716 95654128 1788006400 -0.0124380551 -0.0242104828 0.0000529512 24 0.9200000000 0.0254716799 0.0132796904 0.0292122103 0.0033201928 1.5735810000 88666410 95654128 1784705024 -0.0235000979 -0.0201853029 -0.0014848781 25 0.9600000000 0.0292996839 0.0139204901 0.0292996839 0.0032720952 1.8021750000 88666844 95654128 1785974784 -0.0244310405 -0.0233809967 -0.0008299848 26 1.0000000000 0.0297313035 0.0145285983 0.0297313035 0.0032568555 2.0844480000 88668522 95654128 1788006400 -0.0265735537 -0.0223783888 -0.0013773779 27 1.0400000000 0.0317729115 0.0151672766 0.0317729115 0.0032707686 2.1589860000 88670216 95654128 1784705024 -0.0304499213 -0.0242788196 -0.0041726837 28 1.0800000000 0.0342184529 0.0158476757 0.0342184529 0.0034082894 2.1515610000 88670650 95654128 1785966592 -0.0343751870 -0.0249869786 -0.0040311930 29 1.1200000000 0.0409410000 0.0167129628 0.0409410000 0.0037325246 1.8288640000 88672328 95654128 1787998208 -0.0378549546 -0.0311953016 -0.0045892932 30 1.1600000000 0.0362495072 0.0173641809 0.0409410000 0.0036727095 0.9585820000 88674022 95654128 1784713216 -0.0498410761 -0.0280442499 -0.0043100757 31 1.2000000000 0.0315692089 0.0178224076 0.0409410000 0.0036168866 1.8887710000 88674456 95654128 1785966592 -0.0597527474 -0.0241813846 -0.0074841836 32 1.2400000000 0.0342069939 0.0183344260 0.0409410000 0.0036285995 1.8242320000 88676134 95654128 1787871232 -0.0646726862 -0.0256999582 -0.0097053749 33 1.2800000000 0.0366627648 0.0188898302 0.0409410000 0.0036799584 1.6254750000 88680388 95654128 1784696832 -0.0724986196 -0.0306378026 -0.0087722801 34 1.3200000000 0.0428603813 0.0195948464 0.0428603813 0.0036250168 1.2736530000 88686070 95654128 1785966592 -0.0947986692 -0.0347761214 -0.0096207913 35 1.3600000000 0.0439491719 0.0202906842 0.0439491719 0.0039278749 1.7286140000 88687764 95654128 1787871232 -0.0981783867 -0.0352639146 -0.0113461697 36 1.4000000000 0.0486518443 0.0210784942 0.0486518443 0.0044222486 1.7875220000 88689458 95654128 1784569856 -0.1017695442 -0.0384829305 -0.0112059014 37 1.4400000000 0.0485962145 0.0218222164 0.0486518443 0.0044105283 1.8743460000 88689892 95654128 1785966592 -0.1158213988 -0.0423502401 -0.0089437794 38 1.4800000000 0.0434819795 0.0223922102 0.0486518443 0.0043730169 1.7944880000 88691586 95654128 1787871232 -0.1285577714 -0.0376082957 -0.0096667055 39 1.5200000000 0.0483282618 0.0230572371 0.0486518443 0.0043337083 1.0247090000 88693280 95654128 1784721408 -0.1301627159 -0.0428426862 -0.0117058717 40 1.5600000000 0.0473377816 0.0236642508 0.0486518443 0.0042944042 1.0201030000 88693714 95654128 1785974784 -0.1401509345 -0.0433993936 -0.0114235841 41 1.6000000000 0.0441046432 0.0241627969 0.0486518443 0.0043064310 1.8013670000 88695408 95654128 1787658240 -0.1509848982 -0.0410835221 -0.0109176748 42 1.6400000000 0.0435712337 0.0246249026 0.0486518443 0.0042684828 1.6337840000 88697102 95654128 1784324096 -0.1615762413 -0.0370447822 -0.0097637624 43 1.6800000000 0.0494167842 0.0252014579 0.0494167842 0.0042194002 2.0846460000 88697520 95654128 1785847808 -0.1634085476 -0.0401237234 -0.0070143882 44 1.7200000000 0.0493531339 0.0257503597 0.0494167842 0.0042713991 1.8142350000 88699214 95654128 1787633664 -0.1718157828 -0.0424676910 -0.0089363093 45 1.7600000000 0.0510509349 0.0263125947 0.0510509349 0.0042547027 1.5103420000 88700908 95654128 1784586240 -0.1771989614 -0.0401651338 -0.0057523139 46 1.8000000000 0.0534157455 0.0269017936 0.0534157455 0.0042569243 1.4793000000 88701342 95654128 1785982976 -0.1827763021 -0.0423004776 -0.0045253867 47 1.8400000000 0.0579214282 0.0275617858 0.0579214282 0.0043075250 1.6528610000 88703036 95654128 1787887616 -0.1844479442 -0.0487730503 -0.0038462053 48 1.8800000000 0.0569262728 0.0281735460 0.0579214282 0.0043124372 2.0771110000 88704730 95654128 1784586240 -0.1870971471 -0.0464053825 -0.0043981159 49 1.9200000000 0.0495150089 0.0286090860 0.0579214282 0.0042928376 1.9235010000 88705148 95654128 1785982976 -0.1996146142 -0.0400824882 -0.0048691491 50 1.9600000000 0.0445726588 0.0289283575 0.0579214282 0.0042546872 2.0741310000 88706842 95654128 1788006400 -0.2162593305 -0.0359033681 -0.0014755796 51 2.0000000000 0.0410971120 0.0291669605 0.0579214282 0.0042129558 2.2576930000 88708536 95654128 1784705024 -0.2184904963 -0.0347552933 -0.0033705416 52 2.0400000000 0.0432155058 0.0294371249 0.0579214282 0.0041830595 1.9928810000 88708970 95654128 1785974784 -0.2233807296 -0.0376450233 -0.0038215879 53 2.0800000000 0.0435471497 0.0297033517 0.0579214282 0.0041798881 1.6339910000 88710664 95654128 1787879424 -0.2240162939 -0.0395111106 -0.0074073756 54 2.1200000000 0.0403805040 0.0299010768 0.0579214282 0.0042989210 2.1714450000 88712358 95654128 1784705024 -0.2356427908 -0.0358060524 -0.0041121691 55 2.1600000000 0.0383895636 0.0300554129 0.0579214282 0.0043770730 0.8730410000 88712792 95654128 1785982976 -0.2374864072 -0.0318834111 -0.0045554037 56 2.2000000000 0.0369035602 0.0301777012 0.0579214282 0.0043870163 0.9922830000 88714486 95654128 1788014592 -0.2561827302 -0.0274763852 0.0022648876 57 2.2400000000 0.0379411317 0.0303139018 0.0579214282 0.0043646465 1.2081450000 88716164 95654128 1784713216 -0.2600640357 -0.0306747183 0.0034697470 58 2.2800000000 0.0372791998 0.0304339931 0.0579214282 0.0043707414 1.8779080000 88716598 95654128 1785982976 -0.2705831230 -0.0318396538 0.0072299242 59 2.3200000000 0.0406255163 0.0306067308 0.0579214282 0.0045379721 2.1141400000 88718292 95654128 1788014592 -0.2799059451 -0.0285086818 0.0117465248 60 2.3600000000 0.0451591350 0.0308492709 0.0579214282 0.0046671850 0.9918030000 88719986 95654128 1784713216 -0.2813571393 -0.0357758775 0.0119842067 61 2.4000000000 0.0419229306 0.0310308063 0.0579214282 0.0047344859 1.9764850000 88720420 95654128 1785982976 -0.2904003561 -0.0348521546 0.0108956173 62 2.4400000000 0.0400923826 0.0311769607 0.0579214282 0.0048832101 1.6712620000 88722114 95654128 1787887616 -0.3138504028 -0.0301883630 0.0182448104 63 2.4800000000 0.0365493931 0.0312622374 0.0579214282 0.0049672868 2.0154120000 88724520 95654128 1784840192 -0.3255646825 -0.0297464915 0.0205795951 64 2.5200000000 0.0346793644 0.0313156301 0.0579214282 0.0051993595 1.9689890000 88893554 95654128 1786118144 -0.3383307457 -0.0250696652 0.0242637899 65 2.5600000000 0.0341788754 0.0313596800 0.0579214282 0.0055201153 1.6636260000 88900368 95654128 1788022784 -0.3528909981 -0.0256938469 0.0287024006 66 2.6000000000 0.0300691091 0.0313401259 0.0579214282 0.0055630220 1.4961680000 88912558 95654128 1784721408 -0.3677712977 -0.0234106854 0.0312003810 67 2.6400000000 0.0273551904 0.0312806492 0.0579214282 0.0055749942 1.5219150000 88912992 95654128 1785991168 -0.3798597753 -0.0185120292 0.0328982808 68 2.6800000000 0.0295572467 0.0312553051 0.0579214282 0.0055622733 1.4636800000 88914686 95654128 1787895808 -0.3885392249 -0.0186987631 0.0315528810 69 2.7200000000 0.0268314630 0.0311911914 0.0579214282 0.0055341834 1.2613290000 88916380 95654128 1784713216 -0.3993938267 -0.0138574466 0.0344538912 70 2.7600000000 0.0241567194 0.0310906990 0.0579214282 0.0055134243 1.8107720000 88916830 95654128 1785856000 -0.4111386538 -0.0118566426 0.0344047211 71 2.8000000000 0.0266612582 0.0310283125 0.0579214282 0.0055344768 2.1272820000 88918524 95654128 1787506688 -0.4164086580 -0.0135354931 0.0317617171 72 2.8400000000 0.0291393697 0.0310020772 0.0579214282 0.0061816924 2.0135120000 88920218 95654128 1784586240 -0.4310047626 -0.0110554406 0.0350362994 73 2.8800000000 0.0287211053 0.0309708310 0.0579214282 0.0062523311 1.9867980000 88920652 95654128 1785982976 -0.4423088133 -0.0109510794 0.0364814401 74 2.9200000000 0.0279824343 0.0309304472 0.0579214282 0.0063285409 2.1261300000 88922346 95654128 1787760640 -0.4448080659 -0.0088120606 0.0344259366 75 2.9600000000 0.0288384762 0.0309025543 0.0579214282 0.0063592469 1.7342060000 88924040 95654128 1784586240 -0.4465527833 -0.0074588996 0.0329634026 76 3.0000000000 0.0322768390 0.0309206370 0.0579214282 0.0063893676 1.9514960000 88924474 95654128 1785982976 -0.4471723437 -0.0121311713 0.0282241143 77 3.0400000000 0.0330872424 0.0309487747 0.0579214282 0.0063851731 1.5401630000 88926168 95654128 1787887616 -0.4475110173 -0.0127370832 0.0222986843 78 3.0800000000 0.0361938775 0.0310160196 0.0579214282 0.0063567636 1.4816850000 88927846 95654128 1784713216 -0.4472903013 -0.0161994714 0.0166545324 79 3.1200000000 0.0388050973 0.0311146155 0.0579214282 0.0063276112 1.6946130000 88928280 95654128 1785982976 -0.4524114430 -0.0151115060 0.0144759845 80 3.1600000000 0.0401428752 0.0312274688 0.0579214282 0.0062995126 1.6654090000 88929974 95654128 1788014592 -0.4565701783 -0.0142088756 0.0113150980 81 3.2000000000 0.0401324667 0.0313374070 0.0579214282 0.0062682335 1.5134620000 88931668 95654128 1784713216 -0.4695758522 -0.0157941449 0.0137933465 82 3.2400000000 0.0348566622 0.0313803248 0.0579214282 0.0062673386 2.1744250000 88932102 95654128 1785982976 -0.4792827368 -0.0104657430 0.0115857050 83 3.2800000000 0.0281004645 0.0313408084 0.0579214282 0.0062698965 1.8430910000 88934812 95654128 1788141568 -0.4908078909 -0.0027929693 0.0073706303 84 3.3200000000 0.0309565570 0.0313362340 0.0579214282 0.0062628016 1.7934650000 89105106 95654128 1784213504 -0.5005632043 -0.0055783424 0.0077335536 85 3.3600000000 0.0326051451 0.0313511623 0.0579214282 0.0062549202 1.7414030000 89105540 95654128 1785483264 -0.5123536587 -0.0053901281 0.0078472840 86 3.4000000000 0.0276705250 0.0313083642 0.0579214282 0.0062948707 1.8094320000 89107234 95654128 1787514880 -0.5293261409 -0.0000948114 0.0101675475 87 3.4400000000 0.0261784289 0.0312493994 0.0579214282 0.0063826583 1.1917220000 89108928 95654128 1784594432 -0.5395898819 0.0003275254 0.0091356542 88 3.4800000000 0.0291790254 0.0312258725 0.0579214282 0.0065794804 1.5835330000 89109378 95654128 1785864192 -0.5489145517 -0.0002127053 0.0099713579 89 3.5200000000 0.0281277485 0.0311910621 0.0579214282 0.0067099004 1.8374840000 89111056 95654128 1787887616 -0.5581769347 0.0015696010 0.0094835153 90 3.5600000000 0.0274325982 0.0311493014 0.0579214282 0.0068088836 1.5965120000 89112766 95654128 1784586240 -0.5670621395 -0.0005426412 0.0080496622 91 3.6000000000 0.0289058313 0.0311246479 0.0579214282 0.0068502229 1.2440740000 89113200 95654128 1785856000 -0.5809859633 -0.0030951151 0.0100117326 92 3.6400000000 0.0274359938 0.0310845538 0.0579214282 0.0068679260 1.1620510000 89114894 95654128 1787777024 -0.5956395864 0.0019157981 0.0137391966 93 3.6800000000 0.0306396335 0.0310797697 0.0579214282 0.0068588942 2.3447470000 89116588 95654128 1784713216 -0.5980280042 -0.0016097035 0.0121894581 94 3.7200000000 0.0307268761 0.0310760155 0.0579214282 0.0068312705 1.7153770000 89117022 95654128 1785982976 -0.6041952968 -0.0028661983 0.0111598140 95 3.7600000000 0.0301190428 0.0310659421 0.0579214282 0.0068251315 0.9689480000 89118716 95654128 1787887616 -0.6193203926 -0.0024864194 0.0162121188 96 3.8000000000 0.0290398560 0.0310448371 0.0579214282 0.0067988942 1.2653330000 89120410 95654128 1784713216 -0.6282075047 0.0000395814 0.0155377761 97 3.8400000000 0.0294375494 0.0310282671 0.0579214282 0.0067651214 2.0616810000 89120844 95654128 1785982976 -0.6343841553 -0.0039840713 0.0172816161 98 3.8800000000 0.0349137783 0.0310679152 0.0579214282 0.0067478480 1.8494450000 89122538 95654128 1787633664 -0.6458007097 -0.0094929207 0.0218852703 99 3.9200000000 0.0367046818 0.0311248522 0.0579214282 0.0067283886 1.4745960000 89124904 95654128 1784332288 -0.6515142322 -0.0107822903 0.0251571927 100 3.9600000000 0.0317374058 0.0311309777 0.0579214282 0.0066995727 1.8122850000 89293946 95654128 1785729024 -0.6627074480 -0.0068657314 0.0281708203 101 4.0000000000 0.0305775348 0.0311254981 0.0579214282 0.0066687776 1.7638000000 89295640 95654128 1787760640 -0.6712868214 -0.0067125545 0.0336849168 102 4.0400000000 0.0309573300 0.0311238494 0.0579214282 0.0066474718 1.5591980000 89297334 95654128 1784586240 -0.6742200255 -0.0081217568 0.0355723351 103 4.0800000000 0.0329194292 0.0311412822 0.0579214282 0.0066158241 1.9526230000 89297752 95654128 1785982976 -0.6841361523 -0.0105350632 0.0418741778 104 4.1200000000 0.0322508663 0.0311519513 0.0579214282 0.0065853694 1.5580590000 89299462 95654128 1788014592 -0.6967089176 -0.0104113556 0.0525882430 105 4.1600000000 0.0332110375 0.0311715616 0.0579214282 0.0066043651 1.8235200000 89301140 95654128 1784594432 -0.6976038218 -0.0104438765 0.0555972643 106 4.2000000000 0.0253566038 0.0311167035 0.0579214282 0.0065818042 2.2162120000 89301574 95654128 1785991168 -0.7100806236 -0.0038500992 0.0596044324 107 4.2400000000 0.0248996038 0.0310585998 0.0579214282 0.0065682903 1.7938430000 89303268 95654128 1788022784 -0.7096644044 -0.0062971124 0.0577658862 108 4.2800000000 0.0271344092 0.0310222647 0.0579214282 0.0065416967 1.8494310000 89304962 95654128 1784610816 -0.7185612321 -0.0100560784 0.0660877004 109 4.3200000000 0.0282398108 0.0309967376 0.0579214282 0.0065353371 1.3227970000 89305396 95654128 1785982976 -0.7191510201 -0.0106302323 0.0679474324 110 4.3600000000 0.0272445157 0.0309626265 0.0579214282 0.0065313401 2.1707800000 89307090 95654128 1787887616 -0.7305551767 -0.0129719526 0.0748119652 111 4.4000000000 0.0234823525 0.0308952366 0.0579214282 0.0065217307 1.9095580000 89308784 95654128 1784713216 -0.7388156056 -0.0101084132 0.0805307627 112 4.4400000000 0.0269907992 0.0308603756 0.0579214282 0.0065411399 1.8505130000 89309234 95654128 1785982976 -0.7427060604 -0.0105696702 0.0883334503 113 4.4800000000 0.0267903861 0.0308243580 0.0579214282 0.0065544552 1.7179140000 89310928 95654128 1787887616 -0.7463995814 -0.0092519345 0.0919147283 114 4.5200000000 0.0279344842 0.0307990082 0.0579214282 0.0065960719 1.6889740000 89312622 95654128 1784586240 -0.7568402886 -0.0097791245 0.1022496670 115 4.5600000000 0.0298116934 0.0307904229 0.0579214282 0.0066085191 1.7014620000 89313056 95654128 1785982976 -0.7566875219 -0.0126336571 0.1052323878 116 4.6000000000 0.0308461916 0.0307909036 0.0579214282 0.0066393476 1.8489190000 89314750 95654128 1787887616 -0.7660470009 -0.0098800678 0.1160689294 117 4.6400000000 0.0270495880 0.0307589266 0.0579214282 0.0066388311 2.0124050000 89316444 95654128 1784713216 -0.7760245204 -0.0027136542 0.1261868328 118 4.6800000000 0.0292819701 0.0307464100 0.0579214282 0.0066140347 2.0299310000 89316878 95654128 1785982976 -0.7796232104 -0.0063357162 0.1311187148 119 4.7200000000 0.0270771310 0.0307155757 0.0579214282 0.0065935633 0.6692180000 89318572 95654128 1787899904 -0.7884786725 -0.0059819333 0.1378441751 120 4.7600000000 0.0258295480 0.0306748588 0.0579214282 0.0065683239 0.7874140000 89320266 95654128 1784725504 -0.7957946062 -0.0025273941 0.1455193311 121 4.8000000000 0.0228657797 0.0306103210 0.0579214282 0.0065585237 0.7896470000 89320700 95654128 1786122240 -0.8077149391 0.0023134111 0.1613484472 122 4.8400000000 0.0225341637 0.0305441230 0.0579214282 0.0065400995 0.7708760000 89322394 95654128 1788026880 -0.8081746101 0.0056813275 0.1633155793 123 4.8800000000 0.0224861447 0.0304786109 0.0579214282 0.0065164493 0.7473620000 89324088 95654128 1784741888 -0.8143546581 0.0086008422 0.1695580035 124 4.9200000000 0.0230822731 0.0304189631 0.0579214282 0.0064943900 0.8276020000 89324522 95654128 1785995264 -0.8247439861 0.0092711151 0.1831529289 125 4.9600000000 0.0234155580 0.0303629358 0.0579214282 0.0065007505 0.8370360000 89326216 95654128 1787899904 -0.8279330730 0.0079694428 0.1896238625 126 5.0000000000 0.0215800684 0.0302932305 0.0579214282 0.0064795218 0.7061120000 89327926 95654128 1784344576 -0.8343763947 0.0102674104 0.1974231601 127 5.0400000000 0.0239533931 0.0302433105 0.0579214282 0.0064558218 0.8299890000 89329940 95654128 1785741312 -0.8429452777 0.0069226930 0.2142092288 128 5.0800000000 0.0204395019 0.0301667183 0.0579214282 0.0064383354 1.2164260000 89500234 95654128 1787772928 -0.8501348495 0.0120999627 0.2206285894 129 5.1200000000 0.0186091028 0.0300771244 0.0579214282 0.0064143364 1.7958750000 89512168 95654128 1784479744 -0.8563817739 0.0122199571 0.2277282774 130 5.1600000000 0.0160678085 0.0299693604 0.0579214282 0.0064033281 1.6642170000 89533594 95654128 1785876480 -0.8688892722 0.0168225616 0.2447657287 131 5.2000000000 0.0159222074 0.0298621302 0.0579214282 0.0064239516 1.1666000000 89535288 95654128 1787781120 -0.8720468879 0.0159282014 0.2495713979 132 5.2400000000 0.0136288619 0.0297391509 0.0579214282 0.0064398444 1.8711980000 89536982 95654128 1784598528 -0.8731461167 0.0165977869 0.2495514303 133 5.2800000000 0.0149364090 0.0296278521 0.0579214282 0.0064322665 1.3010450000 89537416 95654128 1785995264 -0.8839902878 0.0180718079 0.2664527297 134 5.3200000000 0.0137357786 0.0295092545 0.0579214282 0.0064360992 1.9418910000 89539110 95654128 1787899904 -0.8964167833 0.0252117831 0.2831790447 135 5.3600000000 0.0150427567 0.0294020953 0.0579214282 0.0064582669 1.6930950000 89540804 95654128 1784598528 -0.8977207541 0.0271264333 0.2872043252 136 5.4000000000 0.0154503034 0.0292995086 0.0579214282 0.0064960759 1.5646720000 89541238 95654128 1785995264 -0.9031008482 0.0225248933 0.2983379960 137 5.4400000000 0.0155392289 0.0291990686 0.0579214282 0.0065613938 1.4316250000 89542932 95654128 1787899904 -0.9075461626 0.0250854697 0.3084815145 138 5.4800000000 0.0161034241 0.0291041726 0.0579214282 0.0065989041 2.2180850000 89544626 95654128 1784725504 -0.9123411775 0.0227003153 0.3127750158 139 5.5200000000 0.0175384823 0.0290209662 0.0579214282 0.0066462993 1.5451290000 89545060 95654128 1785995264 -0.9166138172 0.0187041890 0.3174695671 140 5.5600000000 0.0195210259 0.0289531095 0.0579214282 0.0067193792 1.5328790000 89546754 95654128 1788026880 -0.9243918061 0.0186147615 0.3304921389 141 5.6000000000 0.0200900808 0.0288902511 0.0579214282 0.0067533244 1.8756300000 89548448 95654128 1784725504 -0.9290360808 0.0186774395 0.3360942900 142 5.6400000000 0.0209282320 0.0288341806 0.0579214282 0.0067979618 1.7094910000 89548882 95654128 1785995264 -0.9379159212 0.0166426152 0.3503313065 143 5.6800000000 0.0199920647 0.0287723476 0.0579214282 0.0068764021 1.4596930000 89550576 95654128 1788026880 -0.9444140196 0.0169597734 0.3611678481 144 5.7200000000 0.0196611620 0.0287090755 0.0579214282 0.0069115418 2.1752310000 89552270 95654128 1784725504 -0.9500797987 0.0195193514 0.3698610961 145 5.7600000000 0.0165853519 0.0286254636 0.0579214282 0.0069106715 1.9247900000 89552704 95654128 1785995264 -0.9583642483 0.0226784609 0.3773634732 146 5.8000000000 0.0162087958 0.0285404179 0.0579214282 0.0068987268 2.1090530000 89554398 95654128 1787899904 -0.9648678899 0.0219850652 0.3867862821 147 5.8400000000 0.0172792263 0.0284638112 0.0579214282 0.0068818670 1.6796370000 89557172 95654128 1784725504 -0.9741273522 0.0212373845 0.4071164727 148 5.8800000000 0.0160249975 0.0283797651 0.0579214282 0.0068596778 1.3258090000 89726218 95654128 1785995264 -0.9760413766 0.0210795365 0.4117130041 149 5.9200000000 0.0148651544 0.0282890631 0.0579214282 0.0068408128 1.9014910000 89727912 95654128 1788289024 -0.9814405441 0.0214142241 0.4234722853 150 5.9600000000 0.0139919724 0.0281937491 0.0579214282 0.0068213832 2.2695540000 89729606 95654128 1784352768 -0.9851716757 0.0208998304 0.4334156215 151 6.0000000000 0.0139526771 0.0280994374 0.0579214282 0.0068021333 1.5790140000 89730040 95654128 1785622528 -0.9891383648 0.0240329579 0.4423284829 152 6.0400000000 0.0130399456 0.0280003618 0.0579214282 0.0067862874 2.4293480000 89731734 95654128 1787392000 -0.9932015538 0.0242985524 0.4535379112 153 6.0800000000 0.0118779149 0.0278949863 0.0579214282 0.0067716130 2.1441190000 89733428 95654128 1784725504 -0.9977104664 0.0241812542 0.4628433585 154 6.1200000000 0.0118686454 0.0277909192 0.0579214282 0.0067908464 1.0215090000 89733862 95654128 1785999360 -1.0025426149 0.0250200108 0.4750583768 155 6.1600000000 0.0114054233 0.0276852063 0.0579214282 0.0068372433 0.6909470000 89735556 95654128 1787777024 -1.0055862665 0.0250937324 0.4825132191 156 6.2000000000 0.0176983215 0.0276211878 0.0579214282 0.0069872616 0.9053470000 89737250 95654128 1784762368 -1.0039385557 0.0206453744 0.4942879081 157 6.2400000000 0.0168636590 0.0275526685 0.0579214282 0.0070826250 1.5858030000 89737684 95654128 1786126336 -1.0065557957 0.0249660388 0.5055611730 158 6.2800000000 0.0171978716 0.0274871318 0.0579214282 0.0071466587 1.4628930000 89739378 95654128 1787904000 -1.0096725225 0.0225957502 0.5215225220 159 6.3200000000 0.0182614960 0.0274291089 0.0579214282 0.0071839705 1.7835710000 89741072 95654128 1784602624 -1.0092597008 0.0198547505 0.5291106701 160 6.3600000000 0.0184057187 0.0273727128 0.0579214282 0.0072197520 1.6370250000 89741506 95654128 1785999360 -1.0102256536 0.0215592477 0.5444574356 161 6.4000000000 0.0169238131 0.0273078128 0.0579214282 0.0072066823 1.8644720000 89743200 95654128 1787904000 -1.0101635456 0.0237113554 0.5567666292 162 6.4400000000 0.0194015820 0.0272590089 0.0579214282 0.0071868535 1.1741100000 89744894 95654128 1784729600 -1.0087559223 0.0228141267 0.5657479763 163 6.4800000000 0.0160876457 0.0271904729 0.0579214282 0.0071703987 1.4248640000 89745328 95654128 1786126336 -1.0125888586 0.0259071458 0.5805721283 164 6.5200000000 0.0193154011 0.0271424542 0.0579214282 0.0071508887 1.6376720000 89747022 95654128 1787904000 -1.0113166571 0.0247286316 0.5895068645 165 6.5600000000 0.0179798547 0.0270869233 0.0579214282 0.0071444728 1.6664070000 89748716 95654128 1784856576 -1.0135757923 0.0273056775 0.6080531478 166 6.6000000000 0.0190500040 0.0270385081 0.0579214282 0.0071608050 1.6370430000 89749150 95654128 1786126336 -1.0126920938 0.0290340409 0.6180447340 167 6.6400000000 0.0179350767 0.0269839965 0.0579214282 0.0071691521 1.5507860000 89750844 95654128 1788030976 -1.0131326914 0.0318487883 0.6287825108 168 6.6800000000 0.0167594329 0.0269231360 0.0579214282 0.0071723077 1.6021410000 89752538 95654128 1784729600 -1.0142425299 0.0298035908 0.6415591836 169 6.7200000000 0.0150954360 0.0268531496 0.0579214282 0.0071577207 1.9039590000 89752972 95654128 1785999360 -1.0145226717 0.0288763437 0.6577209234 170 6.7600000000 0.0152994720 0.0267851868 0.0579214282 0.0071528561 1.4760500000 89754666 95654128 1788030976 -1.0159326792 0.0318230875 0.6751407981 171 6.8000000000 0.0151837999 0.0267173425 0.0579214282 0.0071475212 1.3938600000 89756360 95654128 1784610816 -1.0153113604 0.0336033925 0.6841329336 172 6.8400000000 0.0143346181 0.0266453499 0.0579214282 0.0071282551 0.9779480000 89756794 95654128 1785880576 -1.0164759159 0.0382597372 0.6975363493 173 6.8800000000 0.0148311164 0.0265770595 0.0579214282 0.0071087310 1.5322730000 89758488 95654128 1787912192 -1.0174967051 0.0416802391 0.7112889290 174 6.9200000000 0.0170609392 0.0265223692 0.0579214282 0.0070897243 1.8515660000 89760182 95654128 1784737792 -1.0184931755 0.0467767119 0.7229870558 175 6.9600000000 0.0178327058 0.0264727139 0.0579214282 0.0070698118 1.5172750000 89760616 95654128 1786007552 -1.0184491873 0.0495553948 0.7350307107 176 7.0000000000 0.0168235507 0.0264178891 0.0579214282 0.0070556850 2.0917590000 89762310 95654128 1788030976 -1.0214508772 0.0503683612 0.7508494258 177 7.0400000000 0.0177501943 0.0263689191 0.0579214282 0.0070742135 2.0037980000 89764004 95654128 1784729600 -1.0223792791 0.0501112156 0.7581368685 178 7.0800000000 0.0176451299 0.0263199091 0.0579214282 0.0070607111 1.3821660000 89764438 95654128 1785999360 -1.0217084885 0.0489567593 0.7647960782 179 7.1200000000 0.0156977624 0.0262605675 0.0579214282 0.0070477754 1.8227970000 89766116 95654128 1788030976 -1.0202707052 0.0479263477 0.7781007290 180 7.1600000000 0.0145659707 0.0261955975 0.0579214282 0.0070288344 1.5073290000 89767810 95654128 1784221696 -1.0206139088 0.0503243543 0.7923195362 181 7.2000000000 0.0115698660 0.0261147923 0.0579214282 0.0070146069 1.4833260000 89768244 95654128 1785491456 -1.0196911097 0.0499572828 0.8060083985 182 7.2400000000 0.0112826163 0.0260332969 0.0579214282 0.0069981774 1.2660550000 89769938 95654128 1787174912 -1.0201274157 0.0510505736 0.8211856484 183 7.2800000000 0.0113347052 0.0259529767 0.0579214282 0.0069833050 1.4207970000 89771632 95654128 1784348672 -1.0222659111 0.0510079227 0.8367791772 184 7.3200000000 0.0111920759 0.0258727544 0.0579214282 0.0069646730 1.7351370000 89772066 95654128 1785745408 -1.0195993185 0.0492187552 0.8463376760 185 7.3600000000 0.0108329672 0.0257914583 0.0579214282 0.0069495244 1.4951560000 89773760 95654128 1787650048 -1.0188115835 0.0508066788 0.8632289171 186 7.4000000000 0.0110133253 0.0257120059 0.0579214282 0.0069379344 2.1456590000 89776534 95654128 1784602624 -1.0177276134 0.0480690897 0.8793559670 187 7.4400000000 0.0124612805 0.0256411464 0.0579214282 0.0069324024 2.1204840000 89945584 95654128 1785999360 -1.0135282278 0.0474455841 0.8859451413 188 7.4800000000 0.0107580777 0.0255619812 0.0579214282 0.0069350121 1.8273910000 89947278 95654128 1788030976 -1.0131491423 0.0511175133 0.9030993581 189 7.5200000000 0.0118134227 0.0254892375 0.0579214282 0.0069185706 1.6526920000 89948972 95654128 1784729600 -1.0124279261 0.0573944002 0.9220989943 190 7.5600000000 0.0123682488 0.0254201796 0.0579214282 0.0069089632 1.8134880000 89949406 95654128 1786126336 -1.0116258860 0.0583597533 0.9389329553 191 7.6000000000 0.0098266238 0.0253385380 0.0579214282 0.0068994495 1.7742540000 89951100 95654128 1788166144 -1.0099155903 0.0561986342 0.9540011287 192 7.6400000000 0.0095348731 0.0252562272 0.0579214282 0.0068896308 2.0236790000 89952810 95654128 1784229888 -1.0081065893 0.0619675517 0.9699847698 193 7.6800000000 0.0101582939 0.0251779996 0.0579214282 0.0068914007 1.7672500000 89953244 95654128 1785626624 -1.0064060688 0.0621444248 0.9864832759 194 7.7200000000 0.0110296551 0.0251050700 0.0579214282 0.0068893745 1.9085210000 89954938 95654128 1787531264 -1.0068050623 0.0584138259 1.0018631220 195 7.7600000000 0.0084971255 0.0250199010 0.0579214282 0.0068970800 1.9924630000 89956632 95654128 1784737792 -1.0049296618 0.0570787936 1.0170031786 196 7.8000000000 0.0071734795 0.0249288479 0.0579214282 0.0069378500 2.0872900000 89957066 95654128 1786007552 -1.0035095215 0.0610969439 1.0361272097 197 7.8400000000 0.0082898913 0.0248443862 0.0579214282 0.0069595152 1.4522130000 89958760 95654128 1787904000 -1.0010234118 0.0639299080 1.0458024740 198 7.8800000000 0.0082474928 0.0247605635 0.0579214282 0.0069816574 1.4088730000 89960470 95654128 1784729600 -0.9991974235 0.0647572950 1.0614547729 199 7.9200000000 0.0090149045 0.0246814396 0.0579214282 0.0069719000 1.6253310000 89960904 95654128 1785999360 -0.9981929064 0.0682603717 1.0773441792 200 7.9600000000 0.0102082435 0.0246090736 0.0579214282 0.0069592566 2.0339720000 89962598 95654128 1788030976 -0.9982877374 0.0670557767 1.0900982618 201 8.0000000000 0.0095738703 0.0245342716 0.0579214282 0.0069750420 1.6942550000 89964292 95654128 1784729600 -0.9975169897 0.0686830878 1.1101659536 202 8.0400000000 0.0093615195 0.0244591589 0.0579214282 0.0069889621 1.7705380000 89964726 95654128 1785999360 -0.9943914413 0.0688900948 1.1203366518 203 8.0800000000 0.0115492241 0.0243955632 0.0579214282 0.0070052796 0.6046160000 89966420 95654128 1787834368 -0.9915747046 0.0715257078 1.1354516745 204 8.1200000000 0.0103411106 0.0243266688 0.0579214282 0.0069964821 0.7486650000 89968114 95654128 1784868864 -0.9898204803 0.0707107484 1.1492084265 205 8.1600000000 0.0111604100 0.0242624432 0.0579214282 0.0069861072 0.6912980000 89968548 95654128 1786138624 -0.9880528450 0.0717621371 1.1616055965 206 8.1999999990 0.0123151755 0.0242044467 0.0579214282 0.0069780029 0.8040160000 89970242 95654128 1788170240 -0.9853022099 0.0709643960 1.1731170416 207 8.2400000000 0.0136678275 0.0241535452 0.0579214282 0.0069685600 0.6958680000 89971936 95654128 1784393728 -0.9810675979 0.0735692084 1.1849937439 208 8.2799999990 0.0155465659 0.0241121655 0.0579214282 0.0069542685 0.8061550000 89972370 95654128 1785630720 -0.9771829844 0.0766329691 1.1960911751 209 8.3200000000 0.0147991162 0.0240676054 0.0579214282 0.0069501430 0.8552090000 89974064 95654128 1787535360 -0.9722246528 0.0796230733 1.2104538679 210 8.3599999990 0.0104081966 0.0240025606 0.0579214282 0.0069775955 0.6777400000 89975758 95654128 1784373248 -0.9661408663 0.0778403729 1.2251715660 211 8.4000000000 0.0102053937 0.0239371712 0.0579214282 0.0070020759 0.8895640000 89976192 95654128 1785769984 -0.9631754160 0.0767210796 1.2407513857 212 8.4399999990 0.0115072476 0.0238785395 0.0579214282 0.0069864595 1.3497040000 89977886 95654128 1787662336 -0.9552294016 0.0799506530 1.2503455877 213 8.4800000000 0.0127950152 0.0238265042 0.0579214282 0.0069856293 1.8448740000 89979580 95654128 1784614912 -0.9491125941 0.0853028074 1.2645062208 214 8.5200000000 0.0148527371 0.0237845707 0.0579214282 0.0070624569 1.7283460000 89980014 95654128 1786011648 -0.9421975017 0.0894270316 1.2783499956 215 8.5600000000 0.0141181471 0.0237396106 0.0579214282 0.0070695078 2.0518640000 89981708 95654128 1787916288 -0.9346227646 0.0874540061 1.2881797552 216 8.6000000000 0.0187940206 0.0237167143 0.0579214282 0.0070568874 1.9366170000 89983402 95654128 1784750080 -0.9292382598 0.0944767073 1.2976845503 217 8.6400000000 0.0197659656 0.0236985081 0.0579214282 0.0070907348 1.2205180000 89983836 95654128 1786146816 -0.9205182195 0.1001397967 1.3168492317 218 8.6800000000 0.0181042477 0.0236728464 0.0579214282 0.0071419538 1.5423230000 89985530 95654128 1787924480 -0.9114444852 0.0986407325 1.3272169828 219 8.7200000000 0.0188094396 0.0236506390 0.0579214282 0.0071430476 1.8200220000 89987224 95654128 1784623104 -0.9022754431 0.1006932184 1.3356475830 220 8.7600000000 0.0213683024 0.0236402648 0.0579214282 0.0071470804 2.2483730000 89987658 95654128 1786011648 -0.8929226995 0.1074595600 1.3462412357 221 8.8000000000 0.0243515149 0.0236434831 0.0579214282 0.0071971194 1.9806320000 89990100 95654128 1788170240 -0.8839410543 0.1126336083 1.3596363068 222 8.8400000000 0.0260448959 0.0236543003 0.0579214282 0.0072019923 1.8341420000 90160414 95654128 1784360960 -0.8748844266 0.1151840910 1.3718118668 223 8.8800000000 0.0269400757 0.0236690347 0.0579214282 0.0072050812 1.7280290000 90160848 95654128 1785630720 -0.8650854230 0.1184052750 1.3804613352 224 8.9200000000 0.0269307867 0.0236835961 0.0579214282 0.0072114329 1.7353240000 90162542 95654128 1787662336 -0.8549585938 0.1206643358 1.3908132315 225 8.9600000000 0.0266879126 0.0236969486 0.0579214282 0.0072073771 1.8286280000 90164236 95654128 1784614912 -0.8444885015 0.1229560077 1.3987947702 226 9.0000000000 0.0257262010 0.0237059276 0.0579214282 0.0071927638 1.9446520000 90164670 95654128 1786019840 -0.8337552547 0.1266225576 1.4115000963 227 9.0400000000 0.0260899160 0.0237164297 0.0579214282 0.0071782943 1.3175050000 90166380 95654128 1787924480 -0.8219773173 0.1328319609 1.4200940132 228 9.0800000000 0.0257655568 0.0237254171 0.0579214282 0.0071955408 1.6141490000 90168074 95654128 1784750080 -0.8116317391 0.1365596652 1.4323554039 229 9.1200000000 0.0258847978 0.0237348468 0.0579214282 0.0072433332 0.8285180000 90169804 95654128 1786011648 -0.8004600406 0.1410366446 1.4397077560 230 9.1600000000 0.0257579200 0.0237436427 0.0579214282 0.0073540725 0.7589020000 90340098 95654128 1787789312 -0.7907637358 0.1441377848 1.4466080666 231 9.2000000000 0.0267141908 0.0237565022 0.0579214282 0.0075538884 0.8256080000 90341792 95654128 1784868864 -0.7811719775 0.1454791129 1.4521679878 232 9.2400000000 0.0261904411 0.0237669934 0.0579214282 0.0077093475 0.7848120000 90342226 95654128 1786138624 -0.7710043192 0.1484470367 1.4608199596 233 9.2800000000 0.0260454081 0.0237767720 0.0579214282 0.0078499716 0.8725190000 90343920 95654128 1788170240 -0.7613379955 0.1517378390 1.4688830376 234 9.3200000000 0.0260315407 0.0237864077 0.0579214282 0.0079543036 1.4680690000 90345614 95654128 1784487936 -0.7516967654 0.1557824612 1.4765468836 235 9.3600000000 0.0237452295 0.0237862325 0.0579214282 0.0080323237 1.6908570000 90346996 95654128 1785757696 -0.7414916754 0.1573003381 1.4857368469 236 9.4000000000 0.0242026839 0.0237879971 0.0579214282 0.0080887485 1.5511830000 90517314 95654128 1787662336 -0.7316058278 0.1608708799 1.4939966202 237 9.4400000000 0.0226259306 0.0237830939 0.0579214282 0.0081168165 2.0331580000 90519008 95654128 1784614912 -0.7210558653 0.1641008258 1.5015947819 238 9.4800000000 0.0223214366 0.0237769525 0.0579214282 0.0081403130 2.3441290000 90519442 95654128 1786146816 -0.7097152472 0.1702447832 1.5097526312 239 9.5200000000 0.0233071689 0.0237749868 0.0579214282 0.0081818423 1.1962420000 90521136 95654128 1787797504 -0.6995062828 0.1764553189 1.5171899796 240 9.5600000000 0.0225673523 0.0237699550 0.0579214282 0.0082409351 1.8364180000 90522830 95654128 1784496128 -0.6887821555 0.1810045391 1.5265324116 241 9.6000000000 0.0232643727 0.0237678572 0.0579214282 0.0082905657 2.3519800000 90523264 95654128 1785892864 -0.6793721914 0.1838463396 1.5379115343 242 9.6400000000 0.0235932339 0.0237671356 0.0579214282 0.0083087358 0.9440480000 90524958 95654128 1787797504 -0.6700292230 0.1871881783 1.5491765738 243 9.6800000000 0.0232091378 0.0237648393 0.0579214282 0.0083197652 0.9672430000 90526652 95654128 1784868864 -0.6583247781 0.1929699033 1.5556665659 244 9.7200000000 0.0212616231 0.0237545802 0.0579214282 0.0083627614 1.7045530000 90527086 95654128 1786138624 -0.6461988091 0.1976563185 1.5640242100 245 9.7600000000 0.0234684609 0.0237534124 0.0579214282 0.0084203442 1.5930290000 90529720 95654128 1787916288 -0.6372632980 0.1994018555 1.5652781725 246 9.8000000000 0.0216557048 0.0237448851 0.0579214282 0.0084429255 1.6940810000 90700054 95654128 1784868864 -0.6260151863 0.2014349401 1.5759352446 247 9.8400000000 0.0222790204 0.0237389505 0.0579214282 0.0084491019 1.3139890000 90700472 95654128 1786138624 -0.6164439321 0.2034046501 1.5877830982 248 9.8800000000 0.0225735083 0.0237342511 0.0579214282 0.0084350443 2.1644200000 90702166 95654128 1785503744 -0.6075889468 0.2054803371 1.5969365835 249 9.9200000000 0.0218698289 0.0237267635 0.0579214282 0.0084193337 1.7724270000 90703860 95654128 1786900480 -0.5972439051 0.2067947090 1.6036705971 250 9.9600000000 0.0191836711 0.0237085911 0.0579214282 0.0084031179 0.9045920000 90704294 95654128 1784741888 -0.5859820247 0.2071330547 1.6140077114 251 10.0000000000 0.0178366173 0.0236851968 0.0579214282 0.0083872762 0.8003810000 90705988 95654128 1786011648 -0.5740854144 0.2091665417 1.6218731403 252 10.0400000000 0.0158494450 0.0236541025 0.0579214282 0.0083726765 0.6518890000 90707682 95654128 1788043264 -0.5641298890 0.2068720162 1.6330674887 253 10.0800000000 0.0173047241 0.0236290062 0.0579214282 0.0083575120 0.7256860000 90708116 95654128 1784741888 -0.5577459335 0.2040374428 1.6412034035 254 10.1200000000 0.0195605587 0.0236129886 0.0579214282 0.0083738148 0.8761330000 90709810 95654128 1786011648 -0.5492286086 0.2107834369 1.6517235041 255 10.1600000000 0.0210954733 0.0236031160 0.0579214282 0.0083887925 0.7495650000 90711504 95654128 1787916288 -0.5387838483 0.2193040401 1.6607465744 256 10.2000000000 0.0220482964 0.0235970425 0.0579214282 0.0083755950 0.7815560000 90711938 95654128 1784631296 -0.5283293724 0.2247700542 1.6688028574 257 10.2400000000 0.0218356140 0.0235901887 0.0579214282 0.0083616033 0.7741000000 90734112 95654128 1786011648 -0.5191927552 0.2235572189 1.6762878895 258 10.2800000000 0.0224390086 0.0235857268 0.0579214282 0.0083454099 1.0057700000 90777790 95654128 1787916288 -0.5093075037 0.2296508849 1.6862938404 259 10.3200000000 0.0231455863 0.0235840274 0.0579214282 0.0083409250 1.3541020000 90779464 95654128 1784614912 -0.4994071424 0.2341977060 1.6931440830 260 10.3600000000 0.0232536644 0.0235827568 0.0579214282 0.0083474656 1.9005160000 90949802 95654128 1786011648 -0.4893217981 0.2364068776 1.7027968168 261 10.4000000000 0.0218226183 0.0235760129 0.0579214282 0.0083463825 1.1943680000 90951496 95654128 1785630720 -0.4793476164 0.2346778661 1.7103972435 262 10.4400000000 0.0221508201 0.0235705733 0.0579214282 0.0083327603 1.9333350000 90951930 95654128 1786900480 -0.4698924124 0.2346398681 1.7155033350 263 10.4800000000 0.0216903724 0.0235634242 0.0579214282 0.0083187800 1.5289320000 90953624 95654128 1784614912 -0.4592153132 0.2348984182 1.7198629379 264 10.5200000000 0.0212414619 0.0235546289 0.0579214282 0.0083080695 1.6873260000 90955318 95654128 1786019840 -0.4487540722 0.2341920435 1.7260868549 265 10.5600000000 0.0233312789 0.0235537861 0.0579214282 0.0082927953 1.9671920000 90955736 95654128 1787813888 -0.4385961890 0.2385801524 1.7338666916 266 10.6000000000 0.0221111067 0.0235483625 0.0579214282 0.0082807533 1.7757010000 90957430 95654128 1784750080 -0.4259497821 0.2395879328 1.7375667095 267 10.6400000000 0.0229922924 0.0235462798 0.0579214282 0.0082760600 1.0173240000 90959124 95654128 1786019840 -0.4151247442 0.2390449643 1.7405565977 268 10.6800000000 0.0220820922 0.0235408164 0.0579214282 0.0082708706 0.8055710000 90959558 95654128 1787797504 -0.4038037658 0.2378978580 1.7480330467 269 10.7200000000 0.0230679121 0.0235390584 0.0579214282 0.0082584951 0.7095420000 90961252 95654128 1784635392 -0.3921903372 0.2382534444 1.7490246296 270 10.7600000000 0.0228107311 0.0235363609 0.0579214282 0.0082505353 0.9619330000 90962946 95654128 1786019840 -0.3675850928 0.2425645888 1.7604314089 271 10.8000000000 0.0224034991 0.0235321806 0.0579214282 0.0082671096 1.5733180000 90963380 95654128 1787797504 -0.3529522717 0.2458042651 1.7633721828 272 10.8400000000 0.0213398580 0.0235241206 0.0579214282 0.0083303727 1.9689180000 90965074 95654128 1784741888 -0.3405998349 0.2429685593 1.7672864199 273 10.8800000000 0.0212301314 0.0235157177 0.0579214282 0.0083390386 1.4215630000 90966768 95654128 1786138624 -0.3285708129 0.2438706011 1.7735836506 274 10.9200000000 0.0208036732 0.0235058197 0.0579214282 0.0083455682 0.8831760000 90967202 95654128 1788043264 -0.3150394559 0.2449855804 1.7780389786 275 10.9600000000 0.0200604610 0.0234932912 0.0579214282 0.0083481277 0.7142310000 90968896 95654128 1784741888 -0.3017296493 0.2437627614 1.7793353796 276 11.0000000000 0.0192374606 0.0234778715 0.0579214282 0.0083443760 0.9525700000 90970590 95654128 1786138624 -0.2880196273 0.2446673810 1.7830364704 277 11.0400000000 0.0196607728 0.0234640913 0.0579214282 0.0083497873 1.7392670000 90971024 95654128 1788043264 -0.2744980752 0.2468149513 1.7867724895 278 11.0800000000 0.0192460846 0.0234489187 0.0579214282 0.0083559489 1.9124240000 90972718 95654128 1784614912 -0.2609165311 0.2482227683 1.7906779051 279 11.1200000000 0.0200554840 0.0234367558 0.0579214282 0.0083662658 1.8761750000 90974412 95654128 1786011648 -0.2479268014 0.2504865825 1.7950421572 280 11.1600000000 0.0210315362 0.0234281657 0.0579214282 0.0083732125 1.0562550000 90974846 95654128 1787932672 -0.2342104316 0.2537491322 1.7974919081 281 11.2000000000 0.0207625609 0.0234186796 0.0579214282 0.0083788130 0.9695960000 90976540 95654128 1784741888 -0.2205415517 0.2546885610 1.8002958298 282 11.2400000000 0.0201240201 0.0234069964 0.0579214282 0.0083743629 1.6258000000 90979498 95654128 1786011648 -0.2085063159 0.2534933984 1.8062243462 283 11.2800000000 0.0208807569 0.0233980698 0.0579214282 0.0083597325 2.2229420000 91148576 95654128 1788043264 -0.1968604922 0.2553496659 1.8088343143 284 11.3200000000 0.0206883028 0.0233885283 0.0579214282 0.0083483497 0.9598780000 91150270 95654128 1784774656 -0.1843769103 0.2569415867 1.8136308193 285 11.3600000000 0.0210846961 0.0233804447 0.0579214282 0.0083453848 0.9343880000 91151980 95654128 1786011648 -0.1728685051 0.2580144107 1.8166133165 286 11.4000000000 0.0227111988 0.0233781047 0.0579214282 0.0083373885 0.8932300000 91152414 95654128 1788043264 -0.1634000391 0.2591908872 1.8202078342 287 11.4400000000 0.0220124684 0.0233733464 0.0579214282 0.0083228436 0.8472000000 91154108 95654128 1784741888 -0.1534662694 0.2576713860 1.8232558966 288 11.4800000000 0.0223166067 0.0233696771 0.0579214282 0.0083092224 0.8797820000 91155802 95654128 1786011648 -0.1454109401 0.2579282522 1.8284803629 289 11.5200000000 0.0230784807 0.0233686695 0.0579214282 0.0082958106 0.7582840000 91156236 95654128 1788043264 -0.1377053708 0.2582012713 1.8350570202 290 11.5600000000 0.0223473273 0.0233651477 0.0579214282 0.0082876170 0.7500530000 91157930 95654128 1784741888 -0.1294296682 0.2569612265 1.8397431374 291 11.6000000000 0.0232015699 0.0233645855 0.0579214282 0.0082776184 0.9100220000 91159624 95654128 1786028032 -0.1223912388 0.2553580701 1.8444873095 292 11.6400000000 0.0230302569 0.0233634406 0.0579214282 0.0082650014 0.7292660000 91160058 95654128 1788170240 -0.1147953346 0.2552359402 1.8498066664 293 11.6800000000 0.0244445223 0.0233671303 0.0579214282 0.0082513312 0.6484300000 91161768 95654128 1784242176 -0.1082524434 0.2572355270 1.8564246893 294 11.7200000000 0.0239026025 0.0233689516 0.0579214282 0.0082387075 0.8566690000 91163462 95654128 1785511936 -0.1026393026 0.2548060715 1.8634872437 295 11.7600000000 0.0247581638 0.0233736608 0.0579214282 0.0082303362 1.1011610000 91163896 95654128 1787289600 -0.0973805487 0.2562013268 1.8709396124 296 11.8000000000 0.0235045962 0.0233741032 0.0579214282 0.0082215694 1.7617060000 91165590 95654128 1784623104 -0.0908034816 0.2557905614 1.8783795834 297 11.8400000000 0.0233494341 0.0233740201 0.0579214282 0.0082140152 1.5795910000 91167284 95654128 1786019840 -0.0852290392 0.2555724978 1.8855577707 298 11.8800000000 0.0229252446 0.0233725141 0.0579214282 0.0082077825 1.7599060000 91167718 95654128 1787670528 -0.0806083009 0.2542114556 1.8939430714 299 11.9200000000 0.0230144318 0.0233713165 0.0579214282 0.0081987081 1.9180090000 91169412 95654128 1784614912 -0.0758153722 0.2552866936 1.9038636684 300 11.9600000000 0.0229752064 0.0233699962 0.0579214282 0.0081863732 1.5638780000 91171106 95654128 1786011648 -0.0704574510 0.2551828027 1.9102672338 301 12.0000000000 0.0238935482 0.0233717356 0.0579214282 0.0081727954 1.4330650000 91171556 95654128 1787916288 -0.0671335310 0.2563236952 1.9206035137 302 12.0400000000 0.0249711256 0.0233770315 0.0579214282 0.0081612831 1.6017420000 91173348 95654128 1784614912 -0.0635858923 0.2566105425 1.9292240143 303 12.0800000000 0.0251333341 0.0233828279 0.0579214282 0.0081551095 1.6882950000 91175042 95654128 1786011648 -0.0597501583 0.2574878335 1.9401847124 304 12.1200000000 0.0255919434 0.0233900947 0.0579214282 0.0081511300 1.5119080000 91175476 95654128 1787916288 -0.0562566631 0.2581177056 1.9505712986 305 12.1600000000 0.0269242302 0.0234016821 0.0579214282 0.0081492088 1.2278510000 91177310 95654128 1784741888 -0.0530449897 0.2591179609 1.9609657526 306 12.2000000000 0.0278080627 0.0234160820 0.0579214282 0.0081386478 0.6473530000 91177744 95654128 1786015744 -0.0505166315 0.2598167062 1.9733163118 307 12.2400000000 0.0281411316 0.0234314731 0.0579214282 0.0081404139 0.6920980000 91179438 95654128 1787936768 -0.0474809110 0.2603839040 1.9840626717 308 12.2800000000 0.0281498879 0.0234467926 0.0579214282 0.0081453822 0.6460340000 91181132 95654128 1784762368 -0.0448711626 0.2589284778 1.9934633970 309 12.3200000000 0.0286956318 0.0234637791 0.0579214282 0.0081574197 0.8707180000 91181566 95654128 1786015744 -0.0431581698 0.2592493892 2.0042986870 310 12.3600000000 0.0289843492 0.0234815874 0.0579214282 0.0081770069 0.8790400000 91183260 95654128 1788047360 -0.0418293253 0.2590121329 2.0164403915 311 12.4000000000 0.0288051162 0.0234987049 0.0579214282 0.0081858082 0.9894500000 91185094 95654128 1784745984 -0.0402335636 0.2594797015 2.0281786919 312 12.4400000000 0.0294168405 0.0235176733 0.0579214282 0.0082229807 0.7192010000 91185528 95654128 1786015744 -0.0389642529 0.2583525777 2.0513169765 313 12.4800000000 0.0296117272 0.0235371431 0.0579214282 0.0082173527 0.6995320000 91187222 95654128 1788047360 -0.0384669043 0.2584865391 2.0621240139 314 12.5200000000 0.0299894754 0.0235576919 0.0579214282 0.0082104084 0.8906090000 91188916 95654128 1784745984 -0.0383672602 0.2583246231 2.0749330521 315 12.5600000000 0.0297002997 0.0235771922 0.0579214282 0.0082070538 0.8585220000 91189350 95654128 1786015744 -0.0383718349 0.2585912943 2.0879216194 316 12.6000000000 0.0291886739 0.0235949501 0.0579214282 0.0081964086 0.7682660000 91191044 95654128 1787809792 -0.0383993387 0.2575074732 2.0999131203 317 12.6400000000 0.0284204111 0.0236101724 0.0579214282 0.0081839622 0.7361240000 91193978 95654128 1784745984 -0.0384137630 0.2566980124 2.1127161980 318 12.6800000000 0.0276834555 0.0236229814 0.0579214282 0.0081718974 0.7909160000 91363056 95654128 1786032128 -0.0385975577 0.2560142577 2.1249649525 319 12.7200000000 0.0270833950 0.0236338291 0.0579214282 0.0081594833 0.8712460000 91364782 95654128 1788301312 -0.0389791280 0.2551557720 2.1343176365 320 12.7600000000 0.0265790354 0.0236430329 0.0579214282 0.0081471745 0.9259080000 91366476 95654128 1784500224 -0.0401753336 0.2542533278 2.1444830894 321 12.8000000000 0.0264800191 0.0236518709 0.0579214282 0.0081370720 0.8344920000 91366910 95654128 1785769984 -0.0423211381 0.2538166642 2.1562931538 322 12.8400000000 0.0252777543 0.0236569202 0.0579214282 0.0081270458 0.7699690000 91368620 95654128 1787420672 -0.0440554246 0.2521619201 2.1666712761 323 12.8800000000 0.0249983072 0.0236610731 0.0579214282 0.0081225937 0.6874910000 91369194 95654128 1784500224 -0.0460213944 0.2517068684 2.1775822639 324 12.9200000000 0.0243053287 0.0236630615 0.0579214282 0.0081134050 0.7441050000 91372164 95654128 1785913344 -0.0481334329 0.2500334978 2.1885418892 325 12.9600000000 0.0245680809 0.0236658462 0.0579214282 0.0081026820 0.8403360000 91542498 95654128 1787801600 -0.0494626500 0.2520261705 2.2001974583 326 13.0000000000 0.0243412945 0.0236679181 0.0579214282 0.0080922707 0.8368580000 91542948 95654128 1784627200 -0.0506897159 0.2523236275 2.2102911472 327 13.0400000000 0.0258763563 0.0236746718 0.0579214282 0.0080876833 0.7949670000 91544642 95654128 1786023936 -0.0525353588 0.2545717061 2.2238526344 328 13.0800000000 0.0280384142 0.0236879759 0.0579214282 0.0080804183 0.8712590000 91546452 95654128 1787928576 -0.0529730432 0.2583493590 2.2351856232 329 13.1200000000 0.0291503686 0.0237045789 0.0579214282 0.0080713672 0.8166140000 91547258 95654128 1784745984 -0.0543431491 0.2615772188 2.2440524101 330 13.1600000000 0.0303760376 0.0237247954 0.0579214282 0.0080612149 0.8202890000 91548952 95654128 1786032128 -0.0567071214 0.2641208768 2.2506723404 331 13.2000000000 0.0325143375 0.0237513499 0.0579214282 0.0080514863 0.8816310000 91550762 95654128 1787920384 -0.0596503541 0.2675204575 2.2587928772 332 13.2400000000 0.0318873152 0.0237758558 0.0579214282 0.0080429445 0.8102820000 91551196 95654128 1784619008 -0.0609084256 0.2681719661 2.2660102844 333 13.2800000000 0.0328015983 0.0238029602 0.0579214282 0.0080331618 0.8127030000 91553774 95654128 1786015744 -0.0640494898 0.2696861923 2.2718002796 334 13.3200000000 0.0321449265 0.0238279361 0.0579214282 0.0080213731 0.8298230000 91557044 95654128 1788047360 -0.0661729574 0.2691572011 2.2767541409 335 13.3600000000 0.0323761106 0.0238534531 0.0579214282 0.0080105540 0.7812860000 91726366 95654128 1784745984 -0.0681162551 0.2705676556 2.2827129364 336 13.4000000000 0.0338207670 0.0238831177 0.0579214282 0.0079993596 0.8567010000 91728060 95654128 1786032128 -0.0703273267 0.2733802497 2.2874641418 337 13.4400000000 0.0320464596 0.0239073413 0.0579214282 0.0079928991 0.8369500000 91729754 95654128 1788047360 -0.0711326376 0.2738552094 2.2936613560 338 13.4800000000 0.0343289301 0.0239381744 0.0579214282 0.0079951303 0.9696720000 91730304 95654128 1784745984 -0.0737408176 0.2765815854 2.2958831787 339 13.5200000000 0.0367875323 0.0239760781 0.0579214282 0.0080266403 0.8074550000 91731998 95654128 1786015744 -0.0782859772 0.2783490121 2.3020782471 340 13.5600000000 0.0376351774 0.0240162519 0.0579214282 0.0080315879 0.9730340000 91733924 95654128 1788047360 -0.0823154524 0.2789124250 2.3089239597 341 13.6000000000 0.0373655818 0.0240553995 0.0579214282 0.0080293052 0.8064420000 91736274 95654128 1784745984 -0.0842106417 0.2792941034 2.3138263226 342 13.6400000000 0.0370913260 0.0240935162 0.0579214282 0.0080212793 0.8892320000 91906568 95654128 1786015744 -0.0858894363 0.2795583606 2.3190040588 343 13.6800000000 0.0387693197 0.0241363028 0.0579214282 0.0080116381 0.8295470000 91907118 95654128 1788047360 -0.0881949291 0.2815168202 2.3225555420 344 13.7200000000 0.0387423970 0.0241787624 0.0579214282 0.0080009613 0.7018820000 91908812 95654128 1784762368 -0.0892064795 0.2829162776 2.3272516727 345 13.7600000000 0.0384929329 0.0242202528 0.0579214282 0.0079934715 0.9177170000 91910622 95654128 1786015744 -0.0911818147 0.2824205160 2.3329110146 346 13.8000000000 0.0376712345 0.0242591284 0.0579214282 0.0079880202 0.8600500000 91911056 95654128 1787920384 -0.0923031643 0.2816430926 2.3379793167 347 13.8400000000 0.0362595059 0.0242937116 0.0579214282 0.0079781217 0.8859680000 91914862 95654128 1784745984 -0.0935405046 0.2783293724 2.3403215408 348 13.8800000000 0.0351224989 0.0243248288 0.0579214282 0.0079685402 0.8582490000 92085220 95654128 1786015744 -0.0917393491 0.2794216871 2.3430097103 349 13.9200000000 0.0332802013 0.0243504889 0.0579214282 0.0079624421 0.7294730000 92085770 95654128 1787793408 -0.0913330019 0.2782481313 2.3487761021 350 13.9600000000 0.0306753926 0.0243685601 0.0579214282 0.0079644330 0.7624740000 92087888 95654128 1784647680 -0.0896724388 0.2759153247 2.3573000431 351 14.0000000000 0.0299613830 0.0243844941 0.0579214282 0.0079536848 0.9603120000 92089582 95654128 1786015744 -0.0884928405 0.2734820247 2.3580925465 352 14.0400000000 0.0285390373 0.0243962967 0.0579214282 0.0079454381 1.3189790000 92090016 95654128 1787920384 -0.0893965214 0.2703707218 2.3629045486 353 14.0800000000 0.0277466886 0.0244057879 0.0579214282 0.0079343530 1.7505940000 92091710 95654128 1784745984 -0.0892228037 0.2688081264 2.3674812317 354 14.1200000000 0.0277552474 0.0244152497 0.0579214282 0.0079233623 2.1990570000 92093520 95654128 1786150912 -0.0891706645 0.2687677741 2.3720431328 355 14.1600000000 0.0271485727 0.0244229492 0.0579214282 0.0079129915 1.4762620000 92093954 95654128 1787928576 -0.0889965296 0.2675122023 2.3772411346 356 14.2000000000 0.0272457767 0.0244308785 0.0579214282 0.0079042816 1.5808960000 92095648 95654128 1784627200 -0.0880521908 0.2673208416 2.3811807632 357 14.2400000000 0.0274309050 0.0244392819 0.0579214282 0.0078961753 1.1081810000 92097342 95654128 1786023936 -0.0887423605 0.2682860196 2.3877186775 358 14.2800000000 0.0277840998 0.0244486250 0.0579214282 0.0078861833 1.6941460000 92097892 95654128 1787920384 -0.0882238299 0.2667849064 2.3918247223 359 14.3200000000 0.0275612641 0.0244572953 0.0579214282 0.0078754976 2.2799170000 92099586 95654128 1784619008 -0.0895799696 0.2646371424 2.3979415894 360 14.3600000000 0.0281866957 0.0244676547 0.0579214282 0.0078670698 1.5235300000 92101280 95654128 1786015744 -0.0906863585 0.2628546357 2.4035797119 361 14.4000000000 0.0279511288 0.0244773042 0.0579214282 0.0078615526 1.4389770000 92101714 95654128 1787936768 -0.0913189575 0.2626459599 2.4108035564 362 14.4400000000 0.0274847168 0.0244856120 0.0579214282 0.0078553517 1.8699420000 92103408 95654128 1784745984 -0.0916862637 0.2624106407 2.4180901051 363 14.4800000000 0.0282220244 0.0244959052 0.0579214282 0.0078457867 0.9704760000 92105102 95654128 1786142720 -0.0919650868 0.2629565001 2.4242813587 364 14.5200000000 0.0286128707 0.0245072155 0.0579214282 0.0078371620 0.7291890000 92107664 95654128 1788047360 -0.0939925909 0.2624403834 2.4327220917 365 14.5600000000 0.0281221475 0.0245171194 0.0579214282 0.0078266716 0.8117570000 92278026 95654128 1784762368 -0.0948700532 0.2608735561 2.4404449463 366 14.6000000000 0.0282905959 0.0245274295 0.0579214282 0.0078179646 0.8663840000 92279720 95654128 1786015744 -0.0965707749 0.2616136074 2.4499766827 367 14.6400000000 0.0291331392 0.0245399791 0.0579214282 0.0078074527 0.8118930000 92280154 95654128 1788047360 -0.0974701792 0.2620701492 2.4565932751 368 14.6800000000 0.0293824431 0.0245531380 0.0579214282 0.0077984212 1.1808150000 92281988 95654128 1784745984 -0.0981967747 0.2624064684 2.4644227028 369 14.7200000000 0.0298699029 0.0245675465 0.0579214282 0.0078010001 1.9505860000 92283666 95654128 1786015744 -0.1004855484 0.2609861195 2.4724287987 370 14.7600000000 0.0303767268 0.0245832470 0.0579214282 0.0077929675 1.6031770000 92284100 95654128 1788047360 -0.1024461612 0.2619541883 2.4828894138 371 14.8000000000 0.0308626518 0.0246001726 0.0579214282 0.0077940969 1.7671690000 92285794 95654128 1784745984 -0.1039380804 0.2583480477 2.4896261692 372 14.8400000000 0.0321004465 0.0246203347 0.0579214282 0.0077897108 1.7885300000 92287488 95654128 1786015744 -0.1061205119 0.2564003468 2.4972493649 373 14.8800000000 0.0330772847 0.0246430075 0.0579214282 0.0077918519 1.6186500000 92287922 95654128 1787920384 -0.1078930721 0.2542037070 2.5052590370 374 14.9200000000 0.0340153389 0.0246680672 0.0579214282 0.0077893997 1.4657520000 92289616 95654128 1784745984 -0.1091717780 0.2529915869 2.5126883984 375 14.9600000000 0.0348244347 0.0246951508 0.0579214282 0.0077961313 0.8719290000 92290190 95654128 1786032128 -0.1099912748 0.2522744238 2.5201950073 376 15.0000000000 0.0357494019 0.0247245504 0.0579214282 0.0077929330 0.7537220000 92291884 95654128 1787793408 -0.1100206673 0.2534183264 2.5277147293 377 15.0400000000 0.0364256203 0.0247555877 0.0579214282 0.0077945202 0.9041280000 92293594 95654128 1784619008 -0.1082896888 0.2540513575 2.5402908325 378 15.0800000000 0.0366014838 0.0247869261 0.0579214282 0.0077854570 0.9488560000 92294028 95654128 1786015744 -0.1069018617 0.2547398210 2.5478062630 379 15.1200000000 0.0361364931 0.0248168722 0.0579214282 0.0077758233 0.7312690000 92295722 95654128 1787928576 -0.1043618172 0.2550685108 2.5528471470 380 15.1600000000 0.0366985165 0.0248481397 0.0579214282 0.0077679072 0.7657480000 92297416 95654128 1784627200 -0.1017293632 0.2558117211 2.5567588806 381 15.2000000000 0.0371479988 0.0248804228 0.0579214282 0.0077584125 0.7332410000 92297850 95654128 1786040320 -0.0996697322 0.2566797137 2.5613348484 382 15.2400000000 0.0365764201 0.0249110406 0.0579214282 0.0077502298 0.7675580000 92299684 95654128 1787801600 -0.0969928429 0.2572954297 2.5665693283 383 15.2800000000 0.0367367491 0.0249419171 0.0579214282 0.0077421347 0.8450570000 92301494 95654128 1784754176 -0.0946073160 0.2581124902 2.5713684559 384 15.3200000000 0.0365917757 0.0249722552 0.0579214282 0.0077326617 0.7520920000 92301928 95654128 1786150912 -0.0916530937 0.2576312721 2.5751457214 385 15.3600000000 0.0370770991 0.0250036964 0.0579214282 0.0077251327 0.7728490000 92303622 95654128 1788063744 -0.0897240415 0.2554307878 2.5779538155 386 15.4000000000 0.0380219668 0.0250374225 0.0579214282 0.0077275953 0.7560760000 92305316 95654128 1784647680 -0.0882004797 0.2538522482 2.5823590755 387 15.4400000000 0.0406596698 0.0250777901 0.0579214282 0.0077516160 0.7859800000 92305750 95654128 1786015744 -0.0876946598 0.2533828914 2.5884222984 388 15.4800000000 0.0401613005 0.0251166651 0.0579214282 0.0077435434 0.7890590000 92307584 95654128 1787920384 -0.0846879184 0.2563080788 2.5919523239 389 15.5200000000 0.0402971283 0.0251556894 0.0579214282 0.0077365991 0.7693850000 92309278 95654128 1784745984 -0.0823939517 0.2576645911 2.5937871933 390 15.5600000000 0.0393472053 0.0251920779 0.0579214282 0.0077277762 0.7086800000 92309712 95654128 1786032128 -0.0772881210 0.2599018514 2.5929269791 391 15.6000000000 0.0369420908 0.0252221291 0.0579214282 0.0077291316 0.7499280000 92311406 95654128 1787920384 -0.0713726506 0.2621158063 2.5914573669 392 15.6400000000 0.0377631001 0.0252541214 0.0579214282 0.0077288075 0.7512300000 92313100 95654128 1784745984 -0.0691912696 0.2651516199 2.5907537937 393 15.6800000000 0.0356450342 0.0252805614 0.0579214282 0.0077221237 0.9021500000 92313518 95654128 1786015744 -0.0651972964 0.2672733366 2.5943703651 394 15.7200000000 0.0367531404 0.0253096796 0.0579214282 0.0077139102 0.8121090000 92315212 95654128 1787809792 -0.0639142320 0.2678541541 2.5953905582 395 15.7600000000 0.0410924591 0.0253496360 0.0579214282 0.0077220208 0.8096370000 92315786 95654128 1784762368 -0.0646211579 0.2660483718 2.5919065475 396 15.8000000000 0.0442249700 0.0253973010 0.0579214282 0.0077182071 0.8632680000 92317464 95654128 1786015744 -0.0629025549 0.2673697174 2.5882575512 397 15.8400000000 0.0435506515 0.0254430273 0.0579214282 0.0077164101 0.8276920000 92319142 95654128 1787920384 -0.0595659763 0.2682563663 2.5901372433 398 15.8800000000 0.0439668819 0.0254895696 0.0579214282 0.0077086652 0.9875290000 92319576 95654128 1784745984 -0.0573199466 0.2674157321 2.5913441181 399 15.9200000000 0.0402389169 0.0255265354 0.0579214282 0.0076994410 0.7063310000 92321238 95654128 1786015744 -0.0496300422 0.2700364590 2.5953807831 400 15.9600000000 0.0368354134 0.0255548076 0.0579214282 0.0076972924 0.9516930000 92322932 95654128 1788047360 -0.0420772769 0.2662898302 2.5921990871 401 16.0000000000 0.0372489654 0.0255839701 0.0579214282 0.0076924982 0.9870690000 92323506 95654128 1784492032 -0.0374935865 0.2674719691 2.5908474922 402 16.0400000000 0.0382819213 0.0256155570 0.0579214282 0.0076857520 0.7487510000 92325200 95654128 1785888768 -0.0323863477 0.2696745098 2.5900053978 403 16.0800000000 0.0382604524 0.0256469340 0.0579214282 0.0076841266 0.6857400000 92326894 95654128 1787793408 -0.0273712166 0.2689523995 2.5904278755 404 16.1200000000 0.0391517170 0.0256803616 0.0579214282 0.0076781572 0.8491290000 92327328 95654128 1784619008 -0.0218250863 0.2714811265 2.5868461132 405 16.1600000000 0.0391174182 0.0257135396 0.0579214282 0.0076694891 0.9086550000 92329022 95654128 1786015744 -0.0162576288 0.2717079520 2.5879814625 406 16.2000000000 0.0390645377 0.0257464238 0.0579214282 0.0076605286 0.7826600000 92330700 95654128 1787920384 -0.0102257710 0.2732578218 2.5903303623 407 16.2400000000 0.0391120315 0.0257792631 0.0579214282 0.0076532753 0.8131320000 92331274 95654128 1784619008 -0.0049200868 0.2747376263 2.5923023224 408 16.2800000000 0.0381597131 0.0258096074 0.0579214282 0.0076561778 0.6485290000 92332968 95654128 1786032128 0.0006642975 0.2749112546 2.5966935158 409 16.3200000000 0.0374550298 0.0258380803 0.0579214282 0.0076626752 0.8511490000 92336290 95654128 1787920384 0.0076213321 0.2777551115 2.6000320911 410 16.3600000000 0.0377534069 0.0258671420 0.0579214282 0.0076539422 0.7381900000 92505368 95654128 1784619008 0.0135183018 0.2800289094 2.6038146019 411 16.3999999990 0.0385253131 0.0258979405 0.0579214282 0.0076500637 0.7970210000 92507062 95654128 1786142720 0.0172531232 0.2804400623 2.6039590836 412 16.4400000000 0.0383149832 0.0259280790 0.0579214282 0.0076657756 0.8235070000 92508756 95654128 1788047360 0.0227249563 0.2811267078 2.6106495857 413 16.4800000000 0.0378531292 0.0259569532 0.0579214282 0.0076778664 0.7460560000 92509330 95654128 1784647680 0.0287529640 0.2815179825 2.6184072495 414 16.5200000000 0.0387426391 0.0259878365 0.0579214282 0.0076732627 0.6537280000 92511024 95654128 1786015744 0.0327781811 0.2811245322 2.6226820946 415 16.5599999990 0.0391070321 0.0260194490 0.0579214282 0.0076921325 0.6301520000 92511458 95654128 1788047360 0.0360840634 0.2752703130 2.6268749237 416 16.6000000000 0.0393712781 0.0260515447 0.0579214282 0.0077694012 0.9865290000 92513152 95654128 1784745984 0.0421207324 0.2749815583 2.6322638988 417 16.6400000000 0.0397363789 0.0260843621 0.0579214282 0.0078003233 0.8082090000 92514862 95654128 1786015744 0.0479137748 0.2767556310 2.6342260838 418 16.6800000000 0.0406839736 0.0261192894 0.0579214282 0.0078060583 0.8438330000 92516596 95654128 1788174336 0.0503426008 0.2770377100 2.6336812973 419 16.7199999990 0.0415517166 0.0261561210 0.0579214282 0.0078371210 0.7524340000 92687078 95654128 1784365056 0.0566274002 0.2775219679 2.6382119656 420 16.7600000000 0.0421345495 0.0261941648 0.0579214282 0.0078278663 0.6924910000 92688772 95654128 1785634816 0.0629871264 0.2799295783 2.6389362812 421 16.8000000000 0.0413122624 0.0262300748 0.0579214282 0.0078386021 0.7895710000 92689206 95654128 1787666432 0.0675673187 0.2755143642 2.6405942440 422 16.8400000000 0.0445516519 0.0262734909 0.0579214282 0.0078400624 0.7068990000 92692144 95654128 1784619008 0.0758276209 0.2770782113 2.6437838078 423 16.8799999990 0.0429757275 0.0263129761 0.0579214282 0.0078360107 0.7684270000 92862490 95654128 1786023936 0.0831147581 0.2733487189 2.6446759701 424 16.9200000000 0.0409196727 0.0263474258 0.0579214282 0.0078276925 0.6974820000 92862924 95654128 1788182528 0.0893873498 0.2667907178 2.6438374519 425 16.9600000000 0.0390746556 0.0263773722 0.0579214282 0.0078266883 0.7927520000 92864758 95654128 1784373248 0.0981548801 0.2647463381 2.6420056820 426 17.0000000000 0.0376561135 0.0264038482 0.0579214282 0.0078190051 0.7476010000 92866452 95654128 1785659392 0.1077372879 0.2624973655 2.6418349743 427 17.0400000000 0.0367138721 0.0264279934 0.0579214282 0.0078166639 0.7553430000 92866870 95654128 1787453440 0.1145009249 0.2589727044 2.6378724575 428 17.0800000000 0.0353830419 0.0264489164 0.0579214282 0.0078082596 1.0719820000 92868564 95654128 1784500224 0.1253695190 0.2573398948 2.6358997822 429 17.1200000000 0.0345803127 0.0264678707 0.0579214282 0.0078011238 1.9847750000 92870258 95654128 1785896960 0.1363921314 0.2548803985 2.6345086098 430 17.1600000000 0.0322394036 0.0264812929 0.0579214282 0.0077986986 1.7628450000 92870692 95654128 1787801600 0.1469491720 0.2519758940 2.6295902729 431 17.2000000000 0.0306731481 0.0264910188 0.0579214282 0.0077898023 1.2907890000 92872526 95654128 1784627200 0.1579644233 0.2479299605 2.6271653175 432 17.2400000000 0.0294589642 0.0264978890 0.0579214282 0.0077892654 1.8738780000 92872960 95654128 1786015744 0.1708598882 0.2453152388 2.6226272583 433 17.2800000000 0.0278288107 0.0265009627 0.0579214282 0.0077812991 1.0186430000 92875770 95654128 1787920384 0.1835299432 0.2431883961 2.6183676720 434 17.3200000000 0.0259983614 0.0264998047 0.0579214282 0.0077727165 0.8457400000 93046092 95654128 1784619008 0.1952041984 0.2379074991 2.6098906994 435 17.3600000000 0.0266298503 0.0265001036 0.0579214282 0.0077847228 0.7875910000 93046526 95654128 1786015744 0.2077969164 0.2373670489 2.6045043468 436 17.4000000000 0.0277186092 0.0265028984 0.0579214282 0.0077889907 0.8072230000 93048220 95654128 1788047360 0.2227384746 0.2422219515 2.5977382660 437 17.4400000000 0.0311175343 0.0265134582 0.0579214282 0.0077877143 0.8353160000 93050038 95654128 1784619008 0.2361183017 0.2452390641 2.5870976448 438 17.4800000000 0.0355904289 0.0265341819 0.0579214282 0.0078862283 0.7051850000 93050472 95654128 1786032128 0.2456504256 0.2462773323 2.5760827065 439 17.5200000000 0.0360048562 0.0265557551 0.0579214282 0.0080232924 0.7539690000 93052166 95654128 1787793408 0.2529156208 0.2418441623 2.5655381680 440 17.5600000000 0.0323551446 0.0265689356 0.0579214282 0.0080471789 0.7589570000 93053860 95654128 1784619008 0.2628852725 0.2327033579 2.5567111969 441 17.6000000000 0.0271738935 0.0265703074 0.0579214282 0.0080452144 0.7319170000 93054294 95654128 1786015744 0.2756158412 0.2250287086 2.5507190228 442 17.6400000000 0.0251526423 0.0265671000 0.0579214282 0.0081055399 1.1459740000 93055972 95654128 1788047360 0.2917694151 0.2280287296 2.5425710678 443 17.6800000000 0.0246523358 0.0265627777 0.0579214282 0.0081225367 1.8821240000 93057806 95654128 1784745984 0.3166998923 0.2300000042 2.5278604031 444 17.7200000000 0.0275152680 0.0265649230 0.0579214282 0.0081181086 1.7166140000 93059180 95654128 1786015744 0.3239922523 0.2283845991 2.5158617496 445 17.7600000000 0.0283161663 0.0265688583 0.0579214282 0.0081147901 1.8768370000 93229534 95654128 1788047360 0.3329953849 0.2249618322 2.5074818134 446 17.8000000000 0.0275760554 0.0265711166 0.0579214282 0.0081058347 1.6516660000 93231228 95654128 1784745984 0.3439669907 0.2266854495 2.4999935627 447 17.8400000000 0.0271266922 0.0265723595 0.0579214282 0.0081010908 1.6914420000 93231662 95654128 1786015744 0.3525522649 0.2242549807 2.4921500683 448 17.8800000000 0.0266458690 0.0265725236 0.0579214282 0.0080920885 1.3087470000 93233356 95654128 1788047360 0.3606362939 0.2224836498 2.4856770039 449 17.9200000000 0.0258344859 0.0265708799 0.0579214282 0.0080832803 1.6700620000 93233930 95654128 1784745984 0.3695725501 0.2215039432 2.4786317348 450 17.9600000000 0.0264866333 0.0265706927 0.0579214282 0.0080758499 1.9115610000 93235624 95654128 1786015744 0.3755925596 0.2158765942 2.4719829559 451 18.0000000000 0.0190996416 0.0265541271 0.0579214282 0.0080807174 1.8621990000 93237286 95654128 1788182528 0.3928777874 0.2157248557 2.4685339928 452 18.0400000000 0.0181411859 0.0265355144 0.0579214282 0.0080743693 1.3188900000 93237720 95654128 1784246272 0.4033762813 0.2147233337 2.4622037411 453 18.0800000000 0.0198977329 0.0265208615 0.0579214282 0.0080658189 1.9270450000 93239414 95654128 1785516032 0.4091105759 0.2088378817 2.4546689987 454 18.1200000000 0.0206331518 0.0265078930 0.0579214282 0.0080672924 1.8658730000 93241108 95654128 1787285504 0.4184159935 0.2074268311 2.4469277859 455 18.1600000000 0.0215928294 0.0264970906 0.0579214282 0.0080595646 1.9389270000 93241682 95654128 1784619008 0.4279099703 0.2061735839 2.4416844845 456 18.2000000000 0.0221604183 0.0264875804 0.0579214282 0.0080530102 1.5256610000 93243376 95654128 1786015744 0.4361761212 0.2027821392 2.4337711334 457 18.2400000000 0.0232988335 0.0264806028 0.0579214282 0.0080595919 1.9764340000 93245070 95654128 1787793408 0.4452480376 0.2010931671 2.4265179634 458 18.2800000000 0.0246129408 0.0264765250 0.0579214282 0.0080724282 0.8834050000 93245504 95654128 1784619008 0.4556247890 0.2016210109 2.4238188267 459 18.3200000000 0.0237366110 0.0264705556 0.0579214282 0.0080643828 0.6525470000 93247198 95654128 1786015744 0.4686619639 0.2066707611 2.4215624332 460 18.3600000000 0.0276615787 0.0264731448 0.0579214282 0.0080639121 0.7467520000 93248892 95654128 1787920384 0.4734341800 0.2027317584 2.4159543514 461 18.4000000000 0.0310529396 0.0264830793 0.0579214282 0.0080567806 0.7722000000 93249466 95654128 1784647680 0.4811477363 0.2001560181 2.4124031067 462 18.4400000000 0.0361661203 0.0265040383 0.0579214282 0.0080495332 0.7303930000 93251160 95654128 1786015744 0.4875006676 0.2040437460 2.4077534676 463 18.4800000000 0.0351046510 0.0265226141 0.0579214282 0.0080432461 0.7079480000 93252854 95654128 1787920384 0.4976902306 0.2017489672 2.4015383720 464 18.5200000000 0.0378203280 0.0265469626 0.0579214282 0.0080369122 0.8491400000 93253288 95654128 1784619008 0.5030399561 0.1991238743 2.3982722759 465 18.5600000000 0.0413839333 0.0265788701 0.0579214282 0.0080417093 0.7580920000 93254966 95654128 1786032128 0.5081866384 0.1920744032 2.3886017799 466 18.6000000000 0.0504233912 0.0266300386 0.0579214282 0.0080703191 0.6584020000 93256660 95654128 1787920384 0.5130752325 0.1904617846 2.3802187443 467 18.6400000000 0.0529176332 0.0266863289 0.0579214282 0.0080663864 0.7383190000 93257922 95654128 1784745984 0.5217766166 0.1905668676 2.3772051334 468 18.6800000000 0.0591745600 0.0267557482 0.0591745600 0.0080744445 0.7079780000 93428280 95654128 1786015744 0.5266923308 0.1869957596 2.3731184006 469 18.7200000000 0.0611167587 0.0268290127 0.0611167587 0.0081022560 0.8085360000 93428714 95654128 1788174336 0.5347392559 0.1837241203 2.3697788715 470 18.7600000000 0.0741807297 0.0269297610 0.0741807297 0.0081651963 0.6843470000 93430408 95654128 1784365056 0.5349969268 0.1825052351 2.3590514660 471 18.8000000000 0.0773527771 0.0270368162 0.0773527771 0.0082288484 0.6887320000 93432118 95654128 1785634816 0.5435672402 0.1824140847 2.3543679714 472 18.8400000000 0.0694600493 0.0271266960 0.0773527771 0.0082701504 0.7801400000 93433132 95654128 1787666432 0.5613424182 0.1841696203 2.3547599316 473 18.8800000000 0.0628689453 0.0272022610 0.0773527771 0.0082758604 0.7985660000 93603614 95654128 1784619008 0.5766305327 0.1829505712 2.3546764851 474 18.9200000000 0.0646437109 0.0272812514 0.0773527771 0.0082745401 0.7584470000 93605308 95654128 1785888768 0.5806265473 0.1809330285 2.3462786674 475 18.9600000000 0.0681803674 0.0273673548 0.0773527771 0.0082754837 0.7175490000 93605742 95654128 1788047360 0.5858941674 0.1776274294 2.3426043987 476 19.0000000000 0.0710534751 0.0274591323 0.0773527771 0.0082823685 0.6798940000 93607436 95654128 1784619008 0.5928267241 0.1766640991 2.3393754959 477 19.0400000000 0.0601909012 0.0275277524 0.0773527771 0.0082823979 0.7164460000 93609130 95654128 1786015744 0.6103273034 0.1774903983 2.3370919228 478 19.0800000000 0.0601632893 0.0275960276 0.0773527771 0.0082754981 0.6617320000 93610316 95654128 1787920384 0.6228729486 0.1778546572 2.3408010006 479 19.1200000000 0.0578319281 0.0276591505 0.0773527771 0.0082687817 0.8115900000 93780798 95654128 1784745984 0.6319900155 0.1732880473 2.3408350945 480 19.1600000000 0.0592992119 0.0277250673 0.0773527771 0.0082820226 0.8547460000 93782492 95654128 1786015744 0.6421026587 0.1691217124 2.3396234512 481 19.2000000000 0.0576845892 0.0277873532 0.0773527771 0.0082971027 0.9126770000 93782926 95654128 1787793408 0.6516277790 0.1701328605 2.3337836266 482 19.2400000000 0.0528318100 0.0278393127 0.0773527771 0.0082905323 0.7551450000 93784620 95654128 1784647680 0.6651394367 0.1731483042 2.3385992050 483 19.2800000000 0.0545424595 0.0278945987 0.0773527771 0.0082823141 0.7693710000 93786314 95654128 1786015744 0.6720670462 0.1706265956 2.3370335102 484 19.3200000000 0.0526699796 0.0279457875 0.0773527771 0.0082770879 0.7676480000 93787148 95654128 1787920384 0.6783913970 0.1700008512 2.3341860771 485 19.3600000000 0.0511363670 0.0279936031 0.0773527771 0.0082741574 0.8796800000 93957658 95654128 1784492032 0.6890848279 0.1752673090 2.3308348656 486 19.4000000000 0.0447174199 0.0280280143 0.0773527771 0.0082901844 0.7741300000 93958092 95654128 1785888768 0.7056597471 0.1866337359 2.3318564892 487 19.4400000000 0.0436561741 0.0280601050 0.0773527771 0.0083195877 0.7503560000 93959786 95654128 1787920384 0.7136961818 0.1819671690 2.3265638351 488 19.4800000000 0.0435771570 0.0280919022 0.0773527771 0.0083202872 0.7039950000 93961480 95654128 1784500224 0.7120029330 0.1786760390 2.3211622238 489 19.5200000000 0.0515822619 0.0281399397 0.0773527771 0.0083159686 0.7628580000 93961914 95654128 1785769984 0.7072563767 0.1746842563 2.3168067932 490 19.5600000000 0.0536167212 0.0281919332 0.0773527771 0.0083076467 0.8752230000 93963592 95654128 1787547648 0.7091391683 0.1753025055 2.3096756935 491 19.6000000000 0.0543086268 0.0282451240 0.0773527771 0.0082997025 0.6529850000 93965426 95654128 1784659968 0.7133802176 0.1754828244 2.3079683781 492 19.6400000000 0.0527674593 0.0282949661 0.0773527771 0.0082931208 0.6779930000 93966352 95654128 1786023936 0.7156098485 0.1801432818 2.3006386757 493 19.6800000000 0.0528028905 0.0283446780 0.0773527771 0.0082983614 0.6813410000 94136694 95654128 1787928576 0.7192220688 0.1858723164 2.2950975895 494 19.7200000000 0.0542595908 0.0283971373 0.0773527771 0.0082976809 0.7670270000 94138388 95654128 1784500224 0.7195540071 0.1822430044 2.2878878117 495 19.7600000000 0.0554533415 0.0284517963 0.0773527771 0.0082907294 0.8150980000 94138822 95654128 1785786368 0.7185357809 0.1799635142 2.2781980038 496 19.8000000000 0.0534623116 0.0285022207 0.0773527771 0.0082875039 0.6844910000 94140516 95654128 1787801600 0.7195705175 0.1798762679 2.2712864876 497 19.8400000000 0.0539387688 0.0285534009 0.0773527771 0.0082798503 0.7656220000 94142350 95654128 1784627200 0.7232940197 0.1790538877 2.2660226822 498 19.8800000000 0.0559663847 0.0286084471 0.0773527771 0.0082721946 0.7266520000 94142784 95654128 1785896960 0.7194555998 0.1780331284 2.2576415539 499 19.9200000000 0.0614122897 0.0286741862 0.0773527771 0.0082643619 0.7899410000 94144494 95654128 1787801600 0.7161415815 0.1798006892 2.2534632683 500 19.9600000000 0.0671025738 0.0287510430 0.0773527771 0.0082574911 0.8085090000 94146188 95654128 1784872960 0.7122718096 0.1826369911 2.2476215363 501 20.0000000000 0.0685810149 0.0288305439 0.0773527771 0.0082506088 0.7229450000 94146622 95654128 1786142720 0.7132379413 0.1829423010 2.2403526306 502 20.0400000000 0.0700031444 0.0289125611 0.0773527771 0.0082432900 0.6750260000 94148316 95654128 1788174336 0.7156215310 0.1805770248 2.2376194000 503 20.0800000000 0.0729538426 0.0290001183 0.0773527771 0.0082356416 0.6211800000 94148922 95654128 1784397824 0.7170265317 0.1840405762 2.2283344269 504 20.1200000000 0.0760758147 0.0290935224 0.0773527771 0.0082311148 0.8580750000 94150616 95654128 1785634816 0.7168046236 0.1868554056 2.2196071148 505 20.1600000000 0.0804909170 0.0291952995 0.0804909170 0.0082271801 0.8440960000 94152310 95654128 1787428864 0.7070844769 0.1836658716 2.2086906433 506 20.2000000000 0.0835476369 0.0293027152 0.0835476369 0.0082212753 0.9422600000 94153048 95654128 1784492032 0.7045715451 0.1870466322 2.2024662495 507 20.2400000000 0.0884049013 0.0294192875 0.0884049013 0.0082242959 0.9083940000 94323442 95654128 1785888768 0.7033117414 0.1929692179 2.1948189735 508 20.2800000000 0.0885337442 0.0295356546 0.0885337442 0.0082265755 0.8180980000 94325152 95654128 1787920384 0.6972529292 0.1926088482 2.1850321293 509 20.3200000000 0.0882327110 0.0296509729 0.0885337442 0.0082192043 0.8572010000 94325726 95654128 1784619008 0.7015097737 0.1919542700 2.1749136448 510 20.3600000000 0.0942728594 0.0297776825 0.0942728594 0.0082116280 0.7926620000 94327420 95654128 1786015744 0.7023836970 0.1969365478 2.1634397507 511 20.4000000000 0.1007281020 0.0299165287 0.1007281020 0.0082065689 0.8351210000 94329114 95654128 1787920384 0.7009078860 0.2048860788 2.1537461281 512 20.4400000000 0.1038625240 0.0300609545 0.1038625240 0.0082290229 0.7010100000 94329548 95654128 1784492032 0.7002258301 0.2101832032 2.1470072269 513 20.4800000000 0.1036546901 0.0302044121 0.1038625240 0.0082304894 0.7123480000 94372218 95654128 1785888768 0.7041963935 0.2071377039 2.1357095242 514 20.5200000000 0.1045330688 0.0303490204 0.1045330688 0.0082228758 0.7122040000 94458308 95654128 1787793408 0.7033218741 0.2076344341 2.1234607697 515 20.5600000000 0.1128508449 0.0305092181 0.1128508449 0.0082293688 0.7217270000 94627586 95654128 1784619008 0.7047356367 0.2164689302 2.1151952744 516 20.6000000000 0.1168008074 0.0306764498 0.1168008074 0.0082363580 0.7634440000 94629280 95654128 1786015744 0.7075303793 0.2195079625 2.1053822041 517 20.6400000000 0.1200324073 0.0308492854 0.1200324073 0.0082399788 0.8274240000 94630990 95654128 1788047360 0.7027818561 0.2217439860 2.1064391136 518 20.6800000000 0.1211779490 0.0310236650 0.1211779490 0.0082334997 0.6541780000 94631424 95654128 1784029184 0.7148374915 0.2195110470 2.0887043476 519 20.7200000000 0.1278486252 0.0312102256 0.1278486252 0.0082321128 0.7059250000 94633118 95654128 1785380864 0.7020887136 0.2286148071 2.0931093693 520 20.7600000000 0.1281130761 0.0313965773 0.1281130761 0.0082339957 0.6558670000 94634812 95654128 1787285504 0.6964430809 0.2330721170 2.0918595791 521 20.8000000000 0.1212399453 0.0315690213 0.1281130761 0.0082420062 0.7993890000 94635694 95654128 1784492032 0.6996151805 0.2273848951 2.0819308758 522 20.8400000000 0.1173240617 0.0317333030 0.1281130761 0.0082371501 0.8481370000 94806088 95654128 1785778176 0.7059022188 0.2240163535 2.0718288422 523 20.8800000000 0.1151855737 0.0318928676 0.1281130761 0.0082320360 0.7084580000 94806522 95654128 1787793408 0.6976952553 0.2231617272 2.0747833252 524 20.9200000000 0.1209778264 0.0320628771 0.1281130761 0.0082274281 0.7463240000 94808216 95654128 1783984128 0.7084708214 0.2231814116 2.0590584278 525 20.9600000000 0.1252143085 0.0322403084 0.1281130761 0.0082212973 0.6709120000 94809910 95654128 1785253888 0.7031772733 0.2223319858 2.0568706989 526 21.0000000000 0.1291354746 0.0324245197 0.1291354746 0.0082148744 0.9321760000 94810360 95654128 1787285504 0.7066333890 0.2188901305 2.0462422371 527 21.0400000000 0.1286438704 0.0326070991 0.1291354746 0.0082164332 0.7614970000 94812194 95654128 1784639488 0.7099057436 0.2212036699 2.0366919041 528 21.0800000000 0.1306725591 0.0327928292 0.1306725591 0.0082092594 0.7288250000 94813888 95654128 1785888768 0.7117416263 0.2223212123 2.0326817036 529 21.1200000000 0.1366400719 0.0329891377 0.1366400719 0.0082052853 0.7653020000 94814322 95654128 1787920384 0.7199280858 0.2194737494 2.0199730396 530 21.1600000000 0.1369843930 0.0331853552 0.1369843930 0.0082006960 0.9072430000 94816016 95654128 1784619008 0.7156233788 0.2192937136 2.0182819366 531 21.2000000000 0.1465598643 0.0333988665 0.1465598643 0.0081969721 0.8691070000 94817742 95654128 1785888768 0.7202528715 0.2248216867 2.0102865696 532 21.2400000000 0.1492667794 0.0336166634 0.1492667794 0.0081897748 0.7739700000 94818176 95654128 1787666432 0.7197217345 0.2242794484 2.0056910515 533 21.2800000000 0.1511963308 0.0338372631 0.1511963308 0.0081831610 0.8460750000 94820010 95654128 1784619008 0.7178259492 0.2249253392 2.0019297600 534 21.3200000000 0.1556814164 0.0340654357 0.1556814164 0.0081782165 0.9043420000 94821720 95654128 1786023936 0.7220784426 0.2251777053 1.9894601107 535 21.3600000000 0.1581435949 0.0342973575 0.1581435949 0.0081730368 0.7478430000 94822154 95654128 1787674624 0.7269488573 0.2289714515 1.9768164158 536 21.4000000000 0.1586468667 0.0345293528 0.1586468667 0.0081663852 0.8271340000 94823848 95654128 1784627200 0.7247678638 0.2288910896 1.9733339548 537 21.4400000000 0.1611407846 0.0347651283 0.1611407846 0.0081594000 1.0799540000 94825542 95654128 1786023936 0.7298817635 0.2273124009 1.9578278065 538 21.4800000000 0.1610754877 0.0349999059 0.1611407846 0.0081521925 1.6135670000 94825992 95654128 1787801600 0.7306246758 0.2270983309 1.9503185749 539 21.5200000000 0.1604624838 0.0352326751 0.1611407846 0.0081449323 2.1142790000 94827826 95654128 1784754176 0.7287101150 0.2253538221 1.9427256584 540 21.5600000000 0.1614387333 0.0354663900 0.1614387333 0.0081385716 0.8461550000 94829576 95654128 1786150912 0.7320966125 0.2277474105 1.9293994904 541 21.6000000000 0.1601883471 0.0356969297 0.1614387333 0.0081318364 1.8103880000 94999870 95654128 1787928576 0.7335783243 0.2276239246 1.9206318855 542 21.6400000000 0.1608536839 0.0359278462 0.1614387333 0.0081290957 1.2803360000 95001580 95654128 1784619008 0.7364919186 0.2259471118 1.9089535475 543 21.6800000000 0.1598937213 0.0361561443 0.1614387333 0.0081219931 1.2246530000 95002014 95654128 1786015744 0.7377343178 0.2216607332 1.9039835930 544 21.7200000000 0.1598863304 0.0363835895 0.1614387333 0.0081205269 1.2701130000 95003708 95654128 1787920384 0.7389214039 0.2226172835 1.8944966793 545 21.7600000000 0.1597753465 0.0366099964 0.1614387333 0.0081169915 1.5164330000 95005542 95654128 1784619008 0.7422964573 0.2217020541 1.8828122616 546 21.8000000000 0.1580897123 0.0368324867 0.1614387333 0.0081213093 2.8116950000 95005976 95654128 1786015744 0.7441604733 0.2204812318 1.8759195805 547 21.8400000000 0.1580601037 0.0370541094 0.1614387333 0.0081193677 2.0807570000 95007670 95654128 1787793408 0.7465636134 0.2222129256 1.8641897440 548 21.8800000000 0.1584569961 0.0372756475 0.1614387333 0.0081128882 1.2765350000 95009364 95654128 1784872960 0.7449656129 0.2243729532 1.8609699011 549 21.9200000000 0.1573638469 0.0374943874 0.1614387333 0.0081069170 1.6626730000 95009798 95654128 1786142720 0.7458643913 0.2213438153 1.8547673225 550 21.9600000000 0.1573574096 0.0377123202 0.1614387333 0.0081003856 1.9933480000 95011492 95654128 1788174336 0.7451393008 0.2226062566 1.8490251303 551 22.0000000000 0.1574286222 0.0379295911 0.1614387333 0.0080942844 1.6549520000 95013326 95654128 1784492032 0.7462792397 0.2237404734 1.8408718109 552 22.0400000000 0.1578367203 0.0381468142 0.1614387333 0.0080872906 1.8432940000 95014968 95654128 1785761792 0.7495263815 0.2253255099 1.8335205317 553 22.0800000000 0.1584307551 0.0383643259 0.1614387333 0.0080829693 2.0040240000 95185382 95654128 1787928576 0.7473620176 0.2249481678 1.8313878775 554 22.1200000000 0.1603848785 0.0385845796 0.1614387333 0.0080765118 1.5120010000 95187076 95654128 1784627200 0.7470989227 0.2253849804 1.8247232437 555 22.1600000000 0.1613508165 0.0388057800 0.1614387333 0.0080699279 1.6968150000 95187510 95654128 1785896960 0.7479733229 0.2293237001 1.8179315329 556 22.2000000000 0.1610022038 0.0390255577 0.1614387333 0.0080650220 1.7794010000 95189204 95654128 1787928576 0.7480896115 0.2313784212 1.8093924522 557 22.2400000000 0.1609204710 0.0392443996 0.1614387333 0.0080711511 1.8162710000 95189778 95654128 1784619008 0.7474732399 0.2281047702 1.8059165478 558 22.2800000000 0.1604592800 0.0394616306 0.1614387333 0.0080639692 1.8397070000 95191472 95654128 1785888768 0.7457921505 0.2252345532 1.7995364666 559 22.3200000000 0.1605635136 0.0396782708 0.1614387333 0.0080598479 1.8425130000 95193166 95654128 1787793408 0.7448194623 0.2275755703 1.7943243980 560 22.3600000000 0.1625035107 0.0398976016 0.1625035107 0.0080540188 0.8638460000 95194916 95654128 1784619008 0.7429686189 0.2296596169 1.7917913198 561 22.4000000000 0.1646313220 0.0401199433 0.1646313220 0.0080480523 0.6684640000 95365338 95654128 1786032128 0.7450298071 0.2297152728 1.7853802443 562 22.4400000000 0.1644942462 0.0403412499 0.1646313220 0.0080416606 0.8430890000 95367032 95654128 1788047360 0.7441412807 0.2299829423 1.7836747169 563 22.4800000000 0.1658505350 0.0405641794 0.1658505350 0.0080363062 0.7870860000 95367606 95654128 1784619008 0.7452582717 0.2309188694 1.7751812935 564 22.5200000000 0.1670565605 0.0407884566 0.1670565605 0.0080321152 0.8497220000 95369300 95654128 1786015744 0.7453667521 0.2299503237 1.7701414824 565 22.5600000000 0.1682221293 0.0410140029 0.1682221293 0.0080253962 0.7645650000 95370994 95654128 1787920384 0.7473516464 0.2262166142 1.7606037855 566 22.6000000000 0.1663215756 0.0412353944 0.1682221293 0.0080219017 1.0590350000 95371544 95654128 1784619008 0.7483442426 0.2235022336 1.7527456284 567 22.6400000000 0.1675020754 0.0414580870 0.1682221293 0.0080155518 1.9957480000 95373238 95654128 1786015744 0.7490375638 0.2208748460 1.7498412132 568 22.6800000000 0.1684828550 0.0416817221 0.1684828550 0.0080086061 1.1758000000 95374932 95654128 1787793408 0.7509138584 0.2183070332 1.7426730394 569 22.7200000000 0.1670062542 0.0419019761 0.1684828550 0.0080050325 0.9414500000 95375506 95654128 1784872960 0.7531604767 0.2147750109 1.7317034006 570 22.7600000000 0.1657796204 0.0421193053 0.1684828550 0.0080027819 0.8088260000 95378492 95654128 1786142720 0.7528708577 0.2168943733 1.7210597992 571 22.8000000000 0.1659965068 0.0423362532 0.1684828550 0.0079971295 0.5889200000 95548910 95654128 1788047360 0.7526972890 0.2199888378 1.7123687267 572 22.8400000000 0.1656152457 0.0425517759 0.1684828550 0.0079939545 0.9087480000 95549344 95654128 1784745984 0.7535093427 0.2159686983 1.7038315535 573 22.8800000000 0.1654351503 0.0427662320 0.1684828550 0.0079907264 0.8288980000 95551038 95654128 1786142720 0.7536330819 0.2157403529 1.6944137812 574 22.9200000000 0.1640832871 0.0429775858 0.1684828550 0.0079845952 0.8673270000 95552732 95654128 1787920384 0.7514182329 0.2145783603 1.6880415678 575 22.9600000000 0.1644361168 0.0431888180 0.1684828550 0.0079813466 0.9522350000 95553306 95654128 1784745984 0.7504528165 0.2099191546 1.6806805134 576 23.0000000000 0.1643093377 0.0433990967 0.1684828550 0.0079759269 0.8813010000 95555000 95654128 1786015744 0.7498572469 0.2057744265 1.6740149260 577 23.0400000000 0.1632762700 0.0436068561 0.1684828550 0.0079776818 0.9292240000 95555434 95654128 1788047360 0.7488956451 0.2066953629 1.6639949083 578 23.0800000000 0.1652228534 0.0438172644 0.1684828550 0.0079711324 0.8287070000 95557128 95654128 1784745984 0.7473419905 0.2077238858 1.6555302143 579 23.1200000000 0.1661331058 0.0440285180 0.1684828550 0.0079645579 0.7685160000 95558822 95654128 1786032128 0.7465573549 0.2058023661 1.6469061375 580 23.1600000000 0.1673385054 0.0442411214 0.1684828550 0.0079583493 0.9166380000 95559256 95654128 1788047360 0.7456483841 0.2040685862 1.6387945414 581 23.2000000000 0.1673365831 0.0444529897 0.1684828550 0.0079517185 0.9178680000 95561090 95654128 1784745984 0.7442125082 0.2031913698 1.6303974390 582 23.2400000000 0.1690268219 0.0446670341 0.1690268219 0.0079471284 0.7657080000 95562768 95654128 1786015744 0.7425292134 0.2004311085 1.6222105026 583 23.2800000000 0.1671917737 0.0448771966 0.1690268219 0.0079411912 0.9074810000 95563202 95654128 1787920384 0.7431730032 0.1950542331 1.6124460697 584 23.3200000000 0.1647596657 0.0450824748 0.1690268219 0.0079442503 0.8667880000 95564896 95654128 1784745984 0.7417335510 0.1935608834 1.5992406607 585 23.3600000000 0.1646355242 0.0452868390 0.1690268219 0.0079385510 0.9485820000 95566590 95654128 1786150912 0.7404910922 0.1916757077 1.5886466503 586 23.4000000000 0.1640658677 0.0454895336 0.1690268219 0.0079354888 0.8722480000 95567040 95654128 1787674624 0.7404549718 0.1885792315 1.5768945217 587 23.4400000000 0.1619663984 0.0456879609 0.1690268219 0.0079423180 0.8267170000 95570338 95654128 1784655872 0.7401713133 0.1869176626 1.5657250881 588 23.4800000000 0.1622142047 0.0458861348 0.1690268219 0.0079522877 0.8667960000 95740760 95654128 1786023936 0.7383005023 0.1895811707 1.5391082764 589 23.5200000000 0.1613992453 0.0460822521 0.1690268219 0.0079461519 0.9206160000 95741194 95654128 1788055552 0.7366667986 0.1895546913 1.5293363333 590 23.5600000000 0.1589082927 0.0462734827 0.1690268219 0.0079435685 0.9740880000 95743120 95654128 1784754176 0.7354041338 0.1887255609 1.5167988539 591 23.6000000000 0.1592287123 0.0464646083 0.1690268219 0.0079439520 0.7302630000 95744814 95654128 1786150912 0.7344490290 0.1872630566 1.5054689646 592 23.6400000000 0.1589290947 0.0466545821 0.1690268219 0.0079380442 0.6675640000 95745248 95654128 1788055552 0.7342221737 0.1865719259 1.4906612635 593 23.6800000000 0.1557786465 0.0468386025 0.1690268219 0.0079352267 0.9453110000 95747082 95654128 1784872960 0.7335009575 0.1833921671 1.4767032862 594 23.7200000000 0.1511547416 0.0470142189 0.1690268219 0.0079350277 0.8881550000 95747516 95654128 1786159104 0.7334354520 0.1799559295 1.4614275694 595 23.7600000000 0.1495941430 0.0471866221 0.1690268219 0.0079325929 0.8493760000 95749210 95654128 1788047360 0.7316090465 0.1778104901 1.4514337778 596 23.8000000000 0.1496917158 0.0473586105 0.1690268219 0.0079310871 0.8272180000 95750904 95654128 1784745984 0.7301518321 0.1789795756 1.4391114712 597 23.8400000000 0.1502276659 0.0475309205 0.1690268219 0.0079249840 0.8748850000 95751454 95654128 1786142720 0.7275612354 0.1816833913 1.4288775921 598 23.8800000000 0.1501965523 0.0477026021 0.1690268219 0.0079192488 0.7622790000 95753148 95654128 1787920384 0.7265524268 0.1817231029 1.4156777859 599 23.9200000000 0.1488223672 0.0478714164 0.1690268219 0.0079132614 0.6731580000 95754982 95654128 1784619008 0.7243049145 0.1830455363 1.4046975374 600 23.9600000000 0.1476001143 0.0480376309 0.1690268219 0.0079089558 1.0436420000 95755416 95654128 1786015744 0.7226738334 0.1824594438 1.3924045563 601 24.0000000000 0.1476421505 0.0482033622 0.1690268219 0.0079032963 0.8907640000 95757110 95654128 1787793408 0.7201685309 0.1823914945 1.3827475309 602 24.0400000000 0.1477796882 0.0483687714 0.1690268219 0.0078971439 0.9838020000 95758920 95654128 1784762368 0.7184922099 0.1815807372 1.3712455034 603 24.0800000000 0.1459798515 0.0485306472 0.1690268219 0.0078915397 0.8232560000 95759354 95654128 1786015744 0.7157654166 0.1793147326 1.3620342016 604 24.1200000000 0.1454087645 0.0486910414 0.1690268219 0.0078853272 0.8501180000 95761048 95654128 1788047360 0.7127721310 0.1806626618 1.3527176380 605 24.1600000000 0.1450349092 0.0488502875 0.1690268219 0.0078797620 0.9481610000 95762882 95654128 1784745984 0.7101598382 0.1783567518 1.3446385860 606 24.2000000000 0.1452022195 0.0490092841 0.1690268219 0.0078736180 0.8894250000 95763316 95654128 1786015744 0.7078080773 0.1776787937 1.3359936476 607 24.2400000000 0.1456347257 0.0491684693 0.1690268219 0.0078674615 0.8899300000 95765010 95654128 1788047360 0.7056794763 0.1770027429 1.3239828348 608 24.2800000000 0.1452975571 0.0493265764 0.1690268219 0.0078612420 0.7903260000 95766820 95654128 1784635392 0.7029522657 0.1769707352 1.3161860704 609 24.3200000000 0.1438320726 0.0494817578 0.1690268219 0.0078586767 0.6885500000 95767254 95654128 1786032128 0.7016534805 0.1712435633 1.3072178364 610 24.3600000000 0.1449873596 0.0496383244 0.1690268219 0.0078523048 0.8683470000 95768948 95654128 1788047360 0.6994841695 0.1675281525 1.3004266024 611 24.4000000000 0.1452988833 0.0497948883 0.1690268219 0.0078527424 0.8861910000 95769522 95654128 1784524800 0.6984813809 0.1682656407 1.2865660191 612 24.4400000000 0.1431639940 0.0499474522 0.1690268219 0.0078485728 0.7595600000 95771216 95654128 1785888768 0.6961115599 0.1668743491 1.2759823799 613 24.4800000000 0.1440010816 0.0501008839 0.1690268219 0.0078428938 1.1017820000 95772910 95654128 1787666432 0.6940020919 0.1656505316 1.2692492008 614 24.5200000000 0.1447688341 0.0502550662 0.1690268219 0.0078368743 0.9622160000 95773460 95654128 1784619008 0.6923191547 0.1626760811 1.2579483986 615 24.5600000000 0.1452677399 0.0504095584 0.1690268219 0.0078308045 0.9072720000 95775154 95654128 1786015744 0.6908994913 0.1609885544 1.2504215240 616 24.6000000000 0.1457212269 0.0505642851 0.1690268219 0.0078249846 0.9307210000 95776848 95654128 1787920384 0.6896404028 0.1579658687 1.2403874397 617 24.6400000000 0.1437579095 0.0507153282 0.1690268219 0.0078234794 0.8676570000 95779726 95654128 1784619008 0.6880822182 0.1537059098 1.2287276983 618 24.6800000000 0.1439244002 0.0508661520 0.1690268219 0.0078215757 0.8952270000 95950400 95654128 1786015744 0.6871432662 0.1508746892 1.2168335915 619 24.7200000000 0.1437823325 0.0510162589 0.1690268219 0.0078233955 0.7685220000 95952094 95654128 1787920384 0.6864514351 0.1499182880 1.2018438578 620 24.7600000000 0.1437609941 0.0511658472 0.1690268219 0.0078196193 0.8878460000 95952528 95654128 1784774656 0.6838641763 0.1498637050 1.1936495304 621 24.8000000000 0.1437058151 0.0513148648 0.1690268219 0.0078135355 0.8646030000 95954338 95654128 1786142720 0.6826112866 0.1489709169 1.1837654114 622 24.8400000000 0.1430287808 0.0514623149 0.1690268219 0.0078078842 0.9048570000 95956032 95654128 1788047360 0.6810419559 0.1464417577 1.1726571321 623 24.8800000000 0.1426717937 0.0516087185 0.1690268219 0.0078040302 0.7862080000 95956606 95654128 1784745984 0.6790800095 0.1458402127 1.1623951197 624 24.9200000000 0.1409975588 0.0517519699 0.1690268219 0.0078001146 0.9053950000 95958416 95654128 1786142720 0.6769009233 0.1468848884 1.1494387388 625 24.9600000000 0.1415071934 0.0518955782 0.1690268219 0.0077940178 0.8622470000 95960110 95654128 1788182528 0.6743476987 0.1459220797 1.1400088072 626 25.0000000000 0.1413908005 0.0520385418 0.1690268219 0.0077886794 0.9142970000 95960544 95654128 1784373248 0.6724503040 0.1433289945 1.1307418346 627 25.0400000000 0.1401182115 0.0521790198 0.1690268219 0.0077858314 0.8737600000 95962238 95654128 1785769984 0.6701927185 0.1420218050 1.1199351549 628 25.0800000000 0.1389595270 0.0523172053 0.1690268219 0.0077808371 0.8328360000 95966176 95654128 1787547648 0.6670277119 0.1436266750 1.1092722416 629 25.1200000000 0.1390783489 0.0524551404 0.1690268219 0.0077782888 0.8833320000 96135454 95654128 1784881152 0.6644988060 0.1412289441 1.1040985584 630 25.1600000000 0.1399267614 0.0525939842 0.1690268219 0.0077727406 0.8600930000 96137148 95654128 1786150912 0.6610627174 0.1416747719 1.0957638025 631 25.2000000000 0.1394418180 0.0527316194 0.1690268219 0.0077681898 0.9518200000 96137582 95654128 1788182528 0.6573762298 0.1420787573 1.0871449709 632 25.2400000000 0.1378429085 0.0528662892 0.1690268219 0.0077658750 0.8514680000 96139276 95654128 1784373248 0.6540406346 0.1403878480 1.0797901154 633 25.2800000000 0.1373040825 0.0529996822 0.1690268219 0.0077612264 0.6589160000 96140970 95654128 1785643008 0.6504032612 0.1402518004 1.0694266558 634 25.3200000000 0.1365977079 0.0531315403 0.1690268219 0.0077586848 0.8782240000 96141404 95654128 1787666432 0.6455715895 0.1407350898 1.0614511967 635 25.3600000000 0.1360133141 0.0532620628 0.1690268219 0.0077589104 0.8995600000 96143238 95654128 1784619008 0.6418601871 0.1408738494 1.0552791357 636 25.4000000000 0.1344894618 0.0533897788 0.1690268219 0.0077595741 0.8340400000 96144932 95654128 1785905152 0.6387105584 0.1370695382 1.0454362631 637 25.4400000000 0.1334950626 0.0535155328 0.1690268219 0.0077544077 0.9900550000 96145366 95654128 1787699200 0.6347188950 0.1366764605 1.0377840996 638 25.4800000000 0.1339150071 0.0536415508 0.1690268219 0.0077490564 1.1654200000 96147060 95654128 1784619008 0.6315052509 0.1362334341 1.0299081802 639 25.5200000000 0.1325185001 0.0537649889 0.1690268219 0.0077437986 1.5800880000 96148754 95654128 1786015744 0.6268479824 0.1334146559 1.0230489969 640 25.5600000000 0.1312059313 0.0538859904 0.1690268219 0.0077390683 1.0379750000 96149188 95654128 1787793408 0.6230459213 0.1316578239 1.0159078836 641 25.6000000000 0.1318977922 0.0540076936 0.1690268219 0.0077335157 0.8707810000 96151022 95654128 1784619008 0.6183612943 0.1308483481 1.0104731321 642 25.6400000000 0.1318385750 0.0541289256 0.1690268219 0.0077286736 0.7497830000 96152716 95654128 1786015744 0.6132264733 0.1303164661 1.0053350925 643 25.6800000000 0.1315262765 0.0542492947 0.1690268219 0.0077232887 0.7905800000 96153150 95654128 1787920384 0.6086262465 0.1285988092 0.9983884096 644 25.7200000000 0.1320933402 0.0543701705 0.1690268219 0.0077173202 0.8289900000 96154844 95654128 1784619008 0.6033306718 0.1277122498 0.9944857359 645 25.7600000000 0.1321877688 0.0544908180 0.1690268219 0.0077115258 0.7797350000 96156538 95654128 1786032128 0.5985687971 0.1255303770 0.9886144400 646 25.8000000000 0.1302775294 0.0546081349 0.1690268219 0.0077065595 0.8278140000 96156972 95654128 1787920384 0.5924661756 0.1236493662 0.9826440811 647 25.8400000000 0.1291869283 0.0547234035 0.1690268219 0.0077009593 0.8851610000 96158806 95654128 1784745984 0.5856326222 0.1234260350 0.9761739969 648 25.8800000000 0.1288340539 0.0548377718 0.1690268219 0.0076991342 0.9741150000 96159240 95654128 1786142720 0.5790790915 0.1227252111 0.9714748859 649 25.9200000000 0.1283148825 0.0549509876 0.1690268219 0.0076967896 1.0685470000 96160934 95654128 1788047360 0.5720111132 0.1198134571 0.9662027359 650 25.9600000000 0.1292412877 0.0550652804 0.1690268219 0.0076926487 0.7996660000 96162628 95654128 1784745984 0.5588988066 0.1141271815 0.9586405754 651 26.0000000000 0.1283721030 0.0551778869 0.1690268219 0.0076965347 0.8148650000 96163062 95654128 1786142720 0.5423052311 0.1140956506 0.9480315447 652 26.0400000000 0.1264652908 0.0552872234 0.1690268219 0.0076920795 0.9098480000 96164756 95654128 1787920384 0.5328838825 0.1145244986 0.9399609566 653 26.0800000000 0.1244168729 0.0553930881 0.1690268219 0.0076907529 1.1231720000 96169198 95654128 1784745984 0.5229893327 0.1161001250 0.9339551926 654 26.1200000000 0.1230598912 0.0554965542 0.1690268219 0.0076938897 0.8517480000 96338380 95654128 1786142720 0.5130202770 0.1157995537 0.9288896322 655 26.1600000000 0.1238032356 0.0556008392 0.1690268219 0.0076899003 0.9242890000 96340074 95654128 1788174336 0.5035333633 0.1135316268 0.9241858721 656 26.2000000000 0.1226301119 0.0557030180 0.1690268219 0.0076907494 0.8858700000 96341768 95654128 1784651776 0.4932051599 0.1145829633 0.9184890985 657 26.2400000000 0.1213488206 0.0558029355 0.1690268219 0.0076922568 0.8497560000 96342202 95654128 1785905152 0.4829079509 0.1151924878 0.9131546617 658 26.2800000000 0.1206162572 0.0559014359 0.1690268219 0.0076947440 0.8429050000 96343896 95654128 1787793408 0.4720685780 0.1168090105 0.9077073932 659 26.3200000000 0.1194914654 0.0559979307 0.1690268219 0.0076914416 0.9682750000 96345730 95654128 1784619008 0.4605549872 0.1189081520 0.9035106897 660 26.3600000000 0.1186698601 0.0560928882 0.1690268219 0.0076863463 0.7934940000 96346164 95654128 1785888768 0.4499962628 0.1197328269 0.8991476297 661 26.4000000000 0.1175476313 0.0561858605 0.1690268219 0.0076812451 1.0688110000 96347858 95654128 1787920384 0.4382575452 0.1219069883 0.8940620422 662 26.4400000000 0.1168094948 0.0562774370 0.1690268219 0.0076797731 0.9421480000 96349552 95654128 1784619008 0.4265068769 0.1251620501 0.8915975094 663 26.4800000000 0.1171329618 0.0563692251 0.1690268219 0.0076928623 0.9505870000 96349986 95654128 1786150912 0.4160262644 0.1252571493 0.8884198666 664 26.5200000000 0.1161108166 0.0564591974 0.1690268219 0.0076984114 0.8696610000 96351680 95654128 1787801600 0.4055343568 0.1219682097 0.8812789321 665 26.5600000000 0.1162051037 0.0565490409 0.1690268219 0.0076931540 1.1475450000 96352254 95654128 1784627200 0.3951642215 0.1233235300 0.8781662583 666 26.6000000000 0.1152633354 0.0566372005 0.1690268219 0.0076893568 0.9265100000 96353948 95654128 1786023936 0.3842285275 0.1245466545 0.8739570975 667 26.6400000000 0.1154894605 0.0567254348 0.1690268219 0.0076910352 0.9669010000 96355642 95654128 1787928576 0.3737026751 0.1281267703 0.8724660277 668 26.6800000000 0.1142057702 0.0568114832 0.1690268219 0.0077114170 0.8671500000 96356076 95654128 1784754176 0.3627586365 0.1314646751 0.8679960966 669 26.7200000000 0.1134501398 0.0568961448 0.1690268219 0.0077553464 0.8498760000 96357770 95654128 1786150912 0.3517839313 0.1321435124 0.8644367456 670 26.7600000000 0.1130546927 0.0569799636 0.1690268219 0.0077843227 0.7269050000 96359464 95654128 1787928576 0.3422606587 0.1318802834 0.8609256148 671 26.8000000000 0.1132439300 0.0570638145 0.1690268219 0.0077895660 0.6905510000 96360038 95654128 1784791040 0.3327374160 0.1327074021 0.8570639491 672 26.8400000000 0.1124000028 0.0571461600 0.1690268219 0.0077855310 0.8868930000 96361732 95654128 1786150912 0.3232539892 0.1350618452 0.8520106673 673 26.8800000000 0.1122602671 0.0572280532 0.1690268219 0.0077807636 0.9869930000 96363426 95654128 1787920384 0.3145360649 0.1356430799 0.8482789993 674 26.9200000000 0.1115275770 0.0573086163 0.1690268219 0.0077753906 1.0061740000 96366488 95654128 1784619008 0.3057904840 0.1359965950 0.8439294100 675 26.9600000000 0.1106793731 0.0573876841 0.1690268219 0.0077698348 1.1586310000 96536934 95654128 1786015744 0.2972495854 0.1379464120 0.8400266171 676 27.0000000000 0.1100693941 0.0574656156 0.1690268219 0.0077655119 1.9567300000 96538628 95654128 1788047360 0.2885174155 0.1422213465 0.8359661102 677 27.0400000000 0.1095980555 0.0575426207 0.1690268219 0.0077715799 2.4043870000 96539202 95654128 1784745984 0.2798119187 0.1452403069 0.8335396647 678 27.0800000000 0.1099793911 0.0576199610 0.1690268219 0.0077823774 1.0241120000 96540896 95654128 1786142720 0.2715273201 0.1477433592 0.8304168582 679 27.1200000000 0.1095627919 0.0576964600 0.1690268219 0.0077933718 0.8052360000 96542590 95654128 1788047360 0.2629687190 0.1496375799 0.8262990713 680 27.1600000000 0.1094271094 0.0577725345 0.1690268219 0.0077937039 0.8115560000 96543024 95654128 1784774656 0.2551000118 0.1495228559 0.8211961389 681 27.2000000000 0.1088907570 0.0578475980 0.1690268219 0.0077884135 0.8648880000 96544718 95654128 1786142720 0.2471238226 0.1503993869 0.8172500730 682 27.2400000000 0.1082714200 0.0579215332 0.1690268219 0.0077831774 0.7084120000 96546412 95654128 1788047360 0.2391691506 0.1540718228 0.8123821616 683 27.2800000000 0.1071556211 0.0579936183 0.1690268219 0.0077829178 1.1154950000 96546986 95654128 1784872960 0.2314925939 0.1560909301 0.8070597053 684 27.3200000000 0.1069962531 0.0580652595 0.1690268219 0.0077856322 1.9359290000 96548680 95654128 1786142720 0.2234480530 0.1577362418 0.8024505973 685 27.3600000000 0.1063079089 0.0581356868 0.1690268219 0.0077851518 2.3051100000 96549114 95654128 1788174336 0.2156333327 0.1575749516 0.7964819670 686 27.4000000000 0.1058637574 0.0582052612 0.1690268219 0.0077809344 1.3302060000 96550808 95654128 1784492032 0.2075201869 0.1615853161 0.7904508114 687 27.4400000000 0.1056640744 0.0582743425 0.1690268219 0.0077877142 0.9376010000 96552502 95654128 1785761792 0.1995486319 0.1651976407 0.7846008539 688 27.4800000000 0.1043980494 0.0583413827 0.1690268219 0.0078042777 1.1122450000 96552936 95654128 1787666432 0.1912423223 0.1658483595 0.7779800892 689 27.5200000000 0.1047967225 0.0584088070 0.1690268219 0.0078121099 1.0261630000 96554770 95654128 1784745984 0.1833278388 0.1685675532 0.7726215720 690 27.5600000000 0.1047740951 0.0584760031 0.1690268219 0.0078132506 0.9716800000 96556464 95654128 1786015744 0.1756794751 0.1696807742 0.7662618756 691 27.6000000000 0.1040674001 0.0585419820 0.1690268219 0.0078148432 1.0872350000 96556898 95654128 1787666432 0.1669777036 0.1733621061 0.7595636845 692 27.6400000000 0.1033441648 0.0586067250 0.1690268219 0.0078316789 0.8435810000 96558592 95654128 1784745984 0.1585402191 0.1757643074 0.7531298995 693 27.6800000000 0.1034345478 0.0586714116 0.1690268219 0.0078637727 0.7720480000 96560286 95654128 1786159104 0.1508155912 0.1759296656 0.7463186979 694 27.7200000000 0.1033910289 0.0587358491 0.1690268219 0.0078771687 0.8871790000 96563636 95654128 1788047360 0.1437322646 0.1757130772 0.7380827069 695 27.7600000000 0.1031658128 0.0587997771 0.1690268219 0.0078759839 0.8253060000 96734174 95654128 1784889344 0.1368074864 0.1749459207 0.7304930091 696 27.8000000000 0.1029836610 0.0588632597 0.1690268219 0.0078716806 0.8477910000 96735868 95654128 1786150912 0.1295299977 0.1772772670 0.7231258154 697 27.8400000000 0.1021609455 0.0589253798 0.1690268219 0.0078695306 0.7926620000 96736302 95654128 1785643008 0.1219131500 0.1797740906 0.7157241702 698 27.8800000000 0.1016379297 0.0589865725 0.1690268219 0.0078711030 0.8627640000 96737996 95654128 1787039744 0.1134742722 0.1837984324 0.7090999484 699 27.9200000000 0.1002755761 0.0590456412 0.1690268219 0.0078801232 0.9033130000 96739690 95654128 1784627200 0.1054766253 0.1874784082 0.7013735771 700 27.9600000000 0.0992931947 0.0591031377 0.1690268219 0.0078966518 0.6795160000 96740124 95654128 1786040320 0.0972847119 0.1900992841 0.6938140988 701 28.0000000000 0.0988356546 0.0591598175 0.1690268219 0.0079149363 0.9185750000 96741958 95654128 1787801600 0.0894545317 0.1921938956 0.6873853207 702 28.0400000000 0.0980444849 0.0592152087 0.1690268219 0.0079281560 0.7852510000 96742392 95654128 1784745984 0.0816914141 0.1931023896 0.6803092957 703 28.0800000000 0.0977472439 0.0592700196 0.1690268219 0.0079342101 0.8795100000 96744086 95654128 1786142720 0.0747110099 0.1943842173 0.6750590801 704 28.1200000000 0.0971449316 0.0593238192 0.1690268219 0.0079387286 0.9596660000 96745780 95654128 1788047360 0.0663703233 0.2007050663 0.6700650454 705 28.1600000000 0.0966405869 0.0593767508 0.1690268219 0.0079611433 0.9095730000 96746214 95654128 1784745984 0.0583388768 0.2047221512 0.6654164791 706 28.2000000000 0.0964179188 0.0594292170 0.1690268219 0.0079792267 0.9744180000 96747908 95654128 1786142720 0.0508785769 0.2047508359 0.6607058644 707 28.2400000000 0.0956313759 0.0594804223 0.1690268219 0.0079811555 1.0982790000 96749742 95654128 1788047360 0.0435471609 0.2079003453 0.6561894417 708 28.2800000000 0.0955773517 0.0595314067 0.1690268219 0.0079784680 0.8670780000 96750176 95654128 1784872960 0.0355848558 0.2125947475 0.6530471444 709 28.3200000000 0.0952455625 0.0595817793 0.1690268219 0.0079737066 0.8193890000 96754058 95654128 1786142720 0.0292435400 0.2096132785 0.6495170593 710 28.3600000000 0.0951632559 0.0596318940 0.1690268219 0.0079701080 0.7664470000 96924504 95654128 1785556992 0.0225683413 0.2114197612 0.6455495358 711 28.4000000000 0.0938695744 0.0596800483 0.1690268219 0.0079646757 0.9027820000 96924938 95654128 1784651776 0.0146718714 0.2181480080 0.6430481672 712 28.4400000000 0.0937128365 0.0597278472 0.1690268219 0.0079613922 0.8659750000 96926632 95654128 1785888768 0.0066033509 0.2205118090 0.6402089596 713 28.4800000000 0.0940388665 0.0597759692 0.1690268219 0.0079589219 0.8349140000 96928466 95654128 1787920384 0.0015188521 0.2184980512 0.6387585402 714 28.5200000000 0.0928994566 0.0598223606 0.1690268219 0.0079751348 0.7872740000 96928900 95654128 1784745984 -0.0063216090 0.2256073654 0.6370538473 715 28.5600000000 0.0917711556 0.0598670443 0.1690268219 0.0079701048 0.8505380000 96930594 95654128 1786015744 -0.0150906174 0.2316671163 0.6354016662 716 28.6000000000 0.0917176530 0.0599115284 0.1690268219 0.0079704643 0.8889500000 96932288 95654128 1787793408 -0.0219078474 0.2337621599 0.6370506287 717 28.6400000000 0.0913546830 0.0599553821 0.1690268219 0.0079674430 0.8368450000 96932722 95654128 1784492032 -0.0283120424 0.2356332988 0.6390161514 718 28.6800000000 0.0909772888 0.0599985881 0.1690268219 0.0079628630 0.9382630000 96934416 95654128 1785905152 -0.0355564728 0.2406103760 0.6411189437 719 28.7200000000 0.0910144448 0.0600417256 0.1690268219 0.0079612143 0.7489150000 96934990 95654128 1787793408 -0.0432811193 0.2443540096 0.6427789927 720 28.7600000000 0.0914667770 0.0600853715 0.1690268219 0.0079582629 0.8627940000 96936684 95654128 1784745984 -0.0506581217 0.2478797287 0.6463692188 721 28.8000000000 0.0912362561 0.0601285766 0.1690268219 0.0079531352 0.8037410000 96938378 95654128 1786142720 -0.0575721152 0.2496626824 0.6498266459 722 28.8400000000 0.0906789377 0.0601708902 0.1690268219 0.0079480354 0.8574330000 96938812 95654128 1787920384 -0.0656150505 0.2525098026 0.6525387168 723 28.8800000000 0.0906531662 0.0602130510 0.1690268219 0.0079426018 0.9011080000 96940506 95654128 1784745984 -0.0734940469 0.2547451556 0.6567729712 724 28.9200000000 0.0907661021 0.0602552513 0.1690268219 0.0079371924 0.9176680000 96942200 95654128 1786142720 -0.0817064568 0.2583003342 0.6611425281 725 28.9600000000 0.0902990177 0.0602966910 0.1690268219 0.0079342110 0.8173710000 96942774 95654128 1787920384 -0.0903680772 0.2613682151 0.6655192375 726 29.0000000000 0.0899962261 0.0603375995 0.1690268219 0.0079397906 0.8468430000 96944468 95654128 1784774656 -0.0990792811 0.2619573772 0.6709989309 727 29.0400000000 0.0902254507 0.0603787107 0.1690268219 0.0079405062 0.9317490000 96946162 95654128 1786142720 -0.1081384718 0.2661290467 0.6753543019 728 29.0800000000 0.0911055133 0.0604209178 0.1690268219 0.0079417246 1.0282520000 96946596 95654128 1787920384 -0.1169081479 0.2702990472 0.6816988587 729 29.1200000000 0.0919216871 0.0604641287 0.1690268219 0.0079383018 0.8024290000 96948290 95654128 1784619008 -0.1258516014 0.2754643857 0.6871502995 730 29.1600000000 0.0917213485 0.0605069469 0.1690268219 0.0079347210 0.7882770000 96949984 95654128 1786150912 -0.1347614825 0.2767573297 0.6930715442 731 29.2000000000 0.0910378769 0.0605487128 0.1690268219 0.0079304516 0.8687940000 96950558 95654128 1787928576 -0.1441291124 0.2789567709 0.6984040141 732 29.2400000000 0.0909110829 0.0605901915 0.1690268219 0.0079260691 0.7865010000 96952252 95654128 1784627200 -0.1542826146 0.2835522294 0.7040705681 733 29.2800000000 0.0916903690 0.0606326201 0.1690268219 0.0079210927 0.8596040000 96953946 95654128 1786023936 -0.1642157733 0.2881476879 0.7116685510 734 29.3200000000 0.0916400477 0.0606748646 0.1690268219 0.0079167437 1.0124640000 96954380 95654128 1787928576 -0.1740670651 0.2921308279 0.7191358209 735 29.3600000000 0.0915445685 0.0607168642 0.1690268219 0.0079137761 1.6722030000 96956074 95654128 1784619008 -0.1832349747 0.2961637378 0.7262262106 736 29.4000000000 0.0914590284 0.0607586334 0.1690268219 0.0079098446 1.5250140000 96960832 95654128 1786015744 -0.1920437813 0.3006671369 0.7343527079 737 29.4400000000 0.0918605551 0.0608008341 0.1690268219 0.0079053035 1.8895130000 97130134 95654128 1788047360 -0.2010310441 0.3047464490 0.7415128350 738 29.4800000000 0.0920434520 0.0608431683 0.1690268219 0.0079051239 1.8451990000 97131828 95654128 1784745984 -0.2100848705 0.3085457981 0.7492915392 739 29.5200000000 0.0922856629 0.0608857156 0.1690268219 0.0079196806 2.1108630000 97132262 95654128 1786015744 -0.2181299925 0.3123754859 0.7568540573 740 29.5600000000 0.0932206661 0.0609294115 0.1690268219 0.0079372168 0.8404350000 97133956 95654128 1788047360 -0.2252773494 0.3163869977 0.7654116750 741 29.6000000000 0.0931785330 0.0609729326 0.1690268219 0.0079652519 1.1212680000 97135650 95654128 1784745984 -0.2326890230 0.3204962611 0.7738457322 742 29.6400000000 0.0940545350 0.0610175170 0.1690268219 0.0079820161 2.0853630000 97136084 95654128 1786015744 -0.2393639088 0.3252823949 0.7823404670 743 29.6800000000 0.0948561355 0.0610630602 0.1690268219 0.0079806289 1.0277610000 97137918 95654128 1787793408 -0.2442645878 0.3276147842 0.7903862596 744 29.7200000000 0.0945385620 0.0611080541 0.1690268219 0.0079755988 0.9027400000 97139612 95654128 1784745984 -0.2497549206 0.3290097713 0.7965852022 745 29.7600000000 0.0944532007 0.0611528127 0.1690268219 0.0079721318 0.7857720000 97140046 95654128 1786159104 -0.2551261187 0.3314827681 0.8028462529 746 29.8000000000 0.0950795338 0.0611982909 0.1690268219 0.0079682297 1.0195420000 97141740 95654128 1787920384 -0.2601992488 0.3343666196 0.8085064888 747 29.8400000000 0.0952311680 0.0612438503 0.1690268219 0.0079631040 0.8100330000 97143434 95654128 1784774656 -0.2654830217 0.3381492496 0.8132827282 748 29.8800000000 0.0954312161 0.0612895553 0.1690268219 0.0079608136 0.7102480000 97143868 95654128 1786142720 -0.2710315585 0.3419416845 0.8182046413 749 29.9200000000 0.0958237052 0.0613356624 0.1690268219 0.0079572688 0.9061050000 97145702 95654128 1787920384 -0.2747132778 0.3457626700 0.8244131804 750 29.9600000000 0.0960321948 0.0613819244 0.1690268219 0.0079545177 0.8510440000 97147396 95654128 1784745984 -0.2784163654 0.3489868045 0.8301643133 751 30.0000000000 0.0972095653 0.0614296310 0.1690268219 0.0079509439 0.8003760000 97147830 95654128 1786142720 -0.2829190195 0.3524872661 0.8341878653 752 30.0400000000 0.0977562591 0.0614779377 0.1690268219 0.0079469031 0.8260160000 97149524 95654128 1787920384 -0.2865984738 0.3560591638 0.8380716443 753 30.0800000000 0.0977221802 0.0615260708 0.1690268219 0.0079476369 0.7611950000 97151218 95654128 1784774656 -0.2910071909 0.3576355875 0.8409860134 754 30.1200000000 0.0980418250 0.0615745002 0.1690268219 0.0079537184 0.9045080000 97154372 95654128 1786142720 -0.2947562635 0.3601105809 0.8443980813 755 30.1600000000 0.0983795375 0.0616232486 0.1690268219 0.0079647100 0.8288550000 97324966 95654128 1787920384 -0.2986654341 0.3622027338 0.8476210833 756 30.2000000000 0.0993482620 0.0616731494 0.1690268219 0.0079728522 0.7801060000 97325400 95654128 1784745984 -0.3031493723 0.3663850427 0.8506476283 757 30.2400000000 0.0993464515 0.0617229160 0.1690268219 0.0079750791 0.9914270000 97327094 95654128 1786142720 -0.3083402514 0.3695153892 0.8526986837 758 30.2800000000 0.0990697443 0.0617721862 0.1690268219 0.0079797132 0.9216440000 97328788 95654128 1787920384 -0.3135948181 0.3705821931 0.8560723066 759 30.3200000000 0.0981252268 0.0618200822 0.1690268219 0.0080021186 0.8543550000 97329222 95654128 1784619008 -0.3188051283 0.3725724220 0.8595092893 760 30.3600000000 0.0980363637 0.0618677352 0.1690268219 0.0080159869 0.8814520000 97330916 95654128 1786015744 -0.3246787190 0.3779295683 0.8621261120 761 30.4000000000 0.0973437428 0.0619143528 0.1690268219 0.0080308697 0.7673710000 97332750 95654128 1787920384 -0.3313063979 0.3799630702 0.8653010726 762 30.4400000000 0.0970281884 0.0619604339 0.1690268219 0.0080360868 0.8117270000 97333184 95654128 1784619008 -0.3383049965 0.3829163909 0.8675718904 763 30.4800000000 0.0967652798 0.0620060497 0.1690268219 0.0080349105 0.7061740000 97334878 95654128 1786150912 -0.3453729153 0.3871368170 0.8688685894 764 30.5200000000 0.0970956534 0.0620519785 0.1690268219 0.0080348085 1.0630750000 97336572 95654128 1788055552 -0.3530103564 0.3916624486 0.8707166314 765 30.5600000000 0.0971826836 0.0620979010 0.1690268219 0.0080328230 0.8272680000 97337006 95654128 1784754176 -0.3605791628 0.3961819708 0.8722932935 766 30.6000000000 0.0968062058 0.0621432121 0.1690268219 0.0080331890 0.7074420000 97338700 95654128 1786040320 -0.3681347370 0.3993045688 0.8747919798 767 30.6400000000 0.0958368257 0.0621871412 0.1690268219 0.0080316207 0.8355920000 97340534 95654128 1788055552 -0.3753254712 0.4031382799 0.8767144680 768 30.6800000000 0.0962228328 0.0622314585 0.1690268219 0.0080329018 0.9459190000 97340968 95654128 1784754176 -0.3833000064 0.4078413844 0.8782015443 769 30.7200000000 0.0970941037 0.0622767935 0.1690268219 0.0080333627 0.8479770000 97342662 95654128 1786023936 -0.3920409381 0.4132426083 0.8795579076 770 30.7600000000 0.0971252248 0.0623220512 0.1690268219 0.0080313497 0.8830440000 97344356 95654128 1787793408 -0.4007616937 0.4174490869 0.8812096119 771 30.8000000000 0.0968996435 0.0623668990 0.1690268219 0.0080274428 0.8691790000 97344790 95654128 1784745984 -0.4086489081 0.4217171073 0.8821088672 772 30.8400000000 0.0965854451 0.0624112235 0.1690268219 0.0080261345 0.9708270000 97346484 95654128 1786142720 -0.4167396724 0.4242625535 0.8830860853 773 30.8800000000 0.0962272584 0.0624549700 0.1690268219 0.0080267722 0.7872200000 97347058 95654128 1788047360 -0.4255499244 0.4267709851 0.8841453195 774 30.9200000000 0.0964775681 0.0624989268 0.1690268219 0.0080291943 0.9230570000 97348752 95654128 1784745984 -0.4336864948 0.4299040735 0.8847137094 775 30.9600000000 0.0961423218 0.0625423377 0.1690268219 0.0080351755 0.7970150000 97350446 95654128 1786159104 -0.4414633811 0.4314508438 0.8863407969 776 31.0000000000 0.0963284001 0.0625858764 0.1690268219 0.0080421954 0.8190950000 97353356 95654128 1787920384 -0.4496388435 0.4340808094 0.8875762820 777 31.0400000000 0.0965169892 0.0626295458 0.1690268219 0.0080533907 0.8933790000 97523830 95654128 1784745984 -0.4577878118 0.4379863739 0.8882476091 778 31.0800000000 0.0960391760 0.0626724888 0.1690268219 0.0080571950 0.7876090000 97525524 95654128 1786142720 -0.4657917917 0.4408862889 0.8895369768 779 31.1200000000 0.0960292444 0.0627153087 0.1690268219 0.0080561047 0.9618560000 97526098 95654128 1788047360 -0.4738775194 0.4429309070 0.8910998702 780 31.1600000000 0.0959014520 0.0627578551 0.1690268219 0.0080559087 1.0244650000 97527792 95654128 1784745984 -0.4810798168 0.4459416568 0.8918996453 781 31.2000000000 0.0962952599 0.0628007967 0.1690268219 0.0080538363 0.9753240000 97529486 95654128 1786142720 -0.4887980521 0.4488715827 0.8928914070 782 31.2400000000 0.0963573977 0.0628437079 0.1690268219 0.0080497512 0.8205700000 97529920 95654128 1787920384 -0.4961821437 0.4503391981 0.8933209777 783 31.2800000000 0.0964453444 0.0628866219 0.1690268219 0.0080456802 0.8062980000 97531614 95654128 1784745984 -0.5039971471 0.4517632723 0.8940474987 784 31.3200000000 0.0968788043 0.0629299793 0.1690268219 0.0080410206 0.9474800000 97533308 95654128 1786142720 -0.5107283592 0.4533611238 0.8959874511 785 31.3600000000 0.0972118825 0.0629736505 0.1690268219 0.0080360527 0.9880390000 97533882 95654128 1787920384 -0.5171872377 0.4546223283 0.8960064054 786 31.4000000000 0.0972617865 0.0630172741 0.1690268219 0.0080330174 0.9219800000 97535576 95654128 1784745984 -0.5230950713 0.4560144544 0.8971209526 787 31.4400000000 0.0975354239 0.0630611345 0.1690268219 0.0080291053 0.8977220000 97537270 95654128 1786159104 -0.5287658572 0.4584442377 0.8982127309 788 31.4800000000 0.0979269445 0.0631053805 0.1690268219 0.0080261854 0.8431370000 97537704 95654128 1787920384 -0.5343528390 0.4595577717 0.8995515108 789 31.5200000000 0.0981217474 0.0631497611 0.1690268219 0.0080238508 0.9256830000 97539398 95654128 1784745984 -0.5402324796 0.4594965875 0.9000886679 790 31.5600000000 0.0982627049 0.0631942079 0.1690268219 0.0080192532 0.8794480000 97541092 95654128 1786015744 -0.5456484556 0.4596823454 0.9011159539 791 31.6000000000 0.0986828431 0.0632390734 0.1690268219 0.0080146783 0.7697920000 97541666 95654128 1788047360 -0.5496726036 0.4611630142 0.9022291303 792 31.6400000000 0.0988161936 0.0632839941 0.1690268219 0.0080096956 0.8219990000 97543360 95654128 1784745984 -0.5535505414 0.4610844254 0.9043043852 793 31.6800000000 0.0991699398 0.0633292475 0.1690268219 0.0080056269 0.7971190000 97543794 95654128 1786015744 -0.5579383373 0.4603552818 0.9052890539 794 31.7200000000 0.0995305181 0.0633748410 0.1690268219 0.0080063660 0.8941910000 97545488 95654128 1788063744 -0.5616651773 0.4593589306 0.9066953659 795 31.7600000000 0.0996521115 0.0634204728 0.1690268219 0.0080169502 0.9129260000 97547182 95654128 1784668160 -0.5645052195 0.4588200152 0.9079643488 796 31.8000000000 0.1000749618 0.0634665211 0.1690268219 0.0080347296 1.0567450000 97547616 95654128 1786015744 -0.5677312613 0.4581718445 0.9096426964 797 31.8400000000 0.1000392288 0.0635124091 0.1690268219 0.0080521965 0.7410480000 97549450 95654128 1787793408 -0.5703484416 0.4567738771 0.9113218784 798 31.8800000000 0.1002681404 0.0635584689 0.1690268219 0.0080706679 0.7796180000 97551144 95654128 1784872960 -0.5732834935 0.4555834830 0.9121200442 799 31.9200000000 0.1002606601 0.0636044041 0.1690268219 0.0080810310 0.8216500000 97551578 95654128 1786142720 -0.5757536292 0.4538631439 0.9135462046 800 31.9600000000 0.1003271565 0.0636503075 0.1690268219 0.0080891963 0.7875270000 97553272 95654128 1787920384 -0.5782495737 0.4518677592 0.9147704244 801 32.0000000000 0.1010298356 0.0636969736 0.1690268219 0.0081034039 0.9764240000 97554966 95654128 1784745984 -0.5803308487 0.4510757923 0.9163956046 802 32.0400000000 0.1016652361 0.0637443156 0.1690268219 0.0081109826 1.1638700000 97555400 95654128 1786277888 -0.5825824738 0.4497393370 0.9177910686 803 32.0800000000 0.1017197743 0.0637916075 0.1690268219 0.0081205767 1.9510950000 97557234 95654128 1787928576 -0.5834810138 0.4493384659 0.9208177328 804 32.1199999990 0.1022714674 0.0638394681 0.1690268219 0.0081349480 1.0190340000 97558928 95654128 1784627200 -0.5850840211 0.4488301873 0.9229820371 805 32.1600000000 0.1025589257 0.0638875668 0.1690268219 0.0081510722 0.8561130000 97559362 95654128 1786023936 -0.5862259865 0.4474817812 0.9247196317 806 32.2000000000 0.1029565260 0.0639360394 0.1690268219 0.0081677268 0.9003730000 97561056 95654128 1787928576 -0.5874805450 0.4464513958 0.9262441993 807 32.2400000000 0.1033692434 0.0639849034 0.1690268219 0.0081854174 0.6722140000 97562750 95654128 1784672256 -0.5883381963 0.4436855316 0.9282618165 808 32.2800000000 0.1035029590 0.0640338118 0.1690268219 0.0081933958 0.7623100000 97563184 95654128 1786023936 -0.5900708437 0.4409149289 0.9307109118 809 32.3200000000 0.1042820737 0.0640835625 0.1690268219 0.0082011778 0.7954220000 97565018 95654128 1787928576 -0.5904287100 0.4381778240 0.9328568578 810 32.3600000000 0.1046644002 0.0641336623 0.1690268219 0.0082067168 0.7911940000 97565452 95654128 1784627200 -0.5913338065 0.4362027943 0.9348250628 811 32.4000000000 0.1048824862 0.0641839074 0.1690268219 0.0082059594 1.0272860000 97567146 95654128 1786023936 -0.5927373767 0.4323088229 0.9372735620 812 32.4399999990 0.1057851389 0.0642351405 0.1690268219 0.0082059733 0.9986940000 97568840 95654128 1787928576 -0.5939137340 0.4296490252 0.9392792583 813 32.4800000000 0.1059522033 0.0642864530 0.1690268219 0.0082055131 0.8122330000 97569274 95654128 1784745984 -0.5950939655 0.4263239205 0.9431838393 814 32.5200000000 0.1065416485 0.0643383635 0.1690268219 0.0082047790 0.6881720000 97570968 95654128 1786032128 -0.5962600708 0.4236266911 0.9466623068 815 32.5600000000 0.1063194200 0.0643898740 0.1690268219 0.0082027562 0.8251820000 97572802 95654128 1787920384 -0.5967991352 0.4205731153 0.9492259622 816 32.6000000000 0.1068706438 0.0644419338 0.1690268219 0.0082013347 0.8832630000 97573236 95654128 1784745984 -0.5970358849 0.4170200825 0.9524154663 817 32.6400000000 0.1067920625 0.0644937700 0.1690268219 0.0081979822 0.8134950000 97574930 95654128 1786015744 -0.5972453952 0.4139294326 0.9553860426 818 32.6800000000 0.1085206941 0.0645475926 0.1690268219 0.0081938211 0.8017230000 97576624 95654128 1788047360 -0.5989299417 0.4117205441 0.9587625861 819 32.7200000000 0.1093109101 0.0646022487 0.1690268219 0.0081904068 0.9624440000 97577058 95654128 1784745984 -0.5991820693 0.4107632339 0.9630060196 820 32.7599999990 0.1099469736 0.0646575471 0.1690268219 0.0081889592 0.8520410000 97578752 95654128 1786032128 -0.5990527272 0.4096626341 0.9677520394 821 32.7999999990 0.1100766733 0.0647128688 0.1690268219 0.0081926067 1.0294490000 97580586 95654128 1788047360 -0.5994964242 0.4069316983 0.9738454223 822 32.8400000000 0.1109148338 0.0647690756 0.1690268219 0.0082155037 0.9305180000 97581020 95654128 1784647680 -0.6003888845 0.4049648345 0.9785055518 823 32.8800000000 0.1109913737 0.0648252388 0.1690268219 0.0082243828 1.0547810000 97582714 95654128 1786015744 -0.6011471152 0.4028907716 0.9835672975 824 32.9200000000 0.1113962680 0.0648817570 0.1690268219 0.0082310819 2.4189580000 97584408 95654128 1787793408 -0.6016266346 0.4025935829 0.9886184335 825 32.9600000000 0.1121208742 0.0649390165 0.1690268219 0.0082433614 0.9739850000 97584842 95654128 1784745984 -0.6022903323 0.4009840488 0.9941111803 826 33.0000000000 0.1131258979 0.0649973542 0.1690268219 0.0082550187 0.9842410000 97586536 95654128 1786142720 -0.6032468677 0.4006995857 0.9998337626 827 33.0400000000 0.1141640544 0.0650568060 0.1690268219 0.0082713696 0.7878450000 97587110 95654128 1787920384 -0.6045429707 0.3984217346 1.0050698519 828 33.0800000000 0.1146365032 0.0651166849 0.1690268219 0.0082955185 0.7892070000 97588804 95654128 1784745984 -0.6049319506 0.3952111006 1.0104590654 829 33.1199999990 0.1156586036 0.0651776522 0.1690268219 0.0083169815 0.8394670000 97590498 95654128 1786159104 -0.6064285636 0.3928339183 1.0159664154 830 33.1600000000 0.1164958775 0.0652394814 0.1690268219 0.0083339028 1.0455630000 97590932 95654128 1787920384 -0.6072842479 0.3903468549 1.0216708183 831 33.2000000000 0.1170409769 0.0653018178 0.1690268219 0.0083521972 1.1826060000 97592626 95654128 1784619008 -0.6076447964 0.3857032061 1.0284380913 832 33.2400000000 0.1174440458 0.0653644887 0.1690268219 0.0083625768 1.3958930000 97594320 95654128 1786015744 -0.6082425117 0.3822407424 1.0348318815 833 33.2800000000 0.1184891537 0.0654282638 0.1690268219 0.0083649907 2.0126710000 97594894 95654128 1787920384 -0.6105324626 0.3791827261 1.0415301323 834 33.3200000000 0.1191500872 0.0654926785 0.1690268219 0.0083688348 0.8096570000 97596588 95654128 1784619008 -0.6120193601 0.3744260371 1.0477037430 835 33.3600000000 0.1190784872 0.0655568531 0.1690268219 0.0083728688 0.7971930000 97598282 95654128 1786015744 -0.6139892340 0.3712074161 1.0536400080 836 33.4000000000 0.1195339561 0.0656214190 0.1690268219 0.0083822581 0.8055920000 97598716 95654128 1788055552 -0.6154367328 0.3676791787 1.0603414774 837 33.4399999990 0.1204597130 0.0656869367 0.1690268219 0.0084003641 0.8991790000 97603254 95654128 1784655872 -0.6169958115 0.3660403788 1.0665242672 838 33.4800000000 0.1210482568 0.0657530003 0.1690268219 0.0084280916 0.8848710000 97773700 95654128 1786023936 -0.6179436445 0.3615617752 1.0721977949 839 33.5200000000 0.1220947653 0.0658201538 0.1690268219 0.0084613392 0.8181420000 97774274 95654128 1788055552 -0.6191696525 0.3599595129 1.0780140162 840 33.5600000000 0.1233194545 0.0658886053 0.1690268219 0.0084867127 0.7573910000 97775968 95654128 1784754176 -0.6212753057 0.3592824936 1.0818549395 841 33.6000000000 0.1237148494 0.0659573642 0.1690268219 0.0084879214 0.7707520000 97777662 95654128 1786150912 -0.6229789853 0.3575921655 1.0870149136 842 33.6400000000 0.1242454648 0.0660265900 0.1690268219 0.0084873866 1.0193960000 97778096 95654128 1788055552 -0.6244586110 0.3562186956 1.0912613869 843 33.6800000000 0.1250570863 0.0660966143 0.1690268219 0.0084888171 0.9216550000 97779790 95654128 1784754176 -0.6254767776 0.3539258838 1.0964090824 844 33.7200000000 0.1257166266 0.0661672542 0.1690268219 0.0084938935 0.9450080000 97781484 95654128 1786023936 -0.6263191104 0.3497997820 1.1014460325 845 33.7599999990 0.1269885153 0.0662392320 0.1690268219 0.0085087883 0.8783380000 97782058 95654128 1788055552 -0.6271904111 0.3477591574 1.1058977842 846 33.7999999990 0.1271654367 0.0663112488 0.1690268219 0.0085147531 0.8646060000 97783752 95654128 1784770560 -0.6280658841 0.3459819257 1.1107270718 847 33.8400000000 0.1277230829 0.0663837539 0.1690268219 0.0085131585 0.8050110000 97784186 95654128 1786023936 -0.6296240091 0.3415051401 1.1139049530 848 33.8800000000 0.1281116307 0.0664565462 0.1690268219 0.0085085934 0.8292880000 97785880 95654128 1787928576 -0.6303566098 0.3387612104 1.1177399158 849 33.9200000000 0.1289969236 0.0665302098 0.1690268219 0.0085039003 1.0194900000 97787574 95654128 1784627200 -0.6318997145 0.3340651095 1.1203722954 850 33.9600000000 0.1282915771 0.0666028702 0.1690268219 0.0084995348 1.8624430000 97788008 95654128 1786015744 -0.6325039864 0.3296869397 1.1241695881 851 34.0000000000 0.1286697984 0.0666758043 0.1690268219 0.0084945697 1.1018640000 97789842 95654128 1787920384 -0.6333909631 0.3274714053 1.1274061203 852 34.0400000000 0.1286427230 0.0667485354 0.1690268219 0.0084897679 1.4834290000 97791536 95654128 1784619008 -0.6336566210 0.3218996823 1.1306362152 853 34.0800000000 0.1283405572 0.0668207418 0.1690268219 0.0084864461 1.5291690000 97791970 95654128 1786015744 -0.6336306930 0.3184909225 1.1336599588 854 34.1199999990 0.1290882379 0.0668936546 0.1690268219 0.0084861314 0.9287240000 97793664 95654128 1787920384 -0.6346107125 0.3164964914 1.1365982294 855 34.1600000000 0.1293450147 0.0669666971 0.1690268219 0.0084869766 0.8505450000 97797654 95654128 1784619008 -0.6341248751 0.3137436211 1.1403412819 856 34.2000000000 0.1298154444 0.0670401185 0.1690268219 0.0084885286 0.7546790000 97966816 95654128 1786015744 -0.6342202425 0.3118402064 1.1436018944 857 34.2400000000 0.1312420666 0.0671150333 0.1690268219 0.0084848322 1.0316410000 97968650 95654128 1788047360 -0.6362917423 0.3118895888 1.1467182636 858 34.2800000000 0.1313042939 0.0671898459 0.1690268219 0.0084799776 1.7180160000 97970344 95654128 1784745984 -0.6378648877 0.3094217181 1.1495853662 859 34.3200000000 0.1314464658 0.0672646499 0.1690268219 0.0084754419 1.2319410000 97970778 95654128 1786142720 -0.6372780204 0.3038553298 1.1514072418 860 34.3600000000 0.1321008503 0.0673400408 0.1690268219 0.0084713186 1.4769870000 97972472 95654128 1788047360 -0.6380028725 0.2998457253 1.1529123783 861 34.4000000000 0.1315159649 0.0674145773 0.1690268219 0.0084666657 0.9718650000 97974166 95654128 1784745984 -0.6373652220 0.2965696156 1.1554783583 862 34.4400000000 0.1318612546 0.0674893415 0.1690268219 0.0084617982 0.6896200000 97974600 95654128 1786150912 -0.6372109056 0.2933243215 1.1571621895 863 34.4800000000 0.1314977407 0.0675635111 0.1690268219 0.0084577548 0.8389830000 97976434 95654128 1788055552 -0.6364047527 0.2873795927 1.1585444212 864 34.5200000000 0.1312688589 0.0676372442 0.1690268219 0.0084542181 0.9959190000 97976868 95654128 1784754176 -0.6372124553 0.2831655443 1.1601068974 865 34.5600000000 0.1306843013 0.0677101309 0.1690268219 0.0084494030 0.9857680000 97978562 95654128 1786150912 -0.6381291747 0.2814552784 1.1617926359 866 34.6000000000 0.1313857585 0.0677836594 0.1690268219 0.0084453012 1.0818050000 97980256 95654128 1788055552 -0.6391912699 0.2810644805 1.1628684998 867 34.6400000000 0.1304704547 0.0678559625 0.1690268219 0.0084423144 1.0519050000 97980690 95654128 1784754176 -0.6394746304 0.2769347131 1.1642621756 868 34.6800000000 0.1300832480 0.0679276529 0.1690268219 0.0084378299 0.8398910000 97982384 95654128 1786150912 -0.6399956942 0.2727445364 1.1651502848 869 34.7200000000 0.1302709579 0.0679993943 0.1690268219 0.0084342859 0.9898930000 97984218 95654128 1788055552 -0.6399008632 0.2693607509 1.1659955978 870 34.7600000000 0.1305904537 0.0680713381 0.1690268219 0.0084303134 0.9746920000 97984652 95654128 1784754176 -0.6422926188 0.2660441697 1.1672278643 871 34.8000000000 0.1312042773 0.0681438214 0.1690268219 0.0084264023 0.8942470000 97986346 95654128 1786032128 -0.6420305371 0.2659949958 1.1678147316 872 34.8400000000 0.1312262565 0.0682161636 0.1690268219 0.0084220575 1.0124860000 97988040 95654128 1787936768 -0.6438989639 0.2622925043 1.1688406467 873 34.8800000000 0.1314910650 0.0682886434 0.1690268219 0.0084180931 0.9602290000 97988474 95654128 1784762368 -0.6453590393 0.2598726749 1.1701830626 874 34.9200000000 0.1322555989 0.0683618322 0.1690268219 0.0084144774 1.1417420000 97990168 95654128 1786032128 -0.6470766664 0.2587847412 1.1711509228 875 34.9600000000 0.1320127398 0.0684345761 0.1690268219 0.0084112529 0.8409700000 97992002 95654128 1787809792 -0.6485075355 0.2586843371 1.1731914282 876 35.0000000000 0.1326262802 0.0685078543 0.1690268219 0.0084069152 0.7840850000 97992436 95654128 1784762368 -0.6493431926 0.2585894465 1.1738488674 877 35.0400000000 0.1305317581 0.0685785771 0.1690268219 0.0084022972 0.7994020000 97994130 95654128 1786175488 -0.6490578055 0.2566043139 1.1750694513 878 35.0800000000 0.1306053996 0.0686492227 0.1690268219 0.0083976322 0.7457780000 97995824 95654128 1787936768 -0.6497696638 0.2571476698 1.1761513948 879 35.1200000000 0.1324649006 0.0687218230 0.1690268219 0.0083931661 0.9448770000 97996258 95654128 1784762368 -0.6521306634 0.2572622895 1.1775941849 880 35.1600000000 0.1348252892 0.0687969406 0.1690268219 0.0083885104 0.8954390000 97997952 95654128 1786150912 -0.6543141603 0.2600122988 1.1788649559 881 35.2000000000 0.1356650740 0.0688728408 0.1690268219 0.0083841899 0.8596990000 97998526 95654128 1787928576 -0.6550036073 0.2611632049 1.1802357435 882 35.2400000000 0.1360808015 0.0689490403 0.1690268219 0.0083801498 0.9322360000 98000220 95654128 1784754176 -0.6550836563 0.2572710216 1.1810078621 ================================================ FILE: icra2018_results/tegra/memory_infinitam_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 05:59:26 Properties: ================= frame-limit: 0 log-file: output//memory_infinitam_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0597430000 8923125 955859216 1768988672 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025752268 0.0012876134 0.0025752268 0.0016431226 0.0897820000 9088907 955859216 1766846464 0.0001475584 -0.0015264876 0.0011166611 3 0.0800000000 0.0054430887 0.0026727718 0.0054430887 0.0017192722 0.0949580000 9090485 955859216 1765810176 -0.0038318611 -0.0031151283 0.0017624116 4 0.1200000000 0.0070806267 0.0037747356 0.0070806267 0.0015476567 0.0783950000 9092067 955859216 1765052416 -0.0022677977 -0.0055363895 0.0010813347 5 0.1600000000 0.0088763768 0.0047950638 0.0088763768 0.0013746952 0.0522730000 9093641 955859216 1765064704 -0.0045966683 -0.0063697565 0.0030369051 6 0.2000000000 0.0102836676 0.0057098311 0.0102836676 0.0012633804 0.0860970000 9095551 955859216 1765064704 -0.0038756605 -0.0083152633 0.0025941189 7 0.2400000000 0.0119049335 0.0065948457 0.0119049335 0.0012487813 0.0885220000 9096805 955859216 1765064704 -0.0037846602 -0.0100250626 0.0033162425 8 0.2800000000 0.0135537134 0.0074647042 0.0135537134 0.0012151469 0.0504240000 9098059 955859216 1765064704 -0.0048535271 -0.0114145745 0.0035833460 9 0.3200000000 0.0144994939 0.0082463475 0.0144994939 0.0012412189 0.0959810000 9099953 955859216 1765064704 -0.0065839612 -0.0129050696 0.0038821029 10 0.3600000000 0.0164364353 0.0090653563 0.0164364353 0.0012859367 0.0751830000 9102519 955859216 1765064704 -0.0065586180 -0.0136254942 0.0049675517 11 0.4000000000 0.0168208610 0.0097704022 0.0168208610 0.0015209797 0.0960850000 9103773 955859216 1765048320 -0.0073920619 -0.0148503836 0.0057736412 12 0.4400000000 0.0183891989 0.0104886352 0.0183891989 0.0018467156 0.0829480000 9105027 955859216 1765048320 -0.0073362282 -0.0165973045 0.0053857188 13 0.4800000000 0.0194620825 0.0111789004 0.0194620825 0.0019769403 0.0695530000 9106281 955859216 1765048320 -0.0093070837 -0.0177589189 0.0062027662 14 0.5200000000 0.0215980578 0.0119231259 0.0215980578 0.0019383622 0.0674580000 9107535 955859216 1765064704 -0.0092706047 -0.0187649578 0.0061609098 15 0.5600000000 0.0229644962 0.0126592173 0.0229644962 0.0018718496 0.0470440000 9108789 955859216 1765064704 -0.0118011450 -0.0189078078 0.0072193570 16 0.6000000000 0.0226317476 0.0132825004 0.0229644962 0.0018586901 0.0376670000 9110043 955859216 1766686720 -0.0113949236 -0.0204338618 0.0061442838 17 0.6400000000 0.0235379171 0.0138857602 0.0235379171 0.0018264788 0.0728750000 9112577 955859216 1765937152 -0.0131545905 -0.0226019658 0.0049283509 18 0.6800000000 0.0242423695 0.0144611274 0.0242423695 0.0017726472 0.0712870000 9116455 955859216 1764921344 -0.0144393304 -0.0231225416 0.0060585872 19 0.7200000000 0.0251637604 0.0150244239 0.0251637604 0.0017822440 0.0459720000 9117709 955859216 1766449152 -0.0158731714 -0.0237435065 0.0058728126 20 0.7600000000 0.0248112231 0.0155137638 0.0251637604 0.0018968832 0.0458590000 9118963 955859216 1765687296 -0.0188205540 -0.0246393383 0.0053884941 21 0.8000000000 0.0255656186 0.0159924236 0.0255656186 0.0018578846 0.1028640000 9120217 955859216 1765052416 -0.0216071624 -0.0244442672 0.0059025409 22 0.8400000000 0.0259808525 0.0164464431 0.0259808525 0.0018338707 0.0580290000 9121471 955859216 1765036032 -0.0269909985 -0.0256290380 0.0054998826 23 0.8800000000 0.0264334213 0.0168806595 0.0264334213 0.0017935829 0.0712620000 9122725 955859216 1765048320 -0.0269468036 -0.0270331521 0.0040376564 24 0.9200000000 0.0290597994 0.0173881237 0.0290597994 0.0017821474 0.0893490000 9123979 955859216 1765048320 -0.0341918580 -0.0279779620 0.0039193849 25 0.9600000000 0.0310401898 0.0179342063 0.0310401898 0.0017833433 0.0510710000 9125233 955859216 1766686720 -0.0355961137 -0.0287271813 0.0036785232 26 1.0000000000 0.0305415951 0.0184191059 0.0310401898 0.0017524110 0.0462380000 9126487 955859216 1765687296 -0.0414847545 -0.0297263749 0.0043636300 27 1.0400000000 0.0317068398 0.0189112442 0.0317068398 0.0018685308 0.0926110000 9127741 955859216 1765048320 -0.0470278114 -0.0315539911 0.0024883752 28 1.0800000000 0.0337449275 0.0194410186 0.0337449275 0.0020566351 0.0650310000 9128995 955859216 1765064704 -0.0515090376 -0.0317295343 0.0026655416 29 1.1200000000 0.0356403999 0.0199996180 0.0356403999 0.0022451838 0.0417620000 9130249 955859216 1766576128 -0.0572053567 -0.0333285481 0.0003417806 30 1.1600000000 0.0347846821 0.0204924534 0.0356403999 0.0022612490 0.0433460000 9131503 955859216 1765814272 -0.0664434433 -0.0332309455 0.0020062716 31 1.2000000000 0.0365135632 0.0210092634 0.0365135632 0.0022741087 0.0586840000 9132757 955859216 1765048320 -0.0729329214 -0.0341906324 0.0006580207 32 1.2400000000 0.0382344835 0.0215475516 0.0382344835 0.0023188853 0.0589950000 9134011 955859216 1765064704 -0.0794142336 -0.0354804695 -0.0012569270 33 1.2800000000 0.0381462350 0.0220505420 0.0382344835 0.0023853799 0.0486340000 9137825 955859216 1765064704 -0.0849456489 -0.0357755311 -0.0015584856 34 1.3200000000 0.0219009183 0.0220461413 0.0382344835 0.0027767556 0.0546990000 9144327 955859216 1766559744 -0.1155837253 -0.0208386444 -0.0059236633 35 1.3600000000 0.0269159060 0.0221852774 0.0382344835 0.0031667712 0.0514040000 9145581 955859216 1765937152 -0.1185286641 -0.0249475334 -0.0073525519 36 1.4000000000 0.0308910143 0.0224271034 0.0382344835 0.0037763084 0.0434040000 9146835 955859216 1764921344 -0.1235110909 -0.0278915986 -0.0082372036 37 1.4400000000 0.0266997945 0.0225425816 0.0382344835 0.0037812958 0.0800650000 9148089 955859216 1764937728 -0.1348779649 -0.0259018317 -0.0080238227 38 1.4800000000 0.0257545561 0.0226271072 0.0382344835 0.0037361464 0.0776680000 9149343 955859216 1765048320 -0.1467423290 -0.0255145412 -0.0075413943 39 1.5200000000 0.0296498705 0.0228071781 0.0382344835 0.0036957897 0.0495830000 9150597 955859216 1766559744 -0.1497326642 -0.0299596693 -0.0099029411 40 1.5600000000 0.0270953290 0.0229143818 0.0382344835 0.0036939666 0.0620920000 9151851 955859216 1765683200 -0.1597601175 -0.0291187819 -0.0099049201 41 1.6000000000 0.0262610428 0.0229960077 0.0382344835 0.0037119719 0.0403760000 9153105 955859216 1764925440 -0.1702446789 -0.0294303820 -0.0084053697 42 1.6400000000 0.0271362402 0.0230945847 0.0382344835 0.0036685778 0.0540840000 9154359 955859216 1764937728 -0.1833989918 -0.0287986696 -0.0060250689 43 1.6800000000 0.0303252600 0.0232627399 0.0382344835 0.0036352252 0.0390710000 9155613 955859216 1766449152 -0.1894266754 -0.0313700438 -0.0020287596 44 1.7200000000 0.0335428417 0.0234963786 0.0382344835 0.0036443579 0.0470350000 9156867 955859216 1765810176 -0.1955456734 -0.0352123603 -0.0032822082 45 1.7600000000 0.0372681618 0.0238024182 0.0382344835 0.0036358244 0.0881510000 9158121 955859216 1765052416 -0.2029312253 -0.0366865136 0.0011262335 46 1.8000000000 0.0399683081 0.0241538506 0.0399683081 0.0036286008 0.0620950000 9159375 955859216 1765036032 -0.2087789476 -0.0387890637 0.0019256566 47 1.8400000000 0.0405379795 0.0245024491 0.0405379795 0.0037270738 0.0401450000 9160629 955859216 1766559744 -0.2119554728 -0.0412287489 0.0018149428 48 1.8800000000 0.0420053862 0.0248670936 0.0420053862 0.0037508845 0.0642640000 9161883 955859216 1765171200 -0.2160210758 -0.0428644307 0.0032168275 49 1.9200000000 0.0443646014 0.0252650019 0.0443646014 0.0037148991 0.0454480000 9163137 955859216 1764929536 -0.2228544354 -0.0440333523 0.0045193080 50 1.9600000000 0.0251676328 0.0252630546 0.0443646014 0.0038266872 0.0988660000 9164391 955859216 1764937728 -0.2402646244 -0.0259116869 0.0049282685 51 2.0000000000 0.0294033252 0.0253442363 0.0443646014 0.0038211380 0.0656320000 9165645 955859216 1764937728 -0.2385586798 -0.0302304029 0.0030463508 52 2.0400000000 0.0334734619 0.0255005676 0.0443646014 0.0037917677 0.0406500000 9166899 955859216 1764937728 -0.2414333671 -0.0337014236 0.0031665994 53 2.0800000000 0.0354465730 0.0256882281 0.0443646014 0.0038144111 0.0486240000 9168153 955859216 1766559744 -0.2432961315 -0.0379862748 0.0004866123 54 2.1200000000 0.0258681327 0.0256915596 0.0443646014 0.0040138195 0.0653220000 9169407 955859216 1766064128 -0.2575142086 -0.0303003844 0.0039268299 55 2.1600000000 0.0309068579 0.0257863832 0.0443646014 0.0040591542 0.0849500000 9170661 955859216 1765048320 -0.2591560185 -0.0344233178 0.0048095430 56 2.2000000000 0.0258368682 0.0257872848 0.0443646014 0.0041011532 0.0875730000 9171915 955859216 1765064704 -0.2797059119 -0.0290847048 0.0127215888 57 2.2400000000 0.0277807061 0.0258222571 0.0443646014 0.0040724847 0.0453960000 9173169 955859216 1765064704 -0.2843071520 -0.0336441770 0.0137705635 58 2.2800000000 0.0279265717 0.0258585383 0.0443646014 0.0040762066 0.0864250000 9174423 955859216 1765048320 -0.2935943305 -0.0344273597 0.0165719502 59 2.3200000000 0.0288981535 0.0259100572 0.0443646014 0.0042122720 0.0793200000 9175677 955859216 1765064704 -0.3075576425 -0.0330300443 0.0224262476 60 2.3600000000 0.0308657605 0.0259926523 0.0443646014 0.0043343359 0.0859600000 9176931 955859216 1765064704 -0.3106798530 -0.0366725512 0.0210262630 61 2.4000000000 0.0325958021 0.0261009007 0.0443646014 0.0044638887 0.0529860000 9178185 955859216 1765064704 -0.3167955577 -0.0397553146 0.0211276542 62 2.4400000000 0.0260268208 0.0260997058 0.0443646014 0.0045540342 0.0973790000 9179439 955859216 1765064704 -0.3417776823 -0.0328675658 0.0298994966 63 2.4800000000 0.0271837171 0.0261169124 0.0443646014 0.0047037866 0.0770370000 9180693 955859216 1765064704 -0.3502507508 -0.0351225026 0.0313153677 64 2.5200000000 0.0281934943 0.0261493589 0.0443646014 0.0050608738 0.1005620000 9181947 955859216 1765064704 -0.3625961244 -0.0348887853 0.0360408127 65 2.5600000000 0.0282612685 0.0261818499 0.0443646014 0.0053568778 0.0564270000 9188321 955859216 1765064704 -0.3763555884 -0.0351098031 0.0397563688 66 2.6000000000 0.0293185078 0.0262293750 0.0443646014 0.0054467955 0.0865910000 9200071 955859216 1765064704 -0.3868583441 -0.0348285511 0.0419081934 67 2.6400000000 0.0304715242 0.0262926906 0.0443646014 0.0055019650 0.0545040000 9201325 955859216 1766686720 -0.3969154656 -0.0334539786 0.0443790779 68 2.6800000000 0.0303942617 0.0263530079 0.0443646014 0.0054821671 0.0794570000 9202579 955859216 1766178816 -0.4080621302 -0.0335885808 0.0436426289 69 2.7200000000 0.0301158074 0.0264075412 0.0443646014 0.0054436257 0.0857780000 9203833 955859216 1765302272 -0.4176534116 -0.0330484509 0.0480417050 70 2.7600000000 0.0359606110 0.0265440136 0.0443646014 0.0054105779 0.0566730000 9205087 955859216 1764712448 -0.4255230427 -0.0368664749 0.0489397645 71 2.8000000000 0.0408406928 0.0267453753 0.0443646014 0.0054327367 0.0701640000 9206341 955859216 1764823040 -0.4319741428 -0.0409863591 0.0469274223 72 2.8400000000 0.0275084339 0.0267559733 0.0443646014 0.0063415714 0.0598900000 9207595 955859216 1764823040 -0.4500095844 -0.0229855273 0.0466943905 73 2.8800000000 0.0308365487 0.0268118716 0.0443646014 0.0063847413 0.0952510000 9208849 955859216 1764823040 -0.4595466554 -0.0248328596 0.0490876436 74 2.9200000000 0.0377616137 0.0269598411 0.0443646014 0.0064306119 0.0585420000 9210103 955859216 1766334464 -0.4606540203 -0.0298467930 0.0474782549 75 2.9600000000 0.0447686128 0.0271972914 0.0447686128 0.0064506636 0.0450140000 9211357 955859216 1765830656 -0.4608754218 -0.0329297148 0.0461710058 76 3.0000000000 0.0292834621 0.0272247410 0.0447686128 0.0065971554 0.0790470000 9212611 955859216 1765052416 -0.4613790214 -0.0148873935 0.0345981121 77 3.0400000000 0.0325167440 0.0272934683 0.0447686128 0.0065950378 0.0849460000 9213865 955859216 1765064704 -0.4612707794 -0.0176940542 0.0284674540 78 3.0800000000 0.0292143505 0.0273180950 0.0447686128 0.0065643676 0.0935070000 9215119 955859216 1765064704 -0.4601801634 -0.0132636512 0.0205534101 79 3.1200000000 0.0370622911 0.0274414393 0.0447686128 0.0065430195 0.0545170000 9216373 955859216 1765048320 -0.4658182859 -0.0177644398 0.0200869441 80 3.1600000000 0.0434243754 0.0276412260 0.0447686128 0.0065233012 0.0596200000 9217627 955859216 1765064704 -0.4683842063 -0.0210742205 0.0177453607 81 3.2000000000 0.0289335102 0.0276571801 0.0447686128 0.0065045672 0.0801220000 9218881 955859216 1765064704 -0.4826539159 -0.0080731325 0.0175626799 82 3.2400000000 0.0303027797 0.0276894435 0.0447686128 0.0065127666 0.0733960000 9220135 955859216 1765064704 -0.4907025993 -0.0092855459 0.0173263848 83 3.2800000000 0.0311443917 0.0277310694 0.0447686128 0.0065524551 0.0684010000 9221389 955859216 1765064704 -0.4982014298 -0.0080167893 0.0143028507 84 3.3200000000 0.0306372344 0.0277656666 0.0447686128 0.0065410422 0.0774920000 9222643 955859216 1766686720 -0.5108985901 -0.0086666830 0.0144736320 85 3.3600000000 0.0290064793 0.0277802644 0.0447686128 0.0065215949 0.1016170000 9223897 955859216 1764700160 -0.5249118805 -0.0061452128 0.0145513872 86 3.4000000000 0.0297695398 0.0278033955 0.0447686128 0.0065635338 0.0875390000 9225151 955859216 1764679680 -0.5395122766 -0.0061611622 0.0186737198 87 3.4400000000 0.0293374863 0.0278210287 0.0447686128 0.0066824379 0.0908450000 9226405 955859216 1764679680 -0.5493972301 -0.0068779238 0.0182747245 88 3.4800000000 0.0292987041 0.0278378205 0.0447686128 0.0068285460 0.0964810000 9227659 955859216 1764679680 -0.5624472499 -0.0065045129 0.0185360890 89 3.5200000000 0.0291304197 0.0278523441 0.0447686128 0.0069592609 0.0594530000 9228913 955859216 1766178816 -0.5718234777 -0.0061397082 0.0186264683 90 3.5600000000 0.0287340786 0.0278621411 0.0447686128 0.0070499205 0.0956620000 9230167 955859216 1765076992 -0.5794012547 -0.0075505232 0.0173353124 91 3.6000000000 0.0286356658 0.0278706414 0.0447686128 0.0070889276 0.0982540000 9231421 955859216 1765060608 -0.5939218402 -0.0087087462 0.0203020256 92 3.6400000000 0.0288674440 0.0278814762 0.0447686128 0.0070972154 0.0605380000 9232675 955859216 1766572032 -0.6090324521 -0.0068038553 0.0254713297 93 3.6800000000 0.0287807789 0.0278911461 0.0447686128 0.0070756718 0.0640460000 9233929 955859216 1765560320 -0.6138251424 -0.0076507642 0.0220562536 94 3.7200000000 0.0306319073 0.0279203032 0.0447686128 0.0070495572 0.0644850000 9235183 955859216 1764933632 -0.6200987697 -0.0116948634 0.0218572766 95 3.7600000000 0.0289958511 0.0279316247 0.0447686128 0.0070273414 0.1190190000 9236437 955859216 1764937728 -0.6339729428 -0.0088836011 0.0281564593 96 3.8000000000 0.0289122965 0.0279418401 0.0447686128 0.0069981539 0.0752070000 9237691 955859216 1764937728 -0.6441277266 -0.0093512414 0.0276850648 97 3.8400000000 0.0300172865 0.0279632364 0.0447686128 0.0069627495 0.0544390000 9238945 955859216 1764937728 -0.6491667032 -0.0130952196 0.0297213048 98 3.8800000000 0.0288958456 0.0279727528 0.0447686128 0.0069340237 0.0789820000 9240199 955859216 1765048320 -0.6642112732 -0.0126719847 0.0336497724 99 3.9200000000 0.0317927301 0.0280113385 0.0447686128 0.0069086868 0.0485360000 9241453 955859216 1764876288 -0.6686010361 -0.0139818145 0.0370281786 100 3.9600000000 0.0329822972 0.0280610481 0.0447686128 0.0068742564 0.0645550000 9242707 955859216 1764876288 -0.6763663888 -0.0155566279 0.0411809422 101 4.0000000000 0.0329105817 0.0281090632 0.0447686128 0.0068412904 0.0833140000 9243961 955859216 1764876288 -0.6850119233 -0.0171872266 0.0471811183 102 4.0400000000 0.0336099006 0.0281629930 0.0447686128 0.0068169826 0.0747350000 9245215 955859216 1764876288 -0.6883314848 -0.0192921534 0.0489087924 103 4.0800000000 0.0301989950 0.0281827600 0.0447686128 0.0067864975 0.0625390000 9246469 955859216 1766510592 -0.7005796432 -0.0165795051 0.0552164353 104 4.1200000000 0.0291872714 0.0281924188 0.0447686128 0.0067577530 0.0527090000 9247723 955859216 1765662720 -0.7136455774 -0.0173745621 0.0679286197 105 4.1600000000 0.0312364660 0.0282214097 0.0447686128 0.0067604498 0.0512900000 9248977 955859216 1764999168 -0.7153851986 -0.0194859616 0.0698706359 106 4.2000000000 0.0324825309 0.0282616090 0.0447686128 0.0067691322 0.0548490000 9250231 955859216 1765015552 -0.7212490439 -0.0200149585 0.0749783590 107 4.2400000000 0.0297942981 0.0282759332 0.0447686128 0.0067456859 0.0598180000 9251485 955859216 1766526976 -0.7229481339 -0.0208330695 0.0711614490 108 4.2800000000 0.0293417405 0.0282858018 0.0447686128 0.0067146203 0.0535790000 9252739 955859216 1765908480 -0.7326760292 -0.0213696435 0.0795544982 109 4.3200000000 0.0318425000 0.0283184320 0.0447686128 0.0066977815 0.0666220000 9253993 955859216 1765019648 -0.7332743406 -0.0236411877 0.0808008015 110 4.3600000000 0.0318940580 0.0283509377 0.0447686128 0.0067021176 0.0631520000 9255247 955859216 1766526976 -0.7411254048 -0.0242553111 0.0891570225 111 4.4000000000 0.0317267627 0.0283813505 0.0447686128 0.0067007658 0.0507450000 9256501 955859216 1766129664 -0.7474588752 -0.0253920183 0.0958426148 112 4.4400000000 0.0326870345 0.0284197941 0.0447686128 0.0067025805 0.0566680000 9257755 955859216 1765019648 -0.7548301816 -0.0257092528 0.1037217230 113 4.4800000000 0.0331779569 0.0284619018 0.0447686128 0.0067083348 0.0675720000 9259009 955859216 1765015552 -0.7586858273 -0.0262651965 0.1079470664 114 4.5200000000 0.0300231203 0.0284755967 0.0447686128 0.0067398294 0.0947470000 9260263 955859216 1765015552 -0.7710567713 -0.0235413425 0.1201017797 115 4.5600000000 0.0315203220 0.0285020726 0.0447686128 0.0067638026 0.0591620000 9261517 955859216 1765015552 -0.7710288763 -0.0249196179 0.1220005453 116 4.6000000000 0.0301116388 0.0285159481 0.0447686128 0.0067962326 0.0918340000 9262771 955859216 1765015552 -0.7820402980 -0.0210496075 0.1339241266 117 4.6400000000 0.0327633582 0.0285522508 0.0447686128 0.0068083493 0.1014760000 9264025 955859216 1765015552 -0.7884753346 -0.0205718502 0.1443421096 118 4.6800000000 0.0333243757 0.0285926925 0.0447686128 0.0067802338 0.0838510000 9265279 955859216 1765015552 -0.7933770418 -0.0225928668 0.1485173106 119 4.7200000000 0.0343361981 0.0286409573 0.0447686128 0.0067548542 0.0626700000 9266533 955859216 1766526976 -0.7992933989 -0.0239765830 0.1555526853 120 4.7600000000 0.0356825739 0.0286996374 0.0447686128 0.0067277280 0.0807650000 9267787 955859216 1766014976 -0.8054308891 -0.0239614192 0.1637705564 121 4.8000000000 0.0308889560 0.0287177309 0.0447686128 0.0067150643 0.0658860000 9269041 955859216 1764999168 -0.8171624541 -0.0199127514 0.1815876365 122 4.8400000000 0.0342238806 0.0287628633 0.0447686128 0.0066894708 0.0702640000 9270295 955859216 1764986880 -0.8170667887 -0.0215859804 0.1822866350 123 4.8800000000 0.0368626975 0.0288287156 0.0447686128 0.0066685871 0.0609580000 9271549 955859216 1764999168 -0.8214331865 -0.0198947228 0.1885077506 124 4.9200000000 0.0301455166 0.0288393350 0.0447686128 0.0066436297 0.0654380000 9272803 955859216 1766510592 -0.8339167237 -0.0128631145 0.2046166956 125 4.9600000000 0.0321675800 0.0288659610 0.0447686128 0.0066360222 0.0600260000 9274057 955859216 1766023168 -0.8371079564 -0.0149000483 0.2095066160 126 5.0000000000 0.0338458493 0.0289054839 0.0447686128 0.0066179141 0.0586980000 9275311 955859216 1765126144 -0.8411905169 -0.0152961574 0.2167517692 127 5.0400000000 0.0298366603 0.0289128160 0.0447686128 0.0065937661 0.0733280000 9276565 955859216 1765031936 -0.8525592089 -0.0105889989 0.2338444591 128 5.0800000000 0.0325667709 0.0289413625 0.0447686128 0.0065686932 0.0541690000 9277819 955859216 1766543360 -0.8565690517 -0.0133000119 0.2394678444 129 5.1200000000 0.0336138010 0.0289775830 0.0447686128 0.0065449940 0.0607080000 9289313 955859216 1765638144 -0.8601045609 -0.0139219994 0.2461022884 130 5.1600000000 0.0303348619 0.0289880236 0.0447686128 0.0065344195 0.0915410000 9311559 955859216 1765003264 -0.8702767491 -0.0109108556 0.2643425465 131 5.2000000000 0.0316219740 0.0290081301 0.0447686128 0.0065651715 0.0841570000 9312813 955859216 1765015552 -0.8731666803 -0.0115237832 0.2682974339 132 5.2400000000 0.0300591607 0.0290160924 0.0447686128 0.0065733029 0.0613260000 9314067 955859216 1765015552 -0.8743199706 -0.0103790732 0.2661243081 133 5.2800000000 0.0297808889 0.0290218428 0.0447686128 0.0065718615 0.0985090000 9315321 955859216 1764986880 -0.8846463561 -0.0098869167 0.2851698399 134 5.3200000000 0.0297434237 0.0290272277 0.0447686128 0.0065988416 0.0812510000 9316575 955859216 1765015552 -0.8933590055 -0.0073907366 0.3014890254 135 5.3600000000 0.0293396153 0.0290295417 0.0447686128 0.0066169847 0.0889280000 9317829 955859216 1765015552 -0.8967777491 -0.0066297427 0.3054390252 136 5.4000000000 0.0290671084 0.0290298179 0.0447686128 0.0066506716 0.0616540000 9319083 955859216 1765015552 -0.9037781358 -0.0062935911 0.3175323904 137 5.4400000000 0.0297648013 0.0290351827 0.0447686128 0.0067036824 0.1019210000 9320337 955859216 1765015552 -0.9086287022 -0.0065906439 0.3265962899 138 5.4800000000 0.0287103448 0.0290328288 0.0447686128 0.0067421208 0.0786520000 9321591 955859216 1765015552 -0.9147295356 -0.0064089210 0.3314349949 139 5.5200000000 0.0283774883 0.0290281142 0.0447686128 0.0067830255 0.0632770000 9322845 955859216 1765015552 -0.9208660722 -0.0081237229 0.3366904259 140 5.5600000000 0.0283862166 0.0290235292 0.0447686128 0.0068520375 0.0712410000 9324099 955859216 1766526976 -0.9301093817 -0.0073892884 0.3509109914 141 5.6000000000 0.0283796471 0.0290189626 0.0447686128 0.0068842083 0.0630430000 9325353 955859216 1765752832 -0.9355041981 -0.0061428668 0.3563733995 142 5.6400000000 0.0281557012 0.0290128833 0.0447686128 0.0069172522 0.0904320000 9326607 955859216 1765019648 -0.9446830153 -0.0058716298 0.3709899485 143 5.6800000000 0.0296689775 0.0290174714 0.0447686128 0.0069941737 0.0893610000 9327861 955859216 1765015552 -0.9492162466 -0.0050605498 0.3807179034 144 5.7200000000 0.0282708257 0.0290122864 0.0447686128 0.0070339390 0.0680490000 9329115 955859216 1764859904 -0.9560825825 -0.0020087082 0.3887082338 145 5.7600000000 0.0278070699 0.0290039745 0.0447686128 0.0070324933 0.0606580000 9330369 955859216 1764999168 -0.9617613554 -0.0024532024 0.3954329193 146 5.8000000000 0.0278107468 0.0289958017 0.0447686128 0.0070230810 0.0621930000 9331623 955859216 1764999168 -0.9675350785 -0.0023514591 0.4048217535 147 5.8400000000 0.0276998449 0.0289869857 0.0447686128 0.0070058838 0.0745370000 9332877 955859216 1766637568 -0.9776761532 -0.0030037221 0.4256345630 148 5.8800000000 0.0274758413 0.0289767753 0.0447686128 0.0069845010 0.0612950000 9334131 955859216 1766526976 -0.9791069031 -0.0029311348 0.4289702773 149 5.9200000000 0.0298179351 0.0289824206 0.0447686128 0.0069683516 0.0852550000 9335385 955859216 1765761024 -0.9824397564 -0.0044173431 0.4396760166 150 5.9600000000 0.0303075798 0.0289912550 0.0447686128 0.0069493594 0.0905800000 9336639 955859216 1765003264 -0.9858954549 -0.0051437565 0.4483737350 151 6.0000000000 0.0309804324 0.0290044284 0.0447686128 0.0069301216 0.0606830000 9337893 955859216 1765015552 -0.9889296889 -0.0053595696 0.4579939842 152 6.0400000000 0.0317189395 0.0290222870 0.0447686128 0.0069163582 0.1097800000 9339147 955859216 1765015552 -0.9916940331 -0.0047115888 0.4686135054 153 6.0800000000 0.0306731164 0.0290330767 0.0447686128 0.0069043421 0.0846610000 9340401 955859216 1765015552 -0.9955854416 -0.0047187875 0.4771936536 154 6.1200000000 0.0277802739 0.0290249417 0.0447686128 0.0069181775 0.0889590000 9341655 955859216 1765015552 -1.0010762215 -0.0025232658 0.4897629023 155 6.1600000000 0.0269163661 0.0290113380 0.0447686128 0.0069762985 0.0797030000 9342909 955859216 1764999168 -1.0030705929 -0.0025526173 0.4975075722 156 6.2000000000 0.0270295739 0.0289986343 0.0447686128 0.0070844975 0.0651060000 9344163 955859216 1764999168 -1.0075756311 -0.0015088057 0.5121774077 157 6.2400000000 0.0270290226 0.0289860890 0.0447686128 0.0071717792 0.0864450000 9345417 955859216 1764999168 -1.0096888542 -0.0008356311 0.5228844285 158 6.2800000000 0.0267178174 0.0289717329 0.0447686128 0.0072450392 0.0587680000 9346671 955859216 1765015552 -1.0127689838 -0.0001865551 0.5392236114 159 6.3200000000 0.0265871808 0.0289567357 0.0447686128 0.0072731303 0.0658970000 9347925 955859216 1765015552 -1.0135490894 -0.0007016733 0.5471454263 160 6.3600000000 0.0278500989 0.0289498192 0.0447686128 0.0073122829 0.0608810000 9349179 955859216 1766526976 -1.0139187574 -0.0004543550 0.5619804859 161 6.4000000000 0.0293342657 0.0289522071 0.0447686128 0.0072974249 0.0727760000 9350433 955859216 1765888000 -1.0135970116 -0.0014594942 0.5728167295 162 6.4400000000 0.0294710435 0.0289554098 0.0447686128 0.0072771254 0.0558790000 9351687 955859216 1765019648 -1.0136089325 -0.0033538933 0.5839217305 163 6.4800000000 0.0313397422 0.0289700376 0.0447686128 0.0072601368 0.0538240000 9352941 955859216 1765015552 -1.0139015913 -0.0038643372 0.5966669917 164 6.5200000000 0.0332329683 0.0289960311 0.0447686128 0.0072417495 0.0608500000 9354195 955859216 1766526976 -1.0135561228 -0.0043877144 0.6085105538 165 6.5600000000 0.0263508521 0.0289799997 0.0447686128 0.0072380340 0.0713320000 9355449 955859216 1765888000 -1.0164600611 0.0035822387 0.6266128421 166 6.6000000000 0.0314591452 0.0289949343 0.0447686128 0.0072477075 0.0689660000 9356703 955859216 1765019648 -1.0144360065 -0.0007753448 0.6379907131 167 6.6400000000 0.0346696526 0.0290289146 0.0447686128 0.0072499372 0.0655000000 9357957 955859216 1764999168 -1.0124968290 -0.0019965395 0.6481626034 168 6.6800000000 0.0352408066 0.0290658902 0.0447686128 0.0072491122 0.0555930000 9359211 955859216 1766510592 -1.0115426779 -0.0023457708 0.6601836085 169 6.7200000000 0.0334325135 0.0290917282 0.0447686128 0.0072355950 0.0578630000 9360465 955859216 1765740544 -1.0117241144 -0.0027230270 0.6742987633 170 6.7600000000 0.0263996236 0.0290758923 0.0447686128 0.0072258706 0.0833050000 9361719 955859216 1765011456 -1.0159307718 0.0062115556 0.6922356486 171 6.8000000000 0.0297699850 0.0290799513 0.0447686128 0.0072207253 0.0591930000 9362973 955859216 1765007360 -1.0142130852 0.0056835674 0.7016852498 172 6.8400000000 0.0311641563 0.0290920688 0.0447686128 0.0072021107 0.0680190000 9364227 955859216 1765007360 -1.0129600763 0.0056178384 0.7138277888 173 6.8800000000 0.0324886180 0.0291117020 0.0447686128 0.0071823813 0.0722620000 9365481 955859216 1765007360 -1.0127382278 0.0059216474 0.7273181081 174 6.9200000000 0.0333527885 0.0291360761 0.0447686128 0.0071622844 0.0551670000 9366735 955859216 1766629376 -1.0135252476 0.0068576224 0.7397354841 175 6.9600000000 0.0261424594 0.0291189697 0.0447686128 0.0071445959 0.0675120000 9367989 955859216 1766133760 -1.0152844191 0.0147919469 0.7525563836 176 7.0000000000 0.0266936496 0.0291051895 0.0447686128 0.0071280099 0.1027130000 9369243 955859216 1765117952 -1.0164997578 0.0146257430 0.7670995593 177 7.0400000000 0.0264057685 0.0290899385 0.0447686128 0.0071377960 0.0777130000 9370497 955859216 1765023744 -1.0155614614 0.0125228669 0.7742293477 178 7.0800000000 0.0292521138 0.0290908496 0.0447686128 0.0071220900 0.0674280000 9371751 955859216 1764978688 -1.0137115717 0.0092075504 0.7816981077 179 7.1200000000 0.0270649977 0.0290795320 0.0447686128 0.0071067939 0.0890040000 9373005 955859216 1764990976 -1.0138485432 0.0139738061 0.7948889732 180 7.1600000000 0.0307319779 0.0290887122 0.0447686128 0.0070885857 0.0649540000 9374259 955859216 1764990976 -1.0119001865 0.0127911046 0.8072835207 181 7.2000000000 0.0324875563 0.0291074904 0.0447686128 0.0070725718 0.0656840000 9375513 955859216 1765007360 -1.0095129013 0.0117498450 0.8183924556 182 7.2400000000 0.0333156735 0.0291306123 0.0447686128 0.0070546541 0.0699710000 9376767 955859216 1766518784 -1.0092332363 0.0112504140 0.8315385580 183 7.2800000000 0.0254665725 0.0291105902 0.0447686128 0.0070458354 0.0628490000 9378021 955859216 1765756928 -1.0133780241 0.0194710419 0.8488326669 184 7.3200000000 0.0280841179 0.0291050115 0.0447686128 0.0070272456 0.0993700000 9379275 955859216 1765138432 -1.0105569363 0.0165049918 0.8593403697 185 7.3600000000 0.0299452376 0.0291095533 0.0447686128 0.0070113333 0.0613000000 9380529 955859216 1765023744 -1.0081822872 0.0150537193 0.8736750484 186 7.4000000000 0.0250517596 0.0290877372 0.0447686128 0.0069981415 0.0830530000 9381783 955859216 1765023744 -1.0099527836 0.0195820611 0.8928787708 187 7.4400000000 0.0255823173 0.0290689917 0.0447686128 0.0069913608 0.0802990000 9383037 955859216 1765023744 -1.0067065954 0.0191324446 0.9013009667 188 7.4800000000 0.0298654605 0.0290732282 0.0447686128 0.0070034742 0.0782320000 9384291 955859216 1765023744 -1.0030500889 0.0185145941 0.9159898758 189 7.5200000000 0.0247366894 0.0290502835 0.0447686128 0.0069879555 0.1116210000 9385545 955859216 1765007360 -1.0024032593 0.0262695793 0.9341076612 190 7.5600000000 0.0282294154 0.0290459632 0.0447686128 0.0069752648 0.0700690000 9386799 955859216 1766518784 -0.9990338683 0.0217475016 0.9481745362 191 7.6000000000 0.0243646782 0.0290214538 0.0447686128 0.0069626249 0.0919440000 9388053 955859216 1768423424 -0.9989247918 0.0278186798 0.9650231600 192 7.6400000000 0.0311478488 0.0290325288 0.0447686128 0.0069613304 0.0581990000 9389307 955859216 1770057728 -0.9934813976 0.0272609089 0.9794622660 193 7.6800000000 0.0241604503 0.0290072849 0.0447686128 0.0069683453 0.0613900000 9390561 955859216 1771851776 -0.9953159094 0.0345419683 0.9980971813 194 7.7200000000 0.0245263986 0.0289841875 0.0447686128 0.0069634442 0.0625190000 9391815 955859216 1773486080 -0.9954822063 0.0301162191 1.0141148567 195 7.7600000000 0.0245574042 0.0289614861 0.0447686128 0.0069657744 0.0673810000 9393069 955859216 1775136768 -0.9942715764 0.0298271067 1.0269956589 196 7.8000000000 0.0250499230 0.0289415291 0.0447686128 0.0070015282 0.0650790000 9394323 955859216 1776914432 -0.9922564626 0.0329516977 1.0435712337 197 7.8400000000 0.0249918867 0.0289214802 0.0447686128 0.0070258187 0.1019510000 9395577 955859216 1778565120 -0.9904983044 0.0365127139 1.0555113554 198 7.8800000000 0.0249423347 0.0289013835 0.0447686128 0.0070434148 0.0679990000 9396831 955859216 1780215808 -0.9893478155 0.0402547121 1.0719903708 199 7.9200000000 0.0242904779 0.0288782131 0.0447686128 0.0070358315 0.0586290000 9398085 955859216 1781993472 -0.9874849319 0.0418963172 1.0876870155 200 7.9600000000 0.0236445200 0.0288520446 0.0447686128 0.0070255954 0.0597650000 9399339 955859216 1783644160 -0.9875364900 0.0410159789 1.1016032696 201 8.0000000000 0.0236467719 0.0288261478 0.0447686128 0.0070402003 0.0656230000 9400593 955859216 1785438208 -0.9868655205 0.0414898954 1.1200846434 202 8.0400000000 0.0234076846 0.0287993237 0.0447686128 0.0070563607 0.0691700000 9401847 955859216 1787072512 -0.9841372967 0.0425850153 1.1306446791 203 8.0800000000 0.0237127114 0.0287742665 0.0447686128 0.0070652808 0.0849230000 9403101 955859216 1785950208 -0.9817821383 0.0440978669 1.1475789547 204 8.1200000000 0.0232125260 0.0287470030 0.0447686128 0.0070567439 0.0573560000 9404355 955859216 1784803328 -0.9800274968 0.0440633073 1.1601735353 205 8.1600000000 0.0242073946 0.0287248586 0.0447686128 0.0070485208 0.0560920000 9405609 955859216 1784037376 -0.9768038392 0.0420661606 1.1713643074 206 8.1999999990 0.0264129974 0.0287136360 0.0447686128 0.0070397115 0.0556960000 9406863 955859216 1782910976 -0.9728792310 0.0400414169 1.1841446161 207 8.2400000000 0.0300076604 0.0287198873 0.0447686128 0.0070339157 0.0779700000 9408117 955859216 1783058432 -0.9674926996 0.0394951664 1.1974464655 208 8.2799999990 0.0336102061 0.0287433985 0.0447686128 0.0070198737 0.0549640000 9409371 955859216 1782517760 -0.9623956084 0.0381140113 1.2099494934 209 8.3200000000 0.0374253131 0.0287849387 0.0447686128 0.0070143471 0.0585730000 9410625 955859216 1781129216 -0.9568954706 0.0362703241 1.2227053642 210 8.3599999990 0.0407104716 0.0288417270 0.0447686128 0.0070327575 0.0638020000 9411879 955859216 1779990528 -0.9504640102 0.0338201486 1.2343878746 211 8.4000000000 0.0416295640 0.0289023328 0.0447686128 0.0070491363 0.0698130000 9413133 955859216 1781501952 -0.9451460838 0.0311128478 1.2473415136 212 8.4399999990 0.0435116589 0.0289712447 0.0447686128 0.0070343443 0.0560340000 9414387 955859216 1780502528 -0.9375268817 0.0322082452 1.2594786882 213 8.4800000000 0.0477566086 0.0290594389 0.0477566086 0.0070319982 0.0609460000 9415641 955859216 1779118080 -0.9300056696 0.0318916962 1.2732155323 214 8.5200000000 0.0234128162 0.0290330529 0.0477566086 0.0071660616 0.0901260000 9416895 955859216 1777848320 -0.9292197824 0.0556537285 1.2874907255 215 8.5600000000 0.0280717555 0.0290285817 0.0477566086 0.0071703417 0.0790060000 9418149 955859216 1776689152 -0.9202386141 0.0505679883 1.2983661890 216 8.6000000000 0.0231452361 0.0290013440 0.0477566086 0.0071569538 0.0953610000 9419403 955859216 1775656960 -0.9122190475 0.0597438626 1.3096045256 217 8.6400000000 0.0260299668 0.0289876510 0.0477566086 0.0071752807 0.0812020000 9420657 955859216 1777184768 -0.9025844336 0.0599065274 1.3261181116 218 8.6800000000 0.0261050928 0.0289744283 0.0477566086 0.0072218088 0.0998730000 9421911 955859216 1774133248 -0.8940457106 0.0595875271 1.3357032537 219 8.7200000000 0.0324656591 0.0289903700 0.0477566086 0.0072179620 0.0672990000 9423165 955859216 1775661056 -0.8824325204 0.0561353676 1.3470051289 220 8.7600000000 0.0401655734 0.0290411663 0.0477566086 0.0072166136 0.0621680000 9424419 955859216 1774657536 -0.8699932098 0.0534493402 1.3588293791 221 8.8000000000 0.0448223427 0.0291125744 0.0477566086 0.0072454381 0.0829470000 9425673 955859216 1773625344 -0.8591430783 0.0500077829 1.3705586195 222 8.8400000000 0.0473064557 0.0291945288 0.0477566086 0.0072489412 0.0606130000 9426927 955859216 1772470272 -0.8493032455 0.0491847657 1.3842761517 223 8.8800000000 0.0499611013 0.0292876524 0.0499611013 0.0072473538 0.0743780000 9428181 955859216 1771356160 -0.8380852938 0.0496769249 1.3950027227 224 8.9200000000 0.0532392152 0.0293945791 0.0532392152 0.0072492726 0.0552590000 9429435 955859216 1772867584 -0.8265714645 0.0494043268 1.4058001041 225 8.9600000000 0.0543353446 0.0295054269 0.0543353446 0.0072447868 0.0655310000 9430689 955859216 1771991040 -0.8159254193 0.0509779267 1.4142718315 226 9.0000000000 0.0542052165 0.0296147180 0.0543353446 0.0072301294 0.0778490000 9431943 955859216 1770848256 -0.8056874871 0.0549982041 1.4249917269 227 9.0400000000 0.0307744406 0.0296198269 0.0543353446 0.0072569950 0.0768520000 9433197 955859216 1769705472 -0.7993090153 0.0837510079 1.4338700771 228 9.0800000000 0.0324730501 0.0296323411 0.0543353446 0.0072645697 0.0606500000 9434451 955859216 1768673280 -0.7874705195 0.0878663957 1.4475548267 229 9.1200000000 0.0307135154 0.0296370623 0.0543353446 0.0073235971 0.0666700000 9435705 955859216 1767657472 -0.7772885561 0.0936234966 1.4551150799 230 9.1600000000 0.0298012272 0.0296377761 0.0543353446 0.0074223179 0.0764600000 9436959 955859216 1768189952 -0.7666620016 0.0986360684 1.4619890451 231 9.2000000000 0.0292067118 0.0296359100 0.0543353446 0.0076282900 0.1064980000 9438213 955859216 1765617664 -0.7575367093 0.1002691612 1.4694617987 232 9.2400000000 0.0286465976 0.0296316457 0.0543353446 0.0077878235 0.0691310000 9439467 955859216 1767026688 -0.7482122183 0.1037817523 1.4778275490 233 9.2800000000 0.0277637541 0.0296236290 0.0543353446 0.0079284720 0.0824870000 9440721 955859216 1766010880 -0.7388232946 0.1075213030 1.4851785898 234 9.3200000000 0.0267039202 0.0296111517 0.0543353446 0.0080306207 0.1033840000 9441975 955859216 1764990976 -0.7291264534 0.1123129576 1.4921212196 235 9.3600000000 0.0252296664 0.0295925070 0.0543353446 0.0081076320 0.0703510000 9443229 955859216 1766510592 -0.7194246650 0.1171341836 1.4993805885 236 9.4000000000 0.0242702868 0.0295699553 0.0543353446 0.0081665430 0.0603720000 9444483 955859216 1768398848 -0.7102501988 0.1208011806 1.5079209805 237 9.4400000000 0.0240065325 0.0295464809 0.0543353446 0.0081937741 0.0822140000 9445737 955859216 1770049536 -0.7003840804 0.1252666861 1.5142389536 238 9.4800000000 0.0238581188 0.0295225802 0.0543353446 0.0082138287 0.0723830000 9446991 955859216 1771827200 -0.6896051168 0.1313925982 1.5219936371 239 9.5200000000 0.0236721579 0.0294981015 0.0543353446 0.0082556973 0.0825170000 9448245 955859216 1773477888 -0.6789503694 0.1368310302 1.5294327736 240 9.5600000000 0.0234233495 0.0294727900 0.0543353446 0.0083078257 0.0718510000 9449499 955859216 1775255552 -0.6688745022 0.1418637037 1.5380971432 241 9.6000000000 0.0234336816 0.0294477315 0.0543353446 0.0083594659 0.0887970000 9450753 955859216 1776906240 -0.6595866084 0.1427363455 1.5467913151 242 9.6400000000 0.0233085174 0.0294223628 0.0543353446 0.0083789452 0.0979720000 9452007 955859216 1778556928 -0.6498579383 0.1454887241 1.5553197861 243 9.6800000000 0.0227588359 0.0293949409 0.0543353446 0.0083924988 0.0851800000 9453261 955859216 1780334592 -0.6390756965 0.1520200819 1.5630397797 244 9.7200000000 0.0226040799 0.0293671095 0.0543353446 0.0084363876 0.0721830000 9454515 955859216 1782112256 -0.6278228760 0.1586030871 1.5711039305 245 9.7600000000 0.0257818773 0.0293524759 0.0543353446 0.0084913865 0.0876670000 9455769 955859216 1783771136 -0.6166175008 0.1580676287 1.5793142319 246 9.8000000000 0.0261297654 0.0293393754 0.0543353446 0.0085085508 0.0862050000 9457023 955859216 1785421824 -0.6061925888 0.1605719030 1.5880333185 247 9.8400000000 0.0251809973 0.0293225399 0.0543353446 0.0085130657 0.0602210000 9458277 955859216 1787072512 -0.5970044136 0.1616987735 1.5975452662 248 9.8800000000 0.0248271618 0.0293044134 0.0543353446 0.0084976891 0.0696560000 9459531 955859216 1786060800 -0.5877892971 0.1637872756 1.6058850288 249 9.9200000000 0.0242049135 0.0292839335 0.0543353446 0.0084815696 0.0507200000 9460785 955859216 1784942592 -0.5779712200 0.1666728109 1.6131738424 250 9.9600000000 0.0226511285 0.0292574022 0.0543353446 0.0084652150 0.0636910000 9462039 955859216 1783799808 -0.5687608719 0.1704117507 1.6228178740 251 10.0000000000 0.0224969946 0.0292304683 0.0543353446 0.0084486983 0.0602170000 9463293 955859216 1785311232 -0.5587383509 0.1736198366 1.6314529181 252 10.0400000000 0.0223119669 0.0292030140 0.0543353446 0.0084346489 0.0631450000 9464547 955859216 1784324096 -0.5502519011 0.1728909165 1.6417946815 253 10.0800000000 0.0220442433 0.0291747184 0.0543353446 0.0084188906 0.0818110000 9465801 955859216 1783275520 -0.5427387357 0.1700333357 1.6515848637 254 10.1200000000 0.0230965428 0.0291507886 0.0543353446 0.0084378733 0.0534990000 9467055 955859216 1782038528 -0.5327351093 0.1727477908 1.6595883369 255 10.1600000000 0.0232969709 0.0291278325 0.0543353446 0.0084532807 0.0818100000 9468309 955859216 1780899840 -0.5218222141 0.1794586182 1.6687401533 256 10.2000000000 0.0227834079 0.0291030495 0.0543353446 0.0084403315 0.0789280000 9469563 955859216 1780879360 -0.5107809305 0.1848615557 1.6775647402 257 10.2400000000 0.0224592313 0.0290771981 0.0543353446 0.0084257058 0.0522280000 9491297 955859216 1778708480 -0.5015029907 0.1848815084 1.6861339808 258 10.2800000000 0.0238406695 0.0290569015 0.0543353446 0.0084094792 0.0707600000 9534535 955859216 1777434624 -0.4908227324 0.1886508763 1.6949874163 259 10.3200000000 0.0245327987 0.0290394339 0.0543353446 0.0084019371 0.0664930000 9535789 955859216 1776197632 -0.4801974297 0.1918330938 1.7013292313 260 10.3600000000 0.0213832632 0.0290099871 0.0543353446 0.0084099305 0.0759970000 9537043 955859216 1777692672 -0.4710808396 0.1965157986 1.7099558115 261 10.4000000000 0.0232524872 0.0289879277 0.0543353446 0.0084077165 0.0618560000 9538297 955859216 1776422912 -0.4610036314 0.1942018121 1.7163031101 262 10.4400000000 0.0236694757 0.0289676283 0.0543353446 0.0083945592 0.0482160000 9539551 955859216 1775435776 -0.4513912499 0.1940608174 1.7234796286 263 10.4800000000 0.0234619714 0.0289466942 0.0543353446 0.0083804083 0.0569490000 9540805 955859216 1774387200 -0.4406091571 0.1957764179 1.7297093868 264 10.5200000000 0.0232056938 0.0289249480 0.0543353446 0.0083694961 0.0601710000 9542059 955859216 1775915008 -0.4303457737 0.1957006305 1.7357995510 265 10.5600000000 0.0227319673 0.0289015783 0.0543353446 0.0083539092 0.0707550000 9543313 955859216 1774911488 -0.4192053676 0.1980703771 1.7425312996 266 10.6000000000 0.0212342832 0.0288727539 0.0543353446 0.0083434833 0.0619870000 9544567 955859216 1773768704 -0.4076696634 0.2018324733 1.7466001511 267 10.6400000000 0.0210598856 0.0288434922 0.0543353446 0.0083395086 0.0735590000 9545821 955859216 1772736512 -0.3964699507 0.2010834217 1.7506937981 268 10.6800000000 0.0219944436 0.0288179360 0.0543353446 0.0083316475 0.0483360000 9547075 955859216 1774264320 -0.3848015368 0.1997049898 1.7573482990 269 10.7200000000 0.0218426883 0.0287920057 0.0543353446 0.0083199881 0.0636420000 9548329 955859216 1773260800 -0.3728939593 0.1998077184 1.7601466179 270 10.7600000000 0.0206840001 0.0287619761 0.0543353446 0.0083116871 0.0697450000 9549583 955859216 1772118016 -0.3479622304 0.2055512667 1.7698245049 271 10.8000000000 0.0206101723 0.0287318956 0.0543353446 0.0083275846 0.0613270000 9550837 955859216 1773629440 -0.3336513937 0.2093683183 1.7731503248 272 10.8400000000 0.0204063766 0.0287012871 0.0543353446 0.0083878356 0.0682600000 9552091 955859216 1772752896 -0.3217276931 0.2077377439 1.7770125866 273 10.8800000000 0.0204126649 0.0286709259 0.0543353446 0.0083956325 0.0739620000 9553345 955859216 1771610112 -0.3091178238 0.2084585875 1.7815253735 274 10.9200000000 0.0203295741 0.0286404830 0.0543353446 0.0084035678 0.0726560000 9554599 955859216 1770467328 -0.2958691716 0.2097560465 1.7852462530 275 10.9600000000 0.0202784929 0.0286100757 0.0543353446 0.0084084599 0.0682900000 9555853 955859216 1771978752 -0.2829718888 0.2098103613 1.7880759239 276 11.0000000000 0.0201662909 0.0285794823 0.0543353446 0.0084052386 0.0545820000 9557107 955859216 1771102208 -0.2695373893 0.2117967904 1.7919474840 277 11.0400000000 0.0199817847 0.0285484437 0.0543353446 0.0084106582 0.0717210000 9558361 955859216 1769959424 -0.2560412884 0.2134356350 1.7952473164 278 11.0800000000 0.0198907405 0.0285173009 0.0543353446 0.0084156957 0.0739700000 9559615 955859216 1768816640 -0.2424659878 0.2153090835 1.7988913059 279 11.1200000000 0.0197730456 0.0284859594 0.0543353446 0.0084249294 0.0694660000 9560869 955859216 1770328064 -0.2285582721 0.2171880156 1.8027030230 280 11.1600000000 0.0196822789 0.0284545177 0.0543353446 0.0084327404 0.0613860000 9562123 955859216 1769422848 -0.2145723253 0.2197879851 1.8059419394 281 11.2000000000 0.0196274165 0.0284231046 0.0543353446 0.0084383638 0.0572530000 9563377 955859216 1768292352 -0.2014205456 0.2207160294 1.8088154793 282 11.2400000000 0.0195782222 0.0283917397 0.0543353446 0.0084333135 0.0623860000 9564631 955859216 1769811968 -0.1895736009 0.2197960317 1.8133914471 283 11.2800000000 0.0203985292 0.0283634952 0.0543353446 0.0084185443 0.0587120000 9565885 955859216 1768935424 -0.1768731773 0.2204969078 1.8166306019 284 11.3200000000 0.0194786638 0.0283322106 0.0543353446 0.0084075613 0.0640250000 9567139 955859216 1767903232 -0.1646881253 0.2233895361 1.8214689493 285 11.3600000000 0.0192075800 0.0283001943 0.0543353446 0.0084047057 0.0715160000 9568393 955859216 1766887424 -0.1531854868 0.2247402221 1.8256887197 286 11.4000000000 0.0189957730 0.0282676614 0.0543353446 0.0083961070 0.0685220000 9569647 955859216 1768415232 -0.1427059472 0.2249607295 1.8297129869 287 11.4400000000 0.0188618023 0.0282348883 0.0543353446 0.0083815616 0.0573530000 9570901 955859216 1767522304 -0.1332263798 0.2247105092 1.8338524103 288 11.4800000000 0.0187563337 0.0282019767 0.0543353446 0.0083677281 0.0637580000 9572155 955859216 1766506496 -0.1243763119 0.2247389406 1.8378816843 289 11.5200000000 0.0186563302 0.0281689468 0.0543353446 0.0083543481 0.0785400000 9573409 955859216 1765490688 -0.1158819199 0.2247091532 1.8443541527 290 11.5600000000 0.0185600370 0.0281358126 0.0543353446 0.0083452305 0.0831880000 9574663 955859216 1764990976 -0.1075877026 0.2252450883 1.8501938581 291 11.6000000000 0.0184140056 0.0281024043 0.0543353446 0.0083339481 0.0769870000 9575917 955859216 1766510592 -0.1000915319 0.2244643718 1.8572294712 292 11.6400000000 0.0182728060 0.0280687413 0.0543353446 0.0083212757 0.0898740000 9577171 955859216 1765732352 -0.0920880958 0.2256348580 1.8630411625 293 11.6800000000 0.0181980524 0.0280350530 0.0543353446 0.0083070740 0.0780340000 9578425 955859216 1765478400 -0.0851398706 0.2259645313 1.8698259592 294 11.7200000000 0.0181363355 0.0280013839 0.0543353446 0.0082942034 0.0694600000 9579679 955859216 1764843520 -0.0790483505 0.2252762467 1.8770040274 295 11.7600000000 0.0184457041 0.0279689917 0.0543353446 0.0082855078 0.0892830000 9580933 955859216 1764728832 -0.0733676627 0.2249083817 1.8836954832 296 11.8000000000 0.0190157443 0.0279387443 0.0543353446 0.0082763438 0.0687500000 9582187 955859216 1764728832 -0.0674726665 0.2244696319 1.8897864819 297 11.8400000000 0.0194155220 0.0279100465 0.0543353446 0.0082675322 0.0848890000 9583441 955859216 1764855808 -0.0625887737 0.2235512882 1.8967969418 298 11.8800000000 0.0199957900 0.0278834886 0.0543353446 0.0082621649 0.0672560000 9584695 955859216 1764982784 -0.0576896146 0.2222803384 1.9040497541 299 11.9200000000 0.0177804530 0.0278496992 0.0543353446 0.0082522909 0.0697470000 9585949 955859216 1766621184 -0.0528651290 0.2247231603 1.9140111208 300 11.9600000000 0.0194597468 0.0278217327 0.0543353446 0.0082399811 0.0662760000 9587203 955859216 1766248448 -0.0477560721 0.2237199843 1.9210709333 301 12.0000000000 0.0178931635 0.0277887474 0.0543353446 0.0082265147 0.0897200000 9588457 955859216 1764999168 -0.0432937331 0.2257027179 1.9312584400 302 12.0400000000 0.0176581703 0.0277552025 0.0543353446 0.0082152432 0.0646520000 9589711 955859216 1764999168 -0.0393731333 0.2257752120 1.9411780834 303 12.0800000000 0.0174990501 0.0277213538 0.0543353446 0.0082086874 0.0724190000 9590965 955859216 1764970496 -0.0352296643 0.2262658924 1.9510904551 304 12.1200000000 0.0172937270 0.0276870524 0.0543353446 0.0082064720 0.0809270000 9592219 955859216 1764982784 -0.0313898548 0.2267097831 1.9613165855 305 12.1600000000 0.0170722660 0.0276522498 0.0543353446 0.0082027496 0.0905610000 9593473 955859216 1764999168 -0.0277785063 0.2268703729 1.9726722240 306 12.2000000000 0.0168562625 0.0276169688 0.0543353446 0.0081953276 0.0897520000 9594727 955859216 1764999168 -0.0242382437 0.2270654291 1.9842045307 307 12.2400000000 0.0167040415 0.0275814218 0.0543353446 0.0081963378 0.0650200000 9595981 955859216 1766510592 -0.0210358333 0.2279291004 1.9957041740 308 12.2800000000 0.0166005623 0.0275457697 0.0543353446 0.0081992139 0.0699780000 9597235 955859216 1765871616 -0.0184567757 0.2281601429 2.0073132515 309 12.3200000000 0.0162393823 0.0275091794 0.0543353446 0.0082096222 0.0804060000 9598489 955859216 1765003264 -0.0166101288 0.2281951010 2.0183985233 310 12.3600000000 0.0160579849 0.0274722401 0.0543353446 0.0082273039 0.0884110000 9599743 955859216 1764999168 -0.0150081497 0.2278543711 2.0303122997 311 12.4000000000 0.0158907976 0.0274350007 0.0543353446 0.0082400494 0.0709030000 9600997 955859216 1764999168 -0.0128576849 0.2288461775 2.0410690308 312 12.4400000000 0.0155351339 0.0273968601 0.0543353446 0.0082746022 0.0669350000 9602251 955859216 1766510592 -0.0106414091 0.2289642543 2.0650160313 313 12.4800000000 0.0152982157 0.0273582063 0.0543353446 0.0082677529 0.0689920000 9603505 955859216 1765998592 -0.0101087866 0.2290071696 2.0756525993 314 12.5200000000 0.0150808319 0.0273191064 0.0543353446 0.0082592896 0.0632390000 9604759 955859216 1764982784 -0.0101133659 0.2281132340 2.0882499218 315 12.5600000000 0.0147227440 0.0272791179 0.0543353446 0.0082580704 0.0683980000 9606013 955859216 1764982784 -0.0097555444 0.2287423760 2.0997288227 316 12.6000000000 0.0144094387 0.0272383911 0.0543353446 0.0082470989 0.0690100000 9607267 955859216 1766494208 -0.0096430741 0.2293700874 2.1120142937 317 12.6400000000 0.0139635103 0.0271965145 0.0543353446 0.0082341147 0.0675360000 9608521 955859216 1766125568 -0.0100233983 0.2292288542 2.1237232685 318 12.6800000000 0.0138700819 0.0271546075 0.0543353446 0.0082211297 0.0680820000 9609775 955859216 1765003264 -0.0106886681 0.2288524806 2.1349914074 319 12.7200000000 0.0135754114 0.0271120395 0.0543353446 0.0082082227 0.0771640000 9611029 955859216 1764999168 -0.0114713889 0.2293627560 2.1450595856 320 12.7600000000 0.0132907191 0.0270688478 0.0543353446 0.0081953856 0.1064560000 9612283 955859216 1764999168 -0.0127186393 0.2298749834 2.1553292274 321 12.8000000000 0.0130178817 0.0270250754 0.0543353446 0.0081854763 0.0718270000 9613537 955859216 1764999168 -0.0148991039 0.2290928960 2.1658921242 322 12.8400000000 0.0127263898 0.0269806695 0.0543353446 0.0081753151 0.0592090000 9614791 955859216 1764999168 -0.0165695567 0.2297969013 2.1751582623 323 12.8800000000 0.0124324672 0.0269356286 0.0543353446 0.0081669142 0.0701210000 9616045 955859216 1766510592 -0.0185678918 0.2290642262 2.1837685108 324 12.9200000000 0.0121420287 0.0268899694 0.0543353446 0.0081556497 0.0704130000 9617299 955859216 1766125568 -0.0205947217 0.2288141251 2.1928746700 325 12.9600000000 0.0118705817 0.0268437559 0.0543353446 0.0081433789 0.0705090000 9618553 955859216 1764982784 -0.0220130105 0.2300352603 2.2018024921 326 13.0000000000 0.0116470400 0.0267971402 0.0543353446 0.0081318359 0.0862480000 9619807 955859216 1765003264 -0.0240002219 0.2300166488 2.2089166641 327 13.0400000000 0.0113829663 0.0267500020 0.0543353446 0.0081213434 0.1117950000 9621061 955859216 1764982784 -0.0260342490 0.2307869941 2.2185208797 328 13.0800000000 0.0111683896 0.0267024971 0.0543353446 0.0081097107 0.0837310000 9622315 955859216 1764745216 -0.0266172104 0.2338112295 2.2247905731 329 13.1200000000 0.0109547852 0.0266546317 0.0543353446 0.0080983659 0.0956630000 9623569 955859216 1764356096 -0.0282712709 0.2349564284 2.2338318825 330 13.1600000000 0.0107738385 0.0266065081 0.0543353446 0.0080877740 0.1115200000 9624823 955859216 1765986304 -0.0302081686 0.2355667651 2.2420318127 331 13.2000000000 0.0106447209 0.0265582852 0.0543353446 0.0080760967 0.0852860000 9626077 955859216 1767899136 -0.0319873989 0.2365171313 2.2522671223 332 13.2400000000 0.0105931209 0.0265101973 0.0543353446 0.0080653170 0.0914780000 9627331 955859216 1769533440 -0.0338569283 0.2372962981 2.2611901760 333 13.2800000000 0.0104866289 0.0264620785 0.0543353446 0.0080536538 0.0693800000 9628585 955859216 1771311104 -0.0360160619 0.2378829420 2.2710647583 334 13.3200000000 0.0104103778 0.0264140195 0.0543353446 0.0080427481 0.0808720000 9629839 955859216 1772961792 -0.0383323804 0.2381213307 2.2795667648 335 13.3600000000 0.0102899671 0.0263658880 0.0543353446 0.0080307601 0.0913900000 9631093 955859216 1774739456 -0.0404397957 0.2393556684 2.2884619236 336 13.4000000000 0.0101572545 0.0263176481 0.0543353446 0.0080188384 0.0898250000 9632347 955859216 1776390144 -0.0419578962 0.2414965630 2.2964189053 337 13.4400000000 0.0100318603 0.0262693223 0.0543353446 0.0080183275 0.0816660000 9633601 955859216 1778040832 -0.0436882824 0.2441050112 2.3039758205 338 13.4800000000 0.0098840641 0.0262208452 0.0543353446 0.0080257766 0.0840860000 9634855 955859216 1779818496 -0.0455319099 0.2459589392 2.3102927208 339 13.5200000000 0.0097829159 0.0261723557 0.0543353446 0.0080433661 0.0915160000 9636109 955859216 1781469184 -0.0479680896 0.2461474836 2.3159081936 340 13.5600000000 0.0097072730 0.0261239290 0.0543353446 0.0080401927 0.0809530000 9637363 955859216 1783246848 -0.0503541417 0.2467029393 2.3210213184 341 13.6000000000 0.0096618049 0.0260756530 0.0543353446 0.0080337550 0.0848210000 9638617 955859216 1784897536 -0.0525193587 0.2472809404 2.3258562088 342 13.6400000000 0.0095753036 0.0260274063 0.0543353446 0.0080259469 0.0912580000 9639871 955859216 1786691584 -0.0546560362 0.2477834970 2.3315589428 343 13.6800000000 0.0095097031 0.0259792498 0.0543353446 0.0080143994 0.0828880000 9641125 955859216 1785442304 -0.0566344671 0.2481952161 2.3364260197 344 13.7200000000 0.0094763003 0.0259312761 0.0543353446 0.0080027849 0.0847180000 9642379 955859216 1783672832 -0.0577332191 0.2499343008 2.3419730663 345 13.7600000000 0.0094068507 0.0258833792 0.0543353446 0.0079952091 0.0872600000 9643633 955859216 1782611968 -0.0596600361 0.2499299347 2.3474900723 346 13.8000000000 0.0093582915 0.0258356188 0.0543353446 0.0079899875 0.0865140000 9644887 955859216 1781497856 -0.0613337606 0.2499047369 2.3525621891 347 13.8400000000 0.0092939967 0.0257879484 0.0543353446 0.0079790766 0.0845440000 9646141 955859216 1780355072 -0.0636683181 0.2486640364 2.3571133614 348 13.8800000000 0.0092367241 0.0257403875 0.0543353446 0.0079684016 0.0867050000 9647395 955859216 1779212288 -0.0642554238 0.2509550154 2.3628811836 349 13.9200000000 0.0091443462 0.0256928343 0.0543353446 0.0079661720 0.1107490000 9648649 955859216 1778069504 -0.0659269169 0.2507725656 2.3686566353 350 13.9600000000 0.0090708053 0.0256453428 0.0543353446 0.0079572075 0.0858070000 9649903 955859216 1777676288 -0.0679448470 0.2494810820 2.3774847984 351 14.0000000000 0.0090679964 0.0255981139 0.0543353446 0.0079466372 0.0890000000 9651157 955859216 1776914432 -0.0680245832 0.2502037585 2.3817760944 352 14.0400000000 0.0092705712 0.0255517288 0.0543353446 0.0079378116 0.0800220000 9652411 955859216 1775771648 -0.0686992779 0.2496363670 2.3867015839 353 14.0800000000 0.0092248153 0.0255054770 0.0543353446 0.0079265396 0.0832010000 9653665 955859216 1773744128 -0.0690702796 0.2487275004 2.3909800053 354 14.1200000000 0.0090060616 0.0254588684 0.0543353446 0.0079154090 0.1109860000 9654919 955859216 1773027328 -0.0687028915 0.2495062947 2.3956112862 355 14.1600000000 0.0091831638 0.0254130214 0.0543353446 0.0079045229 0.0798170000 9656173 955859216 1774485504 -0.0693470314 0.2479443401 2.4006147385 356 14.2000000000 0.0089707961 0.0253668354 0.0543353446 0.0078952116 0.0912360000 9657427 955859216 1776390144 -0.0689973682 0.2480297685 2.4050798416 357 14.2400000000 0.0089433724 0.0253208313 0.0543353446 0.0078845784 0.0893420000 9658681 955859216 1777922048 -0.0686722100 0.2485629618 2.4106976986 358 14.2800000000 0.0090546394 0.0252753950 0.0543353446 0.0078744236 0.0702120000 9659935 955859216 1779699712 -0.0690722391 0.2471067458 2.4162883759 359 14.3200000000 0.0089662466 0.0252299656 0.0543353446 0.0078647220 0.0842180000 9661189 955859216 1781350400 -0.0696950480 0.2454539835 2.4217455387 360 14.3600000000 0.0089984071 0.0251848779 0.0543353446 0.0078561835 0.0907560000 9662443 955859216 1783128064 -0.0698770881 0.2441376746 2.4279110432 361 14.4000000000 0.0089807324 0.0251399911 0.0543353446 0.0078517594 0.0703150000 9663697 955859216 1784778752 -0.0700170100 0.2440330237 2.4343862534 362 14.4400000000 0.0089308908 0.0250952146 0.0543353446 0.0078449488 0.0842220000 9664951 955859216 1786429440 -0.0700507537 0.2443230301 2.4409406185 363 14.4800000000 0.0089166416 0.0250506455 0.0543353446 0.0078344659 0.1036280000 9666205 955859216 1785323520 -0.0699534118 0.2452179641 2.4481298923 364 14.5200000000 0.0085244933 0.0250052440 0.0543353446 0.0078248609 0.0942280000 9667459 955859216 1786826752 -0.0702317655 0.2449026853 2.4549963474 365 14.5600000000 0.0086148372 0.0249603388 0.0543353446 0.0078142207 0.1042960000 9668713 955859216 1784541184 -0.0708609000 0.2440999448 2.4623084068 366 14.6000000000 0.0086951731 0.0249158984 0.0543353446 0.0078038208 0.0910610000 9669967 955859216 1783283712 -0.0710408464 0.2448254675 2.4702188969 367 14.6400000000 0.0081920922 0.0248703295 0.0543353446 0.0077935822 0.0774120000 9671221 955859216 1784795136 -0.0708691254 0.2460388839 2.4768049717 368 14.6800000000 0.0082098283 0.0248250564 0.0543353446 0.0077840765 0.0853100000 9672475 955859216 1783902208 -0.0711362660 0.2468664050 2.4848630428 369 14.7200000000 0.0082897115 0.0247802451 0.0543353446 0.0077830259 0.1086700000 9673729 955859216 1780473856 -0.0719949380 0.2466013432 2.4924848080 370 14.7600000000 0.0082385270 0.0247355378 0.0543353446 0.0077805673 0.0900940000 9674983 955859216 1780490240 -0.0722288042 0.2470579445 2.5003829002 371 14.8000000000 0.0081976932 0.0246909614 0.0543353446 0.0077741118 0.1060880000 9676237 955859216 1778302976 -0.0723165497 0.2468370199 2.5076346397 372 14.8400000000 0.0081589976 0.0246465206 0.0543353446 0.0077698923 0.0878510000 9677491 955859216 1778827264 -0.0725494921 0.2464032173 2.5146806240 373 14.8800000000 0.0081256181 0.0246022287 0.0543353446 0.0077695582 0.0874120000 9678745 955859216 1777049600 -0.0727058724 0.2462699711 2.5220286846 374 14.9200000000 0.0080879591 0.0245580729 0.0543353446 0.0077655480 0.0859610000 9679999 955859216 1775017984 -0.0729076192 0.2456381023 2.5293750763 375 14.9600000000 0.0080554737 0.0245140659 0.0543353446 0.0077684776 0.0869240000 9681253 955859216 1773002752 -0.0726778135 0.2452624887 2.5363576412 376 15.0000000000 0.0080200853 0.0244701990 0.0543353446 0.0077680264 0.1077420000 9682507 955859216 1771589632 -0.0717114657 0.2466038316 2.5437624454 377 15.0400000000 0.0079682032 0.0244264271 0.0543353446 0.0077605297 0.1093460000 9683761 955859216 1770459136 -0.0694646761 0.2477878332 2.5569653511 378 15.0800000000 0.0078902980 0.0243826807 0.0543353446 0.0077502925 0.0913500000 9685015 955859216 1769316352 -0.0675296485 0.2490383238 2.5634229183 379 15.1200000000 0.0078191413 0.0243389774 0.0543353446 0.0077400779 0.0867270000 9686269 955859216 1768284160 -0.0656445250 0.2496030033 2.5690805912 380 15.1600000000 0.0077667115 0.0242953662 0.0543353446 0.0077310082 0.0862680000 9687523 955859216 1769811968 -0.0628918409 0.2507556975 2.5744299889 381 15.2000000000 0.0077471077 0.0242519325 0.0543353446 0.0077210751 0.0883180000 9688777 955859216 1768939520 -0.0605374351 0.2517878711 2.5795226097 382 15.2400000000 0.0077152601 0.0242086428 0.0543353446 0.0077124248 0.0868600000 9690031 955859216 1767018496 -0.0583155081 0.2522717118 2.5843286514 383 15.2800000000 0.0076702400 0.0241654615 0.0543353446 0.0077030619 0.1044200000 9691285 955859216 1765015552 -0.0556422248 0.2533241510 2.5888416767 384 15.3200000000 0.0076213707 0.0241223780 0.0543353446 0.0076930347 0.0916100000 9692539 955859216 1764982784 -0.0528280064 0.2540442944 2.5926485062 385 15.3600000000 0.0075965072 0.0240794536 0.0543353446 0.0076837433 0.0897010000 9693793 955859216 1764982784 -0.0503174514 0.2536570430 2.5952186584 386 15.4000000000 0.0075549884 0.0240366441 0.0543353446 0.0076801582 0.1255020000 9695047 955859216 1764982784 -0.0472649485 0.2543466985 2.5973522663 387 15.4400000000 0.0075021940 0.0239939195 0.0543353446 0.0076800465 0.0914580000 9696301 955859216 1764999168 -0.0435711220 0.2565053999 2.5994818211 388 15.4800000000 0.0074456860 0.0239512694 0.0543353446 0.0076704798 0.0793260000 9697555 955859216 1764999168 -0.0405410938 0.2577954829 2.6003837585 389 15.5200000000 0.0074004303 0.0239087222 0.0543353446 0.0076610747 0.0961890000 9698809 955859216 1764999168 -0.0379173122 0.2579624355 2.6013607979 390 15.5600000000 0.0073176743 0.0238661811 0.0543353446 0.0076513013 0.0920370000 9700063 955859216 1765146624 -0.0340483449 0.2610728145 2.6025204659 391 15.6000000000 0.0072910693 0.0238237895 0.0543353446 0.0076563417 0.0869540000 9701317 955859216 1766256640 -0.0308624506 0.2614287138 2.6038591862 392 15.6400000000 0.0071855183 0.0237813449 0.0543353446 0.0076471684 0.0873610000 9702571 955859216 1765638144 -0.0280277301 0.2612270117 2.6041915417 393 15.6800000000 0.0069649629 0.0237385551 0.0543353446 0.0076381164 0.1032310000 9703825 955859216 1764978688 -0.0258673653 0.2596989870 2.6045243740 394 15.7200000000 0.0066034133 0.0236950649 0.0543353446 0.0076305832 0.0911610000 9705079 955859216 1764872192 -0.0238964893 0.2578021586 2.6049573421 395 15.7600000000 0.0072074016 0.0236533240 0.0543353446 0.0076342607 0.1086060000 9706333 955859216 1764872192 -0.0206137206 0.2580704391 2.6064074039 396 15.8000000000 0.0083125727 0.0236145847 0.0543353446 0.0076283493 0.0891140000 9707587 955859216 1764982784 -0.0170600452 0.2581849992 2.6082150936 397 15.8400000000 0.0376132950 0.0236498460 0.0543353446 0.0077479125 0.1055590000 9708841 955859216 1764999168 -0.0150358127 0.2577671409 2.6392426491 398 15.8800000000 0.0664858073 0.0237574740 0.0664858073 0.0078499556 0.0926770000 9710095 955859216 1764999168 -0.0126705235 0.2559341490 2.6677255630 399 15.9200000000 0.1071497574 0.0239664772 0.1071497574 0.0080880706 0.0842070000 9711349 955859216 1764999168 -0.0090720719 0.2580938041 2.7070245743 400 15.9600000000 0.1065833718 0.0241730195 0.1071497574 0.0080815810 0.0881750000 9712603 955859216 1764999168 -0.0047743674 0.2589068115 2.7069692612 401 16.0000000000 0.1043165326 0.0243728786 0.1071497574 0.0080772240 0.0979430000 9713857 955859216 1764999168 -0.0001870505 0.2595005333 2.7053580284 402 16.0400000000 0.1034029052 0.0245694707 0.1071497574 0.0080696976 0.0904720000 9715111 955859216 1764999168 0.0053851730 0.2600279748 2.7047343254 403 16.0800000000 0.1027268767 0.0247634097 0.1071497574 0.0080649513 0.0890330000 9716365 955859216 1764982784 0.0100365421 0.2595328689 2.7056992054 404 16.1200000000 0.1021819487 0.0249550397 0.1071497574 0.0080567823 0.1257830000 9717619 955859216 1764982784 0.0149932019 0.2599453032 2.7042913437 405 16.1600000000 0.1017539427 0.0251446667 0.1071497574 0.0080487949 0.0928670000 9718873 955859216 1764990976 0.0203995910 0.2603727579 2.7054202557 406 16.2000000000 0.1014844924 0.0253326958 0.1071497574 0.0080405395 0.0855030000 9720127 955859216 1764990976 0.0262710974 0.2620140016 2.7077887058 407 16.2400000000 0.1011149138 0.0255188929 0.1071497574 0.0080331770 0.0887820000 9721381 955859216 1764990976 0.0313677490 0.2627633214 2.7094311714 408 16.2800000000 0.1008420587 0.0257035085 0.1071497574 0.0080350469 0.0902200000 9722635 955859216 1764990976 0.0366256982 0.2632705569 2.7120337486 409 16.3200000000 0.1005842686 0.0258865910 0.1071497574 0.0080376192 0.1077920000 9723889 955859216 1764990976 0.0432369150 0.2667507231 2.7144012451 410 16.3600000000 0.1003933102 0.0260683147 0.1071497574 0.0080295069 0.0934920000 9725143 955859216 1764990976 0.0493445918 0.2697851360 2.7186157703 411 16.3999999990 0.1002949178 0.0262489147 0.1071497574 0.0080243566 0.1067070000 9726397 955859216 1764990976 0.0527595989 0.2683751881 2.7201912403 412 16.4400000000 0.1001484841 0.0264282826 0.1071497574 0.0080398749 0.1076250000 9727651 955859216 1764974592 0.0578504764 0.2681864500 2.7263000011 413 16.4800000000 0.0999733433 0.0266063578 0.1071497574 0.0080538706 0.1117730000 9728905 955859216 1764990976 0.0639989451 0.2695385516 2.7329139709 414 16.5200000000 0.0998934731 0.0267833799 0.1071497574 0.0080504514 0.0831920000 9730159 955859216 1764990976 0.0687470585 0.2673685253 2.7363884449 415 16.5599999990 0.0998171121 0.0269593648 0.1071497574 0.0080640963 0.0891710000 9731413 955859216 1764990976 0.0718139037 0.2615042925 2.7418918610 416 16.6000000000 0.0995158032 0.0271337793 0.1071497574 0.0081403286 0.1103440000 9732667 955859216 1764990976 0.0780420452 0.2613887489 2.7472774982 417 16.6400000000 0.0991562307 0.0273064950 0.1071497574 0.0081700815 0.0878410000 9733921 955859216 1764990976 0.0842506438 0.2627300322 2.7485208511 418 16.6800000000 0.0988874435 0.0274777413 0.1071497574 0.0081731076 0.0880860000 9735175 955859216 1764990976 0.0864103138 0.2590789497 2.7476596832 419 16.7199999990 0.0985076427 0.0276472637 0.1071497574 0.0082010395 0.0846830000 9736429 955859216 1764990976 0.0940227285 0.2616778314 2.7529268265 420 16.7600000000 0.0976815745 0.0278140121 0.1071497574 0.0081917407 0.1091430000 9737683 955859216 1764990976 0.1013054177 0.2622556686 2.7519857883 421 16.8000000000 0.0973362550 0.0279791480 0.1071497574 0.0082028338 0.0905350000 9738937 955859216 1764974592 0.1052449942 0.2561842799 2.7525026798 422 16.8400000000 0.2335241437 0.0284662215 0.2335241437 0.0089314254 0.0803850000 9740191 955859216 1765007360 0.1122228354 0.4380320013 2.8045878410 423 16.8799999990 0.3356603086 0.0291924486 0.3356603086 0.0091486935 0.0709550000 9741445 955859216 1766502400 0.1199821979 0.5452938080 2.8269131184 424 16.9200000000 0.4455594718 0.0301744463 0.4455594718 0.0093510225 0.0852990000 9742699 955859216 1765736448 0.1258255839 0.6565119028 2.8433835506 425 16.9600000000 0.6067106128 0.0315310020 0.6067106128 0.0099300804 0.0893660000 9743953 955859216 1764978688 0.1404893398 0.8256097436 2.8536787033 426 17.0000000000 0.6541557312 0.0329925624 0.6541557312 0.0099323366 0.1095110000 9745207 955859216 1764990976 0.1389338076 0.8750126958 2.8549065590 427 17.0400000000 0.8002345562 0.0347893821 0.8002345562 0.0103124111 0.0878090000 9746461 955859216 1765867520 0.1523057222 1.0228477716 2.8526597023 428 17.0800000000 0.8216059804 0.0366277386 0.8216059804 0.0103043714 0.0881040000 9747715 955859216 1765740544 0.1526068896 1.0436919928 2.8471031189 429 17.1200000000 0.8125504851 0.0384364163 0.8216059804 0.0102933041 0.1069350000 9748969 955859216 1765007360 0.1677272320 1.0330970287 2.8459298611 430 17.1600000000 0.8083142042 0.0402268298 0.8216059804 0.0102839456 0.0921100000 9750223 955859216 1764990976 0.1781499833 1.0243473053 2.8413074017 431 17.2000000000 0.8052595854 0.0420018478 0.8216059804 0.0102748492 0.0863870000 9751477 955859216 1764974592 0.1901400387 1.0161869526 2.8402812481 432 17.2400000000 0.8004485965 0.0437575116 0.8216059804 0.0102771975 0.0899490000 9752731 955859216 1764990976 0.2051603496 1.0092809200 2.8373224735 433 17.2800000000 0.7952291369 0.0454930119 0.8216059804 0.0102719245 0.0898840000 9753985 955859216 1764990976 0.2189815640 1.0019969940 2.8332650661 434 17.3200000000 0.7970955968 0.0472248151 0.8216059804 0.0102641321 0.0833810000 9755239 955859216 1766502400 0.2296546400 0.9984837770 2.8274645805 435 17.3600000000 0.8055860996 0.0489681743 0.8216059804 0.0102738087 0.0857490000 9756493 955859216 1766391808 0.2442370951 1.0057559013 2.8241722584 436 17.4000000000 0.7895808816 0.0506668273 0.8216059804 0.0102880156 0.0900990000 9757747 955859216 1766359040 0.2571217120 0.9937846661 2.8145263195 437 17.4400000000 0.7840629816 0.0523450794 0.8216059804 0.0102768639 0.0869940000 9759001 955859216 1766232064 0.2731441855 0.9940643311 2.8042938709 438 17.4800000000 0.7843823433 0.0540163973 0.8216059804 0.0103135103 0.1070320000 9760255 955859216 1765097472 0.2831549942 0.9958416224 2.7954766750 439 17.5200000000 0.7786136866 0.0556669606 0.8216059804 0.0103767063 0.0707850000 9761509 955859216 1766739968 0.2896543443 0.9837047458 2.7870824337 440 17.5600000000 0.7801077962 0.0573134171 0.8216059804 0.0103861241 0.0841820000 9762763 955859216 1766002688 0.2939513326 0.9756461382 2.7821545601 441 17.6000000000 0.7766195536 0.0589444968 0.8216059804 0.0103839868 0.0838530000 9764017 955859216 1764962304 0.3004421294 0.9643064737 2.7772917747 442 17.6400000000 0.7719954848 0.0605577343 0.8216059804 0.0104366728 0.0831180000 9765271 955859216 1764462592 0.3143414855 0.9603041410 2.7685985565 443 17.6800000000 0.7662279010 0.0621506692 0.8216059804 0.0104804937 0.0918940000 9766525 955859216 1764741120 0.3383089006 0.9586033821 2.7505543232 444 17.7200000000 0.7592933774 0.0637208104 0.8216059804 0.0104714456 0.0828720000 9767779 955859216 1764483072 0.3488146961 0.9502419233 2.7408976555 445 17.7600000000 0.7576691508 0.0652802449 0.8216059804 0.0104616969 0.0898170000 9769033 955859216 1764720640 0.3579616845 0.9454886913 2.7339847088 446 17.8000000000 0.7544451952 0.0668254578 0.8216059804 0.0104526009 0.0899310000 9770287 955859216 1764720640 0.3640666008 0.9424353242 2.7242524624 447 17.8400000000 0.7514526844 0.0683570623 0.8216059804 0.0104432245 0.0702480000 9771541 955859216 1764720640 0.3721415699 0.9357873201 2.7182362080 448 17.8800000000 0.7497009039 0.0698779191 0.8216059804 0.0104338021 0.1066770000 9772795 955859216 1764720640 0.3799925745 0.9316225052 2.7121889591 449 17.9200000000 0.7467477918 0.0713854244 0.8216059804 0.0104259527 0.1064950000 9774049 955859216 1764720640 0.3875572085 0.9262379408 2.7052528858 450 17.9600000000 0.7451366782 0.0728826494 0.8216059804 0.0104184762 0.0712830000 9775303 955859216 1766359040 0.3947738409 0.9195623994 2.7016897202 451 18.0000000000 0.7429117560 0.0743683015 0.8216059804 0.0104211528 0.0679380000 9776557 955859216 1768644608 0.4007524550 0.9170483351 2.6952478886 452 18.0400000000 0.7396528721 0.0758401701 0.8216059804 0.0104153943 0.0690210000 9777811 955859216 1770295296 0.4138494432 0.9132826924 2.6902813911 453 18.0800000000 0.7379090786 0.0773016908 0.8216059804 0.0104055026 0.1083930000 9779065 955859216 1771945984 0.4224069715 0.9073942900 2.6858117580 454 18.1200000000 0.7351958156 0.0787507968 0.8216059804 0.0104038444 0.0697810000 9780319 955859216 1773723648 0.4302344620 0.9039356709 2.6800632477 455 18.1600000000 0.7334069014 0.0801896015 0.8216059804 0.0103953608 0.0692320000 9781573 955859216 1775374336 0.4419165552 0.9007305503 2.6757249832 456 18.2000000000 0.7306666970 0.0816160863 0.8216059804 0.0103879556 0.0871910000 9782827 955859216 1777152000 0.4518702328 0.8940851688 2.6710512638 457 18.2400000000 0.7291111946 0.0830329246 0.8216059804 0.0103861069 0.0896720000 9784081 955859216 1778802688 0.4613436460 0.8893557787 2.6670904160 458 18.2800000000 0.7275418639 0.0844401494 0.8216059804 0.0103949067 0.0890060000 9785335 955859216 1780453376 0.4736397266 0.8891260624 2.6638340950 459 18.3200000000 0.7239158154 0.0858333426 0.8216059804 0.0103891704 0.0898160000 9786589 955859216 1782231040 0.4867688715 0.8880358338 2.6566135883 460 18.3600000000 0.7232412696 0.0872190120 0.8216059804 0.0103826746 0.0697790000 9787843 955859216 1783881728 0.4979402423 0.8826076388 2.6549732685 461 18.4000000000 0.7225701809 0.0885972141 0.8216059804 0.0103737471 0.0868300000 9789097 955859216 1785659392 0.5092620254 0.8797598481 2.6528046131 462 18.4400000000 0.7204831243 0.0899649325 0.8216059804 0.0103659763 0.0886880000 9790351 955859216 1787310080 0.5210199952 0.8784945011 2.6471345425 463 18.4800000000 0.7182630301 0.0913219478 0.8216059804 0.0103561496 0.1081350000 9791605 955859216 1784401920 0.5295150280 0.8737881780 2.6418628693 464 18.5200000000 0.7195408940 0.0926758680 0.8216059804 0.0103472889 0.0942440000 9792859 955859216 1783275520 0.5371692181 0.8708092570 2.6411752701 465 18.5600000000 0.7202093005 0.0940254022 0.8216059804 0.0103393709 0.1041180000 9794113 955859216 1782132736 0.5476855636 0.8662451506 2.6419937611 466 18.6000000000 0.7201961279 0.0953691162 0.8216059804 0.0103466937 0.0858260000 9795367 955859216 1783644160 0.5605663657 0.8670861125 2.6394674778 467 18.6400000000 0.7205935121 0.0967079265 0.8216059804 0.0103395663 0.1065640000 9796621 955859216 1779957760 0.5761031508 0.8637048006 2.6427781582 468 18.6800000000 0.7220898867 0.0980442127 0.8216059804 0.0103322041 0.0693550000 9797875 955859216 1781485568 0.5901556611 0.8601208925 2.6466462612 469 18.7200000000 0.7199740410 0.0993702891 0.8216059804 0.0103402718 0.0810890000 9799129 955859216 1780482048 0.6012990475 0.8556785583 2.6469900608 470 18.7600000000 0.7725316286 0.1008025473 0.8216059804 0.0104257732 0.0896510000 9800383 955859216 1779339264 0.6019967198 0.8954625130 2.6810610294 471 18.8000000000 0.8159760833 0.1023209625 0.8216059804 0.0104279468 0.0902150000 9801637 955859216 1778167808 0.6117339134 0.9346961379 2.6938531399 472 18.8400000000 0.8137950897 0.1038283229 0.8216059804 0.0104655196 0.1113120000 9802891 955859216 1777053696 0.6341877580 0.9327714443 2.6901497841 473 18.8800000000 0.8488897681 0.1054035057 0.8488897681 0.0105154610 0.1047720000 9804145 955859216 1778565120 0.6233866215 0.9607956409 2.7103319168 474 18.9200000000 0.8428207636 0.1069592383 0.8488897681 0.0105209342 0.0901100000 9805399 955859216 1780326400 0.6394077539 0.9528990984 2.7027463913 475 18.9600000000 0.8456801176 0.1085144401 0.8488897681 0.0105128860 0.1076070000 9806653 955859216 1781977088 0.6434007883 0.9528453946 2.7033634186 476 19.0000000000 0.8578901887 0.1100887589 0.8578901887 0.0105177066 0.1105040000 9807907 955859216 1783754752 0.6345009804 0.9612089992 2.7109847069 477 19.0400000000 0.8668494821 0.1116752594 0.8668494821 0.0105252063 0.0891500000 9809161 955859216 1785405440 0.6249168515 0.9657551646 2.7134397030 478 19.0800000000 0.8816412687 0.1132860669 0.8816412687 0.0105469931 0.0814550000 9810415 955859216 1787056128 0.6159478426 0.9747728109 2.7282016277 479 19.1200000000 0.9236129522 0.1149777723 0.9236129522 0.0111833338 0.0883020000 9811669 955859216 1785933824 0.5132272840 0.9848573208 2.7659146786 480 19.1600000000 1.2805566788 0.1174060617 1.2805566788 0.0220040691 0.1049460000 9812923 955859216 1783881728 -0.0869901776 1.0506291389 2.8681993484 481 19.2000000000 1.4345099926 0.1201443235 1.4345099926 0.0230499114 0.0793090000 9814177 955859216 1785278464 -0.3155035973 1.0470031500 2.8649563789 482 19.2400000000 1.5493167639 0.1231094116 1.5493167639 0.0235151832 0.1129050000 9815431 955859216 1787056128 -0.4725358784 1.0416712761 2.8499791622 483 19.2800000000 1.5556529760 0.1260753403 1.5556529760 0.0234909092 0.0878050000 9816685 955859216 1785933824 -0.4566930830 1.0486763716 2.8692016602 484 19.3200000000 1.5545244217 0.1290266814 1.5556529760 0.0234705188 0.0845010000 9817939 955859216 1783767040 -0.4412404597 1.0520435572 2.8782920837 485 19.3600000000 1.5627026558 0.1319827143 1.5627026558 0.0234499349 0.0879340000 9819193 955859216 1782628352 -0.4387300611 1.0575674772 2.8790254593 486 19.4000000000 1.9004951715 0.1356216288 1.9004951715 0.0273525739 0.1250050000 9820447 955859216 1780883456 -0.8877098560 1.0325423479 2.8094475269 487 19.4400000000 1.9263131618 0.1392986135 1.9263131618 0.0273705452 0.1093570000 9821701 955859216 1782374400 -0.9091635942 1.0291116238 2.8161187172 488 19.4800000000 2.0679178238 0.1432507020 2.0679178238 0.0279396086 0.0871770000 9822955 955859216 1784135680 -1.0935643911 1.0045723915 2.7616779804 489 19.5200000000 2.0934960842 0.1472389339 2.0934960842 0.0279175108 0.0904640000 9824209 955859216 1785786368 -1.1208232641 0.9995232821 2.7501595020 490 19.5600000000 2.2122504711 0.1514532432 2.2122504711 0.0282171702 0.0839990000 9825463 955859216 1787564032 -1.2665888071 0.9788441658 2.6886193752 491 19.6000000000 2.2629892826 0.1557537239 2.2629892826 0.0282233576 0.0876700000 9826717 955859216 1786310656 -1.3351711035 0.9521972537 2.6269857883 492 19.6400000000 2.2571554184 0.1600248655 2.2629892826 0.0282010923 0.0868830000 9827971 955859216 1784274944 -1.3298060894 0.9482067227 2.6167709827 493 19.6800000000 2.3253417015 0.1644169889 2.3253417015 0.0282709288 0.1041480000 9829225 955859216 1782247424 -1.4232400656 0.9130032063 2.5214564800 494 19.7200000000 2.3212852478 0.1687831190 2.3253417015 0.0282429634 0.1302950000 9830479 955859216 1783771136 -1.4185109138 0.9040579200 2.5184254646 495 19.7600000000 2.3317828178 0.1731528154 2.3317828178 0.0282213460 0.1081120000 9831733 955859216 1785532416 -1.4307923317 0.8989840746 2.5029735565 496 19.8000000000 2.3141558170 0.1774693537 2.3317828178 0.0282172480 0.0888480000 9832987 955859216 1787310080 -1.4135382175 0.8960486650 2.5021131039 497 19.8400000000 2.3186895847 0.1817776439 2.3317828178 0.0281928147 0.0878610000 9834241 955859216 1786171392 -1.4154305458 0.8920121193 2.4962320328 498 19.8800000000 2.3092710972 0.1860497191 2.3317828178 0.0281766921 0.0862040000 9835495 955859216 1784168448 -1.4084732533 0.8859641552 2.4867572784 499 19.9200000000 2.3231544495 0.1903324941 2.3317828178 0.0281522449 0.1082310000 9836749 955859216 1782145024 -1.4338800907 0.8614094853 2.4346823692 500 19.9600000000 2.6209173203 0.1951936638 2.6209173203 0.0309234904 0.1435950000 9838003 955859216 1780989952 -1.7723942995 0.7839585543 2.2734744549 501 20.0000000000 2.7699072361 0.2003328126 2.7699072361 0.0315442097 0.1320870000 9839257 955859216 1779847168 -1.9332158566 0.7444635034 2.1947088242 502 20.0400000000 2.7671132088 0.2054459210 2.7699072361 0.0315302529 0.0889960000 9840511 955859216 1778593792 -1.9266204834 0.7439056635 2.1977488995 503 20.0800000000 2.7859170437 0.2105760823 2.7859170437 0.0315040822 0.1060370000 9841765 955859216 1777434624 -1.9444239140 0.7412748337 2.1767649651 504 20.1200000000 2.8224787712 0.2157584289 2.8224787712 0.0315020427 0.1080790000 9843019 955859216 1778946048 -1.9839363098 0.7315290570 2.1462848186 505 20.1600000000 2.7899022102 0.2208557433 2.8224787712 0.0315286198 0.1098750000 9844273 955859216 1780707328 -1.9554083347 0.7259719968 2.1461069584 506 20.2000000000 2.7596049309 0.2258730342 2.8224787712 0.0315771628 0.0905170000 9845527 955859216 1782358016 -1.9245163202 0.7291306257 2.1503119469 507 20.2400000000 2.7485904694 0.2308488082 2.8224787712 0.0315579035 0.1075410000 9846781 955859216 1784135680 -1.9138990641 0.7267599702 2.1430051327 508 20.2800000000 2.7308554649 0.2357700811 2.8224787712 0.0315449413 0.1081760000 9848035 955859216 1785786368 -1.9035644531 0.7221179008 2.1369431019 509 20.3200000000 2.7236862183 0.2406579321 2.8224787712 0.0315210441 0.1311480000 9849289 955859216 1787437056 -1.8926756382 0.7210993767 2.1372551918 510 20.3600000000 2.7120172977 0.2455037348 2.8224787712 0.0315101395 0.1098470000 9850543 955859216 1784786944 -1.8761163950 0.7226184011 2.1360592842 511 20.4000000000 2.7016909122 0.2503103633 2.8224787712 0.0314956140 0.0896470000 9851797 955859216 1783418880 -1.8628993034 0.7257344723 2.1323671341 512 20.4400000000 2.7515194416 0.2551955373 2.8224787712 0.0314737061 0.1059540000 9853051 955859216 1782517760 -1.8909493685 0.8351870775 2.0639183521 513 20.4800000000 2.7125968933 0.2599857933 2.8224787712 0.0314940620 0.1094100000 9895265 955859216 1781133312 -1.8532444239 0.8055505157 2.0998768806 514 20.5200000000 2.7073168755 0.2647471379 2.8224787712 0.0314921463 0.1076710000 9980487 955859216 1779974144 -1.8675700426 0.7160758376 2.1028122902 515 20.5600000000 2.6751160622 0.2694274659 2.8224787712 0.0315265509 0.1082520000 9981741 955859216 1778814976 -1.8274313211 0.7256531119 2.1110568047 516 20.6000000000 2.6631889343 0.2740665385 2.8224787712 0.0315055888 0.1288010000 9982995 955859216 1777577984 -1.8115744591 0.7262841463 2.1109437943 517 20.6400000000 2.6591272354 0.2786798087 2.8224787712 0.0314859355 0.0857190000 9984249 955859216 1776529408 -1.8119657040 0.7227771282 2.1096060276 518 20.6800000000 2.6459438801 0.2832498165 2.8224787712 0.0314709546 0.0916190000 9985503 955859216 1775403008 -1.7834408283 0.7234037519 2.1147608757 519 20.7200000000 2.6416974068 0.2877940316 2.8224787712 0.0314625105 0.0997210000 9986757 955859216 1774260224 -1.7890362740 0.7231424451 2.1078362465 520 20.7600000000 2.6365540028 0.2923108777 2.8224787712 0.0314403208 0.0972940000 9988011 955859216 1773117440 -1.7915999889 0.7222881317 2.1016566753 521 20.8000000000 2.6277241707 0.2967934368 2.8224787712 0.0314135459 0.0914250000 9989265 955859216 1771974656 -1.7853600979 0.7181189060 2.0977566242 522 20.8400000000 2.6227602959 0.3012493120 2.8224787712 0.0313857711 0.0874620000 9990519 955859216 1770942464 -1.7782547474 0.7137815356 2.0982162952 523 20.8800000000 2.6206755638 0.3056841614 2.8224787712 0.0313697498 0.1062040000 9991773 955859216 1769816064 -1.7873822451 0.7101500034 2.0922026634 524 20.9200000000 2.6129438877 0.3100873288 2.8224787712 0.0313567259 0.1118700000 9993027 955859216 1768902656 -1.7613190413 0.7128196359 2.0979435444 525 20.9600000000 2.6075284481 0.3144634071 2.8224787712 0.0313385829 0.0873620000 9994281 955859216 1767768064 -1.7561050653 0.7117303610 2.0960764885 526 21.0000000000 2.6011645794 0.3188107478 2.8224787712 0.0313186625 0.0863140000 9995535 955859216 1769295872 -1.7409932613 0.7090018392 2.0987951756 527 21.0400000000 2.5934557915 0.3231269623 2.8224787712 0.0313152743 0.0860040000 9996789 955859216 1768677376 -1.7318837643 0.7086272836 2.0961220264 528 21.0800000000 2.5907046795 0.3274216170 2.8224787712 0.0312991461 0.1060500000 9998043 955859216 1766375424 -1.7258574963 0.7088901401 2.0969791412 529 21.1200000000 2.5816450119 0.3316829089 2.8224787712 0.0312869532 0.1217860000 9999297 955859216 1765117952 -1.7018824816 0.7081941962 2.1007702351 530 21.1600000000 2.5776164532 0.3359205194 2.8224787712 0.0312772708 0.0870190000 10000551 955859216 1765007360 -1.7015017271 0.7074260712 2.0971531868 531 21.2000000000 2.5695357323 0.3401269510 2.8224787712 0.0312629035 0.1364500000 10001805 955859216 1765007360 -1.6840801239 0.7062197328 2.0985848904 532 21.2400000000 2.5626912117 0.3443047034 2.8224787712 0.0312497036 0.0992870000 10003059 955859216 1765007360 -1.6763683558 0.7042632103 2.0962834358 533 21.2800000000 2.5570623875 0.3484562187 2.8224787712 0.0312301111 0.0911850000 10004313 955859216 1764962304 -1.6721513271 0.7022287250 2.0936570168 534 21.3200000000 2.5488784313 0.3525768596 2.8224787712 0.0312177615 0.1288050000 10005567 955859216 1764990976 -1.6550868750 0.7008774877 2.0947382450 535 21.3600000000 2.5394852161 0.3566645388 2.8224787712 0.0312058929 0.1103900000 10006821 955859216 1766502400 -1.6391427517 0.7024466395 2.0928835869 536 21.4000000000 2.5342512131 0.3607272005 2.8224787712 0.0311860853 0.0895770000 10008075 955859216 1768390656 -1.6365392208 0.7000480294 2.0896399021 537 21.4400000000 2.5251004696 0.3647576907 2.8224787712 0.0311690645 0.1053950000 10009329 955859216 1770041344 -1.6176972389 0.6986249685 2.0904021263 538 21.4800000000 2.5178816319 0.3687597798 2.8224787712 0.0311521819 0.1121890000 10010583 955859216 1771819008 -1.6100584269 0.6970888972 2.0873777866 539 21.5200000000 2.5183510780 0.3727478899 2.8224787712 0.0311267949 0.1062680000 10011837 955859216 1773469696 -1.6130837202 0.6928507090 2.0816493034 540 21.5600000000 2.5113775730 0.3767083152 2.8224787712 0.0311075987 0.1087250000 10013091 955859216 1775247360 -1.6021736860 0.6934575438 2.0773432255 541 21.6000000000 2.4967739582 0.3806271057 2.8224787712 0.0310961707 0.0912570000 10014345 955859216 1776898048 -1.5856261253 0.6952036023 2.0746381283 542 21.6400000000 2.4874429703 0.3845142198 2.8224787712 0.0310706380 0.0881240000 10015599 955859216 1778548736 -1.5727612972 0.6918969750 2.0725288391 543 21.6800000000 2.4836997986 0.3883801233 2.8224787712 0.0310486335 0.0895950000 10016853 955859216 1780326400 -1.5674178600 0.6890638471 2.0724127293 544 21.7200000000 2.4751987457 0.3922161869 2.8224787712 0.0310320407 0.1087660000 10018107 955859216 1781977088 -1.5578645468 0.6878760457 2.0688855648 545 21.7600000000 2.4669985771 0.3960231271 2.8224787712 0.0310121773 0.1102900000 10019361 955859216 1783754752 -1.5459467173 0.6852127314 2.0672729015 546 21.8000000000 2.4624047279 0.3998077088 2.8224787712 0.0309945806 0.0871460000 10020615 955859216 1785405440 -1.5394741297 0.6853766441 2.0655708313 547 21.8400000000 2.4537203312 0.4035625764 2.8224787712 0.0309757985 0.0892670000 10021869 955859216 1787056128 -1.5277954340 0.6853384972 2.0622582436 548 21.8800000000 2.4484727383 0.4072941643 2.8224787712 0.0309522697 0.1102920000 10023123 955859216 1784791040 -1.5259428024 0.6838068366 2.0582051277 549 21.9200000000 2.4437966347 0.4110036406 2.8224787712 0.0309297451 0.1393280000 10024377 955859216 1783418880 -1.5195739269 0.6823105216 2.0569798946 550 21.9600000000 2.4375486374 0.4146882679 2.8224787712 0.0309097701 0.0914790000 10025631 955859216 1782231040 -1.5136665106 0.6831096411 2.0530798435 551 22.0000000000 2.4311370850 0.4183478846 2.8224787712 0.0308860450 0.1023310000 10026885 955859216 1781116928 -1.5062476397 0.6820051074 2.0503861904 552 22.0400000000 2.4264309406 0.4219857162 2.8224787712 0.0308641881 0.0916410000 10028139 955859216 1779974144 -1.4975314140 0.6827741861 2.0494525433 553 22.0800000000 2.4232871532 0.4256047062 2.8224787712 0.0308425948 0.0722220000 10029393 955859216 1778831360 -1.4957535267 0.6819598675 2.0473353863 554 22.1200000000 2.4180119038 0.4292011090 2.8224787712 0.0308224289 0.0858180000 10030647 955859216 1777688576 -1.4891424179 0.6795565486 2.0458033085 555 22.1600000000 2.4115211964 0.4327728569 2.8224787712 0.0308082947 0.0867140000 10031901 955859216 1776545792 -1.4818065166 0.6806611419 2.0422403812 556 22.2000000000 2.4039793015 0.4363181923 2.8224787712 0.0307869744 0.1089200000 10033155 955859216 1775403008 -1.4738835096 0.6816712022 2.0378196239 557 22.2400000000 2.4001705647 0.4398439596 2.8224787712 0.0307615803 0.1094910000 10034409 955859216 1774260224 -1.4704293013 0.6781758666 2.0367865562 558 22.2800000000 2.3938875198 0.4433458297 2.8224787712 0.0307411281 0.0878920000 10035663 955859216 1773228032 -1.4656723738 0.6742579341 2.0339186192 559 22.3200000000 2.3888084888 0.4468260849 2.8224787712 0.0307308135 0.0882490000 10036917 955859216 1772101632 -1.4611419439 0.6753633618 2.0303947926 560 22.3600000000 2.3851554394 0.4502873874 2.8224787712 0.0307137995 0.1084940000 10038171 955859216 1771569152 -1.4587502480 0.6742452383 2.0281515121 561 22.4000000000 2.3806521893 0.4537283228 2.8224787712 0.0306962645 0.1074810000 10039425 955859216 1769807872 -1.4499015808 0.6730030775 2.0280926228 562 22.4400000000 2.3765194416 0.4571496593 2.8224787712 0.0306805644 0.1094310000 10040679 955859216 1768656896 -1.4473280907 0.6728746295 2.0253238678 563 22.4800000000 2.3701341152 0.4605475003 2.8224787712 0.0306603792 0.1107240000 10041933 955859216 1767530496 -1.4379988909 0.6719974875 2.0233683586 564 22.5200000000 2.3654143810 0.4639249238 2.8224787712 0.0306392251 0.1051540000 10043187 955859216 1766645760 -1.4322862625 0.6688287854 2.0223767757 565 22.5600000000 2.3587040901 0.4672785153 2.8224787712 0.0306252365 0.1100500000 10044441 955859216 1765498880 -1.4204442501 0.6658847928 2.0217661858 566 22.6000000000 2.3536410332 0.4706113113 2.8224787712 0.0306192139 0.0899870000 10045695 955859216 1764982784 -1.4139199257 0.6639178395 2.0202412605 567 22.6400000000 2.3494729996 0.4739250003 2.8224787712 0.0306092532 0.0827280000 10046949 955859216 1764990976 -1.4074699879 0.6629135013 2.0191612244 568 22.6800000000 2.3441927433 0.4772177252 2.8224787712 0.0305947338 0.1085710000 10048203 955859216 1764990976 -1.3984538317 0.6602158546 2.0185894966 569 22.7200000000 2.3373301029 0.4804868155 2.8224787712 0.0305827536 0.1017210000 10049457 955859216 1764990976 -1.3880585432 0.6576338410 2.0169303417 570 22.7600000000 2.3282339573 0.4837284771 2.8224787712 0.0305745749 0.1211820000 10050711 955859216 1764990976 -1.3795927763 0.6576836109 2.0113446712 571 22.8000000000 2.3202588558 0.4869448176 2.8224787712 0.0305537814 0.1220550000 10051965 955859216 1764990976 -1.3723608255 0.6570211649 2.0065014362 572 22.8400000000 2.3137309551 0.4901384996 2.8224787712 0.0305296837 0.1102750000 10053219 955859216 1764990976 -1.3646179438 0.6517530680 2.0048494339 573 22.8800000000 2.3058059216 0.4933072037 2.8224787712 0.0305154852 0.0870060000 10054473 955859216 1764990976 -1.3563283682 0.6493154168 2.0010750294 574 22.9200000000 2.2979307175 0.4964511471 2.8224787712 0.0304961352 0.0824900000 10055727 955859216 1764732928 -1.3510628939 0.6484540701 1.9956223965 575 22.9600000000 2.2895038128 0.4995694995 2.8224787712 0.0304727062 0.0714760000 10056981 955859216 1764990976 -1.3427938223 0.6434493661 1.9921944141 576 23.0000000000 2.2833402157 0.5026663237 2.8224787712 0.0304521715 0.0876450000 10058235 955859216 1764990976 -1.3365347385 0.6384491920 1.9902046919 577 23.0400000000 2.2744934559 0.5057370813 2.8224787712 0.0304400052 0.0881500000 10059489 955859216 1764990976 -1.3285398483 0.6380004883 1.9846410751 578 23.0800000000 2.2663154602 0.5087830646 2.8224787712 0.0304196768 0.0875920000 10060743 955859216 1764974592 -1.3202811480 0.6353141665 1.9805992842 579 23.1200000000 2.2589199543 0.5118057536 2.8224787712 0.0303990868 0.1262960000 10061997 955859216 1765007360 -1.3121743202 0.6312028766 1.9776821136 580 23.1600000000 2.2505574226 0.5148036013 2.8224787712 0.0303794805 0.0888060000 10063251 955859216 1764990976 -1.3031276464 0.6281750798 1.9737999439 581 23.2000000000 2.2419443130 0.5177763047 2.8224787712 0.0303580612 0.0905970000 10064505 955859216 1764990976 -1.2951973677 0.6262868047 1.9688422680 582 23.2400000000 2.2324469090 0.5207224742 2.8224787712 0.0303357184 0.0850180000 10065759 955859216 1764990976 -1.2857532501 0.6218819618 1.9643828869 583 23.2800000000 2.2254514694 0.5236465376 2.8224787712 0.0303141750 0.0719160000 10067013 955859216 1764990976 -1.2774512768 0.6173563004 1.9619255066 584 23.3200000000 2.2150189877 0.5265427233 2.8224787712 0.0303025930 0.0972490000 10068267 955859216 1764990976 -1.2679849863 0.6148597002 1.9559154510 585 23.3600000000 2.2053139210 0.5294124177 2.8224787712 0.0302866616 0.1121920000 10069521 955859216 1764990976 -1.2582674026 0.6118140221 1.9507991076 586 23.4000000000 2.1968843937 0.5322579330 2.8224787712 0.0302705596 0.0853370000 10070775 955859216 1764753408 -1.2484583855 0.6067204475 1.9476004839 587 23.4400000000 2.1884820461 0.5350794392 2.8224787712 0.0302656536 0.0881950000 10072029 955859216 1764962304 -1.2402956486 0.6040056348 1.9430459738 588 23.4800000000 2.1651909351 0.5378517376 2.8224787712 0.0303259727 0.1098260000 10073283 955859216 1764974592 -1.2165539265 0.6002579927 1.9295877218 589 23.5200000000 2.1559803486 0.5405989848 2.8224787712 0.0303126703 0.0874570000 10074537 955859216 1766612992 -1.2083323002 0.5993139744 1.9236481190 590 23.5600000000 2.1451280117 0.5433185256 2.8224787712 0.0302945259 0.1100660000 10075791 955859216 1768771584 -1.1987999678 0.5978473425 1.9167380333 591 23.6000000000 2.1359646320 0.5460133582 2.8224787712 0.0302726768 0.0899930000 10077045 955859216 1770422272 -1.1890543699 0.5933495760 1.9123756886 592 23.6400000000 2.1249382496 0.5486804611 2.8224787712 0.0302544955 0.1098840000 10078299 955859216 1772199936 -1.1769618988 0.5882992744 1.9071261883 593 23.6800000000 2.1141893864 0.5513204424 2.8224787712 0.0302423208 0.0870550000 10079553 955859216 1773850624 -1.1664121151 0.5854799747 1.9008972645 594 23.7200000000 2.1041202545 0.5539345835 2.8224787712 0.0302287023 0.1078660000 10080807 955859216 1775628288 -1.1561996937 0.5827465057 1.8951801062 595 23.7600000000 2.0953786373 0.5565252458 2.8224787712 0.0302128389 0.1119890000 10082061 955859216 1777278976 -1.1490278244 0.5793327689 1.8899490833 596 23.8000000000 2.0841689110 0.5590884063 2.8224787712 0.0302013893 0.0967740000 10083315 955859216 1778929664 -1.1379711628 0.5777916908 1.8829513788 597 23.8400000000 2.0739428997 0.5616258510 2.8224787712 0.0301850624 0.1180670000 10084569 955859216 1780707328 -1.1295813322 0.5765305758 1.8759930134 598 23.8800000000 2.0625798702 0.5641358076 2.8224787712 0.0301673419 0.0901780000 10085823 955859216 1782358016 -1.1178661585 0.5733947158 1.8694655895 599 23.9200000000 2.0523409843 0.5666202903 2.8224787712 0.0301490835 0.0890630000 10087077 955859216 1784135680 -1.1098934412 0.5723968148 1.8622528315 600 23.9600000000 2.0424594879 0.5690800223 2.8224787712 0.0301280033 0.0896020000 10088331 955859216 1785786368 -1.1004905701 0.5700666308 1.8560916185 601 24.0000000000 2.0324320793 0.5715148843 2.8224787712 0.0301076081 0.1483230000 10089585 955859216 1787564032 -1.0923565626 0.5670825839 1.8497132063 602 24.0400000000 2.0217549801 0.5739239210 2.8224787712 0.0300889564 0.0861860000 10090839 955859216 1786298368 -1.0817600489 0.5643835664 1.8431838751 603 24.0800000000 2.0124042034 0.5763094605 2.8224787712 0.0300692198 0.0860770000 10092093 955859216 1784897536 -1.0750553608 0.5619068146 1.8368047476 604 24.1200000000 2.0036542416 0.5786726141 2.8224787712 0.0300486867 0.0861510000 10093347 955859216 1783894016 -1.0689842701 0.5598233938 1.8306992054 605 24.1600000000 1.9951895475 0.5810139644 2.8224787712 0.0300278333 0.0867280000 10094601 955859216 1782104064 -1.0622975826 0.5564677715 1.8253663778 606 24.2000000000 1.9880435467 0.5833357954 2.8224787712 0.0300059313 0.0885730000 10095855 955859216 1780989952 -1.0563827753 0.5519667864 1.8214122057 607 24.2400000000 1.9772862196 0.5856322541 2.8224787712 0.0299877674 0.0876460000 10097109 955859216 1779847168 -1.0456842184 0.5484061837 1.8149863482 608 24.2800000000 1.9683308601 0.5879064294 2.8224787712 0.0299679517 0.0888310000 10098363 955859216 1778704384 -1.0390632153 0.5472000241 1.8085091114 609 24.3200000000 1.9611263275 0.5901613061 2.8224787712 0.0299459126 0.0874980000 10099617 955859216 1777561600 -1.0316408873 0.5425053239 1.8048102856 610 24.3600000000 1.9541503191 0.5923973536 2.8224787712 0.0299255257 0.1111050000 10100871 955859216 1776418816 -1.0249530077 0.5366724133 1.8015666008 611 24.4000000000 1.9437701702 0.5946090931 2.8224787712 0.0299112930 0.0874000000 10102125 955859216 1777930240 -1.0132175684 0.5331305265 1.7955690622 612 24.4400000000 1.9348562956 0.5967990395 2.8224787712 0.0298960726 0.0883180000 10103379 955859216 1779691520 -1.0060883760 0.5310121775 1.7894167900 613 24.4800000000 1.9282574654 0.5989710761 2.8224787712 0.0298752315 0.0886170000 10104633 955859216 1781469184 -1.0002915859 0.5269854665 1.7856500149 614 24.5200000000 1.9181321859 0.6011195470 2.8224787712 0.0298573012 0.0896540000 10105887 955859216 1783119872 -0.9892225862 0.5219228864 1.7800835371 615 24.5600000000 1.9115154743 0.6032502720 2.8224787712 0.0298384557 0.0883410000 10107141 955859216 1784770560 -0.9822011590 0.5187054873 1.7762906551 616 24.6000000000 1.9033044577 0.6053607496 2.8224787712 0.0298197700 0.0881450000 10108395 955859216 1786548224 -0.9728619456 0.5137022734 1.7719825506 617 24.6400000000 1.8946413994 0.6074503455 2.8224787712 0.0298052875 0.0905610000 10109649 955859216 1788198912 -0.9638243914 0.5096850395 1.7669045925 618 24.6800000000 1.8854742050 0.6095183453 2.8224787712 0.0297920245 0.1056430000 10110903 955859216 1784688640 -0.9526253939 0.5053492785 1.7618223429 619 24.7200000000 1.8746623993 0.6115621967 2.8224787712 0.0297822965 0.0914850000 10112157 955859216 1783418880 -0.9393092990 0.5015171170 1.7554193735 620 24.7600000000 1.8661036491 0.6135856507 2.8224787712 0.0297747482 0.0894070000 10113411 955859216 1782259712 -0.9323846102 0.4995699823 1.7493194342 621 24.8000000000 1.8580129147 0.6155895593 2.8224787712 0.0297594620 0.1058430000 10114665 955859216 1781116928 -0.9237009287 0.4966448545 1.7442122698 622 24.8400000000 1.8497970104 0.6175738157 2.8224787712 0.0297429903 0.0907040000 10115919 955859216 1779974144 -0.9148220420 0.4923646748 1.7392954826 623 24.8800000000 1.8407032490 0.6195371053 2.8224787712 0.0297314840 0.1067710000 10117173 955859216 1778831360 -0.9059776664 0.4901857078 1.7330319881 624 24.9200000000 1.8308616877 0.6214783306 2.8224787712 0.0297169893 0.1074850000 10118427 955859216 1777672192 -0.8971335292 0.4878654182 1.7260560989 625 24.9600000000 1.8223462105 0.6233997192 2.8224787712 0.0297000815 0.1082000000 10119681 955859216 1776545792 -0.8892697692 0.4835935235 1.7206118107 626 25.0000000000 1.8151681423 0.6253035026 2.8224787712 0.0296838560 0.1050360000 10120935 955859216 1775513600 -0.8816301823 0.4793569744 1.7162848711 627 25.0400000000 1.8064028025 0.6271872335 2.8224787712 0.0296762968 0.1083260000 10122189 955859216 1774276608 -0.8736634851 0.4764047861 1.7101976871 628 25.0800000000 1.7966682911 0.6290494645 2.8224787712 0.0296706493 0.1081400000 10123443 955859216 1773117440 -0.8664808273 0.4750212133 1.7026522160 629 25.1200000000 1.7905143499 0.6308959906 2.8224787712 0.0296557194 0.1089250000 10124697 955859216 1771974656 -0.8618268371 0.4722504020 1.6983886957 630 25.1600000000 1.7811497450 0.6327217902 2.8224787712 0.0296462418 0.1080090000 10125951 955859216 1770942464 -0.8548098207 0.4690184593 1.6916084290 631 25.2000000000 1.7721314430 0.6345275107 2.8224787712 0.0296374166 0.1084570000 10127205 955859216 1769816064 -0.8487457037 0.4670963883 1.6846280098 632 25.2400000000 1.7653467655 0.6363167817 2.8224787712 0.0296227298 0.1081680000 10128459 955859216 1768783872 -0.8450537324 0.4637117684 1.6797305346 633 25.2800000000 1.7550367117 0.6380841118 2.8224787712 0.0296135982 0.1081160000 10129713 955859216 1767768064 -0.8371004462 0.4613028169 1.6719756126 634 25.3200000000 1.7452913523 0.6398304954 2.8224787712 0.0296005710 0.1084770000 10130967 955859216 1766789120 -0.8321899176 0.4595392942 1.6640419960 635 25.3600000000 1.7382688522 0.6415603196 2.8224787712 0.0295820252 0.1084470000 10132221 955859216 1765744640 -0.8288823366 0.4570359588 1.6586194038 636 25.4000000000 1.7298671007 0.6432714938 2.8224787712 0.0295654369 0.1077430000 10133475 955859216 1764986880 -0.8219611645 0.4527226388 1.6528929472 637 25.4400000000 1.7214610577 0.6449640991 2.8224787712 0.0295512909 0.1076960000 10134729 955859216 1764999168 -0.8174290061 0.4502263963 1.6463261843 638 25.4800000000 1.7141282558 0.6466399050 2.8224787712 0.0295351569 0.0905700000 10135983 955859216 1764999168 -0.8117471933 0.4463039935 1.6411683559 639 25.5200000000 1.7063217163 0.6482982489 2.8224787712 0.0295210959 0.1253250000 10137237 955859216 1764999168 -0.8086736798 0.4415889084 1.6355010271 640 25.5600000000 1.6992993355 0.6499404381 2.8224787712 0.0295055836 0.0829250000 10138491 955859216 1764999168 -0.8051000237 0.4380076230 1.6303058863 641 25.6000000000 1.6909879446 0.6515645372 2.8224787712 0.0294900577 0.0881530000 10139745 955859216 1765097472 -0.8013095260 0.4341184497 1.6240180731 642 25.6400000000 1.6838600636 0.6531724742 2.8224787712 0.0294734940 0.0963950000 10140999 955859216 1764982784 -0.7996044159 0.4306455553 1.6181889772 643 25.6800000000 1.6754595041 0.6547623451 2.8224787712 0.0294568215 0.1025990000 10142253 955859216 1764982784 -0.7950989008 0.4258724749 1.6123952866 644 25.7200000000 1.6674549580 0.6563348492 2.8224787712 0.0294397268 0.0878910000 10143507 955859216 1764999168 -0.7930067778 0.4220406413 1.6061774492 645 25.7600000000 1.6596237421 0.6578903359 2.8224787712 0.0294217946 0.1059580000 10144761 955859216 1764999168 -0.7894660234 0.4174809754 1.6003985405 646 25.8000000000 1.6517534256 0.6594288236 2.8224787712 0.0294042846 0.0888290000 10146015 955859216 1764999168 -0.7887569070 0.4130153656 1.5942665339 647 25.8400000000 1.6415379047 0.6609467665 2.8224787712 0.0293893593 0.0848430000 10147269 955859216 1764999168 -0.7866660357 0.4099512696 1.5857558250 648 25.8800000000 1.6328977346 0.6624466909 2.8224787712 0.0293710312 0.0966590000 10148523 955859216 1764999168 -0.7855733037 0.4061753154 1.5787693262 649 25.9200000000 1.6240260601 0.6639283232 2.8224787712 0.0293521213 0.1437490000 10149777 955859216 1764999168 -0.7843247652 0.4003174007 1.5720849037 650 25.9600000000 1.6071741581 0.6653794706 2.8224787712 0.0293598553 0.1100670000 10151031 955859216 1764970496 -0.7822589874 0.3873733878 1.5597974062 651 26.0000000000 1.5848833323 0.6667919190 2.8224787712 0.0293990814 0.1057560000 10152285 955859216 1764859904 -0.7802875042 0.3793322146 1.5413751602 652 26.0400000000 1.5730528831 0.6681818898 2.8224787712 0.0293909205 0.1078100000 10153539 955859216 1766494208 -0.7794185281 0.3758120537 1.5312026739 653 26.0800000000 1.5600657463 0.6695477150 2.8224787712 0.0293801219 0.0919080000 10154793 955859216 1768525824 -0.7795466185 0.3742513061 1.5196398497 654 26.1200000000 1.5483812094 0.6708914971 2.8224787712 0.0293643995 0.1465870000 10156047 955859216 1770303488 -0.7806541324 0.3696674109 1.5098235607 655 26.1600000000 1.5393697023 0.6722174180 2.8224787712 0.0293585243 0.0890960000 10157301 955859216 1771954176 -0.7819337249 0.3634369969 1.5017484426 656 26.2000000000 1.5241665840 0.6735161210 2.8224787712 0.0293480386 0.1074770000 10158555 955859216 1773604864 -0.7803175449 0.3591516614 1.4898782969 657 26.2400000000 1.5121691227 0.6747926096 2.8224787712 0.0293385205 0.1083640000 10159809 955859216 1775382528 -0.7815383673 0.3550324738 1.4795762300 658 26.2800000000 1.4988639355 0.6760449976 2.8224787712 0.0293315851 0.0925840000 10161063 955859216 1777033216 -0.7821874619 0.3515358567 1.4679454565 659 26.3200000000 1.4851957560 0.6772728440 2.8224787712 0.0293232932 0.1091450000 10162317 955859216 1778810880 -0.7839581370 0.3491801322 1.4557530880 660 26.3600000000 1.4726282358 0.6784779279 2.8224787712 0.0293122728 0.1056080000 10163571 955859216 1780461568 -0.7850825787 0.3456662297 1.4448721409 661 26.4000000000 1.4586483240 0.6796582159 2.8224787712 0.0293015759 0.1080950000 10164825 955859216 1782239232 -0.7865891457 0.3429138362 1.4323620796 662 26.4400000000 1.4460246563 0.6808158692 2.8224787712 0.0292884750 0.0924550000 10166079 955859216 1783889920 -0.7901107669 0.3414588571 1.4205602407 663 26.4800000000 1.4342213869 0.6819522274 2.8224787712 0.0292778918 0.1100090000 10167333 955859216 1785540608 -0.7915254831 0.3366469443 1.4105305672 664 26.5200000000 1.4221010208 0.6830669093 2.8224787712 0.0292663193 0.1071640000 10168587 955859216 1787318272 -0.7907633781 0.3293398023 1.4010829926 665 26.5600000000 1.4103690386 0.6841605968 2.8224787712 0.0292544387 0.1250840000 10169841 955859216 1784557568 -0.7924548388 0.3255328834 1.3909163475 666 26.6000000000 1.3975569010 0.6852317624 2.8224787712 0.0292422823 0.1496250000 10171095 955859216 1783410688 -0.7938560247 0.3228846788 1.3794546127 667 26.6400000000 1.3861445189 0.6862826061 2.8224787712 0.0292266855 0.1097920000 10172349 955859216 1782267904 -0.7968472242 0.3213800490 1.3688460588 668 26.6800000000 1.3731743097 0.6873108871 2.8224787712 0.0292118621 0.1053980000 10173603 955859216 1781125120 -0.7984648347 0.3207055032 1.3567215204 669 26.7200000000 1.3611370325 0.6883181011 2.8224787712 0.0292006799 0.1243310000 10174857 955859216 1782636544 -0.8004876971 0.3175475895 1.3459521532 670 26.7600000000 1.3504048586 0.6893062902 2.8224787712 0.0291873388 0.1304640000 10176111 955859216 1784397824 -0.8016979098 0.3132736981 1.3368569613 671 26.8000000000 1.3394089937 0.6902751467 2.8224787712 0.0291723211 0.0896650000 10177365 955859216 1786048512 -0.8023301363 0.3094519973 1.3273965120 672 26.8400000000 1.3276261091 0.6912235857 2.8224787712 0.0291578838 0.1057960000 10178619 955859216 1787826176 -0.8025884032 0.3076343536 1.3168119192 673 26.8800000000 1.3194226027 0.6921570166 2.8224787712 0.0291503723 0.0882730000 10179873 955859216 1786839040 -0.8050712347 0.3037241399 1.3090472221 674 26.9200000000 1.3065624237 0.6930685973 2.8224787712 0.0291347427 0.1088500000 10181127 955859216 1783148544 -0.8032292724 0.3014907241 1.2985137701 675 26.9600000000 1.2965366840 0.6939626241 2.8224787712 0.0291222338 0.1074180000 10182381 955859216 1781997568 -0.8042965531 0.2995963991 1.2894589901 676 27.0000000000 1.2852697372 0.6948373388 2.8224787712 0.0291105736 0.0899620000 10183635 955859216 1780871168 -0.8048805594 0.2996714115 1.2787909508 677 27.0400000000 1.2756054401 0.6956951942 2.8224787712 0.0290963521 0.1060410000 10184889 955859216 1779728384 -0.8068329096 0.2990983427 1.2695835829 678 27.0800000000 1.2658890486 0.6965361881 2.8224787712 0.0290833148 0.1078450000 10186143 955859216 1778585600 -0.8073810339 0.2973396778 1.2607898712 679 27.1200000000 1.2551560402 0.6973588977 2.8224787712 0.0290711277 0.1085040000 10187397 955859216 1777442816 -0.8076317906 0.2952911258 1.2511576414 680 27.1600000000 1.2450273037 0.6981642924 2.8224787712 0.0290592545 0.1084590000 10188651 955859216 1776300032 -0.8064022064 0.2913555205 1.2428891659 681 27.2000000000 1.2355800867 0.6989534492 2.8224787712 0.0290451492 0.0903760000 10189905 955859216 1775157248 -0.8067830205 0.2890179455 1.2344673872 682 27.2400000000 1.2248240709 0.6997245205 2.8224787712 0.0290321861 0.1064630000 10191159 955859216 1774125056 -0.8063129783 0.2886597216 1.2245585918 683 27.2800000000 1.2143907547 0.7004780582 2.8224787712 0.0290189979 0.1018400000 10192413 955859216 1772998656 -0.8055630326 0.2875905633 1.2151528597 684 27.3200000000 1.2041218281 0.7012143795 2.8224787712 0.0290066706 0.0930080000 10193667 955859216 1771855872 -0.8052126169 0.2849137485 1.2061876059 685 27.3600000000 1.1936637163 0.7019332837 2.8224787712 0.0289937686 0.1042770000 10194921 955859216 1770713088 -0.8034605384 0.2818870544 1.1973830462 686 27.4000000000 1.1819504499 0.7026330171 2.8224787712 0.0289806423 0.1080990000 10196175 955859216 1769680896 -0.8020277619 0.2811580002 1.1867568493 687 27.4400000000 1.1705368757 0.7033140999 2.8224787712 0.0289698235 0.1087380000 10197429 955859216 1768665088 -0.8002864122 0.2804644704 1.1764521599 688 27.4800000000 1.1594419479 0.7039770764 2.8224787712 0.0289642443 0.0910840000 10198683 955859216 1767649280 -0.7988524437 0.2780511379 1.1668145657 689 27.5200000000 1.1481242180 0.7046217022 2.8224787712 0.0289580426 0.0883340000 10199937 955859216 1766633472 -0.7971347570 0.2756133676 1.1570547819 690 27.5600000000 1.1367930174 0.7052480374 2.8224787712 0.0289510739 0.1053280000 10201191 955859216 1765617664 -0.7943748832 0.2729665935 1.1474307775 691 27.6000000000 1.1242063046 0.7058543446 2.8224787712 0.0289437439 0.0907210000 10202445 955859216 1765007360 -0.7923300862 0.2726701200 1.1359711885 692 27.6400000000 1.1118266582 0.7064410098 2.8224787712 0.0289399486 0.1046590000 10203699 955859216 1764999168 -0.7900813222 0.2718208432 1.1248488426 693 27.6800000000 1.1003670692 0.7070094457 2.8224787712 0.0289383313 0.0903050000 10204953 955859216 1764982784 -0.7868248820 0.2682048082 1.1154136658 694 27.7200000000 1.0890665054 0.7075599602 2.8224787712 0.0289307618 0.0895640000 10206207 955859216 1764982784 -0.7826928496 0.2634812891 1.1064976454 695 27.7600000000 1.0784370899 0.7080935963 2.8224787712 0.0289184767 0.0887880000 10207461 955859216 1764999168 -0.7789399624 0.2589415908 1.0981730223 696 27.8000000000 1.0666195154 0.7086087198 2.8224787712 0.0289095742 0.1059710000 10208715 955859216 1764999168 -0.7753449678 0.2570385933 1.0880198479 697 27.8400000000 1.0545390844 0.7091050331 2.8224787712 0.0289020284 0.0989490000 10209969 955859216 1764999168 -0.7722181082 0.2559428215 1.0773384571 698 27.8800000000 1.0418648720 0.7095817663 2.8224787712 0.0288941043 0.1151920000 10211223 955859216 1764999168 -0.7700146437 0.2556577921 1.0657277107 699 27.9200000000 1.0299841166 0.7100401388 2.8224787712 0.0288842365 0.1706660000 10212477 955859216 1764999168 -0.7678282261 0.2552871406 1.0548912287 700 27.9600000000 1.0176379681 0.7104795643 2.8224787712 0.0288770821 0.1277310000 10213731 955859216 1766510592 -0.7652572989 0.2538603246 1.0439065695 701 28.0000000000 1.0062232018 0.7109014525 2.8224787712 0.0288704500 0.1075350000 10214985 955859216 1768398848 -0.7630299330 0.2519817352 1.0338782072 702 28.0400000000 0.9952616096 0.7113065239 2.8224787712 0.0288634533 0.0909120000 10216239 955859216 1770049536 -0.7607721686 0.2491611540 1.0244487524 703 28.0800000000 0.9858699441 0.7116970836 2.8224787712 0.0288516658 0.1059110000 10217493 955859216 1771700224 -0.7594432235 0.2467344850 1.0163015127 704 28.1200000000 0.9743143916 0.7120701195 2.8224787712 0.0288411629 0.1081220000 10218747 955859216 1773477888 -0.7591401935 0.2485055178 1.0048742294 705 28.1600000000 0.9635646343 0.7124268493 2.8224787712 0.0288371405 0.1089030000 10220001 955859216 1775128576 -0.7587569952 0.2486268431 0.9946163893 706 28.2000000000 0.9546896219 0.7127699977 2.8224787712 0.0288334276 0.1088800000 10221255 955859216 1776779264 -0.7580843568 0.2452904880 0.9870688915 707 28.2400000000 0.9447598457 0.7130981305 2.8224787712 0.0288225725 0.1089560000 10222509 955859216 1778556928 -0.7577016354 0.2449847907 0.9777283072 708 28.2800000000 0.9348871112 0.7134113917 2.8224787712 0.0288124943 0.1088160000 10223763 955859216 1780207616 -0.7584005594 0.2455363572 0.9680055380 709 28.3200000000 0.9279493093 0.7137139840 2.8224787712 0.0288014041 0.1090730000 10225017 955859216 1781858304 -0.7582296729 0.2402781248 0.9626842737 710 28.3600000000 0.9196849465 0.7140040840 2.8224787712 0.0287905275 0.1087090000 10226271 955859216 1783627776 -0.7579439282 0.2382748425 0.9552897215 711 28.4000000000 0.9096417427 0.7142792424 2.8224787712 0.0287798721 0.1088980000 10227525 955859216 1785278464 -0.7597466111 0.2422045469 0.9443438649 712 28.4400000000 0.9007287621 0.7145411097 2.8224787712 0.0287687388 0.1059450000 10228779 955859216 1787056128 -0.7607632875 0.2411607802 0.9358654618 713 28.4800000000 0.8966261744 0.7147964885 2.8224787712 0.0287504062 0.0900750000 10230033 955859216 1785700352 -0.7622711062 0.2360818088 0.9329504371 714 28.5200000000 0.8873982430 0.7150382276 2.8224787712 0.0287516178 0.1106660000 10231287 955859216 1784193024 -0.7649558783 0.2398983538 0.9225912690 715 28.5600000000 0.8782910109 0.7152665532 2.8224787712 0.0287381430 0.1046800000 10232541 955859216 1783021568 -0.7681618333 0.2429482043 0.9124079943 716 28.6000000000 0.8736677170 0.7154877839 2.8224787712 0.0287296258 0.1079260000 10233795 955859216 1781878784 -0.7730164528 0.2422038615 0.9072273970 717 28.6400000000 0.8695122600 0.7157026018 2.8224787712 0.0287145659 0.1164430000 10235049 955859216 1780625408 -0.7781742811 0.2417955548 0.9022591114 718 28.6800000000 0.8639076948 0.7159090156 2.8224787712 0.0286990631 0.0995760000 10236303 955859216 1779449856 -0.7835890055 0.2443069518 0.8949646950 719 28.7200000000 0.8580290675 0.7161066791 2.8224787712 0.0286890597 0.0925510000 10237557 955859216 1778323456 -0.7885925770 0.2448583245 0.8879727721 720 28.7600000000 0.8540630937 0.7162982852 2.8224787712 0.0286786240 0.1051800000 10238811 955859216 1777180672 -0.7952826023 0.2446601242 0.8826499581 721 28.8000000000 0.8511379361 0.7164853028 2.8224787712 0.0286637125 0.1440920000 10240065 955859216 1776148480 -0.8023598790 0.2438745797 0.8782855272 722 28.8400000000 0.8471207023 0.7166662382 2.8224787712 0.0286487865 0.1121940000 10241319 955859216 1775022080 -0.8095245957 0.2439294457 0.8725023866 723 28.8800000000 0.8442128897 0.7168426513 2.8224787712 0.0286332043 0.0882190000 10242573 955859216 1773879296 -0.8176222444 0.2433164716 0.8676330447 724 28.9200000000 0.8403325081 0.7170132174 2.8224787712 0.0286188567 0.1060240000 10243827 955859216 1772736512 -0.8255761266 0.2438046038 0.8613302708 725 28.9600000000 0.8369322419 0.7171786230 2.8224787712 0.0286042806 0.1105960000 10245081 955859216 1771704320 -0.8343177438 0.2441898286 0.8552204967 726 29.0000000000 0.8347452879 0.7173405605 2.8224787712 0.0285952451 0.1060900000 10246335 955859216 1770569728 -0.8433227539 0.2432833612 0.8505547047 727 29.0400000000 0.8314883709 0.7174975726 2.8224787712 0.0285861212 0.0996010000 10247589 955859216 1769308160 -0.8525496125 0.2429091781 0.8443691134 728 29.0800000000 0.8291007876 0.7176508738 2.8224787712 0.0285751080 0.0986070000 10248843 955859216 1768275968 -0.8621668220 0.2430288643 0.8385865092 729 29.1200000000 0.8269066811 0.7178007446 2.8224787712 0.0285607480 0.0909500000 10250097 955859216 1767260160 -0.8719403744 0.2439698875 0.8324164748 730 29.1600000000 0.8252560496 0.7179479436 2.8224787712 0.0285467410 0.1059390000 10251351 955859216 1766244352 -0.8816888928 0.2431696355 0.8272517920 731 29.2000000000 0.8228815198 0.7180914916 2.8224787712 0.0285351905 0.1080100000 10252605 955859216 1765228544 -0.8913254738 0.2433556318 0.8208625317 732 29.2400000000 0.8201472163 0.7182309120 2.8224787712 0.0285257195 0.1072720000 10253859 955859216 1764986880 -0.9014298916 0.2448176146 0.8132435679 733 29.2800000000 0.8192588687 0.7183687400 2.8224787712 0.0285168108 0.0902680000 10255113 955859216 1764986880 -0.9127702713 0.2458105236 0.8069347143 734 29.3200000000 0.8196979165 0.7185067907 2.8224787712 0.0285072179 0.1057330000 10256367 955859216 1764986880 -0.9247605801 0.2475104630 0.8012307882 735 29.3600000000 0.8201920390 0.7186451379 2.8224787712 0.0284974776 0.0904920000 10257621 955859216 1764974592 -0.9361708760 0.2490289807 0.7956401706 736 29.4000000000 0.8213987947 0.7187847489 2.8224787712 0.0284884740 0.0887700000 10258875 955859216 1764974592 -0.9478303194 0.2514676452 0.7900924087 737 29.4400000000 0.8228110075 0.7189258971 2.8224787712 0.0284795002 0.1060170000 10260129 955859216 1765007360 -0.9589941502 0.2530104220 0.7850785851 738 29.4800000000 0.8243700862 0.7190687754 2.8224787712 0.0284768683 0.1070020000 10261383 955859216 1764990976 -0.9703122377 0.2547625899 0.7797998190 739 29.5200000000 0.8267913461 0.7192145435 2.8224787712 0.0284838784 0.0869660000 10262637 955859216 1764990976 -0.9814959168 0.2562537491 0.7753987908 740 29.5600000000 0.8299205899 0.7193641462 2.8224787712 0.0284882076 0.1100770000 10263891 955859216 1764990976 -0.9923772216 0.2575117648 0.7720929980 741 29.6000000000 0.8329038620 0.7195173712 2.8224787712 0.0285013050 0.0826400000 10265145 955859216 1764990976 -1.0030854940 0.2604311109 0.7675477266 742 29.6400000000 0.8370079398 0.7196757143 2.8224787712 0.0285159580 0.0775160000 10266399 955859216 1764990976 -1.0137277842 0.2633547187 0.7641229630 743 29.6800000000 0.8414544463 0.7198396157 2.8224787712 0.0285111272 0.0878580000 10267653 955859216 1764990976 -1.0231505632 0.2642894089 0.7626159191 744 29.7200000000 0.8449329734 0.7200077519 2.8224787712 0.0284964793 0.0874700000 10268907 955859216 1764962304 -1.0316035748 0.2654995918 0.7604129314 745 29.7600000000 0.8478039503 0.7201792905 2.8224787712 0.0284811087 0.0892220000 10270161 955859216 1764990976 -1.0395765305 0.2672943771 0.7574235201 746 29.8000000000 0.8508599997 0.7203544657 2.8224787712 0.0284664043 0.0869420000 10271415 955859216 1764990976 -1.0472583771 0.2684959471 0.7549703121 747 29.8400000000 0.8532731533 0.7205324023 2.8224787712 0.0284578013 0.1055090000 10272669 955859216 1764990976 -1.0546319485 0.2705091536 0.7515082359 748 29.8800000000 0.8560272455 0.7207135452 2.8224787712 0.0284581838 0.1199510000 10273923 955859216 1764990976 -1.0620211363 0.2731237113 0.7480603456 749 29.9200000000 0.8590866327 0.7208982889 2.8224787712 0.0284563494 0.0947630000 10275177 955859216 1764990976 -1.0689117908 0.2753416002 0.7454538941 750 29.9600000000 0.8618978262 0.7210862883 2.8224787712 0.0284558555 0.0876860000 10276431 955859216 1764990976 -1.0753315687 0.2774223089 0.7428932190 751 30.0000000000 0.8643673658 0.7212770754 2.8224787712 0.0284548047 0.1129210000 10277685 955859216 1764990976 -1.0811072588 0.2789375186 0.7405862212 752 30.0400000000 0.8667399883 0.7214705101 2.8224787712 0.0284502914 0.0859080000 10278939 955859216 1764990976 -1.0865288973 0.2807061374 0.7382213473 753 30.0800000000 0.8684157729 0.7216656565 2.8224787712 0.0284483782 0.0858280000 10280193 955859216 1764990976 -1.0914007425 0.2818382084 0.7357194424 754 30.1200000000 0.8699865341 0.7218623686 2.8224787712 0.0284461349 0.1117770000 10281447 955859216 1764974592 -1.0960292816 0.2839977741 0.7332642078 755 30.1600000000 0.8710882664 0.7220600188 2.8224787712 0.0284478951 0.0857880000 10282701 955859216 1764974592 -1.1005805731 0.2850108147 0.7303853035 756 30.2000000000 0.8725912571 0.7222591342 2.8224787712 0.0284499283 0.0876880000 10283955 955859216 1764974592 -1.1055963039 0.2861590981 0.7270075679 757 30.2400000000 0.8733742833 0.7224587579 2.8224787712 0.0284440595 0.1258880000 10285209 955859216 1764990976 -1.1104091406 0.2878500223 0.7231038213 758 30.2800000000 0.8744293451 0.7226592468 2.8224787712 0.0284382460 0.0882630000 10286463 955859216 1764990976 -1.1154677868 0.2888780534 0.7194603682 759 30.3200000000 0.8754109144 0.7228605006 2.8224787712 0.0284469983 0.1040070000 10287717 955859216 1764990976 -1.1209051609 0.2903797925 0.7149471641 760 30.3600000000 0.8756439686 0.7230615315 2.8224787712 0.0284592342 0.0903940000 10288971 955859216 1764990976 -1.1261963844 0.2936532795 0.7088317871 761 30.4000000000 0.8755064607 0.7232618534 2.8224787712 0.0284667301 0.1104380000 10290225 955859216 1764990976 -1.1311055422 0.2958485186 0.7030254006 762 30.4400000000 0.8749501705 0.7234609194 2.8224787712 0.0284658253 0.0867210000 10291479 955859216 1764990976 -1.1359375715 0.2976538241 0.6968907118 763 30.4800000000 0.8743886352 0.7236587277 2.8224787712 0.0284618419 0.0870120000 10292733 955859216 1764962304 -1.1411235332 0.2992952168 0.6903998256 764 30.5200000000 0.8739854693 0.7238554904 2.8224787712 0.0284687399 0.1110450000 10293987 955859216 1764974592 -1.1465225220 0.2973130643 0.6828737259 765 30.5600000000 0.8734606504 0.7240510527 2.8224787712 0.0284588318 0.0862800000 10295241 955859216 1766612992 -1.1520127058 0.2998789847 0.6765452027 766 30.6000000000 0.8729304075 0.7242454122 2.8224787712 0.0284542958 0.1088290000 10296495 955859216 1768771584 -1.1570827961 0.2999277711 0.6689448953 767 30.6400000000 0.8719639778 0.7244380048 2.8224787712 0.0284477696 0.0879160000 10297749 955859216 1770422272 -1.1623160839 0.3007855415 0.6610170007 768 30.6800000000 0.8713262081 0.7246292655 2.8224787712 0.0284418454 0.0891300000 10299003 955859216 1772072960 -1.1676360369 0.3014357686 0.6534543037 769 30.7200000000 0.8709221482 0.7248195033 2.8224787712 0.0284357933 0.0883340000 10300257 955859216 1773850624 -1.1730289459 0.3026741743 0.6456114650 770 30.7600000000 0.8705774546 0.7250087994 2.8224787712 0.0284284028 0.0890360000 10301511 955859216 1775501312 -1.1783801317 0.3041046858 0.6376847625 771 30.8000000000 0.8698703647 0.7251966873 2.8224787712 0.0284211362 0.1130790000 10302765 955859216 1777278976 -1.1832430363 0.3043601811 0.6293849349 772 30.8400000000 0.8692685366 0.7253833088 2.8224787712 0.0284114344 0.1036930000 10304019 955859216 1778929664 -1.1882421970 0.3040009141 0.6220767498 773 30.8800000000 0.8688603640 0.7255689195 2.8224787712 0.0284025223 0.1078750000 10305273 955859216 1780580352 -1.1933580637 0.3040806353 0.6144342422 774 30.9200000000 0.8689780235 0.7257542026 2.8224787712 0.0283936136 0.1115500000 10306527 955859216 1782358016 -1.1987663507 0.3040505946 0.6079229712 775 30.9600000000 0.8683486581 0.7259381954 2.8224787712 0.0283846404 0.0887980000 10307781 955859216 1784008704 -1.2035927773 0.3027149141 0.6009077430 776 31.0000000000 0.8677886724 0.7261209925 2.8224787712 0.0283789522 0.1068430000 10309035 955859216 1785659392 -1.2084404230 0.3017778099 0.5934700370 777 31.0400000000 0.8673523664 0.7263027574 2.8224787712 0.0283786756 0.0878670000 10310289 955859216 1787437056 -1.2130780220 0.3019734025 0.5856027603 778 31.0800000000 0.8669061065 0.7264834815 2.8224787712 0.0283736679 0.0869060000 10311543 955859216 1786318848 -1.2175111771 0.3023944199 0.5777947307 779 31.1200000000 0.8669673204 0.7266638202 2.8224787712 0.0283647065 0.0851940000 10312797 955859216 1784274944 -1.2221773863 0.3019371927 0.5709274411 780 31.1600000000 0.8672068715 0.7268440036 2.8224787712 0.0283570994 0.0870850000 10314051 955859216 1782882304 -1.2265214920 0.3012788296 0.5636487603 781 31.2000000000 0.8668772578 0.7270233035 2.8224787712 0.0283468756 0.1079640000 10315305 955859216 1780961280 -1.2305585146 0.3008426130 0.5565618277 782 31.2400000000 0.8668812513 0.7272021500 2.8224787712 0.0283334395 0.0808020000 10316559 955859216 1782484992 -1.2346185446 0.2996810079 0.5504343510 783 31.2800000000 0.8672121167 0.7273809622 2.8224787712 0.0283196816 0.0880550000 10317813 955859216 1784406016 -1.2388226986 0.2988945246 0.5442600250 784 31.3200000000 0.8675975204 0.7275598099 2.8224787712 0.0283076390 0.0883140000 10319067 955859216 1786040320 -1.2427700758 0.2978663146 0.5386903286 785 31.3600000000 0.8678243756 0.7277384909 2.8224787712 0.0282939517 0.0886520000 10320321 955859216 1787691008 -1.2464535236 0.2963530123 0.5335553885 786 31.4000000000 0.8682740927 0.7279172893 2.8224787712 0.0282799881 0.1424960000 10321575 955859216 1784655872 -1.2502210140 0.2951442301 0.5283547640 787 31.4400000000 0.8688996434 0.7280964283 2.8224787712 0.0282660455 0.1131360000 10322829 955859216 1783529472 -1.2536242008 0.2950446010 0.5231431127 788 31.4800000000 0.8700522184 0.7282765752 2.8224787712 0.0282517260 0.1043540000 10324083 955859216 1782386688 -1.2572571039 0.2943188250 0.5191060901 789 31.5200000000 0.8704846501 0.7284568136 2.8224787712 0.0282377965 0.0897590000 10325337 955859216 1781133312 -1.2604478598 0.2926470637 0.5150607228 790 31.5600000000 0.8713957071 0.7286377489 2.8224787712 0.0282234896 0.1279280000 10326591 955859216 1779945472 -1.2638746500 0.2912254333 0.5112575889 791 31.6000000000 0.8720963597 0.7288191125 2.8224787712 0.0282094347 0.1292600000 10327845 955859216 1781485568 -1.2669346333 0.2899389267 0.5075903535 792 31.6400000000 0.8730397224 0.7290012092 2.8224787712 0.0281950778 0.0864220000 10329099 955859216 1783373824 -1.2699550390 0.2883439958 0.5047425628 793 31.6800000000 0.8737817407 0.7291837824 2.8224787712 0.0281796769 0.1089190000 10330353 955859216 1785024512 -1.2726774216 0.2864644229 0.5023203492 794 31.7200000000 0.8746704459 0.7293670150 2.8224787712 0.0281657788 0.0894360000 10331607 955859216 1786675200 -1.2752854824 0.2845042348 0.5004979968 795 31.7600000000 0.8755235076 0.7295508596 2.8224787712 0.0281553109 0.1269020000 10332861 955859216 1785552896 -1.2777966261 0.2826151550 0.4986835420 796 31.8000000000 0.8767710328 0.7297358096 2.8224787712 0.0281474467 0.1092590000 10334115 955859216 1787064320 -1.2805944681 0.2807936668 0.4971444607 797 31.8400000000 0.8780754209 0.7299219321 2.8224787712 0.0281458922 0.0844690000 10335369 955859216 1786060800 -1.2830668688 0.2791694701 0.4962216914 798 31.8800000000 0.8788409233 0.7301085474 2.8224787712 0.0281471105 0.0868940000 10336623 955859216 1784668160 -1.2853741646 0.2769856751 0.4949169159 799 31.9200000000 0.8797128201 0.7302957868 2.8224787712 0.0281463705 0.1055270000 10337877 955859216 1782923264 -1.2877016068 0.2746219337 0.4939644337 800 31.9600000000 0.8807382584 0.7304838398 2.8224787712 0.0281441888 0.1080600000 10339131 955859216 1784549376 -1.2900373936 0.2722153962 0.4933763742 801 32.0000000000 0.8824889064 0.7306736090 2.8224787712 0.0281419287 0.0873030000 10340385 955859216 1786040320 -1.2929887772 0.2700435519 0.4935678244 802 32.0400000000 0.8837408423 0.7308644659 2.8224787712 0.0281307891 0.0853330000 10341639 955859216 1787691008 -1.2960951328 0.2678170502 0.4947274029 803 32.0800000000 0.8862347007 0.7310579531 2.8224787712 0.0281203469 0.0849910000 10342893 955859216 1786572800 -1.2987838984 0.2679190040 0.4953252673 804 32.1199999990 0.8883488178 0.7312535885 2.8224787712 0.0281137458 0.0882040000 10344147 955859216 1785167872 -1.3002758026 0.2670755982 0.4936259091 805 32.1600000000 0.8901469111 0.7314509715 2.8224787712 0.0281046776 0.0857380000 10345401 955859216 1783132160 -1.3027697802 0.2658245862 0.4946700335 806 32.2000000000 0.8917311430 0.7316498303 2.8224787712 0.0280995255 0.0876340000 10346655 955859216 1782755328 -1.3047826290 0.2639547586 0.4945357144 807 32.2400000000 0.8931578994 0.7318499642 2.8224787712 0.0280948592 0.0846150000 10347909 955859216 1781882880 -1.3070055246 0.2613594830 0.4964443445 808 32.2800000000 0.8950728774 0.7320519727 2.8224787712 0.0280881480 0.0859580000 10349163 955859216 1779945472 -1.3096330166 0.2590212822 0.4974107742 809 32.3200000000 0.8968425393 0.7322556694 2.8224787712 0.0280786273 0.0867720000 10350417 955859216 1779195904 -1.3124259710 0.2557796836 0.5007395148 810 32.3600000000 0.8988078237 0.7324612893 2.8224787712 0.0280789494 0.0900940000 10351671 955859216 1777942528 -1.3140742779 0.2538816333 0.5002690554 811 32.4000000000 0.9003363848 0.7326682870 2.8224787712 0.0280660195 0.0859290000 10352925 955859216 1776799744 -1.3171457052 0.2495071143 0.5030089617 812 32.4399999990 0.9022760987 0.7328771636 2.8224787712 0.0280541064 0.0879230000 10354179 955859216 1775656960 -1.3197728395 0.2456789613 0.5047150254 813 32.4800000000 0.9054148197 0.7330893870 2.8224787712 0.0280434539 0.1099910000 10355433 955859216 1774514176 -1.3227785826 0.2429761142 0.5063664913 814 32.5200000000 0.9080364704 0.7333043097 2.8224787712 0.0280331123 0.1267160000 10356687 955859216 1776025600 -1.3258105516 0.2401752323 0.5082203746 815 32.5600000000 0.9105519056 0.7335217914 2.8224787712 0.0280218481 0.1108190000 10357941 955859216 1777913856 -1.3290632963 0.2368194759 0.5103322268 816 32.6000000000 0.9135881066 0.7337424609 2.8224787712 0.0280136444 0.1117190000 10359195 955859216 1779564544 -1.3324651718 0.2326347232 0.5131654143 817 32.6400000000 0.9163613319 0.7339659846 2.8224787712 0.0280036267 0.0843500000 10360449 955859216 1781215232 -1.3359340429 0.2284298986 0.5154358745 818 32.6800000000 0.9199112058 0.7341933015 2.8224787712 0.0279929351 0.0874630000 10361703 955859216 1782992896 -1.3396317959 0.2248200178 0.5173782110 819 32.7200000000 0.9244806767 0.7344256427 2.8224787712 0.0279833139 0.1083510000 10362957 955859216 1784643584 -1.3436763287 0.2229413390 0.5191079974 820 32.7599999990 0.9285541177 0.7346623847 2.8224787712 0.0279742144 0.1110110000 10364211 955859216 1786294272 -1.3477518559 0.2212468535 0.5210507512 821 32.7999999990 0.9342253804 0.7349054578 2.8224787712 0.0279709261 0.1274730000 10365465 955859216 1788071936 -1.3523528576 0.2207694799 0.5238411427 822 32.8400000000 0.9383304119 0.7351529334 2.8224787712 0.0279769515 0.0858450000 10366719 955859216 1786957824 -1.3566015959 0.2205653191 0.5269723535 823 32.8800000000 0.9417354465 0.7354039449 2.8224787712 0.0280039166 0.0871810000 10367973 955859216 1784782848 -1.3597865105 0.2243417799 0.5283657312 824 32.9200000000 0.9479098320 0.7356618404 2.8224787712 0.0280011528 0.0839300000 10369227 955859216 1782755328 -1.3655515909 0.2236861289 0.5310949683 825 32.9600000000 0.9536964297 0.7359261248 2.8224787712 0.0279991746 0.0864830000 10370481 955859216 1781866496 -1.3709607124 0.2229428887 0.5338820219 826 33.0000000000 0.9599390626 0.7361973269 2.8224787712 0.0279933250 0.0852900000 10371735 955859216 1779818496 -1.3767088652 0.2226857692 0.5363086462 827 33.0400000000 0.9654734135 0.7364745652 2.8224787712 0.0279906105 0.0886410000 10372989 955859216 1778688000 -1.3821659088 0.2209348083 0.5391681194 828 33.0800000000 0.9708142877 0.7367575842 2.8224787712 0.0280011665 0.0881060000 10374243 955859216 1777561600 -1.3875410557 0.2179545909 0.5427531600 829 33.1199999990 0.9768272638 0.7370471737 2.8224787712 0.0280247167 0.0889050000 10375497 955859216 1776418816 -1.3932840824 0.2161831111 0.5452334881 830 33.1600000000 0.9824264646 0.7373428114 2.8224787712 0.0280466370 0.0870810000 10376751 955859216 1775276032 -1.3988628387 0.2138938755 0.5482731462 831 33.2000000000 0.9887819886 0.7376453856 2.8224787712 0.0280715803 0.0885970000 10378005 955859216 1774133248 -1.4049607515 0.2106291205 0.5528733730 832 33.2400000000 0.9948474765 0.7379545227 2.8224787712 0.0280922283 0.0872790000 10379259 955859216 1773101056 -1.4110845327 0.2078199983 0.5563275814 833 33.2800000000 1.0015304089 0.7382709404 2.8224787712 0.0280954029 0.0882280000 10380513 955859216 1771974656 -1.4179878235 0.2046086341 0.5600135922 834 33.3200000000 1.0075266361 0.7385937889 2.8224787712 0.0280980066 0.1069030000 10381767 955859216 1770831872 -1.4241882563 0.2010471970 0.5636438727 835 33.3600000000 1.0134373903 0.7389229429 2.8224787712 0.0281134348 0.1105560000 10383021 955859216 1769570304 -1.4300978184 0.2000499666 0.5654853582 836 33.4000000000 1.0198861361 0.7392590233 2.8224787712 0.0281223483 0.0874640000 10384275 955859216 1768550400 -1.4367718697 0.1966677457 0.5693876147 837 33.4399999990 1.0260959864 0.7396017198 2.8224787712 0.0281444987 0.0896990000 10385529 955859216 1767514112 -1.4427342415 0.1960709989 0.5711680651 838 33.4800000000 1.0314975977 0.7399500442 2.8224787712 0.0281633983 0.1154690000 10386783 955859216 1766498304 -1.4485816956 0.1918794960 0.5757972002 839 33.5200000000 1.0380232334 0.7403053162 2.8224787712 0.0282004523 0.0974660000 10388037 955859216 1765482496 -1.4544130564 0.1913106292 0.5780291557 840 33.5600000000 1.0422354937 0.7406647569 2.8224787712 0.0282163150 0.0903720000 10389291 955859216 1764982784 -1.4594602585 0.1891178489 0.5788475275 841 33.6000000000 1.0475019217 0.7410296049 2.8224787712 0.0282168486 0.0867600000 10390545 955859216 1764990976 -1.4649168253 0.1877671480 0.5804372430 842 33.6400000000 1.0521498919 0.7413991064 2.8224787712 0.0282075268 0.1044380000 10391799 955859216 1764990976 -1.4702260494 0.1856187582 0.5828116536 843 33.6800000000 1.0572975874 0.7417738377 2.8224787712 0.0282069089 0.1282970000 10393053 955859216 1764990976 -1.4752964973 0.1836799085 0.5844096541 844 33.7200000000 1.0613334179 0.7421524628 2.8224787712 0.0282054922 0.1069920000 10394307 955859216 1764990976 -1.4801373482 0.1793202460 0.5881958604 845 33.7599999990 1.0664767027 0.7425362785 2.8224787712 0.0282191271 0.1064680000 10395561 955859216 1764974592 -1.4847935438 0.1777791679 0.5906438828 846 33.7999999990 1.0707627535 0.7429242530 2.8224787712 0.0282264068 0.0924280000 10396815 955859216 1764974592 -1.4893690348 0.1761169732 0.5922250152 847 33.8400000000 1.0732519627 0.7433142503 2.8224787712 0.0282177641 0.0893900000 10398069 955859216 1764974592 -1.4930735826 0.1716727316 0.5956338048 848 33.8800000000 1.0772634745 0.7437080584 2.8224787712 0.0282120197 0.0873560000 10399323 955859216 1764990976 -1.4970823526 0.1693925261 0.5967836380 849 33.9200000000 1.0790269375 0.7441030158 2.8224787712 0.0281968655 0.1001100000 10400577 955859216 1764990976 -1.5007058382 0.1638485342 0.6017277837 850 33.9600000000 1.0817853212 0.7445002891 2.8224787712 0.0281816880 0.1138120000 10401831 955859216 1764986880 -1.5046499968 0.1590775847 0.6054030061 851 34.0000000000 1.0853499174 0.7449008175 2.8224787712 0.0281674486 0.0868830000 10403085 955859216 1764990976 -1.5088384151 0.1557033807 0.6077119708 852 34.0400000000 1.0889415741 0.7453046212 2.8224787712 0.0281548249 0.1057710000 10404339 955859216 1764990976 -1.5124044418 0.1515798867 0.6109728217 853 34.0800000000 1.0906955004 0.7457095343 2.8224787712 0.0281450100 0.1103710000 10405593 955859216 1765007360 -1.5155934095 0.1473622620 0.6144076586 854 34.1199999990 1.0954823494 0.7461191043 2.8224787712 0.0281614852 0.1045880000 10406847 955859216 1764974592 -1.5184640884 0.1498813927 0.6116509438 855 34.1600000000 1.0974493027 0.7465300169 2.8224787712 0.0281486640 0.1063340000 10408101 955859216 1764974592 -1.5213985443 0.1467983127 0.6167933941 856 34.2000000000 1.0986492634 0.7469413711 2.8224787712 0.0281351841 0.1301300000 10409355 955859216 1764974592 -1.5240058899 0.1442044824 0.6209096313 857 34.2400000000 1.1009846926 0.7473544905 2.8224787712 0.0281199413 0.0880240000 10410609 955859216 1765851136 -1.5270215273 0.1429908723 0.6223493814 858 34.2800000000 1.1034287214 0.7477694954 2.8224787712 0.0281043081 0.0853440000 10411863 955859216 1764974592 -1.5296981335 0.1414954066 0.6222388148 859 34.3200000000 1.1052988768 0.7481857112 2.8224787712 0.0280892369 0.1260150000 10413117 955859216 1764749312 -1.5315247774 0.1369710714 0.6239861846 860 34.3600000000 1.1057987213 0.7486015403 2.8224787712 0.0280746077 0.1482760000 10414371 955859216 1764732928 -1.5332975388 0.1316403151 0.6264943480 861 34.4000000000 1.1080617905 0.7490190319 2.8224787712 0.0280614044 0.0888510000 10415625 955859216 1764732928 -1.5359714031 0.1274527013 0.6286464334 862 34.4400000000 1.1097263098 0.7494374858 2.8224787712 0.0280469874 0.0876970000 10416879 955859216 1764835328 -1.5380290747 0.1232403815 0.6306284070 863 34.4800000000 1.1098477840 0.7498551107 2.8224787712 0.0280339128 0.1264280000 10418133 955859216 1764847616 -1.5392016172 0.1177593917 0.6334742904 864 34.5200000000 1.1109042168 0.7502729916 2.8224787712 0.0280214524 0.1310880000 10419387 955859216 1766486016 -1.5409274101 0.1135631204 0.6365943551 865 34.5600000000 1.1116939783 0.7506908194 2.8224787712 0.0280070554 0.0872530000 10420641 955859216 1768517632 -1.5428349972 0.1114726514 0.6384844780 866 34.6000000000 1.1122872829 0.7511083673 2.8224787712 0.0279913745 0.1051740000 10421895 955859216 1770168320 -1.5443499088 0.1097184047 0.6388453841 867 34.6400000000 1.1145626307 0.7515275763 2.8224787712 0.0279759627 0.1304750000 10423149 955859216 1771945984 -1.5460247993 0.1078016311 0.6389857531 868 34.6800000000 1.1149519682 0.7519462680 2.8224787712 0.0279626498 0.0896940000 10424403 955859216 1773596672 -1.5470200777 0.1048839763 0.6394961476 869 34.7200000000 1.1157563925 0.7523649218 2.8224787712 0.0279492006 0.0873500000 10425657 955859216 1775374336 -1.5478763580 0.1018603072 0.6415390372 870 34.7600000000 1.1149458885 0.7527816815 2.8224787712 0.0279350515 0.0883560000 10426911 955859216 1777025024 -1.5486053228 0.0988329053 0.6433066726 871 34.8000000000 1.1149941683 0.7531975397 2.8224787712 0.0279204020 0.1267020000 10428165 955859216 1778675712 -1.5496566296 0.0965023488 0.6441218257 872 34.8400000000 1.1150470972 0.7536125048 2.8224787712 0.0279070677 0.1299520000 10429419 955859216 1780453376 -1.5507272482 0.0936723426 0.6444554329 873 34.8800000000 1.1163964272 0.7540280649 2.8224787712 0.0278938270 0.0889140000 10430673 955859216 1782104064 -1.5523304939 0.0912766457 0.6452118754 874 34.9200000000 1.1174544096 0.7544438845 2.8224787712 0.0278811712 0.0881540000 10431927 955859216 1783754752 -1.5538095236 0.0894300565 0.6456357241 875 34.9600000000 1.1188651323 0.7548603659 2.8224787712 0.0278683262 0.1276880000 10433181 955859216 1785532416 -1.5557956696 0.0889248252 0.6450946927 876 35.0000000000 1.1205810308 0.7552778552 2.8224787712 0.0278547943 0.1476620000 10434435 955859216 1787183104 -1.5574114323 0.0887058154 0.6442691684 877 35.0400000000 1.1222661734 0.7556963140 2.8224787712 0.0278397846 0.1162790000 10435689 955859216 1784549376 -1.5591065884 0.0886644721 0.6436081529 878 35.0800000000 1.1235537529 0.7561152860 2.8224787712 0.0278240078 0.1000290000 10436943 955859216 1783402496 -1.5605530739 0.0892064646 0.6426718235 879 35.1200000000 1.1245912313 0.7565344850 2.8224787712 0.0278082352 0.1257330000 10438197 955859216 1782259712 -1.5618611574 0.0890232474 0.6423413157 880 35.1600000000 1.1262401342 0.7569546051 2.8224787712 0.0277925502 0.0808710000 10439451 955859216 1781116928 -1.5633894205 0.0895344540 0.6418613791 881 35.2000000000 1.1277614832 0.7573754983 2.8224787712 0.0277769892 0.0969780000 10440705 955859216 1779974144 -1.5649616718 0.0901978910 0.6408498883 882 35.2400000000 1.1283270121 0.7577960782 2.8224787712 0.0277612516 0.1193470000 10441959 955859216 1778720768 -1.5654504299 0.0876554623 0.6420100331 ================================================ FILE: icra2018_results/tegra/memory_kfusion_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 05:39:58 Properties: ================= frame-limit: 0 log-file: output//memory_kfusion_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 nan 0.1290230000 0.0273640000 0.0133930000 0.0001830000 0.0000180000 0.0851520000 7757746 96830484 1697603584 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378715 0.0677660000 0.0087560000 0.0133270000 0.0000960000 0.0000080000 0.0445630000 7923532 96830484 1698893824 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728951 0.1114370000 0.0350040000 0.0359590000 0.0003060000 0.0000220000 0.0398020000 7925530 96830484 1699508224 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723570 0.0889510000 0.0124550000 0.0116550000 0.0000830000 0.0001120000 0.0643000000 7927552 96830484 1700163584 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276867 0.0024566393 0.0055015511 0.0048987371 0.1546180000 0.0084910000 0.0589880000 0.0003210000 0.0002610000 0.0851300000 7929546 96830484 1700798464 3.9957129955 4.0020370483 4.0009112358 6 0.2000000000 0.0021193668 0.0024004272 0.0055015511 0.0043898062 0.0923630000 0.0091890000 0.0455030000 0.0000230000 0.0004940000 0.0362740000 7931876 96830484 1701433344 3.9965579510 4.0017552376 4.0000634193 7 0.2400000000 0.0020520808 0.0023506635 0.0055015511 0.0040162997 0.0895950000 0.0084210000 0.0364430000 0.0002790000 0.0002540000 0.0438020000 7933550 96830484 1702047744 3.9963893890 4.0014748573 4.0003581047 8 0.2800000000 0.0021309818 0.0023232032 0.0055015511 0.0037226413 0.0890490000 0.0086570000 0.0387320000 0.0000160000 0.0002300000 0.0407720000 7935224 96830484 1702830080 3.9949610233 4.0019330978 4.0002708435 9 0.3200000000 0.0021698186 0.0023061605 0.0055015511 0.0035285959 0.1105350000 0.0085400000 0.0331240000 0.0002350000 0.0001720000 0.0681450000 7937538 96830484 1703464960 3.9930253029 4.0012869835 4.0003128052 10 0.3600000000 0.0022089549 0.0022964399 0.0055015511 0.0033889458 0.0838450000 0.0086000000 0.0357560000 0.0000070000 0.0000870000 0.0377170000 7940524 96830484 1704099840 3.9929094315 4.0026316643 4.0009026527 11 0.4000000000 0.0022607681 0.0022931970 0.0055015511 0.0033576477 0.1072160000 0.0082640000 0.0524260000 0.0004320000 0.0002790000 0.0444310000 7942198 96830484 1704734720 3.9919469357 4.0017871857 4.0016007423 12 0.4400000000 0.0022675800 0.0022910623 0.0055015511 0.0034304054 0.0824060000 0.0084970000 0.0347500000 0.0000210000 0.0003400000 0.0374370000 7943872 96830484 1705369600 3.9918613434 4.0017371178 4.0008234978 13 0.4800000000 0.0022817205 0.0022903437 0.0055015511 0.0034359296 0.1203380000 0.0083640000 0.0339780000 0.0003430000 0.0002650000 0.0759900000 7945546 96830484 1706004480 3.9894282818 4.0015411377 4.0013957024 14 0.5200000000 0.0023265851 0.0022929324 0.0055015511 0.0033242156 0.1285680000 0.0090320000 0.0822620000 0.0000050000 0.0000640000 0.0357570000 7947220 96830484 1706639360 3.9894304276 4.0028085709 4.0008177757 15 0.5600000000 0.0023081175 0.0022939447 0.0055015511 0.0032120843 0.0909530000 0.0091720000 0.0410700000 0.0003650000 0.0002720000 0.0396880000 7948894 96830484 1707274240 3.9863359928 4.0038886070 4.0015878677 16 0.6000000000 0.0023983542 0.0023004703 0.0055015511 0.0031278541 0.0983120000 0.0093190000 0.0512380000 0.0000220000 0.0003620000 0.0358030000 7950568 96830484 1707909120 3.9871211052 4.0023255348 4.0005331039 17 0.6400000000 0.0024038421 0.0023065510 0.0055015511 0.0030498086 0.1225000000 0.0091160000 0.0412600000 0.0002890000 0.0002660000 0.0698720000 7953522 96830484 1708670976 3.9851036072 4.0008940697 3.9991033077 18 0.6800000000 0.0024459769 0.0023142969 0.0055015511 0.0029599863 0.0924390000 0.0092450000 0.0489270000 0.0000220000 0.0003100000 0.0334640000 7957820 96830484 1709305856 3.9835436344 4.0011606216 4.0000782013 19 0.7200000000 0.0024385911 0.0023208387 0.0055015511 0.0029191459 0.0911660000 0.0088050000 0.0400370000 0.0003430000 0.0003030000 0.0412540000 7959494 96830484 1709940736 3.9820597172 4.0014066696 3.9996430874 20 0.7600000000 0.0025582798 0.0023327107 0.0055015511 0.0029371889 0.0823980000 0.0086330000 0.0350830000 0.0000150000 0.0001860000 0.0368300000 7961168 96830484 1710546944 3.9790954590 4.0002269745 3.9993181229 21 0.8000000000 0.0026402324 0.0023473546 0.0055015511 0.0028722433 0.1218050000 0.0086700000 0.0413070000 0.0003100000 0.0003410000 0.0686920000 7962842 96830484 1711202304 3.9762647152 4.0010972023 3.9996490479 22 0.8400000000 0.0029144434 0.0023731314 0.0055015511 0.0028126042 0.0874880000 0.0090490000 0.0380860000 0.0000230000 0.0003630000 0.0379030000 7964516 96830484 1711816704 3.9707875252 4.0004653931 3.9992005825 23 0.8800000000 0.0029079607 0.0023963848 0.0055015511 0.0027479746 0.0974130000 0.0085440000 0.0441500000 0.0002790000 0.0002560000 0.0423890000 7966190 96830484 1712451584 3.9713721275 3.9995739460 3.9975578785 24 0.9200000000 0.0028096719 0.0024136051 0.0055015511 0.0026877533 0.0909160000 0.0093130000 0.0435110000 0.0000250000 0.0003040000 0.0362880000 7967864 96830484 1713233920 3.9628987312 4.0010185242 3.9969220161 25 0.9600000000 0.0027906045 0.0024286851 0.0055015511 0.0026594775 0.1221330000 0.0090700000 0.0356180000 0.0002470000 0.0001740000 0.0750610000 7969538 96830484 1713868800 3.9617063999 4.0022830963 3.9961562157 26 1.0000000000 0.0028318348 0.0024441909 0.0055015511 0.0026071390 0.0921300000 0.0094420000 0.0443250000 0.0000250000 0.0003060000 0.0361780000 7971212 96830484 1714503680 3.9554364681 4.0008044243 3.9970476627 27 1.0400000000 0.0026902761 0.0024533051 0.0055015511 0.0026328308 0.0983990000 0.0091350000 0.0437420000 0.0003470000 0.0002700000 0.0428300000 7972886 96830484 1715138560 3.9496479034 4.0000362396 3.9948539734 28 1.0800000000 0.0027714712 0.0024646682 0.0055015511 0.0027076172 0.0904280000 0.0093690000 0.0508880000 0.0000220000 0.0002840000 0.0293390000 7974560 96830484 1715773440 3.9448773861 4.0019016266 3.9945564270 29 1.1200000000 0.0027285318 0.0024737670 0.0055015511 0.0027861190 0.1297830000 0.0085480000 0.0483460000 0.0003680000 0.0002660000 0.0717360000 7976234 96830484 1716387840 3.9388296604 4.0020227432 3.9917793274 30 1.1600000000 0.0030032410 0.0024914161 0.0055015511 0.0027895884 0.0902950000 0.0085150000 0.0430860000 0.0000250000 0.0002860000 0.0378680000 7977908 96830484 1717043200 3.9293973446 4.0014457703 3.9938304424 31 1.2000000000 0.0029136736 0.0025050373 0.0055015511 0.0027657983 0.1076440000 0.0087540000 0.0498050000 0.0003100000 0.0003090000 0.0454690000 7979582 96830484 1717678080 3.9228038788 4.0022139549 3.9920375347 32 1.2400000000 0.0029506644 0.0025189631 0.0055015511 0.0027654780 0.1004550000 0.0087920000 0.0463630000 0.0000230000 0.0003470000 0.0425510000 7981256 96830484 1718312960 3.9160888195 4.0025353432 3.9897420406 33 1.2800000000 0.0029396042 0.0025317098 0.0055015511 0.0028074009 0.1493730000 0.0087070000 0.0516230000 0.0002980000 0.0002560000 0.0804890000 7985490 96830484 1718927360 3.9104783535 4.0022211075 3.9895060062 34 1.3200000000 0.0028935280 0.0025423516 0.0055015511 0.0027808310 0.0902500000 0.0094320000 0.0440640000 0.0000240000 0.0003150000 0.0358440000 7992412 96830484 1719709696 3.8820114136 4.0016813278 3.9892072678 35 1.3600000000 0.0030744108 0.0025575532 0.0055015511 0.0030478038 0.1031010000 0.0100550000 0.0466890000 0.0003140000 0.0002620000 0.0432870000 7994086 96830484 1720344576 3.8787240982 4.0025434494 3.9865615368 36 1.4000000000 0.0030465741 0.0025711372 0.0055015511 0.0035589818 0.0867580000 0.0093690000 0.0363580000 0.0000230000 0.0003370000 0.0379690000 7995760 96830484 1720979456 3.8730773926 4.0032992363 3.9847621918 37 1.4400000000 0.0030497839 0.0025840736 0.0055015511 0.0035973373 0.1408940000 0.0085890000 0.0516130000 0.0002970000 0.0003390000 0.0775170000 7997434 96830484 1721593856 3.8621592522 4.0013198853 3.9860253334 38 1.4800000000 0.0032345029 0.0026011901 0.0055015511 0.0035570682 0.0961810000 0.0088320000 0.0460200000 0.0000270000 0.0002860000 0.0383090000 7999108 96830484 1722249216 3.8505938053 4.0007581711 3.9867534637 39 1.5200000000 0.0032989846 0.0026190823 0.0055015511 0.0035142170 0.1228410000 0.0087250000 0.0628830000 0.0003200000 0.0003480000 0.0478940000 8000782 96830484 1722884096 3.8474638462 4.0001363754 3.9834077358 40 1.5600000000 0.0033597045 0.0026375978 0.0055015511 0.0034974239 0.0884500000 0.0085540000 0.0367340000 0.0000260000 0.0003110000 0.0400750000 8002456 96830484 1723498496 3.8375625610 3.9985222816 3.9840943813 41 1.6000000000 0.0033773324 0.0026556401 0.0055015511 0.0035179614 0.1225860000 0.0083620000 0.0436670000 0.0003530000 0.0002670000 0.0692650000 8004130 96830484 1724280832 3.8271625042 3.9974081516 3.9858469963 42 1.6400000000 0.0033806583 0.0026729025 0.0055015511 0.0034791059 0.0865280000 0.0082860000 0.0364150000 0.0000250000 0.0003460000 0.0387650000 8005804 96830484 1724915712 3.8137972355 3.9989020824 3.9880621433 43 1.6800000000 0.0033616489 0.0026889198 0.0055015511 0.0034582636 0.1196950000 0.0083290000 0.0561720000 0.0002930000 0.0003420000 0.0539120000 8007478 96830484 1725550592 3.8069863319 3.9993288517 3.9914345741 44 1.7200000000 0.0033652280 0.0027042905 0.0055015511 0.0034889558 0.0884750000 0.0084710000 0.0364280000 0.0000230000 0.0003300000 0.0399910000 8009152 96830484 1726185472 3.8006696701 3.9986765385 3.9893207550 45 1.7600000000 0.0033918147 0.0027195688 0.0055015511 0.0035075427 0.1191990000 0.0083380000 0.0431940000 0.0002980000 0.0002730000 0.0664270000 8010826 96830484 1726799872 3.7923023701 4.0006685257 3.9930346012 46 1.8000000000 0.0034418837 0.0027352713 0.0055015511 0.0035142630 0.0957800000 0.0087340000 0.0451860000 0.0000270000 0.0003120000 0.0381810000 8012500 96830484 1727455232 3.7863330841 4.0012736320 3.9931325912 47 1.8400000000 0.0034591854 0.0027506737 0.0055015511 0.0036200882 0.1112130000 0.0085120000 0.0425520000 0.0003890000 0.0002790000 0.0581530000 8014174 96830484 1728090112 3.7833192348 3.9994659424 3.9928328991 48 1.8800000000 0.0034216086 0.0027646515 0.0055015511 0.0036631902 0.0918810000 0.0081150000 0.0460230000 0.0000240000 0.0003430000 0.0365790000 8015848 96830484 1728851968 3.7787630558 3.9991860390 3.9939386845 49 1.9200000000 0.0036153251 0.0027820122 0.0055015511 0.0036249469 0.1186410000 0.0082330000 0.0342410000 0.0002370000 0.0001990000 0.0722350000 8017522 96830484 1729486848 3.7716283798 4.0004005432 3.9947481155 50 1.9600000000 0.0035999152 0.0027983703 0.0055015511 0.0036102982 0.0911660000 0.0087190000 0.0440140000 0.0000270000 0.0003460000 0.0368670000 8019196 96830484 1730121728 3.7573053837 4.0000443459 3.9996886253 51 2.0000000000 0.0035136426 0.0028123952 0.0055015511 0.0035844400 0.0998480000 0.0088560000 0.0413240000 0.0003550000 0.0002690000 0.0458140000 8020870 96830484 1730756608 3.7588639259 3.9998888969 3.9966924191 52 2.0400000000 0.0035622681 0.0028268159 0.0055015511 0.0035492689 0.1061320000 0.0081160000 0.0504730000 0.0000250000 0.0003570000 0.0438940000 8022544 96830484 1731391488 3.7549383640 4.0002870560 3.9959812164 53 2.0800000000 0.0034568321 0.0028387030 0.0055015511 0.0035930304 0.1633980000 0.0083500000 0.0633590000 0.0001160000 0.0000600000 0.0881630000 8024218 96830484 1732005888 3.7529284954 3.9978299141 3.9927301407 54 2.1200000000 0.0036012181 0.0028528236 0.0055015511 0.0036679579 0.0910070000 0.0088270000 0.0439700000 0.0000270000 0.0003850000 0.0363850000 8025892 96830484 1732661248 3.7399032116 3.9963810444 3.9985296726 55 2.1600000000 0.0035210552 0.0028649733 0.0055015511 0.0037628136 0.1001630000 0.0088190000 0.0437390000 0.0003890000 0.0002720000 0.0431540000 8027566 96830484 1733275648 3.7375395298 3.9971230030 3.9982161522 56 2.2000000000 0.0036108077 0.0028782917 0.0055015511 0.0037701873 0.0919140000 0.0087710000 0.0436550000 0.0000290000 0.0003870000 0.0361610000 8029240 96830484 1734057984 3.7177057266 3.9974868298 4.0073981285 57 2.2400000000 0.0037530900 0.0028936391 0.0055015511 0.0037490218 0.1179360000 0.0082660000 0.0408430000 0.0004790000 0.0002720000 0.0672530000 8030914 96830484 1734692864 3.7129147053 3.9949142933 4.0079951286 58 2.2800000000 0.0036983066 0.0029075127 0.0055015511 0.0037578113 0.0895340000 0.0087090000 0.0377790000 0.0000270000 0.0002990000 0.0390320000 8032588 96830484 1735327744 3.7035658360 3.9941787720 4.0107650757 59 2.3200000000 0.0038099838 0.0029228088 0.0055015511 0.0038958326 0.1295010000 0.0080010000 0.0656930000 0.0003980000 0.0003050000 0.0514450000 8034262 96830484 1735962624 3.6894240379 3.9966025352 4.0165247917 60 2.3600000000 0.0037962198 0.0029373656 0.0055015511 0.0040111455 0.0875900000 0.0080160000 0.0377150000 0.0000270000 0.0003160000 0.0377960000 8035936 96830484 1736597504 3.6862916946 3.9948871136 4.0145845413 61 2.4000000000 0.0038407429 0.0029521751 0.0055015511 0.0041276544 0.1245410000 0.0084500000 0.0414440000 0.0003610000 0.0002810000 0.0695780000 8037610 96830484 1737232384 3.6795248985 3.9934597015 4.0143733025 62 2.4400000000 0.0038516498 0.0029666828 0.0055015511 0.0042929660 0.0906780000 0.0080940000 0.0415220000 0.0000240000 0.0005050000 0.0389390000 8039284 96830484 1737846784 3.6558568478 3.9938807487 4.0246858597 63 2.4800000000 0.0038877756 0.0029813033 0.0055015511 0.0044370411 0.1032220000 0.0078580000 0.0445100000 0.0003510000 0.0002640000 0.0464100000 8040958 96830484 1738629120 3.6471881866 3.9928202629 4.0258584023 64 2.5200000000 0.0038804887 0.0029953530 0.0055015511 0.0047966692 0.1073940000 0.0079580000 0.0485040000 0.0000230000 0.0002920000 0.0461000000 8042632 96830484 1739264000 3.6346523762 3.9939303398 4.0304179192 65 2.5600000000 0.0038905402 0.0030091252 0.0055015511 0.0051044200 0.1310550000 0.0078410000 0.0454870000 0.0003040000 0.0002730000 0.0762220000 8049426 96830484 1739898880 3.6208126545 3.9938166142 4.0341472626 66 2.6000000000 0.0040779728 0.0030253198 0.0055015511 0.0051955713 0.0876530000 0.0081220000 0.0366050000 0.0000170000 0.0001970000 0.0386660000 8061596 96830484 1740533760 3.6103200912 3.9951486588 4.0361342430 67 2.6400000000 0.0040969332 0.0030413140 0.0055015511 0.0052466839 0.1105450000 0.0082940000 0.0493120000 0.0005200000 0.0002810000 0.0512190000 8063270 96830484 1741168640 3.6001145840 3.9975600243 4.0384063721 68 2.6800000000 0.0043201996 0.0030601212 0.0055015511 0.0052299538 0.0962100000 0.0076100000 0.0444090000 0.0000270000 0.0003350000 0.0397960000 8064944 96830484 1741783040 3.5891766548 3.9974367619 4.0377378464 69 2.7200000000 0.0043213847 0.0030784004 0.0055015511 0.0051933888 0.1614540000 0.0077130000 0.0681930000 0.0003040000 0.0003830000 0.0806410000 8066618 96830484 1742417920 3.5796022415 3.9977006912 4.0422320366 70 2.7600000000 0.0044693355 0.0030982709 0.0055015511 0.0051654802 0.0918010000 0.0081780000 0.0431050000 0.0000260000 0.0010870000 0.0372320000 8068292 96830484 1743179776 3.5707454681 3.9996337891 4.0418829918 71 2.8000000000 0.0045017679 0.0031180384 0.0055015511 0.0052159198 0.1036800000 0.0077560000 0.0441930000 0.0002990000 0.0003900000 0.0466070000 8069966 96830484 1743835136 3.5635986328 4.0002326965 4.0388050079 72 2.8400000000 0.0048455861 0.0031420322 0.0055015511 0.0058973271 0.1115300000 0.0075330000 0.0544630000 0.0000250000 0.0006950000 0.0478680000 8071640 96830484 1744470016 3.5478820801 4.0054097176 4.0417695045 73 2.8800000000 0.0048695048 0.0031656962 0.0055015511 0.0059700889 0.1238080000 0.0075590000 0.0459840000 0.0004120000 0.0002780000 0.0686230000 8073314 96830484 1745104896 3.5378980637 4.0068230629 4.0434441566 74 2.9200000000 0.0049511874 0.0031898244 0.0055015511 0.0060608059 0.0897010000 0.0094010000 0.0388490000 0.0000190000 0.0002080000 0.0387950000 8074988 96830484 1745739776 3.5358490944 4.0085172653 4.0402970314 75 2.9600000000 0.0050919703 0.0032151864 0.0055015511 0.0061155850 0.1103970000 0.0076090000 0.0495400000 0.0003870000 0.0002720000 0.0516170000 8076662 96830484 1746374656 3.5346438885 4.0121569633 4.0375247002 76 3.0000000000 0.0050736363 0.0032396397 0.0055015511 0.0061499715 0.0915470000 0.0078280000 0.0431970000 0.0000240000 0.0003720000 0.0391060000 8078336 96830484 1746989056 3.5366401672 4.0152049065 4.0294260979 77 3.0400000000 0.0047360552 0.0032590736 0.0055015511 0.0061733563 0.1199370000 0.0075000000 0.0333550000 0.0002230000 0.0001810000 0.0741480000 8080010 96830484 1747623936 3.5357468128 4.0155305862 4.0226578712 78 3.0800000000 0.0043565077 0.0032731433 0.0055015511 0.0061424763 0.0915160000 0.0080190000 0.0454120000 0.0000280000 0.0003880000 0.0366800000 8081684 96830484 1748385792 3.5369172096 4.0168828964 4.0154690742 79 3.1200000000 0.0042994311 0.0032861343 0.0055015511 0.0061043897 0.1032840000 0.0080520000 0.0436100000 0.0009930000 0.0006560000 0.0441260000 8083358 96830484 1749041152 3.5298633575 4.0200643539 4.0133028030 80 3.1600000000 0.0040675509 0.0032959020 0.0055015511 0.0060687379 0.1032250000 0.0082580000 0.0517820000 0.0000230000 0.0003000000 0.0379230000 8085032 96830484 1749676032 3.5259122849 4.0230669975 4.0096015930 81 3.2000000000 0.0041678529 0.0033066668 0.0055015511 0.0060408441 0.1651210000 0.0080020000 0.0834940000 0.0003340000 0.0002760000 0.0719850000 8086706 96830484 1750310912 3.5140886307 4.0221219063 4.0126109123 82 3.2400000000 0.0043998412 0.0033199982 0.0055015511 0.0060490392 0.0964310000 0.0075400000 0.0516820000 0.0000260000 0.0003790000 0.0356690000 8088380 96830484 1750945792 3.5058853626 4.0222730637 4.0121889114 83 3.2800000000 0.0043142238 0.0033319768 0.0055015511 0.0060868578 0.0896880000 0.0075940000 0.0360980000 0.0003040000 0.0001830000 0.0444050000 8090054 96830484 1751580672 3.4979877472 4.0243492126 4.0090532303 84 3.3200000000 0.0043057348 0.0033435692 0.0055015511 0.0060778952 0.1010400000 0.0072890000 0.0439080000 0.0000270000 0.0003400000 0.0439970000 8091728 96830484 1752195072 3.4852621555 4.0233669281 4.0093283653 85 3.3600000000 0.0045070788 0.0033572575 0.0055015511 0.0060685870 0.1654920000 0.0075590000 0.0615600000 0.0003100000 0.0008020000 0.0903250000 8093402 96830484 1752977408 3.4720706940 4.0242362022 4.0097379684 86 3.4000000000 0.0044985469 0.0033705283 0.0055015511 0.0061072585 0.1004140000 0.0078040000 0.0484970000 0.0000260000 0.0003890000 0.0383890000 8095076 96830484 1753575424 3.4570465088 4.0251402855 4.0137996674 87 3.4400000000 0.0041875807 0.0033799197 0.0055015511 0.0062326132 0.1074150000 0.0076650000 0.0453380000 0.0003110000 0.0004960000 0.0485530000 8096750 96830484 1754230784 3.4469785690 4.0238556862 4.0134696960 88 3.4800000000 0.0038636187 0.0033854163 0.0055015511 0.0063830350 0.1117710000 0.0075100000 0.0484310000 0.0000270000 0.0003200000 0.0543040000 8098424 96830484 1754865664 3.4335203171 4.0241293907 4.0137071609 89 3.5200000000 0.0040280754 0.0033926372 0.0055015511 0.0065297436 0.1454630000 0.0073580000 0.0539430000 0.0003100000 0.0002750000 0.0782500000 8100098 96830484 1755754496 3.4245235920 4.0243425369 4.0138111115 90 3.5600000000 0.0044007315 0.0034038383 0.0055015511 0.0066381226 0.0908100000 0.0084320000 0.0390080000 0.0000260000 0.0003110000 0.0418500000 8101772 96830484 1757384704 3.4175665379 4.0225892067 4.0125846863 91 3.6000000000 0.0041434229 0.0034119656 0.0055015511 0.0066784884 0.1065370000 0.0076400000 0.0397670000 0.0001990000 0.0001770000 0.0531220000 8103446 96830484 1759715328 3.4026882648 4.0212779045 4.0156178474 92 3.6400000000 0.0042125247 0.0034206673 0.0055015511 0.0066905032 0.1104600000 0.0075600000 0.0462730000 0.0000250000 0.0003020000 0.0532240000 8105120 96830484 1761320960 3.3876051903 4.0233893394 4.0208153725 93 3.6800000000 0.0041170446 0.0034281552 0.0055015511 0.0066699189 0.1369980000 0.0075610000 0.0419930000 0.0005310000 0.0002780000 0.0854900000 8106794 96830484 1762975744 3.3826262951 4.0225024223 4.0174160004 94 3.7200000000 0.0040446194 0.0034347134 0.0055015511 0.0066420503 0.1023660000 0.0077850000 0.0479490000 0.0000260000 0.0005120000 0.0428090000 8108468 96830484 1764622336 3.3753530979 4.0200648308 4.0169715881 95 3.7600000000 0.0041557457 0.0034423032 0.0055015511 0.0066274985 0.1129930000 0.0075260000 0.0459200000 0.0003920000 0.0002750000 0.0577040000 8110142 96830484 1766526976 3.3624577522 4.0213975906 4.0235295296 96 3.8000000000 0.0040876796 0.0034490258 0.0055015511 0.0065997821 0.1058550000 0.0076890000 0.0466490000 0.0000270000 0.0002860000 0.0453900000 8111816 96830484 1768054784 3.3521332741 4.0208735466 4.0231089592 97 3.8400000000 0.0042544981 0.0034573297 0.0055015511 0.0065660225 0.1491280000 0.0075700000 0.0529040000 0.0003240000 0.0002670000 0.0868640000 8113490 96830484 1769828352 3.3468501568 4.0181550980 4.0250072479 98 3.8800000000 0.0042286213 0.0034652000 0.0055015511 0.0065406206 0.0918080000 0.0078580000 0.0408700000 0.0000260000 0.0002870000 0.0415060000 8115164 96830484 1771606016 3.3322317600 4.0175247192 4.0290803909 99 3.9200000000 0.0043106712 0.0034737401 0.0055015511 0.0065134598 0.1099900000 0.0096470000 0.0438590000 0.0003440000 0.0002700000 0.0545940000 8116838 96830484 1770225664 3.3268041611 4.0189332962 4.0322213173 100 3.9600000000 0.0044734539 0.0034837372 0.0055015511 0.0064808071 0.0911040000 0.0074720000 0.0398540000 0.0000290000 0.0002930000 0.0421750000 8118512 96830484 1772003328 3.3189098835 4.0183291435 4.0362606049 101 4.0000000000 0.0041882480 0.0034907126 0.0055015511 0.0064511271 0.1431910000 0.0095550000 0.0504720000 0.0002920000 0.0003470000 0.0770130000 8120186 96830484 1770733568 3.3098516464 4.0166153908 4.0422801971 102 4.0400000000 0.0041925670 0.0034975935 0.0055015511 0.0064307157 0.0916610000 0.0097110000 0.0391150000 0.0000170000 0.0002030000 0.0414100000 8121860 96830484 1769574400 3.3061838150 4.0152354240 4.0438990593 103 4.0800000000 0.0041389293 0.0035038201 0.0055015511 0.0064001388 0.1242870000 0.0084060000 0.0462910000 0.0002970000 0.0003400000 0.0627810000 8123534 96830484 1767686144 3.2954325676 4.0147409439 4.0505323410 104 4.1200000000 0.0043298230 0.0035117624 0.0055015511 0.0063751894 0.1101470000 0.0075980000 0.0444160000 0.0000260000 0.0002910000 0.0549450000 8125208 96830484 1769357312 3.2831025124 4.0128850937 4.0633416176 105 4.1600000000 0.0042557004 0.0035188475 0.0055015511 0.0063732583 0.1459930000 0.0077140000 0.0408780000 0.0003220000 0.0002530000 0.0905490000 8126882 96830484 1770868736 3.2800943851 4.0127501488 4.0651073456 106 4.2000000000 0.0043538716 0.0035267251 0.0055015511 0.0063828762 0.1023370000 0.0100530000 0.0412710000 0.0000270000 0.0003430000 0.0446200000 8128556 96830484 1769627648 3.2739760876 4.0132474899 4.0701584816 107 4.2400000000 0.0044673840 0.0035355163 0.0055015511 0.0063663586 0.1297890000 0.0075350000 0.0481540000 0.0003360000 0.0003490000 0.0672350000 8130230 96830484 1771233280 3.2737646103 4.0100221634 4.0664815903 108 4.2800000000 0.0041306498 0.0035410268 0.0055015511 0.0063376871 0.1101410000 0.0096020000 0.0433290000 0.0000260000 0.0002920000 0.0511660000 8131904 96830484 1769971712 3.2635633945 4.0090322495 4.0749359131 109 4.3200000000 0.0042447792 0.0035474833 0.0055015511 0.0063186525 0.1487700000 0.0082840000 0.0485470000 0.0002910000 0.0002990000 0.0900120000 8133578 96830484 1771732992 3.2618064880 4.0092082024 4.0760221481 110 4.3600000000 0.0047176909 0.0035581215 0.0055015511 0.0063305631 0.0920200000 0.0100550000 0.0382420000 0.0000070000 0.0000850000 0.0422520000 8135252 96830484 1770479616 3.2547669411 4.0085148811 4.0843915939 111 4.4000000000 0.0043540760 0.0035652923 0.0055015511 0.0063283967 0.1031830000 0.0081440000 0.0369670000 0.0002030000 0.0002050000 0.0508080000 8136926 96830484 1768828928 3.2477731705 4.0073037148 4.0910882950 112 4.4400000000 0.0043636537 0.0035724205 0.0055015511 0.0063294602 0.1018160000 0.0078970000 0.0411840000 0.0000240000 0.0005200000 0.0455380000 8138600 96830484 1770594304 3.2398145199 4.0079445839 4.0989527702 113 4.4800000000 0.0044202693 0.0035799236 0.0055015511 0.0063361286 0.1427180000 0.0093820000 0.0434430000 0.0003230000 0.0003450000 0.0878780000 8140274 96830484 1769353216 3.2356603146 4.0078201294 4.1031579971 114 4.5200000000 0.0044310060 0.0035873892 0.0055015511 0.0063828275 0.1080980000 0.0085290000 0.0462450000 0.0000250000 0.0003340000 0.0461020000 8141948 96830484 1771098112 3.2248780727 4.0076932907 4.1154446602 115 4.5600000000 0.0044104755 0.0035945465 0.0055015511 0.0064050172 0.1334470000 0.0094410000 0.0640350000 0.0003220000 0.0002760000 0.0579840000 8143622 96830484 1769844736 3.2241613865 4.0075888634 4.1172804832 116 4.6000000000 0.0044571646 0.0036019829 0.0055015511 0.0064460610 0.1084100000 0.0075300000 0.0428520000 0.0000270000 0.0003390000 0.0539990000 8145296 96830484 1771503616 3.2138011456 4.0102252960 4.1293311119 117 4.6400000000 0.0045295958 0.0036099112 0.0055015511 0.0064535611 0.1426600000 0.0096400000 0.0342460000 0.0000810000 0.0000790000 0.0921010000 8146970 96830484 1770336256 3.2062163353 4.0131697655 4.1397809982 118 4.6800000000 0.0044899643 0.0036173693 0.0055015511 0.0064263592 0.1025690000 0.0096210000 0.0406120000 0.0000250000 0.0002940000 0.0455160000 8148644 96830484 1769103360 3.2005317211 4.0115976334 4.1439776421 119 4.7200000000 0.0043839146 0.0036238108 0.0055015511 0.0064042992 0.1098160000 0.0081720000 0.0387590000 0.0002860000 0.0003320000 0.0557200000 8150318 96830484 1770618880 3.1941034794 4.0111160278 4.1509785652 120 4.7600000000 0.0043759644 0.0036300788 0.0055015511 0.0063796073 0.1715210000 0.0092250000 0.1046190000 0.0000250000 0.0002890000 0.0559700000 8151992 96830484 1769500672 3.1872189045 4.0124731064 4.1592054367 121 4.8000000000 0.0042338832 0.0036350689 0.0055015511 0.0063623421 0.1673610000 0.0077020000 0.0543180000 0.0003020000 0.0002710000 0.0976300000 8153666 96830484 1771114496 3.1777808666 4.0119271278 4.1769375801 122 4.8400000000 0.0043840194 0.0036412078 0.0055015511 0.0063399134 0.0925940000 0.0099820000 0.0361080000 0.0000080000 0.0000800000 0.0449710000 8155340 96830484 1769992192 3.1763107777 4.0134363174 4.1777849197 123 4.8800000000 0.0044023991 0.0036473964 0.0055015511 0.0063177710 0.1256270000 0.0078760000 0.0492540000 0.0003050000 0.0003500000 0.0632740000 8157014 96830484 1768701952 3.1706545353 4.0176043510 4.1841621399 124 4.9200000000 0.0045968168 0.0036550530 0.0055015511 0.0062977817 0.1289800000 0.0077500000 0.0531210000 0.0000240000 0.0003040000 0.0587770000 8158688 96830484 1770319872 3.1615383625 4.0185518265 4.2000694275 125 4.9600000000 0.0045725657 0.0036623931 0.0055015511 0.0062876576 0.1692290000 0.0075210000 0.0490290000 0.0003790000 0.0002770000 0.1050670000 8160362 96830484 1771847680 3.1571557522 4.0183286667 4.2050676346 126 5.0000000000 0.0043846602 0.0036681254 0.0055015511 0.0062683087 0.1097400000 0.0102850000 0.0457110000 0.0000260000 0.0003800000 0.0463420000 8162036 96830484 1770717184 3.1521465778 4.0194344521 4.2123532295 127 5.0400000000 0.0045854216 0.0036753482 0.0055015511 0.0062440527 0.1098390000 0.0100140000 0.0377750000 0.0000820000 0.0000740000 0.0580880000 8163710 96830484 1769594880 3.1428544521 4.0204439163 4.2293477058 128 5.0800000000 0.0045399363 0.0036821028 0.0055015511 0.0062215252 0.1085140000 0.0074520000 0.0408270000 0.0000190000 0.0002040000 0.0528740000 8165384 96830484 1771335680 3.1373357773 4.0202531815 4.2351298332 129 5.1200000000 0.0045370036 0.0036887299 0.0055015511 0.0061985820 0.1699070000 0.0094780000 0.0491870000 0.0003090000 0.0003470000 0.1040810000 8177298 96830484 1769955328 3.1333868504 4.0206036568 4.2417931557 130 5.1600000000 0.0044152057 0.0036943182 0.0055015511 0.0061938144 0.1089140000 0.0079480000 0.0459900000 0.0000280000 0.0003110000 0.0471220000 8199964 96830484 1771593728 3.1246411800 4.0203986168 4.2597942352 131 5.2000000000 0.0045606871 0.0037009317 0.0055015511 0.0062248603 0.1019970000 0.0101290000 0.0398310000 0.0003040000 0.0002820000 0.0498300000 8201638 96830484 1770463232 3.1212036610 4.0209698677 4.2639036179 132 5.2400000000 0.0045011132 0.0037069937 0.0055015511 0.0062368719 0.1126180000 0.0116160000 0.0421660000 0.0000260000 0.0002960000 0.0504080000 8203312 96830484 1769304064 3.1207258701 4.0206942558 4.2615728378 133 5.2800000000 0.0044290908 0.0037124230 0.0055015511 0.0062367300 0.1711330000 0.0074140000 0.0678510000 0.0003220000 0.0002750000 0.0935990000 8204986 96830484 1770954752 3.1103262901 4.0208992958 4.2806978226 134 5.3200000000 0.0049535483 0.0037216851 0.0055015511 0.0062692380 0.1061710000 0.0094540000 0.0378350000 0.0000080000 0.0000820000 0.0510120000 8206660 96830484 1769738240 3.1018130779 4.0237188339 4.2973408699 135 5.3600000000 0.0050981650 0.0037318812 0.0055015511 0.0062899256 0.1699730000 0.0074500000 0.0580010000 0.0003110000 0.0002800000 0.0985090000 8208334 96830484 1771343872 3.0986688137 4.0242047310 4.3013191223 136 5.4000000000 0.0052580792 0.0037431033 0.0055015511 0.0063266964 0.1477710000 0.0103020000 0.0568530000 0.0000280000 0.0003500000 0.0727450000 8210008 96830484 1770209280 3.0919291973 4.0243339539 4.3133592606 137 5.4400000000 0.0051940610 0.0037536942 0.0055015511 0.0063796535 0.1695990000 0.0074600000 0.0473590000 0.0003520000 0.0002650000 0.1078550000 8211682 96830484 1771847680 3.0865287781 4.0247116089 4.3226008415 138 5.4800000000 0.0052057235 0.0037642162 0.0055015511 0.0064223770 0.1085310000 0.0100170000 0.0380890000 0.0000060000 0.0000790000 0.0527160000 8213356 96830484 1770573824 3.0809540749 4.0238699913 4.3272929192 139 5.5200000000 0.0050517544 0.0037734790 0.0055015511 0.0064647223 0.1268060000 0.0090250000 0.0408720000 0.0003580000 0.0002750000 0.0681990000 8215030 96830484 1769320448 3.0748353004 4.0217118263 4.3324923515 140 5.5600000000 0.0050807847 0.0037828169 0.0055015511 0.0065367369 0.1305200000 0.0073690000 0.0505460000 0.0000270000 0.0002890000 0.0668030000 8216704 96830484 1771081728 3.0655672550 4.0224595070 4.3467688560 141 5.6000000000 0.0050909431 0.0037920944 0.0055015511 0.0065706000 0.1531020000 0.0096670000 0.0400510000 0.0002900000 0.0002610000 0.1011930000 8218378 96830484 1769828352 3.0601978302 4.0236749649 4.3522362709 142 5.6400000000 0.0051241852 0.0038014753 0.0055015511 0.0066050987 0.1031860000 0.0075580000 0.0339330000 0.0000070000 0.0000790000 0.0538960000 8220052 96830484 1771487232 3.0509636402 4.0237746239 4.3669538498 143 5.6800000000 0.0051526418 0.0038109241 0.0055015511 0.0066816118 0.1457740000 0.0094400000 0.0603540000 0.0002990000 0.0003430000 0.0671840000 8221726 96830484 1770336256 3.0457272530 4.0260248184 4.3769593239 144 5.7200000000 0.0052279229 0.0038207643 0.0055015511 0.0067254803 0.1295580000 0.0092120000 0.0462640000 0.0000270000 0.0003420000 0.0649980000 8223400 96830484 1769086976 3.0395171642 4.0277700424 4.3848295212 145 5.7600000000 0.0052101971 0.0038303466 0.0055015511 0.0067254994 0.1830910000 0.0072140000 0.0504960000 0.0003540000 0.0002760000 0.1227650000 8225074 96830484 1770827776 3.0339581966 4.0268373489 4.3915781975 146 5.8000000000 0.0052463310 0.0038400451 0.0055015511 0.0067167629 0.1152170000 0.0101860000 0.0410860000 0.0000240000 0.0002990000 0.0551200000 8226748 96830484 1769463808 3.0281167030 4.0269894600 4.4010472298 147 5.8400000000 0.0052832770 0.0038498631 0.0055015511 0.0067002743 0.1451780000 0.0074050000 0.0462810000 0.0003510000 0.0002650000 0.0824160000 8228422 96830484 1771089920 3.0179305077 4.0262370110 4.4219803810 148 5.8800000000 0.0053111040 0.0038597363 0.0055015511 0.0066797053 0.1322670000 0.0093770000 0.0517080000 0.0000290000 0.0002940000 0.0691710000 8230096 96830484 1769955328 3.0165171623 4.0261402130 4.4253592491 149 5.9200000000 0.0052792788 0.0038692634 0.0055015511 0.0066630867 0.1548070000 0.0074210000 0.0451370000 0.0003580000 0.0002800000 0.0957500000 8231770 96830484 1771606016 3.0121631622 4.0268230438 4.4364194870 150 5.9600000000 0.0053305435 0.0038790053 0.0055015511 0.0066447090 0.1012320000 0.0100370000 0.0403970000 0.0000250000 0.0002910000 0.0487250000 8233444 96830484 1770336256 3.0085997581 4.0266056061 4.4451336861 151 6.0000000000 0.0053739781 0.0038889058 0.0055015511 0.0066260883 0.1218030000 0.0092530000 0.0381260000 0.0002870000 0.0003270000 0.0655740000 8235118 96830484 1769213952 3.0053029060 4.0271229744 4.4548649788 152 6.0400000000 0.0053502726 0.0038985200 0.0055015511 0.0066125780 0.1130910000 0.0074210000 0.0421000000 0.0001910000 0.0002910000 0.0612790000 8236792 96830484 1770700800 3.0021977425 4.0284290314 4.4656472206 153 6.0800000000 0.0054323329 0.0039085450 0.0055015511 0.0066018535 0.1571900000 0.0094340000 0.0386040000 0.0002930000 0.0002690000 0.1068390000 8238466 96830484 1769566208 2.9985551834 4.0274720192 4.4742350578 154 6.1200000000 0.0053986544 0.0039182210 0.0055015511 0.0066206331 0.0977720000 0.0089180000 0.0329410000 0.0000110000 0.0001100000 0.0540490000 8240140 96830484 1771327488 2.9940745831 4.0267801285 4.4865512848 155 6.1600000000 0.0053828186 0.0039276700 0.0055015511 0.0066839783 0.1239320000 0.0095970000 0.0384600000 0.0002930000 0.0003380000 0.0667660000 8241814 96830484 1770074112 2.9924225807 4.0258541107 4.4941563606 156 6.2000000000 0.0053906296 0.0039370480 0.0055015511 0.0067957141 0.1320610000 0.0075560000 0.0541500000 0.0000240000 0.0002900000 0.0682250000 8243488 96830484 1771597824 2.9877223969 4.0269780159 4.5091190338 157 6.2400000000 0.0054095751 0.0039464271 0.0055015511 0.0068865812 0.1560940000 0.0095960000 0.0395200000 0.0002900000 0.0003360000 0.1045810000 8245162 96830484 1770455040 2.9854676723 4.0275936127 4.5200443268 158 6.2800000000 0.0053982022 0.0039556156 0.0055015511 0.0069633910 0.1198930000 0.0119500000 0.0410720000 0.0000250000 0.0002810000 0.0578060000 8246836 96830484 1769222144 2.9824633598 4.0278801918 4.5365538597 159 6.3200000000 0.0054318053 0.0039648998 0.0055015511 0.0069938511 0.1513630000 0.0073960000 0.0459720000 0.0002950000 0.0003480000 0.0953940000 8248510 96830484 1770835968 2.9819014072 4.0272908211 4.5442690849 160 6.3600000000 0.0054244986 0.0039740223 0.0055015511 0.0070315159 0.1279730000 0.0093690000 0.0450130000 0.0000270000 0.0002870000 0.0713390000 8250184 96830484 1769730048 2.9807677269 4.0286664963 4.5597171783 161 6.4000000000 0.0055277729 0.0039836729 0.0055277729 0.0070167934 0.1500920000 0.0077290000 0.0382450000 0.0002860000 0.0002610000 0.1016570000 8251858 96830484 1771454464 2.9808900356 4.0291829109 4.5705785751 162 6.4400000000 0.0056116399 0.0039937221 0.0056116399 0.0069972159 0.1073110000 0.0095630000 0.0397140000 0.0000260000 0.0002870000 0.0558640000 8253532 96830484 1770201088 2.9807767868 4.0274944305 4.5817613602 163 6.4800000000 0.0055531142 0.0040032889 0.0056116399 0.0069804384 0.1103770000 0.0075950000 0.0313970000 0.0000810000 0.0000690000 0.0694430000 8255206 96830484 1771728896 2.9798049927 4.0287609100 4.5947580338 164 6.5200000000 0.0055600577 0.0040127814 0.0056116399 0.0069639819 0.1255530000 0.0094360000 0.0445400000 0.0000240000 0.0002890000 0.0632870000 8256880 96830484 1770582016 2.9796931744 4.0301356316 4.6065859795 165 6.5600000000 0.0056226337 0.0040225381 0.0056226337 0.0069544809 0.1724990000 0.0092040000 0.0414600000 0.0003060000 0.0002770000 0.1193910000 8258554 96830484 1769312256 2.9786641598 4.0314221382 4.6245770454 166 6.6000000000 0.0056311330 0.0040322284 0.0056311330 0.0069715005 0.1072230000 0.0078140000 0.0373860000 0.0000320000 0.0003020000 0.0597120000 8260228 96830484 1770962944 2.9794433117 4.0321297646 4.6358819008 167 6.6400000000 0.0055969302 0.0040415979 0.0056311330 0.0069788229 0.1295980000 0.0096090000 0.0405990000 0.0003070000 0.0002810000 0.0769080000 8261902 96830484 1769840640 2.9804966450 4.0340008736 4.6462559700 168 6.6800000000 0.0056347032 0.0040510806 0.0056347032 0.0069810639 0.1293820000 0.0076010000 0.0453430000 0.0000270000 0.0003120000 0.0742280000 8263576 96830484 1771462656 2.9810054302 4.0342464447 4.6586923599 169 6.7200000000 0.0056538559 0.0040605645 0.0056538559 0.0069675723 0.1642860000 0.0094720000 0.0461770000 0.0002970000 0.0002750000 0.1061650000 8265250 96830484 1770201088 2.9810667038 4.0320744514 4.6730980873 170 6.7600000000 0.0056862906 0.0040701276 0.0056862906 0.0069596586 0.1183090000 0.0100270000 0.0394550000 0.0000260000 0.0005200000 0.0597850000 8266924 96830484 1771962368 2.9791903496 4.0341777802 4.6901607513 171 6.8000000000 0.0056537953 0.0040793888 0.0056862906 0.0069529215 0.1320520000 0.0097250000 0.0421930000 0.0003100000 0.0002840000 0.0775150000 8268598 96830484 1770708992 2.9802505970 4.0369043350 4.6993718147 172 6.8400000000 0.0057232729 0.0040889463 0.0057232729 0.0069346813 0.1264130000 0.0091990000 0.0401070000 0.0000250000 0.0002990000 0.0675440000 8270272 96830484 1769476096 2.9807760715 4.0382065773 4.7124075890 173 6.8800000000 0.0057155616 0.0040983487 0.0057232729 0.0069154841 0.1989350000 0.0073940000 0.0579280000 0.0003840000 0.0002770000 0.1232570000 8271946 96830484 1771073536 2.9804041386 4.0398097038 4.7263331413 174 6.9200000000 0.0057898900 0.0041080702 0.0057898900 0.0068960730 0.1130470000 0.0099110000 0.0388710000 0.0000250000 0.0002950000 0.0605600000 8273620 96830484 1769947136 2.9793498516 4.0416283607 4.7389860153 175 6.9600000000 0.0057721375 0.0041175791 0.0057898900 0.0068762946 0.1297340000 0.0074630000 0.0403670000 0.0003760000 0.0006230000 0.0789560000 8275294 96830484 1771458560 2.9798245430 4.0425558090 4.7508134842 176 7.0000000000 0.0057965261 0.0041271186 0.0057965261 0.0068605514 0.1096560000 0.0094870000 0.0352810000 0.0000190000 0.0002060000 0.0626950000 8276968 96830484 1770328064 2.9785537720 4.0429134369 4.7653565407 177 7.0400000000 0.0058230069 0.0041366999 0.0058230069 0.0068711309 0.1635240000 0.0090650000 0.0399440000 0.0003730000 0.0002750000 0.1117740000 8278642 96830484 1769058304 2.9796037674 4.0405187607 4.7724456787 178 7.0800000000 0.0058713625 0.0041464452 0.0058713625 0.0068569578 0.1093790000 0.0091560000 0.0392550000 0.0000270000 0.0003790000 0.0585080000 8280316 96830484 1770819584 2.9808619022 4.0401058197 4.7797164917 179 7.1200000000 0.0057756775 0.0041555471 0.0058713625 0.0068429434 0.1282650000 0.0092820000 0.0394370000 0.0003690000 0.0002760000 0.0738590000 8281990 96830484 1769566208 2.9810593128 4.0424866676 4.7933707237 180 7.1600000000 0.0058105090 0.0041647413 0.0058713625 0.0068246482 0.1280040000 0.0073910000 0.0413060000 0.0000270000 0.0003080000 0.0693580000 8283664 96830484 1771327488 2.9818563461 4.0449447632 4.8064174652 181 7.2000000000 0.0058070384 0.0041738148 0.0058713625 0.0068099252 0.2236540000 0.0094850000 0.0493090000 0.0003190000 0.0002850000 0.1526740000 8285338 96830484 1769947136 2.9840016365 4.0455956459 4.8172302246 182 7.2400000000 0.0058292793 0.0041829107 0.0058713625 0.0067930637 0.1077490000 0.0076580000 0.0326030000 0.0000260000 0.0003680000 0.0574170000 8287012 96830484 1771585536 2.9836800098 4.0458707809 4.8312015533 183 7.2800000000 0.0058379467 0.0041919546 0.0058713625 0.0067779427 0.1284250000 0.0099910000 0.0378750000 0.0001980000 0.0001750000 0.0696750000 8288686 96830484 1770455040 2.9819910526 4.0464487076 4.8473787308 184 7.3200000000 0.0058432720 0.0042009292 0.0058713625 0.0067600124 0.1310200000 0.0096770000 0.0602260000 0.0000270000 0.0003920000 0.0571540000 8290360 96830484 1769222144 2.9841806889 4.0460124016 4.8579874039 185 7.3600000000 0.0058360742 0.0042097678 0.0058713625 0.0067443456 0.1557620000 0.0082820000 0.0396700000 0.0003000000 0.0003600000 0.1051060000 8292034 96830484 1770827776 2.9857268333 4.0463123322 4.8733577728 186 7.4000000000 0.0057869474 0.0042182473 0.0058713625 0.0067319225 0.1214630000 0.0109150000 0.0391000000 0.0000260000 0.0003060000 0.0609290000 8293708 96830484 1769676800 2.9855818748 4.0459403992 4.8914837837 187 7.4400000000 0.0057564480 0.0042264729 0.0058713625 0.0067254993 0.1500480000 0.0092280000 0.0599920000 0.0016790000 0.0002840000 0.0742830000 8295382 96830484 1768460288 2.9887070656 4.0459337234 4.8998847008 188 7.4800000000 0.0057723727 0.0042346958 0.0058713625 0.0067339833 0.1308420000 0.0074030000 0.0450110000 0.0000260000 0.0003680000 0.0759260000 8297056 96830484 1770184704 2.9910883904 4.0494847298 4.9153275490 189 7.5200000000 0.0057317023 0.0042426165 0.0058713625 0.0067178576 0.1767420000 0.0094930000 0.0400400000 0.0002920000 0.0006590000 0.1155960000 8298730 96830484 1768820736 2.9932467937 4.0521445274 4.9329366684 190 7.5600000000 0.0058005541 0.0042508161 0.0058713625 0.0067078205 0.1126300000 0.0082000000 0.0388880000 0.0000250000 0.0002850000 0.0616700000 8300404 96830484 1770463232 2.9955132008 4.0511283875 4.9477171898 191 7.6000000000 0.0058035296 0.0042589455 0.0058713625 0.0066961314 0.1321890000 0.0096240000 0.0410170000 0.0002990000 0.0002690000 0.0788560000 8302078 96830484 1769312256 2.9968194962 4.0533919334 4.9640216827 192 7.6400000000 0.0059071253 0.0042675298 0.0059071253 0.0066889306 0.1249140000 0.0092420000 0.0396720000 0.0000250000 0.0002970000 0.0658580000 8303752 96830484 1768042496 3.0004868507 4.0595726967 4.9791088104 193 7.6800000000 0.0059852800 0.0042764301 0.0059852800 0.0066903627 0.1907970000 0.0074960000 0.0526970000 0.0002940000 0.0003420000 0.1270680000 8305426 96830484 1769676800 3.0005056858 4.0601115227 4.9973998070 194 7.7200000000 0.0060913847 0.0042857855 0.0060913847 0.0066877133 0.1222960000 0.0098040000 0.0385160000 0.0000250000 0.0003100000 0.0628740000 8307100 96830484 1768579072 3.0002415180 4.0561037064 5.0137042999 195 7.7600000000 0.0060795103 0.0042949841 0.0060913847 0.0066908814 0.1474050000 0.0074980000 0.0449410000 0.0002890000 0.0002650000 0.0833410000 8308774 96830484 1770176512 3.0014679432 4.0556755066 5.0267329216 196 7.8000000000 0.0060571237 0.0043039746 0.0060913847 0.0067277218 0.1524560000 0.0094600000 0.0686390000 0.0000250000 0.0003180000 0.0718160000 8310448 96830484 1768923136 3.0033404827 4.0593228340 5.0434970856 197 7.8400000000 0.0061425329 0.0043133074 0.0061425329 0.0067533313 0.1868770000 0.0075420000 0.0402460000 0.0002940000 0.0003370000 0.1286170000 8312122 96830484 1770684416 3.0051894188 4.0627937317 5.0555682182 198 7.8800000000 0.0060075731 0.0043218643 0.0061425329 0.0067712935 0.1153600000 0.0101260000 0.0354570000 0.0000070000 0.0000810000 0.0675800000 8313796 96830484 1769431040 3.0063166618 4.0664410591 5.0721044540 199 7.9200000000 0.0060479632 0.0043305381 0.0061425329 0.0067644958 0.1434370000 0.0093600000 0.0409320000 0.0003020000 0.0002960000 0.0824030000 8315470 96830484 1768144896 3.0083861351 4.0674052238 5.0879182816 200 7.9600000000 0.0062328703 0.0043400498 0.0062328703 0.0067551367 0.1300620000 0.0075170000 0.0417340000 0.0000260000 0.0003640000 0.0749870000 8317144 96830484 1769824256 3.0085654259 4.0659980774 5.1019802094 201 8.0000000000 0.0061905170 0.0043492561 0.0062328703 0.0067704445 0.2010730000 0.0094880000 0.0464380000 0.0003110000 0.0002800000 0.1332870000 8318818 96830484 1768669184 3.0092012882 4.0664062500 5.1207022667 202 8.0400000000 0.0061700302 0.0043582698 0.0062328703 0.0067875518 0.1132270000 0.0083280000 0.0400330000 0.0000260000 0.0003070000 0.0623250000 8320492 96830484 1770311680 3.0120127201 4.0673093796 5.1309838295 203 8.0800000000 0.0062622698 0.0043676492 0.0062622698 0.0067970822 0.1311090000 0.0096230000 0.0381620000 0.0003140000 0.0008020000 0.0799820000 8322166 96830484 1769160704 3.0143148899 4.0690894127 5.1484227180 204 8.1200000000 0.0061317701 0.0043762968 0.0062622698 0.0067892741 0.1258850000 0.0078040000 0.0382520000 0.0000290000 0.0003770000 0.0729420000 8323840 96830484 1770696704 3.0162017345 4.0684967041 5.1607022285 205 8.1600000000 0.0062015634 0.0043852005 0.0062622698 0.0067814093 0.1885310000 0.0097840000 0.0415900000 0.0003870000 0.0002740000 0.1279700000 8325514 96830484 1769549824 3.0191206932 4.0674786568 5.1724720001 206 8.1999999990 0.0062135546 0.0043940761 0.0062622698 0.0067721491 0.1277460000 0.0099850000 0.0438810000 0.0000290000 0.0003870000 0.0621860000 8327188 96830484 1768296448 3.0224809647 4.0675692558 5.1860198975 207 8.2400000000 0.0061982842 0.0044027920 0.0062622698 0.0067649154 0.1299590000 0.0079600000 0.0381690000 0.0003150000 0.0003420000 0.0748550000 8328862 96830484 1770057728 3.0270125866 4.0703992844 5.1996154785 208 8.2799999990 0.0061652721 0.0044112655 0.0062622698 0.0067522144 0.1509150000 0.0094590000 0.0692060000 0.0000250000 0.0003140000 0.0695200000 8330536 96830484 1768693760 3.0312306881 4.0725245476 5.2122244835 209 8.3200000000 0.0062739123 0.0044201777 0.0062739123 0.0067495938 0.1801440000 0.0077060000 0.0330310000 0.0000860000 0.0000750000 0.1278200000 8332210 96830484 1770328064 3.0357863903 4.0744037628 5.2253375053 210 8.3599999990 0.0062792581 0.0044290304 0.0062792581 0.0067735264 0.1149510000 0.0104730000 0.0392480000 0.0000190000 0.0002060000 0.0627180000 8333884 96830484 1769185280 3.0414152145 4.0752496719 5.2363462448 211 8.4000000000 0.0063404832 0.0044380895 0.0063404832 0.0067932688 0.1456580000 0.0076840000 0.0398810000 0.0003840000 0.0002750000 0.0868860000 8335558 96830484 1770835968 3.0464706421 4.0734324455 5.2501068115 212 8.4399999990 0.0063815415 0.0044472567 0.0063815415 0.0067794063 0.1489690000 0.0099410000 0.0424990000 0.0000970000 0.0003120000 0.0842890000 8337232 96830484 1769676800 3.0537533760 4.0763864517 5.2617316246 213 8.4800000000 0.0064212461 0.0044565242 0.0064212461 0.0067810206 0.1981040000 0.0095510000 0.0662660000 0.0003240000 0.0003400000 0.1192200000 8338906 96830484 1768443904 3.0601816177 4.0803155899 5.2762241364 214 8.5200000000 0.0064659980 0.0044659143 0.0064659980 0.0068438847 0.1206340000 0.0087930000 0.0378880000 0.0000260000 0.0002890000 0.0659020000 8340580 96830484 1769938944 3.0672376156 4.0806236267 5.2883591652 215 8.5600000000 0.0064945477 0.0044753498 0.0064945477 0.0068533298 0.1494730000 0.0099050000 0.0418640000 0.0002980000 0.0003420000 0.0882240000 8342254 96830484 1768804352 3.0751185417 4.0799493790 5.2988648415 216 8.6000000000 0.0065747057 0.0044850691 0.0065747057 0.0068385490 0.1529730000 0.0077970000 0.0510090000 0.0000290000 0.0002940000 0.0914030000 8343928 96830484 1770565632 3.0844266415 4.0844678879 5.3104658127 217 8.6400000000 0.0066987830 0.0044952705 0.0066987830 0.0068624458 0.1793280000 0.0098810000 0.0389530000 0.0003090000 0.0003520000 0.1273880000 8345602 96830484 1769312256 3.0934202671 4.0874967575 5.3273324966 218 8.6800000000 0.0065565794 0.0045047260 0.0066987830 0.0069130553 0.1308480000 0.0139660000 0.0377420000 0.0000260000 0.0003010000 0.0671860000 8347276 96830484 1768042496 3.1018471718 4.0872349739 5.3364033699 219 8.7200000000 0.0067064166 0.0045147794 0.0067064166 0.0069131207 0.1534890000 0.0078340000 0.0477100000 0.0002950000 0.0002700000 0.0949680000 8348950 96830484 1769803776 3.1120157242 4.0900926590 5.3467345238 220 8.7600000000 0.0068453876 0.0045253731 0.0068453876 0.0069163438 0.1269570000 0.0095980000 0.0388800000 0.0000270000 0.0003080000 0.0757340000 8350624 96830484 1768587264 3.1226029396 4.0951023102 5.3584980965 221 8.8000000000 0.0067417342 0.0045354019 0.0068453876 0.0069537746 0.1887990000 0.0081720000 0.0412080000 0.0003090000 0.0002750000 0.1354560000 8352298 96830484 1770184704 3.1322591305 4.0962243080 5.3702726364 222 8.8400000000 0.0069097932 0.0045460973 0.0069097932 0.0069622956 0.1102190000 0.0103020000 0.0307250000 0.0000070000 0.0000700000 0.0665350000 8353972 96830484 1768931328 3.1415610313 4.0980634689 5.3848152161 223 8.8800000000 0.0069119441 0.0045567065 0.0069119441 0.0069630541 0.1292210000 0.0081220000 0.0376840000 0.0007590000 0.0002680000 0.0798850000 8355646 96830484 1770692608 3.1522185802 4.1012015343 5.3941946030 224 8.9200000000 0.0068558217 0.0045669704 0.0069119441 0.0069689221 0.1296310000 0.0100980000 0.0405380000 0.0000260000 0.0002950000 0.0760990000 8357320 96830484 1769422848 3.1629397869 4.1042351723 5.4048171043 225 8.9600000000 0.0068885642 0.0045772886 0.0069119441 0.0069662651 0.1808740000 0.0100370000 0.0408570000 0.0003120000 0.0002750000 0.1267920000 8358994 96830484 1768206336 3.1734106541 4.1069216728 5.4128561020 226 9.0000000000 0.0072183600 0.0045889748 0.0072183600 0.0069526647 0.1268810000 0.0103980000 0.0399130000 0.0000230000 0.0002910000 0.0680740000 8360668 96830484 1769930752 3.1838562489 4.1111717224 5.4244890213 227 9.0400000000 0.0070862393 0.0045999759 0.0072183600 0.0069388859 0.1330730000 0.0104950000 0.0338180000 0.0000780000 0.0000690000 0.0860890000 8362342 96830484 1768714240 3.1958312988 4.1170139313 5.4328708649 228 9.0800000000 0.0072635086 0.0046116581 0.0072635086 0.0069501916 0.1274030000 0.0082420000 0.0393590000 0.0000240000 0.0003530000 0.0769560000 8364016 96830484 1770319872 3.2073814869 4.1231055260 5.4463658333 229 9.1200000000 0.0072230431 0.0046230615 0.0072635086 0.0070095292 0.1820270000 0.0106390000 0.0386150000 0.0002900000 0.0003430000 0.1194350000 8365690 96830484 1769185280 3.2179586887 4.1271810532 5.4538083076 230 9.1600000000 0.0072514252 0.0046344892 0.0072635086 0.0071108724 0.1126540000 0.0090250000 0.0368350000 0.0000170000 0.0001890000 0.0641170000 8367364 96830484 1770823680 3.2288503647 4.1312589645 5.4606761932 231 9.2000000000 0.0071084034 0.0046451988 0.0072635086 0.0073237661 0.1273010000 0.0111190000 0.0316080000 0.0001950000 0.0001680000 0.0767520000 8369038 96830484 1769549824 3.2381000519 4.1320743561 5.4681119919 232 9.2400000000 0.0072278720 0.0046563310 0.0072635086 0.0074885108 0.1478270000 0.0103240000 0.0421240000 0.0000280000 0.0002980000 0.0831120000 8370712 96830484 1768296448 3.2476196289 4.1351494789 5.4764685631 233 9.2800000000 0.0071786158 0.0046671563 0.0072635086 0.0076322463 0.2067620000 0.0086290000 0.0568910000 0.0003640000 0.0019760000 0.1262910000 8372386 96830484 1769959424 3.2572281361 4.1379003525 5.4837727547 234 9.3200000000 0.0072247316 0.0046780861 0.0072635086 0.0077361722 0.1176740000 0.0111840000 0.0406440000 0.0000270000 0.0002810000 0.0628400000 8374060 96830484 1768804352 3.2671837807 4.1416583061 5.4906706810 235 9.3600000000 0.0071897143 0.0046887738 0.0072635086 0.0078133224 0.1280660000 0.0088580000 0.0376170000 0.0002930000 0.0003480000 0.0755490000 8375734 96830484 1770565632 3.2772872448 4.1448612213 5.4979667664 236 9.4000000000 0.0073412992 0.0047000134 0.0073412992 0.0078743775 0.1309290000 0.0107840000 0.0445470000 0.0000260000 0.0002920000 0.0726880000 8377408 96830484 1769185280 3.2867586613 4.1478252411 5.5063419342 237 9.4400000000 0.0072533204 0.0047107868 0.0073412992 0.0079027232 0.1818190000 0.0088650000 0.0339430000 0.0000710000 0.0000620000 0.1258820000 8379082 96830484 1770819584 3.2967314720 4.1517887115 5.5128068924 238 9.4800000000 0.0074419929 0.0047222625 0.0074419929 0.0079247261 0.1301880000 0.0112920000 0.0396970000 0.0000250000 0.0002850000 0.0669320000 8380756 96830484 1769693184 3.3076195717 4.1580171585 5.5205988884 239 9.5200000000 0.0073686484 0.0047333352 0.0074419929 0.0079684690 0.1507560000 0.0105660000 0.0617940000 0.0003890000 0.0002740000 0.0718170000 8382430 96830484 1768460288 3.3183436394 4.1631016731 5.5281271935 240 9.5600000000 0.0074091824 0.0047444846 0.0074419929 0.0080224962 0.1104330000 0.0094890000 0.0330000000 0.0000070000 0.0000810000 0.0652690000 8384104 96830484 1770184704 3.3285520077 4.1679220200 5.5366945267 241 9.6000000000 0.0073671583 0.0047553670 0.0074419929 0.0080772365 0.1785280000 0.0105640000 0.0441350000 0.0003120000 0.0003410000 0.1202670000 8385778 96830484 1768931328 3.3378491402 4.1686501503 5.5454206467 242 9.6400000000 0.0072513977 0.0047656812 0.0074419929 0.0080980232 0.1352330000 0.0102160000 0.0474970000 0.0000260000 0.0003800000 0.0636140000 8387452 96830484 1770442752 3.3475980759 4.1710453033 5.5539622307 243 9.6800000000 0.0072520971 0.0047759134 0.0074419929 0.0081123779 0.1333110000 0.0118780000 0.0494230000 0.0002930000 0.0002640000 0.0687220000 8389126 96830484 1769295872 3.3585801125 4.1770195961 5.5617213249 244 9.7200000000 0.0072627170 0.0047861052 0.0074419929 0.0081593651 0.1272670000 0.0103060000 0.0452280000 0.0000250000 0.0003710000 0.0665010000 8390800 96830484 1768042496 3.3698759079 4.1834473610 5.5698981285 245 9.7600000000 0.0071155876 0.0047956133 0.0074419929 0.0082226075 0.1992640000 0.0086180000 0.0487100000 0.0003640000 0.0002820000 0.1257760000 8392474 96830484 1769705472 3.3801040649 4.1858243942 5.5777435303 246 9.8000000000 0.0071129859 0.0048050335 0.0074419929 0.0082424165 0.1144100000 0.0111870000 0.0374870000 0.0000090000 0.0000900000 0.0630360000 8394148 96830484 1768587264 3.3904457092 4.1886858940 5.5867166519 247 9.8400000000 0.0071934848 0.0048147033 0.0074419929 0.0082475664 0.1277840000 0.0087280000 0.0411500000 0.0003030000 0.0002710000 0.0738170000 8395822 96830484 1770065920 3.3999631405 4.1890296936 5.5966963768 248 9.8800000000 0.0071915998 0.0048242876 0.0074419929 0.0082327684 0.1474390000 0.0108390000 0.0497980000 0.0000270000 0.0002960000 0.0767040000 8397496 96830484 1768931328 3.4092972279 4.1907863617 5.6052098274 249 9.9200000000 0.0071689170 0.0048337038 0.0074419929 0.0082173493 0.1990770000 0.0088300000 0.0527490000 0.0003060000 0.0002890000 0.1341500000 8399170 96830484 1770565632 3.4193298817 4.1930556297 5.6128511429 250 9.9600000000 0.0071839117 0.0048431046 0.0074419929 0.0082011724 0.1205730000 0.0133600000 0.0389890000 0.0000110000 0.0001180000 0.0653640000 8400844 96830484 1769439232 3.4290142059 4.1952667236 5.6217961311 251 10.0000000000 0.0072737900 0.0048527886 0.0074419929 0.0081850175 0.1516220000 0.0102990000 0.0514590000 0.0003100000 0.0003510000 0.0865120000 8402518 96830484 1768189952 3.4391326904 4.1984300613 5.6306056976 252 10.0400000000 0.0072200862 0.0048621827 0.0074419929 0.0081718363 0.1259620000 0.0087600000 0.0451130000 0.0000270000 0.0002900000 0.0655230000 8404192 96830484 1769820160 3.4476654530 4.1974697113 5.6410489082 253 10.0800000000 0.0071694297 0.0048713022 0.0074419929 0.0081565577 0.2457110000 0.0105990000 0.1016020000 0.0003960000 0.0002730000 0.1194850000 8405866 96830484 1768550400 3.4552130699 4.1943402290 5.6508669853 254 10.1200000000 0.0072454321 0.0048806492 0.0074419929 0.0081768545 0.1298800000 0.0092150000 0.0454560000 0.0000270000 0.0003150000 0.0622640000 8407540 96830484 1770213376 3.4650044441 4.1982121468 5.6597628593 255 10.1600000000 0.0072444421 0.0048899190 0.0074419929 0.0081920353 0.1308470000 0.0112510000 0.0419680000 0.0012160000 0.0003040000 0.0708470000 8409214 96830484 1769058304 3.4758853912 4.2050776482 5.6686735153 256 10.2000000000 0.0072643212 0.0048991940 0.0074419929 0.0081795043 0.1107800000 0.0092350000 0.0355850000 0.0000190000 0.0002060000 0.0628900000 8410888 96830484 1770708992 3.4870820045 4.2099967003 5.6771268845 257 10.2400000000 0.0072170347 0.0049082128 0.0074419929 0.0081652195 0.1840640000 0.0105200000 0.0453260000 0.0003130000 0.0003530000 0.1129660000 8433042 96830484 1769439232 3.4964504242 4.2096548080 5.6859345436 258 10.2800000000 0.0072307624 0.0049172149 0.0074419929 0.0081493629 0.1285260000 0.0106340000 0.0535610000 0.0000250000 0.0004780000 0.0609960000 8476700 96830484 1768316928 3.5068004131 4.2147393227 5.6947603226 259 10.3200000000 0.0072531835 0.0049262341 0.0074419929 0.0081435425 0.1284800000 0.0089370000 0.0452860000 0.0003860000 0.0002760000 0.0707280000 8478374 96830484 1770057728 3.5172820091 4.2186408043 5.7011680603 260 10.3600000000 0.0072594336 0.0049352080 0.0074419929 0.0081496000 0.1272460000 0.0107600000 0.0438130000 0.0000260000 0.0003160000 0.0618740000 8480048 96830484 1768841216 3.5272617340 4.2202429771 5.7094039917 261 10.4000000000 0.0071995272 0.0049438835 0.0074419929 0.0081493002 0.1631670000 0.0087490000 0.0426690000 0.0003110000 0.0010740000 0.1075060000 8481722 96830484 1770446848 3.5368244648 4.2197060585 5.7162361145 262 10.4400000000 0.0072190091 0.0049525672 0.0074419929 0.0081369262 0.1335130000 0.0151180000 0.0497340000 0.0000270000 0.0003830000 0.0614770000 8483396 96830484 1769168896 3.5463531017 4.2199959755 5.7234449387 263 10.4800000000 0.0071899486 0.0049610743 0.0074419929 0.0081234539 0.1295650000 0.0088950000 0.0446020000 0.0003190000 0.0003570000 0.0693270000 8485070 96830484 1770946560 3.5571446419 4.2214131355 5.7290558815 264 10.5200000000 0.0071815168 0.0049694851 0.0074419929 0.0081132052 0.1686280000 0.0108860000 0.0867650000 0.0000250000 0.0003750000 0.0609170000 8486744 96830484 1769693184 3.5674560070 4.2210521698 5.7350697517 265 10.5600000000 0.0072301202 0.0049780158 0.0074419929 0.0080980771 0.1635250000 0.0106560000 0.0416780000 0.0003890000 0.0002740000 0.1075910000 8488418 96830484 1768460288 3.5787055492 4.2229838371 5.7412343025 266 10.6000000000 0.0071409997 0.0049861473 0.0074419929 0.0080872630 0.1292240000 0.0102890000 0.0432250000 0.0000260000 0.0011620000 0.0603860000 8490092 96830484 1770086400 3.5906906128 4.2252111435 5.7455463409 267 10.6400000000 0.0071661584 0.0049943122 0.0074419929 0.0080835863 0.1315580000 0.0108060000 0.0448070000 0.0003910000 0.0002880000 0.0690300000 8491766 96830484 1768931328 3.6019568443 4.2243156433 5.7495784760 268 10.6800000000 0.0071932431 0.0050025171 0.0074419929 0.0080768128 0.1292340000 0.0085990000 0.0538500000 0.0000300000 0.0003090000 0.0602240000 8493440 96830484 1770582016 3.6132988930 4.2237806320 5.7556233406 269 10.7200000000 0.0071482142 0.0050104937 0.0074419929 0.0080658521 0.1730130000 0.0109280000 0.0497470000 0.0003170000 0.0002740000 0.1033650000 8495114 96830484 1769295872 3.6251964569 4.2235808372 5.7579751015 270 10.7600000000 0.0071400967 0.0050183811 0.0074419929 0.0080565736 0.1155010000 0.0103500000 0.0436710000 0.0000250000 0.0003290000 0.0581050000 8496788 96830484 1768034304 3.6505968571 4.2283124924 5.7682948112 271 10.8000000000 0.0071303020 0.0050261742 0.0074419929 0.0080735814 0.1280650000 0.0082720000 0.0423870000 0.0003090000 0.0003500000 0.0719350000 8498462 96830484 1769795584 3.6649234295 4.2320523262 5.7716302872 272 10.8400000000 0.0071498575 0.0050339818 0.0074419929 0.0081357162 0.1286570000 0.0099310000 0.0461370000 0.0000280000 0.0003040000 0.0660570000 8500136 96830484 1768542208 3.6768729687 4.2302017212 5.7751474380 273 10.8800000000 0.0071553937 0.0050417526 0.0074419929 0.0081441106 0.2037330000 0.0080690000 0.0546430000 0.0003100000 0.0002830000 0.1249660000 8501810 96830484 1770205184 3.6894824505 4.2309336662 5.7796964645 274 10.9200000000 0.0071847606 0.0050495738 0.0074419929 0.0081529597 0.1136550000 0.0107800000 0.0449590000 0.0000310000 0.0003210000 0.0546200000 8503484 96830484 1769050112 3.7027606964 4.2321753502 5.7833747864 275 10.9600000000 0.0071675256 0.0050572754 0.0074419929 0.0081585821 0.1273290000 0.0087260000 0.0455120000 0.0003240000 0.0003430000 0.0654730000 8505158 96830484 1770700800 3.7156510353 4.2321186066 5.7861371040 276 11.0000000000 0.0071881157 0.0050649959 0.0074419929 0.0081557804 0.1276770000 0.0107180000 0.0419360000 0.0000250000 0.0003630000 0.0617300000 8506832 96830484 1769431040 3.7291152477 4.2340230942 5.7899084091 277 11.0400000000 0.0072061722 0.0050727257 0.0074419929 0.0081613577 0.1896540000 0.0096940000 0.0650870000 0.0003280000 0.0003460000 0.1035660000 8508506 96830484 1768198144 3.7426838875 4.2355213165 5.7932553291 278 11.0800000000 0.0072293654 0.0050804834 0.0074419929 0.0081672050 0.1110900000 0.0085470000 0.0425530000 0.0000260000 0.0003040000 0.0565550000 8510180 96830484 1769824256 3.7562696934 4.2372851372 5.7966260910 279 11.1200000000 0.0072107618 0.0050881188 0.0074419929 0.0081765392 0.1282980000 0.0107430000 0.0456700000 0.0003140000 0.0003440000 0.0638610000 8511854 96830484 1768706048 3.7702217102 4.2390351295 5.8006215096 280 11.1600000000 0.0072117136 0.0050957031 0.0074419929 0.0081848066 0.1106620000 0.0088470000 0.0448150000 0.0000280000 0.0003190000 0.0535620000 8513528 96830484 1770319872 3.7842233181 4.2415375710 5.8037843704 281 11.2000000000 0.0072458065 0.0051033547 0.0074419929 0.0081911724 0.1675240000 0.0102960000 0.0457320000 0.0003610000 0.0002760000 0.1037770000 8515202 96830484 1769050112 3.7973754406 4.2424178123 5.8063907623 282 11.2400000000 0.0072158491 0.0051108458 0.0074419929 0.0081865326 0.1109300000 0.0087790000 0.0458290000 0.0000340000 0.0003170000 0.0523800000 8516876 96830484 1770700800 3.8092210293 4.2414021492 5.8110079765 283 11.2800000000 0.0072045014 0.0051182439 0.0074419929 0.0081722249 0.1279030000 0.0106110000 0.0457770000 0.0002890000 0.0002590000 0.0661880000 8518550 96830484 1769558016 3.8215155602 4.2427053452 5.8134932518 284 11.3200000000 0.0072371671 0.0051257049 0.0074419929 0.0081613399 0.1283860000 0.0096960000 0.0467000000 0.0000240000 0.0002830000 0.0642020000 8520224 96830484 1768288256 3.8341059685 4.2448267937 5.8188529015 285 11.3600000000 0.0073399986 0.0051334744 0.0074419929 0.0081585671 0.1800540000 0.0081550000 0.0519700000 0.0002880000 0.0003270000 0.1036630000 8521898 96830484 1769938944 3.8457179070 4.2460341454 5.8229842186 286 11.4000000000 0.0072419588 0.0051408467 0.0074419929 0.0081504518 0.1136890000 0.0105170000 0.0453820000 0.0000270000 0.0003890000 0.0536660000 8523572 96830484 1768706048 3.8562197685 4.2458934784 5.8269877434 287 11.4400000000 0.0072880541 0.0051483282 0.0074419929 0.0081362742 0.1266550000 0.0086580000 0.0425920000 0.0002850000 0.0003390000 0.0614390000 8525246 96830484 1770319872 3.8657524586 4.2455530167 5.8311848640 288 11.4800000000 0.0072166361 0.0051555099 0.0074419929 0.0081229825 0.1124040000 0.0110760000 0.0452850000 0.0000260000 0.0003930000 0.0523660000 8526920 96830484 1769177088 3.8745987415 4.2453618050 5.8351273537 289 11.5200000000 0.0072731958 0.0051628375 0.0074419929 0.0081102802 0.1660840000 0.0086980000 0.0460090000 0.0003180000 0.0003480000 0.0976450000 8528594 96830484 1770827776 3.8831486702 4.2452931404 5.8416900635 290 11.5600000000 0.0072817197 0.0051701440 0.0074419929 0.0081020250 0.1524060000 0.0109960000 0.0857610000 0.0000270000 0.0002810000 0.0521500000 8530268 96830484 1769558016 3.8914682865 4.2457027435 5.8474440575 291 11.6000000000 0.0073214364 0.0051775368 0.0074419929 0.0080918333 0.1667560000 0.0099850000 0.0846770000 0.0002900000 0.0003340000 0.0607970000 8531942 96830484 1768435712 3.8990240097 4.2448401451 5.8545670509 292 11.6400000000 0.0073223813 0.0051848821 0.0074419929 0.0080797221 0.1270440000 0.0087220000 0.0605170000 0.0000270000 0.0002780000 0.0533740000 8533616 96830484 1769938944 3.9070658684 4.2458314896 5.8603334427 293 11.6800000000 0.0073132911 0.0051921463 0.0074419929 0.0080659949 0.1585140000 0.0105580000 0.0337000000 0.0001950000 0.0001690000 0.0976470000 8535290 96830484 1768796160 3.9140355587 4.2460818291 5.8671889305 294 11.7200000000 0.0073506190 0.0051994880 0.0074419929 0.0080536961 0.1136900000 0.0094210000 0.0446220000 0.0000260000 0.0003150000 0.0529350000 8536964 96830484 1770446848 3.9201622009 4.2453889847 5.8745393753 295 11.7600000000 0.0073434757 0.0052067558 0.0074419929 0.0080458106 0.1289620000 0.0107760000 0.0488040000 0.0003930000 0.0002790000 0.0604980000 8538638 96830484 1769287680 3.9258491993 4.2453398705 5.8814907074 296 11.8000000000 0.0073283808 0.0052139235 0.0074419929 0.0080367550 0.1099120000 0.0101070000 0.0426190000 0.0000260000 0.0002890000 0.0531850000 8540312 96830484 1768034304 3.9317009449 4.2455120087 5.8880209923 297 11.8400000000 0.0073664878 0.0052211711 0.0074419929 0.0080282524 0.1665470000 0.0087330000 0.0464780000 0.0003220000 0.0003550000 0.0963660000 8541986 96830484 1769684992 3.9366052151 4.2450776100 5.8955769539 298 11.8800000000 0.0073884320 0.0052284438 0.0074419929 0.0080237498 0.1109240000 0.0104300000 0.0358560000 0.0000170000 0.0002580000 0.0562230000 8543660 96830484 1768562688 3.9415006638 4.2444596291 5.9035415649 299 11.9200000000 0.0073690070 0.0052356029 0.0074419929 0.0080147546 0.1298670000 0.0082940000 0.0471340000 0.0003860000 0.0002790000 0.0689730000 8545334 96830484 1770065920 3.9465432167 4.2444586754 5.9116683006 300 11.9600000000 0.0073738876 0.0052427305 0.0074419929 0.0080022171 0.1284330000 0.0101810000 0.0410340000 0.0000310000 0.0003160000 0.0681900000 8547008 96830484 1768923136 3.9515573978 4.2452802658 5.9199595451 301 12.0000000000 0.0073729921 0.0052498078 0.0074419929 0.0079891421 0.1871930000 0.0087440000 0.0483600000 0.0003710000 0.0002830000 0.1144610000 8548682 96830484 1770573824 3.9561946392 4.2455625534 5.9291901588 302 12.0400000000 0.0074241417 0.0052570076 0.0074419929 0.0079785176 0.1120210000 0.0107320000 0.0430880000 0.0000310000 0.0003110000 0.0538730000 8550356 96830484 1769414656 3.9601697922 4.2454571724 5.9390864372 303 12.0800000000 0.0073767337 0.0052640034 0.0074419929 0.0079725906 0.1270500000 0.0102750000 0.0430290000 0.0010760000 0.0002830000 0.0617790000 8552030 96830484 1768181760 3.9643566608 4.2457032204 5.9490427971 304 12.1200000000 0.0074868421 0.0052713153 0.0074868421 0.0079715906 0.1295580000 0.0088710000 0.0576980000 0.0000280000 0.0002880000 0.0534470000 8553704 96830484 1769684992 3.9682958126 4.2460737228 5.9593019485 305 12.1600000000 0.0074375300 0.0052784177 0.0074868421 0.0079686468 0.1520220000 0.0103910000 0.0426210000 0.0003730000 0.0002760000 0.0949630000 8555378 96830484 1768542208 3.9719529152 4.2458839417 5.9705891609 306 12.2000000000 0.0074679595 0.0052855731 0.0074868421 0.0079620435 0.1251180000 0.0079870000 0.0464850000 0.0000280000 0.0003590000 0.0574350000 8557052 96830484 1770192896 3.9755680561 4.2458815575 5.9821076393 307 12.2400000000 0.0075131920 0.0052928291 0.0075131920 0.0079639082 0.1522160000 0.0101150000 0.0684320000 0.0003040000 0.0003450000 0.0695630000 8558726 96830484 1769050112 3.9788534641 4.2466526031 5.9937467575 308 12.2800000000 0.0075425324 0.0053001334 0.0075425324 0.0079679500 0.1261040000 0.0080730000 0.0375670000 0.0000280000 0.0003860000 0.0668480000 8560400 96830484 1770700800 3.9814891815 4.2467846870 6.0053153038 309 12.3200000000 0.0075095445 0.0053072836 0.0075425324 0.0079793515 0.1911580000 0.0102090000 0.0666120000 0.0003910000 0.0002840000 0.1076920000 8562074 96830484 1769414656 3.9834015369 4.2463583946 6.0162491798 310 12.3600000000 0.0075569362 0.0053145405 0.0075569362 0.0079982960 0.1277090000 0.0101030000 0.0507020000 0.0000300000 0.0003860000 0.0554550000 8563748 96830484 1768198144 3.9850788116 4.2458825111 6.0282092094 311 12.4000000000 0.0075834822 0.0053218362 0.0075834822 0.0080121738 0.1300290000 0.0083990000 0.0501740000 0.0003150000 0.0003400000 0.0634100000 8565422 96830484 1769811968 3.9873003960 4.2467231750 6.0389986038 312 12.4400000000 0.0076281969 0.0053292283 0.0076281969 0.0080493406 0.1119200000 0.0103610000 0.0421680000 0.0000290000 0.0003000000 0.0556530000 8567096 96830484 1768706048 3.9896602631 4.2464780807 6.0628433228 313 12.4800000000 0.0076256399 0.0053365651 0.0076281969 0.0080431731 0.1553920000 0.0077970000 0.0431010000 0.0003110000 0.0003440000 0.1004110000 8568770 96830484 1770319872 3.9902474880 4.2462701797 6.0735983849 314 12.5200000000 0.0076742438 0.0053440099 0.0076742438 0.0080355083 0.1197510000 0.0132600000 0.0453760000 0.0000290000 0.0003140000 0.0559150000 8570444 96830484 1769050112 3.9903092384 4.2451834679 6.0861616135 315 12.5600000000 0.0077040317 0.0053515021 0.0077040317 0.0080358353 0.1270650000 0.0084420000 0.0423420000 0.0003050000 0.0003470000 0.0636050000 8572118 96830484 1770811392 3.9907627106 4.2454414368 6.0975146294 316 12.6000000000 0.0076975487 0.0053589263 0.0077040317 0.0080256219 0.1115670000 0.0108400000 0.0424070000 0.0000270000 0.0003770000 0.0544570000 8573792 96830484 1769541632 3.9909455776 4.2456779480 6.1096744537 317 12.6400000000 0.0076432684 0.0053661324 0.0077040317 0.0080130648 0.1666440000 0.0102240000 0.0438090000 0.0012000000 0.0002930000 0.0998790000 8575466 96830484 1768435712 3.9906268120 4.2449584007 6.1213231087 318 12.6800000000 0.0076455348 0.0053733003 0.0077040317 0.0080004178 0.1110910000 0.0087090000 0.0424110000 0.0000290000 0.0003050000 0.0559880000 8577140 96830484 1770065920 3.9899880886 4.2444357872 6.1326842308 319 12.7200000000 0.0076021259 0.0053802873 0.0077040317 0.0079878413 0.1291130000 0.0105980000 0.0514210000 0.0003760000 0.0002760000 0.0629760000 8578814 96830484 1768685568 3.9892587662 4.2445030212 6.1427187920 320 12.7600000000 0.0075561246 0.0053870867 0.0077040317 0.0079753180 0.1500010000 0.0086960000 0.0860250000 0.0000300000 0.0003810000 0.0513880000 8580488 96830484 1770557440 3.9880611897 4.2445869446 6.1529593468 321 12.8000000000 0.0075005945 0.0053936709 0.0077040317 0.0079652568 0.1794950000 0.0103620000 0.0536370000 0.0005560000 0.0002840000 0.0964430000 8582162 96830484 1769431040 3.9859168530 4.2434430122 6.1637663841 322 12.8400000000 0.0074224598 0.0053999715 0.0077040317 0.0079550149 0.1134390000 0.0103700000 0.0456470000 0.0000260000 0.0003120000 0.0533960000 8583836 96830484 1768271872 3.9842751026 4.2437133789 6.1732611656 323 12.8800000000 0.0073768292 0.0054060918 0.0077040317 0.0079461761 0.1270650000 0.0086730000 0.0446040000 0.0003830000 0.0002770000 0.0644110000 8585510 96830484 1769938944 3.9823191166 4.2425618172 6.1819939613 324 12.9200000000 0.0073206592 0.0054120009 0.0077040317 0.0079348571 0.1310220000 0.0103120000 0.0551260000 0.0000290000 0.0003760000 0.0616060000 8587184 96830484 1768669184 3.9803371429 4.2418608665 6.1912159920 325 12.9600000000 0.0072150687 0.0054175488 0.0077040317 0.0079228145 0.1864870000 0.0082800000 0.0505560000 0.0003070000 0.0003480000 0.1155910000 8588858 96830484 1770446848 3.9789364338 4.2425885201 6.2003254890 326 13.0000000000 0.0071793455 0.0054229531 0.0077040317 0.0079112010 0.1087730000 0.0110670000 0.0440580000 0.0000270000 0.0003170000 0.0496320000 8590532 96830484 1769431040 3.9769806862 4.2422032356 6.2075972557 327 13.0400000000 0.0072000218 0.0054283876 0.0077040317 0.0079004501 0.1261850000 0.0107520000 0.0464230000 0.0003260000 0.0003510000 0.0586360000 8592206 96830484 1768308736 3.9750475883 4.2426018715 6.2173500061 328 13.0800000000 0.0071992134 0.0054337864 0.0077040317 0.0078895588 0.1096560000 0.0093590000 0.0404520000 0.0000260000 0.0003860000 0.0534960000 8593880 96830484 1769938944 3.9745304585 4.2453002930 6.2239203453 329 13.1200000000 0.0071638525 0.0054390450 0.0077040317 0.0078781255 0.1690900000 0.0106230000 0.0560990000 0.0000820000 0.0000580000 0.0986990000 8595554 96830484 1768652800 3.9729261398 4.2460441589 6.2330021858 330 13.1600000000 0.0071280962 0.0054441633 0.0077040317 0.0078673084 0.1100000000 0.0110430000 0.0445090000 0.0000280000 0.0003110000 0.0489640000 8597228 96830484 1770348544 3.9710223675 4.2462706566 6.2410573959 331 13.2000000000 0.0071798158 0.0054494070 0.0077040317 0.0078558048 0.1267260000 0.0114640000 0.0443530000 0.0003240000 0.0003500000 0.0558240000 8598902 96830484 1769177088 3.9693257809 4.2468862534 6.2511096001 332 13.2400000000 0.0073184771 0.0054550367 0.0077040317 0.0078460846 0.1093710000 0.0095950000 0.0403430000 0.0000290000 0.0003130000 0.0480610000 8600576 96830484 1770827776 3.9675800800 4.2474908829 6.2597055435 333 13.2800000000 0.0072761509 0.0054605055 0.0077040317 0.0078353179 0.1495830000 0.0113920000 0.0432430000 0.0003220000 0.0002770000 0.0838330000 8602250 96830484 1769431040 3.9654788971 4.2476992607 6.2690320015 334 13.3200000000 0.0072991364 0.0054660104 0.0077040317 0.0078240969 0.1113810000 0.0107470000 0.0529180000 0.0000270000 0.0003130000 0.0437610000 8603924 96830484 1768288256 3.9632644653 4.2476191521 6.2770023346 335 13.3600000000 0.0072785006 0.0054714208 0.0077040317 0.0078125575 0.1075590000 0.0090300000 0.0362190000 0.0003180000 0.0002760000 0.0560280000 8605598 96830484 1770065920 3.9612171650 4.2485785484 6.2855963707 336 13.4000000000 0.0072842594 0.0054768162 0.0077040317 0.0078009635 0.1272930000 0.0105410000 0.0495170000 0.0000310000 0.0003070000 0.0537230000 8607272 96830484 1768816640 3.9597706795 4.2504644394 6.2934122086 337 13.4400000000 0.0072782435 0.0054821617 0.0077040317 0.0077996166 0.1470800000 0.0082870000 0.0434380000 0.0003100000 0.0003430000 0.0910190000 8608946 96830484 1770573824 3.9580950737 4.2528557777 6.3008394241 338 13.4800000000 0.0073059909 0.0054875576 0.0077040317 0.0078057002 0.0942080000 0.0107560000 0.0351470000 0.0000080000 0.0000770000 0.0445020000 8610620 96830484 1769447424 3.9563336372 4.2544822693 6.3070406914 339 13.5200000000 0.0073107537 0.0054929358 0.0077040317 0.0078216645 0.1085980000 0.0087020000 0.0418680000 0.0003950000 0.0002880000 0.0536230000 8612294 96830484 1767936000 3.9539306164 4.2544836998 6.3124933243 340 13.5600000000 0.0073153148 0.0054982957 0.0077040317 0.0078181083 0.1082750000 0.0081330000 0.0467730000 0.0000290000 0.0002900000 0.0493650000 8613968 96830484 1767018496 3.9515447617 4.2548317909 6.3176441193 341 13.6000000000 0.0073534627 0.0055037361 0.0077040317 0.0078114644 0.1458360000 0.0080340000 0.0483220000 0.0002960000 0.0002670000 0.0851400000 8615642 96830484 1765748736 3.9494123459 4.2552208900 6.3224954605 342 13.6400000000 0.0073215603 0.0055090514 0.0077040317 0.0078031133 0.1089450000 0.0089640000 0.0452050000 0.0000270000 0.0003840000 0.0414530000 8617316 96830484 1765122048 3.9472951889 4.2555336952 6.3280072212 343 13.6800000000 0.0073881662 0.0055145298 0.0077040317 0.0077921154 0.1095340000 0.0083600000 0.0425660000 0.0002940000 0.0012710000 0.0460040000 8618990 96830484 1764093952 3.9454083443 4.2558550835 6.3327383995 344 13.7200000000 0.0074160439 0.0055200575 0.0077040317 0.0077808971 0.0917570000 0.0088650000 0.0419260000 0.0000270000 0.0002970000 0.0368610000 8620664 96830484 1765748736 3.9443604946 4.2575035095 6.3382768631 345 13.7600000000 0.0074364417 0.0055256122 0.0077040317 0.0077729614 0.1287150000 0.0081680000 0.0448600000 0.0003580000 0.0002700000 0.0711020000 8622338 96830484 1767399424 3.9424867630 4.2573819160 6.3436956406 346 13.8000000000 0.0074265990 0.0055311064 0.0077040317 0.0077671676 0.0911030000 0.0080090000 0.0418040000 0.0000300000 0.0002910000 0.0371620000 8624012 96830484 1769177088 3.9408476353 4.2572388649 6.3486852646 347 13.8400000000 0.0073777032 0.0055364280 0.0077040317 0.0077563942 0.1049110000 0.0076670000 0.0400980000 0.0003620000 0.0002680000 0.0440980000 8625686 96830484 1770827776 3.9384753704 4.2558159828 6.3532862663 348 13.8800000000 0.0073424918 0.0055416178 0.0077040317 0.0077458555 0.0920780000 0.0104720000 0.0423690000 0.0000270000 0.0002870000 0.0351340000 8627360 96830484 1769684992 3.9379105568 4.2579884529 6.3590779305 349 13.9200000000 0.0073302202 0.0055467428 0.0077040317 0.0077429380 0.1211130000 0.0088220000 0.0433280000 0.0002870000 0.0011370000 0.0636400000 8629034 96830484 1768415232 3.9362730980 4.2576265335 6.3647866249 350 13.9600000000 0.0073110075 0.0055517835 0.0077040317 0.0077348310 0.0923360000 0.0081950000 0.0504310000 0.0000280000 0.0003090000 0.0295180000 8630708 96830484 1770176512 3.9342541695 4.2562303543 6.3736166954 351 14.0000000000 0.0071627148 0.0055563731 0.0077040317 0.0077246594 0.1099660000 0.0103880000 0.0453840000 0.0002910000 0.0004640000 0.0442790000 8632382 96830484 1768796160 3.9340023994 4.2567739487 6.3782615662 352 14.0400000000 0.0071655228 0.0055609445 0.0077040317 0.0077164205 0.1288260000 0.0077800000 0.0587350000 0.0000280000 0.0003000000 0.0522200000 8634056 96830484 1770684416 3.9334242344 4.2563672066 6.3830356598 353 14.0800000000 0.0071655605 0.0055654902 0.0077040317 0.0077054963 0.1483970000 0.0101520000 0.0683840000 0.0003030000 0.0000570000 0.0656400000 8635730 96830484 1769414656 3.9330894947 4.2553577423 6.3873291016 354 14.1200000000 0.0071829734 0.0055700593 0.0077040317 0.0076946227 0.0919270000 0.0096010000 0.0432590000 0.0000270000 0.0003610000 0.0347940000 8637404 96830484 1768161280 3.9334175587 4.2559070587 6.3921575546 355 14.1600000000 0.0071995365 0.0055746494 0.0077040317 0.0076841304 0.1049120000 0.0083050000 0.0435300000 0.0002960000 0.0002700000 0.0407480000 8639078 96830484 1767149568 3.9329116344 4.2544860840 6.3968935013 356 14.2000000000 0.0071500433 0.0055790747 0.0077040317 0.0076755479 0.1081960000 0.0085860000 0.0496520000 0.0000230000 0.0002920000 0.0344950000 8640752 96830484 1768923136 3.9331839085 4.2542700768 6.4015455246 357 14.2400000000 0.0070691272 0.0055832485 0.0077040317 0.0076652322 0.1295240000 0.0083390000 0.0435680000 0.0003190000 0.0002750000 0.0634470000 8642426 96830484 1770700800 3.9334659576 4.2547063828 6.4071583748 358 14.2800000000 0.0070911204 0.0055874604 0.0077040317 0.0076552531 0.0920090000 0.0107850000 0.0423660000 0.0000270000 0.0010460000 0.0338990000 8644100 96830484 1769684992 3.9331893921 4.2533326149 6.4125366211 359 14.3200000000 0.0070780781 0.0055916126 0.0077040317 0.0076460730 0.1050830000 0.0087700000 0.0442430000 0.0003240000 0.0002670000 0.0398720000 8645774 96830484 1767780352 3.9325616360 4.2515120506 6.4179773331 360 14.3600000000 0.0070382105 0.0055956309 0.0077040317 0.0076377052 0.0937410000 0.0086400000 0.0533030000 0.0000260000 0.0003710000 0.0274310000 8647448 96830484 1769582592 3.9323914051 4.2501811981 6.4240908623 361 14.4000000000 0.0070457025 0.0055996477 0.0077040317 0.0076342349 0.1200630000 0.0101220000 0.0454290000 0.0003920000 0.0002810000 0.0598430000 8649122 96830484 1767890944 3.9322888851 4.2499985695 6.4305772781 362 14.4400000000 0.0070510106 0.0056036570 0.0077040317 0.0076280866 0.0944860000 0.0076930000 0.0469600000 0.0000240000 0.0002910000 0.0352730000 8650796 96830484 1769684992 3.9322922230 4.2502036095 6.4370865822 363 14.4800000000 0.0070533953 0.0056076508 0.0077040317 0.0076179147 0.1089500000 0.0096950000 0.0478720000 0.0002900000 0.0002630000 0.0438830000 8652470 96830484 1768452096 3.9324440956 4.2510895729 6.4442496300 364 14.5200000000 0.0070514949 0.0056116174 0.0077040317 0.0076082821 0.1092930000 0.0077530000 0.0590190000 0.0000280000 0.0003620000 0.0374920000 8654144 96830484 1770065920 3.9320924282 4.2504234314 6.4514431953 365 14.5600000000 0.0070720995 0.0056156187 0.0077040317 0.0075981655 0.1688520000 0.0099000000 0.0894710000 0.0000600000 0.0000520000 0.0653600000 8655818 96830484 1768796160 3.9315376282 4.2495069504 6.4584455490 366 14.6000000000 0.0070825852 0.0056196268 0.0077040317 0.0075877860 0.1038400000 0.0083800000 0.0523840000 0.0000260000 0.0005370000 0.0332080000 8657492 96830484 1770573824 3.9314501286 4.2504158020 6.4662723541 367 14.6400000000 0.0071512922 0.0056238003 0.0077040317 0.0075775873 0.1093330000 0.0107960000 0.0497710000 0.0003140000 0.0002740000 0.0386570000 8659166 96830484 1769558016 3.9315326214 4.2513794899 6.4734969139 368 14.6800000000 0.0071991710 0.0056280812 0.0077040317 0.0075698810 0.1067660000 0.0099720000 0.0455890000 0.0000270000 0.0003820000 0.0330420000 8660840 96830484 1768288256 3.9313621521 4.2518963814 6.4812440872 369 14.7200000000 0.0072035594 0.0056323508 0.0077040317 0.0075696823 0.1408690000 0.0083820000 0.0700480000 0.0003130000 0.0003470000 0.0575050000 8662514 96830484 1770065920 3.9305880070 4.2516250610 6.4886684418 370 14.7600000000 0.0072354404 0.0056366835 0.0077040317 0.0075677427 0.1208490000 0.0100900000 0.0733590000 0.0000260000 0.0003000000 0.0329570000 8664188 96830484 1768796160 3.9304101467 4.2520046234 6.4965953827 371 14.8000000000 0.0072592520 0.0056410570 0.0077040317 0.0075620691 0.1076270000 0.0082270000 0.0517280000 0.0003070000 0.0003500000 0.0387840000 8665862 96830484 1770573824 3.9303910732 4.2516918182 6.5037398338 372 14.8400000000 0.0072665922 0.0056454267 0.0077040317 0.0075583883 0.1083860000 0.0102100000 0.0542220000 0.0000280000 0.0003800000 0.0333280000 8667536 96830484 1769447424 3.9301850796 4.2511596680 6.5107722282 373 14.8800000000 0.0072774515 0.0056498021 0.0077040317 0.0075590950 0.1107100000 0.0099970000 0.0412690000 0.0003080000 0.0002730000 0.0548190000 8669210 96830484 1768198144 3.9300775528 4.2509202957 6.5180325508 374 14.9200000000 0.0073239352 0.0056542784 0.0077040317 0.0075558475 0.1066010000 0.0086140000 0.0512490000 0.0000270000 0.0003010000 0.0341640000 8670884 96830484 1769938944 3.9299626350 4.2502460480 6.5252280235 375 14.9600000000 0.0073652146 0.0056588409 0.0077040317 0.0075586141 0.1103010000 0.0101520000 0.0504230000 0.0003050000 0.0003520000 0.0404950000 8672558 96830484 1768923136 3.9302515984 4.2498774529 6.5321679115 376 15.0000000000 0.0073881983 0.0056634402 0.0077040317 0.0075581449 0.1299450000 0.0084230000 0.0822100000 0.0000270000 0.0003080000 0.0348950000 8674232 96830484 1770717184 3.9312629700 4.2512402534 6.5395879745 377 15.0400000000 0.0074251681 0.0056681132 0.0077040317 0.0075510548 0.1218000000 0.0106960000 0.0428920000 0.0011770000 0.0002950000 0.0626180000 8675906 96830484 1769160704 3.9335985184 4.2523293495 6.5526790619 378 15.0800000000 0.0075383494 0.0056730609 0.0077040317 0.0075411154 0.0967410000 0.0084710000 0.0495030000 0.0000260000 0.0003130000 0.0342730000 8677580 96830484 1770827776 3.9356408119 4.2535872459 6.5589818954 379 15.1200000000 0.0075239511 0.0056779446 0.0077040317 0.0075311962 0.1076010000 0.0105750000 0.0453150000 0.0003840000 0.0002830000 0.0430080000 8679254 96830484 1769558016 3.9374895096 4.2540149689 6.5646681786 380 15.1600000000 0.0075786663 0.0056829465 0.0077040317 0.0075224188 0.0906520000 0.0104090000 0.0394010000 0.0000280000 0.0003080000 0.0363430000 8680928 96830484 1768689664 3.9402852058 4.2551121712 6.5700902939 381 15.2000000000 0.0075994153 0.0056879766 0.0077040317 0.0075126577 0.1830440000 0.0085230000 0.0911980000 0.0003070000 0.0002710000 0.0665250000 8682602 96830484 1766756352 3.9426660538 4.2560849190 6.5751690865 382 15.2400000000 0.0076246783 0.0056930465 0.0077040317 0.0075039989 0.0923440000 0.0088170000 0.0393480000 0.0000290000 0.0003830000 0.0395350000 8684276 96830484 1768562688 3.9449107647 4.2564477921 6.5799832344 383 15.2800000000 0.0076704901 0.0056982095 0.0077040317 0.0074947939 0.1271450000 0.0081530000 0.0484750000 0.0003210000 0.0003390000 0.0599630000 8685950 96830484 1770176512 3.9476051331 4.2574386597 6.5845594406 384 15.3200000000 0.0076827779 0.0057033776 0.0077040317 0.0074850964 0.1271840000 0.0103510000 0.0725820000 0.0000270000 0.0003060000 0.0391850000 8687624 96830484 1768923136 3.9504241943 4.2580885887 6.5883893967 385 15.3600000000 0.0077608521 0.0057087217 0.0077608521 0.0074763403 0.1431190000 0.0096820000 0.0441650000 0.0003800000 0.0002770000 0.0737340000 8689298 96830484 1770684416 3.9529879093 4.2577366829 6.5909290314 386 15.4000000000 0.0077581960 0.0057140313 0.0077608521 0.0074739498 0.1094190000 0.0111450000 0.0449700000 0.0000280000 0.0003880000 0.0398630000 8690972 96830484 1769304064 3.9560210705 4.2582912445 6.5931172371 387 15.4400000000 0.0077895387 0.0057193943 0.0077895387 0.0074758427 0.1292550000 0.0104240000 0.0586130000 0.0003180000 0.0003500000 0.0472250000 8692646 96830484 1768435712 3.9597289562 4.2604217529 6.5953302383 388 15.4800000000 0.0077734818 0.0057246884 0.0077895387 0.0074668649 0.0930740000 0.0089550000 0.0417420000 0.0000250000 0.0007090000 0.0374290000 8694320 96830484 1770065920 3.9627332687 4.2615780830 6.5963768959 389 15.5200000000 0.0077722073 0.0057299519 0.0077895387 0.0074580563 0.1444820000 0.0107260000 0.0438020000 0.0003070000 0.0002720000 0.0757660000 8695994 96830484 1768796160 3.9653482437 4.2616839409 6.5973796844 390 15.5600000000 0.0077562253 0.0057351475 0.0077895387 0.0074485886 0.1089410000 0.0093610000 0.0423860000 0.0003420000 0.0010730000 0.0422620000 8697668 96830484 1770586112 3.9692153931 4.2647256851 6.5986247063 391 15.6000000000 0.0077050417 0.0057401856 0.0077895387 0.0074559555 0.1112620000 0.0112630000 0.0440030000 0.0003180000 0.0003450000 0.0496660000 8699342 96830484 1769304064 3.9723536968 4.2649388313 6.5999689102 392 15.6400000000 0.0077219601 0.0057452411 0.0077895387 0.0074473827 0.1079080000 0.0107450000 0.0443290000 0.0000260000 0.0003880000 0.0436510000 8701016 96830484 1768017920 3.9752030373 4.2647438049 6.6003608704 393 15.6800000000 0.0076589691 0.0057501107 0.0077895387 0.0074381535 0.1358050000 0.0093460000 0.0401540000 0.0003140000 0.0002730000 0.0814570000 8702690 96830484 1769684992 3.9772679806 4.2631602287 6.6010169983 394 15.7200000000 0.0077032507 0.0057550679 0.0077895387 0.0074300614 0.1024760000 0.0120320000 0.0367580000 0.0000250000 0.0003880000 0.0484230000 8704364 96830484 1768542208 3.9793212414 4.2614035606 6.6020255089 395 15.7600000000 0.0077425814 0.0057600995 0.0077895387 0.0074321638 0.1288210000 0.0084250000 0.0496870000 0.0003050000 0.0002830000 0.0640230000 8706038 96830484 1770303488 3.9826586246 4.2618608475 6.6026248932 396 15.8000000000 0.0077606076 0.0057651513 0.0077895387 0.0074267176 0.1516560000 0.0103270000 0.0767340000 0.0000270000 0.0003190000 0.0599720000 8707712 96830484 1769177088 3.9864311218 4.2621350288 6.6028485298 397 15.8400000000 0.0077267257 0.0057700923 0.0077895387 0.0074296826 0.1644620000 0.0081450000 0.0491980000 0.0003220000 0.0003420000 0.1019340000 8709386 96830484 1770954752 3.9892933369 4.2613101006 6.6028103828 398 15.8800000000 0.0077104382 0.0057749676 0.0077895387 0.0074245778 0.1122400000 0.0110210000 0.0484580000 0.0000190000 0.0002610000 0.0481010000 8711060 96830484 1769684992 3.9922142029 4.2594923973 6.6021232605 399 15.9200000000 0.0076690773 0.0057797147 0.0077895387 0.0074167156 0.1255620000 0.0105070000 0.0383350000 0.0003080000 0.0003560000 0.0613950000 8712734 96830484 1768652800 3.9967300892 4.2611150742 6.6006727219 400 15.9600000000 0.0076455297 0.0057843792 0.0077895387 0.0074096782 0.1289520000 0.0079220000 0.0550950000 0.0000280000 0.0003110000 0.0519830000 8714408 96830484 1770336256 4.0010557175 4.2621231079 6.6008553505 401 16.0000000000 0.0076041436 0.0057889173 0.0077895387 0.0074042735 0.1508460000 0.0107220000 0.0426760000 0.0011900000 0.0002990000 0.0914150000 8716082 96830484 1768923136 4.0053906441 4.2624907494 6.6012415886 402 16.0400000000 0.0076168636 0.0057934644 0.0077895387 0.0073958672 0.1080490000 0.0079180000 0.0360040000 0.0000180000 0.0002030000 0.0554940000 8717756 96830484 1770573824 4.0109233856 4.2631049156 6.6009383202 403 16.0800000000 0.0076494860 0.0057980700 0.0077895387 0.0073903832 0.1504740000 0.0099760000 0.0530340000 0.0003260000 0.0003500000 0.0823100000 8719430 96830484 1769304064 4.0155453682 4.2625999451 6.6022095680 404 16.1200000000 0.0077511077 0.0058029042 0.0077895387 0.0073818933 0.1476150000 0.0095390000 0.0575760000 0.0000270000 0.0003850000 0.0757740000 8721104 96830484 1768071168 4.0205254555 4.2631039619 6.6009349823 405 16.1600000000 0.0079277018 0.0058081506 0.0079277018 0.0073732735 0.1673710000 0.0076530000 0.0440850000 0.0003120000 0.0003550000 0.1046690000 8722778 96830484 1769811968 4.0259718895 4.2636060715 6.6018424034 406 16.2000000000 0.0081254402 0.0058138582 0.0081254402 0.0073646456 0.1257750000 0.0098540000 0.0443660000 0.0000290000 0.0003130000 0.0598210000 8724452 96830484 1768525824 4.0319151878 4.2653026581 6.6040053368 407 16.2400000000 0.0081691369 0.0058196452 0.0081691369 0.0073568986 0.1339870000 0.0077060000 0.0397870000 0.0003860000 0.0002840000 0.0813670000 8726126 96830484 1770319872 4.0370960236 4.2662134171 6.6059141159 408 16.2800000000 0.0082234377 0.0058255368 0.0082234377 0.0073596987 0.1244820000 0.0094850000 0.0418200000 0.0000280000 0.0003090000 0.0607170000 8727800 96830484 1769304064 4.0423955917 4.2668251991 6.6086435318 409 16.3200000000 0.0081765018 0.0058312849 0.0082234377 0.0073627754 0.2084060000 0.0091730000 0.0716800000 0.0003070000 0.0002860000 0.1125010000 8729474 96830484 1768054784 4.0490565300 4.2703709602 6.6114754677 410 16.3600000000 0.0082723964 0.0058372388 0.0082723964 0.0073540251 0.1108290000 0.0084170000 0.0389550000 0.0000270000 0.0003770000 0.0570480000 8731148 96830484 1769684992 4.0552563667 4.2735013962 6.6156973839 411 16.3999999990 0.0083110621 0.0058432579 0.0083110621 0.0073480897 0.1488490000 0.0093110000 0.0460520000 0.0003080000 0.0003540000 0.0850330000 8732822 96830484 1768562688 4.0587868690 4.2723093033 6.6174440384 412 16.4400000000 0.0082759596 0.0058491625 0.0083110621 0.0073639624 0.1279510000 0.0075780000 0.0440790000 0.0000270000 0.0003060000 0.0656640000 8734496 96830484 1770303488 4.0639996529 4.2721552849 6.6239142418 413 16.4800000000 0.0083349580 0.0058551813 0.0083349580 0.0073783307 0.1844220000 0.0098380000 0.0519120000 0.0006200000 0.0003550000 0.1171320000 8736170 96830484 1769050112 4.0703501701 4.2736248970 6.6309952736 414 16.5200000000 0.0083702840 0.0058612565 0.0083702840 0.0073745831 0.1090130000 0.0097780000 0.0387050000 0.0000270000 0.0003910000 0.0554400000 8737844 96830484 1770700800 4.0751848221 4.2715587616 6.6345353127 415 16.5599999990 0.0084680747 0.0058675380 0.0084680747 0.0073893610 0.1458820000 0.0095930000 0.0429980000 0.0003720000 0.0002830000 0.0781120000 8739518 96830484 1769431040 4.0783929825 4.2658658028 6.6400904655 416 16.6000000000 0.0085275099 0.0058739321 0.0085275099 0.0074722271 0.1497880000 0.0091050000 0.0668440000 0.0000270000 0.0003080000 0.0626270000 8741192 96830484 1768415232 4.0847301483 4.2659149170 6.6457996368 417 16.6400000000 0.0085718222 0.0058804019 0.0085718222 0.0075056399 0.1889520000 0.0077370000 0.0624140000 0.0003920000 0.0002860000 0.1084810000 8742866 96830484 1770192896 4.0910453796 4.2675909996 6.6474189758 418 16.6800000000 0.0086434158 0.0058870120 0.0086434158 0.0075103233 0.1110240000 0.0106450000 0.0403070000 0.0000280000 0.0003010000 0.0550720000 8744540 96830484 1768923136 4.0932674408 4.2644848824 6.6467385292 419 16.7199999990 0.0087660309 0.0058938831 0.0087660309 0.0075424214 0.1289270000 0.0073460000 0.0462110000 0.0003080000 0.0002740000 0.0702140000 8746214 96830484 1770700800 4.1011204720 4.2675766945 6.6524605751 420 16.7600000000 0.0087601589 0.0059007076 0.0087660309 0.0075337999 0.1296770000 0.0096040000 0.0469460000 0.0000250000 0.0003720000 0.0681310000 8747888 96830484 1769304064 4.1084680557 4.2703003883 6.6523880959 421 16.8000000000 0.0088421116 0.0059076943 0.0088421116 0.0075450022 0.1668000000 0.0091210000 0.0413210000 0.0003910000 0.0002790000 0.1074430000 8749562 96830484 1768419328 4.1124019623 4.2658686638 6.6533045769 422 16.8400000000 0.0089558968 0.0059149175 0.0089558968 0.0075424742 0.1089900000 0.0082820000 0.0377180000 0.0000260000 0.0002890000 0.0553230000 8751236 96830484 1770065920 4.1212964058 4.2593255043 6.6553258896 423 16.8799999990 0.0089256410 0.0059220351 0.0089558968 0.0075388115 0.1495710000 0.0094470000 0.0487560000 0.0002920000 0.0002670000 0.0847400000 8752910 96830484 1768812544 4.1283464432 4.2582521439 6.6552791595 424 16.9200000000 0.0087943086 0.0059288093 0.0089558968 0.0075304338 0.1282440000 0.0076780000 0.0461420000 0.0000270000 0.0003610000 0.0663020000 8754584 96830484 1770602496 4.1336498260 4.2552485466 6.6530199051 425 16.9600000000 0.0086584957 0.0059352321 0.0089558968 0.0075300232 0.2057770000 0.0097180000 0.0704340000 0.0002880000 0.0002620000 0.1026320000 8756258 96830484 1769304064 4.1413497925 4.2557196617 6.6503591537 426 17.0000000000 0.0086677624 0.0059416465 0.0089558968 0.0075223779 0.1112120000 0.0086700000 0.0381980000 0.0000070000 0.0000770000 0.0541050000 8757932 96830484 1771110400 4.1502294540 4.2558183670 6.6496720314 427 17.0400000000 0.0086701633 0.0059480365 0.0089558968 0.0075204448 0.1530200000 0.0096650000 0.0720360000 0.0002880000 0.0002610000 0.0660600000 8759606 96830484 1769828352 4.1561102867 4.2520570755 6.6452126503 428 17.0800000000 0.0086917570 0.0059544470 0.0089558968 0.0075122547 0.1261600000 0.0098770000 0.0535520000 0.0000280000 0.0002870000 0.0565150000 8761280 96830484 1768308736 4.1658596992 4.2503190041 6.6419038773 429 17.1200000000 0.0085015399 0.0059603843 0.0089558968 0.0075054454 0.1749220000 0.0081230000 0.0596520000 0.0003680000 0.0002720000 0.1018540000 8762954 96830484 1769947136 4.1762084961 4.2491488457 6.6403393745 430 17.1600000000 0.0087890066 0.0059669625 0.0089558968 0.0075029632 0.1403410000 0.0113220000 0.0643190000 0.0000260000 0.0003840000 0.0502370000 8764628 96830484 1768939520 4.1846499443 4.2454690933 6.6335697174 431 17.2000000000 0.0089655230 0.0059739197 0.0089655230 0.0074943338 0.1303870000 0.0085870000 0.0513960000 0.0003760000 0.0002790000 0.0611530000 8766302 96830484 1770860544 4.1942348480 4.2411875725 6.6301498413 432 17.2400000000 0.0091248276 0.0059812135 0.0091248276 0.0074931000 0.1480540000 0.0101990000 0.0762000000 0.0000260000 0.0003010000 0.0492730000 8767976 96830484 1769431040 4.2063589096 4.2399072647 6.6254448891 433 17.2800000000 0.0088815326 0.0059879117 0.0091248276 0.0074859042 0.1897070000 0.0085350000 0.0747390000 0.0003030000 0.0003550000 0.0972210000 8769650 96830484 1771126784 4.2175288200 4.2383656502 6.6197690964 434 17.3200000000 0.0088177864 0.0059944321 0.0091248276 0.0074773307 0.1470630000 0.0102620000 0.0700160000 0.0000280000 0.0003010000 0.0492100000 8771324 96830484 1769955328 4.2272820473 4.2337675095 6.6112532616 435 17.3600000000 0.0087846583 0.0060008464 0.0091248276 0.0074887726 0.1505040000 0.0102490000 0.0691820000 0.0002970000 0.0006850000 0.0597710000 8772998 96830484 1768435712 4.2402067184 4.2329568863 6.6058745384 436 17.4000000000 0.0087365117 0.0060071209 0.0091248276 0.0074940143 0.1251390000 0.0085860000 0.0580510000 0.0000290000 0.0003060000 0.0487320000 8774672 96830484 1770074112 4.2560954094 4.2366814613 6.5988664627 437 17.4400000000 0.0088102780 0.0060135355 0.0091248276 0.0074915455 0.1701610000 0.0101470000 0.0577690000 0.0003060000 0.0002740000 0.0968080000 8776346 96830484 1768452096 4.2734618187 4.2422389984 6.5902500153 438 17.4800000000 0.0087588942 0.0060198034 0.0091248276 0.0075961087 0.1275470000 0.0081230000 0.0628160000 0.0000250000 0.0002890000 0.0471460000 8778020 96830484 1770176512 4.2868099213 4.2434663773 6.5822129250 439 17.5200000000 0.0086241513 0.0060257358 0.0091248276 0.0077373915 0.1491530000 0.0103490000 0.0689850000 0.0002840000 0.0002620000 0.0587550000 8779694 96830484 1768939520 4.2942619324 4.2379932404 6.5713391304 440 17.5600000000 0.0085794767 0.0060315398 0.0091248276 0.0077668337 0.1287640000 0.0083190000 0.0631660000 0.0000270000 0.0003610000 0.0476880000 8781368 96830484 1770602496 4.3002409935 4.2293682098 6.5628824234 441 17.6000000000 0.0086717615 0.0060375267 0.0091248276 0.0077632891 0.1884190000 0.0101350000 0.0755480000 0.0002900000 0.0002680000 0.0926250000 8783042 96830484 1769447424 4.3081417084 4.2225713730 6.5553269386 442 17.6400000000 0.0085224370 0.0060431487 0.0091248276 0.0078228404 0.1275010000 0.0086350000 0.0568460000 0.0000260000 0.0002900000 0.0470440000 8784716 96830484 1771220992 4.3215632439 4.2234497070 6.5462627411 443 17.6800000000 0.0083595999 0.0060483777 0.0091248276 0.0078454389 0.1304920000 0.0101970000 0.0506760000 0.0002820000 0.0003250000 0.0584760000 8786390 96830484 1769828352 4.3470096588 4.2275242805 6.5287947655 444 17.7200000000 0.0079213334 0.0060525960 0.0091248276 0.0078405457 0.1471540000 0.0100220000 0.0749160000 0.0000280000 0.0003090000 0.0469140000 8788064 96830484 1768534016 4.3558940887 4.2267489433 6.5169134140 445 17.7600000000 0.0079277093 0.0060568098 0.0091248276 0.0078367083 0.1433310000 0.0086580000 0.0430560000 0.0010040000 0.0002740000 0.0853330000 8789738 96830484 1770377216 4.3660521507 4.2239346504 6.5088052750 446 17.8000000000 0.0080003282 0.0060611675 0.0091248276 0.0078279146 0.1519000000 0.0128210000 0.0757560000 0.0000240000 0.0002810000 0.0470940000 8791412 96830484 1769074688 4.3761725426 4.2241249084 6.4996924400 447 17.8400000000 0.0077510327 0.0060649479 0.0091248276 0.0078235265 0.1500380000 0.0085940000 0.0721300000 0.0002940000 0.0002620000 0.0575060000 8793086 96830484 1770758144 4.3836603165 4.2211122513 6.4918518066 448 17.8800000000 0.0079052206 0.0060690557 0.0091248276 0.0078148444 0.1088410000 0.0101140000 0.0380320000 0.0000340000 0.0003030000 0.0487900000 8794760 96830484 1769455616 4.3914880753 4.2191715240 6.4844107628 449 17.9200000000 0.0079917358 0.0060733378 0.0091248276 0.0078063418 0.1955760000 0.0077890000 0.0875360000 0.0000600000 0.0000540000 0.0952180000 8796434 96830484 1771266048 4.3996362686 4.2173280716 6.4763917923 450 17.9600000000 0.0079415422 0.0060774894 0.0091248276 0.0077988775 0.1420040000 0.0117890000 0.0744050000 0.0000260000 0.0003030000 0.0453620000 8798108 96830484 1769963520 4.4062328339 4.2131314278 6.4705967903 451 18.0000000000 0.0077358331 0.0060811664 0.0091248276 0.0078021509 0.1493360000 0.0101040000 0.0744980000 0.0005530000 0.0002620000 0.0564480000 8799782 96830484 1768460288 4.4154262543 4.2126812935 6.4646501541 452 18.0400000000 0.0078854114 0.0060851581 0.0091248276 0.0077960959 0.1274220000 0.0081900000 0.0624950000 0.0000280000 0.0002800000 0.0447770000 8801456 96830484 1770119168 4.4255471230 4.2127799988 6.4581031799 453 18.0800000000 0.0078464905 0.0060890462 0.0091248276 0.0077874757 0.1687800000 0.0101120000 0.0561780000 0.0006360000 0.0003620000 0.0888540000 8803130 96830484 1768804352 4.4330363274 4.2094550133 6.4514980316 454 18.1200000000 0.0077444017 0.0060926924 0.0091248276 0.0077867151 0.1290000000 0.0084130000 0.0664490000 0.0000240000 0.0003490000 0.0438380000 8804804 96830484 1770594304 4.4429125786 4.2086596489 6.4458675385 455 18.1600000000 0.0077004139 0.0060962259 0.0091248276 0.0077793448 0.1488280000 0.0102300000 0.0723770000 0.0002830000 0.0003360000 0.0545400000 8806478 96830484 1769312256 4.4531512260 4.2076945305 6.4406189919 456 18.2000000000 0.0078052208 0.0060999737 0.0091248276 0.0077724133 0.1074900000 0.0081540000 0.0374040000 0.0000250000 0.0003550000 0.0461320000 8808152 96830484 1770991616 4.4618844986 4.2045626640 6.4340858459 457 18.2400000000 0.0077359462 0.0061035535 0.0091248276 0.0077735307 0.2107400000 0.0095910000 0.0954230000 0.0003640000 0.0002770000 0.1001300000 8809826 96830484 1769930752 4.4709315300 4.2017431259 6.4290981293 458 18.2800000000 0.0077353511 0.0061071163 0.0091248276 0.0077880781 0.1295900000 0.0097060000 0.0716520000 0.0000260000 0.0002870000 0.0427800000 8811500 96830484 1768206336 4.4827032089 4.2029824257 6.4261455536 459 18.3200000000 0.0079433890 0.0061111169 0.0091248276 0.0077815733 0.1464430000 0.0080580000 0.0704810000 0.0002890000 0.0002640000 0.0542930000 8813174 96830484 1769992192 4.4961209297 4.2053742409 6.4198951721 460 18.3600000000 0.0076793246 0.0061145261 0.0091248276 0.0077813654 0.1113350000 0.0100120000 0.0543990000 0.0000270000 0.0003070000 0.0414450000 8814848 96830484 1768714240 4.5040225983 4.2013864517 6.4160437584 461 18.4000000000 0.0076051545 0.0061177595 0.0091248276 0.0077738866 0.1665420000 0.0079250000 0.0609610000 0.0002900000 0.0002640000 0.0864260000 8816522 96830484 1770483712 4.5150899887 4.1995339394 6.4130654335 462 18.4400000000 0.0075787758 0.0061209219 0.0091248276 0.0077665119 0.1096550000 0.0100650000 0.0493040000 0.0000280000 0.0003130000 0.0428530000 8818196 96830484 1769185280 4.5262746811 4.2004113197 6.4073505402 463 18.4800000000 0.0075788875 0.0061240709 0.0091248276 0.0077608258 0.1267460000 0.0084640000 0.0488240000 0.0003100000 0.0003310000 0.0539840000 8819870 96830484 1770885120 4.5355582237 4.1983661652 6.4011750221 464 18.5200000000 0.0076189884 0.0061272927 0.0091248276 0.0077545571 0.1118670000 0.0105440000 0.0547720000 0.0000260000 0.0003090000 0.0411740000 8821544 96830484 1769566208 4.5433812141 4.1948552132 6.3981895447 465 18.5600000000 0.0076321596 0.0061305290 0.0091248276 0.0077504286 0.1473130000 0.0083020000 0.0429990000 0.0002870000 0.0003360000 0.0864530000 8823218 96830484 1771393024 4.5513353348 4.1907744408 6.3951110840 466 18.6000000000 0.0074416106 0.0061333424 0.0091248276 0.0077670173 0.1072550000 0.0099530000 0.0372430000 0.0000290000 0.0003730000 0.0442720000 8824892 96830484 1770074112 4.5628457069 4.1917309761 6.3919672966 467 18.6400000000 0.0073004998 0.0061358417 0.0091248276 0.0077621466 0.1501130000 0.0099010000 0.0714690000 0.0002870000 0.0003430000 0.0590490000 8826566 96830484 1768460288 4.5738077164 4.1900997162 6.3893146515 468 18.6800000000 0.0074213361 0.0061385885 0.0091248276 0.0077637681 0.1472970000 0.0080600000 0.0787810000 0.0000060000 0.0000610000 0.0464470000 8828240 96830484 1770373120 4.5838704109 4.1866259575 6.3885126114 469 18.7200000000 0.0074087474 0.0061412967 0.0091248276 0.0077859209 0.1855360000 0.0098520000 0.0682680000 0.0002960000 0.0003540000 0.0905970000 8829914 96830484 1769201664 4.5931787491 4.1850814819 6.3871822357 470 18.7600000000 0.0074180793 0.0061440133 0.0091248276 0.0078044004 0.1082130000 0.0087150000 0.0421190000 0.0000260000 0.0010060000 0.0406510000 8831588 96830484 1770946560 4.6016216278 4.1817083359 6.3867826462 471 18.8000000000 0.0073908446 0.0061466605 0.0091248276 0.0078560780 0.1117380000 0.0106230000 0.0410950000 0.0002870000 0.0003310000 0.0537550000 8833262 96830484 1769947136 4.6127433777 4.1799798012 6.3846602440 472 18.8400000000 0.0073674424 0.0061492469 0.0091248276 0.0078997879 0.1067900000 0.0107400000 0.0424580000 0.0000280000 0.0010720000 0.0399820000 8834936 96830484 1768443904 4.6233468056 4.1802644730 6.3816184998 473 18.8800000000 0.0074563385 0.0061520103 0.0091248276 0.0079086701 0.1486780000 0.0087970000 0.0407430000 0.0002870000 0.0003350000 0.0861960000 8836610 96830484 1770246144 4.6330976486 4.1803226471 6.3775629997 474 18.9200000000 0.0074147359 0.0061546743 0.0091248276 0.0079062795 0.1086660000 0.0107410000 0.0424410000 0.0000260000 0.0010580000 0.0404550000 8838284 96830484 1769074688 4.6383762360 4.1788849831 6.3700137138 475 18.9600000000 0.0074525629 0.0061574067 0.0091248276 0.0079050238 0.1095250000 0.0090940000 0.0348970000 0.0000690000 0.0000610000 0.0540480000 8839958 96830484 1770975232 4.6472101212 4.1769499779 6.3678598404 476 19.0000000000 0.0074847084 0.0061601951 0.0091248276 0.0079108247 0.1277630000 0.0103540000 0.0628190000 0.0000260000 0.0003210000 0.0398810000 8841632 96830484 1769693184 4.6564822197 4.1767754555 6.3651432991 477 19.0400000000 0.0074313045 0.0061628599 0.0091248276 0.0079089905 0.1405900000 0.0110090000 0.0427820000 0.0003160000 0.0003400000 0.0807930000 8843306 96830484 1768058880 4.6648793221 4.1767749786 6.3572082520 478 19.0800000000 0.0075026853 0.0061656629 0.0091248276 0.0079029105 0.1149630000 0.0102410000 0.0543500000 0.0000250000 0.0002880000 0.0393800000 8844980 96830484 1769803776 4.6776561737 4.1761674881 6.3603224754 479 19.1200000000 0.0075431373 0.0061685386 0.0091248276 0.0078958418 0.1099660000 0.0106960000 0.0388780000 0.0002910000 0.0002630000 0.0530180000 8846654 96830484 1768677376 4.6849503517 4.1733918190 6.3590517044 480 19.1600000000 0.0076852790 0.0061716985 0.0091248276 0.0079011628 0.1092680000 0.0082480000 0.0520980000 0.0000260000 0.0002870000 0.0433300000 8848328 96830484 1770455040 4.6955251694 4.1714816093 6.3609094620 481 19.2000000000 0.0080006942 0.0061755010 0.0091248276 0.0079167200 0.1667900000 0.0103790000 0.0497340000 0.0003080000 0.0002720000 0.0938160000 8850002 96830484 1769455616 4.7033944130 4.1736936569 6.3550267220 482 19.2400000000 0.0079561258 0.0061791952 0.0091248276 0.0079090299 0.1301920000 0.0090490000 0.0753410000 0.0000250000 0.0002970000 0.0387590000 8851676 96830484 1771266048 4.7131681442 4.1732635498 6.3562173843 483 19.2800000000 0.0078445133 0.0061826431 0.0091248276 0.0079010489 0.1260170000 0.0109000000 0.0445560000 0.0003910000 0.0002810000 0.0510850000 8853350 96830484 1770328064 4.7217383385 4.1709218025 6.3549904823 484 19.3200000000 0.0080375345 0.0061864755 0.0091248276 0.0078976901 0.1485550000 0.0108580000 0.0785850000 0.0000250000 0.0002920000 0.0398200000 8855024 96830484 1768947712 4.7269454002 4.1707930565 6.3504528999 485 19.3600000000 0.0082096308 0.0061906470 0.0091248276 0.0078947842 0.1434060000 0.0093190000 0.0507140000 0.0003670000 0.0002830000 0.0773910000 8856698 96830484 1770438656 4.7365455627 4.1739358902 6.3460388184 486 19.4000000000 0.0079777883 0.0061943242 0.0091248276 0.0078976402 0.1135960000 0.0136020000 0.0472700000 0.0000270000 0.0003190000 0.0391120000 8858372 96830484 1769328640 4.7453336716 4.1768522263 6.3436708450 487 19.4400000000 0.0081363115 0.0061983119 0.0091248276 0.0079399047 0.1270460000 0.0088290000 0.0466620000 0.0006040000 0.0002820000 0.0507360000 8860046 96830484 1771012096 4.7514042854 4.1737546921 6.3407759666 488 19.4800000000 0.0080677867 0.0062021427 0.0091248276 0.0079392897 0.1098720000 0.0107390000 0.0448350000 0.0000260000 0.0003250000 0.0396370000 8861720 96830484 1769820160 4.7512731552 4.1711130142 6.3332405090 489 19.5200000000 0.0081029525 0.0062060299 0.0091248276 0.0079313095 0.1406160000 0.0105340000 0.0475510000 0.0003890000 0.0002710000 0.0765690000 8863394 96830484 1768206336 4.7562594414 4.1705951691 6.3289117813 490 19.5600000000 0.0080789328 0.0062098521 0.0091248276 0.0079234828 0.0966240000 0.0097040000 0.0404760000 0.0000110000 0.0001150000 0.0408900000 8865068 96830484 1769975808 4.7603116035 4.1698718071 6.3206257820 491 19.6000000000 0.0080438135 0.0062135873 0.0091248276 0.0079156123 0.1475840000 0.0098170000 0.0745540000 0.0003830000 0.0002840000 0.0507910000 8866742 96830484 1768550400 4.7660741806 4.1690802574 6.3162760735 492 19.6400000000 0.0082025258 0.0062176298 0.0091248276 0.0079076381 0.1081750000 0.0086000000 0.0470300000 0.0000290000 0.0003120000 0.0394050000 8868416 96830484 1770184704 4.7663903236 4.1695938110 6.3046097755 493 19.6800000000 0.0081422776 0.0062215338 0.0091248276 0.0079049283 0.1493030000 0.0115540000 0.0454640000 0.0003200000 0.0002720000 0.0805080000 8870090 96830484 1768669184 4.7684078217 4.1687703133 6.2935991287 494 19.7200000000 0.0080071427 0.0062251484 0.0091248276 0.0079063777 0.1071390000 0.0084830000 0.0401810000 0.0000270000 0.0003130000 0.0421850000 8871764 96830484 1770496000 4.7697653770 4.1637325287 6.2863707542 495 19.7600000000 0.0080401199 0.0062288150 0.0091248276 0.0078997611 0.1409180000 0.0096880000 0.0696920000 0.0003130000 0.0003450000 0.0446990000 8873438 96830484 1769431040 4.7695794106 4.1607990265 6.2757663727 496 19.8000000000 0.0080954367 0.0062325783 0.0091248276 0.0078958759 0.0958050000 0.0088920000 0.0387460000 0.0000290000 0.0003870000 0.0421390000 8875112 96830484 1771241472 4.7682247162 4.1609854698 6.2685170174 497 19.8400000000 0.0080364430 0.0062362079 0.0091248276 0.0078883690 0.1664230000 0.0099310000 0.0511930000 0.0003140000 0.0003570000 0.0991720000 8876786 96830484 1769938944 4.7715392113 4.1578769684 6.2622261047 498 19.8800000000 0.0080840085 0.0062399183 0.0091248276 0.0078816611 0.1093400000 0.0104150000 0.0462590000 0.0000430000 0.0003140000 0.0408730000 8878460 96830484 1768435712 4.7698273659 4.1567969322 6.2512578964 499 19.9200000000 0.0081665991 0.0062437794 0.0091248276 0.0078738213 0.1264450000 0.0084930000 0.0468630000 0.0003220000 0.0003530000 0.0524280000 8880134 96830484 1770090496 4.7707967758 4.1555738449 6.2446904182 500 19.9600000000 0.0081649562 0.0062476217 0.0091248276 0.0078661778 0.1105460000 0.0101880000 0.0470130000 0.0000960000 0.0003110000 0.0404980000 8881808 96830484 1769066496 4.7706308365 4.1542019844 6.2343931198 501 20.0000000000 0.0082508260 0.0062516201 0.0091248276 0.0078590283 0.1488560000 0.0085210000 0.0531970000 0.0003060000 0.0002720000 0.0809920000 8883482 96830484 1770876928 4.7715206146 4.1525301933 6.2237458229 502 20.0400000000 0.0081566572 0.0062554150 0.0091248276 0.0078512834 0.1078870000 0.0099610000 0.0388950000 0.0000280000 0.0002980000 0.0434210000 8885156 96830484 1769320448 4.7748022079 4.1500973701 6.2177481651 503 20.0800000000 0.0081074219 0.0062590970 0.0091248276 0.0078445984 0.1512980000 0.0080660000 0.0790560000 0.0003850000 0.0002820000 0.0578780000 8886830 96830484 1770983424 4.7768740654 4.1501927376 6.2049226761 504 20.1200000000 0.0082589015 0.0062630648 0.0091248276 0.0078377278 0.1514640000 0.0102910000 0.0908260000 0.0000060000 0.0000590000 0.0446470000 8888504 96830484 1769447424 4.7755432129 4.1470942497 6.1943550110 505 20.1600000000 0.0082028415 0.0062669060 0.0091248276 0.0078334163 0.1806460000 0.0080110000 0.0619670000 0.0002960000 0.0003550000 0.0991110000 8890178 96830484 1771110400 4.7714753151 4.1451792717 6.1814327240 506 20.2000000000 0.0084551731 0.0062712306 0.0091248276 0.0078300980 0.1276960000 0.0102560000 0.0597840000 0.0000250000 0.0003650000 0.0411280000 8891852 96830484 1770192896 4.7707986832 4.1480183601 6.1724371910 507 20.2400000000 0.0084755328 0.0062755783 0.0091248276 0.0078287311 0.1119460000 0.0103650000 0.0454620000 0.0003210000 0.0003320000 0.0499470000 8893526 96830484 1768542208 4.7710099220 4.1490449905 6.1611094475 508 20.2800000000 0.0083852448 0.0062797312 0.0091248276 0.0078340143 0.1068030000 0.0083300000 0.0484690000 0.0000270000 0.0003130000 0.0405880000 8895200 96830484 1770344448 4.7636642456 4.1464610100 6.1515374184 509 20.3200000000 0.0083901798 0.0062838775 0.0091248276 0.0078279331 0.1458020000 0.0105080000 0.0480180000 0.0003200000 0.0003580000 0.0810520000 8896874 96830484 1769304064 4.7673454285 4.1452794075 6.1419496536 510 20.3600000000 0.0084405821 0.0062881063 0.0091248276 0.0078205331 0.1111720000 0.0082090000 0.0470430000 0.0000240000 0.0006300000 0.0436090000 8898548 96830484 1771114496 4.7717442513 4.1464495659 6.1270852089 511 20.4000000000 0.0084531428 0.0062923432 0.0091248276 0.0078139889 0.1465050000 0.0099510000 0.0679500000 0.0002910000 0.0003430000 0.0455770000 8900222 96830484 1769811968 4.7746162415 4.1503448486 6.1147460938 512 20.4400000000 0.0084902244 0.0062966359 0.0091248276 0.0078253246 0.1293580000 0.0101870000 0.0596400000 0.0000250000 0.0003000000 0.0414330000 8901896 96830484 1768177664 4.7712583542 4.1509542465 6.1018142700 513 20.4800000000 0.0085965302 0.0063011192 0.0091248276 0.0078320194 0.1499100000 0.0083210000 0.0405230000 0.0002870000 0.0002620000 0.0864610000 8944530 96830484 1769922560 4.7759838104 4.1494646072 6.0905861855 514 20.5200000000 0.0086431094 0.0063056756 0.0091248276 0.0078261261 0.1095260000 0.0100870000 0.0477530000 0.0000280000 0.0003160000 0.0411510000 9030172 96830484 1768943616 4.7774472237 4.1510152817 6.0789952278 515 20.5600000000 0.0086761015 0.0063102783 0.0091248276 0.0078259353 0.1123380000 0.0085650000 0.0475460000 0.0006500000 0.0003530000 0.0495970000 9031846 96830484 1770586112 4.7827095985 4.1531977654 6.0666203499 516 20.6000000000 0.0087394258 0.0063149860 0.0091248276 0.0078358094 0.1066440000 0.0104250000 0.0479200000 0.0000230000 0.0003810000 0.0415040000 9033520 96830484 1769304064 4.7856016159 4.1524052620 6.0530424118 517 20.6400000000 0.0087875025 0.0063197684 0.0091248276 0.0078390318 0.1464880000 0.0082380000 0.0495520000 0.0003120000 0.0002740000 0.0824360000 9035194 96830484 1770983424 4.7813134193 4.1500859261 6.0541949272 518 20.6800000000 0.0086786440 0.0063243222 0.0091248276 0.0078317229 0.1284290000 0.0098920000 0.0599220000 0.0000270000 0.0003540000 0.0426500000 9036868 96830484 1769684992 4.7955560684 4.1502346992 6.0333909988 519 20.7200000000 0.0087778755 0.0063290497 0.0091248276 0.0078253805 0.1286850000 0.0103150000 0.0483130000 0.0003170000 0.0002730000 0.0538000000 9038542 96830484 1768161280 4.7864699364 4.1530151367 6.0374965668 520 20.7600000000 0.0088110706 0.0063338228 0.0091248276 0.0078297119 0.1301090000 0.0086890000 0.0674110000 0.0000240000 0.0002930000 0.0431420000 9040216 96830484 1769984000 4.7794098854 4.1548037529 6.0376725197 521 20.8000000000 0.0087059606 0.0063383758 0.0091248276 0.0078436613 0.1477220000 0.0098910000 0.0481330000 0.0003160000 0.0002800000 0.0833570000 9041890 96830484 1768906752 4.7771100998 4.1526098251 6.0300984383 522 20.8400000000 0.0087897535 0.0063430720 0.0091248276 0.0078406583 0.1088270000 0.0083340000 0.0447500000 0.0000280000 0.0003180000 0.0432550000 9043564 96830484 1770708992 4.7787585258 4.1489958763 6.0235314369 523 20.8800000000 0.0087277377 0.0063476316 0.0091248276 0.0078337680 0.1112170000 0.0102420000 0.0413000000 0.0003480000 0.0002710000 0.0533300000 9045238 96830484 1769684992 4.7683744431 4.1477708817 6.0292835236 524 20.9200000000 0.0087732831 0.0063522607 0.0091248276 0.0078296809 0.1082800000 0.0100420000 0.0479600000 0.0000250000 0.0003790000 0.0440990000 9046912 96830484 1768181760 4.7851705551 4.1480956078 6.0077319145 525 20.9600000000 0.0086944802 0.0063567220 0.0091248276 0.0078222297 0.1648260000 0.0082100000 0.0413660000 0.0002960000 0.0002760000 0.0915670000 9048586 96830484 1769820160 4.7849416733 4.1473665237 6.0027570724 526 21.0000000000 0.0086199492 0.0063610248 0.0091248276 0.0078152151 0.1123650000 0.0100200000 0.0472810000 0.0000270000 0.0023240000 0.0446480000 9050260 96830484 1768796160 4.7929105759 4.1438097954 5.9897661209 527 21.0400000000 0.0086334758 0.0063653368 0.0091248276 0.0078157123 0.1280850000 0.0080080000 0.0545270000 0.0002930000 0.0005300000 0.0557240000 9051934 96830484 1770582016 4.7939748764 4.1443147659 5.9806618690 528 21.0800000000 0.0087508820 0.0063698549 0.0091248276 0.0078085015 0.1099610000 0.0100600000 0.0480950000 0.0000260000 0.0003090000 0.0450640000 9053608 96830484 1769541632 4.7966613770 4.1438794136 5.9758605957 529 21.1200000000 0.0086401263 0.0063741465 0.0091248276 0.0078020439 0.1655150000 0.0083160000 0.0478330000 0.0003230000 0.0003520000 0.0902320000 9055282 96830484 1771257856 4.8098835945 4.1417546272 5.9553022385 530 21.1600000000 0.0086369449 0.0063784159 0.0091248276 0.0077973892 0.1302520000 0.0105630000 0.0605270000 0.0000300000 0.0003090000 0.0463390000 9056956 96830484 1769938944 4.8064675331 4.1419701576 5.9535174370 531 21.2000000000 0.0087306565 0.0063828458 0.0091248276 0.0077907437 0.1300460000 0.0103000000 0.0477450000 0.0003820000 0.0002870000 0.0582740000 9058630 96830484 1768415232 4.8145346642 4.1408867836 5.9383497238 532 21.2400000000 0.0087214550 0.0063872417 0.0091248276 0.0077846628 0.1124300000 0.0084290000 0.0535730000 0.0000290000 0.0003020000 0.0441800000 9060304 96830484 1770237952 4.8149757385 4.1395254135 5.9302887917 533 21.2800000000 0.0086651528 0.0063915154 0.0091248276 0.0077786148 0.1500750000 0.0102100000 0.0406260000 0.0003040000 0.0003610000 0.0927900000 9061978 96830484 1768923136 4.8135566711 4.1384706497 5.9252114296 534 21.3200000000 0.0087866308 0.0063960006 0.0091248276 0.0077738355 0.1072870000 0.0087510000 0.0480460000 0.0000260000 0.0003040000 0.0441920000 9063652 96830484 1770602496 4.8208560944 4.1369171143 5.9098534584 535 21.3600000000 0.0087555191 0.0064004110 0.0091248276 0.0077697135 0.1249720000 0.0108200000 0.0406240000 0.0001150000 0.0001010000 0.0626970000 9065326 96830484 1769287680 4.8265309334 4.1390762329 5.8949880600 536 21.4000000000 0.0087351520 0.0064047668 0.0091248276 0.0077633644 0.1307230000 0.0080270000 0.0582200000 0.0000290000 0.0003750000 0.0581310000 9067000 96830484 1771130880 4.8240971565 4.1382265091 5.8911051750 537 21.4400000000 0.0089759314 0.0064095548 0.0091248276 0.0077562261 0.1852920000 0.0100040000 0.0571220000 0.0003130000 0.0003520000 0.1010930000 9068674 96830484 1769811968 4.8318753242 4.1367530823 5.8738627434 538 21.4800000000 0.0089796279 0.0064143319 0.0091248276 0.0077492251 0.1109960000 0.0102510000 0.0413820000 0.0000280000 0.0003570000 0.0511300000 9070348 96830484 1768288256 4.8320097923 4.1367077827 5.8656244278 539 21.5200000000 0.0091936821 0.0064194884 0.0091936821 0.0077421646 0.1719960000 0.0081180000 0.0920110000 0.0000610000 0.0000540000 0.0644020000 9072022 96830484 1770094592 4.8303127289 4.1364436150 5.8576221466 540 21.5600000000 0.0093980907 0.0064250043 0.0093980907 0.0077360879 0.1440510000 0.0096250000 0.0602900000 0.0000280000 0.0003200000 0.0602960000 9073696 96830484 1768685568 4.8334670067 4.1376681328 5.8429651260 541 21.6000000000 0.0092131430 0.0064301580 0.0093980907 0.0077293434 0.1869880000 0.0078970000 0.0690150000 0.0004400000 0.0002860000 0.1031310000 9075370 96830484 1770557440 4.8340020180 4.1393089294 5.8336949348 542 21.6400000000 0.0090999780 0.0064350839 0.0093980907 0.0077270901 0.1268070000 0.0108480000 0.0542760000 0.0000270000 0.0003100000 0.0495970000 9077044 96830484 1769177088 4.8363804817 4.1373591423 5.8208937645 543 21.6800000000 0.0091091339 0.0064400085 0.0093980907 0.0077200698 0.1290520000 0.0086730000 0.0484290000 0.0003210000 0.0003450000 0.0607940000 9078718 96830484 1770987520 4.8373413086 4.1347861290 5.8156175613 544 21.7200000000 0.0092120450 0.0064451041 0.0093980907 0.0077198831 0.1268770000 0.0103970000 0.0489150000 0.0000280000 0.0003170000 0.0503070000 9080392 96830484 1769684992 4.8379249573 4.1356096268 5.8053717613 545 21.7600000000 0.0094136735 0.0064505510 0.0094136735 0.0077164969 0.1559710000 0.0086410000 0.0471920000 0.0003880000 0.0002810000 0.0933780000 9082066 96830484 1771368448 4.8407592773 4.1342177391 5.7932038307 546 21.8000000000 0.0094666556 0.0064560750 0.0094666556 0.0077209185 0.1401030000 0.0109680000 0.0566580000 0.0000290000 0.0003040000 0.0509490000 9083740 96830484 1770065920 4.8422384262 4.1348981857 5.7865400314 547 21.8400000000 0.0095789405 0.0064617841 0.0095789405 0.0077189197 0.1315480000 0.0105130000 0.0484100000 0.0003190000 0.0002750000 0.0621400000 9085414 96830484 1768574976 4.8442440033 4.1368021965 5.7747836113 548 21.8800000000 0.0095372852 0.0064673964 0.0095789405 0.0077120100 0.1271370000 0.0083590000 0.0500170000 0.0000280000 0.0003340000 0.0515040000 9087088 96830484 1770176512 4.8409271240 4.1370639801 5.7714886665 549 21.9200000000 0.0091417870 0.0064722677 0.0095789405 0.0077054234 0.1701280000 0.0101520000 0.0500920000 0.0003370000 0.0002900000 0.0992340000 9088762 96830484 1769320448 4.8420429230 4.1360564232 5.7651767731 550 21.9600000000 0.0092780814 0.0064773692 0.0095789405 0.0076990742 0.1099960000 0.0084530000 0.0416750000 0.0000270000 0.0003040000 0.0532410000 9090436 96830484 1771003904 4.8416042328 4.1383428574 5.7582731247 551 22.0000000000 0.0093954476 0.0064826652 0.0095789405 0.0076933996 0.1656670000 0.0099680000 0.0685110000 0.0003930000 0.0002770000 0.0707480000 9092110 96830484 1769701376 4.8420934677 4.1383938789 5.7502312660 552 22.0400000000 0.0097348522 0.0064885568 0.0097348522 0.0076866272 0.1496050000 0.0096200000 0.0645190000 0.0000270000 0.0003190000 0.0638690000 9093784 96830484 1768161280 4.8454060555 4.1400256157 5.7418951988 553 22.0800000000 0.0097717522 0.0064944939 0.0097717522 0.0076831523 0.2258870000 0.0079240000 0.0841080000 0.0003130000 0.0003590000 0.1093040000 9095458 96830484 1769840640 4.8439793587 4.1400651932 5.7395195961 554 22.1200000000 0.0095392745 0.0064999899 0.0097717522 0.0076772135 0.1135780000 0.0101730000 0.0467310000 0.0000290000 0.0003110000 0.0500660000 9097132 96830484 1768652800 4.8443565369 4.1382212639 5.7326464653 555 22.1600000000 0.0095150741 0.0065054225 0.0097717522 0.0076709048 0.1277450000 0.0085720000 0.0481830000 0.0004030000 0.0002770000 0.0634970000 9098806 96830484 1770336256 4.8451075554 4.1407132149 5.7244834900 556 22.2000000000 0.0100272037 0.0065117566 0.0100272037 0.0076671272 0.1261460000 0.0103860000 0.0478640000 0.0000260000 0.0003080000 0.0528890000 9100480 96830484 1768812544 4.8449268341 4.1436815262 5.7156171799 557 22.2400000000 0.0101558128 0.0065182989 0.0101558128 0.0076747445 0.1558770000 0.0086310000 0.0386880000 0.0003020000 0.0002800000 0.1015910000 9102154 96830484 1770496000 4.8444442749 4.1410717964 5.7114362717 558 22.2800000000 0.0102522764 0.0065249906 0.0102522764 0.0076680031 0.1219980000 0.0111920000 0.0421330000 0.0000270000 0.0003560000 0.0571350000 9103828 96830484 1769320448 4.8424096107 4.1385917664 5.7054080963 559 22.3200000000 0.0100625455 0.0065313190 0.0102522764 0.0076632787 0.1479190000 0.0079950000 0.0457990000 0.0003130000 0.0002830000 0.0793560000 9105502 96830484 1771003904 4.8419017792 4.1408109665 5.7001333237 560 22.3600000000 0.0102595342 0.0065379765 0.0102595342 0.0076576538 0.1516290000 0.0096780000 0.0775980000 0.0000300000 0.0003070000 0.0576020000 9107176 96830484 1769701376 4.8406715393 4.1408762932 5.6966967583 561 22.4000000000 0.0104542449 0.0065449574 0.0104542449 0.0076517816 0.2045150000 0.0097270000 0.0495460000 0.0003140000 0.0002710000 0.1258530000 9108850 96830484 1768144896 4.8440914154 4.1399617195 5.6882314682 562 22.4400000000 0.0109158065 0.0065527347 0.0109158065 0.0076451830 0.1126650000 0.0086380000 0.0458740000 0.0000320000 0.0003080000 0.0514630000 9110524 96830484 1769967616 4.8425941467 4.1417274475 5.6850028038 563 22.4800000000 0.0110149700 0.0065606605 0.0110149700 0.0076408441 0.1278780000 0.0100510000 0.0412440000 0.0003600000 0.0002810000 0.0693120000 9112198 96830484 1768796160 4.8447847366 4.1417841911 5.6756644249 564 22.5200000000 0.0108814258 0.0065683214 0.0110149700 0.0076375933 0.1258910000 0.0075240000 0.0406430000 0.0000300000 0.0002990000 0.0613130000 9113872 96830484 1770590208 4.8449993134 4.1396546364 5.6699733734 565 22.5600000000 0.0108505245 0.0065759006 0.0110149700 0.0076309201 0.1847180000 0.0101450000 0.0559080000 0.0003270000 0.0002720000 0.1116480000 9115546 96830484 1769066496 4.8483452797 4.1370759010 5.6585240364 566 22.6000000000 0.0110975625 0.0065838894 0.0110975625 0.0076257732 0.1265720000 0.0102830000 0.0486380000 0.0000250000 0.0002980000 0.0547690000 9117220 96830484 1770749952 4.8491635323 4.1363501549 5.6516737938 567 22.6400000000 0.0110822199 0.0065918229 0.0110975625 0.0076198544 0.1296470000 0.0103690000 0.0393040000 0.0003780000 0.0002800000 0.0698930000 9118894 96830484 1769431040 4.8505392075 4.1357874870 5.6452660561 568 22.6800000000 0.0113063157 0.0066001231 0.0113063157 0.0076134259 0.1484410000 0.0077810000 0.0679210000 0.0000360000 0.0003220000 0.0619190000 9120568 96830484 1771257856 4.8528070450 4.1338176727 5.6363215446 569 22.7200000000 0.0115867658 0.0066088870 0.0115867658 0.0076090206 0.2256040000 0.0096770000 0.0691510000 0.0003860000 0.0002810000 0.1228870000 9122242 96830484 1769955328 4.8549494743 4.1324548721 5.6257243156 570 22.7600000000 0.0117673203 0.0066179368 0.0117673203 0.0076053441 0.1127280000 0.0101810000 0.0417430000 0.0000240000 0.0002880000 0.0541660000 9123916 96830484 1768452096 4.8538489342 4.1351346970 5.6158084869 571 22.8000000000 0.0118031679 0.0066270178 0.0118031679 0.0076001470 0.1289960000 0.0084640000 0.0502810000 0.0003150000 0.0003500000 0.0629050000 9125590 96830484 1770110976 4.8525762558 4.1364488602 5.6073198318 572 22.8400000000 0.0120234694 0.0066364522 0.0120234694 0.0075982273 0.1251520000 0.0105190000 0.0398490000 0.0000250000 0.0002880000 0.0580090000 9127264 96830484 1768796160 4.8525247574 4.1326332092 5.5987730026 573 22.8800000000 0.0114819678 0.0066449086 0.0120234694 0.0075937198 0.1812780000 0.0078310000 0.0643150000 0.0000620000 0.0000540000 0.1021940000 9128938 96830484 1770446848 4.8516178131 4.1319522858 5.5901408195 574 22.9200000000 0.0111094201 0.0066526865 0.0120234694 0.0075871798 0.1270580000 0.0143440000 0.0412250000 0.0000280000 0.0011220000 0.0546160000 9130612 96830484 1769320448 4.8487348557 4.1332368851 5.5837264061 575 22.9600000000 0.0106472438 0.0066596335 0.0120234694 0.0075823730 0.1307730000 0.0086230000 0.0485300000 0.0003540000 0.0002690000 0.0650980000 9132286 96830484 1771003904 4.8473834991 4.1297736168 5.5744400024 576 23.0000000000 0.0106896451 0.0066666301 0.0120234694 0.0075775987 0.1273820000 0.0102550000 0.0496680000 0.0000290000 0.0003910000 0.0541080000 9133960 96830484 1769701376 4.8464598656 4.1263008118 5.5671644211 577 23.0400000000 0.0107573466 0.0066737197 0.0120234694 0.0075788200 0.1601150000 0.0102740000 0.0406000000 0.0002880000 0.0003360000 0.1021560000 9135634 96830484 1768177664 4.8451123238 4.1279835701 5.5576243401 578 23.0800000000 0.0109157283 0.0066810588 0.0120234694 0.0075722736 0.1154750000 0.0096640000 0.0430580000 0.0000240000 0.0010510000 0.0551410000 9137308 96830484 1769820160 4.8441662788 4.1274762154 5.5480494499 579 23.1200000000 0.0108747091 0.0066883017 0.0120234694 0.0075658238 0.1281100000 0.0099500000 0.0401360000 0.0002920000 0.0002650000 0.0688210000 9138982 96830484 1768960000 4.8436036110 4.1246953011 5.5389280319 580 23.1600000000 0.0111034112 0.0066959140 0.0120234694 0.0075609378 0.1481040000 0.0077700000 0.0717450000 0.0000270000 0.0002940000 0.0569470000 9140656 96830484 1770557440 4.8429918289 4.1238946915 5.5285820961 581 23.2000000000 0.0109791821 0.0067032862 0.0120234694 0.0075547483 0.2056400000 0.0098030000 0.0518330000 0.0003170000 0.0003580000 0.1194150000 9142330 96830484 1769558016 4.8414144516 4.1239824295 5.5192971230 582 23.2400000000 0.0109285833 0.0067105462 0.0120234694 0.0075487238 0.1140430000 0.0084780000 0.0481800000 0.0000290000 0.0003920000 0.0504150000 9144004 96830484 1771114496 4.8400149345 4.1217613220 5.5082345009 583 23.2800000000 0.0111092208 0.0067180911 0.0120234694 0.0075426957 0.1272440000 0.0103730000 0.0398710000 0.0001180000 0.0001050000 0.0688060000 9145678 96830484 1769828352 4.8399586678 4.1185960770 5.4986939430 584 23.3200000000 0.0113302721 0.0067259886 0.0120234694 0.0075431738 0.1468080000 0.0097360000 0.0499240000 0.0000290000 0.0003950000 0.0718960000 9147352 96830484 1768177664 4.8379058838 4.1192560196 5.4873566628 585 23.3600000000 0.0114375902 0.0067340427 0.0120234694 0.0075380971 0.2099410000 0.0078610000 0.0678210000 0.0003140000 0.0002740000 0.1231740000 9149026 96830484 1769967616 4.8366322517 4.1185698509 5.4759197235 586 23.4000000000 0.0115266116 0.0067422211 0.0120234694 0.0075339081 0.1120270000 0.0101990000 0.0414220000 0.0000270000 0.0003150000 0.0531340000 9150700 96830484 1768779776 4.8362703323 4.1153521538 5.4647641182 587 23.4400000000 0.0115992622 0.0067504955 0.0120234694 0.0075380636 0.1452120000 0.0078330000 0.0460620000 0.0003270000 0.0002730000 0.0822540000 9152374 96830484 1770459136 4.8348550797 4.1148691177 5.4551963806 588 23.4800000000 0.0118405782 0.0067591521 0.0120234694 0.0075458947 0.1486700000 0.0098490000 0.0684160000 0.0000280000 0.0003150000 0.0611860000 9154048 96830484 1769193472 4.8321790695 4.1171360016 5.4275679588 589 23.5200000000 0.0118931178 0.0067678685 0.0120234694 0.0075401401 0.1897250000 0.0079270000 0.0552570000 0.0003060000 0.0002810000 0.1193500000 9155722 96830484 1770876928 4.8303127289 4.1186265945 5.4176855087 590 23.5600000000 0.0120582636 0.0067768352 0.0120582636 0.0075376666 0.1104540000 0.0109210000 0.0410310000 0.0000280000 0.0002990000 0.0516010000 9157396 96830484 1769684992 4.8280000687 4.1204538345 5.4060840607 591 23.6000000000 0.0120657636 0.0067857844 0.0120657636 0.0075418816 0.1253870000 0.0096170000 0.0349130000 0.0003090000 0.0003560000 0.0709220000 9159070 96830484 1768050688 4.8267989159 4.1181788445 5.3948574066 592 23.6400000000 0.0121659962 0.0067948726 0.0121659962 0.0075357803 0.1298170000 0.0079450000 0.0611290000 0.0000280000 0.0003030000 0.0536160000 9160744 96830484 1769713664 4.8257064819 4.1156754494 5.3807339668 593 23.6800000000 0.0122684296 0.0068041028 0.0122684296 0.0075314720 0.1724990000 0.0094180000 0.0469470000 0.0003080000 0.0003470000 0.1087700000 9162418 96830484 1768816640 4.8238992691 4.1156573296 5.3681468964 594 23.7200000000 0.0124301882 0.0068135744 0.0124301882 0.0075272741 0.1608040000 0.0088790000 0.0816360000 0.0000070000 0.0000580000 0.0527390000 9164092 96830484 1770446848 4.8224272728 4.1156740189 5.3562045097 595 23.7600000000 0.0122766038 0.0068227559 0.0124301882 0.0075240871 0.1296600000 0.0102910000 0.0423480000 0.0003090000 0.0002700000 0.0628580000 9165766 96830484 1769320448 4.8198118210 4.1146378517 5.3472561836 596 23.8000000000 0.0122691244 0.0068318941 0.0124301882 0.0075233464 0.1112870000 0.0085480000 0.0455770000 0.0000290000 0.0003940000 0.0500410000 9167440 96830484 1770987520 4.8180265427 4.1159672737 5.3342776299 597 23.8400000000 0.0123792300 0.0068411861 0.0124301882 0.0075173072 0.1657470000 0.0103810000 0.0448190000 0.0003900000 0.0002840000 0.0973700000 9169114 96830484 1769701376 4.8152709007 4.1177415848 5.3236622810 598 23.8800000000 0.0125074890 0.0068506616 0.0125074890 0.0075118955 0.1124690000 0.0101040000 0.0456690000 0.0000270000 0.0003850000 0.0494990000 9170788 96830484 1768050688 4.8135957718 4.1176447868 5.3098974228 599 23.9200000000 0.0124597894 0.0068600257 0.0125074890 0.0075060412 0.1254780000 0.0081720000 0.0421350000 0.0003110000 0.0003430000 0.0662010000 9172462 96830484 1769795584 4.8105645180 4.1196470261 5.2997112274 600 23.9600000000 0.0127240382 0.0068697991 0.0127240382 0.0075031175 0.1475050000 0.0095060000 0.0585560000 0.0000880000 0.0002970000 0.0657270000 9174136 96830484 1768796160 4.8085494041 4.1199908257 5.2883105278 601 24.0000000000 0.0126939081 0.0068794898 0.0127240382 0.0074975172 0.1864590000 0.0077220000 0.0550150000 0.0005430000 0.0019470000 0.1005970000 9175810 96830484 1770573824 4.8055071831 4.1201095581 5.2780213356 602 24.0400000000 0.0127628166 0.0068892627 0.0127628166 0.0074913713 0.1128900000 0.0104990000 0.0456600000 0.0000290000 0.0003820000 0.0494920000 9177484 96830484 1769574400 4.8035044670 4.1201486588 5.2653918266 603 24.0800000000 0.0127111915 0.0068989177 0.0127628166 0.0074851950 0.1265010000 0.0084940000 0.0437610000 0.0009640000 0.0005790000 0.0605560000 9179158 96830484 1771257856 4.8000788689 4.1204652786 5.2564873695 604 24.1200000000 0.0126210703 0.0069083914 0.0127628166 0.0074789965 0.1103030000 0.0102350000 0.0381280000 0.0000300000 0.0003030000 0.0547630000 9180832 96830484 1770336256 4.7967057228 4.1212468147 5.2485675812 605 24.1600000000 0.0124577666 0.0069175640 0.0127628166 0.0074731794 0.1872190000 0.0099690000 0.0550760000 0.0003770000 0.0002850000 0.1105030000 9182506 96830484 1768796160 4.7938346863 4.1201572418 5.2399396896 606 24.2000000000 0.0124077890 0.0069266237 0.0127628166 0.0074672165 0.1059890000 0.0084970000 0.0381780000 0.0000280000 0.0002960000 0.0520880000 9184180 96830484 1770618880 4.7913460732 4.1177096367 5.2324104309 607 24.2400000000 0.0123958327 0.0069356340 0.0127628166 0.0074614925 0.1683510000 0.0097500000 0.0604490000 0.0003140000 0.0002850000 0.0905800000 9185854 96830484 1769574400 4.7891721725 4.1171121597 5.2196855545 608 24.2800000000 0.0124336425 0.0069446767 0.0127628166 0.0074557216 0.1460930000 0.0078830000 0.0590390000 0.0000290000 0.0003680000 0.0636250000 9187528 96830484 1771347968 4.7860875130 4.1186375618 5.2109289169 609 24.3200000000 0.0124151176 0.0069536594 0.0127628166 0.0074514587 0.1809300000 0.0101170000 0.0680740000 0.0003070000 0.0003550000 0.0950830000 9189202 96830484 1769955328 4.7844367027 4.1158537865 5.2018961906 610 24.3600000000 0.0127007607 0.0069630809 0.0127628166 0.0074456483 0.1156710000 0.0132580000 0.0457190000 0.0000310000 0.0003710000 0.0492690000 9190876 96830484 1768562688 4.7824163437 4.1120834351 5.1934227943 611 24.4000000000 0.0127362516 0.0069725296 0.0127628166 0.0074441592 0.1262840000 0.0087740000 0.0439420000 0.0003810000 0.0002850000 0.0590630000 9192550 96830484 1770237952 4.7810468674 4.1113672256 5.1798610687 612 24.4400000000 0.0127452640 0.0069819622 0.0127628166 0.0074392557 0.1106880000 0.0104700000 0.0437260000 0.0001010000 0.0005270000 0.0488030000 9194224 96830484 1768796160 4.7781620026 4.1117529869 5.1706047058 613 24.4800000000 0.0127890650 0.0069914354 0.0127890650 0.0074338981 0.1489850000 0.0089070000 0.0445390000 0.0003150000 0.0006490000 0.0876770000 9195898 96830484 1770622976 4.7759990692 4.1098341942 5.1632413864 614 24.5200000000 0.0129290847 0.0070011059 0.0129290847 0.0074279398 0.1084130000 0.0107070000 0.0428710000 0.0000260000 0.0002960000 0.0474310000 9197572 96830484 1769066496 4.7741532326 4.1075186729 5.1499814987 615 24.5600000000 0.0129481684 0.0070107759 0.0129481684 0.0074222704 0.1264660000 0.0084820000 0.0466360000 0.0003170000 0.0003540000 0.0585980000 9199246 96830484 1770729472 4.7727689743 4.1062159538 5.1416497231 616 24.6000000000 0.0130404197 0.0070205643 0.0130404197 0.0074171062 0.1266880000 0.0107350000 0.0463650000 0.0000260000 0.0003150000 0.0489960000 9200920 96830484 1769193472 4.7712531090 4.1034317017 5.1305079460 617 24.6400000000 0.0130523136 0.0070303402 0.0130523136 0.0074161152 0.1494540000 0.0087630000 0.0456900000 0.0003210000 0.0002750000 0.0872490000 9202594 96830484 1770856448 4.7693428993 4.1018643379 5.1196284294 618 24.6800000000 0.0132277505 0.0070403684 0.0132277505 0.0074163843 0.1107520000 0.0106230000 0.0434840000 0.0000270000 0.0009840000 0.0486000000 9204268 96830484 1769955328 4.7682404518 4.1001663208 5.1066875458 619 24.7200000000 0.0130799143 0.0070501253 0.0132277505 0.0074178126 0.1268270000 0.0103970000 0.0467890000 0.0003220000 0.0002770000 0.0572270000 9205942 96830484 1768288256 4.7670531273 4.0992817879 5.0915479660 620 24.7600000000 0.0132105090 0.0070600614 0.0132277505 0.0074150581 0.1093160000 0.0084060000 0.0435210000 0.0000280000 0.0010510000 0.0479710000 9207616 96830484 1770110976 4.7641448975 4.1002359390 5.0825390816 621 24.8000000000 0.0132454624 0.0070700218 0.0132454624 0.0074092121 0.1463960000 0.0107500000 0.0426790000 0.0008450000 0.0002930000 0.0847150000 9209290 96830484 1768812544 4.7624368668 4.0997161865 5.0722036362 622 24.8400000000 0.0131339347 0.0070797709 0.0132454624 0.0074034822 0.1124720000 0.0087830000 0.0523050000 0.0000270000 0.0002840000 0.0440940000 9210964 96830484 1770602496 4.7605314255 4.0975975990 5.0613856316 623 24.8800000000 0.0134852519 0.0070900525 0.0134852519 0.0074008803 0.1259460000 0.0105090000 0.0457270000 0.0003270000 0.0003470000 0.0563200000 9212638 96830484 1769320448 4.7582097054 4.0983633995 5.0503821373 624 24.9200000000 0.0136501333 0.0071005655 0.0136501333 0.0073955632 0.1095340000 0.0087770000 0.0441180000 0.0000270000 0.0003200000 0.0475480000 9214312 96830484 1771003904 4.7552542686 4.0992584229 5.0390863419 625 24.9600000000 0.0137903979 0.0071112692 0.0137903979 0.0073897757 0.1456820000 0.0109330000 0.0426990000 0.0010500000 0.0002750000 0.0834170000 9215986 96830484 1769701376 4.7524709702 4.0976781845 5.0290341377 626 25.0000000000 0.0138315009 0.0071220044 0.0138315009 0.0073847096 0.1127180000 0.0102930000 0.0460150000 0.0000300000 0.0002940000 0.0488490000 9217660 96830484 1768198144 4.7505235672 4.0956835747 5.0197148323 627 25.0400000000 0.0139297172 0.0071328620 0.0139297172 0.0073815561 0.1451990000 0.0082760000 0.0507250000 0.0003680000 0.0002760000 0.0681750000 9219334 96830484 1769795584 4.7477254868 4.0953450203 5.0092868805 628 25.0800000000 0.0138479555 0.0071435548 0.0139297172 0.0073759498 0.1295980000 0.0100070000 0.0609330000 0.0000250000 0.0002990000 0.0471930000 9221008 96830484 1768689664 4.7439031601 4.0972547531 4.9998850822 629 25.1200000000 0.0138677983 0.0071542452 0.0139297172 0.0073726137 0.1520700000 0.0085970000 0.0533450000 0.0005410000 0.0002950000 0.0821610000 9222682 96830484 1770332160 4.7413043976 4.0965652466 4.9936246872 630 25.1600000000 0.0139881615 0.0071650927 0.0139881615 0.0073675122 0.1235380000 0.0110000000 0.0462990000 0.0000310000 0.0003440000 0.0488590000 9224356 96830484 1768939520 4.7373986244 4.0966119766 4.9841599464 631 25.2000000000 0.0138956644 0.0071757592 0.0139881615 0.0073639772 0.1334150000 0.0085400000 0.0656760000 0.0003040000 0.0006420000 0.0511350000 9226030 96830484 1770729472 4.7334280014 4.0974245071 4.9755687714 632 25.2400000000 0.0140492180 0.0071866349 0.0140492180 0.0073629160 0.1069120000 0.0110690000 0.0445560000 0.0000250000 0.0003830000 0.0437330000 9227704 96830484 1769574400 4.7296404839 4.0965461731 4.9698591232 633 25.2800000000 0.0136177251 0.0071967946 0.0140492180 0.0073589147 0.1433410000 0.0091010000 0.0462580000 0.0003140000 0.0002700000 0.0800390000 9229378 96830484 1771241472 4.7255887985 4.0975255966 4.9600515366 634 25.3200000000 0.0145225320 0.0072083494 0.0145225320 0.0073556442 0.1522170000 0.0111260000 0.0867850000 0.0000250000 0.0002860000 0.0445360000 9231052 96830484 1769938944 4.7204117775 4.0992050171 4.9509472847 635 25.3600000000 0.0144198742 0.0072197062 0.0145225320 0.0073583949 0.1456560000 0.0111550000 0.0604060000 0.0002940000 0.0002690000 0.0528500000 9232726 96830484 1768300544 4.7163805962 4.0990614891 4.9455409050 636 25.4000000000 0.0144641874 0.0072310968 0.0145225320 0.0073582983 0.1106650000 0.0094720000 0.0461960000 0.0000280000 0.0003130000 0.0440220000 9234400 96830484 1770110976 4.7129130363 4.0974206924 4.9363198280 637 25.4400000000 0.0145586887 0.0072426001 0.0145586887 0.0073531870 0.1670870000 0.0112510000 0.0585510000 0.0003580000 0.0002650000 0.0799760000 9236074 96830484 1769066496 4.7084288597 4.0978798866 4.9292545319 638 25.4800000000 0.0145440083 0.0072540443 0.0145586887 0.0073488817 0.1087150000 0.0095060000 0.0389300000 0.0000280000 0.0003060000 0.0457990000 9237748 96830484 1770856448 4.7051062584 4.0962061882 4.9213223457 639 25.5200000000 0.0147055322 0.0072657055 0.0147055322 0.0073432854 0.1540600000 0.0111560000 0.0755580000 0.0003900000 0.0002800000 0.0594050000 9239422 96830484 1769574400 4.6999769211 4.0941691399 4.9153952599 640 25.5600000000 0.0148764001 0.0072775972 0.0148764001 0.0073383117 0.1436340000 0.0112300000 0.0678440000 0.0000280000 0.0004310000 0.0474250000 9241096 96830484 1768144896 4.6958661079 4.0927925110 4.9091138840 641 25.6000000000 0.0148250721 0.0072893718 0.0148764001 0.0073332560 0.1678610000 0.0091350000 0.0525940000 0.0003070000 0.0002760000 0.0889790000 9242770 96830484 1769840640 4.6907806396 4.0917224884 4.9027447701 642 25.6400000000 0.0152110932 0.0073017109 0.0152110932 0.0073286892 0.1315290000 0.0120940000 0.0697240000 0.0000280000 0.0003110000 0.0419970000 9244444 96830484 1768415232 4.6854014397 4.0906405449 4.8974304199 643 25.6800000000 0.0151236812 0.0073138757 0.0152110932 0.0073232825 0.1253040000 0.0101760000 0.0456240000 0.0003290000 0.0003480000 0.0513980000 9246118 96830484 1770303488 4.6807289124 4.0890192986 4.8910331726 644 25.7200000000 0.0154662654 0.0073265347 0.0154662654 0.0073176902 0.1113200000 0.0124160000 0.0485970000 0.0000290000 0.0002900000 0.0425890000 9247792 96830484 1768939520 4.6750235558 4.0881175995 4.8857321739 645 25.7600000000 0.0155708371 0.0073393165 0.0155708371 0.0073122532 0.1655680000 0.0106520000 0.0623400000 0.0003030000 0.0003470000 0.0750330000 9249466 96830484 1770729472 4.6700453758 4.0861401558 4.8793950081 646 25.8000000000 0.0158476885 0.0073524874 0.0158476885 0.0073066386 0.1286040000 0.0121850000 0.0570960000 0.0000850000 0.0002900000 0.0427580000 9251140 96830484 1769447424 4.6636204720 4.0845589638 4.8751535416 647 25.8400000000 0.0159077831 0.0073657104 0.0159077831 0.0073010504 0.1294310000 0.0120280000 0.0546990000 0.0002980000 0.0002660000 0.0507790000 9252814 96830484 1767788544 4.6562781334 4.0850505829 4.8694906235 648 25.8800000000 0.0161299556 0.0073792355 0.0161299556 0.0072987810 0.1099180000 0.0103170000 0.0527940000 0.0000260000 0.0003630000 0.0390100000 9254488 96830484 1769594880 4.6495547295 4.0844373703 4.8649234772 649 25.9200000000 0.0161708612 0.0073927819 0.0161708612 0.0072975532 0.1623570000 0.0120790000 0.0687770000 0.0003100000 0.0002780000 0.0735180000 9256162 96830484 1768333312 4.6424446106 4.0814595222 4.8598580360 650 25.9600000000 0.0166279692 0.0074069899 0.0166279692 0.0072934451 0.1319730000 0.0100190000 0.0672850000 0.0000310000 0.0003710000 0.0417930000 9257836 96830484 1770057728 4.6283736229 4.0748348236 4.8508095741 651 26.0000000000 0.0171577297 0.0074219680 0.0171577297 0.0072945209 0.1275680000 0.0123830000 0.0481980000 0.0003170000 0.0002680000 0.0495510000 9259510 96830484 1768951808 4.6109142303 4.0750455856 4.8401536942 652 26.0400000000 0.0175521895 0.0074375051 0.0175521895 0.0072890671 0.1287780000 0.0106910000 0.0619710000 0.0000280000 0.0003520000 0.0410670000 9261184 96830484 1770594304 4.6015219688 4.0759072304 4.8340530396 653 26.0800000000 0.0176233854 0.0074531037 0.0176233854 0.0072860479 0.1538700000 0.0124990000 0.0623010000 0.0003500000 0.0002720000 0.0709690000 9262858 96830484 1769312256 4.5913105011 4.0787215233 4.8293747902 654 26.1200000000 0.0182895996 0.0074696733 0.0182895996 0.0072925011 0.1239660000 0.0104880000 0.0625500000 0.0000270000 0.0002820000 0.0406750000 9264532 96830484 1770946560 4.5809755325 4.0787234306 4.8252620697 655 26.1600000000 0.0188709423 0.0074870798 0.0188709423 0.0072880489 0.1295360000 0.0124810000 0.0615570000 0.0002990000 0.0002840000 0.0473460000 9266206 96830484 1769693184 4.5715160370 4.0763998032 4.8187212944 656 26.2000000000 0.0182792228 0.0075035312 0.0188709423 0.0072866575 0.1258480000 0.0119550000 0.0596160000 0.0000280000 0.0002910000 0.0403920000 9267880 96830484 1768206336 4.5606975555 4.0769572258 4.8153972626 657 26.2400000000 0.0184961203 0.0075202627 0.0188709423 0.0072867057 0.1855820000 0.0102950000 0.0821150000 0.0003230000 0.0002760000 0.0665810000 9269554 96830484 1769848832 4.5500874519 4.0773620605 4.8116140366 658 26.2800000000 0.0181955379 0.0075364866 0.0188709423 0.0072881819 0.1136270000 0.0119540000 0.0546200000 0.0000270000 0.0002880000 0.0391030000 9271228 96830484 1768824832 4.5388898849 4.0786585808 4.8073992729 659 26.3200000000 0.0186544377 0.0075533575 0.0188709423 0.0072856640 0.1465460000 0.0102930000 0.0748210000 0.0003470000 0.0002640000 0.0479250000 9272902 96830484 1770471424 4.5270838737 4.0814943314 4.8037166595 660 26.3600000000 0.0182489995 0.0075695630 0.0188709423 0.0072806522 0.1105300000 0.0128540000 0.0482900000 0.0000320000 0.0003810000 0.0413630000 9274576 96830484 1769074688 4.5162558556 4.0826215744 4.8006591797 661 26.4000000000 0.0184710287 0.0075860554 0.0188709423 0.0072755347 0.1418150000 0.0105610000 0.0539740000 0.0002940000 0.0003440000 0.0690150000 9276250 96830484 1770692608 4.5041809082 4.0852212906 4.7965722084 662 26.4400000000 0.0184828807 0.0076025159 0.0188709423 0.0072744321 0.1535700000 0.0123180000 0.0906540000 0.0000280000 0.0002850000 0.0390230000 9277924 96830484 1769455616 4.4923291206 4.0885848999 4.7950773239 663 26.4800000000 0.0185929481 0.0076190927 0.0188709423 0.0072918998 0.1273090000 0.0105770000 0.0544030000 0.0002870000 0.0003330000 0.0463010000 9279598 96830484 1771139072 4.4816460609 4.0880403519 4.7914075851 664 26.5200000000 0.0188496243 0.0076360061 0.0188709423 0.0072996107 0.1273060000 0.0121670000 0.0543970000 0.0000280000 0.0011750000 0.0382400000 9281272 96830484 1770217472 4.4714689255 4.0850958824 4.7854413986 665 26.5600000000 0.0189551562 0.0076530274 0.0189551562 0.0072946899 0.1894780000 0.0124470000 0.0898670000 0.0003140000 0.0003440000 0.0706190000 9282946 96830484 1768710144 4.4609012604 4.0856337547 4.7823987007 666 26.6000000000 0.0184516180 0.0076692415 0.0189551562 0.0072908811 0.1108650000 0.0106160000 0.0551460000 0.0000260000 0.0002850000 0.0372230000 9284620 96830484 1770352640 4.4497818947 4.0878534317 4.7795467377 667 26.6400000000 0.0189688765 0.0076861825 0.0189688765 0.0072947304 0.1257440000 0.0124350000 0.0495790000 0.0003630000 0.0006160000 0.0453850000 9286294 96830484 1769058304 4.4391250610 4.0908665657 4.7774815559 668 26.6800000000 0.0186360497 0.0077025745 0.0189688765 0.0073167286 0.1106710000 0.0102780000 0.0555480000 0.0000260000 0.0002900000 0.0368680000 9287968 96830484 1770864640 4.4280743599 4.0950093269 4.7747716904 669 26.7200000000 0.0189871527 0.0077194423 0.0189871527 0.0073596444 0.1486180000 0.0124390000 0.0614850000 0.0002880000 0.0003350000 0.0663900000 9289642 96830484 1769709568 4.4171404839 4.0963954926 4.7714524269 670 26.7600000000 0.0184010472 0.0077353850 0.0189871527 0.0073964722 0.1271140000 0.0107100000 0.0676890000 0.0000250000 0.0002860000 0.0370110000 9291316 96830484 1771376640 4.4074883461 4.0959706306 4.7692160606 671 26.8000000000 0.0185734630 0.0077515372 0.0189871527 0.0074033644 0.1287050000 0.0123570000 0.0610840000 0.0002890000 0.0002650000 0.0447920000 9292990 96830484 1770090496 4.3979730606 4.0963859558 4.7653260231 672 26.8400000000 0.0186730400 0.0077677894 0.0189871527 0.0073992777 0.1483890000 0.0123950000 0.0900750000 0.0000260000 0.0003730000 0.0372280000 9294664 96830484 1768677376 4.3883886337 4.0989818573 4.7611031532 673 26.8800000000 0.0179606974 0.0077829349 0.0189871527 0.0073953143 0.1624120000 0.0106780000 0.0762100000 0.0002880000 0.0003500000 0.0650100000 9296338 96830484 1770373120 4.3793830872 4.0995182991 4.7584471703 674 26.9200000000 0.0183751434 0.0077986503 0.0189871527 0.0073899029 0.1144930000 0.0124520000 0.0555410000 0.0000280000 0.0002920000 0.0369850000 9298012 96830484 1769312256 4.3706302643 4.1005496979 4.7540612221 675 26.9600000000 0.0181164909 0.0078139360 0.0189871527 0.0073844573 0.1622900000 0.0106140000 0.0890360000 0.0000610000 0.0000530000 0.0445640000 9299686 96830484 1771102208 4.3618955612 4.1025161743 4.7516937256 676 27.0000000000 0.0184583310 0.0078296822 0.0189871527 0.0073801135 0.1099960000 0.0120820000 0.0479350000 0.0000270000 0.0003850000 0.0367780000 9301360 96830484 1769709568 4.3528389931 4.1068372726 4.7477707863 677 27.0400000000 0.0184160452 0.0078453193 0.0189871527 0.0073889287 0.1661910000 0.0119860000 0.0677360000 0.0002910000 0.0002690000 0.0658720000 9303034 96830484 1768570880 4.3441085815 4.1099610329 4.7460718155 678 27.0800000000 0.0179279689 0.0078601905 0.0189871527 0.0074021786 0.1485850000 0.0102070000 0.0824170000 0.0000270000 0.0002850000 0.0368580000 9304708 96830484 1770119168 4.3358817101 4.1119070053 4.7435550690 679 27.1200000000 0.0183698907 0.0078756687 0.0189871527 0.0074118822 0.1287910000 0.0121480000 0.0549210000 0.0003030000 0.0003510000 0.0432560000 9306382 96830484 1768947712 4.3270144463 4.1140413284 4.7391767502 680 27.1600000000 0.0175446160 0.0078898877 0.0189871527 0.0074142580 0.1293970000 0.0101470000 0.0683180000 0.0000270000 0.0002880000 0.0358810000 9308056 96830484 1770610688 4.3191761971 4.1139492989 4.7355732918 681 27.2000000000 0.0185796637 0.0079055849 0.0189871527 0.0074090558 0.1705440000 0.0117080000 0.0896000000 0.0002940000 0.0002690000 0.0609930000 9309730 96830484 1769312256 4.3112182617 4.1151866913 4.7305822372 682 27.2400000000 0.0185933579 0.0079212561 0.0189871527 0.0074038856 0.1073510000 0.0091730000 0.0537870000 0.0000270000 0.0003240000 0.0355750000 9311404 96830484 1771008000 4.3029727936 4.1188216209 4.7265176773 683 27.2800000000 0.0193574764 0.0079380002 0.0193574764 0.0074030387 0.1261260000 0.0115110000 0.0539640000 0.0003690000 0.0002780000 0.0431380000 9313078 96830484 1769836544 4.2950797081 4.1216926575 4.7212076187 684 27.3200000000 0.0189307667 0.0079540715 0.0193574764 0.0074082426 0.1106950000 0.0115350000 0.0549070000 0.0000270000 0.0003660000 0.0357540000 9314752 96830484 1768333312 4.2867355347 4.1227793694 4.7175221443 685 27.3600000000 0.0197091810 0.0079712323 0.0197091810 0.0074075240 0.1849400000 0.0096410000 0.0890240000 0.0003590000 0.0002810000 0.0656580000 9316426 96830484 1770119168 4.2790722847 4.1236004829 4.7110419273 686 27.4000000000 0.0195980482 0.0079881810 0.0197091810 0.0074042894 0.1124760000 0.0109400000 0.0609710000 0.0000260000 0.0002880000 0.0325480000 9318100 96830484 1769078784 4.2705345154 4.1271119118 4.7057271004 687 27.4400000000 0.0192694459 0.0080046020 0.0197091810 0.0074111981 0.1267220000 0.0093730000 0.0634810000 0.0002850000 0.0003360000 0.0424220000 9319774 96830484 1770721280 4.2623238564 4.1306886673 4.7006459236 688 27.4800000000 0.0196907278 0.0080215877 0.0197091810 0.0074269215 0.1090550000 0.0112700000 0.0538160000 0.0001010000 0.0002850000 0.0349790000 9321448 96830484 1769455616 4.2540426254 4.1323790550 4.6946668625 689 27.5200000000 0.0195895862 0.0080383772 0.0197091810 0.0074366654 0.1397550000 0.0095940000 0.0601640000 0.0002890000 0.0002840000 0.0615290000 9323122 96830484 1771118592 4.2456636429 4.1340270042 4.6891784668 690 27.5600000000 0.0193785634 0.0080548123 0.0197091810 0.0074378155 0.1147000000 0.0111500000 0.0538140000 0.0000310000 0.0002840000 0.0342530000 9324796 96830484 1769836544 4.2377271652 4.1354174614 4.6827244759 691 27.6000000000 0.0197376255 0.0080717194 0.0197376255 0.0074379476 0.1498580000 0.0109150000 0.0864450000 0.0000580000 0.0000520000 0.0437310000 9326470 96830484 1768460288 4.2288713455 4.1397361755 4.6760659218 692 27.6400000000 0.0202354994 0.0080892971 0.0202354994 0.0074524403 0.1075840000 0.0092200000 0.0485990000 0.0000250000 0.0003160000 0.0341840000 9328144 96830484 1770119168 4.2202033997 4.1435661316 4.6691527367 693 27.6800000000 0.0205800403 0.0081073213 0.0205800403 0.0074828607 0.1259660000 0.0107620000 0.0457080000 0.0003200000 0.0003490000 0.0609460000 9329818 96830484 1768951808 4.2123656273 4.1440181732 4.6614494324 694 27.7200000000 0.0213539954 0.0081264087 0.0213539954 0.0074974571 0.1112970000 0.0088740000 0.0537580000 0.0000260000 0.0006090000 0.0340820000 9331492 96830484 1770504192 4.2048897743 4.1433930397 4.6523942947 695 27.7600000000 0.0216783658 0.0081459079 0.0216783658 0.0074973039 0.1297300000 0.0107570000 0.0681420000 0.0004200000 0.0003620000 0.0420350000 9333166 96830484 1769185280 4.1977829933 4.1426291466 4.6447014809 696 27.8000000000 0.0223317388 0.0081662899 0.0223317388 0.0074932721 0.1077380000 0.0089710000 0.0529870000 0.0000280000 0.0003590000 0.0344110000 9334840 96830484 1771003904 4.1900348663 4.1451425552 4.6365804672 697 27.8400000000 0.0230007321 0.0081875731 0.0230007321 0.0074904076 0.1484640000 0.0107170000 0.0676140000 0.0002880000 0.0003370000 0.0615230000 9336514 96830484 1769701376 4.1819138527 4.1486091614 4.6288304329 698 27.8800000000 0.0233368780 0.0082092770 0.0233368780 0.0074926116 0.1084110000 0.0104320000 0.0531790000 0.0000280000 0.0002890000 0.0347040000 9338188 96830484 1768050688 4.1729097366 4.1531667709 4.6220345497 699 27.9200000000 0.0234041400 0.0082310150 0.0234041400 0.0075034186 0.1083370000 0.0090500000 0.0469660000 0.0003150000 0.0003530000 0.0424000000 9339862 96830484 1769840640 4.1645202637 4.1572694778 4.6158919334 700 27.9600000000 0.0232656263 0.0082524930 0.0234041400 0.0075204187 0.1088510000 0.0105190000 0.0535160000 0.0000300000 0.0002950000 0.0353790000 9341536 96830484 1768558592 4.1558227539 4.1604790688 4.6093621254 701 28.0000000000 0.0229753759 0.0082734957 0.0234041400 0.0075394607 0.1449340000 0.0084340000 0.0531160000 0.0002910000 0.0003520000 0.0621480000 9343210 96830484 1770319872 4.1475872993 4.1627759933 4.6035981178 702 28.0400000000 0.0222718362 0.0082934364 0.0234041400 0.0075546873 0.1095050000 0.0105550000 0.0469250000 0.0000300000 0.0003150000 0.0358400000 9344884 96830484 1768955904 4.1395316124 4.1639385223 4.5982379913 703 28.0800000000 0.0213125069 0.0083119557 0.0234041400 0.0075631734 0.1094360000 0.0084940000 0.0463660000 0.0003950000 0.0002770000 0.0427880000 9346558 96830484 1770840064 4.1323060989 4.1649956703 4.5947365761 704 28.1200000000 0.0201804210 0.0083288143 0.0234041400 0.0075704159 0.1075610000 0.0107880000 0.0429380000 0.0000260000 0.0009900000 0.0357870000 9348232 96830484 1769447424 4.1233873367 4.1713142395 4.5920209885 705 28.1600000000 0.0193232615 0.0083444093 0.0234041400 0.0075947643 0.1316140000 0.0101670000 0.0531150000 0.0003110000 0.0003450000 0.0596120000 9349906 96830484 1768161280 4.1149296761 4.1755628586 4.5889759064 706 28.2000000000 0.0186705031 0.0083590354 0.0234041400 0.0076159384 0.1057780000 0.0083130000 0.0457260000 0.0003540000 0.0003780000 0.0381810000 9351580 96830484 1769840640 4.1076602936 4.1756229401 4.5860204697 707 28.2400000000 0.0181915853 0.0083729429 0.0234041400 0.0076184285 0.1489630000 0.0099910000 0.0771770000 0.0003600000 0.0002710000 0.0492530000 9353254 96830484 1768452096 4.0998320580 4.1790704727 4.5827794075 708 28.2800000000 0.0175695345 0.0083859324 0.0234041400 0.0076158833 0.1317450000 0.0078030000 0.0766740000 0.0000260000 0.0003550000 0.0386080000 9354928 96830484 1770176512 4.0915536880 4.1835079193 4.5809454918 709 28.3200000000 0.0164776109 0.0083973452 0.0234041400 0.0076115676 0.1264170000 0.0098430000 0.0448930000 0.0006220000 0.0003510000 0.0623090000 9356602 96830484 1769177088 4.0851984024 4.1805315018 4.5794172287 710 28.3600000000 0.0156704504 0.0084075890 0.0234041400 0.0076079782 0.1078120000 0.0086930000 0.0572740000 0.0000260000 0.0003210000 0.0334020000 9358276 96830484 1770811392 4.0783195496 4.1814999580 4.5773091316 711 28.4000000000 0.0153071219 0.0084172930 0.0234041400 0.0076030025 0.1214720000 0.0110890000 0.0480200000 0.0003220000 0.0002780000 0.0426100000 9359950 96830484 1769574400 4.0697679520 4.1894001961 4.5763020515 712 28.4400000000 0.0149861109 0.0084265189 0.0234041400 0.0076000913 0.1086410000 0.0102380000 0.0442470000 0.0000300000 0.0003930000 0.0356580000 9361624 96830484 1767923712 4.0618805885 4.1916584969 4.5742092133 713 28.4800000000 0.0148077440 0.0084354687 0.0234041400 0.0075970405 0.1263180000 0.0083960000 0.0465400000 0.0003150000 0.0002920000 0.0624920000 9363298 96830484 1769713664 4.0568680763 4.1882057190 4.5736980438 714 28.5200000000 0.0148235969 0.0084444157 0.0234041400 0.0076158389 0.0945570000 0.0100320000 0.0430390000 0.0000280000 0.0012220000 0.0320780000 9364972 96830484 1768431616 4.0485210419 4.1957216263 4.5732097626 715 28.5600000000 0.0146974055 0.0084531611 0.0234041400 0.0076110682 0.1228070000 0.0090200000 0.0531490000 0.0002930000 0.0002620000 0.0431390000 9366646 96830484 1767403520 4.0397529602 4.2025599480 4.5731954575 716 28.6000000000 0.0146679385 0.0084618410 0.0234041400 0.0076116557 0.0931890000 0.0084790000 0.0440680000 0.0000260000 0.0003140000 0.0320570000 9368320 96830484 1766551552 4.0330042839 4.2043118477 4.5753064156 717 28.6400000000 0.0146206142 0.0084704306 0.0234041400 0.0076090184 0.1417980000 0.0084210000 0.0532120000 0.0003920000 0.0002830000 0.0577340000 9369994 96830484 1765384192 4.0265536308 4.2058911324 4.5780897141 718 28.6800000000 0.0146794636 0.0084790783 0.0234041400 0.0076042896 0.1098120000 0.0082610000 0.0513600000 0.0000250000 0.0002910000 0.0354410000 9371668 96830484 1765097472 4.0192165375 4.2106003761 4.5808091164 719 28.7200000000 0.0146636609 0.0084876799 0.0234041400 0.0076031499 0.1077230000 0.0087650000 0.0438750000 0.0003200000 0.0002770000 0.0420380000 9373342 96830484 1764605952 4.0114812851 4.2138681412 4.5830125809 720 28.7600000000 0.0146838333 0.0084962857 0.0234041400 0.0076010228 0.1068480000 0.0086370000 0.0438790000 0.0000270000 0.0003820000 0.0345780000 9375016 96830484 1766268928 4.0040273666 4.2162251472 4.5866551399 721 28.8000000000 0.0147242602 0.0085049237 0.0234041400 0.0075962213 0.1224280000 0.0083170000 0.0436790000 0.0003290000 0.0003580000 0.0614220000 9376690 96830484 1767780352 3.9971418381 4.2171368599 4.5912604332 722 28.8400000000 0.0147357145 0.0085135536 0.0234041400 0.0075909757 0.0973380000 0.0081470000 0.0453220000 0.0000290000 0.0003850000 0.0345880000 9378364 96830484 1769558016 3.9892985821 4.2196011543 4.5956435204 723 28.8800000000 0.0147332652 0.0085221562 0.0234041400 0.0075857726 0.1081190000 0.0102090000 0.0460400000 0.0003230000 0.0002790000 0.0412990000 9380038 96830484 1768161280 3.9816117287 4.2208828926 4.6011700630 724 28.9200000000 0.0146774640 0.0085306580 0.0234041400 0.0075805636 0.1065840000 0.0083820000 0.0470920000 0.0000260000 0.0003160000 0.0340330000 9381712 96830484 1769922560 3.9733407497 4.2232346535 4.6065607071 725 28.9600000000 0.0146483900 0.0085390963 0.0234041400 0.0075778954 0.1407730000 0.0101640000 0.0605700000 0.0002890000 0.0003420000 0.0611310000 9383386 96830484 1768816640 3.9646880627 4.2258806229 4.6123008728 726 29.0000000000 0.0146942381 0.0085475744 0.0234041400 0.0075829292 0.1150810000 0.0082660000 0.0507280000 0.0000270000 0.0003160000 0.0347590000 9385060 96830484 1770430464 3.9565818310 4.2273068428 4.6183695793 727 29.0400000000 0.0146342563 0.0085559467 0.0234041400 0.0075873020 0.1104640000 0.0104000000 0.0437710000 0.0007080000 0.0002950000 0.0409530000 9386734 96830484 1769193472 3.9474041462 4.2293629646 4.6242895126 728 29.0800000000 0.0147076957 0.0085643970 0.0234041400 0.0075910323 0.1067560000 0.0088940000 0.0439560000 0.0000270000 0.0003870000 0.0345720000 9388408 96830484 1770856448 3.9386363029 4.2318329811 4.6308751106 729 29.1200000000 0.0146836843 0.0085727910 0.0234041400 0.0075906491 0.1264610000 0.0104350000 0.0465950000 0.0003100000 0.0002730000 0.0604420000 9390082 96830484 1769955328 3.9298713207 4.2344408035 4.6378803253 730 29.1600000000 0.0148183806 0.0085813466 0.0234041400 0.0075871460 0.1307630000 0.0106050000 0.0666420000 0.0000270000 0.0002800000 0.0338740000 9391756 96830484 1768316928 3.9211218357 4.2357854843 4.6446886063 731 29.2000000000 0.0148470541 0.0085899181 0.0234041400 0.0075825937 0.1089100000 0.0084340000 0.0440030000 0.0003090000 0.0002720000 0.0402610000 9393430 96830484 1770110976 3.9117555618 4.2384305000 4.6511240005 732 29.2400000000 0.0150051704 0.0085986821 0.0234041400 0.0075784624 0.1078630000 0.0104970000 0.0455610000 0.0000270000 0.0003090000 0.0332190000 9395104 96830484 1769193472 3.9016520977 4.2428240776 4.6576581001 733 29.2800000000 0.0149256671 0.0086073137 0.0234041400 0.0075737670 0.1205510000 0.0083390000 0.0436910000 0.0003900000 0.0002860000 0.0594760000 9396778 96830484 1770856448 3.8919045925 4.2460803986 4.6660461426 734 29.3200000000 0.0148434648 0.0086158098 0.0234041400 0.0075693552 0.0973780000 0.0104570000 0.0369690000 0.0000240000 0.0002800000 0.0349120000 9398452 96830484 1769684992 3.8827900887 4.2497301102 4.6752996445 735 29.3600000000 0.0146998269 0.0086240874 0.0234041400 0.0075663236 0.1143640000 0.0081340000 0.0594340000 0.0003260000 0.0002780000 0.0374740000 9400126 96830484 1768284160 3.8739161491 4.2531423569 4.6840734482 736 29.4000000000 0.0145548675 0.0086321455 0.0234041400 0.0075631241 0.1011490000 0.0076940000 0.0432860000 0.0000260000 0.0003080000 0.0367890000 9401800 96830484 1767161856 3.8653137684 4.2573699951 4.6932678223 737 29.4400000000 0.0143519957 0.0086399065 0.0234041400 0.0075584236 0.1198480000 0.0082530000 0.0511390000 0.0002910000 0.0002780000 0.0512830000 9403474 96830484 1765781504 3.8570296764 4.2605137825 4.7020540237 738 29.4800000000 0.0142242173 0.0086474733 0.0234041400 0.0075570685 0.0948900000 0.0091560000 0.0502310000 0.0000270000 0.0003220000 0.0266750000 9405148 96830484 1765138432 3.8485243320 4.2639899254 4.7108230591 739 29.5200000000 0.0141146993 0.0086548715 0.0234041400 0.0075721590 0.1075100000 0.0090220000 0.0518180000 0.0000600000 0.0000530000 0.0380790000 9406822 96830484 1765134336 3.8406844139 4.2668724060 4.7196841240 740 29.5600000000 0.0141634969 0.0086623155 0.0234041400 0.0075916405 0.1048840000 0.0083830000 0.0424120000 0.0000300000 0.0010860000 0.0335780000 9408496 96830484 1765007360 3.8336074352 4.2695889473 4.7282757759 741 29.6000000000 0.0142182484 0.0086698134 0.0234041400 0.0076158549 0.1183210000 0.0081230000 0.0427690000 0.0010970000 0.0003530000 0.0574420000 9410170 96830484 1765138432 3.8263628483 4.2739658356 4.7367572784 742 29.6400000000 0.0142703103 0.0086773613 0.0234041400 0.0076342965 0.0960850000 0.0085810000 0.0514830000 0.0000260000 0.0007680000 0.0266860000 9411844 96830484 1766764544 3.8201651573 4.2776603699 4.7457337379 743 29.6800000000 0.0142130833 0.0086848118 0.0234041400 0.0076339178 0.1103630000 0.0084830000 0.0453180000 0.0003920000 0.0002730000 0.0384850000 9413518 96830484 1768542208 3.8153321743 4.2786693573 4.7539277077 744 29.7200000000 0.0142174447 0.0086922481 0.0234041400 0.0076292853 0.1074520000 0.0083180000 0.0457660000 0.0000290000 0.0003150000 0.0319260000 9415192 96830484 1770319872 3.8103616238 4.2806506157 4.7609291077 745 29.7600000000 0.0142213451 0.0086996697 0.0234041400 0.0076270749 0.1202880000 0.0102710000 0.0440580000 0.0003130000 0.0003560000 0.0565810000 9416866 96830484 1769066496 3.8051857948 4.2833600044 4.7673730850 746 29.8000000000 0.0142170060 0.0087070656 0.0234041400 0.0076231020 0.0986740000 0.0083230000 0.0467180000 0.0000290000 0.0003180000 0.0322490000 9418540 96830484 1770733568 3.8003602028 4.2852253914 4.7737121582 747 29.8400000000 0.0142135294 0.0087144370 0.0234041400 0.0076181888 0.1080610000 0.0103810000 0.0457440000 0.0003860000 0.0002870000 0.0381960000 9420214 96830484 1769701376 3.7951130867 4.2883172035 4.7794489861 748 29.8800000000 0.0141802505 0.0087217443 0.0234041400 0.0076153820 0.1076860000 0.0100980000 0.0503760000 0.0000340000 0.0003020000 0.0317620000 9421888 96830484 1768198144 3.7901213169 4.2918338776 4.7853894234 749 29.9200000000 0.0141853075 0.0087290388 0.0234041400 0.0076119248 0.1190800000 0.0084380000 0.0461650000 0.0003820000 0.0002810000 0.0553180000 9423562 96830484 1769840640 3.7858245373 4.2947320938 4.7910404205 750 29.9600000000 0.0141989570 0.0087363320 0.0234041400 0.0076088626 0.0986810000 0.0099120000 0.0456560000 0.0000320000 0.0003130000 0.0313940000 9425236 96830484 1768525824 3.7817771435 4.2975530624 4.7962698936 751 30.0000000000 0.0142370313 0.0087436565 0.0234041400 0.0076058479 0.1063270000 0.0082770000 0.0421780000 0.0003090000 0.0003530000 0.0369330000 9426910 96830484 1770430464 3.7780020237 4.2997326851 4.8008852005 752 30.0400000000 0.0142752025 0.0087510123 0.0234041400 0.0076029880 0.1055360000 0.0101380000 0.0458730000 0.0000320000 0.0003150000 0.0316790000 9428584 96830484 1769320448 3.7744352818 4.3024468422 4.8051929474 753 30.0800000000 0.0142783234 0.0087583527 0.0234041400 0.0076021922 0.1281190000 0.0083280000 0.0436620000 0.0003200000 0.0002710000 0.0574780000 9430258 96830484 1771094016 3.7707328796 4.3043985367 4.8089151382 754 30.1200000000 0.0143137751 0.0087657206 0.0234041400 0.0076077374 0.1088030000 0.0103810000 0.0490330000 0.0000250000 0.0003070000 0.0317210000 9431932 96830484 1769955328 3.7671816349 4.3065361977 4.8124823570 755 30.1600000000 0.0143734552 0.0087731480 0.0234041400 0.0076190293 0.1083380000 0.0103590000 0.0446460000 0.0003310000 0.0003500000 0.0369340000 9433606 96830484 1768435712 3.7631285191 4.3080182076 4.8157296181 756 30.2000000000 0.0143836960 0.0087805694 0.0234041400 0.0076304075 0.1077930000 0.0086890000 0.0505630000 0.0003430000 0.0003140000 0.0306990000 9435280 96830484 1770237952 3.7588603497 4.3107681274 4.8192996979 757 30.2400000000 0.0143522769 0.0087879297 0.0234041400 0.0076320813 0.1162080000 0.0104700000 0.0434190000 0.0003160000 0.0002780000 0.0530390000 9436954 96830484 1769050112 3.7540502548 4.3138208389 4.8223252296 758 30.2800000000 0.0143564139 0.0087952759 0.0234041400 0.0076351886 0.1020280000 0.0082870000 0.0533810000 0.0000290000 0.0003020000 0.0301690000 9438628 96830484 1770729472 3.7491610050 4.3155627251 4.8257799149 759 30.3200000000 0.0144019322 0.0088026628 0.0234041400 0.0076521664 0.1070590000 0.0104070000 0.0418330000 0.0002970000 0.0003550000 0.0356210000 9440302 96830484 1769558016 3.7436444759 4.3186225891 4.8292622566 760 30.3600000000 0.0144118993 0.0088100434 0.0234041400 0.0076650558 0.1086930000 0.0085680000 0.0526570000 0.0000290000 0.0003030000 0.0306210000 9441976 96830484 1771257856 3.7373392582 4.3234786987 4.8322777748 761 30.4000000000 0.0144270370 0.0088174245 0.0234041400 0.0076740923 0.1157990000 0.0103210000 0.0444840000 0.0003210000 0.0002800000 0.0515030000 9443650 96830484 1770192896 3.7310059071 4.3269586563 4.8350033760 762 30.4400000000 0.0144324051 0.0088247932 0.0234041400 0.0076753856 0.1027930000 0.0103580000 0.0513580000 0.0000260000 0.0002950000 0.0292020000 9445324 96830484 1768669184 3.7242331505 4.3305974007 4.8372020721 763 30.4800000000 0.0144912638 0.0088322198 0.0234041400 0.0076742232 0.1063000000 0.0086770000 0.0445790000 0.0003330000 0.0003440000 0.0349380000 9446998 96830484 1770344448 3.7170283794 4.3346767426 4.8394079208 764 30.5200000000 0.0145480139 0.0088397012 0.0234041400 0.0076739763 0.1098120000 0.0106870000 0.0570860000 0.0000920000 0.0002900000 0.0292020000 9448672 96830484 1769177088 3.7092885971 4.3385605812 4.8415946960 765 30.5600000000 0.0145301241 0.0088471397 0.0234041400 0.0076717255 0.1262770000 0.0084120000 0.0446040000 0.0003900000 0.0002820000 0.0529660000 9450346 96830484 1770967040 3.7016010284 4.3425726891 4.8438782692 766 30.6000000000 0.0146085331 0.0088546611 0.0234041400 0.0076707546 0.1075420000 0.0103640000 0.0452010000 0.0000260000 0.0003200000 0.0285120000 9452020 96830484 1769938944 3.6939091682 4.3462052345 4.8461594582 767 30.6400000000 0.0145908296 0.0088621398 0.0234041400 0.0076694135 0.1091970000 0.0102940000 0.0458770000 0.0003250000 0.0003530000 0.0338670000 9453694 96830484 1768144896 3.6854104996 4.3502006531 4.8479971886 768 30.6800000000 0.0146369915 0.0088696591 0.0234041400 0.0076705423 0.1066200000 0.0087460000 0.0457910000 0.0000280000 0.0003190000 0.0281250000 9455368 96830484 1769984000 3.6770977974 4.3538813591 4.8500752449 769 30.7200000000 0.0146542834 0.0088771814 0.0234041400 0.0076712017 0.1292530000 0.0105720000 0.0456270000 0.0003150000 0.0002700000 0.0520880000 9457042 96830484 1768685568 3.6687211990 4.3581404686 4.8521952629 770 30.7600000000 0.0146609889 0.0088846928 0.0234041400 0.0076683892 0.0911250000 0.0081880000 0.0457520000 0.0000250000 0.0006680000 0.0277550000 9458716 96830484 1770348544 3.6603379250 4.3624267578 4.8542914391 771 30.8000000000 0.0146680949 0.0088921940 0.0234041400 0.0076647115 0.1074350000 0.0102210000 0.0502160000 0.0003170000 0.0002770000 0.0338930000 9460390 96830484 1769193472 3.6518762112 4.3662247658 4.8559947014 772 30.8400000000 0.0147304311 0.0088997565 0.0234041400 0.0076623415 0.1049470000 0.0085290000 0.0450240000 0.0000280000 0.0003850000 0.0265650000 9462064 96830484 1770967040 3.6435749531 4.3688349724 4.8577790260 773 30.8800000000 0.0147272693 0.0089072953 0.0234041400 0.0076609558 0.1130380000 0.0101000000 0.0453310000 0.0003270000 0.0002800000 0.0481070000 9463738 96830484 1769574400 3.6350531578 4.3719048500 4.8596186638 774 30.9200000000 0.0147727616 0.0089148734 0.0234041400 0.0076643041 0.1051460000 0.0098130000 0.0522390000 0.0000290000 0.0002910000 0.0262630000 9465412 96830484 1768054784 3.6269917488 4.3743619919 4.8616433144 775 30.9600000000 0.0148143601 0.0089224857 0.0234041400 0.0076695929 0.1067060000 0.0085460000 0.0430380000 0.0003870000 0.0006220000 0.0327670000 9467086 96830484 1769795584 3.6186985970 4.3759398460 4.8631229401 776 31.0000000000 0.0148222661 0.0089300885 0.0234041400 0.0076772483 0.1075880000 0.0099750000 0.0463050000 0.0000280000 0.0003890000 0.0269240000 9468760 96830484 1768579072 3.6101284027 4.3778934479 4.8646459579 777 31.0400000000 0.0148576815 0.0089377173 0.0234041400 0.0076880161 0.1035460000 0.0078500000 0.0375740000 0.0002950000 0.0003500000 0.0485010000 9470434 96830484 1770192896 3.6016600132 4.3811264038 4.8659329414 778 31.0800000000 0.0148812365 0.0089453568 0.0234041400 0.0076890474 0.1129630000 0.0106780000 0.0526350000 0.0000270000 0.0003950000 0.0263370000 9472108 96830484 1769050112 3.5933251381 4.3844819069 4.8670859337 779 31.1200000000 0.0149004431 0.0089530013 0.0234041400 0.0076875440 0.1085730000 0.0082050000 0.0458570000 0.0003210000 0.0003510000 0.0319550000 9473782 96830484 1770602496 3.5854594707 4.3867373466 4.8686213493 780 31.1600000000 0.0149104847 0.0089606391 0.0234041400 0.0076865487 0.0912250000 0.0103570000 0.0452510000 0.0000270000 0.0003190000 0.0249770000 9475456 96830484 1769177088 3.5777521133 4.3893613815 4.8701572418 781 31.2000000000 0.0149608431 0.0089683218 0.0234041400 0.0076843368 0.1235880000 0.0090280000 0.0425530000 0.0010580000 0.0002770000 0.0492140000 9477130 96830484 1768067072 3.5700554848 4.3917856216 4.8709177971 782 31.2400000000 0.0149521809 0.0089759738 0.0234041400 0.0076802814 0.1100390000 0.0081440000 0.0631830000 0.0000230000 0.0002870000 0.0250300000 9478804 96830484 1769861120 3.5627579689 4.3931102753 4.8721847534 783 31.2800000000 0.0149450498 0.0089835971 0.0234041400 0.0076757486 0.1085250000 0.0102020000 0.0525050000 0.0002920000 0.0003400000 0.0310460000 9480478 96830484 1768525824 3.5555570126 4.3947820663 4.8735527992 784 31.3200000000 0.0149870533 0.0089912546 0.0234041400 0.0076710048 0.1056130000 0.0083410000 0.0504920000 0.0000280000 0.0002960000 0.0248060000 9482152 96830484 1770332160 3.5489282608 4.3960862160 4.8749723434 785 31.3600000000 0.0149807893 0.0089988846 0.0234041400 0.0076662732 0.1285420000 0.0103090000 0.0465990000 0.0003250000 0.0003530000 0.0481250000 9483826 96830484 1769066496 3.5425209999 4.3966846466 4.8760986328 786 31.4000000000 0.0149999484 0.0090065195 0.0234041400 0.0076630860 0.0903580000 0.0084080000 0.0439630000 0.0000300000 0.0003180000 0.0242100000 9485500 96830484 1770749952 3.5361075401 4.3976063728 4.8773374557 787 31.4400000000 0.0149907544 0.0090141234 0.0234041400 0.0076597612 0.1066190000 0.0102980000 0.0452770000 0.0005280000 0.0003540000 0.0304210000 9487174 96830484 1769828352 3.5303318501 4.3995628357 4.8785133362 788 31.4800000000 0.0150179910 0.0090217425 0.0234041400 0.0076579051 0.0904520000 0.0101440000 0.0452580000 0.0000290000 0.0003940000 0.0238660000 9488848 96830484 1768288256 3.5251133442 4.4004697800 4.8801250458 789 31.5200000000 0.0150419818 0.0090293727 0.0234041400 0.0076564257 0.1073650000 0.0089190000 0.0448910000 0.0007660000 0.0002920000 0.0434210000 9490522 96830484 1766670336 3.5198178291 4.4005422592 4.8812093735 790 31.5600000000 0.0150332088 0.0090369725 0.0234041400 0.0076527195 0.1043030000 0.0087880000 0.0518710000 0.0000930000 0.0002910000 0.0232760000 9492196 96830484 1768439808 3.5147080421 4.4007182121 4.8826723099 791 31.6000000000 0.0150221139 0.0090445391 0.0234041400 0.0076480306 0.1099900000 0.0082840000 0.0435000000 0.0003130000 0.0002680000 0.0302090000 9493870 96830484 1770082304 3.5098609924 4.4009604454 4.8838796616 792 31.6400000000 0.0150236012 0.0090520884 0.0234041400 0.0076432387 0.1079220000 0.0099900000 0.0559120000 0.0000250000 0.0003570000 0.0271040000 9495544 96830484 1768906752 3.5055963993 4.4005794525 4.8852710724 793 31.6800000000 0.0150265619 0.0090596224 0.0234041400 0.0076400783 0.1387060000 0.0077800000 0.0660010000 0.0003940000 0.0002840000 0.0549260000 9497218 96830484 1770602496 3.5017411709 4.3997955322 4.8864841461 794 31.7200000000 0.0150258644 0.0090671366 0.0234041400 0.0076427218 0.1136860000 0.0102400000 0.0566220000 0.0000270000 0.0003660000 0.0307910000 9498892 96830484 1769320448 3.4984414577 4.3987030983 4.8879008293 795 31.7600000000 0.0150219491 0.0090746269 0.0234041400 0.0076519751 0.1295220000 0.0078900000 0.0769860000 0.0003750000 0.0002870000 0.0330110000 9500566 96830484 1771114496 3.4951846600 4.3976783752 4.8891954422 796 31.8000000000 0.0150127448 0.0090820868 0.0234041400 0.0076693822 0.0870780000 0.0097920000 0.0410720000 0.0000310000 0.0002900000 0.0238960000 9502240 96830484 1769811968 3.4920165539 4.3965725899 4.8908629417 797 31.8400000000 0.0150536066 0.0090895793 0.0234041400 0.0076890770 0.1248850000 0.0104420000 0.0426290000 0.0009410000 0.0002960000 0.0462180000 9503914 96830484 1768177664 3.4896512032 4.3954977989 4.8924775124 798 31.8800000000 0.0150425956 0.0090970393 0.0234041400 0.0077072435 0.0904460000 0.0083900000 0.0433700000 0.0000270000 0.0003180000 0.0240610000 9505588 96830484 1769820160 3.4868018627 4.3940052986 4.8937835693 799 31.9200000000 0.0150640765 0.0091045074 0.0234041400 0.0077175999 0.0894500000 0.0102360000 0.0355010000 0.0002920000 0.0003380000 0.0324140000 9507262 96830484 1768689664 3.4841926098 4.3922376633 4.8951892853 800 31.9600000000 0.0150249191 0.0091119079 0.0234041400 0.0077253028 0.1055020000 0.0083480000 0.0653730000 0.0000340000 0.0005430000 0.0216610000 9508936 96830484 1766764544 3.4818174839 4.3902139664 4.8967137337 801 32.0000000000 0.0150167542 0.0091192798 0.0234041400 0.0077382952 0.1207400000 0.0098200000 0.0468170000 0.0003590000 0.0002700000 0.0541390000 9510610 96830484 1768546304 3.4798398018 4.3885188103 4.8987574577 802 32.0400000000 0.0150408773 0.0091266633 0.0234041400 0.0077441816 0.0956200000 0.0085480000 0.0497620000 0.0000280000 0.0003150000 0.0270760000 9512284 96830484 1770065920 3.4777500629 4.3864583969 4.9005646706 803 32.0800000000 0.0150237493 0.0091340071 0.0234041400 0.0077553806 0.1052410000 0.0113940000 0.0408940000 0.0003580000 0.0002690000 0.0317780000 9513958 96830484 1768685568 3.4768815041 4.3861145973 4.9031500816 804 32.1199999990 0.0150501598 0.0091413655 0.0234041400 0.0077718610 0.0904660000 0.0084530000 0.0464240000 0.0000260000 0.0003130000 0.0249500000 9515632 96830484 1770475520 3.4757683277 4.3853678703 4.9051642418 805 32.1600000000 0.0150162932 0.0091486636 0.0234041400 0.0077879407 0.1251660000 0.0104080000 0.0427650000 0.0010550000 0.0003400000 0.0478950000 9517306 96830484 1769066496 3.4747710228 4.3836479187 4.9073653221 806 32.2000000000 0.0150316413 0.0091559625 0.0234041400 0.0078046176 0.0904650000 0.0083470000 0.0438900000 0.0000290000 0.0003180000 0.0248900000 9518980 96830484 1770729472 3.4735305309 4.3820986748 4.9090895653 807 32.2400000000 0.0150391487 0.0091632527 0.0234041400 0.0078220152 0.1063560000 0.0103910000 0.0435650000 0.0003210000 0.0002740000 0.0317580000 9520654 96830484 1769574400 3.4729351997 4.3790364265 4.9110822678 808 32.2800000000 0.0150476694 0.0091705354 0.0234041400 0.0078311093 0.0904570000 0.0102400000 0.0434020000 0.0000290000 0.0003120000 0.0254390000 9522328 96830484 1768054784 3.4717354774 4.3766255379 4.9133515358 809 32.3200000000 0.0150329769 0.0091777820 0.0234041400 0.0078371428 0.1220940000 0.0088420000 0.0359860000 0.0002980000 0.0002690000 0.0506760000 9524002 96830484 1766129664 3.4715194702 4.3729205132 4.9157776833 810 32.3600000000 0.0150588304 0.0091850425 0.0234041400 0.0078439416 0.0914680000 0.0082070000 0.0461080000 0.0000280000 0.0003860000 0.0258690000 9525676 96830484 1767804928 3.4707312584 4.3705725670 4.9178886414 811 32.4000000000 0.0150542827 0.0091922795 0.0234041400 0.0078425085 0.1456290000 0.0083310000 0.0831720000 0.0003020000 0.0002720000 0.0320130000 9527350 96830484 1769558016 3.4696519375 4.3667635918 4.9199771881 812 32.4399999990 0.0150657520 0.0091995129 0.0234041400 0.0078415460 0.1077840000 0.0100270000 0.0463680000 0.0000250000 0.0003170000 0.0266620000 9529024 96830484 1768308736 3.4688868523 4.3632526398 4.9221863747 813 32.4800000000 0.0150273163 0.0092066812 0.0234041400 0.0078416952 0.1281710000 0.0081980000 0.0460930000 0.0003140000 0.0004390000 0.0496130000 9530698 96830484 1770065920 3.4686744213 4.3606710434 4.9252405167 814 32.5200000000 0.0150446845 0.0092138531 0.0234041400 0.0078422118 0.0913550000 0.0098700000 0.0442020000 0.0000240000 0.0011360000 0.0258540000 9532372 96830484 1768951808 3.4680998325 4.3578500748 4.9280781746 815 32.5600000000 0.0150083303 0.0092209629 0.0234041400 0.0078398080 0.1052720000 0.0090660000 0.0450790000 0.0003160000 0.0003490000 0.0319960000 9534046 96830484 1768050688 3.4672837257 4.3548216820 4.9308123589 816 32.6000000000 0.0150252255 0.0092280760 0.0234041400 0.0078378399 0.0897680000 0.0083790000 0.0442370000 0.0000280000 0.0003170000 0.0260510000 9535720 96830484 1769824256 3.4670374393 4.3505525589 4.9341263771 817 32.6400000000 0.0149835339 0.0092351206 0.0234041400 0.0078340978 0.1174260000 0.0101680000 0.0508500000 0.0003170000 0.0002660000 0.0463270000 9537394 96830484 1768542208 3.4662728310 4.3471016884 4.9370169640 818 32.6800000000 0.0149713913 0.0092421332 0.0234041400 0.0078295514 0.0971160000 0.0084070000 0.0447760000 0.0000290000 0.0003170000 0.0263670000 9539068 96830484 1770205184 3.4656205177 4.3434543610 4.9407253265 819 32.7200000000 0.0149873290 0.0092491481 0.0234041400 0.0078262068 0.1074660000 0.0102890000 0.0430600000 0.0011130000 0.0003640000 0.0327600000 9540742 96830484 1768685568 3.4654166698 4.3415312767 4.9449844360 820 32.7599999990 0.0149738220 0.0092561294 0.0234041400 0.0078233936 0.1066960000 0.0085330000 0.0466300000 0.0000270000 0.0003100000 0.0268850000 9542416 96830484 1770479616 3.4648218155 4.3391108513 4.9492516518 821 32.7999999990 0.0148857543 0.0092629864 0.0234041400 0.0078273846 0.1286280000 0.0101720000 0.0437430000 0.0003180000 0.0003490000 0.0505680000 9544090 96830484 1769082880 3.4653356075 4.3370370865 4.9548072815 822 32.8400000000 0.0149300871 0.0092698807 0.0234041400 0.0078510160 0.0924680000 0.0083770000 0.0456060000 0.0000290000 0.0003190000 0.0283080000 9545764 96830484 1770729472 3.4650657177 4.3345003128 4.9596967697 823 32.8800000000 0.0148633756 0.0092766772 0.0234041400 0.0078609471 0.1072630000 0.0105790000 0.0477880000 0.0003920000 0.0002830000 0.0387230000 9547438 96830484 1769574400 3.4644498825 4.3324174881 4.9647026062 824 32.9200000000 0.0149276219 0.0092835351 0.0234041400 0.0078653469 0.0909370000 0.0101990000 0.0506760000 0.0000270000 0.0003100000 0.0202270000 9549112 96830484 1768054784 3.4640951157 4.3316097260 4.9705533981 825 32.9600000000 0.0148329111 0.0092902616 0.0234041400 0.0078779998 0.1158650000 0.0093140000 0.0471610000 0.0003270000 0.0003510000 0.0491350000 9550786 96830484 1767145472 3.4637951851 4.3291549683 4.9765729904 826 33.0000000000 0.0147286514 0.0092968456 0.0234041400 0.0078859214 0.0951860000 0.0086630000 0.0457470000 0.0000290000 0.0003200000 0.0275040000 9552460 96830484 1768714240 3.4633622169 4.3277950287 4.9827528000 827 33.0400000000 0.0146513162 0.0093033202 0.0234041400 0.0079025225 0.1059070000 0.0082880000 0.0425730000 0.0010220000 0.0006660000 0.0323480000 9554134 96830484 1770463232 3.4628126621 4.3245739937 4.9886050224 828 33.0800000000 0.0146112284 0.0093097307 0.0234041400 0.0079295086 0.1077590000 0.0111370000 0.0457040000 0.0000260000 0.0003130000 0.0275020000 9555808 96830484 1769193472 3.4625041485 4.3207631111 4.9941649437 829 33.1199999990 0.0145648438 0.0093160698 0.0234041400 0.0079506272 0.1128090000 0.0082550000 0.0459950000 0.0003290000 0.0003610000 0.0482360000 9557482 96830484 1770840064 3.4617795944 4.3175425529 5.0003771782 830 33.1600000000 0.0144506451 0.0093222561 0.0234041400 0.0079663728 0.1041000000 0.0105080000 0.0457400000 0.0000290000 0.0003240000 0.0275820000 9559156 96830484 1769684992 3.4611337185 4.3140349388 5.0062394142 831 33.2000000000 0.0143014351 0.0093282479 0.0234041400 0.0079839856 0.1077850000 0.0100470000 0.0425970000 0.0013190000 0.0002780000 0.0333680000 9560830 96830484 1768050688 3.4612655640 4.3089480400 5.0130481720 832 33.2400000000 0.0141460579 0.0093340385 0.0234041400 0.0079937720 0.1064070000 0.0084140000 0.0459940000 0.0000290000 0.0003800000 0.0279250000 9562504 96830484 1769840640 3.4605548382 4.3047413826 5.0195274353 833 33.2800000000 0.0139941080 0.0093396328 0.0234041400 0.0079967386 0.1279160000 0.0101320000 0.0512210000 0.0002980000 0.0002720000 0.0563620000 9564178 96830484 1768558592 3.4596030712 4.3012576103 5.0264129639 834 33.3200000000 0.0139315808 0.0093451387 0.0234041400 0.0080008105 0.1090850000 0.0080740000 0.0518370000 0.0000310000 0.0003710000 0.0277520000 9565852 96830484 1770176512 3.4588158131 4.2961168289 5.0329313278 835 33.3600000000 0.0137639912 0.0093504308 0.0234041400 0.0080073320 0.1090780000 0.0105340000 0.0450440000 0.0003230000 0.0002800000 0.0337180000 9567526 96830484 1768685568 3.4574878216 4.2933235168 5.0391111374 836 33.4000000000 0.0136679774 0.0093555953 0.0234041400 0.0080165424 0.1051380000 0.0084540000 0.0527000000 0.0000230000 0.0002920000 0.0274630000 9569200 96830484 1770479616 3.4566037655 4.2896428108 5.0458092690 837 33.4399999990 0.0135176536 0.0093605679 0.0234041400 0.0080319252 0.1141360000 0.0103490000 0.0426920000 0.0009390000 0.0003760000 0.0501670000 9570874 96830484 1769082880 3.4554553032 4.2869520187 5.0522036552 838 33.4800000000 0.0134433797 0.0093654400 0.0234041400 0.0080611646 0.0839900000 0.0085030000 0.0363390000 0.0000250000 0.0003520000 0.0290760000 9572548 96830484 1770729472 3.4550514221 4.2820529938 5.0581874847 839 33.5200000000 0.0132945431 0.0093701231 0.0234041400 0.0080921430 0.1259910000 0.0096650000 0.0536590000 0.0002950000 0.0002630000 0.0438990000 9574222 96830484 1769574400 3.4545063972 4.2794461250 5.0646343231 840 33.5600000000 0.0130950166 0.0093745575 0.0234041400 0.0081132610 0.1099050000 0.0104620000 0.0570440000 0.0000270000 0.0003240000 0.0307450000 9575896 96830484 1768054784 3.4522798061 4.2767796516 5.0692911148 841 33.6000000000 0.0128930761 0.0093787412 0.0234041400 0.0081158271 0.1141480000 0.0091630000 0.0449330000 0.0003190000 0.0002730000 0.0497080000 9577570 96830484 1769713664 3.4508697987 4.2745780945 5.0747709274 842 33.6400000000 0.0127184391 0.0093827076 0.0234041400 0.0081142846 0.0999900000 0.0101200000 0.0440420000 0.0000280000 0.0003260000 0.0285230000 9579244 96830484 1768525824 3.4494531155 4.2722830772 5.0798406601 843 33.6800000000 0.0125327902 0.0093864443 0.0234041400 0.0081141894 0.1074540000 0.0082830000 0.0455510000 0.0003910000 0.0002740000 0.0336710000 9580918 96830484 1770192896 3.4484107494 4.2687239647 5.0850868225 844 33.7200000000 0.0123616988 0.0093899695 0.0234041400 0.0081192932 0.1070260000 0.0105690000 0.0433020000 0.0000270000 0.0003170000 0.0284870000 9582592 96830484 1769050112 3.4476885796 4.2636761665 5.0899662971 845 33.7599999990 0.0121732969 0.0093932634 0.0234041400 0.0081301969 0.1286920000 0.0083560000 0.0438010000 0.0003220000 0.0002650000 0.0545980000 9584266 96830484 1770602496 3.4476125240 4.2603440285 5.0951604843 846 33.7999999990 0.0117664142 0.0093960685 0.0234041400 0.0081372652 0.1076350000 0.0104190000 0.0447710000 0.0000250000 0.0003830000 0.0289930000 9585940 96830484 1769177088 3.4464166164 4.2576856613 5.0997395515 847 33.8400000000 0.0114463633 0.0093984892 0.0234041400 0.0081360981 0.1085310000 0.0084820000 0.0433290000 0.0003160000 0.0002710000 0.0335840000 9587614 96830484 1770729472 3.4456198215 4.2526707649 5.1033773422 848 33.8800000000 0.0111616468 0.0094005684 0.0234041400 0.0081316447 0.0916150000 0.0102930000 0.0417150000 0.0000110000 0.0001110000 0.0297020000 9589288 96830484 1769938944 3.4447584152 4.2489895821 5.1074609756 849 33.9200000000 0.0107934214 0.0094022090 0.0234041400 0.0081268836 0.1244030000 0.0085180000 0.0507620000 0.0003690000 0.0002700000 0.0544770000 9590962 96830484 1768828928 3.4439668655 4.2432546616 5.1110267639 850 33.9600000000 0.0105347205 0.0094035413 0.0234041400 0.0081224328 0.1079560000 0.0086160000 0.0528910000 0.0000290000 0.0003870000 0.0299720000 9592636 96830484 1770557440 3.4431986809 4.2393631935 5.1146960258 851 34.0000000000 0.0103179747 0.0094046159 0.0234041400 0.0081176833 0.1070710000 0.0099500000 0.0410790000 0.0003000000 0.0002720000 0.0340110000 9594310 96830484 1769336832 3.4423029423 4.2363219261 5.1186394691 852 34.0400000000 0.0101552987 0.0094054970 0.0234041400 0.0081129359 0.1073660000 0.0085710000 0.0464020000 0.0000280000 0.0003110000 0.0287110000 9595984 96830484 1770983424 3.4426252842 4.2310047150 5.1225013733 853 34.0800000000 0.0098382831 0.0094060043 0.0234041400 0.0081104890 0.1094250000 0.0106340000 0.0371170000 0.0002950000 0.0002650000 0.0512500000 9597658 96830484 1769701376 3.4416742325 4.2268700600 5.1254968643 854 34.1199999990 0.0095137870 0.0094061305 0.0234041400 0.0081088307 0.1068600000 0.0105700000 0.0450480000 0.0000270000 0.0003130000 0.0288180000 9599332 96830484 1768181760 3.4414384365 4.2240562439 5.1290454865 855 34.1600000000 0.0090836529 0.0094057534 0.0234041400 0.0081096980 0.1080370000 0.0084660000 0.0438200000 0.0003180000 0.0003490000 0.0342430000 9601006 96830484 1769984000 3.4417095184 4.2203431129 5.1325554848 856 34.2000000000 0.0087150522 0.0094049465 0.0234041400 0.0081096267 0.1476770000 0.0102770000 0.0849720000 0.0000260000 0.0004160000 0.0286970000 9602680 96830484 1768542208 3.4412145615 4.2171568871 5.1353816986 857 34.2400000000 0.0083650555 0.0094037331 0.0234041400 0.0081055255 0.1160760000 0.0083060000 0.0458800000 0.0003210000 0.0002730000 0.0514240000 9604354 96830484 1770336256 3.4401614666 4.2158069611 5.1382479668 858 34.2800000000 0.0080852835 0.0094021964 0.0234041400 0.0081009536 0.0944010000 0.0106110000 0.0512670000 0.0000260000 0.0003790000 0.0221470000 9606028 96830484 1768779776 3.4390001297 4.2133111954 5.1406335831 859 34.3200000000 0.0079318359 0.0094004847 0.0234041400 0.0080965272 0.0957730000 0.0091520000 0.0431100000 0.0003200000 0.0002780000 0.0328880000 9607702 96830484 1767809024 3.4393191338 4.2071647644 5.1425771713 860 34.3600000000 0.0075774812 0.0093983649 0.0234041400 0.0080920928 0.0880740000 0.0086570000 0.0426870000 0.0000270000 0.0002930000 0.0265160000 9609376 96830484 1769570304 3.4386868477 4.2019920349 5.1440424919 861 34.4000000000 0.0072054449 0.0093958180 0.0234041400 0.0080877769 0.1162810000 0.0100070000 0.0438330000 0.0011670000 0.0003430000 0.0509270000 9611050 96830484 1768304640 3.4383511543 4.1982941628 5.1465358734 862 34.4400000000 0.0068416530 0.0093928549 0.0234041400 0.0080831091 0.0971190000 0.0084830000 0.0419840000 0.0000290000 0.0003920000 0.0292130000 9612724 96830484 1770049536 3.4382276535 4.1939520836 5.1484861374 863 34.4800000000 0.0064997002 0.0093895025 0.0234041400 0.0080787465 0.1083180000 0.0104710000 0.0461080000 0.0003200000 0.0002880000 0.0341120000 9614398 96830484 1768681472 3.4380850792 4.1873660088 5.1496939659 864 34.5200000000 0.0060804086 0.0093856725 0.0234041400 0.0080744193 0.0886120000 0.0088190000 0.0361220000 0.0000250000 0.0003820000 0.0302530000 9616072 96830484 1770459136 3.4382736683 4.1836471558 5.1514587402 865 34.5600000000 0.0058761244 0.0093816152 0.0234041400 0.0080697500 0.1547500000 0.0098980000 0.0764980000 0.0000610000 0.0000530000 0.0583110000 9617746 96830484 1769209856 3.4373314381 4.1823906898 5.1531662941 866 34.6000000000 0.0058054565 0.0093774857 0.0234041400 0.0080672612 0.1008300000 0.0088800000 0.0564240000 0.0000280000 0.0003030000 0.0248900000 9619420 96830484 1770856448 3.4360997677 4.1808915138 5.1542882919 867 34.6400000000 0.0056636957 0.0093732022 0.0234041400 0.0080639948 0.1077660000 0.0113480000 0.0454760000 0.0003230000 0.0002810000 0.0337980000 9621094 96830484 1769558016 3.4363296032 4.1781005859 5.1559152603 868 34.6800000000 0.0056597078 0.0093689240 0.0234041400 0.0080598790 0.0894630000 0.0102720000 0.0377300000 0.0000300000 0.0003110000 0.0303280000 9622768 96830484 1768054784 3.4357051849 4.1743249893 5.1566691399 869 34.7200000000 0.0054676021 0.0093644346 0.0234041400 0.0080556353 0.1475760000 0.0098760000 0.0666810000 0.0003240000 0.0002730000 0.0603150000 9624442 96830484 1767170048 3.4363102913 4.1708297729 5.1577215195 870 34.7600000000 0.0053771418 0.0093598515 0.0234041400 0.0080512786 0.1060150000 0.0084090000 0.0467440000 0.0000270000 0.0003740000 0.0345650000 9626116 96830484 1768824832 3.4353466034 4.1681771278 5.1581935883 871 34.8000000000 0.0053591453 0.0093552582 0.0234041400 0.0080466514 0.1278840000 0.0079620000 0.0644400000 0.0003010000 0.0002720000 0.0374800000 9627790 96830484 1770463232 3.4343764782 4.1663417816 5.1589269638 872 34.8400000000 0.0052680951 0.0093505711 0.0234041400 0.0080423951 0.1094780000 0.0099460000 0.0500790000 0.0000280000 0.0003800000 0.0383620000 9629464 96830484 1769320448 3.4332933426 4.1631369591 5.1595563889 873 34.8800000000 0.0051404312 0.0093457485 0.0234041400 0.0080379411 0.1327220000 0.0082330000 0.0619580000 0.0003180000 0.0003520000 0.0518550000 9631138 96830484 1770856448 3.4328896999 4.1610379219 5.1609320641 874 34.9200000000 0.0051960330 0.0093410006 0.0234041400 0.0080340508 0.1017010000 0.0107750000 0.0449460000 0.0000300000 0.0003840000 0.0291000000 9632812 96830484 1769414656 3.4321920872 4.1598315239 5.1621184349 875 34.9600000000 0.0050678770 0.0093361170 0.0234041400 0.0080305382 0.0906100000 0.0088270000 0.0380550000 0.0002990000 0.0002770000 0.0331270000 9634486 96830484 1771130880 3.4306643009 4.1598458290 5.1635971069 876 35.0000000000 0.0051352964 0.0093313215 0.0234041400 0.0080267992 0.1048500000 0.0100680000 0.0402730000 0.0000270000 0.0002890000 0.0382280000 9636160 96830484 1769558016 3.4298913479 4.1590318680 5.1649417877 877 35.0400000000 0.0050764759 0.0093264699 0.0234041400 0.0080222343 0.1365040000 0.0102190000 0.0550050000 0.0003200000 0.0002750000 0.0605490000 9637834 96830484 1767923712 3.4290013313 4.1586966515 5.1663398743 878 35.0800000000 0.0051877159 0.0093217561 0.0234041400 0.0080178060 0.0965740000 0.0081940000 0.0394810000 0.0000270000 0.0003110000 0.0347430000 9639508 96830484 1769586688 3.4279804230 4.1590428352 5.1674957275 879 35.1200000000 0.0051598153 0.0093170212 0.0234041400 0.0080132651 0.1061590000 0.0100010000 0.0399570000 0.0003050000 0.0002780000 0.0384880000 9641182 96830484 1768452096 3.4271280766 4.1579728127 5.1685857773 880 35.1600000000 0.0051180124 0.0093122496 0.0234041400 0.0080090732 0.1101540000 0.0080050000 0.0631320000 0.0000270000 0.0003850000 0.0283790000 9642856 96830484 1770078208 3.4265038967 4.1588759422 5.1699271202 881 35.2000000000 0.0051857093 0.0093075657 0.0234041400 0.0080052118 0.1057320000 0.0108410000 0.0333600000 0.0001390000 0.0001050000 0.0511200000 9644530 96830484 1768558592 3.4254567623 4.1587615013 5.1712312698 882 35.2400000000 0.0050800606 0.0093027726 0.0234041400 0.0080018208 0.1099180000 0.0087890000 0.0578220000 0.0000260000 0.0003100000 0.0317820000 9646204 96830484 1770094592 3.4260027409 4.1547079086 5.1718630791 ================================================ FILE: icra2018_results/tegra/memory_lsdslam_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 04:30:01 Properties: ================= frame-limit: 0 log-file: output//memory_lsdslam_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0403960000 86789171 0 1770831872 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0010192674 0.0005096337 0.0010192674 0.0016461832 0.1277050000 98511908 0 1779458048 -0.0006004850 -0.0001168514 0.0001065529 3 0.0800000000 0.0050369492 0.0020187388 0.0050369492 0.0023323772 0.1242850000 101782498 0 1783267328 -0.0005712212 -0.0001159408 -0.0002626191 4 0.1200000000 0.0030104611 0.0022666694 0.0050369492 0.0021966427 0.1047580000 101784080 0 1784156160 -0.0008395689 -0.0004368157 -0.0003820120 5 0.1600000000 0.0058183502 0.0029770056 0.0058183502 0.0019631229 0.0969810000 101785670 0 1784664064 -0.0009796099 -0.0000026681 -0.0002612149 6 0.2000000000 0.0051384396 0.0033372446 0.0058183502 0.0018813674 0.0981920000 101787580 0 1785171968 -0.0005846015 -0.0000756629 -0.0006002688 7 0.2400000000 0.0052057360 0.0036041719 0.0058183502 0.0017249274 0.0963920000 101788834 0 1785679872 -0.0005683512 0.0000713196 -0.0004218031 8 0.2800000000 0.0065800366 0.0039761550 0.0065800366 0.0016589873 0.0958290000 101790088 0 1786187776 -0.0006064161 0.0001757641 -0.0005147499 9 0.3200000000 0.0080526276 0.0044290964 0.0080526276 0.0016338017 0.1087700000 101792014 0 1786822656 -0.0010380618 0.0000522985 -0.0005211149 10 0.3600000000 0.0081044836 0.0047966351 0.0081044836 0.0016452099 0.1095000000 101794580 0 1787330560 -0.0013087967 0.0000751047 -0.0004509388 11 0.4000000000 0.0093985079 0.0052149872 0.0093985079 0.0018086935 0.0935730000 101795834 0 1787838464 -0.0008956442 0.0000751497 -0.0001809046 12 0.4400000000 0.0094707115 0.0055696309 0.0094707115 0.0021760242 0.1013130000 101797088 0 1785970688 -0.0007592409 -0.0000004653 -0.0004498172 13 0.4800000000 0.0110083176 0.0059879914 0.0110083176 0.0022165767 0.0932590000 101798342 0 1786064896 -0.0016797759 -0.0000336222 -0.0001003948 14 0.5200000000 0.0109668421 0.0063436236 0.0110083176 0.0021936693 0.1290880000 101799596 0 1786699776 -0.0019601998 -0.0010239633 -0.0000114675 15 0.5600000000 0.0139693972 0.0068520085 0.0139693972 0.0021532663 0.0999940000 101800850 0 1787207680 -0.0020311738 0.0001297701 -0.0003221621 16 0.6000000000 0.0133044329 0.0072552850 0.0139693972 0.0022222525 0.0968130000 101802104 0 1787330560 -0.0015770770 -0.0000095433 -0.0005183020 17 0.6400000000 0.0138059678 0.0076406193 0.0139693972 0.0022506147 0.0952150000 101804702 0 1787711488 -0.0031563127 -0.0012518218 -0.0008958530 18 0.6800000000 0.0174066201 0.0081831749 0.0174066201 0.0023576268 0.0997690000 101808580 0 1785970688 -0.0016305163 -0.0045932359 -0.0006293858 19 0.7200000000 0.0175940525 0.0086784842 0.0175940525 0.0025287944 0.0836120000 101809834 0 1785970688 -0.0023679067 -0.0004590496 -0.0013908840 20 0.7600000000 0.0203371495 0.0092614175 0.0203371495 0.0025887978 0.0857380000 101811088 0 1786572800 -0.0026742879 -0.0005095035 -0.0014838526 21 0.8000000000 0.0241026115 0.0099681410 0.0241026115 0.0025306111 0.0929630000 101812342 0 1787080704 -0.0018643828 -0.0001886232 -0.0016553181 22 0.8400000000 0.0295360908 0.0108575933 0.0295360908 0.0026147085 0.0953560000 101813596 0 1787334656 -0.0021180592 -0.0002901079 -0.0015466685 23 0.8800000000 0.0290697664 0.0116494269 0.0295360908 0.0025784997 0.0998500000 101814850 0 1787584512 -0.0020464342 0.0000018626 -0.0023590252 24 0.9200000000 0.0353328027 0.0126362342 0.0353328027 0.0028168712 0.1072840000 101816104 0 1788092416 -0.0040983660 -0.0000607162 -0.0031312595 25 0.9600000000 0.0355542935 0.0135529566 0.0355542935 0.0027710757 0.0855950000 101817358 0 1785970688 -0.0050165136 0.0009018445 -0.0037801615 26 1.0000000000 0.0407121740 0.0145975419 0.0407121740 0.0028418536 0.1170200000 101818612 0 1785171968 -0.0061556743 0.0006631495 -0.0029550409 27 1.0400000000 0.0460832566 0.0157636795 0.0460832566 0.0030270922 0.0952960000 101819866 0 1785171968 -0.0064671142 0.0004708096 -0.0043465942 28 1.0800000000 0.0490001515 0.0169506963 0.0490001515 0.0033444868 0.1024960000 101821120 0 1785679872 -0.0083510950 -0.0004519974 -0.0040306961 29 1.1200000000 0.0525595061 0.0181785863 0.0525595061 0.0036697888 0.1023120000 101822374 0 1786187776 -0.0109448284 -0.0000379827 -0.0050467951 30 1.1600000000 0.0573767237 0.0194851909 0.0573767237 0.0041520138 0.1661480000 101823628 0 1786568704 -0.0156682190 -0.0000791074 -0.0038885016 31 1.2000000000 0.0600685775 0.0207943324 0.0600685775 0.0043312046 0.1409640000 101824882 0 1786695680 -0.0195193309 -0.0003718798 -0.0041893553 32 1.2400000000 0.0643006638 0.0221539053 0.0643006638 0.0044643146 0.1385410000 101826136 0 1787330560 -0.0222020932 -0.0007061152 -0.0050116563 33 1.2800000000 0.0680424720 0.0235444679 0.0680424720 0.0045866968 0.1210550000 101830078 0 1787838464 -0.0239877198 -0.0007081559 -0.0050798859 34 1.3200000000 0.0855101496 0.0253669879 0.0855101496 0.0055831589 0.1314140000 101836580 0 1786060800 -0.0347751044 -0.0007887363 -0.0049192882 35 1.3600000000 0.0872021392 0.0271337065 0.0872021392 0.0057592991 0.1243360000 101837834 0 1786187776 -0.0366729945 -0.0007462856 -0.0058052153 36 1.4000000000 0.0903559625 0.0288898803 0.0903559625 0.0061903276 0.1221450000 101839088 0 1786695680 -0.0393485166 -0.0010604571 -0.0064361827 37 1.4400000000 0.0969478339 0.0307292845 0.0969478339 0.0064239432 0.1160490000 101840342 0 1787330560 -0.0434892885 -0.0008661391 -0.0057029598 38 1.4800000000 0.1035949364 0.0326468016 0.1035949364 0.0065363723 0.2000750000 114180380 0 1787076608 -0.0486340076 -0.0006415468 -0.0051555680 39 1.5200000000 0.1064773276 0.0345398920 0.1064773276 0.0064705126 0.0959490000 117839682 0 1787584512 -0.0491356030 -0.0009606312 -0.0063160397 40 1.5600000000 0.1132199168 0.0365068927 0.1132199168 0.0064297140 0.1196750000 121033032 0 1785462784 -0.0522792265 -0.0013137306 -0.0061512156 41 1.6000000000 0.1197378337 0.0385369156 0.1197378337 0.0063955904 0.0957070000 121034286 0 1784983552 -0.0560408421 -0.0018513507 -0.0056608221 42 1.6400000000 0.1286498159 0.0406824609 0.1286498159 0.0064276900 0.0873770000 121035540 0 1784918016 -0.0603383929 -0.0006434981 -0.0049930047 43 1.6800000000 0.1333017945 0.0428363989 0.1333017945 0.0063694945 0.0945050000 121036794 0 1785425920 -0.0623640157 -0.0006048982 -0.0036623699 44 1.7200000000 0.1370738596 0.0449781593 0.1370738596 0.0063149847 0.0830300000 121038048 0 1785933824 -0.0649211630 -0.0013825274 -0.0045124171 45 1.7600000000 0.1418684423 0.0471312767 0.1418684423 0.0062740913 0.0798760000 121039302 0 1786314752 -0.0684483945 -0.0011991458 -0.0031572122 46 1.8000000000 0.1459868252 0.0492803104 0.1459868252 0.0062097267 0.0837680000 121040556 0 1786441728 -0.0702853426 -0.0000961047 -0.0036110729 47 1.8400000000 0.1493941247 0.0514103915 0.1493941247 0.0062227317 0.0898020000 121041810 0 1786949632 -0.0699011236 -0.0000683115 -0.0032839077 48 1.8800000000 0.1525115073 0.0535166648 0.1525115073 0.0061727624 0.0906270000 121043064 0 1787457536 -0.0712789521 -0.0000058564 -0.0029623264 49 1.9200000000 0.1568023711 0.0556245363 0.1568023711 0.0061523500 0.0937070000 121044318 0 1787965440 -0.0742351860 -0.0000374449 -0.0031260466 50 1.9600000000 0.1663611084 0.0578392678 0.1663611084 0.0063305015 0.0952910000 121045572 0 1786118144 -0.0789800286 0.0001922186 -0.0007714225 51 2.0000000000 0.1646321267 0.0599332454 0.1663611084 0.0062691031 0.0894180000 121046826 0 1785491456 -0.0790327266 -0.0014121289 -0.0016565060 52 2.0400000000 0.1675969064 0.0620037004 0.1675969064 0.0062190152 0.1087570000 121048080 0 1785491456 -0.0800501257 -0.0005165207 -0.0021492448 53 2.0800000000 0.1688640267 0.0640199330 0.1688640267 0.0062147252 0.1062030000 121049334 0 1786060800 -0.0808072686 -0.0011313070 -0.0032754063 54 2.1200000000 0.1772439331 0.0661166737 0.1772439331 0.0062195089 0.1012060000 121050588 0 1786568704 -0.0854749158 -0.0015865732 -0.0011929281 55 2.1600000000 0.1786862314 0.0681633930 0.1786862314 0.0062014509 0.1030870000 121051842 0 1786822656 -0.0862825438 -0.0015682332 -0.0012429463 56 2.2000000000 0.1919633746 0.0703741069 0.1919633746 0.0063137391 0.1141800000 121053096 0 1787076608 -0.0930492207 -0.0005078338 0.0018320929 57 2.2400000000 0.1952913553 0.0725656376 0.1952913553 0.0062723678 0.1114930000 121054350 0 1787584512 -0.0946560651 -0.0012937963 0.0022927416 58 2.2800000000 0.2007973045 0.0747765284 0.2007973045 0.0063730642 0.1128240000 121055604 0 1786118144 -0.0985274836 -0.0018216078 0.0036767516 59 2.3200000000 0.2106232196 0.0770790147 0.2106232196 0.0067582048 0.1122930000 121056858 0 1786118144 -0.1029786617 -0.0007484062 0.0055058072 60 2.3600000000 0.2125504464 0.0793368719 0.2125504464 0.0068116232 0.1142870000 121058112 0 1786593280 -0.1041355655 -0.0010752575 0.0052097286 61 2.4000000000 0.2172030210 0.0815969727 0.2172030210 0.0069252846 0.1195310000 121059366 0 1787076608 -0.1062975004 -0.0009658473 0.0052241022 62 2.4400000000 0.2334515750 0.0840462405 0.2334515750 0.0076095245 0.1175230000 121060620 0 1787457536 -0.1141443700 -0.0009315339 0.0087441392 63 2.4800000000 0.2387628257 0.0865020593 0.2387628257 0.0077835200 0.1280030000 121061874 0 1787703296 -0.1175163016 -0.0009856630 0.0096839033 64 2.5200000000 0.2462916523 0.0889987717 0.2462916523 0.0082246121 0.1137880000 121063128 0 1786109952 -0.1227097511 -0.0007826474 0.0113295736 65 2.5600000000 0.2572418153 0.0915871262 0.2572418153 0.0086204508 0.1220480000 121069758 0 1786109952 -0.1257663220 0.0003894773 0.0125722708 66 2.6000000000 0.2623173892 0.0941739484 0.2623173892 0.0088011315 0.1163990000 121081508 0 1786585088 -0.1314666420 0.0013748839 0.0131324045 67 2.6400000000 0.2714349926 0.0968196356 0.2714349926 0.0088960421 0.3157100000 139913698 0 1785962496 -0.1326480955 0.0019592273 0.0141250091 68 2.6800000000 0.2740630507 0.0994261564 0.2740630507 0.0088869646 0.1135540000 143572800 0 1786560512 -0.1410933435 0.0025807831 0.0144534279 69 2.7200000000 0.2804259062 0.1020493412 0.2804259062 0.0088478424 0.1030320000 146766150 0 1785073664 -0.1445049793 0.0029424820 0.0162140094 70 2.7600000000 0.2863983214 0.1046828980 0.2863983214 0.0087977167 0.0866800000 146767404 0 1785294848 -0.1474036723 0.0032726619 0.0160177704 71 2.8000000000 0.2908037007 0.1073043178 0.2908037007 0.0087591917 0.0826640000 146768658 0 1784070144 -0.1499914527 0.0036285678 0.0149056390 72 2.8400000000 0.3011327386 0.1099963792 0.3011327386 0.0088186243 0.0865610000 146769912 0 1784070144 -0.1558689773 0.0058258707 0.0157219935 73 2.8800000000 0.3076897860 0.1127045081 0.3076897860 0.0087747666 0.0825200000 146771166 0 1784426496 -0.1593580693 0.0061266497 0.0163147114 74 2.9200000000 0.3084312379 0.1153494639 0.3084312379 0.0087777664 0.0878630000 146772420 0 1785061376 -0.1605761051 0.0072926530 0.0152676115 75 2.9600000000 0.3094812334 0.1179378875 0.3094812334 0.0087656631 0.0931390000 146773674 0 1785442304 -0.1607934386 0.0085623395 0.0141087435 76 3.0000000000 0.3070740402 0.1204265211 0.3094812334 0.0087716127 0.0903850000 146774928 0 1785442304 -0.1609349698 0.0093191108 0.0111935809 77 3.0400000000 0.3058043122 0.1228340248 0.3094812334 0.0087704382 0.0908950000 146776182 0 1786052608 -0.1624144912 0.0103263780 0.0095799780 78 3.0800000000 0.3069617450 0.1251946366 0.3094812334 0.0087659300 0.0919070000 146777436 0 1786560512 -0.1594237685 0.0102999518 0.0063210814 79 3.1200000000 0.3114919364 0.1275528303 0.3114919364 0.0087476098 0.0903530000 146778690 0 1787068416 -0.1617866904 0.0115927914 0.0055054408 80 3.1600000000 0.3134737313 0.1298768416 0.3134737313 0.0087315322 0.0980530000 146779944 0 1787576320 -0.1632328033 0.0135562662 0.0043614320 81 3.2000000000 0.3214270771 0.1322416593 0.3214270771 0.0087521547 0.0889680000 146781198 0 1788084224 -0.1672520936 0.0126691861 0.0052987547 82 3.2400000000 0.3271830678 0.1346189935 0.3271830678 0.0087892711 0.0928250000 146782452 0 1786220544 -0.1699357033 0.0130136795 0.0050843102 83 3.2800000000 0.3321548104 0.1369989431 0.3321548104 0.0088726517 0.0955880000 146783706 0 1785462784 -0.1727226675 0.0139959315 0.0040165968 84 3.3200000000 0.3403632939 0.1394199473 0.3403632939 0.0089336685 0.0923980000 146784960 0 1785462784 -0.1770230830 0.0137648182 0.0040442226 85 3.3600000000 0.3491875827 0.1418878018 0.3491875827 0.0090055866 0.0980810000 146786214 0 1785958400 -0.1817945242 0.0144924475 0.0042581544 86 3.4000000000 0.3592995405 0.1444158453 0.3592995405 0.0091448772 0.0942830000 146787468 0 1786466304 -0.1865257323 0.0149873290 0.0054204720 87 3.4400000000 0.3656403422 0.1469586556 0.3656403422 0.0092904121 0.2706930000 159093142 0 1785962496 -0.1899069995 0.0142557556 0.0053101052 88 3.4800000000 0.3740038872 0.1495387151 0.3740038872 0.0094795904 0.1107320000 162752652 0 1786564608 -0.1945840418 0.0140960952 0.0048233559 89 3.5200000000 0.3801400363 0.1521297412 0.3801400363 0.0096347373 0.0875260000 165946002 0 1786945536 -0.1977722496 0.0143603971 0.0048310268 90 3.5600000000 0.3847074807 0.1547139383 0.3847074807 0.0097299221 0.0862410000 165947256 0 1785094144 -0.2006639689 0.0139332088 0.0047941692 91 3.6000000000 0.3940753937 0.1573442839 0.3940753937 0.0098491337 0.0744000000 165948510 0 1785094144 -0.2058265209 0.0133748082 0.0058844411 92 3.6400000000 0.4038735628 0.1600239500 0.4038735628 0.0099503863 0.0815880000 165949764 0 1785569280 -0.2113184929 0.0142174996 0.0077501321 93 3.6800000000 0.4068566561 0.1626780651 0.4068566561 0.0099280867 0.0854940000 165951018 0 1786077184 -0.2130350769 0.0138168084 0.0067035449 94 3.7200000000 0.4116717875 0.1653269345 0.4116717875 0.0099035882 0.0824720000 165952272 0 1786458112 -0.2154244184 0.0130082844 0.0065678246 95 3.7600000000 0.4202312231 0.1680101375 0.4202312231 0.0099428093 0.0810750000 165953526 0 1786458112 -0.2200245112 0.0138787469 0.0090536252 96 3.8000000000 0.4268130958 0.1707060017 0.4268130958 0.0099401043 0.0776720000 165954780 0 1787068416 -0.2235872597 0.0138840731 0.0089071477 97 3.8400000000 0.4306936860 0.1733862871 0.4306936860 0.0098979791 0.0883680000 165956034 0 1787576320 -0.2252798676 0.0127979182 0.0096284514 98 3.8800000000 0.4397839010 0.1761046301 0.4397839010 0.0099321604 0.0782120000 165957288 0 1788084224 -0.2308239192 0.0126727670 0.0115686338 99 3.9200000000 0.4437326491 0.1788079434 0.4437326491 0.0099007032 0.0817000000 165958542 0 1785962496 -0.2324966788 0.0136397230 0.0124858413 100 3.9600000000 0.4491146505 0.1815110105 0.4491146505 0.0098681630 0.0928550000 165959796 0 1785315328 -0.2354813367 0.0132174576 0.0141179049 101 4.0000000000 0.4549082220 0.1842179136 0.4549082220 0.0098308129 0.0904130000 165961050 0 1785315328 -0.2384860814 0.0124808550 0.0162986685 102 4.0400000000 0.4573957622 0.1868961278 0.4573957622 0.0097871864 0.0892620000 165962304 0 1785810944 -0.2396504730 0.0119439298 0.0167749655 103 4.0800000000 0.4643587470 0.1895899396 0.4643587470 0.0097620852 0.0972960000 165963558 0 1786318848 -0.2436052412 0.0116786240 0.0195942819 104 4.1200000000 0.4730614424 0.1923156271 0.4730614424 0.0097802122 0.0956470000 165964812 0 1786699776 -0.2481601238 0.0113258483 0.0243425574 105 4.1600000000 0.4751228690 0.1950090294 0.4751228690 0.0097563465 0.0956890000 165966066 0 1786699776 -0.2489835918 0.0110477526 0.0249507502 106 4.2000000000 0.4796699882 0.1976945102 0.4796699882 0.0097646795 0.0892950000 165967320 0 1787322368 -0.2511102557 0.0109400684 0.0264250226 107 4.2400000000 0.4800687432 0.2003335217 0.4800687432 0.0097299765 0.0893830000 165968574 0 1787830272 -0.2508455217 0.0104340622 0.0251630358 108 4.2800000000 0.4866400063 0.2029845077 0.4866400063 0.0097058582 0.0897310000 165969828 0 1785962496 -0.2543988228 0.0103207845 0.0281216577 109 4.3200000000 0.4877740741 0.2055972560 0.4877740741 0.0096718248 0.0926690000 165971082 0 1785417728 -0.2551061809 0.0107178232 0.0286552869 110 4.3600000000 0.4930076003 0.2082100773 0.4930076003 0.0096867540 0.0961530000 165972336 0 1785417728 -0.2581960261 0.0100554153 0.0321812220 111 4.4000000000 0.4974313974 0.2108156748 0.4974313974 0.0096880016 0.2453510000 178275570 0 1787703296 -0.2605571151 0.0092668608 0.0346407257 112 4.4400000000 0.5024985075 0.2134199858 0.5024985075 0.0096963698 0.1087870000 181934672 0 1785962496 -0.2638903856 0.0111531047 0.0377927795 113 4.4800000000 0.5051602125 0.2160017577 0.5051602125 0.0096928455 0.0794140000 185128022 0 1785925632 -0.2657294273 0.0093026869 0.0394728296 114 4.5200000000 0.5135342479 0.2186116918 0.5135342479 0.0097699125 0.0790990000 185129276 0 1784057856 -0.2690336704 0.0099213598 0.0440970212 115 4.5600000000 0.5143860579 0.2211836428 0.5143860579 0.0097583735 0.0695980000 185130530 0 1784057856 -0.2691613138 0.0099271284 0.0445166826 116 4.6000000000 0.5220249295 0.2237771022 0.5220249295 0.0098436793 0.0717790000 185131784 0 1784532992 -0.2728488147 0.0113700656 0.0491429269 117 4.6400000000 0.5280563235 0.2263777793 0.5280563235 0.0098738951 0.0771100000 185133038 0 1785040896 -0.2754949331 0.0128824841 0.0528927445 118 4.6800000000 0.5320696831 0.2289683887 0.5320696831 0.0098412381 0.0703150000 185134292 0 1785421824 -0.2774558067 0.0120930150 0.0543311760 119 4.7200000000 0.5367418528 0.2315547203 0.5367418528 0.0098036900 0.0711350000 185135546 0 1785417728 -0.2797791958 0.0117449444 0.0570881218 120 4.7600000000 0.5419793725 0.2341415924 0.5419793725 0.0097704644 0.0702460000 185136800 0 1786036224 -0.2821798325 0.0126319155 0.0601052418 121 4.8000000000 0.5499494672 0.2367515748 0.5499494672 0.0097474276 0.0813750000 185138054 0 1786544128 -0.2855708301 0.0128362654 0.0668155998 122 4.8400000000 0.5510703325 0.2393279581 0.5510703325 0.0097098883 0.0774070000 185139308 0 1787052032 -0.2861052752 0.0130581530 0.0670086220 123 4.8800000000 0.5555904508 0.2418991979 0.5555904508 0.0096925691 0.0767950000 185140562 0 1787559936 -0.2879988551 0.0144348331 0.0691579431 124 4.9200000000 0.5635634065 0.2444932641 0.5635634065 0.0097022347 0.0869560000 185141816 0 1788067840 -0.2912820876 0.0152677530 0.0750664547 125 4.9600000000 0.5669167638 0.2470726521 0.5669167638 0.0096884070 0.0793490000 185143070 0 1785946112 -0.2929042578 0.0152141396 0.0771134570 126 5.0000000000 0.5702695251 0.2496377066 0.5702695251 0.0096733318 0.0809330000 185144324 0 1785204736 -0.2952197492 0.0167719964 0.0803865269 127 5.0400000000 0.5793841481 0.2522341353 0.5793841481 0.0096625807 0.0876740000 185145578 0 1785204736 -0.2980814874 0.0169406775 0.0860854685 128 5.0800000000 0.5833221078 0.2548207601 0.5833221078 0.0096333247 0.0865270000 185146832 0 1785683968 -0.3003130555 0.0178292599 0.0886763781 129 5.1200000000 0.5871689320 0.2573971025 0.5871689320 0.0096042669 0.0871310000 185158838 0 1786191872 -0.3014850914 0.0170775410 0.0908955857 130 5.1600000000 0.5956909657 0.2599993630 0.5956909657 0.0096341896 0.0989760000 185181084 0 1786544128 -0.3044962585 0.0171563644 0.0974797383 131 5.2000000000 0.5992580652 0.2625891241 0.5992580652 0.0096502122 0.0867240000 185182338 0 1786671104 -0.3052431047 0.0185596105 0.0986716822 132 5.2400000000 0.5985656381 0.2651344007 0.5992580652 0.0096407069 0.0908580000 185183592 0 1787179008 -0.3058215678 0.0176202320 0.0982448906 133 5.2800000000 0.6084734201 0.2677158971 0.6084734201 0.0096858399 0.0925920000 185184846 0 1787686912 -0.3093174994 0.0179097857 0.1051143557 134 5.3200000000 0.6173092723 0.2703248029 0.6173092723 0.0097501343 0.2359140000 197491004 0 1787310080 -0.3121552765 0.0188397598 0.1108358204 135 5.3600000000 0.6196236610 0.2729122018 0.6196236610 0.0097593948 0.0806960000 201150106 0 1787813888 -0.3136005700 0.0190621782 0.1127997190 136 5.4000000000 0.6257668138 0.2755067210 0.6257668138 0.0098141125 0.1150120000 204343456 0 1785946112 -0.3164344132 0.0194947403 0.1176664755 137 5.4400000000 0.6306478381 0.2780989919 0.6306478381 0.0098644273 0.0855120000 204344710 0 1786167296 -0.3183650076 0.0203127265 0.1213771850 138 5.4800000000 0.6350725293 0.2806857567 0.6350725293 0.0099011492 0.0724750000 204345964 0 1786675200 -0.3203390539 0.0200729240 0.1231066957 139 5.5200000000 0.6397325397 0.2832688271 0.6397325397 0.0099427515 0.0692890000 204347218 0 1787310080 -0.3225022554 0.0196261592 0.1252690852 140 5.5600000000 0.6486890912 0.2858789718 0.6486890912 0.0100490751 0.0717720000 204348472 0 1787305984 -0.3254937232 0.0201435611 0.1304084957 141 5.6000000000 0.6532323956 0.2884843153 0.6532323956 0.0100841143 0.0858840000 204349726 0 1787686912 -0.3274008632 0.0203686543 0.1322867423 142 5.6400000000 0.6621269584 0.2911156015 0.6621269584 0.0101526183 0.0846960000 204350980 0 1786093568 -0.3305256963 0.0205939580 0.1376258433 143 5.6800000000 0.6675658822 0.2937481209 0.6675658822 0.0102259989 0.0755460000 204352234 0 1786093568 -0.3323757052 0.0216164291 0.1412525028 144 5.7200000000 0.6732456684 0.2963835206 0.6732456684 0.0102764313 0.0780070000 204353488 0 1786568704 -0.3345069289 0.0221333131 0.1441175938 145 5.7600000000 0.6780995727 0.2990160451 0.6780995727 0.0102797440 0.0904750000 204354742 0 1787076608 -0.3364561796 0.0217931904 0.1466945261 146 5.8000000000 0.6838271022 0.3016517372 0.6838271022 0.0102796446 0.0765670000 204355996 0 1787457536 -0.3384586275 0.0218819156 0.1501446217 147 5.8400000000 0.6950677633 0.3043280367 0.6950677633 0.0102960415 0.0807080000 204357250 0 1787559936 -0.3419132829 0.0218538828 0.1576835066 148 5.8800000000 0.6967379451 0.3069794550 0.6967379451 0.0102715452 0.0951200000 204358504 0 1788067840 -0.3423889577 0.0217575543 0.1588755399 149 5.9200000000 0.7021251917 0.3096314398 0.7021251917 0.0102576888 0.0904090000 204359758 0 1786093568 -0.3438850641 0.0220236182 0.1627967954 150 5.9600000000 0.7064827085 0.3122771150 0.7064827085 0.0102370428 0.0895890000 204361012 0 1785298944 -0.3451197445 0.0219351668 0.1660286933 151 6.0000000000 0.7110495567 0.3149179921 0.7110495567 0.0102150896 0.2416450000 216663014 0 1787432960 -0.3462056220 0.0222337842 0.1693883836 152 6.0400000000 0.7151370049 0.3175510119 0.7151370049 0.0102097029 0.1154360000 220322116 0 1785311232 -0.3475646079 0.0234801602 0.1740113050 153 6.0800000000 0.7192817330 0.3201767029 0.7192817330 0.0101965049 0.0910650000 223515466 0 1785692160 -0.3490438461 0.0228406768 0.1772301942 154 6.1200000000 0.7244675756 0.3228019683 0.7244675756 0.0102233302 0.0756180000 223516720 0 1785913344 -0.3511894047 0.0225636885 0.1821924448 155 6.1600000000 0.7278093696 0.3254149193 0.7278093696 0.0102526793 0.0737390000 223517974 0 1784688640 -0.3514260948 0.0231957659 0.1849165708 156 6.2000000000 0.7352050543 0.3280417791 0.7352050543 0.0103496057 0.0785730000 223519228 0 1784688640 -0.3526974916 0.0230849274 0.1896995306 157 6.2400000000 0.7390022278 0.3306593616 0.7390022278 0.0104080449 0.0724440000 223520482 0 1785044992 -0.3538649976 0.0230909418 0.1940160841 158 6.2800000000 0.7461206317 0.3332888633 0.7461206317 0.0104823876 0.0769730000 223521736 0 1785552896 -0.3543536961 0.0235638246 0.1993865669 159 6.3200000000 0.7486549616 0.3359012287 0.7486549616 0.0104917585 0.0780100000 223522990 0 1786060800 -0.3545030355 0.0233223271 0.2021942884 160 6.3600000000 0.7540528774 0.3385146765 0.7540528774 0.0105254767 0.0759660000 223524244 0 1786060800 -0.3547536135 0.0238053910 0.2076497823 161 6.4000000000 0.7569117546 0.3411134161 0.7569117546 0.0105038464 0.0806430000 223525498 0 1786544128 -0.3549450934 0.0236644112 0.2115329504 162 6.4400000000 0.7604390383 0.3437018459 0.7604390383 0.0104797875 0.2420360000 235827352 0 1786662912 -0.3548508286 0.0233563986 0.2156254053 163 6.4800000000 0.7651331425 0.3462873139 0.7651331425 0.0104641043 0.1096250000 239487294 0 1784516608 -0.3549914360 0.0238235556 0.2204719931 164 6.5200000000 0.7687261701 0.3488631606 0.7687261701 0.0104349902 0.0763100000 242680644 0 1787297792 -0.3551807702 0.0242688712 0.2249079943 165 6.5600000000 0.7752951980 0.3514475972 0.7752951980 0.0104045982 0.0793300000 242681898 0 1785810944 -0.3553781211 0.0249145329 0.2311642617 166 6.6000000000 0.7783526778 0.3540193146 0.7783526778 0.0103807911 0.0728910000 242683152 0 1785810944 -0.3551954925 0.0253710579 0.2354069203 167 6.6400000000 0.7819418311 0.3565817248 0.7819418311 0.0103550095 0.0691360000 242684406 0 1786286080 -0.3544251323 0.0256493222 0.2383809686 168 6.6800000000 0.7856276631 0.3591355697 0.7856276631 0.0103270489 0.0691140000 242685660 0 1786916864 -0.3542238176 0.0256500784 0.2432068735 169 6.7200000000 0.7900998592 0.3616856543 0.7900998592 0.0102986249 0.0760660000 242686914 0 1787297792 -0.3544889390 0.0252566878 0.2487178594 170 6.7600000000 0.7972372174 0.3642477223 0.7972372174 0.0103028253 0.0723510000 242688168 0 1787297792 -0.3551057875 0.0258583650 0.2548741102 171 6.8000000000 0.8000502586 0.3667962751 0.8000502586 0.0102913067 0.0754820000 242689422 0 1787932672 -0.3546607494 0.0267327037 0.2580031753 172 6.8400000000 0.8043819070 0.3693403776 0.8043819070 0.0102709757 0.0861630000 242690676 0 1785901056 -0.3544632494 0.0272247437 0.2626252472 173 6.8800000000 0.8098071814 0.3718864285 0.8098071814 0.0102522889 0.0798290000 242691930 0 1785307136 -0.3544661701 0.0278861765 0.2675212622 174 6.9200000000 0.8149161935 0.3744325766 0.8149161935 0.0102332352 0.0737340000 242693184 0 1785307136 -0.3549264967 0.0285196081 0.2720630169 175 6.9600000000 0.8190322518 0.3769731462 0.8190322518 0.0102120646 0.0863080000 242694438 0 1785782272 -0.3547048867 0.0289661475 0.2764002681 176 7.0000000000 0.8252726793 0.3795203026 0.8252726793 0.0101961476 0.0869520000 242695692 0 1786290176 -0.3551716805 0.0291148145 0.2816453576 177 7.0400000000 0.8273139596 0.3820502103 0.8273139596 0.0101868881 0.0868830000 242696946 0 1786671104 -0.3547866344 0.0280929171 0.2841733694 178 7.0800000000 0.8294712305 0.3845638115 0.8294712305 0.0101599772 0.0845600000 242698200 0 1786789888 -0.3543307185 0.0280307848 0.2866745889 179 7.1200000000 0.8346336484 0.3870781682 0.8346336484 0.0101504401 0.2955430000 255002910 0 1786683392 -0.3542712629 0.0287229512 0.2914314866 180 7.1600000000 0.8398844600 0.3895937587 0.8398844600 0.0101322287 0.1129070000 258662012 0 1784422400 -0.3537512124 0.0289259925 0.2954109907 181 7.2000000000 0.8428816199 0.3920981115 0.8428816199 0.0101044538 0.0823900000 261855362 0 1787043840 -0.3529670835 0.0292490758 0.2995298803 182 7.2400000000 0.8488826752 0.3946079168 0.8488826752 0.0100798589 0.0720800000 261856616 0 1785556992 -0.3527709246 0.0289577227 0.3043605089 183 7.2800000000 0.8561573029 0.3971300446 0.8561573029 0.0100593466 0.0760590000 261857870 0 1785556992 -0.3534481525 0.0297964364 0.3102976978 184 7.3200000000 0.8596983552 0.3996440028 0.8596983552 0.0100345289 0.0693880000 261859124 0 1786032128 -0.3524969220 0.0292860884 0.3136952519 185 7.3600000000 0.8648719192 0.4021587483 0.8648719192 0.0100188775 0.0736590000 261860378 0 1786540032 -0.3521735668 0.0294799246 0.3194408417 186 7.4000000000 0.8726631999 0.4046883421 0.8726631999 0.0100179632 0.0710020000 261861632 0 1786920960 -0.3520058095 0.0295402370 0.3258995116 187 7.4400000000 0.8744179010 0.4072002649 0.8744179010 0.0100060571 0.0705240000 261862886 0 1786920960 -0.3507229686 0.0293566138 0.3294228315 188 7.4800000000 0.8800787330 0.4097155759 0.8800787330 0.0100241411 0.0724910000 261864140 0 1787551744 -0.3500957489 0.0306585040 0.3342661560 189 7.5200000000 0.8865207434 0.4122383545 0.8865207434 0.0100109548 0.0732800000 261865394 0 1788059648 -0.3493975997 0.0313003846 0.3406423032 190 7.5600000000 0.8924891949 0.4147659905 0.8924891949 0.0099859756 0.0728660000 261866648 0 1785937920 -0.3479802310 0.0303374324 0.3454978466 191 7.6000000000 0.8985893726 0.4172990973 0.8985893726 0.0099856500 0.3424560000 274184446 0 1786793984 -0.3479679823 0.0313706808 0.3514595032 192 7.6400000000 0.9042173624 0.4198351299 0.9042173624 0.0099859615 0.1168890000 277843548 0 1784549376 -0.3464502394 0.0327632241 0.3561179340 193 7.6800000000 0.9120182395 0.4223853014 0.9120182395 0.0099641458 0.0758820000 281036898 0 1787297792 -0.3465333879 0.0319739506 0.3630455136 194 7.7200000000 0.9194725156 0.4249476067 0.9194725156 0.0099498943 0.0757770000 281038152 0 1785958400 -0.3465229869 0.0315765776 0.3687393069 195 7.7600000000 0.9249477386 0.4275117099 0.9249477386 0.0099621973 0.0731030000 281039406 0 1785958400 -0.3460325003 0.0316024087 0.3731586635 196 7.8000000000 0.9319409132 0.4300853283 0.9319409132 0.0100159442 0.0724190000 281040660 0 1786433536 -0.3453625739 0.0323707126 0.3790451586 197 7.8400000000 0.9366095662 0.4326565173 0.9366095662 0.0100520173 0.0711860000 281041914 0 1786941440 -0.3448157609 0.0335499234 0.3832895160 198 7.8800000000 0.9440625310 0.4352393760 0.9440625310 0.0100950575 0.0720690000 281043168 0 1787322368 -0.3442916572 0.0346424617 0.3892309964 199 7.9200000000 0.9504911304 0.4378285808 0.9504911304 0.0100956010 0.0685850000 281044422 0 1787322368 -0.3436577916 0.0342786908 0.3947914243 200 7.9600000000 0.9566283822 0.4404225798 0.9566283822 0.0100998046 0.3823700000 293350284 0 1787416576 -0.3437818289 0.0337360650 0.4000286460 201 8.0000000000 0.9649852514 0.4430323443 0.9649852514 0.0101476434 0.0914160000 297009386 0 1787543552 -0.3433530331 0.0339832902 0.4071685672 202 8.0400000000 0.9696269631 0.4456392484 0.9696269631 0.0101555908 0.0720560000 300202736 0 1787924480 -0.3420802653 0.0336733311 0.4099365473 203 8.0800000000 0.9767532349 0.4482555734 0.9767532349 0.0101804528 0.0718550000 300203990 0 1785929728 -0.3416115642 0.0343754329 0.4161137640 204 8.1200000000 0.9812716246 0.4508683972 0.9812716246 0.0101764893 0.0677710000 300205244 0 1785188352 -0.3411647081 0.0334879011 0.4213275611 205 8.1600000000 0.9857473969 0.4534775631 0.9857473969 0.0101665648 0.0639440000 300206498 0 1785188352 -0.3400350511 0.0337446854 0.4254910946 206 8.1999999990 0.9912689924 0.4560882011 0.9912689924 0.0101584979 0.0672030000 300207752 0 1785667584 -0.3386713862 0.0340815783 0.4300209284 207 8.2400000000 0.9962755442 0.4586978018 0.9962755442 0.0101532512 0.0683910000 300209006 0 1786175488 -0.3370545805 0.0344510227 0.4347391129 208 8.2799999990 1.0009080172 0.4613045816 1.0009080172 0.0101306186 0.0678730000 300210260 0 1786556416 -0.3354949653 0.0352069847 0.4392606914 209 8.3200000000 1.0050262213 0.4639061206 1.0050262213 0.0101069370 0.0609100000 300211514 0 1786654720 -0.3338902593 0.0351249203 0.4445423782 210 8.3599999990 1.0087178946 0.4665004624 1.0087178946 0.0100921815 0.0744800000 300212768 0 1787162624 -0.3319807351 0.0354911983 0.4478959739 211 8.4000000000 1.0135239363 0.4690929907 1.0135239363 0.0100752335 0.4050480000 312519634 0 1787162624 -0.3301270902 0.0349288210 0.4529427588 212 8.4399999990 1.0170174837 0.4716775402 1.0170174837 0.0100528531 0.0796600000 316178736 0 1787289600 -0.3273786902 0.0358248614 0.4566878378 213 8.4800000000 1.0218880177 0.4742606880 1.0218880177 0.0100291962 0.0695920000 319372086 0 1787416576 -0.3250841498 0.0371207297 0.4619652331 214 8.5200000000 1.0250253677 0.4768343547 1.0250253677 0.0100349660 0.0658690000 319373340 0 1785929728 -0.3226347864 0.0363857113 0.4669245780 215 8.5600000000 1.0274757147 0.4793954773 1.0274757147 0.0100234635 0.0622480000 319374594 0 1785929728 -0.3199805319 0.0362488069 0.4703410864 216 8.6000000000 1.0303477049 0.4819461820 1.0303477049 0.0100068571 0.0620130000 319375848 0 1786404864 -0.3167303503 0.0371038653 0.4742747843 217 8.6400000000 1.0357825756 0.4844984235 1.0357825756 0.0099979933 0.0606400000 319377102 0 1786912768 -0.3137926161 0.0377994031 0.4801640511 218 8.6800000000 1.0376106501 0.4870356355 1.0376106501 0.0100058536 0.0675060000 319378356 0 1787293696 -0.3103069365 0.0386480615 0.4836164713 219 8.7200000000 1.0389230251 0.4895556693 1.0389230251 0.0099886287 0.0602130000 319379610 0 1787416576 -0.3066602349 0.0395056680 0.4879801869 220 8.7600000000 1.0415954590 0.4920649411 1.0415954590 0.0099721950 0.0644070000 319380864 0 1787924480 -0.3030706644 0.0407580808 0.4920036793 221 8.8000000000 1.0448502302 0.4945662320 1.0448502302 0.0099666334 0.0771440000 319382118 0 1785892864 -0.2995093465 0.0413424335 0.4960340858 222 8.8400000000 1.0494520664 0.4970657177 1.0494520664 0.0099503175 0.0650130000 319383372 0 1785298944 -0.2963365316 0.0412582383 0.5011515617 223 8.8800000000 1.0508024693 0.4995488421 1.0508024693 0.0099359232 0.0629410000 319384626 0 1785298944 -0.2929980159 0.0422520526 0.5045568943 224 8.9200000000 1.0532546043 0.5020207429 1.0532546043 0.0099181047 0.0785750000 319385880 0 1785774080 -0.2886953652 0.0434423611 0.5085747838 225 8.9600000000 1.0542514324 0.5044751015 1.0542514324 0.0099017760 0.0715040000 319387134 0 1786281984 -0.2850067914 0.0438136235 0.5114227533 226 9.0000000000 1.0572477579 0.5069209982 1.0572477579 0.0098805559 0.0732390000 319388388 0 1786662912 -0.2813266814 0.0453793332 0.5155460238 227 9.0400000000 1.0582113266 0.5093495899 1.0582113266 0.0098652417 0.0776390000 319389642 0 1786781696 -0.2769026458 0.0476771183 0.5186905265 228 9.0800000000 1.0622458458 0.5117745735 1.0622458458 0.0098655348 0.0806310000 319390896 0 1787289600 -0.2728677392 0.0494769029 0.5236781240 229 9.1200000000 1.0634251833 0.5141835282 1.0634251833 0.0099010991 0.0770230000 319392150 0 1787797504 -0.2691063285 0.0506148972 0.5262110233 230 9.1600000000 1.0640877485 0.5165744161 1.0640877485 0.0099707888 0.0715890000 319393404 0 1785929728 -0.2656255364 0.0509344153 0.5285173655 231 9.2000000000 1.0650570393 0.5189487997 1.0650570393 0.0100736661 0.0736320000 319394658 0 1785434112 -0.2621500492 0.0518777482 0.5316764712 232 9.2400000000 1.0674654245 0.5213130955 1.0674654245 0.0101435249 0.0774070000 319395912 0 1785434112 -0.2586177886 0.0533359535 0.5342269540 233 9.2800000000 1.0686982870 0.5236623882 1.0686982870 0.0102098961 0.0843350000 319397166 0 1785798656 -0.2551952600 0.0544839166 0.5370000601 234 9.3200000000 1.0698795319 0.5259966495 1.0698795319 0.0102647464 0.0751140000 319398420 0 1786400768 -0.2521237135 0.0543070212 0.5393409133 235 9.3600000000 1.0713986158 0.5283175089 1.0713986158 0.0102885813 0.0806790000 319399674 0 1786781696 -0.2481801808 0.0566951036 0.5418210030 236 9.4000000000 1.0736641884 0.5306282999 1.0736641884 0.0103111334 0.0794590000 319400928 0 1786908672 -0.2448318899 0.0572929718 0.5449303389 237 9.4400000000 1.0747858286 0.5329243233 1.0747858286 0.0103211271 0.0766560000 319402182 0 1787416576 -0.2412774116 0.0585607812 0.5471639037 238 9.4800000000 1.0765223503 0.5352083486 1.0765223503 0.0103241480 0.0794940000 319403436 0 1788051456 -0.2373639494 0.0610507689 0.5500479341 239 9.5200000000 1.0785076618 0.5374815675 1.0785076618 0.0103509347 0.0746660000 319404690 0 1785929728 -0.2338252962 0.0620791279 0.5523306131 240 9.5600000000 1.0813223124 0.5397475706 1.0813223124 0.0103790575 0.0758560000 319405944 0 1785171968 -0.2304729074 0.0630045086 0.5551471710 241 9.6000000000 1.0834497213 0.5420035961 1.0834497213 0.0103974546 0.0767360000 319407198 0 1785171968 -0.2267772704 0.0642938763 0.5588783622 242 9.6400000000 1.0862194300 0.5442524218 1.0862194300 0.0103999378 0.4262540000 331715260 0 1787289600 -0.2233112454 0.0653612316 0.5616808534 243 9.6800000000 1.0872260332 0.5464868812 1.0872260332 0.0103947605 0.1012210000 335374362 0 1787797504 -0.2203142792 0.0667807385 0.5654063225 244 9.7200000000 1.0899795294 0.5487143100 1.0899795294 0.0104010282 0.0974980000 338567712 0 1785675776 -0.2165182829 0.0686636493 0.5678303242 245 9.7600000000 1.0919765234 0.5509317068 1.0919765234 0.0104142107 0.0924330000 338568966 0 1785896960 -0.2124854028 0.0696942359 0.5712326169 246 9.8000000000 1.0951728821 0.5531440693 1.0951728821 0.0104084933 0.0966940000 338570220 0 1784672256 -0.2089581788 0.0703627467 0.5742379427 247 9.8400000000 1.0989394188 0.5553537671 1.0989394188 0.0103982474 0.0921550000 338571474 0 1784672256 -0.2055997699 0.0704721808 0.5777372718 248 9.8800000000 1.1020497084 0.5575581862 1.1020497084 0.0103787831 0.0862270000 338572728 0 1785155584 -0.2023139000 0.0709169433 0.5807316899 249 9.9200000000 1.1043138504 0.5597539921 1.1043138504 0.0103620633 0.0814030000 338573982 0 1785663488 -0.1989833266 0.0713093206 0.5836230516 250 9.9600000000 1.1080093384 0.5619470135 1.1080093384 0.0103498510 0.0828660000 338575236 0 1786044416 -0.1952547729 0.0723114982 0.5866066217 251 10.0000000000 1.1113600731 0.5641359101 1.1113600731 0.0103361819 0.0812770000 338576490 0 1786146816 -0.1916813850 0.0732912198 0.5897135139 252 10.0400000000 1.1157010794 0.5663246608 1.1157010794 0.0103228723 0.0827370000 338577744 0 1786654720 -0.1886922717 0.0726661012 0.5936142206 253 10.0800000000 1.1198225021 0.5685123993 1.1198225021 0.0103139264 0.0792800000 338578998 0 1787289600 -0.1859738827 0.0713740587 0.5972085595 254 10.1200000000 1.1234194040 0.5706970726 1.1234194040 0.0103378261 0.0783970000 338580252 0 1787797504 -0.1824756265 0.0725731701 0.6004584432 255 10.1600000000 1.1272954941 0.5728798115 1.1272954941 0.0103563927 0.0879060000 338581506 0 1785929728 -0.1786149293 0.0750016421 0.6034691334 256 10.2000000000 1.1305195093 0.5750580915 1.1305195093 0.0103441151 0.0824130000 338582760 0 1785434112 -0.1746358722 0.0765582100 0.6066455841 257 10.2400000000 1.1342113018 0.5772337850 1.1342113018 0.0103273124 0.0803070000 338605518 0 1785434112 -0.1715226024 0.0763652846 0.6095930934 258 10.2800000000 1.1378731728 0.5794068058 1.1378731728 0.0103112775 0.0839400000 338648756 0 1785925632 -0.1675398648 0.0780268386 0.6130447984 259 10.3200000000 1.1403305531 0.5815725346 1.1403305531 0.0102924180 0.4947220000 350988474 0 1787797504 -0.1637909710 0.0794088691 0.6151978970 260 10.3600000000 1.1432216167 0.5837327234 1.1432216167 0.0102786512 0.1119500000 354647576 0 1785819136 -0.1600703001 0.0820147097 0.6184805036 261 10.4000000000 1.1455483437 0.5858852736 1.1455483437 0.0102639278 0.0930240000 357840926 0 1786019840 -0.1566589922 0.0817708522 0.6211354733 262 10.4400000000 1.1485308409 0.5880327758 1.1485308409 0.0102446523 0.0863600000 357842180 0 1784406016 -0.1533162743 0.0817176104 0.6235976219 263 10.4800000000 1.1503921747 0.5901710245 1.1503921747 0.0102253509 0.0836900000 357843434 0 1784406016 -0.1495514363 0.0821840391 0.6255800128 264 10.5200000000 1.1522901058 0.5923002634 1.1522901058 0.0102080642 0.0774220000 357844688 0 1784881152 -0.1458235383 0.0820602179 0.6278039813 265 10.5600000000 1.1546410322 0.5944223041 1.1546410322 0.0101913675 0.0795680000 357845942 0 1785389056 -0.1419044584 0.0825231895 0.6298875809 266 10.6000000000 1.1556470394 0.5965321715 1.1556470394 0.0101820487 0.0805090000 357847196 0 1785769984 -0.1377546191 0.0831671730 0.6314582229 267 10.6400000000 1.1564384699 0.5986291988 1.1564384699 0.0101777259 0.0765460000 357848450 0 1785892864 -0.1337623000 0.0828560069 0.6328725815 268 10.6800000000 1.1586514711 0.6007188342 1.1586514711 0.0101654471 0.0805460000 357849704 0 1786400768 -0.1297091842 0.0825574398 0.6350159645 269 10.7200000000 1.1583645344 0.6027918665 1.1586514711 0.0101529489 0.0910830000 357850958 0 1786908672 -0.1255283654 0.0824505389 0.6358839273 270 10.7600000000 1.1618512869 0.6048624569 1.1618512869 0.0101528922 0.0883690000 357852212 0 1787543552 -0.1165235043 0.0840214789 0.6396794915 271 10.8000000000 1.1624671221 0.6069200387 1.1624671221 0.0101773378 0.0830800000 357853466 0 1788051456 -0.1114866808 0.0852264613 0.6408154964 272 10.8400000000 1.1631122828 0.6089648632 1.1631122828 0.0102338531 0.0949750000 357854720 0 1786077184 -0.1071771160 0.0845486447 0.6421201229 273 10.8800000000 1.1644377708 0.6109995625 1.1644377708 0.0102366429 0.0869350000 357855974 0 1785655296 -0.1026350558 0.0847683996 0.6438310742 274 10.9200000000 1.1653928757 0.6130228957 1.1653928757 0.0102410835 0.0937780000 357857228 0 1785176064 -0.0979471281 0.0851557106 0.6450666785 275 10.9600000000 1.1658052206 0.6150330133 1.1658052206 0.0102465698 0.4739260000 370166170 0 1787183104 -0.0934501663 0.0851352662 0.6459681988 276 11.0000000000 1.1666945219 0.6170317868 1.1666945219 0.0102387624 0.1201770000 373825272 0 1785167872 -0.0877050906 0.0864810720 0.6476469040 277 11.0400000000 1.1675258875 0.6190191302 1.1675258875 0.0102418742 0.0962070000 377018622 0 1785548800 -0.0828922316 0.0869072750 0.6489626765 278 11.0800000000 1.1682015657 0.6209946066 1.1682015657 0.0102480765 0.0812920000 377019876 0 1784922112 -0.0780331045 0.0873834416 0.6505456567 279 11.1200000000 1.1694052219 0.6229602360 1.1694052219 0.0102581352 0.0751530000 377021130 0 1784922112 -0.0729058981 0.0879032835 0.6521978974 280 11.1600000000 1.1710208654 0.6249175954 1.1710208654 0.0102737931 0.0856180000 377022384 0 1784033280 -0.0681358799 0.0887938514 0.6527597308 281 11.2000000000 1.1717439890 0.6268635968 1.1717439890 0.0102835469 0.0840210000 377023638 0 1784033280 -0.0634755194 0.0890657976 0.6536659002 282 11.2400000000 1.1737449169 0.6288028923 1.1737449169 0.0102774400 0.0803120000 377024892 0 1784512512 -0.0591735207 0.0886294097 0.6553179622 283 11.2800000000 1.1746218204 0.6307315811 1.1746218204 0.0102635168 0.0802420000 377026146 0 1785020416 -0.0548661575 0.0890635401 0.6561244726 284 11.3200000000 1.1775275469 0.6326569190 1.1775275469 0.0102519972 0.0825580000 377027400 0 1785401344 -0.0504140146 0.0897729918 0.6579679251 285 11.3600000000 1.1791194677 0.6345743314 1.1791194677 0.0102547295 0.0902940000 377028654 0 1785511936 -0.0464388989 0.0898552984 0.6599023342 286 11.4000000000 1.1814823151 0.6364865971 1.1814823151 0.0102566688 0.0806540000 377029908 0 1786019840 -0.0425992832 0.0900143236 0.6608746648 287 11.4400000000 1.1835119724 0.6383926088 1.1835119724 0.0102524106 0.0837660000 377031162 0 1786654720 -0.0392187834 0.0897487774 0.6623755693 288 11.4800000000 1.1857118607 0.6402930229 1.1857118607 0.0102471315 0.0992050000 377032416 0 1787162624 -0.0360271893 0.0897394717 0.6636737585 289 11.5200000000 1.1893945932 0.6421930284 1.1893945932 0.0102431584 0.0929090000 377033670 0 1787670528 -0.0330840908 0.0895390809 0.6660023928 290 11.5600000000 1.1928281784 0.6440917702 1.1928281784 0.0102407993 0.0953890000 377034924 0 1785929728 -0.0301265009 0.0896064043 0.6680647731 291 11.6000000000 1.1969971657 0.6459917888 1.1969971657 0.0102350244 0.1080690000 377036178 0 1785929728 -0.0274198409 0.0892704800 0.6705003977 292 11.6400000000 1.2004373074 0.6478905748 1.2004373074 0.0102306266 0.1032800000 377037432 0 1786404864 -0.0245596711 0.0895347819 0.6725593805 293 11.6800000000 1.2045376301 0.6497903941 1.2045376301 0.0102234827 0.0972370000 377038686 0 1786912768 -0.0220078658 0.0894610062 0.6750724912 294 11.7200000000 1.2090724707 0.6516927141 1.2090724707 0.0102135162 0.0996240000 377039940 0 1787293696 -0.0199057031 0.0891406164 0.6774806380 295 11.7600000000 1.2134149075 0.6535968571 1.2134149075 0.0102070335 0.0995250000 377041194 0 1787416576 -0.0178239048 0.0889908001 0.6799201965 296 11.8000000000 1.2173588276 0.6555014584 1.2173588276 0.0102004097 0.1020380000 377042448 0 1788051456 -0.0157038886 0.0889090374 0.6823117733 297 11.8400000000 1.2220003605 0.6574088621 1.2220003605 0.0101974298 0.1027140000 377043702 0 1785929728 -0.0139495516 0.0886960775 0.6850124598 298 11.8800000000 1.2269097567 0.6593199389 1.2269097567 0.0102017099 0.1012800000 377044956 0 1786146816 -0.0121500110 0.0883871987 0.6878730655 299 11.9200000000 1.2319976091 0.6612352489 1.2319976091 0.0102008566 0.1015620000 377046210 0 1786781696 -0.0103196306 0.0882246122 0.6908285022 300 11.9600000000 1.2372682095 0.6631553587 1.2372682095 0.0101927707 0.5473190000 389356288 0 1786040320 -0.0084866565 0.0884066522 0.6937891841 301 12.0000000000 1.2420710325 0.6650786666 1.2420710325 0.0101853301 0.1213120000 393015390 0 1785032704 -0.0063400012 0.0884854421 0.6980793476 302 12.0400000000 1.2483757734 0.6670101140 1.2483757734 0.0101828496 0.0992170000 396208740 0 1785421824 -0.0048737805 0.0882406458 0.7015631199 303 12.0800000000 1.2543073893 0.6689483888 1.2543073893 0.0101890976 0.0854600000 396209994 0 1785638912 -0.0033955928 0.0882933885 0.7054798007 304 12.1200000000 1.2609407902 0.6708957322 1.2609407902 0.0102002745 0.0867930000 396211248 0 1784676352 -0.0017752241 0.0882142633 0.7090133429 305 12.1600000000 1.2680908442 0.6728537490 1.2680908442 0.0102103952 0.0890760000 396212502 0 1784053760 -0.0004161657 0.0880656838 0.7131412625 306 12.2000000000 1.2753077745 0.6748225530 1.2753077745 0.0102157169 0.0888550000 396213756 0 1784053760 0.0010344310 0.0878971219 0.7173578739 307 12.2400000000 1.2827430964 0.6768027502 1.2827430964 0.0102302897 0.0846290000 396215010 0 1784401920 0.0021298036 0.0879977643 0.7214166522 308 12.2800000000 1.2901220322 0.6787940466 1.2901220322 0.0102514382 0.0840920000 396216264 0 1785036800 0.0030899232 0.0880354419 0.7256569862 309 12.3200000000 1.2969012260 0.6807943934 1.2969012260 0.0102834852 0.0827910000 396217518 0 1785417728 0.0040244488 0.0877259672 0.7297107577 310 12.3600000000 1.3043224812 0.6828057744 1.3043224812 0.0103299619 0.0969730000 396218772 0 1785417728 0.0047762454 0.0874839872 0.7341158390 311 12.4000000000 1.3111323118 0.6848261169 1.3111323118 0.0103606722 0.0888000000 396220026 0 1785892864 0.0056737205 0.0877270326 0.7380772829 312 12.4400000000 1.3262665272 0.6868820157 1.3262665272 0.0104665311 0.1003940000 396221280 0 1786527744 0.0066728164 0.0874905065 0.7467588186 313 12.4800000000 1.3329354525 0.6889460842 1.3329354525 0.0104678148 0.1112860000 396222534 0 1787035648 0.0070480155 0.0872583538 0.7507681251 314 12.5200000000 1.3408042192 0.6910220655 1.3408042192 0.0104703388 0.1055300000 396223788 0 1787543552 0.0072270273 0.0869491994 0.7553464770 315 12.5600000000 1.3480296135 0.6931078037 1.3480296135 0.0104776425 0.1061440000 396225042 0 1785929728 0.0073787458 0.0868634135 0.7594581842 316 12.6000000000 1.3556011915 0.6952043018 1.3556011915 0.0104791978 0.1097390000 396226296 0 1785929728 0.0077359709 0.0869614333 0.7640995383 317 12.6400000000 1.3628543615 0.6973104534 1.3628543615 0.0104801449 0.1076940000 396227550 0 1786277888 0.0077903736 0.0867347047 0.7682954669 318 12.6800000000 1.3700052500 0.6994258459 1.3700052500 0.0104848149 0.1151230000 396228804 0 1786912768 0.0077551571 0.0864950269 0.7725846767 319 12.7200000000 1.3763047457 0.7015477233 1.3763047457 0.0104943829 0.1135680000 396230058 0 1787293696 0.0075820899 0.0864129141 0.7763491869 320 12.7600000000 1.3828784227 0.7036768817 1.3828784227 0.0105049740 0.1143220000 396231312 0 1787416576 0.0072409306 0.0863081440 0.7800908685 321 12.8000000000 1.3894332647 0.7058131944 1.3894332647 0.0105262323 0.1130280000 396232566 0 1788051456 0.0066538951 0.0859727263 0.7840276361 322 12.8400000000 1.3955305815 0.7079551739 1.3955305815 0.0105612702 0.1134140000 396233820 0 1786019840 0.0060897749 0.0861363560 0.7872561812 323 12.8800000000 1.4006607533 0.7100997732 1.4006607533 0.0106157835 0.1119370000 396235074 0 1786273792 0.0055557126 0.0856257528 0.7906527519 324 12.9200000000 1.4064388275 0.7122489678 1.4064388275 0.0106702512 0.6213430000 408548396 0 1785819136 0.0051747994 0.0853927732 0.7939394712 325 12.9600000000 1.4121723175 0.7144025781 1.4121723175 0.0107307640 0.1481480000 412209154 0 1785409536 0.0051475638 0.0863175318 0.7971737981 326 13.0000000000 1.4166582823 0.7165567367 1.4166582823 0.0108151253 0.1241790000 415402504 0 1785647104 0.0042077149 0.0861671194 0.7998187542 327 13.0400000000 1.4226861000 0.7187161538 1.4226861000 0.0109127661 0.1161220000 415403758 0 1785053184 0.0035180924 0.0861658603 0.8034307957 328 13.0800000000 1.4268804789 0.7208751913 1.4268804789 0.0110081896 0.1077810000 415405012 0 1785053184 0.0032547654 0.0869395137 0.8057091832 329 13.1200000000 1.4323899746 0.7230378502 1.4323899746 0.0110934610 0.1058760000 415406266 0 1785528320 0.0028637713 0.0872226357 0.8092136383 330 13.1600000000 1.4373104572 0.7252023127 1.4373104572 0.0111718647 0.0968970000 415407520 0 1786036224 0.0023011481 0.0872443467 0.8121885061 331 13.2000000000 1.4433510303 0.7273719463 1.4433510303 0.0112424615 0.0934330000 415408774 0 1786417152 0.0016490854 0.0872557610 0.8159117699 332 13.2400000000 1.4484903812 0.7295439898 1.4484903812 0.0112942709 0.0905040000 415410028 0 1786535936 0.0012503903 0.0874785036 0.8191731572 333 13.2800000000 1.4543063641 0.7317204533 1.4543063641 0.0113470428 0.5957060000 427719526 0 1786302464 0.0007834949 0.0876217708 0.8227665424 334 13.3200000000 1.4595321417 0.7338995303 1.4595321417 0.0114179105 0.1841990000 431378628 0 1784905728 -0.0003562724 0.0875260681 0.8254938722 335 13.3600000000 1.4648817778 0.7360815668 1.4648817778 0.0114673260 0.1566370000 434571978 0 1785176064 -0.0007683860 0.0879278928 0.8289424181 336 13.4000000000 1.4701861143 0.7382664018 1.4701861143 0.0115390184 0.1462930000 434573232 0 1785397248 -0.0013561749 0.0882852748 0.8316484690 337 13.4400000000 1.4750403166 0.7404526745 1.4750403166 0.0116499295 0.1478940000 434574486 0 1786032128 -0.0018656753 0.0891973227 0.8344497681 338 13.4800000000 1.4789291620 0.7426375162 1.4789291620 0.0117667196 0.1373800000 434575740 0 1786535936 -0.0023590934 0.0897431597 0.8369367719 339 13.5200000000 1.4823421240 0.7448195357 1.4823421240 0.0118854867 0.1372110000 434576994 0 1786535936 -0.0031696595 0.0897969380 0.8390609622 340 13.5600000000 1.4855993986 0.7469983000 1.4855993986 0.0119614525 0.1617810000 434578248 0 1787043840 -0.0040095588 0.0898766741 0.8408803940 341 13.6000000000 1.4886935949 0.7491733595 1.4886935949 0.0120393744 0.9150200000 446893346 0 1787301888 -0.0048437878 0.0899906680 0.8425883055 342 13.6400000000 1.4936816692 0.7513502844 1.4936816692 0.0121155283 0.1884800000 450552448 0 1785303040 -0.0071287351 0.0911619738 0.8431235552 343 13.6800000000 1.4966392517 0.7535231385 1.4966392517 0.0121525018 0.1508290000 453745798 0 1783517184 -0.0076749297 0.0916106626 0.8449537754 344 13.7200000000 1.4997862577 0.7556925081 1.4997862577 0.0122049633 0.1469660000 453747052 0 1782915072 -0.0077679208 0.0922632515 0.8474073410 345 13.7600000000 1.5034737587 0.7578599899 1.5034737587 0.0122868214 0.1379600000 453748306 0 1782915072 -0.0085869832 0.0919087604 0.8492196798 346 13.8000000000 1.5066417456 0.7600240991 1.5066417456 0.0123646634 0.1317260000 453749560 0 1783615488 -0.0091283303 0.0920137241 0.8510700464 347 13.8400000000 1.5092804432 0.7621833393 1.5092804432 0.0123993273 0.1217940000 453750814 0 1784123392 -0.0099105695 0.0915228277 0.8528875113 348 13.8800000000 1.5128917694 0.7643405474 1.5128917694 0.0124262957 0.1251620000 453752068 0 1784250368 -0.0101076290 0.0924016535 0.8551729321 349 13.9200000000 1.5163598061 0.7664953304 1.5163598061 0.0124627078 0.1268480000 453753322 0 1784631296 -0.0106637385 0.0922546163 0.8574703932 350 13.9600000000 1.5218012333 0.7686533472 1.5218012333 0.0125209468 1.2950500000 466126788 0 1785139200 -0.0112762973 0.0918371677 0.8607237339 351 14.0000000000 1.5319559574 0.7708279985 1.5319559574 0.0125443415 0.1872600000 469785890 0 1785937920 -0.0143578975 0.0933464020 0.8545121551 352 14.0400000000 1.5348793268 0.7729985989 1.5348793268 0.0125388753 0.1370300000 472979240 0 1785290752 -0.0146138882 0.0930053815 0.8562313318 353 14.0800000000 1.5373950005 0.7751640278 1.5373950005 0.0125246606 0.1305410000 472980494 0 1784680448 -0.0146341026 0.0927746370 0.8579201698 354 14.1200000000 1.5404330492 0.7773258047 1.5404330492 0.0125154477 0.1240750000 472981748 0 1784680448 -0.0144896246 0.0929444209 0.8596742153 355 14.1600000000 1.5432088375 0.7794832217 1.5432088375 0.0125055379 0.1223140000 472983002 0 1785155584 -0.0146104302 0.0923658088 0.8615536690 356 14.2000000000 1.5461014509 0.7816366437 1.5461014509 0.0124981754 0.1091990000 472984256 0 1785663488 -0.0144961867 0.0922073275 0.8632937074 357 14.2400000000 1.5496286154 0.7837878817 1.5496286154 0.0124910717 0.1399130000 472985510 0 1786044416 -0.0143571058 0.0924708694 0.8653556705 358 14.2800000000 1.5527447462 0.7859358059 1.5527447462 0.0124809954 0.1316560000 472986764 0 1786146816 -0.0144079225 0.0919109285 0.8675603271 359 14.3200000000 1.5559386015 0.7880806605 1.5559386015 0.0124667460 0.1326930000 472988018 0 1786654720 -0.0145350508 0.0912404358 0.8697298169 360 14.3600000000 1.5595964193 0.7902237598 1.5595964193 0.0124544723 0.1449260000 472989272 0 1787162624 -0.0146360677 0.0905014202 0.8721317053 361 14.4000000000 1.5634597540 0.7923656878 1.5634597540 0.0124450624 0.1411440000 472990526 0 1787670528 -0.0146104870 0.0904857293 0.8746890426 362 14.4400000000 1.5674757957 0.7945068759 1.5674757957 0.0124336547 0.1394770000 472991780 0 1786077184 -0.0145632764 0.0905535370 0.8772160411 363 14.4800000000 1.5720087290 0.7966487543 1.5720087290 0.0124199852 0.1661360000 472993034 0 1786077184 -0.0145506868 0.0907202587 0.8799048066 364 14.5200000000 1.5763734579 0.7987908551 1.5763734579 0.0124064209 0.1662710000 472994288 0 1786679296 -0.0146634299 0.0903665945 0.8827163577 365 14.5600000000 1.5805633068 0.8009326975 1.5805633068 0.0123925844 0.1709170000 472995542 0 1787187200 -0.0148130460 0.0899721682 0.8855302334 366 14.6000000000 1.5854942799 0.8030763084 1.5854942799 0.0123796539 0.1693690000 472996796 0 1787416576 -0.0148773044 0.0901041701 0.8884987831 367 14.6400000000 1.5901068449 0.8052208057 1.5901068449 0.0123659507 0.1708940000 472998050 0 1787543552 -0.0148919597 0.0904391184 0.8912107348 368 14.6800000000 1.5948760509 0.8073666080 1.5948760509 0.0123591746 0.1699170000 472999304 0 1786077184 -0.0149658117 0.0905465484 0.8941155672 369 14.7200000000 1.5993562937 0.8095129215 1.5993562937 0.0123635198 0.1683720000 473000558 0 1786077184 -0.0152047947 0.0904432386 0.8970378041 370 14.7600000000 1.6042542458 0.8116608711 1.6042542458 0.0123676810 0.1672870000 473001812 0 1786552320 -0.0152823795 0.0904835016 0.9000492692 371 14.8000000000 1.6087129116 0.8138092593 1.6087129116 0.0123699248 0.7171710000 485310866 0 1786146816 -0.0153164174 0.0902475193 0.9028111100 372 14.8400000000 1.6179759502 0.8159709977 1.6179759502 0.0123758764 0.1895930000 488969968 0 1784909824 -0.0154594788 0.0903754234 0.9004724622 373 14.8800000000 1.6225223541 0.8181333338 1.6225223541 0.0124125721 0.1273000000 492163318 0 1785184256 -0.0154598057 0.0902353302 0.9032278061 374 14.9200000000 1.6269242764 0.8202958764 1.6269242764 0.0124562710 0.1221260000 492164572 0 1785405440 -0.0154331801 0.0899423584 0.9061067104 375 14.9600000000 1.6311579943 0.8224581754 1.6311579943 0.0125275598 0.1285810000 492165826 0 1786019840 -0.0153108314 0.0898061022 0.9087929726 376 15.0000000000 1.6358718872 0.8246215098 1.6358718872 0.0126046039 0.1224640000 492167080 0 1786527744 -0.0150109483 0.0902323574 0.9115161300 377 15.0400000000 1.6440014839 0.8267949314 1.6440014839 0.0128714958 0.1279130000 492168334 0 1786527744 -0.0141157741 0.0905808434 0.9165133834 378 15.0800000000 1.6480624676 0.8289675969 1.6480624676 0.0129270242 0.1245950000 492169588 0 1787035648 -0.0133767603 0.0909902677 0.9189836383 379 15.1200000000 1.6515538692 0.8311380092 1.6515538692 0.0129715404 0.1247200000 492170842 0 1787670528 -0.0126259206 0.0911489949 0.9211542010 380 15.1600000000 1.6549040079 0.8333058145 1.6549040079 0.0130196006 0.1227400000 492172096 0 1785929728 -0.0115677472 0.0915558040 0.9231641889 381 15.2000000000 1.6580882072 0.8354705976 1.6580882072 0.0130646009 0.1484810000 492173350 0 1785929728 -0.0106579829 0.0919265300 0.9250569940 382 15.2400000000 1.6610032320 0.8376316778 1.6610032320 0.0131208035 1.0089670000 504483348 0 1785511936 -0.0097531984 0.0920424163 0.9269114733 383 15.2800000000 1.6655389071 0.8397933155 1.6655389071 0.0131795644 0.1781990000 508142450 0 1786019840 -0.0070177787 0.0935568959 0.9268395901 384 15.3200000000 1.6679121256 0.8419498749 1.6679121256 0.0132309465 0.1340470000 511335800 0 1785282560 -0.0060131666 0.0937752873 0.9282701612 385 15.3600000000 1.6694597006 0.8440992511 1.6694597006 0.0132822108 0.1250070000 511337054 0 1784786944 -0.0050998121 0.0935860500 0.9292258024 386 15.4000000000 1.6708122492 0.8462409946 1.6708122492 0.0133287120 0.1175500000 511338308 0 1784786944 -0.0039693508 0.0938196778 0.9300152063 387 15.4400000000 1.6722995043 0.8483755127 1.6722995043 0.0133989758 0.1152440000 511339562 0 1785262080 -0.0025963485 0.0945911780 0.9307564497 388 15.4800000000 1.6729902029 0.8505008083 1.6729902029 0.0135106839 0.1107840000 511340816 0 1785896960 -0.0015320550 0.0950338468 0.9310457706 389 15.5200000000 1.6736099720 0.8526167702 1.6736099720 0.0136221621 0.1058080000 511342070 0 1786150912 -0.0005757947 0.0950628817 0.9314054251 390 15.5600000000 1.6745631695 0.8547243250 1.6745631695 0.0137253805 0.1153280000 511343324 0 1786273792 0.0008452940 0.0962289721 0.9318235517 391 15.6000000000 1.6753196716 0.8568230344 1.6753196716 0.0137873617 0.9095300000 523653930 0 1786531840 0.0020714758 0.0962910503 0.9324144125 392 15.6400000000 1.6751003265 0.8589104764 1.6753196716 0.0138779105 0.1234920000 527313032 0 1785548800 0.0029119069 0.0961415768 0.9330649972 393 15.6800000000 1.6753613949 0.8609879597 1.6753613949 0.0139995494 0.1809190000 530506382 0 1785929728 0.0036465183 0.0954064354 0.9334001541 394 15.7200000000 1.6758714914 0.8630561920 1.6758714914 0.0141489893 0.1516480000 530507636 0 1786277888 0.0044465330 0.0946931764 0.9337313771 395 15.7600000000 1.6762844324 0.8651149977 1.6762844324 0.0142921088 0.1254520000 530508890 0 1786912768 0.0056178290 0.0949098319 0.9338564873 396 15.8000000000 1.6763879061 0.8671636666 1.6763879061 0.0144044454 0.1417500000 530510144 0 1787293696 0.0070148916 0.0950203240 0.9339041114 397 15.8400000000 1.6763979197 0.8692020401 1.6763979197 0.0145403055 0.1319890000 530511398 0 1787416576 0.0080232332 0.0947071239 0.9339137673 398 15.8800000000 1.6760941744 0.8712294072 1.6763979197 0.0146542190 0.1375900000 530512652 0 1787924480 0.0088837603 0.0940416008 0.9335384965 399 15.9200000000 1.6752057076 0.8732443854 1.6763979197 0.0147544589 0.1359250000 530513906 0 1786019840 0.0108334487 0.0947191715 0.9330486655 400 15.9600000000 1.6755686998 0.8752501962 1.6763979197 0.0148400318 1.4476290000 542830084 0 1785548800 0.0123032304 0.0949829221 0.9332334995 401 16.0000000000 1.6767392159 0.8772489220 1.6767392159 0.0149341982 0.1463830000 546489186 0 1785819136 0.0136403022 0.0947693959 0.9327381849 402 16.0400000000 1.6770970821 0.8792385940 1.6770970821 0.0150327671 0.1691950000 549682536 0 1785819136 0.0154332919 0.0949916989 0.9326678514 403 16.0800000000 1.6781030893 0.8812208880 1.6781030893 0.0151050877 0.1401130000 549683790 0 1786548224 0.0173884165 0.0948669240 0.9332400560 404 16.1200000000 1.6776318550 0.8831922023 1.6781030893 0.0151631548 0.1603990000 549685044 0 1787162624 0.0188318603 0.0949446186 0.9328694344 405 16.1600000000 1.6784924269 0.8851559066 1.6784924269 0.0152442968 0.1283710000 549686298 0 1787162624 0.0209654663 0.0949178562 0.9336030483 406 16.2000000000 1.6802200079 0.8871141925 1.6802200079 0.0153580426 0.1240620000 549687552 0 1787670528 0.0231350735 0.0954140127 0.9346218109 407 16.2400000000 1.6816797256 0.8890664420 1.6816797256 0.0154900122 1.7379270000 562007626 0 1787289600 0.0251240749 0.0958549827 0.9352164268 408 16.2800000000 1.6838473082 0.8910144343 1.6838473082 0.0156568858 0.1411080000 565666728 0 1784782848 0.0274715815 0.0960718095 0.9359596968 409 16.3200000000 1.6857405901 0.8929575301 1.6857405901 0.0158004320 0.1283280000 568860078 0 1785167872 0.0295901168 0.0970104635 0.9369710684 410 16.3600000000 1.6886647940 0.8948982795 1.6886647940 0.0159265594 0.1068500000 568861332 0 1784541184 0.0320332088 0.0978183001 0.9387014508 411 16.3999999990 1.6896084547 0.8968318809 1.6896084547 0.0160950769 0.1084740000 568862586 0 1784541184 0.0332471281 0.0974711478 0.9393545389 412 16.4400000000 1.6936280727 0.8987658522 1.6936280727 0.0163182358 0.0970350000 568863840 0 1785016320 0.0352775529 0.0974527299 0.9415896535 413 16.4800000000 1.6979572773 0.9007009404 1.6979572773 0.0165156167 0.1052660000 568865094 0 1785651200 0.0376199707 0.0977481008 0.9441885948 414 16.5200000000 1.7002074718 0.9026321156 1.7002074718 0.0166746347 1.6079720000 581186752 0 1787416576 0.0394880474 0.0970520675 0.9453816414 415 16.5599999990 1.7055565119 0.9045668732 1.7055565119 0.0168417284 0.1425340000 584845854 0 1786064896 0.0399574004 0.0942040831 0.9453280568 416 16.6000000000 1.7093108892 0.9065013540 1.7093108892 0.0170223615 0.1089670000 588039204 0 1786527744 0.0425758176 0.0941502750 0.9473147988 417 16.6400000000 1.7104984522 0.9084294046 1.7104984522 0.0171342707 0.0965180000 588040458 0 1785409536 0.0445846394 0.0945834592 0.9479320645 418 16.6800000000 1.7101509571 0.9103473987 1.7104984522 0.0172304610 0.0876290000 588041712 0 1785409536 0.0457054190 0.0935257226 0.9475005865 419 16.7199999990 1.7138668299 0.9122651062 1.7138668299 0.0173719954 0.0833880000 588042966 0 1785913344 0.0488404892 0.0945402384 0.9497346282 420 16.7600000000 1.7141726017 0.9141744098 1.7141726017 0.0174366001 0.0883210000 588044220 0 1786290176 0.0510208271 0.0952156782 0.9497446418 421 16.8000000000 1.7145451307 0.9160755279 1.7145451307 0.0174845920 1.2009070000 600363230 0 1786421248 0.0529552810 0.0937908068 0.9500788450 422 16.8400000000 1.7158814669 0.9179708026 1.7158814669 0.0177271044 0.1216940000 604022332 0 1784643584 0.0558838770 0.0914602503 0.9505034089 423 16.8799999990 1.7159270048 0.9198572239 1.7159270048 0.0177641858 0.0929000000 607215682 0 1785290752 0.0581325591 0.0908957273 0.9505378604 424 16.9200000000 1.7149599791 0.9217324662 1.7159270048 0.0177874654 0.0876950000 607216936 0 1784643584 0.0602342933 0.0900279433 0.9497458339 425 16.9600000000 1.7136602402 0.9235958257 1.7159270048 0.0178181137 0.0866030000 607218190 0 1784643584 0.0629985332 0.0901940838 0.9488388300 426 17.0000000000 1.7134028673 0.9254498328 1.7159270048 0.0178345941 0.0885530000 607219444 0 1784033280 0.0663226321 0.0901044980 0.9485870600 427 17.0400000000 1.7103952169 0.9272881124 1.7159270048 0.0178473414 0.0871520000 607220698 0 1784033280 0.0684024021 0.0889080614 0.9470403194 428 17.0800000000 1.7083880901 0.9291131124 1.7159270048 0.0178588614 0.8118780000 619533300 0 1786912768 0.0720283464 0.0882376730 0.9459530711 429 17.1200000000 1.7080996037 0.9309289317 1.7159270048 0.0178561486 0.0999670000 623192402 0 1787416576 0.0741720870 0.0872289538 0.9451263547 430 17.1600000000 1.7038437128 0.9327264079 1.7159270048 0.0178561698 0.1120510000 626385752 0 1785544704 0.0771489367 0.0858981088 0.9428019524 431 17.2000000000 1.7019668818 0.9345111886 1.7159270048 0.0178606289 0.1186040000 626387006 0 1784750080 0.0805680975 0.0847191662 0.9413781762 432 17.2400000000 1.6994414330 0.9362818605 1.7159270048 0.0178612281 0.1166300000 626388260 0 1784750080 0.0847331360 0.0839942023 0.9396747351 433 17.2800000000 1.6963089705 0.9380371194 1.7159270048 0.0178527856 0.1062600000 626389514 0 1785257984 0.0886625722 0.0834529847 0.9376364350 434 17.3200000000 1.6913063526 0.9397727628 1.7159270048 0.0178484528 0.1019330000 626390768 0 1785892864 0.0922697708 0.0819724575 0.9344035387 435 17.3600000000 1.6885149479 0.9414940092 1.7159270048 0.0178491470 0.0963700000 626392022 0 1786146816 0.0970474556 0.0817179382 0.9325670600 436 17.4000000000 1.6851494312 0.9431996409 1.7159270048 0.0178389489 0.0993800000 626393276 0 1786273792 0.1024822667 0.0830912665 0.9299815297 437 17.4400000000 1.6813325882 0.9448887323 1.7159270048 0.0178235687 0.0973690000 626394530 0 1786781696 0.1084410697 0.0848984718 0.9265646935 438 17.4800000000 1.6772227287 0.9465607277 1.7159270048 0.0178426260 0.0967860000 626395784 0 1787289600 0.1129817963 0.0850686207 0.9237574935 439 17.5200000000 1.6705762148 0.9482099658 1.7159270048 0.0178865735 1.0931360000 638708534 0 1787416576 0.1154623181 0.0832904354 0.9197617769 440 17.5600000000 1.6643949747 0.9498376590 1.7159270048 0.0178961534 0.1457900000 642367636 0 1785257984 0.1154237017 0.0814711973 0.9176580906 441 17.6000000000 1.6595206261 0.9514469174 1.7159270048 0.0178847314 0.1101890000 645560986 0 1785675776 0.1181408167 0.0789963752 0.9151854515 442 17.6400000000 1.6549055576 0.9530384528 1.7159270048 0.0178877590 0.1137280000 645562240 0 1785061376 0.1226115078 0.0792654157 0.9119409323 443 17.6800000000 1.6460261345 0.9546027590 1.7159270048 0.0179000971 0.0981870000 645563494 0 1785061376 0.1313370168 0.0807722583 0.9058856368 444 17.7200000000 1.6400797367 0.9561466261 1.7159270048 0.0178908408 0.0892380000 645564748 0 1785536512 0.1346535832 0.0804468915 0.9019970894 445 17.7600000000 1.6355972290 0.9576734814 1.7159270048 0.0178819121 0.0911230000 645566002 0 1786044416 0.1379788071 0.0795774385 0.8990322948 446 17.8000000000 1.6308348179 0.9591828118 1.7159270048 0.0178686885 0.5112270000 657873856 0 1785819136 0.1414325237 0.0797553509 0.8958250880 447 17.8400000000 1.6268906593 0.9606765653 1.7159270048 0.0178607416 0.1112340000 661532958 0 1786277888 0.1460151374 0.0790815055 0.8923996091 448 17.8800000000 1.6229144335 0.9621547749 1.7159270048 0.0178509153 0.1008100000 664726308 0 1786531840 0.1486986727 0.0785194933 0.8897032738 449 17.9200000000 1.6183656454 0.9636162690 1.7159270048 0.0178470937 0.0968300000 664727562 0 1784291328 0.1514215022 0.0779058263 0.8868572712 450 17.9600000000 1.6153368950 0.9650645371 1.7159270048 0.0178461734 0.0986450000 664728816 0 1783644160 0.1535945833 0.0764022171 0.8848146796 451 18.0000000000 1.6126320362 0.9665003852 1.7159270048 0.0178449378 0.0924140000 664730070 0 1783865344 0.1570774317 0.0763029829 0.8828159571 452 18.0400000000 1.6094868183 0.9679229215 1.7159270048 0.0178364391 0.0915330000 664731324 0 1784373248 0.1602774858 0.0761818513 0.8805841208 453 18.0800000000 1.6061633825 0.9693318409 1.7159270048 0.0178265489 0.0813750000 664732578 0 1784881152 0.1630354822 0.0749480948 0.8783276081 454 18.1200000000 1.6035454273 0.9707287871 1.7159270048 0.0178162754 0.5253700000 677150980 0 1787416576 0.1662907451 0.0746584758 0.8763887286 455 18.1600000000 1.6031581163 0.9721187417 1.7159270048 0.0178021806 0.1095300000 680810082 0 1785569280 0.1699582785 0.0753168091 0.8726592660 456 18.2000000000 1.5998079777 0.9734952531 1.7159270048 0.0177851518 0.1002030000 684003432 0 1785925632 0.1726450473 0.0738925859 0.8704397678 457 18.2400000000 1.5977826118 0.9748613086 1.7159270048 0.0177715862 0.0898310000 684004686 0 1785188352 0.1758893728 0.0730663985 0.8686469793 458 18.2800000000 1.5975896120 0.9762209774 1.7159270048 0.0177657243 0.0918120000 684005940 0 1785188352 0.1801530868 0.0735219866 0.8675199151 459 18.3200000000 1.5953234434 0.9775697845 1.7159270048 0.0177500446 0.0887770000 684007194 0 1785663488 0.1844354123 0.0742927119 0.8652480245 460 18.3600000000 1.5938169956 0.9789094524 1.7159270048 0.0177381648 0.0916220000 684008448 0 1786171392 0.1875210255 0.0729786307 0.8638478518 461 18.4000000000 1.5934431553 0.9802424973 1.7159270048 0.0177254494 0.0802150000 684009702 0 1786552320 0.1913000047 0.0722622275 0.8626632690 462 18.4400000000 1.5915106535 0.9815655885 1.7159270048 0.0177101198 0.0818520000 684010956 0 1786781696 0.1952190101 0.0725540444 0.8605907559 463 18.4800000000 1.5887881517 0.9828770844 1.7159270048 0.0176970203 0.0810320000 684012210 0 1787289600 0.1983523220 0.0718167573 0.8583170772 464 18.5200000000 1.5880467892 0.9841813294 1.7159270048 0.0176873987 0.0918430000 684013464 0 1787797504 0.2013809085 0.0707328022 0.8570363522 465 18.5600000000 1.5870954990 0.9854779190 1.7159270048 0.0176881067 0.0902010000 684014718 0 1786077184 0.2042301595 0.0693184659 0.8558505774 466 18.6000000000 1.5874787569 0.9867697663 1.7159270048 0.0177066372 0.0947470000 684015972 0 1786077184 0.2086585164 0.0697315335 0.8546224833 467 18.6400000000 1.5873515606 0.9880558087 1.7159270048 0.0177089208 0.5113860000 696324058 0 1786077184 0.2125435472 0.0690716431 0.8536289930 468 18.6800000000 1.5880186558 0.9893377806 1.7159270048 0.0177192744 0.1379750000 699983160 0 1785430016 0.2161539346 0.0670072213 0.8538195491 469 18.7200000000 1.5887383223 0.9906158201 1.7159270048 0.0177421083 0.0984930000 703176510 0 1785950208 0.2196651548 0.0665802509 0.8530926704 470 18.7600000000 1.5901316404 0.9918913857 1.7159270048 0.0177791279 0.0953760000 703177764 0 1785315328 0.2232010663 0.0654946938 0.8528401852 471 18.8000000000 1.5905061960 0.9931623301 1.7159270048 0.0178264905 0.0970360000 703179018 0 1785315328 0.2272956520 0.0649226159 0.8518617749 472 18.8400000000 1.5903050900 0.9944274631 1.7159270048 0.0178596335 0.0916680000 703180272 0 1785790464 0.2309703380 0.0651055798 0.8507061601 473 18.8800000000 1.5894411802 0.9956854202 1.7159270048 0.0178719406 0.0812470000 703181526 0 1786298368 0.2347533554 0.0650126189 0.8492215872 474 18.9200000000 1.5858155489 0.9969304205 1.7159270048 0.0178697722 0.0750240000 703182780 0 1786679296 0.2362735569 0.0645491257 0.8464556336 475 18.9600000000 1.5857769251 0.9981700973 1.7159270048 0.0178831792 0.0751590000 703184034 0 1786781696 0.2394512296 0.0638882443 0.8456566334 476 19.0000000000 1.5860688686 0.9994051788 1.7159270048 0.0178997775 0.0801000000 703185288 0 1787289600 0.2429174632 0.0638650730 0.8444297910 477 19.0400000000 1.5824496746 1.0006274943 1.7159270048 0.0178959680 0.0924570000 703186542 0 1787797504 0.2455118597 0.0638769194 0.8416938186 478 19.0800000000 1.5866739750 1.0018535329 1.7159270048 0.0179108636 0.0886480000 703187796 0 1786077184 0.2500692606 0.0636266619 0.8426826596 479 19.1200000000 1.5873173475 1.0030757956 1.7159270048 0.0179095177 0.0819230000 703189050 0 1785511936 0.2526628375 0.0627567545 0.8420034051 480 19.1600000000 1.5902931690 1.0042991651 1.7159270048 0.0179288146 0.1128520000 703190304 0 1785511936 0.2563532889 0.0619462803 0.8425945640 481 19.2000000000 1.5880562067 1.0055127972 1.7159270048 0.0179321438 0.0997190000 703191558 0 1786019840 0.2589470744 0.0627594441 0.8406551480 482 19.2400000000 1.5905966759 1.0067266642 1.7159270048 0.0179318223 0.0991290000 703192812 0 1786527744 0.2622406185 0.0626070946 0.8411065340 483 19.2800000000 1.5913628340 1.0079370910 1.7159270048 0.0179304149 0.1015370000 703194066 0 1786908672 0.2654627562 0.0618018657 0.8405909538 484 19.3200000000 1.5895370245 1.0091387438 1.7159270048 0.0179201725 0.1038650000 703195320 0 1786908672 0.2671851814 0.0618611835 0.8389413953 485 19.3600000000 1.5887019634 1.0103337195 1.7159270048 0.0179106889 0.5631870000 715512374 0 1787039744 0.2703552544 0.0629403889 0.8374657631 486 19.4000000000 1.5887522697 1.0115238811 1.7159270048 0.0178968853 0.1654830000 719171476 0 1785057280 0.2727634013 0.0639534220 0.8371108770 487 19.4400000000 1.5880762339 1.0127077669 1.7159270048 0.0178973089 0.1204000000 722364826 0 1785421824 0.2747245133 0.0625311211 0.8360846639 488 19.4800000000 1.5830943584 1.0138765918 1.7159270048 0.0178878214 0.1065880000 722366080 0 1784795136 0.2746763229 0.0617455728 0.8334798217 489 19.5200000000 1.5815305710 1.0150374384 1.7159270048 0.0178866921 0.1072120000 722367334 0 1784795136 0.2762871385 0.0615696348 0.8318743110 490 19.5600000000 1.5771324635 1.0161845711 1.7159270048 0.0178883907 0.1124230000 722368588 0 1785511936 0.2778505087 0.0611482523 0.8290117979 491 19.6000000000 1.5753465891 1.0173233940 1.7159270048 0.0178904838 0.1082910000 722369842 0 1786019840 0.2798253000 0.0604949854 0.8275663257 492 19.6400000000 1.5686217546 1.0184439191 1.7159270048 0.0178819528 0.1175150000 722371096 0 1786273792 0.2796827555 0.0610072464 0.8234440088 493 19.6800000000 1.5621709824 1.0195468138 1.7159270048 0.0178795160 0.1100590000 722372350 0 1786527744 0.2805361748 0.0608372092 0.8194979429 494 19.7200000000 1.5577594042 1.0206363129 1.7159270048 0.0178803613 0.1044580000 722373604 0 1787035648 0.2808386087 0.0588732138 0.8171012402 495 19.7600000000 1.5512114763 1.0217081819 1.7159270048 0.0178764175 0.1171200000 722374858 0 1787543552 0.2806376219 0.0580105148 0.8133758307 496 19.8000000000 1.5464221239 1.0227660730 1.7159270048 0.0178642316 0.0999290000 722376112 0 1788051456 0.2801401913 0.0580379069 0.8110998273 497 19.8400000000 1.5431355238 1.0238130940 1.7159270048 0.0178543582 0.1065340000 722377366 0 1785929728 0.2811760008 0.0569367521 0.8087952137 498 19.8800000000 1.5359312296 1.0248414437 1.7159270048 0.0178421489 0.1195640000 722378620 0 1786277888 0.2803200781 0.0565261431 0.8051435351 499 19.9200000000 1.5321806669 1.0258581555 1.7159270048 0.0178358766 0.1053840000 722379874 0 1786912768 0.2807849646 0.0560993217 0.8029062748 500 19.9600000000 1.5257155895 1.0268578704 1.7159270048 0.0178312549 0.1044970000 722381128 0 1787543552 0.2804254889 0.0553591996 0.7994641066 501 20.0000000000 1.5193686485 1.0278409258 1.7159270048 0.0178245434 0.1091730000 722382382 0 1787551744 0.2805807889 0.0547240265 0.7958261967 502 20.0400000000 1.5162376165 1.0288138276 1.7159270048 0.0178172163 0.1061420000 722383636 0 1788059648 0.2817964256 0.0537760407 0.7937829494 503 20.0800000000 1.5088237524 1.0297681217 1.7159270048 0.0178074180 0.1157740000 722384890 0 1785827328 0.2823922932 0.0538853034 0.7891962528 504 20.1200000000 1.5019757748 1.0307050416 1.7159270048 0.0177981599 0.1238270000 722386144 0 1786175488 0.2819884419 0.0525859706 0.7856419683 505 20.1600000000 1.4931824207 1.0316208384 1.7159270048 0.0177862473 0.1133640000 722387398 0 1786810368 0.2799260616 0.0517569929 0.7814278007 506 20.2000000000 1.4877383709 1.0325222565 1.7159270048 0.0177779476 0.1076260000 722388652 0 1787191296 0.2796494663 0.0525255576 0.7785535455 507 20.2400000000 1.4807342291 1.0334063038 1.7159270048 0.0177747895 0.1169670000 722389906 0 1787191296 0.2796129286 0.0528434515 0.7746902108 508 20.2800000000 1.4731731415 1.0342719865 1.7159270048 0.0177764454 0.1134850000 722391160 0 1787678720 0.2773688436 0.0521572120 0.7712533474 509 20.3200000000 1.4680800438 1.0351242617 1.7159270048 0.0177644721 0.1111280000 722392414 0 1786085376 0.2779205441 0.0514261723 0.7680429220 510 20.3600000000 1.4600284100 1.0359574071 1.7159270048 0.0177530550 0.1174420000 722393668 0 1786155008 0.2791917026 0.0518088304 0.7629846931 511 20.4000000000 1.4531776905 1.0367738851 1.7159270048 0.0177439856 0.1146870000 722394922 0 1786662912 0.2799858153 0.0532432273 0.7587797642 512 20.4400000000 1.4445389509 1.0375703013 1.7159270048 0.0177517619 0.1175890000 722396176 0 1787170816 0.2786811292 0.0533356294 0.7544137836 513 20.4800000000 1.4388715029 1.0383525648 1.7159270048 0.0177536666 0.1176970000 722440438 0 1787424768 0.2801343203 0.0528374799 0.7505559325 514 20.5200000000 1.4321023226 1.0391186149 1.7159270048 0.0177488488 0.1169240000 722525660 0 1787805696 0.2805417776 0.0532998927 0.7465738058 515 20.5600000000 1.4258334637 1.0398695175 1.7159270048 0.0177461301 0.1163180000 722526914 0 1786085376 0.2820985019 0.0540484041 0.7423999906 516 20.6000000000 1.4183892012 1.0406030828 1.7159270048 0.0177515266 0.1336690000 722528168 0 1786179584 0.2833325565 0.0540184155 0.7374995351 517 20.6400000000 1.4180071354 1.0413330713 1.7159270048 0.0177468546 0.1343800000 722529422 0 1786814464 0.2820546925 0.0531435087 0.7377920747 518 20.6800000000 1.4088269472 1.0420425190 1.7159270048 0.0177376252 0.1220650000 722530676 0 1787297792 0.2859395742 0.0530758388 0.7308517694 519 20.7200000000 1.4092061520 1.0427499633 1.7159270048 0.0177349141 0.1247360000 722531930 0 1787424768 0.2831289768 0.0539014563 0.7322849631 520 20.7600000000 1.4075831175 1.0434515656 1.7159270048 0.0177335031 0.1280160000 722533184 0 1787678720 0.2815929949 0.0547432527 0.7321035862 521 20.8000000000 1.4024709463 1.0441406623 1.7159270048 0.0177365299 0.1104780000 722534438 0 1786085376 0.2802177668 0.0538743176 0.7294600010 522 20.8400000000 1.3988769054 1.0448202336 1.7159270048 0.0177277483 0.1153340000 722535692 0 1786085376 0.2807146907 0.0525009222 0.7271985412 523 20.8800000000 1.3997402191 1.0454988569 1.7159270048 0.0177239755 0.1180670000 722536946 0 1786687488 0.2779377401 0.0519190095 0.7290320396 524 20.9200000000 1.3906733990 1.0461575869 1.7159270048 0.0177098663 0.1139010000 722538200 0 1787195392 0.2832260132 0.0521819927 0.7216455936 525 20.9600000000 1.3875234127 1.0468078076 1.7159270048 0.0177002385 0.1146910000 722539454 0 1787449344 0.2829423249 0.0518500246 0.7199487090 526 21.0000000000 1.3815211058 1.0474441446 1.7159270048 0.0176880814 0.1260290000 722540708 0 1787551744 0.2854227424 0.0504935905 0.7153458595 527 21.0400000000 1.3762180805 1.0480680041 1.7159270048 0.0176796363 0.5881630000 734850062 0 1784918016 0.2857692838 0.0507544875 0.7123027444 528 21.0800000000 1.3734478951 1.0486842539 1.7159270048 0.0176721302 0.0956890000 738512836 0 1785683968 0.2873872519 0.0516286418 0.7108362913 529 21.1200000000 1.3642469645 1.0492807808 1.7159270048 0.0176617058 0.1774100000 741706186 0 1785933824 0.2914698720 0.0508353077 0.7038412094 530 21.1600000000 1.3623645306 1.0498715048 1.7159270048 0.0176547127 0.1224950000 741707440 0 1785139200 0.2900330722 0.0512392968 0.7033155560 531 21.2000000000 1.3553011417 1.0504467019 1.7159270048 0.0176445580 0.1236180000 741708694 0 1785139200 0.2929407656 0.0507699624 0.6979115009 532 21.2400000000 1.3503988981 1.0510105218 1.7159270048 0.0176348521 0.1261230000 741709948 0 1785647104 0.2928994000 0.0501064919 0.6953346133 533 21.2800000000 1.3469185829 1.0515656964 1.7159270048 0.0176219532 0.1205980000 741711202 0 1786155008 0.2921077907 0.0500086397 0.6936077476 534 21.3200000000 1.3396358490 1.0521051536 1.7159270048 0.0176098211 0.1165560000 741712456 0 1786535936 0.2943403423 0.0493158102 0.6884608269 535 21.3600000000 1.3322186470 1.0526287302 1.7159270048 0.0175969137 0.1075780000 741713710 0 1786662912 0.2961425781 0.0501787029 0.6833050847 536 21.4000000000 1.3292154074 1.0531447501 1.7159270048 0.0175879814 0.1205730000 741714964 0 1787170816 0.2953405082 0.0499181375 0.6818830967 537 21.4400000000 1.3210498095 1.0536436422 1.7159270048 0.0175785140 0.1044470000 741716218 0 1787678720 0.2983438671 0.0492426194 0.6759390235 538 21.4800000000 1.3161982298 1.0541316619 1.7159270048 0.0175670435 0.1359510000 741717472 0 1786028032 0.2979773581 0.0493448339 0.6731035113 539 21.5200000000 1.3109910488 1.0546082099 1.7159270048 0.0175565273 0.1206160000 741718726 0 1786155008 0.2972374856 0.0492866300 0.6704652309 540 21.5600000000 1.3032397032 1.0550686386 1.7159270048 0.0175455425 0.1174620000 741719980 0 1786662912 0.2985633016 0.0495701656 0.6653599739 541 21.6000000000 1.2978978157 1.0555174911 1.7159270048 0.0175351904 0.1356690000 741721234 0 1787170816 0.2987700403 0.0502011552 0.6622382998 542 21.6400000000 1.2908533812 1.0559516902 1.7159270048 0.0175285935 0.1195820000 741722488 0 1787424768 0.2992817163 0.0496523045 0.6576683521 543 21.6800000000 1.2879127264 1.0563788744 1.7159270048 0.0175169000 0.1147180000 741723742 0 1787678720 0.2997316122 0.0488718227 0.6557341814 544 21.7200000000 1.2820703983 1.0567937485 1.7159270048 0.0175028506 0.1195550000 741724996 0 1786085376 0.2996644676 0.0492299944 0.6524055004 545 21.7600000000 1.2757273912 1.0571954616 1.7159270048 0.0174880373 0.1204680000 741726250 0 1786085376 0.3004930615 0.0488425680 0.6483501792 546 21.8000000000 1.2723212242 1.0575894648 1.7159270048 0.0174761442 0.1212620000 741727504 0 1786662912 0.3009881973 0.0491155125 0.6460421681 547 21.8400000000 1.2659761906 1.0579704278 1.7159270048 0.0174610306 0.1332530000 741728758 0 1787170816 0.3015486300 0.0497098789 0.6419890523 548 21.8800000000 1.2630184889 1.0583446031 1.7159270048 0.0174480255 0.1189090000 741730012 0 1787424768 0.3004896939 0.0497712158 0.6407725215 549 21.9200000000 1.2594449520 1.0587109061 1.7159270048 0.0174342457 0.1172010000 741731266 0 1787678720 0.3005996943 0.0496193580 0.6386461854 550 21.9600000000 1.2554657459 1.0590686421 1.7159270048 0.0174211665 0.1376410000 741732520 0 1786085376 0.3003715575 0.0504145361 0.6363725066 551 22.0000000000 1.2509734631 1.0594169268 1.7159270048 0.0174104146 0.1302650000 741733774 0 1786077184 0.3002693355 0.0504243709 0.6336960196 552 22.0400000000 1.2472512722 1.0597572064 1.7159270048 0.0173980655 0.1175610000 741735028 0 1786552320 0.3009192050 0.0510964170 0.6310133338 553 22.0800000000 1.2453205585 1.0600927640 1.7159270048 0.0173895127 0.1241970000 741736282 0 1787060224 0.3005034924 0.0509232059 0.6301549077 554 22.1200000000 1.2412774563 1.0604198121 1.7159270048 0.0173798245 0.1320710000 741737536 0 1787424768 0.3004930317 0.0505016074 0.6278182864 555 22.1600000000 1.2370299101 1.0607380285 1.7159270048 0.0173683687 0.4791360000 754044026 0 1785389056 0.3007123470 0.0514593199 0.6249452829 556 22.2000000000 1.2324594259 1.0610468800 1.7159270048 0.0173598692 0.1331800000 757703128 0 1785929728 0.2992261946 0.0518634617 0.6222900152 557 22.2400000000 1.2297422886 1.0613497443 1.7159270048 0.0173561151 0.1432300000 760896478 0 1785434112 0.2992670536 0.0509579927 0.6207633018 558 22.2800000000 1.2255489826 1.0616440081 1.7159270048 0.0173441921 0.1363440000 760897732 0 1784750080 0.2980395854 0.0501601174 0.6189588308 559 22.3200000000 1.2224792242 1.0619317277 1.7159270048 0.0173341581 0.1263730000 760898986 0 1784750080 0.2979178429 0.0509794019 0.6170326471 560 22.3600000000 1.2202439308 1.0622144280 1.7159270048 0.0173247742 0.1193180000 760900240 0 1785257984 0.2972546220 0.0509993099 0.6160039306 561 22.4000000000 1.2165170908 1.0624894773 1.7159270048 0.0173160830 0.1253070000 760901494 0 1785765888 0.2982729673 0.0503827743 0.6130548120 562 22.4400000000 1.2141941786 1.0627594145 1.7159270048 0.0173059990 0.1173510000 760902748 0 1786146816 0.2975940406 0.0512825772 0.6122226119 563 22.4800000000 1.2093683481 1.0630198212 1.7159270048 0.0172990826 0.1191230000 760904002 0 1786273792 0.2981368303 0.0512790456 0.6091138721 564 22.5200000000 1.2059886456 1.0632733120 1.7159270048 0.0172920410 0.1212740000 760905256 0 1786781696 0.2982551455 0.0506408177 0.6071069837 565 22.5600000000 1.2003513575 1.0635159280 1.7159270048 0.0172843325 0.1232240000 760906510 0 1787289600 0.2993355989 0.0500302985 0.6029996872 566 22.6000000000 1.1967544556 1.0637513317 1.7159270048 0.0172773171 0.1228610000 760907764 0 1787924480 0.2994122505 0.0497831926 0.6007124782 567 22.6400000000 1.1934363842 1.0639800532 1.7159270048 0.0172689799 0.1105890000 760909018 0 1786077184 0.2997477949 0.0496874489 0.5986202955 568 22.6800000000 1.1889821291 1.0642001273 1.7159270048 0.0172594224 0.1230890000 760910272 0 1786171392 0.3002704978 0.0490792878 0.5956677198 569 22.7200000000 1.1835241318 1.0644098355 1.7159270048 0.0172488121 0.5301680000 773217230 0 1785389056 0.3008163571 0.0486727320 0.5920853615 570 22.7600000000 1.1775301695 1.0646082922 1.7159270048 0.0172416636 0.1465960000 776876332 0 1785929728 0.3017167747 0.0494313277 0.5881200433 571 22.8000000000 1.1721849442 1.0647966927 1.7159270048 0.0172332991 0.1275650000 780069682 0 1785298944 0.3008374572 0.0501483902 0.5855448246 572 22.8400000000 1.1670517921 1.0649754603 1.7159270048 0.0172275260 0.1319210000 780070936 0 1784651776 0.3007138968 0.0489240848 0.5826141238 573 22.8800000000 1.1614346504 1.0651438010 1.7159270048 0.0172164681 0.1109400000 780072190 0 1784651776 0.3003678024 0.0489136055 0.5794388652 574 22.9200000000 1.1566756964 1.0653032642 1.7159270048 0.0172051088 0.1071250000 780073444 0 1785147392 0.2994468808 0.0495079197 0.5770533085 575 22.9600000000 1.1506438255 1.0654516826 1.7159270048 0.0171957369 0.1269050000 780074698 0 1785655296 0.2987793386 0.0485213287 0.5738521814 576 23.0000000000 1.1461161375 1.0655917250 1.7159270048 0.0171832875 0.1112000000 780075952 0 1786036224 0.2982968390 0.0476562120 0.5714001656 577 23.0400000000 1.1403203011 1.0657212373 1.7159270048 0.0171713276 0.1087390000 780077206 0 1786146816 0.2975497544 0.0481881648 0.5682145953 578 23.0800000000 1.1345789433 1.0658403683 1.7159270048 0.0171600598 0.1025950000 780078460 0 1786654720 0.2972599566 0.0481502339 0.5648781657 579 23.1200000000 1.1291846037 1.0659497711 1.7159270048 0.0171479066 0.1201090000 780079714 0 1787162624 0.2966483533 0.0475032143 0.5617821217 580 23.1600000000 1.1230754852 1.0660482637 1.7159270048 0.0171346026 0.1159770000 780080968 0 1787670528 0.2963704467 0.0472299159 0.5582723022 581 23.2000000000 1.1172448397 1.0661363818 1.7159270048 0.0171209940 0.1167080000 780082222 0 1785929728 0.2955771387 0.0474196039 0.5551995039 582 23.2400000000 1.1103911400 1.0662124209 1.7159270048 0.0171102736 0.1218220000 780083476 0 1786023936 0.2950203419 0.0468883589 0.5514229536 583 23.2800000000 1.1049293280 1.0662788307 1.7159270048 0.0170974577 0.1325420000 780084730 0 1786654720 0.2949220240 0.0456234366 0.5481642485 584 23.3200000000 1.0979053974 1.0663329857 1.7159270048 0.0170852079 0.5883260000 792392512 0 1786404864 0.2941507101 0.0457791761 0.5442694426 585 23.3600000000 1.0911034346 1.0663753284 1.7159270048 0.0170736156 0.1378920000 796051614 0 1784758272 0.2941809297 0.0463319868 0.5399131775 586 23.4000000000 1.0845799446 1.0664063943 1.7159270048 0.0170618637 0.1369150000 799244964 0 1785167872 0.2938672602 0.0453824140 0.5361938477 587 23.4400000000 1.0788115263 1.0664275274 1.7159270048 0.0170523367 0.1046160000 799246218 0 1784520704 0.2929197550 0.0451649129 0.5329489708 588 23.4800000000 1.0624345541 1.0664207366 1.7159270048 0.0170517859 0.1030150000 799247472 0 1784520704 0.2917709351 0.0459237173 0.5237830877 589 23.5200000000 1.0563657284 1.0664036653 1.7159270048 0.0170432046 0.0987830000 799248726 0 1785016320 0.2910550237 0.0466365032 0.5203417540 590 23.5600000000 1.0491544008 1.0663744292 1.7159270048 0.0170398413 0.0956680000 799249980 0 1785651200 0.2900753915 0.0469460562 0.5165148377 591 23.6000000000 1.0422948599 1.0663336855 1.7159270048 0.0170389210 0.0947040000 799251234 0 1785905152 0.2894071341 0.0466798209 0.5127289891 592 23.6400000000 1.0340557098 1.0662791619 1.7159270048 0.0170298723 0.0992740000 799252488 0 1786146816 0.2887027264 0.0461332500 0.5081175566 593 23.6800000000 1.0265445709 1.0662121558 1.7159270048 0.0170189315 0.0986670000 799253742 0 1786654720 0.2879713178 0.0461452976 0.5038032532 594 23.7200000000 1.0194096565 1.0661333637 1.7159270048 0.0170073721 0.1116290000 799254996 0 1787162624 0.2872276306 0.0462744348 0.4998259544 595 23.7600000000 1.0133562088 1.0660446626 1.7159270048 0.0169959065 0.5588590000 811562518 0 1784688640 0.2862951756 0.0460113883 0.4967412949 596 23.8000000000 1.0057312250 1.0659434656 1.7159270048 0.0169835878 0.1412810000 815221620 0 1785290752 0.2851987481 0.0459958240 0.4924643040 597 23.8400000000 0.9990099072 1.0658313491 1.7159270048 0.0169727241 0.1177750000 818414970 0 1785696256 0.2842781246 0.0468520373 0.4888220429 598 23.8800000000 0.9909793139 1.0657061784 1.7159270048 0.0169658461 0.0969870000 818416224 0 1785049088 0.2833856344 0.0467569903 0.4842058718 599 23.9200000000 0.9842659235 1.0655702181 1.7159270048 0.0169566043 0.0956390000 818417478 0 1785049088 0.2818638682 0.0474743992 0.4811336994 600 23.9600000000 0.9773824811 1.0654232385 1.7159270048 0.0169514248 0.1078500000 818418732 0 1785671680 0.2812392712 0.0476374105 0.4770962596 601 24.0000000000 0.9705631733 1.0652654015 1.7159270048 0.0169429071 0.0966430000 818419986 0 1786179584 0.2799947262 0.0473167412 0.4738030434 602 24.0400000000 0.9630229473 1.0650955635 1.7159270048 0.0169320896 0.1055850000 818421240 0 1786433536 0.2790745497 0.0479142927 0.4694697261 603 24.0800000000 0.9568503499 1.0649160524 1.7159270048 0.0169210612 0.0980320000 818422494 0 1786654720 0.2779633105 0.0477061719 0.4664203227 604 24.1200000000 0.9512172341 1.0647278093 1.7159270048 0.0169090561 0.0998120000 818423748 0 1787162624 0.2766343951 0.0482997224 0.4636432827 605 24.1600000000 0.9453837872 1.0645305465 1.7159270048 0.0168992415 0.1131000000 818425002 0 1787670528 0.2756608725 0.0477297977 0.4606608152 606 24.2000000000 0.9401922226 1.0643253677 1.7159270048 0.0168881547 0.0995590000 818426256 0 1786019840 0.2748518288 0.0469912104 0.4579882920 607 24.2400000000 0.9324724674 1.0641081471 1.7159270048 0.0168760751 0.0951250000 818427510 0 1786019840 0.2738642991 0.0472976789 0.4536564648 608 24.2800000000 0.9266578555 1.0638820775 1.7159270048 0.0168635866 0.1134760000 818428764 0 1786654720 0.2727278769 0.0478033610 0.4507358968 609 24.3200000000 0.9210671782 1.0636475703 1.7159270048 0.0168543713 0.5984940000 830737138 0 1786404864 0.2721246779 0.0470473953 0.4475438595 610 24.3600000000 0.9156752229 1.0634049927 1.7159270048 0.0168432810 0.1371500000 834396240 0 1784750080 0.2716706395 0.0454637967 0.4445854127 611 24.4000000000 0.9078539014 1.0631504083 1.7159270048 0.0168313435 0.1113770000 837589590 0 1785315328 0.2710002959 0.0454596244 0.4398973584 612 24.4400000000 0.9018597603 1.0628868615 1.7159270048 0.0168194342 0.0924310000 837590844 0 1784541184 0.2699999213 0.0461720116 0.4366862774 613 24.4800000000 0.8970178962 1.0626162759 1.7159270048 0.0168090959 0.0888900000 837592098 0 1784541184 0.2691766918 0.0452995785 0.4341229498 614 24.5200000000 0.8891823888 1.0623338103 1.7159270048 0.0167989589 0.0891140000 837593352 0 1785016320 0.2683636844 0.0449353084 0.4297735095 615 24.5600000000 0.8840971589 1.0620439946 1.7159270048 0.0167864113 0.0869010000 837594606 0 1785651200 0.2678406537 0.0448988415 0.4268907905 616 24.6000000000 0.8775755763 1.0617445328 1.7159270048 0.0167745398 0.0878090000 837595860 0 1785905152 0.2672298849 0.0439981818 0.4230993092 617 24.6400000000 0.8709788322 1.0614353502 1.7159270048 0.0167632058 0.0880850000 837597114 0 1786146816 0.2662757039 0.0435587019 0.4195898473 618 24.6800000000 0.8637547493 1.0611154787 1.7159270048 0.0167530585 0.0908000000 837598368 0 1786654720 0.2657384872 0.0436121710 0.4150637686 619 24.7200000000 0.8551272750 1.0607827029 1.7159270048 0.0167423802 0.1137000000 837599622 0 1787162624 0.2651306689 0.0434566848 0.4100067616 620 24.7600000000 0.8493325114 1.0604416542 1.7159270048 0.0167328313 0.6900340000 849909268 0 1787416576 0.2640829980 0.0438495800 0.4069279134 621 24.8000000000 0.8433536291 1.0600920761 1.7159270048 0.0167232930 0.1385810000 853568370 0 1784909824 0.2638290524 0.0440544821 0.4029055834 622 24.8400000000 0.8368584514 1.0597331796 1.7159270048 0.0167124934 0.0964290000 856761720 0 1785421824 0.2630054653 0.0436721668 0.3992755115 623 24.8800000000 0.8302907348 1.0593648931 1.7159270048 0.0167018878 0.0852490000 856762974 0 1784807424 0.2620719671 0.0439454280 0.3957595229 624 24.9200000000 0.8234642744 1.0589868473 1.7159270048 0.0166915545 0.0865080000 856764228 0 1784750080 0.2607899904 0.0441480279 0.3919512033 625 24.9600000000 0.8170843124 1.0585998032 1.7159270048 0.0166817084 0.0824400000 856765482 0 1785131008 0.2597193122 0.0438756049 0.3886361420 626 25.0000000000 0.8112921715 1.0582047431 1.7159270048 0.0166712842 0.0819330000 856766736 0 1785765888 0.2588309050 0.0430879332 0.3856246173 627 25.0400000000 0.8049324751 1.0578008001 1.7159270048 0.0166620984 0.0792650000 856767990 0 1786146816 0.2574925721 0.0431882925 0.3823822737 628 25.0800000000 0.7984540462 1.0573878275 1.7159270048 0.0166546751 0.7104820000 869077788 0 1786023936 0.2561604679 0.0440824553 0.3790749013 629 25.1200000000 0.7941255569 1.0569692866 1.7159270048 0.0166491651 0.0879610000 872736890 0 1786908672 0.2547384799 0.0433977619 0.3773269951 630 25.1600000000 0.7877140641 1.0565418973 1.7159270048 0.0166441115 0.0986050000 875930240 0 1787543552 0.2533538640 0.0436646454 0.3739615083 631 25.2000000000 0.7818593979 1.0561065843 1.7159270048 0.0166417618 0.0746310000 875931494 0 1785421824 0.2518381178 0.0439086147 0.3710048795 632 25.2400000000 0.7772603631 1.0556653720 1.7159270048 0.0166393148 0.0726260000 875932748 0 1785421824 0.2504226565 0.0434893109 0.3691746891 633 25.2800000000 0.7703455091 1.0552146297 1.7159270048 0.0166357149 0.0715540000 875934002 0 1785896960 0.2487951219 0.0437232666 0.3656304479 634 25.3200000000 0.7641711235 1.0547555705 1.7159270048 0.0166330917 0.0699420000 875935256 0 1786531840 0.2468411773 0.0443947390 0.3631552160 635 25.3600000000 0.7596703768 1.0542908694 1.7159270048 0.0166331110 0.6356390000 888243494 0 1786277888 0.2454335093 0.0441032834 0.3613165915 636 25.4000000000 0.7539702654 1.0538186672 1.7159270048 0.0166323753 0.0965880000 891902596 0 1787162624 0.2444346994 0.0438625142 0.3574295342 637 25.4400000000 0.7485428452 1.0533394273 1.7159270048 0.0166263796 0.0762110000 895095946 0 1787416576 0.2428450584 0.0437344126 0.3550466001 638 25.4800000000 0.7430940270 1.0528531493 1.7159270048 0.0166188237 0.0720940000 895097200 0 1785548800 0.2415193319 0.0436794646 0.3523827195 639 25.5200000000 0.7379392385 1.0523603262 1.7159270048 0.0166111877 0.0705780000 895098454 0 1785548800 0.2396842390 0.0428632982 0.3505386412 640 25.5600000000 0.7332068682 1.0518616490 1.7159270048 0.0166011727 0.0686800000 895099708 0 1786023936 0.2381906807 0.0428539403 0.3485299349 641 25.6000000000 0.7281922102 1.0513567044 1.7159270048 0.0165927947 0.0724470000 895100962 0 1786531840 0.2366673797 0.0422094464 0.3455967903 642 25.6400000000 0.7231440544 1.0508454698 1.7159270048 0.0165817551 0.0716400000 895102216 0 1786912768 0.2345231175 0.0428219549 0.3444520235 643 25.6800000000 0.7175840139 1.0503271782 1.7159270048 0.0165711820 0.0689960000 895103470 0 1787162624 0.2328306437 0.0424879827 0.3425099254 644 25.7200000000 0.7125866413 1.0498027364 1.7159270048 0.0165608879 0.0676660000 895104724 0 1787670528 0.2308299392 0.0423353761 0.3410011232 645 25.7600000000 0.7072170973 1.0492715959 1.7159270048 0.0165511334 0.0766800000 895105978 0 1786077184 0.2291254848 0.0421567149 0.3389087021 646 25.8000000000 0.7024521232 1.0487347236 1.7159270048 0.0165408380 0.0707020000 895107232 0 1786077184 0.2268032730 0.0418671481 0.3378616273 647 25.8400000000 0.6962650418 1.0481899482 1.7159270048 0.0165311255 0.0704400000 895108486 0 1786527744 0.2241160721 0.0421796702 0.3363859057 648 25.8800000000 0.6911189556 1.0476389128 1.7159270048 0.0165247125 0.5865880000 907417496 0 1786150912 0.2219248563 0.0426196903 0.3349459767 649 25.9200000000 0.6858130693 1.0470813999 1.7159270048 0.0165197001 0.0716520000 911076598 0 1786908672 0.2196364254 0.0421982855 0.3329949379 650 25.9600000000 0.6752776504 1.0465093941 1.7159270048 0.0165201962 0.0918970000 914269948 0 1787289600 0.2149113119 0.0404214039 0.3300557435 651 26.0000000000 0.6626011133 1.0459196733 1.7159270048 0.0165179743 0.0755950000 914271202 0 1785315328 0.2087317854 0.0414837934 0.3272341788 652 26.0400000000 0.6560513377 1.0453217157 1.7159270048 0.0165129146 0.0670950000 914272456 0 1785315328 0.2054659128 0.0410741568 0.3252047896 653 26.0800000000 0.6496155262 1.0447157338 1.7159270048 0.0165101948 0.0680170000 914273710 0 1785765888 0.2018876225 0.0422960743 0.3239670396 654 26.1200000000 0.6435861588 1.0441023858 1.7159270048 0.0165137261 0.0679220000 914274964 0 1786273792 0.1983387470 0.0429731198 0.3229235411 655 26.1600000000 0.6365499496 1.0434801684 1.7159270048 0.0165078362 0.0731250000 914276218 0 1786654720 0.1949622035 0.0426321253 0.3213470876 656 26.2000000000 0.6301667094 1.0428501174 1.7159270048 0.0165002568 0.0734790000 914277472 0 1786781696 0.1911221296 0.0437796935 0.3199965954 657 26.2400000000 0.6241648197 1.0422128490 1.7159270048 0.0164927060 0.0725070000 914278726 0 1787289600 0.1873700470 0.0438095331 0.3188698590 658 26.2800000000 0.6170877218 1.0415667622 1.7159270048 0.0164845495 0.0742190000 914279980 0 1787924480 0.1833954751 0.0447425023 0.3178256750 659 26.3200000000 0.6110256314 1.0409134373 1.7159270048 0.0164779648 0.0756590000 914281234 0 1786077184 0.1794866025 0.0451185517 0.3166345358 660 26.3600000000 0.6054344773 1.0402536207 1.7159270048 0.0164741185 0.0751180000 914282488 0 1785561088 0.1756602824 0.0454657562 0.3150460422 661 26.4000000000 0.5985035300 1.0395853149 1.7159270048 0.0164699508 0.0750680000 914283742 0 1785561088 0.1715490669 0.0460360907 0.3141976893 662 26.4400000000 0.5930376649 1.0389107716 1.7159270048 0.0164714796 0.0882110000 914284996 0 1786036224 0.1675517410 0.0466549397 0.3141624331 663 26.4800000000 0.5869128704 1.0382290252 1.7159270048 0.0164815025 0.0805400000 914286250 0 1786544128 0.1637150794 0.0469844565 0.3134927154 664 26.5200000000 0.5808979869 1.0375402736 1.7159270048 0.0164850846 0.0739610000 914287504 0 1786925056 0.1599734575 0.0471533351 0.3106898665 665 26.5600000000 0.5752024651 1.0368450288 1.7159270048 0.0164789551 0.0818370000 914288758 0 1786925056 0.1563731134 0.0475667305 0.3101205528 666 26.6000000000 0.5689734817 1.0361425190 1.7159270048 0.0164761187 0.5996240000 926598308 0 1787416576 0.1526197344 0.0480766483 0.3094008565 667 26.6400000000 0.5636025667 1.0354340633 1.7159270048 0.0164745179 0.0828440000 930257410 0 1787543552 0.1483416408 0.0499790125 0.3103689849 668 26.6800000000 0.5582824349 1.0347197644 1.7159270048 0.0164966051 0.0904790000 933450760 0 1788051456 0.1446127295 0.0509757251 0.3091934025 669 26.7200000000 0.5531358123 1.0339999080 1.7159270048 0.0165303431 0.0809950000 933452014 0 1786023936 0.1407277733 0.0513161272 0.3081997335 670 26.7600000000 0.5480734110 1.0332746446 1.7159270048 0.0165527367 0.0793320000 933453268 0 1785155584 0.1374495775 0.0511779748 0.3074030280 671 26.8000000000 0.5427534580 1.0325436145 1.7159270048 0.0165571742 0.0702140000 933454522 0 1785131008 0.1340602338 0.0512941927 0.3062637448 672 26.8400000000 0.5375812054 1.0318070633 1.7159270048 0.0165519185 0.0700610000 933455776 0 1785638912 0.1307608634 0.0523414388 0.3047188520 673 26.8800000000 0.5324800014 1.0310651211 1.7159270048 0.0165467611 0.0676600000 933457030 0 1786146816 0.1278009266 0.0519206859 0.3036755323 674 26.9200000000 0.5272571445 1.0303176316 1.7159270048 0.0165382231 0.0680110000 933458284 0 1786527744 0.1247551739 0.0526508875 0.3027704060 675 26.9600000000 0.5230010748 1.0295660515 1.7159270048 0.0165305696 0.0671230000 933459538 0 1786654720 0.1218078807 0.0532559454 0.3019029200 676 27.0000000000 0.5184688568 1.0288099905 1.7159270048 0.0165275191 0.0710730000 933460792 0 1787162624 0.1184857935 0.0543628447 0.3007765710 677 27.0400000000 0.5147253871 1.0280506337 1.7159270048 0.0165357340 0.0752720000 933462046 0 1787797504 0.1155037135 0.0547216460 0.3005413711 678 27.0800000000 0.5106874704 1.0272875611 1.7159270048 0.0165429391 0.0899690000 933463300 0 1785929728 0.1126212850 0.0556176268 0.2992861569 679 27.1200000000 0.5060150623 1.0265198550 1.7159270048 0.0165507039 0.0735370000 933464554 0 1785286656 0.1095122173 0.0561945960 0.2979691029 680 27.1600000000 0.5006621480 1.0257465348 1.7159270048 0.0165497557 0.0788880000 933465808 0 1785286656 0.1069097444 0.0559150055 0.2966161966 681 27.2000000000 0.4963883162 1.0249692100 1.7159270048 0.0165423786 0.0745590000 933467062 0 1785778176 0.1041078493 0.0561063103 0.2955482602 682 27.2400000000 0.4918347895 1.0241874879 1.7159270048 0.0165368983 0.0737400000 933468316 0 1786286080 0.1013557985 0.0566604733 0.2942887545 683 27.2800000000 0.4872173071 1.0234012944 1.7159270048 0.0165359024 0.0854920000 933469570 0 1786667008 0.0986102223 0.0574197993 0.2928942144 684 27.3200000000 0.4824891686 1.0226104872 1.7159270048 0.0165389127 0.0773150000 933470824 0 1786781696 0.0957763344 0.0576656945 0.2915340960 685 27.3600000000 0.4773262441 1.0218144518 1.7159270048 0.0165358620 0.0862640000 933472078 0 1787289600 0.0929895788 0.0581771731 0.2896222770 686 27.4000000000 0.4717403352 1.0210125945 1.7159270048 0.0165325573 0.0876310000 933473332 0 1787924480 0.0901443660 0.0591306277 0.2881963849 687 27.4400000000 0.4666041136 1.0202055953 1.7159270048 0.0165407041 0.0969870000 933474586 0 1786077184 0.0872671232 0.0597272515 0.2863757610 688 27.4800000000 0.4613892436 1.0193933622 1.7159270048 0.0165505950 0.1006700000 933475840 0 1786298368 0.0843298882 0.0608596802 0.2845213413 689 27.5200000000 0.4558504820 1.0185754480 1.7159270048 0.0165647889 0.0886530000 933477094 0 1786806272 0.0816163123 0.0600188598 0.2830443382 690 27.5600000000 0.4499880672 1.0177514083 1.7159270048 0.0165628136 0.1095910000 933478348 0 1787314176 0.0788244382 0.0611732155 0.2807528377 691 27.6000000000 0.4441843033 1.0169213546 1.7159270048 0.0165668589 0.1107450000 933479602 0 1787441152 0.0759216547 0.0619765818 0.2791237533 692 27.6400000000 0.4385271668 1.0160855249 1.7159270048 0.0165807550 0.1330480000 933480856 0 1787797504 0.0729137957 0.0631037503 0.2771424055 693 27.6800000000 0.4321822524 1.0152429516 1.7159270048 0.0166047147 0.1157370000 933482110 0 1786019840 0.0701968521 0.0629984662 0.2749930918 694 27.7200000000 0.4252389371 1.0143928017 1.7159270048 0.0166240702 0.0895090000 933483364 0 1786273792 0.0677497238 0.0611460097 0.2727477551 695 27.7600000000 0.4191826582 1.0135363842 1.7159270048 0.0166213787 0.0929740000 933484618 0 1786781696 0.0653513893 0.0614287108 0.2701496482 696 27.8000000000 0.4130707681 1.0126736463 1.7159270048 0.0166189728 0.5837240000 945794088 0 1786908672 0.0626813546 0.0617846474 0.2679034472 697 27.8400000000 0.4049550593 1.0118017401 1.7159270048 0.0166192220 0.1156110000 949453190 0 1784524800 0.0598535277 0.0634319112 0.2681262791 698 27.8800000000 0.3995276690 1.0109245567 1.7159270048 0.0166266308 0.0855480000 952646540 0 1785167872 0.0568378493 0.0644037873 0.2662082016 699 27.9200000000 0.3945044875 1.0100426968 1.7159270048 0.0166410965 0.0833500000 952647794 0 1785257984 0.0540575869 0.0652390197 0.2643707097 700 27.9600000000 0.3889866471 1.0091554738 1.7159270048 0.0166573195 0.0826530000 952649048 0 1784160256 0.0510716736 0.0660392195 0.2622793019 701 28.0000000000 0.3840253949 1.0082637048 1.7159270048 0.0166737798 0.0835310000 952650302 0 1784160256 0.0482878909 0.0666554719 0.2602618635 702 28.0400000000 0.3787784278 1.0073670021 1.7159270048 0.0166880081 0.0814190000 952651556 0 1784643584 0.0456314646 0.0664960295 0.2584581673 703 28.0800000000 0.3745972216 1.0064669029 1.7159270048 0.0166937875 0.0814490000 952652810 0 1785151488 0.0432432108 0.0665300414 0.2571075261 704 28.1200000000 0.3712294102 1.0055645769 1.7159270048 0.0167023079 0.0913890000 952654064 0 1785532416 0.0402975790 0.0683774129 0.2558717728 705 28.1600000000 0.3679395616 1.0046601443 1.7159270048 0.0167198072 0.0911730000 952655318 0 1785638912 0.0374052823 0.0697875097 0.2544563711 706 28.2000000000 0.3642267287 1.0037530148 1.7159270048 0.0167320398 0.1109300000 952656572 0 1786146816 0.0350360014 0.0694802105 0.2532774806 707 28.2400000000 0.3612959683 1.0028443061 1.7159270048 0.0167330357 0.1164640000 952657826 0 1786654720 0.0323819146 0.0705320239 0.2520073354 708 28.2800000000 0.3589887321 1.0019349055 1.7159270048 0.0167289501 0.6321180000 964967400 0 1786785792 0.0295771174 0.0718848631 0.2511630356 709 28.3200000000 0.3592940867 1.0010285010 1.7159270048 0.0167334382 0.1277020000 968626502 0 1784541184 0.0275361687 0.0696791410 0.2467944920 710 28.3600000000 0.3564533889 1.0001206487 1.7159270048 0.0167225392 0.0944360000 971819852 0 1785061376 0.0251476392 0.0702325702 0.2457323819 711 28.4000000000 0.3554386199 0.9992139230 1.7159270048 0.0167153274 0.0916580000 971821106 0 1784414208 0.0225177165 0.0719415322 0.2458252013 712 28.4400000000 0.3536040187 0.9983071675 1.7159270048 0.0167102156 0.0866210000 971822360 0 1784414208 0.0199231785 0.0724860951 0.2451379150 713 28.4800000000 0.3521326482 0.9974008919 1.7159270048 0.0167011562 0.0911420000 971823614 0 1784877056 0.0180675238 0.0717332512 0.2446087897 714 28.5200000000 0.3524531424 0.9964976037 1.7159270048 0.0166913959 0.0883800000 971824868 0 1785511936 0.0154005187 0.0734950751 0.2447922379 715 28.5600000000 0.3529983759 0.9955976048 1.7159270048 0.0166814936 0.1007670000 971826122 0 1785765888 0.0123848990 0.0757788196 0.2447382808 716 28.6000000000 0.3543303907 0.9947019802 1.7159270048 0.0166780814 0.0882380000 971827376 0 1785892864 0.0101320669 0.0758149400 0.2456121296 717 28.6400000000 0.3559983373 0.9938111801 1.7159270048 0.0166701333 0.0876120000 971828630 0 1786400768 0.0079830401 0.0763748065 0.2466265261 718 28.6800000000 0.3583473563 0.9929261330 1.7159270048 0.0166615632 0.1117780000 971829884 0 1786908672 0.0055703148 0.0781337842 0.2477128953 719 28.7200000000 0.3600030541 0.9920458506 1.7159270048 0.0166566568 0.1029860000 971831138 0 1787543552 0.0030014641 0.0792153329 0.2485135645 720 28.7600000000 0.3626637161 0.9911717087 1.7159270048 0.0166505756 0.1028460000 971832392 0 1788051456 0.0005106946 0.0799575225 0.2498593479 721 28.8000000000 0.3656845689 0.9903041815 1.7159270048 0.0166420392 0.4969850000 984138142 0 1787932672 -0.0018356517 0.0801885352 0.2514722943 722 28.8400000000 0.3688359857 0.9894434222 1.7159270048 0.0166356655 0.1141260000 987797244 0 1786060800 -0.0041134823 0.0790147036 0.2537175119 723 28.8800000000 0.3725430071 0.9885901713 1.7159270048 0.0166267576 0.0879360000 990990594 0 1786413056 -0.0067257788 0.0794512480 0.2555945218 724 28.9200000000 0.3765375912 0.9877447948 1.7159270048 0.0166182133 0.0824340000 990991848 0 1784762368 -0.0094740614 0.0798978806 0.2574774027 725 28.9600000000 0.3808329403 0.9869076750 1.7159270048 0.0166129149 0.0801580000 990993102 0 1784762368 -0.0123213036 0.0806212798 0.2595846951 726 29.0000000000 0.3851522803 0.9860788108 1.7159270048 0.0166120183 0.0799940000 990994356 0 1785397248 -0.0149385696 0.0808990523 0.2617265880 727 29.0400000000 0.3896991313 0.9852584811 1.7159270048 0.0166108354 0.0795670000 990995610 0 1785905152 -0.0181434955 0.0815703645 0.2637937963 728 29.0800000000 0.3948225081 0.9844474427 1.7159270048 0.0166107322 0.5683320000 1003302784 0 1785937920 -0.0210011993 0.0820467696 0.2661657333 729 29.1200000000 0.3994998336 0.9836450454 1.7159270048 0.0166065909 0.1047320000 1006961886 0 1786535936 -0.0236697048 0.0821702331 0.2697731256 730 29.1600000000 0.4046405554 0.9828518886 1.7159270048 0.0166013906 0.0853860000 1010155236 0 1786793984 -0.0265279412 0.0822484046 0.2721687555 731 29.2000000000 0.4098356962 0.9820680087 1.7159270048 0.0165951325 0.0771050000 1010156490 0 1784946688 -0.0296997987 0.0829929188 0.2744853497 732 29.2400000000 0.4156867564 0.9812942638 1.7159270048 0.0165912068 0.0742400000 1010157744 0 1784946688 -0.0331207141 0.0843189359 0.2768265009 733 29.2800000000 0.4223506749 0.9805317214 1.7159270048 0.0165863726 0.0734120000 1010158998 0 1785421824 -0.0363317914 0.0852986574 0.2796440721 734 29.3200000000 0.4296673536 0.9797812250 1.7159270048 0.0165794049 0.0730320000 1010160252 0 1785929728 -0.0395273007 0.0864454135 0.2827686071 735 29.3600000000 0.4366228580 0.9790422340 1.7159270048 0.0165722763 0.5370400000 1022468330 0 1785937920 -0.0424751192 0.0874404535 0.2858234644 736 29.4000000000 0.4438884258 0.9783151229 1.7159270048 0.0165655226 0.0914960000 1026127432 0 1786535936 -0.0455260985 0.0902722403 0.2885215282 737 29.4400000000 0.4508048892 0.9775993695 1.7159270048 0.0165584083 0.0758240000 1029320782 0 1786920960 -0.0482821167 0.0913624838 0.2915210128 738 29.4800000000 0.4579672217 0.9768952609 1.7159270048 0.0165572278 0.0736940000 1029322036 0 1785053184 -0.0513435043 0.0924007893 0.2944910526 739 29.5200000000 0.4649308324 0.9762024809 1.7159270048 0.0165642085 0.0704620000 1029323290 0 1785053184 -0.0538547114 0.0932899490 0.2976778448 740 29.5600000000 0.4716887772 0.9755207056 1.7159270048 0.0165710152 0.0677940000 1029324544 0 1785528320 -0.0563636720 0.0943201259 0.3005383611 741 29.6000000000 0.4788523316 0.9748504379 1.7159270048 0.0165795046 0.0818920000 1029325798 0 1786036224 -0.0586732626 0.0959268883 0.3034966886 742 29.6400000000 0.4859471023 0.9741915385 1.7159270048 0.0165839110 0.4692710000 1041631544 0 1785937920 -0.0607477911 0.0971882939 0.3066483438 743 29.6800000000 0.4920351803 0.9735426067 1.7159270048 0.0165774422 0.0787500000 1045290646 0 1786413056 -0.0622718446 0.0980866626 0.3091135323 744 29.7200000000 0.4974264503 0.9729026656 1.7159270048 0.0165690859 0.0728060000 1048483996 0 1786916864 -0.0639264584 0.0988866240 0.3115127385 745 29.7600000000 0.5028115511 0.9722716708 1.7159270048 0.0165619481 0.0717970000 1048485250 0 1785065472 -0.0657824948 0.0996873826 0.3136286139 746 29.8000000000 0.5076699853 0.9716488804 1.7159270048 0.0165537057 0.0688770000 1048486504 0 1785065472 -0.0672606528 0.1001743004 0.3160182536 747 29.8400000000 0.5127304792 0.9710345318 1.7159270048 0.0165458426 0.0690730000 1048487758 0 1785540608 -0.0691106617 0.1011667028 0.3179355264 748 29.8800000000 0.5179082751 0.9704287480 1.7159270048 0.0165391247 0.0693260000 1048489012 0 1786048512 -0.0708387569 0.1024295837 0.3199233115 749 29.9200000000 0.5226526260 0.9698309161 1.7159270048 0.0165314968 0.0689510000 1048490266 0 1786429440 -0.0721622556 0.1034497172 0.3219358325 750 29.9600000000 0.5270142555 0.9692404938 1.7159270048 0.0165238996 0.0727110000 1048491520 0 1786535936 -0.0735169351 0.1044165194 0.3238282502 751 30.0000000000 0.5309985280 0.9686569493 1.7159270048 0.0165164320 0.4559080000 1060798566 0 1787068416 -0.0748830289 0.1051125750 0.3253644109 752 30.0400000000 0.5349168181 0.9680801672 1.7159270048 0.0165080293 0.0655370000 1064457668 0 1787551744 -0.0759688765 0.1064563319 0.3266011178 753 30.0800000000 0.5380778909 0.9675091150 1.7159270048 0.0165004552 0.0830210000 1067651018 0 1787805696 -0.0773830190 0.1071781814 0.3279450238 754 30.1200000000 0.5413407087 0.9669439050 1.7159270048 0.0164960871 0.0747220000 1067652272 0 1785937920 -0.0786242485 0.1078151166 0.3291545510 755 30.1600000000 0.5443254709 0.9663841454 1.7159270048 0.0164933163 0.0740310000 1067653526 0 1785290752 -0.0799093395 0.1082933620 0.3303597271 756 30.2000000000 0.5478361845 0.9658305106 1.7159270048 0.0164905197 0.0739300000 1067654780 0 1785290752 -0.0813783556 0.1092411503 0.3316336870 757 30.2400000000 0.5511705279 0.9652827431 1.7159270048 0.0164846585 0.0764440000 1067656034 0 1785786368 -0.0831343606 0.1102155223 0.3327192664 758 30.2800000000 0.5546603203 0.9647410249 1.7159270048 0.0164787737 0.0720880000 1067657288 0 1786294272 -0.0846705139 0.1107739583 0.3338998556 759 30.3200000000 0.5584594607 0.9642057395 1.7159270048 0.0164795122 0.0729000000 1067658542 0 1786662912 -0.0865594670 0.1118368730 0.3351294100 760 30.3600000000 0.5625370741 0.9636772281 1.7159270048 0.0164793860 0.0730860000 1067659796 0 1786781696 -0.0886747986 0.1133584902 0.3363267481 761 30.4000000000 0.5662807226 0.9631550251 1.7159270048 0.0164770248 0.0728660000 1067661050 0 1787289600 -0.0908374265 0.1145848557 0.3371849954 762 30.4400000000 0.5697249174 0.9626387126 1.7159270048 0.0164710680 0.0755270000 1067662304 0 1787797504 -0.0930218101 0.1158374026 0.3381036520 763 30.4800000000 0.5734813213 0.9621286767 1.7159270048 0.0164648535 0.0764760000 1067663558 0 1786077184 -0.0954629853 0.1172206774 0.3388609290 764 30.5200000000 0.5772337317 0.9616248875 1.7159270048 0.0164593525 0.0774220000 1067664812 0 1785434112 -0.0980224684 0.1185036898 0.3397000730 765 30.5600000000 0.5811582804 0.9611275455 1.7159270048 0.0164532656 0.0761370000 1067666066 0 1785434112 -0.1006586105 0.1197753996 0.3404599130 766 30.6000000000 0.5850070119 0.9606365266 1.7159270048 0.0164478417 0.0789410000 1067667320 0 1785798656 -0.1033352688 0.1209216490 0.3413079083 767 30.6400000000 0.5889736414 0.9601519596 1.7159270048 0.0164426786 0.0789700000 1067668574 0 1786433536 -0.1059759557 0.1222228929 0.3420616686 768 30.6800000000 0.5928903818 0.9596737544 1.7159270048 0.0164393827 0.0782820000 1067669828 0 1786814464 -0.1089067310 0.1234960482 0.3427661657 769 30.7200000000 0.5971422791 0.9592023221 1.7159270048 0.0164357483 0.0784730000 1067671082 0 1786908672 -0.1115645915 0.1249052137 0.3435394764 770 30.7600000000 0.6013413668 0.9587375676 1.7159270048 0.0164303434 0.4592250000 1079982352 0 1787289600 -0.1144464090 0.1263143122 0.3443639278 771 30.8000000000 0.6035295725 0.9582768568 1.7159270048 0.0164205998 0.1211610000 1083641454 0 1785167872 -0.1178684756 0.1289830059 0.3461823463 772 30.8400000000 0.6070906520 0.9578219524 1.7159270048 0.0164154791 0.1067760000 1086834804 0 1785311232 -0.1207319126 0.1297892183 0.3469010293 773 30.8800000000 0.6111192703 0.9573734366 1.7159270048 0.0164109697 0.1034610000 1086836058 0 1784664064 -0.1235340461 0.1308353990 0.3474110663 774 30.9200000000 0.6148592830 0.9569309119 1.7159270048 0.0164087880 0.0980870000 1086837312 0 1784262656 -0.1262030452 0.1316318214 0.3482448757 775 30.9600000000 0.6182342768 0.9564938840 1.7159270048 0.0164075400 0.0935510000 1086838566 0 1784262656 -0.1289930195 0.1321482062 0.3488070071 776 31.0000000000 0.6218259931 0.9560626109 1.7159270048 0.0164071656 0.0914530000 1086839820 0 1784754176 -0.1319065839 0.1327695251 0.3493563533 777 31.0400000000 0.6256601810 0.9556373826 1.7159270048 0.0164084133 0.0938910000 1086841074 0 1785257984 -0.1347585469 0.1338413060 0.3497956395 778 31.0800000000 0.6294065118 0.9552180627 1.7159270048 0.0164045736 0.0965660000 1086842328 0 1785638912 -0.1375441104 0.1349508315 0.3502056897 779 31.1200000000 0.6329867840 0.9548044153 1.7159270048 0.0163991700 0.0957790000 1086843582 0 1785638912 -0.1402189732 0.1357114315 0.3507684469 780 31.1600000000 0.6365518570 0.9543963992 1.7159270048 0.0163942941 0.1074310000 1086844836 0 1786146816 -0.1428376883 0.1365972757 0.3513048291 781 31.2000000000 0.6398408413 0.9539936392 1.7159270048 0.0163891937 0.1048030000 1086846090 0 1786781696 -0.1453897357 0.1373419911 0.3517261744 782 31.2400000000 0.6429045796 0.9535958271 1.7159270048 0.0163822923 0.1041090000 1086847344 0 1787289600 -0.1478393525 0.1377817392 0.3521414101 783 31.2800000000 0.6461951137 0.9532032336 1.7159270048 0.0163750188 0.1152420000 1086848598 0 1787797504 -0.1502391845 0.1383414716 0.3526213765 784 31.3200000000 0.6491473317 0.9528154072 1.7159270048 0.0163676922 0.1159420000 1086849852 0 1786077184 -0.1524783671 0.1387518048 0.3531405032 785 31.3600000000 0.6518663168 0.9524320326 1.7159270048 0.0163597490 0.1240460000 1086851106 0 1786171392 -0.1545918286 0.1389560997 0.3535116613 786 31.4000000000 0.6547049284 0.9520532449 1.7159270048 0.0163517343 0.1135770000 1086852360 0 1786654720 -0.1567018926 0.1392275095 0.3539696336 787 31.4400000000 0.6575570107 0.9516790439 1.7159270048 0.0163434374 0.1149520000 1086853614 0 1787289600 -0.1586717367 0.1398847997 0.3543637395 788 31.4800000000 0.6602037549 0.9513091514 1.7159270048 0.0163354772 0.1149080000 1086854868 0 1787416576 -0.1603915393 0.1401913911 0.3549783528 789 31.5200000000 0.6624428630 0.9509430344 1.7159270048 0.0163273725 0.1143020000 1086856122 0 1787797504 -0.1621324271 0.1402044892 0.3553830981 790 31.5600000000 0.6648765802 0.9505809250 1.7159270048 0.0163191887 0.1112920000 1086857376 0 1786077184 -0.1638626009 0.1403163970 0.3558145165 791 31.6000000000 0.6670376658 0.9502224632 1.7159270048 0.0163118481 0.1136450000 1086858630 0 1786171392 -0.1654267907 0.1403704286 0.3563125730 792 31.6400000000 0.6690873504 0.9498674946 1.7159270048 0.0163039400 0.1114300000 1086859884 0 1786679296 -0.1668135226 0.1402521431 0.3567219377 793 31.6800000000 0.6707144380 0.9495154731 1.7159270048 0.0162955100 0.1112490000 1086861138 0 1787314176 -0.1680420786 0.1399816126 0.3572445214 794 31.7200000000 0.6722479463 0.9491662697 1.7159270048 0.0162878385 0.1151060000 1086862392 0 1787416576 -0.1691617966 0.1396016330 0.3576684296 795 31.7600000000 0.6737464070 0.9488198296 1.7159270048 0.0162815939 0.1079380000 1086863646 0 1787670528 -0.1702056527 0.1392705739 0.3580850959 796 31.8000000000 0.6753544211 0.9484762801 1.7159270048 0.0162784004 0.5084280000 1099179884 0 1787543552 -0.1712432206 0.1388922781 0.3586439788 797 31.8400000000 0.6781711578 0.9481371269 1.7159270048 0.0162743845 0.1402660000 1102838986 0 1785929728 -0.1710122675 0.1382388175 0.3580928147 798 31.8800000000 0.6793638468 0.9478003182 1.7159270048 0.0162696171 0.0975750000 1106032336 0 1786298368 -0.1718864143 0.1377593428 0.3585641086 799 31.9200000000 0.6805304289 0.9474658128 1.7159270048 0.0162621707 0.0884270000 1106033590 0 1784922112 -0.1727174371 0.1371344030 0.3590119779 800 31.9600000000 0.6815849543 0.9471334617 1.7159270048 0.0162542811 0.0916250000 1106034844 0 1784524800 -0.1735091805 0.1364434958 0.3595336974 801 32.0000000000 0.6829496622 0.9468036442 1.7159270048 0.0162484138 0.0900090000 1106036098 0 1784524800 -0.1741317511 0.1358463913 0.3601576090 802 32.0400000000 0.6841116548 0.9464760981 1.7159270048 0.0162413231 0.0894320000 1106037352 0 1785016320 -0.1748135537 0.1351256371 0.3607586622 803 32.0800000000 0.6856394410 0.9461512704 1.7159270048 0.0162372494 0.0883850000 1106038606 0 1785524224 -0.1751048714 0.1350329518 0.3616303802 804 32.1199999990 0.6869047284 0.9458288244 1.7159270048 0.0162351324 0.0854190000 1106039860 0 1785905152 -0.1754363477 0.1347717792 0.3623103797 805 32.1600000000 0.6880148649 0.9455085586 1.7159270048 0.0162325707 0.0860570000 1106041114 0 1786019840 -0.1757643670 0.1341762841 0.3630346358 806 32.2000000000 0.6889865398 0.9451902931 1.7159270048 0.0162288882 0.0987680000 1106042368 0 1786527744 -0.1761372834 0.1336618066 0.3636124432 807 32.2400000000 0.6895710826 0.9448735407 1.7159270048 0.0162262305 0.0886960000 1106043622 0 1787035648 -0.1763210595 0.1326028258 0.3642549813 808 32.2800000000 0.6906071305 0.9445588545 1.7159270048 0.0162201683 0.6055130000 1118360364 0 1787416576 -0.1766890138 0.1317908168 0.3650123775 809 32.3200000000 0.6916564107 0.9442462433 1.7159270048 0.0162132115 0.1272960000 1122019466 0 1785315328 -0.1765496135 0.1301211715 0.3654802144 810 32.3600000000 0.6925530434 0.9439355110 1.7159270048 0.0162058793 0.0996970000 1125212816 0 1785675776 -0.1768103391 0.1293582767 0.3661199212 811 32.4000000000 0.6931498647 0.9436262808 1.7159270048 0.0161966356 0.0976700000 1125214070 0 1785028608 -0.1771477610 0.1280115545 0.3668594956 812 32.4399999990 0.6938287020 0.9433186484 1.7159270048 0.0161879707 0.0952560000 1125215324 0 1785028608 -0.1773876399 0.1268346161 0.3675978780 813 32.4800000000 0.6950170398 0.9430132343 1.7159270048 0.0161799230 0.0898690000 1125216578 0 1785524224 -0.1773804575 0.1259797961 0.3685833216 814 32.5200000000 0.6961587667 0.9427099733 1.7159270048 0.0161716278 0.0871650000 1125217832 0 1786159104 -0.1775560230 0.1249704733 0.3695258200 815 32.5600000000 0.6972626448 0.9424088109 1.7159270048 0.0161621237 0.0895050000 1125219086 0 1786400768 -0.1777766347 0.1239942685 0.3704370260 816 32.6000000000 0.6982616186 0.9421096110 1.7159270048 0.0161529283 0.0877550000 1125220340 0 1786527744 -0.1778126508 0.1224898547 0.3715603054 817 32.6400000000 0.6994143128 0.9418125543 1.7159270048 0.0161430957 0.7038280000 1137536498 0 1786806272 -0.1779788435 0.1213336587 0.3725101650 818 32.6800000000 0.7007838488 0.9415178982 1.7159270048 0.0161332770 0.1300900000 1141195600 0 1784786944 -0.1781415045 0.1202138662 0.3738219738 819 32.7200000000 0.7027537823 0.9412263669 1.7159270048 0.0161239726 0.0949190000 1144388950 0 1785315328 -0.1781448722 0.1195314601 0.3753064573 820 32.7599999990 0.7048112750 0.9409380558 1.7159270048 0.0161148165 0.0891040000 1144390204 0 1784668160 -0.1783706844 0.1187549755 0.3766663373 821 32.7999999990 0.7072928548 0.9406534697 1.7159270048 0.0161095535 0.0869490000 1144391458 0 1784668160 -0.1780496687 0.1179983020 0.3785902560 822 32.8400000000 0.7096251249 0.9403724133 1.7159270048 0.0161120509 0.0837070000 1144392712 0 1785163776 -0.1780738831 0.1171274632 0.3801715970 823 32.8800000000 0.7121062875 0.9400950547 1.7159270048 0.0161059380 0.0838700000 1144393966 0 1785798656 -0.1783735305 0.1164750680 0.3818455637 824 32.9200000000 0.7152876854 0.9398222302 1.7159270048 0.0160980113 0.0861280000 1144395220 0 1786052608 -0.1784177870 0.1161066443 0.3838109970 825 32.9600000000 0.7182410359 0.9395536470 1.7159270048 0.0160954447 0.0847810000 1144396474 0 1786146816 -0.1784690917 0.1153178737 0.3858163953 826 33.0000000000 0.7214699388 0.9392896231 1.7159270048 0.0160904636 0.0824030000 1144397728 0 1786654720 -0.1786728501 0.1148522273 0.3878938258 827 33.0400000000 0.7243363857 0.9390297038 1.7159270048 0.0160907658 0.0953370000 1144398982 0 1787289600 -0.1787717938 0.1137405783 0.3898677230 828 33.0800000000 0.7268452048 0.9387734424 1.7159270048 0.0160926164 0.0935550000 1144400236 0 1787797504 -0.1788575649 0.1124476194 0.3917165399 829 33.1199999990 0.7299452424 0.9385215386 1.7159270048 0.0160893064 0.7984740000 1156718878 0 1787543552 -0.1790951341 0.1113167778 0.3937736452 830 33.1600000000 0.7329728603 0.9382738896 1.7159270048 0.0160847827 0.1243980000 1160377980 0 1785950208 -0.1792384386 0.1104329228 0.3954538703 831 33.2000000000 0.7358240485 0.9380302677 1.7159270048 0.0160809860 0.0982320000 1163571330 0 1786052608 -0.1792633235 0.1087544188 0.3976885080 832 33.2400000000 0.7389404178 0.9377909770 1.7159270048 0.0160744912 0.0956470000 1163572584 0 1785131008 -0.1794349700 0.1073673517 0.3998525739 833 33.2800000000 0.7425254583 0.9375565646 1.7159270048 0.0160665597 0.0940800000 1163573838 0 1785131008 -0.1796649545 0.1061606035 0.4021454751 834 33.3200000000 0.7456393838 0.9373264481 1.7159270048 0.0160608016 0.0875120000 1163575092 0 1785765888 -0.1799370944 0.1044612005 0.4042465389 835 33.3600000000 0.7491293550 0.9371010623 1.7159270048 0.0160540430 0.0873560000 1163576346 0 1786273792 -0.1802843511 0.1035453826 0.4063195586 836 33.4000000000 0.7525553703 0.9368803139 1.7159270048 0.0160481375 0.0865330000 1163577600 0 1786527744 -0.1805546135 0.1023230329 0.4085306525 837 33.4399999990 0.7561357021 0.9366643705 1.7159270048 0.0160437439 0.0858930000 1163578854 0 1786654720 -0.1809245646 0.1014157459 0.4106418192 838 33.4800000000 0.7589188814 0.9364522637 1.7159270048 0.0160454315 0.0868770000 1163580108 0 1787162624 -0.1810584515 0.0997980982 0.4126246274 839 33.5200000000 0.7623745203 0.9362447813 1.7159270048 0.0160443713 0.0992520000 1163581362 0 1787797504 -0.1811649501 0.0989934206 0.4147521555 840 33.5600000000 0.7652332783 0.9360411962 1.7159270048 0.0160396054 0.0971780000 1163582616 0 1786077184 -0.1818942279 0.0980667174 0.4163618386 841 33.6000000000 0.7683884501 0.9358418469 1.7159270048 0.0160308949 0.7585320000 1175900682 0 1785929728 -0.1826624572 0.0974389836 0.4180326164 842 33.6400000000 0.7714162469 0.9356465671 1.7159270048 0.0160218510 0.1210890000 1179559784 0 1785434112 -0.1832703203 0.0968265161 0.4195899069 843 33.6800000000 0.7742594481 0.9354551233 1.7159270048 0.0160133864 0.0967600000 1182753134 0 1785950208 -0.1835746467 0.0956577137 0.4213307202 844 33.7200000000 0.7765957117 0.9352669012 1.7159270048 0.0160069678 0.0926540000 1182754388 0 1785417728 -0.1837987304 0.0939959586 0.4229368567 845 33.7599999990 0.7791212797 0.9350821135 1.7159270048 0.0160011065 0.0938510000 1182755642 0 1785417728 -0.1838221252 0.0928960219 0.4247037470 846 33.7999999990 0.7818165421 0.9349009485 1.7159270048 0.0159932041 0.0899040000 1182756896 0 1784766464 -0.1842114329 0.0921589956 0.4261384904 847 33.8400000000 0.7834730744 0.9347221671 1.7159270048 0.0159845107 0.0870440000 1182758150 0 1784283136 -0.1844853759 0.0905027688 0.4274061620 848 33.8800000000 0.7856940627 0.9345464264 1.7159270048 0.0159753765 0.0828800000 1182759404 0 1784283136 -0.1847849935 0.0893956199 0.4286516309 849 33.9200000000 0.7872788906 0.9343729664 1.7159270048 0.0159663342 0.0816520000 1182760658 0 1784758272 -0.1850588471 0.0875218809 0.4298586845 850 33.9600000000 0.7891346216 0.9342020978 1.7159270048 0.0159579533 0.0838590000 1182761912 0 1785266176 -0.1853230894 0.0863396078 0.4310799539 851 34.0000000000 0.7913674116 0.9340342544 1.7159270048 0.0159489676 0.0988670000 1182763166 0 1785647104 -0.1856008172 0.0853232965 0.4323692918 852 34.0400000000 0.7929620743 0.9338686768 1.7159270048 0.0159397154 0.0945150000 1182764420 0 1785647104 -0.1855766177 0.0835496038 0.4335581958 853 34.0800000000 0.7945328951 0.9337053288 1.7159270048 0.0159305280 0.0934030000 1182765674 0 1786146816 -0.1858488321 0.0822665468 0.4345350564 854 34.1199999990 0.7962917089 0.9335444230 1.7159270048 0.0159215086 0.1061540000 1182766928 0 1786781696 -0.1859285831 0.0814263970 0.4357845485 855 34.1600000000 0.7979667783 0.9333858526 1.7159270048 0.0159136133 0.1123650000 1182768182 0 1787289600 -0.1858884841 0.0802975520 0.4367893934 856 34.2000000000 0.7993689179 0.9332292908 1.7159270048 0.0159054744 0.1139350000 1182769436 0 1787797504 -0.1860070676 0.0793700293 0.4378213584 857 34.2400000000 0.8012611866 0.9330753023 1.7159270048 0.0158964415 0.1042910000 1182770690 0 1786077184 -0.1863509119 0.0790022835 0.4387323558 858 34.2800000000 0.8027222157 0.9329233757 1.7159270048 0.0158876006 0.1052430000 1182771944 0 1786171392 -0.1867714822 0.0782748237 0.4395231009 859 34.3200000000 0.8032207489 0.9327723831 1.7159270048 0.0158792385 0.0981300000 1182773198 0 1786679296 -0.1866304129 0.0762674585 0.4401029944 860 34.3600000000 0.8037292361 0.9326223329 1.7159270048 0.0158701648 0.8383380000 1195307728 0 1786908672 -0.1867906898 0.0746250749 0.4406776428 861 34.4000000000 0.8048028946 0.9324738783 1.7159270048 0.0158610336 0.1298180000 1198966830 0 1784934400 -0.1867804229 0.0734628364 0.4417108595 862 34.4400000000 0.8055612445 0.9323266478 1.7159270048 0.0158519616 0.1021720000 1202160180 0 1785442304 -0.1870656759 0.0721657723 0.4422440529 863 34.4800000000 0.8057345152 0.9321799594 1.7159270048 0.0158430838 0.0960700000 1202161434 0 1784647680 -0.1869092882 0.0701139122 0.4426618516 864 34.5200000000 0.8063595891 0.9320343340 1.7159270048 0.0158339283 0.0947470000 1202162688 0 1784647680 -0.1867649406 0.0689630285 0.4433631003 865 34.5600000000 0.8076243401 0.9318905074 1.7159270048 0.0158254213 0.0889640000 1202163942 0 1785143296 -0.1870485991 0.0686069280 0.4438380301 866 34.6000000000 0.8084965348 0.9317480201 1.7159270048 0.0158190525 0.0858510000 1202165196 0 1785778176 -0.1875806302 0.0681063309 0.4441581964 867 34.6400000000 0.8091766238 0.9316066459 1.7159270048 0.0158104132 0.0848950000 1202166450 0 1786032128 -0.1874708533 0.0672442093 0.4446951151 868 34.6800000000 0.8094756007 0.9314659420 1.7159270048 0.0158016033 0.0872700000 1202167704 0 1786273792 -0.1876447499 0.0659571737 0.4449553192 869 34.7200000000 0.8096625209 0.9313257769 1.7159270048 0.0157926470 0.0862390000 1202168958 0 1786781696 -0.1874167174 0.0649255142 0.4452819526 870 34.7600000000 0.8099873066 0.9311863074 1.7159270048 0.0157836884 0.1011700000 1202170212 0 1787289600 -0.1878079176 0.0639872923 0.4454482496 871 34.8000000000 0.8105480671 0.9310478020 1.7159270048 0.0157747813 0.0895590000 1202171466 0 1787924480 -0.1880651414 0.0634079352 0.4457241595 872 34.8400000000 0.8110383153 0.9309101764 1.7159270048 0.0157657849 0.0865070000 1202172720 0 1786077184 -0.1884237081 0.0623704717 0.4458942115 873 34.8800000000 0.8118041754 0.9307737434 1.7159270048 0.0157567749 0.1024480000 1202173974 0 1785561088 -0.1885522455 0.0616894737 0.4463829696 874 34.9200000000 0.8126146793 0.9306385500 1.7159270048 0.0157478001 0.0924490000 1202175228 0 1785561088 -0.1888004541 0.0612684600 0.4467467368 875 34.9600000000 0.8139682412 0.9305052125 1.7159270048 0.0157389323 0.0887420000 1202176482 0 1786036224 -0.1892223209 0.0613787286 0.4472589195 876 35.0000000000 0.8148874044 0.9303732287 1.7159270048 0.0157302889 0.0930740000 1202177736 0 1786544128 -0.1894739419 0.0609885342 0.4477447569 877 35.0400000000 0.8159792423 0.9302427909 1.7159270048 0.0157213534 0.0944380000 1202178990 0 1786925056 -0.1897596568 0.0609802343 0.4481807351 878 35.0800000000 0.8169918060 0.9301138034 1.7159270048 0.0157125706 0.0902180000 1202180244 0 1786908672 -0.1900997460 0.0610181764 0.4485568106 879 35.1200000000 0.8178012371 0.9299860303 1.7159270048 0.0157036840 0.0928730000 1202181498 0 1787543552 -0.1903567761 0.0606522821 0.4489568770 880 35.1600000000 0.8188393712 0.9298597273 1.7159270048 0.0156951421 0.0939810000 1202182752 0 1788051456 -0.1905629188 0.0609505996 0.4494279325 881 35.2000000000 0.8199049830 0.9297349205 1.7159270048 0.0156865133 0.0918580000 1202184006 0 1785671680 -0.1909267008 0.0609073304 0.4498409331 882 35.2400000000 0.8198557496 0.9296103410 1.7159270048 0.0156777783 0.0950450000 1202185260 0 1785024512 -0.1907758564 0.0595459044 0.4500186145 ================================================ FILE: icra2018_results/tegra/memory_orbslam2_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 05:34:29 Properties: ================= frame-limit: 0 log-file: output//memory_orbslam2_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1649010000 225834516 0 1384038400 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0016766530 0.0008383265 0.0016766530 0.0014063064 0.1845110000 229184282 0 1493618688 0.0009001556 0.0000838387 -0.0003908983 3 0.0800000000 0.0015822555 0.0010863028 0.0016766530 0.0011931997 0.1798370000 229113697 0 1495388160 -0.0042050271 0.0008191089 -0.0003776929 4 0.1200000000 0.0026836172 0.0014856314 0.0026836172 0.0013483090 0.1846090000 229116406 0 1497165824 -0.0006538451 0.0009003719 -0.0009791600 5 0.1600000000 0.0037289024 0.0019342856 0.0037289024 0.0014272208 0.1841360000 229118172 0 1498927104 -0.0039363396 -0.0008332552 0.0007687336 6 0.2000000000 0.0014823029 0.0018589552 0.0037289024 0.0016825643 0.1816980000 229122918 0 1500594176 -0.0040361751 0.0016616849 -0.0002794753 7 0.2400000000 0.0013730575 0.0017895412 0.0037289024 0.0015480394 0.1850950000 229125328 0 1502482432 -0.0044940715 0.0020401087 -0.0001060311 8 0.2800000000 0.0022861408 0.0018516162 0.0037289024 0.0014893680 0.1804420000 229126806 0 1504149504 -0.0048252293 0.0018688004 0.0000165534 9 0.3200000000 0.0012211959 0.0017815695 0.0037289024 0.0017255683 0.1810450000 229128548 0 1505689600 -0.0081305970 0.0012921972 -0.0007769379 10 0.3600000000 0.0033468958 0.0019381021 0.0037289024 0.0017277050 0.1806620000 229131178 0 1507450880 -0.0061322437 0.0032521156 -0.0002586971 11 0.4000000000 0.0013857047 0.0018878842 0.0037289024 0.0020047483 0.1792020000 229133348 0 1509355520 -0.0092456676 0.0000619719 0.0013931724 12 0.4400000000 0.0007803517 0.0017955898 0.0037289024 0.0022762747 0.1793340000 229134626 0 1511006208 -0.0101746200 0.0001026162 0.0000843234 13 0.4800000000 0.0019019429 0.0018037708 0.0037289024 0.0023894798 0.1827040000 229135936 0 1512656896 -0.0112792291 -0.0005289036 0.0002776457 14 0.5200000000 0.0032929734 0.0019101424 0.0037289024 0.0023172562 0.1791090000 229138562 0 1514434560 -0.0096168006 0.0010777062 -0.0010335768 15 0.5600000000 0.0005310392 0.0018182022 0.0037289024 0.0023163651 0.1847430000 229140316 0 1515958272 -0.0156432744 0.0023403219 0.0010729401 16 0.6000000000 0.0018011628 0.0018171372 0.0037289024 0.0022656392 0.1859400000 229141790 0 1517989888 -0.0131097101 0.0015623422 -0.0002303320 17 0.6400000000 0.0033243373 0.0019057961 0.0037289024 0.0022725242 0.1816760000 229143720 0 1519767552 -0.0150077194 -0.0029044121 -0.0021780066 18 0.6800000000 0.0016184495 0.0018898324 0.0037289024 0.0022444759 0.1800030000 229146958 0 1521418240 -0.0173387267 -0.0008523273 -0.0014156324 19 0.7200000000 0.0052241446 0.0020653225 0.0052241446 0.0022405042 0.1799110000 229149040 0 1523195904 -0.0180345979 -0.0046625151 -0.0016840203 20 0.7600000000 0.0020186957 0.0020629911 0.0052241446 0.0024741347 0.1802910000 229151662 0 1524846592 -0.0225169249 -0.0030229178 -0.0017073650 21 0.8000000000 0.0056635872 0.0022344481 0.0056635872 0.0024492279 0.1828970000 229154804 0 1526497280 -0.0207352489 -0.0022511757 -0.0017252034 22 0.8400000000 0.0043489048 0.0023305598 0.0056635872 0.0024055590 0.1876050000 229158702 0 1528147968 -0.0283416156 -0.0036515759 -0.0024477497 23 0.8800000000 0.0063814018 0.0025066833 0.0063814018 0.0023690540 0.1827700000 229159868 0 1529925632 -0.0251742546 -0.0040369122 -0.0044080056 24 0.9200000000 0.0066323825 0.0026785875 0.0066323825 0.0023217501 0.1831260000 229163426 0 1531703296 -0.0336795151 -0.0033473764 -0.0052825743 25 0.9600000000 0.0051811608 0.0027786904 0.0066323825 0.0023165763 0.1812020000 229165440 0 1532956672 -0.0358606093 -0.0008799685 -0.0058860769 26 1.0000000000 0.0063309334 0.0029153151 0.0066323825 0.0022781846 0.1795870000 229166122 0 1534623744 -0.0410805903 -0.0023115252 -0.0057443343 27 1.0400000000 0.0067953994 0.0030590220 0.0067953994 0.0023444371 0.2117500000 229168708 0 1536528384 -0.0458428785 -0.0006663237 -0.0070305476 28 1.0800000000 0.0048068389 0.0031214440 0.0067953994 0.0025283498 0.1825720000 229171846 0 1538306048 -0.0541934632 -0.0030674089 -0.0075136004 29 1.1200000000 0.0033261059 0.0031285013 0.0067953994 0.0025858752 0.1756440000 229174352 0 1539956736 -0.0610117577 -0.0006792184 -0.0109085348 30 1.1600000000 0.0046261251 0.0031784221 0.0067953994 0.0026634001 0.1773440000 229177118 0 1541844992 -0.0683882162 -0.0006616915 -0.0074605383 31 1.2000000000 0.0050290483 0.0032381197 0.0067953994 0.0026553755 0.1747110000 229179880 0 1543512064 -0.0748161525 -0.0007810020 -0.0103626652 32 1.2400000000 0.0068565798 0.0033511966 0.0068565798 0.0027084472 0.1793080000 229182322 0 1545289728 -0.0798933208 -0.0012083669 -0.0127854012 33 1.2800000000 0.0057009100 0.0034224000 0.0068565798 0.0027662628 0.1749360000 229185388 0 1546940416 -0.0876954719 -0.0035113886 -0.0119123030 34 1.3200000000 0.0034538929 0.0034233263 0.0068565798 0.0027890067 0.1766200000 229192078 0 1548337152 -0.1183921620 -0.0032141623 -0.0119903367 35 1.3600000000 0.0056980588 0.0034883186 0.0068565798 0.0031635414 0.1789820000 229194204 0 1550368768 -0.1183097363 -0.0017775005 -0.0151358098 36 1.4000000000 0.0088938195 0.0036384714 0.0088938195 0.0037489683 0.1745170000 229195374 0 1552146432 -0.1216447428 -0.0028935450 -0.0181959216 37 1.4400000000 0.0045675943 0.0036635829 0.0088938195 0.0037572263 0.1757950000 229198052 0 1553797120 -0.1355436444 -0.0015258109 -0.0153625142 38 1.4800000000 0.0041587916 0.0036766147 0.0088938195 0.0037201264 0.1744700000 229200822 0 1555439616 -0.1481634676 -0.0022919264 -0.0157904625 39 1.5200000000 0.0049450784 0.0037091394 0.0088938195 0.0037001864 0.1718670000 229202700 0 1556819968 -0.1501085460 -0.0012139083 -0.0177894719 40 1.5600000000 0.0048445426 0.0037375245 0.0088938195 0.0037147227 0.1731630000 229204510 0 1558614016 -0.1613652259 -0.0062149391 -0.0185802728 41 1.6000000000 0.0015475304 0.0036841100 0.0088938195 0.0037918775 0.1771280000 229206616 0 1560264704 -0.1740685105 -0.0053947205 -0.0153774805 42 1.6400000000 0.0011346677 0.0036234090 0.0088938195 0.0037543551 0.1727310000 229209766 0 1562169344 -0.1876110286 -0.0030452381 -0.0127223264 43 1.6800000000 0.0045969100 0.0036460485 0.0088938195 0.0037376367 0.1759800000 229210740 0 1563820032 -0.1915526986 -0.0003703534 -0.0100951008 44 1.7200000000 0.0044943467 0.0036653280 0.0088938195 0.0037505172 0.1700270000 229213850 0 1565597696 -0.1975927204 -0.0018653485 -0.0111511257 45 1.7600000000 0.0011303026 0.0036089941 0.0088938195 0.0038188480 0.1715680000 229215660 0 1567375360 -0.2102111429 -0.0003599498 -0.0074327737 46 1.8000000000 0.0032580430 0.0036013648 0.0088938195 0.0038488460 0.1752270000 229218310 0 1568899072 -0.2172471881 0.0023041330 -0.0078194011 47 1.8400000000 0.0006847174 0.0035393084 0.0088938195 0.0039213161 0.1770350000 229219776 0 1570676736 -0.2195922732 -0.0027481634 -0.0088229124 48 1.8800000000 0.0044181962 0.0035576186 0.0088938195 0.0039480606 0.1741620000 229221046 0 1572454400 -0.2206574529 0.0001881612 -0.0080246665 49 1.9200000000 0.0022387670 0.0035307033 0.0088938195 0.0039139479 0.1755280000 229222964 0 1574232064 -0.2287884653 -0.0014738643 -0.0065897517 50 1.9600000000 0.0012831560 0.0034857523 0.0088938195 0.0038979948 0.1754670000 229224910 0 1575882752 -0.2443975657 -0.0028968942 -0.0010861009 51 2.0000000000 0.0041767932 0.0034993021 0.0088938195 0.0038930091 0.1769490000 229225960 0 1577406464 -0.2400517464 -0.0003270412 -0.0036026128 52 2.0400000000 0.0017664135 0.0034659773 0.0088938195 0.0038996651 0.1740760000 229228490 0 1578934272 -0.2492188662 -0.0024687813 -0.0047636032 53 2.0800000000 0.0031699098 0.0034603912 0.0088938195 0.0039505180 0.1778070000 229229404 0 1580707840 -0.2523901165 -0.0050541256 -0.0072477367 54 2.1200000000 0.0024803667 0.0034422426 0.0088938195 0.0040018161 0.2261400000 229231454 0 1582485504 -0.2647712529 -0.0065527344 -0.0016103331 55 2.1600000000 0.0030411889 0.0034349507 0.0088938195 0.0041040652 0.1721180000 229232736 0 1584263168 -0.2658979893 -0.0038243381 -0.0004020352 56 2.2000000000 0.0045522088 0.0034549017 0.0088938195 0.0041464000 0.1816140000 229235290 0 1585913856 -0.2883626223 -0.0024593743 0.0081578270 57 2.2400000000 0.0026095321 0.0034400707 0.0088938195 0.0041138783 0.1755810000 229235720 0 1587564544 -0.2901391983 -0.0054178545 0.0084567554 58 2.2800000000 0.0029196895 0.0034310986 0.0088938195 0.0041144088 0.1742530000 229236566 0 1589596160 -0.3012156188 -0.0069398703 0.0112625062 59 2.3200000000 0.0033843997 0.0034303071 0.0088938195 0.0042594122 0.1719020000 229238160 0 1591246848 -0.3152701855 -0.0069219042 0.0176272746 60 2.3600000000 0.0008594013 0.0033874587 0.0088938195 0.0043875294 0.1729740000 229239410 0 1593016320 -0.3156524301 -0.0070960699 0.0130231176 61 2.4000000000 0.0023033295 0.0033696860 0.0088938195 0.0044850982 0.1795490000 229242240 0 1594540032 -0.3228428960 -0.0069213291 0.0141989235 62 2.4400000000 0.0073623448 0.0034340838 0.0088938195 0.0046998480 0.1738270000 229244854 0 1596190720 -0.3423635364 -0.0031005619 0.0257160235 63 2.4800000000 0.0032611955 0.0034313395 0.0088938195 0.0048453759 0.1703130000 229247564 0 1598332928 -0.3561876416 -0.0093858857 0.0276532751 64 2.5200000000 0.0041931993 0.0034432436 0.0088938195 0.0051687345 0.1700530000 229250450 0 1599492096 -0.3676087558 -0.0051131193 0.0317434296 65 2.5600000000 0.0094868010 0.0035362214 0.0094868010 0.0053206552 0.1714240000 229251468 0 1601269760 -0.3878572285 -0.0017076270 0.0362108648 66 2.6000000000 0.0041976441 0.0035462429 0.0094868010 0.0055264673 0.1715730000 229264418 0 1603301376 -0.3963428438 -0.0078555616 0.0366703421 67 2.6400000000 0.0023540119 0.0035284484 0.0094868010 0.0055620894 0.1709030000 229266680 0 1605079040 -0.4045023024 -0.0040996019 0.0386855975 68 2.6800000000 0.0038275102 0.0035328464 0.0094868010 0.0055504287 0.1948350000 229625767 0 1606856704 -0.4157654643 -0.0028776866 0.0391126573 69 2.7200000000 0.0026838144 0.0035205416 0.0094868010 0.0055126328 0.2432840000 229911265 0 1608761344 -0.4250116646 -0.0039589899 0.0429663248 70 2.7600000000 0.0025700135 0.0035069626 0.0094868010 0.0054777160 0.3620150000 230644025 0 1612595200 -0.4318718016 -0.0024516322 0.0427028909 71 2.8000000000 0.0153044723 0.0036731247 0.0153044723 0.0059041557 0.2700780000 230515848 0 1613713408 -0.4474263489 -0.0141002247 0.0313759185 72 2.8400000000 0.0135346241 0.0038100900 0.0153044723 0.0064721690 0.1727020000 229902750 0 1615384576 -0.4596996009 -0.0088469470 0.0347886458 73 2.8800000000 0.0158154164 0.0039745465 0.0158154164 0.0065557964 0.1716540000 229904756 0 1617051648 -0.4721252620 -0.0082672276 0.0345850438 74 2.9200000000 0.0138919875 0.0041085660 0.0158154164 0.0066600647 0.1706560000 229905890 0 1618702336 -0.4744835198 -0.0048146737 0.0328087807 75 2.9600000000 0.0163013991 0.0042711371 0.0163013991 0.0066947915 0.1679650000 229910164 0 1620480000 -0.4764543772 -0.0032335501 0.0288363993 76 3.0000000000 0.0164734423 0.0044316937 0.0164734423 0.0066977382 0.1686510000 229912146 0 1622257664 -0.4717162549 -0.0002826203 0.0187604427 77 3.0400000000 0.0168796945 0.0045933561 0.0168796945 0.0067245328 0.1662470000 229915584 0 1623891968 -0.4741003811 -0.0008402998 0.0138250515 78 3.0800000000 0.0166008696 0.0047472986 0.0168796945 0.0066864567 0.1639530000 229917642 0 1625559040 -0.4729729891 0.0007109954 0.0073126629 79 3.1200000000 0.0144158956 0.0048696859 0.0168796945 0.0066477546 0.1639600000 229920728 0 1627320320 -0.4812472761 0.0069428808 0.0060961172 80 3.1600000000 0.0166165624 0.0050165218 0.0168796945 0.0066322026 0.1804340000 229923274 0 1628606464 -0.4826141596 0.0065031676 0.0009988174 81 3.2000000000 0.0172294397 0.0051672986 0.0172294397 0.0066065105 0.1662610000 229927308 0 1630638080 -0.4931420386 0.0050761285 0.0024930537 82 3.2400000000 0.0154669695 0.0052929043 0.0172294397 0.0065941026 0.1635730000 229930214 0 1632415744 -0.5055899620 0.0079050381 0.0048041046 83 3.2800000000 0.0165395942 0.0054284066 0.0172294397 0.0066424786 0.1648070000 229932472 0 1634066432 -0.5107808709 0.0082675181 -0.0005279332 84 3.3200000000 0.0167680047 0.0055634018 0.0172294397 0.0066210186 0.1808790000 230275219 0 1636114432 -0.5261814594 0.0072919312 0.0020748377 85 3.3600000000 0.0161990486 0.0056885271 0.0172294397 0.0066143113 0.3673430000 230429871 0 1636605952 -0.5376015306 0.0083903121 0.0009442121 86 3.4000000000 0.0182823204 0.0058349666 0.0182823204 0.0066500701 0.2185800000 231115285 0 1640693760 -0.5554677248 0.0080197658 0.0056042224 87 3.4400000000 0.0138506228 0.0059271005 0.0182823204 0.0068026534 0.2360490000 230866798 0 1641750528 -0.5613848567 0.0096456595 0.0063581467 88 3.4800000000 0.0147245117 0.0060270711 0.0182823204 0.0069494187 0.1635080000 230286962 0 1642745856 -0.5740509629 0.0094418461 0.0052885413 89 3.5200000000 0.0146623161 0.0061240963 0.0182823204 0.0070588655 0.1679110000 230289744 0 1644269568 -0.5863752961 0.0104301050 0.0079159737 90 3.5600000000 0.0151697211 0.0062246033 0.0182823204 0.0071316644 0.1662950000 230290438 0 1645793280 -0.5932260752 0.0085248789 0.0044018626 91 3.6000000000 0.0123684062 0.0062921176 0.0182823204 0.0072073589 0.1657410000 230294540 0 1647554560 -0.6048105955 0.0088025685 0.0079979748 92 3.6400000000 0.0147743439 0.0063843157 0.0182823204 0.0072329804 0.1630510000 230295846 0 1649459200 -0.6148303151 0.0087635433 0.0101623833 93 3.6800000000 0.0133359917 0.0064590649 0.0182823204 0.0072009126 0.1645490000 230296884 0 1651126272 -0.6251058578 0.0101611177 0.0079243481 94 3.7200000000 0.0137320217 0.0065364368 0.0182823204 0.0071690580 0.1671390000 230300030 0 1652776960 -0.6311981678 0.0067978785 0.0073814988 95 3.7600000000 0.0145125976 0.0066203964 0.0182823204 0.0071508087 0.1643150000 230302116 0 1654538240 -0.6466879845 0.0075924606 0.0150310993 96 3.8000000000 0.0143047385 0.0067004416 0.0182823204 0.0071219478 0.1776900000 230622678 0 1656205312 -0.6558203697 0.0070672738 0.0140624791 97 3.8400000000 0.0132926796 0.0067684028 0.0182823204 0.0070921043 0.3716490000 230684560 0 1657896960 -0.6576071978 0.0044821869 0.0157272816 98 3.8800000000 0.0138822347 0.0068409930 0.0182823204 0.0070617240 0.2864260000 231657193 0 1662439424 -0.6771068573 0.0042104055 0.0212195516 99 3.9200000000 0.0149869341 0.0069232752 0.0182823204 0.0070290331 0.2532690000 231585820 0 1661698048 -0.6868873835 0.0066223238 0.0268599391 100 3.9600000000 0.0161623973 0.0070156664 0.0182823204 0.0069936837 0.1846660000 230657682 0 1662631936 -0.6978968978 0.0076158866 0.0318264365 101 4.0000000000 0.0179548319 0.0071239750 0.0182823204 0.0069660151 0.1703140000 230658896 0 1664028672 -0.7074238658 0.0041430211 0.0371915549 102 4.0400000000 0.0149362898 0.0072005663 0.0182823204 0.0069440239 0.1682930000 230660378 0 1666060288 -0.7087871432 0.0047360174 0.0392267853 103 4.0800000000 0.0139941741 0.0072665237 0.0182823204 0.0069106126 0.1804670000 230664276 0 1667821568 -0.7184434533 0.0050229365 0.0445382744 104 4.1200000000 0.0170318522 0.0073604210 0.0182823204 0.0068912619 0.2082780000 230665638 0 1669361664 -0.7313804626 -0.0008432353 0.0558681339 105 4.1600000000 0.0156929083 0.0074397781 0.0182823204 0.0068912105 0.1592600000 230666932 0 1671139328 -0.7337950468 -0.0003013825 0.0596952885 106 4.2000000000 0.0184806120 0.0075439369 0.0184806120 0.0068780392 0.1683700000 230671562 0 1672790016 -0.7450889945 0.0017579906 0.0685303360 107 4.2400000000 0.0203161910 0.0076633037 0.0203161910 0.0069086302 0.1614720000 230671692 0 1674551296 -0.7405720353 -0.0082402229 0.0582598597 108 4.2800000000 0.0190172158 0.0077684326 0.0203161910 0.0068779552 0.1670070000 230674478 0 1676218368 -0.7503468990 -0.0073202914 0.0664624423 109 4.3200000000 0.0179517828 0.0078618578 0.0203161910 0.0068571952 0.1894700000 231004145 0 1677996032 -0.7532903552 -0.0052755009 0.0688859224 110 4.3600000000 0.0171816777 0.0079465834 0.0203161910 0.0068496968 0.4008160000 231030314 0 1679773696 -0.7619408965 -0.0042238981 0.0785889030 111 4.4000000000 0.0167813655 0.0080261761 0.0203161910 0.0068472510 0.3461460000 232307463 0 1685614592 -0.7689713836 -0.0041568093 0.0861169398 112 4.4400000000 0.0144555094 0.0080835808 0.0203161910 0.0068456655 0.2057480000 232252305 0 1687277568 -0.7747436762 -0.0020261556 0.0929177254 113 4.4800000000 0.0127494792 0.0081248720 0.0203161910 0.0068569278 0.2182080000 232181112 0 1688461312 -0.7790321708 0.0005799392 0.1011035591 114 4.5200000000 0.0125993863 0.0081641221 0.0203161910 0.0068828298 0.1780720000 231037714 0 1689513984 -0.7898283601 0.0014003981 0.1150813401 115 4.5600000000 0.0109154247 0.0081880464 0.0203161910 0.0069342348 0.1761370000 231040508 0 1691164672 -0.7881954312 -0.0000385549 0.1133155525 116 4.6000000000 0.0132697541 0.0082318543 0.0203161910 0.0069677049 0.1665600000 231041526 0 1692188672 -0.8003865480 0.0013883226 0.1241805404 117 4.6400000000 0.0126785934 0.0082698606 0.0203161910 0.0069676629 0.1727130000 231042988 0 1694085120 -0.8084028959 0.0058561023 0.1359757781 118 4.6800000000 0.0121245831 0.0083025277 0.0203161910 0.0069516393 0.1672110000 231046806 0 1695735808 -0.8142992258 0.0085125584 0.1433258206 119 4.7200000000 0.0113889808 0.0083284643 0.0203161910 0.0069257650 0.1856840000 231385105 0 1697513472 -0.8194075227 0.0048914403 0.1479855627 120 4.7600000000 0.0118934996 0.0083581729 0.0203161910 0.0068997220 0.3928330000 231399350 0 1698037760 -0.8267896175 0.0062966496 0.1564760506 121 4.8000000000 0.0141295213 0.0084058700 0.0203161910 0.0068854246 0.3503460000 231883987 0 1701462016 -0.8379785419 0.0043713357 0.1761887819 122 4.8400000000 0.0129071912 0.0084427661 0.0203161910 0.0068645944 0.2854140000 232803234 0 1705017344 -0.8387570381 0.0077231042 0.1776588708 123 4.8800000000 0.0141413398 0.0084890960 0.0203161910 0.0068383074 0.2907830000 232703636 0 1703612416 -0.8456108570 0.0120240953 0.1846741140 124 4.9200000000 0.0116936741 0.0085149393 0.0203161910 0.0068229805 0.1762400000 231404906 0 1704202240 -0.8523043394 0.0192957688 0.1992293298 125 4.9600000000 0.0109837875 0.0085346901 0.0203161910 0.0068380274 0.1779980000 231407068 0 1705979904 -0.8559923172 0.0116461180 0.2029545009 126 5.0000000000 0.0097241430 0.0085441302 0.0203161910 0.0068257136 0.1702530000 231410310 0 1708011520 -0.8592715859 0.0139408633 0.2070677131 127 5.0400000000 0.0111455647 0.0085646140 0.0203161910 0.0068121856 0.1739500000 231412188 0 1709789184 -0.8710520864 0.0174207464 0.2287270874 128 5.0800000000 0.0137121677 0.0086048292 0.0203161910 0.0067923529 0.1696340000 231415186 0 1711312896 -0.8790328503 0.0167864487 0.2350903153 129 5.1200000000 0.0136633907 0.0086440429 0.0203161910 0.0067757015 0.1687060000 231415056 0 1713090560 -0.8821942806 0.0205509737 0.2438584566 130 5.1600000000 0.0111348750 0.0086632031 0.0203161910 0.0067718645 0.1905410000 231788563 0 1714741248 -0.8888237476 0.0203420706 0.2597777843 131 5.2000000000 0.0097502759 0.0086715014 0.0203161910 0.0068063863 0.4038590000 231814137 0 1716645888 -0.8915373683 0.0180767979 0.2628960013 132 5.2400000000 0.0118821459 0.0086958245 0.0203161910 0.0068057796 0.3376850000 231894526 0 1718550528 -0.8938233852 0.0198363177 0.2612841427 133 5.2800000000 0.0090744374 0.0086986712 0.0203161910 0.0068118831 0.2755490000 233475411 0 1724760064 -0.9015026689 0.0172636118 0.2794452906 134 5.3200000000 0.0075658243 0.0086902171 0.0203161910 0.0068532982 0.2257630000 233401473 0 1726550016 -0.9084826708 0.0195875987 0.2929534912 135 5.3600000000 0.0037430534 0.0086535714 0.0203161910 0.0068802266 0.2716360000 233328576 0 1723756544 -0.9079650044 0.0224774275 0.2990245819 136 5.4000000000 0.0042538811 0.0086212208 0.0203161910 0.0069153269 0.1786210000 231822902 0 1725480960 -0.9153717756 0.0214705970 0.3094640970 137 5.4400000000 0.0047893533 0.0085932509 0.0203161910 0.0069551713 0.1749840000 231825172 0 1727258624 -0.9213728905 0.0225608759 0.3197729886 138 5.4800000000 0.0056380462 0.0085718364 0.0203161910 0.0069833347 0.1763260000 231826318 0 1728925696 -0.9273906350 0.0231636390 0.3254586458 139 5.5200000000 0.0066004056 0.0085576535 0.0203161910 0.0070340342 0.1710920000 231830236 0 1730686976 -0.9339151382 0.0217168741 0.3322253227 140 5.5600000000 0.0043735313 0.0085277669 0.0203161910 0.0070942626 0.1922750000 232203659 0 1732337664 -0.9417337179 0.0207317118 0.3436403573 141 5.6000000000 0.0084850620 0.0085274640 0.0203161910 0.0071059039 0.3954350000 232212757 0 1734242304 -0.9499056339 0.0248460248 0.3530449569 142 5.6400000000 0.0046619028 0.0085002417 0.0203161910 0.0071501136 0.3612340000 232314919 0 1735905280 -0.9550954700 0.0231570303 0.3621647060 143 5.6800000000 0.0074580442 0.0084929536 0.0203161910 0.0072027207 0.3319260000 234106896 0 1743028224 -0.9618742466 0.0289442688 0.3745380938 144 5.7200000000 0.0044485279 0.0084648674 0.0203161910 0.0072554960 0.2316100000 234009480 0 1745059840 -0.9676692486 0.0266341083 0.3814842105 145 5.7600000000 0.0095775137 0.0084725408 0.0203161910 0.0072611762 0.3374300000 233942460 0 1741901824 -0.9708505273 0.0329780392 0.3882280886 146 5.8000000000 0.0058581028 0.0084546337 0.0203161910 0.0072549251 0.2261350000 232225023 0 1742872576 -0.9762160778 0.0294561945 0.3984597027 147 5.8400000000 0.0072172610 0.0084462162 0.0203161910 0.0072328176 0.1777890000 232224453 0 1744633856 -0.9873563051 0.0296219811 0.4179119468 148 5.8800000000 0.0088947788 0.0084492470 0.0203161910 0.0072121959 0.1759000000 232228979 0 1746305024 -0.9907827377 0.0307523608 0.4242749512 149 5.9200000000 0.0032154529 0.0084141209 0.0203161910 0.0072025817 0.1743310000 232228977 0 1747951616 -0.9930350780 0.0261430629 0.4334711432 150 5.9600000000 0.0074634706 0.0084077832 0.0203161910 0.0071843737 0.1750140000 232231179 0 1749729280 -0.9965966940 0.0305618756 0.4429211617 151 6.0000000000 0.0086389361 0.0084093140 0.0203161910 0.0071612210 0.1686440000 232231625 0 1751379968 -0.9993226528 0.0321126692 0.4510969520 152 6.0400000000 0.0064087594 0.0083961525 0.0203161910 0.0071524843 0.1732900000 232233715 0 1753157632 -1.0010960102 0.0308017507 0.4607962370 153 6.0800000000 0.0076643899 0.0083913697 0.0203161910 0.0071344246 0.1671730000 232233565 0 1754935296 -1.0082458258 0.0308443569 0.4735745192 154 6.1200000000 0.0082445713 0.0083904165 0.0203161910 0.0071482015 0.1675940000 232235251 0 1756585984 -1.0140552521 0.0297587886 0.4871920645 155 6.1600000000 0.0073002730 0.0083833833 0.0203161910 0.0072113409 0.1871910000 232590429 0 1758236672 -1.0159081221 0.0277795754 0.4940171540 156 6.2000000000 0.0077011385 0.0083790099 0.0203161910 0.0073277357 0.4200210000 232601332 0 1760395264 -1.0203971863 0.0289917961 0.5102560520 157 6.2400000000 0.0072768307 0.0083719897 0.0203161910 0.0074069021 0.4040630000 232602886 0 1762172928 -1.0211486816 0.0305307917 0.5154354572 158 6.2800000000 0.0081602857 0.0083706498 0.0203161910 0.0074762475 0.3527690000 233315551 0 1766871040 -1.0240850449 0.0322424360 0.5349706411 159 6.3200000000 0.0100861331 0.0083814390 0.0203161910 0.0074903372 0.2902090000 234621478 0 1771581440 -1.0277978182 0.0318694934 0.5435900092 160 6.3600000000 0.0080597633 0.0083794285 0.0203161910 0.0075403400 0.2027850000 234591411 0 1772838912 -1.0264363289 0.0327061191 0.5576356053 161 6.4000000000 0.0091525968 0.0083842308 0.0203161910 0.0075247374 0.3314240000 234519440 0 1768902656 -1.0257077217 0.0343910269 0.5699087977 162 6.4400000000 0.0096347695 0.0083919502 0.0203161910 0.0075034529 0.1801740000 232944964 0 1770905600 -1.0237598419 0.0335803255 0.5770170689 163 6.4800000000 0.0092873722 0.0083974435 0.0203161910 0.0074888470 0.3951030000 232979102 0 1772441600 -1.0275211334 0.0338016897 0.5940326452 164 6.5200000000 0.0086371731 0.0083989053 0.0203161910 0.0074671030 0.3696190000 232981300 0 1774452736 -1.0266971588 0.0348292179 0.6021296978 165 6.5600000000 0.0096568009 0.0084065289 0.0203161910 0.0074597735 0.3389790000 233358565 0 1776599040 -1.0274411440 0.0372664221 0.6202919483 166 6.6000000000 0.0145814512 0.0084437272 0.0203161910 0.0074614277 0.2507200000 235278247 0 1784254464 -1.0245528221 0.0421647467 0.6275232434 167 6.6400000000 0.0078989044 0.0084404648 0.0203161910 0.0074884940 0.2316730000 235128997 0 1785880576 -1.0276119709 0.0370813981 0.6423790455 168 6.6800000000 0.0143155484 0.0084754356 0.0203161910 0.0075343673 0.3784540000 235056374 0 1782472704 -1.0234900713 0.0450835079 0.6572951674 169 6.7200000000 0.0112502025 0.0084918543 0.0203161910 0.0075288620 0.1609690000 232988298 0 1782910976 -1.0273096561 0.0383854918 0.6735991836 170 6.7600000000 0.0110576181 0.0085069470 0.0203161910 0.0075289631 0.1665980000 232991224 0 1784434688 -1.0253473520 0.0416585989 0.6861886382 171 6.8000000000 0.0102181658 0.0085169542 0.0203161910 0.0075186268 0.1855820000 233336074 0 1786576896 -1.0259852409 0.0433569700 0.6983413696 172 6.8400000000 0.0110639241 0.0085317621 0.0203161910 0.0074999538 0.4003100000 233356060 0 1782042624 -1.0235918760 0.0457016155 0.7078279257 173 6.8800000000 0.0104084658 0.0085426101 0.0203161910 0.0074788189 0.3604780000 233358458 0 1782964224 -1.0243749619 0.0464809276 0.7214022875 174 6.9200000000 0.0099670105 0.0085507963 0.0203161910 0.0074606546 0.3432780000 233501684 0 1785069568 -1.0272833109 0.0476720221 0.7376278639 175 6.9600000000 0.0092530428 0.0085548092 0.0203161910 0.0074397065 0.3425060000 235848393 0 1782878208 -1.0261307955 0.0480288453 0.7474365830 176 7.0000000000 0.0071484963 0.0085468188 0.0203161910 0.0074220263 0.3059620000 235775826 0 1781899264 -1.0275530815 0.0458984226 0.7607774734 177 7.0400000000 0.0119654499 0.0085661331 0.0203161910 0.0074454959 0.2012130000 235733273 0 1783869440 -1.0260431767 0.0488913320 0.7695673108 178 7.0800000000 0.0128980316 0.0085904696 0.0203161910 0.0074290451 0.3630210000 235660930 0 1781989376 -1.0249855518 0.0491656959 0.7791875601 179 7.1200000000 0.0092037590 0.0085938958 0.0203161910 0.0074184136 0.2017670000 233364478 0 1782173696 -1.0259524584 0.0477976091 0.7899841070 180 7.1600000000 0.0123786572 0.0086149222 0.0203161910 0.0074020811 0.1676430000 233365420 0 1784315904 -1.0244891644 0.0537205972 0.8038305044 181 7.2000000000 0.0140633695 0.0086450241 0.0203161910 0.0073912558 0.1685000000 233365790 0 1786200064 -1.0238167048 0.0552459732 0.8185000420 182 7.2400000000 0.0125081949 0.0086662504 0.0203161910 0.0073732427 0.1713930000 233369656 0 1785315328 -1.0253992081 0.0535901077 0.8314534426 183 7.2800000000 0.0134718884 0.0086925107 0.0203161910 0.0073555832 0.1640370000 233369758 0 1784311808 -1.0247458220 0.0561932810 0.8433396220 184 7.3200000000 0.0143895615 0.0087234729 0.0203161910 0.0073399872 0.1578750000 233371476 0 1783422976 -1.0199732780 0.0570694469 0.8546743989 185 7.3600000000 0.0091961352 0.0087260278 0.0203161910 0.0073290677 0.1861000000 233717022 0 1782550528 -1.0203737020 0.0520369075 0.8709236383 186 7.4000000000 0.0136229144 0.0087523552 0.0203161910 0.0073224966 0.3867310000 233738936 0 1781661696 -1.0188070536 0.0563896075 0.8895314336 187 7.4400000000 0.0149121713 0.0087852954 0.0203161910 0.0073098896 0.3368130000 233741366 0 1783742464 -1.0178930759 0.0575607084 0.8973155022 188 7.4800000000 0.0119083328 0.0088019073 0.0203161910 0.0073208946 0.3177460000 233890752 0 1785311232 -1.0164138079 0.0578916296 0.9129542112 189 7.5200000000 0.0078933341 0.0087971000 0.0203161910 0.0073076861 0.3155200000 236337041 0 1783488512 -1.0153627396 0.0557011552 0.9312866926 190 7.5600000000 0.0123451930 0.0088157742 0.0203161910 0.0073023253 0.2854890000 236359030 0 1782521856 -1.0110741854 0.0601769835 0.9442811012 191 7.6000000000 0.0132874157 0.0088391859 0.0203161910 0.0072893205 0.1950470000 236230165 0 1783545856 -1.0086542368 0.0628176481 0.9570289850 192 7.6400000000 0.0107352054 0.0088490610 0.0203161910 0.0072974096 0.3682680000 236208858 0 1780371456 -1.0081204176 0.0644705370 0.9707554579 193 7.6800000000 0.0084179640 0.0088468274 0.0203161910 0.0072996379 0.1768600000 233749746 0 1780531200 -1.0085142851 0.0635360777 0.9925560355 194 7.7200000000 0.0073816925 0.0088392751 0.0203161910 0.0072920103 0.1603550000 233752700 0 1782054912 -1.0085254908 0.0582216084 1.0084667206 195 7.7600000000 0.0084908884 0.0088374885 0.0203161910 0.0072952441 0.1796220000 234066318 0 1783934976 -1.0093642473 0.0552771538 1.0190510750 196 7.8000000000 0.0073864269 0.0088300851 0.0203161910 0.0073326138 0.3660190000 234088720 0 1785802752 -1.0069577694 0.0572146848 1.0364034176 197 7.8400000000 0.0066810423 0.0088191763 0.0203161910 0.0073499414 0.3092610000 234091446 0 1784479744 -1.0041284561 0.0633230433 1.0498040915 198 7.8800000000 0.0083626797 0.0088168708 0.0203161910 0.0073710509 0.2970190000 234242544 0 1786646528 -1.0029478073 0.0665836483 1.0634038448 199 7.9200000000 0.0087879673 0.0088167255 0.0203161910 0.0073624743 0.3047190000 236842349 0 1785872384 -1.0025709867 0.0662703216 1.0795180798 200 7.9600000000 0.0081409868 0.0088133468 0.0203161910 0.0073500276 0.2457710000 236842150 0 1784897536 -1.0017929077 0.0650919676 1.0937924385 201 8.0000000000 0.0099242544 0.0088188737 0.0203161910 0.0073633400 0.1974970000 236933054 0 1787027456 -1.0034377575 0.0626640469 1.1120688915 202 8.0400000000 0.0081901485 0.0088157612 0.0203161910 0.0073908872 0.3683550000 236678412 0 1777967104 -0.9968938231 0.0687019005 1.1228770018 203 8.0800000000 0.0087054409 0.0088152178 0.0203161910 0.0073955427 0.2143230000 234381494 0 1778098176 -0.9956595898 0.0728640556 1.1440529823 204 8.1200000000 0.0112327142 0.0088270682 0.0203161910 0.0073903090 0.3139470000 234413400 0 1780289536 -0.9917175770 0.0751902163 1.1532552242 205 8.1600000000 0.0089959614 0.0088278921 0.0203161910 0.0073830437 0.2967210000 234410990 0 1781813248 -0.9923642278 0.0705051869 1.1701517105 206 8.1999999990 0.0082895886 0.0088252790 0.0203161910 0.0073760472 0.2727580000 235083879 0 1785266176 -0.9901942015 0.0672483146 1.1832368374 207 8.2400000000 0.0089015886 0.0088256476 0.0203161910 0.0073724998 0.2532960000 237372497 0 1784999936 -0.9838126898 0.0741554797 1.1980123520 208 8.2799999990 0.0085143298 0.0088241509 0.0203161910 0.0073648396 0.2633970000 237312624 0 1784090624 -0.9814857244 0.0728680268 1.2107151747 209 8.3200000000 0.0088937730 0.0088244840 0.0203161910 0.0073530442 0.1834110000 237224494 0 1786040320 -0.9752477407 0.0756215230 1.2174723148 210 8.3599999990 0.0102188429 0.0088311238 0.0203161910 0.0074078857 0.3490850000 237171502 0 1781788672 -0.9672210813 0.0818470716 1.2326718569 211 8.4000000000 0.0113183334 0.0088429116 0.0203161910 0.0074479839 0.2215910000 234699982 0 1782333440 -0.9651088715 0.0776972771 1.2531331778 212 8.4399999990 0.0091390247 0.0088443083 0.0203161910 0.0074406421 0.3342040000 234779644 0 1781837824 -0.9599453211 0.0744658336 1.2616053820 213 8.4800000000 0.0094575183 0.0088471872 0.0203161910 0.0074459262 0.3258110000 234781614 0 1784070144 -0.9509748220 0.0829496533 1.2779030800 214 8.5200000000 0.0096295802 0.0088508433 0.0203161910 0.0075123288 0.2947280000 235384955 0 1785614336 -0.9454268217 0.0807357803 1.2906076908 215 8.5600000000 0.0105415098 0.0088587068 0.0203161910 0.0075226462 0.2774510000 237961397 0 1785159680 -0.9365456700 0.0827308074 1.3018846512 216 8.6000000000 0.0102072321 0.0088649500 0.0203161910 0.0075063860 0.2516740000 237937906 0 1784221696 -0.9283289909 0.0865801126 1.3120048046 217 8.6400000000 0.0081358012 0.0088615899 0.0203161910 0.0075184470 0.2080020000 237939457 0 1785499648 -0.9181320667 0.0892531276 1.3251447678 218 8.6800000000 0.0127874045 0.0088795982 0.0203161910 0.0075870471 0.4148580000 237696658 0 1783967744 -0.9122971296 0.0908080190 1.3397974968 219 8.7200000000 0.0148938959 0.0089070608 0.0203161910 0.0075916080 0.2379140000 235111058 0 1780834304 -0.9031801224 0.0930974931 1.3531633615 220 8.7600000000 0.0152160060 0.0089357378 0.0203161910 0.0075968155 0.3429430000 235151400 0 1782722560 -0.8946912289 0.0949488580 1.3645803928 221 8.8000000000 0.0135521432 0.0089566265 0.0203161910 0.0076177355 0.3186090000 235154698 0 1784975360 -0.8829256892 0.0945804343 1.3769000769 222 8.8400000000 0.0139105823 0.0089789416 0.0203161910 0.0076248020 0.3160000000 235314400 0 1786531840 -0.8753929734 0.0960203111 1.3897126913 223 8.8800000000 0.0158271231 0.0090096509 0.0203161910 0.0076274526 0.3257880000 238421457 0 1786466304 -0.8660016656 0.0991760343 1.4008336067 224 8.9200000000 0.0147787202 0.0090354057 0.0203161910 0.0076340451 0.2273090000 238636924 0 1784070144 -0.8515245914 0.1037727520 1.4137698412 225 8.9600000000 0.0148907155 0.0090614293 0.0203161910 0.0076338158 0.2317710000 238322377 0 1785389056 -0.8432201147 0.1041989774 1.4202971458 226 9.0000000000 0.0138444286 0.0090825930 0.0203161910 0.0076185429 0.1792290000 238386875 0 1784430592 -0.8325382471 0.1099563092 1.4300049543 227 9.0400000000 0.0128394077 0.0090991429 0.0203161910 0.0076035087 0.3658610000 238313296 0 1779367936 -0.8174813390 0.1158918068 1.4402896166 228 9.0800000000 0.0131189460 0.0091167736 0.0203161910 0.0076144621 0.2314040000 235510368 0 1779040256 -0.8062014580 0.1208368167 1.4543966055 229 9.1200000000 0.0116760302 0.0091279494 0.0203161910 0.0076661392 0.3693490000 235556258 0 1780932608 -0.7959784269 0.1254074574 1.4592850208 230 9.1600000000 0.0117542278 0.0091393680 0.0203161910 0.0077552768 0.3382190000 235559140 0 1782198272 -0.7855821252 0.1283242106 1.4660917521 231 9.2000000000 0.0153713720 0.0091663464 0.0203161910 0.0079679000 0.3313960000 235705914 0 1784393728 -0.7747657895 0.1341839284 1.4779832363 232 9.2400000000 0.0128679359 0.0091823015 0.0203161910 0.0081029391 0.3357630000 238028655 0 1784614912 -0.7655555010 0.1330673993 1.4845640659 233 9.2800000000 0.0127548622 0.0091976344 0.0203161910 0.0082343179 0.2110540000 239595392 0 1782824960 -0.7560772300 0.1353865862 1.4917190075 234 9.3200000000 0.0151870577 0.0092232302 0.0203161910 0.0083483592 0.2564850000 238962227 0 1781354496 -0.7467283010 0.1400590241 1.5010528564 235 9.3600000000 0.0120666595 0.0092353299 0.0203161910 0.0084049798 0.1984720000 239031225 0 1783132160 -0.7344225645 0.1442152560 1.5056576729 236 9.4000000000 0.0135083087 0.0092534357 0.0203161910 0.0084585665 0.4044920000 238959358 0 1779568640 -0.7284695506 0.1455893666 1.5135682821 237 9.4400000000 0.0145204281 0.0092756593 0.0203161910 0.0084862798 0.2351030000 235570646 0 1779838976 -0.7178358436 0.1510894299 1.5216209888 238 9.4800000000 0.0139400857 0.0092952578 0.0203161910 0.0085044960 0.2003930000 235573816 0 1780944896 -0.7092520595 0.1549846381 1.5266944170 239 9.5200000000 0.0121141588 0.0093070523 0.0203161910 0.0085373580 0.1904380000 235921830 0 1783103488 -0.6977155209 0.1589457840 1.5322037935 240 9.5600000000 0.0138380509 0.0093259315 0.0203161910 0.0085952605 0.4022520000 235955616 0 1783128064 -0.6887853146 0.1646936238 1.5421057940 241 9.6000000000 0.0125297084 0.0093392252 0.0203161910 0.0086374572 0.3538760000 235958222 0 1785135104 -0.6773374081 0.1653116047 1.5515277386 242 9.6400000000 0.0133284694 0.0093557096 0.0203161910 0.0086589150 0.3525590000 236106768 0 1784197120 -0.6677532792 0.1697923243 1.5606286526 243 9.6800000000 0.0125648146 0.0093689158 0.0203161910 0.0086690644 0.3604990000 239197209 0 1784500224 -0.6560807228 0.1755794138 1.5681344271 244 9.7200000000 0.0107278051 0.0093744851 0.0203161910 0.0087048842 0.2145940000 240136260 0 1785417728 -0.6437903047 0.1823617220 1.5744003057 245 9.7600000000 0.0137205692 0.0093922242 0.0203161910 0.0087740655 0.2510910000 239618332 0 1785057280 -0.6352086663 0.1854476780 1.5849347115 246 9.8000000000 0.0131290685 0.0094074146 0.0203161910 0.0087891933 0.2036190000 239605599 0 1783943168 -0.6218924522 0.1897305846 1.5950182676 247 9.8400000000 0.0168392267 0.0094375029 0.0203161910 0.0088093196 0.4409790000 239604232 0 1779675136 -0.6133885384 0.1943988651 1.6066085100 248 9.8800000000 0.0165736675 0.0094662778 0.0203161910 0.0087936481 0.2259210000 236223076 0 1778188288 -0.6044991016 0.1952760369 1.6151657104 249 9.9200000000 0.0150193432 0.0094885792 0.0203161910 0.0087778094 0.3994990000 236312222 0 1779965952 -0.5944013000 0.1974506229 1.6207261086 250 9.9600000000 0.0168595519 0.0095180631 0.0203161910 0.0087608361 0.3488640000 236314536 0 1781669888 -0.5840672851 0.2006977350 1.6320544481 251 10.0000000000 0.0151214385 0.0095403873 0.0203161910 0.0087451265 0.3271850000 237338885 0 1784217600 -0.5749667883 0.2029213607 1.6383011341 252 10.0400000000 0.0153460233 0.0095634256 0.0203161910 0.0087308816 0.3045090000 240242643 0 1784438784 -0.5655943155 0.2031992674 1.6487966776 253 10.0800000000 0.0137188286 0.0095798501 0.0203161910 0.0087150576 0.2852990000 240240892 0 1783656448 -0.5566654801 0.1973668039 1.6594929695 254 10.1200000000 0.0148724224 0.0096006870 0.0203161910 0.0087294848 0.2293640000 240328212 0 1784344576 -0.5474972129 0.2020218223 1.6690539122 255 10.1600000000 0.0143959196 0.0096194918 0.0203161910 0.0087401418 0.1936230000 240085245 0 1786642432 -0.5392846465 0.2088372260 1.6750900745 256 10.2000000000 0.0175038446 0.0096502901 0.0203161910 0.0087353897 0.4058150000 240013718 0 1777610752 -0.5232210159 0.2167912871 1.6888066530 257 10.2400000000 0.0176759623 0.0096815184 0.0203161910 0.0087265994 0.2084380000 236326330 0 1778036736 -0.5183837414 0.2154680490 1.6963500977 258 10.2800000000 0.0165953152 0.0097083160 0.0203161910 0.0087103390 0.1620600000 236368456 0 1779720192 -0.5094029903 0.2212923020 1.7013309002 259 10.3200000000 0.0164683294 0.0097344165 0.0203161910 0.0087012614 0.1690960000 236371670 0 1781497856 -0.4962347746 0.2242803276 1.7110044956 260 10.3600000000 0.0166813768 0.0097611355 0.0203161910 0.0087048247 0.1945590000 236782476 0 1783115776 -0.4861733913 0.2275819778 1.7180308104 261 10.4000000000 0.0172622781 0.0097898756 0.0203161910 0.0087027999 0.4163130000 236770122 0 1783386112 -0.4759194255 0.2280698121 1.7252920866 262 10.4400000000 0.0172286499 0.0098182678 0.0203161910 0.0086890932 0.3686690000 236773508 0 1785389056 -0.4664921165 0.2276394963 1.7332497835 263 10.4800000000 0.0177259594 0.0098483351 0.0203161910 0.0086756953 0.3553670000 238067045 0 1786847232 -0.4561102390 0.2291236818 1.7394881248 264 10.5200000000 0.0177709367 0.0098783449 0.0203161910 0.0086633615 0.3083610000 240974043 0 1784315904 -0.4437996745 0.2301096320 1.7452281713 265 10.5600000000 0.0202928167 0.0099176448 0.0203161910 0.0086484765 0.2951020000 240901616 0 1783373824 -0.4333590865 0.2332270741 1.7536612749 266 10.6000000000 0.0179522019 0.0099478499 0.0203161910 0.0086345520 0.2386740000 241049492 0 1785470976 -0.4211064875 0.2348568588 1.7552711964 267 10.6400000000 0.0163133647 0.0099716908 0.0203161910 0.0086326710 0.1967100000 240807977 0 1784766464 -0.4114083052 0.2303867936 1.7596328259 268 10.6800000000 0.0212334171 0.0100137122 0.0212334171 0.0086337685 0.4401170000 240737266 0 1780940800 -0.3984645009 0.2333586067 1.7705422640 269 10.7200000000 0.0222013500 0.0100590194 0.0222013500 0.0086231778 0.2184960000 236783446 0 1781329920 -0.3876371980 0.2355187833 1.7716575861 270 10.7600000000 0.0198782794 0.0100953870 0.0222013500 0.0086142614 0.1700410000 236786844 0 1782427648 -0.3632601500 0.2368809879 1.7816284895 271 10.8000000000 0.0198992211 0.0101315635 0.0222013500 0.0086252523 0.1777440000 236787070 0 1784713216 -0.3476375937 0.2404039204 1.7858766317 272 10.8400000000 0.0196045339 0.0101663906 0.0222013500 0.0086848200 0.1759610000 236789852 0 1786490880 -0.3376432061 0.2393477261 1.7872685194 273 10.8800000000 0.0202020053 0.0102031511 0.0222013500 0.0086939086 0.1740130000 236789134 0 1783595008 -0.3247672319 0.2400011867 1.7929965258 274 10.9200000000 0.0207647923 0.0102416973 0.0222013500 0.0086996869 0.1726670000 236791420 0 1782968320 -0.3079794645 0.2429271340 1.7974509001 275 10.9600000000 0.0219727140 0.0102843555 0.0222013500 0.0087034950 0.1699760000 236793718 0 1784860672 -0.2952732742 0.2428182065 1.8020021915 276 11.0000000000 0.0223513469 0.0103280765 0.0223513469 0.0087056426 0.1659460000 236793788 0 1786236928 -0.2843343019 0.2442359328 1.8058085442 277 11.0400000000 0.0185988285 0.0103579348 0.0223513469 0.0087034551 0.1685500000 236796558 0 1785495552 -0.2710422277 0.2431425601 1.8060178757 278 11.0800000000 0.0187869128 0.0103882549 0.0223513469 0.0087078859 0.1933670000 237179392 0 1785233408 -0.2565789521 0.2448348403 1.8102678061 279 11.1200000000 0.0184879564 0.0104172860 0.0223513469 0.0087141511 0.4074720000 237172202 0 1779703808 -0.2431516796 0.2473370135 1.8129165173 280 11.1600000000 0.0177592114 0.0104435072 0.0223513469 0.0087201806 0.3637180000 237176960 0 1780969472 -0.2289085686 0.2475604117 1.8172245026 281 11.2000000000 0.0188221578 0.0104733245 0.0223513469 0.0087262499 0.3495120000 238608301 0 1785614336 -0.2162992358 0.2496832311 1.8200768232 282 11.2400000000 0.0195086412 0.0105053646 0.0223513469 0.0087211025 0.3018950000 241573743 0 1783734272 -0.2036653459 0.2497566342 1.8252564669 283 11.2800000000 0.0192828812 0.0105363806 0.0223513469 0.0087060632 0.2938460000 241501320 0 1782448128 -0.1916905642 0.2501094639 1.8280929327 284 11.3200000000 0.0169062279 0.0105588096 0.0223513469 0.0086948833 0.2451580000 241607420 0 1783951360 -0.1803476512 0.2497859299 1.8314315081 285 11.3600000000 0.0189703219 0.0105883237 0.0223513469 0.0086933947 0.2032770000 241404013 0 1786376192 -0.1675856113 0.2531698346 1.8374462128 286 11.4000000000 0.0199471340 0.0106210468 0.0223513469 0.0086885945 0.4391560000 241331646 0 1779953664 -0.1585104764 0.2564993799 1.8387855291 287 11.4400000000 0.0196248535 0.0106524189 0.0223513469 0.0086734988 0.2225210000 237184990 0 1780903936 -0.1479599476 0.2552193403 1.8441001177 288 11.4800000000 0.0199233536 0.0106846097 0.0223513469 0.0086593508 0.1718730000 237186024 0 1781809152 -0.1417578459 0.2566071749 1.8445439339 289 11.5200000000 0.0200475100 0.0107170073 0.0223513469 0.0086456875 0.1687360000 237187786 0 1783095296 -0.1323980689 0.2554109395 1.8535755873 290 11.5600000000 0.0209932439 0.0107524426 0.0223513469 0.0086387969 0.1681950000 237189348 0 1784602624 -0.1210934818 0.2562622428 1.8623292446 291 11.6000000000 0.0198967718 0.0107838664 0.0223513469 0.0086279269 0.1629500000 237189742 0 1786396672 -0.1165963709 0.2543158531 1.8669365644 292 11.6400000000 0.0180895347 0.0108088858 0.0223513469 0.0086166114 0.1935510000 237547776 0 1784627200 -0.1072514951 0.2534336448 1.8727147579 293 11.6800000000 0.0183649808 0.0108346745 0.0223513469 0.0086019090 0.3983740000 237538026 0 1776353280 -0.1006119549 0.2543207407 1.8791862726 294 11.7200000000 0.0189958364 0.0108624336 0.0223513469 0.0085888069 0.3448290000 237538508 0 1778003968 -0.0938985646 0.2544229329 1.8870017529 295 11.7600000000 0.0181307942 0.0108870721 0.0223513469 0.0085803168 0.3470160000 238878761 0 1781174272 -0.0880866051 0.2534959912 1.8936828375 296 11.8000000000 0.0187314115 0.0109135732 0.0223513469 0.0085703353 0.3112230000 241906587 0 1785978880 -0.0829779804 0.2536546290 1.9006856680 297 11.8400000000 0.0196963865 0.0109431450 0.0223513469 0.0085599305 0.2083270000 242121424 0 1781936128 -0.0782833099 0.2542198002 1.9086208344 298 11.8800000000 0.0180943403 0.0109671423 0.0223513469 0.0085551674 0.2617300000 241952898 0 1783775232 -0.0735237896 0.2523810863 1.9151819944 299 11.9200000000 0.0182134137 0.0109913773 0.0223513469 0.0085445151 0.2012770000 241859580 0 1785237504 -0.0690993965 0.2529548407 1.9224847555 300 11.9600000000 0.0214935262 0.0110263845 0.0223513469 0.0085344339 0.4434030000 241843798 0 1782857728 -0.0606583357 0.2557133436 1.9359842539 301 12.0000000000 0.0214433428 0.0110609923 0.0223513469 0.0085205197 0.1979870000 237526830 0 1784303616 -0.0565999746 0.2572824359 1.9436056614 302 12.0400000000 0.0204763822 0.0110921691 0.0223513469 0.0085106049 0.2005770000 237891892 0 1784938496 -0.0525913537 0.2550032139 1.9542210102 303 12.0800000000 0.0226491243 0.0111303109 0.0226491243 0.0085042984 0.3984130000 237882906 0 1781207040 -0.0461760759 0.2570301294 1.9664041996 304 12.1200000000 0.0198566765 0.0111590160 0.0226491243 0.0085021131 0.3410770000 237882016 0 1782726656 -0.0445614755 0.2561790943 1.9729079008 305 12.1600000000 0.0193545967 0.0111858868 0.0226491243 0.0085006644 0.3528670000 239003905 0 1785462784 -0.0401625037 0.2547890544 1.9851803780 306 12.2000000000 0.0195309222 0.0112131581 0.0226491243 0.0084920079 0.3441940000 241889815 0 1784758272 -0.0370952487 0.2555957437 1.9959549904 307 12.2400000000 0.0203509443 0.0112429229 0.0226491243 0.0084902263 0.2601310000 242014841 0 1784229888 -0.0342444777 0.2577760518 2.0069828033 308 12.2800000000 0.0201365873 0.0112717984 0.0226491243 0.0084920953 0.2509510000 241776323 0 1786191872 -0.0323033035 0.2570931911 2.0189018250 309 12.3200000000 0.0186143890 0.0112955609 0.0226491243 0.0085054141 0.1995270000 241851073 0 1785536512 -0.0306698978 0.2561396360 2.0278372765 310 12.3600000000 0.0228036456 0.0113326837 0.0228036456 0.0085129525 0.4203390000 241779574 0 1783541760 -0.0276329517 0.2581003904 2.0443639755 311 12.4000000000 0.0218176749 0.0113663975 0.0228036456 0.0085313049 0.2075380000 237892926 0 1785135104 -0.0247311294 0.2578530610 2.0550308228 312 12.4400000000 0.0229436271 0.0114035040 0.0229436271 0.0085663363 0.1636560000 237893552 0 1785860096 -0.0201271474 0.2587701082 2.0800740719 313 12.4800000000 0.0223238450 0.0114383933 0.0229436271 0.0085588447 0.1737180000 237895434 0 1784840192 -0.0222613513 0.2570959330 2.0905735493 314 12.5200000000 0.0233542603 0.0114763419 0.0233542603 0.0085493423 0.1922490000 238278760 0 1783922688 -0.0209501684 0.2567615509 2.1042764187 315 12.5600000000 0.0240074322 0.0115161231 0.0240074322 0.0085501784 0.4046260000 238280690 0 1779900416 -0.0189411044 0.2574468255 2.1164557934 316 12.6000000000 0.0245504528 0.0115573710 0.0245504528 0.0085385789 0.3629620000 238284852 0 1781825536 -0.0185155869 0.2581957579 2.1290671825 317 12.6400000000 0.0243836474 0.0115978325 0.0245504528 0.0085254605 0.3537910000 238302334 0 1783697408 -0.0186719298 0.2581074834 2.1399192810 318 12.6800000000 0.0249395911 0.0116397877 0.0249395911 0.0085120957 0.3569190000 241478515 0 1784864768 -0.0189008117 0.2580353022 2.1518840790 319 12.7200000000 0.0234539155 0.0116768226 0.0249395911 0.0084993351 0.2216960000 242687922 0 1784840192 -0.0214429796 0.2568790615 2.1608583927 320 12.7600000000 0.0224075895 0.0117103562 0.0249395911 0.0084861664 0.2519390000 242200902 0 1783214080 -0.0247080326 0.2571655810 2.1689853668 321 12.8000000000 0.0222842749 0.0117432968 0.0249395911 0.0084747669 0.1870450000 242207601 0 1785266176 -0.0268678963 0.2559663653 2.1795148849 322 12.8400000000 0.0221104380 0.0117754929 0.0249395911 0.0084631248 0.4275140000 242132690 0 1784012800 -0.0280056298 0.2556812763 2.1894388199 323 12.8800000000 0.0217862390 0.0118064859 0.0249395911 0.0084567575 0.2305710000 238654562 0 1785552896 -0.0344434083 0.2531127036 2.1966707706 324 12.9200000000 0.0221958067 0.0118385517 0.0249395911 0.0084449375 0.4082910000 238671588 0 1781657600 -0.0360680819 0.2529522479 2.2062652111 325 12.9600000000 0.0216309056 0.0118686820 0.0249395911 0.0084319582 0.3616590000 238671110 0 1782403072 -0.0377588421 0.2533913851 2.2146251202 326 13.0000000000 0.0220729560 0.0118999835 0.0249395911 0.0084193744 0.3559300000 238687480 0 1784954880 -0.0384304225 0.2532695234 2.2231094837 327 13.0400000000 0.0222865976 0.0119317468 0.0249395911 0.0084086471 0.3796300000 242040125 0 1785147392 -0.0409934819 0.2542724311 2.2322187424 328 13.0800000000 0.0222635642 0.0119632462 0.0249395911 0.0083976736 0.2107500000 243396522 0 1785237504 -0.0402146950 0.2565779090 2.2396085262 329 13.1200000000 0.0220832601 0.0119940062 0.0249395911 0.0083853937 0.2736910000 242884048 0 1784532992 -0.0421875678 0.2574678063 2.2481365204 330 13.1600000000 0.0222053248 0.0120249496 0.0249395911 0.0083733972 0.1986640000 242778371 0 1786454016 -0.0432102047 0.2575427294 2.2568168640 331 13.2000000000 0.0249028392 0.0120638556 0.0249395911 0.0083672650 0.4271490000 242704536 0 1781575680 -0.0429569110 0.2612736523 2.2683758736 332 13.2400000000 0.0253420770 0.0121038502 0.0253420770 0.0083574727 0.2172310000 239144308 0 1777704960 -0.0445692465 0.2622763515 2.2770144939 333 13.2800000000 0.0257363953 0.0121447888 0.0257363953 0.0083459516 0.4168270000 239130478 0 1779355648 -0.0467860699 0.2631235123 2.2864286900 334 13.3200000000 0.0261369422 0.0121866815 0.0261369422 0.0083345447 0.3674000000 239127440 0 1781133312 -0.0487445742 0.2635497451 2.2945725918 335 13.3600000000 0.0260472968 0.0122280564 0.0261369422 0.0083222324 0.3588890000 239129546 0 1782579200 -0.0513405949 0.2648628354 2.3027324677 336 13.4000000000 0.0260865390 0.0122693019 0.0261369422 0.0083105231 0.3380430000 240722355 0 1785450496 -0.0508838445 0.2659520507 2.3118696213 337 13.4400000000 0.0256278664 0.0123089416 0.0261369422 0.0083045081 0.3564830000 244027737 0 1785454592 -0.0528423190 0.2679388225 2.3190689087 338 13.4800000000 0.0242953263 0.0123444042 0.0261369422 0.0083118401 0.1897370000 244827636 0 1783873536 -0.0554155111 0.2692840099 2.3235838413 339 13.5200000000 0.0251875464 0.0123822896 0.0261369422 0.0083252391 0.3110140000 244390104 0 1782788096 -0.0567947924 0.2692806125 2.3305392265 340 13.5600000000 0.0256540105 0.0124213241 0.0261369422 0.0083204177 0.1867820000 245009612 0 1785602048 -0.0588074625 0.2705449164 2.3354783058 341 13.6000000000 0.0249448679 0.0124580500 0.0261369422 0.0083116011 0.1818830000 244152857 0 1786896384 -0.0616381466 0.2698366642 2.3401479721 342 13.6400000000 0.0293490738 0.0125074390 0.0293490738 0.0083051039 0.4070540000 244076014 0 1779486720 -0.0573702753 0.2722775936 2.3500387669 343 13.6800000000 0.0301150549 0.0125587731 0.0301150549 0.0082937449 0.2458730000 239584474 0 1779634176 -0.0591674745 0.2719418406 2.3562035561 344 13.7200000000 0.0300732329 0.0126096873 0.0301150549 0.0082819200 0.3792180000 239568824 0 1775685632 -0.0603842735 0.2736687362 2.3615951538 345 13.7600000000 0.0299410000 0.0126599230 0.0301150549 0.0082725405 0.3354810000 239571030 0 1777958912 -0.0622861385 0.2732517421 2.3670949936 346 13.8000000000 0.0292282738 0.0127078084 0.0301150549 0.0082642863 0.3455210000 241414507 0 1780117504 -0.0640295148 0.2721314728 2.3719496727 347 13.8400000000 0.0296576153 0.0127566551 0.0301150549 0.0082531329 0.3425130000 244841649 0 1786474496 -0.0665628314 0.2715028524 2.3765041828 348 13.8800000000 0.0293976776 0.0128044741 0.0301150549 0.0082422753 0.1915980000 246159586 0 1784782848 -0.0665462613 0.2734758258 2.3820748329 349 13.9200000000 0.0295058284 0.0128523290 0.0301150549 0.0082362273 0.2922180000 245179346 0 1786376192 -0.0685600638 0.2729948163 2.3881242275 350 13.9600000000 0.0294825900 0.0128998440 0.0301150549 0.0082281782 0.2012990000 245468524 0 1785999360 -0.0698782206 0.2720073462 2.3965103626 351 14.0000000000 0.0296932142 0.0129476884 0.0301150549 0.0082167292 0.1805150000 245044761 0 1785327616 -0.0699749589 0.2732927203 2.4005708694 352 14.0400000000 0.0210391544 0.0129706755 0.0301150549 0.0082198050 0.4380940000 244966026 0 1784147968 -0.0740709305 0.2672617733 2.3987836838 353 14.0800000000 0.0207749568 0.0129927839 0.0301150549 0.0082081557 0.2515630000 239580342 0 1779240960 -0.0741198063 0.2655376494 2.4032626152 354 14.1200000000 0.0208108202 0.0130148688 0.0301150549 0.0081969048 0.1896390000 239964512 0 1779752960 -0.0737656951 0.2667196393 2.4076631069 355 14.1600000000 0.0206219926 0.0130362973 0.0301150549 0.0081854493 0.3755660000 239957394 0 1777242112 -0.0745193958 0.2649039626 2.4124398232 356 14.2000000000 0.0206305627 0.0130576295 0.0301150549 0.0081753973 0.3173180000 239959756 0 1778626560 -0.0740643740 0.2649754584 2.4169871807 357 14.2400000000 0.0200593844 0.0130772423 0.0301150549 0.0081639804 0.3186070000 241699745 0 1781198848 -0.0734598041 0.2646775246 2.4224202633 358 14.2800000000 0.0210811533 0.0130995996 0.0301150549 0.0081534032 0.3178300000 243213959 0 1784360960 -0.0742377043 0.2634503841 2.4289355278 359 14.3200000000 0.0209804997 0.0131215519 0.0301150549 0.0081435579 0.2142120000 246209742 0 1782718464 -0.0744010806 0.2623714209 2.4338674545 360 14.3600000000 0.0208236184 0.0131429466 0.0301150549 0.0081361335 0.2529180000 245800391 0 1782521856 -0.0743154883 0.2608765960 2.4399664402 361 14.4000000000 0.0211068131 0.0131650071 0.0301150549 0.0081296458 0.2246610000 246007322 0 1784360960 -0.0742567778 0.2611453235 2.4464938641 362 14.4400000000 0.0204331558 0.0131850849 0.0301150549 0.0081232285 0.1819130000 245602215 0 1786081280 -0.0747476816 0.2608029544 2.4526064396 363 14.4800000000 0.0219615661 0.0132092625 0.0301150549 0.0081179635 0.4536500000 245523088 0 1780781056 -0.0756384730 0.2578690052 2.4633107185 364 14.5200000000 0.0213152524 0.0132315317 0.0301150549 0.0081074525 0.2659640000 239971756 0 1774272512 -0.0762177706 0.2569457889 2.4699234962 365 14.5600000000 0.0210602563 0.0132529803 0.0301150549 0.0080964413 0.1578510000 239976354 0 1774432256 -0.0764337778 0.2557255030 2.4768540859 366 14.6000000000 0.0216134414 0.0132758231 0.0301150549 0.0080856044 0.1546880000 239977500 0 1776545792 -0.0772333741 0.2571397424 2.4850559235 367 14.6400000000 0.0209094845 0.0132966232 0.0301150549 0.0080747666 0.1520630000 239977542 0 1777545216 -0.0773781538 0.2582834959 2.4915027618 368 14.6800000000 0.0217342209 0.0133195515 0.0301150549 0.0080665059 0.1785740000 240397944 0 1779572736 -0.0768749714 0.2585114837 2.5001947880 369 14.7200000000 0.0215703826 0.0133419115 0.0301150549 0.0080639470 0.3740240000 240360954 0 1781350400 -0.0774887204 0.2581579089 2.5074841976 370 14.7600000000 0.0216407329 0.0133643407 0.0301150549 0.0080605358 0.3082730000 240368580 0 1783382016 -0.0778577328 0.2588040829 2.5153570175 371 14.8000000000 0.0217048135 0.0133868218 0.0301150549 0.0080528669 0.3065170000 240499482 0 1785159680 -0.0777688622 0.2587174177 2.5226132870 372 14.8400000000 0.0216264240 0.0134089713 0.0301150549 0.0080506780 0.3252790000 242818819 0 1784025088 -0.0777856708 0.2578013241 2.5297260284 373 14.8800000000 0.0219528563 0.0134318771 0.0301150549 0.0080477437 0.2769330000 245867357 0 1780449280 -0.0778086185 0.2579503655 2.5372817516 374 14.9200000000 0.0220338069 0.0134548769 0.0301150549 0.0080430143 0.1878740000 246168120 0 1779548160 -0.0782263279 0.2570500970 2.5447666645 375 14.9600000000 0.0221083425 0.0134779528 0.0301150549 0.0080465361 0.3062700000 246006578 0 1781297152 -0.0777965188 0.2567498088 2.5517852306 376 15.0000000000 0.0218766443 0.0135002898 0.0301150549 0.0080467123 0.1838090000 246894078 0 1783136256 -0.0764995813 0.2577399313 2.5590603352 377 15.0400000000 0.0209658500 0.0135200923 0.0301150549 0.0080372044 0.1686650000 245933793 0 1784467456 -0.0747730732 0.2590772808 2.5711250305 378 15.0800000000 0.0225942191 0.0135440980 0.0301150549 0.0080273497 0.4357100000 245854194 0 1781768192 -0.0735077858 0.2602695227 2.5793232918 379 15.1200000000 0.0229295865 0.0135688618 0.0301150549 0.0080167673 0.2529500000 240376250 0 1775869952 -0.0709710717 0.2607665062 2.5853943825 380 15.1600000000 0.0223676749 0.0135920165 0.0301150549 0.0080075311 0.1465840000 240377100 0 1775521792 -0.0684199929 0.2621240914 2.5900557041 381 15.2000000000 0.0219107922 0.0136138506 0.0301150549 0.0079976146 0.1523160000 240380802 0 1777664000 -0.0664052963 0.2625088096 2.5948407650 382 15.2400000000 0.0220561605 0.0136359509 0.0301150549 0.0079878973 0.1472590000 240380724 0 1778958336 -0.0641274452 0.2632075846 2.5996944904 383 15.2800000000 0.0220740009 0.0136579824 0.0301150549 0.0079780092 0.1486490000 240380686 0 1781231616 -0.0613556802 0.2639924586 2.6043264866 384 15.3200000000 0.0221697241 0.0136801483 0.0301150549 0.0079683261 0.1511290000 240384188 0 1782595584 -0.0592900515 0.2643692791 2.6082863808 385 15.3600000000 0.0215749368 0.0137006543 0.0301150549 0.0079590318 0.1499280000 240385918 0 1784258560 -0.0567413867 0.2640732825 2.6101930141 386 15.4000000000 0.0224769302 0.0137233908 0.0301150549 0.0079565155 0.1761370000 240392760 0 1786044416 -0.0530802011 0.2652367055 2.6131801605 387 15.4400000000 0.0210314598 0.0137422747 0.0301150549 0.0079536321 0.1925780000 240797350 0 1783627776 -0.0502838492 0.2666907310 2.6139545441 388 15.4800000000 0.0210625827 0.0137611414 0.0301150549 0.0079443471 0.3932750000 240765428 0 1786351616 -0.0470404774 0.2678174078 2.6150093079 389 15.5200000000 0.0216451827 0.0137814089 0.0301150549 0.0079356725 0.3639880000 240772826 0 1784938496 -0.0445175916 0.2686021626 2.6163945198 390 15.5600000000 0.0204145443 0.0137984169 0.0301150549 0.0079256869 0.3433550000 242434215 0 1786753024 -0.0405929238 0.2710678875 2.6165490150 391 15.6000000000 0.0207133666 0.0138161022 0.0301150549 0.0079338400 0.3738990000 243674103 0 1779716096 -0.0373465382 0.2720795870 2.6179859638 392 15.6400000000 0.0209451206 0.0138342885 0.0301150549 0.0079250491 0.2381860000 247311276 0 1776578560 -0.0343495868 0.2709379792 2.6190726757 393 15.6800000000 0.0207526051 0.0138518923 0.0301150549 0.0079149923 0.2948720000 246928816 0 1774616576 -0.0317456126 0.2696759105 2.6195213795 394 15.7200000000 0.0209447760 0.0138698946 0.0301150549 0.0079059735 0.2468980000 247115076 0 1777160192 -0.0296034366 0.2688203156 2.6203267574 395 15.7600000000 0.0207087118 0.0138872081 0.0301150549 0.0079065989 0.2066790000 246623309 0 1778601984 -0.0263723284 0.2692359090 2.6206207275 396 15.8000000000 0.0193708967 0.0139010558 0.0301150549 0.0079070253 0.4965950000 246549662 0 1767632896 -0.0225247741 0.2680833638 2.6199107170 397 15.8400000000 0.0193227027 0.0139147123 0.0301150549 0.0079072454 0.2410740000 240792538 0 1769254912 -0.0204159021 0.2677091360 2.6197099686 398 15.8800000000 0.0190819185 0.0139276952 0.0301150549 0.0079003876 0.1786940000 240794808 0 1769349120 -0.0173439085 0.2662233710 2.6187641621 399 15.9200000000 0.0193142500 0.0139411954 0.0301150549 0.0078919037 0.1733480000 240794702 0 1770872832 -0.0121753514 0.2682074308 2.6174747944 400 15.9600000000 0.0192896929 0.0139545666 0.0301150549 0.0078854151 0.1758290000 240799384 0 1772929024 -0.0090070665 0.2683948874 2.6181714535 401 16.0000000000 0.0189412739 0.0139670023 0.0301150549 0.0078800643 0.1730090000 240800570 0 1774538752 -0.0052454472 0.2683378160 2.6185166836 402 16.0400000000 0.0186697729 0.0139787007 0.0301150549 0.0078715304 0.2015110000 241185460 0 1776189440 0.0002034307 0.2685742974 2.6186039448 403 16.0800000000 0.0186241195 0.0139902278 0.0301150549 0.0078644930 0.4290260000 241165794 0 1778094080 0.0058004856 0.2682464123 2.6202707291 404 16.1200000000 0.0187359881 0.0140019747 0.0301150549 0.0078560753 0.3654440000 241166440 0 1780125696 0.0101655126 0.2682909369 2.6195855141 405 16.1600000000 0.0181572326 0.0140122346 0.0301150549 0.0078472245 0.3691530000 241313554 0 1782030336 0.0147105455 0.2693141401 2.6201324463 406 16.2000000000 0.0185419451 0.0140233916 0.0301150549 0.0078391168 0.3695990000 244097011 0 1779458048 0.0209316015 0.2704363167 2.6234784126 407 16.2400000000 0.0178072043 0.0140326884 0.0301150549 0.0078304360 0.2599600000 246844977 0 1776525312 0.0267214179 0.2718015015 2.6246075630 408 16.2800000000 0.0189651847 0.0140447779 0.0301150549 0.0078313866 0.3273180000 246462410 0 1772683264 0.0319688916 0.2725464702 2.6286690235 409 16.3200000000 0.0191117823 0.0140571666 0.0301150549 0.0078339559 0.2321120000 247087012 0 1774080000 0.0395119786 0.2768144906 2.6312570572 410 16.3600000000 0.0178320929 0.0140663738 0.0301150549 0.0078244406 0.1963880000 246328155 0 1775427584 0.0450972319 0.2798599005 2.6341855526 411 16.3999999990 0.0191022679 0.0140786265 0.0301150549 0.0078173366 0.4987120000 246257524 0 1771593728 0.0491237640 0.2804509997 2.6363880634 412 16.4400000000 0.0190990008 0.0140908119 0.0301150549 0.0078355144 0.2330540000 241564856 0 1773228032 0.0532387495 0.2785937786 2.6433641911 413 16.4800000000 0.0189315304 0.0141025328 0.0301150549 0.0078479364 0.4211770000 241560670 0 1769218048 0.0607546568 0.2799267173 2.6501553059 414 16.5200000000 0.0191553589 0.0141147377 0.0301150549 0.0078442992 0.3869350000 241563116 0 1771380736 0.0636844635 0.2776098847 2.6537685394 415 16.5599999990 0.0190240070 0.0141265672 0.0301150549 0.0078569379 0.3651360000 241574378 0 1772797952 0.0675442219 0.2728731334 2.6588094234 416 16.6000000000 0.0193573367 0.0141391412 0.0301150549 0.0079319738 0.3705490000 244536423 0 1782087680 0.0693373680 0.2713063955 2.6642498970 417 16.6400000000 0.0191602428 0.0141511822 0.0301150549 0.0079727656 0.2680920000 247204954 0 1784197120 0.0819386244 0.2746241987 2.6663441658 418 16.6800000000 0.0190157406 0.0141628199 0.0301150549 0.0079748997 0.3365560000 246800492 0 1782349824 0.0827215910 0.2709623873 2.6656408310 419 16.7199999990 0.0198993143 0.0141765108 0.0301150549 0.0080051012 0.2120960000 247191014 0 1784442880 0.0934714079 0.2759100497 2.6713764668 420 16.7600000000 0.0197660923 0.0141898194 0.0301150549 0.0079961655 0.1974200000 246658107 0 1786056704 0.1004723310 0.2783297598 2.6713161469 421 16.8000000000 0.0200065468 0.0142036358 0.0301150549 0.0080075666 0.4337980000 246588252 0 1783840768 0.1051083803 0.2755959630 2.6712973118 422 16.8400000000 0.0205933787 0.0142187774 0.0301150549 0.0080109888 0.2544080000 241917576 0 1785630720 0.1098570824 0.2652589381 2.6759147644 423 16.8799999990 0.0201583058 0.0142328188 0.0301150549 0.0080067930 0.3655580000 241921458 0 1775751168 0.1160248518 0.2655698955 2.6744403839 424 16.9200000000 0.0184022728 0.0142426524 0.0301150549 0.0079980196 0.3491490000 241923152 0 1777713152 0.1232976913 0.2609742880 2.6718287468 425 16.9600000000 0.0205920730 0.0142575923 0.0301150549 0.0079955481 0.3439590000 241943246 0 1779548160 0.1312603951 0.2633420527 2.6709210873 426 17.0000000000 0.0206979644 0.0142727105 0.0301150549 0.0079873424 0.3683660000 244855175 0 1785389056 0.1408216953 0.2621042728 2.6710150242 427 17.0400000000 0.0227937214 0.0142926660 0.0301150549 0.0079853882 0.2686810000 247463526 0 1777254400 0.1496351957 0.2586847544 2.6687288284 428 17.0800000000 0.0197333694 0.0143053779 0.0301150549 0.0079775168 0.3096430000 247082994 0 1774084096 0.1554539204 0.2546578348 2.6628830433 429 17.1200000000 0.0214598626 0.0143220551 0.0301150549 0.0079706821 0.2106590000 247800574 0 1775419392 0.1665592194 0.2562274635 2.6620504856 430 17.1600000000 0.0184571818 0.0143316716 0.0301150549 0.0079657888 0.1840300000 246941851 0 1777856512 0.1739441156 0.2488079369 2.6535539627 431 17.2000000000 0.0254576113 0.0143574859 0.0301150549 0.0079686924 0.4167130000 246870396 0 1779036160 0.1889793873 0.2551417351 2.6517972946 432 17.2400000000 0.0290977415 0.0143916069 0.0301150549 0.0079648472 0.3221850000 242289064 0 1776095232 0.2038581371 0.2564162612 2.6490244865 433 17.2800000000 0.0304668490 0.0144287321 0.0304668490 0.0079571639 0.4120280000 242361858 0 1771159552 0.2169998884 0.2542133331 2.6454746723 434 17.3200000000 0.0275356341 0.0144589324 0.0304668490 0.0079486865 0.3954630000 242363564 0 1773043712 0.2254695892 0.2480504066 2.6347472668 435 17.3600000000 0.0272161607 0.0144882593 0.0304668490 0.0079601515 0.3703970000 242518694 0 1775177728 0.2383749485 0.2483510226 2.6279313564 436 17.4000000000 0.0304557066 0.0145248819 0.0304668490 0.0079596357 0.3701440000 244692035 0 1780105216 0.2551882267 0.2531754971 2.6242423058 437 17.4400000000 0.0249907374 0.0145488312 0.0304668490 0.0079531326 0.3175900000 248030917 0 1783312384 0.2694391012 0.2554897368 2.6117877960 438 17.4800000000 0.0279140733 0.0145793455 0.0304668490 0.0080670990 0.2700040000 247694431 0 1781592064 0.2848782539 0.2593676150 2.6049308777 439 17.5200000000 0.0240856186 0.0146009999 0.0304668490 0.0081811614 0.2725240000 247838285 0 1782988800 0.2894597054 0.2508230805 2.5922782421 440 17.5600000000 0.0276119001 0.0146305701 0.0304668490 0.0082182777 0.2126470000 247449647 0 1784995840 0.2967180014 0.2437326461 2.5870869160 441 17.6000000000 0.0326854214 0.0146715108 0.0326854214 0.0082175702 0.4870260000 247469356 0 1783304192 0.3111205101 0.2419591695 2.5796670914 442 17.6400000000 0.0329574645 0.0147128817 0.0329574645 0.0082656428 0.2828310000 242688428 0 1783222272 0.3205134869 0.2405513525 2.5747132301 443 17.6800000000 0.0313048474 0.0147503354 0.0329574645 0.0082885897 0.3790160000 242741614 0 1779068928 0.3430041671 0.2440963089 2.5562405586 444 17.7200000000 0.0307757277 0.0147864286 0.0329574645 0.0082852127 0.3544350000 242743260 0 1781063680 0.3507914543 0.2419518828 2.5460286140 445 17.7600000000 0.0328618549 0.0148270475 0.0329574645 0.0082825064 0.3406020000 242746146 0 1782054912 0.3626162410 0.2398535609 2.5398781300 446 17.8000000000 0.0324565917 0.0148665757 0.0329574645 0.0082737912 0.3434580000 244686379 0 1786601472 0.3731367588 0.2413185388 2.5293200016 447 17.8400000000 0.0331232324 0.0149074183 0.0331232324 0.0082700463 0.2885990000 247230389 0 1783369728 0.3821039796 0.2393573523 2.5214877129 448 17.8800000000 0.0318009891 0.0149451272 0.0331232324 0.0082612920 0.2545740000 247190717 0 1776697344 0.3887982965 0.2360316962 2.5137073994 449 17.9200000000 0.0324503295 0.0149841142 0.0331232324 0.0082522148 0.2265010000 247199106 0 1778348032 0.3963422179 0.2346780151 2.5059936047 450 17.9600000000 0.0328758061 0.0150238736 0.0331232324 0.0082444842 0.1878430000 247271531 0 1779953664 0.4051260948 0.2307794541 2.5003380775 451 18.0000000000 0.0309621487 0.0150592134 0.0331232324 0.0082480698 0.4012770000 247200844 0 1781649408 0.4148319364 0.2272123545 2.4946928024 452 18.0400000000 0.0298584308 0.0150919551 0.0331232324 0.0082424613 0.3216560000 243141368 0 1774821376 0.4212122560 0.2259935737 2.4880635738 453 18.0800000000 0.0301171262 0.0151251232 0.0331232324 0.0082395097 0.3277120000 243087138 0 1776324608 0.4324445724 0.2270240039 2.4780826569 454 18.1200000000 0.0299996529 0.0151578865 0.0331232324 0.0082379074 0.3039280000 243246416 0 1778053120 0.4425295591 0.2248494625 2.4736471176 455 18.1600000000 0.0324437171 0.0151958773 0.0331232324 0.0082296941 0.3059000000 245533595 0 1785192448 0.4545720220 0.2236954570 2.4714293480 456 18.2000000000 0.0298357811 0.0152279824 0.0331232324 0.0082238751 0.2039480000 247544076 0 1782738944 0.4608972073 0.2196661681 2.4626350403 457 18.2400000000 0.0304105617 0.0152612046 0.0331232324 0.0082248055 0.2223600000 246994580 0 1775611904 0.4737653732 0.2155485451 2.4587833881 458 18.2800000000 0.0290803108 0.0152913774 0.0331232324 0.0082395650 0.2025340000 247207675 0 1773326336 0.4801430106 0.2168492675 2.4552302361 459 18.3200000000 0.0281118248 0.0153193086 0.0331232324 0.0082419647 0.4045520000 247137772 0 1774792704 0.4933299422 0.2235816866 2.4434564114 460 18.3600000000 0.0274894703 0.0153457655 0.0331232324 0.0082428858 0.3069170000 243348380 0 1768824832 0.5003629327 0.2179854214 2.4406008720 461 18.4000000000 0.0263813976 0.0153697040 0.0331232324 0.0082375517 0.2906630000 243675466 0 1770618880 0.5127025843 0.2166823447 2.4352388382 462 18.4400000000 0.0280784704 0.0153972121 0.0331232324 0.0082295329 0.2954150000 243626712 0 1772023808 0.5211686492 0.2189932168 2.4305915833 463 18.4800000000 0.0280137081 0.0154244616 0.0331232324 0.0082258602 0.2849970000 243787814 0 1774030848 0.5253269672 0.2159689069 2.4243507385 464 18.5200000000 0.0290837884 0.0154538998 0.0331232324 0.0082265147 0.3118250000 246016967 0 1780760576 0.5417759418 0.2154910266 2.4202470779 465 18.5600000000 0.0270246882 0.0154787832 0.0331232324 0.0082258588 0.3528280000 244253903 0 1777246208 0.5450169444 0.2103063315 2.4153170586 466 18.6000000000 0.0249453932 0.0154990978 0.0331232324 0.0082408867 0.3033210000 244079576 0 1779036160 0.5588664412 0.2080071867 2.4136607647 467 18.6400000000 0.0256474279 0.0155208287 0.0331232324 0.0082373463 0.3017190000 244170921 0 1780928512 0.5702577829 0.2084785104 2.4092543125 468 18.6800000000 0.0256173480 0.0155424025 0.0331232324 0.0082368595 0.3042700000 244368292 0 1782919168 0.5793912411 0.2042450011 2.4095692635 469 18.7200000000 0.0252688546 0.0155631412 0.0331232324 0.0082615251 0.3185490000 244587514 0 1784696832 0.5884196758 0.2037491202 2.4058961868 470 18.7600000000 0.0257788282 0.0155848767 0.0331232324 0.0082784743 0.3027200000 244856792 0 1786474496 0.5921465158 0.1986397803 2.4070520401 471 18.8000000000 0.0244069826 0.0156036073 0.0331232324 0.0083289842 0.3180460000 245119226 0 1782349824 0.6032494307 0.1962524951 2.4037277699 472 18.8400000000 0.0257623773 0.0156251301 0.0331232324 0.0083689481 0.3026620000 245336728 0 1784266752 0.6093646288 0.1954607964 2.4013340473 473 18.8800000000 0.0254444685 0.0156458898 0.0331232324 0.0083897679 0.3249020000 245607910 0 1786101760 0.6268904805 0.1997312605 2.3947179317 474 18.9200000000 0.0260455962 0.0156678301 0.0331232324 0.0083860450 0.3342370000 245867684 0 1784991744 0.6308146715 0.1986687332 2.3870325089 475 18.9600000000 0.0264851227 0.0156906033 0.0331232324 0.0083832767 0.3120120000 245892810 0 1786761216 0.6375320554 0.1963401735 2.3853611946 476 19.0000000000 0.0249652416 0.0157100879 0.0331232324 0.0083907324 0.3537870000 246103528 0 1780326400 0.6465479732 0.1943269819 2.3818843365 477 19.0400000000 0.0244819187 0.0157284774 0.0331232324 0.0083889955 0.3262640000 246317610 0 1782476800 0.6516140699 0.1923291087 2.3732593060 478 19.0800000000 0.0247895680 0.0157474337 0.0331232324 0.0083819652 0.2998960000 246425756 0 1784197120 0.6649275422 0.1920195073 2.3772456646 479 19.1200000000 0.0245002210 0.0157657067 0.0331232324 0.0083751827 0.3271960000 246753606 0 1786228736 0.6740485430 0.1903452128 2.3753516674 480 19.1600000000 0.0282198172 0.0157916528 0.0331232324 0.0083767213 0.3172210000 246818832 0 1782194176 0.6801134944 0.1900591105 2.3782737255 481 19.2000000000 0.0274714846 0.0158159352 0.0331232324 0.0083967477 0.3203460000 247118050 0 1784508416 0.6866101027 0.1909114867 2.3704605103 482 19.2400000000 0.0272607841 0.0158396797 0.0331232324 0.0083889384 0.3378550000 247283560 0 1785974784 0.6978593469 0.1907670051 2.3729372025 483 19.2800000000 0.0268937238 0.0158625659 0.0331232324 0.0083835190 0.3324770000 247522018 0 1784266752 0.7098102570 0.1909280866 2.3689653873 484 19.3200000000 0.0283225328 0.0158883097 0.0331232324 0.0083779775 0.3412620000 247562432 0 1786437632 0.7128610015 0.1903036237 2.3667371273 485 19.3600000000 0.0350331813 0.0159277836 0.0350331813 0.0083750658 0.3316140000 247862174 0 1783373824 0.7137931585 0.1954378933 2.3643839359 486 19.4000000000 0.0362499058 0.0159695987 0.0362499058 0.0083769945 0.3506220000 248036164 0 1785122816 0.7225244641 0.2003239691 2.3606972694 487 19.4400000000 0.0356233343 0.0160099554 0.0362499058 0.0084216401 0.3645230000 248253406 0 1786863616 0.7305625081 0.1970589459 2.3595561981 488 19.4800000000 0.0346620120 0.0160481769 0.0362499058 0.0084194011 0.3596350000 248324016 0 1781608448 0.7318100333 0.1946495622 2.3512158394 489 19.5200000000 0.0348968096 0.0160867221 0.0362499058 0.0084148479 0.3425070000 248614770 0 1782837248 0.7345041037 0.1905917227 2.3510572910 490 19.5600000000 0.0368753821 0.0161291480 0.0368753821 0.0084069653 0.3787240000 248905356 0 1784762368 0.7363169193 0.1914244443 2.3411636353 491 19.6000000000 0.0381543897 0.0161740059 0.0381543897 0.0083988400 0.3876610000 249014950 0 1786257408 0.7423020005 0.1923296750 2.3371338844 492 19.6400000000 0.0380526185 0.0162184746 0.0381543897 0.0083908918 0.3950660000 249133720 0 1782312960 0.7418026924 0.1911385804 2.3268013000 493 19.6800000000 0.0355577543 0.0162577024 0.0381543897 0.0083868673 0.3566880000 249172550 0 1784119296 0.7432633638 0.1855894625 2.3159050941 494 19.7200000000 0.0384831280 0.0163026931 0.0384831280 0.0083951911 0.3744180000 249464472 0 1785585664 0.7475551367 0.1884869635 2.3073551655 495 19.7600000000 0.0381830968 0.0163468959 0.0384831280 0.0083879589 0.3773300000 249415190 0 1785106432 0.7468249798 0.1841652095 2.2973904610 496 19.8000000000 0.0343375206 0.0163831673 0.0384831280 0.0083873473 0.3956070000 249485744 0 1786671104 0.7470962405 0.1795374751 2.2908163071 497 19.8400000000 0.0359110460 0.0164224589 0.0384831280 0.0083795220 0.3810990000 249780842 0 1781014528 0.7479443550 0.1775401086 2.2830348015 498 19.8800000000 0.0358574651 0.0164614850 0.0384831280 0.0083748075 0.3878150000 249769972 0 1782931456 0.7496281266 0.1796935350 2.2706062794 499 19.9200000000 0.0387572087 0.0165061658 0.0387572087 0.0083678282 0.4015100000 249820026 0 1784250368 0.7492033243 0.1796785593 2.2671234608 500 19.9600000000 0.0348593555 0.0165428722 0.0387572087 0.0083608434 0.3779790000 249929064 0 1786277888 0.7487635612 0.1732686162 2.2551937103 501 20.0000000000 0.0383902080 0.0165864796 0.0387572087 0.0083545105 0.4279400000 252881941 0 1781698560 0.7472301126 0.1747813970 2.2437565327 502 20.0400000000 0.0448964424 0.0166428740 0.0448964424 0.0083493293 0.3465140000 257118968 0 1774858240 0.7436330914 0.1750873476 2.2378385067 503 20.0800000000 0.0477271378 0.0167046717 0.0477271378 0.0083444222 0.5411290000 256631568 0 1768112128 0.7484957576 0.1788129807 2.2312436104 504 20.1200000000 0.0586072803 0.0167878118 0.0586072803 0.0083466924 0.4488160000 249882504 0 1760215040 0.7378543615 0.1813323051 2.2232995033 505 20.1600000000 0.0588740595 0.0168711509 0.0588740595 0.0083421228 0.4276320000 249996558 0 1761865728 0.7355328798 0.1813791990 2.2103104591 506 20.2000000000 0.0574904755 0.0169514263 0.0588740595 0.0083383619 0.4009950000 250104580 0 1763491840 0.7372897863 0.1839324832 2.2009673119 507 20.2400000000 0.0594451055 0.0170352402 0.0594451055 0.0083361856 0.4143630000 252085345 0 1767428096 0.7363857031 0.1867955774 2.1894271374 508 20.2800000000 0.0536531731 0.0171073228 0.0594451055 0.0083390447 0.3337210000 255234820 0 1777012736 0.7323930264 0.1794522256 2.1790084839 509 20.3200000000 0.0583627447 0.0171883747 0.0594451055 0.0083351490 0.3316430000 254885388 0 1778278400 0.7333101034 0.1819298863 2.1705820560 510 20.3600000000 0.0495911948 0.0172519096 0.0594451055 0.0083486618 0.5947670000 255717366 0 1769926656 0.7526690960 0.1839583218 2.1504716873 511 20.4000000000 0.0503388718 0.0173166590 0.0594451055 0.0083419858 0.4944440000 250355622 0 1770913792 0.7514572740 0.1861382723 2.1389870644 512 20.4400000000 0.0457363985 0.0173721664 0.0594451055 0.0083476893 0.4629670000 250358340 0 1773293568 0.7537485361 0.1855386347 2.1225655079 513 20.4800000000 0.0490298718 0.0174338773 0.0594451055 0.0083610748 0.4410060000 252124981 0 1774657536 0.7524646521 0.1831474304 2.1146907806 514 20.5200000000 0.0504004471 0.0174980146 0.0594451055 0.0083545558 0.4472100000 255481751 0 1786474496 0.7516767979 0.1846583635 2.1033759117 515 20.5600000000 0.0501274541 0.0175613727 0.0594451055 0.0083528772 0.2469870000 256342082 0 1780817920 0.7583768964 0.1876092106 2.0904102325 516 20.6000000000 0.0477418341 0.0176198620 0.0594451055 0.0083672305 0.3004160000 255910668 0 1782874112 0.7654755712 0.1856028438 2.0784101486 517 20.6400000000 0.0460283272 0.0176748107 0.0594451055 0.0083622053 0.5481670000 255677852 0 1777901568 0.7595696449 0.1816022992 2.0759952068 518 20.6800000000 0.0477052331 0.0177327844 0.0594451055 0.0083569744 0.4207240000 250783696 0 1775489024 0.7772487998 0.1853514612 2.0564868450 519 20.7200000000 0.0461008176 0.0177874435 0.0594451055 0.0083491982 0.4373420000 250784202 0 1777278976 0.7690632343 0.1875636131 2.0577895641 520 20.7600000000 0.0452570170 0.0178402696 0.0594451055 0.0083505467 0.4704330000 252763307 0 1779109888 0.7634082437 0.1893143356 2.0568645000 521 20.8000000000 0.0426887907 0.0178879635 0.0594451055 0.0083593439 0.4305470000 256081093 0 1777532928 0.7616378069 0.1848131865 2.0483767986 522 20.8400000000 0.0433489308 0.0179367393 0.0594451055 0.0083594839 0.2436140000 256732056 0 1776648192 0.7592889667 0.1788416803 2.0441932678 523 20.8800000000 0.0396748930 0.0179783036 0.0594451055 0.0083579482 0.3085270000 256562310 0 1778601984 0.7578957081 0.1780603081 2.0490226746 524 20.9200000000 0.0434522480 0.0180269180 0.0594451055 0.0083533076 0.2312550000 256074015 0 1780367360 0.7698025107 0.1794912964 2.0302958488 525 20.9600000000 0.0438892767 0.0180761796 0.0594451055 0.0083455324 0.2193980000 256166309 0 1782157312 0.7698612213 0.1797149479 2.0247189999 526 21.0000000000 0.0350174196 0.0181083873 0.0594451055 0.0083553793 0.5713310000 256096634 0 1775857664 0.7841156125 0.1715869308 2.0022923946 527 21.0400000000 0.0386544503 0.0181473742 0.0594451055 0.0083538469 0.4471040000 251153538 0 1773002752 0.7831345797 0.1749790758 1.9948055744 528 21.0800000000 0.0364327356 0.0181820055 0.0594451055 0.0083467267 0.4524550000 251154812 0 1775222784 0.7859129906 0.1720182449 1.9896826744 529 21.1200000000 0.0429740958 0.0182288715 0.0594451055 0.0083445230 0.4448100000 253215989 0 1777332224 0.7920079231 0.1734943390 1.9718300104 530 21.1600000000 0.0384711362 0.0182670644 0.0594451055 0.0083484747 0.4566070000 256727499 0 1786327040 0.7961542606 0.1728195548 1.9667854309 531 21.2000000000 0.0393826254 0.0183068301 0.0594451055 0.0083409851 0.2492470000 257729806 0 1779814400 0.8022426963 0.1714446098 1.9532839060 532 21.2400000000 0.0390978903 0.0183459110 0.0594451055 0.0083350788 0.3488680000 257323931 0 1781477376 0.8002887964 0.1686894298 1.9452798367 533 21.2800000000 0.0433146842 0.0183927568 0.0594451055 0.0083306039 0.2323380000 256737997 0 1783173120 0.7980243564 0.1720433831 1.9399931431 534 21.3200000000 0.0440871231 0.0184408735 0.0594451055 0.0083248622 0.2183290000 256834067 0 1785077760 0.8033610582 0.1700054407 1.9261178970 535 21.3600000000 0.0410305001 0.0184830971 0.0594451055 0.0083269401 0.5118300000 256764348 0 1779306496 0.8136733174 0.1713789403 1.9088494778 536 21.4000000000 0.0381595790 0.0185198070 0.0594451055 0.0083214245 0.2376070000 251117120 0 1778954240 0.8135418296 0.1683129221 1.9046143293 537 21.4400000000 0.0417343415 0.0185630370 0.0594451055 0.0083149948 0.1906980000 251118310 0 1780862976 0.8179985881 0.1691953838 1.8883949518 538 21.4800000000 0.0377910137 0.0185987768 0.0594451055 0.0083126089 0.2213140000 251472924 0 1782620160 0.8247028589 0.1674991101 1.8773205280 539 21.5200000000 0.0398714729 0.0186382437 0.0594451055 0.0083051721 0.4429160000 251496810 0 1780862976 0.8219842911 0.1688753664 1.8703234196 540 21.5600000000 0.0363758467 0.0186710912 0.0594451055 0.0082998082 0.4614810000 251606180 0 1782640640 0.8247704506 0.1662805974 1.8560428619 541 21.6000000000 0.0406045988 0.0187116337 0.0594451055 0.0082946491 0.4588350000 253940849 0 1786953728 0.8225988746 0.1715613604 1.8473182917 542 21.6400000000 0.0410091244 0.0187527730 0.0594451055 0.0082923612 0.3856090000 257718328 0 1780981760 0.8262282610 0.1701940447 1.8346732855 543 21.6800000000 0.0402289815 0.0187923240 0.0594451055 0.0082850723 0.2781020000 257296540 0 1778749440 0.8260635138 0.1662741303 1.8298013210 544 21.7200000000 0.0402250104 0.0188317223 0.0594451055 0.0082846777 0.2760560000 257546672 0 1780305920 0.8261753917 0.1670389920 1.8191262484 545 21.7600000000 0.0443148203 0.0188784803 0.0594451055 0.0082841960 0.2407920000 257061885 0 1782001664 0.8240310550 0.1680497229 1.8078078032 546 21.8000000000 0.0367857255 0.0189112775 0.0594451055 0.0083132624 0.5703400000 257085650 0 1776242688 0.8396530151 0.1657448709 1.7950841188 547 21.8400000000 0.0317735337 0.0189347916 0.0594451055 0.0083178925 0.2280130000 251505446 0 1776488448 0.8481938839 0.1624764502 1.7809671164 548 21.8800000000 0.0338962264 0.0189620935 0.0594451055 0.0083150866 0.1986180000 251507128 0 1778307072 0.8386099935 0.1645431519 1.7792844772 549 21.9200000000 0.0335580669 0.0189886800 0.0594451055 0.0083093104 0.1960980000 251508526 0 1779646464 0.8429669142 0.1638137251 1.7721562386 550 21.9600000000 0.0322725810 0.0190128325 0.0594451055 0.0083023690 0.1979510000 251510268 0 1781313536 0.8436881304 0.1648440957 1.7666603327 551 22.0000000000 0.0350897461 0.0190420102 0.0594451055 0.0082971315 0.1961370000 251511274 0 1783091200 0.8443849683 0.1676223576 1.7593383789 552 22.0400000000 0.0323632434 0.0190661429 0.0594451055 0.0082902883 0.2036680000 251512756 0 1784741888 0.8446195126 0.1662324220 1.7496337891 553 22.0800000000 0.0343949348 0.0190938622 0.0594451055 0.0082892344 0.1947520000 251514238 0 1786392576 0.8451081514 0.1680957526 1.7486158609 554 22.1200000000 0.0364840440 0.0191252525 0.0594451055 0.0082826548 0.2256790000 251869204 0 1782968320 0.8455436826 0.1685725600 1.7408723831 555 22.1600000000 0.0355908014 0.0191549201 0.0594451055 0.0082757555 0.4583770000 251884854 0 1782374400 0.8469412327 0.1704926640 1.7329614162 556 22.2000000000 0.0342919081 0.0191821449 0.0594451055 0.0082718203 0.4472880000 251885808 0 1784139776 0.8485360146 0.1716281772 1.7231953144 557 22.2400000000 0.0379189290 0.0192157837 0.0594451055 0.0082817457 0.4399950000 253898001 0 1784119296 0.8429515362 0.1724583209 1.7211461067 558 22.2800000000 0.0359849557 0.0192458359 0.0594451055 0.0082767105 0.3526100000 257544179 0 1781661696 0.8435585499 0.1679382920 1.7161985636 559 22.3200000000 0.0349523425 0.0192739335 0.0594451055 0.0082716771 0.3300710000 257240832 0 1780359168 0.8435155153 0.1694743633 1.7105538845 560 22.3600000000 0.0363261439 0.0193043838 0.0594451055 0.0082653474 0.2822380000 257398832 0 1781338112 0.8436332941 0.1708865911 1.7059307098 561 22.4000000000 0.0394348949 0.0193402671 0.0594451055 0.0082600617 0.2414350000 256980021 0 1783091200 0.8439928293 0.1730923057 1.6987159252 562 22.4400000000 0.0339226164 0.0193662143 0.0594451055 0.0082627118 0.4980710000 256906926 0 1778167808 0.8477272391 0.1685705781 1.6918479204 563 22.4800000000 0.0373835489 0.0193982167 0.0594451055 0.0082597647 0.1990020000 251894394 0 1778434048 0.8460568190 0.1723466367 1.6838995218 564 22.5200000000 0.0402285755 0.0194351500 0.0594451055 0.0082582615 0.1966670000 251895960 0 1779544064 0.8465706110 0.1731204391 1.6794025898 565 22.5600000000 0.0370956957 0.0194664076 0.0594451055 0.0082519940 0.1947670000 251897074 0 1781723136 0.8487048149 0.1674525142 1.6679168940 566 22.6000000000 0.0393042304 0.0195014567 0.0594451055 0.0082480266 0.1932580000 251899016 0 1783209984 0.8519951105 0.1687506735 1.6598606110 567 22.6400000000 0.0411577150 0.0195396512 0.0594451055 0.0082421346 0.1933640000 251900298 0 1784877056 0.8550901413 0.1699849665 1.6527415514 568 22.6800000000 0.0408908688 0.0195772414 0.0594451055 0.0082349527 0.1886130000 251901780 0 1786527744 0.8577547073 0.1675405353 1.6452503204 569 22.7200000000 0.0416281633 0.0196159952 0.0594451055 0.0082319875 0.2006260000 251903070 0 1781084160 0.8551610708 0.1668122709 1.6366860867 570 22.7600000000 0.0376439057 0.0196476231 0.0594451055 0.0082302786 0.2160850000 252291752 0 1782341632 0.8532905579 0.1653783023 1.6251016855 571 22.8000000000 0.0373554863 0.0196786351 0.0594451055 0.0082259651 0.4707160000 252301186 0 1782198272 0.8548847437 0.1663182080 1.6158796549 572 22.8400000000 0.0361048728 0.0197073523 0.0594451055 0.0082222782 0.4385100000 252302920 0 1784123392 0.8528190255 0.1608876735 1.6067936420 573 22.8800000000 0.0366700888 0.0197369557 0.0594451055 0.0082172072 0.4314900000 254312305 0 1784549376 0.8536417484 0.1607598215 1.5981253386 574 22.9200000000 0.0375602692 0.0197680068 0.0594451055 0.0082101268 0.3944660000 258499513 0 1779855360 0.8509615660 0.1629826427 1.5923950672 575 22.9600000000 0.0355210975 0.0197954034 0.0594451055 0.0082056237 0.2823380000 257636816 0 1779187712 0.8485333920 0.1577985287 1.5838947296 576 23.0000000000 0.0368818343 0.0198250674 0.0594451055 0.0082010777 0.2725720000 257906515 0 1780953088 0.8461651802 0.1556243747 1.5768876076 577 23.0400000000 0.0359133221 0.0198529500 0.0594451055 0.0082018659 0.2302290000 257562361 0 1782280192 0.8443223238 0.1563010812 1.5667567253 578 23.0800000000 0.0432653688 0.0198934559 0.0594451055 0.0082077791 0.5171650000 257439046 0 1775775744 0.8522689342 0.1623286456 1.5519344807 579 23.1200000000 0.0386197567 0.0199257984 0.0594451055 0.0082042024 0.1967080000 252315294 0 1775841280 0.8531582355 0.1544593871 1.5420343876 580 23.1600000000 0.0427687801 0.0199651828 0.0594451055 0.0082041607 0.1887110000 252316960 0 1777491968 0.8488817811 0.1584347636 1.5346152782 581 23.2000000000 0.0412027575 0.0200017363 0.0594451055 0.0081996220 0.1900350000 252317974 0 1778724864 0.8503047228 0.1565666348 1.5244300365 582 23.2400000000 0.0421554446 0.0200398011 0.0594451055 0.0081940952 0.1919600000 252319908 0 1780899840 0.8480322361 0.1555865109 1.5150098801 583 23.2800000000 0.0408133827 0.0200754333 0.0594451055 0.0081883519 0.1875440000 252321106 0 1782550528 0.8478172421 0.1509025693 1.5040162802 584 23.3200000000 0.0426914282 0.0201141593 0.0594451055 0.0081886359 0.1876190000 252322672 0 1784328192 0.8459130526 0.1531511843 1.4923968315 585 23.3600000000 0.0391909443 0.0201467692 0.0594451055 0.0081831086 0.1908930000 252324346 0 1785978880 0.8427703381 0.1491910219 1.4827885628 586 23.4000000000 0.0360485949 0.0201739054 0.0594451055 0.0081779400 0.1950230000 252325728 0 1783955456 0.8426334858 0.1427332908 1.4721958637 587 23.4400000000 0.0367230996 0.0202020983 0.0594451055 0.0081797067 0.1830580000 252327202 0 1785589760 0.8411645293 0.1427713335 1.4632662535 588 23.4800000000 0.0374394730 0.0202314135 0.0594451055 0.0081842073 0.1885390000 252328324 0 1783197696 0.8393288255 0.1455266476 1.4356477261 589 23.5200000000 0.0337817706 0.0202544192 0.0594451055 0.0081827255 0.1833620000 252330458 0 1781776384 0.8394933939 0.1428127289 1.4260129929 590 23.5600000000 0.0356360078 0.0202804897 0.0594451055 0.0081778967 0.1792760000 252331464 0 1776074752 0.8359802365 0.1466279626 1.4138468504 591 23.6000000000 0.0362682380 0.0203075418 0.0594451055 0.0081859028 0.2077420000 252735758 0 1773158400 0.8368578553 0.1444193125 1.4035443068 592 23.6400000000 0.0337092020 0.0203301797 0.0594451055 0.0081813775 0.4819290000 252740356 0 1773355008 0.8338522911 0.1395947188 1.3928622007 593 23.6800000000 0.0313400179 0.0203487460 0.0594451055 0.0081760302 0.4424160000 252737638 0 1775861760 0.8325775862 0.1369847953 1.3802659512 594 23.7200000000 0.0328565761 0.0203698030 0.0594451055 0.0081732228 0.4405830000 254662975 0 1778225152 0.8275535107 0.1385891140 1.3711847067 595 23.7600000000 0.0293491520 0.0203848943 0.0594451055 0.0081730685 0.3412020000 257671949 0 1784369152 0.8280798793 0.1338155866 1.3595378399 596 23.8000000000 0.0335426815 0.0204069712 0.0594451055 0.0081786108 0.3357830000 257601790 0 1778786304 0.8224245310 0.1397818625 1.3489243984 597 23.8400000000 0.0317462087 0.0204259649 0.0594451055 0.0081784104 0.2503400000 257867677 0 1780903936 0.8242710829 0.1394189447 1.3339956999 598 23.8800000000 0.0343826003 0.0204493037 0.0594451055 0.0081737885 0.2158940000 257477663 0 1782796288 0.8252295256 0.1412817389 1.3196074963 599 23.9200000000 0.0302075762 0.0204655946 0.0594451055 0.0081687406 0.4982910000 257408100 0 1777102848 0.8179499507 0.1401546896 1.3098747730 600 23.9600000000 0.0289307591 0.0204797033 0.0594451055 0.0081656506 0.2004360000 252750136 0 1777332224 0.8151957989 0.1390573680 1.2986340523 601 24.0000000000 0.0327673554 0.0205001486 0.0594451055 0.0081609807 0.1867150000 252751534 0 1779089408 0.8119121194 0.1430540383 1.2895902395 602 24.0400000000 0.0301628094 0.0205161995 0.0594451055 0.0081554789 0.1880790000 252753024 0 1780752384 0.8081433773 0.1404876858 1.2783236504 603 24.0800000000 0.0298825540 0.0205317325 0.0594451055 0.0081487264 0.1828080000 252754498 0 1782530048 0.8049412966 0.1404012740 1.2700090408 604 24.1200000000 0.0317827798 0.0205503600 0.0594451055 0.0081442402 0.1912400000 252756364 0 1784180736 0.8030369282 0.1431153268 1.2583128214 605 24.1600000000 0.0293678045 0.0205649343 0.0594451055 0.0081419722 0.1807620000 252757578 0 1785831424 0.7990122437 0.1392963082 1.2542831898 606 24.2000000000 0.0275200214 0.0205764113 0.0594451055 0.0081394512 0.1873760000 252759160 0 1784573952 0.7993857861 0.1349360347 1.2420837879 607 24.2400000000 0.0283804983 0.0205892682 0.0594451055 0.0081338758 0.1840550000 252760466 0 1786339328 0.7955964804 0.1353480071 1.2316291332 608 24.2800000000 0.0266653374 0.0205992617 0.0594451055 0.0081311345 0.1847610000 252762240 0 1784725504 0.7961146832 0.1342904866 1.2212023735 609 24.3200000000 0.0281221829 0.0206116146 0.0594451055 0.0081248533 0.1855760000 252763562 0 1786359808 0.7939165831 0.1333042085 1.2102770805 610 24.3600000000 0.0264579058 0.0206211987 0.0594451055 0.0081193952 0.1832380000 252765128 0 1783812096 0.7933861017 0.1270171851 1.2032022476 611 24.4000000000 0.0258288812 0.0206297219 0.0594451055 0.0081176110 0.1839480000 252766634 0 1785597952 0.7888232470 0.1261390895 1.1931576729 612 24.4400000000 0.0281192772 0.0206419597 0.0594451055 0.0081152021 0.1870280000 252767948 0 1784094720 0.7852479219 0.1294371486 1.1822278500 613 24.4800000000 0.0306334030 0.0206582590 0.0594451055 0.0081098262 0.1819760000 252769630 0 1782181888 0.7847969532 0.1295294762 1.1751768589 614 24.5200000000 0.0278064683 0.0206699010 0.0594451055 0.0081040093 0.1841640000 252770844 0 1776308224 0.7816983461 0.1247367039 1.1609899998 615 24.5600000000 0.0278170817 0.0206815225 0.0594451055 0.0080974314 0.1805790000 252772582 0 1774292992 0.7809240818 0.1230733395 1.1537294388 616 24.6000000000 0.0291795153 0.0206953179 0.0594451055 0.0080914393 0.1840920000 252773864 0 1772007424 0.7801296711 0.1212144196 1.1444894075 617 24.6400000000 0.0301815160 0.0207106926 0.0594451055 0.0080936069 0.1802030000 252775438 0 1773404160 0.7749546766 0.1213611811 1.1339588165 618 24.6800000000 0.0302850772 0.0207261851 0.0594451055 0.0080943934 0.1809290000 252776836 0 1775321088 0.7758606076 0.1195243150 1.1191427708 619 24.7200000000 0.0308115054 0.0207424781 0.0594451055 0.0080920388 0.1882630000 252778426 0 1776816128 0.7786153555 0.1180850044 1.1040810347 620 24.7600000000 0.0315593444 0.0207599246 0.0594451055 0.0080957748 0.1744310000 252779748 0 1778720768 0.7692430019 0.1203839779 1.0996115208 621 24.8000000000 0.0316840634 0.0207775158 0.0594451055 0.0080911844 0.1750490000 252781598 0 1780371456 0.7701270580 0.1196513399 1.0886502266 622 24.8400000000 0.0306021795 0.0207933111 0.0594451055 0.0080854474 0.1764890000 252782712 0 1782276096 0.7693060040 0.1164042652 1.0773617029 623 24.8800000000 0.0275309142 0.0208041259 0.0594451055 0.0080817687 0.1775960000 252784302 0 1783926784 0.7659820318 0.1141945720 1.0657263994 624 24.9200000000 0.0270929839 0.0208142042 0.0594451055 0.0080762519 0.2182240000 253335980 0 1785704448 0.7647073269 0.1141507328 1.0541132689 625 24.9600000000 0.0297619011 0.0208285205 0.0594451055 0.0080722616 0.5647640000 253319114 0 1785257984 0.7640416026 0.1151120439 1.0410995483 626 25.0000000000 0.0294373948 0.0208422727 0.0594451055 0.0080673515 0.5025480000 253320240 0 1783939072 0.7595064640 0.1124737859 1.0369060040 627 25.0400000000 0.0275433585 0.0208529602 0.0594451055 0.0080644040 0.4696530000 254994029 0 1783193600 0.7573448420 0.1106118560 1.0245580673 628 25.0800000000 0.0303648952 0.0208681066 0.0594451055 0.0080601771 0.4179030000 257962615 0 1781653504 0.7555395365 0.1149554551 1.0137593746 629 25.1200000000 0.0292066820 0.0208813635 0.0594451055 0.0080566890 0.3983570000 257892452 0 1779556352 0.7518206835 0.1131975055 1.0082757473 630 25.1600000000 0.0293626245 0.0208948258 0.0594451055 0.0080521247 0.2544080000 257703739 0 1781424128 0.7457194328 0.1131076515 1.0017936230 631 25.2000000000 0.0201477222 0.0208936418 0.0594451055 0.0080531709 0.5594980000 257714248 0 1774284800 0.7347547412 0.1064279154 0.9900801182 632 25.2400000000 0.0246180240 0.0208995348 0.0594451055 0.0080498664 0.2137440000 253304388 0 1774444544 0.7310650945 0.1099660993 0.9839020371 633 25.2800000000 0.0257505421 0.0209071984 0.0594451055 0.0080445430 0.2003610000 253305726 0 1775824896 0.7261339426 0.1118716002 0.9743621349 634 25.3200000000 0.0254259314 0.0209143257 0.0594451055 0.0080428669 0.1979760000 253307020 0 1778003968 0.7230001092 0.1134814918 0.9641066790 635 25.3600000000 0.0262490511 0.0209227268 0.0594451055 0.0080418211 0.2349190000 253308618 0 1779507200 0.7185577154 0.1143082678 0.9580247402 636 25.4000000000 0.0215791836 0.0209237590 0.0594451055 0.0080496725 0.1953980000 253310200 0 1781157888 0.7149429321 0.1077874303 0.9500657320 637 25.4400000000 0.0225559026 0.0209263212 0.0594451055 0.0080436874 0.1943680000 253311714 0 1782935552 0.7101967335 0.1091572344 0.9428864121 638 25.4800000000 0.0210360549 0.0209264932 0.0594451055 0.0080393716 0.1942430000 253313420 0 1784696832 0.7066935897 0.1062471271 0.9330557585 639 25.5200000000 0.0272912402 0.0209364537 0.0594451055 0.0080387913 0.1903390000 253314550 0 1786363904 0.7015259266 0.1100128293 0.9305692911 640 25.5600000000 0.0210119281 0.0209365716 0.0594451055 0.0080365720 0.1925850000 253315980 0 1783848960 0.6973074675 0.1022490188 0.9249892235 641 25.6000000000 0.0249891374 0.0209428939 0.0594451055 0.0080354147 0.1892460000 253317678 0 1786003456 0.6903352737 0.1050903946 0.9189701080 642 25.6400000000 0.0270936880 0.0209524746 0.0594451055 0.0080340485 0.1908310000 253319076 0 1783865344 0.6879313588 0.1065935567 0.9105688930 643 25.6800000000 0.0274446104 0.0209625712 0.0594451055 0.0080287666 0.1936170000 253320794 0 1781936128 0.6816964149 0.1046969146 0.9076660872 644 25.7200000000 0.0281129181 0.0209736742 0.0594451055 0.0080265559 0.1879330000 253322148 0 1783701504 0.6772332191 0.1049965471 0.8984717131 645 25.7600000000 0.0286320988 0.0209855478 0.0594451055 0.0080314157 0.1969730000 253323746 0 1785475072 0.6683191061 0.1013869792 0.9009133577 646 25.8000000000 0.0306489747 0.0210005066 0.0594451055 0.0080333346 0.1903510000 253325544 0 1786626048 0.6653734446 0.1038338840 0.8900736570 647 25.8400000000 0.0319214873 0.0210173860 0.0594451055 0.0080381199 0.1909700000 253326830 0 1782464512 0.6533520222 0.1033333838 0.8922142982 648 25.8800000000 0.0315828063 0.0210336907 0.0594451055 0.0080388187 0.1862470000 253328452 0 1778237440 0.6486471295 0.1017820388 0.8894384503 649 25.9200000000 0.0346997343 0.0210547478 0.0594451055 0.0080403464 0.1938120000 253330150 0 1775968256 0.6444163918 0.1047946736 0.8758900762 650 25.9600000000 0.0244820099 0.0210600205 0.0594451055 0.0080568474 0.1905710000 253331496 0 1777348608 0.6284974217 0.0836646557 0.8764741421 651 26.0000000000 0.0218178611 0.0210611846 0.0594451055 0.0080690840 0.1886520000 253332942 0 1779638272 0.6127161980 0.0836154893 0.8608419895 652 26.0400000000 0.0319585837 0.0210778984 0.0594451055 0.0080851647 0.1819090000 253334504 0 1781030912 0.5992175341 0.0905816704 0.8647689819 653 26.0800000000 0.0251535233 0.0210841398 0.0594451055 0.0080986009 0.1836130000 253335834 0 1782689792 0.5913916230 0.0864191055 0.8590228558 654 26.1200000000 0.0316326953 0.0211002691 0.0594451055 0.0080997630 0.1839090000 253337440 0 1784713216 0.5818083882 0.0977781937 0.8464787602 655 26.1600000000 0.0246967804 0.0211057599 0.0594451055 0.0081152940 0.1849250000 253339230 0 1786494976 0.5735966563 0.0864894316 0.8451387286 656 26.2000000000 0.0274529122 0.0211154355 0.0594451055 0.0081125540 0.1857880000 253340668 0 1784750080 0.5623322725 0.0867034048 0.8464590311 657 26.2400000000 0.0287848338 0.0211271088 0.0594451055 0.0081099208 0.1850510000 253342198 0 1786511360 0.5517779589 0.0878605843 0.8438875079 658 26.2800000000 0.0205224603 0.0211261899 0.0594451055 0.0081157990 0.1857310000 253343588 0 1784733696 0.5401830673 0.0828368738 0.8340367079 659 26.3200000000 0.0364718884 0.0211494763 0.0594451055 0.0081768197 0.1858190000 253345154 0 1786384384 0.5262680650 0.1028363332 0.8328135014 660 26.3600000000 0.0296735577 0.0211623915 0.0594451055 0.0081983583 0.2226980000 253346728 0 1784352768 0.5161242485 0.0918834135 0.8351369500 661 26.4000000000 0.0437240675 0.0211965242 0.0594451055 0.0082240202 0.1859020000 253348210 0 1786130432 0.5020928979 0.1075596586 0.8372467160 662 26.4400000000 0.0212246925 0.0211965667 0.0594451055 0.0083194241 0.1856900000 253350084 0 1784623104 0.4940117002 0.0946004689 0.8198353052 663 26.4800000000 0.0283748135 0.0212073936 0.0594451055 0.0083172165 0.1858960000 253351198 0 1786273792 0.4815141559 0.1031306386 0.8134794831 664 26.5200000000 0.0318184905 0.0212233742 0.0594451055 0.0083304669 0.1809780000 253352672 0 1783967744 0.4705571234 0.1016431823 0.8135150671 665 26.5600000000 0.0308073293 0.0212377862 0.0594451055 0.0083284475 0.1884370000 253354622 0 1785876480 0.4601456225 0.0994851738 0.8133970499 666 26.6000000000 0.0287389867 0.0212490492 0.0594451055 0.0083413874 0.2208820000 253910416 0 1783717888 0.4503145814 0.1040555835 0.7976498008 667 26.6400000000 0.0306969117 0.0212632139 0.0594451055 0.0083401747 0.6045460000 253882858 0 1782652928 0.4396468401 0.1089923978 0.7955606580 668 26.6800000000 0.0278320108 0.0212730475 0.0594451055 0.0083729794 0.5062870000 253896844 0 1784877056 0.4291822016 0.1096414775 0.7953309417 669 26.7200000000 0.0331192873 0.0212907549 0.0594451055 0.0083933967 0.4031600000 257272673 0 1781370880 0.4181981087 0.1164818555 0.7920958400 670 26.7600000000 0.0296449121 0.0213032237 0.0594451055 0.0084328426 0.3272920000 257205074 0 1776771072 0.4077824056 0.1124463528 0.7896396518 671 26.8000000000 0.0217359494 0.0213038686 0.0594451055 0.0085491802 0.4752370000 257059892 0 1776828416 0.4058926702 0.1012525186 0.7681670189 672 26.8400000000 0.0211795196 0.0213036836 0.0594451055 0.0085602595 0.2150550000 253890220 0 1777238016 0.3961352110 0.0968906134 0.7579141855 673 26.8800000000 0.0229077376 0.0213060670 0.0594451055 0.0085564292 0.2186060000 253891634 0 1778659328 0.3877414465 0.1020271704 0.7557852268 674 26.9200000000 0.0184744392 0.0213018658 0.0594451055 0.0085539135 0.2181090000 253893172 0 1780645888 0.3778510690 0.1024466306 0.7579771280 675 26.9600000000 0.0195423514 0.0212992591 0.0594451055 0.0085533335 0.2144870000 253894478 0 1782423552 0.3699331582 0.1012327597 0.7505401373 676 27.0000000000 0.0193852540 0.0212964278 0.0594451055 0.0085489443 0.2152000000 253895884 0 1783697408 0.3592710197 0.1080703959 0.7489658594 677 27.0400000000 0.0194149632 0.0212936486 0.0594451055 0.0085624361 0.2094690000 253897190 0 1785470976 0.3502810001 0.1080879122 0.7442573905 678 27.0800000000 0.0192265175 0.0212905998 0.0594451055 0.0085878281 0.2072550000 253898696 0 1783586816 0.3446025252 0.1064743996 0.7403107285 679 27.1200000000 0.0164002832 0.0212833975 0.0594451055 0.0085992778 0.2089140000 253900546 0 1782419456 0.3344841301 0.1068528816 0.7385026813 680 27.1600000000 0.0147499945 0.0212737896 0.0594451055 0.0086014420 0.2023580000 253901768 0 1784225792 0.3264796734 0.1060040817 0.7352540493 681 27.2000000000 0.0160477739 0.0212661156 0.0594451055 0.0085952173 0.2035240000 253903182 0 1785978880 0.3185105920 0.1086729988 0.7308617234 682 27.2400000000 0.0109118652 0.0212509334 0.0594451055 0.0085917669 0.2081140000 253904932 0 1784238080 0.3099427819 0.1095369831 0.7317863703 683 27.2800000000 0.0175421033 0.0212455032 0.0594451055 0.0085917797 0.2023550000 253906222 0 1785978880 0.3026557565 0.1134392470 0.7201598287 684 27.3200000000 0.0151447281 0.0212365839 0.0594451055 0.0085978475 0.2080970000 253907704 0 1784344576 0.2937355936 0.1151740626 0.7186442614 685 27.3600000000 0.0180676337 0.0212319577 0.0594451055 0.0085932572 0.2020190000 253909178 0 1785860096 0.2864003181 0.1189327165 0.7112980485 686 27.4000000000 0.0131100770 0.0212201182 0.0594451055 0.0085958411 0.2066640000 253910684 0 1784238080 0.2776330709 0.1221292838 0.7123343349 687 27.4400000000 0.0191893689 0.0212171623 0.0594451055 0.0086080383 0.2012880000 253911982 0 1785724928 0.2692386508 0.1241037771 0.6978425384 688 27.4800000000 0.0139053855 0.0212065347 0.0594451055 0.0086340085 0.2003470000 253913664 0 1787150336 0.2593782842 0.1244699061 0.6973563433 689 27.5200000000 0.0123957507 0.0211937469 0.0594451055 0.0086435068 0.2007970000 253915070 0 1781932032 0.2523121238 0.1258083731 0.6940500736 690 27.5600000000 0.0154948561 0.0211854876 0.0594451055 0.0086393251 0.2028170000 253916768 0 1783713792 0.2442499697 0.1295905262 0.6846019030 691 27.6000000000 0.0177828111 0.0211805634 0.0594451055 0.0086455846 0.1956980000 253918474 0 1785090048 0.2363640666 0.1310040802 0.6749601364 692 27.6400000000 0.0140816448 0.0211703048 0.0594451055 0.0086626711 0.2006140000 253920064 0 1786740736 0.2277772278 0.1389930397 0.6756996512 693 27.6800000000 0.0145555260 0.0211607597 0.0594451055 0.0086915311 0.1967880000 253921094 0 1781805056 0.2188906074 0.1373727471 0.6655678749 694 27.7200000000 0.0151932733 0.0211521610 0.0594451055 0.0087006963 0.1945480000 253922852 0 1783586816 0.2125641257 0.1411132365 0.6612256765 695 27.7600000000 0.0127709247 0.0211401016 0.0594451055 0.0087034664 0.1965900000 253924158 0 1784836096 0.2046107501 0.1376297772 0.6541440487 696 27.8000000000 0.0145442877 0.0211306249 0.0594451055 0.0086992391 0.1985650000 253925888 0 1786613760 0.1961322725 0.1395384073 0.6432591081 697 27.8400000000 0.0112081263 0.0211163889 0.0594451055 0.0087054862 0.1968000000 253927118 0 1781571584 0.1895081103 0.1391724944 0.6392123103 698 27.8800000000 0.0175418854 0.0211112678 0.0594451055 0.0087019368 0.1921630000 253928656 0 1783222272 0.1795300543 0.1474666744 0.6262233853 699 27.9200000000 0.0142881675 0.0211015066 0.0594451055 0.0087221189 0.1955010000 253930494 0 1784582144 0.1710303724 0.1499986202 0.6231328845 700 27.9600000000 0.0207977183 0.0211010726 0.0594451055 0.0087290854 0.1994470000 253931624 0 1786232832 0.1631249189 0.1556377411 0.6101649404 701 28.0000000000 0.0163442828 0.0210942869 0.0594451055 0.0087798828 0.1918290000 253933322 0 1783480320 0.1558549404 0.1517592967 0.6071264744 702 28.0400000000 0.0146114295 0.0210850521 0.0594451055 0.0087867587 0.2587850000 254469364 0 1777741824 0.1482170671 0.1567035466 0.6046527624 703 28.0800000000 0.0130822649 0.0210736683 0.0594451055 0.0087993415 0.5776360000 254436770 0 1774710784 0.1420451701 0.1559514254 0.6016675234 704 28.1200000000 0.0146619678 0.0210645608 0.0594451055 0.0087995107 0.5051170000 254542846 0 1776455680 0.1337478161 0.1640961766 0.5966164470 705 28.1600000000 0.0140538439 0.0210546165 0.0594451055 0.0088178271 0.4031090000 257836363 0 1785933824 0.1259217411 0.1687335372 0.5942029953 706 28.2000000000 0.0138770510 0.0210444500 0.0594451055 0.0088389479 0.3226970000 257767482 0 1783705600 0.1199841946 0.1683937758 0.5920293331 707 28.2400000000 0.0263634119 0.0210519732 0.0594451055 0.0088965701 0.4521170000 257625868 0 1780969472 0.1098105013 0.1678686440 0.5688995123 708 28.2800000000 0.0261279605 0.0210591427 0.0594451055 0.0088937798 0.2184230000 254449104 0 1780711424 0.1029693037 0.1718388796 0.5665433407 709 28.3200000000 0.0268306248 0.0210672830 0.0594451055 0.0088880449 0.2146280000 254450350 0 1782611968 0.0963261276 0.1719831377 0.5629705787 710 28.3600000000 0.0243678559 0.0210719317 0.0594451055 0.0088828142 0.2088390000 254452316 0 1784639488 0.0915332139 0.1691672057 0.5624424815 711 28.4000000000 0.0255070962 0.0210781696 0.0594451055 0.0088768637 0.2080900000 254453430 0 1786163200 0.0819534659 0.1774455011 0.5588092804 712 28.4400000000 0.0274590645 0.0210871316 0.0594451055 0.0088707838 0.2062910000 254455004 0 1784913920 0.0732792914 0.1834632754 0.5544475317 713 28.4800000000 0.0250555817 0.0210926974 0.0594451055 0.0088655370 0.2002660000 254456670 0 1786564608 0.0686477870 0.1751500219 0.5556930900 714 28.5200000000 0.0240527652 0.0210968432 0.0594451055 0.0088876480 0.2011670000 254457976 0 1784295424 0.0605133027 0.1841371953 0.5563302636 715 28.5600000000 0.0263285507 0.0211041603 0.0594451055 0.0088825440 0.2029800000 254459474 0 1785802752 0.0513723642 0.1899603009 0.5532142520 716 28.6000000000 0.0270132199 0.0211124131 0.0594451055 0.0088787706 0.1994340000 254461096 0 1784401920 0.0442272276 0.1936583370 0.5545591116 717 28.6400000000 0.0295022652 0.0211241145 0.0594451055 0.0088731197 0.1947860000 254462410 0 1786056704 0.0369750708 0.1979647875 0.5548173785 718 28.6800000000 0.0266832989 0.0211318571 0.0594451055 0.0088739334 0.1973040000 254463916 0 1783873536 0.0310051739 0.1985835284 0.5605382919 719 28.7200000000 0.0270469245 0.0211400839 0.0594451055 0.0088697449 0.1965950000 254465598 0 1785786368 0.0234362185 0.2035191059 0.5623920560 720 28.7600000000 0.0281415507 0.0211498081 0.0594451055 0.0088676494 0.2234870000 254466944 0 1784025088 0.0155699253 0.2049181610 0.5646731853 721 28.8000000000 0.0272470098 0.0211582647 0.0594451055 0.0088626706 0.1879170000 254467638 0 1781493760 0.0100200474 0.2074461281 0.5709989071 722 28.8400000000 0.0265520606 0.0211657353 0.0594451055 0.0088569521 0.1891960000 254468736 0 1780338688 0.0031552315 0.2087212056 0.5763089657 723 28.8800000000 0.0280349571 0.0211752363 0.0594451055 0.0088517379 0.1808490000 254470510 0 1781481472 -0.0059438944 0.2110343874 0.5796236992 724 28.9200000000 0.0273473710 0.0211837614 0.0594451055 0.0088460707 0.2202350000 255009636 0 1783242752 -0.0157783926 0.2142758071 0.5851957202 725 28.9600000000 0.0273519959 0.0211922693 0.0594451055 0.0088435399 0.5473000000 254983518 0 1780461568 -0.0237437785 0.2161020637 0.5909492373 726 29.0000000000 0.0275105406 0.0212009721 0.0594451055 0.0088449361 0.5032200000 256646799 0 1784385536 -0.0315875709 0.2185098231 0.5970566273 727 29.0400000000 0.0280396938 0.0212103789 0.0594451055 0.0088456318 0.3489570000 258381729 0 1780350976 -0.0403953195 0.2214393020 0.6027066708 728 29.0800000000 0.0260743145 0.0212170601 0.0594451055 0.0088557533 0.2987980000 258345039 0 1778294784 -0.0488731861 0.2208907306 0.6110316515 729 29.1200000000 0.0359540507 0.0212372755 0.0594451055 0.0089750651 0.4411830000 258274820 0 1777184768 -0.0670450330 0.2483603805 0.6191602349 730 29.1600000000 0.0367438123 0.0212585173 0.0594451055 0.0089701614 0.2061390000 254989464 0 1777500160 -0.0747674406 0.2505273521 0.6259019375 731 29.2000000000 0.0354203656 0.0212778906 0.0594451055 0.0089658253 0.1933930000 254990886 0 1779896320 -0.0849176049 0.2518167794 0.6326935291 732 29.2400000000 0.0366037823 0.0212988276 0.0594451055 0.0089598421 0.1913520000 254990504 0 1781563392 -0.0956701934 0.2570548058 0.6385772228 733 29.2800000000 0.0386230499 0.0213224623 0.0594451055 0.0089544758 0.1881360000 254992434 0 1783341056 -0.1044173837 0.2630201280 0.6468393803 734 29.3200000000 0.0365842395 0.0213432549 0.0594451055 0.0089486037 0.1808570000 254994568 0 1785008128 -0.1113622189 0.2653976083 0.6577483416 735 29.3600000000 0.0370863862 0.0213646741 0.0594451055 0.0089444478 0.1778440000 254994838 0 1786769408 -0.1206541955 0.2692588270 0.6658419967 736 29.4000000000 0.0380210914 0.0213873051 0.0594451055 0.0089418774 0.1731700000 254996172 0 1782616064 -0.1273414791 0.2755292654 0.6763370037 737 29.4400000000 0.0395048074 0.0214118879 0.0594451055 0.0089373155 0.1708210000 254997106 0 1781182464 -0.1346262097 0.2799446583 0.6840524077 738 29.4800000000 0.0406581834 0.0214379669 0.0594451055 0.0089328998 0.1667060000 254997892 0 1782706176 -0.1452712417 0.2849574983 0.6923120022 739 29.5200000000 0.0386119485 0.0214612064 0.0594451055 0.0089531089 0.2010810000 255534714 0 1784119296 -0.1522071064 0.2853021920 0.7008908987 740 29.5600000000 0.0389493294 0.0214848390 0.0594451055 0.0089665780 0.5120650000 255499012 0 1782824960 -0.1589486301 0.2882899642 0.7093765736 741 29.6000000000 0.0389786549 0.0215084473 0.0594451055 0.0089854090 0.4283580000 257202549 0 1786388480 -0.1663366556 0.2927884459 0.7180663347 742 29.6400000000 0.0395194888 0.0215327210 0.0594451055 0.0089974392 0.2973010000 258826351 0 1782845440 -0.1725177765 0.2966125607 0.7263435125 743 29.6800000000 0.0378172621 0.0215546383 0.0594451055 0.0089979000 0.2652680000 258769453 0 1780498432 -0.1772331893 0.2961901426 0.7354414463 744 29.7200000000 0.0349994749 0.0215727093 0.0594451055 0.0089943427 0.4017380000 258742826 0 1775579136 -0.1810763478 0.2972207963 0.7466576695 745 29.7600000000 0.0355226211 0.0215914340 0.0594451055 0.0089920366 0.1726440000 255499690 0 1775632384 -0.1873720884 0.3001334071 0.7520618439 746 29.8000000000 0.0366982222 0.0216116844 0.0594451055 0.0089871042 0.1644570000 255497532 0 1777655808 -0.1918573976 0.3030840456 0.7579514980 747 29.8400000000 0.0357151330 0.0216305645 0.0594451055 0.0089816448 0.1633660000 255500982 0 1779286016 -0.1946978569 0.3051044047 0.7646464109 748 29.8800000000 0.0356597006 0.0216493200 0.0594451055 0.0089779549 0.1576810000 255502104 0 1780936704 -0.2008156180 0.3087336421 0.7704073191 749 29.9200000000 0.0362257175 0.0216687812 0.0594451055 0.0089727008 0.1562880000 255502486 0 1782587392 -0.2063828111 0.3122254908 0.7755630016 750 29.9600000000 0.0328431800 0.0216836804 0.0594451055 0.0089711147 0.1540150000 255502628 0 1784365056 -0.2105106115 0.3116349578 0.7817546725 751 30.0000000000 0.0348344482 0.0217011914 0.0594451055 0.0089662076 0.1528640000 255507222 0 1786269696 -0.2128452063 0.3158285618 0.7864036560 752 30.0400000000 0.0346572138 0.0217184201 0.0594451055 0.0089621132 0.1518260000 255508068 0 1784512512 -0.2170526981 0.3185294271 0.7909156680 753 30.0800000000 0.0349513367 0.0217359937 0.0594451055 0.0089599503 0.1523790000 255509314 0 1786142720 -0.2194580436 0.3204487562 0.7944481969 754 30.1200000000 0.0348839462 0.0217534313 0.0594451055 0.0089632087 0.1489220000 255509244 0 1783894016 -0.2232026160 0.3228338063 0.7986234426 755 30.1600000000 0.0341072045 0.0217697940 0.0594451055 0.0089709993 0.1505680000 255511646 0 1785528320 -0.2282651961 0.3236558139 0.8020740747 756 30.2000000000 0.0347209461 0.0217869251 0.0594451055 0.0089770445 0.1508320000 255516884 0 1783623680 -0.2323541939 0.3266201913 0.8048605323 757 30.2400000000 0.0353519619 0.0218048446 0.0594451055 0.0089773476 0.1487010000 255516866 0 1782095872 -0.2371160984 0.3297929764 0.8067945838 758 30.2800000000 0.0345376506 0.0218216425 0.0594451055 0.0089774279 0.1746990000 255948520 0 1780969472 -0.2425379455 0.3316650689 0.8120061159 759 30.3200000000 0.0350693204 0.0218390966 0.0594451055 0.0089890160 0.3935250000 255956794 0 1782763520 -0.2477427423 0.3349969089 0.8150885105 760 30.3600000000 0.0327786803 0.0218534908 0.0594451055 0.0090048328 0.2824800000 257779663 0 1782788096 -0.2541345358 0.3378311992 0.8193045855 761 30.4000000000 0.0368503742 0.0218731976 0.0594451055 0.0090028388 0.1884710000 257699257 0 1781239808 -0.2608036995 0.3453271985 0.8207355738 762 30.4400000000 0.0324458666 0.0218870725 0.0594451055 0.0090146940 0.2730150000 257620226 0 1779978240 -0.2665864527 0.3447169363 0.8248740435 763 30.4800000000 0.0355137475 0.0219049318 0.0594451055 0.0090100102 0.1982400000 255917694 0 1781014528 -0.2717651129 0.3511895239 0.8260509968 764 30.5200000000 0.0333079360 0.0219198572 0.0594451055 0.0090129840 0.1604600000 255923048 0 1782894592 -0.2802612484 0.3532749414 0.8293989897 765 30.5600000000 0.0338683873 0.0219354762 0.0594451055 0.0090085373 0.1566990000 255919646 0 1784815616 -0.2876012921 0.3576655984 0.8312833905 766 30.6000000000 0.0342761055 0.0219515867 0.0594451055 0.0090058142 0.1570550000 255921820 0 1785946112 -0.2951385975 0.3615542650 0.8334609270 767 30.6400000000 0.0349868424 0.0219685818 0.0594451055 0.0090025082 0.1553690000 255923650 0 1784688640 -0.3026132882 0.3663040996 0.8357148767 768 30.6800000000 0.0348866209 0.0219854022 0.0594451055 0.0090012772 0.1570070000 255923364 0 1786331136 -0.3118235469 0.3697789907 0.8371656537 769 30.7200000000 0.0351296216 0.0220024948 0.0594451055 0.0090002981 0.1539230000 255927170 0 1783820288 -0.3205217123 0.3743144274 0.8391278982 770 30.7600000000 0.0356162190 0.0220201750 0.0594451055 0.0089952935 0.1546650000 255927420 0 1782816768 -0.3283109665 0.3794693351 0.8422331214 771 30.8000000000 0.0348527841 0.0220368191 0.0594451055 0.0089926909 0.1473090000 255926710 0 1784946688 -0.3374059796 0.3817631304 0.8423813581 772 30.8400000000 0.0342649333 0.0220526586 0.0594451055 0.0089925225 0.1493470000 255928716 0 1786216448 -0.3478335142 0.3841381967 0.8441537619 773 30.8800000000 0.0358356275 0.0220704891 0.0594451055 0.0089875911 0.1507630000 255933430 0 1783967744 -0.3547191620 0.3889666498 0.8465210199 774 30.9200000000 0.0336026661 0.0220853885 0.0594451055 0.0089968089 0.1464650000 255933372 0 1785982976 -0.3640679419 0.3888602555 0.8481068611 775 30.9600000000 0.0350223258 0.0221020814 0.0594451055 0.0089975550 0.1464130000 255934542 0 1784434688 -0.3726313114 0.3918507397 0.8491844535 776 31.0000000000 0.0347315818 0.0221183565 0.0594451055 0.0090045851 0.1469090000 255936384 0 1786232832 -0.3806260824 0.3932302296 0.8505073786 777 31.0400000000 0.0354589447 0.0221355258 0.0594451055 0.0090088308 0.1774370000 256375682 0 1785475072 -0.3884334564 0.3974330425 0.8523731828 778 31.0800000000 0.0357699320 0.0221530508 0.0594451055 0.0090077566 0.3742230000 256381860 0 1786490880 -0.3970345855 0.4012566209 0.8536247015 779 31.1200000000 0.0347331837 0.0221691999 0.0594451055 0.0090055138 0.2819430000 257934885 0 1781317632 -0.4041239321 0.4023940861 0.8557357788 780 31.1600000000 0.0350215547 0.0221856772 0.0594451055 0.0090036021 0.2035360000 257919559 0 1780121600 -0.4117160141 0.4052983224 0.8571482897 781 31.2000000000 0.0384363309 0.0222064847 0.0594451055 0.0089992858 0.2533490000 257842480 0 1779875840 -0.4230978787 0.4124955237 0.8587381840 782 31.2400000000 0.0377893224 0.0222264116 0.0594451055 0.0089945005 0.1737930000 256341404 0 1780334592 -0.4283483326 0.4131673872 0.8607408404 783 31.2800000000 0.0380730778 0.0222466500 0.0594451055 0.0089891206 0.1566240000 256342050 0 1782009856 -0.4355636239 0.4150691628 0.8618785143 784 31.3200000000 0.0385132693 0.0222673983 0.0594451055 0.0089834815 0.1594730000 256344784 0 1783754752 -0.4429042637 0.4168982506 0.8631835580 785 31.3600000000 0.0388373435 0.0222885065 0.0594451055 0.0089786256 0.1601650000 256347470 0 1785802752 -0.4474853873 0.4178063571 0.8649929762 786 31.4000000000 0.0394154638 0.0223102965 0.0594451055 0.0089747691 0.1577320000 256350624 0 1786949632 -0.4534238279 0.4192524254 0.8662056923 787 31.4400000000 0.0386070609 0.0223310040 0.0594451055 0.0089699520 0.2078170000 256349898 0 1781264384 -0.4591533840 0.4201712906 0.8669759035 788 31.4800000000 0.0390530974 0.0223522249 0.0594451055 0.0089667309 0.1607500000 256352540 0 1782505472 -0.4650767446 0.4216458201 0.8684269190 789 31.5200000000 0.0395802744 0.0223740602 0.0594451055 0.0089635967 0.1595740000 256354790 0 1784287232 -0.4711448848 0.4223533869 0.8693724871 790 31.5600000000 0.0389242247 0.0223950098 0.0594451055 0.0089585293 0.1593540000 256354964 0 1786310656 -0.4760070443 0.4220346808 0.8714590073 791 31.6000000000 0.0388090797 0.0224157608 0.0594451055 0.0089529479 0.1522610000 256354338 0 1784446976 -0.4806923270 0.4218471646 0.8718644381 792 31.6400000000 0.0400764346 0.0224380596 0.0594451055 0.0089479322 0.1540200000 256358328 0 1786077184 -0.4838422537 0.4227340817 0.8734462261 793 31.6800000000 0.0407272168 0.0224611229 0.0594451055 0.0089436190 0.1597000000 256360654 0 1783664640 -0.4884075224 0.4228236675 0.8747100830 794 31.7200000000 0.0401790775 0.0224834377 0.0594451055 0.0089445056 0.1581210000 256361508 0 1782517760 -0.4912210703 0.4210494757 0.8761027455 795 31.7600000000 0.0403391346 0.0225058977 0.0594451055 0.0089490264 0.1598610000 256360246 0 1780629504 -0.4951107800 0.4200986326 0.8767685890 796 31.8000000000 0.0393785872 0.0225270945 0.0594451055 0.0089597653 0.1459310000 256357236 0 1782394880 -0.4982072115 0.4181128144 0.8787761331 797 31.8400000000 0.0389415212 0.0225476898 0.0594451055 0.0089742941 0.1488400000 256361854 0 1783652352 -0.5004272461 0.4167216122 0.8809601068 798 31.8800000000 0.0397847183 0.0225692901 0.0594451055 0.0089872104 0.1503870000 256362056 0 1785675776 -0.5042456388 0.4159750044 0.8812834620 799 31.9200000000 0.0408843867 0.0225922126 0.0594451055 0.0090012894 0.1461570000 256364842 0 1784045568 -0.5044575334 0.4150328040 0.8828988075 800 31.9600000000 0.0403262153 0.0226143801 0.0594451055 0.0090028220 0.1497190000 256367896 0 1782644736 -0.5077680349 0.4125303030 0.8840454817 801 32.0000000000 0.0407223031 0.0226369868 0.0594451055 0.0090142207 0.1501370000 256366418 0 1780502528 -0.5092133284 0.4115286767 0.8869801760 802 32.0400000000 0.0400282033 0.0226586716 0.0594451055 0.0090146847 0.1473790000 256370140 0 1782165504 -0.5125665665 0.4086225033 0.8879225850 803 32.0800000000 0.0406234898 0.0226810437 0.0594451055 0.0090260405 0.1452860000 256370458 0 1784152064 -0.5118838549 0.4088317156 0.8909283876 804 32.1199999990 0.0395638235 0.0227020422 0.0594451055 0.0090364744 0.1473640000 256374924 0 1785536512 -0.5124158263 0.4069886804 0.8934708834 805 32.1600000000 0.0404517613 0.0227240915 0.0594451055 0.0090510334 0.1445430000 256375302 0 1783664640 -0.5141290426 0.4062525034 0.8951702118 806 32.2000000000 0.0418850631 0.0227478644 0.0594451055 0.0090675689 0.1850240000 256775700 0 1780989952 -0.5146648288 0.4059911370 0.8965843320 807 32.2400000000 0.0424066521 0.0227722248 0.0594451055 0.0090812475 0.3720260000 256741678 0 1779724288 -0.5152326822 0.4033760428 0.8982580304 808 32.2800000000 0.0416456349 0.0227955829 0.0594451055 0.0090852012 0.3226430000 258503891 0 1785896960 -0.5172580481 0.4003381729 0.9005284309 809 32.3200000000 0.0416588001 0.0228188996 0.0594451055 0.0090888963 0.2226090000 258439980 0 1784098816 -0.5169684291 0.3967029750 0.9033217430 810 32.3600000000 0.0406230129 0.0228408800 0.0594451055 0.0090890933 0.2673730000 258350466 0 1785102336 -0.5198658705 0.3928869963 0.9036502838 811 32.4000000000 0.0400148928 0.0228620564 0.0594451055 0.0090856056 0.1607300000 256751490 0 1785790464 -0.5205850005 0.3885191083 0.9060479403 812 32.4399999990 0.0402904898 0.0228835200 0.0594451055 0.0090852754 0.1594400000 256752452 0 1784651776 -0.5203872323 0.3853888512 0.9088503122 813 32.4800000000 0.0401919708 0.0229048096 0.0594451055 0.0090839320 0.1557260000 256752886 0 1786437632 -0.5204634666 0.3827642202 0.9119657278 814 32.5200000000 0.0408367552 0.0229268390 0.0594451055 0.0090813651 0.1809290000 256755864 0 1784414208 -0.5217438340 0.3806569576 0.9145292640 815 32.5600000000 0.0409937687 0.0229490070 0.0594451055 0.0090794710 0.1528540000 256757862 0 1786449920 -0.5232266784 0.3780110478 0.9173524976 816 32.6000000000 0.0394547358 0.0229692346 0.0594451055 0.0090746063 0.1547760000 256760768 0 1784909824 -0.5222895145 0.3720338047 0.9210965633 817 32.6400000000 0.0400045477 0.0229900857 0.0594451055 0.0090717652 0.1523880000 256760702 0 1786687488 -0.5219233036 0.3692550063 0.9245796800 818 32.6800000000 0.0395334736 0.0230103099 0.0594451055 0.0090665459 0.1528690000 256764172 0 1781710848 -0.5237869620 0.3651042283 0.9275543690 819 32.7200000000 0.0389938802 0.0230298258 0.0594451055 0.0090617492 0.1494930000 256764574 0 1780731904 -0.5252152681 0.3628724813 0.9320027828 820 32.7599999990 0.0386095494 0.0230488255 0.0594451055 0.0090575537 0.1480240000 256766872 0 1782468608 -0.5266613364 0.3602290750 0.9363934994 821 32.7999999990 0.0379067622 0.0230669228 0.0594451055 0.0090581360 0.1432690000 256767834 0 1784127488 -0.5251759291 0.3577075303 0.9427842498 822 32.8400000000 0.0393848978 0.0230867744 0.0594451055 0.0090771438 0.1533160000 256770552 0 1786015744 -0.5266058445 0.3562165499 0.9459890723 823 32.8800000000 0.0392400585 0.0231064017 0.0594451055 0.0090862036 0.1473620000 256773102 0 1784799232 -0.5270520449 0.3545475006 0.9522080421 824 32.9200000000 0.0404397100 0.0231274373 0.0594451055 0.0090910762 0.1436610000 256773544 0 1786294272 -0.5273503661 0.3547993898 0.9576272368 825 32.9600000000 0.0398037843 0.0231476510 0.0594451055 0.0090999043 0.1461440000 256777414 0 1784164352 -0.5250351429 0.3512955904 0.9635207057 826 33.0000000000 0.0389299504 0.0231667579 0.0594451055 0.0091034728 0.1442080000 256776896 0 1786163200 -0.5267785192 0.3496344090 0.9704769850 827 33.0400000000 0.0392627381 0.0231862210 0.0594451055 0.0091185626 0.1460620000 256780098 0 1785057280 -0.5285788178 0.3471004367 0.9765274525 828 33.0800000000 0.0402925275 0.0232068808 0.0594451055 0.0091415007 0.1886340000 257273448 0 1786814464 -0.5285018682 0.3440654874 0.9811933041 829 33.1199999990 0.0401354767 0.0232273013 0.0594451055 0.0091580764 0.4293920000 257250066 0 1781202944 -0.5296099782 0.3409244120 0.9877483249 830 33.1600000000 0.0418006182 0.0232496788 0.0594451055 0.0091738274 0.3658190000 258251051 0 1784463360 -0.5306827426 0.3390209675 0.9925931692 831 33.2000000000 0.0425468758 0.0232729005 0.0594451055 0.0091910017 0.2928390000 259168808 0 1784713216 -0.5312199593 0.3350945413 0.9996966124 832 33.2400000000 0.0400547832 0.0232930710 0.0594451055 0.0091915370 0.3331980000 259078662 0 1782116352 -0.5324845910 0.3285876513 1.0064957142 833 33.2800000000 0.0399066918 0.0233130153 0.0594451055 0.0091929722 0.1841040000 257253642 0 1782235136 -0.5335650444 0.3249679804 1.0129070282 834 33.3200000000 0.0391191430 0.0233319675 0.0594451055 0.0091945078 0.1749120000 257254928 0 1783881728 -0.5344268084 0.3191334605 1.0195842981 835 33.3600000000 0.0401186831 0.0233520714 0.0594451055 0.0091994318 0.1753320000 257257154 0 1785532416 -0.5343035460 0.3178107440 1.0266416073 836 33.4000000000 0.0400542170 0.0233720500 0.0594451055 0.0092046939 0.1744030000 257258108 0 1783517184 -0.5363073349 0.3140629232 1.0326068401 837 33.4399999990 0.0412888713 0.0233934560 0.0594451055 0.0092188856 0.1738970000 257261438 0 1781899264 -0.5378277302 0.3125359416 1.0380609035 838 33.4800000000 0.0407982357 0.0234142254 0.0594451055 0.0092407670 0.1745010000 257264944 0 1776660480 -0.5380925536 0.3070995212 1.0438044071 839 33.5200000000 0.0403347835 0.0234343930 0.0594451055 0.0092625260 0.2080760000 257264926 0 1774772224 -0.5397877097 0.3044711053 1.0508011580 840 33.5600000000 0.0399234407 0.0234540228 0.0594451055 0.0092788017 0.1727610000 257267316 0 1776279552 -0.5417606831 0.3016712070 1.0556133986 841 33.6000000000 0.0409121960 0.0234747816 0.0594451055 0.0092818447 0.1759850000 257270770 0 1778085888 -0.5418321490 0.3007844388 1.0613166094 842 33.6400000000 0.0395230167 0.0234938413 0.0594451055 0.0092788370 0.1660130000 257265304 0 1779580928 -0.5421128273 0.2979076505 1.0687603951 843 33.6800000000 0.0415706038 0.0235152846 0.0594451055 0.0092787391 0.1636200000 257269362 0 1781112832 -0.5436645150 0.2958252728 1.0711728334 844 33.7200000000 0.0405925140 0.0235355183 0.0594451055 0.0092816791 0.1645430000 257270928 0 1782992896 -0.5451258421 0.2901497483 1.0765010118 845 33.7599999990 0.0399712808 0.0235549689 0.0594451055 0.0092897751 0.1657930000 257272358 0 1784659968 -0.5466147065 0.2866817415 1.0823743343 846 33.7999999990 0.0412504263 0.0235758856 0.0594451055 0.0092947894 0.1739640000 257274692 0 1786421248 -0.5466376543 0.2856935859 1.0866962671 847 33.8400000000 0.0394124389 0.0235945828 0.0594451055 0.0092917939 0.1634420000 257272370 0 1784811520 -0.5492240191 0.2789175510 1.0897200108 848 33.8800000000 0.0390921086 0.0236128582 0.0594451055 0.0092872819 0.1634610000 257276176 0 1786064896 -0.5479097962 0.2756384313 1.0953646898 849 33.9200000000 0.0400783159 0.0236322521 0.0594451055 0.0092824478 0.1669180000 257277790 0 1783386112 -0.5507533550 0.2709738314 1.0974913836 850 33.9600000000 0.0380544290 0.0236492194 0.0594451055 0.0092774319 0.1602590000 257276580 0 1785077760 -0.5499454737 0.2653655112 1.1018379927 851 34.0000000000 0.0396282300 0.0236679961 0.0594451055 0.0092720056 0.1980150000 257761342 0 1786691584 -0.5522193909 0.2639138997 1.1047140360 852 34.0400000000 0.0406488515 0.0236879267 0.0594451055 0.0092666642 0.4420170000 257731284 0 1781657600 -0.5522532463 0.2597614229 1.1083129644 853 34.0800000000 0.0428082906 0.0237103421 0.0594451055 0.0092645819 0.3783240000 258435905 0 1784152064 -0.5529698133 0.2579835355 1.1104652882 854 34.1199999990 0.0409357548 0.0237305124 0.0594451055 0.0092614671 0.3186020000 259747063 0 1779490816 -0.5536404252 0.2537694275 1.1146970987 855 34.1600000000 0.0423807539 0.0237523256 0.0594451055 0.0092616194 0.1975450000 259781365 0 1777225728 -0.5537354350 0.2516894639 1.1171315908 856 34.2000000000 0.0392063707 0.0237703793 0.0594451055 0.0092569184 0.3178620000 259707410 0 1774186496 -0.5514931679 0.2463989854 1.1228641272 857 34.2400000000 0.0395986810 0.0237888488 0.0594451055 0.0092529962 0.1772730000 257730526 0 1775046656 -0.5542027354 0.2455314547 1.1243993044 858 34.2800000000 0.0402057469 0.0238079827 0.0594451055 0.0092484531 0.1739600000 257734308 0 1776996352 -0.5532054901 0.2439843565 1.1272264719 859 34.3200000000 0.0393061899 0.0238260248 0.0594451055 0.0092439456 0.1707480000 257735130 0 1778466816 -0.5551448464 0.2370373905 1.1286357641 860 34.3600000000 0.0398508199 0.0238446583 0.0594451055 0.0092390070 0.1701030000 257737240 0 1780510720 -0.5547606349 0.2328640968 1.1303802729 861 34.4000000000 0.0407345966 0.0238642750 0.0594451055 0.0092342654 0.1713370000 257736522 0 1782538240 -0.5545815229 0.2305678129 1.1330316067 862 34.4400000000 0.0408459119 0.0238839753 0.0594451055 0.0092289896 0.1663780000 257737344 0 1783808000 -0.5553708673 0.2267563492 1.1347818375 863 34.4800000000 0.0383271351 0.0239007112 0.0594451055 0.0092237549 0.1908290000 257740482 0 1785212928 -0.5544816852 0.2179721594 1.1362696886 864 34.5200000000 0.0384573005 0.0239175591 0.0594451055 0.0092185171 0.1660500000 257739824 0 1783955456 -0.5553421378 0.2150710970 1.1383175850 865 34.5600000000 0.0387895405 0.0239347522 0.0594451055 0.0092133004 0.1612320000 257740770 0 1782935552 -0.5568778515 0.2141837329 1.1391981840 866 34.6000000000 0.0402856730 0.0239536332 0.0594451055 0.0092088768 0.1625810000 257740572 0 1781428224 -0.5586895347 0.2143506110 1.1401569843 867 34.6400000000 0.0389774777 0.0239709617 0.0594451055 0.0092055338 0.1642600000 257746034 0 1783574528 -0.5581322908 0.2108314633 1.1433837414 868 34.6800000000 0.0394471288 0.0239887914 0.0594451055 0.0092010522 0.1603410000 257746136 0 1784938496 -0.5583669543 0.2073622346 1.1435546875 869 34.7200000000 0.0403602980 0.0240076309 0.0594451055 0.0091965146 0.1676050000 257750662 0 1786728448 -0.5573260188 0.2048957646 1.1441870928 870 34.7600000000 0.0387200676 0.0240245417 0.0594451055 0.0091912589 0.1600700000 257751248 0 1782067200 -0.5581990480 0.2008503079 1.1453880072 871 34.8000000000 0.0405208506 0.0240434812 0.0594451055 0.0091861530 0.1572370000 257751802 0 1781411840 -0.5598932505 0.2007864118 1.1454671621 872 34.8400000000 0.0383913070 0.0240599351 0.0594451055 0.0091811029 0.1599570000 257754964 0 1783558144 -0.5601793528 0.1956067830 1.1468411684 873 34.8800000000 0.0397485308 0.0240779060 0.0594451055 0.0091763388 0.1603380000 257756438 0 1785212928 -0.5616711974 0.1947937608 1.1470830441 874 34.9200000000 0.0403141379 0.0240964830 0.0594451055 0.0091717632 0.1565670000 257756232 0 1786470400 -0.5624590516 0.1941349208 1.1482993364 875 34.9600000000 0.0408272110 0.0241156038 0.0594451055 0.0091677579 0.1591700000 257759002 0 1782435840 -0.5647842288 0.1948759258 1.1496040821 876 35.0000000000 0.0396783836 0.0241333695 0.0594451055 0.0091628659 0.1602470000 257760324 0 1780674560 -0.5652132034 0.1929684728 1.1515572071 877 35.0400000000 0.0412948839 0.0241529380 0.0594451055 0.0091581807 0.1563080000 257761262 0 1782714368 -0.5648619533 0.1943114251 1.1527789831 878 35.0800000000 0.0411846675 0.0241723363 0.0594451055 0.0091530601 0.1564850000 257762068 0 1783697408 -0.5665639043 0.1945621222 1.1544144154 879 35.1200000000 0.0391379669 0.0241893620 0.0594451055 0.0091483097 0.1585250000 257764838 0 1785466880 -0.5669767261 0.1915767938 1.1561864614 880 35.1600000000 0.0388030671 0.0242059685 0.0594451055 0.0091435238 0.1551070000 257765476 0 1784090624 -0.5668445230 0.1919355392 1.1569849253 881 35.2000000000 0.0398757420 0.0242237549 0.0594451055 0.0091387867 0.1581160000 257768690 0 1783050240 -0.5694571137 0.1926514804 1.1572393179 882 35.2400000000 0.0398279242 0.0242414467 0.0594451055 0.0091345907 0.1620800000 257769604 0 1781309440 -0.5687960982 0.1888782978 1.1585618258 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:36:52 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.2156560000 88427194 95654128 1759629312 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0060421242 0.0030210621 0.0060421242 0.0064368318 0.9965500000 88877022 95654128 1762390016 -0.0008748523 -0.0012246990 -0.0001687374 3 0.0800000000 0.0096894642 0.0052438628 0.0096894642 0.0048999133 1.0088750000 88879040 95654128 1764294656 -0.0010495110 -0.0070235450 -0.0013660281 4 0.1200000000 0.0045104325 0.0050605052 0.0096894642 0.0066436972 0.8861210000 88879918 95654128 1765945344 -0.0009399353 -0.0027147047 -0.0007515959 5 0.1600000000 0.0026945604 0.0045873163 0.0096894642 0.0067346689 1.0072110000 88881932 95654128 1767833600 0.0032251042 -0.0043189097 -0.0006710247 6 0.2000000000 0.0039803791 0.0044861601 0.0096894642 0.0062175367 1.0919390000 88884282 95654128 1769484288 -0.0014663532 -0.0070180250 0.0018266647 7 0.2400000000 0.0044943029 0.0044873233 0.0096894642 0.0059194037 0.8668830000 88884716 95654128 1771102208 -0.0019190982 -0.0080829486 0.0039738230 8 0.2800000000 0.0061284485 0.0046924640 0.0096894642 0.0054830358 0.9108320000 88886410 95654128 1772879872 -0.0029237398 -0.0045402702 0.0042499709 9 0.3200000000 0.0108284932 0.0053742450 0.0108284932 0.0051686085 0.8297670000 88888744 95654128 1774497792 -0.0071536275 -0.0024286376 0.0047507863 10 0.3600000000 0.0108999759 0.0059268181 0.0108999759 0.0048986246 0.9489370000 88890490 95654128 1776107520 -0.0062365909 -0.0069117676 0.0064064916 11 0.4000000000 0.0110429442 0.0063919205 0.0110429442 0.0047324963 0.9132420000 88892184 95654128 1777876992 -0.0061007533 -0.0088447342 0.0076738545 12 0.4400000000 0.0118310917 0.0068451847 0.0118310917 0.0046988898 1.1532980000 88893878 95654128 1779654656 -0.0057497215 -0.0105310399 0.0082120877 13 0.4800000000 0.0144750597 0.0074320982 0.0144750597 0.0045667897 2.0498250000 88895196 95654128 1781194752 -0.0086358674 -0.0057269470 0.0080917561 14 0.5200000000 0.0185696054 0.0082276344 0.0185696054 0.0044587326 1.8092290000 88896890 95654128 1783074816 -0.0123526882 -0.0047213896 0.0095765460 15 0.5600000000 0.0194061175 0.0089728666 0.0194061175 0.0043976988 1.8715680000 88898584 95654128 1784606720 -0.0112659493 -0.0074909208 0.0117078265 16 0.6000000000 0.0208537150 0.0097154197 0.0208537150 0.0042622148 1.6435360000 88899018 95654128 1786351616 -0.0120193521 -0.0084528374 0.0126010133 17 0.6400000000 0.0212096702 0.0103915520 0.0212096702 0.0042782971 1.3367180000 88901992 95654128 1787994112 -0.0131628029 -0.0070669949 0.0122491764 18 0.6800000000 0.0230852198 0.0110967558 0.0230852198 0.0041865011 1.9080680000 88906310 95654128 1784692736 -0.0141601125 -0.0069040712 0.0130053684 19 0.7200000000 0.0234045424 0.0117445340 0.0234045424 0.0040969037 1.9676940000 88906744 95654128 1786073088 -0.0119209858 -0.0079395985 0.0141094560 20 0.7600000000 0.0235551801 0.0123350663 0.0235551801 0.0040593778 1.9090350000 88908438 95654128 1787850752 -0.0123176929 -0.0058918884 0.0134047093 21 0.8000000000 0.0239467137 0.0128880019 0.0239467137 0.0040396685 1.5494840000 88910132 95654128 1784438784 -0.0144135095 -0.0021146690 0.0129965115 22 0.8400000000 0.0252549388 0.0134501354 0.0252549388 0.0040042069 1.7026760000 88910486 95654128 1785802752 -0.0163701717 0.0005090383 0.0124939727 23 0.8800000000 0.0271202009 0.0140444861 0.0271202009 0.0039396203 1.5014300000 88912180 95654128 1787580416 -0.0175251402 0.0018442010 0.0128565552 24 0.9200000000 0.0283700638 0.0146413852 0.0283700638 0.0038635506 1.9490400000 88913858 95654128 1784532992 -0.0179355331 0.0037226535 0.0126843061 25 0.9600000000 0.0273149498 0.0151483278 0.0283700638 0.0037923341 1.5607360000 88914292 95654128 1786064896 -0.0155534111 0.0025818695 0.0132045029 26 1.0000000000 0.0301874969 0.0157267573 0.0301874969 0.0037668581 1.7017240000 88915986 95654128 1787842560 -0.0191051606 0.0044128345 0.0123772249 27 1.0400000000 0.0315280668 0.0163119910 0.0315280668 0.0037152201 2.2452510000 88917680 95654128 1784668160 -0.0203468688 0.0049826042 0.0126526942 28 1.0800000000 0.0323523656 0.0168848615 0.0323523656 0.0036770653 2.1833130000 88918114 95654128 1786064896 -0.0189024098 0.0046670372 0.0130789969 29 1.1200000000 0.0320143700 0.0174065687 0.0323523656 0.0039304680 1.8733970000 88919792 95654128 1787969536 -0.0171224810 0.0045810905 0.0137671959 30 1.1600000000 0.0325248353 0.0179105109 0.0325248353 0.0041678265 2.3324670000 88921486 95654128 1784668160 -0.0180692729 0.0025356265 0.0150621673 31 1.2000000000 0.0330966748 0.0184003872 0.0330966748 0.0045574262 2.0012450000 88921904 95654128 1785929728 -0.0163324028 -0.0000996818 0.0168611482 32 1.2400000000 0.0349496081 0.0189175504 0.0349496081 0.0048939014 1.3617160000 88923598 95654128 1788088320 -0.0158344172 0.0042681480 0.0172990877 33 1.2800000000 0.0318550281 0.0193095951 0.0349496081 0.0053065313 1.5917170000 88927852 95654128 1784786944 -0.0125833917 0.0040683849 0.0173029695 34 1.3200000000 0.0307569280 0.0196462814 0.0349496081 0.0055213786 1.6943290000 88933534 95654128 1786056704 -0.0114138192 0.0050803921 0.0174103864 35 1.3600000000 0.0321941338 0.0200047915 0.0349496081 0.0059236085 1.5478980000 88935228 95654128 1788088320 -0.0120283915 0.0079271756 0.0178808905 36 1.4000000000 0.0342928246 0.0204016813 0.0349496081 0.0062994700 1.6396750000 88936890 95654128 1784786944 -0.0121546844 0.0089563513 0.0184532031 37 1.4400000000 0.0320502743 0.0207165081 0.0349496081 0.0068349507 2.2439040000 88937324 95654128 1786183680 -0.0089424998 0.0073880563 0.0191463493 38 1.4800000000 0.0320081748 0.0210136572 0.0349496081 0.0085548322 1.9661370000 88939018 95654128 1788104704 -0.0065337233 0.0089589842 0.0196160097 39 1.5200000000 0.0347966217 0.0213670666 0.0349496081 0.0087263914 1.5277990000 88940712 95654128 1784786944 -0.0065666926 0.0135458950 0.0186387524 40 1.5600000000 0.0357095487 0.0217256286 0.0357095487 0.0088198476 1.7642630000 88942034 95654128 1786056704 -0.0057328269 0.0149156488 0.0180223100 41 1.6000000000 0.0399188362 0.0221693654 0.0399188362 0.0088527577 0.8192450000 89112328 95654128 1785606144 -0.0074773543 0.0150892520 0.0177941862 42 1.6400000000 0.0381559320 0.0225499979 0.0399188362 0.0090561006 1.3345490000 89114022 95654128 1787088896 -0.0039850986 0.0143444417 0.0179930627 43 1.6800000000 0.0383604579 0.0229176831 0.0399188362 0.0092565095 1.4491370000 89114456 95654128 1784303616 -0.0033694701 0.0158251282 0.0180958137 44 1.7200000000 0.0391308032 0.0232861631 0.0399188362 0.0095623289 1.3270660000 89116150 95654128 1785700352 -0.0001923195 0.0205311663 0.0185439494 45 1.7600000000 0.0341631472 0.0235278738 0.0399188362 0.0100331062 2.1540920000 89117844 95654128 1787731968 0.0054044635 0.0140124252 0.0213292353 46 1.8000000000 0.0391998924 0.0238685699 0.0399188362 0.0112313825 1.6063650000 89118278 95654128 1784573952 0.0282192733 0.0150753483 0.0189792663 47 1.8400000000 0.0507449098 0.0244404069 0.0507449098 0.0111349653 1.9538500000 89119972 95654128 1785946112 0.0769515410 0.0152143203 0.0106689539 48 1.8800000000 0.0483099073 0.0249376882 0.0507449098 0.0112391152 0.9165130000 89121666 95654128 1787990016 0.0812943503 0.0135468617 0.0100181755 49 1.9200000000 0.0471754074 0.0253915192 0.0507449098 0.0113803253 2.4913570000 89122084 95654128 1784815616 0.0849351138 0.0126465093 0.0094463676 50 1.9600000000 0.0485535115 0.0258547590 0.0507449098 0.0114956431 2.2499870000 89123778 95654128 1786085376 0.0844753906 0.0099146282 0.0108149210 51 2.0000000000 0.0448401645 0.0262270219 0.0507449098 0.0116036830 1.6695780000 89126576 95654128 1787736064 0.0895072371 0.0052708723 0.0100916941 52 2.0400000000 0.0457336418 0.0266021492 0.0507449098 0.0116700935 1.9980720000 89295610 95654128 1784561664 0.0914551467 0.0040044030 0.0101246675 53 2.0800000000 0.0432794020 0.0269168143 0.0507449098 0.0117191634 1.9640190000 89297288 95654128 1786085376 0.0938640907 -0.0008538151 0.0104050227 54 2.1200000000 0.0416619033 0.0271898715 0.0507449098 0.0117227393 1.0611270000 89298982 95654128 1787990016 0.0983490422 0.0003345171 0.0069102598 55 2.1600000000 0.0372867659 0.0273734514 0.0507449098 0.0118541752 2.4439680000 89299400 95654128 1784688640 0.1059050336 -0.0026338387 0.0094039226 56 2.2000000000 0.0413383953 0.0276228254 0.0507449098 0.0118638455 2.2294130000 89301094 95654128 1786085376 0.1026638374 -0.0047120107 0.0096604740 57 2.2400000000 0.0385572240 0.0278146570 0.0507449098 0.0120228643 1.1085100000 89302772 95654128 1787990016 0.1045872867 -0.0101887174 0.0103843799 58 2.2800000000 0.0427202769 0.0280716504 0.0507449098 0.0121395027 1.7550030000 89303206 95654128 1784688640 0.1026195362 -0.0089982552 0.0102192452 59 2.3200000000 0.0414872952 0.0282990342 0.0507449098 0.0123582769 1.5018400000 89305420 95654128 1786085376 0.1048564911 -0.0133137628 0.0095258029 60 2.3600000000 0.0416747890 0.0285219635 0.0507449098 0.0125542120 2.1855820000 89475718 95654128 1788116992 0.1078449711 -0.0136105986 0.0084969271 61 2.4000000000 0.0435722545 0.0287686896 0.0507449098 0.0127438960 1.8666730000 89476152 95654128 1784561664 0.1076977327 -0.0102517884 0.0060073137 62 2.4400000000 0.0446660966 0.0290250993 0.0507449098 0.0128986960 2.0813680000 89477846 95654128 1785966592 0.1102781743 -0.0081523079 0.0030730511 63 2.4800000000 0.0463414192 0.0292999616 0.0507449098 0.0130771774 1.3119430000 89479524 95654128 1787871232 0.1121743694 -0.0079854224 0.0031070863 64 2.5200000000 0.0464802831 0.0295684041 0.0507449098 0.0132036535 1.7206360000 89479958 95654128 1784696832 0.1157729551 -0.0112143978 0.0029108524 65 2.5600000000 0.0479927436 0.0298518555 0.0507449098 0.0132918427 1.4460470000 89486772 95654128 1786023936 0.1178801060 -0.0135827325 0.0021795882 66 2.6000000000 0.0502190776 0.0301604497 0.0507449098 0.0133977096 0.7681760000 89498962 95654128 1787867136 0.1203402430 -0.0165993925 0.0017970415 67 2.6400000000 0.0529604927 0.0305007489 0.0529604927 0.0135200805 0.8063340000 89499396 95654128 1784692736 0.1210809425 -0.0196918882 0.0017534404 68 2.6800000000 0.0552788973 0.0308651334 0.0552788973 0.0136405884 0.9266390000 89501074 95654128 1785962496 0.1238113344 -0.0205600727 0.0008275878 69 2.7200000000 0.0550759174 0.0312160143 0.0552788973 0.0137721951 1.2627580000 89502768 95654128 1787994112 0.1275385916 -0.0222312361 -0.0006100943 70 2.7600000000 0.0558988489 0.0315686263 0.0558988489 0.0139367836 1.8433160000 89503202 95654128 1784565760 0.1284671277 -0.0214416385 -0.0031171835 71 2.8000000000 0.0603556149 0.0319740768 0.0603556149 0.0139982330 1.7212750000 89504896 95654128 1785835520 0.1273923367 -0.0190123338 -0.0070400042 72 2.8400000000 0.0608914718 0.0323757073 0.0608914718 0.0142011068 2.1883230000 89506590 95654128 1787756544 0.1298681945 -0.0196695682 -0.0073879836 73 2.8800000000 0.0602219589 0.0327571628 0.0608914718 0.0143608710 1.6515680000 89507024 95654128 1784692736 0.1329969317 -0.0234278142 -0.0073799072 74 2.9200000000 0.0604846738 0.0331318589 0.0608914718 0.0144562298 1.8658800000 89508718 95654128 1785962496 0.1374702752 -0.0281061903 -0.0087036155 75 2.9600000000 0.0612811856 0.0335071833 0.0612811856 0.0145710775 1.6214320000 89511964 95654128 1787867136 0.1386967301 -0.0320323259 -0.0086291917 76 3.0000000000 0.0607651286 0.0338658404 0.0612811856 0.0146568521 1.7580160000 89680998 95654128 1784692736 0.1447498053 -0.0358979180 -0.0107447524 77 3.0400000000 0.0618905500 0.0342297977 0.0618905500 0.0147386228 1.7165170000 89682692 95654128 1785962496 0.1476235688 -0.0414132178 -0.0115732476 78 3.0800000000 0.0641775355 0.0346137431 0.0641775355 0.0147397629 1.8960500000 89684386 95654128 1787867136 0.1504705846 -0.0446319878 -0.0141295809 79 3.1200000000 0.0635304376 0.0349797772 0.0641775355 0.0148154936 1.3522970000 89684820 95654128 1784565760 0.1567441225 -0.0477442220 -0.0148160318 80 3.1600000000 0.0640868992 0.0353436162 0.0641775355 0.0152866550 1.8516550000 89686514 95654128 1785962496 0.1647767127 -0.0482878163 -0.0203809217 81 3.2000000000 0.0621178672 0.0356741625 0.0641775355 0.0152970755 1.5510830000 89688208 95654128 1787867136 0.1719190031 -0.0516279265 -0.0227658860 82 3.2400000000 0.0611117966 0.0359843775 0.0641775355 0.0152966030 1.7915960000 89688642 95654128 1784692736 0.1763932854 -0.0555165187 -0.0256065968 83 3.2800000000 0.0620597452 0.0362985386 0.0641775355 0.0153479272 1.5011050000 89690336 95654128 1786097664 0.1776196361 -0.0527396537 -0.0273505300 84 3.3200000000 0.0602899566 0.0365841507 0.0641775355 0.0153352977 1.6756970000 89692030 95654128 1787756544 0.1826082617 -0.0583569109 -0.0290569216 85 3.3600000000 0.0599998198 0.0368596292 0.0641775355 0.0153455189 2.0092060000 89692464 95654128 1784320000 0.1862000376 -0.0596072301 -0.0313547626 86 3.4000000000 0.0611278452 0.0371418177 0.0641775355 0.0153704978 1.7964100000 89694158 95654128 1785843712 0.1867776215 -0.0599520504 -0.0323148035 87 3.4400000000 0.0572262406 0.0373726732 0.0641775355 0.0154394155 1.8073410000 89695852 95654128 1787621376 0.1941393912 -0.0579665825 -0.0348188616 88 3.4800000000 0.0607126914 0.0376379007 0.0641775355 0.0154270394 2.1681760000 89696286 95654128 1784819712 0.1956363469 -0.0623287745 -0.0369713604 89 3.5200000000 0.0510195009 0.0377882557 0.0641775355 0.0154805296 2.2140860000 89697980 95654128 1786089472 0.2088032663 -0.0601369441 -0.0398744680 90 3.5600000000 0.0459821336 0.0378792988 0.0641775355 0.0154851929 1.3114120000 89699658 95654128 1787883520 0.2187509835 -0.0645337477 -0.0418041311 91 3.6000000000 0.0471539497 0.0379812180 0.0641775355 0.0154988027 1.8497320000 89700092 95654128 1784565760 0.2210526168 -0.0682178512 -0.0437938459 92 3.6400000000 0.0485917851 0.0380965503 0.0641775355 0.0154919815 1.5967750000 89701786 95654128 1785835520 0.2230521888 -0.0684038401 -0.0453365967 93 3.6800000000 0.0449498743 0.0381702419 0.0641775355 0.0154737877 1.8157450000 89703480 95654128 1787867136 0.2274716645 -0.0660416260 -0.0478970483 94 3.7200000000 0.0447429009 0.0382401639 0.0641775355 0.0154302518 2.0451380000 89703914 95654128 1784692736 0.2307749242 -0.0681720152 -0.0498900935 95 3.7600000000 0.0454684608 0.0383162512 0.0641775355 0.0153797458 1.7127570000 89705608 95654128 1785962496 0.2329321802 -0.0688086003 -0.0526827797 96 3.8000000000 0.0442133471 0.0383776793 0.0641775355 0.0153471120 1.7713790000 89707302 95654128 1787867136 0.2373197377 -0.0684493408 -0.0545354262 97 3.8400000000 0.0457947999 0.0384541444 0.0641775355 0.0153055841 1.8897070000 89707736 95654128 1784692736 0.2379166782 -0.0686559156 -0.0557400212 98 3.8800000000 0.0473037362 0.0385444464 0.0641775355 0.0152485616 2.2161950000 89709430 95654128 1785962496 0.2362539768 -0.0698916242 -0.0569623448 99 3.9200000000 0.0465532616 0.0386253435 0.0641775355 0.0151926279 1.6553910000 89711124 95654128 1787867136 0.2392640412 -0.0709071383 -0.0604873933 100 3.9600000000 0.0448766164 0.0386878562 0.0641775355 0.0151418384 1.7794280000 89711558 95654128 1784565760 0.2410573214 -0.0700939447 -0.0625971481 101 4.0000000000 0.0452470668 0.0387527989 0.0641775355 0.0150867695 2.2144710000 89713252 95654128 1785835520 0.2421535105 -0.0673749968 -0.0646033287 102 4.0400000000 0.0411538295 0.0387763384 0.0641775355 0.0150678018 2.3190770000 89714946 95654128 1788002304 0.2469232380 -0.0625340790 -0.0670260638 103 4.0800000000 0.0415419936 0.0388031895 0.0641775355 0.0150111099 1.4452330000 89715380 95654128 1784573952 0.2485302687 -0.0628630444 -0.0691215023 104 4.1200000000 0.0416010357 0.0388300918 0.0641775355 0.0149630445 2.0738750000 89717922 95654128 1785843712 0.2504954040 -0.0612943731 -0.0694942698 105 4.1600000000 0.0424405560 0.0388644772 0.0641775355 0.0149102300 1.7636060000 89888228 95654128 1787875328 0.2516935766 -0.0604939051 -0.0723592117 106 4.2000000000 0.0429274924 0.0389028075 0.0641775355 0.0148512400 1.8645100000 89888662 95654128 1784332288 0.2521753907 -0.0579907298 -0.0729925036 107 4.2400000000 0.0485568829 0.0389930325 0.0641775355 0.0147846280 1.6359800000 89890356 95654128 1785708544 0.2457059473 -0.0563522913 -0.0737085268 108 4.2800000000 0.0502708517 0.0390974568 0.0641775355 0.0147181178 1.8042980000 89892050 95654128 1787613184 0.2468868792 -0.0523939840 -0.0768618062 109 4.3200000000 0.0534221679 0.0392288762 0.0641775355 0.0146507294 1.8632770000 89892484 95654128 1784692736 0.2447209209 -0.0511380211 -0.0783057362 110 4.3600000000 0.0567474961 0.0393881363 0.0641775355 0.0145856662 1.5693020000 89894162 95654128 1786089472 0.2418765724 -0.0482917540 -0.0789024308 111 4.4000000000 0.0609237030 0.0395821504 0.0641775355 0.0145218587 2.2018240000 89895856 95654128 1787867136 0.2391747534 -0.0476295650 -0.0792113096 112 4.4400000000 0.0559720136 0.0397284885 0.0641775355 0.0144778273 1.8907500000 89896290 95654128 1784692736 0.2476731390 -0.0467439666 -0.0807211474 113 4.4800000000 0.0575584695 0.0398862760 0.0641775355 0.0144150453 1.4476250000 89897984 95654128 1786089472 0.2476292104 -0.0447848141 -0.0810257718 114 4.5200000000 0.0575071797 0.0400408453 0.0641775355 0.0143528014 1.3376790000 89899678 95654128 1787867136 0.2492805719 -0.0427429415 -0.0805695429 115 4.5600000000 0.0572184771 0.0401902160 0.0641775355 0.0142963337 1.7168050000 89900112 95654128 1784692736 0.2497865409 -0.0390925594 -0.0837393478 116 4.6000000000 0.0565961562 0.0403316465 0.0641775355 0.0142388488 1.1536030000 89901806 95654128 1786089472 0.2516164184 -0.0376503319 -0.0834978223 117 4.6400000000 0.0532679372 0.0404422131 0.0641775355 0.0141929383 1.3637320000 89904272 95654128 1787867136 0.2548077106 -0.0346865319 -0.0877455026 118 4.6800000000 0.0519815497 0.0405400041 0.0641775355 0.0141586356 1.7633310000 90073322 95654128 1784565760 0.2567413449 -0.0322548077 -0.0874657258 119 4.7200000000 0.0504103564 0.0406229482 0.0641775355 0.0141153437 1.7508220000 90075016 95654128 1785962496 0.2577317357 -0.0265584365 -0.0890555233 120 4.7600000000 0.0480695479 0.0406850032 0.0641775355 0.0140648860 1.9291970000 90076710 95654128 1787985920 0.2603878975 -0.0265887901 -0.0902799591 121 4.8000000000 0.0466301516 0.0407341367 0.0641775355 0.0140195745 0.8408830000 90077144 95654128 1784741888 0.2605215311 -0.0245398358 -0.0908600688 122 4.8400000000 0.0470090993 0.0407855708 0.0641775355 0.0140005668 0.9226860000 90078838 95654128 1785966592 0.2587085664 -0.0198047832 -0.0927615613 123 4.8800000000 0.0448969863 0.0408189969 0.0641775355 0.0139516338 1.6496870000 90080532 95654128 1787768832 0.2608033717 -0.0211112425 -0.0924128965 124 4.9200000000 0.0447280183 0.0408505213 0.0641775355 0.0139124377 1.7920380000 90080966 95654128 1784451072 0.2600963116 -0.0195977464 -0.0925413221 125 4.9600000000 0.0448438413 0.0408824679 0.0641775355 0.0138718122 1.3356450000 90082660 95654128 1785847808 0.2590847909 -0.0157969464 -0.0921994746 126 5.0000000000 0.0445943289 0.0409119271 0.0641775355 0.0138321658 1.4167100000 90084354 95654128 1787625472 0.2591773272 -0.0143259810 -0.0923668146 127 5.0400000000 0.0452092290 0.0409457641 0.0641775355 0.0138027424 1.2744170000 90085484 95654128 1784569856 0.2569998503 -0.0126310335 -0.0919294730 128 5.0800000000 0.0430920348 0.0409625318 0.0641775355 0.0137630511 1.5538470000 90255806 95654128 1785839616 0.2589123845 -0.0115370201 -0.0908719227 129 5.1200000000 0.0442186296 0.0409877729 0.0641775355 0.0137376236 1.7587210000 90267740 95654128 1787998208 0.2575863898 -0.0083766505 -0.0910628214 130 5.1600000000 0.0440228581 0.0410111197 0.0641775355 0.0137156139 1.6098320000 90289166 95654128 1784569856 0.2575308979 -0.0128747104 -0.0891921297 131 5.2000000000 0.0444509126 0.0410373777 0.0641775355 0.0136982654 1.7957880000 90290860 95654128 1785966592 0.2552226186 -0.0113483360 -0.0868230239 132 5.2400000000 0.0455091074 0.0410712544 0.0641775355 0.0136842016 1.2987810000 90292554 95654128 1787744256 0.2514761686 -0.0085326638 -0.0856052712 133 5.2800000000 0.0468475446 0.0411146852 0.0641775355 0.0136635175 1.6004910000 90292988 95654128 1784696832 0.2484950423 -0.0088017732 -0.0846931711 134 5.3200000000 0.0448021591 0.0411422036 0.0641775355 0.0136206199 1.5671560000 90294698 95654128 1785966592 0.2508878708 -0.0117991325 -0.0823683515 135 5.3600000000 0.0453016572 0.0411730144 0.0641775355 0.0135828208 1.4763570000 90296392 95654128 1787744256 0.2476226240 -0.0103493445 -0.0795154348 136 5.4000000000 0.0445897318 0.0411981373 0.0641775355 0.0135467127 2.0500210000 90296826 95654128 1784569856 0.2475269735 -0.0096548377 -0.0780854896 137 5.4400000000 0.0451277532 0.0412268207 0.0641775355 0.0135168485 1.9556830000 90298520 95654128 1785966592 0.2476100922 -0.0101604145 -0.0761209801 138 5.4800000000 0.0428233892 0.0412383900 0.0641775355 0.0135702128 1.9122290000 90300214 95654128 1787744256 0.2466397285 -0.0099501172 -0.0734546632 139 5.5200000000 0.0448018722 0.0412640266 0.0641775355 0.0135397022 2.2485750000 90302372 95654128 1784569856 0.2436532229 -0.0111784097 -0.0703849122 140 5.5600000000 0.0438786484 0.0412827024 0.0641775355 0.0135183314 1.8660660000 90472666 95654128 1785966592 0.2425859571 -0.0069350037 -0.0691390336 141 5.6000000000 0.0441300869 0.0413028966 0.0641775355 0.0134939301 1.9483820000 90474360 95654128 1787998208 0.2405073941 -0.0057781315 -0.0678481385 142 5.6400000000 0.0456083305 0.0413332166 0.0641775355 0.0134664974 1.8235170000 90474794 95654128 1784823808 0.2380590737 -0.0048522633 -0.0663640946 143 5.6800000000 0.0452972427 0.0413609371 0.0641775355 0.0134473746 1.6749450000 90476488 95654128 1786220544 0.2352178991 -0.0024182098 -0.0646360889 144 5.7200000000 0.0470863096 0.0414006966 0.0641775355 0.0134199591 1.6133830000 90478182 95654128 1788133376 0.2294298112 -0.0001997934 -0.0633864552 145 5.7600000000 0.0473757759 0.0414419040 0.0641775355 0.0133951047 2.0779600000 90478616 95654128 1784197120 0.2258138210 0.0054753651 -0.0627080202 146 5.8000000000 0.0475036465 0.0414834228 0.0641775355 0.0133650908 1.6974420000 90480310 95654128 1785593856 0.2242687494 0.0048557878 -0.0607328042 147 5.8400000000 0.0460106395 0.0415142202 0.0641775355 0.0133398476 1.6305340000 90482004 95654128 1787498496 0.2218952477 0.0081962999 -0.0592404194 148 5.8800000000 0.0460260287 0.0415447054 0.0641775355 0.0133183187 1.6566370000 90482454 95654128 1784578048 0.2193577141 0.0130109768 -0.0586575530 149 5.9200000000 0.0455132797 0.0415713401 0.0641775355 0.0133030570 1.3817560000 90484148 95654128 1785847808 0.2165056169 0.0120594036 -0.0573152564 150 5.9600000000 0.0469963066 0.0416075066 0.0641775355 0.0132844314 1.6053680000 90485842 95654128 1787744256 0.2107071280 0.0121680144 -0.0552669577 151 6.0000000000 0.0465978608 0.0416405553 0.0641775355 0.0132652029 1.9861690000 90486276 95654128 1784586240 0.2071653455 0.0136698699 -0.0533559173 152 6.0400000000 0.0470713824 0.0416762844 0.0641775355 0.0132464683 1.9550730000 90487970 95654128 1785966592 0.2028491795 0.0140066873 -0.0515240207 153 6.0800000000 0.0459946543 0.0417045090 0.0641775355 0.0132258545 1.1974500000 90489664 95654128 1787871232 0.1998566538 0.0154594146 -0.0492210425 154 6.1200000000 0.0476658754 0.0417432192 0.0641775355 0.0132244338 1.1574740000 90491202 95654128 1784696832 0.1953565627 0.0167426448 -0.0471400097 155 6.1600000000 0.0470582843 0.0417775100 0.0641775355 0.0132192899 1.4921180000 90661516 95654128 1785966592 0.1912577897 0.0174390227 -0.0454231426 156 6.2000000000 0.0452087782 0.0417995053 0.0641775355 0.0132121799 2.0966330000 90663210 95654128 1788125184 0.1885866374 0.0198987760 -0.0428299643 157 6.2400000000 0.0472958609 0.0418345139 0.0641775355 0.0132163495 2.0242970000 90663644 95654128 1784442880 0.1819474101 0.0227279216 -0.0412016660 158 6.2800000000 0.0466904268 0.0418652475 0.0641775355 0.0132339478 1.5072500000 90665338 95654128 1785839616 0.1798544377 0.0231077354 -0.0395833515 159 6.3200000000 0.0467654504 0.0418960664 0.0641775355 0.0132367142 2.1449000000 90667032 95654128 1787871232 0.1756761074 0.0255138502 -0.0382048003 160 6.3600000000 0.0470826328 0.0419284825 0.0641775355 0.0132402903 1.2588300000 90667466 95654128 1784823808 0.1720718890 0.0274924040 -0.0370385982 161 6.4000000000 0.0469563454 0.0419597114 0.0641775355 0.0132383786 1.7619870000 90669160 95654128 1786093568 0.1693782806 0.0278104413 -0.0354021750 162 6.4400000000 0.0475544743 0.0419942470 0.0641775355 0.0132444464 2.1662410000 90670854 95654128 1788125184 0.1644063443 0.0282069203 -0.0336759873 163 6.4800000000 0.0452294387 0.0420140948 0.0641775355 0.0132420538 2.2530100000 90671288 95654128 1784442880 0.1627288014 0.0289758481 -0.0322194621 164 6.5200000000 0.0456301309 0.0420361438 0.0641775355 0.0132348635 1.9113740000 90672982 95654128 1785974784 0.1594157666 0.0259101894 -0.0299560279 165 6.5600000000 0.0470249467 0.0420663790 0.0641775355 0.0132303176 0.9693310000 90674676 95654128 1787625472 0.1534072161 0.0306777731 -0.0288064089 166 6.6000000000 0.0461326651 0.0420908747 0.0641775355 0.0132402280 1.4066900000 90675110 95654128 1784578048 0.1489480287 0.0330874063 -0.0267690551 167 6.6400000000 0.0451761149 0.0421093492 0.0641775355 0.0132719056 1.7006110000 90676804 95654128 1785974784 0.1459467262 0.0361871123 -0.0260202195 168 6.6800000000 0.0459463149 0.0421321882 0.0641775355 0.0132655302 1.8330050000 90678498 95654128 1787744256 0.1411365867 0.0380398855 -0.0242851619 169 6.7200000000 0.0405432098 0.0421227860 0.0641775355 0.0132934861 1.5899450000 90679804 95654128 1784569856 0.1425023377 0.0316699333 -0.0224443842 170 6.7600000000 0.0425551832 0.0421253295 0.0641775355 0.0133120396 1.8014720000 90850130 95654128 1785966592 0.1360353231 0.0313690938 -0.0222531520 171 6.8000000000 0.0432504490 0.0421319092 0.0641775355 0.0133230745 1.6168700000 90851824 95654128 1787871232 0.1326708198 0.0329008512 -0.0214774292 172 6.8400000000 0.0416106321 0.0421288785 0.0641775355 0.0133327381 1.7854100000 90852258 95654128 1784696832 0.1326360106 0.0326695479 -0.0193521064 173 6.8800000000 0.0440549515 0.0421400118 0.0641775355 0.0133864081 0.5939970000 90853952 95654128 1786093568 0.1293050349 0.0365145579 -0.0198911689 174 6.9200000000 0.0440700948 0.0421511043 0.0641775355 0.0134107626 0.7289270000 90855646 95654128 1787998208 0.1278671473 0.0362181477 -0.0194803979 175 6.9600000000 0.0428613164 0.0421551626 0.0641775355 0.0134388366 0.7124990000 90856080 95654128 1784713216 0.1284827441 0.0351616219 -0.0196666233 176 7.0000000000 0.0438417047 0.0421647453 0.0641775355 0.0134479894 0.9884410000 90857774 95654128 1785966592 0.1273262501 0.0359084420 -0.0194198228 177 7.0400000000 0.0401719064 0.0421534863 0.0641775355 0.0134650573 1.1476050000 90859468 95654128 1787998208 0.1285479516 0.0367644504 -0.0190738682 178 7.0800000000 0.0416216701 0.0421504985 0.0641775355 0.0135038540 2.1774210000 90860862 95654128 1784442880 0.1248968691 0.0369628184 -0.0180779118 179 7.1200000000 0.0406165160 0.0421419288 0.0641775355 0.0135576207 1.5836680000 91031200 95654128 1785839616 0.1243987158 0.0366742387 -0.0177709740 180 7.1600000000 0.0428783894 0.0421460203 0.0641775355 0.0135991561 2.3438630000 91032894 95654128 1787998208 0.1209371090 0.0376691781 -0.0170374475 181 7.2000000000 0.0443492457 0.0421581928 0.0641775355 0.0135926513 2.1705620000 91033328 95654128 1784569856 0.1168043688 0.0369648449 -0.0155359684 182 7.2400000000 0.0440057889 0.0421683444 0.0641775355 0.0135928219 1.9519330000 91035022 95654128 1785839616 0.1165739745 0.0403346941 -0.0169380158 183 7.2800000000 0.0427867807 0.0421717238 0.0641775355 0.0135739463 1.8474870000 91036716 95654128 1787871232 0.1136539280 0.0406798571 -0.0148234414 184 7.3200000000 0.0424606055 0.0421732938 0.0641775355 0.0135746110 1.9415830000 91037150 95654128 1784696832 0.1122669950 0.0404441431 -0.0148378015 185 7.3600000000 0.0388159826 0.0421551462 0.0641775355 0.0135600355 1.7710510000 91038844 95654128 1785966592 0.1110613197 0.0372477509 -0.0136121530 186 7.4000000000 0.0390446857 0.0421384233 0.0641775355 0.0135735206 1.9407010000 91040538 95654128 1788125184 0.1108676717 0.0392426327 -0.0133316098 187 7.4400000000 0.0380215794 0.0421164081 0.0641775355 0.0135906939 0.7416940000 91040972 95654128 1784578048 0.1097061262 0.0361866578 -0.0123009523 188 7.4800000000 0.0387499444 0.0420985014 0.0641775355 0.0136082870 0.7911540000 91042666 95654128 1785974784 0.1057438031 0.0331215039 -0.0114207156 189 7.5200000000 0.0391300656 0.0420827954 0.0641775355 0.0136349917 0.8165080000 91044376 95654128 1787879424 0.1033469737 0.0327635296 -0.0096953819 190 7.5600000000 0.0406649262 0.0420753329 0.0641775355 0.0136849255 0.8230360000 91044810 95654128 1784229888 0.0993088558 0.0303066429 -0.0081574926 191 7.6000000000 0.0409138948 0.0420692521 0.0641775355 0.0137171983 0.7939910000 91047504 95654128 1785626624 0.0972209945 0.0322235189 -0.0086770235 192 7.6400000000 0.0400886014 0.0420589362 0.0641775355 0.0137408665 0.8031000000 91217842 95654128 1787498496 0.0955858827 0.0303790886 -0.0081829410 193 7.6800000000 0.0393700935 0.0420450044 0.0641775355 0.0137606982 0.7506880000 91218276 95654128 1784451072 0.0952950120 0.0304988343 -0.0071125282 194 7.7200000000 0.0394932404 0.0420318509 0.0641775355 0.0137743722 0.9115860000 91219970 95654128 1785847808 0.0921720862 0.0320823565 -0.0082446737 195 7.7600000000 0.0391956381 0.0420173063 0.0641775355 0.0137809618 0.7870220000 91221664 95654128 1787625472 0.0926828310 0.0372641049 -0.0092679355 196 7.8000000000 0.0390342623 0.0420020866 0.0641775355 0.0137658925 1.0106570000 91222098 95654128 1784696832 0.0895347521 0.0368307307 -0.0085284254 197 7.8400000000 0.0402123332 0.0419930016 0.0641775355 0.0137814028 1.6379650000 91223792 95654128 1786093568 0.0918285623 0.0388631932 -0.0090927975 198 7.8800000000 0.0395961925 0.0419808965 0.0641775355 0.0137879637 1.8558480000 91225502 95654128 1787871232 0.0901250616 0.0395271853 -0.0094495565 199 7.9200000000 0.0402209423 0.0419720525 0.0641775355 0.0138083584 1.7079690000 91225936 95654128 1784569856 0.0941561759 0.0410058275 -0.0094965296 200 7.9600000000 0.0400037728 0.0419622111 0.0641775355 0.0138251087 1.3348890000 91227630 95654128 1785966592 0.0931456089 0.0432630852 -0.0097996350 201 8.0000000000 0.0389609560 0.0419472795 0.0641775355 0.0138360116 1.8259940000 91229324 95654128 1787744256 0.0963893160 0.0437819324 -0.0096662436 202 8.0400000000 0.0397637822 0.0419364701 0.0641775355 0.0138274539 1.8561820000 91231022 95654128 1784823808 0.0940763950 0.0417704023 -0.0093075531 203 8.0800000000 0.0380816162 0.0419174807 0.0641775355 0.0138114750 1.0255730000 91401360 95654128 1786220544 0.0931806564 0.0432147682 -0.0084028319 204 8.1200000000 0.0379741006 0.0418981504 0.0641775355 0.0137824953 1.8564380000 91403070 95654128 1788252160 0.0922240689 0.0463327542 -0.0082431836 205 8.1600000000 0.0387996025 0.0418830355 0.0641775355 0.0137618036 1.2720800000 91403504 95654128 1784442880 0.0895197242 0.0440493226 -0.0064474163 206 8.1999999990 0.0388150215 0.0418681422 0.0641775355 0.0137449782 1.8669840000 91405198 95654128 1785712640 0.0866479799 0.0409144908 -0.0053225383 207 8.2400000000 0.0388952494 0.0418537804 0.0641775355 0.0137413497 1.6307270000 91406892 95654128 1787744256 0.0843126997 0.0428467877 -0.0057919943 208 8.2799999990 0.0386952013 0.0418385950 0.0641775355 0.0137629774 1.9222070000 91407326 95654128 1784696832 0.0850254521 0.0428388678 -0.0047429022 209 8.3200000000 0.0387111492 0.0418236311 0.0641775355 0.0137623489 1.8304860000 91409020 95654128 1786101760 0.0834301561 0.0422969498 -0.0025607436 210 8.3599999990 0.0391722731 0.0418110056 0.0641775355 0.0137759294 1.9214120000 91410730 95654128 1787752448 0.0800596476 0.0443177521 -0.0013801862 211 8.4000000000 0.0377292633 0.0417916608 0.0641775355 0.0137967528 2.2113290000 91411164 95654128 1784705024 0.0792140812 0.0426417589 -0.0007012839 212 8.4399999990 0.0385764688 0.0417764948 0.0641775355 0.0138236249 1.2833520000 91414094 95654128 1785974784 0.0790068656 0.0411150530 0.0014679119 213 8.4800000000 0.0372832716 0.0417553999 0.0641775355 0.0138254615 1.9911220000 91584444 95654128 1785368576 0.0764850602 0.0401614048 0.0026112851 214 8.5200000000 0.0376429036 0.0417361826 0.0641775355 0.0138457314 1.7147760000 91584878 95654128 1784205312 0.0748790503 0.0402302146 0.0038717841 215 8.5600000000 0.0373267159 0.0417156735 0.0641775355 0.0138712949 1.8267870000 91586572 95654128 1785585664 0.0740451217 0.0380857363 0.0056662741 216 8.6000000000 0.0376923643 0.0416970471 0.0641775355 0.0139027590 1.8031980000 91588282 95654128 1787617280 0.0759020373 0.0446518585 0.0068201730 217 8.6400000000 0.0368430875 0.0416746786 0.0641775355 0.0139001114 1.8100100000 91588716 95654128 1784696832 0.0768603459 0.0448393412 0.0089162542 218 8.6800000000 0.0392486341 0.0416635499 0.0641775355 0.0139098672 1.6330800000 91590410 95654128 1785966592 0.0768011212 0.0428277478 0.0114730522 219 8.7200000000 0.0410286114 0.0416606507 0.0641775355 0.0139376772 2.0026140000 91592104 95654128 1787744256 0.0769525096 0.0427448824 0.0148989279 220 8.7600000000 0.0424700901 0.0416643299 0.0641775355 0.0139607875 1.5165960000 91594014 95654128 1784569856 0.0757730752 0.0433237180 0.0178520083 221 8.8000000000 0.0433727019 0.0416720601 0.0641775355 0.0139838897 1.4627720000 91764368 95654128 1785966592 0.0763467923 0.0434936732 0.0200494677 222 8.8400000000 0.0416922942 0.0416721513 0.0641775355 0.0139970264 2.2948580000 91766062 95654128 1787871232 0.0770788491 0.0428927243 0.0221655760 223 8.8800000000 0.0417155065 0.0416723457 0.0641775355 0.0140545709 1.3571300000 91766512 95654128 1784696832 0.0755126104 0.0444785617 0.0231260024 224 8.9200000000 0.0416975096 0.0416724580 0.0641775355 0.0140708897 1.3574910000 91768206 95654128 1785966592 0.0717932954 0.0443589203 0.0241331495 225 8.9600000000 0.0385054536 0.0416583825 0.0641775355 0.0142154819 1.5878050000 91769900 95654128 1787871232 0.0331341252 0.0399905927 0.0086715259 226 9.0000000000 0.0366442986 0.0416361962 0.0641775355 0.0142179905 1.6450450000 91770366 95654128 1784823808 0.0298454985 0.0424589626 0.0076496871 227 9.0400000000 0.0365039557 0.0416135873 0.0641775355 0.0142230486 1.5219510000 91773880 95654128 1786220544 0.0269055516 0.0420652032 0.0083887856 228 9.0800000000 0.0363716930 0.0415905965 0.0641775355 0.0142278876 2.1643220000 91944174 95654128 1788125184 0.0234460644 0.0416193306 0.0089063877 229 9.1200000000 0.0361226946 0.0415667192 0.0641775355 0.0142298510 0.7224580000 91944608 95654128 1784696832 0.0194886141 0.0418992303 0.0088672694 230 9.1600000000 0.0349553227 0.0415379740 0.0641775355 0.0142428610 0.7828900000 91946318 95654128 1786228736 0.0160526745 0.0440919288 0.0081783254 231 9.2000000000 0.0353644900 0.0415112489 0.0641775355 0.0142482540 0.8295220000 91948012 95654128 1787879424 0.0120744901 0.0445541963 0.0078502651 232 9.2400000000 0.0351626836 0.0414838844 0.0641775355 0.0142542245 0.7484400000 91948462 95654128 1784721408 0.0090232333 0.0459987000 0.0077662319 233 9.2800000000 0.0346786492 0.0414546774 0.0641775355 0.0142647173 0.9611270000 91950156 95654128 1785974784 0.0071705543 0.0484494492 0.0064087380 234 9.3200000000 0.0351906829 0.0414279082 0.0641775355 0.0142750388 2.1195950000 91951850 95654128 1787768832 0.0024877405 0.0490134358 0.0054582097 235 9.3600000000 0.0354660675 0.0414025387 0.0641775355 0.0142940852 2.2262490000 91953964 95654128 1784823808 0.0000406848 0.0496403128 0.0052306759 236 9.4000000000 0.0363777690 0.0413812473 0.0641775355 0.0143348497 1.8461930000 92124334 95654128 1786093568 -0.0035417716 0.0489537120 0.0047010616 237 9.4400000000 0.0367569104 0.0413617353 0.0641775355 0.0143717685 1.2937900000 92126028 95654128 1788014592 -0.0066946545 0.0465054959 0.0042558503 238 9.4800000000 0.0367278121 0.0413422650 0.0641775355 0.0143942798 1.9574590000 92126462 95654128 1784823808 -0.0099601652 0.0432112291 0.0038957174 239 9.5200000000 0.0368603505 0.0413235123 0.0641775355 0.0144062677 2.4591230000 92128172 95654128 1786093568 -0.0120556932 0.0441339388 0.0036162054 240 9.5600000000 0.0365403742 0.0413035825 0.0641775355 0.0145480066 2.1635310000 92129866 95654128 1787998208 -0.0147984214 0.0370242111 0.0049301614 241 9.6000000000 0.0375327393 0.0412879359 0.0641775355 0.0145453249 1.5643540000 92130332 95654128 1784696832 -0.0179246049 0.0381714515 0.0042774188 242 9.6400000000 0.0379324891 0.0412740704 0.0641775355 0.0145537997 1.6847750000 92133866 95654128 1785966592 -0.0187718477 0.0374047756 0.0044880793 243 9.6800000000 0.0381908901 0.0412613824 0.0641775355 0.0145692259 1.9003890000 92304228 95654128 1787998208 -0.0202890970 0.0362124629 0.0038971954 244 9.7200000000 0.0388187058 0.0412513714 0.0641775355 0.0145747331 2.0193680000 92304678 95654128 1784840192 -0.0217648596 0.0369905643 0.0042041712 245 9.7600000000 0.0380770192 0.0412384149 0.0641775355 0.0145710440 2.2412480000 92306372 95654128 1786220544 -0.0234551802 0.0364107117 0.0042198417 246 9.8000000000 0.0389308669 0.0412290346 0.0641775355 0.0145783638 2.0938640000 92308066 95654128 1787871232 -0.0249163564 0.0374776609 0.0041201892 247 9.8400000000 0.0399716087 0.0412239438 0.0641775355 0.0145882242 1.5819110000 92308500 95654128 1784569856 -0.0299068205 0.0359354615 0.0037352273 248 9.8800000000 0.0407524705 0.0412220427 0.0641775355 0.0145871072 1.9337430000 92310210 95654128 1785966592 -0.0329504609 0.0343907736 0.0034039088 249 9.9200000000 0.0418232791 0.0412244573 0.0641775355 0.0145996623 2.0635020000 92314268 95654128 1787744256 -0.0375350378 0.0323280841 0.0017892462 250 9.9600000000 0.0425750427 0.0412298597 0.0641775355 0.0145936353 0.9606440000 92483350 95654128 1783537664 -0.0402705297 0.0336407647 0.0014303173 251 10.0000000000 0.0434437804 0.0412386801 0.0641775355 0.0145926976 1.0580490000 92485044 95654128 1785188352 -0.0437755473 0.0326742381 0.0000582316 252 10.0400000000 0.0434455201 0.0412474374 0.0641775355 0.0145950052 2.2521120000 92486854 95654128 1786839040 -0.0467868820 0.0312792361 -0.0012249497 253 10.0800000000 0.0449452475 0.0412620532 0.0641775355 0.0145923148 1.6493800000 92487288 95654128 1785442304 -0.0499104559 0.0325528271 -0.0017382987 254 10.1200000000 0.0465786085 0.0412829845 0.0641775355 0.0145896385 2.1128870000 92488982 95654128 1786966016 -0.0530500971 0.0325809903 -0.0019813981 255 10.1600000000 0.0471653901 0.0413060528 0.0641775355 0.0145803143 1.5262970000 92490676 95654128 1784680448 -0.0553454682 0.0328523852 -0.0029807049 256 10.2000000000 0.0476969965 0.0413310174 0.0641775355 0.0145766949 2.1766730000 92491226 95654128 1786068992 -0.0569348447 0.0331775248 -0.0030902266 257 10.2400000000 0.0475071669 0.0413550491 0.0641775355 0.0146888019 2.3410470000 92515316 95654128 1787973632 -0.0622906908 0.0284938011 -0.0043008216 258 10.2800000000 0.0488310494 0.0413840259 0.0641775355 0.0146919128 1.6976620000 92727666 95654128 1784672256 -0.0645236224 0.0296616461 -0.0051677623 259 10.3200000000 0.0486419909 0.0414120489 0.0641775355 0.0146796212 1.6531560000 92728332 95654128 1786068992 -0.0666234717 0.0277960077 -0.0054431837 260 10.3600000000 0.0498003289 0.0414443115 0.0641775355 0.0146693562 2.2606490000 92730026 95654128 1787973632 -0.0689590350 0.0271476544 -0.0058796261 261 10.4000000000 0.0494289920 0.0414749042 0.0641775355 0.0146494316 1.8454230000 92731720 95654128 1784799232 -0.0706078634 0.0255962275 -0.0070398794 262 10.4400000000 0.0486444347 0.0415022688 0.0641775355 0.0146292690 1.9537440000 92732154 95654128 1786068992 -0.0716435164 0.0235603284 -0.0074690618 263 10.4800000000 0.0493267328 0.0415320196 0.0641775355 0.0146113873 2.1364800000 92733848 95654128 1787973632 -0.0742559731 0.0224732105 -0.0077321194 264 10.5200000000 0.0509367399 0.0415676435 0.0641775355 0.0146019026 2.1261540000 92735658 95654128 1784672256 -0.0766144767 0.0227697250 -0.0079641603 265 10.5600000000 0.0506203249 0.0416018046 0.0641775355 0.0145845532 1.7016930000 92736092 95654128 1785942016 -0.0788099840 0.0208421499 -0.0098782200 266 10.6000000000 0.0519063920 0.0416405437 0.0641775355 0.0145784705 1.7696080000 92737786 95654128 1787973632 -0.0813580453 0.0206417684 -0.0111658480 267 10.6400000000 0.0513619818 0.0416769535 0.0641775355 0.0145753947 1.6174390000 92739480 95654128 1784672256 -0.0833627731 0.0192724615 -0.0123889958 268 10.6800000000 0.0519000292 0.0417150993 0.0641775355 0.0145806727 2.0969220000 92742350 95654128 1785942016 -0.0857179090 0.0184718259 -0.0141997896 269 10.7200000000 0.0533326492 0.0417582873 0.0641775355 0.0145998376 1.9169630000 92912728 95654128 1788108800 -0.0891799927 0.0178186540 -0.0161638670 270 10.7600000000 0.0541802719 0.0418042946 0.0641775355 0.0146042748 1.7980010000 92914422 95654128 1784426496 -0.0918535441 0.0173290297 -0.0188657809 271 10.8000000000 0.0556737892 0.0418554736 0.0641775355 0.0146121086 1.9617990000 92914856 95654128 1785823232 -0.0945099667 0.0172627419 -0.0205938127 272 10.8400000000 0.0557419062 0.0419065266 0.0641775355 0.0146315983 1.2544140000 92916550 95654128 1787727872 -0.0968167335 0.0156796779 -0.0225332621 273 10.8800000000 0.0566674396 0.0419605959 0.0641775355 0.0146536873 1.8949890000 92918360 95654128 1784799232 -0.0998924598 0.0145082902 -0.0243460033 274 10.9200000000 0.0578623638 0.0420186315 0.0641775355 0.0146678394 1.9546820000 92918794 95654128 1786068992 -0.1018963233 0.0146505982 -0.0261379182 275 10.9600000000 0.0580952950 0.0420770921 0.0641775355 0.0146771308 2.1003160000 92920488 95654128 1787846656 -0.1041401997 0.0127622504 -0.0277428944 276 11.0000000000 0.0575426333 0.0421331267 0.0641775355 0.0146725573 1.9750100000 92922182 95654128 1784418304 -0.1065300927 0.0112229846 -0.0297308769 277 11.0400000000 0.0587896518 0.0421932586 0.0641775355 0.0150018213 2.0937440000 92925044 95654128 1785942016 -0.1146757007 0.0054089404 -0.0369389169 278 11.0800000000 0.0603206195 0.0422584649 0.0641775355 0.0149976618 1.7565400000 93095422 95654128 1787846656 -0.1173441112 0.0048274319 -0.0389492251 279 11.1200000000 0.0614253059 0.0423271633 0.0641775355 0.0149841552 1.4368700000 93097540 95654128 1784672256 -0.1195261478 0.0032152664 -0.0395489782 280 11.1600000000 0.0629474595 0.0424008072 0.0641775355 0.0149740952 1.6464260000 93097974 95654128 1786068992 -0.1207818389 0.0039996728 -0.0398473069 281 11.2000000000 0.0620343499 0.0424706774 0.0641775355 0.0149717392 0.9343140000 93099668 95654128 1787973632 -0.1218949556 0.0011411400 -0.0421416238 282 11.2400000000 0.0626681149 0.0425422995 0.0641775355 0.0149673800 1.0541070000 93101362 95654128 1784672256 -0.1231721938 0.0014027803 -0.0441947915 283 11.2800000000 0.0631045774 0.0426149578 0.0641775355 0.0149578389 1.4962100000 93101796 95654128 1786068992 -0.1243359447 -0.0002306532 -0.0458208434 284 11.3200000000 0.0618023388 0.0426825190 0.0641775355 0.0149591593 1.1243880000 93103490 95654128 1787846656 -0.1253741831 -0.0029856737 -0.0473406911 285 11.3600000000 0.0610187650 0.0427468567 0.0641775355 0.0149557973 2.1098360000 93105184 95654128 1784545280 -0.1265945584 -0.0058371089 -0.0490860455 286 11.4000000000 0.0618515983 0.0428136565 0.0641775355 0.0149441226 2.0485040000 93105734 95654128 1786068992 -0.1280038655 -0.0074363467 -0.0503765531 287 11.4400000000 0.0615041107 0.0428787800 0.0641775355 0.0149244415 1.9322380000 93107428 95654128 1787973632 -0.1278377920 -0.0087803714 -0.0508281775 288 11.4800000000 0.0608563796 0.0429412022 0.0641775355 0.0149046636 1.6672060000 93109122 95654128 1784799232 -0.1298403144 -0.0127323242 -0.0515765958 289 11.5200000000 0.0601543412 0.0430007633 0.0641775355 0.0148858187 1.9119300000 93109556 95654128 1786195968 -0.1297449917 -0.0159469452 -0.0512541942 290 11.5600000000 0.0596306548 0.0430581077 0.0641775355 0.0148692217 1.8226940000 93113742 95654128 1787981824 -0.1298463196 -0.0173176602 -0.0513845608 291 11.6000000000 0.0583625846 0.0431107004 0.0641775355 0.0148501127 1.6610500000 93284112 95654128 1784807424 -0.1308512241 -0.0208886284 -0.0528857820 292 11.6400000000 0.0574242510 0.0431597194 0.0641775355 0.0148264047 1.5353950000 93284546 95654128 1786077184 -0.1315296739 -0.0237346068 -0.0556471832 293 11.6800000000 0.0569166467 0.0432066714 0.0641775355 0.0148011904 1.6331230000 93286240 95654128 1787981824 -0.1309674084 -0.0255306885 -0.0562045090 294 11.7200000000 0.0572152659 0.0432543197 0.0641775355 0.0147768166 2.1172480000 93287934 95654128 1784672256 -0.1304665506 -0.0255094673 -0.0570682809 295 11.7600000000 0.0561211370 0.0432979360 0.0641775355 0.0147560174 1.7647960000 93288368 95654128 1785942016 -0.1297595203 -0.0313215069 -0.0571825318 296 11.8000000000 0.0547293536 0.0433365557 0.0641775355 0.0147338681 1.8192370000 93290062 95654128 1787973632 -0.1294419318 -0.0353308022 -0.0564692430 297 11.8400000000 0.0557000078 0.0433781835 0.0641775355 0.0147259753 2.2374840000 93291756 95654128 1784672256 -0.1309661418 -0.0359053612 -0.0572363660 298 11.8800000000 0.0549436770 0.0434169938 0.0641775355 0.0147555515 2.0592140000 93292190 95654128 1785942016 -0.1321204752 -0.0411087722 -0.0582573637 299 11.9200000000 0.0556514077 0.0434579116 0.0641775355 0.0147609566 1.5050100000 93293884 95654128 1787973632 -0.1331203431 -0.0419935323 -0.0592805445 300 11.9600000000 0.0561210625 0.0435001221 0.0641775355 0.0147758626 1.7546100000 93295578 95654128 1784672256 -0.1341385394 -0.0439718515 -0.0593537129 301 12.0000000000 0.0555885807 0.0435402831 0.0641775355 0.0147831521 2.0053680000 93296012 95654128 1785942016 -0.1350860894 -0.0471831448 -0.0596944392 302 12.0400000000 0.0551139861 0.0435786066 0.0641775355 0.0148261721 1.9641300000 93297804 95654128 1787719680 -0.1373074055 -0.0513422303 -0.0627187043 303 12.0800000000 0.0548352636 0.0436157573 0.0641775355 0.0148098821 1.5059690000 93299498 95654128 1784672256 -0.1386688650 -0.0534119569 -0.0646125898 304 12.1200000000 0.0556723922 0.0436554173 0.0641775355 0.0147978615 2.0792200000 93299932 95654128 1786068992 -0.1405278146 -0.0542159043 -0.0675052106 305 12.1600000000 0.0561752431 0.0436964659 0.0641775355 0.0147884586 1.7660900000 93301766 95654128 1787846656 -0.1418675482 -0.0546461083 -0.0693534836 306 12.2000000000 0.0571187250 0.0437403295 0.0641775355 0.0147879045 1.0441500000 93302316 95654128 1784807424 -0.1424362510 -0.0554821976 -0.0705640465 307 12.2400000000 0.0580358878 0.0437868948 0.0641775355 0.0148008544 1.2820030000 93304010 95654128 1786204160 -0.1438804120 -0.0557463616 -0.0730902702 308 12.2800000000 0.0585323907 0.0438347698 0.0641775355 0.0148141286 1.2257340000 93305704 95654128 1787981824 -0.1454475969 -0.0561945625 -0.0768342540 309 12.3200000000 0.0575605817 0.0438791899 0.0641775355 0.0148044068 1.8331930000 93306138 95654128 1784680448 -0.1465240717 -0.0589116365 -0.0794585571 310 12.3600000000 0.0581244640 0.0439251424 0.0641775355 0.0148082590 2.3442880000 93310184 95654128 1786068992 -0.1486218423 -0.0600613393 -0.0827122107 311 12.4000000000 0.0576657765 0.0439693245 0.0641775355 0.0148078422 2.1941100000 93480706 95654128 1787973632 -0.1502159685 -0.0617816187 -0.0862112790 312 12.4400000000 0.0569215082 0.0440108379 0.0641775355 0.0147969301 0.8328790000 93481140 95654128 1784418304 -0.1514017582 -0.0636035800 -0.0895253941 313 12.4800000000 0.0566182844 0.0440511173 0.0641775355 0.0147854174 0.8356320000 93482950 95654128 1785942016 -0.1524486542 -0.0650886521 -0.0923852697 314 12.5200000000 0.0560890175 0.0440894546 0.0641775355 0.0147801145 1.0060910000 93484644 95654128 1787719680 -0.1530523449 -0.0668688118 -0.0941114053 315 12.5600000000 0.0563240908 0.0441282947 0.0641775355 0.0147798695 1.0276780000 93485078 95654128 1784672256 -0.1544864923 -0.0676700547 -0.0961231440 316 12.6000000000 0.0561545491 0.0441663524 0.0641775355 0.0147777760 0.8788340000 93486772 95654128 1786068992 -0.1558668464 -0.0689185262 -0.0992949232 317 12.6400000000 0.0553735122 0.0442017063 0.0641775355 0.0147614680 1.3817390000 93488606 95654128 1787846656 -0.1568483561 -0.0708160996 -0.1011809930 318 12.6800000000 0.0554590747 0.0442371068 0.0641775355 0.0147477313 2.0158320000 93489040 95654128 1784672256 -0.1584281474 -0.0715758950 -0.1041510925 319 12.7200000000 0.0557207614 0.0442731057 0.0641775355 0.0147654431 0.9143680000 93490734 95654128 1786195968 -0.1604673117 -0.0724800453 -0.1086953953 320 12.7600000000 0.0561521463 0.0443102277 0.0641775355 0.0147526846 0.7462750000 93492428 95654128 1788100608 -0.1614863724 -0.0727736205 -0.1109667942 321 12.8000000000 0.0571793541 0.0443503185 0.0641775355 0.0147428107 1.0061010000 93492862 95654128 1784545280 -0.1631215662 -0.0718601122 -0.1133812219 322 12.8400000000 0.0573245063 0.0443906110 0.0641775355 0.0147285537 1.1050230000 93494556 95654128 1785942016 -0.1643195301 -0.0722903311 -0.1153490320 323 12.8800000000 0.0567523316 0.0444288825 0.0641775355 0.0147114975 0.9045120000 93495130 95654128 1787846656 -0.1657500565 -0.0735069364 -0.1177668497 324 12.9200000000 0.0552489199 0.0444622777 0.0641775355 0.0146947247 0.8760790000 93496940 95654128 1784799232 -0.1666533649 -0.0750510097 -0.1203235015 325 12.9600000000 0.0559310876 0.0444975664 0.0641775355 0.0146776147 0.9506990000 93498634 95654128 1786068992 -0.1680297405 -0.0743222907 -0.1214866489 326 13.0000000000 0.0558173247 0.0445322895 0.0641775355 0.0146586686 0.7675040000 93499068 95654128 1788100608 -0.1694077551 -0.0743532479 -0.1235967577 327 13.0400000000 0.0557884611 0.0445667121 0.0641775355 0.0146391198 0.9069770000 93500762 95654128 1784545280 -0.1706978381 -0.0732159019 -0.1256349683 328 13.0800000000 0.0574194938 0.0446058974 0.0641775355 0.0146232114 1.0633860000 93502456 95654128 1785942016 -0.1726161093 -0.0705658272 -0.1270676702 329 13.1200000000 0.0570542738 0.0446437344 0.0641775355 0.0146094753 1.0273920000 93503030 95654128 1787609088 -0.1735716462 -0.0689590499 -0.1292928457 330 13.1600000000 0.0568902902 0.0446808452 0.0641775355 0.0145926296 0.9949570000 93504724 95654128 1784418304 -0.1753657311 -0.0676713362 -0.1313234568 331 13.2000000000 0.0581007339 0.0447213887 0.0641775355 0.0145762171 1.0286940000 93506418 95654128 1785942016 -0.1769769043 -0.0647247434 -0.1318665296 332 13.2400000000 0.0579124205 0.0447611207 0.0641775355 0.0145557837 2.0574320000 93506852 95654128 1787846656 -0.1785870641 -0.0626055896 -0.1338486224 333 13.2800000000 0.0575739592 0.0447995977 0.0641775355 0.0145467777 1.3131120000 93508546 95654128 1784545280 -0.1795490980 -0.0603338219 -0.1347905695 334 13.3200000000 0.0576902255 0.0448381924 0.0641775355 0.0145957228 2.1138780000 93510240 95654128 1786204160 -0.1819574684 -0.0547128879 -0.1368370652 335 13.3600000000 0.0585822575 0.0448792194 0.0641775355 0.0145817705 2.0580510000 93513126 95654128 1787981824 -0.1833190918 -0.0511616506 -0.1371159703 336 13.4000000000 0.0591253601 0.0449216187 0.0641775355 0.0145668343 2.5479770000 93683508 95654128 1784553472 -0.1848496795 -0.0478258803 -0.1379912943 337 13.4400000000 0.0577823631 0.0449597811 0.0641775355 0.0145576799 1.4519580000 93685202 95654128 1786195968 -0.1852019727 -0.0464699864 -0.1391180009 338 13.4800000000 0.0576588102 0.0449973522 0.0641775355 0.0145572702 1.6798380000 93685636 95654128 1788100608 -0.1857360303 -0.0440859273 -0.1399202198 339 13.5200000000 0.0586797781 0.0450377133 0.0641775355 0.0145657774 2.2626680000 93687330 95654128 1784799232 -0.1868690252 -0.0403726362 -0.1395423263 340 13.5600000000 0.0590004660 0.0450787803 0.0641775355 0.0145666137 2.1638730000 93689024 95654128 1786322944 -0.1871750355 -0.0374139771 -0.1388972253 341 13.6000000000 0.0597279817 0.0451217398 0.0641775355 0.0145611329 1.6031570000 93689598 95654128 1785561088 -0.1884741932 -0.0346007794 -0.1378217638 342 13.6400000000 0.0595112778 0.0451638145 0.0641775355 0.0145618829 1.6222480000 93691292 95654128 1786957824 -0.1894201338 -0.0313608348 -0.1390732527 343 13.6800000000 0.0601383075 0.0452074719 0.0641775355 0.0145655668 1.5046130000 93691726 95654128 1785053184 -0.1902878881 -0.0284867734 -0.1383370608 344 13.7200000000 0.0601610765 0.0452509417 0.0641775355 0.0145783091 1.5070480000 93693420 95654128 1786576896 -0.1907180697 -0.0253261495 -0.1387210041 345 13.7600000000 0.0603073575 0.0452945834 0.0641775355 0.0147528034 1.2927870000 93695346 95654128 1785942016 -0.1925357282 -0.0197833050 -0.1384381801 346 13.8000000000 0.0601271503 0.0453374521 0.0641775355 0.0147595296 2.0167290000 93695780 95654128 1787338752 -0.1933098882 -0.0178107861 -0.1383130550 347 13.8400000000 0.0613547452 0.0453836115 0.0641775355 0.0147582425 2.2338810000 93697614 95654128 1784799232 -0.1946226209 -0.0139711602 -0.1380832046 348 13.8800000000 0.0609292984 0.0454282830 0.0641775355 0.0147435676 2.9007350000 93699308 95654128 1786195968 -0.1952494234 -0.0113221072 -0.1383441985 349 13.9200000000 0.0609946400 0.0454728857 0.0641775355 0.0147240566 1.3841860000 93699742 95654128 1785688064 -0.1964424551 -0.0078276899 -0.1388227493 350 13.9600000000 0.0603492856 0.0455153897 0.0641775355 0.0147066469 1.7079840000 93701436 95654128 1787084800 -0.1971607059 -0.0059162071 -0.1392396092 351 14.0000000000 0.0592811666 0.0455546085 0.0641775355 0.0147195758 2.2832170000 93703130 95654128 1784942592 -0.1979203075 -0.0037794588 -0.1401146948 352 14.0400000000 0.0588662140 0.0455924255 0.0641775355 0.0147240293 1.7494020000 93703564 95654128 1786449920 -0.1982721686 -0.0009806065 -0.1400070637 353 14.0800000000 0.0596024804 0.0456321141 0.0641775355 0.0147238184 1.3230290000 93705258 95654128 1785831424 -0.1991616786 0.0032006467 -0.1394172311 354 14.1200000000 0.0597774759 0.0456720727 0.0641775355 0.0147546703 2.1129990000 93706952 95654128 1787355136 -0.1994691491 0.0066092527 -0.1387013048 355 14.1600000000 0.0600577034 0.0457125956 0.0641775355 0.0147741559 2.1018320000 93707386 95654128 1784688640 -0.1998294443 0.0098361699 -0.1377532631 356 14.2000000000 0.0601958893 0.0457532790 0.0641775355 0.0147786031 1.6488400000 93709080 95654128 1786085376 -0.2005138844 0.0136443786 -0.1385604739 357 14.2400000000 0.0599028319 0.0457929136 0.0641775355 0.0147744226 2.1438500000 93710774 95654128 1787854848 -0.2010588497 0.0161764752 -0.1380230784 358 14.2800000000 0.0598862581 0.0458322805 0.0641775355 0.0147705224 1.8557150000 93711208 95654128 1784553472 -0.2018386275 0.0185358040 -0.1376996338 359 14.3200000000 0.0602825433 0.0458725319 0.0641775355 0.0147758158 2.5694130000 93712902 95654128 1785950208 -0.2021653056 0.0217174813 -0.1360810101 360 14.3600000000 0.0596903376 0.0459109147 0.0641775355 0.0147801720 2.0875830000 93714736 95654128 1787854848 -0.2025861740 0.0237775221 -0.1357814968 361 14.4000000000 0.0598776899 0.0459496039 0.0641775355 0.0147711625 2.3801140000 93715170 95654128 1784553472 -0.2028947324 0.0270004608 -0.1355809569 362 14.4400000000 0.0600679889 0.0459886049 0.0641775355 0.0147736019 2.2095530000 93716864 95654128 1786077184 -0.2025683224 0.0302498080 -0.1350364238 363 14.4800000000 0.0606883317 0.0460291000 0.0641775355 0.0147784612 1.5488290000 93718558 95654128 1787981824 -0.2021333277 0.0329035595 -0.1327460557 364 14.5200000000 0.0609513186 0.0460700952 0.0641775355 0.0147791724 2.1231450000 93718992 95654128 1784807424 -0.2023995072 0.0358327143 -0.1316985041 365 14.5600000000 0.0594588965 0.0461067768 0.0641775355 0.0147897259 1.8560530000 93722942 95654128 1786204160 -0.2028169334 0.0352119990 -0.1308793873 366 14.6000000000 0.0600775704 0.0461449484 0.0641775355 0.0148786311 1.7703080000 93892204 95654128 1788108800 -0.2026390731 0.0417282879 -0.1288021356 367 14.6400000000 0.0605775304 0.0461842742 0.0641775355 0.0148908269 1.2753460000 93893898 95654128 1784553472 -0.2022157609 0.0454779901 -0.1284380108 368 14.6800000000 0.0603179634 0.0462226810 0.0641775355 0.0149015769 1.9781630000 93895592 95654128 1786077184 -0.2014656812 0.0476448499 -0.1261037439 369 14.7200000000 0.0609589256 0.0462626166 0.0641775355 0.0149184979 1.6584760000 93896142 95654128 1788243968 -0.2007394135 0.0549430698 -0.1231468171 370 14.7600000000 0.0617059655 0.0463043554 0.0641775355 0.0149136678 1.6459350000 93897836 95654128 1784180736 -0.1993695647 0.0593799725 -0.1214414015 371 14.8000000000 0.0618390925 0.0463462280 0.0641775355 0.0149127266 1.8469980000 93899530 95654128 1785704448 -0.1985287219 0.0613921434 -0.1184130460 372 14.8400000000 0.0610964671 0.0463858792 0.0641775355 0.0149156037 2.0346440000 93900104 95654128 1787609088 -0.1972546428 0.0624009036 -0.1153974608 373 14.8800000000 0.0617378503 0.0464270373 0.0641775355 0.0149101716 2.3974710000 93904730 95654128 1784561664 -0.1962801218 0.0658883974 -0.1128529608 374 14.9200000000 0.0610446930 0.0464661219 0.0641775355 0.0149028411 1.7271600000 94075100 95654128 1785950208 -0.1943765134 0.0685034022 -0.1105683669 375 14.9600000000 0.0601572096 0.0465026315 0.0641775355 0.0148990816 1.3005460000 94075534 95654128 1787981824 -0.1922133416 0.0705553368 -0.1075904593 376 15.0000000000 0.0592939183 0.0465366508 0.0641775355 0.0149066337 1.9576690000 94077228 95654128 1784680448 -0.1901709139 0.0722201914 -0.1053907648 377 15.0400000000 0.0592052042 0.0465702544 0.0641775355 0.0149232582 1.7326710000 94078922 95654128 1786077184 -0.1882235557 0.0743899867 -0.1027333960 378 15.0800000000 0.0590113923 0.0466031675 0.0641775355 0.0149327081 1.1086060000 94082020 95654128 1787981824 -0.1858529150 0.0773585960 -0.1004452184 379 15.1200000000 0.0594140887 0.0466369694 0.0641775355 0.0149274651 1.5506300000 94252418 95654128 1784807424 -0.1842171699 0.0798652843 -0.0979585797 380 15.1600000000 0.0590260252 0.0466695722 0.0641775355 0.0149331593 2.4121640000 94254112 95654128 1786077184 -0.1817523390 0.0814982057 -0.0955280066 381 15.2000000000 0.0583290420 0.0467001745 0.0641775355 0.0149389360 2.5208920000 94254662 95654128 1788235776 -0.1795972437 0.0824210867 -0.0940584093 382 15.2400000000 0.0583607480 0.0467306995 0.0641775355 0.0149349310 2.4647460000 94256356 95654128 1783918592 -0.1771560162 0.0841463730 -0.0915799364 383 15.2800000000 0.0591029190 0.0467630030 0.0641775355 0.0149272815 1.6609230000 94258050 95654128 1785442304 -0.1751334816 0.0868406519 -0.0896862000 384 15.3200000000 0.0591296554 0.0467952078 0.0641775355 0.0149417717 1.9596190000 94260580 95654128 1787219968 -0.1734091640 0.0877570435 -0.0876896083 385 15.3600000000 0.0592684709 0.0468276059 0.0641775355 0.0149416558 2.2800050000 94430978 95654128 1784426496 -0.1715487093 0.0878243670 -0.0854488835 386 15.4000000000 0.0594541840 0.0468603172 0.0641775355 0.0149391622 1.4830910000 94431412 95654128 1785950208 -0.1693449318 0.0902692750 -0.0838165358 387 15.4400000000 0.0598207600 0.0468938067 0.0641775355 0.0149368438 0.9729980000 94433106 95654128 1787854848 -0.1663894951 0.0918013975 -0.0812485740 388 15.4800000000 0.0593355075 0.0469258730 0.0641775355 0.0149455591 0.7856300000 94434800 95654128 1784807424 -0.1631066650 0.0921875983 -0.0788819417 389 15.5200000000 0.0588019341 0.0469564027 0.0641775355 0.0149499211 1.0294480000 94435234 95654128 1786212352 -0.1607370377 0.0930526033 -0.0768442973 390 15.5600000000 0.0590677634 0.0469874575 0.0641775355 0.0149409854 0.8306150000 94439564 95654128 1787863040 -0.1580408216 0.0933211520 -0.0738505721 391 15.6000000000 0.0591686852 0.0470186115 0.0641775355 0.0149380969 0.9438800000 94609974 95654128 1784561664 -0.1555916667 0.0941516086 -0.0714050010 392 15.6400000000 0.0589733496 0.0470491083 0.0641775355 0.0149365355 0.8910090000 94610408 95654128 1786085376 -0.1521462351 0.0940122753 -0.0689026862 393 15.6800000000 0.0593226254 0.0470803386 0.0641775355 0.0149332780 0.7409220000 94612102 95654128 1787863040 -0.1499835253 0.0946354493 -0.0669342428 394 15.7200000000 0.0593198612 0.0471114034 0.0641775355 0.0149368359 0.7133360000 94613796 95654128 1784561664 -0.1473104507 0.0958268344 -0.0649308041 395 15.7600000000 0.0594151691 0.0471425522 0.0641775355 0.0149398305 0.8104130000 94614230 95654128 1786101760 -0.1447590441 0.0956029296 -0.0627305955 396 15.8000000000 0.0589180849 0.0471722884 0.0641775355 0.0149340805 0.6704940000 94616064 95654128 1787990016 -0.1413587183 0.0959907174 -0.0609053485 397 15.8400000000 0.0584795997 0.0472007702 0.0641775355 0.0149256244 0.6861830000 94620170 95654128 1784815616 -0.1380221695 0.0967875123 -0.0586157516 398 15.8800000000 0.0588422865 0.0472300203 0.0641775355 0.0149175120 0.8078570000 94789320 95654128 1786077184 -0.1368606985 0.0978663117 -0.0588195547 399 15.9200000000 0.0584608726 0.0472581678 0.0641775355 0.0149127920 0.8307470000 94791014 95654128 1788108800 -0.1334381104 0.0981305689 -0.0567972921 400 15.9600000000 0.0582439043 0.0472856321 0.0641775355 0.0149075229 0.7675150000 94792708 95654128 1784459264 -0.1316567063 0.0971416086 -0.0561142527 401 16.0000000000 0.0581930093 0.0473128326 0.0641775355 0.0148945631 0.7693290000 94793142 95654128 1785823232 -0.1297094673 0.0964198187 -0.0548762679 402 16.0400000000 0.0581449345 0.0473397781 0.0641775355 0.0148864111 0.7256870000 94794976 95654128 1787617280 -0.1277585924 0.0963911265 -0.0537010245 403 16.0800000000 0.0579526164 0.0473661127 0.0641775355 0.0148856816 0.7270330000 94795410 95654128 1784553472 -0.1262231320 0.0942762569 -0.0527786575 404 16.1200000000 0.0576046333 0.0473914556 0.0641775355 0.0148925228 0.7281510000 94799736 95654128 1785966592 -0.1244856566 0.0937356949 -0.0523453243 405 16.1600000000 0.0578468814 0.0474172714 0.0641775355 0.0148929445 0.8442110000 94970030 95654128 1787854848 -0.1224619076 0.0951026976 -0.0517488606 406 16.2000000000 0.0574136227 0.0474418930 0.0641775355 0.0148879722 0.7528170000 94970464 95654128 1784934400 -0.1196477488 0.0952155441 -0.0505001694 407 16.2400000000 0.0565228239 0.0474642048 0.0641775355 0.0148981475 0.8867800000 94972158 95654128 1786204160 -0.1162480339 0.0944119096 -0.0492446981 408 16.2800000000 0.0555959009 0.0474841355 0.0641775355 0.0149031320 0.9898930000 94973992 95654128 1787854848 -0.1131358221 0.0938084796 -0.0482142121 409 16.3200000000 0.0552098788 0.0475030248 0.0641775355 0.0148943803 0.7885410000 94974426 95654128 1784553472 -0.1093667820 0.0938734859 -0.0462457463 410 16.3600000000 0.0551728867 0.0475217318 0.0641775355 0.0148961933 0.9483260000 94976120 95654128 1785950208 -0.1063287705 0.0931008533 -0.0444233567 411 16.3999999990 0.0551961288 0.0475404043 0.0641775355 0.0149079996 0.9626510000 94977814 95654128 1787727872 -0.1037549824 0.0909973830 -0.0430393741 412 16.4400000000 0.0546535179 0.0475576691 0.0641775355 0.0149092836 0.7685800000 94980216 95654128 1784455168 -0.1016896144 0.0903712884 -0.0422341004 413 16.4800000000 0.0543439537 0.0475741008 0.0641775355 0.0149146991 0.7479810000 95150626 95654128 1785950208 -0.0984995142 0.0886075720 -0.0403819121 414 16.5200000000 0.0542815067 0.0475903023 0.0641775355 0.0149073872 0.6749570000 95152460 95654128 1787981824 -0.0964739993 0.0886165351 -0.0394718125 415 16.5599999990 0.0543648377 0.0476066265 0.0641775355 0.0148962958 0.7634350000 95152894 95654128 1784807424 -0.0945730358 0.0890850201 -0.0387700498 416 16.6000000000 0.0537705123 0.0476214435 0.0641775355 0.0148845067 0.7331200000 95154588 95654128 1786093568 -0.0929847062 0.0885723829 -0.0380406380 417 16.6400000000 0.0536807068 0.0476359741 0.0641775355 0.0148759601 0.9888920000 95156282 95654128 1787981824 -0.0906447545 0.0889681578 -0.0371412784 418 16.6800000000 0.0539314561 0.0476510351 0.0641775355 0.0148656303 0.7830790000 95156716 95654128 1784680448 -0.0905195326 0.0878670439 -0.0371510349 419 16.7199999990 0.0533631556 0.0476646678 0.0641775355 0.0148604694 0.9075980000 95158394 95654128 1786077184 -0.0882420093 0.0860721320 -0.0364129022 420 16.7600000000 0.0538389646 0.0476793685 0.0641775355 0.0148571005 0.7316070000 95158968 95654128 1787854848 -0.0865208432 0.0853657350 -0.0350664929 421 16.8000000000 0.0533897839 0.0476929325 0.0641775355 0.0148604960 0.6872430000 95160662 95654128 1784692736 -0.0848036408 0.0821376368 -0.0330744162 422 16.8400000000 0.0534888133 0.0477066668 0.0641775355 0.0148538419 0.7883760000 95162356 95654128 1786077184 -0.0831447095 0.0830139220 -0.0323576145 423 16.8799999990 0.0530504696 0.0477192999 0.0641775355 0.0148497981 0.7290420000 95162790 95654128 1787981824 -0.0804621950 0.0821111351 -0.0315825753 424 16.9200000000 0.0531098358 0.0477320134 0.0641775355 0.0148405360 0.8278350000 95164484 95654128 1784680448 -0.0782464519 0.0804156959 -0.0306490567 425 16.9600000000 0.0528706126 0.0477441042 0.0641775355 0.0148426181 0.8095440000 95166178 95654128 1785950208 -0.0748988986 0.0813721642 -0.0291129369 426 17.0000000000 0.0529276952 0.0477562723 0.0641775355 0.0148419871 0.7225780000 95166752 95654128 1787854848 -0.0736748427 0.0758970901 -0.0272324290 427 17.0400000000 0.0520762242 0.0477663893 0.0641775355 0.0148373631 0.8480910000 95168446 95654128 1784553472 -0.0697206780 0.0744940341 -0.0259905308 428 17.0800000000 0.0512370989 0.0477744984 0.0641775355 0.0148304550 0.8867690000 95170140 95654128 1785950208 -0.0659403726 0.0743856058 -0.0251640379 429 17.1200000000 0.0509535745 0.0477819088 0.0641775355 0.0148262618 0.7115070000 95170558 95654128 1787854848 -0.0640461147 0.0727681294 -0.0243195053 430 17.1600000000 0.0504960753 0.0477882208 0.0641775355 0.0148199535 0.7488940000 95172252 95654128 1784807424 -0.0619746298 0.0737487003 -0.0234836861 431 17.2000000000 0.0516435951 0.0477971660 0.0641775355 0.0148124086 0.6886580000 95173946 95654128 1786245120 -0.0605870932 0.0740733892 -0.0230841357 432 17.2400000000 0.0516517572 0.0478060887 0.0641775355 0.0148080116 0.9084290000 95174520 95654128 1787990016 -0.0575852133 0.0700352862 -0.0219246168 433 17.2800000000 0.0512694716 0.0478140873 0.0641775355 0.0148207743 0.7039170000 95176214 95654128 1784688640 -0.0562624186 0.0654826090 -0.0201052781 434 17.3200000000 0.0491555855 0.0478171783 0.0641775355 0.0148301941 0.7109670000 95177908 95654128 1785958400 -0.0518182069 0.0622153133 -0.0189808141 435 17.3600000000 0.0502371006 0.0478227413 0.0641775355 0.0148317200 0.6674860000 95178342 95654128 1787625472 -0.0510492437 0.0588330887 -0.0184529889 436 17.4000000000 0.0494063906 0.0478263735 0.0641775355 0.0148300435 0.6693940000 95180036 95654128 1784688640 -0.0498393923 0.0554472171 -0.0169960856 437 17.4400000000 0.0496054739 0.0478304447 0.0641775355 0.0148263619 0.6476160000 95181730 95654128 1786085376 -0.0490913019 0.0551270433 -0.0160645861 438 17.4800000000 0.0477360375 0.0478302292 0.0641775355 0.0148444481 0.6633470000 95182304 95654128 1787981824 -0.0480832979 0.0519919246 -0.0138981752 439 17.5200000000 0.0478100739 0.0478301833 0.0641775355 0.0148501135 0.8038680000 95183998 95654128 1784680448 -0.0495362356 0.0497552007 -0.0137364212 440 17.5600000000 0.0453224145 0.0478244838 0.0641775355 0.0148616593 0.8137180000 95184432 95654128 1786077184 -0.0507443026 0.0435353294 -0.0125484420 441 17.6000000000 0.0452320166 0.0478186052 0.0641775355 0.0148724017 0.6701620000 95186126 95654128 1787981824 -0.0525573120 0.0413918607 -0.0113325100 442 17.6400000000 0.0446764566 0.0478114962 0.0641775355 0.0149527987 0.6644450000 95187820 95654128 1784692736 -0.0593470410 0.0433792137 -0.0123577425 443 17.6800000000 0.0419606604 0.0477982889 0.0641775355 0.0149683992 0.6917630000 95188254 95654128 1786077184 -0.0625041127 0.0376713946 -0.0110254698 444 17.7200000000 0.0403539166 0.0477815223 0.0641775355 0.0149835712 0.7281490000 95190088 95654128 1787854848 -0.0643602312 0.0319071449 -0.0090228487 445 17.7600000000 0.0408129767 0.0477658627 0.0641775355 0.0149882971 0.6488310000 95191782 95654128 1784565760 -0.0659882054 0.0311276577 -0.0088102203 446 17.8000000000 0.0409765765 0.0477506401 0.0641775355 0.0150007966 0.7374830000 95192184 95654128 1786077184 -0.0680184960 0.0270462278 -0.0066388855 447 17.8400000000 0.0416538380 0.0477370007 0.0641775355 0.0150008928 0.6319160000 95193878 95654128 1787854848 -0.0674925297 0.0223237984 -0.0043518427 448 17.8800000000 0.0435205065 0.0477275889 0.0641775355 0.0149881690 0.6510290000 95195572 95654128 1784569856 -0.0683301687 0.0231915694 -0.0045082085 449 17.9200000000 0.0434157476 0.0477179857 0.0641775355 0.0149803536 0.7978770000 95196006 95654128 1786093568 -0.0695485026 0.0208379980 -0.0013994458 450 17.9600000000 0.0427951068 0.0477070459 0.0641775355 0.0149696497 0.8478500000 95197840 95654128 1788108800 -0.0680515766 0.0175317340 0.0001139056 451 18.0000000000 0.0407941788 0.0476917181 0.0641775355 0.0149657286 0.6896490000 95199534 95654128 1784807424 -0.0666807517 0.0148858782 0.0019742767 452 18.0400000000 0.0417538024 0.0476785811 0.0641775355 0.0149580910 0.8404800000 95199968 95654128 1786077184 -0.0671007857 0.0134412851 0.0053655133 453 18.0800000000 0.0434279852 0.0476691979 0.0641775355 0.0149448514 0.8879820000 95201662 95654128 1787871232 -0.0678514689 0.0134944133 0.0077412729 454 18.1200000000 0.0440688580 0.0476612676 0.0641775355 0.0149298526 0.7063830000 95203356 95654128 1784680448 -0.0674900860 0.0151531864 0.0112056872 455 18.1600000000 0.0457053967 0.0476569690 0.0641775355 0.0149141076 0.7472310000 95203790 95654128 1785950208 -0.0666862503 0.0163020696 0.0145745901 456 18.2000000000 0.0479164608 0.0476575380 0.0641775355 0.0149060848 0.6588850000 95205624 95654128 1787854848 -0.0678513050 0.0158034805 0.0196987335 457 18.2400000000 0.0482938327 0.0476589304 0.0641775355 0.0148956896 0.7071710000 95206058 95654128 1784553472 -0.0683830455 0.0188128054 0.0237185881 458 18.2800000000 0.0484680980 0.0476606971 0.0641775355 0.0148899569 0.9032820000 95207752 95654128 1785966592 -0.0683836266 0.0160885174 0.0316010416 459 18.3200000000 0.0501273461 0.0476660711 0.0641775355 0.0148769699 0.9084260000 95209446 95654128 1787854848 -0.0676121712 0.0147928447 0.0398830175 460 18.3600000000 0.0451479331 0.0476605969 0.0641775355 0.0148654509 0.9743340000 95209880 95654128 1784807424 -0.0620708838 0.0154563319 0.0451019295 461 18.4000000000 0.0428369343 0.0476501334 0.0641775355 0.0148508674 0.7453230000 95211574 95654128 1786077184 -0.0590997078 0.0146186836 0.0519278571 462 18.4400000000 0.0427581444 0.0476395447 0.0641775355 0.0148350668 0.7429130000 95213408 95654128 1787727872 -0.0554327480 0.0172496308 0.0582825914 463 18.4800000000 0.0476896465 0.0476396529 0.0641775355 0.0148198304 0.7071000000 95213842 95654128 1784426496 -0.0587512106 0.0241675619 0.0661243871 464 18.5200000000 0.0464011431 0.0476369837 0.0641775355 0.0148077526 0.8367050000 95215536 95654128 1785966592 -0.0568168163 0.0267014727 0.0738938376 465 18.5600000000 0.0455797054 0.0476325594 0.0641775355 0.0147960133 0.8061710000 95217230 95654128 1787727872 -0.0521486774 0.0345649943 0.0904460922 466 18.6000000000 0.0489452258 0.0476353763 0.0641775355 0.0147814133 0.7605400000 95217696 95654128 1784553472 -0.0512725189 0.0423982106 0.1007247865 467 18.6400000000 0.0502277799 0.0476409275 0.0641775355 0.0147660339 0.8158410000 95219390 95654128 1786077184 -0.0491999201 0.0447451845 0.1114933044 468 18.6800000000 0.0510066971 0.0476481193 0.0641775355 0.0147518338 0.7794190000 95221224 95654128 1787854848 -0.0469718501 0.0519827493 0.1211537570 469 18.7200000000 0.0506597087 0.0476545406 0.0641775355 0.0147432300 0.8234130000 95221658 95654128 1784692736 -0.0458121337 0.0540003590 0.1330554038 470 18.7600000000 0.0520316772 0.0476638537 0.0641775355 0.0147362365 0.8269170000 95223352 95654128 1786077184 -0.0442772843 0.0611501224 0.1441164166 471 18.8000000000 0.0550213791 0.0476794747 0.0641775355 0.0147269193 0.9690490000 95225046 95654128 1787981824 -0.0442236811 0.0703876093 0.1560569853 472 18.8400000000 0.0562893786 0.0476977161 0.0641775355 0.0147118876 0.8344940000 95225480 95654128 1784680448 -0.0431733914 0.0756257921 0.1680656821 473 18.8800000000 0.0546117350 0.0477123334 0.0641775355 0.0146965094 0.7874630000 95227174 95654128 1786077184 -0.0386097319 0.0826821253 0.1810152829 474 18.9200000000 0.0528423823 0.0477231563 0.0641775355 0.0146845674 0.8758040000 95227748 95654128 1787854848 -0.0338990055 0.0878579840 0.1920598149 475 18.9600000000 0.0530420840 0.0477343541 0.0641775355 0.0146793269 0.9072880000 95229442 95654128 1784680448 -0.0288396217 0.0951819047 0.2039342076 476 19.0000000000 0.0529152155 0.0477452382 0.0641775355 0.0146687781 1.1372290000 95231136 95654128 1786212352 -0.0250938907 0.0979452282 0.2171439826 477 19.0400000000 0.0523435026 0.0477548782 0.0641775355 0.0146567770 1.0155310000 95231570 95654128 1787879424 -0.0218569413 0.1061309204 0.2276459783 478 19.0800000000 0.0529118814 0.0477656669 0.0641775355 0.0146427102 0.9949410000 95233264 95654128 1784561664 -0.0195105597 0.1120611057 0.2413060516 479 19.1200000000 0.0506597199 0.0477717088 0.0641775355 0.0146304151 0.8937140000 95234974 95654128 1785958400 -0.0162064638 0.1108266562 0.2538366020 480 19.1600000000 0.0499664880 0.0477762812 0.0641775355 0.0146224569 1.0721860000 95235548 95654128 1787863040 -0.0109712174 0.1172502860 0.2629082799 481 19.2000000000 0.0464149155 0.0477734509 0.0641775355 0.0146073539 1.9687690000 95237242 95654128 1784553472 -0.0068827067 0.1250186563 0.2737962902 482 19.2400000000 0.0458348617 0.0477694290 0.0641775355 0.0146020469 0.9078930000 95238936 95654128 1785950208 -0.0023302054 0.1295043975 0.2847579122 483 19.2800000000 0.0461211912 0.0477660165 0.0641775355 0.0146043419 0.8085980000 95239370 95654128 1787854848 -0.0001016927 0.1302583814 0.2960213125 484 19.3200000000 0.0478497036 0.0477661894 0.0641775355 0.0146054158 0.7966630000 95241064 95654128 1784807424 0.0021283934 0.1326617897 0.3075537980 485 19.3600000000 0.0471522771 0.0477649236 0.0641775355 0.0145920291 0.7659100000 95242758 95654128 1786077184 0.0036150995 0.1338661313 0.3196365833 486 19.4000000000 0.0464119986 0.0477621398 0.0641775355 0.0145771086 1.0437240000 95243348 95654128 1787981824 0.0071112942 0.1390780807 0.3318711221 487 19.4400000000 0.0480174683 0.0477626641 0.0641775355 0.0145622643 1.8371220000 95245042 95654128 1784426496 0.0072534848 0.1460689306 0.3429229558 488 19.4800000000 0.0478497818 0.0477628426 0.0641775355 0.0145479865 2.1131140000 95246736 95654128 1785823232 0.0086017614 0.1471942961 0.3544076383 489 19.5200000000 0.0453286245 0.0477578646 0.0641775355 0.0145349502 1.0686730000 95247286 95654128 1787600896 0.0119105456 0.1546519846 0.3639320433 490 19.5600000000 0.0468940362 0.0477561017 0.0641775355 0.0145208380 0.9016130000 95249328 95654128 1784680448 0.0120869512 0.1627816558 0.3739937544 491 19.6000000000 0.0464561917 0.0477534543 0.0641775355 0.0145065354 1.1198530000 95251138 95654128 1786077184 0.0164629985 0.1703907698 0.3837037086 492 19.6400000000 0.0472457521 0.0477524223 0.0641775355 0.0144922065 0.8642550000 95251828 95654128 1787981824 0.0166265331 0.1761301011 0.3930656612 493 19.6800000000 0.0458028987 0.0477484679 0.0641775355 0.0144781285 0.9577270000 95253522 95654128 1784680448 0.0181817338 0.1778257936 0.4036256075 494 19.7200000000 0.0455750376 0.0477440683 0.0641775355 0.0144636014 0.8910760000 95253956 95654128 1786077184 0.0179354101 0.1781855822 0.4141646624 495 19.7600000000 0.0439147875 0.0477363323 0.0641775355 0.0144504068 0.9393020000 95255650 95654128 1787854848 0.0195748154 0.1816991568 0.4246926606 496 19.8000000000 0.0436886586 0.0477281717 0.0641775355 0.0144372005 0.9163410000 95257344 95654128 1784680448 0.0205854252 0.1892831922 0.4349007607 497 19.8400000000 0.0451231673 0.0477229303 0.0641775355 0.0144241858 0.9441420000 95257778 95654128 1786077184 0.0205611512 0.1978007406 0.4456734657 498 19.8800000000 0.0447642729 0.0477169892 0.0641775355 0.0144143424 0.8497070000 95259612 95654128 1787854848 0.0201862808 0.2052207887 0.4558871388 499 19.9200000000 0.0445160381 0.0477105744 0.0641775355 0.0144063237 0.9877000000 95261306 95654128 1784553472 0.0203230493 0.2122035623 0.4673072994 500 19.9600000000 0.0446641035 0.0477044815 0.0641775355 0.0143955795 1.0769340000 95261740 95654128 1786077184 0.0198894255 0.2149479985 0.4780964255 501 20.0000000000 0.0429591909 0.0476950099 0.0641775355 0.0143873363 1.1527200000 95263434 95654128 1787981824 0.0203918517 0.2174071372 0.4886420667 502 20.0400000000 0.0437812656 0.0476872136 0.0641775355 0.0143770904 1.6344470000 95265128 95654128 1784807424 0.0175567698 0.2220242918 0.4995801151 503 20.0800000000 0.0414609276 0.0476748353 0.0641775355 0.0143677548 1.9231210000 95265562 95654128 1786077184 0.0174526535 0.2272488475 0.5105053186 504 20.1200000000 0.0421111323 0.0476637962 0.0641775355 0.0143534903 2.1325670000 95267396 95654128 1787854848 0.0142540289 0.2327163666 0.5210326314 505 20.1600000000 0.0422929004 0.0476531607 0.0641775355 0.0143395498 1.1173060000 95269090 95654128 1784807424 0.0126263779 0.2392754406 0.5318168402 506 20.2000000000 0.0434113406 0.0476447777 0.0641775355 0.0143295868 0.9774910000 95269524 95654128 1786085376 0.0103683230 0.2496079206 0.5419534445 507 20.2400000000 0.0442961082 0.0476381728 0.0641775355 0.0143248985 1.0195460000 95271218 95654128 1787990016 0.0077543473 0.2560968697 0.5522530675 508 20.2800000000 0.0447007902 0.0476323906 0.0641775355 0.0143232353 0.9577900000 95272912 95654128 1784688640 0.0057068947 0.2613867223 0.5622854829 509 20.3200000000 0.0450203307 0.0476272588 0.0641775355 0.0143335637 1.1989800000 95273346 95654128 1785958400 0.0028599356 0.2681856453 0.5720626116 510 20.3600000000 0.0449700467 0.0476220486 0.0641775355 0.0143321113 2.0663900000 95275180 95654128 1787863040 0.0000967267 0.2735607028 0.5819166303 511 20.4000000000 0.0449258797 0.0476167723 0.0641775355 0.0143326750 1.3842700000 95275614 95654128 1784688640 -0.0016284795 0.2785537243 0.5908079147 512 20.4400000000 0.0456187725 0.0476128700 0.0641775355 0.0143365501 2.2222100000 95277308 95654128 1785950208 -0.0018988044 0.2859502435 0.5992071033 513 20.4800000000 0.0459475778 0.0476096238 0.0641775355 0.0143360562 2.3338110000 95319962 95654128 1787600896 -0.0030076697 0.2909219861 0.6076897979 514 20.5200000000 0.0461701304 0.0476068232 0.0641775355 0.0143375343 1.9007000000 95404364 95654128 1784299520 -0.0044242688 0.2933056355 0.6163305044 515 20.5600000000 0.0447648801 0.0476013049 0.0641775355 0.0143474071 1.2049320000 95406058 95654128 1785823232 -0.0050541209 0.2932100594 0.6233544350 516 20.6000000000 0.0441587940 0.0475946334 0.0641775355 0.0143628269 1.0365350000 95407892 95654128 1787727872 -0.0054967483 0.2976625264 0.6306625605 517 20.6400000000 0.0451618657 0.0475899278 0.0641775355 0.0143750111 0.9490870000 95408326 95654128 1784553472 -0.0058381627 0.3020260334 0.6376032829 518 20.6800000000 0.0458121337 0.0475864958 0.0641775355 0.0143924784 0.9018940000 95410020 95654128 1785950208 -0.0065011429 0.3052976429 0.6442093253 519 20.7200000000 0.0457488485 0.0475829550 0.0641775355 0.0144098957 0.9822870000 95411714 95654128 1787727872 -0.0047354545 0.3087806702 0.6500353813 520 20.7600000000 0.0458183661 0.0475795616 0.0641775355 0.0144391671 1.0107060000 95412148 95654128 1784553472 -0.0032162163 0.3120505214 0.6557185054 521 20.8000000000 0.0459505953 0.0475764350 0.0641775355 0.0144649752 0.8975320000 95413842 95654128 1786077184 -0.0010371143 0.3130767643 0.6610790491 522 20.8400000000 0.0446854085 0.0475708966 0.0641775355 0.0144918356 0.9226680000 95415676 95654128 1787854848 0.0012948466 0.3123552203 0.6662090421 523 20.8800000000 0.0439505428 0.0475639743 0.0641775355 0.0145214638 0.9137560000 95416110 95654128 1784680448 0.0033409647 0.3111309111 0.6707646251 524 20.9200000000 0.0432590321 0.0475557588 0.0641775355 0.0145588651 0.7981940000 95417804 95654128 1786204160 0.0059528891 0.3138189018 0.6749478579 525 20.9600000000 0.0430461653 0.0475471691 0.0641775355 0.0145752228 0.9483940000 95419498 95654128 1788108800 0.0088093150 0.3151381612 0.6791428328 526 21.0000000000 0.0421652496 0.0475369373 0.0641775355 0.0145852838 0.9588340000 95419932 95654128 1784680448 0.0125850858 0.3140341640 0.6829336882 527 21.0400000000 0.0424414910 0.0475272685 0.0641775355 0.0146004493 0.8148340000 95421626 95654128 1786204160 0.0157994498 0.3161253929 0.6865579486 528 21.0800000000 0.0416204222 0.0475160813 0.0641775355 0.0146141741 0.8618090000 95422200 95654128 1788235776 0.0203560945 0.3174081445 0.6895223856 529 21.1200000000 0.0418240391 0.0475053213 0.0641775355 0.0146170225 0.8857900000 95423894 95654128 1784946688 0.0230053328 0.3177002668 0.6924278736 530 21.1600000000 0.0423248783 0.0474955469 0.0641775355 0.0146198866 0.8589250000 95425588 95654128 1786331136 0.0255655888 0.3188373446 0.6953698397 531 21.2000000000 0.0412722975 0.0474838270 0.0641775355 0.0146296141 1.1614770000 95426022 95654128 1785823232 0.0296317302 0.3179272115 0.6980834603 532 21.2400000000 0.0406258404 0.0474709361 0.0641775355 0.0146460475 1.1671500000 95427716 95654128 1787219968 0.0342520587 0.3172371686 0.7003638744 533 21.2800000000 0.0407298617 0.0474582887 0.0641775355 0.0146600946 1.1781960000 95429410 95654128 1784934400 0.0374602042 0.3170642853 0.7025363445 534 21.3200000000 0.0404229797 0.0474451139 0.0641775355 0.0146762032 1.9638160000 95429984 95654128 1786458112 0.0418445840 0.3169577718 0.7046918273 535 21.3600000000 0.0402910113 0.0474317418 0.0641775355 0.0146927157 1.3354920000 95431678 95654128 1785577472 0.0456563942 0.3173782527 0.7069003582 536 21.4000000000 0.0396930911 0.0474173040 0.0641775355 0.0147097809 0.9765330000 95433372 95654128 1786974208 0.0500926152 0.3177257478 0.7089864016 537 21.4400000000 0.0402251147 0.0474039107 0.0641775355 0.0147261562 0.7937430000 95433806 95654128 1784815616 0.0526863746 0.3174873888 0.7112475038 538 21.4800000000 0.0383469127 0.0473870761 0.0641775355 0.0147353257 0.7986570000 95435500 95654128 1786212352 0.0590528958 0.3173947334 0.7129974365 539 21.5200000000 0.0398393907 0.0473730730 0.0641775355 0.0147479741 0.8881210000 95437194 95654128 1785831424 0.0642498806 0.3206215799 0.7149088979 540 21.5600000000 0.0400979407 0.0473596006 0.0641775355 0.0147475214 1.0674870000 95437768 95654128 1787355136 0.0667917877 0.3203163743 0.7172245979 541 21.6000000000 0.0411889143 0.0473481945 0.0641775355 0.0147537685 1.0010680000 95439462 95654128 1784561664 0.0709641054 0.3214806020 0.7193586230 542 21.6400000000 0.0412835144 0.0473370050 0.0641775355 0.0147631100 0.7558670000 95441156 95654128 1786212352 0.0740410239 0.3224607706 0.7213041186 543 21.6800000000 0.0420773998 0.0473273188 0.0641775355 0.0147777535 0.7027240000 95441590 95654128 1788125184 0.0774499997 0.3238917887 0.7234872580 544 21.7200000000 0.0424259752 0.0473183090 0.0641775355 0.0147898945 0.7212750000 95469056 95654128 1785188352 0.0805373266 0.3249688447 0.7256975770 545 21.7600000000 0.0404136814 0.0473056400 0.0641775355 0.0148011081 0.7188350000 95615546 95654128 1786966016 0.0859180391 0.3251292109 0.7276056409 546 21.8000000000 0.0400262587 0.0472923078 0.0641775355 0.0148764230 0.7494040000 95616120 95654128 1784553472 0.0923321992 0.3264590502 0.7316088080 547 21.8400000000 0.0409027375 0.0472806267 0.0641775355 0.0148818117 0.7469400000 95617814 95654128 1786220544 0.0951731950 0.3276738524 0.7343189120 548 21.8800000000 0.0414383896 0.0472699656 0.0641775355 0.0148940518 0.8583440000 95618248 95654128 1787981824 0.0994132310 0.3302466273 0.7363860607 549 21.9200000000 0.0397925153 0.0472563455 0.0641775355 0.0149114919 0.8522850000 95619942 95654128 1784934400 0.1035202518 0.3303807676 0.7383761406 550 21.9600000000 0.0392317846 0.0472417554 0.0641775355 0.0149274668 0.9533640000 95621636 95654128 1786585088 0.1092790738 0.3310292363 0.7397381067 551 22.0000000000 0.0392004140 0.0472271613 0.0641775355 0.0149535899 1.1225750000 95622070 95654128 1785442304 0.1133233383 0.3341690302 0.7413578629 552 22.0400000000 0.0416105501 0.0472169863 0.0641775355 0.0149629090 1.9976170000 95623904 95654128 1786966016 0.1165213063 0.3385663927 0.7430681586 553 22.0800000000 0.0432225987 0.0472097632 0.0641775355 0.0149598824 2.1992680000 95625598 95654128 1784553472 0.1199789271 0.3396446705 0.7446945906 554 22.1200000000 0.0421073884 0.0472005531 0.0641775355 0.0149532176 1.6411820000 95626032 95654128 1786077184 0.1242180541 0.3382637501 0.7463423014 555 22.1600000000 0.0415769368 0.0471904205 0.0641775355 0.0149459577 0.9618570000 95627726 95654128 1787871232 0.1306408048 0.3397053182 0.7474972606 556 22.2000000000 0.0408271439 0.0471789757 0.0641775355 0.0149420593 1.0114490000 95629420 95654128 1784807424 0.1356121004 0.3416730762 0.7484359741 557 22.2400000000 0.0410922468 0.0471680480 0.0641775355 0.0149388591 0.8286630000 95629854 95654128 1786077184 0.1396684349 0.3433027267 0.7500597239 558 22.2800000000 0.0412026271 0.0471573573 0.0641775355 0.0149376750 0.7285650000 95631688 95654128 1788108800 0.1445141137 0.3460239768 0.7515394688 559 22.3200000000 0.0382488146 0.0471414207 0.0641775355 0.0149357341 0.7879140000 95633382 95654128 1784807424 0.1535350233 0.3477638662 0.7523348927 560 22.3600000000 0.0383479074 0.0471257180 0.0641775355 0.0149305335 0.9415360000 95633816 95654128 1786204160 0.1560611576 0.3476563692 0.7550299168 561 22.4000000000 0.0393890925 0.0471119273 0.0641775355 0.0149290730 0.8395910000 95635510 95654128 1785696256 0.1608086675 0.3516633511 0.7568498850 562 22.4400000000 0.0381310545 0.0470959471 0.0641775355 0.0149271255 0.8034790000 95637204 95654128 1787092992 0.1685230285 0.3552046716 0.7576160431 563 22.4800000000 0.0375153944 0.0470789301 0.0641775355 0.0149205787 0.8352530000 95637638 95654128 1784934400 0.1741879284 0.3576303124 0.7583749294 564 22.5200000000 0.0394436792 0.0470653924 0.0641775355 0.0149098522 0.6970600000 95639472 95654128 1786204160 0.1765218675 0.3602660298 0.7605760694 565 22.5600000000 0.0387462750 0.0470506683 0.0641775355 0.0148993299 0.9377520000 95639906 95654128 1785696256 0.1800414771 0.3603773415 0.7619453073 566 22.6000000000 0.0392423421 0.0470368727 0.0641775355 0.0148910688 0.8777390000 95641600 95654128 1787232256 0.1853621453 0.3643158972 0.7634247541 567 22.6400000000 0.0416821651 0.0470274287 0.0641775355 0.0148788293 0.8777930000 95643294 95654128 1784709120 0.1873141378 0.3672981262 0.7651031017 568 22.6800000000 0.0415152088 0.0470177241 0.0641775355 0.0148694047 0.8783810000 95669460 95654128 1786458112 0.1920159161 0.3693315089 0.7663097382 569 22.7200000000 0.0399724990 0.0470053424 0.0641775355 0.0148589319 0.8416040000 95816434 95654128 1785569280 0.1988151520 0.3699832559 0.7661103010 570 22.7600000000 0.0405098833 0.0469939468 0.0641775355 0.0148481697 0.7534840000 95818268 95654128 1787092992 0.2025649399 0.3731223941 0.7672842145 571 22.8000000000 0.0426064841 0.0469862630 0.0641775355 0.0148355867 0.8732360000 95818702 95654128 1784942592 0.2048892081 0.3761836886 0.7686153650 572 22.8400000000 0.0429138504 0.0469791434 0.0641775355 0.0148231586 0.8185890000 95820396 95654128 1786466304 0.2089545280 0.3776708543 0.7693141103 573 22.8800000000 0.0391971767 0.0469655623 0.0641775355 0.0148124626 0.6525340000 95822090 95654128 1785712640 0.2150078863 0.3767386973 0.7690810561 574 22.9200000000 0.0397021137 0.0469529082 0.0641775355 0.0148016564 0.8183740000 95822524 95654128 1787101184 0.2198555768 0.3810132146 0.7694464326 575 22.9600000000 0.0374371074 0.0469363590 0.0641775355 0.0147891362 0.8632740000 95824218 95654128 1784942592 0.2252528220 0.3820426464 0.7698546648 576 23.0000000000 0.0402380638 0.0469247300 0.0641775355 0.0147764251 0.8485090000 95826052 95654128 1786339328 0.2280342579 0.3883761466 0.7705975175 577 23.0400000000 0.0366504677 0.0469069237 0.0641775355 0.0147637307 0.8266220000 95826486 95654128 1785450496 0.2345540822 0.3896259367 0.7702425718 578 23.0800000000 0.0394676588 0.0468940530 0.0641775355 0.0147523986 0.9446590000 95828180 95654128 1787101184 0.2337039262 0.3915449381 0.7717558146 579 23.1200000000 0.0432671048 0.0468877888 0.0641775355 0.0147397115 0.8187850000 95829874 95654128 1784725504 0.2340700626 0.3969412446 0.7720441818 580 23.1600000000 0.0417018868 0.0468788476 0.0641775355 0.0147279092 0.7421410000 95830308 95654128 1786331136 0.2402928025 0.4023649693 0.7717484832 581 23.2000000000 0.0393988490 0.0468659732 0.0641775355 0.0147154887 0.9674210000 95857250 95654128 1785569280 0.2462598532 0.4062300324 0.7706347108 582 23.2400000000 0.0364873037 0.0468481405 0.0641775355 0.0147035757 0.8524090000 96003368 95654128 1787219968 0.2522358000 0.4088263512 0.7704420686 583 23.2800000000 0.0371677279 0.0468315360 0.0641775355 0.0146911321 0.7842380000 96005062 95654128 1784553472 0.2555353343 0.4149236381 0.7705727220 584 23.3200000000 0.0387314819 0.0468176660 0.0641775355 0.0146803753 0.8882590000 96006756 95654128 1785950208 0.2569467127 0.4189958274 0.7699404359 585 23.3600000000 0.0368334651 0.0468005990 0.0641775355 0.0146681922 0.8191130000 96007190 95654128 1787871232 0.2615176439 0.4202648997 0.7691935897 586 23.4000000000 0.0360377990 0.0467822325 0.0641775355 0.0146564786 0.8729870000 96008884 95654128 1784807424 0.2623903751 0.4208776951 0.7697826028 587 23.4400000000 0.0374954678 0.0467664118 0.0641775355 0.0146443142 0.8278090000 96010578 95654128 1786077184 0.2647140920 0.4260336757 0.7698251605 588 23.4800000000 0.0386570767 0.0467526204 0.0641775355 0.0146327142 0.8688910000 96011152 95654128 1788108800 0.2646859884 0.4286013246 0.7695157528 589 23.5200000000 0.0390490703 0.0467395413 0.0641775355 0.0146206655 1.1418540000 96012846 95654128 1784553472 0.2667066753 0.4311273098 0.7695844769 590 23.5600000000 0.0365631804 0.0467222933 0.0641775355 0.0146084713 0.9191880000 96038992 95654128 1785950208 0.2696819305 0.4306603670 0.7697403431 591 23.6000000000 0.0366467163 0.0467052449 0.0641775355 0.0145962948 0.8068190000 96185154 95654128 1788108800 0.2709740698 0.4326936305 0.7707301378 592 23.6400000000 0.0370021388 0.0466888545 0.0641775355 0.0145843112 0.9707430000 96186848 95654128 1784299520 0.2739818096 0.4359307587 0.7706022859 593 23.6800000000 0.0374196582 0.0466732235 0.0641775355 0.0145759473 0.8926980000 96188542 95654128 1785823232 0.2770142257 0.4391960502 0.7706653476 594 23.7200000000 0.0381070413 0.0466588023 0.0641775355 0.0145637320 0.8775590000 96189116 95654128 1787600896 0.2784832120 0.4410564303 0.7715805173 595 23.7600000000 0.0369889587 0.0466425505 0.0641775355 0.0145519207 0.8150160000 96214998 95654128 1784426496 0.2798136175 0.4411046505 0.7722029686 596 23.8000000000 0.0372773074 0.0466268370 0.0641775355 0.0145399934 0.8791610000 96362524 95654128 1785950208 0.2827413678 0.4458139539 0.7722986341 597 23.8400000000 0.0364095122 0.0466097225 0.0641775355 0.0145281953 0.8791230000 96362958 95654128 1787981824 0.2840746045 0.4468922913 0.7726459503 598 23.8800000000 0.0365575366 0.0465929129 0.0641775355 0.0145165636 0.9195130000 96364652 95654128 1784684544 0.2853282094 0.4486297965 0.7737341523 599 23.9200000000 0.0374830663 0.0465777044 0.0641775355 0.0145063923 0.8710290000 96366346 95654128 1786077184 0.2859802246 0.4515233636 0.7745501399 600 23.9600000000 0.0349520519 0.0465583284 0.0641775355 0.0144952442 0.8535320000 96366920 95654128 1787854848 0.2880556583 0.4517333508 0.7747642398 601 24.0000000000 0.0377835147 0.0465437280 0.0641775355 0.0144881310 0.7810080000 96368614 95654128 1784680448 0.2879920900 0.4580059648 0.7771974802 602 24.0400000000 0.0366509631 0.0465272948 0.0641775355 0.0144770875 0.8267730000 96393636 95654128 1786077184 0.2897185683 0.4580340385 0.7768116593 603 24.0800000000 0.0377823412 0.0465127924 0.0641775355 0.0144679327 0.8089650000 96541306 95654128 1787981824 0.2890990078 0.4595382214 0.7782931328 604 24.1200000000 0.0392867886 0.0465008288 0.0641775355 0.0144565111 0.9067640000 96543000 95654128 1784426496 0.2904101908 0.4631220698 0.7791106105 605 24.1600000000 0.0381102748 0.0464869602 0.0641775355 0.0144451281 0.8862340000 96543434 95654128 1785966592 0.2902888060 0.4648497999 0.7806088328 606 24.2000000000 0.0379101112 0.0464728069 0.0641775355 0.0144331990 0.6886220000 96545268 95654128 1787727872 0.2910645902 0.4663725197 0.7813953757 607 24.2400000000 0.0379211493 0.0464587185 0.0641775355 0.0144218174 0.7327500000 96546962 95654128 1784426496 0.2934793532 0.4692146480 0.7812100649 608 24.2800000000 0.0372957513 0.0464436479 0.0641775355 0.0144101018 0.7148930000 96547396 95654128 1785950208 0.2941200733 0.4696351588 0.7817760110 609 24.3200000000 0.0369123220 0.0464279971 0.0641775355 0.0143993093 0.8157130000 96549090 95654128 1787854848 0.2921483219 0.4679168463 0.7833992839 610 24.3600000000 0.0390983485 0.0464159813 0.0641775355 0.0143875939 0.9253480000 96550784 95654128 1784934400 0.2916060388 0.4726908803 0.7840206623 611 24.4000000000 0.0373183675 0.0464010916 0.0641775355 0.0143759147 0.8405470000 96551218 95654128 1786331136 0.2936371267 0.4734744430 0.7844967246 612 24.4400000000 0.0380419269 0.0463874328 0.0641775355 0.0143642932 0.8710570000 96553052 95654128 1788243968 0.2917972803 0.4748403728 0.7859013081 613 24.4800000000 0.0371760502 0.0463724061 0.0641775355 0.0143528976 0.8276920000 96554746 95654128 1784180736 0.2929998934 0.4764561653 0.7862528563 614 24.5200000000 0.0381939560 0.0463590861 0.0641775355 0.0143418375 0.9326430000 96555180 95654128 1785704448 0.2914850414 0.4785626233 0.7870929241 615 24.5600000000 0.0376321264 0.0463448959 0.0641775355 0.0143311484 0.7812510000 96580798 95654128 1787609088 0.2908999920 0.4805788994 0.7886129618 616 24.6000000000 0.0366479307 0.0463291541 0.0641775355 0.0143201166 0.8537780000 96728732 95654128 1784688640 0.2907384038 0.4819453657 0.7892104387 617 24.6400000000 0.0376615226 0.0463151061 0.0641775355 0.0143088392 0.7475220000 96729166 95654128 1785974784 0.2899348736 0.4856569767 0.7901595235 618 24.6800000000 0.0390905887 0.0463034159 0.0641775355 0.0142999425 0.7889000000 96731000 95654128 1787990016 0.2880122066 0.4881424904 0.7925518155 619 24.7200000000 0.0387496054 0.0462912127 0.0641775355 0.0142901077 0.8613480000 96731434 95654128 1784434688 0.2853719592 0.4886861145 0.7954260707 620 24.7600000000 0.0406726375 0.0462821505 0.0641775355 0.0142825871 0.6730520000 96733128 95654128 1785958400 0.2830632627 0.4926458299 0.7958744168 621 24.8000000000 0.0405995250 0.0462729997 0.0641775355 0.0142749598 0.8218500000 96734822 95654128 1787871232 0.2823074460 0.4959765673 0.7971066236 622 24.8400000000 0.0398653969 0.0462626981 0.0641775355 0.0142678482 0.8506530000 96735256 95654128 1784684544 0.2799807489 0.4962187409 0.7998550534 623 24.8800000000 0.0379755795 0.0462493961 0.0641775355 0.0142626676 0.9543570000 96736950 95654128 1786077184 0.2806294858 0.4992395043 0.8014726639 624 24.9200000000 0.0383403860 0.0462367214 0.0641775355 0.0142555304 1.1386390000 96738784 95654128 1787981824 0.2793993652 0.5003876090 0.8038588762 625 24.9600000000 0.0381132327 0.0462237239 0.0641775355 0.0142473025 0.9072160000 96739218 95654128 1784700928 0.2783713341 0.5035374165 0.8066288233 626 25.0000000000 0.0367049985 0.0462085182 0.0641775355 0.0142392851 0.8144860000 96740912 95654128 1786077184 0.2766695917 0.5057072639 0.8083348870 627 25.0400000000 0.0365130417 0.0461930549 0.0641775355 0.0142360263 0.7622570000 96767082 95654128 1787981824 0.2770783901 0.5105928183 0.8088592291 628 25.0800000000 0.0363871679 0.0461774405 0.0641775355 0.0142367726 0.6915060000 96914000 95654128 1784553472 0.2752874494 0.5131102800 0.8101590872 629 25.1200000000 0.0367734432 0.0461624898 0.0641775355 0.0142361278 1.0370170000 96915694 95654128 1786077184 0.2746362090 0.5164593458 0.8110157847 630 25.1600000000 0.0370492861 0.0461480244 0.0641775355 0.0142309079 1.7328710000 96917528 95654128 1787981824 0.2713090777 0.5186524391 0.8136282563 631 25.2000000000 0.0369885638 0.0461335086 0.0641775355 0.0142252798 0.8722810000 96917962 95654128 1784692736 0.2692261338 0.5212813616 0.8147844076 632 25.2400000000 0.0369913206 0.0461190431 0.0641775355 0.0142183133 0.8732800000 96919656 95654128 1786077184 0.2653371692 0.5206996202 0.8183292747 633 25.2800000000 0.0368483551 0.0461043975 0.0641775355 0.0142092774 0.8936840000 96921350 95654128 1787854848 0.2622972131 0.5224642158 0.8209705353 634 25.3200000000 0.0362001061 0.0460887755 0.0641775355 0.0142011227 0.9587940000 96921784 95654128 1784680448 0.2585210502 0.5244043469 0.8231079578 635 25.3600000000 0.0360008217 0.0460728890 0.0641775355 0.0141934702 0.8881000000 96923478 95654128 1786077184 0.2557389438 0.5273864865 0.8253943324 636 25.4000000000 0.0367698297 0.0460582616 0.0641775355 0.0141880030 0.9222360000 96924052 95654128 1787981824 0.2508053482 0.5285555124 0.8276939392 637 25.4400000000 0.0367276408 0.0460436138 0.0641775355 0.0141804621 0.8595290000 96925746 95654128 1784680448 0.2465861589 0.5294695497 0.8311291337 638 25.4800000000 0.0367091522 0.0460289830 0.0641775355 0.0141721941 1.1716310000 96927440 95654128 1785933824 0.2413953096 0.5303288102 0.8349273801 639 25.5200000000 0.0357150137 0.0460128422 0.0641775355 0.0141650719 1.0073780000 96927874 95654128 1787973632 0.2368464321 0.5294043422 0.8379463553 640 25.5600000000 0.0370418020 0.0459988249 0.0641775355 0.0141557475 0.9037390000 96929568 95654128 1784672256 0.2322373390 0.5302838087 0.8423910141 641 25.6000000000 0.0366950594 0.0459843105 0.0641775355 0.0141468197 0.9211260000 96931262 95654128 1785942016 0.2283359021 0.5305991173 0.8456785679 642 25.6400000000 0.0350634567 0.0459672998 0.0641775355 0.0141421218 0.9653250000 96955516 95654128 1787846656 0.2253674865 0.5322596431 0.8474117517 643 25.6800000000 0.0359884650 0.0459517806 0.0641775355 0.0141422913 0.9118250000 97103998 95654128 1784672256 0.2181039900 0.5324687958 0.8511345983 644 25.7200000000 0.0373790078 0.0459384689 0.0641775355 0.0141419682 0.8575780000 97105692 95654128 1785942016 0.2114925385 0.5320332646 0.8547139764 645 25.7600000000 0.0363643505 0.0459236253 0.0641775355 0.0141360821 0.9145530000 97106126 95654128 1787846656 0.2070755363 0.5323167443 0.8568280339 646 25.8000000000 0.0362831801 0.0459087020 0.0641775355 0.0141294028 0.8836680000 97107820 95654128 1784418304 0.2034245282 0.5341620445 0.8601598144 647 25.8400000000 0.0377004370 0.0458960153 0.0641775355 0.0141242222 0.9280770000 97109514 95654128 1785831424 0.1977338791 0.5357424021 0.8630279899 648 25.8800000000 0.0379817672 0.0458838020 0.0641775355 0.0141161694 0.9517580000 97110088 95654128 1787592704 0.1932012141 0.5375417471 0.8665365577 649 25.9200000000 0.0386673585 0.0458726826 0.0641775355 0.0141072935 0.9011410000 97111782 95654128 1784799232 0.1884769797 0.5401845574 0.8688825965 650 25.9600000000 0.0380525999 0.0458606517 0.0641775355 0.0140997922 0.8735240000 97113476 95654128 1786204160 0.1836272031 0.5419391990 0.8718107939 651 26.0000000000 0.0385667086 0.0458494475 0.0641775355 0.0141000385 0.8078010000 97113910 95654128 1787854848 0.1802721620 0.5449468493 0.8731862903 652 26.0400000000 0.0382813551 0.0458378400 0.0641775355 0.0140971869 0.8650390000 97115604 95654128 1784553472 0.1768308729 0.5471810699 0.8747034073 653 26.0800000000 0.0370859355 0.0458244374 0.0641775355 0.0140963360 0.7872550000 97117298 95654128 1786077184 0.1723789573 0.5471065640 0.8773294091 654 26.1200000000 0.0371861681 0.0458112291 0.0641775355 0.0140969564 0.8078610000 97117872 95654128 1787854848 0.1681321710 0.5482618213 0.8803251386 655 26.1600000000 0.0367715172 0.0457974280 0.0641775355 0.0140927798 0.8191510000 97119566 95654128 1784565760 0.1671161056 0.5528709888 0.8816587925 656 26.2000000000 0.0356204361 0.0457819143 0.0641775355 0.0140873120 0.7690250000 97120000 95654128 1786077184 0.1580221504 0.5550627112 0.8856590986 657 26.2400000000 0.0365441665 0.0457678538 0.0641775355 0.0140832502 0.6975300000 97121694 95654128 1787854848 0.1551646888 0.5565721393 0.8874388933 658 26.2800000000 0.0369876884 0.0457545100 0.0641775355 0.0140760623 0.7222500000 97123388 95654128 1784672256 0.1507575661 0.5581858754 0.8896284699 659 26.3200000000 0.0369781703 0.0457411924 0.0641775355 0.0140720680 0.7475850000 97123822 95654128 1786085376 0.1470358223 0.5615670681 0.8909097314 660 26.3600000000 0.0373559110 0.0457284874 0.0641775355 0.0140687835 0.8317070000 97149808 95654128 1787846656 0.1426917315 0.5626674294 0.8923220634 661 26.4000000000 0.0375001766 0.0457160391 0.0641775355 0.0140671581 0.9665650000 97298654 95654128 1784672256 0.1406410486 0.5673947930 0.8928413987 662 26.4400000000 0.0372263268 0.0457032148 0.0641775355 0.0140612323 0.9490080000 97299088 95654128 1786068992 0.1377640814 0.5694227219 0.8940122724 663 26.4800000000 0.0371711701 0.0456903460 0.0641775355 0.0140587143 1.0115620000 97300782 95654128 1787973632 0.1343195140 0.5695882440 0.8955003619 664 26.5200000000 0.0360976756 0.0456758992 0.0641775355 0.0140570409 1.1629020000 97302476 95654128 1784418304 0.1326384097 0.5701830983 0.8962737322 665 26.5600000000 0.0365275629 0.0456621423 0.0641775355 0.0140555083 0.8832690000 97302910 95654128 1785942016 0.1286405921 0.5722824931 0.8974100947 666 26.6000000000 0.0356910378 0.0456471706 0.0641775355 0.0140500446 0.8504140000 97304744 95654128 1787719680 0.1264286041 0.5729325414 0.8982626796 667 26.6400000000 0.0370082594 0.0456342187 0.0641775355 0.0140447633 0.8503140000 97306438 95654128 1784418304 0.1218601540 0.5761368275 0.8993500471 668 26.6800000000 0.0360128954 0.0456198156 0.0641775355 0.0140377681 0.8280140000 97306872 95654128 1785815040 0.1190664396 0.5777468681 0.9004336596 669 26.7200000000 0.0366007537 0.0456063342 0.0641775355 0.0140358576 0.7258320000 97308566 95654128 1787719680 0.1146389097 0.5798128843 0.9017087221 670 26.7600000000 0.0377598889 0.0455946230 0.0641775355 0.0140294689 0.9289150000 97310260 95654128 1784418304 0.1100667790 0.5804970860 0.9027405381 671 26.8000000000 0.0381480306 0.0455835253 0.0641775355 0.0140238500 1.1656210000 97310694 95654128 1785815040 0.1056575701 0.5793596506 0.9043619037 672 26.8400000000 0.0372401327 0.0455711095 0.0641775355 0.0140150837 2.3215270000 97312528 95654128 1787592704 0.1014897972 0.5775884986 0.9063081741 673 26.8800000000 0.0360346325 0.0455569394 0.0641775355 0.0140060697 1.8347890000 97312962 95654128 1784418304 0.0998769775 0.5780264139 0.9072591066 674 26.9200000000 0.0337541513 0.0455394279 0.0641775355 0.0140163721 4.3027810000 98916580 95654128 1784356864 0.0904135630 0.5498353839 0.9146820307 675 26.9600000000 0.0310464129 0.0455179567 0.0641775355 0.0140116742 0.9929450000 97435094 95654128 1785466880 0.0896892175 0.5529208779 0.9159695506 676 27.0000000000 0.0309254248 0.0454963702 0.0641775355 0.0140027594 0.8643940000 97435668 95654128 1786609664 0.0856973156 0.5515278578 0.9170734882 677 27.0400000000 0.0316939279 0.0454759825 0.0641775355 0.0139966367 0.9252040000 97437362 95654128 1785466880 0.0803205594 0.5515257716 0.9182571173 678 27.0800000000 0.0321788825 0.0454563703 0.0641775355 0.0139904830 0.7897200000 97439056 95654128 1786601472 0.0746772513 0.5523191690 0.9188661575 679 27.1200000000 0.0312085971 0.0454353868 0.0641775355 0.0139819192 0.8464100000 97439490 95654128 1787744256 0.0707131624 0.5512130857 0.9198417664 680 27.1600000000 0.0315771103 0.0454150070 0.0641775355 0.0139741631 0.8696430000 97465272 95654128 1784950784 0.0659980029 0.5481382012 0.9216301441 681 27.2000000000 0.0315810032 0.0453946927 0.0641775355 0.0139721909 0.7413860000 97614522 95654128 1785966592 0.0629318804 0.5517043471 0.9217996597 682 27.2400000000 0.0307770669 0.0453732593 0.0641775355 0.0139647685 0.8550630000 97615096 95654128 1787109376 0.0607815087 0.5486526489 0.9231727123 683 27.2800000000 0.0315303914 0.0453529915 0.0641775355 0.0139604493 0.8458400000 97616790 95654128 1785458688 0.0569476746 0.5479004383 0.9238399863 684 27.3200000000 0.0320686251 0.0453335699 0.0641775355 0.0139511292 0.8253910000 97618484 95654128 1786982400 0.0506525561 0.5484827161 0.9250998497 685 27.3600000000 0.0308982413 0.0453124965 0.0641775355 0.0139451043 0.6712440000 97618918 95654128 1785458688 0.0491365120 0.5497851968 0.9257451892 686 27.4000000000 0.0309307761 0.0452915318 0.0641775355 0.0139413187 0.9321380000 97620612 95654128 1786474496 0.0448324159 0.5513093472 0.9265170097 687 27.4400000000 0.0317774750 0.0452718607 0.0641775355 0.0139358083 0.7824540000 97622306 95654128 1787617280 0.0405639634 0.5496557355 0.9285449386 688 27.4800000000 0.0315746404 0.0452519520 0.0641775355 0.0139362556 0.8290930000 97622880 95654128 1784561664 0.0388297252 0.5497074127 0.9297088981 689 27.5200000000 0.0304864030 0.0452305216 0.0641775355 0.0139315331 0.9669670000 97624574 95654128 1785704448 0.0362124220 0.5522130132 0.9303429723 690 27.5600000000 0.0314442217 0.0452105414 0.0641775355 0.0139254442 0.8087780000 97625008 95654128 1786847232 0.0313480869 0.5540119410 0.9310724139 691 27.6000000000 0.0324093588 0.0451920158 0.0641775355 0.0139185240 0.7275730000 97626702 95654128 1785450496 0.0274897926 0.5514739752 0.9328345656 692 27.6400000000 0.0321474597 0.0451731653 0.0641775355 0.0139128330 0.7518920000 97628396 95654128 1786847232 0.0240614023 0.5517504811 0.9338929653 693 27.6800000000 0.0324298143 0.0451547767 0.0641775355 0.0139072998 0.7672650000 97628830 95654128 1787990016 0.0194121860 0.5510011315 0.9349471331 694 27.7200000000 0.0307361614 0.0451340006 0.0641775355 0.0139009706 0.7326590000 97630664 95654128 1784180736 0.0189565010 0.5529950261 0.9358842373 695 27.7600000000 0.0300313365 0.0451122701 0.0641775355 0.0138960688 0.7273410000 97632358 95654128 1785180160 0.0169558544 0.5553935170 0.9365946054 696 27.8000000000 0.0305945948 0.0450914114 0.0641775355 0.0138900899 0.7705090000 97632792 95654128 1786322944 0.0125002302 0.5529907346 0.9382216930 697 27.8400000000 0.0309321936 0.0450710969 0.0641775355 0.0138850116 0.8034150000 97634486 95654128 1788100608 0.0087560043 0.5513531566 0.9395554662 698 27.8800000000 0.0302615203 0.0450498797 0.0641775355 0.0138807358 0.7107550000 97636180 95654128 1784164352 0.0067019658 0.5515497923 0.9402065277 699 27.9200000000 0.0295058005 0.0450276421 0.0641775355 0.0138749613 0.7675230000 97636614 95654128 1785069568 0.0038110958 0.5514801741 0.9410744309 700 27.9600000000 0.0293025319 0.0450051777 0.0641775355 0.0138728642 0.7707560000 97638448 95654128 1786322944 0.0001496447 0.5524677038 0.9421681762 701 28.0000000000 0.0292445365 0.0449826946 0.0641775355 0.0138706424 0.7678640000 97640142 95654128 1787973632 -0.0030281746 0.5552382469 0.9429358244 702 28.0400000000 0.0293071680 0.0449603648 0.0641775355 0.0138645719 0.8067490000 97640576 95654128 1784164352 -0.0072228909 0.5549603701 0.9439403415 703 28.0800000000 0.0297631882 0.0449387472 0.0641775355 0.0138630065 0.8267740000 97642270 95654128 1785307136 -0.0106945029 0.5577937961 0.9451565146 704 28.1200000000 0.0302153584 0.0449178333 0.0641775355 0.0138570436 0.8683460000 97667316 95654128 1786449920 -0.0139417462 0.5558847785 0.9466717839 705 28.1600000000 0.0302793253 0.0448970694 0.0641775355 0.0138516868 0.7487690000 97815790 95654128 1788100608 -0.0169829689 0.5547941327 0.9480428696 706 28.2000000000 0.0304590613 0.0448766190 0.0641775355 0.0138472229 0.9668150000 97817624 95654128 1784291328 -0.0189519189 0.5539072752 0.9492388368 707 28.2400000000 0.0299814269 0.0448555508 0.0641775355 0.0138439805 0.8475270000 97818058 95654128 1785307136 -0.0229783747 0.5568289161 0.9499198198 708 28.2800000000 0.0297190230 0.0448341715 0.0641775355 0.0138376938 0.7899470000 97819752 95654128 1786449920 -0.0245238058 0.5543675423 0.9516336918 709 28.3200000000 0.0307947379 0.0448143698 0.0641775355 0.0138306840 0.7603890000 97821446 95654128 1785434112 -0.0291810445 0.5538280606 0.9527756572 710 28.3600000000 0.0306088682 0.0447943620 0.0641775355 0.0138265458 0.7119470000 97821880 95654128 1786449920 -0.0332229584 0.5574012995 0.9536000490 711 28.4000000000 0.0294484198 0.0447727784 0.0641775355 0.0138209221 0.7855300000 97823574 95654128 1787592704 -0.0353943966 0.5563421249 0.9548468590 712 28.4400000000 0.0291923285 0.0447508958 0.0641775355 0.0138138313 0.7305110000 97825408 95654128 1784815616 -0.0402041934 0.5569732189 0.9556731582 713 28.4800000000 0.0289270934 0.0447287025 0.0641775355 0.0138072377 0.7491300000 97825842 95654128 1785942016 -0.0440335721 0.5571528673 0.9566454887 714 28.5200000000 0.0290397126 0.0447067291 0.0641775355 0.0138015093 0.7082940000 97827536 95654128 1787211776 -0.0478587225 0.5566518903 0.9582210779 715 28.5600000000 0.0295208246 0.0446854901 0.0641775355 0.0137940338 0.7874350000 97829230 95654128 1785688064 -0.0529926121 0.5563746095 0.9595946670 716 28.6000000000 0.0290259216 0.0446636192 0.0641775355 0.0137891119 0.8039350000 97829664 95654128 1787084800 -0.0564853437 0.5560048819 0.9608892202 717 28.6400000000 0.0287881102 0.0446414776 0.0641775355 0.0137821025 0.8900250000 97831358 95654128 1785688064 -0.0605570003 0.5583327413 0.9613794684 718 28.6800000000 0.0288195387 0.0446194415 0.0641775355 0.0137752542 0.9519320000 97833192 95654128 1787084800 -0.0654077977 0.5582681298 0.9623658061 719 28.7200000000 0.0291034412 0.0445978615 0.0641775355 0.0137723478 0.9036030000 97833626 95654128 1785450496 -0.0695524588 0.5548665524 0.9637460113 720 28.7600000000 0.0295304582 0.0445769346 0.0641775355 0.0137757384 0.7707610000 97835320 95654128 1786576896 -0.0738062188 0.5579780340 0.9642198682 721 28.8000000000 0.0285416804 0.0445546943 0.0641775355 0.0137707301 0.7089820000 97837014 95654128 1787981824 -0.0757656991 0.5539803505 0.9659072757 722 28.8400000000 0.0281396098 0.0445319587 0.0641775355 0.0137672533 0.9006990000 97837448 95654128 1784553472 -0.0813875571 0.5536935925 0.9662396312 723 28.8800000000 0.0283753276 0.0445096121 0.0641775355 0.0137607070 0.9694800000 97839142 95654128 1785475072 -0.0854481310 0.5539775491 0.9671157598 724 28.9200000000 0.0275847595 0.0444862352 0.0641775355 0.0137529792 0.8935570000 97839716 95654128 1786712064 -0.0900850743 0.5527619720 0.9675375819 725 28.9600000000 0.0274509080 0.0444627382 0.0641775355 0.0137478394 0.8074310000 97841410 95654128 1785315328 -0.0931716263 0.5537346005 0.9690567255 726 29.0000000000 0.0276025813 0.0444395148 0.0641775355 0.0137406405 1.0492300000 97843104 95654128 1786839040 -0.0974477902 0.5524609685 0.9694747925 727 29.0400000000 0.0276555158 0.0444164282 0.0641775355 0.0137362473 0.8678570000 97866746 95654128 1785823232 -0.1010397822 0.5527445078 0.9702254534 728 29.0800000000 0.0274024867 0.0443930574 0.0641775355 0.0137324455 1.0406180000 98016944 95654128 1787346944 -0.1031187028 0.5511595607 0.9711101055 729 29.1200000000 0.0273150336 0.0443696307 0.0641775355 0.0137333330 0.8092900000 98018638 95654128 1784545280 -0.1055004820 0.5517464876 0.9721515179 730 29.1600000000 0.0272298604 0.0443461516 0.0641775355 0.0137304426 0.8223260000 98019212 95654128 1785942016 -0.1076944917 0.5503730178 0.9730788469 731 29.2000000000 0.0268146936 0.0443221688 0.0641775355 0.0137277380 1.0591410000 98020906 95654128 1787846656 -0.1122542024 0.5484713912 0.9731755257 732 29.2400000000 0.0271993540 0.0442987769 0.0641775355 0.0137245449 1.7714440000 98022600 95654128 1784418304 -0.1162348911 0.5494132042 0.9734603167 733 29.2800000000 0.0271829665 0.0442754266 0.0641775355 0.0137207371 2.1356470000 98023034 95654128 1785942016 -0.1185669899 0.5478237867 0.9743387699 734 29.3200000000 0.0267425086 0.0442515398 0.0641775355 0.0137130255 1.9528540000 98024728 95654128 1787846656 -0.1206397265 0.5466762781 0.9747282863 735 29.3600000000 0.0265596323 0.0442274691 0.0641775355 0.0137065750 2.2359940000 98026422 95654128 1784545280 -0.1241297126 0.5467463136 0.9746524692 736 29.4000000000 0.0262744557 0.0442030765 0.0641775355 0.0137007496 1.7507020000 98026996 95654128 1786068992 -0.1268902421 0.5446401238 0.9745832682 737 29.4400000000 0.0263281800 0.0441788229 0.0641775355 0.0136951885 1.1542120000 98028690 95654128 1787846656 -0.1296080202 0.5431972742 0.9749470949 738 29.4800000000 0.0266563538 0.0441550797 0.0641775355 0.0136890046 1.2158650000 98030384 95654128 1784545280 -0.1313652247 0.5415266156 0.9755257964 739 29.5200000000 0.0266037937 0.0441313296 0.0641775355 0.0136830222 1.7693330000 98030818 95654128 1786068992 -0.1325715333 0.5390664935 0.9759953618 740 29.5600000000 0.0266774874 0.0441077434 0.0641775355 0.0136793781 0.9890310000 98032512 95654128 1787719680 -0.1336922050 0.5365530252 0.9764746428 741 29.6000000000 0.0268333927 0.0440844312 0.0641775355 0.0136781487 0.9268460000 98034206 95654128 1784418304 -0.1363351792 0.5358541012 0.9767540693 742 29.6400000000 0.0267918091 0.0440611257 0.0641775355 0.0136729648 0.9287240000 98034780 95654128 1785942016 -0.1379752457 0.5339802504 0.9771074057 743 29.6800000000 0.0269735213 0.0440381276 0.0641775355 0.0136713579 0.9333990000 98036474 95654128 1787719680 -0.1393089890 0.5332865715 0.9775068164 744 29.7200000000 0.0263166279 0.0440143084 0.0641775355 0.0136740422 1.0619320000 98036908 95654128 1784545280 -0.1416001022 0.5297048092 0.9781156778 745 29.7600000000 0.0264894217 0.0439907851 0.0641775355 0.0136658726 0.8427330000 98038602 95654128 1785942016 -0.1421412826 0.5264697671 0.9788635373 746 29.8000000000 0.0265081357 0.0439673499 0.0641775355 0.0136581236 1.0096320000 98040296 95654128 1787846656 -0.1429967582 0.5261285305 0.9798035026 747 29.8400000000 0.0264819115 0.0439439423 0.0641775355 0.0136501255 0.7338780000 98040730 95654128 1784799232 -0.1437918395 0.5241230726 0.9806257486 748 29.8800000000 0.0267348457 0.0439209355 0.0641775355 0.0136410763 0.8851990000 98042564 95654128 1786068992 -0.1455233693 0.5228367448 0.9805337787 749 29.9200000000 0.0269287359 0.0438982490 0.0641775355 0.0136319825 0.9076680000 98044258 95654128 1787973632 -0.1478952616 0.5223228335 0.9805604219 750 29.9600000000 0.0264315717 0.0438749601 0.0641775355 0.0136231046 1.0379600000 98044692 95654128 1784418304 -0.1486760378 0.5215767622 0.9806581736 751 30.0000000000 0.0268456805 0.0438522846 0.0641775355 0.0136140897 0.8634000000 98046386 95654128 1785942016 -0.1492999941 0.5185672641 0.9812387228 752 30.0400000000 0.0267495010 0.0438295416 0.0641775355 0.0136050479 0.9611320000 98048080 95654128 1787727872 -0.1495085210 0.5164350867 0.9820592403 753 30.0800000000 0.0266832728 0.0438067709 0.0641775355 0.0135995393 1.0870370000 98048514 95654128 1784299520 -0.1503158957 0.5155228972 0.9830550551 754 30.1200000000 0.0271881185 0.0437847303 0.0641775355 0.0135919786 0.8275110000 98050348 95654128 1785823232 -0.1503459960 0.5128034949 0.9839289188 755 30.1600000000 0.0275056884 0.0437631686 0.0641775355 0.0135862740 0.9134330000 98052042 95654128 1787600896 -0.1505541652 0.5120860338 0.9853110313 756 30.2000000000 0.0271075368 0.0437411374 0.0641775355 0.0135789013 0.9297120000 98052476 95654128 1784680448 -0.1505523622 0.5120688081 0.9860157967 757 30.2400000000 0.0271608960 0.0437192348 0.0641775355 0.0135712039 0.8788130000 98076978 95654128 1786077184 -0.1507517099 0.5093718171 0.9867970943 758 30.2800000000 0.0268851183 0.0436970262 0.0641775355 0.0135658297 0.7568410000 98227780 95654128 1787981824 -0.1510581374 0.5102140903 0.9874753952 759 30.3200000000 0.0274671074 0.0436756429 0.0641775355 0.0135614143 0.9663560000 98228214 95654128 1784680448 -0.1512030214 0.5083435178 0.9887088537 760 30.3600000000 0.0281171463 0.0436551712 0.0641775355 0.0135596779 0.8589450000 98230048 95654128 1786068992 -0.1506161094 0.5057325959 0.9899320602 761 30.4000000000 0.0280278660 0.0436346360 0.0641775355 0.0135538895 0.8570850000 98230482 95654128 1787846656 -0.1499134749 0.5050473809 0.9916406274 762 30.4400000000 0.0275820233 0.0436135696 0.0641775355 0.0135454211 0.7839320000 98232176 95654128 1784557568 -0.1485996246 0.5045766234 0.9930322170 763 30.4800000000 0.0277350228 0.0435927589 0.0641775355 0.0135367954 0.8211880000 98233870 95654128 1786068992 -0.1468472779 0.5024579167 0.9948821068 764 30.5200000000 0.0274562370 0.0435716378 0.0641775355 0.0135288800 1.0565200000 98234304 95654128 1787846656 -0.1440703720 0.5004482269 0.9962728024 765 30.5600000000 0.0273237824 0.0435503988 0.0641775355 0.0135217293 0.9777000000 98235998 95654128 1784545280 -0.1414767951 0.4987708628 0.9982255697 766 30.6000000000 0.0272840522 0.0435291633 0.0641775355 0.0135173032 1.0717440000 98237832 95654128 1786068992 -0.1392862797 0.4958845675 0.9996505976 767 30.6400000000 0.0278807618 0.0435087612 0.0641775355 0.0135220642 1.0065690000 98238266 95654128 1787846656 -0.1370405257 0.4925536215 1.0015225410 768 30.6800000000 0.0282610115 0.0434889074 0.0641775355 0.0135308664 0.8485800000 98239960 95654128 1784672256 -0.1340368092 0.4917562008 1.0037188530 769 30.7200000000 0.0286452528 0.0434696049 0.0641775355 0.0135835328 0.8614280000 98241654 95654128 1786068992 -0.1281474531 0.4892338812 1.0070906878 770 30.7600000000 0.0288379453 0.0434506027 0.0641775355 0.0136113172 0.9126480000 98242088 95654128 1788100608 -0.1241876706 0.4838833511 1.0084859133 771 30.8000000000 0.0287002046 0.0434314712 0.0641775355 0.0136331807 0.8700910000 98243782 95654128 1784799232 -0.1202026904 0.4811584055 1.0099630356 772 30.8400000000 0.0284932256 0.0434121211 0.0641775355 0.0136552546 0.7986640000 98245616 95654128 1786068992 -0.1179663539 0.4808093309 1.0108168125 773 30.8800000000 0.0287055466 0.0433930958 0.0641775355 0.0136799856 0.9698520000 98246050 95654128 1787973632 -0.1144794151 0.4773994982 1.0123530626 774 30.9200000000 0.0287408698 0.0433741653 0.0641775355 0.0136987738 0.9063650000 98247744 95654128 1784291328 -0.1108419746 0.4731544256 1.0134396553 775 30.9600000000 0.0286083687 0.0433551126 0.0641775355 0.0137179918 0.7856730000 98249438 95654128 1785815040 -0.1074363217 0.4712519944 1.0145603418 776 31.0000000000 0.0287835132 0.0433363348 0.0641775355 0.0137394461 0.7778040000 98249872 95654128 1787482112 -0.1036720276 0.4683963060 1.0160750151 777 31.0400000000 0.0288762022 0.0433177246 0.0641775355 0.0137503151 0.8509260000 98251566 95654128 1784418304 -0.1004774719 0.4662811160 1.0175150633 778 31.0800000000 0.0288335439 0.0432991074 0.0641775355 0.0137569118 0.8882910000 98252140 95654128 1785942016 -0.0976888016 0.4635451734 1.0190618038 779 31.1200000000 0.0287152920 0.0432803862 0.0641775355 0.0137564191 0.8041690000 98253834 95654128 1787719680 -0.0944490209 0.4605111480 1.0209563971 780 31.1600000000 0.0288591590 0.0432618975 0.0641775355 0.0137515728 0.8081720000 98255528 95654128 1784418304 -0.0918339118 0.4564745128 1.0225683451 781 31.2000000000 0.0287631415 0.0432433331 0.0641775355 0.0137469581 0.7984840000 98255962 95654128 1785958400 -0.0898555070 0.4525012374 1.0239712000 782 31.2400000000 0.0289126970 0.0432250075 0.0641775355 0.0137444604 0.8640680000 98257656 95654128 1787846656 -0.0868935511 0.4487091899 1.0264102221 783 31.2800000000 0.0288746692 0.0432066801 0.0641775355 0.0137387636 1.0548780000 98259350 95654128 1784545280 -0.0843496844 0.4441958666 1.0283012390 784 31.3200000000 0.0284985006 0.0431879197 0.0641775355 0.0137338066 0.7812330000 98259924 95654128 1786068992 -0.0816172585 0.4393258691 1.0301570892 785 31.3600000000 0.0286923647 0.0431694540 0.0641775355 0.0137292556 0.8907090000 98261618 95654128 1787846656 -0.0797093064 0.4348464012 1.0322086811 786 31.4000000000 0.0290646590 0.0431515090 0.0641775355 0.0137221178 0.8220380000 98263312 95654128 1784545280 -0.0784767196 0.4307202995 1.0336581469 787 31.4400000000 0.0290124994 0.0431335433 0.0641775355 0.0137143760 0.7966350000 98263746 95654128 1786068992 -0.0768796876 0.4240941405 1.0350739956 788 31.4800000000 0.0286560226 0.0431151708 0.0641775355 0.0137120214 0.7554010000 98265440 95654128 1787719680 -0.0740766376 0.4198359251 1.0375043154 789 31.5200000000 0.0286543015 0.0430968427 0.0641775355 0.0137090883 0.8619980000 98267134 95654128 1784418304 -0.0724856108 0.4141236246 1.0389968157 790 31.5600000000 0.0287299864 0.0430786568 0.0641775355 0.0137083916 0.8575200000 98267708 95654128 1786068992 -0.0712045059 0.4073400497 1.0406697989 791 31.6000000000 0.0292217359 0.0430611385 0.0641775355 0.0137293100 0.9215830000 98269402 95654128 1787727872 -0.0701565072 0.3970471025 1.0434384346 792 31.6400000000 0.0293307640 0.0430438022 0.0641775355 0.0137306414 1.1253300000 98271096 95654128 1784553472 -0.0704091787 0.3945868611 1.0453388691 793 31.6800000000 0.0291348584 0.0430262626 0.0641775355 0.0137274180 1.0379440000 98271530 95654128 1785950208 -0.0696112439 0.3886191547 1.0471247435 794 31.7200000000 0.0291210674 0.0430087497 0.0641775355 0.0137232696 0.8416630000 98273224 95654128 1787727872 -0.0695285276 0.3879846632 1.0487033129 795 31.7600000000 0.0280762669 0.0429899667 0.0641775355 0.0137202930 0.7616210000 98274918 95654128 1784426496 -0.0686406791 0.3899461925 1.0505753756 796 31.8000000000 0.0282194261 0.0429714108 0.0641775355 0.0137174797 1.0294720000 98275492 95654128 1785942016 -0.0681696087 0.3860275447 1.0531257391 797 31.8400000000 0.0270016212 0.0429513734 0.0641775355 0.0137209112 2.1279770000 98277186 95654128 1787719680 -0.0666812658 0.3815630078 1.0554008484 798 31.8800000000 0.0268430263 0.0429311875 0.0641775355 0.0137960584 0.8679360000 98277620 95654128 1784418304 -0.0661700815 0.3622496426 1.0605481863 799 31.9200000000 0.0282674599 0.0429128349 0.0641775355 0.0138169329 0.8790560000 98279314 95654128 1785815040 -0.0672202483 0.3582470715 1.0634229183 800 31.9600000000 0.0282075983 0.0428944533 0.0641775355 0.0138212493 1.1767950000 98281008 95654128 1787609088 -0.0678474158 0.3533205390 1.0655901432 801 32.0000000000 0.0273500010 0.0428750470 0.0641775355 0.0138143701 0.9282300000 98281442 95654128 1784418304 -0.0674680620 0.3471757174 1.0684756041 802 32.0400000000 0.0270138234 0.0428552700 0.0641775355 0.0138061658 0.8269880000 98283276 95654128 1785815040 -0.0679818764 0.3360538185 1.0711946487 803 32.0800000000 0.0272440929 0.0428358289 0.0641775355 0.0137982537 1.0082630000 98284970 95654128 1787592704 -0.0688544735 0.3282449245 1.0745176077 804 32.1199999990 0.0261517018 0.0428150775 0.0641775355 0.0137942013 0.7690860000 98285404 95654128 1784418304 -0.0694375485 0.3142048717 1.0808357000 805 32.1600000000 0.0265235417 0.0427948396 0.0641775355 0.0137863985 0.6819350000 98287098 95654128 1785942016 -0.0707201734 0.3103844225 1.0841206312 806 32.2000000000 0.0262519699 0.0427743149 0.0641775355 0.0137780836 0.6734820000 98288792 95654128 1787719680 -0.0716365725 0.3061122000 1.0876743793 807 32.2400000000 0.0266568121 0.0427543428 0.0641775355 0.0137696840 0.7693720000 98289226 95654128 1784545280 -0.0739068463 0.2982722819 1.0906950235 808 32.2800000000 0.0267938245 0.0427345897 0.0641775355 0.0137611692 0.8226900000 98291060 95654128 1785942016 -0.0768084675 0.2928153872 1.0930421352 809 32.3200000000 0.0274522267 0.0427156992 0.0641775355 0.0137549453 1.0874150000 98292754 95654128 1787719680 -0.0778699145 0.2831351161 1.0975651741 810 32.3600000000 0.0287851673 0.0426985010 0.0641775355 0.0137480827 0.9874540000 98293188 95654128 1784418304 -0.0783502162 0.2755432725 1.1023578644 811 32.4000000000 0.0265467521 0.0426785852 0.0641775355 0.0137448626 0.9237210000 98294882 95654128 1785942016 -0.0803522915 0.2644990385 1.1060541868 812 32.4399999990 0.0264497139 0.0426585989 0.0641775355 0.0137373908 0.8549640000 98296576 95654128 1787719680 -0.0821935982 0.2604117393 1.1094087362 813 32.4800000000 0.0265763514 0.0426388175 0.0641775355 0.0137316116 0.6578420000 98297010 95654128 1784307712 -0.0824368596 0.2544957995 1.1141028404 814 32.5200000000 0.0271624681 0.0426198048 0.0641775355 0.0137254869 0.8981980000 98298844 95654128 1785815040 -0.0832720324 0.2456860691 1.1186989546 815 32.5600000000 0.0281036291 0.0426019936 0.0641775355 0.0137191744 0.7256150000 98299278 95654128 1787592704 -0.0840896517 0.2389322370 1.1228927374 816 32.6000000000 0.0290620662 0.0425854005 0.0641775355 0.0137114751 0.8004510000 98300972 95654128 1784418304 -0.0846718103 0.2348067611 1.1272476912 817 32.6400000000 0.0319377258 0.0425723679 0.0641775355 0.0137033976 0.6936420000 98302666 95654128 1785958400 -0.0866148174 0.2264562696 1.1318622828 818 32.6800000000 0.0361801237 0.0425645534 0.0641775355 0.0136975721 0.8225800000 98303100 95654128 1787846656 -0.0872987956 0.2157307565 1.1387573481 819 32.7200000000 0.0409773476 0.0425626154 0.0641775355 0.0136916563 0.8516490000 98304794 95654128 1784418304 -0.0887097046 0.2111473233 1.1443417072 820 32.7599999990 0.0423229262 0.0425623231 0.0641775355 0.0136837208 0.7835200000 98306628 95654128 1785942016 -0.0905243456 0.2065377831 1.1485006809 821 32.7999999990 0.0399033129 0.0425590844 0.0641775355 0.0136758334 0.8328760000 98307062 95654128 1787719680 -0.0921790749 0.1946600229 1.1531285048 822 32.8400000000 0.0432513729 0.0425599266 0.0641775355 0.0136714424 0.8266610000 98308756 95654128 1784418304 -0.0927952677 0.1867881268 1.1580263376 823 32.8800000000 0.0473584272 0.0425657571 0.0641775355 0.0136680999 1.0383710000 98310450 95654128 1785942016 -0.0933759287 0.1794640124 1.1628606319 824 32.9200000000 0.0503430553 0.0425751955 0.0641775355 0.0136613760 0.9577840000 98310884 95654128 1787719680 -0.0932740495 0.1720831543 1.1677765846 825 32.9600000000 0.0539339557 0.0425889637 0.0641775355 0.0136532906 0.8984990000 98312578 95654128 1784418304 -0.0944102183 0.1662082970 1.1718984842 826 33.0000000000 0.0572157688 0.0426066717 0.0641775355 0.0136458575 0.7672900000 98314412 95654128 1785942016 -0.0950372741 0.1610312462 1.1758358479 827 33.0400000000 0.0425567627 0.0426066114 0.0641775355 0.0136531015 0.7514040000 98314846 95654128 1787846656 -0.0954712480 0.1341076791 1.1793903112 828 33.0800000000 0.0460160337 0.0426107290 0.0641775355 0.0136460748 0.9434680000 98316540 95654128 1784434688 -0.0959956348 0.1302995235 1.1828144789 829 33.1199999990 0.0519966856 0.0426220510 0.0641775355 0.0136429368 0.8295210000 98338338 95654128 1785950208 -0.0964610130 0.1260735393 1.1861344576 830 33.1600000000 0.0580150448 0.0426405968 0.0641775355 0.0136384616 1.1431740000 98489324 95654128 1787727872 -0.0962660983 0.1196082756 1.1900660992 831 33.2000000000 0.0608291887 0.0426624844 0.0641775355 0.0136313316 1.7665420000 98491018 95654128 1784426496 -0.0961324573 0.1110553145 1.1931110620 832 33.2400000000 0.0614179485 0.0426850270 0.0641775355 0.0136268691 0.8688930000 98491592 95654128 1785950208 -0.0965333506 0.1031651720 1.1945964098 833 33.2800000000 0.0663681105 0.0427134581 0.0663681105 0.0136191523 0.7314410000 98493286 95654128 1787727872 -0.0973058045 0.0981749818 1.1972736120 834 33.3200000000 0.0694643259 0.0427455335 0.0694643259 0.0136111547 0.8040720000 98494980 95654128 1784455168 -0.0977169871 0.0921791196 1.1998628378 835 33.3600000000 0.0691845715 0.0427771970 0.0694643259 0.0136032567 0.9645170000 98495414 95654128 1785950208 -0.0980110765 0.0841266960 1.2017598152 836 33.4000000000 0.0722968355 0.0428125076 0.0722968355 0.0135984415 0.8142130000 98497108 95654128 1787727872 -0.0965224877 0.0791418552 1.2042968273 837 33.4399999990 0.0765765384 0.0428528469 0.0765765384 0.0135943842 0.9478030000 98498802 95654128 1784426496 -0.0960357338 0.0727771893 1.2068310976 838 33.4800000000 0.0858186036 0.0429041187 0.0858186036 0.0135880670 0.9075530000 98499376 95654128 1785950208 -0.0959372520 0.0722691640 1.2090408802 839 33.5200000000 0.0907768309 0.0429611780 0.0907768309 0.0135810069 1.0023340000 98501070 95654128 1787719680 -0.0949168652 0.0691030845 1.2109764814 840 33.5600000000 0.0923497155 0.0430199738 0.0923497155 0.0135734419 1.0031930000 98502764 95654128 1784418304 -0.0934456661 0.0645253882 1.2124499083 841 33.6000000000 0.0802639127 0.0430642591 0.0923497155 0.0135854060 0.7655970000 98503198 95654128 1785942016 -0.0915918127 0.0393655822 1.2156209946 842 33.6400000000 0.0854003802 0.0431145396 0.0923497155 0.0135789803 0.8678950000 98504892 95654128 1787846656 -0.0899559706 0.0317017138 1.2198002338 843 33.6800000000 0.0868160054 0.0431663800 0.0923497155 0.0135712520 0.8067320000 98506586 95654128 1784418304 -0.0893717036 0.0273057558 1.2206829786 844 33.7200000000 0.0881377608 0.0432196636 0.0923497155 0.0135711351 0.8467150000 98507160 95654128 1785958400 -0.0887231529 0.0215735584 1.2210839987 845 33.7599999990 0.0903223529 0.0432754064 0.0923497155 0.0135778372 0.8101460000 98508854 95654128 1787846656 -0.0874512941 0.0133400457 1.2220407724 846 33.7999999990 0.0923365578 0.0433333983 0.0923497155 0.0135766707 0.8073940000 98510548 95654128 1784545280 -0.0859578028 0.0103183733 1.2220048904 847 33.8400000000 0.0924026519 0.0433913313 0.0924026519 0.0135781823 0.8880960000 98510982 95654128 1786068992 -0.0853695422 0.0052151806 1.2216006517 848 33.8800000000 0.0959913731 0.0434533597 0.0959913731 0.0135748332 1.0217150000 98512676 95654128 1787719680 -0.0838341713 -0.0025371015 1.2234728336 849 33.9200000000 0.0953854099 0.0435145282 0.0959913731 0.0135688675 1.0345260000 98514370 95654128 1784418304 -0.0840694979 -0.0103989234 1.2237970829 850 33.9600000000 0.0938145667 0.0435737047 0.0959913731 0.0135642768 0.9449340000 98514944 95654128 1785942016 -0.0842895210 -0.0155360438 1.2232372761 851 34.0000000000 0.0950992629 0.0436342518 0.0959913731 0.0135580003 0.7932540000 98516638 95654128 1787719680 -0.0847298726 -0.0211204551 1.2236609459 852 34.0400000000 0.0937539712 0.0436930777 0.0959913731 0.0135529245 0.7837110000 98517072 95654128 1784545280 -0.0856387839 -0.0271689203 1.2230710983 853 34.0800000000 0.0931792930 0.0437510921 0.0959913731 0.0135530004 0.8409530000 98518766 95654128 1785958400 -0.0859671086 -0.0321505368 1.2225602865 854 34.1199999990 0.0949344710 0.0438110258 0.0959913731 0.0135532722 0.9286870000 98520460 95654128 1787846656 -0.0865112990 -0.0379222669 1.2226177454 855 34.1600000000 0.0944560170 0.0438702597 0.0959913731 0.0135475095 0.7459400000 98520894 95654128 1784578048 -0.0861757696 -0.0436254106 1.2228401899 856 34.2000000000 0.0923943222 0.0439269467 0.0959913731 0.0135426584 0.8045900000 98522728 95654128 1785942016 -0.0857508332 -0.0475292206 1.2218756676 857 34.2400000000 0.0926415324 0.0439837898 0.0959913731 0.0135391762 0.9482140000 98524422 95654128 1787719680 -0.0852575451 -0.0496848859 1.2208132744 858 34.2800000000 0.0919370726 0.0440396794 0.0959913731 0.0135427659 0.7298050000 98524856 95654128 1784418304 -0.0852149129 -0.0539973527 1.2198085785 859 34.3200000000 0.0903912932 0.0440936394 0.0959913731 0.0135496696 0.8685110000 98526550 95654128 1785942016 -0.0854505971 -0.0577650815 1.2180187702 860 34.3600000000 0.0895002559 0.0441464378 0.0959913731 0.0135493716 0.8514710000 98528244 95654128 1787846656 -0.0852230787 -0.0613408089 1.2165787220 861 34.4000000000 0.0849963203 0.0441938825 0.0959913731 0.0135511542 0.8676800000 98528678 95654128 1784418304 -0.0834582895 -0.0674478263 1.2155833244 862 34.4400000000 0.0857064798 0.0442420409 0.0959913731 0.0135564287 0.8669350000 98530512 95654128 1785942016 -0.0822837651 -0.0699855536 1.2151262760 863 34.4800000000 0.0869166180 0.0442914900 0.0959913731 0.0135637614 1.0269670000 98532206 95654128 1787719680 -0.0810263082 -0.0725270659 1.2151242495 864 34.5200000000 0.0860301703 0.0443397987 0.0959913731 0.0135678863 1.0066120000 98532640 95654128 1784418304 -0.0813957229 -0.0732880011 1.2132630348 865 34.5600000000 0.0864202529 0.0443884466 0.0959913731 0.0135712265 1.2298570000 98534334 95654128 1785942016 -0.0805956721 -0.0742823184 1.2120363712 866 34.6000000000 0.0874888599 0.0444382162 0.0959913731 0.0135702997 1.3555350000 98536028 95654128 1787854848 -0.0796022043 -0.0773549825 1.2115062475 867 34.6400000000 0.0885455385 0.0444890897 0.0959913731 0.0135645669 1.0538410000 98536462 95654128 1784553472 -0.0793930143 -0.0781728253 1.2106786966 868 34.6800000000 0.0879570246 0.0445391679 0.0959913731 0.0135583620 0.8012810000 98538296 95654128 1785950208 -0.0785493180 -0.0797959045 1.2093162537 869 34.7200000000 0.0867631212 0.0445877571 0.0959913731 0.0135539818 0.8341400000 98538730 95654128 1787854848 -0.0769196972 -0.0833003297 1.2086795568 870 34.7600000000 0.0866014659 0.0446360487 0.0959913731 0.0135472043 1.0399110000 98540424 95654128 1784553472 -0.0759218782 -0.0861334428 1.2080892324 871 34.8000000000 0.0862865746 0.0446838679 0.0959913731 0.0135429531 0.9668300000 98542118 95654128 1786077184 -0.0751994774 -0.0898699909 1.2074034214 872 34.8400000000 0.0868123323 0.0447321803 0.0959913731 0.0135371894 0.8466310000 98542552 95654128 1787854848 -0.0748343691 -0.0932171196 1.2073206902 873 34.8800000000 0.0881622508 0.0447819284 0.0959913731 0.0135298403 0.8509230000 98544246 95654128 1784557568 -0.0739433542 -0.0942029282 1.2070703506 874 34.9200000000 0.0868140981 0.0448300201 0.0959913731 0.0135233298 0.9411940000 98546080 95654128 1786077184 -0.0737051740 -0.0974683091 1.2059801817 875 34.9600000000 0.0849753544 0.0448759005 0.0959913731 0.0135184656 0.8084470000 98546514 95654128 1787854848 -0.0737427175 -0.1025799662 1.2054553032 876 35.0000000000 0.0845053270 0.0449211396 0.0959913731 0.0135111601 0.8351540000 98548208 95654128 1784672256 -0.0730894804 -0.1058909446 1.2053570747 877 35.0400000000 0.0847908854 0.0449666011 0.0959913731 0.0135034892 0.9549020000 98549902 95654128 1786068992 -0.0738511160 -0.1080051512 1.2044007778 878 35.0800000000 0.0848610923 0.0450120390 0.0959913731 0.0134962734 0.7973340000 98550336 95654128 1788227584 -0.0740564615 -0.1116420925 1.2035727501 879 35.1200000000 0.0840031281 0.0450563975 0.0959913731 0.0134888494 0.8448700000 98552030 95654128 1783910400 -0.0735184550 -0.1156448871 1.2029520273 880 35.1600000000 0.0843707249 0.0451010729 0.0959913731 0.0134815730 0.7843600000 98553864 95654128 1785434112 -0.0731476545 -0.1196366921 1.2008310556 881 35.2000000000 0.0826031715 0.0451436405 0.0959913731 0.0134744995 0.7694500000 98554298 95654128 1787338752 -0.0731780455 -0.1228349879 1.1991953850 882 35.2400000000 0.0801977143 0.0451833844 0.0959913731 0.0134680108 0.8782580000 98555992 95654128 1784545280 -0.0733716041 -0.1282576174 1.1980508566 883 35.2800000000 0.0778005347 0.0452203234 0.0959913731 0.0134622834 0.9118570000 98557686 95654128 1785942016 -0.0738536939 -0.1335625350 1.1968220472 884 35.3200000000 0.0756279305 0.0452547211 0.0959913731 0.0134614901 0.7446490000 98558120 95654128 1787719680 -0.0743972063 -0.1380472481 1.1951725483 885 35.3600000000 0.0727583840 0.0452857987 0.0959913731 0.0134610080 0.7084670000 98559814 95654128 1784446976 -0.0748397335 -0.1433292925 1.1939010620 886 35.4000000000 0.0704732984 0.0453142270 0.0959913731 0.0134631392 0.7812340000 98560388 95654128 1785942016 -0.0764205530 -0.1478698701 1.1926232576 887 35.4400000000 0.0678938702 0.0453396832 0.0959913731 0.0134609955 0.8471030000 98562082 95654128 1787719680 -0.0763875097 -0.1514177769 1.1912145615 888 35.4800000000 0.0654196292 0.0453622958 0.0959913731 0.0134618837 0.8586350000 98563776 95654128 1784418304 -0.0777754709 -0.1564033180 1.1896898746 889 35.5200000000 0.0635189936 0.0453827195 0.0959913731 0.0134639901 0.9234040000 98564210 95654128 1785942016 -0.0782937035 -0.1600165665 1.1882674694 890 35.5600000000 0.0619020946 0.0454012806 0.0959913731 0.0134727036 1.0972200000 98565904 95654128 1787719680 -0.0796626285 -0.1624674052 1.1867588758 891 35.6000000000 0.0608171299 0.0454185823 0.0959913731 0.0134784069 0.9559420000 98567598 95654128 1784418304 -0.0815562382 -0.1670273542 1.1856344938 892 35.6400000000 0.0591666102 0.0454339949 0.0959913731 0.0134833354 0.9702540000 98568172 95654128 1785942016 -0.0828112140 -0.1700063497 1.1840370893 893 35.6800000000 0.0569440536 0.0454468841 0.0959913731 0.0134889511 0.9296540000 98569866 95654128 1787719680 -0.0845523030 -0.1732495129 1.1823736429 894 35.7200000000 0.0555988960 0.0454582398 0.0959913731 0.0134980108 0.7663690000 98571560 95654128 1784418304 -0.0861516967 -0.1772858500 1.1812373400 895 35.7600000000 0.0537074730 0.0454674569 0.0959913731 0.0135041168 0.7890690000 98571994 95654128 1785958400 -0.0871979222 -0.1814551651 1.1799417734 896 35.8000000000 0.0516093634 0.0454743117 0.0959913731 0.0135197960 0.8224590000 98573688 95654128 1787719680 -0.0882901400 -0.1842356026 1.1783881187 897 35.8400000000 0.0506316796 0.0454800612 0.0959913731 0.0135350171 0.8860450000 98575382 95654128 1784418304 -0.0891096666 -0.1855560392 1.1778166294 898 35.8800000000 0.0498786792 0.0454849595 0.0959913731 0.0135438283 0.8558100000 98575956 95654128 1785942016 -0.0906303003 -0.1874328107 1.1773511171 899 35.9200000000 0.0489953458 0.0454888643 0.0959913731 0.0135498233 0.7122460000 98577650 95654128 1787846656 -0.0910359174 -0.1893008053 1.1779173613 900 35.9600000000 0.0480175167 0.0454916739 0.0959913731 0.0135513831 0.7695660000 98579344 95654128 1784545280 -0.0917568505 -0.1909725666 1.1775556803 901 36.0000000000 0.0467775539 0.0454931010 0.0959913731 0.0135566950 0.8127860000 98579778 95654128 1786195968 -0.0930817202 -0.1938305348 1.1774537563 902 36.0400000000 0.0456475541 0.0454932723 0.0959913731 0.0135648311 0.8546230000 98581472 95654128 1787854848 -0.0941598192 -0.1958490908 1.1774876118 903 36.0800000000 0.0445908904 0.0454922730 0.0959913731 0.0135738253 0.8260260000 98583166 95654128 1784553472 -0.0959118158 -0.1977868527 1.1769013405 904 36.1200000000 0.0438405983 0.0454904459 0.0959913731 0.0135883393 0.7549240000 98583740 95654128 1786077184 -0.0968337655 -0.2000937462 1.1770035028 905 36.1600000000 0.0435587540 0.0454883114 0.0959913731 0.0136100661 0.8176160000 98585434 95654128 1787981824 -0.0980600193 -0.2007826120 1.1764359474 906 36.2000000000 0.0430691056 0.0454856412 0.0959913731 0.0136314553 0.9564210000 98585868 95654128 1784680448 -0.0996869057 -0.2021577060 1.1758745909 907 36.2400000000 0.0421895459 0.0454820071 0.0959913731 0.0136482529 0.8371680000 98587562 95654128 1785950208 -0.1005204767 -0.2047346383 1.1760410070 908 36.2800000000 0.0415654816 0.0454776938 0.0959913731 0.0136614360 0.6378280000 98589256 95654128 1787744256 -0.1016481668 -0.2050928175 1.1757886410 909 36.3200000000 0.0411680788 0.0454729527 0.0959913731 0.0136693059 0.6683510000 98589690 95654128 1784299520 -0.1031164080 -0.2061259001 1.1757011414 910 36.3600000000 0.0408950895 0.0454679221 0.0959913731 0.0136758612 0.8259770000 98591524 95654128 1785823232 -0.1051006466 -0.2076210529 1.1754779816 911 36.4000000000 0.0406645946 0.0454626495 0.0959913731 0.0136808922 0.8637060000 98593218 95654128 1787592704 -0.1063286662 -0.2094430178 1.1755254269 912 36.4400000000 0.0407234468 0.0454574530 0.0959913731 0.0136862909 0.8216770000 98593652 95654128 1784590336 -0.1078688875 -0.2104763389 1.1754245758 913 36.4800000000 0.0400545448 0.0454515353 0.0959913731 0.0137498727 0.8754740000 98595346 95654128 1786068992 -0.1102629155 -0.2104856521 1.1742116213 914 36.5200000000 0.0392729267 0.0454447753 0.0959913731 0.0137649936 0.6812240000 98597040 95654128 1787973632 -0.1109635681 -0.2119584531 1.1743884087 915 36.5600000000 0.0391057134 0.0454378474 0.0959913731 0.0137819403 0.9929000000 99065918 95654128 1784799232 -0.1130426452 -0.2130344808 1.1745221615 916 36.6000000000 0.0386918671 0.0454304828 0.0959913731 0.0137960439 0.8051180000 98700612 95654128 1786449920 -0.1146150082 -0.2138007730 1.1745630503 917 36.6400000000 0.0382042192 0.0454226024 0.0959913731 0.0138053794 0.8846100000 98702306 95654128 1785434112 -0.1161044240 -0.2147960216 1.1748702526 918 36.6800000000 0.0379047319 0.0454144130 0.0959913731 0.0138153397 0.7869660000 98702740 95654128 1786830848 -0.1177356243 -0.2161804289 1.1749354601 919 36.7200000000 0.0374721885 0.0454057708 0.0959913731 0.0138288084 0.8601220000 98704434 95654128 1784705024 -0.1189357638 -0.2172370106 1.1754372120 920 36.7600000000 0.0367714800 0.0453963857 0.0959913731 0.0138419464 0.8071540000 98706128 95654128 1786195968 -0.1201329082 -0.2179864198 1.1755772829 921 36.8000000000 0.0367347971 0.0453869812 0.0959913731 0.0138505110 0.7542200000 98706562 95654128 1788100608 -0.1213358417 -0.2181091458 1.1758470535 922 36.8400000000 0.0362468995 0.0453770678 0.0959913731 0.0138554066 0.8144880000 98708396 95654128 1784672256 -0.1227922663 -0.2194746733 1.1763362885 923 36.8800000000 0.0358798057 0.0453667783 0.0959913731 0.0138590862 0.7669040000 98708830 95654128 1786322944 -0.1240409687 -0.2198747098 1.1774448156 924 36.9200000000 0.0359931663 0.0453566337 0.0959913731 0.0138613511 0.7875910000 98710524 95654128 1788227584 -0.1253109574 -0.2193712890 1.1777442694 925 36.9600000000 0.0362582691 0.0453467976 0.0959913731 0.0138641401 0.7899710000 98712218 95654128 1784950784 -0.1266594231 -0.2183098197 1.1778681278 926 37.0000000000 0.0355173089 0.0453361826 0.0959913731 0.0138644201 0.7768960000 98712652 95654128 1786449920 -0.1277702451 -0.2194525748 1.1783573627 927 37.0400000000 0.0349897705 0.0453250214 0.0959913731 0.0138667706 0.8814260000 98714346 95654128 1785815040 -0.1287456900 -0.2209506333 1.1791522503 928 37.0800000000 0.0344965793 0.0453133528 0.0959913731 0.0138747395 0.8094660000 98716180 95654128 1787338752 -0.1301543713 -0.2212574035 1.1796700954 929 37.1200000000 0.0340451524 0.0453012235 0.0959913731 0.0138822814 0.7439380000 98716614 95654128 1784713216 -0.1315322220 -0.2213328928 1.1795306206 930 37.1600000000 0.0342932902 0.0452893870 0.0959913731 0.0138903151 0.8752460000 98718308 95654128 1785982976 -0.1334037930 -0.2201925069 1.1784443855 931 37.2000000000 0.0346203372 0.0452779272 0.0959913731 0.0138962829 0.8366000000 98720002 95654128 1787981824 -0.1350951791 -0.2205759138 1.1792105436 932 37.2400000000 0.0345584676 0.0452664256 0.0959913731 0.0139098144 0.8481680000 98720436 95654128 1784680448 -0.1369281560 -0.2208932191 1.1784398556 933 37.2800000000 0.0347969793 0.0452552044 0.0959913731 0.0139331732 0.6849790000 98722130 95654128 1785950208 -0.1387611479 -0.2203031629 1.1777875423 934 37.3200000000 0.0345143452 0.0452437045 0.0959913731 0.0139518795 0.8724860000 98723964 95654128 1787854848 -0.1404452473 -0.2198747694 1.1781419516 935 37.3600000000 0.0346242450 0.0452323468 0.0959913731 0.0139636950 0.9871670000 98724398 95654128 1784426496 -0.1423106194 -0.2197948247 1.1772602797 936 37.4000000000 0.0346492529 0.0452210401 0.0959913731 0.0139725654 0.7155020000 98726092 95654128 1785856000 -0.1439501494 -0.2197765261 1.1767956018 937 37.4400000000 0.0346631892 0.0452097724 0.0959913731 0.0139784980 0.9464420000 98727786 95654128 1787854848 -0.1457911283 -0.2185190022 1.1759595871 938 37.4800000000 0.0356053002 0.0451995331 0.0959913731 0.0139825479 0.7123160000 98728220 95654128 1784553472 -0.1477316022 -0.2173384428 1.1756004095 939 37.5200000000 0.0366540141 0.0451904324 0.0959913731 0.0139883035 0.9625110000 98729914 95654128 1786077184 -0.1496644467 -0.2159281075 1.1750642061 940 37.5600000000 0.0374706872 0.0451822199 0.0959913731 0.0139917628 0.7356000000 98730488 95654128 1787981824 -0.1515073627 -0.2148597836 1.1748414040 941 37.6000000000 0.0386844799 0.0451753148 0.0959913731 0.0139944361 0.7921730000 98732182 95654128 1784553472 -0.1535132080 -0.2132796347 1.1740872860 942 37.6400000000 0.0394811966 0.0451692700 0.0959913731 0.0139971596 0.8163230000 98733876 95654128 1786204160 -0.1551124156 -0.2121364474 1.1732052565 943 37.6800000000 0.0401940495 0.0451639941 0.0959913731 0.0139987067 0.8131460000 98734310 95654128 1788235776 -0.1566371918 -0.2118224055 1.1726241112 944 37.7200000000 0.0411815010 0.0451597754 0.0959913731 0.0140024863 0.9718250000 98736004 95654128 1784180736 -0.1582526863 -0.2106413543 1.1720981598 945 37.7600000000 0.0422134921 0.0451566576 0.0959913731 0.0140065725 1.1934550000 98737698 95654128 1785704448 -0.1598827988 -0.2089975625 1.1739473343 946 37.8000000000 0.0427744277 0.0451541394 0.0959913731 0.0140099406 0.9518700000 98738272 95654128 1787482112 -0.1611381620 -0.2086573243 1.1739081144 947 37.8400000000 0.0433173552 0.0451521998 0.0959913731 0.0140117739 0.7213260000 99117254 95654128 1784717312 -0.1626411825 -0.2072627693 1.1734633446 948 37.8800000000 0.0441801995 0.0451511745 0.0959913731 0.0140122948 0.6592040000 98743708 95654128 1786212352 -0.1640300155 -0.2062004060 1.1757376194 949 37.9200000000 0.0426046625 0.0451484911 0.0959913731 0.0140105461 0.7824430000 98744142 95654128 1788116992 -0.1649153531 -0.2010359019 1.1821849346 950 37.9600000000 0.0423897468 0.0451455872 0.0959913731 0.0140096853 0.7543410000 98745836 95654128 1784606720 -0.1664799154 -0.1963801682 1.1911683083 951 38.0000000000 0.0434224494 0.0451437753 0.0959913731 0.0140136676 0.6810350000 98765730 95654128 1785958400 -0.1678761691 -0.1933818758 1.1951166391 952 38.0400000000 0.0446179472 0.0451432229 0.0959913731 0.0140158366 0.7692680000 98919300 95654128 1787990016 -0.1691173017 -0.1912777573 1.1963485479 953 38.0800000000 0.0457346365 0.0451438435 0.0959913731 0.0140153391 0.7114580000 98920994 95654128 1784561664 -0.1703596115 -0.1901008785 1.1975703239 954 38.1200000000 0.0458049364 0.0451445365 0.0959913731 0.0140133920 0.9407600000 98922688 95654128 1785958400 -0.1714694202 -0.1896135956 1.1987774372 955 38.1600000000 0.0471638106 0.0451466509 0.0959913731 0.0140163254 0.7287640000 98923122 95654128 1787879424 -0.1723617315 -0.1895832866 1.1995147467 956 38.2000000000 0.0471366160 0.0451487324 0.0959913731 0.0140160934 0.8554990000 98924816 95654128 1784307712 -0.1734539121 -0.1889765859 1.2005541325 957 38.2400000000 0.0475139134 0.0451512039 0.0959913731 0.0140138913 0.8691700000 98926510 95654128 1785823232 -0.1748706549 -0.1884821653 1.2003686428 958 38.2800000000 0.0493414365 0.0451555778 0.0959913731 0.0140139348 0.6919350000 98927084 95654128 1787854848 -0.1756562889 -0.1897285879 1.2006655931 959 38.3200000000 0.0501817800 0.0451608189 0.0959913731 0.0140123835 0.7517130000 98928778 95654128 1784426496 -0.1766198128 -0.1900914162 1.2019714117 960 38.3600000000 0.0490244702 0.0451648436 0.0959913731 0.0140098078 0.6838670000 98929212 95654128 1785950208 -0.1778641045 -0.1893154234 1.2022727728 961 38.4000000000 0.0487144850 0.0451685372 0.0959913731 0.0140060809 0.7511410000 98930906 95654128 1787727872 -0.1786068678 -0.1897534430 1.2003912926 962 38.4400000000 0.0474501140 0.0451709089 0.0959913731 0.0140008522 0.7707120000 98932600 95654128 1784426496 -0.1797926128 -0.1901850253 1.1977097988 963 38.4800000000 0.0478619896 0.0451737034 0.0959913731 0.0139985811 0.8366900000 98933034 95654128 1785950208 -0.1804692298 -0.1905825436 1.1953607798 964 38.5200000000 0.0473161228 0.0451759259 0.0959913731 0.0139948229 0.7029220000 98934868 95654128 1787727872 -0.1817674786 -0.1900929511 1.1960077286 965 38.5600000000 0.0469148122 0.0451777278 0.0959913731 0.0139922380 0.8279040000 98936562 95654128 1784426496 -0.1828459501 -0.1900429726 1.1935696602 966 38.6000000000 0.0459376313 0.0451785145 0.0959913731 0.0139900283 0.7455740000 98936996 95654128 1785950208 -0.1839437336 -0.1901484877 1.1913005114 967 38.6400000000 0.0450659245 0.0451783980 0.0959913731 0.0139884421 0.6202380000 98938690 95654128 1787727872 -0.1851115525 -0.1890811622 1.1921180487 968 38.6800000000 0.0449438840 0.0451781558 0.0959913731 0.0139890964 0.6164540000 98940384 95654128 1784455168 -0.1863642037 -0.1909421384 1.1898801327 969 38.7200000000 0.0446025915 0.0451775618 0.0959913731 0.0139920678 0.6713080000 98940818 95654128 1785950208 -0.1873670071 -0.1906653941 1.1905710697 970 38.7600000000 0.0439944863 0.0451763421 0.0959913731 0.0139894298 0.6441850000 98942652 95654128 1787854848 -0.1882931292 -0.1921511292 1.1897171736 971 38.8000000000 0.0440324247 0.0451751640 0.0959913731 0.0139903847 0.7109090000 98944346 95654128 1784565760 -0.1895179152 -0.1925998181 1.1872785091 972 38.8400000000 0.0449894667 0.0451749730 0.0959913731 0.0139935062 0.6000030000 98944780 95654128 1786077184 -0.1904080659 -0.1908671409 1.1882611513 973 38.8800000000 0.0453443192 0.0451751470 0.0959913731 0.0139931131 0.8358240000 98946474 95654128 1787854848 -0.1909916103 -0.1906109452 1.1876522303 974 38.9200000000 0.0457620472 0.0451757496 0.0959913731 0.0139926547 0.6644300000 98948168 95654128 1784565760 -0.1917275637 -0.1890030354 1.1882330179 975 38.9600000000 0.0458326004 0.0451764233 0.0959913731 0.0139927351 0.7735070000 98948602 95654128 1786077184 -0.1928230524 -0.1880240589 1.1875917912 976 39.0000000000 0.0463416502 0.0451776172 0.0959913731 0.0139912329 0.6997870000 98950436 95654128 1787727872 -0.1940422356 -0.1880065501 1.1857943535 977 39.0400000000 0.0454287305 0.0451778742 0.0959913731 0.0139880802 0.6862990000 99324166 95654128 1784426496 -0.1948474199 -0.1885386258 1.1854834557 978 39.0800000000 0.0467261523 0.0451794573 0.0959913731 0.0139883853 0.7192630000 98967884 95654128 1785966592 -0.1957507730 -0.1868765354 1.1841059923 979 39.1200000000 0.0470494628 0.0451813674 0.0959913731 0.0139863413 0.8514100000 99326422 95654128 1787854848 -0.1969745755 -0.1873407215 1.1806967258 980 39.1600000000 0.0471474491 0.0451833736 0.0959913731 0.0139855114 0.7008280000 98970140 95654128 1784807424 -0.1979959756 -0.1858391911 1.1777782440 981 39.2000000000 0.0484679267 0.0451867218 0.0959913731 0.0139873375 0.5626540000 98971834 95654128 1786077184 -0.1988539696 -0.1839353293 1.1772409678 982 39.2400000000 0.0486837626 0.0451902829 0.0959913731 0.0139846126 0.5466450000 98973668 95654128 1787981824 -0.1993807405 -0.1837969869 1.1765800714 983 39.2800000000 0.0487732887 0.0451939279 0.0959913731 0.0139832729 0.7492720000 98974102 95654128 1784680448 -0.2000802606 -0.1828271598 1.1748131514 984 39.3200000000 0.0484192893 0.0451972057 0.0959913731 0.0139849145 0.7500940000 98975796 95654128 1785950208 -0.2010574192 -0.1817983836 1.1713196039 985 39.3600000000 0.0480764434 0.0452001288 0.0959913731 0.0139807248 0.7049240000 98977490 95654128 1787760640 -0.2011099607 -0.1830280721 1.1707657576 986 39.4000000000 0.0476551726 0.0452026187 0.0959913731 0.0139788044 0.7299030000 98977924 95654128 1784553472 -0.2010145187 -0.1831309348 1.1690999269 987 39.4400000000 0.0477210432 0.0452051703 0.0959913731 0.0139771975 0.6887200000 98979618 95654128 1785950208 -0.2008615881 -0.1843470037 1.1690660715 988 39.4800000000 0.0474659763 0.0452074586 0.0959913731 0.0139749245 0.7509370000 99338744 95654128 1787727872 -0.2006800026 -0.1857543588 1.1690140963 989 39.5200000000 0.0486890003 0.0452109788 0.0959913731 0.0139735707 0.7845640000 98982462 95654128 1784553472 -0.2006761730 -0.1853953302 1.1685081720 990 39.5600000000 0.0492760539 0.0452150850 0.0959913731 0.0139747359 0.7683440000 98984156 95654128 1786085376 -0.2010323107 -0.1834143698 1.1666144133 991 39.6000000000 0.0493486971 0.0452192561 0.0959913731 0.0139718556 0.7685760000 99342758 95654128 1787736064 -0.2010716200 -0.1835233718 1.1644169092 992 39.6400000000 0.0492543019 0.0452233237 0.0959913731 0.0139692795 0.8072030000 98986476 95654128 1784434688 -0.2011851668 -0.1834139824 1.1628752947 993 39.6800000000 0.0488291532 0.0452269549 0.0959913731 0.0139669010 0.6151680000 98988170 95654128 1785974784 -0.2019517869 -0.1828951091 1.1589727402 994 39.7200000000 0.0504962467 0.0452322560 0.0959913731 0.0139643435 0.7538260000 98988744 95654128 1787736064 -0.2020665705 -0.1824770421 1.1578454971 995 39.7600000000 0.0492460988 0.0452362901 0.0959913731 0.0139630153 0.7704060000 98990438 95654128 1784434688 -0.2029113322 -0.1802284569 1.1510747671 996 39.8000000000 0.0489254184 0.0452399940 0.0959913731 0.0139643770 0.8054330000 98992132 95654128 1785958400 -0.2030180544 -0.1812952906 1.1507717371 997 39.8400000000 0.0504539125 0.0452452236 0.0959913731 0.0139601917 0.7394850000 98992566 95654128 1787736064 -0.2033407092 -0.1790274382 1.1505743265 998 39.8800000000 0.0509603396 0.0452509502 0.0959913731 0.0139546711 0.7474670000 98994260 95654128 1784455168 -0.2036498338 -0.1768832654 1.1480168104 999 39.9200000000 0.0521684624 0.0452578746 0.0959913731 0.0139731427 0.6339070000 98995954 95654128 1785958400 -0.2041591406 -0.1757194102 1.1458752155 1000 39.9600000000 0.0527182147 0.0452653350 0.0959913731 0.0139692002 0.6146220000 98996528 95654128 1787727872 -0.2045044005 -0.1738349050 1.1441510916 1001 40.0000000000 0.0533973873 0.0452734589 0.0959913731 0.0139636564 0.5819760000 99015194 95654128 1784455168 -0.2051502615 -0.1706316173 1.1401977539 1002 40.0400000000 0.0543431751 0.0452825105 0.0959913731 0.0139572879 1.0374800000 99170888 95654128 1785950208 -0.2057598233 -0.1677063853 1.1367225647 1003 40.0800000000 0.0548422895 0.0452920417 0.0959913731 0.0139552972 0.8833280000 99171322 95654128 1787981824 -0.2060106695 -0.1661944985 1.1349897385 1004 40.1200000000 0.0554007925 0.0453021102 0.0959913731 0.0139597426 0.7373940000 99173016 95654128 1784680448 -0.2062645555 -0.1677553207 1.1346695423 1005 40.1600000000 0.0557672307 0.0453125232 0.0959913731 0.0139619150 0.6665130000 99174710 95654128 1786077184 -0.2068811208 -0.1682721972 1.1348836422 1006 40.2000000000 0.0565160550 0.0453236599 0.0959913731 0.0139739390 0.6889260000 99175284 95654128 1787981824 -0.2068739533 -0.1696074456 1.1350004673 1007 40.2400000000 0.0566336960 0.0453348913 0.0959913731 0.0139759277 0.8574560000 99176978 95654128 1784299520 -0.2067373544 -0.1710019112 1.1331497431 1008 40.2800000000 0.0572998226 0.0453467613 0.0959913731 0.0139747528 0.7766440000 99178672 95654128 1785696256 -0.2064364702 -0.1717506647 1.1327334642 1009 40.3200000000 0.0578520671 0.0453591551 0.0959913731 0.0139730643 0.6775600000 99179106 95654128 1787600896 -0.2065323889 -0.1719304323 1.1314585209 1010 40.3600000000 0.0594468787 0.0453731033 0.0959913731 0.0139710427 0.8861570000 99180800 95654128 1784553472 -0.2067102790 -0.1698748320 1.1290184259 1011 40.4000000000 0.0606653951 0.0453882292 0.0959913731 0.0139890391 0.6980960000 99182494 95654128 1785950208 -0.2066128850 -0.1713519841 1.1285450459 1012 40.4400000000 0.0606171787 0.0454032776 0.0959913731 0.0140107642 0.7410210000 99183068 95654128 1787600896 -0.2060176134 -0.1739084274 1.1280810833 1013 40.4800000000 0.0610275827 0.0454187014 0.0959913731 0.0140115684 0.7212130000 99184762 95654128 1784553472 -0.2062770426 -0.1739825159 1.1262116432 1014 40.5200000000 0.0620788001 0.0454351315 0.0959913731 0.0140133590 0.7158210000 99185196 95654128 1785966592 -0.2064904720 -0.1722357273 1.1249405146 1015 40.5600000000 0.0620763153 0.0454515267 0.0959913731 0.0140273900 0.7622000000 99186890 95654128 1787854848 -0.2064378709 -0.1721669734 1.1238478422 1016 40.6000000000 0.0641699582 0.0454699504 0.0959913731 0.0140481439 0.6178710000 99188584 95654128 1784553472 -0.2069042176 -0.1723815650 1.1254856586 1017 40.6400000000 0.0647588670 0.0454889169 0.0959913731 0.0140562699 0.6521110000 99189018 95654128 1785966592 -0.2069978565 -0.1728480160 1.1243233681 1018 40.6800000000 0.0655917078 0.0455086642 0.0959913731 0.0140679340 0.6848330000 99190852 95654128 1787854848 -0.2074256241 -0.1733263582 1.1238887310 1019 40.7200000000 0.0657252669 0.0455285039 0.0959913731 0.0140796301 0.6212600000 99192546 95654128 1784680448 -0.2080301046 -0.1738802493 1.1226347685 1020 40.7600000000 0.0659884289 0.0455485626 0.0959913731 0.0140835189 0.5967540000 99192980 95654128 1786093568 -0.2085878998 -0.1732247621 1.1216386557 1021 40.8000000000 0.0680233017 0.0455705751 0.0959913731 0.0140992052 0.6094610000 99194674 95654128 1787981824 -0.2088157982 -0.1736090779 1.1224329472 1022 40.8400000000 0.0700297132 0.0455945077 0.0959913731 0.0140986342 0.6074910000 99196368 95654128 1784680448 -0.2101550698 -0.1702867001 1.1228018999 1023 40.8800000000 0.0701871440 0.0456185474 0.0959913731 0.0141054382 0.6669790000 99196802 95654128 1786093568 -0.2106845081 -0.1696181446 1.1221894026 1024 40.9200000000 0.0708507746 0.0456431883 0.0959913731 0.0141208252 0.9865710000 99198636 95654128 1787981824 -0.2111738920 -0.1691555828 1.1215488911 1025 40.9600000000 0.0729026869 0.0456697829 0.0959913731 0.0141529964 0.6477890000 99282250 95654128 1784299520 -0.2114393562 -0.1693734378 1.1228336096 1026 41.0000000000 0.0751675367 0.0456985331 0.0959913731 0.0141852256 0.7061000000 99450620 95654128 1785823232 -0.2118424326 -0.1695060730 1.1231783628 1027 41.0400000000 0.0747964829 0.0457268661 0.0959913731 0.0141936799 0.6631540000 99452314 95654128 1787998208 -0.2126217932 -0.1683302373 1.1204782724 1028 41.0800000000 0.0752955675 0.0457556294 0.0959913731 0.0142013094 0.6273000000 99454008 95654128 1784332288 -0.2125170827 -0.1648271680 1.1197535992 1029 41.1200000000 0.0774441212 0.0457864249 0.0959913731 0.0142108382 0.6781320000 99454442 95654128 1785823232 -0.2128248662 -0.1643020958 1.1202325821 1030 41.1600000000 0.0802151859 0.0458198508 0.0959913731 0.0142196558 0.5457570000 99456276 95654128 1787600896 -0.2134388387 -0.1645365655 1.1212944984 1031 41.2000000000 0.0788391083 0.0458518773 0.0959913731 0.0142218668 0.6545260000 99456710 95654128 1784426496 -0.2135497928 -0.1622671634 1.1176619530 1032 41.2400000000 0.0793787539 0.0458843646 0.0959913731 0.0142207570 0.7116060000 99458404 95654128 1785950208 -0.2141238600 -0.1601398885 1.1161816120 1033 41.2800000000 0.0814150423 0.0459187602 0.0959913731 0.0142212737 0.7746630000 99460098 95654128 1787854848 -0.2143870741 -0.1610557288 1.1171214581 1034 41.3200000000 0.0815946907 0.0459532630 0.0959913731 0.0142356938 0.7821960000 99460532 95654128 1784807424 -0.2145390511 -0.1576339155 1.1141182184 1035 41.3600000000 0.0815352574 0.0459876418 0.0959913731 0.0142323930 0.8201380000 99462226 95654128 1786077184 -0.2144078910 -0.1577771008 1.1130735874 1036 41.4000000000 0.0821041763 0.0460225033 0.0959913731 0.0142375980 0.6866220000 99464060 95654128 1787981824 -0.2147700489 -0.1564209908 1.1119087934 1037 41.4400000000 0.0817007050 0.0460569085 0.0959913731 0.0142391060 0.6866930000 99464494 95654128 1784434688 -0.2156434953 -0.1533774287 1.1100349426 1038 41.4800000000 0.0830506757 0.0460925480 0.0959913731 0.0142391292 0.6462690000 99466188 95654128 1785847808 -0.2163747102 -0.1510880291 1.1094491482 1039 41.5200000000 0.0835429803 0.0461285926 0.0959913731 0.0142474677 0.5635410000 99467882 95654128 1787482112 -0.2166336626 -0.1485617906 1.1085168123 1040 41.5600000000 0.0838023424 0.0461648174 0.0959913731 0.0142569885 0.7974980000 99468316 95654128 1784688640 -0.2166403979 -0.1467916816 1.1075019836 1041 41.6000000000 0.0846531391 0.0462017899 0.0959913731 0.0142639790 0.6671090000 99470010 95654128 1786101760 -0.2167620659 -0.1450531185 1.1073768139 1042 41.6400000000 0.0836620256 0.0462377402 0.0959913731 0.0142733162 0.7006030000 99471844 95654128 1787863040 -0.2171661705 -0.1446380019 1.1046075821 1043 41.6800000000 0.0819635019 0.0462719931 0.0959913731 0.0142812523 0.6995070000 99472278 95654128 1784561664 -0.2170898765 -0.1434807628 1.1012158394 1044 41.7200000000 0.0830172226 0.0463071896 0.0959913731 0.0142863208 0.6909920000 99473972 95654128 1786101760 -0.2175292522 -0.1426005512 1.1012203693 1045 41.7600000000 0.0832702368 0.0463425610 0.0959913731 0.0142860874 0.7201870000 99573530 95654128 1787863040 -0.2174495310 -0.1400484145 1.1015703678 1046 41.8000000000 0.0819221362 0.0463765759 0.0959913731 0.0142813759 0.6881810000 99646928 95654128 1784688640 -0.2172183543 -0.1374554038 1.0993449688 1047 41.8400000000 0.0813390017 0.0464099688 0.0959913731 0.0142812163 0.6049160000 99648622 95654128 1786101760 -0.2172913104 -0.1387822926 1.0980627537 1048 41.8800000000 0.0812307969 0.0464431948 0.0959913731 0.0142799178 0.5875760000 99649196 95654128 1787990016 -0.2174031734 -0.1394456327 1.0963996649 1049 41.9200000000 0.0803006738 0.0464754708 0.0959913731 0.0142834878 0.7054400000 99650890 95654128 1784434688 -0.2174574733 -0.1403839588 1.0935286283 1050 41.9600000000 0.0808154866 0.0465081755 0.0959913731 0.0142863424 0.5876150000 99652584 95654128 1785966592 -0.2176612169 -0.1402444988 1.0925792456 1051 42.0000000000 0.0817031711 0.0465416627 0.0959913731 0.0142862750 0.6710200000 99653018 95654128 1787727872 -0.2180409878 -0.1408058107 1.0919791460 1052 42.0400000000 0.0815990493 0.0465749872 0.0959913731 0.0142828582 0.6854730000 99654712 95654128 1784426496 -0.2179245353 -0.1392344981 1.0916156769 1053 42.0800000000 0.0836351588 0.0466101821 0.0959913731 0.0142817366 0.6242480000 99656406 95654128 1785966592 -0.2182913423 -0.1379037946 1.0926159620 1054 42.1200000000 0.0850001127 0.0466466051 0.0959913731 0.0142827913 0.7106930000 99656980 95654128 1787727872 -0.2189011276 -0.1385513842 1.0928026438 1055 42.1600000000 0.0865868106 0.0466844631 0.0959913731 0.0142852692 0.6237520000 99658674 95654128 1784426496 -0.2193026245 -0.1393856406 1.0933125019 1056 42.2000000000 0.0867727771 0.0467224256 0.0959913731 0.0142852215 0.7203610000 99660368 95654128 1785950208 -0.2191076279 -0.1369624734 1.0936964750 1057 42.2400000000 0.0885278136 0.0467619766 0.0959913731 0.0142959649 0.7051610000 99660802 95654128 1787727872 -0.2197065502 -0.1394715160 1.0938200951 1058 42.2800000000 0.0878985524 0.0468008580 0.0959913731 0.0142916075 0.7727720000 99662496 95654128 1784553472 -0.2200674564 -0.1391330510 1.0927851200 1059 42.3200000000 0.0874607190 0.0468392526 0.0959913731 0.0142884057 0.7395590000 99664190 95654128 1785950208 -0.2205187380 -0.1399305612 1.0918748379 1060 42.3600000000 0.0895016640 0.0468795001 0.0959913731 0.0142860760 0.6692020000 99664764 95654128 1787981824 -0.2213628143 -0.1394586265 1.0941131115 1061 42.4000000000 0.0884759873 0.0469187051 0.0959913731 0.0142818070 0.6197180000 99666458 95654128 1784680448 -0.2215603143 -0.1388001293 1.0930597782 1062 42.4400000000 0.0887717828 0.0469581148 0.0959913731 0.0142851128 0.7416810000 99668152 95654128 1785950208 -0.2221178114 -0.1343641728 1.0967605114 1063 42.4800000000 0.0894296691 0.0469980692 0.0959913731 0.0142815169 0.6497540000 99668586 95654128 1787854848 -0.2228197902 -0.1344791353 1.0977404118 1064 42.5200000000 0.0902969614 0.0470387637 0.0959913731 0.0142773375 0.6485620000 99670280 95654128 1784459264 -0.2233223915 -0.1343831122 1.0990772247 1065 42.5600000000 0.0927978083 0.0470817299 0.0959913731 0.0142758692 0.6403440000 99671974 95654128 1785823232 -0.2240639925 -0.1350470781 1.1021664143 1066 42.6000000000 0.0918205753 0.0471236988 0.0959913731 0.0142707113 0.5327020000 99672548 95654128 1787727872 -0.2238634676 -0.1338251680 1.1013164520 1067 42.6400000000 0.0912915766 0.0471650933 0.0959913731 0.0142661008 0.6160440000 99674242 95654128 1784426496 -0.2237708271 -0.1318957657 1.1019421816 1068 42.6800000000 0.0909151658 0.0472060577 0.0959913731 0.0142639600 0.6016040000 99674676 95654128 1785950208 -0.2235050499 -0.1307325959 1.1027777195 1069 42.7200000000 0.0909403041 0.0472469691 0.0959913731 0.0142683250 0.7090590000 99774614 95654128 1787727872 -0.2234972566 -0.1323180944 1.1020789146 1070 42.7600000000 0.0914012641 0.0472882348 0.0959913731 0.0142717596 0.6912360000 99849756 95654128 1784426496 -0.2235873938 -0.1341274977 1.1010661125 1071 42.8000000000 0.0917568356 0.0473297554 0.0959913731 0.0142724998 0.5470280000 99850190 95654128 1785950208 -0.2239714265 -0.1348792464 1.1020220518 1072 42.8400000000 0.0925236493 0.0473719139 0.0959913731 0.0142710779 0.5407380000 99852024 95654128 1787727872 -0.2245107889 -0.1352882981 1.1038719416 1073 42.8800000000 0.0921461955 0.0474136421 0.0959913731 0.0142652039 0.5757820000 99853718 95654128 1784426496 -0.2246004641 -0.1348259449 1.1029274464 1074 42.9200000000 0.0919534713 0.0474551130 0.0959913731 0.0142592126 0.7063440000 99854152 95654128 1785966592 -0.2246704549 -0.1325711906 1.1041662693 1075 42.9600000000 0.0922527984 0.0474967853 0.0959913731 0.0142527622 0.7717970000 99855846 95654128 1787600896 -0.2246848643 -0.1303141713 1.1053459644 1076 43.0000000000 0.0939886719 0.0475399934 0.0959913731 0.0142499562 0.7012880000 99857540 95654128 1784426496 -0.2255952954 -0.1309755594 1.1081680059 1077 43.0400000000 0.0944712535 0.0475835693 0.0959913731 0.0142465799 0.6538310000 99857974 95654128 1785950208 -0.2263052464 -0.1318240762 1.1103582382 1078 43.0800000000 0.0959674567 0.0476284523 0.0959913731 0.0142453108 0.7745040000 99859808 95654128 1787854848 -0.2265528589 -0.1304901987 1.1142685413 1079 43.1200000000 0.0983996540 0.0476755062 0.0983996540 0.0142449760 0.7366710000 99861502 95654128 1784446976 -0.2272104472 -0.1303755194 1.1192537546 1080 43.1600000000 0.0987215638 0.0477227711 0.0987215638 0.0142393328 0.9004060000 99861936 95654128 1785950208 -0.2272844017 -0.1277424246 1.1227953434 1081 43.2000000000 0.1003159508 0.0477714234 0.1003159508 0.0142469197 0.6920480000 99863630 95654128 1787854848 -0.2283835262 -0.1311121583 1.1249426603 1082 43.2400000000 0.1020766571 0.0478216131 0.1020766571 0.0142493172 0.5747330000 99865324 95654128 1784692736 -0.2290227413 -0.1322346479 1.1276113987 1083 43.2800000000 0.1037284210 0.0478732353 0.1037284210 0.0142557380 0.7479510000 99865758 95654128 1786077184 -0.2294659913 -0.1334681362 1.1307338476 1084 43.3200000000 0.1034196913 0.0479244774 0.1037284210 0.0142515939 0.8896130000 99867592 95654128 1787854848 -0.2295784652 -0.1332963407 1.1309180260 1085 43.3600000000 0.1023847088 0.0479746712 0.1037284210 0.0142454903 0.8586920000 99868026 95654128 1784680448 -0.2293437272 -0.1323005408 1.1308012009 1086 43.4000000000 0.1016272902 0.0480240751 0.1037284210 0.0142409457 0.5746330000 99869720 95654128 1786093568 -0.2294185907 -0.1321071237 1.1301656961 1087 43.4400000000 0.1017048210 0.0480734594 0.1037284210 0.0142369197 0.6717000000 99968414 95654128 1788108800 -0.2295140773 -0.1313190460 1.1319102049 1088 43.4800000000 0.1010303274 0.0481221330 0.1037284210 0.0142308668 0.6713390000 100042660 95654128 1784307712 -0.2291795313 -0.1296849698 1.1323883533 1089 43.5200000000 0.1009151787 0.0481706114 0.1037284210 0.0142262506 0.6374710000 100044354 95654128 1785704448 -0.2288748324 -0.1275139600 1.1350727081 1090 43.5600000000 0.1012199000 0.0482192805 0.1037284210 0.0142210350 0.5894490000 100046188 95654128 1787514880 -0.2282089293 -0.1258783340 1.1377178431 1091 43.6000000000 0.1033257768 0.0482697906 0.1037284210 0.0142197787 0.5530660000 100046622 95654128 1784688640 -0.2283031195 -0.1266212910 1.1407798529 1092 43.6400000000 0.1034299731 0.0483203036 0.1037284210 0.0142194089 0.7445530000 100048316 95654128 1786101760 -0.2281990200 -0.1277250051 1.1421794891 1093 43.6800000000 0.1044978052 0.0483717011 0.1044978052 0.0142189314 0.8104460000 100050010 95654128 1787863040 -0.2282819152 -0.1287519485 1.1444965601 1094 43.7200000000 0.1049195901 0.0484233902 0.1049195901 0.0142168465 0.7412970000 100050444 95654128 1784688640 -0.2280882299 -0.1282243282 1.1467349529 1095 43.7600000000 0.1059262827 0.0484759043 0.1059262827 0.0142174577 0.7694630000 100052138 95654128 1786085376 -0.2285864651 -0.1299399137 1.1486057043 1096 43.8000000000 0.1071576476 0.0485294460 0.1071576476 0.0142171864 0.6621300000 100053972 95654128 1787854848 -0.2288399637 -0.1320996881 1.1498745680 1097 43.8400000000 0.1091180518 0.0485846772 0.1091180518 0.0142158178 0.7253700000 100054406 95654128 1784684544 -0.2290888727 -0.1331291348 1.1534086466 1098 43.8800000000 0.1117477715 0.0486422028 0.1117477715 0.0142121032 0.5627820000 100056100 95654128 1786077184 -0.2295837402 -0.1332674026 1.1577123404 1099 43.9200000000 0.1119390503 0.0486997977 0.1119390503 0.0142071500 0.5701240000 100057794 95654128 1787981824 -0.2293258458 -0.1332518756 1.1579971313 1100 43.9600000000 0.1121879742 0.0487575142 0.1121879742 0.0142031026 0.6113560000 100058228 95654128 1784553472 -0.2285724431 -0.1309949905 1.1618615389 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:58:14 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.2389440000 88427794 95654128 1752367104 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0013824130 0.0006912065 0.0013824130 0.0024910870 1.3388040000 88636274 95654128 1755160576 0.0013812575 0.0003508669 0.0001632988 3 0.0800000000 0.0010363186 0.0008062439 0.0013824130 0.0022441950 1.0423320000 88638292 95654128 1757319168 0.0008455459 -0.0017799647 -0.0005858577 4 0.1200000000 0.0005300906 0.0007372056 0.0013824130 0.0018684094 1.0685850000 88639054 95654128 1759096832 0.0002088040 -0.0012000720 -0.0002909744 5 0.1600000000 0.0014999188 0.0008897482 0.0014999188 0.0020455152 1.2095240000 88641068 95654128 1760874496 -0.0013151702 -0.0017727846 0.0000980004 6 0.2000000000 0.0012231277 0.0009453114 0.0014999188 0.0018791028 1.0902170000 88643418 95654128 1762525184 -0.0000010201 -0.0031980048 -0.0000420445 7 0.2400000000 0.0023489473 0.0011458309 0.0023489473 0.0017836910 1.6624270000 88643852 95654128 1764175872 0.0013491623 -0.0042034723 -0.0001894180 8 0.2800000000 0.0031228950 0.0013929639 0.0031228950 0.0017464132 1.9519370000 88645546 95654128 1765650432 0.0020729294 -0.0031684164 0.0001410516 9 0.3200000000 0.0054810019 0.0018471903 0.0054810019 0.0018185249 1.7914760000 88647880 95654128 1767403520 0.0052081756 -0.0027008587 0.0002153475 10 0.3600000000 0.0056204847 0.0022245198 0.0056204847 0.0017371846 1.9605220000 88649626 95654128 1769033728 0.0052520870 -0.0038804072 0.0000630099 11 0.4000000000 0.0086769043 0.0028111002 0.0086769043 0.0018534562 1.4592440000 88651320 95654128 1770934272 0.0079627344 -0.0044535836 0.0002152058 12 0.4400000000 0.0108587816 0.0034817403 0.0108587816 0.0018508209 0.8849240000 88653014 95654128 1772457984 0.0102843642 -0.0035544061 0.0005600865 13 0.4800000000 0.0114433011 0.0040941681 0.0114433011 0.0018665395 1.0827920000 88653448 95654128 1774235648 0.0111475298 -0.0019142503 0.0007589297 14 0.5200000000 0.0113679711 0.0046137254 0.0114433011 0.0018848206 1.9274170000 88655142 95654128 1775988736 0.0113631701 -0.0010269042 0.0008326165 15 0.5600000000 0.0111102751 0.0050468287 0.0114433011 0.0018905038 1.7187240000 88656836 95654128 1777774592 0.0110925371 -0.0008569338 0.0009716242 16 0.6000000000 0.0108163543 0.0054074241 0.0114433011 0.0018418086 1.8264220000 88657270 95654128 1779425280 0.0111189820 -0.0008228489 0.0009835754 17 0.6400000000 0.0097236829 0.0056613216 0.0114433011 0.0017914580 2.1102130000 88660244 95654128 1780924416 0.0099018971 -0.0008922432 0.0010725072 18 0.6800000000 0.0111722499 0.0059674843 0.0114433011 0.0017585726 2.2815130000 88664562 95654128 1782829056 0.0113765318 -0.0006697292 0.0008683380 19 0.7200000000 0.0104926014 0.0062056484 0.0114433011 0.0020386587 1.8834510000 88664996 95654128 1784479744 0.0106255999 -0.0004623065 0.0007153624 20 0.7600000000 0.0108499294 0.0064378624 0.0114433011 0.0021676945 1.6862990000 88666690 95654128 1786114048 0.0107553694 -0.0020464975 0.0006432245 21 0.8000000000 0.0114195142 0.0066750839 0.0114433011 0.0023796586 2.5246250000 88668384 95654128 1787781120 0.0112472149 -0.0020249973 0.0003799288 22 0.8400000000 0.0113544548 0.0068877826 0.0114433011 0.0024587331 2.2186210000 88668818 95654128 1784463360 0.0112540657 -0.0022081567 0.0003543397 23 0.8800000000 0.0113824382 0.0070832024 0.0114433011 0.0024877192 2.0667450000 88670512 95654128 1785860096 0.0108199753 -0.0032892667 0.0002854304 24 0.9200000000 0.0128078135 0.0073217279 0.0128078135 0.0024832092 1.5465130000 88672206 95654128 1787756544 0.0121436836 -0.0038424740 0.0003211499 25 0.9600000000 0.0108796982 0.0074640467 0.0128078135 0.0024875855 1.4597950000 88672640 95654128 1785344000 0.0094714239 -0.0049006799 0.0003520020 26 1.0000000000 0.0106528131 0.0075866916 0.0128078135 0.0024816202 2.7127350000 88674334 95654128 1786740736 0.0095728310 -0.0041628880 0.0004390136 27 1.0400000000 0.0095114522 0.0076579790 0.0128078135 0.0024958866 1.6911230000 88676028 95654128 1785090048 0.0079825679 -0.0045113624 0.0003925595 28 1.0800000000 0.0095635839 0.0077260363 0.0128078135 0.0024991509 1.6781070000 88676462 95654128 1786359808 0.0079260832 -0.0046442826 0.0002644585 29 1.1200000000 0.0080038346 0.0077356156 0.0128078135 0.0025299745 2.3951850000 88678156 95654128 1785724928 0.0053398404 -0.0050806096 0.0003928833 30 1.1600000000 0.0076535018 0.0077328784 0.0128078135 0.0025538012 1.8320470000 88679850 95654128 1787121664 0.0050928392 -0.0047438755 0.0002820483 31 1.2000000000 0.0086527718 0.0077625524 0.0128078135 0.0025181971 2.2514650000 88680284 95654128 1785217024 0.0064017866 -0.0045697540 0.0000184043 32 1.2400000000 0.0094145518 0.0078141774 0.0128078135 0.0024829008 2.2310710000 88681978 95654128 1786613760 0.0065417355 -0.0057964465 0.0001406034 33 1.2800000000 0.0093720378 0.0078613853 0.0128078135 0.0025325599 1.8807910000 88686232 95654128 1785090048 0.0063837911 -0.0054071010 0.0002182033 34 1.3200000000 0.0085470248 0.0078815512 0.0128078135 0.0025568922 1.5008740000 88691914 95654128 1786486784 0.0048414660 -0.0058911163 0.0004357440 35 1.3600000000 0.0074946890 0.0078704980 0.0128078135 0.0026272113 2.1924980000 88693608 95654128 1785851904 0.0014399325 -0.0081439652 0.0002769812 36 1.4000000000 0.0089768870 0.0079012310 0.0128078135 0.0026065758 2.1846770000 88695302 95654128 1787248640 0.0008634194 -0.0100636380 0.0004791718 37 1.4400000000 0.0118021676 0.0080066617 0.0128078135 0.0026103935 2.1369530000 88695736 95654128 1785479168 0.0020463038 -0.0120877139 0.0008445543 38 1.4800000000 0.0129953055 0.0081379418 0.0129953055 0.0025844905 1.8993500000 88697430 95654128 1786875904 0.0025743027 -0.0136271566 0.0011873937 39 1.5200000000 0.0144799761 0.0083005581 0.0144799761 0.0025794364 1.9048850000 88699124 95654128 1784971264 0.0036518059 -0.0159333851 0.0010793958 40 1.5600000000 0.0161192361 0.0084960250 0.0161192361 0.0027332285 1.5258170000 88699558 95654128 1786384384 0.0034097023 -0.0173197761 0.0018019057 41 1.6000000000 0.0175754651 0.0087174748 0.0175754651 0.0029405960 2.3148760000 88701252 95654128 1785622528 0.0027233439 -0.0178645104 0.0025772352 42 1.6400000000 0.0188821740 0.0089594914 0.0188821740 0.0029696420 2.1821370000 88702946 95654128 1787121664 0.0019153658 -0.0196380597 0.0032302958 43 1.6800000000 0.0197363868 0.0092101169 0.0197363868 0.0029592007 1.8318490000 88703380 95654128 1785090048 0.0005131414 -0.0210644212 0.0039296327 44 1.7200000000 0.0191383250 0.0094357580 0.0197363868 0.0029338471 1.2556280000 88705074 95654128 1786486784 -0.0004751786 -0.0202102773 0.0045889160 45 1.7600000000 0.0182854198 0.0096324171 0.0197363868 0.0029203664 1.6433980000 88706768 95654128 1785851904 -0.0009246627 -0.0198673327 0.0051018354 46 1.8000000000 0.0183019266 0.0098208847 0.0197363868 0.0030429220 1.4168470000 88707202 95654128 1787121664 -0.0009528596 -0.0208927691 0.0059642997 47 1.8400000000 0.0185512062 0.0100066363 0.0197363868 0.0031185921 2.2509230000 88708896 95654128 1784836096 -0.0007435938 -0.0214561522 0.0069310768 48 1.8800000000 0.0177324601 0.0101675909 0.0197363868 0.0032921339 1.6767710000 88710590 95654128 1786105856 -0.0008235492 -0.0205397867 0.0084533663 49 1.9200000000 0.0168399233 0.0103037610 0.0197363868 0.0035306124 2.1987240000 88711024 95654128 1788137472 -0.0017747469 -0.0213881079 0.0092615755 50 1.9600000000 0.0153180249 0.0104040463 0.0197363868 0.0038083045 1.8500960000 88712718 95654128 1784963072 -0.0020917698 -0.0204380155 0.0107925367 51 2.0000000000 0.0142779080 0.0104800043 0.0197363868 0.0039722982 1.6135400000 88714412 95654128 1786232832 -0.0018409669 -0.0190773662 0.0126508353 52 2.0400000000 0.0136057558 0.0105401149 0.0197363868 0.0041548096 1.6828690000 88714846 95654128 1788137472 -0.0023306704 -0.0188435055 0.0143994233 53 2.0800000000 0.0122181233 0.0105717755 0.0197363868 0.0041855499 2.3695620000 88716540 95654128 1784709120 -0.0035201372 -0.0190590005 0.0155446762 54 2.1200000000 0.0122171668 0.0106022457 0.0197363868 0.0042927372 1.8355960000 88718234 95654128 1785978880 -0.0027940935 -0.0198039804 0.0174047388 55 2.1600000000 0.0116964187 0.0106221397 0.0197363868 0.0042956330 1.8032750000 88718668 95654128 1787899904 -0.0040652826 -0.0191682484 0.0195997339 56 2.2000000000 0.0104168374 0.0106184736 0.0197363868 0.0042876481 2.5179300000 88720362 95654128 1784336384 -0.0052356706 -0.0175535250 0.0216345955 57 2.2400000000 0.0114557976 0.0106331635 0.0197363868 0.0043121362 1.9512330000 88722056 95654128 1785733120 -0.0027500354 -0.0187957473 0.0243003555 58 2.2800000000 0.0090274774 0.0106054793 0.0197363868 0.0044088989 1.9357190000 88722490 95654128 1787637760 -0.0027404409 -0.0152738336 0.0271595679 59 2.3200000000 0.0087917941 0.0105747388 0.0197363868 0.0044547996 1.9240020000 88724184 95654128 1784590336 -0.0002723851 -0.0153286401 0.0300678667 60 2.3600000000 0.0078739310 0.0105297254 0.0197363868 0.0047332902 2.0692390000 88725878 95654128 1785987072 0.0009160354 -0.0157301743 0.0322662145 61 2.4000000000 0.0075040273 0.0104801238 0.0197363868 0.0049367413 1.3592040000 88726312 95654128 1787764736 0.0030085619 -0.0152708367 0.0351734720 62 2.4400000000 0.0077402568 0.0104359324 0.0197363868 0.0051746234 1.8190890000 88728006 95654128 1784709120 0.0045744954 -0.0155576915 0.0379744321 63 2.4800000000 0.0085739680 0.0104063774 0.0197363868 0.0053262182 2.2771620000 88729700 95654128 1785978880 0.0066521298 -0.0169045907 0.0406403169 64 2.5200000000 0.0086660534 0.0103791848 0.0197363868 0.0054538573 2.1812640000 88730134 95654128 1787883520 0.0085637877 -0.0165886134 0.0437039472 65 2.5600000000 0.0087980535 0.0103548597 0.0197363868 0.0057074182 1.9254860000 88736948 95654128 1784709120 0.0094192000 -0.0172046106 0.0464665107 66 2.6000000000 0.0090203770 0.0103346403 0.0197363868 0.0060466267 2.1253740000 88749138 95654128 1785978880 0.0108166952 -0.0184996054 0.0490524545 67 2.6400000000 0.0090444880 0.0103153843 0.0197363868 0.0063325679 1.6815200000 88749572 95654128 1787883520 0.0129241664 -0.0170736853 0.0522766337 68 2.6800000000 0.0086852349 0.0102914115 0.0197363868 0.0067274463 2.1055150000 88751266 95654128 1784582144 0.0139401890 -0.0163092501 0.0551125444 69 2.7200000000 0.0085678827 0.0102664328 0.0197363868 0.0069192558 1.2938650000 88752960 95654128 1785851904 0.0162526406 -0.0168734416 0.0578456335 70 2.7600000000 0.0089381784 0.0102474578 0.0197363868 0.0070538052 1.7368010000 88753394 95654128 1787883520 0.0175328832 -0.0180761404 0.0603093281 71 2.8000000000 0.0089818928 0.0102296329 0.0197363868 0.0070734509 1.9159430000 88755088 95654128 1784709120 0.0190899633 -0.0172902867 0.0634125024 72 2.8400000000 0.0095726363 0.0102205079 0.0197363868 0.0070588171 2.0115220000 88756782 95654128 1785978880 0.0197458994 -0.0184420776 0.0660813376 73 2.8800000000 0.0102076204 0.0102203314 0.0197363868 0.0070527505 1.7301260000 88757216 95654128 1788010496 0.0215342250 -0.0195091572 0.0684455708 74 2.9200000000 0.0095104137 0.0102107379 0.0197363868 0.0070572893 1.5594530000 88758910 95654128 1784844288 0.0219954308 -0.0181832984 0.0710783824 75 2.9600000000 0.0098742619 0.0102062516 0.0197363868 0.0071319573 2.0934180000 88760604 95654128 1786114048 0.0235877167 -0.0181559715 0.0739835128 76 3.0000000000 0.0100078573 0.0102036411 0.0197363868 0.0072945014 1.5139340000 88761038 95654128 1788145664 0.0252202731 -0.0194878876 0.0762358457 77 3.0400000000 0.0100459401 0.0102015931 0.0197363868 0.0074691300 2.5012950000 88762732 95654128 1784971264 0.0265542995 -0.0206154846 0.0783142671 78 3.0800000000 0.0102942307 0.0102027807 0.0197363868 0.0076841880 1.6709300000 88764426 95654128 1786232832 0.0280867517 -0.0201886576 0.0809721500 79 3.1200000000 0.0099732941 0.0101998758 0.0197363868 0.0078886363 1.8921390000 88764860 95654128 1788153856 0.0291922167 -0.0195777044 0.0836749449 80 3.1600000000 0.0094536897 0.0101905485 0.0197363868 0.0080329542 2.4366910000 88766554 95654128 1784709120 0.0301969089 -0.0201329999 0.0858168378 81 3.2000000000 0.0104010627 0.0101931474 0.0197363868 0.0081828829 2.3503100000 88768248 95654128 1786105856 0.0318879113 -0.0212517865 0.0884020627 82 3.2400000000 0.0103042070 0.0101945018 0.0197363868 0.0083424630 1.8968150000 88768682 95654128 1788137472 0.0324761011 -0.0213691443 0.0909830630 83 3.2800000000 0.0106121246 0.0101995334 0.0197363868 0.0085303323 2.0215160000 88770376 95654128 1784836096 0.0338885263 -0.0225182027 0.0932957307 84 3.3200000000 0.0106545519 0.0102049503 0.0197363868 0.0086581564 2.4568130000 88772070 95654128 1786105856 0.0341706425 -0.0229100492 0.0957133397 85 3.3600000000 0.0107509652 0.0102113740 0.0197363868 0.0087094841 1.8031290000 88772504 95654128 1787756544 0.0351197198 -0.0225226395 0.0982294828 86 3.4000000000 0.0102743339 0.0102121061 0.0197363868 0.0087599502 1.3758170000 88774198 95654128 1784582144 0.0361489058 -0.0220963694 0.1009017751 87 3.4400000000 0.0105486084 0.0102159739 0.0197363868 0.0088331189 1.5652020000 88777896 95654128 1785978880 0.0371744074 -0.0222818628 0.1037342772 88 3.4800000000 0.0104835741 0.0102190149 0.0197363868 0.0089164319 1.6608900000 88946930 95654128 1787883520 0.0379240401 -0.0225650929 0.1064805984 89 3.5200000000 0.0105633717 0.0102228840 0.0197363868 0.0089991011 2.0865280000 88948624 95654128 1784709120 0.0386177450 -0.0226623584 0.1093853191 90 3.5600000000 0.0104245888 0.0102251252 0.0197363868 0.0091151018 0.9892940000 88950318 95654128 1786241024 0.0389468260 -0.0225429386 0.1121532321 91 3.6000000000 0.0099740149 0.0102223657 0.0197363868 0.0092573264 1.1146200000 88950752 95654128 1788018688 0.0396097153 -0.0228142105 0.1150881946 92 3.6400000000 0.0106133195 0.0102266152 0.0197363868 0.0093300540 1.7407690000 88952430 95654128 1784971264 0.0407452658 -0.0235422589 0.1184692681 93 3.6800000000 0.0106766773 0.0102314546 0.0197363868 0.0093423546 1.8813480000 88954124 95654128 1786241024 0.0412083156 -0.0241168234 0.1213710457 94 3.7200000000 0.0107815443 0.0102373066 0.0197363868 0.0093068843 1.7901730000 88954558 95654128 1788272640 0.0420114994 -0.0240267366 0.1244051605 95 3.7600000000 0.0109534748 0.0102448453 0.0197363868 0.0092977068 1.8628220000 88956252 95654128 1784320000 0.0437601022 -0.0240886323 0.1276239455 96 3.8000000000 0.0106732417 0.0102493077 0.0197363868 0.0093158346 2.1151840000 88957946 95654128 1785589760 0.0445745885 -0.0236807056 0.1307271868 97 3.8400000000 0.0112027731 0.0102591373 0.0197363868 0.0094181440 1.6374900000 88958380 95654128 1787621376 0.0454133525 -0.0226862542 0.1343637407 98 3.8800000000 0.0107455058 0.0102641002 0.0197363868 0.0095582369 1.6348230000 88960074 95654128 1784700928 0.0457517356 -0.0224425197 0.1375401616 99 3.9200000000 0.0108963689 0.0102704868 0.0197363868 0.0096895507 1.2708340000 88961768 95654128 1785970688 0.0464216992 -0.0227409676 0.1407391280 100 3.9600000000 0.0112041701 0.0102798236 0.0197363868 0.0098091835 1.6913510000 88962202 95654128 1788002304 0.0463496298 -0.0215353109 0.1441964954 101 4.0000000000 0.0117550474 0.0102944298 0.0197363868 0.0098432371 1.4732650000 88963896 95654128 1784700928 0.0475450121 -0.0213403534 0.1477662474 102 4.0400000000 0.0117364051 0.0103085668 0.0197363868 0.0098480336 1.4522890000 88965574 95654128 1785970688 0.0484132916 -0.0215629898 0.1507245600 103 4.0800000000 0.0113885449 0.0103190520 0.0197363868 0.0098775753 1.6887680000 88966008 95654128 1787875328 0.0485503711 -0.0200493336 0.1539556533 104 4.1200000000 0.0112270750 0.0103277830 0.0197363868 0.0098823629 1.4944920000 88967702 95654128 1784700928 0.0493320152 -0.0198676065 0.1571530849 105 4.1600000000 0.0113514485 0.0103375322 0.0197363868 0.0098773038 1.7114830000 88969396 95654128 1785970688 0.0500159860 -0.0197822079 0.1599992514 106 4.2000000000 0.0114224320 0.0103477671 0.0197363868 0.0098717081 2.1501500000 88969830 95654128 1787875328 0.0499910824 -0.0191843249 0.1627437323 107 4.2400000000 0.0112454109 0.0103561563 0.0197363868 0.0098511181 2.2585570000 88971524 95654128 1784700928 0.0505549908 -0.0196627956 0.1651533842 108 4.2800000000 0.0111879352 0.0103638579 0.0197363868 0.0098333997 1.0611730000 88973218 95654128 1785970688 0.0509329177 -0.0185796414 0.1679181308 109 4.3200000000 0.0111602368 0.0103711642 0.0197363868 0.0098114395 1.3287310000 88976636 95654128 1787875328 0.0515029430 -0.0175109431 0.1706728935 110 4.3600000000 0.0102009950 0.0103696172 0.0197363868 0.0097766653 1.7434710000 89146930 95654128 1784573952 0.0517075621 -0.0161848646 0.1729287207 111 4.4000000000 0.0101336204 0.0103674911 0.0197363868 0.0097460672 1.8992280000 89148624 95654128 1785978880 0.0525208451 -0.0157448538 0.1758602858 112 4.4400000000 0.0097584967 0.0103620536 0.0197363868 0.0097147987 1.4848000000 89149074 95654128 1788010496 0.0523827523 -0.0154107576 0.1783049852 113 4.4800000000 0.0097555276 0.0103566861 0.0197363868 0.0096819907 2.0721690000 89150768 95654128 1784328192 0.0519313440 -0.0147408787 0.1806276590 114 4.5200000000 0.0090222936 0.0103449809 0.0197363868 0.0096509860 1.3021010000 89152462 95654128 1785724928 0.0516140088 -0.0144041777 0.1829978079 115 4.5600000000 0.0091870921 0.0103349123 0.0197363868 0.0096200065 1.7873150000 89152896 95654128 1787494400 0.0522366203 -0.0145466393 0.1853916943 116 4.6000000000 0.0098517388 0.0103307471 0.0197363868 0.0095992274 2.2554320000 89154590 95654128 1784573952 0.0527921841 -0.0142771872 0.1879830211 117 4.6400000000 0.0107242372 0.0103341102 0.0197363868 0.0095648718 1.7715700000 89156284 95654128 1785970688 0.0535019264 -0.0152892433 0.1904665977 118 4.6800000000 0.0117286807 0.0103459286 0.0197363868 0.0095351874 2.3371530000 89156734 95654128 1787748352 0.0543192476 -0.0158445016 0.1933934242 119 4.7200000000 0.0114257764 0.0103550030 0.0197363868 0.0095117854 1.5398290000 89158428 95654128 1784700928 0.0549304113 -0.0153111648 0.1962593794 120 4.7600000000 0.0108993445 0.0103595391 0.0197363868 0.0094891213 2.2312330000 89160122 95654128 1786097664 0.0546649583 -0.0151941497 0.1990027577 121 4.8000000000 0.0110195233 0.0103649936 0.0197363868 0.0094801389 2.1706390000 89160556 95654128 1788129280 0.0548567064 -0.0151883783 0.2022324651 122 4.8400000000 0.0116193304 0.0103752750 0.0197363868 0.0094778007 2.5204610000 89162250 95654128 1784700928 0.0553346165 -0.0155797973 0.2053755373 123 4.8800000000 0.0110339876 0.0103806304 0.0197363868 0.0094659668 2.2407290000 89163944 95654128 1785970688 0.0551765561 -0.0149012748 0.2081762403 124 4.9200000000 0.0107544074 0.0103836447 0.0197363868 0.0094421441 1.6794610000 89164378 95654128 1787875328 0.0553665385 -0.0141836051 0.2111934870 125 4.9600000000 0.0114202537 0.0103919376 0.0197363868 0.0094166264 1.2354820000 89166072 95654128 1784700928 0.0559217818 -0.0144838495 0.2144927084 126 5.0000000000 0.0115787089 0.0104013564 0.0197363868 0.0094024740 1.2628110000 89167766 95654128 1785970688 0.0563277677 -0.0146453585 0.2175618559 127 5.0400000000 0.0108000459 0.0104044957 0.0197363868 0.0094103092 1.1772300000 89168200 95654128 1788002304 0.0565251485 -0.0138274450 0.2211124748 128 5.0800000000 0.0106784357 0.0104066359 0.0197363868 0.0094310713 1.4645880000 89171610 95654128 1784573952 0.0566024184 -0.0134085007 0.2241633832 129 5.1200000000 0.0105888732 0.0104080486 0.0197363868 0.0094150551 1.7969320000 89352148 95654128 1785843712 0.0571016036 -0.0133070182 0.2272105217 130 5.1600000000 0.0106105087 0.0104096059 0.0197363868 0.0094018472 1.9510810000 89373574 95654128 1788137472 0.0572263040 -0.0143239759 0.2300380617 131 5.2000000000 0.0097695962 0.0104047204 0.0197363868 0.0093969176 2.0052280000 89375268 95654128 1784582144 0.0574963279 -0.0133186271 0.2326491922 132 5.2400000000 0.0099863540 0.0104015509 0.0197363868 0.0093761795 2.0454570000 89376962 95654128 1785851904 0.0578232072 -0.0130300634 0.2355531156 133 5.2800000000 0.0105751492 0.0104028562 0.0197363868 0.0093660717 2.0987150000 89377396 95654128 1787883520 0.0587945543 -0.0141172931 0.2382233292 134 5.3200000000 0.0099012572 0.0103991129 0.0197363868 0.0093970580 2.1107210000 89379090 95654128 1784700928 0.0592611916 -0.0127576934 0.2411123514 135 5.3600000000 0.0094437301 0.0103920360 0.0197363868 0.0094008844 3.1048060000 89380784 95654128 1785970688 0.0596399941 -0.0126418173 0.2434508204 136 5.4000000000 0.0092925299 0.0103839514 0.0197363868 0.0094094062 2.4528750000 89381218 95654128 1787875328 0.0601948947 -0.0133000594 0.2457336187 137 5.4400000000 0.0094034541 0.0103767945 0.0197363868 0.0094088939 1.5480630000 89382912 95654128 1784573952 0.0610373765 -0.0136287371 0.2482677400 138 5.4800000000 0.0096913809 0.0103718277 0.0197363868 0.0093880421 2.0798630000 89384606 95654128 1785843712 0.0616603941 -0.0137505783 0.2505352795 139 5.5200000000 0.0095068077 0.0103656045 0.0197363868 0.0093753190 1.5160230000 89385040 95654128 1787748352 0.0618222766 -0.0138086276 0.2524650693 140 5.5600000000 0.0091129867 0.0103566573 0.0197363868 0.0093709358 2.0259430000 89390566 95654128 1784700928 0.0618741587 -0.0139165130 0.2545476258 141 5.6000000000 0.0084638232 0.0103432329 0.0197363868 0.0094230942 2.2899390000 89560860 95654128 1785843712 0.0615716167 -0.0137733994 0.2583121061 142 5.6400000000 0.0075379899 0.0103234777 0.0197363868 0.0094363741 1.5890240000 89561294 95654128 1787748352 0.0614328608 -0.0133009432 0.2609362602 143 5.6800000000 0.0072376383 0.0103018984 0.0197363868 0.0094422170 1.8514000000 89562988 95654128 1784573952 0.0613432191 -0.0133628063 0.2630110681 144 5.7200000000 0.0065295366 0.0102757014 0.0197363868 0.0094430422 1.0536120000 89564682 95654128 1785970688 0.0608542152 -0.0124499872 0.2649590075 145 5.7600000000 0.0062691285 0.0102480699 0.0197363868 0.0094377432 1.0191020000 89565116 95654128 1787748352 0.0601696298 -0.0121677099 0.2667411864 146 5.8000000000 0.0073788860 0.0102284179 0.0197363868 0.0094301144 1.2730940000 89566810 95654128 1784573952 0.0597502068 -0.0131386220 0.2683320045 147 5.8400000000 0.0078216828 0.0102120456 0.0197363868 0.0094234652 1.9000630000 89568504 95654128 1785970688 0.0592270046 -0.0145105245 0.2700344622 148 5.8800000000 0.0077081984 0.0101951277 0.0197363868 0.0094051978 2.1005840000 89568938 95654128 1787875328 0.0582129396 -0.0151828332 0.2715148628 149 5.9200000000 0.0083372239 0.0101826586 0.0197363868 0.0093854458 1.8937820000 89570632 95654128 1784963072 0.0567908883 -0.0161760822 0.2727802992 150 5.9600000000 0.0078631854 0.0101671954 0.0197363868 0.0093684933 1.6429400000 89572326 95654128 1786232832 0.0554561652 -0.0159981251 0.2741960883 151 6.0000000000 0.0085083190 0.0101562095 0.0197363868 0.0093485762 1.7829860000 89572760 95654128 1788010496 0.0550742336 -0.0166623667 0.2765749693 152 6.0400000000 0.0093468744 0.0101508849 0.0197363868 0.0093311125 1.0689310000 89574454 95654128 1784582144 0.0540089458 -0.0177811105 0.2783384919 153 6.0800000000 0.0082342159 0.0101383576 0.0197363868 0.0093280709 2.6685060000 89576148 95654128 1785851904 0.0528881475 -0.0168611668 0.2808309495 154 6.1200000000 0.0085420124 0.0101279918 0.0197363868 0.0093067948 1.1322860000 89579058 95654128 1787875328 0.0516025722 -0.0176031590 0.2823684812 155 6.1600000000 0.0095229717 0.0101240884 0.0197363868 0.0092851968 1.4391060000 89749364 95654128 1784573952 0.0503024757 -0.0188205447 0.2842635810 156 6.2000000000 0.0090597654 0.0101172658 0.0197363868 0.0092930202 2.1820950000 89751058 95654128 1785970688 0.0469003879 -0.0190580133 0.2869103849 157 6.2400000000 0.0093693137 0.0101125018 0.0197363868 0.0092722800 2.0143690000 89751492 95654128 1788002304 0.0454558693 -0.0194215514 0.2888951302 158 6.2800000000 0.0084870532 0.0101022142 0.0197363868 0.0092573794 1.9986990000 89753186 95654128 1784573952 0.0436637476 -0.0193195399 0.2917664349 159 6.3200000000 0.0080864374 0.0100895363 0.0197363868 0.0092487847 1.6317220000 89754880 95654128 1785843712 0.0418002643 -0.0185592696 0.2923674881 160 6.3600000000 0.0070164609 0.0100703296 0.0197363868 0.0092408499 1.5577580000 89755314 95654128 1787875328 0.0396761820 -0.0173759721 0.2944982648 161 6.4000000000 0.0080695013 0.0100579021 0.0197363868 0.0092294072 1.9788330000 89757008 95654128 1784573952 0.0380978845 -0.0184532814 0.2959956825 162 6.4400000000 0.0077319196 0.0100435442 0.0197363868 0.0092507652 2.5566740000 89758702 95654128 1785843712 0.0356048495 -0.0179205649 0.2970734835 163 6.4800000000 0.0076461402 0.0100288362 0.0197363868 0.0092474330 2.1748870000 89759136 95654128 1787748352 0.0337232687 -0.0175863113 0.2984659374 164 6.5200000000 0.0078595374 0.0100156087 0.0197363868 0.0092328586 1.9985960000 89760830 95654128 1784573952 0.0324996822 -0.0183812752 0.3010201454 165 6.5600000000 0.0089107687 0.0100089127 0.0197363868 0.0092217886 1.7640410000 89762524 95654128 1785970688 0.0310052112 -0.0191714950 0.3020129502 166 6.6000000000 0.0096254013 0.0100066024 0.0197363868 0.0092064873 1.6043000000 89762958 95654128 1787875328 0.0299015418 -0.0201820023 0.3038735390 167 6.6400000000 0.0101978341 0.0100077475 0.0197363868 0.0091908833 1.3907690000 89764652 95654128 1784700928 0.0283174496 -0.0207865536 0.3063775599 168 6.6800000000 0.0097263930 0.0100060728 0.0197363868 0.0091751745 1.8918360000 89766346 95654128 1786105856 0.0266827922 -0.0209846087 0.3080526292 169 6.7200000000 0.0098593011 0.0100052043 0.0197363868 0.0091598243 1.9791980000 89766780 95654128 1787629568 0.0258180853 -0.0213625450 0.3097736537 170 6.7600000000 0.0102263782 0.0100065054 0.0197363868 0.0091438444 1.6205830000 89768474 95654128 1784455168 0.0249944534 -0.0224573612 0.3126681149 171 6.8000000000 0.0101536615 0.0100073659 0.0197363868 0.0091250620 1.8211840000 89770168 95654128 1785851904 0.0235581733 -0.0226597507 0.3129156828 172 6.8400000000 0.0107628992 0.0100117586 0.0197363868 0.0091066560 1.9743420000 89770602 95654128 1787621376 0.0224892013 -0.0234808940 0.3132437468 173 6.8800000000 0.0119216647 0.0100227985 0.0197363868 0.0090883936 1.9304300000 89772296 95654128 1784700928 0.0217058249 -0.0249797031 0.3136354685 174 6.9200000000 0.0114466855 0.0100309817 0.0197363868 0.0091078660 2.3168840000 89773990 95654128 1786097664 0.0211114567 -0.0253631752 0.3155240715 175 6.9600000000 0.0107069118 0.0100348442 0.0197363868 0.0091243927 1.8934370000 89774424 95654128 1787875328 0.0200514179 -0.0252572000 0.3168490231 176 7.0000000000 0.0109808734 0.0100402194 0.0197363868 0.0091351079 1.9743920000 89776118 95654128 1784573952 0.0192083921 -0.0259604789 0.3172830045 177 7.0400000000 0.0106997788 0.0100439457 0.0197363868 0.0091558244 1.5001340000 89777812 95654128 1785970688 0.0185454898 -0.0262976270 0.3181991577 178 7.0800000000 0.0111964047 0.0100504202 0.0197363868 0.0091593765 2.0155700000 89778246 95654128 1787875328 0.0179766025 -0.0270023160 0.3181408942 179 7.1200000000 0.0111942859 0.0100568105 0.0197363868 0.0091641314 2.3203370000 89779940 95654128 1784700928 0.0174103007 -0.0271812808 0.3185854256 180 7.1600000000 0.0113119110 0.0100637833 0.0197363868 0.0091920512 1.3955350000 89783678 95654128 1785970688 0.0170722343 -0.0280694459 0.3198107481 181 7.2000000000 0.0108018024 0.0100678607 0.0197363868 0.0092125688 2.1267970000 89952720 95654128 1788002304 0.0166017730 -0.0279358067 0.3204910457 182 7.2400000000 0.0107446350 0.0100715793 0.0197363868 0.0092296590 1.8460020000 89954414 95654128 1784700928 0.0161662493 -0.0279921684 0.3208163381 183 7.2800000000 0.0106103709 0.0100745235 0.0197363868 0.0092536249 1.8373230000 89956108 95654128 1785970688 0.0158050153 -0.0283215549 0.3212656379 184 7.3200000000 0.0103679774 0.0100761183 0.0197363868 0.0093962786 1.7600950000 89956542 95654128 1788002304 0.0152470581 -0.0288461260 0.3223299980 185 7.3600000000 0.0105389636 0.0100786202 0.0197363868 0.0094087583 1.7214420000 89958236 95654128 1784573952 0.0149605647 -0.0286044739 0.3214748800 186 7.4000000000 0.0105940467 0.0100813913 0.0197363868 0.0094083825 2.0726540000 89959930 95654128 1785978880 0.0144228870 -0.0291399434 0.3226257563 187 7.4400000000 0.0108697163 0.0100856069 0.0197363868 0.0093962023 1.0066860000 89960364 95654128 1787883520 0.0141128525 -0.0295136496 0.3237403035 188 7.4800000000 0.0108531807 0.0100896898 0.0197363868 0.0093835839 2.0708540000 89962058 95654128 1784709120 0.0139725534 -0.0297956653 0.3251962960 189 7.5200000000 0.0109118614 0.0100940399 0.0197363868 0.0093808450 1.4246460000 89963752 95654128 1785978880 0.0136840250 -0.0297040977 0.3259257972 190 7.5600000000 0.0108433375 0.0100979836 0.0197363868 0.0093918136 1.7542500000 89964186 95654128 1787875328 0.0137804793 -0.0296582840 0.3277358413 191 7.6000000000 0.0109415362 0.0101024001 0.0197363868 0.0093831581 1.8493870000 89965880 95654128 1784700928 0.0140541997 -0.0300795492 0.3293568790 192 7.6400000000 0.0104885465 0.0101044113 0.0197363868 0.0093729240 1.6937560000 89967574 95654128 1785970688 0.0141593898 -0.0303664654 0.3320474923 193 7.6800000000 0.0097954581 0.0101028105 0.0197363868 0.0093658977 2.1279210000 89968008 95654128 1788002304 0.0140778674 -0.0301529802 0.3344932199 194 7.7200000000 0.0092878463 0.0100986096 0.0197363868 0.0093535788 1.6365000000 89969702 95654128 1784573952 0.0143307606 -0.0296543147 0.3360621929 195 7.7600000000 0.0084575415 0.0100901939 0.0197363868 0.0093442106 1.2842420000 89971396 95654128 1785843712 0.0144623183 -0.0295110196 0.3387641609 196 7.8000000000 0.0082557602 0.0100808345 0.0197363868 0.0093341608 1.9321970000 89971830 95654128 1787748352 0.0144814858 -0.0297323372 0.3403746188 197 7.8400000000 0.0079165986 0.0100698486 0.0197363868 0.0093233481 2.0373470000 89973524 95654128 1784320000 0.0145911407 -0.0298934467 0.3422480524 198 7.8800000000 0.0074910759 0.0100568245 0.0197363868 0.0093128238 1.5680120000 89975218 95654128 1785716736 0.0146595016 -0.0296335854 0.3449142873 199 7.9200000000 0.0076385811 0.0100446725 0.0197363868 0.0093005795 1.9039810000 89975652 95654128 1787494400 0.0149704702 -0.0299905390 0.3452046812 200 7.9600000000 0.0076225912 0.0100325621 0.0197363868 0.0092871056 0.7716930000 89978858 95654128 1784352768 0.0154227419 -0.0300922841 0.3440533578 201 8.0000000000 0.0071185664 0.0100180646 0.0197363868 0.0092854183 0.9980280000 90149164 95654128 1785970688 0.0154783968 -0.0297902152 0.3472443521 202 8.0400000000 0.0074332482 0.0100052685 0.0197363868 0.0092690458 1.3303740000 90149598 95654128 1787756544 0.0158372317 -0.0300720707 0.3449551165 203 8.0800000000 0.0072565866 0.0099917282 0.0197363868 0.0092572176 1.3304350000 90151292 95654128 1784709120 0.0160443578 -0.0295383986 0.3445776701 204 8.1200000000 0.0075785192 0.0099798987 0.0197363868 0.0092564811 1.5421140000 90152986 95654128 1786105856 0.0162489209 -0.0297907628 0.3449929059 205 8.1600000000 0.0081733176 0.0099710861 0.0197363868 0.0092561655 1.2011390000 90153420 95654128 1787883520 0.0164859984 -0.0301095545 0.3450516760 206 8.1999999990 0.0076173372 0.0099596601 0.0197363868 0.0092601143 1.9455560000 90155114 95654128 1784725504 0.0163772795 -0.0295809563 0.3460729122 207 8.2400000000 0.0073435204 0.0099470218 0.0197363868 0.0092897854 1.1268230000 90156808 95654128 1786097664 0.0163686592 -0.0293577947 0.3469048142 208 8.2799999990 0.0081424098 0.0099383458 0.0197363868 0.0093198528 1.5918980000 90157242 95654128 1788010496 0.0164298285 -0.0299377665 0.3462336659 209 8.3200000000 0.0072449078 0.0099254585 0.0197363868 0.0093449041 1.5728220000 90158936 95654128 1784582144 0.0164348353 -0.0289917234 0.3462612331 210 8.3599999990 0.0066254465 0.0099097442 0.0197363868 0.0093507873 2.2876280000 90160630 95654128 1785978880 0.0163134430 -0.0286190622 0.3478568792 211 8.4000000000 0.0072333012 0.0098970596 0.0197363868 0.0093550715 1.0313620000 90161064 95654128 1787883520 0.0162288696 -0.0291946065 0.3501186073 212 8.4399999990 0.0070064883 0.0098834248 0.0197363868 0.0093498043 1.8975850000 90162758 95654128 1784709120 0.0162966345 -0.0287080575 0.3492000699 213 8.4800000000 0.0080554979 0.0098748430 0.0197363868 0.0093481881 1.7564000000 90164452 95654128 1785970688 0.0164866839 -0.0297474563 0.3468767405 214 8.5200000000 0.0074198940 0.0098633713 0.0197363868 0.0093491447 1.5630650000 90164886 95654128 1788002304 0.0164619945 -0.0290840343 0.3471662998 215 8.5600000000 0.0079238126 0.0098543501 0.0197363868 0.0093519822 1.5985790000 90166580 95654128 1784573952 0.0163597260 -0.0290599540 0.3488827646 216 8.6000000000 0.0083273463 0.0098472806 0.0197363868 0.0093455046 1.8085870000 90168274 95654128 1785843712 0.0165485665 -0.0293046143 0.3465738893 217 8.6400000000 0.0082852384 0.0098400823 0.0197363868 0.0093549609 1.9249830000 90168708 95654128 1787748352 0.0164802950 -0.0288739223 0.3465126753 218 8.6800000000 0.0088764569 0.0098356620 0.0197363868 0.0093825964 1.6819670000 90170402 95654128 1784700928 0.0163200796 -0.0289712083 0.3475142419 219 8.7200000000 0.0097467368 0.0098352559 0.0197363868 0.0094110102 1.7027580000 90172096 95654128 1785970688 0.0161504056 -0.0289270803 0.3490248322 220 8.7600000000 0.0092837866 0.0098327492 0.0197363868 0.0094238829 1.5892730000 90172530 95654128 1788002304 0.0158342142 -0.0275376812 0.3494242430 221 8.8000000000 0.0082589211 0.0098256278 0.0197363868 0.0094254594 0.7907580000 90174224 95654128 1784451072 0.0157628097 -0.0272289235 0.3467875421 222 8.8400000000 0.0072623882 0.0098140817 0.0197363868 0.0094203466 0.8896990000 90179394 95654128 1785847808 0.0156481527 -0.0260838903 0.3445245326 223 8.8800000000 0.0069927885 0.0098014302 0.0197363868 0.0094288814 0.8379340000 90348428 95654128 1787752448 0.0153873591 -0.0251806844 0.3439865410 224 8.9200000000 0.0070326030 0.0097890693 0.0197363868 0.0094386863 1.9446640000 90350122 95654128 1784578048 0.0149757015 -0.0249682330 0.3409115672 225 8.9600000000 0.0061894227 0.0097730709 0.0197363868 0.0094586053 2.0759160000 90351816 95654128 1785847808 0.0145847099 -0.0235896800 0.3408393264 226 9.0000000000 0.0067947581 0.0097598925 0.0197363868 0.0094720064 1.9701220000 90352250 95654128 1787498496 0.0142956665 -0.0232939683 0.3380020857 227 9.0400000000 0.0061281435 0.0097438936 0.0197363868 0.0094789882 0.9890110000 90353944 95654128 1784578048 0.0137729598 -0.0209022556 0.3358011544 228 9.0800000000 0.0067246165 0.0097306512 0.0197363868 0.0095025586 2.1701290000 90355638 95654128 1785974784 0.0134139080 -0.0209082905 0.3344841003 229 9.1200000000 0.0065541063 0.0097167798 0.0197363868 0.0095281967 1.6542850000 90356072 95654128 1787752448 0.0127133355 -0.0205762181 0.3334030211 230 9.1600000000 0.0070465668 0.0097051702 0.0197363868 0.0095423892 1.3994060000 90357766 95654128 1784705024 0.0122991791 -0.0216706172 0.3331192136 231 9.2000000000 0.0080763884 0.0096981192 0.0197363868 0.0095624296 1.8181540000 90359460 95654128 1786109952 0.0117426822 -0.0224122386 0.3319981992 232 9.2400000000 0.0065278597 0.0096844543 0.0197363868 0.0095760673 1.6303810000 90359894 95654128 1787887616 0.0111479424 -0.0196509231 0.3308506012 233 9.2800000000 0.0065117767 0.0096708376 0.0197363868 0.0096167541 0.7211610000 90361588 95654128 1784803328 0.0107056340 -0.0205005556 0.3322471380 234 9.3200000000 0.0056136171 0.0096534991 0.0197363868 0.0096388441 0.8126540000 90363282 95654128 1786109952 0.0100606550 -0.0185203403 0.3302131295 235 9.3600000000 0.0070411894 0.0096423829 0.0197363868 0.0096560547 0.7849810000 90363716 95654128 1787887616 0.0093967626 -0.0202409383 0.3296025395 236 9.4000000000 0.0077635618 0.0096344218 0.0197363868 0.0096685344 0.8779600000 90365410 95654128 1784840192 0.0086731147 -0.0209418554 0.3303303123 237 9.4400000000 0.0089696432 0.0096316168 0.0197363868 0.0096892456 2.0571010000 90367104 95654128 1786109952 0.0078439834 -0.0217542667 0.3311422765 238 9.4800000000 0.0080688782 0.0096250507 0.0197363868 0.0097657583 1.4970970000 90369594 95654128 1788006400 0.0062225014 -0.0188349690 0.3292435110 239 9.5200000000 0.0095756501 0.0096248440 0.0197363868 0.0098040889 0.9649980000 90539892 95654128 1784705024 0.0054353559 -0.0193379913 0.3291121423 240 9.5600000000 0.0093018450 0.0096234982 0.0197363868 0.0098289151 0.8364700000 90541586 95654128 1785991168 0.0045504938 -0.0178329628 0.3272477388 241 9.6000000000 0.0118353842 0.0096326761 0.0197363868 0.0099004412 0.7453760000 90542020 95654128 1788133376 0.0037349784 -0.0197092909 0.3259702027 242 9.6400000000 0.0148137035 0.0096540853 0.0197363868 0.0099877540 0.7159280000 90543714 95654128 1784594432 0.0029173179 -0.0218767971 0.3258525729 243 9.6800000000 0.0165819284 0.0096825950 0.0197363868 0.0100378900 0.8104020000 90545408 95654128 1785974784 0.0019165968 -0.0231211968 0.3220412135 244 9.7200000000 0.0162835848 0.0097096482 0.0197363868 0.0100825000 0.8336110000 90545842 95654128 1787879424 0.0010603894 -0.0217375383 0.3186110854 245 9.7600000000 0.0146521730 0.0097298218 0.0197363868 0.0101284314 0.7306620000 90547536 95654128 1784602624 0.0003354774 -0.0194641836 0.3177921474 246 9.8000000000 0.0157340355 0.0097542291 0.0197363868 0.0101495047 0.7590100000 90549230 95654128 1785856000 -0.0007775271 -0.0195567012 0.3152388334 247 9.8400000000 0.0153805483 0.0097770078 0.0197363868 0.0101793391 0.7049680000 90549664 95654128 1787760640 -0.0017886217 -0.0177649185 0.3123296201 248 9.8800000000 0.0130027495 0.0097900148 0.0197363868 0.0102352665 0.7997180000 90551358 95654128 1784586240 -0.0023905302 -0.0143509060 0.3120954931 249 9.9200000000 0.0135812704 0.0098052407 0.0197363868 0.0102928126 0.7041030000 90553052 95654128 1785872384 -0.0029009809 -0.0141721740 0.3111249804 250 9.9600000000 0.0139688104 0.0098218950 0.0197363868 0.0103425546 0.6987280000 90553486 95654128 1787887616 -0.0036905871 -0.0136681302 0.3104257286 251 10.0000000000 0.0152760530 0.0098436247 0.0197363868 0.0103798805 0.7156180000 90557572 95654128 1784713216 -0.0044902647 -0.0134979431 0.3075273931 252 10.0400000000 0.0152773643 0.0098651872 0.0197363868 0.0104451305 0.7055740000 90727874 95654128 1785982976 -0.0053859544 -0.0125057427 0.3063739240 253 10.0800000000 0.0148307607 0.0098848139 0.0197363868 0.0104736779 0.7294770000 90728308 95654128 1787793408 -0.0062178532 -0.0107780928 0.3034441471 254 10.1200000000 0.0153078847 0.0099061646 0.0197363868 0.0105074640 0.8230710000 90730002 95654128 1784459264 -0.0069080284 -0.0099281743 0.3013024926 255 10.1600000000 0.0186839644 0.0099405873 0.0197363868 0.0105587383 1.3274560000 90731696 95654128 1785856000 -0.0079088947 -0.0124092568 0.2984962463 256 10.2000000000 0.0193215329 0.0099772317 0.0197363868 0.0106052898 1.7312520000 90732130 95654128 1787633664 -0.0088317348 -0.0122927856 0.2971076369 257 10.2400000000 0.0195195563 0.0100143613 0.0197363868 0.0106515946 1.6231410000 90754304 95654128 1784586240 -0.0094339866 -0.0114552807 0.2960333824 258 10.2800000000 0.0190985464 0.0100495713 0.0197363868 0.0106663529 1.5225730000 90797982 95654128 1785982976 -0.0098182391 -0.0100429291 0.2948241532 259 10.3200000000 0.0181242004 0.0100807475 0.0197363868 0.0106696405 1.7200940000 90800308 95654128 1787887616 -0.0103671290 -0.0080831470 0.2938517034 260 10.3600000000 0.0181046091 0.0101116085 0.0197363868 0.0106844977 1.6397060000 90970614 95654128 1784713216 -0.0113918623 -0.0067697521 0.2915687859 261 10.4000000000 0.0182978977 0.0101429736 0.0197363868 0.0107244210 2.0566090000 90972308 95654128 1786236928 -0.0128912320 -0.0068398425 0.2913883328 262 10.4400000000 0.0179667436 0.0101728353 0.0197363868 0.0107346099 1.7098240000 90972742 95654128 1788149760 -0.0132188033 -0.0055188993 0.2893795371 263 10.4800000000 0.0177103654 0.0102014951 0.0197363868 0.0107365474 1.6762830000 90974436 95654128 1784086528 -0.0140591627 -0.0044453684 0.2885991931 264 10.5200000000 0.0167308748 0.0102262276 0.0197363868 0.0107389709 1.5668690000 90976130 95654128 1785483264 -0.0142189208 -0.0021011834 0.2869097888 265 10.5600000000 0.0174650289 0.0102535439 0.0197363868 0.0107582432 1.3185590000 90976564 95654128 1787387904 -0.0145168956 -0.0021688992 0.2842659652 266 10.6000000000 0.0180079136 0.0102826956 0.0197363868 0.0107519216 1.5269540000 90978258 95654128 1784467456 -0.0153760845 -0.0021237249 0.2813995779 267 10.6400000000 0.0185920559 0.0103138168 0.0197363868 0.0107356734 1.7512670000 90979952 95654128 1785737216 -0.0159292817 -0.0018322914 0.2795295119 268 10.6800000000 0.0184453297 0.0103441583 0.0197363868 0.0107294003 1.6273230000 90980386 95654128 1787633664 -0.0172272958 -0.0017762261 0.2789539099 269 10.7200000000 0.0179905985 0.0103725837 0.0197363868 0.0107287670 1.6278920000 90983800 95654128 1784475648 -0.0177467354 -0.0009599901 0.2782545090 270 10.7600000000 0.0186129194 0.0104031035 0.0197363868 0.0107357329 1.5055620000 91154134 95654128 1785856000 -0.0183963589 -0.0012620592 0.2766297460 271 10.8000000000 0.0197380614 0.0104375498 0.0197380614 0.0107293963 1.6176860000 91154568 95654128 1788014592 -0.0191765409 -0.0018069006 0.2735712528 272 10.8400000000 0.0210000984 0.0104763827 0.0210000984 0.0107162788 1.1355930000 91156262 95654128 1784586240 -0.0199417081 -0.0024030078 0.2711881995 273 10.8800000000 0.0209569428 0.0105147731 0.0210000984 0.0107227869 1.4639990000 91157956 95654128 1785856000 -0.0213438328 -0.0022909811 0.2699825764 274 10.9200000000 0.0214944724 0.0105548450 0.0214944724 0.0107224533 1.6450010000 91158390 95654128 1787887616 -0.0220506117 -0.0025161959 0.2678457797 275 10.9600000000 0.0219596121 0.0105963168 0.0219596121 0.0107080315 1.7256040000 91160084 95654128 1784586240 -0.0219177399 -0.0024937461 0.2649908960 276 11.0000000000 0.0227358192 0.0106403005 0.0227358192 0.0106958955 1.6034170000 91161778 95654128 1785856000 -0.0223269593 -0.0032582586 0.2639431655 277 11.0400000000 0.0222116262 0.0106820743 0.0227358192 0.0106894935 1.8526630000 91162212 95654128 1787633664 -0.0239061061 -0.0032240197 0.2642701864 278 11.0800000000 0.0221043788 0.0107231617 0.0227358192 0.0106833505 1.6804820000 91165306 95654128 1784713216 -0.0247323047 -0.0030912226 0.2630080879 279 11.1200000000 0.0230369233 0.0107672971 0.0230369233 0.0106681929 1.8620720000 91335628 95654128 1785982976 -0.0239135381 -0.0032633040 0.2599208355 280 11.1600000000 0.0234693978 0.0108126617 0.0234693978 0.0106497641 1.5232020000 91336062 95654128 1788141568 -0.0238449518 -0.0028027606 0.2578500509 281 11.2000000000 0.0237748101 0.0108587903 0.0237748101 0.0106328726 0.9125590000 91337756 95654128 1784332288 -0.0253008250 -0.0031771953 0.2558699846 282 11.2400000000 0.0239780303 0.0109053125 0.0239780303 0.0106156395 0.6540280000 91339450 95654128 1785729024 -0.0261673927 -0.0030021605 0.2538494468 283 11.2800000000 0.0231925119 0.0109487301 0.0239780303 0.0105983984 0.8916980000 91339884 95654128 1787633664 -0.0279891305 -0.0025783894 0.2540016770 284 11.3200000000 0.0252018720 0.0109989173 0.0252018720 0.0105816423 1.9925050000 91341578 95654128 1784586240 -0.0286270231 -0.0045378432 0.2522128820 285 11.3600000000 0.0267071538 0.0110540339 0.0267071538 0.0105638092 1.4996910000 91343272 95654128 1785991168 -0.0300446637 -0.0061326334 0.2503152490 286 11.4000000000 0.0274473894 0.0111113533 0.0274473894 0.0105455738 1.7806890000 91343706 95654128 1787768832 -0.0319126211 -0.0072687608 0.2487157881 287 11.4400000000 0.0259379372 0.0111630139 0.0274473894 0.0105277225 1.5428500000 91345400 95654128 1784594432 -0.0328517258 -0.0058252574 0.2477605492 288 11.4800000000 0.0257077850 0.0112135166 0.0274473894 0.0105103166 1.5826620000 91347094 95654128 1785991168 -0.0331870541 -0.0055558141 0.2472524643 289 11.5200000000 0.0264752936 0.0112663255 0.0274473894 0.0104933697 0.9895320000 91347528 95654128 1787768832 -0.0340212248 -0.0063042883 0.2456739545 290 11.5600000000 0.0253615677 0.0113149298 0.0274473894 0.0104761104 1.3154590000 91350438 95654128 1784594432 -0.0345963873 -0.0049723964 0.2445413768 291 11.6000000000 0.0247021578 0.0113609340 0.0274473894 0.0104621874 1.3017430000 91520772 95654128 1785991168 -0.0358836725 -0.0044340431 0.2432224154 292 11.6400000000 0.0252547730 0.0114085156 0.0274473894 0.0104451476 2.0117600000 91521206 95654128 1788022784 -0.0363491587 -0.0051389690 0.2421771586 293 11.6800000000 0.0265597887 0.0114602264 0.0274473894 0.0104330340 1.6135760000 91522900 95654128 1784713216 -0.0380606614 -0.0071856417 0.2410747558 294 11.7200000000 0.0266234502 0.0115118020 0.0274473894 0.0104161372 1.0566510000 91524594 95654128 1785982976 -0.0395007916 -0.0070636133 0.2390969992 295 11.7600000000 0.0260698274 0.0115611513 0.0274473894 0.0104000898 1.9275560000 91525028 95654128 1787887616 -0.0417271331 -0.0065809493 0.2377988845 296 11.8000000000 0.0254503805 0.0116080743 0.0274473894 0.0103830098 1.6921750000 91526722 95654128 1784586240 -0.0442240685 -0.0062508299 0.2368777841 297 11.8400000000 0.0253781285 0.0116544382 0.0274473894 0.0103655554 1.4917560000 91528416 95654128 1785856000 -0.0473842472 -0.0067301802 0.2368445992 298 11.8800000000 0.0255132820 0.0117009443 0.0274473894 0.0103539983 1.7785910000 91528850 95654128 1787760640 -0.0491333008 -0.0069437898 0.2346672416 299 11.9200000000 0.0264721140 0.0117503463 0.0274473894 0.0103437445 0.9467900000 91530544 95654128 1784586240 -0.0506325476 -0.0073830835 0.2334470302 300 11.9600000000 0.0271346755 0.0118016274 0.0274473894 0.0103298718 0.6547150000 91533130 95654128 1785982976 -0.0524067171 -0.0080985390 0.2314164937 301 12.0000000000 0.0283279903 0.0118565322 0.0283279903 0.0103175518 0.9030400000 91702216 95654128 1787760640 -0.0545047633 -0.0090779392 0.2306385487 302 12.0400000000 0.0294164605 0.0119146777 0.0294164605 0.0103032045 1.7373840000 91704008 95654128 1784713216 -0.0581965186 -0.0104067912 0.2302471995 303 12.0800000000 0.0292975046 0.0119720467 0.0294164605 0.0102910943 1.3961790000 91705702 95654128 1785982976 -0.0600527003 -0.0101062413 0.2280515581 304 12.1200000000 0.0295957830 0.0120300196 0.0295957830 0.0102810046 1.3848260000 91706136 95654128 1788014592 -0.0622001924 -0.0104883667 0.2264515758 305 12.1600000000 0.0301830638 0.0120895377 0.0301830638 0.0102715813 1.3632140000 91707970 95654128 1784713216 -0.0644356459 -0.0105723403 0.2251537740 306 12.2000000000 0.0320526809 0.0121547768 0.0320526809 0.0102566990 0.9349940000 91710908 95654128 1785991168 -0.0681085214 -0.0127009768 0.2244622856 307 12.2400000000 0.0319358595 0.0122192103 0.0320526809 0.0102410021 0.8239170000 91881202 95654128 1787895808 -0.0698703155 -0.0121726822 0.2228741497 308 12.2800000000 0.0321566015 0.0122839420 0.0321566015 0.0102254285 0.5894310000 91882896 95654128 1784594432 -0.0726835504 -0.0132652689 0.2206577659 309 12.3200000000 0.0324349068 0.0123491555 0.0324349068 0.0102160630 0.5152610000 91883330 95654128 1785880576 -0.0749782771 -0.0138235968 0.2188388854 310 12.3600000000 0.0321484618 0.0124130243 0.0324349068 0.0102065508 0.6607460000 91885024 95654128 1787641856 -0.0766829029 -0.0128746824 0.2179498523 311 12.4000000000 0.0320497304 0.0124761648 0.0324349068 0.0101901280 0.9094510000 91886858 95654128 1784467456 -0.0798299834 -0.0127868429 0.2179780900 312 12.4400000000 0.0318734162 0.0125383355 0.0324349068 0.0101737644 0.6768980000 91887292 95654128 1785864192 -0.0827169493 -0.0131251318 0.2176539451 313 12.4800000000 0.0327842720 0.0126030190 0.0327842720 0.0101589308 0.8151570000 91888986 95654128 1787641856 -0.0850003883 -0.0143566774 0.2164652646 314 12.5200000000 0.0328919813 0.0126676335 0.0328919813 0.0101439348 0.7356460000 91892436 95654128 1784496128 -0.0867509395 -0.0144562265 0.2149378508 315 12.5600000000 0.0335040540 0.0127337809 0.0335040540 0.0101291582 0.7079870000 92061474 95654128 1785864192 -0.0893281698 -0.0162605420 0.2140395194 316 12.6000000000 0.0344552323 0.0128025196 0.0344552323 0.0101194327 0.8716980000 92063168 95654128 1787895808 -0.0902098864 -0.0173034761 0.2129611522 317 12.6400000000 0.0351054929 0.0128728760 0.0351054929 0.0101098489 0.7800160000 92065002 95654128 1784467456 -0.0908310264 -0.0182206761 0.2117483020 318 12.6800000000 0.0354930535 0.0129440087 0.0354930535 0.0101133407 0.8032630000 92065436 95654128 1785872384 -0.0931004733 -0.0195437931 0.2107111216 319 12.7200000000 0.0345834903 0.0130118440 0.0354930535 0.0101146765 0.6069960000 92069122 95654128 1787760640 -0.0954834297 -0.0190582890 0.2084922493 320 12.7600000000 0.0348637588 0.0130801312 0.0354930535 0.0101017185 0.7072350000 92239476 95654128 1784713216 -0.0963526890 -0.0189131852 0.2071583420 321 12.8000000000 0.0346585326 0.0131473537 0.0354930535 0.0100864428 0.7806010000 92239910 95654128 1785982976 -0.0976674259 -0.0192293059 0.2055545896 322 12.8400000000 0.0357334875 0.0132174970 0.0357334875 0.0100729061 0.6017630000 92241604 95654128 1788014592 -0.0978242010 -0.0208156854 0.2051197439 323 12.8800000000 0.0365149900 0.0132896254 0.0365149900 0.0100669636 0.8521040000 92242178 95654128 1784586240 -0.0981185287 -0.0210212823 0.2040899396 324 12.9200000000 0.0364159718 0.0133610030 0.0365149900 0.0100561022 0.6735450000 92243872 95654128 1785856000 -0.0999636576 -0.0214846227 0.2021458447 325 12.9600000000 0.0365917385 0.0134324822 0.0365917385 0.0100434276 0.7208030000 92245566 95654128 1787777024 -0.1010131091 -0.0221496020 0.2007738799 326 13.0000000000 0.0369650237 0.0135046679 0.0369650237 0.0100352580 0.7839040000 92246000 95654128 1784598528 -0.1024212837 -0.0235886481 0.1981549859 327 13.0400000000 0.0379715525 0.0135794902 0.0379715525 0.0100280901 0.8266530000 92249218 95654128 1785982976 -0.1037109345 -0.0250323638 0.1953336298 328 13.0800000000 0.0383701175 0.0136550714 0.0383701175 0.0100180436 0.7166780000 92419584 95654128 1787887616 -0.1041882411 -0.0253655855 0.1934201270 329 13.1200000000 0.0399271101 0.0137349256 0.0399271101 0.0100071141 0.6226660000 92420158 95654128 1784713216 -0.1054664403 -0.0278321933 0.1920703351 330 13.1600000000 0.0392038971 0.0138121043 0.0399271101 0.0099988316 0.7398120000 92421852 95654128 1785999360 -0.1057791188 -0.0268385410 0.1905377060 331 13.2000000000 0.0394781157 0.0138896451 0.0399271101 0.0099894866 0.7265930000 92423546 95654128 1788014592 -0.1062927768 -0.0269442983 0.1888402849 332 13.2400000000 0.0398620442 0.0139678752 0.0399271101 0.0099805846 0.7207190000 92423980 95654128 1784586240 -0.1069815755 -0.0276295356 0.1871472150 333 13.2800000000 0.0395765789 0.0140447783 0.0399271101 0.0099762889 0.6791770000 92425674 95654128 1785872384 -0.1075384468 -0.0267679561 0.1844304800 334 13.3200000000 0.0397078395 0.0141216138 0.0399271101 0.0099680062 0.6846230000 92427368 95654128 1787760640 -0.1077017933 -0.0260295477 0.1820968986 335 13.3600000000 0.0389549620 0.0141957432 0.0399271101 0.0099594439 0.7049790000 92427942 95654128 1784332288 -0.1097138152 -0.0273720790 0.1801404953 336 13.4000000000 0.0389136821 0.0142693085 0.0399271101 0.0099850740 0.6194150000 92429636 95654128 1785729024 -0.1117519662 -0.0280678384 0.1773514599 337 13.4400000000 0.0406547077 0.0143476034 0.0406547077 0.0099910677 0.7851930000 92431330 95654128 1787523072 -0.1126529649 -0.0295045935 0.1740860194 338 13.4800000000 0.0393794440 0.0144216621 0.0406547077 0.0099896618 0.7031800000 92431764 95654128 1784586240 -0.1137935668 -0.0279317070 0.1723704636 339 13.5200000000 0.0397368595 0.0144963382 0.0406547077 0.0099879971 0.7064830000 92433458 95654128 1785982976 -0.1172722057 -0.0297561660 0.1697666049 340 13.5600000000 0.0396333300 0.0145702705 0.0406547077 0.0099765968 0.6899900000 92435152 95654128 1787887616 -0.1202678755 -0.0303112138 0.1663365513 341 13.6000000000 0.0406866036 0.0146468580 0.0406866036 0.0099623470 0.7385340000 92437354 95654128 1784586240 -0.1216482148 -0.0314344391 0.1637500226 342 13.6400000000 0.0403805375 0.0147221027 0.0406866036 0.0099484991 0.6697920000 92607676 95654128 1785982976 -0.1244604215 -0.0323213898 0.1613717973 343 13.6800000000 0.0394137129 0.0147940899 0.0406866036 0.0099349752 0.8494450000 92608110 95654128 1787887616 -0.1258828491 -0.0320322998 0.1587912738 344 13.7200000000 0.0402469411 0.0148680808 0.0406866036 0.0099251855 0.6861030000 92609804 95654128 1784631296 -0.1269385815 -0.0329129994 0.1567724943 345 13.7600000000 0.0399171859 0.0149406869 0.0406866036 0.0099187149 0.6917390000 92611498 95654128 1785982976 -0.1278703511 -0.0321121849 0.1533287168 346 13.8000000000 0.0393557139 0.0150112505 0.0406866036 0.0099054677 0.7355700000 92611932 95654128 1787887616 -0.1286507696 -0.0312343687 0.1503414363 347 13.8400000000 0.0411758274 0.0150866528 0.0411758274 0.0098921098 0.7360390000 92613766 95654128 1784586240 -0.1300655007 -0.0338599160 0.1465942562 348 13.8800000000 0.0415501706 0.0151626973 0.0415501706 0.0098781435 0.7050970000 92615460 95654128 1785982976 -0.1299742609 -0.0340569839 0.1448830813 349 13.9200000000 0.0399292335 0.0152336616 0.0415501706 0.0098687257 0.8770160000 92615894 95654128 1787887616 -0.1320390850 -0.0332406349 0.1408731490 350 13.9600000000 0.0394561030 0.0153028686 0.0415501706 0.0098612237 0.7179100000 92617588 95654128 1784586240 -0.1326925159 -0.0329405405 0.1362293959 351 14.0000000000 0.0376999676 0.0153666780 0.0415501706 0.0098538753 0.7562890000 92619282 95654128 1785856000 -0.1335250586 -0.0313776247 0.1323064566 352 14.0400000000 0.0363495499 0.0154262884 0.0415501706 0.0098478365 0.8705360000 92619716 95654128 1788022784 -0.1355239153 -0.0309306663 0.1297624111 353 14.0800000000 0.0354472697 0.0154830051 0.0415501706 0.0098399452 0.8109520000 92621550 95654128 1784483840 -0.1367052048 -0.0304574948 0.1274385005 354 14.1200000000 0.0360576212 0.0155411255 0.0415501706 0.0098279307 0.7229730000 92623244 95654128 1785753600 -0.1374763548 -0.0307838395 0.1247020736 355 14.1600000000 0.0368786491 0.0156012312 0.0415501706 0.0098147593 0.8296620000 92623678 95654128 1787641856 -0.1385500729 -0.0321064368 0.1225214377 356 14.2000000000 0.0354497693 0.0156569855 0.0415501706 0.0098013196 0.7850960000 92625372 95654128 1784594432 -0.1396297961 -0.0307454001 0.1189768761 357 14.2400000000 0.0360838212 0.0157142035 0.0415501706 0.0097885314 0.7054970000 92627066 95654128 1785864192 -0.1416852325 -0.0319657102 0.1165453270 358 14.2800000000 0.0373055302 0.0157745145 0.0415501706 0.0097785219 0.7285290000 92627500 95654128 1787895808 -0.1425347328 -0.0330461971 0.1130968183 359 14.3200000000 0.0360470712 0.0158309840 0.0415501706 0.0097698607 0.6279400000 92629334 95654128 1784467456 -0.1435306817 -0.0327814072 0.1098256558 360 14.3600000000 0.0359144807 0.0158867715 0.0415501706 0.0097580301 0.7184930000 92629768 95654128 1785737216 -0.1439756751 -0.0336823165 0.1067014411 361 14.4000000000 0.0370649099 0.0159454367 0.0415501706 0.0097542674 0.7188240000 92631462 95654128 1787768832 -0.1437482983 -0.0347044133 0.1044021323 362 14.4400000000 0.0371101983 0.0160039029 0.0415501706 0.0097436450 0.7953520000 92633156 95654128 1784229888 -0.1427262127 -0.0339795612 0.1019771993 363 14.4800000000 0.0386337526 0.0160662441 0.0415501706 0.0097307643 0.6726280000 92633590 95654128 1785610240 -0.1422856301 -0.0359667093 0.1000575125 364 14.5200000000 0.0392706618 0.0161299925 0.0415501706 0.0097232611 0.8504860000 92635284 95654128 1787387904 -0.1415518075 -0.0364924334 0.0971876830 365 14.5600000000 0.0392696261 0.0161933887 0.0415501706 0.0097132506 0.8866910000 92638638 95654128 1784467456 -0.1421096623 -0.0358412899 0.0945147499 366 14.6000000000 0.0388412364 0.0162552681 0.0415501706 0.0097034080 0.6924790000 92807740 95654128 1785872384 -0.1435408741 -0.0358075686 0.0922387093 367 14.6400000000 0.0383928120 0.0163155884 0.0415501706 0.0096945543 0.8977690000 92809434 95654128 1787887616 -0.1449277550 -0.0373419113 0.0898743942 368 14.6800000000 0.0396453217 0.0163789844 0.0415501706 0.0096848174 0.6639210000 92811128 95654128 1784586240 -0.1436665207 -0.0385567546 0.0878661796 369 14.7200000000 0.0396999158 0.0164421848 0.0415501706 0.0096754134 0.6364440000 92811562 95654128 1785982976 -0.1438616812 -0.0384930000 0.0856702700 370 14.7600000000 0.0404887274 0.0165071754 0.0415501706 0.0096631805 0.7141470000 92813256 95654128 1787760640 -0.1439657211 -0.0388621539 0.0834517702 371 14.8000000000 0.0407958291 0.0165726435 0.0415501706 0.0096504783 0.6822990000 92815090 95654128 1784606720 -0.1445289999 -0.0385859236 0.0809656382 372 14.8400000000 0.0403209589 0.0166364830 0.0415501706 0.0096430870 0.8852440000 92815524 95654128 1785982976 -0.1457414329 -0.0385436565 0.0776815116 373 14.8800000000 0.0404144786 0.0167002310 0.0415501706 0.0096361170 0.7862450000 92818762 95654128 1787760640 -0.1474778354 -0.0388919413 0.0743863136 374 14.9200000000 0.0400749855 0.0167627304 0.0415501706 0.0096395954 0.7496300000 92989128 95654128 1784713216 -0.1498229951 -0.0387936085 0.0714124665 375 14.9600000000 0.0385425314 0.0168208098 0.0415501706 0.0096529395 0.7814980000 92989562 95654128 1785999360 -0.1524467021 -0.0392457172 0.0696227476 376 15.0000000000 0.0371175036 0.0168747904 0.0415501706 0.0096422099 0.6615870000 92991256 95654128 1788141568 -0.1539634913 -0.0386180989 0.0671007335 377 15.0400000000 0.0368714817 0.0169278320 0.0415501706 0.0096299332 0.6448520000 92991830 95654128 1784586240 -0.1543307453 -0.0370715074 0.0650122166 378 15.0800000000 0.0370560661 0.0169810813 0.0415501706 0.0096416783 0.6696940000 92993524 95654128 1785872384 -0.1546529084 -0.0378826037 0.0629170090 379 15.1200000000 0.0363017619 0.0170320594 0.0415501706 0.0096370267 0.8458520000 92995218 95654128 1788014592 -0.1543253362 -0.0377237201 0.0606550053 380 15.1600000000 0.0351322033 0.0170796913 0.0415501706 0.0096247868 0.8116930000 92995652 95654128 1784713216 -0.1554730684 -0.0363969766 0.0576183461 381 15.2000000000 0.0349278711 0.0171265369 0.0415501706 0.0096133536 0.6794040000 92997346 95654128 1786236928 -0.1563488245 -0.0361845419 0.0556018651 382 15.2400000000 0.0337881446 0.0171701537 0.0415501706 0.0096017021 0.5754140000 93000452 95654128 1788141568 -0.1565676332 -0.0351873673 0.0527465232 383 15.2800000000 0.0333805606 0.0172124785 0.0415501706 0.0095898639 0.6976360000 93169690 95654128 1784967168 -0.1593913585 -0.0354164205 0.0498967357 384 15.3200000000 0.0332098193 0.0172541383 0.0415501706 0.0095781241 0.8542040000 93171384 95654128 1786363904 -0.1607439816 -0.0350633115 0.0475306027 385 15.3600000000 0.0327664986 0.0172944301 0.0415501706 0.0095680345 0.6945550000 93173078 95654128 1785602048 -0.1633466035 -0.0347641855 0.0451944694 386 15.4000000000 0.0318103284 0.0173320361 0.0415501706 0.0095568109 0.6774340000 93173512 95654128 1787125760 -0.1654070914 -0.0340859219 0.0420353413 387 15.4400000000 0.0322188139 0.0173705032 0.0415501706 0.0095454334 0.7786380000 93175206 95654128 1784840192 -0.1654698104 -0.0337400772 0.0399300568 388 15.4800000000 0.0328244902 0.0174103331 0.0415501706 0.0095385508 1.0330850000 93176900 95654128 1786236928 -0.1678623855 -0.0339815393 0.0380012952 389 15.5200000000 0.0311930254 0.0174457642 0.0415501706 0.0095330623 0.8487090000 93177474 95654128 1787887616 -0.1700341702 -0.0322544873 0.0351857319 390 15.5600000000 0.0313146524 0.0174813254 0.0415501706 0.0095270164 0.7442410000 93179168 95654128 1784840192 -0.1716540903 -0.0321563184 0.0332196541 391 15.6000000000 0.0318507478 0.0175180759 0.0415501706 0.0095182755 0.7332240000 93180862 95654128 1786490880 -0.1723770499 -0.0313825645 0.0308550093 392 15.6400000000 0.0315992422 0.0175539972 0.0415501706 0.0095189671 0.8565660000 93181296 95654128 1785769984 -0.1759158522 -0.0311053004 0.0279230122 393 15.6800000000 0.0307864193 0.0175876675 0.0415501706 0.0095170757 0.6814470000 93182990 95654128 1787125760 -0.1760077327 -0.0297093149 0.0255516786 394 15.7200000000 0.0308279116 0.0176212722 0.0415501706 0.0095113873 0.7504230000 93184684 95654128 1784840192 -0.1771279722 -0.0291619971 0.0231793299 395 15.7600000000 0.0315043814 0.0176564193 0.0415501706 0.0095049553 0.6438640000 93185258 95654128 1786363904 -0.1783566475 -0.0288089495 0.0207455698 396 15.8000000000 0.0313670412 0.0176910421 0.0415501706 0.0095015419 0.8190780000 93186952 95654128 1785651200 -0.1772078425 -0.0270921998 0.0184537694 397 15.8400000000 0.0318946205 0.0177268193 0.0415501706 0.0095065032 0.8315950000 93189170 95654128 1786998784 -0.1772793531 -0.0264943931 0.0166045111 398 15.8800000000 0.0315829478 0.0177616337 0.0415501706 0.0095170348 0.7304870000 93359528 95654128 1784848384 -0.1776707023 -0.0262977984 0.0146558164 399 15.9200000000 0.0300232023 0.0177923645 0.0415501706 0.0095086995 0.7200530000 93361222 95654128 1786245120 -0.1803410500 -0.0253210682 0.0117871389 400 15.9600000000 0.0294123944 0.0178214145 0.0415501706 0.0094977174 0.6893400000 93361656 95654128 1785769984 -0.1813800335 -0.0232722275 0.0092317890 401 16.0000000000 0.0295342952 0.0178506237 0.0415501706 0.0095025204 0.6576660000 93363490 95654128 1787387904 -0.1814755052 -0.0228844844 0.0072991010 402 16.0400000000 0.0295690224 0.0178797740 0.0415501706 0.0094995206 0.7257820000 93365184 95654128 1784594432 -0.1815780550 -0.0220295936 0.0056083892 403 16.0800000000 0.0295645483 0.0179087685 0.0415501706 0.0095018121 0.8340110000 93365618 95654128 1785864192 -0.1813192964 -0.0205210652 0.0038742097 404 16.1200000000 0.0288893599 0.0179359481 0.0415501706 0.0095169051 0.8681970000 93367312 95654128 1787895808 -0.1801873446 -0.0182501376 0.0018584456 405 16.1600000000 0.0283528604 0.0179616689 0.0415501706 0.0095383831 0.8023280000 93369006 95654128 1784999936 -0.1823290139 -0.0186712816 0.0000878962 406 16.2000000000 0.0275026225 0.0179851688 0.0415501706 0.0095336864 0.7384530000 93369440 95654128 1786363904 -0.1846987903 -0.0172569901 -0.0023591029 407 16.2400000000 0.0268695969 0.0180069979 0.0415501706 0.0095464397 0.7914520000 93371274 95654128 1785729024 -0.1851025969 -0.0160631035 -0.0039354013 408 16.2800000000 0.0257730335 0.0180260323 0.0415501706 0.0095496687 0.8896440000 93372968 95654128 1787125760 -0.1851622164 -0.0143628949 -0.0051963301 409 16.3200000000 0.0240039919 0.0180406483 0.0415501706 0.0095423367 0.7349580000 93373402 95654128 1784713216 -0.1877962053 -0.0135307414 -0.0074882451 410 16.3600000000 0.0234990399 0.0180539614 0.0415501706 0.0095324560 0.8932130000 93375096 95654128 1785999360 -0.1888157129 -0.0121178105 -0.0099119069 411 16.3999999990 0.0222919490 0.0180642728 0.0415501706 0.0095370630 0.8036640000 93376790 95654128 1788014592 -0.1902073622 -0.0108217942 -0.0121347522 412 16.4400000000 0.0224465523 0.0180749094 0.0415501706 0.0095452924 0.9715040000 93377224 95654128 1784840192 -0.1897677183 -0.0098035755 -0.0134827504 413 16.4800000000 0.0237314552 0.0180886057 0.0415501706 0.0095466475 0.6424940000 93379058 95654128 1786236928 -0.1867493242 -0.0083502475 -0.0140365968 414 16.5200000000 0.0242659599 0.0181035268 0.0415501706 0.0095399168 0.9181540000 93379492 95654128 1788014592 -0.1848827899 -0.0065925345 -0.0149105955 415 16.5599999990 0.0254424401 0.0181212110 0.0415501706 0.0095296849 0.6923140000 93381186 95654128 1784713216 -0.1839784235 -0.0059700394 -0.0167540982 416 16.6000000000 0.0260313712 0.0181402258 0.0415501706 0.0095228602 0.8898380000 93382880 95654128 1786236928 -0.1834293455 -0.0055103833 -0.0183331277 417 16.6400000000 0.0258063953 0.0181586099 0.0415501706 0.0095172947 0.7002310000 93385210 95654128 1788014592 -0.1845236123 -0.0048565790 -0.0203513857 418 16.6800000000 0.0253825095 0.0181758919 0.0415501706 0.0095163399 0.7332650000 93555588 95654128 1784713216 -0.1862501353 -0.0040689874 -0.0227409825 419 16.7199999990 0.0243063718 0.0181905231 0.0415501706 0.0095258711 0.8746570000 93557422 95654128 1786109952 -0.1871009767 -0.0016156144 -0.0255287718 420 16.7600000000 0.0246925000 0.0182060040 0.0415501706 0.0095486925 0.6817330000 93557856 95654128 1788141568 -0.1865683645 -0.0015688021 -0.0277633257 421 16.8000000000 0.0260648094 0.0182246710 0.0415501706 0.0095471769 0.8007000000 93559550 95654128 1784758272 -0.1856940389 -0.0012238733 -0.0298203900 422 16.8400000000 0.0274007190 0.0182464152 0.0415501706 0.0095446162 0.8709640000 93561244 95654128 1786109952 -0.1839374155 -0.0006730764 -0.0317385867 423 16.8799999990 0.0282895826 0.0182701579 0.0415501706 0.0095402972 0.9324780000 93561678 95654128 1788014592 -0.1836062521 0.0002009333 -0.0339139625 424 16.9200000000 0.0287011638 0.0182947594 0.0415501706 0.0095363122 0.7212620000 93563372 95654128 1784713216 -0.1838922054 0.0006147978 -0.0365651287 425 16.9600000000 0.0271812230 0.0183156687 0.0415501706 0.0095524551 0.7537480000 93565206 95654128 1786109952 -0.1848123521 0.0018008726 -0.0397900194 426 17.0000000000 0.0266142245 0.0183351489 0.0415501706 0.0095507962 0.8805490000 93565640 95654128 1787887616 -0.1850154251 0.0022239722 -0.0429004282 427 17.0400000000 0.0260210950 0.0183531487 0.0415501706 0.0095414001 0.8166790000 93567334 95654128 1784729600 -0.1859695017 0.0017376395 -0.0453848094 428 17.0800000000 0.0253725313 0.0183695492 0.0415501706 0.0095304490 0.6528210000 93569028 95654128 1785982976 -0.1850626618 0.0025275298 -0.0488859937 429 17.1200000000 0.0254495703 0.0183860527 0.0415501706 0.0095214026 0.7162810000 93569462 95654128 1787904000 -0.1849584132 0.0023229120 -0.0513310507 430 17.1600000000 0.0261825584 0.0184041841 0.0415501706 0.0095106614 0.7436460000 93571156 95654128 1784713216 -0.1849028021 0.0019378314 -0.0543775372 431 17.2000000000 0.0259380359 0.0184216641 0.0415501706 0.0094997156 0.8657680000 93571730 95654128 1785999360 -0.1848259419 0.0026825280 -0.0580727309 432 17.2400000000 0.0259846468 0.0184391710 0.0415501706 0.0094952027 0.8217060000 93573424 95654128 1787887616 -0.1845979095 0.0034973940 -0.0603078790 433 17.2800000000 0.0260721408 0.0184567991 0.0415501706 0.0094934831 0.8908240000 93575118 95654128 1784586240 -0.1847790331 0.0038965011 -0.0630494878 434 17.3200000000 0.0240892302 0.0184697770 0.0415501706 0.0094858507 0.7405440000 93575552 95654128 1785856000 -0.1863528192 0.0053128619 -0.0659279004 435 17.3600000000 0.0235637501 0.0184814873 0.0415501706 0.0094760500 0.7349380000 93577246 95654128 1787887616 -0.1861695051 0.0083439481 -0.0690140501 436 17.4000000000 0.0231626891 0.0184922240 0.0415501706 0.0094853282 0.6746340000 93578940 95654128 1784713216 -0.1857598573 0.0092010396 -0.0718218312 437 17.4400000000 0.0226274543 0.0185016868 0.0415501706 0.0094998102 0.8122440000 93579514 95654128 1785982976 -0.1851622462 0.0103191454 -0.0747402757 438 17.4800000000 0.0222855080 0.0185103256 0.0415501706 0.0094976677 0.7447440000 93581208 95654128 1788014592 -0.1843447685 0.0112442542 -0.0774287507 439 17.5200000000 0.0214825198 0.0185170960 0.0415501706 0.0094954918 0.6737410000 93582902 95654128 1784586240 -0.1826771498 0.0124959350 -0.0804522410 440 17.5600000000 0.0208122395 0.0185223122 0.0415501706 0.0094981374 0.6393090000 93583336 95654128 1785872384 -0.1823764294 0.0138215460 -0.0830098987 441 17.6000000000 0.0204716790 0.0185267326 0.0415501706 0.0095007227 0.6643220000 93585030 95654128 1787506688 -0.1816319078 0.0159586947 -0.0851934478 442 17.6400000000 0.0188547876 0.0185274748 0.0415501706 0.0095122372 0.8575930000 93586724 95654128 1784594432 -0.1830568761 0.0157348458 -0.0884525478 443 17.6800000000 0.0184347294 0.0185272654 0.0415501706 0.0095139082 0.7221250000 93587298 95654128 1785991168 -0.1833650321 0.0167438947 -0.0898390859 444 17.7200000000 0.0184284039 0.0185270428 0.0415501706 0.0095071840 0.9744700000 93590732 95654128 1787768832 -0.1837005615 0.0165930819 -0.0918368995 445 17.7600000000 0.0179411788 0.0185257262 0.0415501706 0.0094969073 0.9148770000 93761126 95654128 1784594432 -0.1837362945 0.0179898273 -0.0951909795 446 17.8000000000 0.0181538519 0.0185248924 0.0415501706 0.0094867675 0.7457400000 93761560 95654128 1786007552 -0.1838508993 0.0172708053 -0.0978367850 447 17.8400000000 0.0183989238 0.0185246106 0.0415501706 0.0094802628 0.8184140000 93763254 95654128 1788022784 -0.1835672408 0.0176918972 -0.1004581973 448 17.8800000000 0.0178315248 0.0185230635 0.0415501706 0.0094712304 0.8706910000 93764948 95654128 1784459264 -0.1839136481 0.0184855852 -0.1025965810 449 17.9200000000 0.0169857349 0.0185196396 0.0415501706 0.0094637886 0.6191900000 93765522 95654128 1785856000 -0.1843062788 0.0182817131 -0.1046708226 450 17.9600000000 0.0170792527 0.0185164388 0.0415501706 0.0094535158 0.9337180000 93767216 95654128 1787760640 -0.1850385815 0.0190616455 -0.1093055606 451 18.0000000000 0.0167156514 0.0185124459 0.0415501706 0.0094591764 0.6054800000 93767650 95654128 1784467456 -0.1858312637 0.0196195897 -0.1111345217 452 18.0400000000 0.0164755397 0.0185079395 0.0415501706 0.0094631898 0.6085730000 93769344 95654128 1785856000 -0.1868160218 0.0195794106 -0.1127095222 453 18.0800000000 0.0160109028 0.0185024273 0.0415501706 0.0094664829 0.8163900000 93771038 95654128 1787633664 -0.1878135949 0.0194833931 -0.1148189455 454 18.1200000000 0.0157928746 0.0184964591 0.0415501706 0.0094627950 0.7547320000 93771472 95654128 1784614912 -0.1885888278 0.0194791034 -0.1177931502 455 18.1600000000 0.0155401696 0.0184899617 0.0415501706 0.0094530686 0.7023580000 93773306 95654128 1785982976 -0.1892031878 0.0213247072 -0.1209352389 456 18.2000000000 0.0158557557 0.0184841850 0.0415501706 0.0094435975 0.7820730000 93775000 95654128 1787887616 -0.1896030605 0.0225505680 -0.1233139336 457 18.2400000000 0.0159538258 0.0184786481 0.0415501706 0.0094437612 0.7253860000 93775434 95654128 1784713216 -0.1901082993 0.0235205945 -0.1255231649 458 18.2800000000 0.0169006977 0.0184752028 0.0415501706 0.0094421752 0.8209450000 93777128 95654128 1785982976 -0.1906494498 0.0242909435 -0.1273373663 459 18.3200000000 0.0175207853 0.0184731234 0.0415501706 0.0094573679 0.8358670000 93778822 95654128 1787887616 -0.1911523044 0.0251624081 -0.1295379102 460 18.3600000000 0.0180412084 0.0184721845 0.0415501706 0.0094636147 0.7203330000 93779256 95654128 1784586240 -0.1910064071 0.0253172275 -0.1320847422 461 18.4000000000 0.0194244664 0.0184742502 0.0415501706 0.0094625513 0.7313250000 93781090 95654128 1785856000 -0.1904561371 0.0249552522 -0.1342178434 462 18.4400000000 0.0195695981 0.0184766211 0.0415501706 0.0094805628 0.8609400000 93782784 95654128 1787887616 -0.1909703314 0.0254088379 -0.1363856643 463 18.4800000000 0.0189759433 0.0184776995 0.0415501706 0.0094870605 0.8517400000 93783218 95654128 1784586240 -0.1927930564 0.0257080887 -0.1391438246 464 18.5200000000 0.0192698408 0.0184794067 0.0415501706 0.0094883669 0.7290010000 93784912 95654128 1785872384 -0.1930914074 0.0247858707 -0.1417256296 465 18.5600000000 0.0199101493 0.0184824836 0.0415501706 0.0094874784 0.7250220000 93786606 95654128 1787887616 -0.1934477389 0.0247388296 -0.1442237794 466 18.6000000000 0.0199784189 0.0184856937 0.0415501706 0.0094782515 0.7493690000 93787040 95654128 1784713216 -0.1949281842 0.0261741187 -0.1474123746 467 18.6400000000 0.0188576132 0.0184864901 0.0415501706 0.0094683970 0.8455370000 93788874 95654128 1785982976 -0.1976676285 0.0264029931 -0.1509338915 468 18.6800000000 0.0184516571 0.0184864157 0.0415501706 0.0094593411 0.7306710000 93789308 95654128 1787760640 -0.1997953802 0.0278793778 -0.1539838016 469 18.7200000000 0.0187160615 0.0184869054 0.0415501706 0.0094607446 0.7836960000 93791002 95654128 1784459264 -0.2020470649 0.0284842551 -0.1558887511 470 18.7600000000 0.0185198877 0.0184869755 0.0415501706 0.0094508481 0.8364820000 93792696 95654128 1785856000 -0.2041754276 0.0321833044 -0.1593742967 471 18.8000000000 0.0188904926 0.0184878323 0.0415501706 0.0094831982 0.7514470000 93793130 95654128 1787633664 -0.2045581937 0.0323400423 -0.1616973728 472 18.8400000000 0.0191095639 0.0184891495 0.0415501706 0.0095704982 0.7415590000 93796476 95654128 1784586240 -0.2058626413 0.0338464789 -0.1643838584 473 18.8800000000 0.0184873268 0.0184891456 0.0415501706 0.0096337976 0.7806930000 93967014 95654128 1785999360 -0.2080022544 0.0338095725 -0.1677134931 474 18.9200000000 0.0191126931 0.0184904611 0.0415501706 0.0096357464 0.7272290000 93967448 95654128 1787887616 -0.2098791599 0.0337632895 -0.1697562486 475 18.9600000000 0.0190407485 0.0184916196 0.0415501706 0.0096309577 0.9959020000 93969142 95654128 1784586240 -0.2113086730 0.0351623744 -0.1726108938 476 19.0000000000 0.0195414443 0.0184938251 0.0415501706 0.0096445841 0.7428400000 93970836 95654128 1785982976 -0.2119038254 0.0377134830 -0.1752340645 477 19.0400000000 0.0207329858 0.0184985194 0.0415501706 0.0096429739 0.7786250000 93971270 95654128 1787887616 -0.2113402635 0.0402707756 -0.1775323451 478 19.0800000000 0.0203116518 0.0185023126 0.0415501706 0.0096335165 0.7284190000 93972964 95654128 1784586240 -0.2125878781 0.0433594584 -0.1807049513 479 19.1200000000 0.0212839413 0.0185081197 0.0415501706 0.0096331096 0.6865350000 93974798 95654128 1785982976 -0.2126517594 0.0439178981 -0.1826496124 480 19.1600000000 0.0212786347 0.0185138916 0.0415501706 0.0096332665 0.8736550000 93975232 95654128 1787887616 -0.2143623531 0.0452306047 -0.1850189418 481 19.2000000000 0.0218981095 0.0185209274 0.0415501706 0.0096309932 0.7017640000 93976926 95654128 1784594432 -0.2143010944 0.0456334539 -0.1870892346 482 19.2400000000 0.0223123096 0.0185287934 0.0415501706 0.0096295851 0.7369690000 93978620 95654128 1785864192 -0.2148220539 0.0461757146 -0.1893769056 483 19.2800000000 0.0218456071 0.0185356605 0.0415501706 0.0096461334 0.9106040000 93979054 95654128 1787895808 -0.2168048620 0.0465410091 -0.1916813552 484 19.3200000000 0.0226959679 0.0185442562 0.0415501706 0.0096457410 0.8470020000 93980748 95654128 1784483840 -0.2161523104 0.0464203320 -0.1931389272 485 19.3600000000 0.0228181407 0.0185530683 0.0415501706 0.0096372557 0.7465240000 93981322 95654128 1785737216 -0.2164530754 0.0468091145 -0.1948254406 486 19.4000000000 0.0231876727 0.0185626045 0.0415501706 0.0096291273 0.7531120000 93983016 95654128 1787768832 -0.2162802666 0.0470140055 -0.1965204477 487 19.4400000000 0.0229268689 0.0185715660 0.0415501706 0.0096224923 0.7794160000 93984710 95654128 1784467456 -0.2170990855 0.0477481559 -0.1986770928 488 19.4800000000 0.0231023841 0.0185808505 0.0415501706 0.0096170901 0.8353850000 93985144 95654128 1785864192 -0.2171796113 0.0495004915 -0.2009162903 489 19.5200000000 0.0236443449 0.0185912053 0.0415501706 0.0096206197 0.7871410000 93986838 95654128 1787768832 -0.2167967409 0.0498299897 -0.2026159465 490 19.5600000000 0.0242263302 0.0186027055 0.0415501706 0.0096146243 0.7416780000 93988532 95654128 1784467456 -0.2162648439 0.0514872931 -0.2045271248 491 19.6000000000 0.0239714943 0.0186136399 0.0415501706 0.0096063915 0.9085610000 93989106 95654128 1785864192 -0.2175484449 0.0516130179 -0.2065706998 492 19.6400000000 0.0237841252 0.0186241491 0.0415501706 0.0095978972 1.2644040000 93990800 95654128 1787768832 -0.2174265832 0.0524229333 -0.2085695863 493 19.6800000000 0.0233422760 0.0186337193 0.0415501706 0.0095918221 1.6079400000 93992494 95654128 1784483840 -0.2189845443 0.0530046448 -0.2105475664 494 19.7200000000 0.0231896881 0.0186429419 0.0415501706 0.0095832170 1.7421480000 93995452 95654128 1785856000 -0.2193710357 0.0546631739 -0.2124981135 495 19.7600000000 0.0233777463 0.0186525072 0.0415501706 0.0095865085 1.7090560000 94165834 95654128 1787633664 -0.2205701917 0.0537727475 -0.2142784446 496 19.8000000000 0.0228470564 0.0186609639 0.0415501706 0.0095850545 0.8123750000 94167528 95654128 1784586240 -0.2232970893 0.0540920682 -0.2168969810 497 19.8400000000 0.0233148560 0.0186703279 0.0415501706 0.0095814262 0.8290430000 94168102 95654128 1785982976 -0.2234580666 0.0542583093 -0.2185457051 498 19.8800000000 0.0229123402 0.0186788460 0.0415501706 0.0095748234 0.7705720000 94169796 95654128 1787760640 -0.2239057571 0.0534697026 -0.2202126533 499 19.9200000000 0.0223975014 0.0186862982 0.0415501706 0.0095654005 0.7284740000 94171490 95654128 1784586240 -0.2252342701 0.0541264303 -0.2228002697 500 19.9600000000 0.0242131352 0.0186973519 0.0415501706 0.0095578570 0.7455510000 94171924 95654128 1785999360 -0.2215796262 0.0556591898 -0.2240169048 501 20.0000000000 0.0239480808 0.0187078324 0.0415501706 0.0095696478 0.7303670000 94173618 95654128 1787887616 -0.2238442451 0.0542289764 -0.2267355472 502 20.0400000000 0.0238281637 0.0187180322 0.0415501706 0.0095841013 0.6873770000 94175312 95654128 1784586240 -0.2268095315 0.0540868603 -0.2297348976 503 20.0800000000 0.0237558912 0.0187280479 0.0415501706 0.0095752486 0.6763740000 94175886 95654128 1785999360 -0.2278039008 0.0555951037 -0.2327040732 504 20.1200000000 0.0234982669 0.0187375126 0.0415501706 0.0095657575 0.8301240000 94177580 95654128 1787887616 -0.2289744765 0.0563868061 -0.2354386300 505 20.1600000000 0.0237423908 0.0187474232 0.0415501706 0.0095579367 0.7141480000 94178014 95654128 1784713216 -0.2273845822 0.0573274828 -0.2376816124 506 20.2000000000 0.0240533873 0.0187579093 0.0415501706 0.0095490551 0.7452170000 94179708 95654128 1786109952 -0.2284608781 0.0585104451 -0.2398665696 507 20.2400000000 0.0243230797 0.0187688860 0.0415501706 0.0095438895 0.7517470000 94181402 95654128 1787887616 -0.2294120640 0.0577134676 -0.2423374802 508 20.2800000000 0.0242754556 0.0187797257 0.0415501706 0.0095366137 0.7839980000 94181836 95654128 1784729600 -0.2297141105 0.0578725003 -0.2453001887 509 20.3200000000 0.0249652285 0.0187918780 0.0415501706 0.0095339599 0.8913320000 94183670 95654128 1785982976 -0.2291354090 0.0577711090 -0.2468863428 510 20.3600000000 0.0249558948 0.0188039643 0.0415501706 0.0095345834 0.8904630000 94185364 95654128 1788014592 -0.2297527790 0.0587691106 -0.2493377179 511 20.4000000000 0.0250987839 0.0188162829 0.0415501706 0.0095269179 0.7362010000 94185798 95654128 1784586240 -0.2305100113 0.0594848059 -0.2520312369 512 20.4400000000 0.0252419077 0.0188288329 0.0415501706 0.0095178834 0.7673380000 94187492 95654128 1785856000 -0.2317184210 0.0601854511 -0.2550686598 513 20.4800000000 0.0253007039 0.0188414487 0.0415501706 0.0095104544 0.6469800000 94230146 95654128 1787760640 -0.2284265012 0.0613993593 -0.2575800419 514 20.5200000000 0.0258537121 0.0188550912 0.0415501706 0.0095046997 0.7477330000 94314548 95654128 1784713216 -0.2286136597 0.0616396144 -0.2603997886 515 20.5600000000 0.0263137911 0.0188695741 0.0415501706 0.0094985187 0.7410270000 94318650 95654128 1785982976 -0.2269383073 0.0611506030 -0.2626270950 516 20.6000000000 0.0259868503 0.0188833673 0.0415501706 0.0094952960 0.7517100000 94489012 95654128 1785393152 -0.2263863832 0.0601430647 -0.2659693360 517 20.6400000000 0.0260893181 0.0188973053 0.0415501706 0.0094880953 0.7097940000 94489446 95654128 1784492032 -0.2240272015 0.0601633377 -0.2680310309 518 20.6800000000 0.0258984510 0.0189108210 0.0415501706 0.0094829993 0.7151650000 94491140 95654128 1785729024 -0.2226079702 0.0604223609 -0.2706419826 519 20.7200000000 0.0256401915 0.0189237871 0.0415501706 0.0094783486 0.7370510000 94492834 95654128 1787633664 -0.2220875025 0.0604990646 -0.2736095786 520 20.7600000000 0.0261645168 0.0189377115 0.0415501706 0.0094734428 0.8069260000 94493268 95654128 1784332288 -0.2212163061 0.0604515709 -0.2755424976 521 20.8000000000 0.0265518241 0.0189523260 0.0415501706 0.0094651169 0.6780290000 94495102 95654128 1785856000 -0.2204205990 0.0614853986 -0.2772925794 522 20.8400000000 0.0271288548 0.0189679898 0.0415501706 0.0094566782 0.7120340000 94495536 95654128 1787641856 -0.2208856642 0.0634798631 -0.2793667614 523 20.8800000000 0.0281178784 0.0189854848 0.0415501706 0.0094479760 0.6827860000 94497230 95654128 1784467456 -0.2207458913 0.0644036755 -0.2809607089 524 20.9200000000 0.0283191148 0.0190032971 0.0415501706 0.0094397687 0.8919890000 94498924 95654128 1785864192 -0.2212938964 0.0640681088 -0.2833665609 525 20.9600000000 0.0283433758 0.0190210877 0.0415501706 0.0094334231 0.7440270000 94499358 95654128 1787641856 -0.2216629535 0.0639301315 -0.2859521508 526 21.0000000000 0.0287675709 0.0190396172 0.0415501706 0.0094286380 1.0558800000 94501052 95654128 1784467456 -0.2221859992 0.0646372512 -0.2882682979 527 21.0400000000 0.0292533673 0.0190589981 0.0415501706 0.0094236682 1.7307830000 94502886 95654128 1785864192 -0.2221726328 0.0652275532 -0.2900280356 528 21.0800000000 0.0294092372 0.0190786008 0.0415501706 0.0094246580 0.7262240000 94503320 95654128 1787768832 -0.2211765945 0.0653755441 -0.2915861905 529 21.1200000000 0.0296088494 0.0190985068 0.0415501706 0.0094233198 0.8352860000 94505014 95654128 1784467456 -0.2203824520 0.0645327792 -0.2931631505 530 21.1600000000 0.0297383759 0.0191185820 0.0415501706 0.0094238648 0.7337380000 94506708 95654128 1785864192 -0.2204106003 0.0643766522 -0.2947057486 531 21.2000000000 0.0303337164 0.0191397028 0.0415501706 0.0094292640 0.7991590000 94507142 95654128 1787760640 -0.2207697630 0.0647102743 -0.2963831723 532 21.2400000000 0.0307368226 0.0191615019 0.0415501706 0.0094371199 0.7377380000 94508836 95654128 1784606720 -0.2214502990 0.0628968999 -0.2982444465 533 21.2800000000 0.0303335153 0.0191824625 0.0415501706 0.0094447521 0.7854910000 94510670 95654128 1785982976 -0.2210466117 0.0622406267 -0.3002319634 534 21.3200000000 0.0311278552 0.0192048321 0.0415501706 0.0094385434 0.8336160000 94511104 95654128 1788014592 -0.2219740897 0.0619549789 -0.3019362390 535 21.3600000000 0.0314336829 0.0192276898 0.0415501706 0.0094344289 0.7469710000 94512798 95654128 1784586240 -0.2227740735 0.0605688244 -0.3034283817 536 21.4000000000 0.0320306458 0.0192515759 0.0415501706 0.0094323059 0.7700200000 94514492 95654128 1785872384 -0.2243364453 0.0603612661 -0.3054778278 537 21.4400000000 0.0327462107 0.0192767056 0.0415501706 0.0094307690 0.8672800000 94514926 95654128 1787760640 -0.2247105390 0.0602043085 -0.3063566387 538 21.4800000000 0.0328638703 0.0193019605 0.0415501706 0.0094397088 0.6456440000 94516620 95654128 1784475648 -0.2248963416 0.0593894720 -0.3077471554 539 21.5200000000 0.0321373530 0.0193257739 0.0415501706 0.0094554519 0.8032010000 94519526 95654128 1785856000 -0.2235728949 0.0580790751 -0.3089527786 540 21.5600000000 0.0324530043 0.0193500836 0.0415501706 0.0094613106 0.8593080000 94689932 95654128 1787887616 -0.2250499576 0.0570363365 -0.3109183013 541 21.6000000000 0.0331361257 0.0193755661 0.0415501706 0.0094631391 0.7052280000 94691626 95654128 1784729600 -0.2276582271 0.0560314767 -0.3132838607 542 21.6400000000 0.0339133628 0.0194023886 0.0415501706 0.0094622964 0.7486310000 94692060 95654128 1785982976 -0.2287397385 0.0547464527 -0.3144130707 543 21.6800000000 0.0332815871 0.0194279488 0.0415501706 0.0094633771 0.8509000000 94693754 95654128 1787887616 -0.2286801934 0.0527216420 -0.3152815700 544 21.7200000000 0.0339143649 0.0194545783 0.0415501706 0.0094592432 0.8671860000 94695448 95654128 1784713216 -0.2305344343 0.0519965105 -0.3171761930 545 21.7600000000 0.0344910994 0.0194821682 0.0415501706 0.0094535643 0.7071490000 94696022 95654128 1785982976 -0.2318530381 0.0509883873 -0.3187606931 546 21.8000000000 0.0351268649 0.0195108215 0.0415501706 0.0094573383 0.8513830000 94697716 95654128 1787666432 -0.2333066463 0.0498571843 -0.3199947774 547 21.8400000000 0.0362673625 0.0195414550 0.0415501706 0.0094777877 0.7300580000 94699410 95654128 1784479744 -0.2346642613 0.0483938381 -0.3210772872 548 21.8800000000 0.0372051895 0.0195736881 0.0415501706 0.0094884919 0.8765390000 94699844 95654128 1785856000 -0.2359102368 0.0473413579 -0.3216678798 549 21.9200000000 0.0373968780 0.0196061529 0.0415501706 0.0094988995 0.7579420000 94703610 95654128 1787633664 -0.2366165817 0.0442592986 -0.3226885498 550 21.9600000000 0.0370117873 0.0196377995 0.0415501706 0.0095066114 0.8163950000 94873996 95654128 1784586240 -0.2373659462 0.0431197695 -0.3242183924 551 22.0000000000 0.0379969925 0.0196711193 0.0415501706 0.0095029467 0.7658570000 94874570 95654128 1785999360 -0.2394459844 0.0438002460 -0.3259411752 552 22.0400000000 0.0379724242 0.0197042739 0.0415501706 0.0094990731 0.9524840000 94876264 95654128 1788014592 -0.2403455079 0.0428394675 -0.3271181583 553 22.0800000000 0.0385424197 0.0197383392 0.0415501706 0.0094989634 0.8518570000 94877958 95654128 1784602624 -0.2420579195 0.0411277823 -0.3283517659 554 22.1200000000 0.0391451046 0.0197733695 0.0415501706 0.0095065541 0.8591690000 94878392 95654128 1785982976 -0.2430005968 0.0413099714 -0.3288466632 555 22.1600000000 0.0396934599 0.0198092615 0.0415501706 0.0095104051 0.7506050000 94880086 95654128 1787887616 -0.2443646789 0.0433115736 -0.3308386803 556 22.2000000000 0.0395249426 0.0198447214 0.0415501706 0.0095037054 0.7574690000 94881780 95654128 1784586240 -0.2446720153 0.0427209176 -0.3322425187 557 22.2400000000 0.0403163917 0.0198814748 0.0415501706 0.0094961076 0.7459810000 94882354 95654128 1785999360 -0.2457408756 0.0416384935 -0.3331601024 558 22.2800000000 0.0404990502 0.0199184239 0.0415501706 0.0094922216 0.7638350000 94884048 95654128 1787887616 -0.2458996475 0.0400239155 -0.3334465921 559 22.3200000000 0.0397971421 0.0199539851 0.0415501706 0.0094944190 0.9141940000 94884482 95654128 1784586240 -0.2457213998 0.0390897654 -0.3345205486 560 22.3600000000 0.0394239202 0.0199887529 0.0415501706 0.0094909930 0.7660660000 94889160 95654128 1785982976 -0.2463690192 0.0384317562 -0.3362925351 561 22.4000000000 0.0395568758 0.0200236336 0.0415501706 0.0094889721 0.6369690000 95059454 95654128 1788141568 -0.2464740127 0.0380058512 -0.3373876810 562 22.4400000000 0.0391355045 0.0200576405 0.0415501706 0.0094854249 0.7201800000 95059888 95654128 1784745984 -0.2470280975 0.0368281044 -0.3386893570 563 22.4800000000 0.0391939320 0.0200916304 0.0415501706 0.0094816065 0.7348070000 95061722 95654128 1786109952 -0.2473401129 0.0355682969 -0.3393721581 564 22.5200000000 0.0389520563 0.0201250709 0.0415501706 0.0094833282 0.8073490000 95063416 95654128 1787895808 -0.2474523187 0.0359261632 -0.3406150043 565 22.5600000000 0.0382027552 0.0201570668 0.0415501706 0.0094841102 0.7592740000 95063850 95654128 1784594432 -0.2476960719 0.0338698290 -0.3416139185 566 22.6000000000 0.0377741307 0.0201881923 0.0415501706 0.0094836022 0.8359520000 95065544 95654128 1785864192 -0.2474018037 0.0331795812 -0.3426837623 567 22.6400000000 0.0385336354 0.0202205476 0.0415501706 0.0094817866 0.7006360000 95067238 95654128 1787895808 -0.2487473488 0.0329566672 -0.3441537619 568 22.6800000000 0.0380479395 0.0202519339 0.0415501706 0.0094798809 0.9760830000 95067672 95654128 1784467456 -0.2489680499 0.0311583187 -0.3448414207 569 22.7200000000 0.0379256196 0.0202829948 0.0415501706 0.0094850469 1.4653120000 95069506 95654128 1785737216 -0.2490197867 0.0304327756 -0.3451650143 570 22.7600000000 0.0373480283 0.0203129335 0.0415501706 0.0094862695 2.2219020000 95071200 95654128 1787641856 -0.2487268299 0.0290460140 -0.3451871574 571 22.8000000000 0.0371127911 0.0203423553 0.0415501706 0.0094902370 0.8449150000 95071634 95654128 1784713216 -0.2487019300 0.0273130629 -0.3458528221 572 22.8400000000 0.0367625840 0.0203710620 0.0415501706 0.0094968973 0.7605340000 95073328 95654128 1785982976 -0.2483158410 0.0262365304 -0.3462843597 573 22.8800000000 0.0373102129 0.0204006242 0.0415501706 0.0094948640 0.7127560000 95076966 95654128 1787650048 -0.2493584156 0.0250773542 -0.3473435640 574 22.9200000000 0.0379210524 0.0204311476 0.0415501706 0.0094945096 0.6488970000 95246116 95654128 1784705024 -0.2499532998 0.0232557468 -0.3488788009 575 22.9600000000 0.0389472097 0.0204633494 0.0415501706 0.0094967059 0.7873680000 95247950 95654128 1786101760 -0.2512348294 0.0222142842 -0.3502321839 576 23.0000000000 0.0395547338 0.0204964942 0.0415501706 0.0095025581 0.8220470000 95248384 95654128 1787887616 -0.2522636950 0.0210211910 -0.3514304757 577 23.0400000000 0.0395417735 0.0205295016 0.0415501706 0.0095079404 0.7292120000 95250078 95654128 1784745984 -0.2517487705 0.0190215483 -0.3520591855 578 23.0800000000 0.0396624096 0.0205626035 0.0415501706 0.0095181669 0.7400290000 95251772 95654128 1786109952 -0.2519279420 0.0190849863 -0.3528464437 579 23.1200000000 0.0400153808 0.0205962007 0.0415501706 0.0095213272 0.7485740000 95252206 95654128 1787887616 -0.2519811392 0.0178975519 -0.3528738618 580 23.1600000000 0.0400604680 0.0206297598 0.0415501706 0.0095233818 0.7410310000 95253900 95654128 1784713216 -0.2517945468 0.0154139269 -0.3528325558 581 23.2000000000 0.0396500044 0.0206624969 0.0415501706 0.0095240454 0.7241340000 95255734 95654128 1786126336 -0.2510558963 0.0127249286 -0.3528892994 582 23.2400000000 0.0395528004 0.0206949545 0.0415501706 0.0095247748 0.7059280000 95256168 95654128 1787887616 -0.2502047122 0.0115100415 -0.3535658121 583 23.2800000000 0.0395096578 0.0207272267 0.0415501706 0.0095309202 0.8536300000 95257862 95654128 1784713216 -0.2495055795 0.0117608141 -0.3543790281 584 23.3200000000 0.0398231223 0.0207599251 0.0415501706 0.0095311667 0.7244870000 95262152 95654128 1786109952 -0.2504038215 0.0108526070 -0.3548076153 585 23.3600000000 0.0400276519 0.0207928614 0.0415501706 0.0095425214 0.7605510000 95431258 95654128 1785729024 -0.2502463162 0.0113075115 -0.3553393781 586 23.4000000000 0.0397685841 0.0208252432 0.0415501706 0.0095574212 0.7074420000 95432952 95654128 1787015168 -0.2496231496 0.0115849469 -0.3554269671 587 23.4400000000 0.0396488309 0.0208573106 0.0415501706 0.0095605638 0.7740560000 95434786 95654128 1784586240 -0.2493610978 0.0105096465 -0.3558190763 588 23.4800000000 0.0392744094 0.0208886322 0.0415501706 0.0095673684 0.8365870000 95435220 95654128 1785856000 -0.2484080642 0.0109639559 -0.3554788530 589 23.5200000000 0.0390220210 0.0209194190 0.0415501706 0.0095755496 0.9647900000 95436914 95654128 1787887616 -0.2481906116 0.0118384063 -0.3557836711 590 23.5600000000 0.0385713130 0.0209493374 0.0415501706 0.0095804204 0.6973960000 95438608 95654128 1784840192 -0.2475984246 0.0119052930 -0.3559238315 591 23.6000000000 0.0382269397 0.0209785720 0.0415501706 0.0095797650 0.7507630000 95439042 95654128 1786126336 -0.2471244782 0.0103102233 -0.3555116951 592 23.6400000000 0.0383239426 0.0210078716 0.0415501706 0.0095883142 0.6748610000 95440736 95654128 1788014592 -0.2472581267 0.0087255519 -0.3557528555 593 23.6800000000 0.0382417105 0.0210369337 0.0415501706 0.0095948716 0.7606140000 95441310 95654128 1784475648 -0.2475047857 0.0094628166 -0.3562433422 594 23.7200000000 0.0383375734 0.0210660593 0.0415501706 0.0095922317 0.6672000000 95443004 95654128 1785872384 -0.2474267185 0.0086871153 -0.3563160896 595 23.7600000000 0.0383535847 0.0210951140 0.0415501706 0.0095940507 0.7429840000 95444698 95654128 1787887616 -0.2476484776 0.0080804825 -0.3567769825 596 23.8000000000 0.0385153964 0.0211243427 0.0415501706 0.0095989756 0.7491710000 95447180 95654128 1784713216 -0.2487406433 0.0079766698 -0.3575015664 597 23.8400000000 0.0388151780 0.0211539756 0.0415501706 0.0095984892 0.6647290000 95617582 95654128 1785982976 -0.2490905821 0.0084852790 -0.3575929701 598 23.8800000000 0.0389364995 0.0211837122 0.0415501706 0.0095948111 0.6729640000 95619276 95654128 1788268544 -0.2495144308 0.0067978483 -0.3581711948 599 23.9200000000 0.0379184596 0.0212116500 0.0415501706 0.0095893227 0.8102900000 95619850 95654128 1784205312 -0.2479895353 0.0050888117 -0.3574037850 600 23.9600000000 0.0372792892 0.0212384294 0.0415501706 0.0095846138 0.7493500000 95621544 95654128 1785610240 -0.2469143122 0.0044971420 -0.3569920063 601 24.0000000000 0.0366474800 0.0212640685 0.0415501706 0.0095816367 0.6829650000 95623238 95654128 1787387904 -0.2463514060 0.0034991484 -0.3571438491 602 24.0400000000 0.0359346643 0.0212884382 0.0415501706 0.0095839208 0.8175020000 95623672 95654128 1784516608 -0.2455002069 0.0036876788 -0.3570197523 603 24.0800000000 0.0352983400 0.0213116719 0.0415501706 0.0095932582 0.7277520000 95625366 95654128 1785864192 -0.2449158579 0.0031112921 -0.3572609127 604 24.1200000000 0.0354453586 0.0213350720 0.0415501706 0.0095952907 0.7814200000 95627060 95654128 1787768832 -0.2448763102 0.0021195970 -0.3568465710 605 24.1600000000 0.0353586674 0.0213582515 0.0415501706 0.0095930145 0.7126230000 95627634 95654128 1784594432 -0.2453234941 0.0018509553 -0.3573821187 606 24.2000000000 0.0348162800 0.0213804595 0.0415501706 0.0095863004 0.7364620000 95629328 95654128 1786118144 -0.2441990823 -0.0008261878 -0.3571425080 607 24.2400000000 0.0338325240 0.0214009736 0.0415501706 0.0095801757 0.9146800000 95631022 95654128 1787895808 -0.2420544773 -0.0016526406 -0.3560123146 608 24.2800000000 0.0344283506 0.0214224002 0.0415501706 0.0095726729 0.6363350000 95631456 95654128 1785278464 -0.2420741618 -0.0032538925 -0.3558379412 609 24.3200000000 0.0334166102 0.0214420951 0.0415501706 0.0095663007 0.6818030000 95633150 95654128 1786753024 -0.2410976589 -0.0046408586 -0.3551534414 610 24.3600000000 0.0331910327 0.0214613557 0.0415501706 0.0095657089 0.7568590000 95634844 95654128 1784967168 -0.2407848984 -0.0045744125 -0.3555712700 611 24.4000000000 0.0329411477 0.0214801442 0.0415501706 0.0095599662 0.7323570000 95635418 95654128 1786744832 -0.2401990741 -0.0061278380 -0.3555001318 612 24.4400000000 0.0329886712 0.0214989490 0.0415501706 0.0095591613 0.6757690000 95639248 95654128 1785094144 -0.2409004569 -0.0048593744 -0.3565222025 613 24.4800000000 0.0329661854 0.0215176557 0.0415501706 0.0095537090 1.0608050000 95808298 95654128 1786998784 -0.2393316925 -0.0046387785 -0.3555858731 614 24.5200000000 0.0337259173 0.0215375389 0.0415501706 0.0095461769 1.5965800000 95809992 95654128 1785094144 -0.2410620898 -0.0042173732 -0.3568564653 615 24.5600000000 0.0333854929 0.0215568039 0.0415501706 0.0095387912 1.8700280000 95811686 95654128 1786490880 -0.2406739742 -0.0070654610 -0.3566169143 616 24.6000000000 0.0331420675 0.0215756111 0.0415501706 0.0095357748 1.8826190000 95812120 95654128 1785856000 -0.2398815751 -0.0101563595 -0.3563247025 617 24.6400000000 0.0333225615 0.0215946499 0.0415501706 0.0095370442 0.8594670000 95813954 95654128 1787506688 -0.2397052795 -0.0111625995 -0.3565976620 618 24.6800000000 0.0332978219 0.0216135871 0.0415501706 0.0095369015 0.8654820000 95815648 95654128 1785348096 -0.2391767055 -0.0112823304 -0.3565547168 619 24.7200000000 0.0325288363 0.0216312208 0.0415501706 0.0095532259 0.7017920000 95816082 95654128 1786871808 -0.2385067195 -0.0103441691 -0.3576170802 620 24.7600000000 0.0325132646 0.0216487725 0.0415501706 0.0095568663 0.6940740000 95817776 95654128 1785094144 -0.2379603237 -0.0099414624 -0.3581530452 621 24.8000000000 0.0324714556 0.0216662003 0.0415501706 0.0095501426 0.6809010000 95819470 95654128 1786503168 -0.2377808392 -0.0107182600 -0.3596024811 622 24.8400000000 0.0321226679 0.0216830113 0.0415501706 0.0095427239 0.7475850000 95819904 95654128 1785856000 -0.2369101495 -0.0094719511 -0.3599329889 623 24.8800000000 0.0319564752 0.0216995017 0.0415501706 0.0095359655 0.9615130000 95821738 95654128 1787379712 -0.2345133871 -0.0097954758 -0.3577636480 624 24.9200000000 0.0323628262 0.0217165903 0.0415501706 0.0095286528 0.7597600000 95823432 95654128 1785094144 -0.2347189635 -0.0102077946 -0.3582897484 625 24.9600000000 0.0320761539 0.0217331656 0.0415501706 0.0095233617 0.6932540000 95823866 95654128 1786617856 -0.2334330380 -0.0087496564 -0.3583963513 626 25.0000000000 0.0323690213 0.0217501558 0.0415501706 0.0095160036 0.7482700000 95825560 95654128 1785786368 -0.2325448990 -0.0079985280 -0.3582586944 627 25.0400000000 0.0324944742 0.0217672919 0.0415501706 0.0095092183 0.8772800000 95827254 95654128 1787506688 -0.2308846414 -0.0068789949 -0.3570056558 628 25.0800000000 0.0325872861 0.0217845212 0.0415501706 0.0095047757 0.8273580000 95827688 95654128 1784840192 -0.2295722812 -0.0063219350 -0.3570164740 629 25.1200000000 0.0331777297 0.0218026344 0.0415501706 0.0094981022 0.6967660000 95829522 95654128 1786363904 -0.2285162956 -0.0049796342 -0.3573707044 630 25.1600000000 0.0333705395 0.0218209961 0.0415501706 0.0094950139 0.8224140000 95831816 95654128 1785729024 -0.2268750370 -0.0046929559 -0.3560817838 631 25.2000000000 0.0338603705 0.0218400760 0.0415501706 0.0094893967 0.8087870000 96002218 95654128 1787252736 -0.2249555290 -0.0055206250 -0.3547184169 632 25.2400000000 0.0345792994 0.0218602330 0.0415501706 0.0094823630 0.8315120000 96003912 95654128 1784864768 -0.2226034999 -0.0055067190 -0.3526894450 633 25.2800000000 0.0343843102 0.0218800182 0.0415501706 0.0094748808 0.6433160000 96004346 95654128 1786363904 -0.2214320153 -0.0041539310 -0.3534001112 634 25.3200000000 0.0340059660 0.0218991443 0.0415501706 0.0094689562 0.6127910000 96006040 95654128 1788141568 -0.2194313407 -0.0041278577 -0.3532513976 635 25.3600000000 0.0338102505 0.0219179020 0.0415501706 0.0094630645 0.7063390000 96007874 95654128 1784905728 -0.2174586952 -0.0038112057 -0.3528694510 636 25.4000000000 0.0338425562 0.0219366514 0.0415501706 0.0094571530 0.7709050000 96008308 95654128 1786236928 -0.2163884193 -0.0044130459 -0.3539284766 637 25.4400000000 0.0330395512 0.0219540814 0.0415501706 0.0094507470 0.8627880000 96010002 95654128 1788141568 -0.2139699608 -0.0043669427 -0.3545755446 638 25.4800000000 0.0338382199 0.0219727086 0.0415501706 0.0094477034 0.7199760000 96011696 95654128 1784713216 -0.2116185427 -0.0039319578 -0.3518860042 639 25.5200000000 0.0334990621 0.0219907467 0.0415501706 0.0094403685 0.7086040000 96012130 95654128 1786126336 -0.2088171393 -0.0041067344 -0.3517127335 640 25.5600000000 0.0333417878 0.0220084827 0.0415501706 0.0094335778 0.7705700000 96013824 95654128 1788141568 -0.2071722895 -0.0040818257 -0.3522690535 641 25.6000000000 0.0324584134 0.0220247853 0.0415501706 0.0094277736 0.7481490000 96015658 95654128 1784594432 -0.2051330507 -0.0054346872 -0.3542816341 642 25.6400000000 0.0320546329 0.0220404081 0.0415501706 0.0094219259 0.6146720000 96016092 95654128 1785864192 -0.2027525902 -0.0059137349 -0.3543907404 643 25.6800000000 0.0322397910 0.0220562703 0.0415501706 0.0094164079 0.7120300000 96017786 95654128 1787768832 -0.1985874176 -0.0050713909 -0.3516284525 644 25.7200000000 0.0319862552 0.0220716895 0.0415501706 0.0094097964 0.7079710000 96019480 95654128 1784594432 -0.1958650500 -0.0052888263 -0.3509564400 645 25.7600000000 0.0314249210 0.0220861906 0.0415501706 0.0094027218 0.8291890000 96019914 95654128 1785864192 -0.1929878742 -0.0067692692 -0.3508455455 646 25.8000000000 0.0316573903 0.0221010067 0.0415501706 0.0093979249 0.8241420000 96021608 95654128 1787768832 -0.1907007247 -0.0047069746 -0.3501664400 647 25.8400000000 0.0320954621 0.0221164541 0.0415501706 0.0093908072 0.8572640000 96022182 95654128 1784594432 -0.1882714480 -0.0030574806 -0.3489256203 648 25.8800000000 0.0318732671 0.0221315109 0.0415501706 0.0093849895 0.7222580000 96025420 95654128 1785880576 -0.1864634454 -0.0046694996 -0.3489436805 649 25.9200000000 0.0318531692 0.0221464904 0.0415501706 0.0093781725 0.8345960000 96195858 95654128 1787895808 -0.1834961176 -0.0061554220 -0.3481440842 650 25.9600000000 0.0315146744 0.0221609029 0.0415501706 0.0093716504 0.7076370000 96196292 95654128 1784721408 -0.1804670095 -0.0063422215 -0.3476171196 651 26.0000000000 0.0313905105 0.0221750805 0.0415501706 0.0093644527 0.7153520000 96197986 95654128 1785991168 -0.1779249310 -0.0060557881 -0.3472588956 652 26.0400000000 0.0319129899 0.0221900160 0.0415501706 0.0093588173 0.7014530000 96199680 95654128 1787760640 -0.1747914851 -0.0069959350 -0.3458440602 653 26.0800000000 0.0318025872 0.0222047366 0.0415501706 0.0093519258 0.8072690000 96200254 95654128 1784586240 -0.1723629087 -0.0058021243 -0.3453999162 654 26.1200000000 0.0324581303 0.0222204146 0.0415501706 0.0093450698 0.8489030000 96201948 95654128 1785982976 -0.1668625772 -0.0049625542 -0.3426000476 655 26.1600000000 0.0321862474 0.0222356296 0.0415501706 0.0093379885 0.9608660000 96203642 95654128 1788014592 -0.1643194705 -0.0060734553 -0.3423347771 656 26.2000000000 0.0323378369 0.0222510293 0.0415501706 0.0093311043 0.7271610000 96204076 95654128 1784713216 -0.1613786817 -0.0061255242 -0.3410881758 657 26.2400000000 0.0316904746 0.0222653968 0.0415501706 0.0093242313 0.7953110000 96205770 95654128 1786109952 -0.1577039361 -0.0078883469 -0.3401963413 658 26.2800000000 0.0319401138 0.0222801000 0.0415501706 0.0093172140 0.7055630000 96207464 95654128 1788014592 -0.1552345306 -0.0085434867 -0.3394069672 659 26.3200000000 0.0320279114 0.0222948918 0.0415501706 0.0093109185 0.8607700000 96208038 95654128 1784840192 -0.1527787149 -0.0084523838 -0.3393335938 660 26.3600000000 0.0314869694 0.0223088192 0.0415501706 0.0093040205 0.5839350000 96209732 95654128 1786363904 -0.1498206854 -0.0086565185 -0.3387950659 661 26.4000000000 0.0319644958 0.0223234269 0.0415501706 0.0092974596 0.6157010000 96211426 95654128 1788141568 -0.1481950134 -0.0077097155 -0.3378218412 662 26.4400000000 0.0320944153 0.0223381867 0.0415501706 0.0092915584 0.6465440000 96211860 95654128 1784840192 -0.1451592892 -0.0103393579 -0.3373761475 663 26.4800000000 0.0325226039 0.0223535478 0.0415501706 0.0092848718 0.7711590000 96213554 95654128 1786236928 -0.1422319859 -0.0113795698 -0.3358873427 664 26.5200000000 0.0333036520 0.0223700389 0.0415501706 0.0092780282 0.8122460000 96215248 95654128 1788141568 -0.1400854290 -0.0139319003 -0.3346301615 665 26.5600000000 0.0341507941 0.0223877544 0.0415501706 0.0092727404 0.6960380000 96215822 95654128 1784647680 -0.1379375607 -0.0162370130 -0.3333917260 666 26.6000000000 0.0339792669 0.0224051590 0.0415501706 0.0092727272 0.6828290000 96217516 95654128 1785982976 -0.1354984045 -0.0165045392 -0.3331046104 667 26.6400000000 0.0349925570 0.0224240307 0.0415501706 0.0092700861 0.7822500000 96217950 95654128 1788014592 -0.1332080364 -0.0176200643 -0.3317571282 668 26.6800000000 0.0351698697 0.0224431113 0.0415501706 0.0092663706 0.8274810000 96219644 95654128 1784713216 -0.1307926923 -0.0176382549 -0.3307572007 669 26.7200000000 0.0349729396 0.0224618405 0.0415501706 0.0092620866 0.7482530000 96221338 95654128 1785999360 -0.1284664273 -0.0187006406 -0.3309605420 670 26.7600000000 0.0346908905 0.0224800928 0.0415501706 0.0092612788 0.7207410000 96221772 95654128 1787887616 -0.1265293956 -0.0189649705 -0.3318678439 671 26.8000000000 0.0348388441 0.0224985112 0.0415501706 0.0092570973 0.8946450000 96223606 95654128 1784840192 -0.1244040877 -0.0205173306 -0.3332597911 672 26.8400000000 0.0352663659 0.0225175110 0.0415501706 0.0092507932 0.7314120000 96225300 95654128 1786236928 -0.1213354543 -0.0211386513 -0.3317246437 673 26.8800000000 0.0345224552 0.0225353489 0.0415501706 0.0092551482 0.6893290000 96225734 95654128 1788268544 -0.1202561110 -0.0223618224 -0.3346140087 674 26.9200000000 0.0346872732 0.0225533785 0.0415501706 0.0092628667 0.6692090000 96228704 95654128 1784492032 -0.1180290431 -0.0236219969 -0.3363404870 675 26.9600000000 0.0347320288 0.0225714209 0.0415501706 0.0092589651 0.9587310000 96399122 95654128 1785729024 -0.1158391312 -0.0251384210 -0.3387414515 676 27.0000000000 0.0359327309 0.0225911862 0.0415501706 0.0092526093 0.8322090000 96399556 95654128 1787887616 -0.1136361882 -0.0288388338 -0.3387717307 677 27.0400000000 0.0362076350 0.0226112991 0.0415501706 0.0092491631 0.6649820000 96401390 95654128 1784713216 -0.1102250889 -0.0291548036 -0.3387073576 678 27.0800000000 0.0358140729 0.0226307722 0.0415501706 0.0092461041 0.9273520000 96403084 95654128 1785982976 -0.1081268489 -0.0301769301 -0.3414288461 679 27.1200000000 0.0357578993 0.0226501053 0.0415501706 0.0092440243 1.7397400000 96403518 95654128 1787895808 -0.1063056588 -0.0304916836 -0.3432291448 680 27.1600000000 0.0364830010 0.0226704478 0.0415501706 0.0092417719 1.4927240000 96405212 95654128 1784467456 -0.1035030708 -0.0315974355 -0.3445704281 681 27.2000000000 0.0360816009 0.0226901411 0.0415501706 0.0092363771 1.6667140000 96406906 95654128 1785864192 -0.1007626057 -0.0297118258 -0.3444518447 682 27.2400000000 0.0362598896 0.0227100381 0.0415501706 0.0092302480 0.9105330000 96407340 95654128 1787641856 -0.0983775109 -0.0309092216 -0.3467364907 683 27.2800000000 0.0369946882 0.0227309526 0.0415501706 0.0092242787 0.8433420000 96409174 95654128 1784606720 -0.0953045115 -0.0316813476 -0.3469917774 684 27.3200000000 0.0371098705 0.0227519745 0.0415501706 0.0092177940 0.6827040000 96409608 95654128 1785991168 -0.0918027386 -0.0320096202 -0.3477553725 685 27.3600000000 0.0369407721 0.0227726880 0.0415501706 0.0092111168 0.8395400000 96411302 95654128 1787887616 -0.0894014612 -0.0332283899 -0.3488152623 686 27.4000000000 0.0367750041 0.0227930996 0.0415501706 0.0092098414 0.8078480000 96412996 95654128 1784713216 -0.0861370564 -0.0341077894 -0.3500324786 687 27.4400000000 0.0374747440 0.0228144702 0.0415501706 0.0092101502 0.9341160000 96413430 95654128 1786109952 -0.0835190117 -0.0342225991 -0.3514543176 688 27.4800000000 0.0376609489 0.0228360494 0.0415501706 0.0092096298 0.7874010000 96415124 95654128 1788014592 -0.0805234686 -0.0351570174 -0.3539416492 689 27.5200000000 0.0383054018 0.0228585013 0.0415501706 0.0092084111 0.7689440000 96416958 95654128 1784741888 -0.0776367188 -0.0367702357 -0.3559145331 690 27.5600000000 0.0391887240 0.0228821683 0.0415501706 0.0092105125 0.8144950000 96417392 95654128 1786109952 -0.0747058615 -0.0368064605 -0.3578479886 691 27.6000000000 0.0398053601 0.0229066592 0.0415501706 0.0092038760 0.7254070000 96419086 95654128 1788014592 -0.0712142661 -0.0363141522 -0.3593046665 692 27.6400000000 0.0397220887 0.0229309589 0.0415501706 0.0091996906 0.6461690000 96420780 95654128 1784713216 -0.0689340904 -0.0346486419 -0.3614145517 693 27.6800000000 0.0401325561 0.0229557808 0.0415501706 0.0091968038 0.7752130000 96421214 95654128 1786126336 -0.0656632110 -0.0354107320 -0.3622375429 694 27.7200000000 0.0407467932 0.0229814163 0.0415501706 0.0091903758 0.8087910000 96422908 95654128 1788014592 -0.0619567148 -0.0372080766 -0.3639897704 695 27.7600000000 0.0419822000 0.0230087556 0.0419822000 0.0091840921 0.6188330000 96424742 95654128 1784586240 -0.0597000122 -0.0394727290 -0.3661891818 696 27.8000000000 0.0430734120 0.0230375841 0.0430734120 0.0091785913 0.7331030000 96425176 95654128 1785856000 -0.0569511764 -0.0407931618 -0.3669146895 697 27.8400000000 0.0435316749 0.0230669874 0.0435316749 0.0091758266 0.7086370000 96426870 95654128 1787887616 -0.0526145324 -0.0399813242 -0.3726172149 698 27.8800000000 0.0430616289 0.0230956330 0.0435316749 0.0091693758 0.7137570000 96428564 95654128 1784840192 -0.0504439101 -0.0397177339 -0.3741191030 699 27.9200000000 0.0432059728 0.0231244032 0.0435316749 0.0091871045 0.8403920000 96428998 95654128 1786109952 -0.0465230159 -0.0401422232 -0.3788478971 700 27.9600000000 0.0426275991 0.0231522649 0.0435316749 0.0091819886 0.7519940000 96430692 95654128 1788014592 -0.0445000567 -0.0407026410 -0.3819859028 701 28.0000000000 0.0421707891 0.0231793954 0.0435316749 0.0091794958 0.8071600000 96431266 95654128 1784619008 -0.0426326431 -0.0411989279 -0.3839915693 702 28.0400000000 0.0431446694 0.0232078360 0.0435316749 0.0091830672 0.8013280000 96432960 95654128 1785856000 -0.0413461812 -0.0437140018 -0.3862196803 703 28.0800000000 0.0443557501 0.0232379184 0.0443557501 0.0091968658 0.7760500000 96434654 95654128 1787760640 -0.0395383164 -0.0447125658 -0.3876802623 704 28.1200000000 0.0453184769 0.0232692828 0.0453184769 0.0092004308 0.7803450000 96435088 95654128 1784459264 -0.0375971198 -0.0460452735 -0.3895396888 705 28.1600000000 0.0450349078 0.0233001560 0.0453184769 0.0092014329 0.7463470000 96436782 95654128 1785856000 -0.0349317193 -0.0462309495 -0.3896194100 706 28.2000000000 0.0452640764 0.0233312664 0.0453184769 0.0092071609 0.9329160000 96438476 95654128 1787760640 -0.0331716426 -0.0464909039 -0.3907536566 707 28.2400000000 0.0464519076 0.0233639689 0.0464519076 0.0092116492 1.6434250000 96439050 95654128 1784459264 -0.0317051038 -0.0474310815 -0.3933545947 708 28.2800000000 0.0472688042 0.0233977328 0.0472688042 0.0092060962 1.5886800000 96440744 95654128 1785856000 -0.0302122049 -0.0481341258 -0.3958543539 709 28.3200000000 0.0467903912 0.0234307266 0.0472688042 0.0091996914 2.0964320000 96442438 95654128 1787760640 -0.0287029296 -0.0482330061 -0.3975237608 710 28.3600000000 0.0472678430 0.0234643000 0.0472688042 0.0091975683 1.7713720000 96442872 95654128 1784586240 -0.0262447726 -0.0499326810 -0.3988437057 711 28.4000000000 0.0483635925 0.0234993201 0.0483635925 0.0091945214 2.0717580000 96444566 95654128 1785982976 -0.0238874890 -0.0509865321 -0.4004360735 712 28.4400000000 0.0488240719 0.0235348886 0.0488240719 0.0091882412 0.8473730000 96448248 95654128 1787887616 -0.0225584842 -0.0521216989 -0.4019530416 713 28.4800000000 0.0479784571 0.0235691713 0.0488240719 0.0091856500 0.7514220000 96617566 95654128 1784856576 -0.0216518566 -0.0511231683 -0.4044779837 714 28.5200000000 0.0467380509 0.0236016207 0.0488240719 0.0091878419 0.8698230000 96619260 95654128 1786118144 -0.0200594142 -0.0477914140 -0.4063727260 715 28.5600000000 0.0470917001 0.0236344740 0.0488240719 0.0091842617 0.7051020000 96620954 95654128 1785483264 -0.0178993866 -0.0471636318 -0.4088854790 716 28.6000000000 0.0465796739 0.0236665203 0.0488240719 0.0091792835 0.7554780000 96621388 95654128 1786880000 -0.0148030845 -0.0456117317 -0.4080454409 717 28.6400000000 0.0476672314 0.0236999941 0.0488240719 0.0091763222 0.7649380000 96623082 95654128 1784594432 -0.0130418418 -0.0474912152 -0.4107352197 718 28.6800000000 0.0475295447 0.0237331829 0.0488240719 0.0091704120 0.7893770000 96624776 95654128 1785880576 -0.0112716435 -0.0468180291 -0.4131091237 719 28.7200000000 0.0497658066 0.0237693896 0.0497658066 0.0091658102 0.7647960000 96625350 95654128 1787768832 -0.0091290893 -0.0507040322 -0.4155315459 720 28.7600000000 0.0514863841 0.0238078855 0.0514863841 0.0091627271 0.9065410000 96627044 95654128 1784586240 -0.0065865391 -0.0531499945 -0.4161719382 721 28.8000000000 0.0524258204 0.0238475775 0.0524258204 0.0091659192 0.7504720000 96627478 95654128 1785856000 -0.0041241436 -0.0524547920 -0.4176545143 722 28.8400000000 0.0525180362 0.0238872872 0.0525180362 0.0091598606 0.8664120000 96629172 95654128 1787760640 -0.0003890016 -0.0524239168 -0.4166164100 723 28.8800000000 0.0538274013 0.0239286982 0.0538274013 0.0091541411 0.7884630000 96630866 95654128 1784586240 0.0017685122 -0.0529021397 -0.4174066484 724 28.9200000000 0.0545665920 0.0239710157 0.0545665920 0.0091483348 0.8129200000 96631300 95654128 1785872384 0.0038877660 -0.0522609763 -0.4180579484 725 28.9600000000 0.0567495748 0.0240162275 0.0567495748 0.0091428721 0.8480290000 96633134 95654128 1787887616 0.0069633708 -0.0550051481 -0.4182803631 726 29.0000000000 0.0576776005 0.0240625931 0.0576776005 0.0091375998 0.8049570000 96634828 95654128 1784713216 0.0102095567 -0.0565723516 -0.4175503552 727 29.0400000000 0.0573937930 0.0241084407 0.0576776005 0.0091379113 0.7276290000 96635262 95654128 1785982976 0.0143448673 -0.0553794689 -0.4155418575 728 29.0800000000 0.0584572293 0.0241556231 0.0584572293 0.0091324442 0.7721310000 96636956 95654128 1788014592 0.0171303749 -0.0549744740 -0.4157039821 729 29.1200000000 0.0594712980 0.0242040671 0.0594712980 0.0091263409 0.8701340000 96638650 95654128 1784619008 0.0201375112 -0.0566122532 -0.4141100645 730 29.1600000000 0.0603801534 0.0242536233 0.0603801534 0.0091285890 0.7843100000 96639084 95654128 1785856000 0.0234539900 -0.0581074245 -0.4127650261 731 29.2000000000 0.0607471243 0.0243035460 0.0607471243 0.0091344395 0.7235450000 96640918 95654128 1787506688 0.0269203894 -0.0575508140 -0.4114386737 732 29.2400000000 0.0607142113 0.0243532874 0.0607471243 0.0091327934 0.8724340000 96642612 95654128 1784586240 0.0313902050 -0.0583932921 -0.4091858268 733 29.2800000000 0.0605087839 0.0244026128 0.0607471243 0.0091302184 0.7215330000 96643046 95654128 1785982976 0.0360312089 -0.0590325594 -0.4068062603 734 29.3200000000 0.0605213195 0.0244518208 0.0607471243 0.0091257959 0.8476240000 96644740 95654128 1787887616 0.0397108831 -0.0589440539 -0.4049382508 735 29.3600000000 0.0598093979 0.0244999264 0.0607471243 0.0091202929 0.8909170000 96646434 95654128 1784750080 0.0434874818 -0.0586876422 -0.4024625123 736 29.4000000000 0.0597515814 0.0245478226 0.0607471243 0.0091147500 0.9552110000 96646868 95654128 1786109952 0.0472685136 -0.0597212017 -0.4004108608 737 29.4400000000 0.0598121807 0.0245956711 0.0607471243 0.0091108941 1.5350890000 96648702 95654128 1787887616 0.0501722433 -0.0598384999 -0.3991776705 738 29.4800000000 0.0597099513 0.0246432515 0.0607471243 0.0091066057 0.8837950000 96649136 95654128 1784713216 0.0532159247 -0.0593547747 -0.3977396190 739 29.5200000000 0.0594440475 0.0246903432 0.0607471243 0.0091008241 0.6273120000 96650830 95654128 1786126336 0.0563083254 -0.0599302202 -0.3958057761 740 29.5600000000 0.0618900135 0.0247406130 0.0618900135 0.0090982488 0.6901540000 96654276 95654128 1787887616 0.0573254675 -0.0629336759 -0.3961045444 741 29.6000000000 0.0643512234 0.0247940686 0.0643512234 0.0091026908 0.8091510000 96823410 95654128 1784713216 0.0584119186 -0.0654191002 -0.3956935406 742 29.6400000000 0.0653608516 0.0248487409 0.0653608516 0.0091056396 0.7468430000 96825104 95654128 1786109952 0.0599541068 -0.0653742924 -0.3954316974 743 29.6800000000 0.0658782870 0.0249039623 0.0658782870 0.0091026641 0.7129680000 96826938 95654128 1787887616 0.0626761094 -0.0663226992 -0.3944663107 744 29.7200000000 0.0649602115 0.0249578014 0.0658782870 0.0090985983 0.8342320000 96827372 95654128 1784856576 0.0652279779 -0.0655661300 -0.3932254612 745 29.7600000000 0.0659944564 0.0250128841 0.0659944564 0.0090944590 0.7411960000 96829066 95654128 1786109952 0.0676243678 -0.0662954599 -0.3926375210 746 29.8000000000 0.0663018376 0.0250682313 0.0663018376 0.0090902841 0.7479750000 96830760 95654128 1788141568 0.0683386922 -0.0648750812 -0.3926075995 747 29.8400000000 0.0652370527 0.0251220048 0.0663018376 0.0090896913 0.6942900000 96831194 95654128 1784745984 0.0696819127 -0.0641757548 -0.3912937939 748 29.8800000000 0.0655570477 0.0251760623 0.0663018376 0.0090973283 0.7881120000 96832888 95654128 1785999360 0.0738182068 -0.0646357685 -0.3895376623 749 29.9200000000 0.0653802380 0.0252297395 0.0663018376 0.0090915774 0.7371940000 96834722 95654128 1787887616 0.0749641210 -0.0629643127 -0.3896869123 750 29.9600000000 0.0665557310 0.0252848408 0.0665557310 0.0090867608 0.8740830000 96835156 95654128 1784840192 0.0766168237 -0.0646211058 -0.3888858855 751 30.0000000000 0.0681939796 0.0253419768 0.0681939796 0.0090812508 0.7270440000 96836850 95654128 1786109952 0.0779521316 -0.0657610819 -0.3885668814 752 30.0400000000 0.0680990145 0.0253988345 0.0681939796 0.0090774002 0.7493690000 96838544 95654128 1788014592 0.0794929191 -0.0646916330 -0.3883138597 753 30.0800000000 0.0688028708 0.0254564760 0.0688028708 0.0090735480 0.7665980000 96838978 95654128 1784619008 0.0797838047 -0.0645402446 -0.3891226947 754 30.1200000000 0.0684145465 0.0255134496 0.0688028708 0.0090678841 0.9898140000 96840672 95654128 1785856000 0.0819046795 -0.0637454242 -0.3887678385 755 30.1600000000 0.0687646568 0.0255707360 0.0688028708 0.0090624803 0.7670030000 96841246 95654128 1787887616 0.0835868195 -0.0642205030 -0.3883585334 756 30.2000000000 0.0687413365 0.0256278399 0.0688028708 0.0090568604 0.8435560000 96842940 95654128 1784975360 0.0853541568 -0.0653229803 -0.3872898817 757 30.2400000000 0.0694894716 0.0256857813 0.0694894716 0.0090571953 0.8014430000 96844634 95654128 1786118144 0.0865684375 -0.0666054562 -0.3867602348 758 30.2800000000 0.0708832964 0.0257454086 0.0708832964 0.0090745683 0.8359440000 96845068 95654128 1787768832 0.0874422342 -0.0672928840 -0.3868715465 759 30.3200000000 0.0726532862 0.0258072109 0.0726532862 0.0090846135 0.6925300000 96846762 95654128 1784623104 0.0894986838 -0.0690818429 -0.3865471482 760 30.3600000000 0.0733806863 0.0258698075 0.0733806863 0.0090889426 0.7471670000 96848456 95654128 1785991168 0.0909033492 -0.0696723983 -0.3861772120 761 30.4000000000 0.0748553202 0.0259341775 0.0748553202 0.0090987351 0.8186680000 96849030 95654128 1787768832 0.0916609988 -0.0707894191 -0.3866506517 762 30.4400000000 0.0770072564 0.0260012025 0.0770072564 0.0091135369 0.7180150000 96850724 95654128 1784594432 0.0927046612 -0.0722741410 -0.3863841295 763 30.4800000000 0.0774752796 0.0260686652 0.0774752796 0.0091267853 0.7298840000 96852418 95654128 1786007552 0.0951245129 -0.0725012422 -0.3864012361 764 30.5200000000 0.0781270787 0.0261368045 0.0781270787 0.0091370410 0.7100720000 96852852 95654128 1787768832 0.0970918164 -0.0732166991 -0.3863388896 765 30.5600000000 0.0791990310 0.0262061669 0.0791990310 0.0091552246 0.8080140000 96854546 95654128 1784713216 0.0988047197 -0.0743278638 -0.3861063421 766 30.6000000000 0.0800622106 0.0262764751 0.0800622106 0.0091723646 0.6963480000 96856240 95654128 1785982976 0.1006876826 -0.0740722939 -0.3862533867 767 30.6400000000 0.0816517472 0.0263486723 0.0816517472 0.0091735706 0.8190230000 96856814 95654128 1788014592 0.1020154357 -0.0743712857 -0.3868769109 768 30.6800000000 0.0826435536 0.0264219729 0.0826435536 0.0091720723 0.7925850000 96860444 95654128 1784750080 0.1038088575 -0.0757095367 -0.3866056502 769 30.7200000000 0.0852799341 0.0264985112 0.0852799341 0.0091736161 0.6851870000 97030842 95654128 1786109952 0.1046274975 -0.0774921328 -0.3873456419 770 30.7600000000 0.0853585750 0.0265749529 0.0853585750 0.0091702471 0.7591760000 97031276 95654128 1788014592 0.1064450890 -0.0767555907 -0.3878121674 771 30.8000000000 0.0863217264 0.0266524454 0.0863217264 0.0091643426 0.7539280000 97032970 95654128 1784872960 0.1074008942 -0.0778836533 -0.3881690502 772 30.8400000000 0.0872463584 0.0267309350 0.0872463584 0.0091682707 0.6149010000 97034664 95654128 1786109952 0.1085546911 -0.0787512511 -0.3884905279 773 30.8800000000 0.0882330388 0.0268104978 0.0882330388 0.0091684051 0.7807230000 97035238 95654128 1788141568 0.1103132293 -0.0790502802 -0.3889229298 774 30.9200000000 0.0879803523 0.0268895287 0.0882330388 0.0091634190 0.7110690000 97036932 95654128 1784713216 0.1115829721 -0.0780237392 -0.3894059956 775 30.9600000000 0.0874500126 0.0269676712 0.0882330388 0.0091580639 0.9178180000 97037366 95654128 1785982976 0.1129797250 -0.0767367184 -0.3897209466 776 31.0000000000 0.0885168314 0.0270469872 0.0885168314 0.0091566019 0.7801170000 97039060 95654128 1787887616 0.1137673631 -0.0773292631 -0.3895532787 777 31.0400000000 0.0893014222 0.0271271087 0.0893014222 0.0091537401 0.7675480000 97040754 95654128 1784713216 0.1149912551 -0.0783177316 -0.3895161152 778 31.0800000000 0.0891525745 0.0272068329 0.0893014222 0.0091488022 1.0013810000 97041188 95654128 1785982976 0.1170130968 -0.0776181445 -0.3898144960 779 31.1200000000 0.0885258913 0.0272855480 0.0893014222 0.0091617302 0.7374860000 97043022 95654128 1788014592 0.1185912043 -0.0763538107 -0.3901383579 780 31.1600000000 0.0885754377 0.0273641248 0.0893014222 0.0091985757 0.7564520000 97044716 95654128 1784713216 0.1185077578 -0.0749673992 -0.3904940784 781 31.2000000000 0.0880992487 0.0274418907 0.0893014222 0.0092389659 0.8169320000 97045150 95654128 1785999360 0.1206346676 -0.0754514560 -0.3904926181 782 31.2400000000 0.0882227942 0.0275196156 0.0893014222 0.0092738350 0.7037660000 97046844 95654128 1787887616 0.1213356927 -0.0750209317 -0.3910701275 783 31.2800000000 0.0879899859 0.0275968447 0.0893014222 0.0093063320 0.7561260000 97048538 95654128 1784492032 0.1220401675 -0.0745923445 -0.3914809227 784 31.3200000000 0.0874056444 0.0276731314 0.0893014222 0.0093212055 1.0001920000 97048972 95654128 1785856000 0.1231585741 -0.0744232014 -0.3918989003 785 31.3600000000 0.0870168731 0.0277487285 0.0893014222 0.0093191623 0.8092080000 97050806 95654128 1787633664 0.1234972104 -0.0737718269 -0.3922567666 786 31.4000000000 0.0874150097 0.0278246398 0.0893014222 0.0093135133 0.7102150000 97052500 95654128 1784586240 0.1238335595 -0.0728681087 -0.3930153251 787 31.4400000000 0.0894461647 0.0279029391 0.0894461647 0.0093156344 0.8196450000 97052934 95654128 1785999360 0.1225846410 -0.0728462785 -0.3940551579 788 31.4800000000 0.0882483050 0.0279795195 0.0894461647 0.0093165554 0.8159650000 97054628 95654128 1787887616 0.1241433844 -0.0713663399 -0.3944850564 789 31.5200000000 0.0876814947 0.0280551874 0.0894461647 0.0093210526 0.6584110000 97056322 95654128 1784713216 0.1257002503 -0.0700504407 -0.3947734833 790 31.5600000000 0.0869680569 0.0281297607 0.0894461647 0.0093523159 0.8143030000 97056756 95654128 1786109952 0.1278115064 -0.0696086138 -0.3948351145 791 31.6000000000 0.0880246535 0.0282054812 0.0894461647 0.0093930409 0.8087740000 97058590 95654128 1787887616 0.1291503757 -0.0713426918 -0.3948526084 792 31.6400000000 0.0867183656 0.0282793611 0.0894461647 0.0094010849 0.6135490000 97059024 95654128 1784725504 0.1308160275 -0.0695365369 -0.3949718177 793 31.6800000000 0.0871313363 0.0283535754 0.0894461647 0.0094119966 0.6699590000 97060718 95654128 1786109952 0.1316494197 -0.0694852769 -0.3950384855 794 31.7200000000 0.0870808959 0.0284275393 0.0894461647 0.0094327403 0.7707200000 97062412 95654128 1788014592 0.1326292902 -0.0683575571 -0.3959150612 795 31.7600000000 0.0875616744 0.0285019218 0.0894461647 0.0094669285 0.8467400000 97062846 95654128 1784647680 0.1339269578 -0.0691129267 -0.3955171704 796 31.8000000000 0.0878522918 0.0285764826 0.0894461647 0.0095040914 0.8895960000 97064540 95654128 1785982976 0.1349566579 -0.0690221786 -0.3955250382 797 31.8400000000 0.0880685672 0.0286511276 0.0894461647 0.0095936986 0.7452000000 97066374 95654128 1787760640 0.1364133060 -0.0690919608 -0.3949629366 798 31.8800000000 0.0891274065 0.0287269124 0.0894461647 0.0097051148 0.8587900000 97066808 95654128 1784840192 0.1362689883 -0.0699127540 -0.3957963288 799 31.9200000000 0.0907859653 0.0288045833 0.0907859653 0.0097671834 0.9225390000 97068502 95654128 1786109952 0.1359374672 -0.0709850267 -0.3961823285 800 31.9600000000 0.0907558426 0.0288820224 0.0907859653 0.0097862913 0.7519500000 97070196 95654128 1788149760 0.1366265863 -0.0706707090 -0.3968844116 801 32.0000000000 0.0918356329 0.0289606162 0.0918356329 0.0097925309 0.8267580000 97070630 95654128 1784340480 0.1369254887 -0.0714889020 -0.3967343569 802 32.0400000000 0.0895901769 0.0290362141 0.0918356329 0.0097963543 0.6084830000 97072324 95654128 1785626624 0.1394024938 -0.0700053647 -0.3949118555 803 32.0800000000 0.0886587128 0.0291104638 0.0918356329 0.0097960987 0.6682040000 97074158 95654128 1787641856 0.1418496221 -0.0700350031 -0.3936668336 804 32.1199999990 0.0891530588 0.0291851437 0.0918356329 0.0097966387 0.6368930000 97074592 95654128 1784467456 0.1425900459 -0.0704993680 -0.3933023512 805 32.1600000000 0.0896302089 0.0292602307 0.0918356329 0.0097997139 0.6874870000 97076286 95654128 1785753600 0.1435012370 -0.0711710304 -0.3928713799 806 32.2000000000 0.0906059742 0.0293363421 0.0918356329 0.0098007270 0.7886500000 97077980 95654128 1787641856 0.1432001740 -0.0716645792 -0.3926286995 807 32.2400000000 0.0896328241 0.0294110589 0.0918356329 0.0097965128 0.8478550000 97078414 95654128 1784594432 0.1449450105 -0.0710950717 -0.3912521899 808 32.2800000000 0.0893552154 0.0294852472 0.0918356329 0.0097921159 0.7391540000 97080108 95654128 1785864192 0.1459321678 -0.0709587559 -0.3903181851 809 32.3200000000 0.0897840858 0.0295597822 0.0918356329 0.0097886853 0.8942320000 97080682 95654128 1787641856 0.1460019052 -0.0707493275 -0.3902264237 810 32.3600000000 0.0904583782 0.0296349657 0.0918356329 0.0097856786 0.7308770000 97082376 95654128 1784340480 0.1456780285 -0.0708980709 -0.3904752731 811 32.4000000000 0.0906813070 0.0297102386 0.0918356329 0.0097801794 0.6407510000 97084070 95654128 1785729024 0.1465021819 -0.0713592917 -0.3897927105 812 32.4399999990 0.0916079655 0.0297864673 0.0918356329 0.0097741966 0.8639370000 97084504 95654128 1787633664 0.1468897909 -0.0724501908 -0.3888872564 813 32.4800000000 0.0904271156 0.0298610561 0.0918356329 0.0097692313 0.7309070000 97086198 95654128 1784586240 0.1489561349 -0.0717670023 -0.3875556290 814 32.5200000000 0.0906059518 0.0299356813 0.0918356329 0.0097655577 0.7619870000 97087892 95654128 1785999360 0.1502773464 -0.0727090538 -0.3865618408 815 32.5600000000 0.0902265534 0.0300096578 0.0918356329 0.0097667668 0.8638440000 97088466 95654128 1787760640 0.1522333473 -0.0733716041 -0.3850494027 816 32.6000000000 0.0900050253 0.0300831815 0.0918356329 0.0097688883 0.7773110000 97090160 95654128 1784840192 0.1534308940 -0.0732054263 -0.3844515681 817 32.6400000000 0.0890972391 0.0301554142 0.0918356329 0.0097710632 0.9180310000 97091854 95654128 1786109952 0.1550247818 -0.0729042217 -0.3833785355 818 32.6800000000 0.0895762295 0.0302280557 0.0918356329 0.0097734759 0.7263790000 97092288 95654128 1787887616 0.1554329544 -0.0733498484 -0.3826594353 819 32.7200000000 0.0895774066 0.0303005214 0.0918356329 0.0097754641 0.8365130000 97093982 95654128 1784713216 0.1552588940 -0.0727148727 -0.3824223578 820 32.7599999990 0.0900921226 0.0303734380 0.0918356329 0.0097760922 0.8765450000 97095676 95654128 1786126336 0.1563493907 -0.0744280964 -0.3809295893 821 32.7999999990 0.0904931650 0.0304466654 0.0918356329 0.0097789924 0.7245260000 97096250 95654128 1787887616 0.1565087140 -0.0749632865 -0.3806950748 822 32.8400000000 0.0917041004 0.0305211878 0.0918356329 0.0097804373 0.6327670000 97097944 95654128 1784713216 0.1560410261 -0.0767139047 -0.3800433278 823 32.8800000000 0.0918674916 0.0305957277 0.0918674916 0.0097900278 0.7796930000 97099638 95654128 1786109952 0.1569653302 -0.0777885839 -0.3785967827 824 32.9200000000 0.0920090601 0.0306702584 0.0920090601 0.0097966428 0.8213360000 97100072 95654128 1788014592 0.1577844024 -0.0792354792 -0.3772691190 825 32.9600000000 0.0906679928 0.0307429829 0.0920090601 0.0098109282 0.8464890000 97101766 95654128 1784745984 0.1586807966 -0.0786101371 -0.3761577010 826 33.0000000000 0.0909724012 0.0308158999 0.0920090601 0.0098203736 0.9312760000 97103460 95654128 1785982976 0.1590059102 -0.0794664100 -0.3750356436 827 33.0400000000 0.0903281942 0.0308878616 0.0920090601 0.0098237729 0.7124890000 97104034 95654128 1788014592 0.1593334228 -0.0795452222 -0.3734978139 828 33.0800000000 0.0905587301 0.0309599278 0.0920090601 0.0098298939 0.8757550000 97105728 95654128 1784713216 0.1599034369 -0.0811574310 -0.3723204434 829 33.1199999990 0.0898489207 0.0310309640 0.0920090601 0.0098393088 0.8967520000 97106162 95654128 1785982976 0.1594160944 -0.0801711306 -0.3718055785 830 33.1600000000 0.0919314101 0.0311043381 0.0920090601 0.0098367349 0.6360660000 97107856 95654128 1787887616 0.1603638977 -0.0836561248 -0.3700169027 831 33.2000000000 0.0920877159 0.0311777236 0.0920877159 0.0098407476 0.9968900000 97109550 95654128 1784729600 0.1584700197 -0.0833486244 -0.3699014187 832 33.2400000000 0.0914213359 0.0312501318 0.0920877159 0.0098363547 1.7945330000 97109984 95654128 1785982976 0.1571101695 -0.0818308890 -0.3700455725 833 33.2800000000 0.0912232399 0.0313221283 0.0920877159 0.0098313899 0.8804060000 97111818 95654128 1787887616 0.1571680605 -0.0825661346 -0.3683920205 834 33.3200000000 0.0915056765 0.0313942908 0.0920877159 0.0098270162 0.8485720000 97113512 95654128 1784713216 0.1564628333 -0.0826606154 -0.3679556549 835 33.3600000000 0.0909691751 0.0314656380 0.0920877159 0.0098214461 0.6701250000 97113946 95654128 1785982976 0.1560598910 -0.0819798633 -0.3671303391 836 33.4000000000 0.0906585380 0.0315364429 0.0920877159 0.0098159108 0.7746680000 97115640 95654128 1787633664 0.1563671529 -0.0830467567 -0.3647242188 837 33.4399999990 0.0906483904 0.0316070665 0.0920877159 0.0098114542 0.7386960000 97117334 95654128 1784606720 0.1551929563 -0.0831502527 -0.3646163940 838 33.4800000000 0.0913129970 0.0316783146 0.0920877159 0.0098059905 0.7973960000 97117768 95654128 1785982976 0.1554288417 -0.0849079937 -0.3625762463 839 33.5200000000 0.0918343216 0.0317500143 0.0920877159 0.0098001984 0.9918100000 97119602 95654128 1787887616 0.1548031867 -0.0860647559 -0.3615784347 840 33.5600000000 0.0899366066 0.0318192840 0.0920877159 0.0097952613 0.8128490000 97121296 95654128 1784713216 0.1539764702 -0.0848127306 -0.3604521453 841 33.6000000000 0.0908912867 0.0318895242 0.0920877159 0.0097911318 0.9440070000 97121730 95654128 1786109952 0.1535905749 -0.0875644013 -0.3583224118 842 33.6400000000 0.0917724892 0.0319606441 0.0920877159 0.0097948785 0.7545330000 97123424 95654128 1788149760 0.1527757794 -0.0892656073 -0.3576911688 843 33.6800000000 0.0913185477 0.0320310568 0.0920877159 0.0097962119 0.7547770000 97125118 95654128 1784262656 0.1520573199 -0.0890390351 -0.3569942117 844 33.7200000000 0.0929615200 0.0321032493 0.0929615200 0.0097919113 0.8059770000 97125552 95654128 1785610240 0.1514290720 -0.0918564275 -0.3556618690 845 33.7599999990 0.0925620347 0.0321747982 0.0929615200 0.0097919067 0.8770780000 97127386 95654128 1787514880 0.1511567831 -0.0922529101 -0.3544013202 846 33.7999999990 0.0931378007 0.0322468585 0.0931378007 0.0097901159 0.8520950000 97127820 95654128 1784467456 0.1513392627 -0.0934398249 -0.3521763980 847 33.8400000000 0.0944184959 0.0323202606 0.0944184959 0.0097853653 0.7552730000 97129514 95654128 1785864192 0.1503739655 -0.0948416218 -0.3513875604 848 33.8800000000 0.0930952951 0.0323919293 0.0944184959 0.0097800151 0.7497800000 97131208 95654128 1787768832 0.1491269767 -0.0933291167 -0.3509099782 849 33.9200000000 0.0934587717 0.0324638573 0.0944184959 0.0097745423 0.7441420000 97131642 95654128 1784614912 0.1480434835 -0.0935637951 -0.3510046005 850 33.9600000000 0.0925071537 0.0325344964 0.0944184959 0.0097696701 0.6601130000 97133336 95654128 1785991168 0.1474517137 -0.0929049179 -0.3493002355 851 34.0000000000 0.0904970020 0.0326026075 0.0944184959 0.0097658273 0.8939080000 97135170 95654128 1787887616 0.1461856663 -0.0908620432 -0.3496342003 852 34.0400000000 0.0888185278 0.0326685886 0.0944184959 0.0097624241 0.8151760000 97135604 95654128 1784840192 0.1443457305 -0.0890605599 -0.3504215479 853 34.0800000000 0.0891543776 0.0327348088 0.0944184959 0.0097600791 0.7174370000 97137298 95654128 1786126336 0.1439519674 -0.0903946459 -0.3487189114 854 34.1199999990 0.0907203630 0.0328027076 0.0944184959 0.0097572004 0.7662450000 97141444 95654128 1788014592 0.1432886124 -0.0930604488 -0.3470236063 855 34.1600000000 0.0916774347 0.0328715669 0.0944184959 0.0097528694 0.9567870000 97310586 95654128 1784602624 0.1426653415 -0.0958236232 -0.3455373645 856 34.2000000000 0.0918146670 0.0329404256 0.0944184959 0.0097503731 0.6971820000 97312280 95654128 1785982976 0.1418832988 -0.0970121399 -0.3447424769 857 34.2400000000 0.0917953402 0.0330091012 0.0944184959 0.0097503189 0.7557800000 97314114 95654128 1788014592 0.1409157217 -0.0969209820 -0.3439398408 858 34.2800000000 0.0904883966 0.0330760933 0.0944184959 0.0097470127 0.8432500000 97314548 95654128 1784619008 0.1402327269 -0.0963532403 -0.3434302509 859 34.3200000000 0.0893616900 0.0331416179 0.0944184959 0.0097466520 0.7059500000 97316242 95654128 1785856000 0.1397092938 -0.0959662423 -0.3427253067 860 34.3600000000 0.0882122740 0.0332056535 0.0944184959 0.0097441024 0.7784560000 97317936 95654128 1787760640 0.1389145702 -0.0947520956 -0.3423017561 861 34.4000000000 0.0878350735 0.0332691024 0.0944184959 0.0097389054 0.8502170000 97318370 95654128 1784713216 0.1369191855 -0.0942329839 -0.3418283165 862 34.4400000000 0.0880352780 0.0333326362 0.0944184959 0.0097334584 0.7237490000 97320064 95654128 1785982976 0.1352053583 -0.0943904743 -0.3413585424 863 34.4800000000 0.0862210318 0.0333939206 0.0944184959 0.0097286691 0.7758310000 97320638 95654128 1787760640 0.1332109272 -0.0917221382 -0.3410481215 864 34.5200000000 0.0845800191 0.0334531637 0.0944184959 0.0097233104 0.8154350000 97322332 95654128 1784586240 0.1317015588 -0.0896328613 -0.3406009674 865 34.5600000000 0.0854699016 0.0335132987 0.0944184959 0.0097203650 0.8161110000 97324026 95654128 1785982976 0.1306232512 -0.0914957076 -0.3377407789 866 34.6000000000 0.0856913105 0.0335735504 0.0944184959 0.0097149399 0.8753470000 97324460 95654128 1787760640 0.1286936998 -0.0921015143 -0.3355956674 867 34.6400000000 0.0872360989 0.0336354449 0.0944184959 0.0097097457 1.0588700000 97692678 95654128 1784602624 0.1271370500 -0.0934078321 -0.3349002600 868 34.6800000000 0.0871867687 0.0336971400 0.0944184959 0.0097061490 0.8173220000 97710428 95654128 1785999360 0.1247798875 -0.0927113593 -0.3336009681 869 34.7200000000 0.0893541798 0.0337611872 0.0944184959 0.0097059399 0.8339780000 97424786 95654128 1787777024 0.1235724762 -0.0948940590 -0.3314457536 870 34.7600000000 0.0899585187 0.0338257819 0.0944184959 0.0097091613 0.8290350000 97426480 95654128 1784602624 0.1218455061 -0.0954462811 -0.3295213580 871 34.8000000000 0.0901680067 0.0338904687 0.0944184959 0.0097124374 0.7380180000 97428174 95654128 1786015744 0.1197985113 -0.0965218619 -0.3273433447 872 34.8400000000 0.0885451809 0.0339531461 0.0944184959 0.0097070744 0.8045510000 97428608 95654128 1787904000 0.1166770384 -0.0951488763 -0.3247091472 873 34.8800000000 0.0909167081 0.0340183965 0.0944184959 0.0097050255 0.7838300000 97430302 95654128 1784475648 0.1145331040 -0.0965959504 -0.3228690922 874 34.9200000000 0.0914371982 0.0340840931 0.0944184959 0.0097000548 0.7465940000 97431996 95654128 1785872384 0.1124100238 -0.0960300192 -0.3216367960 875 34.9600000000 0.0926530808 0.0341510290 0.0944184959 0.0097071469 0.8884240000 97432570 95654128 1787650048 0.1095893160 -0.0972707719 -0.3181325495 876 35.0000000000 0.0922393948 0.0342173400 0.0944184959 0.0097081027 0.6876850000 97434264 95654128 1784614912 0.1074880734 -0.0968094468 -0.3164632618 877 35.0400000000 0.0927443653 0.0342840754 0.0944184959 0.0097095050 0.7703820000 97437994 95654128 1785999360 0.1051991060 -0.0969272181 -0.3145839274 878 35.0800000000 0.0920567289 0.0343498757 0.0944184959 0.0097142586 0.7436100000 97607188 95654128 1787895808 0.1020163149 -0.0963834077 -0.3123175800 879 35.1200000000 0.0919187590 0.0344153693 0.0944184959 0.0097121839 0.7290400000 97608882 95654128 1784594432 0.0998920128 -0.0959476382 -0.3106783926 880 35.1600000000 0.0926769078 0.0344815756 0.0944184959 0.0097206896 0.7406530000 97610576 95654128 1785880576 0.0970651209 -0.0957016647 -0.3092062473 881 35.2000000000 0.0909622237 0.0345456853 0.0944184959 0.0097356515 0.7761630000 97611150 95654128 1787895808 0.0944035649 -0.0942116901 -0.3067851365 882 35.2400000000 0.0901751593 0.0346087573 0.0944184959 0.0097366858 0.8080600000 97612844 95654128 1784467456 0.0917426199 -0.0936165303 -0.3039697111 883 35.2800000000 0.0906287208 0.0346722001 0.0944184959 0.0097323849 0.7675430000 97613278 95654128 1785729024 0.0892636329 -0.0939016715 -0.3034285605 884 35.3200000000 0.0909606069 0.0347358747 0.0944184959 0.0097283010 0.7490550000 97614972 95654128 1787650048 0.0861144438 -0.0930963829 -0.3022111058 885 35.3600000000 0.0919265151 0.0348004969 0.0944184959 0.0097259279 0.7583520000 97616666 95654128 1784733696 0.0836873874 -0.0939614475 -0.2995865941 886 35.4000000000 0.0927499309 0.0348659026 0.0944184959 0.0097217851 0.9489040000 97617100 95654128 1786109952 0.0811968297 -0.0950297117 -0.2977620661 887 35.4400000000 0.0931146592 0.0349315720 0.0944184959 0.0097166740 0.8666110000 97618934 95654128 1787785216 0.0780375078 -0.0949146003 -0.2978738248 888 35.4800000000 0.0925986171 0.0349965124 0.0944184959 0.0097114575 0.6470430000 97620628 95654128 1784340480 0.0751022920 -0.0942900851 -0.2960457504 889 35.5200000000 0.0936181024 0.0350624534 0.0944184959 0.0097065204 0.8100410000 97621062 95654128 1785737216 0.0724504963 -0.0949977040 -0.2936191261 890 35.5600000000 0.0921354368 0.0351265804 0.0944184959 0.0097021232 0.7857440000 97622756 95654128 1787641856 0.0701286197 -0.0928445384 -0.2920651436 891 35.6000000000 0.0931742862 0.0351917293 0.0944184959 0.0096970600 0.8548380000 97624450 95654128 1784467456 0.0682054609 -0.0930562317 -0.2919469178 892 35.6400000000 0.0933261141 0.0352569024 0.0944184959 0.0096917544 0.8584560000 97624884 95654128 1785864192 0.0658131912 -0.0923933387 -0.2922382355 893 35.6800000000 0.0933145359 0.0353219165 0.0944184959 0.0096865724 0.8579810000 97626718 95654128 1787760640 0.0635047629 -0.0921266228 -0.2901301086 894 35.7200000000 0.0927876383 0.0353861959 0.0944184959 0.0096814038 0.7604120000 97628412 95654128 1784586240 0.0612418354 -0.0911408067 -0.2887248397 895 35.7600000000 0.0923319459 0.0354498224 0.0944184959 0.0096767633 0.7734970000 97628846 95654128 1785982976 0.0588646047 -0.0902983025 -0.2875715494 896 35.8000000000 0.0917249024 0.0355126294 0.0944184959 0.0096718475 0.7556010000 97630540 95654128 1787887616 0.0564637817 -0.0893344432 -0.2870534062 897 35.8400000000 0.0917640701 0.0355753401 0.0944184959 0.0096665316 0.7091010000 97632234 95654128 1784586240 0.0544221029 -0.0887440592 -0.2869596779 898 35.8800000000 0.0925626084 0.0356388003 0.0944184959 0.0096615529 0.7526090000 97632668 95654128 1786109952 0.0523465723 -0.0887090787 -0.2871316969 899 35.9200000000 0.0925238803 0.0357020762 0.0944184959 0.0096568660 0.9017150000 97634502 95654128 1787887616 0.0500968248 -0.0883148164 -0.2873848379 900 35.9600000000 0.0930135399 0.0357657556 0.0944184959 0.0096518234 0.6484090000 97634936 95654128 1784725504 0.0479387492 -0.0890728310 -0.2875437140 901 36.0000000000 0.0926537067 0.0358288943 0.0944184959 0.0096478744 0.8211630000 97636630 95654128 1786109952 0.0460100174 -0.0884689167 -0.2880202532 902 36.0400000000 0.0932483226 0.0358925522 0.0944184959 0.0096425952 0.7398160000 97638324 95654128 1788014592 0.0436743796 -0.0887797549 -0.2878578007 903 36.0800000000 0.0926373452 0.0359553925 0.0944184959 0.0096375021 0.7699760000 97638758 95654128 1784586240 0.0412943326 -0.0882664546 -0.2874450684 904 36.1200000000 0.0924894437 0.0360179302 0.0944184959 0.0096323443 0.8025890000 97640452 95654128 1785982976 0.0393418297 -0.0882157758 -0.2872658372 905 36.1600000000 0.0914846063 0.0360792193 0.0944184959 0.0096275767 0.7652200000 97642286 95654128 1787887616 0.0369510017 -0.0867623165 -0.2864799500 906 36.2000000000 0.0918367058 0.0361407618 0.0944184959 0.0096255500 0.7474050000 97642720 95654128 1784840192 0.0346974917 -0.0875557587 -0.2853715420 907 36.2400000000 0.0929843485 0.0362034339 0.0944184959 0.0096218108 0.7327260000 97644414 95654128 1786109952 0.0327389836 -0.0883269235 -0.2887656093 908 36.2800000000 0.0935902745 0.0362666353 0.0944184959 0.0096166178 0.7260600000 97646108 95654128 1788014592 0.0306694619 -0.0887307748 -0.2909667492 909 36.3200000000 0.0940844342 0.0363302412 0.0944184959 0.0096113376 0.9567480000 97646542 95654128 1784586240 0.0283372011 -0.0890990123 -0.2916189432 910 36.3600000000 0.0932478160 0.0363927880 0.0944184959 0.0096062885 0.7482520000 97648236 95654128 1785872384 0.0254809484 -0.0880366936 -0.2912085652 911 36.4000000000 0.0930318683 0.0364549604 0.0944184959 0.0096014645 0.8489640000 97650070 95654128 1787887616 0.0229019877 -0.0883671716 -0.2908471227 912 36.4400000000 0.0939924791 0.0365180498 0.0944184959 0.0095962933 0.8572610000 97650504 95654128 1784713216 0.0207683463 -0.0890297741 -0.2915351391 913 36.4800000000 0.0934890583 0.0365804496 0.0944184959 0.0095915131 0.8094660000 97652198 95654128 1786109952 0.0181854665 -0.0881384239 -0.2913967669 914 36.5200000000 0.0931795388 0.0366423742 0.0944184959 0.0095881955 0.7514010000 97653892 95654128 1787760640 0.0156109259 -0.0877258554 -0.2922040522 915 36.5600000000 0.0931903943 0.0367041753 0.0944184959 0.0095851968 0.7687530000 97657338 95654128 1784614912 0.0132765416 -0.0880495608 -0.2924056947 916 36.6000000000 0.0933959931 0.0367660659 0.0944184959 0.0095800177 0.6621780000 97827784 95654128 1785982976 0.0114964042 -0.0881578922 -0.2935096622 917 36.6400000000 0.0940913334 0.0368285799 0.0944184959 0.0095751732 0.6003090000 97828358 95654128 1788014592 0.0093329623 -0.0888336301 -0.2959218621 918 36.6800000000 0.0945111290 0.0368914149 0.0945111290 0.0095703227 0.8570480000 97830052 95654128 1784586240 0.0071269167 -0.0894350410 -0.2954829037 919 36.7200000000 0.0939734057 0.0369535280 0.0945111290 0.0095651928 0.7099980000 97831746 95654128 1785999360 0.0047322083 -0.0889774635 -0.2940177023 920 36.7600000000 0.0944221839 0.0370159940 0.0945111290 0.0095602024 0.8386870000 97832180 95654128 1787887616 0.0026313323 -0.0895194411 -0.2943921387 921 36.8000000000 0.0940690264 0.0370779408 0.0945111290 0.0095550216 0.7323680000 97833874 95654128 1784713216 0.0012743379 -0.0886523426 -0.2952750325 922 36.8400000000 0.0926452205 0.0371382090 0.0945111290 0.0095506731 0.7420220000 97835568 95654128 1786109952 -0.0008402263 -0.0870341137 -0.2932936549 923 36.8800000000 0.0924641714 0.0371981504 0.0945111290 0.0095469252 0.8330790000 97836142 95654128 1788014592 -0.0024325182 -0.0865913555 -0.2934303880 924 36.9200000000 0.0914512798 0.0372568660 0.0945111290 0.0095444889 0.8076540000 97837836 95654128 1784741888 -0.0044658161 -0.0860386938 -0.2924014926 925 36.9600000000 0.0905439034 0.0373144736 0.0945111290 0.0095402013 0.8430940000 97839530 95654128 1786109952 -0.0063709449 -0.0851506069 -0.2922809124 926 37.0000000000 0.0902621076 0.0373716524 0.0945111290 0.0095351505 1.0463930000 97839964 95654128 1787887616 -0.0073099560 -0.0844420865 -0.2927883267 927 37.0400000000 0.0905090645 0.0374289743 0.0945111290 0.0095306308 1.5403580000 97841658 95654128 1784713216 -0.0082472088 -0.0845022500 -0.2931127548 928 37.0800000000 0.0906462073 0.0374863205 0.0945111290 0.0095270035 1.9005870000 97843352 95654128 1786245120 -0.0092782462 -0.0837079883 -0.2928991914 929 37.1200000000 0.0896069333 0.0375424245 0.0945111290 0.0095273119 0.7738610000 97843926 95654128 1787895808 -0.0110748783 -0.0826223791 -0.2913898230 930 37.1600000000 0.0892760381 0.0375980520 0.0945111290 0.0095270029 0.9667890000 97845620 95654128 1784467456 -0.0119214877 -0.0820533112 -0.2910813093 931 37.2000000000 0.0893489718 0.0376536384 0.0945111290 0.0095248902 1.7189010000 97847314 95654128 1785864192 -0.0125440154 -0.0818628743 -0.2907705009 932 37.2400000000 0.0883520246 0.0377080358 0.0945111290 0.0095229845 0.9018690000 97847748 95654128 1787768832 -0.0134440167 -0.0806220025 -0.2903965712 933 37.2800000000 0.0872943476 0.0377611830 0.0945111290 0.0095190534 0.9019770000 97849442 95654128 1784594432 -0.0137980403 -0.0793752819 -0.2892818153 934 37.3200000000 0.0867092907 0.0378135900 0.0945111290 0.0095167173 1.7837630000 97851136 95654128 1785856000 -0.0142718721 -0.0780902877 -0.2886472344 935 37.3600000000 0.0872698650 0.0378664844 0.0945111290 0.0095164986 0.8009980000 97851710 95654128 1787752448 -0.0145861600 -0.0787378177 -0.2874689996 936 37.4000000000 0.0870594904 0.0379190410 0.0945111290 0.0095150955 0.8678000000 97853404 95654128 1784713216 -0.0151807442 -0.0785007253 -0.2868933678 937 37.4400000000 0.0864351913 0.0379708192 0.0945111290 0.0095113382 0.6835150000 97853838 95654128 1785999360 -0.0152701121 -0.0780886263 -0.2862878740 938 37.4800000000 0.0867096707 0.0380227796 0.0945111290 0.0095076128 0.7064870000 97855532 95654128 1787887616 -0.0150763383 -0.0786830038 -0.2858628929 939 37.5200000000 0.0869542435 0.0380748898 0.0945111290 0.0095031898 0.6676330000 97857226 95654128 1784602624 -0.0149512431 -0.0784778669 -0.2869391441 940 37.5600000000 0.0869980603 0.0381269357 0.0945111290 0.0094986894 0.6353070000 97857660 95654128 1785999360 -0.0147057511 -0.0784852356 -0.2864657342 941 37.6000000000 0.0871527418 0.0381790354 0.0945111290 0.0094955514 0.8829510000 97859494 95654128 1787760640 -0.0151255913 -0.0781586319 -0.2859714627 942 37.6400000000 0.0874409005 0.0382313304 0.0945111290 0.0094922406 0.9282610000 97861188 95654128 1784459264 -0.0150104119 -0.0780945122 -0.2857194245 943 37.6800000000 0.0870442986 0.0382830938 0.0945111290 0.0094907780 1.0579550000 97861622 95654128 1785856000 -0.0145213958 -0.0776808113 -0.2855296731 944 37.7200000000 0.0862694681 0.0383339269 0.0945111290 0.0094891409 0.9911310000 97863316 95654128 1787760640 -0.0147767570 -0.0766828954 -0.2843142152 945 37.7600000000 0.0867908075 0.0383852040 0.0945111290 0.0094854025 0.7633310000 97865010 95654128 1784586240 -0.0142994476 -0.0764437988 -0.2863584459 946 37.8000000000 0.0860416889 0.0384355808 0.0945111290 0.0094825379 0.8835550000 97865444 95654128 1785982976 -0.0143007152 -0.0758391917 -0.2853231728 947 37.8400000000 0.0859042257 0.0384857061 0.0945111290 0.0094785236 0.7459500000 97867278 95654128 1787887616 -0.0139050726 -0.0756722912 -0.2846426070 948 37.8800000000 0.0863868818 0.0385362348 0.0945111290 0.0094759193 0.7064450000 97868972 95654128 1784725504 -0.0141049828 -0.0757696927 -0.2851580381 949 37.9200000000 0.0860222653 0.0385862727 0.0945111290 0.0094726005 0.8136010000 97869406 95654128 1786109952 -0.0140333455 -0.0750098005 -0.2854824364 950 37.9600000000 0.0860047191 0.0386361869 0.0945111290 0.0094693935 0.7522160000 97871100 95654128 1787887616 -0.0137919346 -0.0749124065 -0.2846087515 951 38.0000000000 0.0861474499 0.0386861462 0.0945111290 0.0094650671 0.7879870000 97872794 95654128 1784713216 -0.0134679070 -0.0744464248 -0.2859333158 952 38.0400000000 0.0852173418 0.0387350235 0.0945111290 0.0094617478 0.7938430000 97873228 95654128 1786109952 -0.0133788986 -0.0726269111 -0.2874465585 953 38.0800000000 0.0855578184 0.0387841555 0.0945111290 0.0094573833 0.7620400000 97875062 95654128 1788014592 -0.0127421608 -0.0726016238 -0.2883907259 954 38.1200000000 0.0867213383 0.0388344041 0.0945111290 0.0094525289 0.7264880000 97875496 95654128 1784586240 -0.0121773249 -0.0732445940 -0.2894179225 955 38.1600000000 0.0866284594 0.0388844502 0.0945111290 0.0094483324 0.8038210000 97877190 95654128 1785982976 -0.0117203295 -0.0735752359 -0.2883991599 956 38.2000000000 0.0865236744 0.0389342820 0.0945111290 0.0094434069 0.7262870000 97878884 95654128 1787760640 -0.0112655219 -0.0728085712 -0.2895121276 957 38.2400000000 0.0862582475 0.0389837324 0.0945111290 0.0094385466 0.7541000000 97879318 95654128 1784856576 -0.0109943263 -0.0732644647 -0.2880930603 958 38.2800000000 0.0869257376 0.0390337762 0.0945111290 0.0094338723 0.8103510000 97881012 95654128 1786109952 -0.0103997160 -0.0738819018 -0.2880475521 959 38.3200000000 0.0868113041 0.0390835964 0.0945111290 0.0094290458 0.7439370000 97882846 95654128 1788141568 -0.0102428934 -0.0738533959 -0.2878990769 960 38.3600000000 0.0859029070 0.0391323665 0.0945111290 0.0094250525 1.0621090000 97883280 95654128 1784840192 -0.0100220162 -0.0726853311 -0.2880435288 961 38.4000000000 0.0854967386 0.0391806125 0.0945111290 0.0094207649 1.1684270000 97884974 95654128 1786109952 -0.0097579146 -0.0721034855 -0.2882169485 962 38.4400000000 0.0858625993 0.0392291384 0.0945111290 0.0094161306 0.9000920000 97886668 95654128 1788141568 -0.0092135081 -0.0720122308 -0.2897006869 963 38.4800000000 0.0859750956 0.0392776804 0.0945111290 0.0094114848 0.8093960000 97887102 95654128 1784967168 -0.0085208844 -0.0718972459 -0.2911500335 964 38.5200000000 0.0861250833 0.0393262773 0.0945111290 0.0094067322 0.7486420000 97888796 95654128 1786490880 -0.0077997153 -0.0715395361 -0.2923054099 965 38.5600000000 0.0858214423 0.0393744588 0.0945111290 0.0094022136 0.8011940000 97890630 95654128 1785856000 -0.0075267642 -0.0713550895 -0.2917579114 966 38.6000000000 0.0859810412 0.0394227058 0.0945111290 0.0093973940 0.6304800000 97891064 95654128 1787269120 -0.0071623609 -0.0712979734 -0.2926281691 967 38.6400000000 0.0840508640 0.0394688570 0.0945111290 0.0093927499 0.8064320000 97892758 95654128 1784725504 -0.0073429770 -0.0698889345 -0.2905489206 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-19 04:15:54 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1870130000 88427918 95654128 1753726976 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0026374757 0.0013187379 0.0026374757 0.0017024400 1.0871570000 88630598 95654128 1756393472 -0.0024953254 -0.0007021125 0.0006995602 3 0.0800000000 0.0101173818 0.0042516192 0.0101173818 0.0039606649 1.0115280000 88632616 95654128 1758679040 -0.0043978756 -0.0079790503 0.0020776484 4 0.1200000000 0.0064746188 0.0048073691 0.0101173818 0.0045292216 0.8353740000 88633378 95654128 1760329728 -0.0073182695 -0.0036471700 0.0007300427 5 0.1600000000 0.0057244324 0.0049907818 0.0101173818 0.0042780893 0.9212980000 88635508 95654128 1762107392 -0.0100418907 -0.0023229974 0.0015760884 6 0.2000000000 0.0113287689 0.0060471129 0.0113287689 0.0041826629 1.8664200000 88637858 95654128 1763749888 -0.0072733378 -0.0091877244 0.0032580164 7 0.2400000000 0.0137613313 0.0071491441 0.0137613313 0.0039205636 1.9401190000 88638292 95654128 1765502976 -0.0084408261 -0.0116500510 0.0038376036 8 0.2800000000 0.0109567223 0.0076250914 0.0137613313 0.0037287651 1.6127030000 88639986 95654128 1766952960 -0.0091288676 -0.0088033425 0.0031799795 9 0.3200000000 0.0101161199 0.0079018724 0.0137613313 0.0035643689 1.9755370000 88642320 95654128 1768722432 -0.0096302973 -0.0089874156 0.0023234256 10 0.3600000000 0.0064781415 0.0077594993 0.0137613313 0.0034957043 1.6845150000 88644066 95654128 1770500096 -0.0094802184 -0.0044326806 0.0014241862 11 0.4000000000 0.0061003678 0.0076086691 0.0137613313 0.0038332496 2.0008120000 88645760 95654128 1772150784 -0.0113054272 -0.0049017230 0.0014363085 12 0.4400000000 0.0057260180 0.0074517815 0.0137613313 0.0037279963 2.5761470000 88647570 95654128 1773768704 -0.0091215577 -0.0047794878 0.0001811116 13 0.4800000000 0.0093538854 0.0075980972 0.0137613313 0.0035729087 1.7095350000 88648004 95654128 1775521792 -0.0064525381 -0.0063047465 -0.0000028049 14 0.5200000000 0.0097767208 0.0077537132 0.0137613313 0.0034581787 1.7338410000 88649698 95654128 1777188864 -0.0058873254 -0.0053321063 -0.0006355807 15 0.5600000000 0.0114299888 0.0079987982 0.0137613313 0.0033448731 1.8361720000 88651392 95654128 1778798592 -0.0082499012 -0.0058251023 0.0007048107 16 0.6000000000 0.0188821405 0.0086790071 0.0188821405 0.0034238047 1.8475240000 88651826 95654128 1780576256 -0.0077722063 -0.0163366795 0.0019653698 17 0.6400000000 0.0165153481 0.0091399684 0.0188821405 0.0034398740 1.7578470000 88654800 95654128 1782353920 -0.0106976377 -0.0154727967 0.0002382895 18 0.6800000000 0.0189564284 0.0096853272 0.0189564284 0.0034203341 1.7191640000 88659118 95654128 1783894016 -0.0070967162 -0.0152675295 0.0006038457 19 0.7200000000 0.0173973534 0.0100912234 0.0189564284 0.0034630097 1.8364650000 88659552 95654128 1785765888 -0.0088220974 -0.0132348388 -0.0007003625 20 0.7600000000 0.0186653025 0.0105199273 0.0189564284 0.0034202548 2.1212070000 88661246 95654128 1787416576 -0.0128809717 -0.0167293735 0.0001345953 21 0.8000000000 0.0249640271 0.0112077416 0.0249640271 0.0033981273 1.8695640000 88663056 95654128 1784377344 -0.0109311007 -0.0200380180 0.0010270901 22 0.8400000000 0.0286661051 0.0120013036 0.0286661051 0.0034129316 2.1073450000 88663410 95654128 1785647104 -0.0121446857 -0.0219160989 0.0007911119 23 0.8800000000 0.0292122103 0.0127496039 0.0292122103 0.0033463056 1.9479860000 88665104 95654128 1787551744 -0.0124380551 -0.0242104828 0.0000529512 24 0.9200000000 0.0254716799 0.0132796904 0.0292122103 0.0033201928 1.9016750000 88666798 95654128 1784504320 -0.0235000979 -0.0201853029 -0.0014848781 25 0.9600000000 0.0292996839 0.0139204901 0.0292996839 0.0032720952 1.9689780000 88667232 95654128 1785765888 -0.0244310405 -0.0233809967 -0.0008299848 26 1.0000000000 0.0297313035 0.0145285983 0.0297313035 0.0032568555 1.7192650000 88668910 95654128 1787670528 -0.0265735537 -0.0223783888 -0.0013773779 27 1.0400000000 0.0317729115 0.0151672766 0.0317729115 0.0032707686 1.4084950000 88670604 95654128 1784496128 -0.0304499213 -0.0242788196 -0.0041726837 28 1.0800000000 0.0342184529 0.0158476757 0.0342184529 0.0034082894 1.9525300000 88671038 95654128 1785765888 -0.0343751870 -0.0249869786 -0.0040311930 29 1.1200000000 0.0409410000 0.0167129628 0.0409410000 0.0037325246 1.5256530000 88672716 95654128 1787416576 -0.0378549546 -0.0311953016 -0.0045892932 30 1.1600000000 0.0362495072 0.0173641809 0.0409410000 0.0036727095 2.5918750000 88674410 95654128 1784369152 -0.0498410761 -0.0280442499 -0.0043100757 31 1.2000000000 0.0315692089 0.0178224076 0.0409410000 0.0036168866 2.1580140000 88674844 95654128 1785765888 -0.0597527474 -0.0241813846 -0.0074841836 32 1.2400000000 0.0342069939 0.0183344260 0.0409410000 0.0036285995 2.1283400000 88676522 95654128 1787543552 -0.0646726862 -0.0256999582 -0.0097053749 33 1.2800000000 0.0366627648 0.0188898302 0.0409410000 0.0036799584 1.5873690000 88680776 95654128 1784496128 -0.0724986196 -0.0306378026 -0.0087722801 34 1.3200000000 0.0428603813 0.0195948464 0.0428603813 0.0036250168 1.9299930000 88686458 95654128 1786019840 -0.0947986692 -0.0347761214 -0.0096207913 35 1.3600000000 0.0439491719 0.0202906842 0.0439491719 0.0039278749 1.9371460000 88688152 95654128 1787670528 -0.0981783867 -0.0352639146 -0.0113461697 36 1.4000000000 0.0486518443 0.0210784942 0.0486518443 0.0044222486 2.2796590000 88689846 95654128 1784623104 -0.1017695442 -0.0384829305 -0.0112059014 37 1.4400000000 0.0485962145 0.0218222164 0.0486518443 0.0044105283 1.5533310000 88690280 95654128 1785892864 -0.1158213988 -0.0423502401 -0.0089437794 38 1.4800000000 0.0434819795 0.0223922102 0.0486518443 0.0043730169 1.2053890000 88691974 95654128 1784832000 -0.1285577714 -0.0376082957 -0.0096667055 39 1.5200000000 0.0483282618 0.0230572371 0.0486518443 0.0043337083 1.8805880000 88693668 95654128 1786609664 -0.1301627159 -0.0428426862 -0.0117058717 40 1.5600000000 0.0473377816 0.0236642508 0.0486518443 0.0042944042 1.5071180000 88694102 95654128 1785729024 -0.1401509345 -0.0433993936 -0.0114235841 41 1.6000000000 0.0441046432 0.0241627969 0.0486518443 0.0043064310 1.0340350000 88695796 95654128 1786998784 -0.1509848982 -0.0410835221 -0.0109176748 42 1.6400000000 0.0435712337 0.0246249026 0.0486518443 0.0042684828 1.0828370000 88697490 95654128 1784459264 -0.1615762413 -0.0370447822 -0.0097637624 43 1.6800000000 0.0494167842 0.0252014579 0.0494167842 0.0042194002 1.8283870000 88697908 95654128 1785729024 -0.1634085476 -0.0401237234 -0.0070143882 44 1.7200000000 0.0493531339 0.0257503597 0.0494167842 0.0042713991 1.6875050000 88699602 95654128 1787633664 -0.1718157828 -0.0424676910 -0.0089363093 45 1.7600000000 0.0510509349 0.0263125947 0.0510509349 0.0042547027 1.7166200000 88701296 95654128 1784459264 -0.1771989614 -0.0401651338 -0.0057523139 46 1.8000000000 0.0534157455 0.0269017936 0.0534157455 0.0042569243 2.0291620000 88701730 95654128 1785839616 -0.1827763021 -0.0423004776 -0.0045253867 47 1.8400000000 0.0579214282 0.0275617858 0.0579214282 0.0043075250 1.8602340000 88703424 95654128 1787744256 -0.1844479442 -0.0487730503 -0.0038462053 48 1.8800000000 0.0569262728 0.0281735460 0.0579214282 0.0043124372 1.5806400000 88705118 95654128 1784442880 -0.1870971471 -0.0464053825 -0.0043981159 49 1.9200000000 0.0495150089 0.0286090860 0.0579214282 0.0042928376 1.5777050000 88705536 95654128 1785712640 -0.1996146142 -0.0400824882 -0.0048691491 50 1.9600000000 0.0445726588 0.0289283575 0.0579214282 0.0042546872 1.5277460000 88707230 95654128 1787490304 -0.2162593305 -0.0359033681 -0.0014755796 51 2.0000000000 0.0410971120 0.0291669605 0.0579214282 0.0042129558 2.0111460000 88708924 95654128 1784569856 -0.2184904963 -0.0347552933 -0.0033705416 52 2.0400000000 0.0432155058 0.0294371249 0.0579214282 0.0041830595 1.4940080000 88709358 95654128 1785839616 -0.2233807296 -0.0376450233 -0.0038215879 53 2.0800000000 0.0435471497 0.0297033517 0.0579214282 0.0041798881 2.3518860000 88711052 95654128 1787871232 -0.2240162939 -0.0395111106 -0.0074073756 54 2.1200000000 0.0403805040 0.0299010768 0.0579214282 0.0042989210 1.4870410000 88712746 95654128 1784442880 -0.2356427908 -0.0358060524 -0.0041121691 55 2.1600000000 0.0383895636 0.0300554129 0.0579214282 0.0043770730 2.0870050000 88713180 95654128 1785712640 -0.2374864072 -0.0318834111 -0.0045554037 56 2.2000000000 0.0369035602 0.0301777012 0.0579214282 0.0043870163 1.7466510000 88714874 95654128 1787744256 -0.2561827302 -0.0274763852 0.0022648876 57 2.2400000000 0.0379411317 0.0303139018 0.0579214282 0.0043646465 2.0472270000 88716552 95654128 1784197120 -0.2600640357 -0.0306747183 0.0034697470 58 2.2800000000 0.0372791998 0.0304339931 0.0579214282 0.0043707414 2.0853760000 88716986 95654128 1785466880 -0.2705831230 -0.0318396538 0.0072299242 59 2.3200000000 0.0406255163 0.0306067308 0.0579214282 0.0045379721 1.7855800000 88718680 95654128 1787371520 -0.2799059451 -0.0285086818 0.0117465248 60 2.3600000000 0.0451591350 0.0308492709 0.0579214282 0.0046671850 1.5335190000 88720374 95654128 1784442880 -0.2813571393 -0.0357758775 0.0119842067 61 2.4000000000 0.0419229306 0.0310308063 0.0579214282 0.0047344859 1.4686970000 88720808 95654128 1785839616 -0.2904003561 -0.0348521546 0.0108956173 62 2.4400000000 0.0400923826 0.0311769607 0.0579214282 0.0048832101 1.8338630000 88722502 95654128 1787617280 -0.3138504028 -0.0301883630 0.0182448104 63 2.4800000000 0.0365493931 0.0312622374 0.0579214282 0.0049672868 1.6424900000 88724196 95654128 1784442880 -0.3255646825 -0.0297464915 0.0205795951 64 2.5200000000 0.0346793644 0.0313156301 0.0579214282 0.0051993595 1.1245320000 88724630 95654128 1785712640 -0.3383307457 -0.0250696652 0.0242637899 65 2.5600000000 0.0341788754 0.0313596800 0.0579214282 0.0055201153 2.2224810000 88731444 95654128 1787744256 -0.3528909981 -0.0256938469 0.0287024006 66 2.6000000000 0.0300691091 0.0313401259 0.0579214282 0.0055630220 1.7546330000 88743634 95654128 1783173120 -0.3677712977 -0.0234106854 0.0312003810 67 2.6400000000 0.0273551904 0.0312806492 0.0579214282 0.0055749942 1.7409980000 88744872 95654128 1784823808 -0.3798597753 -0.0185120292 0.0328982808 68 2.6800000000 0.0295572467 0.0312553051 0.0579214282 0.0055622733 2.3640730000 88915166 95654128 1786474496 -0.3885392249 -0.0186987631 0.0315528810 69 2.7200000000 0.0268314630 0.0311911914 0.0579214282 0.0055341834 1.5709710000 88916860 95654128 1785712640 -0.3993938267 -0.0138574466 0.0344538912 70 2.7600000000 0.0241567194 0.0310906990 0.0579214282 0.0055134243 2.1460570000 88917310 95654128 1786982400 -0.4111386538 -0.0118566426 0.0344047211 71 2.8000000000 0.0266612582 0.0310283125 0.0579214282 0.0055344768 1.3689680000 88919004 95654128 1784315904 -0.4164086580 -0.0135354931 0.0317617171 72 2.8400000000 0.0291393697 0.0310020772 0.0579214282 0.0061816924 2.1934660000 88920698 95654128 1785585664 -0.4310047626 -0.0110554406 0.0350362994 73 2.8800000000 0.0287211053 0.0309708310 0.0579214282 0.0062523311 1.5215630000 88921132 95654128 1787617280 -0.4423088133 -0.0109510794 0.0364814401 74 2.9200000000 0.0279824343 0.0309304472 0.0579214282 0.0063285409 1.8257450000 88922826 95654128 1784442880 -0.4448080659 -0.0088120606 0.0344259366 75 2.9600000000 0.0288384762 0.0309025543 0.0579214282 0.0063592469 1.5967720000 88924520 95654128 1785712640 -0.4465527833 -0.0074588996 0.0329634026 76 3.0000000000 0.0322768390 0.0309206370 0.0579214282 0.0063893676 1.7529810000 88924954 95654128 1787752448 -0.4471723437 -0.0121311713 0.0282241143 77 3.0400000000 0.0330872424 0.0309487747 0.0579214282 0.0063851731 2.1987140000 88926648 95654128 1784324096 -0.4475110173 -0.0127370832 0.0222986843 78 3.0800000000 0.0361938775 0.0310160196 0.0579214282 0.0063567636 1.5527930000 88928326 95654128 1785593856 -0.4472903013 -0.0161994714 0.0166545324 79 3.1200000000 0.0388050973 0.0311146155 0.0579214282 0.0063276112 2.0237150000 88928760 95654128 1787498496 -0.4524114430 -0.0151115060 0.0144759845 80 3.1600000000 0.0401428752 0.0312274688 0.0579214282 0.0062995126 1.5301710000 88931662 95654128 1784451072 -0.4565701783 -0.0142088756 0.0113150980 81 3.2000000000 0.0401324667 0.0313374070 0.0579214282 0.0062682335 1.3665520000 89101956 95654128 1785712640 -0.4695758522 -0.0157941449 0.0137933465 82 3.2400000000 0.0348566622 0.0313803248 0.0579214282 0.0062673386 1.8955180000 89102390 95654128 1787871232 -0.4792827368 -0.0104657430 0.0115857050 83 3.2800000000 0.0281004645 0.0313408084 0.0579214282 0.0062698965 1.0229450000 89104084 95654128 1784332288 -0.4908078909 -0.0027929693 0.0073706303 84 3.3200000000 0.0309565570 0.0313362340 0.0579214282 0.0062628016 1.6026640000 89105778 95654128 1785712640 -0.5005632043 -0.0055783424 0.0077335536 85 3.3600000000 0.0326051451 0.0313511623 0.0579214282 0.0062549202 1.4853350000 89106212 95654128 1787363328 -0.5123536587 -0.0053901281 0.0078472840 86 3.4000000000 0.0276705250 0.0313083642 0.0579214282 0.0062948707 1.8691300000 89107906 95654128 1784315904 -0.5293261409 -0.0000948114 0.0101675475 87 3.4400000000 0.0261784289 0.0312493994 0.0579214282 0.0063826583 1.5840770000 89109600 95654128 1785712640 -0.5395898819 0.0003275254 0.0091356542 88 3.4800000000 0.0291790254 0.0312258725 0.0579214282 0.0065794804 1.9589390000 89110050 95654128 1787490304 -0.5489145517 -0.0002127053 0.0099713579 89 3.5200000000 0.0281277485 0.0311910621 0.0579214282 0.0067099004 1.6965550000 89111728 95654128 1784315904 -0.5581769347 0.0015696010 0.0094835153 90 3.5600000000 0.0274325982 0.0311493014 0.0579214282 0.0068088836 2.0752250000 89113438 95654128 1785712640 -0.5670621395 -0.0005426412 0.0080496622 91 3.6000000000 0.0289058313 0.0311246479 0.0579214282 0.0068502229 2.1852580000 89113872 95654128 1787490304 -0.5809859633 -0.0030951151 0.0100117326 92 3.6400000000 0.0274359938 0.0310845538 0.0579214282 0.0068679260 1.3066220000 89115566 95654128 1784315904 -0.5956395864 0.0019157981 0.0137391966 93 3.6800000000 0.0306396335 0.0310797697 0.0579214282 0.0068588942 1.9003960000 89117260 95654128 1785712640 -0.5980280042 -0.0016097035 0.0121894581 94 3.7200000000 0.0307268761 0.0310760155 0.0579214282 0.0068312705 2.1418900000 89117694 95654128 1787744256 -0.6041952968 -0.0028661983 0.0111598140 95 3.7600000000 0.0301190428 0.0310659421 0.0579214282 0.0068251315 2.0152940000 89119388 95654128 1784332288 -0.6193203926 -0.0024864194 0.0162121188 96 3.8000000000 0.0290398560 0.0310448371 0.0579214282 0.0067988942 1.6530640000 89121082 95654128 1785847808 -0.6282075047 0.0000395814 0.0155377761 97 3.8400000000 0.0294375494 0.0310282671 0.0579214282 0.0067651214 1.8618050000 89121516 95654128 1787625472 -0.6343841553 -0.0039840713 0.0172816161 98 3.8800000000 0.0349137783 0.0310679152 0.0579214282 0.0067478480 1.7216090000 89123210 95654128 1784451072 -0.6458007097 -0.0094929207 0.0218852703 99 3.9200000000 0.0367046818 0.0311248522 0.0579214282 0.0067283886 1.6407970000 89125648 95654128 1785847808 -0.6515142322 -0.0107822903 0.0251571927 100 3.9600000000 0.0317374058 0.0311309777 0.0579214282 0.0066995727 1.4979440000 89294690 95654128 1787752448 -0.6627074480 -0.0068657314 0.0281708203 101 4.0000000000 0.0305775348 0.0311254981 0.0579214282 0.0066687776 1.8532040000 89296384 95654128 1784340480 -0.6712868214 -0.0067125545 0.0336849168 102 4.0400000000 0.0309573300 0.0311238494 0.0579214282 0.0066474718 1.6068830000 89298078 95654128 1785712640 -0.6742200255 -0.0081217568 0.0355723351 103 4.0800000000 0.0329194292 0.0311412822 0.0579214282 0.0066158241 2.0921510000 89298496 95654128 1787506688 -0.6841361523 -0.0105350632 0.0418741778 104 4.1200000000 0.0322508663 0.0311519513 0.0579214282 0.0065853694 1.8299880000 89300206 95654128 1784442880 -0.6967089176 -0.0104113556 0.0525882430 105 4.1600000000 0.0332110375 0.0311715616 0.0579214282 0.0066043651 1.9584790000 89301884 95654128 1785712640 -0.6976038218 -0.0104438765 0.0555972643 106 4.2000000000 0.0253566038 0.0311167035 0.0579214282 0.0065818042 2.4734700000 89302318 95654128 1787744256 -0.7100806236 -0.0038500992 0.0596044324 107 4.2400000000 0.0248996038 0.0310585998 0.0579214282 0.0065682903 1.5631290000 89304012 95654128 1784442880 -0.7096644044 -0.0062971124 0.0577658862 108 4.2800000000 0.0271344092 0.0310222647 0.0579214282 0.0065416967 1.8524160000 89305706 95654128 1785712640 -0.7185612321 -0.0100560784 0.0660877004 109 4.3200000000 0.0282398108 0.0309967376 0.0579214282 0.0065353371 1.8295570000 89306140 95654128 1787617280 -0.7191510201 -0.0106302323 0.0679474324 110 4.3600000000 0.0272445157 0.0309626265 0.0579214282 0.0065313401 0.8567530000 89307834 95654128 1784389632 -0.7305551767 -0.0129719526 0.0748119652 111 4.4000000000 0.0234823525 0.0308952366 0.0579214282 0.0065217307 0.6560110000 89309528 95654128 1785720832 -0.7388156056 -0.0101084132 0.0805307627 112 4.4400000000 0.0269907992 0.0308603756 0.0579214282 0.0065411399 0.6982650000 89309978 95654128 1787752448 -0.7427060604 -0.0105696702 0.0883334503 113 4.4800000000 0.0267903861 0.0308243580 0.0579214282 0.0065544552 0.8174990000 89311672 95654128 1784197120 -0.7463995814 -0.0092519345 0.0919147283 114 4.5200000000 0.0279344842 0.0307990082 0.0579214282 0.0065960719 0.8133240000 89313366 95654128 1785593856 -0.7568402886 -0.0097791245 0.1022496670 115 4.5600000000 0.0298116934 0.0307904229 0.0579214282 0.0066085191 0.8325890000 89313800 95654128 1787371520 -0.7566875219 -0.0126336571 0.1052323878 116 4.6000000000 0.0308461916 0.0307909036 0.0579214282 0.0066393476 0.8053610000 89315494 95654128 1784451072 -0.7660470009 -0.0098800678 0.1160689294 117 4.6400000000 0.0270495880 0.0307589266 0.0579214282 0.0066388311 0.8301180000 89317188 95654128 1785847808 -0.7760245204 -0.0027136542 0.1261868328 118 4.6800000000 0.0292819701 0.0307464100 0.0579214282 0.0066140347 0.8212830000 89317622 95654128 1787625472 -0.7796232104 -0.0063357162 0.1311187148 119 4.7200000000 0.0270771310 0.0307155757 0.0579214282 0.0065935633 0.7632070000 89319316 95654128 1784324096 -0.7884786725 -0.0059819333 0.1378441751 120 4.7600000000 0.0258295480 0.0306748588 0.0579214282 0.0065683239 0.8350140000 89321010 95654128 1785737216 -0.7957946062 -0.0025273941 0.1455193311 121 4.8000000000 0.0228657797 0.0306103210 0.0579214282 0.0065585237 0.8855410000 89321444 95654128 1787625472 -0.8077149391 0.0023134111 0.1613484472 122 4.8400000000 0.0225341637 0.0305441230 0.0579214282 0.0065400995 0.8548810000 89323138 95654128 1784332288 -0.8081746101 0.0056813275 0.1633155793 123 4.8800000000 0.0224861447 0.0304786109 0.0579214282 0.0065164493 0.8201290000 89324832 95654128 1785729024 -0.8143546581 0.0086008422 0.1695580035 124 4.9200000000 0.0230822731 0.0304189631 0.0579214282 0.0064943900 0.9100210000 89325266 95654128 1787760640 -0.8247439861 0.0092711151 0.1831529289 125 4.9600000000 0.0234155580 0.0303629358 0.0579214282 0.0065007505 0.9349120000 89326960 95654128 1784459264 -0.8279330730 0.0079694428 0.1896238625 126 5.0000000000 0.0215800684 0.0302932305 0.0579214282 0.0064795218 0.8133950000 89330486 95654128 1785729024 -0.8343763947 0.0102674104 0.1974231601 127 5.0400000000 0.0239533931 0.0302433105 0.0579214282 0.0064558218 0.7803720000 89499520 95654128 1787633664 -0.8429452777 0.0069226930 0.2142092288 128 5.0800000000 0.0204395019 0.0301667183 0.0579214282 0.0064383354 0.9864100000 89501214 95654128 1784365056 -0.8501348495 0.0120999627 0.2206285894 129 5.1200000000 0.0186091028 0.0300771244 0.0579214282 0.0064143364 0.7825550000 89513148 95654128 1785729024 -0.8563817739 0.0122199571 0.2277282774 130 5.1600000000 0.0160678085 0.0299693604 0.0579214282 0.0064033281 0.6919020000 89534574 95654128 1787760640 -0.8688892722 0.0168225616 0.2447657287 131 5.2000000000 0.0159222074 0.0298621302 0.0579214282 0.0064239516 0.8093100000 89536268 95654128 1784459264 -0.8720468879 0.0159282014 0.2495713979 132 5.2400000000 0.0136288619 0.0297391509 0.0579214282 0.0064398444 0.7169830000 89537962 95654128 1785720832 -0.8731461167 0.0165977869 0.2495514303 133 5.2800000000 0.0149364090 0.0296278521 0.0579214282 0.0064322665 0.7818250000 89538396 95654128 1787752448 -0.8839902878 0.0180718079 0.2664527297 134 5.3200000000 0.0137357786 0.0295092545 0.0579214282 0.0064360992 1.0049090000 89540090 95654128 1784451072 -0.8964167833 0.0252117831 0.2831790447 135 5.3600000000 0.0150427567 0.0294020953 0.0579214282 0.0064582669 1.9619480000 89541784 95654128 1785720832 -0.8977207541 0.0271264333 0.2872043252 136 5.4000000000 0.0154503034 0.0292995086 0.0579214282 0.0064960759 1.3648140000 89542218 95654128 1787514880 -0.9031008482 0.0225248933 0.2983379960 137 5.4400000000 0.0155392289 0.0291990686 0.0579214282 0.0065613938 1.9083920000 89543912 95654128 1784451072 -0.9075461626 0.0250854697 0.3084815145 138 5.4800000000 0.0161034241 0.0291041726 0.0579214282 0.0065989041 1.9968440000 89545606 95654128 1785720832 -0.9123411775 0.0227003153 0.3127750158 139 5.5200000000 0.0175384823 0.0290209662 0.0579214282 0.0066462993 1.7764020000 89546040 95654128 1787752448 -0.9166138172 0.0187041890 0.3174695671 140 5.5600000000 0.0195210259 0.0289531095 0.0579214282 0.0067193792 1.8045110000 89547734 95654128 1784451072 -0.9243918061 0.0186147615 0.3304921389 141 5.6000000000 0.0200900808 0.0288902511 0.0579214282 0.0067533244 1.5076910000 89549428 95654128 1785720832 -0.9290360808 0.0186774395 0.3360942900 142 5.6400000000 0.0209282320 0.0288341806 0.0579214282 0.0067979618 1.9052170000 89549862 95654128 1787371520 -0.9379159212 0.0166426152 0.3503313065 143 5.6800000000 0.0199920647 0.0287723476 0.0579214282 0.0068764021 1.3204890000 89551556 95654128 1784451072 -0.9444140196 0.0169597734 0.3611678481 144 5.7200000000 0.0196611620 0.0287090755 0.0579214282 0.0069115418 1.8730730000 89553250 95654128 1785847808 -0.9500797987 0.0195193514 0.3698610961 145 5.7600000000 0.0165853519 0.0286254636 0.0579214282 0.0069106715 1.7976920000 89553684 95654128 1787625472 -0.9583642483 0.0226784609 0.3773634732 146 5.8000000000 0.0162087958 0.0285404179 0.0579214282 0.0068987268 1.6077070000 89555378 95654128 1784324096 -0.9648678899 0.0219850652 0.3867862821 147 5.8400000000 0.0172792263 0.0284638112 0.0579214282 0.0068818670 1.9361330000 89557072 95654128 1785720832 -0.9741273522 0.0212373845 0.4071164727 148 5.8800000000 0.0160249975 0.0283797651 0.0579214282 0.0068596778 2.2222470000 89558630 95654128 1787650048 -0.9760413766 0.0210795365 0.4117130041 149 5.9200000000 0.0148651544 0.0282890631 0.0579214282 0.0068408128 2.2476210000 89728936 95654128 1784459264 -0.9814405441 0.0214142241 0.4234722853 150 5.9600000000 0.0139919724 0.0281937491 0.0579214282 0.0068213832 1.7303690000 89730630 95654128 1785856000 -0.9851716757 0.0208998304 0.4334156215 151 6.0000000000 0.0139526771 0.0280994374 0.0579214282 0.0068021333 1.4567910000 89731064 95654128 1787760640 -0.9891383648 0.0240329579 0.4423284829 152 6.0400000000 0.0130399456 0.0280003618 0.0579214282 0.0067862874 1.4110900000 89732758 95654128 1784578048 -0.9932015538 0.0242985524 0.4535379112 153 6.0800000000 0.0118779149 0.0278949863 0.0579214282 0.0067716130 1.8457210000 89734452 95654128 1785847808 -0.9977104664 0.0241812542 0.4628433585 154 6.1200000000 0.0118686454 0.0277909192 0.0579214282 0.0067908464 2.0381980000 89734886 95654128 1787752448 -1.0025426149 0.0250200108 0.4750583768 155 6.1600000000 0.0114054233 0.0276852063 0.0579214282 0.0068372433 1.4707990000 89736580 95654128 1784451072 -1.0055862665 0.0250937324 0.4825132191 156 6.2000000000 0.0176983215 0.0276211878 0.0579214282 0.0069872616 1.7037880000 89738274 95654128 1785720832 -1.0039385557 0.0206453744 0.4942879081 157 6.2400000000 0.0168636590 0.0275526685 0.0579214282 0.0070826250 2.2150620000 89738708 95654128 1787625472 -1.0065557957 0.0249660388 0.5055611730 158 6.2800000000 0.0171978716 0.0274871318 0.0579214282 0.0071466587 1.7866340000 89740402 95654128 1784451072 -1.0096725225 0.0225957502 0.5215225220 159 6.3200000000 0.0182614960 0.0274291089 0.0579214282 0.0071839705 1.3903300000 89742096 95654128 1785720832 -1.0092597008 0.0198547505 0.5291106701 160 6.3600000000 0.0184057187 0.0273727128 0.0579214282 0.0072197520 1.6475130000 89742530 95654128 1787752448 -1.0102256536 0.0215592477 0.5444574356 161 6.4000000000 0.0169238131 0.0273078128 0.0579214282 0.0072066823 1.8157060000 89744224 95654128 1784578048 -1.0101635456 0.0237113554 0.5567666292 162 6.4400000000 0.0194015820 0.0272590089 0.0579214282 0.0071868535 1.6570420000 89745918 95654128 1785847808 -1.0087559223 0.0228141267 0.5657479763 163 6.4800000000 0.0160876457 0.0271904729 0.0579214282 0.0071703987 1.7513610000 89746352 95654128 1787752448 -1.0125888586 0.0259071458 0.5805721283 164 6.5200000000 0.0193154011 0.0271424542 0.0579214282 0.0071508887 1.7515000000 89748046 95654128 1784451072 -1.0113166571 0.0247286316 0.5895068645 165 6.5600000000 0.0179798547 0.0270869233 0.0579214282 0.0071444728 1.6623210000 89749740 95654128 1785720832 -1.0135757923 0.0273056775 0.6080531478 166 6.6000000000 0.0190500040 0.0270385081 0.0579214282 0.0071608050 1.3384950000 89750174 95654128 1787752448 -1.0126920938 0.0290340409 0.6180447340 167 6.6400000000 0.0179350767 0.0269839965 0.0579214282 0.0071691521 1.7270840000 89751868 95654128 1784442880 -1.0131326914 0.0318487883 0.6287825108 168 6.6800000000 0.0167594329 0.0269231360 0.0579214282 0.0071723077 1.6131850000 89753562 95654128 1785847808 -1.0142425299 0.0298035908 0.6415591836 169 6.7200000000 0.0150954360 0.0268531496 0.0579214282 0.0071577207 2.5349320000 89753996 95654128 1787371520 -1.0145226717 0.0288763437 0.6577209234 170 6.7600000000 0.0152994720 0.0267851868 0.0579214282 0.0071528561 1.4607990000 89755690 95654128 1784197120 -1.0159326792 0.0318230875 0.6751407981 171 6.8000000000 0.0151837999 0.0267173425 0.0579214282 0.0071475212 1.3278640000 89757384 95654128 1785593856 -1.0153113604 0.0336033925 0.6841329336 172 6.8400000000 0.0143346181 0.0266453499 0.0579214282 0.0071282551 2.1078830000 89757818 95654128 1787490304 -1.0164759159 0.0382597372 0.6975363493 173 6.8800000000 0.0148311164 0.0265770595 0.0579214282 0.0071087310 1.5642850000 89759512 95654128 1784315904 -1.0174967051 0.0416802391 0.7112889290 174 6.9200000000 0.0170609392 0.0265223692 0.0579214282 0.0070897243 0.8961320000 89761206 95654128 1785729024 -1.0184931755 0.0467767119 0.7229870558 175 6.9600000000 0.0178327058 0.0264727139 0.0579214282 0.0070698118 1.5608530000 89761640 95654128 1787617280 -1.0184491873 0.0495553948 0.7350307107 176 7.0000000000 0.0168235507 0.0264178891 0.0579214282 0.0070556850 2.1507210000 89763334 95654128 1784442880 -1.0214508772 0.0503683612 0.7508494258 177 7.0400000000 0.0177501943 0.0263689191 0.0579214282 0.0070742135 0.5989810000 89765028 95654128 1785839616 -1.0223792791 0.0501112156 0.7581368685 178 7.0800000000 0.0176451299 0.0263199091 0.0579214282 0.0070607111 0.8072240000 89765462 95654128 1787744256 -1.0217084885 0.0489567593 0.7647960782 179 7.1200000000 0.0156977624 0.0262605675 0.0579214282 0.0070477754 1.2029410000 89767140 95654128 1784315904 -1.0202707052 0.0479263477 0.7781007290 180 7.1600000000 0.0145659707 0.0261955975 0.0579214282 0.0070288344 1.9395270000 89768834 95654128 1785712640 -1.0206139088 0.0503243543 0.7923195362 181 7.2000000000 0.0115698660 0.0261147923 0.0579214282 0.0070146069 1.6976840000 89769268 95654128 1787744256 -1.0196911097 0.0499572828 0.8060083985 182 7.2400000000 0.0112826163 0.0260332969 0.0579214282 0.0069981774 1.6181140000 89770962 95654128 1784442880 -1.0201274157 0.0510505736 0.8211856484 183 7.2800000000 0.0113347052 0.0259529767 0.0579214282 0.0069833050 0.9177930000 89772656 95654128 1785712640 -1.0222659111 0.0510079227 0.8367791772 184 7.3200000000 0.0111920759 0.0258727544 0.0579214282 0.0069646730 0.7331770000 89773090 95654128 1787617280 -1.0195993185 0.0492187552 0.8463376760 185 7.3600000000 0.0108329672 0.0257914583 0.0579214282 0.0069495244 0.6987300000 89775748 95654128 1784442880 -1.0188115835 0.0508066788 0.8632289171 186 7.4000000000 0.0110133253 0.0257120059 0.0579214282 0.0069379344 0.7891130000 89946066 95654128 1785729024 -1.0177276134 0.0480690897 0.8793559670 187 7.4400000000 0.0124612805 0.0256411464 0.0579214282 0.0069324024 0.9143590000 89946500 95654128 1787871232 -1.0135282278 0.0474455841 0.8859451413 188 7.4800000000 0.0107580777 0.0255619812 0.0579214282 0.0069350121 1.6219270000 89948194 95654128 1784315904 -1.0131491423 0.0511175133 0.9030993581 189 7.5200000000 0.0118134227 0.0254892375 0.0579214282 0.0069185706 1.4973050000 89949888 95654128 1785585664 -1.0124279261 0.0573944002 0.9220989943 190 7.5600000000 0.0123682488 0.0254201796 0.0579214282 0.0069089632 1.8858780000 89950322 95654128 1787617280 -1.0116258860 0.0583597533 0.9389329553 191 7.6000000000 0.0098266238 0.0253385380 0.0579214282 0.0068994495 1.9279700000 89952016 95654128 1784442880 -1.0099155903 0.0561986342 0.9540011287 192 7.6400000000 0.0095348731 0.0252562272 0.0579214282 0.0068896308 1.8154690000 89953726 95654128 1785847808 -1.0081065893 0.0619675517 0.9699847698 193 7.6800000000 0.0101582939 0.0251779996 0.0579214282 0.0068914007 1.9175240000 89954160 95654128 1787625472 -1.0064060688 0.0621444248 0.9864832759 194 7.7200000000 0.0110296551 0.0251050700 0.0579214282 0.0068893745 1.8882120000 89955854 95654128 1784451072 -1.0068050623 0.0584138259 1.0018631220 195 7.7600000000 0.0084971255 0.0250199010 0.0579214282 0.0068970800 1.6669690000 89957548 95654128 1785712640 -1.0049296618 0.0570787936 1.0170031786 196 7.8000000000 0.0071734795 0.0249288479 0.0579214282 0.0069378500 1.9254180000 89957982 95654128 1787617280 -1.0035095215 0.0610969439 1.0361272097 197 7.8400000000 0.0082898913 0.0248443862 0.0579214282 0.0069595152 1.8823930000 89959676 95654128 1784442880 -1.0010234118 0.0639299080 1.0458024740 198 7.8800000000 0.0082474928 0.0247605635 0.0579214282 0.0069816574 1.4643450000 89961386 95654128 1785712640 -0.9991974235 0.0647572950 1.0614547729 199 7.9200000000 0.0090149045 0.0246814396 0.0579214282 0.0069719000 2.1236450000 89961820 95654128 1787363328 -0.9981929064 0.0682603717 1.0773441792 200 7.9600000000 0.0102082435 0.0246090736 0.0579214282 0.0069592566 1.2018130000 89963514 95654128 1784442880 -0.9982877374 0.0670557767 1.0900982618 201 8.0000000000 0.0095738703 0.0245342716 0.0579214282 0.0069750420 1.5711050000 89965208 95654128 1785966592 -0.9975169897 0.0686830878 1.1101659536 202 8.0400000000 0.0093615195 0.0244591589 0.0579214282 0.0069889621 2.1145310000 89965642 95654128 1787744256 -0.9943914413 0.0688900948 1.1203366518 203 8.0800000000 0.0115492241 0.0243955632 0.0579214282 0.0070052796 1.4153080000 89967336 95654128 1785204736 -0.9915747046 0.0715257078 1.1354516745 204 8.1200000000 0.0103411106 0.0243266688 0.0579214282 0.0069964821 1.3792880000 89969030 95654128 1786728448 -0.9898204803 0.0707107484 1.1492084265 205 8.1600000000 0.0111604100 0.0242624432 0.0579214282 0.0069861072 0.8141070000 89969464 95654128 1784696832 -0.9880528450 0.0717621371 1.1616055965 206 8.1999999990 0.0123151755 0.0242044467 0.0579214282 0.0069780029 0.8290380000 89971158 95654128 1786220544 -0.9853022099 0.0709643960 1.1731170416 207 8.2400000000 0.0136678275 0.0241535452 0.0579214282 0.0069685600 0.9383540000 89972852 95654128 1785585664 -0.9810675979 0.0735692084 1.1849937439 208 8.2799999990 0.0155465659 0.0241121655 0.0579214282 0.0069542685 1.8061870000 89973286 95654128 1787109376 -0.9771829844 0.0766329691 1.1960911751 209 8.3200000000 0.0147991162 0.0240676054 0.0579214282 0.0069501430 1.7930410000 89974980 95654128 1785204736 -0.9722246528 0.0796230733 1.2104538679 210 8.3599999990 0.0104081966 0.0240025606 0.0579214282 0.0069775955 1.8349570000 89976674 95654128 1786855424 -0.9661408663 0.0778403729 1.2251715660 211 8.4000000000 0.0102053937 0.0239371712 0.0579214282 0.0070020759 1.6312390000 89977108 95654128 1784823808 -0.9631754160 0.0767210796 1.2407513857 212 8.4399999990 0.0115072476 0.0238785395 0.0579214282 0.0069864595 1.9017940000 89978802 95654128 1786220544 -0.9552294016 0.0799506530 1.2503455877 213 8.4800000000 0.0127950152 0.0238265042 0.0579214282 0.0069856293 1.8874470000 89980496 95654128 1785839616 -0.9491125941 0.0853028074 1.2645062208 214 8.5200000000 0.0148527371 0.0237845707 0.0579214282 0.0070624569 1.6526860000 89980930 95654128 1787371520 -0.9421975017 0.0894270316 1.2783499956 215 8.5600000000 0.0141181471 0.0237396106 0.0579214282 0.0070695078 1.6422360000 89982624 95654128 1785085952 -0.9346227646 0.0874540061 1.2881797552 216 8.6000000000 0.0187940206 0.0237167143 0.0579214282 0.0070568874 1.5776650000 89985174 95654128 1786482688 -0.9292382598 0.0944767073 1.2976845503 217 8.6400000000 0.0197659656 0.0236985081 0.0579214282 0.0070907348 1.0067620000 90154220 95654128 1784958976 -0.9205182195 0.1001397967 1.3168492317 218 8.6800000000 0.0181042477 0.0236728464 0.0579214282 0.0071419538 1.1065070000 90155914 95654128 1786482688 -0.9114444852 0.0986407325 1.3272169828 219 8.7200000000 0.0188094396 0.0236506390 0.0579214282 0.0071430476 1.6184120000 90157608 95654128 1785712640 -0.9022754431 0.1006932184 1.3356475830 220 8.7600000000 0.0213683024 0.0236402648 0.0579214282 0.0071470804 1.7130910000 90158042 95654128 1787236352 -0.8929226995 0.1074595600 1.3462412357 221 8.8000000000 0.0243515149 0.0236434831 0.0579214282 0.0071971194 1.5633000000 90159752 95654128 1784713216 -0.8839410543 0.1126336083 1.3596363068 222 8.8400000000 0.0260448959 0.0236543003 0.0579214282 0.0072019923 1.8017270000 90161446 95654128 1786347520 -0.8748844266 0.1151840910 1.3718118668 223 8.8800000000 0.0269400757 0.0236690347 0.0579214282 0.0072050812 1.9891530000 90161880 95654128 1785839616 -0.8650854230 0.1184052750 1.3804613352 224 8.9200000000 0.0269307867 0.0236835961 0.0579214282 0.0072114329 1.4941110000 90163574 95654128 1787236352 -0.8549585938 0.1206643358 1.3908132315 225 8.9600000000 0.0266879126 0.0236969486 0.0579214282 0.0072073771 2.0403750000 90165268 95654128 1784569856 -0.8444885015 0.1229560077 1.3987947702 226 9.0000000000 0.0257262010 0.0237059276 0.0579214282 0.0071927638 1.6589420000 90165702 95654128 1785966592 -0.8337552547 0.1266225576 1.4115000963 227 9.0400000000 0.0260899160 0.0237164297 0.0579214282 0.0071782943 2.0820830000 90169112 95654128 1787744256 -0.8219773173 0.1328319609 1.4200940132 228 9.0800000000 0.0257655568 0.0237254171 0.0579214282 0.0071955408 1.4893040000 90339406 95654128 1784442880 -0.8116317391 0.1365596652 1.4323554039 229 9.1200000000 0.0258847978 0.0237348468 0.0579214282 0.0072433332 2.1098970000 90339840 95654128 1785966592 -0.8004600406 0.1410366446 1.4397077560 230 9.1600000000 0.0257579200 0.0237436427 0.0579214282 0.0073540725 2.2294440000 90341534 95654128 1787871232 -0.7907637358 0.1441377848 1.4466080666 231 9.2000000000 0.0267141908 0.0237565022 0.0579214282 0.0075538884 1.8999630000 90343228 95654128 1784569856 -0.7811719775 0.1454791129 1.4521679878 232 9.2400000000 0.0261904411 0.0237669934 0.0579214282 0.0077093475 1.8175490000 90344702 95654128 1785966592 -0.7710043192 0.1484470367 1.4608199596 233 9.2800000000 0.0260454081 0.0237767720 0.0579214282 0.0078499716 0.8893840000 90515020 95654128 1787871232 -0.7613379955 0.1517378390 1.4688830376 234 9.3200000000 0.0260315407 0.0237864077 0.0579214282 0.0079543036 1.2170340000 90516714 95654128 1784823808 -0.7516967654 0.1557824612 1.4765468836 235 9.3600000000 0.0237452295 0.0237862325 0.0579214282 0.0080323237 1.5691080000 90517148 95654128 1786228736 -0.7414916754 0.1573003381 1.4857368469 236 9.4000000000 0.0242026839 0.0237879971 0.0579214282 0.0080887485 1.8364210000 90518842 95654128 1785466880 -0.7316058278 0.1608708799 1.4939966202 237 9.4400000000 0.0226259306 0.0237830939 0.0579214282 0.0081168165 1.7521370000 90520536 95654128 1786990592 -0.7210558653 0.1641008258 1.5015947819 238 9.4800000000 0.0223214366 0.0237769525 0.0579214282 0.0081403130 1.6508750000 90520970 95654128 1784451072 -0.7097152472 0.1702447832 1.5097526312 239 9.5200000000 0.0233071689 0.0237749868 0.0579214282 0.0081818423 2.0861210000 90522664 95654128 1785712640 -0.6995062828 0.1764553189 1.5171899796 240 9.5600000000 0.0225673523 0.0237699550 0.0579214282 0.0082409351 0.8796020000 90524358 95654128 1787617280 -0.6887821555 0.1810045391 1.5265324116 241 9.6000000000 0.0232643727 0.0237678572 0.0579214282 0.0082905657 0.8687290000 90524792 95654128 1784205312 -0.6793721914 0.1838463396 1.5379115343 242 9.6400000000 0.0235932339 0.0237671356 0.0579214282 0.0083087358 0.7879190000 90527786 95654128 1785585664 -0.6700292230 0.1871881783 1.5491765738 243 9.6800000000 0.0232091378 0.0237648393 0.0579214282 0.0083197652 0.7497740000 90698108 95654128 1787617280 -0.6583247781 0.1929699033 1.5556665659 244 9.7200000000 0.0212616231 0.0237545802 0.0579214282 0.0083627614 0.9672270000 90698542 95654128 1784569856 -0.6461988091 0.1976563185 1.5640242100 245 9.7600000000 0.0234684609 0.0237534124 0.0579214282 0.0084203442 1.5093260000 90700236 95654128 1785839616 -0.6372632980 0.1994018555 1.5652781725 246 9.8000000000 0.0216557048 0.0237448851 0.0579214282 0.0084429255 1.6190500000 90701930 95654128 1787871232 -0.6260151863 0.2014349401 1.5759352446 247 9.8400000000 0.0222790204 0.0237389505 0.0579214282 0.0084491019 1.6899850000 90703540 95654128 1784442880 -0.6164439321 0.2034046501 1.5877830982 248 9.8800000000 0.0225735083 0.0237342511 0.0579214282 0.0084350443 1.7020060000 90873874 95654128 1785839616 -0.6075889468 0.2054803371 1.5969365835 249 9.9200000000 0.0218698289 0.0237267635 0.0579214282 0.0084193337 2.3344430000 90875568 95654128 1787998208 -0.5972439051 0.2067947090 1.6036705971 250 9.9600000000 0.0191836711 0.0237085911 0.0579214282 0.0084031179 1.4860160000 90876002 95654128 1784569856 -0.5859820247 0.2071330547 1.6140077114 251 10.0000000000 0.0178366173 0.0236851968 0.0579214282 0.0083872762 1.4070650000 90877696 95654128 1785839616 -0.5740854144 0.2091665417 1.6218731403 252 10.0400000000 0.0158494450 0.0236541025 0.0579214282 0.0083726765 1.8805150000 90879390 95654128 1787871232 -0.5641298890 0.2068720162 1.6330674887 253 10.0800000000 0.0173047241 0.0236290062 0.0579214282 0.0083575120 2.1299140000 90879824 95654128 1784569856 -0.5577459335 0.2040374428 1.6412034035 254 10.1200000000 0.0195605587 0.0236129886 0.0579214282 0.0083738148 1.5987290000 90881518 95654128 1785966592 -0.5492286086 0.2107834369 1.6517235041 255 10.1600000000 0.0210954733 0.0236031160 0.0579214282 0.0083887925 2.1767450000 90883212 95654128 1787617280 -0.5387838483 0.2193040401 1.6607465744 256 10.2000000000 0.0220482964 0.0235970425 0.0579214282 0.0083755950 0.8600550000 90883646 95654128 1784569856 -0.5283293724 0.2247700542 1.6688028574 257 10.2400000000 0.0218356140 0.0235901887 0.0579214282 0.0083616033 1.0821740000 90905820 95654128 1786093568 -0.5191927552 0.2235572189 1.6762878895 258 10.2800000000 0.0224390086 0.0235857268 0.0579214282 0.0083454099 1.8631370000 90949498 95654128 1787879424 -0.5093075037 0.2296508849 1.6862938404 259 10.3200000000 0.0231455863 0.0235840274 0.0579214282 0.0083409250 1.5294170000 90949932 95654128 1784578048 -0.4994071424 0.2341977060 1.6931440830 260 10.3600000000 0.0232536644 0.0235827568 0.0579214282 0.0083474656 2.1181390000 90951626 95654128 1785974784 -0.4893217981 0.2364068776 1.7027968168 261 10.4000000000 0.0218226183 0.0235760129 0.0579214282 0.0083463825 1.6342510000 90954392 95654128 1787879424 -0.4793476164 0.2346778661 1.7103972435 262 10.4400000000 0.0221508201 0.0235705733 0.0579214282 0.0083327603 1.6829560000 91123466 95654128 1784451072 -0.4698924124 0.2346398681 1.7155033350 263 10.4800000000 0.0216903724 0.0235634242 0.0579214282 0.0083187800 1.6622550000 91125160 95654128 1785966592 -0.4592153132 0.2348984182 1.7198629379 264 10.5200000000 0.0212414619 0.0235546289 0.0579214282 0.0083080695 2.0202230000 91126854 95654128 1787744256 -0.4487540722 0.2341920435 1.7260868549 265 10.5600000000 0.0233312789 0.0235537861 0.0579214282 0.0082927953 1.5877370000 91127272 95654128 1784442880 -0.4385961890 0.2385801524 1.7338666916 266 10.6000000000 0.0221111067 0.0235483625 0.0579214282 0.0082807533 1.5205680000 91128966 95654128 1785839616 -0.4259497821 0.2395879328 1.7375667095 267 10.6400000000 0.0229922924 0.0235462798 0.0579214282 0.0082760600 1.6217040000 91130660 95654128 1787871232 -0.4151247442 0.2390449643 1.7405565977 268 10.6800000000 0.0220820922 0.0235408164 0.0579214282 0.0082708706 1.6841990000 91131094 95654128 1784442880 -0.4038037658 0.2378978580 1.7480330467 269 10.7200000000 0.0230679121 0.0235390584 0.0579214282 0.0082584951 1.6590430000 91132788 95654128 1785839616 -0.3921903372 0.2382534444 1.7490246296 270 10.7600000000 0.0228107311 0.0235363609 0.0579214282 0.0082505353 1.5298280000 91134482 95654128 1787744256 -0.3675850928 0.2425645888 1.7604314089 271 10.8000000000 0.0224034991 0.0235321806 0.0579214282 0.0082671096 1.4917050000 91134916 95654128 1784332288 -0.3529522717 0.2458042651 1.7633721828 272 10.8400000000 0.0213398580 0.0235241206 0.0579214282 0.0083303727 1.8505340000 91136610 95654128 1785712640 -0.3405998349 0.2429685593 1.7672864199 273 10.8800000000 0.0212301314 0.0235157177 0.0579214282 0.0083390386 1.7345600000 91138304 95654128 1787744256 -0.3285708129 0.2438706011 1.7735836506 274 10.9200000000 0.0208036732 0.0235058197 0.0579214282 0.0083455682 1.8378740000 91138738 95654128 1784442880 -0.3150394559 0.2449855804 1.7780389786 275 10.9600000000 0.0200604610 0.0234932912 0.0579214282 0.0083481277 1.9059770000 91140432 95654128 1785712640 -0.3017296493 0.2437627614 1.7793353796 276 11.0000000000 0.0192374606 0.0234778715 0.0579214282 0.0083443760 1.4257030000 91142126 95654128 1787617280 -0.2880196273 0.2446673810 1.7830364704 277 11.0400000000 0.0196607728 0.0234640913 0.0579214282 0.0083497873 1.5703840000 91142560 95654128 1784442880 -0.2744980752 0.2468149513 1.7867724895 278 11.0800000000 0.0192460846 0.0234489187 0.0579214282 0.0083559489 1.4894120000 91144254 95654128 1785974784 -0.2609165311 0.2482227683 1.7906779051 279 11.1200000000 0.0200554840 0.0234367558 0.0579214282 0.0083662658 1.5246200000 91145948 95654128 1787752448 -0.2479268014 0.2504865825 1.7950421572 280 11.1600000000 0.0210315362 0.0234281657 0.0579214282 0.0083732125 1.9718970000 91147398 95654128 1784451072 -0.2342104316 0.2537491322 1.7974919081 281 11.2000000000 0.0207625609 0.0234186796 0.0579214282 0.0083788130 1.7114920000 91317740 95654128 1785720832 -0.2205415517 0.2546885610 1.8002958298 282 11.2400000000 0.0201240201 0.0234069964 0.0579214282 0.0083743629 1.4892970000 91319434 95654128 1787625472 -0.2085063159 0.2534933984 1.8062243462 283 11.2800000000 0.0208807569 0.0233980698 0.0579214282 0.0083597325 1.2073840000 91319868 95654128 1784451072 -0.1968604922 0.2553496659 1.8088343143 284 11.3200000000 0.0206883028 0.0233885283 0.0579214282 0.0083483497 1.7977920000 91321562 95654128 1785847808 -0.1843769103 0.2569415867 1.8136308193 285 11.3600000000 0.0210846961 0.0233804447 0.0579214282 0.0083453848 1.4115310000 91323272 95654128 1787625472 -0.1728685051 0.2580144107 1.8166133165 286 11.4000000000 0.0227111988 0.0233781047 0.0579214282 0.0083373885 1.6327560000 91323706 95654128 1784451072 -0.1634000391 0.2591908872 1.8202078342 287 11.4400000000 0.0220124684 0.0233733464 0.0579214282 0.0083228436 1.8735360000 91325400 95654128 1785847808 -0.1534662694 0.2576713860 1.8232558966 288 11.4800000000 0.0223166067 0.0233696771 0.0579214282 0.0083092224 1.7562760000 91327094 95654128 1787752448 -0.1454109401 0.2579282522 1.8284803629 289 11.5200000000 0.0230784807 0.0233686695 0.0579214282 0.0082958106 2.6910280000 91327528 95654128 1784451072 -0.1377053708 0.2582012713 1.8350570202 290 11.5600000000 0.0223473273 0.0233651477 0.0579214282 0.0082876170 0.8558090000 91329222 95654128 1785847808 -0.1294296682 0.2569612265 1.8397431374 291 11.6000000000 0.0232015699 0.0233645855 0.0579214282 0.0082776184 0.8688760000 91330916 95654128 1787625472 -0.1223912388 0.2553580701 1.8444873095 292 11.6400000000 0.0230302569 0.0233634406 0.0579214282 0.0082650014 1.1816140000 91331350 95654128 1784451072 -0.1147953346 0.2552359402 1.8498066664 293 11.6800000000 0.0244445223 0.0233671303 0.0579214282 0.0082513312 2.1816500000 91333060 95654128 1785847808 -0.1082524434 0.2572355270 1.8564246893 294 11.7200000000 0.0239026025 0.0233689516 0.0579214282 0.0082387075 1.0094190000 91334754 95654128 1787768832 -0.1026393026 0.2548060715 1.8634872437 295 11.7600000000 0.0247581638 0.0233736608 0.0579214282 0.0082303362 0.8664170000 91335188 95654128 1784451072 -0.0973805487 0.2562013268 1.8709396124 296 11.8000000000 0.0235045962 0.0233741032 0.0579214282 0.0082215694 0.8969840000 91336882 95654128 1785737216 -0.0908034816 0.2557905614 1.8783795834 297 11.8400000000 0.0233494341 0.0233740201 0.0579214282 0.0082140152 0.8629730000 91338576 95654128 1787752448 -0.0852290392 0.2555724978 1.8855577707 298 11.8800000000 0.0229252446 0.0233725141 0.0579214282 0.0082077825 0.8323900000 91339010 95654128 1784451072 -0.0806083009 0.2542114556 1.8939430714 299 11.9200000000 0.0230144318 0.0233713165 0.0579214282 0.0081987081 0.6770370000 91340704 95654128 1785720832 -0.0758153722 0.2552866936 1.9038636684 300 11.9600000000 0.0229752064 0.0233699962 0.0579214282 0.0081863732 0.7138520000 91342398 95654128 1787625472 -0.0704574510 0.2551828027 1.9102672338 301 12.0000000000 0.0238935482 0.0233717356 0.0579214282 0.0081727954 0.6579040000 91342848 95654128 1784451072 -0.0671335310 0.2563236952 1.9206035137 302 12.0400000000 0.0249711256 0.0233770315 0.0579214282 0.0081612831 0.6535870000 91344640 95654128 1785720832 -0.0635858923 0.2566105425 1.9292240143 303 12.0800000000 0.0251333341 0.0233828279 0.0579214282 0.0081551095 0.6103970000 91346334 95654128 1787752448 -0.0597501583 0.2574878335 1.9401847124 304 12.1200000000 0.0255919434 0.0233900947 0.0579214282 0.0081511300 0.8803260000 91346768 95654128 1784467456 -0.0562566631 0.2581177056 1.9505712986 305 12.1600000000 0.0269242302 0.0234016821 0.0579214282 0.0081492088 0.9419680000 91348602 95654128 1785847808 -0.0530449897 0.2591179609 1.9609657526 306 12.2000000000 0.0278080627 0.0234160820 0.0579214282 0.0081386478 0.9372030000 91349036 95654128 1787633664 -0.0505166315 0.2598167062 1.9733163118 307 12.2400000000 0.0281411316 0.0234314731 0.0579214282 0.0081404139 0.7332180000 91350730 95654128 1784586240 -0.0474809110 0.2603839040 1.9840626717 308 12.2800000000 0.0281498879 0.0234467926 0.0579214282 0.0081453822 0.8545740000 91352424 95654128 1785856000 -0.0448711626 0.2589284778 1.9934633970 309 12.3200000000 0.0286956318 0.0234637791 0.0579214282 0.0081574197 0.7702850000 91354482 95654128 1787760640 -0.0431581698 0.2592493892 2.0042986870 310 12.3600000000 0.0289843492 0.0234815874 0.0579214282 0.0081770069 0.7762440000 91524820 95654128 1784205312 -0.0418293253 0.2590121329 2.0164403915 311 12.4000000000 0.0288051162 0.0234987049 0.0579214282 0.0081858082 0.7799910000 91526654 95654128 1785602048 -0.0402335636 0.2594797015 2.0281786919 312 12.4400000000 0.0294168405 0.0235176733 0.0579214282 0.0082229807 0.8790380000 91527088 95654128 1787633664 -0.0389642529 0.2583525777 2.0513169765 313 12.4800000000 0.0296117272 0.0235371431 0.0579214282 0.0082173527 0.9282270000 91528782 95654128 1784332288 -0.0384669043 0.2584865391 2.0621240139 314 12.5200000000 0.0299894754 0.0235576919 0.0579214282 0.0082104084 0.8347780000 91530476 95654128 1785729024 -0.0383672602 0.2583246231 2.0749330521 315 12.5600000000 0.0297002997 0.0235771922 0.0579214282 0.0082070538 0.7643700000 91530910 95654128 1787498496 -0.0383718349 0.2585912943 2.0879216194 316 12.6000000000 0.0291886739 0.0235949501 0.0579214282 0.0081964086 0.6362970000 91532604 95654128 1784500224 -0.0383993387 0.2575074732 2.0999131203 317 12.6400000000 0.0284204111 0.0236101724 0.0579214282 0.0081839622 0.6204680000 91534438 95654128 1785847808 -0.0384137630 0.2566980124 2.1127161980 318 12.6800000000 0.0276834555 0.0236229814 0.0579214282 0.0081718974 0.6292280000 91534872 95654128 1787625472 -0.0385975577 0.2560142577 2.1249649525 319 12.7200000000 0.0270833950 0.0236338291 0.0579214282 0.0081594833 0.7959780000 91536598 95654128 1784479744 -0.0389791280 0.2551557720 2.1343176365 320 12.7600000000 0.0265790354 0.0236430329 0.0579214282 0.0081471745 0.6854600000 91538292 95654128 1785847808 -0.0401753336 0.2542533278 2.1444830894 321 12.8000000000 0.0264800191 0.0236518709 0.0579214282 0.0081370720 0.6856960000 91538726 95654128 1787752448 -0.0423211381 0.2538166642 2.1562931538 322 12.8400000000 0.0252777543 0.0236569202 0.0579214282 0.0081270458 0.6285200000 91541892 95654128 1784451072 -0.0440554246 0.2521619201 2.1666712761 323 12.8800000000 0.0249983072 0.0236610731 0.0579214282 0.0081225937 0.7327340000 91711094 95654128 1785737216 -0.0460213944 0.2517068684 2.1775822639 324 12.9200000000 0.0243053287 0.0236630615 0.0579214282 0.0081134050 0.8310240000 91712804 95654128 1787879424 -0.0481334329 0.2500334978 2.1885418892 325 12.9600000000 0.0245680809 0.0236658462 0.0579214282 0.0081026820 0.9436740000 91714498 95654128 1784451072 -0.0494626500 0.2520261705 2.2001974583 326 13.0000000000 0.0243412945 0.0236679181 0.0579214282 0.0080922707 0.7572330000 91714948 95654128 1785720832 -0.0506897159 0.2523236275 2.2102911472 327 13.0400000000 0.0258763563 0.0236746718 0.0579214282 0.0080876833 1.0989370000 91716642 95654128 1787752448 -0.0525353588 0.2545717061 2.2238526344 328 13.0800000000 0.0280384142 0.0236879759 0.0579214282 0.0080804183 0.7585780000 91720036 95654128 1784451072 -0.0529730432 0.2583493590 2.2351856232 329 13.1200000000 0.0291503686 0.0237045789 0.0579214282 0.0080713672 0.7283950000 91889442 95654128 1785737216 -0.0543431491 0.2615772188 2.2440524101 330 13.1600000000 0.0303760376 0.0237247954 0.0579214282 0.0080612149 0.7608320000 91891136 95654128 1787879424 -0.0567071214 0.2641208768 2.2506723404 331 13.2000000000 0.0325143375 0.0237513499 0.0579214282 0.0080514863 0.8317590000 91892946 95654128 1784451072 -0.0596503541 0.2675204575 2.2587928772 332 13.2400000000 0.0318873152 0.0237758558 0.0579214282 0.0080429445 0.8769890000 91893380 95654128 1785720832 -0.0609084256 0.2681719661 2.2660102844 333 13.2800000000 0.0328015983 0.0238029602 0.0579214282 0.0080331618 0.8731070000 91895958 95654128 1787752448 -0.0640494898 0.2696861923 2.2718002796 334 13.3200000000 0.0321449265 0.0238279361 0.0579214282 0.0080213731 0.7643930000 91897652 95654128 1784451072 -0.0661729574 0.2691572011 2.2767541409 335 13.3600000000 0.0323761106 0.0238534531 0.0579214282 0.0080105540 0.7660290000 91898342 95654128 1785737216 -0.0681162551 0.2705676556 2.2827129364 336 13.4000000000 0.0338207670 0.0238831177 0.0579214282 0.0079993596 0.8787110000 91900036 95654128 1787404288 -0.0703273267 0.2733802497 2.2874641418 337 13.4400000000 0.0320464596 0.0239073413 0.0579214282 0.0079928991 0.9432620000 91901730 95654128 1784197120 -0.0711326376 0.2738552094 2.2936613560 338 13.4800000000 0.0343289301 0.0239381744 0.0579214282 0.0079951303 0.9892700000 91904004 95654128 1785593856 -0.0737408176 0.2765815854 2.2958831787 339 13.5200000000 0.0367875323 0.0239760781 0.0579214282 0.0080266403 0.8337630000 92074358 95654128 1787498496 -0.0782859772 0.2783490121 2.3020782471 340 13.5600000000 0.0376351774 0.0240162519 0.0579214282 0.0080315879 0.7669260000 92076284 95654128 1784451072 -0.0823154524 0.2789124250 2.3089239597 341 13.6000000000 0.0373655818 0.0240553995 0.0579214282 0.0080293052 0.6985120000 92076718 95654128 1785847808 -0.0842106417 0.2792941034 2.3138263226 342 13.6400000000 0.0370913260 0.0240935162 0.0579214282 0.0080212793 0.7045690000 92078552 95654128 1787625472 -0.0858894363 0.2795583606 2.3190040588 343 13.6800000000 0.0387693197 0.0241363028 0.0579214282 0.0080116381 0.9530070000 92079102 95654128 1784459264 -0.0881949291 0.2815168202 2.3225555420 344 13.7200000000 0.0387423970 0.0241787624 0.0579214282 0.0080009613 0.6882440000 92082444 95654128 1785856000 -0.0892064795 0.2829162776 2.3272516727 345 13.7600000000 0.0384929329 0.0242202528 0.0579214282 0.0079934715 0.7721930000 92252922 95654128 1787633664 -0.0911818147 0.2824205160 2.3329110146 346 13.8000000000 0.0376712345 0.0242591284 0.0579214282 0.0079880202 1.0913390000 92253356 95654128 1784332288 -0.0923031643 0.2816430926 2.3379793167 347 13.8400000000 0.0362595059 0.0242937116 0.0579214282 0.0079781217 1.8745630000 92255166 95654128 1785729024 -0.0935405046 0.2783293724 2.3403215408 348 13.8800000000 0.0351224989 0.0243248288 0.0579214282 0.0079685402 2.1377330000 92256860 95654128 1787760640 -0.0917393491 0.2794216871 2.3430097103 349 13.9200000000 0.0332802013 0.0243504889 0.0579214282 0.0079624421 1.5706890000 92257410 95654128 1784586240 -0.0913330019 0.2782481313 2.3487761021 350 13.9600000000 0.0306753926 0.0243685601 0.0579214282 0.0079644330 1.6360190000 92261684 95654128 1785847808 -0.0896724388 0.2759153247 2.3573000431 351 14.0000000000 0.0299613830 0.0243844941 0.0579214282 0.0079536848 1.9018320000 92432022 95654128 1787752448 -0.0884928405 0.2734820247 2.3580925465 352 14.0400000000 0.0285390373 0.0243962967 0.0579214282 0.0079454381 2.3729260000 92432456 95654128 1784451072 -0.0893965214 0.2703707218 2.3629045486 353 14.0800000000 0.0277466886 0.0244057879 0.0579214282 0.0079343530 2.2116850000 92434150 95654128 1785720832 -0.0892228037 0.2688081264 2.3674812317 354 14.1200000000 0.0277552474 0.0244152497 0.0579214282 0.0079233623 1.8415020000 92435960 95654128 1787752448 -0.0891706645 0.2687677741 2.3720431328 355 14.1600000000 0.0271485727 0.0244229492 0.0579214282 0.0079129915 1.4797210000 92436394 95654128 1784578048 -0.0889965296 0.2675122023 2.3772411346 356 14.2000000000 0.0272457767 0.0244308785 0.0579214282 0.0079042816 2.2809250000 92438088 95654128 1785847808 -0.0880521908 0.2673208416 2.3811807632 357 14.2400000000 0.0274309050 0.0244392819 0.0579214282 0.0078961753 0.8759230000 92439782 95654128 1787752448 -0.0887423605 0.2682860196 2.3877186775 358 14.2800000000 0.0277840998 0.0244486250 0.0579214282 0.0078861833 0.9068240000 92440332 95654128 1784578048 -0.0882238299 0.2667849064 2.3918247223 359 14.3200000000 0.0275612641 0.0244572953 0.0579214282 0.0078754976 1.0575990000 92442026 95654128 1785847808 -0.0895799696 0.2646371424 2.3979415894 360 14.3600000000 0.0281866957 0.0244676547 0.0579214282 0.0078670698 0.9504010000 92443720 95654128 1787752448 -0.0906863585 0.2628546357 2.4035797119 361 14.4000000000 0.0279511288 0.0244773042 0.0579214282 0.0078615526 0.8019570000 92444154 95654128 1784451072 -0.0913189575 0.2626459599 2.4108035564 362 14.4400000000 0.0274847168 0.0244856120 0.0579214282 0.0078553517 0.8931920000 92445848 95654128 1785720832 -0.0916862637 0.2624106407 2.4180901051 363 14.4800000000 0.0282220244 0.0244959052 0.0579214282 0.0078457867 0.8140650000 92447542 95654128 1787625472 -0.0919650868 0.2629565001 2.4242813587 364 14.5200000000 0.0286128707 0.0245072155 0.0579214282 0.0078371620 0.7297960000 92447976 95654128 1784205312 -0.0939925909 0.2624403834 2.4327220917 365 14.5600000000 0.0281221475 0.0245171194 0.0579214282 0.0078266716 1.0200340000 92449670 95654128 1785593856 -0.0948700532 0.2608735561 2.4404449463 366 14.6000000000 0.0282905959 0.0245274295 0.0579214282 0.0078179646 1.5216830000 92451364 95654128 1787498496 -0.0965707749 0.2616136074 2.4499766827 367 14.6400000000 0.0291331392 0.0245399791 0.0579214282 0.0078074527 2.0458700000 92451798 95654128 1784713216 -0.0974701792 0.2620701492 2.4565932751 368 14.6800000000 0.0293824431 0.0245531380 0.0579214282 0.0077984212 1.6215380000 92453492 95654128 1786109952 -0.0981967747 0.2624064684 2.4644227028 369 14.7200000000 0.0298699029 0.0245675465 0.0579214282 0.0078010001 2.1876350000 92455170 95654128 1787887616 -0.1004855484 0.2609861195 2.4724287987 370 14.7600000000 0.0303767268 0.0245832470 0.0579214282 0.0077929675 2.7458240000 92455604 95654128 1784459264 -0.1024461612 0.2619541883 2.4828894138 371 14.8000000000 0.0308626518 0.0246001726 0.0579214282 0.0077940969 2.0164250000 92457298 95654128 1785847808 -0.1039380804 0.2583480477 2.4896261692 372 14.8400000000 0.0321004465 0.0246203347 0.0579214282 0.0077897108 1.9978010000 92458992 95654128 1787752448 -0.1061205119 0.2564003468 2.4972493649 373 14.8800000000 0.0330772847 0.0246430075 0.0579214282 0.0077918519 1.4948290000 92459426 95654128 1784578048 -0.1078930721 0.2542037070 2.5052590370 374 14.9200000000 0.0340153389 0.0246680672 0.0579214282 0.0077893997 1.5546220000 92461120 95654128 1785974784 -0.1091717780 0.2529915869 2.5126883984 375 14.9600000000 0.0348244347 0.0246951508 0.0579214282 0.0077961313 2.0614550000 92462814 95654128 1787752448 -0.1099912748 0.2522744238 2.5201950073 376 15.0000000000 0.0357494019 0.0247245504 0.0579214282 0.0077929330 2.0800360000 92463248 95654128 1784578048 -0.1100206673 0.2534183264 2.5277147293 377 15.0400000000 0.0364256203 0.0247555877 0.0579214282 0.0077945202 1.5312900000 92464958 95654128 1785847808 -0.1082896888 0.2540513575 2.5402908325 378 15.0800000000 0.0366014838 0.0247869261 0.0579214282 0.0077854570 2.2237660000 92466652 95654128 1787879424 -0.1069018617 0.2547398210 2.5478062630 379 15.1200000000 0.0361364931 0.0248168722 0.0579214282 0.0077758233 0.8525390000 92467086 95654128 1784594432 -0.1043618172 0.2550685108 2.5528471470 380 15.1600000000 0.0366985165 0.0248481397 0.0579214282 0.0077679072 0.8515490000 92468780 95654128 1785847808 -0.1017293632 0.2558117211 2.5567588806 381 15.2000000000 0.0371479988 0.0248804228 0.0579214282 0.0077584125 0.7472770000 92470474 95654128 1787752448 -0.0996697322 0.2566797137 2.5613348484 382 15.2400000000 0.0365764201 0.0249110406 0.0579214282 0.0077502298 0.7855790000 92470908 95654128 1784451072 -0.0969928429 0.2572954297 2.5665693283 383 15.2800000000 0.0367367491 0.0249419171 0.0579214282 0.0077421347 0.8327800000 92472718 95654128 1785720832 -0.0946073160 0.2581124902 2.5713684559 384 15.3200000000 0.0365917757 0.0249722552 0.0579214282 0.0077326617 0.7284170000 92474412 95654128 1787625472 -0.0916530937 0.2576312721 2.5751457214 385 15.3600000000 0.0370770991 0.0250036964 0.0579214282 0.0077251327 0.7479650000 92474846 95654128 1784451072 -0.0897240415 0.2554307878 2.5779538155 386 15.4000000000 0.0380219668 0.0250374225 0.0579214282 0.0077275953 0.7475580000 92476540 95654128 1785847808 -0.0882004797 0.2538522482 2.5823590755 387 15.4400000000 0.0406596698 0.0250777901 0.0579214282 0.0077516160 0.8945980000 92478234 95654128 1787752448 -0.0876946598 0.2533828914 2.5884222984 388 15.4800000000 0.0401613005 0.0251166651 0.0579214282 0.0077435434 1.0169060000 92478668 95654128 1784451072 -0.0846879184 0.2563080788 2.5919523239 389 15.5200000000 0.0402971283 0.0251556894 0.0579214282 0.0077365991 1.6377050000 92480362 95654128 1785720832 -0.0823939517 0.2576645911 2.5937871933 390 15.5600000000 0.0393472053 0.0251920779 0.0579214282 0.0077277762 1.3137860000 92482056 95654128 1787625472 -0.0772881210 0.2599018514 2.5929269791 391 15.6000000000 0.0369420908 0.0252221291 0.0579214282 0.0077291316 1.6719410000 92482490 95654128 1784586240 -0.0713726506 0.2621158063 2.5914573669 392 15.6400000000 0.0377631001 0.0252541214 0.0579214282 0.0077288075 1.4869850000 92484184 95654128 1785729024 -0.0691912696 0.2651516199 2.5907537937 393 15.6800000000 0.0356450342 0.0252805614 0.0579214282 0.0077221237 2.4382610000 92485862 95654128 1787379712 -0.0651972964 0.2672733366 2.5943703651 394 15.7200000000 0.0367531404 0.0253096796 0.0579214282 0.0077139102 1.6286040000 92486296 95654128 1784459264 -0.0639142320 0.2678541541 2.5953905582 395 15.7600000000 0.0410924591 0.0253496360 0.0579214282 0.0077220208 1.2227680000 92487990 95654128 1785856000 -0.0646211579 0.2660483718 2.5919065475 396 15.8000000000 0.0442249700 0.0253973010 0.0579214282 0.0077182071 1.3215000000 92489668 95654128 1787633664 -0.0629025549 0.2673697174 2.5882575512 397 15.8400000000 0.0435506515 0.0254430273 0.0579214282 0.0077164101 1.7709800000 92490226 95654128 1784324096 -0.0595659763 0.2682563663 2.5901372433 398 15.8800000000 0.0439668819 0.0254895696 0.0579214282 0.0077086652 2.0270930000 92491920 95654128 1785720832 -0.0573199466 0.2674157321 2.5913441181 399 15.9200000000 0.0402389169 0.0255265354 0.0579214282 0.0076994410 2.0809040000 92493582 95654128 1787752448 -0.0496300422 0.2700364590 2.5953807831 400 15.9600000000 0.0368354134 0.0255548076 0.0579214282 0.0076972924 1.8040400000 92494016 95654128 1784451072 -0.0420772769 0.2662898302 2.5921990871 401 16.0000000000 0.0372489654 0.0255839701 0.0579214282 0.0076924982 1.5554560000 92495710 95654128 1785847808 -0.0374935865 0.2674719691 2.5908474922 402 16.0400000000 0.0382819213 0.0256155570 0.0579214282 0.0076857520 1.3746800000 92497404 95654128 1787625472 -0.0323863477 0.2696745098 2.5900053978 403 16.0800000000 0.0382604524 0.0256469340 0.0579214282 0.0076841266 0.9783920000 92497978 95654128 1784451072 -0.0273712166 0.2689523995 2.5904278755 404 16.1200000000 0.0391517170 0.0256803616 0.0579214282 0.0076781572 0.7737750000 92499672 95654128 1785720832 -0.0218250863 0.2714811265 2.5868461132 405 16.1600000000 0.0391174182 0.0257135396 0.0579214282 0.0076694891 0.8890210000 92501366 95654128 1787752448 -0.0162576288 0.2717079520 2.5879814625 406 16.2000000000 0.0390645377 0.0257464238 0.0579214282 0.0076605286 0.7066290000 92501784 95654128 1784467456 -0.0102257710 0.2732578218 2.5903303623 407 16.2400000000 0.0391120315 0.0257792631 0.0579214282 0.0076532753 0.6267400000 92503478 95654128 1785847808 -0.0049200868 0.2747376263 2.5923023224 408 16.2800000000 0.0381597131 0.0258096074 0.0579214282 0.0076561778 0.8736810000 92505172 95654128 1787752448 0.0006642975 0.2749112546 2.5966935158 409 16.3200000000 0.0374550298 0.0258380803 0.0579214282 0.0076626752 0.7255450000 92505746 95654128 1784451072 0.0076213321 0.2777551115 2.6000320911 410 16.3600000000 0.0377534069 0.0258671420 0.0579214282 0.0076539422 0.7076890000 92507440 95654128 1785720832 0.0135183018 0.2800289094 2.6038146019 411 16.3999999990 0.0385253131 0.0258979405 0.0579214282 0.0076500637 0.6859620000 92509422 95654128 1787625472 0.0172531232 0.2804400623 2.6039590836 412 16.4400000000 0.0383149832 0.0259280790 0.0579214282 0.0076657756 0.6481820000 92679780 95654128 1784451072 0.0227249563 0.2811267078 2.6106495857 413 16.4800000000 0.0378531292 0.0259569532 0.0579214282 0.0076778664 0.6468640000 92681474 95654128 1785720832 0.0287529640 0.2815179825 2.6184072495 414 16.5200000000 0.0387426391 0.0259878365 0.0579214282 0.0076732627 0.7273410000 92681908 95654128 1787752448 0.0327781811 0.2811245322 2.6226820946 415 16.5599999990 0.0391070321 0.0260194490 0.0579214282 0.0076921325 0.8726330000 92683742 95654128 1784467456 0.0360840634 0.2752703130 2.6268749237 416 16.6000000000 0.0393712781 0.0260515447 0.0579214282 0.0077694012 0.7812170000 92685436 95654128 1785720832 0.0421207324 0.2749815583 2.6322638988 417 16.6400000000 0.0397363789 0.0260843621 0.0579214282 0.0078003233 0.8854410000 92685886 95654128 1787625472 0.0479137748 0.2767556310 2.6342260838 418 16.6800000000 0.0406839736 0.0261192894 0.0579214282 0.0078060583 0.7780590000 92689044 95654128 1784070144 0.0503426008 0.2770377100 2.6336812973 419 16.7199999990 0.0415517166 0.0261561210 0.0579214282 0.0078371210 0.8824960000 92859378 95654128 1785466880 0.0566274002 0.2775219679 2.6382119656 420 16.7600000000 0.0421345495 0.0261941648 0.0579214282 0.0078278663 0.7519330000 92859812 95654128 1787371520 0.0629871264 0.2799295783 2.6389362812 421 16.8000000000 0.0413122624 0.0262300748 0.0579214282 0.0078386021 0.8200820000 92861646 95654128 1784500224 0.0675673187 0.2755143642 2.6405942440 422 16.8400000000 0.0445516519 0.0262734909 0.0579214282 0.0078400624 0.8181170000 92863340 95654128 1785974784 0.0758276209 0.2770782113 2.6437838078 423 16.8799999990 0.0429757275 0.0263129761 0.0579214282 0.0078360107 0.6755740000 92863774 95654128 1787760640 0.0831147581 0.2733487189 2.6446759701 424 16.9200000000 0.0409196727 0.0263474258 0.0579214282 0.0078276925 0.7009610000 92865468 95654128 1784459264 0.0893873498 0.2667907178 2.6438374519 425 16.9600000000 0.0390746556 0.0263773722 0.0579214282 0.0078266883 0.7176110000 92868742 95654128 1785872384 0.0981548801 0.2647463381 2.6420056820 426 17.0000000000 0.0376561135 0.0264038482 0.0579214282 0.0078190051 0.7457070000 93037816 95654128 1787760640 0.1077372879 0.2624973655 2.6418349743 427 17.0400000000 0.0367138721 0.0264279934 0.0579214282 0.0078166639 0.7986200000 93039634 95654128 1784459264 0.1145009249 0.2589727044 2.6378724575 428 17.0800000000 0.0353830419 0.0264489164 0.0579214282 0.0078082596 0.8508090000 93040068 95654128 1785856000 0.1253695190 0.2573398948 2.6358997822 429 17.1200000000 0.0345803127 0.0264678707 0.0579214282 0.0078011238 0.7162880000 93041762 95654128 1787887616 0.1363921314 0.2548803985 2.6345086098 430 17.1600000000 0.0322394036 0.0264812929 0.0579214282 0.0077986986 0.7464440000 93043456 95654128 1784348672 0.1469491720 0.2519758940 2.6295902729 431 17.2000000000 0.0306731481 0.0264910188 0.0579214282 0.0077898023 0.7866910000 93045234 95654128 1785602048 0.1579644233 0.2479299605 2.6271653175 432 17.2400000000 0.0294589642 0.0264978890 0.0579214282 0.0077892654 0.7313980000 93215556 95654128 1787633664 0.1708598882 0.2453152388 2.6226272583 433 17.2800000000 0.0278288107 0.0265009627 0.0579214282 0.0077812991 0.7254550000 93217374 95654128 1784586240 0.1835299432 0.2431883961 2.6183676720 434 17.3200000000 0.0259983614 0.0264998047 0.0579214282 0.0077727165 0.7271370000 93217808 95654128 1785872384 0.1952041984 0.2379074991 2.6098906994 435 17.3600000000 0.0266298503 0.0265001036 0.0579214282 0.0077847228 0.7290170000 93219502 95654128 1787760640 0.2077969164 0.2373670489 2.6045043468 436 17.4000000000 0.0277186092 0.0265028984 0.0579214282 0.0077889907 0.7605180000 93221196 95654128 1784459264 0.2227384746 0.2422219515 2.5977382660 437 17.4400000000 0.0311175343 0.0265134582 0.0579214282 0.0077877143 0.6880830000 93221614 95654128 1785729024 0.2361183017 0.2452390641 2.5870976448 438 17.4800000000 0.0355904289 0.0265341819 0.0579214282 0.0078862283 0.7567890000 93223308 95654128 1787625472 0.2456504256 0.2462773323 2.5760827065 439 17.5200000000 0.0360048562 0.0265557551 0.0579214282 0.0080232924 0.7596400000 93225142 95654128 1784451072 0.2529156208 0.2418441623 2.5655381680 440 17.5600000000 0.0323551446 0.0265689356 0.0579214282 0.0080471789 0.8244460000 93226588 95654128 1785720832 0.2628852725 0.2327033579 2.5567111969 441 17.6000000000 0.0271738935 0.0265703074 0.0579214282 0.0080452144 0.7990850000 93396970 95654128 1787625472 0.2756158412 0.2250287086 2.5507190228 442 17.6400000000 0.0251526423 0.0265671000 0.0579214282 0.0081055399 0.8817080000 93398648 95654128 1784451072 0.2917694151 0.2280287296 2.5425710678 443 17.6800000000 0.0246523358 0.0265627777 0.0579214282 0.0081225367 0.6944860000 93399082 95654128 1785737216 0.3166998923 0.2300000042 2.5278604031 444 17.7200000000 0.0275152680 0.0265649230 0.0579214282 0.0081181086 0.5885020000 93400776 95654128 1787371520 0.3239922523 0.2283845991 2.5158617496 445 17.7600000000 0.0283161663 0.0265688583 0.0579214282 0.0081147901 0.6479090000 93401350 95654128 1784324096 0.3329953849 0.2249618322 2.5074818134 446 17.8000000000 0.0275760554 0.0265711166 0.0579214282 0.0081058347 0.7297770000 93403044 95654128 1785720832 0.3439669907 0.2266854495 2.4999935627 447 17.8400000000 0.0271266922 0.0265723595 0.0579214282 0.0081010908 0.7621780000 93404738 95654128 1787498496 0.3525522649 0.2242549807 2.4921500683 448 17.8800000000 0.0266458690 0.0265725236 0.0579214282 0.0080920885 0.7816080000 93405172 95654128 1784451072 0.3606362939 0.2224836498 2.4856770039 449 17.9200000000 0.0258344859 0.0265708799 0.0579214282 0.0080832803 0.9319030000 93406866 95654128 1785847808 0.3695725501 0.2215039432 2.4786317348 450 17.9600000000 0.0264866333 0.0265706927 0.0579214282 0.0080758499 0.7549000000 93408560 95654128 1787625472 0.3755925596 0.2158765942 2.4719829559 451 18.0000000000 0.0190996416 0.0265541271 0.0579214282 0.0080807174 0.7429860000 93409102 95654128 1784451072 0.3928777874 0.2157248557 2.4685339928 452 18.0400000000 0.0181411859 0.0265355144 0.0579214282 0.0080743693 0.6932170000 93410796 95654128 1785847808 0.4033762813 0.2147233337 2.4622037411 453 18.0800000000 0.0198977329 0.0265208615 0.0579214282 0.0080658189 0.7816920000 93412490 95654128 1787625472 0.4091105759 0.2088378817 2.4546689987 454 18.1200000000 0.0206331518 0.0265078930 0.0579214282 0.0080672924 0.6746990000 93412924 95654128 1784451072 0.4184159935 0.2074268311 2.4469277859 455 18.1600000000 0.0215928294 0.0264970906 0.0579214282 0.0080595646 0.6861150000 93414618 95654128 1785864192 0.4279099703 0.2061735839 2.4416844845 456 18.2000000000 0.0221604183 0.0264875804 0.0579214282 0.0080530102 0.8204270000 93416312 95654128 1787752448 0.4361761212 0.2027821392 2.4337711334 457 18.2400000000 0.0232988335 0.0264806028 0.0579214282 0.0080595919 0.7111240000 93416886 95654128 1784451072 0.4452480376 0.2010931671 2.4265179634 458 18.2800000000 0.0246129408 0.0264765250 0.0579214282 0.0080724282 0.8797770000 93418580 95654128 1785720832 0.4556247890 0.2016210109 2.4238188267 459 18.3200000000 0.0237366110 0.0264705556 0.0579214282 0.0080643828 0.8938170000 93421078 95654128 1787752448 0.4686619639 0.2066707611 2.4215624332 460 18.3600000000 0.0276615787 0.0264731448 0.0579214282 0.0080639121 0.8081910000 93590180 95654128 1784451072 0.4734341800 0.2027317584 2.4159543514 461 18.4000000000 0.0310529396 0.0264830793 0.0579214282 0.0080567806 0.6836140000 93591874 95654128 1785720832 0.4811477363 0.2001560181 2.4124031067 462 18.4400000000 0.0361661203 0.0265040383 0.0579214282 0.0080495332 0.8353840000 93593568 95654128 1787752448 0.4875006676 0.2040437460 2.4077534676 463 18.4800000000 0.0351046510 0.0265226141 0.0579214282 0.0080432461 0.7718220000 93594142 95654128 1784451072 0.4976902306 0.2017489672 2.4015383720 464 18.5200000000 0.0378203280 0.0265469626 0.0579214282 0.0080369122 0.8019410000 93595836 95654128 1785720832 0.5030399561 0.1991238743 2.3982722759 465 18.5600000000 0.0413839333 0.0265788701 0.0579214282 0.0080417093 0.7843420000 93596254 95654128 1787625472 0.5081866384 0.1920744032 2.3886017799 466 18.6000000000 0.0504233912 0.0266300386 0.0579214282 0.0080703191 0.7055650000 93597948 95654128 1784451072 0.5130752325 0.1904617846 2.3802187443 467 18.6400000000 0.0529176332 0.0266863289 0.0579214282 0.0080663864 0.6481830000 93599642 95654128 1785974784 0.5217766166 0.1905668676 2.3772051334 468 18.6800000000 0.0591745600 0.0267557482 0.0591745600 0.0080744445 0.8174130000 93600076 95654128 1787887616 0.5266923308 0.1869957596 2.3731184006 469 18.7200000000 0.0611167587 0.0268290127 0.0611167587 0.0081022560 0.7610200000 93602554 95654128 1784365056 0.5347392559 0.1837241203 2.3697788715 470 18.7600000000 0.0741807297 0.0269297610 0.0741807297 0.0081651963 0.7424210000 93772936 95654128 1785602048 0.5349969268 0.1825052351 2.3590514660 471 18.8000000000 0.0773527771 0.0270368162 0.0773527771 0.0082288484 0.7687080000 93773386 95654128 1787506688 0.5435672402 0.1824140847 2.3543679714 472 18.8400000000 0.0694600493 0.0271266960 0.0773527771 0.0082701504 0.6176820000 93775080 95654128 1784586240 0.5613424182 0.1841696203 2.3547599316 473 18.8800000000 0.0628689453 0.0272022610 0.0773527771 0.0082758604 0.5581830000 93777402 95654128 1785872384 0.5766305327 0.1829505712 2.3546764851 474 18.9200000000 0.0646437109 0.0272812514 0.0773527771 0.0082745401 0.5487320000 93946488 95654128 1787760640 0.5806265473 0.1809330285 2.3462786674 475 18.9600000000 0.0681803674 0.0273673548 0.0773527771 0.0082754837 0.6645790000 93948322 95654128 1784520704 0.5858941674 0.1776274294 2.3426043987 476 19.0000000000 0.0710534751 0.0274591323 0.0773527771 0.0082823685 0.7283540000 93950016 95654128 1785856000 0.5928267241 0.1766640991 2.3393754959 477 19.0400000000 0.0601909012 0.0275277524 0.0773527771 0.0082823979 0.8064210000 93950450 95654128 1787633664 0.6103273034 0.1774903983 2.3370919228 478 19.0800000000 0.0601632893 0.0275960276 0.0773527771 0.0082754981 0.8833910000 93952144 95654128 1784451072 0.6228729486 0.1778546572 2.3408010006 479 19.1200000000 0.0578319281 0.0276591505 0.0773527771 0.0082687817 0.9273980000 93953838 95654128 1785847808 0.6319900155 0.1732880473 2.3408350945 480 19.1600000000 0.0592992119 0.0277250673 0.0773527771 0.0082820226 0.8487630000 93954272 95654128 1787752448 0.6421026587 0.1691217124 2.3396234512 481 19.2000000000 0.0576845892 0.0277873532 0.0773527771 0.0082971027 0.7165140000 93956602 95654128 1784496128 0.6516277790 0.1701328605 2.3337836266 482 19.2400000000 0.0528318100 0.0278393127 0.0773527771 0.0082905323 0.8119870000 94125720 95654128 1785847808 0.6651394367 0.1731483042 2.3385992050 483 19.2800000000 0.0545424595 0.0278945987 0.0773527771 0.0082823141 0.5501740000 94127414 95654128 1787879424 0.6720670462 0.1706265956 2.3370335102 484 19.3200000000 0.0526699796 0.0279457875 0.0773527771 0.0082770879 0.7481120000 94129108 95654128 1784467456 0.6783913970 0.1700008512 2.3341860771 485 19.3600000000 0.0511363670 0.0279936031 0.0773527771 0.0082741574 0.8058080000 94129542 95654128 1785737216 0.6890848279 0.1752673090 2.3308348656 486 19.4000000000 0.0447174199 0.0280280143 0.0773527771 0.0082901844 0.7680180000 94131236 95654128 1787625472 0.7056597471 0.1866337359 2.3318564892 487 19.4400000000 0.0436561741 0.0280601050 0.0773527771 0.0083195877 0.7739370000 94133070 95654128 1784578048 0.7136961818 0.1819671690 2.3265638351 488 19.4800000000 0.0435771570 0.0280919022 0.0773527771 0.0083202872 0.7120450000 94133504 95654128 1785847808 0.7120029330 0.1786760390 2.3211622238 489 19.5200000000 0.0515822619 0.0281399397 0.0773527771 0.0083159686 0.7991600000 94135198 95654128 1787879424 0.7072563767 0.1746842563 2.3168067932 490 19.5600000000 0.0536167212 0.0281919332 0.0773527771 0.0083076467 0.6758530000 94136876 95654128 1784483840 0.7091391683 0.1753025055 2.3096756935 491 19.6000000000 0.0543086268 0.0282451240 0.0773527771 0.0082997025 0.7684930000 94137310 95654128 1785720832 0.7133802176 0.1754828244 2.3079683781 492 19.6400000000 0.0527674593 0.0282949661 0.0773527771 0.0082931208 0.9445310000 94139004 95654128 1787625472 0.7156098485 0.1801432818 2.3006386757 493 19.6800000000 0.0528028905 0.0283446780 0.0773527771 0.0082983614 0.9911470000 94140838 95654128 1784451072 0.7192220688 0.1858723164 2.2950975895 494 19.7200000000 0.0542595908 0.0283971373 0.0773527771 0.0082976809 0.7881390000 94141272 95654128 1785847808 0.7195540071 0.1822430044 2.2878878117 495 19.7600000000 0.0554533415 0.0284517963 0.0773527771 0.0082907294 0.7474250000 94142966 95654128 1787752448 0.7185357809 0.1799635142 2.2781980038 496 19.8000000000 0.0534623116 0.0285022207 0.0773527771 0.0082875039 0.9083070000 94144660 95654128 1784229888 0.7195705175 0.1798762679 2.2712864876 497 19.8400000000 0.0539387688 0.0285534009 0.0773527771 0.0082798503 0.7208880000 94145094 95654128 1785593856 0.7232940197 0.1790538877 2.2660226822 498 19.8800000000 0.0559663847 0.0286084471 0.0773527771 0.0082721946 0.8269490000 94146788 95654128 1787371520 0.7194555998 0.1780331284 2.2576415539 499 19.9200000000 0.0614122897 0.0286741862 0.0773527771 0.0082643619 0.7286250000 94147378 95654128 1784451072 0.7161415815 0.1798006892 2.2534632683 500 19.9600000000 0.0671025738 0.0287510430 0.0773527771 0.0082574911 0.7488860000 94149072 95654128 1785864192 0.7122718096 0.1826369911 2.2476215363 501 20.0000000000 0.0685810149 0.0288305439 0.0773527771 0.0082506088 0.6873730000 94150766 95654128 1787752448 0.7132379413 0.1829423010 2.2403526306 502 20.0400000000 0.0700031444 0.0289125611 0.0773527771 0.0082432900 0.7703730000 94151200 95654128 1784451072 0.7156215310 0.1805770248 2.2376194000 503 20.0800000000 0.0729538426 0.0290001183 0.0773527771 0.0082356416 0.8289690000 94152926 95654128 1785847808 0.7170265317 0.1840405762 2.2283344269 504 20.1200000000 0.0760758147 0.0290935224 0.0773527771 0.0082311148 0.7955070000 94154620 95654128 1787625472 0.7168046236 0.1868554056 2.2196071148 505 20.1600000000 0.0804909170 0.0291952995 0.0804909170 0.0082271801 0.7781940000 94155194 95654128 1784479744 0.7070844769 0.1836658716 2.2086906433 506 20.2000000000 0.0835476369 0.0293027152 0.0835476369 0.0082212753 0.7114660000 94156888 95654128 1785847808 0.7045715451 0.1870466322 2.2024662495 507 20.2400000000 0.0884049013 0.0294192875 0.0884049013 0.0082242959 0.7891420000 94158582 95654128 1787752448 0.7033117414 0.1929692179 2.1948189735 508 20.2800000000 0.0885337442 0.0295356546 0.0885337442 0.0082265755 0.7577430000 94159032 95654128 1784451072 0.6972529292 0.1926088482 2.1850321293 509 20.3200000000 0.0882327110 0.0296509729 0.0885337442 0.0082192043 0.8480290000 94160726 95654128 1785864192 0.7015097737 0.1919542700 2.1749136448 510 20.3600000000 0.0942728594 0.0297776825 0.0942728594 0.0082116280 0.7150700000 94162420 95654128 1787879424 0.7023836970 0.1969365478 2.1634397507 511 20.4000000000 0.1007281020 0.0299165287 0.1007281020 0.0082065689 0.9714340000 94163466 95654128 1784451072 0.7009078860 0.2048860788 2.1537461281 512 20.4400000000 0.1038625240 0.0300609545 0.1038625240 0.0082290229 1.6596950000 94333868 95654128 1785856000 0.7002258301 0.2101832032 2.1470072269 513 20.4800000000 0.1036546901 0.0302044121 0.1038625240 0.0082304894 1.6557450000 94376538 95654128 1787887616 0.7041963935 0.2071377039 2.1357095242 514 20.5200000000 0.1045330688 0.0303490204 0.1045330688 0.0082228758 1.9422550000 94460940 95654128 1784459264 0.7033218741 0.2076344341 2.1234607697 515 20.5600000000 0.1128508449 0.0305092181 0.1128508449 0.0082293688 1.8833440000 94462634 95654128 1785856000 0.7047356367 0.2164689302 2.1151952744 516 20.6000000000 0.1168008074 0.0306764498 0.1168008074 0.0082363580 1.8602800000 94464328 95654128 1787887616 0.7075303793 0.2195079625 2.1053822041 517 20.6400000000 0.1200324073 0.0308492854 0.1200324073 0.0082399788 1.9376300000 94464918 95654128 1784459264 0.7027818561 0.2217439860 2.1064391136 518 20.6800000000 0.1211779490 0.0310236650 0.1211779490 0.0082334997 1.6675760000 94466612 95654128 1785720832 0.7148374915 0.2195110470 2.0887043476 519 20.7200000000 0.1278486252 0.0312102256 0.1278486252 0.0082321128 1.5491500000 94467046 95654128 1787641856 0.7020887136 0.2286148071 2.0931093693 520 20.7600000000 0.1281130761 0.0313965773 0.1281130761 0.0082339957 1.0229970000 94469472 95654128 1784578048 0.6964430809 0.2330721170 2.0918595791 521 20.8000000000 0.1212399453 0.0315690213 0.1281130761 0.0082420062 0.7603420000 94639822 95654128 1785864192 0.6996151805 0.2273848951 2.0819308758 522 20.8400000000 0.1173240617 0.0317333030 0.1281130761 0.0082371501 0.7424170000 94640256 95654128 1787912192 0.7059022188 0.2240163535 2.0718288422 523 20.8800000000 0.1151855737 0.0318928676 0.1281130761 0.0082320360 0.7293170000 94642090 95654128 1784324096 0.6976952553 0.2231617272 2.0747833252 524 20.9200000000 0.1209778264 0.0320628771 0.1281130761 0.0082274281 0.9185370000 94643784 95654128 1785720832 0.7084708214 0.2231814116 2.0590584278 525 20.9600000000 0.1252143085 0.0322403084 0.1281130761 0.0082212973 0.7607370000 94644218 95654128 1787498496 0.7031772733 0.2223319858 2.0568706989 526 21.0000000000 0.1291354746 0.0324245197 0.1291354746 0.0082148744 0.7713160000 94645928 95654128 1784479744 0.7066333890 0.2188901305 2.0462422371 527 21.0400000000 0.1286438704 0.0326070991 0.1291354746 0.0082164332 0.7463390000 94647622 95654128 1785847808 0.7099057436 0.2212036699 2.0366919041 528 21.0800000000 0.1306725591 0.0327928292 0.1306725591 0.0082092594 0.7678200000 94648056 95654128 1787625472 0.7117416263 0.2223212123 2.0326817036 529 21.1200000000 0.1366400719 0.0329891377 0.1366400719 0.0082052853 0.6865010000 94649890 95654128 1784578048 0.7199280858 0.2194737494 2.0199730396 530 21.1600000000 0.1369843930 0.0331853552 0.1369843930 0.0082006960 0.6888000000 94651584 95654128 1785991168 0.7156233788 0.2192937136 2.0182819366 531 21.2000000000 0.1465598643 0.0333988665 0.1465598643 0.0081969721 0.9867320000 94652050 95654128 1787752448 0.7202528715 0.2248216867 2.0102865696 532 21.2400000000 0.1492667794 0.0336166634 0.1492667794 0.0081897748 1.8287750000 94653744 95654128 1784451072 0.7197217345 0.2242794484 2.0056910515 533 21.2800000000 0.1511963308 0.0338372631 0.1511963308 0.0081831610 1.9857490000 94655438 95654128 1785847808 0.7178259492 0.2249253392 2.0019297600 534 21.3200000000 0.1556814164 0.0340654357 0.1556814164 0.0081782165 1.0235820000 94655888 95654128 1787752448 0.7220784426 0.2251777053 1.9894601107 535 21.3600000000 0.1581435949 0.0342973575 0.1581435949 0.0081730368 1.0387460000 94658846 95654128 1784578048 0.7269488573 0.2289714515 1.9768164158 536 21.4000000000 0.1586468667 0.0345293528 0.1586468667 0.0081663852 1.7459490000 94827972 95654128 1785847808 0.7247678638 0.2288910896 1.9733339548 537 21.4400000000 0.1611407846 0.0347651283 0.1611407846 0.0081594000 2.0624160000 94829666 95654128 1788006400 0.7298817635 0.2273124009 1.9578278065 538 21.4800000000 0.1610754877 0.0349999059 0.1611407846 0.0081521925 1.8565430000 94831376 95654128 1784705024 0.7306246758 0.2270983309 1.9503185749 539 21.5200000000 0.1604624838 0.0352326751 0.1611407846 0.0081449323 1.5901340000 94831810 95654128 1785982976 0.7287101150 0.2253538221 1.9427256584 540 21.5600000000 0.1614387333 0.0354663900 0.1614387333 0.0081385716 1.8929890000 94833504 95654128 1787887616 0.7320966125 0.2277474105 1.9293994904 541 21.6000000000 0.1601883471 0.0356969297 0.1614387333 0.0081318364 1.7507510000 94835338 95654128 1784459264 0.7335783243 0.2276239246 1.9206318855 542 21.6400000000 0.1608536839 0.0359278462 0.1614387333 0.0081290957 2.1021310000 94835788 95654128 1785720832 0.7364919186 0.2259471118 1.9089535475 543 21.6800000000 0.1598937213 0.0361561443 0.1614387333 0.0081219931 1.7418240000 94839226 95654128 1787625472 0.7377343178 0.2216607332 1.9039835930 544 21.7200000000 0.1598863304 0.0363835895 0.1614387333 0.0081205269 0.9418740000 95009520 95654128 1784578048 0.7389214039 0.2226172835 1.8944966793 545 21.7600000000 0.1597753465 0.0366099964 0.1614387333 0.0081169915 0.8507360000 95009954 95654128 1785847808 0.7422964573 0.2217020541 1.8828122616 546 21.8000000000 0.1580897123 0.0368324867 0.1614387333 0.0081213093 0.7089320000 95011648 95654128 1787879424 0.7441604733 0.2204812318 1.8759195805 547 21.8400000000 0.1580601037 0.0370541094 0.1614387333 0.0081193677 0.8243060000 95013482 95654128 1784467456 0.7465636134 0.2222129256 1.8641897440 548 21.8800000000 0.1584569961 0.0372756475 0.1614387333 0.0081128882 0.8573410000 95013916 95654128 1785720832 0.7449656129 0.2243729532 1.8609699011 549 21.9200000000 0.1573638469 0.0374943874 0.1614387333 0.0081069170 1.1368510000 95015610 95654128 1787371520 0.7458643913 0.2213438153 1.8547673225 550 21.9600000000 0.1573574096 0.0377123202 0.1614387333 0.0081003856 2.0958700000 95017304 95654128 1784578048 0.7451393008 0.2226062566 1.8490251303 551 22.0000000000 0.1574286222 0.0379295911 0.1614387333 0.0080942844 1.8181890000 95017738 95654128 1785974784 0.7462792397 0.2237404734 1.8408718109 552 22.0400000000 0.1578367203 0.0381468142 0.1614387333 0.0080872906 1.7815710000 95019432 95654128 1787752448 0.7495263815 0.2253255099 1.8335205317 553 22.0800000000 0.1584307551 0.0383643259 0.1614387333 0.0080829693 1.2631240000 95020006 95654128 1784451072 0.7473620176 0.2249481678 1.8313878775 554 22.1200000000 0.1603848785 0.0385845796 0.1614387333 0.0080765118 2.0333610000 95022980 95654128 1785847808 0.7470989227 0.2253849804 1.8247232437 555 22.1600000000 0.1613508165 0.0388057800 0.1614387333 0.0080699279 1.9434360000 95193390 95654128 1787752448 0.7479733229 0.2293237001 1.8179315329 556 22.2000000000 0.1610022038 0.0390255577 0.1614387333 0.0080650220 1.1821100000 95193824 95654128 1784451072 0.7480896115 0.2313784212 1.8093924522 557 22.2400000000 0.1609204710 0.0392443996 0.1614387333 0.0080711511 0.9459630000 95195518 95654128 1785847808 0.7474732399 0.2281047702 1.8059165478 558 22.2800000000 0.1604592800 0.0394616306 0.1614387333 0.0080639692 0.7935430000 95197212 95654128 1787752448 0.7457921505 0.2252345532 1.7995364666 559 22.3200000000 0.1605635136 0.0396782708 0.1614387333 0.0080598479 0.7811260000 95197786 95654128 1784561664 0.7448194623 0.2275755703 1.7943243980 560 22.3600000000 0.1625035107 0.0398976016 0.1625035107 0.0080540188 0.8883230000 95199480 95654128 1786093568 0.7429686189 0.2296596169 1.7917913198 561 22.4000000000 0.1646313220 0.0401199433 0.1646313220 0.0080480523 0.8491550000 95201174 95654128 1787871232 0.7450298071 0.2297152728 1.7853802443 562 22.4400000000 0.1644942462 0.0403412499 0.1646313220 0.0080416606 0.6877700000 95201608 95654128 1784569856 0.7441412807 0.2299829423 1.7836747169 563 22.4800000000 0.1658505350 0.0405641794 0.1658505350 0.0080363062 0.7111440000 95204538 95654128 1785982976 0.7452582717 0.2309188694 1.7751812935 564 22.5200000000 0.1670565605 0.0407884566 0.1670565605 0.0080321152 0.8068360000 95374968 95654128 1787998208 0.7453667521 0.2299503237 1.7701414824 565 22.5600000000 0.1682221293 0.0410140029 0.1682221293 0.0080253962 0.8062500000 95375542 95654128 1784950784 0.7473516464 0.2262166142 1.7606037855 566 22.6000000000 0.1663215756 0.0412353944 0.1682221293 0.0080219017 0.9123440000 95377352 95654128 1786474496 0.7483442426 0.2235022336 1.7527456284 567 22.6400000000 0.1675020754 0.0414580870 0.1682221293 0.0080155518 0.7898760000 95379046 95654128 1785593856 0.7490375638 0.2208748460 1.7498412132 568 22.6800000000 0.1684828550 0.0416817221 0.1684828550 0.0080086061 0.9241390000 95379480 95654128 1786863616 0.7509138584 0.2183070332 1.7426730394 569 22.7200000000 0.1670062542 0.0419019761 0.1684828550 0.0080050325 0.8670440000 95381174 95654128 1784451072 0.7531604767 0.2147750109 1.7317034006 570 22.7600000000 0.1657796204 0.0421193053 0.1684828550 0.0080027819 0.9210110000 95384444 95654128 1785737216 0.7528708577 0.2168943733 1.7210597992 571 22.8000000000 0.1659965068 0.0423362532 0.1684828550 0.0079971295 0.8126420000 95553734 95654128 1787752448 0.7526972890 0.2199888378 1.7123687267 572 22.8400000000 0.1656152457 0.0425517759 0.1684828550 0.0079939545 0.8480460000 95555428 95654128 1784578048 0.7535093427 0.2159686983 1.7038315535 573 22.8800000000 0.1654351503 0.0427662320 0.1684828550 0.0079907264 0.9529970000 95555862 95654128 1785847808 0.7536330819 0.2157403529 1.6944137812 574 22.9200000000 0.1640832871 0.0429775858 0.1684828550 0.0079845952 0.7496110000 95557556 95654128 1787752448 0.7514182329 0.2145783603 1.6880415678 575 22.9600000000 0.1644361168 0.0431888180 0.1684828550 0.0079813466 0.8610470000 95559250 95654128 1784324096 0.7504528165 0.2099191546 1.6806805134 576 23.0000000000 0.1643093377 0.0433990967 0.1684828550 0.0079759269 0.7729100000 95559684 95654128 1785712640 0.7498572469 0.2057744265 1.6740149260 577 23.0400000000 0.1632762700 0.0436068561 0.1684828550 0.0079776818 0.7639160000 95561518 95654128 1787490304 0.7488956451 0.2066953629 1.6639949083 578 23.0800000000 0.1652228534 0.0438172644 0.1684828550 0.0079711324 0.6669760000 95563212 95654128 1784442880 0.7473419905 0.2077238858 1.6555302143 579 23.1200000000 0.1661331058 0.0440285180 0.1684828550 0.0079645579 0.8666660000 95563646 95654128 1785839616 0.7465573549 0.2058023661 1.6469061375 580 23.1600000000 0.1673385054 0.0442411214 0.1684828550 0.0079583493 0.8719590000 95565340 95654128 1787744256 0.7456483841 0.2040685862 1.6387945414 581 23.2000000000 0.1673365831 0.0444529897 0.1684828550 0.0079517185 0.7651440000 95567034 95654128 1784442880 0.7442125082 0.2031913698 1.6303974390 582 23.2400000000 0.1690268219 0.0446670341 0.1690268219 0.0079471284 0.9427740000 95567452 95654128 1785839616 0.7425292134 0.2004311085 1.6222105026 583 23.2800000000 0.1671917737 0.0448771966 0.1690268219 0.0079411912 0.8759590000 95569286 95654128 1787744256 0.7431730032 0.1950542331 1.6124460697 584 23.3200000000 0.1647596657 0.0450824748 0.1690268219 0.0079442503 0.7672450000 95570980 95654128 1784590336 0.7417335510 0.1935608834 1.5992406607 585 23.3600000000 0.1646355242 0.0452868390 0.1690268219 0.0079385510 0.7153490000 95571414 95654128 1785966592 0.7404910922 0.1916757077 1.5886466503 586 23.4000000000 0.1640658677 0.0454895336 0.1690268219 0.0079354888 0.8820520000 95573124 95654128 1787871232 0.7404549718 0.1885792315 1.5768945217 587 23.4400000000 0.1619663984 0.0456879609 0.1690268219 0.0079423180 0.8541890000 95574818 95654128 1784442880 0.7401713133 0.1869176626 1.5657250881 588 23.4800000000 0.1622142047 0.0458861348 0.1690268219 0.0079522877 0.8504080000 95576872 95654128 1785839616 0.7383005023 0.1895811707 1.5391082764 589 23.5200000000 0.1613992453 0.0460822521 0.1690268219 0.0079461519 0.6950200000 95747390 95654128 1787744256 0.7366667986 0.1895546913 1.5293363333 590 23.5600000000 0.1589082927 0.0462734827 0.1690268219 0.0079435685 0.7895180000 95748056 95654128 1784696832 0.7354041338 0.1887255609 1.5167988539 591 23.6000000000 0.1592287123 0.0464646083 0.1690268219 0.0079439520 0.8907060000 95749750 95654128 1785966592 0.7344490290 0.1872630566 1.5054689646 592 23.6400000000 0.1589290947 0.0466545821 0.1690268219 0.0079380442 0.7288540000 95751444 95654128 1787871232 0.7342221737 0.1865719259 1.4906612635 593 23.6800000000 0.1557786465 0.0468386025 0.1690268219 0.0079352267 0.8635550000 95751878 95654128 1784569856 0.7335009575 0.1833921671 1.4767032862 594 23.7200000000 0.1511547416 0.0470142189 0.1690268219 0.0079350277 0.9059230000 95753572 95654128 1785856000 0.7334354520 0.1799559295 1.4614275694 595 23.7600000000 0.1495941430 0.0471866221 0.1690268219 0.0079325929 0.9823410000 95755406 95654128 1787871232 0.7316090465 0.1778104901 1.4514337778 596 23.8000000000 0.1496917158 0.0473586105 0.1690268219 0.0079310871 0.9123390000 95755840 95654128 1784475648 0.7301518321 0.1789795756 1.4391114712 597 23.8400000000 0.1502276659 0.0475309205 0.1690268219 0.0079249840 0.8067660000 95757650 95654128 1785712640 0.7275612354 0.1816833913 1.4288775921 598 23.8800000000 0.1501965523 0.0477026021 0.1690268219 0.0079192488 0.7533270000 95759344 95654128 1787744256 0.7265524268 0.1817231029 1.4156777859 599 23.9200000000 0.1488223672 0.0478714164 0.1690268219 0.0079132614 0.8982860000 95759778 95654128 1784459264 0.7243049145 0.1830455363 1.4046975374 600 23.9600000000 0.1476001143 0.0480376309 0.1690268219 0.0079089558 0.9211500000 95761472 95654128 1785839616 0.7226738334 0.1824594438 1.3924045563 601 24.0000000000 0.1476421505 0.0482033622 0.1690268219 0.0079032963 0.9489400000 95763306 95654128 1787617280 0.7201685309 0.1823914945 1.3827475309 602 24.0400000000 0.1477796882 0.0483687714 0.1690268219 0.0078971439 1.1255640000 95763856 95654128 1784442880 0.7184922099 0.1815807372 1.3712455034 603 24.0800000000 0.1459798515 0.0485306472 0.1690268219 0.0078915397 1.0469260000 95765550 95654128 1785839616 0.7157654166 0.1793147326 1.3620342016 604 24.1200000000 0.1454087645 0.0486910414 0.1690268219 0.0078853272 0.8029020000 95767244 95654128 1787617280 0.7127721310 0.1806626618 1.3527176380 605 24.1600000000 0.1450349092 0.0488502875 0.1690268219 0.0078797620 0.8273040000 95767678 95654128 1784569856 0.7101598382 0.1783567518 1.3446385860 606 24.2000000000 0.1452022195 0.0490092841 0.1690268219 0.0078736180 0.7725550000 95769372 95654128 1785982976 0.7078080773 0.1776787937 1.3359936476 607 24.2400000000 0.1456347257 0.0491684693 0.1690268219 0.0078674615 0.8503430000 95769946 95654128 1787871232 0.7056794763 0.1770027429 1.3239828348 608 24.2800000000 0.1452975571 0.0493265764 0.1690268219 0.0078612420 0.9481010000 95771756 95654128 1784324096 0.7029522657 0.1769707352 1.3161860704 609 24.3200000000 0.1438320726 0.0494817578 0.1690268219 0.0078586767 0.9692310000 95773450 95654128 1785720832 0.7016534805 0.1712435633 1.3072178364 610 24.3600000000 0.1449873596 0.0496383244 0.1690268219 0.0078523048 0.9868410000 95773884 95654128 1787498496 0.6994841695 0.1675281525 1.3004266024 611 24.4000000000 0.1452988833 0.0497948883 0.1690268219 0.0078527424 1.0379580000 95775578 95654128 1784451072 0.6984813809 0.1682656407 1.2865660191 612 24.4400000000 0.1431639940 0.0499474522 0.1690268219 0.0078485728 0.7790160000 95777272 95654128 1785847808 0.6961115599 0.1668743491 1.2759823799 613 24.4800000000 0.1440010816 0.0501008839 0.1690268219 0.0078428938 0.6880310000 95777846 95654128 1787752448 0.6940020919 0.1656505316 1.2692492008 614 24.5200000000 0.1447688341 0.0502550662 0.1690268219 0.0078368743 0.8723510000 95781916 95654128 1784578048 0.6923191547 0.1626760811 1.2579483986 615 24.5600000000 0.1452677399 0.0504095584 0.1690268219 0.0078308045 0.7550520000 95952350 95654128 1785982976 0.6908994913 0.1609885544 1.2504215240 616 24.6000000000 0.1457212269 0.0505642851 0.1690268219 0.0078249846 0.7540520000 95952784 95654128 1787871232 0.6896404028 0.1579658687 1.2403874397 617 24.6400000000 0.1437579095 0.0507153282 0.1690268219 0.0078234794 1.0879540000 95954478 95654128 1784569856 0.6880822182 0.1537059098 1.2287276983 618 24.6800000000 0.1439244002 0.0508661520 0.1690268219 0.0078215757 1.8506950000 95956404 95654128 1785839616 0.6871432662 0.1508746892 1.2168335915 619 24.7200000000 0.1437823325 0.0510162589 0.1690268219 0.0078233955 1.4886430000 95956978 95654128 1787744256 0.6864514351 0.1499182880 1.2018438578 620 24.7600000000 0.1437609941 0.0511658472 0.1690268219 0.0078196193 0.9898100000 95958672 95654128 1784696832 0.6838641763 0.1498637050 1.1936495304 621 24.8000000000 0.1437058151 0.0513148648 0.1690268219 0.0078135355 0.9148780000 95960482 95654128 1785966592 0.6826112866 0.1489709169 1.1837654114 622 24.8400000000 0.1430287808 0.0514623149 0.1690268219 0.0078078842 1.1382860000 95960916 95654128 1787998208 0.6810419559 0.1464417577 1.1726571321 623 24.8800000000 0.1426717937 0.0516087185 0.1690268219 0.0078040302 1.1321960000 95962610 95654128 1784569856 0.6790800095 0.1458402127 1.1623951197 624 24.9200000000 0.1409975588 0.0517519699 0.1690268219 0.0078001146 0.9978570000 95964420 95654128 1785839616 0.6769009233 0.1468848884 1.1494387388 625 24.9600000000 0.1415071934 0.0518955782 0.1690268219 0.0077940178 0.9598360000 95967618 95654128 1787744256 0.6743476987 0.1459220797 1.1400088072 626 25.0000000000 0.1413908005 0.0520385418 0.1690268219 0.0077886794 0.9402010000 96138008 95654128 1784569856 0.6724503040 0.1433289945 1.1307418346 627 25.0400000000 0.1401182115 0.0521790198 0.1690268219 0.0077858314 0.9295070000 96138442 95654128 1785839616 0.6701927185 0.1420218050 1.1199351549 628 25.0800000000 0.1389595270 0.0523172053 0.1690268219 0.0077808371 0.9488220000 96140136 95654128 1787617280 0.6670277119 0.1436266750 1.1092722416 629 25.1200000000 0.1390783489 0.0524551404 0.1690268219 0.0077782888 0.9258780000 96141830 95654128 1784442880 0.6644988060 0.1412289441 1.1040985584 630 25.1600000000 0.1399267614 0.0525939842 0.1690268219 0.0077727406 0.7090550000 96142264 95654128 1785856000 0.6610627174 0.1416747719 1.0957638025 631 25.2000000000 0.1394418180 0.0527316194 0.1690268219 0.0077681898 0.8253060000 96144098 95654128 1787617280 0.6573762298 0.1420787573 1.0871449709 632 25.2400000000 0.1378429085 0.0528662892 0.1690268219 0.0077658750 0.9293310000 96145792 95654128 1784569856 0.6540406346 0.1403878480 1.0797901154 633 25.2800000000 0.1373040825 0.0529996822 0.1690268219 0.0077612264 0.7680860000 96146226 95654128 1785966592 0.6504032612 0.1402518004 1.0694266558 634 25.3200000000 0.1365977079 0.0531315403 0.1690268219 0.0077586848 0.7471820000 96147920 95654128 1787744256 0.6455715895 0.1407350898 1.0614511967 635 25.3600000000 0.1360133141 0.0532620628 0.1690268219 0.0077589104 0.9473290000 96149614 95654128 1784569856 0.6418601871 0.1408738494 1.0552791357 636 25.4000000000 0.1344894618 0.0533897788 0.1690268219 0.0077595741 0.8057130000 96150048 95654128 1785982976 0.6387105584 0.1370695382 1.0454362631 637 25.4400000000 0.1334950626 0.0535155328 0.1690268219 0.0077544077 0.8923180000 96154398 95654128 1787744256 0.6347188950 0.1366764605 1.0377840996 638 25.4800000000 0.1339150071 0.0536415508 0.1690268219 0.0077490564 1.2245650000 96324804 95654128 1784705024 0.6315052509 0.1362334341 1.0299081802 639 25.5200000000 0.1325185001 0.0537649889 0.1690268219 0.0077437986 2.0531660000 96325238 95654128 1785974784 0.6268479824 0.1334146559 1.0230489969 640 25.5600000000 0.1312059313 0.0538859904 0.1690268219 0.0077390683 2.3624970000 96326932 95654128 1787879424 0.6230459213 0.1316578239 1.0159078836 641 25.6000000000 0.1318977922 0.0540076936 0.1690268219 0.0077335157 1.9886160000 96328626 95654128 1784451072 0.6183612943 0.1308483481 1.0104731321 642 25.6400000000 0.1318385750 0.0541289256 0.1690268219 0.0077286736 1.1055290000 96329060 95654128 1785839616 0.6132264733 0.1303164661 1.0053350925 643 25.6800000000 0.1315262765 0.0542492947 0.1690268219 0.0077232887 0.8898600000 96330894 95654128 1787617280 0.6086262465 0.1285988092 0.9983884096 644 25.7200000000 0.1320933402 0.0543701705 0.1690268219 0.0077173202 0.9076030000 96331328 95654128 1784696832 0.6033306718 0.1277122498 0.9944857359 645 25.7600000000 0.1321877688 0.0544908180 0.1690268219 0.0077115258 1.0395340000 96333022 95654128 1785966592 0.5985687971 0.1255303770 0.9886144400 646 25.8000000000 0.1302775294 0.0546081349 0.1690268219 0.0077065595 0.9324710000 96334716 95654128 1787998208 0.5924661756 0.1236493662 0.9826440811 647 25.8400000000 0.1291869283 0.0547234035 0.1690268219 0.0077009593 0.9865800000 96335150 95654128 1784459264 0.5856326222 0.1234260350 0.9761739969 648 25.8800000000 0.1288340539 0.0548377718 0.1690268219 0.0076991342 0.9643230000 96336844 95654128 1785839616 0.5790790915 0.1227252111 0.9714748859 649 25.9200000000 0.1283148825 0.0549509876 0.1690268219 0.0076967896 0.9573480000 96338678 95654128 1787871232 0.5720111132 0.1198134571 0.9662027359 650 25.9600000000 0.1292412877 0.0550652804 0.1690268219 0.0076926487 0.9012880000 96339112 95654128 1784569856 0.5588988066 0.1141271815 0.9586405754 651 26.0000000000 0.1283721030 0.0551778869 0.1690268219 0.0076965347 0.7675050000 96340806 95654128 1785839616 0.5423052311 0.1140956506 0.9480315447 652 26.0400000000 0.1264652908 0.0552872234 0.1690268219 0.0076920795 0.8697340000 96342500 95654128 1787744256 0.5328838825 0.1145244986 0.9399609566 653 26.0800000000 0.1244168729 0.0553930881 0.1690268219 0.0076907529 0.8264390000 96342934 95654128 1784586240 0.5229893327 0.1161001250 0.9339551926 654 26.1200000000 0.1230598912 0.0554965542 0.1690268219 0.0076938897 0.7541690000 96346960 95654128 1785839616 0.5130202770 0.1157995537 0.9288896322 655 26.1600000000 0.1238032356 0.0556008392 0.1690268219 0.0076899003 0.7810650000 96517542 95654128 1787490304 0.5035333633 0.1135316268 0.9241858721 656 26.2000000000 0.1226301119 0.0557030180 0.1690268219 0.0076907494 0.8504240000 96517976 95654128 1784569856 0.4932051599 0.1145829633 0.9184890985 657 26.2400000000 0.1213488206 0.0558029355 0.1690268219 0.0076922568 0.8307090000 96519670 95654128 1785966592 0.4829079509 0.1151924878 0.9131546617 658 26.2800000000 0.1206162572 0.0559014359 0.1690268219 0.0076947440 0.7676980000 96521364 95654128 1787871232 0.4720685780 0.1168090105 0.9077073932 659 26.3200000000 0.1194914654 0.0559979307 0.1690268219 0.0076914416 0.8220640000 96521798 95654128 1784475648 0.4605549872 0.1189081520 0.9035106897 660 26.3600000000 0.1186698601 0.0560928882 0.1690268219 0.0076863463 0.8284370000 96523492 95654128 1785839616 0.4499962628 0.1197328269 0.8991476297 661 26.4000000000 0.1175476313 0.0561858605 0.1690268219 0.0076812451 0.8735360000 96524066 95654128 1787744256 0.4382575452 0.1219069883 0.8940620422 662 26.4400000000 0.1168094948 0.0562774370 0.1690268219 0.0076797731 0.7057270000 96525760 95654128 1784442880 0.4265068769 0.1251620501 0.8915975094 663 26.4800000000 0.1171329618 0.0563692251 0.1690268219 0.0076928623 0.8024590000 96527454 95654128 1785839616 0.4160262644 0.1252571493 0.8884198666 664 26.5200000000 0.1161108166 0.0564591974 0.1690268219 0.0076984114 0.9966870000 96527888 95654128 1787617280 0.4055343568 0.1219682097 0.8812789321 665 26.5600000000 0.1162051037 0.0565490409 0.1690268219 0.0076931540 0.9350540000 96529582 95654128 1784582144 0.3951642215 0.1233235300 0.8781662583 666 26.6000000000 0.1152633354 0.0566372005 0.1690268219 0.0076893568 0.8738350000 96531276 95654128 1785966592 0.3842285275 0.1245466545 0.8739570975 667 26.6400000000 0.1154894605 0.0567254348 0.1690268219 0.0076910352 1.1788660000 96531850 95654128 1787744256 0.3737026751 0.1281267703 0.8724660277 668 26.6800000000 0.1142057702 0.0568114832 0.1690268219 0.0077114170 2.4693440000 96533544 95654128 1784569856 0.3627586365 0.1314646751 0.8679960966 669 26.7200000000 0.1134501398 0.0568961448 0.1690268219 0.0077553464 1.0298030000 96535238 95654128 1785966592 0.3517839313 0.1321435124 0.8644367456 670 26.7600000000 0.1130546927 0.0569799636 0.1690268219 0.0077843227 0.9282480000 96535672 95654128 1787871232 0.3422606587 0.1318802834 0.8609256148 671 26.8000000000 0.1132439300 0.0570638145 0.1690268219 0.0077895660 0.9049200000 96537366 95654128 1784705024 0.3327374160 0.1327074021 0.8570639491 672 26.8400000000 0.1124000028 0.0571461600 0.1690268219 0.0077855310 0.9110100000 96539060 95654128 1785974784 0.3232539892 0.1350618452 0.8520106673 673 26.8800000000 0.1122602671 0.0572280532 0.1690268219 0.0077807636 0.8453850000 96539634 95654128 1787752448 0.3145360649 0.1356430799 0.8482789993 674 26.9200000000 0.1115275770 0.0573086163 0.1690268219 0.0077753906 0.9877300000 96544480 95654128 1784578048 0.3057904840 0.1359965950 0.8439294100 675 26.9600000000 0.1106793731 0.0573876841 0.1690268219 0.0077698348 0.9273050000 96714930 95654128 1785847808 0.2972495854 0.1379464120 0.8400266171 676 27.0000000000 0.1100693941 0.0574656156 0.1690268219 0.0077655119 0.9122950000 96715364 95654128 1787879424 0.2885174155 0.1422213465 0.8359661102 677 27.0400000000 0.1095980555 0.0575426207 0.1690268219 0.0077715799 0.9077210000 96717058 95654128 1784451072 0.2798119187 0.1452403069 0.8335396647 678 27.0800000000 0.1099793911 0.0576199610 0.1690268219 0.0077823774 0.9484880000 96718752 95654128 1785737216 0.2715273201 0.1477433592 0.8304168582 679 27.1200000000 0.1095627919 0.0576964600 0.1690268219 0.0077933718 1.0049140000 96719326 95654128 1787752448 0.2629687190 0.1496375799 0.8262990713 680 27.1600000000 0.1094271094 0.0577725345 0.1690268219 0.0077937039 0.9674640000 96721020 95654128 1784373248 0.2551000118 0.1495228559 0.8211961389 681 27.2000000000 0.1088907570 0.0578475980 0.1690268219 0.0077884135 0.8702440000 96721454 95654128 1785720832 0.2471238226 0.1503993869 0.8172500730 682 27.2400000000 0.1082714200 0.0579215332 0.1690268219 0.0077831774 0.8293100000 96723148 95654128 1787490304 0.2391691506 0.1540718228 0.8123821616 683 27.2800000000 0.1071556211 0.0579936183 0.1690268219 0.0077829178 0.8460890000 96724842 95654128 1784442880 0.2314925939 0.1560909301 0.8070597053 684 27.3200000000 0.1069962531 0.0580652595 0.1690268219 0.0077856322 1.0181350000 96725276 95654128 1785839616 0.2234480530 0.1577362418 0.8024505973 685 27.3600000000 0.1063079089 0.0581356868 0.1690268219 0.0077851518 0.8478870000 96727110 95654128 1787744256 0.2156333327 0.1575749516 0.7964819670 686 27.4000000000 0.1058637574 0.0582052612 0.1690268219 0.0077809344 0.8061750000 96728804 95654128 1784569856 0.2075201869 0.1615853161 0.7904508114 687 27.4400000000 0.1056640744 0.0582743425 0.1690268219 0.0077877142 0.8724430000 96729238 95654128 1785966592 0.1995486319 0.1651976407 0.7846008539 688 27.4800000000 0.1043980494 0.0583413827 0.1690268219 0.0078042777 1.1542450000 96730932 95654128 1787871232 0.1912423223 0.1658483595 0.7779800892 689 27.5200000000 0.1047967225 0.0584088070 0.1690268219 0.0078121099 1.1112040000 96735370 95654128 1784442880 0.1833278388 0.1685675532 0.7726215720 690 27.5600000000 0.1047740951 0.0584760031 0.1690268219 0.0078132506 1.0897720000 96904516 95654128 1785839616 0.1756794751 0.1696807742 0.7662618756 691 27.6000000000 0.1040674001 0.0585419820 0.1690268219 0.0078148432 0.8221340000 96906350 95654128 1787871232 0.1669777036 0.1733621061 0.7595636845 692 27.6400000000 0.1033441648 0.0586067250 0.1690268219 0.0078316789 0.7548780000 96908044 95654128 1784569856 0.1585402191 0.1757643074 0.7531298995 693 27.6800000000 0.1034345478 0.0586714116 0.1690268219 0.0078637727 0.8021870000 96908478 95654128 1785982976 0.1508155912 0.1759296656 0.7463186979 694 27.7200000000 0.1033910289 0.0587358491 0.1690268219 0.0078771687 0.9736800000 96910172 95654128 1787744256 0.1437322646 0.1757130772 0.7380827069 695 27.7600000000 0.1031658128 0.0587997771 0.1690268219 0.0078759839 0.8642440000 96911866 95654128 1784606720 0.1368074864 0.1749459207 0.7304930091 696 27.8000000000 0.1029836610 0.0588632597 0.1690268219 0.0078716806 1.0840110000 96912300 95654128 1785966592 0.1295299977 0.1772772670 0.7231258154 697 27.8400000000 0.1021609455 0.0589253798 0.1690268219 0.0078695306 0.9750610000 96914134 95654128 1787871232 0.1219131500 0.1797740906 0.7157241702 698 27.8800000000 0.1016379297 0.0589865725 0.1690268219 0.0078711030 0.9367060000 96914568 95654128 1784475648 0.1134742722 0.1837984324 0.7090999484 699 27.9200000000 0.1002755761 0.0590456412 0.1690268219 0.0078801232 0.7894120000 96916262 95654128 1785712640 0.1054766253 0.1874784082 0.7013735771 700 27.9600000000 0.0992931947 0.0591031377 0.1690268219 0.0078966518 0.8211280000 96917956 95654128 1787633664 0.0972847119 0.1900992841 0.6938140988 701 28.0000000000 0.0988356546 0.0591598175 0.1690268219 0.0079149363 0.9546790000 96918390 95654128 1784569856 0.0894545317 0.1921938956 0.6873853207 702 28.0400000000 0.0980444849 0.0592152087 0.1690268219 0.0079281560 0.8448340000 96920084 95654128 1785839616 0.0816914141 0.1931023896 0.6803092957 703 28.0800000000 0.0977472439 0.0592700196 0.1690268219 0.0079342101 0.9399020000 96924186 95654128 1787871232 0.0747110099 0.1943842173 0.6750590801 704 28.1200000000 0.0971449316 0.0593238192 0.1690268219 0.0079387286 1.1133710000 97093376 95654128 1784442880 0.0663703233 0.2007050663 0.6700650454 705 28.1600000000 0.0966405869 0.0593767508 0.1690268219 0.0079611433 1.8283650000 97095070 95654128 1785712640 0.0583388768 0.2047221512 0.6654164791 706 28.2000000000 0.0964179188 0.0594292170 0.1690268219 0.0079792267 1.6825010000 97096764 95654128 1787752448 0.0508785769 0.2047508359 0.6607058644 707 28.2400000000 0.0956313759 0.0594804223 0.1690268219 0.0079811555 2.3617650000 97097198 95654128 1784324096 0.0435471609 0.2079003453 0.6561894417 708 28.2800000000 0.0955773517 0.0595314067 0.1690268219 0.0079784680 1.9192180000 97098892 95654128 1785720832 0.0355848558 0.2125947475 0.6530471444 709 28.3200000000 0.0952455625 0.0595817793 0.1690268219 0.0079737066 1.8596040000 97100726 95654128 1787625472 0.0292435400 0.2096132785 0.6495170593 710 28.3600000000 0.0951632559 0.0596318940 0.1690268219 0.0079701080 0.9707250000 97101160 95654128 1784442880 0.0225683413 0.2114197612 0.6455495358 711 28.4000000000 0.0938695744 0.0596800483 0.1690268219 0.0079646757 0.8475030000 97102854 95654128 1785839616 0.0146718714 0.2181480080 0.6430481672 712 28.4400000000 0.0937128365 0.0597278472 0.1690268219 0.0079613922 0.9692000000 97104548 95654128 1787617280 0.0066033509 0.2205118090 0.6402089596 713 28.4800000000 0.0940388665 0.0597759692 0.1690268219 0.0079589219 0.9131770000 97104982 95654128 1784569856 0.0015188521 0.2184980512 0.6387585402 714 28.5200000000 0.0928994566 0.0598223606 0.1690268219 0.0079751348 0.8593510000 97106676 95654128 1785982976 -0.0063216090 0.2256073654 0.6370538473 715 28.5600000000 0.0917711556 0.0598670443 0.1690268219 0.0079701048 0.8414960000 97107250 95654128 1787744256 -0.0150906174 0.2316671163 0.6354016662 716 28.6000000000 0.0917176530 0.0599115284 0.1690268219 0.0079704643 0.9844090000 97108944 95654128 1784569856 -0.0219078474 0.2337621599 0.6370506287 717 28.6400000000 0.0913546830 0.0599553821 0.1690268219 0.0079674430 0.8404280000 97110638 95654128 1785966592 -0.0283120424 0.2356332988 0.6390161514 718 28.6800000000 0.0909772888 0.0599985881 0.1690268219 0.0079628630 0.8225050000 97111072 95654128 1787744256 -0.0355564728 0.2406103760 0.6411189437 719 28.7200000000 0.0910144448 0.0600417256 0.1690268219 0.0079612143 0.9008020000 97112766 95654128 1784569856 -0.0432811193 0.2443540096 0.6427789927 720 28.7600000000 0.0914667770 0.0600853715 0.1690268219 0.0079582629 0.9279130000 97114460 95654128 1785966592 -0.0506581217 0.2478797287 0.6463692188 721 28.8000000000 0.0912362561 0.0601285766 0.1690268219 0.0079531352 0.8169280000 97115034 95654128 1787871232 -0.0575721152 0.2496626824 0.6498266459 722 28.8400000000 0.0906789377 0.0601708902 0.1690268219 0.0079480354 0.5875100000 97116728 95654128 1784504320 -0.0656150505 0.2525098026 0.6525387168 723 28.8800000000 0.0906531662 0.0602130510 0.1690268219 0.0079426018 0.9160970000 97118422 95654128 1785839616 -0.0734940469 0.2547451556 0.6567729712 724 28.9200000000 0.0907661021 0.0602552513 0.1690268219 0.0079371924 0.8483540000 97121428 95654128 1787744256 -0.0817064568 0.2583003342 0.6611425281 725 28.9600000000 0.0902990177 0.0602966910 0.1690268219 0.0079342110 0.9298090000 97291866 95654128 1784569856 -0.0903680772 0.2613682151 0.6655192375 726 29.0000000000 0.0899962261 0.0603375995 0.1690268219 0.0079397906 0.8368000000 97293560 95654128 1785839616 -0.0990792811 0.2619573772 0.6709989309 727 29.0400000000 0.0902254507 0.0603787107 0.1690268219 0.0079405062 0.7446590000 97294134 95654128 1787871232 -0.1081384718 0.2661290467 0.6753543019 728 29.0800000000 0.0911055133 0.0604209178 0.1690268219 0.0079417246 0.8406270000 97295828 95654128 1784475648 -0.1169081479 0.2702990472 0.6816988587 729 29.1200000000 0.0919216871 0.0604641287 0.1690268219 0.0079383018 0.7847040000 97297522 95654128 1785712640 -0.1258516014 0.2754643857 0.6871502995 730 29.1600000000 0.0917213485 0.0605069469 0.1690268219 0.0079347210 1.0523930000 97297956 95654128 1787744256 -0.1347614825 0.2767573297 0.6930715442 731 29.2000000000 0.0910378769 0.0605487128 0.1690268219 0.0079304516 0.8810000000 97299650 95654128 1784569856 -0.1441291124 0.2789567709 0.6984040141 732 29.2400000000 0.0909110829 0.0605901915 0.1690268219 0.0079260691 0.8314630000 97301344 95654128 1785839616 -0.1542826146 0.2835522294 0.7040705681 733 29.2800000000 0.0916903690 0.0606326201 0.1690268219 0.0079210927 0.8377950000 97301918 95654128 1787490304 -0.1642157733 0.2881476879 0.7116685510 734 29.3200000000 0.0916400477 0.0606748646 0.1690268219 0.0079167437 1.0237080000 97303612 95654128 1784442880 -0.1740670651 0.2921308279 0.7191358209 735 29.3600000000 0.0915445685 0.0607168642 0.1690268219 0.0079137761 0.8113940000 97304046 95654128 1785839616 -0.1832349747 0.2961637378 0.7262262106 736 29.4000000000 0.0914590284 0.0607586334 0.1690268219 0.0079098446 0.7925330000 97305740 95654128 1787744256 -0.1920437813 0.3006671369 0.7343527079 737 29.4400000000 0.0918605551 0.0608008341 0.1690268219 0.0079053035 0.9260320000 97307434 95654128 1784598528 -0.2010310441 0.3047464490 0.7415128350 738 29.4800000000 0.0920434520 0.0608431683 0.1690268219 0.0079051239 0.9105230000 97307868 95654128 1785966592 -0.2100848705 0.3085457981 0.7492915392 739 29.5200000000 0.0922856629 0.0608857156 0.1690268219 0.0079196806 0.8045140000 97309702 95654128 1787744256 -0.2181299925 0.3123754859 0.7568540573 740 29.5600000000 0.0932206661 0.0609294115 0.1690268219 0.0079372168 0.6483000000 97311396 95654128 1784569856 -0.2252773494 0.3163869977 0.7654116750 741 29.6000000000 0.0931785330 0.0609729326 0.1690268219 0.0079652519 0.6157990000 97313906 95654128 1785982976 -0.2326890230 0.3204962611 0.7738457322 742 29.6400000000 0.0940545350 0.0610175170 0.1690268219 0.0079820161 0.7295050000 97484348 95654128 1787871232 -0.2393639088 0.3252823949 0.7823404670 743 29.6800000000 0.0948561355 0.0610630602 0.1690268219 0.0079806289 0.9290970000 97486042 95654128 1784696832 -0.2442645878 0.3276147842 0.7903862596 744 29.7200000000 0.0945385620 0.0611080541 0.1690268219 0.0079755988 0.8275920000 97486476 95654128 1786101760 -0.2497549206 0.3290097713 0.7965852022 745 29.7600000000 0.0944532007 0.0611528127 0.1690268219 0.0079721318 0.9613940000 97488310 95654128 1787752448 -0.2551261187 0.3314827681 0.8028462529 746 29.8000000000 0.0950795338 0.0611982909 0.1690268219 0.0079682297 0.9321630000 97490004 95654128 1784578048 -0.2601992488 0.3343666196 0.8085064888 747 29.8400000000 0.0952311680 0.0612438503 0.1690268219 0.0079631040 0.9218770000 97490438 95654128 1785974784 -0.2654830217 0.3381492496 0.8132827282 748 29.8800000000 0.0954312161 0.0612895553 0.1690268219 0.0079608136 0.9258160000 97492132 95654128 1787752448 -0.2710315585 0.3419416845 0.8182046413 749 29.9200000000 0.0958237052 0.0613356624 0.1690268219 0.0079572688 0.8188280000 97493826 95654128 1784578048 -0.2747132778 0.3457626700 0.8244131804 750 29.9600000000 0.0960321948 0.0613819244 0.1690268219 0.0079545177 0.7355710000 97494260 95654128 1785991168 -0.2784163654 0.3489868045 0.8301643133 751 30.0000000000 0.0972095653 0.0614296310 0.1690268219 0.0079509439 0.8277200000 97496094 95654128 1787879424 -0.2829190195 0.3524872661 0.8341878653 752 30.0400000000 0.0977562591 0.0614779377 0.1690268219 0.0079469031 0.8077090000 97496528 95654128 1784451072 -0.2865984738 0.3560591638 0.8380716443 753 30.0800000000 0.0977221802 0.0615260708 0.1690268219 0.0079476369 0.9057240000 97498222 95654128 1785720832 -0.2910071909 0.3576355875 0.8409860134 754 30.1200000000 0.0980418250 0.0615745002 0.1690268219 0.0079537184 0.8403740000 97499916 95654128 1787744256 -0.2947562635 0.3601105809 0.8443980813 755 30.1600000000 0.0983795375 0.0616232486 0.1690268219 0.0079647100 0.8506820000 97500350 95654128 1784696832 -0.2986654341 0.3622027338 0.8476210833 756 30.2000000000 0.0993482620 0.0616731494 0.1690268219 0.0079728522 0.9075280000 97502044 95654128 1785966592 -0.3031493723 0.3663850427 0.8506476283 757 30.2400000000 0.0993464515 0.0617229160 0.1690268219 0.0079750791 0.9404980000 97503878 95654128 1787760640 -0.3083402514 0.3695153892 0.8526986837 758 30.2800000000 0.0990697443 0.0617721862 0.1690268219 0.0079797132 0.9659950000 97504312 95654128 1784442880 -0.3135948181 0.3705821931 0.8560723066 759 30.3200000000 0.0981252268 0.0618200822 0.1690268219 0.0080021186 0.8749670000 97506006 95654128 1785729024 -0.3188051283 0.3725724220 0.8595092893 760 30.3600000000 0.0980363637 0.0618677352 0.1690268219 0.0080159869 1.1168090000 97510044 95654128 1787490304 -0.3246787190 0.3779295683 0.8621261120 761 30.4000000000 0.0973437428 0.0619143528 0.1690268219 0.0080308697 2.0097160000 97679262 95654128 1784442880 -0.3313063979 0.3799630702 0.8653010726 762 30.4400000000 0.0970281884 0.0619604339 0.1690268219 0.0080360868 1.7626970000 97680956 95654128 1785839616 -0.3383049965 0.3829163909 0.8675718904 763 30.4800000000 0.0967652798 0.0620060497 0.1690268219 0.0080349105 0.8706030000 97682790 95654128 1787744256 -0.3453729153 0.3871368170 0.8688685894 764 30.5200000000 0.0970956534 0.0620519785 0.1690268219 0.0080348085 0.8221030000 97683224 95654128 1784569856 -0.3530103564 0.3916624486 0.8707166314 765 30.5600000000 0.0971826836 0.0620979010 0.1690268219 0.0080328230 0.9069740000 97684918 95654128 1785966592 -0.3605791628 0.3961819708 0.8722932935 766 30.6000000000 0.0968062058 0.0621432121 0.1690268219 0.0080331890 1.1297870000 97686612 95654128 1787744256 -0.3681347370 0.3993045688 0.8747919798 767 30.6400000000 0.0958368257 0.0621871412 0.1690268219 0.0080316207 0.9059350000 97687046 95654128 1784569856 -0.3753254712 0.4031382799 0.8767144680 768 30.6800000000 0.0962228328 0.0622314585 0.1690268219 0.0080329018 0.9473690000 97688740 95654128 1785966592 -0.3833000064 0.4078413844 0.8782015443 769 30.7200000000 0.0970941037 0.0622767935 0.1690268219 0.0080333627 0.9354470000 97689314 95654128 1787744256 -0.3920409381 0.4132426083 0.8795579076 770 30.7600000000 0.0971252248 0.0623220512 0.1690268219 0.0080313497 0.9016330000 97691008 95654128 1784569856 -0.4007616937 0.4174490869 0.8812096119 771 30.8000000000 0.0968996435 0.0623668990 0.1690268219 0.0080274428 1.2192730000 97692702 95654128 1785966592 -0.4086489081 0.4217171073 0.8821088672 772 30.8400000000 0.0965854451 0.0624112235 0.1690268219 0.0080261345 1.0280430000 97693136 95654128 1787744256 -0.4167396724 0.4242625535 0.8830860853 773 30.8800000000 0.0962272584 0.0624549700 0.1690268219 0.0080267722 0.8279250000 97694830 95654128 1784569856 -0.4255499244 0.4267709851 0.8841453195 774 30.9200000000 0.0964775681 0.0624989268 0.1690268219 0.0080291943 0.8213510000 97696524 95654128 1785966592 -0.4336864948 0.4299040735 0.8847137094 775 30.9600000000 0.0961423218 0.0625423377 0.1690268219 0.0080351755 0.9588550000 97697098 95654128 1787998208 -0.4414633811 0.4314508438 0.8863407969 776 31.0000000000 0.0963284001 0.0625858764 0.1690268219 0.0080421954 0.9925630000 97698792 95654128 1784569856 -0.4496388435 0.4340808094 0.8875762820 777 31.0400000000 0.0965169892 0.0626295458 0.1690268219 0.0080533907 0.9909550000 97700486 95654128 1785839616 -0.4577878118 0.4379863739 0.8882476091 778 31.0800000000 0.0960391760 0.0626724888 0.1690268219 0.0080571950 0.8491950000 97700920 95654128 1787871232 -0.4657917917 0.4408862889 0.8895369768 779 31.1200000000 0.0960292444 0.0627153087 0.1690268219 0.0080561047 0.8645450000 97702614 95654128 1784451072 -0.4738775194 0.4429309070 0.8910998702 780 31.1600000000 0.0959014520 0.0627578551 0.1690268219 0.0080559087 0.9751860000 97704308 95654128 1785720832 -0.4810798168 0.4459416568 0.8918996453 781 31.2000000000 0.0962952599 0.0628007967 0.1690268219 0.0080538363 0.8229540000 97704882 95654128 1787752448 -0.4887980521 0.4488715827 0.8928914070 782 31.2400000000 0.0963573977 0.0628437079 0.1690268219 0.0080497512 0.9629150000 97706576 95654128 1784705024 -0.4961821437 0.4503391981 0.8933209777 783 31.2800000000 0.0964453444 0.0628866219 0.1690268219 0.0080456802 0.8831790000 97708270 95654128 1786355712 -0.5039971471 0.4517632723 0.8940474987 784 31.3200000000 0.0968788043 0.0629299793 0.1690268219 0.0080410206 0.9703200000 97708704 95654128 1785720832 -0.5107283592 0.4533611238 0.8959874511 785 31.3600000000 0.0972118825 0.0629736505 0.1690268219 0.0080360527 0.8362960000 97710398 95654128 1787244544 -0.5171872377 0.4546223283 0.8960064054 786 31.4000000000 0.0972617865 0.0630172741 0.1690268219 0.0080330174 0.9060420000 97712092 95654128 1784958976 -0.5230950713 0.4560144544 0.8971209526 787 31.4400000000 0.0975354239 0.0630611345 0.1690268219 0.0080291053 1.0159920000 97712666 95654128 1786482688 -0.5287658572 0.4584442377 0.8982127309 788 31.4800000000 0.0979269445 0.0631053805 0.1690268219 0.0080261854 1.5857680000 97714360 95654128 1784705024 -0.5343528390 0.4595577717 0.8995515108 789 31.5200000000 0.0981217474 0.0631497611 0.1690268219 0.0080238508 0.8420900000 97714794 95654128 1786232832 -0.5402324796 0.4594965875 0.9000886679 790 31.5600000000 0.0982627049 0.0631942079 0.1690268219 0.0080192532 0.6939610000 97716488 95654128 1785737216 -0.5456484556 0.4596823454 0.9011159539 791 31.6000000000 0.0986828431 0.0632390734 0.1690268219 0.0080146783 0.7286250000 97718182 95654128 1787109376 -0.5496726036 0.4611630142 0.9022291303 792 31.6400000000 0.0988161936 0.0632839941 0.1690268219 0.0080096956 0.8444530000 97718616 95654128 1785204736 -0.5535505414 0.4610844254 0.9043043852 793 31.6800000000 0.0991699398 0.0633292475 0.1690268219 0.0080056269 0.7853560000 97720450 95654128 1786728448 -0.5579383373 0.4603552818 0.9052890539 794 31.7200000000 0.0995305181 0.0633748410 0.1690268219 0.0080063660 0.9663020000 97722144 95654128 1784823808 -0.5616651773 0.4593589306 0.9066953659 795 31.7600000000 0.0996521115 0.0634204728 0.1690268219 0.0080169502 0.9005340000 97722578 95654128 1786359808 -0.5645052195 0.4588200152 0.9079643488 796 31.8000000000 0.1000749618 0.0634665211 0.1690268219 0.0080347296 0.7799680000 97724272 95654128 1785618432 -0.5677312613 0.4581718445 0.9096426964 797 31.8400000000 0.1000392288 0.0635124091 0.1690268219 0.0080521965 0.9824020000 97725966 95654128 1787109376 -0.5703484416 0.4567738771 0.9113218784 798 31.8800000000 0.1002681404 0.0635584689 0.1690268219 0.0080706679 2.1317050000 97726400 95654128 1785077760 -0.5732834935 0.4555834830 0.9121200442 799 31.9200000000 0.1002606601 0.0636044041 0.1690268219 0.0080810310 2.0604290000 97728234 95654128 1786601472 -0.5757536292 0.4538631439 0.9135462046 800 31.9600000000 0.1003271565 0.0636503075 0.1690268219 0.0080891963 0.8011180000 97729928 95654128 1784942592 -0.5782495737 0.4518677592 0.9147704244 801 32.0000000000 0.1010298356 0.0636969736 0.1690268219 0.0081034039 0.7829120000 97730362 95654128 1786220544 -0.5803308487 0.4510757923 0.9163956046 802 32.0400000000 0.1016652361 0.0637443156 0.1690268219 0.0081109826 0.8851820000 97732056 95654128 1785712640 -0.5825824738 0.4497393370 0.9177910686 803 32.0800000000 0.1017197743 0.0637916075 0.1690268219 0.0081205767 0.9557530000 97733750 95654128 1786982400 -0.5834810138 0.4493384659 0.9208177328 804 32.1199999990 0.1022714674 0.0638394681 0.1690268219 0.0081349480 0.8462420000 97734184 95654128 1784950784 -0.5850840211 0.4488301873 0.9229820371 805 32.1600000000 0.1025589257 0.0638875668 0.1690268219 0.0081510722 0.7919920000 97736018 95654128 1786347520 -0.5862259865 0.4474817812 0.9247196317 806 32.2000000000 0.1029565260 0.0639360394 0.1690268219 0.0081677268 0.8957240000 97736452 95654128 1785712640 -0.5874805450 0.4464513958 0.9262441993 807 32.2400000000 0.1033692434 0.0639849034 0.1690268219 0.0081854174 0.7384780000 97738146 95654128 1787125760 -0.5883381963 0.4436855316 0.9282618165 808 32.2800000000 0.1035029590 0.0640338118 0.1690268219 0.0081933958 0.8032350000 97739840 95654128 1784696832 -0.5900708437 0.4409149289 0.9307109118 809 32.3200000000 0.1042820737 0.0640835625 0.1690268219 0.0082011778 0.8543380000 97740274 95654128 1786093568 -0.5904287100 0.4381778240 0.9328568578 810 32.3600000000 0.1046644002 0.0641336623 0.1690268219 0.0082067168 1.0265340000 97741968 95654128 1787998208 -0.5913338065 0.4362027943 0.9348250628 811 32.4000000000 0.1048824862 0.0641839074 0.1690268219 0.0082059594 0.9575580000 97743802 95654128 1784950784 -0.5927373767 0.4323088229 0.9372735620 812 32.4399999990 0.1057851389 0.0642351405 0.1690268219 0.0082059733 0.7263840000 97744236 95654128 1786220544 -0.5939137340 0.4296490252 0.9392792583 813 32.4800000000 0.1059522033 0.0642864530 0.1690268219 0.0082055131 0.9057670000 97745930 95654128 1787998208 -0.5950939655 0.4263239205 0.9431838393 814 32.5200000000 0.1065416485 0.0643383635 0.1690268219 0.0082047790 0.8040990000 97747624 95654128 1784741888 -0.5962600708 0.4236266911 0.9466623068 815 32.5600000000 0.1063194200 0.0643898740 0.1690268219 0.0082027562 0.8282710000 97748058 95654128 1786220544 -0.5967991352 0.4205731153 0.9492259622 816 32.6000000000 0.1068706438 0.0644419338 0.1690268219 0.0082013347 0.8580110000 97749752 95654128 1788006400 -0.5970358849 0.4170200825 0.9524154663 817 32.6400000000 0.1067920625 0.0644937700 0.1690268219 0.0081979822 0.8932980000 97751586 95654128 1784578048 -0.5972453952 0.4139294326 0.9553860426 818 32.6800000000 0.1085206941 0.0645475926 0.1690268219 0.0081938211 0.7627200000 97752020 95654128 1785974784 -0.5989299417 0.4117205441 0.9587625861 819 32.7200000000 0.1093109101 0.0646022487 0.1690268219 0.0081904068 0.9285620000 97753714 95654128 1787879424 -0.5991820693 0.4107632339 0.9630060196 820 32.7599999990 0.1099469736 0.0646575471 0.1690268219 0.0081889592 0.9298690000 97755408 95654128 1784578048 -0.5990527272 0.4096626341 0.9677520394 821 32.7999999990 0.1100766733 0.0647128688 0.1690268219 0.0081926067 1.0164020000 97755842 95654128 1785974784 -0.5994964242 0.4069316983 0.9738454223 822 32.8400000000 0.1109148338 0.0647690756 0.1690268219 0.0082155037 0.8660350000 97757536 95654128 1787879424 -0.6003888845 0.4049648345 0.9785055518 823 32.8800000000 0.1109913737 0.0648252388 0.1690268219 0.0082243828 0.8655240000 97758110 95654128 1784578048 -0.6011471152 0.4028907716 0.9835672975 824 32.9200000000 0.1113962680 0.0648817570 0.1690268219 0.0082310819 0.8110230000 97759804 95654128 1785991168 -0.6016266346 0.4025935829 0.9886184335 825 32.9600000000 0.1121208742 0.0649390165 0.1690268219 0.0082433614 0.7783330000 97761498 95654128 1787752448 -0.6022903323 0.4009840488 0.9941111803 826 33.0000000000 0.1131258979 0.0649973542 0.1690268219 0.0082550187 0.9157930000 97761932 95654128 1784569856 -0.6032468677 0.4006995857 0.9998337626 827 33.0400000000 0.1141640544 0.0650568060 0.1690268219 0.0082713696 0.8083340000 97763626 95654128 1785966592 -0.6045429707 0.3984217346 1.0050698519 828 33.0800000000 0.1146365032 0.0651166849 0.1690268219 0.0082955185 0.7696160000 97765320 95654128 1787871232 -0.6049319506 0.3952111006 1.0104590654 829 33.1199999990 0.1156586036 0.0651776522 0.1690268219 0.0083169815 0.9384900000 97765894 95654128 1784459264 -0.6064285636 0.3928339183 1.0159664154 830 33.1600000000 0.1164958775 0.0652394814 0.1690268219 0.0083339028 0.9558220000 97767588 95654128 1785839616 -0.6072842479 0.3903468549 1.0216708183 831 33.2000000000 0.1170409769 0.0653018178 0.1690268219 0.0083521972 1.0763580000 97769282 95654128 1787871232 -0.6076447964 0.3857032061 1.0284380913 832 33.2400000000 0.1174440458 0.0653644887 0.1690268219 0.0083625768 1.0416090000 97769716 95654128 1784569856 -0.6082425117 0.3822407424 1.0348318815 833 33.2800000000 0.1184891537 0.0654282638 0.1690268219 0.0083649907 0.8438860000 97771410 95654128 1785839616 -0.6105324626 0.3791827261 1.0415301323 834 33.3200000000 0.1191500872 0.0654926785 0.1690268219 0.0083688348 0.8827040000 97773104 95654128 1787871232 -0.6120193601 0.3744260371 1.0477037430 835 33.3600000000 0.1190784872 0.0655568531 0.1690268219 0.0083728688 0.9670170000 97773678 95654128 1784586240 -0.6139892340 0.3712074161 1.0536400080 836 33.4000000000 0.1195339561 0.0656214190 0.1690268219 0.0083822581 0.8717550000 97775372 95654128 1785839616 -0.6154367328 0.3676791787 1.0603414774 837 33.4399999990 0.1204597130 0.0656869367 0.1690268219 0.0084003641 0.8434700000 97777066 95654128 1787871232 -0.6169958115 0.3660403788 1.0665242672 838 33.4800000000 0.1210482568 0.0657530003 0.1690268219 0.0084280916 0.9259820000 97777500 95654128 1784348672 -0.6179436445 0.3615617752 1.0721977949 839 33.5200000000 0.1220947653 0.0658201538 0.1690268219 0.0084613392 1.0762010000 97779194 95654128 1785712640 -0.6191696525 0.3599595129 1.0780140162 840 33.5600000000 0.1233194545 0.0658886053 0.1690268219 0.0084867127 1.4026100000 97783564 95654128 1787617280 -0.6212753057 0.3592824936 1.0818549395 841 33.6000000000 0.1237148494 0.0659573642 0.1690268219 0.0084879214 0.9131410000 97952910 95654128 1784569856 -0.6229789853 0.3575921655 1.0870149136 842 33.6400000000 0.1242454648 0.0660265900 0.1690268219 0.0084873866 0.7250660000 97954604 95654128 1785982976 -0.6244586110 0.3562186956 1.0912613869 843 33.6800000000 0.1250570863 0.0660966143 0.1690268219 0.0084888171 0.8082920000 97955038 95654128 1785458688 -0.6254767776 0.3539258838 1.0964090824 844 33.7200000000 0.1257166266 0.0661672542 0.1690268219 0.0084938935 0.7072880000 97956732 95654128 1786855424 -0.6263191104 0.3497997820 1.1014460325 845 33.7599999990 0.1269885153 0.0662392320 0.1690268219 0.0085087883 0.9290630000 97958426 95654128 1784569856 -0.6271904111 0.3477591574 1.1058977842 846 33.7999999990 0.1271654367 0.0663112488 0.1690268219 0.0085147531 0.8487130000 97958860 95654128 1785966592 -0.6280658841 0.3459819257 1.1107270718 847 33.8400000000 0.1277230829 0.0663837539 0.1690268219 0.0085131585 1.0194630000 97960694 95654128 1787744256 -0.6296240091 0.3415051401 1.1139049530 848 33.8800000000 0.1281116307 0.0664565462 0.1690268219 0.0085085934 0.9742480000 97962388 95654128 1784569856 -0.6303566098 0.3387612104 1.1177399158 849 33.9200000000 0.1289969236 0.0665302098 0.1690268219 0.0085039003 1.1181730000 97962822 95654128 1785966592 -0.6318997145 0.3340651095 1.1203722954 850 33.9600000000 0.1282915771 0.0666028702 0.1690268219 0.0084995348 1.9560770000 97964516 95654128 1787744256 -0.6325039864 0.3296869397 1.1241695881 851 34.0000000000 0.1286697984 0.0666758043 0.1690268219 0.0084945697 0.9626710000 97966210 95654128 1784696832 -0.6333909631 0.3274714053 1.1274061203 852 34.0400000000 0.1286427230 0.0667485354 0.1690268219 0.0084897679 1.0261430000 97966644 95654128 1786101760 -0.6336566210 0.3218996823 1.1306362152 853 34.0800000000 0.1283405572 0.0668207418 0.1690268219 0.0084864461 0.9860100000 97968478 95654128 1787752448 -0.6336306930 0.3184909225 1.1336599588 854 34.1199999990 0.1290882379 0.0668936546 0.1690268219 0.0084861314 0.8755690000 97970172 95654128 1784705024 -0.6346107125 0.3164964914 1.1365982294 855 34.1600000000 0.1293450147 0.0669666971 0.1690268219 0.0084869766 0.6856330000 97970606 95654128 1785991168 -0.6341248751 0.3137436211 1.1403412819 856 34.2000000000 0.1298154444 0.0670401185 0.1690268219 0.0084885286 0.8512780000 97972300 95654128 1787879424 -0.6342202425 0.3118402064 1.1436018944 857 34.2400000000 0.1312420666 0.0671150333 0.1690268219 0.0084848322 0.8635780000 97973994 95654128 1784578048 -0.6362917423 0.3118895888 1.1467182636 858 34.2800000000 0.1313042939 0.0671898459 0.1690268219 0.0084799776 0.9253620000 97974428 95654128 1785847808 -0.6378648877 0.3094217181 1.1495853662 859 34.3200000000 0.1314464658 0.0672646499 0.1690268219 0.0084754419 0.8872550000 97976262 95654128 1787879424 -0.6372780204 0.3038553298 1.1514072418 860 34.3600000000 0.1321008503 0.0673400408 0.1690268219 0.0084713186 1.0086480000 97976696 95654128 1784578048 -0.6380028725 0.2998457253 1.1529123783 861 34.4000000000 0.1315159649 0.0674145773 0.1690268219 0.0084666657 0.7851430000 97978390 95654128 1785839616 -0.6373652220 0.2965696156 1.1554783583 862 34.4400000000 0.1318612546 0.0674893415 0.1690268219 0.0084617982 0.8520380000 97982764 95654128 1787871232 -0.6372109056 0.2933243215 1.1571621895 863 34.4800000000 0.1314977407 0.0675635111 0.1690268219 0.0084577548 1.0019860000 98151958 95654128 1784569856 -0.6364047527 0.2873795927 1.1585444212 864 34.5200000000 0.1312688589 0.0676372442 0.1690268219 0.0084542181 0.9962810000 98153652 95654128 1785839616 -0.6372124553 0.2831655443 1.1601068974 865 34.5600000000 0.1306843013 0.0677101309 0.1690268219 0.0084494030 1.0076470000 98155486 95654128 1787744256 -0.6381291747 0.2814552784 1.1617926359 866 34.6000000000 0.1313857585 0.0677836594 0.1690268219 0.0084453012 0.9253540000 98155920 95654128 1784442880 -0.6391912699 0.2810644805 1.1628684998 867 34.6400000000 0.1304704547 0.0678559625 0.1690268219 0.0084423144 0.8772080000 98157614 95654128 1785839616 -0.6394746304 0.2769347131 1.1642621756 868 34.6800000000 0.1300832480 0.0679276529 0.1690268219 0.0084378299 0.9067050000 98159308 95654128 1787744256 -0.6399956942 0.2727445364 1.1651502848 869 34.7200000000 0.1302709579 0.0679993943 0.1690268219 0.0084342859 0.8124190000 98159742 95654128 1784606720 -0.6399008632 0.2693607509 1.1659955978 870 34.7600000000 0.1305904537 0.0680713381 0.1690268219 0.0084303134 0.8113720000 98161436 95654128 1785966592 -0.6422926188 0.2660441697 1.1672278643 871 34.8000000000 0.1312042773 0.0681438214 0.1690268219 0.0084264023 0.8820460000 98163270 95654128 1787744256 -0.6420305371 0.2659949958 1.1678147316 872 34.8400000000 0.1312262565 0.0682161636 0.1690268219 0.0084220575 1.0083560000 98163704 95654128 1784569856 -0.6438989639 0.2622925043 1.1688406467 873 34.8800000000 0.1314910650 0.0682886434 0.1690268219 0.0084180931 0.8515080000 98165398 95654128 1785966592 -0.6453590393 0.2598726749 1.1701830626 874 34.9200000000 0.1322555989 0.0683618322 0.1690268219 0.0084144774 0.8612970000 98167092 95654128 1787998208 -0.6470766664 0.2587847412 1.1711509228 875 34.9600000000 0.1320127398 0.0684345761 0.1690268219 0.0084112529 1.0595920000 98167526 95654128 1784586240 -0.6485075355 0.2586843371 1.1731914282 876 35.0000000000 0.1326262802 0.0685078543 0.1690268219 0.0084069152 0.8959940000 98169220 95654128 1785966592 -0.6493431926 0.2585894465 1.1738488674 877 35.0400000000 0.1305317581 0.0685785771 0.1690268219 0.0084022972 0.8061300000 98169794 95654128 1787871232 -0.6490578055 0.2566043139 1.1750694513 878 35.0800000000 0.1306053996 0.0686492227 0.1690268219 0.0083976322 0.7177440000 98171488 95654128 1784598528 -0.6497696638 0.2571476698 1.1761513948 879 35.1200000000 0.1324649006 0.0687218230 0.1690268219 0.0083931661 0.8558600000 98173182 95654128 1785966592 -0.6521306634 0.2572622895 1.1775941849 880 35.1600000000 0.1348252892 0.0687969406 0.1690268219 0.0083885104 0.8400880000 98173616 95654128 1787744256 -0.6543141603 0.2600122988 1.1788649559 881 35.2000000000 0.1356650740 0.0688728408 0.1690268219 0.0083841899 1.2429140000 98175310 95654128 1784696832 -0.6550036073 0.2611632049 1.1802357435 882 35.2400000000 0.1360808015 0.0689490403 0.1690268219 0.0083801498 1.5851690000 98177004 95654128 1785966592 -0.6550836563 0.2572710216 1.1810078621 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-19 04:33:42 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.2433110000 88427542 95654128 1753587712 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0015061001 0.0007530500 0.0015061001 0.0018541897 1.3679140000 88881670 95654128 1756508160 -0.0002115301 0.0021070603 0.0016081244 3 0.0800000000 0.0051624225 0.0022228409 0.0051624225 0.0020662965 1.1524590000 88883688 95654128 1758412800 -0.0021166240 -0.0076440927 0.0021208269 4 0.1200000000 0.0061746258 0.0032107871 0.0061746258 0.0026521142 1.2248730000 88884450 95654128 1760190464 -0.0043604253 -0.0071556014 0.0010601312 5 0.1600000000 0.0052042869 0.0036094871 0.0061746258 0.0045019434 1.4097490000 88886464 95654128 1761824768 -0.0025880532 0.0001105652 0.0040212208 6 0.2000000000 0.0058609555 0.0039847318 0.0061746258 0.0045756216 1.6390290000 88888814 95654128 1763577856 -0.0007725633 -0.0102501158 0.0032170252 7 0.2400000000 0.0077999579 0.0045297641 0.0077999579 0.0042792614 2.1088340000 88889248 95654128 1765228544 0.0006374081 -0.0227531847 0.0007032438 8 0.2800000000 0.0059381034 0.0047058065 0.0077999579 0.0039941172 2.1916290000 88890942 95654128 1766805504 -0.0012284035 -0.0190775394 -0.0005988954 9 0.3200000000 0.0059401481 0.0048429556 0.0077999579 0.0049673001 1.5028030000 88893276 95654128 1768583168 -0.0020816834 -0.0151642272 0.0027334418 10 0.3600000000 0.0040903115 0.0047676912 0.0077999579 0.0047507229 1.7604250000 88895022 95654128 1770360832 -0.0038931950 -0.0208792631 0.0007899009 11 0.4000000000 0.0041611716 0.0047125530 0.0077999579 0.0046822206 2.1842470000 88896828 95654128 1771859968 -0.0033655113 -0.0171606373 -0.0004608234 12 0.4400000000 0.0035554043 0.0046161240 0.0077999579 0.0047743797 1.3800430000 88898522 95654128 1773637632 -0.0038431706 -0.0063074632 0.0024072803 13 0.4800000000 0.0038726067 0.0045589303 0.0077999579 0.0046153716 1.5111860000 88898956 95654128 1775415296 -0.0036074820 -0.0070302812 0.0025524744 14 0.5200000000 0.0047911834 0.0045755198 0.0077999579 0.0044969057 1.8678840000 88900650 95654128 1777065984 -0.0015193999 -0.0151717495 0.0001297297 15 0.5600000000 0.0044789440 0.0045690814 0.0077999579 0.0044764382 1.6506070000 88902344 95654128 1778843648 0.0018389507 -0.0137165096 0.0001314575 16 0.6000000000 0.0038710318 0.0045254533 0.0077999579 0.0043451223 1.8106990000 88902778 95654128 1780469760 0.0030917763 -0.0112649575 0.0004570980 17 0.6400000000 0.0031842489 0.0044465590 0.0077999579 0.0042351626 3.0770380000 88905752 95654128 1782222848 0.0033963614 -0.0136465542 -0.0013920283 18 0.6800000000 0.0035370186 0.0043960289 0.0077999579 0.0041177506 2.8060680000 88910070 95654128 1783873536 0.0024540985 -0.0138749015 -0.0026942627 19 0.7200000000 0.0035926832 0.0043537476 0.0077999579 0.0041226208 2.4946650000 88910504 95654128 1785540608 0.0029423966 -0.0084678084 -0.0020872033 20 0.7600000000 0.0049786395 0.0043849922 0.0077999579 0.0043475296 1.9620980000 88912198 95654128 1787420672 0.0012419542 -0.0083571607 -0.0047364864 21 0.8000000000 0.0049706828 0.0044128822 0.0077999579 0.0044808540 2.1750820000 88913892 95654128 1784119296 0.0037069316 -0.0070194337 -0.0038673377 22 0.8400000000 0.0046807970 0.0044250602 0.0077999579 0.0044509592 1.5325670000 88914326 95654128 1785516032 0.0042812140 -0.0045694532 -0.0034118036 23 0.8800000000 0.0059137819 0.0044897872 0.0077999579 0.0043706015 2.2635950000 88916020 95654128 1787420672 0.0056662662 -0.0096320156 -0.0070735775 24 0.9200000000 0.0054464908 0.0045296498 0.0077999579 0.0043150996 1.9350700000 88917714 95654128 1784754176 0.0087009622 -0.0079126339 -0.0065317238 25 0.9600000000 0.0064993971 0.0046084397 0.0077999579 0.0042444607 1.9287840000 88918148 95654128 1786015744 0.0078999503 -0.0134686325 -0.0090154195 26 1.0000000000 0.0063287932 0.0046746072 0.0077999579 0.0041624329 1.8492320000 88919842 95654128 1787809792 0.0069297049 -0.0147697125 -0.0098269051 27 1.0400000000 0.0066499319 0.0047477674 0.0077999579 0.0040840861 2.3981400000 88921536 95654128 1784492032 0.0079063214 -0.0186268110 -0.0118070841 28 1.0800000000 0.0067699803 0.0048199892 0.0077999579 0.0040166090 2.2598430000 88921970 95654128 1785888768 0.0061359722 -0.0197751503 -0.0133109391 29 1.1200000000 0.0066804620 0.0048841435 0.0077999579 0.0040525994 1.8301290000 88923664 95654128 1787539456 0.0085110385 -0.0225826558 -0.0138139976 30 1.1600000000 0.0074174143 0.0049685858 0.0077999579 0.0040242421 1.7472680000 88925358 95654128 1784492032 0.0116086695 -0.0224247165 -0.0136730568 31 1.2000000000 0.0070857969 0.0050368830 0.0077999579 0.0040096676 2.5160120000 88925792 95654128 1786150912 0.0164411422 -0.0194225274 -0.0149544813 32 1.2400000000 0.0091586858 0.0051656893 0.0091586858 0.0041429336 1.4386900000 88927486 95654128 1787801600 0.0155306114 -0.0195875838 -0.0155625744 33 1.2800000000 0.0098572969 0.0053078592 0.0098572969 0.0043753110 1.8302570000 88931740 95654128 1784500224 0.0165915079 -0.0162493531 -0.0152043300 34 1.3200000000 0.0096902745 0.0054367538 0.0098572969 0.0045916517 1.8305050000 88937422 95654128 1786023936 0.0243908651 -0.0124434568 -0.0172821600 35 1.3600000000 0.0102192387 0.0055733962 0.0102192387 0.0045252979 2.7710120000 88939116 95654128 1788182528 0.0243946575 -0.0149518996 -0.0182828475 36 1.4000000000 0.0109039014 0.0057214658 0.0109039014 0.0044698673 2.3345840000 88940810 95654128 1784754176 0.0240832921 -0.0175388493 -0.0213941950 37 1.4400000000 0.0125392219 0.0059057295 0.0125392219 0.0044172811 1.7330770000 88941244 95654128 1786023936 0.0246599596 -0.0193084031 -0.0233754292 38 1.4800000000 0.0128559750 0.0060886307 0.0128559750 0.0043592119 2.0097530000 88942938 95654128 1787928576 0.0237518921 -0.0190084223 -0.0236621164 39 1.5200000000 0.0132173793 0.0062714191 0.0132173793 0.0043380457 1.6477470000 88944632 95654128 1784365056 0.0239044745 -0.0179193709 -0.0244867690 40 1.5600000000 0.0121999104 0.0064196314 0.0132173793 0.0045355934 1.4198710000 88945066 95654128 1785888768 0.0279761292 -0.0159583222 -0.0249908138 41 1.6000000000 0.0124884993 0.0065676526 0.0132173793 0.0048018242 1.8689580000 88946760 95654128 1787793408 0.0328932889 -0.0128278108 -0.0253724791 42 1.6400000000 0.0133340294 0.0067287568 0.0133340294 0.0047531708 1.6116720000 88948454 95654128 1784381440 0.0319585092 -0.0122873103 -0.0266559273 43 1.6800000000 0.0140753109 0.0068996069 0.0140753109 0.0047203005 1.8599240000 88948888 95654128 1785888768 0.0329938978 -0.0132971359 -0.0280609708 44 1.7200000000 0.0151450494 0.0070870033 0.0151450494 0.0046740989 2.4150250000 88950582 95654128 1787920384 0.0335073508 -0.0124828322 -0.0283502899 45 1.7600000000 0.0166287217 0.0072990415 0.0166287217 0.0047407788 2.3636030000 88952276 95654128 1784619008 0.0332685336 -0.0075834338 -0.0297015607 46 1.8000000000 0.0160072986 0.0074883514 0.0166287217 0.0048527229 1.7491980000 88952710 95654128 1786015744 0.0355903506 -0.0081079081 -0.0300754011 47 1.8400000000 0.0167021565 0.0076843898 0.0167021565 0.0048771807 2.0264440000 88954404 95654128 1787920384 0.0367533639 -0.0070765340 -0.0302507021 48 1.8800000000 0.0170220025 0.0078789234 0.0170220025 0.0048619824 1.8414540000 88956098 95654128 1784635392 0.0382825397 -0.0063538789 -0.0301651321 49 1.9200000000 0.0165821705 0.0080565407 0.0170220025 0.0049036650 2.1164750000 88956532 95654128 1786015744 0.0401138514 -0.0089240456 -0.0319049321 50 1.9600000000 0.0170022789 0.0082354555 0.0170220025 0.0048783388 2.4109270000 88958210 95654128 1787920384 0.0353107601 -0.0078194831 -0.0335168615 51 2.0000000000 0.0169702824 0.0084067266 0.0170220025 0.0048630455 2.8412590000 88959904 95654128 1784492032 0.0346028768 -0.0039490610 -0.0327351354 52 2.0400000000 0.0174485426 0.0085806077 0.0174485426 0.0048291704 2.6199170000 88960338 95654128 1786015744 0.0341059715 -0.0060598324 -0.0330192447 53 2.0800000000 0.0177764948 0.0087541150 0.0177764948 0.0047940508 1.6364230000 88962016 95654128 1787801600 0.0343422778 -0.0106836911 -0.0350398347 54 2.1200000000 0.0176323242 0.0089185263 0.0177764948 0.0047988834 2.0718410000 88965226 95654128 1784754176 0.0344194211 -0.0091857621 -0.0350073688 55 2.1600000000 0.0170419551 0.0090662250 0.0177764948 0.0048091324 1.6224280000 89134228 95654128 1786023936 0.0352580510 -0.0056911185 -0.0356634259 56 2.2000000000 0.0158751234 0.0091878124 0.0177764948 0.0048513752 1.7963630000 89135922 95654128 1787928576 0.0385274813 -0.0075712488 -0.0363563262 57 2.2400000000 0.0156131322 0.0093005373 0.0177764948 0.0048533698 2.0621870000 89137600 95654128 1784246272 0.0388877615 -0.0100225918 -0.0390037596 58 2.2800000000 0.0147393914 0.0093943107 0.0177764948 0.0049888436 1.6123570000 89138034 95654128 1785761792 0.0434297621 -0.0085585453 -0.0387133919 59 2.3200000000 0.0142018953 0.0094757952 0.0177764948 0.0051942298 1.9245110000 89139712 95654128 1787666432 0.0481793061 -0.0064253146 -0.0393322334 60 2.3600000000 0.0146550853 0.0095621167 0.0177764948 0.0052119172 1.9616210000 89141390 95654128 1784745984 0.0506995432 -0.0100980094 -0.0419169627 61 2.4000000000 0.0154151721 0.0096580684 0.0177764948 0.0051808318 2.8320930000 89141808 95654128 1786142720 0.0487883016 -0.0112363156 -0.0439411141 62 2.4400000000 0.0131802056 0.0097148771 0.0177764948 0.0052430825 1.2235630000 89143470 95654128 1788047360 0.0531113781 -0.0097715203 -0.0438237377 63 2.4800000000 0.0138896238 0.0097811429 0.0177764948 0.0052495943 2.2313020000 89145148 95654128 1784619008 0.0582487732 -0.0072529167 -0.0443240553 64 2.5200000000 0.0139595969 0.0098464312 0.0177764948 0.0052259098 2.0549690000 89145582 95654128 1786142720 0.0606836602 -0.0110504907 -0.0480503365 65 2.5600000000 0.0119447475 0.0098787130 0.0177764948 0.0052387687 1.7288520000 89152380 95654128 1787920384 0.0636744872 -0.0089913923 -0.0485067517 66 2.6000000000 0.0122890240 0.0099152329 0.0177764948 0.0052012079 2.0513200000 89164554 95654128 1784492032 0.0603147112 -0.0113232965 -0.0512138382 67 2.6400000000 0.0140226847 0.0099765381 0.0177764948 0.0052073595 1.9964060000 89164988 95654128 1785888768 0.0592909902 -0.0102093946 -0.0533064418 68 2.6800000000 0.0166437570 0.0100745855 0.0177764948 0.0052313386 2.6564420000 89166666 95654128 1787793408 0.0617887825 -0.0117565431 -0.0537625290 69 2.7200000000 0.0150441397 0.0101466080 0.0177764948 0.0052734264 2.5839840000 89168360 95654128 1784745984 0.0644418597 -0.0126556782 -0.0549059696 70 2.7600000000 0.0124180634 0.0101790574 0.0177764948 0.0053816894 0.8482660000 89168762 95654128 1786163200 0.0700012073 -0.0111421114 -0.0559345409 71 2.8000000000 0.0119703375 0.0102042867 0.0177764948 0.0054306772 0.8076990000 89170456 95654128 1787940864 0.0726871490 -0.0117003806 -0.0574585609 72 2.8400000000 0.0122250589 0.0102323529 0.0177764948 0.0054484335 0.8432530000 89172134 95654128 1784766464 0.0739498809 -0.0126324091 -0.0581388324 73 2.8800000000 0.0105800433 0.0102371158 0.0177764948 0.0055303338 0.9887940000 89172568 95654128 1786163200 0.0783845261 -0.0134444097 -0.0597537868 74 2.9200000000 0.0109651862 0.0102469546 0.0177764948 0.0056896720 0.8737540000 89174246 95654128 1788067840 0.0806993544 -0.0158414077 -0.0620164350 75 2.9600000000 0.0100864321 0.0102448143 0.0177764948 0.0057281887 0.8049110000 89175940 95654128 1784766464 0.0866723433 -0.0141524458 -0.0639713854 76 3.0000000000 0.0092723556 0.0102320188 0.0177764948 0.0057574772 1.1077790000 89176358 95654128 1786036224 0.0911039039 -0.0135074789 -0.0659303367 77 3.0400000000 0.0100397076 0.0102295213 0.0177764948 0.0058119648 2.0344030000 89178052 95654128 1787932672 0.0962620527 -0.0178630576 -0.0668043122 78 3.0800000000 0.0094181458 0.0102191190 0.0177764948 0.0057872786 2.1267040000 89179730 95654128 1784758272 0.0987780318 -0.0181162059 -0.0698811412 79 3.1200000000 0.0095237587 0.0102103170 0.0177764948 0.0058055179 2.0520640000 89182036 95654128 1786028032 0.1012193263 -0.0152584054 -0.0705506951 80 3.1600000000 0.0111554628 0.0102221313 0.0177764948 0.0057901709 1.5911710000 89352330 95654128 1788059648 0.1047246903 -0.0189996678 -0.0734875426 81 3.2000000000 0.0093652634 0.0102115527 0.0177764948 0.0057759787 2.4415640000 89353992 95654128 1784631296 0.1101412401 -0.0154383145 -0.0752517208 82 3.2400000000 0.0103749270 0.0102135450 0.0177764948 0.0057426802 2.2354600000 89354426 95654128 1786028032 0.1132247075 -0.0174134634 -0.0772676766 83 3.2800000000 0.0104546128 0.0102164495 0.0177764948 0.0057357966 1.8482720000 89356104 95654128 1787932672 0.1156931669 -0.0201980192 -0.0797771141 84 3.3200000000 0.0110310977 0.0102261477 0.0177764948 0.0057186828 1.2751220000 89357798 95654128 1784377344 0.1202763095 -0.0151320426 -0.0823486000 85 3.3600000000 0.0098426081 0.0102216354 0.0177764948 0.0056911766 1.8511990000 89358232 95654128 1785774080 0.1322394907 -0.0147669911 -0.0826918334 86 3.4000000000 0.0111238053 0.0102321258 0.0177764948 0.0057047731 1.3838350000 89359910 95654128 1787551744 0.1334480047 -0.0116949137 -0.0844617337 87 3.4400000000 0.0128157204 0.0102618223 0.0177764948 0.0057109650 1.5692860000 89361604 95654128 1784758272 0.1337478906 -0.0112653794 -0.0870248079 88 3.4800000000 0.0119317826 0.0102807991 0.0177764948 0.0056805035 1.8724170000 89362022 95654128 1786028032 0.1399913132 -0.0103779268 -0.0883075222 89 3.5200000000 0.0107929343 0.0102865534 0.0177764948 0.0056692115 2.7761140000 89363716 95654128 1787805696 0.1439913809 -0.0079691485 -0.0897673815 90 3.5600000000 0.0101809734 0.0102853803 0.0177764948 0.0056444701 1.9480840000 89365410 95654128 1784377344 0.1483124644 -0.0110199461 -0.0912842378 91 3.6000000000 0.0111411158 0.0102947840 0.0177764948 0.0056993855 1.9877980000 89365828 95654128 1786028032 0.1550499350 -0.0132506276 -0.0918164551 92 3.6400000000 0.0132755451 0.0103271836 0.0177764948 0.0057209785 1.9527130000 89367522 95654128 1787686912 0.1597785801 -0.0062432168 -0.0921932086 93 3.6800000000 0.0134855779 0.0103611448 0.0177764948 0.0057646367 2.0547850000 89369216 95654128 1784766464 0.1690309793 -0.0064126216 -0.0935312808 94 3.7200000000 0.0140470257 0.0104003563 0.0177764948 0.0057421012 1.7015250000 89369650 95654128 1786163200 0.1773828119 -0.0085181892 -0.0962028876 95 3.7600000000 0.0133874351 0.0104317992 0.0177764948 0.0057151093 1.8495480000 89371312 95654128 1788186624 0.1841128469 -0.0080684731 -0.0986061320 96 3.8000000000 0.0113062449 0.0104409081 0.0177764948 0.0057057850 1.8482060000 89373006 95654128 1784377344 0.1926289797 -0.0062615066 -0.1007088795 97 3.8400000000 0.0100640999 0.0104370234 0.0177764948 0.0056886547 1.9902640000 89373440 95654128 1785774080 0.2025457323 -0.0042157490 -0.1031288430 98 3.8800000000 0.0085393954 0.0104176599 0.0177764948 0.0056598067 1.8613050000 89375118 95654128 1787678720 0.2126625925 -0.0042630960 -0.1046927571 99 3.9200000000 0.0089306245 0.0104026393 0.0177764948 0.0056769734 1.8476710000 89377668 95654128 1784520704 0.2197790444 -0.0045338818 -0.1069347858 100 3.9600000000 0.0078395372 0.0103770083 0.0177764948 0.0056509711 1.2941570000 89546714 95654128 1786028032 0.2286201119 -0.0031141085 -0.1073188186 101 4.0000000000 0.0090048993 0.0103634231 0.0177764948 0.0056495809 1.5019880000 89548408 95654128 1788059648 0.2363379598 -0.0010983099 -0.1078858897 102 4.0400000000 0.0083989622 0.0103441636 0.0177764948 0.0056472215 2.0054680000 89550086 95654128 1784631296 0.2413722277 -0.0010541518 -0.1102490947 103 4.0800000000 0.0092037832 0.0103330920 0.0177764948 0.0056263031 2.2359950000 89550520 95654128 1785901056 0.2480619848 0.0052605094 -0.1099498197 104 4.1200000000 0.0105447518 0.0103351272 0.0177764948 0.0056059786 1.6243960000 89552214 95654128 1787805696 0.2571184039 0.0093572680 -0.1108096689 105 4.1600000000 0.0091307582 0.0103236570 0.0177764948 0.0055867623 0.8900050000 89553908 95654128 1784377344 0.2651669681 0.0098033240 -0.1111594290 106 4.2000000000 0.0103354109 0.0103237679 0.0177764948 0.0055996448 1.1283520000 89554342 95654128 1785901056 0.2712119818 0.0053855097 -0.1124295741 107 4.2400000000 0.0091680363 0.0103129667 0.0177764948 0.0055741322 2.0106660000 89556020 95654128 1787932672 0.2803981900 0.0036456017 -0.1139958873 108 4.2800000000 0.0085045667 0.0102962222 0.0177764948 0.0055511353 1.1950880000 89557714 95654128 1784631296 0.2914512753 0.0014687756 -0.1154752523 109 4.3200000000 0.0075830221 0.0102713305 0.0177764948 0.0055286418 1.8660630000 89558148 95654128 1786028032 0.3081657290 0.0027436549 -0.1187756062 110 4.3600000000 0.0069319098 0.0102409721 0.0177764948 0.0055229868 2.0296880000 89559842 95654128 1787932672 0.3210142255 0.0033237759 -0.1199790016 111 4.4000000000 0.0084157661 0.0102245288 0.0177764948 0.0055006839 2.1079800000 89561536 95654128 1785020416 0.3287264705 0.0049970029 -0.1210096851 112 4.4400000000 0.0085784486 0.0102098317 0.0177764948 0.0054877422 1.8317480000 89561970 95654128 1786179584 0.3340574503 0.0001005279 -0.1240300015 113 4.4800000000 0.0079950159 0.0101902315 0.0177764948 0.0054643518 1.6932180000 89563664 95654128 1787813888 0.3437467217 0.0004658385 -0.1247860193 114 4.5200000000 0.0075626173 0.0101671823 0.0177764948 0.0054528750 1.8263900000 89565342 95654128 1784385536 0.3555311561 -0.0018381912 -0.1256479919 115 4.5600000000 0.0076503581 0.0101452968 0.0177764948 0.0054430188 1.6012470000 89565776 95654128 1785901056 0.3659330606 -0.0059240982 -0.1275960505 116 4.6000000000 0.0090823891 0.0101361338 0.0177764948 0.0054207898 1.6415860000 89567470 95654128 1787805696 0.3731610775 -0.0101903621 -0.1285761297 117 4.6400000000 0.0077939434 0.0101161151 0.0177764948 0.0054330211 2.2317890000 89569164 95654128 1784377344 0.3812819421 -0.0119903758 -0.1305588186 118 4.6800000000 0.0088092163 0.0101050397 0.0177764948 0.0054319404 1.5850600000 89569598 95654128 1785901056 0.3887129426 -0.0106669944 -0.1301078498 119 4.7200000000 0.0089824032 0.0100956058 0.0177764948 0.0054638359 1.9978740000 89571292 95654128 1787805696 0.4021266103 -0.0092700263 -0.1283447146 120 4.7600000000 0.0120135499 0.0101115887 0.0177764948 0.0054457871 1.3034200000 89574950 95654128 1784504320 0.4107669592 -0.0094529064 -0.1262485087 121 4.8000000000 0.0100628091 0.0101111855 0.0177764948 0.0054276025 1.5121950000 89744000 95654128 1786028032 0.4229512513 -0.0124097280 -0.1282423139 122 4.8400000000 0.0104077561 0.0101136164 0.0177764948 0.0054297051 2.3249860000 89745694 95654128 1787932672 0.4318785667 -0.0126224346 -0.1290185899 123 4.8800000000 0.0111501878 0.0101220438 0.0177764948 0.0054093513 1.6885030000 89747388 95654128 1784631296 0.4428997636 -0.0110600749 -0.1270722896 124 4.9200000000 0.0111302631 0.0101301746 0.0177764948 0.0053907385 2.0120980000 89747822 95654128 1786028032 0.4491582215 -0.0095464792 -0.1239211634 125 4.9600000000 0.0093840435 0.0101242056 0.0177764948 0.0053844853 1.5012090000 89749516 95654128 1787932672 0.4524913430 -0.0064627333 -0.1221378297 126 5.0000000000 0.0084301010 0.0101107603 0.0177764948 0.0053693186 1.5882570000 89751210 95654128 1784631296 0.4621485174 -0.0056348648 -0.1210961342 127 5.0400000000 0.0100197028 0.0101100433 0.0177764948 0.0053507388 1.4582910000 89751644 95654128 1786028032 0.4714464843 -0.0069494983 -0.1181063354 128 5.0800000000 0.0099966004 0.0101091571 0.0177764948 0.0053502769 2.2464380000 89753354 95654128 1788059648 0.4849829972 -0.0076967371 -0.1151894033 129 5.1200000000 0.0098739211 0.0101073335 0.0177764948 0.0053431291 1.6329910000 89765288 95654128 1784758272 0.4962595999 -0.0064579658 -0.1118601635 130 5.1600000000 0.0092785629 0.0101009584 0.0177764948 0.0053241099 1.0545060000 89786714 95654128 1786028032 0.5027812719 -0.0048545646 -0.1096543670 131 5.2000000000 0.0089776153 0.0100923832 0.0177764948 0.0053466780 0.8895360000 89788408 95654128 1787932672 0.5100833178 -0.0060997242 -0.1069594920 132 5.2400000000 0.0092404773 0.0100859294 0.0177764948 0.0053337478 0.9460110000 89790102 95654128 1784639488 0.5212692618 -0.0064542969 -0.1036829650 133 5.2800000000 0.0097653400 0.0100835189 0.0177764948 0.0053141645 1.8525540000 89790536 95654128 1785909248 0.5325838327 -0.0065318430 -0.0994799733 134 5.3200000000 0.0074684345 0.0100640034 0.0177764948 0.0053456199 1.5795640000 89792230 95654128 1787940864 0.5425428748 -0.0049426202 -0.0971508548 135 5.3600000000 0.0089722052 0.0100559160 0.0177764948 0.0053664826 1.0201080000 89793940 95654128 1784512512 0.5508741736 -0.0045634639 -0.0926836208 136 5.4000000000 0.0095497519 0.0100521942 0.0177764948 0.0053864165 2.0353480000 89794374 95654128 1785901056 0.5642192960 0.0025257948 -0.0867431611 137 5.4400000000 0.0108865676 0.0100582845 0.0177764948 0.0053782210 1.4222430000 89796068 95654128 1787805696 0.5704077482 0.0045280196 -0.0829676986 138 5.4800000000 0.0076821554 0.0100410662 0.0177764948 0.0054263687 1.6433010000 89797762 95654128 1784504320 0.5732683539 0.0075612944 -0.0801516324 139 5.5200000000 0.0084278891 0.0100294606 0.0177764948 0.0054082960 1.9459180000 89798196 95654128 1786028032 0.5812504888 0.0078926673 -0.0751380026 140 5.5600000000 0.0100501366 0.0100296083 0.0177764948 0.0053917998 2.1257170000 89799890 95654128 1787822080 0.5898795128 0.0070490022 -0.0697287172 141 5.6000000000 0.0099594379 0.0100291106 0.0177764948 0.0053728407 2.0436160000 89801584 95654128 1784377344 0.5995416045 0.0073226010 -0.0654991120 142 5.6400000000 0.0098778848 0.0100280456 0.0177764948 0.0053567313 1.5699130000 89802018 95654128 1785901056 0.6110571623 0.0075644008 -0.0604991578 143 5.6800000000 0.0085775545 0.0100179024 0.0177764948 0.0053430223 1.5450380000 89803712 95654128 1787678720 0.6208094358 0.0107252365 -0.0555730537 144 5.7200000000 0.0094401482 0.0100138902 0.0177764948 0.0053617547 1.7998260000 89805422 95654128 1784885248 0.6270146370 0.0099640200 -0.0504738912 145 5.7600000000 0.0078032496 0.0099986444 0.0177764948 0.0053450381 2.0272300000 89805856 95654128 1786155008 0.6357873678 0.0116112512 -0.0464385487 146 5.8000000000 0.0108939642 0.0100047767 0.0177764948 0.0053299320 2.6348670000 89807550 95654128 1788059648 0.6443730593 0.0103630302 -0.0394621938 147 5.8400000000 0.0098151779 0.0100034869 0.0177764948 0.0053122821 2.1391210000 89809244 95654128 1784631296 0.6543721557 0.0152742555 -0.0336677581 148 5.8800000000 0.0107471580 0.0100085117 0.0177764948 0.0053269782 2.0382860000 89809678 95654128 1786028032 0.6595434546 0.0138703557 -0.0287130978 149 5.9200000000 0.0083251065 0.0099972137 0.0177764948 0.0053128314 1.9017830000 89811372 95654128 1787805696 0.6654418707 0.0155914705 -0.0249841884 150 5.9600000000 0.0073524658 0.0099795820 0.0177764948 0.0053156503 1.8725950000 89813066 95654128 1784504320 0.6734375954 0.0197281465 -0.0195858944 151 6.0000000000 0.0071820230 0.0099610552 0.0177764948 0.0053113103 1.0350670000 89813500 95654128 1786155008 0.6812595725 0.0221730247 -0.0144128334 152 6.0400000000 0.0094102984 0.0099574318 0.0177764948 0.0053091621 0.8215040000 89815226 95654128 1787813888 0.6919708252 0.0203884691 -0.0039405245 153 6.0800000000 0.0105509022 0.0099613107 0.0177764948 0.0053251403 0.8959460000 89816920 95654128 1784639488 0.6994536519 0.0204539951 0.0018890714 154 6.1200000000 0.0105051752 0.0099648422 0.0177764948 0.0053083287 0.7732980000 89817354 95654128 1786036224 0.7070714235 0.0213990659 0.0059649069 155 6.1600000000 0.0077125113 0.0099503111 0.0177764948 0.0053051140 0.8634260000 89820628 95654128 1787940864 0.7126624584 0.0237321556 0.0091002323 156 6.2000000000 0.0085572042 0.0099413809 0.0177764948 0.0053199764 0.8860390000 89990934 95654128 1784766464 0.7204916477 0.0248110685 0.0158097092 157 6.2400000000 0.0082271192 0.0099304620 0.0177764948 0.0053258105 0.9547520000 89991368 95654128 1786036224 0.7282186747 0.0259624496 0.0209815912 158 6.2800000000 0.0075954986 0.0099156838 0.0177764948 0.0053365864 0.7936720000 89993062 95654128 1788194816 0.7322269082 0.0279270336 0.0275566354 159 6.3200000000 0.0102234660 0.0099176195 0.0177764948 0.0053812123 0.8157320000 89994756 95654128 1784766464 0.7382247448 0.0274257287 0.0345247909 160 6.3600000000 0.0090488866 0.0099121899 0.0177764948 0.0054250077 0.8878900000 89995206 95654128 1786036224 0.7518919110 0.0322685353 0.0482577011 161 6.4000000000 0.0057566627 0.0098863792 0.0177764948 0.0054468145 0.8395950000 89996900 95654128 1787940864 0.7555714250 0.0383894444 0.0549567342 162 6.4400000000 0.0070137908 0.0098686472 0.0177764948 0.0054344780 0.8638230000 89998594 95654128 1784639488 0.7610322237 0.0391920581 0.0626836866 163 6.4800000000 0.0082572503 0.0098587613 0.0177764948 0.0054485976 0.9152900000 89999028 95654128 1785909248 0.7664001584 0.0393366851 0.0715595186 164 6.5200000000 0.0087793237 0.0098521794 0.0177764948 0.0054605195 0.8140170000 90000722 95654128 1787805696 0.7735078931 0.0388395041 0.0795164332 165 6.5600000000 0.0084447740 0.0098436497 0.0177764948 0.0054648549 0.7334640000 90002416 95654128 1784393728 0.7825090885 0.0416210592 0.0876204595 166 6.6000000000 0.0092687476 0.0098401864 0.0177764948 0.0054819916 0.9017580000 90002866 95654128 1785901056 0.7900592089 0.0449391790 0.0969950259 167 6.6400000000 0.0088561466 0.0098342939 0.0177764948 0.0055285217 0.9439230000 90004560 95654128 1787805696 0.7942628264 0.0472806804 0.1049695313 168 6.6800000000 0.0083777215 0.0098256239 0.0177764948 0.0055383995 0.8138410000 90006254 95654128 1784377344 0.8008270264 0.0505694188 0.1135713831 169 6.7200000000 0.0082785813 0.0098164698 0.0177764948 0.0055260349 0.9088250000 90006688 95654128 1785901056 0.8103154302 0.0548687913 0.1242191643 170 6.7600000000 0.0092960615 0.0098134085 0.0177764948 0.0055472080 0.8251580000 90008382 95654128 1787551744 0.8155192137 0.0557218790 0.1335355043 171 6.8000000000 0.0073412554 0.0097989515 0.0177764948 0.0055317425 0.7343600000 90010076 95654128 1784758272 0.8262057900 0.0599431917 0.1430130303 172 6.8400000000 0.0096320882 0.0097979814 0.0177764948 0.0055179420 0.9673710000 90010526 95654128 1786155008 0.8342241645 0.0600681342 0.1534807682 173 6.8800000000 0.0088526914 0.0097925173 0.0177764948 0.0055021509 1.6562330000 90012220 95654128 1787940864 0.8388046026 0.0605681129 0.1604150236 174 6.9200000000 0.0085740779 0.0097855147 0.0177764948 0.0054925284 2.5187590000 90013914 95654128 1784639488 0.8466501236 0.0633632690 0.1702483594 175 6.9600000000 0.0091268308 0.0097817508 0.0177764948 0.0054807938 0.9660890000 90015756 95654128 1786036224 0.8564347625 0.0664140657 0.1805193871 176 7.0000000000 0.0105878785 0.0097863311 0.0177764948 0.0054664402 0.8355920000 90186058 95654128 1787940864 0.8633176088 0.0674697384 0.1909236908 177 7.0400000000 0.0095938658 0.0097852437 0.0177764948 0.0055064302 0.8374610000 90187768 95654128 1784651776 0.8668851852 0.0688830465 0.1992241591 178 7.0800000000 0.0090850638 0.0097813101 0.0177764948 0.0055260103 0.7585430000 90188202 95654128 1786036224 0.8720650077 0.0691122785 0.2069934309 179 7.1200000000 0.0086812517 0.0097751646 0.0177764948 0.0055109021 0.6228390000 90189896 95654128 1787813888 0.8785853386 0.0716780424 0.2154532671 180 7.1600000000 0.0086555444 0.0097689444 0.0177764948 0.0054990965 0.7542360000 90191590 95654128 1784385536 0.8849985600 0.0730017424 0.2246043086 181 7.2000000000 0.0103003057 0.0097718801 0.0177764948 0.0054858246 0.6626580000 90192024 95654128 1785925632 0.8874532580 0.0725653172 0.2339127958 182 7.2400000000 0.0097104674 0.0097715427 0.0177764948 0.0054720481 0.9629090000 90193718 95654128 1787813888 0.8931254745 0.0752732903 0.2427933216 183 7.2800000000 0.0087985313 0.0097662257 0.0177764948 0.0054574721 1.6441260000 90195412 95654128 1784639488 0.8988140821 0.0782080442 0.2518179715 184 7.3200000000 0.0082013523 0.0097577210 0.0177764948 0.0054515449 1.6189950000 90195846 95654128 1786036224 0.9045993090 0.0795212910 0.2595470250 185 7.3600000000 0.0085921949 0.0097514208 0.0177764948 0.0054417468 1.9705830000 90197540 95654128 1787940864 0.9073022604 0.0794668719 0.2662590444 186 7.4000000000 0.0082801143 0.0097435106 0.0177764948 0.0054281033 1.5475180000 90199234 95654128 1784901632 0.9132793546 0.0807486698 0.2748516500 187 7.4400000000 0.0084046917 0.0097363511 0.0177764948 0.0054230649 1.2908360000 90199700 95654128 1786171392 0.9194971323 0.0811205432 0.2822037339 188 7.4800000000 0.0093453182 0.0097342711 0.0177764948 0.0054123775 1.7932310000 90201394 95654128 1787949056 0.9216423035 0.0819783136 0.2892510593 189 7.5200000000 0.0089459782 0.0097301003 0.0177764948 0.0053980765 1.6301940000 90203088 95654128 1784520704 0.9257687926 0.0817671642 0.2955903113 190 7.5600000000 0.0076765860 0.0097192923 0.0177764948 0.0053903285 1.2712860000 90203522 95654128 1785909248 0.9319826961 0.0833350718 0.3030545115 191 7.6000000000 0.0091576772 0.0097163519 0.0177764948 0.0053806885 1.6706870000 90205216 95654128 1787813888 0.9350230098 0.0839006007 0.3115157485 192 7.6400000000 0.0101707354 0.0097187185 0.0177764948 0.0053673687 1.6736070000 90206910 95654128 1784512512 0.9388636947 0.0840262547 0.3198809028 193 7.6800000000 0.0090153376 0.0097150740 0.0177764948 0.0053576270 1.5978800000 90207344 95654128 1786036224 0.9433132410 0.0872582942 0.3346455991 194 7.7200000000 0.0103348289 0.0097182687 0.0177764948 0.0053442367 2.3584710000 90209038 95654128 1787940864 0.9446578026 0.0896115527 0.3441797495 195 7.7600000000 0.0111358119 0.0097255381 0.0177764948 0.0053329738 1.9678970000 90210732 95654128 1784655872 0.9502750039 0.0894892141 0.3617884219 196 7.8000000000 0.0114722317 0.0097344498 0.0177764948 0.0053270611 2.2634220000 90212702 95654128 1786036224 0.9502050281 0.0885342434 0.3714497089 197 7.8400000000 0.0103136552 0.0097373899 0.0177764948 0.0053145294 2.0407940000 90383012 95654128 1787813888 0.9535117149 0.0903245658 0.3815817535 198 7.8800000000 0.0115710190 0.0097466507 0.0177764948 0.0053020645 1.3353880000 90384722 95654128 1784385536 0.9558399916 0.0894216672 0.3923935890 199 7.9200000000 0.0114706783 0.0097553141 0.0177764948 0.0052971070 1.6684750000 90385156 95654128 1785909248 0.9557476640 0.0887593031 0.4024899602 200 7.9600000000 0.0109832613 0.0097614539 0.0177764948 0.0052878413 1.6781930000 90386850 95654128 1787686912 0.9578154683 0.0901869014 0.4134221673 201 8.0000000000 0.0111040734 0.0097681336 0.0177764948 0.0052758737 1.9103770000 90388544 95654128 1784766464 0.9595109820 0.0901604295 0.4247947931 202 8.0400000000 0.0109914867 0.0097741898 0.0177764948 0.0052628716 2.0630980000 90388978 95654128 1786163200 0.9606114626 0.0900897011 0.4351454377 203 8.0800000000 0.0098778456 0.0097747004 0.0177764948 0.0052506754 2.3791910000 90390672 95654128 1787940864 0.9610161185 0.0912940875 0.4454056323 204 8.1200000000 0.0096604479 0.0097741403 0.0177764948 0.0052424318 2.0590610000 90392366 95654128 1784385536 0.9610402584 0.0929735228 0.4560176432 205 8.1600000000 0.0105293524 0.0097778243 0.0177764948 0.0052506454 1.4415980000 90392800 95654128 1786044416 0.9617269635 0.0940543413 0.4679844379 206 8.1999999990 0.0098960716 0.0097783983 0.0177764948 0.0052548797 1.0658670000 90394494 95654128 1787695104 0.9624549747 0.0967716053 0.4798456728 207 8.2400000000 0.0111045940 0.0097848051 0.0177764948 0.0052477924 1.2834980000 90396188 95654128 1784774656 0.9625449181 0.0982164592 0.4930519164 208 8.2799999990 0.0106088333 0.0097887667 0.0177764948 0.0052508778 1.7598020000 90396622 95654128 1786171392 0.9630581141 0.1014622971 0.5045782328 209 8.3200000000 0.0110080699 0.0097946007 0.0177764948 0.0052429490 1.5619340000 90398316 95654128 1788203008 0.9633273482 0.1025353745 0.5162862539 210 8.3599999990 0.0103599383 0.0097972928 0.0177764948 0.0052311820 2.4370990000 90400010 95654128 1784283136 0.9644685388 0.1045222357 0.5279053450 211 8.4000000000 0.0103538046 0.0097999303 0.0177764948 0.0052284492 1.7244780000 90400444 95654128 1785782272 0.9653925896 0.1065339446 0.5402008295 212 8.4399999990 0.0107648419 0.0098044818 0.0177764948 0.0052197561 1.6321070000 90402154 95654128 1787813888 0.9641388655 0.1079106778 0.5525420904 213 8.4800000000 0.0108612971 0.0098094433 0.0177764948 0.0052128460 1.7146790000 90403848 95654128 1784512512 0.9638718367 0.1095791683 0.5639864206 214 8.5200000000 0.0095551414 0.0098082550 0.0177764948 0.0052111215 1.7505470000 90404282 95654128 1785909248 0.9633470178 0.1130470708 0.5750095844 215 8.5600000000 0.0094068795 0.0098063882 0.0177764948 0.0052004399 1.9681890000 90405976 95654128 1787940864 0.9632431865 0.1164389625 0.5871062279 216 8.6000000000 0.0088987909 0.0098021863 0.0177764948 0.0051922334 1.7596640000 90407670 95654128 1784639488 0.9634448290 0.1192924529 0.5993857384 217 8.6400000000 0.0098807197 0.0098025482 0.0177764948 0.0051861585 2.2847950000 90408104 95654128 1785909248 0.9624606967 0.1199195310 0.6106899977 218 8.6800000000 0.0088312030 0.0097980925 0.0177764948 0.0051780151 1.1661810000 90409798 95654128 1787813888 0.9611692429 0.1223694161 0.6210622191 219 8.7200000000 0.0088354796 0.0097936970 0.0177764948 0.0051715891 1.2316500000 90411492 95654128 1784512512 0.9588191509 0.1233301088 0.6313554645 220 8.7600000000 0.0080532515 0.0097857859 0.0177764948 0.0051615950 1.4734920000 90411926 95654128 1785909248 0.9550055861 0.1245101020 0.6408720016 221 8.8000000000 0.0096076587 0.0097849799 0.0177764948 0.0051509141 1.0437840000 90413636 95654128 1787686912 0.9539747238 0.1255979240 0.6530828476 222 8.8400000000 0.0085564889 0.0097794462 0.0177764948 0.0051418091 1.3009050000 90415330 95654128 1784512512 0.9533345103 0.1271358579 0.6637974381 223 8.8800000000 0.0082362853 0.0097725261 0.0177764948 0.0051305762 2.4179260000 90415764 95654128 1785909248 0.9507346749 0.1273764819 0.6732136011 224 8.9200000000 0.0074119824 0.0097619880 0.0177764948 0.0051207901 1.1956790000 90417458 95654128 1787940864 0.9494531751 0.1286978871 0.6833841205 225 8.9600000000 0.0084554376 0.0097561811 0.0177764948 0.0051109244 1.7417490000 90419152 95654128 1784258560 0.9478150606 0.1296730489 0.6948004365 226 9.0000000000 0.0085312948 0.0097507613 0.0177764948 0.0051012588 1.4924860000 90419602 95654128 1785782272 0.9477778077 0.1322325170 0.7158138156 227 9.0400000000 0.0088998079 0.0097470126 0.0177764948 0.0050910145 1.7985460000 90421296 95654128 1787822080 0.9486095309 0.1338093579 0.7274068594 228 9.0800000000 0.0086018126 0.0097419898 0.0177764948 0.0050814019 1.7339820000 90422990 95654128 1784266752 0.9459804893 0.1358635128 0.7368964553 229 9.1200000000 0.0078110895 0.0097335579 0.0177764948 0.0050921916 1.8760130000 90423424 95654128 1785790464 0.9460294843 0.1385685652 0.7477225661 230 9.1600000000 0.0073688668 0.0097232766 0.0177764948 0.0050884391 1.8756790000 90425150 95654128 1787568128 0.9468567371 0.1404426098 0.7582249641 231 9.2000000000 0.0074426821 0.0097134039 0.0177764948 0.0050822151 1.9176790000 90426844 95654128 1784766464 0.9463601708 0.1414069235 0.7757989764 232 9.2400000000 0.0080655785 0.0097063012 0.0177764948 0.0050765760 1.5845480000 90427278 95654128 1786163200 0.9462918043 0.1436454356 0.7883558869 233 9.2800000000 0.0082625961 0.0097001051 0.0177764948 0.0050762831 1.6104640000 90428972 95654128 1787940864 0.9466028810 0.1463195086 0.8007003069 234 9.3200000000 0.0087561579 0.0096960711 0.0177764948 0.0050761779 1.4064340000 90430682 95654128 1784766464 0.9459146857 0.1483650208 0.8119282126 235 9.3600000000 0.0070396378 0.0096847671 0.0177764948 0.0050721853 1.3289760000 90434368 95654128 1786163200 0.9466015697 0.1511278003 0.8224951625 236 9.4000000000 0.0070297397 0.0096735170 0.0177764948 0.0050650437 1.3786780000 90604678 95654128 1788067840 0.9486805201 0.1515485048 0.8320245147 237 9.4400000000 0.0074612694 0.0096641826 0.0177764948 0.0050749194 1.7310650000 90606372 95654128 1784639488 0.9490569830 0.1537608802 0.8427933455 238 9.4800000000 0.0075903586 0.0096554691 0.0177764948 0.0050750411 1.6513640000 90606806 95654128 1786036224 0.9487869740 0.1558007598 0.8533170223 239 9.5200000000 0.0073312805 0.0096457444 0.0177764948 0.0050773130 2.1414120000 90608500 95654128 1787940864 0.9516922832 0.1576767564 0.8639865518 240 9.5600000000 0.0074589020 0.0096366326 0.0177764948 0.0050750825 0.9734460000 90610194 95654128 1784393728 0.9514252543 0.1584355384 0.8737338185 241 9.6000000000 0.0073352456 0.0096270833 0.0177764948 0.0050645356 0.8040500000 90610644 95654128 1785917440 0.9507855177 0.1596617401 0.8834452033 242 9.6400000000 0.0079505984 0.0096201557 0.0177764948 0.0050632242 0.8553810000 90612338 95654128 1787949056 0.9506640434 0.1619655490 0.8954918981 243 9.6800000000 0.0076085664 0.0096118775 0.0177764948 0.0050539065 0.7467290000 90614032 95654128 1784901632 0.9536462426 0.1647266448 0.9086512327 244 9.7200000000 0.0078058285 0.0096044757 0.0177764948 0.0050435685 0.7481570000 90614466 95654128 1786187776 0.9550849199 0.1682001352 0.9206867218 245 9.7600000000 0.0073748608 0.0095953752 0.0177764948 0.0050346920 0.9499990000 90616160 95654128 1788203008 0.9552631378 0.1694370210 0.9309963584 246 9.8000000000 0.0078071388 0.0095881060 0.0177764948 0.0050248958 0.7260210000 90617854 95654128 1784520704 0.9558998346 0.1722066253 0.9423054457 247 9.8400000000 0.0068892064 0.0095771792 0.0177764948 0.0050156090 1.0661800000 90618288 95654128 1785917440 0.9566686749 0.1755501926 0.9535888433 248 9.8800000000 0.0073045688 0.0095680155 0.0177764948 0.0050099709 1.6424950000 90619982 95654128 1787949056 0.9569202065 0.1780998707 0.9640530944 249 9.9200000000 0.0075154947 0.0095597724 0.0177764948 0.0050002584 1.7992490000 90621676 95654128 1784782848 0.9580225945 0.1791400015 0.9747871161 250 9.9600000000 0.0066602947 0.0095481745 0.0177764948 0.0049905953 1.2246800000 90622126 95654128 1786179584 0.9587146640 0.1818656176 0.9852920175 251 10.0000000000 0.0063477973 0.0095354240 0.0177764948 0.0049816517 1.9364520000 90623820 95654128 1787957248 0.9592136145 0.1826393455 0.9952310324 252 10.0400000000 0.0068239858 0.0095246643 0.0177764948 0.0049718928 2.1714650000 90625514 95654128 1784655872 0.9590506554 0.1841107011 1.0049427748 253 10.0800000000 0.0062630442 0.0095117726 0.0177764948 0.0049626844 2.0587860000 90625948 95654128 1785925632 0.9593724012 0.1863961220 1.0140585899 254 10.1200000000 0.0060999831 0.0094983403 0.0177764948 0.0049568218 0.9812850000 90627642 95654128 1787695104 0.9604147077 0.1882467866 1.0233696699 255 10.1600000000 0.0068501183 0.0094879551 0.0177764948 0.0049482563 2.0181240000 90629336 95654128 1784520704 0.9593083262 0.1894018054 1.0328103304 256 10.2000000000 0.0061742268 0.0094750109 0.0177764948 0.0049460535 2.0603610000 90629770 95654128 1785917440 0.9580727220 0.1910958737 1.0406181812 257 10.2400000000 0.0070772972 0.0094656812 0.0177764948 0.0049606581 1.4110400000 90651944 95654128 1787695104 0.9572046995 0.1917530298 1.0493375063 258 10.2800000000 0.0077184155 0.0094589089 0.0177764948 0.0049644983 1.8102760000 90695622 95654128 1784393728 0.9562243819 0.1934594959 1.0588268042 259 10.3200000000 0.0075337603 0.0094514759 0.0177764948 0.0049658922 1.8720340000 90696056 95654128 1785917440 0.9558572769 0.1945802122 1.0669794083 260 10.3600000000 0.0086560072 0.0094484164 0.0177764948 0.0049776148 1.2138480000 90697782 95654128 1787695104 0.9529929161 0.1950507909 1.0748486519 261 10.4000000000 0.0087854713 0.0094458764 0.0177764948 0.0049687953 1.9999580000 90699476 95654128 1784520704 0.9523546696 0.1963504255 1.0841786861 262 10.4400000000 0.0088457651 0.0094435859 0.0177764948 0.0049592911 1.8740850000 90699910 95654128 1786044416 0.9526472092 0.1979830861 1.0932334661 263 10.4800000000 0.0079960367 0.0094380819 0.0177764948 0.0049505665 1.4475690000 90701604 95654128 1787822080 0.9530391097 0.2000790536 1.1027441025 264 10.5200000000 0.0078623481 0.0094321132 0.0177764948 0.0049453978 1.6369460000 90703298 95654128 1784520704 0.9504979253 0.2011890560 1.1106749773 265 10.5600000000 0.0081328098 0.0094272102 0.0177764948 0.0049382727 2.1056910000 90703732 95654128 1786044416 0.9482786059 0.2018801123 1.1184835434 266 10.6000000000 0.0077008000 0.0094207199 0.0177764948 0.0049289830 1.6425630000 90708446 95654128 1787822080 0.9497048259 0.2029240876 1.1267855167 267 10.6400000000 0.0083017489 0.0094165290 0.0177764948 0.0049227356 2.0494850000 90878772 95654128 1784520704 0.9483814240 0.2038404197 1.1352287531 268 10.6800000000 0.0076937336 0.0094101007 0.0177764948 0.0049166821 2.0445420000 90879206 95654128 1786044416 0.9475113153 0.2065143883 1.1446826458 269 10.7200000000 0.0085054385 0.0094067376 0.0177764948 0.0049162175 2.2781950000 90880916 95654128 1788084224 0.9461365938 0.2060538381 1.1538299322 270 10.7600000000 0.0084630651 0.0094032425 0.0177764948 0.0049082239 1.5064080000 90882610 95654128 1784147968 0.9433474541 0.2090063691 1.1629861593 271 10.8000000000 0.0080943564 0.0093984127 0.0177764948 0.0049025324 1.7072610000 90883044 95654128 1785544704 0.9412950873 0.2113366425 1.1728763580 272 10.8400000000 0.0083978595 0.0093947342 0.0177764948 0.0048935393 1.4736280000 90884738 95654128 1787449344 0.9383973479 0.2129027843 1.1821867228 273 10.8800000000 0.0077130897 0.0093885743 0.0177764948 0.0048853156 1.7291090000 90886432 95654128 1784655872 0.9346426129 0.2141498625 1.1910029650 274 10.9200000000 0.0078376923 0.0093829142 0.0177764948 0.0048780605 2.1675860000 90886866 95654128 1785925632 0.9335099459 0.2157968283 1.2013825178 275 10.9600000000 0.0081061609 0.0093782714 0.0177764948 0.0048714084 1.9233660000 90888560 95654128 1787949056 0.9304801822 0.2194460779 1.2111032009 276 11.0000000000 0.0077898810 0.0093725164 0.0177764948 0.0048628830 2.8223350000 90890254 95654128 1784537088 0.9269160032 0.2189701945 1.2186897993 277 11.0400000000 0.0073388657 0.0093651747 0.0177764948 0.0048616066 2.1643910000 90890688 95654128 1785917440 0.9270152450 0.2213689387 1.2293781042 278 11.0800000000 0.0073132911 0.0093577938 0.0177764948 0.0048529573 1.8245860000 90892382 95654128 1787822080 0.9220013618 0.2224621922 1.2384392023 279 11.1200000000 0.0074097747 0.0093508117 0.0177764948 0.0048450371 1.5979390000 90894076 95654128 1784647680 0.9175043702 0.2222590446 1.2478843927 280 11.1600000000 0.0079190917 0.0093456984 0.0177764948 0.0048372232 0.9279880000 90894510 95654128 1785925632 0.9143494368 0.2245841175 1.2583528757 281 11.2000000000 0.0073744375 0.0093386832 0.0177764948 0.0048296048 0.7563990000 90896204 95654128 1787957248 0.9122896791 0.2290470153 1.2679204941 282 11.2400000000 0.0070486707 0.0093305626 0.0177764948 0.0048221908 0.8243110000 90897898 95654128 1784303616 0.9100003839 0.2296625227 1.2765927315 283 11.2800000000 0.0071203681 0.0093227527 0.0177764948 0.0048148571 1.3617290000 90898332 95654128 1785671680 0.9063451886 0.2330553979 1.2858808041 284 11.3200000000 0.0078074513 0.0093174172 0.0177764948 0.0048065074 1.1863690000 90900026 95654128 1787576320 0.9003916383 0.2356148362 1.2968553305 285 11.3600000000 0.0073759509 0.0093106050 0.0177764948 0.0047993573 2.2317180000 90901720 95654128 1784274944 0.8957513571 0.2367448956 1.3061752319 286 11.4000000000 0.0078199124 0.0093053928 0.0177764948 0.0048019642 1.3725840000 90902170 95654128 1785798656 0.8976086974 0.2390976846 1.3164453506 287 11.4400000000 0.0071357498 0.0092978330 0.0177764948 0.0047958879 1.3303650000 90903864 95654128 1787576320 0.8948958516 0.2435390502 1.3255139589 288 11.4800000000 0.0065658865 0.0092883471 0.0177764948 0.0047882070 1.4496730000 90905558 95654128 1784655872 0.8880956769 0.2450469732 1.3325515985 289 11.5200000000 0.0067958003 0.0092797224 0.0177764948 0.0047829533 2.4289860000 90905992 95654128 1786052608 0.8833152056 0.2427660227 1.3398011923 290 11.5600000000 0.0081657702 0.0092758812 0.0177764948 0.0047769304 2.2395500000 90907686 95654128 1787965440 0.8781470656 0.2437308133 1.3485368490 291 11.6000000000 0.0068515763 0.0092675502 0.0177764948 0.0047691268 1.3137850000 90909380 95654128 1784410112 0.8772153258 0.2466359288 1.3565030098 292 11.6400000000 0.0069058929 0.0092594624 0.0177764948 0.0047619055 1.3450650000 90909814 95654128 1785806848 0.8743730187 0.2469633222 1.3643103838 293 11.6800000000 0.0071714320 0.0092523360 0.0177764948 0.0047538313 1.4503000000 90911508 95654128 1787584512 0.8725532293 0.2488763630 1.3709021807 294 11.7200000000 0.0075510908 0.0092465494 0.0177764948 0.0047518436 1.6798300000 90913202 95654128 1784283136 0.8679011464 0.2481330186 1.3778730631 295 11.7600000000 0.0087517938 0.0092448723 0.0177764948 0.0047549846 1.7019830000 90916196 95654128 1785806848 0.8661882281 0.2475875467 1.3855004311 296 11.8000000000 0.0086214943 0.0092427663 0.0177764948 0.0047703231 1.5893030000 91086530 95654128 1787584512 0.8639502525 0.2480190098 1.3934614658 297 11.8400000000 0.0090333726 0.0092420613 0.0177764948 0.0048041538 1.4139240000 91088240 95654128 1784528896 0.8588702083 0.2480253726 1.4008331299 298 11.8800000000 0.0091236923 0.0092416640 0.0177764948 0.0048121151 1.4755830000 91088674 95654128 1785925632 0.8563222885 0.2472717166 1.4094941616 299 11.9200000000 0.0091149537 0.0092412403 0.0177764948 0.0048064848 1.9026400000 91090368 95654128 1787830272 0.8547003269 0.2467941791 1.4176901579 300 11.9600000000 0.0095069176 0.0092421259 0.0177764948 0.0048093012 1.8405080000 91092062 95654128 1784401920 0.8524561524 0.2460893840 1.4252924919 301 12.0000000000 0.0103242099 0.0092457208 0.0177764948 0.0048063123 1.6941510000 91092496 95654128 1785798656 0.8513749838 0.2458694279 1.4346100092 302 12.0400000000 0.0093210591 0.0092459703 0.0177764948 0.0048001380 2.5528710000 91094288 95654128 1787719680 0.8509510756 0.2473124713 1.4433883429 303 12.0800000000 0.0092362352 0.0092459382 0.0177764948 0.0047935773 1.7830800000 91095998 95654128 1784528896 0.8492237329 0.2465234846 1.4512741566 304 12.1200000000 0.0098793041 0.0092480216 0.0177764948 0.0047876638 1.5986190000 91096432 95654128 1785925632 0.8467496634 0.2477365136 1.4605803490 305 12.1600000000 0.0086775413 0.0092461512 0.0177764948 0.0047805575 1.6069060000 91098266 95654128 1787830272 0.8469572663 0.2492188066 1.4700344801 306 12.2000000000 0.0081033679 0.0092424166 0.0177764948 0.0047731323 1.7293390000 91098700 95654128 1784401920 0.8439613581 0.2514195144 1.4789937735 307 12.2400000000 0.0090850797 0.0092419041 0.0177764948 0.0047670744 2.2152860000 91100394 95654128 1785798656 0.8414871693 0.2522951663 1.4885354042 308 12.2800000000 0.0086426931 0.0092399586 0.0177764948 0.0047661350 1.9669110000 91102120 95654128 1787703296 0.8403675556 0.2538304627 1.4982340336 309 12.3200000000 0.0086854259 0.0092381640 0.0177764948 0.0047657293 1.9316330000 91102554 95654128 1784418304 0.8388140202 0.2546212673 1.5074083805 310 12.3600000000 0.0078831762 0.0092337931 0.0177764948 0.0047663670 2.4693800000 91104248 95654128 1785679872 0.8384951949 0.2576160133 1.5170763731 311 12.4000000000 0.0080754980 0.0092300686 0.0177764948 0.0047870254 1.6362660000 91105942 95654128 1787457536 0.8371382952 0.2596718073 1.5272117853 312 12.4400000000 0.0081745731 0.0092266856 0.0177764948 0.0048046943 1.2098660000 91106392 95654128 1784537088 0.8357614875 0.2589710057 1.5352174044 313 12.4800000000 0.0086547323 0.0092248583 0.0177764948 0.0048038298 1.7737240000 91108086 95654128 1785933824 0.8349311948 0.2589650154 1.5444967747 314 12.5200000000 0.0076893964 0.0092199683 0.0177764948 0.0048033942 1.9029760000 91109780 95654128 1787830272 0.8333547115 0.2618196309 1.5539256334 315 12.5600000000 0.0094402013 0.0092206675 0.0177764948 0.0048041399 1.3359680000 91110214 95654128 1784274944 0.8314092159 0.2607482374 1.5620841980 316 12.6000000000 0.0100296456 0.0092232275 0.0177764948 0.0047967061 1.5351340000 91111924 95654128 1785798656 0.8312743902 0.2607317269 1.5701599121 317 12.6400000000 0.0101175010 0.0092260486 0.0177764948 0.0047896353 1.9896410000 91113618 95654128 1787576320 0.8306617141 0.2617590427 1.5790127516 318 12.6800000000 0.0092382738 0.0092260870 0.0177764948 0.0047872162 1.5031960000 91114052 95654128 1784401920 0.8314245343 0.2633888423 1.5878993273 319 12.7200000000 0.0085524255 0.0092239752 0.0177764948 0.0047821667 1.7956500000 91115746 95654128 1785925632 0.8288621902 0.2674976289 1.5980160236 320 12.7600000000 0.0085461056 0.0092218569 0.0177764948 0.0047839176 1.6938210000 91117440 95654128 1787703296 0.8266091943 0.2685050964 1.6072313786 321 12.8000000000 0.0084842425 0.0092195590 0.0177764948 0.0047958537 1.2214500000 91117874 95654128 1784528896 0.8249751329 0.2703152597 1.6164461374 322 12.8400000000 0.0084979236 0.0092173179 0.0177764948 0.0048006292 1.0914610000 91119568 95654128 1785925632 0.8235983253 0.2729976177 1.6252198219 323 12.8800000000 0.0082793860 0.0092144141 0.0177764948 0.0048120211 1.4345960000 91121262 95654128 1787703296 0.8225820661 0.2746497691 1.6336075068 324 12.9200000000 0.0092637129 0.0092145663 0.0177764948 0.0048321778 1.6124680000 91121696 95654128 1784401920 0.8203919530 0.2746794522 1.6407183409 325 12.9600000000 0.0094104381 0.0092151689 0.0177764948 0.0048431249 1.7423190000 91123390 95654128 1785925632 0.8204315305 0.2742793858 1.6479678154 326 13.0000000000 0.0096204085 0.0092164120 0.0177764948 0.0048490714 1.7251900000 91125084 95654128 1787830272 0.8193756938 0.2745733261 1.6560437679 327 13.0400000000 0.0087111462 0.0092148669 0.0177764948 0.0049448670 1.6889120000 91127870 95654128 1784401920 0.8159444928 0.2810924649 1.6737878323 328 13.0800000000 0.0095161712 0.0092157855 0.0177764948 0.0049745123 2.0264320000 91298188 95654128 1785798656 0.8133787513 0.2809996605 1.6831163168 329 13.1200000000 0.0088431975 0.0092146530 0.0177764948 0.0049779956 1.8575500000 91299882 95654128 1787830272 0.8115152717 0.2828714252 1.6911799908 330 13.1600000000 0.0089602368 0.0092138820 0.0177764948 0.0049789413 1.7331670000 91300316 95654128 1784410112 0.8102144003 0.2829317749 1.6985152960 331 13.2000000000 0.0094126193 0.0092144824 0.0177764948 0.0049821758 2.2239480000 91302010 95654128 1785806848 0.8088634610 0.2830601037 1.7052490711 332 13.2400000000 0.0091247540 0.0092142122 0.0177764948 0.0049764628 1.5349320000 91303704 95654128 1787711488 0.8079763055 0.2847645879 1.7127714157 333 13.2800000000 0.0092906393 0.0092144417 0.0177764948 0.0049727898 1.7637360000 91304138 95654128 1784410112 0.8068042994 0.2862791717 1.7202059031 334 13.3200000000 0.0097274343 0.0092159776 0.0177764948 0.0049743342 1.7269220000 91305832 95654128 1785798656 0.8059514165 0.2859049737 1.7265350819 335 13.3600000000 0.0091580134 0.0092158046 0.0177764948 0.0049807090 1.6819660000 91307526 95654128 1787703296 0.8040648699 0.2896572351 1.7349498272 336 13.4000000000 0.0094303405 0.0092164431 0.0177764948 0.0049929671 1.5346290000 91307960 95654128 1784401920 0.8015301228 0.2903302312 1.7413994074 337 13.4400000000 0.0100004468 0.0092187695 0.0177764948 0.0050122110 2.0020970000 91309654 95654128 1785798656 0.7994636297 0.2893005908 1.7467588186 338 13.4800000000 0.0101265963 0.0092214554 0.0177764948 0.0050366219 2.0220410000 91311348 95654128 1787449344 0.7959806919 0.2890277207 1.7522147894 339 13.5200000000 0.0101517383 0.0092241996 0.0177764948 0.0050490055 1.0925970000 91314418 95654128 1784655872 0.7940379977 0.2906588018 1.7594306469 340 13.5600000000 0.0105217369 0.0092280158 0.0177764948 0.0050762838 2.0170680000 91484748 95654128 1785925632 0.7891638279 0.2908102274 1.7654417753 341 13.6000000000 0.0111829480 0.0092337488 0.0177764948 0.0050869932 1.9798760000 91486442 95654128 1787957248 0.7849903703 0.2912361622 1.7724407911 342 13.6400000000 0.0117372507 0.0092410690 0.0177764948 0.0051122240 1.7085750000 91486876 95654128 1784401920 0.7801675200 0.2955079973 1.7804762125 343 13.6800000000 0.0124041392 0.0092502907 0.0177764948 0.0051289942 1.4009080000 91488570 95654128 1785798656 0.7751433253 0.2990748286 1.7890030146 344 13.7200000000 0.0125144385 0.0092597795 0.0177764948 0.0051356486 1.4945220000 91490264 95654128 1787703296 0.7709822059 0.3015573919 1.7951889038 345 13.7600000000 0.0131361568 0.0092710154 0.0177764948 0.0051384226 0.8155210000 91490698 95654128 1784274944 0.7690131068 0.2989852726 1.7999646664 346 13.8000000000 0.0133189755 0.0092827147 0.0177764948 0.0051391560 0.7703240000 91492392 95654128 1785798656 0.7660793066 0.3001234233 1.8040537834 347 13.8400000000 0.0136505766 0.0092953022 0.0177764948 0.0051485972 0.8097370000 91494086 95654128 1787703296 0.7620686889 0.2985328734 1.8097938299 348 13.8800000000 0.0139542529 0.0093086900 0.0177764948 0.0051595745 1.0437420000 91494520 95654128 1784401920 0.7571971416 0.2987997532 1.8161934614 349 13.9200000000 0.0130733447 0.0093194770 0.0177764948 0.0051545016 0.7719090000 91496214 95654128 1785925632 0.7519855499 0.2989951372 1.8234106302 350 13.9600000000 0.0127566503 0.0093292975 0.0177764948 0.0051798572 0.8267710000 91500484 95654128 1787703296 0.7459058166 0.3031963706 1.8309327364 351 14.0000000000 0.0124186007 0.0093380989 0.0177764948 0.0051762687 0.7697870000 91669566 95654128 1784401920 0.7409372926 0.3035394847 1.8375152349 352 14.0400000000 0.0123759964 0.0093467293 0.0177764948 0.0051740761 0.7841620000 91671260 95654128 1785798656 0.7357541919 0.3016378582 1.8413813114 353 14.0800000000 0.0115823289 0.0093530624 0.0177764948 0.0051675946 0.8886990000 91672954 95654128 1787830272 0.7325374484 0.2998121381 1.8464143276 354 14.1200000000 0.0105798217 0.0093565279 0.0177764948 0.0051690787 0.8444430000 91673388 95654128 1784401920 0.7270140648 0.3041573763 1.8543877602 355 14.1600000000 0.0118904319 0.0093636656 0.0177764948 0.0051719693 0.8925110000 91675082 95654128 1785798656 0.7201839685 0.3031960428 1.8599623442 356 14.2000000000 0.0129418075 0.0093737166 0.0177764948 0.0051758072 0.7499660000 91676776 95654128 1787703296 0.7131807804 0.3023708165 1.8643276691 357 14.2400000000 0.0119700227 0.0093809892 0.0177764948 0.0051746531 0.7667210000 91677210 95654128 1784410112 0.7061802745 0.3050892055 1.8705123663 358 14.2800000000 0.0113321971 0.0093864395 0.0177764948 0.0051684045 0.7275880000 91678904 95654128 1785806848 0.7016245723 0.3045985103 1.8761605024 359 14.3200000000 0.0122870933 0.0093945193 0.0177764948 0.0051668471 0.7895070000 91680598 95654128 1787711488 0.6912447214 0.3096888661 1.8832921982 360 14.3600000000 0.0122126872 0.0094023475 0.0177764948 0.0051786309 0.7088450000 91681032 95654128 1784283136 0.6751766801 0.3147925436 1.8947749138 361 14.4000000000 0.0129986182 0.0094123095 0.0177764948 0.0051735913 0.7882720000 91685034 95654128 1785679872 0.6644011736 0.3199830949 1.9036957026 362 14.4400000000 0.0115146032 0.0094181169 0.0177764948 0.0051763722 1.0283210000 91855376 95654128 1787711488 0.6488915086 0.3195750415 1.9107978344 363 14.4800000000 0.0112950820 0.0094232876 0.0177764948 0.0051722285 0.7899360000 91855810 95654128 1784283136 0.6435976028 0.3161552250 1.9149277210 364 14.5200000000 0.0102663394 0.0094256037 0.0177764948 0.0051685693 0.8521570000 91857504 95654128 1785679872 0.6370775104 0.3164203763 1.9217772484 365 14.5600000000 0.0099161984 0.0094269478 0.0177764948 0.0051625168 0.7470570000 91859198 95654128 1787695104 0.6291837096 0.3164239526 1.9273320436 366 14.6000000000 0.0128829647 0.0094363905 0.0177764948 0.0051811097 0.8075870000 91859632 95654128 1784172544 0.6092877388 0.3250383735 1.9395767450 367 14.6400000000 0.0130009502 0.0094461032 0.0177764948 0.0051745439 0.8474220000 91861326 95654128 1785663488 0.5993933082 0.3289389610 1.9446774721 368 14.6800000000 0.0122981919 0.0094538534 0.0177764948 0.0051693415 0.6860620000 91863020 95654128 1787568128 0.5910730362 0.3288352191 1.9490541220 369 14.7200000000 0.0111880777 0.0094585532 0.0177764948 0.0051755243 1.0244100000 91863454 95654128 1784647680 0.5834689140 0.3280240893 1.9512556791 370 14.7600000000 0.0105858399 0.0094615999 0.0177764948 0.0051735957 1.8202960000 91865148 95654128 1786044416 0.5762209296 0.3248663545 1.9532507658 371 14.8000000000 0.0108624930 0.0094653759 0.0177764948 0.0051696792 1.4401180000 91869326 95654128 1787949056 0.5665622950 0.3271022439 1.9600826502 372 14.8400000000 0.0104454365 0.0094680105 0.0177764948 0.0051646057 1.4907690000 92038396 95654128 1784647680 0.5582515597 0.3286216855 1.9658310413 373 14.8800000000 0.0101727024 0.0094698997 0.0177764948 0.0051659627 1.5082300000 92040090 95654128 1786044416 0.5485388637 0.3307771087 1.9708647728 374 14.9200000000 0.0090934765 0.0094688933 0.0177764948 0.0051614108 1.6055650000 92041784 95654128 1788076032 0.5383657813 0.3319078386 1.9738976955 375 14.9600000000 0.0080274325 0.0094650494 0.0177764948 0.0051556202 1.1371990000 92042218 95654128 1784647680 0.5294338465 0.3297044635 1.9749037027 376 15.0000000000 0.0076732170 0.0094602839 0.0177764948 0.0051497983 2.0090580000 92043912 95654128 1786044416 0.5204360485 0.3297612965 1.9800571203 377 15.0400000000 0.0048942482 0.0094481724 0.0177764948 0.0051752915 1.5982980000 92045606 95654128 1788076032 0.5026670098 0.3306428194 1.9874247313 378 15.0800000000 0.0046348982 0.0094354388 0.0177764948 0.0051822645 0.7162180000 92046040 95654128 1784647680 0.4953432977 0.3297993839 1.9911518097 379 15.1200000000 0.0036159451 0.0094200840 0.0177764948 0.0051809964 0.7795250000 92047734 95654128 1785917440 0.4881496131 0.3303680718 1.9941964149 380 15.1600000000 0.0034313384 0.0094043241 0.0177764948 0.0051791884 1.1489930000 92049428 95654128 1787949056 0.4807364941 0.3291277885 1.9973691702 381 15.2000000000 0.0030214270 0.0093875711 0.0177764948 0.0051877152 0.9155350000 92049862 95654128 1784393728 0.4729448855 0.3306491673 2.0030994415 382 15.2400000000 0.0023970283 0.0093692712 0.0177764948 0.0051859265 0.7089820000 92051556 95654128 1785790464 0.4641974866 0.3304459453 2.0042791367 383 15.2800000000 0.0027566557 0.0093520059 0.0177764948 0.0051877990 0.6629630000 92053250 95654128 1787695104 0.4559825063 0.3298730850 2.0068657398 384 15.3200000000 0.0028483586 0.0093350693 0.0177764948 0.0051964673 0.6623330000 92053684 95654128 1784520704 0.4475992918 0.3309272230 2.0120649338 385 15.3600000000 0.0027010005 0.0093178380 0.0177764948 0.0051965531 0.6649490000 92055378 95654128 1785917440 0.4399723113 0.3311917484 2.0146136284 386 15.4000000000 0.0025699856 0.0093003565 0.0177764948 0.0051932843 0.6476900000 92057072 95654128 1787822080 0.4329274595 0.3315622509 2.0175931454 387 15.4400000000 0.0026529934 0.0092831799 0.0177764948 0.0051956168 0.9766390000 92057506 95654128 1784393728 0.4265808165 0.3322950304 2.0211613178 388 15.4800000000 0.0025456604 0.0092658151 0.0177764948 0.0051991958 1.8135550000 92061844 95654128 1785790464 0.4200064540 0.3331053853 2.0246517658 389 15.5200000000 0.0021903198 0.0092476262 0.0177764948 0.0052068561 1.5707280000 92232138 95654128 1787822080 0.4119003117 0.3347848356 2.0284979343 390 15.5600000000 0.0028017408 0.0092310983 0.0177764948 0.0052079274 1.8206860000 92232572 95654128 1784655872 0.4043322802 0.3346818984 2.0312001705 391 15.6000000000 0.0031991021 0.0092156712 0.0177764948 0.0052036856 1.7193330000 92234266 95654128 1785925632 0.3980360329 0.3349100053 2.0344452858 392 15.6400000000 0.0019555336 0.0091971504 0.0177764948 0.0052259778 1.0309510000 92235960 95654128 1787830272 0.3909854293 0.3368411660 2.0398745537 393 15.6800000000 0.0030343947 0.0091814691 0.0177764948 0.0052198976 1.6510060000 92236394 95654128 1784291328 0.3847419322 0.3357559443 2.0422668457 394 15.7200000000 0.0030102101 0.0091658060 0.0177764948 0.0052169275 1.2454140000 92238088 95654128 1785798656 0.3779850006 0.3359317482 2.0454330444 395 15.7600000000 0.0021605054 0.0091480711 0.0177764948 0.0052339746 1.7862840000 92239782 95654128 1787449344 0.3716383874 0.3381192684 2.0522987843 396 15.8000000000 0.0027622650 0.0091319453 0.0177764948 0.0052570971 1.1374870000 92240216 95654128 1784528896 0.3647375405 0.3418067098 2.0579903126 397 15.8400000000 0.0031153921 0.0091167903 0.0177764948 0.0052524603 2.2990150000 92241910 95654128 1785917440 0.3589965403 0.3393363059 2.0592398643 398 15.8800000000 0.0035113308 0.0091027062 0.0177764948 0.0052694978 1.7032430000 92243604 95654128 1787822080 0.3543988764 0.3414124548 2.0679917336 399 15.9200000000 0.0045510945 0.0090912986 0.0177764948 0.0052706585 1.9826090000 92244038 95654128 1784393728 0.3473421335 0.3433363438 2.0713574886 400 15.9600000000 0.0048624035 0.0090807264 0.0177764948 0.0052647525 1.2487290000 92245732 95654128 1785917440 0.3427133858 0.3406125903 2.0742394924 401 16.0000000000 0.0218924657 0.0091126759 0.0218924657 0.0063148981 5.4754510000 95527650 95654128 1784848384 0.3341978192 0.3213011324 2.0674815178 402 16.0400000000 0.0139913112 0.0091248118 0.0218924657 0.0065630550 1.9218920000 92459512 95654128 1785991168 0.3206988871 0.3296612203 2.0787551403 403 16.0800000000 0.0167252626 0.0091436715 0.0218924657 0.0066358047 1.0326000000 92461206 95654128 1787006976 0.3197444081 0.3253813684 2.0856041908 404 16.1200000000 0.0150822252 0.0091583709 0.0218924657 0.0066609414 1.8642000000 92462900 95654128 1785602048 0.3099805415 0.3272685707 2.0899980068 405 16.1600000000 0.0163470544 0.0091761207 0.0218924657 0.0066634396 1.5089160000 92463334 95654128 1787125760 0.3068035245 0.3246096671 2.0944943428 406 16.2000000000 0.0142209623 0.0091885464 0.0218924657 0.0067445929 1.4523700000 92468220 95654128 1785475072 0.2977174819 0.3289990425 2.1022264957 407 16.2400000000 0.0145326648 0.0092016769 0.0218924657 0.0068311124 1.8776970000 92638578 95654128 1786736640 0.2865475416 0.3332881629 2.1066305637 408 16.2800000000 0.0141807497 0.0092138805 0.0218924657 0.0068729785 2.0507610000 92639012 95654128 1787879424 0.2883000076 0.3313472271 2.1118662357 409 16.3200000000 0.0140699511 0.0092257536 0.0218924657 0.0070041222 1.9334710000 92640706 95654128 1784586240 0.2746770978 0.3353039622 2.1178343296 410 16.3600000000 0.0150061613 0.0092398521 0.0218924657 0.0070204181 1.5310810000 92642400 95654128 1785602048 0.2750975490 0.3332333863 2.1206476688 411 16.3999999990 0.0140637159 0.0092515890 0.0218924657 0.0071179885 0.9319410000 92642834 95654128 1786744832 0.2622795105 0.3368415833 2.1252183914 412 16.4400000000 0.0163035374 0.0092687054 0.0218924657 0.0071312251 2.1446810000 92644528 95654128 1785348096 0.2610090375 0.3340786695 2.1272988319 413 16.4800000000 0.0131393364 0.0092780774 0.0218924657 0.0072411706 1.9497550000 92646222 95654128 1786609664 0.2509592175 0.3395425677 2.1374692917 414 16.5200000000 0.0120842485 0.0092848556 0.0218924657 0.0072746912 0.8841970000 92646656 95654128 1787752448 0.2436411828 0.3430421948 2.1437153816 415 16.5599999990 0.0116531728 0.0092905624 0.0218924657 0.0073052803 0.7054540000 92648350 95654128 1784844288 0.2369968146 0.3464331031 2.1505875587 416 16.6000000000 0.0124243330 0.0092980955 0.0218924657 0.0073247578 0.7725770000 92650044 95654128 1785974784 0.2301283330 0.3487308323 2.1541593075 417 16.6400000000 0.0129630566 0.0093068843 0.0218924657 0.0073267940 0.7700210000 92650478 95654128 1786990592 0.2250768840 0.3495230079 2.1571073532 418 16.6800000000 0.0097224852 0.0093078786 0.0218924657 0.0073251020 0.9035360000 92652172 95654128 1785356288 0.2237142026 0.3506544232 2.1657547951 419 16.7199999990 0.0127328159 0.0093160527 0.0218924657 0.0073281236 0.7691650000 92653866 95654128 1786863616 0.2223595977 0.3526963592 2.1701476574 420 16.7600000000 0.0150769493 0.0093297691 0.0218924657 0.0074019588 0.6698160000 92654300 95654128 1788133376 0.2140207142 0.3560789824 2.1724617481 421 16.8000000000 0.0184945706 0.0093515382 0.0218924657 0.0074667050 0.8320180000 92655994 95654128 1784229888 0.2065613717 0.3583799601 2.1738526821 422 16.8400000000 0.0212953892 0.0093798412 0.0218924657 0.0074807189 0.6819040000 92657688 95654128 1785212928 0.1998959184 0.3569679856 2.1758852005 423 16.8799999990 0.0237788036 0.0094138813 0.0237788036 0.0074803148 0.7740450000 92658122 95654128 1786609664 0.1966578662 0.3507052660 2.1798169613 424 16.9200000000 0.0346057191 0.0094732960 0.0346057191 0.0075024658 0.8628810000 92659816 95654128 1785384960 0.2054611742 0.3462608159 2.1880357265 425 16.9600000000 0.0430805571 0.0095523719 0.0430805571 0.0075690803 0.7313300000 92661510 95654128 1786482688 0.2117113024 0.3409052789 2.1940600872 426 17.0000000000 0.0556999408 0.0096606995 0.0556999408 0.0076099990 0.6888120000 92661944 95654128 1787498496 0.2190416008 0.3364308476 2.1993076801 427 17.0400000000 0.0662527755 0.0097932337 0.0662527755 0.0076287802 0.6216560000 92663638 95654128 1784610816 0.2224027067 0.3307309747 2.2041521072 428 17.0800000000 0.0725887716 0.0099399522 0.0725887716 0.0076220358 0.9825860000 92665332 95654128 1785593856 0.2231244445 0.3285634816 2.2093186378 429 17.1200000000 0.0787499100 0.0101003484 0.0787499100 0.0076167250 1.4812360000 92665766 95654128 1786736640 0.2242842317 0.3265949190 2.2118115425 430 17.1600000000 0.0810616016 0.0102653746 0.0810616016 0.0076244824 0.8116780000 92667460 95654128 1785466880 0.2225283831 0.3274474144 2.2150881290 431 17.2000000000 0.0834535658 0.0104351847 0.0834535658 0.0076351060 0.6128290000 92669154 95654128 1786736640 0.2201434672 0.3263239563 2.2180624008 432 17.2400000000 0.0890835375 0.0106172411 0.0890835375 0.0076279530 0.7877530000 92669588 95654128 1787879424 0.2202253640 0.3242136240 2.2233393192 433 17.2800000000 0.0925546065 0.0108064729 0.0925546065 0.0076203889 0.7850080000 92671422 95654128 1784451072 0.2190683186 0.3225982487 2.2283835411 434 17.3200000000 0.0963514149 0.0110035811 0.0963514149 0.0076163776 0.6526760000 92673116 95654128 1785593856 0.2170381397 0.3209926486 2.2338523865 435 17.3600000000 0.0953907222 0.0111975745 0.0963514149 0.0076399704 0.6874190000 92673550 95654128 1786736640 0.2112919241 0.3204003274 2.2360017300 436 17.4000000000 0.0939083844 0.0113872782 0.0963514149 0.0076675170 0.7710130000 92675244 95654128 1785466880 0.2056405544 0.3218725920 2.2390053272 437 17.4400000000 0.0915869698 0.0115708015 0.0963514149 0.0076976285 0.8694330000 92676938 95654128 1786736640 0.1980193555 0.3250735700 2.2434496880 438 17.4800000000 0.0909553543 0.0117520448 0.0963514149 0.0077120596 0.8025440000 92677372 95654128 1787879424 0.1923944652 0.3238115311 2.2461392879 439 17.5200000000 0.0901815668 0.0119306997 0.0963514149 0.0077147978 0.6670330000 92679066 95654128 1784451072 0.1862524152 0.3229405880 2.2488827705 440 17.5600000000 0.0881107971 0.0121038363 0.0963514149 0.0077333395 0.7322760000 92679640 95654128 1785593856 0.1791365147 0.3234451711 2.2507991791 441 17.6000000000 0.0850719362 0.0122692969 0.0963514149 0.0077639727 0.7890320000 92681334 95654128 1786736640 0.1711699516 0.3251508772 2.2528967857 442 17.6400000000 0.0829738304 0.0124292619 0.0963514149 0.0077803359 0.7856220000 92683028 95654128 1785466880 0.1645084620 0.3251203597 2.2543940544 443 17.6800000000 0.0799374878 0.0125816506 0.0963514149 0.0078035288 1.1501330000 92683462 95654128 1786499072 0.1564291269 0.3278454840 2.2572944164 444 17.7200000000 0.0786314830 0.0127304115 0.0963514149 0.0078114514 0.8260100000 92685156 95654128 1787752448 0.1498133093 0.3277021945 2.2598567009 445 17.7600000000 0.0756515190 0.0128718073 0.0963514149 0.0078292871 1.4564140000 92686850 95654128 1784958976 0.1424355060 0.3290568888 2.2617931366 446 17.8000000000 0.0725004822 0.0130055039 0.0963514149 0.0078557823 1.6161840000 92687284 95654128 1786109952 0.1342345029 0.3297664821 2.2635736465 447 17.8400000000 0.0707319453 0.0131346458 0.0963514149 0.0078696962 2.1524080000 92688978 95654128 1787252736 0.1271628886 0.3304235935 2.2670462132 448 17.8800000000 0.0713571683 0.0132646068 0.0963514149 0.0078678590 1.6345670000 92690672 95654128 1785094144 0.1214727536 0.3303195238 2.2699751854 449 17.9200000000 0.0719956234 0.0133954108 0.0963514149 0.0078680369 1.7907460000 92691106 95654128 1786609664 0.1168593764 0.3292418718 2.2717196941 450 17.9600000000 0.0718138143 0.0135252295 0.0963514149 0.0078734859 1.6346350000 92692800 95654128 1788006400 0.1117463261 0.3282376230 2.2741079330 451 18.0000000000 0.0785606280 0.0136694321 0.0963514149 0.0078791700 1.4996680000 92694494 95654128 1784070144 0.1037660614 0.3224123418 2.2788131237 452 18.0400000000 0.0783410147 0.0138125109 0.0963514149 0.0078776223 1.6760730000 92694928 95654128 1785085952 0.0981623456 0.3228694201 2.2815561295 453 18.0800000000 0.0798405558 0.0139582681 0.0963514149 0.0078712275 1.4600560000 92696622 95654128 1786228736 0.0933280364 0.3208091557 2.2842504978 454 18.1200000000 0.0818127766 0.0141077274 0.0963514149 0.0078632728 1.6746870000 92698316 95654128 1788006400 0.0877981558 0.3200162649 2.2878386974 455 18.1600000000 0.0826396197 0.0142583470 0.0963514149 0.0078568884 1.7983830000 92698750 95654128 1784578048 0.0821010843 0.3204316795 2.2914106846 456 18.2000000000 0.0835284144 0.0144102550 0.0963514149 0.0078497035 2.0029000000 92700444 95654128 1785593856 0.0773249716 0.3186207414 2.2925162315 457 18.2400000000 0.0853738561 0.0145655364 0.0963514149 0.0078463535 2.1360800000 92702138 95654128 1786736640 0.0718609393 0.3170272112 2.2958843708 458 18.2800000000 0.0879581347 0.0147257822 0.0963514149 0.0078491208 1.4097010000 92702712 95654128 1785466880 0.0665988475 0.3152505457 2.2976992130 459 18.3200000000 0.0897168145 0.0148891614 0.0963514149 0.0078473550 1.1203910000 92704406 95654128 1786990592 0.0617327206 0.3132335246 2.2991068363 460 18.3600000000 0.0910290182 0.0150546828 0.0963514149 0.0078399352 1.5941110000 92706100 95654128 1786101760 0.0569832399 0.3114859462 2.3003406525 461 18.4000000000 0.0923311114 0.0152223107 0.0963514149 0.0078315425 1.7458020000 92706534 95654128 1787498496 0.0508597493 0.3092825115 2.3026952744 462 18.4400000000 0.0946175009 0.0153941617 0.0963514149 0.0078258413 1.4584240000 92708228 95654128 1785720832 0.0452120490 0.3065225780 2.3055539131 463 18.4800000000 0.0962347537 0.0155687634 0.0963514149 0.0078288932 1.8899960000 92709922 95654128 1787252736 0.0407777727 0.3053008616 2.3078863621 464 18.5200000000 0.0988248810 0.0157481947 0.0988248810 0.0078240832 2.0241900000 92710496 95654128 1785602048 0.0356964394 0.3015648127 2.3093273640 465 18.5600000000 0.1013223231 0.0159322251 0.1013223231 0.0078190866 2.3750620000 92712190 95654128 1787125760 0.0303129219 0.2977509797 2.3112463951 466 18.6000000000 0.1036350429 0.0161204286 0.1036350429 0.0078118606 1.9933060000 92716704 95654128 1785847808 0.0254504588 0.2942968905 2.3129060268 467 18.6400000000 0.1055301651 0.0163118841 0.1055301651 0.0078045413 1.8449720000 92885782 95654128 1787371520 0.0206983536 0.2931259274 2.3149945736 468 18.6800000000 0.1076173931 0.0165069814 0.1076173931 0.0077987602 1.8205960000 92887476 95654128 1785974784 0.0164047293 0.2895550430 2.3155112267 469 18.7200000000 0.1094941795 0.0167052483 0.1094941795 0.0077918868 2.3907680000 92889170 95654128 1787371520 0.0108211320 0.2874714732 2.3183135986 470 18.7600000000 0.1111770794 0.0169062522 0.1111770794 0.0077891010 1.5610700000 92889744 95654128 1785593856 0.0059451736 0.2849147022 2.3203954697 471 18.8000000000 0.1078599989 0.0170993599 0.1111770794 0.0078420490 1.6221390000 92891438 95654128 1787117568 -0.0071150423 0.2878200710 2.3240303993 472 18.8400000000 0.1085042879 0.0172930144 0.1111770794 0.0078343889 1.9732770000 92891872 95654128 1785974784 -0.0117834639 0.2856514752 2.3248136044 473 18.8800000000 0.1070063412 0.0174826832 0.1111770794 0.0078393377 1.6477160000 92893566 95654128 1787498496 -0.0147614423 0.2847446203 2.3247263432 474 18.9200000000 0.1050615832 0.0176674488 0.1111770794 0.0078426676 1.6808620000 92895260 95654128 1785593856 -0.0178334862 0.2852604091 2.3253636360 475 18.9600000000 0.1060600057 0.0178535384 0.1111770794 0.0078371023 2.4286060000 92895694 95654128 1786990592 -0.0215120316 0.2823701203 2.3265960217 476 19.0000000000 0.1049237624 0.0180364591 0.1111770794 0.0078545834 0.7219130000 92897388 95654128 1785741312 -0.0267547145 0.2816189528 2.3273401260 477 19.0400000000 0.1069114581 0.0182227798 0.1111770794 0.0078469816 0.8033680000 92899222 95654128 1787117568 -0.0283576585 0.2765939534 2.3278453350 478 19.0800000000 0.1054289639 0.0184052195 0.1111770794 0.0078766485 0.7351480000 92899656 95654128 1786101760 -0.0347247273 0.2767949998 2.3322753906 479 19.1200000000 0.1046417356 0.0185852540 0.1111770794 0.0078768466 0.6179510000 92901350 95654128 1787498496 -0.0361059345 0.2767287195 2.3319118023 480 19.1600000000 0.1026537940 0.0187603968 0.1111770794 0.0078826766 0.6887600000 92903044 95654128 1785593856 -0.0374452099 0.2778647840 2.3322286606 481 19.2000000000 0.1021645814 0.0189337943 0.1111770794 0.0078838612 0.6713700000 92903478 95654128 1786990592 -0.0394546539 0.2772624493 2.3335325718 482 19.2400000000 0.1006945521 0.0191034224 0.1111770794 0.0078983774 0.8823360000 92905172 95654128 1785847808 -0.0409833789 0.2789325416 2.3347353935 483 19.2800000000 0.0992389768 0.0192693345 0.1111770794 0.0079108257 1.9526000000 92906866 95654128 1787506688 -0.0426137075 0.2793226540 2.3358819485 484 19.3200000000 0.0994563103 0.0194350101 0.1111770794 0.0079081776 1.7564090000 92907300 95654128 1785856000 -0.0422088951 0.2782678902 2.3368248940 485 19.3600000000 0.0980446488 0.0195970918 0.1111770794 0.0079288147 1.5937440000 92908994 95654128 1787252736 -0.0423883349 0.2801590860 2.3378398418 486 19.4000000000 0.0973557159 0.0197570890 0.1111770794 0.0079422414 0.8960230000 92910688 95654128 1785729024 -0.0436844416 0.2812440693 2.3413925171 487 19.4400000000 0.0953770652 0.0199123661 0.1111770794 0.0079770289 0.8269590000 92911122 95654128 1787252736 -0.0441159382 0.2836142480 2.3431706429 488 19.4800000000 0.0945614651 0.0200653356 0.1111770794 0.0080043236 0.8247280000 92912816 95654128 1785729024 -0.0446837470 0.2833115757 2.3451879025 489 19.5200000000 0.0970500931 0.0202227687 0.1111770794 0.0080095832 0.7593710000 92914510 95654128 1787125760 -0.0454663001 0.2812515795 2.3479936123 490 19.5600000000 0.0968553200 0.0203791616 0.1111770794 0.0080062133 0.7827510000 92915084 95654128 1785602048 -0.0448451824 0.2814936042 2.3498165607 491 19.6000000000 0.0989650488 0.0205392143 0.1111770794 0.0080029820 0.8650620000 92916778 95654128 1786617856 -0.0440282598 0.2787036300 2.3519678116 492 19.6400000000 0.1009470299 0.0207026449 0.1111770794 0.0079975051 1.1233510000 92918472 95654128 1787752448 -0.0426566377 0.2760491967 2.3537626266 493 19.6800000000 0.0994414464 0.0208623585 0.1111770794 0.0080066119 1.9678240000 92918906 95654128 1784705024 -0.0416387878 0.2786516845 2.3552660942 494 19.7200000000 0.0994103178 0.0210213624 0.1111770794 0.0080273842 0.8612810000 92920600 95654128 1785610240 -0.0422695391 0.2792702019 2.3609819412 495 19.7600000000 0.1015749350 0.0211840969 0.1111770794 0.0080295935 0.9237480000 92922294 95654128 1786863616 -0.0420794226 0.2763808072 2.3648967743 496 19.8000000000 0.1037371829 0.0213505346 0.1111770794 0.0080265326 0.8348340000 92922868 95654128 1785593856 -0.0414630212 0.2743939459 2.3683302402 497 19.8400000000 0.1038177758 0.0215164646 0.1111770794 0.0080233431 0.6689280000 92924562 95654128 1786990592 -0.0407376401 0.2748573124 2.3710520267 498 19.8800000000 0.1044679731 0.0216830339 0.1111770794 0.0080242304 0.6719250000 92924996 95654128 1788133376 -0.0396344922 0.2746404111 2.3733124733 499 19.9200000000 0.1068323553 0.0218536739 0.1111770794 0.0080201605 0.7161230000 92926690 95654128 1784213504 -0.0386087149 0.2716202140 2.3756144047 500 19.9600000000 0.1085148752 0.0220269963 0.1111770794 0.0080147173 0.8888950000 92928384 95654128 1785212928 -0.0378383547 0.2701975703 2.3790953159 501 20.0000000000 0.1101691499 0.0222029287 0.1111770794 0.0080107245 0.7759930000 92928818 95654128 1786482688 -0.0365816876 0.2687603533 2.3825571537 502 20.0400000000 0.1125026271 0.0223828086 0.1125026271 0.0080049169 0.8257950000 92930652 95654128 1785384960 -0.0353955887 0.2666463256 2.3853852749 503 20.0800000000 0.1145937368 0.0225661305 0.1145937368 0.0080000759 0.7126110000 92932346 95654128 1786482688 -0.0355486795 0.2652908564 2.3898141384 504 20.1200000000 0.1164663285 0.0227524404 0.1164663285 0.0079941472 0.8233840000 92932780 95654128 1787625472 -0.0352151915 0.2632146478 2.3923318386 505 20.1600000000 0.1173416600 0.0229397458 0.1173416600 0.0079936902 0.9475020000 92934474 95654128 1784578048 -0.0356961191 0.2626909912 2.3952357769 506 20.2000000000 0.1175608113 0.0231267440 0.1175608113 0.0079952575 0.8895800000 92936168 95654128 1785720832 -0.0360575989 0.2615861893 2.3994174004 507 20.2400000000 0.1173761860 0.0233126403 0.1175608113 0.0079956506 0.7655390000 92936602 95654128 1786863616 -0.0367775708 0.2613300085 2.4016070366 508 20.2800000000 0.1182316989 0.0234994888 0.1182316989 0.0079970275 0.6470680000 92938436 95654128 1785495552 -0.0381581821 0.2601189315 2.4045729637 509 20.3200000000 0.1195029765 0.0236881008 0.1195029765 0.0079913367 0.7071290000 92940130 95654128 1786863616 -0.0375170745 0.2583547533 2.4054241180 510 20.3600000000 0.1200265214 0.0238769997 0.1200265214 0.0079863481 0.8903460000 92940564 95654128 1787879424 -0.0374158546 0.2576696575 2.4061622620 511 20.4000000000 0.1212167814 0.0240674885 0.1212167814 0.0079911037 0.6991620000 92942258 95654128 1784324096 -0.0376200937 0.2567292750 2.4067807198 512 20.4400000000 0.1218983978 0.0242585645 0.1218983978 0.0079862703 0.8119370000 92943952 95654128 1785339904 -0.0395263582 0.2563002110 2.4095680714 513 20.4800000000 0.1215888411 0.0244482921 0.1218983978 0.0079839353 0.8720120000 92985346 95654128 1786482688 -0.0395793580 0.2569587827 2.4099085331 514 20.5200000000 0.1213571727 0.0246368308 0.1218983978 0.0079801117 0.7514210000 93071148 95654128 1788133376 -0.0411332548 0.2576632202 2.4124958515 515 20.5600000000 0.1207016110 0.0248233643 0.1218983978 0.0079795067 0.8965610000 93071582 95654128 1784451072 -0.0425559692 0.2580462098 2.4135985374 516 20.6000000000 0.1194442362 0.0250067381 0.1218983978 0.0079868060 0.8814140000 93073276 95654128 1785466880 -0.0446863100 0.2591264546 2.4151637554 517 20.6400000000 0.1189429089 0.0251884328 0.1218983978 0.0079842959 0.9942110000 93074970 95654128 1786609664 -0.0458005071 0.2594356239 2.4139184952 518 20.6800000000 0.1186725125 0.0253689040 0.1218983978 0.0079842447 1.0055110000 93075404 95654128 1785466880 -0.0470804609 0.2594236434 2.4152081013 519 20.7200000000 0.1182726026 0.0255479092 0.1218983978 0.0079828757 0.7311910000 93077098 95654128 1786609664 -0.0503645539 0.2597290874 2.4168484211 520 20.7600000000 0.1167709231 0.0257233381 0.1218983978 0.0079858918 0.7439600000 93078932 95654128 1787752448 -0.0529632866 0.2595140934 2.4174759388 521 20.8000000000 0.1150209755 0.0258947347 0.1218983978 0.0079938199 0.6472140000 93079366 95654128 1784713216 -0.0558921918 0.2608016431 2.4182057381 522 20.8400000000 0.1139096543 0.0260633457 0.1218983978 0.0080040200 0.8309620000 93081060 95654128 1785729024 -0.0590413287 0.2610334158 2.4190297127 523 20.8800000000 0.1120324358 0.0262277225 0.1218983978 0.0080083361 0.7492960000 93082754 95654128 1786871808 -0.0612795055 0.2627067864 2.4175376892 524 20.9200000000 0.1101720482 0.0263879216 0.1218983978 0.0080164419 0.8656490000 93083188 95654128 1785348096 -0.0633156598 0.2635916173 2.4171922207 525 20.9600000000 0.1078820005 0.0265431484 0.1218983978 0.0080225654 0.6934330000 93084882 95654128 1786744832 -0.0679755285 0.2633050084 2.4190993309 526 21.0000000000 0.1081423089 0.0266982799 0.1218983978 0.0080213720 0.6539790000 93086716 95654128 1787887616 -0.0699734092 0.2644707859 2.4168188572 527 21.0400000000 0.1074315906 0.0268514741 0.1218983978 0.0080216439 0.6616680000 93087150 95654128 1784205312 -0.0734256506 0.2650204003 2.4157772064 528 21.0800000000 0.1063215882 0.0270019856 0.1218983978 0.0080216542 0.9016400000 93088844 95654128 1785348096 -0.0784425288 0.2640837729 2.4171059132 529 21.1200000000 0.1053461730 0.0271500843 0.1218983978 0.0080266621 0.9932590000 93090538 95654128 1786617856 -0.0830622464 0.2645331323 2.4168200493 530 21.1600000000 0.1046425626 0.0272962965 0.1218983978 0.0080259156 0.7959610000 93090972 95654128 1785393152 -0.0863083154 0.2660809457 2.4144821167 531 21.2000000000 0.1035652235 0.0274399291 0.1218983978 0.0080239310 0.7497250000 93092666 95654128 1786499072 -0.0901316628 0.2666714191 2.4130163193 532 21.2400000000 0.1032707244 0.0275824682 0.1218983978 0.0080192391 0.7705910000 93093240 95654128 1787506688 -0.0948572308 0.2666375935 2.4121477604 533 21.2800000000 0.1027300134 0.0277234580 0.1218983978 0.0080170645 0.8897440000 93094934 95654128 1784586240 -0.0985483825 0.2673037648 2.4107322693 534 21.3200000000 0.1021274552 0.0278627913 0.1218983978 0.0080142241 0.7266310000 93096628 95654128 1785602048 -0.1028774604 0.2657149136 2.4100165367 535 21.3600000000 0.1020745412 0.0280015049 0.1218983978 0.0080107584 0.8200610000 93097062 95654128 1786744832 -0.1079540700 0.2647487521 2.4097874165 536 21.4000000000 0.1023628935 0.0281402388 0.1218983978 0.0080166431 0.7678350000 93098756 95654128 1785475072 -0.1119864061 0.2643897831 2.4084863663 537 21.4400000000 0.1034496948 0.0282804799 0.1218983978 0.0080150071 0.9086060000 93100450 95654128 1786744832 -0.1159021482 0.2640801966 2.4056150913 538 21.4800000000 0.1046789363 0.0284224845 0.1218983978 0.0080138709 0.7728310000 93101024 95654128 1787887616 -0.1201663837 0.2637097836 2.4033260345 539 21.5200000000 0.1051001623 0.0285647436 0.1218983978 0.0080107187 0.8390120000 93102718 95654128 1784459264 -0.1240448505 0.2627714276 2.4019622803 540 21.5600000000 0.1053536758 0.0287069453 0.1218983978 0.0080078981 0.7310340000 93104412 95654128 1785602048 -0.1288256496 0.2627353966 2.4005355835 541 21.6000000000 0.1062018275 0.0288501891 0.1218983978 0.0080068236 0.8569000000 93104846 95654128 1786617856 -0.1331106722 0.2612248361 2.3992865086 542 21.6400000000 0.1062341705 0.0289929640 0.1218983978 0.0080342346 0.9411860000 93106540 95654128 1785729024 -0.1368163377 0.2594625056 2.3991775513 543 21.6800000000 0.1066752151 0.0291360252 0.1218983978 0.0080595748 0.9293050000 93108234 95654128 1786998784 -0.1409751326 0.2572695017 2.3972730637 544 21.7200000000 0.1073849276 0.0292798651 0.1218983978 0.0081909641 0.8108460000 93108808 95654128 1788014592 -0.1477515399 0.2546634078 2.3891191483 545 21.7600000000 0.1091725528 0.0294264572 0.1218983978 0.0081963003 0.7423510000 93110502 95654128 1784205312 -0.1517436355 0.2554570735 2.3842170238 546 21.8000000000 0.1094157770 0.0295729578 0.1218983978 0.0081991691 0.9939970000 93112196 95654128 1785221120 -0.1559456736 0.2552777231 2.3805389404 547 21.8400000000 0.1101742685 0.0297203093 0.1218983978 0.0082153358 1.8851030000 93112630 95654128 1786363904 -0.1599419713 0.2528615892 2.3770935535 548 21.8800000000 0.1106607094 0.0298680108 0.1218983978 0.0082103323 1.7465800000 93119576 95654128 1788141568 -0.1651365608 0.2577383518 2.3714711666 549 21.9200000000 0.1119938940 0.0300176026 0.1218983978 0.0082029393 0.7244620000 93287526 95654128 1784463360 -0.1695777923 0.2597589493 2.3673031330 550 21.9600000000 0.1105205491 0.0301639716 0.1218983978 0.0082259762 0.6334670000 93288100 95654128 1785475072 -0.1734721065 0.2550702393 2.3651194572 551 22.0000000000 0.1107552797 0.0303102353 0.1218983978 0.0082394050 0.6842580000 93289794 95654128 1786617856 -0.1775218844 0.2539866269 2.3596684933 552 22.0400000000 0.1121961996 0.0304585794 0.1218983978 0.0082342649 0.7174290000 93290228 95654128 1785487360 -0.1821128130 0.2598501742 2.3531465530 553 22.0800000000 0.1127689332 0.0306074227 0.1218983978 0.0082288878 0.9000530000 93291922 95654128 1786744832 -0.1859287322 0.2610715628 2.3489284515 554 22.1200000000 0.1127311364 0.0307556605 0.1218983978 0.0082314194 0.9390050000 93293616 95654128 1787887616 -0.1901030540 0.2600556314 2.3457808495 555 22.1600000000 0.1140857786 0.0309058049 0.1218983978 0.0082337464 0.7535200000 93294050 95654128 1784459264 -0.1938294321 0.2597748041 2.3413667679 556 22.2000000000 0.1143562198 0.0310558955 0.1218983978 0.0082356851 0.8284650000 93295884 95654128 1785475072 -0.1975376308 0.2584453225 2.3379571438 557 22.2400000000 0.1152612194 0.0312070720 0.1218983978 0.0082316389 0.7467360000 93297578 95654128 1786617856 -0.2017093003 0.2604559958 2.3330254555 558 22.2800000000 0.1155709028 0.0313582617 0.1218983978 0.0082349408 0.7320850000 93298012 95654128 1785614336 -0.2052125037 0.2599990964 2.3289048672 559 22.3200000000 0.1153756306 0.0315085611 0.1218983978 0.0082419866 0.7737150000 93299706 95654128 1786998784 -0.2088200003 0.2599729896 2.3245370388 560 22.3600000000 0.1162938103 0.0316599633 0.1218983978 0.0082573900 0.7819690000 93301400 95654128 1788014592 -0.2122705132 0.2588936090 2.3193426132 561 22.4000000000 0.1170965731 0.0318122568 0.1218983978 0.0082610310 0.8547790000 93301834 95654128 1784078336 -0.2152083218 0.2591564357 2.3143417835 562 22.4400000000 0.1165258512 0.0319629927 0.1218983978 0.0082737312 0.8064310000 93303668 95654128 1785356288 -0.2191260010 0.2560841441 2.3116967678 563 22.4800000000 0.1174496934 0.0321148341 0.1218983978 0.0082937285 0.9537640000 93305362 95654128 1786499072 -0.2225457281 0.2539694905 2.3082671165 564 22.5200000000 0.1187769994 0.0322684904 0.1218983978 0.0082997270 0.8828540000 93305796 95654128 1788149760 -0.2265263498 0.2540340424 2.3043761253 565 22.5600000000 0.1210394800 0.0324256072 0.1218983978 0.0083017326 0.8038300000 93307490 95654128 1784119296 -0.2334298640 0.2564467192 2.2934744358 566 22.6000000000 0.1221093163 0.0325840590 0.1221093163 0.0083065693 0.7538740000 93309184 95654128 1785229312 -0.2364564538 0.2537312210 2.2888889313 567 22.6400000000 0.1231519803 0.0327437908 0.1231519803 0.0083074943 0.6657010000 93309618 95654128 1786245120 -0.2395115942 0.2532604635 2.2839710712 568 22.6800000000 0.1248226464 0.0329059014 0.1248226464 0.0083073112 0.7111360000 93311452 95654128 1788022784 -0.2410059720 0.2553660870 2.2770681381 569 22.7200000000 0.1267572641 0.0330708423 0.1267572641 0.0083072710 0.9250530000 93311886 95654128 1784729600 -0.2439117134 0.2545798123 2.2717247009 570 22.7600000000 0.1272834837 0.0332361277 0.1272834837 0.0083145646 0.7339740000 93313580 95654128 1785753600 -0.2465436608 0.2518998384 2.2675268650 571 22.8000000000 0.1286458671 0.0334032200 0.1286458671 0.0083203262 0.8089230000 93315274 95654128 1786871808 -0.2484919578 0.2478146255 2.2623705864 572 22.8400000000 0.1319827437 0.0335755618 0.1319827437 0.0083150588 0.8658380000 93315708 95654128 1785602048 -0.2498622239 0.2506168187 2.2561001778 573 22.8800000000 0.1335592121 0.0337500534 0.1335592121 0.0083182166 0.9356320000 93317402 95654128 1786998784 -0.2509537935 0.2499560863 2.2492361069 574 22.9200000000 0.1371966153 0.0339302739 0.1371966153 0.0083128698 1.8081540000 93319236 95654128 1788014592 -0.2507556677 0.2462575287 2.2404992580 575 22.9600000000 0.1375944763 0.0341105594 0.1375944763 0.0083085116 1.5490790000 93319670 95654128 1784586240 -0.2519485950 0.2468029708 2.2326679230 576 23.0000000000 0.1363490224 0.0342880568 0.1375944763 0.0083301519 1.2479270000 93321364 95654128 1785729024 -0.2530572116 0.2457236350 2.2237403393 577 23.0400000000 0.1379431486 0.0344677016 0.1379431486 0.0083249894 1.3738650000 93323058 95654128 1786871808 -0.2544298768 0.2447977811 2.2166178226 578 23.0800000000 0.1380258948 0.0346468681 0.1380258948 0.0083336338 1.7805230000 93323492 95654128 1785475072 -0.2576327622 0.2471075505 2.2116448879 579 23.1200000000 0.1385234296 0.0348262749 0.1385234296 0.0083431976 1.5017030000 93325186 95654128 1786744832 -0.2604286075 0.2479983419 2.2067549229 580 23.1600000000 0.1402566284 0.0350080514 0.1402566284 0.0083373763 1.7072960000 93327020 95654128 1788014592 -0.2604196370 0.2474732697 2.2007088661 581 23.2000000000 0.1426226050 0.0351932744 0.1426226050 0.0083463290 1.9064220000 93327454 95654128 1784332288 -0.2620958090 0.2467298955 2.1935451031 582 23.2400000000 0.1416189671 0.0353761364 0.1426226050 0.0083705964 2.0356080000 93329148 95654128 1785348096 -0.2672791779 0.2472011894 2.1856393814 583 23.2800000000 0.1435495168 0.0355616825 0.1435495168 0.0083664460 1.7442410000 93330842 95654128 1786490880 -0.2682002783 0.2472795844 2.1806833744 584 23.3200000000 0.1467579454 0.0357520870 0.1467579454 0.0083657924 1.6428690000 93331276 95654128 1785491456 -0.2677946091 0.2466746867 2.1742093563 585 23.3600000000 0.1495606154 0.0359466315 0.1495606154 0.0083775188 1.3760590000 93332970 95654128 1786490880 -0.2695147395 0.2448879778 2.1655278206 586 23.4000000000 0.1509412527 0.0361428681 0.1509412527 0.0083779445 1.7383830000 93333544 95654128 1787760640 -0.2699760497 0.2436769456 2.1581540108 587 23.4400000000 0.1515754610 0.0363395165 0.1515754610 0.0083818894 1.5504100000 93335238 95654128 1784840192 -0.2731298506 0.2436680645 2.1509950161 588 23.4800000000 0.1542618722 0.0365400647 0.1542618722 0.0083914410 1.6859180000 93336932 95654128 1785982976 -0.2763732672 0.2427205890 2.1440622807 589 23.5200000000 0.1559960395 0.0367428762 0.1559960395 0.0084051374 1.9448510000 93337366 95654128 1787133952 -0.2788723707 0.2411219776 2.1342482567 590 23.5600000000 0.1598288566 0.0369514965 0.1598288566 0.0084090786 1.7045820000 93339060 95654128 1785229312 -0.2795988321 0.2377324402 2.1246213913 591 23.6000000000 0.1623530537 0.0371636819 0.1623530537 0.0084091643 0.9569620000 93340754 95654128 1786753024 -0.2824291885 0.2359516472 2.1163456440 592 23.6400000000 0.1642263979 0.0373783148 0.1642263979 0.0084055111 0.7373730000 93341328 95654128 1788022784 -0.2860267460 0.2353189290 2.1071550846 593 23.6800000000 0.1677709967 0.0375982013 0.1677709967 0.0084040504 0.8495220000 93343022 95654128 1784594432 -0.2882293761 0.2353394330 2.0999643803 594 23.7200000000 0.1726871580 0.0378256238 0.1726871580 0.0084064498 0.8798950000 93344716 95654128 1785737216 -0.2900357544 0.2306951731 2.0919451714 595 23.7600000000 0.1793121994 0.0380634164 0.1793121994 0.0084145801 0.7509200000 93345150 95654128 1787015168 -0.2919540703 0.2235050946 2.0841114521 596 23.8000000000 0.1824253798 0.0383056344 0.1824253798 0.0084213493 0.7835640000 93346844 95654128 1785376768 -0.2952223718 0.2200158387 2.0741791725 597 23.8400000000 0.1848295331 0.0385510681 0.1848295331 0.0084165136 0.8631910000 93348538 95654128 1786888192 -0.2958015203 0.2200294435 2.0642795563 598 23.8800000000 0.1885149479 0.0388018438 0.1885149479 0.0084158105 0.8201940000 93349112 95654128 1788030976 -0.2998851836 0.2183620185 2.0544493198 599 23.9200000000 0.1922985613 0.0390580988 0.1922985613 0.0084165255 0.8678850000 93350806 95654128 1784221696 -0.3040411174 0.2176444530 2.0451006889 600 23.9600000000 0.1964846104 0.0393204763 0.1964846104 0.0084166556 0.9238750000 93352500 95654128 1785237504 -0.3051182628 0.2151601911 2.0352053642 601 24.0000000000 0.2020154744 0.0395911834 0.2020154744 0.0084119803 0.6478490000 93352934 95654128 1786372096 -0.3086219430 0.2085097283 2.0289087296 602 24.0400000000 0.2166567743 0.0398853123 0.2166567743 0.0084550905 0.8310480000 93354628 95654128 1788149760 -0.3187536001 0.1860664785 2.0219535828 603 24.0800000000 0.2250276804 0.0401923478 0.2250276804 0.0084579344 0.7883250000 93356322 95654128 1784213504 -0.3252343833 0.1724026054 2.0188953876 604 24.1200000000 0.2377254963 0.0405193894 0.2377254963 0.0085217288 0.7758250000 93356896 95654128 1785229312 -0.3345161378 0.1523707658 2.0203986168 605 24.1600000000 0.2451407760 0.0408576066 0.2451407760 0.0085419878 0.6981760000 93358590 95654128 1786499072 -0.3384007215 0.1431148797 2.0163660049 606 24.2000000000 0.2533939779 0.0412083267 0.2533939779 0.0085518165 0.7914310000 93359024 95654128 1788141568 -0.3414400518 0.1323364526 2.0121116638 607 24.2400000000 0.2632958591 0.0415742040 0.2632958591 0.0085637954 0.8636910000 93360718 95654128 1783971840 -0.3458541632 0.1177570298 2.0074739456 608 24.2800000000 0.2740618885 0.0419565850 0.2740618885 0.0085752865 0.8234270000 93362412 95654128 1785094144 -0.3506129682 0.1035273746 2.0024168491 609 24.3200000000 0.2842030823 0.0423543625 0.2842030823 0.0085872742 0.9708020000 93362846 95654128 1786236928 -0.3560747504 0.0910249799 1.9981918335 610 24.3600000000 0.2927511930 0.0427648491 0.2927511930 0.0085908045 1.6362430000 93364680 95654128 1787887616 -0.3578244448 0.0807744414 1.9919440746 611 24.4000000000 0.2970938683 0.0431810996 0.2970938683 0.0085856732 0.7032340000 93366374 95654128 1784459264 -0.3608823717 0.0756908208 1.9850882292 612 24.4400000000 0.3015918434 0.0436033394 0.3015918434 0.0085793885 0.7668670000 93370240 95654128 1785602048 -0.3651952147 0.0713019297 1.9796897173 613 24.4800000000 0.3082449734 0.0440350549 0.3082449734 0.0085738713 1.0906230000 93539474 95654128 1786617856 -0.3695122600 0.0659571737 1.9758108854 614 24.5200000000 0.3099963963 0.0444682167 0.3099963963 0.0085700763 0.8154150000 93541168 95654128 1785475072 -0.3739080131 0.0648653582 1.9681091309 615 24.5600000000 0.3144714832 0.0449072464 0.3144714832 0.0085635821 0.7525840000 93541602 95654128 1786617856 -0.3773221970 0.0602416210 1.9608656168 616 24.6000000000 0.3219331205 0.0453569637 0.3219331205 0.0085611505 0.7330190000 93543436 95654128 1787760640 -0.3814934194 0.0535834804 1.9559671879 617 24.6400000000 0.3285886049 0.0458160102 0.3285886049 0.0085572198 0.7985150000 93545130 95654128 1784713216 -0.3837377131 0.0488083698 1.9484645128 618 24.6800000000 0.3327619135 0.0462803239 0.3327619135 0.0085573058 0.9010550000 93545564 95654128 1785856000 -0.3853492439 0.0467447564 1.9425441027 619 24.7200000000 0.3341506720 0.0467453810 0.3341506720 0.0085532509 0.7794350000 93547258 95654128 1786998784 -0.3879298866 0.0480006710 1.9388862848 620 24.7600000000 0.3475430906 0.0472305386 0.3475430906 0.0085568437 0.7646760000 93548952 95654128 1785475072 -0.3940189481 0.0375955105 1.9288563728 621 24.8000000000 0.3517375290 0.0477208880 0.3517375290 0.0085512819 0.8769710000 93549386 95654128 1787125760 -0.3964283168 0.0345277525 1.9247089624 622 24.8400000000 0.3552539647 0.0482153142 0.3552539647 0.0085471331 0.7335120000 93551220 95654128 1785475072 -0.3994443417 0.0316133387 1.9158370495 623 24.8800000000 0.3590495288 0.0487142455 0.3590495288 0.0085439071 0.9524260000 93551654 95654128 1786490880 -0.4026948214 0.0288549550 1.9102309942 624 24.9200000000 0.3626990020 0.0492174262 0.3626990020 0.0085389625 0.8609350000 93553348 95654128 1787633664 -0.4057929814 0.0258291587 1.9031960964 625 24.9600000000 0.3663242757 0.0497247972 0.3663242757 0.0085342819 0.9956570000 93555042 95654128 1784713216 -0.4094519615 0.0239313971 1.8970016241 626 25.0000000000 0.3709723055 0.0502379721 0.3709723055 0.0085286608 0.7814300000 93555476 95654128 1785856000 -0.4130305946 0.0203153379 1.8879303932 627 25.0400000000 0.3742797673 0.0507547852 0.3742797673 0.0085299492 0.7162620000 93557170 95654128 1786871808 -0.4158626497 0.0180300698 1.8806593418 628 25.0800000000 0.3777185380 0.0512754281 0.3777185380 0.0085279197 0.7325850000 93559004 95654128 1785610240 -0.4176980257 0.0159328729 1.8726958036 629 25.1200000000 0.3816308081 0.0518006354 0.3816308081 0.0085278160 0.8692020000 93559438 95654128 1787006976 -0.4217408001 0.0151853645 1.8642567396 630 25.1600000000 0.3841080666 0.0523281075 0.3841080666 0.0085258965 1.1105770000 93561132 95654128 1788149760 -0.4226903319 0.0138663454 1.8540556431 631 25.2000000000 0.3864239156 0.0528575779 0.3864239156 0.0085223333 1.9430200000 93562826 95654128 1784086528 -0.4236490726 0.0137423947 1.8470162153 632 25.2400000000 0.3904108107 0.0533916811 0.3904108107 0.0085176647 1.7985630000 93563260 95654128 1785102336 -0.4273602068 0.0120373145 1.8377798796 633 25.2800000000 0.3941648006 0.0539300273 0.3941648006 0.0085191606 0.7840350000 93564954 95654128 1786372096 -0.4304977655 0.0097602066 1.8284907341 634 25.3200000000 0.3956751823 0.0544690575 0.3956751823 0.0085185149 1.3368850000 93566788 95654128 1788022784 -0.4316322505 0.0105321398 1.8215850592 635 25.3600000000 0.3971621096 0.0550087316 0.3971621096 0.0085134769 0.9238950000 93567222 95654128 1784332288 -0.4306452274 0.0113046076 1.8156570196 636 25.4000000000 0.4012512863 0.0555531381 0.4012512863 0.0085181097 0.7582500000 93568916 95654128 1785475072 -0.4364034235 0.0098353587 1.8050343990 637 25.4400000000 0.4064534605 0.0561040020 0.4064534605 0.0085149731 0.8836940000 93570610 95654128 1786617856 -0.4409109056 0.0094474265 1.7946027517 638 25.4800000000 0.4076982439 0.0566550902 0.4076982439 0.0085232262 0.9603050000 93571044 95654128 1785475072 -0.4401745200 0.0108318105 1.7880307436 639 25.5200000000 0.4104023278 0.0572086852 0.4104023278 0.0085180746 0.8884600000 93572738 95654128 1786617856 -0.4415291250 0.0112685962 1.7788290977 640 25.5600000000 0.4129943252 0.0577646003 0.4129943252 0.0085168154 0.8388510000 93573312 95654128 1787760640 -0.4429201186 0.0118423812 1.7696090937 641 25.6000000000 0.4143753350 0.0583209353 0.4143753350 0.0085124136 0.5779480000 93575006 95654128 1784713216 -0.4436736405 0.0113963988 1.7595112324 642 25.6400000000 0.4163174927 0.0588785623 0.4163174927 0.0085068195 0.6922750000 93576700 95654128 1785856000 -0.4447841048 0.0105541172 1.7494300604 643 25.6800000000 0.4183910489 0.0594376797 0.4183910489 0.0085028585 0.8873960000 93577134 95654128 1786998784 -0.4448446333 0.0108648352 1.7404116392 644 25.7200000000 0.4208994210 0.0599989557 0.4208994210 0.0084975272 0.8359900000 93578828 95654128 1785602048 -0.4458832443 0.0109678162 1.7329847813 645 25.7600000000 0.4236406684 0.0605627413 0.4236406684 0.0084925869 0.7082210000 93580522 95654128 1787125760 -0.4488040507 0.0113487504 1.7242926359 646 25.8000000000 0.4260259569 0.0611284739 0.4260259569 0.0084890003 0.8479920000 93581096 95654128 1785475072 -0.4494104087 0.0104199536 1.7141176462 647 25.8400000000 0.4276248515 0.0616949288 0.4276248515 0.0084847147 0.5733940000 93582790 95654128 1786490880 -0.4502605498 0.0105221579 1.7038159370 648 25.8800000000 0.4282488823 0.0622605985 0.4282488823 0.0084820988 0.7376450000 93584484 95654128 1787760640 -0.4500033557 0.0112661999 1.6973654032 649 25.9200000000 0.4306492805 0.0628282236 0.4306492805 0.0084804943 0.6392000000 93584918 95654128 1784459264 -0.4512728751 0.0117119830 1.6880478859 650 25.9600000000 0.4333797991 0.0633983030 0.4333797991 0.0084776575 0.9190100000 93586612 95654128 1785475072 -0.4530635476 0.0105497492 1.6791117191 651 26.0000000000 0.4355748892 0.0639700028 0.4355748892 0.0084755243 0.8975420000 93588306 95654128 1786617856 -0.4534339607 0.0090094842 1.6714042425 652 26.0400000000 0.4362610281 0.0645410013 0.4362610281 0.0084758979 0.6996730000 93588880 95654128 1785487360 -0.4539322257 0.0102517754 1.6621329784 653 26.0800000000 0.4391814768 0.0651147233 0.4391814768 0.0084725296 0.7513510000 93590574 95654128 1786490880 -0.4555639029 0.0093180854 1.6535388231 654 26.1200000000 0.4409948885 0.0656894636 0.4409948885 0.0084752719 0.7028300000 93592268 95654128 1787633664 -0.4560714662 0.0107593918 1.6462798119 655 26.1600000000 0.4430823028 0.0662656359 0.4430823028 0.0084755743 0.7175550000 93592702 95654128 1784852480 -0.4569863975 0.0113760419 1.6394159794 656 26.2000000000 0.4449357986 0.0668428770 0.4449357986 0.0084743984 0.7457280000 93594396 95654128 1785856000 -0.4590929747 0.0121186683 1.6313253641 657 26.2400000000 0.4474131465 0.0674221316 0.4474131465 0.0084709935 0.7824070000 93598890 95654128 1786998784 -0.4617913067 0.0119707882 1.6231330633 658 26.2800000000 0.4473101497 0.0679994690 0.4474131465 0.0084758033 0.7918710000 93767908 95654128 1785475072 -0.4634913504 0.0139762964 1.6161177158 659 26.3200000000 0.4494956136 0.0685783706 0.4494956136 0.0084709854 0.8489380000 93769602 95654128 1786744832 -0.4661296904 0.0137202907 1.6078281403 660 26.3600000000 0.4495096207 0.0691555391 0.4495096207 0.0084702456 0.8828430000 93770036 95654128 1788014592 -0.4688341618 0.0144147333 1.5985654593 661 26.4000000000 0.4514459074 0.0697338907 0.4514459074 0.0084711276 0.9170900000 93771730 95654128 1784078336 -0.4703622162 0.0155434646 1.5894585848 662 26.4400000000 0.4537855089 0.0703140291 0.4537855089 0.0084695976 0.7643520000 93773424 95654128 1785094144 -0.4729930758 0.0161279980 1.5794869661 663 26.4800000000 0.4557571113 0.0708953912 0.4557571113 0.0084668044 0.7471820000 93773858 95654128 1786109952 -0.4758240581 0.0176665857 1.5684828758 664 26.5200000000 0.4577683508 0.0714780312 0.4577683508 0.0084667344 0.7422820000 93775692 95654128 1787887616 -0.4784558117 0.0177919399 1.5596783161 665 26.5600000000 0.4626525044 0.0720662635 0.4626525044 0.0084700160 0.7461010000 93777386 95654128 1784459264 -0.4833240211 0.0183678716 1.5408449173 666 26.6000000000 0.4649405181 0.0726561648 0.4649405181 0.0084664536 0.7583920000 93777820 95654128 1785602048 -0.4869121313 0.0191222616 1.5297821760 667 26.6400000000 0.4661766589 0.0732461505 0.4661766589 0.0084645903 0.7099760000 93779514 95654128 1786617856 -0.4889214933 0.0214176718 1.5199878216 668 26.6800000000 0.4679255486 0.0738369879 0.4679255486 0.0084606754 0.6487800000 93781208 95654128 1785610240 -0.4927518964 0.0222475342 1.5082253218 669 26.7200000000 0.4692563117 0.0744280482 0.4692563117 0.0084608613 0.6249660000 93781642 95654128 1786753024 -0.4951526225 0.0229242891 1.4977002144 670 26.7600000000 0.4708793461 0.0750197666 0.4708793461 0.0084557836 0.9974460000 93783476 95654128 1787895808 -0.4967856705 0.0255211256 1.4871873856 671 26.8000000000 0.4730383456 0.0756129388 0.4730383456 0.0084518224 0.7540250000 93785170 95654128 1784369152 -0.5006730556 0.0250922535 1.4763451815 672 26.8400000000 0.4743587673 0.0762063106 0.4743587673 0.0084548348 0.8988050000 93785604 95654128 1785356288 -0.5040440559 0.0266460367 1.4660239220 673 26.8800000000 0.4755977392 0.0767997600 0.4755977392 0.0084597578 0.7169090000 93787298 95654128 1786499072 -0.5066949725 0.0279499199 1.4558525085 674 26.9200000000 0.4763404727 0.0773925503 0.4763404727 0.0084627116 0.7446950000 93791472 95654128 1788149760 -0.5067956448 0.0300421566 1.4465621710 675 26.9600000000 0.4779172242 0.0779859202 0.4779172242 0.0084730098 0.9232530000 93960590 95654128 1784467456 -0.5075891614 0.0317474492 1.4382121563 676 27.0000000000 0.4796265662 0.0785800632 0.4796265662 0.0084781100 0.7494430000 93962424 95654128 1785483264 -0.5110377073 0.0335983112 1.4292083979 677 27.0400000000 0.4806266725 0.0791739282 0.4806266725 0.0084902172 0.8795010000 93962858 95654128 1786626048 -0.5145995021 0.0359845795 1.4200543165 678 27.0800000000 0.4822490215 0.0797684342 0.4822490215 0.0084918191 0.7849730000 93964552 95654128 1785483264 -0.5175828338 0.0369149931 1.4127768278 679 27.1200000000 0.4830548465 0.0803623759 0.4830548465 0.0084995859 0.7232430000 93966246 95654128 1786626048 -0.5202221870 0.0389498845 1.4044919014 680 27.1600000000 0.4839881361 0.0809559432 0.4839881361 0.0085049523 0.7423990000 93966680 95654128 1787760640 -0.5226982832 0.0408817343 1.3973727226 681 27.2000000000 0.4856123626 0.0815501524 0.4856123626 0.0085061392 0.9650130000 93970962 95654128 1784852480 -0.5248887539 0.0424899012 1.3897095919 682 27.2400000000 0.4871503413 0.0821448740 0.4871503413 0.0085059239 0.9496460000 94141484 95654128 1785982976 -0.5276672244 0.0440300480 1.3801563978 683 27.2800000000 0.4885222912 0.0827398629 0.4885222912 0.0085012898 1.1131410000 94141918 95654128 1786998784 -0.5319933295 0.0449438095 1.3699218035 684 27.3200000000 0.4891448915 0.0833340223 0.4891448915 0.0085102771 1.8280930000 94143612 95654128 1785475072 -0.5329073668 0.0460535511 1.3631361723 685 27.3600000000 0.4905283451 0.0839284666 0.4905283451 0.0085097801 1.5479510000 94145306 95654128 1786871808 -0.5324756503 0.0467034392 1.3552469015 686 27.4000000000 0.4920558631 0.0845234045 0.4920558631 0.0085151470 1.6619480000 94145740 95654128 1788141568 -0.5369245410 0.0476703569 1.3438227177 687 27.4400000000 0.4938616455 0.0851192389 0.4938616455 0.0085120885 1.1906970000 94147434 95654128 1784078336 -0.5397053361 0.0467114560 1.3347289562 688 27.4800000000 0.4954642057 0.0857156706 0.4954642057 0.0085086378 1.7350750000 94149268 95654128 1785094144 -0.5412666202 0.0474512540 1.3272686005 689 27.5200000000 0.4977132976 0.0863136352 0.4977132976 0.0085038192 0.9509960000 94151870 95654128 1786236928 -0.5452963710 0.0476776175 1.3166371584 690 27.5600000000 0.5000848770 0.0869133036 0.5000848770 0.0085096784 0.7271130000 94322232 95654128 1787887616 -0.5462473631 0.0485201627 1.3105953932 691 27.6000000000 0.5022946000 0.0875144343 0.5022946000 0.0085047342 0.6593620000 94323926 95654128 1784586240 -0.5473346710 0.0482315421 1.3027350903 692 27.6400000000 0.5058361888 0.0881189455 0.5058361888 0.0085007196 0.8244740000 94324360 95654128 1785602048 -0.5489850640 0.0466745161 1.2951200008 693 27.6800000000 0.5097290277 0.0887273295 0.5097290277 0.0085016239 0.9855150000 94326054 95654128 1786617856 -0.5503546000 0.0458917990 1.2881323099 694 27.7200000000 0.5136337280 0.0893395865 0.5136337280 0.0085045976 0.8874220000 94326628 95654128 1785475072 -0.5514578819 0.0448286347 1.2814788818 695 27.7600000000 0.5164854527 0.0899541849 0.5164854527 0.0085068797 0.7315520000 94328322 95654128 1786617856 -0.5527262092 0.0425272509 1.2725337744 696 27.8000000000 0.5204683542 0.0905727398 0.5204683542 0.0085082658 0.6802950000 94330016 95654128 1787760640 -0.5542969108 0.0422335751 1.2654581070 697 27.8400000000 0.5287202597 0.0912013589 0.5287202597 0.0085412595 0.7470850000 94330450 95654128 1784713216 -0.5568994880 0.0386044979 1.2508419752 698 27.8800000000 0.5308617353 0.0918312448 0.5308617353 0.0085356078 0.9290420000 94332144 95654128 1785856000 -0.5558053851 0.0361331254 1.2423925400 699 27.9200000000 0.5346714854 0.0924647788 0.5346714854 0.0085354546 0.7541120000 94333838 95654128 1786998784 -0.5577539206 0.0372092873 1.2322132587 700 27.9600000000 0.5386851430 0.0931022364 0.5386851430 0.0085354602 0.6635980000 94334272 95654128 1785614336 -0.5570321083 0.0379881077 1.2214311361 701 28.0000000000 0.5405514836 0.0937405378 0.5405514836 0.0085368609 0.7670360000 94336106 95654128 1787125760 -0.5538002253 0.0383296236 1.2110353708 702 28.0400000000 0.5415253639 0.0943784079 0.5415253639 0.0085308296 0.8478930000 94337800 95654128 1785475072 -0.5530576706 0.0406093188 1.1990821362 703 28.0800000000 0.5421952009 0.0950154161 0.5421952009 0.0085257914 0.6589760000 94340726 95654128 1786490880 -0.5551926494 0.0400894620 1.1844567060 704 28.1200000000 0.5427592993 0.0956514160 0.5427592993 0.0085280904 0.9565810000 94511116 95654128 1787633664 -0.5535261631 0.0378946550 1.1719478369 705 28.1600000000 0.5429561734 0.0962858908 0.5429561734 0.0085232010 1.9092210000 94512810 95654128 1784848384 -0.5529789925 0.0352194905 1.1580806971 706 28.2000000000 0.5430053473 0.0969186379 0.5430053473 0.0085194135 1.7352170000 94513244 95654128 1785991168 -0.5527972579 0.0328925923 1.1446292400 707 28.2400000000 0.5454465747 0.0975530480 0.5454465747 0.0085174906 1.8972860000 94514938 95654128 1787006976 -0.5513834357 0.0339805782 1.1322922707 708 28.2800000000 0.5476489067 0.0981887766 0.5476489067 0.0085147192 1.9328800000 94516632 95654128 1785348096 -0.5528232455 0.0363887623 1.1185190678 709 28.3200000000 0.5492137671 0.0988249191 0.5492137671 0.0085162475 0.9211770000 94519230 95654128 1786871808 -0.5515947342 0.0344588533 1.1057622433 710 28.3600000000 0.5498886108 0.0994602200 0.5498886108 0.0085120028 0.7352450000 94689760 95654128 1788014592 -0.5480259657 0.0348151512 1.0964899063 711 28.4000000000 0.5549802184 0.1001008951 0.5549802184 0.0085080467 0.9356480000 94691454 95654128 1784205312 -0.5480927229 0.0345422328 1.0899468660 712 28.4400000000 0.5607682467 0.1007478998 0.5607682467 0.0085141106 0.7193370000 94691888 95654128 1784999936 -0.5476925969 0.0342672616 1.0863478184 713 28.4800000000 0.5670766234 0.1014019373 0.5670766234 0.0085235119 0.7687670000 94693582 95654128 1786236928 -0.5455948114 0.0348862819 1.0853414536 714 28.5200000000 0.5726397634 0.1020619343 0.5726397634 0.0085185889 0.7204860000 94695276 95654128 1788014592 -0.5461276770 0.0346948728 1.0815060139 715 28.5600000000 0.5803989768 0.1027309371 0.5803989768 0.0085173432 0.7309460000 94695710 95654128 1784332288 -0.5480338335 0.0343047753 1.0768144131 716 28.6000000000 0.5877032876 0.1034082728 0.5877032876 0.0085309702 0.5993440000 94697544 95654128 1785475072 -0.5479118228 0.0332748927 1.0736017227 717 28.6400000000 0.5942347050 0.1040928285 0.5942347050 0.0085500083 0.7569600000 94697978 95654128 1786617856 -0.5455759764 0.0326855257 1.0737987757 718 28.6800000000 0.5991650224 0.1047823441 0.5991650224 0.0085455158 0.9462670000 94702336 95654128 1783951360 -0.5453801751 0.0319380499 1.0708707571 719 28.7200000000 0.6049104333 0.1054779325 0.6049104333 0.0085422345 0.8022560000 94872726 95654128 1785475072 -0.5473713279 0.0321115553 1.0652524233 720 28.7600000000 0.6108005643 0.1061797695 0.6108005643 0.0085405204 0.7343100000 94873160 95654128 1787252736 -0.5480386615 0.0314149298 1.0607504845 721 28.8000000000 0.6178943515 0.1068894985 0.6178943515 0.0085455955 0.6827130000 94874854 95654128 1784344576 -0.5476421118 0.0303243864 1.0593328476 722 28.8400000000 0.6207976341 0.1076012826 0.6207976341 0.0085416267 0.8382640000 94876688 95654128 1785856000 -0.5524571538 0.0318783037 1.0496118069 723 28.8800000000 0.6228784919 0.1083139758 0.6228784919 0.0085407890 0.9155980000 94877122 95654128 1787633664 -0.5570414066 0.0327654518 1.0400010347 724 28.9200000000 0.6247996688 0.1090273539 0.6247996688 0.0085407102 0.6709980000 94878816 95654128 1784459264 -0.5593345165 0.0337611549 1.0327597857 725 28.9600000000 0.6287788749 0.1097442525 0.6287788749 0.0085381408 0.8888180000 94880510 95654128 1785982976 -0.5621477962 0.0344828665 1.0247764587 726 29.0000000000 0.6367249489 0.1104701213 0.6367249489 0.0085634220 0.6346430000 94880944 95654128 1787887616 -0.5630525351 0.0340553857 1.0204963684 727 29.0400000000 0.6463180780 0.1112071886 0.6463180780 0.0085781440 0.8198060000 94884946 95654128 1784459264 -0.5691692829 0.0334320404 1.0092527866 728 29.0800000000 0.6485656500 0.1119453184 0.6485656500 0.0085778058 0.9444340000 95055476 95654128 1785982976 -0.5778239369 0.0350088254 0.9962442517 729 29.1200000000 0.6547858119 0.1126899555 0.6547858119 0.0086070179 1.9876440000 95055910 95654128 1787887616 -0.5771774650 0.0355674364 0.9944350123 730 29.1600000000 0.6587575078 0.1134379933 0.6587575078 0.0086054235 0.9237690000 95057604 95654128 1784840192 -0.5787445903 0.0361000560 0.9895918965 731 29.2000000000 0.6644344330 0.1141917504 0.6644344330 0.0086148375 0.7541290000 95059298 95654128 1786109952 -0.5846360922 0.0360830650 0.9800589681 732 29.2400000000 0.6684443951 0.1149489261 0.6684443951 0.0086273008 0.8730400000 95059732 95654128 1788014592 -0.5885684490 0.0366086438 0.9727315307 733 29.2800000000 0.6749237180 0.1157128753 0.6749237180 0.0086561548 0.8468230000 95061426 95654128 1784332288 -0.5902554989 0.0356851406 0.9688567519 734 29.3200000000 0.6789370775 0.1164802108 0.6789370775 0.0086730402 0.7170210000 95062000 95654128 1785745408 -0.5965139270 0.0364111923 0.9593744874 735 29.3600000000 0.6842907071 0.1172527421 0.6842907071 0.0087034597 0.5813590000 95063694 95654128 1787633664 -0.5986028910 0.0363491401 0.9546072483 736 29.4000000000 0.6902450919 0.1180312643 0.6902450919 0.0087223180 0.6779730000 95065388 95654128 1784459264 -0.5990087986 0.0361564979 0.9521098137 737 29.4400000000 0.6986511946 0.1188190796 0.6986511946 0.0087567054 0.7804860000 95067794 95654128 1785982976 -0.6011888981 0.0346770138 0.9469794035 738 29.4800000000 0.7046180367 0.1196128452 0.7046180367 0.0087946780 0.9215110000 95238200 95654128 1787666432 -0.6032846570 0.0345811397 0.9416976571 739 29.5200000000 0.7080290318 0.1204090782 0.7080290318 0.0088173260 0.7779310000 95239894 95654128 1784332288 -0.6029734612 0.0346725322 0.9400677681 740 29.5600000000 0.7139574289 0.1212111705 0.7139574289 0.0088265441 0.7891440000 95240468 95654128 1785856000 -0.6032572985 0.0335860252 0.9369626641 741 29.6000000000 0.7219775319 0.1220219214 0.7219775319 0.0088408037 0.7236260000 95242162 95654128 1787633664 -0.6033623815 0.0324472263 0.9345152378 742 29.6400000000 0.7296363115 0.1228408087 0.7296363115 0.0088532873 0.8084230000 95243856 95654128 1784848384 -0.6032940149 0.0316984802 0.9318091869 743 29.6800000000 0.7360125780 0.1236660735 0.7360125780 0.0088641523 0.7136780000 95244290 95654128 1786261504 -0.6039435267 0.0313181430 0.9288055897 744 29.7200000000 0.7398751378 0.1244943115 0.7398751378 0.0088659166 0.7512540000 95245984 95654128 1788022784 -0.6077458858 0.0323989242 0.9226177335 745 29.7600000000 0.7430312037 0.1253245624 0.7430312037 0.0088823179 0.8560810000 95250114 95654128 1784721408 -0.6095303297 0.0322245136 0.9198731780 746 29.8000000000 0.7467058301 0.1261575131 0.7467058301 0.0088964391 0.7757070000 95419400 95654128 1786118144 -0.6124749184 0.0328398272 0.9146921635 747 29.8400000000 0.7494188547 0.1269918657 0.7494188547 0.0089236951 0.8511560000 95421094 95654128 1787895808 -0.6067008376 0.0326972380 0.9124198556 748 29.8800000000 0.7516568899 0.1278269793 0.7516568899 0.0089223338 0.9392970000 95422788 95654128 1784733696 -0.6037513018 0.0326738581 0.9121292233 749 29.9200000000 0.7558673024 0.1286654844 0.7558673024 0.0089204132 0.5880790000 95423222 95654128 1786118144 -0.6057226062 0.0331089534 0.9077350497 750 29.9600000000 0.7628179789 0.1295110211 0.7628179789 0.0089239936 0.6845320000 95424916 95654128 1787887616 -0.6063014865 0.0333986096 0.9039329290 751 30.0000000000 0.7655575871 0.1303579539 0.7655575871 0.0089276446 0.8676660000 95426610 95654128 1784459264 -0.6062756181 0.0333768427 0.9015966058 752 30.0400000000 0.7673354745 0.1312049985 0.7673354745 0.0089252316 0.9184030000 95428736 95654128 1785982976 -0.6074267030 0.0329617076 0.8990892768 753 30.0800000000 0.7734232545 0.1320578780 0.7734232545 0.0089298362 0.7493110000 95599138 95654128 1787760640 -0.6089830399 0.0333267301 0.8947566748 754 30.1200000000 0.7756584287 0.1329114596 0.7756584287 0.0089399217 0.8596600000 95599572 95654128 1784840192 -0.6068617105 0.0329294614 0.8922448158 755 30.1600000000 0.7758654356 0.1337630543 0.7758654356 0.0089384713 0.7391820000 95601266 95654128 1786109952 -0.6028437614 0.0324642099 0.8909378648 756 30.2000000000 0.7801489234 0.1346180621 0.7801489234 0.0089359775 0.7216670000 95602960 95654128 1788141568 -0.6031318307 0.0324177630 0.8874456882 757 30.2400000000 0.7837678790 0.1354755915 0.7837678790 0.0089346730 0.7374220000 95603394 95654128 1784492032 -0.6035118699 0.0320738070 0.8840292692 758 30.2800000000 0.7873226404 0.1363355481 0.7873226404 0.0089324290 0.8662280000 95605228 95654128 1785856000 -0.6045828462 0.0322436243 0.8807853460 759 30.3200000000 0.7944656610 0.1372026497 0.7944656610 0.0089401814 0.7775430000 95606922 95654128 1787760640 -0.6029661298 0.0321170539 0.8772018552 760 30.3600000000 0.7943575382 0.1380673272 0.7944656610 0.0089465181 0.7236080000 95609816 95654128 1784459264 -0.5995213389 0.0307799205 0.8719779849 761 30.4000000000 0.7961193323 0.1389320473 0.7961193323 0.0089442941 0.8385940000 95780110 95654128 1785856000 -0.5985103250 0.0302533973 0.8691399693 762 30.4400000000 0.8006278276 0.1398004144 0.8006278276 0.0089444694 0.8160450000 95781804 95654128 1788014592 -0.5994025469 0.0300624967 0.8654049635 763 30.4800000000 0.8017949462 0.1406680350 0.8017949462 0.0089457221 0.6660270000 95782238 95654128 1784713216 -0.5991924405 0.0286354106 0.8589260578 764 30.5200000000 0.8057138324 0.1415385138 0.8057138324 0.0089471770 0.8021680000 95783932 95654128 1785982976 -0.5966930389 0.0285530947 0.8557038307 765 30.5600000000 0.8089793921 0.1424109856 0.8089793921 0.0089477169 0.6250830000 95785766 95654128 1787760640 -0.5946956277 0.0277875327 0.8501676917 766 30.6000000000 0.8113341331 0.1432842534 0.8113341331 0.0089494913 0.7015520000 95788460 95654128 1784360960 -0.5890842080 0.0282162409 0.8496179581 767 30.6400000000 0.8155163527 0.1441606968 0.8155163527 0.0089456231 0.9097190000 95958874 95654128 1785856000 -0.5871506333 0.0287681166 0.8433924913 768 30.6800000000 0.8191567063 0.1450395979 0.8191567063 0.0089425754 0.6964150000 95960568 95654128 1787760640 -0.5851688385 0.0291291978 0.8376638293 769 30.7200000000 0.8202766776 0.1459176695 0.8202766776 0.0089434686 0.7986350000 95961002 95654128 1784459264 -0.5784564614 0.0294379536 0.8372748494 770 30.7600000000 0.8233757019 0.1467974851 0.8233757019 0.0089409939 0.8688180000 95964476 95654128 1785982976 -0.5763099194 0.0299637020 0.8326097727 771 30.8000000000 0.8280403614 0.1476810686 0.8280403614 0.0089402213 0.7028970000 96133754 95654128 1787887616 -0.5738885403 0.0307241846 0.8270611763 772 30.8400000000 0.8271734715 0.1485612401 0.8280403614 0.0089368790 0.8081660000 96135448 95654128 1784733696 -0.5680171847 0.0285265576 0.8210228682 773 30.8800000000 0.8297903538 0.1494425197 0.8297903538 0.0089411532 0.6362070000 96139490 95654128 1786109952 -0.5611906648 0.0284090787 0.8170219064 774 30.9200000000 0.8339568377 0.1503269051 0.8339568377 0.0089511995 0.6727410000 96308600 95654128 1788014592 -0.5605973005 0.0294605941 0.8112303019 775 30.9600000000 0.8374142051 0.1512134694 0.8374142051 0.0089520198 0.9487050000 96310294 95654128 1784332288 -0.5609416962 0.0302016474 0.8062531948 776 31.0000000000 0.8400758505 0.1521011786 0.8400758505 0.0089519794 0.5591690000 96311988 95654128 1785872384 -0.5605899692 0.0311551671 0.8018344045 777 31.0400000000 0.8421512842 0.1529892740 0.8421512842 0.0089490475 0.7276260000 96314486 95654128 1787633664 -0.5555087328 0.0314081125 0.7972998619 778 31.0800000000 0.8451426029 0.1538789312 0.8451426029 0.0089501250 0.8207850000 96484864 95654128 1784459264 -0.5545058846 0.0323266052 0.7922621965 779 31.1200000000 0.8500159979 0.1547725603 0.8500159979 0.0089520617 0.7660290000 96486558 95654128 1785982976 -0.5517375469 0.0335738398 0.7882325053 780 31.1600000000 0.8556684852 0.1556711449 0.8556684852 0.0089527124 0.8111690000 96486992 95654128 1787760640 -0.5488438606 0.0344310366 0.7839572430 781 31.2000000000 0.8576352596 0.1565699465 0.8576352596 0.0089495906 0.7860400000 96488686 95654128 1784459264 -0.5432813168 0.0355213471 0.7783154249 782 31.2400000000 0.8588440418 0.1574679953 0.8588440418 0.0089453258 0.6491340000 96492352 95654128 1785982976 -0.5385880470 0.0348515250 0.7730404139 783 31.2800000000 0.8594914675 0.1583645770 0.8594914675 0.0089412926 0.7185910000 96661642 95654128 1788014592 -0.5339708328 0.0358397439 0.7696461082 784 31.3200000000 0.8617287874 0.1592617252 0.8617287874 0.0089388692 0.7793000000 96663336 95654128 1784713216 -0.5320608020 0.0375050977 0.7626973391 785 31.3600000000 0.8643442392 0.1601599195 0.8643442392 0.0089361616 0.9737650000 96665030 95654128 1785982976 -0.5316955447 0.0375666246 0.7591847181 786 31.4000000000 0.8675747514 0.1610599383 0.8675747514 0.0089346360 0.9096870000 96665464 95654128 1788014592 -0.5257007480 0.0374678560 0.7582961917 787 31.4400000000 0.8699598312 0.1619607006 0.8699598312 0.0089315374 0.7836540000 96667158 95654128 1784848384 -0.5211774707 0.0362218693 0.7566050887 788 31.4800000000 0.8708226681 0.1628602716 0.8708226681 0.0089281886 0.7586900000 96670832 95654128 1786118144 -0.5185192823 0.0370130651 0.7524313331 789 31.5200000000 0.8714190722 0.1637583183 0.8714190722 0.0089248066 0.8142220000 96840094 95654128 1788022784 -0.5170203447 0.0383362286 0.7469003201 790 31.5600000000 0.8717540503 0.1646545154 0.8717540503 0.0089212281 0.9948320000 96841788 95654128 1784594432 -0.5150923729 0.0387763605 0.7440391183 791 31.6000000000 0.8725240231 0.1655494199 0.8725240231 0.0089188690 0.8010150000 96842222 95654128 1785880576 -0.5157120824 0.0372381881 0.7373502851 792 31.6400000000 0.8723227382 0.1664418105 0.8725240231 0.0089146977 0.7443880000 96845664 95654128 1787641856 -0.5163479447 0.0359072462 0.7322109938 793 31.6800000000 0.8708745837 0.1673301242 0.8725240231 0.0089095924 0.7003850000 97016106 95654128 1784467456 -0.5145953298 0.0352740996 0.7303608060 794 31.7200000000 0.8721219897 0.1682177714 0.8725240231 0.0089063183 0.9673590000 97016540 95654128 1785991168 -0.5157247186 0.0336207636 0.7231294513 795 31.7600000000 0.8736904860 0.1691051585 0.8736904860 0.0089027548 0.7570520000 97018374 95654128 1787768832 -0.5163158774 0.0328977481 0.7192078829 796 31.8000000000 0.8733083010 0.1699898358 0.8736904860 0.0088975985 0.8763560000 97020068 95654128 1784467456 -0.5137161016 0.0326746814 0.7165468335 797 31.8400000000 0.8746109605 0.1708739275 0.8746109605 0.0088925857 0.7641750000 97020502 95654128 1785999360 -0.5114754438 0.0320014395 0.7134036422 798 31.8800000000 0.8757725954 0.1717572592 0.8757725954 0.0088881673 0.7359800000 97022196 95654128 1787760640 -0.5118902922 0.0315013044 0.7113847136 799 31.9200000000 0.8794639707 0.1726429998 0.8794639707 0.0088886740 0.8508580000 97023890 95654128 1784459264 -0.5124538541 0.0305082649 0.7049849033 800 31.9600000000 0.8804997802 0.1735278207 0.8804997802 0.0088883287 0.6686530000 97024324 95654128 1785982976 -0.5136376023 0.0288441479 0.7008086443 801 32.0000000000 0.8767707348 0.1744057769 0.8804997802 0.0088892776 0.7774970000 97026158 95654128 1787887616 -0.5099003911 0.0284310151 0.7019324899 802 32.0400000000 0.8765735626 0.1752812979 0.8804997802 0.0088968981 0.7336550000 97027852 95654128 1784459264 -0.5109304786 0.0271832682 0.6972771287 803 32.0800000000 0.8774031401 0.1761556713 0.8804997802 0.0088993758 1.0160950000 97029878 95654128 1785982976 -0.5119180083 0.0245635193 0.6899664998 804 32.1199999990 0.8767344356 0.1770270379 0.8804997802 0.0088966452 0.7676620000 97200320 95654128 1787887616 -0.5122240782 0.0232297648 0.6865994930 805 32.1600000000 0.8758684397 0.1778951638 0.8804997802 0.0088973827 0.7399720000 97202014 95654128 1784713216 -0.5134047270 0.0214275122 0.6815207005 806 32.2000000000 0.8792931437 0.1787653847 0.8804997802 0.0089213974 0.7249740000 97202448 95654128 1786126336 -0.5070848465 0.0173704792 0.6663714051 807 32.2400000000 0.8812488914 0.1796358723 0.8812488914 0.0089224607 0.8564780000 97204282 95654128 1788014592 -0.5059447885 0.0157957450 0.6620211601 808 32.2800000000 0.8836737275 0.1805072063 0.8836737275 0.0089277704 0.7851210000 97204716 95654128 1784586240 -0.5065354705 0.0140560474 0.6541593671 809 32.3200000000 0.8850250244 0.1813780565 0.8850250244 0.0089264869 0.8194590000 97208066 95654128 1785982976 -0.5101348758 0.0122422101 0.6473176479 810 32.3600000000 0.8845143318 0.1822461259 0.8850250244 0.0089239156 0.8282100000 97378492 95654128 1788014592 -0.5106515288 0.0106994929 0.6437017918 811 32.4000000000 0.8851916194 0.1831128898 0.8851916194 0.0089237270 0.7504680000 97378926 95654128 1784840192 -0.5133588314 0.0062899482 0.6377865076 812 32.4399999990 0.8831526041 0.1839750077 0.8851916194 0.0089216992 0.7239740000 97380620 95654128 1786126336 -0.5112003088 0.0016711489 0.6359947920 813 32.4800000000 0.8874264956 0.1848402617 0.8874264956 0.0089481281 0.8428150000 97382454 95654128 1788014592 -0.5103186965 0.0045815259 0.6267489195 814 32.5200000000 0.8936028481 0.1857109774 0.8936028481 0.0089595012 0.9327040000 97382888 95654128 1784332288 -0.5135707259 0.0085336976 0.6139701605 815 32.5600000000 0.8925271630 0.1865782365 0.8936028481 0.0089693310 0.6874190000 97386978 95654128 1785729024 -0.5152046680 0.0026682634 0.6110924482 816 32.6000000000 0.8937591314 0.1874448798 0.8937591314 0.0089702400 0.8033160000 97557380 95654128 1787760640 -0.5138579607 0.0011037787 0.6064870954 817 32.6400000000 0.8941685557 0.1883099026 0.8941685557 0.0089673041 0.7048370000 97557814 95654128 1784840192 -0.5182474256 0.0000444537 0.5993221998 818 32.6800000000 0.8951654434 0.1891740292 0.8951654434 0.0089653525 0.7198970000 97559508 95654128 1786109952 -0.5220105648 -0.0009603255 0.5915756822 819 32.7200000000 0.8940225840 0.1900346501 0.8951654434 0.0089615571 1.1693570000 97561202 95654128 1787887616 -0.5246251225 -0.0046331547 0.5862233639 820 32.7599999990 0.8951305151 0.1908945231 0.8951654434 0.0089594187 1.6499730000 97561636 95654128 1784586240 -0.5240510106 -0.0056904913 0.5808176994 821 32.7999999990 0.8972076774 0.1917548315 0.8972076774 0.0089600321 1.0292880000 97563330 95654128 1786109952 -0.5261260271 -0.0054489062 0.5733892322 822 32.8400000000 0.8994189501 0.1926157367 0.8994189501 0.0089569287 0.6455360000 97565024 95654128 1787887616 -0.5269817114 -0.0072877933 0.5678489804 823 32.8800000000 0.9012197256 0.1934767379 0.9012197256 0.0089580157 0.6542360000 97567934 95654128 1784840192 -0.5271851420 -0.0051800250 0.5626364946 824 32.9200000000 0.9043932557 0.1943395007 0.9043932557 0.0089579037 0.7511770000 97738364 95654128 1786245120 -0.5294882655 -0.0036765307 0.5553227663 825 32.9600000000 0.9034582376 0.1951990386 0.9043932557 0.0089545915 0.7689260000 97740058 95654128 1788276736 -0.5294899940 -0.0059507536 0.5507521629 826 33.0000000000 0.9052925110 0.1960587159 0.9052925110 0.0089534051 0.9098680000 97740492 95654128 1784213504 -0.5264266133 -0.0050775316 0.5465953946 827 33.0400000000 0.9059289694 0.1969170838 0.9059289694 0.0089514108 0.6771010000 97742186 95654128 1785737216 -0.5308288932 -0.0056587714 0.5372542143 828 33.0800000000 0.9049022794 0.1977721384 0.9059289694 0.0089483846 0.6306790000 97744020 95654128 1787514880 -0.5298084617 -0.0115876291 0.5349780917 829 33.1199999990 0.9067317247 0.1986273369 0.9067317247 0.0089558008 0.8199180000 97744454 95654128 1784721408 -0.5280498862 -0.0116450116 0.5305905938 830 33.1600000000 0.9095761180 0.1994839017 0.9095761180 0.0089741758 0.7714810000 97746148 95654128 1786118144 -0.5350176096 -0.0085465927 0.5200458169 831 33.2000000000 0.9099191427 0.2003388178 0.9099191427 0.0089706675 0.7432440000 97747842 95654128 1787895808 -0.5360053182 -0.0104226992 0.5150681734 832 33.2400000000 0.9090513587 0.2011906357 0.9099191427 0.0089678803 0.6071990000 97748276 95654128 1784606720 -0.5322809815 -0.0118640438 0.5128511786 833 33.2800000000 0.9110991359 0.2020428668 0.9110991359 0.0089730630 0.7843870000 97752034 95654128 1786118144 -0.5302950144 -0.0127571169 0.5070062876 834 33.3200000000 0.9122678041 0.2028944555 0.9122678041 0.0089794706 0.8748170000 97922496 95654128 1788149760 -0.5328760147 -0.0133073078 0.5002044439 835 33.3600000000 0.9135378599 0.2037455254 0.9135378599 0.0089834376 0.7628660000 97922930 95654128 1784848384 -0.5342652798 -0.0131910713 0.4928513169 836 33.4000000000 0.9144880772 0.2045956959 0.9144880772 0.0089858557 0.7941970000 97924624 95654128 1786245120 -0.5346601605 -0.0120824669 0.4860725105 837 33.4399999990 0.9144607186 0.2054438023 0.9144880772 0.0089870290 0.9477240000 97926318 95654128 1788014592 -0.5343833566 -0.0108518945 0.4795713127 838 33.4800000000 0.9133327007 0.2062885385 0.9144880772 0.0089862798 0.7766290000 97926892 95654128 1784332288 -0.5339270234 -0.0107795289 0.4725299776 839 33.5200000000 0.9148120284 0.2071330241 0.9148120284 0.0089923809 0.7411760000 97928586 95654128 1785856000 -0.5304291248 -0.0078304335 0.4628764987 840 33.5600000000 0.9137766957 0.2079742666 0.9148120284 0.0089892871 0.8288550000 97930844 95654128 1787887616 -0.5234010816 -0.0097732041 0.4572510719 841 33.6000000000 0.9134686589 0.2088131422 0.9148120284 0.0089903186 0.7084070000 98101306 95654128 1784840192 -0.5203044415 -0.0108858980 0.4506318569 842 33.6400000000 0.9135208726 0.2096500873 0.9148120284 0.0090029046 0.7634990000 98103000 95654128 1786109952 -0.5195214152 -0.0100960899 0.4420373738 843 33.6800000000 0.9143763185 0.2104860614 0.9148120284 0.0090409384 0.6236840000 98103434 95654128 1788141568 -0.5114960670 -0.0101687564 0.4268471003 844 33.7200000000 0.9159530997 0.2113219229 0.9159530997 0.0090457240 0.5932130000 98105268 95654128 1784713216 -0.5085013509 -0.0094819311 0.4184204638 845 33.7599999990 0.9180594087 0.2121582986 0.9180594087 0.0090551775 0.5557360000 98106962 95654128 1785999360 -0.5079845786 -0.0052463082 0.4094836414 846 33.7999999990 0.9190346003 0.2129938498 0.9190346003 0.0090601166 0.7127600000 98107396 95654128 1787760640 -0.5083415508 0.0031892811 0.3999114633 847 33.8400000000 0.9209188223 0.2138296526 0.9209188223 0.0090567016 0.7707310000 98110542 95654128 1784332288 -0.5026567578 0.0070568202 0.3908163905 848 33.8800000000 0.9211515188 0.2146637585 0.9211515188 0.0090536691 0.8930280000 98281000 95654128 1785872384 -0.4937637448 0.0075456570 0.3833072186 849 33.9200000000 0.9213410020 0.2154961228 0.9213410020 0.0090489247 1.0319850000 98281434 95654128 1787633664 -0.4920918345 0.0054453486 0.3753858507 850 33.9600000000 0.9217811823 0.2163270464 0.9217811823 0.0090447454 1.5760680000 98283268 95654128 1784459264 -0.4840928316 0.0061661983 0.3666214347 851 34.0000000000 0.9225444198 0.2171569140 0.9225444198 0.0090402047 0.7936900000 98284962 95654128 1785982976 -0.4758959711 0.0055124182 0.3595151603 852 34.0400000000 0.9232374430 0.2179856471 0.9232374430 0.0090356846 0.7124700000 98285396 95654128 1787760640 -0.4727431834 0.0051307534 0.3508370221 853 34.0800000000 0.9249796271 0.2188144794 0.9249796271 0.0090321964 0.7692260000 98287090 95654128 1784487936 -0.4664559662 0.0087974221 0.3424249887 854 34.1199999990 0.9253556728 0.2196418110 0.9253556728 0.0090275738 0.8741840000 98288784 95654128 1785982976 -0.4634637833 0.0099090673 0.3345061839 855 34.1600000000 0.9243720770 0.2204660569 0.9253556728 0.0090230493 0.7460540000 98289218 95654128 1787760640 -0.4599243999 0.0106937429 0.3260823190 856 34.2000000000 0.9250506759 0.2212891698 0.9253556728 0.0090241481 0.8907940000 98291052 95654128 1784459264 -0.4524625838 0.0131517584 0.3189603090 857 34.2400000000 0.9264738560 0.2221120224 0.9264738560 0.0090232387 0.7246530000 98291486 95654128 1785982976 -0.4472804666 0.0142467339 0.3120317161 858 34.2800000000 0.9260494113 0.2229324623 0.9264738560 0.0090201281 0.9551070000 98293180 95654128 1787760640 -0.4428392947 0.0140278991 0.3058805466 859 34.3200000000 0.9264249206 0.2237514290 0.9264738560 0.0090262320 0.8582460000 98294874 95654128 1784459264 -0.4393561780 0.0173035972 0.2968533337 860 34.3600000000 0.9282319546 0.2245705924 0.9282319546 0.0090269424 0.7327540000 98296712 95654128 1785999360 -0.4336648583 0.0204655342 0.2888185084 861 34.4000000000 0.9265406728 0.2253858887 0.9282319546 0.0090218071 0.6372530000 98467178 95654128 1787760640 -0.4297075272 0.0179902595 0.2808069587 862 34.4400000000 0.9266351461 0.2261994029 0.9282319546 0.0090207938 0.6855410000 98469012 95654128 1784705024 -0.4246901274 0.0195032991 0.2731857300 863 34.4800000000 0.9260588288 0.2270103640 0.9282319546 0.0090189048 0.9178060000 98469446 95654128 1786101760 -0.4195297360 0.0229114108 0.2654131651 864 34.5200000000 0.9277048707 0.2278213530 0.9282319546 0.0090155489 0.8006540000 98471140 95654128 1788006400 -0.4158543646 0.0255958159 0.2578658164 865 34.5600000000 0.9257813692 0.2286282432 0.9282319546 0.0090121680 0.8956290000 98472834 95654128 1784832000 -0.4119385779 0.0210825093 0.2510586977 866 34.6000000000 0.9222884178 0.2294292365 0.9282319546 0.0090072711 0.7555270000 98473268 95654128 1786101760 -0.4111421406 0.0113778291 0.2463634163 867 34.6400000000 0.9223092794 0.2302284061 0.9282319546 0.0090625456 0.9276230000 98476358 95654128 1788047360 -0.4081256986 0.0120122815 0.2302752584 868 34.6800000000 0.9232046008 0.2310267658 0.9282319546 0.0090685753 0.7310820000 98646968 95654128 1784459264 -0.4009415805 0.0120498724 0.2248906046 869 34.7200000000 0.9249154925 0.2318252568 0.9282319546 0.0090824334 0.6831790000 98647402 95654128 1785856000 -0.3987464607 0.0152687971 0.2178638279 870 34.7600000000 0.9251915216 0.2326222295 0.9282319546 0.0090882221 0.7052240000 98649096 95654128 1787887616 -0.3942179382 0.0167995244 0.2094967514 871 34.8000000000 0.9252136946 0.2334173977 0.9282319546 0.0090866024 0.8079310000 98650790 95654128 1784365056 -0.3875172436 0.0147690102 0.2045458108 872 34.8400000000 0.9240505099 0.2342094081 0.9282319546 0.0090931016 0.8263990000 98651224 95654128 1785856000 -0.3869553506 0.0131289084 0.1968072057 873 34.8800000000 0.9248045683 0.2350004679 0.9282319546 0.0090989532 0.9064540000 98652918 95654128 1787633664 -0.3797968030 0.0173234623 0.1897214502 874 34.9200000000 0.9261493087 0.2357912560 0.9282319546 0.0091022733 0.9346640000 98653492 95654128 1784459264 -0.3789221942 0.0207360107 0.1819234043 875 34.9600000000 0.9279074073 0.2365822459 0.9282319546 0.0091009078 0.6134360000 98655186 95654128 1785991168 -0.3738738000 0.0235245544 0.1760428250 876 35.0000000000 0.9274332523 0.2373708886 0.9282319546 0.0090968798 0.7446200000 98656880 95654128 1787633664 -0.3694405556 0.0245644841 0.1686740667 877 35.0400000000 0.9275016189 0.2381578108 0.9282319546 0.0090923519 0.7062840000 98657314 95654128 1784459264 -0.3600334227 0.0227452517 0.1648599505 878 35.0800000000 0.9272274375 0.2389426281 0.9282319546 0.0090920910 0.8136660000 98659008 95654128 1785982976 -0.3571544290 0.0225956067 0.1593175530 879 35.1200000000 0.9276980162 0.2397261951 0.9282319546 0.0090997544 0.8016340000 98660702 95654128 1787887616 -0.3557522297 0.0272908956 0.1501180083 880 35.1600000000 0.9274756908 0.2405077286 0.9282319546 0.0090964324 1.0175490000 98663108 95654128 1784586240 -0.3476079702 0.0282538477 0.1436310858 881 35.2000000000 0.9289996624 0.2412892178 0.9289996624 0.0090950647 1.0148030000 98833538 95654128 1786109952 -0.3407917023 0.0272163115 0.1397368908 882 35.2400000000 0.9300124049 0.2420700831 0.9300124049 0.0090951013 1.0780520000 98835232 95654128 1787887616 -0.3339317441 0.0297775902 0.1324050277 883 35.2800000000 0.9297962189 0.2428489349 0.9300124049 0.0090957858 0.7129700000 98835666 95654128 1784725504 -0.3322971463 0.0325767249 0.1224630550 884 35.3200000000 0.9304963946 0.2436268166 0.9304963946 0.0090910173 0.6858260000 98837360 95654128 1786109952 -0.3239805996 0.0322123468 0.1174909174 885 35.3600000000 0.9292486906 0.2444015306 0.9304963946 0.0090876353 0.8014470000 98839054 95654128 1787887616 -0.3175112009 0.0263856184 0.1127439290 886 35.4000000000 0.9271415472 0.2451721175 0.9304963946 0.0090827442 0.7901120000 98839628 95654128 1784713216 -0.3177779615 0.0209456868 0.1048629209 887 35.4400000000 0.9281692505 0.2459421255 0.9304963946 0.0090875702 0.7981540000 98841322 95654128 1786109952 -0.3147453368 0.0229261760 0.0949853361 888 35.4800000000 0.9274969697 0.2467096423 0.9304963946 0.0090840940 0.7378880000 98843016 95654128 1787887616 -0.3103688955 0.0211431086 0.0876201242 889 35.5200000000 0.9267464280 0.2474745880 0.9304963946 0.0090856457 0.8541950000 98843450 95654128 1784586240 -0.3066587150 0.0190705471 0.0797829926 890 35.5600000000 0.9270405769 0.2482381453 0.9304963946 0.0091019150 0.7926830000 98846780 95654128 1786109952 -0.3022402823 0.0219718385 0.0706446245 891 35.6000000000 0.9273066521 0.2490002873 0.9304963946 0.0091123619 0.8033280000 99017258 95654128 1788014592 -0.2969225645 0.0245752353 0.0591532588 892 35.6400000000 0.9257249236 0.2497589472 0.9304963946 0.0091129718 0.8788180000 99017832 95654128 1784459264 -0.2947264314 0.0258971788 0.0491840132 893 35.6800000000 0.9252030253 0.2505153236 0.9304963946 0.0091109605 0.8041960000 99019526 95654128 1785872384 -0.2878273129 0.0242793895 0.0427784659 894 35.7200000000 0.9249650240 0.2512697416 0.9304963946 0.0091196407 0.8583370000 99019960 95654128 1787887616 -0.2798656821 0.0279982649 0.0358234569 895 35.7600000000 0.9260227680 0.2520236556 0.9304963946 0.0091294601 0.7097420000 99021654 95654128 1784459264 -0.2745050490 0.0322451927 0.0259169452 896 35.8000000000 0.9268032908 0.2527767578 0.9304963946 0.0091322357 0.9418090000 99023348 95654128 1785982976 -0.2691290379 0.0368324891 0.0181915369 897 35.8400000000 0.9289609790 0.2535305864 0.9304963946 0.0091327781 0.6368780000 99023782 95654128 1787887616 -0.2615765333 0.0430353358 0.0094125625 898 35.8800000000 0.9285005927 0.2542822234 0.9304963946 0.0091294030 0.7901880000 99027696 95654128 1784340480 -0.2546103299 0.0428827591 0.0030615777 899 35.9200000000 0.9274789095 0.2550310517 0.9304963946 0.0091248109 0.9316360000 99198138 95654128 1785856000 -0.2484454215 0.0420116074 -0.0051642181 900 35.9600000000 0.9260631204 0.2557766429 0.9304963946 0.0091202036 0.8493820000 99198572 95654128 1787887616 -0.2400024235 0.0355175175 -0.0102908760 901 36.0000000000 0.9252666235 0.2565196951 0.9304963946 0.0091218858 0.8817240000 99202362 95654128 1784459264 -0.2369076461 0.0315868556 -0.0161795802 902 36.0400000000 0.9249984622 0.2572608023 0.9304963946 0.0091388222 0.7820350000 99372848 95654128 1785982976 -0.2322693020 0.0342371911 -0.0295309089 903 36.0800000000 0.9240936041 0.2579992661 0.9304963946 0.0091398735 0.6632830000 99373282 95654128 1787887616 -0.2267587334 0.0323035158 -0.0372585393 904 36.1200000000 0.9255004525 0.2587376524 0.9304963946 0.0091449083 0.7266980000 99375116 95654128 1784725504 -0.2127242535 0.0324449204 -0.0333481319 905 36.1600000000 0.9260978103 0.2594750669 0.9304963946 0.0092197851 0.6830030000 99378390 95654128 1786109952 -0.1967028826 0.0417799130 -0.0556297153 906 36.2000000000 0.9268485308 0.2602116822 0.9304963946 0.0092223924 0.7970820000 99547572 95654128 1788014592 -0.1900559217 0.0404731631 -0.0626746491 907 36.2400000000 0.9257275462 0.2609454373 0.9304963946 0.0092234231 0.7773140000 99549266 95654128 1784586240 -0.1853755563 0.0378654152 -0.0682192668 908 36.2800000000 0.9255028963 0.2616773288 0.9304963946 0.0092371836 0.8293530000 99550960 95654128 1785982976 -0.1824969798 0.0386839472 -0.0742745101 909 36.3200000000 0.9264732003 0.2624086774 0.9304963946 0.0092398262 0.7336820000 99551394 95654128 1788014592 -0.1736706197 0.0426256433 -0.0764397085 910 36.3600000000 0.9257488847 0.2631376227 0.9304963946 0.0092357632 0.8445630000 99553228 95654128 1784213504 -0.1663567871 0.0424891710 -0.0778781027 911 36.4000000000 0.9261860847 0.2638654475 0.9304963946 0.0092343102 0.6576460000 99553662 95654128 1785737216 -0.1612440795 0.0418142974 -0.0798222125 912 36.4400000000 0.9278464317 0.2645934969 0.9304963946 0.0092411591 0.7848480000 99556380 95654128 1787514880 -0.1538026035 0.0455282629 -0.0848640576 913 36.4800000000 0.9277396798 0.2653198344 0.9304963946 0.0092382448 0.7060980000 99726814 95654128 1784737792 -0.1477327049 0.0451769158 -0.0890933648 914 36.5200000000 0.9255442023 0.2660421806 0.9304963946 0.0092347022 0.8220190000 99727248 95654128 1786118144 -0.1441380978 0.0429737754 -0.0945046023 915 36.5600000000 0.9248665571 0.2667622072 0.9304963946 0.0092350942 0.7183160000 99728942 95654128 1788022784 -0.1363374591 0.0454626307 -0.0969684720 916 36.6000000000 0.9254525900 0.2674813015 0.9304963946 0.0092366605 0.7684940000 99730776 95654128 1784594432 -0.1287682056 0.0480217971 -0.1006987542 917 36.6400000000 0.9273123741 0.2682008556 0.9304963946 0.0092342319 0.7392280000 99731210 95654128 1786007552 -0.1215313748 0.0449454263 -0.1025468409 918 36.6800000000 0.9264950156 0.2689179516 0.9304963946 0.0092354294 0.7648470000 99732904 95654128 1788022784 -0.1162350625 0.0416044891 -0.1073321775 919 36.7200000000 0.9242407680 0.2696310341 0.9304963946 0.0092381770 0.6902990000 99734598 95654128 1784713216 -0.1106331572 0.0448432118 -0.1126830056 920 36.7600000000 0.9234412313 0.2703416974 0.9304963946 0.0092347644 0.8150680000 99735032 95654128 1785982976 -0.1063159779 0.0465177894 -0.1192293614 921 36.8000000000 0.9243499637 0.2710518041 0.9304963946 0.0092302462 0.6202590000 99736726 95654128 1787887616 -0.0954933167 0.0518075712 -0.1194997430 922 36.8400000000 0.9243932962 0.2717604174 0.9304963946 0.0092263340 0.7338480000 99740056 95654128 1784713216 -0.0858848616 0.0502658412 -0.1212571859 923 36.8800000000 0.9229248762 0.2724659043 0.9304963946 0.0092217456 0.8335670000 99909194 95654128 1785982976 -0.0803216770 0.0481440872 -0.1237314194 924 36.9200000000 0.9236868024 0.2731706889 0.9304963946 0.0092231511 0.7403350000 99910888 95654128 1787887616 -0.0704594180 0.0523497947 -0.1293411702 925 36.9600000000 0.9243795276 0.2738746984 0.9304963946 0.0092188245 0.9461600000 99912582 95654128 1784586240 -0.0605210736 0.0554163642 -0.1337427199 926 37.0000000000 0.9242148399 0.2745770096 0.9304963946 0.0092176770 0.6707660000 99913016 95654128 1785999360 -0.0466371179 0.0594812557 -0.1405598521 927 37.0400000000 0.9240532517 0.2752776312 0.9304963946 0.0092128834 0.7195840000 99914710 95654128 1787887616 -0.0351953283 0.0617675334 -0.1428206116 928 37.0800000000 0.9221622944 0.2759747052 0.9304963946 0.0092081751 0.6645880000 99915284 95654128 1784713216 -0.0291121975 0.0589767322 -0.1474709213 929 37.1200000000 0.9222453833 0.2766703679 0.9304963946 0.0092076928 0.7700940000 99918274 95654128 1786109952 -0.0202899165 0.0575023219 -0.1503128707 930 37.1600000000 0.9219369888 0.2773642030 0.9304963946 0.0092079116 0.8086300000 100088744 95654128 1787887616 -0.0106591433 0.0586602613 -0.1538287401 931 37.2000000000 0.9223324060 0.2780569723 0.9304963946 0.0092071000 0.8498840000 100089178 95654128 1784840192 -0.0039193840 0.0584268570 -0.1582253724 932 37.2400000000 0.9218048453 0.2787476889 0.9304963946 0.0092026610 0.7470120000 100090872 95654128 1786109952 0.0058890204 0.0591998287 -0.1582694352 933 37.2800000000 0.9224709272 0.2794376388 0.9304963946 0.0091980541 0.7274640000 100092566 95654128 1788014592 0.0156012606 0.0603611320 -0.1613984108 934 37.3200000000 0.9226420522 0.2801262945 0.9304963946 0.0091934780 0.8808150000 100093140 95654128 1784332288 0.0252704881 0.0623771921 -0.1654307097 935 37.3600000000 0.9218802452 0.2808126623 0.9304963946 0.0091891682 0.7002130000 100094834 95654128 1785872384 0.0351776853 0.0622540526 -0.1665565372 936 37.4000000000 0.9201940894 0.2814957621 0.9304963946 0.0091843474 0.8636360000 100096528 95654128 1787633664 0.0448643267 0.0611993112 -0.1671213657 937 37.4400000000 0.9188644290 0.2821759848 0.9304963946 0.0091795069 0.8986330000 100096962 95654128 1784459264 0.0548230186 0.0599473119 -0.1687282473 938 37.4800000000 0.9193416834 0.2828552660 0.9304963946 0.0091798368 0.6246210000 100099848 95654128 1785982976 0.0625418797 0.0594048612 -0.1721642166 939 37.5200000000 0.9182801247 0.2835319697 0.9304963946 0.0091826939 0.6783020000 100270354 95654128 1787887616 0.0717995018 0.0640964434 -0.1761638224 940 37.5600000000 0.9168519974 0.2842057145 0.9304963946 0.0091785560 0.7618370000 100270928 95654128 1784725504 0.0810610875 0.0669414401 -0.1761846542 941 37.6000000000 0.9146106839 0.2848756454 0.9304963946 0.0091747411 0.7081900000 100272622 95654128 1786109952 0.0872557312 0.0643693954 -0.1797240824 942 37.6400000000 0.9142494202 0.2855437704 0.9304963946 0.0091754226 0.8831700000 100274316 95654128 1788141568 0.0950509012 0.0621842965 -0.1832879037 943 37.6800000000 0.9114497900 0.2862075095 0.9304963946 0.0091708342 0.7524130000 100274750 95654128 1784459264 0.1032854095 0.0607192814 -0.1846393943 944 37.7200000000 0.9117677212 0.2868701792 0.9304963946 0.0091671746 0.6547650000 100276444 95654128 1785999360 0.1110983416 0.0579106882 -0.1828456521 945 37.7600000000 0.9093676209 0.2875289067 0.9304963946 0.0091642434 0.8081310000 100278138 95654128 1787887616 0.1196435839 0.0564443916 -0.1823415458 946 37.8000000000 0.9071188569 0.2881838644 0.9304963946 0.0091649734 0.8883780000 100278712 95654128 1784586240 0.1271564364 0.0549266599 -0.1850254685 947 37.8400000000 0.9062855840 0.2888365589 0.9304963946 0.0091764383 0.7227130000 100281258 95654128 1785982976 0.1351711452 0.0532105118 -0.1887105405 948 37.8800000000 0.9051010609 0.2894866269 0.9304963946 0.0091844093 0.7088650000 100450508 95654128 1787887616 0.1433903575 0.0511395521 -0.1903603375 949 37.9200000000 0.9026534557 0.2901327458 0.9304963946 0.0091916854 0.6515560000 100452202 95654128 1784713216 0.1497950852 0.0505473912 -0.1952491701 950 37.9600000000 0.8997177482 0.2907744142 0.9304963946 0.0091921857 0.7413150000 100453896 95654128 1785982976 0.1568088681 0.0498837531 -0.1986472756 951 38.0000000000 0.8972339034 0.2914121214 0.9304963946 0.0091913646 0.9350250000 100454330 95654128 1787760640 0.1634384096 0.0472490527 -0.2012314647 952 38.0400000000 0.8953070641 0.2920464648 0.9304963946 0.0091953701 0.7837890000 100456164 95654128 1784332288 0.1706509441 0.0451837368 -0.2049349546 953 38.0800000000 0.8960351944 0.2926802410 0.9304963946 0.0091978418 0.8483820000 100457858 95654128 1785856000 0.1790088266 0.0441335738 -0.2038871199 954 38.1200000000 0.8938794136 0.2933104288 0.9304963946 0.0091965283 0.7267660000 100458292 95654128 1787760640 0.1865313351 0.0423447676 -0.2061812282 955 38.1600000000 0.8943009973 0.2939397383 0.9304963946 0.0091995096 0.8416890000 100461338 95654128 1784356864 0.1939176470 0.0425778925 -0.2062935382 956 38.2000000000 0.8927180171 0.2945660754 0.9304963946 0.0091981089 0.8628050000 100631832 95654128 1785864192 0.2018937469 0.0414236970 -0.2093539387 957 38.2400000000 0.8881152868 0.2951862941 0.9304963946 0.0091945360 0.8362620000 100632266 95654128 1787768832 0.2078632414 0.0400148481 -0.2154624760 958 38.2800000000 0.8845456243 0.2958014917 0.9304963946 0.0091904950 0.7241360000 100634100 95654128 1784721408 0.2128734291 0.0382896625 -0.2212070078 959 38.3200000000 0.8832452297 0.2964140503 0.9304963946 0.0091881610 0.6926990000 100635794 95654128 1786134528 0.2207140625 0.0402572043 -0.2231065035 960 38.3600000000 0.8767019510 0.2970185169 0.9304963946 0.0091871025 0.7085830000 100636228 95654128 1787895808 0.2284438163 0.0419754237 -0.2282755822 961 38.4000000000 0.8723644614 0.2976172119 0.9304963946 0.0091983970 0.6716410000 100637922 95654128 1784594432 0.2326266915 0.0341574252 -0.2304659337 962 38.4400000000 0.8722056150 0.2982144972 0.9304963946 0.0091942714 0.8891590000 100639616 95654128 1786118144 0.2395911962 0.0307273064 -0.2298282087 963 38.4800000000 0.8738092184 0.2988122072 0.9304963946 0.0091929418 0.8904020000 100640050 95654128 1787887616 0.2463890612 0.0250628442 -0.2264192253 964 38.5200000000 0.8752926588 0.2994102159 0.9304963946 0.0091947726 0.8099300000 100641884 95654128 1784598528 0.2510900497 0.0178074799 -0.2211629748 965 38.5600000000 0.8751074076 0.3000067933 0.9304963946 0.0091913345 0.7363840000 100642318 95654128 1786109952 0.2566802502 0.0114516700 -0.2214959860 966 38.6000000000 0.8729377985 0.3005998896 0.9304963946 0.0091907558 0.6711440000 100644012 95654128 1787887616 0.2635998428 0.0076875542 -0.2238300592 967 38.6400000000 0.8711498976 0.3011899103 0.9304963946 0.0091891767 0.8408990000 100645706 95654128 1784586240 0.2672089934 0.0013583200 -0.2219571173 968 38.6800000000 0.8697373867 0.3017772527 0.9304963946 0.0091907787 0.8599140000 100646140 95654128 1786109952 0.2727535367 -0.0007497824 -0.2246627063 969 38.7200000000 0.8677269220 0.3023613081 0.9304963946 0.0091879533 0.7165880000 100647834 95654128 1787760640 0.2769436836 -0.0016445374 -0.2243454158 970 38.7600000000 0.8699952364 0.3029464977 0.9304963946 0.0091882830 0.7589780000 100649668 95654128 1784586240 0.2819085717 -0.0029151943 -0.2245088816 971 38.8000000000 0.8652469516 0.3035255919 0.9304963946 0.0091880182 0.8186720000 100651458 95654128 1785982976 0.2858868241 0.0001723627 -0.2300401628 972 38.8400000000 0.8600189686 0.3040981160 0.9304963946 0.0091858645 0.7536650000 100821936 95654128 1788141568 0.2916288972 0.0003988435 -0.2357334197 973 38.8800000000 0.8538923860 0.3046631666 0.9304963946 0.0091910417 0.8324560000 100823630 95654128 1784619008 0.2966848016 0.0019224612 -0.2414387316 974 38.9200000000 0.8516902328 0.3052247961 0.9304963946 0.0091919634 0.8662360000 100824064 95654128 1785982976 0.3022322357 0.0004711216 -0.2416130602 975 38.9600000000 0.8468271494 0.3057802856 0.9304963946 0.0091912335 0.6557240000 100825758 95654128 1787887616 0.3028765321 -0.0022058436 -0.2428742051 976 39.0000000000 0.8420442939 0.3063297365 0.9304963946 0.0091894855 0.8215810000 100827592 95654128 1784348672 0.3034256399 -0.0050994549 -0.2444483787 977 39.0400000000 0.8409028649 0.3068768942 0.9304963946 0.0091859423 0.9374390000 100828026 95654128 1785856000 0.3031920791 -0.0055880467 -0.2416094393 978 39.0800000000 0.8355275989 0.3074174369 0.9304963946 0.0091852765 0.7208560000 100829720 95654128 1787633664 0.3056756258 -0.0062008519 -0.2427916229 979 39.1200000000 0.8335090876 0.3079548134 0.9304963946 0.0092031458 0.8796440000 100831414 95654128 1784729600 0.3098488748 -0.0058690864 -0.2461785674 980 39.1600000000 0.8407080770 0.3084984392 0.9304963946 0.0092193043 0.7355040000 100831848 95654128 1786109952 0.3197111487 -0.0048016058 -0.2395796180 981 39.2000000000 0.8366013765 0.3090367704 0.9304963946 0.0092177950 0.7889530000 100833542 95654128 1788014592 0.3232826889 -0.0015013954 -0.2410244644 982 39.2400000000 0.8292567134 0.3095665260 0.9304963946 0.0092163954 0.7479050000 100834116 95654128 1784332288 0.3261073828 -0.0024094824 -0.2466831803 983 39.2800000000 0.8247296810 0.3100905984 0.9304963946 0.0092171856 0.7097880000 100835810 95654128 1785872384 0.3287734687 -0.0044300128 -0.2481315732 984 39.3200000000 0.8231820464 0.3106120328 0.9304963946 0.0092144777 0.7472340000 100837504 95654128 1787633664 0.3292016089 -0.0047677658 -0.2463527620 985 39.3600000000 0.8259891868 0.3111352583 0.9304963946 0.0092117926 0.7218940000 100837938 95654128 1784459264 0.3336381316 -0.0058337776 -0.2424227893 986 39.4000000000 0.8257275224 0.3116571572 0.9304963946 0.0092087528 0.6884940000 100839632 95654128 1785982976 0.3348726332 -0.0069324542 -0.2374209017 987 39.4400000000 0.8295320272 0.3121818531 0.9304963946 0.0092075267 0.8456650000 100841326 95654128 1787760640 0.3381704092 -0.0089658108 -0.2295307219 988 39.4800000000 0.8358328342 0.3127118642 0.9304963946 0.0092032606 0.6313610000 100841900 95654128 1784459264 0.3387222588 -0.0130013730 -0.2185142487 989 39.5200000000 0.8386049271 0.3132436064 0.9304963946 0.0092008627 0.8545420000 100843594 95654128 1785982976 0.3397403955 -0.0129572283 -0.2130907476 990 39.5600000000 0.8348798752 0.3137705117 0.9304963946 0.0092019595 0.6718490000 100845288 95654128 1787760640 0.3459397852 -0.0081653185 -0.2160258591 991 39.6000000000 0.8319835663 0.3142934311 0.9304963946 0.0091978061 0.7212980000 100845722 95654128 1784487936 0.3508858681 -0.0051174238 -0.2142429352 992 39.6400000000 0.8272081614 0.3148104822 0.9304963946 0.0091945028 0.7394480000 100847416 95654128 1785982976 0.3563620746 0.0002911324 -0.2171623409 993 39.6800000000 0.8231444955 0.3153223996 0.9304963946 0.0091910897 0.7476890000 100849110 95654128 1787895808 0.3628351986 0.0062921392 -0.2166261375 994 39.7200000000 0.8179804087 0.3158280918 0.9304963946 0.0091877363 0.7068830000 100849684 95654128 1784594432 0.3701753020 0.0109001156 -0.2198476195 995 39.7600000000 0.8161237240 0.3163309015 0.9304963946 0.0091839877 0.7364020000 100851378 95654128 1786007552 0.3767096996 0.0139513519 -0.2201430351 996 39.8000000000 0.8114659786 0.3168280251 0.9304963946 0.0091812990 0.7067260000 100853072 95654128 1787768832 0.3817746639 0.0146231139 -0.2215399295 997 39.8400000000 0.8093478084 0.3173220268 0.9304963946 0.0091776939 0.6970040000 100853506 95654128 1784594432 0.3873486221 0.0169240478 -0.2205682993 998 39.8800000000 0.8095469475 0.3178152382 0.9304963946 0.0091740191 0.7108440000 100855200 95654128 1785991168 0.3926274776 0.0169144366 -0.2180407047 999 39.9200000000 0.8130439520 0.3183109626 0.9304963946 0.0091710772 0.7895710000 100856894 95654128 1788014592 0.3991950154 0.0225271285 -0.2091514021 1000 39.9600000000 0.8104756474 0.3188031273 0.9304963946 0.0091666925 0.8796210000 100857468 95654128 1784840192 0.4065322876 0.0264176521 -0.2118731886 1001 40.0000000000 0.8089862466 0.3192928207 0.9304963946 0.0091635369 0.7289350000 100859162 95654128 1786109952 0.4146715403 0.0265764203 -0.2124626040 1002 40.0400000000 0.8083384633 0.3197808902 0.9304963946 0.0091626179 0.7082580000 100859596 95654128 1788014592 0.4207696319 0.0315719955 -0.2097333670 1003 40.0800000000 0.8058534265 0.3202655089 0.9304963946 0.0091602938 0.7848800000 100861290 95654128 1784459264 0.4270372391 0.0387895033 -0.2097485214 1004 40.1200000000 0.8006933928 0.3207440227 0.9304963946 0.0091567509 0.6842760000 100862984 95654128 1785872384 0.4337745011 0.0414303690 -0.2131561190 1005 40.1600000000 0.7981674075 0.3212190709 0.9304963946 0.0091533229 0.6879000000 100863418 95654128 1787633664 0.4421900213 0.0450419113 -0.2146478742 1006 40.2000000000 0.7941845655 0.3216892155 0.9304963946 0.0091497913 0.8040520000 100865252 95654128 1784713216 0.4491012096 0.0511066578 -0.2148114741 1007 40.2400000000 0.7899736762 0.3221542448 0.9304963946 0.0091461225 0.7212740000 100866946 95654128 1786109952 0.4567732513 0.0565463752 -0.2159506381 1008 40.2800000000 0.7865854502 0.3226149900 0.9304963946 0.0091418447 0.7161000000 100867380 95654128 1788014592 0.4634709954 0.0593600720 -0.2169832885 1009 40.3200000000 0.7803758979 0.3230686678 0.9304963946 0.0091394889 0.8462610000 100869074 95654128 1784586240 0.4708790183 0.0605505146 -0.2197833955 1010 40.3600000000 0.7737120390 0.3235148494 0.9304963946 0.0091377821 0.7544720000 100871176 95654128 1785982976 0.4787411392 0.0647820309 -0.2239138037 1011 40.4000000000 0.7674922347 0.3239539962 0.9304963946 0.0091350218 0.7569250000 101040422 95654128 1787760640 0.4849630892 0.0653075725 -0.2287144214 1012 40.4400000000 0.7656680346 0.3243904725 0.9304963946 0.0091357673 0.8063350000 101042256 95654128 1784487936 0.4905703664 0.0646015927 -0.2288604230 1013 40.4800000000 0.7627285123 0.3248231852 0.9304963946 0.0091410477 0.7277240000 101043950 95654128 1785982976 0.4956664443 0.0698068067 -0.2272768170 1014 40.5200000000 0.7575379610 0.3252499257 0.9304963946 0.0091443488 0.8541850000 101044384 95654128 1787887616 0.5013437271 0.0724986345 -0.2301483750 1015 40.5600000000 0.7539048791 0.3256722458 0.9304963946 0.0091504242 0.7176070000 101046078 95654128 1784713216 0.5075576305 0.0736900568 -0.2334097624 1016 40.6000000000 0.7500417829 0.3260899324 0.9304963946 0.0091552667 0.7644250000 101047772 95654128 1786109952 0.5138846636 0.0740164518 -0.2367144674 1017 40.6400000000 0.7445360422 0.3265013838 0.9304963946 0.0091617318 0.8868480000 101048206 95654128 1787887616 0.5181180239 0.0750232488 -0.2377560288 1018 40.6800000000 0.7407892942 0.3269083464 0.9304963946 0.0091648115 0.8109040000 101050040 95654128 1784725504 0.5243338943 0.0781629756 -0.2391068041 1019 40.7200000000 0.7368072271 0.3273106024 0.9304963946 0.0091646125 0.8595860000 101050474 95654128 1786109952 0.5290670991 0.0801624954 -0.2389737219 1020 40.7600000000 0.7280732989 0.3277035070 0.9304963946 0.0091713010 0.6181060000 101052168 95654128 1787887616 0.5358005762 0.0833301395 -0.2445587665 1021 40.8000000000 0.7207280397 0.3280884478 0.9304963946 0.0091711761 0.7210490000 101053862 95654128 1784713216 0.5430436730 0.0866252780 -0.2485890985 1022 40.8400000000 0.7184807658 0.3284704363 0.9304963946 0.0091686685 0.8602030000 101054296 95654128 1786126336 0.5481429696 0.0890910104 -0.2447642982 1023 40.8800000000 0.7056618333 0.3288391474 0.9304963946 0.0091826480 0.7628530000 101055990 95654128 1788014592 0.5526602268 0.0919311643 -0.2537009716 1024 40.9200000000 0.6971991658 0.3291988740 0.9304963946 0.0091922553 0.7430500000 101057824 95654128 1784713216 0.5597059131 0.0966553688 -0.2591831982 1025 40.9600000000 0.6924669147 0.3295532818 0.9304963946 0.0091897852 0.7554520000 101140178 95654128 1785982976 0.5675585866 0.0970460474 -0.2579583824 1026 41.0000000000 0.6849431396 0.3298996657 0.9304963946 0.0091882935 0.6853380000 101309808 95654128 1788141568 0.5729967952 0.0979265496 -0.2608531117 1027 41.0400000000 0.6758478880 0.3302365189 0.9304963946 0.0091974347 0.8116800000 101311502 95654128 1784471552 0.5774602294 0.0968161002 -0.2682484388 1028 41.0800000000 0.6617602706 0.3305590128 0.9304963946 0.0092118468 0.6719710000 101311936 95654128 1785856000 0.5842438340 0.0985077098 -0.2752512693 1029 41.1200000000 0.6424539089 0.3308621177 0.9304963946 0.0092312715 0.8506360000 101313630 95654128 1787633664 0.5896250010 0.0978664160 -0.2930798233 1030 41.1600000000 0.6367118955 0.3311590592 0.9304963946 0.0092293180 0.8528190000 101315464 95654128 1784586240 0.5976052880 0.0996326730 -0.2969737649 1031 41.2000000000 0.6296376586 0.3314485632 0.9304963946 0.0092288185 0.7773780000 101315898 95654128 1785999360 0.6046900749 0.0972157866 -0.2987447977 1032 41.2400000000 0.6180207133 0.3317262494 0.9304963946 0.0092348560 0.7681290000 101317592 95654128 1787887616 0.6106687188 0.0962907970 -0.3057618141 1033 41.2800000000 0.6046084762 0.3319904141 0.9304963946 0.0092452078 0.9059230000 101319286 95654128 1784594432 0.6167918444 0.0931777805 -0.3121872246 1034 41.3200000000 0.6006129980 0.3322502039 0.9304963946 0.0092432383 0.8964130000 101319720 95654128 1785991168 0.6265720725 0.0944297984 -0.3114366531 1035 41.3600000000 0.5948232412 0.3325038976 0.9304963946 0.0092444213 0.7102610000 101321414 95654128 1787768832 0.6325324178 0.0948632061 -0.3141353428 1036 41.4000000000 0.5928853750 0.3327552311 0.9304963946 0.0092407243 0.8169550000 101321988 95654128 1784721408 0.6386565566 0.0947389826 -0.3140377104 1037 41.4400000000 0.5941566825 0.3330073058 0.9304963946 0.0092402896 0.8048910000 101323682 95654128 1786372096 0.6455075741 0.0925062075 -0.3079853952 1038 41.4800000000 0.5865171552 0.3332515349 0.9304963946 0.0092437756 0.6565780000 101325376 95654128 1785610240 0.6529818177 0.0911100879 -0.3088778853 1039 41.5200000000 0.5741958022 0.3334834351 0.9304963946 0.0092520492 0.6827340000 101325810 95654128 1786880000 0.6612230539 0.0896279514 -0.3167240918 1040 41.5600000000 0.5696152449 0.3337104849 0.9304963946 0.0092494496 0.6060980000 101327504 95654128 1784885248 0.6681843400 0.0911911651 -0.3163938224 1041 41.6000000000 0.5636819005 0.3339313989 0.9304963946 0.0092495440 0.6448530000 101329198 95654128 1786490880 0.6752590537 0.0908381939 -0.3217438459 1042 41.6400000000 0.5615502596 0.3341498431 0.9304963946 0.0092460387 0.9391720000 101329772 95654128 1785475072 0.6827201247 0.0902320594 -0.3163824677 1043 41.6800000000 0.5475977063 0.3343544911 0.9304963946 0.0092562851 0.6791670000 101331466 95654128 1787125760 0.6905146241 0.0892275870 -0.3263327479 1044 41.7200000000 0.5344132185 0.3345461182 0.9304963946 0.0092758625 0.7249950000 101333160 95654128 1784713216 0.7056185007 0.0898864567 -0.3370305896 1045 41.7600000000 0.5283511877 0.3347315776 0.9304963946 0.0092801813 0.8075600000 101333594 95654128 1786249216 0.7126762867 0.0890106410 -0.3393558562 1046 41.8000000000 0.5224736929 0.3349110634 0.9304963946 0.0092803971 0.6945180000 101335288 95654128 1788014592 0.7179208994 0.0890223160 -0.3388650417 1047 41.8400000000 0.5220491886 0.3350898008 0.9304963946 0.0092767591 0.7723250000 101336982 95654128 1785221120 0.7241607904 0.0875069201 -0.3359812200 1048 41.8800000000 0.5163273215 0.3352627374 0.9304963946 0.0092761357 0.7110490000 101337556 95654128 1786617856 0.7337794304 0.0884877369 -0.3367452621 1049 41.9200000000 0.5098000169 0.3354291218 0.9304963946 0.0092752715 0.7326320000 101339250 95654128 1785094144 0.7424894571 0.0899244398 -0.3409488201 1050 41.9600000000 0.5068390965 0.3355923694 0.9304963946 0.0092727696 0.8085150000 101340944 95654128 1786744832 0.7474362850 0.0899519920 -0.3411892056 1051 42.0000000000 0.5041239262 0.3357527230 0.9304963946 0.0092706045 0.7496810000 101341378 95654128 1784840192 0.7548007369 0.0865181610 -0.3396365941 1052 42.0400000000 0.4999646246 0.3359088179 0.9304963946 0.0092684091 0.6893760000 101343072 95654128 1786236928 0.7616686821 0.0876896754 -0.3384873867 1053 42.0800000000 0.4974216223 0.3360622014 0.9304963946 0.0092659527 0.6655280000 101344766 95654128 1785745408 0.7660071850 0.0886246711 -0.3369267285 1054 42.1200000000 0.4934289753 0.3362115057 0.9304963946 0.0092637354 0.6823480000 101345340 95654128 1786998784 0.7694237232 0.0870193765 -0.3349533975 1055 42.1600000000 0.4888150394 0.3363561536 0.9304963946 0.0092744263 0.8129430000 101347034 95654128 1784840192 0.7824073434 0.0874994099 -0.3330575824 1056 42.2000000000 0.4832023680 0.3364952126 0.9304963946 0.0092748629 0.6374330000 101347468 95654128 1786523648 0.7883265018 0.0836279616 -0.3326729834 1057 42.2400000000 0.4803834260 0.3366313414 0.9304963946 0.0092740817 0.7304310000 101349162 95654128 1785602048 0.7961110473 0.0834747404 -0.3301394880 1058 42.2800000000 0.4764437377 0.3367634892 0.9304963946 0.0092712624 0.7910000000 101350856 95654128 1787252736 0.8024802804 0.0838243887 -0.3268629611 1059 42.3200000000 0.4742365479 0.3368933033 0.9304963946 0.0092674946 0.9076140000 101351290 95654128 1784586240 0.8049335480 0.0842747688 -0.3232480288 1060 42.3600000000 0.4750093520 0.3370236014 0.9304963946 0.0092632914 0.6594190000 101353124 95654128 1785982976 0.8108268380 0.0863132849 -0.3176414371 1061 42.4000000000 0.4740947783 0.3371527920 0.9304963946 0.0092591161 0.9154330000 101354818 95654128 1787887616 0.8134065270 0.0853253826 -0.3117493093 1062 42.4400000000 0.4736964405 0.3372813642 0.9304963946 0.0092548495 0.7306650000 101355252 95654128 1784610816 0.8184134960 0.0864636302 -0.3057577312 1063 42.4800000000 0.4696603417 0.3374058975 0.9304963946 0.0092534678 0.7535420000 101356946 95654128 1786236928 0.8219996691 0.0836501643 -0.3018957376 1064 42.5200000000 0.4680344760 0.3375286688 0.9304963946 0.0092500456 0.7260440000 101358640 95654128 1788014592 0.8276960850 0.0834511518 -0.2980813980 1065 42.5600000000 0.4655019641 0.3376488315 0.9304963946 0.0092464108 0.9593610000 101359074 95654128 1784840192 0.8338930011 0.0836777538 -0.2963177562 1066 42.6000000000 0.4617125988 0.3377652140 0.9304963946 0.0092438295 0.7711020000 101360908 95654128 1786236928 0.8362107873 0.0825902373 -0.2926832736 1067 42.6400000000 0.4611226022 0.3378808254 0.9304963946 0.0092397443 0.7885320000 101362602 95654128 1785495552 0.8404259682 0.0838131458 -0.2882615328 1068 42.6800000000 0.4594870508 0.3379946889 0.9304963946 0.0092357968 0.7636330000 101363036 95654128 1786998784 0.8444905877 0.0848362148 -0.2845491469 1069 42.7200000000 0.4567736685 0.3381058012 0.9304963946 0.0092324337 0.7404910000 101364730 95654128 1784459264 0.8520658612 0.0860620290 -0.2804080546 1070 42.7600000000 0.4574892223 0.3382173744 0.9304963946 0.0092317522 0.7972460000 101441644 95654128 1785982976 0.8584017754 0.0919565186 -0.2730859220 1071 42.8000000000 0.4527010918 0.3383242687 0.9304963946 0.0092302550 0.6833840000 101537026 95654128 1787887616 0.8650183678 0.0916600972 -0.2695416212 1072 42.8400000000 0.4520204365 0.3384303285 0.9304963946 0.0092262234 0.7049130000 101538860 95654128 1784840192 0.8671653271 0.0942071974 -0.2629468739 1073 42.8800000000 0.4510188997 0.3385352573 0.9304963946 0.0092246261 0.7263480000 101539294 95654128 1786236928 0.8667429686 0.0946007818 -0.2553082705 1074 42.9200000000 0.4492429793 0.3386383371 0.9304963946 0.0092221509 0.7478570000 101540988 95654128 1788141568 0.8692370653 0.0942977667 -0.2481295466 1075 42.9600000000 0.4483475387 0.3387403922 0.9304963946 0.0092185247 0.8318990000 101542682 95654128 1784520704 0.8729210496 0.0950843394 -0.2398330867 1076 43.0000000000 0.4479431808 0.3388418818 0.9304963946 0.0092156624 0.6608960000 101543116 95654128 1785982976 0.8764039874 0.0967513844 -0.2340166718 1077 43.0400000000 0.4474312365 0.3389427075 0.9304963946 0.0092131648 0.7542340000 101544810 95654128 1787887616 0.8796897531 0.0978489220 -0.2276434153 1078 43.0800000000 0.4444334209 0.3390405653 0.9304963946 0.0092118195 0.8715450000 101546644 95654128 1784975360 0.8823437095 0.0962899774 -0.2241572738 1079 43.1200000000 0.4433282018 0.3391372175 0.9304963946 0.0092093299 0.6547860000 101547078 95654128 1786261504 0.8847693205 0.0957717448 -0.2182676196 1080 43.1600000000 0.4402287602 0.3392308207 0.9304963946 0.0092069911 0.8328020000 101548772 95654128 1788022784 0.8873695135 0.0935624316 -0.2097632289 1081 43.2000000000 0.4400523603 0.3393240877 0.9304963946 0.0092039584 0.8113690000 101550466 95654128 1784610816 0.8878530264 0.0937467515 -0.2013729662 1082 43.2400000000 0.4379053414 0.3394151979 0.9304963946 0.0092005345 0.7418870000 101550900 95654128 1785991168 0.8896855116 0.0936995223 -0.1954288185 1083 43.2800000000 0.4348590970 0.3395033271 0.9304963946 0.0091974966 0.7915230000 101552594 95654128 1787768832 0.8928651810 0.0906371847 -0.1866103262 1084 43.3200000000 0.4327595234 0.3395893568 0.9304963946 0.0091941037 0.7408310000 101554428 95654128 1784348672 0.8944177628 0.0890665501 -0.1770905852 1085 43.3600000000 0.4336230159 0.3396760237 0.9304963946 0.0091925790 0.7484080000 101554862 95654128 1785864192 0.8959968686 0.0908417106 -0.1693639755 1086 43.4000000000 0.4344850481 0.3397633249 0.9304963946 0.0091885464 0.8452900000 101556556 95654128 1787641856 0.8957366347 0.0914453194 -0.1602662057 1087 43.4400000000 0.4340846539 0.3398500970 0.9304963946 0.0091843943 0.6250030000 101558250 95654128 1784467456 0.8962507844 0.0919526592 -0.1513050348 1088 43.4800000000 0.4336333871 0.3399362949 0.9304963946 0.0091806632 0.6700300000 101558684 95654128 1786007552 0.8961490393 0.0924324095 -0.1449551433 1089 43.5200000000 0.4324277937 0.3400212274 0.9304963946 0.0091776425 0.7256100000 101635298 95654128 1787895808 0.8989200592 0.0923619196 -0.1387934536 1090 43.5600000000 0.4309154749 0.3401046166 0.9304963946 0.0091738765 0.7157040000 101731204 95654128 1784840192 0.8999775052 0.0909629092 -0.1293505132 1091 43.6000000000 0.4283794165 0.3401855284 0.9304963946 0.0091726200 0.8050450000 101732898 95654128 1786236928 0.9000691175 0.0855965018 -0.1202803478 1092 43.6400000000 0.4282102287 0.3402661371 0.9304963946 0.0091694868 0.5975130000 101734592 95654128 1788141568 0.8997303843 0.0845622420 -0.1112419590 1093 43.6800000000 0.4253107607 0.3403439456 0.9304963946 0.0091674589 0.5420500000 101735026 95654128 1784459264 0.9014943242 0.0812452286 -0.1032866389 1094 43.7200000000 0.4247369766 0.3404210873 0.9304963946 0.0091638582 0.6942630000 101736720 95654128 1785856000 0.9032382369 0.0819501430 -0.0963788927 1095 43.7600000000 0.4246845245 0.3404980402 0.9304963946 0.0091601793 0.6911190000 101738414 95654128 1787760640 0.9015633464 0.0834298804 -0.0899164900 1096 43.8000000000 0.4241504669 0.3405743654 0.9304963946 0.0091561397 0.6859840000 101738988 95654128 1784840192 0.9016722441 0.0822340399 -0.0815439075 1097 43.8400000000 0.4232254922 0.3406497083 0.9304963946 0.0091523263 0.6307700000 101740682 95654128 1786236928 0.9021112919 0.0814694390 -0.0709093735 1098 43.8800000000 0.4225607216 0.3407243085 0.9304963946 0.0091529076 0.6815150000 101742376 95654128 1788141568 0.9022639394 0.0797394738 -0.0594502538 1099 43.9200000000 0.4226989746 0.3407988987 0.9304963946 0.0091510404 0.6725910000 101742810 95654128 1784586240 0.9019756317 0.0815343931 -0.0517731532 1100 43.9600000000 0.4218380749 0.3408725707 0.9304963946 0.0091474327 0.7079770000 101744504 95654128 1786109952 0.9012043476 0.0800366849 -0.0438275225 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 04:55:07 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 nan 0.2101370000 88633275 95654128 1758015488 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644419193 0.0528085120 0.0567136779 0.0606188439 0.0351166949 1.3677200000 89486106 95654128 1760280576 -0.0045660431 0.0008364068 0.0132681336 3 1305031229.5966169834 0.0653344542 0.0595872700 0.0653344542 0.0422147627 1.0928950000 89605776 95654128 1762566144 -0.0037293795 -0.0090829935 0.0052294414 4 1305031229.6287899017 0.0605313666 0.0598232942 0.0653344542 0.0347635937 1.0849460000 89661054 95654128 1764343808 -0.0075374451 -0.0019470393 0.0114536379 5 1305031229.6646571159 0.0655541942 0.0609694742 0.0655541942 0.0318416417 1.1328270000 89780636 95654128 1766375424 -0.0100531848 -0.0102961808 0.0129517615 6 1305031229.6968429089 0.0629825667 0.0613049896 0.0655541942 0.0286140083 0.9499340000 89836858 95654128 1767899136 -0.0095715849 -0.0070598479 0.0161222797 7 1305031229.7290771008 0.0639055222 0.0616764942 0.0655541942 0.0262459838 1.0681830000 89954636 95654128 1769615360 -0.0195715427 -0.0023566554 0.0180617385 8 1305031229.7648689747 0.0690929294 0.0626035486 0.0690929294 0.0248482780 1.0598240000 90011918 95654128 1771388928 -0.0228811763 -0.0053652218 0.0157319345 9 1305031229.7969229221 0.0686617270 0.0632766796 0.0690929294 0.0235555459 1.1105290000 90131556 95654128 1773420544 -0.0269624982 -0.0028250718 0.0179924779 10 1305031229.8256299496 0.0720666647 0.0641556781 0.0720666647 0.0228895336 1.0867730000 90133750 95654128 1774944256 -0.0335117094 -0.0026049905 0.0174515806 11 1305031229.8630619049 0.0723259524 0.0648984303 0.0723259524 0.0228362832 1.2691890000 90190292 95654128 1776689152 -0.0362684801 -0.0029534132 0.0189602431 12 1305031229.8969380856 0.0745052770 0.0656990008 0.0745052770 0.0229815120 1.0477420000 90308598 95654128 1778466816 -0.0411175080 -0.0009879270 0.0179410093 13 1305031229.9262549877 0.0786310211 0.0666937716 0.0786310211 0.0224382336 0.9137120000 90309512 95654128 1780371456 -0.0471127033 -0.0015311420 0.0161738712 14 1305031229.9662408829 0.0816257969 0.0677603449 0.0816257969 0.0220467835 1.1448220000 90365742 95654128 1781895168 -0.0512065589 -0.0011283467 0.0140732732 15 1305031229.9979310036 0.0812642351 0.0686606042 0.0816257969 0.0220406709 1.0344650000 90537960 95654128 1783926784 -0.0531621389 -0.0002157573 0.0143236127 16 1305031230.0300021172 0.0822144747 0.0695077211 0.0822144747 0.0214926156 0.9677600000 90655094 95654128 1785704448 -0.0565038547 -0.0007800165 0.0144081181 17 1305031230.0656960011 0.0837038755 0.0703427890 0.0837038755 0.0211028478 0.9494170000 90715784 95654128 1787457536 -0.0601958260 -0.0035053822 0.0143857161 18 1305031230.0982739925 0.0824564770 0.0710157717 0.0837038755 0.0208477423 0.8411220000 90835566 95654128 1784918016 -0.0612126105 0.0000442653 0.0138134332 19 1305031230.1299350262 0.0833068267 0.0716626693 0.0837038755 0.0204007233 0.9969780000 90836512 95654128 1786187776 -0.0634977818 0.0002402188 0.0130315116 20 1305031230.1657800674 0.0845989510 0.0723094834 0.0845989510 0.0200143643 1.9331530000 90894622 95654128 1788067840 -0.0671889633 -0.0001413946 0.0118483091 21 1305031230.1977820396 0.0854547247 0.0729354473 0.0854547247 0.0198150724 1.9340360000 91011844 95654128 1785020416 -0.0702919215 0.0005167575 0.0104536274 22 1305031230.2298529148 0.0891829506 0.0736739702 0.0891829506 0.0197109099 1.9853200000 91068454 95654128 1786290176 -0.0744223446 -0.0005317536 0.0076565035 23 1305031230.2655899525 0.0912228078 0.0744369631 0.0912228078 0.0193676495 1.6743260000 91185752 95654128 1785622528 -0.0777258351 0.0003231794 0.0050167311 24 1305031230.2979929447 0.0897726342 0.0750759494 0.0912228078 0.0192011183 1.7307920000 91243350 95654128 1786892288 -0.0796769634 -0.0008020970 0.0064094481 25 1305031230.3351120949 0.0914420038 0.0757305916 0.0914420038 0.0188866417 2.0628990000 91414372 95654128 1784860672 -0.0829476565 -0.0027053040 0.0044681826 26 1305031230.3656799793 0.0944601297 0.0764509584 0.0944601297 0.0185265076 2.0923600000 91586762 95654128 1786241024 -0.0856458694 0.0005981484 0.0011642340 27 1305031230.3973290920 0.0958335176 0.0771688310 0.0958335176 0.0182846440 2.0891400000 91704136 95654128 1784844288 -0.0892046914 -0.0000825133 0.0004138118 28 1305031230.4368140697 0.1018119678 0.0780489430 0.1018119678 0.0188747680 2.1615090000 91760286 95654128 1785978880 -0.0948578268 0.0004681463 -0.0054511409 29 1305031230.4653120041 0.1117228568 0.0792101124 0.1117228568 0.0186230610 1.6514060000 91932600 95654128 1787883520 -0.1035154238 -0.0006473088 -0.0141874067 30 1305031230.4972999096 0.1186211854 0.0805238149 0.1186211854 0.0184447032 1.7286860000 92105998 95654128 1784709120 -0.1108283177 0.0012860320 -0.0204595309 31 1305031230.5301918983 0.1230285540 0.0818949355 0.1230285540 0.0184602520 1.2867150000 92277972 95654128 1786105856 -0.1180432290 -0.0017868303 -0.0238505341 32 1305031230.5661149025 0.1258053482 0.0832671359 0.1258053482 0.0186997887 1.6095490000 92450906 95654128 1785470976 -0.1242827624 0.0008079842 -0.0274419505 33 1305031230.5988430977 0.1277143508 0.0846140212 0.1277143508 0.0187331548 1.9633510000 92628904 95654128 1786867712 -0.1302934140 0.0002448129 -0.0293852724 34 1305031230.6319139004 0.1306569427 0.0859682248 0.1306569427 0.0187130821 1.4369430000 92805258 95654128 1784582144 -0.1345971972 0.0017237253 -0.0332578234 35 1305031230.6660470963 0.1278894395 0.0871659738 0.1306569427 0.0185342468 2.1668030000 92977828 95654128 1785978880 -0.1380562931 0.0068622762 -0.0324770063 36 1305031230.6979451180 0.1268444210 0.0882681529 0.1306569427 0.0184823646 1.5790610000 93149898 95654128 1785597952 -0.1426082253 0.0059367288 -0.0310072266 37 1305031230.7336409092 0.1315406859 0.0894376808 0.1315406859 0.0185962836 1.5247320000 93320952 95654128 1786994688 -0.1466636807 0.0060537765 -0.0372386165 38 1305031230.7659239769 0.1358645111 0.0906594395 0.1358645111 0.0184818822 2.0251850000 93493246 95654128 1784709120 -0.1518318057 0.0049030492 -0.0421181396 39 1305031230.7973229885 0.1391843706 0.0919036685 0.1391843706 0.0184691785 1.8770270000 93665528 95654128 1785978880 -0.1571900100 0.0002646493 -0.0450015366 40 1305031230.8317570686 0.1464731097 0.0932679045 0.1464731097 0.0182486244 1.7356080000 93836290 95654128 1785409536 -0.1609716266 0.0021301636 -0.0544386096 41 1305031230.8655419350 0.1492948234 0.0946344147 0.1492948234 0.0183607703 1.8037710000 94008136 95654128 1784328192 -0.1660008729 0.0003458158 -0.0589007735 42 1305031230.8973939419 0.1512399763 0.0959821662 0.1512399763 0.0184708492 1.8504490000 94179978 95654128 1785724928 -0.1693658084 0.0024697934 -0.0622303300 43 1305031230.9373099804 0.1533282399 0.0973157958 0.1533282399 0.0182800153 1.4681520000 94350528 95654128 1787883520 -0.1710636318 0.0065937913 -0.0667615458 44 1305031230.9650349617 0.1547103822 0.0986202182 0.1547103822 0.0183646810 1.4765260000 94522114 95654128 1784717312 -0.1688418984 0.0088666622 -0.0704814196 45 1305031230.9971239567 0.1565095186 0.0999066471 0.1565095186 0.0182187795 0.8334150000 94637356 95654128 1786114048 -0.1676187664 0.0109955380 -0.0733624175 46 1305031231.0367500782 0.1556433439 0.1011183144 0.1565095186 0.0181873069 0.9275280000 94638398 95654128 1788018688 -0.1715002358 0.0152581492 -0.0706798881 47 1305031231.0644741058 0.1586649418 0.1023427108 0.1586649418 0.0180224475 0.9463420000 94640492 95654128 1784336384 -0.1711497158 0.0154449828 -0.0734629855 48 1305031231.0967879295 0.1593942195 0.1035312839 0.1593942195 0.0179128163 1.1174960000 94642714 95654128 1785606144 -0.1675540805 0.0166811161 -0.0746357366 49 1305031231.1347110271 0.1619438082 0.1047233762 0.1619438082 0.0177788304 2.1685990000 94643692 95654128 1787502592 -0.1726409644 0.0167687312 -0.0737293884 50 1305031231.1652760506 0.1695353687 0.1060196161 0.1695353687 0.0176648170 1.5344780000 94645882 95654128 1784836096 -0.1700363010 0.0150040546 -0.0812862888 51 1305031231.1977710724 0.1701277941 0.1072766392 0.1701277941 0.0175731696 1.7871020000 94648104 95654128 1786105856 -0.1638083905 0.0235045180 -0.0819991082 52 1305031231.2344679832 0.1457930803 0.1080173399 0.1701277941 0.0178868596 1.7915440000 94705770 95654128 1788010496 -0.1486784816 0.0323205963 -0.0570255667 53 1305031231.2656350136 0.1610973924 0.1090188504 0.1701277941 0.0192322228 1.5950660000 94877904 95654128 1784836096 -0.1301882714 0.0302581899 -0.0738606527 54 1305031231.2978610992 0.1715396047 0.1101766421 0.1715396047 0.0196935977 1.8156240000 95050090 95654128 1786105856 -0.1234249622 0.0291872583 -0.0819752961 55 1305031231.3351519108 0.1683034301 0.1112334928 0.1715396047 0.0196576323 1.7331570000 95221560 95654128 1785360384 -0.1168022305 0.0300113112 -0.0751884356 56 1305031231.3650770187 0.1617961526 0.1121363974 0.1715396047 0.0196998395 1.8304620000 95393702 95654128 1786867712 -0.1129933745 0.0284593534 -0.0661885962 57 1305031231.3973300457 0.1593515873 0.1129647341 0.1715396047 0.0197727826 1.9392190000 95565968 95654128 1784455168 -0.1088402271 0.0288653933 -0.0613923222 58 1305031231.4368579388 0.1572090536 0.1137275672 0.1715396047 0.0196808668 1.7465580000 95737298 95654128 1785851904 -0.1059179157 0.0341411978 -0.0565204434 59 1305031231.4649889469 0.1532271206 0.1143970512 0.1715396047 0.0195990163 1.6470890000 95909520 95654128 1788010496 -0.1029215306 0.0351640061 -0.0506479666 60 1305031231.4992439747 0.1502649784 0.1149948499 0.1715396047 0.0195271673 1.6455070000 96082254 95654128 1784836096 -0.0990809724 0.0336186960 -0.0461839475 61 1305031231.5331959724 0.1481448859 0.1155382932 0.1715396047 0.0195270332 1.7230750000 96253748 95654128 1786359808 -0.0958862081 0.0352491401 -0.0426399633 62 1305031231.5650680065 0.1462782621 0.1160340991 0.1715396047 0.0194578469 1.7088610000 96427238 95654128 1784709120 -0.0910327211 0.0373371542 -0.0397875309 63 1305031231.6013169289 0.1419466436 0.1164454093 0.1715396047 0.0193471739 1.2042220000 96599896 95654128 1785978880 -0.0894798264 0.0379181132 -0.0343280584 64 1305031231.6331589222 0.1389209032 0.1167965889 0.1715396047 0.0192537312 1.6023600000 96771818 95654128 1785597952 -0.0865125284 0.0389410295 -0.0300927516 65 1305031231.6650550365 0.1357218474 0.1170877468 0.1715396047 0.0191724708 2.3232620000 96955324 95654128 1787129856 -0.0817086548 0.0404753536 -0.0268504396 66 1305031231.7035079002 0.1334074587 0.1173350151 0.1715396047 0.0191902589 1.8396230000 97138874 95654128 1784590336 -0.0797113255 0.0441732481 -0.0236628763 67 1305031231.7339379787 0.1279755086 0.1174938285 0.1715396047 0.0192650174 1.7636510000 97310788 95654128 1785987072 -0.0757125244 0.0481069311 -0.0180953443 68 1305031231.7655088902 0.1203847677 0.1175363423 0.1715396047 0.0192468105 1.7993520000 97483818 95654128 1785597952 -0.0709386095 0.0524813868 -0.0103125600 69 1305031231.8011910915 0.1163078099 0.1175185374 0.1715396047 0.0192969920 2.3309230000 97656508 95654128 1786867712 -0.0661133528 0.0539115965 -0.0060985629 70 1305031231.8332920074 0.1118587852 0.1174376838 0.1715396047 0.0193715073 1.6221330000 97828566 95654128 1784836096 -0.0631242618 0.0540736020 -0.0012728921 71 1305031231.8649590015 0.1086483970 0.1173138911 0.1715396047 0.0195398667 2.6868140000 98001796 95654128 1786105856 -0.0591399968 0.0544137545 0.0015559301 72 1305031231.9012699127 0.1102632582 0.1172159656 0.1715396047 0.0199083110 2.2795960000 98174942 95654128 1785597952 -0.0585066825 0.0549613573 -0.0001924512 73 1305031231.9330461025 0.1088266075 0.1171010429 0.1715396047 0.0199554378 1.7234170000 98284432 95654128 1786994688 -0.0571282171 0.0530183651 0.0009608408 74 1305031231.9650299549 0.1086642072 0.1169870316 0.1715396047 0.0198966297 1.8315760000 98348726 95654128 1784709120 -0.0533524752 0.0532820225 0.0000733207 75 1305031232.0007200241 0.1095459834 0.1168878176 0.1715396047 0.0199510615 1.9600650000 98459584 95654128 1786105856 -0.0541883036 0.0533728264 -0.0013034568 76 1305031232.0332028866 0.1065966338 0.1167524073 0.1715396047 0.0200027781 2.5472230000 98460578 95654128 1785597952 -0.0491630211 0.0536634214 0.0001592548 77 1305031232.0651450157 0.1039004475 0.1165854987 0.1715396047 0.0200348111 1.8823750000 98524520 95654128 1786859520 -0.0443198867 0.0552695431 0.0012839813 78 1305031232.1007990837 0.1024619937 0.1164044282 0.1715396047 0.0200314316 1.5293320000 98635442 95654128 1784700928 -0.0437128842 0.0548684075 0.0018376138 79 1305031232.1328380108 0.1011767462 0.1162116727 0.1715396047 0.0199980909 1.3696040000 98698948 95654128 1785970688 -0.0420698412 0.0540702492 0.0019175053 80 1305031232.1650519371 0.1008340940 0.1160194530 0.1715396047 0.0199010088 1.9450900000 98809818 95654128 1788002304 -0.0390673615 0.0554430559 0.0008620172 81 1305031232.1992239952 0.1010526791 0.1158346780 0.1715396047 0.0199004289 1.4443380000 98812056 95654128 1784209408 -0.0343577676 0.0579247102 -0.0007830809 82 1305031232.2364680767 0.0980751067 0.1156180978 0.1715396047 0.0197935786 1.5019390000 98874670 95654128 1785589760 -0.0322371945 0.0574996807 0.0005256028 83 1305031232.2626979351 0.0984128043 0.1154108052 0.1715396047 0.0200254413 1.7516720000 98985540 95654128 1787494400 -0.0286930893 0.0582635775 -0.0009779134 84 1305031232.2980248928 0.0979624316 0.1152030864 0.1715396047 0.0201013969 1.9027590000 99049346 95654128 1784455168 -0.0274397656 0.0610408634 -0.0018324364 85 1305031232.3321430683 0.0974227414 0.1149939059 0.1715396047 0.0201207935 2.3599420000 99159128 95654128 1785978880 -0.0291260723 0.0607940704 -0.0017170860 86 1305031232.3647489548 0.0990681201 0.1148087223 0.1715396047 0.0200953488 1.5679000000 99223130 95654128 1787883520 -0.0286519229 0.0648450926 -0.0040917075 87 1305031232.4008779526 0.0999510437 0.1146379444 0.1715396047 0.0200468725 1.9088660000 99334264 95654128 1784709120 -0.0285184085 0.0665033758 -0.0053367238 88 1305031232.4331440926 0.0994799733 0.1144656947 0.1715396047 0.0199489841 1.7735510000 99335242 95654128 1786097664 -0.0283130184 0.0676463991 -0.0055848830 89 1305031232.4647209644 0.0989538953 0.1142914049 0.1715396047 0.0198471360 1.8018010000 99337384 95654128 1787875328 -0.0275794547 0.0673959479 -0.0058996603 90 1305031232.5015261173 0.0994754657 0.1141267833 0.1715396047 0.0197469825 1.5649500000 99339670 95654128 1784844288 -0.0261017457 0.0658036321 -0.0081109181 91 1305031232.5324640274 0.0997400880 0.1139686878 0.1715396047 0.0196629032 1.9562570000 99402420 95654128 1786224640 -0.0240720212 0.0657109842 -0.0093777711 92 1305031232.5647449493 0.0989392102 0.1138053239 0.1715396047 0.0195666540 1.9224040000 99513546 95654128 1785479168 -0.0245399363 0.0644037202 -0.0100983186 93 1305031232.6003499031 0.1004988551 0.1136622436 0.1715396047 0.0194651440 2.0121690000 99515784 95654128 1786859520 -0.0205360688 0.0637579933 -0.0133584719 94 1305031232.6294269562 0.1007989421 0.1135253999 0.1715396047 0.0194295350 2.2769180000 99578490 95654128 1784700928 -0.0171833560 0.0633764267 -0.0156365447 95 1305031232.6647078991 0.0982106701 0.1133641923 0.1715396047 0.0193407236 2.0113590000 99689808 95654128 1785970688 -0.0204279404 0.0620859303 -0.0147846583 96 1305031232.7005090714 0.1013344824 0.1132388828 0.1715396047 0.0192710411 2.3408900000 99692046 95654128 1787875328 -0.0178441592 0.0634330809 -0.0186394695 97 1305031232.7327980995 0.1043197885 0.1131469334 0.1715396047 0.0192405520 1.8877990000 99754532 95654128 1784700928 -0.0150163863 0.0640219226 -0.0230981428 98 1305031232.7684600353 0.1027825475 0.1130411743 0.1715396047 0.0191726175 2.0502280000 99865882 95654128 1786097664 -0.0162416007 0.0641591772 -0.0233242474 99 1305031232.8045380116 0.1020150259 0.1129297991 0.1715396047 0.0191505058 1.9735230000 99929656 95654128 1788002304 -0.0176065452 0.0642771572 -0.0247792993 100 1305031232.8346450329 0.1063062549 0.1128635636 0.1715396047 0.0191337666 1.9123090000 100039678 95654128 1784700928 -0.0159323290 0.0661784858 -0.0304961298 101 1305031232.8685569763 0.1065543368 0.1128010960 0.1715396047 0.0191442630 1.7942040000 100103580 95654128 1786232832 -0.0168200582 0.0668395385 -0.0323954709 102 1305031232.9041829109 0.1070480198 0.1127446933 0.1715396047 0.0190840069 2.2009100000 100214970 95654128 1785409536 -0.0158714466 0.0719759315 -0.0335810408 103 1305031232.9330000877 0.1092154086 0.1127104284 0.1715396047 0.0190111418 2.3211060000 100215852 95654128 1784328192 -0.0142703746 0.0756820738 -0.0353984609 104 1305031232.9683640003 0.1099597365 0.1126839795 0.1715396047 0.0189207136 2.2170190000 100218122 95654128 1785597952 -0.0127497632 0.0766066015 -0.0377504453 105 1305031233.0011510849 0.1167814508 0.1127230030 0.1715396047 0.0188480621 1.2908950000 100220312 95654128 1787629568 -0.0108378110 0.0843126625 -0.0425497852 106 1305031233.0330219269 0.1153666228 0.1127479428 0.1715396047 0.0187932439 1.8486510000 100221274 95654128 1784700928 -0.0102863740 0.0912879407 -0.0378595442 107 1305031233.0688428879 0.1183209196 0.1128000267 0.1715396047 0.0188014689 2.0024620000 100223480 95654128 1786097664 -0.0105945943 0.0922202691 -0.0409680344 108 1305031233.1004469395 0.1221245080 0.1128863645 0.1715396047 0.0187862248 2.3302890000 100225686 95654128 1788002304 -0.0154568460 0.0990369394 -0.0408092663 109 1305031233.1328918934 0.1240974069 0.1129892181 0.1715396047 0.0197967990 2.1348010000 100226632 95654128 1784827904 -0.0115619916 0.0890177116 -0.0478681214 110 1305031233.1684799194 0.1294448972 0.1131388152 0.1715396047 0.0198788467 0.9341850000 100228902 95654128 1786109952 -0.0079262024 0.0862112716 -0.0532983020 111 1305031233.2006340027 0.1288030893 0.1132799348 0.1715396047 0.0199122492 1.1428520000 100231108 95654128 1787760640 -0.0102612823 0.0860926881 -0.0512829535 112 1305031233.2330091000 0.1231344491 0.1133679215 0.1715396047 0.0199012457 1.0061680000 100232022 95654128 1784586240 -0.0189615637 0.0927428454 -0.0410672575 113 1305031233.2684679031 0.1228388846 0.1134517353 0.1715396047 0.0201279188 1.0042380000 100234324 95654128 1785982976 -0.0273694731 0.0979492739 -0.0350892730 114 1305031233.3003950119 0.1258884817 0.1135608296 0.1715396047 0.0200533707 0.9545930000 100236562 95654128 1787887616 -0.0353918150 0.0996954590 -0.0351591893 115 1305031233.3325300217 0.1192537621 0.1136103334 0.1715396047 0.0204812937 1.0919980000 100237572 95654128 1784713216 -0.0440738983 0.0999011472 -0.0243825912 116 1305031233.3686299324 0.1232464239 0.1136934031 0.1715396047 0.0206709514 1.1198370000 100300934 95654128 1786109952 -0.0455245413 0.0923766196 -0.0289115552 117 1305031233.4008929729 0.1255784333 0.1137949846 0.1715396047 0.0207036509 2.4083800000 100412676 95654128 1785475072 -0.0557695255 0.0946314558 -0.0276977140 118 1305031233.4330079556 0.1300740838 0.1139329430 0.1715396047 0.0209405813 1.8910140000 100475098 95654128 1786871808 -0.0728250891 0.0937594399 -0.0288134534 119 1305031233.4687869549 0.1325266510 0.1140891927 0.1715396047 0.0210168776 2.3207820000 100586836 95654128 1784713216 -0.0707717016 0.0924899876 -0.0302397646 120 1305031233.5007359982 0.1318065673 0.1142368375 0.1715396047 0.0209827526 2.3295200000 100589090 95654128 1786109952 -0.0716819093 0.0938214511 -0.0276330765 121 1305031233.5341610909 0.1364278495 0.1144202343 0.1715396047 0.0210644381 2.0772430000 100651244 95654128 1788039168 -0.0800459534 0.0925290436 -0.0302281827 122 1305031233.5697269440 0.1421337426 0.1146473942 0.1715396047 0.0210011298 1.8507520000 100763078 95654128 1784483840 -0.0887676030 0.0936872587 -0.0333008654 123 1305031233.6012749672 0.1461796314 0.1149037538 0.1715396047 0.0209427837 2.2214730000 100765284 95654128 1785864192 -0.0999153256 0.0926847830 -0.0345700867 124 1305031233.6330409050 0.1509402990 0.1151943711 0.1715396047 0.0209620212 2.0422850000 100766262 95654128 1787760640 -0.1046281829 0.0935796499 -0.0383576751 125 1305031233.6717829704 0.1553527415 0.1155156381 0.1715396047 0.0208782486 1.7682640000 100829776 95654128 1784713216 -0.1075358465 0.0965030342 -0.0416449010 126 1305031233.7022960186 0.1510311514 0.1157975072 0.1715396047 0.0210170619 2.3170900000 100941646 95654128 1785982976 -0.1066084430 0.0967531726 -0.0372358114 127 1305031233.7312009335 0.1469303668 0.1160426479 0.1715396047 0.0211074271 1.7544120000 100942528 95654128 1787887616 -0.1002830565 0.1031712070 -0.0319491699 128 1305031233.7691600323 0.1438472569 0.1162598714 0.1715396047 0.0211256126 2.2109130000 100944798 95654128 1784713216 -0.0955173075 0.1067553982 -0.0281308405 129 1305031233.7997679710 0.1440102607 0.1164749907 0.1715396047 0.0210917313 1.4025960000 100957180 95654128 1785982976 -0.0956205726 0.1057858095 -0.0284368359 130 1305031233.8338310719 0.1434038579 0.1166821358 0.1715396047 0.0210688939 1.6778810000 100979150 95654128 1788014592 -0.0991187990 0.0982112214 -0.0302435383 131 1305031233.8655700684 0.1483075917 0.1169235515 0.1715396047 0.0210370557 1.7859760000 100981356 95654128 1784713216 -0.1002822369 0.0988699421 -0.0349166505 132 1305031233.8986968994 0.1478543878 0.1171578760 0.1715396047 0.0209638370 2.3574020000 100983610 95654128 1785982976 -0.1006583497 0.0982745960 -0.0345052816 133 1305031233.9320030212 0.1416108012 0.1173417326 0.1715396047 0.0209314957 1.8232510000 100984524 95654128 1788014592 -0.0975756794 0.0955063403 -0.0293043368 134 1305031233.9681589603 0.1383773386 0.1174987147 0.1715396047 0.0208694011 2.3122320000 100986746 95654128 1784729600 -0.0943976641 0.0955277085 -0.0264786519 135 1305031233.9989380836 0.1322756559 0.1176081736 0.1715396047 0.0208200481 2.1596950000 101060548 95654128 1786109952 -0.0908833817 0.0894393995 -0.0224964600 136 1305031234.0370678902 0.1341145933 0.1177295443 0.1715396047 0.0207554080 1.6972100000 101161202 95654128 1785475072 -0.0887138322 0.0937467068 -0.0232678000 137 1305031234.0687561035 0.1331050396 0.1178417742 0.1715396047 0.0206862384 1.0479780000 101163360 95654128 1786871808 -0.0878221616 0.0931186378 -0.0225396398 138 1305031234.0997409821 0.1349095851 0.1179654540 0.1715396047 0.0206261444 1.0697340000 101165534 95654128 1784471552 -0.0882205367 0.0917522460 -0.0245002359 139 1305031234.1350688934 0.1348198652 0.1180867087 0.1715396047 0.0205619952 1.0850000000 101166512 95654128 1785856000 -0.0873219073 0.0897487029 -0.0245007016 140 1305031234.1659009457 0.1378046870 0.1182275514 0.1715396047 0.0205657339 0.9879440000 101239898 95654128 1787760640 -0.0870246962 0.0951080695 -0.0253662635 141 1305031234.2010040283 0.1352502406 0.1183482797 0.1715396047 0.0205522137 0.9359560000 101341868 95654128 1784848384 -0.0865257680 0.0860554278 -0.0247636866 142 1305031234.2385749817 0.1361314058 0.1184735130 0.1715396047 0.0205091123 1.1149100000 101413738 95654128 1786118144 -0.0861201137 0.0901398286 -0.0235344879 143 1305031234.2655100822 0.1378420442 0.1186089573 0.1715396047 0.0204488927 0.8451710000 101515576 95654128 1785483264 -0.0865416452 0.0943304077 -0.0225194972 144 1305031234.3024549484 0.1341273934 0.1187167242 0.1715396047 0.0203832100 0.8663260000 101517910 95654128 1786880000 -0.0850860253 0.0873973072 -0.0205979347 145 1305031234.3384580612 0.1338936687 0.1188213928 0.1715396047 0.0203209521 1.0493070000 101589664 95654128 1784594432 -0.0847834572 0.0858608037 -0.0197309889 146 1305031234.3661808968 0.1347468197 0.1189304710 0.1715396047 0.0202942881 2.3392880000 101691630 95654128 1786118144 -0.0851090923 0.0884179994 -0.0193473771 147 1305031234.4000349045 0.1334160864 0.1190290126 0.1715396047 0.0202279625 1.8511520000 101765344 95654128 1788022784 -0.0846568123 0.0858284459 -0.0182636939 148 1305031234.4367709160 0.1292299032 0.1190979376 0.1715396047 0.0202128886 1.7766850000 101866270 95654128 1784713216 -0.0819411799 0.0781267881 -0.0166092720 149 1305031234.4676060677 0.1308080107 0.1191765287 0.1715396047 0.0201987664 2.4136490000 101939580 95654128 1786109952 -0.0819142610 0.0817057192 -0.0169318654 150 1305031234.4977810383 0.1289566457 0.1192417295 0.1715396047 0.0201373230 1.6773410000 102041682 95654128 1785602048 -0.0804303214 0.0795544460 -0.0160952322 151 1305031234.5376710892 0.1291801333 0.1193075467 0.1715396047 0.0202101295 2.4261900000 102113940 95654128 1786871808 -0.0776297823 0.0682750270 -0.0207616240 152 1305031234.5690369606 0.1317738593 0.1193895619 0.1715396047 0.0203496080 1.6979790000 102286338 95654128 1784840192 -0.0798746496 0.0751515999 -0.0219343901 153 1305031234.5982480049 0.1310866028 0.1194660132 0.1715396047 0.0203152009 2.1563990000 102388540 95654128 1786109952 -0.0782094598 0.0715596676 -0.0235258359 154 1305031234.6336491108 0.1306439489 0.1195385972 0.1715396047 0.0202613403 1.8872920000 102459534 95654128 1785413632 -0.0769060850 0.0710007176 -0.0248482395 155 1305031234.6658589840 0.1312409788 0.1196140964 0.1715396047 0.0202824299 2.5768850000 102631936 95654128 1784586240 -0.0768929124 0.0725962371 -0.0261048079 156 1305031234.6987318993 0.1324415356 0.1196963236 0.1715396047 0.0202268058 1.8525470000 102734238 95654128 1785856000 -0.0757727101 0.0728037134 -0.0277239550 157 1305031234.7344369888 0.1330016553 0.1197810709 0.1715396047 0.0201665086 0.9672710000 102805052 95654128 1788014592 -0.0753481612 0.0730050057 -0.0298582502 158 1305031234.7689719200 0.1341008693 0.1198717025 0.1715396047 0.0201166639 1.1324700000 102977162 95654128 1784713216 -0.0738161057 0.0694397166 -0.0333792940 159 1305031234.8015530109 0.1368525773 0.1199785005 0.1715396047 0.0202613875 0.8713330000 103148968 95654128 1785982976 -0.0783493668 0.0790238231 -0.0328733027 160 1305031234.8378078938 0.1334597766 0.1200627585 0.1715396047 0.0202016041 0.9347030000 103250166 95654128 1785634816 -0.0745229274 0.0746324211 -0.0325812586 161 1305031234.8693211079 0.1381109953 0.1201748593 0.1715396047 0.0201796892 0.8506090000 103321824 95654128 1786871808 -0.0777914003 0.0798068419 -0.0351683386 162 1305031234.9019980431 0.1395578831 0.1202945076 0.1715396047 0.0201261762 0.9245040000 103424262 95654128 1784713216 -0.0778756887 0.0833268985 -0.0347759910 163 1305031234.9381608963 0.1445828378 0.1204435158 0.1715396047 0.0201394063 0.8879820000 103425272 95654128 1785982976 -0.0806674212 0.0936129987 -0.0328361392 164 1305031234.9730799198 0.1486815959 0.1206156992 0.1715396047 0.0201031319 1.1356260000 103427542 95654128 1788149760 -0.0836096257 0.0918331742 -0.0344736315 165 1305031235.0050830841 0.1487229764 0.1207860463 0.1715396047 0.0201324944 1.3971720000 103429716 95654128 1784213504 -0.0890352651 0.0996553823 -0.0257109925 166 1305031235.0399720669 0.1480132490 0.1209500656 0.1715396047 0.0200872760 1.7034250000 103430726 95654128 1785483264 -0.0890134647 0.0956885293 -0.0235439520 167 1305031235.0729401112 0.1487921327 0.1211167846 0.1715396047 0.0200417516 1.8315460000 103432932 95654128 1787133952 -0.0939545259 0.1022216827 -0.0163863935 168 1305031235.0995910168 0.1456440091 0.1212627800 0.1715396047 0.0199841855 2.3172950000 103435042 95654128 1784586240 -0.0931885242 0.0996487439 -0.0123941321 169 1305031235.1362709999 0.1455656141 0.1214065837 0.1715396047 0.0199976994 2.0082000000 103436052 95654128 1785982976 -0.0914773941 0.0938355625 -0.0128045967 170 1305031235.1663711071 0.1478970498 0.1215624100 0.1715396047 0.0200037185 2.2294370000 103507746 95654128 1787760640 -0.0985764414 0.1060631722 -0.0043419767 171 1305031235.1998469830 0.1435691416 0.1216911043 0.1715396047 0.0199942127 1.7812990000 103610304 95654128 1784840192 -0.0963249579 0.1038151234 0.0007085465 172 1305031235.2375700474 0.1461086869 0.1218330670 0.1715396047 0.0200006595 2.3686570000 103611330 95654128 1786228736 -0.0985152423 0.1058625579 0.0011573499 173 1305031235.2690389156 0.1452435851 0.1219683879 0.1715396047 0.0199595349 2.0302110000 103613536 95654128 1788006400 -0.0998232365 0.1083438322 0.0054572672 174 1305031235.3064870834 0.1463849843 0.1221087132 0.1715396047 0.0199480933 1.9349580000 103615838 95654128 1784705024 -0.1014680043 0.1155117154 0.0101834042 175 1305031235.3380000591 0.1471778899 0.1222519656 0.1715396047 0.0199268198 1.9887830000 103616768 95654128 1786109952 -0.1028635651 0.1176173687 0.0125350412 176 1305031235.3698880672 0.1451729685 0.1223821986 0.1715396047 0.0199962925 2.7618210000 103618974 95654128 1788014592 -0.1013012305 0.1123239100 0.0126596401 177 1305031235.4060161114 0.1508376002 0.1225429636 0.1715396047 0.0200513852 1.9571420000 103621244 95654128 1784729600 -0.1045732200 0.1205213591 0.0134973414 178 1305031235.4381530285 0.1483462006 0.1226879256 0.1715396047 0.0200340389 1.7753350000 103622222 95654128 1786109952 -0.1045628488 0.1198925599 0.0172804445 179 1305031235.4700589180 0.1477776617 0.1228280917 0.1715396047 0.0200302071 1.9676920000 103624428 95654128 1788149760 -0.1036833748 0.1171895489 0.0172509775 180 1305031235.5059850216 0.1503300071 0.1229808801 0.1715396047 0.0200144350 2.1160740000 103626714 95654128 1784340480 -0.1047578454 0.1188000962 0.0177006423 181 1305031235.5385539532 0.1501368433 0.1231309131 0.1715396047 0.0199888554 1.9155130000 103627660 95654128 1785610240 -0.1052564979 0.1206324697 0.0196819622 182 1305031235.5703649521 0.1503343284 0.1232803824 0.1715396047 0.0199464624 1.8381730000 103629866 95654128 1787379712 -0.1058062389 0.1217125505 0.0213561077 183 1305031235.6060059071 0.1512347460 0.1234331385 0.1715396047 0.0199052661 1.7076890000 103702876 95654128 1784713216 -0.1065601110 0.1252953261 0.0236950442 184 1305031235.6389510632 0.1505417824 0.1235804681 0.1715396047 0.0199050397 1.8720480000 103804470 95654128 1786109952 -0.1072315201 0.1231313273 0.0250670910 185 1305031235.6705160141 0.1533501148 0.1237413851 0.1715396047 0.0198988095 1.2402290000 103806660 95654128 1788141568 -0.1093696579 0.1257260442 0.0248691738 186 1305031235.7057778835 0.1558897495 0.1239142257 0.1715396047 0.0198612998 2.0974720000 103879262 95654128 1784205312 -0.1122534871 0.1268369555 0.0254958794 187 1305031235.7387969494 0.1560101360 0.1240858616 0.1715396047 0.0198588062 1.9783720000 103980952 95654128 1785729024 -0.1150155813 0.1279889345 0.0283760354 188 1305031235.7696299553 0.1574083716 0.1242631090 0.1715396047 0.0198298094 1.4764550000 104053634 95654128 1787760640 -0.1172270477 0.1328517348 0.0301456656 189 1305031235.8072249889 0.1586136371 0.1244448579 0.1715396047 0.0198024052 1.5334180000 104156772 95654128 1784713216 -0.1193365455 0.1318665445 0.0304763857 190 1305031235.8388121128 0.1554005146 0.1246077824 0.1715396047 0.0200129225 1.3826300000 104227494 95654128 1785982976 -0.1209220737 0.1173468381 0.0336148515 191 1305031235.8700668812 0.1530196816 0.1247565358 0.1715396047 0.0201542322 2.2826990000 104330532 95654128 1788141568 -0.1212050468 0.1100279912 0.0378285460 192 1305031235.9061110020 0.1511540413 0.1248940228 0.1715396047 0.0201777442 1.9904840000 104403146 95654128 1784332288 -0.1211543381 0.1021912470 0.0420267172 193 1305031235.9382328987 0.1503313631 0.1250258225 0.1715396047 0.0201926034 1.7196540000 104505016 95654128 1785602048 -0.1220456287 0.0955369398 0.0457063355 194 1305031235.9700109959 0.1497820020 0.1251534316 0.1715396047 0.0202072891 2.1354540000 104507222 95654128 1787506688 -0.1227197573 0.0953290015 0.0481364429 195 1305031236.0068531036 0.1511384994 0.1252866884 0.1715396047 0.0201997701 1.2168030000 104579648 95654128 1784459264 -0.1255520284 0.0914385095 0.0513659939 196 1305031236.0380480289 0.1500088871 0.1254128221 0.1715396047 0.0202221095 2.1361400000 104681502 95654128 1785856000 -0.1252016276 0.0867514014 0.0560513027 197 1305031236.0698781013 0.1500620842 0.1255379452 0.1715396047 0.0203863045 1.7164460000 104683740 95654128 1787760640 -0.1262169629 0.0832604542 0.0598876700 198 1305031236.1058719158 0.1510353088 0.1256667198 0.1715396047 0.0203371538 2.0392090000 104756266 95654128 1784721408 -0.1276364475 0.0836601034 0.0615347736 199 1305031236.1383249760 0.1509129107 0.1257935851 0.1715396047 0.0202992417 2.3238580000 104858232 95654128 1785991168 -0.1284689605 0.0847069845 0.0633305982 200 1305031236.1709330082 0.1512125134 0.1259206797 0.1715396047 0.0202539655 2.2816010000 104860470 95654128 1788022784 -0.1288178563 0.0836841539 0.0656230301 201 1305031236.2071900368 0.1488977522 0.1260349935 0.1715396047 0.0202394832 3.1749970000 104862788 95654128 1784467456 -0.1279855520 0.0859122872 0.0683524236 202 1305031236.2383749485 0.1474499106 0.1261410079 0.1715396047 0.0202304545 1.9011060000 104863766 95654128 1785864192 -0.1292506754 0.0855647996 0.0724298954 203 1305031236.2699589729 0.1489504278 0.1262533696 0.1715396047 0.0201875550 1.7628120000 104865956 95654128 1787760640 -0.1305606365 0.0855351910 0.0710963756 204 1305031236.3069939613 0.1498315036 0.1263689487 0.1715396047 0.0201685541 1.4532290000 104868290 95654128 1784840192 -0.1312670410 0.0843445212 0.0700625479 205 1305031236.3392169476 0.1469552666 0.1264693698 0.1715396047 0.0201280506 2.1396700000 104869252 95654128 1786109952 -0.1284467280 0.0849721581 0.0688254461 206 1305031236.3700959682 0.1467173994 0.1265676612 0.1715396047 0.0200839076 2.4956500000 104871458 95654128 1788014592 -0.1267355233 0.0840840116 0.0651215836 207 1305031236.4058690071 0.1445570141 0.1266545663 0.1715396047 0.0200452622 1.8604400000 104873728 95654128 1784713216 -0.1247923076 0.0822514668 0.0632540733 208 1305031236.4387879372 0.1452274173 0.1267438588 0.1715396047 0.0200063846 1.7182920000 104874706 95654128 1785982976 -0.1239004731 0.0797960460 0.0593404844 209 1305031236.4751410484 0.1403664649 0.1268090387 0.1715396047 0.0199768719 1.7649020000 104877024 95654128 1788014592 -0.1202243343 0.0777509958 0.0584845580 210 1305031236.5077209473 0.1384509057 0.1268644762 0.1715396047 0.0199509698 1.7248860000 104879294 95654128 1784713216 -0.1174049303 0.0770118386 0.0546808019 211 1305031236.5386450291 0.1366216838 0.1269107189 0.1715396047 0.0200043747 1.6077700000 104880224 95654128 1785982976 -0.1153904423 0.0766539872 0.0513630360 212 1305031236.5740950108 0.1302142590 0.1269263016 0.1715396047 0.0200017571 1.6394200000 104882526 95654128 1788014592 -0.1097972989 0.0810080543 0.0477651618 213 1305031236.6057569981 0.1287528872 0.1269348771 0.1715396047 0.0200210609 1.8312410000 104884748 95654128 1784713216 -0.1084501222 0.0826582387 0.0433720797 214 1305031236.6384010315 0.1270295829 0.1269353197 0.1715396047 0.0200377398 1.5439100000 104885726 95654128 1785982976 -0.1045858786 0.0817683861 0.0387417823 215 1305031236.6751470566 0.1262046248 0.1269319211 0.1715396047 0.0199997881 2.4942530000 104887996 95654128 1787887616 -0.1034130454 0.0841902047 0.0332395695 216 1305031236.7033619881 0.1252085268 0.1269239424 0.1715396047 0.0199984253 1.8180670000 104890154 95654128 1784848384 -0.1022942737 0.0879514590 0.0292421654 217 1305031236.7339220047 0.1268383265 0.1269235479 0.1715396047 0.0200429804 1.9556870000 104891068 95654128 1785991168 -0.1009698659 0.0870522037 0.0223058760 218 1305031236.7740409374 0.1263457984 0.1269208977 0.1715396047 0.0199977237 1.8439460000 104893402 95654128 1787895808 -0.1010763273 0.0920377746 0.0178755820 219 1305031236.8025879860 0.1302839071 0.1269362539 0.1715396047 0.0201452976 2.1948510000 104895640 95654128 1784713216 -0.1000063121 0.0855017304 0.0093707731 220 1305031236.8364150524 0.1294384748 0.1269476276 0.1715396047 0.0201037805 1.8997040000 104896586 95654128 1785982976 -0.0986497402 0.0840788037 0.0038053822 221 1305031236.8743979931 0.1283133626 0.1269538074 0.1715396047 0.0200637925 1.3396450000 104898904 95654128 1787887616 -0.0957761109 0.0819592699 -0.0024639945 222 1305031236.9060690403 0.1305768192 0.1269701273 0.1715396047 0.0200986685 0.7731500000 104901110 95654128 1784344576 -0.0949601606 0.0793290511 -0.0101311347 223 1305031236.9344370365 0.1322830617 0.1269939521 0.1715396047 0.0200685054 0.8479620000 104901992 95654128 1785741312 -0.0937638730 0.0794980675 -0.0165778585 224 1305031236.9744000435 0.1314633787 0.1270139049 0.1715396047 0.0200247488 0.9626780000 104904310 95654128 1787645952 -0.0920907855 0.0771352574 -0.0232555438 225 1305031237.0074260235 0.1305895448 0.1270297966 0.1715396047 0.0200046171 1.0610110000 104906580 95654128 1784725504 -0.0894263014 0.0742008388 -0.0285831168 226 1305031237.0370240211 0.1329587996 0.1270560311 0.1715396047 0.0200211659 1.0631880000 104907510 95654128 1786122240 -0.0866086632 0.0745864585 -0.0357155576 227 1305031237.0734269619 0.1308685094 0.1270728262 0.1715396047 0.0199814443 0.9281620000 104909748 95654128 1787899904 -0.0832302496 0.0732574090 -0.0401505046 228 1305031237.1059679985 0.1314498335 0.1270920236 0.1715396047 0.0199637822 0.8249550000 104911986 95654128 1784868864 -0.0802340358 0.0680312440 -0.0470085666 229 1305031237.1378319263 0.1306860894 0.1271077182 0.1715396047 0.0199623847 0.8756520000 104912948 95654128 1786249216 -0.0749888867 0.0676867068 -0.0505933575 230 1305031237.1712269783 0.1348724663 0.1271414780 0.1715396047 0.0200367003 0.9741330000 104983854 95654128 1785425920 -0.0745434314 0.0719363242 -0.0568870977 231 1305031237.2042291164 0.1344524622 0.1271731273 0.1715396047 0.0200432993 1.0795710000 105156372 95654128 1784471552 -0.0698079765 0.0643540099 -0.0639888048 232 1305031237.2375690937 0.1365999728 0.1272137602 0.1715396047 0.0201163939 1.0499850000 105327362 95654128 1785995264 -0.0688134283 0.0706656203 -0.0670864955 233 1305031237.2746589184 0.1346093267 0.1272455009 0.1715396047 0.0200875796 1.1700740000 105431280 95654128 1788026880 -0.0643239990 0.0688808188 -0.0699739382 234 1305031237.3058099747 0.1354320347 0.1272804860 0.1715396047 0.0200810996 0.9580700000 105433486 95654128 1784217600 -0.0612086356 0.0718712062 -0.0722979978 235 1305031237.3371419907 0.1369984597 0.1273218391 0.1715396047 0.0200620259 1.0949100000 105434432 95654128 1785614336 -0.0584026650 0.0690191090 -0.0765862018 236 1305031237.3741660118 0.1404527277 0.1273774785 0.1715396047 0.0200247493 1.9367820000 105436654 95654128 1787392000 -0.0587223843 0.0695535168 -0.0831987485 237 1305031237.4057340622 0.1431322247 0.1274439542 0.1715396047 0.0200670878 1.8633780000 105438892 95654128 1784725504 -0.0597544312 0.0753835291 -0.0858207792 238 1305031237.4377219677 0.1438378841 0.1275128363 0.1715396047 0.0200562068 1.9724650000 105439822 95654128 1785995264 -0.0568799116 0.0760006979 -0.0876551792 239 1305031237.4741280079 0.1449837238 0.1275859362 0.1715396047 0.0200352900 1.9195640000 105442060 95654128 1787899904 -0.0552866831 0.0726061538 -0.0933284983 240 1305031237.5060451031 0.1475049555 0.1276689321 0.1715396047 0.0200532709 1.9071040000 105444282 95654128 1784725504 -0.0568794832 0.0792483315 -0.0943842828 241 1305031237.5376501083 0.1447940469 0.1277399907 0.1715396047 0.0200120827 2.5158380000 105445228 95654128 1786257408 -0.0517769642 0.0772434771 -0.0945548862 242 1305031237.5739479065 0.1484655291 0.1278256334 0.1715396047 0.0199748573 1.7027840000 105447434 95654128 1788035072 -0.0530315191 0.0782974958 -0.0991509184 243 1305031237.6068129539 0.1485883594 0.1279110767 0.1715396047 0.0199525993 2.1364470000 105449704 95654128 1784733696 -0.0523422807 0.0821396187 -0.0986895859 244 1305031237.6378550529 0.1495846063 0.1279999027 0.1715396047 0.0199288150 1.9177690000 105518394 95654128 1786003456 -0.0518143997 0.0832797810 -0.0999063328 245 1305031237.6752760410 0.1503047198 0.1280909427 0.1715396047 0.0199084839 2.0328910000 105622556 95654128 1788026880 -0.0501020178 0.0835261717 -0.1002958938 246 1305031237.7071180344 0.1505614072 0.1281822861 0.1715396047 0.0198742899 1.7528690000 105624778 95654128 1784360960 -0.0463160165 0.0851300806 -0.0991881564 247 1305031237.7416670322 0.1532925069 0.1282839469 0.1715396047 0.0198418986 2.0713460000 105625740 95654128 1785741312 -0.0484524891 0.0903981552 -0.0990202948 248 1305031237.7743060589 0.1467263699 0.1283583115 0.1715396047 0.0198603352 1.4524940000 105627898 95654128 1787645952 -0.0456377156 0.0836939290 -0.0949424580 249 1305031237.8064959049 0.1485867053 0.1284395500 0.1715396047 0.0198472531 2.2014520000 105630136 95654128 1784725504 -0.0481711663 0.0832626447 -0.0978105292 250 1305031237.8430309296 0.1547433585 0.1285447653 0.1715396047 0.0198502755 1.8967180000 105631146 95654128 1785995264 -0.0539310649 0.0964987576 -0.0946888998 251 1305031237.8754220009 0.1469498426 0.1286180923 0.1715396047 0.0201076791 2.0303810000 105633304 95654128 1787645952 -0.0425171815 0.0784252286 -0.0972076878 252 1305031237.9077839851 0.1521176994 0.1287113447 0.1715396047 0.0201291896 1.8707680000 105635526 95654128 1784725504 -0.0498671755 0.0773650333 -0.1043737903 253 1305031237.9441869259 0.1552464217 0.1288162264 0.1715396047 0.0202214003 1.1168410000 105636536 95654128 1786122240 -0.0541602187 0.0929801986 -0.0969113484 254 1305031237.9738099575 0.1544916481 0.1289173108 0.1715396047 0.0201940449 1.9820930000 105638630 95654128 1787899904 -0.0564859994 0.0941922888 -0.0931440368 255 1305031238.0069320202 0.1554074883 0.1290211938 0.1715396047 0.0201650778 1.8615350000 105640900 95654128 1784852480 -0.0627800524 0.0987760127 -0.0890225619 256 1305031238.0431399345 0.1539291739 0.1291184906 0.1715396047 0.0203850086 1.7450490000 105709630 95654128 1786249216 -0.0677640811 0.1066528261 -0.0786243230 257 1305031238.0740320683 0.1563279182 0.1292243639 0.1715396047 0.0204211423 1.7797030000 105921924 95654128 1785487360 -0.0764351934 0.1175649837 -0.0683994666 258 1305031238.1065878868 0.1550577283 0.1293244932 0.1715396047 0.0204056290 1.5485920000 106136446 95654128 1787011072 -0.0788559318 0.1205302924 -0.0622903332 259 1305031238.1433279514 0.1552465707 0.1294245784 0.1715396047 0.0204485713 2.4342650000 106219192 95654128 1784725504 -0.0777838379 0.1178931743 -0.0625377968 260 1305031238.1723001003 0.1559372246 0.1295265501 0.1715396047 0.0204941939 1.8279970000 106309674 95654128 1786003456 -0.0835971832 0.1219874546 -0.0576551706 261 1305031238.2054259777 0.1517134309 0.1296115573 0.1715396047 0.0204870024 2.1754400000 106393628 95654128 1788035072 -0.0796706304 0.1113218516 -0.0604787990 262 1305031238.2401471138 0.1529488564 0.1297006310 0.1715396047 0.0204537022 1.6890270000 106482850 95654128 1784860672 -0.0803024322 0.1118066758 -0.0606611855 263 1305031238.2725269794 0.1508719027 0.1297811301 0.1715396047 0.0204356207 1.6947090000 106656572 95654128 1786249216 -0.0792121440 0.1103928834 -0.0580181591 264 1305031238.3060529232 0.1512088925 0.1298622959 0.1715396047 0.0204910303 1.9486800000 106829666 95654128 1785360384 -0.0817693248 0.1132982001 -0.0540481471 265 1305031238.3425960541 0.1495880783 0.1299367328 0.1715396047 0.0205765493 1.8198130000 107002092 95654128 1786884096 -0.0820342526 0.1094530672 -0.0532507636 266 1305031238.3741040230 0.1538753659 0.1300267277 0.1715396047 0.0205985986 2.1320060000 107086194 95654128 1784725504 -0.0855420232 0.1139579266 -0.0534815900 267 1305031238.4060359001 0.1522983760 0.1301101421 0.1715396047 0.0205763059 1.3085770000 107177868 95654128 1785995264 -0.0860476717 0.1128942147 -0.0512198694 268 1305031238.4434239864 0.1512575746 0.1301890504 0.1715396047 0.0205483662 1.7302360000 107260802 95654128 1788026880 -0.0872208476 0.1122574359 -0.0490684882 269 1305031238.4740819931 0.1512759179 0.1302674403 0.1715396047 0.0205356862 2.4474650000 107263008 95654128 1784725504 -0.0896211937 0.1130555272 -0.0476591177 270 1305031238.5058109760 0.1495047361 0.1303386895 0.1715396047 0.0205951885 1.8926370000 107265230 95654128 1785995264 -0.0908929706 0.1099420041 -0.0461497158 271 1305031238.5432639122 0.1478234231 0.1304032088 0.1715396047 0.0205674363 1.7069370000 107266272 95654128 1788026880 -0.0927651674 0.1063875258 -0.0450937115 272 1305031238.5741839409 0.1503301412 0.1304764696 0.1715396047 0.0205311952 1.8151910000 107268414 95654128 1784852480 -0.0951397866 0.1119046062 -0.0451057330 273 1305031238.6058249474 0.1510174870 0.1305517114 0.1715396047 0.0204993142 0.9094220000 107359440 95654128 1786179584 -0.0974152237 0.1149310470 -0.0438554138 274 1305031238.6427590847 0.1507072598 0.1306252718 0.1715396047 0.0204714153 1.1613520000 107442546 95654128 1785622528 -0.0986497477 0.1179634556 -0.0420910977 275 1305031238.6738131046 0.1500664055 0.1306959668 0.1715396047 0.0204435863 1.4929360000 107534424 95654128 1787019264 -0.0991864651 0.1196707860 -0.0405276902 276 1305031238.7051889896 0.1509949714 0.1307695140 0.1715396047 0.0204196388 2.6197000000 107618722 95654128 1784606720 -0.1011705697 0.1226627678 -0.0399833731 277 1305031238.7413070202 0.1474146098 0.1308296046 0.1715396047 0.0204576066 1.1312440000 107708524 95654128 1786003456 -0.1037358269 0.1159901395 -0.0381381325 278 1305031238.7717959881 0.1457574666 0.1308833019 0.1715396047 0.0204488360 1.9175310000 107792866 95654128 1787908096 -0.1052956507 0.1140960008 -0.0366945006 279 1305031238.8070189953 0.1461004168 0.1309378435 0.1715396047 0.0204189654 2.5492000000 107884304 95654128 1784741888 -0.1072029993 0.1138549894 -0.0371024832 280 1305031238.8429400921 0.1452115476 0.1309888211 0.1715396047 0.0204210648 2.2323240000 107967526 95654128 1786011648 -0.1094784439 0.1105043888 -0.0365959518 281 1305031238.8737230301 0.1417845190 0.1310272399 0.1715396047 0.0204281241 1.9017700000 107969764 95654128 1788043264 -0.1105335504 0.1040644795 -0.0341789573 282 1305031238.9061720371 0.1411366761 0.1310630890 0.1715396047 0.0203997448 1.4418060000 107971970 95654128 1784741888 -0.1110519618 0.1048298478 -0.0336893313 283 1305031238.9427859783 0.1431050897 0.1311056402 0.1715396047 0.0203636550 1.9227510000 107973028 95654128 1786138624 -0.1112760380 0.1103342324 -0.0347603261 284 1305031238.9723079205 0.1402036399 0.1311376754 0.1715396047 0.0203471007 1.4008950000 107975234 95654128 1787908096 -0.1126349866 0.1074617058 -0.0317440219 285 1305031239.0104830265 0.1394714415 0.1311669167 0.1715396047 0.0203574249 2.0208970000 107977552 95654128 1784733696 -0.1116203442 0.1118169278 -0.0314929560 286 1305031239.0408790112 0.1403688639 0.1311990913 0.1715396047 0.0203464167 1.6992690000 107978498 95654128 1786130432 -0.1133505479 0.1114397347 -0.0320162550 287 1305031239.0746610165 0.1401612759 0.1312303185 0.1715396047 0.0203754247 2.1651220000 108069488 95654128 1787908096 -0.1163271740 0.1067409739 -0.0315520130 288 1305031239.1109058857 0.1381661296 0.1312544011 0.1715396047 0.0203421582 1.6393500000 108154150 95654128 1784860672 -0.1169298589 0.1046822891 -0.0297480896 289 1305031239.1417789459 0.1379649490 0.1312776210 0.1715396047 0.0203207462 1.9175750000 108155096 95654128 1786257408 -0.1188037694 0.1019699499 -0.0294576976 290 1305031239.1757500172 0.1367425621 0.1312964657 0.1715396047 0.0202882678 1.7351790000 108157366 95654128 1788035072 -0.1189854443 0.1010198593 -0.0288082808 291 1305031239.2096450329 0.1376829743 0.1313184124 0.1715396047 0.0202629424 1.6819650000 108159636 95654128 1784733696 -0.1168955863 0.1003790721 -0.0314515270 292 1305031239.2417099476 0.1381709427 0.1313418800 0.1715396047 0.0202311061 1.9461760000 108160614 95654128 1786003456 -0.1176356673 0.1009018347 -0.0320370980 293 1305031239.2738199234 0.1362020075 0.1313584675 0.1715396047 0.0202138732 1.6807710000 108162820 95654128 1787924480 -0.1154506058 0.1006290168 -0.0314139724 294 1305031239.3101770878 0.1340672970 0.1313676812 0.1715396047 0.0201854157 1.6029740000 108165154 95654128 1784733696 -0.1136723459 0.1004367024 -0.0303707048 295 1305031239.3419699669 0.1318484098 0.1313693108 0.1715396047 0.0201572249 1.5379070000 108166132 95654128 1786003456 -0.1106386483 0.0977451503 -0.0298987441 296 1305031239.3750240803 0.1312029511 0.1313687487 0.1715396047 0.0201375363 1.4570420000 108168338 95654128 1787908096 -0.1097583398 0.0952833071 -0.0303519480 297 1305031239.4106309414 0.1320266128 0.1313709638 0.1715396047 0.0201040974 1.8753940000 108170592 95654128 1784733696 -0.1092504710 0.0939058214 -0.0318940803 298 1305031239.4415419102 0.1331338733 0.1313768796 0.1715396047 0.0200717154 1.9034220000 108171538 95654128 1786130432 -0.1098021939 0.0930662155 -0.0333403088 299 1305031239.4733181000 0.1319024563 0.1313786373 0.1715396047 0.0200465747 2.0132960000 108173744 95654128 1787916288 -0.1073781475 0.0906094387 -0.0339392759 300 1305031239.5097389221 0.1329574138 0.1313838999 0.1715396047 0.0200257517 1.7697400000 108176030 95654128 1784741888 -0.1069165543 0.0924641043 -0.0356304608 301 1305031239.5438020229 0.1329434514 0.1313890812 0.1715396047 0.0200041371 2.1701600000 108177040 95654128 1786011648 -0.1054840907 0.0927794948 -0.0364570767 302 1305031239.5761160851 0.1330547184 0.1313945965 0.1715396047 0.0199955789 1.8435260000 108179344 95654128 1788043264 -0.1032291129 0.0931895450 -0.0374815911 303 1305031239.6111609936 0.1352484971 0.1314073157 0.1715396047 0.0199756907 2.0611100000 108181614 95654128 1784733696 -0.1032533720 0.0930056944 -0.0401605107 304 1305031239.6414220333 0.1350940615 0.1314194431 0.1715396047 0.0199511388 1.5215270000 108182560 95654128 1786003456 -0.1012696028 0.0940482020 -0.0405493714 305 1305031239.6710560322 0.1367539167 0.1314369332 0.1715396047 0.0199330467 2.2422400000 108184842 95654128 1788035072 -0.0997778401 0.0922515318 -0.0436289981 306 1305031239.7075550556 0.1356969178 0.1314508547 0.1715396047 0.0199456204 2.0802240000 108185852 95654128 1784479744 -0.0977688655 0.0867426544 -0.0451417230 307 1305031239.7417550087 0.1375273615 0.1314706479 0.1715396047 0.0199241766 1.8894770000 108188122 95654128 1785876480 -0.0979980677 0.0820375234 -0.0490019508 308 1305031239.7712600231 0.1348750293 0.1314817011 0.1715396047 0.0198995494 1.3476060000 108190264 95654128 1787654144 -0.0943358541 0.0782098994 -0.0490720570 309 1305031239.8060870171 0.1357694417 0.1314955773 0.1715396047 0.0199676205 1.8521490000 108191258 95654128 1784733696 -0.0933832154 0.0730881095 -0.0529091582 310 1305031239.8392889500 0.1409814209 0.1315261768 0.1715396047 0.0199773621 2.0212780000 108193512 95654128 1786130432 -0.0946926028 0.0735303611 -0.0592701063 311 1305031239.8744299412 0.1414709836 0.1315581536 0.1715396047 0.0199532654 2.3505890000 108195874 95654128 1787908096 -0.0931443647 0.0754493326 -0.0609083995 312 1305031239.9090619087 0.1383032054 0.1315797724 0.1715396047 0.0199985966 0.8288860000 108196884 95654128 1784860672 -0.0875395611 0.0724039674 -0.0609784313 313 1305031239.9403729439 0.1390904039 0.1316037680 0.1715396047 0.0200050571 0.9592190000 108199074 95654128 1786257408 -0.0849912316 0.0734565556 -0.0629881248 314 1305031239.9710669518 0.1397061199 0.1316295717 0.1715396047 0.0200389568 0.8847510000 108201280 95654128 1788035072 -0.0827749670 0.0750629976 -0.0647246465 315 1305031240.0088651180 0.1408238858 0.1316587600 0.1715396047 0.0200614973 0.9535760000 108202354 95654128 1784606720 -0.0796728358 0.0681396499 -0.0696083382 316 1305031240.0396599770 0.1428497583 0.1316941745 0.1715396047 0.0200613775 0.9716080000 108204528 95654128 1786003456 -0.0790347382 0.0693984181 -0.0736040547 317 1305031240.0711870193 0.1444504261 0.1317344151 0.1715396047 0.0200394572 0.8369370000 108293702 95654128 1787908096 -0.0773362517 0.0660466477 -0.0781897679 318 1305031240.1093459129 0.1438212842 0.1317724241 0.1715396047 0.0200290974 0.8438580000 108466968 95654128 1784733696 -0.0736434683 0.0604032353 -0.0824426711 319 1305031240.1435019970 0.1470293403 0.1318202514 0.1715396047 0.0200278011 0.9623500000 108639310 95654128 1786130432 -0.0700704604 0.0533697940 -0.0904919133 320 1305031240.1775770187 0.1493417621 0.1318750061 0.1715396047 0.0200515000 0.8751270000 108811632 95654128 1785622528 -0.0731767640 0.0648537725 -0.0908197090 321 1305031240.2093310356 0.1482453942 0.1319260042 0.1715396047 0.0200814709 0.8034240000 108982366 95654128 1787273216 -0.0646095723 0.0539925694 -0.0966282263 322 1305031240.2410049438 0.1502542943 0.1319829244 0.1715396047 0.0201478330 0.8039820000 109154352 95654128 1784487936 -0.0629438087 0.0533880405 -0.1017202139 323 1305031240.2774341106 0.1498064995 0.1320381057 0.1715396047 0.0201197653 0.8673460000 109239690 95654128 1785884672 -0.0657992512 0.0633164868 -0.1010067314 324 1305031240.3089289665 0.1528457105 0.1321023267 0.1715396047 0.0201011607 0.9770250000 109327300 95654128 1787916288 -0.0604265369 0.0560792461 -0.1094588265 325 1305031240.3422729969 0.1531288028 0.1321670236 0.1715396047 0.0201311806 1.6132680000 109412650 95654128 1784614912 -0.0600172430 0.0598463006 -0.1102216840 326 1305031240.3774259090 0.1538835913 0.1322336388 0.1715396047 0.0201187738 2.0342570000 109501060 95654128 1786011648 -0.0566618778 0.0648722723 -0.1111624539 327 1305031240.4091110229 0.1550467163 0.1323034036 0.1715396047 0.0201080911 1.9528480000 109585130 95654128 1788162048 -0.0570724346 0.0672848895 -0.1134417355 328 1305031240.4417860508 0.1557881832 0.1323750035 0.1715396047 0.0200846673 1.0253730000 109673904 95654128 1784352768 -0.0545995384 0.0709269568 -0.1130707934 329 1305031240.4776389599 0.1583148837 0.1324538482 0.1715396047 0.0200572464 0.9524070000 109759374 95654128 1785622528 -0.0523271412 0.0774139315 -0.1136322245 330 1305031240.5084490776 0.1554238796 0.1325234543 0.1715396047 0.0200290622 1.7471040000 109760256 95654128 1787654144 -0.0517155901 0.0744121671 -0.1128361821 331 1305031240.5412700176 0.1583614349 0.1326015147 0.1715396047 0.0200600689 1.7003520000 109848730 95654128 1784733696 -0.0550689884 0.0801780000 -0.1133716181 332 1305031240.5759088993 0.1632624269 0.1326938668 0.1715396047 0.0200319656 1.9927280000 109934248 95654128 1786130432 -0.0508566275 0.0908888504 -0.1111232936 333 1305031240.6101338863 0.1616639793 0.1327808642 0.1715396047 0.0200094456 1.6779390000 109935226 95654128 1787908096 -0.0522376522 0.0924598128 -0.1071556360 334 1305031240.6398229599 0.1625198722 0.1328699031 0.1715396047 0.0200080960 1.5707220000 109937352 95654128 1784606720 -0.0584950373 0.1025579274 -0.0990471095 335 1305031240.6747570038 0.1561192423 0.1329393041 0.1715396047 0.0199892097 2.3967120000 109939622 95654128 1786003456 -0.0549638160 0.1003641188 -0.0908313990 336 1305031240.7079319954 0.1576909870 0.1330129698 0.1715396047 0.0200134832 2.2753360000 110026616 95654128 1787908096 -0.0645048171 0.1081389561 -0.0840961635 337 1305031240.7439579964 0.1558202058 0.1330806471 0.1715396047 0.0200228101 1.6990030000 110112158 95654128 1784733696 -0.0693400204 0.1201217324 -0.0678839833 338 1305031240.7768330574 0.1522675902 0.1331374132 0.1715396047 0.0200209696 0.9044750000 110114428 95654128 1786130432 -0.0658216625 0.1115899161 -0.0710450187 339 1305031240.8096249104 0.1523738354 0.1331941578 0.1715396047 0.0200032128 0.9080720000 110201802 95654128 1788035072 -0.0684888661 0.1133843437 -0.0675212666 340 1305031240.8425960541 0.1563435048 0.1332622441 0.1715396047 0.0200231595 0.9913430000 110287424 95654128 1784766464 -0.0801146552 0.1287485510 -0.0543960109 341 1305031240.8794100285 0.1503358483 0.1333123133 0.1715396047 0.0199994413 0.8994730000 110289726 95654128 1786130432 -0.0747452751 0.1180012599 -0.0577044785 342 1305031240.9084498882 0.1497239470 0.1333603006 0.1715396047 0.0199792965 0.9085900000 110290624 95654128 1787908096 -0.0771704391 0.1210274994 -0.0526166297 343 1305031240.9423189163 0.1531746835 0.1334180685 0.1715396047 0.0199841689 0.7081610000 110292846 95654128 1784733696 -0.0839680955 0.1268080175 -0.0488239527 344 1305031240.9779360294 0.1494115442 0.1334645611 0.1715396047 0.0199763580 0.8295110000 110295116 95654128 1786130432 -0.0792913884 0.1182641536 -0.0517153889 345 1305031241.0083029270 0.1523284614 0.1335192391 0.1715396047 0.0200293577 0.7674840000 110296046 95654128 1788035072 -0.0860266313 0.1236380562 -0.0485453904 346 1305031241.0401480198 0.1491647363 0.1335644573 0.1715396047 0.0200886893 0.8501120000 110298188 95654128 1784750080 -0.0838311762 0.1231137067 -0.0442238040 347 1305031241.0759329796 0.1514579505 0.1336160235 0.1715396047 0.0200764874 0.9442900000 110299386 95654128 1786003456 -0.0866334662 0.1211923286 -0.0479490049 348 1305031241.1065559387 0.1528407335 0.1336712670 0.1715396047 0.0200571148 0.8612580000 110301560 95654128 1788170240 -0.0884930342 0.1225663647 -0.0469590388 349 1305031241.1400520802 0.1496746987 0.1337171221 0.1715396047 0.0201130475 0.8532910000 110303798 95654128 1784233984 -0.0867706463 0.1184885353 -0.0453771129 350 1305031241.1781818867 0.1498059630 0.1337630902 0.1715396047 0.0201021989 0.7086700000 110304840 95654128 1785630720 -0.0875585750 0.1180381551 -0.0442817025 351 1305031241.2106790543 0.1507445872 0.1338114705 0.1715396047 0.0200839004 0.7338980000 110307094 95654128 1787535360 -0.0888717622 0.1198033392 -0.0438213050 352 1305031241.2393150330 0.1494878531 0.1338560057 0.1715396047 0.0201433724 0.7772410000 110309204 95654128 1784635392 -0.0880898833 0.1186625212 -0.0428642184 353 1305031241.2768468857 0.1463515460 0.1338914038 0.1715396047 0.0201398607 0.9237500000 110310434 95654128 1785884672 -0.0874543190 0.1161032245 -0.0416189097 354 1305031241.3063299656 0.1488603204 0.1339336889 0.1715396047 0.0201181595 0.9681010000 110312608 95654128 1787916288 -0.0902194083 0.1219317690 -0.0413234755 355 1305031241.3424758911 0.1473834962 0.1339715757 0.1715396047 0.0201704373 1.0298260000 110314878 95654128 1784741888 -0.0905678496 0.1237723008 -0.0400889032 356 1305031241.3795149326 0.1448042542 0.1340020046 0.1715396047 0.0202559834 1.2198120000 110403000 95654128 1786011648 -0.0918255150 0.1212189123 -0.0401724130 357 1305031241.4096820354 0.1496671289 0.1340458845 0.1715396047 0.0202591624 0.9445680000 110488966 95654128 1785503744 -0.0963325351 0.1263461560 -0.0432783477 358 1305031241.4455459118 0.1515001953 0.1340946395 0.1715396047 0.0202426171 0.8387740000 110491236 95654128 1786916864 -0.1001710147 0.1338120103 -0.0430291779 359 1305031241.4775071144 0.1424375176 0.1341178787 0.1715396047 0.0204609782 0.7405140000 110492338 95654128 1784381440 -0.0987430215 0.1272538900 -0.0364018828 360 1305031241.5098490715 0.1322485507 0.1341126862 0.1715396047 0.0204614882 0.7620520000 110494544 95654128 1785749504 -0.0959534347 0.1158989072 -0.0305491239 361 1305031241.5477299690 0.1281268001 0.1340961048 0.1715396047 0.0204342113 0.8289160000 110496878 95654128 1787654144 -0.0955118984 0.1105325222 -0.0278731789 362 1305031241.5783948898 0.1337564588 0.1340951665 0.1715396047 0.0204462013 0.7930920000 110497760 95654128 1784860672 -0.0974671915 0.1145787612 -0.0326463841 363 1305031241.6092638969 0.1303766370 0.1340849226 0.1715396047 0.0204482955 0.7802440000 110499918 95654128 1786146816 -0.0978819206 0.1070906669 -0.0311973449 364 1305031241.6475839615 0.1309615821 0.1340763420 0.1715396047 0.0204216280 0.8337100000 110502252 95654128 1788035072 -0.0989131480 0.1053527966 -0.0330354087 365 1305031241.6783659458 0.1348635405 0.1340784987 0.1715396047 0.0204661969 0.8377040000 110503338 95654128 1784733696 -0.0969937295 0.1143131852 -0.0360768810 366 1305031241.7098269463 0.1320872605 0.1340730582 0.1715396047 0.0204440867 0.9036860000 110505480 95654128 1786130432 -0.0951969251 0.1114112809 -0.0350386053 367 1305031241.7471020222 0.1329483241 0.1340699935 0.1715396047 0.0204223530 1.2113420000 110506538 95654128 1787908096 -0.0943119004 0.1122426465 -0.0365333855 368 1305031241.7782680988 0.1324227303 0.1340655173 0.1715396047 0.0204155988 1.6291170000 110508728 95654128 1784733696 -0.0938283205 0.1093958244 -0.0371861719 369 1305031241.8098289967 0.1373146623 0.1340743225 0.1715396047 0.0204247643 2.2344200000 110510854 95654128 1786130432 -0.0943642855 0.1157665551 -0.0410304703 370 1305031241.8464360237 0.1330739111 0.1340716187 0.1715396047 0.0204252113 2.2567170000 110511896 95654128 1787908096 -0.0960439593 0.1051885188 -0.0392832048 371 1305031241.8787989616 0.1403079629 0.1340884283 0.1715396047 0.0205565522 2.0610910000 110514242 95654128 1784877056 -0.0976544023 0.1105563417 -0.0456447974 372 1305031241.9114871025 0.1399446726 0.1341041709 0.1715396047 0.0205610820 2.2810280000 110516432 95654128 1786257408 -0.0959969386 0.1135711819 -0.0453448631 373 1305031241.9477050304 0.1361431926 0.1341096374 0.1715396047 0.0205677800 1.6554240000 110604742 95654128 1785241600 -0.0955566838 0.1081289425 -0.0431905501 374 1305031241.9783430099 0.1383175105 0.1341208884 0.1715396047 0.0207379125 1.4845210000 110691052 95654128 1786892288 -0.0959085077 0.1114254892 -0.0449486151 375 1305031242.0105700493 0.1370071024 0.1341285850 0.1715396047 0.0208181465 1.7969080000 110693226 95654128 1784733696 -0.0938103944 0.1090984493 -0.0452174395 376 1305031242.0463600159 0.1348197013 0.1341304230 0.1715396047 0.0208969442 1.2156680000 110694236 95654128 1786003456 -0.0926288590 0.1057441384 -0.0443422198 377 1305031242.0795490742 0.1355319619 0.1341341407 0.1715396047 0.0210748555 1.9319000000 110782722 95654128 1787916288 -0.0934249684 0.1057764515 -0.0454600491 378 1305031242.1105840206 0.1363985091 0.1341401310 0.1715396047 0.0212128331 1.7011790000 110869132 95654128 1784741888 -0.0957478955 0.1038721204 -0.0467082262 379 1305031242.1466050148 0.1377067268 0.1341495416 0.1715396047 0.0214177294 1.8050590000 110870142 95654128 1786011648 -0.0965479314 0.1039337218 -0.0481679142 380 1305031242.1797080040 0.1397261024 0.1341642168 0.1715396047 0.0215878929 1.9578740000 110872380 95654128 1787789312 -0.0994325578 0.1026145294 -0.0501100682 381 1305031242.2087249756 0.1430943310 0.1341876554 0.1715396047 0.0216782558 2.4891800000 110960470 95654128 1784868864 -0.1033470109 0.1023864076 -0.0527963489 382 1305031242.2478089333 0.1434735656 0.1342119640 0.1715396047 0.0217822513 1.6090790000 111045832 95654128 1786130432 -0.1046889350 0.0985583290 -0.0536560453 383 1305031242.2794981003 0.1447519958 0.1342394837 0.1715396047 0.0218762030 1.6416870000 111048178 95654128 1785544704 -0.1048299521 0.0983091444 -0.0547293350 384 1305031242.3097639084 0.1434609741 0.1342634980 0.1715396047 0.0219399528 1.9393870000 111049076 95654128 1786892288 -0.1034516543 0.0954011530 -0.0542483591 385 1305031242.3471269608 0.1434536725 0.1342873686 0.1715396047 0.0221166271 1.8271380000 111140194 95654128 1784479744 -0.1034747288 0.0911468342 -0.0550212301 386 1305031242.3784790039 0.1453212202 0.1343159537 0.1715396047 0.0222986002 2.2756670000 111226772 95654128 1785876480 -0.1025649160 0.0946080834 -0.0564235933 387 1305031242.4109969139 0.1445192248 0.1343423187 0.1715396047 0.0223958098 2.0848080000 111227718 95654128 1787781120 -0.1025143713 0.0901861787 -0.0573065840 388 1305031242.4470989704 0.1469544768 0.1343748243 0.1715396047 0.0226244561 0.8437350000 111230020 95654128 1784848384 -0.1049424335 0.0889098570 -0.0608827658 389 1305031242.4776470661 0.1468871236 0.1344069896 0.1715396047 0.0227656451 0.9461470000 111318562 95654128 1786130432 -0.1026806757 0.0885210484 -0.0625710562 390 1305031242.5097260475 0.1488451064 0.1344440104 0.1715396047 0.0231166206 1.1286610000 111403964 95654128 1788035072 -0.1062368229 0.0834375173 -0.0672633648 391 1305031242.5485460758 0.1513066739 0.1344871374 0.1715396047 0.0237645612 0.8913530000 111406298 95654128 1784651776 -0.1082963422 0.0878282487 -0.0705381036 392 1305031242.5748429298 0.1519943625 0.1345317987 0.1715396047 0.0239611420 0.8515400000 111408376 95654128 1786003456 -0.1060566530 0.0919920281 -0.0714975670 393 1305031242.6061151028 0.1540716738 0.1345815185 0.1715396047 0.0240818751 0.9371490000 111496150 95654128 1787908096 -0.1089132056 0.0864124000 -0.0755745694 394 1305031242.6438109875 0.1568728238 0.1346380954 0.1715396047 0.0244438330 0.9526460000 111582992 95654128 1784733696 -0.1125326082 0.0875371322 -0.0790641606 395 1305031242.6752018929 0.1602927446 0.1347030439 0.1715396047 0.0248896957 1.0275360000 111585370 95654128 1786130432 -0.1195973009 0.0907726735 -0.0825159773 396 1305031242.7139821053 0.1608233005 0.1347690041 0.1715396047 0.0253609655 0.9082710000 111673304 95654128 1788035072 -0.1212406754 0.0948363692 -0.0839934349 397 1305031242.7452580929 0.1560880542 0.1348227045 0.1715396047 0.0254241813 0.8771410000 111760146 95654128 1784733696 -0.1148059517 0.0903969109 -0.0828587934 398 1305031242.7775399685 0.1606591344 0.1348876202 0.1715396047 0.0256951391 0.9160680000 111762384 95654128 1786130432 -0.1233482510 0.0905644894 -0.0880038813 399 1305031242.8140709400 0.1582865119 0.1349462640 0.1715396047 0.0259619346 1.0851360000 111850082 95654128 1785442304 -0.1227563843 0.0967740566 -0.0852545202 400 1305031242.8443179131 0.1578189284 0.1350034457 0.1715396047 0.0260066409 0.8591610000 111936956 95654128 1784614912 -0.1232092530 0.0972122326 -0.0863434896 401 1305031242.8740880489 0.1589311957 0.1350631159 0.1715396047 0.0260784681 0.8266130000 111938074 95654128 1785884672 -0.1272329986 0.0962185115 -0.0886271521 402 1305031242.9137070179 0.1601734459 0.1351255794 0.1715396047 0.0262056272 0.8909510000 112027480 95654128 1787916288 -0.1294189543 0.0978839695 -0.0908594579 403 1305031242.9444379807 0.1608886719 0.1351895076 0.1715396047 0.0264535743 0.9365060000 112114418 95654128 1784741888 -0.1344401091 0.1021110564 -0.0911229327 404 1305031242.9760620594 0.1594407707 0.1352495355 0.1715396047 0.0265073244 0.8686130000 112115364 95654128 1786011648 -0.1337927282 0.1062894613 -0.0897711366 405 1305031243.0141661167 0.1590159535 0.1353082180 0.1715396047 0.0266022715 0.7878770000 112117714 95654128 1787916288 -0.1371324211 0.1073553562 -0.0901663303 406 1305031243.0469100475 0.1596615613 0.1353682016 0.1715396047 0.0266106173 1.3071180000 112120048 95654128 1784741888 -0.1420839280 0.1096762791 -0.0909137204 407 1305031243.0780448914 0.1610653251 0.1354313395 0.1715396047 0.0266166911 1.8852150000 112206966 95654128 1786011648 -0.1450722814 0.1113287583 -0.0928720757 408 1305031243.1136150360 0.1581089199 0.1354869218 0.1715396047 0.0266432656 2.0181380000 112294072 95654128 1788162048 -0.1437717974 0.1160628200 -0.0907612070 409 1305031243.1458160877 0.1590892822 0.1355446293 0.1715396047 0.0266127619 1.9654440000 112296342 95654128 1784369152 -0.1433497816 0.1193873733 -0.0911264643 410 1305031243.1780760288 0.1597869545 0.1356037569 0.1715396047 0.0266206843 2.2329590000 112297320 95654128 1785749504 -0.1454974413 0.1217142045 -0.0908713490 411 1305031243.2136580944 0.1572822183 0.1356565026 0.1715396047 0.0266746463 1.8139140000 112299622 95654128 1787400192 -0.1400515288 0.1219411045 -0.0882634372 412 1305031243.2455608845 0.1629216820 0.1357226802 0.1715396047 0.0270031617 1.6594290000 112301860 95654128 1784479744 -0.1458416581 0.1180146486 -0.0920716748 413 1305031243.2781798840 0.1649245769 0.1357933870 0.1715396047 0.0270740904 1.7361540000 112303010 95654128 1785876480 -0.1508379281 0.1123838276 -0.0928761214 414 1305031243.3142709732 0.1603475511 0.1358526966 0.1715396047 0.0272755003 2.4194860000 112305280 95654128 1787781120 -0.1385332048 0.1154560894 -0.0879486725 415 1305031243.3460359573 0.1641906053 0.1359209807 0.1715396047 0.0276351680 1.8979120000 112307550 95654128 1784733696 -0.1441861838 0.1141061261 -0.0895622596 416 1305031243.3789350986 0.1624048203 0.1359846437 0.1715396047 0.0276954128 2.0712740000 112308560 95654128 1786130432 -0.1428423524 0.1125582606 -0.0869302824 417 1305031243.4139740467 0.1608348489 0.1360442366 0.1715396047 0.0278657658 1.8974240000 112310830 95654128 1788035072 -0.1394329071 0.1182155982 -0.0828287080 418 1305031243.4470911026 0.1648698747 0.1361131974 0.1715396047 0.0281487855 0.9159870000 112313100 95654128 1784803328 -0.1475125253 0.1120477691 -0.0858890861 419 1305031243.4780371189 0.1635465622 0.1361786708 0.1715396047 0.0282393945 0.8364210000 112314186 95654128 1786130432 -0.1453022212 0.1124018356 -0.0833537355 420 1305031243.5154008865 0.1638681889 0.1362445983 0.1715396047 0.0284271722 0.8393470000 112316520 95654128 1788035072 -0.1462441236 0.1149943024 -0.0815884843 421 1305031243.5459430218 0.1671795249 0.1363180779 0.1715396047 0.0285073246 0.9308690000 112317498 95654128 1784733696 -0.1517958641 0.1152683496 -0.0836741552 422 1305031243.5779840946 0.1645900160 0.1363850730 0.1715396047 0.0285236118 1.1854330000 112319672 95654128 1786130432 -0.1526321918 0.1199370995 -0.0792483985 423 1305031243.6140549183 0.1669457257 0.1364573204 0.1715396047 0.0288997737 1.1411640000 112321958 95654128 1788162048 -0.1548510343 0.1194258556 -0.0798321962 424 1305031243.6461870670 0.1720766872 0.1365413284 0.1720766872 0.0292595358 1.8663730000 112410400 95654128 1784487936 -0.1610650867 0.1141183227 -0.0845446289 425 1305031243.6782801151 0.1685521901 0.1366166480 0.1720766872 0.0293109753 1.9445590000 112497942 95654128 1785757696 -0.1609378755 0.1106124371 -0.0808572397 426 1305031243.7142961025 0.1693477184 0.1366934815 0.1720766872 0.0297774716 1.0875960000 112585556 95654128 1787916288 -0.1558123380 0.1147091463 -0.0796006694 427 1305031243.7473781109 0.1693986952 0.1367700745 0.1720766872 0.0301158257 0.9873750000 112671774 95654128 1784901632 -0.1550894827 0.1084624156 -0.0798435956 428 1305031243.7790360451 0.1668792963 0.1368404232 0.1720766872 0.0302224575 0.9624990000 112759120 95654128 1786138624 -0.1550308615 0.1068345904 -0.0758122653 429 1305031243.8141930103 0.1683906764 0.1369139669 0.1720766872 0.0309666810 0.9903840000 112846626 95654128 1788162048 -0.1517643929 0.1050252020 -0.0766455829 430 1305031243.8462920189 0.1614256352 0.1369709708 0.1720766872 0.0314447040 1.0207320000 112933244 95654128 1784512512 -0.1380753964 0.0963345394 -0.0725036338 431 1305031243.8788089752 0.1618976891 0.1370288054 0.1720766872 0.0316268704 1.0258480000 113020950 95654128 1785876480 -0.1373593658 0.0939640105 -0.0722689182 432 1305031243.9140000343 0.1618670076 0.1370863012 0.1720766872 0.0319569218 0.9122070000 113108780 95654128 1787781120 -0.1340278983 0.0943116024 -0.0717455521 433 1305031243.9470779896 0.1554177701 0.1371286372 0.1720766872 0.0321860502 0.8929340000 113195146 95654128 1784877056 -0.1251384318 0.0995640233 -0.0652874485 434 1305031243.9816520214 0.1507534683 0.1371600308 0.1720766872 0.0323544330 1.0129470000 113282068 95654128 1786130432 -0.1193892583 0.1021537110 -0.0605167188 435 1305031244.0112700462 0.1462353915 0.1371808937 0.1720766872 0.0324494050 1.0918780000 113369642 95654128 1785622528 -0.1128239855 0.1018983051 -0.0570080988 436 1305031244.0438230038 0.1483445019 0.1372064983 0.1720766872 0.0324678983 1.2105710000 113456032 95654128 1787019264 -0.1126400828 0.1133316308 -0.0548614487 437 1305031244.0818090439 0.1475735009 0.1372302214 0.1720766872 0.0325231599 1.0045430000 113543918 95654128 1784479744 -0.1125251874 0.1182485372 -0.0520239547 438 1305031244.1127901077 0.1462838352 0.1372508918 0.1720766872 0.0326083315 0.9325120000 113544864 95654128 1785876480 -0.1121615469 0.1148196608 -0.0514469258 439 1305031244.1484949589 0.1494701952 0.1372787262 0.1720766872 0.0326096531 0.8105290000 113547134 95654128 1787781120 -0.1159424782 0.1223502904 -0.0517123789 440 1305031244.1824309826 0.1440334320 0.1372940778 0.1720766872 0.0327192593 0.9614610000 113549340 95654128 1784754176 -0.1129689291 0.1265092641 -0.0445998050 441 1305031244.2124009132 0.1395686865 0.1372992356 0.1720766872 0.0328520978 1.0028200000 113550286 95654128 1786130432 -0.1093351543 0.1273618340 -0.0403920487 442 1305031244.2473471165 0.1388302743 0.1373026995 0.1720766872 0.0330383887 1.3447490000 113637132 95654128 1788035072 -0.1084396392 0.1318782717 -0.0383104980 443 1305031244.2831470966 0.1348358989 0.1372971311 0.1720766872 0.0332064888 2.2269960000 113725110 95654128 1784860672 -0.1055610701 0.1348103136 -0.0354243740 444 1305031244.3137950897 0.1295639426 0.1372797140 0.1720766872 0.0333989078 1.4827220000 113725992 95654128 1786257408 -0.1013135090 0.1414286494 -0.0293508004 445 1305031244.3459599018 0.1248276010 0.1372517318 0.1720766872 0.0336058412 1.5284580000 113812426 95654128 1788035072 -0.0972519219 0.1483900845 -0.0237252433 446 1305031244.3808560371 0.1259400696 0.1372263693 0.1720766872 0.0337893009 1.2286200000 113900296 95654128 1784987648 -0.0962994099 0.1512644887 -0.0263821706 447 1305031244.4130189419 0.1239276603 0.1371966183 0.1720766872 0.0340299288 1.7938220000 113986114 95654128 1786384384 -0.0940088034 0.1542585194 -0.0259409584 448 1305031244.4451670647 0.1245541200 0.1371683984 0.1720766872 0.0341096616 2.4357010000 114073996 95654128 1785622528 -0.0949102044 0.1633388698 -0.0239005145 449 1305031244.4806590080 0.1287511438 0.1371496517 0.1720766872 0.0341850845 1.2025380000 114161806 95654128 1787019264 -0.0975006074 0.1679033637 -0.0269544255 450 1305031244.5142281055 0.1298738420 0.1371334833 0.1720766872 0.0343009291 1.0715310000 114248504 95654128 1784606720 -0.0978725627 0.1686991900 -0.0277812481 451 1305031244.5462141037 0.1337134987 0.1371259002 0.1720766872 0.0342922974 0.9087700000 114250710 95654128 1786138624 -0.1036488190 0.1749257147 -0.0261251330 452 1305031244.5808050632 0.1327759922 0.1371162765 0.1720766872 0.0343490410 0.9674120000 114337604 95654128 1788043264 -0.1044851914 0.1760802567 -0.0230441689 453 1305031244.6132769585 0.1330164969 0.1371072262 0.1720766872 0.0344561154 0.9970030000 114424366 95654128 1784868864 -0.1032670960 0.1741482317 -0.0233663935 454 1305031244.6428399086 0.1354678124 0.1371036151 0.1720766872 0.0344505185 1.0900010000 114426508 95654128 1786138624 -0.1064735055 0.1773981154 -0.0225871354 455 1305031244.6806099415 0.1353686303 0.1370998020 0.1720766872 0.0345289841 0.9882790000 114512514 95654128 1788043264 -0.1086328551 0.1794575751 -0.0191399567 456 1305031244.7152500153 0.1372389793 0.1371001072 0.1720766872 0.0345659129 1.0158430000 114600632 95654128 1784758272 -0.1109655276 0.1828477085 -0.0188994557 457 1305031244.7458879948 0.1344022155 0.1370942037 0.1720766872 0.0347971285 1.0849570000 114602806 95654128 1786130432 -0.1080157608 0.1802523434 -0.0177407302 458 1305031244.7818510532 0.1349719316 0.1370895699 0.1720766872 0.0348770760 1.0112940000 114688556 95654128 1788035072 -0.1077245697 0.1806013882 -0.0186820365 459 1305031244.8140940666 0.1286706924 0.1370712281 0.1720766872 0.0356924611 0.9629060000 114776674 95654128 1784860672 -0.1064799502 0.1828626990 -0.0147932898 460 1305031244.8418219090 0.1229650751 0.1370405626 0.1720766872 0.0356935235 0.9427650000 114778784 95654128 1786130432 -0.1027491689 0.1852534860 -0.0093276249 461 1305031244.8818008900 0.1276864558 0.1370202717 0.1720766872 0.0356656671 0.8187080000 114779998 95654128 1788035072 -0.1050055847 0.1900103986 -0.0119750798 462 1305031244.9149079323 0.1288132668 0.1370025076 0.1720766872 0.0356528411 1.0864960000 114866736 95654128 1784606720 -0.1045328677 0.1924878210 -0.0126723805 463 1305031244.9458680153 0.1282082945 0.1369835136 0.1720766872 0.0356172756 0.9966580000 114954890 95654128 1786130432 -0.1034031734 0.1948580742 -0.0117582660 464 1305031244.9818000793 0.1327812672 0.1369744571 0.1720766872 0.0356343433 1.1752310000 114955900 95654128 1788035072 -0.1065640226 0.1984406561 -0.0108235283 465 1305031245.0140550137 0.1225663498 0.1369434719 0.1720766872 0.0356041262 0.9601520000 114958074 95654128 1784733696 -0.0996376127 0.1974973083 -0.0027379598 466 1305031245.0464398861 0.1344615221 0.1369381458 0.1720766872 0.0355773905 1.1441260000 114960280 95654128 1786130432 -0.1054544970 0.2024495751 -0.0112050790 467 1305031245.0817689896 0.1280222535 0.1369190540 0.1720766872 0.0355695072 1.0734480000 114961414 95654128 1787908096 -0.1052773818 0.2010412961 -0.0032802718 468 1305031245.1143150330 0.1254891157 0.1368946310 0.1720766872 0.0355829132 0.8264900000 114963588 95654128 1784881152 -0.1021539196 0.1989589185 -0.0028228040 469 1305031245.1457099915 0.1328200698 0.1368859433 0.1720766872 0.0355726693 0.9061710000 114965826 95654128 1786257408 -0.1071680188 0.1981984675 -0.0084778490 470 1305031245.1818709373 0.1282170564 0.1368674988 0.1720766872 0.0355900243 1.0133670000 115052216 95654128 1785495552 -0.1073009521 0.1934653372 -0.0050732940 471 1305031245.2140939236 0.1281809658 0.1368490561 0.1720766872 0.0357325839 1.3077850000 115140582 95654128 1786892288 -0.1083855852 0.1891763359 -0.0068873363 472 1305031245.2487950325 0.1369344592 0.1368492370 0.1720766872 0.0361001996 1.5421800000 115142852 95654128 1784606720 -0.1165702865 0.1880982667 -0.0146888727 473 1305031245.2807950974 0.1427198797 0.1368616485 0.1720766872 0.0361790328 1.8465490000 115227946 95654128 1786003456 -0.1206719801 0.1842333823 -0.0224346109 474 1305031245.3143179417 0.1330937892 0.1368536995 0.1720766872 0.0363384608 1.8644150000 115316376 95654128 1788162048 -0.1170098037 0.1778327376 -0.0175053813 475 1305031245.3491809368 0.1357316971 0.1368513373 0.1720766872 0.0366070720 2.4130600000 115401658 95654128 1784479744 -0.1198652536 0.1770911813 -0.0213910621 476 1305031245.3806860447 0.1373924017 0.1368524740 0.1720766872 0.0368758174 1.7490550000 115490084 95654128 1785876480 -0.1195206046 0.1738876700 -0.0271431766 477 1305031245.4133110046 0.1466787755 0.1368730742 0.1720766872 0.0370830199 1.4979400000 115575938 95654128 1787781120 -0.1245637834 0.1740315855 -0.0377741233 478 1305031245.4489970207 0.1390182823 0.1368775621 0.1720766872 0.0370655312 1.2901310000 115663228 95654128 1785257984 -0.1112351418 0.1578152776 -0.0442486256 479 1305031245.4846711159 0.1400149316 0.1368841120 0.1720766872 0.0373718140 0.9855230000 115750198 95654128 1786892288 -0.1142144129 0.1599579453 -0.0459961779 480 1305031245.5124320984 0.1441822797 0.1368993165 0.1720766872 0.0375067498 0.9928050000 115838696 95654128 1785266176 -0.1151444912 0.1610065699 -0.0511877984 481 1305031245.5481460094 0.1482102871 0.1369228320 0.1720766872 0.0376662013 0.9112630000 115839706 95654128 1786773504 -0.1172145456 0.1603953242 -0.0573453382 482 1305031245.5786890984 0.1446633637 0.1369388912 0.1720766872 0.0376831909 1.0108070000 115841912 95654128 1784995840 -0.1130565256 0.1594112515 -0.0560071059 483 1305031245.6104750633 0.1455161273 0.1369566495 0.1720766872 0.0377741554 1.4129870000 115844086 95654128 1786519552 -0.1122145429 0.1516074240 -0.0622268915 484 1305031245.6494629383 0.1494033486 0.1369823658 0.1720766872 0.0379832623 1.1903030000 115845128 95654128 1784995840 -0.1153506637 0.1535220295 -0.0661728680 485 1305031245.6802349091 0.1488811970 0.1370068994 0.1720766872 0.0380134581 0.9111600000 115847490 95654128 1786392576 -0.1154223830 0.1571207941 -0.0643161982 486 1305031245.7110319138 0.1478164792 0.1370291414 0.1720766872 0.0380220082 1.4431590000 115934048 95654128 1786011648 -0.1137810722 0.1529064924 -0.0660309196 487 1305031245.7497749329 0.1475474536 0.1370507396 0.1720766872 0.0380782603 2.3147720000 116021590 95654128 1787400192 -0.1127424687 0.1544533670 -0.0654028580 488 1305031245.7818500996 0.1448909938 0.1370668057 0.1720766872 0.0381195706 2.3579290000 116108648 95654128 1785495552 -0.1089668050 0.1534080654 -0.0638133585 489 1305031245.8135690689 0.1450976133 0.1370832286 0.1720766872 0.0382190662 1.7364190000 116281598 95654128 1787400192 -0.1083805561 0.1525481343 -0.0642234758 490 1305031245.8491089344 0.1459867805 0.1371013991 0.1720766872 0.0382725125 1.4586270000 116369176 95654128 1784860672 -0.1092219800 0.1500271708 -0.0666889250 491 1305031245.8820281029 0.1484110057 0.1371244329 0.1720766872 0.0383315827 1.1350610000 116455770 95654128 1786638336 -0.1123690307 0.1509102285 -0.0685243383 492 1305031245.9126079082 0.1492711306 0.1371491213 0.1720766872 0.0383580792 0.8430910000 116616280 95654128 1784733696 -0.1144612730 0.1480014324 -0.0708114430 493 1305031245.9458959103 0.1501780301 0.1371755491 0.1720766872 0.0384204952 1.0303220000 116702158 95654128 1786638336 -0.1163859665 0.1440708488 -0.0738794953 494 1305031245.9808180332 0.1511436850 0.1372038247 0.1720766872 0.0384587427 0.9610720000 116791068 95654128 1784733696 -0.1161314026 0.1435862035 -0.0759554431 495 1305031246.0110030174 0.1513087302 0.1372323195 0.1720766872 0.0384809605 0.9683600000 116791982 95654128 1786384384 -0.1163597330 0.1391822547 -0.0786691755 496 1305031246.0483930111 0.1525914222 0.1372632854 0.1720766872 0.0385825490 0.9292520000 116794636 95654128 1788035072 -0.1196192503 0.1361642033 -0.0818142146 497 1305031246.0805249214 0.1547974348 0.1372985654 0.1720766872 0.0386676557 0.8021810000 116880338 95654128 1785114624 -0.1233640835 0.1335029900 -0.0854865015 498 1305031246.1123559475 0.1589536518 0.1373420495 0.1720766872 0.0387859518 0.9124650000 116968056 95654128 1786798080 -0.1274676323 0.1322820187 -0.0910401642 499 1305031246.1484489441 0.1582718790 0.1373839930 0.1720766872 0.0388962140 0.8608420000 116970294 95654128 1784766464 -0.1240792423 0.1299407184 -0.0921443701 500 1305031246.1805961132 0.1585365981 0.1374262982 0.1720766872 0.0389514981 1.2622660000 117057356 95654128 1786384384 -0.1227464899 0.1269082576 -0.0937963426 501 1305031246.2111370564 0.1618800461 0.1374751081 0.1720766872 0.0390835352 2.4680030000 117145074 95654128 1784733696 -0.1298902482 0.1230185330 -0.0985022858 502 1305031246.2469689846 0.1640183032 0.1375279830 0.1720766872 0.0392381438 1.0922720000 117147344 95654128 1786130432 -0.1326813549 0.1220421493 -0.1014292687 503 1305031246.2796959877 0.1645614058 0.1375817274 0.1720766872 0.0393189933 0.9679840000 117149690 95654128 1788035072 -0.1341779381 0.1165425032 -0.1041480750 504 1305031246.3124730587 0.1671746373 0.1376404435 0.1720766872 0.0394641850 0.8660830000 117234388 95654128 1785368576 -0.1357807666 0.1168582812 -0.1066886261 505 1305031246.3482720852 0.1682663262 0.1377010888 0.1720766872 0.0396106547 1.0870560000 117323546 95654128 1786892288 -0.1393071562 0.1124184728 -0.1087443605 506 1305031246.3782060146 0.1711468846 0.1377671872 0.1720766872 0.0398263077 0.9652900000 117325704 95654128 1784987648 -0.1421049982 0.1147638634 -0.1105865911 507 1305031246.4156370163 0.1711296141 0.1378329908 0.1720766872 0.0400086747 0.9022000000 117409922 95654128 1786511360 -0.1438730955 0.1158543453 -0.1098042279 508 1305031246.4452888966 0.1724783629 0.1379011904 0.1724783629 0.0401194264 0.8905010000 117499048 95654128 1784987648 -0.1471800357 0.1142495573 -0.1111639738 509 1305031246.4774649143 0.1735679060 0.1379712625 0.1735679060 0.0402440026 0.8080350000 117500198 95654128 1786519552 -0.1498129219 0.1141792089 -0.1119957641 510 1305031246.5163950920 0.1739793271 0.1380418665 0.1739793271 0.0404007200 0.8843300000 117587568 95654128 1784741888 -0.1536332369 0.1152423918 -0.1118445843 511 1305031246.5491750240 0.1716253161 0.1381075876 0.1739793271 0.0405579762 0.9852580000 117676854 95654128 1786265600 -0.1532664448 0.1186183468 -0.1089474037 512 1305031246.5795109272 0.1690101624 0.1381679442 0.1739793271 0.0406696763 1.0272140000 117677800 95654128 1785503744 -0.1554152817 0.1226215586 -0.1058891341 513 1305031246.6164529324 0.1714586318 0.1382328383 0.1739793271 0.0407552642 1.1685300000 117845514 95654128 1786900480 -0.1608825028 0.1224892139 -0.1087257490 514 1305031246.6477630138 0.1703358144 0.1382952954 0.1739793271 0.0408187207 0.8000300000 117977840 95654128 1784614912 -0.1595630497 0.1255625933 -0.1076345146 515 1305031246.6807579994 0.1703796238 0.1383575951 0.1739793271 0.0409294980 0.9717150000 117978990 95654128 1786011648 -0.1657767147 0.1284749061 -0.1081338897 516 1305031246.7169740200 0.1696298122 0.1384182002 0.1739793271 0.0410720067 0.8675420000 118106740 95654128 1787789312 -0.1659850180 0.1305984259 -0.1088646501 517 1305031246.7491660118 0.1678955257 0.1384752163 0.1739793271 0.0411724146 0.7444140000 118155162 95654128 1784909824 -0.1676574945 0.1333988607 -0.1083705947 518 1305031246.7808170319 0.1674316823 0.1385311168 0.1739793271 0.0412561455 0.8090470000 118281596 95654128 1786257408 -0.1704708338 0.1380412132 -0.1082893386 519 1305031246.8168079853 0.1682416350 0.1385883625 0.1739793271 0.0413058127 1.0396680000 118330158 95654128 1785622528 -0.1688183546 0.1377365291 -0.1111709997 520 1305031246.8488121033 0.1680655479 0.1386450494 0.1739793271 0.0413466521 0.9131410000 118456392 95654128 1787019264 -0.1694065481 0.1391812265 -0.1124727279 521 1305031246.8806428909 0.1653830707 0.1386963700 0.1739793271 0.0414426040 0.8397220000 118503814 95654128 1784733696 -0.1718218625 0.1440196186 -0.1109152809 522 1305031246.9166710377 0.1637829542 0.1387444286 0.1739793271 0.0415320677 1.1290420000 118506148 95654128 1786130432 -0.1732844412 0.1481179297 -0.1124534309 523 1305031246.9495339394 0.1666672826 0.1387978183 0.1739793271 0.0415272336 1.0287540000 118632494 95654128 1788035072 -0.1721592844 0.1492160559 -0.1176472381 524 1305031246.9775969982 0.1699585617 0.1388572854 0.1739793271 0.0415255054 0.8050140000 118679744 95654128 1784860672 -0.1753520668 0.1509400159 -0.1228317693 525 1305031247.0167899132 0.1639382392 0.1389050587 0.1739793271 0.0416183974 0.9484710000 118806526 95654128 1786257408 -0.1723059118 0.1544483751 -0.1202051193 526 1305031247.0479340553 0.1651577950 0.1389549688 0.1739793271 0.0415956684 1.2244280000 118855176 95654128 1784606720 -0.1744697392 0.1559147239 -0.1239631101 527 1305031247.0778899193 0.1632952839 0.1390011554 0.1739793271 0.0415949277 1.1247150000 118981902 95654128 1786003456 -0.1719880253 0.1600611061 -0.1242416352 528 1305031247.1162130833 0.1668806076 0.1390539573 0.1739793271 0.0415680521 0.8402980000 119030692 95654128 1785749504 -0.1748875678 0.1646956503 -0.1288886666 529 1305031247.1473660469 0.1711704582 0.1391146691 0.1739793271 0.0415698197 1.0254990000 119031702 95654128 1787019264 -0.1774221808 0.1673010141 -0.1332444102 530 1305031247.1796920300 0.1672518253 0.1391677580 0.1739793271 0.0415315517 0.9730490000 119033972 95654128 1784733696 -0.1729982346 0.1648053080 -0.1313280314 531 1305031247.2169430256 0.1691991985 0.1392243144 0.1739793271 0.0415090802 0.9837950000 119036338 95654128 1786130432 -0.1741729379 0.1660159230 -0.1331344992 532 1305031247.2487928867 0.1690814346 0.1392804368 0.1739793271 0.0414832191 0.9287910000 119037316 95654128 1788162048 -0.1750541478 0.1695872098 -0.1317784041 533 1305031247.2794220448 0.1735964268 0.1393448196 0.1739793271 0.0414633473 0.8446300000 119039694 95654128 1784860672 -0.1788927466 0.1693991274 -0.1355676204 534 1305031247.3166429996 0.1677898169 0.1393980873 0.1739793271 0.0414775400 0.8800600000 119042060 95654128 1786130432 -0.1731516272 0.1641366780 -0.1314890087 535 1305031247.3477900028 0.1714304239 0.1394579609 0.1739793271 0.0415484193 0.8949990000 119043038 95654128 1788051456 -0.1772186905 0.1650542468 -0.1339545846 536 1305031247.3786110878 0.1722339392 0.1395191101 0.1739793271 0.0415666044 0.8642980000 119045276 95654128 1784987648 -0.1787088215 0.1656195819 -0.1344840825 537 1305031247.4168620110 0.1693730950 0.1395747041 0.1739793271 0.0416555780 0.9887540000 119047674 95654128 1786257408 -0.1780077666 0.1640867442 -0.1320935786 538 1305031247.4487700462 0.1736421883 0.1396380266 0.1739793271 0.0418329894 1.0613190000 119173536 95654128 1785749504 -0.1813206673 0.1663362086 -0.1346854270 539 1305031247.4802629948 0.1750016063 0.1397036362 0.1750016063 0.0419008641 0.8904100000 119222530 95654128 1787400192 -0.1846344769 0.1679679751 -0.1347696781 540 1305031247.5178461075 0.1735768467 0.1397663643 0.1750016063 0.0420414810 1.0181490000 119224928 95654128 1784606720 -0.1832613796 0.1682657301 -0.1322164536 541 1305031247.5459010601 0.1744166166 0.1398304129 0.1750016063 0.0421476353 0.9327170000 119225842 95654128 1786003456 -0.1853243709 0.1688064784 -0.1323784292 542 1305031247.5779209137 0.1746345162 0.1398946271 0.1750016063 0.0422581986 0.8226210000 119352668 95654128 1787908096 -0.1862830371 0.1696397513 -0.1320393533 543 1305031247.6152799129 0.1753469408 0.1399599168 0.1753469408 0.0424468461 0.9911850000 119401702 95654128 1784897536 -0.1846875399 0.1712680906 -0.1309754997 544 1305031247.6484000683 0.1757361740 0.1400256820 0.1757361740 0.0425943966 0.8787980000 119402712 95654128 1786273792 -0.1846366823 0.1693462729 -0.1311337799 545 1305031247.6835579872 0.1754898131 0.1400907538 0.1757361740 0.0427579409 0.8507500000 119529042 95654128 1785495552 -0.1850897670 0.1678570360 -0.1299468726 546 1305031247.7159609795 0.1752497256 0.1401551475 0.1757361740 0.0429977563 0.8499310000 119576816 95654128 1787027456 -0.1825334728 0.1680258512 -0.1282832772 547 1305031247.7469019890 0.1736105233 0.1402163090 0.1757361740 0.0432853852 0.7668440000 119702734 95654128 1784614912 -0.1792334318 0.1652935892 -0.1270270348 548 1305031247.7822608948 0.1705690622 0.1402716973 0.1757361740 0.0434495870 0.8571700000 119751844 95654128 1786011648 -0.1799468100 0.1610036343 -0.1259864867 549 1305031247.8139829636 0.1748819351 0.1403347396 0.1757361740 0.0437584038 1.0141710000 119876874 95654128 1787916288 -0.1826062500 0.1543974131 -0.1322814375 550 1305031247.8484420776 0.1690617353 0.1403869705 0.1757361740 0.0440072138 0.8660100000 120050044 95654128 1784868864 -0.1628720164 0.1469283998 -0.1309742182 551 1305031247.8820719719 0.1706425995 0.1404418809 0.1757361740 0.0440595001 1.1435950000 120224318 95654128 1786257408 -0.1671922654 0.1339514703 -0.1365854889 552 1305031247.9173319340 0.1712955236 0.1404977752 0.1757361740 0.0440472642 0.9263490000 120396180 95654128 1785622528 -0.1709128469 0.1435883343 -0.1377300471 553 1305031247.9496860504 0.1685850918 0.1405485660 0.1757361740 0.0441563298 0.9339480000 120445326 95654128 1787146240 -0.1610121131 0.1510745585 -0.1354798675 554 1305031247.9861450195 0.1692119539 0.1406003050 0.1757361740 0.0443341146 1.0399030000 120572784 95654128 1784733696 -0.1556811631 0.1392069310 -0.1417301148 555 1305031248.0181560516 0.1689610630 0.1406514054 0.1757361740 0.0443085078 1.0099320000 120745990 95654128 1786003456 -0.1572055817 0.1423477083 -0.1424193978 556 1305031248.0499138832 0.1710250974 0.1407060344 0.1757361740 0.0443461367 0.8463970000 120795220 95654128 1785544704 -0.1583445817 0.1477196068 -0.1443653405 557 1305031248.0857460499 0.1653914452 0.1407503529 0.1757361740 0.0445549528 0.9309220000 120920922 95654128 1784606720 -0.1440536529 0.1419838220 -0.1428442895 558 1305031248.1175789833 0.1630359739 0.1407902913 0.1757361740 0.0445891947 0.7833410000 121092684 95654128 1786003456 -0.1362546831 0.1357730776 -0.1435572058 559 1305031248.1493461132 0.1646206975 0.1408329217 0.1757361740 0.0446026295 0.9457210000 121265550 95654128 1785544704 -0.1365622133 0.1415567845 -0.1447307318 560 1305031248.1848630905 0.1596424580 0.1408665102 0.1757361740 0.0447744534 0.9230930000 121314904 95654128 1784606720 -0.1219134927 0.1413969100 -0.1405251920 561 1305031248.2167689800 0.1567801982 0.1408948768 0.1757361740 0.0448100318 0.9091740000 121439022 95654128 1785876480 -0.1141242534 0.1409115344 -0.1387432069 562 1305031248.2488510609 0.1602417082 0.1409293018 0.1757361740 0.0448315548 0.9077150000 121611608 95654128 1788035072 -0.1184226200 0.1437912285 -0.1425940543 563 1305031248.2847399712 0.1573024243 0.1409583837 0.1757361740 0.0449255768 0.8696740000 121659974 95654128 1784860672 -0.1093566269 0.1505678594 -0.1370910853 564 1305031248.3161809444 0.1524986774 0.1409788452 0.1757361740 0.0450084410 0.9481620000 121785416 95654128 1786130432 -0.1009905413 0.1550212353 -0.1300789416 565 1305031248.3488430977 0.1526463032 0.1409994956 0.1757361740 0.0450802020 1.0605240000 121834818 95654128 1785495552 -0.1017203629 0.1474194825 -0.1353168488 566 1305031248.3881969452 0.1558426321 0.1410257202 0.1757361740 0.0450799610 0.8866730000 121959156 95654128 1786892288 -0.1061064973 0.1531463563 -0.1384903044 567 1305031248.4155070782 0.1539679468 0.1410485460 0.1757361740 0.0451264178 1.0012600000 122008570 95654128 1784606720 -0.1020097286 0.1562525332 -0.1360883713 568 1305031248.4482519627 0.1519586444 0.1410677539 0.1757361740 0.0451487724 0.8162980000 122134836 95654128 1786003456 -0.0992894620 0.1545871794 -0.1367079169 569 1305031248.4852969646 0.1487338096 0.1410812268 0.1757361740 0.0451977789 0.9025340000 122183302 95654128 1788035072 -0.0967021361 0.1508648843 -0.1375761479 570 1305031248.5154309273 0.1515992880 0.1410996795 0.1757361740 0.0451735292 0.8899630000 122185492 95654128 1784860672 -0.0969765633 0.1595468968 -0.1376984417 571 1305031248.5470030308 0.1485519111 0.1411127307 0.1757361740 0.0452030354 0.7430510000 122310902 95654128 1786273792 -0.0909474567 0.1674599648 -0.1305972934 572 1305031248.5860579014 0.1442407221 0.1411181992 0.1757361740 0.0452651211 1.0042010000 122483432 95654128 1785495552 -0.0874740034 0.1612800807 -0.1323145628 573 1305031248.6180379391 0.1489383131 0.1411318469 0.1757361740 0.0453099166 0.9388670000 122533010 95654128 1787019264 -0.0920393839 0.1621867269 -0.1391544193 574 1305031248.6494390965 0.1501796842 0.1411476097 0.1757361740 0.0452965174 1.0563750000 122658804 95654128 1784606720 -0.0947329700 0.1643959582 -0.1417323947 575 1305031248.6860280037 0.1493775398 0.1411619226 0.1757361740 0.0453378193 1.0017450000 122707434 95654128 1786130432 -0.0946399271 0.1691914201 -0.1408918351 576 1305031248.7199230194 0.1459819227 0.1411702906 0.1757361740 0.0453520621 0.9689950000 122831272 95654128 1785434112 -0.0915353224 0.1718109697 -0.1377926618 577 1305031248.7498369217 0.1445928067 0.1411762222 0.1757361740 0.0454239534 1.0486880000 122880938 95654128 1784406016 -0.0902781337 0.1759241372 -0.1359764785 578 1305031248.7856750488 0.1386465132 0.1411718456 0.1757361740 0.0454746607 0.9479380000 123004248 95654128 1785749504 -0.0816823393 0.1727545261 -0.1321029961 579 1305031248.8181409836 0.1407516003 0.1411711197 0.1757361740 0.0454515184 0.9211980000 123053990 95654128 1787781120 -0.0835392922 0.1865564585 -0.1281355619 580 1305031248.8496789932 0.1369548738 0.1411638504 0.1757361740 0.0454914992 0.8652690000 123177908 95654128 1784860672 -0.0774959475 0.1887251139 -0.1229755133 581 1305031248.8855929375 0.1337576807 0.1411511031 0.1757361740 0.0455060460 0.9348490000 123226638 95654128 1786130432 -0.0734764785 0.1903145015 -0.1187409237 582 1305031248.9178819656 0.1356725544 0.1411416898 0.1757361740 0.0454765663 1.0397040000 123351820 95654128 1785622528 -0.0751795024 0.1973865479 -0.1171533465 583 1305031248.9526810646 0.1303416789 0.1411231649 0.1757361740 0.0454949106 0.9902470000 123400454 95654128 1787154432 -0.0704037696 0.1990731955 -0.1105201170 584 1305031248.9845540524 0.1297183335 0.1411036360 0.1757361740 0.0454872281 1.0570390000 123526344 95654128 1784614912 -0.0682321042 0.2015062869 -0.1089878008 585 1305031249.0169510841 0.1322491765 0.1410885002 0.1757361740 0.0454876909 0.8924610000 123576202 95654128 1786011648 -0.0682089701 0.2033364624 -0.1103468016 586 1305031249.0523660183 0.1317770779 0.1410726104 0.1757361740 0.0454629951 0.8404590000 123700788 95654128 1785442304 -0.0682260767 0.2043764442 -0.1082583219 587 1305031249.0845029354 0.1338747591 0.1410603483 0.1757361740 0.0454465242 0.8730310000 123750846 95654128 1784614912 -0.0707140267 0.2064092755 -0.1067483053 588 1305031249.1168839931 0.1299039572 0.1410413749 0.1757361740 0.0454138062 0.7990320000 123753052 95654128 1785884672 -0.0690693185 0.2041475028 -0.1016179472 589 1305031249.1534469128 0.1353665739 0.1410317402 0.1757361740 0.0453834247 0.8971360000 123754062 95654128 1788043264 -0.0759900361 0.2080901563 -0.1011254042 590 1305031249.1847391129 0.1391361356 0.1410285273 0.1757361740 0.0453618196 0.7010710000 123756268 95654128 1784885248 -0.0819271877 0.2096372247 -0.1014901102 591 1305031249.2168650627 0.1325659454 0.1410142083 0.1757361740 0.0453386603 0.9730680000 123758458 95654128 1786138624 -0.0751883611 0.2006074339 -0.0988716260 592 1305031249.2532238960 0.1405599862 0.1410134410 0.1757361740 0.0453104449 0.9382640000 123759468 95654128 1787781120 -0.0832555145 0.2032572925 -0.1029589102 593 1305031249.2848041058 0.1328427941 0.1409996625 0.1757361740 0.0453041715 1.0791250000 123884186 95654128 1784733696 -0.0792194605 0.1978642792 -0.0962900668 594 1305031249.3174340725 0.1304738075 0.1409819422 0.1757361740 0.0452870052 0.8517710000 123934280 95654128 1786130432 -0.0804253966 0.1989704221 -0.0912971944 595 1305031249.3527359962 0.1334002912 0.1409691999 0.1757361740 0.0452526940 0.8651770000 123935242 95654128 1788035072 -0.0877609774 0.2052626163 -0.0881557688 596 1305031249.3847539425 0.1221709475 0.1409376592 0.1757361740 0.0452475656 1.0128580000 123937448 95654128 1784733696 -0.0768227130 0.1963779777 -0.0813199952 597 1305031249.4178340435 0.1192557812 0.1409013412 0.1757361740 0.0452892893 1.2530220000 123939654 95654128 1786130432 -0.0779670775 0.1952611208 -0.0789443031 598 1305031249.4537220001 0.1247484758 0.1408743297 0.1757361740 0.0453314428 1.9505420000 124063948 95654128 1788035072 -0.0830197483 0.1962316185 -0.0819858685 599 1305031249.4859149456 0.1301412433 0.1408564114 0.1757361740 0.0453754517 1.0472090000 124114222 95654128 1784860672 -0.0868274346 0.1963225901 -0.0879407451 600 1305031249.5177340508 0.1290836334 0.1408367901 0.1757361740 0.0453833412 0.8234670000 124115168 95654128 1786273792 -0.0857060403 0.1926608980 -0.0897985995 601 1305031249.5543251038 0.1319651306 0.1408220286 0.1757361740 0.0455050044 0.8654510000 124240246 95654128 1788035072 -0.0845530704 0.1876994222 -0.0964816511 602 1305031249.5859050751 0.1400630176 0.1408207677 0.1757361740 0.0456940899 0.7574690000 124290444 95654128 1784860672 -0.0919154361 0.1919552386 -0.1016911566 603 1305031249.6180789471 0.1442628056 0.1408264759 0.1757361740 0.0457127162 0.7769850000 124414138 95654128 1786257408 -0.0971006155 0.1856148690 -0.1089357138 604 1305031249.6542129517 0.1432613879 0.1408305072 0.1757361740 0.0459249154 0.7469970000 124585912 95654128 1785495552 -0.0929824933 0.1831572950 -0.1086783111 605 1305031249.6856739521 0.1434790045 0.1408348849 0.1757361740 0.0460512477 0.9135370000 124758442 95654128 1787019264 -0.0931627601 0.1876795292 -0.1038082540 606 1305031249.7177898884 0.1462466419 0.1408438152 0.1757361740 0.0461152354 0.8780920000 124930688 95654128 1784737792 -0.0975617766 0.1835235655 -0.1086001173 607 1305031249.7539620399 0.1438137293 0.1408487080 0.1757361740 0.0461662683 1.0446430000 125103694 95654128 1786003456 -0.0872457623 0.1824046075 -0.1035665423 608 1305031249.7854170799 0.1430666149 0.1408523559 0.1757361740 0.0462021429 1.0123270000 125276112 95654128 1785622528 -0.0852522478 0.1791990846 -0.1033208743 609 1305031249.8186020851 0.1460408568 0.1408608756 0.1757361740 0.0462120093 1.2645150000 125448710 95654128 1787019264 -0.0884691700 0.1727365851 -0.1085522696 610 1305031249.8537468910 0.1468340904 0.1408706677 0.1757361740 0.0463121558 1.0084730000 125621264 95654128 1784733696 -0.0824940801 0.1687695682 -0.1094531417 611 1305031249.8855249882 0.1503203511 0.1408861337 0.1757361740 0.0463402236 1.0022610000 125794146 95654128 1786130432 -0.0869324133 0.1638208479 -0.1139726192 612 1305031249.9170649052 0.1506081223 0.1409020193 0.1757361740 0.0463690554 1.0314700000 125965708 95654128 1785749504 -0.0882362649 0.1586763263 -0.1146566793 613 1305031249.9533979893 0.1523696035 0.1409207266 0.1757361740 0.0463729575 0.9339380000 126016246 95654128 1787273216 -0.0876771882 0.1534687132 -0.1164633781 614 1305031249.9851789474 0.1560101211 0.1409453021 0.1757361740 0.0463812146 0.8130630000 126140968 95654128 1784868864 -0.0905993804 0.1483557522 -0.1211684048 615 1305031250.0164399147 0.1584247351 0.1409737240 0.1757361740 0.0463635063 0.8900090000 126190242 95654128 1786138624 -0.0910430327 0.1449712962 -0.1233531907 616 1305031250.0531940460 0.1584904194 0.1410021602 0.1757361740 0.0464288869 1.2152300000 126314500 95654128 1787932672 -0.0931711420 0.1361460239 -0.1249264926 617 1305031250.0845069885 0.1608565897 0.1410343392 0.1757361740 0.0465249920 1.0777980000 126363926 95654128 1784733696 -0.0976827443 0.1323549300 -0.1270330101 618 1305031250.1208500862 0.1623972356 0.1410689069 0.1757361740 0.0466455241 0.9813410000 126487496 95654128 1786138624 -0.1001817212 0.1360039413 -0.1242386475 619 1305031250.1532480717 0.1642315686 0.1411063264 0.1757361740 0.0469122102 0.8927720000 126538086 95654128 1785503744 -0.1045733243 0.1398260593 -0.1207423136 620 1305031250.1853280067 0.1654669344 0.1411456177 0.1757361740 0.0469204683 0.7836990000 126661308 95654128 1786900480 -0.1057451293 0.1408621669 -0.1190339997 621 1305031250.2214460373 0.1653518230 0.1411845971 0.1757361740 0.0469213097 0.9001490000 126712070 95654128 1784750080 -0.1063341126 0.1389266849 -0.1176314950 622 1305031250.2537350655 0.1631869525 0.1412199707 0.1757361740 0.0470216099 0.7899090000 126836840 95654128 1786130432 -0.1151012182 0.1326582581 -0.1156407073 623 1305031250.2852239609 0.1633313447 0.1412554625 0.1757361740 0.0470359004 0.9031970000 126886398 95654128 1785622528 -0.1170551851 0.1287456155 -0.1157862544 624 1305031250.3208620548 0.1630162746 0.1412903356 0.1757361740 0.0470672815 1.0453450000 127009420 95654128 1787019264 -0.1193595305 0.1260027885 -0.1149528623 625 1305031250.3517000675 0.1646445245 0.1413277023 0.1757361740 0.0470831326 1.0857420000 127060142 95654128 1784766464 -0.1237851754 0.1242244467 -0.1163021997 626 1305031250.3851490021 0.1701121777 0.1413736839 0.1757361740 0.0470913069 0.8495770000 127182148 95654128 1786130432 -0.1295883060 0.1213987619 -0.1202099547 627 1305031250.4215359688 0.1753827631 0.1414279248 0.1757361740 0.0471078771 0.9898890000 127233042 95654128 1785622528 -0.1364351511 0.1195173040 -0.1243539676 628 1305031250.4540181160 0.1755594611 0.1414822744 0.1757361740 0.0471959535 1.0996660000 127358808 95654128 1787019264 -0.1389353573 0.1201652959 -0.1226014867 629 1305031250.4856131077 0.1702133566 0.1415279518 0.1757361740 0.0472108158 0.9065640000 127408482 95654128 1784750080 -0.1408066750 0.1202274635 -0.1153817102 630 1305031250.5215380192 0.1738684475 0.1415792859 0.1757361740 0.0471932472 1.0289570000 127410784 95654128 1786130432 -0.1429573894 0.1219481006 -0.1172114462 631 1305031250.5536580086 0.1767330170 0.1416349971 0.1767330170 0.0471812431 0.9050560000 127413054 95654128 1787908096 -0.1447115690 0.1243313327 -0.1173627824 632 1305031250.5853788853 0.1716305614 0.1416824584 0.1767330170 0.0471804755 0.8668790000 127535676 95654128 1784987648 -0.1463748217 0.1240310371 -0.1112517491 633 1305031250.6213030815 0.1695044190 0.1417264109 0.1767330170 0.0471667924 0.9696960000 127586698 95654128 1786257408 -0.1495507360 0.1242211908 -0.1074907184 634 1305031250.6535439491 0.1723356098 0.1417746904 0.1767330170 0.0471893904 0.8168770000 127589000 95654128 1785749504 -0.1535090655 0.1260248721 -0.1086355746 635 1305031250.6852970123 0.1689239591 0.1418174452 0.1767330170 0.0472167260 0.8139040000 127590086 95654128 1787019264 -0.1494797468 0.1302847862 -0.1036918238 636 1305031250.7216401100 0.1655490249 0.1418547590 0.1767330170 0.0471972037 1.1013170000 127713364 95654128 1784733696 -0.1545261741 0.1307218671 -0.0993433073 637 1305031250.7534279823 0.1705286056 0.1418997729 0.1767330170 0.0471736821 1.0118480000 127763114 95654128 1786003456 -0.1626463532 0.1311844289 -0.1024366170 638 1305031250.7853651047 0.1703386903 0.1419443480 0.1767330170 0.0471493888 0.9865220000 127765352 95654128 1788035072 -0.1599385589 0.1356867701 -0.1010011435 639 1305031250.8217930794 0.1660412997 0.1419820584 0.1767330170 0.0471155872 0.9595430000 127767718 95654128 1784733696 -0.1574658900 0.1380929798 -0.0959324017 640 1305031250.8538279533 0.1665332466 0.1420204196 0.1767330170 0.0470908481 1.1141250000 127768712 95654128 1786003456 -0.1676982939 0.1381940246 -0.0955272168 641 1305031250.8820140362 0.1665891111 0.1420587483 0.1767330170 0.0470569116 1.1004720000 127771026 95654128 1787908096 -0.1698211432 0.1395892948 -0.0949252844 642 1305031250.9217998981 0.1668937206 0.1420974321 0.1767330170 0.0470240892 0.8915440000 127895156 95654128 1784606720 -0.1710615456 0.1411672235 -0.0950715393 643 1305031250.9535419941 0.1719928980 0.1421439258 0.1767330170 0.0470066938 0.9030330000 127945094 95654128 1786003456 -0.1759533882 0.1395105571 -0.1005386934 644 1305031250.9853079319 0.1769717336 0.1421980062 0.1769717336 0.0469774147 0.8940340000 127947284 95654128 1788035072 -0.1830130965 0.1387173086 -0.1049575061 645 1305031251.0214879513 0.1676435024 0.1422374566 0.1769717336 0.0469571527 0.9263450000 127949586 95654128 1784733696 -0.1720324457 0.1413598508 -0.0968084112 646 1305031251.0534679890 0.1692735851 0.1422793082 0.1769717336 0.0469664779 0.7863020000 127950564 95654128 1786130432 -0.1733664721 0.1398542970 -0.0994209200 647 1305031251.0851860046 0.1725478917 0.1423260912 0.1769717336 0.0469701378 0.8273750000 127952942 95654128 1788035072 -0.1793233603 0.1363651454 -0.1038575470 648 1305031251.1214449406 0.1770316660 0.1423796492 0.1770316660 0.0469772782 0.9821370000 127955244 95654128 1784733696 -0.1813424975 0.1339376867 -0.1093170196 649 1305031251.1537809372 0.1773367077 0.1424335121 0.1773367077 0.0470787155 0.9509440000 128078402 95654128 1786130432 -0.1772729754 0.1319981664 -0.1119671538 650 1305031251.1851599216 0.1765269935 0.1424859636 0.1773367077 0.0471178750 0.7982410000 128129680 95654128 1785495552 -0.1729898304 0.1262563318 -0.1145684794 651 1305031251.2204658985 0.1763855368 0.1425380367 0.1773367077 0.0471525836 1.0941590000 128253726 95654128 1787027456 -0.1705467552 0.1220275983 -0.1176936403 652 1305031251.2524240017 0.1720597893 0.1425833155 0.1773367077 0.0472248606 1.3785110000 128303788 95654128 1784741888 -0.1600220799 0.1238761023 -0.1157957837 653 1305031251.2844820023 0.1726076603 0.1426292946 0.1773367077 0.0474385198 1.7607780000 128428214 95654128 1786138624 -0.1564296633 0.1195588410 -0.1191383749 654 1305031251.3190040588 0.1698512137 0.1426709183 0.1773367077 0.0475692548 1.2012800000 128599484 95654128 1785630720 -0.1489500999 0.1160125211 -0.1195924208 655 1305031251.3532440662 0.1696608067 0.1427121242 0.1773367077 0.0476773175 1.0137730000 128650874 95654128 1787019264 -0.1471858919 0.1130348966 -0.1221543625 656 1305031251.3870069981 0.1680518836 0.1427507519 0.1773367077 0.0477372034 0.8661850000 128774380 95654128 1784733696 -0.1364607215 0.1177380607 -0.1205495521 657 1305031251.4210500717 0.1684407294 0.1427898539 0.1773367077 0.0478434167 0.8457620000 128824602 95654128 1786257408 -0.1349157095 0.1134018824 -0.1230765432 658 1305031251.4496629238 0.1661742926 0.1428253925 0.1773367077 0.0479207923 0.8373300000 128947368 95654128 1785495552 -0.1281113774 0.1119212359 -0.1221101284 659 1305031251.4890139103 0.1638966799 0.1428573672 0.1773367077 0.0480217584 0.7691180000 128999082 95654128 1787019264 -0.1231034398 0.1150585636 -0.1198018044 660 1305031251.5207729340 0.1612810940 0.1428852819 0.1773367077 0.0481344920 0.9667550000 129120648 95654128 1784733696 -0.1168828532 0.1141690984 -0.1183418259 661 1305031251.5530450344 0.1576596051 0.1429076334 0.1773367077 0.0482650678 0.9139150000 129292710 95654128 1786130432 -0.1101112962 0.1113418192 -0.1166549623 662 1305031251.5887598991 0.1574675292 0.1429296272 0.1773367077 0.0483014209 1.8249770000 129465696 95654128 1785749504 -0.1086796150 0.1139575019 -0.1159192100 663 1305031251.6208739281 0.1580186784 0.1429523859 0.1773367077 0.0483468529 1.0223060000 129516038 95654128 1787273216 -0.1077921540 0.1169189215 -0.1165570691 664 1305031251.6528749466 0.1587652415 0.1429762005 0.1773367077 0.0484228334 1.2825820000 129640128 95654128 1784733696 -0.1084580272 0.1158635318 -0.1188993976 665 1305031251.6897680759 0.1614944488 0.1430040475 0.1773367077 0.0484623734 1.6826420000 129812862 95654128 1786130432 -0.1117657200 0.1190504804 -0.1205861792 666 1305031251.7204608917 0.1604502499 0.1430302429 0.1773367077 0.0485385703 0.9070090000 129984260 95654128 1785495552 -0.1099058688 0.1207168624 -0.1195849776 667 1305031251.7531440258 0.1546890736 0.1430477225 0.1773367077 0.0486523219 0.8668350000 130035922 95654128 1787019264 -0.1028316021 0.1143506169 -0.1180388182 668 1305031251.7892498970 0.1574919075 0.1430693455 0.1773367077 0.0486920198 0.9463310000 130038208 95654128 1784479744 -0.1044201031 0.1168598458 -0.1198586524 669 1305031251.8209791183 0.1620092839 0.1430976563 0.1773367077 0.0487376425 1.0437960000 130160262 95654128 1785876480 -0.1091202572 0.1220656186 -0.1230336204 670 1305031251.8537969589 0.1542168558 0.1431142521 0.1773367077 0.0488719680 0.8762380000 130212004 95654128 1787908096 -0.1018768772 0.1169435382 -0.1185612008 671 1305031251.8896539211 0.1535563171 0.1431298141 0.1773367077 0.0488916933 0.8041330000 130334138 95654128 1784893440 -0.0998759344 0.1109885797 -0.1208554953 672 1305031251.9219300747 0.1546347886 0.1431469346 0.1773367077 0.0489016369 0.9450240000 130385956 95654128 1786384384 -0.1012534946 0.1217856258 -0.1180816665 673 1305031251.9538369179 0.1502975225 0.1431575595 0.1773367077 0.0489182748 0.9596750000 130509150 95654128 1784479744 -0.0977483615 0.1310873926 -0.1095237434 674 1305031251.9898068905 0.1486652046 0.1431657311 0.1773367077 0.0489247991 0.8473770000 130559768 95654128 1786003456 -0.0948039293 0.1297316551 -0.1091691852 675 1305031252.0221600533 0.1464828998 0.1431706454 0.1773367077 0.0489529756 0.8469160000 130562006 95654128 1787908096 -0.0953747630 0.1299372315 -0.1070299968 676 1305031252.0537619591 0.1457761675 0.1431744997 0.1773367077 0.0489608738 0.9469170000 130684740 95654128 1784860672 -0.0961420238 0.1361809373 -0.1052720621 677 1305031252.0895619392 0.1441067308 0.1431758767 0.1773367077 0.0490350580 0.8511840000 130735530 95654128 1786257408 -0.0949575529 0.1451847553 -0.1007475778 678 1305031252.1221520901 0.1400203556 0.1431712226 0.1773367077 0.0491165513 1.2286660000 130858632 95654128 1785622528 -0.0908982158 0.1469196677 -0.0974707976 679 1305031252.1539709568 0.1351833344 0.1431594584 0.1773367077 0.0492796369 1.4995160000 130910490 95654128 1787019264 -0.0867605880 0.1490736455 -0.0935377255 680 1305031252.1897890568 0.1319666803 0.1431429984 0.1773367077 0.0492852317 1.5736980000 131032700 95654128 1784733696 -0.0856829733 0.1576253921 -0.0869270340 681 1305031252.2220859528 0.1428868771 0.1431426223 0.1773367077 0.0492618505 2.3154860000 131084698 95654128 1786265600 -0.0987464115 0.1738145053 -0.0877809078 682 1305031252.2530639172 0.1380324513 0.1431351294 0.1773367077 0.0493688207 1.8291480000 131208128 95654128 1788051456 -0.0964458808 0.1752122641 -0.0817429423 683 1305031252.2888779640 0.1288866103 0.1431142677 0.1773367077 0.0494475797 1.1966700000 131259018 95654128 1784877056 -0.0889050141 0.1719863713 -0.0743569285 684 1305031252.3206090927 0.1335678697 0.1431003110 0.1773367077 0.0494164446 1.0019720000 131381044 95654128 1786273792 -0.0939967781 0.1778024137 -0.0748782158 685 1305031252.3528549671 0.1330159307 0.1430855893 0.1773367077 0.0494187501 1.0479660000 131433066 95654128 1785765888 -0.0946489125 0.1808764338 -0.0729088783 686 1305031252.3893189430 0.1324773729 0.1430701254 0.1773367077 0.0494012023 0.8073480000 131555596 95654128 1787035648 -0.0943769366 0.1812072992 -0.0730081722 687 1305031252.4217019081 0.1343140304 0.1430573800 0.1773367077 0.0493929802 0.8065300000 131607726 95654128 1784889344 -0.0908140391 0.1817932427 -0.0769081190 688 1305031252.4538249969 0.1299088895 0.1430382688 0.1773367077 0.0493760348 0.8231690000 131609916 95654128 1786138624 -0.0929551050 0.1817414761 -0.0730751529 689 1305031252.4895589352 0.1330769807 0.1430238112 0.1773367077 0.0493438142 0.7868920000 131611002 95654128 1788043264 -0.0966630131 0.1845893860 -0.0742014199 690 1305031252.5221700668 0.1310860962 0.1430065102 0.1773367077 0.0493176113 0.8490000000 131734016 95654128 1784741888 -0.0962104872 0.1835380644 -0.0730599239 691 1305031252.5537741184 0.1295219809 0.1429869957 0.1773367077 0.0492894916 0.9259810000 131784922 95654128 1786138624 -0.0934973508 0.1818948090 -0.0727556050 692 1305031252.5897459984 0.1350853443 0.1429755771 0.1773367077 0.0492597621 0.9450120000 131787160 95654128 1788043264 -0.0964782983 0.1836842597 -0.0772949755 693 1305031252.6221249104 0.1272608489 0.1429529007 0.1773367077 0.0492462551 0.8603310000 131789382 95654128 1784487936 -0.0939128771 0.1817039400 -0.0695168376 694 1305031252.6578559875 0.1296222657 0.1429336923 0.1773367077 0.0492281773 1.0513090000 131909968 95654128 1785757696 -0.0962956622 0.1819488406 -0.0694404244 695 1305031252.6889979839 0.1312556118 0.1429168893 0.1773367077 0.0492496959 0.9891530000 131962342 95654128 1787789312 -0.1019820794 0.1826072484 -0.0680448189 696 1305031252.7216539383 0.1334402710 0.1429032735 0.1773367077 0.0493145713 0.9870530000 131964548 95654128 1784868864 -0.1051541045 0.1816524118 -0.0691728443 697 1305031252.7578220367 0.1387623847 0.1428973325 0.1773367077 0.0494081633 0.8607470000 131965590 95654128 1786138624 -0.1141132712 0.1790775955 -0.0740627795 698 1305031252.7896919250 0.1366101354 0.1428883250 0.1773367077 0.0495811962 0.9157140000 132088356 95654128 1787916288 -0.1098566055 0.1767941117 -0.0742244646 699 1305031252.8224050999 0.1467536688 0.1428938549 0.1773367077 0.0497868110 0.8849610000 132261782 95654128 1784905728 -0.1210926846 0.1787917912 -0.0814029425 700 1305031252.8539779186 0.1460851580 0.1428984139 0.1773367077 0.0497707323 0.8987410000 132312832 95654128 1786392576 -0.1161774173 0.1763921380 -0.0825909004 701 1305031252.8897290230 0.1457674801 0.1429025067 0.1773367077 0.0498043568 0.7817190000 132436258 95654128 1784614912 -0.1130867228 0.1736127138 -0.0837732852 702 1305031252.9206719398 0.1475041807 0.1429090618 0.1773367077 0.0498052813 0.9548560000 132488660 95654128 1785884672 -0.1131935120 0.1715932786 -0.0856964663 703 1305031252.9578649998 0.1454077959 0.1429126162 0.1773367077 0.0498658639 0.9802260000 132610682 95654128 1787789312 -0.1111578867 0.1665157974 -0.0853688642 704 1305031252.9894239902 0.1500305533 0.1429227269 0.1773367077 0.0499373240 0.8319340000 132663080 95654128 1784741888 -0.1156627834 0.1656392217 -0.0889553428 705 1305031253.0196959972 0.1523464024 0.1429360938 0.1773367077 0.0500152259 0.9835370000 132785754 95654128 1786138624 -0.1198657230 0.1658448726 -0.0896484777 706 1305031253.0574259758 0.1552743763 0.1429535701 0.1773367077 0.0500681830 0.7681220000 132837112 95654128 1785630720 -0.1232551411 0.1630013585 -0.0922314003 707 1305031253.0895500183 0.1542289257 0.1429695183 0.1773367077 0.0500948606 1.0054370000 132959858 95654128 1787027456 -0.1210124791 0.1569715589 -0.0947782621 708 1305031253.1197240353 0.1550673693 0.1429866056 0.1773367077 0.0501134056 1.2000810000 133011148 95654128 1784741888 -0.1211346239 0.1529740691 -0.0962542668 709 1305031253.1573839188 0.1595879495 0.1430100208 0.1773367077 0.0502277406 0.9311340000 133133978 95654128 1786138624 -0.1262237430 0.1468854398 -0.1025515199 710 1305031253.1892180443 0.1616073251 0.1430362142 0.1773367077 0.0502874629 0.7852560000 133186556 95654128 1785503744 -0.1317137778 0.1490590721 -0.1021170467 711 1305031253.2180271149 0.1620798707 0.1430629985 0.1773367077 0.0502892314 0.9466340000 133307774 95654128 1786900480 -0.1344913244 0.1538178027 -0.0997657701 712 1305031253.2578470707 0.1653689742 0.1430943271 0.1773367077 0.0502728414 1.1235870000 133360540 95654128 1784868864 -0.1393128783 0.1517031491 -0.1028784215 713 1305031253.2897419930 0.1652405113 0.1431253877 0.1773367077 0.0502409562 1.0268790000 133362854 95654128 1786138624 -0.1390028745 0.1482843459 -0.1034130156 714 1305031253.3220069408 0.1596546620 0.1431485379 0.1773367077 0.0502240850 1.0686260000 133484432 95654128 1787916288 -0.1333763897 0.1429020315 -0.1000076458 715 1305031253.3578300476 0.1551697850 0.1431653509 0.1773367077 0.0501985704 0.9400260000 133537182 95654128 1784868864 -0.1270716637 0.1351131797 -0.0980286449 716 1305031253.3880970478 0.1563293487 0.1431837363 0.1773367077 0.0501659754 0.8337690000 133539356 95654128 1786138624 -0.1279754192 0.1387253702 -0.0975100622 717 1305031253.4213519096 0.1553227305 0.1432006666 0.1773367077 0.0501345212 0.7872270000 133540318 95654128 1788297216 -0.1273959130 0.1362688988 -0.0968278274 718 1305031253.4579629898 0.1554089487 0.1432176698 0.1773367077 0.0501052946 0.9790450000 133542588 95654128 1784655872 -0.1274671108 0.1381273270 -0.0951235667 719 1305031253.4896900654 0.1551523209 0.1432342687 0.1773367077 0.0500718180 0.9704330000 133544934 95654128 1785892864 -0.1283081621 0.1428686380 -0.0918600261 720 1305031253.5207340717 0.1561418921 0.1432521960 0.1773367077 0.0500398496 0.9864090000 133545880 95654128 1787686912 -0.1287930757 0.1404460222 -0.0934158042 721 1305031253.5578539371 0.1588291973 0.1432738007 0.1773367077 0.0500086425 0.8190090000 133548150 95654128 1784754176 -0.1311406940 0.1377454102 -0.0963028818 722 1305031253.5898048878 0.1645073742 0.1433032101 0.1773367077 0.0499827904 0.9496910000 133550356 95654128 1786146816 -0.1397627145 0.1451864839 -0.0972674415 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 05:11:50 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 nan 0.2552560000 88654039 95654128 1753268224 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0293943919 0.0273966109 0.0293943919 0.0122530656 1.3813050000 89432990 95654128 1755774976 -0.0000554346 0.0078804428 0.0104378425 3 1305031102.2432110310 0.0239656884 0.0262529701 0.0293943919 0.0087681085 1.2259560000 89509512 95654128 1757679616 -0.0014141212 0.0065610358 0.0237118918 4 1305031102.2753260136 0.0206932332 0.0248630359 0.0293943919 0.0077485513 1.9874380000 89607146 95654128 1759457280 -0.0017301160 0.0074324966 0.0370710753 5 1305031102.3112668991 0.0151589615 0.0229222210 0.0293943919 0.0071888667 2.3170660000 89684532 95654128 1761234944 -0.0001425352 0.0047266171 0.0516257808 6 1305031102.3432331085 0.0148826102 0.0215822859 0.0293943919 0.0072489471 1.5910390000 89783362 95654128 1762947072 -0.0001035580 0.0067454726 0.0636193305 7 1305031102.3753290176 0.0159750041 0.0207812456 0.0293943919 0.0067039748 2.1734400000 89784392 95654128 1764462592 0.0011613899 0.0083600041 0.0759387091 8 1305031102.4112579823 0.0131075876 0.0198220384 0.0293943919 0.0088425727 1.8817850000 89786694 95654128 1766240256 -0.0015190806 0.0113094710 0.0862212628 9 1305031102.4432709217 0.0134044951 0.0191089780 0.0293943919 0.0094076428 1.5103640000 89863860 95654128 1768017920 -0.0038383589 0.0172586218 0.0961052477 10 1305031102.4753179550 0.0156274308 0.0187608233 0.0293943919 0.0089063852 1.8056230000 89961614 95654128 1769762816 -0.0012851513 0.0172196478 0.1104013100 11 1305031102.5112190247 0.0180294886 0.0186943383 0.0293943919 0.0085826273 1.9437050000 89964000 95654128 1771540480 0.0000622899 0.0167089663 0.1243779287 12 1305031102.5432200432 0.0201554485 0.0188160975 0.0293943919 0.0082491179 1.7393480000 90042218 95654128 1773191168 -0.0011371386 0.0158798359 0.1378088444 13 1305031102.5752859116 0.0268438160 0.0194336143 0.0293943919 0.0082459189 1.8793650000 90138608 95654128 1775071232 -0.0008616130 0.0113712959 0.1531594247 14 1305031102.6112329960 0.0300074704 0.0201888897 0.0300074704 0.0079800391 1.9086920000 90141110 95654128 1776848896 -0.0024004332 0.0095386337 0.1661032736 15 1305031102.6432650089 0.0225312039 0.0203450440 0.0300074704 0.0086625916 1.8215770000 90143432 95654128 1778483200 -0.0091921408 0.0178745687 0.1737539619 16 1305031102.6752851009 0.0250116214 0.0206367051 0.0300074704 0.0084542250 2.5611970000 90144378 95654128 1780133888 -0.0099236481 0.0206319150 0.1868849844 17 1305031102.7112629414 0.0303956587 0.0212107612 0.0303956587 0.0085231333 1.8946790000 90147928 95654128 1781911552 -0.0091690868 0.0202030353 0.2008628249 18 1305031102.7432339191 0.0298850778 0.0216926677 0.0303956587 0.0084473883 1.9852430000 90228666 95654128 1783529472 -0.0088690547 0.0269374587 0.2123260498 19 1305031102.7754719257 0.0378382094 0.0225424330 0.0378382094 0.0082384039 1.7115840000 90323900 95654128 1785561088 -0.0041630561 0.0273647066 0.2271546125 20 1305031102.8112320900 0.0391765349 0.0233741381 0.0391765349 0.0081834799 1.4744970000 90326286 95654128 1787092992 -0.0053764367 0.0309430137 0.2394587994 21 1305031102.8432900906 0.0442591533 0.0243686627 0.0442591533 0.0080214791 1.7109980000 90328524 95654128 1785315328 -0.0057297526 0.0312975124 0.2536904514 22 1305031102.8753631115 0.0448756292 0.0253007975 0.0448756292 0.0081304928 1.9645750000 90329310 95654128 1786712064 -0.0097992448 0.0342629775 0.2652524412 23 1305031102.9111850262 0.0469303019 0.0262412107 0.0469303019 0.0079601956 1.7398290000 90331532 95654128 1785180160 -0.0123491874 0.0368277393 0.2770364285 24 1305031102.9432289600 0.0472379699 0.0271160757 0.0472379699 0.0082681137 1.8340320000 90333770 95654128 1786449920 -0.0202539563 0.0383881070 0.2865879834 25 1305031102.9752030373 0.0459739827 0.0278703920 0.0472379699 0.0083438831 1.6552300000 90410256 95654128 1785434112 -0.0285465047 0.0433285907 0.2963753939 26 1305031103.0112149715 0.0489694402 0.0286818938 0.0489694402 0.0082067842 1.9844150000 90507006 95654128 1787084800 -0.0284756571 0.0462728031 0.3076089323 27 1305031103.0432269573 0.0522538722 0.0295549301 0.0522538722 0.0080637702 1.9149270000 90509244 95654128 1785561088 -0.0286886059 0.0491233058 0.3191935122 28 1305031103.0753190517 0.0599105768 0.0306390603 0.0599105768 0.0082558472 2.1360850000 90510142 95654128 1787084800 -0.0234274492 0.0491134748 0.3322163820 29 1305031103.1112399101 0.0566389821 0.0315356093 0.0599105768 0.0083892533 2.2214450000 90512380 95654128 1785180160 -0.0241755899 0.0572837181 0.3394283354 30 1305031103.1433179379 0.0606316738 0.0325054782 0.0606316738 0.0082949087 2.0078550000 90514570 95654128 1786576896 -0.0226419661 0.0592363961 0.3497621119 31 1305031103.1754519939 0.0583423525 0.0333389257 0.0606316738 0.0082241401 1.8389120000 90515516 95654128 1785180160 -0.0248288736 0.0656586513 0.3573287129 32 1305031103.2112200260 0.0568150766 0.0340725554 0.0606316738 0.0085386228 1.5858100000 90517770 95654128 1786703872 -0.0271834545 0.0713444725 0.3643281460 33 1305031103.2432160378 0.0586020090 0.0348158722 0.0606316738 0.0084047215 1.9740890000 90600616 95654128 1785561088 -0.0260377992 0.0743518695 0.3718012273 34 1305031103.2753698826 0.0593981892 0.0355388815 0.0606316738 0.0083986056 1.4180980000 90698846 95654128 1787219968 -0.0322228409 0.0750468224 0.3776410520 35 1305031103.3112099171 0.0675461590 0.0364533752 0.0675461590 0.0087617086 2.0876620000 90780668 95654128 1785442304 -0.0305162165 0.0708307028 0.3864465952 36 1305031103.3432230949 0.0698260963 0.0373803952 0.0698260963 0.0090608827 1.7973850000 90875002 95654128 1787219968 -0.0231349543 0.0724256337 0.3907008171 37 1305031103.3753271103 0.0708161965 0.0382840655 0.0708161965 0.0089447371 2.0631700000 90875916 95654128 1785315328 -0.0215846822 0.0714103058 0.3919094801 38 1305031103.4112598896 0.0738965422 0.0392212359 0.0738965422 0.0089247938 2.2832590000 90878186 95654128 1786974208 -0.0230298098 0.0655100122 0.3912640810 39 1305031103.4432799816 0.0719516575 0.0400604775 0.0738965422 0.0089268680 2.0811410000 90880424 95654128 1785577472 -0.0235533528 0.0647458360 0.3868674338 40 1305031103.4752740860 0.0742169768 0.0409143900 0.0742169768 0.0089046386 2.3305300000 90881322 95654128 1786847232 -0.0218826178 0.0599803366 0.3837181926 41 1305031103.5113329887 0.0740671232 0.0417229933 0.0742169768 0.0088280697 1.6206150000 90883608 95654128 1785577472 -0.0224066600 0.0558455586 0.3781045377 42 1305031103.5434439182 0.0741153508 0.0424942399 0.0742169768 0.0087887720 1.7309020000 90885846 95654128 1786966016 -0.0220885649 0.0503187701 0.3709446192 43 1305031103.5754740238 0.0687015429 0.0431037120 0.0742169768 0.0086985210 1.7425810000 90965580 95654128 1785442304 -0.0244492833 0.0483271740 0.3599792719 44 1305031103.6112229824 0.0664958656 0.0436353519 0.0742169768 0.0086533085 1.7643890000 91060126 95654128 1786966016 -0.0252885893 0.0441571325 0.3504399657 45 1305031103.6434450150 0.0640610978 0.0440892573 0.0742169768 0.0085865785 1.9054890000 91062364 95654128 1785331712 -0.0244206693 0.0403989516 0.3405870199 46 1305031103.6755230427 0.0615561642 0.0444689727 0.0742169768 0.0085345627 2.0036500000 91141606 95654128 1786839040 -0.0216841251 0.0369530916 0.3299719393 47 1305031103.7116100788 0.0580872111 0.0447587225 0.0742169768 0.0084705501 1.5161340000 91236200 95654128 1785569280 -0.0198351797 0.0341400057 0.3183967471 48 1305031103.7433259487 0.0573148914 0.0450203093 0.0742169768 0.0084150057 1.4683620000 91238438 95654128 1786839040 -0.0177404862 0.0278949626 0.3070681393 49 1305031103.7753419876 0.0501080714 0.0451241412 0.0742169768 0.0083537059 1.2274790000 91239352 95654128 1785569280 -0.0176130403 0.0267943218 0.2920082211 50 1305031103.8112421036 0.0445267186 0.0451121927 0.0742169768 0.0084759454 1.5640240000 91319782 95654128 1786966016 -0.0172636099 0.0261366498 0.2774571180 51 1305031103.8432509899 0.0353908576 0.0449215783 0.0742169768 0.0085157440 2.1918680000 91414444 95654128 1785569280 -0.0214209706 0.0266570952 0.2616552413 52 1305031103.8753609657 0.0403470583 0.0448336068 0.0742169768 0.0087957285 1.8683360000 91415374 95654128 1786966016 -0.0216921680 0.0149550764 0.2521465719 53 1305031103.9112210274 0.0424950644 0.0447894833 0.0742169768 0.0091029834 1.8531040000 91417644 95654128 1785442304 -0.0207061563 0.0082946885 0.2407905757 54 1305031103.9432110786 0.0380985402 0.0446655770 0.0742169768 0.0090302954 2.5507400000 91419882 95654128 1786839040 -0.0190516375 0.0063912510 0.2260865718 55 1305031103.9753730297 0.0381285064 0.0445467212 0.0742169768 0.0091413015 1.9896570000 91498652 95654128 1785696256 -0.0160479415 0.0013016346 0.2139578760 56 1305031104.0112318993 0.0428183526 0.0445158574 0.0742169768 0.0093436509 1.9864990000 91593418 95654128 1787252736 -0.0105998171 -0.0049855630 0.2036770135 57 1305031104.0432488918 0.0383831002 0.0444082652 0.0742169768 0.0093371611 1.1586270000 91673324 95654128 1785323520 -0.0069382358 -0.0072019659 0.1880919039 58 1305031104.0754249096 0.0325069986 0.0442030710 0.0742169768 0.0093169585 1.1939620000 91766826 95654128 1786974208 -0.0050504673 -0.0066566207 0.1720168442 59 1305031104.1112349033 0.0345409326 0.0440393059 0.0742169768 0.0093719860 2.3055610000 91769096 95654128 1785450496 -0.0033250761 -0.0132111562 0.1601559967 60 1305031104.1432299614 0.0297441725 0.0438010537 0.0742169768 0.0093491175 1.7687590000 91848550 95654128 1786847232 -0.0035544352 -0.0185964108 0.1449094564 61 1305031104.1754240990 0.0253650844 0.0434988247 0.0742169768 0.0093131959 1.8044110000 91942116 95654128 1785450496 -0.0036789456 -0.0216772873 0.1302002817 62 1305031104.2112829685 0.0269151852 0.0432313466 0.0742169768 0.0093713316 1.8626810000 91944386 95654128 1786966016 -0.0026584403 -0.0264714472 0.1175882295 63 1305031104.2431960106 0.0238635354 0.0429239210 0.0742169768 0.0093161468 2.4811390000 92023960 95654128 1785442304 -0.0021127642 -0.0291664917 0.1042758822 64 1305031104.2755460739 0.0219326578 0.0425959326 0.0742169768 0.0092447809 1.8515830000 92117590 95654128 1787219968 0.0003126641 -0.0310812853 0.0914752483 65 1305031104.3112189770 0.0231407490 0.0422966220 0.0742169768 0.0092144401 1.2371140000 92124980 95654128 1785442304 0.0004753754 -0.0329592489 0.0792954564 66 1305031104.3433420658 0.0216428488 0.0419836861 0.0742169768 0.0091839636 2.4180600000 92221878 95654128 1786839040 0.0009940456 -0.0332930833 0.0672512427 67 1305031104.3758370876 0.0226874035 0.0416956819 0.0742169768 0.0092604838 1.5120490000 92310468 95654128 1785569280 0.0013137423 -0.0351148434 0.0561144650 68 1305031104.4115090370 0.0217203721 0.0414019273 0.0742169768 0.0092967611 1.2695120000 92312738 95654128 1786966016 -0.0005982701 -0.0357126147 0.0447623432 69 1305031104.4432880878 0.0212794691 0.0411102975 0.0742169768 0.0092342148 1.8876660000 92314944 95654128 1785569280 -0.0047115739 -0.0351648591 0.0328916907 70 1305031104.4754559994 0.0209539998 0.0408223504 0.0742169768 0.0091711789 1.2919650000 92315890 95654128 1787092992 -0.0086976532 -0.0372502431 0.0231632404 71 1305031104.5113289356 0.0219391640 0.0405563900 0.0742169768 0.0093366800 1.8032060000 92318160 95654128 1785569280 -0.0087046614 -0.0417525023 0.0154952053 72 1305031104.5433681011 0.0223739650 0.0403038563 0.0742169768 0.0093573248 1.5052790000 92403802 95654128 1786839040 -0.0056732078 -0.0444229953 0.0073797451 73 1305031104.5753428936 0.0236312170 0.0400754640 0.0742169768 0.0094361898 1.7500720000 92492452 95654128 1785569280 0.0003493689 -0.0483803116 0.0005220678 74 1305031104.6113359928 0.0303916242 0.0399446013 0.0742169768 0.0096627268 2.3217410000 92577278 95654128 1786839040 0.0077359984 -0.0574173890 -0.0040829908 75 1305031104.6432430744 0.0304732826 0.0398183170 0.0742169768 0.0098493772 1.5024420000 92750508 95654128 1785569280 0.0108753163 -0.0574070923 -0.0159820877 76 1305031104.6755249500 0.0281427726 0.0396646915 0.0742169768 0.0098008837 1.5510810000 92921970 95654128 1787219968 0.0117018009 -0.0604884513 -0.0275135338 77 1305031104.7112770081 0.0278839637 0.0395116950 0.0742169768 0.0098600114 1.1493160000 93094584 95654128 1784815616 0.0101722302 -0.0616428182 -0.0383249223 78 1305031104.7432799339 0.0266860072 0.0393472631 0.0742169768 0.0098825234 1.8029160000 93267126 95654128 1786339328 0.0116843916 -0.0604588874 -0.0500903651 79 1305031104.7753269672 0.0274401382 0.0391965400 0.0742169768 0.0099321199 1.6145150000 93438444 95654128 1785704448 0.0107042706 -0.0571651682 -0.0599268377 80 1305031104.8114650249 0.0319019817 0.0391053580 0.0742169768 0.0099317387 2.1304440000 93611118 95654128 1787482112 0.0133243911 -0.0526381209 -0.0684913322 81 1305031104.8432579041 0.0347396620 0.0390514605 0.0742169768 0.0098968523 2.2584330000 93783796 95654128 1784815616 0.0115623577 -0.0482522137 -0.0759805739 82 1305031104.8753499985 0.0395572037 0.0390576281 0.0742169768 0.0098883467 1.8751430000 93872722 95654128 1786339328 0.0073457756 -0.0426127762 -0.0818463638 83 1305031104.9115340710 0.0413017534 0.0390846658 0.0742169768 0.0098363051 1.8830670000 93957392 95654128 1785442304 0.0094179222 -0.0397492349 -0.0851358324 84 1305031104.9432621002 0.0430976376 0.0391324393 0.0742169768 0.0097843574 1.9036360000 94047654 95654128 1787236352 0.0092606237 -0.0372011550 -0.0851280093 85 1305031104.9752020836 0.0498466864 0.0392584892 0.0742169768 0.0097556140 1.3702410000 94048600 95654128 1785315328 0.0071106218 -0.0294617992 -0.0835133195 86 1305031105.0112900734 0.0503536202 0.0393875024 0.0742169768 0.0097169469 1.7572380000 94050886 95654128 1786839040 0.0098583084 -0.0260028299 -0.0790741965 87 1305031105.0433731079 0.0493561700 0.0395020848 0.0742169768 0.0096658222 2.0415710000 94135244 95654128 1785442304 0.0092349788 -0.0246643703 -0.0726275891 88 1305031105.0753200054 0.0461699776 0.0395778563 0.0742169768 0.0096159236 1.4158880000 94224314 95654128 1787092992 0.0096372394 -0.0250746198 -0.0641209558 89 1305031105.1112990379 0.0385636613 0.0395664608 0.0742169768 0.0095854340 2.0850390000 94308388 95654128 1785315328 0.0096080499 -0.0292304754 -0.0539137982 90 1305031105.1431059837 0.0441341139 0.0396172125 0.0742169768 0.0095704676 1.3578270000 94480754 95654128 1787092992 0.0040983707 -0.0203129910 -0.0417222790 91 1305031105.1751589775 0.0445485078 0.0396714026 0.0742169768 0.0095795302 1.7851000000 94651784 95654128 1785315328 0.0032897729 -0.0157967769 -0.0285534151 92 1305031105.2112679482 0.0293032471 0.0395587052 0.0742169768 0.0098440312 1.6138130000 94823938 95654128 1786966016 0.0037959437 -0.0265756100 -0.0146250417 93 1305031105.2432699203 0.0262739193 0.0394158581 0.0742169768 0.0098562032 2.3890590000 94997916 95654128 1785569280 0.0017848017 -0.0257978588 -0.0014540721 94 1305031105.2752881050 0.0224067364 0.0392349100 0.0742169768 0.0099059911 1.9702540000 95169470 95654128 1787219968 -0.0014869384 -0.0255650263 0.0107607078 95 1305031105.3112900257 0.0141938701 0.0389713201 0.0742169768 0.0099128142 0.9880490000 95342368 95654128 1784807424 -0.0021805367 -0.0311750546 0.0246103741 96 1305031105.3433020115 0.0097690271 0.0386671295 0.0742169768 0.0098758006 0.9877930000 95432870 95654128 1786331136 -0.0029153959 -0.0341076590 0.0409464017 97 1305031105.3753380775 0.0112563549 0.0383845442 0.0742169768 0.0099061617 0.9303470000 95516192 95654128 1785704448 -0.0033917814 -0.0350970887 0.0561001115 98 1305031105.4112861156 0.0115143694 0.0381103588 0.0742169768 0.0099484261 1.0136180000 95606802 95654128 1787355136 -0.0070671113 -0.0288855080 0.0666752011 99 1305031105.4433159828 0.0104423361 0.0378308838 0.0742169768 0.0099018998 1.0387710000 95608992 95654128 1785577472 -0.0109924916 -0.0301116053 0.0823385864 100 1305031105.4752800465 0.0103591783 0.0375561667 0.0742169768 0.0098549806 1.1223690000 95609938 95654128 1786974208 -0.0143473335 -0.0278504286 0.0960906819 101 1305031105.5113320351 0.0108720893 0.0372919680 0.0742169768 0.0099050075 1.0801410000 95612176 95654128 1785450496 -0.0158945173 -0.0234538447 0.1092883721 102 1305031105.5432820320 0.0145923207 0.0370694224 0.0742169768 0.0098630006 1.2253730000 95614350 95654128 1786839040 -0.0173282214 -0.0238453895 0.1246052533 103 1305031105.5754489899 0.0139193553 0.0368446645 0.0742169768 0.0098560696 1.0894560000 95697420 95654128 1785696256 -0.0204217881 -0.0200198479 0.1375103146 104 1305031105.6113779545 0.0202702563 0.0366852952 0.0742169768 0.0098189144 1.0057240000 95788154 95654128 1787346944 -0.0198837873 -0.0216246154 0.1532641053 105 1305031105.6432731152 0.0210767854 0.0365366427 0.0742169768 0.0097838179 1.3750060000 95790344 95654128 1785442304 -0.0234501623 -0.0191208143 0.1664414853 106 1305031105.6751658916 0.0246362537 0.0364243749 0.0742169768 0.0097567978 1.6054150000 95791290 95654128 1786839040 -0.0201555006 -0.0163016655 0.1808759123 107 1305031105.7113089561 0.0339185223 0.0364009557 0.0742169768 0.0097736201 1.6541060000 95793560 95654128 1785569280 -0.0161664654 -0.0191730335 0.1978679746 108 1305031105.7433118820 0.0316927619 0.0363573613 0.0742169768 0.0097967584 1.6939560000 95795766 95654128 1786839040 -0.0166793559 -0.0125189004 0.2097600847 109 1305031105.7753388882 0.0378089473 0.0363706786 0.0742169768 0.0097533925 2.1071320000 95878576 95654128 1785442304 -0.0132058021 -0.0124935610 0.2253553718 110 1305031105.8112831116 0.0388216041 0.0363929597 0.0742169768 0.0097181186 1.7336480000 95969418 95654128 1786966016 -0.0143879056 -0.0091456342 0.2398943454 111 1305031105.8432710171 0.0419613272 0.0364431252 0.0742169768 0.0096779527 1.7216420000 95971624 95654128 1785696256 -0.0121549228 -0.0064824778 0.2540083230 112 1305031105.8753368855 0.0409831665 0.0364836613 0.0742169768 0.0096716536 2.3285020000 95972538 95654128 1787092992 -0.0107860044 0.0002331692 0.2663538754 113 1305031105.9112620354 0.0437395833 0.0365478730 0.0742169768 0.0097096714 2.1531980000 96056676 95654128 1785315328 -0.0108987736 0.0039161677 0.2801393569 114 1305031105.9432721138 0.0434112772 0.0366080783 0.0742169768 0.0096843676 1.6690890000 96147554 95654128 1786966016 -0.0107527003 0.0104281511 0.2926838994 115 1305031105.9753289223 0.0452643558 0.0366833503 0.0742169768 0.0096567768 1.7412300000 96148484 95654128 1785442304 -0.0112507194 0.0152543141 0.3054452538 116 1305031106.0112850666 0.0494129397 0.0367930881 0.0742169768 0.0096492316 1.6359890000 96233322 95654128 1786966016 -0.0099739376 0.0190522056 0.3183543086 117 1305031106.0433549881 0.0518388264 0.0369216842 0.0742169768 0.0096125423 1.2089120000 96324280 95654128 1785569280 -0.0114880838 0.0227665491 0.3307595849 118 1305031106.0753300190 0.0536475442 0.0370634287 0.0742169768 0.0095804344 2.6537030000 96325178 95654128 1786974208 -0.0127712442 0.0274973214 0.3421532512 119 1305031106.1113269329 0.0523495972 0.0371918839 0.0742169768 0.0095881589 1.2172220000 96327448 95654128 1785450496 -0.0155413393 0.0355090834 0.3521797955 120 1305031106.1433548927 0.0577037707 0.0373628163 0.0742169768 0.0095755264 1.4855120000 96410862 95654128 1786974208 -0.0176506527 0.0361236222 0.3641566634 121 1305031106.1755340099 0.0618067198 0.0375648321 0.0742169768 0.0095481579 1.2179900000 96500596 95654128 1785577472 -0.0174202602 0.0386879407 0.3751064241 122 1305031106.2112751007 0.0685087517 0.0378184707 0.0742169768 0.0095140086 2.3633630000 96502866 95654128 1787101184 -0.0183194559 0.0382835716 0.3862039149 123 1305031106.2432670593 0.0699731335 0.0380798908 0.0742169768 0.0095168748 1.3773820000 96505104 95654128 1785577472 -0.0188010354 0.0422129370 0.3942884207 124 1305031106.2763850689 0.0684569925 0.0383248674 0.0742169768 0.0094820073 2.2619270000 96506034 95654128 1786966016 -0.0197201930 0.0483845770 0.4001141191 125 1305031106.3112380505 0.0684042126 0.0385655022 0.0742169768 0.0094484798 1.3956560000 96508272 95654128 1785458688 -0.0208772700 0.0519665033 0.4053681195 126 1305031106.3432579041 0.0650836602 0.0387759637 0.0742169768 0.0094311535 1.8229790000 96593046 95654128 1786839040 -0.0207282193 0.0590560883 0.4088050127 127 1305031106.3753879070 0.0681547374 0.0390072926 0.0742169768 0.0094080133 1.6627420000 96682920 95654128 1785569280 -0.0159578733 0.0599474460 0.4124470353 128 1305031106.4113199711 0.0772628263 0.0393061640 0.0772628263 0.0094121854 2.3537750000 96685190 95654128 1786966016 -0.0143198594 0.0524249002 0.4163629413 129 1305031106.4432780743 0.0788883939 0.0396130030 0.0788883939 0.0094475476 2.0893850000 96697636 95654128 1785696256 -0.0176255032 0.0494000837 0.4159561396 130 1305031106.4753448963 0.0777224973 0.0399061530 0.0788883939 0.0094297625 1.1473270000 96719574 95654128 1787092992 -0.0204851367 0.0477064177 0.4122130871 131 1305031106.5111289024 0.0793724135 0.0402074221 0.0793724135 0.0094288281 1.4836980000 96721748 95654128 1785696256 -0.0224046782 0.0423317812 0.4075387418 132 1305031106.5433020592 0.0764207318 0.0404817654 0.0793724135 0.0093995013 1.6670040000 96723986 95654128 1786966016 -0.0209106784 0.0409122147 0.3988136351 133 1305031106.5752820969 0.0734131783 0.0407293700 0.0793724135 0.0093652726 1.6646910000 96724884 95654128 1785569280 -0.0206933580 0.0385600105 0.3887855411 134 1305031106.6111509800 0.0684321001 0.0409361068 0.0793724135 0.0093608720 1.9818260000 96727154 95654128 1786966016 -0.0219980981 0.0375318229 0.3771580756 135 1305031106.6432070732 0.0695108101 0.0411477712 0.0793724135 0.0093876347 2.4328260000 96729392 95654128 1785696256 -0.0213008840 0.0310271233 0.3672945499 136 1305031106.6752789021 0.0630914643 0.0413091219 0.0793724135 0.0093625692 2.2355770000 96730306 95654128 1787219968 -0.0246220957 0.0308114793 0.3536903560 137 1305031106.7115080357 0.0621401481 0.0414611732 0.0793724135 0.0093907277 1.2856630000 96732576 95654128 1785577472 -0.0268361047 0.0257589128 0.3404930830 138 1305031106.7433409691 0.0590983853 0.0415889791 0.0793724135 0.0093734487 1.2046700000 96734814 95654128 1786974208 -0.0274415556 0.0227763914 0.3270297647 139 1305031106.7753899097 0.0566802695 0.0416975495 0.0793724135 0.0093601301 1.6049210000 96735728 95654128 1785577472 -0.0251315236 0.0197329447 0.3131856322 140 1305031106.8112890720 0.0519065335 0.0417704708 0.0793724135 0.0093384013 1.4868370000 96737998 95654128 1786847232 -0.0242702998 0.0194181427 0.2969518602 141 1305031106.8434159756 0.0552920811 0.0418663688 0.0793724135 0.0094166005 1.7014550000 96740204 95654128 1785450496 -0.0240053572 0.0101006627 0.2849394679 142 1305031106.8759050369 0.0543789789 0.0419544858 0.0793724135 0.0094402878 1.6083290000 96741150 95654128 1786847232 -0.0203749184 0.0053107943 0.2703494430 143 1305031106.9112429619 0.0470252000 0.0419899453 0.0793724135 0.0094691332 2.1546410000 96743436 95654128 1785442304 -0.0199328549 0.0072986651 0.2501448691 144 1305031106.9434390068 0.0494923033 0.0420420450 0.0793724135 0.0095366573 2.5062400000 96745642 95654128 1786966016 -0.0180594269 -0.0011010142 0.2371722907 145 1305031106.9755470753 0.0501277596 0.0420978086 0.0793724135 0.0095048964 1.9003870000 96746588 95654128 1785442304 -0.0178541671 -0.0084237093 0.2226037383 146 1305031107.0115759373 0.0394880585 0.0420799336 0.0793724135 0.0095298232 1.2970280000 96748890 95654128 1786839040 -0.0196827538 -0.0047341138 0.1995247900 147 1305031107.0432810783 0.0382703245 0.0420540179 0.0793724135 0.0095078716 1.3527990000 96842656 95654128 1785442304 -0.0200211145 -0.0110453852 0.1843207777 148 1305031107.0754320621 0.0368372612 0.0420187695 0.0793724135 0.0094886366 1.0827900000 96922698 95654128 1787203584 -0.0224904306 -0.0194548871 0.1687662005 149 1305031107.1112289429 0.0324647576 0.0419546486 0.0793724135 0.0094617377 1.6451150000 96924968 95654128 1785434112 -0.0221098755 -0.0185006186 0.1510356218 150 1305031107.1432600021 0.0283041596 0.0418636454 0.0793724135 0.0094395464 1.3931930000 97018742 95654128 1786830848 -0.0193352941 -0.0180378091 0.1355029196 151 1305031107.1753990650 0.0310482401 0.0417920202 0.0793724135 0.0094268144 1.7163650000 97098848 95654128 1785561088 -0.0169932228 -0.0263040587 0.1252571344 152 1305031107.2113580704 0.0342136547 0.0417421625 0.0793724135 0.0094525487 1.3968400000 97101118 95654128 1786957824 -0.0154007589 -0.0321129858 0.1131943017 153 1305031107.2433779240 0.0277322475 0.0416505944 0.0793724135 0.0094261157 0.7276750000 97103356 95654128 1785319424 -0.0157331210 -0.0324589647 0.0971373767 154 1305031107.2753980160 0.0270703565 0.0415559175 0.0793724135 0.0094070208 1.0105080000 97104302 95654128 1786843136 -0.0140017672 -0.0370866135 0.0852847323 155 1305031107.3112258911 0.0302932169 0.0414832550 0.0793724135 0.0094031750 1.1322360000 97198072 95654128 1785827328 -0.0122261867 -0.0443812236 0.0748491138 156 1305031107.3435089588 0.0292320009 0.0414047213 0.0793724135 0.0094090095 1.0067200000 97371030 95654128 1787478016 -0.0084675774 -0.0499031879 0.0639042854 157 1305031107.3754129410 0.0234209523 0.0412901750 0.0793724135 0.0094772451 0.8353920000 97451264 95654128 1784827904 -0.0048727747 -0.0459869280 0.0500443466 158 1305031107.4112710953 0.0219162051 0.0411675549 0.0793724135 0.0094584407 0.8100510000 97544826 95654128 1786335232 -0.0019197362 -0.0475260504 0.0405022651 159 1305031107.4434189796 0.0181208253 0.0410226069 0.0793724135 0.0094400845 0.9357120000 97626428 95654128 1785827328 0.0009749588 -0.0468773618 0.0321551003 160 1305031107.4753770828 0.0154655604 0.0408628754 0.0793724135 0.0094141688 0.9078340000 97719054 95654128 1787351040 0.0044240765 -0.0488143750 0.0267744586 161 1305031107.5113520622 0.0142380698 0.0406975039 0.0793724135 0.0093949774 0.9256420000 97800700 95654128 1784827904 0.0074764672 -0.0453409515 0.0208324529 162 1305031107.5436050892 0.0138445562 0.0405317450 0.0793724135 0.0093823955 0.9308230000 97802970 95654128 1786462208 0.0106882211 -0.0451477543 0.0194876995 163 1305031107.5754539967 0.0110577121 0.0403509227 0.0793724135 0.0093683462 1.1475490000 97803884 95654128 1785708544 0.0137699759 -0.0498103462 0.0208683517 164 1305031107.6112709045 0.0137771675 0.0401888876 0.0793724135 0.0093592395 1.4916160000 97896794 95654128 1787232256 0.0154180480 -0.0423546359 0.0199172832 165 1305031107.6433229446 0.0127306785 0.0400224742 0.0793724135 0.0093320351 2.4440970000 97978524 95654128 1784946688 0.0171079319 -0.0417506658 0.0212027654 166 1305031107.6755681038 0.0105668874 0.0398450309 0.0793724135 0.0093127412 1.4263680000 97979438 95654128 1786335232 0.0175797399 -0.0421579517 0.0226133205 167 1305031107.7113070488 0.0103579666 0.0396684617 0.0793724135 0.0092879500 1.5162690000 97981724 95654128 1785700352 0.0175637752 -0.0386806093 0.0236428529 168 1305031107.7435379028 0.0109260743 0.0394973760 0.0793724135 0.0092628151 1.5751760000 98075242 95654128 1787097088 0.0148051493 -0.0347262248 0.0252540875 169 1305031107.7758018970 0.0095562404 0.0393202096 0.0793724135 0.0092378387 1.1876700000 98155764 95654128 1784684544 0.0162051972 -0.0354047306 0.0284825675 170 1305031107.8115959167 0.0115889823 0.0391570847 0.0793724135 0.0092128455 2.3879620000 98158034 95654128 1786208256 0.0189065225 -0.0334657617 0.0307465680 171 1305031107.8433320522 0.0137075474 0.0390082570 0.0793724135 0.0091896895 1.9020960000 98160240 95654128 1785446400 0.0224599447 -0.0335707068 0.0330987573 172 1305031107.8753581047 0.0180422775 0.0388863618 0.0793724135 0.0091751534 2.4497000000 98161170 95654128 1786970112 0.0278620701 -0.0366678201 0.0372099578 173 1305031107.9115409851 0.0181887057 0.0387667221 0.0793724135 0.0091895027 1.5975620000 98163440 95654128 1785573376 0.0303290077 -0.0361887291 0.0398305990 174 1305031107.9431219101 0.0197086632 0.0386571931 0.0793724135 0.0091857672 1.1290330000 98165646 95654128 1787097088 0.0353702195 -0.0363274328 0.0431578606 175 1305031107.9758069515 0.0193780325 0.0385470264 0.0793724135 0.0091825087 1.4439010000 98166592 95654128 1785573376 0.0425150283 -0.0364596322 0.0461182222 176 1305031108.0113201141 0.0216245912 0.0384508762 0.0793724135 0.0091852771 1.4864630000 98260562 95654128 1786970112 0.0529340990 -0.0355649181 0.0482516922 177 1305031108.0434179306 0.0236693900 0.0383673650 0.0793724135 0.0091633496 1.9673060000 98342508 95654128 1785573376 0.0652660877 -0.0333105661 0.0499576293 178 1305031108.0753519535 0.0250736903 0.0382926814 0.0793724135 0.0091863265 1.1997650000 98434526 95654128 1787097088 0.0761218593 -0.0348330438 0.0545038581 179 1305031108.1113779545 0.0179676767 0.0381791339 0.0793724135 0.0091690979 1.6524810000 98516580 95654128 1785446400 0.0820012614 -0.0356460474 0.0575215481 180 1305031108.1433339119 0.0157051757 0.0380542786 0.0793724135 0.0091511763 1.3922260000 98518786 95654128 1786970112 0.0924180895 -0.0327600688 0.0586657114 181 1305031108.1760580540 0.0085025495 0.0378910094 0.0793724135 0.0091793813 2.1199340000 98610420 95654128 1785700352 0.1014519781 -0.0295121782 0.0592145696 182 1305031108.2114748955 0.0114464825 0.0377457098 0.0793724135 0.0091576154 2.1817070000 98692554 95654128 1787224064 0.1143690795 -0.0314452499 0.0639035255 183 1305031108.2433469296 0.0218796320 0.0376590099 0.0793724135 0.0091386751 1.3016760000 98694760 95654128 1786859520 0.1327597648 -0.0373928621 0.0691852495 184 1305031108.2753579617 0.0163795631 0.0375433607 0.0793724135 0.0091273377 1.9289510000 98786530 95654128 1785352192 0.1397314966 -0.0327947214 0.0689153448 185 1305031108.3113319874 0.0122150630 0.0374064510 0.0793724135 0.0091607545 1.4852050000 98868728 95654128 1786986496 0.1460821927 -0.0300473776 0.0708136186 186 1305031108.3432779312 0.0114643853 0.0372669775 0.0793724135 0.0091545245 1.6731590000 98870966 95654128 1785716736 0.1542316824 -0.0272475481 0.0746880025 187 1305031108.3754100800 0.0135953389 0.0371403912 0.0793724135 0.0091341885 1.3694300000 98962792 95654128 1787113472 0.1631713212 -0.0268627107 0.0780949965 188 1305031108.4113609791 0.0171984062 0.0370343169 0.0793724135 0.0091247440 1.4482510000 99045038 95654128 1784946688 0.1767470241 -0.0270164814 0.0814833343 189 1305031108.4436099529 0.0195174795 0.0369416352 0.0793724135 0.0091224277 1.0950290000 99047276 95654128 1786343424 0.1907156706 -0.0262074508 0.0844533592 190 1305031108.4754710197 0.0259302091 0.0368836803 0.0793724135 0.0091268172 0.8779110000 99048190 95654128 1785597952 0.2048215717 -0.0295463800 0.0885515437 191 1305031108.5113780499 0.0336113498 0.0368665477 0.0793724135 0.0092516337 1.0776130000 99140892 95654128 1787224064 0.2255011499 -0.0330397002 0.0928287506 192 1305031108.5437369347 0.0376898199 0.0368708356 0.0793724135 0.0092888892 1.0073780000 99223190 95654128 1784827904 0.2413431853 -0.0337679163 0.0942982361 193 1305031108.5754139423 0.0329050310 0.0368502873 0.0793724135 0.0093347502 1.2146570000 99224104 95654128 1786335232 0.2492167354 -0.0289668962 0.0904308259 194 1305031108.6114070415 0.0338007733 0.0368345682 0.0793724135 0.0093549613 1.2434310000 99317206 95654128 1785700352 0.2630051970 -0.0281487927 0.0930097625 195 1305031108.6433029175 0.0315319374 0.0368073752 0.0793724135 0.0093872456 2.1752170000 99399568 95654128 1787351040 0.2706527710 -0.0249178577 0.0925711319 196 1305031108.6753749847 0.0304146577 0.0367747593 0.0793724135 0.0093764018 1.8742530000 99400482 95654128 1785352192 0.2804443538 -0.0219427533 0.0939207375 197 1305031108.7114109993 0.0337515026 0.0367594128 0.0793724135 0.0093777603 2.1596900000 99402720 95654128 1786970112 0.2899896502 -0.0234664995 0.0979519188 198 1305031108.7435019016 0.0360677913 0.0367559198 0.0793724135 0.0093768884 1.6392300000 99495498 95654128 1785446400 0.2966075242 -0.0248351991 0.1001291499 199 1305031108.7754929066 0.0357853062 0.0367510423 0.0793724135 0.0093556228 2.0147630000 99576620 95654128 1786970112 0.3044832051 -0.0236214083 0.0985232070 200 1305031108.8112440109 0.0391658545 0.0367631164 0.0793724135 0.0093369266 1.2448560000 99578874 95654128 1785446400 0.3085698783 -0.0253646690 0.0989623293 201 1305031108.8432641029 0.0406522378 0.0367824653 0.0793724135 0.0111234814 1.7437200000 99581112 95654128 1786970112 0.3122055531 -0.0270444211 0.0976214781 202 1305031108.8765149117 0.0393254571 0.0367950543 0.0793724135 0.0113217539 1.7756890000 99582058 95654128 1785446400 0.3134936392 -0.0267127305 0.0942474082 203 1305031108.9113640785 0.0417763442 0.0368195927 0.0793724135 0.0115094065 1.6893930000 99584296 95654128 1786843136 0.3157282770 -0.0299399607 0.0928606465 204 1305031108.9432430267 0.0442098938 0.0368558197 0.0793724135 0.0116268897 1.9874290000 99586534 95654128 1785446400 0.3129532635 -0.0321241915 0.0892837644 205 1305031108.9752678871 0.0403634720 0.0368729302 0.0793724135 0.0116030003 1.1640120000 99587480 95654128 1787097088 0.3081747591 -0.0283230003 0.0820527673 206 1305031109.0112690926 0.0364408493 0.0368708327 0.0793724135 0.0115760513 2.0184180000 99589718 95654128 1785454592 0.3086999357 -0.0269461069 0.0800784305 207 1305031109.0432770252 0.0369366929 0.0368711509 0.0793724135 0.0115558871 1.6032480000 99591940 95654128 1786978304 0.3013569415 -0.0280975774 0.0792403519 208 1305031109.0754098892 0.0331662409 0.0368533388 0.0793724135 0.0115414328 1.7478410000 99592854 95654128 1785708544 0.2905744910 -0.0234983638 0.0756916925 209 1305031109.1112821102 0.0324927457 0.0368324747 0.0793724135 0.0115222990 1.4266810000 99595124 95654128 1787105280 0.2833572924 -0.0248294547 0.0767784342 210 1305031109.1433339119 0.0351391509 0.0368244113 0.0793724135 0.0115051144 1.2302790000 99597362 95654128 1785581568 0.2699186802 -0.0272488594 0.0782976374 211 1305031109.1754639149 0.0312063862 0.0367977856 0.0793724135 0.0115147692 1.8283070000 99598276 95654128 1786978304 0.2587123811 -0.0230745282 0.0751618743 212 1305031109.2113790512 0.0218540654 0.0367272963 0.0793724135 0.0115100823 1.4401170000 99600546 95654128 1785573376 0.2502209246 -0.0140764471 0.0736302286 213 1305031109.2432899475 0.0243285242 0.0366690861 0.0793724135 0.0115045900 1.3493900000 99602784 95654128 1786970112 0.2401748747 -0.0163115654 0.0760853440 214 1305031109.2753078938 0.0329970717 0.0366519272 0.0793724135 0.0115440929 1.7194510000 99603698 95654128 1785573376 0.2294730991 -0.0252723861 0.0793196261 215 1305031109.3113288879 0.0286433622 0.0366146780 0.0793724135 0.0115464488 2.1811100000 99605968 95654128 1787097088 0.2151339501 -0.0219044127 0.0754139721 216 1305031109.3432478905 0.0233299956 0.0365531749 0.0793724135 0.0115243754 2.0725370000 99608222 95654128 1785446400 0.2017629445 -0.0169127900 0.0732620209 217 1305031109.3753969669 0.0274980869 0.0365114463 0.0793724135 0.0115304710 1.4608110000 99699864 95654128 1786970112 0.1931460500 -0.0204497613 0.0769543722 218 1305031109.4113290310 0.0281131621 0.0364729221 0.0793724135 0.0115151127 1.4381470000 99782726 95654128 1785573376 0.1842666715 -0.0184459873 0.0748745799 219 1305031109.4433019161 0.0234511048 0.0364134618 0.0793724135 0.0114927751 2.3452590000 99784932 95654128 1786970112 0.1696797907 -0.0139891114 0.0739736781 220 1305031109.4753630161 0.0240574889 0.0363572982 0.0793724135 0.0114756842 1.6248840000 99875694 95654128 1785700352 0.1558591574 -0.0150910560 0.0750810578 221 1305031109.5112729073 0.0258499794 0.0363097538 0.0793724135 0.0114633963 1.5845590000 99958620 95654128 1787224064 0.1395323724 -0.0165165607 0.0751477778 222 1305031109.5432939529 0.0205380358 0.0362387100 0.0793724135 0.0114412175 1.6029240000 99960858 95654128 1785700352 0.1223423779 -0.0133801075 0.0724674761 223 1305031109.5753619671 0.0165588409 0.0361504595 0.0793724135 0.0114162963 2.2631790000 99961804 95654128 1787097088 0.1080673635 -0.0102283843 0.0694726333 224 1305031109.6113100052 0.0149584804 0.0360558525 0.0793724135 0.0114101958 1.8729320000 99964042 95654128 1785479168 0.0924804136 -0.0080001689 0.0671840310 225 1305031109.6432290077 0.0145535758 0.0359602868 0.0793724135 0.0113874499 1.4583620000 100056388 95654128 1786970112 0.0807915404 -0.0061762631 0.0661772266 226 1305031109.6752629280 0.0119085712 0.0358538633 0.0793724135 0.0113641743 1.8213470000 100138062 95654128 1785581568 0.0662576184 -0.0037972103 0.0641653836 227 1305031109.7113120556 0.0120550841 0.0357490228 0.0793724135 0.0113681770 1.9205760000 100140332 95654128 1787105280 0.0529662892 -0.0001682574 0.0630360693 228 1305031109.7432739735 0.0129444702 0.0356490029 0.0793724135 0.0113542889 0.9861440000 100142570 95654128 1785581568 0.0409651138 0.0007500675 0.0639769882 229 1305031109.7752768993 0.0148704899 0.0355582670 0.0793724135 0.0113375606 1.3806070000 100143484 95654128 1787097088 0.0284758545 0.0008265993 0.0661686510 230 1305031109.8113710880 0.0139485523 0.0354643117 0.0793724135 0.0113282129 1.3609750000 100145754 95654128 1785446400 0.0127850864 0.0025455263 0.0655279681 231 1305031109.8432960510 0.0138811609 0.0353708782 0.0793724135 0.0113067161 0.9745040000 100147976 95654128 1786970112 -0.0017200420 0.0035271733 0.0668000653 232 1305031109.8753058910 0.0137515059 0.0352776912 0.0793724135 0.0113015317 0.9600710000 100148890 95654128 1785446400 -0.0193688832 0.0051948158 0.0683812723 233 1305031109.9112648964 0.0176964998 0.0352022355 0.0793724135 0.0112819346 0.9130820000 100151160 95654128 1786843136 -0.0333454795 0.0029406797 0.0738846883 234 1305031109.9432990551 0.0170058124 0.0351244730 0.0793724135 0.0112887473 0.8674520000 100242994 95654128 1785462784 -0.0448253825 0.0104342233 0.0734395906 235 1305031109.9752581120 0.0178011619 0.0350507567 0.0793724135 0.0112950930 0.9464060000 100324836 95654128 1787224064 -0.0607386976 0.0091834432 0.0775387362 236 1305031110.0112559795 0.0195634440 0.0349851325 0.0793724135 0.0112789303 1.0237100000 100327106 95654128 1785446400 -0.0738756284 0.0102454517 0.0807988718 237 1305031110.0432989597 0.0207683258 0.0349251460 0.0793724135 0.0112591859 1.0122540000 100329312 95654128 1786843136 -0.0864030570 0.0103474809 0.0840042308 238 1305031110.0753190517 0.0200856682 0.0348627953 0.0793724135 0.0112456717 1.0241970000 100419510 95654128 1785700352 -0.1002494842 0.0120486319 0.0854188353 239 1305031110.1113250256 0.0203469824 0.0348020596 0.0793724135 0.0112462798 0.9618390000 100502808 95654128 1787224064 -0.1154091060 0.0127408421 0.0879076347 240 1305031110.1434319019 0.0235810578 0.0347553055 0.0793724135 0.0112376472 0.8895900000 100505046 95654128 1785700352 -0.1298799366 0.0080034081 0.0929954723 241 1305031110.1756410599 0.0218850598 0.0347019020 0.0793724135 0.0112165225 0.8071310000 100505960 95654128 1787097088 -0.1407122761 0.0149887335 0.0920382664 242 1305031110.2116370201 0.0240581688 0.0346579196 0.0793724135 0.0112057203 0.7705160000 100597950 95654128 1785573376 -0.1527483314 0.0121640302 0.0952399373 243 1305031110.2433230877 0.0275003444 0.0346284645 0.0793724135 0.0111878612 1.0099340000 100681268 95654128 1787224064 -0.1649144590 0.0099278428 0.0987813771 244 1305031110.2793209553 0.0299385730 0.0346092437 0.0793724135 0.0111767888 0.8651600000 100682278 95654128 1785602048 -0.1721257865 0.0099660475 0.1001626849 245 1305031110.3114039898 0.0286589339 0.0345849567 0.0793724135 0.0111576648 0.8567710000 100776160 95654128 1786970112 -0.1873912364 0.0114120450 0.0990057439 246 1305031110.3433549404 0.0285079796 0.0345602535 0.0793724135 0.0111349873 0.9155950000 100859542 95654128 1785700352 -0.1985006779 0.0142808035 0.0978552550 247 1305031110.3792810440 0.0298244767 0.0345410804 0.0793724135 0.0111362421 1.0429460000 100950836 95654128 1787097088 -0.2104859352 0.0150307240 0.0981509238 248 1305031110.4114689827 0.0293815974 0.0345202760 0.0793724135 0.0111253489 1.0522730000 101034262 95654128 1785573376 -0.2235428393 0.0215087458 0.0952268466 249 1305031110.4432599545 0.0301031582 0.0345025366 0.0793724135 0.0111305925 1.0414140000 101126316 95654128 1786843136 -0.2315293998 0.0238886699 0.0947075486 250 1305031110.4793310165 0.0322244652 0.0344934243 0.0793724135 0.0111722770 0.8932780000 101208654 95654128 1785581568 -0.2480372190 0.0200975817 0.0976343378 251 1305031110.5114290714 0.0333022103 0.0344886784 0.0793724135 0.0111586991 0.8315120000 101300060 95654128 1787097088 -0.2619728744 0.0201039221 0.0981999338 252 1305031110.5434079170 0.0329759382 0.0344826755 0.0793724135 0.0111385862 0.9030730000 101383606 95654128 1785479168 -0.2710778117 0.0257904977 0.0960439891 253 1305031110.5794260502 0.0349989012 0.0344847159 0.0793724135 0.0111234825 0.7651760000 101474400 95654128 1787097088 -0.2780101597 0.0303437077 0.0960948169 254 1305031110.6113069057 0.0388934240 0.0345020730 0.0793724135 0.0111656079 0.9068680000 101557942 95654128 1785446400 -0.2863099575 0.0235227831 0.1018629074 255 1305031110.6434180737 0.0390197299 0.0345197893 0.0793724135 0.0111574885 0.9152510000 101560180 95654128 1786970112 -0.2986762822 0.0218097474 0.1024305075 256 1305031110.6796059608 0.0370185375 0.0345295500 0.0793724135 0.0111715502 0.9538270000 101650410 95654128 1785446400 -0.3058934212 0.0293855518 0.0978151560 257 1305031110.7114119530 0.0395826548 0.0345492119 0.0793724135 0.0111545313 0.9869600000 101754528 95654128 1787097088 -0.3109550178 0.0277144015 0.1003261730 258 1305031110.7432489395 0.0399688706 0.0345702184 0.0793724135 0.0111568511 0.7718640000 101798718 95654128 1785319424 -0.3186212182 0.0258050952 0.1013408154 259 1305031110.7791929245 0.0412546061 0.0345960268 0.0793724135 0.0111376059 0.9085230000 101799728 95654128 1786732544 -0.3205522001 0.0280389786 0.1011352912 260 1305031110.8113861084 0.0419079363 0.0346241495 0.0793724135 0.0111168863 0.8858840000 101801934 95654128 1785606144 -0.3214343190 0.0293240864 0.1010878086 261 1305031110.8432180882 0.0418644659 0.0346518902 0.0793724135 0.0111021209 1.0275230000 101804140 95654128 1787105280 -0.3266197145 0.0288643260 0.1017922759 262 1305031110.8793129921 0.0430881605 0.0346840897 0.0793724135 0.0110817478 0.8624830000 101915022 95654128 1785454592 -0.3253633976 0.0276114978 0.1032537147 263 1305031110.9113330841 0.0430667512 0.0347159630 0.0793724135 0.0110707052 0.9314320000 101978288 95654128 1787105280 -0.3228563070 0.0295662954 0.1028788611 264 1305031110.9438619614 0.0434807688 0.0347491630 0.0793724135 0.0110819606 0.8359100000 101980526 95654128 1785454592 -0.3192237616 0.0285299607 0.1042818427 265 1305031110.9793450832 0.0440017879 0.0347840785 0.0793724135 0.0111022561 0.8409850000 101981488 95654128 1786978304 -0.3080845475 0.0307988692 0.1041961536 266 1305031111.0114309788 0.0476465486 0.0348324337 0.0793724135 0.0110891757 0.9957890000 101983726 95654128 1785581568 -0.2971162498 0.0295501314 0.1077979878 267 1305031111.0433270931 0.0433916412 0.0348644906 0.0793724135 0.0110842789 1.2282820000 101985948 95654128 1786843136 -0.2944689095 0.0294516739 0.1054203659 268 1305031111.0792829990 0.0390700661 0.0348801831 0.0793724135 0.0110684069 1.8904750000 101986926 95654128 1785700352 -0.2896021008 0.0318171568 0.1031112745 269 1305031111.1115078926 0.0411354639 0.0349034369 0.0793724135 0.0110563015 1.7160590000 101989164 95654128 1787097088 -0.2825612128 0.0274291672 0.1069973931 270 1305031111.1432569027 0.0420448631 0.0349298867 0.0793724135 0.0110389764 1.8942980000 101991370 95654128 1785446400 -0.2736748159 0.0246679299 0.1084494963 271 1305031111.1793260574 0.0417694151 0.0349551248 0.0793724135 0.0110591523 1.4513840000 102101896 95654128 1786970112 -0.2623029351 0.0266846791 0.1090284213 272 1305031111.2114329338 0.0379301794 0.0349660625 0.0793724135 0.0110788664 1.1551760000 102165314 95654128 1785700352 -0.2544472516 0.0268524382 0.1058079228 273 1305031111.2432360649 0.0381224304 0.0349776243 0.0793724135 0.0110869605 1.9096860000 102167520 95654128 1787097088 -0.2490181476 0.0235779043 0.1072355509 274 1305031111.2793080807 0.0413988754 0.0350010595 0.0793724135 0.0111002972 1.4394310000 102277834 95654128 1785573376 -0.2390742451 0.0219270028 0.1111133248 275 1305031111.3115470409 0.0330724753 0.0349940464 0.0793724135 0.0111661182 1.0518740000 102341348 95654128 1787224064 -0.2296945900 0.0287139695 0.1030166298 276 1305031111.3433969021 0.0328380279 0.0349862348 0.0793724135 0.0111548513 1.4383630000 102343554 95654128 1785700352 -0.2219566405 0.0293780714 0.1029513478 277 1305031111.3791339397 0.0383122452 0.0349982420 0.0793724135 0.0112328441 1.3199360000 102344564 95654128 1787097088 -0.2029330134 0.0177870467 0.1110369563 278 1305031111.4112958908 0.0326784700 0.0349898975 0.0793724135 0.0112695085 1.7700910000 102346738 95654128 1785573376 -0.1938878894 0.0223564189 0.1062251925 279 1305031111.4433860779 0.0352669992 0.0349908907 0.0793724135 0.0112869190 1.0747010000 102348976 95654128 1787027456 -0.1717033535 0.0216180477 0.1107720807 280 1305031111.4792590141 0.0356894657 0.0349933856 0.0793724135 0.0113132537 1.0024940000 102350018 95654128 1785372672 -0.1579767168 0.0206699353 0.1125250086 281 1305031111.5112640858 0.0326620415 0.0349850890 0.0793724135 0.0114112921 0.9849490000 102352192 95654128 1786851328 -0.1480845511 0.0196156111 0.1098363847 282 1305031111.5432500839 0.0346983261 0.0349840722 0.0793724135 0.0113993260 0.8114030000 102354446 95654128 1785491456 -0.1404027194 0.0173354447 0.1111069545 283 1305031111.5792369843 0.0304513089 0.0349680553 0.0793724135 0.0114810646 0.8244350000 102355456 95654128 1786851328 -0.1173203140 0.0174166355 0.1089990139 284 1305031111.6112709045 0.0281099174 0.0349439069 0.0793724135 0.0114791689 0.8707520000 102357598 95654128 1785454592 -0.1072647348 0.0161005165 0.1066218689 285 1305031111.6433949471 0.0357056521 0.0349465797 0.0793724135 0.0114718833 0.8542810000 102359836 95654128 1786978304 -0.0981770158 0.0096357726 0.1124478951 286 1305031111.6793200970 0.0288705565 0.0349253349 0.0793724135 0.0116026745 0.8201850000 102360814 95654128 1785454592 -0.0739018321 0.0148409512 0.1095717251 287 1305031111.7117600441 0.0274399556 0.0348992534 0.0793724135 0.0115975159 1.2651760000 102363052 95654128 1786978304 -0.0491692051 0.0129854176 0.1097761989 288 1305031111.7433860302 0.0319031179 0.0348888502 0.0793724135 0.0116090876 1.6216430000 102365258 95654128 1785454592 -0.0275521297 0.0126657728 0.1135875583 289 1305031111.7794229984 0.0363244936 0.0348938178 0.0793724135 0.0117183816 1.8091260000 102366284 95654128 1787240448 0.0016135238 0.0106297769 0.1136935651 290 1305031111.8114058971 0.0356768556 0.0348965179 0.0793724135 0.0117308557 1.8748300000 102368458 95654128 1785462784 0.0118017811 0.0059971614 0.1145383045 291 1305031111.8432989120 0.0325940102 0.0348886055 0.0793724135 0.0117456547 2.0277470000 102479636 95654128 1786986496 0.0226534493 0.0069889510 0.1128973439 292 1305031111.8794419765 0.0255310629 0.0348565592 0.0793724135 0.0117307988 1.6420750000 102542266 95654128 1785589760 0.0296578519 0.0064911954 0.1096492410 293 1305031111.9113540649 0.0287632626 0.0348357629 0.0793724135 0.0117268993 1.4521710000 102544488 95654128 1787113472 0.0347472057 0.0005547428 0.1109038517 294 1305031111.9433000088 0.0268153995 0.0348084828 0.0793724135 0.0117173428 1.5697220000 102546694 95654128 1785454592 0.0490621738 0.0024238457 0.1106605381 295 1305031111.9794490337 0.0256262608 0.0347773566 0.0793724135 0.0117835884 2.0122590000 102547672 95654128 1786978304 0.0704654083 0.0064119380 0.1121797338 296 1305031112.0114328861 0.0293855891 0.0347591412 0.0793724135 0.0117676897 1.6861060000 102549910 95654128 1785708544 0.0892893374 0.0052854861 0.1132122427 297 1305031112.0432701111 0.0282719098 0.0347372987 0.0793724135 0.0117535402 1.4191410000 102552116 95654128 1787105280 0.1041397229 0.0066300412 0.1111661717 298 1305031112.0793390274 0.0291001052 0.0347183819 0.0793724135 0.0117826651 1.8455000000 102553126 95654128 1785581568 0.1214612573 0.0043623573 0.1103668511 299 1305031112.1114230156 0.0241340585 0.0346829828 0.0793724135 0.0118586630 2.0263400000 102555300 95654128 1787105280 0.1286360472 0.0049034008 0.1077045277 300 1305031112.1443419456 0.0232113488 0.0346447440 0.0793724135 0.0118426915 1.6301570000 102557506 95654128 1785581568 0.1425167173 0.0056342799 0.1063346788 301 1305031112.1793899536 0.0243234187 0.0346104539 0.0793724135 0.0118528968 1.6653240000 102666712 95654128 1786978304 0.1611157358 0.0044249143 0.1067096367 302 1305031112.2112538815 0.0285225641 0.0345902953 0.0793724135 0.0118609693 1.3141490000 102730872 95654128 1785581568 0.1719458401 -0.0020261393 0.1105160341 303 1305031112.2433691025 0.0324183963 0.0345831274 0.0793724135 0.0118577699 1.5496740000 102733110 95654128 1787105280 0.1840127259 -0.0086383447 0.1109142974 304 1305031112.2793529034 0.0292477254 0.0345655767 0.0793724135 0.0118601463 3.0016440000 102842836 95654128 1785851904 0.1889383644 -0.0098889209 0.1099140570 305 1305031112.3113119602 0.0324026681 0.0345584852 0.0793724135 0.0118464921 2.3545200000 102907134 95654128 1787613184 0.2013665885 -0.0150387380 0.1083831042 306 1305031112.3433229923 0.0297975522 0.0345429266 0.0793724135 0.0118280974 1.7846890000 102908096 95654128 1785708544 0.2140296400 -0.0141728967 0.1070037261 307 1305031112.3793599606 0.0292949565 0.0345258322 0.0793724135 0.0118100241 2.3577410000 102910398 95654128 1787232256 0.2250233591 -0.0141766118 0.1063169837 308 1305031112.4114420414 0.0290841833 0.0345081645 0.0793724135 0.0117989189 1.7177390000 102912556 95654128 1785335808 0.2379029244 -0.0144629823 0.1055597216 309 1305031112.4433910847 0.0312750079 0.0344977012 0.0793724135 0.0117849216 1.0556030000 102913534 95654128 1787113472 0.2511217296 -0.0173383858 0.1062017679 310 1305031112.4794180393 0.0317359082 0.0344887922 0.0793724135 0.0117677735 1.0449710000 102915804 95654128 1785589760 0.2584587932 -0.0170816574 0.1048518196 311 1305031112.5115039349 0.0332144834 0.0344846948 0.0793724135 0.0117554049 1.0256710000 102918102 95654128 1787240448 0.2672303617 -0.0184083041 0.1041496247 312 1305031112.5432119370 0.0341980457 0.0344837760 0.0793724135 0.0117460022 0.9429490000 103027908 95654128 1786097664 0.2779014111 -0.0197903812 0.1032431647 313 1305031112.5792520046 0.0345490836 0.0344839847 0.0793724135 0.0117309494 0.8670300000 103092230 95654128 1785462784 0.2859595120 -0.0188265219 0.1019637734 314 1305031112.6112608910 0.0308250412 0.0344723320 0.0793724135 0.0117867748 1.0516830000 103094436 95654128 1787113472 0.3028065860 -0.0153632984 0.1000253931 315 1305031112.6432459354 0.0318417326 0.0344639809 0.0793724135 0.0117838258 0.9059100000 103095430 95654128 1785589760 0.3117762804 -0.0151654370 0.1013379544 316 1305031112.6799519062 0.0346401557 0.0344645384 0.0793724135 0.0117762062 0.8474430000 103097700 95654128 1787240448 0.3147429228 -0.0162154119 0.1029654071 317 1305031112.7112510204 0.0345958546 0.0344649526 0.0793724135 0.0117742444 0.8406040000 103100014 95654128 1785708544 0.3173530102 -0.0140974410 0.1027391478 318 1305031112.7432448864 0.0290765837 0.0344480081 0.0793724135 0.0117650897 0.9443260000 103100992 95654128 1787359232 0.3192882836 -0.0060386015 0.1013296694 319 1305031112.7793099880 0.0348740518 0.0344493437 0.0793724135 0.0117534016 0.9343180000 103103262 95654128 1785606144 0.3193762600 -0.0092007443 0.1047830731 320 1305031112.8113100529 0.0407616757 0.0344690697 0.0793724135 0.0117600036 0.8229540000 103105436 95654128 1787281408 0.3122015893 -0.0122477589 0.1070017144 321 1305031112.8432860374 0.0394740142 0.0344846614 0.0793724135 0.0117421043 0.9029760000 103106382 95654128 1785581568 0.3071878552 -0.0087768165 0.1053651571 322 1305031112.8794209957 0.0391097926 0.0344990252 0.0793724135 0.0117696070 1.0354250000 103108636 95654128 1787105280 0.3079896867 -0.0083724791 0.1063827276 323 1305031112.9114110470 0.0413672701 0.0345202891 0.0793724135 0.0117558165 1.0825630000 103109754 95654128 1785597952 0.3009816706 -0.0096662091 0.1080055609 324 1305031112.9433209896 0.0417783968 0.0345426907 0.0793724135 0.0117394079 0.9261890000 103111928 95654128 1787232256 0.2961393893 -0.0100848153 0.1092979684 325 1305031112.9792780876 0.0400659293 0.0345596852 0.0793724135 0.0117888206 0.7615670000 103114198 95654128 1785708544 0.2920797467 -0.0096152127 0.1085234210 326 1305031113.0113530159 0.0353800766 0.0345622018 0.0793724135 0.0117752542 0.9690840000 103115112 95654128 1787105280 0.2861836851 -0.0059103980 0.1057448089 327 1305031113.0432310104 0.0352443531 0.0345642879 0.0793724135 0.0117579099 0.9121930000 103117334 95654128 1785581568 0.2803448141 -0.0066892584 0.1059678718 328 1305031113.0792510509 0.0398313031 0.0345803458 0.0793724135 0.0117646356 0.8461480000 103119620 95654128 1787105280 0.2717901170 -0.0128087150 0.1076503098 329 1305031113.1113159657 0.0349549800 0.0345814845 0.0793724135 0.0117554438 0.8422920000 103120674 95654128 1785708544 0.2589562535 -0.0104343984 0.1030769721 330 1305031113.1433060169 0.0292129666 0.0345652163 0.0793724135 0.0117404994 0.8477840000 103122912 95654128 1787232256 0.2477044910 -0.0062818620 0.0998903215 331 1305031113.1793429852 0.0334123634 0.0345617334 0.0793724135 0.0117473890 0.8569280000 103125182 95654128 1785733120 0.2391579747 -0.0113539193 0.1018259898 332 1305031113.2112588882 0.0308073033 0.0345504248 0.0793724135 0.0117301739 0.9620200000 103126096 95654128 1787232256 0.2241593152 -0.0117410608 0.0994555429 333 1305031113.2432270050 0.0254452769 0.0345230821 0.0793724135 0.0117135140 0.9083780000 103128366 95654128 1785610240 0.2102855444 -0.0088574979 0.0959291011 334 1305031113.2793118954 0.0314846598 0.0345139850 0.0793724135 0.0117378135 0.9027380000 103130604 95654128 1786978304 0.1992619932 -0.0152270161 0.0985439122 335 1305031113.3114519119 0.0348094665 0.0345148670 0.0793724135 0.0117381549 0.9530160000 103131690 95654128 1785454592 0.1841373146 -0.0216622725 0.0986144915 336 1305031113.3432519436 0.0241737440 0.0344840899 0.0793724135 0.0117370633 0.8225770000 103133896 95654128 1787105280 0.1638220102 -0.0150197195 0.0927552581 337 1305031113.3793120384 0.0213301368 0.0344450574 0.0793724135 0.0117380617 0.8463610000 103136150 95654128 1785581568 0.1443266422 -0.0136936698 0.0937922969 338 1305031113.4116249084 0.0273221005 0.0344239835 0.0793724135 0.0117371850 0.8910810000 103137128 95654128 1787232256 0.1287719458 -0.0214837790 0.0973713323 339 1305031113.4432659149 0.0129158767 0.0343605378 0.0793724135 0.0117399595 0.8325210000 103139334 95654128 1785454592 0.1072512940 -0.0099587115 0.0953721479 340 1305031113.4793109894 0.0122134816 0.0342953994 0.0793724135 0.0117410590 0.9365270000 103141556 95654128 1787105280 0.0889935568 -0.0096547278 0.0956260711 341 1305031113.5115230083 0.0122593297 0.0342307775 0.0793724135 0.0117281038 0.9907360000 103142674 95654128 1785581568 0.0681764781 -0.0126997745 0.0970560238 342 1305031113.5432419777 0.0145464875 0.0341732211 0.0793724135 0.0117317109 1.0673430000 103144880 95654128 1787105280 0.0509342253 -0.0157333110 0.0987055227 343 1305031113.5793011189 0.0115946913 0.0341073945 0.0793724135 0.0117254422 1.0275340000 103253342 95654128 1785454592 0.0350779556 -0.0117077567 0.0982365385 344 1305031113.6112680435 0.0121837808 0.0340436630 0.0793724135 0.0117141427 1.0443440000 103318288 95654128 1787367424 0.0200311672 -0.0117017655 0.0990393832 345 1305031113.6432220936 0.0130683314 0.0339828650 0.0793724135 0.0116995123 0.9267420000 103320494 95654128 1785335808 0.0047743088 -0.0118699577 0.0995778590 346 1305031113.6792879105 0.0136860395 0.0339242036 0.0793724135 0.0116937100 0.7904320000 103321504 95654128 1786859520 -0.0138985431 -0.0114169437 0.1002177224 347 1305031113.7119309902 0.0169273093 0.0338752212 0.0793724135 0.0116814780 0.8615810000 103323818 95654128 1785495552 -0.0258508828 -0.0132299373 0.1015975252 348 1305031113.7435901165 0.0160971079 0.0338241347 0.0793724135 0.0116646889 0.8310000000 103326056 95654128 1786986496 -0.0379217565 -0.0110408599 0.1017217860 349 1305031113.7793200016 0.0166399982 0.0337748965 0.0793724135 0.0116666566 0.8041710000 103327034 95654128 1785589760 -0.0580005869 -0.0118095325 0.1025183573 350 1305031113.8112370968 0.0165763479 0.0337257578 0.0793724135 0.0116510647 0.9088260000 103329192 95654128 1786986496 -0.0718609467 -0.0110527137 0.1025930718 351 1305031113.8432950974 0.0161970779 0.0336758185 0.0793724135 0.0116394620 1.0074530000 103331430 95654128 1785716736 -0.0852867067 -0.0063488707 0.1027850434 352 1305031113.8792810440 0.0218950976 0.0336423505 0.0793724135 0.0116802293 0.8429520000 103332440 95654128 1787105280 -0.1082979590 -0.0126816183 0.1060694978 353 1305031113.9112899303 0.0199287571 0.0336035018 0.0793724135 0.0116766901 0.8482600000 103334786 95654128 1785835520 -0.1173312068 -0.0084198406 0.1060376093 354 1305031113.9432909489 0.0210586675 0.0335680645 0.0793724135 0.0116620422 0.8267180000 103336976 95654128 1787232256 -0.1289452165 -0.0090085445 0.1073268056 355 1305031113.9792931080 0.0211941786 0.0335332084 0.0793724135 0.0116484297 0.8438800000 103337986 95654128 1785716736 -0.1442926675 -0.0079808105 0.1078259870 356 1305031114.0112569332 0.0221570544 0.0335012529 0.0793724135 0.0116465804 0.8495600000 103448184 95654128 1787105280 -0.1634863019 -0.0051755640 0.1075149253 357 1305031114.0433011055 0.0257307831 0.0334794869 0.0793724135 0.0116321814 0.8491450000 103513362 95654128 1784946688 -0.1823917776 -0.0051631662 0.1082707122 358 1305031114.0792849064 0.0246214811 0.0334547439 0.0793724135 0.0116230633 0.9278430000 103622580 95654128 1786343424 -0.1957260519 -0.0047879671 0.1095937192 359 1305031114.1112630367 0.0240741335 0.0334286141 0.0793724135 0.0116079058 0.9253060000 103687942 95654128 1785708544 -0.2071228027 -0.0009641389 0.1095619276 360 1305031114.1432840824 0.0247416962 0.0334044837 0.0793724135 0.0116048974 0.9891500000 103688904 95654128 1787359232 -0.2178280205 0.0002835752 0.1115061194 361 1305031114.1793370247 0.0258003417 0.0333834196 0.0793724135 0.0116120129 1.3078910000 103798910 95654128 1785327616 -0.2258206904 -0.0038246559 0.1150188670 362 1305031114.2113029957 0.0246073827 0.0333591764 0.0793724135 0.0116204289 2.0661180000 103864164 95654128 1787105280 -0.2388854325 0.0065241754 0.1123613939 363 1305031114.2433369160 0.0255426448 0.0333376433 0.0793724135 0.0116078520 1.4057370000 103865110 95654128 1785454592 -0.2557290196 0.0054430370 0.1146646515 364 1305031114.2793900967 0.0269521344 0.0333201007 0.0793724135 0.0116366112 1.7412680000 103976272 95654128 1786978304 -0.2754867077 0.0061395797 0.1164603084 365 1305031114.3114290237 0.0274209380 0.0333039386 0.0793724135 0.0116271704 1.7673790000 104041778 95654128 1785581568 -0.2850718498 0.0080493521 0.1177514568 366 1305031114.3433310986 0.0277612451 0.0332887946 0.0793724135 0.0116199333 1.6781980000 104150344 95654128 1787105280 -0.2899623811 0.0067715105 0.1204365641 367 1305031114.3793199062 0.0290707052 0.0332773012 0.0793724135 0.0116096022 1.6867990000 104215802 95654128 1785581568 -0.2970822155 0.0052604564 0.1226263419 368 1305031114.4113969803 0.0292905625 0.0332664677 0.0793724135 0.0116017673 1.9512060000 104218024 95654128 1787105280 -0.3122127056 0.0064369878 0.1233854741 369 1305031114.4433450699 0.0314338021 0.0332615011 0.0793724135 0.0115910676 2.0110210000 104326702 95654128 1785454592 -0.3278651834 0.0094438521 0.1241725907 370 1305031114.4793319702 0.0325452462 0.0332595653 0.0793724135 0.0115988862 1.5755470000 104392240 95654128 1787232256 -0.3417384624 0.0078430902 0.1258861721 371 1305031114.5112659931 0.0319301598 0.0332559820 0.0793724135 0.0115905450 2.0390970000 104501630 95654128 1785454592 -0.3466243148 0.0101358285 0.1258004010 372 1305031114.5432360172 0.0309922639 0.0332498967 0.0793724135 0.0115884574 1.6005500000 104565920 95654128 1787240448 -0.3482947648 0.0066836542 0.1275324970 373 1305031114.5792369843 0.0311443806 0.0332442519 0.0793724135 0.0115774121 2.2713740000 104568190 95654128 1785208832 -0.3535369635 0.0052273418 0.1289807707 374 1305031114.6113910675 0.0313262008 0.0332391234 0.0793724135 0.0115653331 1.7527780000 104679036 95654128 1786859520 -0.3588393033 0.0079385377 0.1286377013 375 1305031114.6441500187 0.0317787118 0.0332352290 0.0793724135 0.0115509733 2.2278300000 104743406 95654128 1784954880 -0.3668913841 0.0070415288 0.1300122291 376 1305031114.6792509556 0.0338088721 0.0332367546 0.0793724135 0.0115475959 1.8898030000 104852884 95654128 1786478592 -0.3750057817 0.0040021278 0.1330549270 377 1305031114.7113060951 0.0353202559 0.0332422811 0.0793724135 0.0115439887 1.6820990000 104917202 95654128 1785835520 -0.3738929331 0.0014805405 0.1353814304 378 1305031114.7432758808 0.0369665399 0.0332521337 0.0793724135 0.0115293302 1.6823300000 104919580 95654128 1787232256 -0.3728624880 -0.0005333039 0.1369074583 379 1305031114.7792890072 0.0371730253 0.0332624790 0.0793724135 0.0115174411 1.3800840000 104921850 95654128 1784819712 -0.3713549078 -0.0001483870 0.1361436248 380 1305031114.8113029003 0.0367365554 0.0332716213 0.0793724135 0.0115086587 1.2689710000 104922764 95654128 1786216448 -0.3698965311 0.0040500537 0.1338949203 381 1305031114.8432080746 0.0362050161 0.0332793205 0.0793724135 0.0114951758 1.8640490000 104925002 95654128 1785581568 -0.3683945239 0.0026748851 0.1335696131 382 1305031114.8792810440 0.0348953716 0.0332835510 0.0793724135 0.0114808004 1.7935410000 104927240 95654128 1787105280 -0.3649636507 0.0057775001 0.1317733824 383 1305031114.9128789902 0.0339476354 0.0332852849 0.0793724135 0.0114692896 1.7933630000 104928390 95654128 1785581568 -0.3606396914 0.0077911704 0.1305212080 384 1305031114.9432640076 0.0341056846 0.0332874214 0.0793724135 0.0114575039 1.9922000000 104930532 95654128 1786851328 -0.3488304615 0.0092994282 0.1307795048 385 1305031114.9792799950 0.0324194133 0.0332851668 0.0793724135 0.0114481172 2.0868070000 104932802 95654128 1785581568 -0.3423931003 0.0117598549 0.1310957521 386 1305031115.0113000870 0.0311806239 0.0332797147 0.0793724135 0.0114366094 1.8894130000 104933748 95654128 1786851328 -0.3351692855 0.0159918591 0.1306710839 387 1305031115.0435299873 0.0332774110 0.0332797087 0.0793724135 0.0114315874 1.5103760000 105043470 95654128 1784692736 -0.3242184520 0.0123401694 0.1359050423 388 1305031115.0792379379 0.0301174372 0.0332715585 0.0793724135 0.0114279651 1.7511250000 105109368 95654128 1786343424 -0.3164953887 0.0160212405 0.1362698823 389 1305031115.1112298965 0.0319315456 0.0332681138 0.0793724135 0.0114173115 1.8267160000 105216966 95654128 1785606144 -0.3024750948 0.0168730356 0.1402494907 390 1305031115.1432940960 0.0310220178 0.0332623545 0.0793724135 0.0114057529 2.3497100000 105282876 95654128 1787367424 -0.2920035422 0.0148769571 0.1426768750 391 1305031115.1794400215 0.0278823245 0.0332485949 0.0793724135 0.0114033677 1.9276280000 105392278 95654128 1784573952 -0.2862505615 0.0166097470 0.1437800974 392 1305031115.2113740444 0.0324962139 0.0332466755 0.0793724135 0.0114006501 1.9989450000 105456908 95654128 1786224640 -0.2728116214 0.0110010738 0.1518308818 393 1305031115.2432971001 0.0332278386 0.0332466276 0.0793724135 0.0113932953 1.6460250000 105566750 95654128 1785454592 -0.2618946135 0.0087093106 0.1556309909 394 1305031115.2799661160 0.0292804874 0.0332365612 0.0793724135 0.0114129113 1.4647080000 105632748 95654128 1787105280 -0.2498062551 0.0168409031 0.1543968171 395 1305031115.3117039204 0.0322311781 0.0332340160 0.0793724135 0.0114160032 1.6890470000 105740754 95654128 1785327616 -0.2304216325 0.0095452052 0.1623588055 396 1305031115.3434259892 0.0277233068 0.0332201000 0.0793724135 0.0114175474 1.4208960000 105806780 95654128 1786851328 -0.2147992849 0.0141448379 0.1621576250 397 1305031115.3791658878 0.0218100119 0.0331913593 0.0793724135 0.0114615463 1.0394970000 105916914 95654128 1785454592 -0.1970171928 0.0238719266 0.1598187983 398 1305031115.4112370014 0.0239305012 0.0331680908 0.0793724135 0.0114713366 1.4138590000 105982968 95654128 1787105280 -0.1790226698 0.0181432702 0.1669024527 399 1305031115.4431591034 0.0249427930 0.0331474760 0.0793724135 0.0114633883 1.3274230000 105985174 95654128 1785200640 -0.1587160528 0.0174202360 0.1718460172 400 1305031115.4792408943 0.0247016661 0.0331263615 0.0793724135 0.0114520956 1.3501870000 106094260 95654128 1786724352 -0.1412673444 0.0189741794 0.1738557220 401 1305031115.5112531185 0.0307576507 0.0331204545 0.0793724135 0.0114971514 1.7649020000 106160502 95654128 1785581568 -0.1131210029 0.0138079431 0.1806580573 402 1305031115.5436201096 0.0324765481 0.0331188527 0.0793724135 0.0114892098 1.6856450000 106270648 95654128 1786978304 -0.0912635997 0.0128779486 0.1823340356 403 1305031115.5793149471 0.0317844823 0.0331155416 0.0793724135 0.0114830631 1.8279570000 106335614 95654128 1785581568 -0.0762835667 0.0122414008 0.1827619821 404 1305031115.6114239693 0.0330877490 0.0331154728 0.0793724135 0.0114714655 2.1406170000 106337788 95654128 1786978304 -0.0600799881 0.0105009107 0.1830847859 405 1305031115.6432540417 0.0343316272 0.0331184757 0.0793724135 0.0114642913 2.0719380000 106339994 95654128 1785708544 -0.0405204296 0.0077038598 0.1826726943 406 1305031115.6792409420 0.0343763046 0.0331215738 0.0793724135 0.0114517206 1.8824550000 106341004 95654128 1787105280 -0.0254950598 0.0058421134 0.1800800711 407 1305031115.7113199234 0.0318408608 0.0331184271 0.0793724135 0.0114818975 1.4289320000 106343350 95654128 1785708544 -0.0043933261 0.0090844370 0.1792653054 408 1305031115.7432498932 0.0348789990 0.0331227422 0.0793724135 0.0114875076 1.8571930000 106345588 95654128 1786978304 0.0217881333 0.0084613934 0.1801091731 409 1305031115.7794249058 0.0340712294 0.0331250612 0.0793724135 0.0114982868 1.8916530000 106346598 95654128 1785716736 0.0378978550 0.0081192534 0.1794403940 410 1305031115.8112769127 0.0317090079 0.0331216074 0.0793724135 0.0114988654 1.9330370000 106348756 95654128 1786986496 0.0556817949 0.0105922343 0.1772673577 411 1305031115.8432240486 0.0345411226 0.0331250612 0.0793724135 0.0114920112 2.0155710000 106458354 95654128 1785716736 0.0726139843 0.0086197155 0.1770161837 412 1305031115.8791980743 0.0375631601 0.0331358333 0.0793724135 0.0114856049 1.5206770000 106523440 95654128 1787367424 0.0850257203 0.0043898546 0.1775637567 413 1305031115.9111180305 0.0349135213 0.0331401377 0.0793724135 0.0114910821 2.0046910000 106525786 95654128 1785335808 0.1039547771 0.0094143366 0.1760447621 414 1305031115.9433109760 0.0354591236 0.0331457391 0.0793724135 0.0114846194 2.3132980000 106633680 95654128 1786851328 0.1211694852 0.0120008374 0.1758681536 415 1305031115.9807400703 0.0336234979 0.0331468903 0.0793724135 0.0114912654 2.1065870000 106700154 95654128 1785454592 0.1350945830 0.0149684930 0.1761277020 416 1305031116.0113790035 0.0363495760 0.0331545891 0.0793724135 0.0115236457 1.8057050000 106702328 95654128 1786978304 0.1523928046 0.0166117474 0.1771204770 417 1305031116.0431640148 0.0393068865 0.0331693428 0.0793724135 0.0115181051 2.9013780000 106810158 95654128 1785581568 0.1680295765 0.0172750130 0.1779685616 418 1305031116.0800299644 0.0329783447 0.0331688858 0.0793724135 0.0115414102 2.3306300000 106876696 95654128 1787232256 0.1734888703 0.0226323735 0.1784239113 419 1305031116.1112999916 0.0371617340 0.0331784153 0.0793724135 0.0115292919 1.7658180000 106879010 95654128 1785454592 0.1900287271 0.0228543170 0.1806635112 420 1305031116.1434469223 0.0411963165 0.0331975056 0.0793724135 0.0115226191 1.6923300000 106986580 95654128 1786978304 0.1969920695 0.0205674041 0.1859249026 421 1305031116.1795721054 0.0415906869 0.0332174418 0.0793724135 0.0115189636 1.0292610000 107053182 95654128 1785200640 0.2041635066 0.0207417030 0.1871587634 422 1305031116.2113199234 0.0458959267 0.0332474857 0.0793724135 0.0115063897 0.8478070000 107055388 95654128 1786724352 0.2140238434 0.0187401623 0.1899136156 423 1305031116.2433199883 0.0502076745 0.0332875807 0.0793724135 0.0114954118 0.9376650000 107056334 95654128 1785454592 0.2285030633 0.0171320904 0.1930229366 424 1305031116.2793850899 0.0475103557 0.0333211249 0.0793724135 0.0115010585 0.8484520000 107058636 95654128 1786851328 0.2373941690 0.0199629106 0.1904482543 425 1305031116.3113360405 0.0476781540 0.0333549062 0.0793724135 0.0115014088 1.1939980000 107167126 95654128 1785454592 0.2481973767 0.0208191369 0.1896268725 426 1305031116.3432919979 0.0566412434 0.0334095689 0.0793724135 0.0114905284 1.8733550000 107232508 95654128 1787232256 0.2603685856 0.0138724428 0.1934083700 427 1305031116.3793840408 0.0519754328 0.0334530487 0.0793724135 0.0114782113 1.0650880000 107234746 95654128 1785581568 0.2638795376 0.0165974945 0.1895839423 428 1305031116.4113330841 0.0408540890 0.0334703409 0.0793724135 0.0114739628 0.8670330000 107236984 95654128 1787105280 0.2630790770 0.0261440650 0.1822164804 429 1305031116.4433689117 0.0399130657 0.0334853589 0.0793724135 0.0114727921 0.7668940000 107237962 95654128 1785581568 0.2659378648 0.0271787718 0.1801500022 430 1305031116.4798500538 0.0476538613 0.0335183089 0.0793724135 0.0114666087 0.7858990000 107240216 95654128 1786978304 0.2715504766 0.0205002520 0.1813105941 431 1305031116.5112049580 0.0428019054 0.0335398486 0.0793724135 0.0114543846 0.9075990000 107241270 95654128 1785708544 0.2671840787 0.0235784166 0.1766367406 432 1305031116.5432620049 0.0389158651 0.0335522930 0.0793724135 0.0114421953 0.9606760000 107243476 95654128 1787240448 0.2599183023 0.0253995489 0.1730666012 433 1305031116.5793130398 0.0376141630 0.0335616738 0.0793724135 0.0114376284 0.9546700000 107245714 95654128 1785716736 0.2530472279 0.0264770687 0.1716350317 434 1305031116.6112608910 0.0379804522 0.0335718553 0.0793724135 0.0114294555 1.0234460000 107246628 95654128 1786986496 0.2468908876 0.0263435468 0.1707057655 435 1305031116.6433548927 0.0348819159 0.0335748669 0.0793724135 0.0114317879 0.7684410000 107248834 95654128 1785602048 0.2328621447 0.0269212294 0.1682793349 436 1305031116.6792809963 0.0333047993 0.0335742475 0.0793724135 0.0114320472 0.9420170000 107251168 95654128 1786986496 0.2171000093 0.0277607162 0.1671516001 437 1305031116.7116339207 0.0314527899 0.0335693929 0.0793724135 0.0114421754 1.0684760000 107252222 95654128 1785716736 0.1966997534 0.0258240644 0.1677280068 438 1305031116.7432909012 0.0321411416 0.0335661321 0.0793724135 0.0114606105 0.9698800000 107254412 95654128 1787113472 0.1747249812 0.0232821684 0.1685425788 439 1305031116.7792980671 0.0332165882 0.0335653359 0.0793724135 0.0114731273 0.9864860000 107256682 95654128 1785462784 0.1582363248 0.0217984747 0.1680861413 440 1305031116.8113429546 0.0338796154 0.0335660501 0.0793724135 0.0115172820 0.9237950000 107257628 95654128 1786851328 0.1457607746 0.0212602392 0.1673630774 441 1305031116.8460888863 0.0329723880 0.0335647040 0.0793724135 0.0116001786 0.7849650000 107259866 95654128 1785454592 0.1237023845 0.0204775464 0.1643922031 442 1305031116.8801651001 0.0321363360 0.0335614724 0.0793724135 0.0115998581 0.9695030000 107262104 95654128 1786851328 0.1082719788 0.0216910634 0.1626674086 443 1305031116.9120440483 0.0334087759 0.0335611277 0.0793724135 0.0115919381 0.8683210000 107263206 95654128 1785454592 0.0938913226 0.0217860509 0.1618400663 444 1305031116.9432959557 0.0284561105 0.0335496299 0.0793724135 0.0115929805 0.8645430000 107265412 95654128 1786978304 0.0759304166 0.0259585716 0.1588560045 445 1305031116.9793510437 0.0317331925 0.0335455480 0.0793724135 0.0116204279 0.8670590000 107374022 95654128 1785454592 0.0565534271 0.0254035145 0.1580914259 446 1305031117.0113821030 0.0302959885 0.0335382620 0.0793724135 0.0116219230 0.8264620000 107439840 95654128 1787105280 0.0371863991 0.0271946080 0.1565311551 447 1305031117.0432610512 0.0282480251 0.0335264270 0.0793724135 0.0116108395 0.8468440000 107442078 95654128 1785344000 0.0183094200 0.0304041505 0.1551147699 448 1305031117.0795199871 0.0292032789 0.0335167771 0.0793724135 0.0116373852 0.8277100000 107550744 95654128 1786724352 -0.0012615733 0.0323334001 0.1542215794 449 1305031117.1112380028 0.0312414132 0.0335117095 0.0793724135 0.0116403144 0.9246260000 107616702 95654128 1785327616 -0.0196410157 0.0335000604 0.1546195894 450 1305031117.1432180405 0.0284399129 0.0335004388 0.0793724135 0.0116321647 0.9859830000 107618940 95654128 1786851328 -0.0314443894 0.0393356532 0.1532508135 451 1305031117.1792640686 0.0297314674 0.0334920819 0.0793724135 0.0116313163 0.8494400000 107725670 95654128 1785581568 -0.0416873917 0.0410920940 0.1546076387 452 1305031117.2113609314 0.0298189130 0.0334839554 0.0793724135 0.0116363870 0.8690810000 107792860 95654128 1787232256 -0.0469244495 0.0437599197 0.1565236598 453 1305031117.2432770729 0.0283429120 0.0334726066 0.0793724135 0.0116338143 0.9399880000 107795066 95654128 1785581568 -0.0452867672 0.0486088991 0.1572307348 454 1305031117.2792990208 0.0316581689 0.0334686100 0.0793724135 0.0116226190 0.8651520000 107796076 95654128 1787105280 -0.0481077172 0.0458611622 0.1601679325 455 1305031117.3111999035 0.0336008519 0.0334689006 0.0793724135 0.0116170311 0.8099500000 107798374 95654128 1785454592 -0.0526813753 0.0424196385 0.1617248356 456 1305031117.3432428837 0.0360104106 0.0334744741 0.0793724135 0.0116109700 0.7830070000 107800612 95654128 1786978304 -0.0555862337 0.0387551449 0.1634118706 457 1305031117.3794538975 0.0358666815 0.0334797087 0.0793724135 0.0116025814 0.8614360000 107801622 95654128 1785720832 -0.0580482036 0.0365291871 0.1639075577 458 1305031117.4112210274 0.0384123288 0.0334904786 0.0793724135 0.0115903157 0.9266310000 107803828 95654128 1787105280 -0.0604078621 0.0298972074 0.1646613777 459 1305031117.4432740211 0.0367646925 0.0334976120 0.0793724135 0.0115794269 0.8074270000 107806002 95654128 1785581568 -0.0607864112 0.0271149520 0.1638658792 460 1305031117.4794030190 0.0351697430 0.0335012471 0.0793724135 0.0115751694 0.8313530000 107807012 95654128 1787105280 -0.0629800111 0.0218138136 0.1636111736 461 1305031117.5113248825 0.0372683406 0.0335094186 0.0793724135 0.0115654939 0.8993580000 107809342 95654128 1785470976 -0.0618886724 0.0130787240 0.1647993177 462 1305031117.5442850590 0.0341074690 0.0335107131 0.0793724135 0.0115591311 0.9131770000 107811516 95654128 1786978304 -0.0648166537 0.0093739517 0.1637980938 463 1305031117.5791549683 0.0304615460 0.0335041274 0.0793724135 0.0115477284 0.8206270000 107812542 95654128 1785708544 -0.0644794405 0.0030409675 0.1640106142 464 1305031117.6111590862 0.0294100586 0.0334953040 0.0793724135 0.0115359730 0.8065100000 107814716 95654128 1787105280 -0.0662235543 -0.0038887090 0.1654689461 465 1305031117.6432840824 0.0294776782 0.0334866640 0.0793724135 0.0115241073 0.9473530000 107816938 95654128 1784848384 -0.0678119957 -0.0114681358 0.1682881564 466 1305031117.6792619228 0.0248036180 0.0334680308 0.0793724135 0.0115136076 0.8480050000 107817948 95654128 1786343424 -0.0681463182 -0.0175677761 0.1704285443 467 1305031117.7112150192 0.0266876016 0.0334535117 0.0793724135 0.0115030692 0.9894230000 107820246 95654128 1785708544 -0.0677513927 -0.0273974054 0.1749873161 468 1305031117.7431840897 0.0284836292 0.0334428923 0.0793724135 0.0114933820 0.8871850000 107821192 95654128 1787105280 -0.0680622309 -0.0377891213 0.1792403460 469 1305031117.7794671059 0.0228318889 0.0334202675 0.0793724135 0.0114829203 0.7668180000 107823462 95654128 1785581568 -0.0675395429 -0.0437780023 0.1822186261 470 1305031117.8113200665 0.0269385241 0.0334064766 0.0793724135 0.0114761735 0.8247950000 107825668 95654128 1787232256 -0.0668427572 -0.0568037294 0.1880808473 471 1305031117.8433070183 0.0284553524 0.0333959647 0.0793724135 0.0114717343 0.8427380000 107826550 95654128 1785081856 -0.0641504303 -0.0671864003 0.1929813474 472 1305031117.8794670105 0.0232835226 0.0333745400 0.0793724135 0.0114614065 0.9513830000 108004776 95654128 1786351616 -0.0643300638 -0.0744406655 0.1957962811 473 1305031117.9114069939 0.0275827665 0.0333622952 0.0793724135 0.0114505646 0.8255570000 108072482 95654128 1785647104 -0.0663653314 -0.0869017094 0.2018394768 474 1305031117.9432721138 0.0259181820 0.0333465904 0.0793724135 0.0114411288 1.0672240000 108073492 95654128 1786986496 -0.0671632215 -0.0936459452 0.2052978724 475 1305031117.9792630672 0.0236572400 0.0333261917 0.0793724135 0.0114368508 1.0264450000 108075762 95654128 1784954880 -0.0705787018 -0.1011467725 0.2093196213 476 1305031118.0112280846 0.0297107827 0.0333185963 0.0793724135 0.0114296903 1.0276130000 108078096 95654128 1786351616 -0.0713367611 -0.1152285337 0.2165935636 477 1305031118.0435490608 0.0323799141 0.0333166284 0.0793724135 0.0114192781 0.8880790000 108185002 95654128 1785765888 -0.0708524734 -0.1262738258 0.2227565050 478 1305031118.0793690681 0.0307081342 0.0333111713 0.0793724135 0.0114103979 1.0211300000 108252768 95654128 1787105280 -0.0701496601 -0.1347482800 0.2269702554 479 1305031118.1112170219 0.0334689841 0.0333115008 0.0793724135 0.0114008172 0.9914560000 108255082 95654128 1785454592 -0.0710921586 -0.1451711357 0.2328255326 480 1305031118.1432559490 0.0351878926 0.0333154099 0.0793724135 0.0113907478 0.8885120000 108362356 95654128 1786867712 -0.0706340149 -0.1546874195 0.2371681035 481 1305031118.1793229580 0.0379187725 0.0333249803 0.0793724135 0.0113829729 0.9227930000 108430186 95654128 1785622528 -0.0712134168 -0.1673947573 0.2425678521 482 1305031118.2112019062 0.0436724126 0.0333464480 0.0793724135 0.0113716675 0.8861620000 108432424 95654128 1786978304 -0.0742435604 -0.1808943301 0.2482087612 483 1305031118.2431728840 0.0456469283 0.0333719149 0.0793724135 0.0113679243 0.7446540000 108539242 95654128 1785470976 -0.0764349774 -0.1898011267 0.2511876822 484 1305031118.2791941166 0.0476613045 0.0334014384 0.0793724135 0.0113736803 0.7296110000 108607136 95654128 1787105280 -0.0763795376 -0.2015098780 0.2554768026 485 1305031118.3112990856 0.0492551886 0.0334341266 0.0793724135 0.0113627921 0.8851790000 108608222 95654128 1785581568 -0.0775477514 -0.2096880227 0.2593521774 486 1305031118.3433239460 0.0466766842 0.0334613746 0.0793724135 0.0113590014 1.0487350000 108715876 95654128 1786978304 -0.0745711327 -0.2129220217 0.2606162429 487 1305031118.3792080879 0.0493332595 0.0334939658 0.0793724135 0.0113494199 0.8397410000 108783834 95654128 1785708544 -0.0784408525 -0.2209396213 0.2637208700 488 1305031118.4112958908 0.0510556027 0.0335299527 0.0793724135 0.0113412877 1.0720580000 108784780 95654128 1787105280 -0.0808457136 -0.2235631496 0.2632187307 489 1305031118.4457030296 0.0506105907 0.0335648824 0.0793724135 0.0113305634 0.9017420000 108787034 95654128 1784946688 -0.0778038353 -0.2257707268 0.2654457390 490 1305031118.4792850018 0.0517349876 0.0336019643 0.0793724135 0.0113202188 0.8536650000 108789240 95654128 1786343424 -0.0770801380 -0.2289547175 0.2689025402 491 1305031118.5112550259 0.0501444675 0.0336356557 0.0793724135 0.0113104502 0.9057480000 108790326 95654128 1785470976 -0.0738435015 -0.2268378884 0.2689818442 492 1305031118.5451989174 0.0480930880 0.0336650408 0.0793724135 0.0113010653 0.7669930000 108792564 95654128 1786851328 -0.0727299601 -0.2212194800 0.2678096890 493 1305031118.5792849064 0.0486320220 0.0336953998 0.0793724135 0.0112908659 1.0285140000 108794834 95654128 1785454592 -0.0711088777 -0.2191911042 0.2692428231 494 1305031118.6161420345 0.0489204600 0.0337262197 0.0793724135 0.0112808654 1.0026300000 108795860 95654128 1786978304 -0.0686666146 -0.2150901109 0.2689824700 495 1305031118.6453309059 0.0470157303 0.0337530672 0.0793724135 0.0112761980 0.8478410000 108798034 95654128 1784946688 -0.0713569820 -0.2071140856 0.2654232383 496 1305031118.6792950630 0.0463599190 0.0337784843 0.0793724135 0.0112667808 0.7880580000 108800304 95654128 1786343424 -0.0708564445 -0.2001111507 0.2647334039 497 1305031118.7114210129 0.0470076650 0.0338051023 0.0793724135 0.0112619955 0.8634190000 108801358 95654128 1785581568 -0.0707776397 -0.1959758103 0.2646228373 498 1305031118.7468008995 0.0484115630 0.0338344326 0.0793724135 0.0112600360 0.9092740000 108803628 95654128 1786978304 -0.0740004256 -0.1868214160 0.2595193386 499 1305031118.7792770863 0.0390193462 0.0338448232 0.0793724135 0.0112604816 0.8899210000 108805866 95654128 1785327616 -0.0701714754 -0.1681511998 0.2528205514 500 1305031118.8112208843 0.0424183458 0.0338619702 0.0793724135 0.0112818744 0.9091920000 108806780 95654128 1786851328 -0.0675315261 -0.1665925831 0.2531162202 501 1305031118.8467741013 0.0378259383 0.0338698823 0.0793724135 0.0112772893 1.1235350000 108809050 95654128 1784819712 -0.0649903119 -0.1521206051 0.2487098575 502 1305031118.8792080879 0.0269048996 0.0338560079 0.0793724135 0.0113033783 1.0695020000 108812472 95654128 1786343424 -0.0648254827 -0.1297493279 0.2372025847 503 1305031118.9111769199 0.0299668442 0.0338482759 0.0793724135 0.0113337741 0.9019710000 108813718 95654128 1785581568 -0.0639014021 -0.1250454485 0.2332586050 504 1305031118.9470090866 0.0281585138 0.0338369867 0.0793724135 0.0113324587 0.9886680000 108816180 95654128 1786978304 -0.0629115179 -0.1114264578 0.2263811231 505 1305031118.9793939590 0.0212809052 0.0338121232 0.0793724135 0.0113273875 1.1396480000 108817222 95654128 1784946688 -0.0638165474 -0.0947813988 0.2177715749 506 1305031119.0113630295 0.0204814859 0.0337857781 0.0793724135 0.0113268340 0.8909520000 108819460 95654128 1786343424 -0.0644201636 -0.0844959691 0.2113735080 507 1305031119.0471799374 0.0244607497 0.0337673855 0.0793724135 0.0113191034 0.9872840000 108928182 95654128 1788121088 -0.0661998466 -0.0756817162 0.2057573795 508 1305031119.0792229176 0.0234434810 0.0337470629 0.0793724135 0.0113110776 0.9875450000 108995304 95654128 1785335808 -0.0689240023 -0.0645592287 0.1996082962 509 1305031119.1113278866 0.0230671987 0.0337260808 0.0793724135 0.0113064749 0.9285410000 108997682 95654128 1786732544 -0.0705221668 -0.0545256175 0.1932976991 510 1305031119.1476290226 0.0227928627 0.0337046431 0.0793724135 0.0113033186 0.9197240000 108999952 95654128 1784827904 -0.0728230253 -0.0411786735 0.1854522526 511 1305031119.1792619228 0.0267818775 0.0336910956 0.0793724135 0.0113160218 0.9063210000 109001090 95654128 1786114048 -0.0728684142 -0.0359309614 0.1811702102 512 1305031119.2113640308 0.0234640036 0.0336711208 0.0793724135 0.0113058679 0.8931540000 109003296 95654128 1785335808 -0.0730141103 -0.0230829418 0.1742931306 513 1305031119.2476599216 0.0250970852 0.0336544073 0.0793724135 0.0112963334 0.8679940000 109046526 95654128 1786732544 -0.0728598684 -0.0123275965 0.1679620147 514 1305031119.2792439461 0.0239470508 0.0336355214 0.0793724135 0.0112864703 0.8645780000 109131440 95654128 1784954880 -0.0720241442 -0.0014599934 0.1625477672 515 1305031119.3112120628 0.0249435715 0.0336186438 0.0793724135 0.0112773106 0.9622230000 109133770 95654128 1786224640 -0.0749042928 0.0076287463 0.1577000171 516 1305031119.3477499485 0.0292393714 0.0336101569 0.0793724135 0.0112668545 1.0337170000 109136040 95654128 1785741312 -0.0747721046 0.0155104399 0.1538161784 517 1305031119.3792390823 0.0264234152 0.0335962560 0.0793724135 0.0112585522 0.9871120000 109136986 95654128 1784725504 -0.0741098300 0.0296479501 0.1483582705 518 1305031119.4114921093 0.0279376656 0.0335853321 0.0793724135 0.0112497004 0.8626730000 109139192 95654128 1786089472 -0.0725438148 0.0377210192 0.1446986943 519 1305031119.4477260113 0.0318764932 0.0335820395 0.0793724135 0.0112392083 0.8486530000 109141494 95654128 1787994112 -0.0712798536 0.0472694859 0.1408970952 520 1305031119.4792668819 0.0316170417 0.0335782607 0.0793724135 0.0112363665 0.8953950000 109142360 95654128 1784946688 -0.0738134086 0.0589494333 0.1360234171 521 1305031119.5112578869 0.0318821818 0.0335750053 0.0793724135 0.0112287438 1.0750220000 109144706 95654128 1786343424 -0.0767312050 0.0701469854 0.1314149350 522 1305031119.5474140644 0.0351719819 0.0335780646 0.0793724135 0.0112184139 0.8086050000 109145748 95654128 1788121088 -0.0754674822 0.0815189332 0.1282132417 523 1305031119.5795691013 0.0344427228 0.0335797179 0.0793724135 0.0112166717 0.9424830000 109147954 95654128 1784946688 -0.0755691975 0.0959566161 0.1237297505 524 1305031119.6150240898 0.0375839993 0.0335873596 0.0793724135 0.0112190971 0.9904790000 109295340 95654128 1786343424 -0.0762705505 0.1031762213 0.1221257001 525 1305031119.6488890648 0.0396885239 0.0335989809 0.0793724135 0.0112236720 0.8862480000 109321814 95654128 1785708544 -0.0786520094 0.1172636226 0.1187504753 526 1305031119.6792080402 0.0412944518 0.0336136111 0.0793724135 0.0112144357 0.8080300000 109469864 95654128 1787105280 -0.0745938346 0.1301277876 0.1167079359 527 1305031119.7152490616 0.0434388183 0.0336322547 0.0793724135 0.0112086350 0.8424270000 109497814 95654128 1785073664 -0.0760430321 0.1377505213 0.1153355911 528 1305031119.7471930981 0.0479064286 0.0336592892 0.0793724135 0.0112044677 0.7697360000 109644912 95654128 1786597376 -0.0813850462 0.1438599229 0.1149186641 529 1305031119.7791690826 0.0493035875 0.0336888625 0.0793724135 0.0111962347 0.8227710000 109672702 95654128 1785708544 -0.0815689564 0.1532627046 0.1128872856 530 1305031119.8145709038 0.0509778671 0.0337214833 0.0793724135 0.0111899308 1.0082950000 109674908 95654128 1787105280 -0.0805566087 0.1634012014 0.1114719436 531 1305031119.8474450111 0.0548598953 0.0337612919 0.0793724135 0.0111822996 0.9262790000 109821082 95654128 1784946688 -0.0790286064 0.1737462580 0.1106344536 532 1305031119.8792319298 0.0592084713 0.0338091250 0.0793724135 0.0111785928 0.9072240000 109848904 95654128 1786470400 -0.0784972757 0.1790955067 0.1110472828 533 1305031119.9114239216 0.0561667345 0.0338510717 0.0793724135 0.0111952757 0.8045140000 109851250 95654128 1784692736 -0.0808049142 0.1952921599 0.1054843366 534 1305031119.9474620819 0.0599822216 0.0339000065 0.0793724135 0.0111910815 0.8443740000 109997796 95654128 1786105856 -0.0799568743 0.2009965777 0.1047585458 535 1305031119.9795460701 0.0614938512 0.0339515837 0.0793724135 0.0111809802 0.8869980000 110025730 95654128 1787994112 -0.0798737258 0.2077750415 0.1033987105 536 1305031120.0152831078 0.0591144972 0.0339985295 0.0793724135 0.0111998485 0.8904850000 110172552 95654128 1785073664 -0.0826547444 0.2215090096 0.0988555923 537 1305031120.0473101139 0.0643451214 0.0340550408 0.0793724135 0.0112131416 0.9071210000 110199286 95654128 1786470400 -0.0848306492 0.2191686481 0.1016955674 538 1305031120.0794179440 0.0655098930 0.0341135071 0.0793724135 0.0112107055 0.9268780000 110201492 95654128 1785454592 -0.0857170969 0.2186058164 0.1013796255 539 1305031120.1152489185 0.0649603233 0.0341707368 0.0793724135 0.0112083604 0.8210650000 110202610 95654128 1786724352 -0.0838958248 0.2229285836 0.1000876576 540 1305031120.1481750011 0.0677203909 0.0342328658 0.0793724135 0.0112192729 0.8260450000 110204848 95654128 1784946688 -0.0836152136 0.2182801664 0.1030566618 541 1305031120.1792609692 0.0697734058 0.0342985600 0.0793724135 0.0112097728 0.7864730000 110207022 95654128 1786216448 -0.0830138326 0.2169999033 0.1056683511 542 1305031120.2152600288 0.0697440580 0.0343639576 0.0793724135 0.0112008880 0.9299860000 110208048 95654128 1788121088 -0.0842369422 0.2152536213 0.1069764122 543 1305031120.2480180264 0.0664113835 0.0344229768 0.0793724135 0.0111922324 0.9296550000 110210286 95654128 1784963072 -0.0835734159 0.2123603970 0.1061108410 544 1305031120.2794411182 0.0648749918 0.0344789547 0.0793724135 0.0111844255 0.9630840000 110212492 95654128 1786216448 -0.0844664276 0.2064481974 0.1076807901 545 1305031120.3152129650 0.0639587343 0.0345330461 0.0793724135 0.0111746259 1.0706180000 110213610 95654128 1787994112 -0.0833203569 0.1979998946 0.1105387881 546 1305031120.3477969170 0.0594238825 0.0345786337 0.0793724135 0.0111656548 0.9004060000 110215832 95654128 1784967168 -0.0825646520 0.1892418712 0.1120945886 547 1305031120.3794460297 0.0594671555 0.0346241337 0.0793724135 0.0111563147 1.0295000000 110220598 95654128 1786470400 -0.0817853510 0.1794167906 0.1175462604 548 1305031120.4154899120 0.0598366298 0.0346701419 0.0793724135 0.0111496216 0.9022340000 110221592 95654128 1785716736 -0.0839850903 0.1768262982 0.1230488196 549 1305031120.4474329948 0.0500391051 0.0346981364 0.0793724135 0.0111842458 0.9075360000 110224086 95654128 1787113472 -0.0766016841 0.1497361809 0.1217247769 550 1305031120.4794321060 0.0506891608 0.0347272110 0.0793724135 0.0111746430 0.9071800000 110226356 95654128 1785462784 -0.0777642503 0.1366387904 0.1277320981 551 1305031120.5148770809 0.0496309996 0.0347542596 0.0793724135 0.0111647537 0.9866770000 110227794 95654128 1786859520 -0.0782822073 0.1250478029 0.1323702782 552 1305031120.5478069782 0.0445014164 0.0347719175 0.0793724135 0.0111561386 1.1275370000 110229840 95654128 1784827904 -0.0796242207 0.1161159128 0.1360495836 553 1305031120.5795590878 0.0425905697 0.0347860561 0.0793724135 0.0111497863 1.1460460000 110232142 95654128 1786216448 -0.0810978338 0.1085663810 0.1400475949 554 1305031120.6152710915 0.0432884954 0.0348014035 0.0793724135 0.0111462542 1.0042940000 110233280 95654128 1787994112 -0.0776560828 0.0977343023 0.1459140927 555 1305031120.6473538876 0.0396866463 0.0348102057 0.0793724135 0.0111396593 1.0233250000 110235582 95654128 1784946688 -0.0752489865 0.0889816210 0.1507078856 556 1305031120.6793179512 0.0383205935 0.0348165193 0.0793724135 0.0111578985 1.0504220000 110237564 95654128 1786470400 -0.0724434927 0.0815643072 0.1548295468 557 1305031120.7145531178 0.0365139507 0.0348195668 0.0793724135 0.0111480551 1.1462670000 110238650 95654128 1785708544 -0.0742307603 0.0732797906 0.1589702964 558 1305031120.7473959923 0.0337121822 0.0348175822 0.0793724135 0.0111434273 0.9633140000 110241048 95654128 1787105280 -0.0743509457 0.0618804619 0.1630932540 559 1305031120.7799079418 0.0353086144 0.0348184607 0.0793724135 0.0111375264 0.9907450000 110241994 95654128 1784819712 -0.0703428313 0.0506926998 0.1686586440 560 1305031120.8149440289 0.0316183902 0.0348127462 0.0793724135 0.0111429575 1.0501060000 110388060 95654128 1786343424 -0.0719528124 0.0453266762 0.1706772447 561 1305031120.8479421139 0.0296918526 0.0348036181 0.0793724135 0.0111415579 1.0623110000 110416794 95654128 1785708544 -0.0705046505 0.0338722169 0.1746185273 562 1305031120.8834540844 0.0310641993 0.0347969643 0.0793724135 0.0111336273 1.3595250000 110417836 95654128 1787232256 -0.0691795349 0.0232347511 0.1791070700 563 1305031120.9154539108 0.0276248083 0.0347842251 0.0793724135 0.0111339283 2.3518070000 110420470 95654128 1784946688 -0.0705864355 0.0175632350 0.1808953434 564 1305031120.9475090504 0.0260985307 0.0347688250 0.0793724135 0.0111244896 1.9609050000 110422868 95654128 1786216448 -0.0706323236 0.0066699004 0.1844525635 565 1305031120.9833900928 0.0269255936 0.0347549431 0.0793724135 0.0111175177 1.3741860000 110423686 95654128 1788121088 -0.0715312511 -0.0037763473 0.1875293106 566 1305031121.0150289536 0.0288117807 0.0347444429 0.0793724135 0.0111136788 2.0158650000 110425924 95654128 1784946688 -0.0714287907 -0.0146675631 0.1908317506 567 1305031121.0477550030 0.0235724580 0.0347247392 0.0793724135 0.0111044192 1.1651640000 110428258 95654128 1786216448 -0.0726969838 -0.0216595009 0.1916720420 568 1305031121.0831170082 0.0286914799 0.0347141172 0.0793724135 0.0110967124 1.1460780000 110573372 95654128 1785520128 -0.0744573325 -0.0355162546 0.1956243515 569 1305031121.1148779392 0.0280836821 0.0347024645 0.0793724135 0.0110899298 1.1621020000 110602074 95654128 1784692736 -0.0745312795 -0.0439573117 0.1972516030 570 1305031121.1473550797 0.0262094662 0.0346875645 0.0793724135 0.0110826634 1.0448110000 110604312 95654128 1785962496 -0.0754901841 -0.0538483262 0.1990160197 571 1305031121.1832809448 0.0272352882 0.0346745132 0.0793724135 0.0110738595 0.9859740000 110749310 95654128 1787740160 -0.0755290538 -0.0636427179 0.2016634792 572 1305031121.2114310265 0.0285222251 0.0346637574 0.0793724135 0.0110669220 0.7857530000 110777888 95654128 1784832000 -0.0741233379 -0.0743033513 0.2043921649 573 1305031121.2472009659 0.0244879089 0.0346459985 0.0793724135 0.0110593134 0.9259540000 110780158 95654128 1786216448 -0.0771522447 -0.0810589716 0.2058517486 574 1305031121.2828760147 0.0276427902 0.0346337978 0.0793724135 0.0110517662 0.8711330000 110925220 95654128 1785327616 -0.0776088685 -0.0925209448 0.2099585533 575 1305031121.3135879040 0.0309794508 0.0346274425 0.0793724135 0.0110444082 0.8058090000 110954066 95654128 1786851328 -0.0763843358 -0.1047000960 0.2139565796 576 1305031121.3475399017 0.0287269726 0.0346171986 0.0793724135 0.0110360459 0.7619520000 110955044 95654128 1784819712 -0.0795648023 -0.1119779199 0.2155215591 577 1305031121.3832480907 0.0315772220 0.0346119300 0.0793724135 0.0110430102 0.8704560000 110957330 95654128 1786343424 -0.0752426982 -0.1250059456 0.2213000804 578 1305031121.4143280983 0.0323091522 0.0346079459 0.0793724135 0.0110350556 0.9480350000 111102728 95654128 1788002304 -0.0762611777 -0.1337566823 0.2229879051 579 1305031121.4473190308 0.0305442847 0.0346009275 0.0793724135 0.0110297216 0.7670440000 111130322 95654128 1785131008 -0.0763739571 -0.1413638741 0.2241163999 580 1305031121.4830150604 0.0347942114 0.0346012608 0.0793724135 0.0110307540 0.8992220000 111132560 95654128 1786494976 -0.0741620585 -0.1552678794 0.2301042527 581 1305031121.5141639709 0.0349386372 0.0346018415 0.0793724135 0.0110364882 0.8366320000 111134890 95654128 1785716736 -0.0795679837 -0.1605654210 0.2290179729 582 1305031121.5472700596 0.0327070430 0.0345985858 0.0793724135 0.0110295432 0.9558260000 111281236 95654128 1787240448 -0.0789205059 -0.1667185724 0.2308319211 583 1305031121.5832130909 0.0352668017 0.0345997320 0.0793724135 0.0110212599 0.9039740000 111310206 95654128 1784954880 -0.0789268911 -0.1784772724 0.2362003624 584 1305031121.6147189140 0.0369354300 0.0346037314 0.0793724135 0.0110129587 0.8077030000 111312380 95654128 1786351616 -0.0791251957 -0.1872367859 0.2383325994 585 1305031121.6471829414 0.0356508866 0.0346055215 0.0793724135 0.0110074879 0.7654200000 111313342 95654128 1785462784 -0.0782635510 -0.1932974458 0.2398091257 586 1305031121.6832110882 0.0393289551 0.0346135819 0.0793724135 0.0110023866 0.9657260000 111315644 95654128 1786859520 -0.0822573677 -0.2010448426 0.2412362099 587 1305031121.7145280838 0.0424704440 0.0346269667 0.0793724135 0.0109948922 1.0058420000 111317958 95654128 1784827904 -0.0838667303 -0.2100299895 0.2442156672 588 1305031121.7471449375 0.0432442427 0.0346416219 0.0793724135 0.0109858639 1.1072160000 111318904 95654128 1786224640 -0.0837265477 -0.2152240425 0.2461956441 589 1305031121.7828710079 0.0452529490 0.0346596378 0.0793724135 0.0109770068 1.1506680000 111321174 95654128 1788121088 -0.0829855055 -0.2231416702 0.2506405711 590 1305031121.8115448952 0.0453151800 0.0346776980 0.0793724135 0.0109718085 1.0025300000 111323348 95654128 1785073664 -0.0803535134 -0.2272853255 0.2532029748 591 1305031121.8473351002 0.0472052693 0.0346988952 0.0793724135 0.0109651578 0.8900470000 111324358 95654128 1786470400 -0.0814287961 -0.2299989164 0.2551171184 592 1305031121.8821229935 0.0487541556 0.0347226372 0.0793724135 0.0109585752 1.0051330000 111469668 95654128 1785708544 -0.0825035498 -0.2322335839 0.2562989295 593 1305031121.9149429798 0.0490742661 0.0347468390 0.0793724135 0.0109500603 1.0191710000 111497690 95654128 1787232256 -0.0821818262 -0.2332536876 0.2575534582 594 1305031121.9473180771 0.0488076471 0.0347705104 0.0793724135 0.0109424912 0.9110940000 111499896 95654128 1784836096 -0.0794046596 -0.2342947423 0.2596414089 595 1305031121.9829349518 0.0471292734 0.0347912814 0.0793724135 0.0109342158 1.1471600000 111502166 95654128 1786216448 -0.0786102861 -0.2295219004 0.2581796646 596 1305031122.0144240856 0.0472889505 0.0348122506 0.0793724135 0.0109255638 1.0670030000 111503112 95654128 1788010496 -0.0803939551 -0.2265602499 0.2576479912 597 1305031122.0473060608 0.0474130921 0.0348333576 0.0793724135 0.0109177894 1.0063590000 111505318 95654128 1784946688 -0.0811084136 -0.2207470536 0.2550633550 598 1305031122.0829689503 0.0457391925 0.0348515948 0.0793724135 0.0109097249 0.9206080000 111507588 95654128 1786343424 -0.0800191835 -0.2139360309 0.2529188991 599 1305031122.1146879196 0.0443692617 0.0348674840 0.0793724135 0.0109045880 0.8256210000 111508642 95654128 1785581568 -0.0817172453 -0.2037496567 0.2477114946 600 1305031122.1507480145 0.0435981378 0.0348820351 0.0793724135 0.0108971969 0.8723540000 111510912 95654128 1786978304 -0.0807135403 -0.1947222650 0.2451753169 601 1305031122.1830520630 0.0418109447 0.0348935641 0.0793724135 0.0109015421 0.9264520000 111513150 95654128 1784819712 -0.0789460838 -0.1846822351 0.2406965196 602 1305031122.2149689198 0.0356910564 0.0348948888 0.0793724135 0.0109084069 0.8277150000 111657852 95654128 1786216448 -0.0810161233 -0.1645440161 0.2329477221 603 1305031122.2513549328 0.0368829258 0.0348981857 0.0793724135 0.0109004757 1.0630990000 111687278 95654128 1785581568 -0.0783376023 -0.1581762284 0.2328884155 604 1305031122.2838659286 0.0340170600 0.0348967269 0.0793724135 0.0108932762 1.0686150000 111689516 95654128 1786978304 -0.0796078593 -0.1449737847 0.2277894318 605 1305031122.3143088818 0.0273735225 0.0348842919 0.0793724135 0.0108893039 0.9070670000 111834454 95654128 1784819712 -0.0813375860 -0.1262112260 0.2214292437 606 1305031122.3513510227 0.0283718593 0.0348735453 0.0793724135 0.0108846404 0.8482240000 111863896 95654128 1786343424 -0.0816600248 -0.1160205603 0.2183276266 607 1305031122.3826780319 0.0210271459 0.0348507341 0.0793724135 0.0108816538 0.9201940000 111866134 95654128 1785581568 -0.0838514715 -0.0977242291 0.2120723277 608 1305031122.4150080681 0.0225911159 0.0348305702 0.0793724135 0.0108849486 0.8699350000 111867016 95654128 1786978304 -0.0836877599 -0.0912756696 0.2085346580 609 1305031122.4512720108 0.0220322665 0.0348095549 0.0793724135 0.0108800530 0.9387050000 111869318 95654128 1784852480 -0.0840227306 -0.0788505673 0.2018790841 610 1305031122.4833879471 0.0210073087 0.0347869283 0.0793724135 0.0108793985 0.9878770000 111871524 95654128 1786216448 -0.0844822079 -0.0688975826 0.1967266798 611 1305031122.5151350498 0.0190235600 0.0347611290 0.0793724135 0.0108764800 0.9301310000 111876018 95654128 1787994112 -0.0822514519 -0.0585840754 0.1915617436 612 1305031122.5515100956 0.0199426040 0.0347369157 0.0793724135 0.0108702970 1.1494020000 112022420 95654128 1784946688 -0.0824656636 -0.0469820239 0.1850590110 613 1305031122.5832169056 0.0205948073 0.0347138454 0.0793724135 0.0108645129 0.9630040000 112050682 95654128 1786470400 -0.0830587074 -0.0375526994 0.1802980602 614 1305031122.6150169373 0.0235555600 0.0346956723 0.0793724135 0.0108602337 1.0656180000 112052904 95654128 1784827904 -0.0866603702 -0.0302530304 0.1757894158 615 1305031122.6488099098 0.0254368093 0.0346806173 0.0793724135 0.0108516911 0.9053620000 112055190 95654128 1786241024 -0.0845702365 -0.0187721774 0.1705521643 616 1305031122.6834199429 0.0254204385 0.0346655845 0.0793724135 0.0108446523 0.8277480000 112056152 95654128 1787875328 -0.0875470042 -0.0081093069 0.1649477184 617 1305031122.7152190208 0.0263116639 0.0346520449 0.0793724135 0.0108371312 1.0668540000 112058530 95654128 1784954880 -0.0881681368 0.0017001880 0.1608963609 618 1305031122.7513089180 0.0266766604 0.0346391398 0.0793724135 0.0108340460 1.0422550000 112060768 95654128 1786224640 -0.0846474096 0.0162923113 0.1562972665 619 1305031122.7834379673 0.0245903060 0.0346229058 0.0793724135 0.0108276242 0.9527860000 112061906 95654128 1788256256 -0.0876838565 0.0301739518 0.1514893323 620 1305031122.8125650883 0.0265579224 0.0346098978 0.0793724135 0.0108212804 1.1293290000 112064272 95654128 1784573952 -0.0863676891 0.0399064869 0.1492527723 621 1305031122.8514859676 0.0322457142 0.0346060907 0.0793724135 0.0108186514 1.0140480000 112066638 95654128 1785851904 -0.0828304738 0.0472472832 0.1482333690 622 1305031122.8837749958 0.0312846266 0.0346007507 0.0793724135 0.0108167126 1.0347280000 112067664 95654128 1787756544 -0.0854912922 0.0584173687 0.1442072690 623 1305031122.9145851135 0.0341501683 0.0346000275 0.0793724135 0.0108133885 1.1021270000 112215090 95654128 1784827904 -0.0889707133 0.0641983226 0.1424085498 624 1305031122.9514129162 0.0377968103 0.0346051505 0.0793724135 0.0108058134 1.0845550000 112245156 95654128 1786351616 -0.0893166587 0.0714743659 0.1399747878 625 1305031122.9830000401 0.0370629951 0.0346090831 0.0793724135 0.0107987200 0.9641210000 112246166 95654128 1785716736 -0.0922693163 0.0816697404 0.1361305416 626 1305031123.0154619217 0.0388966426 0.0346159322 0.0793724135 0.0107906338 0.9496770000 112248148 95654128 1787113472 -0.0911301002 0.0893776789 0.1341633201 627 1305031123.0518379211 0.0431275368 0.0346295073 0.0793724135 0.0107834529 1.0223760000 112250498 95654128 1784827904 -0.0899646804 0.0968372747 0.1326269209 628 1305031123.0829920769 0.0412537456 0.0346400555 0.0793724135 0.0107785344 0.9742160000 112395104 95654128 1786224640 -0.0914428309 0.1090936512 0.1277979463 629 1305031123.1139390469 0.0409192778 0.0346500384 0.0793724135 0.0107718748 1.0644940000 112425158 95654128 1785716736 -0.0918916091 0.1219448745 0.1244219169 630 1305031123.1508400440 0.0441372730 0.0346650975 0.0793724135 0.0107650715 1.1431370000 112426264 95654128 1787113472 -0.0917373300 0.1272093207 0.1228454858 631 1305031123.1821761131 0.0455799736 0.0346823952 0.0793724135 0.0107614875 1.0406590000 112428534 95654128 1784827904 -0.0895938501 0.1360999346 0.1209644601 632 1305031123.2147240639 0.0473923758 0.0347025059 0.0793724135 0.0107535324 1.0661120000 112573760 95654128 1786224640 -0.0877565742 0.1446516365 0.1197694987 633 1305031123.2506411076 0.0474011339 0.0347225669 0.0793724135 0.0107644583 1.1297320000 112602498 95654128 1785589760 -0.0914549008 0.1577253193 0.1166094095 634 1305031123.2823629379 0.0503999852 0.0347472947 0.0793724135 0.0107622117 0.9455140000 112604720 95654128 1786986496 -0.0914511085 0.1697573811 0.1174912900 635 1305031123.3209919930 0.0542900153 0.0347780707 0.0793724135 0.0107619706 0.9006390000 112607162 95654128 1784827904 -0.0888768286 0.1801330894 0.1177653596 636 1305031123.3504929543 0.0559826605 0.0348114112 0.0793724135 0.0107570740 1.0836740000 112608076 95654128 1786224640 -0.0885352716 0.1898226142 0.1172027886 637 1305031123.3822629452 0.0576521829 0.0348472680 0.0793724135 0.0107496396 1.1687980000 112610314 95654128 1788002304 -0.0873131230 0.2005667686 0.1163188070 638 1305031123.4213430882 0.0626021996 0.0348907710 0.0793724135 0.0107419885 0.9035110000 112612616 95654128 1785085952 -0.0857676715 0.2078302950 0.1169870794 639 1305031123.4512660503 0.0623848364 0.0349337977 0.0793724135 0.0107466701 0.8465390000 112757754 95654128 1786478592 -0.0856950954 0.2202653289 0.1143246517 640 1305031123.4836049080 0.0636255294 0.0349786286 0.0793724135 0.0107419722 1.0080080000 112787864 95654128 1784700928 -0.0837220550 0.2294273823 0.1127243042 641 1305031123.5197250843 0.0678445548 0.0350299015 0.0793724135 0.0107370662 0.9255280000 112790242 95654128 1786097664 -0.0810292885 0.2334121168 0.1127307042 642 1305031123.5515730381 0.0687843785 0.0350824785 0.0793724135 0.0107301601 0.9240550000 112934720 95654128 1788002304 -0.0768396780 0.2402301133 0.1107387617 643 1305031123.5796160698 0.0711345151 0.0351385470 0.0793724135 0.0107239534 1.2646710000 112964766 95654128 1784954880 -0.0755099729 0.2473869175 0.1104393750 644 1305031123.6203870773 0.0711376294 0.0351944462 0.0793724135 0.0107273989 1.1623920000 112967100 95654128 1786351616 -0.0733639896 0.2587670088 0.1076526940 645 1305031123.6524300575 0.0724375099 0.0352521874 0.0793724135 0.0107237317 0.9277960000 112968046 95654128 1785589760 -0.0715001673 0.2638434470 0.1068712547 646 1305031123.6837849617 0.0758414567 0.0353150191 0.0793724135 0.0107157872 0.8828340000 113113140 95654128 1787002880 -0.0662553087 0.2691724896 0.1074902788 647 1305031123.7199749947 0.0772135183 0.0353797772 0.0793724135 0.0107078304 0.9283200000 113142186 95654128 1784958976 -0.0648310259 0.2761370540 0.1060491502 648 1305031123.7519800663 0.0797128677 0.0354481925 0.0797128677 0.0107078902 1.0274810000 113144532 95654128 1786351616 -0.0654067621 0.2777234018 0.1069834679 649 1305031123.7841379642 0.0806474760 0.0355178370 0.0806474760 0.0107056971 1.0083210000 113146706 95654128 1788026880 -0.0637657866 0.2792061269 0.1063374653 650 1305031123.8196959496 0.0813269764 0.0355883126 0.0813269764 0.0106992022 0.8435790000 113290116 95654128 1784983552 -0.0620990470 0.2809263468 0.1053411365 651 1305031123.8515510559 0.0818291306 0.0356593430 0.0818291306 0.0106915150 0.9050930000 113320426 95654128 1786359808 -0.0619169660 0.2812973559 0.1053392738 652 1305031123.8838191032 0.0838837773 0.0357333069 0.0838837773 0.0106874578 1.0619550000 113322632 95654128 1785724928 -0.0617286377 0.2783625424 0.1067985520 653 1305031123.9157938957 0.0826025605 0.0358050821 0.0838837773 0.0106826920 0.8685930000 113323546 95654128 1787121664 -0.0610872731 0.2764124572 0.1063866392 654 1305031123.9515299797 0.0780982897 0.0358697507 0.0838837773 0.0106969729 0.9460490000 113325832 95654128 1784963072 -0.0621749237 0.2785939872 0.1039596498 655 1305031123.9834210873 0.0823941156 0.0359407802 0.0838837773 0.0107142928 1.0463290000 113328038 95654128 1786359808 -0.0637818798 0.2688314021 0.1098973751 656 1305031124.0197370052 0.0807842687 0.0360091392 0.0838837773 0.0107115074 1.0278840000 113329188 95654128 1788137472 -0.0631845817 0.2691782117 0.1123291329 657 1305031124.0515310764 0.0774775520 0.0360722570 0.0838837773 0.0107241858 1.1043480000 113331362 95654128 1784954880 -0.0625187531 0.2648021579 0.1120134518 658 1305031124.0839018822 0.0783072636 0.0361364440 0.0838837773 0.0107245407 0.7808170000 113333568 95654128 1786351616 -0.0644618422 0.2569253147 0.1166867912 659 1305031124.1196689606 0.0757249296 0.0361965175 0.0838837773 0.0107176590 1.0115060000 113334578 95654128 1785589760 -0.0651966408 0.2556154132 0.1197459847 660 1305031124.1474580765 0.0712632090 0.0362496489 0.0838837773 0.0107263477 1.0243250000 113336752 95654128 1786986496 -0.0648921877 0.2474624664 0.1192704886 661 1305031124.1827070713 0.0720424801 0.0363037984 0.0838837773 0.0107240654 0.9267960000 113338990 95654128 1784827904 -0.0669480264 0.2377292067 0.1248865053 662 1305031124.2171790600 0.0699247792 0.0363545854 0.0838837773 0.0107197860 0.8273060000 113340108 95654128 1786224640 -0.0674502701 0.2317047119 0.1282129288 663 1305031124.2493400574 0.0649805069 0.0363977617 0.0838837773 0.0107375663 0.7885450000 113342282 95654128 1788002304 -0.0693850666 0.2219267040 0.1277364492 664 1305031124.2825551033 0.0638165474 0.0364390551 0.0838837773 0.0107352296 0.8418120000 113344520 95654128 1784954880 -0.0725898147 0.2114482224 0.1310641170 665 1305031124.3167819977 0.0620791987 0.0364776117 0.0838837773 0.0107306870 0.8723560000 113345514 95654128 1786351616 -0.0725427121 0.2044400722 0.1342426687 666 1305031124.3503708839 0.0607337877 0.0365140324 0.0838837773 0.0107274192 0.8227300000 113347720 95654128 1785647104 -0.0719063953 0.1937596798 0.1363075972 667 1305031124.3824319839 0.0613425858 0.0365512566 0.0838837773 0.0107247632 0.7844710000 113349958 95654128 1786986496 -0.0702856109 0.1809468120 0.1401970983 668 1305031124.4185550213 0.0588468947 0.0365846333 0.0838837773 0.0107181267 1.0255810000 113351140 95654128 1784827904 -0.0710336193 0.1719105095 0.1422905028 669 1305031124.4502561092 0.0563872159 0.0366142336 0.0838837773 0.0107253183 0.8904900000 113353298 95654128 1786224640 -0.0734084994 0.1708251983 0.1430357546 670 1305031124.4801259041 0.0548116975 0.0366413940 0.0838837773 0.0107209055 1.0234910000 113499904 95654128 1788129280 -0.0733957887 0.1526742280 0.1456690878 671 1305031124.5167369843 0.0505811870 0.0366621686 0.0838837773 0.0107174549 0.9423020000 113530810 95654128 1785208832 -0.0739946812 0.1482930928 0.1461757869 672 1305031124.5505030155 0.0496594198 0.0366815098 0.0838837773 0.0107236902 1.0703150000 113533000 95654128 1786478592 -0.0742197782 0.1254512519 0.1504075974 673 1305031124.5846059322 0.0477789566 0.0366979993 0.0838837773 0.0107257309 1.1651840000 113534170 95654128 1785843712 -0.0718634576 0.1047821939 0.1508430690 674 1305031124.6176528931 0.0417105742 0.0367054363 0.0838837773 0.0107295033 1.1100410000 113536612 95654128 1787113472 -0.0723070726 0.0929059833 0.1524403095 675 1305031124.6513130665 0.0399825647 0.0367102914 0.0838837773 0.0107283237 1.1293180000 113538882 95654128 1784844288 -0.0712539926 0.0814768001 0.1555349529 676 1305031124.6854729652 0.0410721451 0.0367167438 0.0838837773 0.0107251900 0.8973350000 113539796 95654128 1786224640 -0.0686162189 0.0670805052 0.1605851501 677 1305031124.7157909870 0.0344144218 0.0367133430 0.0838837773 0.0107184988 0.9464590000 113542306 95654128 1788129280 -0.0687267631 0.0575294867 0.1629643887 678 1305031124.7499411106 0.0338778123 0.0367091608 0.0838837773 0.0107111480 0.8258790000 113544544 95654128 1785020416 -0.0699842572 0.0436558872 0.1670315713 679 1305031124.7851779461 0.0334150568 0.0367043094 0.0838837773 0.0107041560 1.0035200000 113545266 95654128 1786351616 -0.0707401335 0.0308506470 0.1714711040 680 1305031124.8166410923 0.0271559209 0.0366902677 0.0838837773 0.0106975943 0.8888150000 113547804 95654128 1785716736 -0.0696202740 0.0203097630 0.1757707745 681 1305031124.8505589962 0.0287183467 0.0366785615 0.0838837773 0.0106909935 1.0446550000 113550234 95654128 1787113472 -0.0698726103 0.0058649462 0.1818041354 682 1305031124.8835940361 0.0298092254 0.0366684891 0.0838837773 0.0106895985 0.9197720000 113551100 95654128 1784700928 -0.0658880472 -0.0067015979 0.1886262149 683 1305031124.9187700748 0.0223789755 0.0366475674 0.0838837773 0.0107002563 0.8321680000 113553434 95654128 1786224640 -0.0675615445 -0.0139985327 0.1935750991 684 1305031124.9507479668 0.0251301713 0.0366307292 0.0838837773 0.0107046169 1.0702100000 113555416 95654128 1788256256 -0.0677987337 -0.0271136649 0.2000860274 685 1305031124.9864599705 0.0299211424 0.0366209341 0.0838837773 0.0107177650 0.9469640000 113556618 95654128 1784582144 -0.0698071569 -0.0451902486 0.2078448683 686 1305031125.0194671154 0.0312915780 0.0366131654 0.0838837773 0.0107165500 1.1243640000 113559060 95654128 1785978880 -0.0723050535 -0.0556790158 0.2126609236 687 1305031125.0507979393 0.0261371862 0.0365979165 0.0838837773 0.0107242653 1.0934710000 113559910 95654128 1787756544 -0.0670121014 -0.0600799918 0.2166006565 688 1305031125.0834798813 0.0305899903 0.0365891841 0.0838837773 0.0107191588 0.9239570000 113562212 95654128 1784987648 -0.0691791177 -0.0727951229 0.2219137996 689 1305031125.1190290451 0.0320539884 0.0365826018 0.0838837773 0.0107194416 1.1016550000 113564674 95654128 1786359808 -0.0694800913 -0.0859888345 0.2272354364 690 1305031125.1510369778 0.0305967480 0.0365739266 0.0838837773 0.0107192195 0.9462910000 113565652 95654128 1788264448 -0.0672414228 -0.0933003947 0.2312365323 691 1305031125.1870639324 0.0231726952 0.0365545327 0.0838837773 0.0107218447 1.1056100000 113567890 95654128 1784446976 -0.0700899959 -0.0953417942 0.2317181677 692 1305031125.2190179825 0.0287641156 0.0365432748 0.0838837773 0.0107218980 1.1656390000 113570412 95654128 1785843712 -0.0716310591 -0.1087417230 0.2378343791 693 1305031125.2506420612 0.0365705006 0.0365433141 0.0838837773 0.0107151110 1.0490140000 113571134 95654128 1787748352 -0.0741586462 -0.1240593046 0.2420518696 694 1305031125.2863960266 0.0302527472 0.0365342499 0.0838837773 0.0107128371 1.0848690000 113573340 95654128 1784971264 -0.0746902898 -0.1265476048 0.2431610525 695 1305031125.3191399574 0.0332860798 0.0365295763 0.0838837773 0.0107078681 1.1855290000 113575578 95654128 1786351616 -0.0753964782 -0.1366497576 0.2478178889 696 1305031125.3488988876 0.0342194028 0.0365262571 0.0838837773 0.0107067062 0.9067920000 113576460 95654128 1788256256 -0.0783438981 -0.1434772760 0.2493553460 697 1305031125.3867919445 0.0320245996 0.0365197984 0.0838837773 0.0107065932 0.8015250000 113578794 95654128 1784700928 -0.0764594376 -0.1484180689 0.2515678108 698 1305031125.4195740223 0.0334528312 0.0365154045 0.0838837773 0.0107002829 0.8270150000 113581156 95654128 1785970688 -0.0764599591 -0.1545172632 0.2545375526 699 1305031125.4512319565 0.0346033797 0.0365126691 0.0838837773 0.0106986834 0.8874540000 113582102 95654128 1788002304 -0.0782843307 -0.1603201777 0.2578316033 700 1305031125.4869990349 0.0378338359 0.0365145565 0.0838837773 0.0106947338 1.0249440000 113584372 95654128 1784954880 -0.0781042054 -0.1695003957 0.2620882392 701 1305031125.5193541050 0.0379166342 0.0365165566 0.0838837773 0.0106945656 0.8264970000 113586610 95654128 1786241024 -0.0805098563 -0.1705894917 0.2612670660 702 1305031125.5510499477 0.0378980748 0.0365185246 0.0838837773 0.0106902585 1.1088140000 113587524 95654128 1788002304 -0.0792084187 -0.1735081673 0.2631554604 703 1305031125.5853030682 0.0384164974 0.0365212244 0.0838837773 0.0106828339 0.9258880000 113589762 95654128 1784954880 -0.0786058083 -0.1759224981 0.2644102573 704 1305031125.6178700924 0.0424696840 0.0365296739 0.0838837773 0.0106871135 0.7827280000 113590880 95654128 1786368000 -0.0789277479 -0.1818618327 0.2660672069 705 1305031125.6505749226 0.0464984737 0.0365438141 0.0838837773 0.0106853928 1.0274570000 113593102 95654128 1785462784 -0.0842593387 -0.1839418411 0.2635773122 706 1305031125.6846020222 0.0442012958 0.0365546604 0.0838837773 0.0106815249 1.0093230000 113595308 95654128 1786859520 -0.0878586695 -0.1764984131 0.2564263344 707 1305031125.7156689167 0.0452329591 0.0365669352 0.0838837773 0.0107220147 0.8047730000 113596254 95654128 1784827904 -0.0842749923 -0.1770419031 0.2572570741 708 1305031125.7512919903 0.0387771428 0.0365700570 0.0838837773 0.0107274053 0.9070270000 113598524 95654128 1786224640 -0.0810021609 -0.1658416092 0.2501646876 709 1305031125.7868049145 0.0367985144 0.0365703792 0.0838837773 0.0107201209 0.9218460000 113600794 95654128 1788002304 -0.0788290203 -0.1580322981 0.2469045818 710 1305031125.8194499016 0.0342476629 0.0365671077 0.0838837773 0.0107174712 1.8603340000 113601912 95654128 1784954880 -0.0782088935 -0.1490867287 0.2424121648 711 1305031125.8547739983 0.0337918922 0.0365632045 0.0838837773 0.0107163030 2.0614690000 113604118 95654128 1786351616 -0.0778862685 -0.1421087831 0.2394012213 712 1305031125.8866450787 0.0357802995 0.0365621049 0.0838837773 0.0107193953 1.7834840000 113606356 95654128 1785589760 -0.0804548934 -0.1336202323 0.2346850932 713 1305031125.9193339348 0.0331817605 0.0365573639 0.0838837773 0.0107214333 1.3789520000 113607334 95654128 1786986496 -0.0823971853 -0.1215783805 0.2299198061 714 1305031125.9552519321 0.0349686220 0.0365551388 0.0838837773 0.0107242260 1.8701810000 113610852 95654128 1784954880 -0.0825977400 -0.1152661815 0.2285691947 715 1305031125.9870939255 0.0333331823 0.0365506325 0.0838837773 0.0107206139 1.4827780000 113613394 95654128 1786486784 -0.0798257068 -0.1021751538 0.2249044478 716 1305031126.0195720196 0.0287513100 0.0365397396 0.0838837773 0.0107189378 1.7876970000 113614576 95654128 1788264448 -0.0745112076 -0.0887324288 0.2220071554 717 1305031126.0550379753 0.0255597085 0.0365244258 0.0838837773 0.0107126378 1.8388940000 113616878 95654128 1784455168 -0.0742090195 -0.0747692063 0.2180865407 718 1305031126.0870759487 0.0272268467 0.0365114765 0.0838837773 0.0107075978 1.9368710000 113619148 95654128 1785851904 -0.0748421401 -0.0608897284 0.2148558348 719 1305031126.1194519997 0.0266446006 0.0364977534 0.0838837773 0.0107023968 1.5718280000 113620318 95654128 1787756544 -0.0740582496 -0.0485141873 0.2132423222 720 1305031126.1549999714 0.0226594247 0.0364785335 0.0838837773 0.0107030360 2.1302780000 113622204 95654128 1784954880 -0.0747997239 -0.0317745991 0.2104215324 721 1305031126.1871740818 0.0238757953 0.0364610540 0.0838837773 0.0106988953 1.9493690000 113625018 95654128 1786351616 -0.0743725821 -0.0164307095 0.2072691023 722 1305031126.2194728851 0.0290959720 0.0364508531 0.0838837773 0.0107062366 2.0625430000 113626328 95654128 1788256256 -0.0715654790 -0.0088283196 0.2069962621 723 1305031126.2552359104 0.0272952393 0.0364381897 0.0838837773 0.0107091926 2.6287390000 113628534 95654128 1784573952 -0.0709367394 0.0063302927 0.2038186491 724 1305031126.2871050835 0.0317626670 0.0364317318 0.0838837773 0.0107032206 1.5982460000 113629512 95654128 1785843712 -0.0702877566 0.0183448344 0.2014392912 725 1305031126.3197870255 0.0304018874 0.0364234148 0.0838837773 0.0107005982 1.7141910000 113631942 95654128 1787748352 -0.0703471228 0.0328909308 0.1978068203 726 1305031126.3554151058 0.0330391638 0.0364187533 0.0838837773 0.0106962959 1.7477000000 113634244 95654128 1784954880 -0.0689016953 0.0437603667 0.1968674213 727 1305031126.3874828815 0.0370702147 0.0364196494 0.0838837773 0.0106920095 1.4631380000 113635286 95654128 1786351616 -0.0693798512 0.0538729690 0.1936598569 728 1305031126.4197928905 0.0367199220 0.0364200618 0.0838837773 0.0106913752 1.9708140000 113637664 95654128 1788002304 -0.0706088468 0.0656968281 0.1900337636 729 1305031126.4553799629 0.0376283713 0.0364217193 0.0838837773 0.0106912070 1.6868150000 113639966 95654128 1784954880 -0.0722983107 0.0778453946 0.1875697970 730 1305031126.4903860092 0.0426077358 0.0364301933 0.0838837773 0.0106949524 1.5964400000 113782440 95654128 1786351616 -0.0730884224 0.0863785818 0.1845593750 731 1305031126.5223209858 0.0404696576 0.0364357193 0.0838837773 0.0106961754 1.4000520000 113814486 95654128 1785716736 -0.0746796355 0.1029797047 0.1810774058 732 1305031126.5582089424 0.0437637269 0.0364457302 0.0838837773 0.0106921948 1.8327150000 113817076 95654128 1787113472 -0.0731019527 0.1155166030 0.1797094494 733 1305031126.5901761055 0.0457572676 0.0364584335 0.0838837773 0.0106851214 1.4678410000 113818022 95654128 1784827904 -0.0696222037 0.1223481968 0.1782663912 734 1305031126.6186869144 0.0460130535 0.0364714507 0.0838837773 0.0106782917 1.8811430000 113820304 95654128 1786351616 -0.0694075748 0.1316641122 0.1755701005 735 1305031126.6544740200 0.0504451580 0.0364904626 0.0838837773 0.0106859762 2.0199200000 113822590 95654128 1788010496 -0.0668709800 0.1355545819 0.1764463037 736 1305031126.6900219917 0.0526597463 0.0365124317 0.0838837773 0.0106824351 1.1791680000 113823600 95654128 1784963072 -0.0661315396 0.1416322589 0.1739788651 737 1305031126.7157700062 0.0525998510 0.0365342599 0.0838837773 0.0106775314 1.6605460000 113825662 95654128 1786359808 -0.0650983378 0.1494044960 0.1713066995 738 1305031126.7553739548 0.0558590032 0.0365604452 0.0838837773 0.0106709787 2.0693730000 113827996 95654128 1785597952 -0.0630963445 0.1509210616 0.1708194315 739 1305031126.7875649929 0.0553780682 0.0365859089 0.0838837773 0.0106700979 2.0326770000 113969974 95654128 1786986496 -0.0613281541 0.1600261927 0.1673678458 740 1305031126.8199288845 0.0576622151 0.0366143904 0.0838837773 0.0106644527 1.9212480000 114002184 95654128 1784954880 -0.0579733700 0.1610081047 0.1663299501 741 1305031126.8583779335 0.0574878491 0.0366425597 0.0838837773 0.0106576274 2.0242320000 114003258 95654128 1786351616 -0.0565771088 0.1652587652 0.1632526964 742 1305031126.8881540298 0.0572604872 0.0366703466 0.0838837773 0.0106520834 1.9104910000 114005416 95654128 1788129280 -0.0556447618 0.1694154292 0.1612495631 743 1305031126.9194090366 0.0573658347 0.0366982006 0.0838837773 0.0106455336 0.7981670000 114007590 95654128 1784954880 -0.0548181459 0.1703936756 0.1599529982 744 1305031126.9555010796 0.0563030690 0.0367245512 0.0838837773 0.0106414066 0.8105400000 114008600 95654128 1786351616 -0.0550627448 0.1729433835 0.1580172777 745 1305031126.9873158932 0.0579112768 0.0367529898 0.0838837773 0.0106350657 0.8670110000 114010838 95654128 1788129280 -0.0552743599 0.1708122492 0.1581652015 746 1305031127.0195240974 0.0579625219 0.0367814208 0.0838837773 0.0106300131 0.8251730000 114013136 95654128 1785004032 -0.0535917059 0.1713686138 0.1576672941 747 1305031127.0533180237 0.0567109697 0.0368081002 0.0838837773 0.0106278134 0.8271350000 114014114 95654128 1786351616 -0.0539367609 0.1728889346 0.1565862447 748 1305031127.0886490345 0.0565407313 0.0368344808 0.0838837773 0.0106307141 0.9084400000 114016384 95654128 1788256256 -0.0540770106 0.1696971953 0.1570635140 749 1305031127.1209630966 0.0562090725 0.0368603480 0.0838837773 0.0106311413 0.8434600000 114018558 95654128 1784573952 -0.0560583025 0.1675712615 0.1573939770 750 1305031127.1576919556 0.0561375208 0.0368860509 0.0838837773 0.0106242495 1.0057480000 114019600 95654128 1785843712 -0.0550765619 0.1655351222 0.1582530290 751 1305031127.1875000000 0.0546882451 0.0369097556 0.0838837773 0.0106215689 0.8871440000 114021774 95654128 1787875328 -0.0565777570 0.1652944833 0.1581455320 752 1305031127.2218310833 0.0559680872 0.0369350991 0.0838837773 0.0106191263 1.0224720000 114024984 95654128 1784954880 -0.0558302067 0.1616396904 0.1602389365 753 1305031127.2597610950 0.0556057356 0.0369598941 0.0838837773 0.0106157690 1.0912440000 114026090 95654128 1786224640 -0.0562034808 0.1583791077 0.1623588502 754 1305031127.2870380878 0.0529094338 0.0369810473 0.0838837773 0.0106220903 1.3464490000 114028136 95654128 1788035072 -0.0567919649 0.1593166441 0.1618515998 755 1305031127.3204679489 0.0543340705 0.0370040315 0.0838837773 0.0106203745 1.2443120000 114030358 95654128 1784827904 -0.0573872179 0.1515195370 0.1645479798 756 1305031127.3534069061 0.0561229363 0.0370293210 0.0838837773 0.0106152977 1.0060110000 114031432 95654128 1786224640 -0.0564675480 0.1467663944 0.1678680331 757 1305031127.3837130070 0.0530133434 0.0370504360 0.0838837773 0.0106121721 0.9492970000 114033830 95654128 1788002304 -0.0583931506 0.1470215917 0.1674438864 758 1305031127.4196500778 0.0522080921 0.0370704329 0.0838837773 0.0106057138 0.9603110000 114034884 95654128 1784954880 -0.0591363832 0.1438888311 0.1690606028 759 1305031127.4542460442 0.0540444925 0.0370927966 0.0838837773 0.0106091138 0.8932250000 114037170 95654128 1786351616 -0.0592632331 0.1390924305 0.1724496186 760 1305031127.4872000217 0.0502398685 0.0371100954 0.0838837773 0.0106234759 0.9808660000 114039632 95654128 1785589760 -0.0601865537 0.1421220452 0.1719151139 761 1305031127.5218999386 0.0519188531 0.0371295550 0.0838837773 0.0106229866 1.1057870000 114040578 95654128 1786986496 -0.0595997721 0.1375489086 0.1742358506 762 1305031127.5537250042 0.0530775115 0.0371504841 0.0838837773 0.0106230295 0.9437310000 114042752 95654128 1784954880 -0.0606190227 0.1341814846 0.1768607497 763 1305031127.5866320133 0.0509120338 0.0371685202 0.0838837773 0.0106193778 0.8493500000 114044990 95654128 1786486784 -0.0600741841 0.1348813474 0.1766189486 764 1305031127.6206569672 0.0502652936 0.0371856626 0.0838837773 0.0106126698 0.9825160000 114046108 95654128 1785597952 -0.0598308891 0.1347593069 0.1772775799 765 1305031127.6546559334 0.0535775796 0.0372070899 0.0838837773 0.0106072758 0.8341650000 114048314 95654128 1786994688 -0.0612691417 0.1294595301 0.1803756952 766 1305031127.6871099472 0.0525566675 0.0372271285 0.0838837773 0.0106021945 1.0756430000 114051256 95654128 1784868864 -0.0602911003 0.1292297244 0.1805057377 767 1305031127.7232100964 0.0497633964 0.0372434731 0.0838837773 0.0105966403 1.0456960000 114052266 95654128 1786232832 -0.0604776554 0.1316643953 0.1791293323 768 1305031127.7546939850 0.0525818616 0.0372634449 0.0838837773 0.0105935148 0.8508510000 114054440 95654128 1788010496 -0.0601285994 0.1271476448 0.1815031767 769 1305031127.7876410484 0.0525330827 0.0372833014 0.0838837773 0.0105896481 0.9413600000 114056710 95654128 1784983552 -0.0605455488 0.1255440712 0.1817410290 770 1305031127.8201279640 0.0501831621 0.0373000545 0.0838837773 0.0105843619 0.8125040000 114057764 95654128 1786359808 -0.0612133481 0.1274391413 0.1804386824 771 1305031127.8551321030 0.0512160100 0.0373181037 0.0838837773 0.0105777894 0.8426620000 114060002 95654128 1785597952 -0.0618160777 0.1252358854 0.1812308133 772 1305031127.8871219158 0.0507637933 0.0373355204 0.0838837773 0.0105716673 0.8063580000 114062240 95654128 1786986496 -0.0627786890 0.1240547076 0.1811219454 773 1305031127.9225599766 0.0503751822 0.0373523893 0.0838837773 0.0105664033 0.8822450000 114063250 95654128 1784827904 -0.0637502372 0.1233550459 0.1811282039 774 1305031127.9550879002 0.0494429581 0.0373680102 0.0838837773 0.0105602700 0.8472930000 114065456 95654128 1786224640 -0.0632291064 0.1234341189 0.1813120693 775 1305031127.9870929718 0.0492722988 0.0373833706 0.0838837773 0.0105535508 0.8104270000 114067662 95654128 1788129280 -0.0638629943 0.1229516044 0.1834122390 776 1305031128.0217759609 0.0480035879 0.0373970564 0.0838837773 0.0105505263 1.0853580000 114068812 95654128 1784827904 -0.0624037459 0.1239081174 0.1844193041 777 1305031128.0557179451 0.0503927544 0.0374137819 0.0838837773 0.0105504212 0.8427640000 114071018 95654128 1786241024 -0.0624395460 0.1198052168 0.1884078830 778 1305031128.0872058868 0.0513199233 0.0374316561 0.0838837773 0.0105439110 0.8286250000 114071964 95654128 1788129280 -0.0613633282 0.1181775331 0.1906678379 779 1305031128.1247460842 0.0503150038 0.0374481944 0.0838837773 0.0105389968 0.8818800000 114074266 95654128 1785081856 -0.0612274855 0.1174662560 0.1912207603 780 1305031128.1577820778 0.0508459955 0.0374653711 0.0838837773 0.0105363603 1.0322150000 114077272 95654128 1786351616 -0.0608480833 0.1157499328 0.1930954903 781 1305031128.1872210503 0.0532353297 0.0374855631 0.0838837773 0.0105313858 1.0419110000 114078474 95654128 1788129280 -0.0590864383 0.1128541082 0.1956378669 782 1305031128.2254419327 0.0505516492 0.0375022716 0.0838837773 0.0105300862 0.9489110000 114080900 95654128 1784827904 -0.0585749671 0.1138922796 0.1941045970 783 1305031128.2560069561 0.0496548377 0.0375177922 0.0838837773 0.0105259895 0.7858540000 114083074 95654128 1786224640 -0.0590526275 0.1140748337 0.1941943318 784 1305031128.2912750244 0.0529369190 0.0375374594 0.0838837773 0.0105233529 0.8036680000 114084100 95654128 1788129280 -0.0589094348 0.1097557023 0.1964110434 785 1305031128.3241701126 0.0502551608 0.0375536603 0.0838837773 0.0105198292 0.8649110000 114086306 95654128 1784954880 -0.0592096150 0.1122651398 0.1948343664 786 1305031128.3552060127 0.0503691472 0.0375699650 0.0838837773 0.0105133597 0.8066420000 114088496 95654128 1786351616 -0.0598180294 0.1115782037 0.1949271113 787 1305031128.3913969994 0.0519079976 0.0375881836 0.0838837773 0.0105075999 0.8263050000 114089506 95654128 1785647104 -0.0598353855 0.1092066616 0.1958366632 788 1305031128.4236090183 0.0502864905 0.0376042982 0.0838837773 0.0105016313 0.8463750000 114091852 95654128 1786986496 -0.0615995042 0.1102526709 0.1948651671 789 1305031128.4554989338 0.0500713922 0.0376200993 0.0838837773 0.0104968510 0.9870540000 114094058 95654128 1784827904 -0.0627896041 0.1095140800 0.1945945472 790 1305031128.4895229340 0.0507725142 0.0376367480 0.0838837773 0.0104912538 0.8809220000 114095068 95654128 1786224640 -0.0623072535 0.1083171517 0.1951289326 791 1305031128.5236039162 0.0500662029 0.0376524616 0.0838837773 0.0104847185 0.8276290000 114097274 95654128 1788002304 -0.0624733418 0.1078929305 0.1947717071 792 1305031128.5556390285 0.0506868735 0.0376689191 0.0838837773 0.0104795082 1.0857520000 114099480 95654128 1784954880 -0.0624677204 0.1058364362 0.1949685514 793 1305031128.5914599895 0.0511653870 0.0376859387 0.0838837773 0.0104734972 1.1942830000 114100490 95654128 1786351616 -0.0626523048 0.1043288037 0.1951224208 794 1305031128.6233680248 0.0505321026 0.0377021177 0.0838837773 0.0104679786 0.8467360000 114102852 95654128 1785589760 -0.0640418828 0.1040146276 0.1946277916 795 1305031128.6555540562 0.0499434024 0.0377175155 0.0838837773 0.0104628564 0.8388280000 114103798 95654128 1786986496 -0.0644734651 0.1036207154 0.1938459277 796 1305031128.6904489994 0.0505065285 0.0377335821 0.0838837773 0.0104583551 0.8238660000 114246184 95654128 1784827904 -0.0639060363 0.1030293778 0.1941115707 797 1305031128.7229759693 0.0504233912 0.0377495041 0.0838837773 0.0104532113 0.8295570000 114279430 95654128 1786224640 -0.0617359653 0.1029397771 0.1938336939 798 1305031128.7546460629 0.0494116917 0.0377641184 0.0838837773 0.0104489724 1.0640930000 114280376 95654128 1788002304 -0.0627044365 0.1031441540 0.1928392947 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 05:29:12 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 nan 0.3044690000 95916811 95654128 1760464896 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0026867939 0.0022947229 0.0026867939 0.0026436208 1.3194680000 106429634 95654128 1760956416 0.0016575535 0.0007561003 0.0003873046 3 1311867718.7114279270 0.0044163745 0.0030019401 0.0044163745 0.0041990122 1.0164270000 106432336 95654128 1762451456 0.0025906775 0.0028173430 0.0005634688 4 1311867718.7410299778 0.0025706154 0.0028941089 0.0044163745 0.0045286240 1.0816270000 106433526 95654128 1764102144 0.0009774094 0.0001838615 0.0018734166 5 1311867718.7767970562 0.0031892096 0.0029531291 0.0044163745 0.0042504909 1.3457040000 106436416 95654128 1765830656 0.0002441892 -0.0017546193 0.0015314815 6 1311867718.8094089031 0.0027338408 0.0029165810 0.0044163745 0.0042080653 1.1320700000 106439258 95654128 1767481344 -0.0016219129 0.0015554618 0.0005409652 7 1311867718.8408079147 0.0027530068 0.0028932133 0.0044163745 0.0041515397 1.2368850000 106440268 95654128 1769271296 -0.0022536186 0.0010913771 0.0007893369 8 1311867718.8767778873 0.0040942580 0.0030433439 0.0044163745 0.0041670726 2.3250770000 106442518 95654128 1770844160 -0.0034179022 0.0005883931 0.0002951959 9 1311867718.9088680744 0.0045646275 0.0032123754 0.0045646275 0.0041030337 1.6331940000 106445952 95654128 1772494848 -0.0021985408 0.0019503941 0.0002366860 10 1311867718.9438331127 0.0034829513 0.0032394330 0.0045646275 0.0038786842 2.5144870000 106448254 95654128 1774272512 -0.0019875937 0.0015060037 0.0016517583 11 1311867718.9784109592 0.0023394877 0.0031576198 0.0045646275 0.0037588817 1.6151290000 106450504 95654128 1775898624 -0.0030355861 0.0004447111 0.0031644357 12 1311867719.0091300011 0.0023727007 0.0030922098 0.0045646275 0.0035936292 1.8697220000 106452626 95654128 1777696768 -0.0023580894 0.0005006964 0.0033318484 13 1311867719.0441620350 0.0018744332 0.0029985347 0.0045646275 0.0036922378 1.4907430000 106453732 95654128 1779302400 -0.0026633660 0.0019998667 0.0041592447 14 1311867719.0776190758 0.0017444891 0.0029089600 0.0045646275 0.0037687605 1.1157340000 106455950 95654128 1780969472 -0.0023907081 -0.0002662609 0.0050225500 15 1311867719.1086950302 0.0025201046 0.0028830363 0.0045646275 0.0036337027 1.3794410000 106628084 95654128 1782730752 -0.0010924207 0.0007869975 0.0048755486 16 1311867719.1437010765 0.0025536250 0.0028624481 0.0045646275 0.0035385721 1.4550950000 106629042 95654128 1784356864 -0.0011782170 0.0002464216 0.0059262896 17 1311867719.1810290813 0.0030687256 0.0028745821 0.0045646275 0.0035504863 1.1450360000 106633852 95654128 1783250944 -0.0014794022 -0.0009155595 0.0062229871 18 1311867719.2127099037 0.0073509561 0.0031232695 0.0073509561 0.0036262904 1.2536530000 106638662 95654128 1782222848 0.0026661083 -0.0021121984 0.0070753824 19 1311867719.2412090302 0.0070378804 0.0033293017 0.0073509561 0.0036797405 1.0797770000 106639524 95654128 1783848960 0.0024061438 -0.0005767823 0.0075707557 20 1311867719.2779469490 0.0044439523 0.0033850342 0.0073509561 0.0039186489 0.9545670000 106641858 95654128 1785647104 -0.0012319016 -0.0013397937 0.0079351524 21 1311867719.3104898930 0.0042740991 0.0034273707 0.0073509561 0.0038332633 0.9803850000 106644076 95654128 1784520704 -0.0015691222 -0.0007102255 0.0074956841 22 1311867719.3413150311 0.0064362655 0.0035641386 0.0073509561 0.0039059504 1.0957890000 106644986 95654128 1783468032 0.0001823943 -0.0011442683 0.0084011527 23 1311867719.3772718906 0.0063249106 0.0036841722 0.0073509561 0.0038765446 1.1779470000 106647204 95654128 1785102336 -0.0010784838 -0.0030111857 0.0085692778 24 1311867719.4105761051 0.0058173607 0.0037730550 0.0073509561 0.0037919310 1.3993380000 106649422 95654128 1784098816 -0.0020427653 -0.0032864467 0.0080959741 25 1311867719.4427709579 0.0090287225 0.0039832817 0.0090287225 0.0038128468 1.4402700000 106650380 95654128 1782968320 -0.0008185323 -0.0066617532 0.0100777820 26 1311867719.4787840843 0.0096394327 0.0042008260 0.0096394327 0.0037841303 1.2588200000 106652598 95654128 1784594432 -0.0006908162 -0.0074811187 0.0106571205 27 1311867719.5104370117 0.0079275807 0.0043388539 0.0096394327 0.0037879428 1.3561450000 106825456 95654128 1783619584 -0.0015678462 -0.0060447566 0.0097304117 28 1311867719.5449650288 0.0081131607 0.0044736506 0.0096394327 0.0038259490 1.4603940000 106826414 95654128 1782345728 -0.0022895823 -0.0064282897 0.0094380816 29 1311867719.5771939754 0.0082800090 0.0046049044 0.0096394327 0.0037689148 1.2268620000 106828632 95654128 1783951360 -0.0029803843 -0.0071673873 0.0108423270 30 1311867719.6112511158 0.0086817909 0.0047408006 0.0096394327 0.0037765677 1.0792860000 106830834 95654128 1785602048 -0.0017432953 -0.0051972545 0.0110161155 31 1311867719.6421909332 0.0113912709 0.0049553319 0.0113912709 0.0037334228 0.9993910000 106831728 95654128 1784496128 0.0008770117 -0.0045080511 0.0117191095 32 1311867719.6770479679 0.0118389977 0.0051704464 0.0118389977 0.0037128201 1.0136410000 106833978 95654128 1783341056 0.0005926893 -0.0046878206 0.0129476907 33 1311867719.7107939720 0.0108860135 0.0053436454 0.0118389977 0.0036737461 1.0338150000 106841284 95654128 1784967168 -0.0004303179 -0.0026053283 0.0127700316 34 1311867719.7442650795 0.0132011827 0.0055747495 0.0132011827 0.0036826552 1.5487650000 107017162 95654128 1784090624 0.0013511825 -0.0026498146 0.0130845141 35 1311867719.7861878872 0.0140209040 0.0058160682 0.0140209040 0.0036473454 1.2151600000 107019540 95654128 1783107584 0.0012874287 -0.0030531974 0.0141488397 36 1311867719.8099169731 0.0132163754 0.0060216323 0.0140209040 0.0036126152 1.6397980000 107021566 95654128 1784586240 -0.0001239171 -0.0029336289 0.0149572901 37 1311867719.8454990387 0.0128685236 0.0062066834 0.0140209040 0.0035880596 1.2898050000 107022556 95654128 1783484416 -0.0011777122 -0.0035720221 0.0162087064 38 1311867719.8771090508 0.0111450907 0.0063366415 0.0140209040 0.0035787682 1.3943510000 107024742 95654128 1782325248 -0.0028309920 -0.0037578281 0.0153345112 39 1311867719.9114089012 0.0106129637 0.0064462907 0.0140209040 0.0035851201 1.0525300000 107026992 95654128 1784098816 -0.0039027662 -0.0027300129 0.0160962529 40 1311867719.9461970329 0.0108844219 0.0065572440 0.0140209040 0.0035434789 1.3589970000 107027934 95654128 1785729024 -0.0040022959 -0.0034361016 0.0165831242 41 1311867719.9807810783 0.0120053701 0.0066901252 0.0140209040 0.0035229540 1.1967320000 107030152 95654128 1784754176 -0.0039104642 -0.0051147118 0.0172275677 42 1311867720.0117020607 0.0123502240 0.0068248894 0.0140209040 0.0035153063 1.1358340000 107032338 95654128 1783595008 -0.0040004505 -0.0053823055 0.0174887218 43 1311867720.0452380180 0.0129219526 0.0069666816 0.0140209040 0.0034791786 1.5761440000 107204560 95654128 1785221120 -0.0039156717 -0.0052425656 0.0187612418 44 1311867720.0772819519 0.0151030039 0.0071515980 0.0151030039 0.0034614829 2.2666650000 107206778 95654128 1784348672 -0.0028422927 -0.0071400120 0.0201936793 45 1311867720.1172130108 0.0168695338 0.0073675521 0.0168695338 0.0034331651 1.3206850000 107209092 95654128 1783341056 -0.0014143672 -0.0078085088 0.0208472311 46 1311867720.1451559067 0.0178487059 0.0075954033 0.0178487059 0.0034067308 1.2260240000 107209922 95654128 1784975360 -0.0004991478 -0.0079063382 0.0210421272 47 1311867720.1781630516 0.0186892655 0.0078314429 0.0186892655 0.0033766978 1.4889960000 107212108 95654128 1783988224 0.0006044048 -0.0073084533 0.0214251839 48 1311867720.2094950676 0.0172333345 0.0080273157 0.0186892655 0.0034188903 0.9643140000 107214278 95654128 1783095296 -0.0008498043 -0.0072882571 0.0206351019 49 1311867720.2421469688 0.0166362710 0.0082030086 0.0186892655 0.0033852361 1.0149750000 107215236 95654128 1784721408 -0.0009285847 -0.0054874686 0.0207650699 50 1311867720.2770779133 0.0175842326 0.0083906331 0.0186892655 0.0033732594 1.3507360000 107217454 95654128 1783730176 -0.0002256753 -0.0051576025 0.0217493288 51 1311867720.3094570637 0.0169622991 0.0085587050 0.0186892655 0.0033416345 1.2762620000 107219640 95654128 1782587392 -0.0005628191 -0.0039513437 0.0216742437 52 1311867720.3430728912 0.0185018536 0.0087499194 0.0186892655 0.0033344521 1.0515210000 107390710 95654128 1784221696 0.0002513241 -0.0048716748 0.0226219762 53 1311867720.3779859543 0.0176506303 0.0089178573 0.0186892655 0.0033039853 1.0205640000 107392896 95654128 1783463936 -0.0020126910 -0.0072552674 0.0236943699 54 1311867720.4096798897 0.0158336181 0.0090459270 0.0186892655 0.0033763125 0.9750660000 107395082 95654128 1782325248 -0.0036637634 -0.0050525926 0.0231091194 55 1311867720.4461109638 0.0154442322 0.0091622598 0.0186892655 0.0033504113 0.8995190000 107396104 95654128 1783951360 -0.0039945040 -0.0040423814 0.0235865843 56 1311867720.4799289703 0.0157970544 0.0092807383 0.0186892655 0.0033643617 0.9746930000 107398322 95654128 1785618432 -0.0049072402 -0.0060863467 0.0246176403 57 1311867720.5104389191 0.0140389428 0.0093642155 0.0186892655 0.0034866180 0.9599240000 107400444 95654128 1784365056 -0.0060537523 -0.0050524110 0.0229631308 58 1311867720.5467319489 0.0130168777 0.0094271925 0.0186892655 0.0035078051 1.0714070000 107401466 95654128 1783984128 -0.0078894580 -0.0047405832 0.0217906293 59 1311867720.5793280602 0.0127825448 0.0094840628 0.0186892655 0.0035921465 1.1598260000 107403652 95654128 1785761792 -0.0092948005 -0.0070593716 0.0227423720 60 1311867720.6121249199 0.0125289401 0.0095348108 0.0186892655 0.0035947019 1.1009230000 107405838 95654128 1784893440 -0.0098990286 -0.0066178837 0.0222088844 61 1311867720.6463210583 0.0120612634 0.0095762281 0.0186892655 0.0035735745 1.0388990000 107406828 95654128 1784475648 -0.0107465703 -0.0061997776 0.0207577627 62 1311867720.6798269749 0.0125320489 0.0096239026 0.0186892655 0.0035587229 0.9377080000 107408966 95654128 1783734272 -0.0117701143 -0.0078508109 0.0215242077 63 1311867720.7102439404 0.0137792490 0.0096898605 0.0186892655 0.0035438624 1.0756320000 107581240 95654128 1783459840 -0.0124167250 -0.0100678820 0.0222235750 64 1311867720.7451629639 0.0131775979 0.0097443564 0.0186892655 0.0035236818 1.0154630000 107582198 95654128 1785384960 -0.0125533994 -0.0084021818 0.0203772187 65 1311867720.7790179253 0.0151415914 0.0098273908 0.0186892655 0.0035011495 1.1983870000 107594688 95654128 1784475648 -0.0101235081 -0.0064773606 0.0220056251 66 1311867720.8115909100 0.0149776414 0.0099054249 0.0186892655 0.0034773616 1.9131320000 107607370 95654128 1784094720 -0.0108294226 -0.0056519294 0.0235108696 67 1311867720.8467299938 0.0143667646 0.0099720120 0.0186892655 0.0034795197 1.0490980000 107608360 95654128 1785745408 -0.0116678365 -0.0044655725 0.0238703676 68 1311867720.8813319206 0.0153636839 0.0100513013 0.0186892655 0.0034790009 1.0387230000 107610578 95654128 1784983552 -0.0109837120 -0.0038010105 0.0247210655 69 1311867720.9149661064 0.0156346317 0.0101322191 0.0186892655 0.0034673298 1.0122110000 107612764 95654128 1784606720 -0.0111569557 -0.0032743465 0.0252200980 70 1311867720.9500010014 0.0163299404 0.0102207580 0.0186892655 0.0034506941 1.2270750000 107613722 95654128 1783459840 -0.0110552525 -0.0048190402 0.0250407513 71 1311867720.9797990322 0.0163018778 0.0103064076 0.0186892655 0.0034318441 1.3332160000 107615828 95654128 1783205888 -0.0114123905 -0.0049365782 0.0252374634 72 1311867721.0093889236 0.0156994686 0.0103813112 0.0186892655 0.0034107604 1.0597550000 107787986 95654128 1784856576 -0.0123166814 -0.0051258681 0.0252689086 73 1311867721.0478379726 0.0170324519 0.0104724227 0.0186892655 0.0033976883 1.0896700000 107789040 95654128 1784098816 -0.0113272332 -0.0056866049 0.0250176582 74 1311867721.0794439316 0.0157377478 0.0105435758 0.0186892655 0.0033775798 1.1527260000 107791194 95654128 1783463936 -0.0129578887 -0.0057891118 0.0247508548 75 1311867721.1103579998 0.0166487116 0.0106249776 0.0186892655 0.0033663414 0.9818830000 107793364 95654128 1785241600 -0.0125778746 -0.0060551944 0.0253591929 76 1311867721.1467890739 0.0172609817 0.0107122934 0.0186892655 0.0034061145 1.0561190000 107794354 95654128 1784123392 -0.0122781573 -0.0058161346 0.0244205613 77 1311867721.1774179935 0.0172547139 0.0107972599 0.0186892655 0.0034342644 0.9515520000 107796540 95654128 1783738368 -0.0123350453 -0.0065268520 0.0237335023 78 1311867721.2112360001 0.0158001631 0.0108613997 0.0186892655 0.0034274118 0.8384160000 107798726 95654128 1785495552 -0.0135893598 -0.0049615093 0.0235195663 79 1311867721.2469010353 0.0160085186 0.0109265531 0.0186892655 0.0034242454 1.0406930000 107799700 95654128 1784369152 -0.0142119955 -0.0057782414 0.0243624169 80 1311867721.2800450325 0.0147097195 0.0109738427 0.0186892655 0.0034401777 0.9345890000 107801886 95654128 1783988224 -0.0153061282 -0.0043307575 0.0235034004 81 1311867721.3099579811 0.0157909766 0.0110333135 0.0186892655 0.0034522929 0.8763670000 107804040 95654128 1785765888 -0.0152249979 -0.0059130737 0.0240329690 82 1311867721.3483059406 0.0141194575 0.0110709494 0.0186892655 0.0034621516 0.8252880000 107976694 95654128 1784860672 -0.0165398214 -0.0046584010 0.0222986843 83 1311867721.3790040016 0.0127378153 0.0110910321 0.0186892655 0.0034484024 0.8741960000 107978784 95654128 1784381440 -0.0188459344 -0.0049664043 0.0223055147 84 1311867721.4092550278 0.0133914873 0.0111184185 0.0186892655 0.0034413901 0.8738150000 107980938 95654128 1786011648 -0.0183700472 -0.0045880009 0.0220565815 85 1311867721.4478130341 0.0139813004 0.0111520994 0.0186892655 0.0034235953 0.8613320000 107982024 95654128 1784598528 -0.0186011661 -0.0051092319 0.0219708066 86 1311867721.4768960476 0.0150675634 0.0111976281 0.0186892655 0.0034081436 0.8711950000 107984146 95654128 1784127488 -0.0176651012 -0.0048307772 0.0219158325 87 1311867721.5093359947 0.0157048423 0.0112494352 0.0186892655 0.0033910010 0.7594570000 107986300 95654128 1785888768 -0.0176956169 -0.0047773956 0.0232007224 88 1311867721.5451331139 0.0146802841 0.0112884221 0.0186892655 0.0033716622 0.7205700000 107987242 95654128 1784598528 -0.0193643346 -0.0051610442 0.0222624838 89 1311867721.5769670010 0.0132305892 0.0113102442 0.0186892655 0.0033619270 0.8568320000 108159940 95654128 1783984128 -0.0201985203 -0.0031992695 0.0219237655 90 1311867721.6129651070 0.0132819163 0.0113321516 0.0186892655 0.0033580790 0.7859900000 108162158 95654128 1785720832 -0.0213073064 -0.0038509180 0.0225113295 91 1311867721.6496050358 0.0136017697 0.0113570925 0.0186892655 0.0033579440 1.0586270000 108163180 95654128 1784614912 -0.0215736572 -0.0048826686 0.0209955089 92 1311867721.6800351143 0.0138126761 0.0113837836 0.0186892655 0.0033514962 1.2536740000 108165334 95654128 1783840768 -0.0210155938 -0.0042758812 0.0189512670 93 1311867721.7162289619 0.0145348795 0.0114176664 0.0186892655 0.0033609285 1.0716320000 108167616 95654128 1785487360 -0.0215769727 -0.0054592821 0.0208426490 94 1311867721.7467949390 0.0149706537 0.0114554641 0.0186892655 0.0034009407 1.0236840000 108168510 95654128 1784238080 -0.0214886367 -0.0053804712 0.0203741863 95 1311867721.7787001133 0.0116380472 0.0114573860 0.0186892655 0.0033920086 0.8531100000 108170696 95654128 1783328768 -0.0234614313 -0.0020828575 0.0192146879 96 1311867721.8154830933 0.0141554773 0.0114854912 0.0186892655 0.0033917915 0.9813030000 108172946 95654128 1784999936 -0.0214048065 -0.0024422328 0.0200255159 97 1311867721.8485159874 0.0160972252 0.0115330348 0.0186892655 0.0033904022 1.5620240000 108173904 95654128 1783713792 -0.0213616826 -0.0052694641 0.0196735263 98 1311867721.8778810501 0.0145663591 0.0115639871 0.0186892655 0.0033820027 0.9806170000 108176058 95654128 1782841344 -0.0222046450 -0.0034007868 0.0189833492 99 1311867721.9146931171 0.0133083127 0.0115816065 0.0186892655 0.0033712615 0.9985770000 108178180 95654128 1784598528 -0.0232875943 -0.0023075999 0.0185379833 100 1311867721.9467151165 0.0152536817 0.0116183273 0.0186892655 0.0033694641 0.8184000000 108179090 95654128 1783586816 -0.0229648426 -0.0047559123 0.0182068385 101 1311867721.9773728848 0.0136804851 0.0116387447 0.0186892655 0.0033901790 0.9099650000 108181276 95654128 1782587392 -0.0232062768 -0.0024538569 0.0174118187 102 1311867722.0166850090 0.0145083154 0.0116668777 0.0186892655 0.0034139475 0.8002690000 108183494 95654128 1784217600 -0.0227965079 -0.0018407747 0.0191338230 103 1311867722.0475180149 0.0140869068 0.0116903732 0.0186892655 0.0034384198 0.9159000000 108184324 95654128 1785868288 -0.0234910734 -0.0023301474 0.0186616164 104 1311867722.0800709724 0.0160625651 0.0117324135 0.0186892655 0.0034702702 0.7223790000 108186542 95654128 1784745984 -0.0218374226 -0.0032188047 0.0182985645 105 1311867722.1161251068 0.0161472652 0.0117744597 0.0186892655 0.0034759964 0.7559580000 108188792 95654128 1783857152 -0.0232385565 -0.0049159690 0.0176869407 106 1311867722.1479530334 0.0152076930 0.0118068487 0.0186892655 0.0034722493 0.6923550000 108359890 95654128 1785466880 -0.0231121629 -0.0029205175 0.0161040090 107 1311867722.1798410416 0.0153744230 0.0118401905 0.0186892655 0.0034595642 0.6969770000 108362076 95654128 1784619008 -0.0233642552 -0.0023600613 0.0175759718 108 1311867722.2146399021 0.0165121779 0.0118834496 0.0186892655 0.0034729339 0.8349520000 108364326 95654128 1783586816 -0.0242089853 -0.0055436082 0.0172325298 109 1311867722.2469589710 0.0163935721 0.0119248269 0.0186892655 0.0034583483 0.7217740000 108365252 95654128 1785229312 -0.0236812606 -0.0045895353 0.0168741029 110 1311867722.2780389786 0.0154731451 0.0119570843 0.0186892655 0.0034477973 0.8732610000 108367438 95654128 1784238080 -0.0236757733 -0.0028571116 0.0159218535 111 1311867722.3154170513 0.0142008234 0.0119772982 0.0186892655 0.0034362843 0.7375990000 108369688 95654128 1783095296 -0.0252592154 -0.0022886833 0.0169808250 112 1311867722.3488469124 0.0145260189 0.0120000546 0.0186892655 0.0034222323 0.9917570000 108370614 95654128 1784832000 -0.0251153391 -0.0023823956 0.0169989783 113 1311867722.3777940273 0.0131660448 0.0120103731 0.0186892655 0.0034090468 0.9211960000 108372752 95654128 1783713792 -0.0265893731 -0.0021274774 0.0165424999 114 1311867722.4150679111 0.0143887894 0.0120312364 0.0186892655 0.0034048251 0.7953770000 108374906 95654128 1782579200 -0.0272623356 -0.0044899574 0.0167613886 115 1311867722.4467909336 0.0144153154 0.0120519676 0.0186892655 0.0034388000 0.6812850000 108375832 95654128 1784205312 -0.0281529203 -0.0051154899 0.0166184362 116 1311867722.4777851105 0.0129955476 0.0120601019 0.0186892655 0.0035086722 1.0004720000 108377986 95654128 1785982976 -0.0279707182 -0.0030761668 0.0151546281 117 1311867722.5147399902 0.0136676431 0.0120738415 0.0186892655 0.0034954837 1.7082870000 108380204 95654128 1784860672 -0.0268685650 -0.0020046858 0.0169656686 118 1311867722.5469911098 0.0133875553 0.0120849747 0.0186892655 0.0034822748 0.9277370000 108551306 95654128 1783848960 -0.0271997619 -0.0015226214 0.0175149255 119 1311867722.5802359581 0.0133080138 0.0120952524 0.0186892655 0.0034762350 0.8159270000 108553492 95654128 1785729024 -0.0283221863 -0.0027382434 0.0178613923 120 1311867722.6146309376 0.0151036028 0.0121203219 0.0186892655 0.0034640030 0.9627940000 108555710 95654128 1784610816 -0.0276312176 -0.0045997351 0.0183216520 121 1311867722.6560258865 0.0143142790 0.0121384538 0.0186892655 0.0034546873 0.8110930000 108556796 95654128 1783595008 -0.0278325099 -0.0040906910 0.0171671622 122 1311867722.6778230667 0.0144910738 0.0121577376 0.0186892655 0.0034487078 0.7805310000 108558854 95654128 1785221120 -0.0277926698 -0.0045226458 0.0164609794 123 1311867722.7252709866 0.0146991974 0.0121783999 0.0186892655 0.0035247877 0.8175460000 108561264 95654128 1784238080 -0.0282727089 -0.0047648419 0.0178613141 124 1311867722.7449109554 0.0137990955 0.0121914700 0.0186892655 0.0035459312 0.6718830000 108561982 95654128 1783087104 -0.0290483460 -0.0047730762 0.0166605487 125 1311867722.7770080566 0.0134299016 0.0122013774 0.0186892655 0.0035785334 0.7169530000 108564200 95654128 1784737792 -0.0279795658 -0.0027535851 0.0147276018 126 1311867722.8162860870 0.0131164771 0.0122086401 0.0186892655 0.0035697266 0.7174000000 108566450 95654128 1783209984 -0.0289415866 -0.0030712718 0.0145179592 127 1311867722.8466939926 0.0152303381 0.0122324330 0.0186892655 0.0035781237 0.6937410000 108567344 95654128 1782063104 -0.0297380872 -0.0063113612 0.0174689665 128 1311867722.8819770813 0.0154386749 0.0122574818 0.0186892655 0.0035687465 0.8389810000 108569594 95654128 1783705600 -0.0292164795 -0.0059247324 0.0164924897 129 1311867722.9150629044 0.0156846810 0.0122840492 0.0186892655 0.0035655748 0.7203820000 108592164 95654128 1785466880 -0.0287245736 -0.0045185750 0.0166592821 130 1311867722.9485991001 0.0160585102 0.0123130835 0.0186892655 0.0035708765 0.7168890000 108614146 95654128 1784487936 -0.0293272547 -0.0054923813 0.0179776121 131 1311867722.9821140766 0.0146684786 0.0123310637 0.0186892655 0.0035613073 0.7137870000 108616332 95654128 1783459840 -0.0300258920 -0.0038194379 0.0170220174 132 1311867723.0147259235 0.0140221445 0.0123438749 0.0186892655 0.0035508096 0.7274610000 108788614 95654128 1785085952 -0.0300706867 -0.0020206925 0.0169037841 133 1311867723.0460629463 0.0148761207 0.0123629143 0.0186892655 0.0035473524 0.8442030000 108789508 95654128 1784229888 -0.0314407274 -0.0042669605 0.0189089291 134 1311867723.0845439434 0.0149375452 0.0123821280 0.0186892655 0.0035359328 0.8810770000 108791790 95654128 1783078912 -0.0311507173 -0.0036646451 0.0184016619 135 1311867723.1140980721 0.0148538267 0.0124004369 0.0186892655 0.0035275196 0.8097270000 108793944 95654128 1784832000 -0.0322526284 -0.0046102917 0.0173310302 136 1311867723.1505160332 0.0141465180 0.0124132757 0.0186892655 0.0035166126 0.7014100000 108794934 95654128 1783713792 -0.0333614461 -0.0041180048 0.0179857500 137 1311867723.1811029911 0.0131303994 0.0124185102 0.0186892655 0.0035045901 0.6973630000 108797088 95654128 1782697984 -0.0350180604 -0.0041542314 0.0176146291 138 1311867723.2201359272 0.0140044373 0.0124300024 0.0186892655 0.0034950718 0.6542500000 108799370 95654128 1784324096 -0.0357621573 -0.0059562512 0.0175229348 139 1311867723.2486810684 0.0130125489 0.0124341934 0.0186892655 0.0034847968 0.6980340000 108800232 95654128 1785974784 -0.0364992432 -0.0052043665 0.0167494472 140 1311867723.2846419811 0.0129448250 0.0124378408 0.0186892655 0.0034805593 0.7392730000 108802482 95654128 1784967168 -0.0408612527 -0.0082640620 0.0146202259 141 1311867723.3132460117 0.0123943603 0.0124375324 0.0186892655 0.0034724620 0.9550370000 108804620 95654128 1783840768 -0.0400766581 -0.0072405804 0.0138100507 142 1311867723.3499810696 0.0120699899 0.0124349441 0.0186892655 0.0034679562 0.7361320000 108805642 95654128 1785339904 -0.0404012091 -0.0064759324 0.0125288377 143 1311867723.3822429180 0.0113840522 0.0124275952 0.0186892655 0.0034603481 0.7211210000 108807860 95654128 1784356864 -0.0411389731 -0.0062681655 0.0134125939 144 1311867723.4193739891 0.0123202652 0.0124268498 0.0186892655 0.0034812774 0.7756290000 108810110 95654128 1783205888 -0.0410585999 -0.0074058003 0.0131493574 145 1311867723.4455900192 0.0121632293 0.0124250317 0.0186892655 0.0034714083 0.7531640000 108981060 95654128 1784832000 -0.0444833376 -0.0073314179 0.0099818977 146 1311867723.4825348854 0.0116276722 0.0124195704 0.0186892655 0.0034792280 0.6770490000 108983342 95654128 1783951360 -0.0456510484 -0.0060785934 0.0091367522 147 1311867723.5147960186 0.0108608510 0.0124089668 0.0186892655 0.0034735039 0.7322030000 108985496 95654128 1782951936 -0.0464991182 -0.0053397845 0.0096154073 148 1311867723.5451340675 0.0098848082 0.0123919117 0.0186892655 0.0034627665 0.7183590000 108986422 95654128 1784578048 -0.0460389592 -0.0039840778 0.0103837447 149 1311867723.5809938908 0.0101828752 0.0123770860 0.0186892655 0.0034531693 0.7000990000 108988672 95654128 1783472128 -0.0459893309 -0.0046600709 0.0116394293 150 1311867723.6132669449 0.0107961465 0.0123665464 0.0186892655 0.0034471572 0.7750770000 108990890 95654128 1782444032 -0.0464479364 -0.0052834717 0.0117614251 151 1311867723.6453940868 0.0114127593 0.0123602299 0.0186892655 0.0034365414 0.8962530000 108991784 95654128 1784070144 -0.0471191928 -0.0058143381 0.0112754861 152 1311867723.6809489727 0.0117290858 0.0123560776 0.0186892655 0.0034272777 1.0312950000 108994034 95654128 1785720832 -0.0473686755 -0.0062711067 0.0114630917 153 1311867723.7130429745 0.0109030437 0.0123465807 0.0186892655 0.0034223502 0.8400080000 108996220 95654128 1784745984 -0.0485065207 -0.0051635765 0.0106620481 154 1311867723.7471990585 0.0097313663 0.0123295988 0.0186892655 0.0034186742 0.7191420000 108997178 95654128 1783586816 -0.0480402708 -0.0039941226 0.0115240710 155 1311867723.7809250355 0.0108556701 0.0123200896 0.0186892655 0.0034093615 0.7553260000 108999396 95654128 1785212928 -0.0497083664 -0.0054712929 0.0109770885 156 1311867723.8157649040 0.0103628784 0.0123075433 0.0186892655 0.0034080714 0.7159050000 109001614 95654128 1784229888 -0.0509206988 -0.0049793795 0.0104890866 157 1311867723.8468959332 0.0093414262 0.0122886509 0.0186892655 0.0034003999 0.7397960000 109002540 95654128 1783205888 -0.0510896258 -0.0039834455 0.0106416699 158 1311867723.8826351166 0.0113802357 0.0122829014 0.0186892655 0.0033997026 0.6961250000 109004758 95654128 1784840192 -0.0518541038 -0.0067836763 0.0113679562 159 1311867723.9172909260 0.0110531701 0.0122751672 0.0186892655 0.0033956095 0.6570160000 109176720 95654128 1783721984 -0.0517818630 -0.0057581579 0.0098897517 160 1311867723.9490020275 0.0095669609 0.0122582410 0.0186892655 0.0033888508 0.7960930000 109177614 95654128 1782853632 -0.0528435111 -0.0022637793 0.0079279533 161 1311867723.9839010239 0.0091977967 0.0122392320 0.0186892655 0.0033820486 0.7341710000 109179864 95654128 1784332288 -0.0533307195 -0.0038952525 0.0104388986 162 1311867724.0132899284 0.0079329005 0.0122126497 0.0186892655 0.0033736984 0.8974840000 109181986 95654128 1786109952 -0.0525073297 -0.0019635605 0.0098947147 163 1311867724.0475380421 0.0086978972 0.0121910868 0.0186892655 0.0033662656 1.0146420000 109182992 95654128 1784360960 -0.0531442538 -0.0026327344 0.0097543607 164 1311867724.0824530125 0.0095034400 0.0121746987 0.0186892655 0.0033679205 1.0120730000 109185210 95654128 1783988224 -0.0525005534 -0.0041001653 0.0106748147 165 1311867724.1132431030 0.0100131985 0.0121615987 0.0186892655 0.0033605686 0.8341830000 109187396 95654128 1785466880 -0.0528532229 -0.0040397989 0.0094236489 166 1311867724.1547191143 0.0091059878 0.0121431914 0.0186892655 0.0033671452 1.0635040000 109188482 95654128 1784360960 -0.0536332056 -0.0028214240 0.0093424469 167 1311867724.1810541153 0.0104496228 0.0121330503 0.0186892655 0.0033682061 1.0749370000 109190572 95654128 1783205888 -0.0535197929 -0.0048006079 0.0102799106 168 1311867724.2139430046 0.0096772378 0.0121184323 0.0186892655 0.0033635718 0.9119910000 109192790 95654128 1784832000 -0.0543726198 -0.0035966188 0.0095980000 169 1311867724.2507870197 0.0094251856 0.0121024960 0.0186892655 0.0033614534 1.0216770000 109193780 95654128 1783824384 -0.0551247299 -0.0025059280 0.0090102796 170 1311867724.2855930328 0.0089097405 0.0120837151 0.0186892655 0.0033562944 0.6932760000 109365574 95654128 1782718464 -0.0561794862 -0.0027180421 0.0104002133 171 1311867724.3144888878 0.0097430097 0.0120700267 0.0186892655 0.0033468847 0.7965650000 109367696 95654128 1784451072 -0.0564672053 -0.0036003501 0.0100703659 172 1311867724.3517999649 0.0098881219 0.0120573412 0.0186892655 0.0033383242 0.7166500000 109368750 95654128 1783328768 -0.0562844872 -0.0027967300 0.0083922902 173 1311867724.3888330460 0.0096947970 0.0120436849 0.0186892655 0.0033368258 0.7362860000 109370968 95654128 1782190080 -0.0553764477 -0.0029884973 0.0088201771 174 1311867724.4160330296 0.0107900370 0.0120364800 0.0186892655 0.0033384275 0.7355150000 109373090 95654128 1783816192 -0.0539310500 -0.0054834234 0.0112347268 175 1311867724.4509639740 0.0109732021 0.0120304042 0.0186892655 0.0033289496 0.6606290000 109374048 95654128 1785614336 -0.0543378443 -0.0059071165 0.0101209097 176 1311867724.4830689430 0.0111321351 0.0120253004 0.0186892655 0.0033196263 0.6579980000 109376234 95654128 1784467456 -0.0544784702 -0.0063554025 0.0098714931 177 1311867724.5208630562 0.0106136203 0.0120173248 0.0186892655 0.0033126195 0.6746050000 109378452 95654128 1783459840 -0.0547838025 -0.0059043732 0.0089373831 178 1311867724.5523910522 0.0091525987 0.0120012308 0.0186892655 0.0033061951 0.6568340000 109379410 95654128 1785106432 -0.0539141186 -0.0053099860 0.0127546247 179 1311867724.5861799717 0.0113917114 0.0119978257 0.0186892655 0.0033384409 0.6780730000 109381596 95654128 1783951360 -0.0537664257 -0.0079975277 0.0115992287 180 1311867724.6193559170 0.0099913171 0.0119866784 0.0186892655 0.0033622551 0.8555680000 109383782 95654128 1782951936 -0.0538276806 -0.0061860094 0.0097941458 181 1311867724.6529819965 0.0103903413 0.0119778588 0.0186892655 0.0033535520 0.8562120000 109384772 95654128 1784598528 -0.0536321998 -0.0059543112 0.0084816441 182 1311867724.6818330288 0.0130517185 0.0119837592 0.0186892655 0.0033523749 0.8359040000 109386894 95654128 1783455744 -0.0545311160 -0.0098553970 0.0107330941 183 1311867724.7153129578 0.0105847586 0.0119761144 0.0186892655 0.0033611361 0.8371820000 109389112 95654128 1782444032 -0.0561792366 -0.0068339650 0.0081099542 184 1311867724.7518899441 0.0100201461 0.0119654841 0.0186892655 0.0033568276 0.7888050000 109390102 95654128 1784070144 -0.0560122207 -0.0051135290 0.0073189633 185 1311867724.7853860855 0.0113898488 0.0119623726 0.0186892655 0.0033560723 0.8196270000 109392320 95654128 1785720832 -0.0563691035 -0.0071807043 0.0088163279 186 1311867724.8179960251 0.0119648809 0.0119623860 0.0186892655 0.0033548838 0.6634650000 109394506 95654128 1784745984 -0.0566385835 -0.0080640139 0.0094152354 187 1311867724.8547580242 0.0109693259 0.0119570756 0.0186892655 0.0033741792 0.8141920000 109395464 95654128 1783586816 -0.0569187254 -0.0063402290 0.0081213228 188 1311867724.8830249310 0.0114241634 0.0119542409 0.0186892655 0.0033678688 1.1142850000 109568278 95654128 1785360384 -0.0576094575 -0.0073037734 0.0088954447 189 1311867724.9137279987 0.0126369214 0.0119578530 0.0186892655 0.0033884220 1.0322260000 109570464 95654128 1784459264 -0.0578468330 -0.0088118194 0.0089540435 190 1311867724.9535229206 0.0101859346 0.0119485271 0.0186892655 0.0033879165 0.8325680000 109571486 95654128 1783332864 -0.0574086905 -0.0060783373 0.0096232304 191 1311867724.9843940735 0.0109913787 0.0119435159 0.0186892655 0.0033811120 1.0007010000 109573672 95654128 1785106432 -0.0575134754 -0.0071772207 0.0097773196 192 1311867725.0159099102 0.0131021105 0.0119495502 0.0186892655 0.0033925418 1.8764410000 109575826 95654128 1783971840 -0.0569337830 -0.0094115920 0.0097666690 193 1311867725.0518310070 0.0116994791 0.0119482545 0.0186892655 0.0033864561 0.9865370000 109576816 95654128 1782951936 -0.0585949123 -0.0084822327 0.0087440116 194 1311867725.0813930035 0.0123962509 0.0119505638 0.0186892655 0.0033800953 0.8968640000 109578970 95654128 1784578048 -0.0582828969 -0.0090413764 0.0085878335 195 1311867725.1151220798 0.0139102293 0.0119606133 0.0186892655 0.0033765267 0.9960640000 109581188 95654128 1783603200 -0.0581093803 -0.0109647354 0.0101610702 196 1311867725.1557130814 0.0136363851 0.0119691632 0.0186892655 0.0033721099 1.0792230000 109582242 95654128 1782460416 -0.0594674610 -0.0109714484 0.0082891565 197 1311867725.1843969822 0.0134255569 0.0119765560 0.0186892655 0.0033636237 1.0356210000 109584364 95654128 1784078336 -0.0610643588 -0.0109621389 0.0069170282 198 1311867725.2150099277 0.0150446510 0.0119920515 0.0186892655 0.0033626726 0.8001000000 109586550 95654128 1785602048 -0.0612054504 -0.0129836695 0.0071337968 199 1311867725.2516539097 0.0122666182 0.0119934312 0.0186892655 0.0033600814 0.7544580000 109587572 95654128 1784623104 -0.0618033856 -0.0097388346 0.0056358650 200 1311867725.2816410065 0.0122535862 0.0119947320 0.0186892655 0.0033527600 0.6568410000 109589726 95654128 1783468032 -0.0618636683 -0.0098459497 0.0057541658 201 1311867725.3196239471 0.0146361552 0.0120078734 0.0186892655 0.0033476668 0.6184730000 109591992 95654128 1785094144 -0.0616208911 -0.0126087163 0.0065373541 202 1311867725.3517010212 0.0144074401 0.0120197524 0.0186892655 0.0033444304 0.7796230000 109592886 95654128 1784107008 -0.0621606596 -0.0125448881 0.0068584927 203 1311867725.3837459087 0.0128891449 0.0120240351 0.0186892655 0.0033594398 0.7552000000 109595008 95654128 1782960128 -0.0620732121 -0.0102082305 0.0055524101 204 1311867725.4178969860 0.0132463844 0.0120300271 0.0186892655 0.0033567161 0.6156250000 109597258 95654128 1784586240 -0.0625071898 -0.0103108659 0.0052068504 205 1311867725.4492449760 0.0125439446 0.0120325340 0.0186892655 0.0033568688 0.7556410000 109768548 95654128 1783590912 -0.0636845678 -0.0093044266 0.0050663538 206 1311867725.4836509228 0.0137496302 0.0120408694 0.0186892655 0.0033615833 0.7188300000 109770766 95654128 1782702080 -0.0644019470 -0.0107614044 0.0057681380 207 1311867725.5178139210 0.0148265650 0.0120543269 0.0186892655 0.0033753812 0.6953610000 109773048 95654128 1784217600 -0.0653323010 -0.0121032614 0.0070569566 208 1311867725.5497610569 0.0154314945 0.0120705632 0.0186892655 0.0033694595 0.8956730000 109773942 95654128 1785847808 -0.0661331639 -0.0123985810 0.0061201323 209 1311867725.5815479755 0.0149296410 0.0120842430 0.0186892655 0.0033706521 0.8187400000 109776128 95654128 1784729600 -0.0669792891 -0.0111506060 0.0047522848 210 1311867725.6194949150 0.0142188985 0.0120944081 0.0186892655 0.0033672763 0.9266600000 109778410 95654128 1783586816 -0.0679401755 -0.0113969427 0.0071927812 211 1311867725.6515610218 0.0151864383 0.0121090622 0.0186892655 0.0034311020 0.8948250000 109779336 95654128 1785229312 -0.0685519353 -0.0123302164 0.0066907457 212 1311867725.6834650040 0.0139237894 0.0121176223 0.0186892655 0.0034240179 0.7593780000 109781522 95654128 1784229888 -0.0691511184 -0.0106085399 0.0055654878 213 1311867725.7201809883 0.0153736016 0.0121329086 0.0186892655 0.0034284061 0.6952270000 109783788 95654128 1783078912 -0.0689813942 -0.0124779548 0.0071127433 214 1311867725.7515070438 0.0156336222 0.0121492670 0.0186892655 0.0034233966 0.8749480000 109784714 95654128 1784852480 -0.0686338171 -0.0127306320 0.0066153794 215 1311867725.7835409641 0.0116762621 0.0121470670 0.0186892655 0.0034308365 1.5300290000 109786868 95654128 1783824384 -0.0702242851 -0.0081160739 0.0053990334 216 1311867725.8211829662 0.0148050338 0.0121593724 0.0186892655 0.0034319813 1.0240910000 109789182 95654128 1782697984 -0.0707631260 -0.0115585346 0.0049819439 217 1311867725.8517971039 0.0144315930 0.0121698435 0.0186892655 0.0034294144 0.8350340000 109790108 95654128 1784340480 -0.0703481957 -0.0106386160 0.0043914239 218 1311867725.8837900162 0.0142252045 0.0121792717 0.0186892655 0.0034237086 0.8995120000 109792230 95654128 1783345152 -0.0701067075 -0.0091472734 0.0027427042 219 1311867725.9192690849 0.0146005927 0.0121903280 0.0186892655 0.0034173549 0.7507600000 109794480 95654128 1782317056 -0.0716225654 -0.0107140504 0.0047830557 220 1311867725.9511859417 0.0160481203 0.0122078634 0.0186892655 0.0034122255 0.6738250000 109795406 95654128 1783943168 -0.0722442418 -0.0124183735 0.0051840981 221 1311867725.9829630852 0.0138549237 0.0122153162 0.0186892655 0.0034077800 0.6747060000 109797560 95654128 1785593856 -0.0725431070 -0.0088898242 0.0030138714 222 1311867726.0219368935 0.0150719434 0.0122281839 0.0186892655 0.0034084493 0.9475190000 109799874 95654128 1784598528 -0.0729956478 -0.0109332353 0.0047800899 223 1311867726.0504179001 0.0157508906 0.0122439808 0.0186892655 0.0034024512 1.6046420000 109800720 95654128 1783459840 -0.0728998035 -0.0114866113 0.0044353632 224 1311867726.0845088959 0.0146168163 0.0122545738 0.0186892655 0.0033975437 0.9774690000 109802970 95654128 1785085952 -0.0728637502 -0.0104011176 0.0044841589 225 1311867726.1199669838 0.0152257476 0.0122677790 0.0186892655 0.0033952100 0.8617640000 109975252 95654128 1784082432 -0.0729028061 -0.0111327935 0.0045774449 226 1311867726.1506989002 0.0171647370 0.0122894469 0.0186892655 0.0033905902 0.6936650000 109976178 95654128 1782988800 -0.0739462897 -0.0135531407 0.0042583332 227 1311867726.1824700832 0.0162826646 0.0123070382 0.0186892655 0.0033852148 0.7756890000 109978364 95654128 1784451072 -0.0748575032 -0.0119763706 0.0015141538 228 1311867726.2198660374 0.0162208043 0.0123242039 0.0186892655 0.0033905349 0.7583060000 109980614 95654128 1783345152 -0.0760604143 -0.0125363516 0.0020175138 229 1311867726.2506690025 0.0189091861 0.0123529592 0.0189091861 0.0033874553 0.8691410000 109981540 95654128 1782190080 -0.0762705877 -0.0157354847 0.0023451333 230 1311867726.2845950127 0.0172253624 0.0123741436 0.0189091861 0.0033843577 0.7842340000 109983726 95654128 1783816192 -0.0773786604 -0.0138840303 0.0011698297 231 1311867726.3187239170 0.0164057501 0.0123915964 0.0189091861 0.0033778293 0.9564440000 109985976 95654128 1785593856 -0.0777103156 -0.0126185361 0.0003364381 232 1311867726.3524029255 0.0163855683 0.0124088118 0.0189091861 0.0033715023 0.9349680000 109986934 95654128 1784475648 -0.0773762986 -0.0128793046 0.0016816806 233 1311867726.3835608959 0.0161782075 0.0124249895 0.0189091861 0.0033657750 0.8571370000 109989088 95654128 1783459840 -0.0779309198 -0.0120568685 0.0004783610 234 1311867726.4218099117 0.0156077007 0.0124385908 0.0189091861 0.0033591688 0.8779090000 109991402 95654128 1785085952 -0.0776500478 -0.0113908406 0.0016543558 235 1311867726.4504199028 0.0142085655 0.0124461226 0.0189091861 0.0033530534 0.7583880000 109992264 95654128 1784098816 -0.0775978416 -0.0097488668 0.0023424239 236 1311867726.4843189716 0.0149073880 0.0124565517 0.0189091861 0.0033463508 0.7520790000 109994482 95654128 1782960128 -0.0780536830 -0.0099914996 0.0011804174 237 1311867726.5207901001 0.0148188472 0.0124665192 0.0189091861 0.0033499000 0.8974390000 109996732 95654128 1784586240 -0.0782132372 -0.0095139770 0.0013669133 238 1311867726.5524380207 0.0164973326 0.0124834554 0.0189091861 0.0033522172 0.7515270000 109997658 95654128 1783611392 -0.0783230662 -0.0120731387 0.0030546228 239 1311867726.5874860287 0.0154492464 0.0124958646 0.0189091861 0.0033559375 0.7590100000 109999908 95654128 1782452224 -0.0787056312 -0.0103718238 0.0013434161 240 1311867726.6204600334 0.0147893475 0.0125054208 0.0189091861 0.0033859417 0.7580960000 110002094 95654128 1784225792 -0.0785961449 -0.0101174312 0.0033774469 241 1311867726.6509370804 0.0172753315 0.0125252129 0.0189091861 0.0034033474 0.6508070000 110002988 95654128 1785856000 -0.0781869143 -0.0131857367 0.0043717450 242 1311867726.6916151047 0.0163821839 0.0125411508 0.0189091861 0.0033968595 0.7252170000 110005334 95654128 1784864768 -0.0786706433 -0.0123740267 0.0028597303 243 1311867726.7201170921 0.0160905663 0.0125557575 0.0189091861 0.0033912497 0.7118900000 110007424 95654128 1783721984 -0.0769293085 -0.0118061556 0.0034538370 244 1311867726.7513859272 0.0170331988 0.0125741076 0.0189091861 0.0033846412 0.8743570000 110008350 95654128 1785348096 -0.0776111931 -0.0134571297 0.0034275476 245 1311867726.7880010605 0.0158055183 0.0125872971 0.0189091861 0.0033785899 1.0208170000 110010632 95654128 1784348672 -0.0775536001 -0.0124504156 0.0030349272 246 1311867726.8198299408 0.0161250308 0.0126016781 0.0189091861 0.0033736674 0.7887680000 110012786 95654128 1783214080 -0.0779595226 -0.0128361601 0.0018754272 247 1311867726.8500390053 0.0170069318 0.0126195131 0.0189091861 0.0033669716 0.8630800000 110013680 95654128 1784832000 -0.0780225471 -0.0139661785 0.0025596833 248 1311867726.8927390575 0.0147896660 0.0126282637 0.0189091861 0.0033651546 0.9747150000 110016058 95654128 1783824384 -0.0781977624 -0.0115355570 0.0015922184 249 1311867726.9216780663 0.0135144778 0.0126318228 0.0189091861 0.0033588657 0.7519300000 110018180 95654128 1782697984 -0.0771210045 -0.0098778978 0.0019343486 250 1311867726.9543499947 0.0139972977 0.0126372847 0.0189091861 0.0033634199 0.7020270000 110019106 95654128 1784451072 -0.0762313753 -0.0105227046 0.0031015221 251 1311867726.9902989864 0.0141481040 0.0126433039 0.0189091861 0.0033599486 0.7368640000 110021324 95654128 1783455744 -0.0765165165 -0.0108486665 0.0029963495 252 1311867727.0208179951 0.0148580736 0.0126520927 0.0189091861 0.0033577643 0.7114300000 110023510 95654128 1782317056 -0.0754934847 -0.0114299655 0.0031460493 253 1311867727.0536949635 0.0141141089 0.0126578714 0.0189091861 0.0033541635 0.6525620000 110024436 95654128 1783943168 -0.0752064735 -0.0109870303 0.0037481696 254 1311867727.0911629200 0.0143623771 0.0126645821 0.0189091861 0.0033483240 0.6448080000 110026718 95654128 1785720832 -0.0743432119 -0.0111992359 0.0041643255 255 1311867727.1196689606 0.0146939997 0.0126725406 0.0189091861 0.0033448880 0.6592260000 110028776 95654128 1784487936 -0.0750117153 -0.0121783707 0.0052768663 256 1311867727.1514298916 0.0143399835 0.0126790540 0.0189091861 0.0033388095 0.6887650000 110029734 95654128 1783332864 -0.0738032013 -0.0116049293 0.0054872371 257 1311867727.1904149055 0.0136001818 0.0126826382 0.0189091861 0.0033609748 1.0043480000 110072944 95654128 1784958976 -0.0732119009 -0.0108297905 0.0045940373 258 1311867727.2208960056 0.0135220131 0.0126858916 0.0189091861 0.0033560634 0.8106910000 110117114 95654128 1783951360 -0.0739033148 -0.0107885767 0.0023309784 259 1311867727.2544560432 0.0140093630 0.0126910015 0.0189091861 0.0033529652 0.7601730000 110118056 95654128 1782951936 -0.0738116801 -0.0115852924 0.0037291939 260 1311867727.2870850563 0.0153565193 0.0127012535 0.0189091861 0.0033486977 0.8565040000 110120274 95654128 1784578048 -0.0735210925 -0.0129744653 0.0032200087 261 1311867727.3192501068 0.0151466103 0.0127106227 0.0189091861 0.0033425657 0.7589540000 110122460 95654128 1783459840 -0.0713931248 -0.0124822883 0.0039856713 262 1311867727.3502039909 0.0147675145 0.0127184734 0.0189091861 0.0033403801 0.7336390000 110123354 95654128 1782444032 -0.0720510259 -0.0126901800 0.0044877720 263 1311867727.3894629478 0.0141178602 0.0127237943 0.0189091861 0.0033362359 0.8655790000 110125604 95654128 1784070144 -0.0719005689 -0.0119171310 0.0029716161 264 1311867727.4182970524 0.0155076170 0.0127343391 0.0189091861 0.0033310303 1.1128130000 110127758 95654128 1785720832 -0.0705883652 -0.0133615825 0.0036819587 265 1311867727.4495580196 0.0143251764 0.0127403422 0.0189091861 0.0033252261 1.0114020000 110128620 95654128 1784725504 -0.0702051744 -0.0122228367 0.0036884826 266 1311867727.4858360291 0.0123982392 0.0127390561 0.0189091861 0.0033311513 0.7970620000 110130902 95654128 1783586816 -0.0698873177 -0.0098450687 0.0021585533 267 1311867727.5198891163 0.0127595132 0.0127391327 0.0189091861 0.0033297933 0.7155090000 110133072 95654128 1785212928 -0.0692498833 -0.0103895552 0.0034498172 268 1311867727.5494980812 0.0138019091 0.0127430983 0.0189091861 0.0033342148 0.9672440000 110133966 95654128 1784229888 -0.0682120249 -0.0115957493 0.0054096384 269 1311867727.5905909538 0.0131926155 0.0127447694 0.0189091861 0.0033312344 1.0304420000 110136312 95654128 1783078912 -0.0670924857 -0.0114715910 0.0050114780 270 1311867727.6176431179 0.0120483460 0.0127421900 0.0189091861 0.0033370170 0.6793290000 110138402 95654128 1784852480 -0.0661201030 -0.0103591979 0.0039982572 271 1311867727.6497650146 0.0130867399 0.0127434614 0.0189091861 0.0033391538 0.9700520000 110139344 95654128 1783713792 -0.0652951971 -0.0117758950 0.0030948129 272 1311867727.6884338856 0.0125201410 0.0127426404 0.0189091861 0.0033363571 0.9698970000 110141514 95654128 1782697984 -0.0656616911 -0.0118905790 0.0023359507 273 1311867727.7184689045 0.0123033999 0.0127410315 0.0189091861 0.0033347575 0.6294440000 110143700 95654128 1784324096 -0.0648576766 -0.0116313267 0.0008889646 274 1311867727.7523269653 0.0131533369 0.0127425362 0.0189091861 0.0033297194 0.8154180000 110144658 95654128 1785991168 -0.0662712604 -0.0133023718 0.0009713258 275 1311867727.7856590748 0.0109070763 0.0127358618 0.0189091861 0.0033259717 0.9438040000 110146844 95654128 1784967168 -0.0669579282 -0.0108859539 -0.0019260343 276 1311867727.8181309700 0.0111927493 0.0127302708 0.0189091861 0.0033240208 0.7939980000 110149062 95654128 1783951360 -0.0660681799 -0.0107360752 -0.0018936957 277 1311867727.8548729420 0.0133968042 0.0127326771 0.0189091861 0.0033209457 0.6744760000 110150052 95654128 1785593856 -0.0660401881 -0.0130951786 -0.0010143226 278 1311867727.8882629871 0.0111049041 0.0127268218 0.0189091861 0.0033170113 0.6806050000 110152270 95654128 1784487936 -0.0662600845 -0.0104847411 -0.0021887729 279 1311867727.9193139076 0.0109977005 0.0127206242 0.0189091861 0.0033118863 0.6130130000 110154424 95654128 1783468032 -0.0661222190 -0.0102372123 -0.0019525887 280 1311867727.9556980133 0.0124760531 0.0127197508 0.0189091861 0.0033067742 0.9084420000 110155414 95654128 1785094144 -0.0664919019 -0.0118987169 -0.0011385309 281 1311867727.9869389534 0.0119424546 0.0127169846 0.0189091861 0.0033025221 0.8633630000 110157632 95654128 1784090624 -0.0643162355 -0.0109186787 -0.0007418571 282 1311867728.0179219246 0.0124008916 0.0127158637 0.0189091861 0.0033014754 0.6363030000 110159754 95654128 1782960128 -0.0643818825 -0.0115381870 -0.0008664566 283 1311867728.0555219650 0.0113250976 0.0127109493 0.0189091861 0.0032961157 0.6929930000 110160776 95654128 1784459264 -0.0632790849 -0.0100892568 -0.0014741769 284 1311867728.0892169476 0.0102327745 0.0127022234 0.0189091861 0.0032944087 0.6751270000 110162994 95654128 1786109952 -0.0625826493 -0.0087550199 -0.0020058583 285 1311867728.1177880764 0.0100421263 0.0126928897 0.0189091861 0.0033010361 0.8010740000 110165148 95654128 1785102336 -0.0623985454 -0.0085912989 -0.0014636237 286 1311867728.1556169987 0.0107600940 0.0126861317 0.0189091861 0.0032978304 0.6734120000 110166138 95654128 1783975936 -0.0625547245 -0.0093858996 -0.0020858047 287 1311867728.1882989407 0.0110993283 0.0126806027 0.0189091861 0.0032940777 0.7584680000 110168388 95654128 1785602048 -0.0627585724 -0.0097450633 -0.0021032332 288 1311867728.2182519436 0.0103012612 0.0126723411 0.0189091861 0.0032908664 0.9548040000 110170526 95654128 1784614912 -0.0616566092 -0.0086391196 -0.0026256065 289 1311867728.2558999062 0.0113443835 0.0126677461 0.0189091861 0.0032885024 1.0140400000 110171516 95654128 1783459840 -0.0611399896 -0.0095622186 -0.0027679782 290 1311867728.2875900269 0.0094747888 0.0126567359 0.0189091861 0.0032868989 1.0367340000 110173702 95654128 1785085952 -0.0611630306 -0.0075697163 -0.0036598414 291 1311867728.3226509094 0.0085175009 0.0126425117 0.0189091861 0.0032994914 0.8741300000 110175952 95654128 1784098816 -0.0607319362 -0.0064455858 -0.0039482974 292 1311867728.3597300053 0.0089879241 0.0126299960 0.0189091861 0.0033210484 0.8562240000 110176910 95654128 1782951936 -0.0602719337 -0.0068250014 -0.0046911198 293 1311867728.3861401081 0.0087071657 0.0126166075 0.0189091861 0.0033175517 1.0049460000 110179032 95654128 1784578048 -0.0602309927 -0.0064200931 -0.0053478647 294 1311867728.4175701141 0.0095712431 0.0126062491 0.0189091861 0.0033551674 0.9400360000 110181218 95654128 1783603200 -0.0596874990 -0.0073800962 -0.0051478222 295 1311867728.4568250179 0.0104299560 0.0125988719 0.0189091861 0.0033533875 0.8397850000 110182240 95654128 1782444032 -0.0593764298 -0.0082722427 -0.0054713651 296 1311867728.4875330925 0.0090513024 0.0125868868 0.0189091861 0.0033521547 0.6365000000 110184394 95654128 1784086528 -0.0596311167 -0.0067362543 -0.0067198048 297 1311867728.5187420845 0.0091574462 0.0125753399 0.0189091861 0.0033482386 0.9480520000 110186548 95654128 1785847808 -0.0599858202 -0.0069979923 -0.0070926705 298 1311867728.5550920963 0.0086839953 0.0125622817 0.0189091861 0.0033430605 0.8194270000 110187570 95654128 1784856576 -0.0586352684 -0.0065163649 -0.0066424953 299 1311867728.5878560543 0.0091354474 0.0125508207 0.0189091861 0.0033379643 0.6776960000 110189788 95654128 1783713792 -0.0580970272 -0.0071280161 -0.0060322718 300 1311867728.6187679768 0.0101350350 0.0125427681 0.0189091861 0.0033332446 0.6323990000 110191910 95654128 1785356288 -0.0585065484 -0.0082731657 -0.0069062156 301 1311867728.6580820084 0.0094908057 0.0125326287 0.0189091861 0.0033280759 0.6370080000 110192964 95654128 1784340480 -0.0580788665 -0.0073898640 -0.0076979976 302 1311867728.6893489361 0.0105399489 0.0125260304 0.0189091861 0.0033248332 1.0186500000 110195150 95654128 1783332864 -0.0584592745 -0.0084168734 -0.0086245565 303 1311867728.7210168839 0.0094198976 0.0125157792 0.0189091861 0.0033262463 1.1020160000 110197336 95654128 1784958976 -0.0565023273 -0.0070343246 -0.0080940677 304 1311867728.7584259510 0.0092975320 0.0125051928 0.0189091861 0.0033216606 0.8065980000 110198326 95654128 1783971840 -0.0569995008 -0.0070294994 -0.0091348765 305 1311867728.7858450413 0.0106723867 0.0124991836 0.0189091861 0.0033191547 0.8948600000 110200480 95654128 1782824960 -0.0564247854 -0.0084902253 -0.0093058767 306 1311867728.8203740120 0.0105438614 0.0124927937 0.0189091861 0.0033222329 0.7339910000 110202666 95654128 1784451072 -0.0565148816 -0.0086969864 -0.0091031212 307 1311867728.8545160294 0.0089447787 0.0124812366 0.0189091861 0.0033175368 0.9812760000 110203624 95654128 1783455744 -0.0547707528 -0.0064553749 -0.0092454245 308 1311867728.8860759735 0.0103185829 0.0124742150 0.0189091861 0.0033126341 0.9706730000 110205842 95654128 1782317056 -0.0546977632 -0.0081448518 -0.0089820623 309 1311867728.9193949699 0.0095840059 0.0124648616 0.0189091861 0.0033088722 0.8134350000 110207996 95654128 1783943168 -0.0548237339 -0.0071750372 -0.0115588885 310 1311867728.9585559368 0.0097234892 0.0124560185 0.0189091861 0.0033192258 0.7032940000 110209114 95654128 1785720832 -0.0533560030 -0.0072209770 -0.0099091614 311 1311867728.9886839390 0.0104873301 0.0124496883 0.0189091861 0.0033194215 0.7788900000 110211204 95654128 1784487936 -0.0532735586 -0.0084713893 -0.0093281912 312 1311867729.0231020451 0.0091138007 0.0124389963 0.0189091861 0.0033212327 0.8543620000 110213454 95654128 1783459840 -0.0544008464 -0.0069934498 -0.0118084773 313 1311867729.0583839417 0.0091486517 0.0124284840 0.0189091861 0.0033181509 0.6502110000 110214444 95654128 1784975360 -0.0536734946 -0.0070651243 -0.0110745085 314 1311867729.0882170200 0.0075378157 0.0124129087 0.0189091861 0.0033167389 0.7150430000 110216598 95654128 1783971840 -0.0529998913 -0.0047442447 -0.0105863418 315 1311867729.1263229847 0.0072115203 0.0123963963 0.0189091861 0.0033325321 0.8222640000 110218880 95654128 1782824960 -0.0547097363 -0.0039163409 -0.0121853156 316 1311867729.1556320190 0.0086036101 0.0123843938 0.0189091861 0.0033338887 0.6697520000 110219742 95654128 1784598528 -0.0546632111 -0.0054579261 -0.0112915430 317 1311867729.1888830662 0.0086134244 0.0123724980 0.0189091861 0.0033818667 0.6961130000 110221960 95654128 1783472128 -0.0547604859 -0.0051350389 -0.0111542381 318 1311867729.2240469456 0.0081045721 0.0123590769 0.0189091861 0.0033953303 0.7124700000 110224178 95654128 1782444032 -0.0543174967 -0.0046065343 -0.0094184577 319 1311867729.2579979897 0.0106147239 0.0123536087 0.0189091861 0.0033949736 0.7548920000 110225168 95654128 1784070144 -0.0542986989 -0.0078252722 -0.0081730494 320 1311867729.2880148888 0.0081717996 0.0123405405 0.0189091861 0.0033959004 0.8392600000 110227322 95654128 1785720832 -0.0549865253 -0.0057829204 -0.0083602574 321 1311867729.3236539364 0.0088155475 0.0123295592 0.0189091861 0.0033949670 0.7406250000 110229540 95654128 1784754176 -0.0535064563 -0.0066246903 -0.0071484232 322 1311867729.3580930233 0.0078019854 0.0123154985 0.0189091861 0.0034149123 0.6730270000 110230530 95654128 1783595008 -0.0539776869 -0.0066630845 -0.0063044038 323 1311867729.3882780075 0.0084941648 0.0123036677 0.0189091861 0.0034129904 0.9554710000 110232652 95654128 1785221120 -0.0529848486 -0.0070039025 -0.0070242626 324 1311867729.4253289700 0.0065836129 0.0122860132 0.0189091861 0.0034112908 0.8593980000 110234934 95654128 1784221696 -0.0517349690 -0.0047044540 -0.0080296062 325 1311867729.4572670460 0.0092164204 0.0122765683 0.0189091861 0.0034083345 1.0064110000 110235860 95654128 1783222272 -0.0512611680 -0.0081693353 -0.0064884112 326 1311867729.4887750149 0.0090815863 0.0122667677 0.0189091861 0.0034171648 1.1861170000 110238078 95654128 1784840192 -0.0517696403 -0.0085871825 -0.0070286104 327 1311867729.5223650932 0.0089530395 0.0122566340 0.0189091861 0.0034125637 0.9927670000 110240264 95654128 1783832576 -0.0514113717 -0.0087917671 -0.0069025634 328 1311867729.5603790283 0.0087530511 0.0122459524 0.0189091861 0.0034116172 1.3333530000 110241286 95654128 1782706176 -0.0493535362 -0.0087469863 -0.0073512327 329 1311867729.5890150070 0.0092509752 0.0122368491 0.0189091861 0.0034093441 0.9105300000 110243408 95654128 1784332288 -0.0495074019 -0.0099477889 -0.0064924159 330 1311867729.6254830360 0.0072770659 0.0122218194 0.0189091861 0.0034059020 0.7175010000 110245658 95654128 1786109952 -0.0491671674 -0.0081556700 -0.0073120324 331 1311867729.6614611149 0.0083619952 0.0122101583 0.0189091861 0.0034023482 0.6596220000 110246648 95654128 1785102336 -0.0490252376 -0.0099116787 -0.0069970926 332 1311867729.6888220310 0.0093914680 0.0122016683 0.0189091861 0.0033992028 0.7311150000 110248706 95654128 1783975936 -0.0497826561 -0.0110644177 -0.0078772390 333 1311867729.7230739594 0.0073954682 0.0121872353 0.0189091861 0.0033976739 0.8375030000 110250956 95654128 1785602048 -0.0482519828 -0.0095349811 -0.0066520898 334 1311867729.7570610046 0.0090388395 0.0121778089 0.0189091861 0.0033955739 0.7740730000 110251818 95654128 1784606720 -0.0478149243 -0.0117338933 -0.0061523924 335 1311867729.7899730206 0.0103820805 0.0121724486 0.0189091861 0.0033908337 0.8153790000 110254052 95654128 1783468032 -0.0472625643 -0.0135361888 -0.0054058214 336 1311867729.8264250755 0.0100230714 0.0121660516 0.0189091861 0.0033924122 0.7747860000 110256270 95654128 1785094144 -0.0469678491 -0.0132420696 -0.0060965121 337 1311867729.8550031185 0.0089718895 0.0121565734 0.0189091861 0.0033886055 0.8411360000 110257132 95654128 1784102912 -0.0469110012 -0.0121784862 -0.0063277129 338 1311867729.8881840706 0.0107504241 0.0121524132 0.0189091861 0.0033857712 0.7563130000 110259382 95654128 1782960128 -0.0461904630 -0.0142750014 -0.0055870623 339 1311867729.9233629704 0.0104831159 0.0121474890 0.0189091861 0.0033826384 0.7097550000 110261600 95654128 1784459264 -0.0470157824 -0.0137568256 -0.0067687556 340 1311867729.9569330215 0.0097383624 0.0121404033 0.0189091861 0.0033781472 0.6594730000 110262558 95654128 1786257408 -0.0465442576 -0.0127076609 -0.0070879976 341 1311867729.9865698814 0.0107800020 0.0121364139 0.0189091861 0.0033750328 1.0577990000 110264680 95654128 1785102336 -0.0467869155 -0.0144069903 -0.0059915977 342 1311867730.0230469704 0.0110790366 0.0121333221 0.0189091861 0.0033706756 0.9948890000 110266930 95654128 1784102912 -0.0460705571 -0.0150094666 -0.0056373067 343 1311867730.0557899475 0.0112845683 0.0121308476 0.0189091861 0.0033664828 0.7970030000 110267872 95654128 1785729024 -0.0454897769 -0.0149515690 -0.0064597810 344 1311867730.0871100426 0.0110161193 0.0121276071 0.0189091861 0.0033621120 0.8802660000 110270058 95654128 1784733696 -0.0458980873 -0.0145551013 -0.0062624840 345 1311867730.1231229305 0.0123616941 0.0121282857 0.0189091861 0.0033582258 0.7728760000 110272308 95654128 1783595008 -0.0456329025 -0.0153356818 -0.0076496024 346 1311867730.1568520069 0.0101290168 0.0121225074 0.0189091861 0.0033557593 0.7927280000 110273266 95654128 1785221120 -0.0452965386 -0.0132470485 -0.0063069058 347 1311867730.1882419586 0.0102892555 0.0121172243 0.0189091861 0.0033538597 0.9561140000 110275420 95654128 1784217600 -0.0449014492 -0.0134503059 -0.0056434982 348 1311867730.2224810123 0.0110988785 0.0121142980 0.0189091861 0.0033501773 0.7942470000 110277670 95654128 1783070720 -0.0442301258 -0.0139391823 -0.0060771513 349 1311867730.2575879097 0.0112377349 0.0121117864 0.0189091861 0.0033454956 0.8321090000 110278644 95654128 1784713216 -0.0437373370 -0.0140352491 -0.0050752563 350 1311867730.2914879322 0.0101828314 0.0121062751 0.0189091861 0.0033437620 0.7824250000 110280862 95654128 1783738368 -0.0443718135 -0.0126926405 -0.0051514795 351 1311867730.3230810165 0.0090184538 0.0120974778 0.0189091861 0.0033452094 0.7128680000 110453944 95654128 1782579200 -0.0432911925 -0.0108847450 -0.0052344440 352 1311867730.3554260731 0.0092872316 0.0120894942 0.0189091861 0.0033456449 0.6962470000 110454968 95654128 1784479744 -0.0440072306 -0.0108689321 -0.0056876685 353 1311867730.3982920647 0.0089328196 0.0120805518 0.0189091861 0.0033435450 0.7976140000 110457314 95654128 1786109952 -0.0440623872 -0.0107212160 -0.0041812421 354 1311867730.4225230217 0.0080266939 0.0120691002 0.0189091861 0.0033506056 0.7188620000 110459404 95654128 1785122816 -0.0427843444 -0.0089638829 -0.0045034750 355 1311867730.4600110054 0.0089413431 0.0120602896 0.0189091861 0.0033468576 0.7746170000 110460534 95654128 1783975936 -0.0445207730 -0.0091993129 -0.0057670930 356 1311867730.4948410988 0.0094188051 0.0120528697 0.0189091861 0.0033448760 0.7385360000 110462752 95654128 1785602048 -0.0443566777 -0.0098590413 -0.0044911765 357 1311867730.5300729275 0.0085148895 0.0120429594 0.0189091861 0.0033420851 0.7978090000 110463710 95654128 1784606720 -0.0438553020 -0.0088269031 -0.0037166232 358 1311867730.5597670078 0.0090601472 0.0120346275 0.0189091861 0.0033375220 0.7540100000 110465864 95654128 1783468032 -0.0449184850 -0.0087736985 -0.0046651969 359 1311867730.5940020084 0.0112087447 0.0120323270 0.0189091861 0.0033414899 0.6961670000 110468114 95654128 1785110528 -0.0455664545 -0.0107625946 -0.0045257490 360 1311867730.6230149269 0.0090126125 0.0120239389 0.0189091861 0.0033461468 0.6622270000 110468944 95654128 1784090624 -0.0431202911 -0.0088382559 -0.0030634939 361 1311867730.6614060402 0.0100685572 0.0120185223 0.0189091861 0.0033418737 0.7112840000 110471366 95654128 1783087104 -0.0419706032 -0.0099477665 -0.0023387973 362 1311867730.6922950745 0.0105771143 0.0120145406 0.0189091861 0.0033374861 0.9642130000 110473552 95654128 1784721408 -0.0423916727 -0.0105069522 -0.0020574059 363 1311867730.7275629044 0.0111546805 0.0120121718 0.0189091861 0.0033384968 0.7806360000 110474510 95654128 1783730176 -0.0423346944 -0.0108971521 -0.0031047300 364 1311867730.7572948933 0.0097144684 0.0120058594 0.0189091861 0.0033385000 0.8156900000 110646732 95654128 1782697984 -0.0404832587 -0.0090941954 -0.0027400344 365 1311867730.7932779789 0.0093610529 0.0119986134 0.0189091861 0.0033351970 0.8604340000 110649014 95654128 1784467456 -0.0407408737 -0.0080721434 -0.0039090486 366 1311867730.8240480423 0.0128263086 0.0120008748 0.0189091861 0.0033350400 0.6950620000 110649876 95654128 1783472128 -0.0436373018 -0.0104806069 -0.0052971868 367 1311867730.8591129780 0.0113673434 0.0119991486 0.0189091861 0.0033364922 0.7760920000 110652266 95654128 1782206464 -0.0441102162 -0.0075909514 -0.0057713375 368 1311867730.8922739029 0.0079144416 0.0119880489 0.0189091861 0.0033451584 0.7518460000 110654388 95654128 1783832576 -0.0393121392 -0.0050125918 -0.0032617149 369 1311867730.9270720482 0.0087439306 0.0119792572 0.0189091861 0.0033475651 0.9176610000 110655378 95654128 1785483264 -0.0379211232 -0.0055681420 -0.0024891552 370 1311867730.9611239433 0.0080907336 0.0119687477 0.0189091861 0.0033457920 1.0221640000 110657564 95654128 1784475648 -0.0366343558 -0.0039318181 -0.0030192179 371 1311867730.9928169250 0.0076239891 0.0119570367 0.0189091861 0.0033429953 0.8325780000 110659750 95654128 1783324672 -0.0371832252 -0.0040705488 -0.0015902164 372 1311867731.0221049786 0.0105875563 0.0119533553 0.0189091861 0.0033420923 0.7368920000 110660644 95654128 1784967168 -0.0359495953 -0.0072845104 -0.0006920186 373 1311867731.0609729290 0.0081446143 0.0119431442 0.0189091861 0.0033397291 0.8988590000 110663066 95654128 1783959552 -0.0346484743 -0.0046103327 -0.0001256455 374 1311867731.0900061131 0.0086361580 0.0119343020 0.0189091861 0.0033369460 0.8342260000 110663928 95654128 1782833152 -0.0339902528 -0.0052418481 0.0002149511 375 1311867731.1276559830 0.0090313554 0.0119265608 0.0189091861 0.0033428596 0.9729590000 110666226 95654128 1784459264 -0.0350820571 -0.0048219296 -0.0016672923 376 1311867731.1551880836 0.0081742611 0.0119165813 0.0189091861 0.0033401233 0.9550820000 110668348 95654128 1783480320 -0.0359753035 -0.0033929115 -0.0014838070 377 1311867731.1935870647 0.0070213382 0.0119035966 0.0189091861 0.0033388908 0.8744450000 110669338 95654128 1782325248 -0.0342568457 -0.0028397376 0.0001217824 378 1311867731.2235820293 0.0065278639 0.0118893751 0.0189091861 0.0033371759 0.9358720000 110671524 95654128 1783951360 -0.0316420309 -0.0027498442 0.0018314978 379 1311867731.2602028847 0.0069037625 0.0118762204 0.0189091861 0.0033334007 0.9811950000 110673882 95654128 1785745408 -0.0310232434 -0.0033017434 0.0025855333 380 1311867731.2900059223 0.0069234213 0.0118631867 0.0189091861 0.0033814886 0.9960880000 110674776 95654128 1784754176 -0.0297991261 -0.0036817114 0.0029821873 381 1311867731.3230779171 0.0087948861 0.0118551335 0.0189091861 0.0033961941 0.8397700000 110676994 95654128 1783721984 -0.0303924400 -0.0060714334 0.0035619279 382 1311867731.3570859432 0.0088399425 0.0118472403 0.0189091861 0.0033944072 0.8924270000 110679244 95654128 1785348096 -0.0274683386 -0.0062835226 0.0034533846 383 1311867731.3915760517 0.0092543876 0.0118404704 0.0189091861 0.0033920231 0.8389220000 110680170 95654128 1784238080 -0.0265217572 -0.0070907008 0.0029606086 384 1311867731.4279849529 0.0109388605 0.0118381225 0.0189091861 0.0033892362 0.9342810000 110853284 95654128 1783214080 -0.0251159035 -0.0091724396 0.0030005630 385 1311867731.4602010250 0.0095738312 0.0118322412 0.0189091861 0.0033892354 0.9565280000 110855610 95654128 1784856576 -0.0262840111 -0.0084638344 0.0016345266 386 1311867731.4926180840 0.0086516691 0.0118240014 0.0189091861 0.0033858666 0.9145360000 110856568 95654128 1783980032 -0.0253608767 -0.0076377820 0.0012881332 387 1311867731.5259540081 0.0087409914 0.0118160350 0.0189091861 0.0033944124 0.9731700000 110858754 95654128 1782833152 -0.0266222283 -0.0083873263 0.0008448235 388 1311867731.5589148998 0.0085877767 0.0118077147 0.0189091861 0.0033960798 0.7752200000 110860940 95654128 1784459264 -0.0254756063 -0.0083655734 0.0012565886 389 1311867731.5967359543 0.0082083344 0.0117984618 0.0189091861 0.0034357349 0.9386880000 110861994 95654128 1783463936 -0.0239407718 -0.0074977083 0.0000157388 390 1311867731.6247410774 0.0079039158 0.0117884758 0.0189091861 0.0034464738 1.0361470000 110864084 95654128 1782325248 -0.0238490123 -0.0069170082 -0.0002830297 391 1311867731.6616659164 0.0084578376 0.0117799575 0.0189091861 0.0034669899 0.8920660000 110865246 95654128 1784098816 -0.0255676638 -0.0070301346 -0.0006418031 392 1311867731.6925039291 0.0091487626 0.0117732453 0.0189091861 0.0034691928 0.8824010000 110867400 95654128 1785729024 -0.0258038621 -0.0079827067 0.0005474343 393 1311867731.7299311161 0.0083337054 0.0117644933 0.0189091861 0.0034735654 1.2174850000 110869682 95654128 1784606720 -0.0238746554 -0.0075631649 0.0019636138 394 1311867731.7615330219 0.0085247103 0.0117562705 0.0189091861 0.0034694753 1.1816300000 110870608 95654128 1783468032 -0.0241920110 -0.0074562528 0.0004875581 395 1311867731.7939310074 0.0060097817 0.0117417224 0.0189091861 0.0034660993 0.8257230000 110872794 95654128 1785094144 -0.0229892693 -0.0052674012 0.0010988170 396 1311867731.8252151012 0.0088137193 0.0117343285 0.0189091861 0.0034663223 0.6996380000 111044796 95654128 1783975936 -0.0229920521 -0.0086570019 0.0020601712 397 1311867731.8593230247 0.0094717089 0.0117286292 0.0189091861 0.0034816338 0.7718170000 111045910 95654128 1783107584 -0.0231982935 -0.0094288606 0.0007511005 398 1311867731.8910930157 0.0084785456 0.0117204631 0.0189091861 0.0034849308 0.8762670000 111048128 95654128 1784733696 -0.0220245384 -0.0089507466 0.0003696133 399 1311867731.9224479198 0.0069143204 0.0117084177 0.0189091861 0.0034859692 0.7208630000 111050314 95654128 1783463936 -0.0219521485 -0.0077779191 0.0004383283 400 1311867731.9598410130 0.0068542347 0.0116962822 0.0189091861 0.0034823775 0.8716820000 111051272 95654128 1782476800 -0.0205134936 -0.0083517730 0.0004955632 401 1311867731.9915709496 0.0069058058 0.0116843359 0.0189091861 0.0034799760 0.8144880000 111053458 95654128 1784086528 -0.0217527039 -0.0081746792 -0.0007352748 402 1311867732.0239229202 0.0084862225 0.0116763804 0.0189091861 0.0034864250 0.7373380000 111055644 95654128 1785737216 -0.0196718872 -0.0109709268 0.0000073055 403 1311867732.0619950294 0.0110997567 0.0116749496 0.0189091861 0.0034840469 0.9799690000 111056806 95654128 1784741888 -0.0183746815 -0.0135251749 -0.0004729866 404 1311867732.0918290615 0.0075595323 0.0116647629 0.0189091861 0.0034846415 1.1507310000 111058960 95654128 1783730176 -0.0176629703 -0.0098955352 -0.0022762539 405 1311867732.1221950054 0.0108798956 0.0116628249 0.0189091861 0.0034839085 1.1629260000 111061146 95654128 1785356288 -0.0189676005 -0.0135732628 -0.0025859876 406 1311867732.1605980396 0.0102044232 0.0116592328 0.0189091861 0.0034814410 1.0596090000 111062136 95654128 1784238080 -0.0178639386 -0.0133574642 -0.0028288122 407 1311867732.1931400299 0.0084808758 0.0116514236 0.0189091861 0.0035110205 0.7544100000 111064370 95654128 1783222272 -0.0183018781 -0.0114538576 -0.0046009277 408 1311867732.2232089043 0.0096526248 0.0116465246 0.0189091861 0.0035520293 0.8156370000 111066492 95654128 1784848384 -0.0180401988 -0.0129333334 -0.0044134944 409 1311867732.2590498924 0.0073900521 0.0116361175 0.0189091861 0.0036725898 0.8746630000 111067622 95654128 1783832576 -0.0185252447 -0.0094035501 -0.0070899329 410 1311867732.2903969288 0.0072204061 0.0116253475 0.0189091861 0.0037129148 0.6967860000 111069808 95654128 1782706176 -0.0190165397 -0.0088133393 -0.0073680696 411 1311867732.3218240738 0.0099689560 0.0116213174 0.0189091861 0.0037182169 0.9368380000 111070734 95654128 1784332288 -0.0178943668 -0.0130032459 -0.0066317949 412 1311867732.3607840538 0.0099886227 0.0116173545 0.0189091861 0.0037236400 0.9522400000 111073016 95654128 1785982976 -0.0180379562 -0.0127617279 -0.0073180483 413 1311867732.3899528980 0.0087277768 0.0116103580 0.0189091861 0.0037238447 0.8447430000 111245486 95654128 1784975360 -0.0174576100 -0.0116535509 -0.0075046215 414 1311867732.4218940735 0.0088398820 0.0116036660 0.0189091861 0.0037241070 0.7298800000 111246444 95654128 1784012800 -0.0159466658 -0.0126527054 -0.0063273842 415 1311867732.4593050480 0.0070063858 0.0115925882 0.0189091861 0.0037268127 0.8518350000 111248834 95654128 1785602048 -0.0151456296 -0.0107081803 -0.0076526543 416 1311867732.4918489456 0.0077978191 0.0115834662 0.0189091861 0.0037255601 0.8810120000 111251052 95654128 1784479744 -0.0147494702 -0.0115830796 -0.0081397910 417 1311867732.5229809284 0.0085201785 0.0115761201 0.0189091861 0.0037214160 0.9124440000 111251946 95654128 1783341056 -0.0143670840 -0.0122693591 -0.0080861207 418 1311867732.5698928833 0.0074165543 0.0115661690 0.0189091861 0.0037224655 0.9722970000 111254372 95654128 1784967168 -0.0146201281 -0.0096684713 -0.0092276298 419 1311867732.5926280022 0.0090950113 0.0115602713 0.0189091861 0.0037205202 1.1428640000 111256430 95654128 1783980032 -0.0151633956 -0.0106453178 -0.0106941042 420 1311867732.6242370605 0.0076997988 0.0115510797 0.0189091861 0.0037240490 0.9729260000 111257356 95654128 1782706176 -0.0125738895 -0.0107251499 -0.0103641627 421 1311867732.6630299091 0.0089295954 0.0115448529 0.0189091861 0.0037229047 0.9960370000 111259778 95654128 1784332288 -0.0133325718 -0.0114877522 -0.0104553718 422 1311867732.6922440529 0.0099738697 0.0115411302 0.0189091861 0.0037200317 0.9554540000 111261932 95654128 1785999360 -0.0142496573 -0.0104320385 -0.0122066904 423 1311867732.7260940075 0.0090638101 0.0115352736 0.0189091861 0.0037168021 0.9208180000 111262890 95654128 1784991744 -0.0135653848 -0.0095985169 -0.0118917096 424 1311867732.7601239681 0.0079809120 0.0115268907 0.0189091861 0.0037135016 0.9152310000 111265076 95654128 1783848960 -0.0120474873 -0.0096514896 -0.0115220444 425 1311867732.7919039726 0.0085529219 0.0115198931 0.0189091861 0.0037094791 0.8751760000 111437938 95654128 1785491456 -0.0124856252 -0.0091160713 -0.0125406124 426 1311867732.8280360699 0.0094910376 0.0115151305 0.0189091861 0.0037056611 0.7975610000 111438896 95654128 1784733696 -0.0132938484 -0.0092864698 -0.0128444945 427 1311867732.8589270115 0.0090223616 0.0115092927 0.0189091861 0.0037024537 0.9320290000 111441222 95654128 1783595008 -0.0123794740 -0.0098248189 -0.0125607522 428 1311867732.8912909031 0.0101013174 0.0115060030 0.0189091861 0.0037038574 1.0173930000 111442148 95654128 1785368576 -0.0144529659 -0.0082099428 -0.0129125193 429 1311867732.9262781143 0.0108837327 0.0115045525 0.0189091861 0.0036999432 0.9807810000 111444398 95654128 1784229888 -0.0151677188 -0.0064413608 -0.0138644893 430 1311867732.9602870941 0.0242115688 0.0115341037 0.0242115688 0.0042349503 2.2668320000 111523976 95654128 1784504320 0.0170162730 -0.0092374710 -0.0128180049 431 1311867732.9987640381 0.0063811438 0.0115221479 0.0242115688 0.0044523927 1.7400030000 111525154 95654128 1785749504 -0.0000883862 -0.0048223371 -0.0098666903 432 1311867733.0276939869 0.0058585182 0.0115090376 0.0242115688 0.0044504839 1.7904210000 111527292 95654128 1784356864 -0.0008563955 -0.0019253273 -0.0099207042 433 1311867733.0607628822 0.0053064087 0.0114947128 0.0242115688 0.0044610300 0.9765800000 111529478 95654128 1782988800 -0.0004532742 -0.0048416932 -0.0078219157 434 1311867733.0977020264 0.0049471813 0.0114796264 0.0242115688 0.0044611898 0.7862810000 111530468 95654128 1784627200 -0.0008847786 -0.0028508690 -0.0087361038 435 1311867733.1263020039 0.0055232854 0.0114659336 0.0242115688 0.0044572350 0.7693370000 111532590 95654128 1783488512 -0.0010995917 -0.0023879413 -0.0101367766 436 1311867733.1625030041 0.0056366874 0.0114525638 0.0242115688 0.0044546265 0.8291240000 111534840 95654128 1782366208 0.0004958308 -0.0045647980 -0.0071061072 437 1311867733.1926651001 0.0054724761 0.0114388794 0.0242115688 0.0044515361 0.9594660000 111535874 95654128 1783717888 0.0001962611 -0.0050794580 -0.0081646964 438 1311867733.2259631157 0.0045741913 0.0114232066 0.0242115688 0.0044587393 0.8157710000 111538092 95654128 1785384960 -0.0016314313 -0.0016631694 -0.0095191039 439 1311867733.2618060112 0.0034567108 0.0114050597 0.0242115688 0.0044580144 0.8434450000 111540342 95654128 1784250368 -0.0016569147 -0.0030827015 -0.0086934175 440 1311867733.2919199467 0.0041699489 0.0113886162 0.0242115688 0.0044574081 0.7625600000 111712056 95654128 1783128064 -0.0006283086 -0.0051909620 -0.0079298997 441 1311867733.3300418854 0.0040336461 0.0113719383 0.0242115688 0.0044578851 0.7638130000 111714338 95654128 1784479744 -0.0006481230 -0.0052105840 -0.0081676841 442 1311867733.3602790833 0.0033170758 0.0113537146 0.0242115688 0.0044538401 0.8390040000 111716524 95654128 1783230464 -0.0009547622 -0.0060776491 -0.0066091577 443 1311867733.3923840523 0.0038407599 0.0113367554 0.0242115688 0.0044511173 0.8014720000 111717590 95654128 1782247424 -0.0006870052 -0.0068624425 -0.0073831477 444 1311867733.4289550781 0.0028157225 0.0113175638 0.0242115688 0.0044522919 0.9482100000 111719840 95654128 1783582720 -0.0007909893 -0.0036205831 -0.0089017991 445 1311867733.4588150978 0.0031508757 0.0112992117 0.0242115688 0.0044488431 0.9084710000 111720670 95654128 1785233408 0.0001099408 -0.0035435569 -0.0087938327 446 1311867733.4956119061 0.0033430641 0.0112813728 0.0242115688 0.0044448488 0.8065120000 111722856 95654128 1783988224 0.0004077491 -0.0038007246 -0.0090900417 447 1311867733.5290400982 0.0050080647 0.0112673386 0.0242115688 0.0044449586 0.8020340000 111725074 95654128 1782861824 0.0001670518 -0.0011230649 -0.0099464972 448 1311867733.5630290508 0.0047848946 0.0112528689 0.0242115688 0.0044460275 0.8279650000 111726032 95654128 1784233984 0.0024076959 -0.0046218652 -0.0094065275 449 1311867733.5922229290 0.0042877886 0.0112373564 0.0242115688 0.0044443960 0.8136230000 111898866 95654128 1785995264 0.0027784833 -0.0060982304 -0.0078514572 450 1311867733.6283020973 0.0030293390 0.0112191164 0.0242115688 0.0044470348 0.9980750000 111901116 95654128 1784750080 0.0011962766 -0.0038123305 -0.0086368406 451 1311867733.6601879597 0.0035979268 0.0112022180 0.0242115688 0.0044425660 0.8948720000 111902026 95654128 1783607296 0.0017972344 -0.0030790337 -0.0086220289 452 1311867733.6917510033 0.0044148634 0.0111872017 0.0242115688 0.0044386443 0.8749210000 111904228 95654128 1785249792 0.0037568507 -0.0034317975 -0.0081109488 453 1311867733.7288239002 0.0036554600 0.0111705753 0.0242115688 0.0044338149 0.8769680000 111906478 95654128 1784229888 0.0036670223 -0.0050197807 -0.0079573654 454 1311867733.7597820759 0.0029950056 0.0111525675 0.0242115688 0.0044311985 0.7926290000 111907340 95654128 1783226368 0.0013632779 -0.0047340267 -0.0083405413 455 1311867733.7924160957 0.0043499675 0.0111376167 0.0242115688 0.0044556768 0.8783660000 111909666 95654128 1784741888 0.0022776173 -0.0042508040 -0.0085705966 456 1311867733.8282589912 0.0023263341 0.0111182937 0.0242115688 0.0044549396 0.8243680000 111911916 95654128 1783750656 0.0033071428 -0.0073351804 -0.0071959859 457 1311867733.8608579636 0.0027278315 0.0110999338 0.0242115688 0.0044553396 0.9019310000 112083722 95654128 1782591488 0.0028530345 -0.0063992213 -0.0080373185 458 1311867733.8918149471 0.0032770447 0.0110828533 0.0242115688 0.0044507947 0.8598670000 112085844 95654128 1784233984 0.0034431019 -0.0071979812 -0.0087148016 459 1311867733.9289460182 0.0021277848 0.0110633433 0.0242115688 0.0044492041 0.8095530000 112088094 95654128 1785995264 0.0036358116 -0.0076839551 -0.0075544962 460 1311867733.9595899582 0.0028261025 0.0110454363 0.0242115688 0.0044564645 0.8598110000 112089020 95654128 1784987648 0.0033092427 -0.0077242698 -0.0081340587 461 1311867733.9941790104 0.0033961765 0.0110288435 0.0242115688 0.0044566830 0.8630170000 112091378 95654128 1783861248 0.0045602876 -0.0074795820 -0.0090888916 462 1311867734.0275731087 0.0031645030 0.0110118212 0.0242115688 0.0044596577 1.0828710000 112092368 95654128 1785487360 0.0043917676 -0.0088467486 -0.0085427547 463 1311867734.0599920750 0.0025310572 0.0109935042 0.0242115688 0.0044575618 0.8056010000 112094538 95654128 1784508416 0.0059267292 -0.0079943556 -0.0083719855 464 1311867734.0956780910 0.0039854511 0.0109784006 0.0242115688 0.0044535932 0.9668440000 112096788 95654128 1783353344 0.0056506526 -0.0075344155 -0.0096824225 465 1311867734.1274170876 0.0016931584 0.0109584323 0.0242115688 0.0044495646 0.7766170000 112268142 95654128 1784979456 0.0071245455 -0.0100023393 -0.0082099074 466 1311867734.1618878841 0.0028014404 0.0109409281 0.0242115688 0.0044482529 0.7947600000 112270328 95654128 1783992320 0.0070526577 -0.0096973330 -0.0096954182 467 1311867734.1942350864 0.0039469409 0.0109259517 0.0242115688 0.0044464133 0.9676880000 112272686 95654128 1782845440 0.0084437607 -0.0073272511 -0.0103255715 468 1311867734.2291829586 0.0015848305 0.0109059920 0.0242115688 0.0044449623 0.7768600000 112273612 95654128 1784487936 0.0085553145 -0.0107890293 -0.0089496905 469 1311867734.2607750893 0.0031673710 0.0108894917 0.0242115688 0.0044408504 0.8618970000 112275798 95654128 1783476224 0.0093161799 -0.0087021980 -0.0098060565 470 1311867734.2941219807 0.0043545533 0.0108755876 0.0242115688 0.0044368728 0.8707820000 112277984 95654128 1782464512 0.0082305344 -0.0079972195 -0.0102645224 471 1311867734.3263280392 0.0033187643 0.0108595434 0.0242115688 0.0044355325 0.7928000000 112449742 95654128 1784090624 0.0104212528 -0.0088338545 -0.0094897617 472 1311867734.3610401154 0.0042104176 0.0108454563 0.0242115688 0.0044348524 0.7571430000 112451960 95654128 1785614336 0.0114469500 -0.0083879372 -0.0098555479 473 1311867734.3941841125 0.0062524267 0.0108357458 0.0242115688 0.0044439833 0.7985870000 112454318 95654128 1784635392 0.0106571717 -0.0059526633 -0.0104000689 474 1311867734.4276480675 0.0046207891 0.0108226341 0.0242115688 0.0044398079 0.7946360000 112455276 95654128 1783480320 0.0104196230 -0.0076498264 -0.0097033568 475 1311867734.4586091042 0.0039237700 0.0108081102 0.0242115688 0.0044386809 0.9356380000 112457430 95654128 1785114624 0.0115132099 -0.0092103109 -0.0093663689 476 1311867734.4938759804 0.0049780263 0.0107958621 0.0242115688 0.0044364554 0.7599790000 112459680 95654128 1784127488 0.0105887232 -0.0083745662 -0.0101382956 477 1311867734.5300569534 0.0036668940 0.0107809167 0.0242115688 0.0044329274 0.8333190000 112460670 95654128 1782980608 0.0109481458 -0.0100399796 -0.0093327761 478 1311867734.5595300198 0.0027221800 0.0107640574 0.0242115688 0.0044377444 0.7946100000 112462792 95654128 1784606720 0.0117123621 -0.0105389236 -0.0083129229 479 1311867734.5953910351 0.0046447557 0.0107512823 0.0242115688 0.0044362624 0.7714560000 112463890 95654128 1783611392 0.0126675209 -0.0092948461 -0.0092133861 480 1311867734.6285231113 0.0046455986 0.0107385621 0.0242115688 0.0044331731 0.7609830000 112466108 95654128 1782472704 0.0127301197 -0.0085028904 -0.0087239742 481 1311867734.6593229771 0.0042714570 0.0107251170 0.0242115688 0.0044287506 0.7338990000 112468262 95654128 1784098816 0.0121146040 -0.0087450836 -0.0084780799 482 1311867734.6947479248 0.0039552711 0.0107110716 0.0242115688 0.0044242002 0.8127750000 112469220 95654128 1785896960 0.0109244511 -0.0096160490 -0.0085012848 483 1311867734.7310240269 0.0031348008 0.0106953858 0.0242115688 0.0044290885 0.8013810000 112641806 95654128 1784754176 0.0125104673 -0.0108616129 -0.0086561842 484 1311867734.7607629299 0.0036662947 0.0106808629 0.0242115688 0.0044254122 0.8143470000 112643928 95654128 1783779328 0.0125073241 -0.0104611190 -0.0090654474 485 1311867734.7976419926 0.0047076032 0.0106685469 0.0242115688 0.0044239148 0.8150030000 112645090 95654128 1785368576 0.0122067668 -0.0089908242 -0.0088823251 486 1311867734.8298120499 0.0051660850 0.0106572249 0.0242115688 0.0044206798 0.7692360000 112647276 95654128 1784258560 0.0125712054 -0.0084139081 -0.0087563898 487 1311867734.8645250797 0.0056714532 0.0106469872 0.0242115688 0.0044167100 0.8798710000 112649494 95654128 1783099392 0.0145079689 -0.0078851385 -0.0083799707 488 1311867734.8943901062 0.0044485610 0.0106342855 0.0242115688 0.0044148318 0.8465260000 112650420 95654128 1784725504 0.0154432878 -0.0096126152 -0.0080587883 489 1311867734.9263660908 0.0047719437 0.0106222971 0.0242115688 0.0044113972 0.8241760000 112652574 95654128 1783734272 0.0153847402 -0.0094607752 -0.0085355509 490 1311867734.9631719589 0.0048008393 0.0106104165 0.0242115688 0.0044079493 0.8349820000 112654696 95654128 1782591488 0.0157619081 -0.0092974510 -0.0086176032 491 1311867734.9948470592 0.0044069500 0.0105977822 0.0242115688 0.0044126811 0.8742300000 112655762 95654128 1784217600 0.0159273352 -0.0098805185 -0.0082024382 492 1311867735.0292239189 0.0041620713 0.0105847015 0.0242115688 0.0044158544 0.8144320000 112658044 95654128 1785995264 0.0158848800 -0.0110520925 -0.0092323292 493 1311867735.0596508980 0.0042872098 0.0105719277 0.0242115688 0.0044115332 0.7994140000 112660134 95654128 1784877056 0.0158733148 -0.0114838211 -0.0094876615 494 1311867735.0952830315 0.0026423519 0.0105558759 0.0242115688 0.0044078297 0.7944310000 112661124 95654128 1783861248 0.0159820467 -0.0121464618 -0.0079139480 495 1311867735.1313030720 0.0040087570 0.0105426494 0.0242115688 0.0044077199 0.8172780000 112663374 95654128 1785487360 0.0153425103 -0.0106130242 -0.0084808143 496 1311867735.1603751183 0.0044410387 0.0105303478 0.0242115688 0.0044051301 0.8302330000 112665496 95654128 1784508416 0.0166794173 -0.0104082003 -0.0084219100 497 1311867735.1994349957 0.0022219762 0.0105136307 0.0242115688 0.0044036267 0.7941890000 112666658 95654128 1783500800 0.0166435577 -0.0131379599 -0.0072639333 498 1311867735.2263538837 0.0031657519 0.0104988759 0.0242115688 0.0044003949 0.8506870000 112668812 95654128 1784995840 0.0161511172 -0.0128307389 -0.0082930364 499 1311867735.2655019760 0.0044307918 0.0104867154 0.0242115688 0.0043966891 0.8078530000 112840362 95654128 1783844864 0.0165065639 -0.0108526088 -0.0078887623 500 1311867735.2961549759 0.0043615014 0.0104744650 0.0242115688 0.0043977540 0.8041610000 112842548 95654128 1782992896 0.0168610252 -0.0113915317 -0.0074014324 501 1311867735.3321089745 0.0049850130 0.0104635080 0.0242115688 0.0043968978 0.8559220000 112844798 95654128 1784471552 0.0162915867 -0.0110337585 -0.0078832544 502 1311867735.3666970730 0.0050134924 0.0104526514 0.0242115688 0.0044034540 0.9694700000 112845692 95654128 1783476224 0.0167393889 -0.0112348748 -0.0078820353 503 1311867735.3943350315 0.0056571793 0.0104431177 0.0242115688 0.0044192217 0.9562820000 112847922 95654128 1782337536 0.0187362842 -0.0105751958 -0.0073594833 504 1311867735.4322299957 0.0062820478 0.0104348616 0.0242115688 0.0044253017 0.8143490000 112850236 95654128 1783963648 0.0189513508 -0.0097267712 -0.0072933938 505 1311867735.4628560543 0.0044894889 0.0104230886 0.0242115688 0.0044290930 0.7971260000 112851130 95654128 1785614336 0.0181125123 -0.0107069071 -0.0066703074 506 1311867735.4973869324 0.0045483634 0.0104114784 0.0242115688 0.0044341168 0.8807690000 112853380 95654128 1784635392 0.0176750999 -0.0111233350 -0.0064824922 507 1311867735.5293200016 0.0047446033 0.0104003012 0.0242115688 0.0044319282 0.8349450000 112855534 95654128 1783480320 0.0166731142 -0.0107702743 -0.0063633868 508 1311867735.5632629395 0.0036152520 0.0103869448 0.0242115688 0.0044282354 0.9151770000 113026924 95654128 1785106432 0.0180302095 -0.0120251914 -0.0057788859 509 1311867735.5976569653 0.0026054995 0.0103716571 0.0242115688 0.0044248280 0.8137250000 113029282 95654128 1784229888 0.0170878321 -0.0126633542 -0.0051273527 510 1311867735.6363260746 0.0028556366 0.0103569198 0.0242115688 0.0044282624 0.8134830000 113031532 95654128 1783099392 0.0169953164 -0.0127293738 -0.0056511802 511 1311867735.6626520157 0.0023674297 0.0103412848 0.0242115688 0.0044267932 0.7747880000 113032394 95654128 1784860672 0.0193628389 -0.0136094037 -0.0045067482 512 1311867735.6952130795 0.0019937975 0.0103249811 0.0242115688 0.0044233529 0.7780580000 113034580 95654128 1783869440 0.0195170082 -0.0146967750 -0.0047056070 513 1311867735.7291250229 0.0039082821 0.0103124729 0.0242115688 0.0044236768 0.8557360000 113118718 95654128 1782726656 0.0206102543 -0.0131690810 -0.0064153811 514 1311867735.7631659508 0.0032870520 0.0102988048 0.0242115688 0.0044245123 0.7742140000 113203676 95654128 1784352768 0.0196776167 -0.0131098069 -0.0064617954 515 1311867735.7963778973 0.0023270848 0.0102833257 0.0242115688 0.0044248545 0.7977240000 113206002 95654128 1783373824 0.0191164166 -0.0134250075 -0.0060001984 516 1311867735.8277759552 0.0040737689 0.0102712917 0.0242115688 0.0044267184 0.8349120000 113206896 95654128 1782345728 0.0196022764 -0.0116373533 -0.0070705628 517 1311867735.8638889790 0.0031517677 0.0102575208 0.0242115688 0.0044261626 0.8358620000 113209050 95654128 1783971840 0.0203258954 -0.0126657095 -0.0068168510 518 1311867735.8951849937 0.0034090595 0.0102442999 0.0242115688 0.0044237185 0.8163540000 113211236 95654128 1785749504 0.0202692747 -0.0120948618 -0.0068030339 519 1311867735.9322230816 0.0034975200 0.0102313003 0.0242115688 0.0044217621 0.8259920000 113212258 95654128 1784766464 0.0198508240 -0.0112356916 -0.0061034295 520 1311867735.9623689651 0.0037113442 0.0102187619 0.0242115688 0.0044210050 0.8068510000 113214412 95654128 1783607296 0.0205378197 -0.0114204492 -0.0059225610 521 1311867735.9945859909 0.0049519893 0.0102086529 0.0242115688 0.0044224898 0.8563500000 113216706 95654128 1785233408 0.0204142071 -0.0099967904 -0.0060769971 522 1311867736.0290079117 0.0052456446 0.0101991453 0.0242115688 0.0044198353 0.7628800000 113217696 95654128 1784250368 0.0210454054 -0.0098329084 -0.0054234061 523 1311867736.0642199516 0.0035663750 0.0101864631 0.0242115688 0.0044191137 0.8654910000 113219946 95654128 1783099392 0.0201416425 -0.0114255063 -0.0050475537 524 1311867736.0946779251 0.0036380370 0.0101739661 0.0242115688 0.0044160927 0.8074090000 113393132 95654128 1784725504 0.0198037736 -0.0113405408 -0.0050140289 525 1311867736.1299190521 0.0037045428 0.0101616434 0.0242115688 0.0044254773 0.7636040000 113394122 95654128 1783717888 0.0198903307 -0.0116502494 -0.0051271538 526 1311867736.1631360054 0.0041232761 0.0101501636 0.0242115688 0.0044260807 0.7956590000 113396604 95654128 1782865920 0.0201897603 -0.0115722772 -0.0048143184 527 1311867736.1942429543 0.0046289023 0.0101396868 0.0242115688 0.0044292464 0.8329310000 113398866 95654128 1784233984 0.0206046570 -0.0111583760 -0.0047822851 528 1311867736.2298679352 0.0047450485 0.0101294697 0.0242115688 0.0044330293 0.8285130000 113399856 95654128 1785995264 0.0196924172 -0.0110898744 -0.0048559392 529 1311867736.2633900642 0.0039849333 0.0101178543 0.0242115688 0.0044385579 0.8071190000 113402074 95654128 1784877056 0.0184190664 -0.0113805095 -0.0048882868 530 1311867736.2995250225 0.0021438790 0.0101028091 0.0242115688 0.0044349854 0.8734340000 113404324 95654128 1783734272 0.0181852337 -0.0135874022 -0.0039474228 531 1311867736.3304500580 0.0044923271 0.0100922432 0.0242115688 0.0044379615 1.0320580000 113405186 95654128 1785380864 0.0184132010 -0.0110981371 -0.0048375865 532 1311867736.3637149334 0.0024601426 0.0100778972 0.0242115688 0.0044352861 1.0494470000 113407404 95654128 1784377344 0.0177771505 -0.0133286696 -0.0046806172 533 1311867736.3943159580 0.0010584765 0.0100609752 0.0242115688 0.0044313995 1.0237690000 113408406 95654128 1783226368 0.0171880089 -0.0150678251 -0.0038230484 534 1311867736.4313519001 0.0027631966 0.0100473089 0.0242115688 0.0044469572 0.9558110000 113410720 95654128 1784999936 0.0169570073 -0.0125151267 -0.0053706532 535 1311867736.4625089169 0.0022582361 0.0100327499 0.0242115688 0.0044477171 1.0208970000 113412906 95654128 1783861248 0.0176480152 -0.0137605947 -0.0050299256 536 1311867736.4987530708 0.0031298306 0.0100198713 0.0242115688 0.0044439980 1.0146420000 113585248 95654128 1782845440 0.0189154577 -0.0143421823 -0.0042904820 537 1311867736.5321619511 0.0039363946 0.0100085427 0.0242115688 0.0044546700 1.0742020000 113587466 95654128 1784598528 0.0189346895 -0.0127861463 -0.0051732366 538 1311867736.5634689331 0.0036730501 0.0099967667 0.0242115688 0.0044529133 0.8415590000 113589652 95654128 1783603200 0.0186554827 -0.0132163567 -0.0053069578 539 1311867736.5958600044 0.0035353207 0.0099847788 0.0242115688 0.0044496639 0.8679490000 113590718 95654128 1782464512 0.0190831553 -0.0154808685 -0.0038095480 540 1311867736.6320459843 0.0026144674 0.0099711301 0.0242115688 0.0044583616 0.9011620000 113592968 95654128 1784090624 0.0182785690 -0.0144744255 -0.0051983437 541 1311867736.6635379791 0.0025158380 0.0099573495 0.0242115688 0.0044690547 0.7348450000 113595154 95654128 1785741312 0.0175488777 -0.0149269430 -0.0051938109 542 1311867736.6945500374 0.0029350410 0.0099443932 0.0242115688 0.0044680633 0.9159720000 113596016 95654128 1784766464 0.0176742580 -0.0156754702 -0.0041706115 543 1311867736.7332150936 0.0017333152 0.0099292716 0.0242115688 0.0044651678 0.9145460000 113598298 95654128 1783590912 0.0170467291 -0.0166921951 -0.0053594755 544 1311867736.7636179924 0.0025540532 0.0099157142 0.0242115688 0.0044673183 0.7746640000 113600484 95654128 1785249792 0.0183884352 -0.0161566082 -0.0063986094 545 1311867736.7952749729 0.0010392343 0.0098994271 0.0242115688 0.0044708599 0.8242810000 113601518 95654128 1784250368 0.0169935971 -0.0174925663 -0.0066611795 546 1311867736.8325269222 0.0026481263 0.0098861463 0.0242115688 0.0044745309 0.7905690000 113775356 95654128 1783226368 0.0174032431 -0.0158265624 -0.0074313898 547 1311867736.8640279770 0.0044740005 0.0098762520 0.0242115688 0.0044767534 0.8114760000 113777690 95654128 1784979456 0.0170448627 -0.0139561035 -0.0086995233 548 1311867736.8945000172 0.0024085529 0.0098626249 0.0242115688 0.0044748580 0.7786150000 113778552 95654128 1783992320 0.0157854389 -0.0162164085 -0.0076976432 549 1311867736.9362800121 0.0026918869 0.0098495634 0.0242115688 0.0044738468 0.7389920000 113780898 95654128 1782972416 0.0179567654 -0.0155894663 -0.0081140362 550 1311867736.9632000923 0.0070360950 0.0098444480 0.0242115688 0.0044775550 0.7567790000 113783020 95654128 1784598528 0.0194507018 -0.0113913091 -0.0090953205 551 1311867736.9954400063 0.0026692725 0.0098314259 0.0242115688 0.0044757276 0.6961150000 113784086 95654128 1783615488 0.0181608461 -0.0153385699 -0.0072292211 552 1311867737.0307478905 0.0019000027 0.0098170574 0.0242115688 0.0044730502 0.7570250000 113786304 95654128 1782345728 0.0164986365 -0.0164114423 -0.0069993767 553 1311867737.0629029274 0.0034670148 0.0098055745 0.0242115688 0.0044709399 0.8901440000 113787262 95654128 1783971840 0.0167758521 -0.0146542042 -0.0079321433 554 1311867737.0977239609 0.0022878884 0.0097920047 0.0242115688 0.0044708446 0.7987540000 113960200 95654128 1785622528 0.0158560891 -0.0167518891 -0.0078969486 555 1311867737.1300530434 0.0016346899 0.0097773068 0.0242115688 0.0044674581 0.7794370000 113962354 95654128 1784901632 0.0171288271 -0.0164362304 -0.0075048436 556 1311867737.1655049324 0.0032156645 0.0097655053 0.0242115688 0.0044638076 0.8516510000 113963344 95654128 1783742464 0.0197251514 -0.0155397728 -0.0083409427 557 1311867737.1952710152 0.0038913123 0.0097549592 0.0242115688 0.0044619734 0.8218450000 113965754 95654128 1785368576 0.0191251431 -0.0143915256 -0.0081721637 558 1311867737.2333149910 0.0032326828 0.0097432705 0.0242115688 0.0044587569 0.7518360000 113968068 95654128 1784385536 0.0181088466 -0.0149653805 -0.0084802546 559 1311867737.2693018913 0.0032103856 0.0097315838 0.0242115688 0.0044644090 0.8360860000 113969026 95654128 1783234560 0.0178110376 -0.0154990973 -0.0089350557 560 1311867737.2957379818 0.0035587894 0.0097205609 0.0242115688 0.0044609561 0.8933330000 113971116 95654128 1784852480 0.0195014514 -0.0150510920 -0.0091206199 561 1311867737.3316531181 0.0028868914 0.0097083797 0.0242115688 0.0044577004 0.7675280000 113973398 95654128 1783861248 0.0210526865 -0.0161102861 -0.0081378287 562 1311867737.3659460545 0.0053755739 0.0097006701 0.0242115688 0.0044576658 0.8852200000 113974324 95654128 1782718464 0.0209720414 -0.0132363886 -0.0079394877 563 1311867737.3967239857 0.0044836113 0.0096914035 0.0242115688 0.0044567893 0.8365660000 113976650 95654128 1784344576 0.0200139955 -0.0138910692 -0.0081045665 564 1311867737.4355359077 0.0043576178 0.0096819465 0.0242115688 0.0044530605 0.7958780000 114149332 95654128 1786011648 0.0195622984 -0.0139123201 -0.0076116957 565 1311867737.4691100121 0.0036721434 0.0096713096 0.0242115688 0.0044497927 0.8574100000 114150290 95654128 1785262080 0.0201411396 -0.0144672114 -0.0071133235 566 1311867737.4959459305 0.0050589694 0.0096631606 0.0242115688 0.0044469879 0.7964820000 114152496 95654128 1784115200 0.0207938291 -0.0132096885 -0.0065463656 567 1311867737.5353999138 0.0048570223 0.0096546842 0.0242115688 0.0044433932 0.9183280000 114154810 95654128 1785741312 0.0220167097 -0.0138215479 -0.0065232031 568 1311867737.5654399395 0.0060449974 0.0096483291 0.0242115688 0.0044411825 0.8719110000 114155672 95654128 1784766464 0.0223235656 -0.0122903232 -0.0064061759 569 1311867737.5958089828 0.0055174679 0.0096410692 0.0242115688 0.0044382549 0.8533640000 114157998 95654128 1783607296 0.0210322365 -0.0125320386 -0.0054007214 570 1311867737.6330978870 0.0068737669 0.0096362143 0.0242115688 0.0044347457 1.1192800000 114159020 95654128 1785233408 0.0219050962 -0.0113982633 -0.0054656691 571 1311867737.6624519825 0.0056584063 0.0096292479 0.0242115688 0.0044311838 1.0131010000 114161174 95654128 1784250368 0.0204265416 -0.0128690908 -0.0045856200 572 1311867737.7032339573 0.0063832775 0.0096235732 0.0242115688 0.0044293369 0.9513010000 114163456 95654128 1783209984 0.0194739029 -0.0130059626 -0.0034393487 573 1311867737.7314720154 0.0057989769 0.0096168985 0.0242115688 0.0044262734 0.8342230000 114164318 95654128 1784852480 0.0203428604 -0.0135856420 -0.0036050128 574 1311867737.7658560276 0.0064222640 0.0096113329 0.0242115688 0.0044225476 0.7854560000 114166536 95654128 1783734272 0.0216875859 -0.0126898130 -0.0046027834 575 1311867737.8011269569 0.0078786276 0.0096083195 0.0242115688 0.0044200071 0.8021440000 114169042 95654128 1782718464 0.0221878830 -0.0118405744 -0.0041277129 576 1311867737.8323190212 0.0064498838 0.0096028361 0.0242115688 0.0044174309 0.8951570000 114341400 95654128 1784344576 0.0209431369 -0.0136892889 -0.0032973723 577 1311867737.8633110523 0.0070604761 0.0095984300 0.0242115688 0.0044167718 0.9403180000 114343554 95654128 1783476224 0.0233691875 -0.0130643779 -0.0040309578 578 1311867737.9004418850 0.0060357451 0.0095922661 0.0242115688 0.0044131546 0.8137570000 114345772 95654128 1782210560 0.0239428319 -0.0143204043 -0.0029927788 579 1311867737.9305500984 0.0047650426 0.0095839290 0.0242115688 0.0044158570 0.8497420000 114346666 95654128 1783836672 0.0243890956 -0.0161470007 -0.0025504166 580 1311867737.9630560875 0.0040745372 0.0095744300 0.0242115688 0.0044140324 0.7957070000 114348884 95654128 1785614336 0.0248548724 -0.0168007594 -0.0024390479 581 1311867737.9996941090 0.0038623530 0.0095645986 0.0242115688 0.0044103084 0.9295850000 114351274 95654128 1784487936 0.0253963191 -0.0172321368 -0.0016083015 582 1311867738.0315399170 0.0063157175 0.0095590163 0.0242115688 0.0044132109 0.8609320000 114352200 95654128 1783480320 0.0266989022 -0.0148470821 -0.0009102364 583 1311867738.0629770756 0.0073936745 0.0095553021 0.0242115688 0.0044111161 0.8197810000 114354386 95654128 1785106432 0.0264490210 -0.0134855751 -0.0008011094 584 1311867738.0998299122 0.0068058441 0.0095505942 0.0242115688 0.0044076921 0.7966060000 114356604 95654128 1783971840 0.0268820450 -0.0143508064 -0.0000660974 585 1311867738.1308510303 0.0026929572 0.0095388717 0.0242115688 0.0044094047 1.0921650000 114357730 95654128 1782972416 0.0267357789 -0.0185894389 0.0014397586 586 1311867738.1635079384 0.0035613063 0.0095286711 0.0242115688 0.0044067232 1.0902490000 114359948 95654128 1784598528 0.0266341418 -0.0182540230 0.0030599367 587 1311867738.1992070675 0.0054235477 0.0095216777 0.0242115688 0.0044036508 0.8190920000 114532178 95654128 1783623680 0.0263078883 -0.0168485232 0.0032264069 588 1311867738.2306089401 0.0041411310 0.0095125271 0.0242115688 0.0044072239 0.8740850000 114534364 95654128 1782611968 0.0253787544 -0.0201706942 0.0038461830 589 1311867738.2632689476 0.0042293919 0.0095035574 0.0242115688 0.0044115617 0.7961900000 114536582 95654128 1784090624 0.0256813169 -0.0213168859 0.0045709028 590 1311867738.3008689880 0.0054443940 0.0094966775 0.0242115688 0.0044083832 0.8150810000 114537572 95654128 1785876480 0.0277545769 -0.0195555780 0.0049299644 591 1311867738.3339769840 0.0044762488 0.0094881827 0.0242115688 0.0044101608 0.7788050000 114539758 95654128 1784774656 0.0273398608 -0.0212579556 0.0040902724 592 1311867738.3651630878 0.0039094654 0.0094787592 0.0242115688 0.0044091302 0.8735250000 114541944 95654128 1783762944 0.0283566304 -0.0228536129 0.0040184669 593 1311867738.3995900154 0.0035310313 0.0094687293 0.0242115688 0.0044065451 0.8574290000 114543074 95654128 1785241600 0.0286114812 -0.0226707570 0.0028684130 594 1311867738.4334011078 0.0051168720 0.0094614029 0.0242115688 0.0044067368 0.8375200000 114716156 95654128 1784242176 0.0314574614 -0.0203011744 0.0024082833 595 1311867738.4643430710 0.0049703456 0.0094538549 0.0242115688 0.0044032237 0.9124910000 114718310 95654128 1783144448 0.0314039588 -0.0218371376 0.0037231529 596 1311867738.5000250340 0.0063693677 0.0094486796 0.0242115688 0.0044017537 0.8046730000 114719300 95654128 1784745984 0.0330095068 -0.0192367192 0.0026751854 597 1311867738.5332009792 0.0069248718 0.0094444521 0.0242115688 0.0044015723 0.8064400000 114721486 95654128 1783607296 0.0317813493 -0.0180915575 0.0018788127 598 1311867738.5634350777 0.0057283160 0.0094382379 0.0242115688 0.0043993162 1.0521030000 114723788 95654128 1782591488 0.0305483080 -0.0206649490 0.0027651526 599 1311867738.6022439003 0.0063037714 0.0094330050 0.0242115688 0.0043957337 0.9547340000 114724950 95654128 1784217600 0.0295585021 -0.0222879127 0.0033100629 600 1311867738.6328980923 0.0062952195 0.0094277754 0.0242115688 0.0043922527 1.0192340000 114727104 95654128 1785868288 0.0318605155 -0.0200346317 0.0021392778 601 1311867738.6628730297 0.0049631554 0.0094203467 0.0242115688 0.0043917158 0.9388620000 114729290 95654128 1784877056 0.0342330188 -0.0212496258 0.0023172824 602 1311867738.6996099949 0.0049519055 0.0094129241 0.0242115688 0.0043928885 0.8725180000 114730280 95654128 1783734272 0.0348254368 -0.0222322550 0.0025231147 603 1311867738.7314729691 0.0053364434 0.0094061637 0.0242115688 0.0044013236 1.0430870000 114732466 95654128 1785360384 0.0349030234 -0.0222395230 0.0019905677 604 1311867738.7626600266 0.0051346621 0.0093990917 0.0242115688 0.0044031940 0.8888210000 114904948 95654128 1784360960 0.0377531461 -0.0208897330 0.0008261632 605 1311867738.8032259941 0.0058751553 0.0093932670 0.0242115688 0.0044052029 0.9020580000 114906142 95654128 1783484416 0.0379230455 -0.0213790573 0.0019973554 606 1311867738.8306779861 0.0069136885 0.0093891753 0.0242115688 0.0044127720 0.8241860000 114908264 95654128 1784852480 0.0393809602 -0.0206643697 0.0026298042 607 1311867738.8639259338 0.0074074822 0.0093859106 0.0242115688 0.0044127596 0.7991870000 114909222 95654128 1783734272 0.0400246903 -0.0191053934 0.0011321602 608 1311867738.9000120163 0.0055273185 0.0093795642 0.0242115688 0.0044192810 0.8734530000 114911472 95654128 1782591488 0.0406780094 -0.0206950977 -0.0000710024 609 1311867738.9307610989 0.0062830108 0.0093744796 0.0242115688 0.0044202986 0.9510540000 114913626 95654128 1784365056 0.0392409377 -0.0221991856 0.0015151598 610 1311867738.9664750099 0.0061254064 0.0093691532 0.0242115688 0.0044176112 0.9390230000 114914616 95654128 1785995264 0.0410627350 -0.0209843274 0.0003973816 611 1311867738.9989941120 0.0067535653 0.0093648724 0.0242115688 0.0044164379 0.9589150000 114916974 95654128 1785004032 0.0429513752 -0.0208413005 0.0009498592 612 1311867739.0329539776 0.0061229006 0.0093595750 0.0242115688 0.0044142457 0.8106860000 114919192 95654128 1783861248 0.0419884957 -0.0239420384 0.0020315901 613 1311867739.0664470196 0.0053206952 0.0093529863 0.0242115688 0.0044117015 0.7978630000 114920118 95654128 1785487360 0.0431349613 -0.0239955243 0.0010932710 614 1311867739.0997900963 0.0056221667 0.0093469101 0.0242115688 0.0044089155 0.7589400000 115092708 95654128 1784369152 0.0444557741 -0.0222171210 -0.0001633796 615 1311867739.1321549416 0.0042971112 0.0093386990 0.0242115688 0.0044099229 0.9320530000 115094862 95654128 1783611392 0.0446948111 -0.0239548758 -0.0005309772 616 1311867739.1687150002 0.0045518600 0.0093309282 0.0242115688 0.0044083269 0.8506240000 115095852 95654128 1785126912 0.0448511429 -0.0236852244 -0.0007003258 617 1311867739.1999289989 0.0063872361 0.0093261572 0.0242115688 0.0044131667 0.9796670000 115098146 95654128 1783861248 0.0445374288 -0.0220188498 0.0000925704 618 1311867739.2313010693 0.0067014280 0.0093219101 0.0242115688 0.0044106540 0.8730290000 115100300 95654128 1782845440 0.0458318628 -0.0217490643 -0.0003369822 619 1311867739.2672259808 0.0070015993 0.0093181616 0.0242115688 0.0044090451 0.8700210000 115101322 95654128 1784471552 0.0459823832 -0.0223071203 0.0001496286 620 1311867739.2996931076 0.0080946321 0.0093161882 0.0242115688 0.0044154588 0.8042310000 115103508 95654128 1783492608 0.0459728949 -0.0223469827 0.0013635631 621 1311867739.3319859505 0.0082690520 0.0093145019 0.0242115688 0.0044183872 0.9505950000 115105694 95654128 1782337536 0.0445124060 -0.0214733910 0.0008759625 622 1311867739.3670029640 0.0086085256 0.0093133669 0.0242115688 0.0044205293 0.8176840000 115106652 95654128 1783980032 0.0438373759 -0.0213103518 0.0014811264 623 1311867739.3990058899 0.0081494302 0.0093114987 0.0242115688 0.0044173307 0.7759220000 115279630 95654128 1785741312 0.0421390235 -0.0230852868 0.0028009308 624 1311867739.4311320782 0.0077933427 0.0093090657 0.0242115688 0.0044169641 0.8970590000 115280524 95654128 1784868864 0.0428375714 -0.0218202434 0.0013290702 625 1311867739.4668490887 0.0062393639 0.0093041542 0.0242115688 0.0044163688 0.7563070000 115282774 95654128 1783742464 0.0442477539 -0.0235109162 0.0009651352 626 1311867739.4988598824 0.0056507187 0.0092983180 0.0242115688 0.0044195574 0.7926150000 115284960 95654128 1785368576 0.0434531681 -0.0248721447 0.0021668817 627 1311867739.5316400528 0.0063737817 0.0092936537 0.0242115688 0.0044163457 0.8401830000 115285854 95654128 1784369152 0.0445630439 -0.0229886919 0.0010395288 628 1311867739.5670249462 0.0085961884 0.0092925431 0.0242115688 0.0044163428 0.8144040000 115288104 95654128 1783988224 0.0448420867 -0.0208298638 0.0014861797 629 1311867739.5990490913 0.0070759468 0.0092890191 0.0242115688 0.0044129507 0.7769270000 115290430 95654128 1785655296 0.0438075438 -0.0235037562 0.0033246630 630 1311867739.6325490475 0.0088371504 0.0092883018 0.0242115688 0.0044102756 0.7586600000 115291388 95654128 1784877056 0.0443808474 -0.0209216010 0.0026141051 631 1311867739.6706740856 0.0077614104 0.0092858820 0.0242115688 0.0044084670 0.9707980000 115293670 95654128 1784369152 0.0417217016 -0.0229408182 0.0038515972 632 1311867739.7001221180 0.0061901775 0.0092809838 0.0242115688 0.0044061287 0.9151930000 115295824 95654128 1783627776 0.0409666561 -0.0249610990 0.0039402219 633 1311867739.7323939800 0.0092333341 0.0092809085 0.0242115688 0.0044145017 0.9850680000 115296750 95654128 1783353344 0.0421741605 -0.0207871869 0.0036902586 634 1311867739.7662999630 0.0089600869 0.0092804025 0.0242115688 0.0044118889 0.8769790000 115298968 95654128 1785012224 0.0430858731 -0.0213754810 0.0044245538 635 1311867739.8016180992 0.0079064481 0.0092782388 0.0242115688 0.0044092297 0.7608350000 115301358 95654128 1784233984 0.0428604372 -0.0234731697 0.0058735944 636 1311867739.8325679302 0.0105911158 0.0092803030 0.0242115688 0.0044196450 0.8903870000 115302252 95654128 1783853056 0.0425469652 -0.0202497132 0.0056372867 637 1311867739.8701560497 0.0096648159 0.0092809067 0.0242115688 0.0044176623 0.8015150000 115304502 95654128 1785503744 0.0408602729 -0.0214760061 0.0054842802 638 1311867739.9036860466 0.0088599799 0.0092802469 0.0242115688 0.0044144273 0.9361810000 115306752 95654128 1784635392 0.0387708880 -0.0241654310 0.0069943843 639 1311867739.9317240715 0.0094057648 0.0092804433 0.0242115688 0.0044121023 0.9296040000 115307614 95654128 1784254464 0.0387761928 -0.0230074748 0.0062359595 640 1311867739.9668979645 0.0113900276 0.0092837396 0.0242115688 0.0044089362 0.8753120000 115309832 95654128 1786032128 0.0418849960 -0.0201851986 0.0043946379 641 1311867739.9987080097 0.0096875448 0.0092843695 0.0242115688 0.0044067520 0.8421720000 115481258 95654128 1784995840 0.0381596275 -0.0225360598 0.0054200860 642 1311867740.0328791142 0.0099932291 0.0092854737 0.0242115688 0.0044075838 0.7741680000 115483476 95654128 1784762368 0.0355641395 -0.0239338782 0.0071640573 643 1311867740.0671849251 0.0135424649 0.0092920942 0.0242115688 0.0044092106 0.8959280000 115485662 95654128 1783873536 0.0369696207 -0.0185939167 0.0051740054 644 1311867740.0992529392 0.0099937338 0.0092931837 0.0242115688 0.0044191432 0.8562260000 115486620 95654128 1783492608 0.0367732383 -0.0224123262 0.0048265150 645 1311867740.1347720623 0.0080299210 0.0092912251 0.0242115688 0.0044171243 0.7335720000 115488806 95654128 1785270272 0.0344879441 -0.0272719339 0.0067397291 646 1311867740.1666491032 0.0100437514 0.0092923900 0.0242115688 0.0044193384 0.8766400000 115491024 95654128 1784365056 0.0362977348 -0.0229466669 0.0051974198 647 1311867740.1993310452 0.0119361561 0.0092964762 0.0242115688 0.0044173916 0.8936750000 115492122 95654128 1783730176 0.0367071927 -0.0203608219 0.0038188803 648 1311867740.2383539677 0.0110275559 0.0092991476 0.0242115688 0.0044151435 0.7722860000 115494436 95654128 1785417728 0.0336960852 -0.0230094381 0.0058956780 649 1311867740.2664349079 0.0108106984 0.0093014767 0.0242115688 0.0044134047 0.7367180000 115496526 95654128 1784385536 0.0345341675 -0.0222372394 0.0044424385 650 1311867740.2981588840 0.0119103044 0.0093054903 0.0242115688 0.0044122393 0.8568140000 115497452 95654128 1783750656 0.0345402695 -0.0204299111 0.0038855323 651 1311867740.3347120285 0.0113107096 0.0093085705 0.0242115688 0.0044098386 0.7348240000 115499734 95654128 1785507840 0.0341292359 -0.0214874782 0.0043968633 652 1311867740.3665161133 0.0129345395 0.0093141318 0.0242115688 0.0044120690 0.8528670000 115501888 95654128 1784365056 0.0353436172 -0.0197469182 0.0043032477 653 1311867740.3993780613 0.0129599636 0.0093197150 0.0242115688 0.0044096059 0.8344740000 115502954 95654128 1783730176 0.0354438685 -0.0194574241 0.0038219192 654 1311867740.4346680641 0.0135870753 0.0093262400 0.0242115688 0.0044083867 0.7482700000 115505204 95654128 1785417728 0.0368076675 -0.0184347425 0.0024017803 655 1311867740.4664289951 0.0148632033 0.0093346934 0.0242115688 0.0044096808 0.7451330000 115507390 95654128 1784381440 0.0372020490 -0.0173900723 0.0024015224 656 1311867740.4993040562 0.0159197524 0.0093447316 0.0242115688 0.0044092680 0.8775180000 115508316 95654128 1783730176 0.0380442552 -0.0167082213 0.0021451993 657 1311867740.5354259014 0.0145667139 0.0093526798 0.0242115688 0.0044138618 0.7317830000 115510566 95654128 1785544704 0.0382964797 -0.0177491941 0.0000483047 658 1311867740.5666589737 0.0132978270 0.0093586755 0.0242115688 0.0044109783 0.9227690000 115512752 95654128 1784385536 0.0361788943 -0.0186400712 -0.0003062290 659 1311867740.6008880138 0.0133847212 0.0093647848 0.0242115688 0.0044093667 0.7523700000 115513850 95654128 1783623680 0.0352731794 -0.0183634125 -0.0010792853 660 1311867740.6346809864 0.0123532861 0.0093693128 0.0242115688 0.0044098006 1.0517930000 115516068 95654128 1785401344 0.0347634591 -0.0192707274 -0.0015503705 661 1311867740.6665890217 0.0116276648 0.0093727294 0.0242115688 0.0044070929 1.0583730000 115516994 95654128 1784008704 0.0340373479 -0.0206080675 -0.0006539174 662 1311867740.6994900703 0.0116307018 0.0093761402 0.0242115688 0.0044073111 0.9789540000 115519180 95654128 1783377920 0.0329950489 -0.0209831037 -0.0012965485 663 1311867740.7368240356 0.0099476231 0.0093770022 0.0242115688 0.0044078553 0.8141750000 115521366 95654128 1785155584 0.0318590030 -0.0229421128 -0.0021773537 664 1311867740.7668819427 0.0110570090 0.0093795323 0.0242115688 0.0044074944 0.9315190000 115522260 95654128 1783750656 0.0323576815 -0.0213127881 -0.0034361924 665 1311867740.7996399403 0.0121958721 0.0093837674 0.0242115688 0.0044051017 0.7959190000 115524618 95654128 1782845440 0.0310168825 -0.0207741912 -0.0035628099 666 1311867740.8349099159 0.0108309248 0.0093859403 0.0242115688 0.0044033606 0.9161290000 115526804 95654128 1784598528 0.0319920778 -0.0215614904 -0.0047485875 667 1311867740.8668210506 0.0105086248 0.0093876235 0.0242115688 0.0044010926 0.7192190000 115699654 95654128 1783603200 0.0326589085 -0.0215946119 -0.0061667804 668 1311867740.8993830681 0.0112028494 0.0093903409 0.0242115688 0.0044007327 0.8343520000 115701840 95654128 1783009280 0.0307091791 -0.0223841053 -0.0039475807 669 1311867740.9399120808 0.0128818918 0.0093955600 0.0242115688 0.0044043075 0.8739870000 115704186 95654128 1784725504 0.0306599792 -0.0197102521 -0.0056701396 670 1311867740.9665501118 0.0123030869 0.0093998996 0.0242115688 0.0044017513 0.7190510000 115705016 95654128 1783750656 0.0313585214 -0.0202650968 -0.0064670644 671 1311867741.0021579266 0.0089833643 0.0093992788 0.0242115688 0.0044036127 0.9551920000 115707406 95654128 1782845440 0.0294938721 -0.0251021534 -0.0057543525 672 1311867741.0367169380 0.0093331477 0.0093991804 0.0242115688 0.0044013436 0.7573750000 115709624 95654128 1784598528 0.0297784321 -0.0242759734 -0.0066171340 673 1311867741.0666699409 0.0129297692 0.0094044264 0.0242115688 0.0044021070 0.7584310000 115710518 95654128 1783734272 0.0311326701 -0.0194831472 -0.0090040686 674 1311867741.1009640694 0.0095992209 0.0094047155 0.0242115688 0.0044064749 0.7557800000 115712736 95654128 1782845440 0.0283710174 -0.0240738615 -0.0076972763 675 1311867741.1357901096 0.0106283743 0.0094065283 0.0242115688 0.0044057558 0.7128180000 115714954 95654128 1784598528 0.0264940616 -0.0242246352 -0.0067525092 676 1311867741.1675300598 0.0113337515 0.0094093792 0.0242115688 0.0044027386 0.8362470000 115715896 95654128 1783623680 0.0271633919 -0.0225478224 -0.0086134691 677 1311867741.2014830112 0.0107881501 0.0094114158 0.0242115688 0.0044090853 0.9306760000 115718222 95654128 1782845440 0.0258920658 -0.0237543602 -0.0096998839 678 1311867741.2411060333 0.0077214609 0.0094089232 0.0242115688 0.0044191326 0.8348640000 115719276 95654128 1784598528 0.0272600744 -0.0274069756 -0.0100582661 679 1311867741.2668209076 0.0081059141 0.0094070042 0.0242115688 0.0044243667 0.7186500000 115721366 95654128 1783623680 0.0270052813 -0.0268675368 -0.0109350206 680 1311867741.2997009754 0.0118813487 0.0094106430 0.0242115688 0.0044276908 0.8378930000 115723552 95654128 1782845440 0.0250214003 -0.0230598971 -0.0113652172 681 1311867741.3348419666 0.0101180281 0.0094116817 0.0242115688 0.0044264976 1.0352720000 115724542 95654128 1784598528 0.0268563386 -0.0240787100 -0.0125338705 682 1311867741.3701419830 0.0132137863 0.0094172566 0.0242115688 0.0044292585 0.9792150000 115726760 95654128 1783623680 0.0271724779 -0.0201465003 -0.0129692722 683 1311867741.4066278934 0.0142525900 0.0094243362 0.0242115688 0.0044293501 1.0497730000 115729182 95654128 1782734848 0.0270858724 -0.0184087437 -0.0141743645 684 1311867741.4393060207 0.0128942346 0.0094294091 0.0242115688 0.0044336087 0.7771570000 115730140 95654128 1784492032 0.0282937251 -0.0193844792 -0.0140554560 685 1311867741.4667329788 0.0138671845 0.0094358877 0.0242115688 0.0044304282 0.8198220000 115732230 95654128 1786122240 0.0300626010 -0.0176726412 -0.0154347494 686 1311867741.5025069714 0.0150403287 0.0094440574 0.0242115688 0.0044279277 0.7559970000 115734480 95654128 1785131008 0.0307631623 -0.0161375385 -0.0159167256 687 1311867741.5368049145 0.0120397117 0.0094478356 0.0242115688 0.0044270525 0.7529970000 115735438 95654128 1784111104 0.0296629108 -0.0194936469 -0.0149258617 688 1311867741.5688209534 0.0143261580 0.0094549262 0.0242115688 0.0044252149 0.8351470000 115737624 95654128 1785868288 0.0304731242 -0.0166386254 -0.0157258045 689 1311867741.6046030521 0.0144960899 0.0094622429 0.0242115688 0.0044335861 0.8149090000 115739982 95654128 1784872960 0.0319763087 -0.0166318864 -0.0161610413 690 1311867741.6355440617 0.0119944010 0.0094659127 0.0242115688 0.0044332062 0.7535000000 115740908 95654128 1783861248 0.0317650661 -0.0193985961 -0.0156507324 691 1311867741.6679561138 0.0136557426 0.0094719761 0.0242115688 0.0044305514 0.6952700000 115743126 95654128 1785487360 0.0339848213 -0.0173743367 -0.0167027228 692 1311867741.7048020363 0.0130295046 0.0094771170 0.0242115688 0.0044316907 0.6967090000 115745392 95654128 1784508416 0.0333242863 -0.0178214554 -0.0167798735 693 1311867741.7345991135 0.0122179128 0.0094810720 0.0242115688 0.0044310889 0.8167490000 115746254 95654128 1783353344 0.0333652161 -0.0188372880 -0.0169012621 694 1311867741.7702169418 0.0110042682 0.0094832668 0.0242115688 0.0044283863 0.7347420000 115919176 95654128 1785126912 0.0348849781 -0.0200323481 -0.0174868703 695 1311867741.8058650494 0.0126775187 0.0094878628 0.0242115688 0.0044284328 0.7176580000 115920306 95654128 1784119296 0.0357464328 -0.0185177177 -0.0171232000 696 1311867741.8388509750 0.0138157001 0.0094940810 0.0242115688 0.0044268226 0.9524760000 115922556 95654128 1782972416 0.0359677263 -0.0174054764 -0.0179246161 697 1311867741.8683021069 0.0118589131 0.0094974739 0.0242115688 0.0044286269 0.7757390000 115924678 95654128 1784598528 0.0376646072 -0.0190190580 -0.0189677849 698 1311867741.9065721035 0.0122412629 0.0095014048 0.0242115688 0.0044281043 0.8144770000 115925700 95654128 1783734272 0.0374592990 -0.0189834312 -0.0179225206 699 1311867741.9387769699 0.0133558586 0.0095069190 0.0242115688 0.0044252415 0.7146650000 115927918 95654128 1782591488 0.0372766145 -0.0175526626 -0.0192427356 700 1311867741.9665379524 0.0121933362 0.0095107568 0.0242115688 0.0044241864 0.9579600000 115930008 95654128 1784373248 0.0374796987 -0.0187054537 -0.0201091133 701 1311867742.0029959679 0.0114997765 0.0095135942 0.0242115688 0.0044233254 0.7772660000 115931138 95654128 1786003456 0.0396327898 -0.0195436981 -0.0196529441 702 1311867742.0344839096 0.0115876365 0.0095165487 0.0242115688 0.0044209440 0.9346020000 115933292 95654128 1784995840 0.0404383726 -0.0192122553 -0.0205648579 703 1311867742.0674400330 0.0121053625 0.0095202312 0.0242115688 0.0044183126 0.7693970000 115935478 95654128 1783869440 0.0406077281 -0.0184943639 -0.0213372074 704 1311867742.1030650139 0.0120215714 0.0095237842 0.0242115688 0.0044155232 0.9582880000 115936436 95654128 1785495552 0.0422596149 -0.0180624649 -0.0222793762 705 1311867742.1348879337 0.0124153830 0.0095278858 0.0242115688 0.0044128386 1.0395420000 115938590 95654128 1784516608 0.0437848605 -0.0177456494 -0.0216614455 706 1311867742.1672229767 0.0122023961 0.0095316740 0.0242115688 0.0044118038 0.9914530000 115940808 95654128 1783500800 0.0453540348 -0.0177143831 -0.0222510230 707 1311867742.2028279305 0.0128873410 0.0095364204 0.0242115688 0.0044090012 1.0369870000 115941970 95654128 1785126912 0.0473043583 -0.0168272182 -0.0227000751 708 1311867742.2362670898 0.0124491872 0.0095405345 0.0242115688 0.0044069876 0.8976990000 115944156 95654128 1783988224 0.0469915494 -0.0169040225 -0.0236098431 709 1311867742.2674059868 0.0106229745 0.0095420612 0.0242115688 0.0044046776 1.0309190000 115946342 95654128 1782972416 0.0475034043 -0.0192058124 -0.0231124330 710 1311867742.3028159142 0.0104732141 0.0095433727 0.0242115688 0.0044049517 0.8400050000 115947332 95654128 1784471552 0.0473780371 -0.0199166778 -0.0229382031 711 1311867742.3350739479 0.0107856458 0.0095451199 0.0242115688 0.0044025788 0.9385570000 115949486 95654128 1783492608 0.0484989956 -0.0193581618 -0.0237877853 712 1311867742.3694241047 0.0108683482 0.0095469784 0.0242115688 0.0044026526 0.9741300000 115951736 95654128 1782337536 0.0469560400 -0.0199257545 -0.0231669080 713 1311867742.4062991142 0.0115540056 0.0095497933 0.0242115688 0.0044012154 0.9299920000 115952866 95654128 1783980032 0.0481252149 -0.0190904625 -0.0235934500 714 1311867742.4346439838 0.0107687265 0.0095515004 0.0242115688 0.0043985594 1.0186930000 115954988 95654128 1785741312 0.0487068072 -0.0197975151 -0.0243414044 715 1311867742.4666969776 0.0129460320 0.0095562480 0.0242115688 0.0043962142 0.8591310000 115955914 95654128 1784623104 0.0493544452 -0.0169630293 -0.0261182189 716 1311867742.5047059059 0.0121834921 0.0095599174 0.0242115688 0.0043937346 0.7323020000 115958164 95654128 1783607296 0.0490315780 -0.0179040376 -0.0259583555 717 1311867742.5359389782 0.0129436934 0.0095646367 0.0242115688 0.0043928221 0.7370090000 115960350 95654128 1785233408 0.0501121953 -0.0170525201 -0.0257326663 718 1311867742.5678529739 0.0154881850 0.0095728868 0.0242115688 0.0043903051 0.7177510000 115961308 95654128 1784229888 0.0502377301 -0.0140957171 -0.0266715810 719 1311867742.6054639816 0.0139261577 0.0095789414 0.0242115688 0.0043900043 1.0129960000 115963698 95654128 1783083008 0.0513496958 -0.0155858072 -0.0271822345 720 1311867742.6347279549 0.0131085897 0.0095838437 0.0242115688 0.0043876870 0.8582210000 115965820 95654128 1784725504 0.0527567565 -0.0166127328 -0.0272375364 721 1311867742.6724960804 0.0133032314 0.0095890024 0.0242115688 0.0043855853 0.7535500000 116136818 95654128 1783750656 0.0541025251 -0.0167495888 -0.0270060431 722 1311867742.7046229839 0.0125081167 0.0095930455 0.0242115688 0.0043829640 0.8346530000 116138972 95654128 1782738944 0.0523690507 -0.0176094286 -0.0266540479 723 1311867742.7356119156 0.0121517936 0.0095965845 0.0242115688 0.0043800977 0.7313460000 116141158 95654128 1784217600 0.0530790389 -0.0179055091 -0.0274508391 724 1311867742.7726070881 0.0126930214 0.0096008614 0.0242115688 0.0043770986 0.8593870000 116142180 95654128 1785995264 0.0535307899 -0.0177103654 -0.0273725428 725 1311867742.8034689426 0.0137423053 0.0096065737 0.0242115688 0.0043826388 0.6780740000 116144506 95654128 1784877056 0.0534494109 -0.0169333667 -0.0270956513 726 1311867742.8352251053 0.0137099167 0.0096122257 0.0242115688 0.0043799863 1.0085060000 116146660 95654128 1783734272 0.0546962023 -0.0171191655 -0.0276126862 727 1311867742.8705639839 0.0132946232 0.0096172909 0.0242115688 0.0043773617 0.8591640000 116147618 95654128 1785360384 0.0539510511 -0.0172683727 -0.0284355599 728 1311867742.9046700001 0.0119395107 0.0096204808 0.0242115688 0.0043779222 0.7976470000 116149836 95654128 1784377344 0.0526494831 -0.0187686365 -0.0284557566 729 1311867742.9382069111 0.0117409183 0.0096233894 0.0242115688 0.0044040372 0.8124830000 116152086 95654128 1783226368 0.0555227920 -0.0188542362 -0.0297385342 730 1311867742.9707310200 0.0125845242 0.0096274458 0.0242115688 0.0044061894 0.6912320000 116153012 95654128 1784852480 0.0558347218 -0.0179899186 -0.0298622288 731 1311867743.0024189949 0.0133735454 0.0096325704 0.0242115688 0.0044074118 0.7425000000 116155306 95654128 1783844864 0.0569138862 -0.0173416678 -0.0301584043 732 1311867743.0345149040 0.0159631614 0.0096412188 0.0242115688 0.0044151080 0.6928660000 116156232 95654128 1782718464 0.0569099449 -0.0143594863 -0.0301316734 733 1311867743.0722420216 0.0134056313 0.0096463544 0.0242115688 0.0044148602 0.8674980000 116158514 95654128 1784492032 0.0565748625 -0.0169610251 -0.0305865351 734 1311867743.1045989990 0.0144691318 0.0096529249 0.0242115688 0.0044158271 1.0221280000 116160700 95654128 1783365632 0.0567823276 -0.0160493925 -0.0303875003 735 1311867743.1350400448 0.0141652720 0.0096590642 0.0242115688 0.0044149370 0.7770200000 116161594 95654128 1782321152 0.0572246574 -0.0164318494 -0.0304971039 736 1311867743.1704380512 0.0122648505 0.0096626047 0.0242115688 0.0044223950 0.8353070000 116163812 95654128 1783963648 0.0589972548 -0.0191930570 -0.0305423643 737 1311867743.2037980556 0.0133495014 0.0096676072 0.0242115688 0.0044210704 1.0581170000 116166170 95654128 1785634816 0.0596476421 -0.0177026466 -0.0312779956 738 1311867743.2358140945 0.0122772632 0.0096711433 0.0242115688 0.0044228171 0.8297890000 116167064 95654128 1784487936 0.0600855201 -0.0185969993 -0.0323542841 739 1311867743.2708129883 0.0135353804 0.0096763724 0.0242115688 0.0044220708 1.0186720000 116169314 95654128 1783463936 0.0600513816 -0.0172806848 -0.0316085368 740 1311867743.3032529354 0.0149355372 0.0096834793 0.0242115688 0.0044475869 0.8534910000 116171500 95654128 1785135104 0.0588911027 -0.0158588048 -0.0305417459 741 1311867743.3363931179 0.0147297196 0.0096902894 0.0242115688 0.0044461676 0.7782710000 116172426 95654128 1783980032 0.0589972548 -0.0157114100 -0.0312719382 742 1311867743.3707330227 0.0146985399 0.0096970390 0.0242115688 0.0044438017 0.9158190000 116174644 95654128 1782853632 0.0594191477 -0.0156327188 -0.0317478143 743 1311867743.4043838978 0.0133522879 0.0097019586 0.0242115688 0.0044418883 1.0165900000 116177002 95654128 1784496128 0.0598584861 -0.0171367340 -0.0319026373 744 1311867743.4352641106 0.0123329628 0.0097054949 0.0242115688 0.0044495253 0.6930870000 116177928 95654128 1783500800 0.0609067455 -0.0187315512 -0.0319800526 745 1311867743.4768960476 0.0127322134 0.0097095576 0.0242115688 0.0044494179 0.7781120000 116180242 95654128 1782345728 0.0613013208 -0.0184803661 -0.0317171067 746 1311867743.5035250187 0.0129742175 0.0097139338 0.0242115688 0.0044484580 0.9694530000 116182364 95654128 1783980032 0.0595646799 -0.0175499264 -0.0314753391 747 1311867743.5389750004 0.0134796938 0.0097189750 0.0242115688 0.0044469860 0.9389410000 116183322 95654128 1785741312 0.0596095473 -0.0169611033 -0.0320292711 748 1311867743.5749680996 0.0133594563 0.0097238420 0.0242115688 0.0044465203 0.9205020000 116185572 95654128 1784745984 0.0601980016 -0.0167795923 -0.0328182243 749 1311867743.6036109924 0.0148541788 0.0097306916 0.0242115688 0.0044508846 1.1732030000 116186574 95654128 1783607296 0.0604571812 -0.0150375571 -0.0330805779 750 1311867743.6354589462 0.0136245005 0.0097358833 0.0242115688 0.0044520928 0.9123820000 116188760 95654128 1785233408 0.0609739982 -0.0168043524 -0.0332056805 751 1311867743.6759150028 0.0115101114 0.0097382458 0.0242115688 0.0044521422 0.6763650000 116361022 95654128 1784131584 0.0587795153 -0.0191329196 -0.0319929048 752 1311867743.7034959793 0.0127138477 0.0097422027 0.0242115688 0.0044511237 0.6916280000 116361884 95654128 1783246848 0.0610258766 -0.0182811413 -0.0331874788 753 1311867743.7388861179 0.0131074507 0.0097466718 0.0242115688 0.0044493248 0.8385300000 116364134 95654128 1784725504 0.0612510331 -0.0181465317 -0.0338498764 754 1311867743.7733619213 0.0119090080 0.0097495396 0.0242115688 0.0044468115 0.8005270000 116366384 95654128 1783623680 0.0594907068 -0.0191519558 -0.0339044519 755 1311867743.8064749241 0.0127170486 0.0097534701 0.0242115688 0.0044445663 0.9316990000 116367418 95654128 1782464512 0.0591198616 -0.0182924140 -0.0346611217 756 1311867743.8391659260 0.0138648506 0.0097589085 0.0242115688 0.0044460914 0.8710620000 116369604 95654128 1784090624 0.0575124435 -0.0174770281 -0.0339624174 757 1311867743.8726658821 0.0122562414 0.0097622074 0.0242115688 0.0044434596 0.7590610000 116371854 95654128 1785757696 0.0572222918 -0.0203167908 -0.0325579904 758 1311867743.9031310081 0.0128774475 0.0097663173 0.0242115688 0.0044415990 0.7728580000 116372748 95654128 1784766464 0.0568807609 -0.0184353478 -0.0354081653 759 1311867743.9453630447 0.0125441002 0.0097699771 0.0242115688 0.0044414568 0.6925650000 116375094 95654128 1783734272 0.0583483279 -0.0192168821 -0.0363911688 760 1311867743.9741249084 0.0125230746 0.0097735995 0.0242115688 0.0044430410 0.6533480000 116377216 95654128 1785360384 0.0585391372 -0.0194181576 -0.0359290801 761 1311867744.0042529106 0.0166894663 0.0097826874 0.0242115688 0.0044454843 0.9451650000 116378218 95654128 1784360960 0.0596057437 -0.0148224737 -0.0370585732 762 1311867744.0407259464 0.0137276985 0.0097878646 0.0242115688 0.0044492965 0.9539070000 116380500 95654128 1783226368 0.0585638732 -0.0178922098 -0.0362407453 763 1311867744.0716118813 0.0143108945 0.0097937925 0.0242115688 0.0044465735 0.9535480000 116382654 95654128 1784852480 0.0591165945 -0.0171753615 -0.0371299721 764 1311867744.1111290455 0.0140575562 0.0097993734 0.0242115688 0.0044441426 0.9397630000 116383612 95654128 1783861248 0.0582402125 -0.0173167624 -0.0362675190 765 1311867744.1412119865 0.0155512830 0.0098068922 0.0242115688 0.0044425252 0.9511000000 116385766 95654128 1782718464 0.0585582666 -0.0154395252 -0.0365063921 766 1311867744.1734991074 0.0161575731 0.0098151829 0.0242115688 0.0044407205 0.9951630000 116387984 95654128 1784344576 0.0589850619 -0.0143294381 -0.0374902859 767 1311867744.2046771049 0.0145227350 0.0098213206 0.0242115688 0.0044438338 0.7518770000 116389018 95654128 1785995264 0.0590454303 -0.0161272828 -0.0368919410 768 1311867744.2400228977 0.0137290470 0.0098264087 0.0242115688 0.0044427643 0.8429700000 116391300 95654128 1784987648 0.0597670525 -0.0174623765 -0.0356650613 769 1311867744.2773048878 0.0158553924 0.0098342488 0.0242115688 0.0044421622 0.7737080000 116392290 95654128 1783861248 0.0594916567 -0.0143958749 -0.0367966741 770 1311867744.3032519817 0.0142473560 0.0098399801 0.0242115688 0.0044402870 0.8883640000 116394496 95654128 1785487360 0.0569642968 -0.0163251739 -0.0342750102 771 1311867744.3391230106 0.0109042656 0.0098413605 0.0242115688 0.0044484255 0.9650960000 116396746 95654128 1784487936 0.0573273525 -0.0199018046 -0.0346937962 772 1311867744.3707659245 0.0140128108 0.0098467639 0.0242115688 0.0044482119 1.0102950000 116397640 95654128 1783353344 0.0578599498 -0.0160472784 -0.0351087414 773 1311867744.4027431011 0.0141097717 0.0098522788 0.0242115688 0.0044468518 0.8326520000 116399998 95654128 1784979456 0.0579935722 -0.0156695917 -0.0354368873 774 1311867744.4383800030 0.0118829580 0.0098549024 0.0242115688 0.0044452618 0.8186960000 116402216 95654128 1783971840 0.0581644550 -0.0183835886 -0.0353187621 775 1311867744.4717690945 0.0120119192 0.0098576857 0.0242115688 0.0044453504 0.6534810000 116403174 95654128 1782845440 0.0563692003 -0.0184512343 -0.0344227962 776 1311867744.5026860237 0.0122578768 0.0098607787 0.0242115688 0.0044427471 0.9330820000 116405360 95654128 1784471552 0.0585062280 -0.0173706971 -0.0364572927 777 1311867744.5383169651 0.0119087081 0.0098634144 0.0242115688 0.0044422165 0.9160970000 116407610 95654128 1786269696 0.0578694008 -0.0181919839 -0.0355021134 778 1311867744.5726189613 0.0122573096 0.0098664914 0.0242115688 0.0044398493 0.7762330000 116408568 95654128 1785114624 0.0568475164 -0.0181284063 -0.0348910205 779 1311867744.6028740406 0.0129882265 0.0098704987 0.0242115688 0.0044403101 0.9168870000 116410862 95654128 1784139776 0.0569559932 -0.0167865045 -0.0356565937 780 1311867744.6386809349 0.0136295483 0.0098753180 0.0242115688 0.0044444433 0.8131280000 116413112 95654128 1785769984 0.0592846870 -0.0160782803 -0.0368064307 781 1311867744.6707758904 0.0136531452 0.0098801552 0.0242115688 0.0044416961 0.7997920000 116414038 95654128 1784643584 0.0588225201 -0.0161176678 -0.0361165032 782 1311867744.7029349804 0.0127940765 0.0098838814 0.0242115688 0.0044442004 0.8337310000 116416224 95654128 1783615488 0.0588516332 -0.0168295112 -0.0361216702 783 1311867744.7396171093 0.0159401428 0.0098916161 0.0242115688 0.0044511007 0.7678110000 116418474 95654128 1785262080 0.0587860942 -0.0133321788 -0.0360214859 784 1311867744.7705199718 0.0146022849 0.0098976246 0.0242115688 0.0044517085 0.7403890000 116419368 95654128 1784111104 0.0614237264 -0.0151917860 -0.0371044986 785 1311867744.8035891056 0.0123914517 0.0099008015 0.0242115688 0.0044570466 0.6929350000 116421726 95654128 1783107584 0.0596979372 -0.0175565649 -0.0361400507 786 1311867744.8424170017 0.0122931367 0.0099038452 0.0242115688 0.0044543950 0.8373270000 116422748 95654128 1784733696 0.0596545711 -0.0177848656 -0.0362716056 787 1311867744.8727390766 0.0122670690 0.0099068480 0.0242115688 0.0044558524 0.9970840000 116424934 95654128 1783734272 0.0599133819 -0.0180621445 -0.0371867493 788 1311867744.9029939175 0.0130802030 0.0099108751 0.0242115688 0.0044565245 0.9727880000 116427088 95654128 1782591488 0.0561325848 -0.0177813303 -0.0355587192 789 1311867744.9392940998 0.0119054094 0.0099134030 0.0242115688 0.0044606172 0.7660800000 116428110 95654128 1784217600 0.0590604581 -0.0180557799 -0.0384352840 790 1311867744.9708900452 0.0146474186 0.0099193954 0.0242115688 0.0044644442 0.8565600000 116430232 95654128 1785868288 0.0583962239 -0.0152497021 -0.0384756662 791 1311867745.0027489662 0.0126353102 0.0099228290 0.0242115688 0.0044705856 0.7613550000 116432558 95654128 1784893440 0.0594861656 -0.0177234616 -0.0390403643 792 1311867745.0384869576 0.0124532003 0.0099260239 0.0242115688 0.0044695352 0.7123120000 116433548 95654128 1783734272 0.0595170707 -0.0180894714 -0.0398566537 793 1311867745.0729780197 0.0126420856 0.0099294489 0.0242115688 0.0044685935 0.8361240000 116435766 95654128 1785360384 0.0592439137 -0.0183175951 -0.0398366079 794 1311867745.1118760109 0.0135008655 0.0099339469 0.0242115688 0.0044753198 0.9112310000 116438048 95654128 1784229888 0.0599289574 -0.0178538337 -0.0394775085 795 1311867745.1405589581 0.0133566298 0.0099382522 0.0242115688 0.0044729869 0.7320510000 116438910 95654128 1783226368 0.0589608401 -0.0173286758 -0.0404699519 796 1311867745.1729030609 0.0122193936 0.0099411179 0.0242115688 0.0044725692 0.6782590000 116441096 95654128 1784852480 0.0600199252 -0.0186642185 -0.0415133797 797 1311867745.2068369389 0.0122117363 0.0099439669 0.0242115688 0.0044708518 0.6938980000 116443454 95654128 1783750656 0.0590025932 -0.0192759205 -0.0401344933 798 1311867745.2430789471 0.0126306694 0.0099473337 0.0242115688 0.0044685093 0.6582560000 116444444 95654128 1782702080 0.0609858297 -0.0182895791 -0.0426755138 799 1311867745.2729060650 0.0150252990 0.0099536891 0.0242115688 0.0044750987 0.7762590000 116446598 95654128 1784344576 0.0591898710 -0.0155403186 -0.0414517596 800 1311867745.3112850189 0.0121696871 0.0099564591 0.0242115688 0.0044764831 1.0576470000 116448848 95654128 1785995264 0.0582977161 -0.0185366813 -0.0418706834 801 1311867745.3395059109 0.0121415984 0.0099591871 0.0242115688 0.0044737089 0.9297270000 116449742 95654128 1785004032 0.0586136281 -0.0188773852 -0.0419804789 802 1311867745.3733940125 0.0122501291 0.0099620436 0.0242115688 0.0044713598 0.7762650000 116451960 95654128 1783861248 0.0581902005 -0.0184465516 -0.0427739844 803 1311867745.4102098942 0.0127354367 0.0099654974 0.0242115688 0.0044695583 0.8941840000 116453090 95654128 1785487360 0.0590636954 -0.0180850029 -0.0432644486 804 1311867745.4433169365 0.0138414446 0.0099703183 0.0242115688 0.0044680215 0.7768980000 116455308 95654128 1784487936 0.0591939427 -0.0170459561 -0.0432665721 805 1311867745.4708619118 0.0137555087 0.0099750204 0.0242115688 0.0044659442 0.8156740000 116457398 95654128 1783353344 0.0607668571 -0.0171062592 -0.0445165448 806 1311867745.5099780560 0.0150031885 0.0099812588 0.0242115688 0.0044635059 0.9120140000 116458452 95654128 1784979456 0.0610909127 -0.0159781445 -0.0442486182 807 1311867745.5417380333 0.0129266232 0.0099849085 0.0242115688 0.0044668271 0.7582540000 116460638 95654128 1783971840 0.0592291504 -0.0176818073 -0.0453099757 808 1311867745.5704059601 0.0106051518 0.0099856762 0.0242115688 0.0044649792 0.6505350000 116462760 95654128 1782845440 0.0587663613 -0.0208293013 -0.0453620069 809 1311867745.6133821011 0.0119801452 0.0099881415 0.0242115688 0.0044629286 0.7787910000 116464018 95654128 1784471552 0.0588220246 -0.0198274888 -0.0459139943 810 1311867745.6438291073 0.0134258466 0.0099923856 0.0242115688 0.0044631181 0.9570930000 116466204 95654128 1783476224 0.0594438724 -0.0178699922 -0.0473891981 811 1311867745.6709001064 0.0137595953 0.0099970307 0.0242115688 0.0044719049 0.9126660000 116468262 95654128 1782337536 0.0590384677 -0.0176211968 -0.0471910760 812 1311867745.7088780403 0.0131942872 0.0100009683 0.0242115688 0.0044724890 0.8354470000 116469316 95654128 1783963648 0.0609408878 -0.0179939494 -0.0490180738 813 1311867745.7423269749 0.0135918427 0.0100053851 0.0242115688 0.0044726791 0.8128370000 116471502 95654128 1785741312 0.0619814210 -0.0177070778 -0.0500746332 814 1311867745.7760419846 0.0140015353 0.0100102943 0.0242115688 0.0044739849 0.9348840000 116473720 95654128 1784623104 0.0598208494 -0.0169027597 -0.0490563549 815 1311867745.8116889000 0.0145831853 0.0100159053 0.0242115688 0.0044784082 0.9583830000 116644594 95654128 1783607296 0.0608289652 -0.0160001591 -0.0497926101 816 1311867745.8389890194 0.0159163810 0.0100231362 0.0242115688 0.0044825633 0.9932850000 116646716 95654128 1785360384 0.0587284118 -0.0139285373 -0.0498700738 817 1311867745.8709759712 0.0143631687 0.0100284484 0.0242115688 0.0044817790 0.9168090000 116648870 95654128 1784377344 0.0607041866 -0.0156002790 -0.0514031090 818 1311867745.9108459949 0.0141371218 0.0100334712 0.0242115688 0.0044844862 1.0898990000 116649924 95654128 1783226368 0.0593187213 -0.0149252228 -0.0535611622 819 1311867745.9435789585 0.0148795564 0.0100393883 0.0242115688 0.0044851935 0.8348890000 116652142 95654128 1784852480 0.0583853200 -0.0143180648 -0.0542347357 820 1311867745.9732220173 0.0135846129 0.0100437117 0.0242115688 0.0044830432 0.7587030000 116654264 95654128 1783853056 0.0592925474 -0.0158398710 -0.0548111908 821 1311867746.0083909035 0.0136569645 0.0100481128 0.0242115688 0.0044808165 0.6937680000 116655362 95654128 1782726656 0.0581628829 -0.0157296546 -0.0559924133 822 1311867746.0391409397 0.0132394154 0.0100519951 0.0242115688 0.0044790808 0.7950560000 116657580 95654128 1784352768 0.0569680706 -0.0163336117 -0.0566593558 823 1311867746.0728518963 0.0137548996 0.0100564944 0.0242115688 0.0044767336 0.8959990000 116658506 95654128 1786150912 0.0576945692 -0.0157843791 -0.0585035682 824 1311867746.1113359928 0.0166488662 0.0100644949 0.0242115688 0.0044752567 0.8563600000 116660756 95654128 1785012224 0.0582608692 -0.0129855536 -0.0599510819 825 1311867746.1412689686 0.0160658583 0.0100717692 0.0242115688 0.0044725602 0.8723640000 116662942 95654128 1783996416 0.0569221824 -0.0138541711 -0.0609388798 826 1311867746.1721889973 0.0160626285 0.0100790221 0.0242115688 0.0044710139 0.6899840000 116663836 95654128 1785643008 0.0564492680 -0.0140193123 -0.0616030991 827 1311867746.2066209316 0.0198316388 0.0100908149 0.0242115688 0.0044690387 0.6373090000 116666194 95654128 1784496128 0.0575009026 -0.0108520463 -0.0656407177 828 1311867746.2386920452 0.0182575416 0.0101006781 0.0242115688 0.0044670322 0.8536980000 116668412 95654128 1783488512 0.0576273985 -0.0126649197 -0.0649514198 829 1311867746.2704648972 0.0178890973 0.0101100730 0.0242115688 0.0044652694 0.8376640000 116669338 95654128 1785126912 0.0559232831 -0.0140765011 -0.0667079017 830 1311867746.3068819046 0.0228217021 0.0101253882 0.0242115688 0.0044693438 0.7427150000 116671556 95654128 1783971840 0.0587508865 -0.0107994024 -0.0712169930 831 1311867746.3393440247 0.0275321621 0.0101463350 0.0275321621 0.0044689531 0.7324870000 116673774 95654128 1782972416 0.0608248040 -0.0056162286 -0.0705277771 832 1311867746.3797800541 0.0275869835 0.0101672973 0.0275869835 0.0044702591 0.7892980000 116844572 95654128 1784619008 0.0632611066 -0.0055964203 -0.0669895485 833 1311867746.4078478813 0.0204689410 0.0101796643 0.0275869835 0.0044878486 0.9652370000 116846834 95654128 1783734272 0.0642347559 -0.0133451223 -0.0664535537 834 1311867746.4389901161 0.0304312482 0.0102039467 0.0304312482 0.0045043368 0.8526350000 116848988 95654128 1782591488 0.0653548911 -0.0040594209 -0.0698181763 835 1311867746.4774639606 0.0324261859 0.0102305602 0.0324261859 0.0045038064 0.8493490000 116850042 95654128 1784233984 0.0672112554 -0.0024586054 -0.0689913034 836 1311867746.5066781044 0.0315217003 0.0102560281 0.0324261859 0.0045013617 0.8405180000 116852164 95654128 1785995264 0.0677252784 -0.0033792485 -0.0683073699 837 1311867746.5406761169 0.0331293605 0.0102833558 0.0331293605 0.0044988697 1.0383650000 116854382 95654128 1784987648 0.0673379824 -0.0022597644 -0.0705717802 838 1311867746.5748629570 0.0330688581 0.0103105462 0.0331293605 0.0044979748 0.9161260000 116855372 95654128 1783861248 0.0679878071 -0.0022215161 -0.0687181428 839 1311867746.6067559719 0.0321309231 0.0103365538 0.0331293605 0.0045001600 0.8260810000 116857666 95654128 1785487360 0.0668716878 -0.0035136924 -0.0707189366 840 1311867746.6396849155 0.0324187204 0.0103628421 0.0331293605 0.0045030980 0.8240650000 116858656 95654128 1784508416 0.0668084696 -0.0033580919 -0.0714198053 841 1311867746.6749529839 0.0302219260 0.0103864557 0.0331293605 0.0045066569 0.9922390000 116860874 95654128 1783353344 0.0653759614 -0.0056602331 -0.0709580779 842 1311867746.7095060349 0.0292470492 0.0104088555 0.0331293605 0.0045050911 0.8552250000 116863092 95654128 1784979456 0.0636811852 -0.0065265703 -0.0713627636 843 1311867746.7391049862 0.0278924815 0.0104295952 0.0331293605 0.0045054338 0.8726840000 116863954 95654128 1783844864 0.0628641024 -0.0078426935 -0.0707359463 844 1311867746.7751340866 0.0280977581 0.0104505291 0.0331293605 0.0045033549 0.8337240000 116866236 95654128 1782829056 0.0615198910 -0.0075437827 -0.0707563087 845 1311867746.8070099354 0.0267425813 0.0104698096 0.0331293605 0.0045023704 0.8792120000 116868562 95654128 1784360960 0.0626063198 -0.0098317675 -0.0717058852 846 1311867746.8401610851 0.0277471654 0.0104902320 0.0331293605 0.0045000079 0.8374240000 116869488 95654128 1783365632 0.0625455454 -0.0092955111 -0.0722980350 847 1311867746.8748359680 0.0247829407 0.0105071065 0.0331293605 0.0045007855 0.7765300000 116871738 95654128 1782210560 0.0626393855 -0.0121501423 -0.0718011037 848 1311867746.9086029530 0.0283141937 0.0105281054 0.0331293605 0.0044996816 0.7882960000 116873924 95654128 1783836672 0.0634962842 -0.0090664811 -0.0732519105 849 1311867746.9389610291 0.0277104825 0.0105483438 0.0331293605 0.0045000108 0.8633860000 116874850 95654128 1785614336 0.0641855896 -0.0092705237 -0.0712691098 850 1311867746.9748229980 0.0218290444 0.0105616152 0.0331293605 0.0045341277 0.7536320000 116877100 95654128 1784487936 0.0632311478 -0.0146657806 -0.0701528341 851 1311867747.0066559315 0.0277214423 0.0105817795 0.0331293605 0.0045583041 0.6906890000 116879394 95654128 1783480320 0.0648643672 -0.0099335946 -0.0726622567 852 1311867747.0389339924 0.0258652605 0.0105997179 0.0331293605 0.0045582051 0.7155250000 116880320 95654128 1785106432 0.0635496676 -0.0115805687 -0.0723545477 853 1311867747.0749640465 0.0264291968 0.0106182753 0.0331293605 0.0045560260 0.7794550000 116882602 95654128 1783988224 0.0648243800 -0.0108570717 -0.0720292702 854 1311867747.1066820621 0.0283715557 0.0106390637 0.0331293605 0.0045670548 0.7363130000 116884756 95654128 1782972416 0.0649969876 -0.0083601214 -0.0715085343 855 1311867747.1389479637 0.0297417268 0.0106614060 0.0331293605 0.0045661542 0.7953190000 116885682 95654128 1784598528 0.0663143396 -0.0069045825 -0.0709070638 856 1311867747.1744880676 0.0299063362 0.0106838884 0.0331293605 0.0045638494 0.7728350000 116887932 95654128 1783492608 0.0657322928 -0.0068182852 -0.0710612684 857 1311867747.2066030502 0.0232169088 0.0106985127 0.0331293605 0.0045766392 0.8133730000 116888998 95654128 1782464512 0.0651188046 -0.0135798855 -0.0700530782 858 1311867747.2385439873 0.0275882240 0.0107181977 0.0331293605 0.0045755750 0.7942780000 116891216 95654128 1784090624 0.0657781661 -0.0091593843 -0.0719003230 859 1311867747.2745490074 0.0290452726 0.0107395330 0.0331293605 0.0046006718 1.0081690000 116893466 95654128 1785741312 0.0661173463 -0.0080926288 -0.0721342191 860 1311867747.3064720631 0.0296281464 0.0107614965 0.0331293605 0.0046097669 0.9852130000 116894328 95654128 1784766464 0.0661450624 -0.0071006883 -0.0723226070 861 1311867747.3388469219 0.0258544739 0.0107790261 0.0331293605 0.0046219445 0.8546140000 116896578 95654128 1783623680 0.0660346895 -0.0115293283 -0.0722515360 862 1311867747.3758800030 0.0283408668 0.0107993995 0.0331293605 0.0046224495 0.8282520000 116898796 95654128 1785241600 0.0675501823 -0.0091335168 -0.0731360838 863 1311867747.4068729877 0.0298734829 0.0108215016 0.0331293605 0.0046206404 0.7617180000 116899862 95654128 1784258560 0.0681208670 -0.0082065286 -0.0742722005 864 1311867747.4396450520 0.0297492910 0.0108434087 0.0331293605 0.0046265568 0.8687710000 116902016 95654128 1783218176 0.0672080740 -0.0073855571 -0.0737725496 865 1311867747.4756069183 0.0266832244 0.0108617206 0.0331293605 0.0046290985 0.8349820000 116904266 95654128 1784881152 0.0669233054 -0.0107637970 -0.0742379129 866 1311867747.5095520020 0.0291711558 0.0108828632 0.0331293605 0.0046294605 0.8624240000 116905256 95654128 1783742464 0.0667448044 -0.0081984792 -0.0746713355 867 1311867747.5405330658 0.0308913458 0.0109059410 0.0331293605 0.0046525268 1.0120660000 116907410 95654128 1782718464 0.0694940984 -0.0092073362 -0.0800424516 868 1311867747.5766739845 0.0292921029 0.0109271232 0.0331293605 0.0046674099 0.8104060000 116909660 95654128 1784344576 0.0683365762 -0.0085702250 -0.0763564259 869 1311867747.6086390018 0.0292864703 0.0109482502 0.0331293605 0.0046651915 1.1148570000 116910726 95654128 1785868288 0.0676211268 -0.0083724828 -0.0761304423 870 1311867747.6432039738 0.0296447519 0.0109697404 0.0331293605 0.0046627264 0.8560930000 116912976 95654128 1785004032 0.0682644993 -0.0083399033 -0.0767163411 871 1311867747.6760280132 0.0327830724 0.0109947844 0.0331293605 0.0046682138 0.9065170000 116915162 95654128 1783861248 0.0691310465 -0.0060413759 -0.0790240765 872 1311867747.7068400383 0.0294830296 0.0110159866 0.0331293605 0.0046675612 0.8588070000 116916056 95654128 1785487360 0.0666373745 -0.0083523402 -0.0771678537 873 1311867747.7480750084 0.0310942829 0.0110389858 0.0331293605 0.0046808031 0.8882110000 116918466 95654128 1785520128 0.0673794746 -0.0085472260 -0.0815106630 874 1311867747.7826869488 0.0276095308 0.0110579452 0.0331293605 0.0046893954 0.9578330000 116920684 95654128 1784623104 0.0644960627 -0.0089434050 -0.0753062144 875 1311867747.8149020672 0.0257768910 0.0110747668 0.0331293605 0.0047057879 0.9476130000 116921750 95654128 1786294272 0.0651886687 -0.0120482864 -0.0775851831 876 1311867747.8466539383 0.0323053636 0.0110990027 0.0331293605 0.0047135398 0.7951550000 116923904 95654128 1784750080 0.0656159073 -0.0063840291 -0.0814908817 877 1311867747.8827810287 0.0313022509 0.0111220395 0.0331293605 0.0047138275 0.7931330000 116924926 95654128 1783861248 0.0649166852 -0.0070117642 -0.0814573094 878 1311867747.9150440693 0.0301544275 0.0111437164 0.0331293605 0.0047126114 0.6143550000 116927144 95654128 1785532416 0.0655744374 -0.0078821331 -0.0802646801 879 1311867747.9477820396 0.0299235452 0.0111650814 0.0331293605 0.0047123449 0.9386950000 116929330 95654128 1783975936 0.0618648715 -0.0070519601 -0.0798695609 880 1311867747.9826579094 0.0302730724 0.0111867951 0.0331293605 0.0047141994 0.7561920000 116930288 95654128 1783083008 0.0642081350 -0.0080083348 -0.0810417309 881 1311867748.0146598816 0.0313259289 0.0112096545 0.0331293605 0.0047124986 0.7718100000 116932614 95654128 1784770560 0.0645710230 -0.0067668464 -0.0802902952 882 1311867748.0469269753 0.0304276850 0.0112314436 0.0331293605 0.0047106687 1.0388930000 116934800 95654128 1786269696 0.0612688251 -0.0063758278 -0.0786787122 883 1311867748.0828750134 0.0308339074 0.0112536435 0.0331293605 0.0047088468 1.0798560000 116935822 95654128 1785008128 0.0611875504 -0.0059647849 -0.0786562711 884 1311867748.1150569916 0.0299908649 0.0112748394 0.0331293605 0.0047071527 0.9463500000 116937976 95654128 1784115200 0.0613717884 -0.0067750872 -0.0781694725 885 1311867748.1486010551 0.0287664160 0.0112946039 0.0331293605 0.0047063253 0.7948590000 116940194 95654128 1785769984 0.0613903962 -0.0078807585 -0.0778066665 886 1311867748.1831040382 0.0295474734 0.0113152053 0.0331293605 0.0047421877 0.8306950000 116941120 95654128 1784254464 0.0599696860 -0.0045471778 -0.0730067790 887 1311867748.2148320675 0.0306540169 0.0113370078 0.0331293605 0.0047689940 0.8769950000 116943478 95654128 1783353344 0.0598252825 -0.0047431062 -0.0769853741 888 1311867748.2466599941 0.0299449582 0.0113579627 0.0331293605 0.0047753760 0.9976140000 116945632 95654128 1785024512 0.0591680743 -0.0041623064 -0.0749032423 889 1311867748.2827599049 0.0284805428 0.0113772232 0.0331293605 0.0047768187 0.8149180000 116946622 95654128 1783480320 0.0604388267 -0.0069170003 -0.0766590014 890 1311867748.3148829937 0.0272693150 0.0113950795 0.0331293605 0.0047775955 0.7930650000 116948808 95654128 1782591488 0.0595375560 -0.0077240439 -0.0750050992 891 1311867748.3470869064 0.0273401663 0.0114129752 0.0331293605 0.0047808650 0.6944530000 116950994 95654128 1784262656 0.0587033331 -0.0074879010 -0.0755898878 892 1311867748.3826999664 0.0294940267 0.0114332455 0.0331293605 0.0047787507 0.8931270000 116951984 95654128 1785741312 0.0575750098 -0.0052933395 -0.0765232146 893 1311867748.4148259163 0.0280505233 0.0114518538 0.0331293605 0.0047768082 0.9603790000 116954278 95654128 1784512512 0.0566361360 -0.0066028363 -0.0757395923 894 1311867748.4520189762 0.0259803664 0.0114681050 0.0331293605 0.0047896542 0.9952740000 116955300 95654128 1783607296 0.0574568808 -0.0086400323 -0.0746622011 895 1311867748.4831318855 0.0292482749 0.0114879711 0.0331293605 0.0047876194 0.8663780000 116957486 95654128 1785262080 0.0577230901 -0.0051591881 -0.0752753466 896 1311867748.5149960518 0.0295557305 0.0115081360 0.0331293605 0.0047869450 0.8568220000 116959672 95654128 1783607296 0.0592840314 -0.0055841664 -0.0748601407 897 1311867748.5467929840 0.0271849297 0.0115256129 0.0331293605 0.0047847530 0.8711990000 116960566 95654128 1782845440 0.0566313043 -0.0063115633 -0.0728923008 898 1311867748.5827159882 0.0289165583 0.0115449792 0.0331293605 0.0047870130 0.7947350000 116962816 95654128 1784500224 0.0595815741 -0.0057218899 -0.0744788572 899 1311867748.6147999763 0.0267930720 0.0115619404 0.0331293605 0.0047904641 0.7368310000 116965174 95654128 1785868288 0.0561653264 -0.0062385323 -0.0723378211 900 1311867748.6470849514 0.0270879529 0.0115791915 0.0331293605 0.0048151089 0.7782440000 116966068 95654128 1784631296 0.0559831969 -0.0066915415 -0.0728468746 901 1311867748.6827559471 0.0267068315 0.0115959813 0.0331293605 0.0048141667 0.7892520000 116968318 95654128 1783742464 0.0569857806 -0.0076376535 -0.0732792541 902 1311867748.7147359848 0.0240316261 0.0116097681 0.0331293605 0.0048497812 0.8933520000 116970504 95654128 1785413632 0.0549766496 -0.0083318045 -0.0705784187 903 1311867748.7499361038 0.0259441193 0.0116256422 0.0331293605 0.0048475361 0.9139940000 116971462 95654128 1783873536 0.0544125959 -0.0065601524 -0.0712023675 904 1311867748.7828259468 0.0262828227 0.0116418559 0.0331293605 0.0048449333 0.9170080000 116973712 95654128 1782980608 0.0541464053 -0.0063946643 -0.0712781772 905 1311867748.8151619434 0.0255809613 0.0116572583 0.0331293605 0.0048438114 0.7716410000 116976038 95654128 1784606720 0.0536709018 -0.0075824056 -0.0721282959 906 1311867748.8466329575 0.0249187704 0.0116718957 0.0331293605 0.0048430221 0.7195940000 116976900 95654128 1783611392 0.0522890836 -0.0074355467 -0.0703460872 907 1311867748.8829579353 0.0260157231 0.0116877103 0.0331293605 0.0048406931 1.2307680000 116979150 95654128 1782718464 0.0528698713 -0.0072897077 -0.0709015876 908 1311867748.9149119854 0.0255131386 0.0117029365 0.0331293605 0.0048394572 0.9109940000 116981368 95654128 1784389632 0.0510515533 -0.0073509021 -0.0696571246 909 1311867748.9472498894 0.0239470191 0.0117164063 0.0331293605 0.0048370057 0.8884950000 116982294 95654128 1785741312 0.0503984913 -0.0085482467 -0.0683145225 910 1311867748.9829359055 0.0270098802 0.0117332124 0.0331293605 0.0048361119 1.0012960000 116984544 95654128 1784639488 0.0523945093 -0.0063600289 -0.0699975193 911 1311867749.0159859657 0.0253908560 0.0117482043 0.0331293605 0.0048348026 0.9953820000 116985610 95654128 1783627776 0.0493925139 -0.0069481074 -0.0680387095 912 1311867749.0467190742 0.0254661050 0.0117632458 0.0331293605 0.0048326485 0.8304360000 116987764 95654128 1785233408 0.0503987633 -0.0062547536 -0.0669674948 913 1311867749.0828969479 0.0267433077 0.0117796534 0.0331293605 0.0048300766 0.7560060000 116990014 95654128 1784119296 0.0504172780 -0.0052941088 -0.0672809556 914 1311867749.1158421040 0.0283309780 0.0117977620 0.0331293605 0.0048276237 0.9359880000 116990972 95654128 1783353344 0.0503787920 -0.0038472456 -0.0685138106 915 1311867749.1485249996 0.0260664038 0.0118133562 0.0331293605 0.0048265727 0.8149160000 116993190 95654128 1785008128 0.0511185750 -0.0061434871 -0.0677913055 916 1311867749.1829619408 0.0259136744 0.0118287495 0.0331293605 0.0048251534 0.8587050000 116995408 95654128 1783480320 0.0505397283 -0.0057124593 -0.0664929450 917 1311867749.2156000137 0.0262064543 0.0118444286 0.0331293605 0.0048226581 0.7935470000 116996442 95654128 1782591488 0.0491035432 -0.0052335039 -0.0665635690 918 1311867749.2468719482 0.0256167464 0.0118594311 0.0331293605 0.0048210030 0.7134980000 116998596 95654128 1784262656 0.0485490300 -0.0052762362 -0.0652387217 919 1311867749.2828478813 0.0255327914 0.0118743096 0.0331293605 0.0048224611 0.8924750000 117000846 95654128 1785761792 0.0496410616 -0.0051667057 -0.0641382784 920 1311867749.3148140907 0.0269518401 0.0118906983 0.0331293605 0.0048208965 0.7578000000 117001804 95654128 1784512512 0.0487984568 -0.0041283322 -0.0652546585 921 1311867749.3468968868 0.0259181578 0.0119059290 0.0331293605 0.0048185613 0.8368320000 117003958 95654128 1783607296 0.0495318882 -0.0050131204 -0.0644827411 922 1311867749.3828470707 0.0264707841 0.0119217260 0.0331293605 0.0048160036 0.8146230000 117006208 95654128 1785131008 0.0484224893 -0.0043448638 -0.0647815093 923 1311867749.4147930145 0.0264786165 0.0119374973 0.0331293605 0.0048136903 0.8380730000 117007306 95654128 1783607296 0.0462437160 -0.0039915191 -0.0644873381 924 1311867749.4467489719 0.0258991737 0.0119526073 0.0331293605 0.0048111423 0.8298890000 117009460 95654128 1782992896 0.0459072627 -0.0036851454 -0.0631753951 925 1311867749.4829080105 0.0236322135 0.0119652339 0.0331293605 0.0048109706 0.9364930000 117011710 95654128 1784619008 0.0485743880 -0.0062028384 -0.0629218742 926 1311867749.5159850121 0.0223374125 0.0119764350 0.0331293605 0.0048112124 0.8557710000 117012636 95654128 1783382016 0.0471281372 -0.0064883144 -0.0604732595 927 1311867749.5468530655 0.0227253567 0.0119880303 0.0331293605 0.0048089451 0.8949940000 117014822 95654128 1782591488 0.0463343151 -0.0058498043 -0.0599314868 928 1311867749.5830268860 0.0217682067 0.0119985693 0.0331293605 0.0048065458 0.9703000000 117017072 95654128 1784262656 0.0450684540 -0.0066312975 -0.0589855723 929 1311867749.6148250103 0.0221960749 0.0120095462 0.0331293605 0.0048041974 0.8964810000 117018106 95654128 1785614336 0.0452112444 -0.0068221777 -0.0598202087 930 1311867749.6469049454 0.0211058874 0.0120193272 0.0331293605 0.0048027077 0.8409290000 117020324 95654128 1784381440 0.0455093458 -0.0075641191 -0.0588515364 931 1311867749.6829149723 0.0202121940 0.0120281273 0.0331293605 0.0048027754 0.8339020000 117021314 95654128 1783480320 0.0428779945 -0.0079551106 -0.0564133115 932 1311867749.7160799503 0.0206573773 0.0120373861 0.0331293605 0.0048002244 0.8718300000 117023500 95654128 1785131008 0.0423616171 -0.0075953235 -0.0563858747 933 1311867749.7468609810 0.0224838927 0.0120485828 0.0331293605 0.0048000955 0.8609830000 117025686 95654128 1783607296 0.0420924723 -0.0057869088 -0.0572784692 934 1311867749.7828791142 0.0213490874 0.0120585405 0.0331293605 0.0047988788 0.8886780000 117026676 95654128 1782992896 0.0428031720 -0.0072948160 -0.0572625361 935 1311867749.8148949146 0.0223468151 0.0120695440 0.0331293605 0.0048056632 0.7155360000 117028970 95654128 1784598528 0.0420217961 -0.0068398239 -0.0586483702 936 1311867749.8469030857 0.0210616086 0.0120791509 0.0331293605 0.0048055336 0.6529790000 117031188 95654128 1783603200 0.0390580744 -0.0074222242 -0.0568704344 937 1311867749.8829030991 0.0220455714 0.0120897874 0.0331293605 0.0048201980 0.8637590000 117032178 95654128 1782718464 0.0403407440 -0.0061236727 -0.0563337840 938 1311867749.9149639606 0.0237666517 0.0121022361 0.0331293605 0.0048369686 0.7582900000 117034332 95654128 1784389632 0.0391911082 -0.0046448489 -0.0567727238 939 1311867749.9508709908 0.0230253693 0.0121138689 0.0331293605 0.0048345787 0.8395210000 117036582 95654128 1785757696 0.0394753627 -0.0053962371 -0.0569498166 940 1311867749.9827940464 0.0226928703 0.0121251231 0.0331293605 0.0048344165 0.7793400000 117037540 95654128 1784631296 0.0392709076 -0.0055347737 -0.0557469279 941 1311867750.0147750378 0.0224721339 0.0121361189 0.0331293605 0.0048323955 0.8557820000 117039866 95654128 1783742464 0.0370552428 -0.0056287893 -0.0556438789 942 1311867750.0470709801 0.0208750609 0.0121453959 0.0331293605 0.0048302177 0.7531000000 117042052 95654128 1785368576 0.0377771631 -0.0071823704 -0.0552653894 943 1311867750.0829339027 0.0215020329 0.0121553181 0.0331293605 0.0048281295 0.7194140000 117043042 95654128 1784360960 0.0375705138 -0.0064516468 -0.0548703782 944 1311867750.1156458855 0.0207378287 0.0121644097 0.0331293605 0.0048273487 0.9337790000 117045228 95654128 1783234560 0.0349902175 -0.0070635350 -0.0538621061 945 1311867750.1474790573 0.0222935639 0.0121751284 0.0331293605 0.0048263735 0.9158190000 117047414 95654128 1784905728 0.0370442308 -0.0054652561 -0.0548193380 946 1311867750.1828711033 0.0215941556 0.0121850851 0.0331293605 0.0048242445 0.8931860000 117048404 95654128 1783377920 0.0348579772 -0.0057693743 -0.0534614697 947 1311867750.2156589031 0.0221231580 0.0121955794 0.0331293605 0.0048221785 0.8938480000 117050730 95654128 1782218752 0.0357006565 -0.0050738924 -0.0529243909 948 1311867750.2469079494 0.0218449477 0.0122057580 0.0331293605 0.0048203292 0.8166330000 117051624 95654128 1783881728 0.0356062762 -0.0051125200 -0.0530769713 949 1311867750.2829968929 0.0224854108 0.0122165901 0.0331293605 0.0048191938 0.9135600000 117053874 95654128 1785233408 0.0356762297 -0.0040542390 -0.0530561395 950 1311867750.3150129318 0.0205842834 0.0122253982 0.0331293605 0.0048174568 0.7535740000 117056092 95654128 1783975936 0.0343255661 -0.0053434847 -0.0508763269 951 1311867750.3469090462 0.0192926694 0.0122328296 0.0331293605 0.0048167908 0.6351040000 117056986 95654128 1783099392 0.0348498113 -0.0064162607 -0.0506495610 952 1311867750.3828659058 0.0189335439 0.0122398682 0.0331293605 0.0048145198 0.6970410000 117059236 95654128 1784750080 0.0328994319 -0.0064605754 -0.0501288585 953 1311867750.4148640633 0.0193535816 0.0122473327 0.0331293605 0.0048132753 1.0845190000 117061594 95654128 1783238656 0.0335909501 -0.0057930187 -0.0483218320 954 1311867750.4469859600 0.0188759863 0.0122542810 0.0331293605 0.0048119301 0.8884770000 117062488 95654128 1782337536 0.0336743146 -0.0063744998 -0.0476623811 955 1311867750.4829618931 0.0197322909 0.0122621114 0.0331293605 0.0048100145 0.8786550000 117064706 95654128 1784119296 0.0332254283 -0.0054533691 -0.0495025218 956 1311867750.5148859024 0.0199101474 0.0122701114 0.0331293605 0.0048076880 0.8343290000 117066860 95654128 1785487360 0.0325181335 -0.0052340883 -0.0478173532 957 1311867750.5476069450 0.0205104761 0.0122787220 0.0331293605 0.0048060032 0.7778360000 117067818 95654128 1784233984 0.0331065655 -0.0044299588 -0.0472816639 958 1311867750.5827779770 0.0208972469 0.0122877184 0.0331293605 0.0048059737 0.8124450000 117070068 95654128 1783353344 0.0322637297 -0.0039709704 -0.0486594737 959 1311867750.6148829460 0.0201200638 0.0122958856 0.0331293605 0.0048034986 0.8749820000 117072362 95654128 1784979456 0.0317271277 -0.0043848413 -0.0486806817 960 1311867750.6469810009 0.0216505453 0.0123056301 0.0331293605 0.0048012737 0.8963110000 117243296 95654128 1784119296 0.0325004831 -0.0026350799 -0.0486481674 961 1311867750.6829319000 0.0206778925 0.0123143421 0.0331293605 0.0047989715 0.7940900000 117245546 95654128 1782972416 0.0323096812 -0.0032181086 -0.0484722517 962 1311867750.7149219513 0.0193722807 0.0123216788 0.0331293605 0.0047981138 0.8572180000 117247764 95654128 1784643584 0.0316177420 -0.0042929067 -0.0480160564 963 1311867750.7469151020 0.0189926587 0.0123286061 0.0331293605 0.0047999860 0.8528260000 117248658 95654128 1786011648 0.0295395814 -0.0047246525 -0.0452417359 964 1311867750.7832129002 0.0190914683 0.0123356215 0.0331293605 0.0047979329 1.0024320000 117250876 95654128 1784860672 0.0301409848 -0.0042965077 -0.0462244749 965 1311867750.8149549961 0.0195267107 0.0123430734 0.0331293605 0.0047961215 0.9700510000 117251878 95654128 1783988224 0.0306263473 -0.0035162864 -0.0468749925 966 1311867750.8468461037 0.0190394968 0.0123500056 0.0331293605 0.0047946142 0.9532900000 117254064 95654128 1785643008 0.0307355672 -0.0032329303 -0.0452232547 967 1311867750.8828840256 0.0195869952 0.0123574895 0.0331293605 0.0047922634 0.9771730000 117256346 95654128 1784123392 0.0298040826 -0.0025541824 -0.0443623997 968 1311867750.9147970676 0.0199388657 0.0123653215 0.0331293605 0.0047915966 0.9508040000 117257240 95654128 1783226368 0.0293429699 -0.0019678480 -0.0437128171 969 1311867750.9468770027 0.0184535123 0.0123716045 0.0331293605 0.0047911060 0.8141940000 117259426 95654128 1784897536 0.0298991464 -0.0027711974 -0.0429126918 970 1311867750.9830369949 0.0169137791 0.0123762871 0.0331293605 0.0047887004 0.8525300000 117261708 95654128 1783480320 0.0293889083 -0.0043945913 -0.0406366512 971 1311867751.0168409348 0.0168995671 0.0123809455 0.0331293605 0.0047868670 0.9174650000 117262806 95654128 1782591488 0.0303449985 -0.0041261679 -0.0412698314 972 1311867751.0470340252 0.0176633243 0.0123863800 0.0331293605 0.0047850885 0.8931910000 117264960 95654128 1784262656 0.0278496686 -0.0034861863 -0.0413323194 973 1311867751.0828599930 0.0180392973 0.0123921898 0.0331293605 0.0047837430 0.8999660000 117267178 95654128 1785614336 0.0290537868 -0.0028603410 -0.0424622670 974 1311867751.1174809933 0.0168799069 0.0123967973 0.0331293605 0.0047826543 0.9342820000 117268168 95654128 1784369152 0.0272039473 -0.0044124536 -0.0407117307 975 1311867751.1468789577 0.0188857559 0.0124034527 0.0331293605 0.0047808733 0.9553080000 117270290 95654128 1783754752 0.0279823840 -0.0023190754 -0.0426918715 976 1311867751.1835930347 0.0189219173 0.0124101314 0.0331293605 0.0047823255 0.9341620000 117442688 95654128 1785360384 0.0287941918 -0.0018819064 -0.0441118702 977 1311867751.2161049843 0.0179809667 0.0124158334 0.0331293605 0.0047841157 0.8836100000 117443754 95654128 1784250368 0.0255587287 -0.0032042135 -0.0411804952 978 1311867751.2468481064 0.0181284491 0.0124216745 0.0331293605 0.0047834135 0.9918620000 117445908 95654128 1783500800 0.0281984303 -0.0026815399 -0.0424977876 979 1311867751.2831909657 0.0205211397 0.0124299477 0.0331293605 0.0047845399 1.1952210000 117448190 95654128 1784987648 0.0285839681 0.0001854354 -0.0447098874 980 1311867751.3149859905 0.0163312647 0.0124339287 0.0331293605 0.0047826444 1.0614540000 117449084 95654128 1783869440 0.0262981933 -0.0040163081 -0.0418109894 981 1311867751.3498640060 0.0170118380 0.0124385953 0.0331293605 0.0047809558 0.9233920000 117451334 95654128 1782853632 0.0270366687 -0.0032166967 -0.0405494608 982 1311867751.3834669590 0.0195444450 0.0124458314 0.0331293605 0.0047812534 0.7998320000 117453552 95654128 1784606720 0.0275658406 -0.0007526360 -0.0438942611 983 1311867751.4151160717 0.0181278251 0.0124516116 0.0331293605 0.0047813275 0.6354090000 117454618 95654128 1783627776 0.0269129109 -0.0022883310 -0.0432925113 984 1311867751.4513890743 0.0152232274 0.0124544283 0.0331293605 0.0047831598 0.7971140000 117456836 95654128 1782599680 0.0256775692 -0.0052138302 -0.0406610034 985 1311867751.4838130474 0.0183040034 0.0124603669 0.0331293605 0.0047811322 0.8969270000 117457794 95654128 1784352768 0.0261093769 -0.0019314624 -0.0424113125 986 1311867751.5149779320 0.0194312427 0.0124674368 0.0331293605 0.0047796083 0.9542330000 117459980 95654128 1786003456 0.0275875926 -0.0004907558 -0.0432653949 987 1311867751.5495769978 0.0191876348 0.0124742455 0.0331293605 0.0047772544 0.8157700000 117462198 95654128 1785131008 0.0269082095 -0.0007793471 -0.0428693295 988 1311867751.5829720497 0.0198019762 0.0124816622 0.0331293605 0.0047754861 0.7515220000 117463124 95654128 1784242176 0.0266942866 -0.0003911305 -0.0438081399 989 1311867751.6149520874 0.0190282650 0.0124882817 0.0331293605 0.0047740422 0.9602250000 117465450 95654128 1785995264 0.0260143746 -0.0011007172 -0.0428265296 990 1311867751.6501350403 0.0173976477 0.0124932406 0.0331293605 0.0047730431 1.0105730000 117467668 95654128 1785020416 0.0262792632 -0.0024627619 -0.0419873036 991 1311867751.6839730740 0.0177675821 0.0124985629 0.0331293605 0.0047710152 0.9066300000 117468658 95654128 1783988224 0.0264437776 -0.0020327489 -0.0419207662 992 1311867751.7150709629 0.0168858357 0.0125029855 0.0331293605 0.0047691387 0.8111160000 117470780 95654128 1785643008 0.0250259582 -0.0029588430 -0.0411802046 993 1311867751.7507519722 0.0166994575 0.0125072116 0.0331293605 0.0047669785 1.0874600000 117473030 95654128 1784123392 0.0266247839 -0.0029712673 -0.0407205448 994 1311867751.7830109596 0.0172008071 0.0125119335 0.0331293605 0.0047648158 0.8498120000 117473956 95654128 1783226368 0.0258078631 -0.0023872652 -0.0405163430 995 1311867751.8149600029 0.0184831787 0.0125179347 0.0331293605 0.0047646585 1.0748270000 117646726 95654128 1784877056 0.0266546644 -0.0014728538 -0.0409935415 996 1311867751.8509531021 0.0193071682 0.0125247512 0.0331293605 0.0047624558 0.8528090000 117648976 95654128 1783627776 0.0263974443 -0.0002550604 -0.0403620824 997 1311867751.8832330704 0.0175166279 0.0125297581 0.0331293605 0.0047608745 0.8162440000 117649902 95654128 1782464512 0.0247591678 -0.0023249497 -0.0392524786 998 1311867751.9149179459 0.0189350452 0.0125361763 0.0331293605 0.0047627462 1.0575980000 117652056 95654128 1784115200 0.0265520439 -0.0003184313 -0.0401796177 999 1311867751.9530611038 0.0177775975 0.0125414229 0.0331293605 0.0047608022 1.1679120000 117654370 95654128 1785634816 0.0263848156 -0.0008657543 -0.0400227979 1000 1311867751.9829521179 0.0174508449 0.0125463324 0.0331293605 0.0047612786 0.9240310000 117655264 95654128 1784365056 0.0244799722 -0.0010132610 -0.0388090089 1001 1311867752.0153670311 0.0185699034 0.0125523499 0.0331293605 0.0047597858 0.9484670000 117657558 95654128 1783345152 0.0264655724 0.0002399260 -0.0401134379 1002 1311867752.0510330200 0.0169372391 0.0125567260 0.0331293605 0.0047574248 0.8119800000 117658548 95654128 1784971264 0.0257908795 -0.0009347511 -0.0392128937 1003 1311867752.0828928947 0.0159038976 0.0125600632 0.0331293605 0.0047551686 0.8758700000 117660766 95654128 1783963648 0.0236573759 -0.0018936655 -0.0377446450 1004 1311867752.1150529385 0.0166114811 0.0125640985 0.0331293605 0.0047535632 0.9296610000 117832764 95654128 1782964224 0.0249713510 -0.0008594119 -0.0380432643 1005 1311867752.1509859562 0.0155320447 0.0125670517 0.0331293605 0.0047522781 0.9028000000 117833754 95654128 1784614912 0.0247108229 -0.0015151154 -0.0380140729 1006 1311867752.1829679012 0.0156092541 0.0125700757 0.0331293605 0.0047504919 0.7967690000 117835972 95654128 1783357440 0.0232053567 -0.0010300842 -0.0369091518 1007 1311867752.2150039673 0.0155308507 0.0125730159 0.0331293605 0.0047485526 0.8705060000 117838298 95654128 1782583296 0.0238710102 -0.0006061364 -0.0371911749 1008 1311867752.2512340546 0.0160054024 0.0125764211 0.0331293605 0.0047486868 0.7537730000 117839256 95654128 1784336384 0.0238264799 0.0005361775 -0.0374369211 1009 1311867752.2833271027 0.0149802389 0.0125788034 0.0331293605 0.0047475241 0.9958480000 117841442 95654128 1786134528 0.0216068123 -0.0000379891 -0.0362954885 1010 1311867752.3150799274 0.0153121781 0.0125815097 0.0331293605 0.0047468122 0.8729610000 117843596 95654128 1785122816 0.0230858475 0.0001831587 -0.0368194170 1011 1311867752.3509979248 0.0125736604 0.0125815020 0.0331293605 0.0047451230 0.8387910000 117844586 95654128 1784233984 0.0226017833 -0.0019530862 -0.0360093489 1012 1311867752.3829851151 0.0118241841 0.0125807536 0.0331293605 0.0047432791 0.9939260000 117846804 95654128 1785987072 0.0225359034 -0.0028808140 -0.0360297821 1013 1311867752.4160280228 0.0128832832 0.0125810523 0.0331293605 0.0047412281 1.0026270000 117849130 95654128 1785122816 0.0242326818 -0.0019639861 -0.0369302891 1014 1311867752.4510710239 0.0129489908 0.0125814152 0.0331293605 0.0047466592 0.8854520000 117850120 95654128 1784233984 0.0254974160 -0.0023069829 -0.0368161462 1015 1311867752.4829080105 0.0140809258 0.0125828925 0.0331293605 0.0047488947 0.9316720000 117852306 95654128 1785987072 0.0235235337 -0.0006950562 -0.0360360779 1016 1311867752.5181159973 0.0766752884 0.0126459756 0.0766752884 0.0055084563 2.1151460000 118022840 95654128 1785520128 -0.0481787920 0.0128506655 -0.0263393708 1017 1311867752.5511059761 0.0653483868 0.0126977970 0.0766752884 0.0055380132 1.2119990000 118137058 95654128 1784623104 -0.0350791886 0.0146778580 -0.0273417141 1018 1311867752.5830090046 0.0636851713 0.0127478828 0.0766752884 0.0055369178 0.9924020000 118139340 95654128 1786294272 -0.0328110307 0.0153439632 -0.0262679197 1019 1311867752.6167891026 0.0647463351 0.0127989117 0.0766752884 0.0055346066 0.8740010000 118140330 95654128 1784750080 -0.0336281992 0.0157628730 -0.0253710430 1020 1311867752.6514921188 0.0642812923 0.0128493847 0.0766752884 0.0055343572 0.8751290000 118142612 95654128 1783861248 -0.0331700817 0.0156291276 -0.0259291958 1021 1311867752.6830079556 0.0652885139 0.0129007452 0.0766752884 0.0055357913 0.9149000000 118144862 95654128 1785532416 -0.0346206427 0.0146507677 -0.0256194398 1022 1311867752.7152869701 0.0635934547 0.0129503467 0.0766752884 0.0055342856 0.9184400000 118145884 95654128 1783967744 -0.0330423079 0.0139570441 -0.0256315041 1023 1311867752.7510609627 0.0621317625 0.0129984224 0.0766752884 0.0055319162 0.9732250000 118148018 95654128 1783091200 -0.0313473158 0.0137614124 -0.0259141568 1024 1311867752.7830440998 0.0628359988 0.0130470919 0.0766752884 0.0055330845 1.0127640000 118150300 95654128 1784733696 -0.0313522741 0.0150813190 -0.0267195348 1025 1311867752.8162839413 0.0627530664 0.0130955855 0.0766752884 0.0055306697 0.9175760000 118315258 95654128 1784111104 -0.0314599238 0.0148715395 -0.0276156422 1026 1311867752.8511059284 0.0630953833 0.0131443183 0.0766752884 0.0055282609 0.8483050000 118485220 95654128 1783074816 -0.0317515247 0.0148108313 -0.0274483543 1027 1311867752.8833000660 0.0628048927 0.0131926733 0.0766752884 0.0055256036 0.9562310000 118487630 95654128 1784971264 -0.0314435214 0.0150910718 -0.0278630909 1028 1311867752.9183809757 0.0634140000 0.0132415267 0.0766752884 0.0055243638 0.9794470000 118488556 95654128 1784111104 -0.0325422026 0.0135978218 -0.0274231751 1029 1311867752.9511129856 0.0632216111 0.0132900982 0.0766752884 0.0055247529 1.1525030000 118490914 95654128 1783074816 -0.0326798595 0.0128196888 -0.0267387219 1030 1311867752.9828579426 0.0631901696 0.0133385449 0.0766752884 0.0055220974 1.0550930000 118493068 95654128 1784635392 -0.0326687917 0.0128426598 -0.0271675456 1031 1311867753.0168170929 0.0632573515 0.0133869627 0.0766752884 0.0055197243 1.0166810000 118493930 95654128 1785987072 -0.0325426012 0.0132081117 -0.0279791187 1032 1311867753.0510199070 0.0636908710 0.0134357068 0.0766752884 0.0055171638 1.1553700000 118496340 95654128 1784741888 -0.0333934762 0.0119138155 -0.0269528665 1033 1311867753.0829060078 0.0632801354 0.0134839589 0.0766752884 0.0055150304 1.0340660000 118498558 95654128 1784143872 -0.0328693390 0.0124768829 -0.0276455861 1034 1311867753.1184310913 0.0635224283 0.0135323520 0.0766752884 0.0055131381 1.1053610000 118499900 95654128 1785753600 -0.0326108262 0.0139584802 -0.0287013222 1035 1311867753.1510760784 0.0624902658 0.0135796544 0.0766752884 0.0055108207 1.0052450000 118502130 95654128 1784500224 -0.0323231295 0.0117570395 -0.0272279158 1036 1311867753.1830070019 0.0621665679 0.0136265529 0.0766752884 0.0055082917 1.0970950000 118503472 95654128 1783726080 -0.0319295637 0.0124879256 -0.0276561044 1037 1311867753.2186999321 0.0624585152 0.0136736426 0.0766752884 0.0055056686 0.9908370000 118677226 95654128 1785241600 -0.0313275568 0.0153965456 -0.0296825096 1038 1311867753.2520470619 0.0618149824 0.0137200215 0.0766752884 0.0055030820 0.9151680000 118679508 95654128 1784229888 -0.0317941159 0.0130966119 -0.0282633267 1039 1311867753.2829909325 0.0629017726 0.0137673572 0.0766752884 0.0055008380 1.0336590000 118680626 95654128 1783353344 -0.0335172154 0.0130235739 -0.0280892998 1040 1311867753.3196740150 0.0632684901 0.0138149544 0.0766752884 0.0055000902 0.9280990000 118682972 95654128 1784979456 -0.0330708101 0.0164913479 -0.0294133760 1041 1311867753.3509368896 0.0639817789 0.0138631454 0.0766752884 0.0054979753 1.4418410000 118685298 95654128 1783971840 -0.0346326977 0.0155160176 -0.0281098709 1042 1311867753.3829340935 0.0633225888 0.0139106113 0.0766752884 0.0054954687 1.2515500000 118686256 95654128 1783083008 -0.0348365642 0.0144146513 -0.0269600302 1043 1311867753.4182109833 0.0637362078 0.0139583827 0.0766752884 0.0054930172 1.0762700000 118688634 95654128 1784725504 -0.0353536941 0.0157489199 -0.0275411978 1044 1311867753.4511721134 0.0632840917 0.0140056296 0.0766752884 0.0054905718 1.0412390000 118861824 95654128 1783750656 -0.0360379815 0.0142781259 -0.0272401962 1045 1311867753.4831509590 0.0636765286 0.0140531615 0.0766752884 0.0054889416 1.1097530000 118862782 95654128 1782845440 -0.0363813601 0.0157582350 -0.0275145061 1046 1311867753.5199849606 0.0635348633 0.0141004672 0.0766752884 0.0054864310 1.2308920000 118865128 95654128 1784471552 -0.0365737304 0.0168507174 -0.0288942419 1047 1311867753.5532789230 0.0632524490 0.0141474127 0.0766752884 0.0054843313 0.8847810000 118867454 95654128 1786122240 -0.0369002447 0.0168713816 -0.0285116136 1048 1311867753.5832290649 0.0635170192 0.0141945211 0.0766752884 0.0054818439 0.9907840000 118868348 95654128 1785114624 -0.0379227363 0.0167180430 -0.0287353843 1049 1311867753.6183180809 0.0637207627 0.0142417339 0.0766752884 0.0054796424 1.0332600000 118870918 95654128 1783996416 -0.0388471372 0.0170920733 -0.0285290554 1050 1311867753.6509299278 0.0633393750 0.0142884936 0.0766752884 0.0054774411 0.9502920000 118873104 95654128 1785778176 -0.0393463559 0.0165491402 -0.0281495303 1051 1311867753.6830120087 0.0644971728 0.0143362659 0.0766752884 0.0054751316 0.9576130000 119044966 95654128 1784410112 -0.0407874882 0.0171791613 -0.0282723550 1052 1311867753.7204821110 0.0642839149 0.0143837446 0.0766752884 0.0054726404 1.0728070000 119047280 95654128 1782870016 -0.0411271863 0.0172792152 -0.0286168512 1053 1311867753.7510209084 0.0649050996 0.0144317231 0.0766752884 0.0054703317 0.8155980000 119048282 95654128 1784762368 -0.0430486836 0.0158796571 -0.0274096243 1054 1311867753.7865459919 0.0657980889 0.0144804578 0.0766752884 0.0054705905 0.9368880000 119050532 95654128 1786130432 -0.0447432362 0.0162014719 -0.0269907303 1055 1311867753.8151860237 0.0667848140 0.0145300354 0.0766752884 0.0054697823 0.8971900000 119052654 95654128 1784868864 -0.0450141393 0.0188802276 -0.0281987637 1056 1311867753.8510670662 0.0649216920 0.0145777548 0.0766752884 0.0054693887 0.8135670000 119053644 95654128 1783988224 -0.0448617712 0.0163347349 -0.0263647418 1057 1311867753.8831698895 0.0664996877 0.0146268768 0.0766752884 0.0054687289 0.8360110000 119055862 95654128 1785614336 -0.0473732688 0.0152459033 -0.0244121738 1058 1311867753.9155960083 0.0649758950 0.0146744656 0.0766752884 0.0054663872 0.9979190000 119058912 95654128 1784635392 -0.0461160056 0.0165156480 -0.0265005194 1059 1311867753.9511620998 0.0643590540 0.0147213821 0.0766752884 0.0054639198 1.0700290000 119230554 95654128 1783734272 -0.0465715528 0.0157505702 -0.0268248040 1060 1311867753.9859020710 0.0671304241 0.0147708246 0.0766752884 0.0054631010 0.7752450000 119232804 95654128 1785360384 -0.0508531965 0.0134292198 -0.0246797334 1061 1311867754.0151760578 0.0661156327 0.0148192175 0.0766752884 0.0054608282 0.8198330000 119234926 95654128 1784524800 -0.0509736426 0.0132474201 -0.0241836682 1062 1311867754.0510439873 0.0648731515 0.0148663492 0.0766752884 0.0054607006 0.8078830000 119235948 95654128 1783590912 -0.0498728938 0.0151051972 -0.0253496300 1063 1311867754.0839149952 0.0668878555 0.0149152876 0.0766752884 0.0054597828 0.7140740000 119238134 95654128 1785249792 -0.0527133718 0.0143488888 -0.0233845506 1064 1311867754.1166028976 0.0674695149 0.0149646807 0.0766752884 0.0054572749 0.7378160000 119240320 95654128 1784229888 -0.0540123656 0.0146879833 -0.0225797221 1065 1311867754.1511039734 0.0683484152 0.0150148063 0.0766752884 0.0054594600 0.8730430000 119411894 95654128 1783480320 -0.0554079488 0.0157281365 -0.0230643004 1066 1311867754.1832261086 0.0662601665 0.0150628788 0.0766752884 0.0054616836 0.9408900000 119414432 95654128 1785106432 -0.0543065704 0.0152893020 -0.0233770013 1067 1311867754.2166349888 0.0675755665 0.0151120941 0.0766752884 0.0054631009 1.0062950000 119416618 95654128 1784119296 -0.0571052097 0.0146502163 -0.0220064782 1068 1311867754.2522869110 0.0671783611 0.0151608453 0.0766752884 0.0054670724 1.0293380000 119417864 95654128 1783226368 -0.0572701991 0.0158211496 -0.0215691458 1069 1311867754.2873370647 0.0665276200 0.0152088965 0.0766752884 0.0054702118 1.2623220000 119420306 95654128 1784852480 -0.0586354733 0.0142751364 -0.0212793089 1070 1311867754.3188319206 0.0676168725 0.0152578759 0.0766752884 0.0054690626 0.8949440000 119593396 95654128 1783861248 -0.0609731674 0.0134114577 -0.0209280010 1071 1311867754.3511719704 0.0683681518 0.0153074654 0.0766752884 0.0054692331 1.0528150000 119594462 95654128 1782956032 -0.0627930239 0.0131636290 -0.0202908050 1072 1311867754.3868899345 0.0670779645 0.0153557587 0.0766752884 0.0054684390 0.9542270000 119596680 95654128 1784725504 -0.0621130913 0.0136894723 -0.0205030032 1073 1311867754.4159760475 0.0678604767 0.0154046914 0.0766752884 0.0054663930 0.8327580000 119597606 95654128 1783750656 -0.0634818003 0.0135204215 -0.0196407102 1074 1311867754.4545960426 0.0675055236 0.0154532024 0.0766752884 0.0054747658 0.8395710000 119599856 95654128 1782845440 -0.0642359480 0.0124290809 -0.0187484492 1075 1311867754.4863700867 0.0678380579 0.0155019325 0.0766752884 0.0054813669 0.7278180000 119602042 95654128 1784471552 -0.0652818903 0.0120699462 -0.0179413855 1076 1311867754.5164580345 0.0669162869 0.0155497154 0.0766752884 0.0054789872 1.0087910000 119602936 95654128 1783476224 -0.0645778552 0.0129131079 -0.0179543439 1077 1311867754.5513699055 0.0661791936 0.0155967251 0.0766752884 0.0054790217 1.0457280000 119605262 95654128 1782591488 -0.0643610284 0.0120344581 -0.0171170905 1078 1311867754.5835940838 0.0674868971 0.0156448607 0.0766752884 0.0054790551 1.0940370000 119607992 95654128 1784217600 -0.0662809238 0.0113103576 -0.0156370699 1079 1311867754.6154909134 0.0654442608 0.0156910140 0.0766752884 0.0054767598 1.0551980000 119608822 95654128 1785884672 -0.0641420931 0.0125101553 -0.0163888987 1080 1311867754.6510920525 0.0659723431 0.0157375708 0.0766752884 0.0054746140 0.9212180000 119611104 95654128 1784877056 -0.0649947003 0.0123165390 -0.0157093517 1081 1311867754.6872758865 0.0675872117 0.0157855353 0.0766752884 0.0054727643 0.7889370000 119613354 95654128 1783734272 -0.0671945363 0.0121134054 -0.0149064995 1082 1311867754.7162959576 0.0689474568 0.0158346683 0.0766752884 0.0054702686 1.0347190000 119785724 95654128 1785487360 -0.0690469965 0.0119513944 -0.0149083929 1083 1311867754.7516000271 0.0680218190 0.0158828559 0.0766752884 0.0054680155 1.0016250000 119788370 95654128 1784487936 -0.0681873709 0.0129238302 -0.0153053347 1084 1311867754.7865269184 0.0682076290 0.0159311260 0.0766752884 0.0054671477 0.9293040000 119790652 95654128 1783353344 -0.0693144351 0.0110184429 -0.0137853120 1085 1311867754.8154470921 0.0696559027 0.0159806419 0.0766752884 0.0054650112 0.9312030000 119791834 95654128 1785114624 -0.0710438713 0.0114224702 -0.0125779156 1086 1311867754.8510210514 0.0683089644 0.0160288263 0.0766752884 0.0054679934 0.9607540000 119794020 95654128 1784127488 -0.0702079684 0.0120822294 -0.0133596445 1087 1311867754.8877389431 0.0685929507 0.0160771834 0.0766752884 0.0054656871 1.3852450000 119796238 95654128 1782980608 -0.0723908395 0.0081034675 -0.0115132472 1088 1311867754.9201259613 0.0706201047 0.0161273148 0.0766752884 0.0054641436 1.1073270000 119797100 95654128 1784606720 -0.0750982091 0.0081602503 -0.0100630075 1089 1311867754.9510319233 0.0700656548 0.0161768449 0.0766752884 0.0054620580 1.1845890000 119799586 95654128 1783603200 -0.0748294666 0.0098988218 -0.0111112129 1090 1311867754.9837870598 0.0683496669 0.0162247099 0.0766752884 0.0054636487 0.9686020000 119971144 95654128 1782575104 -0.0746032298 0.0087613491 -0.0110397302 1091 1311867755.0183880329 0.0685263202 0.0162726490 0.0766752884 0.0054614011 0.9792280000 119973490 95654128 1784217600 -0.0752478540 0.0086689703 -0.0094969673 1092 1311867755.0540831089 0.0688500479 0.0163207968 0.0766752884 0.0054650661 0.9936750000 119975676 95654128 1785995264 -0.0759167969 0.0091051916 -0.0082838237 1093 1311867755.0850980282 0.0707389712 0.0163705847 0.0766752884 0.0054652660 1.0572440000 119976794 95654128 1784877056 -0.0782112628 0.0095534232 -0.0080992691 1094 1311867755.1156959534 0.0705557168 0.0164201141 0.0766752884 0.0054646677 1.0100600000 119978980 95654128 1783861248 -0.0788334459 0.0088128746 -0.0075863246 1095 1311867755.1556220055 0.0702816248 0.0164693027 0.0766752884 0.0054625800 1.0909960000 119981498 95654128 1785634816 -0.0792177916 0.0086931074 -0.0068904273 1096 1311867755.1847031116 0.0711106062 0.0165191579 0.0766752884 0.0054602533 1.0612040000 119982488 95654128 1784643584 -0.0805549473 0.0090549709 -0.0065287817 1097 1311867755.2151238918 0.0701405928 0.0165680380 0.0766752884 0.0054580896 1.0543530000 119984674 95654128 1783353344 -0.0795629025 0.0106327236 -0.0071433908 1098 1311867755.2512340546 0.0710992292 0.0166177021 0.0766752884 0.0054556902 1.0876940000 119987116 95654128 1784979456 -0.0813643783 0.0096242046 -0.0058201384 1099 1311867755.2832889557 0.0718266591 0.0166679377 0.0766752884 0.0054540462 1.0220500000 119988106 95654128 1783861248 -0.0826429650 0.0089555327 -0.0051864274 1100 1311867755.3192110062 0.0707763359 0.0167171272 0.0766752884 0.0054518359 1.3398810000 119990164 95654128 1782845440 -0.0818398371 0.0090798950 -0.0067957076 1101 1311867755.3553090096 0.0711686835 0.0167665836 0.0766752884 0.0054497361 1.3260770000 119992650 95654128 1784471552 -0.0830001608 0.0073966552 -0.0062933885 1102 1311867755.3900220394 0.0722652450 0.0168169454 0.0766752884 0.0054479763 0.9213230000 119993512 95654128 1783365632 -0.0842128471 0.0076453690 -0.0053134016 1103 1311867755.4156589508 0.0715487301 0.0168665662 0.0766752884 0.0054455517 0.9914550000 119995698 95654128 1782337536 -0.0831013024 0.0101651810 -0.0081470991 1104 1311867755.4549160004 0.0708845034 0.0169154955 0.0766752884 0.0054433768 1.0774830000 119997916 95654128 1783963648 -0.0831817463 0.0092779519 -0.0074789696 1105 1311867755.4860870838 0.0735554025 0.0169667533 0.0766752884 0.0054414717 1.1350950000 119999130 95654128 1785614336 -0.0868665799 0.0076172668 -0.0056045740 1106 1311867755.5161950588 0.0723785236 0.0170168544 0.0766752884 0.0054390645 0.8943240000 120001188 95654128 1784619008 -0.0855160207 0.0092629660 -0.0069299312 1107 1311867755.5550999641 0.0721377656 0.0170666475 0.0766752884 0.0054368999 1.0061130000 120002574 95654128 1783463936 -0.0860151947 0.0081464862 -0.0065715383 1108 1311867755.5854589939 0.0719696358 0.0171161989 0.0766752884 0.0054348171 0.9446580000 120004696 95654128 1785106432 -0.0860566869 0.0082980525 -0.0064332308 1109 1311867755.6171119213 0.0714797378 0.0171652192 0.0766752884 0.0054323903 1.0127900000 120007042 95654128 1784119296 -0.0853507593 0.0097943544 -0.0071685640 1110 1311867755.6542940140 0.0710246414 0.0172137412 0.0766752884 0.0054301270 1.0686430000 120008128 95654128 1782972416 -0.0850997344 0.0098417997 -0.0073339129 1111 1311867755.6831719875 0.0715300515 0.0172626308 0.0766752884 0.0054282187 1.0560260000 120010314 95654128 1784598528 -0.0861181691 0.0084374435 -0.0062551107 1112 1311867755.7182741165 0.0724753514 0.0173122825 0.0766752884 0.0054267712 1.2147160000 120012372 95654128 1783603200 -0.0874507278 0.0081063947 -0.0062128366 1113 1311867755.7511448860 0.0718235970 0.0173612594 0.0766752884 0.0054243571 1.0508630000 120013502 95654128 1782489088 -0.0870831385 0.0079597495 -0.0069529074 1114 1311867755.7863750458 0.0722294673 0.0174105128 0.0766752884 0.0054222470 0.7777360000 120186544 95654128 1784098816 -0.0880723968 0.0067996229 -0.0074791573 1115 1311867755.8156878948 0.0720311180 0.0174594999 0.0766752884 0.0054199369 0.9493960000 120189050 95654128 1785876480 -0.0876366571 0.0078376364 -0.0076282443 1116 1311867755.8554079533 0.0721965805 0.0175085474 0.0766752884 0.0054179655 0.7581210000 120190040 95654128 1785049088 -0.0872525722 0.0107780909 -0.0092916731 1117 1311867755.8848359585 0.0712063909 0.0175566207 0.0766752884 0.0054164084 0.9962820000 120192226 95654128 1783615488 -0.0878098980 0.0070436168 -0.0088621620 1118 1311867755.9156229496 0.0714628696 0.0176048374 0.0766752884 0.0054141720 1.0102490000 120194412 95654128 1785241600 -0.0880834386 0.0073814085 -0.0078167785 1119 1311867755.9550359249 0.0715692490 0.0176530629 0.0766752884 0.0054117706 0.8197110000 120195542 95654128 1784238080 -0.0883174762 0.0089556081 -0.0097438833 1120 1311867755.9855198860 0.0717110410 0.0177013290 0.0766752884 0.0054112734 0.7701860000 120197696 95654128 1783107584 -0.0890156701 0.0078688627 -0.0094587468 1121 1311867756.0173881054 0.0722772479 0.0177500140 0.0766752884 0.0054095464 0.9082710000 120199850 95654128 1784733696 -0.0896641761 0.0079071084 -0.0083175292 1122 1311867756.0554430485 0.0715912804 0.0177980009 0.0766752884 0.0054072497 0.7657530000 120200840 95654128 1783758848 -0.0887686014 0.0094419429 -0.0096996902 1123 1311867756.0835959911 0.0716766119 0.0178459783 0.0766752884 0.0054052999 0.8455770000 120203634 95654128 1782599680 -0.0893829390 0.0080130706 -0.0088074347 1124 1311867756.1196908951 0.0716554001 0.0178938514 0.0766752884 0.0054029923 1.0319440000 120205948 95654128 1784217600 -0.0895633250 0.0061436468 -0.0066849831 1125 1311867756.1519339085 0.0718222186 0.0179417878 0.0766752884 0.0054007890 0.9771910000 120206918 95654128 1785868288 -0.0891571790 0.0088715488 -0.0087388530 1126 1311867756.1836869717 0.0711183399 0.0179890138 0.0766752884 0.0053989002 0.9980400000 120209040 95654128 1784893440 -0.0889685974 0.0073090014 -0.0091163833 1127 1311867756.2230648994 0.0723008886 0.0180372054 0.0766752884 0.0053973914 0.8986530000 120209966 95654128 1783734272 -0.0900221020 0.0067476714 -0.0072651110 1128 1311867756.2552509308 0.0718024299 0.0180848696 0.0766752884 0.0053974255 1.0837330000 120212152 95654128 1785360384 -0.0893004090 0.0077604400 -0.0077930782 1129 1311867756.2851591110 0.0714842901 0.0181321676 0.0766752884 0.0053981833 0.9192540000 120214338 95654128 1784377344 -0.0889843404 0.0077931043 -0.0088402107 1130 1311867756.3200058937 0.0709197745 0.0181788823 0.0766752884 0.0053960580 0.7531290000 120215296 95654128 1783226368 -0.0881998092 0.0076180063 -0.0077187642 1131 1311867756.3546419144 0.0723130479 0.0182267462 0.0766752884 0.0053940321 0.8412970000 120218262 95654128 1784868864 -0.0893072560 0.0080592427 -0.0070360922 1132 1311867756.3843090534 0.0719018579 0.0182741624 0.0766752884 0.0053917778 0.8762670000 120220384 95654128 1783844864 -0.0890362412 0.0082188305 -0.0085825203 1133 1311867756.4231688976 0.0712129101 0.0183208868 0.0766752884 0.0053901821 0.9877590000 120221502 95654128 1782702080 -0.0880624205 0.0079697100 -0.0080646798 1134 1311867756.4510979652 0.0718797818 0.0183681169 0.0766752884 0.0053879320 0.8331040000 120223528 95654128 1784344576 -0.0886850655 0.0078402795 -0.0073867962 1135 1311867756.4865350723 0.0717882514 0.0184151831 0.0766752884 0.0053908032 0.8322560000 120225810 95654128 1786122240 -0.0882099196 0.0087147932 -0.0085858433 1136 1311867756.5264549255 0.0712887347 0.0184617267 0.0766752884 0.0053890185 0.8406330000 120226832 95654128 1785004032 -0.0877232850 0.0079812286 -0.0086976299 1137 1311867756.5525779724 0.0710862055 0.0185080103 0.0766752884 0.0053870578 1.0933120000 120229094 95654128 1784242176 -0.0876416266 0.0073839137 -0.0087561496 1138 1311867756.5897810459 0.0709790885 0.0185541185 0.0766752884 0.0053847749 1.0775810000 120231632 95654128 1785896960 -0.0874664262 0.0072941747 -0.0084902672 1139 1311867756.6202929020 0.0716922879 0.0186007718 0.0766752884 0.0053825772 1.0273720000 120232686 95654128 1784381440 -0.0878421739 0.0076641496 -0.0075827949 1140 1311867756.6518390179 0.0720898807 0.0186476921 0.0766752884 0.0053802513 1.0210520000 120234936 95654128 1783209984 -0.0885956958 0.0062839882 -0.0067213266 1141 1311867756.6839349270 0.0710513443 0.0186936199 0.0766752884 0.0053784085 1.0408930000 120237154 95654128 1784852480 -0.0873292983 0.0075513325 -0.0074096262 1142 1311867756.7217059135 0.0717493594 0.0187400785 0.0766752884 0.0053782007 1.1012370000 120238208 95654128 1783861248 -0.0886858776 0.0062283548 -0.0067823944 1143 1311867756.7516939640 0.0709942430 0.0187857952 0.0766752884 0.0053769629 1.1143250000 120240566 95654128 1782718464 -0.0877705812 0.0062033776 -0.0058544185 1144 1311867756.7872660160 0.0718041286 0.0188321399 0.0766752884 0.0053747273 1.1540930000 120241492 95654128 1784344576 -0.0884979293 0.0067893937 -0.0060568904 1145 1311867756.8227219582 0.0715349168 0.0188781685 0.0766752884 0.0053725536 0.9776550000 120243934 95654128 1785995264 -0.0882135257 0.0070565138 -0.0058403281 1146 1311867756.8542120457 0.0709639639 0.0189236186 0.0766752884 0.0053762756 1.0145330000 120246024 95654128 1785004032 -0.0878871456 0.0059245606 -0.0049502505 1147 1311867756.8841960430 0.0708280355 0.0189688710 0.0766752884 0.0053782123 1.0368580000 120247142 95654128 1783861248 -0.0877370089 0.0065289647 -0.0054247272 1148 1311867756.9223539829 0.0705109015 0.0190137682 0.0766752884 0.0053766173 0.9527780000 120249328 95654128 1785487360 -0.0876888186 0.0060211942 -0.0050318879 1149 1311867756.9552440643 0.0714227259 0.0190593809 0.0766752884 0.0053750036 0.9513850000 120251878 95654128 1784516608 -0.0886022523 0.0059553739 -0.0040440070 1150 1311867756.9841780663 0.0706138611 0.0191042108 0.0766752884 0.0053728661 1.1378410000 120252932 95654128 1783361536 -0.0875809863 0.0074686073 -0.0057310588 1151 1311867757.0282740593 0.0702320784 0.0191486312 0.0766752884 0.0053725911 1.0089660000 120255502 95654128 1784987648 -0.0881596208 0.0041665747 -0.0037241830 1152 1311867757.0552940369 0.0710929707 0.0191937218 0.0766752884 0.0053710085 1.0599590000 120257560 95654128 1783980032 -0.0888317376 0.0050422242 -0.0039790422 1153 1311867757.0858569145 0.0710784793 0.0192387216 0.0766752884 0.0053687205 0.9964520000 120258390 95654128 1782853632 -0.0883614793 0.0064326967 -0.0040503875 1154 1311867757.1283040047 0.0719282925 0.0192843798 0.0766752884 0.0053671776 1.1946720000 120430904 95654128 1784606720 -0.0896810815 0.0032322637 -0.0011919411 1155 1311867757.1522068977 0.0728608295 0.0193307663 0.0766752884 0.0053689656 1.0869450000 120433198 95654128 1783611392 -0.0901174843 0.0051078480 -0.0021646661 1156 1311867757.1851921082 0.0728825033 0.0193770914 0.0766752884 0.0053669859 0.7241600000 120434156 95654128 1782599680 -0.0897688195 0.0054873722 -0.0027871435 1157 1311867757.2192370892 0.0727979988 0.0194232633 0.0766752884 0.0053656170 0.9149210000 120436406 95654128 1784225792 -0.0898362920 0.0027799371 -0.0020967624 1158 1311867757.2523930073 0.0729448870 0.0194694823 0.0766752884 0.0053726926 0.9725810000 120438784 95654128 1785868288 -0.0899373218 0.0018591488 -0.0024862771 1159 1311867757.2835690975 0.0727143362 0.0195154226 0.0766752884 0.0053711261 1.0153570000 120439614 95654128 1784877056 -0.0887389481 0.0051213298 -0.0049411929 1160 1311867757.3233768940 0.0722038895 0.0195608437 0.0766752884 0.0053770141 1.1739950000 120441992 95654128 1783844864 -0.0880163163 0.0026963952 -0.0044041593 1161 1311867757.3555359840 0.0725479126 0.0196064829 0.0766752884 0.0053752157 0.9296600000 120443090 95654128 1785487360 -0.0880403519 0.0030275420 -0.0046089664 1162 1311867757.3833439350 0.0724205822 0.0196519339 0.0766752884 0.0053732072 1.2371560000 120445308 95654128 1784487936 -0.0870449543 0.0056924196 -0.0059134378 1163 1311867757.4264349937 0.0740767345 0.0196987308 0.0766752884 0.0053714510 0.7543770000 120447622 95654128 1783644160 -0.0878238231 0.0060304767 -0.0029667425 ================================================ FILE: icra2018_results/tegra/violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 05:47:09 Properties: ================= frame-limit: 0 log-file: output//violons_libefusion-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libefusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 confidence: 10 depth: 3 icp: 10 icpErrThresh: 5e-05 covThresh: 1e-05 photoThresh: 115 fernThresh: 0.3095 icpCountThresh: 35000 timeDelta: 200 textureDim: 512 nodeTextureDim: 2048 openLoop: false reloc: false fastOdom: false so3: true frameToFrameRGB: false shader-dir: /harddrive/slambench2/benchmarks/efusion/src/cuda/Core/src/Shaders Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 nan 0.3047990000 96224587 95654128 1758253056 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0590395965 0.0586458202 0.0590395965 0.0043695630 1.0854490000 106737346 95654128 1758498816 -0.0046297587 -0.0003250803 -0.0017532537 3 1311867170.5264289379 0.0593872108 0.0588929504 0.0593872108 0.0035967954 1.0773730000 106740048 95654128 1760182272 -0.0087010767 -0.0014965255 -0.0033720005 4 1311867170.5623490810 0.0583232008 0.0587505130 0.0593872108 0.0048158044 1.1960940000 106741482 95654128 1761927168 -0.0087041268 -0.0010303888 -0.0057441890 5 1311867170.5942170620 0.0584076978 0.0586819500 0.0593872108 0.0047503333 1.0142660000 106744276 95654128 1763655680 -0.0113976868 -0.0026515401 -0.0070477310 6 1311867170.6260869503 0.0571007952 0.0584184242 0.0593872108 0.0045263473 0.9373760000 106747118 95654128 1765306368 -0.0123161534 -0.0040108599 -0.0096999612 7 1311867170.6621398926 0.0564304069 0.0581344217 0.0593872108 0.0043279576 1.0757890000 106748140 95654128 1766989824 -0.0142994700 -0.0065731280 -0.0112961400 8 1311867170.6942050457 0.0553153642 0.0577820395 0.0593872108 0.0042001668 1.1348540000 106750294 95654128 1768718336 -0.0137486551 -0.0067191049 -0.0138849709 9 1311867170.7263879776 0.0557638295 0.0575577940 0.0593872108 0.0040378525 1.2938190000 106753876 95654128 1770401792 -0.0166832916 -0.0081510656 -0.0149160959 10 1311867170.7620189190 0.0573873818 0.0575407527 0.0593872108 0.0038913842 1.1944910000 106756210 95654128 1772105728 -0.0208571628 -0.0095856255 -0.0154249892 11 1311867170.7941920757 0.0576700196 0.0575525043 0.0593872108 0.0038753654 1.0568190000 106758332 95654128 1773756416 -0.0219789352 -0.0120281586 -0.0167258978 12 1311867170.8262820244 0.0578117184 0.0575741054 0.0593872108 0.0039107512 1.5404930000 106930530 95654128 1775439872 -0.0231595840 -0.0151669020 -0.0187399797 13 1311867170.8622210026 0.0566113368 0.0575000463 0.0593872108 0.0041741095 1.1397240000 106931752 95654128 1777160192 -0.0219171587 -0.0170680452 -0.0219577681 14 1311867170.8943779469 0.0570422001 0.0574673430 0.0593872108 0.0040900781 1.1115400000 106933906 95654128 1778843648 -0.0214157701 -0.0191405229 -0.0241591297 15 1311867170.9263520241 0.0568430685 0.0574257247 0.0593872108 0.0040338778 0.9769760000 106936124 95654128 1780588544 -0.0204151627 -0.0215134434 -0.0269868039 16 1311867170.9621469975 0.0567336865 0.0573824723 0.0593872108 0.0039864537 0.8180310000 106937114 95654128 1782239232 -0.0219652895 -0.0223075058 -0.0304109044 17 1311867170.9942629337 0.0557758622 0.0572879658 0.0593872108 0.0040482889 1.0818720000 106941828 95654128 1784000512 -0.0206563734 -0.0237760637 -0.0341141559 18 1311867171.0262739658 0.0555885695 0.0571935549 0.0593872108 0.0039512163 1.2366440000 106946670 95654128 1785651200 -0.0201262217 -0.0271924157 -0.0363608189 19 1311867171.0623519421 0.0553662516 0.0570973811 0.0593872108 0.0045599777 0.9349700000 106947660 95654128 1784889344 -0.0211413894 -0.0299601126 -0.0391975492 20 1311867171.0942349434 0.0544657297 0.0569657985 0.0593872108 0.0045674032 0.9952480000 107120358 95654128 1784508416 -0.0194505081 -0.0302127115 -0.0421793126 21 1311867171.1262509823 0.0545005761 0.0568484070 0.0593872108 0.0044684692 0.9527990000 107122576 95654128 1784000512 -0.0215338506 -0.0326050706 -0.0440473929 22 1311867171.1622469425 0.0549981445 0.0567643041 0.0593872108 0.0048484479 1.0948310000 107123534 95654128 1783619584 -0.0203466564 -0.0316030905 -0.0455996394 23 1311867171.1942689419 0.0528933220 0.0565960006 0.0593872108 0.0058697819 0.9128400000 107125672 95654128 1785372672 -0.0151479300 -0.0305932313 -0.0475577451 24 1311867171.2262530327 0.0532901809 0.0564582581 0.0593872108 0.0059476557 0.8979990000 107127890 95654128 1784483840 -0.0115759028 -0.0311542563 -0.0488610640 25 1311867171.2622439861 0.0524212271 0.0562967768 0.0593872108 0.0058329640 1.0107210000 107128880 95654128 1784102912 -0.0067584771 -0.0288666245 -0.0512366779 26 1311867171.2943410873 0.0513527319 0.0561066213 0.0593872108 0.0057673758 1.2932760000 107131002 95654128 1783181312 -0.0045648543 -0.0286129583 -0.0529360324 27 1311867171.3263869286 0.0525493883 0.0559748719 0.0593872108 0.0060520063 1.2123180000 107133220 95654128 1783054336 -0.0039762170 -0.0290050656 -0.0530894250 28 1311867171.3622460365 0.0529402234 0.0558664916 0.0593872108 0.0060355928 1.3546600000 107134210 95654128 1784446976 -0.0028461213 -0.0256772153 -0.0543870144 29 1311867171.3941431046 0.0538258217 0.0557961237 0.0593872108 0.0059808629 1.0800110000 107136364 95654128 1783709696 -0.0046027815 -0.0234379042 -0.0556271151 30 1311867171.4262878895 0.0560286753 0.0558038754 0.0593872108 0.0060498159 1.0751850000 107138582 95654128 1783181312 -0.0087633161 -0.0259505250 -0.0548655428 31 1311867171.4622440338 0.0556693748 0.0557995366 0.0593872108 0.0060708967 1.0712170000 107139572 95654128 1784840192 -0.0075734709 -0.0246111285 -0.0577058569 32 1311867171.4944040775 0.0550765395 0.0557769430 0.0593872108 0.0059884850 1.1198750000 107141726 95654128 1783828480 -0.0067127100 -0.0231670011 -0.0606448948 33 1311867171.5261778831 0.0566027835 0.0558019685 0.0593872108 0.0059492871 1.0900790000 107149048 95654128 1783209984 -0.0087534925 -0.0229871254 -0.0607217439 34 1311867171.5622971058 0.0562855378 0.0558161911 0.0593872108 0.0059631345 0.9141710000 107155286 95654128 1784840192 -0.0067214258 -0.0205412060 -0.0627184734 35 1311867171.5942931175 0.0548040755 0.0557872735 0.0593872108 0.0059562412 1.0392800000 107157440 95654128 1783828480 -0.0056193219 -0.0221905336 -0.0641570762 36 1311867171.6263399124 0.0565896779 0.0558095625 0.0593872108 0.0059167025 1.2834270000 107159658 95654128 1783459840 -0.0094992705 -0.0218665358 -0.0633907616 37 1311867171.6622560024 0.0576589406 0.0558595457 0.0593872108 0.0058699786 1.1393500000 107160648 95654128 1785090048 -0.0123062236 -0.0198261105 -0.0642024428 38 1311867171.6943440437 0.0578230098 0.0559112158 0.0593872108 0.0058651626 1.0612330000 107162802 95654128 1784221696 -0.0129630258 -0.0195442867 -0.0646993220 39 1311867171.7262439728 0.0576510578 0.0559558271 0.0593872108 0.0057900694 1.0904630000 107165020 95654128 1784090624 -0.0165277757 -0.0210464373 -0.0650094301 40 1311867171.7621190548 0.0579682216 0.0560061370 0.0593872108 0.0057200750 1.0309430000 107166010 95654128 1783058432 -0.0184061714 -0.0220167041 -0.0651536286 41 1311867171.7941710949 0.0576449148 0.0560461072 0.0593872108 0.0056848230 1.1571820000 107168164 95654128 1782546432 -0.0203307327 -0.0229816511 -0.0660416335 42 1311867171.8262550831 0.0574936084 0.0560805715 0.0593872108 0.0056338759 1.0117920000 107170382 95654128 1784356864 -0.0217187591 -0.0232937150 -0.0674158186 43 1311867171.8623590469 0.0573481768 0.0561100507 0.0593872108 0.0055881382 1.0577930000 107171356 95654128 1783201792 -0.0268588215 -0.0248993803 -0.0681789145 44 1311867171.8944430351 0.0574418865 0.0561403197 0.0593872108 0.0056763918 1.2340010000 107173542 95654128 1782820864 -0.0299081951 -0.0223788247 -0.0700934529 45 1311867171.9262220860 0.0565409064 0.0561492216 0.0593872108 0.0057468334 1.2905970000 107175728 95654128 1784598528 -0.0337208062 -0.0240939688 -0.0707545504 46 1311867171.9624669552 0.0570410080 0.0561686083 0.0593872108 0.0057360583 1.3976860000 107176718 95654128 1783586816 -0.0365872085 -0.0218247715 -0.0712081790 47 1311867171.9946711063 0.0565888882 0.0561775504 0.0593872108 0.0058883994 1.0772850000 107178904 95654128 1782820864 -0.0403092578 -0.0227173194 -0.0710438192 48 1311867172.0262680054 0.0557974540 0.0561696317 0.0593872108 0.0059637182 0.9554710000 107181090 95654128 1784598528 -0.0412862413 -0.0219650939 -0.0710382834 49 1311867172.0622880459 0.0555329733 0.0561566387 0.0593872108 0.0059047433 1.3772480000 107182080 95654128 1783586816 -0.0449542478 -0.0222551860 -0.0700057149 50 1311867172.0941960812 0.0556864142 0.0561472342 0.0593872108 0.0058698522 1.0970450000 107184266 95654128 1783095296 -0.0484787636 -0.0234941263 -0.0680501387 51 1311867172.1263689995 0.0556669682 0.0561378172 0.0593872108 0.0058726496 1.2394160000 107355964 95654128 1784832000 -0.0523436554 -0.0249330271 -0.0667900071 52 1311867172.1623349190 0.0557489507 0.0561303390 0.0593872108 0.0058658668 1.0592760000 107356954 95654128 1783713792 -0.0553347915 -0.0228705667 -0.0665258989 53 1311867172.1944270134 0.0551638082 0.0561121026 0.0593872108 0.0058285636 1.1082280000 107359140 95654128 1783062528 -0.0582162738 -0.0232382100 -0.0661056861 54 1311867172.2264409065 0.0565062761 0.0561194021 0.0593872108 0.0060826974 1.1148580000 107361326 95654128 1784832000 -0.0594271421 -0.0202931073 -0.0654258505 55 1311867172.2622280121 0.0566044897 0.0561282219 0.0593872108 0.0060490784 1.3555200000 107362316 95654128 1783459840 -0.0597737655 -0.0182471536 -0.0647308379 56 1311867172.2944829464 0.0574160703 0.0561512192 0.0593872108 0.0060248288 1.1700010000 107364502 95654128 1782845440 -0.0648879558 -0.0169185251 -0.0641474202 57 1311867172.3263380527 0.0577596165 0.0561794367 0.0593872108 0.0060282519 1.1144180000 107366688 95654128 1784324096 -0.0679509044 -0.0149500379 -0.0638337359 58 1311867172.3624010086 0.0570558906 0.0561945479 0.0593872108 0.0059823832 0.8174060000 107539118 95654128 1783570432 -0.0729844645 -0.0170178059 -0.0636347830 59 1311867172.3942890167 0.0560659841 0.0561923689 0.0593872108 0.0059771993 0.9924670000 107541288 95654128 1783189504 -0.0752919167 -0.0169306844 -0.0640818924 60 1311867172.4265220165 0.0567514710 0.0562016873 0.0593872108 0.0060204231 1.2266090000 107543474 95654128 1784848384 -0.0794756263 -0.0182639584 -0.0638984218 61 1311867172.4623498917 0.0560562797 0.0561993035 0.0593872108 0.0060692158 1.0779200000 107544464 95654128 1783955456 -0.0770915821 -0.0173059274 -0.0644074678 62 1311867172.4952669144 0.0558628067 0.0561938762 0.0593872108 0.0061009167 0.9455150000 107546618 95654128 1783214080 -0.0812973231 -0.0187739134 -0.0646615848 63 1311867172.5263059139 0.0567112751 0.0562020889 0.0593872108 0.0061675714 1.1758220000 107548804 95654128 1784967168 -0.0874481201 -0.0190708507 -0.0651847944 64 1311867172.5624930859 0.0564761460 0.0562063710 0.0593872108 0.0061291811 1.0118330000 107549794 95654128 1783721984 -0.0872496590 -0.0171613656 -0.0665538236 65 1311867172.5945439339 0.0561747961 0.0562058852 0.0593872108 0.0061070532 1.0393910000 107562156 95654128 1783091200 -0.0880366489 -0.0182761829 -0.0667734072 66 1311867172.6263699532 0.0565976985 0.0562118218 0.0593872108 0.0060957645 0.8934780000 107574870 95654128 1784713216 -0.0905268118 -0.0181227364 -0.0671966150 67 1311867172.6624419689 0.0562022999 0.0562116797 0.0593872108 0.0060739618 1.1807260000 107575860 95654128 1783066624 -0.0913824365 -0.0171354562 -0.0681039765 68 1311867172.6945450306 0.0558617003 0.0562065329 0.0593872108 0.0061479892 1.7552040000 107748010 95654128 1782689792 -0.0944850072 -0.0179444887 -0.0685523599 69 1311867172.7263929844 0.0556021892 0.0561977743 0.0593872108 0.0061608901 1.9405860000 107750180 95654128 1784467456 -0.0964549631 -0.0162022896 -0.0698607191 70 1311867172.7623739243 0.0543602183 0.0561715235 0.0593872108 0.0061525628 1.7438100000 107751170 95654128 1783332864 -0.1009600535 -0.0175871011 -0.0707219616 71 1311867172.7944509983 0.0540678538 0.0561418944 0.0593872108 0.0061292472 1.3167670000 107753324 95654128 1782575104 -0.1040844247 -0.0181117021 -0.0710704327 72 1311867172.8263089657 0.0541565232 0.0561143198 0.0593872108 0.0061134142 1.1479910000 107755542 95654128 1784197120 -0.1058001816 -0.0190949347 -0.0714485794 73 1311867172.8632309437 0.0542309247 0.0560885198 0.0593872108 0.0060743355 1.1015780000 107926420 95654128 1783443456 -0.1099782214 -0.0197884645 -0.0718666539 74 1311867172.8944649696 0.0537985787 0.0560575747 0.0593872108 0.0060357675 0.9508910000 107928526 95654128 1783078912 -0.1130677536 -0.0196822342 -0.0728839114 75 1311867172.9263219833 0.0531453229 0.0560187447 0.0593872108 0.0060055585 0.9339980000 107930744 95654128 1784815616 -0.1150684580 -0.0209271088 -0.0737171918 76 1311867172.9623310566 0.0536868684 0.0559880621 0.0593872108 0.0059696497 0.9223580000 107931734 95654128 1783693312 -0.1160425544 -0.0205168612 -0.0739527717 77 1311867172.9945271015 0.0532102883 0.0559519871 0.0593872108 0.0059346255 1.0426310000 107933888 95654128 1782845440 -0.1175899208 -0.0216507334 -0.0745356306 78 1311867173.0262629986 0.0535338782 0.0559209857 0.0593872108 0.0058968441 1.1040720000 107936074 95654128 1784578048 -0.1180491671 -0.0210370477 -0.0746004134 79 1311867173.0624630451 0.0538179167 0.0558943646 0.0593872108 0.0058620378 0.9077570000 107937064 95654128 1782710272 -0.1176437959 -0.0198677573 -0.0749624074 80 1311867173.0945179462 0.0542015657 0.0558732046 0.0593872108 0.0059158563 0.7731240000 107939250 95654128 1782575104 -0.1212317869 -0.0197939072 -0.0752711520 81 1311867173.1267819405 0.0543637797 0.0558545697 0.0593872108 0.0059060733 0.8218800000 107941452 95654128 1784307712 -0.1217626557 -0.0179609880 -0.0757146105 82 1311867173.1622309685 0.0543331467 0.0558360158 0.0593872108 0.0059121143 0.9124560000 107942442 95654128 1783463936 -0.1216508746 -0.0170793887 -0.0757398158 83 1311867173.1943008900 0.0542391203 0.0558167761 0.0593872108 0.0058806991 0.9046270000 107944596 95654128 1782575104 -0.1253245920 -0.0177079979 -0.0756626874 84 1311867173.2264449596 0.0540481023 0.0557957204 0.0593872108 0.0058513098 0.7717230000 107946782 95654128 1784340480 -0.1273073107 -0.0171268359 -0.0756059662 85 1311867173.2622020245 0.0540673435 0.0557753866 0.0593872108 0.0058484055 1.1297290000 108117552 95654128 1783189504 -0.1284490228 -0.0159532800 -0.0760795325 86 1311867173.2942678928 0.0535362139 0.0557493497 0.0593872108 0.0058497795 0.8729460000 108119706 95654128 1782464512 -0.1290127635 -0.0173590332 -0.0756448507 87 1311867173.3262879848 0.0540894754 0.0557302707 0.0593872108 0.0058245705 1.0104450000 108121892 95654128 1784213504 -0.1306219548 -0.0175520107 -0.0748270452 88 1311867173.3623280525 0.0543467589 0.0557145489 0.0593872108 0.0057925689 0.8573650000 108122914 95654128 1783193600 -0.1335334331 -0.0166366305 -0.0751037821 89 1311867173.3942871094 0.0545040853 0.0557009482 0.0593872108 0.0057684630 0.8775040000 108125068 95654128 1782321152 -0.1363980472 -0.0165574010 -0.0749413446 90 1311867173.4262790680 0.0545565337 0.0556882325 0.0593872108 0.0057468067 0.7969040000 108127254 95654128 1783943168 -0.1399706602 -0.0169741455 -0.0749210119 91 1311867173.4622900486 0.0543191135 0.0556731873 0.0593872108 0.0057502096 0.7317600000 108128244 95654128 1783193600 -0.1421236992 -0.0162172429 -0.0755097568 92 1311867173.4943389893 0.0549703985 0.0556655482 0.0593872108 0.0058358041 1.0742380000 108130430 95654128 1782321152 -0.1436935663 -0.0176192559 -0.0753008574 93 1311867173.5263900757 0.0549704917 0.0556580745 0.0593872108 0.0058064894 2.2660570000 108132648 95654128 1783951360 -0.1447359174 -0.0165357664 -0.0759340897 94 1311867173.5624370575 0.0537626296 0.0556379102 0.0593872108 0.0058333411 1.2149800000 108133638 95654128 1783201792 -0.1473668069 -0.0171825644 -0.0768116117 95 1311867173.5943109989 0.0543402061 0.0556242502 0.0593872108 0.0058407242 1.0541000000 108135792 95654128 1782329344 -0.1503979862 -0.0174369980 -0.0766160861 96 1311867173.6263959408 0.0542346984 0.0556097757 0.0593872108 0.0058259275 0.8778460000 108137978 95654128 1783951360 -0.1542816609 -0.0182530079 -0.0766691566 97 1311867173.6623299122 0.0539740585 0.0555929126 0.0593872108 0.0058045025 0.9542080000 108138968 95654128 1783070720 -0.1549789906 -0.0177134443 -0.0778079629 98 1311867173.6943540573 0.0551285632 0.0555881743 0.0593872108 0.0057790884 1.2221820000 108141154 95654128 1782312960 -0.1588711143 -0.0176726598 -0.0777007341 99 1311867173.7267971039 0.0554225147 0.0555865010 0.0593872108 0.0057548793 1.0169440000 108143372 95654128 1783943168 -0.1597618461 -0.0177438706 -0.0780265853 100 1311867173.7623970509 0.0544813760 0.0555754498 0.0593872108 0.0057386479 0.9144870000 108144362 95654128 1785626624 -0.1602898985 -0.0154010626 -0.0807029158 101 1311867173.7943561077 0.0548628829 0.0555683946 0.0593872108 0.0057219811 1.2469930000 108146484 95654128 1783963648 -0.1621924937 -0.0171339810 -0.0803649053 102 1311867173.8265669346 0.0553101897 0.0555658632 0.0593872108 0.0057006635 1.1340710000 108148702 95654128 1783443456 -0.1634290963 -0.0167871621 -0.0808200911 103 1311867173.8635799885 0.0548172556 0.0555585952 0.0593872108 0.0056783679 0.8738330000 108149644 95654128 1785212928 -0.1657581031 -0.0160857793 -0.0826748163 104 1311867173.8946080208 0.0553274564 0.0555563727 0.0593872108 0.0056786396 1.1006880000 108151830 95654128 1783447552 -0.1699153781 -0.0189960450 -0.0822025239 105 1311867173.9266970158 0.0546933226 0.0555481532 0.0593872108 0.0056654236 0.9157170000 108154064 95654128 1783066624 -0.1727369726 -0.0193075705 -0.0835307166 106 1311867173.9625461102 0.0540616922 0.0555341300 0.0593872108 0.0056853356 0.7548440000 108155054 95654128 1784705024 -0.1723008752 -0.0155039160 -0.0858847573 107 1311867173.9944310188 0.0536896065 0.0555168914 0.0593872108 0.0056871402 0.8421200000 108329088 95654128 1783840768 -0.1746742427 -0.0184462834 -0.0853700116 108 1311867174.0264260769 0.0541414358 0.0555041557 0.0593872108 0.0056929105 0.7669520000 108331274 95654128 1783209984 -0.1754577160 -0.0181119703 -0.0858922750 109 1311867174.0624630451 0.0534783043 0.0554855699 0.0593872108 0.0056884022 0.9520810000 108332264 95654128 1784848384 -0.1761000007 -0.0153194815 -0.0878045335 110 1311867174.0945188999 0.0538584553 0.0554707780 0.0593872108 0.0057043389 1.0257280000 108334450 95654128 1783844864 -0.1775941104 -0.0159770697 -0.0875431299 111 1311867174.1264541149 0.0549067110 0.0554656963 0.0593872108 0.0057044388 0.8959540000 108336636 95654128 1782935552 -0.1824406236 -0.0154203670 -0.0875378773 112 1311867174.1624329090 0.0541818850 0.0554542337 0.0593872108 0.0056824675 0.9169590000 108337626 95654128 1784610816 -0.1826354712 -0.0117096780 -0.0904454961 113 1311867174.1943979263 0.0531490184 0.0554338336 0.0593872108 0.0057074633 1.1398100000 108339812 95654128 1783590912 -0.1827432960 -0.0152078979 -0.0890919045 114 1311867174.2267580032 0.0539984219 0.0554212422 0.0593872108 0.0056835822 1.6893350000 108342030 95654128 1782812672 -0.1875070632 -0.0154579477 -0.0885409042 115 1311867174.2626769543 0.0536849722 0.0554061442 0.0593872108 0.0056832081 2.1559770000 108342988 95654128 1784451072 -0.1868792921 -0.0119367000 -0.0902366638 116 1311867174.2945280075 0.0543007217 0.0553966147 0.0593872108 0.0057115997 0.8998330000 108345174 95654128 1783574528 -0.1886403859 -0.0153992036 -0.0885485858 117 1311867174.3265740871 0.0541434139 0.0553859036 0.0593872108 0.0056909060 0.9335690000 108347360 95654128 1782681600 -0.1915687472 -0.0148516465 -0.0894137770 118 1311867174.3624329567 0.0535396151 0.0553702571 0.0593872108 0.0056719102 0.8567560000 108348382 95654128 1784356864 -0.1946952492 -0.0131126828 -0.0908580348 119 1311867174.3946359158 0.0538408719 0.0553574051 0.0593872108 0.0056628016 0.7820820000 108350536 95654128 1783574528 -0.1970368326 -0.0133381952 -0.0904610157 120 1311867174.4266788960 0.0543265454 0.0553488146 0.0593872108 0.0056453762 0.9045810000 108352754 95654128 1782702080 -0.1997717917 -0.0148773259 -0.0894716755 121 1311867174.4630160332 0.0532893017 0.0553317939 0.0593872108 0.0056799664 0.9375630000 108524536 95654128 1784324096 -0.2018149644 -0.0135312798 -0.0908690542 122 1311867174.4945669174 0.0542837493 0.0553232033 0.0593872108 0.0056673206 0.8140600000 108526722 95654128 1783717888 -0.2025564313 -0.0129586020 -0.0899372548 123 1311867174.5267519951 0.0539408997 0.0553119651 0.0593872108 0.0056615578 0.8021390000 108528940 95654128 1782829056 -0.2043891996 -0.0141893886 -0.0894447267 124 1311867174.5623500347 0.0540269576 0.0553016021 0.0593872108 0.0056624255 0.7288560000 108529930 95654128 1784483840 -0.2059770972 -0.0112418532 -0.0906220600 125 1311867174.5944879055 0.0539204292 0.0552905527 0.0593872108 0.0056542734 0.8152920000 108532084 95654128 1783717888 -0.2071164548 -0.0104772914 -0.0905983523 126 1311867174.6265459061 0.0537980907 0.0552787078 0.0593872108 0.0056595203 0.8756820000 108534270 95654128 1782837248 -0.2116306573 -0.0130544920 -0.0893824100 127 1311867174.6624910831 0.0534214564 0.0552640838 0.0593872108 0.0056390949 0.7545750000 108535260 95654128 1784602624 -0.2139445841 -0.0110236360 -0.0905444548 128 1311867174.6945910454 0.0532088280 0.0552480271 0.0593872108 0.0056258178 0.7351160000 108537446 95654128 1783726080 -0.2147743404 -0.0089948121 -0.0910325944 129 1311867174.7265629768 0.0539635755 0.0552380701 0.0593872108 0.0056224916 0.8128610000 108560080 95654128 1782837248 -0.2166261524 -0.0126150344 -0.0885161012 130 1311867174.7623760700 0.0542557389 0.0552305137 0.0593872108 0.0056083950 0.8743950000 108582094 95654128 1784569856 -0.2204513401 -0.0108461492 -0.0893718302 131 1311867174.7944738865 0.0536881052 0.0552187396 0.0593872108 0.0055881299 0.8012840000 108584216 95654128 1783726080 -0.2206824571 -0.0111731468 -0.0894657895 132 1311867174.8273398876 0.0551216565 0.0552180041 0.0593872108 0.0055700747 0.8125400000 108586434 95654128 1782579200 -0.2254074961 -0.0111077195 -0.0887927264 133 1311867174.8624229431 0.0538542233 0.0552077501 0.0593872108 0.0055491172 0.8034670000 108587440 95654128 1784348672 -0.2269458324 -0.0099647325 -0.0909740627 134 1311867174.8944199085 0.0530929156 0.0551919678 0.0593872108 0.0055338371 1.1411620000 108589578 95654128 1783472128 -0.2284037918 -0.0116731143 -0.0910993814 135 1311867174.9270179272 0.0535627976 0.0551798998 0.0593872108 0.0055148341 2.2887310000 108591812 95654128 1782325248 -0.2287308127 -0.0107292011 -0.0910543948 136 1311867174.9626429081 0.0538647175 0.0551702294 0.0593872108 0.0054954607 1.0032460000 108592802 95654128 1784180736 -0.2317237258 -0.0132993609 -0.0903005227 137 1311867174.9943349361 0.0533900224 0.0551572352 0.0593872108 0.0054953863 0.8315580000 108594940 95654128 1783209984 -0.2339088917 -0.0078667253 -0.0938039720 138 1311867175.0265510082 0.0526088737 0.0551387688 0.0593872108 0.0054770428 0.9396090000 108597174 95654128 1782464512 -0.2364141494 -0.0082286233 -0.0943907350 139 1311867175.0633120537 0.0525457226 0.0551201138 0.0593872108 0.0054590635 0.7906100000 108598164 95654128 1784180736 -0.2399640679 -0.0077959984 -0.0947072059 140 1311867175.0947189331 0.0527273379 0.0551030225 0.0593872108 0.0054646931 0.7774130000 108600350 95654128 1783209984 -0.2413482517 -0.0070116902 -0.0943059847 141 1311867175.1265308857 0.0529039875 0.0550874265 0.0593872108 0.0054487156 0.9373580000 108602536 95654128 1782194176 -0.2412216812 -0.0070315185 -0.0929677710 142 1311867175.1625180244 0.0529675856 0.0550724981 0.0593872108 0.0054488736 0.9285680000 108603526 95654128 1783926784 -0.2434723228 -0.0073775821 -0.0926176533 143 1311867175.1946399212 0.0524467081 0.0550541359 0.0593872108 0.0054309718 0.8166890000 108605680 95654128 1785610240 -0.2449476421 -0.0069193267 -0.0930736512 144 1311867175.2270050049 0.0513167083 0.0550281815 0.0593872108 0.0054977581 1.0379520000 108778574 95654128 1784733696 -0.2455521822 -0.0047437809 -0.0938869193 145 1311867175.2624669075 0.0512982868 0.0550024581 0.0593872108 0.0055299487 1.1306060000 108779532 95654128 1784098816 -0.2481161356 -0.0063823308 -0.0926600173 146 1311867175.2944509983 0.0516397990 0.0549794262 0.0593872108 0.0055174606 1.0016700000 108781718 95654128 1785704448 -0.2502306104 -0.0027912287 -0.0932136327 147 1311867175.3267059326 0.0512506552 0.0549540604 0.0593872108 0.0055018385 0.7624890000 108783936 95654128 1784733696 -0.2513915598 -0.0018784464 -0.0924432650 148 1311867175.3625650406 0.0519890264 0.0549340264 0.0593872108 0.0055062586 0.8095290000 108784894 95654128 1783844864 -0.2536948025 -0.0039731194 -0.0901082456 149 1311867175.3945989609 0.0522247441 0.0549158433 0.0593872108 0.0054881394 0.7818770000 108787080 95654128 1785466880 -0.2574791908 -0.0031317815 -0.0900603905 150 1311867175.4266059399 0.0523110405 0.0548984780 0.0593872108 0.0054711668 0.7804990000 108789266 95654128 1783578624 -0.2596337199 -0.0008792845 -0.0901975110 151 1311867175.4625999928 0.0521847121 0.0548805060 0.0593872108 0.0054555836 0.8501570000 108790288 95654128 1783590912 -0.2639670670 -0.0002820819 -0.0899861604 152 1311867175.4945731163 0.0521194413 0.0548623411 0.0593872108 0.0054378572 0.8543410000 108792490 95654128 1785196544 -0.2681343257 -0.0001142722 -0.0899386555 153 1311867175.5264270306 0.0529656447 0.0548499444 0.0593872108 0.0054408932 0.7847430000 108794644 95654128 1784209408 -0.2686964273 0.0017092184 -0.0893071666 154 1311867175.5625700951 0.0518991314 0.0548307833 0.0593872108 0.0054584965 0.9246170000 108966102 95654128 1783336960 -0.2703181207 0.0022262523 -0.0894809887 155 1311867175.5946640968 0.0532826111 0.0548207951 0.0593872108 0.0054859102 0.7783380000 108968256 95654128 1785069568 -0.2753724754 0.0017135625 -0.0884803012 156 1311867175.6264801025 0.0514993630 0.0547995038 0.0593872108 0.0055157724 0.8208050000 108970442 95654128 1783955456 -0.2798380852 0.0026794686 -0.0905768201 157 1311867175.6624929905 0.0516274571 0.0547792997 0.0593872108 0.0055414329 0.8335170000 108971432 95654128 1783083008 -0.2823447585 0.0034683398 -0.0907503590 158 1311867175.6947000027 0.0513835996 0.0547578079 0.0593872108 0.0055580569 0.8152010000 108973618 95654128 1784705024 -0.2867136002 0.0022967639 -0.0903683603 159 1311867175.7273120880 0.0528903678 0.0547460630 0.0593872108 0.0055440511 0.8370670000 108975836 95654128 1783963648 -0.2881442010 0.0060765091 -0.0902947113 160 1311867175.7624969482 0.0520949848 0.0547294938 0.0593872108 0.0055313809 0.8088190000 108976826 95654128 1783091200 -0.2887620926 0.0040638000 -0.0896963552 161 1311867175.7948620319 0.0528737903 0.0547179677 0.0593872108 0.0055339909 1.2668640000 108978980 95654128 1784705024 -0.2931215167 0.0032457486 -0.0887981057 162 1311867175.8287971020 0.0515245646 0.0546982553 0.0593872108 0.0055250578 0.9383670000 108981230 95654128 1782693888 -0.2955418825 0.0038744388 -0.0907906964 163 1311867175.8625519276 0.0520754904 0.0546821647 0.0593872108 0.0055108120 0.7758100000 108982188 95654128 1782829056 -0.3003889322 0.0055337888 -0.0914429203 164 1311867175.8946080208 0.0520388149 0.0546660468 0.0593872108 0.0054982719 1.0094250000 109154770 95654128 1784434688 -0.3028960228 0.0049154297 -0.0914955661 165 1311867175.9282429218 0.0522805899 0.0546515894 0.0593872108 0.0054909825 0.8588510000 109157004 95654128 1783590912 -0.3045987487 0.0043771258 -0.0906553343 166 1311867175.9629371166 0.0524336547 0.0546382284 0.0593872108 0.0054760921 0.8474450000 109157962 95654128 1782837248 -0.3071008623 0.0066349213 -0.0918267518 167 1311867175.9983000755 0.0523389243 0.0546244601 0.0593872108 0.0054614804 1.1128140000 109160180 95654128 1784467456 -0.3105661273 0.0052351272 -0.0915923342 168 1311867176.0268509388 0.0539640561 0.0546205291 0.0593872108 0.0054609229 0.8620010000 109162302 95654128 1783590912 -0.3145714402 0.0044262595 -0.0906922966 169 1311867176.0627059937 0.0524080247 0.0546074374 0.0593872108 0.0055227356 0.8336910000 109163292 95654128 1782702080 -0.3164067566 0.0051638442 -0.0928816199 170 1311867176.0946600437 0.0526494235 0.0545959197 0.0593872108 0.0055749772 0.9016850000 109165446 95654128 1784307712 -0.3179384470 0.0062704543 -0.0940281451 171 1311867176.1268119812 0.0534036681 0.0545889474 0.0593872108 0.0055637530 0.7734950000 109167664 95654128 1783336960 -0.3207167387 0.0071066841 -0.0945895687 172 1311867176.1625900269 0.0535136946 0.0545826960 0.0593872108 0.0056467762 0.8314090000 109339242 95654128 1782444032 -0.3208974004 0.0071368585 -0.0942036584 173 1311867176.1946918964 0.0532523803 0.0545750063 0.0593872108 0.0056963703 0.8360870000 109341428 95654128 1784434688 -0.3211624920 0.0085220132 -0.0957662165 174 1311867176.2265360355 0.0542731211 0.0545732713 0.0593872108 0.0056873677 0.8385370000 109343646 95654128 1783463936 -0.3230563700 0.0092848251 -0.0951374769 175 1311867176.2625019550 0.0539728366 0.0545698402 0.0593872108 0.0056734077 0.8738270000 109344636 95654128 1782575104 -0.3255454004 0.0084461272 -0.0958638042 176 1311867176.2946109772 0.0526487231 0.0545589248 0.0593872108 0.0056616530 0.8393080000 109346790 95654128 1784340480 -0.3280803859 0.0135871023 -0.1006025076 177 1311867176.3266019821 0.0534148104 0.0545524609 0.0593872108 0.0056483376 0.8361080000 109348976 95654128 1783463936 -0.3313313723 0.0111317094 -0.0992694721 178 1311867176.3624560833 0.0533591397 0.0545457568 0.0593872108 0.0056334869 0.8275820000 109349998 95654128 1782575104 -0.3320657909 0.0132860513 -0.1006736010 179 1311867176.3952438831 0.0534385480 0.0545395713 0.0593872108 0.0056234138 0.8128070000 109352152 95654128 1784307712 -0.3330970705 0.0142905861 -0.1013102159 180 1311867176.4268360138 0.0531535447 0.0545318712 0.0593872108 0.0056083072 0.8595230000 109354338 95654128 1783463936 -0.3335606456 0.0168360826 -0.1027893052 181 1311867176.4629659653 0.0529496111 0.0545231294 0.0593872108 0.0056695475 0.8513310000 109355328 95654128 1782575104 -0.3340849578 0.0155275268 -0.1019738093 182 1311867176.4945809841 0.0531074293 0.0545153508 0.0593872108 0.0056727107 0.8656210000 109357482 95654128 1784307712 -0.3373910189 0.0169054903 -0.1044669077 183 1311867176.5266211033 0.0534297675 0.0545094187 0.0593872108 0.0056929020 0.8456940000 109359700 95654128 1783463936 -0.3406025469 0.0183421187 -0.1059037074 184 1311867176.5636389256 0.0543584861 0.0545085984 0.0593872108 0.0056848863 0.8088560000 109360722 95654128 1782575104 -0.3435205519 0.0165400151 -0.1049650833 185 1311867176.5946090221 0.0528695099 0.0544997384 0.0593872108 0.0056704701 0.8975270000 109362876 95654128 1784197120 -0.3441944718 0.0172306038 -0.1071199402 186 1311867176.6283841133 0.0535840131 0.0544948152 0.0593872108 0.0056659522 0.8341980000 109365094 95654128 1783316480 -0.3469379246 0.0185476113 -0.1077351719 187 1311867176.6625781059 0.0527273044 0.0544853633 0.0593872108 0.0056535604 0.9035790000 109366052 95654128 1782575104 -0.3491599858 0.0177928265 -0.1085844487 188 1311867176.6945180893 0.0525985323 0.0544753269 0.0593872108 0.0056394224 0.8406330000 109368206 95654128 1784197120 -0.3510541916 0.0185759701 -0.1094831005 189 1311867176.7265889645 0.0523742363 0.0544642100 0.0593872108 0.0056263258 0.7983340000 109370424 95654128 1783316480 -0.3544533253 0.0193275213 -0.1108689681 190 1311867176.7632329464 0.0530797169 0.0544569232 0.0593872108 0.0056151763 1.1950440000 109541706 95654128 1782575104 -0.3576987982 0.0218512416 -0.1118790582 191 1311867176.7947680950 0.0527242459 0.0544478516 0.0593872108 0.0056082638 0.8935070000 109543860 95654128 1784340480 -0.3603706956 0.0207053665 -0.1120527238 192 1311867176.8266770840 0.0516116731 0.0544330799 0.0593872108 0.0055996694 0.7958900000 109546078 95654128 1783336960 -0.3609664440 0.0192812197 -0.1125056893 193 1311867176.8627309799 0.0521213301 0.0544211019 0.0593872108 0.0055909714 0.8418540000 109547068 95654128 1782427648 -0.3632731438 0.0216909163 -0.1135805547 194 1311867176.8949549198 0.0518812500 0.0544080099 0.0593872108 0.0055801716 0.8457520000 109549254 95654128 1784102912 -0.3682153523 0.0193931479 -0.1136109233 195 1311867176.9268178940 0.0511215739 0.0543911563 0.0593872108 0.0055858315 0.8151290000 109551440 95654128 1783336960 -0.3707111478 0.0200376250 -0.1146538779 196 1311867176.9650609493 0.0508989654 0.0543733390 0.0593872108 0.0055908766 0.8333010000 109552430 95654128 1782427648 -0.3733673394 0.0221155919 -0.1163046286 197 1311867176.9947481155 0.0519858673 0.0543612199 0.0593872108 0.0055772134 0.8601590000 109554584 95654128 1784102912 -0.3766568303 0.0204037372 -0.1146042049 198 1311867177.0267279148 0.0516350642 0.0543474514 0.0593872108 0.0055697445 0.8307160000 109556770 95654128 1783070720 -0.3781035841 0.0215075575 -0.1156920344 199 1311867177.0626339912 0.0518517643 0.0543349103 0.0593872108 0.0055573716 0.7849940000 109557760 95654128 1782329344 -0.3810012639 0.0230355710 -0.1166331097 200 1311867177.0946850777 0.0515517183 0.0543209943 0.0593872108 0.0055458437 1.1597750000 109559946 95654128 1783951360 -0.3825529516 0.0211653430 -0.1160362512 201 1311867177.1266150475 0.0512327738 0.0543056301 0.0593872108 0.0055322764 1.0980520000 109562132 95654128 1785602048 -0.3849583268 0.0223444942 -0.1173218340 202 1311867177.1627299786 0.0514033586 0.0542912624 0.0593872108 0.0055217797 0.9322080000 109563122 95654128 1783992320 -0.3878602386 0.0245564897 -0.1185468882 203 1311867177.1946458817 0.0512738824 0.0542763984 0.0593872108 0.0055147334 0.8149390000 109565308 95654128 1783324672 -0.3895924985 0.0244408641 -0.1185864061 204 1311867177.2264730930 0.0510918759 0.0542607880 0.0593872108 0.0055018073 0.8130690000 109567494 95654128 1784999936 -0.3919920623 0.0236992259 -0.1187345609 205 1311867177.2638640404 0.0509552062 0.0542446632 0.0593872108 0.0054889419 0.8674130000 109568516 95654128 1783218176 -0.3947922885 0.0243405327 -0.1197575033 206 1311867177.2946178913 0.0509469472 0.0542286549 0.0593872108 0.0054940387 0.7643110000 109570670 95654128 1782943744 -0.3963248730 0.0229553636 -0.1187374964 207 1311867177.3276090622 0.0510827191 0.0542134572 0.0593872108 0.0054869726 0.8359790000 109572888 95654128 1784721408 -0.3976864219 0.0262526125 -0.1204126477 208 1311867177.3627710342 0.0511014909 0.0541984958 0.0593872108 0.0054740686 0.7793980000 109744442 95654128 1783844864 -0.4022011757 0.0263334122 -0.1213418692 209 1311867177.3946089745 0.0506333634 0.0541814377 0.0593872108 0.0054772163 0.8285240000 109746628 95654128 1783209984 -0.4039068520 0.0261206273 -0.1220846698 210 1311867177.4312860966 0.0505833402 0.0541643039 0.0593872108 0.0054671570 0.7362700000 109748910 95654128 1784688640 -0.4071044028 0.0261026770 -0.1224585697 211 1311867177.4626040459 0.0505215637 0.0541470398 0.0593872108 0.0054585283 0.7656880000 109749836 95654128 1783574528 -0.4078201056 0.0278644115 -0.1232374981 212 1311867177.4946429729 0.0510908701 0.0541326239 0.0593872108 0.0054514021 1.0155230000 109752022 95654128 1782702080 -0.4113801420 0.0285413750 -0.1235213205 213 1311867177.5276319981 0.0502190404 0.0541142502 0.0593872108 0.0054438504 0.9214060000 109754208 95654128 1784340480 -0.4124140441 0.0305381194 -0.1256165355 214 1311867177.5626399517 0.0498086475 0.0540941306 0.0593872108 0.0054385532 0.8356330000 109755166 95654128 1783336960 -0.4150907993 0.0280108955 -0.1249158233 215 1311867177.5947310925 0.0499037579 0.0540746405 0.0593872108 0.0054311201 0.9361130000 109757352 95654128 1782444032 -0.4163902402 0.0291590169 -0.1255657077 216 1311867177.6311450005 0.0506724603 0.0540588897 0.0593872108 0.0054192450 0.7938380000 109759634 95654128 1784102912 -0.4204056859 0.0294774994 -0.1257605106 217 1311867177.6624829769 0.0503155924 0.0540416394 0.0593872108 0.0054082280 0.7948100000 109760560 95654128 1783336960 -0.4215726256 0.0307832006 -0.1268745363 218 1311867177.6945610046 0.0503904000 0.0540248906 0.0593872108 0.0054194235 0.7933360000 109762746 95654128 1782448128 -0.4229133725 0.0328647308 -0.1278698295 219 1311867177.7305839062 0.0507741049 0.0540100469 0.0593872108 0.0054108228 1.0375120000 109764964 95654128 1784102912 -0.4231037199 0.0352166221 -0.1286519021 220 1311867177.7625379562 0.0506253690 0.0539946620 0.0593872108 0.0054013472 0.7594720000 109765890 95654128 1783336960 -0.4233617783 0.0340730697 -0.1281915903 221 1311867177.7945590019 0.0510154441 0.0539811813 0.0593872108 0.0053901085 0.7869890000 109768076 95654128 1782448128 -0.4262126088 0.0338849872 -0.1290220469 222 1311867177.8309149742 0.0503031984 0.0539646138 0.0593872108 0.0053876128 0.7732470000 109770326 95654128 1784102912 -0.4282693863 0.0325791240 -0.1300786436 223 1311867177.8625319004 0.0505144075 0.0539491421 0.0593872108 0.0053783515 0.9761570000 109771252 95654128 1783336960 -0.4285979867 0.0343737900 -0.1311481744 224 1311867177.8946919441 0.0497750454 0.0539305077 0.0593872108 0.0053777937 0.9153450000 109773406 95654128 1782448128 -0.4287094176 0.0346081816 -0.1323916316 225 1311867177.9317860603 0.0499557219 0.0539128420 0.0593872108 0.0053669060 0.9377150000 109775720 95654128 1784102912 -0.4286293685 0.0351307765 -0.1323553324 226 1311867177.9627909660 0.0504182726 0.0538973793 0.0593872108 0.0053728193 0.7441590000 109776614 95654128 1783062528 -0.4306974709 0.0373672955 -0.1340396404 227 1311867177.9947769642 0.0500798561 0.0538805620 0.0593872108 0.0053614552 0.7835350000 109778736 95654128 1782321152 -0.4323002696 0.0373995155 -0.1351972371 228 1311867178.0306100845 0.0501603447 0.0538642453 0.0593872108 0.0053506411 0.8204860000 109781002 95654128 1783943168 -0.4350642562 0.0359643623 -0.1350722164 229 1311867178.0634479523 0.0496124402 0.0538456784 0.0593872108 0.0053402017 0.7400180000 109781928 95654128 1785593856 -0.4359329343 0.0368737578 -0.1365978420 230 1311867178.0951139927 0.0493090004 0.0538259537 0.0593872108 0.0053286743 0.7482240000 109784114 95654128 1783836672 -0.4371568561 0.0374673419 -0.1375246346 231 1311867178.1307909489 0.0516545512 0.0538165537 0.0593872108 0.0053200289 0.7505940000 109786364 95654128 1783463936 -0.4412415624 0.0377601534 -0.1360508651 232 1311867178.1627469063 0.0506360754 0.0538028448 0.0593872108 0.0053248674 0.9159520000 109959130 95654128 1785085952 -0.4414263368 0.0395661145 -0.1385514438 233 1311867178.1950459480 0.0511368178 0.0537914026 0.0593872108 0.0053183243 0.7784060000 109961284 95654128 1783468032 -0.4451051652 0.0401538312 -0.1393518150 234 1311867178.2307190895 0.0519844480 0.0537836806 0.0593872108 0.0053092649 0.7921680000 109963534 95654128 1782956032 -0.4486342669 0.0383281298 -0.1382431984 235 1311867178.2628939152 0.0505395606 0.0537698758 0.0593872108 0.0053042869 0.8529360000 109964492 95654128 1784578048 -0.4486816823 0.0403346308 -0.1406374872 236 1311867178.2954900265 0.0490714461 0.0537499672 0.0593872108 0.0052972424 0.7817880000 109966678 95654128 1782804480 -0.4506510794 0.0378720276 -0.1409410685 237 1311867178.3306670189 0.0498602204 0.0537335548 0.0593872108 0.0052883226 0.7309970000 109968896 95654128 1782448128 -0.4548486471 0.0381103568 -0.1409953982 238 1311867178.3627231121 0.0494635962 0.0537156138 0.0593872108 0.0052777492 0.7210600000 109969854 95654128 1784111104 -0.4564160407 0.0397780165 -0.1421652287 239 1311867178.3949439526 0.0482998751 0.0536929538 0.0593872108 0.0052708249 0.9085990000 109972008 95654128 1783328768 -0.4576436579 0.0375940129 -0.1418399215 240 1311867178.4306581020 0.0486692041 0.0536720215 0.0593872108 0.0052700945 0.7310420000 109974258 95654128 1782456320 -0.4598143101 0.0404135883 -0.1431523710 241 1311867178.4628739357 0.0491349362 0.0536531954 0.0593872108 0.0052593922 0.7375890000 109975184 95654128 1784111104 -0.4618790150 0.0405731462 -0.1425060630 242 1311867178.4946439266 0.0486280546 0.0536324304 0.0593872108 0.0052500752 0.7170090000 109977370 95654128 1783218176 -0.4645104110 0.0403797179 -0.1431667656 243 1311867178.5306270123 0.0481329560 0.0536097988 0.0593872108 0.0052440763 0.7530550000 109979620 95654128 1782562816 -0.4677267671 0.0416966639 -0.1449800134 244 1311867178.5626420975 0.0490656383 0.0535911752 0.0593872108 0.0052335107 0.7565730000 110151830 95654128 1784315904 -0.4702941179 0.0410367288 -0.1433247775 245 1311867178.5947000980 0.0505570173 0.0535787909 0.0593872108 0.0052238088 0.7764150000 110154032 95654128 1783595008 -0.4735176563 0.0419057608 -0.1427449584 246 1311867178.6306900978 0.0500829928 0.0535645803 0.0593872108 0.0052136374 1.0181250000 110156250 95654128 1782837248 -0.4709035456 0.0440117046 -0.1429124475 247 1311867178.6626410484 0.0496873520 0.0535488830 0.0593872108 0.0052244875 0.9424170000 110157208 95654128 1784569856 -0.4724267721 0.0419172123 -0.1416349411 248 1311867178.6946120262 0.0492493920 0.0535315464 0.0593872108 0.0052149774 0.7177250000 110159362 95654128 1783578624 -0.4749730825 0.0408809334 -0.1422737688 249 1311867178.7307450771 0.0491475649 0.0535139400 0.0593872108 0.0052108117 0.7306430000 110161612 95654128 1782964224 -0.4751594663 0.0443487056 -0.1445633024 250 1311867178.7632350922 0.0492765047 0.0534969903 0.0593872108 0.0052043443 0.8647190000 110162570 95654128 1784569856 -0.4794189334 0.0413218513 -0.1438232809 251 1311867178.8006799221 0.0503974073 0.0534846413 0.0593872108 0.0051966987 0.7299650000 110164820 95654128 1783582720 -0.4796901941 0.0438412055 -0.1440552175 252 1311867178.8309500217 0.0497796200 0.0534699389 0.0593872108 0.0051865906 0.7499450000 110166974 95654128 1782685696 -0.4785304070 0.0463752262 -0.1460752785 253 1311867178.8627939224 0.0493842140 0.0534537898 0.0593872108 0.0051836714 0.8155960000 110167932 95654128 1784324096 -0.4786030948 0.0421036780 -0.1433317661 254 1311867178.8952279091 0.0502713583 0.0534412605 0.0593872108 0.0051744152 0.9171650000 110170118 95654128 1783443456 -0.4786432981 0.0414636359 -0.1423575729 255 1311867178.9306209087 0.0499823093 0.0534276960 0.0593872108 0.0051711546 0.8557830000 110172336 95654128 1782448128 -0.4754516780 0.0434241854 -0.1438909769 256 1311867178.9627609253 0.0507779382 0.0534173454 0.0593872108 0.0051613549 0.8779990000 110173294 95654128 1784070144 -0.4786927998 0.0422281735 -0.1436450630 257 1311867178.9946830273 0.0502595566 0.0534050582 0.0593872108 0.0051529987 0.7517300000 110216440 95654128 1783189504 -0.4848946035 0.0436383709 -0.1480305195 258 1311867179.0309159756 0.0504953004 0.0533937801 0.0593872108 0.0051516953 0.8560080000 110260674 95654128 1782448128 -0.4887785614 0.0456300899 -0.1511038393 259 1311867179.0628120899 0.0509839505 0.0533844758 0.0593872108 0.0051486544 1.1920590000 110261632 95654128 1784180736 -0.4899497330 0.0425551273 -0.1486014873 260 1311867179.0968201160 0.0510305241 0.0533754221 0.0593872108 0.0051485432 1.6041530000 110263818 95654128 1783336960 -0.4851949513 0.0400474407 -0.1457182318 261 1311867179.1310369968 0.0502961539 0.0533636241 0.0593872108 0.0051414364 1.0713000000 110266020 95654128 1782448128 -0.4825708270 0.0429199971 -0.1486089081 262 1311867179.1627540588 0.0523813814 0.0533598751 0.0593872108 0.0052057222 0.7405330000 110437426 95654128 1784180736 -0.4864413738 0.0403646231 -0.1474395245 263 1311867179.1957008839 0.0504592843 0.0533488463 0.0593872108 0.0051980882 0.8324770000 110439612 95654128 1783463936 -0.4901311100 0.0423678942 -0.1532983631 264 1311867179.2307469845 0.0508938283 0.0533395469 0.0593872108 0.0051933967 0.8325120000 110441830 95654128 1782575104 -0.4951657653 0.0444268808 -0.1569711268 265 1311867179.2634611130 0.0511576943 0.0533313135 0.0593872108 0.0051981127 0.7620660000 110442820 95654128 1784229888 -0.4999955893 0.0414527021 -0.1567282677 266 1311867179.2959330082 0.0503573902 0.0533201334 0.0593872108 0.0051894394 0.7521540000 110444974 95654128 1783463936 -0.4995429218 0.0435400903 -0.1587777436 267 1311867179.3307149410 0.0502050258 0.0533084663 0.0593872108 0.0051799615 0.8109790000 110447192 95654128 1782575104 -0.4978575706 0.0436921790 -0.1578261256 268 1311867179.3629300594 0.0490282476 0.0532924953 0.0593872108 0.0051721693 0.8427670000 110448182 95654128 1784229888 -0.4977244139 0.0433130041 -0.1586768627 269 1311867179.3948490620 0.0499838330 0.0532801955 0.0593872108 0.0051636795 0.8768420000 110450304 95654128 1783463936 -0.5030962229 0.0435277522 -0.1597863734 270 1311867179.4308040142 0.0495451912 0.0532663621 0.0593872108 0.0051577466 0.8726280000 110452586 95654128 1782575104 -0.5039368868 0.0473859869 -0.1628009081 271 1311867179.4637460709 0.0483491533 0.0532482174 0.0593872108 0.0051751759 0.8897940000 110453544 95654128 1784197120 -0.5047534704 0.0444934405 -0.1607636362 272 1311867179.4949469566 0.0495241396 0.0532345260 0.0593872108 0.0051665884 0.7559830000 110455698 95654128 1783447552 -0.5048065782 0.0467815623 -0.1599066257 273 1311867179.5307800770 0.0486615188 0.0532177750 0.0593872108 0.0051606645 0.8737710000 110457948 95654128 1782575104 -0.5049092770 0.0487444215 -0.1609677374 274 1311867179.5627610683 0.0483047552 0.0531998443 0.0593872108 0.0051737166 0.7638150000 110458874 95654128 1784197120 -0.5061141253 0.0474602990 -0.1595796347 275 1311867179.5946741104 0.0473028198 0.0531784006 0.0593872108 0.0051643320 0.8084800000 110461060 95654128 1783447552 -0.5073814988 0.0492007844 -0.1618352085 276 1311867179.6306900978 0.0481292568 0.0531601066 0.0593872108 0.0051746472 0.7324920000 110463278 95654128 1782575104 -0.5108857751 0.0505493954 -0.1621769667 277 1311867179.6625750065 0.0485393815 0.0531434253 0.0593872108 0.0051657122 0.7766640000 110464236 95654128 1784197120 -0.5111467242 0.0493787825 -0.1599342078 278 1311867179.6946051121 0.0489730351 0.0531284239 0.0593872108 0.0051753846 0.7721190000 110466390 95654128 1783455744 -0.5106921196 0.0524329878 -0.1605820060 279 1311867179.7309470177 0.0492995866 0.0531147004 0.0593872108 0.0051675338 0.7963360000 110468672 95654128 1782583296 -0.5122320056 0.0515692346 -0.1594221741 280 1311867179.7627270222 0.0489358567 0.0530997760 0.0593872108 0.0051920514 0.8547570000 110639970 95654128 1784205312 -0.5120824575 0.0523991510 -0.1596712768 281 1311867179.7948911190 0.0475962833 0.0530801906 0.0593872108 0.0051913998 0.8377500000 110642124 95654128 1783345152 -0.5138744116 0.0532138608 -0.1624273509 282 1311867179.8307530880 0.0476258397 0.0530608489 0.0593872108 0.0051836202 0.7349490000 110644406 95654128 1782456320 -0.5146886110 0.0522339940 -0.1609703004 283 1311867179.8627979755 0.0481294543 0.0530434235 0.0593872108 0.0051750054 0.7340300000 110645332 95654128 1783951360 -0.5167106390 0.0502064414 -0.1588971168 284 1311867179.8948040009 0.0481740795 0.0530262779 0.0593872108 0.0051673216 0.7361580000 110647518 95654128 1785593856 -0.5153439641 0.0523734353 -0.1591823101 285 1311867179.9309051037 0.0493659712 0.0530134348 0.0593872108 0.0051895529 0.8359040000 110649768 95654128 1783582720 -0.5152223110 0.0552872121 -0.1592392474 286 1311867179.9635379314 0.0498928055 0.0530025235 0.0593872108 0.0051881564 0.7184460000 110650726 95654128 1783463936 -0.5182863474 0.0522211492 -0.1567541659 287 1311867179.9958879948 0.0489184223 0.0529882931 0.0593872108 0.0051800712 0.9093200000 110652880 95654128 1785085952 -0.5182145238 0.0559223443 -0.1602439433 288 1311867180.0309770107 0.0480282977 0.0529710709 0.0593872108 0.0051730872 0.7256840000 110655130 95654128 1783074816 -0.5186164379 0.0562100857 -0.1607280523 289 1311867180.0626471043 0.0490961932 0.0529576631 0.0593872108 0.0051655519 0.9652270000 110656056 95654128 1782702080 -0.5202900171 0.0558026917 -0.1590105593 290 1311867180.0947730541 0.0490835123 0.0529443039 0.0593872108 0.0051579084 0.7571030000 110658210 95654128 1784451072 -0.5193780661 0.0573339202 -0.1596610248 291 1311867180.1307730675 0.0503652655 0.0529354412 0.0593872108 0.0051492252 0.7506210000 110660460 95654128 1783590912 -0.5174151063 0.0576591529 -0.1577702016 292 1311867180.1636900902 0.0497540757 0.0529245462 0.0593872108 0.0051605595 0.7375160000 110661450 95654128 1782427648 -0.5147285461 0.0566598400 -0.1572396904 293 1311867180.1949090958 0.0493927971 0.0529124924 0.0593872108 0.0051522206 0.8124830000 110663572 95654128 1784102912 -0.5133013129 0.0550077409 -0.1567599028 294 1311867180.2308139801 0.0503261574 0.0529036953 0.0593872108 0.0051463622 0.9043330000 110665790 95654128 1783336960 -0.5136138201 0.0560418367 -0.1577883959 295 1311867180.2637619972 0.0491749421 0.0528910555 0.0593872108 0.0051627974 0.7654060000 110666748 95654128 1782448128 -0.5150222778 0.0552089661 -0.1602556407 296 1311867180.2947549820 0.0492090434 0.0528786163 0.0593872108 0.0051551496 0.7747770000 110668902 95654128 1784102912 -0.5157277584 0.0549926758 -0.1609275043 297 1311867180.3308670521 0.0489835665 0.0528655016 0.0593872108 0.0051501450 0.7529660000 110671152 95654128 1783336960 -0.5135107636 0.0544748530 -0.1605528146 298 1311867180.3658289909 0.0496352091 0.0528546617 0.0593872108 0.0051423584 0.8648740000 110672110 95654128 1782173696 -0.5092903972 0.0557062589 -0.1598776579 299 1311867180.3964109421 0.0492722169 0.0528426803 0.0593872108 0.0051353960 0.8000030000 110674296 95654128 1783832576 -0.5085346699 0.0547957011 -0.1600810587 300 1311867180.4309151173 0.0491716675 0.0528304436 0.0593872108 0.0051276606 0.8795730000 110676514 95654128 1785577472 -0.5098428726 0.0545662716 -0.1613520533 301 1311867180.4670670033 0.0492868088 0.0528186707 0.0593872108 0.0051207385 1.1735160000 110677504 95654128 1784590336 -0.5095802546 0.0559217706 -0.1627401859 302 1311867180.4947559834 0.0495962091 0.0528080003 0.0593872108 0.0051320186 0.9237290000 110679692 95654128 1783717888 -0.5085573792 0.0544276945 -0.1614068300 303 1311867180.5308880806 0.0500871688 0.0527990207 0.0593872108 0.0051253930 0.8010710000 110681974 95654128 1785339904 -0.5071244836 0.0563419238 -0.1619720161 304 1311867180.5629510880 0.0496407896 0.0527886318 0.0593872108 0.0051196359 0.8033360000 110682900 95654128 1783328768 -0.5055462718 0.0557244644 -0.1616208106 305 1311867180.5946910381 0.0495293699 0.0527779457 0.0593872108 0.0051151468 0.8233370000 110685226 95654128 1783209984 -0.5036684871 0.0562585443 -0.1616823971 306 1311867180.6308128834 0.0496593602 0.0527677542 0.0593872108 0.0051087519 0.8859390000 110686216 95654128 1784832000 -0.5036606789 0.0556518510 -0.1613317281 307 1311867180.6640911102 0.0485432036 0.0527539934 0.0593872108 0.0051347142 0.9012380000 110688402 95654128 1782951936 -0.5014773011 0.0550190248 -0.1610385329 308 1311867180.6957859993 0.0492807329 0.0527427166 0.0593872108 0.0051269519 0.8933850000 110690588 95654128 1782681600 -0.5025095344 0.0556024462 -0.1612231433 309 1311867180.7309739590 0.0496552028 0.0527327247 0.0593872108 0.0051265908 0.7824300000 110691578 95654128 1784451072 -0.5014370680 0.0565222092 -0.1611053199 310 1311867180.7650830746 0.0494617708 0.0527221732 0.0593872108 0.0051380823 0.8273440000 110693796 95654128 1783463936 -0.5014281273 0.0545874275 -0.1600502878 311 1311867180.7949280739 0.0491882190 0.0527108100 0.0593872108 0.0051371286 0.8145370000 110696058 95654128 1782554624 -0.4990316033 0.0565270148 -0.1608784348 312 1311867180.8309240341 0.0499268547 0.0527018871 0.0593872108 0.0051298702 0.7840340000 110697080 95654128 1784229888 -0.4992087781 0.0565699600 -0.1601160020 313 1311867180.8652698994 0.0500545464 0.0526934291 0.0593872108 0.0051226632 0.8082600000 110699298 95654128 1783463936 -0.4979481101 0.0566202886 -0.1595047563 314 1311867180.8966469765 0.0490510911 0.0526818293 0.0593872108 0.0051178211 0.8466950000 110701484 95654128 1782583296 -0.4965867698 0.0547567420 -0.1594496369 315 1311867180.9306049347 0.0490916297 0.0526704319 0.0593872108 0.0051258216 0.8313370000 110702426 95654128 1784205312 -0.4965972304 0.0549784265 -0.1597055495 316 1311867180.9631829262 0.0492453836 0.0526595931 0.0593872108 0.0051229725 0.8842430000 110704612 95654128 1783455744 -0.4957150519 0.0560546778 -0.1603198647 317 1311867180.9948179722 0.0486098975 0.0526468180 0.0593872108 0.0051178112 0.9963260000 110706906 95654128 1782566912 -0.4927422702 0.0555944070 -0.1598170996 318 1311867181.0308310986 0.0495258942 0.0526370038 0.0593872108 0.0051110032 0.8434350000 110707896 95654128 1784205312 -0.4925378263 0.0549555346 -0.1587538272 319 1311867181.0627830029 0.0510065518 0.0526318927 0.0593872108 0.0051127613 0.8392260000 110710114 95654128 1783336960 -0.4909001291 0.0573725663 -0.1591258347 320 1311867181.0948719978 0.0495751649 0.0526223404 0.0593872108 0.0051235147 0.7530070000 110712300 95654128 1782448128 -0.4861163497 0.0565293022 -0.1586683095 321 1311867181.1311910152 0.0493734553 0.0526122193 0.0593872108 0.0051199528 0.7550850000 110713290 95654128 1784102912 -0.4835918844 0.0550445206 -0.1577590555 322 1311867181.1629528999 0.0506913066 0.0526062537 0.0593872108 0.0051385445 0.8498710000 110715476 95654128 1783336960 -0.4822014868 0.0554508530 -0.1571710408 323 1311867181.1972830296 0.0505439192 0.0525998688 0.0593872108 0.0051318788 0.7754440000 110716574 95654128 1782173696 -0.4806872606 0.0556918457 -0.1579027921 324 1311867181.2342460155 0.0503878444 0.0525930415 0.0593872108 0.0051264178 0.8350860000 110718856 95654128 1783848960 -0.4789053202 0.0540336818 -0.1575700194 325 1311867181.2629361153 0.0510894097 0.0525884150 0.0593872108 0.0051193430 0.7958410000 110720978 95654128 1785593856 -0.4775963724 0.0557603091 -0.1582476497 326 1311867181.2948091030 0.0500053801 0.0525804915 0.0593872108 0.0051154977 0.8379180000 110721872 95654128 1783578624 -0.4727830589 0.0548086576 -0.1574708968 327 1311867181.3317139149 0.0503402166 0.0525736405 0.0593872108 0.0051102352 0.7742680000 110724154 95654128 1783463936 -0.4721580148 0.0548098087 -0.1573402733 328 1311867181.3626708984 0.0499667153 0.0525656926 0.0593872108 0.0051100551 0.8513720000 110726308 95654128 1785085952 -0.4688641131 0.0564270243 -0.1580500007 329 1311867181.3948218822 0.0494535677 0.0525562333 0.0593872108 0.0051030629 0.8162880000 110727374 95654128 1784352768 -0.4685190022 0.0538353175 -0.1569979489 330 1311867181.4308950901 0.0503893793 0.0525496670 0.0593872108 0.0050969710 0.9135000000 110729560 95654128 1783463936 -0.4662307203 0.0558014922 -0.1570286155 331 1311867181.4628310204 0.0511152297 0.0525453334 0.0593872108 0.0050917080 0.8365630000 110731746 95654128 1785229312 -0.4643658996 0.0555969886 -0.1561926007 332 1311867181.4963610172 0.0506836101 0.0525397258 0.0593872108 0.0051019207 0.7882830000 110732704 95654128 1784352768 -0.4624018371 0.0552941263 -0.1559867263 333 1311867181.5359110832 0.0511302836 0.0525354932 0.0593872108 0.0050975196 0.8190840000 110734986 95654128 1783463936 -0.4614166915 0.0531914122 -0.1546999663 334 1311867181.5671720505 0.0503689386 0.0525290065 0.0593872108 0.0050904033 0.8300980000 110737140 95654128 1785102336 -0.4570493996 0.0529523566 -0.1549382359 335 1311867181.5948610306 0.0515546314 0.0525260980 0.0593872108 0.0050901230 0.8360850000 110738110 95654128 1784098816 -0.4565973580 0.0555681959 -0.1558318287 336 1311867181.6313591003 0.0504997112 0.0525200670 0.0593872108 0.0050899528 0.8557490000 110740408 95654128 1782935552 -0.4558743834 0.0522639751 -0.1557241976 337 1311867181.6628570557 0.0519616380 0.0525184100 0.0593872108 0.0050851154 0.8354780000 110742594 95654128 1784483840 -0.4551590979 0.0522299111 -0.1553790867 338 1311867181.6949229240 0.0500899665 0.0525112252 0.0593872108 0.0050910927 0.8206830000 110743488 95654128 1783717888 -0.4507861137 0.0522739328 -0.1571106613 339 1311867181.7310829163 0.0527679697 0.0525119826 0.0593872108 0.0051256124 0.8147490000 110745738 95654128 1782829056 -0.4503562748 0.0507280678 -0.1543421447 340 1311867181.7634840012 0.0522480197 0.0525112062 0.0593872108 0.0051202024 0.7978640000 110747956 95654128 1784451072 -0.4489473999 0.0509223044 -0.1558159739 341 1311867181.7948980331 0.0520509183 0.0525098564 0.0593872108 0.0051215402 0.8684960000 110748958 95654128 1783463936 -0.4466357231 0.0511821806 -0.1569094658 342 1311867181.8308010101 0.0519899912 0.0525083363 0.0593872108 0.0051177107 0.7520410000 110751208 95654128 1782575104 -0.4454697371 0.0486590080 -0.1559706032 343 1311867181.8627979755 0.0527224429 0.0525089606 0.0593872108 0.0051134949 0.8165270000 110752166 95654128 1784197120 -0.4442848861 0.0506849475 -0.1567325741 344 1311867181.8949289322 0.0514774658 0.0525059620 0.0593872108 0.0051110614 0.8689920000 110754320 95654128 1783447552 -0.4404530823 0.0480172448 -0.1558052003 345 1311867181.9307990074 0.0520123504 0.0525045313 0.0593872108 0.0051146053 0.8548380000 110756602 95654128 1782575104 -0.4400386810 0.0469535328 -0.1556704640 346 1311867181.9629189968 0.0514648966 0.0525015265 0.0593872108 0.0051084113 0.8116060000 110757528 95654128 1784197120 -0.4383611381 0.0472789221 -0.1568700373 347 1311867181.9955599308 0.0516148508 0.0524989713 0.0593872108 0.0051296938 0.8583870000 110759854 95654128 1783336960 -0.4357354641 0.0458862633 -0.1546954662 348 1311867182.0320639610 0.0527015589 0.0524995534 0.0593872108 0.0051234339 0.8251860000 110762104 95654128 1782304768 -0.4338744283 0.0476933457 -0.1545637548 349 1311867182.0629000664 0.0517073087 0.0524972834 0.0593872108 0.0051183790 0.8083110000 110763030 95654128 1783943168 -0.4326632321 0.0456639864 -0.1544583440 350 1311867182.0948839188 0.0523521155 0.0524968686 0.0593872108 0.0051244006 0.8473900000 110765184 95654128 1783070720 -0.4312287569 0.0466690175 -0.1545385718 351 1311867182.1314840317 0.0520232432 0.0524955193 0.0593872108 0.0051181067 0.8968140000 110767466 95654128 1782075392 -0.4283619523 0.0448731668 -0.1531158090 352 1311867182.1629920006 0.0526927449 0.0524960796 0.0593872108 0.0051129940 0.8151510000 110768392 95654128 1783697408 -0.4269683361 0.0467522256 -0.1536267549 353 1311867182.1994500160 0.0528536513 0.0524970925 0.0593872108 0.0051086423 0.8173110000 110770734 95654128 1785380864 -0.4248065352 0.0450876802 -0.1519885063 354 1311867182.2307739258 0.0526397340 0.0524974955 0.0593872108 0.0051082059 0.8534400000 110772888 95654128 1783476224 -0.4223920703 0.0441569164 -0.1513766497 355 1311867182.2629120350 0.0535283424 0.0525003993 0.0593872108 0.0051023599 0.8014880000 110773846 95654128 1783488512 -0.4229685962 0.0441271290 -0.1511468142 356 1311867182.2973539829 0.0531062558 0.0525021011 0.0593872108 0.0050995605 0.9054590000 110776064 95654128 1785077760 -0.4199710190 0.0419511236 -0.1500457823 357 1311867182.3308460712 0.0538107865 0.0525057669 0.0593872108 0.0051189047 0.8132840000 110778250 95654128 1783963648 -0.4204221964 0.0426725298 -0.1507422030 358 1311867182.3629670143 0.0537443645 0.0525092267 0.0593872108 0.0051399974 0.8535920000 110779208 95654128 1783091200 -0.4172624946 0.0424695872 -0.1498440206 359 1311867182.3990368843 0.0544647500 0.0525146738 0.0593872108 0.0051453247 0.8062800000 110781566 95654128 1784696832 -0.4170357287 0.0417496450 -0.1492224485 360 1311867182.4308118820 0.0561910830 0.0525248860 0.0593872108 0.0051394378 0.7831030000 110782492 95654128 1783709696 -0.4162238836 0.0414754748 -0.1478759050 361 1311867182.4629440308 0.0553789623 0.0525327921 0.0593872108 0.0051349284 0.9530470000 110784710 95654128 1782829056 -0.4134884775 0.0399589576 -0.1481039375 362 1311867182.4969599247 0.0577638969 0.0525472426 0.0593872108 0.0051305621 0.7770940000 110786912 95654128 1784434688 -0.4115059376 0.0392512083 -0.1459720284 363 1311867182.5309500694 0.0576795116 0.0525613811 0.0593872108 0.0051264636 0.8186350000 110787870 95654128 1783209984 -0.4108108580 0.0383530520 -0.1472893953 364 1311867182.5629699230 0.0577563979 0.0525756531 0.0593872108 0.0051249107 0.8101880000 110790056 95654128 1782431744 -0.4092718661 0.0391502418 -0.1494733095 365 1311867182.6036369801 0.0586525686 0.0525923022 0.0593872108 0.0051205195 0.8340480000 110792510 95654128 1784070144 -0.4093327820 0.0374951400 -0.1492943019 366 1311867182.6308450699 0.0578032695 0.0526065398 0.0593872108 0.0051373207 0.8150560000 110793340 95654128 1785720832 -0.4064835608 0.0367350690 -0.1504348516 367 1311867182.6635921001 0.0585323200 0.0526226864 0.0593872108 0.0051316083 0.8391130000 110795558 95654128 1783709696 -0.4061345756 0.0374414250 -0.1512700915 368 1311867182.6970019341 0.0587196648 0.0526392543 0.0593872108 0.0051287352 0.9109030000 110797744 95654128 1783590912 -0.4025557041 0.0356320404 -0.1504083127 369 1311867182.7330639362 0.0595620684 0.0526580153 0.0595620684 0.0051230236 0.8892830000 110969270 95654128 1785196544 -0.4016260505 0.0354094170 -0.1510326713 370 1311867182.7631130219 0.0594502725 0.0526763727 0.0595620684 0.0051171424 0.9192910000 110971360 95654128 1784352768 -0.3986784816 0.0349843577 -0.1512227058 371 1311867182.7970550060 0.0602686927 0.0526968372 0.0602686927 0.0051108573 0.9146230000 110973750 95654128 1783353344 -0.3963547051 0.0348193385 -0.1507922411 372 1311867182.8306989670 0.0594076850 0.0527148771 0.0602686927 0.0051043925 1.0532040000 110974676 95654128 1784848384 -0.3946314454 0.0335800350 -0.1519402415 373 1311867182.8641169071 0.0586079210 0.0527306762 0.0602686927 0.0051105598 1.0368790000 110976862 95654128 1783701504 -0.3929462731 0.0323400386 -0.1522514522 374 1311867182.8969969749 0.0580076948 0.0527447858 0.0602686927 0.0051039763 0.8834100000 110979080 95654128 1782575104 -0.3917638063 0.0323027968 -0.1536194980 375 1311867182.9318990707 0.0567291006 0.0527554107 0.0602686927 0.0051031285 0.8401850000 110980038 95654128 1784180736 -0.3890846670 0.0322365500 -0.1546096355 376 1311867182.9630720615 0.0575310774 0.0527681119 0.0602686927 0.0050970290 0.8171850000 110982224 95654128 1783209984 -0.3875414431 0.0325159319 -0.1536100805 377 1311867182.9983949661 0.0600369386 0.0527873926 0.0602686927 0.0051321109 0.8527010000 110983322 95654128 1782046720 -0.3866497576 0.0326546542 -0.1508792490 378 1311867183.0308830738 0.0609546080 0.0528089990 0.0609546080 0.0051259175 0.8568780000 110985508 95654128 1783721984 -0.3859285712 0.0331847854 -0.1505638659 379 1311867183.0628600121 0.0583472662 0.0528236119 0.0609546080 0.0051328120 0.8542260000 110987726 95654128 1785577472 -0.3804741800 0.0318854190 -0.1510424912 380 1311867183.1000499725 0.0602993257 0.0528432848 0.0609546080 0.0051385910 0.8168820000 110988684 95654128 1784590336 -0.3792634010 0.0319712870 -0.1484953016 381 1311867183.1344780922 0.0600219667 0.0528621265 0.0609546080 0.0051326193 0.8128260000 110990934 95654128 1783447552 -0.3783288896 0.0333830379 -0.1501285285 382 1311867183.1673240662 0.0593528524 0.0528791179 0.0609546080 0.0051261657 0.9236380000 110993152 95654128 1785085952 -0.3771171868 0.0324398093 -0.1501549929 383 1311867183.2004919052 0.0601603650 0.0528981290 0.0609546080 0.0051197283 0.8396200000 110994218 95654128 1783062528 -0.3742711544 0.0309981946 -0.1470046043 384 1311867183.2311279774 0.0591710173 0.0529144646 0.0609546080 0.0051141990 0.9544040000 110996372 95654128 1782956032 -0.3712346256 0.0314859971 -0.1477988958 385 1311867183.2633349895 0.0593835376 0.0529312674 0.0609546080 0.0051077444 0.8656600000 110998590 95654128 1784561664 -0.3716703653 0.0298470333 -0.1473587155 386 1311867183.2991099358 0.0610324107 0.0529522548 0.0610324107 0.0051090755 0.8383660000 110999548 95654128 1783590912 -0.3695804477 0.0305617433 -0.1454260349 387 1311867183.3320920467 0.0601801202 0.0529709315 0.0610324107 0.0051057702 0.8125700000 111001766 95654128 1782681600 -0.3682753742 0.0304624327 -0.1469618380 388 1311867183.3695240021 0.0608998686 0.0529913669 0.0610324107 0.0050998130 0.7733720000 111004048 95654128 1784324096 -0.3686625659 0.0282595810 -0.1460933387 389 1311867183.3986210823 0.0622855462 0.0530152594 0.0622855462 0.0050954018 1.0129360000 111005050 95654128 1783599104 -0.3672530949 0.0284442473 -0.1447706223 390 1311867183.4311549664 0.0607277267 0.0530350349 0.0622855462 0.0050934631 0.9351430000 111007236 95654128 1782583296 -0.3643933833 0.0286269598 -0.1468235403 391 1311867183.4667448997 0.0597710870 0.0530522627 0.0622855462 0.0050899788 0.7931110000 111009486 95654128 1784188928 -0.3609817922 0.0275492277 -0.1468726546 392 1311867183.4988338947 0.0615653992 0.0530739799 0.0622855462 0.0050937906 0.8378420000 111010444 95654128 1783087104 -0.3606705964 0.0272064917 -0.1448038369 393 1311867183.5321829319 0.0613380596 0.0530950081 0.0622855462 0.0050927764 0.8725870000 111012630 95654128 1782075392 -0.3585402071 0.0275056809 -0.1449679583 394 1311867183.5661609173 0.0589960515 0.0531099853 0.0622855462 0.0050903060 0.8156860000 111185608 95654128 1783681024 -0.3542804718 0.0261362176 -0.1457861215 395 1311867183.5985479355 0.0623926446 0.0531334857 0.0623926446 0.0050875842 0.8392200000 111186674 95654128 1785491456 -0.3554549813 0.0263461731 -0.1433527023 396 1311867183.6310880184 0.0622100346 0.0531564063 0.0623926446 0.0051008834 1.0543590000 111188860 95654128 1784459264 -0.3530356288 0.0274025239 -0.1441222131 397 1311867183.6649260521 0.0610571504 0.0531763074 0.0623926446 0.0050964194 0.8060720000 111189818 95654128 1783332864 -0.3502602875 0.0244380087 -0.1429488808 398 1311867183.6993949413 0.0627586320 0.0532003836 0.0627586320 0.0050949838 0.8188350000 111192068 95654128 1784958976 -0.3488290608 0.0249809045 -0.1414808780 399 1311867183.7308928967 0.0623031557 0.0532231976 0.0627586320 0.0050898733 0.8167500000 111194190 95654128 1783971840 -0.3450681567 0.0255730134 -0.1416458786 400 1311867183.7676479816 0.0625738204 0.0532465742 0.0627586320 0.0050921196 0.8472650000 111195212 95654128 1782824960 -0.3439056873 0.0241470840 -0.1406468898 401 1311867183.7971870899 0.0632499084 0.0532715201 0.0632499084 0.0050861618 0.8309720000 111197474 95654128 1784451072 -0.3426562548 0.0238029882 -0.1397597194 402 1311867183.8309071064 0.0627056435 0.0532949881 0.0632499084 0.0050805554 0.7996750000 111199660 95654128 1783463936 -0.3391684294 0.0235524848 -0.1393674612 403 1311867183.8655049801 0.0625960305 0.0533180676 0.0632499084 0.0050750094 0.8311610000 111200618 95654128 1782317056 -0.3366844654 0.0207661279 -0.1373889595 404 1311867183.8970971107 0.0622695796 0.0533402248 0.0632499084 0.0050701793 0.8333220000 111202772 95654128 1784053760 -0.3358748555 0.0211066995 -0.1385721117 405 1311867183.9314939976 0.0624892004 0.0533628149 0.0632499084 0.0050643908 0.8033570000 111205022 95654128 1785704448 -0.3338127732 0.0200699829 -0.1373035908 406 1311867183.9658319950 0.0622278638 0.0533846500 0.0632499084 0.0050612986 0.8284030000 111205948 95654128 1784713216 -0.3320165873 0.0195227470 -0.1370014101 407 1311867183.9966781139 0.0630708560 0.0534084490 0.0632499084 0.0050593173 0.8205510000 111208274 95654128 1783717888 -0.3316195607 0.0192299113 -0.1365811974 408 1311867184.0309689045 0.0632581338 0.0534325904 0.0632581338 0.0050811506 0.8039910000 111210492 95654128 1785339904 -0.3302663863 0.0192579981 -0.1366423666 409 1311867184.0647850037 0.0636414737 0.0534575510 0.0636414737 0.0050754592 0.8360120000 111211450 95654128 1783558144 -0.3296771944 0.0184135437 -0.1356483847 410 1311867184.0968890190 0.0625810400 0.0534798034 0.0636414737 0.0050715275 0.8206900000 111213604 95654128 1783209984 -0.3251273632 0.0190968569 -0.1357121617 411 1311867184.1312260628 0.0634782165 0.0535041304 0.0636414737 0.0050661341 0.7740380000 111215822 95654128 1784832000 -0.3251001537 0.0188849512 -0.1350141913 412 1311867184.1650640965 0.0633122548 0.0535279366 0.0636414737 0.0050602761 0.8227610000 111216748 95654128 1783189504 -0.3219033778 0.0183737949 -0.1338041872 413 1311867184.1969559193 0.0632620975 0.0535515060 0.0636414737 0.0050549049 0.8120440000 111219106 95654128 1782681600 -0.3214615285 0.0183656439 -0.1344768256 414 1311867184.2309360504 0.0622648969 0.0535725528 0.0636414737 0.0050501587 0.7949840000 111220064 95654128 1784451072 -0.3187885582 0.0159323905 -0.1332691759 415 1311867184.2681369781 0.0629972592 0.0535952629 0.0636414737 0.0050460530 0.8938940000 111222346 95654128 1783590912 -0.3176278174 0.0142388195 -0.1318152994 416 1311867184.2983899117 0.0636379793 0.0536194041 0.0636414737 0.0050490211 0.8523430000 111224500 95654128 1782321152 -0.3142963946 0.0187887345 -0.1330875009 417 1311867184.3314700127 0.0627366602 0.0536412680 0.0636414737 0.0050449934 0.9569950000 111395826 95654128 1783926784 -0.3121162355 0.0157599095 -0.1314761341 418 1311867184.3697841167 0.0628690273 0.0536633440 0.0636414737 0.0050446429 1.0495830000 111398108 95654128 1785483264 -0.3115988672 0.0143502699 -0.1315620244 419 1311867184.4000220299 0.0637452006 0.0536874057 0.0637452006 0.0050772873 0.8379970000 111400402 95654128 1784332288 -0.3083449900 0.0180504415 -0.1326398402 420 1311867184.4310610294 0.0628404096 0.0537091986 0.0637452006 0.0050784914 0.8367570000 111401328 95654128 1783463936 -0.3062306345 0.0162639767 -0.1325040758 421 1311867184.4655809402 0.0635626465 0.0537326034 0.0637452006 0.0050733588 0.9321610000 111403546 95654128 1785069568 -0.3044998348 0.0134328865 -0.1301946044 422 1311867184.5037670135 0.0628205985 0.0537541390 0.0637452006 0.0051276771 0.8877330000 111405828 95654128 1784098816 -0.2998145521 0.0127042560 -0.1305772662 423 1311867184.5310881138 0.0635722205 0.0537773496 0.0637452006 0.0051658333 0.8589360000 111406690 95654128 1783209984 -0.2967684269 0.0143580679 -0.1314748526 424 1311867184.5682930946 0.0637750402 0.0538009290 0.0637750402 0.0051638749 0.8281760000 111408972 95654128 1784815616 -0.2941172719 0.0132408207 -0.1313539594 425 1311867184.6018071175 0.0641217157 0.0538252132 0.0641217157 0.0051579059 0.9747820000 111411298 95654128 1783824384 -0.2924526930 0.0121797407 -0.1309591830 426 1311867184.6367399693 0.0629963800 0.0538467418 0.0641217157 0.0051566540 0.8334120000 111412288 95654128 1782812672 -0.2894585729 0.0109074088 -0.1315728575 427 1311867184.6662440300 0.0631327778 0.0538684889 0.0641217157 0.0051600066 0.8030820000 111414410 95654128 1784451072 -0.2869350314 0.0082660336 -0.1294888854 428 1311867184.6994929314 0.0627318621 0.0538891977 0.0641217157 0.0051548544 0.7834240000 111416660 95654128 1783590912 -0.2838742733 0.0082777832 -0.1298306435 429 1311867184.7359158993 0.0639301389 0.0539126032 0.0641217157 0.0051577211 0.9744300000 111417586 95654128 1782566912 -0.2826344967 0.0084969709 -0.1295663416 430 1311867184.7690689564 0.0632443652 0.0539343050 0.0641217157 0.0051601210 0.9499380000 111419836 95654128 1784188928 -0.2792689800 0.0050731720 -0.1275876611 431 1311867184.8001279831 0.0618658327 0.0539527076 0.0641217157 0.0051661420 0.8375100000 111420870 95654128 1783201792 -0.2747600675 0.0039417837 -0.1273726225 432 1311867184.8348441124 0.0620350465 0.0539714167 0.0641217157 0.0051604197 0.8523100000 111423056 95654128 1782075392 -0.2723128200 0.0037833005 -0.1269279867 433 1311867184.8690660000 0.0626671463 0.0539914992 0.0641217157 0.0051552897 0.7951750000 111425274 95654128 1783681024 -0.2707230747 0.0023899768 -0.1251818389 434 1311867184.9055209160 0.0636983961 0.0540138654 0.0641217157 0.0051539063 0.7727760000 111426200 95654128 1785364480 -0.2679087520 0.0044367532 -0.1248183548 435 1311867184.9332280159 0.0626525208 0.0540337243 0.0641217157 0.0051554500 0.8205480000 111428322 95654128 1784360960 -0.2657960057 0.0019849516 -0.1238495559 436 1311867184.9656410217 0.0627800226 0.0540537846 0.0641217157 0.0051506079 0.8112200000 111430508 95654128 1783328768 -0.2617080808 0.0002496731 -0.1204690039 437 1311867184.9983251095 0.0623043031 0.0540726646 0.0641217157 0.0051467479 0.8306120000 111431606 95654128 1784950784 -0.2600523829 -0.0005736049 -0.1204552725 438 1311867185.0360550880 0.0639965236 0.0540953218 0.0641217157 0.0051435305 0.8583930000 111433856 95654128 1783824384 -0.2570163310 -0.0001307932 -0.1175386906 439 1311867185.0652348995 0.0629961193 0.0541155969 0.0641217157 0.0051390256 0.9315580000 111436010 95654128 1782829056 -0.2512125373 -0.0016795842 -0.1151763126 440 1311867185.0991280079 0.0625756904 0.0541348244 0.0641217157 0.0051378587 0.7742100000 111436968 95654128 1784434688 -0.2490137964 -0.0017034735 -0.1149732769 441 1311867185.1360778809 0.0615560785 0.0541516527 0.0641217157 0.0051333199 0.8364240000 111439218 95654128 1783463936 -0.2453135252 -0.0036153314 -0.1132586226 442 1311867185.1648709774 0.0627249777 0.0541710493 0.0641217157 0.0051281439 0.8571940000 111612044 95654128 1782194176 -0.2424240708 -0.0042962246 -0.1099231839 443 1311867185.2000720501 0.0633132756 0.0541916864 0.0641217157 0.0051238951 0.7895120000 111613110 95654128 1783959552 -0.2394571006 -0.0032785472 -0.1090152934 444 1311867185.2342920303 0.0643941984 0.0542146650 0.0643941984 0.0051284889 0.8119780000 111615360 95654128 1785704448 -0.2374241203 -0.0038681712 -0.1067425758 445 1311867185.2663950920 0.0635830089 0.0542357175 0.0643941984 0.0051244990 0.9882610000 111672578 95654128 1784586240 -0.2328919023 -0.0060508046 -0.1044695452 446 1311867185.2970550060 0.0635202825 0.0542565349 0.0643941984 0.0051533522 0.9623570000 111673536 95654128 1783590912 -0.2287371159 -0.0043255482 -0.1036509499 447 1311867185.3360140324 0.0620712638 0.0542740175 0.0643941984 0.0051497984 1.1520120000 111675882 95654128 1785323520 -0.2245462984 -0.0075529199 -0.1014911607 448 1311867185.3681778908 0.0619764328 0.0542912104 0.0643941984 0.0051441084 0.8986580000 111678164 95654128 1784225792 -0.2225204557 -0.0088927401 -0.1004279405 449 1311867185.4036509991 0.0629337505 0.0543104588 0.0643941984 0.0051414515 1.0086990000 111679454 95654128 1783062528 -0.2206928581 -0.0085979244 -0.0992352515 450 1311867185.4386389256 0.0628296584 0.0543293904 0.0643941984 0.0051357715 1.0747000000 111681736 95654128 1784815616 -0.2166180164 -0.0076331696 -0.0983897224 451 1311867185.4655449390 0.0632974878 0.0543492753 0.0643941984 0.0051342540 0.9346170000 111682630 95654128 1783717888 -0.2136511356 -0.0113465637 -0.0947081521 452 1311867185.5013909340 0.0632983670 0.0543690742 0.0643941984 0.0051450322 0.9753950000 111684944 95654128 1782554624 -0.2113359571 -0.0107387006 -0.0950483307 453 1311867185.5336329937 0.0623996705 0.0543868018 0.0643941984 0.0051509873 0.9926690000 111687194 95654128 1784213504 -0.2072872221 -0.0112057952 -0.0947648436 454 1311867185.5666799545 0.0626810938 0.0544050711 0.0643941984 0.0051467523 0.9540540000 111688344 95654128 1783209984 -0.2045823634 -0.0143733360 -0.0923928320 455 1311867185.5970540047 0.0622253269 0.0544222585 0.0643941984 0.0051435168 1.2110920000 111690818 95654128 1782177792 -0.1998358369 -0.0143681625 -0.0918120891 456 1311867185.6329469681 0.0621929988 0.0544392996 0.0643941984 0.0051519015 1.3417440000 111693004 95654128 1783799808 -0.1968328506 -0.0148455175 -0.0917686298 457 1311867185.6664180756 0.0626764745 0.0544573240 0.0643941984 0.0051515902 1.1437010000 111693994 95654128 1785450496 -0.1944502592 -0.0154184550 -0.0908960178 458 1311867185.6973390579 0.0630603135 0.0544761079 0.0643941984 0.0051475583 0.7950970000 111696180 95654128 1784479744 -0.1921855807 -0.0156445764 -0.0901299790 459 1311867185.7351899147 0.0635976046 0.0544959804 0.0643941984 0.0051460483 1.0718460000 111699070 95654128 1783316480 -0.1898368746 -0.0152017847 -0.0892537534 460 1311867185.7649769783 0.0617556125 0.0545117622 0.0643941984 0.0051450240 1.0556790000 111870708 95654128 1784975360 -0.1837825477 -0.0192570053 -0.0867136866 461 1311867185.7989649773 0.0629951060 0.0545301643 0.0643941984 0.0051659808 0.8988070000 111873162 95654128 1784233984 -0.1824330240 -0.0187035091 -0.0862427577 462 1311867185.8327999115 0.0638542250 0.0545503462 0.0643941984 0.0051621784 1.0715590000 111875476 95654128 1783218176 -0.1793740243 -0.0173284523 -0.0852799267 463 1311867185.8649098873 0.0634592995 0.0545695880 0.0643941984 0.0051569634 1.1118290000 111876466 95654128 1784696832 -0.1754928678 -0.0177188739 -0.0842912346 464 1311867185.9030420780 0.0639232025 0.0545897467 0.0643941984 0.0051534757 0.8191240000 111878716 95654128 1783582720 -0.1741693020 -0.0189118795 -0.0828230381 465 1311867185.9396789074 0.0615033954 0.0546046147 0.0643941984 0.0051539540 0.9523020000 111881126 95654128 1782456320 -0.1696140319 -0.0208325256 -0.0824596137 466 1311867185.9650609493 0.0600230284 0.0546162422 0.0643941984 0.0051669032 1.0522480000 111882084 95654128 1784053760 -0.1656861752 -0.0253557898 -0.0798704177 467 1311867186.0039470196 0.0613971986 0.0546307625 0.0643941984 0.0051735975 1.0710900000 111884474 95654128 1783083008 -0.1646728665 -0.0241197310 -0.0792413726 468 1311867186.0396919250 0.0621390529 0.0546468058 0.0643941984 0.0051750038 1.1327370000 111885656 95654128 1781940224 -0.1651852578 -0.0230191164 -0.0794033185 469 1311867186.0653240681 0.0626984611 0.0546639735 0.0643941984 0.0051748074 1.0938400000 111887842 95654128 1783418880 -0.1636711508 -0.0249896888 -0.0766471177 470 1311867186.1047339439 0.0612543188 0.0546779955 0.0643941984 0.0051713784 1.0360280000 111890188 95654128 1785102336 -0.1612624824 -0.0261801705 -0.0770347193 471 1311867186.1361179352 0.0609891377 0.0546913950 0.0643941984 0.0051676289 0.9800270000 111891018 95654128 1784098816 -0.1587108225 -0.0272047035 -0.0761435628 472 1311867186.1649448872 0.0616076961 0.0547060482 0.0643941984 0.0051624555 0.9517480000 111893364 95654128 1782935552 -0.1582707316 -0.0279379655 -0.0753415972 473 1311867186.2044749260 0.0617519319 0.0547209443 0.0643941984 0.0051571248 0.8718850000 111895882 95654128 1784594432 -0.1575948596 -0.0290986206 -0.0750201270 474 1311867186.2359659672 0.0628080815 0.0547380058 0.0643941984 0.0051543429 1.0786200000 111896840 95654128 1783590912 -0.1549509615 -0.0279762056 -0.0737151876 475 1311867186.2674899101 0.0627471879 0.0547548672 0.0643941984 0.0051489494 0.9546320000 111898962 95654128 1782702080 -0.1528958976 -0.0294034500 -0.0729001313 476 1311867186.3030838966 0.0633479059 0.0547729199 0.0643941984 0.0051462889 1.1306780000 111901276 95654128 1784307712 -0.1510576010 -0.0285481643 -0.0725587681 477 1311867186.3349270821 0.0627111718 0.0547895619 0.0643941984 0.0051460220 1.0160630000 111902362 95654128 1783316480 -0.1479213983 -0.0295910910 -0.0714403763 478 1311867186.3670160770 0.0638785288 0.0548085765 0.0643941984 0.0051455792 1.0636950000 111904580 95654128 1782321152 -0.1477023065 -0.0313391313 -0.0693741664 479 1311867186.4019849300 0.0635787249 0.0548268857 0.0643941984 0.0051481281 1.1360700000 111907002 95654128 1783926784 -0.1449202597 -0.0298572686 -0.0699138120 480 1311867186.4360210896 0.0612201057 0.0548402050 0.0643941984 0.0051447369 1.0927070000 111907768 95654128 1785577472 -0.1403554082 -0.0321041048 -0.0691349804 481 1311867186.4659481049 0.0626971871 0.0548565396 0.0643941984 0.0051401825 1.0023800000 111910242 95654128 1784606720 -0.1403083950 -0.0348382480 -0.0656947047 482 1311867186.5031139851 0.0624180250 0.0548722274 0.0643941984 0.0051372686 0.9518360000 112082964 95654128 1783463936 -0.1371582747 -0.0337268934 -0.0656268746 483 1311867186.5363171101 0.0607654974 0.0548844288 0.0643941984 0.0051343700 1.1416040000 112084146 95654128 1785196544 -0.1337573826 -0.0346967839 -0.0654192418 484 1311867186.5651130676 0.0630008727 0.0549011983 0.0643941984 0.0051296716 0.9975270000 112086492 95654128 1784205312 -0.1342103481 -0.0356905758 -0.0626129732 485 1311867186.6014220715 0.0639931634 0.0549199446 0.0643941984 0.0051271929 0.8761070000 112087686 95654128 1783062528 -0.1343025416 -0.0357921720 -0.0625894666 486 1311867186.6362628937 0.0652643293 0.0549412293 0.0652643293 0.0051229266 0.9147450000 112089968 95654128 1784815616 -0.1329426318 -0.0336555764 -0.0628514439 487 1311867186.6650478840 0.0640099049 0.0549598508 0.0652643293 0.0051182715 0.9757430000 112092270 95654128 1783697408 -0.1294093281 -0.0340876803 -0.0633144379 488 1311867186.7043809891 0.0567211695 0.0549634601 0.0652643293 0.0052485705 1.8062900000 112181372 95654128 1784070144 -0.1184477359 -0.0438724793 -0.0627035126 489 1311867186.7337749004 0.0589370653 0.0549715861 0.0652643293 0.0052713367 1.2732070000 112184450 95654128 1783197696 -0.1181593686 -0.0367579423 -0.0645699948 490 1311867186.7673180103 0.0580484383 0.0549778654 0.0652643293 0.0052665093 1.1115650000 112186732 95654128 1782202368 -0.1173308790 -0.0393480584 -0.0641441718 491 1311867186.8047299385 0.0578567684 0.0549837287 0.0652643293 0.0052648106 1.0164630000 112187706 95654128 1783808000 -0.1149512529 -0.0414083563 -0.0633299276 492 1311867186.8340749741 0.0603043959 0.0549945431 0.0652643293 0.0052749925 1.1983110000 112190004 95654128 1785491456 -0.1134736612 -0.0338178650 -0.0648064837 493 1311867186.8775999546 0.0587908775 0.0550022436 0.0652643293 0.0052733001 1.1344530000 112363846 95654128 1784479744 -0.1108732969 -0.0357949585 -0.0651416183 494 1311867186.9052100182 0.0609792061 0.0550143427 0.0652643293 0.0052705345 1.0542420000 112364804 95654128 1783447552 -0.1106583849 -0.0330982320 -0.0644819364 495 1311867186.9334239960 0.0610325411 0.0550265006 0.0652643293 0.0052653643 0.9748630000 112367066 95654128 1784942592 -0.1061179712 -0.0315498225 -0.0642761663 496 1311867186.9663379192 0.0602362975 0.0550370043 0.0652643293 0.0052614080 0.9760120000 112369284 95654128 1783844864 -0.1041989177 -0.0305109490 -0.0657989979 497 1311867187.0017139912 0.0620307140 0.0550510761 0.0652643293 0.0052586555 1.0883290000 112370242 95654128 1782812672 -0.1018038318 -0.0314537287 -0.0631599873 498 1311867187.0336461067 0.0618043691 0.0550646370 0.0652643293 0.0052583760 0.9953330000 112372492 95654128 1784426496 -0.0965949148 -0.0281556305 -0.0648672432 499 1311867187.0749349594 0.0613591634 0.0550772512 0.0652643293 0.0052532168 1.0998320000 112545370 95654128 1783328768 -0.0957726985 -0.0279836506 -0.0658241585 500 1311867187.1016030312 0.0612188317 0.0550895344 0.0652643293 0.0052498282 1.0100090000 112546360 95654128 1782165504 -0.0934977531 -0.0295196176 -0.0649526939 501 1311867187.1342070103 0.0627551526 0.0551048350 0.0652643293 0.0052457790 1.0344680000 112549006 95654128 1783918592 -0.0898731649 -0.0302988105 -0.0629204810 502 1311867187.1710209846 0.0629830211 0.0551205286 0.0652643293 0.0052517172 1.0562900000 112550304 95654128 1785569280 -0.0859545097 -0.0256929006 -0.0652657449 503 1311867187.2041370869 0.0602790304 0.0551307841 0.0652643293 0.0052665890 0.8765270000 112722962 95654128 1784582144 -0.0827130377 -0.0304267071 -0.0660866126 504 1311867187.2331659794 0.0629054457 0.0551462100 0.0652643293 0.0052716603 1.0163640000 112725244 95654128 1783455744 -0.0806916282 -0.0278982967 -0.0648120940 505 1311867187.2707629204 0.0581266843 0.0551521119 0.0652643293 0.0052782327 0.8690270000 112726234 95654128 1785061376 -0.0764888898 -0.0320194177 -0.0673883930 506 1311867187.3015060425 0.0586203039 0.0551589661 0.0652643293 0.0052791856 0.9763710000 112728548 95654128 1783943168 -0.0749094933 -0.0319424719 -0.0668811277 507 1311867187.3336570263 0.0625553653 0.0551735546 0.0652643293 0.0052928122 0.9362160000 112730906 95654128 1782927360 -0.0738085285 -0.0264761392 -0.0660674497 508 1311867187.3707590103 0.0589709915 0.0551810299 0.0652643293 0.0053012352 0.9071480000 112731928 95654128 1784553472 -0.0703723952 -0.0320646465 -0.0669936389 509 1311867187.4033529758 0.0599317700 0.0551903634 0.0652643293 0.0052995310 0.9363080000 112734146 95654128 1783435264 -0.0710438490 -0.0310753360 -0.0673186928 510 1311867187.4335899353 0.0591413304 0.0551981104 0.0652643293 0.0053012704 1.1899160000 112736492 95654128 1782439936 -0.0671503320 -0.0317501500 -0.0678011775 511 1311867187.4763159752 0.0610104166 0.0552094848 0.0652643293 0.0053048282 0.9971730000 112737642 95654128 1784045568 -0.0670436174 -0.0289951731 -0.0686876178 512 1311867187.5056400299 0.0628807321 0.0552244677 0.0652643293 0.0053017143 0.9366740000 112739828 95654128 1783074816 -0.0655250698 -0.0284595694 -0.0681729689 513 1311867187.5342190266 0.0636002868 0.0552407948 0.0652643293 0.0053023023 0.8735580000 112824042 95654128 1781932032 -0.0619721375 -0.0267952234 -0.0692584440 514 1311867187.5709679127 0.0633478239 0.0552565672 0.0652643293 0.0052976814 0.9112490000 112909000 95654128 1783537664 -0.0583262183 -0.0276316628 -0.0701659247 515 1311867187.6045789719 0.0629492477 0.0552715045 0.0652643293 0.0053242297 0.8559890000 112911250 95654128 1785315328 -0.0561490655 -0.0272605717 -0.0717300102 516 1311867187.6353919506 0.0636731386 0.0552877867 0.0652643293 0.0053246106 1.0585140000 112913660 95654128 1784197120 -0.0546321645 -0.0282043535 -0.0720625371 517 1311867187.6707689762 0.0622515306 0.0553012562 0.0652643293 0.0053246641 0.9721300000 112914618 95654128 1783201792 -0.0502057597 -0.0264077000 -0.0753582492 518 1311867187.7035770416 0.0605238341 0.0553113384 0.0652643293 0.0053236501 0.8974020000 112917080 95654128 1784807424 -0.0466290563 -0.0317233652 -0.0750258937 519 1311867187.7345480919 0.0612653904 0.0553228106 0.0652643293 0.0053228857 1.0489790000 113088786 95654128 1783820288 -0.0436538421 -0.0331277363 -0.0740402639 520 1311867187.7707819939 0.0605827197 0.0553329258 0.0652643293 0.0053213075 1.0133080000 113091020 95654128 1782693888 -0.0406491533 -0.0272687264 -0.0784290135 521 1311867187.8017508984 0.0592232831 0.0553403929 0.0652643293 0.0053255851 0.8548910000 113093206 95654128 1784299520 -0.0398283489 -0.0325596072 -0.0779404566 522 1311867187.8339610100 0.0605736338 0.0553504183 0.0652643293 0.0053257913 0.9019460000 113094132 95654128 1783193600 -0.0389353149 -0.0297398791 -0.0787054002 523 1311867187.8708090782 0.0593172982 0.0553580031 0.0652643293 0.0053380516 0.8680160000 113096382 95654128 1782067200 -0.0339591093 -0.0299055353 -0.0794685334 524 1311867187.9038810730 0.0597068816 0.0553663025 0.0652643293 0.0053375474 0.8909970000 113098632 95654128 1783681024 -0.0310354196 -0.0276684873 -0.0804227069 525 1311867187.9363000393 0.0595166683 0.0553742080 0.0652643293 0.0053329298 0.8982710000 113099666 95654128 1785364480 -0.0286149047 -0.0289200228 -0.0804468542 526 1311867187.9713420868 0.0613174960 0.0553855070 0.0652643293 0.0053303202 0.8971150000 113101916 95654128 1784360960 -0.0274153259 -0.0285007600 -0.0801056027 527 1311867188.0047569275 0.0617279001 0.0553975419 0.0652643293 0.0053539323 0.9522060000 113104134 95654128 1783218176 -0.0226895474 -0.0253901966 -0.0820983946 528 1311867188.0333108902 0.0624921061 0.0554109786 0.0652643293 0.0053654822 0.9148110000 113104996 95654128 1784856576 -0.0209237840 -0.0260947999 -0.0818808526 529 1311867188.0698699951 0.0633894950 0.0554260608 0.0652643293 0.0053617112 0.8968610000 113107214 95654128 1783832576 -0.0166874826 -0.0260917246 -0.0821808875 530 1311867188.1088800430 0.0629636869 0.0554402828 0.0652643293 0.0053619001 0.9926450000 113109576 95654128 1783074816 -0.0145705147 -0.0256179944 -0.0846294537 531 1311867188.1359970570 0.0615788400 0.0554518431 0.0652643293 0.0053741269 0.9586160000 113110546 95654128 1784594432 -0.0107949842 -0.0249651019 -0.0862015039 532 1311867188.1703350544 0.0639053807 0.0554677332 0.0652643293 0.0053715596 1.1122480000 113112764 95654128 1783590912 -0.0070418017 -0.0260760393 -0.0854247063 533 1311867188.2026720047 0.0630763322 0.0554820083 0.0652643293 0.0053741576 1.0170720000 113114982 95654128 1782427648 -0.0049891151 -0.0264532845 -0.0877649859 534 1311867188.2352449894 0.0625987649 0.0554953355 0.0652643293 0.0053817131 0.8686140000 113115876 95654128 1784086528 -0.0017852122 -0.0255351327 -0.0894704089 535 1311867188.2706460953 0.0631528050 0.0555096486 0.0652643293 0.0053834640 0.9177840000 113288170 95654128 1783083008 0.0017370507 -0.0266895629 -0.0897728354 536 1311867188.3047339916 0.0632238910 0.0555240408 0.0652643293 0.0053792650 0.9083420000 113290420 95654128 1782173696 0.0046646427 -0.0275686048 -0.0905095264 537 1311867188.3398799896 0.0634297207 0.0555387627 0.0652643293 0.0053755891 1.0527700000 113291550 95654128 1783689216 0.0082595199 -0.0247764848 -0.0927104726 538 1311867188.3718800545 0.0625216886 0.0555517422 0.0652643293 0.0053712949 0.8694690000 113293704 95654128 1785450496 0.0114658596 -0.0249030888 -0.0938024148 539 1311867188.4054470062 0.0618468560 0.0555634214 0.0652643293 0.0053772310 0.8429640000 113294630 95654128 1784336384 0.0155316610 -0.0257248580 -0.0938811526 540 1311867188.4398789406 0.0631179959 0.0555774114 0.0652643293 0.0053737479 0.9523500000 113296880 95654128 1783209984 0.0177720115 -0.0252338350 -0.0932518020 541 1311867188.4724500179 0.0619932748 0.0555892706 0.0652643293 0.0053717983 1.0585800000 113299066 95654128 1784815616 0.0223037452 -0.0218101889 -0.0963778570 542 1311867188.5049159527 0.0610896721 0.0555994190 0.0652643293 0.0053816782 0.9837270000 113299992 95654128 1783844864 0.0247016661 -0.0247784629 -0.0955523625 543 1311867188.5389990807 0.0622420311 0.0556116521 0.0652643293 0.0053775070 0.9857240000 113472538 95654128 1782681600 0.0272870008 -0.0232963450 -0.0952605754 544 1311867188.5723888874 0.0611274876 0.0556217915 0.0652643293 0.0053799652 0.9311840000 113474956 95654128 1784561664 0.0319511369 -0.0194024853 -0.0983019024 545 1311867188.6045958996 0.0604824983 0.0556307103 0.0652643293 0.0053767619 0.9002480000 113475882 95654128 1783443456 0.0325141549 -0.0245923381 -0.0963925719 546 1311867188.6398339272 0.0621353537 0.0556426235 0.0652643293 0.0053729165 1.0987080000 113478068 95654128 1782431744 0.0367338248 -0.0222491231 -0.0960320532 547 1311867188.6715080738 0.0626868904 0.0556555015 0.0652643293 0.0053749357 0.9230330000 113480286 95654128 1784053760 0.0391427316 -0.0204284508 -0.0971585140 548 1311867188.7038300037 0.0639055446 0.0556705564 0.0652643293 0.0053709192 0.8223300000 113481212 95654128 1785577472 0.0409821905 -0.0216564499 -0.0961940661 549 1311867188.7393829823 0.0647634491 0.0556871190 0.0652643293 0.0053692910 0.9723070000 113655834 95654128 1784606720 0.0440827198 -0.0219786316 -0.0963069052 550 1311867188.7721049786 0.0639211237 0.0557020899 0.0652643293 0.0053654973 0.9124630000 113658052 95654128 1783717888 0.0478735790 -0.0199766979 -0.0996395797 551 1311867188.8045220375 0.0640060976 0.0557171607 0.0652643293 0.0053636994 0.9327870000 113659010 95654128 1785196544 0.0522092544 -0.0201949775 -0.1006455496 552 1311867188.8402431011 0.0657652244 0.0557353637 0.0657652244 0.0053651590 0.8567290000 113832696 95654128 1784098816 0.0549741052 -0.0223107599 -0.0996595770 553 1311867188.8705990314 0.0642313734 0.0557507272 0.0657652244 0.0053606145 0.9882450000 113834850 95654128 1783209984 0.0593184456 -0.0214613993 -0.1032083929 554 1311867188.9016311169 0.0632581413 0.0557642785 0.0657652244 0.0053583099 0.8529980000 113835776 95654128 1784688640 0.0616081320 -0.0219806843 -0.1050555557 555 1311867188.9401769638 0.0649513081 0.0557808317 0.0657652244 0.0053545863 1.0988370000 113838230 95654128 1783590912 0.0649260208 -0.0236294605 -0.1041897088 556 1311867188.9709990025 0.0630011931 0.0557938180 0.0657652244 0.0053512113 1.0530830000 114009708 95654128 1782427648 0.0704058930 -0.0242823139 -0.1065440625 557 1311867189.0052258968 0.0627894849 0.0558063775 0.0657652244 0.0053467357 0.8338600000 114011958 95654128 1784307712 0.0767288283 -0.0231775194 -0.1075994521 558 1311867189.0400099754 0.0636791363 0.0558204864 0.0657652244 0.0053453163 0.8384290000 114014260 95654128 1783320576 0.0800379589 -0.0244559143 -0.1066957042 559 1311867189.0724329948 0.0629176348 0.0558331826 0.0657652244 0.0053435924 0.8301460000 114015250 95654128 1782194176 0.0833516642 -0.0252479371 -0.1072453633 560 1311867189.1026360989 0.0620724894 0.0558443242 0.0657652244 0.0053400428 0.8143730000 114017404 95654128 1783808000 0.0882309005 -0.0242715515 -0.1081799343 561 1311867189.1417639256 0.0623621456 0.0558559424 0.0657652244 0.0053372568 0.8477380000 114019858 95654128 1785475072 0.0906948894 -0.0250963196 -0.1068467870 562 1311867189.1717920303 0.0622075014 0.0558672441 0.0657652244 0.0053349226 0.8603030000 114020752 95654128 1784487936 0.0913271978 -0.0253866930 -0.1060196012 563 1311867189.2019069195 0.0627653152 0.0558794965 0.0657652244 0.0053303687 0.8531730000 114193150 95654128 1783455744 0.0936636254 -0.0240113139 -0.1053417772 564 1311867189.2390630245 0.0618659072 0.0558901107 0.0657652244 0.0053261891 0.8547790000 114195400 95654128 1785204736 0.0956526473 -0.0263978429 -0.1041813642 565 1311867189.2722640038 0.0618895479 0.0559007291 0.0657652244 0.0053217351 1.0319360000 114196326 95654128 1784233984 0.0968199894 -0.0271227658 -0.1032172665 566 1311867189.3046789169 0.0617170334 0.0559110053 0.0657652244 0.0053213682 0.8957940000 114198544 95654128 1783345152 0.1018879861 -0.0281525888 -0.1020047292 567 1311867189.3397970200 0.0619493276 0.0559216549 0.0657652244 0.0053224690 0.9134470000 114200902 95654128 1784975360 0.1047614440 -0.0297462903 -0.1000505686 568 1311867189.3720359802 0.0625657737 0.0559333523 0.0657652244 0.0053663714 0.8171180000 114201812 95654128 1783971840 0.1064362526 -0.0292034075 -0.0997778103 569 1311867189.4056949615 0.0616929866 0.0559434747 0.0657652244 0.0053739792 1.0734310000 114204030 95654128 1782808576 0.1102377251 -0.0297770128 -0.0995582193 570 1311867189.4405019283 0.0627540052 0.0559554230 0.0657652244 0.0053724037 0.9149580000 114206248 95654128 1784561664 0.1132927611 -0.0325699747 -0.0966276079 571 1311867189.4729130268 0.0630309358 0.0559678144 0.0657652244 0.0053683827 1.0005740000 114207206 95654128 1783590912 0.1191372350 -0.0336535536 -0.0961434618 572 1311867189.5060400963 0.0630750284 0.0559802396 0.0657652244 0.0053671952 0.9340140000 114209392 95654128 1782448128 0.1206433177 -0.0334622934 -0.0961859971 573 1311867189.5394289494 0.0626384243 0.0559918595 0.0657652244 0.0053636536 0.8581020000 114210458 95654128 1784086528 0.1252190471 -0.0381348208 -0.0949652940 574 1311867189.5720269680 0.0628160760 0.0560037484 0.0657652244 0.0053608989 0.9731110000 114212676 95654128 1783083008 0.1298180073 -0.0406131409 -0.0946527645 575 1311867189.6112909317 0.0629463568 0.0560158225 0.0657652244 0.0053578614 0.8342420000 114385534 95654128 1781792768 0.1348850131 -0.0387902856 -0.0966266766 576 1311867189.6424219608 0.0627085790 0.0560274418 0.0657652244 0.0053534342 0.8947400000 114386460 95654128 1783799808 0.1385726333 -0.0406696089 -0.0964601338 577 1311867189.6728401184 0.0624401085 0.0560385556 0.0657652244 0.0053493798 0.8323000000 114388646 95654128 1785450496 0.1430137008 -0.0429640599 -0.0961735174 578 1311867189.7065870762 0.0631867275 0.0560509227 0.0657652244 0.0053490466 0.8201640000 114390832 95654128 1784463360 0.1473295987 -0.0417026430 -0.0964889973 579 1311867189.7401719093 0.0629552901 0.0560628474 0.0657652244 0.0053452817 0.8698810000 114391930 95654128 1783336960 0.1520385593 -0.0412504449 -0.0965204835 580 1311867189.7729759216 0.0631475672 0.0560750624 0.0657652244 0.0053420613 0.9109760000 114394116 95654128 1784942592 0.1568483561 -0.0424606428 -0.0951913148 581 1311867189.8073968887 0.0629596114 0.0560869119 0.0657652244 0.0053420532 0.8609390000 114396334 95654128 1783955456 0.1596401632 -0.0455389246 -0.0928470418 582 1311867189.8405311108 0.0635112375 0.0560996684 0.0657652244 0.0053391575 0.8146300000 114567604 95654128 1782829056 0.1650846601 -0.0428884700 -0.0931055099 583 1311867189.8713529110 0.0637030676 0.0561127103 0.0657652244 0.0053358254 0.9484380000 114569790 95654128 1784594432 0.1687369943 -0.0451096892 -0.0911065340 584 1311867189.9102680683 0.0640633255 0.0561263244 0.0657652244 0.0053344720 0.8748990000 114572072 95654128 1783590912 0.1702304333 -0.0461797640 -0.0897514448 585 1311867189.9402260780 0.0636795536 0.0561392359 0.0657652244 0.0053310550 0.8492980000 114573138 95654128 1782427648 0.1746726632 -0.0452466495 -0.0902591348 586 1311867189.9727621078 0.0640011504 0.0561526521 0.0657652244 0.0053276077 0.8170580000 114575324 95654128 1784086528 0.1800750941 -0.0470440611 -0.0886764899 587 1311867190.0107009411 0.0639579743 0.0561659491 0.0657652244 0.0053250740 0.9946840000 114577574 95654128 1783062528 0.1835237592 -0.0483948030 -0.0881296173 588 1311867190.0402929783 0.0639919266 0.0561792586 0.0657652244 0.0053232499 1.0557990000 114578468 95654128 1781907456 0.1883782446 -0.0477439612 -0.0886451304 589 1311867190.0719039440 0.0651029572 0.0561944091 0.0657652244 0.0053219635 0.9295340000 114580654 95654128 1783689216 0.1890999079 -0.0488639101 -0.0872889385 590 1311867190.1096539497 0.0657960400 0.0562106831 0.0657960400 0.0053199342 0.8262480000 114582936 95654128 1785339904 0.1903000772 -0.0491264723 -0.0873388201 591 1311867190.1396369934 0.0655532405 0.0562264911 0.0657960400 0.0053161696 0.8609190000 114584002 95654128 1784578048 0.1969438046 -0.0488682278 -0.0883316770 592 1311867190.1706380844 0.0661299005 0.0562432199 0.0661299005 0.0053182732 1.0773850000 114586124 95654128 1784197120 0.1984786540 -0.0501681827 -0.0874765441 593 1311867190.2096021175 0.0669278949 0.0562612379 0.0669278949 0.0053165479 0.9491610000 114587178 95654128 1783308288 0.2021940798 -0.0518408865 -0.0870048031 594 1311867190.2394330502 0.0666171834 0.0562786721 0.0669278949 0.0053163437 0.8719200000 114589300 95654128 1783181312 0.2065507472 -0.0503126793 -0.0887828991 595 1311867190.2714810371 0.0658917800 0.0562948286 0.0669278949 0.0053195624 0.8329690000 114591518 95654128 1784832000 0.2089496553 -0.0535311103 -0.0879467949 596 1311867190.3072700500 0.0650197119 0.0563094677 0.0669278949 0.0053155144 0.9361840000 114762724 95654128 1784090624 0.2124726474 -0.0548378825 -0.0885059536 597 1311867190.3414731026 0.0643922538 0.0563230067 0.0669278949 0.0053126333 0.8300200000 114765082 95654128 1783848960 0.2160711288 -0.0558842830 -0.0886284187 598 1311867190.3716828823 0.0642268211 0.0563362238 0.0669278949 0.0053160665 0.8607050000 114767236 95654128 1783062528 0.2182636708 -0.0543480664 -0.0890954509 599 1311867190.4101090431 0.0641078055 0.0563491980 0.0669278949 0.0053126630 0.9075250000 114768242 95654128 1782824960 0.2206071615 -0.0550318547 -0.0886769369 600 1311867190.4394960403 0.0632041395 0.0563606229 0.0669278949 0.0053120189 0.8550320000 114770460 95654128 1784586240 0.2247833312 -0.0533058941 -0.0901715606 601 1311867190.4708199501 0.0633790940 0.0563723009 0.0669278949 0.0053088107 0.8773660000 114772582 95654128 1783586816 0.2266692519 -0.0554422699 -0.0885878801 602 1311867190.5097529888 0.0633468032 0.0563838865 0.0669278949 0.0053071400 0.9688620000 114773668 95654128 1783189504 0.2274653018 -0.0553969517 -0.0883183405 603 1311867190.5405189991 0.0644466653 0.0563972576 0.0669278949 0.0053054388 0.8772710000 114775930 95654128 1784836096 0.2329736799 -0.0522794463 -0.0884947553 604 1311867190.5708439350 0.0648940355 0.0564113251 0.0669278949 0.0053035172 0.8713480000 114778084 95654128 1784098816 0.2357564121 -0.0542604029 -0.0866096541 605 1311867190.6067750454 0.0649311468 0.0564254074 0.0669278949 0.0053017458 0.7976560000 114779074 95654128 1783590912 0.2372691631 -0.0552735515 -0.0855461806 606 1311867190.6389939785 0.0655412003 0.0564404500 0.0669278949 0.0053028998 0.8551820000 114781292 95654128 1785360384 0.2416611463 -0.0529927351 -0.0855535045 607 1311867190.6723659039 0.0660480037 0.0564562779 0.0669278949 0.0052986360 0.8930030000 114783478 95654128 1784233984 0.2453280687 -0.0541064329 -0.0842312202 608 1311867190.7114980221 0.0665410161 0.0564728647 0.0669278949 0.0053000887 0.8733670000 114784500 95654128 1783836672 0.2474050969 -0.0539566241 -0.0832226276 609 1311867190.7392649651 0.0654592067 0.0564876206 0.0669278949 0.0052980954 0.8514790000 114957178 95654128 1785466880 0.2494770885 -0.0555807464 -0.0829084069 610 1311867190.7751801014 0.0649544522 0.0565015006 0.0669278949 0.0052943436 0.8363710000 114958168 95654128 1784725504 0.2520686388 -0.0564040355 -0.0822877735 611 1311867190.8070900440 0.0643768087 0.0565143898 0.0669278949 0.0052910621 0.8540300000 114960386 95654128 1783947264 0.2539591789 -0.0582291298 -0.0812652484 612 1311867190.8414280415 0.0650032610 0.0565282605 0.0669278949 0.0052875458 0.8346230000 114962604 95654128 1785720832 0.2542132139 -0.0604057796 -0.0789929479 613 1311867190.8739249706 0.0656617582 0.0565431602 0.0669278949 0.0052859086 1.0141550000 114963530 95654128 1784455168 0.2569172978 -0.0584496260 -0.0788963586 614 1311867190.9076139927 0.0652025416 0.0565572634 0.0669278949 0.0052826415 0.8450880000 114965748 95654128 1783947264 0.2599620521 -0.0597154722 -0.0780448988 615 1311867190.9393599033 0.0664170235 0.0565732956 0.0669278949 0.0052786349 0.8361920000 114968042 95654128 1785720832 0.2640734315 -0.0612724200 -0.0758090839 616 1311867190.9741609097 0.0662242547 0.0565889627 0.0669278949 0.0052752503 0.8385010000 114969032 95654128 1784455168 0.2676862776 -0.0623384453 -0.0751787424 617 1311867191.0085949898 0.0662425458 0.0566046087 0.0669278949 0.0052720540 0.8100330000 114971250 95654128 1783963648 0.2724911571 -0.0583663955 -0.0765419900 618 1311867191.0396919250 0.0662056282 0.0566201443 0.0669278949 0.0052707933 0.8737680000 114973436 95654128 1785720832 0.2735958695 -0.0625460595 -0.0734506845 619 1311867191.0764329433 0.0659103319 0.0566351527 0.0669278949 0.0052768668 0.8600460000 114974426 95654128 1784344576 0.2741916180 -0.0665226802 -0.0713048950 620 1311867191.1103041172 0.0653965250 0.0566492840 0.0669278949 0.0052779934 0.8550210000 114976644 95654128 1783967744 0.2783511281 -0.0640928373 -0.0723522455 621 1311867191.1388139725 0.0651779696 0.0566630178 0.0669278949 0.0052944081 0.8708600000 114978938 95654128 1783205888 0.2819184363 -0.0656122863 -0.0710945055 622 1311867191.1742820740 0.0652527362 0.0566768276 0.0669278949 0.0052917980 1.2322980000 114979896 95654128 1782317056 0.2847465873 -0.0677857250 -0.0692548826 623 1311867191.2077920437 0.0657010227 0.0566913127 0.0669278949 0.0052880350 0.9127710000 114982114 95654128 1783943168 0.2896554172 -0.0650269911 -0.0692074746 624 1311867191.2408421040 0.0653735846 0.0567052266 0.0669278949 0.0052843172 0.8205930000 114984332 95654128 1783205888 0.2919951677 -0.0678801537 -0.0675844401 625 1311867191.2769579887 0.0651332140 0.0567187113 0.0669278949 0.0052813970 1.0068600000 114985290 95654128 1782300672 0.2942529917 -0.0698047951 -0.0665036142 626 1311867191.3085029125 0.0642060637 0.0567306720 0.0669278949 0.0052821120 0.9510630000 114987380 95654128 1783943168 0.2966977358 -0.0680625141 -0.0674070194 627 1311867191.3404779434 0.0649819300 0.0567438319 0.0669278949 0.0052794341 0.9163890000 115159334 95654128 1783209984 0.2989410162 -0.0696985871 -0.0651396513 628 1311867191.3794629574 0.0661719367 0.0567588448 0.0669278949 0.0052756265 1.0133630000 115161764 95654128 1782317056 0.3011210561 -0.0704468489 -0.0627786368 629 1311867191.4091579914 0.0659747496 0.0567734965 0.0669278949 0.0052725566 0.8939880000 115163886 95654128 1784053760 0.3041677773 -0.0697298944 -0.0630656406 630 1311867191.4415969849 0.0659176931 0.0567880110 0.0669278949 0.0052692362 0.8976090000 115164812 95654128 1783074816 0.3081184924 -0.0685099959 -0.0629076362 631 1311867191.4775309563 0.0658382103 0.0568023537 0.0669278949 0.0052659320 0.9934980000 115167030 95654128 1782300672 0.3079736233 -0.0710356012 -0.0608835220 632 1311867191.5075590611 0.0655227751 0.0568161518 0.0669278949 0.0052646002 0.8372690000 115169152 95654128 1784053760 0.3100416660 -0.0696511045 -0.0606010891 633 1311867191.5390620232 0.0653472766 0.0568296291 0.0669278949 0.0052628966 0.8503780000 115170218 95654128 1785704448 0.3148129582 -0.0716627836 -0.0595082380 634 1311867191.5764698982 0.0647498965 0.0568421216 0.0669278949 0.0052591555 0.8792850000 115172468 95654128 1784856576 0.3183139265 -0.0722520649 -0.0589077920 635 1311867191.6118669510 0.0651140064 0.0568551482 0.0669278949 0.0052773975 1.0496770000 115174718 95654128 1783734272 0.3215720057 -0.0708627701 -0.0580436923 636 1311867191.6451880932 0.0656569749 0.0568689876 0.0669278949 0.0052754286 1.0751690000 115175644 95654128 1785458688 0.3235048950 -0.0706805736 -0.0564428791 637 1311867191.6827919483 0.0666324645 0.0568843149 0.0669278949 0.0052724117 0.8778980000 115177958 95654128 1784479744 0.3248774707 -0.0708997250 -0.0541810915 638 1311867191.7119400501 0.0660374612 0.0568986615 0.0669278949 0.0052717461 0.8446010000 115180080 95654128 1783574528 0.3279220462 -0.0707637593 -0.0541771650 639 1311867191.7457199097 0.0654739141 0.0569120813 0.0669278949 0.0052807673 0.8078030000 115181114 95654128 1785364480 0.3271103799 -0.0733065680 -0.0517763123 640 1311867191.7763800621 0.0656528771 0.0569257388 0.0669278949 0.0052870183 0.8900250000 115183268 95654128 1784246272 0.3285196424 -0.0708973929 -0.0520976447 641 1311867191.8097250462 0.0651243776 0.0569385292 0.0669278949 0.0052849070 0.8471930000 115185486 95654128 1783324672 0.3292897642 -0.0711079016 -0.0515354723 642 1311867191.8395779133 0.0654700547 0.0569518181 0.0669278949 0.0052888293 1.0701300000 115186380 95654128 1785077760 0.3309433460 -0.0733125806 -0.0494536720 643 1311867191.8745219707 0.0652016178 0.0569646483 0.0669278949 0.0052899914 1.0580120000 115188598 95654128 1784086528 0.3314424455 -0.0715550408 -0.0493136272 644 1311867191.9077119827 0.0648571476 0.0569769038 0.0669278949 0.0052873847 0.9146330000 115190816 95654128 1782935552 0.3328515887 -0.0713172033 -0.0487084500 645 1311867191.9391601086 0.0654439032 0.0569900309 0.0669278949 0.0052847834 0.8930700000 115191882 95654128 1784594432 0.3329803050 -0.0747025460 -0.0459852368 646 1311867191.9755239487 0.0658947080 0.0570038152 0.0669278949 0.0052830464 0.9097540000 115194100 95654128 1783570432 0.3374844193 -0.0715061277 -0.0461292006 647 1311867192.0076289177 0.0648145974 0.0570158875 0.0669278949 0.0052830014 0.8550950000 115195026 95654128 1782444032 0.3382103443 -0.0744892135 -0.0449497998 648 1311867192.0447950363 0.0657410920 0.0570293523 0.0669278949 0.0052868294 0.9517260000 115197308 95654128 1784180736 0.3384986520 -0.0762329772 -0.0422240123 649 1311867192.0751929283 0.0643448830 0.0570406243 0.0669278949 0.0052836649 0.8581360000 115199430 95654128 1783189504 0.3389976919 -0.0758637935 -0.0430289395 650 1311867192.1073920727 0.0641272441 0.0570515268 0.0669278949 0.0052825452 0.8332140000 115200388 95654128 1782173696 0.3416954279 -0.0757469609 -0.0427825227 651 1311867192.1433029175 0.0649628267 0.0570636794 0.0669278949 0.0052815471 0.8704270000 115202778 95654128 1783799808 0.3412113190 -0.0782957971 -0.0398226269 652 1311867192.1754670143 0.0649766028 0.0570758158 0.0669278949 0.0052857100 0.8913530000 115204964 95654128 1785483264 0.3440842032 -0.0751679689 -0.0404350013 653 1311867192.2077538967 0.0650004148 0.0570879514 0.0669278949 0.0052820664 1.0291680000 115205922 95654128 1784586240 0.3451671004 -0.0756948143 -0.0393817872 654 1311867192.2451250553 0.0655751750 0.0571009288 0.0669278949 0.0052827777 1.1064710000 115208204 95654128 1783316480 0.3459498286 -0.0793909058 -0.0360721797 655 1311867192.2744629383 0.0647006109 0.0571125314 0.0669278949 0.0052795446 0.8340480000 115210326 95654128 1784975360 0.3487836421 -0.0767861828 -0.0374072418 656 1311867192.3067719936 0.0644052550 0.0571236484 0.0669278949 0.0052778356 0.9401610000 115211252 95654128 1783951360 0.3497359753 -0.0793837160 -0.0359084755 657 1311867192.3427391052 0.0649308264 0.0571355314 0.0669278949 0.0052746803 0.9936390000 115384570 95654128 1782824960 0.3511469960 -0.0805282220 -0.0344794765 658 1311867192.3755910397 0.0647576675 0.0571471152 0.0669278949 0.0052726033 0.8329310000 115386788 95654128 1784594432 0.3552364707 -0.0799006224 -0.0346621573 659 1311867192.4059340954 0.0643840730 0.0571580970 0.0669278949 0.0052691454 0.9545680000 115387650 95654128 1783590912 0.3566381931 -0.0811162293 -0.0343440138 660 1311867192.4447100163 0.0656518340 0.0571709663 0.0669278949 0.0052665264 0.9740820000 115389964 95654128 1782444032 0.3587521315 -0.0824916512 -0.0327056050 661 1311867192.4748210907 0.0659407154 0.0571842337 0.0669278949 0.0052642753 0.9139930000 115392118 95654128 1784086528 0.3629266620 -0.0810021460 -0.0330943987 662 1311867192.5077190399 0.0664061233 0.0571981640 0.0669278949 0.0052614490 0.8364890000 115393044 95654128 1783083008 0.3657077551 -0.0822549984 -0.0322196782 663 1311867192.5427820683 0.0657558590 0.0572110715 0.0669278949 0.0052578978 0.9343770000 115395434 95654128 1781936128 0.3654485047 -0.0846933499 -0.0318534300 664 1311867192.5787169933 0.0649973229 0.0572227978 0.0669278949 0.0052565431 1.0512850000 115396392 95654128 1783578624 0.3678145111 -0.0833743587 -0.0330723673 665 1311867192.6109929085 0.0648055077 0.0572342004 0.0669278949 0.0052536036 0.8971610000 115398578 95654128 1785323520 0.3689199090 -0.0847751722 -0.0324974805 666 1311867192.6435210705 0.0657646731 0.0572470089 0.0669278949 0.0052558195 0.8146670000 115400796 95654128 1784205312 0.3710858524 -0.0868109912 -0.0307902563 667 1311867192.6790139675 0.0647211522 0.0572582145 0.0669278949 0.0052524375 1.0331190000 115401786 95654128 1783209984 0.3740468621 -0.0861389264 -0.0320762917 668 1311867192.7113289833 0.0659989342 0.0572712994 0.0669278949 0.0052502088 0.7958800000 115403940 95654128 1784815616 0.3768303394 -0.0854645073 -0.0308717713 669 1311867192.7439620495 0.0654950216 0.0572835920 0.0669278949 0.0052486876 0.9301790000 115406298 95654128 1783697408 0.3762221634 -0.0874714553 -0.0302322414 670 1311867192.7760629654 0.0653649569 0.0572956537 0.0669278949 0.0052475190 0.8720000000 115407224 95654128 1782702080 0.3785817325 -0.0847893730 -0.0309465770 671 1311867192.8091869354 0.0645887256 0.0573065227 0.0669278949 0.0052442316 0.8880060000 115409442 95654128 1784307712 0.3791231215 -0.0887394473 -0.0298189502 672 1311867192.8422288895 0.0651083291 0.0573181325 0.0669278949 0.0052408558 0.9453400000 115411628 95654128 1783320576 0.3801508844 -0.0893466175 -0.0287027694 673 1311867192.8792889118 0.0654428899 0.0573302050 0.0669278949 0.0052381089 0.8889630000 115412650 95654128 1782202368 0.3840834498 -0.0864120573 -0.0291922633 674 1311867192.9092190266 0.0658265874 0.0573428109 0.0669278949 0.0052345457 0.8566380000 115414772 95654128 1783808000 0.3843766451 -0.0870376602 -0.0281017888 675 1311867192.9434111118 0.0663525984 0.0573561587 0.0669278949 0.0052308406 0.8526320000 115417162 95654128 1785585664 0.3832660317 -0.0890174061 -0.0265390277 676 1311867192.9776289463 0.0658193827 0.0573686783 0.0669278949 0.0052295757 1.0353180000 115418088 95654128 1784467456 0.3869033158 -0.0858767331 -0.0281701665 677 1311867193.0086810589 0.0652219728 0.0573802784 0.0669278949 0.0052292184 0.9123780000 115420274 95654128 1783472128 0.3858722746 -0.0881125927 -0.0271691121 678 1311867193.0430600643 0.0665701181 0.0573938327 0.0669278949 0.0052258692 0.8354830000 115422492 95654128 1785077760 0.3869331479 -0.0892286301 -0.0252240971 679 1311867193.0767369270 0.0657856911 0.0574061919 0.0669278949 0.0052255215 0.8977420000 115423418 95654128 1784107008 0.3913329840 -0.0856809616 -0.0275113396 680 1311867193.1105849743 0.0644853637 0.0574166024 0.0669278949 0.0052235589 0.8304750000 115425636 95654128 1782816768 0.3905542493 -0.0887333006 -0.0270444974 681 1311867193.1429219246 0.0649174005 0.0574276168 0.0669278949 0.0052215567 0.8452170000 115426734 95654128 1784434688 0.3914729059 -0.0911605731 -0.0251833126 682 1311867193.1767370701 0.0657769218 0.0574398592 0.0669278949 0.0052385182 0.8454210000 115428920 95654128 1783463936 0.3945611715 -0.0842250437 -0.0269217063 683 1311867193.2122681141 0.0660436302 0.0574524562 0.0669278949 0.0052442389 0.8878170000 115431170 95654128 1782321152 0.3950575888 -0.0887801126 -0.0242355298 684 1311867193.2432429790 0.0656746924 0.0574644770 0.0669278949 0.0052421271 0.8737740000 115432096 95654128 1783926784 0.3971272111 -0.0892981067 -0.0241600443 685 1311867193.2773900032 0.0659231544 0.0574768255 0.0669278949 0.0052385092 0.9166810000 115434314 95654128 1785610240 0.4010147452 -0.0866710097 -0.0249775928 686 1311867193.3139379025 0.0657707527 0.0574889158 0.0669278949 0.0052366160 0.9362500000 115436564 95654128 1784606720 0.4003466964 -0.0907420143 -0.0230754185 687 1311867193.3426671028 0.0653473288 0.0575003545 0.0669278949 0.0052376887 0.8322030000 115437566 95654128 1783443456 0.4025602043 -0.0884789973 -0.0244544316 688 1311867193.3788230419 0.0657363907 0.0575123255 0.0669278949 0.0052341211 1.0726810000 115439816 95654128 1785102336 0.4052754045 -0.0880435854 -0.0240172222 689 1311867193.4126739502 0.0657431334 0.0575242715 0.0669278949 0.0052400140 0.8198630000 115442002 95654128 1784098816 0.4063212276 -0.0925140083 -0.0223381240 690 1311867193.4440810680 0.0654281676 0.0575357264 0.0669278949 0.0052406310 0.7912870000 115442960 95654128 1782951936 0.4080878496 -0.0906335190 -0.0234722737 691 1311867193.4782969952 0.0657630414 0.0575476328 0.0669278949 0.0052370628 0.8339350000 115445178 95654128 1784594432 0.4100445807 -0.0886619762 -0.0239468198 692 1311867193.5199069977 0.0663308874 0.0575603254 0.0669278949 0.0052360821 0.8500260000 115447460 95654128 1783590912 0.4119570255 -0.0929594859 -0.0220291633 693 1311867193.5431120396 0.0660172477 0.0575725287 0.0669278949 0.0052349304 0.8380010000 115448430 95654128 1782427648 0.4139555693 -0.0904807150 -0.0233029462 694 1311867193.5765709877 0.0664562657 0.0575853295 0.0669278949 0.0052321168 0.8939350000 115450616 95654128 1784086528 0.4161099792 -0.0889093727 -0.0234415978 695 1311867193.6127800941 0.0668178871 0.0575986137 0.0669278949 0.0052284710 0.8753430000 115452898 95654128 1783083008 0.4155410528 -0.0931282640 -0.0216327906 696 1311867193.6461451054 0.0655706972 0.0576100679 0.0669278949 0.0052261575 1.0101440000 115453824 95654128 1781936128 0.4185444117 -0.0916144848 -0.0235833526 697 1311867193.6757860184 0.0662544444 0.0576224702 0.0669278949 0.0052228249 0.9355360000 115455978 95654128 1783578624 0.4206722379 -0.0893588439 -0.0238156226 698 1311867193.7122890949 0.0669734553 0.0576358670 0.0669734553 0.0052192943 0.8940850000 115458228 95654128 1785323520 0.4190834463 -0.0923377946 -0.0215981416 699 1311867193.7430191040 0.0659684241 0.0576477877 0.0669734553 0.0052159221 0.8181010000 115459262 95654128 1784352768 0.4227260947 -0.0905800238 -0.0233283769 700 1311867193.7760169506 0.0674982294 0.0576618597 0.0674982294 0.0052126902 0.8317540000 115461448 95654128 1783209984 0.4268070161 -0.0888123289 -0.0225510187 701 1311867193.8139710426 0.0673181266 0.0576756347 0.0674982294 0.0052096682 0.9147130000 115633706 95654128 1784815616 0.4266887009 -0.0919445455 -0.0214259271 702 1311867193.8436760902 0.0672566816 0.0576892829 0.0674982294 0.0052097931 0.9317670000 115635828 95654128 1783971840 0.4282194376 -0.0908673182 -0.0218346585 703 1311867193.8771181107 0.0673363656 0.0577030057 0.0674982294 0.0052063757 0.8744200000 115638046 95654128 1782972416 0.4312779605 -0.0899274275 -0.0226225182 704 1311867193.9151229858 0.0680272728 0.0577176708 0.0680272728 0.0052028702 0.8848660000 115639036 95654128 1784561664 0.4314076602 -0.0918136463 -0.0212110858 705 1311867193.9425311089 0.0684634894 0.0577329131 0.0684634894 0.0052022614 0.8807610000 115641330 95654128 1783447552 0.4338747561 -0.0886514783 -0.0221174490 706 1311867193.9781770706 0.0666110963 0.0577454884 0.0684634894 0.0052045714 0.8524410000 115643580 95654128 1782173696 0.4354626238 -0.0917569399 -0.0229692515 707 1311867194.0148570538 0.0674271584 0.0577591825 0.0684634894 0.0052013352 0.8370710000 115644538 95654128 1783799808 0.4365073740 -0.0930562243 -0.0218524300 708 1311867194.0433440208 0.0679727048 0.0577736083 0.0684634894 0.0052002384 0.9935170000 115646692 95654128 1785450496 0.4396135211 -0.0916598737 -0.0221341532 709 1311867194.0746119022 0.0681397021 0.0577882291 0.0684634894 0.0051983109 0.8361950000 115648846 95654128 1784479744 0.4412463903 -0.0905835032 -0.0224077776 710 1311867194.1131060123 0.0673229098 0.0578016582 0.0684634894 0.0051959926 0.9752430000 115649900 95654128 1783336960 0.4411666393 -0.0934662595 -0.0218944456 711 1311867194.1428558826 0.0671546236 0.0578148129 0.0684634894 0.0051947223 0.9540550000 115652194 95654128 1784950784 0.4424559772 -0.0912196338 -0.0226901900 712 1311867194.1758549213 0.0658307821 0.0578260712 0.0684634894 0.0052004291 0.8593580000 115654380 95654128 1783963648 0.4422062039 -0.0904334038 -0.0231276155 713 1311867194.2138450146 0.0664651468 0.0578381878 0.0684634894 0.0051969202 0.9846650000 115655402 95654128 1782837248 0.4407076240 -0.0927001387 -0.0210084189 714 1311867194.2451140881 0.0664200634 0.0578502072 0.0684634894 0.0051937136 0.8745010000 115657524 95654128 1784442880 0.4446142316 -0.0905066505 -0.0219791364 715 1311867194.2760241032 0.0670869127 0.0578631257 0.0684634894 0.0051906515 0.8362500000 115659678 95654128 1783455744 0.4463152289 -0.0904902145 -0.0211294293 716 1311867194.3139200211 0.0669886097 0.0578758707 0.0684634894 0.0051904238 0.8928900000 115660700 95654128 1782329344 0.4455882311 -0.0933530629 -0.0200796854 717 1311867194.3447821140 0.0667466223 0.0578882428 0.0684634894 0.0051886409 0.8950100000 115663026 95654128 1783934976 0.4465091527 -0.0909574926 -0.0208709277 718 1311867194.3802230358 0.0672431365 0.0579012719 0.0684634894 0.0051879833 1.0157460000 115663984 95654128 1785602048 0.4481017292 -0.0930976942 -0.0194365606 719 1311867194.4124519825 0.0673317984 0.0579143881 0.0684634894 0.0051846186 0.8957200000 115666138 95654128 1784614912 0.4482432902 -0.0944887847 -0.0184872281 720 1311867194.4447510242 0.0663435683 0.0579260952 0.0684634894 0.0051814672 1.0706670000 115668356 95654128 1783463936 0.4481071234 -0.0933902413 -0.0197400339 721 1311867194.4805839062 0.0671284497 0.0579388586 0.0684634894 0.0051799079 1.0308440000 115669282 95654128 1785085952 0.4483966529 -0.0913807824 -0.0196929630 722 1311867194.5174930096 0.0678111091 0.0579525320 0.0684634894 0.0051778859 0.8983570000 115671596 95654128 1784098816 0.4496150315 -0.0933477283 -0.0182209779 723 1311867194.5439500809 0.0663507581 0.0579641478 0.0684634894 0.0051761660 0.8146620000 115673794 95654128 1782956032 0.4487100542 -0.0924635231 -0.0198207553 724 1311867194.5795979500 0.0658543035 0.0579750459 0.0684634894 0.0051729012 0.8918000000 115674752 95654128 1784594432 0.4486217499 -0.0938300341 -0.0195265207 725 1311867194.6129479408 0.0670609474 0.0579875781 0.0684634894 0.0051695725 0.9374970000 115676970 95654128 1783590912 0.4512179196 -0.0941529721 -0.0181790255 726 1311867194.6493880749 0.0670217350 0.0580000219 0.0684634894 0.0051750601 1.0526910000 115679252 95654128 1782427648 0.4524303079 -0.0926616564 -0.0184474811 727 1311867194.6784319878 0.0662667304 0.0580113929 0.0684634894 0.0051753574 0.8743980000 115680114 95654128 1784180736 0.4514647126 -0.0928790569 -0.0184979625 728 1311867194.7133309841 0.0669202432 0.0580236303 0.0684634894 0.0051725569 0.8387910000 115682332 95654128 1783062528 0.4503507614 -0.0927041322 -0.0172532964 729 1311867194.7475099564 0.0669252053 0.0580358410 0.0684634894 0.0051691103 0.8491340000 115684690 95654128 1782050816 0.4514673650 -0.0921892449 -0.0171142090 730 1311867194.7784450054 0.0677666441 0.0580491708 0.0684634894 0.0051658153 0.8764470000 115685616 95654128 1783672832 0.4528728724 -0.0915745124 -0.0164137296 731 1311867194.8130390644 0.0675870702 0.0580622186 0.0684634894 0.0051623233 0.8324820000 115687834 95654128 1785323520 0.4538428783 -0.0911319852 -0.0166543033 732 1311867194.8476719856 0.0674735457 0.0580750756 0.0684634894 0.0051588225 0.8738010000 115690052 95654128 1784352768 0.4535542428 -0.0917067230 -0.0163161661 733 1311867194.8814148903 0.0669486299 0.0580871814 0.0684634894 0.0051553404 1.0154790000 115691010 95654128 1783062528 0.4528551400 -0.0907328203 -0.0167974886 734 1311867194.9104089737 0.0678126067 0.0581004313 0.0684634894 0.0051650273 0.9908350000 115693132 95654128 1784721408 0.4535075724 -0.0907051787 -0.0158517249 735 1311867194.9451448917 0.0685783252 0.0581146869 0.0685783252 0.0051629459 0.8776250000 115694262 95654128 1783717888 0.4528943002 -0.0905720815 -0.0147208441 736 1311867194.9787399769 0.0687106550 0.0581290836 0.0687106550 0.0051595734 0.8538680000 115696480 95654128 1782554624 0.4519525170 -0.0915948451 -0.0139079755 737 1311867195.0132799149 0.0679780990 0.0581424473 0.0687106550 0.0051566702 0.9527070000 115698698 95654128 1784213504 0.4511153996 -0.0913309082 -0.0142807942 738 1311867195.0464940071 0.0686933696 0.0581567439 0.0687106550 0.0051539052 0.8957330000 115699624 95654128 1783209984 0.4482256472 -0.0931486711 -0.0127524305 739 1311867195.0781710148 0.0675980896 0.0581695197 0.0687106550 0.0051536760 0.8874200000 115701810 95654128 1782046720 0.4489761889 -0.0920263082 -0.0145404255 740 1311867195.1115310192 0.0680408925 0.0581828594 0.0687106550 0.0051518792 0.7972700000 115703996 95654128 1783705600 0.4491288662 -0.0916528702 -0.0146989003 741 1311867195.1458311081 0.0687231496 0.0581970839 0.0687231496 0.0051488763 0.9330780000 115705126 95654128 1785450496 0.4483712912 -0.0920729786 -0.0139526967 742 1311867195.1780319214 0.0695080310 0.0582123277 0.0695080310 0.0051504561 0.8591860000 115707312 95654128 1784332288 0.4478969872 -0.0887136161 -0.0141679421 743 1311867195.2114748955 0.0677761286 0.0582251996 0.0695080310 0.0051484654 0.8512360000 115709498 95654128 1783320576 0.4451357126 -0.0912130550 -0.0146522988 744 1311867195.2436800003 0.0679223835 0.0582382334 0.0695080310 0.0051458913 0.8103030000 115710456 95654128 1784950784 0.4443399608 -0.0920499340 -0.0144326342 745 1311867195.2780399323 0.0679786503 0.0582513078 0.0695080310 0.0051429177 0.8351180000 115712674 95654128 1783853056 0.4431974292 -0.0900658742 -0.0151794394 746 1311867195.3123180866 0.0680524781 0.0582644461 0.0695080310 0.0051401509 1.1535780000 115714892 95654128 1782837248 0.4411472082 -0.0899474919 -0.0152728893 747 1311867195.3425979614 0.0690567344 0.0582788936 0.0695080310 0.0051395216 0.8931820000 115715926 95654128 1784442880 0.4396395385 -0.0929917097 -0.0135584287 748 1311867195.3782711029 0.0689346865 0.0582931393 0.0695080310 0.0051376602 0.7766970000 115718176 95654128 1783324672 0.4396789670 -0.0903689116 -0.0153712500 749 1311867195.4119830132 0.0690943971 0.0583075602 0.0695080310 0.0051375857 0.8781050000 115720362 95654128 1782312960 0.4380871654 -0.0906751677 -0.0155520756 750 1311867195.4435520172 0.0692127869 0.0583221005 0.0695080310 0.0051361158 0.8760990000 115721320 95654128 1783934976 0.4353142381 -0.0909347534 -0.0154689886 751 1311867195.4788239002 0.0677674711 0.0583346776 0.0695080310 0.0051336097 0.8224380000 115723538 95654128 1785618432 0.4334408641 -0.0891760141 -0.0176184699 752 1311867195.5113179684 0.0680145174 0.0583475497 0.0695080310 0.0051318292 1.0017460000 115725724 95654128 1784606720 0.4325591624 -0.0896950886 -0.0176680982 753 1311867195.5439620018 0.0681087151 0.0583605128 0.0695080310 0.0051300672 0.8274940000 115726822 95654128 1783443456 0.4301378131 -0.0907366723 -0.0170782618 754 1311867195.5782160759 0.0670921504 0.0583720932 0.0695080310 0.0051280956 0.8548690000 115729040 95654128 1785102336 0.4270105958 -0.0895616487 -0.0186494924 755 1311867195.6119859219 0.0674230233 0.0583840812 0.0695080310 0.0051279913 0.8366510000 115729998 95654128 1784225792 0.4260275066 -0.0901712403 -0.0183152538 756 1311867195.6430909634 0.0677466914 0.0583964656 0.0695080310 0.0051256709 0.8692850000 115732152 95654128 1783193600 0.4243779778 -0.0918342695 -0.0174505375 757 1311867195.6779129505 0.0672134981 0.0584081129 0.0695080310 0.0051234370 0.8308820000 115734402 95654128 1784815616 0.4215860665 -0.0910569578 -0.0186128709 758 1311867195.7107300758 0.0672194511 0.0584197374 0.0695080310 0.0051230835 0.8597920000 115735296 95654128 1783697408 0.4188335836 -0.0915447846 -0.0185039155 759 1311867195.7458300591 0.0680622831 0.0584324417 0.0695080310 0.0051205180 0.8320040000 115737686 95654128 1782575104 0.4178269804 -0.0919162184 -0.0175341070 760 1311867195.7821879387 0.0669811293 0.0584436899 0.0695080310 0.0051172227 0.8148660000 115739904 95654128 1784180736 0.4153234363 -0.0906885117 -0.0192637537 761 1311867195.8100500107 0.0685143471 0.0584569234 0.0695080310 0.0051147921 0.9354130000 115740766 95654128 1783193600 0.4135442376 -0.0912165865 -0.0176193602 762 1311867195.8458549976 0.0684147701 0.0584699914 0.0695080310 0.0051123221 0.9128340000 115743016 95654128 1782067200 0.4108299017 -0.0918084532 -0.0176757835 763 1311867195.8778660297 0.0679254383 0.0584823839 0.0695080310 0.0051097692 0.8326270000 115745234 95654128 1783672832 0.4113737643 -0.0893290043 -0.0193626564 764 1311867195.9098269939 0.0678862855 0.0584946926 0.0695080310 0.0051086485 0.8957160000 115746160 95654128 1785323520 0.4086823463 -0.0906155631 -0.0186344646 765 1311867195.9458460808 0.0670635626 0.0585058938 0.0695080310 0.0051054978 0.9591890000 115748518 95654128 1784352768 0.4062615037 -0.0904626921 -0.0194285326 766 1311867195.9778430462 0.0675872415 0.0585177493 0.0695080310 0.0051035398 0.8119520000 115750736 95654128 1783209984 0.4053663611 -0.0883923396 -0.0195100289 767 1311867196.0100569725 0.0667079836 0.0585284276 0.0695080310 0.0051019387 0.8535450000 115751662 95654128 1784815616 0.4011223912 -0.0910826102 -0.0191924423 768 1311867196.0498790741 0.0671839118 0.0585396978 0.0695080310 0.0050997158 0.9920950000 115753976 95654128 1783844864 0.4002386034 -0.0907833129 -0.0189310573 769 1311867196.0793108940 0.0671037808 0.0585508344 0.0695080310 0.0050984931 0.9741790000 115756162 95654128 1782702080 0.4005013704 -0.0876865014 -0.0202781595 770 1311867196.1113979816 0.0675139278 0.0585624748 0.0695080310 0.0050955973 0.8151510000 115757024 95654128 1784307712 0.3978072703 -0.0895568132 -0.0190138333 771 1311867196.1473290920 0.0677601993 0.0585744044 0.0695080310 0.0050933827 0.8396840000 115759446 95654128 1783336960 0.3949567378 -0.0893858522 -0.0189225171 772 1311867196.1811769009 0.0673814341 0.0585858125 0.0695080310 0.0050909171 0.7859370000 115760404 95654128 1782194176 0.3959866762 -0.0890920237 -0.0197495036 773 1311867196.2114949226 0.0679444000 0.0585979193 0.0695080310 0.0050885540 0.8565950000 115762526 95654128 1783799808 0.3921737969 -0.0900629237 -0.0187870897 774 1311867196.2462599277 0.0685320646 0.0586107541 0.0695080310 0.0050856383 0.8370380000 115764776 95654128 1785483264 0.3914032876 -0.0889948308 -0.0188357588 775 1311867196.2800569534 0.0680900440 0.0586229855 0.0695080310 0.0050841910 0.8141460000 115765734 95654128 1784479744 0.3911622763 -0.0881030634 -0.0198936202 776 1311867196.3111600876 0.0685539916 0.0586357832 0.0695080310 0.0050831669 0.9951430000 115767888 95654128 1783332864 0.3886796236 -0.0876791328 -0.0195891596 777 1311867196.3484730721 0.0688786507 0.0586489657 0.0695080310 0.0050818090 0.8898750000 115770310 95654128 1784975360 0.3874916434 -0.0880770534 -0.0191747788 778 1311867196.3842670918 0.0669676363 0.0586596581 0.0695080310 0.0050796245 0.9325300000 115771268 95654128 1783975936 0.3848480582 -0.0880166367 -0.0210346580 779 1311867196.4107549191 0.0686255917 0.0586724514 0.0695080310 0.0050770276 0.8159050000 115773358 95654128 1782964224 0.3819984198 -0.0881787091 -0.0188859235 780 1311867196.4463150501 0.0678085983 0.0586841644 0.0695080310 0.0050790496 0.8311040000 115775608 95654128 1784569856 0.3791192472 -0.0874096677 -0.0200015735 781 1311867196.4798319340 0.0672249496 0.0586951001 0.0695080310 0.0050766714 0.8754790000 115776566 95654128 1783582720 0.3779309690 -0.0871220082 -0.0206160024 782 1311867196.5113470554 0.0683715492 0.0587074740 0.0695080310 0.0050747897 0.8760370000 115778720 95654128 1782456320 0.3756165206 -0.0874335691 -0.0188882314 783 1311867196.5468420982 0.0672520846 0.0587183867 0.0695080310 0.0050736709 0.9672950000 115781110 95654128 1784053760 0.3741435707 -0.0855958164 -0.0200906452 784 1311867196.5795550346 0.0666584074 0.0587285143 0.0695080310 0.0050733033 0.7817720000 115782068 95654128 1783066624 0.3724724054 -0.0853834152 -0.0207393467 785 1311867196.6108930111 0.0677896813 0.0587400572 0.0695080310 0.0050704251 0.9896120000 115784222 95654128 1781940224 0.3703020811 -0.0869648457 -0.0186013021 786 1311867196.6521809101 0.0675742254 0.0587512966 0.0695080310 0.0050721980 0.9735570000 115786568 95654128 1783451648 0.3688610196 -0.0847446993 -0.0193400513 787 1311867196.6805100441 0.0663036630 0.0587608930 0.0695080310 0.0050875203 0.9147770000 115787430 95654128 1785196544 0.3666846454 -0.0844024494 -0.0198172368 788 1311867196.7112100124 0.0669756681 0.0587713178 0.0695080310 0.0050853000 0.7967080000 115789584 95654128 1784094720 0.3639394343 -0.0845716968 -0.0189450178 789 1311867196.7464900017 0.0673493221 0.0587821898 0.0695080310 0.0050826898 0.9105840000 115790714 95654128 1783083008 0.3627978265 -0.0832191557 -0.0187422149 790 1311867196.7783749104 0.0668767244 0.0587924360 0.0695080310 0.0050806413 0.8593980000 115792932 95654128 1784688640 0.3583474755 -0.0825376064 -0.0191681534 791 1311867196.8109180927 0.0668577477 0.0588026324 0.0695080310 0.0050827227 0.9525780000 115795054 95654128 1783570432 0.3567737341 -0.0842764452 -0.0183990095 792 1311867196.8488750458 0.0674413592 0.0588135399 0.0695080310 0.0050827997 0.8931610000 115796108 95654128 1782575104 0.3549209833 -0.0831702724 -0.0181706492 793 1311867196.8821749687 0.0674240887 0.0588243981 0.0695080310 0.0050800797 0.9133830000 115798294 95654128 1784180736 0.3515991569 -0.0822416320 -0.0183303822 794 1311867196.9115700722 0.0680908114 0.0588360686 0.0695080310 0.0050789002 0.9623190000 115800416 95654128 1783062528 0.3498838246 -0.0840927288 -0.0170665476 795 1311867196.9482440948 0.0676630214 0.0588471717 0.0695080310 0.0050763243 0.8283100000 115801578 95654128 1782067200 0.3466063440 -0.0823594928 -0.0183054507 796 1311867196.9809880257 0.0679350272 0.0588585886 0.0695080310 0.0050760188 0.8332080000 115803796 95654128 1783672832 0.3449436426 -0.0826859474 -0.0181547794 797 1311867197.0154891014 0.0683008656 0.0588704359 0.0695080310 0.0050750731 1.0528570000 115805982 95654128 1785450496 0.3426223993 -0.0835391730 -0.0178896394 798 1311867197.0490679741 0.0680305958 0.0588819148 0.0695080310 0.0050724697 0.8776440000 115806940 95654128 1784348672 0.3394613862 -0.0832654312 -0.0183949135 799 1311867197.0806479454 0.0671357960 0.0588922450 0.0695080310 0.0050713442 0.8732710000 115809062 95654128 1783336960 0.3364920616 -0.0832754150 -0.0196777061 800 1311867197.1148109436 0.0678082705 0.0589033901 0.0695080310 0.0050682373 1.0935610000 115811312 95654128 1784942592 0.3352921307 -0.0830980539 -0.0192968342 801 1311867197.1468429565 0.0675380155 0.0589141699 0.0695080310 0.0050657278 0.8557090000 115812378 95654128 1783824384 0.3326997757 -0.0819007903 -0.0203287285 802 1311867197.1792430878 0.0675851628 0.0589249816 0.0695080310 0.0050639478 0.9584080000 115814596 95654128 1782829056 0.3312581182 -0.0824706852 -0.0200485624 803 1311867197.2143619061 0.0669088960 0.0589349242 0.0695080310 0.0050652011 0.8533370000 115816814 95654128 1784434688 0.3272531033 -0.0823874474 -0.0207920205 804 1311867197.2459290028 0.0668087527 0.0589447175 0.0695080310 0.0050631624 0.8339370000 115817740 95654128 1783463936 0.3266002238 -0.0827541873 -0.0208221450 805 1311867197.2799959183 0.0669040903 0.0589546049 0.0695080310 0.0050611073 0.8230360000 115819990 95654128 1782321152 0.3235183954 -0.0827572271 -0.0205701031 806 1311867197.3157260418 0.0674814358 0.0589651841 0.0695080310 0.0050590970 0.8975580000 115822176 95654128 1783926784 0.3218200207 -0.0811663046 -0.0206715763 807 1311867197.3468708992 0.0668816268 0.0589749939 0.0695080310 0.0050565368 0.9521050000 115823242 95654128 1785704448 0.3179293871 -0.0815174431 -0.0211912468 808 1311867197.3784019947 0.0674037710 0.0589854255 0.0695080310 0.0050558237 0.8191180000 115825396 95654128 1784602624 0.3163468838 -0.0815068260 -0.0209278017 809 1311867197.4155099392 0.0674392506 0.0589958752 0.0695080310 0.0050537598 0.8524440000 115826386 95654128 1783590912 0.3128728271 -0.0820557624 -0.0211260691 810 1311867197.4478878975 0.0681288391 0.0590071505 0.0695080310 0.0050507709 0.9923160000 115828572 95654128 1785196544 0.3122637570 -0.0811317787 -0.0216053706 811 1311867197.4793179035 0.0677954406 0.0590179869 0.0695080310 0.0050476955 1.1183860000 115830694 95654128 1784225792 0.3088166416 -0.0818781182 -0.0219249520 812 1311867197.5150759220 0.0668824390 0.0590276721 0.0695080310 0.0050447484 1.0330290000 115831684 95654128 1782935552 0.3059452176 -0.0810300931 -0.0239769351 813 1311867197.5469260216 0.0671170801 0.0590376222 0.0695080310 0.0050423443 1.1886390000 115833978 95654128 1784594432 0.3050176799 -0.0812505186 -0.0244082212 814 1311867197.5802750587 0.0678165630 0.0590484072 0.0695080310 0.0050402043 0.8390320000 115836196 95654128 1783590912 0.3021129966 -0.0804497972 -0.0250416193 815 1311867197.6152749062 0.0666498169 0.0590577340 0.0695080310 0.0050394128 0.8065420000 115837154 95654128 1782452224 0.2998091578 -0.0809158087 -0.0268774368 816 1311867197.6470439434 0.0654688478 0.0590655908 0.0695080310 0.0050388449 0.8528950000 115839340 95654128 1784094720 0.2980566621 -0.0798286721 -0.0291197542 817 1311867197.6800849438 0.0673778877 0.0590757650 0.0695080310 0.0050388624 0.9360210000 115841558 95654128 1785839616 0.2961468697 -0.0795775726 -0.0277954061 818 1311867197.7143290043 0.0657000691 0.0590838631 0.0695080310 0.0050393514 0.8762720000 115842516 95654128 1784737792 0.2941394746 -0.0779688805 -0.0307802204 819 1311867197.7463419437 0.0658731014 0.0590921528 0.0695080310 0.0050402504 1.0534570000 115844842 95654128 1783726080 0.2927113771 -0.0782403275 -0.0309714656 820 1311867197.7793009281 0.0668316409 0.0591015912 0.0695080310 0.0050377272 1.0536380000 115847060 95654128 1785331712 0.2909526825 -0.0792561918 -0.0301017445 821 1311867197.8146750927 0.0658117756 0.0591097644 0.0695080310 0.0050420488 0.9754160000 115848050 95654128 1784352768 0.2878092229 -0.0765893757 -0.0331192166 822 1311867197.8467919827 0.0655733347 0.0591176276 0.0695080310 0.0050420521 0.9900340000 116021320 95654128 1783209984 0.2857035100 -0.0788448751 -0.0332951695 823 1311867197.8802978992 0.0662671626 0.0591263148 0.0695080310 0.0050412806 0.9155590000 116023506 95654128 1784848384 0.2840711176 -0.0787421986 -0.0335881487 824 1311867197.9148609638 0.0660333261 0.0591346971 0.0695080310 0.0050434243 0.9942580000 116024496 95654128 1783844864 0.2827255130 -0.0756363943 -0.0360027365 825 1311867197.9470140934 0.0656642690 0.0591426117 0.0695080310 0.0050463298 0.8743540000 116026822 95654128 1782702080 0.2779966593 -0.0768393055 -0.0363184698 826 1311867197.9812700748 0.0656308159 0.0591504667 0.0695080310 0.0050434739 0.9521470000 116027780 95654128 1784324096 0.2777704298 -0.0763829798 -0.0371434316 827 1311867198.0145471096 0.0656194761 0.0591582889 0.0695080310 0.0050405839 0.8393920000 116030030 95654128 1783447552 0.2769384682 -0.0741834790 -0.0385628827 828 1311867198.0463368893 0.0655458868 0.0591660034 0.0695080310 0.0050380249 0.8722380000 116032184 95654128 1782321152 0.2721535265 -0.0746752471 -0.0386824384 829 1311867198.0787069798 0.0658541992 0.0591740712 0.0695080310 0.0050373080 0.8739140000 116033142 95654128 1783926784 0.2709972858 -0.0738833398 -0.0395190679 830 1311867198.1143770218 0.0659147874 0.0591821926 0.0695080310 0.0050344215 0.8548140000 116035360 95654128 1785610240 0.2682499290 -0.0724992380 -0.0403602347 831 1311867198.1463611126 0.0662530288 0.0591907014 0.0695080310 0.0050319919 0.8719400000 116037686 95654128 1784606720 0.2674860358 -0.0731343701 -0.0401986241 832 1311867198.1822519302 0.0659952089 0.0591988799 0.0695080310 0.0050294756 0.8740400000 116038676 95654128 1783443456 0.2648760080 -0.0725158826 -0.0413581245 833 1311867198.2144989967 0.0659290701 0.0592069593 0.0695080310 0.0050321890 0.8886990000 116040862 95654128 1785196544 0.2622511983 -0.0718511716 -0.0423482060 834 1311867198.2464120388 0.0660841614 0.0592152054 0.0695080310 0.0050316041 0.9172790000 116043048 95654128 1784078336 0.2608526051 -0.0719169006 -0.0429265238 835 1311867198.2821578979 0.0659137666 0.0592232276 0.0695080310 0.0050303246 0.8527270000 116044038 95654128 1783083008 0.2577723861 -0.0692716911 -0.0447812229 836 1311867198.3159120083 0.0662241802 0.0592316020 0.0695080310 0.0050308790 0.9110330000 116046224 95654128 1784688640 0.2551702857 -0.0694775060 -0.0451906361 837 1311867198.3481218815 0.0665774941 0.0592403784 0.0695080310 0.0050279768 0.8230920000 116048550 95654128 1783570432 0.2520316541 -0.0705768019 -0.0453154817 838 1311867198.3828320503 0.0652945042 0.0592476029 0.0695080310 0.0050336769 0.8072700000 116049540 95654128 1782575104 0.2494366467 -0.0676398799 -0.0481611341 839 1311867198.4242680073 0.0657325163 0.0592553322 0.0695080310 0.0050390521 0.8870130000 116051758 95654128 1784053760 0.2472620010 -0.0672706217 -0.0487920977 840 1311867198.4497859478 0.0660154596 0.0592633800 0.0695080310 0.0050385987 0.9360150000 116053784 95654128 1785737216 0.2433100641 -0.0693107918 -0.0488164127 841 1311867198.4856219292 0.0662486181 0.0592716859 0.0695080310 0.0050447909 1.1195050000 116054710 95654128 1784733696 0.2408873439 -0.0661724806 -0.0512328930 842 1311867198.5190339088 0.0659111142 0.0592795712 0.0695080310 0.0050424599 1.0506920000 116056928 95654128 1783590912 0.2387766689 -0.0655339733 -0.0529378057 843 1311867198.5499279499 0.0663442612 0.0592879516 0.0695080310 0.0050410512 0.8324510000 116057994 95654128 1785196544 0.2339285165 -0.0667577535 -0.0526355468 844 1311867198.5824239254 0.0655411631 0.0592953606 0.0695080310 0.0050384119 0.9201440000 116060180 95654128 1784217600 0.2330706269 -0.0641382635 -0.0554598235 845 1311867198.6147489548 0.0654289499 0.0593026193 0.0695080310 0.0050427371 1.0503630000 116062366 95654128 1783074816 0.2316264510 -0.0640725121 -0.0562604256 846 1311867198.6482009888 0.0649190843 0.0593092582 0.0695080310 0.0050419452 0.9523920000 116063292 95654128 1784680448 0.2284564376 -0.0633263513 -0.0576225817 847 1311867198.6827540398 0.0640031397 0.0593147999 0.0695080310 0.0050424524 0.8591610000 116237010 95654128 1783709696 0.2228860110 -0.0633774400 -0.0592750311 848 1311867198.7146520615 0.0641949177 0.0593205548 0.0695080310 0.0050396610 0.9651910000 116239164 95654128 1782693888 0.2229278535 -0.0618941076 -0.0603892617 849 1311867198.7467699051 0.0651963204 0.0593274756 0.0695080310 0.0050388067 0.8198220000 116240198 95654128 1784299520 0.2206977308 -0.0620971061 -0.0600936264 850 1311867198.7842700481 0.0646448955 0.0593337314 0.0695080310 0.0050363303 0.8950980000 116242448 95654128 1783201792 0.2170065343 -0.0588518344 -0.0627801046 851 1311867198.8149418831 0.0644623637 0.0593397580 0.0695080310 0.0050353415 0.8520540000 116244602 95654128 1782059008 0.2149621695 -0.0597286113 -0.0631636679 852 1311867198.8464009762 0.0642716065 0.0593455465 0.0695080310 0.0050336709 0.8335280000 116245528 95654128 1783672832 0.2118968368 -0.0582394265 -0.0644468367 853 1311867198.8845369816 0.0646411330 0.0593517547 0.0695080310 0.0050317503 0.8764030000 116247746 95654128 1785356288 0.2090812176 -0.0574385747 -0.0652148947 854 1311867198.9147930145 0.0644974336 0.0593577801 0.0695080310 0.0050290992 0.8554740000 116249900 95654128 1784332288 0.2072737217 -0.0570636094 -0.0661323816 855 1311867198.9465179443 0.0646203831 0.0593639352 0.0695080310 0.0050263715 0.8122440000 116250966 95654128 1783320576 0.2069286108 -0.0557246357 -0.0669809282 856 1311867198.9839329720 0.0647804067 0.0593702629 0.0695080310 0.0050238160 0.7883530000 116253280 95654128 1784942592 0.2047145963 -0.0542010330 -0.0678358302 857 1311867199.0148730278 0.0638317615 0.0593754688 0.0695080310 0.0050271312 0.8580640000 116255434 95654128 1783955456 0.2028516233 -0.0534792840 -0.0695238709 858 1311867199.0468010902 0.0648334995 0.0593818301 0.0695080310 0.0050272319 0.8714110000 116256360 95654128 1782829056 0.2018414885 -0.0520164818 -0.0702833831 859 1311867199.0849320889 0.0654804185 0.0593889298 0.0695080310 0.0050281510 0.8136860000 116258674 95654128 1784434688 0.2027260363 -0.0498737730 -0.0712850690 860 1311867199.1149818897 0.0652087405 0.0593956970 0.0695080310 0.0050264835 0.8764300000 116260796 95654128 1783447552 0.1993040293 -0.0502841696 -0.0720645040 861 1311867199.1465420723 0.0655296296 0.0594028212 0.0695080310 0.0050235952 0.8165100000 116261862 95654128 1782321152 0.1989233792 -0.0484815314 -0.0734337866 862 1311867199.1823658943 0.0656056181 0.0594100170 0.0695080310 0.0050223441 0.8489250000 116264112 95654128 1783926784 0.1989986449 -0.0464375019 -0.0751686841 863 1311867199.2146680355 0.0660257265 0.0594176830 0.0695080310 0.0050195296 1.0305360000 116265070 95654128 1785696256 0.1962415725 -0.0467755124 -0.0755641684 864 1311867199.2467749119 0.0658622086 0.0594251419 0.0695080310 0.0050169215 1.0396120000 116267224 95654128 1784598528 0.1951069832 -0.0450152420 -0.0773353428 865 1311867199.2833590508 0.0658935159 0.0594326198 0.0695080310 0.0050142881 1.1053560000 116269506 95654128 1783455744 0.1941907406 -0.0443403348 -0.0784918666 866 1311867199.3159129620 0.0659652203 0.0594401632 0.0695080310 0.0050139299 0.7988270000 116270368 95654128 1785061376 0.1903514862 -0.0446315333 -0.0794296116 867 1311867199.3465209007 0.0659014881 0.0594476157 0.0695080310 0.0050119784 0.9135250000 116272662 95654128 1784090624 0.1891962737 -0.0440056436 -0.0808549151 868 1311867199.3829050064 0.0658795014 0.0594550257 0.0695080310 0.0050094404 0.8447430000 116274944 95654128 1782927360 0.1871218979 -0.0437053218 -0.0822196528 869 1311867199.4147589207 0.0663292706 0.0594629362 0.0695080310 0.0050066347 0.7984500000 116275838 95654128 1784586240 0.1871843934 -0.0429429263 -0.0831708238 870 1311867199.4512910843 0.0661301687 0.0594705997 0.0695080310 0.0050042286 0.8193340000 116278120 95654128 1783582720 0.1852425635 -0.0413383394 -0.0853110999 871 1311867199.4837360382 0.0660363063 0.0594781379 0.0695080310 0.0050028440 0.8515230000 116280306 95654128 1782439936 0.1839125156 -0.0419187099 -0.0860819817 872 1311867199.5150198936 0.0659637377 0.0594855755 0.0695080310 0.0050004385 0.8517260000 116281232 95654128 1784045568 0.1797652096 -0.0411986671 -0.0874355659 873 1311867199.5544059277 0.0662616566 0.0594933373 0.0695080310 0.0050000848 0.8785890000 116283686 95654128 1783074816 0.1780224591 -0.0406462774 -0.0882386118 874 1311867199.5835030079 0.0665498748 0.0595014112 0.0695080310 0.0049981848 0.8690240000 116285840 95654128 1781932032 0.1746623367 -0.0385410786 -0.0894996002 875 1311867199.6158308983 0.0664044023 0.0595093003 0.0695080310 0.0049963448 0.9119540000 116286702 95654128 1783537664 0.1732787639 -0.0383444689 -0.0899169296 876 1311867199.6538460255 0.0662406981 0.0595169845 0.0695080310 0.0049940484 0.9579180000 116289016 95654128 1785315328 0.1714972258 -0.0375871584 -0.0909590647 877 1311867199.6824479103 0.0655851215 0.0595239037 0.0695080310 0.0049914442 0.8564430000 116291138 95654128 1784217600 0.1676903516 -0.0385482758 -0.0916038007 878 1311867199.7146759033 0.0657450482 0.0595309893 0.0695080310 0.0049906496 0.9282250000 116292096 95654128 1783185408 0.1645519733 -0.0370858721 -0.0926066861 879 1311867199.7511539459 0.0657120124 0.0595380212 0.0695080310 0.0049890988 1.0356510000 116294454 95654128 1784807424 0.1603020877 -0.0365481414 -0.0933248997 880 1311867199.7826020718 0.0659656823 0.0595453254 0.0695080310 0.0049883384 0.9330290000 116295380 95654128 1783689216 0.1587613225 -0.0368552580 -0.0931687206 881 1311867199.8150150776 0.0660437420 0.0595527015 0.0695080310 0.0049932678 0.9722570000 116297566 95654128 1782677504 0.1543125361 -0.0368648320 -0.0936377943 882 1311867199.8519051075 0.0667369664 0.0595608470 0.0695080310 0.0049912516 0.8529220000 116299816 95654128 1784299520 0.1530960649 -0.0340527222 -0.0947454125 883 1311867199.8839609623 0.0661035925 0.0595682566 0.0695080310 0.0049920005 1.0361110000 116300774 95654128 1783181312 0.1484351754 -0.0367742255 -0.0944683999 884 1311867199.9148159027 0.0656913295 0.0595751832 0.0695080310 0.0049913859 1.0722360000 116302960 95654128 1782185984 0.1471424699 -0.0368264429 -0.0950260013 885 1311867199.9520709515 0.0661360249 0.0595825966 0.0695080310 0.0049899911 1.0542550000 116305350 95654128 1783791616 0.1454671025 -0.0344855189 -0.0963816866 886 1311867199.9828410149 0.0658636540 0.0595896858 0.0695080310 0.0049878408 0.8351970000 116306244 95654128 1785475072 0.1412927508 -0.0358760804 -0.0963087529 887 1311867200.0144031048 0.0650714189 0.0595958659 0.0695080310 0.0049851750 0.9374100000 116308430 95654128 1784471552 0.1384458989 -0.0364949703 -0.0969501063 888 1311867200.0539638996 0.0649797693 0.0596019288 0.0695080310 0.0049832913 0.8120790000 116310744 95654128 1783439360 0.1377621889 -0.0348304994 -0.0978263691 889 1311867200.0830330849 0.0651046559 0.0596081186 0.0695080310 0.0049805822 0.8282560000 116311606 95654128 1785061376 0.1340808272 -0.0351658426 -0.0976193547 890 1311867200.1174468994 0.0644298717 0.0596135363 0.0695080310 0.0049799813 0.9023990000 116313824 95654128 1783951360 0.1326642036 -0.0346617028 -0.0981707945 891 1311867200.1517000198 0.0645352378 0.0596190601 0.0695080310 0.0049787471 0.9452510000 116316182 95654128 1782829056 0.1295159906 -0.0333395153 -0.0985757783 892 1311867200.1853220463 0.0647009090 0.0596247573 0.0695080310 0.0049776885 0.9576540000 116317172 95654128 1784434688 0.1257830858 -0.0350692943 -0.0976412818 893 1311867200.2179059982 0.0639603063 0.0596296123 0.0695080310 0.0049770796 0.8907800000 116319358 95654128 1783447552 0.1248561516 -0.0327530615 -0.0992999747 894 1311867200.2522649765 0.0636581182 0.0596341185 0.0695080310 0.0049745569 0.8396450000 116321576 95654128 1782321152 0.1216382161 -0.0340565071 -0.0983444080 895 1311867200.2825429440 0.0633239895 0.0596382412 0.0695080310 0.0049741366 0.7907700000 116322470 95654128 1783926784 0.1200071648 -0.0349201746 -0.0975622237 896 1311867200.3148880005 0.0643370673 0.0596434855 0.0695080310 0.0049736415 0.8565380000 116495616 95654128 1785577472 0.1164657176 -0.0315702669 -0.0978791267 897 1311867200.3514990807 0.0643590987 0.0596487425 0.0695080310 0.0049733250 0.9178060000 116496714 95654128 1784725504 0.1133636907 -0.0335742123 -0.0964483544 898 1311867200.3837759495 0.0640855730 0.0596536833 0.0695080310 0.0049844756 1.0482660000 116498932 95654128 1783562240 0.1100784689 -0.0322229229 -0.0972466618 899 1311867200.4162800312 0.0639638677 0.0596584778 0.0695080310 0.0049830522 1.0744850000 116501086 95654128 1785315328 0.1077262387 -0.0325680748 -0.0969622433 900 1311867200.4522490501 0.0639851764 0.0596632852 0.0695080310 0.0049812849 0.9340150000 116502076 95654128 1784328192 0.1047734916 -0.0334940888 -0.0962121040 901 1311867200.4850699902 0.0636283234 0.0596676859 0.0695080310 0.0049823357 0.8533110000 116504262 95654128 1783201792 0.1020847484 -0.0334782936 -0.0962835848 902 1311867200.5143918991 0.0639988333 0.0596724876 0.0695080310 0.0049811278 0.8140550000 116506448 95654128 1784807424 0.0983776152 -0.0340209194 -0.0952626392 903 1311867200.5505030155 0.0628387704 0.0596759940 0.0695080310 0.0049936777 0.8553100000 116507578 95654128 1783820288 0.0961936638 -0.0343274996 -0.0952762812 904 1311867200.5832219124 0.0636730269 0.0596804155 0.0695080310 0.0049973910 0.8926970000 116509764 95654128 1782693888 0.0927267969 -0.0321429521 -0.0956191048 905 1311867200.6145610809 0.0634561107 0.0596845876 0.0695080310 0.0049962176 0.8117890000 116511918 95654128 1784426496 0.0903524533 -0.0337153524 -0.0943668485 906 1311867200.6504778862 0.0631449297 0.0596884069 0.0695080310 0.0049940420 1.0491920000 116512908 95654128 1783328768 0.0856351852 -0.0331694707 -0.0943093449 907 1311867200.6851279736 0.0630996525 0.0596921679 0.0695080310 0.0049927173 0.8208140000 116515158 95654128 1782296576 0.0841649473 -0.0333277583 -0.0934412107 908 1311867200.7189719677 0.0627740696 0.0596955621 0.0695080310 0.0049939623 0.8500880000 116517376 95654128 1783918592 0.0803853124 -0.0336826444 -0.0931739733 909 1311867200.7503669262 0.0629798993 0.0596991752 0.0695080310 0.0049934713 0.8561710000 116518410 95654128 1785569280 0.0807825625 -0.0317546800 -0.0931008011 910 1311867200.7832930088 0.0617778562 0.0597014595 0.0695080310 0.0049996455 0.8945960000 116520628 95654128 1784598528 0.0760234147 -0.0340736359 -0.0927734897 911 1311867200.8181068897 0.0623890385 0.0597044096 0.0695080310 0.0049976222 0.7718930000 116694330 95654128 1783582720 0.0711014569 -0.0333897583 -0.0918470025 912 1311867200.8501501083 0.0617075972 0.0597066061 0.0695080310 0.0049951617 0.8115290000 116695224 95654128 1785315328 0.0698411390 -0.0330749191 -0.0919514447 913 1311867200.8845369816 0.0619731434 0.0597090886 0.0695080310 0.0049959560 0.8977030000 116697506 95654128 1784197120 0.0667742118 -0.0323173292 -0.0915960371 914 1311867200.9194929600 0.0622157902 0.0597118312 0.0695080310 0.0049984603 0.8518270000 116699724 95654128 1783185408 0.0628207698 -0.0335106887 -0.0905446559 915 1311867200.9512679577 0.0621221028 0.0597144654 0.0695080310 0.0049978324 1.0731100000 116700758 95654128 1784807424 0.0616008155 -0.0331618302 -0.0901472718 916 1311867200.9856009483 0.0619737357 0.0597169318 0.0695080310 0.0050044491 0.8913070000 116703008 95654128 1783836672 0.0599727482 -0.0334011130 -0.0907859579 917 1311867201.0184400082 0.0612900034 0.0597186473 0.0695080310 0.0050035231 0.9546620000 116703934 95654128 1782673408 0.0582220480 -0.0365181938 -0.0901141465 918 1311867201.0555179119 0.0620099865 0.0597211433 0.0695080310 0.0050026043 0.8738480000 116706216 95654128 1784299520 0.0562982708 -0.0355211645 -0.0900873616 919 1311867201.0825428963 0.0625483468 0.0597242197 0.0695080310 0.0050044764 1.1358920000 116708306 95654128 1783181312 0.0520865470 -0.0357623845 -0.0901571587 920 1311867201.1193449497 0.0624607541 0.0597271942 0.0695080310 0.0050032816 0.9224720000 116709328 95654128 1782169600 0.0501483455 -0.0349610038 -0.0910791829 921 1311867201.1506710052 0.0622267537 0.0597299081 0.0695080310 0.0050015112 0.8793650000 116711590 95654128 1783791616 0.0501199774 -0.0350636467 -0.0912955329 922 1311867201.1830160618 0.0625873432 0.0597330073 0.0695080310 0.0049993595 0.9936820000 116713776 95654128 1785442304 0.0484238565 -0.0354175568 -0.0909182653 923 1311867201.2196528912 0.0628296137 0.0597363623 0.0695080310 0.0049975799 0.9589750000 116714734 95654128 1784455168 0.0445076041 -0.0347995050 -0.0914915577 924 1311867201.2503149509 0.0626565665 0.0597395226 0.0695080310 0.0049950382 0.8103240000 116716920 95654128 1783328768 0.0450035036 -0.0335935727 -0.0920034051 925 1311867201.2824099064 0.0626329929 0.0597426507 0.0695080310 0.0049928962 1.0945290000 116745474 95654128 1784934400 0.0452142358 -0.0336399786 -0.0917364880 926 1311867201.3180539608 0.0628621206 0.0597460195 0.0695080310 0.0049933929 0.8977940000 116746464 95654128 1783947264 0.0399961248 -0.0341349579 -0.0920705646 927 1311867201.3522200584 0.0615014620 0.0597479132 0.0695080310 0.0049924044 0.9112570000 116748950 95654128 1782820864 0.0396422856 -0.0343396813 -0.0932448059 928 1311867201.3842790127 0.0627387613 0.0597511361 0.0695080310 0.0049974758 0.9290400000 116751200 95654128 1784434688 0.0370379947 -0.0302511491 -0.0939656869 929 1311867201.4198760986 0.0621861368 0.0597537572 0.0695080310 0.0050234254 0.8983090000 116752126 95654128 1783447552 0.0334167108 -0.0329099298 -0.0925650001 930 1311867201.4558579922 0.0620673150 0.0597562449 0.0695080310 0.0050266566 0.7905850000 116754312 95654128 1782321152 0.0320953950 -0.0310102198 -0.0932167321 931 1311867201.4853110313 0.0619794987 0.0597586329 0.0695080310 0.0050246602 1.0757230000 116756658 95654128 1783926784 0.0315802172 -0.0292537250 -0.0936202258 932 1311867201.5198690891 0.0618309677 0.0597608564 0.0695080310 0.0050245817 0.9124290000 116757648 95654128 1785610240 0.0270523243 -0.0292365346 -0.0934951901 933 1311867201.5527739525 0.0610832796 0.0597622738 0.0695080310 0.0050266939 0.9766840000 116759942 95654128 1784598528 0.0234745909 -0.0299380999 -0.0936998948 934 1311867201.5840220451 0.0615597926 0.0597641983 0.0695080310 0.0050240203 1.2036470000 116761188 95654128 1783435264 0.0217611138 -0.0289066751 -0.0936069861 935 1311867201.6197049618 0.0614069439 0.0597659553 0.0695080310 0.0050220857 1.0413910000 116934218 95654128 1785094144 0.0185709894 -0.0286864694 -0.0942558050 936 1311867201.6515579224 0.0609685220 0.0597672401 0.0695080310 0.0050220311 1.1557780000 116936372 95654128 1784197120 0.0158777628 -0.0291833542 -0.0945475176 937 1311867201.6839449406 0.0610483512 0.0597686073 0.0695080310 0.0050195130 1.1265340000 116937330 95654128 1783349248 0.0140794450 -0.0278815962 -0.0950402617 938 1311867201.7189009190 0.0622135960 0.0597712139 0.0695080310 0.0050188157 1.2292550000 116939836 95654128 1784807424 0.0131351799 -0.0247335341 -0.0953430980 939 1311867201.7507290840 0.0612523705 0.0597727913 0.0695080310 0.0050181140 1.0355760000 116942226 95654128 1783582720 0.0112608997 -0.0264106970 -0.0951743498 940 1311867201.7858049870 0.0603074059 0.0597733600 0.0695080310 0.0050257086 1.0128490000 116943216 95654128 1782566912 0.0093539814 -0.0271975826 -0.0949188545 941 1311867201.8190178871 0.0616386011 0.0597753422 0.0695080310 0.0050354333 1.0223990000 116945658 95654128 1784172544 0.0075937365 -0.0220360626 -0.0963691399 942 1311867201.8505740166 0.0611923337 0.0597768465 0.0695080310 0.0050399532 0.9840880000 116947748 95654128 1783185408 0.0065853903 -0.0228665750 -0.0960866138 943 1311867201.8862850666 0.0608394146 0.0597779733 0.0695080310 0.0050375125 1.0317270000 116948898 95654128 1782059008 0.0057781823 -0.0240304507 -0.0956743509 944 1311867201.9195730686 0.0611635484 0.0597794410 0.0695080310 0.0050373902 1.2855850000 116951084 95654128 1783570432 0.0025427430 -0.0214637928 -0.0971681178 945 1311867201.9516520500 0.0614226833 0.0597811799 0.0695080310 0.0050367437 1.1281310000 116953410 95654128 1785315328 0.0019938573 -0.0218168516 -0.0967714041 946 1311867201.9894599915 0.0612915233 0.0597827765 0.0695080310 0.0050342920 1.1751360000 116954528 95654128 1784197120 0.0017400542 -0.0228401311 -0.0965288803 947 1311867202.0184879303 0.0611934550 0.0597842661 0.0695080310 0.0050321209 1.0513830000 116956714 95654128 1783185408 -0.0001187950 -0.0206708442 -0.0983809158 948 1311867202.0507359505 0.0613720156 0.0597859409 0.0695080310 0.0050304887 1.1128910000 116958836 95654128 1784807424 -0.0004022641 -0.0207156055 -0.0983377323 949 1311867202.0866351128 0.0616387837 0.0597878934 0.0695080310 0.0050279921 2.0728530000 116963374 95654128 1783943168 -0.0013519304 -0.0200885683 -0.0986154005 950 1311867202.1185920238 0.0627869442 0.0597910503 0.0695080310 0.0050318704 1.3701910000 116966392 95654128 1782931456 -0.0065255901 -0.0183348879 -0.0988505110 951 1311867202.1516621113 0.0622080825 0.0597935918 0.0695080310 0.0050301905 1.3884770000 116967286 95654128 1784553472 -0.0056439536 -0.0175949037 -0.0992299020 952 1311867202.1866259575 0.0617719367 0.0597956699 0.0695080310 0.0050280908 1.3441100000 116969824 95654128 1783435264 -0.0074424511 -0.0184366088 -0.0990988836 953 1311867202.2191269398 0.0613137111 0.0597972628 0.0695080310 0.0050263147 0.9743110000 116971946 95654128 1782423552 -0.0084164860 -0.0195634943 -0.0987261161 954 1311867202.2513220310 0.0617548674 0.0597993148 0.0695080310 0.0050245965 0.9508130000 116972904 95654128 1784045568 -0.0113479281 -0.0171654969 -0.0995354205 955 1311867202.2868280411 0.0613775477 0.0598009674 0.0695080310 0.0050228639 1.3143110000 116975358 95654128 1785696256 -0.0113644525 -0.0161146782 -0.0999740884 956 1311867202.3199880123 0.0605825111 0.0598017849 0.0695080310 0.0050229908 1.0658850000 116977480 95654128 1784725504 -0.0126624592 -0.0186571404 -0.0994580761 957 1311867202.3523900509 0.0614723153 0.0598035305 0.0695080310 0.0050225195 0.9856150000 116978598 95654128 1783582720 -0.0134041859 -0.0170563031 -0.0989361033 958 1311867202.3883628845 0.0605114512 0.0598042695 0.0695080310 0.0050203285 0.9535520000 116980912 95654128 1785212928 -0.0146421632 -0.0164867826 -0.0997853577 959 1311867202.4196391106 0.0608624406 0.0598053729 0.0695080310 0.0050203812 1.0961610000 116983290 95654128 1784225792 -0.0154219288 -0.0170168597 -0.0991300195 960 1311867202.4529430866 0.0614194870 0.0598070543 0.0695080310 0.0050180675 1.1910230000 116984280 95654128 1783083008 -0.0166384745 -0.0179632362 -0.0980862156 961 1311867202.4875710011 0.0620648190 0.0598094037 0.0695080310 0.0050183121 1.0936530000 116986574 95654128 1784688640 -0.0189880170 -0.0144676082 -0.0995699987 962 1311867202.5206449032 0.0618898422 0.0598115663 0.0695080310 0.0050329114 1.0970820000 116988824 95654128 1783717888 -0.0198691152 -0.0160797294 -0.0989158154 963 1311867202.5508940220 0.0620183274 0.0598138578 0.0695080310 0.0050303513 0.9484740000 116989782 95654128 1782575104 -0.0208902787 -0.0158993416 -0.0990783945 964 1311867202.5864949226 0.0626171306 0.0598167658 0.0695080310 0.0050432443 1.1294340000 116992128 95654128 1784197120 -0.0220465828 -0.0154556399 -0.0992019698 965 1311867202.6185030937 0.0622497909 0.0598192871 0.0695080310 0.0050466390 1.0176740000 116994378 95654128 1783201792 -0.0218057502 -0.0159664359 -0.0997231454 966 1311867202.6514449120 0.0630332530 0.0598226141 0.0695080310 0.0050522330 0.9704510000 116995368 95654128 1782038528 -0.0268801842 -0.0158329532 -0.1000845358 967 1311867202.6866559982 0.0621740222 0.0598250458 0.0695080310 0.0050507869 1.0937020000 116997822 95654128 1783697408 -0.0262272991 -0.0148509508 -0.1017427295 968 1311867202.7185359001 0.0619634464 0.0598272549 0.0695080310 0.0050491367 0.9625210000 117169980 95654128 1785442304 -0.0290171392 -0.0169728436 -0.1022835970 969 1311867202.7507350445 0.0621727146 0.0598296754 0.0695080310 0.0050469205 0.9879430000 117172422 95654128 1784451072 -0.0301150810 -0.0188325141 -0.1022086963 970 1311867202.7897169590 0.0622296445 0.0598321496 0.0695080310 0.0050444592 0.9144990000 117174800 95654128 1783455744 -0.0298886225 -0.0165151954 -0.1042943001 971 1311867202.8190000057 0.0625360236 0.0598349342 0.0695080310 0.0050432130 0.9517870000 117175694 95654128 1784934400 -0.0341770165 -0.0171098579 -0.1050186455 972 1311867202.8527579308 0.0611790270 0.0598363170 0.0695080310 0.0050410231 0.9431260000 117177880 95654128 1783816192 -0.0350013562 -0.0190390516 -0.1057517752 973 1311867202.8873219490 0.0609832704 0.0598374958 0.0695080310 0.0050403000 0.9851440000 117180302 95654128 1782820864 -0.0351237841 -0.0178371277 -0.1064803749 974 1311867202.9199879169 0.0615377501 0.0598392414 0.0695080310 0.0050388648 1.0535340000 117181420 95654128 1784426496 -0.0354050510 -0.0158652700 -0.1069701016 975 1311867202.9525690079 0.0611790270 0.0598406156 0.0695080310 0.0050408849 1.0764510000 117183638 95654128 1783308288 -0.0361671150 -0.0174610689 -0.1066906974 976 1311867202.9868710041 0.0617741086 0.0598425966 0.0695080310 0.0050429211 0.9089280000 117185856 95654128 1782312960 -0.0364674442 -0.0158839207 -0.1066672057 977 1311867203.0202019215 0.0619712025 0.0598447753 0.0695080310 0.0050408984 0.9333680000 117199518 95654128 1783918592 -0.0364912041 -0.0144467829 -0.1071436927 978 1311867203.0560851097 0.0612962916 0.0598462595 0.0695080310 0.0050447358 1.0155240000 117201704 95654128 1785569280 -0.0366862752 -0.0172189400 -0.1065387428 979 1311867203.0865778923 0.0623517595 0.0598488187 0.0695080310 0.0050457354 1.1540910000 117204062 95654128 1784598528 -0.0362984575 -0.0165155083 -0.1062633246 980 1311867203.1189930439 0.0623961538 0.0598514181 0.0695080310 0.0050518026 1.2443210000 117204924 95654128 1783455744 -0.0363353528 -0.0170100853 -0.1064774245 981 1311867203.1549820900 0.0618223473 0.0598534272 0.0695080310 0.0050637863 0.9525460000 117207110 95654128 1785061376 -0.0362470709 -0.0212748572 -0.1054701135 982 1311867203.1877939701 0.0625497699 0.0598561729 0.0695080310 0.0051013979 0.9641440000 117209360 95654128 1784090624 -0.0345400237 -0.0225117411 -0.1049261093 983 1311867203.2185909748 0.0637349263 0.0598601188 0.0695080310 0.0051036219 1.2096520000 117210478 95654128 1782947840 -0.0339678824 -0.0187867973 -0.1065964475 984 1311867203.2552030087 0.0628368855 0.0598631439 0.0695080310 0.0051047782 0.9325850000 117212792 95654128 1784553472 -0.0337550677 -0.0221300833 -0.1065001562 985 1311867203.2864799500 0.0623768233 0.0598656959 0.0695080310 0.0051059756 0.9966280000 117213890 95654128 1783582720 -0.0333709866 -0.0246023256 -0.1062720940 986 1311867203.3194670677 0.0632117167 0.0598690894 0.0695080310 0.0051046564 0.9317700000 117216204 95654128 1782419456 -0.0339741781 -0.0229146313 -0.1073339581 987 1311867203.3547461033 0.0621254146 0.0598713755 0.0695080310 0.0051028258 0.9742120000 117218454 95654128 1784045568 -0.0319795310 -0.0239345692 -0.1082680970 988 1311867203.3865599632 0.0618872046 0.0598734158 0.0695080310 0.0051062285 1.0182710000 117219316 95654128 1783074816 -0.0326366015 -0.0245978981 -0.1090806946 989 1311867203.4183609486 0.0620887876 0.0598756558 0.0695080310 0.0051137556 1.1280680000 117221726 95654128 1781936128 -0.0333876237 -0.0310340393 -0.1066522673 990 1311867203.4545118809 0.0620125569 0.0598778143 0.0695080310 0.0051133839 0.9756010000 117224040 95654128 1783578624 -0.0313162766 -0.0308498349 -0.1073748469 991 1311867203.4864439964 0.0624458753 0.0598804057 0.0695080310 0.0051160006 1.0546690000 117225138 95654128 1785323520 -0.0318081193 -0.0303692780 -0.1085411608 992 1311867203.5185539722 0.0616939515 0.0598822338 0.0695080310 0.0051224162 0.9528180000 117227420 95654128 1784360960 -0.0326307938 -0.0361693352 -0.1077716574 993 1311867203.5560259819 0.0619665533 0.0598843328 0.0695080310 0.0051213150 1.0086620000 117229862 95654128 1783218176 -0.0322942995 -0.0381786153 -0.1081493571 994 1311867203.5876550674 0.0629281625 0.0598873950 0.0695080310 0.0051224939 1.1166520000 117230724 95654128 1784823808 -0.0321290381 -0.0365956500 -0.1095016450 995 1311867203.6191980839 0.0614093877 0.0598889247 0.0695080310 0.0051234006 1.1499780000 117232974 95654128 1783832576 -0.0327695273 -0.0409550890 -0.1101292074 996 1311867203.6557719707 0.0624756292 0.0598915218 0.0695080310 0.0051211281 1.0337970000 117235384 95654128 1782681600 -0.0327680595 -0.0428898484 -0.1094409451 997 1311867203.6866750717 0.0616461337 0.0598932817 0.0695080310 0.0051187382 1.1965290000 117236514 95654128 1784307712 -0.0321897157 -0.0448918827 -0.1102470681 998 1311867203.7195260525 0.0625284538 0.0598959221 0.0695080310 0.0051169550 1.0019340000 117238892 95654128 1783189504 -0.0327775292 -0.0448613577 -0.1107673049 999 1311867203.7566421032 0.0622456856 0.0598982742 0.0695080310 0.0051153245 1.0906340000 117240854 95654128 1782194176 -0.0317888781 -0.0470116958 -0.1109578684 1000 1311867203.7867228985 0.0625325888 0.0599009086 0.0695080310 0.0051130283 0.9896640000 117241940 95654128 1783832576 -0.0317388065 -0.0480617881 -0.1112280414 1001 1311867203.8193860054 0.0624614842 0.0599034666 0.0695080310 0.0051112116 1.0007470000 117244062 95654128 1785577472 -0.0316679291 -0.0495891571 -0.1118029803 1002 1311867203.8572859764 0.0614040457 0.0599049642 0.0695080310 0.0051107931 1.1063000000 117246536 95654128 1784475648 -0.0308583807 -0.0523075126 -0.1127163246 1003 1311867203.8891890049 0.0614400692 0.0599064947 0.0695080310 0.0051099756 0.9311790000 117247666 95654128 1783463936 -0.0299835000 -0.0548585244 -0.1124496013 1004 1311867203.9188020229 0.0617886595 0.0599083693 0.0695080310 0.0051107248 0.8850500000 117249820 95654128 1785069568 -0.0327510834 -0.0558451638 -0.1135496721 1005 1311867203.9553489685 0.0618918687 0.0599103430 0.0695080310 0.0051086182 0.8810360000 117250810 95654128 1783967744 -0.0324919336 -0.0549022220 -0.1156484559 1006 1311867203.9866371155 0.0617073625 0.0599121293 0.0695080310 0.0051081357 0.8715060000 117252996 95654128 1782956032 -0.0329792090 -0.0578842126 -0.1157412082 1007 1311867204.0199849606 0.0614730380 0.0599136793 0.0695080310 0.0051071115 1.0750660000 117255438 95654128 1784561664 -0.0322157405 -0.0588638484 -0.1170784831 1008 1311867204.0551509857 0.0617188513 0.0599154702 0.0695080310 0.0051048371 1.0152580000 117256428 95654128 1783463936 -0.0321515612 -0.0600195415 -0.1180130541 1009 1311867204.0867509842 0.0618182756 0.0599173560 0.0695080310 0.0051035723 0.9513570000 117258754 95654128 1782300672 -0.0329788327 -0.0613339543 -0.1188220754 1010 1311867204.1191530228 0.0608037971 0.0599182337 0.0695080310 0.0051014269 0.8949810000 117431560 95654128 1784053760 -0.0328619704 -0.0649016127 -0.1199552193 1011 1311867204.1555769444 0.0604414344 0.0599187512 0.0695080310 0.0050989247 0.8750640000 117432518 95654128 1783226368 -0.0324648023 -0.0662466139 -0.1213109642 1012 1311867204.1876530647 0.0600694716 0.0599189001 0.0695080310 0.0050975061 0.9107010000 117434704 95654128 1782050816 -0.0337802917 -0.0687329620 -0.1220828146 1013 1311867204.2187769413 0.0593456253 0.0599183342 0.0695080310 0.0050962919 0.9136210000 117436890 95654128 1783545856 -0.0332870893 -0.0711337253 -0.1226378009 1014 1311867204.2566440105 0.0590540618 0.0599174819 0.0695080310 0.0050948057 0.8160280000 117437912 95654128 1785229312 -0.0314066075 -0.0720812455 -0.1237442270 1015 1311867204.2867140770 0.0595162101 0.0599170865 0.0695080310 0.0050927038 0.9554190000 117440206 95654128 1784225792 -0.0331614874 -0.0737199336 -0.1241535395 1016 1311867204.3204538822 0.0592262931 0.0599164066 0.0695080310 0.0050913197 0.9526840000 117612616 95654128 1783193600 -0.0336891375 -0.0763675570 -0.1246041879 1017 1311867204.3625741005 0.0598067194 0.0599162987 0.0695080310 0.0050894400 0.8735630000 117613734 95654128 1784815616 -0.0341363512 -0.0770998299 -0.1251637042 1018 1311867204.3869600296 0.0583819672 0.0599147915 0.0695080310 0.0050876409 1.0142720000 117615856 95654128 1783697408 -0.0339682736 -0.0811375454 -0.1254280806 1019 1311867204.4240970612 0.0592600591 0.0599141490 0.0695080310 0.0050858102 0.8740750000 117618138 95654128 1782702080 -0.0343006849 -0.0812629536 -0.1260549873 1020 1311867204.4549949169 0.0594828613 0.0599137262 0.0695080310 0.0050852454 0.8904810000 117619032 95654128 1784307712 -0.0344464667 -0.0809716508 -0.1271479875 1021 1311867204.4872748852 0.0595742986 0.0599133937 0.0695080310 0.0050832030 0.8388780000 117621358 95654128 1783320576 -0.0340655819 -0.0824863613 -0.1274363697 1022 1311867204.5237219334 0.0599068552 0.0599133873 0.0695080310 0.0050810117 0.8108980000 117622380 95654128 1782194176 -0.0349015519 -0.0840445906 -0.1277188361 1023 1311867204.5581860542 0.0588685237 0.0599123660 0.0695080310 0.0050798529 0.8292060000 117624598 95654128 1783799808 -0.0350623094 -0.0876901001 -0.1278901994 1024 1311867204.5878469944 0.0589163452 0.0599113933 0.0695080310 0.0050779158 0.8934420000 117796904 95654128 1785483264 -0.0348792858 -0.0882862508 -0.1281938404 1025 1311867204.6241528988 0.0588195696 0.0599103281 0.0695080310 0.0050755825 0.8388670000 117961734 95654128 1784729600 -0.0352773853 -0.0889551640 -0.1285687685 1026 1311867204.6541819572 0.0588112995 0.0599092569 0.0695080310 0.0050733013 0.8682890000 118131824 95654128 1783590912 -0.0363069847 -0.0908571929 -0.1287161410 1027 1311867204.6871540546 0.0580307357 0.0599074278 0.0695080310 0.0050710495 0.9146650000 118134150 95654128 1785331712 -0.0358035900 -0.0935823247 -0.1286297888 1028 1311867204.7225689888 0.0588172376 0.0599063673 0.0695080310 0.0050709441 0.8418480000 118135140 95654128 1784213504 -0.0359417871 -0.0927297845 -0.1288361847 1029 1311867204.7539510727 0.0577855669 0.0599043063 0.0695080310 0.0050692337 0.8235540000 118137326 95654128 1783201792 -0.0360700116 -0.0950868353 -0.1286886036 1030 1311867204.7878720760 0.0579675436 0.0599024259 0.0695080310 0.0050698609 0.8521250000 118139544 95654128 1784823808 -0.0377841480 -0.0966627821 -0.1277731806 1031 1311867204.8227200508 0.0580023862 0.0599005830 0.0695080310 0.0050674650 0.9975300000 118140502 95654128 1783869440 -0.0392737798 -0.0975161865 -0.1271799654 1032 1311867204.8542668819 0.0588291511 0.0598995448 0.0695080310 0.0050656533 0.8919870000 118142688 95654128 1782583296 -0.0389154367 -0.0974825770 -0.1256179512 1033 1311867204.8864960670 0.0578461327 0.0598975570 0.0695080310 0.0050643501 0.9726280000 118145014 95654128 1784188928 -0.0408812054 -0.1021477208 -0.1244638860 1034 1311867204.9220221043 0.0589657724 0.0598966558 0.0695080310 0.0050629054 0.9577920000 118315868 95654128 1783070720 -0.0442191847 -0.1025158241 -0.1239633113 1035 1311867204.9542920589 0.0584907196 0.0598952974 0.0695080310 0.0050620080 0.9282790000 118318054 95654128 1782075392 -0.0437590368 -0.1036985815 -0.1236100122 1036 1311867204.9865999222 0.0568614453 0.0598923690 0.0695080310 0.0050624674 0.9732310000 118320240 95654128 1783681024 -0.0417073779 -0.1081050411 -0.1225343198 1037 1311867205.0227239132 0.0566680059 0.0598892597 0.0695080310 0.0050670073 1.1142170000 118321230 95654128 1785331712 -0.0422061868 -0.1127840355 -0.1206092834 1038 1311867205.0550808907 0.0566521659 0.0598861411 0.0695080310 0.0050836483 1.0180370000 118323448 95654128 1784360960 -0.0416545905 -0.1115660071 -0.1204906031 1039 1311867205.0880999565 0.0556898862 0.0598821024 0.0695080310 0.0050827008 0.8963940000 118324450 95654128 1783218176 -0.0426023453 -0.1156727970 -0.1196132079 1040 1311867205.1232450008 0.0557684675 0.0598781469 0.0695080310 0.0050814742 0.8265680000 118326700 95654128 1784815616 -0.0433959700 -0.1180578172 -0.1191132590 1041 1311867205.1545319557 0.0570590086 0.0598754388 0.0695080310 0.0050947130 0.8768910000 118328854 95654128 1783697408 -0.0417378843 -0.1171196774 -0.1183910370 1042 1311867205.1863510609 0.0565055050 0.0598722047 0.0695080310 0.0051028044 0.8693830000 118329780 95654128 1782702080 -0.0426574871 -0.1206431389 -0.1174387261 1043 1311867205.2223129272 0.0551204905 0.0598676489 0.0695080310 0.0051042565 0.8339480000 118332030 95654128 1784307712 -0.0415573567 -0.1243784428 -0.1169910282 1044 1311867205.2541849613 0.0555498637 0.0598635131 0.0695080310 0.0051057776 0.9556160000 118334216 95654128 1783336960 -0.0415599942 -0.1246840432 -0.1164905876 1045 1311867205.2880499363 0.0560425520 0.0598598567 0.0695080310 0.0051038576 0.8305460000 118335314 95654128 1782194176 -0.0415289998 -0.1250197738 -0.1161538139 1046 1311867205.3218879700 0.0568791665 0.0598570071 0.0695080310 0.0051059786 0.9342900000 118337500 95654128 1783799808 -0.0423322879 -0.1272367835 -0.1146061569 1047 1311867205.3542900085 0.0559808835 0.0598533050 0.0695080310 0.0051110901 0.8354250000 118339718 95654128 1785577472 -0.0429092199 -0.1296533793 -0.1145722568 1048 1311867205.3862779140 0.0556285828 0.0598492737 0.0695080310 0.0051165634 0.9147630000 118510676 95654128 1784475648 -0.0436952896 -0.1329148859 -0.1134213954 1049 1311867205.4225649834 0.0545593165 0.0598442309 0.0695080310 0.0051206966 0.9150500000 118512926 95654128 1783463936 -0.0445684046 -0.1358979791 -0.1132231951 1050 1311867205.4540419579 0.0557387061 0.0598403209 0.0695080310 0.0051282008 0.8406800000 118515112 95654128 1784942592 -0.0447005294 -0.1351136118 -0.1123344600 1051 1311867205.4865119457 0.0547754243 0.0598355017 0.0695080310 0.0051314721 0.8454690000 118516178 95654128 1783971840 -0.0457759760 -0.1377868354 -0.1113068759 1052 1311867205.5230340958 0.0543480851 0.0598302856 0.0695080310 0.0051410281 0.8459900000 118518428 95654128 1782829056 -0.0464743674 -0.1407315880 -0.1100283787 1053 1311867205.5542900562 0.0545316041 0.0598252536 0.0695080310 0.0051632370 0.8778250000 118520614 95654128 1784561664 -0.0482120179 -0.1409803033 -0.1096726879 1054 1311867205.5866839886 0.0547467656 0.0598204353 0.0695080310 0.0051610614 1.0179740000 118521540 95654128 1783463936 -0.0489669964 -0.1415306479 -0.1084546894 1055 1311867205.6226179600 0.0544315726 0.0598153273 0.0695080310 0.0051668883 0.9519000000 118523790 95654128 1782448128 -0.0510400161 -0.1436964273 -0.1076497585 1056 1311867205.6555979252 0.0546178520 0.0598104055 0.0695080310 0.0051651366 0.7918770000 118525976 95654128 1784053760 -0.0518829450 -0.1450709850 -0.1066995412 1057 1311867205.6902959347 0.0548118241 0.0598056765 0.0695080310 0.0051627784 0.8548580000 118527106 95654128 1785704448 -0.0516450740 -0.1455052197 -0.1063301787 1058 1311867205.7222061157 0.0545451678 0.0598007043 0.0695080310 0.0051607753 0.8748300000 118529292 95654128 1784733696 -0.0547967479 -0.1511036754 -0.1050405949 1059 1311867205.7548348904 0.0543884300 0.0597955936 0.0695080310 0.0051585092 0.9108260000 118530250 95654128 1783590912 -0.0557661168 -0.1536817253 -0.1046525165 1060 1311867205.7906379700 0.0545825958 0.0597906757 0.0695080310 0.0051572735 0.9119490000 118532468 95654128 1785204736 -0.0566119775 -0.1538634449 -0.1049965993 1061 1311867205.8232109547 0.0536927506 0.0597849283 0.0695080310 0.0051700210 0.9581070000 118704574 95654128 1784381440 -0.0577894449 -0.1579248458 -0.1046744585 1062 1311867205.8554759026 0.0543527305 0.0597798133 0.0695080310 0.0051758704 0.8499470000 118705532 95654128 1783074816 -0.0586764961 -0.1600819826 -0.1032123193 1063 1311867205.8905880451 0.0544583984 0.0597748072 0.0695080310 0.0051751142 0.9719880000 118707858 95654128 1784602624 -0.0595947541 -0.1605954617 -0.1034963951 1064 1311867205.9223020077 0.0543072633 0.0597696686 0.0695080310 0.0051814243 0.8735460000 118710044 95654128 1783599104 -0.0589936823 -0.1614539176 -0.1031663492 1065 1311867205.9544939995 0.0539402664 0.0597641950 0.0695080310 0.0051793877 0.8724250000 118710970 95654128 1782435840 -0.0591917746 -0.1637014896 -0.1028791070 1066 1311867205.9905850887 0.0533554740 0.0597581830 0.0695080310 0.0051857111 0.9845740000 118713252 95654128 1784086528 -0.0605173223 -0.1663783342 -0.1027787626 1067 1311867206.0259850025 0.0549248271 0.0597536532 0.0695080310 0.0051924264 0.8415710000 118715470 95654128 1783230464 -0.0620994382 -0.1636826545 -0.1033763438 1068 1311867206.0604250431 0.0537313223 0.0597480143 0.0695080310 0.0052095370 0.8666690000 118716396 95654128 1781809152 -0.0641469806 -0.1698199064 -0.1025643349 1069 1311867206.0903289318 0.0537782125 0.0597424298 0.0695080310 0.0052077740 0.8160210000 118718690 95654128 1783545856 -0.0642292574 -0.1705973595 -0.1028773561 1070 1311867206.1227540970 0.0547167398 0.0597377329 0.0695080310 0.0052060704 0.8090800000 118720876 95654128 1785229312 -0.0638607815 -0.1697132587 -0.1030858532 1071 1311867206.1546130180 0.0537638627 0.0597321551 0.0695080310 0.0052048363 0.8612770000 118721802 95654128 1784225792 -0.0641919971 -0.1757699251 -0.1023462787 1072 1311867206.1903800964 0.0535745844 0.0597264111 0.0695080310 0.0052045884 0.9288850000 118724084 95654128 1783193600 -0.0660017952 -0.1796023399 -0.1022533402 1073 1311867206.2239561081 0.0538588166 0.0597209427 0.0695080310 0.0052037467 0.7943870000 118726302 95654128 1784815616 -0.0657123625 -0.1792016029 -0.1029301435 1074 1311867206.2553579807 0.0538763590 0.0597155008 0.0695080310 0.0052028250 0.9394040000 118727196 95654128 1783697408 -0.0650556833 -0.1803694516 -0.1028675437 1075 1311867206.2904770374 0.0526311062 0.0597089106 0.0695080310 0.0052019312 0.8673010000 118729554 95654128 1782685696 -0.0663015246 -0.1853351593 -0.1031923294 1076 1311867206.3222041130 0.0527050085 0.0597024014 0.0695080310 0.0052008387 0.9318450000 118730448 95654128 1784307712 -0.0663308650 -0.1862615347 -0.1033819616 1077 1311867206.3542530537 0.0532121286 0.0596963752 0.0695080310 0.0051996046 0.8112550000 118732666 95654128 1783083008 -0.0676144361 -0.1868527830 -0.1036976799 1078 1311867206.3900070190 0.0527699850 0.0596899500 0.0695080310 0.0052005777 0.8523250000 118734884 95654128 1782050816 -0.0681013614 -0.1902074963 -0.1035565734 1079 1311867206.4220259190 0.0531694256 0.0596839068 0.0695080310 0.0052018810 0.8163360000 118735810 95654128 1783672832 -0.0669652075 -0.1891631931 -0.1040382385 1080 1311867206.4542310238 0.0529082827 0.0596776331 0.0695080310 0.0051997072 1.0112460000 118738028 95654128 1785323520 -0.0672612935 -0.1907218695 -0.1043381244 1081 1311867206.4905378819 0.0523887724 0.0596708904 0.0695080310 0.0052069103 1.0353240000 118740386 95654128 1784352768 -0.0683109164 -0.1936423630 -0.1044640318 1082 1311867206.5250329971 0.0518021807 0.0596636180 0.0695080310 0.0052077977 0.9712250000 118741376 95654128 1783209984 -0.0693738461 -0.1979719102 -0.1044499800 1083 1311867206.5539300442 0.0519360192 0.0596564827 0.0695080310 0.0052110702 0.9124530000 118743530 95654128 1784815616 -0.0688993186 -0.1988710016 -0.1046789587 1084 1311867206.5921130180 0.0517632253 0.0596492011 0.0695080310 0.0052096160 0.8966770000 118745780 95654128 1783828480 -0.0690996051 -0.2020909339 -0.1045731828 1085 1311867206.6226360798 0.0524062142 0.0596425255 0.0695080310 0.0052178779 0.8935960000 118916826 95654128 1782829056 -0.0696327761 -0.2034579962 -0.1050086394 1086 1311867206.6566751003 0.0519389547 0.0596354320 0.0695080310 0.0052164499 0.8119980000 118919044 95654128 1784561664 -0.0700808465 -0.2049652189 -0.1053370759 1087 1311867206.6945209503 0.0520151965 0.0596284216 0.0695080310 0.0052143454 0.7962250000 118921466 95654128 1783590912 -0.0700502694 -0.2063502669 -0.1056110114 1088 1311867206.7248480320 0.0513629429 0.0596208247 0.0695080310 0.0052231286 0.8663980000 118922360 95654128 1782448128 -0.0697103962 -0.2084418535 -0.1057357714 1089 1311867206.7587969303 0.0514755286 0.0596133451 0.0695080310 0.0052719867 0.8932170000 118924610 95654128 1784053760 -0.0701124519 -0.2128198594 -0.1057775244 1090 1311867206.7902839184 0.0507975779 0.0596052572 0.0695080310 0.0052879420 0.7565340000 118926796 95654128 1783083008 -0.0709284768 -0.2134252638 -0.1068832502 1091 1311867206.8229770660 0.0504858345 0.0595968984 0.0695080310 0.0052883300 0.8912020000 118927722 95654128 1781940224 -0.0717861354 -0.2172271460 -0.1068900228 1092 1311867206.8605449200 0.0511554480 0.0595891682 0.0695080310 0.0052866113 0.9729400000 119099784 95654128 1783672832 -0.0724681690 -0.2183131725 -0.1074517593 1093 1311867206.8907771111 0.0510750525 0.0595813785 0.0695080310 0.0052842866 0.9132120000 119100818 95654128 1785323520 -0.0714995861 -0.2181466222 -0.1082743630 1094 1311867206.9225020409 0.0516165532 0.0595740980 0.0695080310 0.0052821585 0.8566560000 119103004 95654128 1784352768 -0.0723147169 -0.2181974351 -0.1093628407 1095 1311867206.9592480659 0.0509160012 0.0595661911 0.0695080310 0.0052806726 0.9373760000 119105286 95654128 1783189504 -0.0733892396 -0.2244894356 -0.1095097661 1096 1311867206.9948680401 0.0508841574 0.0595582695 0.0695080310 0.0052866632 0.9479940000 119106244 95654128 1784848384 -0.0733408183 -0.2263890058 -0.1098681465 1097 1311867207.0247550011 0.0513271466 0.0595507662 0.0695080310 0.0052894849 0.8943140000 119108430 95654128 1783844864 -0.0739952624 -0.2284725457 -0.1102680266 1098 1311867207.0597259998 0.0506955422 0.0595427014 0.0695080310 0.0052879868 0.8152940000 119280068 95654128 1782816768 -0.0734311193 -0.2306715548 -0.1105710417 1099 1311867207.0942800045 0.0500250421 0.0595340411 0.0695080310 0.0052942337 0.8516120000 119281134 95654128 1784569856 -0.0741638839 -0.2355952561 -0.1105400994 1100 1311867207.1229140759 0.0499277562 0.0595253081 0.0695080310 0.0052982258 0.8442820000 119283256 95654128 1783599104 -0.0738904402 -0.2352019846 -0.1117954105 1101 1311867207.1583549976 0.0499997288 0.0595166563 0.0695080310 0.0053034394 0.7775910000 119285506 95654128 1782456320 -0.0729021505 -0.2362629026 -0.1122052148 1102 1311867207.1904919147 0.0500173829 0.0595080363 0.0695080310 0.0053021549 0.7791470000 119286400 95654128 1784078336 -0.0725475550 -0.2367587686 -0.1122848392 1103 1311867207.2226181030 0.0496978909 0.0594991423 0.0695080310 0.0053036430 1.0477070000 119288618 95654128 1785712640 -0.0727398396 -0.2386765927 -0.1122347042 1104 1311867207.2604830265 0.0487000756 0.0594893605 0.0695080310 0.0053037290 0.9952200000 119290900 95654128 1784758272 -0.0727003068 -0.2426450402 -0.1117547229 1105 1311867207.2926900387 0.0484313779 0.0594793533 0.0695080310 0.0053051552 0.8330510000 119291966 95654128 1783447552 -0.0737889111 -0.2456819266 -0.1114760041 1106 1311867207.3235239983 0.0483810380 0.0594693186 0.0695080310 0.0053092986 0.7922050000 119294120 95654128 1785069568 -0.0726489946 -0.2483682930 -0.1100592241 1107 1311867207.3597478867 0.0484226607 0.0594593397 0.0695080310 0.0053077150 0.8070250000 119296402 95654128 1783951360 -0.0725031942 -0.2456323206 -0.1110811755 1108 1311867207.3901309967 0.0485288054 0.0594494746 0.0695080310 0.0053090056 0.8797890000 119297296 95654128 1782939648 -0.0745956600 -0.2493780404 -0.1100207418 1109 1311867207.4227840900 0.0481074825 0.0594392474 0.0695080310 0.0053074628 0.9593750000 119299482 95654128 1784467456 -0.0757338703 -0.2522281110 -0.1093882918 1110 1311867207.4586789608 0.0471295230 0.0594281575 0.0695080310 0.0053085859 0.9485740000 119301732 95654128 1783463936 -0.0742199793 -0.2524802983 -0.1096510664 1111 1311867207.4927639961 0.0478845313 0.0594177672 0.0695080310 0.0053079927 0.9506740000 119302830 95654128 1782300672 -0.0771602094 -0.2553387284 -0.1090364158 1112 1311867207.5237300396 0.0475230999 0.0594070706 0.0695080310 0.0053135783 0.8897500000 119474840 95654128 1784180736 -0.0782021582 -0.2590622306 -0.1084842831 1113 1311867207.5598409176 0.0472233519 0.0593961239 0.0695080310 0.0053126551 0.8139720000 119475798 95654128 1783062528 -0.0789658725 -0.2610422969 -0.1084598377 1114 1311867207.5944800377 0.0470084138 0.0593850038 0.0695080310 0.0053124014 0.9624350000 119478048 95654128 1782050816 -0.0785861537 -0.2616837025 -0.1085229069 1115 1311867207.6259219646 0.0470618829 0.0593739517 0.0695080310 0.0053102415 0.9613050000 119480202 95654128 1783672832 -0.0817197859 -0.2656104565 -0.1082506701 1116 1311867207.6592938900 0.0470487587 0.0593629076 0.0695080310 0.0053091229 0.7842410000 119481192 95654128 1785323520 -0.0833263174 -0.2683014274 -0.1083403826 1117 1311867207.6923089027 0.0479698628 0.0593527079 0.0695080310 0.0053103013 0.7862430000 119483518 95654128 1784336384 -0.0846037343 -0.2686140537 -0.1082447767 1118 1311867207.7238640785 0.0474756472 0.0593420845 0.0695080310 0.0053120096 0.8752520000 119485704 95654128 1783209984 -0.0859518498 -0.2728113234 -0.1082013994 1119 1311867207.7588050365 0.0468106829 0.0593308857 0.0695080310 0.0053102165 0.8468590000 119656570 95654128 1784975360 -0.0861440748 -0.2748745382 -0.1086077988 1120 1311867207.7921919823 0.0470568910 0.0593199268 0.0695080310 0.0053080617 0.9188860000 119658788 95654128 1784119296 -0.0860366002 -0.2750245929 -0.1083220765 1121 1311867207.8237760067 0.0471303351 0.0593090529 0.0695080310 0.0053064051 0.9289380000 119660974 95654128 1782956032 -0.0883723497 -0.2793791294 -0.1081429869 1122 1311867207.8608479500 0.0467194021 0.0592978322 0.0695080310 0.0053047195 0.8124850000 119661964 95654128 1784561664 -0.0886418521 -0.2830922604 -0.1079246998 1123 1311867207.8937089443 0.0467172079 0.0592866295 0.0695080310 0.0053035570 0.8416760000 119664322 95654128 1783590912 -0.0865728110 -0.2806102335 -0.1082169339 1124 1311867207.9244139194 0.0460447483 0.0592748485 0.0695080310 0.0053042101 0.9494500000 119666476 95654128 1782448128 -0.0874913484 -0.2853769660 -0.1075750142 1125 1311867207.9614970684 0.0457647927 0.0592628395 0.0695080310 0.0053044581 0.8700570000 119667402 95654128 1784086528 -0.0876074433 -0.2862626612 -0.1074183807 1126 1311867207.9914131165 0.0467387252 0.0592517169 0.0695080310 0.0053289437 0.7966640000 119839528 95654128 1783226368 -0.0872343853 -0.2843687236 -0.1077639535 1127 1311867208.0248498917 0.0458929092 0.0592398635 0.0695080310 0.0053548250 0.7567880000 119841778 95654128 1782067200 -0.0884163305 -0.2893361151 -0.1071689054 1128 1311867208.0618500710 0.0457805693 0.0592279315 0.0695080310 0.0053536016 0.8029060000 119842672 95654128 1783672832 -0.0894289687 -0.2930920422 -0.1070848256 1129 1311867208.0924620628 0.0458723977 0.0592161019 0.0695080310 0.0053521496 0.8570070000 119844966 95654128 1785229312 -0.0886087194 -0.2923409641 -0.1072914898 1130 1311867208.1276559830 0.0461358204 0.0592045265 0.0695080310 0.0053507924 0.9118460000 119845924 95654128 1784225792 -0.0897060409 -0.2949607372 -0.1070848033 1131 1311867208.1596069336 0.0460593626 0.0591929039 0.0695080310 0.0053486641 0.8715190000 119848110 95654128 1783062528 -0.0896891505 -0.2944701016 -0.1079041362 1132 1311867208.1905009747 0.0460590199 0.0591813015 0.0695080310 0.0053484020 0.7937230000 119850232 95654128 1784721408 -0.0906868950 -0.2971395850 -0.1080754325 1133 1311867208.2280850410 0.0462680385 0.0591699041 0.0695080310 0.0053466476 0.9363360000 119851286 95654128 1783717888 -0.0899231732 -0.2965643704 -0.1085586250 1134 1311867208.2581789494 0.0459801517 0.0591582729 0.0695080310 0.0053447267 1.0732900000 119853440 95654128 1782554624 -0.0905033499 -0.2985464334 -0.1089359671 1135 1311867208.2901990414 0.0458880551 0.0591465811 0.0695080310 0.0053424081 0.8127500000 120024974 95654128 1784307712 -0.0905593485 -0.3006143570 -0.1088749915 1136 1311867208.3270208836 0.0449466631 0.0591340812 0.0695080310 0.0053421950 0.8928740000 120025996 95654128 1783320576 -0.0895553082 -0.3047279119 -0.1089246795 1137 1311867208.3580970764 0.0442400649 0.0591209818 0.0695080310 0.0053415756 0.8728320000 120028182 95654128 1782329344 -0.0894823745 -0.3059855402 -0.1093918234 1138 1311867208.3910560608 0.0449292846 0.0591085110 0.0695080310 0.0053399402 0.9923490000 120030336 95654128 1783934976 -0.0900022462 -0.3061096966 -0.1093185991 1139 1311867208.4260230064 0.0447536260 0.0590959080 0.0695080310 0.0053384147 0.8613810000 120031326 95654128 1785585664 -0.0916728154 -0.3105128109 -0.1093733013 1140 1311867208.4577419758 0.0449561328 0.0590835047 0.0695080310 0.0053409112 0.8526340000 120033512 95654128 1784614912 -0.0911350995 -0.3098230064 -0.1101426259 1141 1311867208.4907650948 0.0443211496 0.0590705666 0.0695080310 0.0053387479 0.7516470000 120035870 95654128 1783599104 -0.0904272124 -0.3110281527 -0.1102093011 1142 1311867208.5257411003 0.0442846641 0.0590576192 0.0695080310 0.0053367629 0.8132230000 120036860 95654128 1785204736 -0.0902912766 -0.3109621704 -0.1099655405 1143 1311867208.5583798885 0.0446718596 0.0590450332 0.0695080310 0.0053351905 0.7578140000 120209030 95654128 1784250368 -0.0901887119 -0.3122981787 -0.1086247265 1144 1311867208.5904500484 0.0446628928 0.0590324614 0.0695080310 0.0053341041 0.8060970000 120211248 95654128 1782947840 -0.0922745541 -0.3159409165 -0.1082837656 1145 1311867208.6259779930 0.0441302657 0.0590194464 0.0695080310 0.0053324035 0.8702480000 120212174 95654128 1784569856 -0.0919607207 -0.3163816035 -0.1079203188 1146 1311867208.6582078934 0.0444356054 0.0590067205 0.0695080310 0.0053304091 0.8591350000 120214392 95654128 1783451648 -0.0927433148 -0.3158237040 -0.1079051644 1147 1311867208.6910300255 0.0432544239 0.0589929871 0.0695080310 0.0053330977 0.7908070000 120215458 95654128 1782456320 -0.0928591266 -0.3182319105 -0.1065903455 1148 1311867208.7262260914 0.0437535420 0.0589797123 0.0695080310 0.0053323639 0.7536280000 120217708 95654128 1784053760 -0.0927697644 -0.3195620775 -0.1058951318 1149 1311867208.7591009140 0.0442977995 0.0589669343 0.0695080310 0.0053306116 0.7930890000 120219894 95654128 1783083008 -0.0946553573 -0.3195778728 -0.1058290750 1150 1311867208.7909750938 0.0441119149 0.0589540169 0.0695080310 0.0053301847 0.8738790000 120220788 95654128 1781919744 -0.0963267758 -0.3225421011 -0.1054949090 1151 1311867208.8259930611 0.0432074405 0.0589403361 0.0695080310 0.0053300497 0.9734930000 120393098 95654128 1783705600 -0.0934215635 -0.3242687881 -0.1040144339 1152 1311867208.8588190079 0.0437837243 0.0589271793 0.0695080310 0.0053378895 0.9728920000 120395316 95654128 1785450496 -0.0956782624 -0.3256378770 -0.1044216305 1153 1311867208.8916258812 0.0443403833 0.0589145282 0.0695080310 0.0053446178 0.8185280000 120396350 95654128 1784479744 -0.0991217270 -0.3246767521 -0.1042121127 1154 1311867208.9275119305 0.0436388813 0.0589012910 0.0695080310 0.0053457190 0.7466570000 120398568 95654128 1783332864 -0.0975398868 -0.3281993568 -0.1039649472 1155 1311867208.9577760696 0.0433705635 0.0588878445 0.0695080310 0.0053448571 0.9561230000 120400722 95654128 1784975360 -0.0984368324 -0.3323324919 -0.1040614247 1156 1311867208.9911639690 0.0439641625 0.0588749348 0.0695080310 0.0053439721 1.0949380000 120401680 95654128 1783820288 -0.0986354873 -0.3315416873 -0.1042695642 1157 1311867209.0270779133 0.0440373905 0.0588621106 0.0695080310 0.0053429616 0.9705930000 120403930 95654128 1783308288 -0.0987229124 -0.3342407048 -0.1042260230 1158 1311867209.0579569340 0.0446063615 0.0588497999 0.0695080310 0.0053408446 0.8323570000 120406084 95654128 1784958976 -0.1003622115 -0.3372168839 -0.1046820059 1159 1311867209.0906980038 0.0441047885 0.0588370778 0.0695080310 0.0053421792 0.8198840000 120407182 95654128 1784066048 -0.1000112221 -0.3362165391 -0.1056506112 1160 1311867209.1260778904 0.0436767265 0.0588240085 0.0695080310 0.0053402734 0.7308880000 120409368 95654128 1783685120 -0.0999642536 -0.3358103335 -0.1068081707 1161 1311867209.1600620747 0.0445508398 0.0588117146 0.0695080310 0.0053392186 0.7947440000 120411618 95654128 1785466880 -0.1015777066 -0.3375772536 -0.1071363464 1162 1311867209.1917839050 0.0433106981 0.0587983747 0.0695080310 0.0053373560 0.8157920000 120583088 95654128 1784594432 -0.0994977802 -0.3371110260 -0.1080300286 1163 1311867209.2259531021 0.0434555747 0.0587851822 0.0695080310 0.0053353500 0.8685170000 120585274 95654128 1784324096 -0.0987223163 -0.3370712698 -0.1080423817 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-19 01:38:53 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.5107820000 954995638 0 1769201664 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0030307032 0.0015153516 0.0030307032 0.0051710135 0.6106970000 953385791 0 1766391808 -0.0004179855 -0.0040805205 0.0006781412 3 0.0800000000 0.0063021961 0.0031109664 0.0063021961 0.0043163384 0.5598730000 953074333 0 1768177664 -0.0005357219 -0.0099226749 0.0005363578 4 0.1200000000 0.0034978779 0.0032076943 0.0063021961 0.0068916938 0.5682390000 953075935 0 1770082304 0.0011232148 -0.0099831866 0.0018558176 5 0.1600000000 0.0070138560 0.0039689266 0.0070138560 0.0064668200 0.5665210000 953077209 0 1771732992 0.0027215397 -0.0109837959 0.0027254899 6 0.2000000000 0.0037474607 0.0039320156 0.0070138560 0.0058252651 0.5703960000 953079139 0 1773350912 0.0021924744 -0.0133906724 0.0027369487 7 0.2400000000 0.0055200560 0.0041588785 0.0070138560 0.0054982837 0.5680770000 953080413 0 1775140864 0.0024585607 -0.0153336581 0.0031443520 8 0.2800000000 0.0094181057 0.0048162819 0.0094181057 0.0053446976 0.5684090000 953081687 0 1776812032 0.0038683375 -0.0161468387 0.0041306503 9 0.3200000000 0.0107593322 0.0054766209 0.0107593322 0.0050496571 0.5707150000 953082961 0 1778589696 0.0039524189 -0.0174923502 0.0041715754 10 0.3600000000 0.0107116550 0.0060001243 0.0107593322 0.0047697090 0.5715210000 953085547 0 1780240384 0.0053224508 -0.0188344084 0.0043840399 11 0.4000000000 0.0117678279 0.0065244610 0.0117678279 0.0045900930 0.5727240000 953086821 0 1781858304 0.0058938973 -0.0203031264 0.0047866073 12 0.4400000000 0.0133966962 0.0070971472 0.0133966962 0.0044341521 0.5734950000 953088095 0 1783668736 0.0062644258 -0.0214415602 0.0047239484 13 0.4800000000 0.0158700496 0.0077719859 0.0158700496 0.0044922169 0.5764410000 953089369 0 1782620160 0.0069554667 -0.0221345536 0.0048639672 14 0.5200000000 0.0175139718 0.0084678420 0.0175139718 0.0044913810 0.5756240000 953090643 0 1784160256 0.0076835668 -0.0226559360 0.0050747632 15 0.5600000000 0.0184783936 0.0091352121 0.0184783936 0.0043480890 0.5787420000 953091917 0 1783050240 0.0080343671 -0.0228929389 0.0048284428 16 0.6000000000 0.0184607804 0.0097180601 0.0184783936 0.0042054049 0.6191750000 953093191 0 1781731328 0.0079875123 -0.0230684597 0.0045861495 17 0.6400000000 0.0192412399 0.0102782472 0.0192412399 0.0040869392 0.5729810000 953094465 0 1783263232 0.0074315192 -0.0231402200 0.0042385617 18 0.6800000000 0.0199765339 0.0108170409 0.0199765339 0.0039862641 0.5839830000 953098363 0 1782239232 0.0078386646 -0.0227293652 0.0042332639 19 0.7200000000 0.0202570576 0.0113138839 0.0202570576 0.0040362789 0.5706330000 953099637 0 1783906304 0.0092463410 -0.0225248206 0.0042224741 20 0.7600000000 0.0204151012 0.0117689447 0.0204151012 0.0039323573 0.5738370000 953100911 0 1782796288 0.0095849754 -0.0227003694 0.0038053002 21 0.8000000000 0.0211696867 0.0122165991 0.0211696867 0.0038355620 0.5717340000 953102185 0 1784414208 0.0093405666 -0.0225135833 0.0041338503 22 0.8400000000 0.0208713263 0.0126099958 0.0211696867 0.0037437322 0.5712510000 953103459 0 1783410688 0.0085612098 -0.0225288440 0.0038858207 23 0.8800000000 0.0202048980 0.0129402089 0.0211696867 0.0036579517 0.5718230000 953104733 0 1782366208 0.0088347187 -0.0227466617 0.0038711813 24 0.9200000000 0.0203672405 0.0132496686 0.0211696867 0.0035866194 0.5722510000 953106007 0 1784025088 0.0099441232 -0.0232077483 0.0042073512 25 0.9600000000 0.0206863675 0.0135471366 0.0211696867 0.0035201479 0.6139650000 953107281 0 1783042048 0.0111695779 -0.0236721225 0.0046314155 26 1.0000000000 0.0211716145 0.0138403857 0.0211716145 0.0034537242 0.5686500000 953108555 0 1781886976 0.0107511897 -0.0246230643 0.0045076390 27 1.0400000000 0.0222102702 0.0141503814 0.0222102702 0.0034038690 0.5782510000 953109829 0 1783513088 0.0112664411 -0.0249360185 0.0048414213 28 1.0800000000 0.0215391777 0.0144142670 0.0222102702 0.0033590948 0.5792990000 953111103 0 1782484992 0.0127984229 -0.0254975185 0.0048252814 29 1.1200000000 0.0225214418 0.0146938248 0.0225214418 0.0035402061 0.5709180000 953112377 0 1784152064 0.0142958416 -0.0258445516 0.0051448806 30 1.1600000000 0.0220270827 0.0149382667 0.0225214418 0.0037890466 0.5737180000 953113651 0 1783119872 0.0138194486 -0.0268434957 0.0051476336 31 1.2000000000 0.0226744395 0.0151878207 0.0226744395 0.0039669023 0.5768130000 953114925 0 1782136832 0.0158906151 -0.0272215698 0.0055823214 32 1.2400000000 0.0237923823 0.0154567132 0.0237923823 0.0044084740 0.5710050000 953116199 0 1783762944 0.0180731993 -0.0270667840 0.0062088016 33 1.2800000000 0.0234685242 0.0156994954 0.0237923823 0.0047336495 0.5709280000 953117473 0 1782632448 0.0181008596 -0.0272775143 0.0068547558 34 1.3200000000 0.0235683452 0.0159309321 0.0237923823 0.0049331008 0.5999750000 953123995 0 1784414208 0.0178165454 -0.0275932252 0.0076426137 35 1.3600000000 0.0242828075 0.0161695571 0.0242828075 0.0053842019 0.5742400000 953125269 0 1783365632 0.0183059145 -0.0276384596 0.0084820995 36 1.4000000000 0.0232123416 0.0163651900 0.0242828075 0.0057359381 0.5697110000 953126543 0 1782284288 0.0192882065 -0.0282969344 0.0091561042 37 1.4400000000 0.0238645636 0.0165678758 0.0242828075 0.0061981749 0.5685190000 953127817 0 1784033280 0.0204212964 -0.0288691390 0.0098654302 38 1.4800000000 0.0235146172 0.0167506848 0.0242828075 0.0081864683 0.5762200000 953129091 0 1783140352 0.0221447907 -0.0293930564 0.0114344964 39 1.5200000000 0.0243630707 0.0169458742 0.0243630707 0.0085130288 0.5710680000 953130365 0 1782136832 0.0238734335 -0.0299722087 0.0126924748 40 1.5600000000 0.0249333009 0.0171455598 0.0249333009 0.0086534571 0.5751140000 953131639 0 1783746560 0.0251264405 -0.0307064541 0.0132727996 41 1.6000000000 0.0227659587 0.0172826427 0.0249333009 0.0087854998 0.5902020000 953132913 0 1782763520 0.0263215546 -0.0321759544 0.0141776260 42 1.6400000000 0.0241867267 0.0174470257 0.0249333009 0.0089385716 0.5783510000 953134187 0 1784397824 0.0284331664 -0.0333535150 0.0149236163 43 1.6800000000 0.0272381622 0.0176747265 0.0272381622 0.0092472809 0.5841180000 953135461 0 1783287808 0.0310361851 -0.0339145474 0.0162314605 44 1.7200000000 0.0295534898 0.0179446984 0.0295534898 0.0095294873 0.5891560000 953136735 0 1782267904 0.0330988392 -0.0345346332 0.0177192297 45 1.7600000000 0.0287318937 0.0181844139 0.0295534898 0.0098391562 0.5840970000 953138009 0 1783873536 0.0349057093 -0.0358507857 0.0186446346 46 1.8000000000 0.0200050585 0.0182239931 0.0295534898 0.0109506050 0.6053960000 953139283 0 1782870016 0.0617495105 -0.0279230289 0.0122951819 47 1.8400000000 0.0200413410 0.0182626601 0.0295534898 0.0108604853 0.6100950000 953140557 0 1784541184 0.1221652329 -0.0312380381 0.0012581302 48 1.8800000000 0.0231165700 0.0183637832 0.0295534898 0.0110193111 0.5840000000 953141831 0 1783525376 0.1248495802 -0.0345170014 0.0026448676 49 1.9200000000 0.0251062233 0.0185013840 0.0295534898 0.0111830761 0.5782910000 953143105 0 1782542336 0.1275981963 -0.0374377556 0.0034679379 50 1.9600000000 0.0273963008 0.0186792824 0.0295534898 0.0112862992 0.5756040000 953144379 0 1784127488 0.1305495948 -0.0398439839 0.0043778904 51 2.0000000000 0.0287633147 0.0188770085 0.0295534898 0.0113609686 0.5690420000 953145653 0 1783136256 0.1335841715 -0.0421532169 0.0046163108 52 2.0400000000 0.0300062299 0.0190910320 0.0300062299 0.0114281236 0.5718920000 953146927 0 1781850112 0.1370867044 -0.0442072116 0.0049715438 53 2.0800000000 0.0311352201 0.0193182808 0.0311352201 0.0114657845 0.5582250000 953148201 0 1783533568 0.1388857067 -0.0461192429 0.0052981433 54 2.1200000000 0.0332166329 0.0195756577 0.0332166329 0.0115030566 0.5613300000 953149475 0 1782407168 0.1425548494 -0.0477256700 0.0054334160 55 2.1600000000 0.0236942489 0.0196505412 0.0332166329 0.0115175333 0.5816650000 953150749 0 1784020992 0.1446274072 -0.0364435390 0.0016972346 56 2.2000000000 0.0256213825 0.0197571633 0.0332166329 0.0115954107 0.5379340000 953152023 0 1783042048 0.1459121704 -0.0398542956 0.0022159219 57 2.2400000000 0.0264290422 0.0198742138 0.0332166329 0.0117550142 0.5297340000 953153297 0 1781850112 0.1458753645 -0.0431738645 0.0030045826 58 2.2800000000 0.0282856897 0.0200192393 0.0332166329 0.0119248621 0.5233290000 953154571 0 1783517184 0.1479239315 -0.0460941978 0.0032224359 59 2.3200000000 0.0305474959 0.0201976843 0.0332166329 0.0121804036 0.5224010000 953155845 0 1782484992 0.1503429413 -0.0486670360 0.0033241399 60 2.3600000000 0.0321314670 0.0203965807 0.0332166329 0.0123588020 0.5204920000 953157119 0 1784152064 0.1535878181 -0.0509560741 0.0027087890 61 2.4000000000 0.0339946523 0.0206194999 0.0339946523 0.0126413095 0.5392330000 953158393 0 1783119872 0.1563411504 -0.0529052839 0.0028332022 62 2.4400000000 0.0309596788 0.0207862770 0.0339946523 0.0128608617 0.5404110000 953159667 0 1782034432 0.1592558771 -0.0501757786 0.0008124671 63 2.4800000000 0.0300084744 0.0209326611 0.0339946523 0.0130700515 0.5447010000 953160941 0 1783517184 0.1624461412 -0.0487444736 -0.0004865863 64 2.5200000000 0.0307331849 0.0210857943 0.0339946523 0.0132109533 0.5469110000 953162215 0 1782390784 0.1658998877 -0.0514752157 -0.0018399281 65 2.5600000000 0.0298097283 0.0212200086 0.0339946523 0.0133119665 0.5525510000 953163489 0 1783889920 0.1698773950 -0.0503016040 -0.0039645322 66 2.6000000000 0.0291592721 0.0213403005 0.0339946523 0.0133967127 0.5555490000 953175259 0 1782763520 0.1740995198 -0.0506418683 -0.0063659330 67 2.6400000000 0.0289999638 0.0214546238 0.0339946523 0.0135042182 0.5738220000 953176533 0 1784397824 0.1773356348 -0.0509838611 -0.0084102750 68 2.6800000000 0.0290552117 0.0215663972 0.0339946523 0.0136201765 0.5743240000 953177807 0 1783382016 0.1819611490 -0.0507632867 -0.0112035312 69 2.7200000000 0.0297711473 0.0216853066 0.0339946523 0.0137325433 0.5639650000 953179081 0 1782517760 0.1851116866 -0.0535357259 -0.0128239105 70 2.7600000000 0.0308556054 0.0218163109 0.0339946523 0.0139154912 0.5721990000 953180355 0 1784287232 0.1879596412 -0.0558831282 -0.0135671087 71 2.8000000000 0.0298637487 0.0219296551 0.0339946523 0.0140274839 0.6251060000 953181629 0 1783521280 0.1918370724 -0.0543755516 -0.0160651207 72 2.8400000000 0.0294991117 0.0220347864 0.0339946523 0.0141873227 0.5915410000 953182903 0 1782620160 0.1943846345 -0.0541254729 -0.0176091921 73 2.8800000000 0.0310590584 0.0221584066 0.0339946523 0.0143171643 0.5772550000 953184177 0 1784270848 0.1970846653 -0.0561640039 -0.0185308773 74 2.9200000000 0.0298303124 0.0222620810 0.0339946523 0.0143983446 0.5912930000 953185451 0 1783521280 0.2011907101 -0.0553361326 -0.0215344112 75 2.9600000000 0.0317583941 0.0223886985 0.0339946523 0.0145428843 0.5837620000 953186725 0 1782771712 0.2033577412 -0.0570571125 -0.0220549889 76 3.0000000000 0.0297146533 0.0224850926 0.0339946523 0.0145752090 0.5939820000 953187999 0 1782136832 0.2075513005 -0.0576686561 -0.0254628249 77 3.0400000000 0.0306416117 0.0225910214 0.0339946523 0.0146435693 0.5822020000 953189273 0 1783779328 0.2104737610 -0.0598748811 -0.0272907894 78 3.0800000000 0.0299411584 0.0226852540 0.0339946523 0.0146619024 0.5984580000 953190547 0 1783001088 0.2152135074 -0.0600565746 -0.0308724977 79 3.1200000000 0.0299079567 0.0227766806 0.0339946523 0.0147129802 0.5998870000 953191821 0 1782140928 0.2192739844 -0.0603831857 -0.0334458463 80 3.1600000000 0.0299608298 0.0228664824 0.0339946523 0.0151448709 0.6335420000 953193095 0 1783906304 0.2279130965 -0.0615588054 -0.0396086648 81 3.2000000000 0.0300007965 0.0229545604 0.0339946523 0.0151710423 0.5968380000 953194369 0 1782882304 0.2319781631 -0.0619219989 -0.0421079546 82 3.2400000000 0.0296288058 0.0230359536 0.0339946523 0.0151717609 0.5864600000 953195643 0 1782104064 0.2344198823 -0.0646172315 -0.0443165563 83 3.2800000000 0.0300191008 0.0231200879 0.0339946523 0.0152242482 0.5982320000 953196917 0 1784000512 0.2384096831 -0.0651855394 -0.0464992337 84 3.3200000000 0.0296368804 0.0231976688 0.0339946523 0.0152125968 0.5856440000 953198191 0 1782882304 0.2399628907 -0.0678442195 -0.0478006266 85 3.3600000000 0.0298476536 0.0232759039 0.0339946523 0.0152283181 0.6003980000 953199465 0 1782136832 0.2440209091 -0.0692799762 -0.0501435921 86 3.4000000000 0.0307388678 0.0233626826 0.0339946523 0.0152667300 0.5912330000 953200739 0 1783906304 0.2459936887 -0.0713811517 -0.0511518009 87 3.4400000000 0.0303360019 0.0234428357 0.0339946523 0.0152948376 0.5961460000 953202013 0 1783279616 0.2500515878 -0.0713699311 -0.0536424443 88 3.4800000000 0.0305055026 0.0235230932 0.0339946523 0.0153171362 0.5951030000 953203287 0 1782349824 0.2538995147 -0.0706913471 -0.0562323183 89 3.5200000000 0.0313644409 0.0236111983 0.0339946523 0.0153157880 0.5799840000 953204561 0 1784160256 0.2561988235 -0.0721889883 -0.0579915792 90 3.5600000000 0.0311378185 0.0236948274 0.0339946523 0.0153234077 0.5800190000 953205835 0 1783279616 0.2582818270 -0.0740545094 -0.0595234185 91 3.6000000000 0.0318831913 0.0237848094 0.0339946523 0.0153406771 0.5805380000 953207109 0 1782497280 0.2610257268 -0.0755276307 -0.0609788671 92 3.6400000000 0.0311910007 0.0238653115 0.0339946523 0.0153414369 0.5919120000 953208383 0 1784287232 0.2646813989 -0.0738518909 -0.0633245334 93 3.6800000000 0.0312708616 0.0239449411 0.0339946523 0.0153011996 0.5781610000 953209657 0 1783492608 0.2658623457 -0.0754571855 -0.0649282560 94 3.7200000000 0.0319113508 0.0240296901 0.0339946523 0.0152626594 0.5763060000 953210931 0 1782771712 0.2685708106 -0.0766274184 -0.0661762506 95 3.7600000000 0.0327821225 0.0241218210 0.0339946523 0.0152198953 0.5797690000 953212205 0 1784414208 0.2717747986 -0.0771834999 -0.0681217238 96 3.8000000000 0.0329752043 0.0242140437 0.0339946523 0.0151750469 0.5753250000 953213479 0 1783685120 0.2743087113 -0.0777107626 -0.0703830570 97 3.8400000000 0.0332776383 0.0243074828 0.0339946523 0.0151380768 0.5744990000 953214753 0 1782861824 0.2767067850 -0.0782771632 -0.0723249391 98 3.8800000000 0.0330784880 0.0243969829 0.0339946523 0.0150962511 0.6126610000 953216027 0 1782095872 0.2777773738 -0.0791504681 -0.0730271861 99 3.9200000000 0.0331035182 0.0244849277 0.0339946523 0.0150407800 0.5727650000 953217301 0 1783779328 0.2799656391 -0.0798791647 -0.0750722289 100 3.9600000000 0.0328340307 0.0245684187 0.0339946523 0.0149886101 0.5733710000 953218575 0 1782988800 0.2814606130 -0.0810013860 -0.0763547048 101 4.0000000000 0.0344779231 0.0246665326 0.0344779231 0.0149380894 0.5732560000 953219849 0 1782153216 0.2843399048 -0.0808087960 -0.0776449293 102 4.0400000000 0.0348773263 0.0247666384 0.0348773263 0.0148924215 0.5713640000 953221123 0 1783906304 0.2864781320 -0.0805762783 -0.0791619420 103 4.0800000000 0.0350857787 0.0248668243 0.0350857787 0.0148464367 0.5784050000 953222397 0 1783160832 0.2887752354 -0.0802905187 -0.0803937763 104 4.1200000000 0.0355090983 0.0249691538 0.0355090983 0.0147929725 0.5727860000 953223671 0 1782251520 0.2906038463 -0.0797188878 -0.0816323385 105 4.1600000000 0.0359677821 0.0250739027 0.0359677821 0.0147449077 0.5712760000 953224945 0 1783881728 0.2930746973 -0.0789555758 -0.0833920687 106 4.2000000000 0.0358053222 0.0251751425 0.0359677821 0.0146884685 0.5736310000 953226219 0 1782923264 0.2947015464 -0.0782933235 -0.0846110955 107 4.2400000000 0.0354117379 0.0252708116 0.0359677821 0.0146255640 0.6019850000 953227493 0 1782272000 0.2954931557 -0.0779035613 -0.0853630900 108 4.2800000000 0.0362064615 0.0253720676 0.0362064615 0.0145615292 0.5708260000 953228767 0 1784029184 0.2986265123 -0.0764499977 -0.0879948139 109 4.3200000000 0.0360504501 0.0254700344 0.0362064615 0.0144944618 0.5715780000 953230041 0 1783304192 0.3001860380 -0.0756386667 -0.0892599076 110 4.3600000000 0.0363718309 0.0255691417 0.0363718309 0.0144302703 0.5750410000 953231315 0 1782484992 0.3011218309 -0.0748663172 -0.0903142840 111 4.4000000000 0.0371932536 0.0256738634 0.0371932536 0.0143664628 0.5725090000 953232589 0 1784168448 0.3023641706 -0.0735634640 -0.0915317610 112 4.4400000000 0.0380605049 0.0257844584 0.0380605049 0.0143085158 0.5766790000 953233863 0 1783152640 0.3045689464 -0.0718040690 -0.0935506374 113 4.4800000000 0.0386020243 0.0258978882 0.0386020243 0.0142454916 0.5738390000 953235137 0 1782517760 0.3061260283 -0.0698958933 -0.0945895612 114 4.5200000000 0.0383558199 0.0260071683 0.0386020243 0.0141824083 0.5712910000 953236411 0 1784143872 0.3069632947 -0.0681228787 -0.0956537277 115 4.5600000000 0.0387445576 0.0261179282 0.0387445576 0.0141223698 0.5722440000 953237685 0 1783382016 0.3081066608 -0.0660410598 -0.0970716774 116 4.6000000000 0.0384928845 0.0262246089 0.0387445576 0.0140652910 0.5693320000 953238959 0 1782607872 0.3085239530 -0.0643293038 -0.0981341377 117 4.6400000000 0.0388605520 0.0263326084 0.0388605520 0.0140230429 0.5696260000 953240233 0 1784270848 0.3093242049 -0.0621537827 -0.0994405448 118 4.6800000000 0.0378930345 0.0264305781 0.0388605520 0.0139879780 0.5686650000 953241507 0 1783537664 0.3096379936 -0.0606743805 -0.1001128554 119 4.7200000000 0.0387563370 0.0265341559 0.0388605520 0.0139488813 0.5687750000 953242781 0 1782771712 0.3100874126 -0.0588278472 -0.1004454568 120 4.7600000000 0.0384603292 0.0266335407 0.0388605520 0.0139025731 0.5684440000 953244055 0 1782005760 0.3098065257 -0.0575556830 -0.1014042646 121 4.8000000000 0.0386215337 0.0267326150 0.0388605520 0.0138585643 0.5788000000 953245329 0 1783652352 0.3092122972 -0.0563839786 -0.1010206193 122 4.8400000000 0.0406300798 0.0268465286 0.0406300798 0.0138324472 0.5693970000 953246603 0 1782603776 0.3085488975 -0.0536486953 -0.1013753563 123 4.8800000000 0.0408149511 0.0269600930 0.0408149511 0.0137863614 0.5702690000 953247877 0 1781989376 0.3078645170 -0.0515761524 -0.1011511385 124 4.9200000000 0.0401328057 0.0270663246 0.0408149511 0.0137457670 0.5722790000 953249151 0 1783783424 0.3068937957 -0.0499106385 -0.1012890711 125 4.9600000000 0.0408766679 0.0271768073 0.0408766679 0.0137046034 0.6128080000 953250425 0 1782882304 0.3066158593 -0.0477197170 -0.1008033082 126 5.0000000000 0.0406455100 0.0272837018 0.0408766679 0.0136656433 0.5744160000 953251699 0 1782005760 0.3062403798 -0.0456344411 -0.1009159908 127 5.0400000000 0.0398173966 0.0273823923 0.0408766679 0.0136370605 0.5732860000 953252973 0 1783746560 0.3048360348 -0.0432901755 -0.1004159376 128 5.0800000000 0.0377880521 0.0274636865 0.0408766679 0.0136101428 0.5661120000 953254247 0 1782771712 0.3032716513 -0.0397683121 -0.1002047136 129 5.1200000000 0.0369722880 0.0275373966 0.0408766679 0.0135830501 0.5764960000 953255521 0 1784508416 0.3029180765 -0.0362764113 -0.1004662663 130 5.1600000000 0.0361709408 0.0276038085 0.0408766679 0.0135622993 0.5728790000 953277787 0 1783685120 0.3012242913 -0.0346705876 -0.0993152782 131 5.2000000000 0.0355547331 0.0276645026 0.0408766679 0.0135435439 0.5705750000 953279061 0 1783009280 0.2990324199 -0.0339557305 -0.0981506631 132 5.2400000000 0.0353088453 0.0277224143 0.0408766679 0.0135243936 0.5755760000 953280335 0 1782026240 0.2969988585 -0.0334384032 -0.0970234647 133 5.2800000000 0.0354583673 0.0277805793 0.0408766679 0.0134932471 0.5886520000 953281609 0 1783799808 0.2958523631 -0.0327608660 -0.0953815207 134 5.3200000000 0.0362328291 0.0278436558 0.0408766679 0.0134562313 0.6206780000 953282883 0 1782603776 0.2943367660 -0.0318201259 -0.0938610137 135 5.3600000000 0.0358895957 0.0279032554 0.0408766679 0.0134205192 0.5824130000 953284157 0 1784397824 0.2918370068 -0.0311931670 -0.0917735770 136 5.4000000000 0.0362543836 0.0279646607 0.0408766679 0.0133877361 0.5878660000 953285431 0 1783410688 0.2904296517 -0.0299621653 -0.0904113576 137 5.4400000000 0.0368402898 0.0280294463 0.0408766679 0.0133559260 0.5979250000 953286705 0 1782374400 0.2896467149 -0.0279332306 -0.0891539007 138 5.4800000000 0.0353743620 0.0280826704 0.0408766679 0.0134168214 0.5934160000 953287979 0 1784053760 0.2858532071 -0.0265669990 -0.0862433165 139 5.5200000000 0.0355263166 0.0281362218 0.0408766679 0.0133856648 0.5988310000 953289253 0 1783238656 0.2838682830 -0.0259217285 -0.0844861791 140 5.5600000000 0.0358380601 0.0281912349 0.0408766679 0.0133665445 0.5995010000 953290527 0 1782009856 0.2828562558 -0.0243705232 -0.0831647590 141 5.6000000000 0.0360730551 0.0282471343 0.0408766679 0.0133433641 0.6017690000 953291801 0 1783545856 0.2813153863 -0.0228414722 -0.0815996230 142 5.6400000000 0.0365126245 0.0283053420 0.0408766679 0.0133173984 0.6157920000 953293075 0 1782603776 0.2801417112 -0.0207485072 -0.0802087486 143 5.6800000000 0.0356968977 0.0283570312 0.0408766679 0.0132993831 0.6091150000 953294349 0 1784291328 0.2776838839 -0.0194926020 -0.0787237883 144 5.7200000000 0.0352500267 0.0284048993 0.0408766679 0.0132701362 0.6196470000 953295623 0 1783427072 0.2749544084 -0.0188190341 -0.0774036795 145 5.7600000000 0.0366304666 0.0284616273 0.0408766679 0.0132394127 0.6123690000 953296897 0 1782538240 0.2736958265 -0.0166454185 -0.0755931884 146 5.8000000000 0.0358509794 0.0285122393 0.0408766679 0.0132115654 0.6157110000 953298171 0 1784180736 0.2713168561 -0.0152129047 -0.0743058771 147 5.8400000000 0.0356033854 0.0285604784 0.0408766679 0.0131890458 0.6161150000 953299445 0 1783492608 0.2684658468 -0.0139813684 -0.0721116737 148 5.8800000000 0.0354373194 0.0286069435 0.0408766679 0.0131694013 0.6148500000 953300719 0 1782251520 0.2666626275 -0.0126323719 -0.0713664293 149 5.9200000000 0.0348551273 0.0286488777 0.0408766679 0.0131486427 0.6134800000 953301993 0 1783799808 0.2634463012 -0.0120406700 -0.0694160610 150 5.9600000000 0.0339867696 0.0286844636 0.0408766679 0.0131300670 0.6195560000 953303267 0 1782476800 0.2595180571 -0.0124534443 -0.0672285259 151 6.0000000000 0.0343067273 0.0287216971 0.0408766679 0.0131071854 0.6136830000 953304541 0 1784414208 0.2559889257 -0.0124760568 -0.0650641248 152 6.0400000000 0.0336031355 0.0287538119 0.0408766679 0.0130905305 0.6541600000 953305815 0 1783521280 0.2524568439 -0.0130986851 -0.0627959296 153 6.0800000000 0.0349735171 0.0287944635 0.0408766679 0.0130729711 0.6238890000 953307089 0 1782542336 0.2489896566 -0.0122154076 -0.0601724908 154 6.1200000000 0.0352523886 0.0288363981 0.0408766679 0.0130657346 0.6172600000 953308363 0 1784160256 0.2462000400 -0.0108100865 -0.0584410168 155 6.1600000000 0.0344064794 0.0288723341 0.0408766679 0.0130605581 0.6184620000 953309637 0 1783111680 0.2418426424 -0.0106844930 -0.0560834408 156 6.2000000000 0.0347746164 0.0289101693 0.0408766679 0.0130573081 0.6202250000 953310911 0 1782136832 0.2376002669 -0.0101590585 -0.0533984490 157 6.2400000000 0.0354427248 0.0289517779 0.0408766679 0.0130588723 0.6217140000 953312185 0 1783762944 0.2336495370 -0.0088100750 -0.0516060106 158 6.2800000000 0.0353192426 0.0289920783 0.0408766679 0.0130738941 0.6221470000 953313459 0 1782730752 0.2307752669 -0.0075232144 -0.0500620157 159 6.3200000000 0.0350141339 0.0290299529 0.0408766679 0.0130809773 0.6194050000 953314733 0 1784524800 0.2269551605 -0.0070644957 -0.0483440123 160 6.3600000000 0.0353497975 0.0290694519 0.0408766679 0.0130806119 0.6521010000 953316007 0 1783541760 0.2240598500 -0.0061642276 -0.0467527285 161 6.4000000000 0.0355156772 0.0291094906 0.0408766679 0.0130816596 0.6289000000 953317281 0 1782484992 0.2212878019 -0.0051454622 -0.0454325117 162 6.4400000000 0.0348549969 0.0291449566 0.0408766679 0.0130945627 0.6257030000 953318555 0 1784152064 0.2167917341 -0.0051217731 -0.0438727438 163 6.4800000000 0.0346235521 0.0291785677 0.0408766679 0.0130932181 0.6279580000 953319829 0 1783132160 0.2126551718 -0.0055398708 -0.0419742838 164 6.5200000000 0.0342471674 0.0292094738 0.0408766679 0.0130870994 0.6306610000 953321103 0 1782145024 0.2093878388 -0.0063809650 -0.0403334387 165 6.5600000000 0.0363005474 0.0292524500 0.0408766679 0.0130724861 0.6324100000 953322377 0 1783771136 0.2064366788 -0.0049717147 -0.0383624509 166 6.6000000000 0.0350837708 0.0292875784 0.0408766679 0.0130845601 0.6343620000 953323651 0 1782738944 0.2005636543 -0.0051191044 -0.0358615927 167 6.6400000000 0.0349636711 0.0293215670 0.0408766679 0.0131018264 0.6338820000 953324925 0 1784406016 0.1964601278 -0.0052293581 -0.0337671191 168 6.6800000000 0.0362364724 0.0293627271 0.0408766679 0.0130999283 0.6758600000 953326199 0 1783296000 0.1934868693 -0.0039691916 -0.0318818726 169 6.7200000000 0.0350318812 0.0293962724 0.0408766679 0.0131440399 0.6442520000 953327473 0 1782231040 0.1891364008 -0.0040435814 -0.0302558728 170 6.7600000000 0.0347115956 0.0294275390 0.0408766679 0.0131625272 0.6364970000 953328747 0 1783898112 0.1851835549 -0.0048073577 -0.0288558062 171 6.8000000000 0.0363595076 0.0294680769 0.0408766679 0.0131708317 0.6468820000 953330021 0 1782890496 0.1836912781 -0.0036274833 -0.0278924499 172 6.8400000000 0.0363673456 0.0295081889 0.0408766679 0.0131900603 0.6529890000 953331295 0 1784508416 0.1815637499 -0.0026567797 -0.0269087721 173 6.8800000000 0.0356697626 0.0295438049 0.0408766679 0.0132165509 0.6524250000 953332569 0 1783525376 0.1803937852 -0.0024985275 -0.0265971757 174 6.9200000000 0.0346875302 0.0295733666 0.0408766679 0.0132485405 0.6551430000 953333843 0 1782394880 0.1786070019 -0.0034552666 -0.0252365638 175 6.9600000000 0.0354776680 0.0296071054 0.0408766679 0.0132884117 0.6579830000 953335117 0 1784000512 0.1787439138 -0.0032710517 -0.0248426534 176 7.0000000000 0.0361240879 0.0296441337 0.0408766679 0.0132973502 0.6664710000 953336391 0 1783017472 0.1788972169 -0.0025167977 -0.0248989724 177 7.0400000000 0.0367944054 0.0296845307 0.0408766679 0.0133377409 0.6814820000 953337665 0 1781878784 0.1769612283 -0.0011232005 -0.0240114927 178 7.0800000000 0.0363400429 0.0297219213 0.0408766679 0.0133809922 0.6798840000 953338939 0 1783365632 0.1744874269 -0.0003768830 -0.0235625952 179 7.1200000000 0.0351126827 0.0297520373 0.0408766679 0.0134442183 0.6948940000 953340213 0 1782288384 0.1722313911 -0.0009114746 -0.0229719747 180 7.1600000000 0.0362385362 0.0297880734 0.0408766679 0.0134732017 0.7011560000 953341487 0 1783762944 0.1716946065 -0.0003579760 -0.0226584151 181 7.2000000000 0.0363284498 0.0298242080 0.0408766679 0.0134631803 0.7132270000 953342761 0 1782763520 0.1690599173 -0.0001857742 -0.0219880063 182 7.2400000000 0.0367979221 0.0298625251 0.0408766679 0.0134568319 0.7231810000 953344035 0 1784381440 0.1688282937 0.0005764841 -0.0219962373 183 7.2800000000 0.0369591527 0.0299013045 0.0408766679 0.0134426023 0.7316950000 953345309 0 1783287808 0.1645383835 0.0011776263 -0.0208128449 184 7.3200000000 0.0358757451 0.0299337743 0.0408766679 0.0134469780 0.7717970000 953346583 0 1782284288 0.1621351540 0.0008624807 -0.0205775127 185 7.3600000000 0.0364655554 0.0299690812 0.0408766679 0.0134340932 0.7428520000 953347857 0 1783762944 0.1575066149 0.0008073336 -0.0201461073 186 7.4000000000 0.0360477120 0.0300017621 0.0408766679 0.0134491989 0.7450740000 953349131 0 1782603776 0.1569994092 0.0008090884 -0.0196920559 187 7.4400000000 0.0353579372 0.0300304047 0.0408766679 0.0134682368 0.7500390000 953350405 0 1784143872 0.1542775482 -0.0002141986 -0.0195037331 188 7.4800000000 0.0354871564 0.0300594300 0.0408766679 0.0134839419 0.7583090000 953351679 0 1782870016 0.1514086425 -0.0011655312 -0.0185487811 189 7.5200000000 0.0365681425 0.0300938676 0.0408766679 0.0135163756 0.7500600000 953352953 0 1784524800 0.1495726407 -0.0007671915 -0.0177155621 190 7.5600000000 0.0356834382 0.0301232864 0.0408766679 0.0135720249 0.7594800000 953354227 0 1783492608 0.1464831233 -0.0015608423 -0.0170257557 191 7.6000000000 0.0370273590 0.0301594334 0.0408766679 0.0136084768 0.7517690000 953355501 0 1782394880 0.1456182152 -0.0007005489 -0.0167463049 192 7.6400000000 0.0366660878 0.0301933222 0.0408766679 0.0136313948 0.7523610000 953356775 0 1783889920 0.1428432316 -0.0006948262 -0.0164750870 193 7.6800000000 0.0368720815 0.0302279272 0.0408766679 0.0136652009 0.7534670000 953358049 0 1782763520 0.1415514946 -0.0001978347 -0.0159693137 194 7.7200000000 0.0362148769 0.0302587877 0.0408766679 0.0136708890 0.7507710000 953359323 0 1784254464 0.1389505416 -0.0011241980 -0.0162767377 195 7.7600000000 0.0373758599 0.0302952855 0.0408766679 0.0136657471 0.7527840000 953360597 0 1783287808 0.1400895715 -0.0000908683 -0.0161526036 196 7.8000000000 0.0370112322 0.0303295506 0.0408766679 0.0136526022 0.7569180000 953361871 0 1782136832 0.1364819705 -0.0003080054 -0.0162624307 197 7.8400000000 0.0343723036 0.0303500722 0.0408766679 0.0136714550 0.7781490000 953363145 0 1783635968 0.1389086246 0.0026196691 -0.0162197445 198 7.8800000000 0.0360565782 0.0303788929 0.0408766679 0.0136736411 0.7956430000 953364419 0 1782509568 0.1375825554 0.0016462287 -0.0160449389 199 7.9200000000 0.0343513414 0.0303988550 0.0408766679 0.0137026040 0.7783950000 953365693 0 1784000512 0.1415897757 0.0044189668 -0.0158405285 200 7.9600000000 0.0361381136 0.0304275512 0.0408766679 0.0137131018 0.7673110000 953366967 0 1782890496 0.1410733908 0.0040408997 -0.0157590788 201 8.0000000000 0.0362847745 0.0304566917 0.0408766679 0.0137289283 0.7692890000 953368241 0 1784397824 0.1430203319 0.0042756605 -0.0154534290 202 8.0400000000 0.0354345404 0.0304813345 0.0408766679 0.0137329960 0.7808840000 953369515 0 1783144448 0.1396221071 0.0042588138 -0.0154522117 203 8.0800000000 0.0354060419 0.0305055941 0.0408766679 0.0137164018 0.7934810000 953370789 0 1781993472 0.1358185560 0.0053711408 -0.0151371397 204 8.1200000000 0.0351823941 0.0305285196 0.0408766679 0.0136882159 0.7907140000 953372063 0 1783619584 0.1336019933 0.0075274347 -0.0145504577 205 8.1600000000 0.0338014364 0.0305444851 0.0408766679 0.0136651651 0.7948540000 953373337 0 1782525952 0.1308349669 0.0071448251 -0.0140096238 206 8.1999999990 0.0330063589 0.0305564359 0.0408766679 0.0136500464 0.8031760000 953374611 0 1784143872 0.1278677285 0.0054347045 -0.0125729255 207 8.2400000000 0.0337636657 0.0305719298 0.0408766679 0.0136437818 0.8042550000 953375885 0 1782898688 0.1259335279 0.0061897966 -0.0116723431 208 8.2799999990 0.0320587195 0.0305790778 0.0408766679 0.0136663740 0.8113730000 953377159 0 1784397824 0.1249905527 0.0049591144 -0.0099549806 209 8.3200000000 0.0331805386 0.0305915250 0.0408766679 0.0136767721 0.8290890000 953378433 0 1783246848 0.1236896664 0.0058500310 -0.0092961146 210 8.3599999990 0.0343335010 0.0306093439 0.0408766679 0.0136883403 0.8242490000 953379707 0 1782104064 0.1215979382 0.0083775399 -0.0086029936 211 8.4000000000 0.0337235779 0.0306241033 0.0408766679 0.0137238672 0.8309410000 953380981 0 1783644160 0.1193476990 0.0094737522 -0.0077729826 212 8.4399999990 0.0319380015 0.0306303009 0.0408766679 0.0137548419 0.8729650000 953382255 0 1782517760 0.1185882986 0.0081888093 -0.0058968402 213 8.4800000000 0.0333774947 0.0306431986 0.0408766679 0.0137632708 0.8382520000 953383529 0 1784025088 0.1158118099 0.0082712974 -0.0050101751 214 8.5200000000 0.0329539366 0.0306539964 0.0408766679 0.0137810925 0.8455570000 953384803 0 1782788096 0.1140881553 0.0085486928 -0.0035659829 215 8.5600000000 0.0322962254 0.0306616347 0.0408766679 0.0138156919 0.8535080000 953386077 0 1784389632 0.1123699918 0.0074671707 -0.0023399573 216 8.6000000000 0.0328311138 0.0306716786 0.0408766679 0.0138339084 0.8494890000 953387351 0 1783373824 0.1136802509 0.0107797682 -0.0000317786 217 8.6400000000 0.0326102413 0.0306806120 0.0408766679 0.0138366997 0.8505690000 953388625 0 1782231040 0.1137578115 0.0125675835 0.0013584848 218 8.6800000000 0.0314685218 0.0306842263 0.0408766679 0.0138489158 0.8611850000 953389899 0 1783889920 0.1151380613 0.0128492974 0.0035467371 219 8.7200000000 0.0309818517 0.0306855853 0.0408766679 0.0138769194 0.8533800000 953391173 0 1782886400 0.1167900488 0.0125539545 0.0069990228 220 8.7600000000 0.0307136644 0.0306857130 0.0408766679 0.0138907515 0.8597650000 953392447 0 1782026240 0.1174223498 0.0108704632 0.0103746243 221 8.8000000000 0.0311329532 0.0306877367 0.0408766679 0.0139166280 0.8734350000 953393721 0 1783635968 0.1186906621 0.0108712092 0.0126877306 222 8.8400000000 0.0319411270 0.0306933826 0.0408766679 0.0139437470 0.8717840000 953394995 0 1782632448 0.1182826906 0.0122038536 0.0144189484 223 8.8800000000 0.0315183811 0.0306970821 0.0408766679 0.0139833956 0.8757110000 953396269 0 1784254464 0.1172679886 0.0115047675 0.0164218526 224 8.9200000000 0.0319449045 0.0307026527 0.0408766679 0.0140013087 0.9173250000 953397543 0 1783365632 0.1143533215 0.0108944653 0.0175118856 225 8.9600000000 0.0311513282 0.0307046469 0.0408766679 0.0141442957 0.9211340000 953398817 0 1782222848 0.0727532506 0.0061091296 0.0028985552 226 9.0000000000 0.0330535583 0.0307150403 0.0408766679 0.0141473858 0.8863480000 953400091 0 1783889920 0.0682221800 0.0074565592 0.0020540738 227 9.0400000000 0.0325089581 0.0307229430 0.0408766679 0.0141551051 0.8879320000 953401365 0 1782882304 0.0646744519 0.0067659020 0.0026001662 228 9.0800000000 0.0327756740 0.0307319462 0.0408766679 0.0141628036 0.8887970000 953402639 0 1784672256 0.0610801540 0.0065891510 0.0027488347 229 9.1200000000 0.0328066349 0.0307410060 0.0408766679 0.0141690497 0.8958000000 953403913 0 1783668736 0.0569182225 0.0061241165 0.0025006181 230 9.1600000000 0.0330830850 0.0307511889 0.0408766679 0.0141784837 0.9341540000 953405187 0 1782484992 0.0524349585 0.0062300679 0.0025458913 231 9.2000000000 0.0329791084 0.0307608336 0.0408766679 0.0141837872 0.9005910000 953406461 0 1784291328 0.0485070646 0.0059126592 0.0020127271 232 9.2400000000 0.0329438299 0.0307702431 0.0408766679 0.0141899633 0.9136270000 953407735 0 1783152640 0.0448224843 0.0052935574 0.0023676418 233 9.2800000000 0.0332067274 0.0307807001 0.0408766679 0.0142021627 0.9102190000 953409009 0 1782120448 0.0419272967 0.0059374585 0.0015507910 234 9.3200000000 0.0332155712 0.0307911055 0.0408766679 0.0142057683 0.9116670000 953410283 0 1783746560 0.0380817652 0.0060454346 0.0008300951 235 9.3600000000 0.0330198258 0.0308005894 0.0408766679 0.0142260342 0.9149650000 953411557 0 1782730752 0.0352215096 0.0054979837 0.0007525106 236 9.4000000000 0.0329249427 0.0308095909 0.0408766679 0.0142638931 0.9173000000 953412831 0 1784508416 0.0325488672 0.0044892277 0.0004686322 237 9.4400000000 0.0326285921 0.0308172660 0.0408766679 0.0142950760 0.9226270000 953414105 0 1783508992 0.0297384430 0.0020148838 0.0000760797 238 9.4800000000 0.0323874541 0.0308238635 0.0408766679 0.0143207281 0.9178700000 953415379 0 1782730752 0.0263578743 -0.0016896807 -0.0001637796 239 9.5200000000 0.0330921561 0.0308333542 0.0408766679 0.0143330435 0.9132200000 953416653 0 1784524800 0.0238558780 -0.0021004793 -0.0006110063 240 9.5600000000 0.0320929922 0.0308386027 0.0408766679 0.0144872067 0.9112110000 953417927 0 1783668736 0.0211389102 -0.0072332039 0.0005482523 241 9.6000000000 0.0330361687 0.0308477213 0.0408766679 0.0144846819 0.9077150000 953419201 0 1783005184 0.0185579136 -0.0081785489 -0.0003472636 242 9.6400000000 0.0327133201 0.0308554303 0.0408766679 0.0144987930 0.9317660000 953420475 0 1782251520 0.0171715841 -0.0102526005 0.0001684399 243 9.6800000000 0.0326277688 0.0308627239 0.0408766679 0.0145144535 0.9107200000 953421749 0 1783910400 0.0153801562 -0.0127895540 -0.0000983924 244 9.7200000000 0.0329321958 0.0308712054 0.0408766679 0.0145239482 0.9003000000 953423023 0 1782898688 0.0137850503 -0.0137834679 0.0002720025 245 9.7600000000 0.0332683288 0.0308809895 0.0408766679 0.0145222863 0.9035100000 953424297 0 1782263808 0.0119580394 -0.0133226644 0.0000283173 246 9.8000000000 0.0329475962 0.0308893904 0.0408766679 0.0145268938 0.8890630000 953425571 0 1783910400 0.0100895250 -0.0143363914 0.0000314792 247 9.8400000000 0.0330731086 0.0308982313 0.0408766679 0.0145334122 0.8914170000 953426845 0 1783255040 0.0071599921 -0.0149283754 -0.0008216717 248 9.8800000000 0.0326543339 0.0309053124 0.0408766679 0.0145313551 0.8912250000 953428119 0 1782484992 0.0039789169 -0.0178277753 -0.0012203680 249 9.9200000000 0.0326258317 0.0309122221 0.0408766679 0.0145333572 0.8824140000 953429393 0 1784135680 0.0001761980 -0.0208569672 -0.0029886414 250 9.9600000000 0.0331069455 0.0309210010 0.0408766679 0.0145264202 0.8787840000 953430667 0 1783418880 -0.0027808114 -0.0213180520 -0.0037627753 251 10.0000000000 0.0328299701 0.0309286065 0.0408766679 0.0145276330 0.8765210000 953431941 0 1782628352 -0.0059747985 -0.0233943574 -0.0047825272 252 10.0400000000 0.0328900926 0.0309363901 0.0408766679 0.0145338077 0.8743780000 953433215 0 1784299520 -0.0094407192 -0.0255248323 -0.0061012493 253 10.0800000000 0.0329816826 0.0309444743 0.0408766679 0.0145310482 0.8812850000 953434489 0 1783537664 -0.0123382108 -0.0262480676 -0.0070047406 254 10.1200000000 0.0324595161 0.0309504390 0.0408766679 0.0145292400 0.9152140000 953435763 0 1782759424 -0.0149896936 -0.0275673494 -0.0074593504 255 10.1600000000 0.0322834365 0.0309556665 0.0408766679 0.0145234237 0.8655000000 953437037 0 1784418304 -0.0177076552 -0.0284246877 -0.0086307097 256 10.2000000000 0.0324827321 0.0309616316 0.0408766679 0.0145223193 0.8667010000 953438311 0 1783635968 -0.0201446544 -0.0297927633 -0.0090678120 257 10.2400000000 0.0323801078 0.0309671509 0.0408766679 0.0146313984 0.8636910000 953439585 0 1782730752 -0.0242698546 -0.0332149975 -0.0101067526 258 10.2800000000 0.0325918831 0.0309734483 0.0408766679 0.0146342621 0.8650540000 953482843 0 1782222848 -0.0270935390 -0.0343611054 -0.0115937842 259 10.3200000000 0.0326430537 0.0309798947 0.0408766679 0.0146257793 0.8659320000 953484117 0 1783910400 -0.0291736312 -0.0355466716 -0.0125304721 260 10.3600000000 0.0325162411 0.0309858037 0.0408766679 0.0146150436 0.9002260000 953485391 0 1782882304 -0.0311187170 -0.0372065604 -0.0132816527 261 10.4000000000 0.0325243995 0.0309916987 0.0408766679 0.0145969694 0.8685960000 953486665 0 1784672256 -0.0329734236 -0.0384786092 -0.0142699108 262 10.4400000000 0.0323760286 0.0309969824 0.0408766679 0.0145790775 0.8594160000 953487939 0 1783668736 -0.0351070724 -0.0400449969 -0.0151885971 263 10.4800000000 0.0323608555 0.0310021683 0.0408766679 0.0145616182 0.8554490000 953489213 0 1782501376 -0.0372248739 -0.0412044637 -0.0163043812 264 10.5200000000 0.0323463753 0.0310072599 0.0408766679 0.0145456305 0.8487690000 953490487 0 1784254464 -0.0389514118 -0.0424900278 -0.0167695023 265 10.5600000000 0.0322586559 0.0310119822 0.0408766679 0.0145309035 0.8549260000 953491761 0 1783255040 -0.0417524539 -0.0443794094 -0.0190005954 266 10.6000000000 0.0322499201 0.0310166361 0.0408766679 0.0145222330 0.8478990000 953493035 0 1782493184 -0.0445341915 -0.0464637540 -0.0206080023 267 10.6400000000 0.0325203016 0.0310222678 0.0408766679 0.0145245158 0.8440790000 953494309 0 1784164352 -0.0469176620 -0.0475274958 -0.0220910441 268 10.6800000000 0.0324141122 0.0310274613 0.0408766679 0.0145307548 0.8429540000 953495583 0 1783410688 -0.0494143777 -0.0491709784 -0.0237681009 269 10.7200000000 0.0323968008 0.0310325517 0.0408766679 0.0145424920 0.8395500000 953496857 0 1782620160 -0.0517812856 -0.0510527194 -0.0253633671 270 10.7600000000 0.0324068666 0.0310376418 0.0408766679 0.0145486640 0.8446870000 953498131 0 1784401920 -0.0544122607 -0.0528303087 -0.0278175715 271 10.8000000000 0.0324326493 0.0310427894 0.0408766679 0.0145538735 0.8420660000 953499405 0 1783635968 -0.0567908548 -0.0546945967 -0.0295821223 272 10.8400000000 0.0325081646 0.0310481768 0.0408766679 0.0145709350 0.8686820000 953500679 0 1782874112 -0.0591677763 -0.0564647019 -0.0316029154 273 10.8800000000 0.0325385332 0.0310536360 0.0408766679 0.0145871178 0.8322610000 953501953 0 1782095872 -0.0617338680 -0.0583271571 -0.0338552035 274 10.9200000000 0.0326334648 0.0310594018 0.0408766679 0.0145977713 0.8306090000 953503227 0 1783894016 -0.0637062117 -0.0599685609 -0.0353241488 275 10.9600000000 0.0325525925 0.0310648316 0.0408766679 0.0146063728 0.8273230000 953504501 0 1783005184 -0.0658064634 -0.0619366802 -0.0369942673 276 11.0000000000 0.0328849368 0.0310714262 0.0408766679 0.0146060448 0.8247010000 953505775 0 1782263808 -0.0677312836 -0.0628193542 -0.0388087928 277 11.0400000000 0.0317685939 0.0310739430 0.0408766679 0.0149350421 0.8413160000 953507049 0 1784000512 -0.0757891089 -0.0690593868 -0.0456497148 278 11.0800000000 0.0325127915 0.0310791187 0.0408766679 0.0149274414 0.8597520000 953508323 0 1783128064 -0.0775839984 -0.0719491988 -0.0473886430 279 11.1200000000 0.0327024907 0.0310849373 0.0408766679 0.0149143122 0.8172550000 953509597 0 1782349824 -0.0790791512 -0.0745658353 -0.0482759327 280 11.1600000000 0.0331718475 0.0310923905 0.0408766679 0.0149054940 0.8175460000 953510871 0 1784164352 -0.0801724419 -0.0760173649 -0.0489440113 281 11.2000000000 0.0331023857 0.0310995435 0.0408766679 0.0149042462 0.8164210000 953512145 0 1783390208 -0.0814026147 -0.0781890973 -0.0498954765 282 11.2400000000 0.0335434526 0.0311082099 0.0408766679 0.0149025140 0.8156770000 953513419 0 1782497280 -0.0826755166 -0.0794808865 -0.0512650162 283 11.2800000000 0.0333765596 0.0311162253 0.0408766679 0.0148952519 0.8191410000 953514693 0 1784270848 -0.0836556628 -0.0815876350 -0.0520815775 284 11.3200000000 0.0336889625 0.0311252842 0.0408766679 0.0149014201 0.8520250000 953515967 0 1783508992 -0.0848058984 -0.0832611546 -0.0531554148 285 11.3600000000 0.0337079167 0.0311343461 0.0408766679 0.0148979345 0.8067080000 953517241 0 1782603776 -0.0858880058 -0.0851827487 -0.0543349013 286 11.4000000000 0.0336845033 0.0311432627 0.0408766679 0.0148862778 0.8107650000 953518515 0 1784418304 -0.0867425054 -0.0875091553 -0.0552383289 287 11.4400000000 0.0340109132 0.0311532545 0.0408766679 0.0148700952 0.8073520000 953519789 0 1783537664 -0.0874486789 -0.0893280655 -0.0559886843 288 11.4800000000 0.0339580588 0.0311629934 0.0408766679 0.0148493795 0.8053160000 953521063 0 1782505472 -0.0884917155 -0.0914998055 -0.0572382845 289 11.5200000000 0.0340548381 0.0311729998 0.0408766679 0.0148346009 0.8075070000 953522337 0 1784168448 -0.0889122412 -0.0939671025 -0.0578176528 290 11.5600000000 0.0346470773 0.0311849794 0.0408766679 0.0148200092 0.8025210000 953523611 0 1783119872 -0.0895058587 -0.0955548435 -0.0584670603 291 11.6000000000 0.0346537307 0.0311968995 0.0408766679 0.0147978798 0.7994630000 953524885 0 1781886976 -0.0898719355 -0.0973060578 -0.0587916784 292 11.6400000000 0.0345275551 0.0312083058 0.0408766679 0.0147732495 0.7982980000 953526159 0 1783517184 -0.0906161815 -0.0993051082 -0.0600099154 293 11.6800000000 0.0346418433 0.0312200244 0.0408766679 0.0147479847 0.7966810000 953527433 0 1782509568 -0.0909141377 -0.1012899801 -0.0603712462 294 11.7200000000 0.0350604579 0.0312330871 0.0408766679 0.0147241436 0.7963070000 953528707 0 1784168448 -0.0910952687 -0.1027344391 -0.0610996149 295 11.7600000000 0.0340761133 0.0312427245 0.0408766679 0.0147069426 0.8071070000 953529981 0 1783119872 -0.0911918655 -0.1065844595 -0.0611994565 296 11.8000000000 0.0345918871 0.0312540392 0.0408766679 0.0146872809 0.7909590000 953531255 0 1782095872 -0.0911892429 -0.1092712134 -0.0614722148 297 11.8400000000 0.0353018008 0.0312676680 0.0408766679 0.0146732256 0.7878550000 953532529 0 1783635968 -0.0915399417 -0.1109707579 -0.0623386353 298 11.8800000000 0.0349246524 0.0312799398 0.0408766679 0.0147067320 0.8292450000 953533803 0 1782509568 -0.0925320908 -0.1142888889 -0.0641888902 299 11.9200000000 0.0354485884 0.0312938818 0.0408766679 0.0147096485 0.7859170000 953535077 0 1784016896 -0.0933214873 -0.1164316833 -0.0655201003 300 11.9600000000 0.0356331170 0.0313083459 0.0408766679 0.0147224205 0.7860670000 953536351 0 1782747136 -0.0936812013 -0.1184794381 -0.0661222786 301 12.0000000000 0.0357296988 0.0313230348 0.0408766679 0.0147283152 0.7902030000 953537625 0 1784270848 -0.0943612456 -0.1204888895 -0.0672471598 302 12.0400000000 0.0356606841 0.0313373978 0.0408766679 0.0147643292 0.7809180000 953538899 0 1783287808 -0.0962210819 -0.1235722750 -0.0703523308 303 12.0800000000 0.0359918997 0.0313527592 0.0408766679 0.0147498612 0.7744380000 953540173 0 1782009856 -0.0976539776 -0.1255986840 -0.0724470764 304 12.1200000000 0.0361334607 0.0313684852 0.0408766679 0.0147375864 0.7714840000 953541447 0 1783508992 -0.0991231427 -0.1275829822 -0.0748942643 305 12.1600000000 0.0365406200 0.0313854430 0.0408766679 0.0147306533 0.7780410000 953542721 0 1782349824 -0.1003914401 -0.1291138083 -0.0768737048 306 12.2000000000 0.0363683477 0.0314017270 0.0408766679 0.0147311279 0.7582270000 953543995 0 1783906304 -0.1012001634 -0.1311009675 -0.0784721375 307 12.2400000000 0.0366351455 0.0314187740 0.0408766679 0.0147439270 0.7570460000 953545269 0 1782870016 -0.1025028899 -0.1330508739 -0.0805128142 308 12.2800000000 0.0368760228 0.0314364923 0.0408766679 0.0147601231 0.7624840000 953546543 0 1781899264 -0.1040337458 -0.1348747462 -0.0830720663 309 12.3200000000 0.0368864499 0.0314541297 0.0408766679 0.0147589665 0.7480870000 953547817 0 1783492608 -0.1056780219 -0.1366268843 -0.0860675052 310 12.3600000000 0.0370202772 0.0314720851 0.0408766679 0.0147589654 0.7463860000 953549091 0 1782476800 -0.1073202118 -0.1383572668 -0.0891603902 311 12.4000000000 0.0372700058 0.0314907279 0.0408766679 0.0147586009 0.7410730000 953550365 0 1784143872 -0.1086040661 -0.1397216767 -0.0919953287 312 12.4400000000 0.0373601802 0.0315095402 0.0408766679 0.0147516620 0.7683470000 953551639 0 1783033856 -0.1098847538 -0.1409290731 -0.0946883708 313 12.4800000000 0.0373714864 0.0315282685 0.0408766679 0.0147435616 0.7332230000 953552913 0 1781968896 -0.1111628041 -0.1423165798 -0.0971648321 314 12.5200000000 0.0374451280 0.0315471120 0.0408766679 0.0147421639 0.7303440000 953554187 0 1783619584 -0.1122012362 -0.1436908543 -0.0993575826 315 12.5600000000 0.0376493856 0.0315664843 0.0408766679 0.0147443452 0.7257490000 953555461 0 1782616064 -0.1135493144 -0.1448161900 -0.1018719450 316 12.6000000000 0.0376498103 0.0315857353 0.0408766679 0.0147423054 0.7254290000 953556735 0 1784270848 -0.1148148030 -0.1459597498 -0.1043964475 317 12.6400000000 0.0378019176 0.0316053447 0.0408766679 0.0147318192 0.7264900000 953558009 0 1783238656 -0.1160547286 -0.1468921900 -0.1070018634 318 12.6800000000 0.0378578231 0.0316250066 0.0408766679 0.0147173881 0.7114380000 953559283 0 1782136832 -0.1173412874 -0.1477360278 -0.1094495654 319 12.7200000000 0.0379448310 0.0316448180 0.0408766679 0.0147333475 0.7369560000 953560557 0 1783762944 -0.1193772107 -0.1491489708 -0.1140742376 320 12.7600000000 0.0379061140 0.0316643845 0.0408766679 0.0147224462 0.7001280000 953561831 0 1782779904 -0.1204699427 -0.1500012130 -0.1162439883 321 12.8000000000 0.0381700769 0.0316846515 0.0408766679 0.0147104647 0.7003960000 953563105 0 1784381440 -0.1217484921 -0.1504712254 -0.1186099872 322 12.8400000000 0.0381137803 0.0317046177 0.0408766679 0.0146964719 0.6919480000 953564379 0 1783398400 -0.1231103912 -0.1510848850 -0.1207318902 323 12.8800000000 0.0382937267 0.0317250174 0.0408766679 0.0146827158 0.6894510000 953565653 0 1782284288 -0.1241497621 -0.1515455246 -0.1224094108 324 12.9200000000 0.0385932326 0.0317462156 0.0408766679 0.0146693964 0.6849830000 953566927 0 1783873536 -0.1254417002 -0.1517396718 -0.1245293915 325 12.9600000000 0.0387258753 0.0317676915 0.0408766679 0.0146497246 0.6828740000 953568201 0 1782870016 -0.1266501844 -0.1515965313 -0.1264607459 326 13.0000000000 0.0387229994 0.0317890268 0.0408766679 0.0146301584 0.6756480000 953569475 0 1784524800 -0.1280517131 -0.1514627337 -0.1285722405 327 13.0400000000 0.0391655602 0.0318115850 0.0408766679 0.0146105005 0.6749560000 953570749 0 1783492608 -0.1293358803 -0.1507356316 -0.1302908510 328 13.0800000000 0.0393907763 0.0318346923 0.0408766679 0.0145903859 0.6791470000 953572023 0 1782542336 -0.1307148784 -0.1498157382 -0.1322683394 329 13.1200000000 0.0398023389 0.0318589101 0.0408766679 0.0145727948 0.6737380000 953573297 0 1784152064 -0.1319461614 -0.1484729201 -0.1339009553 330 13.1600000000 0.0399980545 0.0318835742 0.0408766679 0.0145555371 0.6775730000 953574571 0 1783152640 -0.1332559586 -0.1468709856 -0.1354259551 331 13.2000000000 0.0402310118 0.0319087930 0.0408766679 0.0145399615 0.6706640000 953575845 0 1781977088 -0.1344370395 -0.1450468600 -0.1370318532 332 13.2400000000 0.0404309221 0.0319344621 0.0408766679 0.0145229792 0.6668570000 953577119 0 1783644160 -0.1356791258 -0.1428355873 -0.1381533593 333 13.2800000000 0.0405904725 0.0319604561 0.0408766679 0.0145105749 0.6690080000 953578393 0 1782534144 -0.1369766593 -0.1404032111 -0.1396466792 334 13.3200000000 0.0419089235 0.0319902419 0.0419089235 0.0145353754 0.6687310000 953579667 0 1784135680 -0.1391810179 -0.1361706555 -0.1418590248 335 13.3600000000 0.0411651060 0.0320176296 0.0419089235 0.0145233925 0.6639900000 953580941 0 1783132160 -0.1401561350 -0.1324978024 -0.1426394731 336 13.4000000000 0.0406265594 0.0320432514 0.0419089235 0.0145118270 0.6688050000 953582215 0 1782145024 -0.1411948204 -0.1290618032 -0.1433471292 337 13.4400000000 0.0396667905 0.0320658732 0.0419089235 0.0145010082 0.6601830000 953583489 0 1783627776 -0.1421264261 -0.1256160438 -0.1439090669 338 13.4800000000 0.0388358869 0.0320859028 0.0419089235 0.0145023922 0.6587500000 953584763 0 1782624256 -0.1429425776 -0.1226080805 -0.1444089413 339 13.5200000000 0.0384225063 0.0321045948 0.0419089235 0.0145132947 0.6609450000 953586037 0 1784270848 -0.1440085769 -0.1195704117 -0.1448831707 340 13.5600000000 0.0379792936 0.0321218734 0.0419089235 0.0145150220 0.6602760000 953587311 0 1783238656 -0.1448221803 -0.1168367416 -0.1447851956 341 13.6000000000 0.0377049297 0.0321382460 0.0419089235 0.0145108315 0.6614380000 953588585 0 1782136832 -0.1456329823 -0.1139409989 -0.1448663771 342 13.6400000000 0.0375460610 0.0321540583 0.0419089235 0.0145050328 0.6552460000 953589859 0 1783762944 -0.1468420476 -0.1107713580 -0.1454658359 343 13.6800000000 0.0371836983 0.0321687220 0.0419089235 0.0145134078 0.7101940000 953591133 0 1782730752 -0.1477593482 -0.1080719605 -0.1455984563 344 13.7200000000 0.0370213240 0.0321828284 0.0419089235 0.0145263782 0.6583170000 953592407 0 1784397824 -0.1484995484 -0.1051211059 -0.1457712054 345 13.7600000000 0.0371022522 0.0321970876 0.0419089235 0.0146777402 0.6566830000 953593681 0 1783377920 -0.1501241773 -0.0996070653 -0.1458218396 346 13.8000000000 0.0378023647 0.0322132878 0.0419089235 0.0146803237 0.6581950000 953594955 0 1782222848 -0.1507794112 -0.0978922248 -0.1457493901 347 13.8400000000 0.0368013680 0.0322265099 0.0419089235 0.0146876769 0.6596460000 953596229 0 1783889920 -0.1516564786 -0.0942587033 -0.1461406201 348 13.8800000000 0.0362011418 0.0322379313 0.0419089235 0.0146736958 0.6760020000 953597503 0 1782616064 -0.1524901092 -0.0906625763 -0.1463899463 349 13.9200000000 0.0361921452 0.0322492614 0.0419089235 0.0146530774 0.6764060000 953598777 0 1784254464 -0.1532955021 -0.0870650187 -0.1465721577 350 13.9600000000 0.0367117897 0.0322620115 0.0419089235 0.0146367313 0.6675340000 953600051 0 1783287808 -0.1541014761 -0.0850669295 -0.1467864811 351 14.0000000000 0.0360025987 0.0322726684 0.0419089235 0.0146363923 0.7261720000 953601325 0 1782136832 -0.1547931880 -0.0810458884 -0.1467400342 352 14.0400000000 0.0366084799 0.0322849861 0.0419089235 0.0146313520 0.6633950000 953602599 0 1783746560 -0.1555444598 -0.0786938816 -0.1466885805 353 14.0800000000 0.0358240604 0.0322950118 0.0419089235 0.0146440239 0.6830880000 953603873 0 1782755328 -0.1561874896 -0.0744215325 -0.1463420689 354 14.1200000000 0.0364605375 0.0323067788 0.0419089235 0.0146678966 0.6621570000 953605147 0 1784545280 -0.1567182988 -0.0720101148 -0.1460484564 355 14.1600000000 0.0364056490 0.0323183249 0.0419089235 0.0146903392 0.6669480000 953606421 0 1783508992 -0.1572311372 -0.0690480992 -0.1456370652 356 14.2000000000 0.0357938223 0.0323280875 0.0419089235 0.0147016438 0.6872040000 953607695 0 1782874112 -0.1577155292 -0.0650228560 -0.1454389244 357 14.2400000000 0.0364399031 0.0323396052 0.0419089235 0.0147028849 0.6698900000 953608969 0 1782153216 -0.1582067162 -0.0627445504 -0.1449884027 358 14.2800000000 0.0362827554 0.0323506196 0.0419089235 0.0147075520 0.6717720000 953610243 0 1783762944 -0.1586395651 -0.0600499958 -0.1443148255 359 14.3200000000 0.0356331505 0.0323597632 0.0419089235 0.0147161971 0.6918900000 953611517 0 1783001088 -0.1588796079 -0.0563599281 -0.1435745955 360 14.3600000000 0.0361161195 0.0323701975 0.0419089235 0.0147158998 0.6728290000 953612791 0 1782263808 -0.1591335386 -0.0539235808 -0.1431799978 361 14.4000000000 0.0354726315 0.0323787915 0.0419089235 0.0147135814 0.6931110000 953614065 0 1784020992 -0.1592002064 -0.0503997393 -0.1421654671 362 14.4400000000 0.0357285589 0.0323880450 0.0419089235 0.0147170430 0.6760680000 953615339 0 1782874112 -0.1593352854 -0.0481483489 -0.1415261477 363 14.4800000000 0.0356689803 0.0323970834 0.0419089235 0.0147191801 0.6790730000 953616613 0 1782140928 -0.1593140662 -0.0461389497 -0.1407465339 364 14.5200000000 0.0357286222 0.0324062360 0.0419089235 0.0147221223 0.6802340000 953617887 0 1783783424 -0.1594055146 -0.0433547981 -0.1401226819 365 14.5600000000 0.0356171541 0.0324150330 0.0419089235 0.0147281864 0.6928380000 953619161 0 1782984704 -0.1593383551 -0.0413903669 -0.1393264830 366 14.6000000000 0.0352972820 0.0324229080 0.0419089235 0.0148220563 0.7120600000 953620435 0 1782153216 -0.1584613025 -0.0348255150 -0.1372572482 367 14.6400000000 0.0354951732 0.0324312793 0.0419089235 0.0148350514 0.7272980000 953621709 0 1783910400 -0.1581483036 -0.0322147310 -0.1365452558 368 14.6800000000 0.0355179310 0.0324396669 0.0419089235 0.0148460401 0.7017880000 953622983 0 1783152640 -0.1573289484 -0.0294212289 -0.1348769665 369 14.7200000000 0.0351163931 0.0324469209 0.0419089235 0.0148690345 0.7306920000 953624257 0 1782349824 -0.1555505991 -0.0217421521 -0.1317759603 370 14.7600000000 0.0356243290 0.0324555085 0.0419089235 0.0148745767 0.7109530000 953625531 0 1784147968 -0.1543668360 -0.0191578120 -0.1297296286 371 14.8000000000 0.0358060710 0.0324645397 0.0419089235 0.0148762679 0.7271210000 953626805 0 1783410688 -0.1531322896 -0.0168770403 -0.1275330335 372 14.8400000000 0.0358858854 0.0324737368 0.0419089235 0.0148751707 0.7303740000 953628079 0 1782476800 -0.1520164460 -0.0148438131 -0.1250888258 373 14.8800000000 0.0360827222 0.0324834124 0.0419089235 0.0148706175 0.7336410000 953629353 0 1784254464 -0.1505556554 -0.0120959729 -0.1224106625 374 14.9200000000 0.0347478539 0.0324894671 0.0419089235 0.0148639135 0.7573510000 953630627 0 1783521280 -0.1487223953 -0.0073465491 -0.1195000261 375 14.9600000000 0.0357946604 0.0324982809 0.0419089235 0.0148586003 0.7407450000 953631901 0 1782767616 -0.1474760026 -0.0057612653 -0.1171488911 376 15.0000000000 0.0358521193 0.0325072007 0.0419089235 0.0148672524 0.7433530000 953633175 0 1782136832 -0.1458918601 -0.0035180477 -0.1145836413 377 15.0400000000 0.0358566754 0.0325160852 0.0419089235 0.0148885856 0.7464960000 953634449 0 1783873536 -0.1439995766 -0.0012440440 -0.1119689271 378 15.0800000000 0.0359825902 0.0325252559 0.0419089235 0.0149009857 0.7517150000 953635723 0 1783005184 -0.1420878917 0.0014915292 -0.1097953990 379 15.1200000000 0.0359127335 0.0325341938 0.0419089235 0.0148983665 0.7636780000 953636997 0 1782263808 -0.1399347484 0.0040454189 -0.1073516011 380 15.1600000000 0.0355547667 0.0325421427 0.0419089235 0.0149058165 0.7629040000 953638271 0 1784008704 -0.1377935112 0.0063725351 -0.1048623472 381 15.2000000000 0.0351934358 0.0325491015 0.0419089235 0.0149121136 0.8098740000 953639545 0 1783263232 -0.1357697248 0.0084214937 -0.1029013619 382 15.2400000000 0.0350327529 0.0325556032 0.0419089235 0.0149090618 0.7711400000 953640819 0 1782358016 -0.1336066425 0.0101850573 -0.1007521302 383 15.2800000000 0.0349931456 0.0325619675 0.0419089235 0.0149062173 0.7714270000 953642093 0 1784262656 -0.1315889060 0.0118343243 -0.0987531692 384 15.3200000000 0.0348238647 0.0325678579 0.0419089235 0.0149255157 0.7759240000 953643367 0 1783144448 -0.1294944286 0.0132732214 -0.0967091247 385 15.3600000000 0.0346357822 0.0325732291 0.0419089235 0.0149299162 0.7839790000 953644641 0 1782398976 -0.1270563155 0.0140096638 -0.0945648476 386 15.4000000000 0.0349112116 0.0325792861 0.0419089235 0.0149308180 0.7803690000 953645915 0 1784008704 -0.1247993335 0.0158309583 -0.0926627517 387 15.4400000000 0.0347021371 0.0325847715 0.0419089235 0.0149326425 0.7822810000 953647189 0 1783271424 -0.1221034229 0.0168426018 -0.0900296494 388 15.4800000000 0.0346016586 0.0325899696 0.0419089235 0.0149431423 0.8074480000 953648463 0 1782415360 -0.1192117482 0.0176726766 -0.0875347629 389 15.5200000000 0.0347600691 0.0325955483 0.0419089235 0.0149480267 0.7885620000 953649737 0 1784143872 -0.1169305965 0.0191332046 -0.0857206210 390 15.5600000000 0.0345697887 0.0326006104 0.0419089235 0.0149417990 0.7918940000 953651011 0 1783410688 -0.1139432862 0.0195683874 -0.0826159269 391 15.6000000000 0.0345876291 0.0326056923 0.0419089235 0.0149407778 0.7986710000 953652285 0 1782620160 -0.1115292162 0.0202672333 -0.0803755522 392 15.6400000000 0.0343938433 0.0326102539 0.0419089235 0.0149412762 0.7990260000 953653559 0 1784401920 -0.1084970459 0.0202197377 -0.0776447356 393 15.6800000000 0.0344243273 0.0326148699 0.0419089235 0.0149408973 0.8022720000 953654833 0 1783394304 -0.1059427932 0.0206359122 -0.0755414963 394 15.7200000000 0.0346032605 0.0326199166 0.0419089235 0.0149458048 0.8046560000 953656107 0 1782607872 -0.1031454876 0.0218626913 -0.0736434534 395 15.7600000000 0.0343616828 0.0326243261 0.0419089235 0.0149514773 0.8054320000 953657381 0 1784401920 -0.1003984809 0.0221067797 -0.0717156231 396 15.8000000000 0.0344836600 0.0326290214 0.0419089235 0.0149463297 0.8155500000 953658655 0 1783635968 -0.0974163339 0.0227916762 -0.0699776784 397 15.8400000000 0.0346368812 0.0326340790 0.0419089235 0.0149379017 0.8230910000 953659929 0 1782857728 -0.0941185504 0.0241164416 -0.0676517412 398 15.8800000000 0.0345745459 0.0326389545 0.0419089235 0.0149329254 0.8305520000 953661203 0 1782153216 -0.0925182253 0.0249235779 -0.0676944330 399 15.9200000000 0.0346233025 0.0326439278 0.0419089235 0.0149288138 0.8347670000 953662477 0 1783783424 -0.0893259272 0.0257401541 -0.0656946674 400 15.9600000000 0.0343743078 0.0326482538 0.0419089235 0.0149242547 0.8395180000 953663751 0 1783005184 -0.0874433517 0.0252660029 -0.0649133250 401 16.0000000000 0.0344190411 0.0326526697 0.0419089235 0.0149126514 0.8826990000 953665025 0 1782153216 -0.0855098888 0.0245808307 -0.0635467917 402 16.0400000000 0.0345740654 0.0326574493 0.0419089235 0.0149053946 0.8482260000 953666299 0 1783889920 -0.0834556520 0.0246492643 -0.0623763725 403 16.0800000000 0.0341424979 0.0326611343 0.0419089235 0.0149053086 0.8576800000 953667573 0 1782874112 -0.0818599984 0.0233743973 -0.0615306795 404 16.1200000000 0.0344256908 0.0326655020 0.0419089235 0.0149129620 0.8546190000 953668847 0 1782095872 -0.0800621882 0.0231232457 -0.0608743615 405 16.1600000000 0.0347533338 0.0326706571 0.0419089235 0.0149159906 0.8583420000 953670121 0 1783783424 -0.0776922554 0.0241714288 -0.0599780977 406 16.2000000000 0.0345598310 0.0326753103 0.0419089235 0.0149132854 0.8630030000 953671395 0 1783136256 -0.0753687173 0.0246051438 -0.0585988462 407 16.2400000000 0.0344344005 0.0326796324 0.0419089235 0.0149199805 0.8985140000 953672669 0 1782374400 -0.0725224838 0.0247976184 -0.0571792237 408 16.2800000000 0.0344717987 0.0326840249 0.0419089235 0.0149249973 0.8683270000 953673943 0 1784033280 -0.0698535070 0.0251199584 -0.0561303347 409 16.3200000000 0.0344594121 0.0326883657 0.0419089235 0.0149168347 0.8793920000 953675217 0 1783136256 -0.0667491555 0.0253278166 -0.0543358251 410 16.3600000000 0.0342426486 0.0326921567 0.0419089235 0.0149196703 0.8791210000 953676491 0 1782247424 -0.0636419654 0.0249525849 -0.0524882115 411 16.3999999990 0.0339446031 0.0326952040 0.0419089235 0.0149295868 0.8805120000 953677765 0 1784016896 -0.0605064258 0.0236303359 -0.0506560467 412 16.4400000000 0.0342423283 0.0326989591 0.0419089235 0.0149335694 0.8845430000 953679039 0 1783111680 -0.0584147200 0.0232526213 -0.0495147631 413 16.4800000000 0.0339454040 0.0327019772 0.0419089235 0.0149388664 0.8872930000 953680313 0 1782476800 -0.0556195080 0.0219901185 -0.0475015789 414 16.5200000000 0.0342451520 0.0327057046 0.0419089235 0.0149329537 0.8917410000 953681587 0 1784143872 -0.0534632243 0.0218323059 -0.0465522520 415 16.5599999990 0.0344507024 0.0327099095 0.0419089235 0.0149238184 0.8898500000 953682861 0 1783410688 -0.0513387173 0.0221981686 -0.0457040034 416 16.6000000000 0.0344223008 0.0327140258 0.0419089235 0.0149117659 0.8929630000 953684135 0 1782009856 -0.0498763137 0.0224483851 -0.0451020859 417 16.6400000000 0.0344600603 0.0327182129 0.0419089235 0.0149033177 0.8964970000 953685409 0 1783799808 -0.0476943217 0.0229483489 -0.0440851264 418 16.6800000000 0.0341585986 0.0327216588 0.0419089235 0.0148940486 0.8994160000 953686683 0 1782644736 -0.0468104370 0.0222134832 -0.0438157283 419 16.7199999990 0.0341674611 0.0327251094 0.0419089235 0.0148879051 0.9395670000 953687957 0 1784418304 -0.0446655080 0.0214701872 -0.0427329913 420 16.7600000000 0.0339413919 0.0327280053 0.0419089235 0.0148857067 0.9095710000 953689231 0 1783410688 -0.0428747684 0.0201514382 -0.0412083790 421 16.8000000000 0.0338020697 0.0327305566 0.0419089235 0.0148854545 0.9082190000 953690505 0 1782272000 -0.0408042781 0.0185859501 -0.0395515822 422 16.8400000000 0.0343368128 0.0327343628 0.0419089235 0.0148806667 0.9070270000 953691779 0 1783881728 -0.0391537100 0.0186429657 -0.0387950055 423 16.8799999990 0.0340426229 0.0327374557 0.0419089235 0.0148765067 0.9115380000 953693053 0 1782992896 -0.0371511690 0.0179141648 -0.0376912914 424 16.9200000000 0.0339258127 0.0327402584 0.0419089235 0.0148674177 0.9122430000 953694327 0 1782104064 -0.0346074067 0.0168082789 -0.0364770442 425 16.9600000000 0.0340822041 0.0327434159 0.0419089235 0.0148737323 0.9219010000 953695601 0 1783754752 -0.0321881026 0.0165332649 -0.0343118869 426 17.0000000000 0.0332726166 0.0327446582 0.0419089235 0.0148684314 0.9162580000 953696875 0 1782984704 -0.0298255775 0.0134298913 -0.0326813608 427 17.0400000000 0.0337124877 0.0327469247 0.0419089235 0.0148642178 0.9181920000 953698149 0 1782026240 -0.0269836113 0.0119805867 -0.0317400806 428 17.0800000000 0.0339449570 0.0327497239 0.0419089235 0.0148589099 0.9188550000 953699423 0 1783762944 -0.0241707675 0.0115651926 -0.0303522609 429 17.1200000000 0.0338802934 0.0327523592 0.0419089235 0.0148526586 0.9192150000 953700697 0 1782902784 -0.0217236318 0.0110327825 -0.0292340890 430 17.1600000000 0.0344726704 0.0327563600 0.0419089235 0.0148446418 0.9222690000 953701971 0 1781878784 -0.0193485077 0.0128246872 -0.0286916867 431 17.2000000000 0.0340528600 0.0327593681 0.0419089235 0.0148383327 0.9567470000 953703245 0 1783525376 -0.0169095211 0.0130535727 -0.0283225663 432 17.2400000000 0.0329693593 0.0327598542 0.0419089235 0.0148382560 0.9213900000 953704519 0 1782611968 -0.0143606300 0.0094116041 -0.0269133747 433 17.2800000000 0.0328341648 0.0327600258 0.0419089235 0.0148502738 0.9224280000 953705793 0 1784270848 -0.0128872423 0.0054975329 -0.0250865556 434 17.3200000000 0.0331578553 0.0327609425 0.0419089235 0.0148547832 0.9292060000 953707067 0 1783283712 -0.0105068060 0.0029567762 -0.0233920235 435 17.3600000000 0.0329355113 0.0327613438 0.0419089235 0.0148591848 0.9229900000 953708341 0 1781862400 -0.0082539516 -0.0002388152 -0.0223365668 436 17.4000000000 0.0331647545 0.0327622690 0.0419089235 0.0148580618 0.9293820000 953709615 0 1783508992 -0.0068375575 -0.0021950917 -0.0211777687 437 17.4400000000 0.0333621539 0.0327636417 0.0419089235 0.0148538782 0.9213820000 953710889 0 1782730752 -0.0061306898 -0.0031133308 -0.0207900219 438 17.4800000000 0.0333874971 0.0327650661 0.0419089235 0.0148688393 0.9201020000 953712163 0 1784508416 -0.0058608456 -0.0035197046 -0.0195620432 439 17.5200000000 0.0331688374 0.0327659858 0.0419089235 0.0148778110 0.9269610000 953713437 0 1783619584 -0.0061829938 -0.0043572034 -0.0187974535 440 17.5600000000 0.0331869833 0.0327669426 0.0419089235 0.0148815141 0.9264090000 953714711 0 1782603776 -0.0075090989 -0.0048507308 -0.0184718799 441 17.6000000000 0.0330748521 0.0327676408 0.0419089235 0.0148938978 0.9278120000 953715985 0 1784381440 -0.0088379784 -0.0054005594 -0.0173663683 442 17.6400000000 0.0326467268 0.0327673673 0.0419089235 0.0149866030 0.9343190000 953717259 0 1783492608 -0.0162380710 -0.0079612024 -0.0174423084 443 17.6800000000 0.0331361927 0.0327681999 0.0419089235 0.0149955802 0.9571370000 953718533 0 1782525952 -0.0210392214 -0.0080828136 -0.0174966678 444 17.7200000000 0.0330258906 0.0327687802 0.0419089235 0.0150005439 0.9264810000 953719807 0 1784143872 -0.0240746457 -0.0081982929 -0.0167009085 445 17.7600000000 0.0320909135 0.0327672569 0.0419089235 0.0150054685 0.9236770000 953721081 0 1783140352 -0.0262501389 -0.0114139868 -0.0158716757 446 17.8000000000 0.0322893113 0.0327661853 0.0419089235 0.0150140683 0.9228840000 953722355 0 1782136832 -0.0281527024 -0.0136675974 -0.0149611272 447 17.8400000000 0.0317145698 0.0327638327 0.0419089235 0.0150124472 0.9270290000 953723629 0 1783762944 -0.0278783366 -0.0175155886 -0.0131887868 448 17.8800000000 0.0318173766 0.0327617201 0.0419089235 0.0150038811 0.9281060000 953724903 0 1782636544 -0.0272189789 -0.0204491541 -0.0118952729 449 17.9200000000 0.0318505764 0.0327596908 0.0419089235 0.0149950070 0.9627680000 953726177 0 1784270848 -0.0284291841 -0.0233168323 -0.0097937901 450 17.9600000000 0.0316490978 0.0327572228 0.0419089235 0.0149821741 0.9195800000 953727451 0 1783271424 -0.0281512681 -0.0264034681 -0.0080486881 451 18.0000000000 0.0319439173 0.0327554195 0.0419089235 0.0149745403 0.9162080000 953728725 0 1782136832 -0.0278265085 -0.0274261050 -0.0050366195 452 18.0400000000 0.0316103250 0.0327528861 0.0419089235 0.0149686435 0.9217650000 953729999 0 1783758848 -0.0275481641 -0.0293803271 -0.0019343192 453 18.0800000000 0.0315896943 0.0327503183 0.0419089235 0.0149583089 0.9184700000 953731273 0 1782890496 -0.0267484821 -0.0308427252 0.0013292662 454 18.1200000000 0.0316154808 0.0327478187 0.0419089235 0.0149462331 0.9111050000 953732547 0 1784508416 -0.0261902437 -0.0314490199 0.0053087380 455 18.1600000000 0.0312012117 0.0327444196 0.0419089235 0.0149311403 0.9191950000 953733821 0 1783365632 -0.0248934906 -0.0326464698 0.0092235170 456 18.2000000000 0.0311397780 0.0327409006 0.0419089235 0.0149220742 0.9117060000 953735095 0 1782239232 -0.0237310138 -0.0337015614 0.0142427189 457 18.2400000000 0.0308751576 0.0327368180 0.0419089235 0.0149156989 0.9309700000 953736369 0 1783873536 -0.0220601000 -0.0303061400 0.0186585467 458 18.2800000000 0.0308010392 0.0327325914 0.0419089235 0.0149045596 0.9232520000 953737643 0 1782915072 -0.0208921321 -0.0294841882 0.0248775948 459 18.3200000000 0.0306743011 0.0327281071 0.0419089235 0.0148895868 0.9190400000 953738917 0 1784532992 -0.0185921937 -0.0291934516 0.0309976637 460 18.3600000000 0.0306636915 0.0327236193 0.0419089235 0.0148752046 0.9209480000 953740191 0 1783386112 -0.0171081722 -0.0254976805 0.0374636389 461 18.4000000000 0.0305332337 0.0327188679 0.0419089235 0.0148602096 0.9490780000 953741465 0 1782280192 -0.0163149983 -0.0255715270 0.0447031520 462 18.4400000000 0.0304919723 0.0327140478 0.0419089235 0.0148446858 0.9075210000 953742739 0 1784025088 -0.0128206993 -0.0249403361 0.0523666069 463 18.4800000000 0.0305244587 0.0327093186 0.0419089235 0.0148318116 0.9075460000 953744013 0 1783025664 -0.0120548420 -0.0226797890 0.0604068488 464 18.5200000000 0.0306203924 0.0327048166 0.0419089235 0.0148186759 0.8887110000 953745287 0 1781878784 -0.0109555013 -0.0206694305 0.0695047155 465 18.5600000000 0.0304034501 0.0326998675 0.0419089235 0.0148069053 0.9075980000 953746561 0 1783382016 -0.0068330169 -0.0138987433 0.0889676809 466 18.6000000000 0.0303973816 0.0326949265 0.0419089235 0.0147921365 0.8906810000 953747835 0 1782288384 -0.0041197124 -0.0099838460 0.0992865935 467 18.6400000000 0.0302727427 0.0326897398 0.0419089235 0.0147770493 0.8857630000 953749109 0 1783746560 -0.0013031820 -0.0088696992 0.1102293953 468 18.6800000000 0.0301865358 0.0326843911 0.0419089235 0.0147635533 0.8927500000 953750383 0 1782493184 0.0006482115 -0.0039950153 0.1212936193 469 18.7200000000 0.0300591867 0.0326787936 0.0419089235 0.0147525731 0.8858110000 953751657 0 1784127488 0.0022382597 -0.0005524524 0.1327947974 470 18.7600000000 0.0298778079 0.0326728341 0.0419089235 0.0147458569 0.8855890000 953752931 0 1783025664 0.0042593479 0.0047659208 0.1445323527 471 18.8000000000 0.0296851490 0.0326664908 0.0419089235 0.0147387164 0.8831290000 953754205 0 1782009856 0.0056910757 0.0107658682 0.1568472683 472 18.8400000000 0.0295245480 0.0326598342 0.0419089235 0.0147237942 0.8829940000 953755479 0 1783508992 0.0088183703 0.0171289891 0.1685844809 473 18.8800000000 0.0291021224 0.0326523126 0.0419089235 0.0147084448 0.9300870000 953756753 0 1782525952 0.0113838930 0.0250605997 0.1804026216 474 18.9200000000 0.0292850565 0.0326452087 0.0419089235 0.0146966805 0.8839200000 953758027 0 1784160256 0.0148090012 0.0311343316 0.1915784925 475 18.9600000000 0.0290930439 0.0326377304 0.0419089235 0.0146885936 0.8745350000 953759301 0 1783144448 0.0184309091 0.0361754075 0.2041871995 476 19.0000000000 0.0288953763 0.0326298683 0.0419089235 0.0146789065 0.8714780000 953760575 0 1781993472 0.0216754042 0.0391290039 0.2161772549 477 19.0400000000 0.0285603851 0.0326213369 0.0419089235 0.0146659244 0.8843330000 953761849 0 1783492608 0.0233323444 0.0462110676 0.2278884351 478 19.0800000000 0.0283672623 0.0326124372 0.0419089235 0.0146531063 0.8833000000 953763123 0 1782476800 0.0269020107 0.0537520647 0.2389763892 479 19.1200000000 0.0284961071 0.0326038436 0.0419089235 0.0146425005 0.8714020000 953764397 0 1784127488 0.0304802954 0.0569138937 0.2507564723 480 19.1600000000 0.0283506811 0.0325949828 0.0419089235 0.0146337745 0.8660300000 953765671 0 1783025664 0.0341209397 0.0618494414 0.2618898153 481 19.2000000000 0.0278543103 0.0325851270 0.0419089235 0.0146202564 0.8814670000 953766945 0 1782009856 0.0350936837 0.0724152252 0.2720281780 482 19.2400000000 0.0279503819 0.0325755113 0.0419089235 0.0146183119 0.8674900000 953768219 0 1783508992 0.0388977937 0.0766360611 0.2835534811 483 19.2800000000 0.0277027190 0.0325654227 0.0419089235 0.0146199510 0.8725200000 953769493 0 1782509568 0.0413519926 0.0775505677 0.2950692773 484 19.3200000000 0.0275584385 0.0325550777 0.0419089235 0.0146181926 0.8679020000 953770767 0 1784033280 0.0447792560 0.0789784938 0.3062269092 485 19.3600000000 0.0275332425 0.0325447234 0.0419089235 0.0146056245 0.9036730000 953772041 0 1783033856 0.0468921289 0.0826113150 0.3173474371 486 19.4000000000 0.0272110049 0.0325337487 0.0419089235 0.0145905764 0.8807070000 953773315 0 1781858304 0.0500579588 0.0898405686 0.3273679316 487 19.4400000000 0.0273258332 0.0325230548 0.0419089235 0.0145757575 0.8589590000 953774589 0 1783492608 0.0504176430 0.0937656611 0.3390388191 488 19.4800000000 0.0271537062 0.0325120520 0.0419089235 0.0145610589 0.8643270000 953775863 0 1782272000 0.0523934327 0.0966357142 0.3500539064 489 19.5200000000 0.0268467162 0.0325004665 0.0419089235 0.0145467251 0.8845730000 953777137 0 1783906304 0.0532040447 0.1046399400 0.3605289161 490 19.5600000000 0.0269830115 0.0324892064 0.0419089235 0.0145325561 0.8734400000 953778411 0 1782525952 0.0535233133 0.1098270565 0.3712323010 491 19.6000000000 0.0266252384 0.0324772635 0.0419089235 0.0145179733 0.9581880000 953779685 0 1784160256 0.0564366914 0.1163709983 0.3814295530 492 19.6400000000 0.0266553741 0.0324654304 0.0419089235 0.0145032130 0.9401970000 953780959 0 1783123968 0.0567744412 0.1207158417 0.3916304708 493 19.6800000000 0.0265269764 0.0324533848 0.0419089235 0.0144887643 0.9559760000 953782233 0 1781899264 0.0573085248 0.1234154254 0.4025077224 494 19.7200000000 0.0263545159 0.0324410389 0.0419089235 0.0144740968 0.9615390000 953783507 0 1783382016 0.0576580875 0.1247483566 0.4137169719 495 19.7600000000 0.0262382794 0.0324285081 0.0419089235 0.0144605288 0.9668340000 953784781 0 1782394880 0.0583409183 0.1296808273 0.4248058200 496 19.8000000000 0.0261446219 0.0324158390 0.0419089235 0.0144476938 0.9686800000 953786055 0 1783885824 0.0584236719 0.1364965886 0.4352098405 497 19.8400000000 0.0260254331 0.0324029810 0.0419089235 0.0144354305 0.9727250000 953787329 0 1782915072 0.0583286025 0.1427928805 0.4461492002 498 19.8800000000 0.0259073172 0.0323899375 0.0419089235 0.0144262712 0.9926150000 953788603 0 1781776384 0.0570307150 0.1497612298 0.4568016231 499 19.9200000000 0.0257500038 0.0323766310 0.0419089235 0.0144181974 0.9981330000 953789877 0 1783406592 0.0563078485 0.1562148482 0.4683898687 500 19.9600000000 0.0255468786 0.0323629715 0.0419089235 0.0144080741 0.9941190000 953791151 0 1782407168 0.0552384891 0.1583041698 0.4795427918 501 20.0000000000 0.0254448541 0.0323491629 0.0419089235 0.0143990139 1.0018690000 953792425 0 1784025088 0.0537933484 0.1613745391 0.4903195798 502 20.0400000000 0.0253529549 0.0323352262 0.0419089235 0.0143893323 1.0370680000 953793699 0 1782878208 0.0523768738 0.1662009209 0.5013262033 503 20.0800000000 0.0252412707 0.0323211229 0.0419089235 0.0143772564 0.9927170000 953794973 0 1781899264 0.0502136946 0.1728149354 0.5120372772 504 20.1200000000 0.0250603072 0.0323067166 0.0419089235 0.0143630174 0.9863960000 953796247 0 1783508992 0.0475429744 0.1780284494 0.5228516459 505 20.1600000000 0.0249458998 0.0322921407 0.0419089235 0.0143490475 0.9814960000 953797521 0 1782636544 0.0459264331 0.1845003515 0.5333995223 506 20.2000000000 0.0247087181 0.0322771537 0.0419089235 0.0143383329 1.0021580000 953798795 0 1784160256 0.0441244170 0.1939197630 0.5432572961 507 20.2400000000 0.0246405695 0.0322620914 0.0419089235 0.0143345696 1.0178430000 953800069 0 1783123968 0.0412625857 0.1990674585 0.5536788702 508 20.2800000000 0.0245165434 0.0322468443 0.0419089235 0.0143329227 0.9747580000 953801343 0 1782026240 0.0390521027 0.2038190365 0.5637055635 509 20.3200000000 0.0243910179 0.0322314104 0.0419089235 0.0143439354 0.9775100000 953802617 0 1783652352 0.0364358798 0.2105617374 0.5731528997 510 20.3600000000 0.0242579207 0.0322157761 0.0419089235 0.0143451575 0.9677180000 953803891 0 1782632448 0.0325553790 0.2152881026 0.5825420618 511 20.4000000000 0.0241437219 0.0321999795 0.0419089235 0.0143432811 0.9737360000 953805165 0 1784287232 0.0304881334 0.2202187777 0.5912088156 512 20.4400000000 0.0240408089 0.0321840437 0.0419089235 0.0143485738 0.9633730000 953806439 0 1783267328 0.0301375929 0.2268606126 0.5991047621 513 20.4800000000 0.0238971915 0.0321678899 0.0419089235 0.0143492631 0.9658110000 953807713 0 1782284288 0.0285494756 0.2312451899 0.6073337793 514 20.5200000000 0.0237625241 0.0321515371 0.0419089235 0.0143524193 0.9653990000 953892955 0 1784143872 0.0271793157 0.2335577607 0.6157910228 515 20.5600000000 0.0237021018 0.0321351304 0.0419089235 0.0143585190 0.9708330000 953894229 0 1783140352 0.0269186869 0.2355213463 0.6228304505 516 20.6000000000 0.0236559175 0.0321186978 0.0419089235 0.0143730180 0.9783940000 953895503 0 1782136832 0.0269000288 0.2411367148 0.6299511790 517 20.6400000000 0.0235364605 0.0321020978 0.0419089235 0.0143871518 0.9712970000 953896777 0 1783783424 0.0271634329 0.2448659241 0.6364705563 518 20.6800000000 0.0234481860 0.0320853914 0.0419089235 0.0144053476 0.9727080000 953898051 0 1782628352 0.0272865891 0.2480313033 0.6429030895 519 20.7200000000 0.0234112833 0.0320686783 0.0419089235 0.0144242801 0.9719580000 953899325 0 1784418304 0.0292449966 0.2518090606 0.6485432982 520 20.7600000000 0.0233323388 0.0320518776 0.0419089235 0.0144523345 0.9726820000 953900599 0 1783410688 0.0304654781 0.2548547685 0.6540412903 521 20.8000000000 0.0232527163 0.0320349886 0.0419089235 0.0144773788 0.9766670000 953901873 0 1782394880 0.0324189961 0.2556250095 0.6593692303 522 20.8400000000 0.0232398212 0.0320181396 0.0419089235 0.0145053895 0.9681880000 953903147 0 1784037376 0.0339769386 0.2559085786 0.6645475030 523 20.8800000000 0.0238886047 0.0320025956 0.0419089235 0.0145345032 0.9486630000 953904421 0 1783111680 0.0362421311 0.2550304532 0.6690052748 524 20.9200000000 0.0232632942 0.0319859175 0.0419089235 0.0145684203 0.9641670000 953905695 0 1782349824 0.0385353789 0.2591407597 0.6731770635 525 20.9600000000 0.0240512956 0.0319708040 0.0419089235 0.0145853245 0.9470700000 953906969 0 1784127488 0.0414093956 0.2599146664 0.6770039201 526 21.0000000000 0.0239084587 0.0319554763 0.0419089235 0.0145972075 0.9383520000 953908243 0 1783255040 0.0444370657 0.2595162392 0.6807210445 527 21.0400000000 0.0245409366 0.0319414070 0.0419089235 0.0146144293 0.9299250000 953909517 0 1782620160 0.0474116877 0.2604265213 0.6841730475 528 21.0800000000 0.0245745089 0.0319274545 0.0419089235 0.0146249185 0.9231740000 953910791 0 1784381440 0.0510363877 0.2620166242 0.6871386766 529 21.1200000000 0.0242643431 0.0319129685 0.0419089235 0.0146276908 0.9189030000 953912065 0 1783648256 0.0538422093 0.2624704540 0.6901091933 530 21.1600000000 0.0245170929 0.0318990140 0.0419089235 0.0146328273 0.9140970000 953913339 0 1782878208 0.0571954846 0.2633668482 0.6928405166 531 21.2000000000 0.0242700148 0.0318846468 0.0419089235 0.0146427537 0.9273700000 953914613 0 1782140928 0.0608742610 0.2638174891 0.6954584122 532 21.2400000000 0.0241903905 0.0318701839 0.0419089235 0.0146576980 0.9044480000 953915887 0 1783783424 0.0645084307 0.2632634640 0.6978132129 533 21.2800000000 0.0243761316 0.0318561238 0.0419089235 0.0146755231 0.8918230000 953917161 0 1783013376 0.0684093311 0.2632897794 0.7000429630 534 21.3200000000 0.0244213734 0.0318422010 0.0419089235 0.0146922256 0.8854540000 953918435 0 1782382592 0.0724199265 0.2632122934 0.7022875547 535 21.3600000000 0.0246231612 0.0318287075 0.0419089235 0.0147090694 0.8781610000 953919709 0 1784045568 0.0761202946 0.2634355724 0.7046353817 536 21.4000000000 0.0247569103 0.0318155138 0.0419089235 0.0147259178 0.8758430000 953920983 0 1783308288 0.0798235983 0.2637917101 0.7067930102 537 21.4400000000 0.0249037780 0.0318026428 0.0419089235 0.0147449005 0.8735140000 953922257 0 1782501376 0.0843240246 0.2642233074 0.7090620399 538 21.4800000000 0.0250743944 0.0317901368 0.0419089235 0.0147539365 0.8630340000 953923531 0 1784152064 0.0889895335 0.2649630904 0.7109820247 539 21.5200000000 0.0251707118 0.0317778558 0.0419089235 0.0147641466 0.8592000000 953924805 0 1783164928 0.0940280855 0.2660596073 0.7126231790 540 21.5600000000 0.0247476865 0.0317648370 0.0419089235 0.0147661725 0.8550170000 953926079 0 1782415360 0.0977666602 0.2668319643 0.7148330212 541 21.6000000000 0.0247607064 0.0317518904 0.0419089235 0.0147698281 0.8497310000 953927353 0 1784033280 0.1023248732 0.2669263482 0.7166937590 542 21.6400000000 0.0254083574 0.0317401864 0.0419089235 0.0147774961 0.8516650000 953928627 0 1783013376 0.1062374935 0.2676571012 0.7185853124 543 21.6800000000 0.0253629256 0.0317284419 0.0419089235 0.0147941307 0.8802580000 953929901 0 1782411264 0.1101269871 0.2684448957 0.7206616402 544 21.7200000000 0.0253700707 0.0317167537 0.0419089235 0.0148088860 0.8343870000 953931175 0 1784127488 0.1132313311 0.2690103054 0.7228320241 545 21.7600000000 0.0257602911 0.0317058245 0.0419089235 0.0148234300 0.8278340000 953932449 0 1783238656 0.1175393239 0.2704176903 0.7249612212 546 21.8000000000 0.0236156192 0.0316910072 0.0419089235 0.0148994435 0.8341580000 953933723 0 1782501376 0.1227508858 0.2738003731 0.7295415401 547 21.8400000000 0.0248860978 0.0316785668 0.0419089235 0.0149080737 0.8107570000 953934997 0 1784291328 0.1268394589 0.2733830214 0.7316898704 548 21.8800000000 0.0259007420 0.0316680233 0.0419089235 0.0149213780 0.8049980000 953936271 0 1783173120 0.1311808527 0.2742121518 0.7334437966 549 21.9200000000 0.0261061490 0.0316578924 0.0419089235 0.0149425612 0.8405880000 953937545 0 1782263808 0.1348221898 0.2757455409 0.7355877161 550 21.9600000000 0.0258604735 0.0316473517 0.0419089235 0.0149594803 0.7922540000 953938819 0 1783873536 0.1399921179 0.2769834995 0.7371684909 551 22.0000000000 0.0265036523 0.0316380164 0.0419089235 0.0149868726 0.7899670000 953940093 0 1782747136 0.1433932036 0.2787960470 0.7387520671 552 22.0400000000 0.0261043496 0.0316279917 0.0419089235 0.0149979219 0.7852190000 953941367 0 1782136832 0.1478614360 0.2816163599 0.7401245236 553 22.0800000000 0.0249458086 0.0316159082 0.0419089235 0.0149945217 0.7796240000 953942641 0 1783894016 0.1521693766 0.2826834321 0.7417094707 554 22.1200000000 0.0250390954 0.0316040367 0.0419089235 0.0149880304 0.7705900000 953943915 0 1783132160 0.1555050611 0.2817796767 0.7437969446 555 22.1600000000 0.0267988015 0.0315953786 0.0419089235 0.0149802647 0.7719200000 953945189 0 1782366208 0.1614678651 0.2817839980 0.7449188828 556 22.2000000000 0.0278337486 0.0315886131 0.0419089235 0.0149794243 0.7623560000 953946463 0 1784037376 0.1669706106 0.2837319076 0.7461389303 557 22.2400000000 0.0273448080 0.0315809940 0.0419089235 0.0149756950 0.7603100000 953947737 0 1783009280 0.1715121716 0.2859675288 0.7476528287 558 22.2800000000 0.0275326464 0.0315737389 0.0419089235 0.0149751331 0.7528590000 953949011 0 1782243328 0.1767411083 0.2886494696 0.7491652369 559 22.3200000000 0.0273876265 0.0315662504 0.0419089235 0.0149721681 0.7538220000 953950285 0 1784000512 0.1822488308 0.2914210856 0.7505749464 560 22.3600000000 0.0266335048 0.0315574419 0.0419089235 0.0149684585 0.7502820000 953951559 0 1783128064 0.1864256263 0.2931066155 0.7530335188 561 22.4000000000 0.0272617452 0.0315497847 0.0419089235 0.0149648448 0.7483080000 953952833 0 1782398976 0.1905344427 0.2947503924 0.7548168898 562 22.4400000000 0.0279106218 0.0315433093 0.0419089235 0.0149625302 0.7496290000 953954107 0 1784127488 0.1956908852 0.2973383367 0.7560080290 563 22.4800000000 0.0276523679 0.0315363982 0.0419089235 0.0149554948 0.7772760000 953955381 0 1783263232 0.2015811950 0.3011055291 0.7566542625 564 22.5200000000 0.0263983384 0.0315272882 0.0419089235 0.0149461699 0.7396700000 953956655 0 1782476800 0.2060328722 0.3041570783 0.7582457662 565 22.5600000000 0.0257155467 0.0315170019 0.0419089235 0.0149363343 0.7349280000 953957929 0 1784164352 0.2095084935 0.3058479428 0.7599081993 566 22.6000000000 0.0266153440 0.0315083417 0.0419089235 0.0149272042 0.7319170000 953959203 0 1783156736 0.2145290375 0.3080718517 0.7612420321 567 22.6400000000 0.0262553208 0.0314990771 0.0419089235 0.0149160448 0.7253560000 953960477 0 1782407168 0.2192194164 0.3105656207 0.7622846365 568 22.6800000000 0.0260270219 0.0314894432 0.0419089235 0.0149064642 0.7270910000 953961751 0 1784143872 0.2236003876 0.3126345277 0.7636924982 569 22.7200000000 0.0259153806 0.0314796470 0.0419089235 0.0148951200 0.7196090000 953963025 0 1783156736 0.2285314202 0.3141491413 0.7641865611 570 22.7600000000 0.0267044287 0.0314712694 0.0419089235 0.0148844913 0.7519180000 953964299 0 1782415360 0.2329294980 0.3161605000 0.7650147080 571 22.8000000000 0.0268968679 0.0314632582 0.0419089235 0.0148724288 0.7151610000 953965573 0 1784262656 0.2379783392 0.3186410069 0.7657718062 572 22.8400000000 0.0269416124 0.0314553532 0.0419089235 0.0148598979 0.7107000000 953966847 0 1783418880 0.2434305996 0.3214755952 0.7655470967 573 22.8800000000 0.0262751542 0.0314463127 0.0419089235 0.0148485714 0.7072120000 953968121 0 1782018048 0.2480372787 0.3244229853 0.7660874128 574 22.9200000000 0.0261514615 0.0314370883 0.0419089235 0.0148373328 0.7016080000 953969395 0 1783664640 0.2521984875 0.3276399374 0.7663462758 575 22.9600000000 0.0257073175 0.0314271234 0.0419089235 0.0148245924 0.7056840000 953970669 0 1782611968 0.2561479211 0.3309075832 0.7669646740 576 23.0000000000 0.0262347925 0.0314181090 0.0419089235 0.0148117897 0.6964770000 953971943 0 1784279040 0.2597002089 0.3337171674 0.7675670385 577 23.0400000000 0.0263205059 0.0314092743 0.0419089235 0.0147989484 0.7364320000 953973217 0 1783267328 0.2634571195 0.3371639252 0.7679533362 578 23.0800000000 0.0256571472 0.0313993225 0.0419089235 0.0147863027 0.6913820000 953974491 0 1782284288 0.2662917972 0.3396214545 0.7683482766 579 23.1200000000 0.0269425381 0.0313916252 0.0419089235 0.0147740458 0.6884130000 953975765 0 1783906304 0.2698327601 0.3418391049 0.7681612968 580 23.1600000000 0.0276546367 0.0313851821 0.0419089235 0.0147619388 0.6903530000 953977039 0 1782870016 0.2744306624 0.3468856215 0.7679354548 581 23.2000000000 0.0266452115 0.0313770238 0.0419089235 0.0147493521 0.6858910000 953978313 0 1781878784 0.2780743241 0.3525239527 0.7676260471 582 23.2400000000 0.0255877338 0.0313670765 0.0419089235 0.0147367951 0.6877420000 953979587 0 1783492608 0.2807023823 0.3570761681 0.7675209641 583 23.2800000000 0.0258612651 0.0313576326 0.0419089235 0.0147242612 0.6808140000 953980861 0 1782509568 0.2838366330 0.3618195951 0.7675948739 584 23.3200000000 0.0247430410 0.0313463063 0.0419089235 0.0147128167 0.6767980000 953982135 0 1784143872 0.2861862481 0.3658564389 0.7669081688 585 23.3600000000 0.0241746195 0.0313340470 0.0419089235 0.0147008505 0.6721280000 953983409 0 1782984704 0.2886765003 0.3685080111 0.7664798498 586 23.4000000000 0.0245779641 0.0313225178 0.0419089235 0.0146887326 0.6684980000 953984683 0 1781899264 0.2910095155 0.3710214198 0.7664737105 587 23.4400000000 0.0248148106 0.0313114314 0.0419089235 0.0146762433 0.6664950000 953985957 0 1783377920 0.2931760252 0.3740041256 0.7662360668 588 23.4800000000 0.0244105626 0.0312996953 0.0419089235 0.0146638501 0.6677780000 953987231 0 1782239232 0.2953515351 0.3771777451 0.7661105990 589 23.5200000000 0.0241299588 0.0312875225 0.0419089235 0.0146515064 0.6642500000 953988505 0 1783779328 0.2979813814 0.3802265823 0.7659359574 590 23.5600000000 0.0235849097 0.0312744673 0.0419089235 0.0146391294 0.6722100000 953989779 0 1782636544 0.2999531031 0.3825952411 0.7661616206 591 23.6000000000 0.0239979215 0.0312621550 0.0419089235 0.0146268372 0.6618000000 953991053 0 1784127488 0.3018594384 0.3849019110 0.7666894197 592 23.6400000000 0.0239656027 0.0312498297 0.0419089235 0.0146154117 0.6626210000 953992327 0 1783144448 0.3040669262 0.3875745535 0.7663707733 593 23.6800000000 0.0221641008 0.0312345081 0.0419089235 0.0146063392 0.6982670000 953993601 0 1782026240 0.3092483580 0.3930180967 0.7659580112 594 23.7200000000 0.0223749764 0.0312195931 0.0419089235 0.0145940383 0.6587060000 953994875 0 1783619584 0.3103334308 0.3933971524 0.7667655945 595 23.7600000000 0.0233593490 0.0312063826 0.0419089235 0.0145820615 0.6572010000 953996149 0 1782616064 0.3115137219 0.3942646682 0.7672958374 596 23.8000000000 0.0239861179 0.0311942680 0.0419089235 0.0145698826 0.6539660000 953997423 0 1784143872 0.3129227161 0.3960085213 0.7680337429 597 23.8400000000 0.0238318704 0.0311819357 0.0419089235 0.0145579319 0.6608500000 953998697 0 1783111680 0.3141329885 0.3982586265 0.7684879303 598 23.8800000000 0.0230680648 0.0311683674 0.0419089235 0.0145466752 0.6537290000 953999971 0 1782018048 0.3147780001 0.4000983834 0.7692479491 599 23.9200000000 0.0232287981 0.0311551127 0.0419089235 0.0145365857 0.6483750000 954001245 0 1783779328 0.3155088127 0.4017713070 0.7701475620 600 23.9600000000 0.0230113436 0.0311415397 0.0419089235 0.0145267455 0.6478910000 954002519 0 1782620160 0.3157100677 0.4037444592 0.7709174156 601 24.0000000000 0.0223136842 0.0311268511 0.0419089235 0.0145177455 0.6437030000 954003793 0 1784397824 0.3174598515 0.4082308710 0.7718536854 602 24.0400000000 0.0225234143 0.0311125597 0.0419089235 0.0145072826 0.6439220000 954005067 0 1783394304 0.3172766268 0.4082606435 0.7729865313 603 24.0800000000 0.0230354033 0.0310991647 0.0419089235 0.0144968519 0.6434250000 954006341 0 1782476800 0.3177642226 0.4088949561 0.7738910913 604 24.1200000000 0.0235340837 0.0310866398 0.0419089235 0.0144850464 0.6410170000 954007615 0 1784176640 0.3184407353 0.4096465409 0.7747761011 605 24.1600000000 0.0240667872 0.0310750367 0.0419089235 0.0144731748 0.6482540000 954008889 0 1783119872 0.3203031123 0.4135859013 0.7755534053 606 24.2000000000 0.0236406866 0.0310627688 0.0419089235 0.0144612115 0.6404580000 954010163 0 1782112256 0.3203445077 0.4155791998 0.7767990232 607 24.2400000000 0.0235079825 0.0310503227 0.0419089235 0.0144495546 0.6377380000 954011437 0 1783783424 0.3209415674 0.4173414409 0.7773366570 608 24.2800000000 0.0234346371 0.0310377969 0.0419089235 0.0144378320 0.6412020000 954012711 0 1782759424 0.3214040697 0.4184192419 0.7782835960 609 24.3200000000 0.0234297980 0.0310253043 0.0419089235 0.0144261772 0.6829880000 954013985 0 1784508416 0.3219105303 0.4197141230 0.7787185311 610 24.3600000000 0.0241726357 0.0310140704 0.0419089235 0.0144144246 0.6394660000 954015259 0 1783685120 0.3225010037 0.4217198491 0.7791436315 611 24.4000000000 0.0244026873 0.0310032498 0.0419089235 0.0144026334 0.6348660000 954016533 0 1782632448 0.3231879771 0.4238839149 0.7795675397 612 24.4400000000 0.0239888914 0.0309917884 0.0419089235 0.0143908694 0.6433800000 954017807 0 1784381440 0.3229465783 0.4260999560 0.7804679871 613 24.4800000000 0.0242578331 0.0309808032 0.0419089235 0.0143793661 0.6453300000 954019081 0 1783377920 0.3233627379 0.4283282459 0.7810898423 614 24.5200000000 0.0239136424 0.0309692931 0.0419089235 0.0143682395 0.6390990000 954020355 0 1782284288 0.3231718838 0.4304718971 0.7818978429 615 24.5600000000 0.0238503460 0.0309577176 0.0419089235 0.0143574469 0.6370040000 954021629 0 1783873536 0.3224073052 0.4332582355 0.7828952074 616 24.6000000000 0.0235349666 0.0309456677 0.0419089235 0.0143464481 0.6397530000 954022903 0 1782870016 0.3215156496 0.4354754686 0.7842072248 617 24.6400000000 0.0237908848 0.0309340716 0.0419089235 0.0143350601 0.6642680000 954024177 0 1781878784 0.3203054070 0.4371707439 0.7856047153 618 24.6800000000 0.0240662750 0.0309229587 0.0419089235 0.0143256188 0.6375670000 954025451 0 1783492608 0.3193114102 0.4387665093 0.7871310115 619 24.7200000000 0.0241481792 0.0309120140 0.0419089235 0.0143163703 0.6387050000 954026725 0 1782509568 0.3178779781 0.4415065348 0.7884749174 620 24.7600000000 0.0238496866 0.0309006231 0.0419089235 0.0143078779 0.6418600000 954027999 0 1784160256 0.3161259890 0.4433653951 0.7898985744 621 24.8000000000 0.0244393200 0.0308902184 0.0419089235 0.0142999546 0.6425920000 954029273 0 1783140352 0.3139769733 0.4445640445 0.7919247150 622 24.8400000000 0.0248038266 0.0308804332 0.0419089235 0.0142928093 0.6393270000 954030547 0 1781882880 0.3118518889 0.4461466372 0.7942705154 623 24.8800000000 0.0257515684 0.0308722007 0.0419089235 0.0142884179 0.6417520000 954031821 0 1783508992 0.3098045886 0.4484988451 0.7964734435 624 24.9200000000 0.0250953902 0.0308629430 0.0419089235 0.0142822592 0.6432250000 954033095 0 1782525952 0.3083291650 0.4501761198 0.7983149290 625 24.9600000000 0.0257172771 0.0308547099 0.0419089235 0.0142753339 0.6765140000 954034369 0 1784160256 0.3062423468 0.4520143270 0.8004176021 626 25.0000000000 0.0257690642 0.0308465859 0.0419089235 0.0142687041 0.6445770000 954035643 0 1783123968 0.3040853739 0.4554195106 0.8023316860 627 25.0400000000 0.0224612672 0.0308332122 0.0419089235 0.0142665433 0.6840230000 954036917 0 1782026240 0.3051553965 0.4624299407 0.8018332124 628 25.0800000000 0.0230829064 0.0308208709 0.0419089235 0.0142659617 0.6465610000 954038191 0 1783771136 0.3016031384 0.4640697837 0.8043681383 629 25.1200000000 0.0239995681 0.0308100263 0.0419089235 0.0142683206 0.6447420000 954039465 0 1782771712 0.2994230390 0.4652538598 0.8059626818 630 25.1600000000 0.0241302699 0.0307994235 0.0419089235 0.0142627260 0.6454960000 954040739 0 1784406016 0.2963933945 0.4666852057 0.8081176877 631 25.2000000000 0.0247273110 0.0307898005 0.0419089235 0.0142571648 0.6479430000 954042013 0 1783398400 0.2935843170 0.4683737755 0.8099283576 632 25.2400000000 0.0240788348 0.0307791819 0.0419089235 0.0142507718 0.6467000000 954043287 0 1782112256 0.2906307578 0.4691669643 0.8124097586 633 25.2800000000 0.0245688483 0.0307693709 0.0419089235 0.0142422815 0.6455010000 954044561 0 1783762944 0.2868704200 0.4702310860 0.8145990372 634 25.3200000000 0.0251219273 0.0307604633 0.0419089235 0.0142337878 0.6503550000 954045835 0 1782779904 0.2833675742 0.4724195600 0.8170866966 635 25.3600000000 0.0248306151 0.0307511249 0.0419089235 0.0142263991 0.6554980000 954047109 0 1784254464 0.2795489132 0.4749395251 0.8198046684 636 25.4000000000 0.0242538638 0.0307409091 0.0419089235 0.0142202426 0.6557300000 954048383 0 1783144448 0.2756960392 0.4766837358 0.8221776485 637 25.4400000000 0.0241894145 0.0307306242 0.0419089235 0.0142137050 0.6553250000 954049657 0 1781899264 0.2715818882 0.4778814912 0.8250142336 638 25.4800000000 0.0239072517 0.0307199292 0.0419089235 0.0142063786 0.6571190000 954050931 0 1783619584 0.2669875026 0.4793173671 0.8282337785 639 25.5200000000 0.0232563410 0.0307082491 0.0419089235 0.0141992898 0.6604310000 954052205 0 1782624256 0.2626453638 0.4803316593 0.8313421011 640 25.5600000000 0.0225751158 0.0306955411 0.0419089235 0.0141909524 0.6652470000 954053479 0 1784401920 0.2582073510 0.4803734720 0.8347436190 641 25.6000000000 0.0227185749 0.0306830965 0.0419089235 0.0141828406 0.7005110000 954054753 0 1783394304 0.2533877790 0.4803816974 0.8379277587 642 25.6400000000 0.0235058852 0.0306719171 0.0419089235 0.0141787644 0.6759420000 954056027 0 1782497280 0.2490150630 0.4820073843 0.8409006596 643 25.6800000000 0.0234949253 0.0306607554 0.0419089235 0.0141762538 0.6738820000 954057301 0 1784274944 0.2443026751 0.4831643403 0.8439898491 644 25.7200000000 0.0230862554 0.0306489937 0.0419089235 0.0141728117 0.6762140000 954058575 0 1783410688 0.2400171310 0.4835439920 0.8467996120 645 25.7600000000 0.0236664359 0.0306381680 0.0419089235 0.0141668968 0.6773740000 954059849 0 1782603776 0.2357189357 0.4847828746 0.8493826985 646 25.8000000000 0.0237654448 0.0306275292 0.0419089235 0.0141613021 0.6830140000 954061123 0 1784307712 0.2313716114 0.4862540364 0.8522525430 647 25.8400000000 0.0234828740 0.0306164864 0.0419089235 0.0141552599 0.6882780000 954062397 0 1783377920 0.2266359925 0.4867897928 0.8553162217 648 25.8800000000 0.0245122910 0.0306070664 0.0419089235 0.0141476411 0.6913000000 954063671 0 1782366208 0.2220677882 0.4876881838 0.8580909371 649 25.9200000000 0.0248720720 0.0305982297 0.0419089235 0.0141398263 0.6938190000 954064945 0 1784381440 0.2176373005 0.4891347289 0.8608082533 650 25.9600000000 0.0216720738 0.0305844971 0.0419089235 0.0141337959 0.7414720000 954066219 0 1783267328 0.2150928825 0.4962089658 0.8625128269 651 26.0000000000 0.0218428113 0.0305710691 0.0419089235 0.0141327989 0.7244550000 954067493 0 1782390784 0.2116947770 0.4979116917 0.8647573590 652 26.0400000000 0.0218334142 0.0305576677 0.0419089235 0.0141296907 0.7263890000 954068767 0 1784143872 0.2079178691 0.5000832081 0.8666230440 653 26.0800000000 0.0224231239 0.0305452106 0.0419089235 0.0141285923 0.7133040000 954070041 0 1783373824 0.2024264932 0.5008761287 0.8691786528 654 26.1200000000 0.0218942184 0.0305319827 0.0419089235 0.0141284635 0.7364590000 954071315 0 1782497280 0.1988678724 0.5027976632 0.8712601662 655 26.1600000000 0.0214230325 0.0305180759 0.0419089235 0.0141243546 0.7623820000 954072589 0 1784381440 0.1962730736 0.5067278743 0.8727892041 656 26.2000000000 0.0228067487 0.0305063209 0.0419089235 0.0141200780 0.7730260000 954073863 0 1783382016 0.1862236261 0.5085084438 0.8767015338 657 26.2400000000 0.0216191430 0.0304927940 0.0419089235 0.0141180823 0.7585100000 954075137 0 1782620160 0.1837452054 0.5101579428 0.8783199191 658 26.2800000000 0.0216289852 0.0304793231 0.0419089235 0.0141111164 0.7678240000 954076411 0 1784307712 0.1800516844 0.5120694637 0.8798835874 659 26.3200000000 0.0212173369 0.0304652685 0.0419089235 0.0141069231 0.7937260000 954077685 0 1783394304 0.1768774688 0.5162716508 0.8811655641 660 26.3600000000 0.0213900283 0.0304515182 0.0419089235 0.0141044521 0.7821020000 954078959 0 1782382592 0.1729568839 0.5170247555 0.8827008605 661 26.4000000000 0.0215324275 0.0304380248 0.0419089235 0.0141028611 0.7855950000 954080233 0 1784254464 0.1701786220 0.5206811428 0.8834143877 662 26.4400000000 0.0214152597 0.0304243953 0.0419089235 0.0140972811 0.7891390000 954081507 0 1783144448 0.1676360071 0.5236805677 0.8841955066 663 26.4800000000 0.0216322988 0.0304111342 0.0419089235 0.0140940463 0.8151830000 954082781 0 1782493184 0.1630973071 0.5230612755 0.8858481646 664 26.5200000000 0.0213579666 0.0303974999 0.0419089235 0.0140927591 0.7970720000 954084055 0 1784025088 0.1614381969 0.5250405073 0.8866599798 665 26.5600000000 0.0229675677 0.0303863271 0.0419089235 0.0140905827 0.7803130000 954085329 0 1783119872 0.1574885249 0.5254677534 0.8879742622 666 26.6000000000 0.0232722405 0.0303756453 0.0419089235 0.0140857901 0.7872310000 954086603 0 1782136832 0.1545111090 0.5263102651 0.8890008926 667 26.6400000000 0.0236101411 0.0303655021 0.0419089235 0.0140804201 0.7879380000 954087877 0 1784156160 0.1505742520 0.5278955698 0.8899593949 668 26.6800000000 0.0234786291 0.0303551924 0.0419089235 0.0140751423 0.7948630000 954089151 0 1783017472 0.1466701627 0.5300171375 0.8909882903 669 26.7200000000 0.0209911056 0.0303411952 0.0419089235 0.0140721632 0.8439210000 954090425 0 1782259712 0.1436795294 0.5346179008 0.8916770220 670 26.7600000000 0.0216443911 0.0303282149 0.0419089235 0.0140655705 0.7997410000 954091699 0 1783898112 0.1387431175 0.5329313278 0.8930119872 671 26.8000000000 0.0211381670 0.0303145189 0.0419089235 0.0140608402 0.8279330000 954092973 0 1782882304 0.1357840300 0.5327917933 0.8944698572 672 26.8400000000 0.0221436843 0.0303023599 0.0419089235 0.0140529842 0.8098950000 954094247 0 1782272000 0.1312372833 0.5316398740 0.8960308433 673 26.8800000000 0.0211831592 0.0302888098 0.0419089235 0.0140440251 0.8314780000 954095521 0 1784029184 0.1280716062 0.5327624679 0.8972262740 674 26.9200000000 0.0208834168 0.0302748553 0.0419089235 0.0140402251 0.8379480000 954096795 0 1783152640 0.1241200343 0.5325140953 0.8987420201 675 26.9600000000 0.0214462727 0.0302617759 0.0419089235 0.0140363432 0.8164430000 954098069 0 1782398976 0.1196224615 0.5318070054 0.8998903036 676 27.0000000000 0.0218225289 0.0302492918 0.0419089235 0.0140284754 0.8166180000 954099343 0 1784143872 0.1152074933 0.5316716433 0.9007531404 677 27.0400000000 0.0215491690 0.0302364408 0.0419089235 0.0140216476 0.8083830000 954100617 0 1783492608 0.1105429232 0.5320895314 0.9014919996 678 27.0800000000 0.0214803368 0.0302235262 0.0419089235 0.0140142941 0.8114260000 954101891 0 1782636544 0.1058454737 0.5318083763 0.9024919271 679 27.1200000000 0.0214049947 0.0302105386 0.0419089235 0.0140055334 0.8107400000 954103165 0 1784401920 0.1006719768 0.5307831168 0.9035172462 680 27.1600000000 0.0208982676 0.0301968441 0.0419089235 0.0140000211 0.8318180000 954104439 0 1783779328 0.0961942077 0.5307886004 0.9047931433 681 27.2000000000 0.0208942015 0.0301831839 0.0419089235 0.0139951044 0.8366760000 954105713 0 1782988800 0.0936938971 0.5305472612 0.9055228233 682 27.2400000000 0.0208322443 0.0301694728 0.0419089235 0.0139900794 0.8276000000 954106987 0 1782112256 0.0900635570 0.5300085545 0.9062931538 683 27.2800000000 0.0208293982 0.0301557977 0.0419089235 0.0139849532 0.8288540000 954108261 0 1783889920 0.0874319077 0.5288797021 0.9072453976 684 27.3200000000 0.0221815966 0.0301441395 0.0419089235 0.0139756027 0.8082440000 954109535 0 1782882304 0.0813651830 0.5279585719 0.9084358215 685 27.3600000000 0.0211928431 0.0301310720 0.0419089235 0.0139696805 0.8278370000 954110809 0 1781862400 0.0788446665 0.5300486088 0.9092211723 686 27.4000000000 0.0217841268 0.0301189044 0.0419089235 0.0139646800 0.8091860000 954112083 0 1783640064 0.0745334923 0.5285181403 0.9104119539 687 27.4400000000 0.0210620016 0.0301057211 0.0419089235 0.0139611231 0.8361290000 954113357 0 1782628352 0.0711787194 0.5300810337 0.9117274284 688 27.4800000000 0.0209624078 0.0300924314 0.0419089235 0.0139584046 0.8273530000 954114631 0 1784381440 0.0691355541 0.5306532979 0.9127714038 689 27.5200000000 0.0226609707 0.0300816456 0.0419089235 0.0139539983 0.8087140000 954115905 0 1783398400 0.0647941455 0.5295372605 0.9136030078 690 27.5600000000 0.0233466700 0.0300718847 0.0419089235 0.0139476065 0.8094680000 954117179 0 1782390784 0.0613062978 0.5297533274 0.9146695137 691 27.6000000000 0.0211811922 0.0300590183 0.0419089235 0.0139428754 0.8684550000 954118453 0 1784029184 0.0585694164 0.5322746634 0.9155867100 692 27.6400000000 0.0223632175 0.0300478972 0.0419089235 0.0139371262 0.8109580000 954119727 0 1782988800 0.0545416363 0.5318906307 0.9168397784 693 27.6800000000 0.0223106891 0.0300367324 0.0419089235 0.0139311802 0.8162670000 954121001 0 1782005760 0.0502964519 0.5313487649 0.9178773165 694 27.7200000000 0.0211538672 0.0300239329 0.0419089235 0.0139240055 0.8252920000 954122275 0 1783762944 0.0482980423 0.5329482555 0.9190889597 695 27.7600000000 0.0210274886 0.0300109884 0.0419089235 0.0139183286 0.8284470000 954123549 0 1782984704 0.0456151068 0.5333395600 0.9201591015 696 27.8000000000 0.0210782122 0.0299981539 0.0419089235 0.0139130212 0.8090170000 954124823 0 1784672256 0.0413879193 0.5316889882 0.9214542508 697 27.8400000000 0.0219559092 0.0299866156 0.0419089235 0.0139092610 0.8440290000 954126097 0 1783668736 0.0376481377 0.5313814878 0.9224737883 698 27.8800000000 0.0209264811 0.0299736354 0.0419089235 0.0139058179 0.8317620000 954127371 0 1782607872 0.0354246832 0.5326594710 0.9235181212 699 27.9200000000 0.0214656573 0.0299614638 0.0419089235 0.0139006318 0.8144040000 954128645 0 1784266752 0.0313268341 0.5327789187 0.9245602489 700 27.9600000000 0.0215957295 0.0299495127 0.0419089235 0.0138980114 0.8089610000 954129919 0 1783365632 0.0274593830 0.5327370167 0.9256369472 701 28.0000000000 0.0222239699 0.0299384920 0.0419089235 0.0138944894 0.8080120000 954131193 0 1782493184 0.0241991989 0.5328317285 0.9265691638 702 28.0400000000 0.0236115307 0.0299294792 0.0419089235 0.0138899095 0.8056840000 954132467 0 1784180736 0.0195286330 0.5335206389 0.9271605611 703 28.0800000000 0.0232538767 0.0299199833 0.0419089235 0.0138856862 0.8062980000 954133741 0 1783152640 0.0166926496 0.5343208313 0.9283736348 704 28.1200000000 0.0227965675 0.0299098649 0.0419089235 0.0138810014 0.8108400000 954135015 0 1782136832 0.0136408443 0.5346625447 0.9294316769 705 28.1600000000 0.0226566754 0.0298995766 0.0419089235 0.0138764836 0.8175540000 954136289 0 1783758848 0.0104859909 0.5345492959 0.9308976531 706 28.2000000000 0.0220995452 0.0298885284 0.0419089235 0.0138719920 0.8157880000 954137563 0 1782755328 0.0077112475 0.5339848995 0.9320509434 707 28.2400000000 0.0219122861 0.0298772466 0.0419089235 0.0138674265 0.8206280000 954138837 0 1782104064 0.0035661259 0.5337662101 0.9332275391 708 28.2800000000 0.0218783468 0.0298659487 0.0419089235 0.0138616678 0.8147450000 954140111 0 1783775232 0.0008821151 0.5332543254 0.9344218373 709 28.3200000000 0.0229675658 0.0298562190 0.0419089235 0.0138544213 0.8156610000 954141385 0 1782382592 -0.0026866526 0.5334635973 0.9354516864 710 28.3600000000 0.0227745268 0.0298462448 0.0419089235 0.0138482255 0.8138730000 954142659 0 1784045568 -0.0067925379 0.5337648392 0.9364258647 711 28.4000000000 0.0228330269 0.0298363809 0.0419089235 0.0138432659 0.8196580000 954143933 0 1782882304 -0.0108054131 0.5333993435 0.9377104640 712 28.4400000000 0.0231973976 0.0298270565 0.0419089235 0.0138367570 0.8150230000 954145207 0 1784643584 -0.0156605132 0.5330443978 0.9386003017 713 28.4800000000 0.0235637203 0.0298182720 0.0419089235 0.0138302313 0.8193280000 954146481 0 1783521280 -0.0200774819 0.5334258676 0.9395868182 714 28.5200000000 0.0230049323 0.0298087295 0.0419089235 0.0138242867 0.8185850000 954147755 0 1782648832 -0.0240524076 0.5332396626 0.9410167933 715 28.5600000000 0.0231648143 0.0297994373 0.0419089235 0.0138165012 0.8166490000 954149029 0 1784414208 -0.0285249595 0.5334630609 0.9422738552 716 28.6000000000 0.0226475112 0.0297894486 0.0419089235 0.0138112016 0.8180530000 954150303 0 1783394304 -0.0330735818 0.5329083800 0.9434513450 717 28.6400000000 0.0232282858 0.0297802978 0.0419089235 0.0138041436 0.8221800000 954151577 0 1782603776 -0.0375936069 0.5326341391 0.9442783594 718 28.6800000000 0.0234683193 0.0297715067 0.0419089235 0.0137979683 0.8135710000 954152851 0 1784381440 -0.0426803678 0.5330753326 0.9450941086 719 28.7200000000 0.0227949694 0.0297618036 0.0419089235 0.0137950585 0.8156970000 954154125 0 1783410688 -0.0471135639 0.5323550701 0.9460069537 720 28.7600000000 0.0235706270 0.0297532047 0.0419089235 0.0137959788 0.8162320000 954155399 0 1782263808 -0.0511392429 0.5318319798 0.9468789697 721 28.8000000000 0.0229516104 0.0297437712 0.0419089235 0.0137928988 0.8170550000 954156673 0 1784164352 -0.0548214316 0.5313619971 0.9481053352 722 28.8400000000 0.0226185434 0.0297339024 0.0419089235 0.0137883722 0.8178440000 954157947 0 1783156736 -0.0597762465 0.5306115746 0.9489831924 723 28.8800000000 0.0232201647 0.0297248931 0.0419089235 0.0137820509 0.8247390000 954159221 0 1782112256 -0.0638822168 0.5302476883 0.9498671293 724 28.9200000000 0.0231041536 0.0297157485 0.0419089235 0.0137750640 0.8220930000 954160495 0 1783746560 -0.0690804869 0.5297964811 0.9505769014 725 28.9600000000 0.0227669310 0.0297061639 0.0419089235 0.0137680264 0.8195050000 954161769 0 1782775808 -0.0732253566 0.5292925835 0.9518234730 726 29.0000000000 0.0232033059 0.0296972068 0.0419089235 0.0137614375 0.8188640000 954163043 0 1784397824 -0.0769468695 0.5288998485 0.9525430202 727 29.0400000000 0.0233676303 0.0296885003 0.0419089235 0.0137571948 0.8315180000 954164317 0 1783537664 -0.0805609822 0.5286890864 0.9533793926 728 29.0800000000 0.0230958369 0.0296794445 0.0419089235 0.0137540947 0.8233300000 954165591 0 1782251520 -0.0835005492 0.5279361606 0.9541267157 729 29.1200000000 0.0231919270 0.0296705453 0.0419089235 0.0137537077 0.8299260000 954166865 0 1783898112 -0.0865675509 0.5277791023 0.9547846317 730 29.1600000000 0.0230236258 0.0296614399 0.0419089235 0.0137516707 0.8239400000 954168139 0 1782865920 -0.0891642570 0.5268406868 0.9556952715 731 29.2000000000 0.0230261236 0.0296523629 0.0419089235 0.0137492199 0.8756600000 954169413 0 1781886976 -0.0932070315 0.5257420540 0.9559655786 732 29.2400000000 0.0232251082 0.0296435825 0.0419089235 0.0137457931 0.8233370000 954170687 0 1783517184 -0.0969071686 0.5257113576 0.9563519359 733 29.2800000000 0.0227264706 0.0296341458 0.0419089235 0.0137418487 0.8266630000 954171961 0 1782513664 -0.0998255908 0.5245770812 0.9570392370 734 29.3200000000 0.0230388064 0.0296251603 0.0419089235 0.0137350093 0.8216790000 954173235 0 1784168448 -0.1023395509 0.5236806870 0.9574303031 735 29.3600000000 0.0230971258 0.0296162786 0.0419089235 0.0137277851 0.8327550000 954174509 0 1783136256 -0.1056429371 0.5234142542 0.9575264454 736 29.4000000000 0.0226043221 0.0296067515 0.0419089235 0.0137225757 0.8261750000 954175783 0 1781977088 -0.1087810323 0.5224041343 0.9576739073 737 29.4400000000 0.0225665104 0.0295971989 0.0419089235 0.0137172955 0.8640560000 954177057 0 1783754752 -0.1116161048 0.5206262469 0.9578788280 738 29.4800000000 0.0222937632 0.0295873027 0.0419089235 0.0137103792 0.8278830000 954178331 0 1782771712 -0.1132654250 0.5193411112 0.9584712386 739 29.5200000000 0.0219901986 0.0295770224 0.0419089235 0.0137047060 0.8276190000 954179605 0 1784397824 -0.1147525385 0.5176016092 0.9588972330 740 29.5600000000 0.0226251613 0.0295676280 0.0419089235 0.0137013918 0.8307260000 954180879 0 1783377920 -0.1161988005 0.5152791739 0.9590908289 741 29.6000000000 0.0225152560 0.0295581106 0.0419089235 0.0136994505 0.8370210000 954182153 0 1782120448 -0.1181301326 0.5140842199 0.9595382810 742 29.6400000000 0.0220667925 0.0295480145 0.0419089235 0.0136959450 0.8266700000 954183427 0 1783746560 -0.1197755709 0.5132479072 0.9600189924 743 29.6800000000 0.0219611209 0.0295378034 0.0419089235 0.0136933458 0.8921490000 954184701 0 1782747136 -0.1210594252 0.5118687153 0.9601352811 744 29.7200000000 0.0219394639 0.0295275905 0.0419089235 0.0136944257 0.8305800000 954185975 0 1784287232 -0.1241611317 0.5081208348 0.9609280229 745 29.7600000000 0.0221667625 0.0295177102 0.0419089235 0.0136873378 0.8350090000 954187249 0 1783287808 -0.1250647455 0.5055754781 0.9615244865 746 29.8000000000 0.0226447955 0.0295084972 0.0419089235 0.0136795223 0.8352100000 954188523 0 1782157312 -0.1264187545 0.5044713616 0.9618223906 747 29.8400000000 0.0222288668 0.0294987521 0.0419089235 0.0136718767 0.8375430000 954189797 0 1783762944 -0.1276284307 0.5032302141 0.9623842835 748 29.8800000000 0.0223606862 0.0294892092 0.0419089235 0.0136627534 0.8279200000 954191071 0 1782767616 -0.1283724159 0.5016600490 0.9627693892 749 29.9200000000 0.0221652798 0.0294794309 0.0419089235 0.0136537708 0.8692570000 954192345 0 1784516608 -0.1294853538 0.5006170869 0.9631516337 750 29.9600000000 0.0220238939 0.0294694902 0.0419089235 0.0136447260 0.8349800000 954193619 0 1783500800 -0.1306658089 0.5002902150 0.9634981155 751 30.0000000000 0.0215121694 0.0294588946 0.0419089235 0.0136358222 0.8309050000 954194893 0 1782128640 -0.1311018765 0.4974218011 0.9642843008 752 30.0400000000 0.0220423304 0.0294490321 0.0419089235 0.0136270361 0.8277550000 954196167 0 1783771136 -0.1315277070 0.4951528609 0.9651176929 753 30.0800000000 0.0219119992 0.0294390228 0.0419089235 0.0136204233 0.8406940000 954197441 0 1782788096 -0.1323437244 0.4941586852 0.9659199715 754 30.1200000000 0.0216038898 0.0294286313 0.0419089235 0.0136140735 0.8268150000 954198715 0 1784295424 -0.1320412010 0.4926671684 0.9669193029 755 30.1600000000 0.0214533098 0.0294180680 0.0419089235 0.0136077184 0.8581000000 954199989 0 1783263232 -0.1321814805 0.4914529324 0.9681177139 756 30.2000000000 0.0206625275 0.0294064866 0.0419089235 0.0135997505 0.8343040000 954201263 0 1782104064 -0.1324712038 0.4912528396 0.9689740539 757 30.2400000000 0.0203252006 0.0293944902 0.0419089235 0.0135930181 0.8223930000 954202537 0 1783754752 -0.1327976137 0.4898670316 0.9700974822 758 30.2800000000 0.0202817619 0.0293824681 0.0419089235 0.0135879890 0.8219750000 954203811 0 1782763520 -0.1335666776 0.4911808670 0.9711768627 759 30.3200000000 0.0200876128 0.0293702219 0.0419089235 0.0135840567 0.8290840000 954205085 0 1784414208 -0.1340012848 0.4903432131 0.9723235965 760 30.3600000000 0.0202324744 0.0293581986 0.0419089235 0.0135833056 0.8230750000 954206359 0 1783398400 -0.1335953474 0.4880238473 0.9735251665 761 30.4000000000 0.0201568678 0.0293461075 0.0419089235 0.0135780214 0.8562830000 954207633 0 1782284288 -0.1330892444 0.4877993762 0.9750668406 762 30.4400000000 0.0200049076 0.0293338487 0.0419089235 0.0135693364 0.8230460000 954208907 0 1783873536 -0.1323237568 0.4873284101 0.9764781594 763 30.4800000000 0.0200925600 0.0293217369 0.0419089235 0.0135606194 0.8237460000 954210181 0 1782730752 -0.1312426031 0.4848370552 0.9781423807 764 30.5200000000 0.0198764857 0.0293093740 0.0419089235 0.0135554629 0.8624990000 954211455 0 1784397824 -0.1222597435 0.4830328524 0.9800544977 765 30.5600000000 0.0197349302 0.0292968584 0.0419089235 0.0135497750 0.8243370000 954212729 0 1783398400 -0.1240317672 0.4816169739 0.9816797376 766 30.6000000000 0.0198918786 0.0292845804 0.0419089235 0.0135476050 0.8271550000 954214003 0 1782284288 -0.1239015236 0.4800454974 0.9831597209 767 30.6400000000 0.0199959967 0.0292724701 0.0419089235 0.0135525629 0.8657090000 954215277 0 1783762944 -0.1220914945 0.4771200418 0.9848872423 768 30.6800000000 0.0196724627 0.0292599701 0.0419089235 0.0135607430 0.8686950000 954216551 0 1782636544 -0.1118950620 0.4761980176 0.9872072339 769 30.7200000000 0.0195988808 0.0292474069 0.0419089235 0.0136149911 0.8637030000 954217825 0 1784127488 -0.1052033305 0.4740339816 0.9909649491 770 30.7600000000 0.0194658041 0.0292347035 0.0419089235 0.0136499467 0.8318400000 954219099 0 1782984704 -0.1065332964 0.4695352912 0.9920436144 771 30.8000000000 0.0195188466 0.0292221019 0.0419089235 0.0136696972 0.8621850000 954220373 0 1784524800 -0.0975032970 0.4670574367 0.9939137101 772 30.8400000000 0.0193595439 0.0292093265 0.0419089235 0.0136952121 0.8260530000 954221647 0 1783271424 -0.0996983647 0.4660402834 0.9944114089 773 30.8800000000 0.0195366293 0.0291968133 0.0419089235 0.0137217963 0.8645370000 954222921 0 1782136832 -0.0989185497 0.4631808996 0.9957379103 774 30.9200000000 0.0194012746 0.0291841576 0.0419089235 0.0137418407 0.8640300000 954224195 0 1783635968 -0.0878344178 0.4589490891 0.9978190064 775 30.9600000000 0.0191182289 0.0291711693 0.0419089235 0.0137657477 0.8232970000 954225469 0 1782509568 -0.0893836245 0.4572337568 0.9982529879 776 31.0000000000 0.0192656908 0.0291584045 0.0419089235 0.0137866435 0.8686590000 954226743 0 1784000512 -0.0806064010 0.4543002844 1.0005539656 777 31.0400000000 0.0189070590 0.0291452110 0.0419089235 0.0138024586 0.8221980000 954228017 0 1782857728 -0.0819610357 0.4526244104 1.0014654398 778 31.0800000000 0.0191593543 0.0291323757 0.0419089235 0.0138079240 0.8609990000 954229291 0 1784397824 -0.0743065774 0.4487517476 1.0037728548 779 31.1200000000 0.0187229998 0.0291190133 0.0419089235 0.0138105254 0.8635520000 954230565 0 1783144448 -0.0758092925 0.4458247423 1.0051069260 780 31.1600000000 0.0191538502 0.0291062374 0.0419089235 0.0138079720 0.8163520000 954231839 0 1782026240 -0.0755411237 0.4430174828 1.0065919161 781 31.2000000000 0.0190846734 0.0290934057 0.0419089235 0.0138071156 0.8548040000 954233113 0 1783508992 -0.0663017556 0.4388174117 1.0095510483 782 31.2400000000 0.0186232924 0.0290800168 0.0419089235 0.0138068887 0.8221340000 954234387 0 1782349824 -0.0681101531 0.4352885485 1.0109682083 783 31.2800000000 0.0189686157 0.0290671031 0.0419089235 0.0138036313 0.8528520000 954235661 0 1783873536 -0.0607488193 0.4308143556 1.0139911175 784 31.3200000000 0.0184615888 0.0290535757 0.0419089235 0.0138013629 0.8134990000 954236935 0 1782730752 -0.0626207218 0.4262948334 1.0151052475 785 31.3600000000 0.0187046975 0.0290403924 0.0419089235 0.0137965587 0.8099630000 954238209 0 1784270848 -0.0625142902 0.4218596518 1.0165101290 786 31.4000000000 0.0188955702 0.0290274855 0.0419089235 0.0137897837 0.8103430000 954239483 0 1783123968 -0.0615341067 0.4182814062 1.0178328753 787 31.4400000000 0.0188408382 0.0290145419 0.0419089235 0.0137863992 0.8474750000 954240757 0 1782136832 -0.0535569936 0.4115999043 1.0208332539 788 31.4800000000 0.0183149911 0.0290009638 0.0419089235 0.0137856395 0.8128840000 954242031 0 1783767040 -0.0551194474 0.4072146714 1.0219835043 789 31.5200000000 0.0185566787 0.0289877264 0.0419089235 0.0137851334 0.8153580000 954243305 0 1782755328 -0.0552896634 0.4025608003 1.0232812166 790 31.5600000000 0.0187424589 0.0289747577 0.0419089235 0.0137848625 0.8405420000 954244579 0 1784389632 -0.0487000532 0.3955098391 1.0263596773 791 31.6000000000 0.0183772575 0.0289613601 0.0419089235 0.0138171898 0.8030780000 954245853 0 1783386112 -0.0522945449 0.3872218430 1.0279992819 792 31.6400000000 0.0182599332 0.0289478482 0.0419089235 0.0138147124 0.8402120000 954247127 0 1782386688 -0.0521775633 0.3832218051 1.0298749208 793 31.6800000000 0.0185704939 0.0289347620 0.0419089235 0.0138120786 0.8382900000 954248401 0 1784025088 -0.0462011956 0.3761702776 1.0332634449 794 31.7200000000 0.0181415696 0.0289211686 0.0419089235 0.0138080505 0.8050790000 954249675 0 1783021568 -0.0481109470 0.3750870228 1.0342638493 795 31.7600000000 0.0184517670 0.0289079995 0.0419089235 0.0138034112 0.8376110000 954250949 0 1782104064 -0.0461998768 0.3734797537 1.0364534855 796 31.8000000000 0.0185690336 0.0288950108 0.0419089235 0.0138002647 0.8363820000 954252223 0 1783746560 -0.0458060578 0.3681015372 1.0387219191 797 31.8400000000 0.0185510162 0.0288820322 0.0419089235 0.0138009108 0.8363000000 954253497 0 1782779904 -0.0457485616 0.3623668849 1.0413528681 798 31.8800000000 0.0186156929 0.0288691671 0.0419089235 0.0138679563 0.8703490000 954254771 0 1784397824 -0.0444420129 0.3442419171 1.0478383303 799 31.9200000000 0.0180687886 0.0288556497 0.0419089235 0.0138850968 0.7975900000 954256045 0 1783541760 -0.0455891937 0.3363634348 1.0501992702 800 31.9600000000 0.0180461034 0.0288421378 0.0419089235 0.0138915762 0.8004860000 954257319 0 1782632448 -0.0464832336 0.3320702910 1.0524113178 801 32.0000000000 0.0178078860 0.0288283622 0.0419089235 0.0138863371 0.7949210000 954258593 0 1784143872 -0.0470639914 0.3283860385 1.0553725958 802 32.0400000000 0.0177862439 0.0288145940 0.0419089235 0.0138777706 0.7941190000 954259867 0 1782984704 -0.0479380265 0.3204585910 1.0580878258 803 32.0800000000 0.0177420229 0.0288008050 0.0419089235 0.0138692982 0.7918780000 954261141 0 1782136832 -0.0486778393 0.3111883104 1.0613037348 804 32.1199999990 0.0181768201 0.0287875911 0.0419089235 0.0138624741 0.8037920000 954262415 0 1783762944 -0.0490260720 0.2957693338 1.0687390566 805 32.1600000000 0.0178800449 0.0287740413 0.0419089235 0.0138548076 0.7810800000 954263689 0 1782738944 -0.0503412969 0.2919251323 1.0717571974 806 32.2000000000 0.0176600348 0.0287602522 0.0419089235 0.0138462115 0.7830830000 954264963 0 1784381440 -0.0523432493 0.2868954539 1.0750151873 807 32.2400000000 0.0178786442 0.0287467682 0.0419089235 0.0138383999 0.8041540000 954266237 0 1783365632 -0.0527824126 0.2783838511 1.0789710283 808 32.2800000000 0.0174389109 0.0287327733 0.0419089235 0.0138302338 0.7732840000 954267511 0 1782272000 -0.0554914363 0.2726952434 1.0823453665 809 32.3200000000 0.0178644806 0.0287193391 0.0419089235 0.0138227357 0.8118190000 954268785 0 1784037376 -0.0552485548 0.2586854398 1.0877376795 810 32.3600000000 0.0178138725 0.0287058755 0.0419089235 0.0138142223 0.7921890000 954270059 0 1783263232 -0.0563993268 0.2469940186 1.0920895338 811 32.4000000000 0.0176813826 0.0286922818 0.0419089235 0.0138065282 0.7689110000 954271333 0 1782366208 -0.0589743368 0.2436002791 1.0957417488 812 32.4399999990 0.0177182313 0.0286787670 0.0419089235 0.0138004302 0.7891930000 954272607 0 1784033280 -0.0605541915 0.2372073084 1.1002460718 813 32.4800000000 0.0176466051 0.0286651973 0.0419089235 0.0137930939 0.7851270000 954273881 0 1783263232 -0.0620066486 0.2277657092 1.1051851511 814 32.5200000000 0.0176156368 0.0286516229 0.0419089235 0.0137851123 0.7808700000 954275155 0 1782509568 -0.0630494878 0.2167078257 1.1103516817 815 32.5600000000 0.0175896902 0.0286380500 0.0419089235 0.0137776972 0.7776110000 954276429 0 1784291328 -0.0641308725 0.2069616914 1.1153817177 816 32.6000000000 0.0176392309 0.0286245710 0.0419089235 0.0137695738 0.7745270000 954277703 0 1783508992 -0.0652389675 0.1999189556 1.1206293106 817 32.6400000000 0.0176142529 0.0286110945 0.0419089235 0.0137633003 0.7763230000 954278977 0 1782767616 -0.0661458895 0.1870903522 1.1276432276 818 32.6800000000 0.0175684169 0.0285975949 0.0419089235 0.0137549221 0.7720430000 954280251 0 1784418304 -0.0669729486 0.1708209813 1.1345541477 819 32.7200000000 0.0173059348 0.0285838078 0.0419089235 0.0137473480 0.7908200000 954281525 0 1783541760 -0.0681000501 0.1609179378 1.1397359371 820 32.7599999990 0.0172937308 0.0285700394 0.0419089235 0.0137391263 0.7497860000 954282799 0 1782874112 -0.0701958090 0.1547251046 1.1439092159 821 32.7999999990 0.0174170751 0.0285564548 0.0419089235 0.0137309268 0.7696630000 954284073 0 1781985280 -0.0714244321 0.1459905654 1.1487275362 822 32.8400000000 0.0173459221 0.0285428167 0.0419089235 0.0137237277 0.7634130000 954285347 0 1783783424 -0.0715447888 0.1344070584 1.1542918682 823 32.8800000000 0.0173146054 0.0285291736 0.0419089235 0.0137173392 0.7672530000 954286621 0 1782751232 -0.0714428425 0.1225399375 1.1600431204 824 32.9200000000 0.0172516350 0.0285154873 0.0419089235 0.0137099301 0.7636930000 954287895 0 1784418304 -0.0711331069 0.1118105054 1.1657885313 825 32.9600000000 0.0172781423 0.0285018663 0.0419089235 0.0137019429 0.7688180000 954289169 0 1783635968 -0.0713609532 0.1022213325 1.1706233025 826 33.0000000000 0.0168824587 0.0284877992 0.0419089235 0.0136947124 0.7393470000 954290443 0 1782861824 -0.0728478581 0.0937166959 1.1750825644 827 33.0400000000 0.0170978326 0.0284740266 0.0419089235 0.0136880021 0.7576650000 954291717 0 1781907456 -0.0720403716 0.0836044922 1.1800365448 828 33.0800000000 0.0171680246 0.0284603720 0.0419089235 0.0136815312 0.7542290000 954292991 0 1783537664 -0.0718639717 0.0759361982 1.1838341951 829 33.1199999990 0.0171187408 0.0284466909 0.0419089235 0.0136783752 0.7536230000 954294265 0 1782484992 -0.0716930479 0.0651284158 1.1881742477 830 33.1600000000 0.0171833616 0.0284331206 0.0419089235 0.0136744046 0.7435030000 954295539 0 1784152064 -0.0711585730 0.0519630909 1.1933773756 831 33.2000000000 0.0172224529 0.0284196300 0.0419089235 0.0136678453 0.7478050000 954296813 0 1783398400 -0.0705436766 0.0404447466 1.1978187561 832 33.2400000000 0.0168142598 0.0284056813 0.0419089235 0.0136637929 0.7278670000 954298087 0 1782763520 -0.0711304396 0.0323534422 1.2006403208 833 33.2800000000 0.0170738231 0.0283920776 0.0419089235 0.0136590627 0.7592450000 954299361 0 1784406016 -0.0705884174 0.0222664308 1.2043620348 834 33.3200000000 0.0170718208 0.0283785042 0.0419089235 0.0136514741 0.7375080000 954300635 0 1783644160 -0.0702402964 0.0132756792 1.2073600292 835 33.3600000000 0.0171039328 0.0283650017 0.0419089235 0.0136437104 0.7394570000 954301909 0 1782792192 -0.0693497509 0.0060600322 1.2098200321 836 33.4000000000 0.0170856398 0.0283515096 0.0419089235 0.0136397938 0.7393080000 954303183 0 1781993472 -0.0678504556 -0.0022178276 1.2129598856 837 33.4399999990 0.0171954054 0.0283381809 0.0419089235 0.0136388511 0.7369380000 954304457 0 1783635968 -0.0666992366 -0.0130164437 1.2165082693 838 33.4800000000 0.0171771813 0.0283248623 0.0419089235 0.0136341012 0.7467460000 954305731 0 1782730752 -0.0656098649 -0.0229733884 1.2194451094 839 33.5200000000 0.0170416459 0.0283114139 0.0419089235 0.0136261791 0.7135710000 954307005 0 1784528896 -0.0652592331 -0.0313943811 1.2213708162 840 33.5600000000 0.0170122813 0.0282979626 0.0419089235 0.0136183109 0.7528810000 954308279 0 1783525376 -0.0650140345 -0.0378227495 1.2225557566 841 33.6000000000 0.0174692441 0.0282850866 0.0419089235 0.0136174834 0.7532800000 954309553 0 1782857728 -0.0620416030 -0.0504022315 1.2267163992 842 33.6400000000 0.0174128953 0.0282721742 0.0419089235 0.0136099583 0.7323480000 954310827 0 1782112256 -0.0605839826 -0.0634315982 1.2308169603 843 33.6800000000 0.0181964319 0.0282602220 0.0419089235 0.0136022385 0.7120530000 954312101 0 1783783424 -0.0583356321 -0.0696662739 1.2318693399 844 33.7200000000 0.0180204399 0.0282480895 0.0419089235 0.0135998028 0.7106380000 954313375 0 1783021568 -0.0576428622 -0.0765334517 1.2326732874 845 33.7599999990 0.0178893059 0.0282358306 0.0419089235 0.0136021040 0.7355650000 954314649 0 1782239232 -0.0578281470 -0.0872905254 1.2342897654 846 33.7999999990 0.0179629084 0.0282236877 0.0419089235 0.0135992390 0.7059080000 954315923 0 1784037376 -0.0571765266 -0.0927099288 1.2346915007 847 33.8400000000 0.0178461019 0.0282114355 0.0419089235 0.0135989220 0.7486200000 954317197 0 1783296000 -0.0570368022 -0.0977974236 1.2347087860 848 33.8800000000 0.0179596953 0.0281993462 0.0419089235 0.0135963001 0.7267250000 954318471 0 1782509568 -0.0555003174 -0.1093399599 1.2379868031 849 33.9200000000 0.0187813900 0.0281882532 0.0419089235 0.0135894423 0.7067770000 954319745 0 1784143872 -0.0539739244 -0.1168790385 1.2395347357 850 33.9600000000 0.0196084641 0.0281781593 0.0419089235 0.0135839871 0.7120820000 954321019 0 1783173120 -0.0537886061 -0.1210555956 1.2390071154 851 34.0000000000 0.0193201527 0.0281677504 0.0419089235 0.0135773320 0.7102880000 954322293 0 1782517760 -0.0550025515 -0.1278746128 1.2394238710 852 34.0400000000 0.0196104776 0.0281577066 0.0419089235 0.0135701959 0.7161330000 954323567 0 1784143872 -0.0554462560 -0.1326802075 1.2390887737 853 34.0800000000 0.0195063557 0.0281475644 0.0419089235 0.0135673481 0.7115160000 954324841 0 1783144448 -0.0559332110 -0.1369882822 1.2385900021 854 34.1199999990 0.0191642251 0.0281370452 0.0419089235 0.0135662194 0.7104270000 954326115 0 1782538240 -0.0566703565 -0.1442243755 1.2388687134 855 34.1600000000 0.0195426811 0.0281269934 0.0419089235 0.0135600504 0.7086540000 954327389 0 1784164352 -0.0564387478 -0.1498968303 1.2392814159 856 34.2000000000 0.0188395604 0.0281161435 0.0419089235 0.0135534262 0.7319090000 954328663 0 1783111680 -0.0573212765 -0.1512373537 1.2377246618 857 34.2400000000 0.0192535911 0.0281058022 0.0419089235 0.0135510722 0.7094430000 954329937 0 1781751808 -0.0567699373 -0.1541137993 1.2365248203 858 34.2800000000 0.0190596804 0.0280952589 0.0419089235 0.0135513158 0.7090370000 954331211 0 1783529472 -0.0559269227 -0.1571324021 1.2357832193 859 34.3200000000 0.0193680171 0.0280850991 0.0419089235 0.0135556999 0.7116790000 954332485 0 1782521856 -0.0549558438 -0.1592662781 1.2342678308 860 34.3600000000 0.0192400608 0.0280748142 0.0419089235 0.0135543735 0.7103370000 954333759 0 1784127488 -0.0536888316 -0.1613650173 1.2331137657 861 34.4000000000 0.0193926822 0.0280647304 0.0419089235 0.0135517197 0.7549050000 954335033 0 1783140352 -0.0512624271 -0.1625994593 1.2325763702 862 34.4400000000 0.0192659758 0.0280545231 0.0419089235 0.0135616823 0.7132730000 954336307 0 1782136832 -0.0493785553 -0.1654633135 1.2321380377 863 34.4800000000 0.0195434988 0.0280446609 0.0419089235 0.0135718295 0.7147200000 954337581 0 1783746560 -0.0478918701 -0.1695571542 1.2318623066 864 34.5200000000 0.0204144213 0.0280358296 0.0419089235 0.0135793439 0.7143720000 954338855 0 1782730752 -0.0469262525 -0.1699646711 1.2296931744 865 34.5600000000 0.0196818318 0.0280261718 0.0419089235 0.0135825636 0.7128430000 954340129 0 1784397824 -0.0463444069 -0.1705614924 1.2280998230 866 34.6000000000 0.0193003546 0.0280160958 0.0419089235 0.0135818304 0.7216560000 954341403 0 1783398400 -0.0454708450 -0.1743249744 1.2275627851 867 34.6400000000 0.0201230794 0.0280069920 0.0419089235 0.0135775174 0.7157380000 954342677 0 1782349824 -0.0438567065 -0.1767642200 1.2268086672 868 34.6800000000 0.0203002039 0.0279981132 0.0419089235 0.0135717063 0.7485010000 954343951 0 1783889920 -0.0425219983 -0.1777840704 1.2253099680 869 34.7200000000 0.0199382845 0.0279888384 0.0419089235 0.0135655335 0.7181920000 954345225 0 1782898688 -0.0420847461 -0.1800174862 1.2245028019 870 34.7600000000 0.0198213868 0.0279794505 0.0419089235 0.0135588817 0.7159330000 954346499 0 1784532992 -0.0415252596 -0.1826642901 1.2237484455 871 34.8000000000 0.0197448172 0.0279699963 0.0419089235 0.0135539106 0.7210150000 954347773 0 1783373824 -0.0414200574 -0.1861406118 1.2228838205 872 34.8400000000 0.0198592823 0.0279606950 0.0419089235 0.0135485118 0.7185660000 954349047 0 1782292480 -0.0417638905 -0.1903722882 1.2227764130 873 34.8800000000 0.0203405246 0.0279519663 0.0419089235 0.0135413725 0.7246620000 954350321 0 1783914496 -0.0413559936 -0.1935212761 1.2222985029 874 34.9200000000 0.0205011461 0.0279434413 0.0419089235 0.0135345506 0.7203600000 954351595 0 1782636544 -0.0409071594 -0.1954677850 1.2212246656 875 34.9600000000 0.0201663878 0.0279345533 0.0419089235 0.0135279138 0.7579710000 954352869 0 1784143872 -0.0412828103 -0.1982930005 1.2206127644 876 35.0000000000 0.0203034449 0.0279258420 0.0419089235 0.0135204206 0.7186950000 954354143 0 1783017472 -0.0408392921 -0.2012085021 1.2204526663 877 35.0400000000 0.0204088967 0.0279172707 0.0419089235 0.0135128115 0.7166880000 954355417 0 1781878784 -0.0407080911 -0.2034857273 1.2193443775 878 35.0800000000 0.0201402977 0.0279084131 0.0419089235 0.0135053941 0.7193120000 954356691 0 1783492608 -0.0408191755 -0.2068136930 1.2184978724 879 35.1200000000 0.0203813482 0.0278998499 0.0419089235 0.0134978317 0.7262310000 954357965 0 1782476800 -0.0406732112 -0.2102369666 1.2179545164 880 35.1600000000 0.0211410131 0.0278921694 0.0419089235 0.0134906325 0.7185930000 954359239 0 1784143872 -0.0401486605 -0.2155934274 1.2157484293 881 35.2000000000 0.0209038295 0.0278842372 0.0419089235 0.0134837137 0.7201200000 954360513 0 1783033856 -0.0404714011 -0.2166716456 1.2140365839 882 35.2400000000 0.0201573297 0.0278754765 0.0419089235 0.0134787538 0.7613460000 954361787 0 1781968896 -0.0411123075 -0.2186189592 1.2127447128 883 35.2800000000 0.0201934762 0.0278667766 0.0419089235 0.0134747710 0.7243110000 954363061 0 1783635968 -0.0416163653 -0.2213522643 1.2113474607 884 35.3200000000 0.0203761850 0.0278583031 0.0419089235 0.0134743458 0.7249880000 954364335 0 1782616064 -0.0424021818 -0.2236852944 1.2093962431 885 35.3600000000 0.0202776231 0.0278497373 0.0419089235 0.0134775711 0.7200760000 954365609 0 1784270848 -0.0438309088 -0.2257631421 1.2077020407 886 35.4000000000 0.0204361901 0.0278413699 0.0419089235 0.0134812243 0.7300480000 954366883 0 1783128064 -0.0456587523 -0.2277423739 1.2059285641 887 35.4400000000 0.0206680950 0.0278332828 0.0419089235 0.0134864180 0.7322630000 954368157 0 1782157312 -0.0473937280 -0.2289198339 1.2040306330 888 35.4800000000 0.0202077907 0.0278246955 0.0419089235 0.0134898729 0.7230210000 954369431 0 1783889920 -0.0493731648 -0.2305926234 1.2021424770 889 35.5200000000 0.0205094777 0.0278164669 0.0419089235 0.0134994272 0.7683170000 954370705 0 1783013376 -0.0505008884 -0.2323503196 1.2004629374 890 35.5600000000 0.0207377989 0.0278085134 0.0419089235 0.0135066019 0.7230790000 954371979 0 1781968896 -0.0519978292 -0.2329086363 1.1986519098 891 35.6000000000 0.0199774243 0.0277997243 0.0419089235 0.0135128785 0.7208500000 954373253 0 1783635968 -0.0539823212 -0.2351559103 1.1972849369 892 35.6400000000 0.0207408778 0.0277918108 0.0419089235 0.0135234278 0.7218430000 954374527 0 1782632448 -0.0554193035 -0.2371115685 1.1953724623 893 35.6800000000 0.0208423939 0.0277840287 0.0419089235 0.0135353374 0.7272150000 954375801 0 1784270848 -0.0574070886 -0.2377363145 1.1934754848 894 35.7200000000 0.0203225985 0.0277756825 0.0419089235 0.0135492325 0.7239440000 954377075 0 1783238656 -0.0595387816 -0.2394088209 1.1921454668 895 35.7600000000 0.0206239689 0.0277676918 0.0419089235 0.0135663166 0.7204760000 954378349 0 1782136832 -0.0615390018 -0.2419444323 1.1909103394 896 35.8000000000 0.0215798691 0.0277607858 0.0419089235 0.0135907554 0.7738230000 954379623 0 1783906304 -0.0632755533 -0.2429986149 1.1891503334 897 35.8400000000 0.0217866506 0.0277541256 0.0419089235 0.0136093483 0.7212860000 954380897 0 1782886400 -0.0648843572 -0.2427523583 1.1880372763 898 35.8800000000 0.0212985072 0.0277469367 0.0419089235 0.0136200287 0.7176470000 954382171 0 1781841920 -0.0664038882 -0.2429029644 1.1866874695 899 35.9200000000 0.0215019677 0.0277399902 0.0419089235 0.0136306745 0.7153970000 954383445 0 1783525376 -0.0674000159 -0.2432478070 1.1864248514 900 35.9600000000 0.0216479395 0.0277332212 0.0419089235 0.0136352851 0.7279940000 954384719 0 1782525952 -0.0684657395 -0.2438400984 1.1855442524 901 36.0000000000 0.0199308693 0.0277245616 0.0419089235 0.0136452210 0.7736560000 954385993 0 1784143872 -0.0597362518 -0.2431814820 1.1876412630 902 36.0400000000 0.0201450642 0.0277161586 0.0419089235 0.0136635509 0.7142140000 954387267 0 1783111680 -0.0643759742 -0.2442582250 1.1857533455 903 36.0800000000 0.0202910993 0.0277079359 0.0419089235 0.0136790553 0.7108020000 954388541 0 1782136832 -0.0681902394 -0.2446753383 1.1834824085 904 36.1200000000 0.0202011131 0.0276996319 0.0419089235 0.0137015696 0.7113000000 954389815 0 1783762944 -0.0708323866 -0.2453885972 1.1823188066 905 36.1600000000 0.0204783473 0.0276916526 0.0419089235 0.0137251811 0.7116730000 954391089 0 1782730752 -0.0724783018 -0.2460404187 1.1809905767 906 36.2000000000 0.0204975531 0.0276837121 0.0419089235 0.0137511904 0.7119220000 954392363 0 1784270848 -0.0741934702 -0.2458841056 1.1799086332 907 36.2400000000 0.0200128574 0.0276752547 0.0419089235 0.0137741408 0.7095380000 954393637 0 1783271424 -0.0755256042 -0.2466972470 1.1793366671 908 36.2800000000 0.0204234384 0.0276672681 0.0419089235 0.0137894477 0.7061140000 954394911 0 1782136832 -0.0765839592 -0.2470323592 1.1787225008 909 36.3200000000 0.0202080719 0.0276590622 0.0419089235 0.0137990426 0.7033850000 954396185 0 1783746560 -0.0779937804 -0.2470975220 1.1780321598 910 36.3600000000 0.0199637320 0.0276506058 0.0419089235 0.0138064222 0.7427810000 954397459 0 1782616064 -0.0793940574 -0.2474377453 1.1775021553 911 36.4000000000 0.0197496153 0.0276419329 0.0419089235 0.0138139720 0.7032250000 954398733 0 1784287232 -0.0805859491 -0.2483010739 1.1771531105 912 36.4400000000 0.0198749322 0.0276334164 0.0419089235 0.0138194561 0.7016180000 954400007 0 1783238656 -0.0819636732 -0.2498882115 1.1770342588 913 36.4800000000 0.0198947992 0.0276249404 0.0419089235 0.0138702665 0.7651200000 954401281 0 1781858304 -0.0784495175 -0.2497837245 1.1787685156 914 36.5200000000 0.0193889774 0.0276159295 0.0419089235 0.0138999724 0.6990430000 954402555 0 1783525376 -0.0821544677 -0.2502384484 1.1773966551 915 36.5600000000 0.0194265638 0.0276069794 0.0419089235 0.0139210316 0.6985550000 954403829 0 1782636544 -0.0849483684 -0.2506223023 1.1767400503 916 36.6000000000 0.0194575116 0.0275980826 0.0419089235 0.0139405712 0.6972050000 954405103 0 1784262656 -0.0875067115 -0.2507824302 1.1759201288 917 36.6400000000 0.0194321480 0.0275891775 0.0419089235 0.0139544468 0.7402420000 954406377 0 1783279616 -0.0899404809 -0.2511232197 1.1752851009 918 36.6800000000 0.0193953160 0.0275802518 0.0419089235 0.0139691403 0.6911800000 954407651 0 1782145024 -0.0920433328 -0.2515802681 1.1748157740 919 36.7200000000 0.0193927661 0.0275713426 0.0419089235 0.0139870954 0.6919470000 954408925 0 1783660544 -0.0937877074 -0.2521085441 1.1746103764 920 36.7600000000 0.0195026807 0.0275625723 0.0419089235 0.0140046729 0.6996780000 954410199 0 1782484992 -0.0953350738 -0.2520340681 1.1741394997 921 36.8000000000 0.0190716125 0.0275533531 0.0419089235 0.0140164723 0.6887140000 954411473 0 1784152064 -0.0973697454 -0.2521412671 1.1740761995 922 36.8400000000 0.0191621669 0.0275442520 0.0419089235 0.0140252390 0.6909920000 954412747 0 1783144448 -0.0994569808 -0.2529795468 1.1742389202 923 36.8800000000 0.0195572004 0.0275355986 0.0419089235 0.0140312453 0.6881120000 954414021 0 1781739520 -0.1014442742 -0.2538715601 1.1746882200 924 36.9200000000 0.0198874939 0.0275273215 0.0419089235 0.0140340680 0.6857200000 954415295 0 1783529472 -0.1032953262 -0.2548263371 1.1746795177 925 36.9600000000 0.0201009177 0.0275192929 0.0419089235 0.0140374385 0.7217400000 954416569 0 1782747136 -0.1049491912 -0.2551834285 1.1747415066 926 37.0000000000 0.0198168792 0.0275109750 0.0419089235 0.0140419665 0.6784250000 954417843 0 1784508416 -0.1063175946 -0.2550406158 1.1747653484 927 37.0400000000 0.0194140952 0.0275022405 0.0419089235 0.0140491477 0.6836290000 954419117 0 1783685120 -0.1075582653 -0.2553147376 1.1751923561 928 37.0800000000 0.0197155662 0.0274938497 0.0419089235 0.0140597188 0.6756710000 954420391 0 1782767616 -0.1088977531 -0.2552989423 1.1753492355 929 37.1200000000 0.0194820762 0.0274852256 0.0419089235 0.0140723952 0.6725480000 954421665 0 1784508416 -0.1106467471 -0.2542584538 1.1746734381 930 37.1600000000 0.0189575478 0.0274760560 0.0419089235 0.0140828946 0.6752530000 954422939 0 1783762944 -0.1126221269 -0.2531914413 1.1739696264 931 37.2000000000 0.0202611741 0.0274683064 0.0419089235 0.0140916071 0.7264370000 954424213 0 1783152640 -0.1076695919 -0.2540731132 1.1782226562 932 37.2400000000 0.0194300283 0.0274596817 0.0419089235 0.0141217638 0.6639170000 954425487 0 1782538240 -0.1121089607 -0.2542381585 1.1756181717 933 37.2800000000 0.0192140900 0.0274508439 0.0419089235 0.0141575221 0.6608740000 954426761 0 1784143872 -0.1154624149 -0.2536775172 1.1730946302 934 37.3200000000 0.0190500040 0.0274418495 0.0419089235 0.0141894413 0.6559520000 954428035 0 1783173120 -0.1185374111 -0.2522435188 1.1715041399 935 37.3600000000 0.0204974338 0.0274344223 0.0419089235 0.0141997075 0.6954170000 954429309 0 1782390784 -0.1150370613 -0.2521143258 1.1739435196 936 37.4000000000 0.0189815257 0.0274253914 0.0419089235 0.0142257855 0.6419070000 954430583 0 1784016896 -0.1199023500 -0.2512539327 1.1707949638 937 37.4400000000 0.0206026845 0.0274181100 0.0419089235 0.0142307272 0.6824850000 954431857 0 1783279616 -0.1180146188 -0.2504048049 1.1727486849 938 37.4800000000 0.0185279399 0.0274086322 0.0419089235 0.0142441370 0.6385580000 954433131 0 1782407168 -0.1229615062 -0.2491086423 1.1695692539 939 37.5200000000 0.0206704978 0.0274014563 0.0419089235 0.0142482295 0.6712350000 954434405 0 1784143872 -0.1205904409 -0.2502294481 1.1719692945 940 37.5600000000 0.0190789942 0.0273926026 0.0419089235 0.0142583529 0.6299610000 954435679 0 1783279616 -0.1250201315 -0.2494542152 1.1688945293 941 37.6000000000 0.0207516402 0.0273855453 0.0419089235 0.0142616349 0.7042970000 954436953 0 1782497280 -0.1232582629 -0.2495248169 1.1703268290 942 37.6400000000 0.0186883956 0.0273763127 0.0419089235 0.0142700820 0.6246570000 954438227 0 1784270848 -0.1279343665 -0.2482715100 1.1662377119 943 37.6800000000 0.0208295863 0.0273693702 0.0419089235 0.0142752234 0.6541250000 954439501 0 1783537664 -0.1256105155 -0.2497266829 1.1684572697 944 37.7200000000 0.0187393799 0.0273602283 0.0419089235 0.0142851790 0.6139670000 954440775 0 1782620160 -0.1297280192 -0.2489331365 1.1657855511 945 37.7600000000 0.0182462949 0.0273505839 0.0419089235 0.0142907738 0.6052950000 954442049 0 1784397824 -0.1323141456 -0.2484743595 1.1658887863 946 37.8000000000 0.0208916795 0.0273437563 0.0419089235 0.0142942039 0.6504600000 954443323 0 1783652352 -0.1293887645 -0.2501720488 1.1693580151 947 37.8400000000 0.0195301883 0.0273355054 0.0419089235 0.0143018330 0.6003460000 954444597 0 1783009280 -0.1330419630 -0.2494057417 1.1668643951 948 37.8800000000 0.0185929965 0.0273262834 0.0419089235 0.0143035047 0.5989100000 954445871 0 1782251520 -0.1357169449 -0.2488414049 1.1672438383 949 37.9200000000 0.0208142027 0.0273194213 0.0419089235 0.0143064996 0.6534530000 954447145 0 1783910400 -0.1334753186 -0.2439162433 1.1795331240 950 37.9600000000 0.0195046160 0.0273111952 0.0419089235 0.0143114642 0.5951890000 954448419 0 1782890496 -0.1375191808 -0.2399901450 1.1853933334 951 38.0000000000 0.0206328407 0.0273041728 0.0419089235 0.0143164436 0.6264600000 954449693 0 1782251520 -0.1365534961 -0.2375545949 1.1923501492 952 38.0400000000 0.0193446595 0.0272958119 0.0419089235 0.0143226630 0.5824960000 954450967 0 1784000512 -0.1398662925 -0.2364928424 1.1902967691 953 38.0800000000 0.0187263787 0.0272868199 0.0419089235 0.0143205181 0.5795170000 954452241 0 1783017472 -0.1421313435 -0.2359309494 1.1896591187 954 38.1200000000 0.0206529461 0.0272798661 0.0419089235 0.0143228037 0.6178200000 954453515 0 1782243328 -0.1397551149 -0.2360515743 1.1942678690 955 38.1600000000 0.0197492037 0.0272719806 0.0419089235 0.0143297729 0.5756790000 954454789 0 1783889920 -0.1425199509 -0.2362964749 1.1911705732 956 38.2000000000 0.0194617994 0.0272638110 0.0419089235 0.0143326127 0.5741880000 954456063 0 1783009280 -0.1444137394 -0.2355854213 1.1907110214 957 38.2400000000 0.0209109709 0.0272571727 0.0419089235 0.0143332174 0.6120740000 954457337 0 1782263808 -0.1430868804 -0.2350606024 1.1922683716 958 38.2800000000 0.0208133422 0.0272504464 0.0419089235 0.0143339583 0.5739150000 954458611 0 1783889920 -0.1458304971 -0.2358301282 1.1896227598 959 38.3200000000 0.0212521013 0.0272441916 0.0419089235 0.0143340177 0.5691570000 954459885 0 1783169024 -0.1476705372 -0.2360519469 1.1896232367 960 38.3600000000 0.0226966497 0.0272394545 0.0419089235 0.0143326704 0.6040520000 954461159 0 1782366208 -0.1465031952 -0.2350396216 1.1926734447 961 38.4000000000 0.0243818145 0.0272364809 0.0419089235 0.0143321289 0.5645340000 954462433 0 1784274944 -0.1492618024 -0.2353288233 1.1934899092 962 38.4400000000 0.0302937012 0.0272396589 0.0419089235 0.0143372901 0.6020010000 954463707 0 1783394304 -0.1488807797 -0.2353797555 1.2001307011 963 38.4800000000 0.0360143520 0.0272487707 0.0419089235 0.0143375867 0.5619910000 954464981 0 1782517760 -0.1517727524 -0.2361010015 1.2040761709 964 38.5200000000 0.0449010171 0.0272670822 0.0449010171 0.0143472601 0.5970850000 954466255 0 1784270848 -0.1515150070 -0.2353646755 1.2146902084 965 38.5600000000 0.0513908900 0.0272920810 0.0513908900 0.0143507896 0.5559560000 954467529 0 1783508992 -0.1546537280 -0.2344869375 1.2201403379 966 38.6000000000 0.0647440106 0.0273308511 0.0647440106 0.0143733250 0.5935890000 954468803 0 1782751232 -0.1539891511 -0.2345318794 1.2333054543 967 38.6400000000 0.0733733401 0.0273784648 0.0733733401 0.0143808731 0.6385990000 954470077 0 1782104064 -0.1554578245 -0.2329583168 1.2445076704 968 38.6800000000 0.0863733515 0.0274394100 0.0863733515 0.0143938011 0.5919190000 954471351 0 1783779328 -0.1568134576 -0.2340579480 1.2553941011 969 38.7200000000 0.0929125026 0.0275069776 0.0929125026 0.0144065108 0.5565660000 954472625 0 1782861824 -0.1599912196 -0.2323978990 1.2625740767 970 38.7600000000 0.1113797277 0.0275934444 0.1113797277 0.0144337428 0.5888740000 954473899 0 1781866496 -0.1595771164 -0.2329623103 1.2796796560 971 38.8000000000 0.1257581711 0.0276945409 0.1257581711 0.0144461069 0.5844300000 954475173 0 1783664640 -0.1610757560 -0.2334583700 1.2920241356 972 38.8400000000 0.1394514889 0.0278095172 0.1394514889 0.0144570194 0.5865710000 954476447 0 1782902784 -0.1626126468 -0.2324764729 1.3053485155 973 38.8800000000 0.1558702737 0.0279411315 0.1558702737 0.0144720302 0.5846330000 954477721 0 1782292480 -0.1638106555 -0.2322567701 1.3206627369 974 38.9200000000 0.1699003428 0.0280868802 0.1699003428 0.0144810915 0.5833810000 954478995 0 1783934976 -0.1651085913 -0.2311675251 1.3349329233 975 38.9600000000 0.1874034405 0.0282502818 0.1874034405 0.0144972749 0.5893110000 954480269 0 1782882304 -0.1664838344 -0.2299049497 1.3519592285 976 39.0000000000 0.2058479190 0.0284322466 0.2058479190 0.0145141962 0.5771810000 954481543 0 1784532992 -0.1678893268 -0.2302830219 1.3688206673 977 39.0400000000 0.2196598947 0.0286279760 0.2196598947 0.0145205585 0.5796990000 954482817 0 1783418880 -0.1690667123 -0.2291059792 1.3821493387 978 39.0800000000 0.2390370816 0.0288431183 0.2390370816 0.0145398089 0.5783870000 954484091 0 1782382592 -0.1702622622 -0.2285968661 1.3996183872 979 39.1200000000 0.2577021420 0.0290768864 0.2577021420 0.0145577976 0.5825800000 954485365 0 1784299520 -0.1713342220 -0.2292575538 1.4155106544 980 39.1600000000 0.2787315845 0.0293316361 0.2787315845 0.0145804982 0.6024870000 954486639 0 1783390208 -0.1726861000 -0.2282991409 1.4348382950 981 39.2000000000 0.2994635701 0.0296070000 0.2994635701 0.0145988979 0.5757290000 954487913 0 1782755328 -0.1738417596 -0.2279349267 1.4549895525 982 39.2400000000 0.3208747208 0.0299036066 0.3208747208 0.0146153838 0.5718560000 954489187 0 1784434688 -0.1751095653 -0.2272098064 1.4746785164 983 39.2800000000 0.3453815877 0.0302245405 0.3453815877 0.0146426218 0.5962290000 954490461 0 1783537664 -0.1762165874 -0.2261292636 1.4976882935 984 39.3200000000 0.3718433976 0.0305717141 0.3718433976 0.0146747042 0.5955130000 954491735 0 1782751232 -0.1773232967 -0.2252990454 1.5232428312 985 39.3600000000 0.4105543196 0.0309574832 0.4105543196 0.0147407602 0.6151310000 954493009 0 1784508416 -0.1785851270 -0.2244163752 1.5593348742 986 39.4000000000 0.4547173083 0.0313872599 0.4547173083 0.0148328807 0.5877340000 954494283 0 1783410688 -0.1796555221 -0.2233955860 1.6019071341 987 39.4400000000 0.4932486713 0.0318552046 0.4932486713 0.0148856263 0.6463970000 954495557 0 1782390784 -0.1811211109 -0.2226291150 1.6387665272 988 39.4800000000 0.5536399484 0.0323833268 0.5536399484 0.0150668051 0.6593470000 954496831 0 1784143872 -0.1816517860 -0.2227689922 1.6976876259 989 39.5200000000 0.6153824329 0.0329728103 0.6153824329 0.0151832534 0.6381770000 954498105 0 1783263232 -0.1839661598 -0.2208136618 1.7568361759 990 39.5600000000 0.6969664097 0.0336435109 0.6969664097 0.0153992504 0.6344760000 954499379 0 1782153216 -0.1863356382 -0.2181658298 1.8371874094 991 39.6000000000 0.7720308304 0.0343886040 0.7720308304 0.0155910382 0.6336530000 954500653 0 1784037376 -0.1886979789 -0.2161268294 1.9095575809 992 39.6400000000 0.8289450407 0.0351895682 0.8289450407 0.0157024920 0.6287960000 954501927 0 1783152640 -0.1905133575 -0.2143117934 1.9644290209 993 39.6800000000 0.8703582883 0.0360306243 0.8703582883 0.0157615916 0.6605480000 954503201 0 1782136832 -0.1917829067 -0.2135454565 2.0039532185 994 39.7200000000 0.9072053432 0.0369070576 0.9072053432 0.0158559405 0.5645490000 954504475 0 1783926784 -0.1915518194 -0.2154818177 2.0372745991 995 39.7600000000 0.9288337231 0.0378034663 0.9288337231 0.0158583231 0.6254140000 954505749 0 1782898688 -0.1926537603 -0.2138278037 2.0557668209 996 39.8000000000 0.9535165429 0.0387228570 0.9535165429 0.0158758831 0.6224440000 954507023 0 1784508416 -0.1947184205 -0.2102024257 2.0779836178 997 39.8400000000 0.9710841179 0.0396580237 0.9710841179 0.0159221988 0.5658440000 954508297 0 1783541760 -0.1943472326 -0.2108137757 2.0939986706 998 39.8800000000 0.9798301458 0.0406000800 0.9798301458 0.0159160843 0.5066370000 954509571 0 1782476800 -0.1963387132 -0.2069523931 2.1006295681 999 39.9200000000 0.9945633411 0.0415549981 0.9945633411 0.0159949522 0.5654990000 954510845 0 1784287232 -0.1958575100 -0.2076532543 2.1107292175 1000 39.9600000000 0.9982454181 0.0425116886 0.9982454181 0.0159886524 0.5124390000 954512119 0 1783156736 -0.1979137957 -0.2033156753 2.1125223637 1001 40.0000000000 1.0026061535 0.0434708239 1.0026061535 0.0159813137 0.5049770000 954513393 0 1782284288 -0.1997977495 -0.1993563622 2.1144366264 1002 40.0400000000 1.0085456371 0.0444339724 1.0085456371 0.0159754456 0.5452470000 954514667 0 1783889920 -0.2010286450 -0.1962552369 2.1181695461 1003 40.0800000000 1.0175634623 0.0454041912 1.0175634623 0.0160954261 0.5676890000 954515941 0 1782882304 -0.1977583170 -0.2025310546 2.1256194115 1004 40.1200000000 1.0210115910 0.0463759118 1.0210115910 0.0160882044 0.5061680000 954517215 0 1781878784 -0.1995005757 -0.1984564215 2.1256003380 1005 40.1600000000 1.0238244534 0.0473484974 1.0238244534 0.0160804663 0.5072630000 954518489 0 1783508992 -0.2009159625 -0.1945417821 2.1275722980 1006 40.2000000000 1.0290284157 0.0483243223 1.0290284157 0.0161705235 0.5682700000 954519763 0 1782484992 -0.1985641420 -0.2009096146 2.1302356720 1007 40.2400000000 1.0308295488 0.0492999978 1.0308295488 0.0161663967 0.5119550000 954521037 0 1784254464 -0.2005833685 -0.1955362409 2.1284954548 1008 40.2800000000 1.0328780413 0.0502757697 1.0328780413 0.0161596850 0.5130210000 954522311 0 1783410688 -0.2014628053 -0.1922542155 2.1282243729 1009 40.3200000000 1.0366917849 0.0512533872 1.0366917849 0.0162320332 0.5788020000 954523585 0 1782366208 -0.1989696920 -0.1993672103 2.1291816235 1010 40.3600000000 1.0385466814 0.0522309053 1.0385466814 0.0162286869 0.5150440000 954524859 0 1784160256 -0.2009669840 -0.1931269765 2.1274209023 1011 40.4000000000 1.0422904491 0.0532101927 1.0422904491 0.0162214488 0.5174240000 954526133 0 1783140352 -0.2018859833 -0.1887567490 2.1272873878 1012 40.4400000000 1.0466588736 0.0541918613 1.0466588736 0.0162151106 0.5211400000 954527407 0 1782026240 -0.2026685029 -0.1843391061 2.1286818981 1013 40.4800000000 1.0516477823 0.0551765167 1.0516477823 0.0163433999 0.5788300000 954528681 0 1783795712 -0.2003298700 -0.1931770891 2.1312532425 1014 40.5200000000 1.0516872406 0.0561592689 1.0516872406 0.0163363107 0.5292190000 954529955 0 1782779904 -0.2019470036 -0.1865548342 2.1289820671 1015 40.5600000000 1.0533584356 0.0571417311 1.0533584356 0.0163287225 0.5203750000 954531229 0 1784397824 -0.2030248791 -0.1803425103 2.1283476353 1016 40.6000000000 1.0547451973 0.0581236243 1.0547451973 0.0163215412 0.5222110000 954532503 0 1783492608 -0.2039657384 -0.1752868444 2.1279602051 1017 40.6400000000 1.0576676130 0.0591064601 1.0576676130 0.0163148043 0.5269990000 954533777 0 1782525952 -0.2047007382 -0.1707586348 2.1281263828 1018 40.6800000000 1.0607188940 0.0600903623 1.0607188940 0.0163093762 0.5326150000 954535051 0 1784127488 -0.2055387646 -0.1658271998 2.1290163994 1019 40.7200000000 1.0599801540 0.0610716084 1.0607188940 0.0164677470 0.5927880000 954536325 0 1783271424 -0.2045002878 -0.1764196306 2.1264967918 1020 40.7600000000 1.0568429232 0.0620478548 1.0607188940 0.0164597202 0.5328970000 954537599 0 1781985280 -0.2054432780 -0.1713219732 2.1218616962 1021 40.8000000000 1.0552501678 0.0630206289 1.0607188940 0.0164524641 0.5275180000 954538873 0 1783652352 -0.2061690092 -0.1670237780 2.1181092262 1022 40.8400000000 1.0541166067 0.0639903901 1.0607188940 0.0164453769 0.5674410000 954540147 0 1782616064 -0.2069797814 -0.1629180610 2.1157913208 1023 40.8800000000 1.0536415577 0.0649577910 1.0607188940 0.0164384758 0.5322240000 954541421 0 1784287232 -0.2078468651 -0.1583175063 2.1141510010 1024 40.9200000000 1.0539945364 0.0659236472 1.0607188940 0.0164352855 0.5342640000 954542695 0 1783140352 -0.2086395323 -0.1544544399 2.1128425598 1025 40.9600000000 1.0544523001 0.0668880654 1.0607188940 0.0164343657 0.5321980000 954543969 0 1782009856 -0.2093016207 -0.1500035673 2.1119606495 1026 41.0000000000 1.0558708906 0.0678519863 1.0607188940 0.0164294832 0.5338110000 954713179 0 1783889920 -0.2102553993 -0.1431974024 2.1106817722 1027 41.0400000000 1.0576642752 0.0688157763 1.0607188940 0.0164269807 0.5384140000 954714453 0 1782874112 -0.2110822350 -0.1383489072 2.1103098392 1028 41.0800000000 1.0578995943 0.0697779201 1.0607188940 0.0164249751 0.5358540000 954715727 0 1784541184 -0.2116983831 -0.1333784163 2.1091580391 1029 41.1200000000 1.0589021444 0.0707391681 1.0607188940 0.0164204357 0.5378710000 954717001 0 1783365632 -0.2122872621 -0.1289689094 2.1080653667 1030 41.1600000000 1.0591479540 0.0716987883 1.0607188940 0.0164189256 0.5358380000 954718275 0 1782284288 -0.2127635628 -0.1275657117 2.1064002514 1031 41.2000000000 1.0602703094 0.0726576355 1.0607188940 0.0164168019 0.5334500000 954719549 0 1783881728 -0.2133697420 -0.1229252964 2.1052625179 1032 41.2400000000 1.0605306625 0.0736148768 1.0607188940 0.0164121365 0.5370680000 954720823 0 1782767616 -0.2136528641 -0.1201013848 2.1037108898 1033 41.2800000000 1.0595836639 0.0745693481 1.0607188940 0.0164069310 0.5376760000 954722097 0 1784422400 -0.2139581591 -0.1189408004 2.1014544964 1034 41.3200000000 1.0614931583 0.0755238198 1.0614931583 0.0164102501 0.5393390000 954723371 0 1783386112 -0.2147719860 -0.1117054224 2.1000366211 1035 41.3600000000 1.0603008270 0.0764752952 1.0614931583 0.0164059646 0.5389650000 954724645 0 1782292480 -0.2149056643 -0.1111534089 2.0978555679 1036 41.4000000000 1.0604413748 0.0774250694 1.0614931583 0.0164048298 0.5421360000 954725919 0 1783881728 -0.2155817747 -0.1079626009 2.0961873531 1037 41.4400000000 1.0607354641 0.0783732954 1.0614931583 0.0164042060 0.5475170000 954727193 0 1782906880 -0.2160117179 -0.1043840274 2.0953187943 1038 41.4800000000 1.0611346960 0.0793200791 1.0614931583 0.0164012661 0.5354500000 954728467 0 1784516608 -0.2165122032 -0.1017080992 2.0938503742 1039 41.5200000000 1.0615919828 0.0802654803 1.0615919828 0.0164002863 0.5377740000 954729741 0 1783549952 -0.2170804888 -0.0975516886 2.0927562714 1040 41.5600000000 1.0612328053 0.0812087181 1.0615919828 0.0163990373 0.5344620000 954731015 0 1782120448 -0.2174046338 -0.0937629640 2.0910263062 1041 41.6000000000 1.0609856844 0.0821499064 1.0615919828 0.0163966368 0.5334220000 954732289 0 1783767040 -0.2177779526 -0.0900471359 2.0897331238 1042 41.6400000000 1.0604268312 0.0830887518 1.0615919828 0.0163955561 0.5738920000 954733563 0 1782784000 -0.2180438489 -0.0856667534 2.0878307819 1043 41.6800000000 1.0592325926 0.0840246519 1.0615919828 0.0163968200 0.5341040000 954734837 0 1784532992 -0.2181763202 -0.0824206844 2.0852267742 1044 41.7200000000 1.0592899323 0.0849588141 1.0615919828 0.0163950728 0.5337550000 954736111 0 1783414784 -0.2182932496 -0.0791303590 2.0844507217 1045 41.7600000000 1.0592463017 0.0858911466 1.0615919828 0.0163950795 0.5399440000 954737385 0 1782120448 -0.2185274363 -0.0774235502 2.0843236446 1046 41.8000000000 1.0595475435 0.0868219845 1.0615919828 0.0163940213 0.5341580000 954738659 0 1783762944 -0.2187001258 -0.0754415616 2.0836706161 1047 41.8400000000 1.0596938133 0.0877511839 1.0615919828 0.0163916529 0.5320030000 954739933 0 1782747136 -0.2188340276 -0.0755698085 2.0835075378 1048 41.8800000000 1.0594553947 0.0886783826 1.0615919828 0.0163868146 0.5299140000 954741207 0 1784287232 -0.2190585881 -0.0744269192 2.0822865963 1049 41.9200000000 1.0594527721 0.0896038110 1.0615919828 0.0163816733 0.5342920000 954742481 0 1783255040 -0.2193242162 -0.0711162388 2.0809705257 1050 41.9600000000 1.0578383207 0.0905259391 1.0615919828 0.0163766952 0.5307600000 954743755 0 1782136832 -0.2192823887 -0.0691067651 2.0783476830 1051 42.0000000000 1.0568391085 0.0914453617 1.0615919828 0.0163717631 0.5296040000 954745029 0 1783746560 -0.2191582918 -0.0680180565 2.0764937401 1052 42.0400000000 1.0565161705 0.0923627294 1.0615919828 0.0163668172 0.5320200000 954746303 0 1782779904 -0.2192895859 -0.0667196289 2.0757617950 1053 42.0800000000 1.0556658506 0.0932775472 1.0615919828 0.0163615780 0.5308240000 954747577 0 1784414208 -0.2194197923 -0.0648208335 2.0738432407 1054 42.1200000000 1.0550305843 0.0941900263 1.0615919828 0.0163578302 0.5302070000 954748851 0 1783398400 -0.2194700986 -0.0641191974 2.0726711750 1055 42.1600000000 1.0553295612 0.0951010591 1.0615919828 0.0163525450 0.5340370000 954750125 0 1782009856 -0.2198993564 -0.0615938827 2.0727357864 1056 42.2000000000 1.0545276403 0.0960096070 1.0615919828 0.0163514074 0.5272170000 954751399 0 1783635968 -0.2200351059 -0.0596387871 2.0718786716 1057 42.2400000000 1.0541465282 0.0969160752 1.0615919828 0.0163502511 0.5286360000 954752673 0 1782632448 -0.2201938331 -0.0591725782 2.0710926056 1058 42.2800000000 1.0539772511 0.0978206699 1.0615919828 0.0163447246 0.5251190000 954753947 0 1784254464 -0.2204717994 -0.0578051805 2.0712783337 1059 42.3200000000 1.0529639721 0.0987225994 1.0615919828 0.0163405207 0.5252410000 954755221 0 1782996992 -0.2207405567 -0.0581947379 2.0705902576 1060 42.3600000000 1.0529000759 0.0996227668 1.0615919828 0.0163363297 0.5255330000 954756495 0 1784508416 -0.2211379558 -0.0578939468 2.0707736015 1061 42.4000000000 1.0528272390 0.1005211687 1.0615919828 0.0163316028 0.5256810000 954757769 0 1783414784 -0.2214569449 -0.0571228117 2.0712122917 1062 42.4400000000 1.0453945398 0.1014108800 1.0615919828 0.0163283795 0.6108060000 954759043 0 1782222848 -0.2213446498 -0.0539404526 2.0662462711 1063 42.4800000000 1.0440415144 0.1022976445 1.0615919828 0.0163223898 0.5801250000 954760317 0 1783906304 -0.2211215496 -0.0543239526 2.0658791065 1064 42.5200000000 1.0457631350 0.1031843602 1.0615919828 0.0163193517 0.5260120000 954761591 0 1782779904 -0.2212028056 -0.0538808219 2.0685729980 1065 42.5600000000 1.0425688028 0.1040664113 1.0615919828 0.0163131733 0.5790800000 954762865 0 1784414208 -0.2208664864 -0.0528990477 2.0667033195 1066 42.6000000000 1.0437641144 0.1049479288 1.0615919828 0.0163087632 0.5213630000 954764139 0 1783377920 -0.2207825035 -0.0514425747 2.0686933994 1067 42.6400000000 1.0448813438 0.1058288411 1.0615919828 0.0163069779 0.5203480000 954765413 0 1782112256 -0.2206732333 -0.0509882905 2.0708215237 1068 42.6800000000 1.0397444963 0.1067032940 1.0615919828 0.0163005610 0.5750850000 954766687 0 1783762944 -0.2200403512 -0.0503470637 2.0667958260 1069 42.7200000000 1.0407162905 0.1075770199 1.0615919828 0.0162998285 0.5383060000 954767961 0 1782620160 -0.2196726650 -0.0498574004 2.0684294701 1070 42.7600000000 1.0413870811 0.1084497396 1.0615919828 0.0162990638 0.5144350000 954769235 0 1784287232 -0.2194098532 -0.0490690731 2.0695259571 1071 42.8000000000 1.0375076532 0.1093172073 1.0615919828 0.0162920631 0.6030470000 954770509 0 1783267328 -0.2192288041 -0.0487246253 2.0674617290 1072 42.8400000000 1.0361471176 0.1101817874 1.0615919828 0.0162877942 0.5733180000 954771783 0 1782136832 -0.2191938907 -0.0495391563 2.0677258968 1073 42.8800000000 1.0350375175 0.1110437219 1.0615919828 0.0162810619 0.5749100000 954773057 0 1783922688 -0.2190621495 -0.0488247871 2.0671422482 1074 42.9200000000 1.0340391397 0.1119031218 1.0615919828 0.0162749105 0.5722800000 954774331 0 1782857728 -0.2190825641 -0.0491048433 2.0666964054 1075 42.9600000000 1.0334857702 0.1127604080 1.0615919828 0.0162679104 0.5659500000 954775605 0 1781731328 -0.2189404815 -0.0482098758 2.0665802956 1076 43.0000000000 1.0327405930 0.1136154081 1.0615919828 0.0162613426 0.5656100000 954776879 0 1783365632 -0.2187231779 -0.0484285355 2.0677678585 1077 43.0400000000 1.0327984095 0.1144688742 1.0615919828 0.0162561126 0.5669380000 954778153 0 1782394880 -0.2185390294 -0.0487133861 2.0706331730 1078 43.0800000000 1.0311952829 0.1153192698 1.0615919828 0.0162498416 0.5641240000 954779427 0 1784012800 -0.2182462215 -0.0482833944 2.0712740421 1079 43.1200000000 1.0314321518 0.1161683086 1.0615919828 0.0162440319 0.5599750000 954780701 0 1783029760 -0.2180546075 -0.0471990518 2.0746624470 1080 43.1600000000 1.0300382376 0.1170144845 1.0615919828 0.0162372456 0.5961160000 954781975 0 1782026240 -0.2178758830 -0.0471756980 2.0754280090 1081 43.2000000000 1.0297230482 0.1178588032 1.0615919828 0.0162331881 0.5720640000 954783249 0 1783746560 -0.2177255005 -0.0480768047 2.0777988434 1082 43.2400000000 1.0308493376 0.1187026022 1.0615919828 0.0162302232 0.5154220000 954784523 0 1782902784 -0.2176575363 -0.0475201383 2.0810663700 1083 43.2800000000 1.0286504030 0.1195428126 1.0615919828 0.0162261398 0.5549660000 954785797 0 1782095872 -0.2174572945 -0.0480267406 2.0810804367 1084 43.3200000000 1.0283038616 0.1203811530 1.0615919828 0.0162197245 0.5549480000 954787071 0 1783672832 -0.2170711309 -0.0479208976 2.0822248459 1085 43.3600000000 1.0303314924 0.1212198169 1.0615919828 0.0162153053 0.4948940000 954788345 0 1782644736 -0.2166704088 -0.0484453849 2.0856065750 1086 43.4000000000 1.0320327282 0.1220585028 1.0615919828 0.0162111402 0.4928300000 954789619 0 1784270848 -0.2161922455 -0.0479237214 2.0887854099 1087 43.4400000000 1.0339245796 0.1228973861 1.0615919828 0.0162075349 0.4930010000 954790893 0 1783173120 -0.2157497406 -0.0483189113 2.0926930904 1088 43.4800000000 1.0353463888 0.1237360341 1.0615919828 0.0162016265 0.4918880000 954792167 0 1782390784 -0.2152911127 -0.0478198864 2.0955734253 1089 43.5200000000 1.0252162218 0.1245638396 1.0615919828 0.0162040097 0.5585440000 954793441 0 1784160256 -0.2153319269 -0.0458563529 2.0874948502 1090 43.5600000000 1.0283188820 0.1253929726 1.0615919828 0.0162040411 0.4990900000 954794715 0 1783246848 -0.2145174891 -0.0465011708 2.0921566486 1091 43.6000000000 1.0248667002 0.1262174215 1.0615919828 0.0162010607 0.5615310000 954795989 0 1782415360 -0.2141664028 -0.0448591821 2.0905895233 1092 43.6400000000 1.0244054794 0.1270399380 1.0615919828 0.0161965255 0.5583140000 954797263 0 1784147968 -0.2135262787 -0.0455988348 2.0926525593 1093 43.6800000000 1.0241335630 0.1278607007 1.0615919828 0.0161907786 0.5567300000 954798537 0 1783283712 -0.2128064930 -0.0450647324 2.0952842236 1094 43.7200000000 1.0239732265 0.1286798164 1.0615919828 0.0161851932 0.5649550000 954799811 0 1782501376 -0.2119983882 -0.0455043949 2.0974388123 1095 43.7600000000 1.0241920948 0.1294976358 1.0615919828 0.0161798753 0.5614560000 954801085 0 1784152064 -0.2113869041 -0.0454677306 2.1004374027 1096 43.8000000000 1.0279805660 0.1303174195 1.0615919828 0.0161808684 0.5045360000 954802359 0 1783627776 -0.2102862000 -0.0468391664 2.1069166660 1097 43.8400000000 1.0243568420 0.1311324053 1.0615919828 0.0161786640 0.5642780000 954803633 0 1782902784 -0.2100836486 -0.0453776270 2.1055588722 1098 43.8800000000 1.0265915394 0.1319479419 1.0615919828 0.0161730698 0.5252860000 954804907 0 1782149120 -0.2092182189 -0.0456131808 2.1100542545 1099 43.9200000000 1.0304430723 0.1327654989 1.0615919828 0.0161696238 0.5028030000 954806181 0 1783791616 -0.2081395835 -0.0455649719 2.1156361103 1100 43.9600000000 1.0253015757 0.1335768953 1.0615919828 0.0161674043 0.6045010000 954807455 0 1783013376 -0.2081188411 -0.0426086225 2.1128475666 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-19 01:52:25 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.5867540000 954995638 0 1771765760 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0002910965 0.0001455483 0.0002910965 0.0020534056 0.7305460000 953139727 0 1768873984 0.0002571754 0.0005311928 0.0001826408 3 0.0800000000 0.0004577617 0.0002496194 0.0004577617 0.0017290551 0.6892810000 952828269 0 1770745856 0.0003170961 -0.0020085967 -0.0006930974 4 0.1200000000 0.0004247506 0.0002934022 0.0004577617 0.0014803938 0.6981110000 952829871 0 1772429312 0.0004795926 -0.0013546797 -0.0006147256 5 0.1600000000 0.0006735011 0.0003694220 0.0006735011 0.0014680103 0.6859670000 952831145 0 1774206976 0.0005451371 -0.0009306478 -0.0004296732 6 0.2000000000 0.0006569872 0.0004173495 0.0006735011 0.0016120501 0.6906630000 952833075 0 1775824896 0.0006312328 -0.0019516861 -0.0007426095 7 0.2400000000 0.0007790207 0.0004690168 0.0007790207 0.0016031670 0.6909480000 952834349 0 1777508352 0.0006583823 -0.0021561997 -0.0008140900 8 0.2800000000 0.0007656234 0.0005060926 0.0007790207 0.0016106914 0.7033710000 952835623 0 1779269632 0.0005130592 -0.0009041536 -0.0003786774 9 0.3200000000 0.0007770904 0.0005362035 0.0007790207 0.0015152436 0.6920390000 952836897 0 1780903936 0.0007065011 -0.0008357103 -0.0003088087 10 0.3600000000 0.0007575410 0.0005583373 0.0007790207 0.0014549182 0.6929670000 952839483 0 1782587392 0.0007054310 -0.0015180771 -0.0004736727 11 0.4000000000 0.0007901298 0.0005794093 0.0007901298 0.0013900280 0.6959190000 952840757 0 1784356864 0.0006105092 -0.0008906043 -0.0003012363 12 0.4400000000 0.0008149085 0.0005990342 0.0008149085 0.0013422920 0.6908930000 952842031 0 1783230464 0.0006533127 -0.0000866373 -0.0000065762 13 0.4800000000 0.0007846489 0.0006133123 0.0008149085 0.0013139534 0.6938260000 952843305 0 1781784576 0.0005740318 0.0004037211 0.0003144571 14 0.5200000000 0.0007722099 0.0006246621 0.0008149085 0.0014175311 0.6942330000 952844579 0 1783324672 0.0007183104 0.0004871410 0.0004010132 15 0.5600000000 0.0008261008 0.0006380914 0.0008261008 0.0015055754 0.6873180000 952845853 0 1782206464 0.0007673725 0.0005713719 0.0004756446 16 0.6000000000 0.0008128357 0.0006490129 0.0008261008 0.0014899886 0.6893000000 952847127 0 1783943168 0.0010690122 0.0005240747 0.0004198054 17 0.6400000000 0.0008736217 0.0006622252 0.0008736217 0.0014548227 0.6897910000 952848401 0 1782923264 0.0010283582 0.0003618375 0.0004575096 18 0.6800000000 0.0008956101 0.0006751910 0.0008956101 0.0014295015 0.6898850000 952852299 0 1782050816 0.0010210092 -0.0002855734 0.0002169097 19 0.7200000000 0.0008395265 0.0006838402 0.0008956101 0.0015662047 0.6905490000 952853573 0 1783681024 0.0008901245 -0.0002150962 0.0001454976 20 0.7600000000 0.0008183112 0.0006905638 0.0008956101 0.0017824161 0.6893630000 952854847 0 1782833152 0.0006795703 -0.0004507552 0.0000470184 21 0.8000000000 0.0009582066 0.0007033087 0.0009582066 0.0019828855 0.6871880000 952856121 0 1784475648 0.0007440611 -0.0005470748 -0.0000900981 22 0.8400000000 0.0008392957 0.0007094899 0.0009582066 0.0020045726 0.7397450000 952857395 0 1783599104 0.0007198028 -0.0004003328 0.0000062159 23 0.8800000000 0.0009253955 0.0007188771 0.0009582066 0.0020142724 0.6907660000 952858669 0 1782665216 0.0004904012 -0.0005274808 -0.0000571083 24 0.9200000000 0.0009948771 0.0007303771 0.0009948771 0.0019796015 0.6977570000 952859943 0 1784590336 0.0005703214 -0.0003525105 -0.0000485434 25 0.9600000000 0.0009867561 0.0007406323 0.0009948771 0.0019404185 0.6908340000 952861217 0 1783566336 0.0002764327 -0.0003293427 -0.0000493976 26 1.0000000000 0.0009839804 0.0007499918 0.0009948771 0.0019031986 0.6941970000 952862491 0 1782665216 0.0004309739 -0.0000770344 -0.0000018292 27 1.0400000000 0.0009465216 0.0007572707 0.0009948771 0.0018735060 0.6914350000 952863765 0 1784590336 0.0001223435 -0.0000966704 -0.0000267894 28 1.0800000000 0.0009420904 0.0007638714 0.0009948771 0.0018678418 0.6933990000 952865039 0 1783693312 0.0000084327 -0.0002121412 0.0000079871 29 1.1200000000 0.0009401255 0.0007699491 0.0009948771 0.0018452803 0.6862970000 952866313 0 1782706176 -0.0003395606 0.0000324855 0.0001157036 30 1.1600000000 0.0009078729 0.0007745466 0.0009948771 0.0018346766 0.6891780000 952867587 0 1784315904 -0.0001613400 0.0004401623 0.0000887882 31 1.2000000000 0.0009566820 0.0007804219 0.0009948771 0.0018285691 0.6916830000 952868861 0 1783488512 -0.0003293889 0.0002387570 0.0000664852 32 1.2400000000 0.0009795740 0.0007866454 0.0009948771 0.0018057873 0.6904670000 952870135 0 1782558720 -0.0005382482 -0.0001778484 0.0000324311 33 1.2800000000 0.0009828813 0.0007925920 0.0009948771 0.0018224620 0.6920080000 952871409 0 1784315904 -0.0007755266 -0.0000377950 0.0001885096 34 1.3200000000 0.0009790084 0.0007980748 0.0009948771 0.0018262211 0.6956580000 952877931 0 1783214080 -0.0012333841 -0.0003531861 0.0002600283 35 1.3600000000 0.0009897830 0.0008035522 0.0009948771 0.0018177306 0.6878780000 952879205 0 1782542336 -0.0015796238 -0.0011494461 0.0000278524 36 1.4000000000 0.0010660785 0.0008108446 0.0010660785 0.0018012601 0.6926060000 952880479 0 1784188928 -0.0018431052 -0.0013316703 0.0000052475 37 1.4400000000 0.0009768525 0.0008153313 0.0010660785 0.0017774357 0.6918830000 952881753 0 1783361536 -0.0020520852 -0.0008965061 0.0002431303 38 1.4800000000 0.0010505946 0.0008215224 0.0010660785 0.0017534308 0.7327120000 952883027 0 1782452224 -0.0022161314 -0.0013389026 0.0002739447 39 1.5200000000 0.0010733070 0.0008279784 0.0010733070 0.0017447792 0.6901990000 952884301 0 1784115200 -0.0027711419 -0.0028810757 -0.0000496290 40 1.5600000000 0.0010202037 0.0008327841 0.0010733070 0.0018691239 0.6977100000 952885575 0 1783046144 -0.0030636440 -0.0025097439 0.0003489742 41 1.6000000000 0.0010391064 0.0008378163 0.0010733070 0.0020500901 0.6875100000 952886849 0 1781960704 -0.0034084022 -0.0012873362 0.0010612769 42 1.6400000000 0.0010792225 0.0008435641 0.0010792225 0.0021360610 0.6891880000 952888123 0 1783586816 -0.0039447513 -0.0015624301 0.0014198466 43 1.6800000000 0.0010622945 0.0008486508 0.0010792225 0.0021592253 0.6858630000 952889397 0 1782665216 -0.0041732430 -0.0016930491 0.0019549020 44 1.7200000000 0.0010698107 0.0008536772 0.0010792225 0.0021465768 0.6839470000 952890671 0 1784340480 -0.0046063135 -0.0013332389 0.0026026240 45 1.7600000000 0.0011005457 0.0008591632 0.0011005457 0.0021523889 0.6833060000 952891945 0 1783189504 -0.0048946952 -0.0017835848 0.0031571756 46 1.8000000000 0.0010598196 0.0008635253 0.0011005457 0.0022891880 0.6870410000 952893219 0 1782165504 -0.0052175894 -0.0029085344 0.0037042822 47 1.8400000000 0.0010726555 0.0008679748 0.0011005457 0.0024675093 0.6896770000 952894493 0 1783832576 -0.0052523674 -0.0033041018 0.0045957225 48 1.8800000000 0.0010713350 0.0008722115 0.0011005457 0.0026832596 0.6875470000 952895767 0 1782702080 -0.0055722627 -0.0033987684 0.0060324608 49 1.9200000000 0.0010969045 0.0008767971 0.0011005457 0.0030017017 0.6855160000 952897041 0 1784356864 -0.0055200211 -0.0047758669 0.0070743919 50 1.9600000000 0.0010697418 0.0008806560 0.0011005457 0.0033003476 0.6833480000 952898315 0 1783181312 -0.0055071851 -0.0053352024 0.0085819578 51 2.0000000000 0.0010672254 0.0008843142 0.0011005457 0.0034955778 0.6842830000 952899589 0 1781944320 -0.0054262183 -0.0051886863 0.0104799801 52 2.0400000000 0.0010805283 0.0008880875 0.0011005457 0.0036499870 0.6842890000 952900863 0 1783459840 -0.0048529482 -0.0053060525 0.0124021675 53 2.0800000000 0.0010931261 0.0008919562 0.0011005457 0.0037198821 0.6910530000 952902137 0 1782411264 -0.0044620656 -0.0065202764 0.0140537415 54 2.1200000000 0.0010602970 0.0008950736 0.0011005457 0.0037956444 0.6888590000 952903411 0 1784078336 -0.0035291654 -0.0072404747 0.0158395059 55 2.1600000000 0.0010503939 0.0008978976 0.0011005457 0.0038001176 0.6883840000 952904685 0 1782951936 -0.0031648364 -0.0070163244 0.0183322188 56 2.2000000000 0.0010622748 0.0009008329 0.0011005457 0.0037844571 0.6849120000 952905959 0 1784569856 -0.0026616666 -0.0067381677 0.0208449662 57 2.2400000000 0.0010401809 0.0009032776 0.0011005457 0.0038060637 0.6892230000 952907233 0 1783459840 -0.0015404086 -0.0068763411 0.0232610460 58 2.2800000000 0.0010681293 0.0009061199 0.0011005457 0.0038660567 0.6875370000 952908507 0 1782329344 -0.0008398240 -0.0058485549 0.0261067338 59 2.3200000000 0.0010620139 0.0009087622 0.0011005457 0.0039774380 0.6839500000 952909781 0 1783934976 0.0004153883 -0.0060813427 0.0287530124 60 2.3600000000 0.0010791230 0.0009116015 0.0011005457 0.0042842415 0.6912400000 952911055 0 1782681600 0.0013352688 -0.0073564267 0.0311640985 61 2.4000000000 0.0010642203 0.0009141035 0.0011005457 0.0045527313 0.6883610000 952912329 0 1784205312 0.0026139575 -0.0073974663 0.0340855606 62 2.4400000000 0.0010419417 0.0009161654 0.0011005457 0.0048141397 0.7484360000 952913603 0 1782951936 0.0038667745 -0.0074632522 0.0369982719 63 2.4800000000 0.0010696771 0.0009186021 0.0011005457 0.0050061863 0.6863320000 952914877 0 1784442880 0.0053121271 -0.0081092082 0.0397002026 64 2.5200000000 0.0010205670 0.0009201953 0.0011005457 0.0051433178 0.6873820000 952916151 0 1783205888 0.0068564587 -0.0077968887 0.0428434387 65 2.5600000000 0.0010552520 0.0009222731 0.0011005457 0.0054011142 0.6879910000 952917425 0 1781833728 0.0080816699 -0.0081396857 0.0456997342 66 2.6000000000 0.0010360043 0.0009239963 0.0011005457 0.0057554895 0.6918260000 952929195 0 1783427072 0.0098284101 -0.0091042267 0.0482503325 67 2.6400000000 0.0012049803 0.0009281901 0.0012049803 0.0060401530 0.7082430000 952930469 0 1782333440 0.0120437741 -0.0075085536 0.0516153909 68 2.6800000000 0.0010374218 0.0009297964 0.0012049803 0.0064606930 0.6812550000 952931743 0 1783951360 0.0122793550 -0.0074348892 0.0544129312 69 2.7200000000 0.0010209612 0.0009311176 0.0012049803 0.0066813178 0.6923740000 952933017 0 1782951936 0.0140605057 -0.0082642520 0.0570881367 70 2.7600000000 0.0010312891 0.0009325487 0.0012049803 0.0068093108 0.6763200000 952934291 0 1784569856 0.0155672254 -0.0089874193 0.0595704354 71 2.8000000000 0.0010148287 0.0009337075 0.0012049803 0.0068356049 0.6767350000 952935565 0 1783459840 0.0168145876 -0.0082857795 0.0625928640 72 2.8400000000 0.0009860249 0.0009344342 0.0012049803 0.0068266931 0.6703790000 952936839 0 1782218752 0.0182601754 -0.0085625229 0.0652743578 73 2.8800000000 0.0010225183 0.0009356408 0.0012049803 0.0068162325 0.6650730000 952938113 0 1783934976 0.0196061004 -0.0090491604 0.0677427500 74 2.9200000000 0.0010142917 0.0009367036 0.0012049803 0.0068314338 0.6671730000 952939387 0 1782947840 0.0211034697 -0.0082258815 0.0706287250 75 2.9600000000 0.0010098554 0.0009376790 0.0012049803 0.0069013031 0.6657930000 952940661 0 1784586240 0.0224415287 -0.0078724287 0.0733377039 76 3.0000000000 0.0010526363 0.0009391916 0.0012049803 0.0070772505 0.6746890000 952941935 0 1783427072 0.0239504278 -0.0090612685 0.0755383521 77 3.0400000000 0.0010772235 0.0009409842 0.0012049803 0.0072408655 0.6675670000 952943209 0 1782202368 0.0250704680 -0.0101910979 0.0776418746 78 3.0800000000 0.0010218294 0.0009420207 0.0012049803 0.0074731508 0.7038140000 952944483 0 1783824384 0.0265515111 -0.0095480401 0.0804634318 79 3.1200000000 0.0010211532 0.0009430224 0.0012049803 0.0076773746 0.6670480000 952945757 0 1782665216 0.0273517817 -0.0093103144 0.0831950977 80 3.1600000000 0.0010599653 0.0009444842 0.0012049803 0.0078213143 0.6704730000 952947031 0 1784328192 0.0284412913 -0.0103358412 0.0854341090 81 3.2000000000 0.0010229400 0.0009454528 0.0012049803 0.0079752301 0.6720550000 952948305 0 1783312384 0.0297365431 -0.0105981976 0.0879572704 82 3.2400000000 0.0010292146 0.0009464742 0.0012049803 0.0081525539 0.6747580000 952949579 0 1782030336 0.0302770399 -0.0108425710 0.0904753730 83 3.2800000000 0.0010361808 0.0009475550 0.0012049803 0.0083405879 0.6758050000 952950853 0 1783697408 0.0313621275 -0.0117395381 0.0928757787 84 3.3200000000 0.0010289238 0.0009485237 0.0012049803 0.0084485025 0.6814150000 952952127 0 1782587392 0.0321118273 -0.0119430907 0.0954185724 85 3.3600000000 0.0009755779 0.0009488420 0.0012049803 0.0085188708 0.6837740000 952953401 0 1784221696 0.0326502398 -0.0115748914 0.0981872380 86 3.4000000000 0.0009715435 0.0009491060 0.0012049803 0.0085820815 0.6844410000 952954675 0 1783205888 0.0334414802 -0.0117143514 0.1007667705 87 3.4400000000 0.0009469219 0.0009490809 0.0012049803 0.0086554505 0.6850350000 952955949 0 1781952512 0.0342690572 -0.0116598792 0.1036146209 88 3.4800000000 0.0009713293 0.0009493337 0.0012049803 0.0087433971 0.6861780000 952957223 0 1783595008 0.0350745954 -0.0119873099 0.1063810512 89 3.5200000000 0.0009444306 0.0009492786 0.0012049803 0.0088275108 0.6851440000 952958497 0 1782419456 0.0358544886 -0.0119591840 0.1092833579 90 3.5600000000 0.0009550656 0.0009493429 0.0012049803 0.0089455534 0.6849100000 952959771 0 1784082432 0.0363132469 -0.0119191520 0.1122474000 91 3.6000000000 0.0009445399 0.0009492901 0.0012049803 0.0090855368 0.6924790000 952961045 0 1783087104 0.0375233479 -0.0124860285 0.1152552217 92 3.6400000000 0.0009597630 0.0009494040 0.0012049803 0.0091760673 0.6895240000 952962319 0 1781784576 0.0380602628 -0.0127017349 0.1184263080 93 3.6800000000 0.0009530885 0.0009494436 0.0012049803 0.0091791468 0.6901400000 952963593 0 1783468032 0.0385130718 -0.0132180434 0.1213695183 94 3.7200000000 0.0008900168 0.0009488114 0.0012049803 0.0091579535 0.7326750000 952964867 0 1782341632 0.0392468385 -0.0130442437 0.1245462224 95 3.7600000000 0.0009129554 0.0009484339 0.0012049803 0.0091469864 0.6913060000 952966141 0 1783832576 0.0400862657 -0.0132214045 0.1276175678 96 3.8000000000 0.0008606901 0.0009475199 0.0012049803 0.0091675439 0.6949110000 952967415 0 1782673408 0.0409702212 -0.0131066944 0.1308618933 97 3.8400000000 0.0008213061 0.0009462188 0.0012049803 0.0092848605 0.6965180000 952968689 0 1784332288 0.0414943248 -0.0116820671 0.1344784945 98 3.8800000000 0.0008866239 0.0009456107 0.0012049803 0.0094098466 0.7027020000 952969963 0 1783205888 0.0421093181 -0.0117269335 0.1376438290 99 3.9200000000 0.0008632704 0.0009447789 0.0012049803 0.0095395635 0.7030100000 952971237 0 1782030336 0.0431259722 -0.0117241014 0.1408686936 100 3.9600000000 0.0008029655 0.0009433608 0.0012049803 0.0096524346 0.7007070000 952972511 0 1783697408 0.0433137305 -0.0101667121 0.1444668770 101 4.0000000000 0.0008536185 0.0009424723 0.0012049803 0.0097023588 0.6998170000 952973785 0 1782550528 0.0438450463 -0.0095374323 0.1478527486 102 4.0400000000 0.0008909728 0.0009419674 0.0012049803 0.0097157578 0.7040110000 952975059 0 1784188928 0.0445497483 -0.0098132929 0.1508178264 103 4.0800000000 0.0008114409 0.0009407001 0.0012049803 0.0097287315 0.7081940000 952976333 0 1782951936 0.0448321253 -0.0086717522 0.1541997790 104 4.1200000000 0.0008715957 0.0009400357 0.0012049803 0.0097356502 0.7126390000 952977607 0 1784475648 0.0456646308 -0.0085551534 0.1573371142 105 4.1600000000 0.0008550429 0.0009392262 0.0012049803 0.0097414267 0.7201620000 952978881 0 1783353344 0.0461303480 -0.0084483335 0.1600829214 106 4.2000000000 0.0008135660 0.0009380407 0.0012049803 0.0097312624 0.7168170000 952980155 0 1781903360 0.0462103263 -0.0077467533 0.1629075408 107 4.2400000000 0.0008868367 0.0009375622 0.0012049803 0.0097075019 0.7190000000 952981429 0 1783570432 0.0468397066 -0.0083248485 0.1653666794 108 4.2800000000 0.0008010919 0.0009362986 0.0012049803 0.0096958950 0.7182820000 952982703 0 1782456320 0.0469305329 -0.0074846321 0.1681134403 109 4.3200000000 0.0007945136 0.0009349978 0.0012049803 0.0096791539 0.7591480000 952983977 0 1784078336 0.0470968969 -0.0065999147 0.1707959026 110 4.3600000000 0.0008102717 0.0009338639 0.0012049803 0.0096428704 0.7340270000 952985251 0 1783173120 0.0474648885 -0.0062390533 0.1733499914 111 4.4000000000 0.0008040777 0.0009326947 0.0012049803 0.0096108534 0.7290680000 952986525 0 1782325248 0.0479401387 -0.0060175546 0.1758708805 112 4.4400000000 0.0007834827 0.0009313624 0.0012049803 0.0095795975 0.7354570000 952987799 0 1783988224 0.0483830795 -0.0058127791 0.1782709360 113 4.4800000000 0.0007821535 0.0009300420 0.0012049803 0.0095466005 0.7306410000 952989073 0 1782939648 0.0480295755 -0.0050915186 0.1806861609 114 4.5200000000 0.0008530045 0.0009293662 0.0012049803 0.0095151180 0.7469310000 952990347 0 1781903360 0.0483163744 -0.0051830201 0.1830923110 115 4.5600000000 0.0008564835 0.0009287325 0.0012049803 0.0094860058 0.7357010000 952991621 0 1783586816 0.0486363508 -0.0052401354 0.1854231954 116 4.6000000000 0.0008568672 0.0009281129 0.0012049803 0.0094654293 0.7734880000 952992895 0 1782542336 0.0484309644 -0.0045665866 0.1879845858 117 4.6400000000 0.0009378527 0.0009281962 0.0012049803 0.0094348676 0.7392010000 952994169 0 1784369152 0.0485989861 -0.0047736908 0.1903998852 118 4.6800000000 0.0009628113 0.0009284895 0.0012049803 0.0094077821 0.7582970000 952995443 0 1783173120 0.0485462435 -0.0045974148 0.1930421889 119 4.7200000000 0.0010758782 0.0009297281 0.0012049803 0.0093823203 0.7478660000 952996717 0 1782452224 0.0489098094 -0.0044104122 0.1959355325 120 4.7600000000 0.0011540987 0.0009315978 0.0012049803 0.0093577478 0.7477960000 952997991 0 1784221696 0.0489864610 -0.0046181385 0.1986726522 121 4.8000000000 0.0012534021 0.0009342574 0.0012534021 0.0093446246 0.7474100000 952999265 0 1783341056 0.0490804985 -0.0044296016 0.2016451061 122 4.8400000000 0.0013660761 0.0009377969 0.0013660761 0.0093510931 0.7498590000 953000539 0 1782411264 0.0490081832 -0.0043253046 0.2046703994 123 4.8800000000 0.0014733698 0.0009421511 0.0014733698 0.0093368508 0.7498780000 953001813 0 1784221696 0.0489787944 -0.0041460553 0.2077513635 124 4.9200000000 0.0015600802 0.0009471344 0.0015600802 0.0093144221 0.7522930000 953003087 0 1783197696 0.0489421561 -0.0038026818 0.2107780725 125 4.9600000000 0.0017469713 0.0009535331 0.0017469713 0.0092938000 0.7626120000 953004361 0 1782341632 0.0490807109 -0.0033982124 0.2139904648 126 5.0000000000 0.0018880267 0.0009609497 0.0018880267 0.0092813400 0.7534420000 953005635 0 1784061952 0.0492454022 -0.0033790555 0.2170802951 127 5.0400000000 0.0020235912 0.0009693170 0.0020235912 0.0092832494 0.7545840000 953006909 0 1783300096 0.0496120229 -0.0032537428 0.2202659547 128 5.0800000000 0.0021284737 0.0009783729 0.0021284737 0.0093005508 0.7587570000 953008183 0 1782468608 0.0499872379 -0.0027168698 0.2233975828 129 5.1200000000 0.0022730420 0.0009884091 0.0022730420 0.0092855979 0.7601360000 953009457 0 1784336384 0.0504233949 -0.0026160572 0.2264428437 130 5.1600000000 0.0023428015 0.0009988275 0.0023428015 0.0092739802 0.8005500000 953031723 0 1783435264 0.0509992167 -0.0032896115 0.2290732563 131 5.2000000000 0.0023940390 0.0010094780 0.0023940390 0.0092642148 0.7768120000 953032997 0 1782538240 0.0515084565 -0.0031264795 0.2317942083 132 5.2400000000 0.0024829649 0.0010206408 0.0024829649 0.0092435265 0.7735300000 953034271 0 1784336384 0.0517258607 -0.0026338345 0.2346577048 133 5.2800000000 0.0027041966 0.0010332991 0.0027041966 0.0092383471 0.7691350000 953035545 0 1783488512 0.0522805937 -0.0030443182 0.2371213734 134 5.3200000000 0.0028349152 0.0010467440 0.0028349152 0.0092653641 0.7731260000 953036819 0 1782689792 0.0527352132 -0.0024387627 0.2400345802 135 5.3600000000 0.0029433975 0.0010607933 0.0029433975 0.0092675434 0.7756120000 953038093 0 1784324096 0.0532052293 -0.0026399330 0.2423023283 136 5.4000000000 0.0031366593 0.0010760570 0.0031366593 0.0092749373 0.7807170000 953039367 0 1783435264 0.0537876673 -0.0033112301 0.2444495112 137 5.4400000000 0.0033060692 0.0010923344 0.0033060692 0.0092737228 0.7804720000 953040641 0 1782677504 0.0543919653 -0.0036054673 0.2467863858 138 5.4800000000 0.0033252637 0.0011085151 0.0033252637 0.0092549014 0.7882970000 953041915 0 1784471552 0.0548171848 -0.0035637417 0.2490533590 139 5.5200000000 0.0035004532 0.0011257233 0.0035004532 0.0092440541 0.7873500000 953043189 0 1783463936 0.0550662801 -0.0037072687 0.2511986494 140 5.5600000000 0.0037740520 0.0011446399 0.0037740520 0.0092364107 0.7897850000 953044463 0 1782546432 0.0551655963 -0.0040594540 0.2532837689 141 5.6000000000 0.0020987736 0.0011514068 0.0037740520 0.0092998609 0.8319980000 953045737 0 1784324096 0.0566002652 -0.0046950905 0.2588238120 142 5.6400000000 0.0032924435 0.0011664845 0.0037740520 0.0092963562 0.7959420000 953047011 0 1783222272 0.0554782525 -0.0051994785 0.2596766949 143 5.6800000000 0.0037860717 0.0011848033 0.0037860717 0.0092963891 0.8003560000 953048285 0 1782476800 0.0549675561 -0.0055972044 0.2611626387 144 5.7200000000 0.0039783078 0.0012042027 0.0039783078 0.0092921599 0.8466820000 953049559 0 1784201216 0.0543539822 -0.0056036040 0.2629387379 145 5.7600000000 0.0041227615 0.0012243307 0.0041227615 0.0092818002 0.8060530000 953050833 0 1783488512 0.0536438450 -0.0055864933 0.2646008432 146 5.8000000000 0.0043869149 0.0012459922 0.0043869149 0.0092818137 0.8098120000 953052107 0 1782538240 0.0528704338 -0.0053577945 0.2662892342 147 5.8400000000 0.0046283109 0.0012690012 0.0046283109 0.0092734323 0.8101040000 953053381 0 1784315904 0.0520665608 -0.0060699703 0.2676740885 148 5.8800000000 0.0046786475 0.0012920393 0.0046786475 0.0092555469 0.8140740000 953054655 0 1783488512 0.0511644557 -0.0068510836 0.2690010369 149 5.9200000000 0.0048492062 0.0013159129 0.0048492062 0.0092384054 0.8156990000 953055929 0 1782452224 0.0501192063 -0.0070593208 0.2705667913 150 5.9600000000 0.0051039062 0.0013411662 0.0051039062 0.0092217938 0.8223870000 953057203 0 1784074240 0.0490585156 -0.0073217796 0.2723287046 151 6.0000000000 0.0051803733 0.0013665914 0.0051803733 0.0092034214 0.8181640000 953058477 0 1783173120 0.0478888378 -0.0075458484 0.2740010917 152 6.0400000000 0.0053760516 0.0013929694 0.0053760516 0.0091882106 0.8198790000 953059751 0 1782411264 0.0466909930 -0.0077646030 0.2757154703 153 6.0800000000 0.0057219397 0.0014212634 0.0057219397 0.0091749079 0.8191020000 953061025 0 1784221696 0.0454275757 -0.0079700993 0.2776726186 154 6.1200000000 0.0058510872 0.0014500285 0.0058510872 0.0091594525 0.8260430000 953062299 0 1783087104 0.0441259667 -0.0083604287 0.2795415819 155 6.1600000000 0.0058693304 0.0014785401 0.0058693304 0.0091407826 0.8233540000 953063573 0 1782325248 0.0426966958 -0.0085887015 0.2815211117 156 6.2000000000 0.0066664619 0.0015117960 0.0066664619 0.0091468218 0.8274540000 953064847 0 1784094720 0.0394826308 -0.0094138179 0.2849594057 157 6.2400000000 0.0064785741 0.0015434315 0.0066664619 0.0091305428 0.8247000000 953066121 0 1783300096 0.0381784290 -0.0096498802 0.2873989046 158 6.2800000000 0.0065327226 0.0015750093 0.0066664619 0.0091139105 0.8268750000 953067395 0 1782411264 0.0366994143 -0.0100558633 0.2893712521 159 6.3200000000 0.0066144131 0.0016067037 0.0066664619 0.0091009788 0.8275360000 953068669 0 1784242176 0.0350333788 -0.0103044044 0.2912729383 160 6.3600000000 0.0067748763 0.0016390048 0.0067748763 0.0090853792 0.8298390000 953069943 0 1783087104 0.0334210843 -0.0102710966 0.2932426631 161 6.4000000000 0.0069051604 0.0016717138 0.0069051604 0.0090769446 0.8286720000 953071217 0 1782325248 0.0317083262 -0.0102913817 0.2950586677 162 6.4400000000 0.0069162780 0.0017040876 0.0069162780 0.0090850144 0.8416810000 953072491 0 1784094720 0.0299365390 -0.0105557442 0.2968576849 163 6.4800000000 0.0069835857 0.0017364772 0.0069835857 0.0090774085 0.8344010000 953073765 0 1783214080 0.0283703171 -0.0106932363 0.2984823883 164 6.5200000000 0.0072303195 0.0017699762 0.0072303195 0.0090630503 0.8735960000 953075039 0 1781903360 0.0267559774 -0.0106924847 0.3001578450 165 6.5600000000 0.0074214940 0.0018042279 0.0074214940 0.0090553555 0.8358720000 953076313 0 1783554048 0.0251109805 -0.0108822286 0.3019335866 166 6.6000000000 0.0074758474 0.0018383942 0.0074758474 0.0090407014 0.8392320000 953077587 0 1782562816 0.0236513987 -0.0110684913 0.3036482930 167 6.6400000000 0.0076351366 0.0018731053 0.0076351366 0.0090293912 0.8388520000 953078861 0 1784205312 0.0220986996 -0.0108520696 0.3056390584 168 6.6800000000 0.0076615890 0.0019075605 0.0076615890 0.0090143252 0.8476380000 953080135 0 1783197696 0.0206264332 -0.0112899700 0.3071235716 169 6.7200000000 0.0076413476 0.0019414883 0.0076615890 0.0090001417 0.8391920000 953081409 0 1782198272 0.0191788934 -0.0115727754 0.3085944653 170 6.7600000000 0.0078276498 0.0019761128 0.0078276498 0.0089851630 0.8728720000 953082683 0 1783861248 0.0179988537 -0.0117435316 0.3101305068 171 6.8000000000 0.0079844100 0.0020112490 0.0079844100 0.0089722502 0.8433530000 953083957 0 1782792192 0.0169237331 -0.0123772109 0.3114570081 172 6.8400000000 0.0079120621 0.0020455560 0.0079844100 0.0089560827 0.8442400000 953085231 0 1784442880 0.0157772694 -0.0130336769 0.3125790060 173 6.8800000000 0.0078826351 0.0020792964 0.0079844100 0.0089416916 0.8528720000 953086505 0 1783472128 0.0148318773 -0.0136470497 0.3135320544 174 6.9200000000 0.0080085164 0.0021133724 0.0080085164 0.0089505344 0.8488280000 953087779 0 1782198272 0.0139692221 -0.0141778206 0.3144343197 175 6.9600000000 0.0081529729 0.0021478844 0.0081529729 0.0089666117 0.8452090000 953089053 0 1783967744 0.0130693782 -0.0147347506 0.3153930604 176 7.0000000000 0.0080936933 0.0021816674 0.0081529729 0.0089760626 0.8744830000 953090327 0 1783050240 0.0122413114 -0.0152575700 0.3160548210 177 7.0400000000 0.0082497215 0.0022159502 0.0082497215 0.0090007775 0.8514180000 953091601 0 1784594432 0.0115949539 -0.0157995485 0.3167617321 178 7.0800000000 0.0083275018 0.0022502847 0.0083275018 0.0090067066 0.8462960000 953092875 0 1783435264 0.0109908385 -0.0163119957 0.3173899353 179 7.1200000000 0.0083947508 0.0022846114 0.0083947508 0.0090135746 0.8499200000 953094149 0 1782292480 0.0104879169 -0.0166743975 0.3180850446 180 7.1600000000 0.0084668454 0.0023189571 0.0084668454 0.0090401237 0.8419280000 953095423 0 1783959552 0.0100371717 -0.0171341673 0.3188509941 181 7.2000000000 0.0084046768 0.0023525799 0.0084668454 0.0090596163 0.8411600000 953096697 0 1782951936 0.0095143691 -0.0175381489 0.3193407655 182 7.2400000000 0.0084202150 0.0023859185 0.0084668454 0.0090778433 0.8792770000 953097971 0 1784606720 0.0090276608 -0.0177810527 0.3197817206 183 7.2800000000 0.0084459446 0.0024190334 0.0084668454 0.0091024780 0.8382050000 953099245 0 1783472128 0.0086123385 -0.0180261284 0.3199289739 184 7.3200000000 0.0080471402 0.0024496209 0.0084668454 0.0092517533 0.8540200000 953100519 0 1782165504 0.0079346402 -0.0181872938 0.3210086226 185 7.3600000000 0.0080160573 0.0024797098 0.0084668454 0.0092734492 0.8563090000 953101793 0 1783808000 0.0076431972 -0.0183959082 0.3212586939 186 7.4000000000 0.0083373124 0.0025112023 0.0084668454 0.0092698403 0.8306780000 953103067 0 1782792192 0.0070619322 -0.0188677460 0.3218006790 187 7.4400000000 0.0080307703 0.0025407187 0.0084668454 0.0092590441 0.8456350000 953104341 0 1784459264 0.0067653591 -0.0188440401 0.3234829605 188 7.4800000000 0.0082542049 0.0025711096 0.0084668454 0.0092450425 0.8428080000 953105615 0 1783455744 0.0065012309 -0.0192401987 0.3245013654 189 7.5200000000 0.0082220752 0.0026010089 0.0084668454 0.0092406446 0.8188450000 953106889 0 1782218752 0.0063225729 -0.0195245743 0.3258866966 190 7.5600000000 0.0082257735 0.0026306129 0.0084668454 0.0092522611 0.8126810000 953108163 0 1783967744 0.0063137501 -0.0193862095 0.3274060488 191 7.6000000000 0.0080862213 0.0026591763 0.0084668454 0.0092437072 0.8423540000 953109437 0 1782927360 0.0066165128 -0.0192777459 0.3290178180 192 7.6400000000 0.0080394484 0.0026871985 0.0084668454 0.0092322552 0.8353490000 953110711 0 1781903360 0.0067036073 -0.0195110943 0.3308449984 193 7.6800000000 0.0079505537 0.0027144698 0.0084668454 0.0092218629 0.8142540000 953111985 0 1783554048 0.0067018294 -0.0197934043 0.3324466646 194 7.7200000000 0.0079033850 0.0027412168 0.0084668454 0.0092097966 0.8581990000 953113259 0 1782566912 0.0068592345 -0.0198947433 0.3338505626 195 7.7600000000 0.0078857737 0.0027675991 0.0084668454 0.0091961470 0.8229740000 953114533 0 1784205312 0.0070795147 -0.0200614911 0.3350305855 196 7.8000000000 0.0078376681 0.0027934668 0.0084668454 0.0091826911 0.8271080000 953115807 0 1783054336 0.0072456570 -0.0203253366 0.3360693753 197 7.8400000000 0.0079071382 0.0028194245 0.0084668454 0.0091695478 0.8371490000 953117081 0 1782087680 0.0074663702 -0.0206820499 0.3368953168 198 7.8800000000 0.0078436704 0.0028447995 0.0084668454 0.0091557048 0.8353180000 953118355 0 1783808000 0.0076919715 -0.0208084024 0.3379847705 199 7.9200000000 0.0076882462 0.0028691385 0.0084668454 0.0091454987 0.8413330000 953119629 0 1782792192 0.0079627717 -0.0210243072 0.3386197686 200 7.9600000000 0.0077910880 0.0028937482 0.0084668454 0.0091398139 0.8768830000 953120903 0 1784475648 0.0081962021 -0.0213993415 0.3392899632 201 8.0000000000 0.0078311609 0.0029183124 0.0084668454 0.0091277670 0.8516660000 953122177 0 1783455744 0.0083361873 -0.0216184091 0.3400282562 202 8.0400000000 0.0077977129 0.0029424679 0.0084668454 0.0091186610 0.8541150000 953123451 0 1782329344 0.0086062979 -0.0217361022 0.3404709995 203 8.0800000000 0.0076470561 0.0029656432 0.0084668454 0.0091129294 0.8613370000 953124725 0 1783967744 0.0087133348 -0.0217652842 0.3410134912 204 8.1200000000 0.0077645485 0.0029891673 0.0084668454 0.0091113083 0.8623310000 953125999 0 1782968320 0.0088352859 -0.0217491034 0.3414354920 205 8.1600000000 0.0077958130 0.0030126143 0.0084668454 0.0091125418 0.8667700000 953127273 0 1784569856 0.0089110741 -0.0217194725 0.3419586122 206 8.1999999990 0.0078583099 0.0030361371 0.0084668454 0.0091137951 0.9109020000 953128547 0 1783427072 0.0089243045 -0.0215501860 0.3420099020 207 8.2400000000 0.0078290608 0.0030592913 0.0084668454 0.0091434013 0.8737380000 953129821 0 1782157312 0.0090058558 -0.0214518644 0.3424012363 208 8.2799999990 0.0076953555 0.0030815801 0.0084668454 0.0091788272 0.8772220000 953131095 0 1783808000 0.0089967567 -0.0214248504 0.3426944911 209 8.3200000000 0.0077294474 0.0031038187 0.0084668454 0.0092061342 0.8737420000 953132369 0 1782824960 0.0089727696 -0.0215989780 0.3426078856 210 8.3599999990 0.0077682775 0.0031260304 0.0084668454 0.0092041562 0.8726030000 953133643 0 1784459264 0.0088635562 -0.0215653181 0.3427237272 211 8.4000000000 0.0077648843 0.0031480155 0.0084668454 0.0091956014 0.8696830000 953134917 0 1783332864 0.0088520618 -0.0214251205 0.3426031470 212 8.4399999990 0.0077153044 0.0031695593 0.0084668454 0.0091934439 0.8995730000 953136191 0 1782071296 0.0088435551 -0.0212789290 0.3421330750 213 8.4800000000 0.0077526714 0.0031910763 0.0084668454 0.0092037760 0.8637990000 953137465 0 1783693312 0.0088643758 -0.0213043895 0.3417896926 214 8.5200000000 0.0077231759 0.0032122543 0.0084668454 0.0092007040 0.8684410000 953138739 0 1782538240 0.0088843498 -0.0212634970 0.3413060308 215 8.5600000000 0.0077681537 0.0032334445 0.0084668454 0.0091917383 0.8610340000 953140013 0 1784061952 0.0088036275 -0.0209730137 0.3408113420 216 8.6000000000 0.0077694585 0.0032544446 0.0084668454 0.0091968151 0.8599680000 953141287 0 1782792192 0.0087228809 -0.0207286514 0.3402846754 217 8.6400000000 0.0077462820 0.0032751443 0.0084668454 0.0092066644 0.8592090000 953142561 0 1784336384 0.0085704764 -0.0204675905 0.3398560584 218 8.6800000000 0.0077521717 0.0032956811 0.0084668454 0.0092216699 0.9016780000 953143835 0 1783197696 0.0084608914 -0.0201889351 0.3393264115 219 8.7200000000 0.0077165063 0.0033158675 0.0084668454 0.0092352333 0.8573660000 953145109 0 1781841920 0.0083430698 -0.0198396556 0.3389608264 220 8.7600000000 0.0077101863 0.0033358417 0.0084668454 0.0092454615 0.8586760000 953146383 0 1783341056 0.0082277954 -0.0194665324 0.3383956850 221 8.8000000000 0.0077359476 0.0033557517 0.0084668454 0.0092601432 0.8569470000 953147657 0 1782083584 0.0081416918 -0.0192547999 0.3379755020 222 8.8400000000 0.0076695816 0.0033751834 0.0084668454 0.0092648990 0.8484130000 953148931 0 1783562240 0.0079698116 -0.0189110059 0.3374938369 223 8.8800000000 0.0077634272 0.0033948616 0.0084668454 0.0092758936 0.8462230000 953150205 0 1782292480 0.0076806098 -0.0185572002 0.3366475105 224 8.9200000000 0.0077531058 0.0034143180 0.0084668454 0.0093032453 0.8465510000 953151479 0 1783808000 0.0074016419 -0.0185219608 0.3360050023 225 8.9600000000 0.0076863966 0.0034333051 0.0084668454 0.0093237609 0.8435100000 953152753 0 1782571008 0.0070594838 -0.0181792285 0.3352566659 226 9.0000000000 0.0076289405 0.0034518698 0.0084668454 0.0093536470 0.8513550000 953154027 0 1784205312 0.0067420839 -0.0179071184 0.3345336020 227 9.0400000000 0.0076282537 0.0034702680 0.0084668454 0.0093721258 0.8454040000 953155301 0 1782935552 0.0063412585 -0.0175775681 0.3337391317 228 9.0800000000 0.0076605687 0.0034886465 0.0084668454 0.0094010524 0.8442350000 953156575 0 1784459264 0.0059869690 -0.0173289105 0.3329020441 229 9.1200000000 0.0076107751 0.0035066470 0.0084668454 0.0094318718 0.8491930000 953157849 0 1783173120 0.0055939844 -0.0173263419 0.3319969177 230 9.1600000000 0.0076704281 0.0035247504 0.0084668454 0.0094417717 0.8780580000 953159123 0 1781776384 0.0051582525 -0.0171048250 0.3309011161 231 9.2000000000 0.0076566078 0.0035426373 0.0084668454 0.0094586027 0.8444600000 953160397 0 1783300096 0.0046153632 -0.0167807564 0.3298938870 232 9.2400000000 0.0077068326 0.0035605864 0.0084668454 0.0094792911 0.8529230000 953161671 0 1782222848 0.0040898551 -0.0165061317 0.3288875222 233 9.2800000000 0.0076659787 0.0035782061 0.0084668454 0.0095076387 0.8416040000 953162945 0 1783697408 0.0034818284 -0.0161181018 0.3282167315 234 9.3200000000 0.0075874790 0.0035953397 0.0084668454 0.0095371216 0.8436030000 953164219 0 1782571008 0.0028913277 -0.0157800745 0.3270574808 235 9.3600000000 0.0076671280 0.0036126665 0.0084668454 0.0095490741 0.8372020000 953165493 0 1784221696 0.0022699200 -0.0155446790 0.3260022402 236 9.4000000000 0.0076462496 0.0036297580 0.0084668454 0.0095528597 0.8839550000 953166767 0 1783205888 0.0015635068 -0.0150929950 0.3249275982 237 9.4400000000 0.0077316212 0.0036470654 0.0084668454 0.0095626417 0.8428220000 953168041 0 1781776384 0.0008005733 -0.0148795210 0.3238276541 238 9.4800000000 0.0081225652 0.0036658700 0.0084668454 0.0096418162 0.8308430000 953169315 0 1783300096 -0.0009866230 -0.0141533343 0.3213700652 239 9.5200000000 0.0080760447 0.0036843226 0.0084668454 0.0096706113 0.8274850000 953170589 0 1782222848 -0.0019481967 -0.0133460350 0.3202607632 240 9.5600000000 0.0082373442 0.0037032936 0.0084668454 0.0096989423 0.8236260000 953171863 0 1783697408 -0.0030166279 -0.0124177467 0.3189290464 241 9.6000000000 0.0084660314 0.0037230560 0.0084668454 0.0097677073 0.8241100000 953173137 0 1782571008 -0.0040759249 -0.0120523768 0.3178712428 242 9.6400000000 0.0086143147 0.0037432678 0.0086143147 0.0098400452 0.8565280000 953174411 0 1784205312 -0.0051353918 -0.0116189923 0.3167698979 243 9.6800000000 0.0088245636 0.0037641784 0.0088245636 0.0098975679 0.8213050000 953175685 0 1782919168 -0.0061518964 -0.0111533552 0.3151733577 244 9.7200000000 0.0091026630 0.0037860575 0.0091026630 0.0099515583 0.8140430000 953176959 0 1784569856 -0.0072811614 -0.0106040780 0.3137952089 245 9.7600000000 0.0090822289 0.0038076745 0.0091026630 0.0099966343 0.8151320000 953178233 0 1783353344 -0.0082896501 -0.0100980205 0.3124764860 246 9.8000000000 0.0093380120 0.0038301556 0.0093380120 0.0100243223 0.8096180000 953179507 0 1781944320 -0.0094152503 -0.0095861545 0.3109121025 247 9.8400000000 0.0095188906 0.0038531869 0.0095188906 0.0100638388 0.8054070000 953180781 0 1783443456 -0.0105288429 -0.0088152224 0.3095251024 248 9.8800000000 0.0095172124 0.0038760257 0.0095188906 0.0101143657 0.8082400000 953182055 0 1782222848 -0.0116254203 -0.0078334687 0.3078384697 249 9.9200000000 0.0094247647 0.0038983098 0.0095188906 0.0101671917 0.8081480000 953183329 0 1783681024 -0.0126017779 -0.0069832210 0.3062656522 250 9.9600000000 0.0090563362 0.0039189419 0.0095188906 0.0102109486 0.8047970000 953184603 0 1782423552 -0.0136284884 -0.0056263502 0.3049798608 251 10.0000000000 0.0085186986 0.0039372676 0.0095188906 0.0102546375 0.7935010000 953185877 0 1784078336 -0.0147472359 -0.0034863905 0.3036214113 252 10.0400000000 0.0080984104 0.0039537801 0.0095188906 0.0103140312 0.8015020000 953187151 0 1782845440 -0.0158130974 -0.0017065285 0.3021461666 253 10.0800000000 0.0080495970 0.0039699691 0.0095188906 0.0103497114 0.7944390000 953188425 0 1784356864 -0.0167085323 -0.0006315554 0.3004552424 254 10.1200000000 0.0080981897 0.0039862219 0.0095188906 0.0103860072 0.7923360000 953189699 0 1783054336 -0.0176913571 0.0003168756 0.2988880575 255 10.1600000000 0.0081830341 0.0040026800 0.0095188906 0.0104366591 0.7970430000 953190973 0 1784578048 -0.0187191572 0.0010841226 0.2973553538 256 10.2000000000 0.0082302578 0.0040191940 0.0095188906 0.0104801193 0.7948570000 953192247 0 1783324672 -0.0196140632 0.0018707928 0.2958118916 257 10.2400000000 0.0083436687 0.0040360207 0.0095188906 0.0105232751 0.7942470000 953193521 0 1781952512 -0.0206027366 0.0026662855 0.2943174541 258 10.2800000000 0.0083435280 0.0040527165 0.0095188906 0.0105361655 0.7935080000 953236779 0 1783578624 -0.0214295983 0.0035098153 0.2927270234 259 10.3200000000 0.0083276620 0.0040692221 0.0095188906 0.0105382995 0.7967500000 953238053 0 1782292480 -0.0223302599 0.0043095923 0.2911986411 260 10.3600000000 0.0085584670 0.0040864884 0.0095188906 0.0105572404 0.7927730000 953239327 0 1783943168 -0.0233410262 0.0051839594 0.2896013856 261 10.4000000000 0.0085431486 0.0041035637 0.0095188906 0.0105904342 0.7923670000 953240601 0 1782706176 -0.0242073033 0.0058378661 0.2881044745 262 10.4400000000 0.0085781598 0.0041206423 0.0095188906 0.0106022851 0.7957730000 953241875 0 1784205312 -0.0250414293 0.0065191090 0.2864304483 263 10.4800000000 0.0086228261 0.0041377609 0.0095188906 0.0106020155 0.8254690000 953243149 0 1783078912 -0.0259645190 0.0073328372 0.2848834395 264 10.5200000000 0.0086781969 0.0041549595 0.0095188906 0.0106061263 0.7884110000 953244423 0 1784569856 -0.0269421730 0.0080453428 0.2832992375 265 10.5600000000 0.0087165125 0.0041721729 0.0095188906 0.0106309966 0.7900700000 953245697 0 1783554048 -0.0278552268 0.0082437461 0.2819406092 266 10.6000000000 0.0086610531 0.0041890484 0.0095188906 0.0106300076 0.7859680000 953246971 0 1782460416 -0.0285894070 0.0086718854 0.2803958654 267 10.6400000000 0.0086977836 0.0042059351 0.0095188906 0.0106135972 0.7868300000 953248245 0 1784078336 -0.0294720158 0.0093618464 0.2786816657 268 10.6800000000 0.0086944699 0.0042226833 0.0095188906 0.0106043992 0.7918560000 953249519 0 1782968320 -0.0303518493 0.0097512780 0.2769910097 269 10.7200000000 0.0086974185 0.0042393180 0.0095188906 0.0106028133 0.7829700000 953250793 0 1784569856 -0.0312387906 0.0099908952 0.2756141722 270 10.7600000000 0.0087895682 0.0042561708 0.0095188906 0.0106076913 0.7836740000 953252067 0 1783427072 -0.0320466794 0.0101958541 0.2738803327 271 10.8000000000 0.0088832304 0.0042732448 0.0095188906 0.0106020192 0.7808410000 953253341 0 1782329344 -0.0327318832 0.0106691150 0.2717443109 272 10.8400000000 0.0089286175 0.0042903602 0.0095188906 0.0105883986 0.7794400000 953254615 0 1783967744 -0.0336645953 0.0111941630 0.2700874507 273 10.8800000000 0.0090629729 0.0043078423 0.0095188906 0.0105936178 0.7869030000 953255889 0 1782947840 -0.0346000269 0.0114644589 0.2682322562 274 10.9200000000 0.0090270434 0.0043250656 0.0095188906 0.0105927999 0.7777000000 953257163 0 1784569856 -0.0354550593 0.0116807269 0.2666536570 275 10.9600000000 0.0089967437 0.0043420536 0.0095188906 0.0105793369 0.7788810000 953258437 0 1783427072 -0.0359878466 0.0117779337 0.2646970153 276 11.0000000000 0.0089981416 0.0043589234 0.0095188906 0.0105643542 0.7665930000 953259711 0 1782439936 -0.0367508791 0.0118661411 0.2629737556 277 11.0400000000 0.0090527944 0.0043758688 0.0095188906 0.0105553206 0.7989130000 953260985 0 1784078336 -0.0376202054 0.0119339479 0.2614066899 278 11.0800000000 0.0091275889 0.0043929613 0.0095188906 0.0105481650 0.7642700000 953262259 0 1783091200 -0.0383637734 0.0119592901 0.2596820295 279 11.1200000000 0.0090166954 0.0044095339 0.0095188906 0.0105334692 0.7618960000 953263533 0 1781903360 -0.0390083492 0.0119732730 0.2581245601 280 11.1600000000 0.0091106771 0.0044263237 0.0095188906 0.0105155402 0.7596950000 953264807 0 1783586816 -0.0397673734 0.0122747608 0.2564146221 281 11.2000000000 0.0092118187 0.0044433539 0.0095188906 0.0104993514 0.7639240000 953266081 0 1782681600 -0.0405542180 0.0124839954 0.2547279000 282 11.2400000000 0.0092655513 0.0044604539 0.0095188906 0.0104830986 0.7551210000 953267355 0 1784225792 -0.0414563753 0.0127336346 0.2531011999 283 11.2800000000 0.0093219224 0.0044776322 0.0095188906 0.0104656549 0.7600470000 953268629 0 1783316480 -0.0423949249 0.0130040664 0.2515279353 284 11.3200000000 0.0093152002 0.0044946659 0.0095188906 0.0104475740 0.7484440000 953269903 0 1782460416 -0.0432267450 0.0131074190 0.2501233220 285 11.3600000000 0.0093265027 0.0045116197 0.0095188906 0.0104295143 0.7453450000 953271177 0 1784225792 -0.0442080349 0.0132803749 0.2483943403 286 11.4000000000 0.0092620067 0.0045282295 0.0095188906 0.0104115615 0.7483470000 953272451 0 1783472128 -0.0451732390 0.0134047884 0.2465683818 287 11.4400000000 0.0093075568 0.0045448822 0.0095188906 0.0103936864 0.7522010000 953273725 0 1782538240 -0.0461871102 0.0132730659 0.2448678911 288 11.4800000000 0.0093710106 0.0045616396 0.0095188906 0.0103760168 0.7465340000 953274999 0 1784188928 -0.0472273193 0.0130745275 0.2428865284 289 11.5200000000 0.0093674408 0.0045782686 0.0095188906 0.0103588851 0.7468820000 953276273 0 1783234560 -0.0488802083 0.0127986409 0.2415175736 290 11.5600000000 0.0094875749 0.0045951973 0.0095188906 0.0103413575 0.7385430000 953277547 0 1782325248 -0.0502085425 0.0124066658 0.2395325452 291 11.6000000000 0.0095742662 0.0046123075 0.0095742662 0.0103278869 0.7824370000 953278821 0 1784098816 -0.0517443083 0.0120704062 0.2377769649 292 11.6400000000 0.0093891080 0.0046286664 0.0095742662 0.0103104905 0.7406330000 953280095 0 1783054336 -0.0532966144 0.0116355326 0.2362636775 293 11.6800000000 0.0092805848 0.0046445432 0.0095742662 0.0102994053 0.7441370000 953281369 0 1781821440 -0.0548641495 0.0112241600 0.2346435487 294 11.7200000000 0.0093964189 0.0046607061 0.0095742662 0.0102823403 0.7418440000 953282643 0 1783320576 -0.0567170046 0.0108772367 0.2327464223 295 11.7600000000 0.0094623873 0.0046769830 0.0095742662 0.0102669184 0.7335160000 953283917 0 1782198272 -0.0587753877 0.0106640793 0.2311848253 296 11.8000000000 0.0094697913 0.0046931749 0.0095742662 0.0102501990 0.7305070000 953285191 0 1783689216 -0.0608563311 0.0104931798 0.2295829952 297 11.8400000000 0.0094418870 0.0047091638 0.0095742662 0.0102331633 0.7288810000 953286465 0 1782452224 -0.0629598051 0.0103815133 0.2280669659 298 11.8800000000 0.0093264738 0.0047246582 0.0095742662 0.0102206518 0.7669360000 953287739 0 1783967744 -0.0650145337 0.0103279985 0.2265070677 299 11.9200000000 0.0094170859 0.0047403519 0.0095742662 0.0102110960 0.7273980000 953289013 0 1782845440 -0.0673668608 0.0103342962 0.2250458896 300 11.9600000000 0.0094452593 0.0047560349 0.0095742662 0.0101967711 0.7304000000 953290287 0 1784315904 -0.0697333887 0.0100539317 0.2234999090 301 12.0000000000 0.0095467474 0.0047719509 0.0095742662 0.0101860518 0.7245580000 953291561 0 1783107584 -0.0720985234 0.0100461328 0.2219309509 302 12.0400000000 0.0096711311 0.0047881734 0.0096711311 0.0101734544 0.7228880000 953292835 0 1781944320 -0.0745846927 0.0101620536 0.2204431295 303 12.0800000000 0.0096570672 0.0048042423 0.0096711311 0.0101597097 0.7224600000 953294109 0 1783570432 -0.0769778565 0.0101951929 0.2187764347 304 12.1200000000 0.0095396237 0.0048198192 0.0096711311 0.0101489827 0.7268050000 953295383 0 1782460416 -0.0793695226 0.0101596229 0.2173472345 305 12.1600000000 0.0096199652 0.0048355574 0.0096711311 0.0101408601 0.7643560000 953296657 0 1784225792 -0.0818654671 0.0104044527 0.2157027870 306 12.2000000000 0.0096795801 0.0048513875 0.0096795801 0.0101267692 0.7311730000 953297931 0 1783218176 -0.0844396129 0.0106161730 0.2143124491 307 12.2400000000 0.0096895425 0.0048671470 0.0096895425 0.0101104760 0.7373580000 953299205 0 1782284288 -0.0868965015 0.0106622856 0.2127550095 308 12.2800000000 0.0095255058 0.0048822716 0.0096895425 0.0100947209 0.7347150000 953300479 0 1784098816 -0.0892589092 0.0103615364 0.2114648223 309 12.3200000000 0.0094823269 0.0048971585 0.0096895425 0.0100850058 0.7355120000 953301753 0 1783324672 -0.0916351900 0.0100750830 0.2101186812 310 12.3600000000 0.0096333856 0.0049124366 0.0096895425 0.0100759861 0.7455480000 953303027 0 1782333440 -0.0941123143 0.0100023197 0.2086622566 311 12.4000000000 0.0098121772 0.0049281914 0.0098121772 0.0100601428 0.7383130000 953304301 0 1784078336 -0.0966053307 0.0095818806 0.2076910883 312 12.4400000000 0.0097129093 0.0049435270 0.0098121772 0.0100442326 0.7416650000 953305575 0 1783070720 -0.0991362259 0.0093237432 0.2065753043 313 12.4800000000 0.0097762877 0.0049589672 0.0098121772 0.0100295001 0.7538580000 953306849 0 1782214656 -0.1015105247 0.0089646950 0.2054192275 314 12.5200000000 0.0098396894 0.0049745109 0.0098396894 0.0100139174 0.7553460000 953308123 0 1783844864 -0.1041470096 0.0085022096 0.2045346349 315 12.5600000000 0.0097771268 0.0049897573 0.0098396894 0.0099996048 0.7520720000 953309397 0 1783062528 -0.1062183678 0.0074628666 0.2036625296 316 12.6000000000 0.0096340431 0.0050044544 0.0098396894 0.0099885985 0.7573150000 953310671 0 1782284288 -0.1087346300 0.0069516534 0.2029233873 317 12.6400000000 0.0094998190 0.0050186353 0.0098396894 0.0099783651 0.7552170000 953311945 0 1784209408 -0.1107455567 0.0061784745 0.2019621134 318 12.6800000000 0.0094718337 0.0050326391 0.0098396894 0.0099804140 0.7673610000 953313219 0 1783070720 -0.1126953140 0.0054254998 0.2011764795 319 12.7200000000 0.0096590305 0.0050471419 0.0098396894 0.0099763881 0.7948350000 953314493 0 1782198272 -0.1145764813 0.0048730988 0.1999197453 320 12.7600000000 0.0099724215 0.0050625334 0.0099724215 0.0099620954 0.7669910000 953315767 0 1783824384 -0.1161858663 0.0041130306 0.1987380981 321 12.8000000000 0.0100291017 0.0050780056 0.0100291017 0.0099468910 0.7625340000 953317041 0 1782812672 -0.1176684797 0.0032913259 0.1974330097 322 12.8400000000 0.0099333432 0.0050930843 0.0100291017 0.0099343501 0.7605150000 953318315 0 1784623104 -0.1190696284 0.0021542341 0.1963333338 323 12.8800000000 0.0101492452 0.0051087380 0.0101492452 0.0099280365 0.7670340000 953319589 0 1783619584 -0.1206198186 0.0015706380 0.1949993372 324 12.9200000000 0.0102019915 0.0051244579 0.0102019915 0.0099165323 0.7614920000 953320863 0 1782284288 -0.1222766936 0.0010494166 0.1934559196 325 12.9600000000 0.0101266894 0.0051398494 0.0102019915 0.0099039636 0.7648280000 953322137 0 1784061952 -0.1238183603 0.0003153896 0.1920375824 326 13.0000000000 0.0100591816 0.0051549394 0.0102019915 0.0098943869 0.7637430000 953323411 0 1782943744 -0.1251187474 -0.0004614666 0.1905073225 327 13.0400000000 0.0101480540 0.0051702089 0.0102019915 0.0098854751 0.7687140000 953324685 0 1781940224 -0.1265240312 -0.0011291681 0.1888554096 328 13.0800000000 0.0102230627 0.0051856139 0.0102230627 0.0098734825 0.7649200000 953325959 0 1783570432 -0.1277436167 -0.0018480121 0.1874131709 329 13.1200000000 0.0101955505 0.0052008417 0.0102230627 0.0098635492 0.7669280000 953327233 0 1782538240 -0.1289617419 -0.0025034780 0.1856464595 330 13.1600000000 0.0102413362 0.0052161159 0.0102413362 0.0098532030 0.7632510000 953328507 0 1784205312 -0.1302556843 -0.0032983776 0.1838856637 331 13.2000000000 0.0103396969 0.0052315950 0.0103396969 0.0098433587 0.7670970000 953329781 0 1783058432 -0.1316286623 -0.0038782982 0.1818780452 332 13.2400000000 0.0102917040 0.0052468363 0.0103396969 0.0098345588 0.7648060000 953331055 0 1781813248 -0.1329474896 -0.0045567313 0.1799529195 333 13.2800000000 0.0104390876 0.0052624286 0.0104390876 0.0098295301 0.8075350000 953332329 0 1783554048 -0.1341011226 -0.0048938291 0.1774989814 334 13.3200000000 0.0104202451 0.0052778712 0.0104390876 0.0098195851 0.7651520000 953333603 0 1782411264 -0.1354524791 -0.0051351851 0.1751824915 335 13.3600000000 0.0100439964 0.0052920984 0.0104390876 0.0098111880 0.7649460000 953334877 0 1784078336 -0.1365871578 -0.0062219254 0.1732371300 336 13.4000000000 0.0102666775 0.0053069037 0.0104390876 0.0098364734 0.7675240000 953336151 0 1782951936 -0.1375996470 -0.0065233926 0.1706363559 337 13.4400000000 0.0105245449 0.0053223863 0.0105245449 0.0098455165 0.7662020000 953337425 0 1784586240 -0.1388449818 -0.0063467077 0.1672657728 338 13.4800000000 0.0104771871 0.0053376372 0.0105245449 0.0098430196 0.7701010000 953338699 0 1783435264 -0.1401541531 -0.0065319841 0.1648598909 339 13.5200000000 0.0106480429 0.0053533021 0.0106480429 0.0098415183 0.7785650000 953339973 0 1782210560 -0.1413964927 -0.0063283676 0.1621540487 340 13.5600000000 0.0108192824 0.0053693786 0.0108192824 0.0098292463 0.8101620000 953341247 0 1783705600 -0.1426199079 -0.0060176491 0.1593831480 341 13.6000000000 0.0108229704 0.0053853715 0.0108229704 0.0098147948 0.7743810000 953342521 0 1782579200 -0.1438655257 -0.0058440892 0.1568732709 342 13.6400000000 0.0106715616 0.0054008282 0.0108229704 0.0098004162 0.7709750000 953343795 0 1784205312 -0.1450623125 -0.0058916369 0.1542216390 343 13.6800000000 0.0105060488 0.0054157122 0.0108229704 0.0097866177 0.7743990000 953345069 0 1783046144 -0.1459913850 -0.0062899045 0.1516495347 344 13.7200000000 0.0105696823 0.0054306947 0.0108229704 0.0097803750 0.7717480000 953346343 0 1781960704 -0.1469921023 -0.0062883347 0.1483715177 345 13.7600000000 0.0107125100 0.0054460043 0.0108229704 0.0097718200 0.7731880000 953347617 0 1783562240 -0.1479963809 -0.0061239321 0.1452592313 346 13.8000000000 0.0106657706 0.0054610903 0.0108229704 0.0097581446 0.7779050000 953348891 0 1782444032 -0.1489970982 -0.0059763598 0.1424624026 347 13.8400000000 0.0106249126 0.0054759717 0.0108229704 0.0097440765 0.7705530000 953350165 0 1784061952 -0.1498904228 -0.0061384328 0.1395502836 348 13.8800000000 0.0105104931 0.0054904387 0.0108229704 0.0097305315 0.7715920000 953351439 0 1782919168 -0.1509006619 -0.0063630389 0.1370150596 349 13.9200000000 0.0105431257 0.0055049163 0.0108229704 0.0097183545 0.7720150000 953352713 0 1784586240 -0.1517499834 -0.0067881681 0.1341734678 350 13.9600000000 0.0105632422 0.0055193686 0.0108229704 0.0097081690 0.7781330000 953353987 0 1783332864 -0.1524105966 -0.0071475147 0.1309632957 351 14.0000000000 0.0105129313 0.0055335953 0.0108229704 0.0096975755 0.7773410000 953355261 0 1781952512 -0.1531496644 -0.0076221875 0.1281696707 352 14.0400000000 0.0105141141 0.0055477445 0.0108229704 0.0096907983 0.7806980000 953356535 0 1783554048 -0.1538429260 -0.0079483185 0.1250913441 353 14.0800000000 0.0105061587 0.0055617910 0.0108229704 0.0096826948 0.7736180000 953357809 0 1782444032 -0.1546018720 -0.0081997486 0.1222743466 354 14.1200000000 0.0106380777 0.0055761308 0.0108229704 0.0096713604 0.8061060000 953359083 0 1784078336 -0.1554718912 -0.0081113465 0.1194054112 355 14.1600000000 0.0105506051 0.0055901434 0.0108229704 0.0096578404 0.7741110000 953360357 0 1782968320 -0.1562225223 -0.0081194490 0.1169873103 356 14.2000000000 0.0105577586 0.0056040974 0.0108229704 0.0096443411 0.7751260000 953361631 0 1784586240 -0.1569643021 -0.0082569635 0.1143007278 357 14.2400000000 0.0107056312 0.0056183874 0.0108229704 0.0096310284 0.7741750000 953362905 0 1783427072 -0.1576817632 -0.0082025388 0.1116328388 358 14.2800000000 0.0106681427 0.0056324929 0.0108229704 0.0096215759 0.7697950000 953364179 0 1782312960 -0.1585384756 -0.0080203833 0.1095024049 359 14.3200000000 0.0103751281 0.0056457035 0.0108229704 0.0096144026 0.7740820000 953365453 0 1783951360 -0.1591509730 -0.0085932789 0.1069627330 360 14.3600000000 0.0103091560 0.0056586576 0.0108229704 0.0096021573 0.7702260000 953366727 0 1782931456 -0.1593974531 -0.0094591528 0.1046432629 361 14.4000000000 0.0104059651 0.0056718080 0.0108229704 0.0095987889 0.7704380000 953368001 0 1784569856 -0.1598778963 -0.0097102243 0.1023960263 362 14.4400000000 0.0104606049 0.0056850367 0.0108229704 0.0095878139 0.7720910000 953369275 0 1783427072 -0.1603410691 -0.0097999563 0.0995954648 363 14.4800000000 0.0102191651 0.0056975275 0.0108229704 0.0095751721 0.7716480000 953370549 0 1782329344 -0.1607820541 -0.0101850210 0.0975307375 364 14.5200000000 0.0101343635 0.0057097166 0.0108229704 0.0095669811 0.7694980000 953371823 0 1783951360 -0.1609654725 -0.0104570715 0.0951286778 365 14.5600000000 0.0100191189 0.0057215231 0.0108229704 0.0095564438 0.7780920000 953373097 0 1782837248 -0.1614333838 -0.0097660189 0.0926731303 366 14.6000000000 0.0097898915 0.0057326389 0.0108229704 0.0095467076 0.7759300000 953374371 0 1784442880 -0.1618936211 -0.0093176318 0.0902095586 367 14.6400000000 0.0096868649 0.0057434134 0.0108229704 0.0095378574 0.7713150000 953375645 0 1783312384 -0.1620036215 -0.0104220444 0.0878722593 368 14.6800000000 0.0098717036 0.0057546315 0.0108229704 0.0095284424 0.8130580000 953376919 0 1782202368 -0.1622031182 -0.0112380954 0.0854478627 369 14.7200000000 0.0097995298 0.0057655933 0.0108229704 0.0095190881 0.7684270000 953378193 0 1783824384 -0.1625436991 -0.0111548398 0.0832354054 370 14.7600000000 0.0096105849 0.0057759852 0.0108229704 0.0095071629 0.7688590000 953379467 0 1782693888 -0.1630471200 -0.0105372965 0.0810111985 371 14.8000000000 0.0095426533 0.0057861379 0.0108229704 0.0094945916 0.7736250000 953380741 0 1784315904 -0.1635786742 -0.0098370649 0.0782821849 372 14.8400000000 0.0094630858 0.0057960222 0.0108229704 0.0094880258 0.7694370000 953382015 0 1783205888 -0.1639583558 -0.0097496808 0.0753523856 373 14.8800000000 0.0096179787 0.0058062687 0.0108229704 0.0094813735 0.7692210000 953383289 0 1782091776 -0.1644184440 -0.0095875906 0.0725786537 374 14.9200000000 0.0097984131 0.0058169429 0.0108229704 0.0094863327 0.7677990000 953384563 0 1783697408 -0.1651762724 -0.0094838338 0.0702539757 375 14.9600000000 0.0097609134 0.0058274602 0.0108229704 0.0095002456 0.7682620000 953385837 0 1782538240 -0.1656949371 -0.0105972802 0.0683591887 376 15.0000000000 0.0098840259 0.0058382489 0.0108229704 0.0094907711 0.7684560000 953387111 0 1784221696 -0.1662256867 -0.0113256620 0.0659932867 377 15.0400000000 0.0101867579 0.0058497834 0.0108229704 0.0094788768 0.7687630000 953388385 0 1783058432 -0.1670369059 -0.0107261986 0.0636274293 378 15.0800000000 0.0100248680 0.0058608286 0.0108229704 0.0094887387 0.7704910000 953389659 0 1781944320 -0.1674452573 -0.0109648108 0.0608627126 379 15.1200000000 0.0098605920 0.0058713821 0.0108229704 0.0094844496 0.7612660000 953390933 0 1783570432 -0.1679964811 -0.0117336428 0.0584605671 380 15.1600000000 0.0100426516 0.0058823591 0.0108229704 0.0094719861 0.7635480000 953392207 0 1782411264 -0.1686059237 -0.0118256900 0.0556106865 381 15.2000000000 0.0099993404 0.0058931648 0.0108229704 0.0094608560 0.7616090000 953393481 0 1784078336 -0.1695443988 -0.0117618637 0.0534998290 382 15.2400000000 0.0099953758 0.0059039036 0.0108229704 0.0094496913 0.7946180000 953394755 0 1782968320 -0.1699576527 -0.0121712806 0.0505642518 383 15.2800000000 0.0101181976 0.0059149070 0.0108229704 0.0094374325 0.7596840000 953396029 0 1781694464 -0.1707215458 -0.0122020710 0.0483900830 384 15.3200000000 0.0101637403 0.0059259717 0.0108229704 0.0094260124 0.7586040000 953397303 0 1783308288 -0.1718297452 -0.0120214801 0.0458160900 385 15.3600000000 0.0101770516 0.0059370134 0.0108229704 0.0094162185 0.7535460000 953398577 0 1782210560 -0.1730480194 -0.0117031066 0.0435404703 386 15.4000000000 0.0101508256 0.0059479300 0.0108229704 0.0094056013 0.7503830000 953399851 0 1783832576 -0.1738231331 -0.0115698976 0.0406525135 387 15.4400000000 0.0102202976 0.0059589697 0.0108229704 0.0093938863 0.7479150000 953401125 0 1782706176 -0.1748016924 -0.0111554358 0.0380203351 388 15.4800000000 0.0102426223 0.0059700101 0.0108229704 0.0093858050 0.7433460000 953402399 0 1784324096 -0.1764120609 -0.0104711959 0.0359424204 389 15.5200000000 0.0102041066 0.0059808947 0.0108229704 0.0093824478 0.7432020000 953403673 0 1783230464 -0.1772460043 -0.0100308834 0.0331823379 390 15.5600000000 0.0101706162 0.0059916375 0.0108229704 0.0093762263 0.7413560000 953404947 0 1781952512 -0.1787165850 -0.0096795345 0.0309455954 391 15.6000000000 0.0103521356 0.0060027897 0.0108229704 0.0093672609 0.7437890000 953406221 0 1783570432 -0.1802675128 -0.0089087961 0.0286134463 392 15.6400000000 0.0103357621 0.0060138432 0.0108229704 0.0093678087 0.7341340000 953407495 0 1782411264 -0.1815630496 -0.0082904985 0.0261087175 393 15.6800000000 0.0103709465 0.0060249300 0.0108229704 0.0093659761 0.7315730000 953408769 0 1784078336 -0.1825395525 -0.0080554513 0.0237153154 394 15.7200000000 0.0104489354 0.0060361584 0.0108229704 0.0093615912 0.7404170000 953410043 0 1783087104 -0.1838016510 -0.0076584825 0.0214247312 395 15.7600000000 0.0105789872 0.0060476592 0.0108229704 0.0093552577 0.7355750000 953411317 0 1782050816 -0.1855576932 -0.0069656540 0.0188282914 396 15.8000000000 0.0106458915 0.0060592709 0.0108229704 0.0093511585 0.7703660000 953412591 0 1783824384 -0.1864954680 -0.0061712097 0.0159756616 397 15.8400000000 0.0105977356 0.0060707028 0.0108229704 0.0093554179 0.7476560000 953413865 0 1782681600 -0.1878746152 -0.0054354751 0.0138900168 398 15.8800000000 0.0103584118 0.0060814760 0.0108229704 0.0093647237 0.7477070000 953415139 0 1781796864 -0.1890503019 -0.0055921613 0.0114053572 399 15.9200000000 0.0103590908 0.0060921968 0.0108229704 0.0093571753 0.7485710000 953416413 0 1783459840 -0.1901778132 -0.0057040728 0.0091961417 400 15.9600000000 0.0106770359 0.0061036589 0.0108229704 0.0093467307 0.7596070000 953417687 0 1782431744 -0.1913672686 -0.0049186563 0.0067143105 401 16.0000000000 0.0105683710 0.0061147929 0.0108229704 0.0093511336 0.7635000000 953418961 0 1784315904 -0.1923451126 -0.0046194643 0.0044163703 402 16.0400000000 0.0106028700 0.0061259572 0.0108229704 0.0093476120 0.7773040000 953420235 0 1783181312 -0.1935365796 -0.0043027126 0.0022384387 403 16.0800000000 0.0107564554 0.0061374473 0.0108229704 0.0093499502 0.8122620000 953421509 0 1782304768 -0.1945749670 -0.0037902424 0.0000153119 404 16.1200000000 0.0108765801 0.0061491778 0.0108765801 0.0093666139 0.7900050000 953422783 0 1784090624 -0.1949157417 -0.0034498074 -0.0025820725 405 16.1600000000 0.0106218280 0.0061602214 0.0108765801 0.0093869453 0.7883330000 953424057 0 1783435264 -0.1959621757 -0.0034102930 -0.0043330868 406 16.2000000000 0.0109651033 0.0061720561 0.0109651033 0.0093827142 0.7897350000 953425331 0 1782538240 -0.1965720505 -0.0023955985 -0.0067226943 407 16.2400000000 0.0108072003 0.0061834447 0.0109651033 0.0093982786 0.7921600000 953426605 0 1784221696 -0.1975187361 -0.0020588955 -0.0084881810 408 16.2800000000 0.0108742304 0.0061949417 0.0109651033 0.0094035609 0.7952000000 953427879 0 1783197696 -0.1979273111 -0.0019973840 -0.0105833448 409 16.3200000000 0.0109392228 0.0062065414 0.0109651033 0.0093968865 0.7969600000 953429153 0 1782452224 -0.1985729188 -0.0020087578 -0.0126645947 410 16.3600000000 0.0113585405 0.0062191072 0.0113585405 0.0093877868 0.7994370000 953430427 0 1784094720 -0.1989918500 -0.0013439044 -0.0148210889 411 16.3999999990 0.0113544520 0.0062316020 0.0113585405 0.0093946362 0.7982830000 953431701 0 1783316480 -0.1995071024 -0.0008418715 -0.0169102605 412 16.4400000000 0.0113676712 0.0062440682 0.0113676712 0.0094002151 0.7980150000 953432975 0 1782460416 -0.2000475675 -0.0002105041 -0.0191021394 413 16.4800000000 0.0113375578 0.0062564011 0.0113676712 0.0093986580 0.8005910000 953434249 0 1784098816 -0.2007423192 -0.0000396781 -0.0211123377 414 16.5200000000 0.0114012193 0.0062688282 0.0114012193 0.0093910782 0.7989830000 953435523 0 1783070720 -0.2010963857 0.0000771745 -0.0232899878 415 16.5599999990 0.0117664188 0.0062820754 0.0117664188 0.0093805030 0.8009510000 953436797 0 1782214656 -0.2014220655 0.0005534491 -0.0258129630 416 16.6000000000 0.0117233405 0.0062951554 0.0117664188 0.0093738117 0.8111240000 953438071 0 1783951360 -0.2018940598 0.0007482151 -0.0279865302 417 16.6400000000 0.0119217290 0.0063086483 0.0119217290 0.0093686203 0.8025870000 953439345 0 1782829056 -0.2026160806 0.0011449930 -0.0303722080 418 16.6800000000 0.0120236091 0.0063223205 0.0120236091 0.0093683643 0.8001400000 953440619 0 1782050816 -0.2036979795 0.0020214522 -0.0328293070 419 16.7199999990 0.0121176932 0.0063361519 0.0121176932 0.0093807900 0.7997530000 953441893 0 1783717888 -0.2041581869 0.0031742745 -0.0355712436 420 16.7600000000 0.0115477797 0.0063485606 0.0121176932 0.0094020330 0.8004640000 953443167 0 1782812672 -0.2043233961 0.0037457128 -0.0380941480 421 16.8000000000 0.0116236899 0.0063610906 0.0121176932 0.0093988513 0.7968280000 953444441 0 1784332288 -0.2047024220 0.0043054433 -0.0408647582 422 16.8400000000 0.0117340162 0.0063738226 0.0121176932 0.0093940859 0.8048210000 953445715 0 1783554048 -0.2043956816 0.0049434043 -0.0437169783 423 16.8799999990 0.0116803134 0.0063863675 0.0121176932 0.0093891575 0.7958420000 953446989 0 1782792192 -0.2051140368 0.0056113806 -0.0462520570 424 16.9200000000 0.0118293371 0.0063992047 0.0121176932 0.0093841749 0.8299090000 953448263 0 1784479744 -0.2054493576 0.0064772405 -0.0492712520 425 16.9600000000 0.0115768462 0.0064113874 0.0121176932 0.0094002438 0.8005720000 953449537 0 1783582720 -0.2052102387 0.0070688170 -0.0523561873 426 17.0000000000 0.0112890033 0.0064228372 0.0121176932 0.0093988302 0.7970120000 953450811 0 1782697984 -0.2050357014 0.0074915057 -0.0552543290 427 17.0400000000 0.0110772429 0.0064337374 0.0121176932 0.0093885688 0.7979380000 953452085 0 1782038528 -0.2050392330 0.0074131121 -0.0580552332 428 17.0800000000 0.0113343410 0.0064451875 0.0121176932 0.0093777562 0.8011170000 953453359 0 1783726080 -0.2036513090 0.0077765621 -0.0615037158 429 17.1200000000 0.0112411687 0.0064563669 0.0121176932 0.0093678585 0.8070530000 953454633 0 1782726656 -0.2031132728 0.0080417357 -0.0646663085 430 17.1600000000 0.0112922089 0.0064676130 0.0121176932 0.0093572294 0.7972800000 953455907 0 1784487936 -0.2034417838 0.0082585672 -0.0676113516 431 17.2000000000 0.0116020562 0.0064795259 0.0121176932 0.0093465101 0.7987520000 953457181 0 1783336960 -0.2030634880 0.0087438710 -0.0711436644 432 17.2400000000 0.0116028488 0.0064913854 0.0121176932 0.0093409094 0.7965980000 953458455 0 1782419456 -0.2029995024 0.0091817873 -0.0740952492 433 17.2800000000 0.0114739258 0.0065028925 0.0121176932 0.0093385060 0.7980640000 953459729 0 1784229888 -0.2030821741 0.0096380208 -0.0773593187 434 17.3200000000 0.0115425177 0.0065145045 0.0121176932 0.0093316041 0.7989390000 953461003 0 1783480320 -0.2028570473 0.0099413665 -0.0804676265 435 17.3600000000 0.0119706327 0.0065270473 0.0121176932 0.0093224685 0.8015860000 953462277 0 1782312960 -0.2029780596 0.0108400257 -0.0839090124 436 17.4000000000 0.0116555123 0.0065388099 0.0121176932 0.0093302566 0.7972740000 953463551 0 1784098816 -0.2022999674 0.0116276871 -0.0871090218 437 17.4400000000 0.0113391988 0.0065497947 0.0121176932 0.0093454654 0.8028550000 953464825 0 1782935552 -0.2016452998 0.0122556137 -0.0899456218 438 17.4800000000 0.0112119960 0.0065604390 0.0121176932 0.0093426039 0.7958470000 953466099 0 1782157312 -0.2005859166 0.0127260694 -0.0931731313 439 17.5200000000 0.0111611895 0.0065709191 0.0121176932 0.0093411150 0.7972910000 953467373 0 1783967744 -0.1985313445 0.0132557685 -0.0963160396 440 17.5600000000 0.0110716773 0.0065811481 0.0121176932 0.0093455507 0.7985050000 953468647 0 1783050240 -0.1977409571 0.0136073483 -0.0989624560 441 17.6000000000 0.0110962624 0.0065913865 0.0121176932 0.0093499589 0.8019450000 953469921 0 1782198272 -0.1969897151 0.0141240088 -0.1015794948 442 17.6400000000 0.0109074833 0.0066011514 0.0121176932 0.0093606248 0.7969760000 953471195 0 1783934976 -0.1967459917 0.0140314335 -0.1042949930 443 17.6800000000 0.0107509177 0.0066105188 0.0121176932 0.0093630950 0.7993180000 953472469 0 1783046144 -0.1965210587 0.0136351781 -0.1066219509 444 17.7200000000 0.0109565388 0.0066203071 0.0121176932 0.0093562419 0.7958250000 953473743 0 1784733696 -0.1963987350 0.0133635588 -0.1092885286 445 17.7600000000 0.0113912970 0.0066310285 0.0121176932 0.0093457504 0.8377500000 953475017 0 1783730176 -0.1964372247 0.0136597641 -0.1121261418 446 17.8000000000 0.0113043915 0.0066415068 0.0121176932 0.0093360027 0.7955210000 953476291 0 1782943744 -0.1963806301 0.0138958190 -0.1148078740 447 17.8400000000 0.0115047358 0.0066523866 0.0121176932 0.0093292441 0.8016040000 953477565 0 1782087680 -0.1965690851 0.0142423175 -0.1173774078 448 17.8800000000 0.0112734875 0.0066627015 0.0121176932 0.0093201862 0.7956310000 953478839 0 1783697408 -0.1961789429 0.0145309670 -0.1198213249 449 17.9200000000 0.0107900351 0.0066718938 0.0121176932 0.0093126320 0.7964520000 953480113 0 1782706176 -0.1956546158 0.0140668489 -0.1220012382 450 17.9600000000 0.0115374411 0.0066827061 0.0121176932 0.0093023995 0.7931370000 953481387 0 1784352768 -0.1957423538 0.0141817005 -0.1270774454 451 18.0000000000 0.0112118497 0.0066927486 0.0121176932 0.0093084033 0.7986070000 953482661 0 1783218176 -0.1958660185 0.0143160839 -0.1296599060 452 18.0400000000 0.0107246693 0.0067016687 0.0121176932 0.0093146241 0.7944350000 953483935 0 1782198272 -0.1961915642 0.0136638740 -0.1317391694 453 18.0800000000 0.0107809091 0.0067106737 0.0121176932 0.0093197371 0.8004210000 953485209 0 1783808000 -0.1963593662 0.0129802823 -0.1340951920 454 18.1200000000 0.0111963609 0.0067205541 0.0121176932 0.0093152279 0.8008680000 953486483 0 1782706176 -0.1967803091 0.0130463066 -0.1369626969 455 18.1600000000 0.0117224064 0.0067315471 0.0121176932 0.0093051006 0.7947660000 953487757 0 1784332288 -0.1973711550 0.0136563750 -0.1400060207 456 18.2000000000 0.0117353955 0.0067425205 0.0121176932 0.0092956441 0.7930190000 953489031 0 1783361536 -0.1978007555 0.0146120889 -0.1427082270 457 18.2400000000 0.0110974759 0.0067520499 0.0121176932 0.0092974047 0.7911110000 953490305 0 1782325248 -0.1982427835 0.0150508527 -0.1450864524 458 18.2800000000 0.0112994770 0.0067619788 0.0121176932 0.0092945698 0.7923130000 953491579 0 1783934976 -0.1989903897 0.0155773126 -0.1478967071 459 18.3200000000 0.0110312551 0.0067712801 0.0121176932 0.0093104019 0.7952730000 953492853 0 1782923264 -0.1999623626 0.0160330422 -0.1504841149 460 18.3600000000 0.0108236559 0.0067800896 0.0121176932 0.0093158214 0.7917320000 953494127 0 1781940224 -0.2002889365 0.0164111778 -0.1533724219 461 18.4000000000 0.0108901365 0.0067890051 0.0121176932 0.0093128813 0.7903790000 953495401 0 1783607296 -0.2010808885 0.0166326985 -0.1562175304 462 18.4400000000 0.0104609979 0.0067969531 0.0121176932 0.0093337835 0.7901810000 953496675 0 1782562816 -0.2014913261 0.0163197666 -0.1586690396 463 18.4800000000 0.0105941975 0.0068051545 0.0121176932 0.0093400129 0.7905920000 953497949 0 1784094720 -0.2020106614 0.0163308214 -0.1616264284 464 18.5200000000 0.0103319958 0.0068127555 0.0121176932 0.0093405035 0.7897670000 953499223 0 1783214080 -0.2028199136 0.0159763172 -0.1641100794 465 18.5600000000 0.0105739096 0.0068208440 0.0121176932 0.0093383272 0.7889770000 953500497 0 1782071296 -0.2035686076 0.0161417685 -0.1672259420 466 18.6000000000 0.0110719763 0.0068299666 0.0121176932 0.0093294995 0.8241390000 953501771 0 1783840768 -0.2049176991 0.0168733187 -0.1705929488 467 18.6400000000 0.0113083329 0.0068395562 0.0121176932 0.0093195458 0.7872660000 953503045 0 1782837248 -0.2062235177 0.0177941378 -0.1737525314 468 18.6800000000 0.0113958260 0.0068492918 0.0121176932 0.0093102820 0.7844320000 953504319 0 1784442880 -0.2073920667 0.0188602563 -0.1768898517 469 18.7200000000 0.0110442834 0.0068582364 0.0121176932 0.0093097231 0.7924570000 953505593 0 1783300096 -0.2082691342 0.0196457785 -0.1797213256 470 18.7600000000 0.0117445979 0.0068686329 0.0121176932 0.0093005757 0.7873580000 953506867 0 1782210560 -0.2097295672 0.0215785038 -0.1831943095 471 18.8000000000 0.0106059331 0.0068765677 0.0121176932 0.0093287785 0.7838460000 953508141 0 1783975936 -0.2104650289 0.0225638766 -0.1857594848 472 18.8400000000 0.0102832476 0.0068837853 0.0121176932 0.0094174172 0.7968400000 953509415 0 1782956032 -0.2113271952 0.0240864418 -0.1887324899 473 18.8800000000 0.0096869897 0.0068897117 0.0121176932 0.0094814341 0.7886780000 953510689 0 1781800960 -0.2123174071 0.0244155340 -0.1916474551 474 18.9200000000 0.0100835981 0.0068964499 0.0121176932 0.0094823307 0.7831350000 953511963 0 1783562240 -0.2140516937 0.0244535841 -0.1944794059 475 18.9600000000 0.0105619840 0.0069041668 0.0121176932 0.0094787944 0.7803470000 953513237 0 1782480896 -0.2154398710 0.0252601560 -0.1973811537 476 19.0000000000 0.0105820773 0.0069118935 0.0121176932 0.0094951894 0.7778130000 953514511 0 1784225792 -0.2165612876 0.0268751923 -0.2002315074 477 19.0400000000 0.0107538784 0.0069199479 0.0121176932 0.0094942396 0.7822730000 953515785 0 1783070720 -0.2173539251 0.0286499597 -0.2032979131 478 19.0800000000 0.0111420788 0.0069287809 0.0121176932 0.0094858743 0.7832040000 953517059 0 1784696832 -0.2184325159 0.0303903054 -0.2060028166 479 19.1200000000 0.0108136218 0.0069368912 0.0121176932 0.0094839865 0.7779210000 953518333 0 1783603200 -0.2196741402 0.0316985175 -0.2084345371 480 19.1600000000 0.0106013548 0.0069445255 0.0121176932 0.0094858112 0.8049590000 953519607 0 1782185984 -0.2206760198 0.0328765474 -0.2110402286 481 19.2000000000 0.0105055431 0.0069519288 0.0121176932 0.0094826219 0.7726700000 953520881 0 1783861248 -0.2216128111 0.0337254442 -0.2134153396 482 19.2400000000 0.0105371494 0.0069593671 0.0121176932 0.0094802954 0.7795880000 953522155 0 1782837248 -0.2227198780 0.0347262062 -0.2159880251 483 19.2800000000 0.0098909661 0.0069654366 0.0121176932 0.0094994039 0.7709290000 953523429 0 1784569856 -0.2235253602 0.0347633958 -0.2179934084 484 19.3200000000 0.0101179089 0.0069719500 0.0121176932 0.0094975482 0.7810810000 953524703 0 1783619584 -0.2241286486 0.0349204876 -0.2200635970 485 19.3600000000 0.0102243498 0.0069786560 0.0121176932 0.0094894321 0.7757680000 953525977 0 1782460416 -0.2244562060 0.0350400433 -0.2218846828 486 19.4000000000 0.0104629146 0.0069858252 0.0121176932 0.0094809704 0.7747230000 953527251 0 1784205312 -0.2247675955 0.0354394056 -0.2239554971 487 19.4400000000 0.0106374137 0.0069933234 0.0121176932 0.0094748490 0.7767560000 953528525 0 1783046144 -0.2252899557 0.0362989567 -0.2260279357 488 19.4800000000 0.0105708586 0.0070006544 0.0121176932 0.0094711306 0.7704330000 953529799 0 1782030336 -0.2256305218 0.0371022671 -0.2281763554 489 19.5200000000 0.0101049310 0.0070070026 0.0121176932 0.0094746170 0.7669120000 953531073 0 1783697408 -0.2258710861 0.0372264087 -0.2299302667 490 19.5600000000 0.0103013273 0.0070137257 0.0121176932 0.0094698232 0.7673930000 953532347 0 1782693888 -0.2260490954 0.0377399251 -0.2319785058 491 19.6000000000 0.0104440181 0.0070207120 0.0121176932 0.0094620726 0.7671000000 953533621 0 1784332288 -0.2268728465 0.0378576852 -0.2339610606 492 19.6400000000 0.0106966877 0.0070281835 0.0121176932 0.0094536732 0.7600840000 953534895 0 1783173120 -0.2267094851 0.0385273397 -0.2360351384 493 19.6800000000 0.0103956098 0.0070350140 0.0121176932 0.0094486852 0.7575960000 953536169 0 1781944320 -0.2268736660 0.0389731787 -0.2378725708 494 19.7200000000 0.0106413392 0.0070423143 0.0121176932 0.0094412503 0.7840080000 953537443 0 1783443456 -0.2265536934 0.0397116467 -0.2399060279 495 19.7600000000 0.0101440698 0.0070485804 0.0121176932 0.0094430220 0.7486930000 953538717 0 1782333440 -0.2274289876 0.0397687145 -0.2418601364 496 19.8000000000 0.0101883356 0.0070549106 0.0121176932 0.0094437519 0.7424150000 953539991 0 1783934976 -0.2287868261 0.0398156233 -0.2442626357 497 19.8400000000 0.0100825774 0.0070610025 0.0121176932 0.0094405019 0.7510920000 953541265 0 1782804480 -0.2292929888 0.0393963233 -0.2462173104 498 19.8800000000 0.0097607635 0.0070664237 0.0121176932 0.0094352157 0.7434110000 953542539 0 1784475648 -0.2284010202 0.0380038321 -0.2475461215 499 19.9200000000 0.0102934102 0.0070728906 0.0121176932 0.0094264721 0.7385580000 953543813 0 1783312384 -0.2277799845 0.0375906006 -0.2498332709 500 19.9600000000 0.0105890539 0.0070799229 0.0121176932 0.0094173514 0.7372840000 953545087 0 1782030336 -0.2270344496 0.0378540531 -0.2522435784 501 20.0000000000 0.0096255550 0.0070850040 0.0121176932 0.0094298143 0.7356050000 953546361 0 1783697408 -0.2274745554 0.0368019193 -0.2543635666 502 20.0400000000 0.0096010370 0.0070900160 0.0121176932 0.0094474748 0.7358510000 953547635 0 1782697984 -0.2283596843 0.0360175781 -0.2571497560 503 20.0800000000 0.0103020156 0.0070964017 0.0121176932 0.0094400200 0.7294040000 953548909 0 1784332288 -0.2280831039 0.0364202745 -0.2601774037 504 20.1200000000 0.0105752572 0.0071033042 0.0121176932 0.0094312928 0.7381670000 953550183 0 1783173120 -0.2276557386 0.0367688686 -0.2625875175 505 20.1600000000 0.0109495325 0.0071109205 0.0121176932 0.0094229636 0.7328040000 953551457 0 1781960704 -0.2274070680 0.0375548378 -0.2653990388 506 20.2000000000 0.0110605583 0.0071187261 0.0121176932 0.0094146748 0.7304770000 953552731 0 1783586816 -0.2276048064 0.0384305641 -0.2678283155 507 20.2400000000 0.0103351036 0.0071250700 0.0121176932 0.0094095972 0.7280320000 953554005 0 1782317056 -0.2280784547 0.0380253270 -0.2701660693 508 20.2800000000 0.0104452288 0.0071316058 0.0121176932 0.0094031603 0.7636510000 953555279 0 1783934976 -0.2279171944 0.0378750190 -0.2729639113 509 20.3200000000 0.0103006102 0.0071378317 0.0121176932 0.0094001054 0.7295190000 953556553 0 1782681600 -0.2271043211 0.0375390425 -0.2750741243 510 20.3600000000 0.0106879855 0.0071447928 0.0121176932 0.0094027202 0.7284000000 953557827 0 1784205312 -0.2267130166 0.0381347574 -0.2774848938 511 20.4000000000 0.0107944505 0.0071519350 0.0121176932 0.0093958505 0.7352760000 953559101 0 1782951936 -0.2266426831 0.0385512747 -0.2801250219 512 20.4400000000 0.0108800931 0.0071592166 0.0121176932 0.0093876092 0.7298090000 953560375 0 1784442880 -0.2263798565 0.0390868112 -0.2829766870 513 20.4800000000 0.0112934932 0.0071672756 0.0121176932 0.0093802858 0.7302230000 953561649 0 1783205888 -0.2240253687 0.0401615389 -0.2860257030 514 20.5200000000 0.0108009679 0.0071743450 0.0121176932 0.0093747537 0.7317950000 953646891 0 1781944320 -0.2230677307 0.0405880623 -0.2889261842 515 20.5600000000 0.0106067816 0.0071810100 0.0121176932 0.0093682444 0.7724230000 953648165 0 1783443456 -0.2216810882 0.0402361006 -0.2916682959 516 20.6000000000 0.0106203891 0.0071876754 0.0121176932 0.0093650105 0.7308880000 953649439 0 1782292480 -0.2193727791 0.0397434793 -0.2943691909 517 20.6400000000 0.0108808540 0.0071948189 0.0121176932 0.0093578129 0.7294480000 953650713 0 1783832576 -0.2172610611 0.0397961028 -0.2968858182 518 20.6800000000 0.0110285794 0.0072022200 0.0121176932 0.0093526169 0.7382200000 953651987 0 1782579200 -0.2153955698 0.0404175855 -0.2994462252 519 20.7200000000 0.0110135498 0.0072095636 0.0121176932 0.0093479805 0.7295620000 953653261 0 1784086528 -0.2139736712 0.0410358161 -0.3020626307 520 20.7600000000 0.0105826035 0.0072160502 0.0121176932 0.0093430466 0.7332520000 953654535 0 1782800384 -0.2130827010 0.0411178283 -0.3043365777 521 20.8000000000 0.0110718170 0.0072234509 0.0121176932 0.0093350290 0.7299960000 953655809 0 1784467456 -0.2121643275 0.0417669788 -0.3066936135 522 20.8400000000 0.0115158353 0.0072316739 0.0121176932 0.0093270941 0.7678120000 953657083 0 1783214080 -0.2115747929 0.0433469713 -0.3091775477 523 20.8800000000 0.0111659048 0.0072391963 0.0121176932 0.0093186886 0.7337240000 953658357 0 1781833728 -0.2108747959 0.0442015119 -0.3113753200 524 20.9200000000 0.0110184588 0.0072464086 0.0121176932 0.0093111396 0.7399720000 953659631 0 1783300096 -0.2104898691 0.0443645678 -0.3137597144 525 20.9600000000 0.0111904647 0.0072539211 0.0121176932 0.0093052440 0.7374900000 953660905 0 1782075392 -0.2099702656 0.0444020070 -0.3161234856 526 21.0000000000 0.0114336880 0.0072618674 0.0121176932 0.0093009258 0.7368060000 953662179 0 1783570432 -0.2094707340 0.0447397605 -0.3183935881 527 21.0400000000 0.0115272775 0.0072699612 0.0121176932 0.0092959644 0.7402900000 953663453 0 1782317056 -0.2090009600 0.0448677018 -0.3203133345 528 21.0800000000 0.0118354447 0.0072786079 0.0121176932 0.0092971923 0.7398730000 953664727 0 1783808000 -0.2081366330 0.0448346473 -0.3222408891 529 21.1200000000 0.0116787888 0.0072869259 0.0121176932 0.0092961933 0.7433170000 953666001 0 1782697984 -0.2074210346 0.0440956093 -0.3240624070 530 21.1600000000 0.0117735602 0.0072953912 0.0121176932 0.0092973221 0.7458800000 953667275 0 1784332288 -0.2075064629 0.0438728966 -0.3258939087 531 21.2000000000 0.0119649330 0.0073041851 0.0121176932 0.0093037673 0.7576580000 953668549 0 1783099392 -0.2070018500 0.0439454913 -0.3278028071 532 21.2400000000 0.0117107332 0.0073124681 0.0121176932 0.0093144659 0.7454960000 953669823 0 1784569856 -0.2062531710 0.0428157859 -0.3293736279 533 21.2800000000 0.0118382862 0.0073209593 0.0121176932 0.0093225689 0.7676130000 953671097 0 1783332864 -0.2057429105 0.0423053689 -0.3309773505 534 21.3200000000 0.0116238454 0.0073290171 0.0121176932 0.0093167425 0.7570790000 953672371 0 1781944320 -0.2051744312 0.0416521020 -0.3323270082 535 21.3600000000 0.0115425121 0.0073368928 0.0121176932 0.0093139386 0.7558060000 953673645 0 1783443456 -0.2049575895 0.0407238565 -0.3336624205 536 21.4000000000 0.0119569916 0.0073455124 0.0121176932 0.0093124867 0.7854420000 953674919 0 1782157312 -0.2047109604 0.0404458307 -0.3353161514 537 21.4400000000 0.0116143776 0.0073534619 0.0121176932 0.0093110175 0.7576360000 953676193 0 1783681024 -0.2047788352 0.0398110300 -0.3364875913 538 21.4800000000 0.0120661566 0.0073622215 0.0121176932 0.0093214848 0.7537790000 953677467 0 1782444032 -0.2042840719 0.0392126292 -0.3377885222 539 21.5200000000 0.0119643696 0.0073707598 0.0121176932 0.0093384586 0.7538810000 953678741 0 1783967744 -0.2039569318 0.0382883102 -0.3390166461 540 21.5600000000 0.0120815970 0.0073794836 0.0121176932 0.0093461302 0.7569690000 953680015 0 1782845440 -0.2037504464 0.0378662236 -0.3402617276 541 21.6000000000 0.0120630153 0.0073881408 0.0121176932 0.0093505162 0.7620370000 953681289 0 1784315904 -0.2039621472 0.0375829861 -0.3415197134 542 21.6400000000 0.0117594004 0.0073962058 0.0121176932 0.0093512659 0.7686780000 953682563 0 1783078912 -0.2040176392 0.0365158953 -0.3426302075 543 21.6800000000 0.0116867144 0.0074041073 0.0121176932 0.0093539523 0.8096260000 953683837 0 1784602624 -0.2045706958 0.0355995595 -0.3437113166 544 21.7200000000 0.0115478626 0.0074117245 0.0121176932 0.0093509544 0.7840490000 953685111 0 1783443456 -0.2050568759 0.0346537568 -0.3449021280 545 21.7600000000 0.0114848260 0.0074191981 0.0121176932 0.0093461251 0.7820000000 953686385 0 1782030336 -0.2052840739 0.0333718993 -0.3459038734 546 21.8000000000 0.0116515476 0.0074269496 0.0121176932 0.0093520232 0.7874840000 953687659 0 1783554048 -0.2055940032 0.0322633348 -0.3469009399 547 21.8400000000 0.0118243517 0.0074349888 0.0121176932 0.0093756019 0.7899750000 953688933 0 1782317056 -0.2054487169 0.0306168832 -0.3479410410 548 21.8800000000 0.0117929494 0.0074429413 0.0121176932 0.0093893575 0.7930750000 953690207 0 1783951360 -0.2057466805 0.0295765270 -0.3490422666 549 21.9200000000 0.0115505913 0.0074504233 0.0121176932 0.0094004356 0.8006500000 953691481 0 1782968320 -0.2062389255 0.0263479557 -0.3499929011 550 21.9600000000 0.0117797460 0.0074582948 0.0121176932 0.0094090680 0.8118020000 953692755 0 1781653504 -0.2069094926 0.0252600424 -0.3510506451 551 22.0000000000 0.0120945647 0.0074667091 0.0121176932 0.0094061547 0.8120600000 953694029 0 1783300096 -0.2074624747 0.0250974912 -0.3522038758 552 22.0400000000 0.0117452741 0.0074744601 0.0121176932 0.0094033641 0.8225350000 953695303 0 1782202368 -0.2081061751 0.0245442707 -0.3530193865 553 22.0800000000 0.0116414195 0.0074819953 0.0121176932 0.0094036572 0.8223920000 953696577 0 1783824384 -0.2088759392 0.0226576347 -0.3538677394 554 22.1200000000 0.0119743161 0.0074901042 0.0121176932 0.0094113861 0.8378390000 953697851 0 1782824960 -0.2093680501 0.0220916253 -0.3547619879 555 22.1600000000 0.0123625696 0.0074988834 0.0123625696 0.0094141818 0.8348270000 953699125 0 1784459264 -0.2096582055 0.0229927432 -0.3558668196 556 22.2000000000 0.0121402424 0.0075072312 0.0123625696 0.0094079284 0.8786420000 953700399 0 1783320576 -0.2097812593 0.0229460467 -0.3567521274 557 22.2400000000 0.0114905396 0.0075143825 0.0123625696 0.0094009175 0.8449190000 953701673 0 1782165504 -0.2099139988 0.0220124573 -0.3573839962 558 22.2800000000 0.0115497075 0.0075216143 0.0123625696 0.0093994755 0.8531380000 953702947 0 1783816192 -0.2097053230 0.0215094704 -0.3580160439 559 22.3200000000 0.0116651934 0.0075290268 0.0123625696 0.0094026952 0.8492400000 953704221 0 1782845440 -0.2099204361 0.0210000705 -0.3588604331 560 22.3600000000 0.0117433127 0.0075365523 0.0123625696 0.0094002254 0.8514000000 953705495 0 1784467456 -0.2102371007 0.0210505743 -0.3596080244 561 22.4000000000 0.0116303060 0.0075438495 0.0123625696 0.0093980267 0.8526640000 953706769 0 1783463936 -0.2100392729 0.0205335636 -0.3603117764 562 22.4400000000 0.0115086446 0.0075509043 0.0123625696 0.0093949410 0.9034730000 953708043 0 1781936128 -0.2104745656 0.0200028569 -0.3609223068 563 22.4800000000 0.0115792369 0.0075580595 0.0123625696 0.0093922615 0.8594940000 953709317 0 1783717888 -0.2105400413 0.0194641724 -0.3616046011 564 22.5200000000 0.0115779992 0.0075651870 0.0123625696 0.0093925399 0.8626970000 953710591 0 1782681600 -0.2106308937 0.0193548687 -0.3621284962 565 22.5600000000 0.0115435692 0.0075722284 0.0123625696 0.0093953677 0.8701070000 953711865 0 1784332288 -0.2111400217 0.0185001139 -0.3627717793 566 22.6000000000 0.0115685249 0.0075792890 0.0123625696 0.0093950896 0.8673340000 953713139 0 1783316480 -0.2110477537 0.0182170793 -0.3633020222 567 22.6400000000 0.0116090160 0.0075863961 0.0123625696 0.0093935354 0.8804810000 953714413 0 1782554624 -0.2111451477 0.0177738778 -0.3640841842 568 22.6800000000 0.0115593243 0.0075933907 0.0123625696 0.0093930265 0.8919380000 953715687 0 1784225792 -0.2115334272 0.0171759836 -0.3644104898 569 22.7200000000 0.0119335242 0.0076010183 0.0123625696 0.0093989077 0.8753700000 953716961 0 1783345152 -0.2116848379 0.0164544098 -0.3650274575 570 22.7600000000 0.0119316522 0.0076086159 0.0123625696 0.0094019015 0.8777090000 953718235 0 1782468608 -0.2120151520 0.0160866342 -0.3655463457 571 22.8000000000 0.0121207414 0.0076165181 0.0123625696 0.0094069644 0.8792580000 953719509 0 1784225792 -0.2121197432 0.0148601327 -0.3662676513 572 22.8400000000 0.0122957425 0.0076246985 0.0123625696 0.0094171881 0.8900900000 953720783 0 1783087104 -0.2120939046 0.0149617959 -0.3669529855 573 22.8800000000 0.0121531421 0.0076326016 0.0123625696 0.0094169444 0.8949320000 953722057 0 1782218752 -0.2122247219 0.0146366730 -0.3676847219 574 22.9200000000 0.0120071704 0.0076402228 0.0123625696 0.0094191711 0.9288500000 953723331 0 1783808000 -0.2119169980 0.0139573105 -0.3686700165 575 22.9600000000 0.0118974447 0.0076476267 0.0123625696 0.0094240344 0.8986220000 953724605 0 1782792192 -0.2118309438 0.0134231094 -0.3694705069 576 23.0000000000 0.0119109303 0.0076550282 0.0123625696 0.0094317049 0.9006810000 953725879 0 1784442880 -0.2119613886 0.0125464629 -0.3704269230 577 23.0400000000 0.0117939981 0.0076622015 0.0123625696 0.0094397811 0.9029660000 953727153 0 1783300096 -0.2116509229 0.0116329324 -0.3712736964 578 23.0800000000 0.0116547216 0.0076691090 0.0123625696 0.0094488638 0.9083570000 953728427 0 1782218752 -0.2115515769 0.0107141398 -0.3720346391 579 23.1200000000 0.0114495968 0.0076756383 0.0123625696 0.0094553933 0.9026690000 953729701 0 1783824384 -0.2114951760 0.0100564770 -0.3728405535 580 23.1600000000 0.0113027096 0.0076818919 0.0123625696 0.0094623926 0.9356750000 953730975 0 1782697984 -0.2116075456 0.0095754871 -0.3735357821 581 23.2000000000 0.0109501360 0.0076875171 0.0123625696 0.0094660782 0.9028740000 953732249 0 1784332288 -0.2116853744 0.0090109231 -0.3740013838 582 23.2400000000 0.0108435294 0.0076929398 0.0123625696 0.0094680401 0.9001110000 953733523 0 1783205888 -0.2110681832 0.0086803678 -0.3745824993 583 23.2800000000 0.0112232491 0.0076989952 0.0123625696 0.0094744878 0.9000060000 953734797 0 1782071296 -0.2102677524 0.0083437013 -0.3752514422 584 23.3200000000 0.0108370483 0.0077043686 0.0123625696 0.0094760244 0.9008470000 953736071 0 1783697408 -0.2104877084 0.0074098413 -0.3756552339 585 23.3600000000 0.0109635014 0.0077099397 0.0123625696 0.0094865486 0.9007130000 953737345 0 1782415360 -0.2100279331 0.0067893704 -0.3759325743 586 23.4000000000 0.0113398442 0.0077161341 0.0123625696 0.0095020380 0.8943880000 953738619 0 1784188928 -0.2096400112 0.0065940507 -0.3763486147 587 23.4400000000 0.0111986017 0.0077220668 0.0123625696 0.0095071546 0.8976540000 953739893 0 1783189504 -0.2094590217 0.0062765405 -0.3766825199 588 23.4800000000 0.0111222323 0.0077278494 0.0123625696 0.0095130701 0.8932880000 953741167 0 1782284288 -0.2089498192 0.0057685040 -0.3766090870 589 23.5200000000 0.0112035722 0.0077337504 0.0123625696 0.0095200919 0.9000870000 953742441 0 1784078336 -0.2087542862 0.0055268607 -0.3768891990 590 23.5600000000 0.0111875208 0.0077396043 0.0123625696 0.0095248067 0.8936650000 953743715 0 1783324672 -0.2086374313 0.0052902810 -0.3771526814 591 23.6000000000 0.0108254943 0.0077448257 0.0123625696 0.0095249834 0.8897680000 953744989 0 1782468608 -0.2087065727 0.0042466018 -0.3771019578 592 23.6400000000 0.0110117747 0.0077503442 0.0123625696 0.0095355150 0.9301650000 953746263 0 1784098816 -0.2087182105 0.0034148092 -0.3773267865 593 23.6800000000 0.0110376123 0.0077558877 0.0123625696 0.0095407101 0.8914220000 953747537 0 1783324672 -0.2087305486 0.0030252635 -0.3774129450 594 23.7200000000 0.0109868301 0.0077613270 0.0123625696 0.0095394738 0.8912990000 953748811 0 1782460416 -0.2086482644 0.0027017042 -0.3778061867 595 23.7600000000 0.0109112589 0.0077666210 0.0123625696 0.0095409660 0.8935330000 953750085 0 1784233984 -0.2086352259 0.0019017344 -0.3778895736 596 23.8000000000 0.0110261552 0.0077720900 0.0123625696 0.0095451644 0.8878320000 953751359 0 1783332864 -0.2090943009 0.0013308120 -0.3779695928 597 23.8400000000 0.0111041125 0.0077776713 0.0123625696 0.0095448938 0.8890450000 953752633 0 1782419456 -0.2090543211 0.0010503307 -0.3778976202 598 23.8800000000 0.0110160857 0.0077830867 0.0123625696 0.0095421841 0.8850630000 953753907 0 1784324096 -0.2090993822 0.0006250290 -0.3779511750 599 23.9200000000 0.0106758224 0.0077879160 0.0123625696 0.0095366945 0.8848650000 953755181 0 1783451648 -0.2090316266 -0.0001857988 -0.3778278232 600 23.9600000000 0.0106342444 0.0077926598 0.0123625696 0.0095316287 0.8911660000 953756455 0 1782566912 -0.2088093162 -0.0010845138 -0.3778771758 601 24.0000000000 0.0108116344 0.0077976831 0.0123625696 0.0095285292 0.8826750000 953757729 0 1784360960 -0.2087775767 -0.0020388993 -0.3777615726 602 24.0400000000 0.0108529394 0.0078027583 0.0123625696 0.0095286136 0.8818070000 953759003 0 1783353344 -0.2085893601 -0.0031470496 -0.3776142299 603 24.0800000000 0.0110841794 0.0078082001 0.0123625696 0.0095361377 0.8819790000 953760277 0 1782579200 -0.2083729059 -0.0041426001 -0.3772909045 604 24.1200000000 0.0111023271 0.0078136540 0.0123625696 0.0095397276 0.9153590000 953761551 0 1784221696 -0.2081617117 -0.0046476838 -0.3769266009 605 24.1600000000 0.0112133315 0.0078192733 0.0123625696 0.0095372773 0.8786870000 953762825 0 1783488512 -0.2081948668 -0.0048281709 -0.3767055571 606 24.2000000000 0.0110014481 0.0078245244 0.0123625696 0.0095310899 0.8793470000 953764099 0 1782325248 -0.2079897225 -0.0051961746 -0.3766121268 607 24.2400000000 0.0110098282 0.0078297720 0.0123625696 0.0095244673 0.8714650000 953765373 0 1784061952 -0.2076244205 -0.0055886214 -0.3765231967 608 24.2800000000 0.0109670162 0.0078349319 0.0123625696 0.0095176223 0.8734100000 953766647 0 1783062528 -0.2072028518 -0.0059758583 -0.3764175177 609 24.3200000000 0.0107582081 0.0078397321 0.0123625696 0.0095109232 0.8742470000 953767921 0 1782087680 -0.2077941298 -0.0070128692 -0.3763083518 610 24.3600000000 0.0112583786 0.0078453364 0.0123625696 0.0095100455 0.9105340000 953769195 0 1783717888 -0.2074260563 -0.0076637827 -0.3763702512 611 24.4000000000 0.0112284133 0.0078508733 0.0123625696 0.0095048194 0.8701190000 953770469 0 1782816768 -0.2071230263 -0.0085902289 -0.3760952950 612 24.4400000000 0.0113814473 0.0078566423 0.0123625696 0.0095020179 0.8778780000 953771743 0 1784369152 -0.2069367766 -0.0089367097 -0.3763473928 613 24.4800000000 0.0116828233 0.0078628840 0.0123625696 0.0094968656 0.8685790000 953773017 0 1783361536 -0.2060377449 -0.0083208699 -0.3761749864 614 24.5200000000 0.0117531419 0.0078692199 0.0123625696 0.0094892849 0.8694980000 953774291 0 1782054912 -0.2056724578 -0.0084340917 -0.3758542538 615 24.5600000000 0.0118129505 0.0078756325 0.0123625696 0.0094821583 0.8661670000 953775565 0 1783808000 -0.2058388144 -0.0098167146 -0.3756285906 616 24.6000000000 0.0118209561 0.0078820372 0.0123625696 0.0094802777 0.8668000000 953776839 0 1782792192 -0.2059558779 -0.0114835035 -0.3757739961 617 24.6400000000 0.0118829459 0.0078885217 0.0123625696 0.0094820186 0.8726370000 953778113 0 1784442880 -0.2055984437 -0.0119603304 -0.3757782876 618 24.6800000000 0.0117388302 0.0078947520 0.0123625696 0.0094825580 0.8680070000 953779387 0 1783316480 -0.2051668912 -0.0125396214 -0.3760454953 619 24.7200000000 0.0119824586 0.0079013557 0.0123625696 0.0094951713 0.8649830000 953780661 0 1782218752 -0.2044302225 -0.0128198219 -0.3760476708 620 24.7600000000 0.0122771878 0.0079084135 0.0123625696 0.0095001635 0.8642290000 953781935 0 1783824384 -0.2039135396 -0.0123454975 -0.3765299320 621 24.8000000000 0.0119100930 0.0079148574 0.0123625696 0.0094934075 0.8679670000 953783209 0 1782571008 -0.2033514827 -0.0120863896 -0.3769226968 622 24.8400000000 0.0118160006 0.0079211293 0.0123625696 0.0094857959 0.9026100000 953784483 0 1784348672 -0.2022114843 -0.0125547564 -0.3768919408 623 24.8800000000 0.0118651772 0.0079274601 0.0123625696 0.0094784036 0.8681910000 953785757 0 1783205888 -0.2013212889 -0.0129921865 -0.3767841756 624 24.9200000000 0.0119221052 0.0079338617 0.0123625696 0.0094712331 0.8650370000 953787031 0 1781776384 -0.2006408423 -0.0137757175 -0.3768956065 625 24.9600000000 0.0118300365 0.0079400956 0.0123625696 0.0094656956 0.8622100000 953788305 0 1783300096 -0.1995216310 -0.0136492867 -0.3770603538 626 25.0000000000 0.0120506659 0.0079466620 0.0123625696 0.0094583189 0.8624240000 953789579 0 1782349824 -0.1981282085 -0.0134836864 -0.3767888248 627 25.0400000000 0.0120965773 0.0079532807 0.0123625696 0.0094508446 0.8618970000 953790853 0 1783840768 -0.1968565732 -0.0142603740 -0.3766207695 628 25.0800000000 0.0122797675 0.0079601700 0.0123625696 0.0094463402 0.9009490000 953792127 0 1782824960 -0.1954063028 -0.0141334878 -0.3766078055 629 25.1200000000 0.0124894269 0.0079673708 0.0124894269 0.0094398691 0.8674570000 953793401 0 1784459264 -0.1936340630 -0.0129291108 -0.3769296408 630 25.1600000000 0.0122053362 0.0079740977 0.0124894269 0.0094364981 0.8650460000 953794675 0 1783332864 -0.1925175190 -0.0128984042 -0.3767219782 631 25.2000000000 0.0120235924 0.0079805153 0.0124894269 0.0094302185 0.8647940000 953795949 0 1782091776 -0.1908323169 -0.0133925183 -0.3764903247 632 25.2400000000 0.0121734003 0.0079871496 0.0124894269 0.0094227818 0.8650920000 953797223 0 1783681024 -0.1891526282 -0.0135330688 -0.3763230443 633 25.2800000000 0.0124631142 0.0079942206 0.0124894269 0.0094153844 0.8658210000 953798497 0 1782665216 -0.1875157058 -0.0127087198 -0.3761747479 634 25.3200000000 0.0123288594 0.0080010576 0.0124894269 0.0094097338 0.8718860000 953799771 0 1784197120 -0.1856310815 -0.0127151068 -0.3756261170 635 25.3600000000 0.0122970389 0.0080078229 0.0124894269 0.0094044553 0.8724500000 953801045 0 1782960128 -0.1835924536 -0.0130387265 -0.3749126196 636 25.4000000000 0.0125002284 0.0080148864 0.0125002284 0.0093982543 0.8753410000 953802319 0 1784594432 -0.1816893816 -0.0130118942 -0.3748539984 637 25.4400000000 0.0124599962 0.0080218646 0.0125002284 0.0093924734 0.8879440000 953803593 0 1783595008 -0.1795139015 -0.0127916439 -0.3745501637 638 25.4800000000 0.0123307835 0.0080286184 0.0125002284 0.0093885727 0.8754560000 953804867 0 1782210560 -0.1777751893 -0.0136506464 -0.3739427924 639 25.5200000000 0.0124900164 0.0080356003 0.0125002284 0.0093812900 0.8656660000 953806141 0 1783840768 -0.1754900515 -0.0137868077 -0.3738665283 640 25.5600000000 0.0125670014 0.0080426806 0.0125670014 0.0093743525 0.9118630000 953807415 0 1782820864 -0.1731131226 -0.0135212308 -0.3733460903 641 25.6000000000 0.0125532169 0.0080497173 0.0125670014 0.0093675907 0.8677320000 953808689 0 1784442880 -0.1703741550 -0.0130868796 -0.3728472888 642 25.6400000000 0.0124973282 0.0080566450 0.0125670014 0.0093622817 0.8690350000 953809963 0 1783300096 -0.1682024151 -0.0134621067 -0.3725008368 643 25.6800000000 0.0126487995 0.0080637868 0.0126487995 0.0093550123 0.8773280000 953811237 0 1782157312 -0.1657064408 -0.0130271958 -0.3723950982 644 25.7200000000 0.0125639858 0.0080707747 0.0126487995 0.0093485156 0.8647100000 953812511 0 1783824384 -0.1632582396 -0.0131846182 -0.3717285395 645 25.7600000000 0.0125143798 0.0080776640 0.0126487995 0.0093413546 0.8675540000 953813785 0 1782820864 -0.1607158482 -0.0138008362 -0.3710906804 646 25.8000000000 0.0127244489 0.0080848572 0.0127244489 0.0093359279 0.8962710000 953815059 0 1784459264 -0.1581949145 -0.0135704512 -0.3706368208 647 25.8400000000 0.0127288727 0.0080920349 0.0127288727 0.0093287081 0.8778130000 953816333 0 1783312384 -0.1555374116 -0.0131398616 -0.3699190915 648 25.8800000000 0.0126195792 0.0080990219 0.0127288727 0.0093224588 0.8660880000 953817607 0 1782218752 -0.1533349454 -0.0135814818 -0.3690384030 649 25.9200000000 0.0126269581 0.0081059987 0.0127288727 0.0093152766 0.8655940000 953818881 0 1783934976 -0.1507550478 -0.0139975147 -0.3686155081 650 25.9600000000 0.0127401697 0.0081131282 0.0127401697 0.0093086054 0.8669700000 953820155 0 1782919168 -0.1481515169 -0.0136787035 -0.3680866361 651 26.0000000000 0.0127802780 0.0081202974 0.0127802780 0.0093014609 0.8704020000 953821429 0 1784569856 -0.1456431448 -0.0131808240 -0.3675475121 652 26.0400000000 0.0127197159 0.0081273517 0.0127802780 0.0092944969 0.8659550000 953822703 0 1783476224 -0.1432350874 -0.0129526742 -0.3675659299 653 26.0800000000 0.0127083259 0.0081343670 0.0127802780 0.0092874826 0.8633280000 953823977 0 1782329344 -0.1409853101 -0.0131458975 -0.3674064577 654 26.1200000000 0.0126327630 0.0081412452 0.0127802780 0.0092811681 0.8639270000 953825251 0 1783951360 -0.1358352751 -0.0124828266 -0.3666045666 655 26.1600000000 0.0126148332 0.0081480752 0.0127802780 0.0092742370 0.8652880000 953826525 0 1782837248 -0.1332939416 -0.0129605532 -0.3655609488 656 26.2000000000 0.0127541870 0.0081550967 0.0127802780 0.0092674934 0.8606360000 953827799 0 1784475648 -0.1304346472 -0.0126873087 -0.3646438420 657 26.2400000000 0.0127516203 0.0081620929 0.0127802780 0.0092604736 0.8757120000 953829073 0 1783427072 -0.1277395487 -0.0127598364 -0.3635516763 658 26.2800000000 0.0127960769 0.0081691354 0.0127960769 0.0092535393 0.8978160000 953830347 0 1782157312 -0.1250863373 -0.0129673788 -0.3627506793 659 26.3200000000 0.0129692713 0.0081764194 0.0129692713 0.0092474144 0.8584300000 953831621 0 1783808000 -0.1224587113 -0.0126736751 -0.3624764681 660 26.3600000000 0.0128165241 0.0081834499 0.0129692713 0.0092403974 0.8610570000 953832895 0 1782697984 -0.1199329421 -0.0129545480 -0.3617738187 661 26.4000000000 0.0128029790 0.0081904386 0.0129692713 0.0092338955 0.8612040000 953834169 0 1784221696 -0.1170980036 -0.0132741472 -0.3607045710 662 26.4400000000 0.0128811384 0.0081975242 0.0129692713 0.0092283471 0.8611550000 953835443 0 1783222272 -0.1143416911 -0.0131843518 -0.3599813282 663 26.4800000000 0.0127183795 0.0082043430 0.0129692713 0.0092213881 0.8649560000 953836717 0 1782091776 -0.1118453518 -0.0135820471 -0.3594323099 664 26.5200000000 0.0126013299 0.0082109650 0.0129692713 0.0092148049 0.8895260000 953837991 0 1783697408 -0.1095029265 -0.0146067096 -0.3587445915 665 26.5600000000 0.0125771994 0.0082175307 0.0129692713 0.0092101599 0.8592310000 953839265 0 1782444032 -0.1073308140 -0.0161768533 -0.3584086597 666 26.6000000000 0.0127202179 0.0082242915 0.0129692713 0.0092101157 0.8570640000 953840539 0 1783934976 -0.1048104912 -0.0169470329 -0.3580164313 667 26.6400000000 0.0127429301 0.0082310661 0.0129692713 0.0092085377 0.8552710000 953841813 0 1782665216 -0.1023802087 -0.0176471546 -0.3577785492 668 26.6800000000 0.0126959663 0.0082377501 0.0129692713 0.0092045776 0.8638660000 953843087 0 1784221696 -0.0999816209 -0.0182408728 -0.3573624492 669 26.7200000000 0.0126127657 0.0082442897 0.0129692713 0.0091997798 0.8615800000 953844361 0 1783078912 -0.0976951718 -0.0192371346 -0.3573117852 670 26.7600000000 0.0126613574 0.0082508823 0.0129692713 0.0091993033 0.8905290000 953845635 0 1784586240 -0.0953516290 -0.0196946859 -0.3575305343 671 26.8000000000 0.0127191311 0.0082575414 0.0129692713 0.0091959694 0.8627780000 953846909 0 1783349248 -0.0928109512 -0.0194759127 -0.3579988480 672 26.8400000000 0.0125780115 0.0082639707 0.0129692713 0.0091894842 0.8626250000 953848183 0 1782071296 -0.0905331895 -0.0206268579 -0.3581826091 673 26.8800000000 0.0126640340 0.0082705087 0.0129692713 0.0091915153 0.8600920000 953849457 0 1783713792 -0.0880506709 -0.0215250868 -0.3584100306 674 26.9200000000 0.0128927436 0.0082773666 0.0129692713 0.0091986784 0.8709320000 953850731 0 1782419456 -0.0853066221 -0.0210861024 -0.3587444723 675 26.9600000000 0.0128485272 0.0082841387 0.0129692713 0.0091942797 0.8643040000 953852005 0 1784070144 -0.0826825798 -0.0210100040 -0.3596003056 676 27.0000000000 0.0126720201 0.0082906296 0.0129692713 0.0091880751 0.8621710000 953853279 0 1783099392 -0.0802420229 -0.0221573748 -0.3597939014 677 27.0400000000 0.0127617288 0.0082972339 0.0129692713 0.0091848674 0.8657360000 953854553 0 1781948416 -0.0775258616 -0.0223229639 -0.3608384430 678 27.0800000000 0.0127483895 0.0083037990 0.0129692713 0.0091803121 0.8645890000 953855827 0 1783853056 -0.0748534799 -0.0226259548 -0.3615075648 679 27.1200000000 0.0127734356 0.0083103817 0.0129692713 0.0091773665 0.8630260000 953857101 0 1782566912 -0.0723887756 -0.0230923835 -0.3623736501 680 27.1600000000 0.0128967781 0.0083171264 0.0129692713 0.0091760103 0.8693400000 953858375 0 1784459264 -0.0695877075 -0.0228414312 -0.3636211753 681 27.2000000000 0.0128473761 0.0083237788 0.0129692713 0.0091696925 0.8595770000 953859649 0 1783234560 -0.0669039935 -0.0228753164 -0.3646777868 682 27.2400000000 0.0128408335 0.0083304020 0.0129692713 0.0091635769 0.9007990000 953860923 0 1782411264 -0.0642701909 -0.0231438149 -0.3660781980 683 27.2800000000 0.0128573934 0.0083370301 0.0129692713 0.0091585013 0.8593910000 953862197 0 1784188928 -0.0614719614 -0.0232080054 -0.3674394488 684 27.3200000000 0.0128315538 0.0083436011 0.0129692713 0.0091519546 0.8597530000 953863471 0 1783173120 -0.0587156974 -0.0233437978 -0.3692086637 685 27.3600000000 0.0125943990 0.0083498066 0.0129692713 0.0091453171 0.8624580000 953864745 0 1782198272 -0.0561870039 -0.0249790400 -0.3705543578 686 27.4000000000 0.0126470644 0.0083560708 0.0129692713 0.0091445174 0.8673190000 953866019 0 1783824384 -0.0536056682 -0.0259490311 -0.3723541200 687 27.4400000000 0.0127096428 0.0083624079 0.0129692713 0.0091464786 0.8613730000 953867293 0 1782812672 -0.0506600030 -0.0259535648 -0.3744705319 688 27.4800000000 0.0127090709 0.0083687257 0.0129692713 0.0091471893 0.9040630000 953868567 0 1784479744 -0.0476470403 -0.0260193683 -0.3765448928 689 27.5200000000 0.0126513345 0.0083749414 0.0129692713 0.0091480123 0.8639260000 953869841 0 1783459840 -0.0448876731 -0.0263347104 -0.3786515296 690 27.5600000000 0.0121781798 0.0083804534 0.0129692713 0.0091541259 0.8813190000 953871115 0 1782665216 -0.0418156944 -0.0249378271 -0.3816183507 691 27.6000000000 0.0124800205 0.0083863862 0.0129692713 0.0091475498 0.8618170000 953872389 0 1784569856 -0.0383813530 -0.0244030301 -0.3834726810 692 27.6400000000 0.0123447012 0.0083921063 0.0129692713 0.0091443538 0.8602140000 953873663 0 1783443456 -0.0352743156 -0.0241347365 -0.3858241439 693 27.6800000000 0.0123067033 0.0083977550 0.0129692713 0.0091406790 0.8565400000 953874937 0 1782571008 -0.0323610716 -0.0248725768 -0.3878621161 694 27.7200000000 0.0123266708 0.0084034163 0.0129692713 0.0091340823 0.8920100000 953876211 0 1784221696 -0.0293838251 -0.0252136160 -0.3901593983 695 27.7600000000 0.0122972289 0.0084090189 0.0129692713 0.0091277364 0.8545420000 953877485 0 1783328768 -0.0263914540 -0.0257049296 -0.3920779526 696 27.8000000000 0.0122841662 0.0084145866 0.0129692713 0.0091232556 0.8514340000 953878759 0 1782460416 -0.0235265493 -0.0260788668 -0.3936977386 697 27.8400000000 0.0119460784 0.0084196534 0.0129692713 0.0091215330 0.8777720000 953880033 0 1784098816 -0.0180284698 -0.0247233640 -0.3992161453 698 27.8800000000 0.0121734543 0.0084250313 0.0129692713 0.0091150762 0.8640790000 953881307 0 1783189504 -0.0154123697 -0.0261480268 -0.4004043043 699 27.9200000000 0.0118723474 0.0084299631 0.0129692713 0.0091347384 0.8703260000 953882581 0 1782284288 -0.0110319043 -0.0260076709 -0.4050111175 700 27.9600000000 0.0121494932 0.0084352767 0.0129692713 0.0091289763 0.8542700000 953883855 0 1784188928 -0.0086957766 -0.0270508267 -0.4063640237 701 28.0000000000 0.0121748252 0.0084406113 0.0129692713 0.0091256758 0.8605870000 953885129 0 1783324672 -0.0065259193 -0.0281032231 -0.4076068401 702 28.0400000000 0.0122456709 0.0084460316 0.0129692713 0.0091307461 0.8578320000 953886403 0 1782579200 -0.0045025842 -0.0290991459 -0.4089621603 703 28.0800000000 0.0124465963 0.0084517223 0.0129692713 0.0091490558 0.8648070000 953887677 0 1784352768 -0.0023404856 -0.0291203558 -0.4109230638 704 28.1200000000 0.0124538280 0.0084574071 0.0129692713 0.0091555667 0.8593930000 953888951 0 1783472128 -0.0000308921 -0.0290691722 -0.4126289487 705 28.1600000000 0.0123275891 0.0084628967 0.0129692713 0.0091558742 0.8584050000 953890225 0 1782808576 0.0018847684 -0.0297936611 -0.4140318036 706 28.2000000000 0.0123932930 0.0084684639 0.0129692713 0.0091618448 0.8916410000 953891499 0 1784459264 0.0039696116 -0.0303088482 -0.4154618680 707 28.2400000000 0.0125041381 0.0084741720 0.0129692713 0.0091665712 0.8621090000 953892773 0 1783332864 0.0063887998 -0.0296613257 -0.4170223475 708 28.2800000000 0.0123766996 0.0084796841 0.0129692713 0.0091602805 0.8669320000 953894047 0 1782538240 0.0089007225 -0.0292755142 -0.4185898006 709 28.3200000000 0.0121776816 0.0084848999 0.0129692713 0.0091538852 0.8615210000 953895321 0 1784229888 0.0110516576 -0.0300522149 -0.4194768071 710 28.3600000000 0.0123518202 0.0084903462 0.0129692713 0.0091515387 0.8582370000 953896595 0 1783480320 0.0133543247 -0.0306867082 -0.4203812778 711 28.4000000000 0.0125426520 0.0084960457 0.0129692713 0.0091493582 0.8603990000 953897869 0 1782824960 0.0159146190 -0.0303125400 -0.4216716886 712 28.4400000000 0.0123306476 0.0085014314 0.0129692713 0.0091429284 0.9003480000 953899143 0 1784377344 0.0181983057 -0.0308874734 -0.4222927690 713 28.4800000000 0.0122875003 0.0085067414 0.0129692713 0.0091375528 0.8612270000 953900417 0 1783336960 0.0204654187 -0.0316554159 -0.4227861762 714 28.5200000000 0.0125079239 0.0085123453 0.0129692713 0.0091356881 0.8668880000 953901691 0 1782349824 0.0230627917 -0.0314899571 -0.4236156940 715 28.5600000000 0.0126288366 0.0085181026 0.0129692713 0.0091302254 0.8565440000 953902965 0 1783959552 0.0259670112 -0.0306528062 -0.4244121015 716 28.6000000000 0.0125438096 0.0085237251 0.0129692713 0.0091251474 0.8596870000 953904239 0 1783308288 0.0287614148 -0.0300946757 -0.4248351157 717 28.6400000000 0.0124090388 0.0085291440 0.0129692713 0.0091217320 0.8567810000 953905513 0 1782304768 0.0315046906 -0.0301949475 -0.4251727462 718 28.6800000000 0.0124730067 0.0085346368 0.0129692713 0.0091157127 0.8899960000 953906787 0 1784209408 0.0341907963 -0.0304014832 -0.4252409637 719 28.7200000000 0.0125105958 0.0085401667 0.0129692713 0.0091093775 0.8561470000 953908061 0 1782960128 0.0370166525 -0.0307901744 -0.4249933362 720 28.7600000000 0.0126572140 0.0085458848 0.0129692713 0.0091058667 0.8619980000 953909335 0 1781960704 0.0400932357 -0.0312067475 -0.4245520532 721 28.8000000000 0.0116567221 0.0085501994 0.0129692713 0.0091093630 0.8694220000 953910609 0 1783586816 0.0438266583 -0.0285691116 -0.4240254462 722 28.8400000000 0.0125445658 0.0085557318 0.0129692713 0.0091031805 0.8640540000 953911883 0 1782558720 0.0469798632 -0.0294156075 -0.4238955379 723 28.8800000000 0.0127343852 0.0085615114 0.0129692713 0.0090971666 0.8532500000 953913157 0 1784315904 0.0502679832 -0.0294558350 -0.4233872294 724 28.9200000000 0.0127346283 0.0085672753 0.0129692713 0.0090909648 0.8518440000 953914431 0 1783189504 0.0536437146 -0.0292461179 -0.4226033986 725 28.9600000000 0.0127481539 0.0085730421 0.0129692713 0.0090847991 0.8554140000 953915705 0 1782177792 0.0572214350 -0.0292177964 -0.4216497242 726 29.0000000000 0.0127236722 0.0085787592 0.0129692713 0.0090798504 0.8497840000 953916979 0 1783861248 0.0605446659 -0.0292803310 -0.4207597077 727 29.0400000000 0.0117116347 0.0085830685 0.0129692713 0.0090822959 0.8712310000 953918253 0 1782833152 0.0649884492 -0.0268835835 -0.4190770686 728 29.0800000000 0.0126639009 0.0085886741 0.0129692713 0.0090764295 0.8498720000 953919527 0 1784475648 0.0683702081 -0.0274481438 -0.4185613990 729 29.1200000000 0.0127481408 0.0085943798 0.0129692713 0.0090702097 0.8533100000 953920801 0 1783472128 0.0716454610 -0.0281012077 -0.4174666703 730 29.1600000000 0.0117400410 0.0085986889 0.0129692713 0.0090754662 0.9068390000 953922075 0 1782411264 0.0756146461 -0.0267940350 -0.4155607224 731 29.2000000000 0.0117316069 0.0086029747 0.0129692713 0.0090799912 0.8761000000 953923349 0 1784061952 0.0795433521 -0.0261910614 -0.4140705168 732 29.2400000000 0.0127999457 0.0086087083 0.0129692713 0.0090769589 0.8585570000 953924623 0 1783062528 0.0824337751 -0.0273995213 -0.4135343432 733 29.2800000000 0.0117799202 0.0086130346 0.0129692713 0.0090755339 0.8762230000 953925897 0 1782087680 0.0864531547 -0.0255684294 -0.4121365845 734 29.3200000000 0.0117497928 0.0086173081 0.0129692713 0.0090708134 0.8755100000 953927171 0 1783734272 0.0899967998 -0.0252588876 -0.4109471738 735 29.3600000000 0.0125210769 0.0086226194 0.0129692713 0.0090647452 0.8588090000 953928445 0 1782669312 0.0925811753 -0.0264908373 -0.4104282260 736 29.4000000000 0.0127020571 0.0086281621 0.0129692713 0.0090586390 0.8908840000 953929719 0 1784369152 0.0954085141 -0.0270767473 -0.4094051421 737 29.4400000000 0.0129017914 0.0086339608 0.0129692713 0.0090541717 0.8629950000 953930993 0 1783361536 0.0982478112 -0.0273590703 -0.4084686935 738 29.4800000000 0.0118437316 0.0086383100 0.0129692713 0.0090511119 0.8778140000 953932267 0 1782308864 0.1019525900 -0.0254894234 -0.4068498015 739 29.5200000000 0.0124805886 0.0086435093 0.0129692713 0.0090450596 0.8587630000 953933541 0 1783934976 0.1041283160 -0.0269743558 -0.4061077237 740 29.5600000000 0.0127387820 0.0086490435 0.0129692713 0.0090423368 0.8602970000 953934815 0 1782919168 0.1064787656 -0.0281548705 -0.4049699605 741 29.6000000000 0.0130520938 0.0086549855 0.0130520938 0.0090493683 0.8605570000 953936089 0 1784623104 0.1087326705 -0.0287268441 -0.4039654732 742 29.6400000000 0.0132129090 0.0086611283 0.0132129090 0.0090517077 0.8917930000 953937363 0 1783619584 0.1113494784 -0.0286083259 -0.4031305015 743 29.6800000000 0.0131479995 0.0086671671 0.0132129090 0.0090488250 0.8667200000 953938637 0 1782308864 0.1137943938 -0.0283582620 -0.4022365510 744 29.7200000000 0.0130115962 0.0086730064 0.0132129090 0.0090438992 0.8624500000 953939911 0 1784078336 0.1161072329 -0.0283615831 -0.4012780786 745 29.7600000000 0.0132042859 0.0086790887 0.0132129090 0.0090399977 0.8613600000 953941185 0 1783091200 0.1186059117 -0.0278499573 -0.4004541039 746 29.8000000000 0.0129624140 0.0086848304 0.0132129090 0.0090360034 0.8588360000 953942459 0 1784733696 0.1210558191 -0.0268691778 -0.3997602463 747 29.8400000000 0.0125335176 0.0086899826 0.0132129090 0.0090358428 0.8615110000 953943733 0 1783554048 0.1229062155 -0.0272320695 -0.3986849487 748 29.8800000000 0.0132478289 0.0086960760 0.0132478289 0.0090432805 0.8713380000 953945007 0 1782411264 0.1257870793 -0.0280283187 -0.3978335261 749 29.9200000000 0.0131688006 0.0087020476 0.0132478289 0.0090373794 0.8639850000 953946281 0 1784119296 0.1283366829 -0.0274791885 -0.3967452645 750 29.9600000000 0.0130206970 0.0087078058 0.0132478289 0.0090318015 0.8629840000 953947555 0 1783078912 0.1303778291 -0.0272233244 -0.3958076537 751 30.0000000000 0.0131439324 0.0087137127 0.0132478289 0.0090258343 0.8628060000 953948829 0 1782067200 0.1324254274 -0.0268040188 -0.3951992095 752 30.0400000000 0.0130485948 0.0087194772 0.0132478289 0.0090222423 0.8628830000 953950103 0 1783721984 0.1343815327 -0.0261475220 -0.3947650492 753 30.0800000000 0.0128540853 0.0087249680 0.0132478289 0.0090191653 0.8741280000 953951377 0 1782714368 0.1359903365 -0.0262504052 -0.3943496346 754 30.1200000000 0.0130930617 0.0087307613 0.0132478289 0.0090132072 0.9128550000 953952651 0 1784373248 0.1378096789 -0.0263001360 -0.3940815926 755 30.1600000000 0.0130218482 0.0087364448 0.0132478289 0.0090078685 0.8623370000 953953925 0 1783308288 0.1394300014 -0.0262218174 -0.3937461674 756 30.2000000000 0.0129171712 0.0087419749 0.0132478289 0.0090019818 0.8656270000 953955199 0 1782181888 0.1408161074 -0.0269685257 -0.3931502402 757 30.2400000000 0.0131700486 0.0087478244 0.0132478289 0.0090022606 0.8608930000 953956473 0 1783943168 0.1423344016 -0.0281180143 -0.3925706744 758 30.2800000000 0.0136740180 0.0087543233 0.0136740180 0.0090189435 0.8662230000 953957747 0 1782943744 0.1440676004 -0.0286370963 -0.3924724758 759 30.3200000000 0.0123967137 0.0087591223 0.0136740180 0.0090365372 0.8831170000 953959021 0 1784496128 0.1467324644 -0.0263014417 -0.3921034932 760 30.3600000000 0.0132452697 0.0087650251 0.0136740180 0.0090385899 0.9124440000 953960295 0 1783619584 0.1484107375 -0.0278804842 -0.3917079568 761 30.4000000000 0.0136195840 0.0087714043 0.0136740180 0.0090467946 0.8693660000 953961569 0 1782308864 0.1504052281 -0.0287427884 -0.3914459944 762 30.4400000000 0.0139737492 0.0087782315 0.0139737492 0.0090618455 0.8676000000 953962843 0 1784078336 0.1525090486 -0.0291018542 -0.3910059035 763 30.4800000000 0.0125622852 0.0087831909 0.0139737492 0.0090773899 0.8955660000 953964117 0 1782964224 0.1555493772 -0.0267138463 -0.3906945288 764 30.5200000000 0.0134702213 0.0087893258 0.0139737492 0.0090831306 0.8740140000 953965391 0 1781903360 0.1574697942 -0.0284248088 -0.3905066252 765 30.5600000000 0.0139905708 0.0087961248 0.0139905708 0.0090991350 0.8798770000 953966665 0 1783681024 0.1595271826 -0.0292862784 -0.3903229833 766 30.6000000000 0.0126891490 0.0088012071 0.0139905708 0.0091197332 0.8972830000 953967939 0 1782665216 0.1625891030 -0.0266149361 -0.3901915252 767 30.6400000000 0.0136081567 0.0088074743 0.0139905708 0.0091184764 0.8745230000 953969213 0 1784348672 0.1648423076 -0.0275648292 -0.3903273046 768 30.6800000000 0.0137643656 0.0088139286 0.0139905708 0.0091162866 0.8790050000 953970487 0 1783345152 0.1671061963 -0.0280644372 -0.3901592195 769 30.7200000000 0.0141460160 0.0088208624 0.0141460160 0.0091175182 0.8793960000 953971761 0 1781944320 0.1694753915 -0.0280733630 -0.3903276622 770 30.7600000000 0.0141183631 0.0088277423 0.0141460160 0.0091135856 0.8773150000 953973035 0 1783734272 0.1717884988 -0.0274743121 -0.3905704021 771 30.8000000000 0.0136921275 0.0088340514 0.0141460160 0.0091079756 0.8841600000 953974309 0 1782562816 0.1739704162 -0.0275456607 -0.3905543983 772 30.8400000000 0.0140628107 0.0088408244 0.0141460160 0.0091105987 0.9185590000 953975583 0 1784221696 0.1759791821 -0.0281448159 -0.3905749023 773 30.8800000000 0.0143312514 0.0088479272 0.0143312514 0.0091100436 0.8779560000 953976857 0 1783201792 0.1784803122 -0.0279373769 -0.3905879259 774 30.9200000000 0.0141857276 0.0088548236 0.0143312514 0.0091046353 0.8828990000 953978131 0 1782030336 0.1806424409 -0.0276409294 -0.3906303048 775 30.9600000000 0.0142770121 0.0088618200 0.0143312514 0.0090988956 0.8794630000 953979405 0 1783681024 0.1825487167 -0.0273651090 -0.3908178806 776 31.0000000000 0.0140576018 0.0088685155 0.0143312514 0.0090958875 0.8844540000 953980679 0 1782665216 0.1844471693 -0.0269036721 -0.3909417391 777 31.0400000000 0.0139911696 0.0088751084 0.0143312514 0.0090918059 0.8775670000 953981953 0 1784348672 0.1860456020 -0.0269186124 -0.3910161853 778 31.0800000000 0.0143815447 0.0088821861 0.0143815447 0.0090866499 0.9153650000 953983227 0 1783205888 0.1877308935 -0.0263495520 -0.3916050792 779 31.1200000000 0.0140731735 0.0088888497 0.0143815447 0.0090968041 0.8776580000 953984501 0 1781944320 0.1892077327 -0.0250133164 -0.3922284245 780 31.1600000000 0.0135842273 0.0088948695 0.0143815447 0.0091296254 0.8727940000 953985775 0 1783443456 0.1904736757 -0.0239364691 -0.3924721479 781 31.2000000000 0.0134820780 0.0089007430 0.0143815447 0.0091643147 0.8764640000 953987049 0 1782349824 0.1917108595 -0.0235575363 -0.3926759660 782 31.2400000000 0.0135362307 0.0089066707 0.0143815447 0.0091969086 0.8782830000 953988323 0 1783951360 0.1928391010 -0.0232632197 -0.3928164840 783 31.2800000000 0.0134063689 0.0089124174 0.0143815447 0.0092275080 0.8714480000 953989597 0 1782792192 0.1935594082 -0.0231307540 -0.3931459486 784 31.3200000000 0.0133868828 0.0089181247 0.0143815447 0.0092431481 0.8686830000 953990871 0 1784442880 0.1941499710 -0.0233936459 -0.3933378458 785 31.3600000000 0.0135919489 0.0089240786 0.0143815447 0.0092415811 0.8702960000 953992145 0 1783173120 0.1947879344 -0.0239985660 -0.3934287429 786 31.4000000000 0.0139645534 0.0089304914 0.0143815447 0.0092360392 0.8651850000 953993419 0 1781833728 0.1956992745 -0.0238196608 -0.3938162327 787 31.4400000000 0.0138222082 0.0089367071 0.0143815447 0.0092362064 0.8665230000 953994693 0 1783443456 0.1966093779 -0.0229481626 -0.3940774202 788 31.4800000000 0.0136402976 0.0089426761 0.0143815447 0.0092388623 0.8724130000 953995967 0 1782341632 0.1972942948 -0.0222409461 -0.3943252861 789 31.5200000000 0.0136549976 0.0089486486 0.0143815447 0.0092430691 0.8644560000 953997241 0 1783848960 0.1981864423 -0.0212374944 -0.3947028220 790 31.5600000000 0.0132767102 0.0089541272 0.0143815447 0.0092717986 0.9033310000 953998515 0 1782706176 0.1989257336 -0.0198942963 -0.3949163258 791 31.6000000000 0.0130191799 0.0089592663 0.0143815447 0.0093058866 0.8614430000 953999789 0 1784197120 0.1997344345 -0.0193019994 -0.3950702250 792 31.6400000000 0.0131504973 0.0089645582 0.0143815447 0.0093180737 0.8576710000 954001063 0 1782927360 0.2007328868 -0.0190242548 -0.3949709833 793 31.6800000000 0.0132881058 0.0089700104 0.0143815447 0.0093282988 0.8604080000 954002337 0 1784451072 0.2018047720 -0.0183413755 -0.3948276639 794 31.7200000000 0.0132517992 0.0089754031 0.0143815447 0.0093503476 0.8558880000 954003611 0 1783332864 0.2028750926 -0.0172234960 -0.3947029710 795 31.7600000000 0.0130944736 0.0089805843 0.0143815447 0.0093791666 0.8525680000 954004885 0 1781833728 0.2035669833 -0.0164293144 -0.3943684697 796 31.8000000000 0.0130779343 0.0089857317 0.0143815447 0.0094126436 0.8833750000 954006159 0 1783312384 0.2042894363 -0.0155198462 -0.3941124380 797 31.8400000000 0.0129291136 0.0089906795 0.0143815447 0.0094927643 0.8444500000 954007433 0 1782222848 0.2052383721 -0.0142897405 -0.3936977386 798 31.8800000000 0.0129011450 0.0089955798 0.0143815447 0.0095940579 0.8377350000 954008707 0 1783697408 0.2057268322 -0.0137944007 -0.3933654726 799 31.9200000000 0.0129636293 0.0090005461 0.0143815447 0.0096495491 0.8417010000 954009981 0 1782411264 0.2061364949 -0.0136952009 -0.3930993080 800 31.9600000000 0.0130897705 0.0090056576 0.0143815447 0.0096696294 0.8315580000 954011255 0 1783934976 0.2067997456 -0.0136226434 -0.3927795589 801 32.0000000000 0.0131855551 0.0090108760 0.0143815447 0.0096729391 0.8330050000 954012529 0 1782697984 0.2076248676 -0.0135021042 -0.3921711445 802 32.0400000000 0.0132485544 0.0090161599 0.0143815447 0.0096755096 0.8558050000 954013803 0 1784332288 0.2086237073 -0.0132812755 -0.3915500939 803 32.0800000000 0.0134017598 0.0090216214 0.0143815447 0.0096741147 0.8295210000 954015077 0 1783349248 0.2096480876 -0.0130109219 -0.3909483552 804 32.1199999990 0.0134638622 0.0090271466 0.0143815447 0.0096731989 0.8313000000 954016351 0 1781952512 0.2104880810 -0.0128071858 -0.3901294768 805 32.1600000000 0.0135143651 0.0090327207 0.0143815447 0.0096741761 0.8339280000 954017625 0 1783554048 0.2112553120 -0.0125793200 -0.3895221949 806 32.2000000000 0.0135377496 0.0090383101 0.0143815447 0.0096734650 0.8325080000 954018899 0 1782411264 0.2119952440 -0.0126212956 -0.3887398839 807 32.2400000000 0.0136301694 0.0090440001 0.0143815447 0.0096685413 0.8303320000 954020173 0 1784078336 0.2128088921 -0.0126449289 -0.3881447613 808 32.2800000000 0.0136782723 0.0090497356 0.0143815447 0.0096633962 0.8715570000 954021447 0 1782951936 0.2134739012 -0.0124710901 -0.3874557614 809 32.3200000000 0.0136496434 0.0090554216 0.0143815447 0.0096595477 0.8274710000 954022721 0 1784586240 0.2142083794 -0.0123018771 -0.3868036568 810 32.3600000000 0.0136794327 0.0090611302 0.0143815447 0.0096561673 0.8287050000 954023995 0 1783222272 0.2149540782 -0.0124262143 -0.3858371973 811 32.4000000000 0.0137788001 0.0090669473 0.0143815447 0.0096505020 0.8368860000 954025269 0 1782071296 0.2158279568 -0.0126276435 -0.3848962486 812 32.4399999990 0.0139441099 0.0090729537 0.0143815447 0.0096447826 0.8348060000 954026543 0 1783681024 0.2168141007 -0.0129252998 -0.3837569356 813 32.4800000000 0.0140235517 0.0090790430 0.0143815447 0.0096396140 0.8322490000 954027817 0 1782538240 0.2178466916 -0.0129026929 -0.3828500211 814 32.5200000000 0.0140648130 0.0090851680 0.0143815447 0.0096366888 0.8306740000 954029091 0 1784221696 0.2186505198 -0.0131424107 -0.3817433417 815 32.5600000000 0.0141742574 0.0090914123 0.0143815447 0.0096384827 0.8351960000 954030365 0 1783078912 0.2195076197 -0.0133750942 -0.3806071579 816 32.6000000000 0.0142404921 0.0090977224 0.0143815447 0.0096411029 0.8345690000 954031639 0 1784586240 0.2203910649 -0.0132350763 -0.3796669841 817 32.6400000000 0.0142128179 0.0091039832 0.0143815447 0.0096433350 0.8425300000 954032913 0 1783332864 0.2211531997 -0.0132876774 -0.3785465062 818 32.6800000000 0.0141585739 0.0091101624 0.0143815447 0.0096469357 0.8381560000 954034187 0 1781903360 0.2217968851 -0.0132132173 -0.3775311112 819 32.7200000000 0.0140085872 0.0091161434 0.0143815447 0.0096488598 0.8326760000 954035461 0 1783427072 0.2223758847 -0.0130707091 -0.3763496876 820 32.7599999990 0.0141581250 0.0091222922 0.0143815447 0.0096516770 0.8752470000 954036735 0 1782157312 0.2227408439 -0.0134380478 -0.3751866817 821 32.7999999990 0.0142627601 0.0091285534 0.0143815447 0.0096549825 0.8384980000 954038009 0 1783697408 0.2229637355 -0.0136699416 -0.3743188977 822 32.8400000000 0.0142714325 0.0091348100 0.0143815447 0.0096582675 0.8432590000 954039283 0 1782444032 0.2229067087 -0.0142234517 -0.3732868135 823 32.8800000000 0.0143144447 0.0091411036 0.0143815447 0.0096696024 0.8547240000 954040557 0 1783967744 0.2230374962 -0.0147513635 -0.3721606731 824 32.9200000000 0.0143827535 0.0091474648 0.0143827535 0.0096783781 0.8478030000 954041831 0 1782824960 0.2230041772 -0.0153331570 -0.3710803390 825 32.9600000000 0.0144041730 0.0091538366 0.0144041730 0.0096899437 0.8410740000 954043105 0 1784332288 0.2228478491 -0.0157911573 -0.3702090383 826 33.0000000000 0.0144708874 0.0091602737 0.0144708874 0.0097009545 0.8991770000 954044379 0 1783046144 0.2227173895 -0.0158965159 -0.3694260716 827 33.0400000000 0.0143819842 0.0091665877 0.0144708874 0.0097061582 0.8517080000 954045653 0 1781665792 0.2224256694 -0.0162034705 -0.3686496615 828 33.0800000000 0.0143348845 0.0091728296 0.0144708874 0.0097146029 0.8522800000 954046927 0 1783316480 0.2218568623 -0.0167230535 -0.3681117296 829 33.1199999990 0.0144187082 0.0091791576 0.0144708874 0.0097235525 0.8506030000 954048201 0 1782231040 0.2213523239 -0.0167938359 -0.3675632477 830 33.1600000000 0.0142495893 0.0091852665 0.0144708874 0.0097239744 0.8532000000 954049475 0 1783721984 0.2208177000 -0.0167881045 -0.3666884303 831 33.2000000000 0.0146262143 0.0091918140 0.0146262143 0.0097268651 0.8561890000 954050749 0 1782452224 0.2201674581 -0.0167781860 -0.3645188212 832 33.2400000000 0.0141974594 0.0091978304 0.0146262143 0.0097218432 0.8966770000 954052023 0 1784086528 0.2193244100 -0.0167632457 -0.3640435934 833 33.2800000000 0.0142637687 0.0092039120 0.0146262143 0.0097173973 0.8562150000 954053297 0 1783103488 0.2186290175 -0.0170109812 -0.3630441725 834 33.3200000000 0.0143668903 0.0092101026 0.0146262143 0.0097132653 0.8625850000 954054571 0 1781784576 0.2179611772 -0.0169445295 -0.3620205820 835 33.3600000000 0.0142598888 0.0092161502 0.0146262143 0.0097075977 0.8554570000 954055845 0 1783308288 0.2174131125 -0.0167706162 -0.3609270453 836 33.4000000000 0.0142481104 0.0092221693 0.0146262143 0.0097019044 0.8571260000 954057119 0 1782210560 0.2165881395 -0.0170487873 -0.3597196341 837 33.4399999990 0.0142943254 0.0092282292 0.0146262143 0.0096970427 0.8548050000 954058393 0 1783828480 0.2155520022 -0.0174623597 -0.3588220775 838 33.4800000000 0.0142962318 0.0092342770 0.0146262143 0.0096922600 0.8989510000 954059667 0 1782824960 0.2144359499 -0.0176091548 -0.3582512140 839 33.5200000000 0.0142243654 0.0092402246 0.0146262143 0.0096867359 0.8588850000 954060941 0 1784459264 0.2131862342 -0.0177282821 -0.3578800261 840 33.5600000000 0.0140879294 0.0092459957 0.0146262143 0.0096814961 0.8653350000 954062215 0 1783074816 0.2118574530 -0.0184004232 -0.3572796285 841 33.6000000000 0.0141089158 0.0092517780 0.0146262143 0.0096790810 0.8621810000 954063489 0 1782030336 0.2104202807 -0.0194794871 -0.3561828136 842 33.6400000000 0.0143729784 0.0092578602 0.0146262143 0.0096842890 0.8619360000 954064763 0 1783697408 0.2092161924 -0.0203084052 -0.3553248048 843 33.6800000000 0.0145315798 0.0092641161 0.0146262143 0.0096854531 0.8640360000 954066037 0 1782665216 0.2081060261 -0.0205485355 -0.3544279933 844 33.7200000000 0.0144384168 0.0092702468 0.0146262143 0.0096828593 0.8627050000 954067311 0 1784459264 0.2068603039 -0.0209171958 -0.3533039987 845 33.7599999990 0.0146423820 0.0092766043 0.0146423820 0.0096835448 0.8645800000 954068585 0 1783222272 0.2055932581 -0.0213099346 -0.3527629972 846 33.7999999990 0.0147441514 0.0092830672 0.0147441514 0.0096834680 0.8691640000 954069859 0 1782317056 0.2043322325 -0.0212764479 -0.3521473706 847 33.8400000000 0.0146373902 0.0092893887 0.0147441514 0.0096796760 0.8620350000 954071133 0 1783971840 0.2031499892 -0.0210882276 -0.3512525856 848 33.8800000000 0.0145601323 0.0092956042 0.0147441514 0.0096740990 0.8648120000 954072407 0 1783324672 0.2019427270 -0.0208478738 -0.3504126966 849 33.9200000000 0.0135834394 0.0093006546 0.0147441514 0.0096714041 0.9065750000 954073681 0 1782587392 0.1988643855 -0.0195348784 -0.3536094725 850 33.9600000000 0.0139098503 0.0093060772 0.0147441514 0.0096674437 0.8984900000 954074955 0 1784205312 0.1989077628 -0.0200943220 -0.3498627245 851 34.0000000000 0.0135455085 0.0093110589 0.0147441514 0.0096643752 0.9071960000 954076229 0 1783443456 0.1962618232 -0.0197314620 -0.3522852063 852 34.0400000000 0.0134907113 0.0093159646 0.0147441514 0.0096608368 0.8985220000 954077503 0 1782300672 0.1944800168 -0.0198164564 -0.3526432812 853 34.0800000000 0.0135664986 0.0093209477 0.0147441514 0.0096580239 0.8605750000 954078777 0 1784082432 0.1942470521 -0.0204577912 -0.3497052491 854 34.1199999990 0.0135209933 0.0093258657 0.0147441514 0.0096542856 0.9007950000 954080051 0 1783087104 0.1918490082 -0.0208262783 -0.3512968421 855 34.1600000000 0.0134396721 0.0093306772 0.0147441514 0.0096497413 0.8633270000 954081325 0 1782198272 0.1914173514 -0.0222206544 -0.3479695320 856 34.2000000000 0.0137659730 0.0093358586 0.0147441514 0.0096472647 0.9054460000 954082599 0 1783861248 0.1903123111 -0.0235616453 -0.3460750878 857 34.2400000000 0.0140932947 0.0093414099 0.0147441514 0.0096478698 0.8727840000 954083873 0 1782816768 0.1892628372 -0.0239449777 -0.3450341821 858 34.2800000000 0.0140322438 0.0093468771 0.0147441514 0.0096435701 0.8659340000 954085147 0 1784586240 0.1880280524 -0.0244308747 -0.3437072635 859 34.3200000000 0.0141002173 0.0093524106 0.0147441514 0.0096408988 0.8647370000 954086421 0 1783554048 0.1866531670 -0.0249911286 -0.3420790136 860 34.3600000000 0.0142130889 0.0093580626 0.0147441514 0.0096369534 0.8678060000 954087695 0 1782300672 0.1852894872 -0.0249701962 -0.3407358229 861 34.4000000000 0.0141009456 0.0093635712 0.0147441514 0.0096314841 0.8651510000 954088969 0 1784061952 0.1838604808 -0.0249843039 -0.3393457830 862 34.4400000000 0.0141327484 0.0093691039 0.0147441514 0.0096259989 0.8717560000 954090243 0 1782931456 0.1823598444 -0.0251613874 -0.3377381563 863 34.4800000000 0.0142561523 0.0093747667 0.0147441514 0.0096204797 0.8703680000 954091517 0 1781686272 0.1808402091 -0.0250492971 -0.3362398446 864 34.5200000000 0.0142399026 0.0093803977 0.0147441514 0.0096154288 0.8683310000 954092791 0 1783316480 0.1789862514 -0.0247386768 -0.3342424333 865 34.5600000000 0.0141219534 0.0093858792 0.0147441514 0.0096116213 0.8702570000 954094065 0 1781927936 0.1771351099 -0.0248909015 -0.3321145177 866 34.6000000000 0.0141812190 0.0093914166 0.0147441514 0.0096061174 0.8746430000 954095339 0 1783681024 0.1750977039 -0.0252434723 -0.3297117352 867 34.6400000000 0.0143864779 0.0093971779 0.0147441514 0.0096009005 0.8788770000 954096613 0 1782542336 0.1729522794 -0.0249673110 -0.3279740214 868 34.6800000000 0.0143371234 0.0094028691 0.0147441514 0.0095969702 0.9079770000 954097887 0 1784205312 0.1706929356 -0.0243665501 -0.3259570897 869 34.7200000000 0.0143400300 0.0094085505 0.0147441514 0.0095945470 0.8714250000 954099161 0 1783324672 0.1684062630 -0.0236147158 -0.3238931596 870 34.7600000000 0.0142380660 0.0094141017 0.0147441514 0.0095971964 0.8714970000 954100435 0 1782435840 0.1658683866 -0.0230040830 -0.3214557469 871 34.8000000000 0.0140812341 0.0094194600 0.0147441514 0.0096002130 0.8719140000 954101709 0 1784217600 0.1631866843 -0.0233179834 -0.3189583421 872 34.8400000000 0.0142629724 0.0094250145 0.0147441514 0.0095947322 0.8764410000 954102983 0 1783222272 0.1602775306 -0.0240635965 -0.3161524534 873 34.8800000000 0.0147439754 0.0094311073 0.0147441514 0.0095932592 0.8714310000 954104257 0 1782468608 0.1575075686 -0.0234620757 -0.3139904439 874 34.9200000000 0.0147100184 0.0094371472 0.0147441514 0.0095885462 0.9085260000 954105531 0 1784336384 0.1547373831 -0.0221294034 -0.3118886352 875 34.9600000000 0.0144714871 0.0094429007 0.0147441514 0.0095917174 0.8694190000 954106805 0 1783214080 0.1518253535 -0.0214085262 -0.3096319735 876 35.0000000000 0.0144105535 0.0094485716 0.0147441514 0.0095950547 0.8680800000 954108079 0 1782468608 0.1488521695 -0.0210214611 -0.3073733151 877 35.0400000000 0.0144688236 0.0094542959 0.0147441514 0.0095962517 0.8670440000 954109353 0 1784205312 0.1458644271 -0.0204600655 -0.3050513268 878 35.0800000000 0.0143398866 0.0094598604 0.0147441514 0.0096010127 0.8761540000 954110627 0 1783316480 0.1427720934 -0.0204352904 -0.3026399016 879 35.1200000000 0.0144544384 0.0094655425 0.0147441514 0.0095993227 0.8728620000 954111901 0 1782411264 0.1397674829 -0.0200128946 -0.3006246686 880 35.1600000000 0.0144763533 0.0094712366 0.0147441514 0.0096058949 0.8663280000 954113175 0 1783967744 0.1368318200 -0.0190705173 -0.2981453836 881 35.2000000000 0.0143966665 0.0094768273 0.0147441514 0.0096224254 0.8837780000 954114449 0 1783070720 0.1334670931 -0.0191598721 -0.2966085374 882 35.2400000000 0.0144638903 0.0094824816 0.0147441514 0.0096239248 0.8636790000 954115723 0 1782202368 0.1307361573 -0.0191828851 -0.2937135100 883 35.2800000000 0.0144586209 0.0094881171 0.0147441514 0.0096200388 0.8793800000 954116997 0 1783844864 0.1273200363 -0.0191061627 -0.2919202149 884 35.3200000000 0.0144856423 0.0094937704 0.0147441514 0.0096155778 0.8804360000 954118271 0 1782697984 0.1245350987 -0.0182230324 -0.2900178730 885 35.3600000000 0.0144568197 0.0094993783 0.0147441514 0.0096122052 0.8839310000 954119545 0 1782071296 0.1216372848 -0.0177394357 -0.2880480587 886 35.4000000000 0.0144489612 0.0095049648 0.0147441514 0.0096077785 0.9127180000 954120819 0 1783808000 0.1186275110 -0.0178019162 -0.2858553231 887 35.4400000000 0.0144677470 0.0095105598 0.0147441514 0.0096025149 0.8822410000 954122093 0 1782665216 0.1157262772 -0.0177651849 -0.2839749157 888 35.4800000000 0.0144801103 0.0095161561 0.0147441514 0.0095972056 0.8861760000 954123367 0 1784315904 0.1129017621 -0.0177333280 -0.2821137309 889 35.5200000000 0.0145048210 0.0095217677 0.0147441514 0.0095935216 0.8999250000 954124641 0 1783361536 0.1102806330 -0.0172238853 -0.2803671658 890 35.5600000000 0.0145162819 0.0095273795 0.0147441514 0.0095887414 0.8970470000 954125915 0 1782177792 0.1077155024 -0.0166250058 -0.2785616815 891 35.6000000000 0.0145327346 0.0095329972 0.0147441514 0.0095834808 0.9054810000 954127189 0 1783988224 0.1051483750 -0.0158340167 -0.2769088149 892 35.6400000000 0.0145262312 0.0095385950 0.0147441514 0.0095781874 0.9453020000 954128463 0 1782812672 0.1026221737 -0.0153710879 -0.2752888501 893 35.6800000000 0.0145121319 0.0095441645 0.0147441514 0.0095728818 0.8978360000 954129737 0 1781817344 0.1000790745 -0.0148823168 -0.2737317979 894 35.7200000000 0.0145211220 0.0095497315 0.0147441514 0.0095677119 0.8893880000 954131011 0 1783717888 0.0975914225 -0.0143854609 -0.2723148465 895 35.7600000000 0.0145564554 0.0095553256 0.0147441514 0.0095628757 0.8825970000 954132285 0 1782542336 0.0951077864 -0.0140397744 -0.2710562944 896 35.8000000000 0.0145588545 0.0095609099 0.0147441514 0.0095577979 0.8843360000 954133559 0 1784225792 0.0926544815 -0.0139144417 -0.2696329355 897 35.8400000000 0.0145176472 0.0095664358 0.0147441514 0.0095525784 0.8764090000 954134833 0 1782935552 0.0902800187 -0.0133957528 -0.2684640586 898 35.8800000000 0.0145344967 0.0095719682 0.0147441514 0.0095475373 0.8695040000 954136107 0 1784696832 0.0878405049 -0.0127109606 -0.2674045265 899 35.9200000000 0.0145421717 0.0095774968 0.0147441514 0.0095429000 0.8666730000 954137381 0 1783603200 0.0852442011 -0.0125390207 -0.2665976286 900 35.9600000000 0.0145912487 0.0095830676 0.0147441514 0.0095376788 0.8592120000 954138655 0 1782075392 0.0827081949 -0.0128647303 -0.2661886215 901 36.0000000000 0.0145560754 0.0095885870 0.0147441514 0.0095341617 0.8535400000 954139929 0 1783844864 0.0803416148 -0.0126687093 -0.2660101652 902 36.0400000000 0.0145390248 0.0095940753 0.0147441514 0.0095289294 0.8604910000 954141203 0 1782714368 0.0779838338 -0.0123222088 -0.2657516301 903 36.0800000000 0.0145747755 0.0095995911 0.0147441514 0.0095237293 0.8504120000 954142477 0 1784332288 0.0754402280 -0.0123900892 -0.2654864490 904 36.1200000000 0.0144436862 0.0096049496 0.0147441514 0.0095185353 0.8697730000 954143751 0 1783349248 0.0730489865 -0.0121914223 -0.2649946809 905 36.1600000000 0.0144991260 0.0096103575 0.0147441514 0.0095136614 0.8349620000 954145025 0 1782046720 0.0706073940 -0.0117495414 -0.2645654380 906 36.2000000000 0.0144201312 0.0096156663 0.0147441514 0.0095101888 0.8247120000 954146299 0 1783713792 0.0679924116 -0.0116683040 -0.2643558979 907 36.2400000000 0.0144031569 0.0096209447 0.0147441514 0.0095066707 0.8264520000 954147573 0 1782423552 0.0653655455 -0.0118828220 -0.2647695541 908 36.2800000000 0.0143940533 0.0096262014 0.0147441514 0.0095015140 0.8290080000 954148847 0 1784078336 0.0627054200 -0.0120443348 -0.2651994526 909 36.3200000000 0.0144001059 0.0096314532 0.0147441514 0.0094962908 0.8297520000 954150121 0 1782833152 0.0600707009 -0.0120629044 -0.2651072443 910 36.3600000000 0.0144225089 0.0096367181 0.0147441514 0.0094911231 0.8546720000 954151395 0 1784356864 0.0574523024 -0.0118877925 -0.2650499642 911 36.4000000000 0.0143887382 0.0096419344 0.0147441514 0.0094863254 0.8266800000 954152669 0 1783181312 0.0547934249 -0.0121425288 -0.2653884590 912 36.4400000000 0.0144241750 0.0096471781 0.0147441514 0.0094811393 0.8330530000 954153943 0 1781911552 0.0522735231 -0.0120155551 -0.2652240396 913 36.4800000000 0.0143902358 0.0096523731 0.0147441514 0.0094761996 0.8224820000 954155217 0 1783451648 0.0498244651 -0.0116442135 -0.2650821507 914 36.5200000000 0.0143704154 0.0096575351 0.0147441514 0.0094726560 0.8329840000 954156491 0 1782341632 0.0471807681 -0.0117886197 -0.2650590241 915 36.5600000000 0.0143548166 0.0096626687 0.0147441514 0.0094688389 0.8394800000 954157765 0 1783840768 0.0447326899 -0.0119914291 -0.2654252946 916 36.6000000000 0.0143787460 0.0096678173 0.0147441514 0.0094638953 0.8674000000 954159039 0 1782697984 0.0423464254 -0.0121741379 -0.2653681636 917 36.6400000000 0.0143416366 0.0096729141 0.0147441514 0.0094587356 0.8289780000 954160313 0 1784332288 0.0399267860 -0.0127654197 -0.2656188309 918 36.6800000000 0.0143541628 0.0096780135 0.0147441514 0.0094538965 0.8330070000 954161587 0 1783173120 0.0376708172 -0.0128554907 -0.2653615177 919 36.7200000000 0.0143894674 0.0096831403 0.0147441514 0.0094487549 0.8417720000 954162861 0 1781903360 0.0356074460 -0.0126634650 -0.2650850117 920 36.7600000000 0.0143925464 0.0096882592 0.0147441514 0.0094438859 0.8358510000 954164135 0 1783459840 0.0335594565 -0.0128642246 -0.2650775015 921 36.8000000000 0.0143581461 0.0096933296 0.0147441514 0.0094387928 0.8374450000 954165409 0 1782460416 0.0317479633 -0.0126421638 -0.2649083138 922 36.8400000000 0.0144352438 0.0096984727 0.0147441514 0.0094341062 0.8705770000 954166683 0 1784078336 0.0301208273 -0.0122255944 -0.2644468248 923 36.8800000000 0.0144270882 0.0097035958 0.0147441514 0.0094303435 0.8386690000 954167957 0 1782968320 0.0285406709 -0.0121108517 -0.2641900182 924 36.9200000000 0.0143915974 0.0097086694 0.0147441514 0.0094278864 0.8413390000 954169231 0 1781649408 0.0270739701 -0.0123035898 -0.2643961012 925 36.9600000000 0.0144068105 0.0097137485 0.0147441514 0.0094236050 0.8505060000 954170505 0 1783300096 0.0255287718 -0.0125609068 -0.2641645074 926 37.0000000000 0.0144314291 0.0097188431 0.0147441514 0.0094185952 0.8483820000 954171779 0 1782284288 0.0242399182 -0.0123204226 -0.2641507387 927 37.0400000000 0.0144438259 0.0097239402 0.0147441514 0.0094140601 0.8413810000 954173053 0 1783951360 0.0230893828 -0.0121927839 -0.2641426921 928 37.0800000000 0.0144151030 0.0097289953 0.0147441514 0.0094109946 0.8827740000 954174327 0 1782947840 0.0220456515 -0.0113709988 -0.2634839416 929 37.1200000000 0.0144303050 0.0097340560 0.0147441514 0.0094100989 0.8465390000 954175601 0 1784586240 0.0210549906 -0.0112079876 -0.2631500959 930 37.1600000000 0.0144457733 0.0097391223 0.0147441514 0.0094093788 0.8507600000 954176875 0 1783619584 0.0202107038 -0.0110158771 -0.2628904581 931 37.2000000000 0.0144454911 0.0097441775 0.0147441514 0.0094076604 0.8528170000 954178149 0 1782317056 0.0193919372 -0.0106989592 -0.2625836432 932 37.2400000000 0.0144795394 0.0097492584 0.0147441514 0.0094047643 0.8467590000 954179423 0 1784061952 0.0187264737 -0.0105762687 -0.2624796927 933 37.2800000000 0.0144495675 0.0097542962 0.0147441514 0.0094018157 0.8500240000 954180697 0 1783046144 0.0180172455 -0.0101282978 -0.2620128989 934 37.3200000000 0.0144461254 0.0097593196 0.0147441514 0.0093994907 0.8472460000 954181971 0 1781960704 0.0174988844 -0.0094029820 -0.2615430057 935 37.3600000000 0.0144401724 0.0097643258 0.0147441514 0.0093994109 0.8400920000 954183245 0 1783697408 0.0170993879 -0.0090246154 -0.2613968849 936 37.4000000000 0.0143904965 0.0097692683 0.0147441514 0.0093976662 0.8509200000 954184519 0 1782587392 0.0166775919 -0.0088378266 -0.2612907887 937 37.4400000000 0.0144706089 0.0097742858 0.0147441514 0.0093942512 0.8470040000 954185793 0 1784205312 0.0163966678 -0.0089511639 -0.2612934709 938 37.4800000000 0.0144867664 0.0097793097 0.0147441514 0.0093909019 0.8478480000 954187067 0 1783078912 0.0161164552 -0.0090228207 -0.2613027990 939 37.5200000000 0.0145214591 0.0097843599 0.0147441514 0.0093866167 0.8467280000 954188341 0 1781776384 0.0161104035 -0.0088685099 -0.2615555227 940 37.5600000000 0.0145339128 0.0097894127 0.0147441514 0.0093823935 0.8801590000 954189615 0 1783427072 0.0160992723 -0.0085891495 -0.2616598010 941 37.6000000000 0.0145493094 0.0097944710 0.0147441514 0.0093787989 0.8421030000 954190889 0 1782329344 0.0160349179 -0.0080966670 -0.2614980340 942 37.6400000000 0.0145926615 0.0097995646 0.0147441514 0.0093756925 0.8413840000 954192163 0 1783951360 0.0161581803 -0.0076705478 -0.2615779042 943 37.6800000000 0.0145735107 0.0098046271 0.0147441514 0.0093741087 0.8483780000 954193437 0 1782824960 0.0162563901 -0.0074232426 -0.2618082762 944 37.7200000000 0.0145778349 0.0098096835 0.0147441514 0.0093718609 0.8393920000 954194711 0 1784459264 0.0163826905 -0.0069483933 -0.2619539499 945 37.7600000000 0.0145669328 0.0098147176 0.0147441514 0.0093694632 0.8384800000 954195985 0 1783058432 0.0165343769 -0.0066560172 -0.2621252537 946 37.8000000000 0.0145613076 0.0098197352 0.0147441514 0.0093671058 0.8719770000 954197259 0 1781776384 0.0165454280 -0.0064960234 -0.2622165978 947 37.8400000000 0.0145760588 0.0098247577 0.0147441514 0.0093637405 0.8351290000 954198533 0 1783427072 0.0166872926 -0.0062454995 -0.2621313632 948 37.8800000000 0.0145827802 0.0098297767 0.0147441514 0.0093611305 0.8321200000 954199807 0 1782349824 0.0167894140 -0.0060627558 -0.2621876299 949 37.9200000000 0.0145984245 0.0098348016 0.0147441514 0.0093582183 0.8361920000 954201081 0 1783951360 0.0169982035 -0.0058068675 -0.2623551786 950 37.9600000000 0.0146164922 0.0098398350 0.0147441514 0.0093543029 0.8304450000 954202355 0 1782558720 0.0172562636 -0.0053985249 -0.2626491785 951 38.0000000000 0.0146097448 0.0098448506 0.0147441514 0.0093500882 0.8299930000 954203629 0 1784213504 0.0174623299 -0.0051330053 -0.2627064884 952 38.0400000000 0.0146086933 0.0098498547 0.0147441514 0.0093477498 0.8714430000 954204903 0 1782939648 0.0175989121 -0.0048875040 -0.2625941038 953 38.0800000000 0.0146296620 0.0098548702 0.0147441514 0.0093436451 0.8271360000 954206177 0 1784451072 0.0179554708 -0.0046568392 -0.2629554868 954 38.1200000000 0.0146277212 0.0098598732 0.0147441514 0.0093388674 0.8356990000 954207451 0 1783308288 0.0181972422 -0.0043033906 -0.2629815340 955 38.1600000000 0.0146368109 0.0098648752 0.0147441514 0.0093343485 0.8256990000 954208725 0 1781952512 0.0183636211 -0.0042944993 -0.2630205452 956 38.2000000000 0.0146471290 0.0098698776 0.0147441514 0.0093295078 0.8293270000 954209999 0 1783451648 0.0186686199 -0.0039545489 -0.2632302046 957 38.2400000000 0.0146243274 0.0098748457 0.0147441514 0.0093247555 0.8281490000 954211273 0 1782222848 0.0187986810 -0.0040556067 -0.2634536922 958 38.2800000000 0.0146639831 0.0098798448 0.0147441514 0.0093200591 0.8576790000 954212547 0 1783840768 0.0189574417 -0.0038938792 -0.2634420395 959 38.3200000000 0.0146742947 0.0098848442 0.0147441514 0.0093153468 0.8263660000 954213821 0 1782792192 0.0192380305 -0.0038857309 -0.2637571096 960 38.3600000000 0.0146617675 0.0098898202 0.0147441514 0.0093107587 0.8321420000 954215095 0 1784442880 0.0193976834 -0.0037698750 -0.2635698915 961 38.4000000000 0.0146714589 0.0098947958 0.0147441514 0.0093062386 0.8262290000 954216369 0 1783472128 0.0197034962 -0.0036435851 -0.2637827992 962 38.4400000000 0.0146779949 0.0098997680 0.0147441514 0.0093015964 0.8356930000 954217643 0 1781940224 0.0199656952 -0.0035339610 -0.2640462518 963 38.4800000000 0.0146546178 0.0099047055 0.0147441514 0.0092968631 0.8240330000 954218917 0 1783701504 0.0202376153 -0.0036505458 -0.2641505301 964 38.5200000000 0.0146824606 0.0099096617 0.0147441514 0.0092921093 0.8612040000 954220191 0 1782833152 0.0205657668 -0.0034731003 -0.2642744184 965 38.5600000000 0.0146612860 0.0099145857 0.0147441514 0.0092873750 0.8218530000 954221465 0 1784348672 0.0208405070 -0.0033861105 -0.2642288804 966 38.6000000000 0.0146438014 0.0099194813 0.0147441514 0.0092827765 0.8254630000 954222739 0 1783316480 0.0211000871 -0.0033874018 -0.2643904090 967 38.6400000000 0.0146516236 0.0099243750 0.0147441514 0.0092780078 0.8214240000 954224013 0 1782321152 0.0213946905 -0.0033697775 -0.2645437121 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-19 02:05:41 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.4406190000 954995638 0 1769435136 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025287580 0.0012643790 0.0025287580 0.0016396729 0.5829190000 953139695 0 1765142528 0.0001298894 -0.0014884579 0.0010924048 3 0.0800000000 0.0054244380 0.0026510654 0.0054244380 0.0017391977 0.5077960000 952828237 0 1766998016 -0.0038504642 -0.0031067394 0.0017398237 4 0.1200000000 0.0070274421 0.0037451595 0.0070274421 0.0015669244 0.4986340000 952829839 0 1768681472 -0.0023110318 -0.0054961848 0.0010509992 5 0.1600000000 0.0088551790 0.0047671634 0.0088551790 0.0013909642 0.5059750000 952831113 0 1770299392 -0.0046131993 -0.0063578775 0.0030123633 6 0.2000000000 0.0102930972 0.0056881524 0.0102930972 0.0012778220 0.5024910000 952833043 0 1772093440 -0.0038861982 -0.0083314199 0.0025791780 7 0.2400000000 0.0118946498 0.0065747949 0.0118946498 0.0012581951 0.5077260000 952834317 0 1773727744 -0.0038171627 -0.0100242635 0.0032994985 8 0.2800000000 0.0135098193 0.0074416729 0.0135098193 0.0012218635 0.5096750000 952835591 0 1775411200 -0.0048788586 -0.0113805616 0.0035558587 9 0.3200000000 0.0144352987 0.0082187425 0.0144352987 0.0012466534 0.5094420000 952836865 0 1777156096 -0.0066229966 -0.0128532359 0.0038512140 10 0.3600000000 0.0163385924 0.0090307275 0.0163385924 0.0012909927 0.5093510000 952839451 0 1778839552 -0.0065648258 -0.0135375271 0.0049187383 11 0.4000000000 0.0166966375 0.0097276284 0.0166966375 0.0015214718 0.5049320000 952840725 0 1780473856 -0.0074224779 -0.0147393653 0.0057224147 12 0.4400000000 0.0182190146 0.0104352439 0.0182190146 0.0018500371 0.5109770000 952841999 0 1782259712 -0.0073891315 -0.0164435059 0.0053270306 13 0.4800000000 0.0193160996 0.0111183866 0.0193160996 0.0019798412 0.5093810000 952843273 0 1783877632 -0.0093520060 -0.0176293720 0.0061454088 14 0.5200000000 0.0214044042 0.0118531022 0.0214044042 0.0019401732 0.5112490000 952844547 0 1782738944 -0.0093163243 -0.0185875688 0.0060941246 15 0.5600000000 0.0227404237 0.0125789236 0.0227404237 0.0018736660 0.5090140000 952845821 0 1784438784 -0.0118633416 -0.0187024008 0.0071492945 16 0.6000000000 0.0223943722 0.0131923891 0.0227404237 0.0018615365 0.5144100000 952847095 0 1783287808 -0.0114700813 -0.0202183407 0.0060664122 17 0.6400000000 0.0232618582 0.0137847109 0.0232618582 0.0018285122 0.5141210000 952848369 0 1782140928 -0.0132108238 -0.0223458391 0.0048402767 18 0.6800000000 0.0240122750 0.0143529089 0.0240122750 0.0017749035 0.5068970000 952852267 0 1783910400 -0.0145212021 -0.0229160916 0.0059817573 19 0.7200000000 0.0249491297 0.0149106047 0.0249491297 0.0017824498 0.5141640000 952853541 0 1782861824 -0.0159210172 -0.0235471185 0.0057967831 20 0.7600000000 0.0246747509 0.0153988120 0.0249491297 0.0018944932 0.5142850000 952854815 0 1781878784 -0.0188484509 -0.0245167017 0.0053310469 21 0.8000000000 0.0253916997 0.0158746638 0.0253916997 0.0018566142 0.5084200000 952856089 0 1783521280 -0.0216679387 -0.0242892690 0.0058404533 22 0.8400000000 0.0259012319 0.0163304169 0.0259012319 0.0018347269 0.5443900000 952857363 0 1782476800 -0.0270100478 -0.0255603846 0.0054578921 23 0.8800000000 0.0264086220 0.0167685997 0.0264086220 0.0017946405 0.5099210000 952858637 0 1784135680 -0.0269538909 -0.0270172078 0.0040060580 24 0.9200000000 0.0290326439 0.0172796016 0.0290326439 0.0017834514 0.5130090000 952859911 0 1783373824 -0.0342004895 -0.0279597286 0.0038877232 25 0.9600000000 0.0310492106 0.0178303859 0.0310492106 0.0017832536 0.5050460000 952861185 0 1782243328 -0.0355904661 -0.0287421215 0.0036555349 26 1.0000000000 0.0305184126 0.0183183870 0.0310492106 0.0017516522 0.5041780000 952862459 0 1784008704 -0.0414997153 -0.0297127590 0.0043343063 27 1.0400000000 0.0316585489 0.0188124670 0.0316585489 0.0018679059 0.5053720000 952863733 0 1782886400 -0.0470298566 -0.0315143652 0.0024488762 28 1.0800000000 0.0337427706 0.0193456922 0.0337427706 0.0020575715 0.5035470000 952865007 0 1781903360 -0.0515263528 -0.0317365564 0.0026429466 29 1.1200000000 0.0356616117 0.0199083101 0.0356616117 0.0022462127 0.4983660000 952866281 0 1783529472 -0.0572203286 -0.0333577357 0.0003263837 30 1.1600000000 0.0347459950 0.0204028996 0.0356616117 0.0022621525 0.5005420000 952867555 0 1782480896 -0.0664714128 -0.0332040861 0.0019750241 31 1.2000000000 0.0364708230 0.0209212197 0.0364708230 0.0022742735 0.4983670000 952868829 0 1784164352 -0.0729596764 -0.0341592617 0.0006260027 32 1.2400000000 0.0381802619 0.0214605647 0.0381802619 0.0023202545 0.5384350000 952870103 0 1783115776 -0.0794395208 -0.0354375206 -0.0012914835 33 1.2800000000 0.0381288864 0.0219656654 0.0381802619 0.0023857797 0.5024120000 952871377 0 1782161408 -0.0849699974 -0.0357683301 -0.0015824484 34 1.3200000000 0.0218318962 0.0219617310 0.0381802619 0.0027784334 0.5383190000 952877899 0 1783750656 -0.1156183258 -0.0207833499 -0.0059610819 35 1.3600000000 0.0268591959 0.0221016586 0.0381802619 0.0031682293 0.5137490000 952879173 0 1782730752 -0.1185536608 -0.0249020699 -0.0073874514 36 1.4000000000 0.0308420341 0.0223444468 0.0381802619 0.0037781103 0.5056870000 952880447 0 1781710848 -0.1235345602 -0.0278535448 -0.0082703531 37 1.4400000000 0.0266013537 0.0224594983 0.0381802619 0.0037828942 0.5126840000 952881721 0 1783521280 -0.1349016428 -0.0258151703 -0.0080697108 38 1.4800000000 0.0256703403 0.0225439942 0.0381802619 0.0037377330 0.5139840000 952882995 0 1782497280 -0.1467753053 -0.0254432615 -0.0075817294 39 1.5200000000 0.0295660384 0.0227240466 0.0381802619 0.0036973662 0.5031810000 952884269 0 1784156160 -0.1497665495 -0.0298888888 -0.0099438569 40 1.5600000000 0.0270281024 0.0228316480 0.0381802619 0.0036952050 0.5125700000 952885543 0 1783169024 -0.1597890556 -0.0290632881 -0.0099405823 41 1.6000000000 0.0262013189 0.0229138351 0.0381802619 0.0037131604 0.5118710000 952886817 0 1782153216 -0.1702698320 -0.0293819550 -0.0084404247 42 1.6400000000 0.0270584319 0.0230125160 0.0381802619 0.0036697689 0.5673240000 952888091 0 1783775232 -0.1834227741 -0.0287324563 -0.0060658068 43 1.6800000000 0.0302418545 0.0231806401 0.0381802619 0.0036364029 0.5029080000 952889365 0 1782730752 -0.1894585788 -0.0312994123 -0.0020689426 44 1.7200000000 0.0334674791 0.0234144319 0.0381802619 0.0036455073 0.5070480000 952890639 0 1781985280 -0.1955709010 -0.0351484343 -0.0033213510 45 1.7600000000 0.0372042060 0.0237208713 0.0381802619 0.0036369052 0.5000800000 952891913 0 1783762944 -0.2029559463 -0.0366335660 0.0010901372 46 1.8000000000 0.0399144553 0.0240729058 0.0399144553 0.0036293910 0.5040460000 952893187 0 1782624256 -0.2087889761 -0.0387435630 0.0018900111 47 1.8400000000 0.0404890180 0.0244221847 0.0404890180 0.0037283174 0.5002060000 952894461 0 1784393728 -0.2119741291 -0.0411892831 0.0017824080 48 1.8800000000 0.0419484936 0.0247873162 0.0419484936 0.0037521275 0.5122640000 952895735 0 1783279616 -0.2160506248 -0.0428190641 0.0031834058 49 1.9200000000 0.0443078317 0.0251856940 0.0443078317 0.0037161100 0.5083990000 952897009 0 1782243328 -0.2228876352 -0.0439889804 0.0044853278 50 1.9600000000 0.0251014587 0.0251840093 0.0443078317 0.0038279571 0.5472730000 952898283 0 1784049664 -0.2402954698 -0.0258579608 0.0048924354 51 2.0000000000 0.0293367971 0.0252654365 0.0443078317 0.0038224467 0.5141970000 952899557 0 1782853632 -0.2385860234 -0.0301750433 0.0030105023 52 2.0400000000 0.0334153064 0.0254221648 0.0443078317 0.0037930717 0.5120980000 952900831 0 1781858304 -0.2414633632 -0.0336550996 0.0031324867 53 2.0800000000 0.0354022160 0.0256104677 0.0443078317 0.0038156666 0.5182590000 952902105 0 1783488512 -0.2433242053 -0.0379534923 0.0004539975 54 2.1200000000 0.0257769022 0.0256135498 0.0443078317 0.0040158417 0.5342810000 952903379 0 1782386688 -0.2575461864 -0.0302218180 0.0038856138 55 2.1600000000 0.0308175385 0.0257081678 0.0443078317 0.0040609178 0.5146550000 952904653 0 1783996416 -0.2591843009 -0.0343457200 0.0047684051 56 2.2000000000 0.0257450417 0.0257088262 0.0443078317 0.0041029739 0.5367520000 952905927 0 1783152640 -0.2797384560 -0.0290056430 0.0126802158 57 2.2400000000 0.0276982542 0.0257437285 0.0443078317 0.0040742956 0.5161440000 952907201 0 1781895168 -0.2843386531 -0.0335744508 0.0137302596 58 2.2800000000 0.0278495625 0.0257800359 0.0443078317 0.0040779958 0.5255870000 952908475 0 1783668736 -0.2936227918 -0.0343621448 0.0165341031 59 2.3200000000 0.0288281068 0.0258316982 0.0443078317 0.0042142301 0.5351040000 952909749 0 1782497280 -0.3075851798 -0.0329716392 0.0223895777 60 2.3600000000 0.0307974983 0.0259144615 0.0443078317 0.0043360932 0.5147310000 952911023 0 1784266752 -0.3107059300 -0.0366161279 0.0209876820 61 2.4000000000 0.0325306095 0.0260229229 0.0443078317 0.0044656939 0.5201460000 952912297 0 1783169024 -0.3168232143 -0.0397018977 0.0210909694 62 2.4400000000 0.0259285700 0.0260214011 0.0443078317 0.0045554998 0.5854290000 952913571 0 1781862400 -0.3418099284 -0.0327821933 0.0298561640 63 2.4800000000 0.0270987302 0.0260385016 0.0443078317 0.0047054844 0.5239450000 952914845 0 1783541760 -0.3502790034 -0.0350490548 0.0312764645 64 2.5200000000 0.0281145778 0.0260709403 0.0443078317 0.0050623618 0.5247530000 952916119 0 1782607872 -0.3626227677 -0.0348216854 0.0360009484 65 2.5600000000 0.0281840824 0.0261034502 0.0443078317 0.0053579694 0.5235660000 952917393 0 1784291328 -0.3763869703 -0.0350450389 0.0397181176 66 2.6000000000 0.0292355809 0.0261509067 0.0443078317 0.0054480375 0.5232530000 952929163 0 1783115776 -0.3868853748 -0.0347572081 0.0418681577 67 2.6400000000 0.0303836875 0.0262140825 0.0443078317 0.0055029355 0.5251230000 952930437 0 1782161408 -0.3969535232 -0.0333797969 0.0443389192 68 2.6800000000 0.0303079095 0.0262742859 0.0443078317 0.0054830817 0.5246010000 952931711 0 1783750656 -0.4081037045 -0.0335166976 0.0436026230 69 2.7200000000 0.0300418381 0.0263288881 0.0443078317 0.0054444954 0.5228070000 952932985 0 1782652928 -0.4176835418 -0.0329865329 0.0480040461 70 2.7600000000 0.0358705111 0.0264651970 0.0443078317 0.0054114762 0.5114280000 952934259 0 1784291328 -0.4255656302 -0.0367906317 0.0488999374 71 2.8000000000 0.0407526977 0.0266664294 0.0443078317 0.0054333941 0.5105190000 952935533 0 1783017472 -0.4320038557 -0.0409099162 0.0468874089 72 2.8400000000 0.0274354331 0.0266771100 0.0443078317 0.0063415877 0.5986720000 952936807 0 1781895168 -0.4500329196 -0.0229230318 0.0466579869 73 2.8800000000 0.0307546612 0.0267329668 0.0443078317 0.0063847232 0.5341860000 952938081 0 1783504896 -0.4595737755 -0.0247619227 0.0490499549 74 2.9200000000 0.0376771577 0.0268808613 0.0443078317 0.0064306945 0.5225540000 952939355 0 1782243328 -0.4606820941 -0.0297736637 0.0474384315 75 2.9600000000 0.0446866304 0.0271182716 0.0446866304 0.0064508769 0.5204820000 952940629 0 1783885824 -0.4609116912 -0.0328598581 0.0461347923 76 3.0000000000 0.0291847736 0.0271454624 0.0446866304 0.0065975415 0.5626770000 952941903 0 1782734848 -0.4614055157 -0.0148006212 0.0345522277 77 3.0400000000 0.0324298181 0.0272140904 0.0446866304 0.0065953163 0.5322420000 952943177 0 1784504320 -0.4612962306 -0.0176177993 0.0284275189 78 3.0800000000 0.0291208029 0.0272385354 0.0446866304 0.0065646904 0.5461700000 952944451 0 1783427072 -0.4602061510 -0.0131810606 0.0205118675 79 3.1200000000 0.0369680077 0.0273616933 0.0446866304 0.0065433166 0.5245540000 952945725 0 1782345728 -0.4658581913 -0.0176831875 0.0200481489 80 3.1600000000 0.0433340110 0.0275613473 0.0446866304 0.0065236538 0.5259950000 952946999 0 1784012800 -0.4684139490 -0.0209948346 0.0177062508 81 3.2000000000 0.0288642589 0.0275774326 0.0446866304 0.0065047939 0.5853670000 952948273 0 1782755328 -0.4826931357 -0.0080165071 0.0175307114 82 3.2400000000 0.0302476492 0.0276099962 0.0446866304 0.0065131187 0.5508890000 952949547 0 1784393728 -0.4907263219 -0.0092401607 0.0172958374 83 3.2800000000 0.0310676284 0.0276516544 0.0446866304 0.0065525618 0.5505870000 952950821 0 1783279616 -0.4982347190 -0.0079518510 0.0142678097 84 3.3200000000 0.0305678956 0.0276863716 0.0446866304 0.0065412443 0.5570710000 952952095 0 1782136832 -0.5109238029 -0.0086074853 0.0144391367 85 3.3600000000 0.0289352499 0.0277010643 0.0446866304 0.0065217528 0.5760730000 952953369 0 1783885824 -0.5249391794 -0.0060845204 0.0145171443 86 3.4000000000 0.0296942536 0.0277242409 0.0446866304 0.0065637018 0.5658310000 952954643 0 1782599680 -0.5395395160 -0.0060966010 0.0186377764 87 3.4400000000 0.0292584635 0.0277418756 0.0446866304 0.0066826388 0.5692290000 952955917 0 1784393728 -0.5494241118 -0.0068093129 0.0182386935 88 3.4800000000 0.0292184688 0.0277586551 0.0446866304 0.0068286450 0.5736410000 952957191 0 1783427072 -0.5624784827 -0.0064354716 0.0185003728 89 3.5200000000 0.0290529244 0.0277731974 0.0446866304 0.0069593087 0.5842660000 952958465 0 1782263808 -0.5718539357 -0.0060733305 0.0185912121 90 3.5600000000 0.0286536757 0.0277829805 0.0446866304 0.0070498710 0.5823200000 952959739 0 1784008704 -0.5794345140 -0.0074816234 0.0173002779 91 3.6000000000 0.0285568945 0.0277914851 0.0446866304 0.0070888513 0.6179600000 952961013 0 1782980608 -0.5939573050 -0.0086420821 0.0202666838 92 3.6400000000 0.0287906993 0.0278023461 0.0446866304 0.0070971992 0.5873820000 952962287 0 1781768192 -0.6090651751 -0.0067387070 0.0254363678 93 3.6800000000 0.0287062395 0.0278120654 0.0446866304 0.0070756835 0.5835830000 952963561 0 1783377920 -0.6138530970 -0.0075869896 0.0220206399 94 3.7200000000 0.0305592939 0.0278412912 0.0446866304 0.0070495793 0.5856840000 952964835 0 1782157312 -0.6201261878 -0.0116325542 0.0218243767 95 3.7600000000 0.0289144404 0.0278525875 0.0446866304 0.0070272854 0.5981150000 952966109 0 1783758848 -0.6340102553 -0.0088144252 0.0281218886 96 3.8000000000 0.0288373530 0.0278628455 0.0446866304 0.0069981352 0.6021010000 952967383 0 1782472704 -0.6441577077 -0.0092871040 0.0276510287 97 3.8400000000 0.0299426075 0.0278842864 0.0446866304 0.0069627242 0.5895280000 952968657 0 1784156160 -0.6492022872 -0.0130329458 0.0296870489 98 3.8800000000 0.0288126431 0.0278937594 0.0446866304 0.0069339941 0.6104710000 952969931 0 1782886400 -0.6642423272 -0.0125998827 0.0336141586 99 3.9200000000 0.0317117199 0.0279323246 0.0446866304 0.0069086294 0.5955030000 952971205 0 1784520704 -0.6686418653 -0.0139141716 0.0369931795 100 3.9600000000 0.0329026356 0.0279820278 0.0446866304 0.0068742044 0.6341760000 952972479 0 1783283712 -0.6764013767 -0.0154888695 0.0411466993 101 4.0000000000 0.0328424312 0.0280301506 0.0446866304 0.0068412241 0.6044290000 952973753 0 1781837824 -0.6850337386 -0.0171283241 0.0471471734 102 4.0400000000 0.0335425846 0.0280841940 0.0446866304 0.0068169184 0.6019600000 952975027 0 1783504896 -0.6883590817 -0.0192353167 0.0488757789 103 4.0800000000 0.0301299654 0.0281040559 0.0446866304 0.0067864477 0.6167950000 952976301 0 1782251520 -0.7006049752 -0.0165205132 0.0551828071 104 4.1200000000 0.0291143879 0.0281137706 0.0446866304 0.0067576942 0.6243500000 952977575 0 1783869440 -0.7136771679 -0.0173130576 0.0678944811 105 4.1600000000 0.0311649740 0.0281428297 0.0446866304 0.0067603817 0.6122690000 952978849 0 1782632448 -0.7154179811 -0.0194263011 0.0698365569 106 4.2000000000 0.0324176066 0.0281831578 0.0446866304 0.0067690931 0.6154340000 952980123 0 1784139776 -0.7212789655 -0.0199616533 0.0749443993 107 4.2400000000 0.0297205150 0.0281975256 0.0446866304 0.0067456207 0.6227770000 952981397 0 1782886400 -0.7229821682 -0.0207712483 0.0711267963 108 4.2800000000 0.0292756949 0.0282075087 0.0446866304 0.0067145505 0.6574090000 952982671 0 1784520704 -0.7327040434 -0.0213146787 0.0795206577 109 4.3200000000 0.0317794569 0.0282402788 0.0446866304 0.0066977384 0.6124800000 952983945 0 1783234560 -0.7332975268 -0.0235880483 0.0807672888 110 4.3600000000 0.0318299010 0.0282729118 0.0446866304 0.0067020273 0.6122970000 952985219 0 1781878784 -0.7411538959 -0.0242023021 0.0891230553 111 4.4000000000 0.0316610150 0.0283034352 0.0446866304 0.0067007091 0.6094070000 952986493 0 1783504896 -0.7474845648 -0.0253366698 0.0958094522 112 4.4400000000 0.0326180272 0.0283419583 0.0446866304 0.0067024913 0.6110060000 952987767 0 1782218752 -0.7548597455 -0.0256515797 0.1036877185 113 4.4800000000 0.0331114046 0.0283841658 0.0446866304 0.0067082208 0.6081550000 952989041 0 1783775232 -0.7587178349 -0.0262106732 0.1079137027 114 4.5200000000 0.0299579594 0.0283979710 0.0446866304 0.0067397464 0.6303260000 952990315 0 1782521856 -0.7710879445 -0.0234878026 0.1200691164 115 4.5600000000 0.0314624831 0.0284246190 0.0446866304 0.0067637046 0.6077540000 952991589 0 1784156160 -0.7710580826 -0.0248733722 0.1219678521 116 4.6000000000 0.0300508551 0.0284386383 0.0446866304 0.0067961550 0.6574850000 952992863 0 1782886400 -0.7820670009 -0.0209997874 0.1338907480 117 4.6400000000 0.0327004343 0.0284750639 0.0446866304 0.0068082653 0.6076930000 952994137 0 1784520704 -0.7885058522 -0.0205204636 0.1443094760 118 4.6800000000 0.0332619175 0.0285156304 0.0446866304 0.0067801472 0.6147060000 952995411 0 1783283712 -0.7934094667 -0.0225427300 0.1484848559 119 4.7200000000 0.0342768207 0.0285640438 0.0446866304 0.0067547838 0.6121830000 952996685 0 1781878784 -0.7993285656 -0.0239302181 0.1555210501 120 4.7600000000 0.0356172621 0.0286228206 0.0446866304 0.0067276498 0.6087550000 952997959 0 1783361536 -0.8054621816 -0.0239076652 0.1637386233 121 4.8000000000 0.0308281817 0.0286410467 0.0446866304 0.0067149779 0.6287440000 952999233 0 1782140928 -0.8171929121 -0.0198640209 0.1815543622 122 4.8400000000 0.0341622904 0.0286863028 0.0446866304 0.0066893842 0.6178640000 953000507 0 1783758848 -0.8170983791 -0.0215366371 0.1822530478 123 4.8800000000 0.0368016399 0.0287522812 0.0446866304 0.0066684997 0.6166800000 953001781 0 1782611968 -0.8214647770 -0.0198454801 0.1884757131 124 4.9200000000 0.0300904643 0.0287630730 0.0446866304 0.0066435417 0.6774480000 953003055 0 1784164352 -0.8339459300 -0.0128198825 0.2045845836 125 4.9600000000 0.0321081020 0.0287898332 0.0446866304 0.0066359300 0.6245950000 953004329 0 1782894592 -0.8371396661 -0.0148524856 0.2094759047 126 5.0000000000 0.0337906927 0.0288295226 0.0446866304 0.0066178176 0.6215250000 953005603 0 1784401920 -0.8412200212 -0.0152525250 0.2167205960 127 5.0400000000 0.0297778510 0.0288369897 0.0446866304 0.0065936680 0.6523180000 953006877 0 1783037952 -0.8525908589 -0.0105423816 0.2338129282 128 5.0800000000 0.0325106643 0.0288656903 0.0446866304 0.0065685971 0.6236950000 953008151 0 1781776384 -0.8565985560 -0.0132557712 0.2394359112 129 5.1200000000 0.0335628726 0.0289021026 0.0446866304 0.0065449050 0.6253880000 953009425 0 1783259136 -0.8601301908 -0.0138818864 0.2460701168 130 5.1600000000 0.0302795358 0.0289126982 0.0446866304 0.0065343207 0.6461700000 953031691 0 1782018048 -0.8703052998 -0.0108670453 0.2643115520 131 5.2000000000 0.0315696821 0.0289329805 0.0446866304 0.0065650756 0.6278810000 953032965 0 1783496704 -0.8731924295 -0.0114824548 0.2682652771 132 5.2400000000 0.0300072543 0.0289411190 0.0446866304 0.0065732037 0.6417540000 953034239 0 1782132736 -0.8743463755 -0.0103387637 0.2660914660 133 5.2800000000 0.0297301076 0.0289470512 0.0446866304 0.0065717535 0.6364400000 953035513 0 1783767040 -0.8846749067 -0.0098479362 0.2851389945 134 5.3200000000 0.0296878237 0.0289525794 0.0446866304 0.0065987058 0.6354180000 953036787 0 1782464512 -0.8933884501 -0.0073471004 0.3014575541 135 5.3600000000 0.0292826220 0.0289550241 0.0446866304 0.0066168515 0.6322220000 953038061 0 1784131584 -0.8968079686 -0.0065847961 0.3054076433 136 5.4000000000 0.0290133357 0.0289554529 0.0446866304 0.0066505519 0.6316500000 953039335 0 1782878208 -0.9038048983 -0.0062511908 0.3175005615 137 5.4400000000 0.0297141913 0.0289609911 0.0446866304 0.0067035720 0.6222850000 953040609 0 1784504320 -0.9086548686 -0.0065512089 0.3265651166 138 5.4800000000 0.0286593977 0.0289588057 0.0446866304 0.0067419990 0.6321780000 953041883 0 1783267328 -0.9147543907 -0.0063692611 0.3314028978 139 5.5200000000 0.0283235852 0.0289542357 0.0446866304 0.0067829095 0.6328330000 953043157 0 1781768192 -0.9208930731 -0.0080815498 0.3366583586 140 5.5600000000 0.0283395350 0.0289498450 0.0446866304 0.0068519187 0.6728730000 953044431 0 1783250944 -0.9301340580 -0.0073541179 0.3508787155 141 5.6000000000 0.0283341128 0.0289454781 0.0446866304 0.0068840997 0.6306090000 953045705 0 1782009856 -0.9355274439 -0.0061084479 0.3563413024 142 5.6400000000 0.0281046722 0.0289395569 0.0446866304 0.0069171061 0.6309000000 953046979 0 1783504896 -0.9447095990 -0.0058322214 0.3709584475 143 5.6800000000 0.0296220500 0.0289443296 0.0446866304 0.0069940541 0.6149680000 953048253 0 1782251520 -0.9492399693 -0.0050243489 0.3806863725 144 5.7200000000 0.0282245930 0.0289393315 0.0446866304 0.0070338061 0.6299530000 953049527 0 1783885824 -0.9561077952 -0.0019738025 0.3886772394 145 5.7600000000 0.0277580712 0.0289311848 0.0446866304 0.0070323720 0.6346140000 953050801 0 1782472704 -0.9617867470 -0.0024151248 0.3954031169 146 5.8000000000 0.0277679637 0.0289232176 0.0446866304 0.0070229511 0.6306270000 953052075 0 1784156160 -0.9675586820 -0.0023199711 0.4047899842 147 5.8400000000 0.0276571903 0.0289146051 0.0446866304 0.0070057491 0.6373700000 953053349 0 1782886400 -0.9777003527 -0.0029727053 0.4256019592 148 5.8800000000 0.0274334177 0.0289045971 0.0446866304 0.0069843652 0.6870930000 953054623 0 1784504320 -0.9791314006 -0.0029004626 0.4289377630 149 5.9200000000 0.0297739450 0.0289104317 0.0446866304 0.0069682119 0.6176490000 953055897 0 1783267328 -0.9824667573 -0.0043845051 0.4396472275 150 5.9600000000 0.0302614141 0.0289194382 0.0446866304 0.0069492195 0.6170500000 953057171 0 1781878784 -0.9859200716 -0.0051081590 0.4483430982 151 6.0000000000 0.0309361033 0.0289327936 0.0446866304 0.0069299800 0.6162650000 953058445 0 1783488512 -0.9889553785 -0.0053260871 0.4579631686 152 6.0400000000 0.0316748284 0.0289508333 0.0446866304 0.0069162113 0.6177260000 953059719 0 1782251520 -0.9917199016 -0.0046782959 0.4685825706 153 6.0800000000 0.0306232870 0.0289617644 0.0446866304 0.0069041970 0.6195380000 953060993 0 1783885824 -0.9956125021 -0.0046799760 0.4771626890 154 6.1200000000 0.0277381632 0.0289538189 0.0446866304 0.0069180418 0.6292650000 953062267 0 1782632448 -1.0011019707 -0.0024925210 0.4897336364 155 6.1600000000 0.0268720165 0.0289403879 0.0446866304 0.0069761569 0.6134140000 953063541 0 1784266752 -1.0030964613 -0.0025201535 0.4974766076 156 6.2000000000 0.0269857813 0.0289278584 0.0446866304 0.0070843716 0.6657150000 953064815 0 1783156736 -1.0076019764 -0.0014764799 0.5121485591 157 6.2400000000 0.0269881133 0.0289155033 0.0446866304 0.0071716463 0.6089250000 953066089 0 1781768192 -1.0097137690 -0.0008060522 0.5228550434 158 6.2800000000 0.0266826544 0.0289013714 0.0446866304 0.0072448802 0.6224780000 953067363 0 1783377920 -1.0127949715 -0.0001630299 0.5391961336 159 6.3200000000 0.0265468527 0.0288865631 0.0446866304 0.0072729663 0.6058680000 953068637 0 1782091776 -1.0135755539 -0.0006733424 0.5471164584 160 6.3600000000 0.0278146546 0.0288798637 0.0446866304 0.0073121155 0.6043410000 953069911 0 1783779328 -1.0139428377 -0.0004300960 0.5619501472 161 6.4000000000 0.0292989910 0.0288824669 0.0446866304 0.0072972593 0.6093550000 953071185 0 1782517760 -1.0136204958 -0.0014346093 0.5727889538 162 6.4400000000 0.0294361431 0.0288858847 0.0446866304 0.0072769573 0.6028550000 953072459 0 1784143872 -1.0136331320 -0.0033300486 0.5838913321 163 6.4800000000 0.0313045867 0.0289007234 0.0446866304 0.0072599702 0.6041720000 953073733 0 1782878208 -1.0139292479 -0.0038401077 0.5966418386 164 6.5200000000 0.0331947356 0.0289269064 0.0446866304 0.0072415838 0.6378740000 953075007 0 1781710848 -1.0135819912 -0.0043600611 0.6084800363 165 6.5600000000 0.0263160057 0.0289110827 0.0446866304 0.0072378742 0.6308110000 953076281 0 1783500800 -1.0164842606 0.0036056149 0.6265828609 166 6.6000000000 0.0314239673 0.0289262206 0.0446866304 0.0072475460 0.6078550000 953077555 0 1782386688 -1.0144587755 -0.0007506125 0.6379581690 167 6.6400000000 0.0346388444 0.0289604279 0.0446866304 0.0072497875 0.6039280000 953078829 0 1784123392 -1.0125205517 -0.0019754916 0.6481342316 168 6.6800000000 0.0352025628 0.0289975835 0.0446866304 0.0072489600 0.6057970000 953080103 0 1783242752 -1.0115665197 -0.0023176072 0.6601485014 169 6.7200000000 0.0334024094 0.0290236475 0.0446866304 0.0072354396 0.6089060000 953081377 0 1782132736 -1.0117472410 -0.0027024487 0.6742693782 170 6.7600000000 0.0263667740 0.0290080189 0.0446866304 0.0072257087 0.6320900000 953082651 0 1783775232 -1.0159559250 0.0062325476 0.6922062039 171 6.8000000000 0.0297420658 0.0290123115 0.0446866304 0.0072205691 0.6007590000 953083925 0 1782902784 -1.0142363310 0.0057009417 0.7016582489 172 6.8400000000 0.0311426725 0.0290246974 0.0446866304 0.0072019574 0.6299830000 953085199 0 1784512512 -1.0129834414 0.0056296624 0.7138055563 173 6.8800000000 0.0324637145 0.0290445761 0.0446866304 0.0071822263 0.6019850000 953086473 0 1783435264 -1.0127617121 0.0059367269 0.7272904515 174 6.9200000000 0.0333267525 0.0290691863 0.0446866304 0.0071621284 0.6034430000 953087747 0 1782378496 -1.0135505199 0.0068736644 0.7397085428 175 6.9600000000 0.0261157826 0.0290523097 0.0446866304 0.0071444405 0.6276630000 953089021 0 1784004608 -1.0153071880 0.0148075977 0.7525281310 176 7.0000000000 0.0266707670 0.0290387782 0.0446866304 0.0071278565 0.6172240000 953090295 0 1782996992 -1.0165221691 0.0146376453 0.7670709491 177 7.0400000000 0.0263873320 0.0290237983 0.0446866304 0.0071376417 0.6253280000 953091569 0 1781866496 -1.0155833960 0.0125300940 0.7742021084 178 7.0800000000 0.0292313863 0.0290249645 0.0446866304 0.0071219407 0.6008450000 953092843 0 1783533568 -1.0137325525 0.0092171356 0.7816644907 179 7.1200000000 0.0270396583 0.0290138734 0.0446866304 0.0071066451 0.6145860000 953094117 0 1782403072 -1.0138715506 0.0139873791 0.7948554754 180 7.1600000000 0.0307074748 0.0290232823 0.0446866304 0.0070884381 0.6319220000 953095391 0 1784020992 -1.0119253397 0.0128048398 0.8072535992 181 7.2000000000 0.0324671529 0.0290423092 0.0446866304 0.0070724261 0.6105170000 953096665 0 1782784000 -1.0095353127 0.0117601547 0.8183614016 182 7.2400000000 0.0332995988 0.0290657009 0.0446866304 0.0070545080 0.5997420000 953097939 0 1784393728 -1.0092556477 0.0112573849 0.8315156698 183 7.2800000000 0.0254504345 0.0290459453 0.0446866304 0.0070456855 0.6298010000 953099213 0 1783107584 -1.0133997202 0.0194761995 0.8488067389 184 7.3200000000 0.0280691162 0.0290406365 0.0446866304 0.0070270967 0.6013640000 953100487 0 1781768192 -1.0105774403 0.0165097043 0.8593125939 185 7.3600000000 0.0299293771 0.0290454405 0.0446866304 0.0070111818 0.6045890000 953101761 0 1783394304 -1.0082039833 0.0150599862 0.8736475706 186 7.4000000000 0.0250340179 0.0290238737 0.0446866304 0.0069979851 0.6235870000 953103035 0 1782149120 -1.0099749565 0.0195881743 0.8928505182 187 7.4400000000 0.0255674310 0.0290053901 0.0446866304 0.0069912103 0.6057330000 953104309 0 1783869440 -1.0067262650 0.0191360489 0.9012693763 188 7.4800000000 0.0298507847 0.0290098868 0.0446866304 0.0070033208 0.5948270000 953105583 0 1782853632 -1.0030721426 0.0185187645 0.9159586430 189 7.5200000000 0.0247259699 0.0289872206 0.0446866304 0.0069878065 0.6214760000 953106857 0 1781878784 -1.0024241209 0.0262698997 0.9340865016 190 7.5600000000 0.0282169450 0.0289831665 0.0446866304 0.0069751284 0.5922310000 953108131 0 1783635968 -0.9990570545 0.0217495970 0.9481508136 191 7.6000000000 0.0243561286 0.0289589412 0.0446866304 0.0069624875 0.6201020000 953109405 0 1782472704 -0.9989462495 0.0278159566 0.9649982452 192 7.6400000000 0.0311395600 0.0289702986 0.0446866304 0.0069611919 0.5892290000 953110679 0 1784156160 -0.9935017228 0.0272600688 0.9794375300 193 7.6800000000 0.0241488665 0.0289453171 0.0446866304 0.0069682127 0.6243550000 953111953 0 1783169024 -0.9953376651 0.0345420800 0.9980693460 194 7.7200000000 0.0245175175 0.0289224934 0.0446866304 0.0069633146 0.6020630000 953113227 0 1782259712 -0.9955043197 0.0301136728 1.0140877962 195 7.7600000000 0.0245581362 0.0289001120 0.0446866304 0.0069656494 0.5974770000 953114501 0 1784008704 -0.9942916632 0.0298158452 1.0269739628 196 7.8000000000 0.0250490140 0.0288804636 0.0446866304 0.0070014090 0.5975170000 953115775 0 1783107584 -0.9922754169 0.0329421274 1.0435432196 197 7.8400000000 0.0249890387 0.0288607102 0.0446866304 0.0070256866 0.5963040000 953117049 0 1782112256 -0.9905188680 0.0365051515 1.0554870367 198 7.8800000000 0.0249431264 0.0288409244 0.0446866304 0.0070432881 0.6281440000 953118323 0 1784008704 -0.9893665910 0.0402446762 1.0719709396 199 7.9200000000 0.0242867842 0.0288180393 0.0446866304 0.0070357006 0.5937390000 953119597 0 1782894592 -0.9875054955 0.0418901220 1.0876656771 200 7.9600000000 0.0236442387 0.0287921703 0.0446866304 0.0070254602 0.5932160000 953120871 0 1781895168 -0.9875559211 0.0410059467 1.1015785933 201 8.0000000000 0.0236447826 0.0287665614 0.0446866304 0.0070400593 0.5951820000 953122145 0 1783615488 -0.9868863821 0.0414819010 1.1200648546 202 8.0400000000 0.0234087389 0.0287400375 0.0446866304 0.0070562199 0.5888510000 953123419 0 1782624256 -0.9841577411 0.0425732285 1.1306200027 203 8.0800000000 0.0237116162 0.0287152669 0.0446866304 0.0070651325 0.5853950000 953124693 0 1784303616 -0.9818026423 0.0440891758 1.1475585699 204 8.1200000000 0.0232105274 0.0286882829 0.0446866304 0.0070565991 0.5836530000 953125967 0 1783373824 -0.9800468683 0.0440554954 1.1601493359 205 8.1600000000 0.0242071543 0.0286664238 0.0446866304 0.0070483731 0.5709190000 953127241 0 1782259712 -0.9768241644 0.0420570634 1.1713432074 206 8.1999999990 0.0264091101 0.0286554659 0.0446866304 0.0070395675 0.5680490000 953128515 0 1783869440 -0.9729002714 0.0400369018 1.1841256618 207 8.2400000000 0.0300083514 0.0286620016 0.0446866304 0.0070337732 0.5659780000 953129789 0 1782878208 -0.9675136209 0.0394863002 1.1974240541 208 8.2799999990 0.0336062349 0.0286857720 0.0446866304 0.0070197265 0.5747390000 953131063 0 1781858304 -0.9624182582 0.0381099992 1.2099269629 209 8.3200000000 0.0374257006 0.0287275898 0.0446866304 0.0070142025 0.5705310000 953132337 0 1783541760 -0.9569171071 0.0362624489 1.2226811647 210 8.3599999990 0.0407013483 0.0287846077 0.0446866304 0.0070326302 0.5756800000 953133611 0 1782386688 -0.9504877329 0.0338215567 1.2343746424 211 8.4000000000 0.0416130163 0.0288454058 0.0446866304 0.0070490255 0.5640610000 953134885 0 1784156160 -0.9451721907 0.0311215147 1.2473305464 212 8.4399999990 0.0434843861 0.0289144576 0.0446866304 0.0070342250 0.5650040000 953136159 0 1783169024 -0.9375541210 0.0322277471 1.2594678402 213 8.4800000000 0.0477394052 0.0290028377 0.0477394052 0.0070319041 0.5705040000 953137433 0 1782091776 -0.9300318360 0.0319013707 1.2732051611 214 8.5200000000 0.0234137066 0.0289767202 0.0477394052 0.0071658780 0.6069810000 953138707 0 1783775232 -0.9292411804 0.0556427017 1.2874691486 215 8.5600000000 0.0280660745 0.0289724847 0.0477394052 0.0071701517 0.5674700000 953139981 0 1782730752 -0.9202616811 0.0505635552 1.2983418703 216 8.6000000000 0.0231504142 0.0289455306 0.0477394052 0.0071567610 0.6242340000 953141255 0 1784410112 -0.9122391939 0.0597286969 1.3095833063 217 8.6400000000 0.0260397848 0.0289321401 0.0477394052 0.0071750857 0.5781710000 953142529 0 1783406592 -0.9026035666 0.0598872341 1.3260929585 218 8.6800000000 0.0261116903 0.0289192023 0.0477394052 0.0072216281 0.5819520000 953143803 0 1781964800 -0.8940652013 0.0595716611 1.3356837034 219 8.7200000000 0.0324650817 0.0289353935 0.0477394052 0.0072177842 0.5637750000 953145077 0 1783758848 -0.8824545145 0.0561267808 1.3469892740 220 8.7600000000 0.0401501320 0.0289863696 0.0477394052 0.0072164260 0.5571310000 953146351 0 1782648832 -0.8700218797 0.0534540787 1.3588006496 221 8.8000000000 0.0448022820 0.0290579348 0.0477394052 0.0072452724 0.5588890000 953147625 0 1784291328 -0.8591704965 0.0500190631 1.3705412149 222 8.8400000000 0.0472803190 0.0291400176 0.0477394052 0.0072487966 0.5574050000 953148899 0 1783021568 -0.8493315578 0.0492025279 1.3842591047 223 8.8800000000 0.0499361679 0.0292332739 0.0499361679 0.0072472047 0.5552340000 953150173 0 1781776384 -0.8381104469 0.0496940836 1.3949847221 224 8.9200000000 0.0532379225 0.0293404375 0.0532379225 0.0072491188 0.5562850000 953151447 0 1783259136 -0.8265940547 0.0493974201 1.4057772160 225 8.9600000000 0.0543614216 0.0294516419 0.0543614216 0.0072446139 0.5945640000 953152721 0 1781972992 -0.8159413338 0.0509439334 1.4142439365 226 9.0000000000 0.0542247966 0.0295612576 0.0543614216 0.0072299592 0.5497280000 953153995 0 1783640064 -0.8057051301 0.0549710691 1.4249681234 227 9.0400000000 0.0308881365 0.0295671029 0.0543614216 0.0072565294 0.5965330000 953155269 0 1782276096 -0.7993001938 0.0836307108 1.4338469505 228 9.0800000000 0.0325907990 0.0295803647 0.0543614216 0.0072641046 0.5580020000 953156543 0 1784020992 -0.7874616385 0.0877426788 1.4475362301 229 9.1200000000 0.0306948535 0.0295852315 0.0543614216 0.0073234496 0.5689340000 953157817 0 1782632448 -0.7773137093 0.0936340615 1.4551087618 230 9.1600000000 0.0299003050 0.0295866014 0.0543614216 0.0074218900 0.5624200000 953159091 0 1784250368 -0.7666629553 0.0985279977 1.4619692564 231 9.2000000000 0.0292761568 0.0295852574 0.0543614216 0.0076279956 0.5606260000 953160365 0 1783013376 -0.7575433254 0.1001906618 1.4694421291 232 9.2400000000 0.0287532117 0.0295816710 0.0543614216 0.0077874441 0.5509830000 953161639 0 1781583872 -0.7482094765 0.1036657467 1.4778003693 233 9.2800000000 0.0277943201 0.0295740000 0.0543614216 0.0079283201 0.5490910000 953162913 0 1783267328 -0.7388361096 0.1074815094 1.4851577282 234 9.3200000000 0.0267272163 0.0295618343 0.0543614216 0.0080304969 0.5885340000 953164187 0 1782009856 -0.7291427255 0.1122790873 1.4920989275 235 9.3600000000 0.0252441037 0.0295434609 0.0543614216 0.0081075126 0.5414060000 953165461 0 1783631872 -0.7194440365 0.1171088293 1.4993621111 236 9.4000000000 0.0243094657 0.0295212830 0.0543614216 0.0081663498 0.5468170000 953166735 0 1782378496 -0.7102630138 0.1207522526 1.5079084635 237 9.4400000000 0.0240435526 0.0294981702 0.0543614216 0.0081936387 0.5426740000 953168009 0 1783885824 -0.7003966570 0.1252189428 1.5142196417 238 9.4800000000 0.0239049923 0.0294746695 0.0543614216 0.0082136802 0.5435110000 953169283 0 1782611968 -0.6896160841 0.1313351095 1.5219753981 239 9.5200000000 0.0237058196 0.0294505320 0.0543614216 0.0082555251 0.5394410000 953170557 0 1784250368 -0.6789648533 0.1367871463 1.5294191837 240 9.5600000000 0.0234565306 0.0294255570 0.0543614216 0.0083076623 0.5469890000 953171831 0 1783013376 -0.6688886285 0.1418201178 1.5380811691 241 9.6000000000 0.0234701931 0.0294008459 0.0543614216 0.0083593289 0.5357900000 953173105 0 1781583872 -0.6595992446 0.1426884830 1.5467685461 242 9.6400000000 0.0233632661 0.0293758973 0.0543614216 0.0083788115 0.5345970000 953174379 0 1783250944 -0.6498669982 0.1454228610 1.5552991629 243 9.6800000000 0.0227970704 0.0293488239 0.0543614216 0.0083923624 0.5995870000 953175653 0 1782026240 -0.6390882134 0.1519712955 1.5630235672 244 9.7200000000 0.0226324797 0.0293212979 0.0543614216 0.0084362606 0.5629020000 953176927 0 1783631872 -0.6278383136 0.1585643589 1.5710906982 245 9.7600000000 0.0258133821 0.0293069799 0.0543614216 0.0084912745 0.5353560000 953178201 0 1782267904 -0.6166321039 0.1580253690 1.5792951584 246 9.8000000000 0.0261746813 0.0292942470 0.0543614216 0.0085084448 0.5319330000 953179475 0 1783996416 -0.6062035561 0.1605175883 1.5880184174 247 9.8400000000 0.0252214633 0.0292777580 0.0543614216 0.0085129645 0.5326350000 953180749 0 1782738944 -0.5970177650 0.1616484821 1.5975294113 248 9.8800000000 0.0248773824 0.0292600145 0.0543614216 0.0084975943 0.5303500000 953182023 0 1784377344 -0.5877997875 0.1637276858 1.6058694124 249 9.9200000000 0.0242841449 0.0292400311 0.0543614216 0.0084814709 0.5285830000 953183297 0 1783119872 -0.5779731274 0.1665855497 1.6131573915 250 9.9600000000 0.0226938147 0.0292138462 0.0543614216 0.0084651282 0.5359610000 953184571 0 1781837824 -0.5687730312 0.1703588814 1.6228016615 251 10.0000000000 0.0225406736 0.0291872599 0.0543614216 0.0084486076 0.5352750000 953185845 0 1783504896 -0.5587514639 0.1735661924 1.6314402819 252 10.0400000000 0.0223575812 0.0291601580 0.0543614216 0.0084345545 0.5411110000 953187119 0 1782394880 -0.5502635241 0.1728352904 1.6417778730 253 10.0800000000 0.0220897496 0.0291322117 0.0543614216 0.0084187912 0.5280870000 953188393 0 1784012800 -0.5427508354 0.1699784547 1.6515748501 254 10.1200000000 0.0231625587 0.0291087091 0.0543614216 0.0084377777 0.5221140000 953189667 0 1782775808 -0.5327401757 0.1726741493 1.6595714092 255 10.1600000000 0.0233392473 0.0290860838 0.0543614216 0.0084531877 0.5160130000 953190941 0 1784393728 -0.5218361020 0.1794072837 1.6687281132 256 10.2000000000 0.0228321832 0.0290616545 0.0543614216 0.0084402407 0.5168300000 953192215 0 1783140352 -0.5107924342 0.1848034412 1.6775497198 257 10.2400000000 0.0225042310 0.0290361392 0.0543614216 0.0084256147 0.5180850000 953193489 0 1781768192 -0.5015147924 0.1848278493 1.6861225367 258 10.2800000000 0.0238870829 0.0290161817 0.0543614216 0.0084093896 0.5165490000 953236747 0 1783377920 -0.4908342063 0.1885958314 1.6949714422 259 10.3200000000 0.0245976504 0.0289991217 0.0543614216 0.0084018566 0.5177420000 953238021 0 1782157312 -0.4802021086 0.1917608827 1.7013096809 260 10.3600000000 0.0214257054 0.0289699932 0.0543614216 0.0084098695 0.5411800000 953239295 0 1783775232 -0.4710964561 0.1964629591 1.7099431753 261 10.4000000000 0.0232970491 0.0289482577 0.0543614216 0.0084076499 0.5141450000 953240569 0 1782599680 -0.4610159397 0.1941488236 1.7162905931 262 10.4400000000 0.0237149801 0.0289282834 0.0543614216 0.0083944924 0.5115370000 953241843 0 1784266752 -0.4514031112 0.1940072030 1.7234681845 263 10.4800000000 0.0235084929 0.0289076758 0.0543614216 0.0083803430 0.5490180000 953243117 0 1782980608 -0.4406219125 0.1957210600 1.7296997309 264 10.5200000000 0.0232526734 0.0288862554 0.0543614216 0.0083694284 0.5088020000 953244391 0 1781768192 -0.4303574860 0.1956447512 1.7357870340 265 10.5600000000 0.0227729883 0.0288631864 0.0543614216 0.0083538404 0.5079440000 953245665 0 1783361536 -0.4192191362 0.1980194300 1.7425166368 266 10.6000000000 0.0212874468 0.0288347062 0.0543614216 0.0083434162 0.5191990000 953246939 0 1782157312 -0.4076790810 0.2017699629 1.7465833426 267 10.6400000000 0.0211077649 0.0288057664 0.0543614216 0.0083394428 0.5212650000 953248213 0 1783758848 -0.3964811265 0.2010258138 1.7506774664 268 10.6800000000 0.0220427848 0.0287805314 0.0543614216 0.0083315785 0.5071450000 953249487 0 1782484992 -0.3848115504 0.1996466517 1.7573298216 269 10.7200000000 0.0218891818 0.0287549130 0.0543614216 0.0083199224 0.5070880000 953250761 0 1784156160 -0.3729061782 0.1997503936 1.7601319551 270 10.7600000000 0.0207304861 0.0287251929 0.0543614216 0.0083116225 0.5353740000 953252035 0 1782886400 -0.3479732573 0.2054950595 1.7698085308 271 10.8000000000 0.0206556916 0.0286954161 0.0543614216 0.0083275335 0.5362080000 953253309 0 1784520704 -0.3336623907 0.2093136907 1.7731373310 272 10.8400000000 0.0205309968 0.0286653998 0.0543614216 0.0083878474 0.5272320000 953254583 0 1783267328 -0.3217173815 0.2076014429 1.7769614458 273 10.8800000000 0.0204669461 0.0286353689 0.0543614216 0.0083956085 0.5661440000 953255857 0 1781878784 -0.3091274798 0.2083938271 1.7815051079 274 10.9200000000 0.0203796420 0.0286052385 0.0543614216 0.0084035386 0.5284960000 953257131 0 1783504896 -0.2958793342 0.2096959054 1.7852296829 275 10.9600000000 0.0203268081 0.0285751351 0.0543614216 0.0084084353 0.5326200000 953258405 0 1782251520 -0.2829836607 0.2097513676 1.7880587578 276 11.0000000000 0.0202140417 0.0285448413 0.0543614216 0.0084052123 0.5276270000 953259679 0 1783894016 -0.2695486248 0.2117384374 1.7919300795 277 11.0400000000 0.0200366061 0.0285141256 0.0543614216 0.0084106461 0.5409040000 953260953 0 1782640640 -0.2560504079 0.2133706659 1.7952300310 278 11.0800000000 0.0199292302 0.0284832447 0.0543614216 0.0084156653 0.5326850000 953262227 0 1784131584 -0.2424791604 0.2152604014 1.7988780737 279 11.1200000000 0.0198238734 0.0284522076 0.0543614216 0.0084249157 0.5505170000 953263501 0 1782874112 -0.2285693586 0.2171262950 1.8026837111 280 11.1600000000 0.0197298378 0.0284210562 0.0543614216 0.0084327258 0.5534610000 953264775 0 1784545280 -0.2145838439 0.2197296023 1.8059235811 281 11.2000000000 0.0196754429 0.0283899331 0.0543614216 0.0084383438 0.5419160000 953266049 0 1783308288 -0.2014309317 0.2206573933 1.8087974787 282 11.2400000000 0.0196273178 0.0283588599 0.0543614216 0.0084332976 0.5499300000 953267323 0 1782161408 -0.1895838529 0.2197365761 1.8133748770 283 11.2800000000 0.0204287861 0.0283308385 0.0543614216 0.0084185269 0.5290500000 953268597 0 1783910400 -0.1768898964 0.2204543948 1.8166152239 284 11.3200000000 0.0195283480 0.0282998438 0.0543614216 0.0084075471 0.5543380000 953269871 0 1782886400 -0.1647023410 0.2233263403 1.8214428425 285 11.3600000000 0.0192491729 0.0282680871 0.0543614216 0.0084046874 0.5599220000 953271145 0 1781846016 -0.1532017291 0.2246850878 1.8256642818 286 11.4000000000 0.0190346390 0.0282358023 0.0543614216 0.0083960919 0.5576110000 953272419 0 1783513088 -0.1427212954 0.2249091566 1.8296921253 287 11.4400000000 0.0189106278 0.0282033104 0.0543614216 0.0083815465 0.5603880000 953273693 0 1782480896 -0.1332391798 0.2246488035 1.8338299990 288 11.4800000000 0.0187999886 0.0281706600 0.0543614216 0.0083677140 0.5602840000 953274967 0 1784160256 -0.1243903637 0.2246825695 1.8378609419 289 11.5200000000 0.0187016707 0.0281378953 0.0543614216 0.0083543335 0.5611500000 953276241 0 1782992896 -0.1158945113 0.2246515602 1.8443342447 290 11.5600000000 0.0186050404 0.0281050234 0.0543614216 0.0083452214 0.5610610000 953277515 0 1781620736 -0.1076002941 0.2251874506 1.8501700163 291 11.6000000000 0.0184641723 0.0280718933 0.0543614216 0.0083339379 0.5678680000 953278789 0 1783123968 -0.1001020968 0.2244017273 1.8572038412 292 11.6400000000 0.0183231700 0.0280385073 0.0543614216 0.0083212627 0.6032120000 953280063 0 1781837824 -0.0921012387 0.2255711108 1.8630200624 293 11.6800000000 0.0182387661 0.0280050610 0.0543614216 0.0083070617 0.5628400000 953281337 0 1783377920 -0.0851537883 0.2259117812 1.8698086739 294 11.7200000000 0.0181825086 0.0279716510 0.0543614216 0.0082941904 0.5680070000 953282611 0 1782157312 -0.0790602788 0.2252178937 1.8769829273 295 11.7600000000 0.0185017716 0.0279395497 0.0543614216 0.0082854889 0.5572900000 953283885 0 1783631872 -0.0733783394 0.2248403430 1.8836721182 296 11.8000000000 0.0190395396 0.0279094821 0.0543614216 0.0082763278 0.5619060000 953285159 0 1782247424 -0.0674882233 0.2244371623 1.8897815943 297 11.8400000000 0.0194591060 0.0278810297 0.0543614216 0.0082675186 0.5654520000 953286433 0 1783902208 -0.0626015589 0.2234985679 1.8967819214 298 11.8800000000 0.0200460721 0.0278547379 0.0543614216 0.0082621478 0.5706930000 953287707 0 1782611968 -0.0577028617 0.2222214192 1.9040298462 299 11.9200000000 0.0178279653 0.0278212035 0.0543614216 0.0082522740 0.6004770000 953288981 0 1784250368 -0.0528770201 0.2246644795 1.9139964581 300 11.9600000000 0.0195127446 0.0277935086 0.0543614216 0.0082399682 0.5786630000 953290255 0 1783042048 -0.0477671959 0.2236581147 1.9210500717 301 12.0000000000 0.0179417636 0.0277607786 0.0543614216 0.0082265017 0.6303010000 953291529 0 1781989376 -0.0433052406 0.2256433517 1.9312410355 302 12.0400000000 0.0177051276 0.0277274817 0.0543614216 0.0082152342 0.6002350000 953292803 0 1783742464 -0.0393838510 0.2257177532 1.9411599636 303 12.0800000000 0.0175474845 0.0276938844 0.0543614216 0.0082086791 0.6035820000 953294077 0 1782636544 -0.0352408327 0.2262063920 1.9510699511 304 12.1200000000 0.0173404496 0.0276598270 0.0543614216 0.0082064585 0.6045190000 953295351 0 1784266752 -0.0314008333 0.2266527563 1.9613018036 305 12.1600000000 0.0171213299 0.0276252746 0.0543614216 0.0082027368 0.6096020000 953296625 0 1783410688 -0.0277891718 0.2268104553 1.9726533890 306 12.2000000000 0.0169023406 0.0275902323 0.0543614216 0.0081953128 0.6088710000 953297899 0 1782370304 -0.0242488552 0.2270090878 1.9841905832 307 12.2400000000 0.0167525839 0.0275549305 0.0543614216 0.0081963254 0.6138460000 953299173 0 1784012800 -0.0210468099 0.2278698534 1.9956901073 308 12.2800000000 0.0166547913 0.0275195405 0.0543614216 0.0081992105 0.6105650000 953300447 0 1783005184 -0.0184663944 0.2280949801 2.0072941780 309 12.3200000000 0.0162922759 0.0274832063 0.0543614216 0.0082096263 0.6270170000 953301721 0 1782005760 -0.0166200362 0.2281305641 2.0183784962 310 12.3600000000 0.0161117688 0.0274465242 0.0543614216 0.0082273182 0.6274260000 953302995 0 1783648256 -0.0150182424 0.2277883738 2.0302879810 311 12.4000000000 0.0159453638 0.0274095430 0.0543614216 0.0082400566 0.6362860000 953304269 0 1782624256 -0.0128676565 0.2287794203 2.0410461426 312 12.4400000000 0.0155855455 0.0273716456 0.0543614216 0.0082746003 0.6260660000 953305543 0 1784504320 -0.0106513668 0.2289025337 2.0650012493 313 12.4800000000 0.0153534180 0.0273332487 0.0543614216 0.0082677602 0.6198220000 953306817 0 1783521280 -0.0101177171 0.2289399207 2.0756297112 314 12.5200000000 0.0151387323 0.0272944126 0.0543614216 0.0082592952 0.6178380000 953308091 0 1782349824 -0.0101221940 0.2280430496 2.0882301331 315 12.5600000000 0.0147768511 0.0272546744 0.0543614216 0.0082580804 0.6219840000 953309365 0 1784123392 -0.0097649405 0.2286757827 2.0997109413 316 12.6000000000 0.0144647500 0.0272141999 0.0543614216 0.0082471072 0.6211280000 953310639 0 1783152640 -0.0096518304 0.2293022126 2.1119968891 317 12.6400000000 0.0140205780 0.0271725796 0.0543614216 0.0082341234 0.6213640000 953311913 0 1782153216 -0.0100321528 0.2291576266 2.1237027645 318 12.6800000000 0.0139236692 0.0271309164 0.0543614216 0.0082211386 0.6685120000 953313187 0 1783742464 -0.0106974095 0.2287863046 2.1349771023 319 12.7200000000 0.0136369988 0.0270886157 0.0543614216 0.0082082304 0.6485900000 953314461 0 1782751232 -0.0114802402 0.2292859852 2.1450350285 320 12.7600000000 0.0133544253 0.0270456964 0.0543614216 0.0081953932 0.6495580000 953315735 0 1784410112 -0.0127277579 0.2297961861 2.1553115845 321 12.8000000000 0.0130755361 0.0270021756 0.0543614216 0.0081854883 0.6575070000 953317009 0 1783377920 -0.0149080381 0.2290204465 2.1658735275 322 12.8400000000 0.0127872480 0.0269580299 0.0543614216 0.0081753204 0.6645390000 953318283 0 1782497280 -0.0165786985 0.2297202647 2.1751379967 323 12.8800000000 0.0125010256 0.0269132714 0.0543614216 0.0081669071 0.6758940000 953319557 0 1784303616 -0.0185752753 0.2289783955 2.1837420464 324 12.9200000000 0.0122072389 0.0268678824 0.0543614216 0.0081556498 0.6766940000 953320831 0 1783107584 -0.0206021015 0.2287326753 2.1928577423 325 12.9600000000 0.0119352965 0.0268219360 0.0543614216 0.0081433767 0.6767780000 953322105 0 1782153216 -0.0220205411 0.2299533784 2.2017810345 326 13.0000000000 0.0117094209 0.0267755786 0.0543614216 0.0081318373 0.7367990000 953323379 0 1783795712 -0.0240088366 0.2299367636 2.2088973522 327 13.0400000000 0.0114456126 0.0267286979 0.0543614216 0.0081213402 0.7043670000 953324653 0 1782640640 -0.0260423571 0.2307066321 2.2185032368 328 13.0800000000 0.0112321535 0.0266814524 0.0543614216 0.0081097083 0.7153830000 953325927 0 1784410112 -0.0266249906 0.2337291241 2.2247712612 329 13.1200000000 0.0110177742 0.0266338424 0.0543614216 0.0080983576 0.7232020000 953327201 0 1783279616 -0.0282783005 0.2348740548 2.2338063717 330 13.1600000000 0.0108346520 0.0265859661 0.0543614216 0.0080877695 0.7359350000 953328475 0 1782222848 -0.0302154776 0.2354855090 2.2420098782 331 13.2000000000 0.0107029257 0.0265379810 0.0543614216 0.0080760873 0.7458820000 953329749 0 1783996416 -0.0319941081 0.2364348471 2.2522368431 332 13.2400000000 0.0106451130 0.0264901110 0.0543614216 0.0080653093 0.7469810000 953331023 0 1782771712 -0.0338644721 0.2372169495 2.2611582279 333 13.2800000000 0.0105416868 0.0264422178 0.0543614216 0.0080536466 0.7471060000 953332297 0 1784401920 -0.0360236876 0.2378012985 2.2710464001 334 13.3200000000 0.0104576247 0.0263943597 0.0543614216 0.0080427421 0.7564450000 953333571 0 1783435264 -0.0383398607 0.2380460650 2.2795479298 335 13.3600000000 0.0103404485 0.0263464376 0.0543614216 0.0080307541 0.7590690000 953334845 0 1782353920 -0.0404470451 0.2392724901 2.2884390354 336 13.4000000000 0.0102095203 0.0262984111 0.0543614216 0.0080188308 0.7654490000 953336119 0 1784020992 -0.0419663638 0.2414096892 2.2963979244 337 13.4400000000 0.0100791343 0.0262502827 0.0543614216 0.0080183228 0.7644200000 953337393 0 1783013376 -0.0436958037 0.2440219820 2.3039512634 338 13.4800000000 0.0099295145 0.0262019964 0.0543614216 0.0080257873 0.7675110000 953338667 0 1781739520 -0.0455394052 0.2458784580 2.3102707863 339 13.5200000000 0.0098284949 0.0261536969 0.0543614216 0.0080433554 0.7842160000 953339941 0 1783422976 -0.0479758568 0.2460658103 2.3158879280 340 13.5600000000 0.0097501390 0.0261054512 0.0543614216 0.0080401937 0.7895710000 953341215 0 1782226944 -0.0503606573 0.2466218472 2.3209972382 341 13.6000000000 0.0097071109 0.0260573622 0.0543614216 0.0080337481 0.7976990000 953342489 0 1783877632 -0.0525271185 0.2471944839 2.3258330822 342 13.6400000000 0.0096162176 0.0260092887 0.0543614216 0.0080259379 0.8078410000 953343763 0 1782730752 -0.0546630062 0.2477012277 2.3315336704 343 13.6800000000 0.0095529482 0.0259613110 0.0543614216 0.0080143895 0.8157380000 953345037 0 1784537088 -0.0566411614 0.2481106371 2.3364045620 344 13.7200000000 0.0095183142 0.0259135116 0.0543614216 0.0080027775 0.8115050000 953346311 0 1783537664 -0.0577380694 0.2498516887 2.3419513702 345 13.7600000000 0.0094488952 0.0258657881 0.0543614216 0.0079951963 0.8141620000 953347585 0 1782091776 -0.0596651211 0.2498450875 2.3474674225 346 13.8000000000 0.0093997912 0.0258181985 0.0543614216 0.0079899727 0.8124970000 953348859 0 1783742464 -0.0613379292 0.2498205602 2.3525397778 347 13.8400000000 0.0093324734 0.0257706892 0.0543614216 0.0079790656 0.8162750000 953350133 0 1782751232 -0.0636740252 0.2485821992 2.3570911884 348 13.8800000000 0.0092784567 0.0257232977 0.0543614216 0.0079683906 0.8151620000 953351407 0 1784520704 -0.0642604604 0.2508701682 2.3628613949 349 13.9200000000 0.0091856997 0.0256759121 0.0543614216 0.0079661520 0.8222090000 953352681 0 1783427072 -0.0659326762 0.2506852448 2.3686351776 350 13.9600000000 0.0091099301 0.0256285807 0.0543614216 0.0079571881 0.8128120000 953353955 0 1781862400 -0.0679502711 0.2493959814 2.3774631023 351 14.0000000000 0.0091069583 0.0255815105 0.0543614216 0.0079466188 0.8169460000 953355229 0 1783488512 -0.0680290982 0.2501206994 2.3817565441 352 14.0400000000 0.0093098953 0.0255352844 0.0543614216 0.0079377912 0.8052760000 953356503 0 1782218752 -0.0687038228 0.2495507002 2.3866791725 353 14.0800000000 0.0092637064 0.0254891892 0.0543614216 0.0079265195 0.7979250000 953357777 0 1784033280 -0.0690730736 0.2486437559 2.3909575939 354 14.1200000000 0.0090449620 0.0254427366 0.0543614216 0.0079153923 0.8507130000 953359051 0 1782898688 -0.0687036887 0.2494246364 2.3955914974 355 14.1600000000 0.0092181442 0.0253970335 0.0543614216 0.0079045101 0.7977510000 953360325 0 1784668160 -0.0693497807 0.2478629351 2.4005901814 356 14.2000000000 0.0090119494 0.0253510080 0.0543614216 0.0078951940 0.8179120000 953361599 0 1783537664 -0.0690029636 0.2479412854 2.4050617218 357 14.2400000000 0.0089822970 0.0253051573 0.0543614216 0.0078845605 0.8195290000 953362873 0 1781710848 -0.0686765313 0.2484767288 2.4106774330 358 14.2800000000 0.0090952273 0.0252598782 0.0543614216 0.0078744027 0.8021010000 953364147 0 1783361536 -0.0690774694 0.2470176816 2.4162683487 359 14.3200000000 0.0090062572 0.0252146034 0.0543614216 0.0078647014 0.8029670000 953365421 0 1782390784 -0.0696984828 0.2453631461 2.4217226505 360 14.3600000000 0.0090389056 0.0251696710 0.0543614216 0.0078561561 0.8026600000 953366695 0 1784156160 -0.0698829517 0.2440449595 2.4278886318 361 14.4000000000 0.0090220692 0.0251249408 0.0543614216 0.0078517284 0.8106260000 953367969 0 1783005184 -0.0700202584 0.2439420074 2.4343652725 362 14.4400000000 0.0089729298 0.0250803219 0.0543614216 0.0078449235 0.8053580000 953369243 0 1784631296 -0.0700562447 0.2442297041 2.4409210682 363 14.4800000000 0.0089569204 0.0250359049 0.0543614216 0.0078344394 0.8143900000 953370517 0 1783361536 -0.0699577332 0.2451262176 2.4481079578 364 14.5200000000 0.0085666664 0.0249906597 0.0543614216 0.0078248377 0.7867840000 953371791 0 1782411264 -0.0702374354 0.2448065430 2.4549758434 365 14.5600000000 0.0086564003 0.0249459083 0.0543614216 0.0078141991 0.8067710000 953373065 0 1784012800 -0.0708659366 0.2440022528 2.4622881413 366 14.6000000000 0.0087381573 0.0249016248 0.0543614216 0.0078037990 0.8097760000 953374339 0 1782861824 -0.0710458457 0.2447295487 2.4702005386 367 14.6400000000 0.0082351184 0.0248562120 0.0543614216 0.0077935596 0.7953990000 953375613 0 1781710848 -0.0708739534 0.2459439337 2.4767863750 368 14.6800000000 0.0082472721 0.0248110790 0.0543614216 0.0077840555 0.8084100000 953376887 0 1783488512 -0.0711407438 0.2467722893 2.4848432541 369 14.7200000000 0.0083256373 0.0247664030 0.0543614216 0.0077829948 0.8322710000 953378161 0 1782374400 -0.0719992444 0.2465077788 2.4924645424 370 14.7600000000 0.0082745822 0.0247218305 0.0543614216 0.0077805423 0.8298960000 953379435 0 1784164352 -0.0722334608 0.2469644397 2.5003640652 371 14.8000000000 0.0082323793 0.0246773846 0.0543614216 0.0077740914 0.8361510000 953380709 0 1782874112 -0.0723218471 0.2467420101 2.5076134205 372 14.8400000000 0.0081947157 0.0246330763 0.0543614216 0.0077698690 0.8341830000 953381983 0 1784528896 -0.0725527108 0.2463087142 2.5146603584 373 14.8800000000 0.0081616584 0.0245889170 0.0543614216 0.0077695531 0.8549520000 953383257 0 1783435264 -0.0727101043 0.2461734414 2.5220096111 374 14.9200000000 0.0081239454 0.0245448930 0.0543614216 0.0077655119 0.8705010000 953384531 0 1782099968 -0.0729126483 0.2455411404 2.5293569565 375 14.9600000000 0.0080894697 0.0245010119 0.0543614216 0.0077684708 0.8503140000 953385805 0 1783750656 -0.0726821795 0.2451671511 2.5363380909 376 15.0000000000 0.0080517540 0.0244572639 0.0543614216 0.0077680188 0.8559340000 953387079 0 1782505472 -0.0717170835 0.2465086579 2.5437412262 377 15.0400000000 0.0080004688 0.0244136119 0.0543614216 0.0077605250 0.8801050000 953388353 0 1784139776 -0.0694686770 0.2476917356 2.5569448471 378 15.0800000000 0.0079211481 0.0243699810 0.0543614216 0.0077502889 0.8900620000 953389627 0 1783013376 -0.0675347075 0.2489410490 2.5634014606 379 15.1200000000 0.0078496048 0.0243263917 0.0543614216 0.0077400737 0.8849900000 953390901 0 1781620736 -0.0656488389 0.2495046854 2.5690591335 380 15.1600000000 0.0077990340 0.0242828986 0.0543614216 0.0077310017 0.9276120000 953392175 0 1783250944 -0.0628958419 0.2506545484 2.5744099617 381 15.2000000000 0.0077789472 0.0242395812 0.0543614216 0.0077210682 0.9125550000 953393449 0 1782009856 -0.0605418459 0.2516887188 2.5795047283 382 15.2400000000 0.0077455444 0.0241964031 0.0543614216 0.0077124253 0.9173990000 953394723 0 1783631872 -0.0583184920 0.2521734834 2.5843093395 383 15.2800000000 0.0076979171 0.0241533261 0.0543614216 0.0077030619 0.9229070000 953395997 0 1782378496 -0.0556466803 0.2532240450 2.5888197422 384 15.3200000000 0.0076508271 0.0241103508 0.0543614216 0.0076930360 0.9323770000 953397271 0 1783869440 -0.0528317727 0.2539459765 2.5926306248 385 15.3600000000 0.0076222275 0.0240675245 0.0543614216 0.0076837357 0.9398830000 953398545 0 1782599680 -0.0503209382 0.2535602450 2.5951974392 386 15.4000000000 0.0075830822 0.0240248187 0.0543614216 0.0076801858 0.9359840000 953399819 0 1784250368 -0.0472688377 0.2542500496 2.5973358154 387 15.4400000000 0.0075314897 0.0239822003 0.0543614216 0.0076800535 0.9424280000 953401093 0 1782980608 -0.0435752124 0.2564043105 2.5994653702 388 15.4800000000 0.0074752965 0.0239396567 0.0543614216 0.0076704879 0.9392250000 953402367 0 1781583872 -0.0405459516 0.2576940358 2.6003687382 389 15.5200000000 0.0074242242 0.0238972006 0.0543614216 0.0076610785 0.9487890000 953403641 0 1783234560 -0.0379219390 0.2578617930 2.6013383865 390 15.5600000000 0.0073444047 0.0238547575 0.0543614216 0.0076513051 0.9436100000 953404915 0 1781964800 -0.0340526663 0.2609692514 2.6024999619 391 15.6000000000 0.0073167868 0.0238124609 0.0543614216 0.0076563597 0.9365910000 953406189 0 1783504896 -0.0308679231 0.2613257468 2.6038391590 392 15.6400000000 0.0072133825 0.0237701163 0.0543614216 0.0076471856 0.9667410000 953407463 0 1782267904 -0.0280320365 0.2611272633 2.6041750908 393 15.6800000000 0.0069915112 0.0237274227 0.0543614216 0.0076381363 0.9190920000 953408737 0 1783885824 -0.0258717332 0.2595966160 2.6045012474 394 15.7200000000 0.0066298852 0.0236840279 0.0543614216 0.0076305937 0.9089190000 953410011 0 1782632448 -0.0238999240 0.2577049136 2.6049308777 395 15.7600000000 0.0072077238 0.0236423158 0.0543614216 0.0076343476 0.9688010000 953411285 0 1784266752 -0.0206122547 0.2579753101 2.6063437462 396 15.8000000000 0.0085046673 0.0236040894 0.0543614216 0.0076283715 0.9643090000 953412559 0 1783013376 -0.0170898139 0.2580772638 2.6084268093 397 15.8400000000 0.0379960127 0.0236403411 0.0543614216 0.0077493340 1.0049420000 953413833 0 1781620736 -0.0150508946 0.2576646805 2.6396214962 398 15.8800000000 0.0672647581 0.0237499502 0.0672647581 0.0078546293 1.0422830000 953415107 0 1783140352 -0.0126945814 0.2558351755 2.6685025692 399 15.9200000000 0.1078777388 0.0239607967 0.1078777388 0.0080921268 1.0302680000 953416381 0 1781899264 -0.0090968255 0.2579944134 2.7077510357 400 15.9600000000 0.1071120724 0.0241686749 0.1078777388 0.0080856570 1.0888560000 953417655 0 1783377920 -0.0047896015 0.2588081658 2.7074964046 401 16.0000000000 0.1048971936 0.0243699929 0.1078777388 0.0080813364 1.0123150000 953418929 0 1782140928 -0.0002073086 0.2593933046 2.7059369087 402 16.0400000000 0.1040103734 0.0245681033 0.1078777388 0.0080738051 0.9901280000 953420203 0 1783758848 0.0053660735 0.2599286735 2.7053406239 403 16.0800000000 0.1033502892 0.0247635926 0.1078777388 0.0080690694 1.0013540000 953421477 0 1782362112 0.0100155864 0.2594304085 2.7063212395 404 16.1200000000 0.1028076783 0.0249567711 0.1078777388 0.0080609076 0.9533080000 953422751 0 1784029184 0.0149716102 0.2598450184 2.7049155235 405 16.1600000000 0.1023918539 0.0251479688 0.1078777388 0.0080529363 0.9158150000 953424025 0 1782775808 0.0203775167 0.2602718472 2.7060565948 406 16.2000000000 0.1021243557 0.0253375658 0.1078777388 0.0080446804 0.8759390000 953425299 0 1784393728 0.0262495354 0.2619132996 2.7084271908 407 16.2400000000 0.1017639711 0.0255253457 0.1078777388 0.0080373268 0.8465610000 953426573 0 1783148544 0.0313455239 0.2626607120 2.7100784779 408 16.2800000000 0.1014742255 0.0257114949 0.1078777388 0.0080391891 0.8422690000 953427847 0 1781628928 0.0366028547 0.2631689310 2.7126643658 409 16.3200000000 0.1012378484 0.0258961559 0.1078777388 0.0080417167 0.8375490000 953429121 0 1783259136 0.0432151258 0.2666545808 2.7150530815 410 16.3600000000 0.1010439694 0.0260794432 0.1078777388 0.0080336272 0.8396320000 953430395 0 1781972992 0.0493219346 0.2696826160 2.7192645073 411 16.3999999990 0.1009322107 0.0262615668 0.1078777388 0.0080284851 0.8261950000 953431669 0 1783623680 0.0527348854 0.2682754397 2.7208268642 412 16.4400000000 0.1007808447 0.0264424388 0.1078777388 0.0080439750 0.8178780000 953432943 0 1782386688 0.0578249730 0.2680850625 2.7269306183 413 16.4800000000 0.1005987823 0.0266219941 0.1078777388 0.0080579988 0.8093820000 953434217 0 1783894016 0.0639772713 0.2694359422 2.7335374355 414 16.5200000000 0.1005103961 0.0268004685 0.1078777388 0.0080545969 0.8011460000 953435491 0 1782521856 0.0687185079 0.2672743201 2.7370035648 415 16.5599999990 0.1004399732 0.0269779131 0.1078777388 0.0080681542 0.7893870000 953436765 0 1784139776 0.0717961267 0.2614095807 2.7425127029 416 16.6000000000 0.1001457497 0.0271537973 0.1078777388 0.0081443430 0.7811360000 953438039 0 1782853632 0.0780189931 0.2612844110 2.7479050159 417 16.6400000000 0.0997946858 0.0273279961 0.1078777388 0.0081740523 0.7611140000 953439313 0 1784520704 0.0842291340 0.2626291215 2.7491567135 418 16.6800000000 0.0995119587 0.0275006850 0.1078777388 0.0081770684 0.7508740000 953440587 0 1783267328 0.0863847211 0.2590003014 2.7482819557 419 16.7199999990 0.0991443768 0.0276716723 0.1078777388 0.0082050465 0.7395450000 953441861 0 1781878784 0.0939929634 0.2615820169 2.7535607815 420 16.7600000000 0.0983204693 0.0278398838 0.1078777388 0.0081957470 0.7211790000 953443135 0 1783361536 0.1012887508 0.2621380985 2.7526190281 421 16.8000000000 0.0979707688 0.0280064654 0.1078777388 0.0082069061 0.7105940000 953444409 0 1782009856 0.1052228808 0.2560845613 2.7531316280 422 16.8400000000 0.2135668099 0.0284461819 0.2135668099 0.0087337794 0.7767900000 953445683 0 1783648256 0.1115637720 0.4150114954 2.8007838726 423 16.8799999990 0.3051761687 0.0291003899 0.3051761687 0.0088871111 0.8661130000 953446957 0 1782358016 0.1197020262 0.5119701624 2.8229231834 424 16.9200000000 0.4159935713 0.0300128738 0.4159935713 0.0091290801 0.9077050000 953448231 0 1784012800 0.1254704297 0.6240264773 2.8426575661 425 16.9600000000 0.4534773529 0.0310092608 0.4534773529 0.0091562575 0.9007360000 953449505 0 1782726656 0.1344543546 0.6628901958 2.8472507000 426 17.0000000000 0.5691772699 0.0322725660 0.5691772699 0.0094659694 0.9425650000 953450779 0 1784250368 0.1465134472 0.7849091887 2.8549563885 427 17.0400000000 0.6995093822 0.0338351815 0.6995093822 0.0097640262 1.0145290000 953452053 0 1782980608 0.1527062505 0.9163606763 2.8583371639 428 17.0800000000 0.7207075357 0.0354400235 0.7207075357 0.0097557679 1.0010060000 953453327 0 1781710848 0.1565087438 0.9368551970 2.8547158241 429 17.1200000000 0.7247764468 0.0370468683 0.7247764468 0.0097445288 0.9779650000 953454601 0 1783361536 0.1677475572 0.9403135777 2.8519241810 430 17.1600000000 0.7197548151 0.0386345612 0.7247764468 0.0097354877 0.9546560000 953455875 0 1782091776 0.1777317822 0.9309351444 2.8462169170 431 17.2000000000 0.7153630257 0.0402046968 0.7247764468 0.0097271438 0.9235230000 953457149 0 1783742464 0.1891143471 0.9212855101 2.8450443745 432 17.2400000000 0.7106573582 0.0417566706 0.7247764468 0.0097297574 0.9034840000 953458423 0 1782472704 0.2041817307 0.9144124985 2.8419024944 433 17.2800000000 0.7075401545 0.0432942768 0.7247764468 0.0097243999 0.8870710000 953459697 0 1784139776 0.2189382464 0.9091289639 2.8380234241 434 17.3200000000 0.7043322325 0.0448174057 0.7247764468 0.0097183365 0.8617580000 953460971 0 1782865920 0.2290567458 0.9003304839 2.8317987919 435 17.3600000000 0.7014659047 0.0463269425 0.7247764468 0.0097321528 0.8738960000 953462245 0 1784520704 0.2401317656 0.8963688612 2.8265395164 436 17.4000000000 0.6973229647 0.0478200526 0.7247764468 0.0097435873 0.8223890000 953463519 0 1783394304 0.2550900877 0.8963263631 2.8181869984 437 17.4400000000 0.6939935088 0.0492987104 0.7247764468 0.0097327452 0.8156100000 953464793 0 1782013952 0.2720148861 0.8988641500 2.8080585003 438 17.4800000000 0.6922077537 0.0507665393 0.7247764468 0.0097766974 0.8184250000 953466067 0 1783742464 0.2847695649 0.8981860280 2.8000681400 439 17.5200000000 0.6886222959 0.0522195137 0.7247764468 0.0098483764 0.8236480000 953467341 0 1782489088 0.2920229435 0.8881899714 2.7915341854 440 17.5600000000 0.6861029863 0.0536601579 0.7247764468 0.0098602189 0.8096140000 953468615 0 1784250368 0.2973349094 0.8757917285 2.7864823341 441 17.6000000000 0.6839681864 0.0550894278 0.7247764468 0.0098583585 0.8398940000 953469889 0 1782882304 0.3051539063 0.8656638861 2.7816948891 442 17.6400000000 0.6806405783 0.0565047019 0.7247764468 0.0099139046 0.7765650000 953471163 0 1781641216 0.3200274706 0.8628761172 2.7731704712 443 17.6800000000 0.6746684313 0.0579001054 0.7247764468 0.0099583731 0.7377210000 953472437 0 1783242752 0.3428162634 0.8611473441 2.7544851303 444 17.7200000000 0.6707509160 0.0592804000 0.7247764468 0.0099490514 0.7233610000 953473711 0 1782140928 0.3526557684 0.8559701443 2.7443921566 445 17.7600000000 0.6672523022 0.0606466290 0.7247764468 0.0099404957 0.7109210000 953474985 0 1783877632 0.3607120514 0.8493097425 2.7370026112 446 17.8000000000 0.6627119780 0.0619965513 0.7247764468 0.0099319411 0.7035340000 953476259 0 1782902784 0.3679801524 0.8447912335 2.7274785042 447 17.8400000000 0.6613342762 0.0633373516 0.7247764468 0.0099228657 0.6888930000 953477533 0 1782099968 0.3747755289 0.8399203420 2.7208883762 448 17.8800000000 0.6595602632 0.0646682063 0.7247764468 0.0099138501 0.6722910000 953478807 0 1783787520 0.3825474083 0.8356918693 2.7146821022 449 17.9200000000 0.6570352316 0.0659875092 0.7247764468 0.0099061555 0.6648020000 953480081 0 1782644736 0.3901843131 0.8307089210 2.7075908184 450 17.9600000000 0.6554586887 0.0672974452 0.7247764468 0.0098990523 0.6437140000 953481355 0 1784401920 0.3977594972 0.8239979744 2.7038590908 451 18.0000000000 0.6539657116 0.0685982617 0.7247764468 0.0099014989 0.6294840000 953482629 0 1783418880 0.4076089561 0.8217882514 2.6988155842 452 18.0400000000 0.6514788866 0.0698878207 0.7247764468 0.0098959701 0.6179960000 953483903 0 1782358016 0.4175080061 0.8192096949 2.6923980713 453 18.0800000000 0.6496919990 0.0711677416 0.7247764468 0.0098863588 0.6089870000 953485177 0 1784020992 0.4230245650 0.8136760592 2.6864657402 454 18.1200000000 0.6487750411 0.0724400044 0.7247764468 0.0098845457 0.6000510000 953486451 0 1783021568 0.4358998239 0.8115647435 2.6822216511 455 18.1600000000 0.6466614008 0.0737020294 0.7247764468 0.0098766981 0.5921880000 953487725 0 1781964800 0.4455131292 0.8083422184 2.6767730713 456 18.2000000000 0.6449778080 0.0749548272 0.7247764468 0.0098694356 0.5977330000 953488999 0 1783648256 0.4561161995 0.8028157949 2.6717429161 457 18.2400000000 0.6430775523 0.0761979841 0.7247764468 0.0098691505 0.5676280000 953490273 0 1782751232 0.4654996097 0.7978974581 2.6671273708 458 18.2800000000 0.6413738728 0.0774319926 0.7247764468 0.0098802440 0.5664440000 953491547 0 1784430592 0.4775405526 0.7977373004 2.6632986069 459 18.3200000000 0.6380556822 0.0786533950 0.7247764468 0.0098754421 0.5690560000 953492821 0 1783427072 0.4908978939 0.7971462011 2.6555867195 460 18.3600000000 0.6368016601 0.0798667608 0.7247764468 0.0098686661 0.5682550000 953494095 0 1781964800 0.5001853704 0.7914755344 2.6526331902 461 18.4000000000 0.6352956295 0.0810715956 0.7247764468 0.0098612177 0.5668750000 953495369 0 1783758848 0.5128397346 0.7879990339 2.6496431828 462 18.4400000000 0.6323165894 0.0822647666 0.7247764468 0.0098550049 0.5772560000 953496643 0 1782734848 0.5249195695 0.7862534523 2.6426568031 463 18.4800000000 0.6316329837 0.0834513070 0.7247764468 0.0098457635 0.5703400000 953497917 0 1784410112 0.5336950421 0.7831076980 2.6374163628 464 18.5200000000 0.6311570406 0.0846317073 0.7247764468 0.0098363573 0.5681010000 953499191 0 1783246848 0.5417199135 0.7787125111 2.6353344917 465 18.5600000000 0.6318362951 0.0858084914 0.7247764468 0.0098292981 0.5859170000 953500465 0 1781964800 0.5523808002 0.7740795016 2.6358876228 466 18.6000000000 0.6325770020 0.0869818144 0.7247764468 0.0098331978 0.5896280000 953501739 0 1783648256 0.5680561066 0.7736867666 2.6383028030 467 18.6400000000 0.6327304840 0.0881504411 0.7247764468 0.0098254529 0.5654470000 953503013 0 1782599680 0.5827928185 0.7709026337 2.6386737823 468 18.6800000000 0.6321919560 0.0893129229 0.7247764468 0.0098288666 0.6083160000 953504287 0 1784393728 0.5887490511 0.7685140371 2.6341536045 469 18.7200000000 0.6317120194 0.0904694242 0.7247764468 0.0098400184 0.6168090000 953505561 0 1783373824 0.5990805030 0.7660655379 2.6337642670 470 18.7600000000 0.6413078904 0.0916414209 0.7247764468 0.0098514043 0.6279900000 953506835 0 1782218752 0.6227347851 0.7660221457 2.6495032310 471 18.8000000000 0.6738494635 0.0928775314 0.7247764468 0.0098643997 0.6122010000 953508109 0 1784033280 0.6254514456 0.7880108953 2.6748380661 472 18.8400000000 0.7033802867 0.0941709695 0.7247764468 0.0099124715 0.6076960000 953509383 0 1783021568 0.6257997155 0.8049277663 2.7054359913 473 18.8800000000 0.7260935307 0.0955069580 0.7260935307 0.0099930072 0.6144690000 953510657 0 1781989376 0.6393350959 0.8121069074 2.7362170219 474 18.9200000000 0.7516570687 0.0968912409 0.7516570687 0.0101499185 0.6492350000 953511931 0 1783648256 0.6457377672 0.8156403303 2.7708902359 475 18.9600000000 0.7893791199 0.0983491101 0.7893791199 0.0103620280 0.6266490000 953513205 0 1782640640 0.6319953799 0.8287926316 2.8147418499 476 19.0000000000 0.7832907438 0.0997880631 0.7893791199 0.0103788117 0.6151500000 953514479 0 1784262656 0.6368167996 0.8244788647 2.8070390224 477 19.0400000000 0.7817862630 0.1012178288 0.7893791199 0.0103761043 0.6180390000 953515753 0 1783427072 0.6453956366 0.8219603300 2.8001122475 478 19.0800000000 0.8233787417 0.1027286256 0.8233787417 0.0105969663 0.6828900000 953517027 0 1782345728 0.6033650041 0.8458570838 2.8355958462 479 19.1200000000 0.9374663234 0.1044712931 0.9374663234 0.0133143905 0.6906590000 953518301 0 1784029184 0.3520748913 0.8615369797 2.9048531055 480 19.1600000000 1.0139639378 0.1063660694 1.0139639378 0.0135440386 0.7669010000 953519575 0 1783005184 0.2906045914 0.9356203675 2.8930871487 481 19.2000000000 1.2495567799 0.1087427653 1.2495567799 0.0179923858 0.8371960000 953520849 0 1782132736 -0.0650448352 0.9445251822 2.9725332260 482 19.2400000000 1.6188454628 0.1118757584 1.6188454628 0.0238325283 0.9104970000 953522123 0 1783906304 -0.6071327925 0.9210107327 2.9255125523 483 19.2800000000 1.9198116064 0.1156188968 1.9198116064 0.0265052132 0.9589830000 953523397 0 1782894592 -0.9880802631 0.8913539052 2.8538906574 484 19.3200000000 1.9248895645 0.1193570594 1.9248895645 0.0264830508 0.9283100000 953524671 0 1781878784 -0.9888651371 0.8892185092 2.8512268066 485 19.3600000000 1.9931248426 0.1232204981 1.9931248426 0.0265360417 0.9017620000 953525945 0 1783631872 -1.0633543730 0.8900366426 2.8223721981 486 19.4000000000 2.1034083366 0.1272949587 2.1034083366 0.0268104140 0.9538460000 953527219 0 1782599680 -1.1963059902 0.8739775419 2.7607176304 487 19.4400000000 2.1724963188 0.1314945508 2.1724963188 0.0269267033 0.9708250000 953528493 0 1784250368 -1.2812877893 0.8496087193 2.7104752064 488 19.4800000000 2.3047757149 0.1359479958 2.3047757149 0.0273471201 0.9991420000 953529767 0 1783250944 -1.4446630478 0.8160225749 2.6162226200 489 19.5200000000 2.3479883671 0.1404715957 2.3479883671 0.0273315834 1.0755690000 953531041 0 1782218752 -1.5039100647 0.7796310782 2.5266826153 490 19.5600000000 2.3549313545 0.1449909014 2.3549313545 0.0273097372 1.0121570000 953532315 0 1783922688 -1.5157212019 0.7582029700 2.4724266529 491 19.6000000000 2.3629384041 0.1495081061 2.3629384041 0.0272897845 1.0160740000 953533589 0 1782730752 -1.5278674364 0.7312282920 2.4105484486 492 19.6400000000 2.3515665531 0.1539838346 2.3629384041 0.0272741855 1.0068510000 953534863 0 1781886976 -1.5182991028 0.7220618129 2.3893103600 493 19.6800000000 2.3469018936 0.1584319443 2.3629384041 0.0272516605 1.0485590000 953536137 0 1783549952 -1.5159082413 0.7055647373 2.3517739773 494 19.7200000000 2.3434255123 0.1628550082 2.3629384041 0.0272286711 1.0236070000 953537411 0 1782378496 -1.5161367655 0.6807299256 2.3048851490 495 19.7600000000 2.3261685371 0.1672253385 2.3629384041 0.0272240539 1.0117570000 953538685 0 1784147968 -1.4990211725 0.6746520996 2.3034439087 496 19.8000000000 2.3257043362 0.1715771107 2.3629384041 0.0272049051 1.0263520000 953539959 0 1783021568 -1.5033851862 0.6579950452 2.2575068474 497 19.8400000000 2.3239517212 0.1759078443 2.3629384041 0.0271819665 1.0389720000 953541233 0 1781985280 -1.5005413294 0.6437734962 2.2284088135 498 19.8800000000 2.3113756180 0.1801959322 2.3629384041 0.0271670107 1.0743200000 953542507 0 1783775232 -1.4902788401 0.6379846931 2.2210216522 499 19.9200000000 2.3117582798 0.1844676002 2.3629384041 0.0271526416 1.0548360000 953543781 0 1782751232 -1.4920425415 0.6196068525 2.1750109196 500 19.9600000000 2.3043282032 0.1887073215 2.3629384041 0.0271438138 1.0456420000 953545055 0 1784410112 -1.4862350225 0.6072899699 2.1515629292 501 20.0000000000 2.2964031696 0.1929142992 2.3629384041 0.0271325836 1.0498010000 953546329 0 1783279616 -1.4780094624 0.6000984907 2.1362583637 502 20.0400000000 2.2956833839 0.1971030822 2.3629384041 0.0271210828 1.0545600000 953547603 0 1781989376 -1.4744113684 0.5923084617 2.1188473701 503 20.0800000000 2.2846174240 0.2012532101 2.3629384041 0.0271140945 1.0932230000 953548877 0 1783615488 -1.4619075060 0.5892280936 2.1084821224 504 20.1200000000 2.2745711803 0.2053669363 2.3629384041 0.0270951529 1.0552260000 953550151 0 1782472704 -1.4533120394 0.5833441615 2.1003894806 505 20.1600000000 2.2604224682 0.2094363532 2.3629384041 0.0270911280 1.0525290000 953551425 0 1784123392 -1.4434555769 0.5774603486 2.0877606869 506 20.2000000000 2.2533333302 0.2134756753 2.3629384041 0.0270887504 1.0549870000 953552699 0 1782853632 -1.4368233681 0.5774832964 2.0798017979 507 20.2400000000 2.2426080704 0.2174779088 2.3629384041 0.0270725089 1.0535930000 953553973 0 1784504320 -1.4265592098 0.5752816200 2.0721035004 508 20.2800000000 2.2303287983 0.2214402137 2.3629384041 0.0270567741 1.0565080000 953555247 0 1783234560 -1.4221084118 0.5679264665 2.0582315922 509 20.3200000000 2.2231028080 0.2253727532 2.3629384041 0.0270366765 1.0480310000 953556521 0 1781846016 -1.4117195606 0.5650197864 2.0534751415 510 20.3600000000 2.2123835087 0.2292688527 2.3629384041 0.0270268379 1.0416630000 953557795 0 1783504896 -1.3968442678 0.5653461218 2.0495586395 511 20.4000000000 2.2022600174 0.2331298921 2.3629384041 0.0270143314 1.0391770000 953559069 0 1782124544 -1.3846182823 0.5654463768 2.0410687923 512 20.4400000000 2.1887347698 0.2369494329 2.3629384041 0.0270001649 1.0423790000 953560343 0 1783885824 -1.3748177290 0.5623179078 2.0294666290 513 20.4800000000 2.1817224026 0.2407404134 2.3629384041 0.0269819190 1.0863730000 953561617 0 1782521856 -1.3630605936 0.5600748658 2.0278618336 514 20.5200000000 2.1717107296 0.2444971650 2.3629384041 0.0269669524 1.0221890000 953646859 0 1784135680 -1.3524507284 0.5571702123 2.0210380554 515 20.5600000000 2.1634485722 0.2482232842 2.3629384041 0.0269489360 1.0315570000 953648133 0 1783013376 -1.3385789394 0.5614929795 2.0198061466 516 20.6000000000 2.1527295113 0.2519141877 2.3629384041 0.0269285809 1.0255770000 953649407 0 1781620736 -1.3249360323 0.5600221157 2.0169243813 517 20.6400000000 2.1513938904 0.2555882297 2.3629384041 0.0269095634 1.0230730000 953650681 0 1783250944 -1.3279062510 0.5566951036 2.0129444599 518 20.6800000000 2.1407113075 0.2592274635 2.3629384041 0.0268942017 1.0483160000 953651955 0 1782009856 -1.3027620316 0.5587689877 2.0162658691 519 20.7200000000 2.1387970448 0.2628489848 2.3629384041 0.0268870758 1.0193870000 953653229 0 1783631872 -1.3101168871 0.5589067340 2.0073471069 520 20.7600000000 2.1343731880 0.2664480698 2.3629384041 0.0268669253 1.0123720000 953654503 0 1782378496 -1.3131319284 0.5578287840 2.0004076958 521 20.8000000000 2.1251502037 0.2700156363 2.3629384041 0.0268444516 0.9994480000 953655777 0 1784012800 -1.3063633442 0.5549609661 1.9950251579 522 20.8400000000 2.1212944984 0.2735621475 2.3629384041 0.0268196645 1.0016770000 953657051 0 1782759424 -1.3003367186 0.5524215102 1.9948244095 523 20.8800000000 2.1192119122 0.2770911146 2.3629384041 0.0268080250 1.0116010000 953658325 0 1784393728 -1.3088688850 0.5486586094 1.9865512848 524 20.9200000000 2.1098897457 0.2805888219 2.3629384041 0.0267970896 0.9828740000 953659599 0 1783140352 -1.2825076580 0.5513878465 1.9932327271 525 20.9600000000 2.1053423882 0.2840645430 2.3629384041 0.0267795563 0.9883650000 953660873 0 1781760000 -1.2783367634 0.5502800345 1.9909968376 526 21.0000000000 2.0971479416 0.2875114696 2.3629384041 0.0267629665 0.9732460000 953662147 0 1783275520 -1.2620666027 0.5476386547 1.9929263592 527 21.0400000000 2.0877673626 0.2909275149 2.3629384041 0.0267622919 0.9649240000 953663421 0 1782034432 -1.2515848875 0.5470799804 1.9873931408 528 21.0800000000 2.0854063034 0.2943261490 2.3629384041 0.0267460975 0.9740600000 953664695 0 1783656448 -1.2463406324 0.5468285084 1.9888007641 529 21.1200000000 2.0727586746 0.2976880252 2.3629384041 0.0267385011 0.9624790000 953665969 0 1782366208 -1.2198755741 0.5458632708 1.9913966656 530 21.1600000000 2.0681138039 0.3010284512 2.3629384041 0.0267308516 0.9574450000 953667243 0 1784020992 -1.2187957764 0.5451593995 1.9863021374 531 21.2000000000 2.0586230755 0.3043384222 2.3629384041 0.0267182034 0.9447810000 953668517 0 1782775808 -1.2006648779 0.5440741777 1.9870138168 532 21.2400000000 2.0527410507 0.3076248934 2.3629384041 0.0267051360 0.9582830000 953669791 0 1784393728 -1.1940137148 0.5429097414 1.9858244658 533 21.2800000000 2.0480008125 0.3108901390 2.3629384041 0.0266873159 0.9537090000 953671065 0 1783246848 -1.1909908056 0.5399371982 1.9838988781 534 21.3200000000 2.0398170948 0.3141278299 2.3629384041 0.0266748841 0.9582240000 953672339 0 1782026240 -1.1746870279 0.5379680395 1.9866554737 535 21.3600000000 2.0302634239 0.3173355600 2.3629384041 0.0266642889 0.9592560000 953673613 0 1783631872 -1.1589972973 0.5399861932 1.9853169918 536 21.4000000000 2.0250713825 0.3205216343 2.3629384041 0.0266467786 0.9727000000 953674887 0 1782358016 -1.1563537121 0.5381058455 1.9820939302 537 21.4400000000 2.0153925419 0.3236778185 2.3629384041 0.0266318920 0.9593840000 953676161 0 1784012800 -1.1375501156 0.5371316671 1.9831643105 538 21.4800000000 2.0080883503 0.3268086931 2.3629384041 0.0266170103 0.9696480000 953677435 0 1782886400 -1.1299523115 0.5358808637 1.9803516865 539 21.5200000000 2.0006940365 0.3299142317 2.3629384041 0.0266009057 1.0038090000 953678709 0 1784520704 -1.1245212555 0.5329934955 1.9765379429 540 21.5600000000 1.9895577431 0.3329876456 2.3629384041 0.0265883398 0.9570290000 953679983 0 1783267328 -1.1095745564 0.5340449810 1.9728510380 541 21.6000000000 1.9814984798 0.3360348006 2.3629384041 0.0265694607 0.9962830000 953681257 0 1781878784 -1.1004436016 0.5338273644 1.9700353146 542 21.6400000000 1.9720971584 0.3390533658 2.3629384041 0.0265486919 0.9512030000 953682531 0 1783504896 -1.0876432657 0.5317640901 1.9675194025 543 21.6800000000 1.9679800272 0.3420532308 2.3629384041 0.0265289045 1.0017780000 953683805 0 1782267904 -1.0822464228 0.5279996991 1.9678816795 544 21.7200000000 1.9597265720 0.3450268950 2.3629384041 0.0265139944 0.9188010000 953685079 0 1783877632 -1.0729023218 0.5280749798 1.9641193151 545 21.7600000000 1.9513870478 0.3479743448 2.3629384041 0.0264970874 0.9320310000 953686353 0 1782624256 -1.0610098839 0.5261074305 1.9624688625 546 21.8000000000 1.9467059374 0.3509024247 2.3629384041 0.0264813989 0.9280690000 953687627 0 1784131584 -1.0545400381 0.5264637470 1.9609441757 547 21.8400000000 1.9377880096 0.3538034952 2.3629384041 0.0264657634 0.9117370000 953688901 0 1782845440 -1.0427750349 0.5267419815 1.9579284191 548 21.8800000000 1.9324767590 0.3566842858 2.3629384041 0.0264455421 0.9286640000 953690175 0 1784393728 -1.0407791138 0.5255587697 1.9537949562 549 21.9200000000 1.9276771545 0.3595458393 2.3629384041 0.0264256537 0.9017530000 953691449 0 1783107584 -1.0343940258 0.5242094398 1.9526314735 550 21.9600000000 1.9214608669 0.3623856848 2.3629384041 0.0264084096 0.9082200000 953692723 0 1781837824 -1.0284930468 0.5254539251 1.9488465786 551 22.0000000000 1.9149771929 0.3652034553 2.3629384041 0.0263877547 0.8849660000 953693997 0 1783504896 -1.0210670233 0.5246804357 1.9462580681 552 22.0400000000 1.9102799892 0.3680025070 2.3629384041 0.0263678020 0.8862530000 953695271 0 1782251520 -1.0124775171 0.5256872773 1.9454998970 553 22.0800000000 1.9071326256 0.3707857441 2.3629384041 0.0263482217 0.9149150000 953696545 0 1783885824 -1.0106921196 0.5249720216 1.9434010983 554 22.1200000000 1.9016919136 0.3735491126 2.3629384041 0.0263298856 0.8746470000 953697819 0 1782632448 -1.0040031672 0.5228315592 1.9418386221 555 22.1600000000 1.8951227665 0.3762906868 2.3629384041 0.0263173539 0.8570050000 953699093 0 1784266752 -0.9966133237 0.5241998434 1.9384539127 556 22.2000000000 1.8875621557 0.3790088009 2.3629384041 0.0262986933 0.8357590000 953700367 0 1783013376 -0.9886829853 0.5255611539 1.9342480898 557 22.2400000000 1.8837238550 0.3817102642 2.3629384041 0.0262764657 0.8315270000 953701641 0 1781608448 -0.9852803946 0.5220120549 1.9332205057 558 22.2800000000 1.8773334026 0.3843905924 2.3629384041 0.0262587796 0.8221810000 953702915 0 1783242752 -0.9804903865 0.5181313157 1.9303138256 559 22.3200000000 1.8722660542 0.3870522659 2.3629384041 0.0262498754 0.8196370000 953704189 0 1782018048 -0.9759318829 0.5194941759 1.9269911051 560 22.3600000000 1.8685843945 0.3896978589 2.3629384041 0.0262342879 0.8091200000 953705463 0 1783640064 -0.9734821320 0.5186435580 1.9246861935 561 22.4000000000 1.8641172647 0.3923260575 2.3629384041 0.0262172392 0.7989090000 953706737 0 1782276096 -0.9648028016 0.5175219178 1.9247930050 562 22.4400000000 1.8602477312 0.3949380178 2.3629384041 0.0262024868 0.7873460000 953708011 0 1783877632 -0.9624513984 0.5176641345 1.9220007658 563 22.4800000000 1.8538498878 0.3975293355 2.3629384041 0.0261835878 0.7975010000 953709285 0 1782607872 -0.9532271624 0.5168184042 1.9202841520 564 22.5200000000 1.8495699167 0.4001038756 2.3629384041 0.0261637330 0.7868200000 953710559 0 1784274944 -0.9479534626 0.5141844153 1.9192301035 565 22.5600000000 1.8428184986 0.4026573528 2.3629384041 0.0261489491 0.7822630000 953711833 0 1783033856 -0.9362915754 0.5109879375 1.9189335108 566 22.6000000000 1.8379492760 0.4051932042 2.3629384041 0.0261412870 0.8381810000 953713107 0 1784651776 -0.9299654365 0.5094479918 1.9173928499 567 22.6400000000 1.8338882923 0.4077129486 2.3629384041 0.0261303757 0.7836680000 953714381 0 1783300096 -0.9236239195 0.5088413358 1.9163793325 568 22.6800000000 1.8285454512 0.4102144143 2.3629384041 0.0261157679 0.7760030000 953715655 0 1782218752 -0.9146261215 0.5063235760 1.9158877134 569 22.7200000000 1.8216613531 0.4126949889 2.3629384041 0.0261041763 0.7706460000 953716929 0 1783922688 -0.9042425752 0.5041216612 1.9143290520 570 22.7600000000 1.8125324249 0.4151508440 2.3629384041 0.0260970232 0.7733640000 953718203 0 1782734848 -0.8956628442 0.5046573281 1.9089138508 571 22.8000000000 1.8045371771 0.4175840951 2.3629384041 0.0260784537 0.7744580000 953719477 0 1784393728 -0.8883699179 0.5042472482 1.9042725563 572 22.8400000000 1.7978633642 0.4199971707 2.3629384041 0.0260576270 0.7746960000 953720751 0 1783107584 -0.8805297613 0.4991816282 1.9025409222 573 22.8800000000 1.7899371386 0.4223879909 2.3629384041 0.0260442311 0.7597740000 953722025 0 1781837824 -0.8722095490 0.4971013665 1.8988322020 574 22.9200000000 1.7823286057 0.4247572254 2.3629384041 0.0260270782 0.7563470000 953723299 0 1783504896 -0.8670943975 0.4968281984 1.8934426308 575 22.9600000000 1.7740496397 0.4271038209 2.3629384041 0.0260075266 0.7564250000 953724573 0 1782378496 -0.8589772582 0.4920475185 1.8900597095 576 23.0000000000 1.7680544853 0.4294318603 2.3629384041 0.0259894508 0.7365180000 953725847 0 1783996416 -0.8529039025 0.4871446788 1.8880988359 577 23.0400000000 1.7589555979 0.4317360609 2.3629384041 0.0259795370 0.7481900000 953727121 0 1782726656 -0.8445583582 0.4871206582 1.8826619387 578 23.0800000000 1.7507592440 0.4340181079 2.3629384041 0.0259619557 0.7454760000 953728395 0 1784393728 -0.8362092972 0.4848279357 1.8786915541 579 23.1200000000 1.7435314655 0.4362797890 2.3629384041 0.0259438969 0.7382360000 953729669 0 1783119872 -0.8282545805 0.4809435606 1.8758052588 580 23.1600000000 1.7351487875 0.4385192183 2.3629384041 0.0259274562 0.7692840000 953730943 0 1781768192 -0.8191136718 0.4782241583 1.8720427752 581 23.2000000000 1.7264997959 0.4407360523 2.3629384041 0.0259098393 0.7296670000 953732217 0 1783488512 -0.8110532761 0.4766806960 1.8671914339 582 23.2400000000 1.7169252634 0.4429288173 2.3629384041 0.0258918501 0.7298520000 953733491 0 1782136832 -0.8014610410 0.4725228548 1.8627940416 583 23.2800000000 1.7098271847 0.4451018848 2.3629384041 0.0258738288 0.7248950000 953734765 0 1783775232 -0.7929973006 0.4682913125 1.8602805138 584 23.3200000000 1.6991381645 0.4472492072 2.3629384041 0.0258653688 0.7417000000 953736039 0 1782620160 -0.7831153870 0.4662919641 1.8543182611 585 23.3600000000 1.6893759966 0.4493725009 2.3629384041 0.0258521771 0.7435860000 953737313 0 1784393728 -0.7732077241 0.4636171162 1.8492791653 586 23.4000000000 1.6811461449 0.4514745037 2.3629384041 0.0258382287 0.7248540000 953738587 0 1783410688 -0.7634993792 0.4587069452 1.8461745977 587 23.4400000000 1.6724619865 0.4535545505 2.3629384041 0.0258353897 0.7698360000 953739861 0 1782624256 -0.7549169064 0.4563248754 1.8416318893 588 23.4800000000 1.6493089199 0.4555881464 2.3629384041 0.0258901156 0.7539330000 953741135 0 1784287232 -0.7308185101 0.4535939693 1.8285775185 589 23.5200000000 1.6401458979 0.4575992801 2.3629384041 0.0258785914 0.7546080000 953742409 0 1783234560 -0.7224506140 0.4530100226 1.8228125572 590 23.5600000000 1.6293718815 0.4595853353 2.3629384041 0.0258636843 0.7610080000 953743683 0 1782026240 -0.7127487063 0.4520550370 1.8160471916 591 23.6000000000 1.6202476025 0.4615492309 2.3629384041 0.0258459805 0.7671410000 953744957 0 1783652352 -0.7028362155 0.4478569329 1.8117384911 592 23.6400000000 1.6093019247 0.4634880023 2.3629384041 0.0258313988 0.7810140000 953746231 0 1782624256 -0.6905330420 0.4433009624 1.8065124750 593 23.6800000000 1.5986429453 0.4654022602 2.3629384041 0.0258209699 0.7795190000 953747505 0 1784377344 -0.6797819734 0.4409120381 1.8004134893 594 23.7200000000 1.5887287855 0.4672933823 2.3629384041 0.0258089951 0.7822080000 953748779 0 1783488512 -0.6694211960 0.4386382699 1.7948194742 595 23.7600000000 1.5800541639 0.4691635685 2.3629384041 0.0257951848 0.7858300000 953750053 0 1782624256 -0.6621016264 0.4355454445 1.7896203995 596 23.8000000000 1.5689948797 0.4710089231 2.3629384041 0.0257855379 0.7892510000 953751327 0 1784266752 -0.6508243680 0.4345595241 1.7827877998 597 23.8400000000 1.5589011908 0.4728311882 2.3629384041 0.0257715166 0.7981620000 953752601 0 1783279616 -0.6422637701 0.4337219298 1.7760013342 598 23.8800000000 1.5477877855 0.4746287745 2.3629384041 0.0257569461 0.8153910000 953753875 0 1782108160 -0.6303823590 0.4311159551 1.7696048021 599 23.9200000000 1.5376820564 0.4764034878 2.3629384041 0.0257415571 0.8183400000 953755149 0 1783996416 -0.6222216487 0.4306234717 1.7625217438 600 23.9600000000 1.5279449224 0.4781560568 2.3629384041 0.0257246079 0.8326060000 953756423 0 1782784000 -0.6126150489 0.4286249280 1.7565035820 601 24.0000000000 1.5181201696 0.4798864464 2.3629384041 0.0257079514 0.8651450000 953757697 0 1781895168 -0.6043379903 0.4261437356 1.7501841784 602 24.0400000000 1.5076689720 0.4815937263 2.3629384041 0.0256931496 0.8376260000 953758971 0 1783513088 -0.5935304165 0.4238785803 1.7437945604 603 24.0800000000 1.4985302687 0.4832801883 2.3629384041 0.0256764184 0.8276680000 953760245 0 1782505472 -0.5867498517 0.4215994775 1.7375901937 604 24.1200000000 1.4898991585 0.4849467760 2.3629384041 0.0256590643 0.8341250000 953761519 0 1784274944 -0.5805068016 0.4199987054 1.7315022945 605 24.1600000000 1.4815689325 0.4865940853 2.3629384041 0.0256414962 0.8406040000 953762793 0 1783259136 -0.5736501813 0.4169816375 1.7261852026 606 24.2000000000 1.4744889736 0.4882242749 2.3629384041 0.0256230201 0.8392980000 953764067 0 1782099968 -0.5675347447 0.4127792716 1.7221325636 607 24.2400000000 1.4641103745 0.4898319950 2.3629384041 0.0256083916 0.8802230000 953765341 0 1783914496 -0.5566861629 0.4097014666 1.7158277035 608 24.2800000000 1.4553427696 0.4914200061 2.3629384041 0.0255918939 0.8578730000 953766615 0 1782886400 -0.5499038100 0.4089386165 1.7094446421 609 24.3200000000 1.4482750893 0.4929911967 2.3629384041 0.0255739806 0.8665620000 953767889 0 1781755904 -0.5422391891 0.4044412673 1.7057334185 610 24.3600000000 1.4415178299 0.4945461584 2.3629384041 0.0255564105 0.8740240000 953769163 0 1783529472 -0.5354253650 0.3989752531 1.7023184299 611 24.4000000000 1.4316380024 0.4960798603 2.3629384041 0.0255445559 0.8782970000 953770437 0 1782497280 -0.5235312581 0.3958449960 1.6964778900 612 24.4400000000 1.4229599237 0.4975943702 2.3629384041 0.0255317979 0.8890430000 953771711 0 1784250368 -0.5162180066 0.3941762447 1.6903768778 613 24.4800000000 1.4165554047 0.4990934910 2.3629384041 0.0255140756 0.9338510000 953772985 0 1783250944 -0.5102552176 0.3904596269 1.6865677834 614 24.5200000000 1.4070049524 0.5005721741 2.3629384041 0.0254997331 0.8984180000 953774259 0 1782218752 -0.4990775585 0.3858145177 1.6810610294 615 24.5600000000 1.4006876945 0.5020357766 2.3629384041 0.0254838406 0.9124070000 953775533 0 1783869440 -0.4918956757 0.3829143941 1.6772826910 616 24.6000000000 1.3928745985 0.5034819435 2.3629384041 0.0254682763 0.9128230000 953776807 0 1782853632 -0.4823369980 0.3781691492 1.6729854345 617 24.6400000000 1.3846654892 0.5049101178 2.3629384041 0.0254559535 0.9182960000 953778081 0 1781735424 -0.4731263220 0.3746195734 1.6678875685 618 24.6800000000 1.3761665821 0.5063199179 2.3629384041 0.0254443860 0.9292690000 953779355 0 1783525376 -0.4617828429 0.3706887662 1.6628921032 619 24.7200000000 1.3661347628 0.5077089565 2.3629384041 0.0254358048 0.9646020000 953780629 0 1782497280 -0.4482330382 0.3673565388 1.6566225290 620 24.7600000000 1.3578736782 0.5090801899 2.3629384041 0.0254281198 0.9484840000 953781903 0 1784287232 -0.4410646558 0.3657326996 1.6505985260 621 24.8000000000 1.3504140377 0.5104349948 2.3629384041 0.0254140657 0.9629240000 953783177 0 1783169024 -0.4322989881 0.3631562293 1.6456137896 622 24.8400000000 1.3427693844 0.5117731530 2.3629384041 0.0253995606 0.9518150000 953784451 0 1781878784 -0.4232335091 0.3592823148 1.6406940222 623 24.8800000000 1.3342602253 0.5130933570 2.3629384041 0.0253886843 0.9513290000 953785725 0 1783668736 -0.4142135680 0.3574628234 1.6345759630 624 24.9200000000 1.3250621557 0.5143945890 2.3629384041 0.0253754397 0.9666500000 953786999 0 1782476800 -0.4052116275 0.3555732369 1.6277434826 625 24.9600000000 1.3171453476 0.5156789902 2.3629384041 0.0253601356 0.9714230000 953788273 0 1784156160 -0.3972074986 0.3516820073 1.6223140955 626 25.0000000000 1.3105635643 0.5169487739 2.3629384041 0.0253448981 0.9875450000 953789547 0 1783279616 -0.3894191086 0.3478130102 1.6179611683 627 25.0400000000 1.3023424149 0.5182013953 2.3629384041 0.0253360808 0.9892420000 953790821 0 1781878784 -0.3812100589 0.3451915979 1.6119431257 628 25.0800000000 1.2931227684 0.5194353465 2.3629384041 0.0253289160 1.0146690000 953792095 0 1783525376 -0.3738211095 0.3444364965 1.6044355631 629 25.1200000000 1.2873221636 0.5206561523 2.3629384041 0.0253137917 1.0221410000 953793369 0 1782513664 -0.3690302670 0.3419724405 1.6001485586 630 25.1600000000 1.2785173655 0.5218591066 2.3629384041 0.0253030426 1.0562230000 953794643 0 1784156160 -0.3618218005 0.3392248452 1.5933767557 631 25.2000000000 1.2699782848 0.5230447154 2.3629384041 0.0252923546 1.0326060000 953795917 0 1783279616 -0.3555804193 0.3376438618 1.5864962339 632 25.2400000000 1.2634280920 0.5242162081 2.3629384041 0.0252774792 1.0151280000 953797191 0 1781768192 -0.3517004251 0.3344760239 1.5815541744 633 25.2800000000 1.2537696362 0.5253687412 2.3629384041 0.0252670753 1.0058960000 953798465 0 1783541760 -0.3435100317 0.3324361444 1.5739233494 634 25.3200000000 1.2443493605 0.5265027800 2.3629384041 0.0252540924 0.9985780000 953799739 0 1782243328 -0.3383484185 0.3309810162 1.5660787821 635 25.3600000000 1.2375856638 0.5276225956 2.3629384041 0.0252372003 1.0374100000 953801013 0 1783922688 -0.3348921835 0.3288449049 1.5606098175 636 25.4000000000 1.2298449278 0.5287267187 2.3629384041 0.0252220468 0.9903560000 953802287 0 1782730752 -0.3277904391 0.3249575794 1.5548360348 637 25.4400000000 1.2218451500 0.5298148168 2.3629384041 0.0252079595 0.9827900000 953803561 0 1784520704 -0.3230931461 0.3228833079 1.5482643843 638 25.4800000000 1.2149809599 0.5308887449 2.3629384041 0.0251927780 0.9846110000 953804835 0 1783279616 -0.3171435595 0.3190707862 1.5431102514 639 25.5200000000 1.2074759007 0.5319475667 2.3629384041 0.0251787128 0.9731180000 953806109 0 1782272000 -0.3139341474 0.3148669899 1.5372549295 640 25.5600000000 1.2007714510 0.5329926040 2.3629384041 0.0251637212 0.9859460000 953807383 0 1783910400 -0.3101725876 0.3110531569 1.5321966410 641 25.6000000000 1.1929043531 0.5340221076 2.3629384041 0.0251492679 0.9544670000 953808657 0 1782878208 -0.3062816560 0.3074255586 1.5259114504 642 25.6400000000 1.1854416132 0.5350367797 2.3629384041 0.0251344226 0.9455550000 953809931 0 1781907456 -0.3039505482 0.3039657176 1.5198857784 643 25.6800000000 1.1779273748 0.5360366095 2.3629384041 0.0251196256 0.9416090000 953811205 0 1783529472 -0.2996906936 0.3000072837 1.5140030384 644 25.7200000000 1.1701159477 0.5370212048 2.3629384041 0.0251045945 0.9396030000 953812479 0 1782370304 -0.2974483967 0.2964489758 1.5077071190 645 25.7600000000 1.1623830795 0.5379907581 2.3629384041 0.0250891163 0.9546480000 953813753 0 1784139776 -0.2934776843 0.2924577892 1.5016064644 646 25.8000000000 1.1546449661 0.5389453311 2.3629384041 0.0250739165 0.9408010000 953815027 0 1783005184 -0.2927003503 0.2880930901 1.4954401255 647 25.8400000000 1.1443682909 0.5398810699 2.3629384041 0.0250615512 0.9511210000 953816301 0 1781620736 -0.2902172208 0.2857392132 1.4866670370 648 25.8800000000 1.1361238956 0.5408011977 2.3629384041 0.0250456785 0.9261680000 953817575 0 1783287808 -0.2892574668 0.2820473015 1.4798084497 649 25.9200000000 1.1273052692 0.5417049020 2.3629384041 0.0250299170 0.9298400000 953818849 0 1782280192 -0.2877759933 0.2766277492 1.4728516340 650 25.9600000000 1.1100571156 0.5425792900 2.3629384041 0.0250369509 0.9330640000 953820123 0 1783885824 -0.2848095298 0.2644656599 1.4597697258 651 26.0000000000 1.0877703428 0.5434167570 2.3629384041 0.0250737779 0.9318760000 953821397 0 1782628352 -0.2823685408 0.2573712170 1.4410676956 652 26.0400000000 1.0757185221 0.5442331708 2.3629384041 0.0250671721 0.9236800000 953822671 0 1784377344 -0.2810291052 0.2543100119 1.4307000637 653 26.0800000000 1.0625300407 0.5450268873 2.3629384041 0.0250578495 0.9417680000 953823945 0 1783234560 -0.2809332609 0.2532602251 1.4191222191 654 26.1200000000 1.0504027605 0.5457996333 2.3629384041 0.0250448976 0.9375710000 953825219 0 1782218752 -0.2816578448 0.2490972131 1.4090542793 655 26.1600000000 1.0386909246 0.5465521391 2.3629384041 0.0250336800 0.9135910000 953826493 0 1783996416 -0.2801339924 0.2431076765 1.3996012211 656 26.2000000000 1.0257810354 0.5472826709 2.3629384041 0.0250258491 0.9155900000 953827767 0 1782726656 -0.2805959582 0.2395034283 1.3886266947 657 26.2400000000 1.0137042999 0.5479925973 2.3629384041 0.0250173049 0.9044370000 953829041 0 1784410112 -0.2817972898 0.2359472215 1.3782014847 658 26.2800000000 0.9998856783 0.5486793649 2.3629384041 0.0250108273 0.9308070000 953830315 0 1783267328 -0.2819297910 0.2329201996 1.3663536310 659 26.3200000000 0.9860023856 0.5493429810 2.3629384041 0.0250038671 0.8967220000 953831589 0 1781878784 -0.2837015092 0.2312224209 1.3541197777 660 26.3600000000 0.9727711082 0.5499845388 2.3629384041 0.0249932527 0.9120740000 953832863 0 1783521280 -0.2842745185 0.2282264531 1.3429495096 661 26.4000000000 0.9582819343 0.5506022353 2.3629384041 0.0249840717 0.9089090000 953834137 0 1782394880 -0.2854259014 0.2260736674 1.3302725554 662 26.4400000000 0.9447857738 0.5511976787 2.3629384041 0.0249730544 0.9106010000 953835411 0 1784029184 -0.2885825336 0.2250261456 1.3183444738 663 26.4800000000 0.9325641990 0.5517728922 2.3629384041 0.0249661473 0.9039240000 953836685 0 1782759424 -0.2896821201 0.2206876576 1.3080581427 664 26.5200000000 0.9204260707 0.5523280927 2.3629384041 0.0249577910 0.8962970000 953837959 0 1784266752 -0.2886044383 0.2138302773 1.2983125448 665 26.5600000000 0.9081326127 0.5528631371 2.3629384041 0.0249473786 0.8992660000 953839233 0 1782980608 -0.2899294496 0.2105003446 1.2879006863 666 26.6000000000 0.8948674202 0.5533766571 2.3629384041 0.0249371177 0.9020850000 953840507 0 1781583872 -0.2910308540 0.2083437890 1.2763143778 667 26.6400000000 0.8827707171 0.5538705012 2.3629384041 0.0249243774 0.8970200000 953841781 0 1783234560 -0.2937907279 0.2073297054 1.2655845881 668 26.6800000000 0.8692528605 0.5543426305 2.3629384041 0.0249133153 0.8918710000 953843055 0 1781964800 -0.2951210439 0.2071993202 1.2534098625 669 26.7200000000 0.8566777110 0.5547945514 2.3629384041 0.0249074663 0.8886410000 953844329 0 1783631872 -0.2968569100 0.2045285702 1.2424657345 670 26.7600000000 0.8455659151 0.5552285385 2.3629384041 0.0248990939 0.9257330000 953845603 0 1782378496 -0.2978068292 0.2006549090 1.2331694365 671 26.8000000000 0.8342511058 0.5556443695 2.3629384041 0.0248874835 0.8862740000 953846877 0 1783885824 -0.2981300056 0.1972808242 1.2235165834 672 26.8400000000 0.8222795129 0.5560411480 2.3629384041 0.0248754471 0.8854510000 953848151 0 1782611968 -0.2982060611 0.1959819943 1.2128913403 673 26.8800000000 0.8113952279 0.5564205745 2.3629384041 0.0248635221 0.8896710000 953849425 0 1784283136 -0.2982366681 0.1930267513 1.2036349773 674 26.9200000000 0.8006647825 0.5567829546 2.3629384041 0.0248514271 0.8890090000 953850699 0 1783013376 -0.2982748449 0.1906569749 1.1943162680 675 26.9600000000 0.7902063131 0.5571287670 2.3629384041 0.0248398131 0.8818500000 953851973 0 1781583872 -0.2990585566 0.1892022491 1.1851358414 676 27.0000000000 0.7785560489 0.5574563222 2.3629384041 0.0248288968 0.8839030000 953853247 0 1783250944 -0.2993792593 0.1897754520 1.1744699478 677 27.0400000000 0.7682775259 0.5577677272 2.3629384041 0.0248175181 0.8803770000 953854521 0 1781972992 -0.3010534346 0.1895890683 1.1651922464 678 27.0800000000 0.7583496571 0.5580635708 2.3629384041 0.0248077594 0.8871960000 953855795 0 1783623680 -0.3014415205 0.1882731169 1.1563355923 679 27.1200000000 0.7473320961 0.5583423168 2.3629384041 0.0247992462 0.8617350000 953857069 0 1782276096 -0.3014043570 0.1866543740 1.1466150284 680 27.1600000000 0.7372819185 0.5586054632 2.3629384041 0.0247902427 0.8643710000 953858343 0 1783894016 -0.2999687791 0.1831982881 1.1381944418 681 27.2000000000 0.7275234461 0.5588535073 2.3629384041 0.0247774701 0.8682670000 953859617 0 1782640640 -0.3000414371 0.1813029051 1.1296088696 682 27.2400000000 0.7166076899 0.5590848184 2.3629384041 0.0247657728 0.9080190000 953860891 0 1784274944 -0.2993579209 0.1813935339 1.1197319031 683 27.2800000000 0.7060773969 0.5593000344 2.3629384041 0.0247549587 0.8672810000 953862165 0 1783013376 -0.2983773053 0.1807636619 1.1103167534 684 27.3200000000 0.6957325935 0.5594994973 2.3629384041 0.0247456553 0.8683060000 953863439 0 1784504320 -0.2978220284 0.1785347164 1.1012607813 685 27.3600000000 0.6853225231 0.5596831805 2.3629384041 0.0247355636 0.8678400000 953864713 0 1783123968 -0.2957408726 0.1759770662 1.0923182964 686 27.4000000000 0.6736554503 0.5598493208 2.3629384041 0.0247245056 0.8681910000 953865987 0 1781710848 -0.2940858603 0.1757439673 1.0817400217 687 27.4400000000 0.6623270512 0.5599984878 2.3629384041 0.0247166190 0.8677100000 953867261 0 1783267328 -0.2921019793 0.1755725741 1.0714581013 688 27.4800000000 0.6511988640 0.5601310465 2.3629384041 0.0247147118 0.9026850000 953868535 0 1782009856 -0.2903039157 0.1736641675 1.0616977215 689 27.5200000000 0.6400452852 0.5602470324 2.3629384041 0.0247112241 0.8673460000 953869809 0 1783504896 -0.2883631885 0.1717439443 1.0518805981 690 27.5600000000 0.6291568279 0.5603469016 2.3629384041 0.0247062557 0.8792240000 953871083 0 1782267904 -0.2853989899 0.1695828885 1.0422433615 691 27.6000000000 0.6166710854 0.5604284127 2.3629384041 0.0247001743 0.8722960000 953872357 0 1783902208 -0.2830502093 0.1698703617 1.0308158398 692 27.6400000000 0.6044741273 0.5604920626 2.3629384041 0.0246992827 0.8739710000 953873631 0 1782632448 -0.2804940045 0.1695898324 1.0197036266 693 27.6800000000 0.5936104655 0.5605398525 2.3629384041 0.0247030804 0.8737880000 953874905 0 1784250368 -0.2769896984 0.1664686203 1.0102002621 694 27.7200000000 0.5829868913 0.5605721970 2.3629384041 0.0246998168 0.8838580000 953876179 0 1782980608 -0.2724095285 0.1622192860 1.0011019707 695 27.7600000000 0.5730792284 0.5605901927 2.3629384041 0.0246893487 0.8893400000 953877453 0 1781583872 -0.2683310509 0.1581469029 0.9926298857 696 27.8000000000 0.5621179342 0.5605923877 2.3629384041 0.0246793952 0.8833060000 953878727 0 1783123968 -0.2646186650 0.1567855924 0.9825527072 697 27.8400000000 0.5506632924 0.5605781422 2.3629384041 0.0246702393 0.8904260000 953880001 0 1781886976 -0.2612634599 0.1562545300 0.9719214439 698 27.8800000000 0.5382785797 0.5605461944 2.3629384041 0.0246617127 0.8947690000 953881275 0 1783521280 -0.2587089539 0.1565516591 0.9603271484 699 27.9200000000 0.5268048644 0.5604979236 2.3629384041 0.0246537342 0.9021050000 953882549 0 1782140928 -0.2562737465 0.1567362994 0.9495421648 700 27.9600000000 0.5149993896 0.5604329257 2.3629384041 0.0246499751 0.9374900000 953883823 0 1783758848 -0.2533878386 0.1558523327 0.9385576248 701 28.0000000000 0.5041855574 0.5603526869 2.3629384041 0.0246467913 0.9111260000 953885097 0 1782505472 -0.2509539425 0.1544964910 0.9285266995 702 28.0400000000 0.4938559830 0.5602579623 2.3629384041 0.0246429153 0.9066810000 953886371 0 1784029184 -0.2484035045 0.1521654427 0.9190168977 703 28.0800000000 0.4849047363 0.5601507742 2.3629384041 0.0246330652 0.9176150000 953887645 0 1782775808 -0.2468597591 0.1501573622 0.9107986689 704 28.1200000000 0.4733035862 0.5600274117 2.3629384041 0.0246236527 0.9201000000 953888919 0 1784250368 -0.2463085204 0.1524772644 0.8994731307 705 28.1600000000 0.4626669288 0.5598893117 2.3629384041 0.0246234691 0.9245400000 953890193 0 1782870016 -0.2457075715 0.1530813277 0.8892573118 706 28.2000000000 0.4541597962 0.5597395532 2.3629384041 0.0246238825 0.9331200000 953891467 0 1781456896 -0.2448271662 0.1501410753 0.8815780282 707 28.2400000000 0.4443949461 0.5595764067 2.3629384041 0.0246148214 0.9280110000 953892741 0 1782980608 -0.2442443669 0.1502842307 0.8722617626 708 28.2800000000 0.4342953563 0.5593994560 2.3629384041 0.0246053899 0.9324450000 953894015 0 1781710848 -0.2447064966 0.1513016671 0.8625448346 709 28.3200000000 0.4280664325 0.5592142190 2.3629384041 0.0245955559 0.9146630000 953895289 0 1783234560 -0.2445401549 0.1460926384 0.8572418094 710 28.3600000000 0.4202388823 0.5590184791 2.3629384041 0.0245838139 0.9208310000 953896563 0 1781899264 -0.2441620082 0.1443504691 0.8498905301 711 28.4000000000 0.4091304243 0.5588076661 2.3629384041 0.0245740711 0.9410670000 953897837 0 1783394304 -0.2455513924 0.1490529776 0.8387942910 712 28.4400000000 0.4004480839 0.5585852510 2.3629384041 0.0245654069 0.9683590000 953899111 0 1782140928 -0.2465624958 0.1480543911 0.8305863738 713 28.4800000000 0.3958098292 0.5583569544 2.3629384041 0.0245492451 0.9242760000 953900385 0 1783758848 -0.2476464510 0.1434216797 0.8269834518 714 28.5200000000 0.3856911063 0.5581151255 2.3629384041 0.0245515652 0.9442210000 953901659 0 1782505472 -0.2502283752 0.1477040946 0.8168534040 715 28.5600000000 0.3755690455 0.5578598163 2.3629384041 0.0245393716 0.9451160000 953902933 0 1784164352 -0.2532467544 0.1511940658 0.8067578673 716 28.6000000000 0.3696126938 0.5575969014 2.3629384041 0.0245323173 0.9224350000 953904207 0 1782894592 -0.2578844726 0.1506800056 0.8013095856 717 28.6400000000 0.3640333414 0.5573269382 2.3629384041 0.0245193637 0.9295430000 953905481 0 1784528896 -0.2629104555 0.1505136490 0.7961813211 718 28.6800000000 0.3568746150 0.5570477567 2.3629384041 0.0245057940 0.9412550000 953906755 0 1783275520 -0.2682658732 0.1531678885 0.7890196443 719 28.7200000000 0.3500551879 0.5567598672 2.3629384041 0.0244976620 0.9218830000 953908029 0 1781886976 -0.2732778490 0.1536441743 0.7822439671 720 28.7600000000 0.3441268802 0.5564645436 2.3629384041 0.0244878459 0.9202480000 953909303 0 1783513088 -0.2795948088 0.1539898217 0.7763324976 721 28.8000000000 0.3394950628 0.5561636151 2.3629384041 0.0244743980 0.9182450000 953910577 0 1782353920 -0.2865197062 0.1533604562 0.7717178464 722 28.8400000000 0.3339159787 0.5558557928 2.3629384041 0.0244609248 0.9164930000 953911851 0 1784004608 -0.2935221493 0.1536489278 0.7657276392 723 28.8800000000 0.3294003904 0.5555425765 2.3629384041 0.0244471126 0.9130970000 953913125 0 1782726656 -0.3015007675 0.1531645656 0.7606485486 724 28.9200000000 0.3244725466 0.5552234190 2.3629384041 0.0244342596 0.9142910000 953914399 0 1784377344 -0.3095878065 0.1534267813 0.7546672225 725 28.9600000000 0.3197687268 0.5548986539 2.3629384041 0.0244215965 0.9138580000 953915673 0 1783107584 -0.3182131350 0.1538994908 0.7484164834 726 29.0000000000 0.3161287308 0.5545697697 2.3629384041 0.0244136587 0.9123480000 953916947 0 1781895168 -0.3268774748 0.1534404457 0.7431105971 727 29.0400000000 0.3119468391 0.5542360381 2.3629384041 0.0244061526 0.9080760000 953918221 0 1783631872 -0.3359222114 0.1532766074 0.7366504073 728 29.0800000000 0.3088909686 0.5538990256 2.3629384041 0.0243969690 0.9126940000 953919495 0 1782636544 -0.3454181552 0.1536011994 0.7306451201 729 29.1200000000 0.3066036105 0.5535598001 2.3629384041 0.0243849601 0.9040760000 953920769 0 1784397824 -0.3552756906 0.1542285085 0.7247374654 730 29.1600000000 0.3048968315 0.5532191659 2.3629384041 0.0243724165 0.9562570000 953922043 0 1783300096 -0.3649158776 0.1535576284 0.7193377614 731 29.2000000000 0.3026036918 0.5528763266 2.3629384041 0.0243616785 0.9222220000 953923317 0 1782243328 -0.3742504716 0.1542112231 0.7124525309 732 29.2400000000 0.3007341325 0.5525318701 2.3629384041 0.0243519118 0.9224100000 953924591 0 1783885824 -0.3841944635 0.1558859348 0.7046785355 733 29.2800000000 0.3010416627 0.5521887729 2.3629384041 0.0243422689 0.9290900000 953925865 0 1782894592 -0.3953944743 0.1570188701 0.6981634498 734 29.3200000000 0.3033781946 0.5518497940 2.3629384041 0.0243322089 0.9029710000 953927139 0 1781837824 -0.4074515104 0.1584913284 0.6926199794 735 29.3600000000 0.3058945537 0.5515151610 2.3629384041 0.0243218465 0.8998420000 953928413 0 1783631872 -0.4187671542 0.1601216644 0.6868597865 736 29.4000000000 0.3093541563 0.5511861379 2.3629384041 0.0243120126 0.9169050000 953929687 0 1782599680 -0.4301817417 0.1629241705 0.6808443069 737 29.4400000000 0.3136344850 0.5508638154 2.3629384041 0.0243017136 0.8949570000 953930961 0 1784266752 -0.4414100647 0.1642886251 0.6759914756 738 29.4800000000 0.3181321025 0.5505484608 2.3629384041 0.0242971440 0.9176830000 953932235 0 1783234560 -0.4524875283 0.1663618386 0.6702278256 739 29.5200000000 0.3239018023 0.5502417671 2.3629384041 0.0243043211 0.8903270000 953933509 0 1782153216 -0.4637398422 0.1676040739 0.6659513116 740 29.5600000000 0.3299620450 0.5499440918 2.3629384041 0.0243087898 0.8860640000 953934783 0 1783922688 -0.4743364751 0.1689539552 0.6620290875 741 29.6000000000 0.3365853727 0.5496561583 2.3629384041 0.0243214647 0.8838010000 953936057 0 1782751232 -0.4850095809 0.1719028503 0.6574202776 742 29.6400000000 0.3441359103 0.5493791768 2.3629384041 0.0243349633 0.9163860000 953937331 0 1784520704 -0.4956366420 0.1747154891 0.6539264917 743 29.6800000000 0.3512248099 0.5491124818 2.3629384041 0.0243300742 0.8725670000 953938605 0 1783427072 -0.5050315261 0.1755415201 0.6522331238 744 29.7200000000 0.3574429154 0.5488548614 2.3629384041 0.0243165313 0.8799750000 953939879 0 1782009856 -0.5134219527 0.1768127680 0.6498262882 745 29.7600000000 0.3632887602 0.5486057794 2.3629384041 0.0243025860 0.8732780000 953941153 0 1783631872 -0.5213551521 0.1786084920 0.6467474699 746 29.8000000000 0.3691296279 0.5483651948 2.3629384041 0.0242890523 0.8708870000 953942427 0 1782472704 -0.5290133953 0.1797589809 0.6442070603 747 29.8400000000 0.3746917844 0.5481327002 2.3629384041 0.0242805184 0.8669560000 953943701 0 1784123392 -0.5363621116 0.1817330867 0.6407144070 748 29.8800000000 0.3806505203 0.5479087936 2.3629384041 0.0242797939 0.8627270000 953944975 0 1782861824 -0.5437469482 0.1842541397 0.6372833252 749 29.9200000000 0.3864954412 0.5476932884 2.3629384041 0.0242769466 0.8643220000 953946249 0 1781747712 -0.5506151319 0.1864478588 0.6346297264 750 29.9600000000 0.3919819891 0.5474856734 2.3629384041 0.0242753580 0.8591540000 953947523 0 1783410688 -0.5570137501 0.1885087937 0.6320217252 751 30.0000000000 0.3968940675 0.5472851519 2.3629384041 0.0242734893 0.8508240000 953948797 0 1782489088 -0.5627787113 0.1899968833 0.6296771169 752 30.0400000000 0.4016495645 0.5470914876 2.3629384041 0.0242686654 0.8474970000 953950071 0 1784139776 -0.5681561232 0.1918844879 0.6272493601 753 30.0800000000 0.4056421518 0.5469036399 2.3629384041 0.0242667644 0.8546210000 953951345 0 1783148544 -0.5729993582 0.1930421293 0.6246985793 754 30.1200000000 0.4096936584 0.5467216638 2.3629384041 0.0242695071 0.8191460000 953952619 0 1782116352 -0.5778448582 0.1938336343 0.6225057244 755 30.1600000000 0.4133679569 0.5465450363 2.3629384041 0.0242748293 0.8232940000 953953893 0 1783787520 -0.5825538039 0.1941242516 0.6198190451 756 30.2000000000 0.4178356826 0.5463747859 2.3629384041 0.0242786254 0.8166470000 953955167 0 1782755328 -0.5876803398 0.1951000541 0.6166228652 757 30.2400000000 0.4216194451 0.5462099836 2.3629384041 0.0242742922 0.8145900000 953956441 0 1781743616 -0.5924987793 0.1967128515 0.6127348542 758 30.2800000000 0.4256422222 0.5460509232 2.3629384041 0.0242701612 0.8098050000 953957715 0 1783513088 -0.5975650549 0.1976172626 0.6090838909 759 30.3200000000 0.4302235246 0.5458983179 2.3629384041 0.0242808140 0.8153230000 953958989 0 1782353920 -0.6031016111 0.1988372952 0.6047073603 760 30.3600000000 0.4347630739 0.5457520873 2.3629384041 0.0242948860 0.8015000000 953960263 0 1784037376 -0.6085761189 0.2016277760 0.5988789201 761 30.4000000000 0.4386888146 0.5456113997 2.3629384041 0.0243033878 0.7978040000 953961537 0 1783271424 -0.6135370135 0.2035923749 0.5931426287 762 30.4400000000 0.4423158467 0.5454758413 2.3629384041 0.0243030408 0.7969760000 953962811 0 1782140928 -0.6183058619 0.2054182291 0.5869664550 763 30.4800000000 0.4462360740 0.5453457760 2.3629384041 0.0242995647 0.7860910000 953964085 0 1783648256 -0.6233179569 0.2072358876 0.5803082585 764 30.5200000000 0.4504631758 0.5452215842 2.3629384041 0.0242959849 0.8043180000 953965359 0 1782726656 -0.6276568770 0.2087246180 0.5720338225 765 30.5600000000 0.4548711479 0.5451034790 2.3629384041 0.0242900638 0.7926240000 953966633 0 1784520704 -0.6326475739 0.2103470564 0.5647053123 766 30.6000000000 0.4594579041 0.5449916702 2.3629384041 0.0242843743 0.7922740000 953967907 0 1783410688 -0.6377802491 0.2114894390 0.5576077104 767 30.6400000000 0.4640333056 0.5448861182 2.3629384041 0.0242788173 0.7867070000 953969181 0 1782603776 -0.6428138614 0.2127999067 0.5495964289 768 30.6800000000 0.4688804746 0.5447871525 2.3629384041 0.0242742758 0.8264830000 953970455 0 1784430592 -0.6479399800 0.2138046473 0.5419046879 769 30.7200000000 0.4741655886 0.5446953169 2.3629384041 0.0242696462 0.7785130000 953971729 0 1783361536 -0.6531561613 0.2153661102 0.5339803696 770 30.7600000000 0.4796290994 0.5446108153 2.3629384041 0.0242636345 0.7752090000 953973003 0 1782218752 -0.6583640575 0.2170236856 0.5259909630 771 30.8000000000 0.4847236872 0.5445331407 2.3629384041 0.0242561160 0.7714200000 953974277 0 1783922688 -0.6632051468 0.2181152552 0.5179920197 772 30.8400000000 0.4896487296 0.5444620469 2.3629384041 0.0242480792 0.7698170000 953975551 0 1782894592 -0.6680109501 0.2180924863 0.5105459690 773 30.8800000000 0.4950287938 0.5443980971 2.3629384041 0.0242409619 0.7683400000 953976825 0 1781747712 -0.6729653478 0.2184589505 0.5028083920 774 30.9200000000 0.5005195141 0.5443414064 2.3629384041 0.0242351420 0.7687730000 953978099 0 1783361536 -0.6779845357 0.2183744907 0.4957396388 775 30.9600000000 0.5054277182 0.5442911952 2.3629384041 0.0242287689 0.7628640000 953979373 0 1782386688 -0.6826024652 0.2173208147 0.4885144234 776 31.0000000000 0.5106900930 0.5442478948 2.3629384041 0.0242255889 0.7582840000 953980647 0 1784029184 -0.6873108149 0.2166174948 0.4809642434 777 31.0400000000 0.5162369013 0.5442118446 2.3629384041 0.0242273591 0.7560180000 953981921 0 1783013376 -0.6918053031 0.2170602530 0.4730207026 778 31.0800000000 0.5217095017 0.5441829213 2.3629384041 0.0242241284 0.7524050000 953983195 0 1781964800 -0.6960585117 0.2177003473 0.4651018977 779 31.1200000000 0.5272052288 0.5441611271 2.3629384041 0.0242169479 0.7483370000 953984469 0 1783615488 -0.7005357742 0.2175185829 0.4580717981 780 31.1600000000 0.5327627063 0.5441465137 2.3629384041 0.0242095728 0.7443800000 953985743 0 1782734848 -0.7048677206 0.2176603824 0.4510863721 781 31.2000000000 0.5378643274 0.5441384699 2.3629384041 0.0242012761 0.7511990000 953987017 0 1784393728 -0.7087426186 0.2175347507 0.4439209700 782 31.2400000000 0.5427764654 0.5441367282 2.3629384041 0.0241898617 0.7794560000 953988291 0 1783361536 -0.7126349807 0.2166506648 0.4376445711 783 31.2800000000 0.5480518341 0.5441417284 2.3629384041 0.0241780646 0.7455990000 953989565 0 1781981184 -0.7166926265 0.2160996646 0.4313479364 784 31.3200000000 0.5529058576 0.5441529071 2.3629384041 0.0241674403 0.7389650000 953990839 0 1783631872 -0.7204375863 0.2154081017 0.4256271422 785 31.3600000000 0.5573396683 0.5441697055 2.3629384041 0.0241552917 0.7421510000 953992113 0 1782243328 -0.7239680290 0.2141555399 0.4203529656 786 31.4000000000 0.5623368025 0.5441928189 2.3629384041 0.0241434357 0.7544670000 953993387 0 1784012800 -0.7274807096 0.2128344178 0.4147171378 787 31.4400000000 0.5667874813 0.5442215287 2.3629384041 0.0241304170 0.7454630000 953994661 0 1782980608 -0.7308982611 0.2131694257 0.4097149968 788 31.4800000000 0.5712615252 0.5442558435 2.3629384041 0.0241173635 0.7403330000 953995935 0 1781620736 -0.7343882918 0.2126774341 0.4055639803 789 31.5200000000 0.5754202008 0.5442953420 2.3629384041 0.0241050882 0.8090080000 953997209 0 1783267328 -0.7373466492 0.2108648866 0.4010701180 790 31.5600000000 0.5795937181 0.5443400235 2.3629384041 0.0240920050 0.7612430000 953998483 0 1782009856 -0.7406615615 0.2095895708 0.3971203566 791 31.6000000000 0.5831340551 0.5443890678 2.3629384041 0.0240791096 0.7385790000 953999757 0 1783615488 -0.7437328100 0.2086587399 0.3936127126 792 31.6400000000 0.5866014957 0.5444423663 2.3629384041 0.0240663806 0.7413320000 954001031 0 1782386688 -0.7466237545 0.2072462440 0.3906155527 793 31.6800000000 0.5896147490 0.5444993302 2.3629384041 0.0240526049 0.7379110000 954002305 0 1783910400 -0.7492532730 0.2054541558 0.3880316019 794 31.7200000000 0.5923637152 0.5445596128 2.3629384041 0.0240402503 0.7578750000 954003579 0 1782640640 -0.7517752051 0.2035437822 0.3860417604 795 31.7600000000 0.5950464606 0.5446231183 2.3629384041 0.0240312193 0.7421800000 954004853 0 1784258560 -0.7542309761 0.2016879767 0.3840861022 796 31.8000000000 0.5979386568 0.5446900976 2.3629384041 0.0240253388 0.7463350000 954006127 0 1783021568 -0.7569333911 0.1999303848 0.3823724091 797 31.8400000000 0.6004652977 0.5447600790 2.3629384041 0.0240246342 0.7492870000 954007401 0 1781776384 -0.7593989372 0.1981938779 0.3812917471 798 31.8800000000 0.6026987433 0.5448326839 2.3629384041 0.0240261158 0.7482330000 954008675 0 1783259136 -0.7616615295 0.1960182786 0.3798574209 799 31.9200000000 0.6048585773 0.5449078102 2.3629384041 0.0240252997 0.7530660000 954009949 0 1781972992 -0.7639458179 0.1936248541 0.3787283599 800 31.9600000000 0.6069299579 0.5449853378 2.3629384041 0.0240234991 0.7629960000 954011223 0 1783615488 -0.7662142515 0.1911883056 0.3779313564 801 32.0000000000 0.6089105606 0.5450651446 2.3629384041 0.0240222016 0.7389080000 954012497 0 1782505472 -0.7693216801 0.1889239699 0.3783603013 802 32.0400000000 0.6108044386 0.5451471138 2.3629384041 0.0240151428 0.7385050000 954013771 0 1784139776 -0.7717678547 0.1868751496 0.3781414032 803 32.0800000000 0.6136574745 0.5452324318 2.3629384041 0.0240074234 0.7737690000 954015045 0 1782853632 -0.7742934823 0.1866779476 0.3781546354 804 32.1199999990 0.6155115366 0.5453198436 2.3629384041 0.0240004953 0.7426530000 954016319 0 1784377344 -0.7764846087 0.1863882989 0.3784035146 805 32.1600000000 0.6171538234 0.5454090784 2.3629384041 0.0239944375 0.7468670000 954017593 0 1783119872 -0.7788351774 0.1852298379 0.3791438937 806 32.2000000000 0.6197690964 0.5455013365 2.3629384041 0.0239903736 0.7641570000 954018867 0 1781899264 -0.7807530165 0.1829880774 0.3783788681 807 32.2400000000 0.6202952266 0.5455940179 2.3629384041 0.0239880385 0.7547100000 954020141 0 1783504896 -0.7829667330 0.1805357039 0.3803339303 808 32.2800000000 0.6228321195 0.5456896096 2.3629384041 0.0239830122 0.7748870000 954021415 0 1782218752 -0.7853744626 0.1778601259 0.3803532422 809 32.3200000000 0.6236643791 0.5457859937 2.3629384041 0.0239768013 0.7546340000 954022689 0 1783758848 -0.7877877951 0.1747122556 0.3826648891 810 32.3600000000 0.6251749992 0.5458840049 2.3629384041 0.0239722397 0.7913340000 954023963 0 1782521856 -0.7904059291 0.1719999760 0.3840813041 811 32.4000000000 0.6265147924 0.5459834263 2.3629384041 0.0239634413 0.7591860000 954025237 0 1784156160 -0.7927693129 0.1682347357 0.3852071166 812 32.4399999990 0.6281918883 0.5460846682 2.3629384041 0.0239547411 0.7672590000 954026511 0 1782870016 -0.7950393558 0.1648310274 0.3861922324 813 32.4800000000 0.6306771040 0.5461887180 2.3629384041 0.0239470869 0.7692390000 954027785 0 1781600256 -0.7978556156 0.1624530405 0.3875695765 814 32.5200000000 0.6326646209 0.5462949537 2.3629384041 0.0239397069 0.7621120000 954029059 0 1783361536 -0.8007187247 0.1599457711 0.3891255260 815 32.5600000000 0.6346042156 0.5464033087 2.3629384041 0.0239308935 0.7663440000 954030333 0 1781993472 -0.8037942648 0.1568336487 0.3907914758 816 32.6000000000 0.6365298033 0.5465137578 2.3629384041 0.0239255785 0.7684620000 954031607 0 1783631872 -0.8069393635 0.1531140506 0.3931716681 817 32.6400000000 0.6385719180 0.5466264361 2.3629384041 0.0239180834 0.7736900000 954032881 0 1782472704 -0.8101736307 0.1494150609 0.3950265944 818 32.6800000000 0.6414222121 0.5467423233 2.3629384041 0.0239093961 0.7751760000 954034155 0 1784029184 -0.8137742877 0.1461015791 0.3968164921 819 32.7200000000 0.6452289224 0.5468625756 2.3629384041 0.0239018648 0.7795180000 954035429 0 1782902784 -0.8178377151 0.1443142146 0.3985806406 820 32.7599999990 0.6486369371 0.5469866907 2.3629384041 0.0238949221 0.7871510000 954036703 0 1784520704 -0.8219254613 0.1426341683 0.4004366994 821 32.7999999990 0.6530435681 0.5471158708 2.3629384041 0.0238937373 0.7863510000 954037977 0 1783234560 -0.8266387582 0.1419093013 0.4031992257 822 32.8400000000 0.6561757922 0.5472485471 2.3629384041 0.0239022167 0.7890770000 954039251 0 1781964800 -0.8309900165 0.1412586868 0.4060013294 823 32.8800000000 0.6596456766 0.5473851171 2.3629384041 0.0239101062 0.8087800000 954040525 0 1783631872 -0.8356612921 0.1411422491 0.4085516036 824 32.9200000000 0.6648859382 0.5475277152 2.3629384041 0.0239112768 0.8482040000 954041799 0 1782394880 -0.8411475420 0.1411244720 0.4107144177 825 32.9600000000 0.6697712541 0.5476758892 2.3629384041 0.0239113355 0.8181460000 954043073 0 1784008704 -0.8466286659 0.1401138306 0.4133159816 826 33.0000000000 0.6753036976 0.5478304023 2.3629384041 0.0239074923 0.8236480000 954044347 0 1782775808 -0.8524438143 0.1396302134 0.4155845642 827 33.0400000000 0.6800363660 0.5479902644 2.3629384041 0.0239071408 0.8285620000 954045621 0 1784377344 -0.8579723835 0.1375831962 0.4182401597 828 33.0800000000 0.6842522621 0.5481548320 2.3629384041 0.0239203802 0.8278120000 954046895 0 1783107584 -0.8632964492 0.1346066743 0.4214358330 829 33.1199999990 0.6894385219 0.5483252587 2.3629384041 0.0239389309 0.8257110000 954048169 0 1781768192 -0.8693726659 0.1319954544 0.4243339896 830 33.1600000000 0.6942241788 0.5485010405 2.3629384041 0.0239586071 0.8690870000 954049443 0 1783377920 -0.8750454187 0.1293596029 0.4271950722 831 33.2000000000 0.6990679502 0.5486822281 2.3629384041 0.0239827778 0.8348490000 954050717 0 1782132736 -0.8811765909 0.1258683354 0.4314241409 832 33.2400000000 0.7042380571 0.5488691942 2.3629384041 0.0240013631 0.8404170000 954051991 0 1783783424 -0.8873801231 0.1226919442 0.4346614480 833 33.2800000000 0.7101894021 0.5490628560 2.3629384041 0.0240095560 0.8383930000 954053265 0 1782513664 -0.8939688802 0.1203242987 0.4374129176 834 33.3200000000 0.7152490616 0.5492621200 2.3629384041 0.0240139160 0.8407270000 954054539 0 1784004608 -0.9001657963 0.1166103780 0.4407290220 835 33.3600000000 0.7209677100 0.5494677554 2.3629384041 0.0240245804 0.8429810000 954055813 0 1782751232 -0.9064294696 0.1143163145 0.4429012239 836 33.4000000000 0.7266215086 0.5496796618 2.3629384041 0.0240390747 0.8425230000 954057087 0 1784418304 -0.9128321409 0.1117561832 0.4458960295 837 33.4399999990 0.7324607968 0.5498980383 2.3629384041 0.0240557646 0.8437340000 954058361 0 1783128064 -0.9191183448 0.1099429354 0.4481622279 838 33.4800000000 0.7369112968 0.5501212045 2.3629384041 0.0240812037 0.8558750000 954059635 0 1781776384 -0.9247380495 0.1064378545 0.4516898394 839 33.5200000000 0.7424843311 0.5503504812 2.3629384041 0.0241093698 0.8502810000 954060909 0 1783373824 -0.9308837056 0.1047324464 0.4547241032 840 33.5600000000 0.7474098802 0.5505850757 2.3629384041 0.0241271139 0.8725100000 954062183 0 1782140928 -0.9357738495 0.1029588282 0.4547882080 841 33.6000000000 0.7523899674 0.5508250340 2.3629384041 0.0241257226 0.8533060000 954063457 0 1783742464 -0.9413473010 0.1010775641 0.4567008615 842 33.6400000000 0.7573413253 0.5510703027 2.3629384041 0.0241198407 0.8976220000 954064731 0 1782726656 -0.9465239048 0.0994107053 0.4579722285 843 33.6800000000 0.7619784474 0.5513204903 2.3629384041 0.0241174704 0.8620700000 954066005 0 1784266752 -0.9517281651 0.0967262909 0.4600374997 844 33.7200000000 0.7655436993 0.5515743093 2.3629384041 0.0241199027 0.8603460000 954067279 0 1783013376 -0.9564535022 0.0927757248 0.4628390670 845 33.7599999990 0.7696374655 0.5518323722 2.3629384041 0.0241292867 0.8595020000 954068553 0 1781768192 -0.9612821937 0.0903541520 0.4658625722 846 33.7999999990 0.7737087607 0.5520946374 2.3629384041 0.0241352759 0.8649000000 954069827 0 1783377920 -0.9658818245 0.0884839520 0.4674885869 847 33.8400000000 0.7762115002 0.5523592382 2.3629384041 0.0241301386 0.8670220000 954071101 0 1782263808 -0.9694799185 0.0845707506 0.4695286453 848 33.8800000000 0.7795993686 0.5526272101 2.3629384041 0.0241221411 0.9044220000 954072375 0 1783996416 -0.9735665321 0.0815703720 0.4713971019 849 33.9200000000 0.7810755968 0.5528962894 2.3629384041 0.0241100806 0.8581740000 954073649 0 1782853632 -0.9771178365 0.0765241906 0.4747988284 850 33.9600000000 0.7836909890 0.5531678126 2.3629384041 0.0240976002 0.8481080000 954074923 0 1781710848 -0.9809494019 0.0723284408 0.4773043394 851 34.0000000000 0.7872360349 0.5534428634 2.3629384041 0.0240858869 0.8494180000 954076197 0 1783361536 -0.9850280285 0.0693718791 0.4788951874 852 34.0400000000 0.7899968624 0.5537205089 2.3629384041 0.0240755171 0.8521670000 954077471 0 1782390784 -0.9885119200 0.0654985011 0.4815729856 853 34.0800000000 0.7914366126 0.5539991914 2.3629384041 0.0240681655 0.8535810000 954078745 0 1784012800 -0.9916252494 0.0616137609 0.4842069149 854 34.1199999990 0.7937648296 0.5542799474 2.3629384041 0.0240617164 0.8959530000 954080019 0 1783009280 -0.9950141311 0.0590703860 0.4868262708 855 34.1600000000 0.7957329154 0.5545623485 2.3629384041 0.0240547029 0.8634000000 954081293 0 1781620736 -0.9979826808 0.0572367422 0.4896767437 856 34.2000000000 0.7971089482 0.5548456973 2.3629384041 0.0240451255 0.8576190000 954082567 0 1783250944 -1.0006387234 0.0552379005 0.4920352995 857 34.2400000000 0.8000244498 0.5551317869 2.3629384041 0.0240324843 0.8593250000 954083841 0 1781964800 -1.0036717653 0.0542608947 0.4925520718 858 34.2800000000 0.8029274344 0.5554205930 2.3629384041 0.0240191496 0.8557960000 954085115 0 1783615488 -1.0063115358 0.0528055914 0.4921459556 859 34.3200000000 0.8041597605 0.5557101613 2.3629384041 0.0240064637 0.8590930000 954086389 0 1782218752 -1.0080432892 0.0484987907 0.4935667217 860 34.3600000000 0.8043304682 0.5559992547 2.3629384041 0.0239940961 0.8574550000 954087663 0 1783885824 -1.0097230673 0.0434714146 0.4955474734 861 34.4000000000 0.8062322736 0.5562898854 2.3629384041 0.0239831871 0.8669300000 954088937 0 1782611968 -1.0122921467 0.0396656692 0.4973241389 862 34.4400000000 0.8074086905 0.5565812065 2.3629384041 0.0239710174 0.8612550000 954090211 0 1784283136 -1.0142316818 0.0358651988 0.4989930093 863 34.4800000000 0.8068135381 0.5568711628 2.3629384041 0.0239601398 0.8612770000 954091485 0 1782898688 -1.0153129101 0.0307049677 0.5013422966 864 34.5200000000 0.8072876930 0.5571609968 2.3629384041 0.0239498460 0.8586930000 954092759 0 1781862400 -1.0169804096 0.0268705413 0.5038987994 865 34.5600000000 0.8082147241 0.5574512323 2.3629384041 0.0239374529 0.8585380000 954094033 0 1783631872 -1.0188959837 0.0248748530 0.5053065419 866 34.6000000000 0.8091996908 0.5577419349 2.3629384041 0.0239239917 0.9004090000 954095307 0 1782218752 -1.0203965902 0.0231195483 0.5054204464 867 34.6400000000 0.8111652136 0.5580342340 2.3629384041 0.0239106265 0.8590860000 954096581 0 1784012800 -1.0219964981 0.0212176740 0.5056659579 868 34.6800000000 0.8113278151 0.5583260469 2.3629384041 0.0238992336 0.8612730000 954097855 0 1783042048 -1.0229150057 0.0182895698 0.5062175393 869 34.7200000000 0.8114378452 0.5586173147 2.3629384041 0.0238879285 0.8617920000 954099129 0 1782005760 -1.0237295628 0.0154092284 0.5080411434 870 34.7600000000 0.8106331825 0.5589069882 2.3629384041 0.0238758615 0.8601980000 954100403 0 1783652352 -1.0244442225 0.0124885766 0.5093882084 871 34.8000000000 0.8108985424 0.5591963011 2.3629384041 0.0238632616 0.8604910000 954101677 0 1782632448 -1.0254786015 0.0102118785 0.5099163651 872 34.8400000000 0.8111466169 0.5594852349 2.3629384041 0.0238517966 0.8914300000 954102951 0 1784434688 -1.0265040398 0.0073422873 0.5100764632 873 34.8800000000 0.8124627471 0.5597750144 2.3629384041 0.0238406171 0.8601780000 954104225 0 1783275520 -1.0280511379 0.0050851041 0.5106729865 874 34.9200000000 0.8136201501 0.5600654551 2.3629384041 0.0238300958 0.8588950000 954105499 0 1782226944 -1.0294673443 0.0034436248 0.5109772086 875 34.9600000000 0.8156021237 0.5603574970 2.3629384041 0.0238194078 0.8572700000 954106773 0 1783910400 -1.0314099789 0.0030350978 0.5104404092 876 35.0000000000 0.8175321221 0.5606510753 2.3629384041 0.0238079049 0.8605570000 954108047 0 1782894592 -1.0329849720 0.0026743114 0.5098158717 877 35.0400000000 0.8194911480 0.5609462180 2.3629384041 0.0237950303 0.8611520000 954109321 0 1782157312 -1.0346509218 0.0024727951 0.5093392134 878 35.0800000000 0.8211787343 0.5612426103 2.3629384041 0.0237815214 0.8955650000 954110595 0 1783926784 -1.0360985994 0.0027084970 0.5086297393 879 35.1200000000 0.8224171400 0.5615397372 2.3629384041 0.0237680082 0.8559420000 954111869 0 1783013376 -1.0374147892 0.0022073176 0.5084083080 880 35.1600000000 0.8243846297 0.5618384246 2.3629384041 0.0237546427 0.8584940000 954113143 0 1781882880 -1.0389436483 0.0025726659 0.5080454350 881 35.2000000000 0.8262577057 0.5621385600 2.3629384041 0.0237414943 0.8588870000 954114417 0 1783615488 -1.0405169725 0.0028982456 0.5072843432 882 35.2400000000 0.8262278438 0.5624379810 2.3629384041 0.0237280868 0.8597620000 954115691 0 1782345728 -1.0409868956 0.0002449313 0.5083729029 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-19 02:16:54 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.8259080000 954995638 0 1770733568 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0003881263 0.0001940631 0.0003881263 0.0010333611 1.0233760000 953385763 0 1765085184 -0.0001940523 0.0036086100 0.0017813192 3 0.0800000000 0.0007211429 0.0003697564 0.0007211429 0.0018866465 0.9388230000 953074305 0 1766805504 -0.0019451390 -0.0020266830 0.0017657793 4 0.1200000000 0.0008640065 0.0004933189 0.0008640065 0.0023545570 0.9353190000 953075907 0 1768488960 -0.0023192738 -0.0007952096 0.0006177251 5 0.1600000000 0.0010552917 0.0006057135 0.0010552917 0.0042423851 0.9627340000 953077181 0 1770246144 -0.0001187189 0.0056788325 0.0036431807 6 0.2000000000 0.0012217654 0.0007083888 0.0012217654 0.0040664473 0.9578650000 953079111 0 1771917312 0.0030027553 -0.0044090343 0.0027599339 7 0.2400000000 0.0012698837 0.0007886024 0.0012698837 0.0039254769 0.9979490000 953080385 0 1774944256 0.0032089448 -0.0144204032 -0.0003563718 8 0.2800000000 0.0012073653 0.0008409477 0.0012698837 0.0036445731 0.9425020000 953081659 0 1776709632 0.0010051118 -0.0127783921 -0.0012683957 9 0.3200000000 0.0010883431 0.0008684361 0.0012698837 0.0045220793 0.9368740000 953082933 0 1778360320 -0.0001103831 -0.0090666683 0.0016685696 10 0.3600000000 0.0014994163 0.0009315341 0.0014994163 0.0042875227 0.9384850000 953085519 0 1780011008 -0.0020229411 -0.0159801748 -0.0001115449 11 0.4000000000 0.0013570037 0.0009702132 0.0014994163 0.0041268347 0.9313070000 953086793 0 1781780480 -0.0019455865 -0.0125929080 -0.0013916764 12 0.4400000000 0.0015243968 0.0010163952 0.0015243968 0.0041904032 0.9552000000 953088067 0 1783431168 -0.0009501032 -0.0024546958 0.0015401212 13 0.4800000000 0.0015203318 0.0010551595 0.0015243968 0.0040158152 0.9387940000 953089341 0 1781915648 0.0010167509 -0.0045938040 0.0015782597 14 0.5200000000 0.0016968712 0.0011009961 0.0016968712 0.0039728100 0.9532690000 953090615 0 1783431168 0.0039402922 -0.0120999720 -0.0011736540 15 0.5600000000 0.0013440389 0.0011171989 0.0016968712 0.0039349492 0.9441200000 953091889 0 1782083584 0.0065079909 -0.0107586458 -0.0013718579 16 0.6000000000 0.0014858663 0.0011402406 0.0016968712 0.0038099059 0.9323360000 953093163 0 1783574528 0.0077317939 -0.0094446698 -0.0010760449 17 0.6400000000 0.0016916678 0.0011726775 0.0016968712 0.0037102063 0.9293220000 953094437 0 1782083584 0.0074940114 -0.0129345423 -0.0028987098 18 0.6800000000 0.0015150504 0.0011916982 0.0016968712 0.0036018900 0.9329890000 953098335 0 1783582720 0.0066664973 -0.0120898513 -0.0042951098 19 0.7200000000 0.0017877599 0.0012230699 0.0017877599 0.0036713333 0.9916590000 953099609 0 1782181888 0.0073413188 -0.0077866302 -0.0040916274 20 0.7600000000 0.0016812142 0.0012459771 0.0017877599 0.0039498345 0.9329160000 953100883 0 1783820288 0.0067599341 -0.0091080507 -0.0066858632 21 0.8000000000 0.0018798064 0.0012761595 0.0018798064 0.0041365165 0.9589600000 953102157 0 1782546432 0.0094311796 -0.0058905394 -0.0064882729 22 0.8400000000 0.0017238290 0.0012965081 0.0018798064 0.0040716751 0.9346390000 953103431 0 1784201216 0.0095290691 -0.0033452257 -0.0061299056 23 0.8800000000 0.0019181789 0.0013235372 0.0019181789 0.0040459337 0.9539580000 953104705 0 1782816768 0.0122243939 -0.0094487602 -0.0100603420 24 0.9200000000 0.0017549687 0.0013415136 0.0019181789 0.0040366121 0.9359350000 953105979 0 1784455168 0.0142292166 -0.0084284069 -0.0099117905 25 0.9600000000 0.0018983454 0.0013637868 0.0019181789 0.0039536868 0.9381020000 953107253 0 1783242752 0.0143053634 -0.0110958023 -0.0129500115 26 1.0000000000 0.0018951360 0.0013842233 0.0019181789 0.0038745562 0.9435260000 953108527 0 1781821440 0.0126407268 -0.0115280608 -0.0139671285 27 1.0400000000 0.0020072646 0.0014072989 0.0020072646 0.0038137422 0.9307730000 953109801 0 1783484416 0.0137046194 -0.0154553959 -0.0164126065 28 1.0800000000 0.0019873453 0.0014280149 0.0020072646 0.0037460087 0.9405610000 953111075 0 1782206464 0.0125787705 -0.0176726561 -0.0178422425 29 1.1200000000 0.0020048956 0.0014479073 0.0020072646 0.0037666314 0.9348040000 953112349 0 1783812096 0.0137591409 -0.0197222568 -0.0190353431 30 1.1600000000 0.0018466520 0.0014611988 0.0020072646 0.0037355185 0.9388100000 953113623 0 1782542336 0.0169673078 -0.0190150943 -0.0194324479 31 1.2000000000 0.0021455453 0.0014832745 0.0021455453 0.0037431940 0.9594030000 953114897 0 1784311808 0.0218952298 -0.0174801815 -0.0208284352 32 1.2400000000 0.0018769824 0.0014955779 0.0021455453 0.0037877226 0.9329470000 953116171 0 1783042048 0.0221752841 -0.0146748107 -0.0219452120 33 1.2800000000 0.0021589387 0.0015156797 0.0021589387 0.0040354142 0.9447230000 953117445 0 1781518336 0.0235111173 -0.0102991937 -0.0220287573 34 1.3200000000 0.0021975997 0.0015357362 0.0021975997 0.0042478665 0.9300230000 953123967 0 1783422976 0.0317813829 -0.0078666443 -0.0243408773 35 1.3600000000 0.0021009310 0.0015518846 0.0021975997 0.0041881770 0.9025480000 953125241 0 1782198272 0.0309623592 -0.0092785256 -0.0259293467 36 1.4000000000 0.0021279689 0.0015678870 0.0021975997 0.0041387427 0.9009410000 953126515 0 1783955456 0.0313442349 -0.0115507534 -0.0293286927 37 1.4400000000 0.0021159369 0.0015826991 0.0021975997 0.0040818707 0.9266470000 953127789 0 1782550528 0.0339456238 -0.0126444893 -0.0316049084 38 1.4800000000 0.0021567827 0.0015978066 0.0021975997 0.0040270145 0.8894020000 953129063 0 1784336384 0.0338486321 -0.0126470802 -0.0318739712 39 1.5200000000 0.0021337562 0.0016115489 0.0021975997 0.0039993253 0.8868420000 953130337 0 1783074816 0.0346376449 -0.0119361216 -0.0328073651 40 1.5600000000 0.0021122920 0.0016240675 0.0021975997 0.0041980284 0.8869780000 953131611 0 1781436416 0.0376095846 -0.0116420658 -0.0336467177 41 1.6000000000 0.0023531662 0.0016418503 0.0023531662 0.0044641356 0.8883570000 953132885 0 1783103488 0.0432794355 -0.0096684834 -0.0342809744 42 1.6400000000 0.0022277071 0.0016557993 0.0023531662 0.0044263719 0.8759920000 953134159 0 1781653504 0.0436204374 -0.0099310521 -0.0355459005 43 1.6800000000 0.0022249743 0.0016690359 0.0023531662 0.0044127577 0.8692870000 953135433 0 1783431168 0.0454232767 -0.0101228831 -0.0370668620 44 1.7200000000 0.0021790185 0.0016806265 0.0023531662 0.0043828241 0.8587540000 953136707 0 1782153216 0.0473813564 -0.0092666736 -0.0372761302 45 1.7600000000 0.0021316784 0.0016906498 0.0023531662 0.0045699315 0.8514820000 953137981 0 1783967744 0.0492033884 -0.0077264439 -0.0384219065 46 1.8000000000 0.0022145605 0.0017020392 0.0023531662 0.0046636509 0.8499910000 953139255 0 1782542336 0.0507014804 -0.0068858871 -0.0391054265 47 1.8400000000 0.0024187560 0.0017172885 0.0024187560 0.0046737143 0.8645640000 953140529 0 1784328192 0.0524861142 -0.0040459926 -0.0395063683 48 1.8800000000 0.0021772922 0.0017268719 0.0024187560 0.0046573866 0.8507800000 953141803 0 1783070720 0.0543598086 -0.0032750939 -0.0393008403 49 1.9200000000 0.0022766755 0.0017380924 0.0024187560 0.0046889094 0.8760210000 953143077 0 1781702656 0.0554875135 -0.0055013741 -0.0411554426 50 1.9600000000 0.0023217972 0.0017497665 0.0024187560 0.0046627666 0.8432120000 953144351 0 1783422976 0.0509126745 -0.0035073820 -0.0431814604 51 2.0000000000 0.0022670222 0.0017599087 0.0024187560 0.0046600533 0.8468420000 953145625 0 1782153216 0.0501251891 0.0006700824 -0.0423161313 52 2.0400000000 0.0023658446 0.0017715614 0.0024187560 0.0046347541 0.8347280000 953146899 0 1783947264 0.0501660071 -0.0010062853 -0.0425400957 53 2.0800000000 0.0024408812 0.0017841900 0.0024408812 0.0046008280 0.8317610000 953148173 0 1782689792 0.0504351854 -0.0051818588 -0.0448345616 54 2.1200000000 0.0022424429 0.0017926762 0.0024408812 0.0046224988 0.8293260000 953149447 0 1784344576 0.0507728308 -0.0043760245 -0.0444331095 55 2.1600000000 0.0021923073 0.0017999422 0.0024408812 0.0046148550 0.8508620000 953150721 0 1783074816 0.0516592786 -0.0022814365 -0.0443636812 56 2.2000000000 0.0022699158 0.0018083346 0.0024408812 0.0046229630 0.8158790000 953151995 0 1781702656 0.0530546121 -0.0027904531 -0.0452460237 57 2.2400000000 0.0023484798 0.0018178108 0.0024408812 0.0046395090 0.8150510000 953153269 0 1783296000 0.0533399209 -0.0052824696 -0.0475350134 58 2.2800000000 0.0025689355 0.0018307613 0.0025689355 0.0048108104 0.8279400000 953154543 0 1781944320 0.0571397357 -0.0035924444 -0.0470067896 59 2.3200000000 0.0026037595 0.0018438629 0.0026037595 0.0049712651 0.8229920000 953155817 0 1783693312 0.0609237961 -0.0008012513 -0.0477212369 60 2.3600000000 0.0026250924 0.0018568834 0.0026250924 0.0050212424 0.8269300000 953157091 0 1782312960 0.0642571971 -0.0051397495 -0.0503228754 61 2.4000000000 0.0025686112 0.0018685511 0.0026250924 0.0050104770 0.8334860000 953158365 0 1783947264 0.0640233234 -0.0078689326 -0.0517068133 62 2.4400000000 0.0024076076 0.0018772455 0.0026250924 0.0050547054 0.7929670000 953159639 0 1782566912 0.0660888329 -0.0071850228 -0.0511818789 63 2.4800000000 0.0026780702 0.0018899571 0.0026780702 0.0050912618 0.8062140000 953160913 0 1784184832 0.0724292397 -0.0050554001 -0.0512449555 64 2.5200000000 0.0026639283 0.0019020504 0.0026780702 0.0050669772 0.8040690000 953162187 0 1782820864 0.0747830048 -0.0091883652 -0.0551531576 65 2.5600000000 0.0024824566 0.0019109797 0.0026780702 0.0050569824 0.7810040000 953163461 0 1784471552 0.0759560764 -0.0088118883 -0.0549784452 66 2.6000000000 0.0025767437 0.0019210670 0.0026780702 0.0050192829 0.7830250000 953175231 0 1783201792 0.0728055984 -0.0126218451 -0.0567811914 67 2.6400000000 0.0024373026 0.0019287720 0.0026780702 0.0050505411 0.7704450000 953176505 0 1781780480 0.0730713755 -0.0144207571 -0.0585783087 68 2.6800000000 0.0027540582 0.0019409086 0.0027540582 0.0051325031 0.7870170000 953177779 0 1783422976 0.0783797726 -0.0166709479 -0.0589998178 69 2.7200000000 0.0023668185 0.0019470812 0.0027540582 0.0051502484 0.7656270000 953179053 0 1782091776 0.0797838345 -0.0166945774 -0.0601100177 70 2.7600000000 0.0027634311 0.0019587433 0.0027634311 0.0052040047 0.7783740000 953180327 0 1783693312 0.0824580491 -0.0146073699 -0.0608541891 71 2.8000000000 0.0027494603 0.0019698802 0.0027634311 0.0052473095 0.7762480000 953181601 0 1782312960 0.0849826634 -0.0139193591 -0.0625933409 72 2.8400000000 0.0023677356 0.0019754060 0.0027634311 0.0052636978 0.7617990000 953182875 0 1783803904 0.0865467936 -0.0147398300 -0.0634094179 73 2.8800000000 0.0027488077 0.0019860005 0.0027634311 0.0053160917 0.7718150000 953184149 0 1782439936 0.0892937630 -0.0116770649 -0.0657262877 74 2.9200000000 0.0028382838 0.0019975178 0.0028382838 0.0054345358 0.7675730000 953185423 0 1784074240 0.0912256762 -0.0117970845 -0.0687618405 75 2.9600000000 0.0028578863 0.0020089894 0.0028578863 0.0054762209 0.8007740000 953186697 0 1782546432 0.0968059674 -0.0118469754 -0.0702111349 76 3.0000000000 0.0028256236 0.0020197346 0.0028578863 0.0054963200 0.7576840000 953187971 0 1784217600 0.1002148017 -0.0103617907 -0.0719309747 77 3.0400000000 0.0022811822 0.0020231300 0.0028578863 0.0055168389 0.7352740000 953189245 0 1782915072 0.1028734073 -0.0105563905 -0.0728534311 78 3.0800000000 0.0028893780 0.0020342358 0.0028893780 0.0054913790 0.7494610000 953190519 0 1781583872 0.1061240658 -0.0120873051 -0.0764956474 79 3.1200000000 0.0028701182 0.0020448166 0.0028893780 0.0055143837 0.7488830000 953191793 0 1783209984 0.1098565981 -0.0107130501 -0.0769850612 80 3.1600000000 0.0028423625 0.0020547859 0.0028893780 0.0054980444 0.7384400000 953193067 0 1781841920 0.1136287749 -0.0110421311 -0.0798505768 81 3.2000000000 0.0029422552 0.0020657423 0.0029422552 0.0054775457 0.7369600000 953194341 0 1783431168 0.1192786396 -0.0124088489 -0.0814535171 82 3.2400000000 0.0029344733 0.0020763366 0.0029422552 0.0054510434 0.7336210000 953195615 0 1782083584 0.1233354136 -0.0138706835 -0.0837719589 83 3.2800000000 0.0021270576 0.0020769477 0.0029422552 0.0054340718 0.7099490000 953196889 0 1783697408 0.1247441843 -0.0148397190 -0.0857043639 84 3.3200000000 0.0029164273 0.0020869415 0.0029422552 0.0054142597 0.7251020000 953198163 0 1782448128 0.1314346641 -0.0144071355 -0.0886911675 85 3.3600000000 0.0028968421 0.0020964697 0.0029422552 0.0053848562 0.7223830000 953199437 0 1784066048 0.1419917047 -0.0111498712 -0.0887685940 86 3.4000000000 0.0018575918 0.0020936921 0.0029422552 0.0054112240 0.7042170000 953200711 0 1782702080 0.1440492421 -0.0102205426 -0.0908332691 87 3.4400000000 0.0017664534 0.0020899307 0.0029422552 0.0054080413 0.6977220000 953201985 0 1784336384 0.1459816843 -0.0105157401 -0.0936278328 88 3.4800000000 0.0028933457 0.0020990604 0.0029422552 0.0053799408 0.7211250000 953203259 0 1783050240 0.1522522271 -0.0068649882 -0.0946388319 89 3.5200000000 0.0019383691 0.0020972549 0.0029422552 0.0053597387 0.7283320000 953204533 0 1781555200 0.1546663344 -0.0075008860 -0.0956141502 90 3.5600000000 0.0017808339 0.0020937391 0.0029422552 0.0053324457 0.6909780000 953205807 0 1783058432 0.1575242132 -0.0075799152 -0.0970878303 91 3.6000000000 0.0028545640 0.0021020998 0.0029422552 0.0053784628 0.7088040000 953207081 0 1781559296 0.1644373238 -0.0060271742 -0.0983095765 92 3.6400000000 0.0028971862 0.0021107421 0.0029422552 0.0054548951 0.7084700000 953208355 0 1783042048 0.1738338321 -0.0032193428 -0.0982872397 93 3.6800000000 0.0028789677 0.0021190026 0.0029422552 0.0054700080 0.6983070000 953209629 0 1781686272 0.1819665283 0.0007607164 -0.0997446701 94 3.7200000000 0.0029980363 0.0021283540 0.0029980363 0.0054463450 0.6937330000 953210903 0 1783185408 0.1903028637 0.0002183826 -0.1023092121 95 3.7600000000 0.0030176518 0.0021377150 0.0030176518 0.0054189491 0.6926640000 953212177 0 1781645312 0.1964348406 0.0002131662 -0.1047842279 96 3.8000000000 0.0030817462 0.0021475487 0.0030817462 0.0054038474 0.6879770000 953213451 0 1783185408 0.2039246410 -0.0009953497 -0.1067652777 97 3.8400000000 0.0030542433 0.0021568960 0.0030817462 0.0053780649 0.7324190000 953214725 0 1781833728 0.2118429393 0.0004565464 -0.1098655909 98 3.8800000000 0.0031273379 0.0021667985 0.0031273379 0.0053513263 0.6864580000 953215999 0 1783328768 0.2203843445 0.0006080307 -0.1106900573 99 3.9200000000 0.0031462854 0.0021766923 0.0031462854 0.0053613224 0.6887740000 953217273 0 1781817344 0.2286081612 -0.0000052899 -0.1125907898 100 3.9600000000 0.0031817560 0.0021867430 0.0031817560 0.0053362478 0.6799990000 953218547 0 1783312384 0.2362652421 0.0004141382 -0.1130118221 101 4.0000000000 0.0031515153 0.0021962952 0.0031817560 0.0053256941 0.6817800000 953219821 0 1781944320 0.2448963821 0.0024855062 -0.1143302470 102 4.0400000000 0.0019539411 0.0021939191 0.0031817560 0.0053463318 0.6629720000 953221095 0 1783549952 0.2483409047 0.0012676260 -0.1158780083 103 4.0800000000 0.0031076933 0.0022027907 0.0031817560 0.0053204702 0.6784970000 953222369 0 1781964800 0.2576060295 0.0051592900 -0.1156237721 104 4.1200000000 0.0031505490 0.0022119038 0.0031817560 0.0052958055 0.6736090000 953223643 0 1783582720 0.2680364251 0.0078305146 -0.1163259149 105 4.1600000000 0.0031940746 0.0022212578 0.0031940746 0.0052878178 0.6781590000 953224917 0 1782026240 0.2746435106 0.0092007946 -0.1165760830 106 4.2000000000 0.0032492685 0.0022309560 0.0032492685 0.0053001600 0.6740600000 953226191 0 1783709696 0.2815669477 0.0075077633 -0.1190995872 107 4.2400000000 0.0032653911 0.0022406236 0.0032653911 0.0052773805 0.6881490000 953227465 0 1782419456 0.2894879282 0.0065861093 -0.1203104481 108 4.2800000000 0.0032519903 0.0022499881 0.0032653911 0.0052610311 0.6699170000 953228739 0 1784057856 0.2981427014 0.0067423424 -0.1220755279 109 4.3200000000 0.0034310978 0.0022608240 0.0034310978 0.0052411220 0.6880310000 953230013 0 1782693888 0.3153135478 0.0065540345 -0.1246544346 110 4.3600000000 0.0032861680 0.0022701453 0.0034310978 0.0052375347 0.6656660000 953231287 0 1784328192 0.3273329735 0.0074607730 -0.1253699213 111 4.4000000000 0.0033445780 0.0022798249 0.0034310978 0.0052140205 0.6677200000 953232561 0 1782915072 0.3371117711 0.0067626019 -0.1270627677 112 4.4400000000 0.0025944759 0.0022826343 0.0034310978 0.0051938425 0.6524270000 953233835 0 1781555200 0.3409480155 0.0028756920 -0.1290723830 113 4.4800000000 0.0032916616 0.0022915637 0.0034310978 0.0051714870 0.7081500000 953235109 0 1783058432 0.3518296480 0.0019349639 -0.1304049343 114 4.5200000000 0.0033075260 0.0023004757 0.0034310978 0.0051553371 0.6675900000 953236383 0 1781686272 0.3627971411 0.0018346561 -0.1312977076 115 4.5600000000 0.0033377027 0.0023094950 0.0034310978 0.0051425030 0.6613130000 953237657 0 1783312384 0.3727826774 -0.0000169938 -0.1325936764 116 4.6000000000 0.0033887625 0.0023187991 0.0034310978 0.0051223865 0.6591270000 953238931 0 1781944320 0.3806789517 -0.0029450208 -0.1341945082 117 4.6400000000 0.0034054890 0.0023280870 0.0034310978 0.0051269381 0.6554360000 953240205 0 1783566336 0.3881557584 -0.0054616788 -0.1353447437 118 4.6800000000 0.0033762990 0.0023369702 0.0034310978 0.0051401594 0.6522360000 953241479 0 1782202368 0.3974255323 -0.0055791736 -0.1357126236 119 4.7200000000 0.0033885562 0.0023458070 0.0034310978 0.0051785995 0.6471780000 953242753 0 1783820288 0.4115477502 -0.0048991414 -0.1338302195 120 4.7600000000 0.0033975197 0.0023545713 0.0034310978 0.0051571637 0.6465850000 953244027 0 1782456320 0.4227978587 -0.0030094204 -0.1324203163 121 4.8000000000 0.0034969139 0.0023640121 0.0034969139 0.0051526963 0.6452430000 953245301 0 1784090624 0.4312384129 -0.0041011055 -0.1339133233 122 4.8400000000 0.0035005051 0.0023733277 0.0035005051 0.0051516283 0.6512710000 953246575 0 1782800384 0.4402763546 -0.0036332021 -0.1344350129 123 4.8800000000 0.0035126882 0.0023825908 0.0035126882 0.0051314708 0.6412480000 953247849 0 1784438784 0.4517433941 -0.0013766792 -0.1324632764 124 4.9200000000 0.0036389059 0.0023927223 0.0036389059 0.0051120980 0.6422480000 953249123 0 1783070720 0.4582326710 0.0001494214 -0.1292464882 125 4.9600000000 0.0036915492 0.0024031129 0.0036915492 0.0051038213 0.6441440000 953250397 0 1781702656 0.4616656899 -0.0000655884 -0.1277965605 126 5.0000000000 0.0036426934 0.0024129509 0.0036915492 0.0050896958 0.6438690000 953251671 0 1783422976 0.4709666073 -0.0000399491 -0.1260651052 127 5.0400000000 0.0036834581 0.0024229549 0.0036915492 0.0050724191 0.6440690000 953252945 0 1782194176 0.4811763465 -0.0001753904 -0.1238919795 128 5.0800000000 0.0036820162 0.0024327913 0.0036915492 0.0050665233 0.6404550000 953254219 0 1784090624 0.4930611849 0.0010819826 -0.1205547601 129 5.1200000000 0.0037074133 0.0024426721 0.0037074133 0.0050592072 0.6470860000 953255493 0 1782812672 0.5041992664 0.0024149842 -0.1170086712 130 5.1600000000 0.0037748993 0.0024529200 0.0037748993 0.0050412333 0.6409830000 953277759 0 1781817344 0.5108761787 0.0033423738 -0.1145467162 131 5.2000000000 0.0039145974 0.0024640778 0.0039145974 0.0050756946 0.6409870000 953279033 0 1783578624 0.5175778270 0.0026551750 -0.1114236712 132 5.2400000000 0.0038241157 0.0024743811 0.0039145974 0.0050617588 0.6414600000 953280307 0 1782288384 0.5283123255 0.0030545290 -0.1076136157 133 5.2800000000 0.0038344213 0.0024846070 0.0039145974 0.0050426875 0.6390340000 953281581 0 1784066048 0.5389285088 0.0039381795 -0.1031933278 134 5.3200000000 0.0039203949 0.0024953218 0.0039203949 0.0050899530 0.6374940000 953282855 0 1782947840 0.5475147367 0.0037301802 -0.1005027443 135 5.3600000000 0.0038940664 0.0025056829 0.0039203949 0.0051038837 0.6391990000 953284129 0 1784573952 0.5573081374 0.0046823523 -0.0970826447 136 5.4000000000 0.0040542833 0.0025170697 0.0040542833 0.0051308740 0.6524300000 953285403 0 1783455744 0.5714302659 0.0125526087 -0.0908371359 137 5.4400000000 0.0038856433 0.0025270593 0.0040542833 0.0051273979 0.6804430000 953286677 0 1782284288 0.5766417384 0.0160855576 -0.0870524198 138 5.4800000000 0.0040174061 0.0025378589 0.0040542833 0.0051730471 0.6335190000 953287951 0 1784057856 0.5802193880 0.0152762951 -0.0841876641 139 5.5200000000 0.0039007503 0.0025476639 0.0040542833 0.0051545965 0.6362080000 953289225 0 1782939648 0.5890861750 0.0157650523 -0.0792163908 140 5.5600000000 0.0039080144 0.0025573807 0.0040542833 0.0051380828 0.6340470000 953290499 0 1784619008 0.5975115895 0.0169902146 -0.0740919039 141 5.6000000000 0.0039190049 0.0025670376 0.0040542833 0.0051200259 0.6318570000 953291773 0 1783361536 0.6061477661 0.0179575365 -0.0692369044 142 5.6400000000 0.0039343121 0.0025766663 0.0040542833 0.0051051244 0.6322400000 953293047 0 1782431744 0.6170736551 0.0184215494 -0.0640323609 143 5.6800000000 0.0039606788 0.0025863447 0.0040542833 0.0050952075 0.6275870000 953294321 0 1783963648 0.6261430383 0.0203909017 -0.0587830544 144 5.7200000000 0.0040447302 0.0025964723 0.0040542833 0.0051137137 0.6279360000 953295595 0 1782812672 0.6321409345 0.0205378532 -0.0543432236 145 5.7600000000 0.0039927298 0.0026061017 0.0040542833 0.0051008492 0.6696220000 953296869 0 1784582144 0.6401028633 0.0209178887 -0.0490517318 146 5.8000000000 0.0039761523 0.0026154856 0.0040542833 0.0050856877 0.6278230000 953298143 0 1783296000 0.6498979330 0.0223803334 -0.0428841114 147 5.8400000000 0.0039167511 0.0026243378 0.0040542833 0.0050684304 0.6264410000 953299417 0 1781813248 0.6592545509 0.0262472518 -0.0367672443 148 5.8800000000 0.0040803296 0.0026341755 0.0040803296 0.0050916869 0.6243520000 953300691 0 1783566336 0.6635368466 0.0261610094 -0.0320641696 149 5.9200000000 0.0040146373 0.0026434404 0.0040803296 0.0050769831 0.6235080000 953301965 0 1782280192 0.6692796350 0.0255228430 -0.0276732147 150 5.9600000000 0.0038960685 0.0026517912 0.0040803296 0.0050822934 0.6198300000 953303239 0 1783963648 0.6772196293 0.0284923017 -0.0216730237 151 6.0000000000 0.0038539749 0.0026597527 0.0040803296 0.0050791888 0.6224530000 953304513 0 1782702080 0.6849811673 0.0306799971 -0.0169163048 152 6.0400000000 0.0040444010 0.0026688622 0.0040803296 0.0050874318 0.6275780000 953305787 0 1784459264 0.6983593702 0.0303456783 -0.0079049170 153 6.0800000000 0.0039543919 0.0026772644 0.0040803296 0.0051059453 0.6549450000 953307061 0 1783324672 0.7060841322 0.0313288234 -0.0024986865 154 6.1200000000 0.0040241731 0.0026860106 0.0040803296 0.0050895403 0.6199860000 953308335 0 1782210560 0.7123110890 0.0330450758 0.0025295317 155 6.1600000000 0.0040641278 0.0026949016 0.0040803296 0.0050892774 0.6170500000 953309609 0 1783947264 0.7165535688 0.0331060849 0.0067752302 156 6.2000000000 0.0039790948 0.0027031337 0.0040803296 0.0051025690 0.6194510000 953310883 0 1782829056 0.7251696587 0.0345497988 0.0124240834 157 6.2400000000 0.0041054091 0.0027120653 0.0041054091 0.0051125409 0.6173080000 953312157 0 1784455168 0.7319667935 0.0357549973 0.0183894616 158 6.2800000000 0.0041077435 0.0027208987 0.0041077435 0.0051219785 0.6187900000 953313431 0 1783455744 0.7365710735 0.0366642550 0.0241569579 159 6.3200000000 0.0040510562 0.0027292645 0.0041077435 0.0051517094 0.6177360000 953314705 0 1782321152 0.7438672781 0.0387660339 0.0310146511 160 6.3600000000 0.0042683370 0.0027388837 0.0042683370 0.0052058724 0.6184580000 953315979 0 1784057856 0.7575113773 0.0424899124 0.0452480875 161 6.4000000000 0.0041202432 0.0027474636 0.0042683370 0.0052307222 0.6150720000 953317253 0 1782939648 0.7614218593 0.0448145494 0.0521185100 162 6.4400000000 0.0040180543 0.0027553067 0.0042683370 0.0052207264 0.6134450000 953318527 0 1781809152 0.7664698362 0.0471812636 0.0598561764 163 6.4800000000 0.0039650607 0.0027627286 0.0042683370 0.0052297502 0.6125320000 953319801 0 1783459840 0.7729118466 0.0480182022 0.0679463670 164 6.5200000000 0.0039409380 0.0027699128 0.0042683370 0.0052402216 0.6163400000 953321075 0 1782321152 0.7806457281 0.0479306839 0.0760341063 165 6.5600000000 0.0039450685 0.0027770349 0.0042683370 0.0052467822 0.6142950000 953322349 0 1784074240 0.7893335223 0.0507089868 0.0848555639 166 6.6000000000 0.0039693341 0.0027842174 0.0042683370 0.0052691124 0.6151630000 953323623 0 1782820864 0.7973346114 0.0546711460 0.0939114094 167 6.6400000000 0.0040433304 0.0027917570 0.0042683370 0.0053200755 0.6137380000 953324897 0 1781813248 0.8017250896 0.0566000640 0.1020739973 168 6.6800000000 0.0038962208 0.0027983312 0.0042683370 0.0053245413 0.6169720000 953326171 0 1783422976 0.8086844683 0.0589769520 0.1108896807 169 6.7200000000 0.0039214939 0.0028049772 0.0042683370 0.0053185224 0.6131650000 953327445 0 1782448128 0.8174842596 0.0635419041 0.1214956194 170 6.7600000000 0.0039197225 0.0028115345 0.0042683370 0.0053319829 0.6557820000 953328719 0 1784090624 0.8231517076 0.0649570748 0.1297684163 171 6.8000000000 0.0039414489 0.0028181422 0.0042683370 0.0053164801 0.6154090000 953329993 0 1782796288 0.8325622082 0.0677816123 0.1400122344 172 6.8400000000 0.0040369616 0.0028252283 0.0042683370 0.0053010077 0.6116050000 953331267 0 1784492032 0.8407388330 0.0704838410 0.1502694488 173 6.8800000000 0.0039778552 0.0028318909 0.0042683370 0.0052861905 0.6136860000 953332541 0 1783169024 0.8445305824 0.0704571456 0.1574947685 174 6.9200000000 0.0039110864 0.0028380932 0.0042683370 0.0052785219 0.6146220000 953333815 0 1782194176 0.8528626561 0.0726822838 0.1672866642 175 6.9600000000 0.0038914995 0.0028441126 0.0042683370 0.0052663840 0.6098880000 953335089 0 1783836672 0.8625735641 0.0764485374 0.1777748168 176 7.0000000000 0.0040568165 0.0028510030 0.0042683370 0.0052515058 0.6230690000 953336363 0 1782661120 0.8695501685 0.0790018663 0.1877007484 177 7.0400000000 0.0040123551 0.0028575643 0.0042683370 0.0052910731 0.6286040000 953337637 0 1784344576 0.8742113709 0.0788815320 0.1958889365 178 7.0800000000 0.0039686169 0.0028638062 0.0042683370 0.0053192855 0.6669770000 953338911 0 1783087104 0.8784821033 0.0788860768 0.2037318051 179 7.1200000000 0.0039324882 0.0028697765 0.0042683370 0.0053049819 0.6261310000 953340185 0 1781899264 0.8844783902 0.0814099163 0.2129372656 180 7.1600000000 0.0038090909 0.0028749949 0.0042683370 0.0052956189 0.6247560000 953341459 0 1783730176 0.8906404376 0.0827477202 0.2220881879 181 7.2000000000 0.0039146151 0.0028807387 0.0042683370 0.0052811246 0.6287810000 953342733 0 1782411264 0.8945499659 0.0835262462 0.2309093177 182 7.2400000000 0.0036992645 0.0028852360 0.0042683370 0.0052677972 0.6276410000 953344007 0 1784201216 0.9001281857 0.0853615850 0.2395849824 183 7.2800000000 0.0037450180 0.0028899343 0.0042683370 0.0052535269 0.6348430000 953345281 0 1782968320 0.9054279327 0.0875858292 0.2489520907 184 7.3200000000 0.0036300910 0.0028939569 0.0042683370 0.0052459658 0.6395480000 953346555 0 1784700928 0.9108008146 0.0882299468 0.2565349042 185 7.3600000000 0.0021457186 0.0028899124 0.0042683370 0.0052419857 0.6223300000 953347829 0 1783353344 0.9126199484 0.0875017121 0.2631382048 186 7.4000000000 0.0036083693 0.0028937750 0.0042683370 0.0052279043 0.6816050000 953349103 0 1781952512 0.9199618697 0.0893982723 0.2720238864 187 7.4400000000 0.0036998226 0.0028980855 0.0042683370 0.0052271135 0.6442400000 953350377 0 1783558144 0.9250144958 0.0904628858 0.2793053091 188 7.4800000000 0.0037855243 0.0029028059 0.0042683370 0.0052137869 0.6492340000 953351651 0 1782312960 0.9292421341 0.0913836360 0.2859705687 189 7.5200000000 0.0027648206 0.0029020758 0.0042683370 0.0052021389 0.6370770000 953352925 0 1784082432 0.9313357472 0.0908793584 0.2925795019 190 7.5600000000 0.0037117584 0.0029063373 0.0042683370 0.0051963501 0.6599900000 953354199 0 1782923264 0.9374534488 0.0919739679 0.3004256785 191 7.6000000000 0.0039378814 0.0029117380 0.0042683370 0.0051864279 0.6586650000 953355473 0 1784590336 0.9414679408 0.0939223021 0.3085894287 192 7.6400000000 0.0040991283 0.0029179224 0.0042683370 0.0051732867 0.6724440000 953356747 0 1783345152 0.9444305301 0.0954950824 0.3169986904 193 7.6800000000 0.0043484797 0.0029253346 0.0043484797 0.0051607665 0.6696670000 953358021 0 1781899264 0.9501449466 0.0973975137 0.3323291838 194 7.7200000000 0.0041076876 0.0029314292 0.0043484797 0.0051473865 0.6710190000 953359295 0 1783709696 0.9535546899 0.0998358130 0.3411497176 195 7.7600000000 0.0040497682 0.0029371642 0.0043484797 0.0051342466 0.7002020000 953360569 0 1782312960 0.9582189322 0.1014303789 0.3597729206 196 7.8000000000 0.0043634223 0.0029444411 0.0043634223 0.0051270647 0.6837620000 953361843 0 1783947264 0.9588860273 0.1004433781 0.3683657646 197 7.8400000000 0.0043501435 0.0029515766 0.0043634223 0.0051151734 0.6861150000 953363117 0 1782566912 0.9614655972 0.1012376100 0.3785613179 198 7.8800000000 0.0044324449 0.0029590558 0.0044324449 0.0051022991 0.6914220000 953364391 0 1784201216 0.9636092186 0.1019150466 0.3895017207 199 7.9200000000 0.0044996855 0.0029667976 0.0044996855 0.0050970036 0.6968410000 953365665 0 1782820864 0.9638066292 0.1010573506 0.3995251656 200 7.9600000000 0.0045141871 0.0029745346 0.0045141871 0.0050861596 0.6959370000 953366939 0 1784438784 0.9659584165 0.1018987596 0.4104884267 201 8.0000000000 0.0041456334 0.0029803609 0.0045141871 0.0050746440 0.7186350000 953368213 0 1783201792 0.9679464698 0.1016950086 0.4221303165 202 8.0400000000 0.0041378448 0.0029860910 0.0045141871 0.0050627833 0.7566600000 953369487 0 1781813248 0.9676842093 0.1020409018 0.4324452281 203 8.0800000000 0.0041501634 0.0029918254 0.0045141871 0.0050505606 0.7144560000 953370761 0 1783439360 0.9675351381 0.1023454666 0.4431123137 204 8.1200000000 0.0041347467 0.0029974279 0.0045141871 0.0050412910 0.7149830000 953372035 0 1782026240 0.9676635861 0.1037524864 0.4538073540 205 8.1600000000 0.0041669421 0.0030031329 0.0045141871 0.0050527252 0.7210680000 953373309 0 1783693312 0.9688125253 0.1055723652 0.4655384421 206 8.1999999990 0.0041738511 0.0030088160 0.0045141871 0.0050597231 0.7282990000 953374583 0 1782439936 0.9694669843 0.1077029034 0.4777165651 207 8.2400000000 0.0041904058 0.0030145242 0.0045141871 0.0050554677 0.7243800000 953375857 0 1784057856 0.9703497291 0.1100884154 0.4905181825 208 8.2799999990 0.0041801459 0.0030201281 0.0045141871 0.0050561112 0.7300090000 953377131 0 1782693888 0.9700168371 0.1131434515 0.5022591352 209 8.3200000000 0.0046323356 0.0030278420 0.0046323356 0.0050513863 0.7584470000 953378405 0 1784328192 0.9706246257 0.1147581488 0.5137482882 210 8.3599999990 0.0042237053 0.0030335366 0.0046323356 0.0050398876 0.7328260000 953379679 0 1783074816 0.9708723426 0.1162181422 0.5259914398 211 8.4000000000 0.0042043366 0.0030390854 0.0046323356 0.0050359982 0.7362500000 953380953 0 1781645312 0.9712995291 0.1183306575 0.5383704305 212 8.4399999990 0.0042133094 0.0030446242 0.0046323356 0.0050290827 0.7431670000 953382227 0 1783312384 0.9703632593 0.1200802922 0.5507316589 213 8.4800000000 0.0042063333 0.0030500782 0.0046323356 0.0050211662 0.7409780000 953383501 0 1781944320 0.9690865278 0.1220590770 0.5622546673 214 8.5200000000 0.0041959863 0.0030554330 0.0046323356 0.0050168469 0.7417390000 953384775 0 1783566336 0.9683546424 0.1242350712 0.5735765100 215 8.5600000000 0.0042093121 0.0030607998 0.0046323356 0.0050077837 0.7438430000 953386049 0 1782153216 0.9685080647 0.1274784356 0.5857249498 216 8.6000000000 0.0041853520 0.0030660061 0.0046323356 0.0049992559 0.7459680000 953387323 0 1783930880 0.9691517949 0.1297006458 0.5980773568 217 8.6400000000 0.0041819881 0.0030711489 0.0046323356 0.0049926035 0.7487540000 953388597 0 1782566912 0.9680197835 0.1312916428 0.6089697480 218 8.6800000000 0.0041714334 0.0030761960 0.0046323356 0.0049872942 0.7528870000 953389871 0 1784201216 0.9663276672 0.1327985227 0.6196524501 219 8.7200000000 0.0041695358 0.0030811885 0.0046323356 0.0049805303 0.7613460000 953391145 0 1782820864 0.9635511041 0.1338469088 0.6299847960 220 8.7600000000 0.0041735275 0.0030861536 0.0046323356 0.0049709332 0.7554990000 953392419 0 1784438784 0.9602277875 0.1341596097 0.6395586729 221 8.8000000000 0.0041711535 0.0030910631 0.0046323356 0.0049600987 0.7625010000 953393693 0 1783054336 0.9605746865 0.1364879012 0.6516400576 222 8.8400000000 0.0041658040 0.0030959043 0.0046323356 0.0049510283 0.7625920000 953394967 0 1781686272 0.9589748979 0.1371781826 0.6623822451 223 8.8800000000 0.0045761368 0.0031025421 0.0046323356 0.0049400227 0.7831900000 953396241 0 1783455744 0.9566540718 0.1372150481 0.6717541814 224 8.9200000000 0.0041677807 0.0031072977 0.0046323356 0.0049296480 0.7690070000 953397515 0 1782026240 0.9545631409 0.1377409250 0.6823642254 225 8.9600000000 0.0043827663 0.0031129664 0.0046323356 0.0049224534 0.7563900000 953398789 0 1783717888 0.9545652270 0.1393861026 0.6935692430 226 9.0000000000 0.0041554994 0.0031175794 0.0046323356 0.0049119429 0.7804260000 953400063 0 1782321152 0.9553512335 0.1416703910 0.7155795693 227 9.0400000000 0.0044101616 0.0031232736 0.0046323356 0.0049010715 0.7620510000 953401337 0 1783955456 0.9558473825 0.1438578963 0.7261607051 228 9.0800000000 0.0044519706 0.0031291012 0.0046323356 0.0048919219 0.7654670000 953402611 0 1782669312 0.9534508586 0.1454288214 0.7351964116 229 9.1200000000 0.0044144895 0.0031347142 0.0046323356 0.0049034619 0.7671070000 953403885 0 1784320000 0.9536594152 0.1471776515 0.7463606000 230 9.1600000000 0.0043496066 0.0031399964 0.0046323356 0.0049004691 0.7642710000 953405159 0 1782956032 0.9542887211 0.1485448480 0.7566017509 231 9.2000000000 0.0041636182 0.0031444277 0.0046323356 0.0048959557 0.7841790000 953406433 0 1784590336 0.9534225464 0.1498372108 0.7753664255 232 9.2400000000 0.0043441164 0.0031495987 0.0046323356 0.0048887472 0.7910060000 953407707 0 1783209984 0.9542768002 0.1523498446 0.7872368097 233 9.2800000000 0.0043029925 0.0031545489 0.0046323356 0.0048897594 0.7775510000 953408981 0 1781780480 0.9549927115 0.1549083292 0.7993047833 234 9.3200000000 0.0042831441 0.0031593720 0.0046323356 0.0048888174 0.7793920000 953410255 0 1783431168 0.9540384412 0.1575793773 0.8100912571 235 9.3600000000 0.0042344630 0.0031639468 0.0046323356 0.0048869716 0.7882160000 953411529 0 1782185984 0.9538775682 0.1588166654 0.8209279776 236 9.4000000000 0.0042026569 0.0031683481 0.0046323356 0.0048818137 0.7869400000 953412803 0 1783820288 0.9553072453 0.1595621109 0.8304806352 237 9.4400000000 0.0042793136 0.0031730358 0.0046323356 0.0048893776 0.8293710000 953414077 0 1782439936 0.9561697245 0.1621260345 0.8414703012 238 9.4800000000 0.0042971252 0.0031777588 0.0046323356 0.0048875291 0.7950240000 953415351 0 1784057856 0.9569498301 0.1637762785 0.8522577286 239 9.5200000000 0.0042525604 0.0031822559 0.0046323356 0.0048938522 0.7925360000 953416625 0 1782661120 0.9587486982 0.1659607142 0.8630276322 240 9.5600000000 0.0043145586 0.0031869738 0.0046323356 0.0048915051 0.7842030000 953417899 0 1784344576 0.9585274458 0.1668558866 0.8725352287 241 9.6000000000 0.0042855092 0.0031915321 0.0046323356 0.0048813712 0.7837120000 953419173 0 1783074816 0.9567821026 0.1683061421 0.8822680712 242 9.6400000000 0.0041230246 0.0031953812 0.0046323356 0.0048838556 0.7975570000 953420447 0 1781555200 0.9577871561 0.1708337814 0.8945516944 243 9.6800000000 0.0042056865 0.0031995388 0.0046323356 0.0048746628 0.7766050000 953421721 0 1783169024 0.9609078765 0.1731607616 0.9081048369 244 9.7200000000 0.0042006159 0.0032036416 0.0046323356 0.0048646262 0.7783250000 953422995 0 1781661696 0.9622589946 0.1769119352 0.9201523662 245 9.7600000000 0.0041791201 0.0032076232 0.0046323356 0.0048567992 0.7651480000 953424269 0 1783328768 0.9621579051 0.1777396798 0.9298114777 246 9.8000000000 0.0041535157 0.0032114683 0.0046323356 0.0048468872 0.7633020000 953425543 0 1781944320 0.9638180137 0.1804433316 0.9415014386 247 9.8400000000 0.0041922452 0.0032154390 0.0046323356 0.0048372353 0.7603720000 953426817 0 1783566336 0.9640433788 0.1831398606 0.9531691670 248 9.8800000000 0.0041096173 0.0032190446 0.0046323356 0.0048316550 0.7590110000 953428091 0 1782153216 0.9638770223 0.1862645745 0.9632847309 249 9.9200000000 0.0041315169 0.0032227091 0.0046323356 0.0048219488 0.7525530000 953429365 0 1783820288 0.9653109908 0.1874279231 0.9740324616 250 9.9600000000 0.0041382401 0.0032263712 0.0046323356 0.0048127121 0.7520700000 953430639 0 1782435840 0.9658607841 0.1893048882 0.9848653674 251 10.0000000000 0.0041000959 0.0032298522 0.0046323356 0.0048047664 0.7885880000 953431913 0 1784201216 0.9653472304 0.1901118606 0.9940472245 252 10.0400000000 0.0040055276 0.0032329303 0.0046323356 0.0047952155 0.7483330000 953433187 0 1782788096 0.9657695293 0.1917085648 1.0036535263 253 10.0800000000 0.0039886977 0.0032359175 0.0046323356 0.0047863743 0.7416100000 953434461 0 1784455168 0.9659585953 0.1934967041 1.0130661726 254 10.1200000000 0.0039430051 0.0032387013 0.0046323356 0.0047809503 0.7424080000 953435735 0 1783087104 0.9662401676 0.1954737008 1.0223896503 255 10.1600000000 0.0039294320 0.0032414101 0.0046323356 0.0047718803 0.7365550000 953437009 0 1781555200 0.9655497670 0.1972357035 1.0315577984 256 10.2000000000 0.0040071146 0.0032444011 0.0046323356 0.0047716270 0.7114640000 953438283 0 1783296000 0.9646547437 0.1978616267 1.0389416218 257 10.2400000000 0.0038300722 0.0032466800 0.0046323356 0.0047846760 0.7289040000 953439557 0 1782198272 0.9635252357 0.1996954232 1.0480191708 258 10.2800000000 0.0037988729 0.0032488203 0.0046323356 0.0047860511 0.7555130000 953482815 0 1783963648 0.9637354016 0.2015111297 1.0576351881 259 10.3200000000 0.0040880535 0.0032520605 0.0046323356 0.0047936553 0.6983340000 953484089 0 1782562816 0.9633771181 0.2024936080 1.0652672052 260 10.3600000000 0.0042026690 0.0032557167 0.0046323356 0.0048004258 0.6939380000 953485363 0 1784311808 0.9613195062 0.2032742351 1.0727161169 261 10.4000000000 0.0037798854 0.0032577250 0.0046323356 0.0047927887 0.7276250000 953486637 0 1782947840 0.9593762159 0.2059694082 1.0828554630 262 10.4400000000 0.0037865692 0.0032597435 0.0046323356 0.0047836396 0.6973230000 953487911 0 1784582144 0.9602664709 0.2073080540 1.0919959545 263 10.4800000000 0.0038289037 0.0032619076 0.0046323356 0.0047745315 0.6953370000 953489185 0 1783169024 0.9597895145 0.2089811862 1.1015859842 264 10.5200000000 0.0039633587 0.0032645647 0.0046323356 0.0047680059 0.6678140000 953490459 0 1781813248 0.9581999183 0.2096219659 1.1093324423 265 10.5600000000 0.0038471362 0.0032667630 0.0046323356 0.0047605868 0.7018790000 953491733 0 1783439360 0.9567483664 0.2098181248 1.1168682575 266 10.6000000000 0.0037661556 0.0032686404 0.0046323356 0.0047520970 0.6793250000 953493007 0 1781911552 0.9573736787 0.2108792514 1.1256439686 267 10.6400000000 0.0038033337 0.0032706430 0.0046323356 0.0047450942 0.6765200000 953494281 0 1783582720 0.9565913081 0.2122360468 1.1342672110 268 10.6800000000 0.0038115962 0.0032726615 0.0046323356 0.0047388895 0.6749010000 953495555 0 1782308864 0.9554523826 0.2143484503 1.1436505318 269 10.7200000000 0.0038128279 0.0032746696 0.0046323356 0.0047349490 0.6715150000 953496829 0 1783947264 0.9537346959 0.2151258439 1.1528538465 270 10.7600000000 0.0038088846 0.0032766482 0.0046323356 0.0047288714 0.6649160000 953498103 0 1782534144 0.9516978264 0.2175206542 1.1619669199 271 10.8000000000 0.0038392991 0.0032787244 0.0046323356 0.0047217577 0.6673870000 953499377 0 1784336384 0.9496108294 0.2194709778 1.1719083786 272 10.8400000000 0.0038500070 0.0032808247 0.0046323356 0.0047130383 0.6696360000 953500651 0 1783111680 0.9468075633 0.2213403881 1.1811470985 273 10.8800000000 0.0051128226 0.0032875353 0.0051128226 0.0047068190 0.6411130000 953501925 0 1781653504 0.9439331293 0.2226283401 1.1893192530 274 10.9200000000 0.0036556555 0.0032888788 0.0051128226 0.0046988871 0.6769660000 953503199 0 1783341056 0.9413179755 0.2238034904 1.2006108761 275 10.9600000000 0.0038563283 0.0032909422 0.0051128226 0.0046930344 0.6560990000 953504473 0 1782312960 0.9389159083 0.2275335044 1.2101039886 276 11.0000000000 0.0053273425 0.0032983205 0.0053273425 0.0046900413 0.6324710000 953505747 0 1783955456 0.9363127351 0.2277802378 1.2171154022 277 11.0400000000 0.0036734056 0.0032996746 0.0053273425 0.0046834831 0.6697990000 953507021 0 1782702080 0.9347536564 0.2288962156 1.2293009758 278 11.0800000000 0.0036871387 0.0033010683 0.0053273425 0.0046750221 0.6677810000 953508295 0 1784475648 0.9296788573 0.2300003320 1.2382402420 279 11.1200000000 0.0056244121 0.0033093957 0.0056244121 0.0046677777 0.6344570000 953509569 0 1783312384 0.9263816476 0.2312966138 1.2464034557 280 11.1600000000 0.0036861759 0.0033107414 0.0056244121 0.0046620523 0.6664760000 953510843 0 1782194176 0.9224503636 0.2325794846 1.2582776546 281 11.2000000000 0.0036996081 0.0033121253 0.0056244121 0.0046539672 0.6942800000 953512117 0 1783967744 0.9203686118 0.2363519818 1.2677236795 282 11.2400000000 0.0037062794 0.0033135230 0.0056244121 0.0046463642 0.6643450000 953513391 0 1782788096 0.9169334769 0.2374175489 1.2764177322 283 11.2800000000 0.0036862025 0.0033148399 0.0056244121 0.0046390103 0.6611070000 953514665 0 1784471552 0.9137579203 0.2405633628 1.2859849930 284 11.3200000000 0.0037064825 0.0033162189 0.0056244121 0.0046317673 0.6595550000 953515939 0 1783324672 0.9087917209 0.2432233244 1.2969770432 285 11.3600000000 0.0055457805 0.0033240419 0.0056244121 0.0046277141 0.6200120000 953517213 0 1782153216 0.9054051042 0.2450504601 1.3048373461 286 11.4000000000 0.0036730904 0.0033252624 0.0056244121 0.0046275899 0.6547360000 953518487 0 1783967744 0.9052631259 0.2472818047 1.3163714409 287 11.4400000000 0.0037004170 0.0033265695 0.0056244121 0.0046203577 0.6582000000 953519761 0 1782796288 0.9027736187 0.2506976724 1.3253601789 288 11.4800000000 0.0037037651 0.0033278792 0.0056244121 0.0046124409 0.6533300000 953521035 0 1784565760 0.8957124352 0.2516560853 1.3320978880 289 11.5200000000 0.0056048376 0.0033357580 0.0056244121 0.0046101898 0.6131370000 953522309 0 1783328768 0.8914411664 0.2516568601 1.3384237289 290 11.5600000000 0.0037044820 0.0033370294 0.0056244121 0.0046080262 0.6524460000 953523583 0 1781960704 0.8872438669 0.2511873543 1.3482183218 291 11.6000000000 0.0038383075 0.0033387520 0.0056244121 0.0046003160 0.6309290000 953524857 0 1783566336 0.8849470019 0.2537658513 1.3565198183 292 11.6400000000 0.0052123023 0.0033451683 0.0056244121 0.0045934454 0.6104490000 953526131 0 1782185984 0.8828841448 0.2552721500 1.3635109663 293 11.6800000000 0.0049792798 0.0033507455 0.0056244121 0.0045859237 0.6047850000 953527405 0 1783676928 0.8811625242 0.2570083439 1.3700915575 294 11.7200000000 0.0055051954 0.0033580735 0.0056244121 0.0045826199 0.6054110000 953528679 0 1782312960 0.8773712516 0.2568371296 1.3764472008 295 11.7600000000 0.0038671142 0.0033597991 0.0056244121 0.0045894031 0.6313040000 953529953 0 1783947264 0.8748794794 0.2564437985 1.3850317001 296 11.8000000000 0.0045554345 0.0033638384 0.0056244121 0.0046027508 0.6080360000 953531227 0 1782534144 0.8729657531 0.2572765350 1.3923299313 297 11.8400000000 0.0048593050 0.0033688736 0.0056244121 0.0046293990 0.6377660000 953532501 0 1784217600 0.8688964844 0.2573608756 1.3994581699 298 11.8800000000 0.0036901210 0.0033699517 0.0056244121 0.0046472556 0.6239190000 953533775 0 1782947840 0.8650948405 0.2563530803 1.4088979959 299 11.9200000000 0.0035418561 0.0033705266 0.0056244121 0.0046461384 0.6212180000 953535049 0 1784582144 0.8631490469 0.2559112012 1.4170778990 300 11.9600000000 0.0034744553 0.0033708730 0.0056244121 0.0046449365 0.6200070000 953536323 0 1783218176 0.8613690734 0.2552585304 1.4247319698 301 12.0000000000 0.0034800991 0.0033712359 0.0056244121 0.0046405311 0.6201800000 953537597 0 1781772288 0.8604826927 0.2559445500 1.4343104362 302 12.0400000000 0.0034460030 0.0033714835 0.0056244121 0.0046339264 0.6172380000 953538871 0 1783439360 0.8598105311 0.2562736273 1.4429631233 303 12.0800000000 0.0034082446 0.0033716048 0.0056244121 0.0046279851 0.6296310000 953540145 0 1782091776 0.8577573895 0.2555595934 1.4505230188 304 12.1200000000 0.0033665618 0.0033715882 0.0056244121 0.0046221676 0.6136740000 953541419 0 1783803904 0.8566477299 0.2563851774 1.4601241350 305 12.1600000000 0.0034045528 0.0033716963 0.0056244121 0.0046147122 0.6427280000 953542693 0 1782456320 0.8556873202 0.2574178576 1.4697657824 306 12.2000000000 0.0033343371 0.0033715742 0.0056244121 0.0046072557 0.6082450000 953543967 0 1784074240 0.8529742956 0.2583877742 1.4786444902 307 12.2400000000 0.0032366219 0.0033711346 0.0056244121 0.0046013277 0.6066220000 953545241 0 1782788096 0.8508971930 0.2601538002 1.4882501364 308 12.2800000000 0.0032131094 0.0033706215 0.0056244121 0.0046000481 0.6004820000 953546515 0 1784455168 0.8498418331 0.2609167397 1.4979952574 309 12.3200000000 0.0031645221 0.0033699546 0.0056244121 0.0045983394 0.5992460000 953547789 0 1782931456 0.8484064341 0.2615479529 1.5071263313 310 12.3600000000 0.0031589535 0.0033692739 0.0056244121 0.0046068337 0.5954720000 953549063 0 1781702656 0.8473700881 0.2641708851 1.5171266794 311 12.4000000000 0.0032220604 0.0033688005 0.0056244121 0.0046253251 0.5931310000 953550337 0 1783328768 0.8461561799 0.2664710581 1.5273407698 312 12.4400000000 0.0029565697 0.0033674793 0.0056244121 0.0046353925 0.6067970000 953551611 0 1781899264 0.8450868726 0.2650310099 1.5350995064 313 12.4800000000 0.0029879836 0.0033662669 0.0056244121 0.0046356941 0.5821180000 953552885 0 1783693312 0.8440302014 0.2662118673 1.5447008610 314 12.5200000000 0.0029668945 0.0033649950 0.0056244121 0.0046337714 0.6124050000 953554159 0 1782288384 0.8424375653 0.2673671842 1.5539212227 315 12.5600000000 0.0028066458 0.0033632224 0.0056244121 0.0046299444 0.5788160000 953555433 0 1784094720 0.8411161900 0.2682016492 1.5621124506 316 12.6000000000 0.0027217192 0.0033611924 0.0056244121 0.0046226772 0.5777630000 953556707 0 1782706176 0.8419792652 0.2676469088 1.5701203346 317 12.6400000000 0.0027247788 0.0033591847 0.0056244121 0.0046158317 0.5762260000 953557981 0 1784311808 0.8413600326 0.2688596845 1.5790840387 318 12.6800000000 0.0027649151 0.0033573160 0.0056244121 0.0046110024 0.5733400000 953559255 0 1783197696 0.8410813212 0.2705129981 1.5880566835 319 12.7200000000 0.0025689630 0.0033548446 0.0056244121 0.0046056610 0.6008830000 953560529 0 1781653504 0.8384248018 0.2731176615 1.5985678434 320 12.7600000000 0.0027401554 0.0033529237 0.0056244121 0.0046038655 0.5727660000 953561803 0 1783336960 0.8361630440 0.2744389176 1.6075156927 321 12.8000000000 0.0026945106 0.0033508726 0.0056244121 0.0046146880 0.5702240000 953563077 0 1782185984 0.8342586160 0.2764826417 1.6168406010 322 12.8400000000 0.0026100886 0.0033485720 0.0056244121 0.0046207641 0.5670920000 953564351 0 1784098816 0.8330605030 0.2787071466 1.6258490086 323 12.8800000000 0.0025679085 0.0033461551 0.0056244121 0.0046342591 0.6000860000 953565625 0 1782824960 0.8318796754 0.2801394761 1.6337977648 324 12.9200000000 0.0025107036 0.0033435766 0.0056244121 0.0046477838 0.5818420000 953566899 0 1784463360 0.8307236433 0.2802312672 1.6407585144 325 12.9600000000 0.0024700833 0.0033408889 0.0056244121 0.0046594598 0.5619530000 953568173 0 1783369728 0.8304203749 0.2806662917 1.6479548216 326 13.0000000000 0.0024840210 0.0033382605 0.0056244121 0.0046703618 0.5604500000 953569447 0 1781968896 0.8293838501 0.2813612819 1.6561111212 327 13.0400000000 0.0024791784 0.0033356333 0.0056244121 0.0047741886 0.5754990000 953570721 0 1783738368 0.8257789016 0.2859212756 1.6756497622 328 13.0800000000 0.0024731404 0.0033330038 0.0056244121 0.0047943918 0.5791350000 953571995 0 1782439936 0.8239515424 0.2865539789 1.6835149527 329 13.1200000000 0.0024644511 0.0033303638 0.0056244121 0.0047990185 0.5697540000 953573269 0 1784193024 0.8217438459 0.2875210643 1.6914532185 330 13.1600000000 0.0024697713 0.0033277559 0.0056244121 0.0047986577 0.5683240000 953574543 0 1782939648 0.8204863667 0.2878124714 1.6987094879 331 13.2000000000 0.0024706321 0.0033251664 0.0056244121 0.0047991430 0.5661540000 953575817 0 1784692736 0.8197026253 0.2877473831 1.7054512501 332 13.2400000000 0.0024477122 0.0033225235 0.0056244121 0.0047951243 0.5673230000 953577091 0 1783345152 0.8185871840 0.2891744673 1.7131334543 333 13.2800000000 0.0023959854 0.0033197411 0.0056244121 0.0047916415 0.5675710000 953578365 0 1781960704 0.8175502419 0.2906250358 1.7206395864 334 13.3200000000 0.0023745112 0.0033169111 0.0056244121 0.0047916568 0.5647260000 953579639 0 1783566336 0.8169620633 0.2907540202 1.7266939878 335 13.3600000000 0.0023711782 0.0033140880 0.0056244121 0.0047994042 0.5684520000 953580913 0 1782181888 0.8147847652 0.2935825586 1.7354131937 336 13.4000000000 0.0023800372 0.0033113081 0.0056244121 0.0048086352 0.5795630000 953582187 0 1783803904 0.8124914765 0.2944510877 1.7415733337 337 13.4400000000 0.0023872135 0.0033085659 0.0056244121 0.0048262625 0.5839550000 953583461 0 1782435840 0.8109444976 0.2937100828 1.7466858625 338 13.4800000000 0.0023945800 0.0033058618 0.0056244121 0.0048530010 0.5886900000 953584735 0 1784074240 0.8075014949 0.2937654555 1.7521280050 339 13.5200000000 0.0024129841 0.0033032280 0.0056244121 0.0048744982 0.5922390000 953586009 0 1782820864 0.8056171536 0.2954072952 1.7597197294 340 13.5600000000 0.0024048521 0.0033005857 0.0056244121 0.0048944986 0.5968510000 953587283 0 1784455168 0.8011192083 0.2955909371 1.7654211521 341 13.6000000000 0.0024045657 0.0032979581 0.0056244121 0.0049075494 0.6347610000 953588557 0 1783042048 0.7974258661 0.2966254950 1.7726908922 342 13.6400000000 0.0024130689 0.0032953707 0.0056244121 0.0049155901 0.5943750000 953589831 0 1781702656 0.7937882543 0.2988263071 1.7808042765 343 13.6800000000 0.0024121946 0.0032927958 0.0056244121 0.0049282677 0.5948870000 953591105 0 1783312384 0.7894722223 0.3022278845 1.7892346382 344 13.7200000000 0.0024183602 0.0032902539 0.0056244121 0.0049316183 0.5989180000 953592379 0 1781944320 0.7855024934 0.3041652441 1.7950855494 345 13.7600000000 0.0024020800 0.0032876794 0.0056244121 0.0049326170 0.5884950000 953593653 0 1783582720 0.7838636637 0.3031876683 1.7997517586 346 13.8000000000 0.0011791164 0.0032815853 0.0056244121 0.0049321226 0.5468270000 953594927 0 1782280192 0.7795774937 0.3034460247 1.8037008047 347 13.8400000000 0.0023833872 0.0032789969 0.0056244121 0.0049418023 0.5825670000 953596201 0 1783820288 0.7773927450 0.3028752208 1.8094658852 348 13.8800000000 0.0023715887 0.0032763894 0.0056244121 0.0049543524 0.5833150000 953597475 0 1782439936 0.7727854848 0.3033353686 1.8161336184 349 13.9200000000 0.0023743361 0.0032738047 0.0056244121 0.0049636183 0.5822340000 953598749 0 1783947264 0.7666068673 0.3037765026 1.8234994411 350 13.9600000000 0.0023424823 0.0032711438 0.0056244121 0.0049729320 0.6049020000 953600023 0 1782546432 0.7606734633 0.3049981892 1.8311290741 351 14.0000000000 0.0023398441 0.0032684905 0.0056244121 0.0049758941 0.5832750000 953601297 0 1784184832 0.7552377582 0.3065988421 1.8376028538 352 14.0400000000 0.0014895962 0.0032634368 0.0056244121 0.0049710947 0.5449320000 953602571 0 1782820864 0.7481429577 0.3064350784 1.8412897587 353 14.0800000000 0.0022799203 0.0032606507 0.0056244121 0.0049745490 0.5858330000 953603845 0 1784311808 0.7452916503 0.3051679134 1.8467564583 354 14.1200000000 0.0022650049 0.0032578381 0.0056244121 0.0049757964 0.5854530000 953605119 0 1782964224 0.7392570972 0.3074359894 1.8558455706 355 14.1600000000 0.0010927181 0.0032517392 0.0056244121 0.0049736810 0.5430190000 953606393 0 1784582144 0.7318734527 0.3081526458 1.8607548475 356 14.2000000000 0.0022693917 0.0032489798 0.0056244121 0.0049981300 0.5820290000 953607667 0 1783169024 0.7271270156 0.3083057702 1.8653805256 357 14.2400000000 0.0014310251 0.0032438875 0.0056244121 0.0049970184 0.5456650000 953608941 0 1781702656 0.7189392447 0.3090011775 1.8715502024 358 14.2800000000 0.0022745109 0.0032411797 0.0056244121 0.0050080183 0.5835460000 953610215 0 1783169024 0.7141361237 0.3097670376 1.8773126602 359 14.3200000000 0.0022811289 0.0032385055 0.0056244121 0.0050016816 0.5839510000 953611489 0 1781833728 0.7051672339 0.3133470118 1.8848841190 360 14.3600000000 0.0022677290 0.0032358089 0.0056244121 0.0050022121 0.5939540000 953612763 0 1783312384 0.6892129183 0.3165167868 1.8968014717 361 14.4000000000 0.0022789405 0.0032331583 0.0056244121 0.0049965278 0.6033820000 953614037 0 1781817344 0.6792948246 0.3214451671 1.9054576159 362 14.4400000000 0.0023004271 0.0032305816 0.0056244121 0.0049917984 0.6050620000 953615311 0 1783312384 0.6624026895 0.3207790554 1.9117270708 363 14.4800000000 0.0020393436 0.0032273000 0.0056244121 0.0049863774 0.5495480000 953616585 0 1781899264 0.6564071178 0.3194881082 1.9156507254 364 14.5200000000 0.0028281934 0.0032262036 0.0056244121 0.0049874608 0.5493140000 953617859 0 1783455744 0.6498210430 0.3190540671 1.9218189716 365 14.5600000000 0.0031581137 0.0032260170 0.0056244121 0.0049809047 0.5543210000 953619133 0 1782042624 0.6418300867 0.3191134930 1.9270298481 366 14.6000000000 0.0023022466 0.0032234930 0.0056244121 0.0049972952 0.6130580000 953620407 0 1783709696 0.6241073608 0.3265179992 1.9414699078 367 14.6400000000 0.0026194684 0.0032218472 0.0056244121 0.0049923548 0.5539460000 953621681 0 1782439936 0.6148015261 0.3303155005 1.9466172457 368 14.6800000000 0.0020867272 0.0032187626 0.0056244121 0.0049994339 0.5793650000 953622955 0 1784057856 0.6051327586 0.3311126828 1.9505792856 369 14.7200000000 0.0025088370 0.0032168387 0.0056244121 0.0050077191 0.5538640000 953624229 0 1782693888 0.5958089828 0.3304507434 1.9519981146 370 14.7600000000 0.0023491380 0.0032144936 0.0056244121 0.0050009446 0.5582630000 953625503 0 1784311808 0.5878688693 0.3288449049 1.9535059929 371 14.8000000000 0.0023469508 0.0032121552 0.0056244121 0.0050166485 0.5550080000 953626777 0 1783074816 0.5795597434 0.3289515376 1.9601622820 372 14.8400000000 0.0027319179 0.0032108642 0.0056244121 0.0050316757 0.5558740000 953628051 0 1781534720 0.5711340308 0.3308464289 1.9653837681 373 14.8800000000 0.0030345179 0.0032103914 0.0056244121 0.0050338111 0.5521500000 953629325 0 1783201792 0.5615237355 0.3322770894 1.9700726271 374 14.9200000000 0.0030867490 0.0032100609 0.0056244121 0.0050302990 0.5481170000 953630599 0 1781833728 0.5503029823 0.3332978487 1.9734090567 375 14.9600000000 0.0026831501 0.0032086558 0.0056244121 0.0050395886 0.5417420000 953631873 0 1783439360 0.5393854380 0.3333927989 1.9746131897 376 15.0000000000 0.0025979243 0.0032070315 0.0056244121 0.0050330085 0.5444820000 953633147 0 1782091776 0.5301991701 0.3327733576 1.9797849655 377 15.0400000000 0.0031372458 0.0032068464 0.0056244121 0.0050271940 0.5667990000 953634421 0 1783676928 0.5098153353 0.3332688510 1.9867978096 378 15.0800000000 0.0027729797 0.0032056986 0.0056244121 0.0050215109 0.5392670000 953635695 0 1782439936 0.5003649592 0.3340835571 1.9905556440 379 15.1200000000 0.0024872888 0.0032038030 0.0056244121 0.0050153658 0.5438150000 953636969 0 1783955456 0.4924887717 0.3338827193 1.9934489727 380 15.1600000000 0.0023771215 0.0032016276 0.0056244121 0.0050121742 0.5379320000 953638243 0 1782554624 0.4848594666 0.3327419162 1.9971354008 381 15.2000000000 0.0023591369 0.0031994163 0.0056244121 0.0050240538 0.5589940000 953639517 0 1784209408 0.4766749144 0.3341189325 2.0033311844 382 15.2400000000 0.0022581976 0.0031969524 0.0056244121 0.0050345359 0.5378770000 953640791 0 1782464512 0.4660268128 0.3342078924 2.0043480396 383 15.2800000000 0.0022274703 0.0031944211 0.0056244121 0.0050471536 0.5348540000 953642065 0 1784078336 0.4574397504 0.3339965343 2.0065612793 384 15.3200000000 0.0022937630 0.0031920756 0.0056244121 0.0050568241 0.5834940000 953643339 0 1782669312 0.4491578937 0.3347929120 2.0122425556 385 15.3600000000 0.0022833161 0.0031897152 0.0056244121 0.0050600917 0.5320360000 953644613 0 1784209408 0.4408042729 0.3353827298 2.0145814419 386 15.4000000000 0.0022741102 0.0031873432 0.0056244121 0.0050566486 0.6036840000 953645887 0 1782669312 0.4338489473 0.3349974453 2.0181121826 387 15.4400000000 0.0023174968 0.0031850955 0.0056244121 0.0050618783 0.5357720000 953647161 0 1784225792 0.4273294210 0.3359730840 2.0213716030 388 15.4800000000 0.0022742213 0.0031827479 0.0056244121 0.0050667313 0.5809070000 953648435 0 1782808576 0.4210358858 0.3364921510 2.0256807804 389 15.5200000000 0.0023405566 0.0031805829 0.0056244121 0.0050689765 0.5364140000 953649709 0 1784463360 0.4131830931 0.3376873732 2.0291645527 390 15.5600000000 0.0022845971 0.0031782855 0.0056244121 0.0050803189 0.5764670000 953650983 0 1783062528 0.4051030874 0.3380152285 2.0328156948 391 15.6000000000 0.0022852896 0.0031760016 0.0056244121 0.0050776994 0.5744130000 953652257 0 1781653504 0.3983471990 0.3383392394 2.0362312794 392 15.6400000000 0.0022909667 0.0031737439 0.0056244121 0.0050841356 0.5745370000 953653531 0 1783312384 0.3915981352 0.3390569687 2.0411183834 393 15.6800000000 0.0024110160 0.0031718031 0.0056244121 0.0050801245 0.5338250000 953654805 0 1781899264 0.3845791817 0.3392015994 2.0434000492 394 15.7200000000 0.0023306215 0.0031696681 0.0056244121 0.0050776600 0.5694560000 953656079 0 1783566336 0.3782735765 0.3389874697 2.0473427773 395 15.7600000000 0.0023448737 0.0031675800 0.0056244121 0.0050776673 0.6072610000 953657353 0 1782185984 0.3717418909 0.3396854401 2.0535097122 396 15.8000000000 0.0023730239 0.0031655736 0.0056244121 0.0050750479 0.5820720000 953658627 0 1783820288 0.3645868003 0.3413668871 2.0586371422 397 15.8400000000 0.0025749935 0.0031640859 0.0056244121 0.0050743320 0.5382660000 953659901 0 1782439936 0.3581312597 0.3412980139 2.0606379509 398 15.8800000000 0.0024257246 0.0031622308 0.0056244121 0.0050697526 0.5786320000 953661175 0 1784057856 0.3532971144 0.3411661685 2.0683999062 399 15.9200000000 0.0025267825 0.0031606382 0.0056244121 0.0050730714 0.5443860000 953662449 0 1782710272 0.3451363742 0.3431541622 2.0715422630 400 15.9600000000 0.0025000277 0.0031589866 0.0056244121 0.0050702130 0.5789940000 953663723 0 1784311808 0.3400962353 0.3416216075 2.0753812790 401 16.0000000000 0.0025246134 0.0031574047 0.0056244121 0.0050669493 0.5416270000 953664997 0 1782951936 0.3341110647 0.3409715891 2.0790400505 402 16.0400000000 0.0025919646 0.0031559981 0.0056244121 0.0050694752 0.5840950000 953666271 0 1781575680 0.3285260499 0.3412999213 2.0865211487 403 16.0800000000 0.0026500842 0.0031547427 0.0056244121 0.0050657863 0.5711540000 953667545 0 1783185408 0.3224121034 0.3419376612 2.0925874710 404 16.1200000000 0.0027073708 0.0031536354 0.0056244121 0.0050613608 0.5815130000 953668819 0 1781833728 0.3152891099 0.3419556916 2.0965692997 405 16.1600000000 0.0027555872 0.0031526525 0.0056244121 0.0050573721 0.5880670000 953670093 0 1783549952 0.3101564944 0.3407952785 2.1011681557 406 16.2000000000 0.0028225232 0.0031518394 0.0056244121 0.0050668189 0.5866300000 953671367 0 1782308864 0.3039731383 0.3418080211 2.1096730232 407 16.2400000000 0.0028943296 0.0031512067 0.0056244121 0.0050696300 0.5764980000 953672641 0 1783947264 0.2964811325 0.3438983858 2.1151037216 408 16.2800000000 0.0029519633 0.0031507184 0.0056244121 0.0050737076 0.5867770000 953673915 0 1782702080 0.2911257446 0.3443894982 2.1197187901 409 16.3200000000 0.0028646293 0.0031500189 0.0056244121 0.0050797098 0.5894730000 953675189 0 1784344576 0.2840375006 0.3454047740 2.1265614033 410 16.3600000000 0.0027482316 0.0031490389 0.0056244121 0.0050781370 0.5817850000 953676463 0 1783185408 0.2786108255 0.3459525108 2.1305003166 411 16.3999999990 0.0023978546 0.0031472112 0.0056244121 0.0050750961 0.5704410000 953677737 0 1782067200 0.2722017765 0.3462208509 2.1337676048 412 16.4400000000 0.0020271521 0.0031444926 0.0056244121 0.0050732061 0.5776560000 953679011 0 1783709696 0.2659957111 0.3461823761 2.1390972137 413 16.4800000000 0.0018496508 0.0031413574 0.0056244121 0.0050834801 0.6027870000 953680285 0 1782702080 0.2595785856 0.3475378454 2.1462688446 414 16.5200000000 0.0017977485 0.0031381120 0.0056244121 0.0050904853 0.5952030000 953681559 0 1784455168 0.2529333830 0.3491511643 2.1516015530 415 16.5599999990 0.0019214924 0.0031351804 0.0056244121 0.0051052464 0.5886910000 953682833 0 1783296000 0.2465885878 0.3514726758 2.1582801342 416 16.6000000000 0.0022247075 0.0031329917 0.0056244121 0.0051073353 0.5856270000 953684107 0 1782194176 0.2412063926 0.3527561426 2.1622571945 417 16.6400000000 0.0019486228 0.0031301515 0.0056244121 0.0051114106 0.5645310000 953685381 0 1783803904 0.2358445227 0.3533724248 2.1660225391 418 16.6800000000 0.0024999857 0.0031286439 0.0056244121 0.0051250591 0.6103890000 953686655 0 1782677504 0.2252369523 0.3551130295 2.1751046181 419 16.7199999990 0.0024750782 0.0031270841 0.0056244121 0.0051317927 0.5922850000 953687929 0 1784471552 0.2190471441 0.3567810059 2.1814999580 420 16.7600000000 0.0020111138 0.0031244270 0.0056244121 0.0051401895 0.5928550000 953689203 0 1783169024 0.2125721276 0.3587133884 2.1873676777 421 16.8000000000 0.0014490355 0.0031204475 0.0056244121 0.0051466570 0.5930950000 953690477 0 1782341632 0.2064106315 0.3595042527 2.1924715042 422 16.8400000000 0.0013804429 0.0031163243 0.0056244121 0.0051551133 0.6311690000 953691751 0 1783836672 0.2006260753 0.3596653640 2.1972095966 423 16.8799999990 0.0015087592 0.0031125239 0.0056244121 0.0051700731 0.5969050000 953693025 0 1782558720 0.1955590844 0.3595135510 2.2024416924 424 16.9200000000 0.0016154990 0.0031089932 0.0056244121 0.0052515891 0.6005540000 953694299 0 1784238080 0.1835619360 0.3612700403 2.2120900154 425 16.9600000000 0.0018262230 0.0031059749 0.0056244121 0.0052593545 0.6079290000 953695573 0 1782931456 0.1787140816 0.3619824052 2.2156205177 426 17.0000000000 0.0018325611 0.0031029856 0.0056244121 0.0052797449 0.6002550000 953696847 0 1781800960 0.1731277704 0.3635091782 2.2206456661 427 17.0400000000 0.0018312318 0.0031000073 0.0056244121 0.0052905367 0.5999860000 953698121 0 1783582720 0.1676618308 0.3652193248 2.2250792980 428 17.0800000000 0.0018619678 0.0030971147 0.0056244121 0.0052994442 0.6010270000 953699395 0 1782177792 0.1626957655 0.3672154844 2.2289865017 429 17.1200000000 0.0018577063 0.0030942256 0.0056244121 0.0053043596 0.5982100000 953700669 0 1783820288 0.1576667130 0.3675180376 2.2311968803 430 17.1600000000 0.0019124409 0.0030914773 0.0056244121 0.0053084883 0.6043180000 953701943 0 1782407168 0.1528023779 0.3678471148 2.2346138954 431 17.2000000000 0.0019398844 0.0030888054 0.0056244121 0.0053126165 0.5996490000 953703217 0 1784221696 0.1481654048 0.3674533963 2.2382850647 432 17.2400000000 0.0019581886 0.0030861882 0.0056244121 0.0053132907 0.6060350000 953704491 0 1782685696 0.1428873241 0.3680277765 2.2427687645 433 17.2800000000 0.0019523728 0.0030835697 0.0056244121 0.0053135740 0.6041550000 953705765 0 1784438784 0.1390778124 0.3694496155 2.2465057373 434 17.3200000000 0.0019564538 0.0030809726 0.0056244121 0.0053132615 0.6023180000 953707039 0 1783345152 0.1335591823 0.3706180453 2.2488694191 435 17.3600000000 0.0019386569 0.0030783466 0.0056244121 0.0053119943 0.6035800000 953708313 0 1782280192 0.1283331066 0.3691727519 2.2503144741 436 17.4000000000 0.0019386468 0.0030757326 0.0056244121 0.0053156144 0.6058320000 953709587 0 1783967744 0.1233606413 0.3688878119 2.2530827522 437 17.4400000000 0.0019247269 0.0030730988 0.0056244121 0.0053146612 0.6082470000 953710861 0 1782808576 0.1171344221 0.3701720834 2.2561087608 438 17.4800000000 0.0019617821 0.0030705615 0.0056244121 0.0053143153 0.6157530000 953712135 0 1781813248 0.1120663434 0.3687783480 2.2583801746 439 17.5200000000 0.0019363158 0.0030679778 0.0056244121 0.0053132385 0.6109320000 953713409 0 1783558144 0.1072219983 0.3686675727 2.2607142925 440 17.5600000000 0.0019349252 0.0030654027 0.0056244121 0.0053123838 0.6546460000 953714683 0 1782292480 0.1020791978 0.3683686256 2.2627367973 441 17.6000000000 0.0019085117 0.0030627793 0.0056244121 0.0053108621 0.6130030000 953715957 0 1784082432 0.0963951424 0.3680220544 2.2641451359 442 17.6400000000 0.0044021644 0.0030658096 0.0056244121 0.0053237412 0.5739690000 953717231 0 1782837248 0.0898772031 0.3681958914 2.2636773586 443 17.6800000000 0.0019285057 0.0030632424 0.0056244121 0.0053233025 0.6171350000 953718505 0 1781780480 0.0857036784 0.3677362502 2.2671070099 444 17.7200000000 0.0044475221 0.0030663601 0.0056244121 0.0053307376 0.5770510000 953719779 0 1783468032 0.0789656192 0.3687984645 2.2677972317 445 17.7600000000 0.0019888161 0.0030639387 0.0056244121 0.0053350637 0.6146600000 953721053 0 1782321152 0.0754738897 0.3670423627 2.2710421085 446 17.8000000000 0.0039774249 0.0030659868 0.0056244121 0.0053494970 0.5837640000 953722327 0 1784074240 0.0688652471 0.3673276007 2.2712152004 447 17.8400000000 0.0020361934 0.0030636830 0.0056244121 0.0053509757 0.6254140000 953723601 0 1782829056 0.0643065944 0.3657303452 2.2760066986 448 17.8800000000 0.0041907453 0.0030661988 0.0056244121 0.0053612447 0.5798460000 953724875 0 1781788672 0.0566440597 0.3670375943 2.2764358521 449 17.9200000000 0.0057060965 0.0030720783 0.0057060965 0.0053611896 0.5785760000 953726149 0 1783586816 0.0506341048 0.3671810329 2.2765827179 450 17.9600000000 0.0065594190 0.0030798280 0.0065594190 0.0053583156 0.5794080000 953727423 0 1782415360 0.0451327004 0.3664487898 2.2775807381 451 18.0000000000 0.0021255424 0.0030777120 0.0065594190 0.0053776402 0.6382020000 953728697 0 1784049664 0.0338281617 0.3620171547 2.2842731476 452 18.0400000000 0.0045047733 0.0030808692 0.0065594190 0.0053825505 0.5767230000 953729971 0 1782804480 0.0270468667 0.3633334637 2.2849040031 453 18.0800000000 0.0056021917 0.0030864351 0.0065594190 0.0053875232 0.5821550000 953731245 0 1781383168 0.0203188416 0.3625741303 2.2865583897 454 18.1200000000 0.0021956658 0.0030844730 0.0065594190 0.0053903757 0.6443070000 953732519 0 1783177216 0.0144079542 0.3602662981 2.2923672199 455 18.1600000000 0.0043233754 0.0030871959 0.0065594190 0.0053926718 0.5821160000 953733793 0 1782071296 0.0067708120 0.3618487716 2.2942562103 456 18.2000000000 0.0056648934 0.0030928487 0.0065594190 0.0053923963 0.5794470000 953735067 0 1783676928 0.0007780531 0.3614691198 2.2951073647 457 18.2400000000 0.0065055545 0.0031003164 0.0065594190 0.0053870885 0.5801300000 953736341 0 1782579200 -0.0063138036 0.3617940247 2.2971310616 458 18.2800000000 0.0022744923 0.0030985132 0.0065594190 0.0054406950 0.6796030000 953737615 0 1784238080 -0.0118891876 0.3590437472 2.3017585278 459 18.3200000000 0.0043054591 0.0031011428 0.0065594190 0.0054355608 0.5804600000 953738889 0 1782947840 -0.0189328343 0.3593755364 2.3015897274 460 18.3600000000 0.0053815902 0.0031061003 0.0065594190 0.0054301898 0.5803530000 953740163 0 1781940224 -0.0250788666 0.3590480089 2.3024816513 461 18.4000000000 0.0057591638 0.0031118553 0.0065594190 0.0054250421 0.5803170000 953741437 0 1783549952 -0.0322308317 0.3580225408 2.3048586845 462 18.4400000000 0.0023892941 0.0031102913 0.0065594190 0.0054470984 0.6440030000 953742711 0 1782579200 -0.0381464846 0.3551697135 2.3105111122 463 18.4800000000 0.0035235835 0.0031111839 0.0065594190 0.0054426387 0.5876820000 953743985 0 1784201216 -0.0440876372 0.3560187817 2.3100171089 464 18.5200000000 0.0043663690 0.0031138891 0.0065594190 0.0054414201 0.5842630000 953745259 0 1782804480 -0.0510705039 0.3552109003 2.3101177216 465 18.5600000000 0.0024360844 0.0031124314 0.0065594190 0.0054469775 0.6417970000 953746533 0 1784475648 -0.0570981652 0.3528311849 2.3146462440 466 18.6000000000 0.0047748196 0.0031159988 0.0065594190 0.0054507541 0.5806480000 953747807 0 1783042048 -0.0638929605 0.3531956077 2.3156681061 467 18.6400000000 0.0061063617 0.0031224021 0.0065594190 0.0054527256 0.5811440000 953749081 0 1784729600 -0.0702177733 0.3545268476 2.3158471584 468 18.6800000000 0.0066941483 0.0031300341 0.0066941483 0.0054536951 0.5835760000 953750355 0 1783345152 -0.0754382685 0.3540940583 2.3152515888 469 18.7200000000 0.0025803039 0.0031288619 0.0066941483 0.0054716951 0.6414450000 953751629 0 1781518336 -0.0807614401 0.3512652814 2.3204078674 470 18.7600000000 0.0038493131 0.0031303948 0.0066941483 0.0054684620 0.5801910000 953752903 0 1783201792 -0.0869800821 0.3510812521 2.3200151920 471 18.8000000000 0.0026557199 0.0031293870 0.0066941483 0.0054758081 0.6458660000 953754177 0 1782071296 -0.1003810763 0.3460983932 2.3221702576 472 18.8400000000 0.0048069851 0.0031329412 0.0066941483 0.0054834684 0.5803340000 953755451 0 1783693312 -0.1057065800 0.3463803828 2.3219051361 473 18.8800000000 0.0066640838 0.0031404067 0.0066941483 0.0054926969 0.5821560000 953756725 0 1782583296 -0.1080499142 0.3457036614 2.3194913864 474 18.9200000000 0.0078159673 0.0031502707 0.0078159673 0.0055001452 0.5770220000 953757999 0 1784184832 -0.1104672700 0.3446100354 2.3188099861 475 18.9600000000 0.0027718786 0.0031494741 0.0078159673 0.0055169694 0.6385730000 953759273 0 1782820864 -0.1128555387 0.3403496444 2.3240473270 476 19.0000000000 0.0027521248 0.0031486393 0.0078159673 0.0055333388 0.6640550000 953760547 0 1784455168 -0.1179188117 0.3376567960 2.3243288994 477 19.0400000000 0.0046484550 0.0031517836 0.0078159673 0.0055674094 0.5783350000 953761821 0 1783058432 -0.1205738783 0.3365823030 2.3221540451 478 19.0800000000 0.0027906750 0.0031510281 0.0078159673 0.0055798566 0.6385120000 953763095 0 1781686272 -0.1262589842 0.3331763446 2.3297574520 479 19.1200000000 0.0066421088 0.0031583164 0.0078159673 0.0056167178 0.5843360000 953764369 0 1783169024 -0.1274978518 0.3357953429 2.3272476196 480 19.1600000000 0.0028574737 0.0031576896 0.0078159673 0.0056206614 0.6363230000 953765643 0 1781821440 -0.1267083883 0.3326497376 2.3294229507 481 19.2000000000 0.0067329463 0.0031651226 0.0078159673 0.0056916764 0.5766210000 953766917 0 1783455744 -0.1290307939 0.3344936669 2.3276784420 482 19.2400000000 0.0029656093 0.0031647087 0.0078159673 0.0056954255 0.6372970000 953768191 0 1782042624 -0.1288220733 0.3323031068 2.3311417103 483 19.2800000000 0.0070452518 0.0031727429 0.0078159673 0.0057664900 0.5826830000 953769465 0 1783709696 -0.1304574162 0.3339220583 2.3294866085 484 19.3200000000 0.0031616599 0.0031727200 0.0078159673 0.0057760244 0.6414670000 953770739 0 1782456320 -0.1291686296 0.3308455944 2.3335289955 485 19.3600000000 0.0032356745 0.0031728498 0.0078159673 0.0057994000 0.6453850000 953772013 0 1784057856 -0.1287723333 0.3308741152 2.3337047100 486 19.4000000000 0.0032097802 0.0031729258 0.0078159673 0.0058115740 0.6465410000 953773287 0 1782710272 -0.1298002750 0.3309098482 2.3367941380 487 19.4400000000 0.0032623103 0.0031731094 0.0078159673 0.0058232520 0.6529120000 953774561 0 1784328192 -0.1291816384 0.3311023414 2.3390381336 488 19.4800000000 0.0032736107 0.0031733153 0.0078159673 0.0058381681 0.6548100000 953775835 0 1782931456 -0.1292328387 0.3300622106 2.3417527676 489 19.5200000000 0.0032765507 0.0031735264 0.0078159673 0.0058474765 0.6566050000 953777109 0 1781575680 -0.1315017939 0.3305493593 2.3473286629 490 19.5600000000 0.0093749240 0.0031861823 0.0093749240 0.0059463129 0.5970300000 953778383 0 1783296000 -0.1312596798 0.3353872001 2.3436939716 491 19.6000000000 0.0033622477 0.0031865409 0.0093749240 0.0059743868 0.6566330000 953779657 0 1781944320 -0.1301570535 0.3317695260 2.3519158363 492 19.6400000000 0.0033060459 0.0031867838 0.0093749240 0.0059781459 0.6591700000 953780931 0 1783566336 -0.1293250471 0.3319559693 2.3550574780 493 19.6800000000 0.0031527407 0.0031867148 0.0093749240 0.0059865492 0.6981840000 953782205 0 1782439936 -0.1271685213 0.3333886564 2.3553817272 494 19.7200000000 0.0030509103 0.0031864399 0.0093749240 0.0060101857 0.6681690000 953783479 0 1784082432 -0.1281889975 0.3331636488 2.3604795933 495 19.7600000000 0.0102851028 0.0032007806 0.0102851028 0.0061757223 0.6045640000 953784753 0 1782718464 -0.1296091676 0.3377662897 2.3604443073 496 19.8000000000 0.0167398583 0.0032280771 0.0167398583 0.0062825041 0.6081440000 953786027 0 1784320000 -0.1302868128 0.3429543376 2.3602390289 497 19.8400000000 0.0033570649 0.0032283367 0.0167398583 0.0064871821 0.6705900000 953787301 0 1783083008 -0.1278862804 0.3352865279 2.3721303940 498 19.8800000000 0.0098860878 0.0032417056 0.0167398583 0.0065959419 0.6122060000 953788575 0 1781563392 -0.1275500059 0.3402184248 2.3695573807 499 19.9200000000 0.0031947980 0.0032416116 0.0167398583 0.0066552017 0.6690100000 953789849 0 1783177216 -0.1269168407 0.3353313208 2.3794794083 500 19.9600000000 0.0029086655 0.0032409457 0.0167398583 0.0066563523 0.6746010000 953791123 0 1781841920 -0.1263998747 0.3362226784 2.3825027943 501 20.0000000000 0.0028979592 0.0032402611 0.0167398583 0.0066603041 0.7082980000 953792397 0 1783447552 -0.1257495731 0.3367723227 2.3851513863 502 20.0400000000 0.0028326807 0.0032394492 0.0167398583 0.0066667113 0.6832470000 953793671 0 1782161408 -0.1255199909 0.3371621966 2.3885946274 503 20.0800000000 0.0028998968 0.0032387742 0.0167398583 0.0066734275 0.6798680000 953794945 0 1783803904 -0.1265802830 0.3381700218 2.3920793533 504 20.1200000000 0.0036641117 0.0032396181 0.0167398583 0.0066833115 0.6795210000 953796219 0 1782456320 -0.1267569214 0.3391939104 2.3953871727 505 20.1600000000 0.0037831364 0.0032406944 0.0167398583 0.0066914255 0.6821700000 953797493 0 1784090624 -0.1272840202 0.3401558697 2.3978965282 506 20.2000000000 0.0037013842 0.0032416048 0.0167398583 0.0066986726 0.6847560000 953798767 0 1782677504 -0.1269048303 0.3402674496 2.4002425671 507 20.2400000000 0.0040201754 0.0032431405 0.0167398583 0.0067061379 0.6872980000 953800041 0 1784328192 -0.1274642795 0.3402118087 2.4030673504 508 20.2800000000 0.0044112080 0.0032454398 0.0167398583 0.0067154191 0.6898070000 953801315 0 1783091200 -0.1293463856 0.3400953412 2.4066705704 509 20.3200000000 0.0046383901 0.0032481764 0.0167398583 0.0067250826 0.6976740000 953802589 0 1781645312 -0.1292402744 0.3397944570 2.4096210003 510 20.3600000000 0.0049624545 0.0032515378 0.0167398583 0.0067290536 0.6958340000 953803863 0 1783328768 -0.1287766546 0.3407277763 2.4093897343 511 20.4000000000 0.0132796876 0.0032711623 0.0167398583 0.0068756287 0.6409750000 953805137 0 1781944320 -0.1297463179 0.3463725746 2.4044404030 512 20.4400000000 0.0059028883 0.0032763024 0.0167398583 0.0069303583 0.7017190000 953806411 0 1783549952 -0.1321926713 0.3416299224 2.4131348133 513 20.4800000000 0.0084999455 0.0032864850 0.0167398583 0.0069371981 0.7090000000 953807685 0 1782296576 -0.1322398037 0.3444800079 2.4128596783 514 20.5200000000 0.0134256948 0.0033062111 0.0167398583 0.0070340124 0.6488190000 953892927 0 1783947264 -0.1336383820 0.3475448489 2.4086771011 515 20.5600000000 0.0078317039 0.0033149984 0.0167398583 0.0070831039 0.7065150000 953894201 0 1782534144 -0.1351045966 0.3437104523 2.4149956703 516 20.6000000000 0.0077329692 0.0033235604 0.0167398583 0.0070827857 0.7142930000 953895475 0 1784184832 -0.1366233677 0.3435283303 2.4148674011 517 20.6400000000 0.0094908718 0.0033354894 0.0167398583 0.0070859270 0.7105440000 953896749 0 1782800384 -0.1377135068 0.3448613286 2.4138789177 518 20.6800000000 0.0176646411 0.0033631519 0.0176646411 0.0071092856 0.7174280000 953898023 0 1784455168 -0.1392219365 0.3523570001 2.4139130116 519 20.7200000000 0.0180641897 0.0033914776 0.0180641897 0.0071107597 0.7205300000 953899297 0 1782931456 -0.1423157901 0.3526515365 2.4149382114 520 20.7600000000 0.0186730865 0.0034208653 0.0186730865 0.0071131323 0.7161440000 953900571 0 1784598528 -0.1441163421 0.3516362011 2.4154336452 521 20.8000000000 0.0234232396 0.0034592576 0.0234232396 0.0071232759 0.7239060000 953901845 0 1783201792 -0.1463029385 0.3557625115 2.4144802094 522 20.8400000000 0.0269969590 0.0035043489 0.0269969590 0.0071341820 0.7277180000 953903119 0 1781702656 -0.1491689533 0.3580951691 2.4146606922 523 20.8800000000 0.0485966466 0.0035905675 0.0485966466 0.0072128156 0.7604470000 953904393 0 1783296000 -0.1496680826 0.3802745342 2.4093763828 524 20.9200000000 0.0611703694 0.0037004526 0.0611703694 0.0073129110 0.7234300000 953905667 0 1781944320 -0.1508444548 0.3908945620 2.4033501148 525 20.9600000000 0.0612622947 0.0038100942 0.0612622947 0.0073237719 0.6829360000 953906941 0 1783566336 -0.1538451016 0.3882304430 2.4005119801 526 21.0000000000 0.0559099615 0.0039091434 0.0612622947 0.0074006255 0.7426560000 953908215 0 1782185984 -0.1573763490 0.3839606643 2.4048662186 527 21.0400000000 0.0573926270 0.0040106301 0.0612622947 0.0073991324 0.7360390000 953909489 0 1783693312 -0.1600256115 0.3853465021 2.4009015560 528 21.0800000000 0.0631076097 0.0041225562 0.0631076097 0.0074518106 0.6642640000 953910763 0 1782439936 -0.1638960987 0.3885273635 2.3955731392 529 21.1200000000 0.0554636531 0.0042196093 0.0631076097 0.0075005466 0.7225000000 953912037 0 1784074240 -0.1685755849 0.3802286088 2.3990287781 530 21.1600000000 0.0602178201 0.0043252663 0.0631076097 0.0075174711 0.6517050000 953913311 0 1782677504 -0.1709142476 0.3854184449 2.3912601471 531 21.2000000000 0.0606486425 0.0044313367 0.0631076097 0.0075235286 0.6314610000 953914585 0 1784344576 -0.1740910262 0.3845670521 2.3861069679 532 21.2400000000 0.0703810304 0.0045553023 0.0703810304 0.0075583299 0.6656850000 953915859 0 1782964224 -0.1784457266 0.3933827579 2.3807096481 533 21.2800000000 0.0674385577 0.0046732821 0.0703810304 0.0075609386 0.6203300000 953917133 0 1784565760 -0.1820761561 0.3897167146 2.3780305386 534 21.3200000000 0.0669747368 0.0047899515 0.0703810304 0.0075653598 0.6185490000 953918407 0 1783234560 -0.1860603839 0.3866819143 2.3762321472 535 21.3600000000 0.0548702292 0.0048835595 0.0703810304 0.0077223304 0.6748850000 953919681 0 1781833728 -0.1921451986 0.3742110729 2.3845767975 536 21.4000000000 0.0811876729 0.0050259179 0.0811876729 0.0077936447 0.6242370000 953920955 0 1783549952 -0.1958698630 0.3997427821 2.3755943775 537 21.4400000000 0.0835910141 0.0051722216 0.0835910141 0.0077970630 0.6248400000 953922229 0 1782325248 -0.2001188695 0.4025993943 2.3706994057 538 21.4800000000 0.0933087543 0.0053360442 0.0933087543 0.0078051706 0.6266760000 953923503 0 1784098816 -0.2049572915 0.4126885533 2.3653993607 539 21.5200000000 0.0851645023 0.0054841489 0.0933087543 0.0078032638 0.6187100000 953924777 0 1782669312 -0.2092279494 0.4033897817 2.3639376163 540 21.5600000000 0.0809055790 0.0056238182 0.0933087543 0.0078044379 0.6213760000 953926051 0 1784463360 -0.2142007053 0.3987498879 2.3614714146 541 21.6000000000 0.0713098422 0.0057452342 0.0933087543 0.0078972971 0.6733150000 953927325 0 1783193600 -0.2196946889 0.3887905777 2.3659381866 542 21.6400000000 0.0753943548 0.0058737381 0.0933087543 0.0079228600 0.6219390000 953928599 0 1781968896 -0.2234348059 0.3896183968 2.3610565662 543 21.6800000000 0.0680798367 0.0059882981 0.0933087543 0.0079938929 0.6742860000 953929873 0 1783590912 -0.2281417847 0.3804904521 2.3612651825 544 21.7200000000 0.0739135593 0.0061131607 0.0933087543 0.0080955326 0.6696680000 953931147 0 1782415360 -0.2357614636 0.3829517961 2.3515920639 545 21.7600000000 0.0753662139 0.0062402306 0.0933087543 0.0080902612 0.6176000000 953932421 0 1784082432 -0.2405274212 0.3866466582 2.3452007771 546 21.8000000000 0.0802740529 0.0063758236 0.0933087543 0.0080887282 0.6100150000 953933695 0 1782710272 -0.2449947149 0.3906695247 2.3397777081 547 21.8400000000 0.0773787796 0.0065056279 0.0933087543 0.0080955675 0.6101780000 953934969 0 1784320000 -0.2495661080 0.3853738606 2.3360085487 548 21.8800000000 0.0835551694 0.0066462293 0.0933087543 0.0080906871 0.6445030000 953936243 0 1782951936 -0.2553479373 0.3960227966 2.3286502361 549 21.9200000000 0.0836957619 0.0067865745 0.0933087543 0.0080915250 0.6096030000 953937517 0 1781686272 -0.2604152560 0.3988669217 2.3228080273 550 21.9600000000 0.1005766839 0.0069571020 0.1005766839 0.0081278912 0.6055900000 953938791 0 1783296000 -0.2637674510 0.4081079960 2.3176755905 551 22.0000000000 0.0890725777 0.0071061319 0.1005766839 0.0081529446 0.6073880000 953940065 0 1782218752 -0.2680657208 0.3953125477 2.3139612675 552 22.0400000000 0.0780292898 0.0072346159 0.1005766839 0.0081523094 0.6077810000 953941339 0 1783803904 -0.2736000717 0.3905722797 2.3070023060 553 22.0800000000 0.0743839443 0.0073560432 0.1005766839 0.0081467778 0.6197900000 953942613 0 1782448128 -0.2776809931 0.3879465461 2.3010163307 554 22.1200000000 0.0730199963 0.0074745702 0.1005766839 0.0081406369 0.6051350000 953943887 0 1784201216 -0.2818015814 0.3842387795 2.2954483032 555 22.1600000000 0.0724467039 0.0075916371 0.1005766839 0.0081337412 0.6042740000 953945161 0 1783042048 -0.2856767774 0.3843542933 2.2885808945 556 22.2000000000 0.0651158094 0.0076950979 0.1005766839 0.0081286467 0.6060870000 953946435 0 1781800960 -0.2890453935 0.3752821982 2.2837157249 557 22.2400000000 0.0634484738 0.0077951937 0.1005766839 0.0081370481 0.7029110000 953947709 0 1783566336 -0.2941266894 0.3759713173 2.2794101238 558 22.2800000000 0.0692452341 0.0079053192 0.1005766839 0.0081417605 0.5989020000 953948983 0 1782423552 -0.2972077429 0.3803783357 2.2714240551 559 22.3200000000 0.0554012172 0.0079902851 0.1005766839 0.0081581816 0.6602110000 953950257 0 1784221696 -0.3008102179 0.3649847507 2.2670571804 560 22.3600000000 0.0579238757 0.0080794522 0.1005766839 0.0081561055 0.6419890000 953951531 0 1782939648 -0.3037382960 0.3663962483 2.2587816715 561 22.4000000000 0.0558408312 0.0081645883 0.1005766839 0.0081498343 0.6451450000 953952805 0 1781661696 -0.3069041073 0.3639494479 2.2520067692 562 22.4400000000 0.0569204055 0.0082513425 0.1005766839 0.0081524094 0.6581100000 953954079 0 1783332864 -0.3103981316 0.3606518209 2.2487802505 563 22.4800000000 0.0241513681 0.0082795841 0.1005766839 0.0082250119 0.6597050000 953955353 0 1782071296 -0.3132168949 0.3255860209 2.2434358597 564 22.5200000000 0.0607280433 0.0083725778 0.1005766839 0.0083846122 0.6569980000 953956627 0 1783820288 -0.3163851798 0.3635103703 2.2360577583 565 22.5600000000 0.0151089141 0.0083845005 0.1005766839 0.0084864485 0.6537600000 953957901 0 1782681600 -0.3235329688 0.3198586404 2.2226054668 566 22.6000000000 0.0085136723 0.0083847287 0.1005766839 0.0084908816 0.6586920000 953959175 0 1784348672 -0.3271039426 0.3083007634 2.2152364254 567 22.6400000000 0.0077558993 0.0083836197 0.1005766839 0.0084848769 0.6603730000 953960449 0 1783169024 -0.3303835988 0.3059248030 2.2081339359 568 22.6800000000 0.0073733446 0.0083818410 0.1005766839 0.0084825071 0.6377460000 953961723 0 1782071296 -0.3337106109 0.3074212670 2.2006602287 569 22.7200000000 0.0058333147 0.0083773621 0.1005766839 0.0084823439 0.6572670000 953962997 0 1783730176 -0.3372622430 0.3059513271 2.1941692829 570 22.7600000000 0.0050571496 0.0083715371 0.1005766839 0.0084822420 0.6527860000 953964271 0 1782534144 -0.3404414952 0.3012591302 2.1895134449 571 22.8000000000 0.0064223944 0.0083681236 0.1005766839 0.0084753401 0.6493020000 953965545 0 1784201216 -0.3428043425 0.2986534238 2.1816852093 572 22.8400000000 0.0029275084 0.0083586120 0.1005766839 0.0084862469 0.6319300000 953966819 0 1782820864 -0.3459168971 0.2999073863 2.1766910553 573 22.8800000000 0.0067335279 0.0083557759 0.1005766839 0.0085042414 0.6894790000 953968093 0 1784311808 -0.3500626385 0.3042459488 2.1678295135 574 22.9200000000 0.0247002766 0.0083842506 0.1005766839 0.0085593402 0.6519900000 953969367 0 1782964224 -0.3547302186 0.3233641684 2.1605839729 575 22.9600000000 0.0493089519 0.0084554240 0.1005766839 0.0086283367 0.6322110000 953970641 0 1781428224 -0.3574084938 0.3466092348 2.1509141922 576 23.0000000000 0.0550085977 0.0085362455 0.1005766839 0.0086714245 0.6360860000 953971915 0 1783042048 -0.3607845306 0.3468681276 2.1407456398 577 23.0400000000 0.0558098704 0.0086181756 0.1005766839 0.0086960204 0.6266430000 953973189 0 1781686272 -0.3649182320 0.3452085257 2.1349258423 578 23.0800000000 0.0612853356 0.0087092952 0.1005766839 0.0087185431 0.6317160000 953974463 0 1783169024 -0.3671682477 0.3516071737 2.1281809807 579 23.1200000000 0.0465531014 0.0087746558 0.1005766839 0.0087462945 0.6270700000 953975737 0 1781833728 -0.3687461913 0.3363844156 2.1251335144 580 23.1600000000 0.0297028236 0.0088107389 0.1005766839 0.0087911850 0.6306660000 953977011 0 1783439360 -0.3700370491 0.3191507757 2.1256351471 581 23.2000000000 0.0125249894 0.0088171317 0.1005766839 0.0088462100 0.6667220000 953978285 0 1782042624 -0.3750841916 0.2824315429 2.1248443127 582 23.2400000000 0.0739305168 0.0089290104 0.1005766839 0.0092388671 0.6540090000 953979559 0 1783820288 -0.3823622465 0.3585045040 2.1113493443 583 23.2800000000 0.0658088028 0.0090265744 0.1005766839 0.0092653454 0.6288790000 953980833 0 1782439936 -0.3845156133 0.3501065969 2.1058530807 584 23.3200000000 0.0582645908 0.0091108860 0.1005766839 0.0092828540 0.6374230000 953982107 0 1784057856 -0.3879334927 0.3420044780 2.1001293659 585 23.3600000000 0.0973592997 0.0092617380 0.1005766839 0.0094230433 0.6721260000 953983381 0 1782820864 -0.3944827914 0.3789372444 2.0945193768 586 23.4000000000 0.0946286172 0.0094074153 0.1005766839 0.0094229243 0.6413540000 953984655 0 1784455168 -0.3975698054 0.3746528625 2.0892443657 587 23.4400000000 0.0929058716 0.0095496614 0.1005766839 0.0094225996 0.6488140000 953985929 0 1783042048 -0.4021610916 0.3727200329 2.0838983059 588 23.4800000000 0.0933590457 0.0096921944 0.1005766839 0.0094208647 0.6565110000 953987203 0 1781702656 -0.4090576172 0.3712994158 2.0769286156 589 23.5200000000 0.0935817510 0.0098346215 0.1005766839 0.0094168350 0.6751860000 953988477 0 1783312384 -0.4154331982 0.3685843945 2.0697741508 590 23.5600000000 0.0949300304 0.0099788510 0.1005766839 0.0094229474 0.6174610000 953989751 0 1781899264 -0.4205324948 0.3679650128 2.0607666969 591 23.6000000000 0.0953436494 0.0101232922 0.1005766839 0.0094174611 0.6613650000 953991025 0 1783566336 -0.4278761148 0.3663122654 2.0551357269 592 23.6400000000 0.0954163373 0.0102673683 0.1005766839 0.0094124399 0.6677860000 953992299 0 1782296576 -0.4342263043 0.3660938442 2.0472631454 593 23.6800000000 0.1135020033 0.0104414571 0.1135020033 0.0094626734 0.6307420000 953993573 0 1783939072 -0.4390501678 0.3846275806 2.0365433693 594 23.7200000000 0.0956977308 0.0105849862 0.1135020033 0.0094937263 0.6716810000 953994847 0 1782841344 -0.4475172758 0.3638431728 2.0332553387 595 23.7600000000 0.1071955189 0.0107473568 0.1135020033 0.0094966471 0.6811530000 953996121 0 1784590336 -0.4561383724 0.3717678189 2.0243117809 596 23.8000000000 0.1065341830 0.0109080730 0.1135020033 0.0094995924 0.6834680000 953997395 0 1783304192 -0.4636631310 0.3683737218 2.0167605877 597 23.8400000000 0.1060023308 0.0110673598 0.1135020033 0.0094944442 0.6973220000 953998669 0 1782099968 -0.4676315486 0.3682314456 2.0090301037 598 23.8800000000 0.1068559512 0.0112275414 0.1135020033 0.0094899796 0.6900250000 953999943 0 1783721984 -0.4762555659 0.3684281409 2.0011212826 599 23.9200000000 0.1069298461 0.0113873116 0.1135020033 0.0094866039 0.7181940000 954001217 0 1782423552 -0.4847814739 0.3681329489 1.9925192595 600 23.9600000000 0.1084533781 0.0115490883 0.1135020033 0.0094835009 0.7131270000 954002491 0 1784193024 -0.4908230603 0.3684451878 1.9846599102 601 24.0000000000 0.1110736877 0.0117146867 0.1135020033 0.0094814472 0.6999320000 954003765 0 1782931456 -0.4983970821 0.3699941337 1.9765303135 602 24.0400000000 0.1140037850 0.0118846021 0.1140037850 0.0094919960 0.7355480000 954005039 0 1781837824 -0.5148708820 0.3712330759 1.9598289728 603 24.0800000000 0.1122839451 0.0120511018 0.1140037850 0.0094886149 0.7050660000 954006313 0 1783558144 -0.5241213441 0.3685236275 1.9522292614 604 24.1200000000 0.1112724692 0.0122153756 0.1140037850 0.0094887997 0.7464060000 954007587 0 1782407168 -0.5360046625 0.3651408851 1.9436898232 605 24.1600000000 0.1114993766 0.0123794814 0.1140037850 0.0094911735 0.7367680000 954008861 0 1784090624 -0.5423541069 0.3651691973 1.9356281757 606 24.2000000000 0.1133928299 0.0125461701 0.1140037850 0.0094884122 0.7339030000 954010135 0 1782689792 -0.5477420092 0.3667982519 1.9270901680 607 24.2400000000 0.1129866764 0.0127116405 0.1140037850 0.0094835025 0.7199820000 954011409 0 1784438784 -0.5546792746 0.3650147915 1.9185512066 608 24.2800000000 0.1130844951 0.0128767274 0.1140037850 0.0094786690 0.7191300000 954012683 0 1783197696 -0.5628408790 0.3637151718 1.9094934464 609 24.3200000000 0.1137978509 0.0130424435 0.1140037850 0.0094750029 0.7231980000 954013957 0 1781833728 -0.5710436702 0.3641048074 1.9013524055 610 24.3600000000 0.1139097139 0.0132077997 0.1140037850 0.0094716723 0.7214690000 954015231 0 1783328768 -0.5760999322 0.3635197878 1.8931702375 611 24.4000000000 0.1142607555 0.0133731892 0.1142607555 0.0094675172 0.7603750000 954016505 0 1782280192 -0.5809441805 0.3630981445 1.8846422434 612 24.4400000000 0.1143387333 0.0135381655 0.1143387333 0.0094640159 0.7326090000 954017779 0 1783984128 -0.5876022577 0.3617044091 1.8760492802 613 24.4800000000 0.1155395284 0.0137045626 0.1155395284 0.0094615343 0.7365280000 954019053 0 1782542336 -0.5947540998 0.3622814417 1.8670717478 614 24.5200000000 0.1158275232 0.0138708866 0.1158275232 0.0094589337 0.7327680000 954020327 0 1784201216 -0.6014727354 0.3617146909 1.8593863249 615 24.5600000000 0.1164049506 0.0140376086 0.1164049506 0.0094557226 0.7435070000 954021601 0 1782788096 -0.6071415544 0.3616972268 1.8506926298 616 24.6000000000 0.1171397790 0.0142049823 0.1171397790 0.0094524530 0.7228820000 954022875 0 1784582144 -0.6145951152 0.3616365194 1.8412076235 617 24.6400000000 0.1176739335 0.0143726791 0.1176739335 0.0094491128 0.7353520000 954024149 0 1783361536 -0.6217656732 0.3617897034 1.8321886063 618 24.6800000000 0.1185572669 0.0145412626 0.1185572669 0.0094454225 0.7748220000 954025423 0 1782181888 -0.6261524558 0.3625804484 1.8233567476 619 24.7200000000 0.1192083508 0.0147103532 0.1192083508 0.0094404402 0.7565080000 954026697 0 1783930880 -0.6295241117 0.3634252548 1.8158545494 620 24.7600000000 0.1204376817 0.0148808812 0.1204376817 0.0094488613 0.8077390000 954027971 0 1782788096 -0.6419597864 0.3635146022 1.7968376875 621 24.8000000000 0.1210877448 0.0150519067 0.1210877448 0.0094452231 0.7936620000 954029245 0 1784455168 -0.6464851499 0.3629466295 1.7884614468 622 24.8400000000 0.1218144372 0.0152235507 0.1218144372 0.0094412512 0.7819670000 954030519 0 1783054336 -0.6534016728 0.3615158796 1.7785027027 623 24.8800000000 0.1224342287 0.0153956384 0.1224342287 0.0094361692 0.7850990000 954031793 0 1781702656 -0.6587797403 0.3609435260 1.7692991495 624 24.9200000000 0.1230875179 0.0155682216 0.1230875179 0.0094303222 0.7919710000 954033067 0 1783169024 -0.6644150615 0.3602642119 1.7598850727 625 24.9600000000 0.1238719821 0.0157415076 0.1238719821 0.0094242552 0.8010600000 954034341 0 1781772288 -0.6700753570 0.3599645197 1.7492836714 626 25.0000000000 0.1245187223 0.0159152731 0.1245187223 0.0094184725 0.8062990000 954035615 0 1783308288 -0.6771248579 0.3598194718 1.7386987209 627 25.0400000000 0.1251858771 0.0160895484 0.1251858771 0.0094137629 0.8224290000 954036889 0 1781948416 -0.6822587848 0.3592895567 1.7287358046 628 25.0800000000 0.1257658303 0.0162641922 0.1257658303 0.0094085180 0.8400720000 954038163 0 1783582720 -0.6876601577 0.3580915928 1.7186534405 629 25.1200000000 0.1267379969 0.0164398262 0.1267379969 0.0094025017 0.8790380000 954039437 0 1782153216 -0.6946648359 0.3585974872 1.7062090635 630 25.1600000000 0.1273591667 0.0166158886 0.1273591667 0.0093991767 0.9016900000 954040711 0 1783676928 -0.6990038157 0.3583731353 1.6961768866 631 25.2000000000 0.1279990822 0.0167924072 0.1279990822 0.0093919647 0.9768780000 954041985 0 1782280192 -0.7022446990 0.3579590917 1.6860748529 632 25.2400000000 0.1289423853 0.0169698597 0.1289423853 0.0093847824 0.9658180000 954043259 0 1783930880 -0.7092441916 0.3575149477 1.6731728315 633 25.2800000000 0.1296728551 0.0171479055 0.1296728551 0.0093796261 0.9501070000 954044533 0 1782534144 -0.7156050801 0.3566152751 1.6611361504 634 25.3200000000 0.1304035932 0.0173265422 0.1304035932 0.0093736412 0.9596590000 954045807 0 1784057856 -0.7186354399 0.3559755683 1.6509552002 635 25.3600000000 0.1310174465 0.0175055830 0.1310174465 0.0093681036 0.9438590000 954047081 0 1782661120 -0.7194865942 0.3557166457 1.6424226761 636 25.4000000000 0.1318964362 0.0176854428 0.1318964362 0.0093755687 0.9790040000 954048355 0 1784328192 -0.7287815213 0.3552242219 1.6282860041 637 25.4400000000 0.1330068409 0.0178664811 0.1330068409 0.0093689205 0.9788750000 954049629 0 1782923264 -0.7378894687 0.3564345837 1.6140990257 638 25.4800000000 0.1335750520 0.0180478425 0.1335750520 0.0093658445 0.9495520000 954050903 0 1784573952 -0.7380242348 0.3571579754 1.6045727730 639 25.5200000000 0.1343577802 0.0182298612 0.1343577802 0.0093590382 0.9420900000 954052177 0 1783177216 -0.7425253391 0.3572598994 1.5929526091 640 25.5600000000 0.1351924092 0.0184126152 0.1351924092 0.0093533304 0.9293800000 954053451 0 1781780480 -0.7467538118 0.3569985628 1.5804494619 641 25.6000000000 0.1359995157 0.0185960581 0.1359995157 0.0093467969 0.7871840000 954054725 0 1783320576 -0.7491986156 0.3569604158 1.5693442822 642 25.6400000000 0.1368338913 0.0187802292 0.1368338913 0.0093399609 0.7246380000 954055999 0 1781817344 -0.7524871826 0.3561805785 1.5573627949 643 25.6800000000 0.1375937760 0.0189650092 0.1375937760 0.0093333164 0.7553070000 954057273 0 1783296000 -0.7551981807 0.3553164303 1.5456734896 644 25.7200000000 0.1382990479 0.0191503105 0.1382990479 0.0093272962 0.6508440000 954058547 0 1781944320 -0.7588145733 0.3539297879 1.5343741179 645 25.7600000000 0.1391738057 0.0193363934 0.1391738057 0.0093213195 0.6460280000 954059821 0 1783566336 -0.7641788721 0.3536552489 1.5219810009 646 25.8000000000 0.1399883181 0.0195231611 0.1399883181 0.0093154619 0.6546540000 954061095 0 1782185984 -0.7670627832 0.3533942401 1.5098742247 647 25.8400000000 0.1408007443 0.0197106071 0.1408007443 0.0093096225 0.6505290000 954062369 0 1783693312 -0.7696061134 0.3539834619 1.4983512163 648 25.8800000000 0.1414068937 0.0198984100 0.1414068937 0.0093036340 0.6528050000 954063643 0 1782185984 -0.7700813413 0.3529602885 1.4891895056 649 25.9200000000 0.1422155052 0.0200868801 0.1422155052 0.0092997389 0.6573320000 954064917 0 1783709696 -0.7744242549 0.3520418108 1.4772766829 650 25.9600000000 0.1429545432 0.0202759073 0.1429545432 0.0092952549 0.6549180000 954066191 0 1782312960 -0.7785605788 0.3506670594 1.4651522636 651 26.0000000000 0.1437513530 0.0204655777 0.1437513530 0.0092907341 0.6873230000 954067465 0 1783947264 -0.7809446454 0.3491247594 1.4549707174 652 26.0400000000 0.1445175856 0.0206558416 0.1445175856 0.0092869588 0.6552690000 954068739 0 1782308864 -0.7831334472 0.3480172753 1.4437446594 653 26.0800000000 0.1453362554 0.0208467763 0.1453362554 0.0092836914 0.6551750000 954070013 0 1783947264 -0.7877470255 0.3457218111 1.4315391779 654 26.1200000000 0.1460639685 0.0210382399 0.1460639685 0.0092799382 0.6594050000 954071287 0 1782452224 -0.7909448743 0.3434990644 1.4206296206 655 26.1600000000 0.1468047649 0.0212302499 0.1468047649 0.0092759423 0.6602480000 954072561 0 1784090624 -0.7943111062 0.3407587111 1.4096242189 656 26.2000000000 0.1475176811 0.0214227612 0.1475176811 0.0092730112 0.6677040000 954073835 0 1782661120 -0.7986356020 0.3389669955 1.3983315229 657 26.2400000000 0.1482970715 0.0216158728 0.1482970715 0.0092682102 0.6608630000 954075109 0 1784328192 -0.8040163517 0.3365522325 1.3866282701 658 26.2800000000 0.1489996314 0.0218094651 0.1489996314 0.0092629674 0.6646560000 954076383 0 1782947840 -0.8063145876 0.3345029652 1.3768856525 659 26.3200000000 0.1497633159 0.0220036288 0.1497633159 0.0092587724 0.6638670000 954077657 0 1784565760 -0.8105611801 0.3333280683 1.3653639555 660 26.3600000000 0.1504828334 0.0221982943 0.1504828334 0.0092534977 0.6662330000 954078931 0 1783201792 -0.8137519956 0.3314812481 1.3542106152 661 26.4000000000 0.1512519270 0.0223935343 0.1512519270 0.0092500128 0.6693500000 954080205 0 1781813248 -0.8177586198 0.3302831650 1.3425878286 662 26.4400000000 0.1520394534 0.0225893740 0.1520394534 0.0092462816 0.6697550000 954081479 0 1783422976 -0.8231654167 0.3292698860 1.3303281069 663 26.4800000000 0.1529200971 0.0227859513 0.1529200971 0.0092414498 0.6729390000 954082753 0 1781964800 -0.8283757567 0.3290865719 1.3171070814 664 26.5200000000 0.1537565887 0.0229831962 0.1537565887 0.0092374287 0.6805980000 954084027 0 1783439360 -0.8326104283 0.3276145160 1.3050874472 665 26.5600000000 0.1554144919 0.0231823410 0.1554144919 0.0092472666 0.6833890000 954085301 0 1781899264 -0.8411059380 0.3273556828 1.2805427313 666 26.6000000000 0.1563238651 0.0233822532 0.1563238651 0.0092428655 0.6804990000 954086575 0 1783566336 -0.8461727500 0.3282153606 1.2667931318 667 26.6400000000 0.1570307910 0.0235826258 0.1570307910 0.0092377605 0.7189880000 954087849 0 1782059008 -0.8495851755 0.3283988833 1.2548590899 668 26.6800000000 0.1578994095 0.0237836989 0.1578994095 0.0092328150 0.6877610000 954089123 0 1783549952 -0.8551567793 0.3285298645 1.2412614822 669 26.7200000000 0.1586518735 0.0239852955 0.1586518735 0.0092294064 0.6908690000 954090397 0 1782202368 -0.8584364057 0.3292660117 1.2290320396 670 26.7600000000 0.1594667584 0.0241875067 0.1594667584 0.0092238206 0.6916840000 954091671 0 1783836672 -0.8614946604 0.3310109377 1.2165399790 671 26.8000000000 0.1603687406 0.0243904593 0.1603687406 0.0092194536 0.6963090000 954092945 0 1782439936 -0.8671503067 0.3302994668 1.2033745050 672 26.8400000000 0.1613165587 0.0245942184 0.1613165587 0.0092164155 0.6945650000 954094219 0 1784057856 -0.8721853495 0.3290868700 1.1907150745 673 26.8800000000 0.1622888446 0.0247988167 0.1622888446 0.0092132436 0.7035530000 954095493 0 1782546432 -0.8760242462 0.3278085291 1.1778755188 674 26.9200000000 0.1630626023 0.0250039558 0.1630626023 0.0092085305 0.6906380000 954096767 0 1784201216 -0.8769922853 0.3268525302 1.1662884951 675 26.9600000000 0.1639554948 0.0252098099 0.1639554948 0.0092076056 0.6934620000 954098041 0 1782788096 -0.8785828948 0.3254182637 1.1540920734 676 27.0000000000 0.1647570729 0.0254162408 0.1647570729 0.0092096667 0.6894640000 954099315 0 1784344576 -0.8823007345 0.3248848021 1.1409541368 677 27.0400000000 0.1655526906 0.0256232370 0.1655526906 0.0092093632 0.6995880000 954100589 0 1782964224 -0.8859945536 0.3245356381 1.1286103725 678 27.0800000000 0.1662111282 0.0258305938 0.1662111282 0.0092077821 0.6972060000 954101863 0 1784582144 -0.8890362978 0.3246800900 1.1180382967 679 27.1200000000 0.1670156270 0.0260385246 0.1670156270 0.0092067255 0.6944610000 954103137 0 1783209984 -0.8919175267 0.3239642680 1.1070742607 680 27.1600000000 0.1675809175 0.0262466752 0.1675809175 0.0092045444 0.6956620000 954104411 0 1781710848 -0.8947688341 0.3237677813 1.0976994038 681 27.2000000000 0.1683707088 0.0264553742 0.1683707088 0.0092028625 0.6738830000 954105685 0 1783209984 -0.8977333903 0.3238424361 1.0873205662 682 27.2400000000 0.1689091921 0.0266642508 0.1689091921 0.0092010688 0.6992010000 954106959 0 1781780480 -0.9015989304 0.3242461383 1.0758566856 683 27.2800000000 0.1697118282 0.0268736909 0.1697118282 0.0091965339 0.6995010000 954108233 0 1783447552 -0.9068768620 0.3247108459 1.0639802217 684 27.3200000000 0.1710339487 0.0270844515 0.1710339487 0.0091935595 0.6821970000 954109507 0 1782099968 -0.9077881575 0.3238152862 1.0546482801 685 27.3600000000 0.1714708507 0.0272952346 0.1714708507 0.0091919733 0.6895250000 954110781 0 1783685120 -0.9082316160 0.3235771358 1.0449763536 686 27.4000000000 0.1718956381 0.0275060223 0.1718956381 0.0091949750 0.7052820000 954112055 0 1782464512 -0.9139977694 0.3231388330 1.0319664478 687 27.4400000000 0.1729077846 0.0277176697 0.1729077846 0.0091913455 0.6855760000 954113329 0 1783971840 -0.9179915786 0.3220230043 1.0207076073 688 27.4800000000 0.1731765866 0.0279290926 0.1731765866 0.0091866119 0.6881040000 954114603 0 1782669312 -0.9203523993 0.3220759630 1.0112822056 689 27.5200000000 0.1741820574 0.0281413610 0.1741820574 0.0091830497 0.7067880000 954115877 0 1784438784 -0.9256242514 0.3221926093 0.9980704784 690 27.5600000000 0.1748394072 0.0283539669 0.1748394072 0.0091789969 0.7082460000 954117151 0 1783197696 -0.9264159203 0.3222956359 0.9876147509 691 27.6000000000 0.1755569875 0.0285669959 0.1755569875 0.0091737496 0.7376430000 954118425 0 1782321152 -0.9284183383 0.3217706978 0.9768739343 692 27.6400000000 0.1763116419 0.0287804997 0.1763116419 0.0091679522 0.7094030000 954119699 0 1783947264 -0.9310463667 0.3200818002 0.9644216299 693 27.6800000000 0.1770211309 0.0289944111 0.1770211309 0.0091617435 0.7123840000 954120973 0 1782808576 -0.9333186150 0.3198936880 0.9523552656 694 27.7200000000 0.1779483408 0.0292090422 0.1779483408 0.0091562733 0.7133240000 954122247 0 1781796864 -0.9353149533 0.3186280727 0.9402331710 695 27.7600000000 0.1787256598 0.0294241740 0.1787256598 0.0091512529 0.7143530000 954123521 0 1783459840 -0.9378268123 0.3161341846 0.9277737141 696 27.8000000000 0.1794374883 0.0296397103 0.1794374883 0.0091453502 0.7178350000 954124795 0 1782280192 -0.9402922988 0.3148986101 0.9150808454 697 27.8400000000 0.1812966019 0.0298572956 0.1812966019 0.0091432355 0.7360120000 954126069 0 1783963648 -0.9448047876 0.3090736866 0.8886520267 698 27.8800000000 0.1821290702 0.0300754500 0.1821290702 0.0091381274 0.7511460000 954127343 0 1782812672 -0.9450704455 0.3064463735 0.8778657913 699 27.9200000000 0.1829216033 0.0302941140 0.1829216033 0.0091451830 0.7254280000 954128617 0 1784471552 -0.9480955601 0.3087680042 0.8634303212 700 27.9600000000 0.1837275773 0.0305133046 0.1837275773 0.0091387312 0.7212110000 954129891 0 1783185408 -0.9491391182 0.3102073967 0.8485731483 701 28.0000000000 0.1845335811 0.0307330197 0.1845335811 0.0091365551 0.7178590000 954131165 0 1782050816 -0.9475235939 0.3097994328 0.8364909291 702 28.0400000000 0.1852397770 0.0309531148 0.1852397770 0.0091301600 0.7162900000 954132439 0 1783857152 -0.9477435350 0.3110308051 0.8235863447 703 28.0800000000 0.1863382608 0.0311741463 0.1863382608 0.0091243538 0.7260340000 954133713 0 1782661120 -0.9511091113 0.3100011647 0.8085428476 704 28.1200000000 0.1873996556 0.0313960576 0.1873996556 0.0091240069 0.7189560000 954134987 0 1784438784 -0.9505952597 0.3074339628 0.7955461144 705 28.1600000000 0.1885163784 0.0316189233 0.1885163784 0.0091182788 0.7572940000 954136261 0 1783230464 -0.9510537982 0.3041801155 0.7814566493 706 28.2000000000 0.1894518733 0.0318424827 0.1894518733 0.0091133583 0.7274940000 954137535 0 1781796864 -0.9517061710 0.3010635376 0.7678957582 707 28.2400000000 0.1903332174 0.0320666563 0.1903332174 0.0091134111 0.7199570000 954138809 0 1783422976 -0.9519623518 0.3017803133 0.7532826662 708 28.2800000000 0.1912849098 0.0322915408 0.1912849098 0.0091112005 0.7213050000 954140083 0 1782198272 -0.9551786780 0.3039416075 0.7378122211 709 28.3200000000 0.1923980862 0.0325173611 0.1923980862 0.0091108251 0.7181210000 954141357 0 1783820288 -0.9556865692 0.3019810319 0.7238857150 710 28.3600000000 0.1930117458 0.0327434095 0.1930117458 0.0091056920 0.7113670000 954142631 0 1782685696 -0.9528727531 0.3015003800 0.7138382792 711 28.4000000000 0.1938506514 0.0329700020 0.1938506514 0.0091015357 0.7166960000 954143905 0 1784438784 -0.9542905092 0.3011399806 0.7009899616 712 28.4400000000 0.1946239918 0.0331970441 0.1946239918 0.0090959502 0.7571470000 954145179 0 1783214080 -0.9546486735 0.2994882464 0.6893121600 713 28.4800000000 0.1953648627 0.0334244884 0.1953648627 0.0090907188 0.7154510000 954146453 0 1782321152 -0.9530352950 0.2970311940 0.6789457798 714 28.5200000000 0.1959857643 0.0336521653 0.1959857643 0.0090923374 0.7118850000 954147727 0 1783967744 -0.9538720846 0.2970513999 0.6675313115 715 28.5600000000 0.1968315840 0.0338803882 0.1968315840 0.0090922523 0.7127640000 954149001 0 1782931456 -0.9558812380 0.2998357415 0.6527687907 716 28.6000000000 0.1977919787 0.0341093150 0.1977919787 0.0090878900 0.7062020000 954150275 0 1781796864 -0.9561963677 0.3001073301 0.6399313211 717 28.6400000000 0.2002437413 0.0343410228 0.2002437413 0.0090866651 0.6927400000 954151549 0 1783586816 -0.9549060464 0.2983766198 0.6310272217 718 28.6800000000 0.1993560046 0.0345708486 0.2002437413 0.0090820741 0.6887750000 954152823 0 1782423552 -0.9555717111 0.2966013551 0.6225350499 719 28.7200000000 0.1998728067 0.0348007540 0.2002437413 0.0090800845 0.7483340000 954154097 0 1784201216 -0.9585301280 0.2962084115 0.6097254157 720 28.7600000000 0.1993932277 0.0350293547 0.2002437413 0.0090746654 0.6889530000 954155371 0 1783066624 -0.9604930878 0.2945660949 0.5989440084 721 28.8000000000 0.2011186332 0.0352597143 0.2011186332 0.0090729144 0.7070050000 954156645 0 1782046720 -0.9596581459 0.2975742519 0.5877068639 722 28.8400000000 0.2023618966 0.0354911577 0.2023618966 0.0090727191 0.7234350000 954157919 0 1783693312 -0.9655463696 0.3008815944 0.5750814080 723 28.8800000000 0.2027223706 0.0357224595 0.2027223706 0.0090703654 0.7034990000 954159193 0 1782558720 -0.9714634418 0.3007817268 0.5637528896 724 28.9200000000 0.2007686496 0.0359504239 0.2027223706 0.0090717860 0.6875290000 954160467 0 1784221696 -0.9745436907 0.2989955544 0.5554508567 725 28.9600000000 0.2044563740 0.0361828459 0.2044563740 0.0090691417 0.7252380000 954161741 0 1783058432 -0.9792628288 0.3032259941 0.5427969098 726 29.0000000000 0.2049759328 0.0364153433 0.2049759328 0.0090701015 0.7395800000 954163015 0 1782026240 -0.9820221066 0.3015062511 0.5294272900 727 29.0400000000 0.2065138072 0.0366493164 0.2065138072 0.0090695948 0.7205090000 954164289 0 1783701504 -0.9927285314 0.3018334508 0.5092387795 728 29.0800000000 0.2073844969 0.0368838427 0.2073844969 0.0090688894 0.7264830000 954165563 0 1782566912 -1.0037211180 0.3018412888 0.4948878884 729 29.1200000000 0.2083657980 0.0371190718 0.2083657980 0.0090917551 0.7009170000 954166837 0 1784336384 -1.0068216324 0.2970322967 0.4868634939 730 29.1600000000 0.2086888403 0.0373540988 0.2086888403 0.0090873707 0.7019620000 954168111 0 1783095296 -1.0096791983 0.2971082330 0.4778970778 731 29.2000000000 0.2096101642 0.0375897433 0.2096101642 0.0090826614 0.7211570000 954169385 0 1781932032 -1.0184384584 0.3005389273 0.4638083875 732 29.2400000000 0.2099437118 0.0378251995 0.2099437118 0.0090849968 0.7027370000 954170659 0 1783701504 -1.0240347385 0.3019879460 0.4529328942 733 29.2800000000 0.2103727162 0.0380605986 0.2103727162 0.0090837123 0.7332690000 954171933 0 1782542336 -1.0276041031 0.3050521314 0.4428715706 734 29.3200000000 0.2118480355 0.0382973662 0.2118480355 0.0090796163 0.7220630000 954173207 0 1784209408 -1.0359265804 0.3105729818 0.4303660989 735 29.3600000000 0.2123185247 0.0385341297 0.2123185247 0.0091030664 0.7050750000 954174481 0 1782960128 -1.0409384966 0.3091226518 0.4207871556 736 29.4000000000 0.2127832770 0.0387708812 0.2127832770 0.0091057436 0.7045050000 954175755 0 1784565760 -1.0436517000 0.3104016185 0.4126844108 737 29.4400000000 0.2139269710 0.0390085421 0.2139269710 0.0091004129 0.7251620000 954177029 0 1783361536 -1.0490736961 0.3161745369 0.4003294706 738 29.4800000000 0.2141681463 0.0392458858 0.2141681463 0.0091174171 0.7075210000 954178303 0 1782177792 -1.0539631844 0.3174287677 0.3899564743 739 29.5200000000 0.2142532468 0.0394827022 0.2142532468 0.0091351227 0.6847400000 954179577 0 1783836672 -1.0544537306 0.3156204522 0.3844141662 740 29.5600000000 0.2153504789 0.0397203614 0.2153504789 0.0091307624 0.7462080000 954180851 0 1782788096 -1.0570437908 0.3162080944 0.3753480017 741 29.6000000000 0.2159644663 0.0399582077 0.2159644663 0.0091256535 0.7071000000 954182125 0 1784471552 -1.0593024492 0.3171212375 0.3646087945 742 29.6400000000 0.2165476829 0.0401961989 0.2165476829 0.0091215721 0.7084630000 954183399 0 1783234560 -1.0618025064 0.3187128603 0.3544933498 743 29.6800000000 0.2135722488 0.0404295448 0.2165476829 0.0091208012 0.6878390000 954184673 0 1782026240 -1.0649878979 0.3177763820 0.3467220664 744 29.7200000000 0.2181396931 0.0406684026 0.2181396931 0.0091186727 0.7281080000 954185947 0 1783820288 -1.0714735985 0.3241255283 0.3369117081 745 29.7600000000 0.2156111747 0.0409032251 0.2181396931 0.0091353139 0.6895270000 954187221 0 1782702080 -1.0744423866 0.3221178353 0.3319852352 746 29.8000000000 0.2189732343 0.0411419248 0.2189732343 0.0091366945 0.7287150000 954188495 0 1784455168 -1.0795109272 0.3263620436 0.3231935203 747 29.8400000000 0.2193103433 0.0413804368 0.2193103433 0.0091607943 0.7398170000 954189769 0 1783422976 -1.0747226477 0.3252806067 0.3179112971 748 29.8800000000 0.2195587307 0.0416186430 0.2195587307 0.0091587079 0.6857420000 954191043 0 1782050816 -1.0726259947 0.3224275112 0.3148072660 749 29.9200000000 0.2197430581 0.0418564594 0.2197430581 0.0091562721 0.7043820000 954192317 0 1783820288 -1.0767962933 0.3226764798 0.3067461848 750 29.9600000000 0.2203197330 0.0420944104 0.2203197330 0.0091505324 0.7065020000 954193591 0 1782558720 -1.0801115036 0.3257876933 0.2967320085 751 30.0000000000 0.2192198187 0.0423302631 0.2203197330 0.0091560080 0.6836860000 954194865 0 1784311808 -1.0813963413 0.3233439624 0.2919979095 752 30.0400000000 0.2191207260 0.0425653568 0.2203197330 0.0091523865 0.6864020000 954196139 0 1782960128 -1.0838626623 0.3220686615 0.2881550491 753 30.0800000000 0.2219699621 0.0428036100 0.2219699621 0.0091479469 0.7233540000 954197413 0 1784602624 -1.0884985924 0.3284116983 0.2786094844 754 30.1200000000 0.2225008607 0.0430419352 0.2225008607 0.0091600377 0.7275550000 954198687 0 1783169024 -1.0874342918 0.3258612156 0.2735803425 755 30.1600000000 0.2232879400 0.0432806717 0.2232879400 0.0091588544 0.6818400000 954199961 0 1781813248 -1.0833330154 0.3237799406 0.2712551057 756 30.2000000000 0.2210638523 0.0435158346 0.2232879400 0.0091529719 0.6826880000 954201235 0 1783455744 -1.0853949785 0.3212717175 0.2641824484 757 30.2400000000 0.2209060341 0.0437501677 0.2232879400 0.0091488089 0.6831170000 954202509 0 1782153216 -1.0874614716 0.3202183843 0.2574563622 758 30.2800000000 0.2205601484 0.0439834263 0.2232879400 0.0091445168 0.6814880000 954203783 0 1783820288 -1.0899322033 0.3202216923 0.2509914637 759 30.3200000000 0.2238894105 0.0442204566 0.2238894105 0.0091397309 0.7041870000 954205057 0 1782439936 -1.0914248228 0.3261560500 0.2406769693 760 30.3600000000 0.2250523567 0.0444583933 0.2250523567 0.0091478312 0.6802250000 954206331 0 1784074240 -1.0879852772 0.3246165216 0.2351649106 761 30.4000000000 0.2244642526 0.0446949319 0.2250523567 0.0091452051 0.6868320000 954207605 0 1782661120 -1.0875117779 0.3226487339 0.2303716540 762 30.4400000000 0.2233182192 0.0449293456 0.2250523567 0.0091408988 0.6790930000 954208879 0 1784328192 -1.0906355381 0.3214184642 0.2229461372 763 30.4800000000 0.2252801657 0.0451657163 0.2252801657 0.0091422298 0.6791150000 954210153 0 1782820864 -1.0911339521 0.3207324743 0.2150028497 764 30.5200000000 0.2248297185 0.0454008786 0.2252801657 0.0091387736 0.6754580000 954211427 0 1784311808 -1.0901203156 0.3215243220 0.2082865089 765 30.5600000000 0.2270025313 0.0456382664 0.2270025313 0.0091342827 0.6956390000 954212701 0 1782947840 -1.0895465612 0.3225758970 0.1991627812 766 30.6000000000 0.2294764519 0.0458782640 0.2294764519 0.0091320908 0.6755800000 954213975 0 1784582144 -1.0848377943 0.3195961714 0.1950756609 767 30.6400000000 0.2281941175 0.0461159640 0.2294764519 0.0091262898 0.6923250000 954215249 0 1783042048 -1.0847290754 0.3184231818 0.1850223690 768 30.6800000000 0.2284384668 0.0463533630 0.2294764519 0.0091226684 0.6690030000 954216523 0 1781702656 -1.0844135284 0.3173839748 0.1759163439 769 30.7200000000 0.2297264934 0.0465918197 0.2297264934 0.0091220307 0.6891600000 954217797 0 1783185408 -1.0782389641 0.3125622869 0.1730914414 770 30.7600000000 0.2288921475 0.0468285733 0.2297264934 0.0091179510 0.7012300000 954219071 0 1781825536 -1.0772563219 0.3112614453 0.1655353904 771 30.8000000000 0.2295183837 0.0470655251 0.2297264934 0.0091137041 0.6655550000 954220345 0 1783431168 -1.0772701502 0.3098908067 0.1555785984 772 30.8400000000 0.2311562151 0.0473039845 0.2311562151 0.0091092426 0.6802850000 954221619 0 1782083584 -1.0709780455 0.3072372973 0.1493995637 773 30.8800000000 0.2315330058 0.0475423144 0.2315330058 0.0091100678 0.6806420000 954222893 0 1783717888 -1.0654315948 0.3056743443 0.1426626742 774 30.9200000000 0.2295073122 0.0477774113 0.2315330058 0.0091106782 0.6591180000 954224167 0 1782415360 -1.0669592619 0.3045677245 0.1336591840 775 30.9600000000 0.2299490273 0.0480124715 0.2315330058 0.0091084370 0.6576500000 954225441 0 1784082432 -1.0688947439 0.3044199646 0.1254804432 776 31.0000000000 0.2303423434 0.0482474327 0.2315330058 0.0091045903 0.6690270000 954226715 0 1782845440 -1.0701514482 0.3046991825 0.1188177913 777 31.0400000000 0.2320979536 0.0484840485 0.2320979536 0.0091008101 0.6584290000 954227989 0 1784446976 -1.0664767027 0.3053327799 0.1122176796 778 31.0800000000 0.2316187322 0.0487194401 0.2320979536 0.0090976062 0.6599800000 954229263 0 1782972416 -1.0670349598 0.3047616482 0.1046987474 779 31.1200000000 0.2309110612 0.0489533190 0.2320979536 0.0090956173 0.6621980000 954230537 0 1781563392 -1.0667622089 0.3070221245 0.0968652442 780 31.1600000000 0.2347632349 0.0491915368 0.2347632349 0.0091042121 0.6934450000 954231811 0 1783177216 -1.0666155815 0.3164713979 0.0876422450 781 31.2000000000 0.2352328300 0.0494297459 0.2352328300 0.0090994641 0.6791980000 954233085 0 1781944320 -1.0616153479 0.3173498809 0.0798850954 782 31.2400000000 0.2349924147 0.0496670383 0.2352328300 0.0090952075 0.6655780000 954234359 0 1783566336 -1.0575616360 0.3153359890 0.0732635483 783 31.2800000000 0.2359259725 0.0499049169 0.2359259725 0.0090912354 0.6871840000 954235633 0 1782407168 -1.0528668165 0.3162462115 0.0688094571 784 31.3200000000 0.2344155610 0.0501402621 0.2359259725 0.0090855912 0.6676090000 954236907 0 1784074240 -1.0521261692 0.3145254552 0.0600444973 785 31.3600000000 0.2347528487 0.0503754374 0.2359259725 0.0090815309 0.6711880000 954238181 0 1782693888 -1.0531176329 0.3131077588 0.0542145483 786 31.4000000000 0.2373828441 0.0506133603 0.2373828441 0.0090788622 0.7075970000 954239455 0 1784311808 -1.0494327545 0.3110525310 0.0497892313 787 31.4400000000 0.2374597937 0.0508507764 0.2374597937 0.0090738655 0.6713150000 954240729 0 1782964224 -1.0463204384 0.3082542121 0.0458646081 788 31.4800000000 0.2366453707 0.0510865563 0.2374597937 0.0090684403 0.6688210000 954242003 0 1784582144 -1.0438078642 0.3070931137 0.0407661013 789 31.5200000000 0.2362592816 0.0513212492 0.2374597937 0.0090631113 0.6666030000 954243277 0 1783185408 -1.0422146320 0.3065385520 0.0344513543 790 31.5600000000 0.2358090132 0.0515547781 0.2374597937 0.0090575599 0.6643120000 954244551 0 1781944320 -1.0403661728 0.3058137596 0.0312468819 791 31.6000000000 0.2347566187 0.0517863859 0.2374597937 0.0090520481 0.6622880000 954245825 0 1783582720 -1.0412392616 0.3066094220 0.0243254174 792 31.6400000000 0.2365723848 0.0520197016 0.2374597937 0.0090483634 0.6593500000 954247099 0 1782165504 -1.0416094065 0.3055256307 0.0188178644 793 31.6800000000 0.2375084013 0.0522536092 0.2375084013 0.0090430828 0.6547980000 954248373 0 1783947264 -1.0389789343 0.3033561409 0.0175651610 794 31.7200000000 0.2368159294 0.0524860554 0.2375084013 0.0090383638 0.7007010000 954249647 0 1782566912 -1.0407279730 0.3037065268 0.0097300541 795 31.7600000000 0.2376128882 0.0527189194 0.2376128882 0.0090339416 0.6561780000 954250921 0 1784074240 -1.0420861244 0.3036241233 0.0044099619 796 31.8000000000 0.2387502491 0.0529526271 0.2387502491 0.0090291537 0.6582540000 954252195 0 1782661120 -1.0395162106 0.3025443554 0.0014995632 797 31.8400000000 0.2385484874 0.0531854951 0.2387502491 0.0090235842 0.6562280000 954253469 0 1784217600 -1.0376687050 0.3020098805 -0.0029556744 798 31.8800000000 0.2386295050 0.0534178811 0.2387502491 0.0090180548 0.6614220000 954254743 0 1782800384 -1.0381540060 0.2996250391 -0.0062619373 799 31.9200000000 0.2412874103 0.0536530119 0.2412874103 0.0090220441 0.6788850000 954256017 0 1784438784 -1.0413954258 0.3075114787 -0.0153612951 800 31.9600000000 0.2416919321 0.0538880606 0.2416919321 0.0090225284 0.6545540000 954257291 0 1783054336 -1.0429677963 0.3028064072 -0.0206226651 801 32.0000000000 0.2418113649 0.0541226715 0.2418113649 0.0090257829 0.6674780000 954258565 0 1781702656 -1.0376582146 0.2920839787 -0.0177816823 802 32.0400000000 0.2408774793 0.0543555328 0.2418113649 0.0090298279 0.6525620000 954259839 0 1783296000 -1.0376584530 0.2903918922 -0.0222465936 803 32.0800000000 0.2403181493 0.0545871176 0.2418113649 0.0090305423 0.6514980000 954261113 0 1781817344 -1.0391087532 0.2909914851 -0.0298302136 804 32.1199999990 0.2415330559 0.0548196375 0.2418113649 0.0090266539 0.6514860000 954262387 0 1783439360 -1.0390869379 0.2890163362 -0.0330249593 805 32.1600000000 0.2428621799 0.0550532307 0.2428621799 0.0090254421 0.6554530000 954263661 0 1782026240 -1.0395504236 0.2863437831 -0.0379690044 806 32.2000000000 0.2419387400 0.0552850986 0.2428621799 0.0090379657 0.6456350000 954264935 0 1783709696 -1.0364598036 0.2884445786 -0.0551073998 807 32.2400000000 0.2416077554 0.0555159817 0.2428621799 0.0090371771 0.6528470000 954266209 0 1782292480 -1.0351879597 0.2897060215 -0.0605288856 808 32.2800000000 0.2398020774 0.0557440585 0.2428621799 0.0090368817 0.6479960000 954267483 0 1783930880 -1.0359412432 0.2940337062 -0.0691018850 809 32.3200000000 0.2411203235 0.0559732010 0.2428621799 0.0090332161 0.6489570000 954268757 0 1782546432 -1.0389300585 0.2946670055 -0.0767129138 810 32.3600000000 0.2454858571 0.0562071672 0.2454858571 0.0090404175 0.7157110000 954270031 0 1784217600 -1.0426523685 0.2947598100 -0.0815645158 811 32.4000000000 0.2463620454 0.0564416369 0.2463620454 0.0090364110 0.6589930000 954271305 0 1782915072 -1.0434484482 0.2894467711 -0.0876021087 812 32.4399999990 0.2462320924 0.0566753690 0.2463620454 0.0090388257 0.6779240000 954272579 0 1784455168 -1.0428820848 0.2814399898 -0.0887130201 813 32.4800000000 0.2470198274 0.0569094950 0.2470198274 0.0090714979 0.7029620000 954273853 0 1783054336 -1.0440671444 0.2925494313 -0.1009762585 814 32.5200000000 0.2482602745 0.0571445696 0.2482602745 0.0090793061 0.7024720000 954275127 0 1781534720 -1.0508050919 0.3042706549 -0.1178679392 815 32.5600000000 0.2485414892 0.0573794125 0.2485414892 0.0091032129 0.6908590000 954276401 0 1783328768 -1.0526077747 0.2954699695 -0.1199331880 816 32.6000000000 0.2476977259 0.0576126457 0.2485414892 0.0090983232 0.6844330000 954277675 0 1781927936 -1.0521514416 0.2912065387 -0.1241905540 817 32.6400000000 0.2465213984 0.0578438682 0.2485414892 0.0090932344 0.6879510000 954278949 0 1783549952 -1.0544987917 0.2902761102 -0.1316788197 818 32.6800000000 0.2471530586 0.0580752975 0.2485414892 0.0090890714 0.6939510000 954280223 0 1782198272 -1.0588372946 0.2880491614 -0.1398417205 819 32.7200000000 0.2493330836 0.0583088235 0.2493330836 0.0090867418 0.6935790000 954281497 0 1783963648 -1.0612231493 0.2835132182 -0.1452019513 820 32.7599999990 0.2484768778 0.0585407358 0.2493330836 0.0090821539 0.7035310000 954282771 0 1782689792 -1.0615901947 0.2832858264 -0.1516911387 821 32.7999999990 0.2484287471 0.0587720244 0.2493330836 0.0090782074 0.7096880000 954284045 0 1784336384 -1.0643393993 0.2841520905 -0.1601768881 822 32.8400000000 0.2493844032 0.0590039130 0.2493844032 0.0090739587 0.7060080000 954285319 0 1783062528 -1.0671901703 0.2831884027 -0.1670872718 823 32.8800000000 0.2493964434 0.0592352526 0.2493964434 0.0090698589 0.7060900000 954286593 0 1781575680 -1.0686602592 0.2840139568 -0.1734863967 824 32.9200000000 0.2492556125 0.0594658599 0.2493964434 0.0090653549 0.7103140000 954287867 0 1783304192 -1.0724332333 0.2853359878 -0.1827329546 825 32.9600000000 0.2520483136 0.0596992931 0.2520483136 0.0090656979 0.7133060000 954289141 0 1781952512 -1.0732556581 0.2821038067 -0.1872928143 826 33.0000000000 0.2510083020 0.0599309021 0.2520483136 0.0090609784 0.7553770000 954290415 0 1783717888 -1.0722087622 0.2822237611 -0.1928869784 827 33.0400000000 0.2521236837 0.0601632997 0.2521236837 0.0090568738 0.7220990000 954291689 0 1782292480 -1.0758140087 0.2812970281 -0.2024302185 828 33.0800000000 0.2536307573 0.0603969560 0.2536307573 0.0090621581 0.7327720000 954292963 0 1783930880 -1.0772136450 0.2730525732 -0.2050834298 829 33.1199999990 0.2519417107 0.0606280112 0.2536307573 0.0090636233 0.7189180000 954294237 0 1782546432 -1.0754268169 0.2730320096 -0.2106865346 830 33.1600000000 0.2547770143 0.0608619257 0.2547770143 0.0090818370 0.7543790000 954295511 0 1784328192 -1.0844724178 0.2806734741 -0.2238896489 831 33.2000000000 0.2549982071 0.0610955433 0.2549982071 0.0090780253 0.7288660000 954296785 0 1782689792 -1.0847375393 0.2773225904 -0.2286416739 832 33.2400000000 0.2557997704 0.0613295628 0.2557997704 0.0090748453 0.7265830000 954298059 0 1784438784 -1.0817734003 0.2736920118 -0.2306882143 833 33.2800000000 0.2548725307 0.0615619073 0.2557997704 0.0090728614 0.7359510000 954299333 0 1783087104 -1.0808099508 0.2722835839 -0.2378475219 834 33.3200000000 0.2545244694 0.0617932773 0.2557997704 0.0090710318 0.7321760000 954300607 0 1784709120 -1.0835510492 0.2704527080 -0.2450185269 835 33.3600000000 0.2545022666 0.0620240665 0.2557997704 0.0090687111 0.7348280000 954301881 0 1783345152 -1.0855141878 0.2702114284 -0.2535781562 836 33.4000000000 0.2546398342 0.0622544682 0.2557997704 0.0090663083 0.7351920000 954303155 0 1781772288 -1.0862138271 0.2711948752 -0.2615007162 837 33.4399999990 0.2557099164 0.0624855977 0.2557997704 0.0090631990 0.7366350000 954304429 0 1783582720 -1.0861397982 0.2705920935 -0.2683565617 838 33.4800000000 0.2567107677 0.0627173700 0.2567107677 0.0090594026 0.7390530000 954305703 0 1782431744 -1.0853803158 0.2683489323 -0.2748927176 839 33.5200000000 0.2566966116 0.0629485729 0.2567107677 0.0090569713 0.7355080000 954306977 0 1784184832 -1.0832773447 0.2693670094 -0.2857003510 840 33.5600000000 0.2590936422 0.0631820790 0.2590936422 0.0090540963 0.7810130000 954308251 0 1782931456 -1.0771698952 0.2655872405 -0.2912631333 841 33.6000000000 0.2592093050 0.0634151672 0.2592093050 0.0090501941 0.7325090000 954309525 0 1782067200 -1.0734519958 0.2626333833 -0.2977876663 842 33.6400000000 0.2591409385 0.0636476206 0.2592093050 0.0090517518 0.7301740000 954310799 0 1783840768 -1.0721026659 0.2612502575 -0.3064286709 843 33.6800000000 0.2608438134 0.0638815426 0.2608438134 0.0090656789 0.7282440000 954312073 0 1782685696 -1.0652173758 0.2592813671 -0.3229859173 844 33.7200000000 0.2604390681 0.0641144306 0.2608438134 0.0090630615 0.7261610000 954313347 0 1784311808 -1.0631135702 0.2577735186 -0.3325028121 845 33.7599999990 0.2597742379 0.0643459807 0.2608438134 0.0090631652 0.7258110000 954314621 0 1782943744 -1.0629774332 0.2592362165 -0.3429823220 846 33.7999999990 0.2637110353 0.0645816368 0.2637110353 0.0090733744 0.7549500000 954315895 0 1781817344 -1.0632383823 0.2686028779 -0.3549406528 847 33.8400000000 0.2642142475 0.0648173305 0.2642142475 0.0090703537 0.7569020000 954317169 0 1783570432 -1.0587309599 0.2704542875 -0.3655534089 848 33.8800000000 0.2650378048 0.0650534396 0.2650378048 0.0090698904 0.7337970000 954318443 0 1782280192 -1.0501408577 0.2694061697 -0.3735694885 849 33.9200000000 0.2648580372 0.0652887807 0.2650378048 0.0090662103 0.7141510000 954319717 0 1784074240 -1.0482765436 0.2651072741 -0.3817584515 850 33.9600000000 0.2663203180 0.0655252884 0.2663203180 0.0090613774 0.7267770000 954320991 0 1782689792 -1.0410368443 0.2639114857 -0.3913372755 851 34.0000000000 0.2669332623 0.0657619605 0.2669332623 0.0090561690 0.7249600000 954322265 0 1784344576 -1.0339016914 0.2615079582 -0.3990015984 852 34.0400000000 0.2676033378 0.0659988635 0.2676033378 0.0090517701 0.7283280000 954323539 0 1783042048 -1.0305956602 0.2619946003 -0.4087689519 853 34.0800000000 0.2682535946 0.0662359734 0.2682535946 0.0090470938 0.7214930000 954324813 0 1781555200 -1.0251884460 0.2645380199 -0.4186781943 854 34.1199999990 0.2678690255 0.0664720777 0.2682535946 0.0090430541 0.7408750000 954326087 0 1783201792 -1.0221414566 0.2638801038 -0.4266822934 855 34.1600000000 0.2694966197 0.0667095333 0.2694966197 0.0090384631 0.7133260000 954327361 0 1781833728 -1.0179758072 0.2626004815 -0.4351357818 856 34.2000000000 0.2700664699 0.0669470998 0.2700664699 0.0090354610 0.7106950000 954328635 0 1783422976 -1.0112284422 0.2626262903 -0.4427628219 857 34.2400000000 0.2694465816 0.0671833886 0.2700664699 0.0090304068 0.6929560000 954329909 0 1782075392 -1.0073665380 0.2602809370 -0.4501791298 858 34.2800000000 0.2700152099 0.0674197893 0.2700664699 0.0090259454 0.6910810000 954331183 0 1783709696 -1.0025498867 0.2582911253 -0.4563619494 859 34.3200000000 0.2694112957 0.0676549366 0.2700664699 0.0090245614 0.6976410000 954332457 0 1782280192 -0.9983992577 0.2597003877 -0.4655685723 860 34.3600000000 0.2699637413 0.0678901794 0.2700664699 0.0090204038 0.6873750000 954333731 0 1783820288 -0.9944485426 0.2601627111 -0.4746548533 861 34.4000000000 0.2713104784 0.0681264399 0.2713104784 0.0090163191 0.7433880000 954335005 0 1782456320 -0.9894726872 0.2584539354 -0.4820642471 862 34.4400000000 0.2719095349 0.0683628472 0.2719095349 0.0090118866 0.6858810000 954336279 0 1784090624 -0.9849867225 0.2574988008 -0.4894146323 863 34.4800000000 0.2716625929 0.0685984205 0.2719095349 0.0090071563 0.6824990000 954337553 0 1782661120 -0.9793819785 0.2583456635 -0.4966682792 864 34.5200000000 0.2718739510 0.0688336931 0.2719095349 0.0090031560 0.6794330000 954338827 0 1784344576 -0.9755009413 0.2606805265 -0.5056608319 865 34.5600000000 0.2744425237 0.0690713912 0.2744425237 0.0090034279 0.6779460000 954340101 0 1782943744 -0.9705675840 0.2574168742 -0.5122280717 866 34.6000000000 0.2765361667 0.0693109579 0.2765361667 0.0090011473 0.6756180000 954341375 0 1781518336 -0.9674916863 0.2483056784 -0.5154196024 867 34.6400000000 0.2748398185 0.0695480154 0.2765361667 0.0090112799 0.6683400000 954342649 0 1783332864 -0.9627484083 0.2436441332 -0.5311189890 868 34.6800000000 0.2750348449 0.0697847514 0.2765361667 0.0090097671 0.6732690000 954343923 0 1781944320 -0.9568210840 0.2417534739 -0.5377838612 869 34.7200000000 0.2745904326 0.0700204311 0.2765361667 0.0090090347 0.6643700000 954345197 0 1783590912 -0.9545842409 0.2414029837 -0.5456141233 870 34.7600000000 0.2756469250 0.0702567834 0.2765361667 0.0090081732 0.6594010000 954346471 0 1782099968 -0.9501428604 0.2410228252 -0.5547370911 871 34.8000000000 0.2771992385 0.0704943752 0.2771992385 0.0090051515 0.6564770000 954347745 0 1783828480 -0.9441906810 0.2389648706 -0.5603920817 872 34.8400000000 0.2768709362 0.0707310455 0.2771992385 0.0090054597 0.6562040000 954349019 0 1782415360 -0.9420387745 0.2368608713 -0.5669801831 873 34.8800000000 0.2794112265 0.0709700836 0.2794112265 0.0090150298 0.6780910000 954350293 0 1784098816 -0.9349277616 0.2437735349 -0.5763443708 874 34.9200000000 0.2780339420 0.0712069987 0.2794112265 0.0090108893 0.6478480000 954351567 0 1782550528 -0.9333597422 0.2431332767 -0.5841919184 875 34.9600000000 0.2770252228 0.0714422196 0.2794112265 0.0090072206 0.6494910000 954352841 0 1784320000 -0.9285109639 0.2458628714 -0.5917577744 876 35.0000000000 0.2782839835 0.0716783403 0.2794112265 0.0090032829 0.6408700000 954354115 0 1783222272 -0.9238891006 0.2457260042 -0.5990994573 877 35.0400000000 0.2810623944 0.0719170906 0.2810623944 0.0089994531 0.6779550000 954355389 0 1781575680 -0.9156224132 0.2446414232 -0.6039801836 878 35.0800000000 0.2808850706 0.0721550952 0.2810623944 0.0089950690 0.6333650000 954356663 0 1783169024 -0.9115691781 0.2409973145 -0.6093193293 879 35.1200000000 0.2783813179 0.0723897098 0.2810623944 0.0089941786 0.6333700000 954357937 0 1781813248 -0.9080186486 0.2424181998 -0.6183528900 880 35.1600000000 0.2800649405 0.0726257043 0.2810623944 0.0089903547 0.6283640000 954359211 0 1783459840 -0.9004510045 0.2416556180 -0.6255484223 881 35.2000000000 0.2806497514 0.0728618270 0.2810623944 0.0089858604 0.6269190000 954360485 0 1782042624 -0.8954057097 0.2395852804 -0.6301571131 882 35.2400000000 0.2798710167 0.0730965313 0.2810623944 0.0089815225 0.6224850000 954361759 0 1783840768 -0.8884434700 0.2387925833 -0.6377754807 883 35.2800000000 0.2797721326 0.0733305920 0.2810623944 0.0089773102 0.6267330000 954363033 0 1782452224 -0.8860020041 0.2382135987 -0.6465510726 884 35.3200000000 0.2804778218 0.0735649214 0.2810623944 0.0089734257 0.6171820000 954364307 0 1784074240 -0.8783268929 0.2386855781 -0.6531301141 885 35.3600000000 0.2838514149 0.0738025333 0.2838514149 0.0089711513 0.6426210000 954365581 0 1782931456 -0.8714101315 0.2343351245 -0.6587502956 886 35.4000000000 0.2857827544 0.0740417886 0.2857827544 0.0089681172 0.6116640000 954366855 0 1784557568 -0.8701494932 0.2284610569 -0.6651955247 887 35.4400000000 0.2839976251 0.0742784919 0.2857827544 0.0089639511 0.6117030000 954368129 0 1783226368 -0.8670942187 0.2258772552 -0.6746668816 888 35.4800000000 0.2847889066 0.0745155532 0.2857827544 0.0089598906 0.6080850000 954369403 0 1781805056 -0.8624794483 0.2221950889 -0.6821063757 889 35.5200000000 0.2847425640 0.0747520290 0.2857827544 0.0089573266 0.6072450000 954370677 0 1783431168 -0.8582566977 0.2190822512 -0.6892048717 890 35.5600000000 0.2835283875 0.0749866092 0.2857827544 0.0089591378 0.6070290000 954371951 0 1782321152 -0.8535432816 0.2185940146 -0.6975678802 891 35.6000000000 0.2827257812 0.0752197620 0.2857827544 0.0089600904 0.6076680000 954373225 0 1784090624 -0.8475078344 0.2192036808 -0.7087105513 892 35.6400000000 0.2835988402 0.0754533709 0.2857827544 0.0089580462 0.6068290000 954374499 0 1782833152 -0.8435143828 0.2200939208 -0.7178112864 893 35.6800000000 0.2861323059 0.0756892935 0.2861323059 0.0089566455 0.6069020000 954375773 0 1781702656 -0.8372477889 0.2197647840 -0.7252346277 894 35.7200000000 0.2863176763 0.0759248957 0.2863176763 0.0089554063 0.6071950000 954377047 0 1783296000 -0.8293529749 0.2213429511 -0.7317813039 895 35.7600000000 0.2861607373 0.0761597961 0.2863176763 0.0089537974 0.6016770000 954378321 0 1781944320 -0.8236729503 0.2220830619 -0.7416856289 896 35.8000000000 0.2856386900 0.0763935895 0.2863176763 0.0089509659 0.6023140000 954379595 0 1783566336 -0.8183665276 0.2232934386 -0.7496295571 897 35.8400000000 0.2842893600 0.0766253574 0.2863176763 0.0089490832 0.6119580000 954380869 0 1782308864 -0.8106005192 0.2289290577 -0.7598562241 898 35.8800000000 0.2868866920 0.0768595014 0.2868866920 0.0089525468 0.6035910000 954382143 0 1783963648 -0.8033993840 0.2322016656 -0.7674595118 899 35.9200000000 0.2891122401 0.0770956001 0.2891122401 0.0089562686 0.6094690000 954383417 0 1782534144 -0.7967570424 0.2321857512 -0.7756518722 900 35.9600000000 0.2923505604 0.0773347723 0.2923505604 0.0089600344 0.6028330000 954384691 0 1784233984 -0.7886814475 0.2276761234 -0.7814147472 901 36.0000000000 0.2929273844 0.0775740538 0.2929273844 0.0089592094 0.6103760000 954385965 0 1782964224 -0.7855668068 0.2217115164 -0.7867822647 902 36.0400000000 0.2913753390 0.0778110840 0.2929273844 0.0089581907 0.5915610000 954387239 0 1781518336 -0.7785605788 0.2205307782 -0.7979639769 903 36.0800000000 0.2938419580 0.0780503209 0.2938419580 0.0089613557 0.5984300000 954388513 0 1783312384 -0.7735658288 0.2191750109 -0.8070102334 904 36.1200000000 0.2941787541 0.0782894010 0.2941787541 0.0089594712 0.5939830000 954389787 0 1781944320 -0.7610890269 0.2184148729 -0.8043587804 905 36.1600000000 0.2954961061 0.0785294084 0.2954961061 0.0089915299 0.5929630000 954391061 0 1783566336 -0.7373270988 0.2187503576 -0.8306907415 906 36.2000000000 0.2937986851 0.0787670125 0.2954961061 0.0089879124 0.5773280000 954392335 0 1782185984 -0.7291871905 0.2149309814 -0.8373165131 907 36.2400000000 0.2941763699 0.0790045090 0.2954961061 0.0089849370 0.5849660000 954393609 0 1783803904 -0.7229176760 0.2101544142 -0.8426929712 908 36.2800000000 0.2972910106 0.0792449126 0.2972910106 0.0089933611 0.6047020000 954394883 0 1782456320 -0.7200367451 0.2138658017 -0.8512437940 909 36.3200000000 0.2951411307 0.0794824222 0.2972910106 0.0089904534 0.5802770000 954396157 0 1784074240 -0.7097868323 0.2150888741 -0.8542863727 910 36.3600000000 0.2960420847 0.0797203999 0.2972910106 0.0089892644 0.5859390000 954397431 0 1782419456 -0.7011230588 0.2150559574 -0.8560805917 911 36.4000000000 0.2970198691 0.0799589284 0.2972910106 0.0089871469 0.5839900000 954398705 0 1784090624 -0.6955252886 0.2137204558 -0.8581880331 912 36.4400000000 0.2964237928 0.0801962802 0.2972910106 0.0089842698 0.6360770000 954399979 0 1782661120 -0.6877395511 0.2135942578 -0.8636994958 913 36.4800000000 0.2969648540 0.0804337047 0.2972910106 0.0089820033 0.5922320000 954401253 0 1784217600 -0.6804633141 0.2130514830 -0.8686722517 914 36.5200000000 0.2975414991 0.0806712406 0.2975414991 0.0089789518 0.5932260000 954402527 0 1782800384 -0.6748059392 0.2105025053 -0.8729806542 915 36.5600000000 0.2971313894 0.0809078091 0.2975414991 0.0089757078 0.5897080000 954403801 0 1784471552 -0.6665830016 0.2100259662 -0.8757619262 916 36.6000000000 0.2957740128 0.0811423792 0.2975414991 0.0089725563 0.6019670000 954405075 0 1783074816 -0.6574375629 0.2107509822 -0.8798911572 917 36.6400000000 0.2974807918 0.0813782989 0.2975414991 0.0089689249 0.5972630000 954406349 0 1781518336 -0.6508371830 0.2078879476 -0.8836488128 918 36.6800000000 0.2977810800 0.0816140318 0.2977810800 0.0089663067 0.5961450000 954407623 0 1783058432 -0.6448178887 0.2036324441 -0.8881703615 919 36.7200000000 0.2958828509 0.0818471861 0.2977810800 0.0089626172 0.5983260000 954408897 0 1781833728 -0.6372949481 0.2037672698 -0.8912375569 920 36.7600000000 0.2951121628 0.0820789959 0.2977810800 0.0089583763 0.5976010000 954410171 0 1783439360 -0.6307218671 0.2042134553 -0.8964290023 921 36.8000000000 0.3005056083 0.0823161583 0.3005056083 0.0089579532 0.6685400000 954411445 0 1781964800 -0.6210560799 0.2122309655 -0.9013479948 922 36.8400000000 0.3014719486 0.0825538544 0.3014719486 0.0089592691 0.6016640000 954412719 0 1783422976 -0.6116318703 0.2085403949 -0.9042548537 923 36.8800000000 0.3007779419 0.0827902835 0.3014719486 0.0089546846 0.6036980000 954413993 0 1782202368 -0.6040776968 0.2055987567 -0.9056522846 924 36.9200000000 0.3009609580 0.0830263990 0.3014719486 0.0089526075 0.6225300000 954415267 0 1783836672 -0.5926197767 0.2092926800 -0.9122655392 925 36.9600000000 0.3006061316 0.0832616203 0.3014719486 0.0089530199 0.6062730000 954416541 0 1782431744 -0.5818127990 0.2086755633 -0.9172003865 926 37.0000000000 0.3006965816 0.0834964313 0.3014719486 0.0089565105 0.6077530000 954417815 0 1784082432 -0.5655238032 0.2100932300 -0.9245639443 927 37.0400000000 0.3003705442 0.0837303839 0.3014719486 0.0089560936 0.6071400000 954419089 0 1782702080 -0.5536010265 0.2105718702 -0.9282989502 928 37.0800000000 0.3011792600 0.0839647039 0.3014719486 0.0089525263 0.6063740000 954420363 0 1784225792 -0.5453229547 0.2069885731 -0.9311791658 929 37.1200000000 0.3011178970 0.0841984533 0.3014719486 0.0089486847 0.6527610000 954421637 0 1782956032 -0.5359719992 0.2038796693 -0.9346287847 930 37.1600000000 0.3006998897 0.0844312505 0.3014719486 0.0089451366 0.6037880000 954422911 0 1784463360 -0.5256631374 0.2031684667 -0.9379819632 931 37.2000000000 0.3011486232 0.0846640296 0.3014719486 0.0089411730 0.6058030000 954424185 0 1783209984 -0.5177335143 0.2010514438 -0.9420751333 932 37.2400000000 0.3008560240 0.0848959953 0.3014719486 0.0089386797 0.6069810000 954425459 0 1781436416 -0.5077291727 0.2022863626 -0.9438427687 933 37.2800000000 0.3009365201 0.0851275500 0.3014719486 0.0089362388 0.5997920000 954426733 0 1783050240 -0.4965291917 0.2039593905 -0.9478879571 934 37.3200000000 0.3013989329 0.0853591039 0.3014719486 0.0089345227 0.5942050000 954428007 0 1781694464 -0.4856090248 0.2055510283 -0.9520210624 935 37.3600000000 0.3016874194 0.0855904711 0.3016874194 0.0089341145 0.5908510000 954429281 0 1783201792 -0.4746591747 0.2061803490 -0.9541985989 936 37.4000000000 0.3023337126 0.0858220344 0.3023337126 0.0089316117 0.5882360000 954430555 0 1781706752 -0.4643804431 0.2048559636 -0.9546256661 937 37.4400000000 0.3027985394 0.0860535995 0.3027985394 0.0089286209 0.5871040000 954431829 0 1783328768 -0.4529965520 0.2035299689 -0.9557604790 938 37.4800000000 0.3025685847 0.0862844257 0.3027985394 0.0089244097 0.5864010000 954433103 0 1781915648 -0.4440220892 0.2004139125 -0.9578238726 939 37.5200000000 0.2997914553 0.0865118027 0.3027985394 0.0089206314 0.5870810000 954434377 0 1783582720 -0.4323103428 0.2006398737 -0.9606961012 940 37.5600000000 0.2988539040 0.0867376986 0.3027985394 0.0089176040 0.5940210000 954435651 0 1782202368 -0.4215292037 0.2017488033 -0.9613999724 941 37.6000000000 0.2995675802 0.0869638727 0.3027985394 0.0089135096 0.5877310000 954436925 0 1783820288 -0.4122464359 0.2001645565 -0.9630790353 942 37.6400000000 0.3006511629 0.0871907170 0.3027985394 0.0089098399 0.5890400000 954438199 0 1782292480 -0.4031739533 0.1981559545 -0.9655644894 943 37.6800000000 0.3012061119 0.0874176686 0.3027985394 0.0089076550 0.5908330000 954439473 0 1783930880 -0.3926449418 0.1980401427 -0.9671453834 944 37.7200000000 0.3014262617 0.0876443727 0.3027985394 0.0089040062 0.5950890000 954440747 0 1782439936 -0.3847165406 0.1968212426 -0.9669508338 945 37.7600000000 0.3021096587 0.0878713201 0.3027985394 0.0089007663 0.5937040000 954442021 0 1783963648 -0.3739221394 0.1958829015 -0.9668911695 946 37.8000000000 0.3021567464 0.0880978374 0.3027985394 0.0088975654 0.5970530000 954443295 0 1782439936 -0.3637279868 0.1941678673 -0.9676147103 947 37.8400000000 0.3020573854 0.0883237715 0.3027985394 0.0088986772 0.6234740000 954444569 0 1783963648 -0.3533297181 0.1920890659 -0.9699587226 948 37.8800000000 0.3022471964 0.0885494291 0.3027985394 0.0088981489 0.6034710000 954445843 0 1782407168 -0.3434862196 0.1899226308 -0.9714448452 949 37.9200000000 0.3010850847 0.0887733866 0.3027985394 0.0088976547 0.5979110000 954447117 0 1783947264 -0.3330501616 0.1887217760 -0.9739941359 950 37.9600000000 0.3008125722 0.0889965857 0.3027985394 0.0088950215 0.5966900000 954448391 0 1782439936 -0.3229812384 0.1881382614 -0.9759945273 951 38.0000000000 0.3014963865 0.0892200345 0.3027985394 0.0088920388 0.5938570000 954449665 0 1783947264 -0.3138557673 0.1868775636 -0.9772568345 952 38.0400000000 0.3016567230 0.0894431823 0.3027985394 0.0088903613 0.5915920000 954450939 0 1782329344 -0.3037690520 0.1846020669 -0.9795142412 953 38.0800000000 0.3015046418 0.0896657022 0.3027985394 0.0088884436 0.5871970000 954452213 0 1783930880 -0.2940356135 0.1838767827 -0.9806981683 954 38.1200000000 0.3013309836 0.0898875736 0.3027985394 0.0088858359 0.5889650000 954453487 0 1782439936 -0.2834217250 0.1828404963 -0.9824609756 955 38.1600000000 0.2996312976 0.0901072005 0.3027985394 0.0088842649 0.5797170000 954454761 0 1783947264 -0.2733487189 0.1821114272 -0.9836724401 956 38.2000000000 0.2992940843 0.0903260152 0.3027985394 0.0088810535 0.5781430000 954456035 0 1782419456 -0.2617038786 0.1812691092 -0.9856595397 957 38.2400000000 0.2988274395 0.0905438850 0.3027985394 0.0088770906 0.5730180000 954457309 0 1783963648 -0.2502274513 0.1803632230 -0.9880898595 958 38.2800000000 0.2990400493 0.0907615220 0.3027985394 0.0088731397 0.5723780000 954458583 0 1782550528 -0.2409256846 0.1787734181 -0.9904485345 959 38.3200000000 0.2971436381 0.0909767275 0.3027985394 0.0088696828 0.5687430000 954459857 0 1784217600 -0.2300831228 0.1795138419 -0.9923988581 960 38.3600000000 0.2955367863 0.0911898109 0.3027985394 0.0088684940 0.5692710000 954461131 0 1782808576 -0.2171393931 0.1817617565 -0.9936440587 961 38.4000000000 0.2999440432 0.0914070370 0.3027985394 0.0088744190 0.5647350000 954462405 0 1784455168 -0.2078789026 0.1799367666 -0.9947801828 962 38.4400000000 0.3015408814 0.0916254713 0.3027985394 0.0088731222 0.5658870000 954463679 0 1783054336 -0.1979859322 0.1789774150 -0.9960001111 963 38.4800000000 0.3040356636 0.0918460426 0.3040356636 0.0088760483 0.5750820000 954464953 0 1781555200 -0.1877376586 0.1791377515 -1.0009232759 964 38.5200000000 0.3046588004 0.0920668028 0.3046588004 0.0088762090 0.5724030000 954466227 0 1783185408 -0.1778943390 0.1776457578 -1.0020262003 965 38.5600000000 0.3046812415 0.0922871286 0.3046812415 0.0088735405 0.6192370000 954467501 0 1781899264 -0.1672104150 0.1752382815 -1.0053861141 966 38.6000000000 0.3022212386 0.0925044517 0.3046812415 0.0088695827 0.5524630000 954468775 0 1783693312 -0.1571763307 0.1707497686 -1.0052344799 967 38.6400000000 0.2995162308 0.0927185280 0.3046812415 0.0088670180 0.5487200000 954470049 0 1782435840 -0.1463465989 0.1669003218 -1.0051400661 968 38.6800000000 0.2978002429 0.0929303893 0.3046812415 0.0088637566 0.5450510000 954471323 0 1784217600 -0.1366869658 0.1632408947 -1.0061028004 969 38.7200000000 0.2967167199 0.0931406951 0.3046812415 0.0088601866 0.5442350000 954472597 0 1782796288 -0.1269461960 0.1619172990 -1.0061503649 970 38.7600000000 0.2967357635 0.0933505869 0.3046812415 0.0088564514 0.5369860000 954473871 0 1784582144 -0.1205593571 0.1596171707 -1.0071625710 971 38.8000000000 0.2966461778 0.0935599541 0.3046812415 0.0088532197 0.5422470000 954475145 0 1783234560 -0.1112537831 0.1593560129 -1.0080486536 972 38.8400000000 0.2979426086 0.0937702244 0.3046812415 0.0088540347 0.5344280000 954476419 0 1782169600 -0.1025315970 0.1603419334 -1.0085580349 973 38.8800000000 0.3000724614 0.0939822513 0.3046812415 0.0088624824 0.5312290000 954477693 0 1783951360 -0.0935779661 0.1621506065 -1.0085779428 974 38.9200000000 0.3020814955 0.0941959056 0.3046812415 0.0088693978 0.5662140000 954478967 0 1782788096 -0.0862578601 0.1619804502 -1.0079009533 975 38.9600000000 0.3026091158 0.0944096627 0.3046812415 0.0088681420 0.5292100000 954480241 0 1784475648 -0.0782245547 0.1605690867 -1.0066921711 976 39.0000000000 0.3026433289 0.0946230169 0.3046812415 0.0088643902 0.5330200000 954481515 0 1783107584 -0.0713505968 0.1584418118 -1.0047427416 977 39.0400000000 0.3010519445 0.0948343054 0.3046812415 0.0088608183 0.5353850000 954482789 0 1782050816 -0.0608629882 0.1567289084 -1.0059989691 978 39.0800000000 0.2997938395 0.0950438755 0.3046812415 0.0088569006 0.5361410000 954484063 0 1783689216 -0.0516017824 0.1538203508 -1.0040823221 979 39.1200000000 0.2979463637 0.0952511304 0.3046812415 0.0088571693 0.5371810000 954485337 0 1782431744 -0.0431700759 0.1498111635 -1.0034112930 980 39.1600000000 0.2967508137 0.0954567423 0.3046812415 0.0088559385 0.5354620000 954486611 0 1784074240 -0.0319027081 0.1483634263 -1.0041530132 981 39.2000000000 0.2949720025 0.0956601218 0.3046812415 0.0088525182 0.5444990000 954487885 0 1782661120 -0.0202025138 0.1478670686 -1.0041959286 982 39.2400000000 0.2949301600 0.0958630444 0.3046812415 0.0088495028 0.5451370000 954489159 0 1784344576 -0.0148637043 0.1464732438 -1.0048373938 983 39.2800000000 0.2953487635 0.0960659800 0.3046812415 0.0088488754 0.5546460000 954490433 0 1783169024 -0.0060551693 0.1456215978 -1.0083547831 984 39.3200000000 0.3052383363 0.0962785536 0.3052383363 0.0088646089 0.5850830000 954491707 0 1781813248 0.0048213992 0.1551083177 -1.0276126862 985 39.3600000000 0.3035596609 0.0964889912 0.3052383363 0.0088624557 0.5468560000 954492981 0 1783447552 0.0120197162 0.1508921832 -1.0278370380 986 39.4000000000 0.3017467856 0.0966971634 0.3052383363 0.0088589039 0.5472880000 954494255 0 1782312960 0.0201340150 0.1478804052 -1.0257637501 987 39.4400000000 0.3004966080 0.0969036472 0.3052383363 0.0088557612 0.5423170000 954495529 0 1783955456 0.0297179986 0.1454659551 -1.0245711803 988 39.4800000000 0.2995184958 0.0971087229 0.3052383363 0.0088522687 0.5477070000 954496803 0 1782583296 0.0402913839 0.1436422169 -1.0245988369 989 39.5200000000 0.2980627418 0.0973119120 0.3052383363 0.0088488184 0.5350170000 954498077 0 1784336384 0.0490277261 0.1412949562 -1.0255270004 990 39.5600000000 0.2968256176 0.0975134410 0.3052383363 0.0088452485 0.5329150000 954499351 0 1783066624 0.0586938784 0.1402228475 -1.0260182619 991 39.6000000000 0.2958860397 0.0977136152 0.3052383363 0.0088422126 0.5309770000 954500625 0 1784627200 0.0685169771 0.1411556900 -1.0237733126 992 39.6400000000 0.2946289480 0.0979121185 0.3052383363 0.0088399047 0.5343880000 954501899 0 1783336960 0.0782642886 0.1423092335 -1.0220409632 993 39.6800000000 0.2941799164 0.0981097699 0.3052383363 0.0088417916 0.5246830000 954503173 0 1782202368 0.0875772312 0.1439680606 -1.0186932087 994 39.7200000000 0.2943342328 0.0983071788 0.3052383363 0.0088438328 0.5499620000 954504447 0 1783971840 0.0972485840 0.1448815167 -1.0165504217 995 39.7600000000 0.2958267927 0.0985056910 0.3052383363 0.0088451310 0.5166960000 954505721 0 1782947840 0.1056562066 0.1450052559 -1.0159739256 996 39.8000000000 0.2970975935 0.0987050805 0.3052383363 0.0088428642 0.5130150000 954506995 0 1781710848 0.1152238846 0.1451580077 -1.0150941610 997 39.8400000000 0.2974304855 0.0989044038 0.3052383363 0.0088406627 0.5082910000 954508269 0 1783558144 0.1258165389 0.1455025226 -1.0140385628 998 39.8800000000 0.2985262275 0.0991044257 0.3052383363 0.0088381889 0.5073210000 954509543 0 1782157312 0.1349355131 0.1455580145 -1.0135469437 999 39.9200000000 0.2999803126 0.0993055027 0.3052383363 0.0088346457 0.5187790000 954510817 0 1783951360 0.1474433243 0.1511981189 -1.0111299753 1000 39.9600000000 0.3011841476 0.0995073813 0.3052383363 0.0088342373 0.5153440000 954512091 0 1782718464 0.1561494619 0.1516391486 -1.0117301941 1001 40.0000000000 0.2994807661 0.0997071549 0.3052383363 0.0088309495 0.5026830000 954513365 0 1784438784 0.1656541675 0.1486917138 -1.0111496449 1002 40.0400000000 0.2976314723 0.0999046842 0.3052383363 0.0088274413 0.5086190000 954514639 0 1783328768 0.1765218824 0.1479888856 -1.0086903572 1003 40.0800000000 0.2959865928 0.1001001796 0.3052383363 0.0088250481 0.5052050000 954515913 0 1782177792 0.1880619824 0.1486925185 -1.0066812038 1004 40.1200000000 0.2969301939 0.1002962254 0.3052383363 0.0088263504 0.5429280000 954517187 0 1783967744 0.1966846734 0.1486491561 -1.0046706200 1005 40.1600000000 0.2960762680 0.1004910314 0.3052383363 0.0088234193 0.5063930000 954518461 0 1782939648 0.2062850595 0.1480302066 -1.0030821562 1006 40.2000000000 0.2945763469 0.1006839592 0.3052383363 0.0088205974 0.5089300000 954519735 0 1781702656 0.2166380286 0.1487858593 -0.9999871254 1007 40.2400000000 0.2937638164 0.1008756969 0.3052383363 0.0088188678 0.5082990000 954521009 0 1783549952 0.2265228778 0.1493205130 -0.9965739846 1008 40.2800000000 0.2939922810 0.1010672808 0.3052383363 0.0088174333 0.5117570000 954522283 0 1782411264 0.2345953584 0.1491511315 -0.9929530621 1009 40.3200000000 0.2932638228 0.1012577630 0.3052383363 0.0088147988 0.5134430000 954523557 0 1784184832 0.2433381677 0.1489762217 -0.9892048240 1010 40.3600000000 0.2923996449 0.1014470124 0.3052383363 0.0088127239 0.5175120000 954524831 0 1782976512 0.2534552813 0.1487808079 -0.9858002067 1011 40.4000000000 0.2920910716 0.1016355822 0.3052383363 0.0088109807 0.5224790000 954526105 0 1781899264 0.2615354061 0.1478086412 -0.9833080769 1012 40.4400000000 0.2911782265 0.1018228773 0.3052383363 0.0088068959 0.5188310000 954527379 0 1783582720 0.2698025107 0.1454242170 -0.9819552302 1013 40.4800000000 0.2891815007 0.1020078315 0.3052383363 0.0088032044 0.5227780000 954528653 0 1782153216 0.2791720331 0.1441256702 -0.9782362580 1014 40.5200000000 0.2874293625 0.1021906930 0.3052383363 0.0087990955 0.5259980000 954529927 0 1783836672 0.2867578864 0.1424194872 -0.9743750691 1015 40.5600000000 0.2861836553 0.1023719668 0.3052383363 0.0087955508 0.5300160000 954531201 0 1782411264 0.2950740457 0.1397986561 -0.9731329679 1016 40.6000000000 0.2857250869 0.1025524325 0.3052383363 0.0087916381 0.5323540000 954532475 0 1784217600 0.3027105927 0.1371844113 -0.9717194438 1017 40.6400000000 0.2847688496 0.1027316030 0.3052383363 0.0087886977 0.5380550000 954533749 0 1782796288 0.3098621368 0.1367286891 -0.9685262442 1018 40.6800000000 0.2853330970 0.1029109758 0.3052383363 0.0087848211 0.5344960000 954535023 0 1784471552 0.3183573186 0.1371232122 -0.9660508037 1019 40.7200000000 0.2856655717 0.1030903228 0.3052383363 0.0087808485 0.5371540000 954536297 0 1783234560 0.3252471387 0.1378577501 -0.9620938897 1020 40.7600000000 0.2858457565 0.1032694948 0.3052383363 0.0087770499 0.5449840000 954537571 0 1781788672 0.3339735270 0.1380603760 -0.9585372806 1021 40.8000000000 0.2856200039 0.1034480947 0.3052383363 0.0087734569 0.5412910000 954538845 0 1783603200 0.3420790136 0.1382463127 -0.9549261332 1022 40.8400000000 0.2846286595 0.1036253751 0.3052383363 0.0087693363 0.5471610000 954540119 0 1782169600 0.3495039940 0.1381063610 -0.9490422606 1023 40.8800000000 0.2838891745 0.1038015861 0.3052383363 0.0087652022 0.5443840000 954541393 0 1783840768 0.3568598330 0.1377293020 -0.9433847666 1024 40.9200000000 0.2831397355 0.1039767210 0.3052383363 0.0087616727 0.5841660000 954542667 0 1782300672 0.3661401570 0.1377224773 -0.9393569231 1025 40.9600000000 0.2832959592 0.1041516666 0.3052383363 0.0087588884 0.5472900000 954543941 0 1784201216 0.3757742941 0.1384944320 -0.9342333674 1026 41.0000000000 0.2838006914 0.1043267631 0.3052383363 0.0087567964 0.5515760000 954713151 0 1783070720 0.3819800913 0.1388022453 -0.9288234115 1027 41.0400000000 0.2835154831 0.1045012409 0.3052383363 0.0087529010 0.5621230000 954714425 0 1781796864 0.3903505802 0.1371893734 -0.9265135527 1028 41.0800000000 0.2822012305 0.1046741008 0.3052383363 0.0087493942 0.5564980000 954715699 0 1783603200 0.4013736844 0.1376804113 -0.9200133681 1029 41.1200000000 0.2808458507 0.1048453076 0.3052383363 0.0087468636 0.5611120000 954716973 0 1782153216 0.4100105762 0.1363459527 -0.9162129164 1030 41.1600000000 0.2810123563 0.1050163435 0.3052383363 0.0087456709 0.5576540000 954718247 0 1783853056 0.4181985855 0.1361518800 -0.9126429558 1031 41.2000000000 0.2825756967 0.1051885640 0.3052383363 0.0087460073 0.5615980000 954719521 0 1782411264 0.4272608161 0.1369220912 -0.9088707566 1032 41.2400000000 0.2836727202 0.1053615138 0.3052383363 0.0087457083 0.5645960000 954720795 0 1784090624 0.4360022545 0.1378857791 -0.9051409364 1033 41.2800000000 0.2841720283 0.1055346121 0.3052383363 0.0087456973 0.6023860000 954722069 0 1782829056 0.4460470974 0.1394261271 -0.9008167386 1034 41.3200000000 0.2853408158 0.1057085059 0.3052383363 0.0087477713 0.5845860000 954723343 0 1781772288 0.4562820792 0.1411418319 -0.8950818181 1035 41.3600000000 0.2856163085 0.1058823299 0.3052383363 0.0087538270 0.5687390000 954724617 0 1783476224 0.4625023603 0.1412554383 -0.8926034570 1036 41.4000000000 0.2861369848 0.1060563208 0.3052383363 0.0087519765 0.5743920000 954725891 0 1782042624 0.4690949619 0.1393962651 -0.8896912336 1037 41.4400000000 0.2848005593 0.1062286875 0.3052383363 0.0087483406 0.5663470000 954727165 0 1783963648 0.4785710275 0.1371794343 -0.8858646750 1038 41.4800000000 0.2823442519 0.1063983557 0.3052383363 0.0087445638 0.5786470000 954728439 0 1782546432 0.4877577722 0.1366105676 -0.8796470165 1039 41.5200000000 0.2804535329 0.1065658775 0.3052383363 0.0087407475 0.5709540000 954729713 0 1784201216 0.4968065619 0.1364614666 -0.8742119670 1040 41.5600000000 0.2780678272 0.1067307832 0.3052383363 0.0087372659 0.5819530000 954730987 0 1782800384 0.5039359927 0.1369551122 -0.8678277731 1041 41.6000000000 0.2771601081 0.1068945002 0.3052383363 0.0087340317 0.5708670000 954732261 0 1784438784 0.5110535622 0.1361484975 -0.8644468188 1042 41.6400000000 0.2768187523 0.1070575753 0.3052383363 0.0087337238 0.5716790000 954733535 0 1783218176 0.5213369727 0.1376131177 -0.8594216108 1043 41.6800000000 0.2768390477 0.1072203571 0.3052383363 0.0087416287 0.5720020000 954734809 0 1781813248 0.5275572538 0.1390312314 -0.8540875316 1044 41.7200000000 0.2796832621 0.1073855515 0.3052383363 0.0087791138 0.5714330000 954736083 0 1783439360 0.5415930748 0.1423487663 -0.8494308591 1045 41.7600000000 0.2806624770 0.1075513667 0.3052383363 0.0087874797 0.5767980000 954737357 0 1782075392 0.5492425561 0.1434574425 -0.8472055793 1046 41.8000000000 0.2794684172 0.1077157234 0.3052383363 0.0087906463 0.5800480000 954738631 0 1783676928 0.5546411276 0.1433575153 -0.8412621021 1047 41.8400000000 0.2775687575 0.1078779517 0.3052383363 0.0087881003 0.5759060000 954739905 0 1782312960 0.5609996915 0.1414984614 -0.8365259767 1048 41.8800000000 0.2761252522 0.1080384930 0.3052383363 0.0087855962 0.5755170000 954741179 0 1783947264 0.5689405203 0.1408285499 -0.8295239806 1049 41.9200000000 0.2744557858 0.1081971367 0.3052383363 0.0087842907 0.5765570000 954742453 0 1782439936 0.5755774975 0.1396926194 -0.8227978349 1050 41.9600000000 0.2719893157 0.1083531293 0.3052383363 0.0087808862 0.5754350000 954743727 0 1784209408 0.5807458162 0.1379055679 -0.8167704344 1051 42.0000000000 0.2711437345 0.1085080204 0.3052383363 0.0087777928 0.6075470000 954745001 0 1782829056 0.5881262422 0.1363728046 -0.8105147481 1052 42.0400000000 0.2693517208 0.1086609137 0.3052383363 0.0087748444 0.5787670000 954746275 0 1784463360 0.5945978165 0.1360892653 -0.8030469418 1053 42.0800000000 0.2670047879 0.1088112877 0.3052383363 0.0087711691 0.5785600000 954747549 0 1782923264 0.5998190641 0.1354583800 -0.7963407636 1054 42.1200000000 0.2661452889 0.1089605610 0.3052383363 0.0087680195 0.5750770000 954748823 0 1784479744 0.6054478288 0.1349605322 -0.7891336083 1055 42.1600000000 0.2637656331 0.1091072956 0.3052383363 0.0087647806 0.5875940000 954750097 0 1783062528 0.6154532433 0.1328641325 -0.7766761184 1056 42.2000000000 0.2626741827 0.1092527188 0.3052383363 0.0087607826 0.5812780000 954751371 0 1781710848 0.6212180853 0.1319388449 -0.7690218687 1057 42.2400000000 0.2615009844 0.1093967569 0.3052383363 0.0087567035 0.5810570000 954752645 0 1783320576 0.6265105605 0.1313819438 -0.7611017227 1058 42.2800000000 0.2604216039 0.1095395025 0.3052383363 0.0087538234 0.5820880000 954753919 0 1781669888 0.6320114732 0.1315817386 -0.7522885203 1059 42.3200000000 0.2586948872 0.1096803480 0.3052383363 0.0087515288 0.5837830000 954755193 0 1783336960 0.6350513101 0.1320675761 -0.7452624440 1060 42.3600000000 0.2582607567 0.1098205182 0.3052383363 0.0087494041 0.6237950000 954756467 0 1781714944 0.6389405131 0.1325642020 -0.7381290793 1061 42.4000000000 0.2572821975 0.1099595019 0.3052383363 0.0087462235 0.5809270000 954757741 0 1783447552 0.6430702209 0.1326061487 -0.7315175533 1062 42.4400000000 0.2565290034 0.1100975146 0.3052383363 0.0087439520 0.5818640000 954759015 0 1782071296 0.6472721100 0.1331052780 -0.7239506245 1063 42.4800000000 0.2563510239 0.1102351002 0.3052383363 0.0087442341 0.5873530000 954760289 0 1783676928 0.6520287395 0.1338098347 -0.7161490321 1064 42.5200000000 0.2562856972 0.1103723658 0.3052383363 0.0087451529 0.5854770000 954761563 0 1782308864 0.6557799578 0.1340959370 -0.7080939412 1065 42.5600000000 0.2555932999 0.1105087235 0.3052383363 0.0087435534 0.5876470000 954762837 0 1783947264 0.6588317156 0.1342085898 -0.7010586858 1066 42.6000000000 0.2542238533 0.1106435407 0.3052383363 0.0087409912 0.5897780000 954764111 0 1782546432 0.6622884870 0.1342750788 -0.6931499243 1067 42.6400000000 0.2535907924 0.1107775119 0.3052383363 0.0087396528 0.5914670000 954765385 0 1784201216 0.6654519439 0.1343291551 -0.6855823994 1068 42.6800000000 0.2518111467 0.1109095659 0.3052383363 0.0087369461 0.6086050000 954766659 0 1782804480 0.6670919061 0.1340800077 -0.6778936386 1069 42.7200000000 0.2531097233 0.1110425875 0.3052383363 0.0087365449 0.6046040000 954767933 0 1784471552 0.6732450724 0.1381972432 -0.6696361899 1070 42.7600000000 0.2515738308 0.1111739251 0.3052383363 0.0087437684 0.6080030000 954769207 0 1783201792 0.6774203777 0.1410071105 -0.6596143246 1071 42.8000000000 0.2484638095 0.1113021136 0.3052383363 0.0087509245 0.6040240000 954770481 0 1781518336 0.6811697483 0.1398345828 -0.6496888995 1072 42.8400000000 0.2475365400 0.1114291980 0.3052383363 0.0087470625 0.6101270000 954771755 0 1783185408 0.6850571632 0.1412785202 -0.6409639120 1073 42.8800000000 0.2469646633 0.1115555125 0.3052383363 0.0087452135 0.6067390000 954773029 0 1781944320 0.6870492697 0.1416600049 -0.6323814392 1074 42.9200000000 0.2457939535 0.1116805017 0.3052383363 0.0087427961 0.6075020000 954774303 0 1783566336 0.6921089292 0.1428063214 -0.6244989634 1075 42.9600000000 0.2437586784 0.1118033651 0.3052383363 0.0087401538 0.6099780000 954775577 0 1782202368 0.6954471469 0.1432053745 -0.6148733497 1076 43.0000000000 0.2423041016 0.1119246484 0.3052383363 0.0087396240 0.6122700000 954776851 0 1783693312 0.6991447210 0.1446954608 -0.6089692712 1077 43.0400000000 0.2408806086 0.1120443846 0.3052383363 0.0087394097 0.6208040000 954778125 0 1782292480 0.7042175531 0.1450064331 -0.6022118330 1078 43.0800000000 0.2391652912 0.1121623075 0.3052383363 0.0087392666 0.6401560000 954779399 0 1783963648 0.7071099281 0.1449441761 -0.5963197351 1079 43.1200000000 0.2377778590 0.1122787260 0.3052383363 0.0087371904 0.6346830000 954780673 0 1782661120 0.7105715275 0.1453198642 -0.5901408195 1080 43.1600000000 0.2360711396 0.1123933486 0.3052383363 0.0087337558 0.6183140000 954781947 0 1784328192 0.7156966329 0.1455693096 -0.5801722407 1081 43.2000000000 0.2349166423 0.1125066912 0.3052383363 0.0087315785 0.6245770000 954783221 0 1782673408 0.7192905545 0.1451199502 -0.5724289417 1082 43.2400000000 0.2322139889 0.1126173264 0.3052383363 0.0087277652 0.6155960000 954784495 0 1784344576 0.7213848233 0.1445340216 -0.5645398498 1083 43.2800000000 0.2301862091 0.1127258849 0.3052383363 0.0087238124 0.6233610000 954785769 0 1782820864 0.7257722020 0.1435160339 -0.5535613894 1084 43.3200000000 0.2279984951 0.1128322250 0.3052383363 0.0087204105 0.6230390000 954787043 0 1784311808 0.7306479216 0.1423300803 -0.5425643921 1085 43.3600000000 0.2219988853 0.1129328394 0.3052383363 0.0087170618 0.6128100000 954788317 0 1782673408 0.7320290208 0.1385267824 -0.5347884893 1086 43.4000000000 0.2193788737 0.1130308560 0.3052383363 0.0087132179 0.6438300000 954789591 0 1784344576 0.7349562645 0.1369517595 -0.5267985463 1087 43.4400000000 0.2168036252 0.1131263231 0.3052383363 0.0087094415 0.6270730000 954790865 0 1782931456 0.7383837700 0.1357348710 -0.5179638863 1088 43.4800000000 0.2142426521 0.1132192609 0.3052383363 0.0087055650 0.6210800000 954792139 0 1781448704 0.7402089238 0.1337255687 -0.5111225843 1089 43.5200000000 0.2124378234 0.1133103707 0.3052383363 0.0087016424 0.6214300000 954793413 0 1783058432 0.7431562543 0.1323222220 -0.5034250617 1090 43.5600000000 0.2093777210 0.1133985059 0.3052383363 0.0086978917 0.6292500000 954794687 0 1781407744 0.7472980022 0.1309202909 -0.4938622713 1091 43.6000000000 0.2073619217 0.1134846319 0.3052383363 0.0086963970 0.6241970000 954795961 0 1783074816 0.7505080700 0.1298834234 -0.4847062528 1092 43.6400000000 0.2038245052 0.1135673607 0.3052383363 0.0086945287 0.6313580000 954797235 0 1781448704 0.7526560426 0.1285674870 -0.4770869911 1093 43.6800000000 0.2004610598 0.1136468609 0.3052383363 0.0086936866 0.6278240000 954798509 0 1783074816 0.7566345930 0.1268574148 -0.4683527052 1094 43.7200000000 0.1958246976 0.1137219777 0.3052383363 0.0086923569 0.6681820000 954799783 0 1781428224 0.7587991357 0.1248548925 -0.4616451263 1095 43.7600000000 0.1919677854 0.1137934351 0.3052383363 0.0086897572 0.6371790000 954801057 0 1783074816 0.7596952319 0.1224177852 -0.4556979537 1096 43.8000000000 0.1877431124 0.1138609074 0.3052383363 0.0086864974 0.6335120000 954802331 0 1781686272 0.7626236677 0.1201880574 -0.4486252964 1097 43.8400000000 0.1832394004 0.1139241513 0.3052383363 0.0086835983 0.6375830000 954803605 0 1783328768 0.7671481371 0.1183704957 -0.4393886030 1098 43.8800000000 0.1807756275 0.1139850360 0.3052383363 0.0086872313 0.6370370000 954804879 0 1781772288 0.7719866633 0.1174488813 -0.4293727577 1099 43.9200000000 0.1767206788 0.1140421203 0.3052383363 0.0086901385 0.6353310000 954806153 0 1783455744 0.7743973732 0.1156724170 -0.4228210747 1100 43.9600000000 0.1707810462 0.1140937012 0.3052383363 0.0086883839 0.6378970000 954807427 0 1781817344 0.7772350311 0.1128129438 -0.4166353345 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 02:29:18 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 nan 0.4327580000 955056214 0 1770795008 -0.0000000000 0.0000000000 -0.0000000000 2 1305031229.5644419193 0.0543008223 0.0574598331 0.0606188439 0.0575154386 0.6404430000 953937995 0 1765089280 0.0013284727 0.0021752566 0.0096042426 3 1305031229.5966169834 0.0526679009 0.0558625224 0.0606188439 0.0579651978 0.5831240000 953627049 0 1766907904 0.0134093547 -0.0028601678 0.0144226337 4 1305031229.6287899017 0.0486778058 0.0540663432 0.0606188439 0.0479727785 0.6002290000 953629131 0 1768779776 0.0181392469 0.0010273705 0.0209821649 5 1305031229.6646571159 0.0491808131 0.0530892372 0.0606188439 0.0428248784 0.5723700000 953630949 0 1770463232 0.0175234601 -0.0027280499 0.0255012531 6 1305031229.6968429089 0.0501704067 0.0526027655 0.0606188439 0.0383582944 0.5785400000 953633423 0 1772113920 0.0196025092 -0.0042240052 0.0289259385 7 1305031229.7290771008 0.0478473045 0.0519234139 0.0606188439 0.0365901110 0.5965690000 953635177 0 1773858816 0.0188597720 -0.0036055960 0.0342993289 8 1305031229.7648689747 0.0481450669 0.0514511205 0.0606188439 0.0339867748 0.5955120000 953637027 0 1775542272 0.0209880508 -0.0045139603 0.0390044041 9 1305031229.7969229221 0.0485008061 0.0511233078 0.0606188439 0.0320864180 0.5981020000 953638813 0 1777160192 0.0224461090 -0.0050776736 0.0428236090 10 1305031229.8256299496 0.0478119105 0.0507921681 0.0606188439 0.0303557355 0.5972430000 953641847 0 1778970624 0.0242812298 -0.0046882550 0.0481722243 11 1305031229.8630619049 0.0489652716 0.0506260866 0.0606188439 0.0293552630 0.5920690000 953643761 0 1780604928 0.0272096954 -0.0042807739 0.0526911877 12 1305031229.8969380856 0.0514247529 0.0506926421 0.0606188439 0.0295543220 0.5875390000 953645547 0 1782222848 0.0292605869 -0.0042593074 0.0566220507 13 1305031229.9262549877 0.0545423292 0.0509887719 0.0606188439 0.0285052952 0.6176090000 953647301 0 1784033280 0.0354337804 -0.0009483785 0.0630965978 14 1305031229.9662408829 0.0574350618 0.0514492212 0.0606188439 0.0275761876 0.5885240000 953649215 0 1782349824 0.0361509174 -0.0010470260 0.0666313469 15 1305031229.9979310036 0.0596316643 0.0519947174 0.0606188439 0.0274281242 0.5766900000 953650969 0 1784016896 0.0372411124 -0.0007555957 0.0704538226 16 1305031230.0300021172 0.0623285212 0.0526405801 0.0623285212 0.0266459844 0.5803090000 953652755 0 1782362112 0.0380477533 -0.0008432003 0.0737015903 17 1305031230.0656960011 0.0661172643 0.0534333262 0.0661172643 0.0260534134 0.5790790000 953654605 0 1784000512 0.0387226641 -0.0020595030 0.0765622854 18 1305031230.0982739925 0.0683833286 0.0542638819 0.0683833286 0.0254805949 0.5785160000 953659015 0 1782370304 0.0387406908 -0.0019745734 0.0788502544 19 1305031230.1299350262 0.0698051080 0.0550818412 0.0698051080 0.0247991483 0.6042030000 953660801 0 1783992320 0.0379568674 -0.0011932148 0.0806973949 20 1305031230.1657800674 0.0730145276 0.0559784755 0.0730145276 0.0243076504 0.5834090000 953662651 0 1782370304 0.0373982452 -0.0017067118 0.0830453336 21 1305031230.1977820396 0.0752828941 0.0568977335 0.0752828941 0.0238630206 0.5764360000 953664437 0 1784025088 0.0367249846 -0.0025708643 0.0849393830 22 1305031230.2298529148 0.0773567185 0.0578276874 0.0773567185 0.0234075269 0.5843940000 953666223 0 1782468608 0.0355429314 -0.0030011819 0.0865821764 23 1305031230.2655899525 0.0798041001 0.0587831836 0.0798041001 0.0230290519 0.5932760000 953668073 0 1784152064 0.0341872610 -0.0036662878 0.0885230303 24 1305031230.2979929447 0.0817128047 0.0597385845 0.0817128047 0.0225729718 0.6114960000 953669859 0 1782722560 0.0327740237 -0.0035330050 0.0907797366 25 1305031230.3351120949 0.0850541368 0.0607512066 0.0850541368 0.0222213300 0.6198500000 953671741 0 1784532992 0.0320036039 -0.0050126659 0.0929688364 26 1305031230.3656799793 0.0853716955 0.0616981485 0.0853716955 0.0218208875 0.6430790000 953673495 0 1783169024 0.0297696777 -0.0044551045 0.0947101116 27 1305031230.3973290920 0.0857760385 0.0625899222 0.0857760385 0.0214041292 0.6486110000 953675313 0 1781960704 0.0267408807 -0.0055106981 0.0964611471 28 1305031230.4368140697 0.0882240981 0.0635054284 0.0882240981 0.0221082960 0.6608130000 953677195 0 1783644160 0.0243069194 -0.0068114279 0.0982394889 29 1305031230.4653120041 0.0899938345 0.0644188218 0.0899938345 0.0219527700 0.6807550000 953678917 0 1782366208 0.0205324125 -0.0107504381 0.0993829295 30 1305031230.4972999096 0.0902861655 0.0652810665 0.0902861655 0.0217323143 0.7076730000 953680735 0 1783992320 0.0154204089 -0.0135441655 0.0994332582 31 1305031230.5301918983 0.0905578583 0.0660964469 0.0905578583 0.0214470620 0.7399030000 953682489 0 1782595584 0.0097415801 -0.0175818950 0.0990061015 32 1305031230.5661149025 0.0903098956 0.0668531172 0.0905578583 0.0224933791 0.7615400000 953684371 0 1784410112 0.0031996958 -0.0192076974 0.0962915346 33 1305031230.5988430977 0.0873788521 0.0674751092 0.0905578583 0.0222700738 0.8038480000 953686157 0 1782894592 -0.0040739449 -0.0194838438 0.0910903588 34 1305031230.6319139004 0.0753306970 0.0677061559 0.0905578583 0.0220660581 0.8497280000 953693223 0 1784664064 -0.0225499198 -0.0183824524 0.0730051473 35 1305031230.6660470963 0.0752613246 0.0679220178 0.0905578583 0.0224980204 0.8638790000 953695041 0 1782976512 -0.0263532102 -0.0152419116 0.0685169846 36 1305031230.6979451180 0.0753794685 0.0681291692 0.0905578583 0.0223844075 0.8593780000 953696795 0 1781579776 -0.0275709871 -0.0107132541 0.0634325743 37 1305031230.7336409092 0.0790955871 0.0684255589 0.0905578583 0.0238808140 0.9171570000 953698613 0 1783230464 -0.0292206649 0.0083415965 0.0397923030 38 1305031230.7659239769 0.0846514553 0.0688525562 0.0905578583 0.0244261002 0.9204460000 953700431 0 1781833728 -0.0283509828 0.0122131053 0.0326073430 39 1305031230.7973229885 0.0882658064 0.0693503318 0.0905578583 0.0244678094 0.9379940000 953702217 0 1783611392 -0.0302705429 0.0146286767 0.0247829184 40 1305031230.8317570686 0.0926440880 0.0699326757 0.0926440880 0.0242489451 0.9786120000 953704035 0 1782214656 -0.0423943028 0.0194379501 0.0058258502 41 1305031230.8655419350 0.0949963480 0.0705439848 0.0949963480 0.0251449404 0.9612810000 953705821 0 1783865344 -0.0478964783 0.0179164577 -0.0014161685 42 1305031230.8973939419 0.0987026915 0.0712144302 0.0987026915 0.0249053420 0.9780090000 953707639 0 1782341632 -0.0528753810 0.0172418412 -0.0095114214 43 1305031230.9373099804 0.1162689626 0.0722622100 0.1162689626 0.0248412739 1.0316680000 953709521 0 1783865344 -0.0643738732 0.0323478654 -0.0357030109 44 1305031230.9650349617 0.1168347895 0.0732752232 0.1168347895 0.0247622001 1.0066120000 953711243 0 1782468608 -0.0640283376 0.0348853171 -0.0362471603 45 1305031230.9971239567 0.1170187816 0.0742473023 0.1170187816 0.0245862613 1.0167610000 953713061 0 1784127488 -0.0653014481 0.0372291282 -0.0363934785 46 1305031231.0367500782 0.1160593182 0.0751562591 0.1170187816 0.0244297310 1.0489440000 953714943 0 1782476800 -0.0675643906 0.0378680117 -0.0356470123 47 1305031231.0644741058 0.1138043925 0.0759785599 0.1170187816 0.0242522644 1.0174890000 953716633 0 1784127488 -0.0698926300 0.0361978151 -0.0337302908 48 1305031231.0967879295 0.1125448942 0.0767403585 0.1170187816 0.0240749710 1.0293250000 953718451 0 1782730752 -0.0705963150 0.0346136875 -0.0318889506 49 1305031231.1347110271 0.1116561964 0.0774529266 0.1170187816 0.0238346960 1.0314890000 953720301 0 1784381440 -0.0708481371 0.0320403799 -0.0300357547 50 1305031231.1652760506 0.1104363278 0.0781125946 0.1170187816 0.0236978798 1.0332570000 953722087 0 1782857728 -0.0706005916 0.0295578782 -0.0276941787 51 1305031231.1977710724 0.1089007631 0.0787162842 0.1170187816 0.0237934289 1.0867090000 953723905 0 1784508416 -0.0674020573 0.0314883590 -0.0233035386 52 1305031231.2344679832 0.1089307219 0.0792973311 0.1170187816 0.0250127061 1.0697430000 953725755 0 1783103488 -0.0636689514 0.0329823233 -0.0196292214 53 1305031231.2656350136 0.1086432040 0.0798510268 0.1170187816 0.0256762508 1.1141360000 953727509 0 1781895168 -0.0585180596 0.0359087177 -0.0153140025 54 1305031231.2978610992 0.1046912298 0.0803110306 0.1170187816 0.0264052886 1.1305910000 953729327 0 1783521280 -0.0593281090 0.0344908051 -0.0100086937 55 1305031231.3351519108 0.0787700340 0.0802830124 0.1170187816 0.0302119169 1.2129490000 953731177 0 1781731328 -0.0582845472 0.0186252017 0.0206298120 56 1305031231.3650770187 0.0622198582 0.0799604561 0.1170187816 0.0315726405 1.2730570000 953732931 0 1783611392 -0.0587014779 0.0056990157 0.0442904495 57 1305031231.3973300457 0.0613334030 0.0796336657 0.1170187816 0.0332513070 1.2860410000 953734749 0 1782214656 -0.0509144887 -0.0205189865 0.0862920806 58 1305031231.4368579388 0.0782788768 0.0796103073 0.1170187816 0.0336303372 1.2999190000 953736631 0 1783902208 -0.0366800241 -0.0319169238 0.1123590767 59 1305031231.4649889469 0.0813386515 0.0796396013 0.1170187816 0.0333604668 1.2799980000 953738353 0 1782214656 -0.0244436506 -0.0265447982 0.1173937172 60 1305031231.4992439747 0.0883871987 0.0797853945 0.1170187816 0.0330845200 1.2907490000 953740139 0 1783865344 -0.0114232562 -0.0223948415 0.1269275099 61 1305031231.5331959724 0.0995191634 0.0801088990 0.1170187816 0.0328505387 1.2910180000 953742021 0 1782476800 0.0018161112 -0.0203314815 0.1393733025 62 1305031231.5650680065 0.1040678322 0.0804953334 0.1170187816 0.0327835344 1.2464340000 953743775 0 1784246272 0.0090395194 -0.0182564277 0.1454710513 63 1305031231.6013169289 0.1087965071 0.0809445583 0.1170187816 0.0325348024 1.2221210000 953745625 0 1782722560 0.0158477984 -0.0156991165 0.1512944847 64 1305031231.6331589222 0.1159125417 0.0814909331 0.1170187816 0.0324864999 1.2208010000 953747443 0 1784500224 0.0247217566 -0.0143082831 0.1586730182 65 1305031231.6650550365 0.1175902113 0.0820463066 0.1175902113 0.0322639824 1.1509780000 953749197 0 1783169024 0.0289376192 -0.0124977697 0.1600888819 66 1305031231.7035079002 0.1007448211 0.0823296174 0.1175902113 0.0321052741 1.1422390000 953761607 0 1781362688 0.0235650111 -0.0016390177 0.1466816068 67 1305031231.7339379787 0.0865100846 0.0823920125 0.1175902113 0.0318836199 1.0931760000 953763329 0 1783156736 0.0164263062 0.0036073893 0.1345545650 68 1305031231.7655088902 0.0866088569 0.0824540249 0.1175902113 0.0316801048 0.9959680000 953765115 0 1781747712 0.0190982427 0.0040202956 0.1338104904 69 1305031231.8011910915 0.0860582143 0.0825062595 0.1175902113 0.0315111660 0.9618220000 953766965 0 1783537664 0.0219791196 0.0054020104 0.1319250911 70 1305031231.8332920074 0.0687385872 0.0823095785 0.1175902113 0.0314285302 0.9164660000 953768751 0 1782112256 0.0091854082 0.0073383413 0.1150124669 71 1305031231.8649590015 0.0688964278 0.0821206608 0.1175902113 0.0312822447 0.7847590000 953770537 0 1783902208 0.0119965877 0.0067428285 0.1124515235 72 1305031231.9012699127 0.0700731725 0.0819533346 0.1175902113 0.0313531656 0.7155290000 953772387 0 1782468608 0.0134391356 0.0036128364 0.1089229733 73 1305031231.9330461025 0.0698407218 0.0817874084 0.1175902113 0.0312194871 0.6621660000 953774173 0 1784127488 0.0130140223 0.0002387369 0.1049424410 74 1305031231.9650299549 0.0684368834 0.0816069959 0.1175902113 0.0310156602 0.6266610000 953775959 0 1782738944 0.0114836777 -0.0019619022 0.0997134447 75 1305031232.0007200241 0.0665070340 0.0814056631 0.1175902113 0.0308799272 0.6049650000 953777809 0 1784508416 0.0081162481 -0.0031453902 0.0940649137 76 1305031232.0332028866 0.0650052428 0.0811898681 0.1175902113 0.0308183053 0.5876990000 953779627 0 1783029760 0.0055709654 -0.0046874424 0.0888224542 77 1305031232.0651450157 0.0635783300 0.0809611468 0.1175902113 0.0306712069 0.6125570000 953781381 0 1781608448 -0.0080474978 -0.0066193254 0.0755304322 78 1305031232.1007990837 0.0634541661 0.0807366983 0.1175902113 0.0305675212 0.5640930000 953783231 0 1783238656 -0.0095763411 -0.0065615838 0.0720112175 79 1305031232.1328380108 0.0645045936 0.0805312287 0.1175902113 0.0304334613 0.5589790000 953785049 0 1781866496 -0.0120270811 -0.0072958842 0.0675964952 80 1305031232.1650519371 0.0656230599 0.0803448766 0.1175902113 0.0302643913 0.5572470000 953786803 0 1783619584 -0.0152300335 -0.0080857696 0.0629469901 81 1305031232.1992239952 0.0672667697 0.0801834184 0.1175902113 0.0301219484 0.5623020000 953788621 0 1782247424 -0.0182391759 -0.0085812053 0.0586008541 82 1305031232.2364680767 0.0689375550 0.0800462738 0.1175902113 0.0299665177 0.5652920000 953790503 0 1783889920 -0.0211941488 -0.0092926798 0.0544851571 83 1305031232.2626979351 0.0719963461 0.0799492867 0.1175902113 0.0299605248 0.5658420000 953792193 0 1782501376 -0.0240367334 -0.0104604783 0.0501508601 84 1305031232.2980248928 0.0728541985 0.0798648214 0.1175902113 0.0300166224 0.5690510000 953794043 0 1784291328 -0.0245056469 -0.0093543530 0.0455156118 85 1305031232.3321430683 0.0750340819 0.0798079891 0.1175902113 0.0298816451 0.6190850000 953795861 0 1782730752 -0.0247069057 -0.0090750922 0.0404830948 86 1305031232.3647489548 0.0764222294 0.0797686198 0.1175902113 0.0297448686 0.5856060000 953797615 0 1784389632 -0.0260318480 -0.0080687981 0.0362667851 87 1305031232.4008779526 0.0777037144 0.0797448853 0.1175902113 0.0296060190 0.5937560000 953799497 0 1782722560 -0.0277546048 -0.0075471844 0.0332809463 88 1305031232.4331440926 0.0779464245 0.0797244482 0.1175902113 0.0294410436 0.5973080000 953801315 0 1784410112 -0.0292677842 -0.0061403946 0.0306460075 89 1305031232.4647209644 0.0791600347 0.0797181065 0.1175902113 0.0292768354 0.6014360000 953803037 0 1782751232 -0.0314966105 -0.0056817061 0.0282540228 90 1305031232.5015261173 0.0804394260 0.0797261212 0.1175902113 0.0291175422 0.6003410000 953804919 0 1784373248 -0.0322695412 -0.0061144158 0.0255400334 91 1305031232.5324640274 0.0829206482 0.0797612259 0.1175902113 0.0289634637 0.6147700000 953806705 0 1783009280 -0.0335370190 -0.0074171922 0.0223252475 92 1305031232.5647449493 0.0853438675 0.0798219067 0.1175902113 0.0288329564 0.6114410000 953808491 0 1781489664 -0.0355807990 -0.0085557690 0.0189258065 93 1305031232.6003499031 0.0880249143 0.0799101111 0.1175902113 0.0286891166 0.6179370000 953810309 0 1783103488 -0.0377565548 -0.0097453455 0.0154531347 94 1305031232.6294269562 0.0910817161 0.0800289580 0.1175902113 0.0285756132 0.6187800000 953812031 0 1781493760 -0.0407197364 -0.0109405452 0.0116799530 95 1305031232.6647078991 0.0942240804 0.0801783803 0.1175902113 0.0284297762 0.6174590000 953813913 0 1783103488 -0.0458989553 -0.0120391678 0.0079467725 96 1305031232.7005090714 0.0984017178 0.0803682068 0.1175902113 0.0282997036 0.6225600000 953815731 0 1781620736 -0.0515118279 -0.0126310214 0.0038955396 97 1305031232.7327980995 0.1014714986 0.0805857665 0.1175902113 0.0282131346 0.6104540000 953817517 0 1783263232 -0.0550182313 -0.0127579998 0.0000472402 98 1305031232.7684600353 0.1041973829 0.0808267013 0.1175902113 0.0281441458 0.6254540000 953819367 0 1781706752 -0.0590523519 -0.0135064973 -0.0032031378 99 1305031232.8045380116 0.1092156097 0.0811134580 0.1175902113 0.0280336275 0.6259490000 953821217 0 1783246848 -0.0660039186 -0.0165733974 -0.0068975990 100 1305031232.8346450329 0.1120058447 0.0814223818 0.1175902113 0.0279393766 0.6190950000 953822971 0 1781751808 -0.0699001849 -0.0164438020 -0.0105583789 101 1305031232.8685569763 0.1144320369 0.0817492101 0.1175902113 0.0278463701 0.6231760000 953824821 0 1783230464 -0.0736784488 -0.0165606383 -0.0137402415 102 1305031232.9041829109 0.1163090095 0.0820880317 0.1175902113 0.0277445736 0.6591270000 953826639 0 1781751808 -0.0777688697 -0.0162860323 -0.0164052639 103 1305031232.9330000877 0.1177536696 0.0824343000 0.1177536696 0.0276544544 0.6232700000 953828361 0 1783373824 -0.0800567493 -0.0149252480 -0.0185187664 104 1305031232.9683640003 0.1170489937 0.0827671336 0.1177536696 0.0275203419 0.6267290000 953830243 0 1781960704 -0.0802863538 -0.0141913760 -0.0201813132 105 1305031233.0011510849 0.1151640937 0.0830756761 0.1177536696 0.0274438406 0.6223490000 953832029 0 1783627776 -0.0791221708 -0.0116378088 -0.0206804350 106 1305031233.0330219269 0.1102719605 0.0833322448 0.1177536696 0.0276132750 0.6722090000 953833815 0 1782087680 -0.0802937523 -0.0007622670 -0.0189515799 107 1305031233.0688428879 0.1050392836 0.0835351143 0.1177536696 0.0277746799 0.6781470000 953835601 0 1783611392 -0.0767971128 0.0031640537 -0.0171612650 108 1305031233.1004469395 0.0969288498 0.0836591304 0.1177536696 0.0276969499 0.6788960000 953837355 0 1782120448 -0.0711428374 0.0135045452 -0.0130349183 109 1305031233.1328918934 0.0912633538 0.0837288939 0.1177536696 0.0281053245 0.6846150000 953839141 0 1783627776 -0.0614186153 0.0092687244 -0.0102193812 110 1305031233.1684799194 0.0858014300 0.0837477351 0.1177536696 0.0281425455 0.7115040000 953840991 0 1782087680 -0.0475751720 0.0085927593 -0.0077387453 111 1305031233.2006340027 0.0856975839 0.0837653014 0.1177536696 0.0280673689 0.6754490000 953842777 0 1783627776 -0.0476743244 0.0067219222 -0.0046640201 112 1305031233.2330091000 0.0845617726 0.0837724127 0.1177536696 0.0280619687 0.6700430000 953844563 0 1782009856 -0.0485554971 0.0060481755 -0.0009518594 113 1305031233.2684679031 0.0819255561 0.0837560688 0.1177536696 0.0287113676 0.7057200000 953846413 0 1783611392 -0.0504806675 0.0099785114 0.0037296787 114 1305031233.3003950119 0.0734117106 0.0836653289 0.1177536696 0.0289148729 0.7152050000 953848199 0 1782009856 -0.0470002145 0.0192939956 0.0109951906 115 1305031233.3325300217 0.0725952834 0.0835690676 0.1177536696 0.0288611284 0.6890620000 953849985 0 1783627776 -0.0493587591 0.0048120203 0.0231913235 116 1305031233.3686299324 0.0649403855 0.0834084755 0.1177536696 0.0287964352 0.6963490000 953851771 0 1781960704 -0.0269662905 0.0145814428 0.0313112624 117 1305031233.4008929729 0.0651623681 0.0832525259 0.1177536696 0.0287291080 0.6629270000 953853589 0 1783611392 -0.0172437970 0.0162666049 0.0396671109 118 1305031233.4330079556 0.0688427687 0.0831304093 0.1177536696 0.0288068176 0.6361330000 953855407 0 1782009856 -0.0209750123 0.0064057708 0.0444996357 119 1305031233.4687869549 0.0718999282 0.0830360355 0.1177536696 0.0288032507 0.6111040000 953857193 0 1783611392 -0.0226189494 0.0009905640 0.0485401750 120 1305031233.5007359982 0.0736346245 0.0829576904 0.1177536696 0.0287244954 0.6172360000 953859011 0 1781981184 -0.0244120732 -0.0022297006 0.0512301847 121 1305031233.5341610909 0.0759229586 0.0828995521 0.1177536696 0.0287178722 0.6150140000 953860829 0 1783652352 -0.0255867783 -0.0047527268 0.0534047000 122 1305031233.5697269440 0.0767497197 0.0828491437 0.1177536696 0.0286223120 0.6127170000 953862647 0 1782095872 -0.0262277536 -0.0059285932 0.0562154390 123 1305031233.6012749672 0.0783959553 0.0828129389 0.1177536696 0.0285657605 0.6109530000 953864433 0 1783635968 -0.0266790446 -0.0079646632 0.0585752912 124 1305031233.6330409050 0.0782671794 0.0827762795 0.1177536696 0.0285237152 0.6280800000 953866219 0 1782128640 -0.0274319202 -0.0084123369 0.0609701350 125 1305031233.6717829704 0.0773733854 0.0827330564 0.1177536696 0.0284573230 0.6643440000 953868133 0 1783619584 -0.0157302096 -0.0037324741 0.0739653036 126 1305031233.7022960186 0.0763813555 0.0826826460 0.1177536696 0.0284988036 0.6715410000 953869919 0 1782128640 -0.0171915423 -0.0034799196 0.0752843022 127 1305031233.7312009335 0.0739511028 0.0826138937 0.1177536696 0.0285773769 0.6562810000 953871641 0 1783635968 -0.0177831985 -0.0012465678 0.0765543133 128 1305031233.7691600323 0.0718157887 0.0825295335 0.1177536696 0.0286435059 0.6600890000 953873491 0 1782095872 -0.0164187476 0.0013759355 0.0780818090 129 1305031233.7997679710 0.0715602487 0.0824445003 0.1177536696 0.0285499526 0.6661520000 953875245 0 1783627776 -0.0143037196 0.0022156471 0.0792654827 130 1305031233.8338310719 0.0727688372 0.0823700721 0.1177536696 0.0284796280 0.6640900000 953898055 0 1782099968 -0.0121020200 0.0000887683 0.0799315125 131 1305031233.8655700684 0.0740104243 0.0823062580 0.1177536696 0.0284127518 0.6554810000 953899841 0 1783738368 -0.0109475115 -0.0013089640 0.0798598155 132 1305031233.8986968994 0.0733708665 0.0822385657 0.1177536696 0.0283059001 0.6682180000 953901691 0 1782247424 -0.0105006108 -0.0011317757 0.0800435320 133 1305031233.9320030212 0.0729388744 0.0821686432 0.1177536696 0.0282368134 0.6550810000 953903477 0 1783754752 -0.0094030732 -0.0011740471 0.0805176049 134 1305031233.9681589603 0.0716951489 0.0820904828 0.1177536696 0.0281486772 0.7127160000 953905327 0 1782214656 -0.0081562139 -0.0003505226 0.0805734023 135 1305031233.9989380836 0.0717326328 0.0820137580 0.1177536696 0.0280776555 0.6520140000 953907113 0 1783754752 -0.0059548365 -0.0003022623 0.0804177374 136 1305031234.0370678902 0.0700524300 0.0819258070 0.1177536696 0.0279850816 0.6434740000 953908995 0 1782247424 -0.0043459516 0.0019653500 0.0797622502 137 1305031234.0687561035 0.0683893412 0.0818270007 0.1177536696 0.0278889353 0.6460490000 953910749 0 1783738368 -0.0025683357 0.0044176015 0.0794655904 138 1305031234.0997409821 0.0674798414 0.0817230358 0.1177536696 0.0277986951 0.6350510000 953912535 0 1782247424 -0.0013746732 0.0064968220 0.0782097727 139 1305031234.1350688934 0.0663553178 0.0816124767 0.1177536696 0.0277154703 0.6344430000 953914353 0 1783771136 -0.0008371228 0.0083483392 0.0766726360 140 1305031234.1659009457 0.0618202724 0.0814711038 0.1177536696 0.0277121320 0.6695980000 953916139 0 1782087680 0.0003592977 0.0161533915 0.0776425898 141 1305031234.2010040283 0.0618994758 0.0813322979 0.1177536696 0.0276790680 0.6411240000 953917957 0 1783771136 0.0006913463 0.0156829562 0.0770548955 142 1305031234.2385749817 0.0605029799 0.0811856126 0.1177536696 0.0275814378 0.6799150000 953919871 0 1782099968 0.0001085455 0.0169782247 0.0763719305 143 1305031234.2655100822 0.0557238869 0.0810075585 0.1177536696 0.0275197412 0.6933220000 953921529 0 1783738368 0.0001175003 0.0255385172 0.0779848322 144 1305031234.3024549484 0.0554776713 0.0808302677 0.1177536696 0.0274242875 0.6726750000 953923443 0 1782099968 0.0001014783 0.0251517612 0.0778654590 145 1305031234.3384580612 0.0552788973 0.0806540513 0.1177536696 0.0273608979 0.6907160000 953925293 0 1783754752 -0.0002253633 0.0255750418 0.0772413611 146 1305031234.3661808968 0.0522872545 0.0804597582 0.1177536696 0.0272960562 0.7096210000 953926983 0 1782087680 -0.0018512122 0.0290253200 0.0775509998 147 1305031234.4000349045 0.0515988357 0.0802634254 0.1177536696 0.0272036515 0.7115820000 953928801 0 1783738368 -0.0020747706 0.0304987989 0.0773884431 148 1305031234.4367709160 0.0519105941 0.0800718522 0.1177536696 0.0271838309 0.7236370000 953930683 0 1782099968 -0.0010247725 0.0304380618 0.0764715001 149 1305031234.4676060677 0.0518762246 0.0798826198 0.1177536696 0.0270966369 0.7408140000 953932437 0 1783771136 -0.0002224324 0.0316983722 0.0754755065 150 1305031234.4977810383 0.0513136238 0.0796921598 0.1177536696 0.0270083418 0.7567780000 953934191 0 1782214656 0.0002750871 0.0342009515 0.0749180987 151 1305031234.5376710892 0.0528100021 0.0795141323 0.1177536696 0.0270860869 0.7510440000 953936105 0 1783865344 0.0019731175 0.0328813083 0.0721225739 152 1305031234.5690369606 0.0526725836 0.0793375431 0.1177536696 0.0270677814 0.7620170000 953937859 0 1782480896 0.0021851840 0.0353574827 0.0704436600 153 1305031234.5982480049 0.0524040908 0.0791615075 0.1177536696 0.0269826249 0.7656020000 953939645 0 1784152064 0.0028356877 0.0373921879 0.0696969256 154 1305031234.6336491108 0.0543392003 0.0790003237 0.1177536696 0.0269069248 0.7640400000 953941431 0 1782468608 0.0060346248 0.0379508063 0.0689753592 155 1305031234.6658589840 0.0549161695 0.0788449421 0.1177536696 0.0268475039 0.7516520000 953943249 0 1784119296 0.0068285074 0.0395490453 0.0679406002 156 1305031234.6987318993 0.0599864684 0.0787240544 0.1177536696 0.0267901776 0.7662850000 953945067 0 1782730752 0.0151172392 0.0485122278 0.0760977343 157 1305031234.7344369888 0.0634658784 0.0786268686 0.1177536696 0.0267225173 0.7715780000 953946853 0 1784516608 0.0182760581 0.0482879765 0.0757925063 158 1305031234.7689719200 0.0689782128 0.0785658011 0.1177536696 0.0266628175 0.7234260000 953948703 0 1783021568 0.0240978003 0.0476937778 0.0762664676 159 1305031234.8015530109 0.0720386356 0.0785247498 0.1177536696 0.0266919854 0.7155440000 953950521 0 1781960704 0.0265804883 0.0487468541 0.0765715167 160 1305031234.8378078938 0.0753750205 0.0785050640 0.1177536696 0.0266218530 0.7097360000 953952403 0 1783644160 0.0294320974 0.0489080958 0.0773204491 161 1305031234.8693211079 0.0769573897 0.0784954511 0.1177536696 0.0265609464 0.7135980000 953954125 0 1782235136 0.0302449092 0.0492412746 0.0767784640 162 1305031234.9019980431 0.0767865106 0.0784849021 0.1177536696 0.0264819329 0.7104480000 953955943 0 1783992320 0.0290867332 0.0514326282 0.0779818520 163 1305031234.9381608963 0.0686163008 0.0784243585 0.1177536696 0.0265770807 0.7449770000 953957793 0 1782595584 0.0152256414 0.0658955425 0.0821595863 164 1305031234.9730799198 0.0664896369 0.0783515858 0.1177536696 0.0265011026 0.7370100000 953959643 0 1784258560 0.0136482567 0.0634971187 0.0834564790 165 1305031235.0050830841 0.0612843521 0.0782481480 0.1177536696 0.0265227663 0.7661990000 953961397 0 1783115776 0.0075657349 0.0653680041 0.0872147903 166 1305031235.0399720669 0.0575328469 0.0781233571 0.1177536696 0.0264499735 0.7694060000 953963247 0 1781960704 0.0046383082 0.0625583231 0.0879698172 167 1305031235.0729401112 0.0508432090 0.0779600029 0.1177536696 0.0263937564 0.7886810000 953965033 0 1783611392 -0.0033149831 0.0615341291 0.0878824741 168 1305031235.0995910168 0.0463669077 0.0777719487 0.1177536696 0.0263373721 0.7781190000 953966755 0 1782366208 -0.0069595296 0.0591972917 0.0882054418 169 1305031235.1362709999 0.0436161272 0.0775698433 0.1177536696 0.0262939194 0.7945250000 953968605 0 1784152064 -0.0096843131 0.0550264567 0.0873765573 170 1305031235.1663711071 0.0404343456 0.0773513992 0.1177536696 0.0262650079 0.8089430000 953970359 0 1782644736 -0.0156653281 0.0534597859 0.0865282193 171 1305031235.1998469830 0.0379207246 0.0771208104 0.1177536696 0.0262446851 0.8498700000 953972113 0 1784397824 -0.0243791379 0.0549816452 0.0857636482 172 1305031235.2375700474 0.0368073694 0.0768864300 0.1177536696 0.0262326350 0.8301920000 953973995 0 1782984704 -0.0276436917 0.0539479554 0.0865054727 173 1305031235.2690389156 0.0360639952 0.0766504621 0.1177536696 0.0261826799 0.8425840000 953975781 0 1781841920 -0.0323681831 0.0528736189 0.0873015001 174 1305031235.3064870834 0.0367045254 0.0764208878 0.1177536696 0.0261871861 0.8317480000 953977663 0 1783508992 -0.0356997028 0.0527902506 0.0886697993 175 1305031235.3380000591 0.0384995192 0.0762041943 0.1177536696 0.0261277532 0.8504830000 953979417 0 1782247424 -0.0420278795 0.0522475131 0.0895085558 176 1305031235.3698880672 0.0419290736 0.0760094493 0.1177536696 0.0260892837 0.8583880000 953981203 0 1783906304 -0.0457927659 0.0490771309 0.0893157199 177 1305031235.4060161114 0.0442321673 0.0758299166 0.1177536696 0.0261671126 0.8837800000 953983053 0 1782599680 -0.0473433733 0.0492231324 0.0915156603 178 1305031235.4381530285 0.0440088771 0.0756511467 0.1177536696 0.0261344325 0.8604170000 953984839 0 1784246272 -0.0519234389 0.0511051342 0.0955471173 179 1305031235.4700589180 0.0361595452 0.0754305232 0.1177536696 0.0260793766 0.8644610000 953986625 0 1783103488 -0.0419531763 0.0499005541 0.1042051539 180 1305031235.5059850216 0.0367387123 0.0752155687 0.1177536696 0.0260355002 0.8144190000 953988475 0 1781960704 -0.0400633179 0.0504203960 0.1079749465 181 1305031235.5385539532 0.0357527286 0.0749975420 0.1177536696 0.0259726626 0.7742540000 953990261 0 1783898112 -0.0379716419 0.0506027117 0.1118982732 182 1305031235.5703649521 0.0342746004 0.0747737896 0.1177536696 0.0259073705 0.7699050000 953992047 0 1782599680 -0.0290109981 0.0482051820 0.1198600307 183 1305031235.6060059071 0.0318674073 0.0745393285 0.1177536696 0.0259184618 0.7658070000 953993929 0 1781600256 -0.0240785889 0.0514761358 0.1284482926 184 1305031235.6389510632 0.0374691971 0.0743378603 0.1177536696 0.0258707344 0.6934900000 953995715 0 1783230464 -0.0254110154 0.0474234186 0.1309355944 185 1305031235.6705160141 0.0424655527 0.0741655776 0.1177536696 0.0258108769 0.6640250000 953997469 0 1782001664 -0.0280238073 0.0445668697 0.1337001920 186 1305031235.7057778835 0.0538258813 0.0740562244 0.1177536696 0.0257480628 0.6566890000 953999319 0 1783644160 -0.0305485670 0.0370605960 0.1364511698 187 1305031235.7387969494 0.0591125898 0.0739763119 0.1177536696 0.0257091680 0.6182520000 954001137 0 1782341632 -0.0335743502 0.0354091637 0.1385866255 188 1305031235.7696299553 0.0642099679 0.0739243633 0.1177536696 0.0256605895 0.6062090000 954002891 0 1784025088 -0.0369710550 0.0342755318 0.1403622180 189 1305031235.8072249889 0.0710140094 0.0739089646 0.1177536696 0.0256014122 0.5942830000 954004837 0 1782747136 -0.0403913334 0.0332211368 0.1409449726 190 1305031235.8388121128 0.0770502761 0.0739254978 0.1177536696 0.0255733521 0.5893150000 954006623 0 1784279040 -0.0437673964 0.0312450565 0.1431077421 191 1305031235.8700668812 0.0825814381 0.0739708169 0.1177536696 0.0255451118 0.6182520000 954008441 0 1783021568 -0.0466193855 0.0296563786 0.1456322372 192 1305031235.9061110020 0.0882441327 0.0740451570 0.1177536696 0.0254815690 0.5807350000 954010323 0 1781579776 -0.0483041592 0.0287940335 0.1481556147 193 1305031235.9382328987 0.0934717730 0.0741458131 0.1177536696 0.0254272759 0.5770260000 954012173 0 1783390208 -0.0496231429 0.0270719454 0.1509137899 194 1305031235.9700109959 0.0970770866 0.0742640155 0.1177536696 0.0253736159 0.5841800000 954013959 0 1782239232 -0.0510731339 0.0269146189 0.1538949311 195 1305031236.0068531036 0.1025635526 0.0744091414 0.1177536696 0.0253164259 0.5760120000 954015873 0 1783898112 -0.0525090322 0.0258260705 0.1572324932 196 1305031236.0380480289 0.1065677330 0.0745732158 0.1177536696 0.0252572115 0.5750540000 954017659 0 1782472704 -0.0538818575 0.0255253986 0.1602605581 197 1305031236.0698781013 0.1102514714 0.0747543237 0.1177536696 0.0252461012 0.5631010000 954019477 0 1784246272 -0.0555083677 0.0252489708 0.1634464413 198 1305031236.1058719158 0.1149624437 0.0749573950 0.1177536696 0.0251911826 0.5719000000 954021359 0 1782910976 -0.0567334443 0.0241334997 0.1666889042 199 1305031236.1383249760 0.1182032898 0.0751747111 0.1182032898 0.0251312505 0.5704650000 954023209 0 1781706752 -0.0580540858 0.0234691277 0.1692230552 200 1305031236.1709330082 0.1207844615 0.0754027598 0.1207844615 0.0250689432 0.6240950000 954025027 0 1783631872 -0.0590030923 0.0233587287 0.1709131151 201 1305031236.2071900368 0.1222251058 0.0756357068 0.1222251058 0.0250167862 0.5729000000 954026941 0 1782345728 -0.0593171418 0.0241823420 0.1725911200 202 1305031236.2383749485 0.1240962148 0.0758756103 0.1240962148 0.0249822005 0.5735430000 954028759 0 1784119296 -0.0602623038 0.0229586661 0.1747768521 203 1305031236.2699589729 0.1267021298 0.0761259873 0.1267021298 0.0249216763 0.5774210000 954030545 0 1782730752 -0.0610807464 0.0202216953 0.1761686951 204 1305031236.3069939613 0.1275485158 0.0763780585 0.1275485158 0.0249221121 0.5751430000 954032459 0 1784373248 -0.0608668663 0.0173276477 0.1767305434 205 1305031236.3392169476 0.1292675138 0.0766360558 0.1292675138 0.0248788243 0.5768260000 954034277 0 1783021568 -0.0602012947 0.0133742504 0.1766812354 206 1305031236.3700959682 0.1295797974 0.0768930643 0.1295797974 0.0248333194 0.5836070000 954036063 0 1781637120 -0.0589086674 0.0100206025 0.1748962402 207 1305031236.4058690071 0.1277912259 0.0771389491 0.1295797974 0.0248266910 0.5766900000 954037945 0 1783357440 -0.0572188646 0.0071498305 0.1725066900 208 1305031236.4387879372 0.1255074590 0.0773714900 0.1295797974 0.0247667766 0.5870240000 954039763 0 1782112256 -0.0545574017 0.0047607352 0.1697842628 209 1305031236.4751410484 0.1215852499 0.0775830391 0.1295797974 0.0247089118 0.6189070000 954041677 0 1783738368 -0.0505608432 0.0031418614 0.1666060090 210 1305031236.5077209473 0.1168449447 0.0777700006 0.1295797974 0.0246555031 0.5851170000 954043527 0 1782382592 -0.0462442711 0.0027128719 0.1628919393 211 1305031236.5386450291 0.1138513982 0.0779410025 0.1295797974 0.0246169956 0.5875080000 954045313 0 1784045568 -0.0425383747 0.0007327087 0.1592135578 212 1305031236.5740950108 0.1086832732 0.0780860132 0.1295797974 0.0245597855 0.5906730000 954047195 0 1782595584 -0.0393922441 -0.0004365165 0.1546577513 213 1305031236.6057569981 0.1067487076 0.0782205798 0.1295797974 0.0245056430 0.5934570000 954048981 0 1784389632 -0.0363697968 -0.0034452491 0.1503378302 214 1305031236.6384010315 0.1034722850 0.0783385784 0.1295797974 0.0244789800 0.5915580000 954050799 0 1782849536 -0.0329241566 -0.0046768449 0.1446936727 215 1305031236.6751470566 0.0977241546 0.0784287439 0.1295797974 0.0244385285 0.5859840000 954052649 0 1781620736 -0.0300460160 -0.0046946374 0.1388274282 216 1305031236.7033619881 0.0940017626 0.0785008412 0.1295797974 0.0243867772 0.5899300000 954054371 0 1783410688 -0.0256960765 -0.0048808591 0.1338941008 217 1305031236.7339220047 0.0837894753 0.0785252128 0.1295797974 0.0243678838 0.6250210000 954056125 0 1781833728 -0.0245664995 0.0021048759 0.1227671281 218 1305031236.7740409374 0.0800864846 0.0785323746 0.1295797974 0.0243526282 0.5890210000 954058039 0 1783644160 -0.0220351126 0.0011813999 0.1166674048 219 1305031236.8025879860 0.0772144273 0.0785263566 0.1295797974 0.0244291418 0.6060460000 954059825 0 1782341632 -0.0198715925 0.0029411770 0.1084648073 220 1305031236.8364150524 0.0706918389 0.0784907451 0.1295797974 0.0243753040 0.6160470000 954061611 0 1783898112 -0.0171588473 0.0064471755 0.1015447378 221 1305031236.8743979931 0.0663771629 0.0784359325 0.1295797974 0.0243332999 0.6193480000 954063493 0 1782722560 -0.0148780039 0.0078272829 0.0943352878 222 1305031236.9060690403 0.0643325970 0.0783724040 0.1295797974 0.0243346983 0.6410460000 954065279 0 1784381440 -0.0121331448 0.0092423446 0.0872900784 223 1305031236.9344370365 0.0639386252 0.0783076785 0.1295797974 0.0242939213 0.6537520000 954067001 0 1782919168 -0.0104808388 0.0093696201 0.0799787864 224 1305031236.9744000435 0.0622194074 0.0782358559 0.1295797974 0.0242460639 0.6679180000 954068883 0 1784561664 -0.0082843769 0.0097738225 0.0737185553 225 1305031237.0074260235 0.0621257015 0.0781642552 0.1295797974 0.0241928853 0.7001060000 954070733 0 1783111680 -0.0102081578 0.0079568503 0.0645098314 226 1305031237.0370240211 0.0597325303 0.0780826989 0.1295797974 0.0241831074 0.7817510000 954072487 0 1781714944 -0.0099335443 0.0114058098 0.0583630838 227 1305031237.0734269619 0.0608924143 0.0780069708 0.1295797974 0.0241391952 0.7307480000 954074305 0 1783398400 -0.0069947811 0.0093446104 0.0531743579 228 1305031237.1059679985 0.0633167624 0.0779425400 0.1295797974 0.0240929076 0.7547240000 954076123 0 1782013952 -0.0045271269 0.0080089513 0.0470552705 229 1305031237.1378319263 0.0655823126 0.0778885652 0.1295797974 0.0240447219 0.7799390000 954077909 0 1783746560 -0.0010761007 0.0085187797 0.0406614244 230 1305031237.1712269783 0.0650542155 0.0778327637 0.1295797974 0.0240591241 0.7753850000 954079727 0 1781968896 0.0003954568 0.0116697578 0.0360406935 231 1305031237.2042291164 0.0660027415 0.0777815515 0.1295797974 0.0240634332 0.7715590000 954081481 0 1783635968 0.0028737250 0.0114092184 0.0304022655 232 1305031237.2375690937 0.0673076883 0.0777364055 0.1295797974 0.0240680337 0.7870840000 954083331 0 1782136832 0.0055610007 0.0169979706 0.0266437158 233 1305031237.2746589184 0.0700763911 0.0777035299 0.1295797974 0.0240329726 0.7928520000 954085181 0 1783771136 0.0101411557 0.0174234323 0.0235314779 234 1305031237.3058099747 0.0737605169 0.0776866795 0.1295797974 0.0239976724 0.7766050000 954086967 0 1782341632 0.0152167585 0.0220006965 0.0222217496 235 1305031237.3371419907 0.0781504065 0.0776886528 0.1295797974 0.0239919655 0.7484690000 954088753 0 1783992320 0.0191652924 0.0225000568 0.0191856083 236 1305031237.3741660118 0.0826764479 0.0777097875 0.1295797974 0.0239532128 0.7507470000 954090571 0 1782501376 0.0240629725 0.0240255035 0.0167461950 237 1305031237.4057340622 0.0844942331 0.0777384138 0.1295797974 0.0239600791 0.7422710000 954092389 0 1784025088 0.0259067472 0.0262074433 0.0142849283 238 1305031237.4377219677 0.0886502936 0.0777842621 0.1295797974 0.0239559082 0.7502530000 954094175 0 1782722560 0.0296788048 0.0278349388 0.0125148054 239 1305031237.4741280079 0.0916571394 0.0778423076 0.1295797974 0.0239302619 0.7315570000 954095993 0 1784373248 0.0330290049 0.0294631124 0.0110830562 240 1305031237.5060451031 0.0935350284 0.0779076939 0.1295797974 0.0239113008 0.7280440000 954097811 0 1782763520 0.0350995921 0.0313579924 0.0104986494 241 1305031237.5376501083 0.0962917507 0.0779839763 0.1295797974 0.0238640622 0.7282890000 954099597 0 1784397824 0.0381612889 0.0329628736 0.0094238482 242 1305031237.5739479065 0.0986780748 0.0780694891 0.1295797974 0.0238324595 0.7371700000 954101415 0 1782968320 0.0403343290 0.0335714556 0.0084396908 243 1305031237.6068129539 0.0993734524 0.0781571598 0.1295797974 0.0237941450 0.7330460000 954103265 0 1781444608 0.0413487703 0.0357281491 0.0087577133 244 1305031237.6378550529 0.0999498293 0.0782464740 0.1295797974 0.0237548502 0.7352140000 954105019 0 1783111680 0.0415221378 0.0382214598 0.0088239769 245 1305031237.6752760410 0.1004537418 0.0783371159 0.1295797974 0.0237199522 0.7427840000 954106869 0 1781641216 0.0413420834 0.0400182642 0.0089059919 246 1305031237.7071180344 0.1000518724 0.0784253873 0.1295797974 0.0236746505 0.7371130000 954108687 0 1783103488 0.0403302610 0.0418679491 0.0088587217 247 1305031237.7416670322 0.0972321182 0.0785015279 0.1295797974 0.0236453097 0.7872930000 954110505 0 1781706752 0.0365858413 0.0439526141 0.0091199093 248 1305031237.7743060589 0.0988861620 0.0785837240 0.1295797974 0.0236746884 0.7467560000 954112259 0 1783500800 0.0386855826 0.0433992669 0.0098450296 249 1305031237.8064959049 0.0988177732 0.0786649852 0.1295797974 0.0236388325 0.7377500000 954114077 0 1782136832 0.0397618823 0.0410760492 0.0091465171 250 1305031237.8430309296 0.0942052752 0.0787271464 0.1295797974 0.0236609202 0.7475660000 954115959 0 1783754752 0.0329896100 0.0443028994 0.0089389905 251 1305031237.8754220009 0.0965280533 0.0787980663 0.1295797974 0.0238564205 0.7656530000 954117713 0 1782341632 0.0367019325 0.0428624861 0.0090826610 252 1305031237.9077839851 0.0958598629 0.0788657719 0.1295797974 0.0238424821 0.7502930000 954119531 0 1784008704 0.0373458527 0.0395810120 0.0085703367 253 1305031237.9441869259 0.0929533467 0.0789214540 0.1295797974 0.0239305961 0.7584490000 954121381 0 1782497280 0.0331181809 0.0424354635 0.0098202685 254 1305031237.9738099575 0.0930149481 0.0789769402 0.1295797974 0.0238890924 0.8124880000 954123071 0 1784279040 0.0321098790 0.0445683114 0.0125490688 255 1305031238.0069320202 0.0904828534 0.0790220614 0.1295797974 0.0238522117 0.7905440000 954124921 0 1782595584 0.0295594689 0.0440372117 0.0158655904 256 1305031238.0431399345 0.0880314335 0.0790572543 0.1295797974 0.0240289960 0.7988770000 954126771 0 1784246272 0.0272359494 0.0431032777 0.0184515379 257 1305031238.0740320683 0.0831814706 0.0790733018 0.1295797974 0.0240535579 0.8273530000 954128525 0 1782882304 0.0210029073 0.0441286303 0.0209033545 258 1305031238.1065878868 0.0739344284 0.0790533837 0.1295797974 0.0240378355 0.8268520000 954172295 0 1784516608 0.0097508067 0.0404155254 0.0161064826 259 1305031238.1433279514 0.0702507943 0.0790193968 0.1295797974 0.0240649769 0.8317290000 954174145 0 1782861824 0.0029465733 0.0372161940 0.0143897170 260 1305031238.1723001003 0.0608244911 0.0789494164 0.1295797974 0.0240399704 0.8668800000 954175931 0 1781489664 -0.0126040159 0.0430873893 0.0162438974 261 1305031238.2054259777 0.0575410537 0.0788673921 0.1295797974 0.0239974862 0.8703180000 954177685 0 1782976512 -0.0166538749 0.0344243795 0.0161127988 262 1305031238.2401471138 0.0547879003 0.0787754856 0.1295797974 0.0239749971 0.8874300000 954179535 0 1781452800 -0.0203327965 0.0289680939 0.0180052351 263 1305031238.2725269794 0.0521252602 0.0786741540 0.1295797974 0.0239326490 0.8921150000 954181353 0 1782976512 -0.0245232545 0.0273968950 0.0213059392 264 1305031238.3060529232 0.0491524190 0.0785623292 0.1295797974 0.0241139357 0.9104240000 954183139 0 1781452800 -0.0312114656 0.0288683735 0.0252607074 265 1305031238.3425960541 0.0483834036 0.0784484465 0.1295797974 0.0241054041 0.8823340000 954184989 0 1782976512 -0.0289649703 0.0265545025 0.0314098746 266 1305031238.3741040230 0.0511094965 0.0783456685 0.1295797974 0.0241529215 0.8811730000 954186775 0 1781612544 -0.0185470767 0.0265717898 0.0426499993 267 1305031238.4060359001 0.0571856648 0.0782664175 0.1295797974 0.0241086456 0.8393750000 954188561 0 1783144448 -0.0066980505 0.0275585726 0.0534088165 268 1305031238.4434239864 0.0606877804 0.0782008256 0.1295797974 0.0240693756 0.7663940000 954190411 0 1781501952 -0.0044174809 0.0256241970 0.0569087490 269 1305031238.4740819931 0.0615696609 0.0781389997 0.1295797974 0.0240299934 0.7428750000 954192197 0 1783111680 -0.0049950755 0.0236291960 0.0603413135 270 1305031238.5058109760 0.0624678098 0.0780809582 0.1295797974 0.0240493985 0.6996350000 954193983 0 1781460992 -0.0068754153 0.0196670685 0.0627183169 271 1305031238.5432639122 0.0659272745 0.0780361107 0.1295797974 0.0240080411 0.6732320000 954195865 0 1783128064 -0.0088749249 0.0142733306 0.0637885183 272 1305031238.5741839409 0.0666456595 0.0779942340 0.1295797974 0.0239669070 0.6687990000 954197587 0 1781587968 -0.0114657618 0.0120929684 0.0662808120 273 1305031238.6058249474 0.0685536042 0.0779596530 0.1295797974 0.0239273691 0.6655780000 954199405 0 1783230464 -0.0135920895 0.0095355231 0.0683779418 274 1305031238.6427590847 0.0701064393 0.0779309916 0.1295797974 0.0238912052 0.6626950000 954201287 0 1781751808 -0.0159329623 0.0076267081 0.0709853247 275 1305031238.6738131046 0.0728757828 0.0779126090 0.1295797974 0.0238538863 0.6534250000 954203009 0 1783357440 -0.0185260158 0.0062926314 0.0727873370 276 1305031238.7051889896 0.0737757683 0.0778976205 0.1295797974 0.0238115690 0.6491640000 954204795 0 1781833728 -0.0214414708 0.0061763194 0.0746827796 277 1305031238.7413070202 0.0758113265 0.0778900887 0.1295797974 0.0237977704 0.6365020000 954206677 0 1783627776 -0.0233774800 0.0052524344 0.0760188550 278 1305031238.7717959881 0.0784067959 0.0778919474 0.1295797974 0.0237749946 0.6235550000 954208463 0 1782087680 -0.0257480498 0.0034958688 0.0772137493 279 1305031238.8070189953 0.0809831694 0.0779030270 0.1295797974 0.0237527715 0.6217680000 954210313 0 1783754752 -0.0280358978 0.0034453059 0.0782799795 280 1305031238.8429400921 0.0821441859 0.0779181740 0.1295797974 0.0237141954 0.6202600000 954212195 0 1782247424 -0.0301011782 0.0032703264 0.0800015405 281 1305031238.8737230301 0.0866137967 0.0779491193 0.1295797974 0.0237159494 0.6153700000 954214013 0 1783865344 -0.0306228977 0.0004272209 0.0814353377 282 1305031238.9061720371 0.0901658386 0.0779924410 0.1295797974 0.0236908458 0.6515450000 954215799 0 1782480896 -0.0312261712 -0.0023429012 0.0831420720 283 1305031238.9427859783 0.0925115496 0.0780437453 0.1295797974 0.0236491310 0.6120880000 954217713 0 1784135680 -0.0319043435 -0.0034556556 0.0848190784 284 1305031238.9723079205 0.0948816761 0.0781030338 0.1295797974 0.0236189034 0.6221460000 954219499 0 1782722560 -0.0323567055 -0.0050275130 0.0861758739 285 1305031239.0104830265 0.0975634456 0.0781713159 0.1295797974 0.0236136204 0.6103740000 954221413 0 1784389632 -0.0328027122 -0.0059340252 0.0875306800 286 1305031239.0408790112 0.0990969613 0.0782444825 0.1295797974 0.0235759429 0.6137030000 954223199 0 1782898688 -0.0332569033 -0.0064579044 0.0888551474 287 1305031239.0746610165 0.1018458307 0.0783267172 0.1295797974 0.0235831316 0.6144840000 954225049 0 1784500224 -0.0335564725 -0.0085165231 0.0899309739 288 1305031239.1109058857 0.1044079512 0.0784172770 0.1295797974 0.0235421341 0.6091100000 954226963 0 1783009280 -0.0339022912 -0.0109736593 0.0909494981 289 1305031239.1417789459 0.1059543416 0.0785125610 0.1295797974 0.0235126184 0.6036310000 954228749 0 1784500224 -0.0344152041 -0.0132199144 0.0915129036 290 1305031239.1757500172 0.1082981974 0.0786152701 0.1295797974 0.0234931035 0.6370360000 954230599 0 1783009280 -0.0342492536 -0.0163046122 0.0913653523 291 1305031239.2096450329 0.1086293384 0.0787184112 0.1295797974 0.0234584562 0.6107920000 954232449 0 1784516608 -0.0335941501 -0.0170216039 0.0905112550 292 1305031239.2417099476 0.1089082360 0.0788218010 0.1295797974 0.0234314314 0.6200440000 954234267 0 1782976512 -0.0327971503 -0.0180591363 0.0897285715 293 1305031239.2738199234 0.1082998142 0.0789224086 0.1295797974 0.0234175357 0.6114180000 954236085 0 1781235712 -0.0318082832 -0.0187189709 0.0886490345 294 1305031239.3101770878 0.1079030335 0.0790209821 0.1295797974 0.0233786933 0.6109580000 954237999 0 1782755328 -0.0308500640 -0.0192540735 0.0872438103 295 1305031239.3419699669 0.1066315696 0.0791145773 0.1295797974 0.0233421050 0.6085500000 954239817 0 1781235712 -0.0299082771 -0.0190708563 0.0855824053 296 1305031239.3750240803 0.1047050059 0.0792010315 0.1295797974 0.0233235497 0.6092440000 954241603 0 1782738944 -0.0286921561 -0.0185152255 0.0834119171 297 1305031239.4106309414 0.1022520512 0.0792786443 0.1295797974 0.0232876105 0.5995240000 954243453 0 1781198848 -0.0276752505 -0.0170496665 0.0810627639 298 1305031239.4415419102 0.1012131721 0.0793522501 0.1295797974 0.0232529847 0.6000880000 954245239 0 1782738944 -0.0262070466 -0.0170178507 0.0787035599 299 1305031239.4733181000 0.0976612568 0.0794134843 0.1295797974 0.0232148514 0.6480400000 954247025 0 1781235712 -0.0252918303 -0.0145197958 0.0761776790 300 1305031239.5097389221 0.0939561129 0.0794619597 0.1295797974 0.0231784758 0.6329520000 954248875 0 1782722560 -0.0236722566 -0.0112907840 0.0731782243 301 1305031239.5438020229 0.0907687023 0.0794995236 0.1295797974 0.0231496324 0.6160390000 954250725 0 1781235712 -0.0225198101 -0.0091821812 0.0702655688 302 1305031239.5761160851 0.0875346810 0.0795261301 0.1295797974 0.0231215800 0.6162530000 954252511 0 1782992896 -0.0214365795 -0.0062199235 0.0671349987 303 1305031239.6111609936 0.0852354616 0.0795449728 0.1295797974 0.0230887684 0.6056110000 954254361 0 1781579776 -0.0204121284 -0.0041878154 0.0640510917 304 1305031239.6414220333 0.0840791985 0.0795598880 0.1295797974 0.0230535486 0.5987220000 954256115 0 1783390208 -0.0192034300 -0.0032310851 0.0606898032 305 1305031239.6710560322 0.0813096240 0.0795656248 0.1295797974 0.0230291064 0.5997070000 954257837 0 1782087680 -0.0182399601 -0.0003503919 0.0575768948 306 1305031239.7075550556 0.0797439069 0.0795662075 0.1295797974 0.0230410403 0.5982670000 954259687 0 1783754752 -0.0167674739 0.0004961014 0.0542231165 307 1305031239.7417550087 0.0795949176 0.0795663010 0.1295797974 0.0230048445 0.6408070000 954261537 0 1782370304 -0.0148873394 0.0004860187 0.0506682470 308 1305031239.7712600231 0.0794626698 0.0795659645 0.1295797974 0.0229729650 0.6284300000 954263259 0 1783992320 -0.0124566564 0.0006978668 0.0474006571 309 1305031239.8060870171 0.0797308981 0.0795664983 0.1295797974 0.0230521490 0.6524590000 954265077 0 1782620160 -0.0090272399 -0.0008637578 0.0443941019 310 1305031239.8392889500 0.0769485608 0.0795580533 0.1295797974 0.0230348737 0.7023290000 954266895 0 1784389632 -0.0093645817 0.0018437863 0.0404022671 311 1305031239.8744299412 0.0735683367 0.0795387938 0.1295797974 0.0230072814 0.7408060000 954268681 0 1782976512 -0.0109101282 0.0032694661 0.0378434844 312 1305031239.9090619087 0.0723788291 0.0795158452 0.1295797974 0.0230167069 0.7663540000 954270531 0 1781706752 -0.0097536827 0.0043773479 0.0355092920 313 1305031239.9403729439 0.0711750910 0.0794891974 0.1295797974 0.0229943714 0.8007420000 954272285 0 1783521280 -0.0100882770 0.0051225801 0.0320008062 314 1305031239.9710669518 0.0701102763 0.0794593282 0.1295797974 0.0229932009 0.8557600000 954274071 0 1782116352 -0.0099123139 0.0070079905 0.0288510285 315 1305031240.0088651180 0.0708171502 0.0794318927 0.1295797974 0.0230335265 0.8217140000 954275985 0 1783758848 -0.0087651918 0.0054954439 0.0246040579 316 1305031240.0396599770 0.0713968575 0.0794064654 0.1295797974 0.0230052212 0.8223250000 954277707 0 1781960704 -0.0076697785 0.0060621602 0.0208893996 317 1305031240.0711870193 0.0730680972 0.0793864706 0.1295797974 0.0229702746 0.8154200000 954279493 0 1783738368 -0.0057046935 0.0057769157 0.0174632687 318 1305031240.1093459129 0.0757227838 0.0793749495 0.1295797974 0.0229780158 0.8171530000 954281375 0 1782476800 -0.0013586907 0.0044841776 0.0141327158 319 1305031240.1435019970 0.0806432888 0.0793789255 0.1295797974 0.0229779229 0.8162980000 954283225 0 1784033280 0.0070160511 0.0050130677 0.0130184945 320 1305031240.1775770187 0.0818883553 0.0793867675 0.1295797974 0.0229647801 0.8274890000 954285011 0 1782525952 0.0093236314 0.0077627199 0.0107230330 321 1305031240.2093310356 0.0883010477 0.0794145378 0.1295797974 0.0229753784 0.8202020000 954286829 0 1784287232 0.0201350190 0.0085487897 0.0134681361 322 1305031240.2410049438 0.0940881744 0.0794601081 0.1295797974 0.0230075693 0.7799190000 954288583 0 1782603776 0.0269515961 0.0098359771 0.0104737561 323 1305031240.2774341106 0.0948907062 0.0795078809 0.1295797974 0.0229922737 0.7589900000 954290433 0 1784254464 0.0292008892 0.0120777572 0.0092585655 324 1305031240.3089289665 0.1019765809 0.0795772287 0.1295797974 0.0229599064 0.7902520000 954292187 0 1782890496 0.0385631770 0.0173286200 0.0127795823 325 1305031240.3422729969 0.1053159311 0.0796564247 0.1295797974 0.0229409789 0.7570380000 954294005 0 1784516608 0.0425361618 0.0180472136 0.0112705110 326 1305031240.3774259090 0.1024052054 0.0797262063 0.1295797974 0.0229589930 0.7692550000 954295855 0 1783025664 0.0379752964 0.0367816165 0.0163589250 327 1305031240.4091110229 0.1025139093 0.0797958934 0.1295797974 0.0229260840 0.7457670000 954297609 0 1781452800 0.0374788754 0.0399129800 0.0132857785 328 1305031240.4417860508 0.1021970510 0.0798641896 0.1295797974 0.0228919877 0.7291550000 954299427 0 1783115776 0.0360325165 0.0430708192 0.0127934515 329 1305031240.4776389599 0.0980319232 0.0799194107 0.1295797974 0.0228663669 0.7576070000 954301277 0 1781768192 0.0241442397 0.0579175353 0.0131617021 330 1305031240.5084490776 0.0988997146 0.0799769268 0.1295797974 0.0228526222 0.7263960000 954302999 0 1783500800 0.0233107638 0.0611595474 0.0134673947 331 1305031240.5412700176 0.0977041796 0.0800304834 0.1295797974 0.0228506517 0.7209110000 954304817 0 1782087680 0.0182023887 0.0660117865 0.0137264533 332 1305031240.5759088993 0.1006294787 0.0800925286 0.1295797974 0.0228308778 0.7408500000 954306667 0 1783754752 0.0116779935 0.0771817043 0.0175445247 333 1305031240.6101338863 0.0989533663 0.0801491678 0.1295797974 0.0228050601 0.7325750000 954308485 0 1782099968 0.0099769710 0.0764677152 0.0177365486 334 1305031240.6398229599 0.0972166285 0.0802002679 0.1295797974 0.0227940112 0.7779990000 954310207 0 1783754752 0.0082612382 0.0755076706 0.0191212799 335 1305031240.6747570038 0.0940803438 0.0802417010 0.1295797974 0.0227646329 0.7621110000 954312057 0 1782341632 0.0117775127 0.0683157071 0.0195903219 336 1305031240.7079319954 0.0910624787 0.0802739057 0.1295797974 0.0227602717 0.7735360000 954313875 0 1783992320 0.0119713629 0.0637119561 0.0210657362 337 1305031240.7439579964 0.0884324238 0.0802981150 0.1295797974 0.0227458950 0.7956190000 954315661 0 1782497280 0.0127215395 0.0594609976 0.0218018722 338 1305031240.7768330574 0.0852148086 0.0803126614 0.1295797974 0.0227169483 0.8126360000 954317511 0 1784152064 0.0133230407 0.0522048846 0.0197867751 339 1305031240.8096249104 0.0826989338 0.0803197005 0.1295797974 0.0226956853 0.8248800000 954319297 0 1782751232 0.0126924952 0.0473045707 0.0200401917 340 1305031240.8425960541 0.0782732144 0.0803136815 0.1295797974 0.0226732048 0.8243490000 954321083 0 1784500224 0.0082834819 0.0453824438 0.0198943354 341 1305031240.8794100285 0.0755575001 0.0802997337 0.1295797974 0.0226534737 0.8282720000 954322965 0 1782976512 0.0054981401 0.0420738570 0.0183791984 342 1305031240.9084498882 0.0712238401 0.0802731960 0.1295797974 0.0226318944 0.8162050000 954324719 0 1781747712 0.0000843946 0.0388337933 0.0168538038 343 1305031240.9423189163 0.0638856068 0.0802254188 0.1295797974 0.0226276248 0.8473830000 954326505 0 1783500800 -0.0231435895 0.0359023251 0.0040159607 344 1305031240.9779360294 0.0637287870 0.0801774635 0.1295797974 0.0225955505 0.8331350000 954328355 0 1782226944 -0.0262684990 0.0320363902 0.0039099138 345 1305031241.0083029270 0.0612675957 0.0801226523 0.1295797974 0.0226740777 0.8615510000 954330109 0 1783881728 -0.0340586454 0.0338816717 0.0056924652 346 1305031241.0401480198 0.0595988519 0.0800633349 0.1295797974 0.0227232969 0.8700900000 954331831 0 1782468608 -0.0436745733 0.0330763496 0.0066810492 347 1305031241.0759329796 0.0611878335 0.0800089387 0.1295797974 0.0227126857 0.9074730000 954333713 0 1784119296 -0.0491103344 0.0304803830 0.0071426490 348 1305031241.1065559387 0.0646406412 0.0799647769 0.1295797974 0.0226875927 0.8904910000 954335467 0 1782595584 -0.0595326498 0.0271305777 0.0069605093 349 1305031241.1400520802 0.0706493184 0.0799380850 0.1295797974 0.0226868647 0.9000650000 954337253 0 1784246272 -0.0695927218 0.0248962343 0.0059512509 350 1305031241.1781818867 0.0757517144 0.0799261240 0.1295797974 0.0227428850 0.9139850000 954339135 0 1782849536 -0.0778651610 0.0258805081 0.0070745540 351 1305031241.2106790543 0.0773339570 0.0799187389 0.1295797974 0.0227150522 0.9048580000 954340953 0 1784500224 -0.0814076811 0.0260321498 0.0097356588 352 1305031241.2393150330 0.0762127191 0.0799082104 0.1295797974 0.0227335947 0.8537110000 954342643 0 1783021568 -0.0765094385 0.0227702335 0.0132093597 353 1305031241.2768468857 0.0719942749 0.0798857913 0.1295797974 0.0227344158 0.8484860000 954344557 0 1781751808 -0.0678381473 0.0223626979 0.0188281331 354 1305031241.3063299656 0.0490680896 0.0797987357 0.1295797974 0.0227581655 0.8123820000 954346311 0 1783394304 -0.0218496844 0.0323123261 0.0535193346 355 1305031241.3424758911 0.0516264960 0.0797193772 0.1295797974 0.0227403205 0.7526620000 954348161 0 1781833728 -0.0113497600 0.0333251730 0.0659726784 356 1305031241.3795149326 0.0557838567 0.0796521426 0.1295797974 0.0227823608 0.6929430000 954350011 0 1783492608 -0.0127720833 0.0294073988 0.0666364431 357 1305031241.4096820354 0.0599054433 0.0795968298 0.1295797974 0.0227800496 0.6750450000 954351765 0 1782145024 -0.0148773789 0.0260288678 0.0674847513 358 1305031241.4455459118 0.0641450882 0.0795536685 0.1295797974 0.0227675140 0.6791670000 954353615 0 1783746560 -0.0169269014 0.0240909494 0.0703117326 359 1305031241.4775071144 0.0677322447 0.0795207397 0.1295797974 0.0229924139 0.6721460000 954355401 0 1782349824 -0.0175399873 0.0213018097 0.0719196722 360 1305031241.5098490715 0.0708204135 0.0794965721 0.1295797974 0.0229911965 0.6606410000 954357187 0 1784016896 -0.0184831675 0.0185735933 0.0723845810 361 1305031241.5477299690 0.0730936602 0.0794788355 0.1295797974 0.0229628485 0.6550380000 954359101 0 1782632448 -0.0192281529 0.0159372315 0.0720731542 362 1305031241.5783948898 0.0736676976 0.0794627827 0.1295797974 0.0229458717 0.6495410000 954360823 0 1784254464 -0.0195822921 0.0152308745 0.0714280382 363 1305031241.6092638969 0.0745733604 0.0794493132 0.1295797974 0.0229408123 0.6539220000 954362577 0 1782886400 -0.0192052815 0.0136400172 0.0702881366 364 1305031241.6475839615 0.0765647963 0.0794413887 0.1295797974 0.0229130263 0.6490850000 954364491 0 1784508416 -0.0182416458 0.0107042547 0.0683075562 365 1305031241.6783659458 0.0733771622 0.0794247744 0.1295797974 0.0229321220 0.6648520000 954366277 0 1783111680 -0.0176954139 0.0137824174 0.0669144541 366 1305031241.7098269463 0.0718578622 0.0794040997 0.1295797974 0.0229120832 0.6589030000 954367999 0 1781510144 -0.0167267397 0.0153979603 0.0654537156 367 1305031241.7471020222 0.0703346655 0.0793793874 0.1295797974 0.0228862452 0.6580450000 954369913 0 1783140352 -0.0161211360 0.0164996311 0.0642073005 368 1305031241.7782680988 0.0703621730 0.0793548841 0.1295797974 0.0228747628 0.6799710000 954371699 0 1781452800 -0.0154070407 0.0163680352 0.0630939528 369 1305031241.8098289967 0.0686762109 0.0793259446 0.1295797974 0.0228740174 0.6493500000 954373421 0 1783140352 -0.0153168654 0.0184567738 0.0623516813 370 1305031241.8464360237 0.0701380521 0.0793011125 0.1295797974 0.0228777683 0.6568490000 954375303 0 1781493760 -0.0151975546 0.0162452646 0.0609022528 371 1305031241.8787989616 0.0701524094 0.0792764529 0.1295797974 0.0229589682 0.6611000000 954377121 0 1783103488 -0.0157831796 0.0164535102 0.0598199368 372 1305031241.9114871025 0.0676777139 0.0792452735 0.1295797974 0.0229881471 0.6757470000 954378907 0 1781366784 -0.0166007690 0.0193172786 0.0599490814 373 1305031241.9477050304 0.0684767216 0.0792164034 0.1295797974 0.0229916024 0.6694610000 954380757 0 1782992896 -0.0166679621 0.0185306668 0.0595938526 374 1305031241.9783430099 0.0684207305 0.0791875379 0.1295797974 0.0231305529 0.6774150000 954382543 0 1781198848 -0.0177404769 0.0185232013 0.0588594116 375 1305031242.0105700493 0.0680027157 0.0791577117 0.1295797974 0.0232433071 0.6689020000 954384297 0 1782865920 -0.0193269085 0.0190250371 0.0580986440 376 1305031242.0463600159 0.0690481737 0.0791308247 0.1295797974 0.0233406361 0.7203470000 954386147 0 1781510144 -0.0207235292 0.0180945266 0.0567985699 377 1305031242.0795490742 0.0707019269 0.0791084668 0.1295797974 0.0234732743 0.6670890000 954387933 0 1783103488 -0.0225942638 0.0162485708 0.0548992455 378 1305031242.1105840206 0.0725809261 0.0790911982 0.1295797974 0.0235794821 0.6704910000 954389719 0 1781493760 -0.0253178328 0.0132832313 0.0523691140 379 1305031242.1466050148 0.0748236850 0.0790799383 0.1295797974 0.0237354708 0.6580130000 954391569 0 1782992896 -0.0279091708 0.0102775823 0.0498270094 380 1305031242.1797080040 0.0772754326 0.0790751896 0.1295797974 0.0238389459 0.6613250000 954393387 0 1781452800 -0.0305877253 0.0066169947 0.0473418608 381 1305031242.2087249756 0.0793525055 0.0790759175 0.1295797974 0.0238893235 0.6483150000 954395109 0 1782992896 -0.0336042047 0.0026323989 0.0450403132 382 1305031242.2478089333 0.0815751329 0.0790824599 0.1295797974 0.0239648366 0.6392210000 954397023 0 1781493760 -0.0359091014 -0.0014814094 0.0429472029 383 1305031242.2794981003 0.0829075202 0.0790924470 0.1295797974 0.0240209020 0.6359480000 954398809 0 1782976512 -0.0384210721 -0.0040538968 0.0405429490 384 1305031242.3097639084 0.0845302641 0.0791066080 0.1295797974 0.0240628276 0.6276160000 954400531 0 1781493760 -0.0402849764 -0.0071788337 0.0381000899 385 1305031242.3471269608 0.0860189199 0.0791245620 0.1295797974 0.0241852537 0.6301130000 954402445 0 1782992896 -0.0420610644 -0.0103740767 0.0353783593 386 1305031242.3784790039 0.0864617676 0.0791435704 0.1295797974 0.0243062226 0.6272500000 954404231 0 1781452800 -0.0435441583 -0.0120424442 0.0335434936 387 1305031242.4109969139 0.0875937045 0.0791654053 0.1295797974 0.0243784971 0.6206740000 954406017 0 1782992896 -0.0445547625 -0.0143069923 0.0313183330 388 1305031242.4470989704 0.0886885449 0.0791899495 0.1295797974 0.0245380472 0.6285000000 954407899 0 1781493760 -0.0459144935 -0.0167481098 0.0283896253 389 1305031242.4776470661 0.0901900828 0.0792182275 0.1295797974 0.0246528239 0.6183820000 954409685 0 1782976512 -0.0473507233 -0.0185308959 0.0248389635 390 1305031242.5097260475 0.0921092257 0.0792512813 0.1295797974 0.0249246300 0.6228460000 954411471 0 1781493760 -0.0491550341 -0.0207645297 0.0206054561 391 1305031242.5485460758 0.0930131599 0.0792864779 0.1295797974 0.0253968361 0.6266250000 954413385 0 1782976512 -0.0521493554 -0.0210514646 0.0166722964 392 1305031242.5748429298 0.0942614451 0.0793246794 0.1295797974 0.0255648761 0.6630030000 954415043 0 1781383168 -0.0550268441 -0.0207979772 0.0125758350 393 1305031242.6061151028 0.0962528735 0.0793677537 0.1295797974 0.0256754974 0.6271960000 954416861 0 1782992896 -0.0577693731 -0.0219503902 0.0086115096 394 1305031242.6438109875 0.0989384428 0.0794174255 0.1295797974 0.0259313114 0.6303150000 954418743 0 1781325824 -0.0612712465 -0.0232944395 0.0047574863 395 1305031242.6752018929 0.1001919582 0.0794700192 0.1295797974 0.0262569393 0.6357890000 954420561 0 1783009280 -0.0648905858 -0.0233864635 0.0020101089 396 1305031242.7139821053 0.1023000777 0.0795276709 0.1295797974 0.0266562652 0.6479210000 954422507 0 1781383168 -0.0689352229 -0.0229685307 -0.0011681058 397 1305031242.7452580929 0.1050863713 0.0795920505 0.1295797974 0.0267517595 0.6514960000 954424293 0 1782976512 -0.0730215758 -0.0229742825 -0.0050448757 398 1305031242.7775399685 0.1076173931 0.0796624659 0.1295797974 0.0269239640 0.6531370000 954426111 0 1781383168 -0.0773488432 -0.0235488415 -0.0080723464 399 1305031242.8140709400 0.1100239158 0.0797385598 0.1295797974 0.0271501111 0.6589150000 954427993 0 1783119872 -0.0815419778 -0.0227874368 -0.0099141132 400 1305031242.8443179131 0.1120034680 0.0798192220 0.1295797974 0.0272090882 0.7078600000 954429779 0 1781452800 -0.0846111551 -0.0216773394 -0.0116563020 401 1305031242.8740880489 0.1151208207 0.0799072560 0.1295797974 0.0272604327 0.6672700000 954431597 0 1783119872 -0.0882244781 -0.0217914842 -0.0133867878 402 1305031242.9137070179 0.1194919795 0.0800057254 0.1295797974 0.0273664623 0.6644350000 954433575 0 1781510144 -0.0933642015 -0.0214225687 -0.0161538143 403 1305031242.9444379807 0.1208875477 0.0801071691 0.1295797974 0.0275461176 0.6691030000 954435361 0 1783103488 -0.0980636626 -0.0188610666 -0.0175016169 404 1305031242.9760620594 0.1220008656 0.0802108664 0.1295797974 0.0276091392 0.6696020000 954437147 0 1781579776 -0.1037625149 -0.0157514382 -0.0194833633 405 1305031243.0141661167 0.1242908239 0.0803197058 0.1295797974 0.0276726402 0.6570990000 954439061 0 1783119872 -0.1088742614 -0.0138542857 -0.0207917131 406 1305031243.0469100475 0.1255471557 0.0804311035 0.1295797974 0.0276762105 0.6596840000 954440975 0 1781579776 -0.1133888215 -0.0121776024 -0.0217385720 407 1305031243.0780448914 0.1265187562 0.0805443410 0.1295797974 0.0276686018 0.6611300000 954442793 0 1783103488 -0.1170124486 -0.0097153382 -0.0236529298 408 1305031243.1136150360 0.1262003779 0.0806562430 0.1295797974 0.0276766767 0.6943440000 954444643 0 1781522432 -0.1199379191 -0.0065168096 -0.0249497686 409 1305031243.1458160877 0.1259854883 0.0807670725 0.1295797974 0.0276448676 0.6571170000 954446493 0 1783111680 -0.1227343753 -0.0037163924 -0.0268901419 410 1305031243.1780760288 0.1248663515 0.0808746317 0.1295797974 0.0276379134 0.6665870000 954448311 0 1781460992 -0.1244405061 -0.0027186095 -0.0275544673 411 1305031243.2136580944 0.1239816770 0.0809795150 0.1295797974 0.0276746974 0.6703960000 954450193 0 1783017472 -0.1237317398 -0.0048542665 -0.0267316476 412 1305031243.2455608845 0.1258023232 0.0810883082 0.1295797974 0.0279824370 0.6688700000 954452011 0 1781501952 -0.1226889044 -0.0087196641 -0.0271341261 413 1305031243.2781798840 0.1269435734 0.0811993379 0.1295797974 0.0280905701 0.6665380000 954453861 0 1782984704 -0.1210124046 -0.0132730920 -0.0265009031 414 1305031243.3142709732 0.1271736324 0.0813103869 0.1295797974 0.0281682786 0.6641300000 954455711 0 1781374976 -0.1177713647 -0.0157647543 -0.0246124193 415 1305031243.3460359573 0.1277125776 0.0814221994 0.1295797974 0.0285289295 0.6584270000 954457561 0 1782890496 -0.1142790690 -0.0175339784 -0.0233882144 416 1305031243.3789350986 0.1278471202 0.0815337978 0.1295797974 0.0285884489 0.7109240000 954459411 0 1781334016 -0.1118619293 -0.0186617151 -0.0208844766 417 1305031243.4139740467 0.1171708032 0.0816192583 0.1295797974 0.0286641134 0.7180450000 954461261 0 1782890496 -0.0979001820 -0.0096650142 -0.0106482953 418 1305031243.4470911026 0.1197912917 0.0817105789 0.1295797974 0.0289158015 0.6724830000 954463111 0 1781391360 -0.0987067595 -0.0108950939 -0.0105886664 419 1305031243.4780371189 0.1194239631 0.0818005870 0.1295797974 0.0289579790 0.6769680000 954464897 0 1782857728 -0.0977125093 -0.0076131211 -0.0090089217 420 1305031243.5154008865 0.1174576804 0.0818854848 0.1295797974 0.0290909923 0.6918650000 954466811 0 1781383168 -0.0984184891 -0.0017006068 -0.0073409444 421 1305031243.5459430218 0.1187491044 0.0819730469 0.1295797974 0.0291742901 0.6580200000 954468629 0 1782992896 -0.1005375162 -0.0011013316 -0.0070884787 422 1305031243.5779840946 0.1148615032 0.0820509816 0.1295797974 0.0291830900 0.6945670000 954470383 0 1781325824 -0.1000341699 0.0051244223 -0.0049525057 423 1305031243.6140549183 0.1137786806 0.0821259880 0.1295797974 0.0294701512 0.6809380000 954472233 0 1782976512 -0.1002460718 0.0084074354 -0.0040790183 424 1305031243.6461870670 0.1163091287 0.0822066086 0.1295797974 0.0298061282 0.6596800000 954474083 0 1781383168 -0.1022400409 0.0052862000 -0.0057378639 425 1305031243.6782801151 0.1186157316 0.0822922771 0.1295797974 0.0298684543 0.6657280000 954475869 0 1782976512 -0.1034998894 0.0023478090 -0.0067626955 426 1305031243.7142961025 0.1095173210 0.0823561857 0.1295797974 0.0302072230 0.7214470000 954477687 0 1781452800 -0.0956255645 0.0111301113 -0.0014504716 427 1305031243.7473781109 0.1113624424 0.0824241160 0.1295797974 0.0305436979 0.6730700000 954479505 0 1782992896 -0.0957850516 0.0065376614 -0.0022949427 428 1305031243.7790360451 0.1126841083 0.0824948169 0.1295797974 0.0307692478 0.6958130000 954481259 0 1781493760 -0.0952763036 0.0022316659 -0.0022187307 429 1305031243.8141930103 0.1016049683 0.0825393627 0.1295797974 0.0312438928 0.7679820000 954483077 0 1782976512 -0.0800127536 0.0086070374 0.0069709467 430 1305031243.8462920189 0.1040709317 0.0825894362 0.1295797974 0.0316405482 0.7357130000 954484863 0 1781452800 -0.0751363039 0.0035493216 0.0065485910 431 1305031243.8788089752 0.0981697664 0.0826255854 0.1295797974 0.0317930303 0.7923630000 954486681 0 1782992896 -0.0642369986 0.0066222632 0.0135061443 432 1305031243.9140000343 0.0947812051 0.0826537234 0.1295797974 0.0321020874 0.8101650000 954488467 0 1781493760 -0.0609565154 0.0071364772 0.0152099095 433 1305031243.9470779896 0.0844660774 0.0826579090 0.1295797974 0.0322244050 0.8370070000 954490317 0 1783119872 -0.0491248257 0.0176409762 0.0250297245 434 1305031243.9816520214 0.0820285529 0.0826564589 0.1295797974 0.0323694839 0.8084210000 954492135 0 1781579776 -0.0488210134 0.0189713743 0.0252223574 435 1305031244.0112700462 0.0793473646 0.0826488518 0.1295797974 0.0324438132 0.8156580000 954493889 0 1783230464 -0.0482702553 0.0211390220 0.0259181913 436 1305031244.0438230038 0.0710066557 0.0826221495 0.1295797974 0.0324471556 0.8646550000 954495675 0 1781960704 -0.0497194156 0.0329067744 0.0287491791 437 1305031244.0818090439 0.0670771152 0.0825865773 0.1295797974 0.0324753442 0.8642730000 954497557 0 1783627776 -0.0484813340 0.0379889160 0.0321180560 438 1305031244.1127901077 0.0677443072 0.0825526908 0.1295797974 0.0325456591 0.8955700000 954499343 0 1782239232 -0.0476500615 0.0378528722 0.0329638720 439 1305031244.1484949589 0.0643177330 0.0825111534 0.1295797974 0.0325436608 0.9040110000 954501193 0 1784008704 -0.0516330712 0.0438056402 0.0338502005 440 1305031244.1824309826 0.0619095676 0.0824643316 0.1295797974 0.0326180641 0.8999010000 954502979 0 1782620160 -0.0527307019 0.0462989584 0.0359658487 441 1305031244.2124009132 0.0611713603 0.0824160482 0.1295797974 0.0327288132 0.9113830000 954504765 0 1784279040 -0.0525853708 0.0493674353 0.0371634699 442 1305031244.2473471165 0.0573360883 0.0823593062 0.1295797974 0.0328843195 0.9284780000 954506583 0 1782976512 -0.0528028160 0.0560849980 0.0391254611 443 1305031244.2831470966 0.0559703521 0.0822997375 0.1295797974 0.0330241101 0.9325780000 954508433 0 1781579776 -0.0508018173 0.0594542548 0.0403140150 444 1305031244.3137950897 0.0480234064 0.0822225385 0.1295797974 0.0331416519 0.9631320000 954510155 0 1783230464 -0.0445609502 0.0699393004 0.0461944826 445 1305031244.3459599018 0.0427696481 0.0821338803 0.1295797974 0.0333068550 0.9572450000 954511973 0 1782087680 -0.0344680250 0.0792955309 0.0532602221 446 1305031244.3808560371 0.0427345075 0.0820455409 0.1295797974 0.0334772036 0.9470970000 954513791 0 1783865344 -0.0265499111 0.0841694251 0.0566374138 447 1305031244.4130189419 0.0434958786 0.0819593001 0.1295797974 0.0336958352 0.9417690000 954515577 0 1782468608 -0.0180360042 0.0910221711 0.0610300750 448 1305031244.4451670647 0.0415289812 0.0818690538 0.1295797974 0.0337665637 0.9326400000 954517363 0 1784246272 -0.0164743736 0.1002349332 0.0621329434 449 1305031244.4806590080 0.0406250767 0.0817771964 0.1295797974 0.0338419724 0.8766260000 954519213 0 1782976512 -0.0190077852 0.1046170667 0.0591669604 450 1305031244.5142281055 0.0411134511 0.0816868325 0.1295797974 0.0339420938 0.8671390000 954521031 0 1781768192 -0.0205037314 0.1091363356 0.0581199750 451 1305031244.5462141037 0.0375862680 0.0815890486 0.1295797974 0.0339213683 0.8938620000 954522817 0 1783537664 -0.0229808521 0.1182077080 0.0604944304 452 1305031244.5808050632 0.0365438573 0.0814893911 0.1295797974 0.0339708260 0.8560270000 954524635 0 1782099968 -0.0259925462 0.1194281280 0.0605197027 453 1305031244.6132769585 0.0363861993 0.0813898255 0.1295797974 0.0340550853 0.8495910000 954526453 0 1783779328 -0.0278290026 0.1206989139 0.0609843731 454 1305031244.6428399086 0.0347258560 0.0812870415 0.1295797974 0.0340467407 0.8529460000 954528175 0 1782501376 -0.0296849180 0.1231316626 0.0622178577 455 1305031244.6806099415 0.0332264826 0.0811814139 0.1295797974 0.0341043232 0.8541350000 954530025 0 1784127488 -0.0296831746 0.1270375699 0.0656112432 456 1305031244.7152500153 0.0319921300 0.0810735426 0.1295797974 0.0341269270 0.8629640000 954531875 0 1782730752 -0.0332497619 0.1286233664 0.0657504573 457 1305031244.7458879948 0.0323278718 0.0809668781 0.1295797974 0.0343122795 0.8265260000 954533629 0 1781460992 -0.0353724286 0.1289492846 0.0654233992 458 1305031244.7818510532 0.0328346007 0.0808617858 0.1295797974 0.0344014017 0.8304560000 954535511 0 1783136256 -0.0354950875 0.1293486804 0.0650706664 459 1305031244.8140940666 0.0285854340 0.0807478940 0.1295797974 0.0352634626 0.8721140000 954537297 0 1781747712 -0.0298539288 0.1333308965 0.0697034746 460 1305031244.8418219090 0.0283323023 0.0806339471 0.1295797974 0.0352500918 0.8417820000 954538987 0 1783369728 -0.0290100351 0.1350966096 0.0691996813 461 1305031244.8818008900 0.0249975622 0.0805132608 0.1295797974 0.0352212761 0.8702550000 954540901 0 1781981184 -0.0281343572 0.1418773234 0.0703408420 462 1305031244.9149079323 0.0252099149 0.0803935565 0.1295797974 0.0352032311 0.8796330000 954542687 0 1783738368 -0.0284162275 0.1434118897 0.0693976358 463 1305031244.9458680153 0.0246506501 0.0802731615 0.1295797974 0.0351667012 0.8420510000 954544441 0 1782468608 -0.0276739579 0.1463747919 0.0697221309 464 1305031244.9818000793 0.0249849614 0.0801540059 0.1295797974 0.0351882230 0.8462890000 954546291 0 1784119296 -0.0269650482 0.1496369392 0.0710279271 465 1305031245.0140550137 0.0240912456 0.0800334408 0.1295797974 0.0351527302 0.8499990000 954548077 0 1783259136 -0.0245113876 0.1508000493 0.0733076558 466 1305031245.0464398861 0.0245309360 0.0799143367 0.1295797974 0.0351182405 0.8510140000 954549863 0 1781981184 -0.0250591934 0.1526230872 0.0736689195 467 1305031245.0817689896 0.0239969138 0.0797945992 0.1295797974 0.0350983223 0.8540680000 954551713 0 1783771136 -0.0233964100 0.1533291042 0.0768660307 468 1305031245.1143150330 0.0257162284 0.0796790471 0.1295797974 0.0350977878 0.8972270000 954553467 0 1782599680 -0.0225172713 0.1524307877 0.0779830441 469 1305031245.1457099915 0.0275413413 0.0795678793 0.1295797974 0.0350826268 0.8782690000 954555285 0 1784406016 -0.0231446903 0.1518720984 0.0789006501 470 1305031245.1818709373 0.0300025884 0.0794624212 0.1295797974 0.0350951142 0.8896940000 954557103 0 1783230464 -0.0212230776 0.1488753408 0.0808179602 471 1305031245.2140939236 0.0344743580 0.0793669052 0.1295797974 0.0351733028 0.9078740000 954558889 0 1782087680 -0.0199465286 0.1432473511 0.0804411918 472 1305031245.2487950325 0.0326301344 0.0792678866 0.1295797974 0.0355131832 0.9569620000 954560739 0 1783865344 -0.0317074545 0.1416426301 0.0723670051 473 1305031245.2807950974 0.0342664458 0.0791727461 0.1295797974 0.0356043585 0.9625330000 954562493 0 1782849536 -0.0357683674 0.1364401877 0.0682401657 474 1305031245.3143179417 0.0366699547 0.0790830778 0.1295797974 0.0357506363 0.9405550000 954564279 0 1781706752 -0.0316831805 0.1303603798 0.0696006939 475 1305031245.3491809368 0.0366929844 0.0789938355 0.1295797974 0.0359930281 0.9813200000 954566161 0 1783246848 -0.0364387594 0.1242112368 0.0631874278 476 1305031245.3806860447 0.0390971787 0.0789100190 0.1295797974 0.0362056437 0.9878210000 954567883 0 1781960704 -0.0378173664 0.1161845177 0.0569160506 477 1305031245.4133110046 0.0414691307 0.0788315266 0.1295797974 0.0363658423 0.9839390000 954569669 0 1783738368 -0.0418213420 0.1095234901 0.0493544824 478 1305031245.4489970207 0.0472311862 0.0787654171 0.1295797974 0.0363573355 0.9905100000 954571487 0 1782341632 -0.0406613462 0.0984958038 0.0418552011 479 1305031245.4846711159 0.0486051254 0.0787024520 0.1295797974 0.0365995859 0.9715370000 954573337 0 1784246272 -0.0385950767 0.0953913182 0.0399649814 480 1305031245.5124320984 0.0508999377 0.0786445300 0.1295797974 0.0366845004 0.9999610000 954575059 0 1782722560 -0.0450599752 0.0900338814 0.0316156484 481 1305031245.5481460094 0.0521992147 0.0785895502 0.1295797974 0.0368459750 0.9962190000 954576877 0 1781706752 -0.0466275625 0.0863407105 0.0281631108 482 1305031245.5786890984 0.0551510490 0.0785409226 0.1295797974 0.0368606682 1.0110960000 954578663 0 1783484416 -0.0516527407 0.0804993734 0.0212376155 483 1305031245.6104750633 0.0587519147 0.0784999516 0.1295797974 0.0369383883 1.0190400000 954580417 0 1782087680 -0.0539008491 0.0750745386 0.0158689525 484 1305031245.6494629383 0.0591743216 0.0784600226 0.1295797974 0.0371264810 1.0061230000 954582299 0 1783738368 -0.0585751310 0.0726416335 0.0124083301 485 1305031245.6802349091 0.0611500144 0.0784243318 0.1295797974 0.0371472920 1.0423620000 954584085 0 1782341632 -0.0626689568 0.0694910735 0.0092365332 486 1305031245.7110319138 0.0614977740 0.0783895035 0.1295797974 0.0371659623 0.9649440000 954585871 0 1784119296 -0.0614398941 0.0676305890 0.0093088085 487 1305031245.7497749329 0.0640828982 0.0783601265 0.1295797974 0.0372266836 0.9795640000 954587753 0 1782849536 -0.0666444674 0.0645480603 0.0053310674 488 1305031245.7818500996 0.0646265745 0.0783319840 0.1295797974 0.0372847585 0.9329210000 954589571 0 1784500224 -0.0629309267 0.0648866445 0.0060675815 489 1305031245.8135690689 0.0655949488 0.0783059369 0.1295797974 0.0373946081 0.9234120000 954591325 0 1783103488 -0.0616253167 0.0645288900 0.0063546216 490 1305031245.8491089344 0.0677576810 0.0782844098 0.1295797974 0.0374271642 0.8883990000 954593175 0 1781968896 -0.0596939474 0.0621672198 0.0057645626 491 1305031245.8820281029 0.0696831122 0.0782668919 0.1295797974 0.0374544219 0.8735640000 954594993 0 1783799808 -0.0582571030 0.0592594147 0.0053067724 492 1305031245.9126079082 0.0724525452 0.0782550741 0.1295797974 0.0374662269 0.8420960000 954596747 0 1782394880 -0.0566116720 0.0559042618 0.0044441679 493 1305031245.9458959103 0.0746103749 0.0782476812 0.1295797974 0.0375204876 0.8308000000 954598533 0 1784053760 -0.0564484596 0.0520708486 0.0033198884 494 1305031245.9808180332 0.0763283744 0.0782437960 0.1295797974 0.0375552046 0.7995280000 954600383 0 1782603776 -0.0574433841 0.0493546985 0.0013261475 495 1305031246.0110030174 0.0792287588 0.0782457858 0.1295797974 0.0375718676 0.7809020000 954602137 0 1784381440 -0.0584182441 0.0454234481 -0.0017339420 496 1305031246.0483930111 0.0837166533 0.0782568158 0.1295797974 0.0376441379 0.8001600000 954604051 0 1782984704 -0.0641827658 0.0386401787 -0.0078115147 497 1305031246.0805249214 0.0861244053 0.0782726460 0.1295797974 0.0377165440 0.7590960000 954605773 0 1781637120 -0.0647986457 0.0358182378 -0.0098740878 498 1305031246.1123559475 0.0884245336 0.0782930313 0.1295797974 0.0378229233 0.7899070000 954607591 0 1783369728 -0.0656163767 0.0331184343 -0.0119042005 499 1305031246.1484489441 0.0909317434 0.0783183593 0.1295797974 0.0379387576 0.7587010000 954609409 0 1782087680 -0.0666274801 0.0303920154 -0.0142810093 500 1305031246.1805961132 0.0929375142 0.0783475977 0.1295797974 0.0379977737 0.7597510000 954611163 0 1783738368 -0.0691111758 0.0284097362 -0.0171778388 501 1305031246.2111370564 0.0990475789 0.0783889150 0.1295797974 0.0380807100 0.7897050000 954612949 0 1782366208 -0.0790097117 0.0203405991 -0.0250568725 502 1305031246.2469689846 0.1004516333 0.0784328646 0.1295797974 0.0382214749 0.7541000000 954614799 0 1784156160 -0.0802551210 0.0193396658 -0.0267050415 503 1305031246.2796959877 0.1064147577 0.0784884946 0.1295797974 0.0382838802 0.7899970000 954616585 0 1782349824 -0.0871981606 0.0129481638 -0.0331301428 504 1305031246.3124730587 0.1073363945 0.0785457325 0.1295797974 0.0384204680 0.7668080000 954618403 0 1783992320 -0.0884072557 0.0140739977 -0.0345381498 505 1305031246.3482720852 0.1132735536 0.0786145005 0.1295797974 0.0385344309 0.7937470000 954620253 0 1782595584 -0.0956368670 0.0088085709 -0.0400722884 506 1305031246.3782060146 0.1135605797 0.0786835639 0.1295797974 0.0386964420 0.7670770000 954622007 0 1784532992 -0.0979917571 0.0110986065 -0.0410610139 507 1305031246.4156370163 0.1147010699 0.0787546043 0.1295797974 0.0388629612 0.7694970000 954623921 0 1783169024 -0.1014083400 0.0129856206 -0.0417437889 508 1305031246.4452888966 0.1150896028 0.0788261299 0.1295797974 0.0389643115 0.7846070000 954625675 0 1781895168 -0.1031575277 0.0156328809 -0.0420190282 509 1305031246.4774649143 0.1220853850 0.0789111186 0.1295797974 0.0390481416 0.8065970000 954627525 0 1783484416 -0.1150581241 0.0107015520 -0.0484138727 510 1305031246.5163950920 0.1219491288 0.0789955069 0.1295797974 0.0391904795 0.7956240000 954629439 0 1781833728 -0.1164385080 0.0149455182 -0.0478681177 511 1305031246.5491750240 0.1213073358 0.0790783089 0.1295797974 0.0393245871 0.7926830000 954631289 0 1783644160 -0.1183938980 0.0185695160 -0.0472667962 512 1305031246.5795109272 0.1201718524 0.0791585697 0.1295797974 0.0394248425 0.8247400000 954633075 0 1782226944 -0.1197076365 0.0227439050 -0.0463647470 513 1305031246.6164529324 0.1255437732 0.0792489892 0.1295797974 0.0394877353 0.8245960000 954634989 0 1783898112 -0.1274385154 0.0213403869 -0.0505765155 514 1305031246.6477630138 0.1250527203 0.0793381015 0.1295797974 0.0395504419 0.8023600000 954720775 0 1782468608 -0.1282604933 0.0261265021 -0.0505671725 515 1305031246.6807579994 0.1237202063 0.0794242804 0.1295797974 0.0396458075 0.7946310000 954722625 0 1784119296 -0.1292571425 0.0298555885 -0.0497273728 516 1305031246.7169740200 0.1241835058 0.0795110231 0.1295797974 0.0397868641 0.7981950000 954724539 0 1782595584 -0.1305302233 0.0327554792 -0.0503497496 517 1305031246.7491660118 0.1236005276 0.0795963026 0.1295797974 0.0398774397 0.7917060000 954726357 0 1784279040 -0.1316521168 0.0368509330 -0.0511480644 518 1305031246.7808170319 0.1235524714 0.0796811601 0.1295797974 0.0399455978 0.7911200000 954728207 0 1782734848 -0.1337138265 0.0395593755 -0.0520005412 519 1305031246.8168079853 0.1259293556 0.0797702703 0.1295797974 0.0400118322 0.7799470000 954730121 0 1784373248 -0.1362836063 0.0425410606 -0.0554399379 520 1305031246.8488121033 0.1258436888 0.0798588730 0.1295797974 0.0400400827 0.7758430000 954731971 0 1782849536 -0.1386839002 0.0452236943 -0.0569401532 521 1305031246.8806428909 0.1252965480 0.0799460854 0.1295797974 0.0401138157 0.7622250000 954733821 0 1784532992 -0.1410141140 0.0478826649 -0.0582552105 522 1305031246.9166710377 0.1311865747 0.0800442473 0.1311865747 0.0401704884 0.8034280000 954735735 0 1783005184 -0.1505985707 0.0456134900 -0.0657283142 523 1305031246.9495339394 0.1318816245 0.0801433627 0.1318816245 0.0401747705 0.7703430000 954737585 0 1781489664 -0.1500330120 0.0492275283 -0.0683927014 524 1305031246.9775969982 0.1363984644 0.0802507198 0.1363984644 0.0401548149 0.7664160000 954739339 0 1783103488 -0.1552871168 0.0478185304 -0.0733276382 525 1305031247.0167899132 0.1333350688 0.0803518328 0.1363984644 0.0402457967 0.7337910000 954741285 0 1781579776 -0.1548444480 0.0517589748 -0.0734979808 526 1305031247.0479340553 0.1400362849 0.0804653014 0.1400362849 0.0402171712 0.7500190000 954743135 0 1783390208 -0.1645175815 0.0487916507 -0.0812034979 527 1305031247.0778899193 0.1342473030 0.0805673545 0.1400362849 0.0402096374 0.6963520000 954744953 0 1781641216 -0.1618457139 0.0542667285 -0.0804422721 528 1305031247.1162130833 0.1300584227 0.0806610876 0.1400362849 0.0401827992 0.6848910000 954746899 0 1783357440 -0.1603836864 0.0589120388 -0.0812821612 529 1305031247.1473660469 0.1364018470 0.0807664576 0.1400362849 0.0401660066 0.7395360000 954748749 0 1781899264 -0.1680254340 0.0563008823 -0.0881260633 530 1305031247.1796920300 0.1346512586 0.0808681271 0.1400362849 0.0401303541 0.6777250000 954750599 0 1783517184 -0.1658589542 0.0562857874 -0.0879155248 531 1305031247.2169430256 0.1326448321 0.0809656350 0.1400362849 0.0401030090 0.6868090000 954752545 0 1782087680 -0.1642447710 0.0559541881 -0.0874354839 532 1305031247.2487928867 0.1304334253 0.0810586196 0.1400362849 0.0400794630 0.6877260000 954754363 0 1783738368 -0.1627868265 0.0554785803 -0.0861315951 533 1305031247.2794220448 0.1323535740 0.0811548577 0.1400362849 0.0400598454 0.6928340000 954756181 0 1782099968 -0.1627532840 0.0530920625 -0.0875191540 534 1305031247.3166429996 0.1355832964 0.0812567837 0.1400362849 0.0400717307 0.7201800000 954758127 0 1783771136 -0.1628611982 0.0475662760 -0.0880707353 535 1305031247.3477900028 0.1386746168 0.0813641067 0.1400362849 0.0401425300 0.6899830000 954759977 0 1782468608 -0.1632802337 0.0443687625 -0.0880495235 536 1305031247.3786110878 0.1401651949 0.0814738102 0.1401651949 0.0401606340 0.6861610000 954761795 0 1784012800 -0.1635672152 0.0413028970 -0.0877771303 537 1305031247.4168620110 0.1373022944 0.0815777739 0.1401651949 0.0401960794 0.7191100000 954763773 0 1782632448 -0.1574277878 0.0426808968 -0.0833977908 538 1305031247.4487700462 0.1374681741 0.0816816594 0.1401651949 0.0403301093 0.7088080000 954765623 0 1784254464 -0.1557472944 0.0430167317 -0.0815146118 539 1305031247.4802629948 0.1353163868 0.0817811672 0.1401651949 0.0403945513 0.7113990000 954767409 0 1782603776 -0.1537254006 0.0447815023 -0.0777932182 540 1305031247.5178461075 0.1361138672 0.0818817834 0.1401651949 0.0404826470 0.7083350000 954769387 0 1784287232 -0.1509196162 0.0446745679 -0.0750591978 541 1305031247.5459010601 0.1351336688 0.0819802157 0.1401651949 0.0405745749 0.7530840000 954771141 0 1782906880 -0.1482127905 0.0448755100 -0.0722303689 542 1305031247.5779209137 0.1341016293 0.0820763806 0.1401651949 0.0406459017 0.7231990000 954772959 0 1784508416 -0.1452590376 0.0454934575 -0.0698814169 543 1305031247.6152799129 0.1336399764 0.0821713412 0.1401651949 0.0407939149 0.7364530000 954774841 0 1782857728 -0.1415846050 0.0458024032 -0.0676480457 544 1305031247.6484000683 0.1360186636 0.0822703253 0.1401651949 0.0409332467 0.6980430000 954776691 0 1781362688 -0.1430344433 0.0422507711 -0.0683300495 545 1305031247.6835579872 0.1306583434 0.0823591106 0.1401651949 0.0410763884 0.7550760000 954778541 0 1783009280 -0.1344435662 0.0446983762 -0.0627586693 546 1305031247.7159609795 0.1274798214 0.0824417493 0.1401651949 0.0412626011 0.7595450000 954780359 0 1781452800 -0.1280742884 0.0462089553 -0.0587410666 547 1305031247.7469019890 0.1251610667 0.0825198468 0.1401651949 0.0415049453 0.7629370000 954782177 0 1782976512 -0.1234813705 0.0455415025 -0.0559481755 548 1305031247.7822608948 0.1285497993 0.0826038430 0.1401651949 0.0417088395 0.7244730000 954784027 0 1781493760 -0.1259609312 0.0364506096 -0.0577050447 549 1305031247.8139829636 0.1308131665 0.0826916560 0.1401651949 0.0419946292 0.7540850000 954785749 0 1782992896 -0.1237057596 0.0308720879 -0.0596755818 550 1305031247.8484420776 0.1241697073 0.0827670706 0.1401651949 0.0421531062 0.8327480000 954787663 0 1781452800 -0.1078427881 0.0362629481 -0.0521816127 551 1305031247.8820719719 0.1271661967 0.0828476498 0.1401651949 0.0422273886 0.7789690000 954789449 0 1783103488 -0.1093709692 0.0308024734 -0.0572240353 552 1305031247.9173319340 0.1226713434 0.0829197942 0.1401651949 0.0422086811 0.8306200000 954791299 0 1781452800 -0.1056614146 0.0377596579 -0.0593266711 553 1305031247.9496860504 0.1210206002 0.0829886926 0.1401651949 0.0422799278 0.8214300000 954793053 0 1783136256 -0.1024844646 0.0393325984 -0.0609174520 554 1305031247.9861450195 0.1227788106 0.0830605159 0.1401651949 0.0424535650 0.8338850000 954794935 0 1781493760 -0.0983716771 0.0339848809 -0.0643278733 555 1305031248.0181560516 0.1210716441 0.0831290044 0.1401651949 0.0424332400 0.8843270000 954796689 0 1783009280 -0.0959626585 0.0346032158 -0.0665508807 556 1305031248.0499138832 0.1155838221 0.0831873764 0.1401651949 0.0424536720 0.9388100000 954798475 0 1781493760 -0.0832318738 0.0416337252 -0.0611470155 557 1305031248.0857460499 0.1146571636 0.0832438751 0.1401651949 0.0426495496 0.8814280000 954800293 0 1782976512 -0.0779437125 0.0386859365 -0.0635971725 558 1305031248.1175789833 0.1135300249 0.0832981514 0.1401651949 0.0426839170 0.9274170000 954802079 0 1781452800 -0.0665886924 0.0406761095 -0.0607106201 559 1305031248.1493461132 0.1101370379 0.0833461637 0.1401651949 0.0426954708 0.8990130000 954803865 0 1783103488 -0.0665564910 0.0417326614 -0.0636362955 560 1305031248.1848630905 0.1065247580 0.0833875540 0.1401651949 0.0428678733 0.9205450000 954805683 0 1781452800 -0.0685760379 0.0403659232 -0.0668888763 561 1305031248.2167689800 0.1044816151 0.0834251548 0.1401651949 0.0428995224 0.9275760000 954807469 0 1783103488 -0.0668750927 0.0418420583 -0.0687734261 562 1305031248.2488510609 0.1027555168 0.0834595505 0.1401651949 0.0429259716 0.9240470000 954809223 0 1781452800 -0.0671732500 0.0408446789 -0.0702081844 563 1305031248.2847399712 0.0964077562 0.0834825491 0.1401651949 0.0429862538 0.9649940000 954811105 0 1783103488 -0.0588225052 0.0509297773 -0.0645399541 564 1305031248.3161809444 0.0930523649 0.0834995169 0.1401651949 0.0430370286 0.9617630000 954812891 0 1781706752 -0.0526784472 0.0590058491 -0.0607217401 565 1305031248.3488430977 0.0958995819 0.0835214639 0.1401651949 0.0431053638 0.9286320000 954814645 0 1783246848 -0.0488808043 0.0549760275 -0.0619989820 566 1305031248.3881969452 0.0955112651 0.0835426473 0.1401651949 0.0431103222 0.9507570000 954816559 0 1781878784 -0.0456663370 0.0569167100 -0.0614438727 567 1305031248.4155070782 0.0950870588 0.0835630078 0.1401651949 0.0431403086 0.9794370000 954818281 0 1783496704 -0.0430767126 0.0597500987 -0.0610257089 568 1305031248.4482519627 0.0957245007 0.0835844189 0.1401651949 0.0431539542 0.9762310000 954820067 0 1782009856 -0.0406083763 0.0612593181 -0.0618323907 569 1305031248.4852969646 0.0967560112 0.0836075675 0.1401651949 0.0431927703 0.9657750000 954821917 0 1783623680 -0.0377218761 0.0632883981 -0.0628823638 570 1305031248.5154309273 0.0920633152 0.0836224022 0.1401651949 0.0431629361 1.0073470000 954823703 0 1782099968 -0.0388927907 0.0746405646 -0.0611485504 571 1305031248.5470030308 0.0921633765 0.0836373601 0.1401651949 0.0432036578 0.9832030000 954825489 0 1783631872 -0.0372699425 0.0778459087 -0.0619862899 572 1305031248.5860579014 0.0929705799 0.0836536769 0.1401651949 0.0432409500 0.9886020000 954827371 0 1782108160 -0.0302528068 0.0843156651 -0.0592290834 573 1305031248.6180379391 0.0937063172 0.0836712208 0.1401651949 0.0432977706 0.9494610000 954829125 0 1783779328 -0.0308962036 0.0852716044 -0.0620573834 574 1305031248.6494390965 0.0946782604 0.0836903968 0.1401651949 0.0432904835 0.9638970000 954830911 0 1782108160 -0.0288098492 0.0885904804 -0.0628570616 575 1305031248.6860280037 0.0938277841 0.0837080271 0.1401651949 0.0433192074 0.9963610000 954832793 0 1783631872 -0.0233446397 0.1006782129 -0.0564448126 576 1305031248.7199230194 0.0946763158 0.0837270692 0.1401651949 0.0433162385 0.9997830000 954834579 0 1782108160 -0.0184782185 0.1095445529 -0.0521938726 577 1305031248.7498369217 0.0978204459 0.0837514945 0.1401651949 0.0433656887 1.0032850000 954836333 0 1783631872 -0.0110709732 0.1169800386 -0.0463385023 578 1305031248.7856750488 0.1044355556 0.0837872801 0.1401651949 0.0433998609 0.9960990000 954838183 0 1782108160 0.0013233904 0.1235945895 -0.0379995815 579 1305031248.8181409836 0.1017056406 0.0838182271 0.1401651949 0.0433748118 0.9941460000 954839969 0 1783771136 0.0010011626 0.1336224526 -0.0352927297 580 1305031248.8496789932 0.0988097712 0.0838440746 0.1401651949 0.0434236293 0.9762690000 954841755 0 1782120448 0.0019171722 0.1333328187 -0.0379374661 581 1305031248.8855929375 0.0949796364 0.0838632408 0.1401651949 0.0434534233 0.9669190000 954843605 0 1783644160 0.0034421182 0.1336230636 -0.0398822203 582 1305031248.9178819656 0.0905280709 0.0838746924 0.1401651949 0.0434379940 0.9744180000 954845391 0 1781972992 0.0029984724 0.1346456409 -0.0405358747 583 1305031248.9526810646 0.0858238190 0.0838780357 0.1401651949 0.0434566510 0.9602130000 954847241 0 1783644160 0.0022952759 0.1373726726 -0.0415905714 584 1305031248.9845540524 0.0780602843 0.0838680738 0.1401651949 0.0434400137 0.9605650000 954849027 0 1782132736 -0.0027107040 0.1487270594 -0.0390196741 585 1305031249.0169510841 0.0743683502 0.0838518350 0.1401651949 0.0434431693 0.9164300000 954850813 0 1783898112 -0.0038952618 0.1483629197 -0.0389317200 586 1305031249.0523660183 0.0705815405 0.0838291894 0.1401651949 0.0434223437 0.9077520000 954852663 0 1782476800 -0.0052472614 0.1493730843 -0.0368347690 587 1305031249.0845029354 0.0694267079 0.0838046537 0.1401651949 0.0433968340 0.9403370000 954854449 0 1784406016 -0.0047913808 0.1551726162 -0.0308654122 588 1305031249.1168839931 0.0667351633 0.0837756239 0.1401651949 0.0433631954 0.9118230000 954856235 0 1783021568 -0.0066554006 0.1536009908 -0.0291435719 589 1305031249.1534469128 0.0641135722 0.0837422418 0.1401651949 0.0433412632 0.9423980000 954858085 0 1781706752 -0.0125875194 0.1599573642 -0.0246018991 590 1305031249.1847391129 0.0627196282 0.0837066103 0.1401651949 0.0433175571 0.9173670000 954859871 0 1783357440 -0.0126284882 0.1581957042 -0.0210480578 591 1305031249.2168650627 0.0624520369 0.0836706465 0.1401651949 0.0432865585 0.9290690000 954861657 0 1781833728 -0.0119436383 0.1565670967 -0.0183833204 592 1305031249.2532238960 0.0627371892 0.0836352860 0.1401651949 0.0432618229 0.9485820000 954863507 0 1783611392 -0.0111066354 0.1567788273 -0.0140163321 593 1305031249.2848041058 0.0665766448 0.0836065193 0.1401651949 0.0432383385 0.9736000000 954865261 0 1782214656 -0.0050763753 0.1576882601 -0.0087782200 594 1305031249.3174340725 0.0660306215 0.0835769302 0.1401651949 0.0432125782 0.9668010000 954867079 0 1783992320 -0.0056174113 0.1575650573 -0.0063195629 595 1305031249.3527359962 0.0652126297 0.0835460659 0.1401651949 0.0431795576 0.9793980000 954868897 0 1782468608 -0.0064556887 0.1579415947 -0.0034421529 596 1305031249.3847539425 0.0669761226 0.0835182639 0.1401651949 0.0431569281 0.9864530000 954870683 0 1784246272 -0.0052332394 0.1550208926 -0.0038848557 597 1305031249.4178340435 0.0690009445 0.0834939468 0.1401651949 0.0431856421 1.0018330000 954872469 0 1782722560 -0.0037659141 0.1530839056 -0.0038377563 598 1305031249.4537220001 0.0707787424 0.0834726839 0.1401651949 0.0432135993 1.0064060000 954874319 0 1784373248 -0.0043330216 0.1498181075 -0.0046278206 599 1305031249.4859149456 0.0715416074 0.0834527656 0.1401651949 0.0432462415 1.0118560000 954876105 0 1782722560 -0.0046644094 0.1451181322 -0.0065351976 600 1305031249.5177340508 0.0709217265 0.0834318805 0.1401651949 0.0432517725 1.0394000000 954877891 0 1784373248 -0.0079497807 0.1372336149 -0.0137657374 601 1305031249.5543251038 0.0738437548 0.0834159269 0.1401651949 0.0433437560 1.0268680000 954879741 0 1782595584 -0.0065358765 0.1280724406 -0.0186854117 602 1305031249.5859050751 0.0751571283 0.0834022080 0.1401651949 0.0434480507 1.0374200000 954881495 0 1784246272 -0.0070637725 0.1240873858 -0.0206159092 603 1305031249.6180789471 0.0730108619 0.0833849752 0.1401651949 0.0434740288 1.0451370000 954883281 0 1782722560 -0.0139186457 0.1136824638 -0.0286212675 604 1305031249.6542129517 0.0751146153 0.0833712826 0.1401651949 0.0436982951 1.0259280000 954885099 0 1784373248 -0.0128083881 0.1112821102 -0.0289553851 605 1305031249.6856739521 0.0702240840 0.0833495517 0.1401651949 0.0438091416 1.0531960000 954886885 0 1782878208 -0.0252453741 0.1091174185 -0.0355717167 606 1305031249.7177898884 0.0669545233 0.0833224972 0.1401651949 0.0438787923 1.0498990000 954888671 0 1784627200 -0.0344944522 0.1011929661 -0.0409458391 607 1305031249.7539620399 0.0697721913 0.0833001738 0.1401651949 0.0439547648 1.0533390000 954890489 0 1783033856 -0.0333099402 0.0999836177 -0.0409649573 608 1305031249.7854170799 0.0688693002 0.0832764388 0.1401651949 0.0440060024 1.0206640000 954892243 0 1781645312 -0.0426937155 0.0963795930 -0.0460231304 609 1305031249.8186020851 0.0709024444 0.0832561202 0.1401651949 0.0440204383 1.0124570000 954894093 0 1783271424 -0.0501185209 0.0910070390 -0.0511548445 610 1305031249.8537468910 0.0725402385 0.0832385532 0.1401651949 0.0441439172 0.9731010000 954895879 0 1781760000 -0.0503965765 0.0908990502 -0.0518543646 611 1305031249.8855249882 0.0737983137 0.0832231028 0.1401651949 0.0441628142 0.9712800000 954897665 0 1783373824 -0.0580187105 0.0878017023 -0.0555890687 612 1305031249.9170649052 0.0763131082 0.0832118119 0.1401651949 0.0441670834 0.9777070000 954899483 0 1782026240 -0.0630623847 0.0811249688 -0.0591558069 613 1305031249.9533979893 0.0793871731 0.0832055727 0.1401651949 0.0441666021 0.9278910000 954901301 0 1783771136 -0.0662221983 0.0747957602 -0.0620086379 614 1305031249.9851789474 0.0821157843 0.0832037978 0.1401651949 0.0441628346 0.9003580000 954903087 0 1782243328 -0.0703694075 0.0704304427 -0.0644992739 615 1305031250.0164399147 0.0842894390 0.0832055631 0.1401651949 0.0441464883 0.8702230000 954904873 0 1783992320 -0.0722137094 0.0670079663 -0.0657428429 616 1305031250.0531940460 0.0881504342 0.0832135905 0.1401651949 0.0442122692 0.8832120000 954906723 0 1782468608 -0.0755950809 0.0600269884 -0.0680244938 617 1305031250.0845069885 0.0903000906 0.0832250759 0.1401651949 0.0442795290 0.8692110000 954908477 0 1784119296 -0.0800607875 0.0578294806 -0.0689383671 618 1305031250.1208500862 0.0919903293 0.0832392591 0.1401651949 0.0443631414 0.8423680000 954910359 0 1782611968 -0.0831756592 0.0575450957 -0.0683526397 619 1305031250.1532480717 0.0940414742 0.0832567102 0.1401651949 0.0446175494 0.8566520000 954912113 0 1784295424 -0.0891638622 0.0573544502 -0.0669728965 620 1305031250.1853280067 0.0960264355 0.0832773065 0.1401651949 0.0446251334 0.8752790000 954913867 0 1782370304 -0.0911657140 0.0527023077 -0.0658526495 621 1305031250.2214460373 0.0992462710 0.0833030215 0.1401651949 0.0446278165 0.8747170000 954915749 0 1784152064 -0.0944185406 0.0468170457 -0.0659876913 622 1305031250.2537350655 0.1009251550 0.0833313529 0.1401651949 0.0447228353 0.8769470000 954917535 0 1782497280 -0.0960479081 0.0426471941 -0.0635770038 623 1305031250.2852239609 0.1032375544 0.0833633050 0.1401651949 0.0447391738 0.8917580000 954919289 0 1784152064 -0.1000771374 0.0373072810 -0.0629252866 624 1305031250.3208620548 0.1058396101 0.0833993247 0.1401651949 0.0447657925 0.9235930000 954921107 0 1782722560 -0.1024613008 0.0342799537 -0.0625061691 625 1305031250.3517000675 0.1077524796 0.0834382898 0.1401651949 0.0447802235 0.9005160000 954922861 0 1784373248 -0.1051828936 0.0321628600 -0.0621796176 626 1305031250.3851490021 0.1141609177 0.0834873675 0.1401651949 0.0447878619 0.9112890000 954924647 0 1782722560 -0.1117494702 0.0272716284 -0.0647271127 627 1305031250.4215359688 0.1183542758 0.0835429766 0.1401651949 0.0447974787 0.9066590000 954926529 0 1784279040 -0.1178913638 0.0247577559 -0.0663078651 628 1305031250.4540181160 0.1182351783 0.0835982189 0.1401651949 0.0448845740 0.8847410000 954928379 0 1782231040 -0.1204828843 0.0282018501 -0.0639208853 629 1305031250.4856131077 0.1178627908 0.0836526936 0.1401651949 0.0448868858 0.8757020000 954930133 0 1783914496 -0.1232258677 0.0302126016 -0.0613674484 630 1305031250.5215380192 0.1235745996 0.0837160617 0.1401651949 0.0448640983 0.9243300000 954932015 0 1781862400 -0.1318093836 0.0259920489 -0.0633591712 631 1305031250.5536580086 0.1252588332 0.0837818981 0.1401651949 0.0448522453 0.8643010000 954933865 0 1783644160 -0.1348325014 0.0274623092 -0.0617084354 632 1305031250.5853788853 0.1250943393 0.0838472659 0.1401651949 0.0448410663 0.8621680000 954935651 0 1782243328 -0.1376300901 0.0286309011 -0.0594966859 633 1305031250.6213030815 0.1262678504 0.0839142811 0.1401651949 0.0448228885 0.8566920000 954937533 0 1783881728 -0.1410872340 0.0299250502 -0.0584072471 634 1305031250.6535439491 0.1294052303 0.0839860333 0.1401651949 0.0448427644 0.8685100000 954939415 0 1782341632 -0.1450787336 0.0305716097 -0.0581678115 635 1305031250.6852970123 0.1290198416 0.0840569527 0.1401651949 0.0448665895 0.8676010000 954941201 0 1783992320 -0.1475798339 0.0330244228 -0.0555595085 636 1305031250.7216401100 0.1286547035 0.0841270750 0.1401651949 0.0448446875 0.8726890000 954943083 0 1782468608 -0.1502626985 0.0356722511 -0.0534846932 637 1305031250.7534279823 0.1361498982 0.0842087435 0.1401651949 0.0448147497 0.8931310000 954944901 0 1784119296 -0.1594253033 0.0323255286 -0.0559291057 638 1305031250.7853651047 0.1350003481 0.0842883541 0.1401651949 0.0447897942 0.8639530000 954946719 0 1782624256 -0.1597498804 0.0347565971 -0.0536912754 639 1305031250.8217930794 0.1333712339 0.0843651661 0.1401651949 0.0447581831 0.8546550000 954948665 0 1784279040 -0.1600819826 0.0361605845 -0.0513577610 640 1305031250.8538279533 0.1323529780 0.0844401471 0.1401651949 0.0447263813 0.8713180000 954950515 0 1782730752 -0.1598912776 0.0369684920 -0.0503568761 641 1305031250.8820140362 0.1314831376 0.0845135371 0.1401651949 0.0446929002 0.8554220000 954952269 0 1781362688 -0.1585080624 0.0373706855 -0.0494723134 642 1305031250.9217998981 0.1311848909 0.0845862339 0.1401651949 0.0446609895 0.8908900000 954954215 0 1782976512 -0.1578850895 0.0380289182 -0.0498900302 643 1305031250.9535419941 0.1313305497 0.0846589311 0.1401651949 0.0446395411 0.8533110000 954956065 0 1781088256 -0.1585954875 0.0382073857 -0.0515381284 644 1305031250.9853079319 0.1312769949 0.0847313194 0.1401651949 0.0446088404 0.8563470000 954957851 0 1782738944 -0.1585309803 0.0365704522 -0.0516741052 645 1305031251.0214879513 0.1314755380 0.0848037911 0.1401651949 0.0445870611 0.8657610000 954959733 0 1780969472 -0.1576569080 0.0357368737 -0.0527867973 646 1305031251.0534679890 0.1304361671 0.0848744294 0.1401651949 0.0445909722 0.8658790000 954961551 0 1782669312 -0.1565246284 0.0340116769 -0.0536450669 647 1305031251.0851860046 0.1300595254 0.0849442673 0.1401651949 0.0445905852 0.8616440000 954963369 0 1784287232 -0.1553939730 0.0307718609 -0.0548667125 648 1305031251.1214449406 0.1307916790 0.0850150195 0.1401651949 0.0445905529 0.9053360000 954965251 0 1782648832 -0.1534878463 0.0273681022 -0.0572092496 649 1305031251.1537809372 0.1312884539 0.0850863191 0.1401651949 0.0446910094 0.8718640000 954967101 0 1781223424 -0.1522635520 0.0231416095 -0.0606692508 650 1305031251.1851599216 0.1320770383 0.0851586125 0.1401651949 0.0447172770 0.8752540000 954968887 0 1782890496 -0.1503610313 0.0182260741 -0.0631942376 651 1305031251.2204658985 0.1318664700 0.0852303603 0.1401651949 0.0447352561 0.8989390000 954970737 0 1780842496 -0.1468156576 0.0142667294 -0.0654559061 652 1305031251.2524240017 0.1227660477 0.0852879304 0.1401651949 0.0447777376 0.9261770000 954972523 0 1782611968 -0.1309763640 0.0180545058 -0.0614382699 653 1305031251.2844820023 0.1254032552 0.0853493628 0.1401651949 0.0449889313 0.8802120000 954974341 0 1784119296 -0.1291505694 0.0118022561 -0.0659083277 654 1305031251.3190040588 0.1205008030 0.0854031111 0.1401651949 0.0450665918 0.9371090000 954976191 0 1782501376 -0.1173028052 0.0125390003 -0.0635929108 655 1305031251.3532440662 0.1212654337 0.0854578628 0.1401651949 0.0451636416 0.8852870000 954977977 0 1784119296 -0.1143192127 0.0078786639 -0.0659405142 656 1305031251.3870069981 0.1115870550 0.0854976939 0.1401651949 0.0451999015 0.9561370000 954979795 0 1782738944 -0.0989606082 0.0160059370 -0.0585531145 657 1305031251.4210500717 0.1151564419 0.0855428366 0.1401651949 0.0452947697 0.9091770000 954981613 0 1784406016 -0.0973399058 0.0093797343 -0.0620723478 658 1305031251.4496629238 0.1102549583 0.0855803930 0.1401651949 0.0453512352 0.9574470000 954983335 0 1783005184 -0.0864252746 0.0123658432 -0.0571969673 659 1305031251.4890139103 0.1092131436 0.0856162545 0.1401651949 0.0454520040 0.9344440000 954985217 0 1781346304 -0.0847788304 0.0102405148 -0.0578130931 660 1305031251.5207729340 0.1042416096 0.0856444747 0.1401651949 0.0455411750 1.0259610000 954987035 0 1783025664 -0.0752242804 0.0135715827 -0.0529093258 661 1305031251.5530450344 0.1038311198 0.0856719886 0.1401651949 0.0456562616 0.9134880000 954988821 0 1780981760 -0.0723525509 0.0112543851 -0.0533902161 662 1305031251.5887598991 0.0979547277 0.0856905426 0.1401651949 0.0456775986 0.9513620000 954990639 0 1782755328 -0.0652996376 0.0183632653 -0.0481699184 663 1305031251.6208739281 0.0974956453 0.0857083482 0.1401651949 0.0457285229 0.9232370000 954992457 0 1781362688 -0.0631786361 0.0169821046 -0.0480367877 664 1305031251.6528749466 0.0969912261 0.0857253404 0.1401651949 0.0458105417 0.9388780000 954994243 0 1783009280 -0.0588734299 0.0165045019 -0.0472776666 665 1305031251.6897680759 0.0917768851 0.0857344405 0.1401651949 0.0458337636 0.9924810000 954996093 0 1781620736 -0.0537411086 0.0240198132 -0.0421642810 666 1305031251.7204608917 0.0910349712 0.0857423993 0.1401651949 0.0458950003 0.9733300000 954997879 0 1783390208 -0.0500739291 0.0234292895 -0.0397033021 667 1305031251.7531440258 0.0916786566 0.0857512992 0.1401651949 0.0459802063 1.0107850000 954999665 0 1782009856 -0.0445967019 0.0222719684 -0.0383432060 668 1305031251.7892498970 0.0882575735 0.0857550511 0.1401651949 0.0460106522 1.0711030000 955001515 0 1783771136 -0.0407079607 0.0289628189 -0.0335620902 669 1305031251.8209791183 0.0879013911 0.0857582594 0.1401651949 0.0460482478 1.0742020000 955003301 0 1782370304 -0.0401112884 0.0277570300 -0.0326969400 670 1305031251.8537969589 0.0881297588 0.0857617989 0.1401651949 0.0461442061 1.1386000000 955005087 0 1784119296 -0.0305447429 0.0299921520 -0.0256567374 671 1305031251.8896539211 0.0878818631 0.0857649585 0.1401651949 0.0461322593 1.1619350000 955006905 0 1782738944 -0.0225709993 0.0369743407 -0.0184644815 672 1305031251.9219300747 0.0842182264 0.0857626568 0.1401651949 0.0461198740 1.1585900000 955008723 0 1784389632 -0.0197607949 0.0475454889 -0.0111445077 673 1305031251.9538369179 0.0823325366 0.0857575600 0.1401651949 0.0461302339 1.1717990000 955010477 0 1783230464 -0.0179553702 0.0542906374 -0.0059930561 674 1305031251.9898068905 0.0813502371 0.0857510210 0.1401651949 0.0461287039 1.1360780000 955012327 0 1781768192 -0.0177337155 0.0552110448 -0.0049469010 675 1305031252.0221600533 0.0801798999 0.0857427675 0.1401651949 0.0461579789 1.1684100000 955014145 0 1783263232 -0.0143420789 0.0612417534 0.0007249089 676 1305031252.0537619591 0.0758443922 0.0857281249 0.1401651949 0.0461725243 1.2198160000 955015931 0 1781706752 -0.0130575188 0.0703903586 0.0052860547 677 1305031252.0895619392 0.0723667145 0.0857083887 0.1401651949 0.0462231572 1.1717760000 955017749 0 1783357440 -0.0118469670 0.0805886239 0.0093481671 678 1305031252.1221520901 0.0686415434 0.0856832164 0.1401651949 0.0462759026 1.1388510000 955019567 0 1781706752 -0.0126572456 0.0850839466 0.0078354683 679 1305031252.1539709568 0.0634400249 0.0856504576 0.1401651949 0.0463866582 1.1761420000 955021289 0 1783611392 -0.0123976562 0.0989125445 0.0121159889 680 1305031252.1897890568 0.0546968915 0.0856049377 0.1401651949 0.0463716026 1.1550130000 955023139 0 1781891072 -0.0222426206 0.1136771441 0.0095600672 681 1305031252.2220859528 0.0502460375 0.0855530156 0.1401651949 0.0463554012 1.1268080000 955024957 0 1783525376 -0.0305802822 0.1252463758 0.0089775724 682 1305031252.2530639172 0.0482946821 0.0854983847 0.1401651949 0.0464530609 1.1209410000 955026743 0 1781841920 -0.0271234363 0.1272127926 0.0131069925 683 1305031252.2888779640 0.0465074517 0.0854412969 0.1401651949 0.0465101303 1.0675760000 955028529 0 1783365632 -0.0261906385 0.1260989010 0.0122578926 684 1305031252.3206090927 0.0458713472 0.0853834461 0.1401651949 0.0464865837 1.0599640000 955030315 0 1781841920 -0.0260232687 0.1284003556 0.0125507489 685 1305031252.3528549671 0.0469303653 0.0853273102 0.1401651949 0.0464838397 1.0872550000 955032069 0 1783365632 -0.0214103423 0.1338139325 0.0184976906 686 1305031252.3893189430 0.0464013703 0.0852705669 0.1401651949 0.0464692361 1.0443140000 955033919 0 1781706752 -0.0223058667 0.1328942925 0.0164269507 687 1305031252.4217019081 0.0464789569 0.0852141016 0.1401651949 0.0464560496 1.0395400000 955035737 0 1783357440 -0.0236450695 0.1336084455 0.0150213484 688 1305031252.4538249969 0.0470630080 0.0851586495 0.1401651949 0.0464322960 1.0362050000 955037523 0 1781706752 -0.0232115313 0.1347274631 0.0164059959 689 1305031252.4895589352 0.0475656688 0.0851040878 0.1401651949 0.0464021421 1.0411720000 955039309 0 1783230464 -0.0239428468 0.1355353892 0.0170393772 690 1305031252.5221700668 0.0482227691 0.0850506366 0.1401651949 0.0463751674 1.0435540000 955041127 0 1781592064 -0.0242260639 0.1354382038 0.0174850132 691 1305031252.5537741184 0.0488554463 0.0849982557 0.1401651949 0.0463493980 1.0799810000 955042913 0 1783263232 -0.0255539883 0.1352662295 0.0169909019 692 1305031252.5897459984 0.0483887270 0.0849453518 0.1401651949 0.0463202317 1.0640220000 955044731 0 1781751808 -0.0275609605 0.1363224089 0.0169578996 693 1305031252.6221249104 0.0498903655 0.0848947674 0.1401651949 0.0462935794 1.0695410000 955046549 0 1783246848 -0.0256752670 0.1374850273 0.0204515532 694 1305031252.6578559875 0.0526381284 0.0848482881 0.1401651949 0.0462756229 1.0785920000 955048367 0 1781624832 -0.0241045952 0.1379015744 0.0228919014 695 1305031252.6889979839 0.0547321439 0.0848049555 0.1401651949 0.0462902917 1.0689120000 955050121 0 1783103488 -0.0230630692 0.1363295615 0.0250843838 696 1305031252.7216539383 0.0546800196 0.0847616726 0.1401651949 0.0463686768 1.1467870000 955051907 0 1781452800 -0.0277270786 0.1352120936 0.0218942631 697 1305031252.7578220367 0.0565029420 0.0847211292 0.1401651949 0.0464786520 1.1046830000 955053789 0 1782976512 -0.0276183672 0.1278973669 0.0185106695 698 1305031252.7896919250 0.0605635867 0.0846865195 0.1401651949 0.0465960249 1.0992380000 955055543 0 1781325824 -0.0247456562 0.1229988635 0.0161646269 699 1305031252.8224050999 0.0580344312 0.0846483906 0.1401651949 0.0466960902 1.0776500000 955057361 0 1782976512 -0.0359006599 0.1203959286 0.0055267680 700 1305031252.8539779186 0.0612201840 0.0846149218 0.1401651949 0.0466899516 1.0364820000 955059083 0 1781325824 -0.0334102362 0.1152643412 0.0044491384 701 1305031252.8897290230 0.0632256344 0.0845844092 0.1401651949 0.0467172951 1.0892480000 955060933 0 1782882304 -0.0340945497 0.1116711348 0.0019349977 702 1305031252.9206719398 0.0642622560 0.0845554603 0.1401651949 0.0467254478 1.0763400000 955062719 0 1781383168 -0.0389707536 0.1065801084 -0.0027482128 703 1305031252.9578649998 0.0661338344 0.0845292560 0.1401651949 0.0468018620 1.0854380000 955064633 0 1782734848 -0.0432787798 0.0999733210 -0.0061994223 704 1305031252.9894239902 0.0675606504 0.0845051529 0.1401651949 0.0468572366 1.0925430000 955066355 0 1781088256 -0.0501110889 0.0953258350 -0.0102771269 705 1305031253.0196959972 0.0688069612 0.0844828859 0.1401651949 0.0469295964 1.0859070000 955068141 0 1782849536 -0.0574492514 0.0910839140 -0.0138881402 706 1305031253.0574259758 0.0728458539 0.0844664029 0.1401651949 0.0469710536 1.1193250000 955070023 0 1781358592 -0.0644927099 0.0832902491 -0.0186542496 707 1305031253.0895500183 0.0748862997 0.0844528525 0.1401651949 0.0470079153 1.0984010000 955071777 0 1783103488 -0.0649362355 0.0782901645 -0.0197846182 708 1305031253.1197240353 0.0810863525 0.0844480976 0.1401651949 0.0470146471 1.0869270000 955073563 0 1781612544 -0.0703658760 0.0697139949 -0.0256666057 709 1305031253.1573839188 0.0862995759 0.0844507090 0.1401651949 0.0470915809 1.0832420000 955075413 0 1783357440 -0.0787847266 0.0628990531 -0.0320140682 710 1305031253.1892180443 0.0860002413 0.0844528914 0.1401651949 0.0471179341 1.0813780000 955077167 0 1781850112 -0.0819827318 0.0617016181 -0.0310921967 711 1305031253.2180271149 0.0836175457 0.0844517165 0.1401651949 0.0471095214 1.1043880000 955078953 0 1783627776 -0.0816530809 0.0629379749 -0.0278774928 712 1305031253.2578470707 0.0849438831 0.0844524078 0.1401651949 0.0470882445 1.0691630000 955080867 0 1782398976 -0.0847466961 0.0596402399 -0.0283656195 713 1305031253.2897419930 0.0853426382 0.0844536563 0.1401651949 0.0470581700 1.0545370000 955082621 0 1784033280 -0.0831131861 0.0566665232 -0.0264512822 714 1305031253.3220069408 0.0854331776 0.0844550282 0.1401651949 0.0470333084 1.0642670000 955084439 0 1782632448 -0.0777556226 0.0532313958 -0.0234168377 715 1305031253.3578300476 0.0866673142 0.0844581223 0.1401651949 0.0470053948 1.0695440000 955086257 0 1784139776 -0.0721176043 0.0505982153 -0.0211445857 716 1305031253.3880970478 0.0856316984 0.0844597614 0.1401651949 0.0469730161 1.1365800000 955088011 0 1782857728 -0.0709770247 0.0510630608 -0.0190019011 717 1305031253.4213519096 0.0859779790 0.0844618789 0.1401651949 0.0469416823 1.0921050000 955089829 0 1784508416 -0.0695810542 0.0507883802 -0.0178025514 718 1305031253.4579629898 0.0860843435 0.0844641386 0.1401651949 0.0469111638 1.0983980000 955091679 0 1782984704 -0.0693732426 0.0520042852 -0.0167983454 719 1305031253.4896900654 0.0852183104 0.0844651875 0.1401651949 0.0468790077 1.0904060000 955093465 0 1781579776 -0.0721438229 0.0536106676 -0.0167443268 720 1305031253.5207340717 0.0862159207 0.0844676191 0.1401651949 0.0468485077 1.0910920000 955095251 0 1783357440 -0.0721289217 0.0526705310 -0.0169838686 721 1305031253.5578539371 0.0872974619 0.0844715439 0.1401651949 0.0468181392 1.1116550000 955097101 0 1781858304 -0.0743274018 0.0525527373 -0.0177401416 722 1305031253.5898048878 0.0861183107 0.0844738248 0.1401651949 0.0467903714 1.1250860000 955098887 0 1783513088 -0.0804081783 0.0548496246 -0.0182316825 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 02:39:07 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 nan 0.4791890000 955056310 0 1770221568 -0.0000000000 0.0000000000 -0.0000000000 2 1305031102.2112140656 0.0217132382 0.0235560341 0.0253988300 0.0240807198 0.6371710000 953938575 0 1765076992 -0.0023110609 0.0007926704 0.0125146396 3 1305031102.2432110310 0.0218830090 0.0229983591 0.0253988300 0.0192133201 0.6071230000 953627629 0 1766801408 -0.0037648196 0.0053030890 0.0258693416 4 1305031102.2753260136 0.0166577362 0.0214132033 0.0253988300 0.0157464548 0.6255480000 953629743 0 1768738816 -0.0045058951 0.0041049188 0.0388879441 5 1305031102.3112668991 0.0125653408 0.0196436308 0.0253988300 0.0141426807 0.6299490000 953631593 0 1770516480 -0.0033666748 0.0037937891 0.0516050719 6 1305031102.3432331085 0.0089179929 0.0178560245 0.0253988300 0.0148810281 0.6348860000 953634035 0 1772134400 -0.0042274017 0.0023542177 0.0636251271 7 1305031102.3753290176 0.0086959992 0.0165474495 0.0253988300 0.0137550554 0.6449540000 953635789 0 1773797376 -0.0045752311 0.0031223341 0.0755111650 8 1305031102.4112579823 0.0069343597 0.0153458132 0.0253988300 0.0147573621 0.6420730000 953637671 0 1775562752 -0.0064932299 0.0048687789 0.0872642323 9 1305031102.4432709217 0.0075785089 0.0144827794 0.0253988300 0.0167665033 0.6352560000 953639457 0 1777246208 -0.0082849171 0.0075757690 0.0996242762 10 1305031102.4753179550 0.0110958805 0.0141440895 0.0253988300 0.0160631513 0.6322440000 953642523 0 1778868224 -0.0071401950 0.0111965314 0.1126649082 11 1305031102.5112190247 0.0133498581 0.0140718867 0.0253988300 0.0161505850 0.6330240000 953644373 0 1780633600 -0.0073671723 0.0107301213 0.1251651198 12 1305031102.5432200432 0.0163775757 0.0142640274 0.0253988300 0.0154022485 0.6778520000 953646191 0 1782317056 -0.0085271988 0.0107750772 0.1370552182 13 1305031102.5752859116 0.0188209489 0.0146145599 0.0253988300 0.0158768560 0.6185090000 953647945 0 1784094720 -0.0114282425 0.0102413446 0.1486866027 14 1305031102.6112329960 0.0235547293 0.0152531434 0.0253988300 0.0167637806 0.6226660000 953649795 0 1782284288 -0.0129637737 0.0076711057 0.1597723216 15 1305031102.6432650089 0.0261492636 0.0159795514 0.0261492636 0.0169669304 0.6307330000 953651581 0 1784221696 -0.0159895029 0.0083113248 0.1706601679 16 1305031102.6752851009 0.0239397082 0.0164770612 0.0261492636 0.0170281577 0.6404420000 953653367 0 1782702080 -0.0179047883 0.0152680939 0.1823418438 17 1305031102.7112629414 0.0265402682 0.0170690146 0.0265402682 0.0168263684 0.6191710000 953655217 0 1784307712 -0.0183669031 0.0179004837 0.1947544664 18 1305031102.7432339191 0.0301314481 0.0177947053 0.0301314481 0.0164467201 0.6149340000 953659659 0 1782718464 -0.0191838052 0.0194257516 0.2075117528 19 1305031102.7754719257 0.0298243705 0.0184278456 0.0301314481 0.0165171660 0.6341630000 953661413 0 1784356864 -0.0186980963 0.0254253782 0.2203727961 20 1305031102.8112320900 0.0337720662 0.0191950566 0.0337720662 0.0161469702 0.6487780000 953663263 0 1782784000 -0.0199224744 0.0273315031 0.2330058217 21 1305031102.8432900906 0.0353447236 0.0199640884 0.0353447236 0.0157480524 0.6041150000 953665081 0 1781407744 -0.0219851732 0.0307009239 0.2455426902 22 1305031102.8753631115 0.0383028872 0.0207976701 0.0383028872 0.0154429153 0.6001490000 953666835 0 1783037952 -0.0247266982 0.0325005278 0.2572790086 23 1305031102.9111850262 0.0411039367 0.0216805513 0.0411039367 0.0151398281 0.5918270000 953668685 0 1781809152 -0.0272495188 0.0351213142 0.2687972188 24 1305031102.9432289600 0.0426411964 0.0225539115 0.0426411964 0.0152337543 0.5916750000 953670503 0 1783451648 -0.0292246900 0.0386258475 0.2801080942 25 1305031102.9752030373 0.0453554057 0.0234659713 0.0453554057 0.0162051964 0.5947330000 953672225 0 1782022144 -0.0328820087 0.0411625132 0.2913650572 26 1305031103.0112149715 0.0483161025 0.0244217456 0.0483161025 0.0158924776 0.5868460000 953674107 0 1783726080 -0.0335788727 0.0441867672 0.3029504120 27 1305031103.0432269573 0.0512476936 0.0254152992 0.0512476936 0.0155968920 0.5911290000 953675925 0 1782030336 -0.0334141627 0.0471050218 0.3143710792 28 1305031103.0753190517 0.0541951917 0.0264431525 0.0541951917 0.0159737637 0.5858070000 953677679 0 1783734272 -0.0323164612 0.0496869534 0.3251523376 29 1305031103.1112399101 0.0580569096 0.0275332820 0.0580569096 0.0159077995 0.6194710000 953679529 0 1782288384 -0.0319524668 0.0512570739 0.3349383175 30 1305031103.1433179379 0.0572063290 0.0285223836 0.0580569096 0.0156672572 0.5991730000 953681315 0 1783934976 -0.0317829251 0.0575056002 0.3443083167 31 1305031103.1754519939 0.0596304834 0.0295258707 0.0596304834 0.0154259889 0.5918270000 953683101 0 1782542336 -0.0325625055 0.0595722720 0.3532659113 32 1305031103.2112200260 0.0603799932 0.0304900620 0.0603799932 0.0161113371 0.5818860000 953684951 0 1784315904 -0.0330628939 0.0643571094 0.3620291054 33 1305031103.2432160378 0.0617018752 0.0314358745 0.0617018752 0.0158979857 0.5808720000 953686769 0 1782833152 -0.0329652131 0.0682022125 0.3710341752 34 1305031103.2753698826 0.0645312667 0.0324092684 0.0645312667 0.0160693267 0.5705860000 953693771 0 1781432320 -0.0328852050 0.0698009059 0.3792896569 35 1305031103.3112099171 0.0699891821 0.0334829802 0.0699891821 0.0166352107 0.5778640000 953695621 0 1783173120 -0.0339906886 0.0672876239 0.3866491020 36 1305031103.3432230949 0.0762746185 0.0346716369 0.0762746185 0.0173808180 0.5743450000 953697439 0 1781809152 -0.0338216536 0.0623835698 0.3917616904 37 1305031103.3753271103 0.0769611150 0.0358145957 0.0769611150 0.0173547835 0.5360180000 953699193 0 1783418880 -0.0325225033 0.0623918436 0.3943509161 38 1305031103.4112598896 0.0775124505 0.0369119077 0.0775124505 0.0172806675 0.5515040000 953701043 0 1781956608 -0.0310421828 0.0614453740 0.3950692415 39 1305031103.4432799816 0.0794869512 0.0380035755 0.0794869512 0.0171898299 0.5416150000 953702861 0 1783689216 -0.0316712745 0.0579599440 0.3937063813 40 1305031103.4752740860 0.0805252343 0.0390666170 0.0805252343 0.0169944415 0.5411760000 953704615 0 1781936128 -0.0316916853 0.0544049367 0.3908626437 41 1305031103.5113329887 0.0843588412 0.0401713054 0.0843588412 0.0169768408 0.5679570000 953706465 0 1783578624 -0.0295045786 0.0473142862 0.3869664073 42 1305031103.5434439182 0.0841166824 0.0412176239 0.0843588412 0.0169023604 0.5619870000 953708283 0 1782149120 -0.0293504670 0.0425348803 0.3802960515 43 1305031103.5754740238 0.0832320601 0.0421947038 0.0843588412 0.0167506380 0.5584270000 953710037 0 1783832576 -0.0287682023 0.0377165675 0.3721603155 44 1305031103.6112229824 0.0809806660 0.0430762029 0.0843588412 0.0166646894 0.5683840000 953711887 0 1782149120 -0.0275115483 0.0346989855 0.3629991114 45 1305031103.6434450150 0.0791882277 0.0438786923 0.0843588412 0.0164832418 0.5580090000 953713705 0 1783832576 -0.0264334548 0.0302133597 0.3532452285 46 1305031103.6755230427 0.0770643279 0.0446001192 0.0843588412 0.0163584420 0.5597090000 953715459 0 1782149120 -0.0242256336 0.0260936320 0.3428215384 47 1305031103.7116100788 0.0747848451 0.0452423474 0.0843588412 0.0161992232 0.5876880000 953717309 0 1783705600 -0.0218394212 0.0223230850 0.3316751122 48 1305031103.7433259487 0.0722440854 0.0458048836 0.0843588412 0.0160780371 0.5573900000 953719127 0 1782300672 -0.0195286293 0.0181570463 0.3199556470 49 1305031103.7753419876 0.0699913576 0.0462984851 0.0843588412 0.0159108272 0.5578310000 953720881 0 1783926784 -0.0184760857 0.0126498379 0.3074005842 50 1305031103.8112421036 0.0666768178 0.0467060518 0.0843588412 0.0161684880 0.5580260000 953722731 0 1782534144 -0.0174081642 0.0103794811 0.2941673994 51 1305031103.8432509899 0.0629338697 0.0470242443 0.0843588412 0.0161933827 0.5567170000 953724549 0 1784307712 -0.0156802945 0.0082207881 0.2813541889 52 1305031103.8753609657 0.0604557730 0.0472825429 0.0843588412 0.0161779315 0.5664560000 953726303 0 1782657024 -0.0159030613 0.0048991074 0.2690972686 53 1305031103.9112210274 0.0644434541 0.0476063337 0.0843588412 0.0172117590 0.5919050000 953728153 0 1784348672 -0.0159069635 -0.0061114095 0.2567071021 54 1305031103.9432110786 0.0646184087 0.0479213721 0.0843588412 0.0171156424 0.5936250000 953729971 0 1782562816 -0.0139486734 -0.0137337260 0.2432561070 55 1305031103.9753730297 0.0612333603 0.0481634083 0.0843588412 0.0170823223 0.5827440000 953731757 0 1784242176 -0.0128657818 -0.0169828683 0.2288586646 56 1305031104.0112318993 0.0606679805 0.0483867042 0.0843588412 0.0172836297 0.6344830000 953733575 0 1782792192 -0.0108844284 -0.0223575160 0.2144831717 57 1305031104.0432488918 0.0579670668 0.0485547807 0.0843588412 0.0172387746 0.6063840000 953735393 0 1781452800 -0.0080458038 -0.0279830620 0.1995846331 58 1305031104.0754249096 0.0522708744 0.0486188513 0.0843588412 0.0172633860 0.6097800000 953737147 0 1783058432 -0.0053718234 -0.0290106982 0.1839419752 59 1305031104.1112349033 0.0477200039 0.0486036166 0.0843588412 0.0171794008 0.5982140000 953738997 0 1781649408 -0.0058814404 -0.0298179742 0.1689551622 60 1305031104.1432299614 0.0440692939 0.0485280446 0.0843588412 0.0171282952 0.6060690000 953740815 0 1783480320 -0.0059157484 -0.0349263921 0.1545003951 61 1305031104.1754240990 0.0401882045 0.0483913259 0.0843588412 0.0170808458 0.6201030000 953742569 0 1781776384 -0.0061053066 -0.0383447520 0.1403286904 62 1305031104.2112829685 0.0389980450 0.0482398214 0.0843588412 0.0169864884 0.6177480000 953744419 0 1783697408 -0.0060320371 -0.0408134572 0.1267062426 63 1305031104.2431960106 0.0354537666 0.0480368681 0.0843588412 0.0168696369 0.6239190000 953746237 0 1781923840 -0.0054498180 -0.0440218598 0.1132635921 64 1305031104.2755460739 0.0320804827 0.0477875496 0.0843588412 0.0167453430 0.6541320000 953747991 0 1783545856 -0.0036243021 -0.0459876955 0.1003665328 65 1305031104.3112189770 0.0310994964 0.0475308103 0.0843588412 0.0166596175 0.6297110000 953749841 0 1782173696 -0.0023430134 -0.0472281836 0.0876730531 66 1305031104.3433420658 0.0276574343 0.0472296985 0.0843588412 0.0165852762 0.6293680000 953762155 0 1783816192 -0.0005899951 -0.0478065722 0.0755128413 67 1305031104.3758370876 0.0267637502 0.0469242366 0.0843588412 0.0165338844 0.6488480000 953763909 0 1782149120 0.0009817602 -0.0479202345 0.0637405962 68 1305031104.4115090370 0.0244609751 0.0465938946 0.0843588412 0.0164892157 0.6466010000 953765759 0 1783836672 0.0004277445 -0.0480692424 0.0525509194 69 1305031104.4432880878 0.0223830864 0.0462430133 0.0843588412 0.0164252938 0.6649530000 953767545 0 1782321152 -0.0007998676 -0.0485529155 0.0420349091 70 1305031104.4754559994 0.0211601481 0.0458846866 0.0843588412 0.0163633426 0.6546530000 953769331 0 1784053760 -0.0029902679 -0.0491927378 0.0323415473 71 1305031104.5113289356 0.0234387573 0.0455685468 0.0843588412 0.0164739440 0.6647120000 953771181 0 1782702080 -0.0048789643 -0.0510689020 0.0231719054 72 1305031104.5433681011 0.0227865838 0.0452521306 0.0843588412 0.0164614259 0.7007990000 953772999 0 1784344576 -0.0042696404 -0.0544402786 0.0135232601 73 1305031104.5753428936 0.0218510330 0.0449315676 0.0843588412 0.0165784694 0.6771510000 953774721 0 1782910976 -0.0030585565 -0.0561268330 0.0035210762 74 1305031104.6113359928 0.0239793900 0.0446484301 0.0843588412 0.0173302238 0.6821660000 953776603 0 1781551104 0.0005940144 -0.0595672615 -0.0078649130 75 1305031104.6432430744 0.0215192474 0.0443400410 0.0843588412 0.0173342591 0.6992370000 953778389 0 1783435264 0.0049035996 -0.0626320466 -0.0213265065 76 1305031104.6755249500 0.0220373049 0.0440465840 0.0843588412 0.0172274242 0.7152910000 953780175 0 1781817344 0.0072171530 -0.0575757697 -0.0354465395 77 1305031104.7112770081 0.0247527938 0.0437960153 0.0843588412 0.0174385899 0.7082030000 953782025 0 1783418880 0.0098869968 -0.0553642996 -0.0497361682 78 1305031104.7432799339 0.0290041734 0.0436063763 0.0843588412 0.0173544621 0.7063680000 953783811 0 1781669888 0.0121642686 -0.0504485704 -0.0638700947 79 1305031104.7753269672 0.0369462334 0.0435220706 0.0843588412 0.0172742197 0.7013220000 953785565 0 1783328768 0.0165370312 -0.0437888578 -0.0759269297 80 1305031104.8114650249 0.0439484268 0.0435274001 0.0843588412 0.0172086552 0.7026950000 953787447 0 1781641216 0.0193474256 -0.0379509628 -0.0862249658 81 1305031104.8432579041 0.0519252047 0.0436310767 0.0843588412 0.0171407312 0.7068400000 953789233 0 1783328768 0.0240113195 -0.0313872024 -0.0943625942 82 1305031104.8753499985 0.0548320077 0.0437676734 0.0843588412 0.0171866815 0.7039680000 953791019 0 1781575680 0.0243714880 -0.0282996856 -0.0995387957 83 1305031104.9115340710 0.0583767630 0.0439436865 0.0843588412 0.0171355346 0.6982940000 953792869 0 1783328768 0.0247265063 -0.0240465607 -0.1022020951 84 1305031104.9432621002 0.0615138896 0.0441528556 0.0843588412 0.0170432814 0.7050330000 953794655 0 1781514240 0.0257996842 -0.0204949547 -0.1023093835 85 1305031104.9752020836 0.0633709282 0.0443789506 0.0843588412 0.0170583815 0.7076950000 953796441 0 1783201792 0.0259651858 -0.0173949972 -0.0996037200 86 1305031105.0112900734 0.0711960196 0.0446907770 0.0843588412 0.0171841466 0.7473770000 953798291 0 1781575680 0.0252599474 -0.0069692563 -0.0932220072 87 1305031105.0433731079 0.0719139576 0.0450036871 0.0843588412 0.0171468904 0.7660400000 953800077 0 1783164928 0.0233846977 -0.0036793798 -0.0854431540 88 1305031105.0753200054 0.0686612949 0.0452725236 0.0843588412 0.0170847643 0.7487650000 953801863 0 1781387264 0.0197547525 -0.0039953352 -0.0761975199 89 1305031105.1112990379 0.0654696226 0.0454994573 0.0843588412 0.0170004216 0.7496820000 953803713 0 1783074816 0.0165770352 -0.0042558853 -0.0657323599 90 1305031105.1431059837 0.0597289912 0.0456575632 0.0843588412 0.0169927656 0.7670190000 953805499 0 1781428224 0.0114364587 -0.0064888247 -0.0541227162 91 1305031105.1751589775 0.0609677471 0.0458258070 0.0843588412 0.0174696337 0.7869640000 953807285 0 1783074816 0.0064662099 -0.0005788594 -0.0390918702 92 1305031105.2112679482 0.0563619584 0.0459403304 0.0843588412 0.0175059991 0.7715360000 953809135 0 1781260288 -0.0003990363 -0.0007600366 -0.0231473409 93 1305031105.2432699203 0.0449675284 0.0459298701 0.0843588412 0.0175274960 0.7782120000 953810921 0 1782927360 -0.0041788444 -0.0082393307 -0.0088919373 94 1305031105.2752881050 0.0396626554 0.0458631976 0.0843588412 0.0176814999 0.8203440000 953812707 0 1781317632 -0.0092299553 -0.0089393361 0.0063912729 95 1305031105.3112900257 0.0328299701 0.0457260058 0.0843588412 0.0176777448 0.7822910000 953814557 0 1782947840 -0.0139413038 -0.0108665116 0.0219245218 96 1305031105.3433020115 0.0241904072 0.0455016766 0.0843588412 0.0176192910 0.7872320000 953816343 0 1781309440 -0.0157951433 -0.0149266478 0.0369993038 97 1305031105.3753380775 0.0154066700 0.0451914188 0.0843588412 0.0178051812 0.7771530000 953818129 0 1782919168 -0.0152854947 -0.0196138360 0.0510063060 98 1305031105.4112861156 0.0111468742 0.0448440255 0.0843588412 0.0178382381 0.7709090000 953819979 0 1781178368 -0.0153444763 -0.0197734311 0.0650393069 99 1305031105.4433159828 0.0103812292 0.0444959164 0.0843588412 0.0177514358 0.7749790000 953821765 0 1782951936 -0.0175442956 -0.0157144666 0.0792926177 100 1305031105.4752800465 0.0059864530 0.0441108218 0.0843588412 0.0176957397 0.7539960000 953823551 0 1781579776 -0.0178274233 -0.0178848840 0.0931539014 101 1305031105.5113320351 0.0056045954 0.0437295720 0.0843588412 0.0176792764 0.7565700000 953825401 0 1783173120 -0.0190025903 -0.0166614167 0.1070545837 102 1305031105.5432820320 0.0074177780 0.0433735741 0.0843588412 0.0176211629 0.7521150000 953827187 0 1781768192 -0.0190506279 -0.0153934211 0.1209970564 103 1305031105.5754489899 0.0093127107 0.0430428861 0.0843588412 0.0175426030 0.7289080000 953828973 0 1783578624 -0.0207775366 -0.0154578267 0.1345171332 104 1305031105.6113779545 0.0114946282 0.0427395374 0.0843588412 0.0174640644 0.7224420000 953830823 0 1782071296 -0.0222574547 -0.0138851078 0.1482236832 105 1305031105.6432731152 0.0156552028 0.0424815914 0.0843588412 0.0174362044 0.7113580000 953832609 0 1783799808 -0.0233387128 -0.0143065071 0.1620744467 106 1305031105.6751658916 0.0176609699 0.0422474346 0.0843588412 0.0174046043 0.7139320000 953834395 0 1782308864 -0.0244315099 -0.0117847994 0.1762249768 107 1305031105.7113089561 0.0204152577 0.0420433955 0.0843588412 0.0175019820 0.7043710000 953836245 0 1783943168 -0.0238088463 -0.0091933711 0.1898150444 108 1305031105.7433118820 0.0240067802 0.0418763898 0.0843588412 0.0174321999 0.7421310000 953838031 0 1782308864 -0.0245194752 -0.0083963694 0.2035864592 109 1305031105.7753388882 0.0228547975 0.0417018798 0.0843588412 0.0173608417 0.7291010000 953839817 0 1783926784 -0.0250900220 -0.0026203990 0.2174229175 110 1305031105.8112831116 0.0271733962 0.0415698027 0.0843588412 0.0172974228 0.7068350000 953841667 0 1782435840 -0.0253440794 -0.0012873969 0.2311418504 111 1305031105.8432710171 0.0292899385 0.0414591733 0.0843588412 0.0172218640 0.7054990000 953843453 0 1784070144 -0.0261703525 0.0016494682 0.2449409813 112 1305031105.8753368855 0.0303208753 0.0413597242 0.0843588412 0.0171709988 0.7211320000 953845239 0 1782530048 -0.0255019832 0.0061538839 0.2584518790 113 1305031105.9112620354 0.0318453610 0.0412755263 0.0843588412 0.0172017596 0.7196910000 953847089 0 1784180736 -0.0251500811 0.0121520068 0.2724490464 114 1305031105.9432721138 0.0345136411 0.0412162115 0.0843588412 0.0171409135 0.6944270000 953848875 0 1782562816 -0.0243632197 0.0155508462 0.2857072651 115 1305031105.9753289223 0.0363576561 0.0411739632 0.0843588412 0.0171163728 0.7044360000 953850661 0 1784213504 -0.0249338523 0.0204199422 0.2985688150 116 1305031106.0112850666 0.0404219963 0.0411674807 0.0843588412 0.0170642665 0.6693190000 953852511 0 1782657024 -0.0244901106 0.0242201816 0.3113239408 117 1305031106.0433549881 0.0428375714 0.0411817550 0.0843588412 0.0169921700 0.6500490000 953854329 0 1784451072 -0.0246898327 0.0281293616 0.3236108422 118 1305031106.0753300190 0.0460626185 0.0412231183 0.0843588412 0.0169335302 0.6394380000 953856083 0 1782833152 -0.0253418628 0.0315606631 0.3356249332 119 1305031106.1113269329 0.0489076339 0.0412876940 0.0843588412 0.0169323269 0.6478800000 953857933 0 1781133312 -0.0289799906 0.0360516682 0.3470163643 120 1305031106.1433548927 0.0507354923 0.0413664257 0.0843588412 0.0168686560 0.6231740000 953859751 0 1782927360 -0.0295895543 0.0403346121 0.3585247993 121 1305031106.1755340099 0.0559915267 0.0414872943 0.0843588412 0.0168027190 0.6087890000 953861505 0 1781444608 -0.0310402662 0.0410727635 0.3694921136 122 1305031106.2112751007 0.0601263344 0.0416400733 0.0843588412 0.0167375741 0.5969890000 953863355 0 1783037952 -0.0325340815 0.0429674536 0.3793527782 123 1305031106.2432670593 0.0652098656 0.0418316976 0.0843588412 0.0166735536 0.5943190000 953865173 0 1781682176 -0.0339133851 0.0430548936 0.3884099126 124 1305031106.2763850689 0.0673783794 0.0420377193 0.0843588412 0.0166130312 0.5941130000 953866959 0 1783291904 -0.0344835632 0.0458860211 0.3960971832 125 1305031106.3112380505 0.0675330162 0.0422416816 0.0843588412 0.0165601233 0.5921830000 953868777 0 1781686272 -0.0342955738 0.0499657020 0.4029954374 126 1305031106.3432579041 0.0690534934 0.0424544738 0.0843588412 0.0165831386 0.5827700000 953870595 0 1783324672 -0.0341668129 0.0524535477 0.4091717303 127 1305031106.3753879070 0.0688192323 0.0426620703 0.0843588412 0.0166122310 0.5704950000 953872349 0 1781895168 -0.0350417681 0.0556854904 0.4137847126 128 1305031106.4113199711 0.0698905066 0.0428747925 0.0843588412 0.0166575578 0.5628980000 953874199 0 1783689216 -0.0356300958 0.0565347821 0.4166498482 129 1305031106.4432780743 0.0806466192 0.0431675973 0.0843588412 0.0168364222 0.5882570000 953875985 0 1782149120 -0.0368120335 0.0455744416 0.4185357094 130 1305031106.4753448963 0.0812916309 0.0434608591 0.0843588412 0.0168973053 0.5466300000 953898763 0 1783943168 -0.0386227444 0.0434063487 0.4162032604 131 1305031106.5111289024 0.0820901319 0.0437557391 0.0843588412 0.0169121958 0.5550120000 953900517 0 1782403072 -0.0403283164 0.0400408655 0.4119924307 132 1305031106.5433020592 0.0857124925 0.0440735933 0.0857124925 0.0168761606 0.6235590000 953902335 0 1784180736 -0.0394477211 0.0323075652 0.4062016606 133 1305031106.5752820969 0.0840156153 0.0443739092 0.0857124925 0.0168276180 0.5852170000 953904089 0 1782546432 -0.0379054770 0.0291561466 0.3976009190 134 1305031106.6111509800 0.0816171020 0.0446518435 0.0857124925 0.0168466665 0.5701530000 953905939 0 1784180736 -0.0380679853 0.0266175698 0.3877213299 135 1305031106.6432070732 0.0797675475 0.0449119598 0.0857124925 0.0168219189 0.5696750000 953907757 0 1782579200 -0.0379183367 0.0232523382 0.3773932457 136 1305031106.6752789021 0.0812164322 0.0451789045 0.0857124925 0.0167825342 0.5828870000 953909511 0 1784307712 -0.0375055708 0.0159613006 0.3662341833 137 1305031106.7115080357 0.0789231881 0.0454252131 0.0857124925 0.0168030404 0.5635540000 953911361 0 1782710272 -0.0368991420 0.0135923810 0.3534568846 138 1305031106.7433409691 0.0789860412 0.0456684075 0.0857124925 0.0167975628 0.5792240000 953913179 0 1784324096 -0.0361809246 0.0074994639 0.3408176303 139 1305031106.7753899097 0.0776161999 0.0458982477 0.0857124925 0.0167419918 0.5830990000 953914933 0 1782657024 -0.0346138850 0.0030019693 0.3272836804 140 1305031106.8112890720 0.0760572404 0.0461136691 0.0857124925 0.0167088320 0.5757710000 953916783 0 1784467456 -0.0323459804 -0.0000389703 0.3128827512 141 1305031106.8434159756 0.0731874332 0.0463056816 0.0857124925 0.0166865349 0.6224540000 953918569 0 1782784000 -0.0303421784 -0.0030016156 0.2983026803 142 1305031106.8759050369 0.0740420371 0.0465010081 0.0857124925 0.0168320295 0.5838220000 953920355 0 1784475648 -0.0298108961 -0.0117505603 0.2829808295 143 1305031106.9112429619 0.0718633309 0.0466783670 0.0857124925 0.0168431913 0.5847170000 953922205 0 1782931456 -0.0286701452 -0.0151233086 0.2656101882 144 1305031106.9434390068 0.0650741830 0.0468061157 0.0857124925 0.0168005429 0.5830390000 953923991 0 1784569856 -0.0279436447 -0.0154428948 0.2478889823 145 1305031106.9755470753 0.0638739541 0.0469238249 0.0857124925 0.0168049062 0.5853170000 953925777 0 1782968320 -0.0290995315 -0.0228732582 0.2305249125 146 1305031107.0115759373 0.0619586930 0.0470268035 0.0857124925 0.0167713253 0.5927240000 953927659 0 1784569856 -0.0304149017 -0.0279823318 0.2122163177 147 1305031107.0432810783 0.0525631905 0.0470644660 0.0857124925 0.0167971874 0.5994910000 953929445 0 1782820864 -0.0292374454 -0.0245298687 0.1940853894 148 1305031107.0754320621 0.0503825359 0.0470868854 0.0857124925 0.0168395108 0.5986450000 953931199 0 1784586240 -0.0304379631 -0.0309293643 0.1777979732 149 1305031107.1112289429 0.0499289706 0.0471059598 0.0857124925 0.0167897670 0.6096490000 953933049 0 1783046144 -0.0311617516 -0.0362981185 0.1613505036 150 1305031107.1432600021 0.0437976532 0.0470839044 0.0857124925 0.0167823565 0.6122690000 953934867 0 1781325824 -0.0289743431 -0.0358460955 0.1453363448 151 1305031107.1753990650 0.0392515622 0.0470320346 0.0857124925 0.0167365029 0.6063830000 953936621 0 1782919168 -0.0281031094 -0.0372274183 0.1305018961 152 1305031107.2113580704 0.0406553186 0.0469900825 0.0857124925 0.0168207058 0.6084520000 953938471 0 1781444608 -0.0286259353 -0.0437522642 0.1161171496 153 1305031107.2433779240 0.0365172774 0.0469216328 0.0857124925 0.0167749678 0.6289150000 953940257 0 1783308288 -0.0272211470 -0.0467548445 0.1016025245 154 1305031107.2753980160 0.0321807191 0.0468259126 0.0857124925 0.0167331889 0.6397710000 953942043 0 1781641216 -0.0250102729 -0.0473137572 0.0877775401 155 1305031107.3112258911 0.0314380117 0.0467266358 0.0857124925 0.0167200537 0.6410760000 953943893 0 1783435264 -0.0253980886 -0.0501950979 0.0740636140 156 1305031107.3435089588 0.0280382391 0.0466068384 0.0857124925 0.0167801070 0.6613310000 953945711 0 1781665792 -0.0257282332 -0.0538749769 0.0605005659 157 1305031107.3754129410 0.0234950501 0.0464596295 0.0857124925 0.0168332786 0.6965520000 953947465 0 1783291904 -0.0242211800 -0.0538735539 0.0478241518 158 1305031107.4112710953 0.0200295094 0.0462923503 0.0857124925 0.0168125770 0.7356920000 953949315 0 1781768192 -0.0198881309 -0.0502017774 0.0375646390 159 1305031107.4434189796 0.0172577389 0.0461097427 0.0857124925 0.0167633900 0.7180790000 953951133 0 1783451648 -0.0179095417 -0.0487004183 0.0294726454 160 1305031107.4753770828 0.0178871285 0.0459333513 0.0857124925 0.0167218049 0.7075530000 953952919 0 1781833728 -0.0159989558 -0.0466437899 0.0237357672 161 1305031107.5113520622 0.0207776967 0.0457771050 0.0857124925 0.0166999933 0.6959290000 953954737 0 1783418880 -0.0141588850 -0.0449422151 0.0198377203 162 1305031107.5436050892 0.0243082251 0.0456445811 0.0857124925 0.0167176154 0.7033700000 953956555 0 1782087680 -0.0125143966 -0.0410325155 0.0183320753 163 1305031107.5754539967 0.0246194359 0.0455155925 0.0857124925 0.0166927937 0.7037010000 953958309 0 1783816192 -0.0099098999 -0.0408326425 0.0177765805 164 1305031107.6112709045 0.0229812637 0.0453781880 0.0857124925 0.0166533991 0.7136910000 953960159 0 1782276096 -0.0073326924 -0.0419374220 0.0176871624 165 1305031107.6433229446 0.0228000376 0.0452413507 0.0857124925 0.0166420446 0.7455820000 953961977 0 1784053760 -0.0046025105 -0.0380163267 0.0192471668 166 1305031107.6755681038 0.0219343547 0.0451009472 0.0857124925 0.0166125800 0.7075450000 953963731 0 1782706176 -0.0037140595 -0.0370029174 0.0209306087 167 1305031107.7113070488 0.0206902865 0.0449547755 0.0857124925 0.0165708202 0.7132000000 953965581 0 1784340480 -0.0038770537 -0.0361197405 0.0229385495 168 1305031107.7435379028 0.0207502525 0.0448107010 0.0857124925 0.0165520119 0.7184650000 953967367 0 1782784000 -0.0040415931 -0.0333477892 0.0254116971 169 1305031107.7758018970 0.0208576769 0.0446689671 0.0857124925 0.0165104508 0.7255310000 953969153 0 1784578048 -0.0052638357 -0.0310682096 0.0278591067 170 1305031107.8115959167 0.0197315626 0.0445222765 0.0857124925 0.0164634738 0.7302420000 953971003 0 1783070720 -0.0050666300 -0.0311831795 0.0303581916 171 1305031107.8433320522 0.0192623567 0.0443745577 0.0857124925 0.0164232145 0.7362760000 953972789 0 1781698560 -0.0046199611 -0.0304549802 0.0328798704 172 1305031107.8753581047 0.0189493634 0.0442267368 0.0857124925 0.0164018928 0.7707550000 953974575 0 1783291904 -0.0041542668 -0.0307300240 0.0348920859 173 1305031107.9115409851 0.0193743706 0.0440830815 0.0857124925 0.0163871129 0.7443790000 953976425 0 1781768192 -0.0025547706 -0.0320979431 0.0364691801 174 1305031107.9431219101 0.0212879106 0.0439520748 0.0857124925 0.0163919203 0.7286100000 953978211 0 1783562240 -0.0012519235 -0.0322917141 0.0377527140 175 1305031107.9758069515 0.0246983878 0.0438420537 0.0857124925 0.0163867390 0.7168340000 953979997 0 1782071296 0.0022292398 -0.0316084474 0.0387557484 176 1305031108.0113201141 0.0275980178 0.0437497580 0.0857124925 0.0163559051 0.7255520000 953981847 0 1783799808 0.0065816902 -0.0313247852 0.0401621498 177 1305031108.0434179306 0.0294689294 0.0436690754 0.0857124925 0.0163226344 0.7437030000 953983633 0 1782284288 0.0141133117 -0.0273650307 0.0417596735 178 1305031108.0753519535 0.0317102000 0.0436018907 0.0857124925 0.0162895827 0.7175420000 953985387 0 1784070144 0.0225571636 -0.0234909467 0.0437425226 179 1305031108.1113779545 0.0407762229 0.0435861048 0.0857124925 0.0162521270 0.7308720000 953987237 0 1782575104 0.0269637313 -0.0240255576 0.0458063893 180 1305031108.1433339119 0.0439081639 0.0435878940 0.0857124925 0.0162247090 0.7251080000 953989023 0 1784180736 0.0351594947 -0.0223462172 0.0484831184 181 1305031108.1760580540 0.0491375662 0.0436185552 0.0857124925 0.0162718976 0.7096160000 953990809 0 1782824960 0.0455078147 -0.0180182811 0.0516952313 182 1305031108.2114748955 0.0521965995 0.0436656873 0.0857124925 0.0162724451 0.7085490000 953992659 0 1784578048 0.0541811176 -0.0140354848 0.0559755117 183 1305031108.2433469296 0.0525612980 0.0437142972 0.0857124925 0.0162794465 0.7083850000 953994445 0 1782910976 0.0642976090 -0.0173913855 0.0592009388 184 1305031108.2753579617 0.0523219295 0.0437610778 0.0857124925 0.0162383140 0.7209380000 953996231 0 1784561664 0.0754121467 -0.0206204504 0.0618668310 185 1305031108.3113319874 0.0576498285 0.0438361522 0.0857124925 0.0163859449 0.7143030000 953998081 0 1783083008 0.0844740868 -0.0150371976 0.0655990392 186 1305031108.3432779312 0.0586828403 0.0439159731 0.0857124925 0.0163700386 0.7341190000 953999899 0 1781428224 0.0938280746 -0.0122757265 0.0696055591 187 1305031108.3754100800 0.0575636290 0.0439889552 0.0857124925 0.0163423680 0.7131890000 954001653 0 1783037952 0.1052864194 -0.0119712148 0.0733178034 188 1305031108.4113609791 0.0599159747 0.0440736734 0.0857124925 0.0163055712 0.7176020000 954003503 0 1781428224 0.1171256676 -0.0127864555 0.0769078061 189 1305031108.4436099529 0.0574294962 0.0441443391 0.0857124925 0.0163160407 0.7194920000 954005321 0 1783091200 0.1308197379 -0.0141626820 0.0798671395 190 1305031108.4754710197 0.0568456277 0.0442111880 0.0857124925 0.0163211761 0.7155320000 954007075 0 1781297152 0.1429045945 -0.0151066510 0.0824418142 191 1305031108.5113780499 0.0607486516 0.0442977716 0.0857124925 0.0165854145 0.7164290000 954008925 0 1783037952 0.1550609618 -0.0179474205 0.0836116374 192 1305031108.5437369347 0.0625881180 0.0443930338 0.0857124925 0.0166185156 0.7110360000 954010743 0 1781420032 0.1656466872 -0.0203715265 0.0835162699 193 1305031108.5754139423 0.0648001209 0.0444987700 0.0857124925 0.0166523007 0.7548790000 954012497 0 1782951936 0.1750675738 -0.0192105044 0.0840870589 194 1305031108.6114070415 0.0708040595 0.0446343643 0.0857124925 0.0166456659 0.7179200000 954014347 0 1781452800 0.1829239279 -0.0119334999 0.0853826478 195 1305031108.6433029175 0.0732134208 0.0447809235 0.0857124925 0.0166159204 0.6932810000 954016165 0 1783046144 0.1919949651 -0.0115520088 0.0865802243 196 1305031108.6753749847 0.0753129795 0.0449366993 0.0857124925 0.0166157040 0.6979080000 954017919 0 1781530624 0.2005223036 -0.0074133016 0.0883419439 197 1305031108.7114109993 0.0795845091 0.0451125765 0.0857124925 0.0166264510 0.6903470000 954019737 0 1783332864 0.2096536607 -0.0047539813 0.0897886828 198 1305031108.7435019016 0.0817745477 0.0452977380 0.0857124925 0.0166008849 0.6863540000 954021555 0 1781776384 0.2174956352 -0.0060178023 0.0906140581 199 1305031108.7754929066 0.0824318379 0.0454843415 0.0857124925 0.0165612860 0.6750360000 954023309 0 1783570432 0.2254624516 -0.0061776065 0.0910373405 200 1305031108.8112440109 0.0835049599 0.0456744446 0.0857124925 0.0165224749 0.6740810000 954025159 0 1781821440 0.2335198671 -0.0047798213 0.0910861045 201 1305031108.8432641029 0.0839959458 0.0458650989 0.0857124925 0.0179462013 0.6697440000 954026977 0 1783427072 0.2408382595 -0.0055039460 0.0900238082 202 1305031108.8765149117 0.0770886242 0.0460196708 0.0857124925 0.0179775292 0.6723770000 954028763 0 1782063104 0.2479701489 -0.0059792744 0.0880853385 203 1305031108.9113640785 0.0719504282 0.0461474085 0.0857124925 0.0180633040 0.6763740000 954030581 0 1783816192 0.2532963157 -0.0060480055 0.0856560469 204 1305031108.9432430267 0.0706518292 0.0462675282 0.0857124925 0.0181278050 0.6835710000 954032399 0 1782022144 0.2557848394 -0.0096006095 0.0825164691 205 1305031108.9752678871 0.0692030042 0.0463794086 0.0857124925 0.0181072257 0.6769050000 954034185 0 1783709696 0.2545102239 -0.0103734983 0.0800327435 206 1305031109.0112690926 0.0618907399 0.0464547063 0.0857124925 0.0180821015 0.7093530000 954036003 0 1782157312 0.2545456588 -0.0053552110 0.0780690312 207 1305031109.0432770252 0.0595160834 0.0465178047 0.0857124925 0.0180594526 0.6769200000 954037821 0 1783816192 0.2511269152 -0.0075245090 0.0761631951 208 1305031109.0754098892 0.0583679490 0.0465747766 0.0857124925 0.0180532419 0.6883930000 954039575 0 1782403072 0.2452125847 -0.0080481665 0.0749129578 209 1305031109.1112821102 0.0530689955 0.0466058494 0.0857124925 0.0180277013 0.6967370000 954041425 0 1784197120 0.2381925881 -0.0042988625 0.0747059956 210 1305031109.1433339119 0.0504884943 0.0466243382 0.0857124925 0.0180057592 0.7043280000 954043243 0 1782812672 0.2316680849 -0.0074004633 0.0737280920 211 1305031109.1754639149 0.0489211716 0.0466352236 0.0857124925 0.0180159892 0.7165730000 954044997 0 1784434688 0.2233880013 -0.0091534844 0.0729615465 212 1305031109.2113790512 0.0418345965 0.0466125792 0.0857124925 0.0180220755 0.7309330000 954046847 0 1782939648 0.2153211385 -0.0053221928 0.0735381246 213 1305031109.2432899475 0.0376481563 0.0465704927 0.0857124925 0.0179872245 0.7115730000 954048665 0 1781551104 0.2075161785 -0.0028980325 0.0752221346 214 1305031109.2753078938 0.0371108763 0.0465262889 0.0857124925 0.0181029924 0.7249450000 954050419 0 1783201792 0.1973956525 -0.0069825631 0.0754745752 215 1305031109.3113288879 0.0341377594 0.0464686678 0.0857124925 0.0181700939 0.7191620000 954052269 0 1781514240 0.1866093725 -0.0131144579 0.0746879578 216 1305031109.3432478905 0.0300488174 0.0463926500 0.0857124925 0.0182026150 0.7547220000 954054087 0 1783201792 0.1759703010 -0.0093587618 0.0751497746 217 1305031109.3753969669 0.0281820484 0.0463087302 0.0857124925 0.0181699237 0.7215170000 954055841 0 1781428224 0.1642580032 -0.0083449641 0.0761947483 218 1305031109.4113290310 0.0251076464 0.0462114775 0.0857124925 0.0181303896 0.7223610000 954057691 0 1783074816 0.1526608318 -0.0113113150 0.0762597471 219 1305031109.4433019161 0.0232945308 0.0461068339 0.0857124925 0.0181125833 0.7282890000 954059477 0 1781387264 0.1410330236 -0.0095094303 0.0766906217 220 1305031109.4753630161 0.0236127116 0.0460045879 0.0857124925 0.0181023938 0.7225020000 954061231 0 1783197696 0.1282267869 -0.0098627340 0.0765995607 221 1305031109.5112729073 0.0240272805 0.0459051430 0.0857124925 0.0180845632 0.7166340000 954063081 0 1781682176 0.1145418063 -0.0131548857 0.0755270645 222 1305031109.5432939529 0.0260488037 0.0458157001 0.0857124925 0.0180640109 0.7164860000 954064899 0 1783291904 0.1008023918 -0.0157636236 0.0736571252 223 1305031109.5753619671 0.0245335698 0.0457202645 0.0857124925 0.0180261639 0.7553730000 954066685 0 1781641216 0.0890631005 -0.0142509174 0.0718044043 224 1305031109.6113100052 0.0217689462 0.0456133390 0.0857124925 0.0180110095 0.7285100000 954068503 0 1783435264 0.0766860098 -0.0124471942 0.0700496957 225 1305031109.6432290077 0.0217984319 0.0455074950 0.0857124925 0.0179718079 0.7236470000 954070321 0 1781923840 0.0649310350 -0.0117379576 0.0686302632 226 1305031109.6752629280 0.0202782061 0.0453958609 0.0857124925 0.0179344811 0.7333350000 954072075 0 1783545856 0.0546075813 -0.0097779222 0.0679334700 227 1305031109.7113120556 0.0190904681 0.0452799781 0.0857124925 0.0179555779 0.7294890000 954073925 0 1781895168 0.0429460630 -0.0084223449 0.0678017661 228 1305031109.7432739735 0.0188679546 0.0451641359 0.0857124925 0.0179167503 0.7363660000 954075743 0 1783578624 0.0305693522 -0.0052535320 0.0685328320 229 1305031109.7752768993 0.0199672896 0.0450541060 0.0857124925 0.0179008570 0.7158490000 954077497 0 1782198272 0.0195253268 -0.0064468952 0.0695843697 230 1305031109.8113710880 0.0200727247 0.0449454913 0.0857124925 0.0178719800 0.7373300000 954079347 0 1783926784 0.0067151156 -0.0066823070 0.0705711991 231 1305031109.8432960510 0.0202570688 0.0448386150 0.0857124925 0.0178399694 0.7202550000 954081165 0 1782403072 -0.0055758487 -0.0046399278 0.0721163526 232 1305031109.8753058910 0.0210174341 0.0447359375 0.0857124925 0.0178104081 0.7093860000 954082919 0 1784070144 -0.0184758939 -0.0038196156 0.0745693669 233 1305031109.9112648964 0.0234183036 0.0446444456 0.0857124925 0.0177913976 0.7084020000 954084769 0 1782435840 -0.0297318809 -0.0050061210 0.0770858899 234 1305031109.9432990551 0.0251726024 0.0445612325 0.0857124925 0.0177858509 0.7006380000 954086587 0 1784188928 -0.0436156280 -0.0047221719 0.0803163201 235 1305031109.9752581120 0.0257241651 0.0444810748 0.0857124925 0.0177523723 0.7030930000 954088341 0 1782571008 -0.0541874953 -0.0003084885 0.0837675780 236 1305031110.0112559795 0.0288331248 0.0444147699 0.0857124925 0.0177185422 0.6931010000 954090191 0 1784221696 -0.0679865181 -0.0020733147 0.0872048587 237 1305031110.0432989597 0.0296708569 0.0443525593 0.0857124925 0.0176824908 0.7459500000 954092009 0 1782538240 -0.0820942819 -0.0014506802 0.0906685889 238 1305031110.0753190517 0.0312164389 0.0442973656 0.0857124925 0.0176577484 0.6868290000 954093763 0 1784188928 -0.0952449217 -0.0017541554 0.0942098275 239 1305031110.1113250256 0.0333195776 0.0442514334 0.0857124925 0.0176702138 0.6666250000 954095613 0 1782677504 -0.1074371412 -0.0005631372 0.0977568552 240 1305031110.1434319019 0.0358538777 0.0442164436 0.0857124925 0.0176959942 0.6800730000 954097431 0 1784451072 -0.1214100718 -0.0038743075 0.1013500765 241 1305031110.1756410599 0.0382411480 0.0441916498 0.0857124925 0.0176597449 0.6609430000 954099185 0 1782657024 -0.1310005635 -0.0048140432 0.1042522416 242 1305031110.2116370201 0.0408149138 0.0441776964 0.0857124925 0.0176325671 0.6600730000 954101067 0 1784451072 -0.1405128092 -0.0026283858 0.1069706678 243 1305031110.2433230877 0.0442964211 0.0441781849 0.0857124925 0.0176340723 0.6527210000 954102853 0 1782833152 -0.1508374065 -0.0064019617 0.1095603257 244 1305031110.2793209553 0.0481054746 0.0441942804 0.0857124925 0.0176195542 0.6426820000 954104703 0 1784561664 -0.1585031599 -0.0079846932 0.1107219830 245 1305031110.3114039898 0.0485361442 0.0442120023 0.0857124925 0.0175850838 0.6650270000 954106457 0 1782943744 -0.1683960706 -0.0076073632 0.1112314165 246 1305031110.3433549404 0.0503281280 0.0442368646 0.0857124925 0.0175550666 0.6578640000 954108243 0 1784578048 -0.1761618406 -0.0069957916 0.1117560714 247 1305031110.3792810440 0.0517297126 0.0442672000 0.0857124925 0.0175482758 0.6857760000 954110093 0 1782910976 -0.1875252724 -0.0047438308 0.1119843796 248 1305031110.4114689827 0.0530945510 0.0443027942 0.0857124925 0.0175312748 0.6920850000 954111879 0 1781317632 -0.1982494593 -0.0039488282 0.1126907095 249 1305031110.4432599545 0.0542284250 0.0443426561 0.0857124925 0.0175007278 0.6951270000 954113665 0 1782927360 -0.2081588060 0.0005350559 0.1137343794 250 1305031110.4793310165 0.0583357513 0.0443986285 0.0857124925 0.0175321490 0.7013070000 954115547 0 1781387264 -0.2195135057 0.0001357552 0.1151950210 251 1305031110.5114290714 0.0617009699 0.0444675621 0.0857124925 0.0175150460 0.6999130000 954117301 0 1783181312 -0.2296694666 -0.0027066746 0.1172366291 252 1305031110.5434079170 0.0635307655 0.0445432098 0.0857124925 0.0174902431 0.7081040000 954119119 0 1781428224 -0.2393973023 -0.0011715535 0.1185482889 253 1305031110.5794260502 0.0649930239 0.0446240391 0.0857124925 0.0174964378 0.7585040000 954120969 0 1783070720 -0.2520871162 0.0023805108 0.1201650351 254 1305031110.6113069057 0.0671648011 0.0447127822 0.0857124925 0.0175186311 0.7197270000 954122723 0 1781514240 -0.2621755302 0.0020902322 0.1222881377 255 1305031110.6434180737 0.0704326704 0.0448136445 0.0857124925 0.0175441197 0.7125400000 954124541 0 1783308288 -0.2710598409 -0.0033603124 0.1243842542 256 1305031110.6796059608 0.0721641704 0.0449204825 0.0857124925 0.0175536435 0.6964920000 954126359 0 1781813248 -0.2779634893 -0.0028626714 0.1245666668 257 1305031110.7114119530 0.0717469156 0.0450248655 0.0857124925 0.0175239855 0.6980160000 954128145 0 1783418880 -0.2855711877 -0.0000685267 0.1250230819 258 1305031110.7432489395 0.0723605007 0.0451308176 0.0857124925 0.0175326492 0.6976570000 954171915 0 1781768192 -0.2921122015 -0.0018055402 0.1258633733 259 1305031110.7791929245 0.0732785612 0.0452394962 0.0857124925 0.0174999891 0.7018370000 954173765 0 1783562240 -0.2983643711 -0.0037651025 0.1264131218 260 1305031110.8113861084 0.0734142289 0.0453478605 0.0857124925 0.0174675546 0.7383460000 954175551 0 1782054912 -0.3010573685 -0.0028574094 0.1267723441 261 1305031110.8432180882 0.0726392791 0.0454524253 0.0857124925 0.0174456892 0.7093490000 954177337 0 1783672832 -0.3050612509 -0.0022716355 0.1270845830 262 1305031110.8793129921 0.0727067217 0.0455564494 0.0857124925 0.0174135650 0.7074230000 954179187 0 1782161408 -0.3079515398 -0.0044142138 0.1274420023 263 1305031110.9113330841 0.0726981908 0.0456596499 0.0857124925 0.0173948835 0.7060950000 954180973 0 1783943168 -0.3088693619 -0.0042720288 0.1282278150 264 1305031110.9438619614 0.0723155290 0.0457606191 0.0857124925 0.0173840056 0.7116140000 954182791 0 1782276096 -0.3088573813 -0.0047168937 0.1288079023 265 1305031110.9793450832 0.0712276548 0.0458567212 0.0857124925 0.0174117727 0.7179550000 954184577 0 1783926784 -0.3067139387 -0.0038427990 0.1292987764 266 1305031111.0114309788 0.0692819655 0.0459447860 0.0857124925 0.0174061511 0.7197860000 954186395 0 1782325248 -0.3014455140 -0.0008568635 0.1290970743 267 1305031111.0433270931 0.0695891380 0.0460333416 0.0857124925 0.0173752933 0.7396240000 954188181 0 1784086528 -0.2938248515 -0.0018158890 0.1292430013 268 1305031111.0792829990 0.0681714937 0.0461159467 0.0857124925 0.0173663439 0.7278210000 954189999 0 1782530048 -0.2855658233 -0.0007908884 0.1292399615 269 1305031111.1115078926 0.0678443536 0.0461967214 0.0857124925 0.0173457446 0.7228150000 954191817 0 1784180736 -0.2792948782 -0.0013554543 0.1295008063 270 1305031111.1432569027 0.0679218918 0.0462771850 0.0857124925 0.0173277117 0.7245290000 954193603 0 1782562816 -0.2711801529 -0.0030639670 0.1292419881 271 1305031111.1793260574 0.0670447275 0.0463538180 0.0857124925 0.0173865287 0.7535740000 954195453 0 1784197120 -0.2560463548 -0.0029715542 0.1286431253 272 1305031111.2114329338 0.0645468980 0.0464207043 0.0857124925 0.0173713214 0.7358380000 954197207 0 1782657024 -0.2447586507 -0.0011788160 0.1267911941 273 1305031111.2432360649 0.0630601943 0.0464816548 0.0857124925 0.0174067292 0.7071160000 954198993 0 1784340480 -0.2367602587 -0.0013062600 0.1262429506 274 1305031111.2793080807 0.0613649487 0.0465359734 0.0857124925 0.0174480048 0.7401550000 954200843 0 1782689792 -0.2312829643 -0.0046377983 0.1252626032 275 1305031111.3115470409 0.0589270517 0.0465810319 0.0857124925 0.0174542050 0.7372520000 954202629 0 1784340480 -0.2154210955 -0.0031639095 0.1238464192 276 1305031111.3433969021 0.0565420091 0.0466171224 0.0857124925 0.0175933219 0.6913790000 954204415 0 1782784000 -0.2098420411 -0.0004835017 0.1239653081 277 1305031111.3791339397 0.0563890263 0.0466524000 0.0857124925 0.0177021084 0.7036250000 954206265 0 1781305344 -0.2032182962 -0.0027417468 0.1238418445 278 1305031111.4112958908 0.0577197447 0.0466922106 0.0857124925 0.0176754233 0.7458100000 954208019 0 1783062528 -0.1823860556 -0.0064295568 0.1247105151 279 1305031111.4433860779 0.0538662635 0.0467179241 0.0857124925 0.0176668536 0.7273920000 954209837 0 1781563392 -0.1729529649 -0.0021698792 0.1239016503 280 1305031111.4792590141 0.0534932762 0.0467421218 0.0857124925 0.0181098209 0.7326990000 954211687 0 1783173120 -0.1569744498 -0.0041700471 0.1240547970 281 1305031111.5112640858 0.0509560369 0.0467571179 0.0857124925 0.0181093811 0.7057250000 954213441 0 1781710848 -0.1431296319 -0.0043965690 0.1219791174 282 1305031111.5432500839 0.0495918132 0.0467671700 0.0857124925 0.0180884436 0.6779810000 954215259 0 1783443456 -0.1349055022 -0.0058101416 0.1202276498 283 1305031111.5792369843 0.0473158024 0.0467691086 0.0857124925 0.0181096369 0.6946200000 954217109 0 1781649408 -0.1185887009 -0.0063851196 0.1182715893 284 1305031111.6112709045 0.0443861000 0.0467607178 0.0857124925 0.0181936938 0.6838600000 954218831 0 1783451648 -0.1079376712 -0.0035566653 0.1170730889 285 1305031111.6433949471 0.0475155972 0.0467633665 0.0857124925 0.0182108471 0.6469270000 954220649 0 1781915648 -0.1005586907 -0.0078349030 0.1168333441 286 1305031111.6793200970 0.0453663133 0.0467584817 0.0857124925 0.0184285106 0.6735820000 954222467 0 1783664640 -0.0788279548 -0.0093409559 0.1157321855 287 1305031111.7117600441 0.0388330556 0.0467308669 0.0857124925 0.0184479702 0.6637880000 954224285 0 1782280192 -0.0637709871 -0.0025439104 0.1140282154 288 1305031111.7433860302 0.0391732417 0.0467046252 0.0857124925 0.0185294096 0.6482500000 954226071 0 1783934976 -0.0502677187 -0.0053231693 0.1130899340 289 1305031111.7794229984 0.0373196974 0.0466721514 0.0857124925 0.0186221394 0.6729010000 954227921 0 1782276096 -0.0349304378 -0.0038498854 0.1118620932 290 1305031111.8114058971 0.0383416601 0.0466434256 0.0857124925 0.0186484112 0.5912440000 954229675 0 1783943168 -0.0280873887 -0.0028470317 0.1106049642 291 1305031111.8432989120 0.0417499915 0.0466266096 0.0857124925 0.0186297930 0.5796300000 954231461 0 1782435840 -0.0216733683 -0.0031181299 0.1091502309 292 1305031111.8794419765 0.0405145101 0.0466056778 0.0857124925 0.0186202927 0.6127690000 954233279 0 1784053760 -0.0076191975 0.0015388710 0.1087130606 293 1305031111.9113540649 0.0438242480 0.0465961848 0.0857124925 0.0186426848 0.5981590000 954235097 0 1782435840 0.0013918593 -0.0002823882 0.1093347818 294 1305031111.9433000088 0.0456166901 0.0465928532 0.0857124925 0.0186114374 0.6229280000 954236883 0 1784070144 0.0134242736 -0.0033238959 0.1098045930 295 1305031111.9794490337 0.0451038182 0.0465878057 0.0857124925 0.0187622226 0.6241420000 954238701 0 1782579200 0.0293386430 -0.0017354266 0.1100976318 296 1305031112.0114328861 0.0418835171 0.0465719128 0.0857124925 0.0187849670 0.6304050000 954240519 0 1784324096 0.0431530960 0.0007381914 0.1089686975 297 1305031112.0432701111 0.0468266495 0.0465727705 0.0857124925 0.0187544918 0.6260370000 954242305 0 1782784000 0.0493585020 -0.0005260380 0.1078144535 298 1305031112.0793390274 0.0505078994 0.0465859756 0.0857124925 0.0187969207 0.6211600000 954244155 0 1784578048 0.0601424165 0.0012629293 0.1065399274 299 1305031112.1114230156 0.0542929061 0.0466117513 0.0857124925 0.0188525542 0.6047290000 954245909 0 1782976512 0.0676168948 0.0006142566 0.1054160148 300 1305031112.1443419456 0.0568335354 0.0466458239 0.0857124925 0.0188323046 0.6287060000 954247695 0 1784561664 0.0768419951 0.0014127959 0.1051019728 301 1305031112.1793899536 0.0622005612 0.0466975008 0.0857124925 0.0189093523 0.6371130000 954249481 0 1783103488 0.0875281394 0.0028887996 0.1047809198 302 1305031112.2112538815 0.0674261451 0.0467661387 0.0857124925 0.0189042902 0.6359020000 954251267 0 1781571584 0.0961412191 -0.0003875698 0.1047243550 303 1305031112.2433691025 0.0723192543 0.0468504724 0.0857124925 0.0189181786 0.6291210000 954253085 0 1783291904 0.1056679338 -0.0066342428 0.1035560071 304 1305031112.2793529034 0.0782047138 0.0469536113 0.0857124925 0.0189015387 0.6394310000 954254903 0 1781936128 0.1161506549 -0.0064626159 0.1025368124 305 1305031112.3113119602 0.0792591423 0.0470595311 0.0857124925 0.0188919137 0.6781410000 954256721 0 1783578624 0.1272869706 -0.0070916861 0.1014784351 306 1305031112.3433229923 0.0788998306 0.0471635844 0.0857124925 0.0188709057 0.6489250000 954258507 0 1781895168 0.1394896507 -0.0074160141 0.1001245528 307 1305031112.3793599606 0.0810474306 0.0472739552 0.0857124925 0.0188463580 0.6652790000 954260389 0 1783599104 0.1518151611 -0.0043445034 0.0992466435 308 1305031112.4114420414 0.0794670582 0.0473784783 0.0857124925 0.0188275975 0.6514490000 954262143 0 1782063104 0.1643136144 -0.0031589221 0.0988817215 309 1305031112.4433910847 0.0772593990 0.0474751803 0.0857124925 0.0188137753 0.6546040000 954263961 0 1783672832 0.1772619039 -0.0032193447 0.0981957167 310 1305031112.4794180393 0.0786126330 0.0475756237 0.0857124925 0.0187969381 0.6595320000 954265811 0 1782296576 0.1894912869 -0.0041119796 0.0972277299 311 1305031112.5115039349 0.0756122619 0.0476657737 0.0857124925 0.0187808162 0.6583360000 954267565 0 1783975936 0.2013893574 -0.0027149979 0.0963552520 312 1305031112.5432119370 0.0737246349 0.0477492956 0.0857124925 0.0187633254 0.6670950000 954269351 0 1782657024 0.2123204172 -0.0034583928 0.0955735222 313 1305031112.5792520046 0.0746227354 0.0478351533 0.0857124925 0.0187354482 0.6576360000 954271169 0 1784340480 0.2226387709 -0.0026880465 0.0951786339 314 1305031112.6112608910 0.0724532455 0.0479135548 0.0857124925 0.0187830241 0.6633290000 954272955 0 1782972416 0.2329154760 -0.0009143029 0.0949388668 315 1305031112.6432459354 0.0713549256 0.0479879719 0.0857124925 0.0188135488 0.6827840000 954274773 0 1781641216 0.2409831434 0.0022512418 0.0952685103 316 1305031112.6799519062 0.0745021999 0.0480718777 0.0857124925 0.0188088507 0.6551600000 954276623 0 1783328768 0.2454223186 0.0028393012 0.0955980644 317 1305031112.7112510204 0.0756076053 0.0481587412 0.0857124925 0.0188032304 0.6533810000 954278377 0 1781809152 0.2487408966 0.0031536513 0.0963104963 318 1305031112.7432448864 0.0759682655 0.0482461925 0.0857124925 0.0187968377 0.6456400000 954280195 0 1783545856 0.2507989705 0.0061771567 0.0978356376 319 1305031112.7793099880 0.0747173578 0.0483291742 0.0857124925 0.0187961034 0.6458620000 954282045 0 1782190080 0.2520114183 0.0104040857 0.0999906659 320 1305031112.8113100529 0.0727492273 0.0484054869 0.0857124925 0.0188053799 0.6584930000 954283799 0 1783853056 0.2528919578 0.0084206611 0.1008593291 321 1305031112.8432860374 0.0715318471 0.0484775316 0.0857124925 0.0188155703 0.6867940000 954285585 0 1782276096 0.2515481412 0.0079834703 0.1024897397 322 1305031112.8794209957 0.0676185042 0.0485369756 0.0857124925 0.0188324358 0.6536730000 954287435 0 1784070144 0.2506879270 0.0094269337 0.1041992009 323 1305031112.9114110470 0.0637630820 0.0485841153 0.0857124925 0.0188066804 0.6538300000 954289253 0 1782407168 0.2500799596 0.0099897729 0.1051212251 324 1305031112.9433209896 0.0606289729 0.0486212908 0.0857124925 0.0187807900 0.6582400000 954291039 0 1784180736 0.2475153357 0.0093387021 0.1055731326 325 1305031112.9792780876 0.0562942997 0.0486449000 0.0857124925 0.0187962796 0.6628440000 954292889 0 1782681600 0.2435866147 0.0071942783 0.1056090593 326 1305031113.0113530159 0.0541767478 0.0486618689 0.0857124925 0.0187727435 0.6659590000 954294643 0 1784451072 0.2386967689 0.0055634975 0.1054409221 327 1305031113.0432310104 0.0517963730 0.0486714545 0.0857124925 0.0187536457 0.6662100000 954296461 0 1782784000 0.2319566607 0.0056745172 0.1053794101 328 1305031113.0792510509 0.0494637750 0.0486738701 0.0857124925 0.0187633066 0.6767700000 954298311 0 1784614912 0.2226348817 0.0012613918 0.1043216363 329 1305031113.1113159657 0.0491054542 0.0486751819 0.0857124925 0.0187566242 0.7268040000 954300065 0 1783070720 0.2140735239 -0.0033406857 0.1023790166 330 1305031113.1433060169 0.0468697287 0.0486697109 0.0857124925 0.0187407125 0.6882480000 954301883 0 1781522432 0.2035743147 -0.0006252779 0.1016031578 331 1305031113.1793429852 0.0417095870 0.0486486833 0.0857124925 0.0187573503 0.6831470000 954303733 0 1783173120 0.1936267167 -0.0013962965 0.1006868929 332 1305031113.2112588882 0.0425937846 0.0486304457 0.0857124925 0.0187450917 0.6855200000 954305487 0 1781710848 0.1833598912 -0.0070810374 0.0987722725 333 1305031113.2432270050 0.0386552513 0.0486004901 0.0857124925 0.0187420295 0.6918280000 954307305 0 1783443456 0.1732596904 -0.0058276840 0.0980753601 334 1305031113.2793118954 0.0329473428 0.0485536244 0.0857124925 0.0187608829 0.6982540000 954309123 0 1781776384 0.1620026082 -0.0069991695 0.0978369117 335 1305031113.3114519119 0.0352532156 0.0485139217 0.0857124925 0.0188271784 0.7051830000 954310909 0 1783586816 0.1496950537 -0.0146392956 0.0966082737 336 1305031113.3432519436 0.0318200551 0.0484642376 0.0857124925 0.0188391704 0.7122670000 954312695 0 1781944320 0.1369044334 -0.0145410076 0.0953806266 337 1305031113.3793120384 0.0204500463 0.0483811094 0.0857124925 0.0188848919 0.7162090000 954314513 0 1783681024 0.1239568070 -0.0078403186 0.0971060246 338 1305031113.4116249084 0.0220373515 0.0483031693 0.0857124925 0.0189074001 0.7068330000 954316331 0 1782288384 0.1082868427 -0.0122025087 0.0985322297 339 1305031113.4432659149 0.0217640568 0.0482248828 0.0857124925 0.0188903115 0.7141760000 954318117 0 1784086528 0.0930481106 -0.0146694416 0.0991561413 340 1305031113.4793109894 0.0167859234 0.0481324153 0.0857124925 0.0189163551 0.7339020000 954319935 0 1782554624 0.0758294165 -0.0113751674 0.1013765410 341 1305031113.5115230083 0.0177953709 0.0480434504 0.0857124925 0.0188962029 0.7221100000 954321753 0 1784180736 0.0602889135 -0.0129100382 0.1033998877 342 1305031113.5432419777 0.0202566683 0.0479622025 0.0857124925 0.0188892291 0.7255510000 954323539 0 1782824960 0.0433680378 -0.0162248146 0.1043290868 343 1305031113.5793011189 0.0204434916 0.0478819730 0.0857124925 0.0188644023 0.7276460000 954325357 0 1784578048 0.0257971901 -0.0181778632 0.1047506481 344 1305031113.6112680435 0.0204046350 0.0478020970 0.0857124925 0.0188398562 0.7541630000 954327175 0 1783103488 0.0112134656 -0.0161304213 0.1059845239 345 1305031113.6432220936 0.0217441786 0.0477265668 0.0857124925 0.0188172783 0.7065110000 954328961 0 1781514240 -0.0014821877 -0.0166681558 0.1066578850 346 1305031113.6792879105 0.0227409694 0.0476543541 0.0857124925 0.0187984937 0.7173950000 954330843 0 1783197696 -0.0149962530 -0.0181472320 0.1071046367 347 1305031113.7119309902 0.0240303501 0.0475862734 0.0857124925 0.0187741815 0.7253590000 954332597 0 1781702656 -0.0295939408 -0.0184759218 0.1071323007 348 1305031113.7435901165 0.0239082128 0.0475182330 0.0857124925 0.0187487267 0.7289940000 954334415 0 1783291904 -0.0433139391 -0.0185426176 0.1073496044 349 1305031113.7793200016 0.0237499680 0.0474501291 0.0857124925 0.0187377358 0.7253160000 954336233 0 1781641216 -0.0565909967 -0.0179088470 0.1077431813 350 1305031113.8112370968 0.0249568671 0.0473858626 0.0857124925 0.0187126393 0.7260060000 954337987 0 1783345152 -0.0716617927 -0.0184382815 0.1087378785 351 1305031113.8432950974 0.0241886601 0.0473197737 0.0857124925 0.0186973075 0.7569870000 954339805 0 1781792768 -0.0847534686 -0.0149700427 0.1095932201 352 1305031113.8792810440 0.0252743270 0.0472571446 0.0857124925 0.0187378628 0.7258610000 954341655 0 1783545856 -0.0983439907 -0.0160078425 0.1106463596 353 1305031113.9112899303 0.0272228587 0.0472003903 0.0857124925 0.0187115943 0.7207670000 954343441 0 1782022144 -0.1117505506 -0.0182429310 0.1116813272 354 1305031113.9432909489 0.0264895372 0.0471418850 0.0857124925 0.0186959711 0.7293420000 954345227 0 1783836672 -0.1237483025 -0.0144015588 0.1122305766 355 1305031113.9792931080 0.0270674936 0.0470853374 0.0857124925 0.0186732896 0.7488360000 954347077 0 1782034432 -0.1390402913 -0.0131221553 0.1129386500 356 1305031114.0112569332 0.0270978399 0.0470291928 0.0857124925 0.0186630142 0.7444260000 954348863 0 1783672832 -0.1552402675 -0.0113319019 0.1138567552 357 1305031114.0433011055 0.0286083389 0.0469775938 0.0857124925 0.0186678641 0.7484040000 954350649 0 1781895168 -0.1713012904 -0.0098218964 0.1155061349 358 1305031114.0792849064 0.0295120664 0.0469288074 0.0857124925 0.0186656607 0.7381100000 954352499 0 1783705600 -0.1834156066 -0.0105734710 0.1167445034 359 1305031114.1112630367 0.0308079738 0.0468839025 0.0857124925 0.0186454186 0.7612970000 954354285 0 1782304768 -0.1992050558 -0.0085984413 0.1186761558 360 1305031114.1432840824 0.0317208655 0.0468417830 0.0857124925 0.0186241159 0.7636260000 954356103 0 1783926784 -0.2101192176 -0.0062174597 0.1204199567 361 1305031114.1793370247 0.0333058499 0.0468042873 0.0857124925 0.0186350478 0.7586010000 954357953 0 1782149120 -0.2223416716 -0.0062407311 0.1222789809 362 1305031114.2113029957 0.0341102034 0.0467692208 0.0857124925 0.0186314422 0.7700790000 954359707 0 1783943168 -0.2338338345 -0.0043418440 0.1239668280 363 1305031114.2433369160 0.0362207182 0.0467401616 0.0857124925 0.0186431278 0.7756130000 954361493 0 1782304768 -0.2514702082 0.0018541629 0.1270368695 364 1305031114.2793900967 0.0369941294 0.0467133867 0.0857124925 0.0186958045 0.7657610000 954363343 0 1784086528 -0.2632330358 -0.0007175356 0.1296616048 365 1305031114.3114290237 0.0396413431 0.0466940113 0.0857124925 0.0186761713 0.8052100000 954365129 0 1782784000 -0.2735831439 0.0002973723 0.1328940839 366 1305031114.3433310986 0.0420964919 0.0466814498 0.0857124925 0.0186623864 0.7817080000 954366947 0 1784434688 -0.2809212804 0.0023218677 0.1353102177 367 1305031114.3793199062 0.0446327999 0.0466758676 0.0857124925 0.0186464586 0.7988070000 954368797 0 1782800384 -0.2890262306 0.0030025505 0.1372723728 368 1305031114.4113969803 0.0458360203 0.0466735854 0.0857124925 0.0186300247 0.7940200000 954370583 0 1784451072 -0.2990320623 0.0021140836 0.1390942782 369 1305031114.4433450699 0.0468274243 0.0466740023 0.0857124925 0.0186212593 0.8042280000 954372369 0 1782833152 -0.3109700680 0.0017455841 0.1413718760 370 1305031114.4793319702 0.0488352217 0.0466798435 0.0857124925 0.0186297690 0.8154470000 954374219 0 1781260288 -0.3200183213 0.0002861256 0.1436000019 371 1305031114.5112659931 0.0500967652 0.0466890535 0.0857124925 0.0186078678 0.8391760000 954375973 0 1783037952 -0.3288154900 -0.0007653991 0.1465473473 372 1305031114.5432360172 0.0521806329 0.0467038158 0.0857124925 0.0185938947 0.8366800000 954377791 0 1781641216 -0.3341055214 0.0002328278 0.1492621750 373 1305031114.5792369843 0.0532061830 0.0467212484 0.0857124925 0.0185749806 0.8147980000 954379641 0 1783435264 -0.3394107819 -0.0032592323 0.1511585265 374 1305031114.6113910675 0.0541252829 0.0467410453 0.0857124925 0.0185565648 0.8254670000 954381395 0 1781940224 -0.3437784016 -0.0042626113 0.1530401707 375 1305031114.6441500187 0.0553944148 0.0467641209 0.0857124925 0.0185410563 0.8248680000 954383213 0 1783799808 -0.3489086330 -0.0036638798 0.1551483423 376 1305031114.6792509556 0.0564112775 0.0467897783 0.0857124925 0.0185343102 0.8301020000 954384999 0 1782157312 -0.3555621803 -0.0070729270 0.1570034027 377 1305031114.7113060951 0.0574402399 0.0468180288 0.0857124925 0.0185307831 0.8329220000 954386753 0 1783934976 -0.3592895269 -0.0110590011 0.1579158157 378 1305031114.7432758808 0.0587707460 0.0468496498 0.0857124925 0.0185100775 0.8766560000 954388571 0 1782538240 -0.3609412611 -0.0130367307 0.1584883928 379 1305031114.7792890072 0.0593251027 0.0468825665 0.0857124925 0.0184928867 0.8296250000 954390421 0 1784221696 -0.3617946208 -0.0140229110 0.1583318263 380 1305031114.8113029003 0.0595292635 0.0469158473 0.0857124925 0.0184778268 0.8328050000 954392175 0 1782677504 -0.3608133197 -0.0128548667 0.1580413133 381 1305031114.8432080746 0.0597782955 0.0469496070 0.0857124925 0.0184545458 0.8383470000 954393993 0 1784459264 -0.3603228927 -0.0124315871 0.1579673439 382 1305031114.8792810440 0.0588120967 0.0469806607 0.0857124925 0.0184303255 0.8388110000 954395811 0 1782816768 -0.3591596782 -0.0116030565 0.1573504657 383 1305031114.9128789902 0.0588873886 0.0470117487 0.0857124925 0.0184104567 0.8365170000 954397661 0 1784434688 -0.3555612266 -0.0101886429 0.1572925150 384 1305031114.9432640076 0.0582356639 0.0470409777 0.0857124925 0.0183874697 0.8847670000 954399383 0 1782910976 -0.3518972397 -0.0072798547 0.1577175558 385 1305031114.9792799950 0.0567272566 0.0470661368 0.0857124925 0.0183684688 0.8447550000 954401233 0 1784561664 -0.3457304239 -0.0045970245 0.1575764567 386 1305031115.0113000870 0.0559091419 0.0470890462 0.0857124925 0.0183527770 0.8418320000 954403019 0 1783087104 -0.3396725655 -0.0014840737 0.1582663655 387 1305031115.0435299873 0.0550468974 0.0471096091 0.0857124925 0.0183459937 0.8437290000 954404837 0 1781571584 -0.3322243690 0.0001610145 0.1590660214 388 1305031115.0792379379 0.0540023930 0.0471273740 0.0857124925 0.0183247432 0.8624910000 954406687 0 1783308288 -0.3169671595 0.0000795741 0.1604093015 389 1305031115.1112298965 0.0527123511 0.0471417313 0.0857124925 0.0183180569 0.8370480000 954408441 0 1781960704 -0.3091087043 0.0010825471 0.1613995731 390 1305031115.1432940960 0.0510938726 0.0471518650 0.0857124925 0.0183095612 0.8861410000 954410259 0 1783418880 -0.2908857763 0.0022689067 0.1620217562 391 1305031115.1794400215 0.0489343591 0.0471564238 0.0857124925 0.0183145906 0.8179610000 954412109 0 1781768192 -0.2829436660 0.0014983320 0.1638464332 392 1305031115.2113740444 0.0486262999 0.0471601735 0.0857124925 0.0183128221 0.8085010000 954413863 0 1783545856 -0.2747535408 -0.0002579708 0.1658094972 393 1305031115.2432971001 0.0478359424 0.0471618930 0.0857124925 0.0183192100 0.8494790000 954415681 0 1782198272 -0.2526785433 -0.0035482007 0.1678649932 394 1305031115.2799661160 0.0448051319 0.0471559114 0.0857124925 0.0183412651 0.8348560000 954417499 0 1783816192 -0.2398692518 -0.0008391626 0.1702973098 395 1305031115.3117039204 0.0434077308 0.0471464223 0.0857124925 0.0183625697 0.8323710000 954419317 0 1782181888 -0.2246380150 0.0002264939 0.1725687832 396 1305031115.3434259892 0.0426456071 0.0471350566 0.0857124925 0.0183473519 0.8458720000 954421103 0 1783705600 -0.2070671916 -0.0020646248 0.1741793156 397 1305031115.3791658878 0.0393784828 0.0471155186 0.0857124925 0.0185810494 0.8063840000 954422889 0 1782022144 -0.1961274892 0.0057730624 0.1763449758 398 1305031115.4112370014 0.0446358062 0.0471092882 0.0857124925 0.0185670754 0.7607520000 954424675 0 1783799808 -0.1899612248 0.0040964074 0.1804837286 399 1305031115.4431591034 0.0437181517 0.0471007891 0.0857124925 0.0186223373 0.8132800000 954426461 0 1782288384 -0.1641422510 0.0021216255 0.1845028698 400 1305031115.4792408943 0.0456762537 0.0470972278 0.0857124925 0.0186051624 0.7895880000 954428311 0 1784086528 -0.1470435411 0.0021878127 0.1876092106 401 1305031115.5112531185 0.0474596508 0.0470981316 0.0857124925 0.0186851557 0.7749460000 954430065 0 1782562816 -0.1281496435 0.0002053864 0.1898504794 402 1305031115.5436201096 0.0476395003 0.0470994783 0.0857124925 0.0187169801 0.7597980000 954431883 0 1784180736 -0.1073363125 -0.0015159119 0.1903454512 403 1305031115.5793149471 0.0484663025 0.0471028699 0.0857124925 0.0186955244 0.7476650000 954433733 0 1782530048 -0.0916421711 -0.0016377827 0.1894838214 404 1305031115.6114239693 0.0494639426 0.0471087141 0.0857124925 0.0186755511 0.7304300000 954435487 0 1784197120 -0.0770377070 -0.0026472865 0.1886914670 405 1305031115.6432540417 0.0483435057 0.0471117630 0.0857124925 0.0186545597 0.7248510000 954437273 0 1782562816 -0.0594711117 -0.0031744915 0.1873227656 406 1305031115.6792409420 0.0511604548 0.0471217351 0.0857124925 0.0186379941 0.7145100000 954439123 0 1784180736 -0.0443258211 -0.0041894321 0.1860360503 407 1305031115.7113199234 0.0497230254 0.0471281265 0.0857124925 0.0186569897 0.7091930000 954440909 0 1782689792 -0.0266278181 -0.0037567599 0.1845251471 408 1305031115.7432498932 0.0458474010 0.0471249875 0.0857124925 0.0186968990 0.7057010000 954442727 0 1784451072 -0.0077951043 -0.0014051702 0.1826168299 409 1305031115.7794249058 0.0484312773 0.0471281813 0.0857124925 0.0186953450 0.6901690000 954444577 0 1782689792 0.0078735333 -0.0024920662 0.1806056350 410 1305031115.8112769127 0.0482025370 0.0471308017 0.0857124925 0.0186932254 0.7051450000 954446331 0 1784434688 0.0196913704 -0.0006436370 0.1788731068 411 1305031115.8432240486 0.0459121168 0.0471278366 0.0857124925 0.0186839079 0.6697890000 954448149 0 1782833152 0.0345817916 0.0025417435 0.1775891334 412 1305031115.8791980743 0.0522022285 0.0471401530 0.0857124925 0.0186756901 0.6410930000 954449935 0 1781170176 0.0463654585 -0.0001273118 0.1768296361 413 1305031115.9111180305 0.0542842671 0.0471574511 0.0857124925 0.0186651168 0.6374000000 954451721 0 1782784000 0.0568468384 0.0002389215 0.1761586517 414 1305031115.9433109760 0.0514745414 0.0471678789 0.0857124925 0.0186613392 0.6531870000 954453475 0 1781297152 0.0702051371 0.0053470354 0.1761455685 415 1305031115.9807400703 0.0564755127 0.0471903069 0.0857124925 0.0186538668 0.6271240000 954455325 0 1782943744 0.0807095021 0.0069464743 0.1770194769 416 1305031116.0113790035 0.0564266182 0.0472125096 0.0857124925 0.0186992559 0.6282840000 954457079 0 1781317632 0.0924880877 0.0097068325 0.1776471883 417 1305031116.0431640148 0.0577266514 0.0472377234 0.0857124925 0.0186813990 0.6214670000 954458897 0 1782927360 0.1020412669 0.0124678276 0.1788401902 418 1305031116.0800299644 0.0638728216 0.0472775202 0.0857124925 0.0186785736 0.6517040000 954460747 0 1781387264 0.1108295843 0.0145983612 0.1807399541 419 1305031116.1112999916 0.0649119765 0.0473196073 0.0857124925 0.0186596309 0.6047130000 954462501 0 1783181312 0.1209536195 0.0170298684 0.1829605401 420 1305031116.1434469223 0.0682049617 0.0473693343 0.0857124925 0.0186403777 0.6090470000 954464287 0 1781547008 0.1301320344 0.0165402833 0.1851596981 421 1305031116.1795721054 0.0733018070 0.0474309316 0.0857124925 0.0186224434 0.5797050000 954466137 0 1783046144 0.1397889405 0.0165596157 0.1870013475 422 1305031116.2113199234 0.0742845014 0.0474945657 0.0857124925 0.0186026413 0.5805590000 954467923 0 1781563392 0.1492103338 0.0184694380 0.1889061332 423 1305031116.2433199883 0.0753907040 0.0475605140 0.0857124925 0.0185867054 0.5638930000 954469709 0 1783300096 0.1592787951 0.0184200201 0.1899425089 424 1305031116.2793850899 0.0798330605 0.0476366285 0.0857124925 0.0186021689 0.5661810000 954471591 0 1781821440 0.1677375734 0.0185041837 0.1896461397 425 1305031116.3113360405 0.0811155736 0.0477154025 0.0857124925 0.0185983832 0.5563360000 954473345 0 1783443456 0.1750493050 0.0192753039 0.1898122281 426 1305031116.3432919979 0.0811431333 0.0477938713 0.0857124925 0.0185813173 0.5454490000 954475131 0 1781952512 0.1823603362 0.0192014519 0.1886340678 427 1305031116.3793840408 0.0831837654 0.0478767516 0.0857124925 0.0185649498 0.5647520000 954476949 0 1783713792 0.1876090467 0.0177195836 0.1860384047 428 1305031116.4113330841 0.0826829448 0.0479580745 0.0857124925 0.0185464116 0.5320750000 954478767 0 1782284288 0.1928246468 0.0169569422 0.1841147542 429 1305031116.4433689117 0.0788608715 0.0480301090 0.0857124925 0.0185336677 0.5330570000 954480585 0 1783951360 0.1979409009 0.0189496838 0.1826228499 430 1305031116.4798500538 0.0750384331 0.0480929191 0.0857124925 0.0185170699 0.5339000000 954482435 0 1782411264 0.1998019069 0.0202206932 0.1802415401 431 1305031116.5112049580 0.0738141835 0.0481525972 0.0857124925 0.0184985079 0.5357690000 954484189 0 1784094720 0.1979238540 0.0189467631 0.1778722107 432 1305031116.5432620049 0.0727672502 0.0482095755 0.0857124925 0.0184775988 0.5352960000 954485975 0 1782538240 0.1941040903 0.0170675237 0.1760884374 433 1305031116.5793130398 0.0668487251 0.0482526221 0.0857124925 0.0184835358 0.5544430000 954487825 0 1784324096 0.1886269450 0.0184693467 0.1744447052 434 1305031116.6112608910 0.0637399480 0.0482883072 0.0857124925 0.0184783946 0.5564890000 954489579 0 1782706176 0.1813863665 0.0179490075 0.1728246659 435 1305031116.6433548927 0.0612016320 0.0483179930 0.0857124925 0.0184721159 0.5846240000 954491365 0 1784307712 0.1721344292 0.0175190307 0.1713852584 436 1305031116.6792809963 0.0558529608 0.0483352750 0.0857124925 0.0184589524 0.6039940000 954493279 0 1782833152 0.1621963680 0.0162642337 0.1705681086 437 1305031116.7116339207 0.0550530478 0.0483506475 0.0857124925 0.0184395780 0.5678740000 954495033 0 1784434688 0.1497924477 0.0148057798 0.1696385294 438 1305031116.7432909012 0.0551516823 0.0483661749 0.0857124925 0.0184333985 0.5687160000 954496819 0 1782939648 0.1356495917 0.0137040829 0.1692116261 439 1305031116.7792980671 0.0527034551 0.0483760549 0.0857124925 0.0184325103 0.5714290000 954498669 0 1784578048 0.1212504208 0.0119022410 0.1687294543 440 1305031116.8113429546 0.0541297793 0.0483891315 0.0857124925 0.0184718798 0.5774920000 954500455 0 1782976512 0.1063511521 0.0091961101 0.1677159816 441 1305031116.8460888863 0.0516176336 0.0483964524 0.0857124925 0.0185672440 0.5748320000 954502273 0 1784598528 0.0918468311 0.0072130081 0.1662196517 442 1305031116.8801651001 0.0498290099 0.0483996934 0.0857124925 0.0185466237 0.5804130000 954504091 0 1783037952 0.0784358308 0.0084354328 0.1654073596 443 1305031116.9120440483 0.0506161898 0.0484046968 0.0857124925 0.0185372206 0.5843360000 954505877 0 1781698560 0.0644383505 0.0072696735 0.1650843024 444 1305031116.9432959557 0.0482111275 0.0484042609 0.0857124925 0.0185300031 0.5904940000 954507663 0 1783328768 0.0504951999 0.0091271130 0.1646507233 445 1305031116.9793510437 0.0473733731 0.0484019443 0.0857124925 0.0185295358 0.6213810000 954509481 0 1781686272 0.0347421207 0.0102178911 0.1641727388 446 1305031117.0113821030 0.0477795824 0.0484005488 0.0857124925 0.0185249167 0.5853390000 954511299 0 1783435264 0.0197227690 0.0112483408 0.1636855900 447 1305031117.0432610512 0.0466277078 0.0483965827 0.0857124925 0.0185050179 0.6057200000 954513085 0 1782022144 0.0043426198 0.0150350649 0.1635468006 448 1305031117.0795199871 0.0473313928 0.0483942051 0.0857124925 0.0185084930 0.6108390000 954514935 0 1783816192 -0.0105548706 0.0177352410 0.1641584933 449 1305031117.1112380028 0.0499429181 0.0483976543 0.0857124925 0.0185084667 0.5752550000 954516689 0 1782435840 -0.0203097202 0.0178643353 0.1653493345 450 1305031117.1432180405 0.0519474037 0.0484055427 0.0857124925 0.0184909156 0.5713790000 954518507 0 1784070144 -0.0300971549 0.0190792102 0.1667803526 451 1305031117.1792640686 0.0516363978 0.0484127064 0.0857124925 0.0184772210 0.5943900000 954520357 0 1782452224 -0.0409617238 0.0229207166 0.1678784490 452 1305031117.2113609314 0.0530451015 0.0484229551 0.0857124925 0.0184797767 0.5900790000 954522143 0 1784180736 -0.0481748506 0.0231152233 0.1695456058 453 1305031117.2432770729 0.0538771711 0.0484349953 0.0857124925 0.0184764641 0.5996890000 954523929 0 1782562816 -0.0530248992 0.0241058711 0.1715909839 454 1305031117.2792990208 0.0539520346 0.0484471474 0.0857124925 0.0184617430 0.6291920000 954525779 0 1784197120 -0.0571007207 0.0248389430 0.1733816415 455 1305031117.3111999035 0.0554428697 0.0484625226 0.0857124925 0.0184499235 0.5916460000 954527533 0 1782657024 -0.0618730001 0.0231360663 0.1747751534 456 1305031117.3432428837 0.0575779192 0.0484825125 0.0857124925 0.0184397149 0.5979380000 954529351 0 1784324096 -0.0659112260 0.0196883269 0.1754978001 457 1305031117.3794538975 0.0583337992 0.0485040689 0.0857124925 0.0184301072 0.6020500000 954531201 0 1782657024 -0.0681981891 0.0157786626 0.1755843610 458 1305031117.4112210274 0.0588852093 0.0485267352 0.0857124925 0.0184111019 0.6011650000 954532987 0 1784324096 -0.0699669123 0.0115962047 0.1751599461 459 1305031117.4432740211 0.0583991148 0.0485482436 0.0857124925 0.0183922554 0.6204030000 954534773 0 1782812672 -0.0710775331 0.0073513286 0.1744224876 460 1305031117.4794030190 0.0550544336 0.0485623875 0.0857124925 0.0183772287 0.6141210000 954536623 0 1784561664 -0.0708117858 0.0037766281 0.1735484153 461 1305031117.5113248825 0.0535167344 0.0485731345 0.0857124925 0.0183589384 0.6113980000 954538409 0 1783083008 -0.0714568943 -0.0013743305 0.1726153493 462 1305031117.5442850590 0.0512826778 0.0485789993 0.0857124925 0.0183414640 0.6099560000 954540163 0 1784688640 -0.0714233816 -0.0063446537 0.1717978120 463 1305031117.5791549683 0.0456858501 0.0485727506 0.0857124925 0.0183234185 0.6068540000 954542045 0 1783087104 -0.0720244050 -0.0100332638 0.1715909541 464 1305031117.6111590862 0.0426913798 0.0485600752 0.0857124925 0.0183048269 0.6015290000 954543799 0 1784725504 -0.0722720996 -0.0143152252 0.1727951467 465 1305031117.6432840824 0.0410755873 0.0485439795 0.0857124925 0.0182873565 0.6082870000 954545617 0 1782910976 -0.0728076696 -0.0203885268 0.1746778041 466 1305031117.6792619228 0.0365463383 0.0485182335 0.0857124925 0.0182725599 0.5978260000 954547467 0 1781551104 -0.0728661790 -0.0260554794 0.1773921698 467 1305031117.7112150192 0.0355092026 0.0484903769 0.0857124925 0.0182540292 0.6035060000 954549221 0 1783201792 -0.0726289526 -0.0327808261 0.1808502376 468 1305031117.7431840897 0.0373709835 0.0484666175 0.0857124925 0.0182412103 0.6507500000 954551007 0 1781641216 -0.0690696537 -0.0440904498 0.1856169701 469 1305031117.7794671059 0.0319187082 0.0484313341 0.0857124925 0.0182218392 0.6036150000 954552857 0 1783435264 -0.0702617615 -0.0498241708 0.1887710840 470 1305031117.8113200665 0.0297011696 0.0483914827 0.0857124925 0.0182050130 0.6145260000 954554643 0 1782022144 -0.0698509067 -0.0566576160 0.1925776303 471 1305031117.8433070183 0.0328757614 0.0483585406 0.0857124925 0.0182009946 0.6406700000 954556365 0 1783689216 -0.0666693449 -0.0695694163 0.1975087672 472 1305031117.8794670105 0.0259459279 0.0483110563 0.0857124925 0.0181842572 0.6578580000 954558215 0 1782177792 -0.0681669936 -0.0748332143 0.2005812824 473 1305031117.9114069939 0.0244055167 0.0482605160 0.0857124925 0.0181663810 0.6129410000 954559969 0 1783926784 -0.0698857084 -0.0818581879 0.2043051124 474 1305031117.9432721138 0.0266488362 0.0482149218 0.0857124925 0.0181487175 0.6593830000 954561755 0 1782448128 -0.0685388371 -0.0930805355 0.2098732144 475 1305031117.9792630672 0.0210773181 0.0481577900 0.0857124925 0.0181433109 0.6202090000 954563605 0 1784197120 -0.0710222200 -0.0980025381 0.2141235918 476 1305031118.0112280846 0.0243144091 0.0481076988 0.0857124925 0.0181312299 0.6622080000 954565359 0 1782657024 -0.0712047368 -0.1094423532 0.2202293873 477 1305031118.0435490608 0.0267035458 0.0480628264 0.0857124925 0.0181140801 0.6581260000 954567177 0 1784324096 -0.0721075386 -0.1200239137 0.2257007211 478 1305031118.0793690681 0.0230384320 0.0480104741 0.0857124925 0.0180976664 0.6389140000 954569027 0 1782910976 -0.0736846030 -0.1260092556 0.2300386876 479 1305031118.1112170219 0.0250300355 0.0479624983 0.0857124925 0.0180876115 0.6619590000 954570781 0 1781395456 -0.0720436648 -0.1365312040 0.2355464995 480 1305031118.1432559490 0.0262407996 0.0479172447 0.0857124925 0.0180708728 0.6462080000 954572599 0 1783189504 -0.0737555698 -0.1449909806 0.2399424016 481 1305031118.1793229580 0.0256701671 0.0478709930 0.0857124925 0.0180539038 0.6460190000 954574449 0 1781821440 -0.0753134266 -0.1533356309 0.2440919876 482 1305031118.2112019062 0.0298278313 0.0478335591 0.0857124925 0.0180452509 0.6556010000 954576203 0 1783427072 -0.0767410621 -0.1652754396 0.2486540377 483 1305031118.2431728840 0.0305374507 0.0477977493 0.0857124925 0.0180363963 0.6382360000 954577989 0 1781948416 -0.0788518786 -0.1722698212 0.2517250478 484 1305031118.2791941166 0.0303975344 0.0477617984 0.0857124925 0.0180418447 0.6662130000 954579839 0 1783697408 -0.0785477683 -0.1811877191 0.2553890944 485 1305031118.3112990856 0.0330306850 0.0477314250 0.0857124925 0.0180242649 0.6681660000 954581625 0 1782284288 -0.0795372874 -0.1903024316 0.2588603497 486 1305031118.3433239460 0.0323223956 0.0476997192 0.0857124925 0.0180166031 0.6618280000 954583411 0 1783971840 -0.0791538805 -0.1949267536 0.2616548240 487 1305031118.3792080879 0.0324606188 0.0476684274 0.0857124925 0.0180002380 0.6836680000 954585261 0 1782546432 -0.0815747976 -0.1988615394 0.2649490535 488 1305031118.4112958908 0.0350313820 0.0476425318 0.0857124925 0.0179970684 0.7149540000 954587047 0 1784188928 -0.0848298371 -0.2029446810 0.2686274052 489 1305031118.4457030296 0.0340213627 0.0476146767 0.0857124925 0.0179802675 0.6871450000 954588865 0 1782538240 -0.0819115639 -0.2051554024 0.2717668414 490 1305031118.4792850018 0.0342612639 0.0475874248 0.0857124925 0.0179623051 0.6860120000 954590651 0 1784217600 -0.0811288655 -0.2075579464 0.2750782669 491 1305031118.5112550259 0.0355801731 0.0475629701 0.0857124925 0.0179466493 0.7015520000 954592437 0 1782685696 -0.0806853995 -0.2094922215 0.2774148881 492 1305031118.5451989174 0.0351516716 0.0475377439 0.0857124925 0.0179405887 0.6989850000 954594255 0 1784307712 -0.0798467845 -0.2078424245 0.2794818580 493 1305031118.5792849064 0.0324835777 0.0475072081 0.0857124925 0.0179226450 0.7464110000 954596105 0 1782812672 -0.0749635845 -0.2035920620 0.2799904943 494 1305031118.6161420345 0.0356144458 0.0474831337 0.0857124925 0.0179072793 0.7010210000 954597955 0 1784578048 -0.0757345632 -0.2019479424 0.2802414000 495 1305031118.6453309059 0.0320801660 0.0474520165 0.0857124925 0.0178918317 0.7880850000 954599709 0 1783037952 -0.0725459456 -0.1958067566 0.2789939642 496 1305031118.6792950630 0.0353698879 0.0474276574 0.0857124925 0.0178788421 0.6978580000 954601559 0 1784688640 -0.0733590797 -0.1919653118 0.2783607244 497 1305031118.7114210129 0.0376998670 0.0474080844 0.0857124925 0.0178716271 0.7084320000 954603313 0 1782976512 -0.0743161887 -0.1877377629 0.2763587832 498 1305031118.7468008995 0.0434110165 0.0474000582 0.0857124925 0.0178679083 0.7176920000 954605163 0 1781571584 -0.0747804865 -0.1841077209 0.2737928331 499 1305031118.7792770863 0.0364685506 0.0473781513 0.0857124925 0.0178999342 0.7397630000 954606981 0 1783291904 -0.0731741115 -0.1687444150 0.2701551318 500 1305031118.8112208843 0.0347545147 0.0473529041 0.0857124925 0.0179077993 0.7535460000 954608735 0 1781768192 -0.0684197322 -0.1598022133 0.2665618956 501 1305031118.8467741013 0.0438026339 0.0473458177 0.0857124925 0.0179237927 0.7361760000 954610585 0 1783435264 -0.0679840595 -0.1573938727 0.2615169287 502 1305031118.8792080879 0.0379684158 0.0473271376 0.0857124925 0.0179750993 0.7823160000 954612403 0 1781833728 -0.0666777045 -0.1416512579 0.2548346519 503 1305031118.9111769199 0.0360610560 0.0473047398 0.0857124925 0.0179799938 0.7432210000 954614157 0 1783545856 -0.0656980127 -0.1301295757 0.2486090362 504 1305031118.9470090866 0.0416481942 0.0472935165 0.0857124925 0.0179643370 0.7525620000 954616007 0 1782022144 -0.0668873414 -0.1220203638 0.2418121547 505 1305031118.9793939590 0.0390654542 0.0472772233 0.0857124925 0.0179594902 0.7467460000 954617825 0 1783689216 -0.0677045286 -0.1091334671 0.2350174338 506 1305031119.0113630295 0.0384862497 0.0472598499 0.0857124925 0.0179480863 0.7339170000 954619579 0 1782034432 -0.0688180178 -0.0978350341 0.2288030684 507 1305031119.0471799374 0.0442149416 0.0472538441 0.0857124925 0.0179345616 0.7311600000 954621429 0 1783672832 -0.0709985793 -0.0896768793 0.2222653627 508 1305031119.0792229176 0.0458865054 0.0472511525 0.0857124925 0.0179220064 0.7317340000 954623183 0 1782149120 -0.0729668960 -0.0813516974 0.2156313062 509 1305031119.1113278866 0.0460493714 0.0472487915 0.0857124925 0.0179075611 0.7380900000 954625001 0 1783943168 -0.0740949586 -0.0719567686 0.2088921070 510 1305031119.1476290226 0.0487023816 0.0472516416 0.0857124925 0.0178956192 0.7419580000 954626851 0 1782431744 -0.0736738071 -0.0617518276 0.2023021430 511 1305031119.1792619228 0.0486502238 0.0472543786 0.0857124925 0.0178896387 0.7449260000 954628637 0 1784053760 -0.0742861703 -0.0524295531 0.1958982944 512 1305031119.2113640308 0.0490498245 0.0472578853 0.0857124925 0.0178775771 0.7400090000 954630423 0 1782403072 -0.0733455196 -0.0441951118 0.1896500140 513 1305031119.2476599216 0.0502067059 0.0472636335 0.0857124925 0.0178670211 0.7459780000 954632273 0 1784070144 -0.0733044073 -0.0326465033 0.1834838241 514 1305031119.2792439461 0.0498607643 0.0472686863 0.0857124925 0.0178519591 0.7500820000 954718027 0 1782562816 -0.0740130842 -0.0229415614 0.1781737357 515 1305031119.3112120628 0.0532743819 0.0472803478 0.0857124925 0.0178359141 0.7060720000 954719813 0 1784307712 -0.0738852695 -0.0176843908 0.1742225736 516 1305031119.3477499485 0.0545762777 0.0472944872 0.0857124925 0.0178212125 0.7907210000 954721663 0 1782657024 -0.0743096024 -0.0065966137 0.1690026820 517 1305031119.3792390823 0.0538355969 0.0473071393 0.0857124925 0.0178095297 0.7440320000 954723449 0 1784324096 -0.0733659267 0.0037082974 0.1646643877 518 1305031119.4114921093 0.0538539253 0.0473197779 0.0857124925 0.0177992937 0.7583050000 954725235 0 1782816768 -0.0725058243 0.0138657317 0.1607290208 519 1305031119.4477260113 0.0608715266 0.0473458891 0.0857124925 0.0177834587 0.7082070000 954727117 0 1784434688 -0.0719579533 0.0195450447 0.1577245742 520 1305031119.4792668819 0.0594149120 0.0473690988 0.0857124925 0.0177707558 0.7351280000 954728839 0 1782784000 -0.0744481981 0.0311557949 0.1525935829 521 1305031119.5112578869 0.0591808185 0.0473917700 0.0857124925 0.0177582743 0.7366600000 954730625 0 1784324096 -0.0746439248 0.0427116454 0.1488946527 522 1305031119.5474140644 0.0662329867 0.0474278643 0.0857124925 0.0177413067 0.7021260000 954732507 0 1782689792 -0.0749151409 0.0485369638 0.1462647468 523 1305031119.5795691013 0.0637031272 0.0474589834 0.0857124925 0.0177404465 0.7740400000 954734293 0 1784307712 -0.0756098703 0.0631548911 0.1423880011 524 1305031119.6150240898 0.0678379387 0.0474978745 0.0857124925 0.0177302453 0.6948550000 954736143 0 1782657024 -0.0761979967 0.0694713816 0.1406210065 525 1305031119.6488890648 0.0704580173 0.0475416081 0.0857124925 0.0177301001 0.7188460000 954737961 0 1784324096 -0.0788667351 0.0816586465 0.1375804842 526 1305031119.6792080402 0.0706159398 0.0475854757 0.0857124925 0.0177219824 0.7072640000 954739683 0 1782788096 -0.0796424523 0.0934020206 0.1355382651 527 1305031119.7152490616 0.0753078610 0.0476380798 0.0857124925 0.0177077950 0.6720550000 954741533 0 1784315904 -0.0800689533 0.0991451144 0.1350380927 528 1305031119.7471930981 0.0822063684 0.0477035501 0.0857124925 0.0177008669 0.6569870000 954743351 0 1782697984 -0.0823668391 0.1040357500 0.1340195239 529 1305031119.7791690826 0.0815019086 0.0477674411 0.0857124925 0.0176863805 0.6910330000 954745137 0 1784332288 -0.0843952298 0.1163242757 0.1319904774 530 1305031119.8145709038 0.0865610093 0.0478406365 0.0865610093 0.0176764410 0.6603450000 954746923 0 1782665216 -0.0844714865 0.1202194542 0.1315676123 531 1305031119.8474450111 0.0876272023 0.0479155641 0.0876272023 0.0176667100 0.7026740000 954748773 0 1784475648 -0.0833880082 0.1329983473 0.1296233088 532 1305031119.8792319298 0.0914725661 0.0479974382 0.0914725661 0.0176605029 0.6494330000 954750527 0 1782714368 -0.0848645195 0.1364217550 0.1280629039 533 1305031119.9114239216 0.0890222043 0.0480744077 0.0914725661 0.0176687064 0.6766940000 954752313 0 1784315904 -0.0860125124 0.1489984095 0.1251286715 534 1305031119.9474620819 0.0938895047 0.0481602038 0.0938895047 0.0176561140 0.6439510000 954754195 0 1782706176 -0.0867773592 0.1534663141 0.1239571571 535 1305031119.9795460701 0.0958803743 0.0482494004 0.0958803743 0.0176426460 0.6380510000 954755981 0 1784324096 -0.0878783986 0.1577670276 0.1224484369 536 1305031120.0152831078 0.0969611704 0.0483402805 0.0969611704 0.0176461910 0.6380650000 954757799 0 1782657024 -0.0882217959 0.1632681042 0.1214489415 537 1305031120.0473101139 0.0989246890 0.0484344787 0.0989246890 0.0176421579 0.6227760000 954759617 0 1784324096 -0.0903822929 0.1676589549 0.1204662174 538 1305031120.0794179440 0.1002000868 0.0485306973 0.1002000868 0.0176402843 0.6162470000 954761403 0 1782689792 -0.0927046463 0.1682950854 0.1195190251 539 1305031120.1152489185 0.1000790894 0.0486263344 0.1002000868 0.0176310622 0.6638040000 954763221 0 1784307712 -0.0932478607 0.1697066873 0.1190451756 540 1305031120.1481750011 0.0980761275 0.0487179081 0.1002000868 0.0176297373 0.6308630000 954765039 0 1782542336 -0.0930453464 0.1708573401 0.1187430248 541 1305031120.1792609692 0.0965766907 0.0488063716 0.1002000868 0.0176202586 0.6251810000 954766793 0 1784197120 -0.0926103592 0.1690938771 0.1182563305 542 1305031120.2152600288 0.0946398824 0.0488909353 0.1002000868 0.0176054624 0.6342120000 954768643 0 1782530048 -0.0921530500 0.1655923575 0.1176325455 543 1305031120.2480180264 0.0896785259 0.0489660506 0.1002000868 0.0175905048 0.6313770000 954770461 0 1784197120 -0.0918940455 0.1630679071 0.1172490567 544 1305031120.2794411182 0.0855070278 0.0490332215 0.1002000868 0.0175750277 0.6347160000 954772247 0 1782562816 -0.0931770205 0.1596287489 0.1170863584 545 1305031120.3152129650 0.0814080015 0.0490926247 0.1002000868 0.0175591155 0.6343470000 954774065 0 1784053760 -0.0941228941 0.1552240998 0.1175809428 546 1305031120.3477969170 0.0752352849 0.0491405051 0.1002000868 0.0175432466 0.6318220000 954775883 0 1782452224 -0.0951524898 0.1493884027 0.1188380048 547 1305031120.3794460297 0.0720971227 0.0491824733 0.1002000868 0.0175277850 0.6696040000 954777669 0 1784086528 -0.0952668935 0.1428859234 0.1213708222 548 1305031120.4154899120 0.0759400055 0.0492313009 0.1002000868 0.0175593379 0.6619780000 954779487 0 1782403072 -0.0934556350 0.1252737343 0.1262912750 549 1305031120.4474329948 0.0675930828 0.0492647468 0.1002000868 0.0175492103 0.6270060000 954781305 0 1784070144 -0.0934169441 0.1203806847 0.1288343966 550 1305031120.4794321060 0.0639994070 0.0492915371 0.1002000868 0.0175334772 0.6211320000 954783091 0 1782403072 -0.0921498537 0.1154679358 0.1326830536 551 1305031120.5148770809 0.0618703663 0.0493143662 0.1002000868 0.0175224831 0.6155920000 954784909 0 1784070144 -0.0907210857 0.1066949591 0.1365365982 552 1305031120.5478069782 0.0570294261 0.0493283427 0.1002000868 0.0175092170 0.6221780000 954786727 0 1782435840 -0.0893509611 0.0984441340 0.1407827139 553 1305031120.5795590878 0.0550543517 0.0493386972 0.1002000868 0.0174983042 0.6243130000 954788513 0 1784053760 -0.0871248171 0.0919973403 0.1456010044 554 1305031120.6152710915 0.0550938547 0.0493490855 0.1002000868 0.0174915525 0.6625550000 954790299 0 1782435840 -0.0814191103 0.0821415931 0.1510464996 555 1305031120.6473538876 0.0492785126 0.0493489584 0.1002000868 0.0174784854 0.6755840000 954792117 0 1784070144 -0.0821877271 0.0758594051 0.1546453685 556 1305031120.6793179512 0.0471172482 0.0493449445 0.1002000868 0.0174867818 0.6441070000 954793871 0 1782403072 -0.0803491846 0.0704549327 0.1591189951 557 1305031120.7145531178 0.0451608375 0.0493374327 0.1002000868 0.0174715223 0.6363990000 954795721 0 1783943168 -0.0793414786 0.0635880977 0.1635471880 558 1305031120.7473959923 0.0426075049 0.0493253719 0.1002000868 0.0174605473 0.6756930000 954797539 0 1782067200 -0.0761955529 0.0535166301 0.1686222553 559 1305031120.7799079418 0.0408784561 0.0493102611 0.1002000868 0.0174481286 0.6546210000 954799357 0 1783799808 -0.0762648359 0.0461636372 0.1722482741 560 1305031120.8149440289 0.0399139374 0.0492934819 0.1002000868 0.0174415630 0.6768400000 954801175 0 1782177792 -0.0762998685 0.0386146381 0.1760627925 561 1305031120.8479421139 0.0353448130 0.0492686180 0.1002000868 0.0174263724 0.6831830000 954802993 0 1783832576 -0.0770056322 0.0325237028 0.1796366274 562 1305031120.8834540844 0.0373278111 0.0492473710 0.1002000868 0.0174186235 0.7196330000 954804811 0 1782149120 -0.0763719231 0.0194803253 0.1834567189 563 1305031120.9154539108 0.0348401740 0.0492217810 0.1002000868 0.0174142418 0.6831080000 954806597 0 1783799808 -0.0779050142 0.0143234627 0.1862322092 564 1305031120.9475090504 0.0322901830 0.0491917604 0.1002000868 0.0173992994 0.7025510000 954808383 0 1782198272 -0.0796266347 0.0056543062 0.1893485636 565 1305031120.9833900928 0.0320884548 0.0491614891 0.1002000868 0.0173869159 0.7090380000 954810233 0 1783816192 -0.0805180296 -0.0029589459 0.1924246997 566 1305031121.0150289536 0.0329576880 0.0491328604 0.1002000868 0.0173782864 0.7139630000 954811987 0 1782149120 -0.0819084719 -0.0125432275 0.1952089518 567 1305031121.0477550030 0.0285269767 0.0490965185 0.1002000868 0.0173635734 0.7052140000 954813837 0 1783816192 -0.0828430355 -0.0180451106 0.1974150240 568 1305031121.0831170082 0.0306507405 0.0490640435 0.1002000868 0.0173532197 0.7359990000 954815655 0 1782181888 -0.0845198631 -0.0295493323 0.2002382278 569 1305031121.1148779392 0.0289209615 0.0490286427 0.1002000868 0.0173389306 0.7094430000 954817409 0 1783799808 -0.0848964602 -0.0362684727 0.2018872947 570 1305031121.1473550797 0.0253886897 0.0489871691 0.1002000868 0.0173248260 0.7446140000 954819227 0 1782403072 -0.0854888335 -0.0431604981 0.2039545625 571 1305031121.1832809448 0.0274264067 0.0489494094 0.1002000868 0.0173097602 0.7520970000 954821077 0 1784070144 -0.0875210166 -0.0539059490 0.2066369653 572 1305031121.2114310265 0.0256722420 0.0489087151 0.1002000868 0.0172968077 0.7239880000 954822767 0 1782452224 -0.0877324417 -0.0606275946 0.2086585909 573 1305031121.2472009659 0.0227490012 0.0488630611 0.1002000868 0.0172832993 0.7292600000 954824617 0 1784053760 -0.0881086886 -0.0672560558 0.2114430219 574 1305031121.2828760147 0.0251781028 0.0488217981 0.1002000868 0.0172683052 0.7561670000 954826467 0 1782403072 -0.0897984728 -0.0779066980 0.2150504142 575 1305031121.3135879040 0.0252291933 0.0487807675 0.1002000868 0.0172601616 0.7496940000 954828221 0 1784070144 -0.0890455693 -0.0879137814 0.2181755453 576 1305031121.3475399017 0.0244519878 0.0487385301 0.1002000868 0.0172494121 0.7530040000 954830039 0 1782435840 -0.0901451558 -0.0955834910 0.2216905206 577 1305031121.3832480907 0.0241060089 0.0486958394 0.1002000868 0.0172429375 0.7644920000 954831889 0 1784070144 -0.0906851813 -0.1022876129 0.2246261388 578 1305031121.4143280983 0.0242285281 0.0486535084 0.1002000868 0.0172293798 0.7560900000 954833643 0 1782411264 -0.0904273167 -0.1121942699 0.2275197357 579 1305031121.4473190308 0.0249557681 0.0486125797 0.1002000868 0.0172208191 0.7504330000 954835461 0 1784078336 -0.0922435299 -0.1183062866 0.2308614701 580 1305031121.4830150604 0.0250190366 0.0485719011 0.1002000868 0.0172202764 0.7672700000 954837279 0 1782456320 -0.0921159312 -0.1252399087 0.2332796603 581 1305031121.5141639709 0.0270601902 0.0485348758 0.1002000868 0.0172103991 0.7851590000 954839033 0 1784094720 -0.0937111750 -0.1355040073 0.2361959964 582 1305031121.5472700596 0.0285635889 0.0485005609 0.1002000868 0.0172042174 0.7826070000 954840883 0 1782665216 -0.0955945998 -0.1406758875 0.2388890982 583 1305031121.5832130909 0.0295393784 0.0484680374 0.1002000868 0.0171911733 0.7693480000 954842733 0 1784442880 -0.0967759863 -0.1470375061 0.2414727211 584 1305031121.6147189140 0.0311277136 0.0484383451 0.1002000868 0.0171777729 0.8038540000 954844487 0 1783091200 -0.0985412002 -0.1567293853 0.2440608591 585 1305031121.6471829414 0.0314508937 0.0484093067 0.1002000868 0.0171702381 0.7699300000 954846273 0 1781682176 -0.0980985165 -0.1631656885 0.2459701151 586 1305031121.6832110882 0.0336309597 0.0483840877 0.1002000868 0.0171616157 0.7639190000 954848155 0 1783324672 -0.1000268757 -0.1688664258 0.2489019483 587 1305031121.7145280838 0.0364590771 0.0483637725 0.1002000868 0.0171475860 0.8000310000 954849909 0 1781895168 -0.1026974842 -0.1784323007 0.2516159713 588 1305031121.7471449375 0.0363276750 0.0483433029 0.1002000868 0.0171348286 0.7831540000 954851695 0 1783672832 -0.1009768099 -0.1870684177 0.2553404570 589 1305031121.7828710079 0.0365950167 0.0483233568 0.1002000868 0.0171215244 0.7850010000 954853545 0 1782280192 -0.0999345332 -0.1954741776 0.2592638135 590 1305031121.8115448952 0.0370582528 0.0483042634 0.1002000868 0.0171110641 0.7823490000 954855267 0 1783943168 -0.0988405272 -0.2005035728 0.2621255517 591 1305031121.8473351002 0.0373681039 0.0482857589 0.1002000868 0.0170981845 0.8039650000 954857117 0 1782407168 -0.0968138799 -0.2046326697 0.2653499246 592 1305031121.8821229935 0.0369341113 0.0482665838 0.1002000868 0.0170837680 0.7818890000 954858935 0 1784307712 -0.0953343883 -0.2083588541 0.2679389417 593 1305031121.9149429798 0.0376251973 0.0482486388 0.1002000868 0.0170703257 0.7895240000 954860753 0 1782784000 -0.0955541581 -0.2107978165 0.2697254121 594 1305031121.9473180771 0.0391910225 0.0482333903 0.1002000868 0.0170576690 0.7834300000 954862539 0 1784582144 -0.0964217037 -0.2126076072 0.2707889080 595 1305031121.9829349518 0.0380622372 0.0482162959 0.1002000868 0.0170440483 0.7922010000 954864389 0 1782923264 -0.0949711278 -0.2116123140 0.2713259459 596 1305031122.0144240856 0.0386028215 0.0482001659 0.1002000868 0.0170306134 0.7944360000 954866175 0 1781526528 -0.0958387926 -0.2092723697 0.2709712982 597 1305031122.0473060608 0.0405717604 0.0481873880 0.1002000868 0.0170168027 0.7864320000 954867961 0 1783418880 -0.0967345610 -0.2068390250 0.2698718607 598 1305031122.0829689503 0.0414083265 0.0481760518 0.1002000868 0.0170026508 0.7907080000 954869811 0 1781673984 -0.0972055718 -0.2021251172 0.2678889334 599 1305031122.1146879196 0.0417991467 0.0481654059 0.1002000868 0.0169892395 0.7945110000 954871565 0 1783672832 -0.0975304022 -0.1958217770 0.2651236653 600 1305031122.1507480145 0.0387205705 0.0481496645 0.1002000868 0.0169843043 0.8337530000 954873415 0 1782190080 -0.0980670825 -0.1796838641 0.2611002922 601 1305031122.1830520630 0.0401563682 0.0481363645 0.1002000868 0.0169828891 0.8031740000 954875233 0 1784086528 -0.0969048962 -0.1752305627 0.2578327954 602 1305031122.2149689198 0.0372061878 0.0481182081 0.1002000868 0.0170156491 0.8386210000 954876987 0 1782403072 -0.0990854502 -0.1575571895 0.2538730204 603 1305031122.2513549328 0.0408389717 0.0481061364 0.1002000868 0.0170029121 0.8013800000 954878869 0 1784053760 -0.0983855426 -0.1511537880 0.2505611479 604 1305031122.2838659286 0.0394894220 0.0480918703 0.1002000868 0.0169948426 0.8399840000 954880687 0 1782403072 -0.0985251218 -0.1396863610 0.2453944236 605 1305031122.3143088818 0.0374752320 0.0480743221 0.1002000868 0.0170141707 0.8373890000 954882409 0 1784107008 -0.1002956629 -0.1237599403 0.2415933609 606 1305031122.3513510227 0.0425198227 0.0480651563 0.1002000868 0.0170076265 0.8018340000 954884259 0 1782427648 -0.0995099172 -0.1185605973 0.2375127077 607 1305031122.3826780319 0.0398861282 0.0480516818 0.1002000868 0.0169974467 0.8341410000 954886077 0 1784107008 -0.0962813795 -0.1081339195 0.2320271879 608 1305031122.4150080681 0.0429896303 0.0480433560 0.1002000868 0.0169959552 0.7905930000 954887799 0 1782403072 -0.0950771272 -0.1033606455 0.2269563228 609 1305031122.4512720108 0.0440697707 0.0480368313 0.1002000868 0.0169848835 0.8081530000 954889681 0 1784180736 -0.0930701196 -0.0924665406 0.2208145261 610 1305031122.4833879471 0.0425072387 0.0480277663 0.1002000868 0.0169739650 0.8061350000 954891467 0 1782276096 -0.0903050750 -0.0825600475 0.2152687013 611 1305031122.5151350498 0.0425325371 0.0480187725 0.1002000868 0.0169667742 0.7994510000 954893253 0 1784090624 -0.0878576040 -0.0740009025 0.2099680454 612 1305031122.5515100956 0.0452429913 0.0480142369 0.1002000868 0.0169592896 0.8425230000 954895103 0 1782300672 -0.0864754617 -0.0636312142 0.2044880390 613 1305031122.5832169056 0.0461544357 0.0480112030 0.1002000868 0.0169464205 0.8042150000 954896889 0 1784090624 -0.0873214528 -0.0546011403 0.1991410404 614 1305031122.6150169373 0.0505297482 0.0480153049 0.1002000868 0.0169389185 0.7658290000 954898643 0 1782149120 -0.0883862525 -0.0499890037 0.1945827156 615 1305031122.6488099098 0.0525288321 0.0480226439 0.1002000868 0.0169256661 0.7893680000 954900493 0 1783926784 -0.0887857005 -0.0387092493 0.1884576976 616 1305031122.6834199429 0.0519496836 0.0480290190 0.1002000868 0.0169121553 0.7943620000 954902311 0 1782026240 -0.0884904563 -0.0276786070 0.1833663285 617 1305031122.7152190208 0.0527972430 0.0480367471 0.1002000868 0.0169004712 0.7991990000 954904065 0 1783836672 -0.0880029574 -0.0183538608 0.1791225225 618 1305031122.7513089180 0.0555080324 0.0480488365 0.1002000868 0.0168958843 0.7987250000 954905947 0 1782046720 -0.0872575492 -0.0066809542 0.1751079559 619 1305031122.7834379673 0.0538533814 0.0480582138 0.1002000868 0.0168870298 0.8023350000 954907733 0 1783799808 -0.0861868039 0.0065390747 0.1718151420 620 1305031122.8125650883 0.0579638407 0.0480741906 0.1002000868 0.0168752110 0.7428140000 954909487 0 1782149120 -0.0873921514 0.0124609722 0.1698903441 621 1305031122.8514859676 0.0631130859 0.0480984079 0.1002000868 0.0168749766 0.7343900000 954911369 0 1783943168 -0.0873827785 0.0190954655 0.1674649268 622 1305031122.8837749958 0.0611813962 0.0481194416 0.1002000868 0.0168679814 0.7588840000 954913187 0 1781927936 -0.0889712870 0.0315300897 0.1640017778 623 1305031122.9145851135 0.0654551685 0.0481472678 0.1002000868 0.0168607654 0.7085600000 954914909 0 1783681024 -0.0909303054 0.0352451243 0.1620428711 624 1305031122.9514129162 0.0709462613 0.0481838047 0.1002000868 0.0168488574 0.6995130000 954916791 0 1782157312 -0.0923999846 0.0400456265 0.1596937031 625 1305031122.9830000401 0.0692970082 0.0482175858 0.1002000868 0.0168404803 0.7318860000 954918577 0 1783951360 -0.0935269892 0.0508521795 0.1565149724 626 1305031123.0154619217 0.0727934688 0.0482568444 0.1002000868 0.0168276909 0.7358000000 954920331 0 1782296576 -0.0933982804 0.0549007878 0.1546070576 627 1305031123.0518379211 0.0744785741 0.0482986653 0.1002000868 0.0168173721 0.7298860000 954922213 0 1783934976 -0.0925965309 0.0635953471 0.1509475559 628 1305031123.0829920769 0.0776561648 0.0483454129 0.1002000868 0.0168062034 0.7005810000 954923999 0 1782206464 -0.0922308639 0.0684660673 0.1490767300 629 1305031123.1139390469 0.0738854632 0.0483860171 0.1002000868 0.0168021179 0.7322460000 954925721 0 1783820288 -0.0924972370 0.0827071145 0.1456031203 630 1305031123.1508400440 0.0803095177 0.0484366894 0.1002000868 0.0167893123 0.6921480000 954927603 0 1782157312 -0.0930422693 0.0869205222 0.1445924342 631 1305031123.1821761131 0.0799522847 0.0484866348 0.1002000868 0.0167872526 0.7228110000 954929389 0 1783926784 -0.0933072716 0.0982785970 0.1424715519 632 1305031123.2147240639 0.0800739899 0.0485366148 0.1002000868 0.0167774680 0.7215530000 954931175 0 1782288384 -0.0924826190 0.1094952375 0.1412014216 633 1305031123.2506411076 0.0873977840 0.0485980069 0.1002000868 0.0167817549 0.7161900000 954933025 0 1783943168 -0.0933299586 0.1150427610 0.1414462477 634 1305031123.2823629379 0.0882711709 0.0486605829 0.1002000868 0.0167710548 0.6923540000 954934811 0 1782276096 -0.0946368426 0.1263210177 0.1409263462 635 1305031123.3209919930 0.0958993360 0.0487349746 0.1002000868 0.0167620227 0.6538270000 954936693 0 1783943168 -0.0957573205 0.1306164414 0.1411162764 636 1305031123.3504929543 0.0996366516 0.0488150087 0.1002000868 0.0167517461 0.6476200000 954938447 0 1782198272 -0.0955135748 0.1365788132 0.1411947459 637 1305031123.3822629452 0.0978687033 0.0488920161 0.1002000868 0.0167406345 0.6715850000 954940233 0 1783799808 -0.0945276842 0.1493569613 0.1392587423 638 1305031123.4213430882 0.1053285524 0.0489804746 0.1053285524 0.0167291043 0.6286380000 954942115 0 1782177792 -0.0953699574 0.1524339616 0.1389260143 639 1305031123.4512660503 0.1096082702 0.0490753538 0.1096082702 0.0167215782 0.6220640000 954943837 0 1783816192 -0.0955763981 0.1564582139 0.1385507137 640 1305031123.4836049080 0.1131068766 0.0491754030 0.1131068766 0.0167108936 0.6190470000 954945655 0 1782149120 -0.0958626419 0.1615948230 0.1379788220 641 1305031123.5197250843 0.1187041178 0.0492838721 0.1187041178 0.0166998091 0.6093370000 954947473 0 1783816192 -0.0961467773 0.1662885398 0.1374240071 642 1305031123.5515730381 0.1215245575 0.0493963966 0.1215245575 0.0166872038 0.6045280000 954949291 0 1782198272 -0.0959307477 0.1709911525 0.1365613341 643 1305031123.5796160698 0.1133825183 0.0494959084 0.1215245575 0.0166819094 0.6554070000 954950981 0 1783799808 -0.0916824415 0.1892238110 0.1326528639 644 1305031123.6203870773 0.1200384572 0.0496054465 0.1215245575 0.0166734709 0.6097540000 954952895 0 1782034432 -0.0926546305 0.1911926866 0.1327094436 645 1305031123.6524300575 0.1228411049 0.0497189902 0.1228411049 0.0166621460 0.6082210000 954954681 0 1783672832 -0.0920761749 0.1954586059 0.1325308979 646 1305031123.6837849617 0.1250793785 0.0498356471 0.1250793785 0.0166494076 0.6035500000 954956467 0 1782034432 -0.0908698961 0.1998880208 0.1323647648 647 1305031123.7199749947 0.1284917444 0.0499572176 0.1284917444 0.0166369202 0.5969400000 954958317 0 1783689216 -0.0902015418 0.2042598724 0.1319863796 648 1305031123.7519800663 0.1293128878 0.0500796801 0.1293128878 0.0166302447 0.5977310000 954960103 0 1782022144 -0.0896858796 0.2076043785 0.1312701404 649 1305031123.7841379642 0.1294587553 0.0502019899 0.1294587553 0.0166217991 0.5890380000 954961857 0 1783689216 -0.0890530795 0.2099514604 0.1304183155 650 1305031123.8196959496 0.1291571110 0.0503234593 0.1294587553 0.0166103152 0.6214580000 954963739 0 1781923840 -0.0876270384 0.2121795267 0.1294417828 651 1305031123.8515510559 0.1276805252 0.0504422874 0.1294587553 0.0165977938 0.5926000000 954965525 0 1783545856 -0.0864861608 0.2134887129 0.1284145564 652 1305031123.8838191032 0.1266036183 0.0505590992 0.1294587553 0.0165873567 0.5903940000 954967311 0 1781944320 -0.0861279964 0.2133213580 0.1277942955 653 1305031123.9157938957 0.1240518019 0.0506716455 0.1294587553 0.0165767563 0.5994340000 954969065 0 1783545856 -0.0852801576 0.2122159004 0.1269795150 654 1305031123.9515299797 0.1209203973 0.0507790595 0.1294587553 0.0165765800 0.6017600000 954970947 0 1781923840 -0.0856321454 0.2117785513 0.1265249103 655 1305031123.9834210873 0.1190789193 0.0508833341 0.1294587553 0.0165718449 0.5992740000 954972733 0 1783689216 -0.0872004330 0.2096806169 0.1271246076 656 1305031124.0197370052 0.1157478839 0.0509822130 0.1294587553 0.0165790226 0.6175200000 954974583 0 1782022144 -0.0886975676 0.2052933723 0.1281116158 657 1305031124.0515310764 0.1129290536 0.0510765004 0.1294587553 0.0165789182 0.6080970000 954976337 0 1783705600 -0.0884670392 0.2019050270 0.1290851533 658 1305031124.0839018822 0.1099736840 0.0511660098 0.1294587553 0.0165692274 0.6192100000 954978123 0 1782022144 -0.0890909284 0.1986368001 0.1305554658 659 1305031124.1196689606 0.1055431962 0.0512485245 0.1294587553 0.0165734036 0.6134380000 954979973 0 1783689216 -0.0896980688 0.1927937269 0.1325393617 660 1305031124.1474580765 0.1027113497 0.0513264985 0.1294587553 0.0165761721 0.6048840000 954981727 0 1782034432 -0.0878448635 0.1886280179 0.1346477568 661 1305031124.1827070713 0.0994073451 0.0513992380 0.1294587553 0.0165666760 0.6038920000 954983545 0 1783672832 -0.0875904337 0.1842078865 0.1366179883 662 1305031124.2171790600 0.0951993465 0.0514654013 0.1294587553 0.0165733925 0.5935840000 954985363 0 1782054912 -0.0876365304 0.1771587729 0.1387130320 663 1305031124.2493400574 0.0927970037 0.0515277416 0.1294587553 0.0165829370 0.5961640000 954987117 0 1783689216 -0.0863789096 0.1709406674 0.1407406926 664 1305031124.2825551033 0.0895635113 0.0515850244 0.1294587553 0.0165711053 0.6082200000 954988935 0 1782022144 -0.0866967365 0.1657438874 0.1425025612 665 1305031124.3167819977 0.0856003016 0.0516361752 0.1294587553 0.0165766220 0.5937250000 954990753 0 1783689216 -0.0873260647 0.1576947421 0.1443402767 666 1305031124.3503708839 0.0843237266 0.0516852556 0.1294587553 0.0165688406 0.6153180000 954992539 0 1781895168 -0.0863049477 0.1495177448 0.1464641392 667 1305031124.3824319839 0.0823433697 0.0517312198 0.1294587553 0.0165600612 0.6163420000 954994357 0 1783689216 -0.0843985304 0.1417021006 0.1484741569 668 1305031124.4185550213 0.0828068405 0.0517777402 0.1294587553 0.0165669725 0.6881390000 954996239 0 1782181888 -0.0785925984 0.1264644712 0.1522067338 669 1305031124.4502561092 0.0780904442 0.0518170716 0.1294587553 0.0165548427 0.6249370000 954997961 0 1783799808 -0.0801488459 0.1196615472 0.1520579457 670 1305031124.4801259041 0.0744038075 0.0518507831 0.1294587553 0.0165425605 0.6297520000 954999747 0 1782181888 -0.0808775797 0.1119181514 0.1525602043 671 1305031124.5167369843 0.0679544881 0.0518747827 0.1294587553 0.0165307387 0.6219720000 955001597 0 1783816192 -0.0813222975 0.1037707925 0.1533940285 672 1305031124.5505030155 0.0643089563 0.0518932859 0.1294587553 0.0165185221 0.6297590000 955003415 0 1782149120 -0.0810248852 0.0959550589 0.1550222337 673 1305031124.5846059322 0.0646216720 0.0519121988 0.1294587553 0.0165071323 0.6452500000 955005233 0 1783816192 -0.0787819102 0.0831298828 0.1583816260 674 1305031124.6176528931 0.0569009036 0.0519196004 0.1294587553 0.0165074752 0.6213630000 955007051 0 1782034432 -0.0801586956 0.0750193596 0.1599751711 675 1305031124.6513130665 0.0539686754 0.0519226361 0.1294587553 0.0165012610 0.6280300000 955008837 0 1783681024 -0.0802716464 0.0666340441 0.1629539132 676 1305031124.6854729652 0.0542463176 0.0519260735 0.1294587553 0.0164971067 0.6622940000 955010655 0 1782042624 -0.0769430324 0.0528003052 0.1670028269 677 1305031124.7157909870 0.0464320146 0.0519179582 0.1294587553 0.0164854790 0.6450120000 955012441 0 1783681024 -0.0778360665 0.0457599312 0.1696013957 678 1305031124.7499411106 0.0450388454 0.0519078120 0.1294587553 0.0164738397 0.6753520000 955014259 0 1781903360 -0.0767874122 0.0346840881 0.1738540828 679 1305031124.7851779461 0.0439527929 0.0518960962 0.1294587553 0.0164624166 0.6899280000 955016077 0 1783697408 -0.0767606720 0.0231123157 0.1780553609 680 1305031124.8166410923 0.0360323563 0.0518727672 0.1294587553 0.0164515367 0.6684790000 955017863 0 1781952512 -0.0778732523 0.0162043869 0.1822583526 681 1305031124.8505589962 0.0357660986 0.0518491157 0.1294587553 0.0164397484 0.7071040000 955019681 0 1783554048 -0.0777352750 0.0044015413 0.1881895214 682 1305031124.8835940361 0.0354565866 0.0518250798 0.1294587553 0.0164354928 0.7089340000 955021467 0 1781952512 -0.0772814378 -0.0073100235 0.1940896511 683 1305031124.9187700748 0.0305800922 0.0517939744 0.1294587553 0.0164370276 0.7030920000 955023317 0 1783570432 -0.0794765651 -0.0151794329 0.1999575496 684 1305031124.9507479668 0.0300343577 0.0517621620 0.1294587553 0.0164268044 0.7379320000 955025071 0 1781903360 -0.0807659775 -0.0233314764 0.2061923146 685 1305031124.9864599705 0.0312182326 0.0517321709 0.1294587553 0.0164571882 0.7155680000 955026921 0 1783554048 -0.0808458477 -0.0394692235 0.2125111520 686 1305031125.0194671154 0.0331854075 0.0517051348 0.1294587553 0.0164501344 0.7198340000 955028739 0 1781927936 -0.0836005136 -0.0498513617 0.2178532183 687 1305031125.0507979393 0.0297305528 0.0516731485 0.1294587553 0.0164489245 0.7291180000 955030493 0 1783578624 -0.0822651684 -0.0546011552 0.2230635881 688 1305031125.0834798813 0.0295331031 0.0516409682 0.1294587553 0.0164392857 0.7374690000 955032311 0 1781768192 -0.0827110633 -0.0622960031 0.2284283042 689 1305031125.1190290451 0.0291965194 0.0516083928 0.1294587553 0.0164337006 0.7631900000 955034161 0 1783291904 -0.0844709352 -0.0734487027 0.2331752777 690 1305031125.1510369778 0.0288689360 0.0515754371 0.1294587553 0.0164249427 0.7343160000 955035915 0 1781559296 -0.0852859840 -0.0818054900 0.2369693816 691 1305031125.1870639324 0.0245058499 0.0515362626 0.1294587553 0.0164247454 0.7646320000 955037797 0 1783054336 -0.0861300677 -0.0856785774 0.2410390824 692 1305031125.2190179825 0.0263381395 0.0514998491 0.1294587553 0.0164165761 0.7420080000 955039583 0 1781133312 -0.0889319405 -0.0944439992 0.2447046638 693 1305031125.2506420612 0.0301999003 0.0514691132 0.1294587553 0.0164083711 0.7665980000 955041337 0 1782784000 -0.0914182365 -0.1069975719 0.2479611039 694 1305031125.2863960266 0.0279209372 0.0514351822 0.1294587553 0.0163979598 0.7367570000 955043187 0 1784467456 -0.0929755867 -0.1124033928 0.2505940795 695 1305031125.3191399574 0.0267023463 0.0513995953 0.1294587553 0.0163892315 0.7476490000 955045005 0 1782816768 -0.0932953730 -0.1180104241 0.2534675300 696 1305031125.3488988876 0.0292197336 0.0513677277 0.1294587553 0.0163789605 0.7442240000 955046727 0 1784434688 -0.0961618051 -0.1266505718 0.2564711273 697 1305031125.3867919445 0.0280533507 0.0513342781 0.1294587553 0.0163786451 0.7391250000 955048641 0 1782657024 -0.0976748243 -0.1298636049 0.2595442832 698 1305031125.4195740223 0.0272260997 0.0512997392 0.1294587553 0.0163680260 0.7426880000 955050427 0 1784324096 -0.0969348848 -0.1347221434 0.2625564039 699 1305031125.4512319565 0.0299905632 0.0512692540 0.1294587553 0.0163634235 0.7469060000 955052213 0 1782542336 -0.0993202031 -0.1406795382 0.2660105824 700 1305031125.4869990349 0.0329571106 0.0512430937 0.1294587553 0.0163625700 0.7694340000 955054063 0 1784180736 -0.0996523201 -0.1506852210 0.2684042156 701 1305031125.5193541050 0.0331369713 0.0512172648 0.1294587553 0.0163569865 0.7437110000 955055881 0 1782403072 -0.0997644514 -0.1535556614 0.2706451714 702 1305031125.5510499477 0.0338422656 0.0511925140 0.1294587553 0.0163478229 0.7316710000 955057635 0 1784070144 -0.1001981273 -0.1560461968 0.2720101774 703 1305031125.5853030682 0.0347717106 0.0511691559 0.1294587553 0.0163362448 0.7337940000 955059453 0 1782452224 -0.1003070027 -0.1582974941 0.2729056478 704 1305031125.6178700924 0.0378253013 0.0511502015 0.1294587553 0.0163439102 0.7235850000 955061271 0 1783926784 -0.1009796336 -0.1626596153 0.2727485299 705 1305031125.6505749226 0.0424107984 0.0511378052 0.1294587553 0.0163356990 0.7582150000 955063057 0 1782276096 -0.1023562551 -0.1675189883 0.2714252472 706 1305031125.6846020222 0.0435685404 0.0511270839 0.1294587553 0.0163321171 0.7344380000 955064843 0 1783943168 -0.1027542800 -0.1670430601 0.2694110870 707 1305031125.7156689167 0.0438148454 0.0511167412 0.1294587553 0.0163495921 0.7514080000 955066629 0 1782198272 -0.1019096151 -0.1646142602 0.2669616044 708 1305031125.7512919903 0.0376492850 0.0510977194 0.1294587553 0.0163487415 0.7777090000 955068479 0 1783816192 -0.0979557112 -0.1554915607 0.2634041607 709 1305031125.7868049145 0.0399434380 0.0510819870 0.1294587553 0.0163411206 0.7524300000 955070329 0 1782022144 -0.0987968743 -0.1507922113 0.2605765164 710 1305031125.8194499016 0.0364366323 0.0510613597 0.1294587553 0.0163339366 0.7777220000 955072147 0 1783672832 -0.0976477638 -0.1398851722 0.2566196024 711 1305031125.8547739983 0.0375321656 0.0510423313 0.1294587553 0.0163240432 0.7653100000 955073933 0 1782050816 -0.0970311314 -0.1350601166 0.2535142303 712 1305031125.8866450787 0.0424076878 0.0510302040 0.1294587553 0.0163227548 0.7885790000 955075751 0 1783705600 -0.0982972533 -0.1295654774 0.2496403456 713 1305031125.9193339348 0.0396813489 0.0510142870 0.1294587553 0.0163287989 0.8065100000 955077569 0 1782022144 -0.0995016694 -0.1149587110 0.2465761304 714 1305031125.9552519321 0.0445868596 0.0510052850 0.1294587553 0.0163269091 0.7820910000 955079387 0 1783799808 -0.1000319496 -0.1122289449 0.2436099499 715 1305031125.9870939255 0.0446451567 0.0509963897 0.1294587553 0.0163210094 0.8225740000 955081173 0 1782022144 -0.0971715376 -0.1010810882 0.2402138859 716 1305031126.0195720196 0.0427360535 0.0509848529 0.1294587553 0.0163130796 0.8212760000 955082991 0 1783816192 -0.0951904655 -0.0888825431 0.2375590801 717 1305031126.0550379753 0.0411498137 0.0509711360 0.1294587553 0.0163081625 0.8234260000 955084809 0 1782050816 -0.0917315856 -0.0771454200 0.2352015078 718 1305031126.0870759487 0.0468128771 0.0509653445 0.1294587553 0.0162992454 0.7811150000 955086595 0 1783832576 -0.0884617940 -0.0699827224 0.2330080718 719 1305031126.1194519997 0.0456518047 0.0509579544 0.1294587553 0.0162901005 0.8162820000 955088413 0 1782149120 -0.0877014920 -0.0561826564 0.2302063406 720 1305031126.1549999714 0.0492225587 0.0509555441 0.1294587553 0.0162808512 0.7772310000 955090199 0 1783799808 -0.0851171091 -0.0491270721 0.2287805974 721 1305031126.1871740818 0.0502982140 0.0509546324 0.1294587553 0.0162795523 0.7997900000 955092017 0 1782304768 -0.0847293362 -0.0321730897 0.2267944813 722 1305031126.2194728851 0.0553972796 0.0509607856 0.1294587553 0.0162891213 0.7530660000 955093835 0 1783840768 -0.0813342184 -0.0263963733 0.2247693390 723 1305031126.2552359104 0.0537855476 0.0509646926 0.1294587553 0.0162879097 0.7790540000 955095685 0 1782206464 -0.0774157122 -0.0120623903 0.2218363881 724 1305031126.2871050835 0.0614492297 0.0509791740 0.1294587553 0.0162806648 0.7434390000 955097439 0 1783808000 -0.0759397373 -0.0043215565 0.2199467570 725 1305031126.3197870255 0.0598360635 0.0509913904 0.1294587553 0.0162746146 0.7745120000 955099257 0 1782157312 -0.0759673417 0.0108046476 0.2168781608 726 1305031126.3554151058 0.0645998791 0.0510101349 0.1294587553 0.0162660000 0.7119510000 955101075 0 1783824384 -0.0757343695 0.0171188060 0.2150309533 727 1305031126.3874828815 0.0673743710 0.0510326442 0.1294587553 0.0162629818 0.7210420000 955102893 0 1782034432 -0.0792576969 0.0293332729 0.2115824819 728 1305031126.4197928905 0.0715316385 0.0510608021 0.1294587553 0.0162529004 0.6729150000 955104647 0 1783562240 -0.0795878470 0.0357685722 0.2098115534 729 1305031126.4553799629 0.0754797980 0.0510942987 0.1294587553 0.0162525832 0.6574960000 955106465 0 1781321728 -0.0803021118 0.0421396606 0.2075207084 730 1305031126.4903860092 0.0821475163 0.0511368374 0.1294587553 0.0162502887 0.6498440000 955108315 0 1783070720 -0.0809160098 0.0488210171 0.2047585398 731 1305031126.5223209858 0.0786967799 0.0511745391 0.1294587553 0.0162537017 0.6750550000 955110101 0 1780658176 -0.0819391608 0.0634789616 0.2009388953 732 1305031126.5582089424 0.0851703435 0.0512209814 0.1294587553 0.0162525722 0.6428920000 955111951 0 1782435840 -0.0811348855 0.0692780092 0.1997513175 733 1305031126.5901761055 0.0872565210 0.0512701431 0.1294587553 0.0162418178 0.6480920000 955113737 0 1783959552 -0.0794644207 0.0753619373 0.1979585886 734 1305031126.6186869144 0.0892024413 0.0513218220 0.1294587553 0.0162308487 0.6671320000 955115459 0 1782308864 -0.0789763257 0.0817675143 0.1965382546 735 1305031126.6544740200 0.0911463797 0.0513760051 0.1294587553 0.0162335201 0.6396400000 955117341 0 1784086528 -0.0785769522 0.0865625590 0.1947522163 736 1305031126.6900219917 0.0954689085 0.0514359139 0.1294587553 0.0162233715 0.6331180000 955119191 0 1782452224 -0.0777740106 0.0905198306 0.1928757131 737 1305031126.7157700062 0.0960894749 0.0514965022 0.1294587553 0.0162135967 0.6308410000 955120849 0 1784053760 -0.0765965655 0.0956124589 0.1907307208 738 1305031126.7553739548 0.0971646830 0.0515583832 0.1294587553 0.0162041886 0.6224670000 955122763 0 1782558720 -0.0759045631 0.0989100561 0.1882659495 739 1305031126.7875649929 0.0988605991 0.0516223916 0.1294587553 0.0161950506 0.6195400000 955124549 0 1784307712 -0.0747975409 0.1024353355 0.1857295036 740 1305031126.8199288845 0.0985618681 0.0516858233 0.1294587553 0.0161869833 0.6331520000 955126335 0 1782784000 -0.0736804903 0.1064572409 0.1831641346 741 1305031126.8583779335 0.0986605287 0.0517492170 0.1294587553 0.0161763287 0.6244140000 955128249 0 1780785152 -0.0725505129 0.1102040261 0.1806388050 742 1305031126.8881540298 0.0980601832 0.0518116307 0.1294587553 0.0161660899 0.6377610000 955130003 0 1782435840 -0.0725513399 0.1128397360 0.1782542467 743 1305031126.9194090366 0.0971233547 0.0518726155 0.1294587553 0.0161554495 0.6104670000 955131757 0 1784066048 -0.0725306794 0.1148812547 0.1762890667 744 1305031126.9555010796 0.0964689106 0.0519325568 0.1294587553 0.0161473094 0.6076440000 955133607 0 1782448128 -0.0724254996 0.1164152473 0.1746656746 745 1305031126.9873158932 0.0962423980 0.0519920331 0.1294587553 0.0161372360 0.6137670000 955135425 0 1784197120 -0.0727303252 0.1169265360 0.1732889265 746 1305031127.0195240974 0.0957949311 0.0520507501 0.1294587553 0.0161270173 0.6235680000 955137179 0 1782050816 -0.0724321753 0.1168540567 0.1722745597 747 1305031127.0533180237 0.0947382748 0.0521078954 0.1294587553 0.0161198379 0.6110650000 955138997 0 1783705600 -0.0716791376 0.1173932180 0.1716908813 748 1305031127.0886490345 0.0926635787 0.0521621142 0.1294587553 0.0161124025 0.6276210000 955140847 0 1781530624 -0.0714179203 0.1179873273 0.1715309173 749 1305031127.1209630966 0.0920721889 0.0522153987 0.1294587553 0.0161078276 0.6179080000 955142601 0 1783214080 -0.0719783828 0.1169850379 0.1715853065 750 1305031127.1576919556 0.0908877552 0.0522669618 0.1294587553 0.0160975493 0.6661960000 955144483 0 1781276672 -0.0721807107 0.1155873612 0.1716635078 751 1305031127.1875000000 0.0897717476 0.0523169016 0.1294587553 0.0160898475 0.6217300000 955146237 0 1782960128 -0.0715871677 0.1146718413 0.1721525043 752 1305031127.2218310833 0.0883335993 0.0523647962 0.1294587553 0.0160826120 0.6338820000 955148055 0 1780916224 -0.0711842403 0.1142878681 0.1727967262 753 1305031127.2597610950 0.0862113312 0.0524097451 0.1294587553 0.0160767615 0.6256010000 955149937 0 1782784000 -0.0714610741 0.1123419255 0.1735272408 754 1305031127.2870380878 0.0851394758 0.0524531532 0.1294587553 0.0160736970 0.6318520000 955151627 0 1781170176 -0.0713651255 0.1109463796 0.1745803356 755 1305031127.3204679489 0.0839190036 0.0524948298 0.1294587553 0.0160644172 0.6341620000 955153445 0 1782800384 -0.0721971318 0.1098530740 0.1759258956 756 1305031127.3534069061 0.0839747041 0.0525364699 0.1294587553 0.0160571676 0.6419950000 955155231 0 1781133312 -0.0728837624 0.1064869240 0.1772774160 757 1305031127.3837130070 0.0834115669 0.0525772560 0.1294587553 0.0160484107 0.6333220000 955157017 0 1782927360 -0.0728070512 0.1044871360 0.1788433343 758 1305031127.4196500778 0.0818264037 0.0526158433 0.1294587553 0.0160394704 0.6672000000 955158835 0 1781444608 -0.0727629662 0.1034230739 0.1807035953 759 1305031127.4542460442 0.0816328898 0.0526540739 0.1294587553 0.0160382656 0.6256270000 955160685 0 1783164928 -0.0733873993 0.1010274813 0.1823058128 760 1305031127.4872000217 0.0808949172 0.0526912329 0.1294587553 0.0160404529 0.6326340000 955162471 0 1781702656 -0.0736712217 0.0996708348 0.1840487868 761 1305031127.5218999386 0.0806138963 0.0527279250 0.1294587553 0.0160306158 0.6297070000 955164321 0 1783435264 -0.0734318718 0.0993667990 0.1859210283 762 1305031127.5537250042 0.0813173950 0.0527654440 0.1294587553 0.0160290556 0.6323720000 955166075 0 1781895168 -0.0740803555 0.0967830122 0.1875856221 763 1305031127.5866320133 0.0813369974 0.0528028903 0.1294587553 0.0160198208 0.6334970000 955167893 0 1783689216 -0.0737871826 0.0952416062 0.1888746619 764 1305031127.6206569672 0.0811108574 0.0528399426 0.1294587553 0.0160100840 0.6376290000 955169711 0 1782034432 -0.0734306499 0.0950865299 0.1903410852 765 1305031127.6546559334 0.0817771554 0.0528777690 0.1294587553 0.0160006467 0.6322250000 955171497 0 1783672832 -0.0736336783 0.0936670825 0.1914675236 766 1305031127.6871099472 0.0820622593 0.0529158689 0.1294587553 0.0159904403 0.6362220000 955173315 0 1782034432 -0.0732650012 0.0917780623 0.1922661215 767 1305031127.7232100964 0.0815570131 0.0529532107 0.1294587553 0.0159815159 0.6308750000 955175165 0 1783672832 -0.0728241801 0.0918635726 0.1929920316 768 1305031127.7546939850 0.0813483968 0.0529901836 0.1294587553 0.0159720421 0.6357900000 955176919 0 1782050816 -0.0728283972 0.0912249982 0.1935136318 769 1305031127.7876410484 0.0816349387 0.0530274329 0.1294587553 0.0159669787 0.6359640000 955178769 0 1783689216 -0.0731560588 0.0892526880 0.1937762499 770 1305031127.8201279640 0.0810188130 0.0530637854 0.1294587553 0.0159579442 0.6308620000 955180523 0 1782022144 -0.0730023235 0.0888411924 0.1937118322 771 1305031127.8551321030 0.0806628168 0.0530995818 0.1294587553 0.0159475848 0.6264000000 955182341 0 1783689216 -0.0736705959 0.0886580348 0.1937957108 772 1305031127.8871219158 0.0806130841 0.0531352210 0.1294587553 0.0159384821 0.6387140000 955184159 0 1782030336 -0.0745776147 0.0876402110 0.1938953400 773 1305031127.9225599766 0.0808005780 0.0531710106 0.1294587553 0.0159294283 0.6338530000 955186009 0 1783799808 -0.0751661807 0.0871771425 0.1944520473 774 1305031127.9550879002 0.0802888125 0.0532060466 0.1294587553 0.0159209168 0.6646120000 955187795 0 1782161408 -0.0752476826 0.0875013024 0.1953619123 775 1305031127.9870929718 0.0793322921 0.0532397578 0.1294587553 0.0159107715 0.6313630000 955189581 0 1783820288 -0.0754635185 0.0874434188 0.1966496706 776 1305031128.0217759609 0.0789852813 0.0532729351 0.1294587553 0.0159033129 0.6403010000 955191431 0 1782030336 -0.0752931088 0.0873165429 0.1983717382 777 1305031128.0557179451 0.0787885338 0.0533057737 0.1294587553 0.0158964184 0.6299300000 955193217 0 1783693312 -0.0751251876 0.0864401460 0.2005925924 778 1305031128.0872058868 0.0799049437 0.0533399628 0.1294587553 0.0158876519 0.6351560000 955195003 0 1782038528 -0.0754652992 0.0841115639 0.2023205161 779 1305031128.1247460842 0.0804790109 0.0533748011 0.1294587553 0.0158783953 0.6375600000 955196885 0 1783808000 -0.0747680143 0.0826098248 0.2040022761 780 1305031128.1577820778 0.0805192143 0.0534096017 0.1294587553 0.0158696522 0.6350520000 955198703 0 1782206464 -0.0736205131 0.0815805346 0.2056721747 781 1305031128.1872210503 0.0813204646 0.0534453390 0.1294587553 0.0158618641 0.6374240000 955200425 0 1783824384 -0.0734302998 0.0795717016 0.2066560686 782 1305031128.2254419327 0.0814822018 0.0534811918 0.1294587553 0.0158547290 0.6611690000 955202307 0 1782157312 -0.0721103698 0.0786277056 0.2074460089 783 1305031128.2560069561 0.0808785558 0.0535161820 0.1294587553 0.0158452049 0.6280730000 955204061 0 1783832576 -0.0713477954 0.0786607563 0.2080719024 784 1305031128.2912750244 0.0813941285 0.0535517406 0.1294587553 0.0158379482 0.6330190000 955205911 0 1782149120 -0.0715559274 0.0775613636 0.2085022479 785 1305031128.3241701126 0.0812623426 0.0535870408 0.1294587553 0.0158290169 0.6300400000 955207697 0 1783705600 -0.0714811459 0.0772088841 0.2085655779 786 1305031128.3552060127 0.0807994381 0.0536216621 0.1294587553 0.0158193952 0.6252400000 955209483 0 1782034432 -0.0716069788 0.0772796869 0.2085400373 787 1305031128.3913969994 0.0807439387 0.0536561250 0.1294587553 0.0158094608 0.6257050000 955211333 0 1783672832 -0.0728683546 0.0765802786 0.2084661424 788 1305031128.4236090183 0.0808097646 0.0536905839 0.1294587553 0.0157995097 0.6348690000 955213119 0 1781944320 -0.0733606741 0.0757311508 0.2083187997 789 1305031128.4554989338 0.0804840997 0.0537245428 0.1294587553 0.0157911835 0.6228400000 955214905 0 1783562240 -0.0739257783 0.0754243731 0.2081787139 790 1305031128.4895229340 0.0803629756 0.0537582623 0.1294587553 0.0157816779 0.6559670000 955216755 0 1781895168 -0.0742819309 0.0748059154 0.2081549168 791 1305031128.5236039162 0.0802350193 0.0537917348 0.1294587553 0.0157718773 0.6261580000 955218541 0 1783562240 -0.0747149214 0.0739453435 0.2081363201 792 1305031128.5556390285 0.0799810141 0.0538248021 0.1294587553 0.0157625747 0.6181280000 955220327 0 1781833728 -0.0750287175 0.0734058842 0.2079972774 793 1305031128.5914599895 0.0803338140 0.0538582308 0.1294587553 0.0157538232 0.6282280000 955222177 0 1783418880 -0.0754735991 0.0720030814 0.2077857703 794 1305031128.6233680248 0.0804019347 0.0538916612 0.1294587553 0.0157447830 0.6206080000 955223963 0 1781817344 -0.0755857378 0.0708846748 0.2074860483 795 1305031128.6555540562 0.0801137313 0.0539246449 0.1294587553 0.0157367825 0.6277940000 955225749 0 1783304192 -0.0753148198 0.0706193149 0.2073167264 796 1305031128.6904489994 0.0799735188 0.0539573697 0.1294587553 0.0157282999 0.6163860000 955227599 0 1781895168 -0.0752035156 0.0701485276 0.2069534212 797 1305031128.7229759693 0.0796856657 0.0539896511 0.1294587553 0.0157195745 0.6181830000 955229385 0 1783578624 -0.0747811869 0.0697230995 0.2065797001 798 1305031128.7546460629 0.0791393742 0.0540211670 0.1294587553 0.0157109307 0.6484800000 955231171 0 1781641216 -0.0747849941 0.0697520450 0.2060418725 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 02:48:22 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 nan 0.4323020000 958693034 0 1770409984 -0.0000000000 0.0000000000 -0.0000000000 2 1311867718.6768438816 0.0027222037 0.0023124279 0.0027222037 0.0021564551 0.5627880000 968632743 0 1765244928 0.0005164510 -0.0010936994 0.0001798777 3 1311867718.7114279270 0.0031998577 0.0026082378 0.0031998577 0.0034740969 0.5063090000 968321829 0 1766739968 0.0005414290 -0.0010923829 0.0002229991 4 1311867718.7410299778 0.0041535799 0.0029945733 0.0041535799 0.0042840818 0.5170930000 968323879 0 1768407040 0.0010235405 -0.0015497371 0.0003004720 5 1311867718.7767970562 0.0055215186 0.0034999624 0.0055215186 0.0043328137 0.5144030000 968325729 0 1770057728 0.0021279443 -0.0026175210 0.0001474886 6 1311867718.8094089031 0.0056038373 0.0038506082 0.0056038373 0.0041691247 0.5261170000 968328171 0 1771835392 0.0020348993 -0.0026791331 0.0002581733 7 1311867718.8408079147 0.0062560188 0.0041942383 0.0062560188 0.0038580576 0.5203800000 968329925 0 1773486080 0.0026844614 -0.0024253663 0.0003454532 8 1311867718.8767778873 0.0070276498 0.0045484147 0.0070276498 0.0036762000 0.5322640000 968331775 0 1775247360 0.0029800036 -0.0028167740 0.0004529347 9 1311867718.9088680744 0.0079749720 0.0049291433 0.0079749720 0.0035488510 0.5425510000 968333529 0 1776914432 0.0036907864 -0.0027795082 0.0006452871 10 1311867718.9438331127 0.0086715957 0.0053033886 0.0086715957 0.0033970858 0.5395870000 968336691 0 1778565120 0.0044372287 -0.0028011375 0.0010422878 11 1311867718.9784109592 0.0095486473 0.0056893212 0.0095486473 0.0033672821 0.5491370000 968338541 0 1780342784 0.0048542167 -0.0037217583 0.0012516964 12 1311867719.0091300011 0.0099188192 0.0060417793 0.0099188192 0.0032145368 0.5559290000 968340263 0 1781993472 0.0048059565 -0.0041586147 0.0013767426 13 1311867719.0441620350 0.0108008822 0.0064078642 0.0108008822 0.0031134331 0.5618590000 968342113 0 1783754752 0.0055802651 -0.0042275270 0.0016255215 14 1311867719.0776190758 0.0118897557 0.0067994279 0.0118897557 0.0031009619 0.5607070000 968343931 0 1781911552 0.0065739057 -0.0046500736 0.0017758372 15 1311867719.1086950302 0.0124932183 0.0071790139 0.0124932183 0.0029912324 0.5636040000 968345717 0 1783382016 0.0069134827 -0.0050463038 0.0020168941 16 1311867719.1437010765 0.0134275518 0.0075695475 0.0134275518 0.0029022557 0.6149340000 968347535 0 1781506048 0.0076452424 -0.0050778883 0.0022302240 17 1311867719.1810290813 0.0144314533 0.0079731890 0.0144314533 0.0028862151 0.5631670000 968349385 0 1783238656 0.0082772011 -0.0055704145 0.0025775169 18 1311867719.2127099037 0.0148636140 0.0083559904 0.0148636140 0.0028202809 0.5696130000 968353795 0 1781506048 0.0084169051 -0.0058969860 0.0028509451 19 1311867719.2412090302 0.0157005247 0.0087425448 0.0157005247 0.0027981034 0.5712860000 968355517 0 1783001088 0.0087130973 -0.0063769422 0.0030896224 20 1311867719.2779469490 0.0170060880 0.0091557220 0.0170060880 0.0031184502 0.5838560000 968357335 0 1781125120 0.0094178505 -0.0066734664 0.0032724121 21 1311867719.3104898930 0.0180170480 0.0095776899 0.0180170480 0.0030977194 0.5771240000 968359153 0 1782730752 0.0101720300 -0.0067485818 0.0034030336 22 1311867719.3413150311 0.0193813536 0.0100233110 0.0193813536 0.0032175325 0.5806360000 968360939 0 1784373248 0.0111272270 -0.0071389289 0.0034835998 23 1311867719.3772718906 0.0210286118 0.0105018023 0.0210286118 0.0032547602 0.5837140000 968362757 0 1782521856 0.0121979713 -0.0079122754 0.0034724493 24 1311867719.4105761051 0.0215905532 0.0109638336 0.0215905532 0.0032100197 0.5812590000 968364575 0 1784000512 0.0124833751 -0.0081555303 0.0034877476 25 1311867719.4427709579 0.0226408858 0.0114309157 0.0226408858 0.0032949385 0.6198060000 968366393 0 1782140928 0.0133451736 -0.0086114462 0.0035924183 26 1311867719.4787840843 0.0232483596 0.0118854328 0.0232483596 0.0033750144 0.5868060000 968368211 0 1783619584 0.0132260676 -0.0100192204 0.0035402346 27 1311867719.5104370117 0.0230147243 0.0122976288 0.0232483596 0.0035821381 0.5859280000 968369997 0 1781760000 0.0125882337 -0.0103840549 0.0036512141 28 1311867719.5449650288 0.0236965120 0.0127047317 0.0236965120 0.0036169007 0.5962100000 968371815 0 1783255040 0.0126733799 -0.0101461150 0.0039970982 29 1311867719.5771939754 0.0249575973 0.0131272443 0.0249575973 0.0036255614 0.5932710000 968373633 0 1781379072 0.0133445160 -0.0108856326 0.0040449784 30 1311867719.6112511158 0.0255328193 0.0135407635 0.0255328193 0.0035846514 0.5930650000 968375451 0 1783005184 0.0132251410 -0.0112168388 0.0043068542 31 1311867719.6421909332 0.0261436515 0.0139473083 0.0261436515 0.0035408247 0.5999430000 968377205 0 1780998144 0.0135880997 -0.0106634386 0.0046803202 32 1311867719.6770479679 0.0270632897 0.0143571827 0.0270632897 0.0034894405 0.5921170000 968379055 0 1782603776 0.0138398530 -0.0110422168 0.0051461454 33 1311867719.7107939720 0.0278834458 0.0147670695 0.0278834458 0.0034401260 0.6129250000 968380841 0 1784254464 0.0142674390 -0.0107113784 0.0056474078 34 1311867719.7442650795 0.0289801992 0.0151851027 0.0289801992 0.0033952144 0.6122310000 968387875 0 1782394880 0.0150840711 -0.0100112893 0.0061871912 35 1311867719.7861878872 0.0304474961 0.0156211711 0.0304474961 0.0033713313 0.6129450000 968389853 0 1783865344 0.0157365706 -0.0103753619 0.0066375094 36 1311867719.8099169731 0.0313496962 0.0160580745 0.0313496962 0.0033377787 0.6164530000 968391479 0 1782005760 0.0160532426 -0.0108214961 0.0070252866 37 1311867719.8454990387 0.0328119658 0.0165108824 0.0328119658 0.0034010209 0.6084750000 968393329 0 1783631872 0.0168597847 -0.0118108233 0.0070664724 38 1311867719.8771090508 0.0328123085 0.0169398673 0.0328123085 0.0033579676 0.6149620000 968395115 0 1781624832 0.0166821573 -0.0120170135 0.0073734131 39 1311867719.9114089012 0.0345024839 0.0173901908 0.0345024839 0.0033497942 0.6288130000 968396965 0 1783230464 0.0177300330 -0.0124560045 0.0076781665 40 1311867719.9461970329 0.0354770385 0.0178423620 0.0354770385 0.0033129188 0.6229640000 968398783 0 1781370880 0.0183896851 -0.0133048892 0.0080092177 41 1311867719.9807810783 0.0374687910 0.0183210554 0.0374687910 0.0032934292 0.6193540000 968400601 0 1782976512 0.0196960475 -0.0139862001 0.0080925813 42 1311867720.0117020607 0.0390283391 0.0188140860 0.0390283391 0.0032626868 0.6631110000 968402387 0 1781260288 0.0209043827 -0.0141489087 0.0083339354 43 1311867720.0452380180 0.0417646952 0.0193478211 0.0417646952 0.0032388922 0.6363770000 968404173 0 1782849536 0.0233671758 -0.0141236968 0.0086758286 44 1311867720.0772819519 0.0448217355 0.0199267737 0.0448217355 0.0032669754 0.6479990000 968405991 0 1781116928 0.0262091588 -0.0145149874 0.0091045909 45 1311867720.1172130108 0.0467269123 0.0205223323 0.0467269123 0.0032558789 0.6332670000 968407905 0 1782595584 0.0279839449 -0.0147238625 0.0095852558 46 1311867720.1451559067 0.0470525585 0.0210990763 0.0470525585 0.0032210834 0.6241850000 968409595 0 1784373248 0.0281355232 -0.0150319152 0.0100246780 47 1311867720.1781630516 0.0480803996 0.0216731471 0.0480803996 0.0031926413 0.6342230000 968411381 0 1782513664 0.0292455796 -0.0148247257 0.0103708766 48 1311867720.2094950676 0.0490147583 0.0222427640 0.0490147583 0.0031648372 0.6302040000 968413167 0 1784246272 0.0301371906 -0.0146506652 0.0108571090 49 1311867720.2421469688 0.0500514619 0.0228102884 0.0500514619 0.0031344345 0.6425040000 968414985 0 1782640640 0.0311343651 -0.0142723750 0.0113337347 50 1311867720.2770779133 0.0517418124 0.0233889189 0.0517418124 0.0031732759 0.6850870000 968416803 0 1784246272 0.0324827172 -0.0142896213 0.0120433699 51 1311867720.3094570637 0.0526057258 0.0239617974 0.0526057258 0.0031493426 0.6527960000 968418589 0 1782530048 0.0334237926 -0.0135851074 0.0129396133 52 1311867720.3430728912 0.0541700348 0.0245427251 0.0541700348 0.0031576676 0.6540790000 968420407 0 1784119296 0.0348048992 -0.0134350844 0.0138160503 53 1311867720.3779859543 0.0560598224 0.0251373873 0.0560598224 0.0032240026 0.6558010000 968422193 0 1782386688 0.0360160358 -0.0146876955 0.0142032299 54 1311867720.4096798897 0.0581909455 0.0257494902 0.0581909455 0.0034531685 0.6576640000 968423979 0 1783865344 0.0371581614 -0.0155865829 0.0146272397 55 1311867720.4461109638 0.0593197867 0.0263598593 0.0593197867 0.0034459616 0.6603790000 968425861 0 1782013952 0.0382126607 -0.0155595299 0.0152003244 56 1311867720.4799289703 0.0609358773 0.0269772882 0.0609358773 0.0035090689 0.6575970000 968427679 0 1783619584 0.0394976065 -0.0158386473 0.0152589725 57 1311867720.5104389191 0.0614541471 0.0275821453 0.0614541471 0.0035418709 0.6632960000 968429433 0 1781760000 0.0399839804 -0.0161759052 0.0151854903 58 1311867720.5467319489 0.0631131008 0.0281947480 0.0631131008 0.0036263146 0.6862010000 968431315 0 1783492608 0.0407272913 -0.0163183436 0.0155861927 59 1311867720.5793280602 0.0634645149 0.0287925407 0.0634645149 0.0036690018 0.6685840000 968433101 0 1781755904 0.0410324112 -0.0168032292 0.0158057772 60 1311867720.6121249199 0.0653288215 0.0294014787 0.0653288215 0.0036556465 0.6566730000 968434887 0 1783492608 0.0422002152 -0.0172633491 0.0158894192 61 1311867720.6463210583 0.0660445839 0.0300021853 0.0660445839 0.0036477136 0.6851130000 968436737 0 1781878784 0.0422330089 -0.0175841171 0.0162818935 62 1311867720.6798269749 0.0669471920 0.0305980725 0.0669471920 0.0036314386 0.6607170000 968438491 0 1783656448 0.0424763635 -0.0180453863 0.0162905622 63 1311867720.7102439404 0.0682390630 0.0311955486 0.0682390630 0.0036238739 0.6623270000 968440277 0 1782005760 0.0430201069 -0.0190101843 0.0162183177 64 1311867720.7451629639 0.0691557229 0.0317886763 0.0691557229 0.0036188294 0.6667500000 968442095 0 1783635968 0.0430572666 -0.0192454495 0.0163051691 65 1311867720.7790179253 0.1112890318 0.0330117587 0.1112890318 0.0049849408 0.7076720000 968443945 0 1782140928 0.0858090669 -0.0169442128 0.0258403197 66 1311867720.8115909100 0.1122932583 0.0342129935 0.1122932583 0.0049595591 0.6640820000 968456227 0 1783754752 0.0859970823 -0.0182950683 0.0259775855 67 1311867720.8467299938 0.1132659987 0.0353928891 0.1132659987 0.0049515695 0.6636720000 968458077 0 1782394880 0.0864317790 -0.0188154522 0.0265642032 68 1311867720.8813319206 0.1134043261 0.0365401161 0.1134043261 0.0049404931 0.6565450000 968459895 0 1784025088 0.0862195343 -0.0191105939 0.0269471537 69 1311867720.9149661064 0.1145056635 0.0376700516 0.1145056635 0.0049159550 0.6579760000 968461681 0 1782648832 0.0867543668 -0.0199182015 0.0272817742 70 1311867720.9500010014 0.1150836572 0.0387759603 0.1150836572 0.0048828246 0.6670300000 968463499 0 1784389632 0.0869918689 -0.0204014201 0.0275887959 71 1311867720.9797990322 0.1155364588 0.0398570940 0.1155364588 0.0048552610 0.6737750000 968465221 0 1783013376 0.0871988833 -0.0206156839 0.0277729928 72 1311867721.0093889236 0.1155943871 0.0409090009 0.1155943871 0.0048215510 0.6618190000 968466975 0 1781616640 0.0870424211 -0.0210745912 0.0277788416 73 1311867721.0478379726 0.1162131280 0.0419405643 0.1162131280 0.0047903253 0.6645640000 968468889 0 1783246848 0.0872777626 -0.0214146189 0.0278040823 74 1311867721.0794439316 0.1170981154 0.0429562069 0.1170981154 0.0047639658 0.7153140000 968470643 0 1781870592 0.0878638998 -0.0218984466 0.0279857405 75 1311867721.1103579998 0.1176450700 0.0439520584 0.1176450700 0.0047424699 0.6766450000 968472429 0 1783648256 0.0880393609 -0.0221785922 0.0281600319 76 1311867721.1467890739 0.1189697981 0.0449391339 0.1189697981 0.0047318802 0.6654910000 968474279 0 1782013952 0.0885612518 -0.0227220785 0.0280914828 77 1311867721.1774179935 0.1197786555 0.0459110757 0.1197786555 0.0047669337 0.6700010000 968476065 0 1783627776 0.0894679278 -0.0231008437 0.0282042548 78 1311867721.2112360001 0.1199615672 0.0468604410 0.1199615672 0.0047380819 0.6714620000 968477851 0 1782267904 0.0892119929 -0.0236661099 0.0283494610 79 1311867721.2469010353 0.1209370270 0.0477981193 0.1209370270 0.0047276176 0.6756250000 968479701 0 1784008704 0.0899060369 -0.0242700931 0.0284018610 80 1311867721.2800450325 0.1217170507 0.0487221060 0.1217170507 0.0047133545 0.6671190000 968481487 0 1782632448 0.0900781676 -0.0249035228 0.0284766369 81 1311867721.3099579811 0.1227784827 0.0496363822 0.1227784827 0.0047002651 0.6734460000 968483241 0 1784283136 0.0907731354 -0.0255494490 0.0286507756 82 1311867721.3483059406 0.1241525039 0.0505451154 0.1241525039 0.0046784825 0.6738630000 968485123 0 1782779904 0.0917313918 -0.0258326884 0.0287377127 83 1311867721.3790040016 0.1249221712 0.0514412245 0.1249221712 0.0046524716 0.6735390000 968486845 0 1784410112 0.0920503139 -0.0257972442 0.0288444031 84 1311867721.4092550278 0.1252330989 0.0523196992 0.1252330989 0.0046268540 0.6818540000 968488599 0 1782779904 0.0917763188 -0.0262422077 0.0291128419 85 1311867721.4478130341 0.1258739084 0.0531850428 0.1258739084 0.0046000001 0.6763300000 968490545 0 1784410112 0.0918184444 -0.0265669283 0.0294794980 86 1311867721.4768960476 0.1262684166 0.0540348495 0.1262684166 0.0045773476 0.6806920000 968492267 0 1782759424 0.0917426944 -0.0268824715 0.0296663176 87 1311867721.5093359947 0.1269229203 0.0548726434 0.1269229203 0.0045701554 0.6831030000 968494021 0 1784537088 0.0919150934 -0.0273746010 0.0299401097 88 1311867721.5451331139 0.1286669821 0.0557112155 0.1286669821 0.0045487582 0.6869670000 968495839 0 1782886400 0.0931138620 -0.0282134991 0.0300794747 89 1311867721.5769670010 0.1295164227 0.0565404874 0.1295164227 0.0045268805 0.6782470000 968497561 0 1781346304 0.0936903730 -0.0282427110 0.0304121748 90 1311867721.6129651070 0.1305833310 0.0573631857 0.1305833310 0.0045475358 0.6750720000 968499379 0 1782882304 0.0941878930 -0.0288094301 0.0303651094 91 1311867721.6496050358 0.1311130077 0.0581736233 0.1311130077 0.0045708554 0.6814750000 968501261 0 1781362688 0.0943512097 -0.0292281955 0.0301027019 92 1311867721.6800351143 0.1315615028 0.0589713177 0.1315615028 0.0045696033 0.6809760000 968503015 0 1783140352 0.0944875851 -0.0288787428 0.0302896034 93 1311867721.7162289619 0.1316179484 0.0597524642 0.1316179484 0.0045614228 0.6839370000 968504897 0 1781489664 0.0944845527 -0.0289901253 0.0305068120 94 1311867721.7467949390 0.1326336116 0.0605277956 0.1326336116 0.0045979808 0.6842920000 968506651 0 1783267328 0.0945903957 -0.0299757682 0.0304868855 95 1311867721.7787001133 0.1328321397 0.0612888939 0.1328321397 0.0045745067 0.6920220000 968508437 0 1781616640 0.0944953933 -0.0300050415 0.0306397770 96 1311867721.8154830933 0.1335879117 0.0620420087 0.1335879117 0.0045539425 0.6908500000 968510287 0 1783267328 0.0947577655 -0.0303748231 0.0306907240 97 1311867721.8485159874 0.1341292858 0.0627851765 0.1341292858 0.0045333982 0.6880570000 968512105 0 1781616640 0.0947201550 -0.0311706923 0.0305065475 98 1311867721.8778810501 0.1339831352 0.0635116863 0.1341292858 0.0045131214 0.7365840000 968513859 0 1783394304 0.0942909047 -0.0311197676 0.0303716473 99 1311867721.9146931171 0.1341236532 0.0642249385 0.1341292858 0.0044910600 0.6896130000 968515581 0 1781743616 0.0941514298 -0.0311745033 0.0302191451 100 1311867721.9467151165 0.1345186681 0.0649278758 0.1345186681 0.0044694655 0.6944900000 968517367 0 1783394304 0.0941567197 -0.0316166170 0.0300926827 101 1311867721.9773728848 0.1349219084 0.0656208860 0.1349219084 0.0044719354 0.6961570000 968519153 0 1781891072 0.0945182368 -0.0316441655 0.0299133211 102 1311867722.0166850090 0.1355451345 0.0663064179 0.1355451345 0.0045024655 0.6963580000 968520971 0 1783521280 0.0945179984 -0.0321988091 0.0298294798 103 1311867722.0475180149 0.1359875947 0.0669829341 0.1359875947 0.0045094198 0.6982670000 968522661 0 1781870592 0.0949974954 -0.0325961560 0.0295316726 104 1311867722.0800709724 0.1365925670 0.0676522575 0.1365925670 0.0044987575 0.6869150000 968524479 0 1783517184 0.0951626077 -0.0329803824 0.0295324270 105 1311867722.1161251068 0.1372561306 0.0683151516 0.1372561306 0.0044838617 0.7329700000 968526329 0 1782026240 0.0951995626 -0.0338951387 0.0295275319 106 1311867722.1479530334 0.1374590546 0.0689674525 0.1374590546 0.0044805093 0.6929030000 968528083 0 1783656448 0.0948990732 -0.0343758091 0.0293367915 107 1311867722.1798410416 0.1383277476 0.0696156796 0.1383277476 0.0044614090 0.6998160000 968529869 0 1782005760 0.0954760388 -0.0342540033 0.0298121851 108 1311867722.2146399021 0.1387964934 0.0702562427 0.1387964934 0.0044628664 0.6908050000 968531719 0 1783656448 0.0956922993 -0.0349090658 0.0297366232 109 1311867722.2469589710 0.1397388875 0.0708936981 0.1397388875 0.0044452716 0.7020920000 968533505 0 1782026240 0.0963026360 -0.0354609415 0.0297875106 110 1311867722.2780389786 0.1405603737 0.0715270315 0.1405603737 0.0044270851 0.7019970000 968535291 0 1783767040 0.0969729871 -0.0352971144 0.0302240867 111 1311867722.3154170513 0.1405433565 0.0721488002 0.1405603737 0.0044075180 0.7102640000 968537141 0 1782005760 0.0967969671 -0.0356412753 0.0302410144 112 1311867722.3488469124 0.1413122267 0.0727663308 0.1413122267 0.0043981126 0.7314430000 968538927 0 1783783424 0.0971794352 -0.0363973416 0.0302071851 113 1311867722.3777940273 0.1410310119 0.0733704431 0.1413122267 0.0043822720 0.7023410000 968540681 0 1782136832 0.0968071893 -0.0362816676 0.0303826537 114 1311867722.4150679111 0.1416312456 0.0739692220 0.1416312456 0.0043651585 0.7050980000 968542435 0 1783894016 0.0969827250 -0.0368554294 0.0305495057 115 1311867722.4467909336 0.1417530626 0.0745586467 0.1417530626 0.0043934954 0.7087650000 968544221 0 1781899264 0.0967671201 -0.0376841612 0.0308891777 116 1311867722.4777851105 0.1429831833 0.0751485134 0.1429831833 0.0044263541 0.7063550000 968545975 0 1783660544 0.0974770188 -0.0376081243 0.0312971510 117 1311867722.5147399902 0.1436205208 0.0757337443 0.1436205208 0.0044105531 0.6993150000 968547793 0 1781518336 0.0977548286 -0.0380104296 0.0319105238 118 1311867722.5469911098 0.1434940100 0.0763079838 0.1436205208 0.0043963572 0.7054620000 968549579 0 1783386112 0.0974092558 -0.0382191204 0.0320958458 119 1311867722.5802359581 0.1441236734 0.0768778635 0.1441236734 0.0043854099 0.7275410000 968551365 0 1781768192 0.0978218839 -0.0387770794 0.0326429494 120 1311867722.6146309376 0.1453208178 0.0774482215 0.1453208178 0.0043691817 0.7002130000 968553183 0 1783267328 0.0988320261 -0.0395366736 0.0328069814 121 1311867722.6560258865 0.1459261626 0.0780141549 0.1459261626 0.0043549532 0.7074780000 968555129 0 1781256192 0.0991952494 -0.0402022079 0.0327663086 122 1311867722.6778230667 0.1469575167 0.0785792644 0.1469575167 0.0043457139 0.7094850000 968556787 0 1783123968 0.1000323221 -0.0406641066 0.0329723731 123 1311867722.7252709866 0.1475107819 0.0791396833 0.1475107819 0.0044096763 0.7154580000 968558797 0 1781383168 0.1001682878 -0.0409680791 0.0331067927 124 1311867722.7449109554 0.1477058530 0.0796926362 0.1477058530 0.0044251378 0.7085710000 968560359 0 1783013376 0.1003483012 -0.0413043648 0.0326618105 125 1311867722.7770080566 0.1476423591 0.0802362340 0.1477058530 0.0044622617 0.7072470000 968562177 0 1781387264 0.0999130607 -0.0412744284 0.0326259620 126 1311867722.8162860870 0.1479717940 0.0807738178 0.1479717940 0.0044448844 0.7404320000 968564027 0 1783103488 0.0997507945 -0.0414337106 0.0332277864 127 1311867722.8466939926 0.1489837170 0.0813109036 0.1489837170 0.0044630835 0.7117340000 968565781 0 1781497856 0.1000082716 -0.0428180136 0.0338095054 128 1311867722.8819770813 0.1501057893 0.0818483637 0.1501057893 0.0044495165 0.7144490000 968567631 0 1783250944 0.1002499163 -0.0437155738 0.0346648619 129 1311867722.9150629044 0.1526916921 0.0823975368 0.1526916921 0.0044488563 0.7122140000 968569321 0 1781493760 0.1022910252 -0.0432531685 0.0358820558 130 1311867722.9485991001 0.1533403993 0.0829432511 0.1533403993 0.0044638645 0.7156130000 968592163 0 1783230464 0.1024645492 -0.0440738127 0.0361975543 131 1311867722.9821140766 0.1543785632 0.0834885588 0.1543785632 0.0044484020 0.7225870000 968593949 0 1781641216 0.1026506200 -0.0450338237 0.0371668600 132 1311867723.0147259235 0.1552529782 0.0840322287 0.1552529782 0.0044328998 0.7207690000 968595735 0 1783250944 0.1032524034 -0.0444755331 0.0380127206 133 1311867723.0460629463 0.1562499553 0.0845752191 0.1562499553 0.0044472009 0.7261390000 968597489 0 1781239808 0.1034773737 -0.0451915152 0.0387445837 134 1311867723.0845439434 0.1584323049 0.0851263914 0.1584323049 0.0044436922 0.7195100000 968599371 0 1782976512 0.1048118249 -0.0464578718 0.0395377465 135 1311867723.1140980721 0.1593410075 0.0856761293 0.1593410075 0.0044295435 0.7294340000 968601125 0 1781387264 0.1049825624 -0.0469842292 0.0403098390 136 1311867723.1505160332 0.1607893854 0.0862284326 0.1607893854 0.0044205775 0.7317800000 968602975 0 1783103488 0.1056158394 -0.0478690974 0.0406842269 137 1311867723.1811029911 0.1614291668 0.0867773431 0.1614291668 0.0044069116 0.7314040000 968604729 0 1781497856 0.1053485721 -0.0490925461 0.0410355851 138 1311867723.2201359272 0.1624829322 0.0873259343 0.1624829322 0.0043911174 0.7288590000 968606611 0 1783123968 0.1055576950 -0.0499960557 0.0420408249 139 1311867723.2486810684 0.1648434401 0.0878836142 0.1648434401 0.0043882528 0.7335760000 968608333 0 1781129216 0.1074073762 -0.0507757589 0.0423922949 140 1311867723.2846419811 0.1599349082 0.0883982663 0.1648434401 0.0044242249 0.7589910000 968610183 0 1782870016 0.1021907330 -0.0507568941 0.0397702605 141 1311867723.3132460117 0.1587590128 0.0888972787 0.1648434401 0.0044111223 0.7330340000 968611905 0 1784389632 0.1007126197 -0.0510485023 0.0391098075 142 1311867723.3499810696 0.1581773609 0.0893851666 0.1648434401 0.0043990890 0.7405370000 968613787 0 1782509568 0.0995965302 -0.0508338213 0.0391852409 143 1311867723.3822429180 0.1585641205 0.0898689355 0.1648434401 0.0043879590 0.7447670000 968615605 0 1784393728 0.0995410159 -0.0512241088 0.0397457592 144 1311867723.4193739891 0.1591811478 0.0903502703 0.1648434401 0.0044060193 0.7390970000 968617455 0 1782636544 0.0999977812 -0.0516368411 0.0405905358 145 1311867723.4455900192 0.1590107381 0.0908237908 0.1648434401 0.0043953111 0.7394060000 968619145 0 1784414208 0.0995398089 -0.0515006036 0.0404019132 146 1311867723.4825348854 0.1595131755 0.0912942660 0.1648434401 0.0043943937 0.7435380000 968621027 0 1782255616 0.0991431177 -0.0516311936 0.0408667549 147 1311867723.5147960186 0.1598329395 0.0917605155 0.1648434401 0.0043808817 0.7670490000 968622781 0 1783992320 0.0989991054 -0.0516822934 0.0410336517 148 1311867723.5451340675 0.1602384746 0.0922232044 0.1648434401 0.0043683612 0.7549240000 968624567 0 1782403072 0.0987360701 -0.0519965701 0.0415016748 149 1311867723.5809938908 0.1607666910 0.0926832278 0.1648434401 0.0043576109 0.7434400000 968626417 0 1784012800 0.0986202881 -0.0523674078 0.0418882929 150 1311867723.6132669449 0.1625450402 0.0931489732 0.1648434401 0.0043495658 0.7568650000 968628235 0 1782022144 0.0999619141 -0.0526462831 0.0426585153 151 1311867723.6453940868 0.1622140408 0.0936063578 0.1648434401 0.0043362603 0.7424120000 968629989 0 1783631872 0.0993372202 -0.0525935628 0.0428060032 152 1311867723.6809489727 0.1627744287 0.0940614109 0.1648434401 0.0043235855 0.7478860000 968631839 0 1781649408 0.0995032340 -0.0531752817 0.0429344773 153 1311867723.7130429745 0.1634685695 0.0945150525 0.1648434401 0.0043121999 0.7458900000 968633625 0 1783365632 0.0996746942 -0.0536468923 0.0435164273 154 1311867723.7471990585 0.1644689441 0.0949692985 0.1648434401 0.0043009273 0.7871810000 968635443 0 1781760000 0.1003103703 -0.0538852587 0.0433267206 155 1311867723.7809250355 0.1650302261 0.0954213045 0.1650302261 0.0042906071 0.7493130000 968637261 0 1783513088 0.1001850590 -0.0547446981 0.0432993434 156 1311867723.8157649040 0.1666626185 0.0958779796 0.1666626185 0.0042840659 0.7552040000 968639079 0 1781886976 0.1012014374 -0.0554544926 0.0432043709 157 1311867723.8468959332 0.1680740565 0.0963378272 0.1680740565 0.0042726066 0.7532030000 968640865 0 1783640064 0.1023509353 -0.0554033071 0.0435120016 158 1311867723.8826351166 0.1668736488 0.0967842565 0.1680740565 0.0042716825 0.7514230000 968642683 0 1781903360 0.1006441638 -0.0559036955 0.0427499712 159 1311867723.9172909260 0.1672487259 0.0972274292 0.1680740565 0.0042657294 0.7503550000 968644437 0 1783635968 0.1006811485 -0.0560212433 0.0426985398 160 1311867723.9490020275 0.1674895734 0.0976665676 0.1680740565 0.0042548149 0.7590930000 968646191 0 1782013952 0.1008978412 -0.0552182980 0.0425502062 161 1311867723.9839010239 0.1690389216 0.0981098742 0.1690389216 0.0042549161 0.7755100000 968648041 0 1783631872 0.1019589007 -0.0561131723 0.0429149680 162 1311867724.0132899284 0.1687721312 0.0985460609 0.1690389216 0.0042533715 0.7733870000 968649763 0 1781641216 0.1016195044 -0.0560094193 0.0426497050 163 1311867724.0475380421 0.1701840162 0.0989855576 0.1701840162 0.0042432414 0.7562090000 968651613 0 1783357440 0.1028439105 -0.0559257716 0.0429725274 164 1311867724.0824530125 0.1704281121 0.0994211829 0.1704281121 0.0042360665 0.7596020000 968653431 0 1781751808 0.1027379259 -0.0563105941 0.0430332795 165 1311867724.1132431030 0.1696391553 0.0998467464 0.1704281121 0.0042244825 0.7598470000 968655217 0 1783484416 0.1017445326 -0.0562448315 0.0426156186 166 1311867724.1547191143 0.1699458212 0.1002690300 0.1704281121 0.0042204840 0.7615410000 968657163 0 1781878784 0.1019466743 -0.0557543524 0.0422836877 167 1311867724.1810541153 0.1701995730 0.1006877757 0.1704281121 0.0042123839 0.7609450000 968658853 0 1783525376 0.1019057408 -0.0559529327 0.0426037200 168 1311867724.2139430046 0.1701688617 0.1011013536 0.1704281121 0.0042040946 0.8007230000 968660671 0 1781514240 0.1014816687 -0.0563478880 0.0428304709 169 1311867724.2507870197 0.1695775092 0.1015065380 0.1704281121 0.0042009392 0.7709140000 968662521 0 1783103488 0.1005958244 -0.0558686927 0.0426088274 170 1311867724.2855930328 0.1707139611 0.1019136405 0.1707139611 0.0041942192 0.7717050000 968664339 0 1781514240 0.1015396416 -0.0558459312 0.0428342074 171 1311867724.3144888878 0.1710410267 0.1023178942 0.1710410267 0.0041829320 0.7713660000 968666061 0 1783230464 0.1015773863 -0.0563534722 0.0423233509 172 1311867724.3517999649 0.1709397733 0.1027168586 0.1710410267 0.0041861093 0.7760870000 968667975 0 1781641216 0.1010679007 -0.0566256121 0.0425700098 173 1311867724.3888330460 0.1704858691 0.1031085870 0.1710410267 0.0041803352 0.7689440000 968669793 0 1783357440 0.1004336551 -0.0565601662 0.0423155949 174 1311867724.4160330296 0.1705839187 0.1034963763 0.1710410267 0.0041752710 0.7781320000 968671515 0 1781751808 0.1005145684 -0.0568137020 0.0421054065 175 1311867724.4509639740 0.1705097407 0.1038793098 0.1710410267 0.0041652416 0.7840400000 968673333 0 1783357440 0.1001028344 -0.0574776158 0.0415797047 176 1311867724.4830689430 0.1707406938 0.1042592040 0.1710410267 0.0041538382 0.7771510000 968675119 0 1781768192 0.1000208631 -0.0579568185 0.0410769880 177 1311867724.5208630562 0.1695165634 0.1046278896 0.1710410267 0.0041457311 0.7776110000 968676937 0 1783357440 0.0981926918 -0.0584335364 0.0408414826 178 1311867724.5523910522 0.1679688096 0.1049837375 0.1710410267 0.0041363600 0.7810190000 968678755 0 1781624832 0.0965874866 -0.0587032922 0.0393634178 179 1311867724.5861799717 0.1659447998 0.1053243021 0.1710410267 0.0041324381 0.7840210000 968680541 0 1783103488 0.0941839442 -0.0590774342 0.0381752960 180 1311867724.6193559170 0.1650672853 0.1056562076 0.1710410267 0.0041678162 0.7813440000 968682327 0 1781260288 0.0931794867 -0.0590432249 0.0370342582 181 1311867724.6529819965 0.1632223278 0.1059742524 0.1710410267 0.0041743436 0.7913140000 968684145 0 1782849536 0.0907663032 -0.0589332655 0.0366492011 182 1311867724.6818330288 0.1601962745 0.1062721756 0.1710410267 0.0041651587 0.7892870000 968685867 0 1781006336 0.0872452483 -0.0592480600 0.0350188389 183 1311867724.7153129578 0.1569058001 0.1065488621 0.1710410267 0.0041831837 0.7806080000 968687685 0 1782611968 0.0835191905 -0.0584435277 0.0339691937 184 1311867724.7518899441 0.1543411016 0.1068086025 0.1710410267 0.0041923659 0.7979710000 968689535 0 1784373248 0.0805257559 -0.0572936051 0.0336453170 185 1311867724.7853860855 0.1516981870 0.1070512489 0.1710410267 0.0041952599 0.7925540000 968691353 0 1782513664 0.0774809718 -0.0569859482 0.0328401439 186 1311867724.8179960251 0.1491652578 0.1072776683 0.1710410267 0.0041846292 0.7945050000 968693139 0 1783992320 0.0744717941 -0.0569741279 0.0317456983 187 1311867724.8547580242 0.1469592899 0.1074898695 0.1710410267 0.0042224513 0.7897220000 968694957 0 1782132736 0.0717843026 -0.0567350537 0.0312946886 188 1311867724.8830249310 0.1449178904 0.1076889547 0.1710410267 0.0042194847 0.7959980000 968696679 0 1783611392 0.0693646371 -0.0564501509 0.0309191849 189 1311867724.9137279987 0.1435054541 0.1078784600 0.1710410267 0.0042161226 0.8287120000 968698465 0 1781751808 0.0674042478 -0.0567324087 0.0299177784 190 1311867724.9535229206 0.1415828764 0.1080558517 0.1710410267 0.0042176804 0.8056360000 968700347 0 1783382016 0.0652867407 -0.0563965775 0.0289766248 191 1311867724.9843940735 0.1401309520 0.1082237842 0.1710410267 0.0042077048 0.7970480000 968702133 0 1781633024 0.0637283251 -0.0562674031 0.0280466117 192 1311867725.0159099102 0.1389569789 0.1083838529 0.1710410267 0.0042213626 0.7967350000 968703887 0 1783111680 0.0624201261 -0.0565697774 0.0277714580 193 1311867725.0518310070 0.1371206343 0.1085327481 0.1710410267 0.0042175238 0.7994470000 968705737 0 1781268480 0.0599889196 -0.0569462776 0.0275721438 194 1311867725.0813930035 0.1360423416 0.1086745501 0.1710410267 0.0042097103 0.8032830000 968707491 0 1782857728 0.0585680008 -0.0568218231 0.0273751989 195 1311867725.1151220798 0.1352529377 0.1088108496 0.1710410267 0.0041992391 0.8016060000 968709309 0 1781125120 0.0574454777 -0.0573236309 0.0266451053 196 1311867725.1557130814 0.1337698847 0.1089381916 0.1710410267 0.0041994783 0.7970860000 968711223 0 1782722560 0.0554162748 -0.0573838390 0.0264195111 197 1311867725.1843969822 0.1324204803 0.1090573910 0.1710410267 0.0041979263 0.8054220000 968712945 0 1784500224 0.0536023639 -0.0575257465 0.0261146557 198 1311867725.2150099277 0.1307694763 0.1091670480 0.1710410267 0.0041904708 0.8009050000 968714731 0 1782894592 0.0512558185 -0.0582694784 0.0250478890 199 1311867725.2516539097 0.1288935989 0.1092661764 0.1710410267 0.0041878622 0.8055180000 968716613 0 1781239808 0.0487667918 -0.0581976250 0.0248101465 200 1311867725.2816410065 0.1267160624 0.1093534258 0.1710410267 0.0041828606 0.8034210000 968718367 0 1782870016 0.0462591760 -0.0581800938 0.0238605235 201 1311867725.3196239471 0.1258396655 0.1094354469 0.1710410267 0.0041789296 0.8026580000 968720217 0 1784520704 0.0448154584 -0.0583919585 0.0233220663 202 1311867725.3517010212 0.1240926757 0.1095080075 0.1710410267 0.0041833401 0.8070450000 968721971 0 1782525952 0.0424061120 -0.0585986152 0.0236613154 203 1311867725.3837459087 0.1231754646 0.1095753348 0.1710410267 0.0042166372 0.7998620000 968723693 0 1784393728 0.0414588861 -0.0582411513 0.0234817341 204 1311867725.4178969860 0.1223820820 0.1096381130 0.1710410267 0.0042192285 0.8093370000 968725543 0 1782652928 0.0401614644 -0.0583762154 0.0232389346 205 1311867725.4492449760 0.1205766425 0.1096914717 0.1710410267 0.0042371313 0.8089220000 968727297 0 1784414208 0.0376093276 -0.0581208728 0.0231286418 206 1311867725.4836509228 0.1199250817 0.1097411494 0.1710410267 0.0042630353 0.8299760000 968729115 0 1782255616 0.0362634733 -0.0579163954 0.0229193512 207 1311867725.5178139210 0.1190024465 0.1097858900 0.1710410267 0.0042606420 0.8158180000 968730997 0 1784012800 0.0348010659 -0.0576757975 0.0220877733 208 1311867725.5497610569 0.1180870682 0.1098257995 0.1710410267 0.0042508791 0.8178120000 968732751 0 1782128640 0.0328494571 -0.0581097156 0.0220166836 209 1311867725.5815479755 0.1172629297 0.1098613839 0.1710410267 0.0042419480 0.8185470000 968734537 0 1783758848 0.0312742367 -0.0579295978 0.0217313487 210 1311867725.6194949150 0.1171117276 0.1098959093 0.1710410267 0.0042338982 0.8184170000 968736419 0 1781895168 0.0303852186 -0.0581817366 0.0214419644 211 1311867725.6515610218 0.1166732982 0.1099280296 0.1710410267 0.0042979113 0.8182700000 968738205 0 1783525376 0.0289716423 -0.0587419346 0.0213926639 212 1311867725.6834650040 0.1163123623 0.1099581444 0.1710410267 0.0042945779 0.8313650000 968739991 0 1781514240 0.0276265480 -0.0590734072 0.0220831037 213 1311867725.7201809883 0.1158241704 0.1099856844 0.1710410267 0.0042861546 0.8243410000 968741841 0 1783103488 0.0261269603 -0.0595115349 0.0225736145 214 1311867725.7515070438 0.1162221730 0.1100148269 0.1710410267 0.0042761777 0.8231120000 968743627 0 1781514240 0.0256082676 -0.0603796020 0.0225677285 215 1311867725.7835409641 0.1041444838 0.1099875230 0.1710410267 0.0043103231 0.8332510000 968745381 0 1783230464 0.0115661537 -0.0585538298 0.0208294429 216 1311867725.8211829662 0.1009887010 0.1099458618 0.1710410267 0.0043366897 0.8612700000 968747295 0 1781641216 0.0062752487 -0.0596789196 0.0200829487 217 1311867725.8517971039 0.0994830802 0.1098976462 0.1710410267 0.0043273098 0.8228250000 968749081 0 1783250944 0.0034789201 -0.0601687208 0.0193195306 218 1311867725.8837900162 0.0985332802 0.1098455161 0.1710410267 0.0043470942 0.8266810000 968750803 0 1781239808 0.0016545493 -0.0597719625 0.0195402205 219 1311867725.9192690849 0.0984849408 0.1097936413 0.1710410267 0.0043381946 0.8199790000 968752653 0 1782976512 0.0002550111 -0.0604299568 0.0197215229 220 1311867725.9511859417 0.0988596976 0.1097439415 0.1710410267 0.0043302290 0.8226440000 968754439 0 1781387264 -0.0007498225 -0.0613935515 0.0206733644 221 1311867725.9829630852 0.0994059294 0.1096971632 0.1710410267 0.0043296023 0.8225920000 968756193 0 1783103488 -0.0009494098 -0.0615006536 0.0216912590 222 1311867726.0219368935 0.1015004665 0.1096602412 0.1710410267 0.0043228356 0.8716020000 968758107 0 1781514240 -0.0007068156 -0.0629255548 0.0241972394 223 1311867726.0504179001 0.1029356122 0.1096300859 0.1710410267 0.0043148468 0.8228510000 968759797 0 1783250944 -0.0011488252 -0.0646857992 0.0259663295 224 1311867726.0845088959 0.1041281670 0.1096055237 0.1710410267 0.0043170454 0.8258990000 968761647 0 1781493760 -0.0015825266 -0.0659542829 0.0285113156 225 1311867726.1199669838 0.1063448414 0.1095910318 0.1710410267 0.0043084700 0.8299660000 968763465 0 1783123968 -0.0012436071 -0.0677786097 0.0308593996 226 1311867726.1506989002 0.1073813438 0.1095812544 0.1710410267 0.0043061981 0.8232480000 968765251 0 1781112832 -0.0014382602 -0.0687633380 0.0321758501 227 1311867726.1824700832 0.1086430773 0.1095771215 0.1710410267 0.0043126904 0.8283040000 968767037 0 1782890496 -0.0020720451 -0.0700393617 0.0345644765 228 1311867726.2198660374 0.1100326031 0.1095791192 0.1710410267 0.0043356211 0.8636910000 968768887 0 1784373248 -0.0023761333 -0.0712224692 0.0365425386 229 1311867726.2506690025 0.1124232262 0.1095915389 0.1710410267 0.0043315018 0.8367280000 968770673 0 1782509568 -0.0022438015 -0.0733223036 0.0390676521 230 1311867726.2845950127 0.1147685274 0.1096140475 0.1710410267 0.0043335676 0.8337080000 968772459 0 1784139776 -0.0023010017 -0.0752196386 0.0420031585 231 1311867726.3187239170 0.1171583161 0.1096467067 0.1710410267 0.0043342095 0.8338520000 968774309 0 1782255616 -0.0019725687 -0.0767817348 0.0443442166 232 1311867726.3524029255 0.1194314957 0.1096888825 0.1710410267 0.0043319435 0.8451390000 968776127 0 1784000512 -0.0014763819 -0.0778280050 0.0470266752 233 1311867726.3835608959 0.1216465011 0.1097402028 0.1710410267 0.0043255345 0.8413390000 968777881 0 1782390784 -0.0016164267 -0.0793421343 0.0493630432 234 1311867726.4218099117 0.1231827140 0.1097976494 0.1710410267 0.0043224704 0.8678090000 968779795 0 1784037376 -0.0016306269 -0.0798720792 0.0512930527 235 1311867726.4504199028 0.1255237460 0.1098645690 0.1710410267 0.0043166874 0.8512450000 968781517 0 1782136832 -0.0017596917 -0.0812615454 0.0542427115 236 1311867726.4843189716 0.1275259852 0.1099394055 0.1710410267 0.0043120607 0.8422610000 968783335 0 1783767040 -0.0019536167 -0.0825972408 0.0564952344 237 1311867726.5207901001 0.1303827316 0.1100256642 0.1710410267 0.0043125080 0.8432170000 968785185 0 1781882880 -0.0019351310 -0.0843770653 0.0597657226 238 1311867726.5524380207 0.1334853321 0.1101242343 0.1710410267 0.0043158867 0.8451030000 968786971 0 1783513088 -0.0007397063 -0.0858181939 0.0627070367 239 1311867726.5874860287 0.1361693144 0.1102332095 0.1710410267 0.0043138805 0.8458260000 968788821 0 1781620736 -0.0006015580 -0.0872680545 0.0658791810 240 1311867726.6204600334 0.1383212954 0.1103502432 0.1710410267 0.0043284204 0.8966790000 968790607 0 1783250944 0.0003194674 -0.0882118344 0.0680758208 241 1311867726.6509370804 0.1403126419 0.1104745685 0.1710410267 0.0043337120 0.8550670000 968792361 0 1781239808 0.0010445251 -0.0895050764 0.0696334019 242 1311867726.6916151047 0.1407870650 0.1105998267 0.1710410267 0.0043248809 0.8510760000 968794307 0 1782886400 0.0013913289 -0.0899024084 0.0696620569 243 1311867726.7201170921 0.1415063739 0.1107270142 0.1710410267 0.0043176157 0.8525980000 968795997 0 1784500224 0.0022851164 -0.0902307928 0.0698625222 244 1311867726.7513859272 0.1407745630 0.1108501599 0.1710410267 0.0043138782 0.8562800000 968797783 0 1782763520 0.0021711935 -0.0902011618 0.0688225254 245 1311867726.7880010605 0.1390777379 0.1109653745 0.1710410267 0.0043149160 0.8559480000 968799665 0 1784410112 0.0018779180 -0.0897503272 0.0666958168 246 1311867726.8198299408 0.1372189671 0.1110720964 0.1710410267 0.0043063054 0.8875360000 968801419 0 1782779904 0.0016776039 -0.0886509344 0.0647325441 247 1311867726.8500390053 0.1364343762 0.1111747777 0.1710410267 0.0043005295 0.8631180000 968803173 0 1784410112 0.0019980429 -0.0881573260 0.0634829774 248 1311867726.8927390575 0.1360676289 0.1112751521 0.1710410267 0.0042918664 0.8573810000 968805151 0 1782382592 0.0021645410 -0.0881336480 0.0628625378 249 1311867726.9216780663 0.1350346953 0.1113705719 0.1710410267 0.0042852020 0.8569050000 968806873 0 1784012800 0.0019872079 -0.0873298123 0.0621334203 250 1311867726.9543499947 0.1336502284 0.1114596906 0.1710410267 0.0042933532 0.8675550000 968808659 0 1782022144 0.0021400135 -0.0863113031 0.0610359572 251 1311867726.9902989864 0.1320712566 0.1115418084 0.1710410267 0.0042882480 0.8670830000 968810477 0 1783738368 0.0013537087 -0.0858727843 0.0593843125 252 1311867727.0208179951 0.1308163702 0.1116182947 0.1710410267 0.0042845941 0.8731180000 968812263 0 1782128640 0.0017580707 -0.0848847479 0.0576540567 253 1311867727.0536949635 0.1292837411 0.1116881186 0.1710410267 0.0042825008 0.8640270000 968814049 0 1783758848 0.0015750673 -0.0842779353 0.0560643822 254 1311867727.0911629200 0.1284157634 0.1117539755 0.1710410267 0.0042779120 0.8666290000 968815931 0 1781747712 0.0015152097 -0.0837962180 0.0554575473 255 1311867727.1196689606 0.1265027076 0.1118118137 0.1710410267 0.0042741690 0.8666790000 968817589 0 1783484416 0.0009585072 -0.0831052884 0.0532733016 256 1311867727.1514298916 0.1246806681 0.1118620826 0.1710410267 0.0042700426 0.8664680000 968819407 0 1781891072 0.0000998494 -0.0825150087 0.0518540218 257 1311867727.1904149055 0.1237127706 0.1119081942 0.1710410267 0.0042754387 0.8808390000 968821257 0 1783648256 0.0005708523 -0.0815167874 0.0512863509 258 1311867727.2208960056 0.1217141151 0.1119462017 0.1710410267 0.0042679760 0.9087230000 968865027 0 1782018048 -0.0001145573 -0.0804080218 0.0498323441 259 1311867727.2544560432 0.1186144128 0.1119719477 0.1710410267 0.0042708427 0.8723620000 968866813 0 1783754752 -0.0015387950 -0.0791610628 0.0465891324 260 1311867727.2870850563 0.1161662191 0.1119880795 0.1710410267 0.0042679400 0.8780170000 968868631 0 1781997568 -0.0019264016 -0.0776966363 0.0439966992 261 1311867727.3192501068 0.1134368703 0.1119936304 0.1710410267 0.0042696971 0.8790660000 968870417 0 1783758848 -0.0022788292 -0.0763056949 0.0407194272 262 1311867727.3502039909 0.1106513441 0.1119885072 0.1710410267 0.0042808429 0.8805640000 968872171 0 1781743616 -0.0030893160 -0.0751943886 0.0373660550 263 1311867727.3894629478 0.1075927839 0.1119717934 0.1710410267 0.0042876953 0.8848260000 968874021 0 1783521280 -0.0032360144 -0.0728396177 0.0343228057 264 1311867727.4182970524 0.1038803384 0.1119411440 0.1710410267 0.0042836011 0.9098130000 968875775 0 1781764096 -0.0043677636 -0.0707582608 0.0313044935 265 1311867727.4495580196 0.1009477377 0.1118996594 0.1710410267 0.0042856022 0.8752560000 968877497 0 1783373824 -0.0049912762 -0.0687824935 0.0284608118 266 1311867727.4858360291 0.0986162126 0.1118497216 0.1710410267 0.0042796143 0.8823870000 968879379 0 1781510144 -0.0054790140 -0.0668390170 0.0268766265 267 1311867727.5198891163 0.0964320973 0.1117919777 0.1710410267 0.0042805245 0.8831570000 968881165 0 1783250944 -0.0060195024 -0.0653002709 0.0247216672 268 1311867727.5494980812 0.0945309922 0.1117275711 0.1710410267 0.0042810299 0.8859880000 968882919 0 1781493760 -0.0068745543 -0.0647507757 0.0226071831 269 1311867727.5905909538 0.0919949263 0.1116542155 0.1710410267 0.0042809568 0.8854960000 968884865 0 1783230464 -0.0077361385 -0.0637792796 0.0206410736 270 1311867727.6176431179 0.0904410481 0.1115756482 0.1710410267 0.0042743234 0.8860380000 968886555 0 1781641216 -0.0086914310 -0.0633247197 0.0194951445 271 1311867727.6497650146 0.0882688463 0.1114896453 0.1710410267 0.0042736765 0.8787440000 968888341 0 1783377920 -0.0099939061 -0.0626269281 0.0175223388 272 1311867727.6884338856 0.0858946294 0.1113955459 0.1710410267 0.0042728202 0.8845810000 968890127 0 1781649408 -0.0116283670 -0.0620107390 0.0154555757 273 1311867727.7184689045 0.0832283422 0.1112923694 0.1710410267 0.0042667031 0.8836280000 968891913 0 1783365632 -0.0140763186 -0.0612184256 0.0132268686 274 1311867727.7523269653 0.0810690597 0.1111820653 0.1710410267 0.0042616552 0.8821800000 968893731 0 1781760000 -0.0172869153 -0.0615925714 0.0116516994 275 1311867727.7856590748 0.0782997832 0.1110624934 0.1710410267 0.0042686820 0.8834620000 968895517 0 1783513088 -0.0214005355 -0.0614030734 0.0114751384 276 1311867727.8181309700 0.0755966231 0.1109339939 0.1710410267 0.0042818771 0.9044070000 968897335 0 1781903360 -0.0249435641 -0.0606003106 0.0103642745 277 1311867727.8548729420 0.0729869157 0.1107970008 0.1710410267 0.0042810575 0.8719930000 968899185 0 1783508992 -0.0284616705 -0.0600104965 0.0089975707 278 1311867727.8882629871 0.0706430823 0.1106525622 0.1710410267 0.0042783046 0.8738370000 968901003 0 1781886976 -0.0318219364 -0.0595634282 0.0080734380 279 1311867727.9193139076 0.0689536780 0.1105031039 0.1710410267 0.0042773842 0.8741270000 968902757 0 1783504896 -0.0344927534 -0.0591807403 0.0077412953 280 1311867727.9556980133 0.0667997301 0.1103470204 0.1710410267 0.0042739978 0.8749290000 968904607 0 1781514240 -0.0376146659 -0.0586169660 0.0065692384 281 1311867727.9869389534 0.0647871196 0.1101848855 0.1710410267 0.0042708584 0.8752760000 968906425 0 1783230464 -0.0404887795 -0.0579944625 0.0053148582 282 1311867728.0179219246 0.0633749291 0.1100188928 0.1710410267 0.0042670488 0.8718170000 968908147 0 1781624832 -0.0425998084 -0.0576344877 0.0046852198 283 1311867728.0555219650 0.0613439791 0.1098468966 0.1710410267 0.0042650730 0.8630240000 968910029 0 1783103488 -0.0451602302 -0.0566605590 0.0037426911 284 1311867728.0892169476 0.0601710714 0.1096719817 0.1710410267 0.0042598226 0.8756400000 968911847 0 1781243904 -0.0462817661 -0.0559859276 0.0033847862 285 1311867728.1177880764 0.0586511716 0.1094929613 0.1710410267 0.0042699475 0.8703580000 968913601 0 1782722560 -0.0492935553 -0.0553560555 0.0023394302 286 1311867728.1556169987 0.0577782206 0.1093121406 0.1710410267 0.0042728462 0.8843310000 968915451 0 1784520704 -0.0515799969 -0.0550689064 0.0018841289 287 1311867728.1882989407 0.0568118356 0.1091292127 0.1710410267 0.0042673296 0.8702580000 968917301 0 1782513664 -0.0538720004 -0.0545665696 0.0007230137 288 1311867728.2182519436 0.0560894758 0.1089450469 0.1710410267 0.0042672565 0.8978600000 968919055 0 1784119296 -0.0564348623 -0.0542640164 -0.0001671724 289 1311867728.2558999062 0.0553344153 0.1087595430 0.1710410267 0.0042676788 0.8680990000 968920905 0 1782243328 -0.0604464859 -0.0538266636 -0.0011226349 290 1311867728.2875900269 0.0554438233 0.1085756957 0.1710410267 0.0042801424 0.8747600000 968922691 0 1783738368 -0.0659390762 -0.0539432205 -0.0012797061 291 1311867728.3226509094 0.0550766625 0.1083918502 0.1710410267 0.0042790564 0.8762220000 968924541 0 1781878784 -0.0692319721 -0.0534322932 -0.0016140381 292 1311867728.3597300053 0.0557798594 0.1082116722 0.1710410267 0.0042775639 0.8736240000 968926359 0 1783357440 -0.0726021156 -0.0536269397 -0.0022242088 293 1311867728.3861401081 0.0552247018 0.1080308293 0.1710410267 0.0042761440 0.8715100000 968928081 0 1781497856 -0.0756947100 -0.0522959381 -0.0042813178 294 1311867728.4175701141 0.0564255901 0.1078553012 0.1710410267 0.0043353441 0.9006030000 968929867 0 1782976512 -0.0781683698 -0.0523360968 -0.0052172169 295 1311867728.4568250179 0.0570749491 0.1076831645 0.1710410267 0.0043310075 0.8679230000 968931749 0 1781116928 -0.0816358104 -0.0517639741 -0.0066509498 296 1311867728.4875330925 0.0570350997 0.1075120561 0.1710410267 0.0043261990 0.8645410000 968933503 0 1782743040 -0.0835385248 -0.0509281307 -0.0074696280 297 1311867728.5187420845 0.0587286763 0.1073478023 0.1710410267 0.0043226952 0.8724660000 968935257 0 1784373248 -0.0877152309 -0.0508630052 -0.0076553104 298 1311867728.5550920963 0.0608570650 0.1071917931 0.1710410267 0.0043320668 0.8743000000 968937139 0 1782497280 -0.0925627276 -0.0505005009 -0.0082905339 299 1311867728.5878560543 0.0641990155 0.1070480046 0.1710410267 0.0043415210 0.8657920000 968938957 0 1783992320 -0.0987656713 -0.0501599908 -0.0092137335 300 1311867728.6187679768 0.0685504749 0.1069196795 0.1710410267 0.0043595296 0.8654550000 968940679 0 1782132736 -0.1061190888 -0.0496073775 -0.0103478441 301 1311867728.6580820084 0.0723708868 0.1068048994 0.1710410267 0.0043723615 0.8582290000 968942593 0 1783627776 -0.1118927822 -0.0488869138 -0.0120578669 302 1311867728.6893489361 0.0745537430 0.1066981075 0.1710410267 0.0043667793 0.8659830000 968944379 0 1781751808 -0.1149809286 -0.0484734848 -0.0131066646 303 1311867728.7210168839 0.0774698630 0.1066016447 0.1710410267 0.0043619453 0.8647010000 968946165 0 1783377920 -0.1190332472 -0.0482212603 -0.0142525891 304 1311867728.7584259510 0.0805244893 0.1065158646 0.1710410267 0.0043612541 0.8620650000 968948015 0 1781370880 -0.1225872487 -0.0481693819 -0.0150909796 305 1311867728.7858450413 0.0816426054 0.1064343129 0.1710410267 0.0043558897 0.8622460000 968949769 0 1782976512 -0.1236544251 -0.0485693626 -0.0144542046 306 1311867728.8203740120 0.0812294036 0.1063519439 0.1710410267 0.0043490551 0.9160460000 968951555 0 1781125120 -0.1228813604 -0.0483992621 -0.0151181677 307 1311867728.8545160294 0.0818906650 0.1062722655 0.1710410267 0.0043423739 0.8683590000 968953373 0 1782595584 -0.1236227006 -0.0481776260 -0.0153779853 308 1311867728.8860759735 0.0834498331 0.1061981667 0.1710410267 0.0043371374 0.8661930000 968955191 0 1784246272 -0.1252759546 -0.0481248051 -0.0170644894 309 1311867728.9193949699 0.0850201249 0.1061296293 0.1710410267 0.0043319407 0.8636960000 968956945 0 1782386688 -0.1273136884 -0.0475234017 -0.0178316720 310 1311867728.9585559368 0.0863037631 0.1060656749 0.1710410267 0.0043547287 0.8629910000 968958923 0 1784012800 -0.1286513954 -0.0468344465 -0.0190531276 311 1311867728.9886839390 0.0890857354 0.1060110770 0.1710410267 0.0043512209 0.8687540000 968960613 0 1782013952 -0.1314360350 -0.0469917208 -0.0197350383 312 1311867729.0231020451 0.0906549841 0.1059618588 0.1710410267 0.0043486451 0.9022510000 968962463 0 1783619584 -0.1328993887 -0.0467446819 -0.0196515992 313 1311867729.0583839417 0.0925288424 0.1059189418 0.1710410267 0.0043483398 0.8633100000 968964313 0 1781760000 -0.1352144480 -0.0459856093 -0.0199367851 314 1311867729.0882170200 0.0947946161 0.1058835140 0.1710410267 0.0043440389 0.8672190000 968966067 0 1783386112 -0.1377382576 -0.0461851656 -0.0195015334 315 1311867729.1263229847 0.0949172154 0.1058487004 0.1710410267 0.0043585624 0.8594900000 968967949 0 1781497856 -0.1387310326 -0.0452486426 -0.0192006864 316 1311867729.1556320190 0.0959138870 0.1058172611 0.1710410267 0.0043526701 0.8563580000 968969671 0 1782976512 -0.1407813430 -0.0444701537 -0.0189744160 317 1311867729.1888830662 0.0977663249 0.1057918638 0.1710410267 0.0043811934 0.8679060000 968971489 0 1781116928 -0.1435847133 -0.0441577733 -0.0191443674 318 1311867729.2240469456 0.1003971100 0.1057748992 0.1710410267 0.0043878144 0.8637240000 968973307 0 1782611968 -0.1465563029 -0.0438302867 -0.0194747988 319 1311867729.2579979897 0.1028011143 0.1057655770 0.1710410267 0.0043819383 0.8632940000 968975157 0 1784381440 -0.1490043402 -0.0441666804 -0.0189827830 320 1311867729.2880148888 0.1060792655 0.1057665572 0.1710410267 0.0043781769 0.8657580000 968976911 0 1782525952 -0.1522419155 -0.0447391234 -0.0186428037 321 1311867729.3236539364 0.1105367318 0.1057814176 0.1710410267 0.0043799343 0.8584320000 968978729 0 1783992320 -0.1567015350 -0.0445433483 -0.0186081585 322 1311867729.3580930233 0.1145670786 0.1058087023 0.1710410267 0.0043928403 0.8624580000 968980579 0 1782132736 -0.1601657271 -0.0445364527 -0.0189156849 323 1311867729.3882780075 0.1172928289 0.1058442568 0.1710410267 0.0043903965 0.8581730000 968982301 0 1783627776 -0.1624441445 -0.0443861485 -0.0187007207 324 1311867729.4253289700 0.1206593812 0.1058899825 0.1710410267 0.0043891537 0.9065700000 968984183 0 1781878784 -0.1656219363 -0.0437189266 -0.0188733153 325 1311867729.4572670460 0.1229313910 0.1059424176 0.1710410267 0.0043879263 0.8628890000 968985969 0 1783484416 -0.1673048735 -0.0431575738 -0.0200450588 326 1311867729.4887750149 0.1251432747 0.1060013160 0.1710410267 0.0043980849 0.8554010000 968987787 0 1781624832 -0.1691776812 -0.0429859683 -0.0208793469 327 1311867729.5223650932 0.1279651970 0.1060684838 0.1710410267 0.0043951886 0.8446390000 968989573 0 1783103488 -0.1716035306 -0.0431600697 -0.0210627317 328 1311867729.5603790283 0.1305528879 0.1061431314 0.1710410267 0.0043931664 0.8522090000 968991455 0 1781243904 -0.1738020331 -0.0432097465 -0.0218863823 329 1311867729.5890150070 0.1320686638 0.1062219324 0.1710410267 0.0043873703 0.8473710000 968993177 0 1782722560 -0.1750266552 -0.0432613716 -0.0225336738 330 1311867729.6254830360 0.1346064210 0.1063079460 0.1710410267 0.0043851670 0.8801410000 968995027 0 1780862976 -0.1774459183 -0.0429890752 -0.0224239212 331 1311867729.6614611149 0.1368739903 0.1064002905 0.1710410267 0.0043806117 0.8543970000 968996877 0 1782468608 -0.1795335412 -0.0430110656 -0.0225505680 332 1311867729.6888220310 0.1379020065 0.1064951752 0.1710410267 0.0043758767 0.8443140000 968998535 0 1784119296 -0.1804502904 -0.0428867191 -0.0231059678 333 1311867729.7230739594 0.1402303874 0.1065964822 0.1710410267 0.0043716707 0.8456630000 969000385 0 1782259712 -0.1826107949 -0.0429904535 -0.0233246498 334 1311867729.7570610046 0.1426063478 0.1067042961 0.1710410267 0.0043689970 0.8430200000 969002107 0 1783738368 -0.1845924854 -0.0429498963 -0.0232956894 335 1311867729.7899730206 0.1457589269 0.1068208771 0.1710410267 0.0043639197 0.8469930000 969003925 0 1781878784 -0.1874528229 -0.0433255099 -0.0233282670 336 1311867729.8264250755 0.1487987787 0.1069458113 0.1710410267 0.0043657915 0.8803180000 969005743 0 1783484416 -0.1902704090 -0.0431185067 -0.0230070632 337 1311867729.8550031185 0.1521682292 0.1070800025 0.1710410267 0.0043641014 0.8454200000 969007465 0 1781641216 -0.1935433745 -0.0428536572 -0.0223895982 338 1311867729.8881840706 0.1542525142 0.1072195661 0.1710410267 0.0043605037 0.8362680000 969009315 0 1783357440 -0.1954357922 -0.0430995412 -0.0224891845 339 1311867729.9233629704 0.1573992372 0.1073675888 0.1710410267 0.0043558727 0.8364580000 969011133 0 1781768192 -0.1985193342 -0.0427086949 -0.0224318206 340 1311867729.9569330215 0.1620080918 0.1075282961 0.1710410267 0.0043641735 0.8345630000 969012951 0 1783484416 -0.2031855583 -0.0426990055 -0.0215735286 341 1311867729.9865698814 0.1656063497 0.1076986130 0.1710410267 0.0043638261 0.8406400000 969014673 0 1781874688 -0.2066444904 -0.0428769439 -0.0220085531 342 1311867730.0230469704 0.1684733331 0.1078763169 0.1710410267 0.0043596617 0.8687320000 969016523 0 1783504896 -0.2094283402 -0.0424996167 -0.0222182423 343 1311867730.0557899475 0.1713615954 0.1080614051 0.1713615954 0.0043565072 0.8292120000 969018341 0 1781489664 -0.2123687416 -0.0420563929 -0.0217434019 344 1311867730.0871100426 0.1734897494 0.1082516038 0.1734897494 0.0043514307 0.8280880000 969020127 0 1783267328 -0.2143027037 -0.0420658365 -0.0218263865 345 1311867730.1231229305 0.1750998199 0.1084453668 0.1750998199 0.0043463125 0.8295640000 969021977 0 1781633024 -0.2157875597 -0.0419830494 -0.0215617418 346 1311867730.1568520069 0.1767839938 0.1086428772 0.1767839938 0.0043407548 0.8266280000 969023795 0 1783373824 -0.2174612880 -0.0418815240 -0.0209678803 347 1311867730.1882419586 0.1788301766 0.1088451461 0.1788301766 0.0043387811 0.8298500000 969025549 0 1781997568 -0.2194227874 -0.0412535705 -0.0212743562 348 1311867730.2224810123 0.1813780367 0.1090535740 0.1813780367 0.0043340170 0.8796880000 969027399 0 1783648256 -0.2220354676 -0.0409305729 -0.0205755923 349 1311867730.2575879097 0.1832469106 0.1092661623 0.1832469106 0.0043286101 0.8283670000 969029217 0 1781993472 -0.2240368128 -0.0402506590 -0.0204947963 350 1311867730.2914879322 0.1833941340 0.1094779565 0.1833941340 0.0043237421 0.8294090000 969031035 0 1783754752 -0.2241222411 -0.0396617465 -0.0206801686 351 1311867730.3230810165 0.1836881638 0.1096893816 0.1836881638 0.0043207753 0.8376810000 969032821 0 1782386688 -0.2243989557 -0.0394136868 -0.0207597092 352 1311867730.3554260731 0.1856895536 0.1099052912 0.1856895536 0.0043218339 0.8230220000 969034607 0 1784164352 -0.2260418981 -0.0397108234 -0.0205365587 353 1311867730.3982920647 0.1860239357 0.1101209247 0.1860239357 0.0043200915 0.8299750000 969036553 0 1782530048 -0.2262107581 -0.0392997488 -0.0202547386 354 1311867730.4225230217 0.1867931634 0.1103375130 0.1867931634 0.0043204218 0.8598300000 969038243 0 1784016896 -0.2272560149 -0.0384145416 -0.0198672637 355 1311867730.4600110054 0.1866320074 0.1105524271 0.1867931634 0.0043146604 0.8257720000 969040093 0 1782530048 -0.2270866930 -0.0384208523 -0.0200654510 356 1311867730.4948410988 0.1885007471 0.1107713830 0.1885007471 0.0043171676 0.8246760000 969041911 0 1784283136 -0.2286852300 -0.0386679210 -0.0198886041 357 1311867730.5300729275 0.1897636801 0.1109926500 0.1897636801 0.0043115662 0.8315990000 969043729 0 1782755328 -0.2297871560 -0.0384731293 -0.0195534304 358 1311867730.5597670078 0.1893599629 0.1112115531 0.1897636801 0.0043060489 0.8290400000 969045483 0 1781489664 -0.2292041332 -0.0383602343 -0.0198048577 359 1311867730.5940020084 0.1920353174 0.1114366889 0.1920353174 0.0043046387 0.8311150000 969047333 0 1783119872 -0.2316884398 -0.0384358391 -0.0195811447 360 1311867730.6230149269 0.1921443790 0.1116608769 0.1921443790 0.0043037852 0.8749280000 969049023 0 1781637120 -0.2316262275 -0.0376223139 -0.0197220836 361 1311867730.6614060402 0.1951743662 0.1118922162 0.1951743662 0.0043010204 0.8315010000 969050905 0 1783267328 -0.2342843413 -0.0376236849 -0.0191762727 362 1311867730.6922950745 0.1961115450 0.1121248663 0.1961115450 0.0042954365 0.8248420000 969052691 0 1781764096 -0.2348391265 -0.0374986455 -0.0192511082 363 1311867730.7275629044 0.1976460069 0.1123604617 0.1976460069 0.0042960404 0.8271300000 969054509 0 1783394304 -0.2360078394 -0.0372899771 -0.0196984634 364 1311867730.7572948933 0.1987101138 0.1125976861 0.1987101138 0.0042914017 0.8275930000 969056263 0 1781743616 -0.2366929203 -0.0365416333 -0.0197593123 365 1311867730.7932779789 0.1995399594 0.1128358841 0.1995399594 0.0042871546 0.8267310000 969058145 0 1783521280 -0.2368995547 -0.0360859856 -0.0202545673 366 1311867730.8240480423 0.1990351975 0.1130714013 0.1995399594 0.0042820818 0.8581320000 969059867 0 1781870592 -0.2353247851 -0.0369510427 -0.0211051423 367 1311867730.8591129780 0.1988283545 0.1133050715 0.1995399594 0.0042772410 0.8222670000 969061717 0 1783390208 -0.2344825417 -0.0363702811 -0.0212061200 368 1311867730.8922739029 0.1997982860 0.1135401074 0.1997982860 0.0042734820 0.8304190000 969063439 0 1781870592 -0.2348746806 -0.0354948603 -0.0206077695 369 1311867730.9270720482 0.2009193003 0.1137769074 0.2009193003 0.0042728721 0.8202450000 969065289 0 1783648256 -0.2352674603 -0.0349520221 -0.0198964793 370 1311867730.9611239433 0.2026427686 0.1140170854 0.2026427686 0.0042732284 0.8322610000 969067075 0 1781997568 -0.2363839597 -0.0343907066 -0.0193625242 371 1311867730.9928169250 0.2029688656 0.1142568476 0.2029688656 0.0042735923 0.8305790000 969068861 0 1783627776 -0.2359915823 -0.0345174856 -0.0189175904 372 1311867731.0221049786 0.2046689838 0.1144998910 0.2046689838 0.0042707127 0.8778460000 969070615 0 1782124544 -0.2370981127 -0.0346268192 -0.0187957380 373 1311867731.0609729290 0.2071761191 0.1147483527 0.2071761191 0.0042687670 0.8265410000 969072497 0 1783775232 -0.2389049083 -0.0341693088 -0.0185072124 374 1311867731.0900061131 0.2070053220 0.1149950291 0.2071761191 0.0042675516 0.8272370000 969074219 0 1782124544 -0.2380984426 -0.0340224914 -0.0190321505 375 1311867731.1276559830 0.2070317715 0.1152404604 0.2071761191 0.0042635241 0.8299360000 969076101 0 1783902208 -0.2372404486 -0.0344893858 -0.0190415923 376 1311867731.1551880836 0.2081322670 0.1154875131 0.2081322670 0.0042585036 0.8329880000 969077823 0 1782267904 -0.2380106598 -0.0337751582 -0.0182046164 377 1311867731.1935870647 0.2083894759 0.1157339374 0.2083894759 0.0042551664 0.8348620000 969079673 0 1783902208 -0.2377170473 -0.0334929414 -0.0175385792 378 1311867731.2235820293 0.2089155167 0.1159804495 0.2089155167 0.0042499802 0.8502860000 969081459 0 1782398976 -0.2376861125 -0.0335130841 -0.0166776869 379 1311867731.2602028847 0.2106126696 0.1162301387 0.2106126696 0.0042475049 0.8253810000 969083277 0 1784029184 -0.2384972274 -0.0336595029 -0.0161403120 380 1311867731.2900059223 0.2134158313 0.1164858906 0.2134158313 0.0043032999 0.8323320000 969085031 0 1782378496 -0.2400817424 -0.0337233357 -0.0158626456 381 1311867731.3230779171 0.2137781382 0.1167412508 0.2137781382 0.0043358016 0.8298840000 969086849 0 1784156160 -0.2401220500 -0.0336670689 -0.0162839275 382 1311867731.3570859432 0.2119436264 0.1169904717 0.2137781382 0.0043471653 0.8267100000 969088699 0 1782505472 -0.2376378328 -0.0334952734 -0.0166606884 383 1311867731.3915760517 0.2098856121 0.1172330177 0.2137781382 0.0043764014 0.8401580000 969090485 0 1784283136 -0.2348042578 -0.0340633877 -0.0169664137 384 1311867731.4279849529 0.2088735104 0.1174716648 0.2137781382 0.0043950494 0.8309720000 969092367 0 1782779904 -0.2331172973 -0.0345732868 -0.0180050246 385 1311867731.4602010250 0.2065144926 0.1177029449 0.2137781382 0.0044116261 0.8423850000 969094153 0 1784410112 -0.2301356047 -0.0348890014 -0.0191439912 386 1311867731.4926180840 0.2068994939 0.1179340241 0.2137781382 0.0044167474 0.8483080000 969095939 0 1782759424 -0.2299284041 -0.0354836136 -0.0190126039 387 1311867731.5259540081 0.2085417211 0.1181681525 0.2137781382 0.0044238542 0.8586590000 969097725 0 1781481472 -0.2307581753 -0.0358127467 -0.0188701358 388 1311867731.5589148998 0.2104557306 0.1184060071 0.2137781382 0.0044335033 0.8548110000 969099511 0 1783148544 -0.2317740768 -0.0359893739 -0.0191202797 389 1311867731.5967359543 0.2131758630 0.1186496314 0.2137781382 0.0044349333 0.8635480000 969101425 0 1781518336 -0.2343830615 -0.0373093858 -0.0168992728 390 1311867731.6247410774 0.2138577253 0.1188937547 0.2138577253 0.0044446922 0.8798310000 969103115 0 1783148544 -0.2345660776 -0.0376809873 -0.0161796920 391 1311867731.6616659164 0.2144187242 0.1191380641 0.2144187242 0.0044454530 0.8533900000 969104997 0 1781121024 -0.2344973236 -0.0378772691 -0.0155648831 392 1311867731.6925039291 0.2152919024 0.1193833545 0.2152919024 0.0044570301 0.8461440000 969106751 0 1782878208 -0.2351060063 -0.0378183983 -0.0149268629 393 1311867731.7299311161 0.2157437205 0.1196285462 0.2157437205 0.0044539044 0.8538090000 969108633 0 1784397824 -0.2349003404 -0.0386523604 -0.0135874571 394 1311867731.7615330219 0.2141442746 0.1198684339 0.2157437205 0.0044526964 0.8514170000 969110419 0 1782636544 -0.2327193767 -0.0396778993 -0.0119067933 395 1311867731.7939310074 0.2129208297 0.1201040096 0.2157437205 0.0044489456 0.8587230000 969112205 0 1784287232 -0.2309275717 -0.0399367623 -0.0109127574 396 1311867731.8252151012 0.2109282017 0.1203333636 0.2157437205 0.0044559086 0.8819290000 969113959 0 1782276096 -0.2283632308 -0.0412145481 -0.0102357613 397 1311867731.8593230247 0.2084928006 0.1205554277 0.2157437205 0.0044529537 0.8463890000 969115777 0 1783885824 -0.2250545770 -0.0422406085 -0.0092002871 398 1311867731.8910930157 0.2049859315 0.1207675646 0.2157437205 0.0044749916 0.8548390000 969117595 0 1782001664 -0.2210883796 -0.0432849191 -0.0081644021 399 1311867731.9224479198 0.2018837631 0.1209708633 0.2157437205 0.0044737651 0.8555660000 969119381 0 1783738368 -0.2173629403 -0.0447745919 -0.0068294709 400 1311867731.9598410130 0.2001798600 0.1211688858 0.2157437205 0.0044699634 0.8477880000 969121199 0 1782149120 -0.2148898393 -0.0462212004 -0.0047271471 401 1311867731.9915709496 0.1985636503 0.1213618902 0.2157437205 0.0044685220 0.8563090000 969122985 0 1783758848 -0.2126785517 -0.0469126254 -0.0033066007 402 1311867732.0239229202 0.1959697604 0.1215474820 0.2157437205 0.0044937470 0.8935800000 969124771 0 1781895168 -0.2091804743 -0.0482085384 -0.0027118472 403 1311867732.0619950294 0.1941496134 0.1217276361 0.2157437205 0.0045019094 0.8509100000 969126653 0 1783525376 -0.2066011727 -0.0495225191 -0.0021442696 404 1311867732.0918290615 0.1926417947 0.1219031662 0.2157437205 0.0045016090 0.8489430000 969128407 0 1781366784 -0.2041528225 -0.0503554195 -0.0013683363 405 1311867732.1221950054 0.1903734803 0.1220722287 0.2157437205 0.0045244529 0.8429430000 969130193 0 1783103488 -0.2013624161 -0.0513755716 -0.0012837052 406 1311867732.1605980396 0.1894249320 0.1222381221 0.2157437205 0.0045325208 0.8553430000 969132043 0 1781514240 -0.1998939216 -0.0520735048 -0.0011525154 407 1311867732.1931400299 0.1882028282 0.1224001975 0.2157437205 0.0045465746 0.8576210000 969133861 0 1783230464 -0.1977947056 -0.0521197505 -0.0019301736 408 1311867732.2232089043 0.1861499995 0.1225564470 0.2157437205 0.0046316899 0.9044760000 969135583 0 1781641216 -0.1955966651 -0.0528850034 -0.0025783109 409 1311867732.2590498924 0.1861136407 0.1227118436 0.2157437205 0.0046735647 0.8555510000 969137433 0 1783271424 -0.1945424378 -0.0535058752 -0.0019407757 410 1311867732.2903969288 0.1852291971 0.1228643250 0.2157437205 0.0047345823 0.8553170000 969139219 0 1781260288 -0.1934245378 -0.0539111309 -0.0017323678 411 1311867732.3218240738 0.1865511239 0.1230192807 0.2157437205 0.0047304413 0.8651650000 969141005 0 1782865920 -0.1938879639 -0.0550790802 -0.0011980234 412 1311867732.3607840538 0.1877314448 0.1231763490 0.2157437205 0.0047278988 0.8702610000 969142887 0 1781260288 -0.1942150146 -0.0552624911 -0.0009471253 413 1311867732.3899528980 0.1887690276 0.1233351691 0.2157437205 0.0047224692 0.8606530000 969144609 0 1782976512 -0.1946000159 -0.0558267832 -0.0003177039 414 1311867732.4218940735 0.1899170578 0.1234959949 0.2157437205 0.0047196774 0.9163070000 969146427 0 1781387264 -0.1946641505 -0.0568356924 -0.0000781566 415 1311867732.4593050480 0.1900751144 0.1236564265 0.2157437205 0.0047179327 0.8729820000 969148277 0 1783103488 -0.1941386163 -0.0572844557 0.0002252050 416 1311867732.4918489456 0.1901304722 0.1238162199 0.2157437205 0.0047182332 0.8653270000 969150095 0 1781497856 -0.1932200342 -0.0580476671 0.0001230575 417 1311867732.5229809284 0.1904079765 0.1239759123 0.2157437205 0.0047239517 0.8652980000 969151849 0 1783144448 -0.1925624758 -0.0585535876 -0.0000243150 418 1311867732.5698928833 0.1925269961 0.1241399102 0.2157437205 0.0047190326 0.8781340000 969153859 0 1781002240 -0.1937896609 -0.0588307269 0.0005779900 419 1311867732.5926280022 0.1932201385 0.1243047794 0.2157437205 0.0047192603 0.8670770000 969155517 0 1782743040 -0.1941578239 -0.0589685105 0.0005042852 420 1311867732.6242370605 0.1925193667 0.1244671951 0.2157437205 0.0047469642 0.9028820000 969157303 0 1784373248 -0.1929263473 -0.0590839311 -0.0003932826 421 1311867732.6630299091 0.1929082572 0.1246297630 0.2157437205 0.0047482681 0.8764780000 969159185 0 1782530048 -0.1926654875 -0.0594344847 0.0001089387 422 1311867732.6922440529 0.1917865276 0.1247889022 0.2157437205 0.0047552125 0.8874150000 969160939 0 1784246272 -0.1913573146 -0.0587092265 0.0001996569 423 1311867732.7260940075 0.1900894642 0.1249432771 0.2157437205 0.0047637476 0.8978460000 969162757 0 1782636544 -0.1892360598 -0.0587738529 -0.0001707450 424 1311867732.7601239681 0.1889878660 0.1250943256 0.2157437205 0.0047588320 0.8783980000 969164543 0 1784266752 -0.1877664924 -0.0590263754 -0.0002576001 425 1311867732.7919039726 0.1890393049 0.1252447844 0.2157437205 0.0047556280 0.8918270000 969166361 0 1782403072 -0.1876913011 -0.0586154237 -0.0001748279 426 1311867732.8280360699 0.1892701834 0.1253950788 0.2157437205 0.0047513782 0.8950070000 969168179 0 1784127488 -0.1876967251 -0.0584668815 -0.0003337413 427 1311867732.8589270115 0.1892572045 0.1255446388 0.2157437205 0.0047466052 0.8994150000 969169965 0 1782538240 -0.1877132356 -0.0582847297 -0.0004941373 428 1311867732.8912909031 0.1899991482 0.1256952334 0.2157437205 0.0047421901 0.9011330000 969171751 0 1784147968 -0.1883851141 -0.0579714626 -0.0002324842 429 1311867732.9262781143 0.1913212985 0.1258482079 0.2157437205 0.0047372907 0.9122160000 969173601 0 1782157312 -0.1896059811 -0.0575737171 0.0002780073 430 1311867732.9602870941 0.1925258040 0.1260032721 0.2157437205 0.0047352805 0.9051100000 969175387 0 1783873536 -0.1904616356 -0.0582446158 0.0003682897 431 1311867732.9987640381 0.1933033019 0.1261594207 0.2157437205 0.0047315706 0.9056600000 969177301 0 1782267904 -0.1911406964 -0.0583133437 0.0006612763 432 1311867733.0276939869 0.1939544231 0.1263163536 0.2157437205 0.0047266173 0.9318920000 969179055 0 1783894016 -0.1917835176 -0.0578733198 0.0013046414 433 1311867733.0607628822 0.1953619421 0.1264758122 0.2157437205 0.0047364715 0.9093030000 969180841 0 1781886976 -0.1928823292 -0.0586937889 0.0013719500 434 1311867733.0977020264 0.1975729465 0.1266396305 0.2157437205 0.0047376491 0.9066210000 969182691 0 1783611392 -0.1949424446 -0.0588221513 0.0017032737 435 1311867733.1263020039 0.1979558170 0.1268035757 0.2157437205 0.0047353445 0.9176480000 969184413 0 1782005760 -0.1954399794 -0.0580635332 0.0019768402 436 1311867733.1625030041 0.2001678646 0.1269718424 0.2157437205 0.0047402626 0.9059230000 969186263 0 1783611392 -0.1972986013 -0.0590977930 0.0017611755 437 1311867733.1926651001 0.2025841773 0.1271448684 0.2157437205 0.0047376358 0.9083350000 969188017 0 1782005760 -0.1996385455 -0.0593931265 0.0018824340 438 1311867733.2259631157 0.2045444548 0.1273215798 0.2157437205 0.0047333054 0.8968320000 969189835 0 1783738368 -0.2014162987 -0.0589856766 0.0022469312 439 1311867733.2618060112 0.2066631317 0.1275023122 0.2157437205 0.0047370457 0.9233050000 969191685 0 1782149120 -0.2032848597 -0.0590125881 0.0021679255 440 1311867733.2919199467 0.2079535723 0.1276851560 0.2157437205 0.0047358714 0.9130080000 969193407 0 1783758848 -0.2044395804 -0.0590338558 0.0018524678 441 1311867733.3300418854 0.2100832760 0.1278719998 0.2157437205 0.0047435457 0.9163990000 969195289 0 1781751808 -0.2062709033 -0.0590170622 0.0019158237 442 1311867733.3602790833 0.2120636553 0.1280624787 0.2157437205 0.0047476219 0.9085900000 969197075 0 1783373824 -0.2078564763 -0.0594720133 0.0014918149 443 1311867733.3923840523 0.2137930393 0.1282560014 0.2157437205 0.0047430121 0.9205740000 969198861 0 1781747712 -0.2091644108 -0.0594908595 0.0010471791 444 1311867733.4289550781 0.2166073173 0.1284549908 0.2166073173 0.0047429486 0.9623660000 969200711 0 1783631872 -0.2117010653 -0.0589368455 0.0009219646 445 1311867733.4588150978 0.2193748951 0.1286593052 0.2193748951 0.0047384113 0.9240280000 969202401 0 1781874688 -0.2143417299 -0.0587699041 0.0008117780 446 1311867733.4956119061 0.2223084122 0.1288692808 0.2223084122 0.0047349913 0.9166080000 969204187 0 1783652352 -0.2170934081 -0.0586798489 0.0008023828 447 1311867733.5290400982 0.2236981243 0.1290814259 0.2236981243 0.0047403404 0.9206050000 969206005 0 1781641216 -0.2184267044 -0.0580063462 0.0007504746 448 1311867733.5630290508 0.2259411961 0.1292976307 0.2259411961 0.0047434449 0.9229410000 969207823 0 1783357440 -0.2204275876 -0.0578128956 0.0003278814 449 1311867733.5922229290 0.2284467071 0.1295184527 0.2284467071 0.0047395964 0.9255190000 969209545 0 1781768192 -0.2226013243 -0.0584280752 0.0000589639 450 1311867733.6283020973 0.2305153906 0.1297428903 0.2305153906 0.0047366814 0.9389230000 969211395 0 1783525376 -0.2243782431 -0.0585901253 0.0002150200 451 1311867733.6601879597 0.2333775908 0.1299726790 0.2333775908 0.0047336195 0.9328790000 969213181 0 1781514240 -0.2270347923 -0.0587049052 0.0006363391 452 1311867733.6917510033 0.2361323982 0.1302075457 0.2361323982 0.0047318670 0.9287420000 969214967 0 1783230464 -0.2295069993 -0.0587727763 0.0004061162 453 1311867733.7288239002 0.2386125326 0.1304468503 0.2386125326 0.0047315358 0.9340170000 969216817 0 1781641216 -0.2315346450 -0.0587273389 0.0002470762 454 1311867733.7597820759 0.2421016246 0.1306927859 0.2421016246 0.0047280783 0.9315530000 969218539 0 1783250944 -0.2346403450 -0.0590016358 0.0004262477 455 1311867733.7924160957 0.2446386367 0.1309432163 0.2446386367 0.0047615782 0.9410900000 969220325 0 1781239808 -0.2368226796 -0.0590719432 0.0004782304 456 1311867733.8282589912 0.2482095063 0.1312003793 0.2482095063 0.0047621420 0.9346850000 969222175 0 1782976512 -0.2395475805 -0.0598566458 0.0001574420 457 1311867733.8608579636 0.2507681549 0.1314620155 0.2507681549 0.0047604383 0.9298530000 969223897 0 1781497856 -0.2417507470 -0.0596919246 -0.0000708438 458 1311867733.8918149471 0.2529928684 0.1317273667 0.2529928684 0.0047554667 0.9231260000 969225619 0 1783103488 -0.2436253726 -0.0593627580 -0.0003225394 459 1311867733.9289460182 0.2568514347 0.1319999682 0.2568514347 0.0047524150 0.9349520000 969227469 0 1781497856 -0.2468948364 -0.0596862808 -0.0005262383 460 1311867733.9595899582 0.2593109906 0.1322767313 0.2593109906 0.0047608019 0.9351540000 969229255 0 1783103488 -0.2490808666 -0.0597334541 -0.0006121211 461 1311867733.9941790104 0.2621932924 0.1325585460 0.2621932924 0.0047719767 0.9319790000 969231073 0 1781243904 -0.2510931790 -0.0599761680 -0.0003814399 462 1311867734.0275731087 0.2643994391 0.1328439159 0.2643994391 0.0047731501 0.9559970000 969232923 0 1782849536 -0.2531717122 -0.0603169762 -0.0003726073 463 1311867734.0599920750 0.2657536864 0.1331309780 0.2657536864 0.0047682692 0.9192300000 969234677 0 1784500224 -0.2543085217 -0.0598261729 -0.0003654994 464 1311867734.0956780910 0.2675538063 0.1334206824 0.2675538063 0.0047636132 0.9264340000 969236527 0 1782775808 -0.2558662593 -0.0594821908 -0.0003443063 465 1311867734.1274170876 0.2704016268 0.1337152650 0.2704016268 0.0047599855 0.9237180000 969238345 0 1784254464 -0.2582455873 -0.0604125448 -0.0007272288 466 1311867734.1618878841 0.2723311782 0.1340127241 0.2723311782 0.0047567865 0.9294850000 969240131 0 1782521856 -0.2598320842 -0.0603306219 -0.0008777453 467 1311867734.1942350864 0.2744479179 0.1343134418 0.2744479179 0.0047530941 0.9222920000 969241949 0 1784016896 -0.2615884840 -0.0599588417 -0.0008417405 468 1311867734.2291829586 0.2763852775 0.1346170141 0.2763852775 0.0047563847 0.9239460000 969243735 0 1782259712 -0.2631087601 -0.0607676841 -0.0011843890 469 1311867734.2607750893 0.2784819007 0.1349237623 0.2784819007 0.0047520048 0.9166940000 969245521 0 1783738368 -0.2648725212 -0.0608694218 -0.0011523664 470 1311867734.2941219807 0.2805909216 0.1352336924 0.2805909216 0.0047476085 0.9166190000 969247307 0 1781878784 -0.2668351233 -0.0603094921 -0.0009194667 471 1311867734.3263280392 0.2826925218 0.1355467685 0.2826925218 0.0047476118 0.9181600000 969249093 0 1783484416 -0.2686539292 -0.0604934692 -0.0007466506 472 1311867734.3610401154 0.2839189768 0.1358611164 0.2839189768 0.0047447597 0.9173650000 969250911 0 1781878784 -0.2696509361 -0.0603782050 -0.0006269570 473 1311867734.3941841125 0.2852207720 0.1361768873 0.2852207720 0.0047475653 0.9168650000 969252729 0 1783484416 -0.2709229589 -0.0594950542 -0.0001938790 474 1311867734.4276480675 0.2872276306 0.1364955598 0.2872276306 0.0047434317 0.9173310000 969254547 0 1781878784 -0.2726753056 -0.0600379519 0.0000294633 475 1311867734.4586091042 0.2884671688 0.1368155000 0.2884671688 0.0047407285 0.9160070000 969256301 0 1783484416 -0.2736604214 -0.0608030781 0.0001815706 476 1311867734.4938759804 0.2897193730 0.1371367266 0.2897193730 0.0047360653 0.9246320000 969258151 0 1781895168 -0.2746953368 -0.0602509081 0.0006466285 477 1311867734.5300569534 0.2902677655 0.1374577561 0.2902677655 0.0047325549 0.9154400000 969260001 0 1783504896 -0.2749862671 -0.0602009483 0.0009699593 478 1311867734.5595300198 0.2923333049 0.1377817635 0.2923333049 0.0047368313 0.9119510000 969261723 0 1781493760 -0.2765595317 -0.0605916753 0.0012396611 479 1311867734.5953910351 0.2925215662 0.1381048111 0.2925215662 0.0047331823 0.9147670000 969263541 0 1783230464 -0.2769643366 -0.0604365282 0.0016353466 480 1311867734.6285231113 0.2930094898 0.1384275292 0.2930094898 0.0047300844 0.9476420000 969265359 0 1781641216 -0.2768799663 -0.0608462542 0.0016740989 481 1311867734.6593229771 0.2935515642 0.1387500324 0.2935515642 0.0047252020 0.9143640000 969267113 0 1783250944 -0.2773304284 -0.0614937022 0.0017596558 482 1311867734.6947479248 0.2939088345 0.1390719386 0.2939088345 0.0047210129 0.9275860000 969268931 0 1781260288 -0.2777636349 -0.0618267432 0.0017914809 483 1311867734.7310240269 0.2955059707 0.1393958186 0.2955059707 0.0047207604 0.9219790000 969270813 0 1782976512 -0.2790081501 -0.0616846122 0.0019306430 484 1311867734.7607629299 0.2949008346 0.1397171099 0.2955059707 0.0047169054 0.9227320000 969272535 0 1781387264 -0.2779696286 -0.0613344237 0.0017258916 485 1311867734.7976419926 0.2956910729 0.1400387057 0.2956910729 0.0047126927 0.9148570000 969274417 0 1782996992 -0.2785473764 -0.0614636764 0.0018665792 486 1311867734.8298120499 0.2968606949 0.1403613847 0.2968606949 0.0047094349 0.9160680000 969276203 0 1784500224 -0.2794530094 -0.0612337030 0.0021744324 487 1311867734.8645250797 0.2974860370 0.1406840226 0.2974860370 0.0047047389 0.9263060000 969278021 0 1782636544 -0.2798547149 -0.0608664453 0.0027095228 488 1311867734.8943901062 0.2979638875 0.1410063174 0.2979638875 0.0047030934 0.9133930000 969279807 0 1784283136 -0.2799790800 -0.0613633581 0.0025775044 489 1311867734.9263660908 0.2987370193 0.1413288751 0.2987370193 0.0046984671 0.9193560000 969281561 0 1782403072 -0.2804705799 -0.0613445267 0.0028234143 490 1311867734.9631719589 0.3006736040 0.1416540684 0.3006736040 0.0046982631 0.9120700000 969283283 0 1784012800 -0.2818460763 -0.0614608340 0.0028223705 491 1311867734.9948470592 0.3009118438 0.1419784223 0.3009118438 0.0047003607 0.9184930000 969285069 0 1782022144 -0.2823358774 -0.0620390438 0.0024454577 492 1311867735.0292239189 0.3013143539 0.1423022759 0.3013143539 0.0047003781 0.9165210000 969286951 0 1783738368 -0.2823860347 -0.0618905500 0.0023624450 493 1311867735.0596508980 0.3021837473 0.1426265791 0.3021837473 0.0046959643 0.9190570000 969288641 0 1782149120 -0.2833973765 -0.0617325827 0.0024778296 494 1311867735.0952830315 0.3029241562 0.1429510681 0.3029241562 0.0046930420 0.9104640000 969290491 0 1783758848 -0.2840726376 -0.0622250661 0.0024621866 495 1311867735.1313030720 0.3047416210 0.1432779177 0.3047416210 0.0046934427 0.9180630000 969292341 0 1781874688 -0.2858084738 -0.0623384640 0.0029556577 496 1311867735.1603751183 0.3056377172 0.1436052560 0.3056377172 0.0046887494 0.9039230000 969294063 0 1783525376 -0.2865999937 -0.0623965859 0.0031843446 497 1311867735.1994349957 0.3061309159 0.1439322694 0.3061309159 0.0046877489 0.9078920000 969295945 0 1781522432 -0.2868754864 -0.0628618747 0.0031370362 498 1311867735.2263538837 0.3054891229 0.1442566807 0.3061309159 0.0046851309 0.9321310000 969297699 0 1783152640 -0.2862087488 -0.0622771271 0.0034420842 499 1311867735.2655019760 0.3053094447 0.1445794318 0.3061309159 0.0046813476 0.9263260000 969299549 0 1781141504 -0.2858478725 -0.0621266328 0.0039698873 500 1311867735.2961549759 0.3068508804 0.1449039747 0.3068508804 0.0046840676 0.9120260000 969301335 0 1782857728 -0.2872972786 -0.0626337305 0.0044344491 501 1311867735.3321089745 0.3068394661 0.1452271992 0.3068508804 0.0046839047 0.9059960000 969303185 0 1784508416 -0.2872135639 -0.0622223653 0.0048591257 502 1311867735.3666970730 0.3070926964 0.1455496404 0.3070926964 0.0046881796 0.9138980000 969304939 0 1782894592 -0.2873103917 -0.0620965958 0.0051439349 503 1311867735.3943350315 0.3082518876 0.1458731041 0.3082518876 0.0046967375 0.9136280000 969306629 0 1781239808 -0.2882749438 -0.0621981509 0.0055024521 504 1311867735.4322299957 0.3093332648 0.1461974299 0.3093332648 0.0046952436 0.9045830000 969308543 0 1782870016 -0.2892449498 -0.0621913858 0.0059365104 505 1311867735.4628560543 0.3117758632 0.1465253079 0.3117758632 0.0047060414 0.9012390000 969310297 0 1784520704 -0.2908419669 -0.0629886761 0.0063860686 506 1311867735.4973869324 0.3119176328 0.1468521702 0.3119176328 0.0047110719 0.9074650000 969312147 0 1782509568 -0.2912598252 -0.0633488074 0.0068453052 507 1311867735.5293200016 0.3120859563 0.1471780751 0.3120859563 0.0047071993 0.9047090000 969313901 0 1784373248 -0.2912050486 -0.0633567423 0.0073073041 508 1311867735.5632629395 0.3121396601 0.1475028027 0.3121396601 0.0047030634 0.9077070000 969315751 0 1782784000 -0.2910252213 -0.0635649785 0.0075398553 509 1311867735.5976569653 0.3131369650 0.1478282136 0.3131369650 0.0047000359 0.9070820000 969317569 0 1784393728 -0.2917367816 -0.0641681254 0.0079038376 510 1311867735.6363260746 0.3132971227 0.1481526624 0.3132971227 0.0046987081 0.9516950000 969319419 0 1782382592 -0.2916849256 -0.0643977597 0.0080443462 511 1311867735.6626520157 0.3144191206 0.1484780371 0.3144191206 0.0046953472 0.9120480000 969321141 0 1784139776 -0.2925181389 -0.0652221218 0.0079495730 512 1311867735.6952130795 0.3156219125 0.1488044900 0.3156219125 0.0046915919 0.9051030000 969322927 0 1782145024 -0.2935133278 -0.0663239583 0.0077828467 513 1311867735.7291250229 0.3163690567 0.1491311266 0.3163690567 0.0046898230 0.8925610000 969324745 0 1783885824 -0.2940788567 -0.0662911385 0.0076372824 514 1311867735.7631659508 0.3164809048 0.1494567098 0.3164809048 0.0046863442 0.8957930000 969410563 0 1782018048 -0.2941415608 -0.0660176873 0.0076438934 515 1311867735.7963778973 0.3173443377 0.1497827052 0.3173443377 0.0046842404 0.8853060000 969412349 0 1783758848 -0.2947166860 -0.0664606094 0.0076293349 516 1311867735.8277759552 0.3185681403 0.1501098088 0.3185681403 0.0046891629 0.8910800000 969414103 0 1782018048 -0.2958080173 -0.0658694431 0.0078155706 517 1311867735.8638889790 0.3186914623 0.1504358855 0.3186914623 0.0046854715 0.8871130000 969415857 0 1783664640 -0.2958704531 -0.0651765242 0.0082992921 518 1311867735.8951849937 0.3188022375 0.1507609170 0.3188022375 0.0046811785 0.8841150000 969417643 0 1782145024 -0.2959961593 -0.0647166967 0.0086199110 519 1311867735.9322230816 0.3194994628 0.1510860395 0.3194994628 0.0046780891 0.8839290000 969419525 0 1783885824 -0.2966235578 -0.0648093149 0.0092317546 520 1311867735.9623689651 0.3198485672 0.1514105828 0.3198485672 0.0046749540 0.8806710000 969421279 0 1782128640 -0.2972153425 -0.0642356724 0.0098699825 521 1311867735.9945859909 0.3198701441 0.1517339217 0.3198701441 0.0046714979 0.8830880000 969423033 0 1783865344 -0.2973461151 -0.0640995726 0.0102570262 522 1311867736.0290079117 0.3202684224 0.1520567847 0.3202684224 0.0046687949 0.9162560000 969424883 0 1782255616 -0.2978380620 -0.0639951080 0.0107964147 523 1311867736.0642199516 0.3202669919 0.1523784103 0.3202684224 0.0046665914 0.8756080000 969426733 0 1783885824 -0.2978568077 -0.0639117435 0.0110222381 524 1311867736.0946779251 0.3212506771 0.1527006857 0.3212506771 0.0046624593 0.8744160000 969428455 0 1782001664 -0.2989830375 -0.0636712313 0.0115842680 525 1311867736.1299190521 0.3219184577 0.1530230052 0.3219184577 0.0046695689 0.8822320000 969430305 0 1783631872 -0.2997795045 -0.0635114759 0.0118479030 526 1311867736.1631360054 0.3213270307 0.1533429749 0.3219184577 0.0046663415 0.8696810000 969432155 0 1781747712 -0.2996134162 -0.0634345114 0.0118367663 527 1311867736.1942429543 0.3222474754 0.1536634768 0.3222474754 0.0046681860 0.8617060000 969433877 0 1783484416 -0.3006369472 -0.0634335876 0.0118908808 528 1311867736.2298679352 0.3229935169 0.1539841776 0.3229935169 0.0046679525 0.8639520000 969435727 0 1781895168 -0.3019702435 -0.0637221336 0.0122316051 529 1311867736.2633900642 0.3241677284 0.1543058856 0.3241677284 0.0046688815 0.8636630000 969437545 0 1783504896 -0.3033014238 -0.0640169084 0.0125118298 530 1311867736.2995250225 0.3245831132 0.1546271634 0.3245831132 0.0046669216 0.8680780000 969439395 0 1781493760 -0.3038823605 -0.0644148737 0.0125327874 531 1311867736.3304500580 0.3261723518 0.1549502240 0.3261723518 0.0046633527 0.8729500000 969441117 0 1783123968 -0.3056725562 -0.0644131452 0.0131515153 532 1311867736.3637149334 0.3281116784 0.1552757155 0.3281116784 0.0046610198 0.8660310000 969442935 0 1781239808 -0.3076369166 -0.0649874732 0.0134246917 533 1311867736.3943159580 0.3298446536 0.1556032369 0.3298446536 0.0046582309 0.8586980000 969444657 0 1782870016 -0.3092720807 -0.0659438297 0.0133144557 534 1311867736.4313519001 0.3307558894 0.1559312382 0.3307558894 0.0046662494 0.8941190000 969446571 0 1784500224 -0.3100748956 -0.0658951998 0.0135220923 535 1311867736.4625089169 0.3325366378 0.1562613417 0.3325366378 0.0046649062 0.8650140000 969448357 0 1782644736 -0.3120050132 -0.0664952397 0.0137480022 536 1311867736.4987530708 0.3340300024 0.1565929997 0.3340300024 0.0046621034 0.8630090000 969450175 0 1784401920 -0.3133398890 -0.0672618002 0.0137199005 537 1311867736.5321619511 0.3353838325 0.1569259435 0.3353838325 0.0046637612 0.8900580000 969451993 0 1782407168 -0.3146187067 -0.0671002045 0.0140443053 538 1311867736.5634689331 0.3354829848 0.1572578339 0.3354829848 0.0046612548 0.8655850000 969453779 0 1784016896 -0.3148307502 -0.0671932623 0.0141030643 539 1311867736.5958600044 0.3377561569 0.1575927102 0.3377561569 0.0046576262 0.8613900000 969455565 0 1782136832 -0.3171251714 -0.0686413124 0.0141859464 540 1311867736.6320459843 0.3391253352 0.1579288817 0.3391253352 0.0046643535 0.8855670000 969457415 0 1783873536 -0.3181858957 -0.0686938241 0.0144925676 541 1311867736.6635379791 0.3392283022 0.1582640008 0.3392283022 0.0046742253 0.8566500000 969459201 0 1782263808 -0.3187066317 -0.0691819414 0.0144449752 542 1311867736.6945500374 0.3421916664 0.1586033507 0.3421916664 0.0046789982 0.8609480000 969460923 0 1783881728 -0.3215223253 -0.0708554238 0.0141931027 543 1311867736.7332150936 0.3440412581 0.1589448570 0.3440412581 0.0046751179 0.8613170000 969462805 0 1782001664 -0.3233183622 -0.0717018470 0.0141181359 544 1311867736.7636179924 0.3451322019 0.1592871132 0.3451322019 0.0046748734 0.8546160000 969464591 0 1783631872 -0.3237629533 -0.0719960183 0.0143301385 545 1311867736.7952749729 0.3487523198 0.1596347557 0.3487523198 0.0046784479 0.8711370000 969466345 0 1781641216 -0.3275711834 -0.0721175522 0.0143906809 546 1311867736.8325269222 0.3542942107 0.1599912749 0.3542942107 0.0046872183 0.8707080000 969468195 0 1783357440 -0.3329154551 -0.0717264861 0.0147563266 547 1311867736.8640279770 0.3561028838 0.1603497970 0.3561028838 0.0046855715 0.8598240000 969470013 0 1781768192 -0.3344803751 -0.0719717070 0.0147633068 548 1311867736.8945000172 0.3578103185 0.1607101264 0.3578103185 0.0046836670 0.8604190000 969471735 0 1783377920 -0.3358277082 -0.0730296895 0.0152207771 549 1311867736.9362800121 0.3611197770 0.1610751713 0.3611197770 0.0046866479 0.8591260000 969473681 0 1781387264 -0.3387209773 -0.0732209310 0.0153967217 550 1311867736.9632000923 0.3648296297 0.1614456340 0.3648296297 0.0046832576 0.8542010000 969475403 0 1783103488 -0.3424683809 -0.0727867261 0.0162090827 551 1311867736.9954400063 0.3663312495 0.1618174772 0.3663312495 0.0046815882 0.8564980000 969477189 0 1781497856 -0.3436749876 -0.0734359622 0.0167384855 552 1311867737.0307478905 0.3674321175 0.1621899675 0.3674321175 0.0046779826 0.8827620000 969479007 0 1783103488 -0.3446081579 -0.0745823532 0.0168211460 553 1311867737.0629029274 0.3655460179 0.1625577000 0.3674321175 0.0046750304 0.8616280000 969480825 0 1781387264 -0.3425886631 -0.0743259564 0.0173536614 554 1311867737.0977239609 0.3659793437 0.1629248870 0.3674321175 0.0046722223 0.8576830000 969482643 0 1783103488 -0.3429731429 -0.0747064427 0.0172695313 555 1311867737.1300530434 0.3660509586 0.1632908800 0.3674321175 0.0046682448 0.8549880000 969484397 0 1781497856 -0.3429845572 -0.0751067922 0.0172249489 556 1311867737.1655049324 0.3650071621 0.1636536790 0.3674321175 0.0046643117 0.8519870000 969486247 0 1783123968 -0.3419195116 -0.0744932219 0.0172431376 557 1311867737.1952710152 0.3648221195 0.1640148432 0.3674321175 0.0046601927 0.8530900000 969488001 0 1781112832 -0.3415535688 -0.0744531602 0.0171406828 558 1311867737.2333149910 0.3656338751 0.1643761676 0.3674321175 0.0046562321 0.8984960000 969489915 0 1782849536 -0.3422252834 -0.0747358650 0.0172065813 559 1311867737.2693018913 0.3645573258 0.1647342735 0.3674321175 0.0046598875 0.8607350000 969491733 0 1784516608 -0.3405090868 -0.0743941516 0.0171761941 560 1311867737.2957379818 0.3652920723 0.1650924124 0.3674321175 0.0046563530 0.8560950000 969493423 0 1782910976 -0.3410311043 -0.0743549690 0.0175902676 561 1311867737.3316531181 0.3657300174 0.1654500552 0.3674321175 0.0046524679 0.8545360000 969495305 0 1784520704 -0.3412572443 -0.0744557306 0.0177632906 562 1311867737.3659460545 0.3654118180 0.1658058590 0.3674321175 0.0046483643 0.8594560000 969497091 0 1782513664 -0.3410914540 -0.0740463957 0.0180359595 563 1311867737.3967239857 0.3665848970 0.1661624825 0.3674321175 0.0046465330 0.8553730000 969498877 0 1784246272 -0.3420185149 -0.0742514729 0.0185038671 564 1311867737.4355359077 0.3673719764 0.1665192370 0.3674321175 0.0046433934 0.8985680000 969500759 0 1782640640 -0.3426848650 -0.0742937624 0.0190501064 565 1311867737.4691100121 0.3680267334 0.1668758874 0.3680267334 0.0046393027 0.8571670000 969502577 0 1784246272 -0.3431982398 -0.0744198486 0.0193973854 566 1311867737.4959459305 0.3683327734 0.1672318183 0.3683327734 0.0046352533 0.8575030000 969504267 0 1782386688 -0.3435775340 -0.0744952708 0.0199981891 567 1311867737.5353999138 0.3690067232 0.1675876823 0.3690067232 0.0046317609 0.8600880000 969506181 0 1783865344 -0.3439925909 -0.0747795254 0.0203691553 568 1311867737.5654399395 0.3686143458 0.1679416025 0.3690067232 0.0046282685 0.8546710000 969507903 0 1782132736 -0.3430500329 -0.0748638585 0.0206433702 569 1311867737.5958089828 0.3691155910 0.1682951596 0.3691155910 0.0046256973 0.8626080000 969509689 0 1783611392 -0.3432172835 -0.0750726983 0.0211904459 570 1311867737.6330978870 0.3705064356 0.1686499162 0.3705064356 0.0046225171 0.8686100000 969511571 0 1781751808 -0.3443022966 -0.0752203166 0.0216633677 571 1311867737.6624519825 0.3720081449 0.1690060602 0.3720081449 0.0046193798 0.8557670000 969513325 0 1783357440 -0.3455042243 -0.0760815218 0.0221669450 572 1311867737.7032339573 0.3730270863 0.1693627404 0.3730270863 0.0046167467 0.8573270000 969515207 0 1781387264 -0.3461468220 -0.0770814493 0.0223720837 573 1311867737.7314720154 0.3735996783 0.1697191748 0.3735996783 0.0046130328 0.8557400000 969516929 0 1782976512 -0.3463739455 -0.0775023699 0.0227795765 574 1311867737.7658560276 0.3737444878 0.1700746196 0.3737444878 0.0046091747 0.8569910000 969518747 0 1781116928 -0.3462515473 -0.0776053220 0.0229789689 575 1311867737.8011269569 0.3739722669 0.1704292242 0.3739722669 0.0046061056 0.8636500000 969520597 0 1782603776 -0.3461938798 -0.0775199682 0.0234305263 576 1311867737.8323190212 0.3736862242 0.1707821009 0.3739722669 0.0046023786 0.8905680000 969522383 0 1784381440 -0.3457041681 -0.0775931850 0.0238220878 577 1311867737.8633110523 0.3748909831 0.1711358425 0.3748909831 0.0046048535 0.8604770000 969524137 0 1782505472 -0.3463481069 -0.0773663595 0.0244116560 578 1311867737.9004418850 0.3749772012 0.1714885092 0.3749772012 0.0046013209 0.8568370000 969525955 0 1784000512 -0.3459319472 -0.0780464709 0.0250860527 579 1311867737.9305500984 0.3753897846 0.1718406703 0.3753897846 0.0046036716 0.8584720000 969527709 0 1782124544 -0.3459851444 -0.0783389583 0.0256638080 580 1311867737.9630560875 0.3766497970 0.1721937895 0.3766497970 0.0046005960 0.8600390000 969529527 0 1783619584 -0.3468956053 -0.0783866420 0.0262768734 581 1311867737.9996941090 0.3779206276 0.1725478804 0.3779206276 0.0045985139 0.8657280000 969531377 0 1781760000 -0.3477167487 -0.0789107457 0.0268387012 582 1311867738.0315399170 0.3787911534 0.1729022503 0.3787911534 0.0045957531 0.9008450000 969533163 0 1783238656 -0.3481928408 -0.0787132382 0.0277500767 583 1311867738.0629770756 0.3775362372 0.1732532520 0.3787911534 0.0045919801 0.8617050000 969534949 0 1781370880 -0.3463530838 -0.0787194893 0.0286882371 584 1311867738.0998299122 0.3780075312 0.1736038587 0.3787911534 0.0045891539 0.8581470000 969536767 0 1782849536 -0.3462327123 -0.0789024532 0.0293400083 585 1311867738.1308510303 0.3775158823 0.1739524262 0.3787911534 0.0045871638 0.8599270000 969538521 0 1780989952 -0.3451203704 -0.0795479193 0.0302280951 586 1311867738.1635079384 0.3778152764 0.1743003150 0.3787911534 0.0045845500 0.8616730000 969540339 0 1782468608 -0.3449201882 -0.0802832991 0.0307813212 587 1311867738.1992070675 0.3790990114 0.1746492055 0.3790990114 0.0045818612 0.8633450000 969542157 0 1784246272 -0.3455494046 -0.0808195025 0.0315657444 588 1311867738.2306089401 0.3797884881 0.1749980818 0.3797884881 0.0045824597 0.8608150000 969543943 0 1782276096 -0.3458796144 -0.0817765594 0.0318910219 589 1311867738.2632689476 0.3805049062 0.1753469898 0.3805049062 0.0045842958 0.8642750000 969545761 0 1783865344 -0.3460721672 -0.0827547014 0.0319475681 590 1311867738.3008689880 0.3814370036 0.1756962950 0.3814370036 0.0045813696 0.8631800000 969547611 0 1782009856 -0.3463983834 -0.0836600587 0.0322517529 591 1311867738.3339769840 0.3833388984 0.1760476361 0.3833388984 0.0045806794 0.8617810000 969549397 0 1783484416 -0.3478125036 -0.0843270496 0.0323638283 592 1311867738.3651630878 0.3853533268 0.1764011930 0.3853533268 0.0045771140 0.8802010000 969551183 0 1781624832 -0.3496307433 -0.0846987888 0.0324785784 593 1311867738.3995900154 0.3861715496 0.1767549373 0.3861715496 0.0045740278 0.8739890000 969553033 0 1783119872 -0.3499733508 -0.0846114010 0.0326073803 594 1311867738.4334011078 0.3863626719 0.1771078122 0.3863626719 0.0045705502 0.8992820000 969554851 0 1781370880 -0.3500178456 -0.0844312906 0.0326425061 595 1311867738.4643430710 0.3880359232 0.1774623133 0.3880359232 0.0045671079 0.8788990000 969556605 0 1782849536 -0.3508671522 -0.0848585591 0.0326974653 596 1311867738.5000250340 0.3881278634 0.1778157790 0.3881278634 0.0045638344 0.8675760000 969558455 0 1784500224 -0.3503699303 -0.0845740661 0.0328330956 597 1311867738.5332009792 0.3880221546 0.1781678834 0.3881278634 0.0045603788 0.8708850000 969560241 0 1782640640 -0.3495293558 -0.0839694515 0.0331455246 598 1311867738.5634350777 0.3884684741 0.1785195567 0.3884684741 0.0045579107 0.8734450000 969562027 0 1784266752 -0.3493169546 -0.0843629539 0.0333518907 599 1311867738.6022439003 0.3882425725 0.1788696786 0.3884684741 0.0045557464 0.8812470000 969563909 0 1782259712 -0.3481090963 -0.0847769827 0.0334104821 600 1311867738.6328980923 0.3885417879 0.1792191321 0.3885417879 0.0045523119 0.8982000000 969565663 0 1783885824 -0.3474784493 -0.0847934559 0.0335365348 601 1311867738.6628730297 0.3892583847 0.1795686150 0.3892583847 0.0045499888 0.8779820000 969567449 0 1782005760 -0.3473362327 -0.0850998014 0.0336923599 602 1311867738.6996099949 0.3901827037 0.1799184723 0.3901827037 0.0045499036 0.8645620000 969569299 0 1783484416 -0.3472927809 -0.0857419446 0.0336686857 603 1311867738.7314729691 0.3903295398 0.1802674127 0.3903295398 0.0045524938 0.8670450000 969571085 0 1781641216 -0.3466325998 -0.0858672708 0.0338272452 604 1311867738.7626600266 0.3913326263 0.1806168584 0.3913326263 0.0045527379 0.8682930000 969572839 0 1783230464 -0.3467468619 -0.0855212957 0.0340112485 605 1311867738.8032259941 0.3926621079 0.1809673465 0.3926621079 0.0045576959 0.8759170000 969574753 0 1781370880 -0.3470661640 -0.0857134387 0.0342337415 606 1311867738.8306779861 0.3925401568 0.1813164765 0.3926621079 0.0045567069 0.8698560000 969576475 0 1782976512 -0.3462897241 -0.0860325024 0.0342644006 607 1311867738.8639259338 0.3910887539 0.1816620651 0.3926621079 0.0045529532 0.8701570000 969578293 0 1781133312 -0.3441202044 -0.0858216658 0.0341927372 608 1311867738.9000120163 0.3924043477 0.1820086807 0.3926621079 0.0045558684 0.8705120000 969580143 0 1782722560 -0.3447012007 -0.0857361853 0.0342953131 609 1311867738.9307610989 0.3936204612 0.1823561549 0.3936204612 0.0045606869 0.8729700000 969581897 0 1784373248 -0.3453595042 -0.0858738422 0.0346689075 610 1311867738.9664750099 0.3938429952 0.1827028546 0.3938429952 0.0045570513 0.8787180000 969583747 0 1782513664 -0.3451001644 -0.0856914371 0.0348627344 611 1311867738.9989941120 0.3949593008 0.1830502465 0.3949593008 0.0045538322 0.8605020000 969585565 0 1784119296 -0.3457419872 -0.0855995566 0.0348751470 612 1311867739.0329539776 0.3943256140 0.1833954677 0.3949593008 0.0045526789 0.9009580000 969587383 0 1782259712 -0.3445965052 -0.0865219235 0.0348811224 613 1311867739.0664470196 0.3927587867 0.1837370066 0.3949593008 0.0045541150 0.8664320000 969589169 0 1783865344 -0.3425199986 -0.0867706984 0.0349120311 614 1311867739.0997900963 0.3918793797 0.1840760007 0.3949593008 0.0045506456 0.8637290000 969590891 0 1782013952 -0.3412738144 -0.0865411982 0.0349216238 615 1311867739.1321549416 0.3914321065 0.1844131651 0.3949593008 0.0045490580 0.8694930000 969592645 0 1783619584 -0.3405188918 -0.0865961611 0.0351035856 616 1311867739.1687150002 0.3914657831 0.1847492894 0.3949593008 0.0045457877 0.8614520000 969594495 0 1781776384 -0.3404834270 -0.0863107219 0.0353834070 617 1311867739.1999289989 0.3920954764 0.1850853448 0.3949593008 0.0045433643 0.8529010000 969596249 0 1783492608 -0.3411265016 -0.0861194879 0.0358444527 618 1311867739.2313010693 0.3914103806 0.1854192041 0.3949593008 0.0045406371 0.8997910000 969598003 0 1781882880 -0.3403858244 -0.0864137039 0.0359748490 619 1311867739.2672259808 0.3909056783 0.1857511693 0.3949593008 0.0045382280 0.8530750000 969599885 0 1783504896 -0.3400212228 -0.0869103894 0.0361524522 620 1311867739.2996931076 0.3911289871 0.1860824239 0.3949593008 0.0045395110 0.8577930000 969601671 0 1781493760 -0.3403808177 -0.0873214602 0.0364098512 621 1311867739.3319859505 0.3903210759 0.1864113106 0.3949593008 0.0045365316 0.8560100000 969603457 0 1783230464 -0.3395618200 -0.0873224959 0.0367060713 622 1311867739.3670029640 0.3906327188 0.1867396409 0.3949593008 0.0045354698 0.8566630000 969605275 0 1781637120 -0.3401493728 -0.0870537981 0.0368860103 623 1311867739.3990058899 0.3893414736 0.1870648444 0.3949593008 0.0045324319 0.8485670000 969607093 0 1783267328 -0.3390646875 -0.0870804936 0.0371572785 624 1311867739.4311320782 0.3879042566 0.1873867025 0.3949593008 0.0045301102 0.8533760000 969608847 0 1781616640 -0.3376116157 -0.0870128199 0.0374197587 625 1311867739.4668490887 0.3893280923 0.1877098087 0.3949593008 0.0045267834 0.8552230000 969610697 0 1783394304 -0.3390608430 -0.0871663466 0.0378950350 626 1311867739.4988598824 0.3904080987 0.1880336079 0.3949593008 0.0045341214 0.8499730000 969612483 0 1781743616 -0.3401091993 -0.0875806287 0.0383994617 627 1311867739.5316400528 0.3897924423 0.1883553923 0.3949593008 0.0045307301 0.8538330000 969614237 0 1783390208 -0.3392978311 -0.0873639137 0.0388117507 628 1311867739.5670249462 0.3908993304 0.1886779145 0.3949593008 0.0045281179 0.8541820000 969616087 0 1781870592 -0.3404047787 -0.0870750174 0.0396576859 629 1311867739.5990490913 0.3919452429 0.1890010740 0.3949593008 0.0045246856 0.8537560000 969617873 0 1783500800 -0.3414922059 -0.0874736309 0.0403159671 630 1311867739.6325490475 0.3929374814 0.1893247826 0.3949593008 0.0045211671 0.8749730000 969619691 0 1782140928 -0.3427397013 -0.0870274305 0.0409701020 631 1311867739.6706740856 0.3942941129 0.1896496151 0.3949593008 0.0045193191 0.8453570000 969621573 0 1783902208 -0.3444156349 -0.0871864855 0.0415478870 632 1311867739.7001221180 0.3949485123 0.1899744551 0.3949593008 0.0045168439 0.8543360000 969623327 0 1782374400 -0.3451982737 -0.0869394243 0.0421079881 633 1311867739.7323939800 0.3944891393 0.1902975431 0.3949593008 0.0045144406 0.8570390000 969625113 0 1784135680 -0.3449242711 -0.0866734162 0.0429225378 634 1311867739.7662999630 0.3949398994 0.1906203229 0.3949593008 0.0045114040 0.8494880000 969626931 0 1782759424 -0.3455499113 -0.0867217556 0.0436609015 635 1311867739.8016180992 0.3950450122 0.1909422515 0.3950450122 0.0045087443 0.8391500000 969628781 0 1784426496 -0.3459501565 -0.0872130319 0.0441756174 636 1311867739.8325679302 0.3953163624 0.1912635944 0.3953163624 0.0045081076 0.8661420000 969630535 0 1782886400 -0.3465371430 -0.0867785811 0.0446650870 637 1311867739.8701560497 0.3953531981 0.1915839863 0.3953531981 0.0045049646 0.8418940000 969632385 0 1781489664 -0.3471760154 -0.0866882354 0.0451540798 638 1311867739.9036860466 0.3960301578 0.1919044348 0.3960301578 0.0045022576 0.8419840000 969634235 0 1782992896 -0.3485802710 -0.0874466449 0.0452987924 639 1311867739.9317240715 0.3969041109 0.1922252481 0.3969041109 0.0044991039 0.8349260000 969635957 0 1781489664 -0.3499675989 -0.0873911083 0.0455140248 640 1311867739.9668979645 0.3969476819 0.1925451269 0.3969476819 0.0044966274 0.8318980000 969637775 0 1783136256 -0.3504648209 -0.0871171877 0.0457114577 641 1311867739.9987080097 0.3982883096 0.1928660991 0.3982883096 0.0044938582 0.8342490000 969639593 0 1781637120 -0.3525027335 -0.0872429907 0.0462696962 642 1311867740.0328791142 0.3986075222 0.1931865686 0.3986075222 0.0044905083 0.8730560000 969641411 0 1783267328 -0.3534306884 -0.0873522907 0.0464738049 643 1311867740.0671849251 0.3978539109 0.1935048693 0.3986075222 0.0044875155 0.8356300000 969643197 0 1781633024 -0.3531083465 -0.0869381055 0.0465052202 644 1311867740.0992529392 0.3980799615 0.1938225325 0.3986075222 0.0044872009 0.8375900000 969645015 0 1783246848 -0.3536632359 -0.0875152424 0.0467588119 645 1311867740.1347720623 0.3990378380 0.1941406957 0.3990378380 0.0044852435 0.8330440000 969646801 0 1781764096 -0.3553621769 -0.0881535709 0.0468521640 646 1311867740.1666491032 0.3988166153 0.1944575315 0.3990378380 0.0044820821 0.8326140000 969648619 0 1783521280 -0.3553152382 -0.0876991600 0.0467468426 647 1311867740.1993310452 0.3984972239 0.1947728943 0.3990378380 0.0044789457 0.8312450000 969650437 0 1781870592 -0.3554561436 -0.0873789787 0.0468983874 648 1311867740.2383539677 0.3994016051 0.1950886793 0.3994016051 0.0044772928 0.8542480000 969652351 0 1783521280 -0.3568713069 -0.0878296793 0.0468445495 649 1311867740.2664349079 0.3988546431 0.1954026485 0.3994016051 0.0044766306 0.8316640000 969654041 0 1781886976 -0.3566870689 -0.0875906944 0.0467916578 650 1311867740.2981588840 0.4001885355 0.1957177037 0.4001885355 0.0044741173 0.8324810000 969655827 0 1783500800 -0.3583661020 -0.0870089158 0.0469328240 651 1311867740.3347120285 0.3992547691 0.1960303566 0.4001885355 0.0044709255 0.8301420000 969657709 0 1781997568 -0.3578793705 -0.0873968825 0.0466633402 652 1311867740.3665161133 0.3986146152 0.1963410687 0.4001885355 0.0044698686 0.8277960000 969659463 0 1783775232 -0.3574483395 -0.0872340500 0.0462711230 653 1311867740.3993780613 0.3980085254 0.1966499009 0.4001885355 0.0044677256 0.8320850000 969661249 0 1782140928 -0.3569694459 -0.0873653963 0.0459324680 654 1311867740.4346680641 0.3983223736 0.1969582686 0.4001885355 0.0044665402 0.8309630000 969663099 0 1783754752 -0.3571600616 -0.0873830095 0.0455974787 655 1311867740.4664289951 0.3989759684 0.1972666926 0.4001885355 0.0044641811 0.8329930000 969664885 0 1782259712 -0.3579498231 -0.0871851370 0.0452958196 656 1311867740.4993040562 0.4000316560 0.1975757855 0.4001885355 0.0044641918 0.8299080000 969666671 0 1783902208 -0.3586254716 -0.0871319249 0.0451942347 657 1311867740.5354259014 0.4011906981 0.1978857017 0.4011906981 0.0044661901 0.8242480000 969668521 0 1782267904 -0.3593943715 -0.0872235894 0.0450483263 658 1311867740.5666589737 0.4015312493 0.1981951934 0.4015312493 0.0044636537 0.8252720000 969670307 0 1784029184 -0.3595664799 -0.0870740712 0.0448102504 659 1311867740.6008880138 0.4031279385 0.1985061687 0.4031279385 0.0044630420 0.8215930000 969672125 0 1782398976 -0.3610344827 -0.0869474113 0.0449089706 660 1311867740.6346809864 0.4037981927 0.1988172172 0.4037981927 0.0044614244 0.8651200000 969673943 0 1784020992 -0.3617818356 -0.0871002227 0.0449776500 661 1311867740.6665890217 0.4035904706 0.1991270103 0.4037981927 0.0044584130 0.8146910000 969675729 0 1782386688 -0.3617737591 -0.0870792195 0.0446416549 662 1311867740.6994900703 0.4044587612 0.1994371792 0.4044587612 0.0044561515 0.8304700000 969677515 0 1784156160 -0.3628174961 -0.0873181820 0.0442449786 663 1311867740.7368240356 0.4045419693 0.1997465378 0.4045419693 0.0044551334 0.8233590000 969679301 0 1782509568 -0.3630649745 -0.0873303711 0.0439554639 664 1311867740.7668819427 0.4051683545 0.2000559080 0.4051683545 0.0044524793 0.8081740000 969681055 0 1784139776 -0.3639458418 -0.0874390006 0.0438697897 665 1311867740.7996399403 0.4070231318 0.2003671369 0.4070231318 0.0044501943 0.8149500000 969682873 0 1782145024 -0.3660964966 -0.0878445432 0.0442716293 666 1311867740.8349099159 0.4073312879 0.2006778939 0.4073312879 0.0044472761 0.8467390000 969684659 0 1783771136 -0.3667340875 -0.0874279886 0.0438977182 667 1311867740.8668210506 0.4077284932 0.2009883146 0.4077284932 0.0044447833 0.8164930000 969686477 0 1782272000 -0.3674982488 -0.0874750689 0.0439340621 668 1311867740.8993830681 0.4081553519 0.2012984449 0.4081553519 0.0044416005 0.8131420000 969688263 0 1783902208 -0.3686009645 -0.0877707824 0.0437270366 669 1311867740.9399120808 0.4079679549 0.2016073679 0.4081553519 0.0044406397 0.8140060000 969690209 0 1782272000 -0.3690313101 -0.0874252170 0.0433091260 670 1311867740.9665501118 0.4073044956 0.2019143786 0.4081553519 0.0044374126 0.8136770000 969691899 0 1784033280 -0.3688144684 -0.0871454999 0.0429375917 671 1311867741.0021579266 0.4080555141 0.2022215934 0.4081553519 0.0044347746 0.8173710000 969693749 0 1782018048 -0.3700695336 -0.0876587927 0.0427708179 672 1311867741.0367169380 0.4080461562 0.2025278799 0.4081553519 0.0044316211 0.8371390000 969695567 0 1783758848 -0.3703621328 -0.0877896175 0.0423602127 673 1311867741.0666699409 0.4074721634 0.2028324034 0.4081553519 0.0044294127 0.8154050000 969697321 0 1781747712 -0.3701443374 -0.0871591568 0.0419923812 674 1311867741.1009640694 0.4083032906 0.2031372563 0.4083032906 0.0044307381 0.8179610000 969699139 0 1783484416 -0.3714331686 -0.0878995433 0.0417329222 675 1311867741.1357901096 0.4080413878 0.2034408180 0.4083032906 0.0044280508 0.8097760000 969700957 0 1781891072 -0.3717156947 -0.0879750997 0.0409903079 676 1311867741.1675300598 0.4075302780 0.2037427255 0.4083032906 0.0044251431 0.8138820000 969702775 0 1783631872 -0.3712453544 -0.0883830711 0.0405083187 677 1311867741.2014830112 0.4079530835 0.2040443656 0.4083032906 0.0044263552 0.8128500000 969704561 0 1781641216 -0.3715846837 -0.0888471603 0.0401722379 678 1311867741.2411060333 0.4089217484 0.2043465446 0.4089217484 0.0044283455 0.8357370000 969706475 0 1783357440 -0.3727380335 -0.0895919055 0.0399602503 679 1311867741.2668209076 0.4096424580 0.2046488950 0.4096424580 0.0044284733 0.8023610000 969708165 0 1781747712 -0.3733020127 -0.0896607190 0.0398461930 680 1311867741.2997009754 0.4103949666 0.2049514628 0.4103949666 0.0044252635 0.7947580000 969709951 0 1783377920 -0.3738620281 -0.0897130817 0.0396627039 681 1311867741.3348419666 0.4110561609 0.2052541128 0.4110561609 0.0044222040 0.8045530000 969711801 0 1781514240 -0.3744663298 -0.0892328545 0.0392772257 682 1311867741.3701419830 0.4111200273 0.2055559690 0.4111200273 0.0044189748 0.8006190000 969713619 0 1783119872 -0.3742107153 -0.0885566324 0.0388581157 683 1311867741.4066278934 0.4115829468 0.2058576191 0.4115829468 0.0044174244 0.8138780000 969715501 0 1781493760 -0.3742252290 -0.0886216164 0.0386744440 684 1311867741.4393060207 0.4116076529 0.2061584232 0.4116076529 0.0044155459 0.8146990000 969717319 0 1783246848 -0.3739982843 -0.0879296288 0.0386940837 685 1311867741.4667329788 0.4107503295 0.2064570975 0.4116076529 0.0044126201 0.8012130000 969719009 0 1781641216 -0.3727571666 -0.0873408020 0.0384360850 686 1311867741.5025069714 0.4115342200 0.2067560438 0.4116076529 0.0044102232 0.8029420000 969720859 0 1783250944 -0.3730331659 -0.0866857097 0.0387430899 687 1311867741.5368049145 0.4119476080 0.2070547214 0.4119476080 0.0044086212 0.7995380000 969722677 0 1781239808 -0.3730584383 -0.0864835456 0.0385592878 688 1311867741.5688209534 0.4115807414 0.2073519976 0.4119476080 0.0044054760 0.7987270000 969724463 0 1782976512 -0.3722247183 -0.0860294253 0.0383326113 689 1311867741.6046030521 0.4120883942 0.2076491477 0.4120883942 0.0044113102 0.7988220000 969726281 0 1781387264 -0.3723731339 -0.0857216418 0.0385615826 690 1311867741.6355440617 0.4127565026 0.2079464047 0.4127565026 0.0044087734 0.8110540000 969728067 0 1782996992 -0.3725557923 -0.0855206475 0.0384981669 691 1311867741.6679561138 0.4122672975 0.2082420934 0.4127565026 0.0044058444 0.7966030000 969729885 0 1784500224 -0.3714897335 -0.0852887705 0.0382695347 692 1311867741.7048020363 0.4138595760 0.2085392285 0.4138595760 0.0044083912 0.8334370000 969731735 0 1782657024 -0.3722420037 -0.0849706233 0.0381910205 693 1311867741.7345991135 0.4134140611 0.2088348632 0.4138595760 0.0044065755 0.7996510000 969733457 0 1784389632 -0.3712530434 -0.0848199129 0.0377947837 694 1311867741.7702169418 0.4137906730 0.2091301886 0.4138595760 0.0044034829 0.7959580000 969735307 0 1782784000 -0.3708101213 -0.0849088430 0.0376926661 695 1311867741.8058650494 0.4136323333 0.2094244363 0.4138595760 0.0044003754 0.7960750000 969737157 0 1784393728 -0.3698075116 -0.0845813453 0.0372709036 696 1311867741.8388509750 0.4137457609 0.2097180014 0.4138595760 0.0043981081 0.8078850000 969739007 0 1782403072 -0.3693310916 -0.0845883638 0.0369510911 697 1311867741.8683021069 0.4142286777 0.2100114170 0.4142286777 0.0043956477 0.8017430000 969740729 0 1784016896 -0.3691827059 -0.0845844820 0.0367719717 698 1311867741.9065721035 0.4143989682 0.2103042358 0.4143989682 0.0043925942 0.8052430000 969742611 0 1782136832 -0.3687065244 -0.0842345953 0.0363031365 699 1311867741.9387769699 0.4149651825 0.2105970269 0.4149651825 0.0043902159 0.7973040000 969744429 0 1783873536 -0.3684182465 -0.0839629546 0.0359925367 700 1311867741.9665379524 0.4148474932 0.2108888133 0.4149651825 0.0043881657 0.8079740000 969746119 0 1782263808 -0.3676035106 -0.0840300322 0.0355856903 701 1311867742.0029959679 0.4151516259 0.2111802010 0.4151516259 0.0043856012 0.7982780000 969747969 0 1783894016 -0.3669155538 -0.0843555406 0.0355343819 702 1311867742.0344839096 0.4157119989 0.2114715569 0.4157119989 0.0043825600 0.8048430000 969749723 0 1782030336 -0.3666819632 -0.0840255320 0.0353342444 703 1311867742.0674400330 0.4154615104 0.2117617275 0.4157119989 0.0043799962 0.7971310000 969751509 0 1783746560 -0.3656622171 -0.0836886317 0.0350574292 704 1311867742.1030650139 0.4169445038 0.2120531803 0.4169445038 0.0043780490 0.8035780000 969753327 0 1782149120 -0.3658573329 -0.0833870322 0.0349282026 705 1311867742.1348879337 0.4174192846 0.2123444797 0.4174192846 0.0043761069 0.7929240000 969755081 0 1783779328 -0.3652962446 -0.0833455548 0.0347098708 706 1311867742.1672229767 0.4169470370 0.2126342851 0.4174192846 0.0043738936 0.7928240000 969756899 0 1781637120 -0.3643350601 -0.0828603953 0.0346593000 707 1311867742.2028279305 0.4171777070 0.2129235968 0.4174192846 0.0043714685 0.7922460000 969758781 0 1783373824 -0.3636343479 -0.0825416744 0.0346050560 708 1311867742.2362670898 0.4174613059 0.2132124919 0.4174613059 0.0043698118 0.7881170000 969760567 0 1781768192 -0.3631069362 -0.0821973085 0.0345726199 709 1311867742.2674059868 0.4178261459 0.2135010866 0.4178261459 0.0043674548 0.7995580000 969762353 0 1783484416 -0.3628574610 -0.0826081410 0.0346312970 710 1311867742.3028159142 0.4181205332 0.2137892830 0.4181205332 0.0043649235 0.8049620000 969764203 0 1781878784 -0.3627728522 -0.0825658292 0.0343416519 711 1311867742.3350739479 0.4187238812 0.2140775173 0.4187238812 0.0043621396 0.7878990000 969765957 0 1783504896 -0.3630045652 -0.0824498385 0.0340330601 712 1311867742.3694241047 0.4185071290 0.2143646376 0.4187238812 0.0043591274 0.7810870000 969767807 0 1781514240 -0.3625700772 -0.0827792138 0.0336711556 713 1311867742.4062991142 0.4199369848 0.2146529578 0.4199369848 0.0043561661 0.8099080000 969769657 0 1783230464 -0.3636070788 -0.0828640014 0.0332033485 714 1311867742.4346439838 0.4198963344 0.2149404135 0.4199369848 0.0043532271 0.7860740000 969771379 0 1781624832 -0.3632731140 -0.0829928294 0.0328528434 715 1311867742.4666969776 0.4206843972 0.2152281674 0.4206843972 0.0043509120 0.7801910000 969773165 0 1783246848 -0.3637083173 -0.0828284621 0.0325910002 716 1311867742.5047059059 0.4207217097 0.2155151695 0.4207217097 0.0043479587 0.7851930000 969775015 0 1781641216 -0.3633060753 -0.0827352405 0.0325293876 717 1311867742.5359389782 0.4210042357 0.2158017652 0.4210042357 0.0043453632 0.7792860000 969776801 0 1783267328 -0.3632043302 -0.0824790671 0.0325394459 718 1311867742.5678529739 0.4206433296 0.2160870598 0.4210042357 0.0043430944 0.7794100000 969778619 0 1781260288 -0.3624222577 -0.0821607560 0.0324168652 719 1311867742.6054639816 0.4209972620 0.2163720531 0.4210042357 0.0043403294 0.7779820000 969780469 0 1782976512 -0.3624367118 -0.0824571177 0.0324107744 720 1311867742.6347279549 0.4199456275 0.2166547942 0.4210042357 0.0043378655 0.7847470000 969782191 0 1781370880 -0.3611922562 -0.0820803866 0.0323417783 721 1311867742.6724960804 0.4206757545 0.2169377636 0.4210042357 0.0043352037 0.7836170000 969784105 0 1783103488 -0.3616133630 -0.0822746977 0.0325319506 722 1311867742.7046229839 0.4210515320 0.2172204697 0.4210515320 0.0043322007 0.7823230000 969785859 0 1781497856 -0.3617270291 -0.0825579837 0.0325779766 723 1311867742.7356119156 0.4208315909 0.2175020895 0.4210515320 0.0043292866 0.7822250000 969787645 0 1783144448 -0.3611867726 -0.0825800672 0.0323642939 724 1311867742.7726070881 0.4216292500 0.2177840331 0.4216292500 0.0043270972 0.7758830000 969789527 0 1781133312 -0.3614939749 -0.0830292106 0.0324078798 725 1311867742.8034689426 0.4219671190 0.2180656649 0.4219671190 0.0043279247 0.7744170000 969791313 0 1782722560 -0.3618791401 -0.0830158219 0.0324278176 726 1311867742.8352251053 0.4225390553 0.2183473087 0.4225390553 0.0043274953 0.7777770000 969793067 0 1784500224 -0.3617976308 -0.0831422582 0.0323366709 727 1311867742.8705639839 0.4232803583 0.2186291974 0.4232803583 0.0043249138 0.7870070000 969794885 0 1782894592 -0.3623228371 -0.0830744356 0.0324023217 728 1311867742.9046700001 0.4229784310 0.2189098969 0.4232803583 0.0043220655 0.7776390000 969796703 0 1781260288 -0.3616475463 -0.0831567720 0.0322467126 729 1311867742.9382069111 0.4225375056 0.2191892214 0.4232803583 0.0043424339 0.7738130000 969798553 0 1782870016 -0.3611625433 -0.0829705000 0.0321789831 730 1311867742.9707310200 0.4220889509 0.2194671663 0.4232803583 0.0043430328 0.7746560000 969800339 0 1784389632 -0.3603796661 -0.0828178525 0.0319524556 731 1311867743.0024189949 0.4227926731 0.2197453133 0.4232803583 0.0043444091 0.7827530000 969802093 0 1782657024 -0.3608211577 -0.0827863589 0.0321341790 732 1311867743.0345149040 0.4227243960 0.2200226072 0.4232803583 0.0043448590 0.7650350000 969803879 0 1784373248 -0.3603966832 -0.0824504495 0.0321065001 733 1311867743.0722420216 0.4228611588 0.2202993310 0.4232803583 0.0043433713 0.7758620000 969805761 0 1782767616 -0.3600477278 -0.0828104839 0.0319768749 734 1311867743.1045989990 0.4227078855 0.2205750920 0.4232803583 0.0043407567 0.7999100000 969807547 0 1784393728 -0.3595670164 -0.0828720182 0.0319891423 735 1311867743.1350400448 0.4232898355 0.2208508943 0.4232898355 0.0043395125 0.7822090000 969809301 0 1782394880 -0.3595218062 -0.0829214677 0.0318815149 736 1311867743.1704380512 0.4229620993 0.2211255019 0.4232898355 0.0043429115 0.7733100000 969811119 0 1784127488 -0.3590600789 -0.0832808763 0.0315895490 737 1311867743.2037980556 0.4228997529 0.2213992798 0.4232898355 0.0043406745 0.7779800000 969812937 0 1782521856 -0.3585811853 -0.0831229240 0.0313717872 738 1311867743.2358140945 0.4234337211 0.2216730392 0.4234337211 0.0043388205 0.7698990000 969814691 0 1784168448 -0.3586042523 -0.0830525383 0.0314536095 739 1311867743.2708129883 0.4229955375 0.2219454647 0.4234337211 0.0043410180 0.7710180000 969816541 0 1782140928 -0.3580073416 -0.0825063139 0.0315460525 740 1311867743.3032529354 0.4233565032 0.2222176418 0.4234337211 0.0043483371 0.7757770000 969818327 0 1783873536 -0.3583205044 -0.0824693441 0.0316166878 741 1311867743.3363931179 0.4235288501 0.2224893169 0.4235288501 0.0043456411 0.7805940000 969820113 0 1782284288 -0.3583852947 -0.0819488913 0.0317548104 742 1311867743.3707330227 0.4232504964 0.2227598845 0.4235288501 0.0043430930 0.7749600000 969821931 0 1783873536 -0.3579626381 -0.0815416276 0.0318795294 743 1311867743.4043838978 0.4237296581 0.2230303687 0.4237296581 0.0043402962 0.7779730000 969823749 0 1782267904 -0.3584013581 -0.0814879537 0.0320367515 744 1311867743.4352641106 0.4239572883 0.2233004318 0.4239572883 0.0043458436 0.7723550000 969825535 0 1783992320 -0.3586184084 -0.0817848518 0.0319246985 745 1311867743.4768960476 0.4239771962 0.2235697966 0.4239771962 0.0043452439 0.7713560000 969827449 0 1782386688 -0.3585765958 -0.0815128163 0.0319043733 746 1311867743.5035250187 0.4247169495 0.2238394308 0.4247169495 0.0043430197 0.7698090000 969829171 0 1783992320 -0.3590995669 -0.0813721865 0.0319820940 747 1311867743.5389750004 0.4248529375 0.2241085252 0.4248529375 0.0043439628 0.7733840000 969830989 0 1782259712 -0.3594396412 -0.0814376995 0.0318392552 748 1311867743.5749680996 0.4240895212 0.2243758795 0.4248529375 0.0043440611 0.8066310000 969832839 0 1783992320 -0.3580762744 -0.0807667524 0.0314043313 749 1311867743.6036109924 0.4247244895 0.2246433676 0.4248529375 0.0043477976 0.7741650000 969834561 0 1782386688 -0.3592476547 -0.0807035565 0.0315110832 750 1311867743.6354589462 0.4248480499 0.2249103072 0.4248529375 0.0043478343 0.7779320000 969836347 0 1784119296 -0.3595420420 -0.0805704147 0.0312281437 751 1311867743.6759150028 0.4243597686 0.2251758857 0.4248529375 0.0043450884 0.7814410000 969838261 0 1782513664 -0.3591484725 -0.0811617747 0.0309753902 752 1311867743.7034959793 0.4250045419 0.2254416153 0.4250045419 0.0043422578 0.7796330000 969839983 0 1784119296 -0.3599933386 -0.0811818764 0.0309673995 753 1311867743.7388861179 0.4242047369 0.2257055769 0.4250045419 0.0043402948 0.7818150000 969841833 0 1782530048 -0.3594303131 -0.0811839327 0.0303773433 754 1311867743.7733619213 0.4244978726 0.2259692272 0.4250045419 0.0043375905 0.7788770000 969843683 0 1784246272 -0.3599609435 -0.0816579014 0.0301672556 755 1311867743.8064749241 0.4248882234 0.2262326961 0.4250045419 0.0043351056 0.7751680000 969845437 0 1782657024 -0.3605372608 -0.0817821547 0.0299469233 756 1311867743.8391659260 0.4261964858 0.2264971984 0.4261964858 0.0043332790 0.7730230000 969847223 0 1784266752 -0.3621423244 -0.0821862221 0.0297865588 757 1311867743.8726658821 0.4250016510 0.2267594236 0.4261964858 0.0043310237 0.7812900000 969849073 0 1782272000 -0.3611840010 -0.0826357678 0.0293051749 758 1311867743.9031310081 0.4251850247 0.2270211988 0.4261964858 0.0043284299 0.7785870000 969850827 0 1784012800 -0.3613016903 -0.0826233849 0.0288453363 759 1311867743.9453630447 0.4266164899 0.2272841702 0.4266164899 0.0043260646 0.7746760000 969852773 0 1782018048 -0.3628826141 -0.0831036270 0.0288127959 760 1311867743.9741249084 0.4263755381 0.2275461325 0.4266164899 0.0043243647 0.7830540000 969854495 0 1783865344 -0.3627523184 -0.0826214030 0.0282675587 761 1311867744.0042529106 0.4258471131 0.2278067120 0.4266164899 0.0043231732 0.7822800000 969856217 0 1782276096 -0.3622423410 -0.0815826356 0.0280500799 762 1311867744.0407259464 0.4257009327 0.2280664157 0.4266164899 0.0043213031 0.7750570000 969858099 0 1783885824 -0.3621172011 -0.0813874677 0.0279459227 763 1311867744.0716118813 0.4251722693 0.2283247458 0.4266164899 0.0043189298 0.7779500000 969859853 0 1781874688 -0.3617242277 -0.0809990168 0.0278514586 764 1311867744.1111290455 0.4250359833 0.2285822212 0.4266164899 0.0043161495 0.7868290000 969861671 0 1783611392 -0.3616331816 -0.0808352828 0.0275682379 765 1311867744.1412119865 0.4253064990 0.2288393771 0.4266164899 0.0043139016 0.7816360000 969863425 0 1782001664 -0.3619259894 -0.0798792988 0.0273324102 766 1311867744.1734991074 0.4245164990 0.2290948303 0.4266164899 0.0043113088 0.7862740000 969865243 0 1783648256 -0.3609098196 -0.0790194944 0.0271786116 767 1311867744.2046771049 0.4259005785 0.2293514219 0.4266164899 0.0043137045 0.7872380000 969866997 0 1781747712 -0.3622778654 -0.0794439018 0.0271295011 768 1311867744.2400228977 0.4259998798 0.2296074746 0.4266164899 0.0043120507 0.7886820000 969868879 0 1783377920 -0.3624546826 -0.0795361325 0.0269937404 769 1311867744.2773048878 0.4257124960 0.2298624876 0.4266164899 0.0043095330 0.8187290000 969870729 0 1781387264 -0.3621250987 -0.0784444064 0.0268648863 770 1311867744.3032519817 0.4251328409 0.2301160855 0.4266164899 0.0043077660 0.7847310000 969872419 0 1783103488 -0.3617069423 -0.0788176656 0.0266464539 771 1311867744.3391230106 0.4255229533 0.2303695315 0.4266164899 0.0043074383 0.7929720000 969874269 0 1781514240 -0.3619357944 -0.0791985467 0.0267777145 772 1311867744.3707659245 0.4251284897 0.2306218099 0.4266164899 0.0043048513 0.7914970000 969876023 0 1783230464 -0.3613783419 -0.0787017271 0.0265442319 773 1311867744.4027431011 0.4261253774 0.2308747253 0.4266164899 0.0043029382 0.7932990000 969877841 0 1781624832 -0.3622263670 -0.0786340758 0.0268017910 774 1311867744.4383800030 0.4270361960 0.2311281639 0.4270361960 0.0043006169 0.7852210000 969879659 0 1783271424 -0.3631252050 -0.0789080486 0.0265882928 775 1311867744.4717690945 0.4277644157 0.2313818880 0.4277644157 0.0042991164 0.7934470000 969881477 0 1781112832 -0.3636817932 -0.0790766478 0.0268889219 776 1311867744.5026860237 0.4268429577 0.2316337709 0.4277644157 0.0042964762 0.7915950000 969883263 0 1782865920 -0.3626936972 -0.0783347934 0.0262888968 777 1311867744.5383169651 0.4270162284 0.2318852283 0.4277644157 0.0042963067 0.7852120000 969885113 0 1781260288 -0.3627418578 -0.0786877200 0.0260036457 778 1311867744.5726189613 0.4267852008 0.2321357424 0.4277644157 0.0042936579 0.7841550000 969886931 0 1782890496 -0.3624325991 -0.0794096664 0.0258233882 779 1311867744.6028740406 0.4274050593 0.2323864091 0.4277644157 0.0042940125 0.7923250000 969888685 0 1780887552 -0.3625564575 -0.0792370513 0.0257795565 780 1311867744.6386809349 0.4271309674 0.2326360816 0.4277644157 0.0042943218 0.7880990000 969890535 0 1782603776 -0.3626450002 -0.0791261569 0.0255653299 781 1311867744.6707758904 0.4257813692 0.2328833867 0.4277644157 0.0042919075 0.7894590000 969892321 0 1784254464 -0.3613711298 -0.0788663402 0.0250093788 782 1311867744.7029349804 0.4277631640 0.2331325936 0.4277644157 0.0042954929 0.7889440000 969894107 0 1782665216 -0.3626877964 -0.0787932724 0.0253732838 783 1311867744.7396171093 0.4257645607 0.2333786114 0.4277644157 0.0042992997 0.8332760000 969895957 0 1784381440 -0.3612157702 -0.0780341551 0.0250169821 784 1311867744.7705199718 0.4264707565 0.2336249024 0.4277644157 0.0042968225 0.7945290000 969897711 0 1782784000 -0.3619422913 -0.0786413997 0.0251481980 785 1311867744.8035891056 0.4269952774 0.2338712341 0.4277644157 0.0042977788 0.7985750000 969899529 0 1784393728 -0.3620842993 -0.0791811496 0.0251097679 786 1311867744.8424170017 0.4264550507 0.2341162517 0.4277644157 0.0042955864 0.7908590000 969901411 0 1782403072 -0.3613534868 -0.0793960094 0.0251459815 787 1311867744.8727390766 0.4263621271 0.2343605285 0.4277644157 0.0042966924 0.7872280000 969903197 0 1784119296 -0.3618761897 -0.0798392594 0.0248694867 788 1311867744.9029939175 0.4267586470 0.2346046886 0.4277644157 0.0042940577 0.7926490000 969904951 0 1782530048 -0.3623080850 -0.0805534944 0.0247163810 789 1311867744.9392940998 0.4265515208 0.2348479672 0.4277644157 0.0042956835 0.7908400000 969906833 0 1784139776 -0.3614485562 -0.0806746110 0.0245030373 790 1311867744.9708900452 0.4262067080 0.2350901935 0.4277644157 0.0042964715 0.7939870000 969908555 0 1782255616 -0.3615667224 -0.0805800259 0.0239841044 791 1311867745.0027489662 0.4263609648 0.2353320023 0.4277644157 0.0043001177 0.7933510000 969910341 0 1783885824 -0.3612501323 -0.0805146843 0.0233782232 792 1311867745.0384869576 0.4265332222 0.2355734180 0.4277644157 0.0043000672 0.7891080000 969912191 0 1781997568 -0.3617168069 -0.0807868242 0.0235883147 793 1311867745.0729780197 0.4258113205 0.2358133144 0.4277644157 0.0043001180 0.7825800000 969914009 0 1783758848 -0.3608853817 -0.0810169578 0.0234269947 794 1311867745.1118760109 0.4256032109 0.2360523445 0.4277644157 0.0043005974 0.7919820000 969915891 0 1781874688 -0.3609307408 -0.0806310028 0.0229692776 795 1311867745.1405589581 0.4246970117 0.2362896334 0.4277644157 0.0042993307 0.7816650000 969917613 0 1783504896 -0.3599212468 -0.0806343183 0.0226706415 796 1311867745.1729030609 0.4257603288 0.2365276619 0.4277644157 0.0042969513 0.7860590000 969919399 0 1781493760 -0.3608486056 -0.0813068897 0.0228340495 797 1311867745.2068369389 0.4267480969 0.2367663325 0.4277644157 0.0042944808 0.7867990000 969921217 0 1783144448 -0.3618643582 -0.0815139264 0.0229521096 798 1311867745.2430789471 0.4255361259 0.2370028861 0.4277644157 0.0042924496 0.7836670000 969923067 0 1780981760 -0.3604241014 -0.0810774788 0.0228807945 799 1311867745.2729060650 0.4275574982 0.2372413775 0.4277644157 0.0042904209 0.7793360000 969924821 0 1782759424 -0.3622931838 -0.0811695978 0.0231819768 800 1311867745.3112850189 0.4265334904 0.2374779926 0.4277644157 0.0042892139 0.7782470000 969926671 0 1784373248 -0.3612872958 -0.0810425207 0.0227445811 801 1311867745.3395059109 0.4259314537 0.2377132654 0.4277644157 0.0042866160 0.7852130000 969928425 0 1782505472 -0.3606006205 -0.0809420198 0.0223634690 802 1311867745.3733940125 0.4258295596 0.2379478243 0.4277644157 0.0042854643 0.7752990000 969930243 0 1784156160 -0.3604091704 -0.0809417963 0.0219917297 803 1311867745.4102098942 0.4255959988 0.2381815082 0.4277644157 0.0042831085 0.7949380000 969932093 0 1782525952 -0.3598729372 -0.0813917816 0.0218428969 804 1311867745.4433169365 0.4267847240 0.2384160894 0.4277644157 0.0042809562 0.8073680000 969933911 0 1784266752 -0.3609852791 -0.0811481029 0.0218418986 805 1311867745.4708619118 0.4251760244 0.2386480893 0.4277644157 0.0042786093 0.7794080000 969935601 0 1782509568 -0.3594264090 -0.0807676464 0.0213187188 806 1311867745.5099780560 0.4263122976 0.2388809233 0.4277644157 0.0042776190 0.7773580000 969937515 0 1784266752 -0.3603274226 -0.0809178799 0.0210557580 807 1311867745.5417380333 0.4264024198 0.2391132919 0.4277644157 0.0042765909 0.7806360000 969939301 0 1782525952 -0.3601847887 -0.0812768191 0.0209942609 808 1311867745.5704059601 0.4260770082 0.2393446827 0.4277644157 0.0042743100 0.7784260000 969941023 0 1784266752 -0.3599427640 -0.0820167214 0.0206222683 809 1311867745.6133821011 0.4258756936 0.2395752525 0.4277644157 0.0042726877 0.7745350000 969943001 0 1782272000 -0.3597576618 -0.0821760893 0.0203078091 810 1311867745.6438291073 0.4249706566 0.2398041357 0.4277644157 0.0042741910 0.7807040000 969944787 0 1784012800 -0.3588605821 -0.0818892643 0.0196905434 811 1311867745.6709001064 0.4257575870 0.2400334248 0.4277644157 0.0042782666 0.7745970000 969946445 0 1782018048 -0.3595700264 -0.0816102326 0.0196286291 812 1311867745.7088780403 0.4263554811 0.2402628855 0.4277644157 0.0042766508 0.7720890000 969948359 0 1783627776 -0.3598354757 -0.0814490840 0.0192886423 813 1311867745.7423269749 0.4254920483 0.2404907196 0.4277644157 0.0042765830 0.7739280000 969950145 0 1781747712 -0.3592039347 -0.0815789178 0.0190777052 814 1311867745.7760419846 0.4266743660 0.2407194465 0.4277644157 0.0042813238 0.7812640000 969951963 0 1783504896 -0.3598747253 -0.0822429657 0.0194853097 815 1311867745.8116889000 0.4260645509 0.2409468638 0.4277644157 0.0042846512 0.7766210000 969953813 0 1781493760 -0.3591718078 -0.0819708779 0.0197523702 816 1311867745.8389890194 0.4258672595 0.2411734819 0.4277644157 0.0042840714 0.7766950000 969955535 0 1783140352 -0.3591005802 -0.0821350068 0.0200624168 817 1311867745.8709759712 0.4274364412 0.2414014659 0.4277644157 0.0042822335 0.7779600000 969957289 0 1781256192 -0.3606984913 -0.0820973292 0.0203919094 818 1311867745.9108459949 0.4265960157 0.2416278651 0.4277644157 0.0042829597 0.7698400000 969959203 0 1782996992 -0.3596249223 -0.0816082284 0.0200443584 819 1311867745.9435789585 0.4273857772 0.2418546758 0.4277644157 0.0042832151 0.7678220000 969961021 0 1781256192 -0.3603582382 -0.0821606964 0.0198950917 820 1311867745.9732220173 0.4279330373 0.2420816006 0.4279330373 0.0042809076 0.7734080000 969962743 0 1782996992 -0.3605778217 -0.0835802704 0.0209013969 821 1311867746.0083909035 0.4276811481 0.2423076658 0.4279330373 0.0042798792 0.7733290000 969964561 0 1784516608 -0.3600709736 -0.0838640481 0.0211081225 822 1311867746.0391409397 0.4271993339 0.2425325949 0.4279330373 0.0042777740 0.7786040000 969966379 0 1782771712 -0.3593535423 -0.0840535387 0.0213382710 823 1311867746.0728518963 0.4269321561 0.2427566527 0.4279330373 0.0042755343 0.7665580000 969968165 0 1784401920 -0.3588391840 -0.0837687477 0.0209082533 824 1311867746.1113359928 0.4277581275 0.2429811690 0.4279330373 0.0042742447 0.7696010000 969970015 0 1782407168 -0.3591811955 -0.0842321664 0.0212569088 825 1311867746.1412689686 0.4291229248 0.2432067954 0.4291229248 0.0042721335 0.8115960000 969971801 0 1784274944 -0.3602989912 -0.0849490613 0.0215276927 826 1311867746.1721889973 0.4294125438 0.2434322261 0.4294125438 0.0042705140 0.7730610000 969973555 0 1782517760 -0.3603863120 -0.0850349292 0.0217368156 827 1311867746.2066209316 0.4290297031 0.2436566487 0.4294125438 0.0042682349 0.7637860000 969975373 0 1784164352 -0.3597537279 -0.0847312659 0.0216323882 828 1311867746.2386920452 0.4294897616 0.2438810848 0.4294897616 0.0042661948 0.7616520000 969977191 0 1782284288 -0.3604866862 -0.0856598318 0.0217524916 829 1311867746.2704648972 0.4298602939 0.2441054264 0.4298602939 0.0042636843 0.7674780000 969978977 0 1783992320 -0.3609668612 -0.0863007456 0.0219601840 830 1311867746.3068819046 0.4276439846 0.2443265572 0.4298602939 0.0042625737 0.7606100000 969980795 0 1782386688 -0.3590320349 -0.0857488289 0.0210093409 831 1311867746.3393440247 0.4273736775 0.2445468305 0.4298602939 0.0042639186 0.7594780000 969982613 0 1784012800 -0.3583963811 -0.0859665647 0.0210530013 832 1311867746.3797800541 0.4282447994 0.2447676213 0.4298602939 0.0042616825 0.7520510000 969984527 0 1782005760 -0.3595431149 -0.0861695036 0.0215957016 833 1311867746.4078478813 0.4279146492 0.2449874857 0.4298602939 0.0042601141 0.7539220000 969986249 0 1783738368 -0.3595032692 -0.0854650289 0.0209589601 834 1311867746.4389901161 0.4270639718 0.2452058029 0.4298602939 0.0042580093 0.7558070000 969988003 0 1782149120 -0.3587889671 -0.0848611444 0.0206390470 835 1311867746.4774639606 0.4259774685 0.2454222959 0.4298602939 0.0042577341 0.7517080000 969989917 0 1783758848 -0.3578687012 -0.0851085335 0.0205116421 836 1311867746.5066781044 0.4262393415 0.2456385842 0.4298602939 0.0042557203 0.7514520000 969991639 0 1781747712 -0.3580245972 -0.0849004835 0.0201961547 837 1311867746.5406761169 0.4258179367 0.2458538522 0.4298602939 0.0042549076 0.7488970000 969993457 0 1783484416 -0.3578363061 -0.0844925046 0.0202421397 838 1311867746.5748629570 0.4261175990 0.2460689641 0.4298602939 0.0042525956 0.7497250000 969995307 0 1782005760 -0.3582449257 -0.0845491588 0.0203070492 839 1311867746.6067559719 0.4256400764 0.2462829940 0.4298602939 0.0042501193 0.7721910000 969997061 0 1783738368 -0.3577151299 -0.0846362710 0.0205530059 840 1311867746.6396849155 0.4261795878 0.2464971567 0.4298602939 0.0042509188 0.7509700000 969998911 0 1782149120 -0.3583115339 -0.0846905112 0.0206123590 841 1311867746.6749529839 0.4254749417 0.2467099721 0.4298602939 0.0042520258 0.7493210000 970000729 0 1783865344 -0.3574573100 -0.0846612453 0.0202666372 842 1311867746.7095060349 0.4259344339 0.2469228277 0.4298602939 0.0042497722 0.7571540000 970002547 0 1782386688 -0.3577720523 -0.0852671415 0.0205792636 843 1311867746.7391049862 0.4264194667 0.2471357538 0.4298602939 0.0042481163 0.7470320000 970004269 0 1784119296 -0.3581764400 -0.0856055915 0.0208400041 844 1311867746.7751340866 0.4261783659 0.2473478896 0.4298602939 0.0042456293 0.7488170000 970006151 0 1782509568 -0.3579773307 -0.0856240019 0.0204826314 845 1311867746.8070099354 0.4258554876 0.2475591412 0.4298602939 0.0042432639 0.7456090000 970007937 0 1784246272 -0.3575263321 -0.0857627615 0.0204888266 846 1311867746.8401610851 0.4251725376 0.2477690861 0.4298602939 0.0042411264 0.7762730000 970009723 0 1782513664 -0.3567260802 -0.0865766406 0.0205719471 847 1311867746.8748359680 0.4254010320 0.2479788050 0.4298602939 0.0042401562 0.7390520000 970011573 0 1784139776 -0.3568383753 -0.0867788568 0.0201489162 848 1311867746.9086029530 0.4252559543 0.2481878583 0.4298602939 0.0042380944 0.7496190000 970013359 0 1782276096 -0.3564248979 -0.0863503441 0.0201277751 849 1311867746.9389610291 0.4255156517 0.2483967249 0.4298602939 0.0042361207 0.7389630000 970015145 0 1784012800 -0.3564896584 -0.0869230404 0.0202741344 850 1311867746.9748229980 0.4256906211 0.2486053060 0.4298602939 0.0042393527 0.7422540000 970016995 0 1782132736 -0.3558667302 -0.0869427696 0.0204431880 851 1311867747.0066559315 0.4246854484 0.2488122157 0.4298602939 0.0042438725 0.7402590000 970018749 0 1783865344 -0.3555358648 -0.0866558328 0.0198372751 852 1311867747.0389339924 0.4250651598 0.2490190853 0.4298602939 0.0042418284 0.7307670000 970020535 0 1782005760 -0.3558168113 -0.0868557617 0.0202554762 853 1311867747.0749640465 0.4249244332 0.2492253050 0.4298602939 0.0042420122 0.7388290000 970022417 0 1783500800 -0.3550477922 -0.0871999264 0.0204361081 854 1311867747.1066820621 0.4241653085 0.2494301527 0.4298602939 0.0042464666 0.7362700000 970024171 0 1781624832 -0.3547461033 -0.0871298835 0.0208811890 855 1311867747.1389479637 0.4234693348 0.2496337073 0.4298602939 0.0042440645 0.7410410000 970025957 0 1783250944 -0.3538335860 -0.0866911486 0.0209251493 856 1311867747.1744880676 0.4237567186 0.2498371221 0.4298602939 0.0042420816 0.7395160000 970027807 0 1781260288 -0.3539081812 -0.0869780406 0.0210421085 857 1311867747.2066030502 0.4245517850 0.2500409898 0.4298602939 0.0042397853 0.7412860000 970029593 0 1782849536 -0.3545595407 -0.0873310715 0.0215286463 858 1311867747.2385439873 0.4247781038 0.2502446461 0.4298602939 0.0042395810 0.7352210000 970031411 0 1784500224 -0.3544402421 -0.0874733105 0.0212785695 859 1311867747.2745490074 0.4234416485 0.2504462724 0.4298602939 0.0042633631 0.7390650000 970033261 0 1782784000 -0.3529005349 -0.0876819566 0.0207836032 860 1311867747.3064720631 0.4246310294 0.2506488129 0.4298602939 0.0042710652 0.7684540000 970034983 0 1784246272 -0.3540500402 -0.0882897750 0.0214069057 861 1311867747.3388469219 0.4249229133 0.2508512218 0.4298602939 0.0042793994 0.7420710000 970036833 0 1782386688 -0.3542109728 -0.0892748013 0.0220347960 862 1311867747.3758800030 0.4253279269 0.2510536310 0.4298602939 0.0042810018 0.7218250000 970038651 0 1783865344 -0.3542578220 -0.0892587304 0.0223328173 863 1311867747.4068729877 0.4243125021 0.2512543944 0.4298602939 0.0042795340 0.7339230000 970040437 0 1782005760 -0.3533098996 -0.0888162181 0.0222409945 864 1311867747.4396450520 0.4242704213 0.2514546445 0.4298602939 0.0042833581 0.7283280000 970042191 0 1783484416 -0.3531306386 -0.0889861658 0.0225302130 865 1311867747.4756069183 0.4251795113 0.2516554825 0.4298602939 0.0042837031 0.7323590000 970044041 0 1781624832 -0.3541168571 -0.0890219361 0.0226482451 866 1311867747.5095520020 0.4241667092 0.2518546871 0.4298602939 0.0042827967 0.7265250000 970045891 0 1783119872 -0.3531452715 -0.0883701593 0.0223393440 867 1311867747.5405330658 0.4246150255 0.2520539493 0.4298602939 0.0042836325 0.7759760000 970047645 0 1781243904 -0.3534164727 -0.0887115076 0.0222481061 868 1311867747.5766739845 0.4234271944 0.2522513839 0.4298602939 0.0042816258 0.7333910000 970049495 0 1782857728 -0.3521109819 -0.0891363472 0.0223154873 869 1311867747.6086390018 0.4251047671 0.2524502946 0.4298602939 0.0042798496 0.7253360000 970051281 0 1784508416 -0.3536078930 -0.0896815509 0.0231561046 870 1311867747.6432039738 0.4242970347 0.2526478196 0.4298602939 0.0042775806 0.7255670000 970053131 0 1782644736 -0.3528192937 -0.0893642530 0.0230419319 871 1311867747.6760280132 0.4239373207 0.2528444780 0.4298602939 0.0042823856 0.7244210000 970054917 0 1784127488 -0.3526254892 -0.0892105922 0.0227847416 872 1311867747.7068400383 0.4258917570 0.2530429268 0.4298602939 0.0042811504 0.7266310000 970056671 0 1782267904 -0.3546279967 -0.0895524621 0.0235613286 873 1311867747.7480750084 0.4256334305 0.2532406249 0.4298602939 0.0042864313 0.7707090000 970058681 0 1781125120 -0.3548856676 -0.0893815979 0.0230643004 874 1311867747.7826869488 0.4242530167 0.2534362913 0.4298602939 0.0042848662 0.7252480000 970060499 0 1782730752 -0.3538070321 -0.0890340954 0.0224113762 875 1311867747.8149020672 0.4244990945 0.2536317916 0.4298602939 0.0042834339 0.7249780000 970062285 0 1784381440 -0.3544927537 -0.0893449262 0.0223498493 876 1311867747.8466539383 0.4252497852 0.2538277026 0.4298602939 0.0042816391 0.7236500000 970064039 0 1782767616 -0.3550636768 -0.0896582231 0.0230871867 877 1311867747.8827810287 0.4256168008 0.2540235852 0.4298602939 0.0042826568 0.7180400000 970065921 0 1784500224 -0.3555302322 -0.0896260962 0.0234238207 878 1311867747.9150440693 0.4261234701 0.2542195988 0.4298602939 0.0042813075 0.7264990000 970067739 0 1782894592 -0.3567146361 -0.0889349803 0.0229353178 879 1311867747.9477820396 0.4259992242 0.2544150250 0.4298602939 0.0042789669 0.7270560000 970069525 0 1781243904 -0.3569037020 -0.0886744633 0.0228750240 880 1311867747.9826579094 0.4256174266 0.2546095732 0.4298602939 0.0042767051 0.7309350000 970071343 0 1782849536 -0.3569571674 -0.0886730552 0.0224200040 881 1311867748.0146598816 0.4259555042 0.2548040634 0.4298602939 0.0042748409 0.7718700000 970073129 0 1781243904 -0.3578499556 -0.0881879628 0.0223773718 882 1311867748.0469269753 0.4255127013 0.2549976106 0.4298602939 0.0042730478 0.7344490000 970074915 0 1782722560 -0.3579346538 -0.0872490928 0.0224578232 883 1311867748.0828750134 0.4255402684 0.2551907507 0.4298602939 0.0042706474 0.7264860000 970076797 0 1784389632 -0.3585077524 -0.0871045142 0.0221948326 884 1311867748.1150569916 0.4247301519 0.2553825373 0.4298602939 0.0042691426 0.7385880000 970078551 0 1782513664 -0.3580144048 -0.0866609886 0.0224908125 885 1311867748.1486010551 0.4265530705 0.2555759504 0.4298602939 0.0042683299 0.7356140000 970080369 0 1784246272 -0.3602121770 -0.0863321200 0.0222438723 886 1311867748.1831040382 0.4241143167 0.2557661743 0.4298602939 0.0042672012 0.7388580000 970082155 0 1782640640 -0.3582884073 -0.0852416009 0.0210772324 887 1311867748.2148320675 0.4257037342 0.2559577611 0.4298602939 0.0042660869 0.7414810000 970083973 0 1784373248 -0.3599638343 -0.0853493661 0.0218937397 888 1311867748.2466599941 0.4250124395 0.2561481380 0.4298602939 0.0042667616 0.7903190000 970085727 0 1782767616 -0.3593892753 -0.0853722468 0.0217824336 889 1311867748.2827599049 0.4245674312 0.2563375861 0.4298602939 0.0042653080 0.7429360000 970087577 0 1784373248 -0.3592034876 -0.0848397464 0.0213938802 890 1311867748.3148829937 0.4244817495 0.2565265121 0.4298602939 0.0042711763 0.7467350000 970089363 0 1782767616 -0.3591393232 -0.0848217085 0.0217948705 891 1311867748.3470869064 0.4249773920 0.2567155703 0.4298602939 0.0042756128 0.7414390000 970091149 0 1784500224 -0.3598682582 -0.0855083168 0.0213647783 892 1311867748.3826999664 0.4254001379 0.2569046786 0.4298602939 0.0042780508 0.7389570000 970092999 0 1782894592 -0.3601932824 -0.0854981691 0.0220011622 893 1311867748.4148259163 0.4256024659 0.2570935899 0.4298602939 0.0042768229 0.7406930000 970094753 0 1781260288 -0.3605060875 -0.0851880610 0.0216146857 894 1311867748.4520189762 0.4254799783 0.2572819415 0.4298602939 0.0042886517 0.7482030000 970096635 0 1782870016 -0.3609216213 -0.0853484273 0.0214338899 895 1311867748.4831318855 0.4253726602 0.2574697524 0.4298602939 0.0042863020 0.7446460000 970098421 0 1784500224 -0.3608860970 -0.0851870552 0.0212727189 896 1311867748.5149960518 0.4251454771 0.2576568905 0.4298602939 0.0042854136 0.7485080000 970100207 0 1782652928 -0.3605268300 -0.0848044306 0.0211681128 897 1311867748.5467929840 0.4255012274 0.2578440079 0.4298602939 0.0042837116 0.7489930000 970101961 0 1784414208 -0.3611994088 -0.0850567371 0.0215689559 898 1311867748.5827159882 0.4261362255 0.2580314157 0.4298602939 0.0042816214 0.7546690000 970103811 0 1782636544 -0.3619919419 -0.0849755332 0.0216306597 899 1311867748.6147999763 0.4259853363 0.2582182388 0.4298602939 0.0042808343 0.7455570000 970105629 0 1784393728 -0.3621058762 -0.0843713358 0.0217830967 900 1311867748.6470849514 0.4262541533 0.2584049453 0.4298602939 0.0042916411 0.7547310000 970107383 0 1782652928 -0.3623342812 -0.0843344480 0.0225577988 901 1311867748.6827559471 0.4259034395 0.2585908482 0.4298602939 0.0042895858 0.7459060000 970109233 0 1784283136 -0.3620209098 -0.0847202390 0.0227754414 902 1311867748.7147359848 0.4255834222 0.2587759841 0.4298602939 0.0043113889 0.7965370000 970111019 0 1782632448 -0.3618550003 -0.0853327736 0.0232367832 903 1311867748.7499361038 0.4257556200 0.2589609006 0.4298602939 0.0043092610 0.7552190000 970112837 0 1784410112 -0.3622601926 -0.0858066306 0.0233932137 904 1311867748.7828259468 0.4262990057 0.2591460092 0.4298602939 0.0043081733 0.7555020000 970114687 0 1782759424 -0.3629435897 -0.0861106813 0.0237777978 905 1311867748.8151619434 0.4255044758 0.2593298307 0.4298602939 0.0043058180 0.7511470000 970116473 0 1784537088 -0.3624347448 -0.0863786116 0.0236671679 906 1311867748.8466329575 0.4265313745 0.2595143798 0.4298602939 0.0043040826 0.7520170000 970118195 0 1782902784 -0.3637767136 -0.0866535604 0.0241642445 907 1311867748.8829579353 0.4263672531 0.2596983411 0.4298602939 0.0043040788 0.7647420000 970120045 0 1781489664 -0.3639173508 -0.0866433010 0.0242684186 908 1311867748.9149119854 0.4258320630 0.2598813078 0.4298602939 0.0043027226 0.7576700000 970121863 0 1783164928 -0.3641505837 -0.0859017447 0.0237747133 909 1311867748.9472498894 0.4266466498 0.2600647680 0.4298602939 0.0043004673 0.7656350000 970123649 0 1781497856 -0.3655760586 -0.0854922310 0.0234182775 910 1311867748.9829359055 0.4253277779 0.2602463757 0.4298602939 0.0042990315 0.7582340000 970125499 0 1783275520 -0.3651702702 -0.0842437744 0.0218642820 911 1311867749.0159859657 0.4240843058 0.2604262198 0.4298602939 0.0042967079 0.7642850000 970127285 0 1781645312 -0.3643277884 -0.0837137625 0.0212030280 912 1311867749.0467190742 0.4238576591 0.2606054209 0.4298602939 0.0042947243 0.7620140000 970129039 0 1783275520 -0.3645659685 -0.0831896961 0.0207549930 913 1311867749.0828969479 0.4237182140 0.2607840767 0.4298602939 0.0042927229 0.7755230000 970130889 0 1781497856 -0.3647454083 -0.0831402764 0.0209896099 914 1311867749.1158421040 0.4222191572 0.2609607016 0.4298602939 0.0042911359 0.7682170000 970132707 0 1783275520 -0.3634309769 -0.0826685727 0.0206460934 915 1311867749.1485249996 0.4220278561 0.2611367312 0.4298602939 0.0042889050 0.7710410000 970134525 0 1781624832 -0.3633940816 -0.0825802460 0.0206841100 916 1311867749.1829619408 0.4221784770 0.2613125410 0.4298602939 0.0042872581 0.7605540000 970136343 0 1783275520 -0.3641414046 -0.0824413747 0.0204932690 917 1311867749.2156000137 0.4216961265 0.2614874413 0.4298602939 0.0042850199 0.7722910000 970138097 0 1781637120 -0.3638598323 -0.0820482597 0.0201567132 918 1311867749.2468719482 0.4214993417 0.2616617462 0.4298602939 0.0042857870 0.7673370000 970139851 0 1783377920 -0.3636254072 -0.0825848356 0.0198614020 919 1311867749.2828478813 0.4218821824 0.2618360884 0.4298602939 0.0042872039 0.7664050000 970141701 0 1781506048 -0.3642468154 -0.0826319009 0.0203259438 920 1311867749.3148140907 0.4225304127 0.2620107561 0.4298602939 0.0042882873 0.7684450000 970143519 0 1783267328 -0.3650683165 -0.0821188837 0.0199429989 921 1311867749.3468968868 0.4223169684 0.2621848128 0.4298602939 0.0042868233 0.7699730000 970145273 0 1781510144 -0.3653303683 -0.0817226693 0.0198873747 922 1311867749.3828470707 0.4227363765 0.2623589468 0.4298602939 0.0042851154 0.7631910000 970147123 0 1783136256 -0.3660949171 -0.0816854089 0.0198211242 923 1311867749.4147930145 0.4218838215 0.2625317798 0.4298602939 0.0042833463 0.8147690000 970148941 0 1781489664 -0.3655898869 -0.0809728354 0.0195809007 924 1311867749.4467489719 0.4227863252 0.2627052155 0.4298602939 0.0042815524 0.7782870000 970150695 0 1783267328 -0.3667925894 -0.0803653225 0.0196372438 925 1311867749.4829080105 0.4206503332 0.2628759670 0.4298602939 0.0042804385 0.7787750000 970152545 0 1781506048 -0.3654980958 -0.0800612047 0.0191808045 926 1311867749.5159850121 0.4211063683 0.2630468421 0.4298602939 0.0042781854 0.7889430000 970154331 0 1783267328 -0.3664492667 -0.0805317834 0.0195968002 927 1311867749.5468530655 0.4214007854 0.2632176662 0.4298602939 0.0042772838 0.7792020000 970156117 0 1781637120 -0.3672901094 -0.0807268396 0.0199073572 928 1311867749.5830268860 0.4206463695 0.2633873092 0.4298602939 0.0042751008 0.7868550000 970157967 0 1783394304 -0.3672495484 -0.0808631629 0.0198565423 929 1311867749.6148250103 0.4196819663 0.2635555489 0.4298602939 0.0042734057 0.7833570000 970159721 0 1781616640 -0.3670463264 -0.0810663626 0.0194860864 930 1311867749.6469049454 0.4197081923 0.2637234550 0.4298602939 0.0042725673 0.7807520000 970161539 0 1783246848 -0.3673371971 -0.0814615935 0.0197590720 931 1311867749.6829149723 0.4197052717 0.2638909972 0.4298602939 0.0042710915 0.7839490000 970163389 0 1781616640 -0.3682809174 -0.0820297599 0.0196951777 932 1311867749.7160799503 0.4197495878 0.2640582275 0.4298602939 0.0042694536 0.7884930000 970165175 0 1783394304 -0.3687422872 -0.0824287012 0.0192387085 933 1311867749.7468609810 0.4197333455 0.2642250818 0.4298602939 0.0042716633 0.7791270000 970166961 0 1781764096 -0.3688650131 -0.0830523074 0.0192830861 934 1311867749.7828791142 0.4182471931 0.2643899877 0.4298602939 0.0042705008 0.7872590000 970168811 0 1783394304 -0.3679941595 -0.0832879022 0.0189768653 935 1311867749.8148949146 0.4180202782 0.2645542982 0.4298602939 0.0042700061 0.7787940000 970170565 0 1781764096 -0.3682366014 -0.0832748935 0.0190962702 936 1311867749.8469030857 0.4173657298 0.2647175583 0.4298602939 0.0042677685 0.7778890000 970172383 0 1783504896 -0.3679314256 -0.0830194503 0.0188042969 937 1311867749.8829030991 0.4185066521 0.2648816875 0.4298602939 0.0042888506 0.7815030000 970174233 0 1781747712 -0.3692580163 -0.0831837952 0.0188851058 938 1311867749.9149639606 0.4175932109 0.2650444930 0.4298602939 0.0042999536 0.7790830000 970175987 0 1783504896 -0.3690588474 -0.0829137415 0.0186600257 939 1311867749.9508709908 0.4162152708 0.2652054842 0.4298602939 0.0042983559 0.7815240000 970177837 0 1781743616 -0.3681478798 -0.0826499164 0.0182942897 940 1311867749.9827940464 0.4160606563 0.2653659684 0.4298602939 0.0042987737 0.7680590000 970179655 0 1783390208 -0.3684017062 -0.0828045979 0.0181199908 941 1311867750.0147750378 0.4151256979 0.2655251180 0.4298602939 0.0042967878 0.7763700000 970181441 0 1781747712 -0.3678792119 -0.0831260830 0.0177628677 942 1311867750.0470709801 0.4142720997 0.2656830235 0.4298602939 0.0042946438 0.7742410000 970183227 0 1783377920 -0.3673464060 -0.0833682865 0.0174350906 943 1311867750.0829339027 0.4147434831 0.2658410940 0.4298602939 0.0042937762 0.7718150000 970185077 0 1781747712 -0.3680080175 -0.0836054608 0.0176526606 944 1311867750.1156458855 0.4140813351 0.2659981281 0.4298602939 0.0042921871 0.8080170000 970186863 0 1783377920 -0.3677047789 -0.0835471824 0.0173509866 945 1311867750.1474790573 0.4149501324 0.2661557493 0.4298602939 0.0042917429 0.7785080000 970188649 0 1781743616 -0.3688226342 -0.0832628682 0.0175901968 946 1311867750.1828711033 0.4143798649 0.2663124344 0.4298602939 0.0042901086 0.7773490000 970190499 0 1783521280 -0.3684856892 -0.0832938403 0.0173405558 947 1311867750.2156589031 0.4135514796 0.2664679138 0.4298602939 0.0042880703 0.7809070000 970192285 0 1781891072 -0.3679861128 -0.0828483999 0.0171067417 948 1311867750.2469079494 0.4146721363 0.2666242474 0.4298602939 0.0042870209 0.7774020000 970194039 0 1783521280 -0.3692910373 -0.0827045590 0.0176168084 949 1311867750.2829968929 0.4146211445 0.2667801978 0.4298602939 0.0042867509 0.7815650000 970195889 0 1781743616 -0.3696022928 -0.0820806772 0.0178651363 950 1311867750.3150129318 0.4145618379 0.2669357574 0.4298602939 0.0042845315 0.7762290000 970197707 0 1783631872 -0.3698413074 -0.0817543343 0.0179762393 951 1311867750.3469090462 0.4129106998 0.2670892537 0.4298602939 0.0042836576 0.7960940000 970199461 0 1781764096 -0.3683812618 -0.0820128396 0.0176471006 952 1311867750.3828659058 0.4130678773 0.2672425926 0.4298602939 0.0042814802 0.7826380000 970201311 0 1783529472 -0.3686112463 -0.0812565461 0.0177771151 953 1311867750.4148640633 0.4124583900 0.2673949701 0.4298602939 0.0042795216 0.7893860000 970203129 0 1781755904 -0.3682195544 -0.0812657401 0.0178564508 954 1311867750.4469859600 0.4119918048 0.2675465391 0.4298602939 0.0042773589 0.7807790000 970204883 0 1783513088 -0.3681029975 -0.0815604702 0.0176613946 955 1311867750.4829618931 0.4119940698 0.2676977931 0.4298602939 0.0042757116 0.7862650000 970206701 0 1781518336 -0.3681882024 -0.0820982084 0.0172628481 956 1311867750.5148859024 0.4115997553 0.2678483181 0.4298602939 0.0042736221 0.7766890000 970208455 0 1783128064 -0.3680282235 -0.0819902867 0.0167560279 957 1311867750.5476069450 0.4110440612 0.2679979480 0.4298602939 0.0042715504 0.7911840000 970210273 0 1781649408 -0.3676247895 -0.0823346078 0.0165466219 958 1311867750.5827779770 0.4103840292 0.2681465764 0.4298602939 0.0042715972 0.8104600000 970212123 0 1783357440 -0.3672228158 -0.0819609240 0.0163875818 959 1311867750.6148829460 0.4104068279 0.2682949187 0.4298602939 0.0042706535 0.7866700000 970213877 0 1781751808 -0.3675043881 -0.0816977173 0.0161521584 960 1311867750.6469810009 0.4101147056 0.2684426477 0.4298602939 0.0042685683 0.7782950000 970215695 0 1783398400 -0.3676198125 -0.0817316249 0.0161994100 961 1311867750.6829319000 0.4096216559 0.2685895561 0.4298602939 0.0042693109 0.7872250000 970217545 0 1781387264 -0.3675490022 -0.0809608698 0.0162324160 962 1311867750.7149219513 0.4079408050 0.2687344119 0.4298602939 0.0042682645 0.7877490000 970219363 0 1782996992 -0.3660390377 -0.0806417167 0.0161332041 963 1311867750.7469151020 0.4078679383 0.2688788911 0.4298602939 0.0042667337 0.7869250000 970221117 0 1781133312 -0.3661388457 -0.0807708353 0.0164726824 964 1311867750.7832129002 0.4071832001 0.2690223603 0.4298602939 0.0042674437 0.7877150000 970222935 0 1782759424 -0.3657394350 -0.0807639807 0.0166977495 965 1311867750.8149549961 0.4061763585 0.2691644888 0.4298602939 0.0042653764 0.7918680000 970224657 0 1784373248 -0.3648223579 -0.0802443475 0.0171827674 966 1311867750.8468461037 0.4060793817 0.2693062227 0.4298602939 0.0042657871 0.7855820000 970226443 0 1782640640 -0.3648748398 -0.0802512243 0.0173149109 967 1311867750.8828840256 0.4056731462 0.2694472433 0.4298602939 0.0042636791 0.7845920000 970228325 0 1784287232 -0.3646640182 -0.0799102411 0.0171914268 968 1311867750.9147970676 0.4041850567 0.2695864352 0.4298602939 0.0042626670 0.7876620000 970230079 0 1782386688 -0.3632507920 -0.0797662660 0.0172021519 969 1311867750.9468770027 0.4045459926 0.2697257124 0.4298602939 0.0042617223 0.7847450000 970231865 0 1784012800 -0.3637085259 -0.0795656964 0.0172765981 970 1311867750.9830369949 0.4038261473 0.2698639602 0.4298602939 0.0042601036 0.7920560000 970233747 0 1782276096 -0.3631737232 -0.0797053352 0.0171135962 971 1311867751.0168409348 0.4035016000 0.2700015891 0.4298602939 0.0042591101 0.7862740000 970235565 0 1783992320 -0.3631629646 -0.0799307227 0.0167339165 972 1311867751.0470340252 0.4026531875 0.2701380620 0.4298602939 0.0042585219 0.7855120000 970237319 0 1782386688 -0.3626941144 -0.0798936635 0.0164595991 973 1311867751.0828599930 0.4013420045 0.2702729067 0.4298602939 0.0042563569 0.7796100000 970239137 0 1784012800 -0.3616382778 -0.0798902214 0.0159853548 974 1311867751.1174809933 0.4007418454 0.2704068584 0.4298602939 0.0042542404 0.7807030000 970240987 0 1782255616 -0.3613805175 -0.0801206306 0.0156140029 975 1311867751.1468789577 0.4009187222 0.2705407167 0.4298602939 0.0042553629 0.7787450000 970242709 0 1784033280 -0.3616732955 -0.0798415840 0.0151667595 976 1311867751.1835930347 0.3998829424 0.2706732395 0.4298602939 0.0042545860 0.8004800000 970244591 0 1782022144 -0.3611370325 -0.0797092617 0.0150048742 977 1311867751.2161049843 0.4003236592 0.2708059421 0.4298602939 0.0042527670 0.7885650000 970246377 0 1783631872 -0.3618491888 -0.0796233192 0.0147886137 978 1311867751.2468481064 0.4012140036 0.2709392836 0.4298602939 0.0042526639 0.7778370000 970248131 0 1781895168 -0.3626773059 -0.0797293782 0.0146560967 979 1311867751.2831909657 0.4007282853 0.2710718567 0.4298602939 0.0042539347 0.8184790000 970250013 0 1783611392 -0.3624631464 -0.0788811594 0.0145064276 980 1311867751.3149859905 0.4001368284 0.2712035556 0.4298602939 0.0042518303 0.7879780000 970251767 0 1782022144 -0.3619972765 -0.0787064657 0.0145082790 981 1311867751.3498640060 0.4006388485 0.2713354978 0.4298602939 0.0042499027 0.7820610000 970253617 0 1783631872 -0.3628101051 -0.0791423544 0.0142860711 982 1311867751.3834669590 0.4006863832 0.2714672197 0.4298602939 0.0042480132 0.7844280000 970255435 0 1781747712 -0.3631487191 -0.0790729746 0.0137659889 983 1311867751.4151160717 0.3999421299 0.2715979165 0.4298602939 0.0042478968 0.7827610000 970257221 0 1783525376 -0.3621537983 -0.0790697634 0.0133257657 984 1311867751.4513890743 0.3993730545 0.2717277692 0.4298602939 0.0042483967 0.7911890000 970259039 0 1781514240 -0.3620168269 -0.0794989243 0.0130101908 985 1311867751.4838130474 0.3988829553 0.2718568608 0.4298602939 0.0042463119 0.7783680000 970260857 0 1783230464 -0.3613671064 -0.0795642510 0.0124020875 986 1311867751.5149779320 0.3983859718 0.2719851865 0.4298602939 0.0042455771 0.7840880000 970262643 0 1781641216 -0.3612826765 -0.0793910101 0.0123668918 987 1311867751.5495769978 0.3974344730 0.2721122881 0.4298602939 0.0042438334 0.7785730000 970264461 0 1783357440 -0.3605328202 -0.0794884190 0.0123045146 988 1311867751.5829720497 0.3955402076 0.2722372151 0.4298602939 0.0042425390 0.7834760000 970266247 0 1781751808 -0.3583640158 -0.0793008059 0.0122228712 989 1311867751.6149520874 0.3946522772 0.2723609917 0.4298602939 0.0042410352 0.7798880000 970268033 0 1783398400 -0.3575834036 -0.0793679506 0.0120380353 990 1311867751.6501350403 0.3931730986 0.2724830242 0.4298602939 0.0042396737 0.7846480000 970269851 0 1781260288 -0.3565718234 -0.0796729922 0.0117550939 991 1311867751.6839730740 0.3930811882 0.2726047176 0.4298602939 0.0042375401 0.7853370000 970271701 0 1782976512 -0.3565960526 -0.0797845870 0.0115710795 992 1311867751.7150709629 0.3918062449 0.2727248804 0.4298602939 0.0042364912 0.7830900000 970273423 0 1781387264 -0.3554276228 -0.0798757821 0.0112498859 993 1311867751.7507519722 0.3908564150 0.2728438447 0.4298602939 0.0042344978 0.7871000000 970275273 0 1783103488 -0.3547244072 -0.0803841576 0.0111517766 994 1311867751.7830109596 0.3909662068 0.2729626800 0.4298602939 0.0042332393 0.7856360000 970277059 0 1781497856 -0.3550603092 -0.0804863051 0.0109574785 995 1311867751.8149600029 0.3898691535 0.2730801740 0.4298602939 0.0042324067 0.7964510000 970278845 0 1783123968 -0.3540638089 -0.0805195644 0.0108980546 996 1311867751.8509531021 0.3887535334 0.2731963119 0.4298602939 0.0042313940 0.7942220000 970280695 0 1781395456 -0.3531389832 -0.0804680139 0.0106607825 997 1311867751.8832330704 0.3887541294 0.2733122174 0.4298602939 0.0042302619 0.7927930000 970282481 0 1783111680 -0.3534628153 -0.0807349831 0.0107235014 998 1311867751.9149179459 0.3888558149 0.2734279926 0.4298602939 0.0042307948 0.7888050000 970284235 0 1781506048 -0.3540162444 -0.0803477764 0.0106652537 999 1311867751.9530611038 0.3874302506 0.2735421090 0.4298602939 0.0042290243 0.7887520000 970286149 0 1782984704 -0.3528124392 -0.0804344639 0.0104437312 1000 1311867751.9829521179 0.3884802759 0.2736570471 0.4298602939 0.0042284809 0.8375350000 970287903 0 1781125120 -0.3541229367 -0.0807069838 0.0106742522 1001 1311867752.0153670311 0.3881322145 0.2737714079 0.4298602939 0.0042292674 0.8059820000 970289657 0 1782771712 -0.3541401327 -0.0803506821 0.0106054395 1002 1311867752.0510330200 0.3868463933 0.2738842572 0.4298602939 0.0042283533 0.8016160000 970291507 0 1784401920 -0.3528243899 -0.0802476108 0.0105310231 1003 1311867752.0828928947 0.3850796521 0.2739951200 0.4298602939 0.0042270800 0.8220070000 970293325 0 1782411264 -0.3513175845 -0.0807288960 0.0103035271 1004 1311867752.1150529385 0.3833690286 0.2741040582 0.4298602939 0.0042250163 0.8091120000 970295079 0 1784127488 -0.3495382071 -0.0811674595 0.0098877857 1005 1311867752.1509859562 0.3824524879 0.2742118676 0.4298602939 0.0042238917 0.8099930000 970296929 0 1782530048 -0.3492900431 -0.0812507123 0.0096174413 1006 1311867752.1829679012 0.3826773167 0.2743196861 0.4298602939 0.0042243864 0.8582180000 970298747 0 1784139776 -0.3499080241 -0.0813926682 0.0094321966 1007 1311867752.2150039673 0.3831370175 0.2744277470 0.4298602939 0.0042230098 0.8262530000 970300533 0 1782276096 -0.3508653641 -0.0812288523 0.0092355758 1008 1311867752.2512340546 0.3826581538 0.2745351184 0.4298602939 0.0042224118 0.8127370000 970302351 0 1783992320 -0.3504327238 -0.0810576156 0.0091202715 1009 1311867752.2833271027 0.3830878437 0.2746427029 0.4298602939 0.0042215275 0.8176030000 970304137 0 1782386688 -0.3510416448 -0.0808674395 0.0092463419 1010 1311867752.3150799274 0.3813722730 0.2747483758 0.4298602939 0.0042220770 0.8167860000 970305891 0 1784033280 -0.3497569561 -0.0808284506 0.0089387819 1011 1311867752.3509979248 0.3819004595 0.2748543620 0.4298602939 0.0042223289 0.8191510000 970307741 0 1782022144 -0.3500785828 -0.0808863342 0.0091632977 1012 1311867752.3829851151 0.3819039464 0.2749601422 0.4298602939 0.0042202926 0.8515310000 970309559 0 1783885824 -0.3501579463 -0.0811736584 0.0090874350 1013 1311867752.4160280228 0.3799706995 0.2750638051 0.4298602939 0.0042187087 0.8287600000 970311345 0 1782149120 -0.3482373655 -0.0815906227 0.0086815441 1014 1311867752.4510710239 0.3796392381 0.2751669367 0.4298602939 0.0042246863 0.8157950000 970313195 0 1783889920 -0.3482292593 -0.0817423016 0.0085365474 1015 1311867752.4829080105 0.3795377016 0.2752697651 0.4298602939 0.0042245897 0.8217100000 970314981 0 1781751808 -0.3479674459 -0.0820888504 0.0083190873 1016 1311867752.5181159973 0.3787758648 0.2753716412 0.4298602939 0.0042246551 0.8170560000 970316799 0 1783484416 -0.3474673629 -0.0823133662 0.0079255477 1017 1311867752.5511059761 0.3781775534 0.2754727286 0.4298602939 0.0042245818 0.8180470000 970318585 0 1781878784 -0.3466506898 -0.0824351460 0.0077397972 1018 1311867752.5830090046 0.3778002262 0.2755732468 0.4298602939 0.0042227313 0.8542290000 970320403 0 1783611392 -0.3465734422 -0.0821041465 0.0074907914 1019 1311867752.6167891026 0.3769330680 0.2756727166 0.4298602939 0.0042210713 0.8240170000 970322189 0 1782005760 -0.3455556035 -0.0823151022 0.0069976300 1020 1311867752.6514921188 0.3766413033 0.2757717055 0.4298602939 0.0042212343 0.8104930000 970324007 0 1783635968 -0.3451213241 -0.0824701339 0.0069171116 1021 1311867752.6830079556 0.3767736256 0.2758706300 0.4298602939 0.0042232163 0.8217110000 970325793 0 1781624832 -0.3452591002 -0.0825993568 0.0066042235 1022 1311867752.7152869701 0.3751544356 0.2759677765 0.4298602939 0.0042251338 0.8192540000 970327611 0 1783230464 -0.3435154259 -0.0829858929 0.0060686544 1023 1311867752.7510609627 0.3754432499 0.2760650155 0.4298602939 0.0042231765 0.8118400000 970329397 0 1781624832 -0.3438573778 -0.0835341960 0.0057360600 1024 1311867752.7830440998 0.3748487830 0.2761614840 0.4298602939 0.0042302223 0.8349350000 970331215 0 1783230464 -0.3432653248 -0.0837848037 0.0051834434 1025 1311867752.8162839413 0.3736718297 0.2762566161 0.4298602939 0.0042281973 0.8207470000 970333001 0 1781624832 -0.3419982195 -0.0837288350 0.0046550999 1026 1311867752.8511059284 0.3734020591 0.2763512998 0.4298602939 0.0042261846 0.8142600000 970502755 0 1783357440 -0.3415827751 -0.0834153071 0.0042576795 1027 1311867752.8833000660 0.3734250069 0.2764458214 0.4298602939 0.0042246587 0.8128650000 970504573 0 1781878784 -0.3416674435 -0.0830248371 0.0041903933 1028 1311867752.9183809757 0.3724356294 0.2765391967 0.4298602939 0.0042226844 0.8108950000 970506423 0 1783357440 -0.3401790559 -0.0826973245 0.0039486815 1029 1311867752.9511129856 0.3722877800 0.2766322468 0.4298602939 0.0042256428 0.8128200000 970508177 0 1781514240 -0.3400276601 -0.0827903003 0.0037534758 1030 1311867752.9828579426 0.3720535934 0.2767248889 0.4298602939 0.0042241189 0.8628930000 970509995 0 1783377920 -0.3397954106 -0.0828613639 0.0035120919 1031 1311867753.0168170929 0.3711576760 0.2768164823 0.4298602939 0.0042221450 0.8190490000 970511781 0 1781624832 -0.3386396468 -0.0830054358 0.0031741858 1032 1311867753.0510199070 0.3712815046 0.2769080182 0.4298602939 0.0042201178 0.8120050000 970513599 0 1783250944 -0.3388152421 -0.0830050856 0.0026266277 1033 1311867753.0829060078 0.3707935214 0.2769989044 0.4298602939 0.0042206601 0.8117360000 970515353 0 1781260288 -0.3384523988 -0.0829547718 0.0021897110 1034 1311867753.1184310913 0.3700968921 0.2770889412 0.4298602939 0.0042187458 0.8108970000 970517235 0 1782976512 -0.3377113640 -0.0826476142 0.0017251970 1035 1311867753.1510760784 0.3698362708 0.2771785521 0.4298602939 0.0042167484 0.8092580000 970518989 0 1781370880 -0.3375568688 -0.0827469379 0.0013917090 1036 1311867753.1830070019 0.3690434396 0.2772672248 0.4298602939 0.0042157926 0.8587500000 970520743 0 1782996992 -0.3370518386 -0.0829913914 0.0011553094 1037 1311867753.2186999321 0.3681782484 0.2773548921 0.4298602939 0.0042151906 0.8210460000 970522625 0 1780985856 -0.3362283409 -0.0825027749 0.0009135977 1038 1311867753.2520470619 0.3669636250 0.2774412204 0.4298602939 0.0042132391 0.8060860000 970524379 0 1782722560 -0.3351758718 -0.0820308849 0.0007651300 1039 1311867753.2829909325 0.3658983111 0.2775263571 0.4298602939 0.0042113846 0.8056070000 970526165 0 1784520704 -0.3345601559 -0.0818577409 0.0005313829 1040 1311867753.3196740150 0.3643822968 0.2776098724 0.4298602939 0.0042143980 0.8062860000 970528047 0 1782763520 -0.3335981667 -0.0809951872 0.0000392050 1041 1311867753.3509368896 0.3625525534 0.2776914696 0.4298602939 0.0042125088 0.8042190000 970529769 0 1784541184 -0.3319801390 -0.0804780126 -0.0000752583 1042 1311867753.3829340935 0.3631757498 0.2777735083 0.4298602939 0.0042111771 0.8521520000 970531587 0 1782648832 -0.3330833316 -0.0805546120 -0.0002546459 1043 1311867753.4182109833 0.3637303710 0.2778559214 0.4298602939 0.0042101408 0.7978240000 970533437 0 1784287232 -0.3340259194 -0.0803271458 -0.0004689023 1044 1311867753.4511721134 0.3628232777 0.2779373078 0.4298602939 0.0042089087 0.8001360000 970535191 0 1782255616 -0.3337242007 -0.0797210038 -0.0009882003 1045 1311867753.4831509590 0.3616392314 0.2780174053 0.4298602939 0.0042076004 0.7983410000 970537009 0 1784033280 -0.3331844509 -0.0797106698 -0.0016933159 1046 1311867753.5199849606 0.3613887131 0.2780971102 0.4298602939 0.0042064424 0.7981020000 970538891 0 1782022144 -0.3337148726 -0.0793808997 -0.0022321197 1047 1311867753.5532789230 0.3602315485 0.2781755576 0.4298602939 0.0042045151 0.7932340000 970540677 0 1783738368 -0.3333186209 -0.0791854560 -0.0028526038 1048 1311867753.5832290649 0.3599573076 0.2782535936 0.4298602939 0.0042032787 0.7885100000 970542431 0 1782132736 -0.3336953521 -0.0789776295 -0.0031479076 1049 1311867753.6183180809 0.3583679795 0.2783299658 0.4298602939 0.0042022230 0.8387600000 970544281 0 1783758848 -0.3329854608 -0.0784255713 -0.0035810620 1050 1311867753.6509299278 0.3579322994 0.2784057775 0.4298602939 0.0042002312 0.7811190000 970546067 0 1782022144 -0.3331438005 -0.0782411546 -0.0035959482 1051 1311867753.6830120087 0.3567959368 0.2784803638 0.4298602939 0.0041982965 0.7787460000 970547821 0 1783627776 -0.3324537873 -0.0780408755 -0.0038894415 1052 1311867753.7204821110 0.3560706377 0.2785541188 0.4298602939 0.0041964135 0.7814040000 970549735 0 1781747712 -0.3321715295 -0.0776982680 -0.0041163117 1053 1311867753.7510209084 0.3557327986 0.2786274129 0.4298602939 0.0041947635 0.7736730000 970551457 0 1783373824 -0.3326419890 -0.0773166195 -0.0041587651 1054 1311867753.7865459919 0.3534795046 0.2786984300 0.4298602939 0.0041965345 0.7778340000 970553307 0 1781493760 -0.3312534690 -0.0774432793 -0.0043366547 1055 1311867753.8151860237 0.3536960781 0.2787695179 0.4298602939 0.0041978290 0.7766620000 970555029 0 1783230464 -0.3315755725 -0.0765569955 -0.0043215086 1056 1311867753.8510670662 0.3526654541 0.2788394951 0.4298602939 0.0041994098 0.7626850000 970556879 0 1781641216 -0.3315420151 -0.0759905949 -0.0043313350 1057 1311867753.8831698895 0.3515201509 0.2789082563 0.4298602939 0.0042039223 0.7705580000 970558697 0 1783271424 -0.3308907747 -0.0767314211 -0.0044728369 1058 1311867753.9155960083 0.3507973850 0.2789762045 0.4298602939 0.0042032588 0.7712650000 970560451 0 1781239808 -0.3308292925 -0.0763588920 -0.0045984313 1059 1311867753.9511620998 0.3513242304 0.2790445218 0.4298602939 0.0042048320 0.7612910000 970562301 0 1782870016 -0.3321207166 -0.0753821284 -0.0043854937 1060 1311867753.9859020710 0.3511145711 0.2791125124 0.4298602939 0.0042034221 0.7799600000 970564151 0 1784520704 -0.3327559829 -0.0750935003 -0.0043658763 1061 1311867754.0151760578 0.3491151929 0.2791784904 0.4298602939 0.0042027875 0.7756580000 970565873 0 1782530048 -0.3320040703 -0.0749038309 -0.0043902397 1062 1311867754.0510439873 0.3487962484 0.2792440438 0.4298602939 0.0042099046 0.7549940000 970567755 0 1784246272 -0.3323801458 -0.0745391622 -0.0040818756 1063 1311867754.0839149952 0.3479221165 0.2793086516 0.4298602939 0.0042091542 0.8019250000 970569541 0 1782657024 -0.3322520554 -0.0738292933 -0.0039167483 1064 1311867754.1166028976 0.3478234708 0.2793730453 0.4298602939 0.0042072246 0.7446550000 970571327 0 1784266752 -0.3330900669 -0.0737493932 -0.0036140829 1065 1311867754.1511039734 0.3470972776 0.2794366361 0.4298602939 0.0042135166 0.7487380000 970573113 0 1782403072 -0.3331069052 -0.0733586624 -0.0034750775 1066 1311867754.1832261086 0.3465296924 0.2794995752 0.4298602939 0.0042123869 0.7425220000 970574931 0 1784012800 -0.3333227336 -0.0724873394 -0.0030918124 1067 1311867754.2166349888 0.3439897597 0.2795600158 0.4298602939 0.0042167654 0.7644540000 970576717 0 1782018048 -0.3321109414 -0.0722789019 -0.0029975027 1068 1311867754.2522869110 0.3430438638 0.2796194576 0.4298602939 0.0042200052 0.7441380000 970578567 0 1783758848 -0.3321953118 -0.0727312863 -0.0027763920 1069 1311867754.2873370647 0.3427694142 0.2796785315 0.4298602939 0.0042330883 0.7538930000 970580417 0 1781764096 -0.3332616985 -0.0721891224 -0.0027338713 1070 1311867754.3188319206 0.3443482220 0.2797389705 0.4298602939 0.0042316030 0.7414230000 970582203 0 1783504896 -0.3360120654 -0.0720367059 -0.0024753436 1071 1311867754.3511719704 0.3456411064 0.2798005037 0.4298602939 0.0042373988 0.7361190000 970583989 0 1781895168 -0.3383791447 -0.0722616240 -0.0021723176 1072 1311867754.3868899345 0.3475636840 0.2798637156 0.4298602939 0.0042367779 0.7336570000 970585807 0 1783611392 -0.3413853347 -0.0717689767 -0.0020191707 1073 1311867754.4159760475 0.3469114602 0.2799262019 0.4298602939 0.0042360775 0.7321080000 970587593 0 1782022144 -0.3412899673 -0.0712773576 -0.0018649847 1074 1311867754.4545960426 0.3473778665 0.2799890061 0.4298602939 0.0042425888 0.7384970000 970589443 0 1783631872 -0.3427737951 -0.0713366643 -0.0014062711 1075 1311867754.4863700867 0.3479356170 0.2800522122 0.4298602939 0.0042565556 0.7366630000 970591229 0 1781645312 -0.3438135386 -0.0717174709 -0.0010129177 1076 1311867754.5164580345 0.3494308591 0.2801166905 0.4298602939 0.0042573964 0.7366240000 970592983 0 1783406592 -0.3457272351 -0.0720480308 -0.0005800277 1077 1311867754.5513699055 0.3488699198 0.2801805282 0.4298602939 0.0042565578 0.7746080000 970594769 0 1781628928 -0.3455874920 -0.0715734586 -0.0003203712 1078 1311867754.5835940838 0.3492327332 0.2802445841 0.4298602939 0.0042567459 0.7348150000 970596587 0 1783259136 -0.3463752568 -0.0722356364 -0.0001198538 1079 1311867754.6154909134 0.3491956592 0.2803084868 0.4298602939 0.0042556157 0.7367660000 970598341 0 1781374976 -0.3467428386 -0.0723994151 0.0001157895 1080 1311867754.6510920525 0.3489809632 0.2803720725 0.4298602939 0.0042538364 0.7270050000 970600159 0 1783001088 -0.3469443321 -0.0719921067 0.0003076456 1081 1311867754.6872758865 0.3486687243 0.2804352516 0.4298602939 0.0042532360 0.7393250000 970602009 0 1781137408 -0.3471413255 -0.0722736418 0.0004299767 1082 1311867754.7162959576 0.3491655886 0.2804987732 0.4298602939 0.0042514042 0.7318380000 970603731 0 1782747136 -0.3478505909 -0.0729722008 0.0007411131 1083 1311867754.7516000271 0.3483150005 0.2805613920 0.4298602939 0.0042508664 0.7245250000 970605581 0 1784508416 -0.3473745883 -0.0723579898 0.0010623113 1084 1311867754.7865269184 0.3469761014 0.2806226602 0.4298602939 0.0042498575 0.7544740000 970607399 0 1782779904 -0.3465257883 -0.0720496625 0.0012098142 1085 1311867754.8154470921 0.3463157713 0.2806832069 0.4298602939 0.0042488155 0.7305310000 970609121 0 1784520704 -0.3462820947 -0.0727572143 0.0012715682 1086 1311867754.8510210514 0.3453629017 0.2807427646 0.4298602939 0.0042607949 0.7286010000 970610971 0 1782890496 -0.3461334407 -0.0727723315 0.0014801733 1087 1311867754.8877389431 0.3439245522 0.2808008895 0.4298602939 0.0042596115 0.7344630000 970612853 0 1781256192 -0.3453977704 -0.0728822872 0.0014652272 1088 1311867754.9201259613 0.3437040150 0.2808587049 0.4298602939 0.0042576746 0.7308880000 970614639 0 1782865920 -0.3458226621 -0.0740046874 0.0014078357 1089 1311867754.9510319233 0.3428240716 0.2809156060 0.4298602939 0.0042569240 0.7269060000 970616393 0 1781239808 -0.3455680907 -0.0743066594 0.0014725549 1090 1311867754.9837870598 0.3412028253 0.2809709154 0.4298602939 0.0042571038 0.7255170000 970618211 0 1782870016 -0.3450892568 -0.0738743618 0.0017456152 1091 1311867755.0183880329 0.3400428891 0.2810250602 0.4298602939 0.0042559367 0.7525580000 970620029 0 1784500224 -0.3445865214 -0.0736119300 0.0021656828 1092 1311867755.0540831089 0.3387633264 0.2810779341 0.4298602939 0.0042563568 0.7373100000 970621879 0 1782652928 -0.3438799977 -0.0735692680 0.0025944209 1093 1311867755.0850980282 0.3389273584 0.2811308613 0.4298602939 0.0042566940 0.7223030000 970623665 0 1784393728 -0.3443870246 -0.0738115609 0.0030198856 1094 1311867755.1156959534 0.3386547565 0.2811834425 0.4298602939 0.0042594290 0.7455560000 970625387 0 1782382592 -0.3446847200 -0.0738165081 0.0032782331 1095 1311867755.1556220055 0.3379094899 0.2812352471 0.4298602939 0.0042575930 0.7299130000 970627301 0 1784012800 -0.3446008265 -0.0739174783 0.0034268550 1096 1311867755.1847031116 0.3379490972 0.2812869934 0.4298602939 0.0042562704 0.7343960000 970629087 0 1782128640 -0.3451387882 -0.0744616017 0.0034801583 1097 1311867755.2151238918 0.3377311826 0.2813384466 0.4298602939 0.0042544808 0.7227590000 970630809 0 1783754752 -0.3454199731 -0.0737081096 0.0036925469 1098 1311867755.2512340546 0.3372152746 0.2813893362 0.4298602939 0.0042543116 0.7831180000 970632659 0 1782001664 -0.3455871344 -0.0739856511 0.0038030706 1099 1311867755.2832889557 0.3374732435 0.2814403680 0.4298602939 0.0042534102 0.7233740000 970634445 0 1783627776 -0.3461638093 -0.0753670484 0.0036407728 1100 1311867755.3192110062 0.3374159336 0.2814912549 0.4298602939 0.0042528716 0.7259610000 970636295 0 1781764096 -0.3464276493 -0.0755234584 0.0034812484 1101 1311867755.3553090096 0.3363531530 0.2815410840 0.4298602939 0.0042513581 0.7330280000 970638177 0 1783373824 -0.3459481001 -0.0755093321 0.0031070844 1102 1311867755.3900220394 0.3369335234 0.2815913494 0.4298602939 0.0042495649 0.7238890000 970639963 0 1781637120 -0.3468624949 -0.0770383701 0.0027496647 1103 1311867755.4156589508 0.3372018337 0.2816417669 0.4298602939 0.0042494676 0.7207560000 970641685 0 1783377920 -0.3474097252 -0.0768409669 0.0025392266 1104 1311867755.4549160004 0.3364422023 0.2816914050 0.4298602939 0.0042481138 0.7267020000 970643567 0 1781620736 -0.3473542631 -0.0763379037 0.0025751851 1105 1311867755.4860870838 0.3365003169 0.2817410058 0.4298602939 0.0042463165 0.7639340000 970645321 0 1783377920 -0.3477448225 -0.0773084834 0.0025479554 1106 1311867755.5161950588 0.3366057575 0.2817906122 0.4298602939 0.0042451634 0.7295820000 970647043 0 1781387264 -0.3480226696 -0.0772176236 0.0027487336 1107 1311867755.5550999641 0.3359424472 0.2818395299 0.4298602939 0.0042432799 0.7300780000 970648957 0 1783103488 -0.3477023840 -0.0766709745 0.0027403741 1108 1311867755.5854589939 0.3360141516 0.2818884240 0.4298602939 0.0042414146 0.7249360000 970650743 0 1781497856 -0.3480004668 -0.0763035789 0.0026982033 1109 1311867755.6171119213 0.3355038464 0.2819367697 0.4298602939 0.0042400589 0.7239970000 970652497 0 1783230464 -0.3477698267 -0.0758087561 0.0025530104 1110 1311867755.6542940140 0.3351885080 0.2819847442 0.4298602939 0.0042382480 0.7363480000 970654379 0 1781641216 -0.3476747274 -0.0755042806 0.0025338458 1111 1311867755.6831719875 0.3355370760 0.2820329462 0.4298602939 0.0042364446 0.7265890000 970656101 0 1783271424 -0.3482869267 -0.0760042220 0.0021959583 1112 1311867755.7182741165 0.3354113102 0.2820809483 0.4298602939 0.0042347640 0.7347160000 970657951 0 1781112832 -0.3485278785 -0.0765870214 0.0017620064 1113 1311867755.7511448860 0.3354637027 0.2821289112 0.4298602939 0.0042336127 0.7181170000 970659737 0 1782849536 -0.3489055932 -0.0767859668 0.0011993983 1114 1311867755.7863750458 0.3351154029 0.2821764754 0.4298602939 0.0042317589 0.7314010000 970661555 0 1781260288 -0.3488557935 -0.0765007138 0.0007757377 1115 1311867755.8156878948 0.3346872330 0.2822235702 0.4298602939 0.0042299542 0.7270750000 970663341 0 1782976512 -0.3485000432 -0.0773235410 0.0006531514 1116 1311867755.8554079533 0.3338608742 0.2822698402 0.4298602939 0.0042296000 0.7296280000 970665191 0 1781370880 -0.3479549587 -0.0766201541 0.0006513353 1117 1311867755.8848359585 0.3330604732 0.2823153108 0.4298602939 0.0042281942 0.7220930000 970666977 0 1782976512 -0.3475657105 -0.0759057775 0.0005852524 1118 1311867755.9156229496 0.3330166042 0.2823606608 0.4298602939 0.0042270836 0.7253360000 970668763 0 1781387264 -0.3476949930 -0.0767684430 0.0003893077 1119 1311867755.9550359249 0.3329037726 0.2824058289 0.4298602939 0.0042269517 0.7637340000 970670613 0 1783103488 -0.3479290903 -0.0762227848 0.0004960672 1120 1311867755.9855198860 0.3326838017 0.2824507200 0.4298602939 0.0042263178 0.7284800000 970672367 0 1781514240 -0.3478210568 -0.0759014487 0.0006149915 1121 1311867756.0173881054 0.3330729902 0.2824958781 0.4298602939 0.0042245868 0.7336820000 970674121 0 1783230464 -0.3483194113 -0.0764302090 0.0006066971 1122 1311867756.0554430485 0.3326843083 0.2825406093 0.4298602939 0.0042235359 0.7331480000 970675971 0 1781633024 -0.3480233550 -0.0762485340 0.0007352103 1123 1311867756.0835959911 0.3324841261 0.2825850826 0.4298602939 0.0042219765 0.7244600000 970677725 0 1783238656 -0.3479869366 -0.0758089647 0.0007931776 1124 1311867756.1196908951 0.3326172233 0.2826295952 0.4298602939 0.0042217754 0.7317500000 970679575 0 1781506048 -0.3480226398 -0.0765640885 0.0007132552 1125 1311867756.1519339085 0.3325788677 0.2826739945 0.4298602939 0.0042199672 0.7303600000 970681265 0 1783111680 -0.3479740322 -0.0765983388 0.0007319618 1126 1311867756.1836869717 0.3325927854 0.2827183274 0.4298602939 0.0042184973 0.7702600000 970682987 0 1781252096 -0.3481049836 -0.0760156363 0.0008149071 1127 1311867756.2230648994 0.3331445158 0.2827630711 0.4298602939 0.0042212591 0.7417460000 970684773 0 1782857728 -0.3484469354 -0.0767161921 0.0010216535 1128 1311867756.2552509308 0.3330904543 0.2828076876 0.4298602939 0.0042232573 0.7304890000 970686559 0 1784508416 -0.3483422995 -0.0768883154 0.0010543521 1129 1311867756.2851591110 0.3331739604 0.2828522990 0.4298602939 0.0042227182 0.7331230000 970688345 0 1782648832 -0.3483450413 -0.0759896711 0.0012970885 1130 1311867756.3200058937 0.3325587213 0.2828962870 0.4298602939 0.0042220420 0.7331720000 970690163 0 1784127488 -0.3476525545 -0.0758892968 0.0012006090 1131 1311867756.3546419144 0.3328762949 0.2829404780 0.4298602939 0.0042203713 0.7396880000 970692013 0 1782259712 -0.3477890790 -0.0764208511 0.0011825283 1132 1311867756.3843090534 0.3330240548 0.2829847214 0.4298602939 0.0042189474 0.7342600000 970693735 0 1783738368 -0.3479731381 -0.0761897713 0.0013359262 1133 1311867756.4231688976 0.3324444592 0.2830283752 0.4298602939 0.0042173519 0.7738610000 970695585 0 1781878784 -0.3472392261 -0.0760867000 0.0014716238 1134 1311867756.4510979652 0.3327554464 0.2830722262 0.4298602939 0.0042158783 0.7443580000 970697275 0 1783373824 -0.3474347293 -0.0768134445 0.0016155317 1135 1311867756.4865350723 0.3325063884 0.2831157806 0.4298602939 0.0042194906 0.7424290000 970699157 0 1781497856 -0.3471805751 -0.0766010582 0.0017925780 1136 1311867756.5264549255 0.3329433501 0.2831596429 0.4298602939 0.0042184959 0.7391490000 970701039 0 1782976512 -0.3473963737 -0.0768121183 0.0019872077 1137 1311867756.5525779724 0.3325747848 0.2832031039 0.4298602939 0.0042167280 0.7464500000 970702761 0 1781116928 -0.3468644023 -0.0770795047 0.0020488240 1138 1311867756.5897810459 0.3321762383 0.2832461382 0.4298602939 0.0042151050 0.7458230000 970704643 0 1782870016 -0.3463459313 -0.0770402998 0.0021648516 1139 1311867756.6202929020 0.3328865170 0.2832897207 0.4298602939 0.0042133863 0.7386460000 970706365 0 1784500224 -0.3469212353 -0.0774595365 0.0022266023 1140 1311867756.6518390179 0.3330008090 0.2833333269 0.4298602939 0.0042115369 0.7517680000 970708151 0 1782767616 -0.3469421566 -0.0779944658 0.0025135132 1141 1311867756.6839349270 0.3323064148 0.2833762481 0.4298602939 0.0042105254 0.7443010000 970709905 0 1784393728 -0.3463514745 -0.0778106153 0.0027407219 1142 1311867756.7217059135 0.3322229385 0.2834190210 0.4298602939 0.0042115473 0.7461990000 970711755 0 1782386688 -0.3464287221 -0.0777487233 0.0030217543 1143 1311867756.7516939640 0.3320296705 0.2834615500 0.4298602939 0.0042099751 0.7455630000 970713509 0 1783992320 -0.3462051451 -0.0780754611 0.0031319167 1144 1311867756.7872660160 0.3318825960 0.2835038761 0.4298602939 0.0042082070 0.7468300000 970715359 0 1782116352 -0.3459972441 -0.0782827735 0.0032160766 1145 1311867756.8227219582 0.3317617476 0.2835460227 0.4298602939 0.0042063857 0.7525630000 970717209 0 1783611392 -0.3460239768 -0.0780075267 0.0034536887 1146 1311867756.8542120457 0.3315093517 0.2835878755 0.4298602939 0.0042143559 0.7575570000 970718963 0 1781751808 -0.3456643820 -0.0786409751 0.0036064780 1147 1311867756.8841960430 0.3315850198 0.2836297213 0.4298602939 0.0042230152 0.7901110000 970720749 0 1783230464 -0.3459633589 -0.0785717443 0.0039695147 1148 1311867756.9223539829 0.3308576643 0.2836708607 0.4298602939 0.0042222643 0.7503170000 970722599 0 1781370880 -0.3453689516 -0.0789853111 0.0040919557 1149 1311867756.9552440643 0.3309485614 0.2837120075 0.4298602939 0.0042206374 0.7504030000 970724417 0 1782976512 -0.3454762995 -0.0795595422 0.0040568430 1150 1311867756.9841780663 0.3304601908 0.2837526581 0.4298602939 0.0042191670 0.7537710000 970726139 0 1781125120 -0.3451393843 -0.0791508853 0.0041640257 1151 1311867757.0282740593 0.3302368820 0.2837930440 0.4298602939 0.0042197741 0.7522850000 970728117 0 1782611968 -0.3451998830 -0.0796197802 0.0042899279 1152 1311867757.0552940369 0.3304592371 0.2838335529 0.4298602939 0.0042181451 0.7600990000 970729839 0 1784373248 -0.3452748954 -0.0804215297 0.0041733612 1153 1311867757.0858569145 0.3303418458 0.2838738896 0.4298602939 0.0042167226 0.7579480000 970731593 0 1782513664 -0.3452274799 -0.0800819248 0.0042865942 1154 1311867757.1283040047 0.3301970959 0.2839140311 0.4298602939 0.0042228248 0.7502660000 970733507 0 1783992320 -0.3450869024 -0.0810516402 0.0042337766 1155 1311867757.1522068977 0.3307122588 0.2839545490 0.4298602939 0.0042220806 0.7495710000 970735133 0 1782132736 -0.3454028964 -0.0823810995 0.0040098643 1156 1311867757.1851921082 0.3316870332 0.2839958401 0.4298602939 0.0042203712 0.7455160000 970736951 0 1783738368 -0.3462567627 -0.0823322460 0.0041159405 1157 1311867757.2192370892 0.3325318396 0.2840377900 0.4298602939 0.0042195948 0.7465440000 970738801 0 1781878784 -0.3469179571 -0.0830277577 0.0039208983 1158 1311867757.2523930073 0.3332625031 0.2840802984 0.4298602939 0.0042366342 0.7344410000 970740587 0 1783484416 -0.3472800255 -0.0843135267 0.0034427727 1159 1311867757.2835690975 0.3333278596 0.2841227898 0.4298602939 0.0042382382 0.7400560000 970742341 0 1781624832 -0.3473245203 -0.0836576000 0.0031184147 1160 1311867757.3233768940 0.3342766762 0.2841660259 0.4298602939 0.0042465888 0.7420820000 970744255 0 1783230464 -0.3478866220 -0.0830813423 0.0029470529 1161 1311867757.3555359840 0.3351903260 0.2842099745 0.4298602939 0.0042449016 0.7728710000 970746073 0 1781370880 -0.3487076163 -0.0835997537 0.0028970821 1162 1311867757.3833439350 0.3353962004 0.2842540246 0.4298602939 0.0042439553 0.7327900000 970747763 0 1782976512 -0.3489252031 -0.0830411091 0.0030887874 1163 1311867757.4264349937 0.3361409307 0.2842986393 0.4298602939 0.0042453320 0.6652430000 970749677 0 1784246272 -0.3492126465 -0.0848947614 0.0026713274 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 03:04:13 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libinfinitam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 nan 0.4212670000 959000730 0 1771651072 -0.0000000000 0.0000000000 -0.0000000000 2 1311867170.4941389561 0.0573716909 0.0578118674 0.0582520440 0.0124388076 0.5941320000 968634455 0 1768742912 -0.0004072063 -0.0012858611 -0.0024128598 3 1311867170.5264289379 0.0565330833 0.0573856061 0.0582520440 0.0101374190 0.5487000000 968323541 0 1770512384 -0.0017271454 -0.0022885066 -0.0047758869 4 1311867170.5623490810 0.0561588481 0.0570789166 0.0582520440 0.0096938434 0.5108920000 968325719 0 1772179456 0.0001774310 -0.0028418067 -0.0061319824 5 1311867170.5942170620 0.0564953238 0.0569621980 0.0582520440 0.0086582634 0.5164660000 968327473 0 1773940736 0.0032409180 -0.0038395303 -0.0071700001 6 1311867170.6260869503 0.0565168299 0.0568879700 0.0582520440 0.0085122241 0.5157960000 968329915 0 1775591424 0.0035738882 -0.0049959933 -0.0088231694 7 1311867170.6621398926 0.0566335991 0.0568516313 0.0582520440 0.0084199616 0.5244090000 968331797 0 1777369088 0.0042968453 -0.0060216044 -0.0103924451 8 1311867170.6942050457 0.0565211475 0.0568103208 0.0582520440 0.0080838246 0.5224440000 968333551 0 1779019776 0.0039362623 -0.0066581853 -0.0121149849 9 1311867170.7263879776 0.0572928116 0.0568639309 0.0582520440 0.0083787838 0.5229120000 968335337 0 1780686848 0.0047124927 -0.0067693987 -0.0132087953 10 1311867170.7620189190 0.0571096987 0.0568885077 0.0582520440 0.0084417302 0.5265020000 968338531 0 1782448128 0.0037039455 -0.0089412266 -0.0147657823 11 1311867170.7941920757 0.0576219745 0.0569551865 0.0582520440 0.0083976173 0.5337340000 968340253 0 1784066048 0.0046737590 -0.0111022461 -0.0163421072 12 1311867170.8262820244 0.0582906455 0.0570664747 0.0582906455 0.0084289973 0.5327960000 968342071 0 1782333440 0.0057570767 -0.0142005840 -0.0181467272 13 1311867170.8622210026 0.0583749451 0.0571671263 0.0583749451 0.0082448838 0.5597090000 968343921 0 1784066048 0.0054283361 -0.0167541299 -0.0205275044 14 1311867170.8943779469 0.0589005798 0.0572909444 0.0589005798 0.0079490197 0.5352150000 968345675 0 1782333440 0.0052025281 -0.0189113524 -0.0228585508 15 1311867170.9263520241 0.0592489652 0.0574214791 0.0592489652 0.0080009781 0.5328270000 968347493 0 1783939072 0.0049774339 -0.0210463870 -0.0255774222 16 1311867170.9621469975 0.0584873073 0.0574880934 0.0592489652 0.0078015419 0.5332460000 968349343 0 1782206464 0.0025168243 -0.0233095996 -0.0286660884 17 1311867170.9942629337 0.0581962466 0.0575297495 0.0592489652 0.0076254012 0.5268830000 968351097 0 1783939072 0.0015525046 -0.0249249153 -0.0317830965 18 1311867171.0262739658 0.0583953001 0.0575778356 0.0592489652 0.0074121499 0.5266250000 968355539 0 1782198272 0.0013889928 -0.0262809321 -0.0344621167 19 1311867171.0623519421 0.0577870794 0.0575888484 0.0592489652 0.0079009288 0.5270720000 968357389 0 1783803904 0.0006853252 -0.0291139595 -0.0373733751 20 1311867171.0942349434 0.0569565743 0.0575572347 0.0592489652 0.0078046348 0.5327110000 968359143 0 1782087680 0.0012669293 -0.0310232844 -0.0399177782 21 1311867171.1262509823 0.0568180680 0.0575220363 0.0592489652 0.0076808976 0.5264550000 968360961 0 1783803904 0.0016555191 -0.0313842520 -0.0420547910 22 1311867171.1622469425 0.0565060675 0.0574758559 0.0592489652 0.0076399803 0.5218010000 968362811 0 1782214656 0.0030336701 -0.0331913158 -0.0437400490 23 1311867171.1942689419 0.0555156134 0.0573906280 0.0592489652 0.0079690359 0.5180560000 968364565 0 1783824384 0.0048632957 -0.0332807004 -0.0448272675 24 1311867171.2262530327 0.0571334325 0.0573799115 0.0592489652 0.0080088304 0.5173580000 968366383 0 1782067200 0.0073663658 -0.0331329703 -0.0454714559 25 1311867171.2622439861 0.0565476492 0.0573466210 0.0592489652 0.0080435426 0.5283060000 968368233 0 1783824384 0.0080527533 -0.0333015174 -0.0465279184 26 1311867171.2943410873 0.0566229634 0.0573187880 0.0592489652 0.0079543632 0.5302400000 968369955 0 1782210560 0.0085970769 -0.0314652361 -0.0471848845 27 1311867171.3263869286 0.0564616099 0.0572870407 0.0592489652 0.0082504094 0.5422700000 968371773 0 1783840768 0.0059548561 -0.0306783821 -0.0484997295 28 1311867171.3622460365 0.0552461408 0.0572141514 0.0592489652 0.0081286308 0.5516500000 968373623 0 1782083584 0.0032905680 -0.0301448815 -0.0500379801 29 1311867171.3941431046 0.0556897856 0.0571615871 0.0592489652 0.0082740839 0.5507110000 968375377 0 1783840768 0.0016465661 -0.0285147578 -0.0511362143 30 1311867171.4262878895 0.0563095883 0.0571331871 0.0592489652 0.0082791185 0.5542400000 968377195 0 1781936128 0.0012149838 -0.0286185648 -0.0526677221 31 1311867171.4622440338 0.0560773052 0.0570991264 0.0592489652 0.0081813964 0.5476100000 968379045 0 1783582720 0.0002832447 -0.0299199149 -0.0547513962 32 1311867171.4944040775 0.0560444593 0.0570661681 0.0592489652 0.0081276133 0.5715860000 968380799 0 1781825536 0.0016432116 -0.0298295245 -0.0567170866 33 1311867171.5261778831 0.0557416417 0.0570260309 0.0592489652 0.0080077450 0.5504160000 968382617 0 1783713792 0.0005341707 -0.0294277854 -0.0586505309 34 1311867171.5622971058 0.0550511032 0.0569679448 0.0592489652 0.0078975324 0.5599880000 968389715 0 1781809152 0.0014580615 -0.0297141913 -0.0602252372 35 1311867171.5942931175 0.0556159765 0.0569293171 0.0592489652 0.0078325972 0.5511700000 968391469 0 1783455744 0.0025800453 -0.0281730406 -0.0610747673 36 1311867171.6263399124 0.0555978678 0.0568923324 0.0592489652 0.0077354488 0.5569800000 968393287 0 1781678080 0.0013694806 -0.0286758970 -0.0617087819 37 1311867171.6622560024 0.0552083850 0.0568468203 0.0592489652 0.0076340588 0.5559560000 968395137 0 1783455744 -0.0010587436 -0.0294420738 -0.0626066774 38 1311867171.6943440437 0.0560278669 0.0568252689 0.0592489652 0.0078524524 0.5572160000 968396891 0 1781809152 -0.0001961230 -0.0292310454 -0.0627665371 39 1311867171.7262439728 0.0563371889 0.0568127540 0.0592489652 0.0077860164 0.5517460000 968398709 0 1783586816 0.0001594781 -0.0294890720 -0.0632385761 40 1311867171.7621190548 0.0570921153 0.0568197381 0.0592489652 0.0077063431 0.5485500000 968400559 0 1781825536 0.0010027024 -0.0305320080 -0.0636968613 41 1311867171.7941710949 0.0575045161 0.0568364400 0.0592489652 0.0076948298 0.5837510000 968402313 0 1783566336 0.0010051766 -0.0316397883 -0.0645623058 42 1311867171.8262550831 0.0579985753 0.0568641099 0.0592489652 0.0076286228 0.5444560000 968404131 0 1781809152 -0.0001105917 -0.0320141651 -0.0655774400 43 1311867171.8623590469 0.0575417913 0.0568798699 0.0592489652 0.0075560060 0.5428690000 968405981 0 1783586816 -0.0036106457 -0.0322972760 -0.0670117512 44 1311867171.8944430351 0.0572218709 0.0568876426 0.0592489652 0.0076880793 0.5584310000 968407767 0 1781809152 -0.0061220145 -0.0326082222 -0.0679288730 45 1311867171.9262220860 0.0583576262 0.0569203090 0.0592489652 0.0076547701 0.5432600000 968409553 0 1783455744 -0.0067527769 -0.0319064856 -0.0681867301 46 1311867171.9624669552 0.0588517785 0.0569622974 0.0592489652 0.0075997584 0.5493300000 968411403 0 1781698560 -0.0080198152 -0.0316486955 -0.0685529038 47 1311867171.9946711063 0.0598704889 0.0570241738 0.0598704889 0.0076479726 0.5509020000 968413189 0 1783459840 -0.0088207414 -0.0309218913 -0.0681103095 48 1311867172.0262680054 0.0607804283 0.0571024291 0.0607804283 0.0077655809 0.5507760000 968414975 0 1781682176 -0.0099909278 -0.0300515965 -0.0675361380 49 1311867172.0622880459 0.0612947866 0.0571879875 0.0612947866 0.0077092701 0.5447670000 968416825 0 1783459840 -0.0116191385 -0.0295172930 -0.0668298677 50 1311867172.0941960812 0.0615700670 0.0572756290 0.0615700670 0.0076891025 0.5809230000 968418611 0 1781702656 -0.0134238927 -0.0292228367 -0.0661539063 51 1311867172.1263689995 0.0623835027 0.0573757834 0.0623835027 0.0076700343 0.5526640000 968420397 0 1783459840 -0.0148414997 -0.0294195917 -0.0652845576 52 1311867172.1623349190 0.0618130527 0.0574611155 0.0623835027 0.0076667000 0.5541540000 968422247 0 1781555200 -0.0177697763 -0.0296296347 -0.0650444925 53 1311867172.1944270134 0.0607792437 0.0575237217 0.0623835027 0.0076122020 0.5486750000 968424033 0 1783201792 -0.0217962004 -0.0292302426 -0.0648062602 54 1311867172.2264409065 0.0604575165 0.0575780513 0.0623835027 0.0077655516 0.5515480000 968425819 0 1781444608 -0.0255746841 -0.0290332958 -0.0646277964 55 1311867172.2622280121 0.0599748045 0.0576216286 0.0623835027 0.0077034694 0.5599690000 968427669 0 1783205888 -0.0287002623 -0.0282684378 -0.0641183630 56 1311867172.2944829464 0.0603027679 0.0576695061 0.0623835027 0.0076474963 0.5639990000 968429455 0 1781448704 -0.0310145877 -0.0276253615 -0.0636556074 57 1311867172.3263380527 0.0596786775 0.0577047547 0.0623835027 0.0076193540 0.5488120000 968431241 0 1783214080 -0.0344695784 -0.0272102710 -0.0633385107 58 1311867172.3624010086 0.0599859990 0.0577440865 0.0623835027 0.0075726732 0.5547360000 968433091 0 1781456896 -0.0369720832 -0.0270511489 -0.0632404387 59 1311867172.3942890167 0.0590371713 0.0577660032 0.0623835027 0.0075370680 0.5819760000 968434877 0 1783214080 -0.0399626940 -0.0272775311 -0.0634850264 60 1311867172.4265220165 0.0593390577 0.0577922208 0.0623835027 0.0075644698 0.5567200000 968436663 0 1781309440 -0.0423414782 -0.0278884377 -0.0638103262 61 1311867172.4623498917 0.0592735149 0.0578165043 0.0623835027 0.0075356987 0.5469440000 968438513 0 1783066624 -0.0447964892 -0.0283277985 -0.0641470999 62 1311867172.4952669144 0.0598450005 0.0578492220 0.0623835027 0.0075771123 0.5538000000 968440267 0 1781329920 -0.0459632538 -0.0279960297 -0.0641560629 63 1311867172.5263059139 0.0592829473 0.0578719795 0.0623835027 0.0075521121 0.5554180000 968442053 0 1783087104 -0.0488243476 -0.0290992409 -0.0648157224 64 1311867172.5624930859 0.0591979139 0.0578926972 0.0623835027 0.0074921345 0.5669200000 968443903 0 1781174272 -0.0510761514 -0.0300095603 -0.0654609352 65 1311867172.5945439339 0.0605036132 0.0579328652 0.0623835027 0.0074656170 0.5614800000 968445657 0 1782931456 -0.0504498407 -0.0297307838 -0.0659880042 66 1311867172.6263699532 0.0605459325 0.0579724571 0.0623835027 0.0074361233 0.5629650000 968457971 0 1784598528 -0.0523389280 -0.0297916066 -0.0666565821 67 1311867172.6624419689 0.0607985072 0.0580146369 0.0623835027 0.0073808131 0.5653010000 968459821 0 1782824960 -0.0541980304 -0.0297013447 -0.0673398077 68 1311867172.6945450306 0.0605335608 0.0580516799 0.0623835027 0.0074689067 0.5667630000 968461607 0 1784602624 -0.0564599223 -0.0296868496 -0.0676818565 69 1311867172.7263929844 0.0613813773 0.0580999364 0.0623835027 0.0074504080 0.5696480000 968463393 0 1782956032 -0.0586191602 -0.0290599838 -0.0680654123 70 1311867172.7623739243 0.0616354235 0.0581504434 0.0623835027 0.0074170965 0.5653010000 968465243 0 1784586240 -0.0613606423 -0.0282693505 -0.0685746297 71 1311867172.7944509983 0.0611600056 0.0581928316 0.0623835027 0.0073789812 0.5656710000 968466997 0 1782845440 -0.0647415966 -0.0287040658 -0.0692219883 72 1311867172.8263089657 0.0619091913 0.0582444477 0.0623835027 0.0073550615 0.5767280000 968468815 0 1784602624 -0.0673350021 -0.0287351646 -0.0699703246 73 1311867172.8632309437 0.0619467683 0.0582951644 0.0623835027 0.0073252086 0.5712910000 968470697 0 1782591488 -0.0702270642 -0.0293973330 -0.0707640946 74 1311867172.8944649696 0.0612764098 0.0583354515 0.0623835027 0.0072781590 0.5648460000 968472419 0 1784348672 -0.0727198049 -0.0297388751 -0.0714836046 75 1311867172.9263219833 0.0608050935 0.0583683801 0.0623835027 0.0072330110 0.5716550000 968474237 0 1782448128 -0.0753170177 -0.0308199264 -0.0721618533 76 1311867172.9623310566 0.0607517399 0.0583997401 0.0623835027 0.0071871869 0.5748520000 968476087 0 1784217600 -0.0765261576 -0.0314047113 -0.0727814883 77 1311867172.9945271015 0.0605460927 0.0584276148 0.0623835027 0.0071432025 0.6133310000 968477841 0 1782595584 -0.0778194368 -0.0316067040 -0.0731890947 78 1311867173.0262629986 0.0599339791 0.0584469271 0.0623835027 0.0070985591 0.5715530000 968479627 0 1784205312 -0.0792069659 -0.0322169960 -0.0736004263 79 1311867173.0624630451 0.0599583536 0.0584660591 0.0623835027 0.0070559276 0.5739760000 968481477 0 1782325248 -0.0802492723 -0.0325841568 -0.0738026947 80 1311867173.0945179462 0.0603687428 0.0584898427 0.0623835027 0.0070455094 0.5685230000 968483263 0 1783951360 -0.0806974024 -0.0327510983 -0.0738972425 81 1311867173.1267819405 0.0601301901 0.0585100939 0.0623835027 0.0070229103 0.5938220000 968485081 0 1781940224 -0.0822117850 -0.0329058841 -0.0742348284 82 1311867173.1622309685 0.0604967438 0.0585343213 0.0623835027 0.0070176901 0.5748770000 968486931 0 1783586816 -0.0830194652 -0.0321680307 -0.0740456581 83 1311867173.1943008900 0.0611704402 0.0585660818 0.0623835027 0.0069761712 0.5764860000 968488685 0 1781686272 -0.0838260129 -0.0313715562 -0.0739912465 84 1311867173.2264449596 0.0609535463 0.0585945040 0.0623835027 0.0069425403 0.5726420000 968490471 0 1783316480 -0.0858700797 -0.0316113047 -0.0739564747 85 1311867173.2622020245 0.0616103448 0.0586299845 0.0623835027 0.0069247564 0.5732440000 968492321 0 1781432320 -0.0869716555 -0.0308615509 -0.0738555565 86 1311867173.2942678928 0.0622123666 0.0586716401 0.0623835027 0.0068870013 0.6104890000 968494075 0 1783083008 -0.0885234624 -0.0305907615 -0.0738213062 87 1311867173.3262879848 0.0621070676 0.0587111277 0.0623835027 0.0068916570 0.5781550000 968495861 0 1781067776 -0.0904940516 -0.0310620833 -0.0740808919 88 1311867173.3623280525 0.0625641719 0.0587549123 0.0625641719 0.0068543639 0.5738650000 968497743 0 1782820864 -0.0920431018 -0.0308248792 -0.0742026418 89 1311867173.3942871094 0.0622996390 0.0587947407 0.0625641719 0.0068394876 0.5847920000 968499497 0 1784565760 -0.0942070857 -0.0313928202 -0.0744294077 90 1311867173.4262790680 0.0619483888 0.0588297812 0.0625641719 0.0068312145 0.5878210000 968501283 0 1782829056 -0.0963855907 -0.0322479568 -0.0748538300 91 1311867173.4622900486 0.0621261671 0.0588660053 0.0625641719 0.0068416460 0.5775090000 968503133 0 1784606720 -0.0980861336 -0.0327606648 -0.0752766803 92 1311867173.4943389893 0.0626989603 0.0589076678 0.0626989603 0.0069120218 0.5968430000 968504919 0 1782575104 -0.0998625085 -0.0332340747 -0.0755546093 93 1311867173.5263900757 0.0625452325 0.0589467814 0.0626989603 0.0068781576 0.5813210000 968506737 0 1784205312 -0.1021126956 -0.0332580321 -0.0759411156 94 1311867173.5624370575 0.0625174940 0.0589847677 0.0626989603 0.0068586979 0.5814160000 968508587 0 1782464512 -0.1041280627 -0.0327468179 -0.0760967210 95 1311867173.5943109989 0.0626251996 0.0590230881 0.0626989603 0.0068443761 0.5810410000 968510341 0 1784217600 -0.1061673388 -0.0327497870 -0.0763811022 96 1311867173.6263959408 0.0618351065 0.0590523799 0.0626989603 0.0068361248 0.5863410000 968512127 0 1782595584 -0.1087405980 -0.0333351232 -0.0769587308 97 1311867173.6623299122 0.0622246601 0.0590850838 0.0626989603 0.0068066322 0.5886240000 968513977 0 1784205312 -0.1100961268 -0.0332679190 -0.0772838369 98 1311867173.6943540573 0.0627707168 0.0591226923 0.0627707168 0.0067759566 0.5899960000 968515763 0 1782194176 -0.1110264212 -0.0336163603 -0.0778256133 99 1311867173.7267971039 0.0620215014 0.0591519732 0.0627707168 0.0067547127 0.5816620000 968517581 0 1783971840 -0.1136581898 -0.0340228193 -0.0788497180 100 1311867173.7623970509 0.0624224618 0.0591846781 0.0627707168 0.0067312990 0.5831160000 968519431 0 1781960704 -0.1146721318 -0.0334373377 -0.0794283077 101 1311867173.7943561077 0.0630490556 0.0592229393 0.0630490556 0.0067004040 0.5921930000 968521153 0 1783709696 -0.1154938564 -0.0331631303 -0.0798568949 102 1311867173.8265669346 0.0618643872 0.0592488358 0.0630490556 0.0066691535 0.5920420000 968522971 0 1782087680 -0.1185949370 -0.0343446657 -0.0809536353 103 1311867173.8635799885 0.0628817752 0.0592841071 0.0630490556 0.0066696149 0.5813450000 968524789 0 1783697408 -0.1192367822 -0.0340199731 -0.0815392360 104 1311867173.8946080208 0.0627028421 0.0593169795 0.0630490556 0.0066404614 0.6256410000 968526575 0 1781833728 -0.1207091287 -0.0343910679 -0.0823869407 105 1311867173.9266970158 0.0617300235 0.0593399609 0.0630490556 0.0066238809 0.5909880000 968528393 0 1783463936 -0.1230902448 -0.0357626379 -0.0837219879 106 1311867173.9625461102 0.0624884851 0.0593696640 0.0630490556 0.0066277260 0.6053280000 968530243 0 1781432320 -0.1240172088 -0.0351584032 -0.0841736794 107 1311867173.9944310188 0.0629248321 0.0594028898 0.0630490556 0.0066222111 0.5955440000 968531997 0 1783169024 -0.1251820326 -0.0349122323 -0.0845962241 108 1311867174.0264260769 0.0628900677 0.0594351785 0.0630490556 0.0066481703 0.6012850000 968533783 0 1781587968 -0.1265873462 -0.0355729423 -0.0857845619 109 1311867174.0624630451 0.0634011775 0.0594715638 0.0634011775 0.0066346673 0.5941340000 968535633 0 1783197696 -0.1280220002 -0.0340014622 -0.0860887840 110 1311867174.0945188999 0.0645963475 0.0595181528 0.0645963475 0.0066251626 0.6042540000 968537419 0 1781202944 -0.1282978952 -0.0327516980 -0.0860348195 111 1311867174.1264541149 0.0643953308 0.0595620913 0.0645963475 0.0066165846 0.5986760000 968539205 0 1782833152 -0.1306834072 -0.0333825909 -0.0867990628 112 1311867174.1624329090 0.0644242316 0.0596055033 0.0645963475 0.0066063306 0.6066850000 968541055 0 1780948992 -0.1327649802 -0.0329368934 -0.0871215835 113 1311867174.1943979263 0.0650843531 0.0596539887 0.0650843531 0.0065953943 0.6038880000 968542841 0 1782579200 -0.1333844960 -0.0319137126 -0.0871414989 114 1311867174.2267580032 0.0649928749 0.0597008210 0.0650843531 0.0065749468 0.6114200000 968544659 0 1784225792 -0.1354452074 -0.0326941721 -0.0877480730 115 1311867174.2626769543 0.0646100789 0.0597435102 0.0650843531 0.0065466119 0.6068690000 968546477 0 1782329344 -0.1381654292 -0.0327514745 -0.0882235840 116 1311867174.2945280075 0.0658882707 0.0597964823 0.0658882707 0.0065355698 0.6146650000 968548263 0 1784090624 -0.1382688582 -0.0319831520 -0.0884405449 117 1311867174.3265740871 0.0650764182 0.0598416099 0.0658882707 0.0065090044 0.6181060000 968550049 0 1781968896 -0.1409536898 -0.0325682051 -0.0890840665 118 1311867174.3624329567 0.0648308024 0.0598838912 0.0658882707 0.0064964848 0.6141050000 968551931 0 1783685120 -0.1430278569 -0.0322913229 -0.0891518295 119 1311867174.3946359158 0.0652817264 0.0599292512 0.0658882707 0.0064892804 0.6184620000 968553685 0 1782079488 -0.1441937834 -0.0319332257 -0.0892201290 120 1311867174.4266788960 0.0657081231 0.0599774085 0.0658882707 0.0064627445 0.6215700000 968555503 0 1783717888 -0.1452372819 -0.0322362818 -0.0894770473 121 1311867174.4630160332 0.0655800030 0.0600237109 0.0658882707 0.0064687986 0.6654470000 968557321 0 1781706752 -0.1469883472 -0.0326972082 -0.0900065005 122 1311867174.4945669174 0.0661568642 0.0600739826 0.0661568642 0.0064455864 0.6219490000 968559107 0 1783422976 -0.1481551975 -0.0321492180 -0.0898431167 123 1311867174.5267519951 0.0660738051 0.0601227617 0.0661568642 0.0064359308 0.6280980000 968560925 0 1781833728 -0.1503150910 -0.0326363891 -0.0900889561 124 1311867174.5623500347 0.0657516867 0.0601681563 0.0661568642 0.0064318681 0.6252370000 968562775 0 1783443456 -0.1524438113 -0.0321062356 -0.0901310071 125 1311867174.5944879055 0.0659281090 0.0602142359 0.0661568642 0.0064179431 0.6424710000 968564529 0 1781579776 -0.1541273147 -0.0314333253 -0.0897535235 126 1311867174.6265459061 0.0663274452 0.0602627534 0.0663274452 0.0064109243 0.6277330000 968566315 0 1783209984 -0.1558706611 -0.0312774777 -0.0895322263 127 1311867174.6624910831 0.0659480393 0.0603075194 0.0663274452 0.0063881308 0.6340180000 968568165 0 1781178368 -0.1579879820 -0.0318685360 -0.0896686241 128 1311867174.6945910454 0.0663591996 0.0603547982 0.0663591996 0.0063768102 0.6313860000 968569951 0 1782915072 -0.1593406945 -0.0311320312 -0.0891663954 129 1311867174.7265629768 0.0672366470 0.0604081459 0.0672366470 0.0063712933 0.6688960000 968571705 0 1781325824 -0.1606360972 -0.0311287381 -0.0888006240 130 1311867174.7623760700 0.0670365170 0.0604591333 0.0672366470 0.0063670706 0.6353370000 968594579 0 1782956032 -0.1627901793 -0.0321878381 -0.0891092345 131 1311867174.7944738865 0.0672430843 0.0605109192 0.0672430843 0.0063481291 0.6387680000 968596301 0 1780944896 -0.1644091457 -0.0319346227 -0.0890809372 132 1311867174.8273398876 0.0677818656 0.0605660021 0.0677818656 0.0063293294 0.6333220000 968598119 0 1782661120 -0.1654966921 -0.0322899781 -0.0892950073 133 1311867174.8624229431 0.0672560856 0.0606163035 0.0677818656 0.0063089727 0.6321000000 968599969 0 1784311808 -0.1675920933 -0.0325719640 -0.0900381804 134 1311867174.8944199085 0.0678037927 0.0606699415 0.0678037927 0.0062929173 0.6378900000 968601723 0 1782595584 -0.1680862010 -0.0317219719 -0.0909676999 135 1311867174.9270179272 0.0677269325 0.0607222155 0.0678037927 0.0062799494 0.6360470000 968603541 0 1784311808 -0.1699437946 -0.0312704034 -0.0914111361 136 1311867174.9626429081 0.0679608881 0.0607754410 0.0679608881 0.0062578819 0.6341720000 968605391 0 1782595584 -0.1719203144 -0.0315381177 -0.0920931026 137 1311867174.9943349361 0.0671009496 0.0608216126 0.0679608881 0.0062571047 0.6768180000 968607145 0 1784311808 -0.1745228618 -0.0311315041 -0.0929772854 138 1311867175.0265510082 0.0677557066 0.0608718597 0.0679608881 0.0062655561 0.6400970000 968608963 0 1782706176 -0.1759681702 -0.0294240061 -0.0929694995 139 1311867175.0633120537 0.0677348673 0.0609212338 0.0679608881 0.0062473689 0.6379160000 968610813 0 1784352768 -0.1779284030 -0.0295664109 -0.0931557864 140 1311867175.0947189331 0.0609018318 0.0609210953 0.0679608881 0.0062457714 0.6607820000 968612599 0 1782194176 -0.1883538365 -0.0271328799 -0.0940192342 141 1311867175.1265308857 0.0612031668 0.0609230958 0.0679608881 0.0062325979 0.6515110000 968614385 0 1783824384 -0.1895860881 -0.0276358481 -0.0934981331 142 1311867175.1625180244 0.0615493767 0.0609275062 0.0679608881 0.0062338999 0.6512270000 968616235 0 1781833728 -0.1903919578 -0.0275385343 -0.0934089497 143 1311867175.1946399212 0.0613542460 0.0609304904 0.0679608881 0.0062147692 0.6517160000 968617989 0 1783549952 -0.1919733584 -0.0274186134 -0.0932127014 144 1311867175.2270050049 0.0620672032 0.0609383842 0.0679608881 0.0062945408 0.6656050000 968619807 0 1781944320 -0.1925722957 -0.0265685171 -0.0926960930 145 1311867175.2624669075 0.0627724230 0.0609510328 0.0679608881 0.0063093527 0.6762150000 968621625 0 1783590912 -0.1931114644 -0.0259534791 -0.0924069732 146 1311867175.2944509983 0.0627571493 0.0609634034 0.0679608881 0.0062897012 0.6651370000 968623411 0 1781448704 -0.1943080127 -0.0258315634 -0.0922203287 147 1311867175.3267059326 0.0645399913 0.0609877340 0.0679608881 0.0062713407 0.6690610000 968625229 0 1783201792 -0.1940492243 -0.0243694000 -0.0913368985 148 1311867175.3625650406 0.0655661374 0.0610186691 0.0679608881 0.0062631343 0.6743810000 968627047 0 1781579776 -0.1956432313 -0.0240325071 -0.0907067209 149 1311867175.3945989609 0.0656402484 0.0610496864 0.0679608881 0.0062493572 0.6722700000 968628833 0 1783189504 -0.1979715079 -0.0240272954 -0.0905090272 150 1311867175.4266059399 0.0661486909 0.0610836798 0.0679608881 0.0062327325 0.6779460000 968630619 0 1781325824 -0.2001099885 -0.0228140689 -0.0902449936 151 1311867175.4625999928 0.0665855929 0.0611201163 0.0679608881 0.0062182198 0.6867350000 968632501 0 1783042048 -0.2031275928 -0.0225902647 -0.0899060294 152 1311867175.4945731163 0.0667416602 0.0611571001 0.0679608881 0.0062014559 0.6881100000 968634287 0 1781452800 -0.2062538415 -0.0225797743 -0.0897544846 153 1311867175.5264270306 0.0671685785 0.0611963909 0.0679608881 0.0061915362 0.7097000000 968636041 0 1783062528 -0.2091707289 -0.0220771767 -0.0896717608 154 1311867175.5625700951 0.0674997643 0.0612373219 0.0679608881 0.0062003233 0.6888970000 968637923 0 1781178368 -0.2115590274 -0.0206145532 -0.0894594714 155 1311867175.5946640968 0.0681300685 0.0612817912 0.0681300685 0.0062251464 0.6903670000 968639677 0 1782808576 -0.2141860574 -0.0195258167 -0.0893233791 156 1311867175.6264801025 0.0669968948 0.0613184265 0.0681300685 0.0062392382 0.6918410000 968641463 0 1784438784 -0.2180115581 -0.0194764659 -0.0892812386 157 1311867175.6624929905 0.0686482862 0.0613651135 0.0686482862 0.0062873020 0.6890720000 968643313 0 1782595584 -0.2190369517 -0.0190367140 -0.0888317525 158 1311867175.6947000027 0.0695567280 0.0614169591 0.0695567280 0.0063059273 0.7020580000 968645099 0 1784205312 -0.2207296789 -0.0196064115 -0.0888898075 159 1311867175.7273120880 0.0700300708 0.0614711296 0.0700300708 0.0062990114 0.6966250000 968646917 0 1782448128 -0.2228933722 -0.0200597793 -0.0887295008 160 1311867175.7624969482 0.0707717389 0.0615292585 0.0707717389 0.0062856571 0.6930640000 968648767 0 1784193024 -0.2246117294 -0.0190253910 -0.0887769684 161 1311867175.7948620319 0.0712165460 0.0615894279 0.0712165460 0.0062983526 0.7043480000 968650521 0 1782472704 -0.2270032316 -0.0192993805 -0.0889208615 162 1311867175.8287971020 0.0707513988 0.0616459833 0.0712165460 0.0062837565 0.6997180000 968652371 0 1784213504 -0.2303149551 -0.0195937529 -0.0893343389 163 1311867175.8625519276 0.0719150156 0.0617089835 0.0719150156 0.0062916994 0.7050750000 968654189 0 1782345728 -0.2324058563 -0.0192902815 -0.0894312039 164 1311867175.8946080208 0.0726238787 0.0617755378 0.0726238787 0.0062792409 0.7042080000 968655943 0 1784098816 -0.2347372770 -0.0195613354 -0.0899247304 165 1311867175.9282429218 0.0725507066 0.0618408418 0.0726238787 0.0062804870 0.7103720000 968657761 0 1782476800 -0.2377617359 -0.0200960152 -0.0906233862 166 1311867175.9629371166 0.0729433447 0.0619077244 0.0729433447 0.0062619022 0.7044410000 968659579 0 1784086528 -0.2401602417 -0.0194612052 -0.0908118263 167 1311867175.9983000755 0.0731695294 0.0619751603 0.0731695294 0.0062613689 0.7190280000 968661397 0 1782321152 -0.2426565140 -0.0189471692 -0.0908365920 168 1311867176.0268509388 0.0732815415 0.0620424602 0.0732815415 0.0062441136 0.7388360000 968663119 0 1784090624 -0.2448677719 -0.0203407891 -0.0913235024 169 1311867176.0627059937 0.0722366571 0.0621027809 0.0732815415 0.0062815620 0.7111710000 968664969 0 1782468608 -0.2479785085 -0.0209172834 -0.0920501500 170 1311867176.0946600437 0.0726624876 0.0621648968 0.0732815415 0.0063200887 0.7123030000 968666723 0 1784078336 -0.2493826449 -0.0205292683 -0.0924133658 171 1311867176.1268119812 0.0729824975 0.0622281576 0.0732815415 0.0063072850 0.7131180000 968668541 0 1782321152 -0.2511039972 -0.0205700360 -0.0930405632 172 1311867176.1625900269 0.0726634711 0.0622888281 0.0732815415 0.0063916492 0.7119860000 968670391 0 1784090624 -0.2529873848 -0.0202592034 -0.0937380716 173 1311867176.1946918964 0.0726422146 0.0623486742 0.0732815415 0.0064454890 0.7074030000 968672177 0 1782448128 -0.2543494105 -0.0186388902 -0.0943907201 174 1311867176.2265360355 0.0719396323 0.0624037947 0.0732815415 0.0064301665 0.7210380000 968673963 0 1784078336 -0.2567382455 -0.0176191647 -0.0949704796 175 1311867176.2625019550 0.0712897405 0.0624545715 0.0732815415 0.0064209643 0.7383730000 968675813 0 1782198272 -0.2592792511 -0.0172434337 -0.0959360152 176 1311867176.2946109772 0.0705415681 0.0625005204 0.0732815415 0.0064162753 0.7007760000 968677567 0 1783824384 -0.2620387375 -0.0160519052 -0.0964792371 177 1311867176.3266019821 0.0715385899 0.0625515829 0.0732815415 0.0064046523 0.7052160000 968679353 0 1781829632 -0.2628792226 -0.0146283470 -0.0969587117 178 1311867176.3624560833 0.0715354830 0.0626020542 0.0732815415 0.0063874469 0.7129290000 968681235 0 1783459840 -0.2647369504 -0.0150817530 -0.0978562981 179 1311867176.3952438831 0.0720744357 0.0626549726 0.0732815415 0.0063708960 0.7112440000 968682989 0 1781579776 -0.2655078173 -0.0139186941 -0.0985270590 180 1311867176.4268360138 0.0730582178 0.0627127684 0.0732815415 0.0063556927 0.7120160000 968684775 0 1783205888 -0.2656541467 -0.0126468427 -0.0991799980 181 1311867176.4629659653 0.0729900524 0.0627695490 0.0732815415 0.0064314087 0.7090320000 968686625 0 1781305344 -0.2674722373 -0.0121585922 -0.1000619233 182 1311867176.4945809841 0.0724434108 0.0628227020 0.0732815415 0.0064317008 0.7525790000 968688379 0 1782935552 -0.2698113918 -0.0118832057 -0.1011568531 183 1311867176.5266211033 0.0734128505 0.0628805717 0.0734128505 0.0064780973 0.7061210000 968690197 0 1784565760 -0.2709539831 -0.0107498970 -0.1018931419 184 1311867176.5636389256 0.0733845383 0.0629376585 0.0734128505 0.0064758913 0.7152800000 968692079 0 1782722560 -0.2729501426 -0.0110718757 -0.1028527468 185 1311867176.5946090221 0.0730406120 0.0629922690 0.0734128505 0.0064633797 0.7158420000 968693833 0 1784332288 -0.2751462460 -0.0113478461 -0.1040857285 186 1311867176.6283841133 0.0732497349 0.0630474167 0.0734128505 0.0064561544 0.7324180000 968695651 0 1782468608 -0.2770044208 -0.0105486503 -0.1049043760 187 1311867176.6625781059 0.0735266507 0.0631034554 0.0735266507 0.0064444544 0.7121690000 968697469 0 1784094720 -0.2793664038 -0.0097433124 -0.1057179719 188 1311867176.6945180893 0.0735361576 0.0631589485 0.0735361576 0.0064291766 0.7138760000 968699223 0 1782321152 -0.2815468311 -0.0092517799 -0.1065308526 189 1311867176.7265889645 0.0731983408 0.0632120670 0.0735361576 0.0064127888 0.7443160000 968701041 0 1784090624 -0.2845626771 -0.0087773288 -0.1072742492 190 1311867176.7632329464 0.0738800690 0.0632682143 0.0738800690 0.0063997673 0.7171490000 968702891 0 1782448128 -0.2866167426 -0.0088859554 -0.1077541560 191 1311867176.7947680950 0.0743061230 0.0633260044 0.0743061230 0.0063945159 0.7179330000 968704645 0 1784078336 -0.2884404361 -0.0086408397 -0.1083020866 192 1311867176.8266770840 0.0743506327 0.0633834244 0.0743506327 0.0063801645 0.7160870000 968706463 0 1782448128 -0.2908178270 -0.0087462207 -0.1089365706 193 1311867176.8627309799 0.0747266412 0.0634421975 0.0747266412 0.0063680223 0.7191400000 968708313 0 1784221696 -0.2929095030 -0.0082271257 -0.1092540696 194 1311867176.8949549198 0.0747074261 0.0635002657 0.0747266412 0.0063548652 0.7175340000 968710099 0 1782194176 -0.2954373360 -0.0079459520 -0.1097010523 195 1311867176.9268178940 0.0745382607 0.0635568708 0.0747266412 0.0063553260 0.7242020000 968711885 0 1783824384 -0.2979459167 -0.0081739463 -0.1102037281 196 1311867176.9650609493 0.0752914026 0.0636167409 0.0752914026 0.0063662081 0.7173290000 968713735 0 1782067200 -0.2997258604 -0.0071785515 -0.1104414314 197 1311867176.9947481155 0.0759363994 0.0636792772 0.0759363994 0.0063544536 0.7207110000 968715489 0 1783803904 -0.3011356592 -0.0067918920 -0.1108561680 198 1311867177.0267279148 0.0761041045 0.0637420289 0.0761041045 0.0063429418 0.7203810000 968717275 0 1782214656 -0.3034275770 -0.0075806491 -0.1111970693 199 1311867177.0626339912 0.0763754845 0.0638055136 0.0763754845 0.0063314675 0.7235170000 968719125 0 1783824384 -0.3056449890 -0.0069123879 -0.1114229858 200 1311867177.0946850777 0.0766487047 0.0638697295 0.0766487047 0.0063197722 0.7361300000 968720911 0 1782210560 -0.3070062995 -0.0066261580 -0.1119769961 201 1311867177.1266150475 0.0769410431 0.0639347609 0.0769410431 0.0063050105 0.7282290000 968722697 0 1783975936 -0.3090550303 -0.0071098721 -0.1122842133 202 1311867177.1627299786 0.0778167546 0.0640034837 0.0778167546 0.0062898904 0.7248510000 968724547 0 1782091776 -0.3106590509 -0.0065834164 -0.1125818416 203 1311867177.1946458817 0.0774159133 0.0640695548 0.0778167546 0.0062788714 0.7399330000 968726333 0 1783828480 -0.3129885197 -0.0058310376 -0.1129957512 204 1311867177.2264730930 0.0783910230 0.0641397580 0.0783910230 0.0062635860 0.7239050000 968728119 0 1782091776 -0.3145266473 -0.0059305253 -0.1134051159 205 1311867177.2638640404 0.0784294084 0.0642094636 0.0784294084 0.0062486284 0.7262080000 968730001 0 1783848960 -0.3173520267 -0.0053963885 -0.1137848422 206 1311867177.2946178913 0.0782832578 0.0642777830 0.0784294084 0.0062540715 0.7327150000 968731755 0 1782075392 -0.3193901181 -0.0056420052 -0.1144134104 207 1311867177.3276090622 0.0777993202 0.0643431045 0.0784294084 0.0062390825 0.7373060000 968733573 0 1783701504 -0.3221361041 -0.0055866963 -0.1149728969 208 1311867177.3627710342 0.0788382813 0.0644127928 0.0788382813 0.0062281745 0.7464240000 968735391 0 1782202368 -0.3233879507 -0.0045770654 -0.1152538285 209 1311867177.3946089745 0.0786416903 0.0644808737 0.0788382813 0.0062300091 0.7231940000 968737177 0 1783848960 -0.3258527517 -0.0048648501 -0.1157105491 210 1311867177.4312860966 0.0791865736 0.0645509008 0.0791865736 0.0062211290 0.7762970000 968739059 0 1782083584 -0.3278531730 -0.0042867749 -0.1159497201 211 1311867177.4626040459 0.0791808367 0.0646202370 0.0791865736 0.0062071870 0.7212700000 968740845 0 1783840768 -0.3300016522 -0.0036312072 -0.1164198443 212 1311867177.4946429729 0.0791243911 0.0646886528 0.0791865736 0.0061943533 0.7278910000 968742631 0 1781940224 -0.3319250345 -0.0032205163 -0.1168983579 213 1311867177.5276319981 0.0794230476 0.0647578284 0.0794230476 0.0061822652 0.7365580000 968744417 0 1783676928 -0.3333662152 -0.0024190776 -0.1174653843 214 1311867177.5626399517 0.0806087852 0.0648318983 0.0806087852 0.0061752715 0.7272970000 968746235 0 1782067200 -0.3348313272 -0.0021046437 -0.1176331192 215 1311867177.5947310925 0.0765919015 0.0648865960 0.0806087852 0.0061665306 0.7300330000 968748021 0 1783697408 -0.3405983746 -0.0020669941 -0.1190897375 216 1311867177.6311450005 0.0761862472 0.0649389092 0.0806087852 0.0061530908 0.7353300000 968749903 0 1781833728 -0.3432420194 -0.0017709024 -0.1197063625 217 1311867177.6624829769 0.0763832107 0.0649916479 0.0806087852 0.0061405865 0.7707930000 968751689 0 1783443456 -0.3443087339 -0.0009178585 -0.1203517094 218 1311867177.6945610046 0.0761399195 0.0650427867 0.0806087852 0.0061512186 0.7473750000 968753475 0 1781448704 -0.3462499380 -0.0009234818 -0.1209454760 219 1311867177.7305839062 0.0758294761 0.0650920410 0.0806087852 0.0061388240 0.7341820000 968755293 0 1783209984 -0.3480463624 0.0004853271 -0.1215059757 220 1311867177.7625379562 0.0765036196 0.0651439118 0.0806087852 0.0061323677 0.7392990000 968757079 0 1781194752 -0.3482526243 0.0006636474 -0.1220416725 221 1311867177.7945590019 0.0755981207 0.0651912160 0.0806087852 0.0061210637 0.7307830000 968758865 0 1782824960 -0.3500069082 0.0009446116 -0.1229631677 222 1311867177.8309149742 0.0760197937 0.0652399933 0.0806087852 0.0061105837 0.7435510000 968760715 0 1780924416 -0.3510475159 0.0011790731 -0.1237946525 223 1311867177.8625319004 0.0760716945 0.0652885660 0.0806087852 0.0060974718 0.7357230000 968762501 0 1782702080 -0.3518436551 0.0012730183 -0.1245614812 224 1311867177.8946919441 0.0762437060 0.0653374729 0.0806087852 0.0060859247 0.7546400000 968764255 0 1784217600 -0.3525289297 0.0018264428 -0.1250697821 225 1311867177.9317860603 0.0765651017 0.0653873734 0.0806087852 0.0060727123 0.7388620000 968766169 0 1782321152 -0.3534936309 0.0024235072 -0.1259492636 226 1311867177.9627909660 0.0765371770 0.0654367088 0.0806087852 0.0060722895 0.7454870000 968767923 0 1784098816 -0.3553035259 0.0026182393 -0.1268894076 227 1311867177.9947769642 0.0765616372 0.0654857173 0.0806087852 0.0060645627 0.7444690000 968769645 0 1782087680 -0.3563937843 0.0037839091 -0.1276370734 228 1311867178.0306100845 0.0771435574 0.0655368482 0.0806087852 0.0060564584 0.7451550000 968771495 0 1783713792 -0.3573783338 0.0037727419 -0.1286203861 229 1311867178.0634479523 0.0777343661 0.0655901125 0.0806087852 0.0060464850 0.7435720000 968773281 0 1781940224 -0.3583022356 0.0034269514 -0.1293172985 230 1311867178.0951139927 0.0780497342 0.0656442848 0.0806087852 0.0060334978 0.7345440000 968775067 0 1783709696 -0.3591789007 0.0046894895 -0.1298547089 231 1311867178.1307909489 0.0781642497 0.0656984837 0.0806087852 0.0060240450 0.7741690000 968776917 0 1782087680 -0.3614409864 0.0043221568 -0.1305281967 232 1311867178.1627469063 0.0780719593 0.0657518177 0.0806087852 0.0060398926 0.7429270000 968778703 0 1783713792 -0.3635365069 0.0041614110 -0.1312973350 233 1311867178.1950459480 0.0785997510 0.0658069590 0.0806087852 0.0060363617 0.7522260000 968780457 0 1781833728 -0.3650166690 0.0054309764 -0.1315664053 234 1311867178.2307190895 0.0791688710 0.0658640612 0.0806087852 0.0060321078 0.7447120000 968782307 0 1783549952 -0.3670872748 0.0042929952 -0.1323149651 235 1311867178.2628939152 0.0793344080 0.0659213818 0.0806087852 0.0060213432 0.7532070000 968784125 0 1781813248 -0.3689261377 0.0040065125 -0.1328222603 236 1311867178.2954900265 0.0800240412 0.0659811389 0.0806087852 0.0060132736 0.7469370000 968785911 0 1783590912 -0.3699398041 0.0048915856 -0.1330425888 237 1311867178.3306670189 0.0809168294 0.0660441587 0.0809168294 0.0060090366 0.7462870000 968787729 0 1781579776 -0.3716053069 0.0037591611 -0.1334241778 238 1311867178.3627231121 0.0808922052 0.0661065454 0.0809168294 0.0060018780 0.7707650000 968789547 0 1783296000 -0.3739463985 0.0041390192 -0.1336511672 239 1311867178.3949439526 0.0810784698 0.0661691895 0.0810784698 0.0059914367 0.7525040000 968791301 0 1781690368 -0.3758466840 0.0045538372 -0.1339275688 240 1311867178.4306581020 0.0811791644 0.0662317310 0.0811791644 0.0059891456 0.7497960000 968793151 0 1783336960 -0.3781614006 0.0051005450 -0.1339212656 241 1311867178.4628739357 0.0814912990 0.0662950487 0.0814912990 0.0059771984 0.7508000000 968794937 0 1781305344 -0.3799554706 0.0058349231 -0.1338492632 242 1311867178.4946439266 0.0811371654 0.0663563798 0.0814912990 0.0059688449 0.7482010000 968796723 0 1783074816 -0.3819590509 0.0053539448 -0.1340880841 243 1311867178.5306270123 0.0819009617 0.0664203493 0.0819009617 0.0059715576 0.7502090000 968798573 0 1781436416 -0.3834880590 0.0056608114 -0.1339385808 244 1311867178.5626420975 0.0825432464 0.0664864267 0.0825432464 0.0059599650 0.7561920000 968800391 0 1783169024 -0.3848527968 0.0058767600 -0.1339928806 245 1311867178.5947000980 0.0828688964 0.0665532939 0.0828688964 0.0059580052 0.7636250000 968802177 0 1781563392 -0.3862260878 0.0053835656 -0.1341166645 246 1311867178.6306900978 0.0831261724 0.0666206634 0.0831261724 0.0059553155 0.7518720000 968803995 0 1783209984 -0.3880575001 0.0057420097 -0.1340920925 247 1311867178.6626410484 0.0831463560 0.0666875690 0.0831463560 0.0059665344 0.7684700000 968805813 0 1781190656 -0.3891792893 0.0069254208 -0.1343814582 248 1311867178.6946120262 0.0825243443 0.0667514270 0.0831463560 0.0059583347 0.7564240000 968807567 0 1782837248 -0.3914498091 0.0063882992 -0.1348221898 249 1311867178.7307450771 0.0817231983 0.0668115546 0.0831463560 0.0059568060 0.7563450000 968809417 0 1784352768 -0.3935551941 0.0073409230 -0.1351324767 250 1311867178.7632350922 0.0817598701 0.0668713478 0.0831463560 0.0059496132 0.7538610000 968811235 0 1782460416 -0.3946980536 0.0073168892 -0.1352157891 251 1311867178.8006799221 0.0817932263 0.0669307975 0.0831463560 0.0059463692 0.7526140000 968813085 0 1784193024 -0.3957255185 0.0056167650 -0.1357012242 252 1311867178.8309500217 0.0819861442 0.0669905410 0.0831463560 0.0059405457 0.8007130000 968814839 0 1782456320 -0.3959457278 0.0072694737 -0.1359704733 253 1311867178.8627939224 0.0818395391 0.0670492327 0.0831463560 0.0059377872 0.7593990000 968816657 0 1784225792 -0.3968337178 0.0077970787 -0.1361829638 254 1311867178.8952279091 0.0814270303 0.0671058382 0.0831463560 0.0059388114 0.7588490000 968818443 0 1782587392 -0.3979481459 0.0058069201 -0.1369006336 255 1311867178.9306209087 0.0813250616 0.0671615998 0.0831463560 0.0059515506 0.7560200000 968820261 0 1784320000 -0.3985897899 0.0073922104 -0.1375169307 256 1311867178.9627609253 0.0804687366 0.0672135808 0.0831463560 0.0059483228 0.7652640000 968822079 0 1782587392 -0.4000591934 0.0085994219 -0.1381785125 257 1311867178.9946830273 0.0787648633 0.0672585275 0.0831463560 0.0059568976 0.7629350000 968823865 0 1784311808 -0.4028103650 0.0082368664 -0.1392155886 258 1311867179.0309159756 0.0787319094 0.0673029979 0.0831463560 0.0059805706 0.7754310000 968867699 0 1782706176 -0.4041044116 0.0082204547 -0.1400542855 259 1311867179.0628120899 0.0795752034 0.0673503810 0.0831463560 0.0059788424 0.7630120000 968869517 0 1784438784 -0.4045144916 0.0069901049 -0.1408397406 260 1311867179.0968201160 0.0793222338 0.0673964265 0.0831463560 0.0060624508 0.7606740000 968871303 0 1782833152 -0.4063635468 0.0049200323 -0.1417238861 261 1311867179.1310369968 0.0791945904 0.0674416302 0.0831463560 0.0060560459 0.7542000000 968873089 0 1784438784 -0.4070363045 0.0068875328 -0.1427172720 262 1311867179.1627540588 0.0793532953 0.0674870946 0.0831463560 0.0060726652 0.7710070000 968874875 0 1782706176 -0.4084529281 0.0067655286 -0.1440253407 263 1311867179.1957008839 0.0775682554 0.0675254260 0.0831463560 0.0060662949 0.7507720000 968876661 0 1784184832 -0.4116679430 0.0062272642 -0.1456737518 264 1311867179.2307469845 0.0771878511 0.0675620261 0.0831463560 0.0061121221 0.7608600000 968878479 0 1782325248 -0.4138533473 0.0083773239 -0.1467439085 265 1311867179.2634611130 0.0780085325 0.0676014469 0.0831463560 0.0061172448 0.7574320000 968880329 0 1783963648 -0.4146194458 0.0067644329 -0.1477612406 266 1311867179.2959330082 0.0780429021 0.0676407005 0.0831463560 0.0061120283 0.8024130000 968882083 0 1782325248 -0.4160071313 0.0060250731 -0.1486919969 267 1311867179.3307149410 0.0792619959 0.0676842259 0.0831463560 0.0061039401 0.7445130000 968883901 0 1783930880 -0.4161286354 0.0069526611 -0.1491242796 268 1311867179.3629300594 0.0795404091 0.0677284654 0.0831463560 0.0060927621 0.7512160000 968885751 0 1782198272 -0.4168387949 0.0075174822 -0.1495648026 269 1311867179.3948490620 0.0792001262 0.0677711110 0.0831463560 0.0060866307 0.7464460000 968887473 0 1783836672 -0.4183486402 0.0069435528 -0.1500785202 270 1311867179.4308040142 0.0797396749 0.0678154390 0.0831463560 0.0060911734 0.7565770000 968889355 0 1782198272 -0.4191409349 0.0074502723 -0.1503922939 271 1311867179.4637460709 0.0810593590 0.0678643096 0.0831463560 0.0060951568 0.7545340000 968891173 0 1783803904 -0.4191350639 0.0078499308 -0.1501434296 272 1311867179.4949469566 0.0818959549 0.0679158965 0.0831463560 0.0061064402 0.7579400000 968892927 0 1782087680 -0.4197605550 0.0071046920 -0.1502139866 273 1311867179.5307800770 0.0828353912 0.0679705467 0.0831463560 0.0061051998 0.7477750000 968894777 0 1783803904 -0.4202930629 0.0097800829 -0.1502909660 274 1311867179.5627610683 0.0833005607 0.0680264956 0.0833005607 0.0061237563 0.7542010000 968896563 0 1782067200 -0.4211272001 0.0103013720 -0.1503686309 275 1311867179.5946741104 0.0830236822 0.0680810308 0.0833005607 0.0061160951 0.7561830000 968898349 0 1783836672 -0.4227636158 0.0108121904 -0.1502326578 276 1311867179.6306900978 0.0837932974 0.0681379593 0.0837932974 0.0061288445 0.7550510000 968900167 0 1782198272 -0.4231093526 0.0116462987 -0.1502395421 277 1311867179.6625750065 0.0846821144 0.0681976855 0.0846821144 0.0061286835 0.7631160000 968901985 0 1783930880 -0.4233198762 0.0107459072 -0.1501284242 278 1311867179.6946051121 0.0850665346 0.0682583649 0.0850665346 0.0061365565 0.7572880000 968903739 0 1782194176 -0.4238439798 0.0119008170 -0.1501133442 279 1311867179.7309470177 0.0853820890 0.0683197402 0.0853820890 0.0061288175 0.7610620000 968905621 0 1783930880 -0.4243530929 0.0126962336 -0.1498863995 280 1311867179.7627270222 0.0850780457 0.0683795913 0.0853820890 0.0061510573 0.7875070000 968907407 0 1782325248 -0.4253169000 0.0118236700 -0.1500958204 281 1311867179.7948911190 0.0858302265 0.0684416932 0.0858302265 0.0061668638 0.7601230000 968909161 0 1783963648 -0.4247787297 0.0130869448 -0.1501041353 282 1311867179.8307530880 0.0867911503 0.0685067622 0.0867911503 0.0061585897 0.7724620000 968911043 0 1782325248 -0.4244306386 0.0134982755 -0.1499071568 283 1311867179.8627979755 0.0870847329 0.0685724087 0.0870847329 0.0061521009 0.7714330000 968912829 0 1783963648 -0.4253606200 0.0119230263 -0.1497716308 284 1311867179.8948040009 0.0874952748 0.0686390386 0.0874952748 0.0061457782 0.7712820000 968914615 0 1782325248 -0.4257265329 0.0118037779 -0.1495852172 285 1311867179.9309051037 0.0879938230 0.0687069501 0.0879938230 0.0061652947 0.7611690000 968916465 0 1783930880 -0.4258143008 0.0145065803 -0.1492574662 286 1311867179.9635379314 0.0878877267 0.0687740157 0.0879938230 0.0061634320 0.7697070000 968918283 0 1782214656 -0.4267491400 0.0138796680 -0.1490205228 287 1311867179.9958879948 0.0872900710 0.0688385316 0.0879938230 0.0061569005 0.7552080000 968920037 0 1783930880 -0.4280885458 0.0139477663 -0.1487410367 288 1311867180.0309770107 0.0877363533 0.0689041490 0.0879938230 0.0061540221 0.7689780000 968921887 0 1782198272 -0.4278892875 0.0158763900 -0.1483240426 289 1311867180.0626471043 0.0871407688 0.0689672515 0.0879938230 0.0061444602 0.7652100000 968923673 0 1783803904 -0.4294129908 0.0150362523 -0.1478948444 290 1311867180.0947730541 0.0848661214 0.0690220752 0.0879938230 0.0061350289 0.7761400000 968925427 0 1782087680 -0.4313611686 0.0162978861 -0.1487014294 291 1311867180.1307730675 0.0843472704 0.0690747391 0.0879938230 0.0061343728 0.7703580000 968927277 0 1783803904 -0.4316785038 0.0155952983 -0.1485493779 292 1311867180.1636900902 0.0842419416 0.0691266816 0.0879938230 0.0061514413 0.7687410000 968929127 0 1782079488 -0.4304431379 0.0159159228 -0.1489464492 293 1311867180.1949090958 0.0835753605 0.0691759945 0.0879938230 0.0061415844 0.7662990000 968930849 0 1783701504 -0.4303165376 0.0160829611 -0.1492308527 294 1311867180.2308139801 0.0830022246 0.0692230225 0.0879938230 0.0061387204 0.8186950000 968932667 0 1781948416 -0.4293683171 0.0164532699 -0.1502513885 295 1311867180.2637619972 0.0821164399 0.0692667290 0.0879938230 0.0061648964 0.7697220000 968934485 0 1783685120 -0.4295092821 0.0165377017 -0.1509105265 296 1311867180.2947549820 0.0811867937 0.0693069995 0.0879938230 0.0061545521 0.7818440000 968936239 0 1781948416 -0.4298765957 0.0164999254 -0.1515489370 297 1311867180.3308670521 0.0804131925 0.0693443941 0.0879938230 0.0061465252 0.7696240000 968938089 0 1783717888 -0.4299764931 0.0165108107 -0.1519418955 298 1311867180.3658289909 0.0795852020 0.0693787592 0.0879938230 0.0061459234 0.7774290000 968939907 0 1782087680 -0.4298036397 0.0171591192 -0.1523845643 299 1311867180.3964109421 0.0791355222 0.0694113905 0.0879938230 0.0061377275 0.7734100000 968941693 0 1783803904 -0.4295217395 0.0180110987 -0.1525005698 300 1311867180.4309151173 0.0783765614 0.0694412744 0.0879938230 0.0061296593 0.7701000000 968943511 0 1782214656 -0.4293422997 0.0175075531 -0.1531458944 301 1311867180.4670670033 0.0781069472 0.0694700640 0.0879938230 0.0061234678 0.7785150000 968945361 0 1783824384 -0.4285345674 0.0179078411 -0.1534818560 302 1311867180.4947559834 0.0780079663 0.0694983352 0.0879938230 0.0061257690 0.7778850000 968947051 0 1781940224 -0.4281122684 0.0176704824 -0.1536527872 303 1311867180.5308880806 0.0776967257 0.0695253926 0.0879938230 0.0061166204 0.7867350000 968948933 0 1783570432 -0.4271888137 0.0179337841 -0.1536694616 304 1311867180.5629510880 0.0775679275 0.0695518483 0.0879938230 0.0061070232 0.7834210000 968950719 0 1781956608 -0.4262370169 0.0180365276 -0.1535055637 305 1311867180.5946910381 0.0774316713 0.0695776838 0.0879938230 0.0060980418 0.7818520000 968952505 0 1783697408 -0.4249707758 0.0184180308 -0.1534745842 306 1311867180.6308128834 0.0771845430 0.0696025428 0.0879938230 0.0060889559 0.7815850000 968954355 0 1781809152 -0.4240753055 0.0181654282 -0.1533324420 307 1311867180.6640911102 0.0768161565 0.0696260399 0.0879938230 0.0060973123 0.7786350000 968956141 0 1783566336 -0.4232244790 0.0184844714 -0.1530890614 308 1311867180.6957859993 0.0769044757 0.0696496712 0.0879938230 0.0060877529 0.8178620000 968957927 0 1781936128 -0.4222899377 0.0176463127 -0.1527201831 309 1311867180.7309739590 0.0767692700 0.0696727120 0.0879938230 0.0060837390 0.7812360000 968959777 0 1783713792 -0.4209062457 0.0183891542 -0.1526862532 310 1311867180.7650830746 0.0772172138 0.0696970491 0.0879938230 0.0060890455 0.7818540000 968961595 0 1781932032 -0.4204479158 0.0181652866 -0.1523332298 311 1311867180.7949280739 0.0771224424 0.0697209250 0.0879938230 0.0060796716 0.7759680000 968963317 0 1783730176 -0.4201360643 0.0182245709 -0.1520633698 312 1311867180.8309240341 0.0773876384 0.0697454978 0.0879938230 0.0060705849 0.7829480000 968965199 0 1781936128 -0.4191054404 0.0189544410 -0.1516544968 313 1311867180.8652698994 0.0772799551 0.0697695695 0.0879938230 0.0060699302 0.7807630000 968967017 0 1783713792 -0.4179583490 0.0180036407 -0.1516835690 314 1311867180.8966469765 0.0770173669 0.0697926517 0.0879938230 0.0060627608 0.7771560000 968968803 0 1782063104 -0.4167905152 0.0183555130 -0.1516137570 315 1311867180.9306049347 0.0771803856 0.0698161048 0.0879938230 0.0060800037 0.7879550000 968970621 0 1783709696 -0.4161981344 0.0184488147 -0.1514703333 316 1311867180.9631829262 0.0768320337 0.0698383071 0.0879938230 0.0060804742 0.7881850000 968972407 0 1782079488 -0.4155347943 0.0182112269 -0.1514123082 317 1311867180.9948179722 0.0773018077 0.0698618513 0.0879938230 0.0060718403 0.7767190000 968974161 0 1783857152 -0.4137041271 0.0187304281 -0.1509174705 318 1311867181.0308310986 0.0777895823 0.0698867812 0.0879938230 0.0060647018 0.7841890000 968976011 0 1782190080 -0.4120278358 0.0174159445 -0.1506518871 319 1311867181.0627830029 0.0777576268 0.0699114547 0.0879938230 0.0060635755 0.7830550000 968977829 0 1783967744 -0.4101696908 0.0171901863 -0.1504414529 320 1311867181.0948719978 0.0779107511 0.0699364525 0.0879938230 0.0060623090 0.7871660000 968979615 0 1782185984 -0.4073179662 0.0173272602 -0.1502925903 321 1311867181.1311910152 0.0777433738 0.0699607732 0.0879938230 0.0060547099 0.7909960000 968981465 0 1783967744 -0.4044717550 0.0177607201 -0.1503025442 322 1311867181.1629528999 0.0769706070 0.0699825428 0.0879938230 0.0060564292 0.7896260000 968983251 0 1782317056 -0.4033860266 0.0171133801 -0.1504977345 323 1311867181.1972830296 0.0765298381 0.0700028131 0.0879938230 0.0060475483 0.7903690000 968985069 0 1783984128 -0.4015765190 0.0166627802 -0.1504896134 324 1311867181.2342460155 0.0761886612 0.0700219052 0.0879938230 0.0060407358 0.7854010000 968986951 0 1782317056 -0.3997510076 0.0162807293 -0.1506761014 325 1311867181.2629361153 0.0763652921 0.0700414233 0.0879938230 0.0060317889 0.7820830000 968988673 0 1783984128 -0.3978756368 0.0163333509 -0.1504070163 326 1311867181.2948091030 0.0764065608 0.0700609483 0.0879938230 0.0060229311 0.7913710000 968990427 0 1782317056 -0.3960385025 0.0167402439 -0.1503541917 327 1311867181.3317139149 0.0763415843 0.0700801551 0.0879938230 0.0060192173 0.7869910000 968992309 0 1784094720 -0.3941868544 0.0166933052 -0.1504157186 328 1311867181.3626708984 0.0766967461 0.0701003277 0.0879938230 0.0060218946 0.7866940000 968994063 0 1782444032 -0.3923056722 0.0183629449 -0.1498960853 329 1311867181.3948218822 0.0766262934 0.0701201634 0.0879938230 0.0060143322 0.8231730000 968995849 0 1784221696 -0.3910869062 0.0171248242 -0.1498445272 330 1311867181.4308950901 0.0758200288 0.0701374357 0.0879938230 0.0060059236 0.7951850000 968997635 0 1782591488 -0.3900675476 0.0168065764 -0.1497480571 331 1311867181.4628310204 0.0759159625 0.0701548935 0.0879938230 0.0060016762 0.7999480000 968999421 0 1784348672 -0.3878013790 0.0160994250 -0.1492759138 332 1311867181.4963610172 0.0761559084 0.0701729689 0.0879938230 0.0060123172 0.8005160000 969001239 0 1782587392 -0.3844715953 0.0161030833 -0.1492826790 333 1311867181.5359110832 0.0756788626 0.0701895031 0.0879938230 0.0060074212 0.7883180000 969003121 0 1784348672 -0.3831350803 0.0156789888 -0.1490146667 334 1311867181.5671720505 0.0750686824 0.0702041114 0.0879938230 0.0060025815 0.7966690000 969004875 0 1782697984 -0.3818491697 0.0150875980 -0.1493204683 335 1311867181.5948610306 0.0752115026 0.0702190588 0.0879938230 0.0059989454 0.7874520000 969006565 0 1784344576 -0.3800894916 0.0160790682 -0.1493395865 336 1311867181.6313591003 0.0757473186 0.0702355120 0.0879938230 0.0059979279 0.7938940000 969008447 0 1782722560 -0.3780276775 0.0153880315 -0.1494149417 337 1311867181.6628570557 0.0751697421 0.0702501536 0.0879938230 0.0059930162 0.7895990000 969010233 0 1784463360 -0.3767428398 0.0139493337 -0.1498679519 338 1311867181.6949229240 0.0748739243 0.0702638334 0.0879938230 0.0059858847 0.7938160000 969011987 0 1782452224 -0.3756291568 0.0142990537 -0.1501264125 339 1311867181.7310829163 0.0752347112 0.0702784968 0.0879938230 0.0059910496 0.7919220000 969013837 0 1784229888 -0.3734787405 0.0134461122 -0.1504137963 340 1311867181.7634840012 0.0746425763 0.0702913323 0.0879938230 0.0059827486 0.8009570000 969015655 0 1782456320 -0.3724365532 0.0122250663 -0.1509184539 341 1311867181.7948980331 0.0742046684 0.0703028084 0.0879938230 0.0059821369 0.7864190000 969017377 0 1784102912 -0.3705814779 0.0124982651 -0.1510781050 342 1311867181.8308010101 0.0738747567 0.0703132527 0.0879938230 0.0059781100 0.7923030000 969019227 0 1782194176 -0.3688826859 0.0111726969 -0.1512145102 343 1311867181.8627979755 0.0740016326 0.0703240060 0.0879938230 0.0059718832 0.7916180000 969021045 0 1783840768 -0.3672960699 0.0104090553 -0.1513828039 344 1311867181.8949289322 0.0735357478 0.0703333424 0.0879938230 0.0059663275 0.7984960000 969022799 0 1781940224 -0.3653095365 0.0106868939 -0.1511768252 345 1311867181.9307990074 0.0727884248 0.0703404586 0.0879938230 0.0059664538 0.7898310000 969024681 0 1783586816 -0.3641710877 0.0101972977 -0.1512221545 346 1311867181.9629189968 0.0723060668 0.0703461395 0.0879938230 0.0059620263 0.7982460000 969026467 0 1781555200 -0.3624996841 0.0098046409 -0.1510656923 347 1311867181.9955599308 0.0718045682 0.0703503425 0.0879938230 0.0059809288 0.7874760000 969028253 0 1783185408 -0.3611700237 0.0089209210 -0.1503834128 348 1311867182.0320639610 0.0718891099 0.0703547643 0.0879938230 0.0059732818 0.7940850000 969030103 0 1781194752 -0.3588154018 0.0082040913 -0.1500329971 349 1311867182.0629000664 0.0718344226 0.0703590040 0.0879938230 0.0059668728 0.7810310000 969031889 0 1782947840 -0.3570758998 0.0081486804 -0.1496613473 350 1311867182.0948839188 0.0723767355 0.0703647689 0.0879938230 0.0059695928 0.8432930000 969033643 0 1781321728 -0.3551396132 0.0076839179 -0.1494284868 351 1311867182.1314840317 0.0725113004 0.0703708844 0.0879938230 0.0059618501 0.7885590000 969035525 0 1782935552 -0.3534143865 0.0074339993 -0.1488846987 352 1311867182.1629920006 0.0719357356 0.0703753300 0.0879938230 0.0059544858 0.7965710000 969037311 0 1781174272 -0.3519990146 0.0077181137 -0.1486643702 353 1311867182.1994500160 0.0714459792 0.0703783630 0.0879938230 0.0059500487 0.7836860000 969039129 0 1783042048 -0.3512888253 0.0072339899 -0.1482006460 354 1311867182.2307739258 0.0712877735 0.0703809319 0.0879938230 0.0059468038 0.7914980000 969040883 0 1781321728 -0.3499764800 0.0067448225 -0.1477897763 355 1311867182.2629120350 0.0711911768 0.0703832143 0.0879938230 0.0059430920 0.7853580000 969042701 0 1782951936 -0.3489004374 0.0067141168 -0.1472580433 356 1311867182.2973539829 0.0713571161 0.0703859500 0.0879938230 0.0059397563 0.7895170000 969044519 0 1784565760 -0.3472147286 0.0053692446 -0.1471468359 357 1311867182.3308460712 0.0710494667 0.0703878086 0.0879938230 0.0059561638 0.7834480000 969046305 0 1782591488 -0.3463346362 0.0051289741 -0.1465681344 358 1311867182.3629670143 0.0704686791 0.0703880345 0.0879938230 0.0059757393 0.7950560000 969048123 0 1784344576 -0.3456604779 0.0047278283 -0.1460972130 359 1311867182.3990368843 0.0703425556 0.0703879078 0.0879938230 0.0059743304 0.7919200000 969049941 0 1782722560 -0.3443900645 0.0037389195 -0.1456386596 360 1311867182.4308118820 0.0702023879 0.0703873925 0.0879938230 0.0059723934 0.7780440000 969051727 0 1784332288 -0.3434856832 0.0021081923 -0.1456248462 361 1311867182.4629440308 0.0691207349 0.0703838837 0.0879938230 0.0059698143 0.7954150000 969053545 0 1782468608 -0.3430058062 0.0018392475 -0.1456318200 362 1311867182.4969599247 0.0685679391 0.0703788673 0.0879938230 0.0059669074 0.7902850000 969055331 0 1784078336 -0.3424015641 0.0005607791 -0.1455374360 363 1311867182.5309500694 0.0679138526 0.0703720766 0.0879938230 0.0059603003 0.7871370000 969057149 0 1782341632 -0.3414511681 -0.0004856139 -0.1460417360 364 1311867182.5629699230 0.0671259984 0.0703631588 0.0879938230 0.0059573199 0.7826950000 969058935 0 1784057856 -0.3403031528 -0.0005851928 -0.1463531256 365 1311867182.6036369801 0.0634611100 0.0703442491 0.0879938230 0.0059536832 0.7745450000 969060849 0 1782468608 -0.3421085179 -0.0011374382 -0.1474161893 366 1311867182.6308450699 0.0624742359 0.0703227463 0.0879938230 0.0059698686 0.7709200000 969062539 0 1784078336 -0.3420614302 -0.0021290036 -0.1478876323 367 1311867182.6635921001 0.0620445423 0.0703001899 0.0879938230 0.0059624704 0.7695970000 969064357 0 1782087680 -0.3406496048 -0.0024444212 -0.1480638087 368 1311867182.6970019341 0.0612854362 0.0702756933 0.0879938230 0.0059617018 0.7678310000 969066143 0 1783803904 -0.3392688334 -0.0030657393 -0.1483632177 369 1311867182.7330639362 0.0606950857 0.0702497296 0.0879938230 0.0059567788 0.7671560000 969067993 0 1782067200 -0.3371049464 -0.0035469746 -0.1488498747 370 1311867182.7631130219 0.0606953911 0.0702239071 0.0879938230 0.0059511138 0.7603810000 969069683 0 1783803904 -0.3353059590 -0.0037344280 -0.1487698257 371 1311867182.7970550060 0.0599929206 0.0701963303 0.0879938230 0.0059432434 0.8215630000 969071533 0 1782214656 -0.3342603445 -0.0048471414 -0.1489489973 372 1311867182.8306989670 0.0594940633 0.0701675608 0.0879938230 0.0059365985 0.7685110000 969073319 0 1783803904 -0.3326484561 -0.0054145725 -0.1492096484 373 1311867182.8641169071 0.0582736507 0.0701356736 0.0879938230 0.0059334739 0.7695210000 969075105 0 1782214656 -0.3315208852 -0.0056288764 -0.1492544413 374 1311867182.8969969749 0.0585731380 0.0701047577 0.0879938230 0.0059257375 0.7636340000 969076923 0 1783836672 -0.3291398883 -0.0062139118 -0.1490550488 375 1311867182.9318990707 0.0590284839 0.0700752210 0.0879938230 0.0059185743 0.7718740000 969078741 0 1782214656 -0.3262960017 -0.0056888163 -0.1489105523 376 1311867182.9630720615 0.0592343397 0.0700463889 0.0879938230 0.0059109249 0.7677520000 969080527 0 1783803904 -0.3239943683 -0.0055898530 -0.1486110985 377 1311867182.9983949661 0.0590308085 0.0700171698 0.0879938230 0.0059196530 0.7843070000 969082345 0 1782067200 -0.3230759203 -0.0062497891 -0.1482107788 378 1311867183.0308830738 0.0587462783 0.0699873526 0.0879938230 0.0059121354 0.7648060000 969084131 0 1783836672 -0.3214825392 -0.0069104936 -0.1477975547 379 1311867183.0628600121 0.0591432080 0.0699587401 0.0879938230 0.0059052066 0.7748980000 969085949 0 1782206464 -0.3186892569 -0.0062110890 -0.1474346220 380 1311867183.1000499725 0.0584324524 0.0699284078 0.0879938230 0.0059289212 0.7702880000 969087767 0 1783717888 -0.3172332644 -0.0072071883 -0.1471090913 381 1311867183.1344780922 0.0581045337 0.0698973740 0.0879938230 0.0059242057 0.7769370000 969089617 0 1781952512 -0.3158214986 -0.0069333520 -0.1467102915 382 1311867183.1673240662 0.0582085364 0.0698667749 0.0879938230 0.0059186072 0.7683520000 969091435 0 1783685120 -0.3140028417 -0.0062886630 -0.1461768597 383 1311867183.2004919052 0.0578786545 0.0698354744 0.0879938230 0.0059131559 0.7766090000 969093221 0 1782079488 -0.3132314980 -0.0075267996 -0.1456231922 384 1311867183.2311279774 0.0582065545 0.0698051907 0.0879938230 0.0059058045 0.7770630000 969094975 0 1783709696 -0.3115791082 -0.0080163032 -0.1451889724 385 1311867183.2633349895 0.0584571175 0.0697757152 0.0879938230 0.0058996834 0.8164000000 969096793 0 1781460992 -0.3094587922 -0.0077706613 -0.1449115574 386 1311867183.2991099358 0.0581897087 0.0697456996 0.0879938230 0.0058942830 0.7723670000 969098611 0 1783177216 -0.3085637689 -0.0092672594 -0.1448948085 387 1311867183.3320920467 0.0581947640 0.0697158523 0.0879938230 0.0058952385 0.7744170000 969100429 0 1781563392 -0.3070240617 -0.0090401489 -0.1447590590 388 1311867183.3695240021 0.0578953251 0.0696853870 0.0879938230 0.0058877595 0.7781430000 969102311 0 1783209984 -0.3057631552 -0.0093884170 -0.1444395632 389 1311867183.3986210823 0.0576515831 0.0696544518 0.0879938230 0.0058816176 0.7783460000 969104033 0 1781067776 -0.3046114147 -0.0106894467 -0.1447695494 390 1311867183.4311549664 0.0573810525 0.0696229815 0.0879938230 0.0058900705 0.7729510000 969105819 0 1782915072 -0.3032265007 -0.0104124034 -0.1445705593 391 1311867183.4667448997 0.0574100055 0.0695917463 0.0879938230 0.0058879192 0.7783920000 969107669 0 1784565760 -0.3011461496 -0.0103547862 -0.1441475898 392 1311867183.4988338947 0.0566250607 0.0695586680 0.0879938230 0.0059121401 0.7796290000 969109487 0 1782976512 -0.2998910248 -0.0116325142 -0.1442613453 393 1311867183.5321829319 0.0565600097 0.0695255925 0.0879938230 0.0059053369 0.7725050000 969111273 0 1781325824 -0.2980910540 -0.0122029204 -0.1439304203 394 1311867183.5661609173 0.0562329404 0.0694918548 0.0879938230 0.0058991990 0.7758100000 969113091 0 1783042048 -0.2965752184 -0.0116872536 -0.1435151249 395 1311867183.5985479355 0.0559943579 0.0694576840 0.0879938230 0.0058960465 0.7778460000 969114877 0 1781452800 -0.2944778800 -0.0126889134 -0.1433445662 396 1311867183.6310880184 0.0559803322 0.0694236502 0.0879938230 0.0059110616 0.7740030000 969116663 0 1783083008 -0.2927418649 -0.0131151555 -0.1428873390 397 1311867183.6649260521 0.0554248281 0.0693883887 0.0879938230 0.0059063172 0.7778220000 969118481 0 1784565760 -0.2913693190 -0.0134921819 -0.1421783417 398 1311867183.6993949413 0.0559312813 0.0693545769 0.0879938230 0.0058994648 0.7738320000 969120331 0 1782722560 -0.2886547446 -0.0145002687 -0.1417363435 399 1311867183.7308928967 0.0553512871 0.0693194809 0.0879938230 0.0058972278 0.8089840000 969122053 0 1784438784 -0.2871647477 -0.0145825753 -0.1413233429 400 1311867183.7676479816 0.0551571436 0.0692840751 0.0879938230 0.0059013175 0.7830190000 969123935 0 1782849536 -0.2844594121 -0.0150759649 -0.1406958550 401 1311867183.7971870899 0.0548406914 0.0692480567 0.0879938230 0.0058939553 0.7781850000 969125657 0 1784565760 -0.2832235396 -0.0158767216 -0.1400458664 402 1311867183.8309071064 0.0549413525 0.0692124679 0.0879938230 0.0058868283 0.7764170000 969127443 0 1782829056 -0.2812655270 -0.0166091844 -0.1393148750 403 1311867183.8655049801 0.0548676401 0.0691768728 0.0879938230 0.0058819927 0.7874120000 969129261 0 1781178368 -0.2792900205 -0.0178462435 -0.1391554624 404 1311867183.8970971107 0.0547106080 0.0691410652 0.0879938230 0.0058751786 0.7708260000 969131015 0 1782915072 -0.2779329717 -0.0181491822 -0.1387858987 405 1311867183.9314939976 0.0542130992 0.0691042060 0.0879938230 0.0058684083 0.7869480000 969132865 0 1784598528 -0.2770396471 -0.0184354708 -0.1381097287 406 1311867183.9658319950 0.0539764091 0.0690669454 0.0879938230 0.0058679786 0.7775880000 969134651 0 1782976512 -0.2751897275 -0.0193091556 -0.1379531771 407 1311867183.9966781139 0.0536295511 0.0690290157 0.0879938230 0.0058633354 0.7785840000 969136437 0 1781325824 -0.2743080258 -0.0200150870 -0.1374554038 408 1311867184.0309689045 0.0537685230 0.0689916125 0.0879938230 0.0058861771 0.7808000000 969138255 0 1783042048 -0.2733588219 -0.0202321745 -0.1369432211 409 1311867184.0647850037 0.0537862517 0.0689544356 0.0879938230 0.0058819237 0.7727940000 969140073 0 1781452800 -0.2718114257 -0.0212661400 -0.1364651918 410 1311867184.0968890190 0.0534372441 0.0689165888 0.0879938230 0.0058749308 0.7695680000 969141827 0 1783169024 -0.2705381513 -0.0216316842 -0.1359550655 411 1311867184.1312260628 0.0535990819 0.0688793199 0.0879938230 0.0058681289 0.7696430000 969143645 0 1781579776 -0.2688177824 -0.0216059685 -0.1353037953 412 1311867184.1650640965 0.0531384125 0.0688411138 0.0879938230 0.0058616988 0.7731920000 969145431 0 1783201792 -0.2676850259 -0.0226682629 -0.1350502521 413 1311867184.1969559193 0.0531603917 0.0688031460 0.0879938230 0.0058560302 0.7778710000 969147249 0 1781579776 -0.2656040192 -0.0222359318 -0.1345844567 414 1311867184.2309360504 0.0535569377 0.0687663194 0.0879938230 0.0058492529 0.7680300000 969149067 0 1783205888 -0.2631482184 -0.0220687818 -0.1339173168 415 1311867184.2681369781 0.0524531975 0.0687270107 0.0879938230 0.0058459863 0.7822610000 969150949 0 1781198848 -0.2623432577 -0.0234580934 -0.1337895244 416 1311867184.2983899117 0.0524678342 0.0686879261 0.0879938230 0.0058407856 0.7733480000 969152703 0 1782915072 -0.2606370449 -0.0230252724 -0.1332118660 417 1311867184.3314700127 0.0526670292 0.0686495067 0.0879938230 0.0058338930 0.7741360000 969154489 0 1784565760 -0.2578442693 -0.0226383209 -0.1326968372 418 1311867184.3697841167 0.0518581383 0.0686093360 0.0879938230 0.0058356756 0.7789400000 969156371 0 1782976512 -0.2564678490 -0.0238840878 -0.1325751245 419 1311867184.4000220299 0.0519608110 0.0685696020 0.0879938230 0.0058746860 0.7772260000 969158125 0 1781305344 -0.2544809580 -0.0236874744 -0.1321374774 420 1311867184.4310610294 0.0532790460 0.0685331959 0.0879938230 0.0058714010 0.8105250000 969159911 0 1783083008 -0.2507994771 -0.0231796335 -0.1316337883 421 1311867184.4655809402 0.0523303784 0.0684947094 0.0879938230 0.0058670881 0.7816570000 969161729 0 1784549376 -0.2502565980 -0.0249454379 -0.1317691207 422 1311867184.5037670135 0.0516579188 0.0684548118 0.0879938230 0.0059070463 0.7724510000 969163611 0 1782566912 -0.2484021932 -0.0260195471 -0.1320636570 423 1311867184.5310881138 0.0521470979 0.0684162593 0.0879938230 0.0059309253 0.7726300000 969165333 0 1784438784 -0.2457875162 -0.0253882632 -0.1325668395 424 1311867184.5682930946 0.0515473969 0.0683764742 0.0879938230 0.0059254023 0.7738870000 969167215 0 1782702080 -0.2434843630 -0.0256837066 -0.1330544502 425 1311867184.6018071175 0.0503706671 0.0683341076 0.0879938230 0.0059188177 0.7750130000 969169001 0 1784438784 -0.2420501411 -0.0267855357 -0.1334889531 426 1311867184.6367399693 0.0496190749 0.0682901756 0.0879938230 0.0059129570 0.7749100000 969170851 0 1782849536 -0.2405637950 -0.0269278418 -0.1328905374 427 1311867184.6662440300 0.0493509658 0.0682458215 0.0879938230 0.0059207244 0.7699520000 969172573 0 1784459264 -0.2377701700 -0.0280261710 -0.1326145977 428 1311867184.6994929314 0.0487667397 0.0682003096 0.0879938230 0.0059168349 0.7737830000 969174423 0 1782337536 -0.2356757671 -0.0294397101 -0.1324470341 429 1311867184.7359158993 0.0484164394 0.0681541934 0.0879938230 0.0059187960 0.7648680000 969176209 0 1784184832 -0.2332607955 -0.0291774459 -0.1317110658 430 1311867184.7690689564 0.0484219566 0.0681083045 0.0879938230 0.0059177510 0.7705220000 969178059 0 1782464512 -0.2313174456 -0.0307592079 -0.1308369339 431 1311867184.8001279831 0.0479041673 0.0680614271 0.0879938230 0.0059163290 0.7626400000 969179813 0 1784225792 -0.2291001976 -0.0312372036 -0.1300863028 432 1311867184.8348441124 0.0477539636 0.0680144191 0.0879938230 0.0059099690 0.7576940000 969181599 0 1782075392 -0.2262553722 -0.0312625133 -0.1290702373 433 1311867184.8690660000 0.0469643027 0.0679658045 0.0879938230 0.0059034848 0.7637670000 969183417 0 1783828480 -0.2243519872 -0.0323553495 -0.1282170415 434 1311867184.9055209160 0.0464297533 0.0679161823 0.0879938230 0.0058983373 0.7965200000 969185203 0 1782185984 -0.2215730101 -0.0329053700 -0.1271098554 435 1311867184.9332280159 0.0467189699 0.0678674531 0.0879938230 0.0058932654 0.7626540000 969186893 0 1783832576 -0.2182404101 -0.0328032635 -0.1254765093 436 1311867184.9656410217 0.0464529060 0.0678183371 0.0879938230 0.0058924673 0.7634230000 969188679 0 1781805056 -0.2161566168 -0.0342291035 -0.1240764633 437 1311867184.9983251095 0.0458184481 0.0677679941 0.0879938230 0.0058909941 0.7606670000 969190497 0 1783541760 -0.2133809179 -0.0352552533 -0.1227990985 438 1311867185.0360550880 0.0457076728 0.0677176281 0.0879938230 0.0058847290 0.7588120000 969192347 0 1781952512 -0.2099133581 -0.0355157107 -0.1210615635 439 1311867185.0652348995 0.0455422699 0.0676671147 0.0879938230 0.0058804683 0.7646990000 969194101 0 1783562240 -0.2076330334 -0.0366408639 -0.1196310893 440 1311867185.0991280079 0.0443153232 0.0676140425 0.0879938230 0.0058758620 0.7684160000 969195919 0 1781551104 -0.2061123997 -0.0366283022 -0.1182133555 441 1311867185.1360778809 0.0439823642 0.0675604559 0.0879938230 0.0058731310 0.7644720000 969197769 0 1783287808 -0.2033153474 -0.0369649902 -0.1162707508 442 1311867185.1648709774 0.0439530946 0.0675070456 0.0879938230 0.0058690307 0.7607360000 969199523 0 1781698560 -0.2004395425 -0.0380936451 -0.1145657077 443 1311867185.2000720501 0.0437257178 0.0674533631 0.0879938230 0.0058640909 0.7556340000 969201309 0 1783414784 -0.1971271038 -0.0382053033 -0.1127812043 444 1311867185.2342920303 0.0442330837 0.0674010652 0.0879938230 0.0058658204 0.7664720000 969203159 0 1781825536 -0.1936559230 -0.0382657275 -0.1107070148 445 1311867185.2663950920 0.0438934639 0.0673482392 0.0879938230 0.0058594727 0.7576460000 969204977 0 1783324672 -0.1910772473 -0.0403150059 -0.1091776416 446 1311867185.2970550060 0.0435416028 0.0672948610 0.0879938230 0.0058767632 0.7644470000 969206731 0 1781297152 -0.1880412251 -0.0404949076 -0.1076296195 447 1311867185.3360140324 0.0436066277 0.0672418672 0.0879938230 0.0058703183 0.7612180000 969208613 0 1783066624 -0.1852299124 -0.0408684872 -0.1058819517 448 1311867185.3681778908 0.0435968116 0.0671890881 0.0879938230 0.0058643155 0.7930190000 969210431 0 1781424128 -0.1819837540 -0.0421017036 -0.1046814546 449 1311867185.4036509991 0.0431988724 0.0671356578 0.0879938230 0.0058618190 0.7603510000 969212249 0 1783054336 -0.1792500913 -0.0425577573 -0.1034568697 450 1311867185.4386389256 0.0435859039 0.0670833250 0.0879938230 0.0058559063 0.7582700000 969214067 0 1781043200 -0.1757482737 -0.0423123315 -0.1019653007 451 1311867185.4655449390 0.0445142016 0.0670332826 0.0879938230 0.0058497253 0.7601010000 969215757 0 1782779904 -0.1733403504 -0.0435434692 -0.1008877233 452 1311867185.5013909340 0.0442309231 0.0669828349 0.0879938230 0.0058597258 0.7535380000 969217607 0 1784463360 -0.1703363955 -0.0446933918 -0.1001218483 453 1311867185.5336329937 0.0442703180 0.0669326969 0.0879938230 0.0058760228 0.7626300000 969219393 0 1782841344 -0.1677029431 -0.0442318432 -0.0989775732 454 1311867185.5666799545 0.0441662706 0.0668825506 0.0879938230 0.0058700280 0.7571050000 969221211 0 1784557568 -0.1661491543 -0.0453388765 -0.0981684402 455 1311867185.5970540047 0.0437718369 0.0668317578 0.0879938230 0.0058692946 0.7550380000 969222965 0 1782947840 -0.1632625461 -0.0466053225 -0.0978191867 456 1311867185.6329469681 0.0436101817 0.0667808333 0.0879938230 0.0058913896 0.7520900000 969224815 0 1781313536 -0.1610289961 -0.0461378247 -0.0968455449 457 1311867185.6664180756 0.0435544811 0.0667300097 0.0879938230 0.0058921365 0.7489820000 969226601 0 1783054336 -0.1575590968 -0.0467179678 -0.0960324854 458 1311867185.6973390579 0.0430778898 0.0666783676 0.0879938230 0.0058857077 0.7501530000 969228387 0 1784557568 -0.1545867771 -0.0475468040 -0.0953704417 459 1311867185.7351899147 0.0431323908 0.0666270691 0.0879938230 0.0058814283 0.7507860000 969230237 0 1782693888 -0.1513461769 -0.0471710563 -0.0937969834 460 1311867185.7649769783 0.0434882268 0.0665767673 0.0879938230 0.0058762023 0.7483490000 969232023 0 1784324096 -0.1487487406 -0.0486296155 -0.0925224870 461 1311867185.7989649773 0.0435772836 0.0665268769 0.0879938230 0.0058819979 0.7468040000 969233809 0 1782202368 -0.1457696557 -0.0498448499 -0.0916991979 462 1311867185.8327999115 0.0436031781 0.0664772585 0.0879938230 0.0058773226 0.7726740000 969235659 0 1784057856 -0.1424308866 -0.0496207327 -0.0905866623 463 1311867185.8649098873 0.0436655059 0.0664279890 0.0879938230 0.0058719419 0.7442710000 969237445 0 1782337536 -0.1394404620 -0.0507574938 -0.0894353539 464 1311867185.9030420780 0.0427812971 0.0663770264 0.0879938230 0.0058669160 0.7405640000 969239295 0 1783947264 -0.1370272487 -0.0516633429 -0.0885705352 465 1311867185.9396789074 0.0426522084 0.0663260052 0.0879938230 0.0058623816 0.7542080000 969241177 0 1781940224 -0.1348496079 -0.0517420135 -0.0870023593 466 1311867185.9650609493 0.0431744978 0.0662763239 0.0879938230 0.0058745656 0.7709870000 969242803 0 1783676928 -0.1319580227 -0.0535531417 -0.0859602541 467 1311867186.0039470196 0.0431120247 0.0662267215 0.0879938230 0.0058709647 0.7513480000 969244717 0 1782067200 -0.1292021573 -0.0545426160 -0.0850141197 468 1311867186.0396919250 0.0434392542 0.0661780304 0.0879938230 0.0058741769 0.7586540000 969246567 0 1783689216 -0.1269929856 -0.0543068536 -0.0836563259 469 1311867186.0653240681 0.0437498912 0.0661302092 0.0879938230 0.0058763728 0.7621380000 969248289 0 1781678080 -0.1254011393 -0.0559978597 -0.0827314630 470 1311867186.1047339439 0.0430136099 0.0660810249 0.0879938230 0.0058708634 0.7547490000 969250171 0 1783414784 -0.1240509152 -0.0574170537 -0.0822096393 471 1311867186.1361179352 0.0440868475 0.0660343282 0.0879938230 0.0058666075 0.7631120000 969251925 0 1781825536 -0.1206708252 -0.0579558983 -0.0813584477 472 1311867186.1649448872 0.0440382585 0.0659877263 0.0879938230 0.0058619627 0.7635290000 969253679 0 1783435264 -0.1191956401 -0.0592984073 -0.0808850676 473 1311867186.2044749260 0.0438622460 0.0659409494 0.0879938230 0.0058558354 0.7591810000 969255593 0 1781424128 -0.1169036329 -0.0599743389 -0.0805246681 474 1311867186.2359659672 0.0439480469 0.0658945509 0.0879938230 0.0058516889 0.7706070000 969257347 0 1783160832 -0.1150396019 -0.0603177994 -0.0797621608 475 1311867186.2674899101 0.0435943753 0.0658476031 0.0879938230 0.0058457246 0.7571110000 969259133 0 1781420032 -0.1139766797 -0.0614375025 -0.0791197494 476 1311867186.3030838966 0.0431617759 0.0657999438 0.0879938230 0.0058414187 0.7961540000 969260983 0 1783181312 -0.1119579375 -0.0617541894 -0.0784800276 477 1311867186.3349270821 0.0434784926 0.0657531483 0.0879938230 0.0058372930 0.7598310000 969262737 0 1781170176 -0.1089337692 -0.0619332902 -0.0772994906 478 1311867186.3670160770 0.0430223905 0.0657055944 0.0879938230 0.0058378830 0.7611860000 969264491 0 1782906880 -0.1075842679 -0.0637089238 -0.0765909925 479 1311867186.4019849300 0.0429281592 0.0656580424 0.0879938230 0.0058422193 0.7601520000 969266309 0 1784573952 -0.1054970026 -0.0639461875 -0.0756396502 480 1311867186.4360210896 0.0434559211 0.0656117880 0.0879938230 0.0058406466 0.7635860000 969268127 0 1782947840 -0.1025591195 -0.0636548549 -0.0739530474 481 1311867186.4659481049 0.0433771089 0.0655655620 0.0879938230 0.0058367135 0.7569670000 969269881 0 1784578048 -0.1013211682 -0.0654677153 -0.0727899894 482 1311867186.5031139851 0.0427470803 0.0655182208 0.0879938230 0.0058318838 0.7608840000 969271763 0 1782566912 -0.0997218713 -0.0665442944 -0.0719540119 483 1311867186.5363171101 0.0437503792 0.0654731528 0.0879938230 0.0058270875 0.7923870000 969273549 0 1784193024 -0.0967074707 -0.0661630556 -0.0703641176 484 1311867186.5651130676 0.0439684577 0.0654287216 0.0879938230 0.0058269778 0.7640010000 969275303 0 1782308864 -0.0951442420 -0.0675949454 -0.0696712732 485 1311867186.6014220715 0.0438881330 0.0653843080 0.0879938230 0.0058214005 0.7655570000 969277153 0 1783955456 -0.0936955661 -0.0685246140 -0.0694344640 486 1311867186.6362628937 0.0442850702 0.0653408939 0.0879938230 0.0058154290 0.7660620000 969278971 0 1782439936 -0.0916449428 -0.0689268112 -0.0691956952 487 1311867186.6650478840 0.0448603854 0.0652988395 0.0879938230 0.0058117988 0.7644830000 969280693 0 1784070144 -0.0899348184 -0.0686497018 -0.0689284578 488 1311867186.7043809891 0.0447149314 0.0652566594 0.0879938230 0.0058256494 0.7592840000 969282639 0 1782059008 -0.0882794857 -0.0690040663 -0.0692162290 489 1311867186.7337749004 0.0450490378 0.0652153350 0.0879938230 0.0058279346 0.7636600000 969284361 0 1783816192 -0.0863197669 -0.0677724257 -0.0693600923 490 1311867186.7673180103 0.0455743559 0.0651752514 0.0879938230 0.0058230624 0.7944310000 969286179 0 1781821440 -0.0842850730 -0.0670936182 -0.0692666322 491 1311867186.8047299385 0.0453873649 0.0651349502 0.0879938230 0.0058237647 0.7664590000 969288061 0 1783431168 -0.0828569010 -0.0680311844 -0.0699619353 492 1311867186.8340749741 0.0452660881 0.0650945663 0.0879938230 0.0058221271 0.7637080000 969289783 0 1781551104 -0.0815085694 -0.0667035207 -0.0702211931 493 1311867186.8775999546 0.0454006158 0.0650546191 0.0879938230 0.0058166590 0.7671730000 969291761 0 1783308288 -0.0789944679 -0.0652320012 -0.0703044012 494 1311867186.9052100182 0.0454120450 0.0650148568 0.0879938230 0.0058122180 0.7665400000 969293451 0 1781424128 -0.0776158199 -0.0648748204 -0.0704866052 495 1311867186.9334239960 0.0452799611 0.0649749884 0.0879938230 0.0058071713 0.7578690000 969295237 0 1783160832 -0.0758805797 -0.0643822849 -0.0706941932 496 1311867186.9663379192 0.0458211079 0.0649363717 0.0879938230 0.0058089537 0.7668130000 969296991 0 1781555200 -0.0733753964 -0.0624318644 -0.0704723895 497 1311867187.0017139912 0.0459823385 0.0648982348 0.0879938230 0.0058098745 0.7643330000 969298745 0 1783181312 -0.0709212571 -0.0621705838 -0.0706377402 498 1311867187.0336461067 0.0455562323 0.0648593954 0.0879938230 0.0058131924 0.7624590000 969300531 0 1781190656 -0.0691161975 -0.0612772740 -0.0709982291 499 1311867187.0749349594 0.0454381593 0.0648204751 0.0879938230 0.0058136454 0.7583150000 969302477 0 1782906880 -0.0677316040 -0.0593212135 -0.0706381500 500 1311867187.1016030312 0.0457581356 0.0647823504 0.0879938230 0.0058092891 0.7547040000 969304199 0 1784557568 -0.0648082867 -0.0585543960 -0.0704950318 501 1311867187.1342070103 0.0454343222 0.0647437316 0.0879938230 0.0058082070 0.7525560000 969305985 0 1782968320 -0.0633720830 -0.0599842258 -0.0708001927 502 1311867187.1710209846 0.0453845523 0.0647051675 0.0879938230 0.0058153646 0.7505290000 969307835 0 1781317632 -0.0615106151 -0.0589024648 -0.0707102269 503 1311867187.2041370869 0.0459951125 0.0646679706 0.0879938230 0.0058201585 0.7449670000 969309653 0 1782943744 -0.0587881804 -0.0582134798 -0.0707549304 504 1311867187.2331659794 0.0461072885 0.0646311438 0.0879938230 0.0058224791 0.7901450000 969311407 0 1780916224 -0.0556332022 -0.0590905920 -0.0714608058 505 1311867187.2707629204 0.0460449979 0.0645943396 0.0879938230 0.0058254161 0.7425790000 969313257 0 1782652928 -0.0533528775 -0.0579526834 -0.0717911124 506 1311867187.3015060425 0.0461029299 0.0645577953 0.0879938230 0.0058267364 0.7465960000 969315043 0 1784320000 -0.0513255633 -0.0579524562 -0.0721277744 507 1311867187.3336570263 0.0460027568 0.0645211976 0.0879938230 0.0058211378 0.7526690000 969316797 0 1782722560 -0.0497478843 -0.0586339980 -0.0728272945 508 1311867187.3707590103 0.0461712852 0.0644850757 0.0879938230 0.0058166407 0.7520450000 969318679 0 1784438784 -0.0483709313 -0.0585776567 -0.0732579008 509 1311867187.4033529758 0.0460813642 0.0644489191 0.0879938230 0.0058142633 0.7513770000 969320497 0 1782702080 -0.0468807854 -0.0586252287 -0.0738674030 510 1311867187.4335899353 0.0457998328 0.0644123523 0.0879938230 0.0058126030 0.7563940000 969322251 0 1784455168 -0.0451690070 -0.0591584146 -0.0744744763 511 1311867187.4763159752 0.0462230556 0.0643767568 0.0879938230 0.0058088526 0.7965010000 969324197 0 1782849536 -0.0426682383 -0.0588257201 -0.0748861358 512 1311867187.5056400299 0.0465775765 0.0643419928 0.0879938230 0.0058054341 0.7524420000 969325919 0 1784459264 -0.0399968065 -0.0593701750 -0.0755303428 513 1311867187.5342190266 0.0468437113 0.0643078830 0.0879938230 0.0058020729 0.7526690000 969327673 0 1782579200 -0.0371870436 -0.0597937964 -0.0763929486 514 1311867187.5709679127 0.0469409227 0.0642740952 0.0879938230 0.0057968180 0.7535430000 969413491 0 1784209408 -0.0344156027 -0.0600474365 -0.0772901475 515 1311867187.6045789719 0.0458121300 0.0642382467 0.0879938230 0.0058221693 0.7569420000 969415341 0 1782566912 -0.0331620090 -0.0601146407 -0.0786200538 516 1311867187.6353919506 0.0458627865 0.0642026353 0.0879938230 0.0058182621 0.7489910000 969417095 0 1784344576 -0.0304296538 -0.0605586767 -0.0798329189 517 1311867187.6707689762 0.0457124934 0.0641668710 0.0879938230 0.0058220258 0.7654590000 969418913 0 1782079488 -0.0272986665 -0.0596661568 -0.0808482543 518 1311867187.7035770416 0.0462035276 0.0641321928 0.0879938230 0.0058233393 0.7581020000 969420731 0 1783795712 -0.0246867798 -0.0593328401 -0.0815356746 519 1311867187.7345480919 0.0454245806 0.0640961473 0.0879938230 0.0058355948 0.7589450000 969422357 0 1782190080 -0.0228422415 -0.0610667430 -0.0830259770 520 1311867187.7707819939 0.0453128517 0.0640600256 0.0879938230 0.0058349111 0.7494570000 969424207 0 1783922688 -0.0202025883 -0.0596110597 -0.0837642103 521 1311867187.8017508984 0.0457995199 0.0640249766 0.0879938230 0.0058305796 0.7642170000 969425993 0 1782317056 -0.0173935611 -0.0589599684 -0.0845187381 522 1311867187.8339610100 0.0454408713 0.0639893749 0.0879938230 0.0058262313 0.7616430000 969427779 0 1783955456 -0.0153641161 -0.0589726195 -0.0853776932 523 1311867187.8708090782 0.0452044047 0.0639534571 0.0879938230 0.0058263779 0.7674090000 969429629 0 1782317056 -0.0124701578 -0.0580734983 -0.0859421939 524 1311867187.9038810730 0.0456249230 0.0639184790 0.0879938230 0.0058239330 0.7582980000 969431479 0 1784049664 -0.0091960384 -0.0573827662 -0.0864727423 525 1311867187.9363000393 0.0458182059 0.0638840023 0.0879938230 0.0058192278 0.7965340000 969433233 0 1782333440 -0.0060010869 -0.0570861958 -0.0871958137 526 1311867187.9713420868 0.0455838703 0.0638492112 0.0879938230 0.0058191389 0.7628140000 969435083 0 1784082432 -0.0030358471 -0.0578334257 -0.0883718878 527 1311867188.0047569275 0.0454594977 0.0638143161 0.0879938230 0.0058413074 0.7574380000 969436901 0 1782444032 -0.0004755447 -0.0568862595 -0.0893802717 528 1311867188.0333108902 0.0455927551 0.0637798056 0.0879938230 0.0058473862 0.7588900000 969438623 0 1784176640 0.0025916859 -0.0564966947 -0.0902371407 529 1311867188.0698699951 0.0453423522 0.0637449522 0.0879938230 0.0058418465 0.7666940000 969440441 0 1782571008 0.0057283682 -0.0576849431 -0.0916564539 530 1311867188.1088800430 0.0451593399 0.0637098850 0.0879938230 0.0058426284 0.7638370000 969442387 0 1784217600 0.0083636418 -0.0578543432 -0.0929626450 531 1311867188.1359970570 0.0439508632 0.0636726740 0.0879938230 0.0058498178 0.7590120000 969444077 0 1781936128 0.0120318923 -0.0569637492 -0.0940947533 532 1311867188.1703350544 0.0450453497 0.0636376602 0.0879938230 0.0058470212 0.7557900000 969445895 0 1783541760 0.0145082520 -0.0575817041 -0.0953783169 533 1311867188.2026720047 0.0447405167 0.0636022059 0.0879938230 0.0058488787 0.7603940000 969447713 0 1781698560 0.0162078794 -0.0581201762 -0.0967558548 534 1311867188.2352449894 0.0436175615 0.0635647815 0.0879938230 0.0058525702 0.7670360000 969449467 0 1783287808 0.0186540447 -0.0574537143 -0.0978985056 535 1311867188.2706460953 0.0443132631 0.0635287974 0.0879938230 0.0058498048 0.7567300000 969451317 0 1781444608 0.0219055340 -0.0572059080 -0.0990734845 536 1311867188.3047339916 0.0442588590 0.0634928460 0.0879938230 0.0058451425 0.7593760000 969453167 0 1783033856 0.0250832867 -0.0570751354 -0.1001976728 537 1311867188.3398799896 0.0441181920 0.0634567666 0.0879938230 0.0058406301 0.7493210000 969455017 0 1781301248 0.0273061749 -0.0563100092 -0.1010301262 538 1311867188.3718800545 0.0443929397 0.0634213319 0.0879938230 0.0058399984 0.7501590000 969456771 0 1782779904 0.0305969194 -0.0548828617 -0.1015011221 539 1311867188.4054470062 0.0442669652 0.0633857951 0.0879938230 0.0058410544 0.7839170000 969458557 0 1784430592 0.0338357538 -0.0543568917 -0.1020657867 540 1311867188.4398789406 0.0441457666 0.0633501654 0.0879938230 0.0058389579 0.7533840000 969460407 0 1782571008 0.0371427052 -0.0543329716 -0.1026922986 541 1311867188.4724500179 0.0445152745 0.0633153504 0.0879938230 0.0058416690 0.7511070000 969462193 0 1784082432 0.0395080969 -0.0524549782 -0.1028657332 542 1311867188.5049159527 0.0442944653 0.0632802565 0.0879938230 0.0058413866 0.7489600000 969463979 0 1782317056 0.0421119817 -0.0515148230 -0.1033027172 543 1311867188.5389990807 0.0441480279 0.0632450222 0.0879938230 0.0058433008 0.7550490000 969465829 0 1783922688 0.0448078886 -0.0517715700 -0.1039742380 544 1311867188.5723888874 0.0441351831 0.0632098939 0.0879938230 0.0058615658 0.7500790000 969467615 0 1782063104 0.0469395928 -0.0491707176 -0.1041191295 545 1311867188.6045958996 0.0447404981 0.0631760051 0.0879938230 0.0058563350 0.7496720000 969469401 0 1783574528 0.0493473560 -0.0484946370 -0.1040525064 546 1311867188.6398339272 0.0449491106 0.0631426225 0.0879938230 0.0058528225 0.7443390000 969471187 0 1781706752 0.0509085059 -0.0488990210 -0.1045950949 547 1311867188.6715080738 0.0454814620 0.0631103352 0.0879938230 0.0058529167 0.7456520000 969473005 0 1783296000 0.0536955707 -0.0479009636 -0.1050454304 548 1311867188.7038300037 0.0455087461 0.0630782155 0.0879938230 0.0058522534 0.7401550000 969474791 0 1781305344 0.0548559800 -0.0481650978 -0.1059126556 549 1311867188.7393829823 0.0453684218 0.0630459572 0.0879938230 0.0058571526 0.7360200000 969476609 0 1782915072 0.0561218560 -0.0487220176 -0.1071211770 550 1311867188.7721049786 0.0455431119 0.0630141338 0.0879938230 0.0058532280 0.7301620000 969478427 0 1784582144 0.0570268035 -0.0475830361 -0.1081647351 551 1311867188.8045220375 0.0463654958 0.0629839185 0.0879938230 0.0058533659 0.7239110000 969480245 0 1782706176 0.0592402406 -0.0462345928 -0.1089508981 552 1311867188.8402431011 0.0471775569 0.0629552838 0.0879938230 0.0058518452 0.7075340000 969482063 0 1784184832 0.0614363290 -0.0469437391 -0.1099007130 553 1311867188.8705990314 0.0476826057 0.0629276659 0.0879938230 0.0058490482 0.7347980000 969483817 0 1782325248 0.0631282777 -0.0465223007 -0.1108751372 554 1311867188.9016311169 0.0477672517 0.0629003006 0.0879938230 0.0058455693 0.6974390000 969485603 0 1783803904 0.0657955110 -0.0451761223 -0.1119481921 555 1311867188.9401769638 0.0483235456 0.0628740362 0.0879938230 0.0058439979 0.6896420000 969487517 0 1781944320 0.0695156977 -0.0457545593 -0.1131150052 556 1311867188.9709990025 0.0483366102 0.0628478897 0.0879938230 0.0058432764 0.6827020000 969489239 0 1783541760 0.0723982751 -0.0458109900 -0.1139376536 557 1311867189.0052258968 0.0485698245 0.0628222558 0.0879938230 0.0058389703 0.6874880000 969491089 0 1781682176 0.0763346776 -0.0449126214 -0.1143328026 558 1311867189.0400099754 0.0489930585 0.0627974723 0.0879938230 0.0058400054 0.6823690000 969492875 0 1783193600 0.0790175945 -0.0447522923 -0.1147475466 559 1311867189.0724329948 0.0488308854 0.0627724874 0.0879938230 0.0058386131 0.6816580000 969494725 0 1781301248 0.0822195336 -0.0447359644 -0.1149106771 560 1311867189.1026360989 0.0491767563 0.0627482093 0.0879938230 0.0058378160 0.6753960000 969496479 0 1782812672 0.0845813379 -0.0437341444 -0.1144043058 561 1311867189.1417639256 0.0494168364 0.0627244457 0.0879938230 0.0058333898 0.6758380000 969498393 0 1784557568 0.0869851187 -0.0436726920 -0.1136148870 562 1311867189.1717920303 0.0492399037 0.0627004519 0.0879938230 0.0058302202 0.6730170000 969500147 0 1782587392 0.0880171955 -0.0439604744 -0.1128539741 563 1311867189.2019069195 0.0494818985 0.0626769731 0.0879938230 0.0058256204 0.6774230000 969501901 0 1784176640 0.0903526098 -0.0437223241 -0.1116919890 564 1311867189.2390630245 0.0496042594 0.0626537945 0.0879938230 0.0058230542 0.6658580000 969503751 0 1782317056 0.0910057351 -0.0439216383 -0.1108968705 565 1311867189.2722640038 0.0495500006 0.0626306019 0.0879938230 0.0058183618 0.6712150000 969505537 0 1783795712 0.0925586298 -0.0446610749 -0.1100537106 566 1311867189.3046789169 0.0496642254 0.0626076932 0.0879938230 0.0058140607 0.6724260000 969507355 0 1781936128 0.0955843925 -0.0452299640 -0.1089517027 567 1311867189.3397970200 0.0491536073 0.0625839646 0.0879938230 0.0058174683 0.6604560000 969509173 0 1783447552 0.0972904116 -0.0466557406 -0.1082500517 568 1311867189.3720359802 0.0497447029 0.0625613603 0.0879938230 0.0058545729 0.6607580000 969510959 0 1781682176 0.0994483978 -0.0475882329 -0.1074346080 569 1311867189.4056949615 0.0497142524 0.0625387819 0.0879938230 0.0058583565 0.6858110000 969512777 0 1783193600 0.1035258994 -0.0472541228 -0.1059637517 570 1311867189.4405019283 0.0495871976 0.0625160598 0.0879938230 0.0058599933 0.6684310000 969514595 0 1781428224 0.1061364934 -0.0490125157 -0.1052586213 571 1311867189.4729130268 0.0503171459 0.0624946957 0.0879938230 0.0058562369 0.6609540000 969516413 0 1782923264 0.1089133844 -0.0507947169 -0.1045250669 572 1311867189.5060400963 0.0501622930 0.0624731355 0.0879938230 0.0058533680 0.6551590000 969518199 0 1781190656 0.1118686572 -0.0512213297 -0.1041605622 573 1311867189.5394289494 0.0502938777 0.0624518803 0.0879938230 0.0058491101 0.6553840000 969519985 0 1782812672 0.1153707057 -0.0534506105 -0.1039198190 574 1311867189.5720269680 0.0501110815 0.0624303806 0.0879938230 0.0058471936 0.6563270000 969521803 0 1784557568 0.1186292097 -0.0559489764 -0.1044377908 575 1311867189.6112909317 0.0506350696 0.0624098670 0.0879938230 0.0058447726 0.6517630000 969523685 0 1782820864 0.1233139783 -0.0563117005 -0.1044368967 576 1311867189.6424219608 0.0508069694 0.0623897231 0.0879938230 0.0058408495 0.6445600000 969525471 0 1784557568 0.1263473183 -0.0569482557 -0.1045525894 577 1311867189.6728401184 0.0508746244 0.0623697663 0.0879938230 0.0058360799 0.6815500000 969527257 0 1782947840 0.1290704310 -0.0584520809 -0.1048028171 578 1311867189.7065870762 0.0514802039 0.0623509262 0.0879938230 0.0058343473 0.6641910000 969529043 0 1784578048 0.1321672648 -0.0589704998 -0.1047168747 579 1311867189.7401719093 0.0513792038 0.0623319768 0.0879938230 0.0058298188 0.6557270000 969530861 0 1782566912 0.1366579384 -0.0587915629 -0.1041545570 580 1311867189.7729759216 0.0514832847 0.0623132721 0.0879938230 0.0058248444 0.6554610000 969532647 0 1784303616 0.1400240213 -0.0587231703 -0.1038609147 581 1311867189.8073968887 0.0510149300 0.0622938258 0.0879938230 0.0058232523 0.6696500000 969534465 0 1782714368 0.1432853043 -0.0597844087 -0.1033459902 582 1311867189.8405311108 0.0511746965 0.0622747207 0.0879938230 0.0058198295 0.6642330000 969536251 0 1784344576 0.1472254246 -0.0601808541 -0.1022681147 583 1311867189.8713529110 0.0508538820 0.0622551310 0.0879938230 0.0058159775 0.6678420000 969538037 0 1782181888 0.1513503194 -0.0611500181 -0.1014321148 584 1311867189.9102680683 0.0507537387 0.0622354368 0.0879938230 0.0058163020 0.6600980000 969539919 0 1783959552 0.1538436562 -0.0627329424 -0.1012452096 585 1311867189.9402260780 0.0504044332 0.0622152129 0.0879938230 0.0058127815 0.7106610000 969541705 0 1782202368 0.1578317434 -0.0628434420 -0.1008971557 586 1311867189.9727621078 0.0501188114 0.0621945705 0.0879938230 0.0058079211 0.6627600000 969543491 0 1783828480 0.1619335115 -0.0631047934 -0.1005780846 587 1311867190.0107009411 0.0503206886 0.0621743425 0.0879938230 0.0058059669 0.6801530000 969545341 0 1782181888 0.1652814746 -0.0637516156 -0.1004942805 588 1311867190.0402929783 0.0504664294 0.0621544310 0.0879938230 0.0058026732 0.6638260000 969547095 0 1783828480 0.1681109220 -0.0642103553 -0.1004210040 589 1311867190.0719039440 0.0506563708 0.0621349097 0.0879938230 0.0057982834 0.6727780000 969548881 0 1782177792 0.1707396954 -0.0650255829 -0.1004575938 590 1311867190.1096539497 0.0539918579 0.0621211079 0.0879938230 0.0058081609 0.6635410000 969550763 0 1783959552 0.1650584042 -0.0659054145 -0.1020752788 591 1311867190.1396369934 0.0549914241 0.0621090442 0.0879938230 0.0058064167 0.6660930000 969552549 0 1782325248 0.1661363244 -0.0655541793 -0.1026265398 592 1311867190.1706380844 0.0555980466 0.0620980459 0.0879938230 0.0058074266 0.6634990000 969554271 0 1784086528 0.1678483188 -0.0659637302 -0.1029811651 593 1311867190.2096021175 0.0564013757 0.0620884393 0.0879938230 0.0058033478 0.6666220000 969556185 0 1782435840 0.1689461023 -0.0678687543 -0.1037288904 594 1311867190.2394330502 0.0564653315 0.0620789728 0.0879938230 0.0058085714 0.6541640000 969557907 0 1784213504 0.1721969247 -0.0672912821 -0.1038652807 595 1311867190.2714810371 0.0568817519 0.0620702380 0.0879938230 0.0058101495 0.6586670000 969559725 0 1782562816 0.1742671430 -0.0675983503 -0.1041295826 596 1311867190.3072700500 0.0579314716 0.0620632938 0.0879938230 0.0058084556 0.6529400000 969561575 0 1784348672 0.1756761819 -0.0677592680 -0.1043319702 597 1311867190.3414731026 0.0575116612 0.0620556696 0.0879938230 0.0058053318 0.6449810000 969563393 0 1782697984 0.1793997288 -0.0678570867 -0.1041377708 598 1311867190.3716828823 0.0570073798 0.0620472276 0.0879938230 0.0058079262 0.6454680000 969565147 0 1784475648 0.1830969155 -0.0673486888 -0.1036962345 599 1311867190.4101090431 0.0578893498 0.0620402863 0.0879938230 0.0058059810 0.6572280000 969566997 0 1782845440 0.1845778078 -0.0676207542 -0.1037872881 600 1311867190.4394960403 0.0577375442 0.0620331150 0.0879938230 0.0058033830 0.6620660000 969568815 0 1784492032 0.1877806634 -0.0667652488 -0.1031729579 601 1311867190.4708199501 0.0578412302 0.0620261402 0.0879938230 0.0057992924 0.6867870000 969570537 0 1782841344 0.1903792620 -0.0671960860 -0.1027386338 602 1311867190.5097529888 0.0576175116 0.0620188169 0.0879938230 0.0057950371 0.6506650000 969572483 0 1781170176 0.1931057274 -0.0680658594 -0.1023996919 603 1311867190.5405189991 0.0582127050 0.0620125049 0.0879938230 0.0057970346 0.6553190000 969574205 0 1782968320 0.1953571290 -0.0670176223 -0.1021567807 604 1311867190.5708439350 0.0581706204 0.0620061442 0.0879938230 0.0057943426 0.6662240000 969575959 0 1781301248 0.1978677511 -0.0677928552 -0.1016065702 605 1311867190.6067750454 0.0583340451 0.0620000746 0.0879938230 0.0057900451 0.6591240000 969577809 0 1783078912 0.1999045312 -0.0683911890 -0.1014923379 606 1311867190.6389939785 0.0578697808 0.0619932589 0.0879938230 0.0057863422 0.6612000000 969579627 0 1781420032 0.2034628391 -0.0681577101 -0.1007355973 607 1311867190.6723659039 0.0577881858 0.0619863313 0.0879938230 0.0057824055 0.6652660000 969581413 0 1783066624 0.2067763358 -0.0692612231 -0.0999223739 608 1311867190.7114980221 0.0583678596 0.0619803799 0.0879938230 0.0057794627 0.6669060000 969583295 0 1781420032 0.2086078823 -0.0696616545 -0.0993009657 609 1311867190.7392649651 0.0578367785 0.0619735759 0.0879938230 0.0057750816 0.7002350000 969584985 0 1783181312 0.2114271075 -0.0701972693 -0.0984911323 610 1311867190.7751801014 0.0574922375 0.0619662295 0.0879938230 0.0057705579 0.6702250000 969586835 0 1781186560 0.2141136527 -0.0704674572 -0.0979105532 611 1311867190.8070900440 0.0575665608 0.0619590287 0.0879938230 0.0057668106 0.6658830000 969588653 0 1782906880 0.2167117745 -0.0707615986 -0.0970383734 612 1311867190.8414280415 0.0571688339 0.0619512016 0.0879938230 0.0057687163 0.6642030000 969590471 0 1781297152 0.2193602920 -0.0721074343 -0.0962699428 613 1311867190.8739249706 0.0576320179 0.0619441556 0.0879938230 0.0057647349 0.6664090000 969592257 0 1782927360 0.2209453136 -0.0730998144 -0.0956423879 614 1311867190.9076139927 0.0577365234 0.0619373028 0.0879938230 0.0057601941 0.6731740000 969594075 0 1784446976 0.2231757045 -0.0732241347 -0.0948269889 615 1311867190.9393599033 0.0571757406 0.0619295604 0.0879938230 0.0057570438 0.6683040000 969595829 0 1782566912 0.2263802290 -0.0746472329 -0.0939749777 616 1311867190.9741609097 0.0572037771 0.0619218887 0.0879938230 0.0057527081 0.6582110000 969597679 0 1784336384 0.2285767943 -0.0758594796 -0.0934160054 617 1311867191.0085949898 0.0573705770 0.0619145122 0.0879938230 0.0057555707 0.6707870000 969599497 0 1782693888 0.2313562036 -0.0749394447 -0.0924769789 618 1311867191.0396919250 0.0574918203 0.0619073557 0.0879938230 0.0057523374 0.6683600000 969601283 0 1784324096 0.2334159613 -0.0753506273 -0.0915010497 619 1311867191.0764329433 0.0578314513 0.0619007710 0.0879938230 0.0057502450 0.6673870000 969603133 0 1782312960 0.2347712368 -0.0774542913 -0.0911613032 620 1311867191.1103041172 0.0586842522 0.0618955831 0.0879938230 0.0057560146 0.6617810000 969604951 0 1784049664 0.2373175472 -0.0773064792 -0.0899030566 621 1311867191.1388139725 0.0577109754 0.0618888446 0.0879938230 0.0057679696 0.6848420000 969606705 0 1782460416 0.2414419055 -0.0777149722 -0.0887774900 622 1311867191.1742820740 0.0583931282 0.0618832245 0.0879938230 0.0057649871 0.6714300000 969608523 0 1784070144 0.2425928712 -0.0791558772 -0.0883182809 623 1311867191.2077920437 0.0587808266 0.0618782447 0.0879938230 0.0057604777 0.6671050000 969610341 0 1782079488 0.2453230470 -0.0787785500 -0.0873233974 624 1311867191.2408421040 0.0595974177 0.0618745895 0.0879938230 0.0057571321 0.6628570000 969612159 0 1783795712 0.2470606565 -0.0787819028 -0.0867107138 625 1311867191.2769579887 0.0602387674 0.0618719722 0.0879938230 0.0057549118 0.7134460000 969613977 0 1782206464 0.2491734177 -0.0794684663 -0.0861362517 626 1311867191.3085029125 0.0607159026 0.0618701255 0.0879938230 0.0057560107 0.6622470000 969615667 0 1783816192 0.2514884770 -0.0786514282 -0.0852444917 627 1311867191.3404779434 0.0606077723 0.0618681121 0.0879938230 0.0057528967 0.6747530000 969617453 0 1781825536 0.2543446124 -0.0792383701 -0.0843202323 628 1311867191.3794629574 0.0607183836 0.0618662814 0.0879938230 0.0057486515 0.6656720000 969619367 0 1783541760 0.2562068999 -0.0805896670 -0.0838597938 629 1311867191.4091579914 0.0602083765 0.0618636456 0.0879938230 0.0057455945 0.6765330000 969621089 0 1781952512 0.2593692839 -0.0812659413 -0.0830139890 630 1311867191.4415969849 0.0595272370 0.0618599370 0.0879938230 0.0057418580 0.6674230000 969622875 0 1783562240 0.2630372941 -0.0809436888 -0.0820731297 631 1311867191.4775309563 0.0599266924 0.0618568732 0.0879938230 0.0057424372 0.6692300000 969624693 0 1781420032 0.2640049756 -0.0823364332 -0.0817145780 632 1311867191.5075590611 0.0600473993 0.0618540101 0.0879938230 0.0057384346 0.6703810000 969626415 0 1783193600 0.2656361163 -0.0820004046 -0.0808858275 633 1311867191.5390620232 0.0595078468 0.0618503037 0.0879938230 0.0057341535 0.6683270000 969628201 0 1781551104 0.2686074972 -0.0822711810 -0.0800542682 634 1311867191.5764698982 0.0597577170 0.0618470031 0.0879938230 0.0057306533 0.6747320000 969630051 0 1783287808 0.2707704902 -0.0822387189 -0.0793093517 635 1311867191.6118669510 0.0597829744 0.0618437527 0.0879938230 0.0057555370 0.6743120000 969631901 0 1781698560 0.2733978629 -0.0815445408 -0.0782194063 636 1311867191.6451880932 0.0597631373 0.0618404813 0.0879938230 0.0057524935 0.6732630000 969633687 0 1783320576 0.2752816379 -0.0819655284 -0.0770531967 637 1311867191.6827919483 0.0586477146 0.0618354691 0.0879938230 0.0057565825 0.6835130000 969635601 0 1781694464 0.2785885036 -0.0827357545 -0.0757841021 638 1311867191.7119400501 0.0586734191 0.0618305129 0.0879938230 0.0057546270 0.6743280000 969637323 0 1783324672 0.2803943157 -0.0821855664 -0.0748362318 639 1311867191.7457199097 0.0588087961 0.0618257840 0.0879938230 0.0057700278 0.6785540000 969639077 0 1781313536 0.2804464102 -0.0827910453 -0.0743811280 640 1311867191.7763800621 0.0593141243 0.0618218596 0.0879938230 0.0057731670 0.6752410000 969640831 0 1783033856 0.2814078331 -0.0828536674 -0.0735324696 641 1311867191.8097250462 0.0582797863 0.0618163337 0.0879938230 0.0057715411 0.7132940000 969642649 0 1781444608 0.2848813832 -0.0828299671 -0.0717095509 642 1311867191.8395779133 0.0576835610 0.0618098964 0.0879938230 0.0057755571 0.6865800000 969644403 0 1783160832 0.2865324914 -0.0833722576 -0.0710965768 643 1311867191.8745219707 0.0580048487 0.0618039787 0.0879938230 0.0057773628 0.6879050000 969646221 0 1781571584 0.2875160277 -0.0828671977 -0.0701755360 644 1311867191.9077119827 0.0567989983 0.0617962070 0.0879938230 0.0057739245 0.6856840000 969648039 0 1783328768 0.2905316949 -0.0831636116 -0.0687357634 645 1311867191.9391601086 0.0575011224 0.0617895480 0.0879938230 0.0057706327 0.6864950000 969649825 0 1781166080 0.2906857133 -0.0842816532 -0.0680174008 646 1311867191.9755239487 0.0570034161 0.0617821391 0.0879938230 0.0057696150 0.6852900000 969651643 0 1782939648 0.2928217947 -0.0840598345 -0.0668400526 647 1311867192.0076289177 0.0573630147 0.0617753089 0.0879938230 0.0057662378 0.6901750000 969653429 0 1781452800 0.2937386036 -0.0840930641 -0.0658900291 648 1311867192.0447950363 0.0569215603 0.0617678186 0.0879938230 0.0057751533 0.6891080000 969655311 0 1783074816 0.2945650816 -0.0857828707 -0.0655422211 649 1311867192.0751929283 0.0573520362 0.0617610146 0.0879938230 0.0057737171 0.6861410000 969657033 0 1781432320 0.2950821221 -0.0855080038 -0.0649343133 650 1311867192.1073920727 0.0573256724 0.0617541910 0.0879938230 0.0057722530 0.6927450000 969658851 0 1783169024 0.2977640033 -0.0848280415 -0.0633258671 651 1311867192.1433029175 0.0580619760 0.0617485194 0.0879938230 0.0057769232 0.6946900000 969660701 0 1781579776 0.2970792353 -0.0862864405 -0.0633151084 652 1311867192.1754670143 0.0590139031 0.0617443252 0.0879938230 0.0057818707 0.6918980000 969662487 0 1783201792 0.2975403965 -0.0857621953 -0.0624917038 653 1311867192.2077538967 0.0589491017 0.0617400446 0.0879938230 0.0057785647 0.6874210000 969664305 0 1781559296 0.2997363508 -0.0854781717 -0.0613059625 654 1311867192.2451250553 0.0584459342 0.0617350077 0.0879938230 0.0057863116 0.6874290000 969666187 0 1783296000 0.3014686108 -0.0872352049 -0.0603227615 655 1311867192.2744629383 0.0590356141 0.0617308865 0.0879938230 0.0057842305 0.6882920000 969667909 0 1781571584 0.3024509549 -0.0863493383 -0.0596491136 656 1311867192.3067719936 0.0592161119 0.0617270530 0.0879938230 0.0057820718 0.6800470000 969669695 0 1783193600 0.3044680953 -0.0869387314 -0.0584710687 657 1311867192.3427391052 0.0596467629 0.0617238867 0.0879938230 0.0057788397 0.7092340000 969671545 0 1781571584 0.3052995205 -0.0884576812 -0.0580172874 658 1311867192.3755910397 0.0609612241 0.0617227276 0.0879938230 0.0057816605 0.6903320000 969673363 0 1783160832 0.3059704006 -0.0881423280 -0.0574683286 659 1311867192.4059340954 0.0606766157 0.0617211402 0.0879938230 0.0057777252 0.6937730000 969675085 0 1781571584 0.3084964156 -0.0888974071 -0.0567212626 660 1311867192.4447100163 0.0619163886 0.0617214360 0.0879938230 0.0057751359 0.6871650000 969676999 0 1783160832 0.3091114759 -0.0902419016 -0.0567739308 661 1311867192.4748210907 0.0634757876 0.0617240901 0.0879938230 0.0057747532 0.6908460000 969678753 0 1781571584 0.3094933927 -0.0899393931 -0.0564083569 662 1311867192.5077190399 0.0643242374 0.0617280178 0.0879938230 0.0057708986 0.6850610000 969680539 0 1783160832 0.3104281425 -0.0906811580 -0.0560372919 663 1311867192.5427820683 0.0643649474 0.0617319951 0.0879938230 0.0057693722 0.6875680000 969682389 0 1781444608 0.3115700781 -0.0923030227 -0.0561434999 664 1311867192.5787169933 0.0655943155 0.0617378118 0.0879938230 0.0057696597 0.6935420000 969684207 0 1783066624 0.3123826981 -0.0917515978 -0.0560411029 665 1311867192.6109929085 0.0681328848 0.0617474285 0.0879938230 0.0057665080 0.7026810000 969685993 0 1781301248 0.3107953966 -0.0913890079 -0.0561539419 666 1311867192.6435210705 0.0695236251 0.0617591045 0.0879938230 0.0057665411 0.6814330000 969687811 0 1782906880 0.3103911877 -0.0926626548 -0.0563949347 667 1311867192.6790139675 0.0699859858 0.0617714386 0.0879938230 0.0057636847 0.7015440000 969689661 0 1784557568 0.3118737042 -0.0924986824 -0.0558603890 668 1311867192.7113289833 0.0696320385 0.0617832060 0.0879938230 0.0057605661 0.6923020000 969691415 0 1782820864 0.3138009012 -0.0927205831 -0.0554784425 669 1311867192.7439620495 0.0704277754 0.0617961276 0.0879938230 0.0057599005 0.6916400000 969693233 0 1781317632 0.3140271604 -0.0936340541 -0.0552888662 670 1311867192.7760629654 0.0700864866 0.0618085013 0.0879938230 0.0057582245 0.6943290000 969695019 0 1782939648 0.3160710633 -0.0930087566 -0.0546934754 671 1311867192.8091869354 0.0702228323 0.0618210413 0.0879938230 0.0057540275 0.6989030000 969696837 0 1781297152 0.3172957301 -0.0936239660 -0.0542609170 672 1311867192.8422288895 0.0701042786 0.0618333675 0.0879938230 0.0057504057 0.6861710000 969698623 0 1783033856 0.3184920549 -0.0943671092 -0.0539254099 673 1311867192.8792889118 0.0707888231 0.0618466743 0.0879938230 0.0057510176 0.7403550000 969700505 0 1781444608 0.3191873133 -0.0935577452 -0.0533471107 674 1311867192.9092190266 0.0700676739 0.0618588716 0.0879938230 0.0057471502 0.6920180000 969702227 0 1783160832 0.3213333786 -0.0941004008 -0.0524356738 675 1311867192.9434111118 0.0698385090 0.0618706933 0.0879938230 0.0057443391 0.7008710000 969704077 0 1781571584 0.3225650489 -0.0956012607 -0.0522099659 676 1311867192.9776289463 0.0697685108 0.0618823765 0.0879938230 0.0057446233 0.6886060000 969705863 0 1783193600 0.3244501948 -0.0948684439 -0.0516288467 677 1311867193.0086810589 0.0697738305 0.0618940330 0.0879938230 0.0057424866 0.6995570000 969707649 0 1781571584 0.3253902495 -0.0950449929 -0.0511779897 678 1311867193.0430600643 0.0694494173 0.0619051766 0.0879938230 0.0057403963 0.6997320000 969709467 0 1783287808 0.3267589211 -0.0965535045 -0.0510733202 679 1311867193.0767369270 0.0700016618 0.0619171007 0.0879938230 0.0057457317 0.6998820000 969711253 0 1781698560 0.3279662728 -0.0953343064 -0.0509073585 680 1311867193.1105849743 0.0696833804 0.0619285217 0.0879938230 0.0057425943 0.7363610000 969713071 0 1783320576 0.3299361765 -0.0953154266 -0.0504043400 681 1311867193.1429219246 0.0686110333 0.0619383345 0.0879938230 0.0057436667 0.7075320000 969714889 0 1781678080 0.3314611316 -0.0968809575 -0.0503637046 682 1311867193.1767370701 0.0700615272 0.0619502454 0.0879938230 0.0057580281 0.7082590000 969716675 0 1783414784 0.3324097395 -0.0948431417 -0.0500379391 683 1311867193.2122681141 0.0702053010 0.0619623318 0.0879938230 0.0057582574 0.7119840000 969718525 0 1781825536 0.3337548375 -0.0953670293 -0.0495942645 684 1311867193.2432429790 0.0696907490 0.0619736307 0.0879938230 0.0057570375 0.7001750000 969720311 0 1783541760 0.3354823291 -0.0960997492 -0.0495615043 685 1311867193.2773900032 0.0704036951 0.0619859374 0.0879938230 0.0057550455 0.7193250000 969722129 0 1781952512 0.3362779021 -0.0950269401 -0.0494445786 686 1311867193.3139379025 0.0717306733 0.0620001425 0.0879938230 0.0057552084 0.7150760000 969723979 0 1783574528 0.3359970748 -0.0957760736 -0.0498198718 687 1311867193.3426671028 0.0714795813 0.0620139408 0.0879938230 0.0057548808 0.7456910000 969725701 0 1781932032 0.3375914395 -0.0955931842 -0.0495345332 688 1311867193.3788230419 0.0709161311 0.0620268800 0.0879938230 0.0057513910 0.7129450000 969727551 0 1783668736 0.3401193619 -0.0951059908 -0.0492183715 689 1311867193.4126739502 0.0714065880 0.0620404936 0.0879938230 0.0057575610 0.7052740000 969729337 0 1782079488 0.3407556117 -0.0962742269 -0.0493626520 690 1311867193.4440810680 0.0717593879 0.0620545789 0.0879938230 0.0057578229 0.7020410000 969731155 0 1783795712 0.3419938385 -0.0961117372 -0.0492810234 691 1311867193.4782969952 0.0719255060 0.0620688639 0.0879938230 0.0057545987 0.7153100000 969732973 0 1782190080 0.3437280059 -0.0955497697 -0.0490240864 692 1311867193.5199069977 0.0731385350 0.0620848605 0.0879938230 0.0057526811 0.7207860000 969734855 0 1783828480 0.3439872861 -0.0966779664 -0.0493108593 693 1311867193.5431120396 0.0723395124 0.0620996580 0.0879938230 0.0057520970 0.7075600000 969736545 0 1782185984 0.3461091220 -0.0967302993 -0.0491067097 694 1311867193.5765709877 0.0729002133 0.0621152208 0.0879938230 0.0057482778 0.7095620000 969738331 0 1783922688 0.3473703563 -0.0961081386 -0.0489583462 695 1311867193.6127800941 0.0732700229 0.0621312708 0.0879938230 0.0057442549 0.7237620000 969740213 0 1782317056 0.3482514024 -0.0971077308 -0.0492082983 696 1311867193.6461451054 0.0740156472 0.0621483461 0.0879938230 0.0057415178 0.7159990000 969741999 0 1784057856 0.3488800824 -0.0970031768 -0.0493515171 697 1311867193.6757860184 0.0742280260 0.0621656771 0.0879938230 0.0057380686 0.7204330000 969743753 0 1782468608 0.3506169915 -0.0959505439 -0.0490519367 698 1311867193.7122890949 0.0748957917 0.0621839150 0.0879938230 0.0057343612 0.7163960000 969745603 0 1784184832 0.3509355187 -0.0969184265 -0.0492734127 699 1311867193.7430191040 0.0757922903 0.0622033834 0.0879938230 0.0057321180 0.7298840000 969747357 0 1782595584 0.3513859510 -0.0962526947 -0.0493907705 700 1311867193.7760169506 0.0765026361 0.0622238109 0.0879938230 0.0057293813 0.7208280000 969749143 0 1784205312 0.3521889150 -0.0953539461 -0.0496671610 701 1311867193.8139710426 0.0771804526 0.0622451471 0.0879938230 0.0057268387 0.7556420000 969751057 0 1782214656 0.3530339599 -0.0966304392 -0.0494766943 702 1311867193.8436760902 0.0774923563 0.0622668667 0.0879938230 0.0057246469 0.7164740000 969752779 0 1783930880 0.3540333509 -0.0964789614 -0.0495697260 703 1311867193.8771181107 0.0775535032 0.0622886116 0.0879938230 0.0057215965 0.7243840000 969754597 0 1782341632 0.3558516800 -0.0959574208 -0.0494635738 704 1311867193.9151229858 0.0788355023 0.0623121157 0.0879938230 0.0057184149 0.7208340000 969756447 0 1783943168 0.3557518721 -0.0967604518 -0.0497265123 705 1311867193.9425311089 0.0789105594 0.0623356596 0.0879938230 0.0057162981 0.7269710000 969758201 0 1781952512 0.3569136560 -0.0961432680 -0.0497240275 706 1311867193.9781770706 0.0797028393 0.0623602590 0.0879938230 0.0057132490 0.7255710000 969760051 0 1783668736 0.3577201068 -0.0958528891 -0.0497576557 707 1311867194.0148570538 0.0818522722 0.0623878290 0.0879938230 0.0057116474 0.7175830000 969761869 0 1781948416 0.3565260470 -0.0964071825 -0.0504834652 708 1311867194.0433440208 0.0829741135 0.0624169057 0.0879938230 0.0057094251 0.7492890000 969763623 0 1783709696 0.3567338586 -0.0960115418 -0.0504346862 709 1311867194.0746119022 0.0820284411 0.0624445665 0.0879938230 0.0057059287 0.7292580000 969765377 0 1781567488 0.3591734767 -0.0958691239 -0.0499321036 710 1311867194.1131060123 0.0830720291 0.0624736193 0.0879938230 0.0057021321 0.7216510000 969767291 0 1783320576 0.3587432206 -0.0963721275 -0.0504492708 711 1311867194.1428558826 0.0841026530 0.0625040399 0.0879938230 0.0057003686 0.7377430000 969769045 0 1781678080 0.3585480452 -0.0957240835 -0.0503556952 712 1311867194.1758549213 0.0836271569 0.0625337072 0.0879938230 0.0057022024 0.7364380000 969770831 0 1783324672 0.3599259853 -0.0949484259 -0.0498614982 713 1311867194.2138450146 0.0843547732 0.0625643118 0.0879938230 0.0056993403 0.7330640000 969772713 0 1781424128 0.3596064150 -0.0958064720 -0.0501781590 714 1311867194.2451140881 0.0843514279 0.0625948259 0.0879938230 0.0056971762 0.7202700000 969774435 0 1783160832 0.3605155647 -0.0949544311 -0.0498569310 715 1311867194.2760241032 0.0837784335 0.0626244533 0.0879938230 0.0056936481 0.7662330000 969776189 0 1781571584 0.3618211448 -0.0950569734 -0.0493059643 716 1311867194.3139200211 0.0849993303 0.0626557032 0.0879938230 0.0056909587 0.7342040000 969778071 0 1783287808 0.3610484600 -0.0956534892 -0.0496134609 717 1311867194.3447821140 0.0847714096 0.0626865480 0.0879938230 0.0056912938 0.7314150000 969779857 0 1781567488 0.3619318008 -0.0947122425 -0.0491480827 718 1311867194.3802230358 0.0832403675 0.0627151744 0.0879938230 0.0056885141 0.7319830000 969781675 0 1783328768 0.3642794788 -0.0949020311 -0.0484853685 719 1311867194.4124519825 0.0835782513 0.0627441912 0.0879938230 0.0056868548 0.7431140000 969783429 0 1781186560 0.3641083539 -0.0961415619 -0.0482568331 720 1311867194.4447510242 0.0839892477 0.0627736983 0.0879938230 0.0056831926 0.7295870000 969785247 0 1782939648 0.3643970788 -0.0962305069 -0.0480035879 721 1311867194.4805839062 0.0839343816 0.0628030473 0.0879938230 0.0056797275 0.7363670000 969787033 0 1781297152 0.3651268184 -0.0959321558 -0.0478773229 722 1311867194.5174930096 0.0846551657 0.0628333134 0.0879938230 0.0056770779 0.7588110000 969788947 0 1782943744 0.3646615744 -0.0966913104 -0.0479016379 723 1311867194.5439500809 0.0848088786 0.0628637084 0.0879938230 0.0056751895 0.7341220000 969790605 0 1780916224 0.3647927046 -0.0963296220 -0.0479436181 724 1311867194.5795979500 0.0841261074 0.0628930764 0.0879938230 0.0056713336 0.7268240000 969792423 0 1782652928 0.3660731912 -0.0963512734 -0.0474120937 725 1311867194.6129479408 0.0834767446 0.0629214676 0.0879938230 0.0056678437 0.7366750000 969794241 0 1784336384 0.3672362566 -0.0971570536 -0.0468105413 726 1311867194.6493880749 0.0822292641 0.0629480624 0.0879938230 0.0056761261 0.7350700000 969796123 0 1782693888 0.3689143062 -0.0969603807 -0.0459647179 727 1311867194.6784319878 0.0814757496 0.0629735475 0.0879938230 0.0056750679 0.7339290000 969797845 0 1784340480 0.3700369895 -0.0970665440 -0.0456723012 728 1311867194.7133309841 0.0822350532 0.0630000056 0.0879938230 0.0056729524 0.7393150000 969799663 0 1782312960 0.3695612848 -0.0968983173 -0.0456201918 729 1311867194.7475099564 0.0824447870 0.0630266788 0.0879938230 0.0056694350 0.7720600000 969801481 0 1784049664 0.3700195253 -0.0964999199 -0.0451909378 730 1311867194.7784450054 0.0827682912 0.0630537222 0.0879938230 0.0056657494 0.7316330000 969803267 0 1782439936 0.3700872660 -0.0966043696 -0.0448601358 731 1311867194.8130390644 0.0827194601 0.0630806247 0.0879938230 0.0056618765 0.7382300000 969805085 0 1784070144 0.3703576028 -0.0965475291 -0.0445846915 732 1311867194.8476719856 0.0836562738 0.0631087335 0.0879938230 0.0056582624 0.7469610000 969806903 0 1782079488 0.3693118691 -0.0961353332 -0.0448220298 733 1311867194.8814148903 0.0839471072 0.0631371624 0.0879938230 0.0056548577 0.7366950000 969808721 0 1783795712 0.3687480092 -0.0956941471 -0.0447215773 734 1311867194.9104089737 0.0836095363 0.0631650539 0.0879938230 0.0056616419 0.7419810000 969810443 0 1782206464 0.3689176142 -0.0952317864 -0.0445808247 735 1311867194.9451448917 0.0834687129 0.0631926779 0.0879938230 0.0056586094 0.7277350000 969812293 0 1783816192 0.3683601618 -0.0955715179 -0.0442241654 736 1311867194.9787399769 0.0811838508 0.0632171224 0.0879938230 0.0056569838 0.7820200000 969814111 0 1781805056 0.3704602420 -0.0963830873 -0.0435031876 737 1311867195.0132799149 0.0803118348 0.0632403174 0.0879938230 0.0056551150 0.7338670000 969815929 0 1783541760 0.3704149723 -0.0960328206 -0.0431468710 738 1311867195.0464940071 0.0792711973 0.0632620395 0.0879938230 0.0056524192 0.7440050000 969817715 0 1781948416 0.3709812462 -0.0974400342 -0.0427024215 739 1311867195.0781710148 0.0788260475 0.0632831004 0.0879938230 0.0056491804 0.7368060000 969819501 0 1783689216 0.3710097671 -0.0965630114 -0.0425560735 740 1311867195.1115310192 0.0788678378 0.0633041609 0.0879938230 0.0056456749 0.7442220000 969821287 0 1781678080 0.3702987432 -0.0963129550 -0.0423981100 741 1311867195.1458311081 0.0790094584 0.0633253556 0.0879938230 0.0056419540 0.7364740000 969823137 0 1783414784 0.3690609932 -0.0968309343 -0.0425873734 742 1311867195.1780319214 0.0783899426 0.0633456583 0.0879938230 0.0056397620 0.7409840000 969824923 0 1781829632 0.3690620661 -0.0959124267 -0.0424030274 743 1311867195.2114748955 0.0769427270 0.0633639585 0.0879938230 0.0056364366 0.7345650000 969826709 0 1783549952 0.3691789806 -0.0960131437 -0.0422100089 744 1311867195.2436800003 0.0764604956 0.0633815614 0.0879938230 0.0056346852 0.7509340000 969828527 0 1781940224 0.3689676523 -0.0968886241 -0.0421821997 745 1311867195.2780399323 0.0758498609 0.0633982973 0.0879938230 0.0056315315 0.7435650000 969830345 0 1783570432 0.3685865998 -0.0969573781 -0.0420094468 746 1311867195.3123180866 0.0754094049 0.0634143980 0.0879938230 0.0056281101 0.7463500000 969832163 0 1781555200 0.3682020903 -0.0969075188 -0.0419758670 747 1311867195.3425979614 0.0760488287 0.0634313116 0.0879938230 0.0056286940 0.7329750000 969833917 0 1783316480 0.3658108413 -0.0983191207 -0.0426342338 748 1311867195.3782711029 0.0756855235 0.0634476942 0.0879938230 0.0056264074 0.7512590000 969835767 0 1781305344 0.3651320338 -0.0977213830 -0.0427635908 749 1311867195.4119830132 0.0751588345 0.0634633299 0.0879938230 0.0056255161 0.7317190000 969837553 0 1783042048 0.3642443120 -0.0974942967 -0.0431934223 750 1311867195.4435520172 0.0755058601 0.0634793866 0.0879938230 0.0056232146 0.7407440000 969839371 0 1781321728 0.3617020547 -0.0979965478 -0.0440378934 751 1311867195.4788239002 0.0742758736 0.0634937628 0.0879938230 0.0056203804 0.7400170000 969841189 0 1782931456 0.3618754148 -0.0972033069 -0.0440010428 752 1311867195.5113179684 0.0738385692 0.0635075192 0.0879938230 0.0056168981 0.7453600000 969842975 0 1784557568 0.3610325158 -0.0972214341 -0.0440550148 753 1311867195.5439620018 0.0733762607 0.0635206251 0.0879938230 0.0056133913 0.7467650000 969844793 0 1782714368 0.3591668308 -0.0981474444 -0.0442449301 754 1311867195.5782160759 0.0721522123 0.0635320728 0.0879938230 0.0056109926 0.7403570000 969846611 0 1784430592 0.3593621850 -0.0978055522 -0.0439105816 755 1311867195.6119859219 0.0723055154 0.0635436932 0.0879938230 0.0056089390 0.7461230000 969848429 0 1782820864 0.3572815955 -0.0978242904 -0.0442158394 756 1311867195.6430909634 0.0725434795 0.0635555977 0.0879938230 0.0056054898 0.7401110000 969850183 0 1784451072 0.3546821177 -0.0982218236 -0.0448035188 757 1311867195.6779129505 0.0724398419 0.0635673338 0.0879938230 0.0056021566 0.7954240000 969852033 0 1782439936 0.3530024886 -0.0979860425 -0.0448264331 758 1311867195.7107300758 0.0724968091 0.0635791142 0.0879938230 0.0056022193 0.7450330000 969853787 0 1784176640 0.3506561518 -0.0980331302 -0.0448624268 759 1311867195.7458300591 0.0713133141 0.0635893041 0.0879938230 0.0056004082 0.7534410000 969855637 0 1782566912 0.3499199450 -0.0988518149 -0.0448189527 760 1311867195.7821879387 0.0709230304 0.0635989538 0.0879938230 0.0055968797 0.7340700000 969857455 0 1784197120 0.3487367630 -0.0985429734 -0.0445629694 761 1311867195.8100500107 0.0717067346 0.0636096079 0.0879938230 0.0055937838 0.7409380000 969859177 0 1782312960 0.3459145725 -0.0988677442 -0.0447726026 762 1311867195.8458549976 0.0705220923 0.0636186794 0.0879938230 0.0055905307 0.7450190000 969861027 0 1783943168 0.3452062011 -0.0990979522 -0.0448326319 763 1311867195.8778660297 0.0699656829 0.0636269979 0.0879938230 0.0055893191 0.7528540000 969862845 0 1781948416 0.3441146314 -0.0980072990 -0.0447989069 764 1311867195.9098269939 0.0700067058 0.0636353483 0.0879938230 0.0055866780 0.7336080000 969864631 0 1783701504 0.3424334228 -0.0979094058 -0.0447931364 765 1311867195.9458460808 0.0698385835 0.0636434571 0.0879938230 0.0055835940 0.7491320000 969866449 0 1782075392 0.3405055702 -0.0982827023 -0.0449047498 766 1311867195.9778430462 0.0700172484 0.0636517780 0.0879938230 0.0055815283 0.7345640000 969868267 0 1783685120 0.3389813006 -0.0973019227 -0.0447791815 767 1311867196.0100569725 0.0694359243 0.0636593192 0.0879938230 0.0055786713 0.7539940000 969870053 0 1781825536 0.3382934928 -0.0974617228 -0.0445468985 768 1311867196.0498790741 0.0685187876 0.0636656467 0.0879938230 0.0055762585 0.7456690000 969871967 0 1783541760 0.3375883400 -0.0979254767 -0.0447697192 769 1311867196.0793108940 0.0688706934 0.0636724152 0.0879938230 0.0055772120 0.7492550000 969873753 0 1781952512 0.3359510601 -0.0967751145 -0.0446458310 770 1311867196.1113979816 0.0687811747 0.0636790500 0.0879938230 0.0055743301 0.7446410000 969875475 0 1783562240 0.3341937661 -0.0971881673 -0.0447862260 771 1311867196.1473290920 0.0680108517 0.0636846684 0.0879938230 0.0055709933 0.7914470000 969877357 0 1781571584 0.3332873583 -0.0976681933 -0.0447651893 772 1311867196.1811769009 0.0677798763 0.0636899731 0.0879938230 0.0055712407 0.7454440000 969879175 0 1783287808 0.3319714069 -0.0969638228 -0.0446892679 773 1311867196.2114949226 0.0684687048 0.0636961552 0.0879938230 0.0055690314 0.7425670000 969880897 0 1781567488 0.3294453919 -0.0976219550 -0.0449536033 774 1311867196.2462599277 0.0684073493 0.0637022420 0.0879938230 0.0055660676 0.7354460000 969882747 0 1783308288 0.3277376592 -0.0975994766 -0.0450951271 775 1311867196.2800569534 0.0682615787 0.0637081250 0.0879938230 0.0055626048 0.7377740000 969884565 0 1781297152 0.3262494206 -0.0973374099 -0.0450081676 776 1311867196.3111600876 0.0675647780 0.0637130949 0.0879938230 0.0055592436 0.7419570000 969886319 0 1783033856 0.3251605630 -0.0978245884 -0.0450972877 777 1311867196.3484730721 0.0677062273 0.0637182341 0.0879938230 0.0055562822 0.7397750000 969888201 0 1781444608 0.3233028352 -0.0975077748 -0.0452816784 778 1311867196.3842670918 0.0674013868 0.0637229682 0.0879938230 0.0055532262 0.7877300000 969890019 0 1783160832 0.3219926655 -0.0968339741 -0.0449670702 779 1311867196.4107549191 0.0674363151 0.0637277350 0.0879938230 0.0055512268 0.7363540000 969891709 0 1781571584 0.3202750087 -0.0975066647 -0.0449690260 780 1311867196.4463150501 0.0672015399 0.0637321886 0.0879938230 0.0055504385 0.7374120000 969893559 0 1783193600 0.3190053105 -0.0970053300 -0.0449216291 781 1311867196.4798319340 0.0665944070 0.0637358534 0.0879938230 0.0055469484 0.7366580000 969895377 0 1781551104 0.3184280992 -0.0964991152 -0.0444734544 782 1311867196.5113470554 0.0668534487 0.0637398401 0.0879938230 0.0055437768 0.7383780000 969897131 0 1783287808 0.3158578575 -0.0968868136 -0.0447366089 783 1311867196.5468420982 0.0661964342 0.0637429775 0.0879938230 0.0055413999 0.7497000000 969898981 0 1781682176 0.3142746687 -0.0960663855 -0.0445100218 784 1311867196.5795550346 0.0658432692 0.0637456565 0.0879938230 0.0055399080 0.7552460000 969900799 0 1783287808 0.3138043582 -0.0956497788 -0.0439963639 785 1311867196.6108930111 0.0651496351 0.0637474450 0.0879938230 0.0055395875 0.7473190000 969902553 0 1781698560 0.3125582933 -0.0965161771 -0.0437229536 786 1311867196.6521809101 0.0649453774 0.0637489691 0.0879938230 0.0055433307 0.7447050000 969904499 0 1783414784 0.3101540506 -0.0954604074 -0.0438407958 787 1311867196.6805100441 0.0642889738 0.0637496552 0.0879938230 0.0055516610 0.7499610000 969906221 0 1781809152 0.3089005947 -0.0944839120 -0.0433414988 788 1311867196.7112100124 0.0637813732 0.0637496955 0.0879938230 0.0055486000 0.7488120000 969907975 0 1783549952 0.3080937564 -0.0950607136 -0.0427394547 789 1311867196.7464900017 0.0639713928 0.0637499765 0.0879938230 0.0055451205 0.7467990000 969909825 0 1781944320 0.3057115972 -0.0944708437 -0.0424347185 790 1311867196.7783749104 0.0634010732 0.0637495348 0.0879938230 0.0055417957 0.7486160000 969911643 0 1783549952 0.3042875230 -0.0944185704 -0.0420282409 791 1311867196.8109180927 0.0631696060 0.0637488016 0.0879938230 0.0055399497 0.7561460000 969913365 0 1781960704 0.3022151887 -0.0945587903 -0.0419346504 792 1311867196.8488750458 0.0629925877 0.0637478468 0.0879938230 0.0055378542 0.7707760000 969915279 0 1783549952 0.2999384999 -0.0944904983 -0.0418385975 793 1311867196.8821749687 0.0624987818 0.0637462717 0.0879938230 0.0055347452 0.7436950000 969917065 0 1781678080 0.2985834479 -0.0941088572 -0.0414861366 794 1311867196.9115700722 0.0626739487 0.0637449212 0.0879938230 0.0055322167 0.7349340000 969918787 0 1783287808 0.2961399555 -0.0948789269 -0.0415048078 795 1311867196.9482440948 0.0622247458 0.0637430090 0.0879938230 0.0055288036 0.7466110000 969920669 0 1781444608 0.2941840291 -0.0948606506 -0.0414443612 796 1311867196.9809880257 0.0618058220 0.0637405754 0.0879938230 0.0055264669 0.7390240000 969922487 0 1783033856 0.2926931679 -0.0952019095 -0.0411909036 797 1311867197.0154891014 0.0615467466 0.0637378228 0.0879938230 0.0055237221 0.7510140000 969924273 0 1781190656 0.2909754515 -0.0955931842 -0.0413773507 798 1311867197.0490679741 0.0611912608 0.0637346316 0.0879938230 0.0055214066 0.7325840000 969926091 0 1782685696 0.2891786397 -0.0955805182 -0.0415351167 799 1311867197.0806479454 0.0607387573 0.0637308820 0.0879938230 0.0055186060 0.7796340000 969927813 0 1784430592 0.2877979875 -0.0959655568 -0.0416018963 800 1311867197.1148109436 0.0606341921 0.0637270112 0.0879938230 0.0055154300 0.7430080000 969929663 0 1782571008 0.2852329910 -0.0962866023 -0.0421239659 801 1311867197.1468429565 0.0606494173 0.0637231690 0.0879938230 0.0055129391 0.7414780000 969931449 0 1784049664 0.2832314074 -0.0956598222 -0.0422340333 802 1311867197.1792430878 0.0606809333 0.0637193757 0.0879938230 0.0055103757 0.7403890000 969933267 0 1782190080 0.2806787193 -0.0958595648 -0.0425491445 803 1311867197.2143619061 0.0605719686 0.0637154561 0.0879938230 0.0055094424 0.7385080000 969935085 0 1783668736 0.2784529030 -0.0955607444 -0.0426213443 804 1311867197.2459290028 0.0604649819 0.0637114132 0.0879938230 0.0055062028 0.7404340000 969936871 0 1781809152 0.2768870294 -0.0951599628 -0.0424702503 805 1311867197.2799959183 0.0596420094 0.0637063581 0.0879938230 0.0055045283 0.7420940000 969938721 0 1783414784 0.2757970989 -0.0955136493 -0.0422399752 806 1311867197.3157260418 0.0594445243 0.0637010704 0.0879938230 0.0055015994 0.7414370000 969940507 0 1781555200 0.2736090124 -0.0951642245 -0.0423771814 807 1311867197.3468708992 0.0588945895 0.0636951145 0.0879938230 0.0054992561 0.7313450000 969942293 0 1783160832 0.2723469734 -0.0951824933 -0.0422026664 808 1311867197.3784019947 0.0589707308 0.0636892674 0.0879938230 0.0054975928 0.7365090000 969944047 0 1781301248 0.2699037492 -0.0952253342 -0.0426645279 809 1311867197.4155099392 0.0590206012 0.0636834965 0.0879938230 0.0054946545 0.7390530000 969945897 0 1782812672 0.2675264776 -0.0951794907 -0.0430655815 810 1311867197.4478878975 0.0587150604 0.0636773627 0.0879938230 0.0054914428 0.7464350000 969947683 0 1784557568 0.2665410936 -0.0950897187 -0.0432314090 811 1311867197.4793179035 0.0584428869 0.0636709083 0.0879938230 0.0054887575 0.7393050000 969949405 0 1782697984 0.2644507289 -0.0955233723 -0.0440703556 812 1311867197.5150759220 0.0586268865 0.0636646965 0.0879938230 0.0054870629 0.7291190000 969951255 0 1784209408 0.2620416284 -0.0949027687 -0.0449290685 813 1311867197.5469260216 0.0584262274 0.0636582531 0.0879938230 0.0054838027 0.7799470000 969953009 0 1782333440 0.2608685195 -0.0944297984 -0.0452738516 814 1311867197.5802750587 0.0584177449 0.0636518151 0.0879938230 0.0054823800 0.7352910000 969954827 0 1783922688 0.2587801218 -0.0952851102 -0.0461321510 815 1311867197.6152749062 0.0599178486 0.0636472336 0.0879938230 0.0054837801 0.7434930000 969956645 0 1781932032 0.2543718815 -0.0941614509 -0.0475165844 816 1311867197.6470439434 0.0594086647 0.0636420392 0.0879938230 0.0054820299 0.7398650000 969958431 0 1783541760 0.2535350025 -0.0933563113 -0.0478288233 817 1311867197.6800849438 0.0596995912 0.0636372137 0.0879938230 0.0054811313 0.7447710000 969960249 0 1781809152 0.2505220771 -0.0940248370 -0.0488734469 818 1311867197.7143290043 0.0596577264 0.0636323488 0.0879938230 0.0054812876 0.7403230000 969962067 0 1783287808 0.2490344644 -0.0925424546 -0.0494730435 819 1311867197.7463419437 0.0596260242 0.0636274571 0.0879938230 0.0054796195 0.7389790000 969963853 0 1781297152 0.2471817583 -0.0921920687 -0.0501600653 820 1311867197.7793009281 0.0600688644 0.0636231173 0.0879938230 0.0054771608 0.7673170000 969965671 0 1782906880 0.2439645529 -0.0925182551 -0.0514022484 821 1311867197.8146750927 0.0597593449 0.0636184112 0.0879938230 0.0054782538 0.7420010000 969967521 0 1784590336 0.2432380021 -0.0911308751 -0.0519824252 822 1311867197.8467919827 0.0593129620 0.0636131734 0.0879938230 0.0054764155 0.7437230000 969969275 0 1782824960 0.2422176301 -0.0915887132 -0.0528313890 823 1311867197.8802978992 0.0594691709 0.0636081382 0.0879938230 0.0054741643 0.7524420000 969971061 0 1784336384 0.2394450754 -0.0914639458 -0.0539902188 824 1311867197.9148609638 0.0590967499 0.0636026632 0.0879938230 0.0054754224 0.7437480000 969972911 0 1782444032 0.2389061451 -0.0904035121 -0.0544050485 825 1311867197.9470140934 0.0586283617 0.0635966337 0.0879938230 0.0054792461 0.7445040000 969974697 0 1783947264 0.2371551991 -0.0907807350 -0.0551049858 826 1311867197.9812700748 0.0589771084 0.0635910411 0.0879938230 0.0054762683 0.7518860000 969976515 0 1782071296 0.2346043885 -0.0902321115 -0.0559872985 827 1311867198.0145471096 0.0583594628 0.0635847151 0.0879938230 0.0054739419 0.7368310000 969978365 0 1783660544 0.2341041118 -0.0893049240 -0.0562465079 828 1311867198.0463368893 0.0580177233 0.0635779917 0.0879938230 0.0054711595 0.7417760000 969980119 0 1781796864 0.2324913442 -0.0892616361 -0.0569775291 829 1311867198.0787069798 0.0580203943 0.0635712877 0.0879938230 0.0054699916 0.7391810000 969981937 0 1783533568 0.2309984267 -0.0888522118 -0.0574661531 830 1311867198.1143770218 0.0570407286 0.0635634196 0.0879938230 0.0054670110 0.7522000000 969983755 0 1781682176 0.2305444181 -0.0882385001 -0.0578242913 831 1311867198.1463611126 0.0572219044 0.0635557884 0.0879938230 0.0054637844 0.7404810000 969985541 0 1783193600 0.2279458642 -0.0879652128 -0.0587750003 832 1311867198.1822519302 0.0565978400 0.0635474255 0.0879938230 0.0054606749 0.7434220000 969987391 0 1781301248 0.2267095298 -0.0873628333 -0.0594856925 833 1311867198.2144989967 0.0569389910 0.0635394922 0.0879938230 0.0054635922 0.7344870000 969989177 0 1782906880 0.2244923860 -0.0868237019 -0.0601441860 834 1311867198.2464120388 0.0562923960 0.0635308026 0.0879938230 0.0054612789 0.7649020000 969990963 0 1781055488 0.2233839780 -0.0869211778 -0.0610755160 835 1311867198.2821578979 0.0558027029 0.0635215474 0.0879938230 0.0054585277 0.7433080000 969992813 0 1782534144 0.2220656872 -0.0862743929 -0.0615999401 836 1311867198.3159120083 0.0552024506 0.0635115963 0.0879938230 0.0054577027 0.7339170000 969994599 0 1784184832 0.2206441760 -0.0857951939 -0.0626004413 837 1311867198.3481218815 0.0546901487 0.0635010569 0.0879938230 0.0054548877 0.7500510000 969996385 0 1782325248 0.2192149460 -0.0859488845 -0.0634582639 838 1311867198.3828320503 0.0544993058 0.0634903150 0.0879938230 0.0054574428 0.7407140000 969998235 0 1783836672 0.2165880054 -0.0849371403 -0.0644592494 839 1311867198.4242680073 0.0536380820 0.0634785722 0.0879938230 0.0054632204 0.7327350000 970000053 0 1781944320 0.2149636149 -0.0843916237 -0.0654829741 840 1311867198.4497859478 0.0539267920 0.0634672010 0.0879938230 0.0054608673 0.7265750000 970001679 0 1783549952 0.2121755481 -0.0853027478 -0.0667510927 841 1311867198.4856219292 0.0544168949 0.0634564396 0.0879938230 0.0054664035 0.7765370000 970003465 0 1781698560 0.2089145929 -0.0842081681 -0.0679715052 842 1311867198.5190339088 0.0542414486 0.0634454955 0.0879938230 0.0054637881 0.7285620000 970005283 0 1783287808 0.2065470666 -0.0832976475 -0.0690142140 843 1311867198.5499279499 0.0535922162 0.0634338071 0.0879938230 0.0054638670 0.7407870000 970007069 0 1781571584 0.2043840289 -0.0836679116 -0.0702712685 844 1311867198.5824239254 0.0531535484 0.0634216267 0.0879938230 0.0054611702 0.7228800000 970008855 0 1783066624 0.2028255165 -0.0822836757 -0.0710373595 845 1311867198.6147489548 0.0526562668 0.0634088867 0.0879938230 0.0054612293 0.7307290000 970010641 0 1781170176 0.2008432299 -0.0820143074 -0.0719707832 846 1311867198.6482009888 0.0522098579 0.0633956490 0.0879938230 0.0054608789 0.7209030000 970012427 0 1782779904 0.1986955106 -0.0818149000 -0.0729045793 847 1311867198.6827540398 0.0524732023 0.0633827536 0.0879938230 0.0054591165 0.7290990000 970014245 0 1784430592 0.1953204125 -0.0806849003 -0.0741045699 848 1311867198.7146520615 0.0527686216 0.0633702369 0.0879938230 0.0054559656 0.7256470000 970015999 0 1782697984 0.1932532638 -0.0798592418 -0.0746277049 849 1311867198.7467699051 0.0529961661 0.0633580177 0.0879938230 0.0054541170 0.7269060000 970017753 0 1784303616 0.1910972744 -0.0796083063 -0.0754431784 850 1311867198.7842700481 0.0526071414 0.0633453697 0.0879938230 0.0054514130 0.7338800000 970019603 0 1782714368 0.1897532642 -0.0788136572 -0.0759430826 851 1311867198.8149418831 0.0532271452 0.0633334799 0.0879938230 0.0054483726 0.7348240000 970021357 0 1784193024 0.1858236045 -0.0783329383 -0.0772690997 852 1311867198.8464009762 0.0533470586 0.0633217587 0.0879938230 0.0054462520 0.7283870000 970023143 0 1782202368 0.1835892797 -0.0775163621 -0.0780874044 853 1311867198.8845369816 0.0533156656 0.0633100282 0.0879938230 0.0054441130 0.7298850000 970024961 0 1783955456 0.1826011389 -0.0768329650 -0.0786421001 854 1311867198.9147930145 0.0538585596 0.0632989609 0.0879938230 0.0054409466 0.7356160000 970026715 0 1782312960 0.1798684895 -0.0762190595 -0.0796728730 855 1311867198.9465179443 0.0539113581 0.0632879813 0.0879938230 0.0054378429 0.7677760000 970028501 0 1783959552 0.1781630814 -0.0751090422 -0.0805707499 856 1311867198.9839329720 0.0539702773 0.0632770961 0.0879938230 0.0054351160 0.7394050000 970030415 0 1781932032 0.1759880632 -0.0741910413 -0.0815499425 857 1311867199.0148730278 0.0544779561 0.0632668287 0.0879938230 0.0054367875 0.7411130000 970032169 0 1783668736 0.1733056456 -0.0730588064 -0.0826374963 858 1311867199.0468010902 0.0554846525 0.0632577586 0.0879938230 0.0054367275 0.7393060000 970033955 0 1782059008 0.1715124696 -0.0722446665 -0.0835964382 859 1311867199.0849320889 0.0556938387 0.0632489531 0.0879938230 0.0054365800 0.7420280000 970035869 0 1783689216 0.1704301834 -0.0710593387 -0.0843540579 860 1311867199.1149818897 0.0560981743 0.0632406382 0.0879938230 0.0054345325 0.7449400000 970037591 0 1781694464 0.1684295386 -0.0704925731 -0.0856548473 861 1311867199.1465420723 0.0570716932 0.0632334734 0.0879938230 0.0054321582 0.7437230000 970039377 0 1783304192 0.1658436805 -0.0692935511 -0.0870563611 862 1311867199.1823658943 0.0577457957 0.0632271072 0.0879938230 0.0054308271 0.7789980000 970041227 0 1781420032 0.1638181806 -0.0678865835 -0.0882565826 863 1311867199.2146680355 0.0585919879 0.0632217362 0.0879938230 0.0054279915 0.7486450000 970043045 0 1783197696 0.1611846983 -0.0673272908 -0.0897172019 864 1311867199.2467749119 0.0588894524 0.0632167220 0.0879938230 0.0054251089 0.7376120000 970044799 0 1781567488 0.1595887691 -0.0664005876 -0.0907525718 865 1311867199.2833590508 0.0592009127 0.0632120795 0.0879938230 0.0054219994 0.7419610000 970046681 0 1783193600 0.1578012109 -0.0654878393 -0.0918214843 866 1311867199.3159129620 0.0595406108 0.0632078399 0.0879938230 0.0054222653 0.7471060000 970048403 0 1781673984 0.1559915096 -0.0653056279 -0.0931818038 867 1311867199.3465209007 0.0595196597 0.0632035859 0.0879938230 0.0054191825 0.7434100000 970050157 0 1783341056 0.1547496617 -0.0648189783 -0.0944226086 868 1311867199.3829050064 0.0593847893 0.0631991864 0.0879938230 0.0054165137 0.7430470000 970052039 0 1781690368 0.1532002538 -0.0641096905 -0.0956145376 869 1311867199.4147589207 0.0593929887 0.0631948064 0.0879938230 0.0054134385 0.7470800000 970053793 0 1783451648 0.1511746198 -0.0642104000 -0.0968907848 870 1311867199.4512910843 0.0591277592 0.0631901317 0.0879938230 0.0054106760 0.7466970000 970055675 0 1781800960 0.1492376626 -0.0634367168 -0.0982684717 871 1311867199.4837360382 0.0588014349 0.0631850930 0.0879938230 0.0054090674 0.7391140000 970057461 0 1783447552 0.1477865577 -0.0635495186 -0.0991302207 872 1311867199.5150198936 0.0587706529 0.0631800305 0.0879938230 0.0054060940 0.7450980000 970059247 0 1781796864 0.1458272487 -0.0635005161 -0.1000610217 873 1311867199.5544059277 0.0583175831 0.0631744607 0.0879938230 0.0054047267 0.7426750000 970061161 0 1783595008 0.1441121697 -0.0628170893 -0.1009262502 874 1311867199.5835030079 0.0581791550 0.0631687453 0.0879938230 0.0054017619 0.7455050000 970062915 0 1781952512 0.1416811794 -0.0622604489 -0.1018248051 875 1311867199.6158308983 0.0577220395 0.0631625205 0.0879938230 0.0053990021 0.7300050000 970064637 0 1783713792 0.1396310627 -0.0617569685 -0.1024097130 876 1311867199.6538460255 0.0567095838 0.0631551541 0.0879938230 0.0053981423 0.7979180000 970066551 0 1782079488 0.1385171562 -0.0618309192 -0.1027947143 877 1311867199.6824479103 0.0567681678 0.0631478713 0.0879938230 0.0053953485 0.7382120000 970068273 0 1783836672 0.1361232549 -0.0613953508 -0.1034609377 878 1311867199.7146759033 0.0558397099 0.0631395477 0.0879938230 0.0053930527 0.7363960000 970070091 0 1782337536 0.1348758936 -0.0609664470 -0.1040330529 879 1311867199.7511539459 0.0556671843 0.0631310467 0.0879938230 0.0053916235 0.7291060000 970071909 0 1783967744 0.1325792074 -0.0605409816 -0.1043510437 880 1311867199.7826020718 0.0554659702 0.0631223364 0.0879938230 0.0053893651 0.7332430000 970073695 0 1782317056 0.1303417087 -0.0605737120 -0.1049729735 881 1311867199.8150150776 0.0549525321 0.0631130631 0.0879938230 0.0053936117 0.7292860000 970075481 0 1784094720 0.1282841563 -0.0604773089 -0.1055105776 882 1311867199.8519051075 0.0544808470 0.0631032760 0.0879938230 0.0053906560 0.7317680000 970077331 0 1782444032 0.1267359853 -0.0597253032 -0.1059177592 883 1311867199.8839609623 0.0542276427 0.0630932243 0.0879938230 0.0053908261 0.7724360000 970079149 0 1784102912 0.1245303303 -0.0602316894 -0.1063442901 884 1311867199.9148159027 0.0539641082 0.0630828972 0.0879938230 0.0053889902 0.7390340000 970080935 0 1782435840 0.1222876832 -0.0603700578 -0.1068788245 885 1311867199.9520709515 0.0536821112 0.0630722749 0.0879938230 0.0053864052 0.7296790000 970082785 0 1784086528 0.1208474264 -0.0598335639 -0.1071536765 886 1311867199.9828410149 0.0529879294 0.0630608930 0.0879938230 0.0053844127 0.7388810000 970084539 0 1782325248 0.1197542548 -0.0602833256 -0.1074320525 887 1311867200.0144031048 0.0527582243 0.0630492778 0.0879938230 0.0053817134 0.7359790000 970086325 0 1784066048 0.1174516529 -0.0598200262 -0.1078763232 888 1311867200.0539638996 0.0523565747 0.0630372365 0.0879938230 0.0053799389 0.7372780000 970088239 0 1782308864 0.1158140600 -0.0586982109 -0.1079950109 889 1311867200.0830330849 0.0518734232 0.0630246788 0.0879938230 0.0053772311 0.7390630000 970089961 0 1784086528 0.1145816743 -0.0592940524 -0.1081158966 890 1311867200.1174468994 0.0514651872 0.0630116906 0.0879938230 0.0053770195 0.7362650000 970091779 0 1782456320 0.1123414040 -0.0589140616 -0.1082024574 891 1311867200.1517000198 0.0510639288 0.0629982812 0.0879938230 0.0053758141 0.7335250000 970093597 0 1784082432 0.1106929779 -0.0584272817 -0.1080787554 892 1311867200.1853220463 0.0512440912 0.0629851038 0.0879938230 0.0053751856 0.7301190000 970095447 0 1782583296 0.1083571985 -0.0588483028 -0.1081207022 893 1311867200.2179059982 0.0505206734 0.0629711459 0.0879938230 0.0053739359 0.7339600000 970097233 0 1784213504 0.1080198362 -0.0579997860 -0.1078408808 894 1311867200.2522649765 0.0499927253 0.0629566287 0.0879938230 0.0053711662 0.7364310000 970099051 0 1782435840 0.1064974889 -0.0580906123 -0.1075420305 895 1311867200.2825429440 0.0497087352 0.0629418265 0.0879938230 0.0053689047 0.7316270000 970100805 0 1784209408 0.1043203697 -0.0579642653 -0.1073322147 896 1311867200.3148880005 0.0494078621 0.0629267217 0.0879938230 0.0053660259 0.7370620000 970102623 0 1782587392 0.1034417897 -0.0572923645 -0.1066886485 897 1311867200.3514990807 0.0490536094 0.0629112556 0.0879938230 0.0053651955 0.7594070000 970104441 0 1784193024 0.1013815328 -0.0579693392 -0.1064487100 898 1311867200.3837759495 0.0489953198 0.0628957590 0.0879938230 0.0053735299 0.7280960000 970106259 0 1782333440 0.0992392898 -0.0574924871 -0.1060266569 899 1311867200.4162800312 0.0488025844 0.0628800825 0.0879938230 0.0053711684 0.7314070000 970108013 0 1784049664 0.0981457680 -0.0574403368 -0.1055416837 900 1311867200.4522490501 0.0484239161 0.0628640201 0.0879938230 0.0053694341 0.7228410000 970109863 0 1782444032 0.0951403528 -0.0578592196 -0.1055906937 901 1311867200.4850699902 0.0481098965 0.0628476448 0.0879938230 0.0053702808 0.7297740000 970111649 0 1784090624 0.0925797746 -0.0577200241 -0.1053158417 902 1311867200.5143918991 0.0479148924 0.0628310896 0.0879938230 0.0053698618 0.7295720000 970113435 0 1781927936 0.0907941237 -0.0582133308 -0.1047484800 903 1311867200.5505030155 0.0474894606 0.0628141000 0.0879938230 0.0053746525 0.7350950000 970115285 0 1783701504 0.0872092471 -0.0580271259 -0.1044485569 904 1311867200.5832219124 0.0477698818 0.0627974582 0.0879938230 0.0053762290 0.7648790000 970117071 0 1782059008 0.0850653127 -0.0580007806 -0.1039094254 905 1311867200.6145610809 0.0475536175 0.0627806141 0.0879938230 0.0053750803 0.7308290000 970118825 0 1783705600 0.0824238434 -0.0582432151 -0.1035410613 906 1311867200.6504778862 0.0472150855 0.0627634336 0.0879938230 0.0053734785 0.7303880000 970120675 0 1781698560 0.0795171931 -0.0580630191 -0.1031227112 907 1311867200.6851279736 0.0469475910 0.0627459961 0.0879938230 0.0053708041 0.7318150000 970122525 0 1783414784 0.0768882558 -0.0578688681 -0.1028104946 908 1311867200.7189719677 0.0468009934 0.0627284355 0.0879938230 0.0053697749 0.7341050000 970124343 0 1781805056 0.0734962970 -0.0578594916 -0.1026351675 909 1311867200.7503669262 0.0465295278 0.0627106150 0.0879938230 0.0053686213 0.7290400000 970126097 0 1783435264 0.0711639971 -0.0576814264 -0.1022264212 910 1311867200.7832930088 0.0463830084 0.0626926725 0.0879938230 0.0053736018 0.7351620000 970127915 0 1781424128 0.0686814263 -0.0575192273 -0.1018781364 911 1311867200.8181068897 0.0458712392 0.0626742077 0.0879938230 0.0053726475 0.7625170000 970129733 0 1783160832 0.0657190084 -0.0578908846 -0.1015224382 912 1311867200.8501501083 0.0458806790 0.0626557938 0.0879938230 0.0053697701 0.7293280000 970131487 0 1781571584 0.0637758896 -0.0573647544 -0.1010047495 913 1311867200.8845369816 0.0462342016 0.0626378074 0.0879938230 0.0053703768 0.7325510000 970133369 0 1783287808 0.0604876541 -0.0573435128 -0.1004240438 914 1311867200.9194929600 0.0467586853 0.0626204341 0.0879938230 0.0053716457 0.7414390000 970135187 0 1781567488 0.0573858917 -0.0577050522 -0.0999366865 915 1311867200.9512679577 0.0463462472 0.0626026482 0.0879938230 0.0053715699 0.7290610000 970136941 0 1783287808 0.0552369468 -0.0579877757 -0.0995881706 916 1311867200.9856009483 0.0470197909 0.0625856363 0.0879938230 0.0053765390 0.7422340000 970138791 0 1781698560 0.0529357083 -0.0582495630 -0.0995653272 917 1311867201.0184400082 0.0472404659 0.0625689022 0.0879938230 0.0053739257 0.7235830000 970140577 0 1783308288 0.0510017239 -0.0585399903 -0.0995621905 918 1311867201.0555179119 0.0472505204 0.0625522155 0.0879938230 0.0053717329 0.7267640000 970142459 0 1781297152 0.0494456403 -0.0585042201 -0.0997282863 919 1311867201.0825428963 0.0475413613 0.0625358816 0.0879938230 0.0053707123 0.7280950000 970144149 0 1783033856 0.0475892052 -0.0588964038 -0.0998064727 920 1311867201.1193449497 0.0479090512 0.0625199829 0.0879938230 0.0053686563 0.7266690000 970146031 0 1781452800 0.0462222472 -0.0585936531 -0.0997033864 921 1311867201.1506710052 0.0482335389 0.0625044710 0.0879938230 0.0053659662 0.7225230000 970147753 0 1783169024 0.0446824022 -0.0583534688 -0.0997780338 922 1311867201.1830160618 0.0481464043 0.0624888983 0.0879938230 0.0053641010 0.7334840000 970149539 0 1781432320 0.0435498506 -0.0585838147 -0.0998931974 923 1311867201.2196528912 0.0480731837 0.0624732799 0.0879938230 0.0053644673 0.7241600000 970151357 0 1783169024 0.0421267487 -0.0584986880 -0.0999921039 924 1311867201.2503149509 0.0480869748 0.0624577103 0.0879938230 0.0053615742 0.7227760000 970153143 0 1781579776 0.0410731472 -0.0582362227 -0.0999080837 925 1311867201.2824099064 0.0479874238 0.0624420668 0.0879938230 0.0053593751 0.7691140000 970154929 0 1783296000 0.0394047126 -0.0581276417 -0.1000959873 926 1311867201.3180539608 0.0479053333 0.0624263684 0.0879938230 0.0053580660 0.7214300000 970156779 0 1781706752 0.0373695157 -0.0585817993 -0.1003419533 927 1311867201.3522200584 0.0477758758 0.0624105642 0.0879938230 0.0053567151 0.7163610000 970158597 0 1783328768 0.0355314799 -0.0576973595 -0.1007322595 928 1311867201.3842790127 0.0477219895 0.0623947360 0.0879938230 0.0053566273 0.7214320000 970160383 0 1781702656 0.0336444341 -0.0566962808 -0.1006971821 929 1311867201.4198760986 0.0467785895 0.0623779263 0.0879938230 0.0053761296 0.7266520000 970162169 0 1783422976 0.0309127942 -0.0572305471 -0.1012536287 930 1311867201.4558579922 0.0466193818 0.0623609817 0.0879938230 0.0053779113 0.7218530000 970163955 0 1781686272 0.0281028096 -0.0562590174 -0.1015033647 931 1311867201.4853110313 0.0467715189 0.0623442368 0.0879938230 0.0053766598 0.7167900000 970165709 0 1783414784 0.0251137335 -0.0548443906 -0.1015306190 932 1311867201.5198690891 0.0463064723 0.0623270289 0.0879938230 0.0053753996 0.7597450000 970167559 0 1781825536 0.0224687941 -0.0546835586 -0.1016925871 933 1311867201.5527739525 0.0458169058 0.0623093332 0.0879938230 0.0053760234 0.7201660000 970169313 0 1783447552 0.0204861704 -0.0545904823 -0.1018412709 934 1311867201.5840220451 0.0458113514 0.0622916694 0.0879938230 0.0053731898 0.7278160000 970171099 0 1781825536 0.0186111983 -0.0542001687 -0.1020268574 935 1311867201.6197049618 0.0458861329 0.0622741233 0.0879938230 0.0053710965 0.7196160000 970172949 0 1783447552 0.0163847581 -0.0539220981 -0.1023572758 936 1311867201.6515579224 0.0454311632 0.0622561287 0.0879938230 0.0053708755 0.7317080000 970174703 0 1781825536 0.0153352180 -0.0540426783 -0.1026316956 937 1311867201.6839449406 0.0453309491 0.0622380656 0.0879938230 0.0053681652 0.7185210000 970176521 0 1783447552 0.0129483528 -0.0534445457 -0.1030944586 938 1311867201.7189009190 0.0452551879 0.0622199602 0.0879938230 0.0053658694 0.7290630000 970178371 0 1781825536 0.0123825455 -0.0523903444 -0.1032723561 939 1311867201.7507290840 0.0450390279 0.0622016631 0.0879938230 0.0053636123 0.7488860000 970180157 0 1783414784 0.0100527015 -0.0523056090 -0.1036373526 940 1311867201.7858049870 0.0443021543 0.0621826211 0.0879938230 0.0053706850 0.7205470000 970181943 0 1781825536 0.0085692760 -0.0518379435 -0.1038738638 941 1311867201.8190178871 0.0446680598 0.0621640084 0.0879938230 0.0053756354 0.7265640000 970183793 0 1783414784 0.0073142149 -0.0503109843 -0.1038673148 942 1311867201.8505740166 0.0444478616 0.0621452014 0.0879938230 0.0053761321 0.7380060000 970185547 0 1781678080 0.0056387386 -0.0502847396 -0.1041686311 943 1311867201.8862850666 0.0443002880 0.0621262779 0.0879938230 0.0053734927 0.7326640000 970187365 0 1783414784 0.0050289081 -0.0501070917 -0.1044385806 944 1311867201.9195730686 0.0445759445 0.0621076864 0.0879938230 0.0053746500 0.7288290000 970189215 0 1781825536 0.0036158462 -0.0493335947 -0.1046654359 945 1311867201.9516520500 0.0443831794 0.0620889303 0.0879938230 0.0053726472 0.7320600000 970190937 0 1783541760 0.0026714657 -0.0494043045 -0.1052167341 946 1311867201.9894599915 0.0440952331 0.0620699095 0.0879938230 0.0053699929 0.7285470000 970192851 0 1781952512 0.0022748262 -0.0493847467 -0.1058364958 947 1311867202.0184879303 0.0440089889 0.0620508378 0.0879938230 0.0053672600 0.7287530000 970194573 0 1783701504 0.0010784097 -0.0489076190 -0.1064110771 948 1311867202.0507359505 0.0438748784 0.0620316648 0.0879938230 0.0053648316 0.7339740000 970196359 0 1782059008 0.0007525575 -0.0483543649 -0.1069710404 949 1311867202.0866351128 0.0439252593 0.0620125854 0.0879938230 0.0053623206 0.7347670000 970198209 0 1783795712 -0.0010777581 -0.0481147096 -0.1074401587 950 1311867202.1185920238 0.0434883088 0.0619930861 0.0879938230 0.0053607514 0.7307430000 970199995 0 1782206464 -0.0014844248 -0.0475918055 -0.1077426374 951 1311867202.1516621113 0.0436038673 0.0619737494 0.0879938230 0.0053587635 0.7355090000 970201813 0 1783922688 -0.0024315934 -0.0467954054 -0.1077627167 952 1311867202.1866259575 0.0434294678 0.0619542701 0.0879938230 0.0053559778 0.7368860000 970203631 0 1782317056 -0.0030138234 -0.0465628952 -0.1078331620 953 1311867202.2191269398 0.0431407057 0.0619345287 0.0879938230 0.0053532654 0.7723020000 970205417 0 1783955456 -0.0039604586 -0.0465719029 -0.1080475897 954 1311867202.2513220310 0.0429015942 0.0619145780 0.0879938230 0.0053509831 0.7335420000 970207171 0 1782312960 -0.0048310221 -0.0459062755 -0.1080027148 955 1311867202.2868280411 0.0429434218 0.0618947129 0.0879938230 0.0053503371 0.7324930000 970209021 0 1784049664 -0.0061516617 -0.0449190103 -0.1078736633 956 1311867202.3199880123 0.0428724065 0.0618748151 0.0879938230 0.0053499024 0.7412510000 970210807 0 1782460416 -0.0073062335 -0.0455805548 -0.1081060395 957 1311867202.3523900509 0.0426393561 0.0618547154 0.0879938230 0.0053474915 0.7414360000 970212593 0 1784176640 -0.0090067778 -0.0452228673 -0.1083337739 958 1311867202.3883628845 0.0423177555 0.0618343219 0.0879938230 0.0053447984 0.7435430000 970214443 0 1782571008 -0.0100566857 -0.0445205308 -0.1084094569 959 1311867202.4196391106 0.0425188765 0.0618141807 0.0879938230 0.0053438463 0.7409840000 970216229 0 1784209408 -0.0110816425 -0.0445246249 -0.1084407941 960 1311867202.4529430866 0.0427701212 0.0617943431 0.0879938230 0.0053415703 0.7728790000 970218015 0 1782566912 -0.0116581870 -0.0446939282 -0.1083843932 961 1311867202.4875710011 0.0432884730 0.0617750862 0.0879938230 0.0053418232 0.7313480000 970219833 0 1784303616 -0.0132032288 -0.0440964103 -0.1082115471 962 1311867202.5206449032 0.0432813056 0.0617558619 0.0879938230 0.0053579217 0.7377100000 970221619 0 1782714368 -0.0144181922 -0.0435127392 -0.1084435806 963 1311867202.5508940220 0.0435910225 0.0617369992 0.0879938230 0.0053552754 0.7337380000 970223373 0 1784430592 -0.0153436372 -0.0437184535 -0.1083129868 964 1311867202.5864949226 0.0440781489 0.0617186808 0.0879938230 0.0053671004 0.7359310000 970225255 0 1782693888 -0.0164002366 -0.0438702144 -0.1085737571 965 1311867202.6185030937 0.0441528186 0.0617004779 0.0879938230 0.0053709248 0.7375620000 970227041 0 1784557568 -0.0183085501 -0.0436369330 -0.1091798767 966 1311867202.6514449120 0.0439410992 0.0616820934 0.0879938230 0.0053751139 0.7314750000 970228827 0 1782968320 -0.0209662244 -0.0436089337 -0.1099383533 967 1311867202.6866559982 0.0437695235 0.0616635696 0.0879938230 0.0053728095 0.7277510000 970230677 0 1784565760 -0.0219430029 -0.0431704484 -0.1106539369 968 1311867202.7185359001 0.0438084044 0.0616451241 0.0879938230 0.0053704654 0.7261230000 970232463 0 1782976512 -0.0235032793 -0.0438697338 -0.1116418168 969 1311867202.7507350445 0.0437841788 0.0616266918 0.0879938230 0.0053684527 0.7265520000 970234249 0 1781321728 -0.0250838138 -0.0445159227 -0.1127474904 970 1311867202.7897169590 0.0438792184 0.0616083954 0.0879938230 0.0053660013 0.7174220000 970236163 0 1783074816 -0.0263232365 -0.0439786650 -0.1136588752 971 1311867202.8190000057 0.0435062982 0.0615897527 0.0879938230 0.0053643584 0.7258100000 970237917 0 1781432320 -0.0278560426 -0.0443117097 -0.1145308912 972 1311867202.8527579308 0.0427547246 0.0615703751 0.0879938230 0.0053616335 0.7106260000 970239703 0 1783062528 -0.0292038582 -0.0446800552 -0.1153141782 973 1311867202.8873219490 0.0421215966 0.0615503866 0.0879938230 0.0053606723 0.7228500000 970241521 0 1784590336 -0.0297201946 -0.0433106534 -0.1158721298 974 1311867202.9199879169 0.0421543010 0.0615304728 0.0879938230 0.0053587480 0.7493120000 970243307 0 1782693888 -0.0299328025 -0.0424935780 -0.1157730892 975 1311867202.9525690079 0.0423063971 0.0615107558 0.0879938230 0.0053605488 0.7168900000 970245125 0 1784446976 -0.0300368275 -0.0428308137 -0.1157151759 976 1311867202.9868710041 0.0423805751 0.0614911552 0.0879938230 0.0053629011 0.7147490000 970246943 0 1782820864 -0.0304588731 -0.0426354147 -0.1152451858 977 1311867203.0202019215 0.0423108377 0.0614715233 0.0879938230 0.0053601726 0.7189520000 970248729 0 1784451072 -0.0301244911 -0.0423219465 -0.1149569079 978 1311867203.0560851097 0.0424811393 0.0614521058 0.0879938230 0.0053617481 0.7235980000 970250579 0 1782460416 -0.0295489170 -0.0440406278 -0.1146019325 979 1311867203.0865778923 0.0431316122 0.0614333923 0.0879938230 0.0053603837 0.7219660000 970252333 0 1784176640 -0.0297900941 -0.0446666852 -0.1141668409 980 1311867203.1189930439 0.0434501395 0.0614150420 0.0879938230 0.0053632787 0.7329340000 970254119 0 1782571008 -0.0300579146 -0.0453971177 -0.1138382703 981 1311867203.1549820900 0.0436828919 0.0613969665 0.0879938230 0.0053697167 0.7701500000 970255969 0 1784303616 -0.0304373782 -0.0474135354 -0.1138361916 982 1311867203.1877939701 0.0443408303 0.0613795977 0.0879938230 0.0054022805 0.7356970000 970257755 0 1782566912 -0.0310717095 -0.0487751700 -0.1140343398 983 1311867203.2185909748 0.0445170030 0.0613624435 0.0879938230 0.0054010406 0.7273180000 970259541 0 1784213504 -0.0305678770 -0.0487230420 -0.1142641976 984 1311867203.2552030087 0.0447589830 0.0613455700 0.0879938230 0.0053993828 0.7350400000 970261391 0 1782206464 -0.0301472135 -0.0497649498 -0.1144720763 985 1311867203.2864799500 0.0448500291 0.0613288233 0.0879938230 0.0053991801 0.7243800000 970263145 0 1783939072 -0.0307971407 -0.0511821583 -0.1148757935 986 1311867203.3194670677 0.0446201190 0.0613118773 0.0879938230 0.0053966092 0.7328630000 970264995 0 1782333440 -0.0301415157 -0.0516870283 -0.1152604148 987 1311867203.3547461033 0.0441345163 0.0612944737 0.0879938230 0.0053945203 0.7302900000 970266781 0 1783943168 -0.0290349685 -0.0519211218 -0.1156376228 988 1311867203.3865599632 0.0437459387 0.0612767121 0.0879938230 0.0053970068 0.7643720000 970268567 0 1781932032 -0.0290006548 -0.0531024821 -0.1159995198 989 1311867203.4183609486 0.0433812328 0.0612586175 0.0879938230 0.0054024262 0.7394970000 970270385 0 1783668736 -0.0283924770 -0.0564433411 -0.1164177731 990 1311867203.4545118809 0.0431702659 0.0612403465 0.0879938230 0.0054017039 0.7320700000 970272235 0 1782079488 -0.0280529130 -0.0576652326 -0.1165857166 991 1311867203.4864439964 0.0431526527 0.0612220945 0.0879938230 0.0054016616 0.7273600000 970273989 0 1783689216 -0.0276765693 -0.0591075309 -0.1165637225 992 1311867203.5185539722 0.0431412533 0.0612038679 0.0879938230 0.0054037557 0.7351100000 970275807 0 1781678080 -0.0281617735 -0.0618458912 -0.1171007678 993 1311867203.5560259819 0.0433522463 0.0611858904 0.0879938230 0.0054013791 0.7264750000 970277657 0 1783414784 -0.0281349048 -0.0638702512 -0.1175152510 994 1311867203.5876550674 0.0433169864 0.0611679136 0.0879938230 0.0053995749 0.7337810000 970279443 0 1781809152 -0.0277914833 -0.0649675354 -0.1178492680 995 1311867203.6191980839 0.0432680845 0.0611499238 0.0879938230 0.0053979143 0.7295220000 970281229 0 1783455744 -0.0279116277 -0.0672218874 -0.1182075515 996 1311867203.6557719707 0.0431109071 0.0611318124 0.0879938230 0.0053952767 0.7376890000 970283047 0 1781293056 -0.0277063251 -0.0698237121 -0.1187367067 997 1311867203.6866750717 0.0429159626 0.0611135417 0.0879938230 0.0053926782 0.7207400000 970284833 0 1783066624 -0.0280738659 -0.0714766234 -0.1191593930 998 1311867203.7195260525 0.0431139916 0.0610955061 0.0879938230 0.0053903615 0.7286060000 970286619 0 1781444608 -0.0280527472 -0.0733730718 -0.1192405447 999 1311867203.7566421032 0.0435555764 0.0610779486 0.0879938230 0.0053880374 0.7294850000 970288501 0 1783160832 -0.0282527059 -0.0746032149 -0.1193496138 1000 1311867203.7867228985 0.0437909067 0.0610606616 0.0879938230 0.0053853951 0.7407550000 970290255 0 1781567488 -0.0287385564 -0.0764197186 -0.1196722314 1001 1311867203.8193860054 0.0438679159 0.0610434860 0.0879938230 0.0053827829 0.7215960000 970292041 0 1783308288 -0.0281417817 -0.0776651204 -0.1201399192 1002 1311867203.8572859764 0.0440290757 0.0610265056 0.0879938230 0.0053812070 0.7627350000 970293923 0 1781424128 -0.0283701699 -0.0788294375 -0.1207929254 1003 1311867203.8891890049 0.0440629683 0.0610095928 0.0879938230 0.0053792847 0.7190870000 970295709 0 1783160832 -0.0287714005 -0.0807669237 -0.1216548830 1004 1311867203.9188020229 0.0442396775 0.0609928897 0.0879938230 0.0053772672 0.7182930000 970297463 0 1781551104 -0.0295807794 -0.0819247290 -0.1224406436 1005 1311867203.9553489685 0.0441815779 0.0609761620 0.0879938230 0.0053749728 0.7195320000 970299313 0 1783181312 -0.0292638037 -0.0823605657 -0.1233160347 1006 1311867203.9866371155 0.0442338325 0.0609595195 0.0879938230 0.0053738697 0.7194950000 970301099 0 1781170176 -0.0295686312 -0.0839545876 -0.1242193505 1007 1311867204.0199849606 0.0443804190 0.0609430557 0.0879938230 0.0053723553 0.7223540000 970302885 0 1782906880 -0.0298536327 -0.0847880989 -0.1253487915 1008 1311867204.0551509857 0.0443884991 0.0609266325 0.0879938230 0.0053700246 0.7200200000 970304735 0 1784557568 -0.0304094143 -0.0858920887 -0.1265278161 1009 1311867204.0867509842 0.0441398248 0.0609099954 0.0879938230 0.0053689055 0.7486050000 970306521 0 1782947840 -0.0309751797 -0.0876575634 -0.1275871694 1010 1311867204.1191530228 0.0444762371 0.0608937244 0.0879938230 0.0053663167 0.7151590000 970308307 0 1784578048 -0.0313128307 -0.0889529213 -0.1285041422 1011 1311867204.1555769444 0.0445590280 0.0608775674 0.0879938230 0.0053639767 0.7090530000 970310125 0 1782587392 -0.0314020328 -0.0904416516 -0.1291969568 1012 1311867204.1876530647 0.0444874130 0.0608613716 0.0879938230 0.0053620202 0.7082760000 970311911 0 1784303616 -0.0321757495 -0.0920106098 -0.1298840791 1013 1311867204.2187769413 0.0447474010 0.0608454644 0.0879938230 0.0053601312 0.7055300000 970313697 0 1782714368 -0.0329917967 -0.0930447727 -0.1303219050 1014 1311867204.2566440105 0.0451347530 0.0608299706 0.0879938230 0.0053576998 0.7013070000 970315579 0 1784332288 -0.0331775919 -0.0942201763 -0.1307953000 1015 1311867204.2867140770 0.0452872030 0.0608146575 0.0879938230 0.0053551245 0.6995060000 970317333 0 1782190080 -0.0337746181 -0.0962421447 -0.1312317252 1016 1311867204.3204538822 0.0458821803 0.0607999602 0.0879938230 0.0053530923 0.7449750000 970319119 0 1784057856 -0.0348662436 -0.0971374884 -0.1316336542 1017 1311867204.3625741005 0.0465323813 0.0607859311 0.0879938230 0.0053505889 0.6897150000 970321097 0 1782337536 -0.0359207541 -0.0986962840 -0.1317964941 1018 1311867204.3869600296 0.0466784760 0.0607720731 0.0879938230 0.0053481414 0.6896470000 970322755 0 1783947264 -0.0367169045 -0.0999734476 -0.1321695894 1019 1311867204.4240970612 0.0474660024 0.0607590152 0.0879938230 0.0053459573 0.6856700000 970324637 0 1782083584 -0.0377618931 -0.1009620577 -0.1324880123 1020 1311867204.4549949169 0.0480021536 0.0607465084 0.0879938230 0.0053446029 0.6831600000 970326391 0 1783693312 -0.0385429636 -0.1017265543 -0.1326780617 1021 1311867204.4872748852 0.0484962761 0.0607345102 0.0879938230 0.0053424298 0.6887050000 970328177 0 1781694464 -0.0395916775 -0.1034256965 -0.1329675168 1022 1311867204.5237219334 0.0488369018 0.0607228687 0.0879938230 0.0053399314 0.6802900000 970330059 0 1783304192 -0.0401589796 -0.1045491919 -0.1333711743 1023 1311867204.5581860542 0.0491931848 0.0607115982 0.0879938230 0.0053383130 0.7122020000 970331877 0 1781424128 -0.0408049449 -0.1052764058 -0.1335963458 1024 1311867204.5878469944 0.0491915382 0.0607003481 0.0879938230 0.0053360913 0.6780090000 970333631 0 1783160832 -0.0414486602 -0.1069922596 -0.1337192506 1025 1311867204.6241528988 0.0490309782 0.0606889634 0.0879938230 0.0053336708 0.6741220000 970335481 0 1781657600 -0.0421751142 -0.1080594808 -0.1336793005 1026 1311867204.6541819572 0.0492874347 0.0606778508 0.0879938230 0.0053314563 0.6739260000 970505171 0 1783562240 -0.0426774994 -0.1101419032 -0.1335196644 1027 1311867204.6871540546 0.0496795885 0.0606671417 0.0879938230 0.0053292371 0.6712900000 970506957 0 1781551104 -0.0435862355 -0.1111721471 -0.1334138960 1028 1311867204.7225689888 0.0498870872 0.0606566552 0.0879938230 0.0053278747 0.6717680000 970508807 0 1783414784 -0.0437798090 -0.1117125526 -0.1331493855 1029 1311867204.7539510727 0.0499026142 0.0606462043 0.0879938230 0.0053254456 0.6723080000 970510593 0 1781694464 -0.0451772921 -0.1129362136 -0.1328381896 1030 1311867204.7878720760 0.0500993021 0.0606359646 0.0879938230 0.0053246201 0.6771040000 970512411 0 1783304192 -0.0467808135 -0.1145394072 -0.1320266128 1031 1311867204.8227200508 0.0499870330 0.0606256358 0.0879938230 0.0053221753 0.6682330000 970514229 0 1781293056 -0.0468080342 -0.1153704450 -0.1307394952 1032 1311867204.8542668819 0.0498245247 0.0606151696 0.0879938230 0.0053209312 0.6693850000 970516015 0 1783054336 -0.0470262095 -0.1168244705 -0.1294371039 1033 1311867204.8864960670 0.0501334667 0.0606050228 0.0879938230 0.0053194417 0.6652330000 970517801 0 1784590336 -0.0481538437 -0.1190299988 -0.1284589320 1034 1311867204.9220221043 0.0504932031 0.0605952434 0.0879938230 0.0053170493 0.6658920000 970519651 0 1782820864 -0.0495101921 -0.1210291684 -0.1272798926 1035 1311867204.9542920589 0.0504830815 0.0605854732 0.0879938230 0.0053150157 0.6632220000 970521437 0 1784451072 -0.0499029309 -0.1225313991 -0.1262915879 1036 1311867204.9865999222 0.0507358126 0.0605759658 0.0879938230 0.0053126246 0.6671370000 970523223 0 1782566912 -0.0504765883 -0.1252074987 -0.1254582852 1037 1311867205.0227239132 0.0509761348 0.0605667085 0.0879938230 0.0053142956 0.6679740000 970525073 0 1784193024 -0.0508934893 -0.1268046498 -0.1247153953 1038 1311867205.0550808907 0.0504993685 0.0605570098 0.0879938230 0.0053273641 0.6590690000 970526891 0 1782587392 -0.0512390025 -0.1277250201 -0.1238454357 1039 1311867205.0880999565 0.0507009327 0.0605475236 0.0879938230 0.0053250492 0.6969800000 970528613 0 1784303616 -0.0518182479 -0.1299712211 -0.1229799762 1040 1311867205.1232450008 0.0513555259 0.0605386852 0.0879938230 0.0053239352 0.6712850000 970530463 0 1782714368 -0.0518861264 -0.1314589530 -0.1221532226 1041 1311867205.1545319557 0.0520523861 0.0605305331 0.0879938230 0.0053350322 0.6527200000 970532217 0 1784430592 -0.0517203957 -0.1326367706 -0.1214353070 1042 1311867205.1863510609 0.0520578213 0.0605224019 0.0879938230 0.0053425979 0.6615730000 970534003 0 1782693888 -0.0518125854 -0.1350508481 -0.1206098273 1043 1311867205.2223129272 0.0516833551 0.0605139273 0.0879938230 0.0053414130 0.6615830000 970535853 0 1784430592 -0.0516123287 -0.1369571388 -0.1200411916 1044 1311867205.2541849613 0.0517979488 0.0605055786 0.0879938230 0.0053405342 0.6609350000 970537639 0 1782841344 -0.0518631227 -0.1384920329 -0.1193049625 1045 1311867205.2880499363 0.0522893928 0.0604977163 0.0879938230 0.0053384755 0.6475300000 970539457 0 1784557568 -0.0524789542 -0.1401036978 -0.1184797511 1046 1311867205.3218879700 0.0526992381 0.0604902607 0.0879938230 0.0053379561 0.6537410000 970541243 0 1782968320 -0.0529828519 -0.1417438537 -0.1177205294 1047 1311867205.3542900085 0.0530326590 0.0604831379 0.0879938230 0.0053420520 0.6770150000 970543061 0 1783242752 -0.0537682995 -0.1434633583 -0.1167937592 1048 1311867205.3862779140 0.0532266870 0.0604762138 0.0879938230 0.0053485462 0.6411690000 970544847 0 1781207040 -0.0544583462 -0.1447674483 -0.1159331724 1049 1311867205.4225649834 0.0533508249 0.0604694213 0.0879938230 0.0053506880 0.6546550000 970546697 0 1782923264 -0.0556435250 -0.1464816928 -0.1152073145 1050 1311867205.4540419579 0.0536190867 0.0604628971 0.0879938230 0.0053537253 0.6500900000 970548483 0 1784573952 -0.0560716018 -0.1476295143 -0.1142719835 1051 1311867205.4865119457 0.0528287254 0.0604556334 0.0879938230 0.0053563807 0.6518170000 970550269 0 1782984704 -0.0565465018 -0.1491586417 -0.1132693365 1052 1311867205.5230340958 0.0528657362 0.0604484187 0.0879938230 0.0053648799 0.6501730000 970552119 0 1784594432 -0.0576945581 -0.1510431319 -0.1123577952 1053 1311867205.5542900562 0.0533277951 0.0604416564 0.0879938230 0.0053838631 0.6519000000 970553905 0 1782587392 -0.0590654723 -0.1517648697 -0.1111940369 1054 1311867205.5866839886 0.0531649627 0.0604347526 0.0879938230 0.0053813779 0.6504900000 970555691 0 1784320000 -0.0601763688 -0.1531539112 -0.1101280227 1055 1311867205.6226179600 0.0524347350 0.0604271696 0.0879938230 0.0053852979 0.6746850000 970557541 0 1782714368 -0.0606506504 -0.1553824395 -0.1091829836 1056 1311867205.6555979252 0.0524418727 0.0604196078 0.0879938230 0.0053837779 0.6521560000 970559327 0 1784340480 -0.0622367598 -0.1578474194 -0.1083030254 1057 1311867205.6902959347 0.0525316074 0.0604121451 0.0879938230 0.0053813135 0.6578250000 970561177 0 1782333440 -0.0627412200 -0.1593710035 -0.1075408682 1058 1311867205.7222061157 0.0528197400 0.0604049690 0.0879938230 0.0053788923 0.6510660000 970562963 0 1784193024 -0.0643307790 -0.1617744863 -0.1070265472 1059 1311867205.7548348904 0.0530975685 0.0603980687 0.0879938230 0.0053767678 0.6565410000 970564781 0 1782587392 -0.0655801818 -0.1634795070 -0.1066183895 1060 1311867205.7906379700 0.0531611815 0.0603912414 0.0879938230 0.0053746121 0.6482680000 970566599 0 1784225792 -0.0664204285 -0.1651137620 -0.1060985625 1061 1311867205.8232109547 0.0536894538 0.0603849249 0.0879938230 0.0053814245 0.6525050000 970568417 0 1782603776 -0.0679058656 -0.1672340930 -0.1055749729 1062 1311867205.8554759026 0.0536723658 0.0603786043 0.0879938230 0.0053831138 0.6433100000 970570235 0 1784221696 -0.0689198971 -0.1688263565 -0.1051428467 1063 1311867205.8905880451 0.0539163388 0.0603725250 0.0879938230 0.0053824373 0.6461880000 970572021 0 1782214656 -0.0701104850 -0.1703488678 -0.1048111692 1064 1311867205.9223020077 0.0539222062 0.0603664627 0.0879938230 0.0053895012 0.6443170000 970573807 0 1783930880 -0.0708513260 -0.1717477590 -0.1044794396 1065 1311867205.9544939995 0.0538731068 0.0603603656 0.0879938230 0.0053871653 0.6468590000 970575593 0 1782333440 -0.0715588480 -0.1739567220 -0.1040698364 1066 1311867205.9905850887 0.0546818823 0.0603550387 0.0879938230 0.0053955174 0.6386430000 970577475 0 1784066048 -0.0730746463 -0.1745784134 -0.1035934836 1067 1311867206.0259850025 0.0545636341 0.0603496110 0.0879938230 0.0053966428 0.6543300000 970579293 0 1782329344 -0.0733577386 -0.1755334139 -0.1033443138 1068 1311867206.0604250431 0.0540561937 0.0603437182 0.0879938230 0.0054039012 0.6496800000 970581079 0 1784057856 -0.0736754686 -0.1782147735 -0.1032490358 1069 1311867206.0903289318 0.0537894368 0.0603375870 0.0879938230 0.0054015310 0.6493570000 970582833 0 1782325248 -0.0738761574 -0.1802476346 -0.1033012271 1070 1311867206.1227540970 0.0540053695 0.0603316691 0.0879938230 0.0053990149 0.6450710000 970584619 0 1784057856 -0.0740172714 -0.1821957529 -0.1028790101 1071 1311867206.1546130180 0.0544399470 0.0603261679 0.0879938230 0.0053968033 0.6801980000 970586405 0 1782452224 -0.0746058598 -0.1844416112 -0.1029883772 1072 1311867206.1903800964 0.0547489971 0.0603209653 0.0879938230 0.0053982089 0.6475100000 970588287 0 1784184832 -0.0760247037 -0.1870635003 -0.1030403450 1073 1311867206.2239561081 0.0547466390 0.0603157702 0.0879938230 0.0053961660 0.6518040000 970590105 0 1782448128 -0.0762559921 -0.1884755045 -0.1031708494 1074 1311867206.2553579807 0.0542899147 0.0603101596 0.0879938230 0.0053949279 0.6578750000 970591859 0 1784176640 -0.0760730505 -0.1901592761 -0.1034922451 1075 1311867206.2904770374 0.0541339889 0.0603044143 0.0879938230 0.0053925296 0.6514610000 970593677 0 1782444032 -0.0766308382 -0.1923867464 -0.1038477421 1076 1311867206.3222041130 0.0540844686 0.0602986337 0.0879938230 0.0053904789 0.6425070000 970595431 0 1783922688 -0.0771852136 -0.1935405582 -0.1042879373 1077 1311867206.3542530537 0.0540710241 0.0602928513 0.0879938230 0.0053890176 0.6511010000 970597249 0 1782063104 -0.0780029446 -0.1952494979 -0.1045264453 1078 1311867206.3900070190 0.0539423674 0.0602869603 0.0879938230 0.0053877921 0.6535690000 970599067 0 1783574528 -0.0781827942 -0.1971859932 -0.1046607345 1079 1311867206.4220259190 0.0537451357 0.0602808975 0.0879938230 0.0053863077 0.6955630000 970600853 0 1781809152 -0.0780435279 -0.1988390237 -0.1046907231 1080 1311867206.4542310238 0.0535851829 0.0602746977 0.0879938230 0.0053845552 0.6455220000 970602671 0 1783320576 -0.0783320889 -0.2006486952 -0.1046207920 1081 1311867206.4905378819 0.0531781502 0.0602681329 0.0879938230 0.0053927071 0.6525060000 970604489 0 1781555200 -0.0789638832 -0.2032083422 -0.1047311723 1082 1311867206.5250329971 0.0535220988 0.0602618982 0.0879938230 0.0053945338 0.6526730000 970606339 0 1783066624 -0.0797362700 -0.2055415809 -0.1048413813 1083 1311867206.5539300442 0.0535583012 0.0602557083 0.0879938230 0.0053984477 0.6500070000 970608093 0 1781174272 -0.0798298344 -0.2078464329 -0.1048265174 1084 1311867206.5921130180 0.0536297821 0.0602495958 0.0879938230 0.0053970213 0.6535060000 970609943 0 1782779904 -0.0798754990 -0.2097912729 -0.1050499380 1085 1311867206.6226360798 0.0547598936 0.0602445362 0.0879938230 0.0054093072 0.6457700000 970611697 0 1784430592 -0.0808862895 -0.2116146982 -0.1051943973 1086 1311867206.6566751003 0.0541918091 0.0602389628 0.0879938230 0.0054077510 0.6598750000 970613515 0 1782566912 -0.0811685920 -0.2136647403 -0.1053888872 1087 1311867206.6945209503 0.0540088750 0.0602332313 0.0879938230 0.0054062846 0.6403930000 970615397 0 1784176640 -0.0807989016 -0.2147164196 -0.1057281345 1088 1311867206.7248480320 0.0534183718 0.0602269677 0.0879938230 0.0054122859 0.6552060000 970617151 0 1782312960 -0.0810311884 -0.2169203609 -0.1060249582 1089 1311867206.7587969303 0.0545266494 0.0602217332 0.0879938230 0.0054529695 0.6547930000 970619001 0 1783922688 -0.0809971467 -0.2180281281 -0.1064221412 1090 1311867206.7902839184 0.0537690632 0.0602158134 0.0879938230 0.0054676852 0.6485950000 970620787 0 1782059008 -0.0815411136 -0.2197567970 -0.1068517715 1091 1311867206.8229770660 0.0545287356 0.0602106006 0.0879938230 0.0054660260 0.6395220000 970622573 0 1783668736 -0.0834338292 -0.2216609269 -0.1073836535 1092 1311867206.8605449200 0.0545210019 0.0602053904 0.0879938230 0.0054637072 0.6460790000 970624423 0 1781809152 -0.0837054253 -0.2235170007 -0.1080230772 1093 1311867206.8907771111 0.0541496947 0.0601998499 0.0879938230 0.0054623011 0.6459460000 970626177 0 1783287808 -0.0833381638 -0.2245333195 -0.1086425185 1094 1311867206.9225020409 0.0542099364 0.0601943747 0.0879938230 0.0054598097 0.6498260000 970627963 0 1781428224 -0.0836960971 -0.2263810486 -0.1092303470 1095 1311867206.9592480659 0.0553346425 0.0601899366 0.0879938230 0.0054589753 0.6775200000 970629845 0 1782906880 -0.0853496268 -0.2290300727 -0.1097483113 1096 1311867206.9948680401 0.0557023287 0.0601858421 0.0879938230 0.0054670573 0.6473550000 970631663 0 1784590336 -0.0859618261 -0.2311540842 -0.1099670008 1097 1311867207.0247550011 0.0563897416 0.0601823816 0.0879938230 0.0054700650 0.6556780000 970633449 0 1782697984 -0.0860521123 -0.2329414040 -0.1100000590 1098 1311867207.0597259998 0.0556657463 0.0601782681 0.0879938230 0.0054679885 0.6433450000 970635299 0 1784209408 -0.0857244879 -0.2352167219 -0.1104027480 1099 1311867207.0942800045 0.0558332391 0.0601743145 0.0879938230 0.0054714017 0.6422280000 970637085 0 1782333440 -0.0862970278 -0.2379751503 -0.1105467230 1100 1311867207.1229140759 0.0558130145 0.0601703497 0.0879938230 0.0054744097 0.6361650000 970638807 0 1783922688 -0.0857972801 -0.2390163541 -0.1107803360 1101 1311867207.1583549976 0.0563367680 0.0601668678 0.0879938230 0.0054785609 0.6407780000 970640657 0 1781932032 -0.0859285742 -0.2408723980 -0.1108430624 1102 1311867207.1904919147 0.0560077280 0.0601630936 0.0879938230 0.0054772734 0.6402460000 970642411 0 1783541760 -0.0861166865 -0.2427089512 -0.1109685376 1103 1311867207.2226181030 0.0557624772 0.0601591039 0.0879938230 0.0054770176 0.6839880000 970644229 0 1781682176 -0.0858737528 -0.2439330518 -0.1108894944 1104 1311867207.2604830265 0.0558768362 0.0601552250 0.0879938230 0.0054773417 0.6363910000 970646111 0 1783160832 -0.0862409920 -0.2453197688 -0.1106141657 1105 1311867207.2926900387 0.0555994101 0.0601511021 0.0879938230 0.0054768798 0.6494790000 970647897 0 1781301248 -0.0863913894 -0.2470615953 -0.1104686707 1106 1311867207.3235239983 0.0563425273 0.0601476586 0.0879938230 0.0054810762 0.6391260000 970649651 0 1782779904 -0.0873279274 -0.2485226244 -0.1098478734 1107 1311867207.3597478867 0.0559025854 0.0601438238 0.0879938230 0.0054797365 0.6394670000 970651533 0 1784446976 -0.0877316743 -0.2501475513 -0.1093933359 1108 1311867207.3901309967 0.0557819158 0.0601398871 0.0879938230 0.0054801491 0.6420690000 970653287 0 1782571008 -0.0883888081 -0.2524258494 -0.1088789329 1109 1311867207.4227840900 0.0556118377 0.0601358041 0.0879938230 0.0054778662 0.6376380000 970655073 0 1784082432 -0.0899303034 -0.2544566691 -0.1086915657 1110 1311867207.4586789608 0.0556997024 0.0601318076 0.0879938230 0.0054773559 0.6366910000 970656923 0 1782190080 -0.0904866457 -0.2553872466 -0.1082109660 1111 1311867207.4927639961 0.0557426661 0.0601278570 0.0879938230 0.0054766293 0.6440540000 970658741 0 1783795712 -0.0914069563 -0.2572803497 -0.1078850627 1112 1311867207.5237300396 0.0559114777 0.0601240653 0.0879938230 0.0054802720 0.6464840000 970660527 0 1781952512 -0.0922442451 -0.2588818669 -0.1075769141 1113 1311867207.5598409176 0.0561912283 0.0601205317 0.0879938230 0.0054786164 0.6410650000 970662345 0 1783541760 -0.0935841277 -0.2604077756 -0.1073574200 1114 1311867207.5944800377 0.0564748459 0.0601172591 0.0879938230 0.0054787441 0.6422660000 970664195 0 1781698560 -0.0948588550 -0.2621178925 -0.1071738377 1115 1311867207.6259219646 0.0552762747 0.0601129174 0.0879938230 0.0054765246 0.6443150000 970665949 0 1783287808 -0.0943568721 -0.2650370002 -0.1066417769 1116 1311867207.6592938900 0.0549814105 0.0601083193 0.0879938230 0.0054748499 0.6425700000 970667799 0 1781297152 -0.0946095437 -0.2666766047 -0.1065658405 1117 1311867207.6923089027 0.0557541400 0.0601044212 0.0879938230 0.0054743474 0.6395000000 970669585 0 1782915072 -0.0960388854 -0.2683781385 -0.1062985137 1118 1311867207.7238640785 0.0551887676 0.0601000244 0.0879938230 0.0054747449 0.6374940000 970671371 0 1784565760 -0.0961407349 -0.2710916102 -0.1061723456 1119 1311867207.7588050365 0.0552728213 0.0600957105 0.0879938230 0.0054731018 0.6803500000 970673125 0 1782833152 -0.0970308036 -0.2734617889 -0.1059736609 1120 1311867207.7921919823 0.0554210022 0.0600915367 0.0879938230 0.0054708612 0.6323890000 970674943 0 1784344576 -0.0979547501 -0.2747938037 -0.1059355587 1121 1311867207.8237760067 0.0555001535 0.0600874409 0.0879938230 0.0054684461 0.6286640000 970676729 0 1782595584 -0.0988408402 -0.2771259844 -0.1059005111 1122 1311867207.8608479500 0.0552730858 0.0600831500 0.0879938230 0.0054668069 0.6320090000 970678579 0 1784311808 -0.0983877853 -0.2789663076 -0.1056211367 1123 1311867207.8937089443 0.0555093698 0.0600790772 0.0879938230 0.0054646049 0.6262790000 970680397 0 1782722560 -0.0983546227 -0.2799433768 -0.1053562015 1124 1311867207.9244139194 0.0553421564 0.0600748628 0.0879938230 0.0054634790 0.6354240000 970682151 0 1784352768 -0.0988477618 -0.2820968926 -0.1050839648 1125 1311867207.9614970684 0.0552618913 0.0600705846 0.0879938230 0.0054624760 0.6262390000 970683937 0 1782210560 -0.0993358791 -0.2835271955 -0.1046949700 1126 1311867207.9914131165 0.0551976413 0.0600662570 0.0879938230 0.0054774003 0.6359320000 970685691 0 1783963648 -0.0987348035 -0.2848398387 -0.1045350730 1127 1311867208.0248498917 0.0545879342 0.0600613960 0.0879938230 0.0054928124 0.6689780000 970687541 0 1782337536 -0.0989303514 -0.2874852121 -0.1042629704 1128 1311867208.0618500710 0.0550366528 0.0600569414 0.0879938230 0.0054911838 0.6297520000 970689295 0 1783959552 -0.0993248597 -0.2891390622 -0.1039757282 1129 1311867208.0924620628 0.0550112538 0.0600524723 0.0879938230 0.0054887684 0.6302510000 970691049 0 1781948416 -0.0991703197 -0.2905237079 -0.1038079858 1130 1311867208.1276559830 0.0552681163 0.0600482383 0.0879938230 0.0054871300 0.6282300000 970692867 0 1783689216 -0.1000807285 -0.2926084697 -0.1037825122 1131 1311867208.1596069336 0.0552479215 0.0600439940 0.0879938230 0.0054848234 0.6281380000 970694653 0 1781547008 -0.1004355475 -0.2940447927 -0.1039471850 1132 1311867208.1905009747 0.0553160384 0.0600398174 0.0879938230 0.0054833160 0.6285540000 970696375 0 1783320576 -0.1008405387 -0.2952595651 -0.1043717787 1133 1311867208.2280850410 0.0554156825 0.0600357361 0.0879938230 0.0054813985 0.6263500000 970698289 0 1781694464 -0.1009358242 -0.2968260944 -0.1045228988 1134 1311867208.2581789494 0.0548226163 0.0600311390 0.0879938230 0.0054794698 0.6221240000 970700043 0 1783324672 -0.1007073075 -0.2985856831 -0.1048398167 1135 1311867208.2901990414 0.0547161140 0.0600264561 0.0879938230 0.0054774171 0.6522730000 970701797 0 1781313536 -0.1003084704 -0.2990712225 -0.1051554158 1136 1311867208.3270208836 0.0556866191 0.0600226358 0.0879938230 0.0054795513 0.6217470000 970703679 0 1783054336 -0.1012428924 -0.3000438809 -0.1054591164 1137 1311867208.3580970764 0.0559739396 0.0600190750 0.0879938230 0.0054800071 0.6221400000 970705465 0 1781055488 -0.1019635722 -0.3011880517 -0.1053801626 1138 1311867208.3910560608 0.0561417416 0.0600156678 0.0879938230 0.0054781449 0.6204190000 970707219 0 1782689792 -0.1023773029 -0.3023715615 -0.1054713726 1139 1311867208.4260230064 0.0559517778 0.0600120999 0.0879938230 0.0054762340 0.6191210000 970709069 0 1784430592 -0.1028098166 -0.3047025204 -0.1056210548 1140 1311867208.4577419758 0.0564779639 0.0600089998 0.0879938230 0.0054762200 0.6215420000 970710855 0 1782689792 -0.1030905247 -0.3065102994 -0.1054766625 1141 1311867208.4907650948 0.0564301796 0.0600058632 0.0879938230 0.0054740315 0.6195270000 970712673 0 1784336384 -0.1030131504 -0.3074967861 -0.1053017974 1142 1311867208.5257411003 0.0563807376 0.0600026888 0.0879938230 0.0054722979 0.6270450000 970714523 0 1782689792 -0.1037261710 -0.3087692857 -0.1050833836 1143 1311867208.5583798885 0.0565167405 0.0599996390 0.0879938230 0.0054699723 0.6231720000 970716309 0 1784336384 -0.1040748656 -0.3095564842 -0.1046138927 1144 1311867208.5904500484 0.0563678816 0.0599964644 0.0879938230 0.0054683764 0.6144140000 970718127 0 1782837248 -0.1040435061 -0.3111065030 -0.1040001065 1145 1311867208.6259779930 0.0561031140 0.0599930641 0.0879938230 0.0054661893 0.6211740000 970719913 0 1784483840 -0.1046112925 -0.3123181760 -0.1035985947 1146 1311867208.6582078934 0.0553780384 0.0599890370 0.0879938230 0.0054640035 0.6214780000 970721731 0 1782833152 -0.1041415706 -0.3136973977 -0.1030510068 1147 1311867208.6910300255 0.0542288870 0.0599840151 0.0879938230 0.0054669230 0.6227750000 970723517 0 1781166080 -0.1041544154 -0.3145480752 -0.1023239717 1148 1311867208.7262260914 0.0545520931 0.0599792834 0.0879938230 0.0054663392 0.6161680000 970725367 0 1782943744 -0.1043977961 -0.3159737587 -0.1019948423 1149 1311867208.7591009140 0.0547310114 0.0599747158 0.0879938230 0.0054640728 0.6171830000 970727153 0 1781293056 -0.1050893888 -0.3164013326 -0.1014192253 1150 1311867208.7909750938 0.0542899407 0.0599697725 0.0879938230 0.0054620334 0.6304190000 970728907 0 1783070720 -0.1049611643 -0.3170952201 -0.1009962633 1151 1311867208.8259930611 0.0544883385 0.0599650102 0.0879938230 0.0054608081 0.6556530000 970730757 0 1781420032 -0.1057120413 -0.3189155161 -0.1005392075 1152 1311867208.8588190079 0.0555819720 0.0599612054 0.0879938230 0.0054650921 0.6256110000 970732575 0 1783087104 -0.1071878821 -0.3199354410 -0.0999281183 1153 1311867208.8916258812 0.0545181111 0.0599564846 0.0879938230 0.0054753385 0.6268120000 970734329 0 1781415936 -0.1080626547 -0.3206292391 -0.0994725302 1154 1311867208.9275119305 0.0551810004 0.0599523464 0.0879938230 0.0054747024 0.6256830000 970736147 0 1783197696 -0.1086110547 -0.3227930963 -0.0994011834 1155 1311867208.9577760696 0.0557983108 0.0599487499 0.0879938230 0.0054725340 0.6228130000 970737901 0 1781547008 -0.1100201756 -0.3243974745 -0.0995990261 1156 1311867208.9911639690 0.0559946522 0.0599453294 0.0879938230 0.0054704693 0.6190040000 970739719 0 1783193600 -0.1101774201 -0.3250129521 -0.0998657569 1157 1311867209.0270779133 0.0563127808 0.0599421897 0.0879938230 0.0054697685 0.6194640000 970741569 0 1781563392 -0.1106342897 -0.3267911971 -0.0999561101 1158 1311867209.0579569340 0.0569965765 0.0599396460 0.0879938230 0.0054677075 0.6247980000 970743323 0 1783324672 -0.1118759960 -0.3278527558 -0.1006343737 1159 1311867209.0906980038 0.0568086728 0.0599369446 0.0879938230 0.0054657496 0.6561040000 970745141 0 1781694464 -0.1118265167 -0.3283006251 -0.1010820046 1160 1311867209.1260778904 0.0570163131 0.0599344268 0.0879938230 0.0054640921 0.6170290000 970746927 0 1783341056 -0.1126667485 -0.3295074403 -0.1016006544 1161 1311867209.1600620747 0.0575176254 0.0599323451 0.0879938230 0.0054624215 0.6141890000 970748777 0 1781694464 -0.1133303419 -0.3307045698 -0.1019779593 1162 1311867209.1917839050 0.0576604381 0.0599303900 0.0879938230 0.0054604982 0.6120680000 970750563 0 1783324672 -0.1134753376 -0.3309710026 -0.1024694294 1163 1311867209.2259531021 0.0579216890 0.0599286628 0.0879938230 0.0054582565 0.6136800000 970752349 0 1781694464 -0.1143727526 -0.3325488865 -0.1028637439 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-19 06:05:36 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0600070000 9055081 955859216 1769037824 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0030796253 0.0015398127 0.0030796253 0.0051980098 0.0679160000 9384703 955859216 1767231488 -0.0004412749 -0.0040355935 0.0006708794 3 0.0800000000 0.0063277814 0.0031358022 0.0063277814 0.0043254801 0.0608920000 9386281 955859216 1768607744 -0.0005280133 -0.0098962383 0.0005286219 4 0.1200000000 0.0034282017 0.0032089021 0.0063277814 0.0068763620 0.0759520000 9387863 955859216 1766957056 0.0010960712 -0.0099197524 0.0018420874 5 0.1600000000 0.0069111115 0.0039493440 0.0069111115 0.0064541179 0.0955310000 9389437 955859216 1765081088 0.0026801426 -0.0108894827 0.0027075049 6 0.2000000000 0.0036851119 0.0039053053 0.0069111115 0.0058146557 0.0854880000 9391347 955859216 1765068800 0.0021821600 -0.0133301169 0.0027215795 7 0.2400000000 0.0054515046 0.0041261909 0.0069111115 0.0054895361 0.0419050000 9392601 955859216 1766432768 0.0024365392 -0.0152695607 0.0031306273 8 0.2800000000 0.0093697906 0.0047816409 0.0093697906 0.0053377610 0.0659430000 9393855 955859216 1765847040 0.0038609661 -0.0161003526 0.0041185687 9 0.3200000000 0.0107250018 0.0054420143 0.0107250018 0.0050432784 0.0758740000 9395749 955859216 1765072896 0.0039528613 -0.0174582470 0.0041623074 10 0.3600000000 0.0106940242 0.0059672153 0.0107250018 0.0047634960 0.0623310000 9398315 955859216 1765085184 0.0053193183 -0.0188170504 0.0043809977 11 0.4000000000 0.0117380824 0.0064918396 0.0117380824 0.0045842179 0.0407360000 9399569 955859216 1766449152 0.0058876481 -0.0202745665 0.0047804802 12 0.4400000000 0.0133785354 0.0070657309 0.0133785354 0.0044289360 0.0569270000 9400823 955859216 1766068224 0.0062713367 -0.0214215070 0.0047200890 13 0.4800000000 0.0158552770 0.0077418498 0.0158552770 0.0044865807 0.0413410000 9402077 955859216 1765089280 0.0069556241 -0.0221189223 0.0048628538 14 0.5200000000 0.0175231695 0.0084405155 0.0175231695 0.0044873557 0.0887800000 9403331 955859216 1765085184 0.0076843789 -0.0226648469 0.0050772894 15 0.5600000000 0.0184833538 0.0091100381 0.0184833538 0.0043442140 0.0702610000 9404585 955859216 1765085184 0.0080508590 -0.0228940342 0.0048286282 16 0.6000000000 0.0184273068 0.0096923674 0.0184833538 0.0042012883 0.0499490000 9405839 955859216 1765085184 0.0079695573 -0.0230383184 0.0045816847 17 0.6400000000 0.0192077551 0.0102520960 0.0192077551 0.0040825623 0.0459140000 9408373 955859216 1766559744 0.0074271653 -0.0231072661 0.0042317752 18 0.6800000000 0.0200516731 0.0107965170 0.0200516731 0.0039808863 0.0618050000 9412251 955859216 1766211584 0.0078896908 -0.0227937382 0.0042468091 19 0.7200000000 0.0203029569 0.0112968559 0.0203029569 0.0040316686 0.0408800000 9413505 955859216 1767575552 0.0092713265 -0.0225642342 0.0042348853 20 0.7600000000 0.0204567779 0.0117548520 0.0204567779 0.0039280208 0.0496590000 9414759 955859216 1766703104 0.0096157584 -0.0227349382 0.0038148188 21 0.8000000000 0.0211403705 0.0122017815 0.0211403705 0.0038312079 0.0493620000 9416013 955859216 1765974016 0.0093373284 -0.0224840324 0.0041298233 22 0.8400000000 0.0208135676 0.0125932263 0.0211403705 0.0037395753 0.0638680000 9417267 955859216 1765089280 0.0085491519 -0.0224736035 0.0038731783 23 0.8800000000 0.0203150474 0.0129289577 0.0211403705 0.0036537239 0.0425830000 9418521 955859216 1766449152 0.0089148246 -0.0228405260 0.0038881837 24 0.9200000000 0.0203999598 0.0132402494 0.0211403705 0.0035813892 0.0789480000 9419775 955859216 1765830656 0.0099424738 -0.0232408587 0.0042160642 25 0.9600000000 0.0206158794 0.0135352746 0.0211403705 0.0035152313 0.0485530000 9421029 955859216 1765072896 0.0111629320 -0.0236031860 0.0046140789 26 1.0000000000 0.0211200919 0.0138269984 0.0211403705 0.0034490315 0.0580300000 9422283 955859216 1766449152 0.0107598128 -0.0245712195 0.0044891555 27 1.0400000000 0.0221333485 0.0141346410 0.0221333485 0.0033986417 0.0789040000 9423537 955859216 1765941248 0.0112010613 -0.0248714313 0.0048344960 28 1.0800000000 0.0215430632 0.0143992275 0.0221333485 0.0033551684 0.0795800000 9424791 955859216 1765687296 0.0128012756 -0.0254999418 0.0048287632 29 1.1200000000 0.0225070566 0.0146788078 0.0225070566 0.0035356704 0.0813460000 9426045 955859216 1765433344 0.0143048242 -0.0258287657 0.0051393034 30 1.1600000000 0.0220213961 0.0149235607 0.0225070566 0.0037857941 0.0919790000 9427299 955859216 1765179392 0.0138211371 -0.0268370472 0.0051475791 31 1.2000000000 0.0226567220 0.0151730175 0.0226567220 0.0039633462 0.0719290000 9428553 955859216 1766178816 0.0158831980 -0.0272049978 0.0055799722 32 1.2400000000 0.0237930771 0.0154423944 0.0237930771 0.0044066855 0.0546640000 9429807 955859216 1765560320 0.0180898253 -0.0270643290 0.0062060147 33 1.2800000000 0.0234302245 0.0156844499 0.0237930771 0.0047301171 0.0810590000 9433621 955859216 1765081088 0.0180875901 -0.0272415485 0.0068482910 34 1.3200000000 0.0235877037 0.0159168985 0.0237930771 0.0049316329 0.0628660000 9440123 955859216 1765085184 0.0178495329 -0.0276061110 0.0076404125 35 1.3600000000 0.0243069846 0.0161566152 0.0243069846 0.0053828187 0.0839630000 9441377 955859216 1765085184 0.0183153693 -0.0276595969 0.0084898630 36 1.4000000000 0.0231961086 0.0163521567 0.0243069846 0.0057326029 0.0898110000 9442631 955859216 1765085184 0.0192569401 -0.0282860454 0.0091608288 37 1.4400000000 0.0237548836 0.0165522304 0.0243069846 0.0061920023 0.0870560000 9443885 955859216 1765085184 0.0203603134 -0.0287727751 0.0098450659 38 1.4800000000 0.0233947039 0.0167322955 0.0243069846 0.0081848483 0.1036160000 9445139 955859216 1765085184 0.0221105181 -0.0292813610 0.0114063527 39 1.5200000000 0.0242697448 0.0169255634 0.0243069846 0.0085117103 0.0548710000 9446393 955859216 1765085184 0.0238488410 -0.0298852436 0.0126685835 40 1.5600000000 0.0248921793 0.0171247288 0.0248921793 0.0086530580 0.0884990000 9447647 955859216 1765085184 0.0251196288 -0.0306670945 0.0132622914 41 1.6000000000 0.0227469280 0.0172618557 0.0248921793 0.0087851377 0.1114930000 9448901 955859216 1765068800 0.0263179950 -0.0321574733 0.0141738085 42 1.6400000000 0.0241546854 0.0174259706 0.0248921793 0.0089384137 0.0779650000 9450155 955859216 1765924864 0.0284361262 -0.0333212577 0.0149139278 43 1.6800000000 0.0271947011 0.0176531504 0.0271947011 0.0092470857 0.0976320000 9451409 955859216 1765056512 0.0310290977 -0.0338726938 0.0162212327 44 1.7200000000 0.0295376219 0.0179232520 0.0295376219 0.0095295233 0.0696270000 9452663 955859216 1766559744 0.0331002846 -0.0345184095 0.0177153572 45 1.7600000000 0.0287204292 0.0181631893 0.0295376219 0.0098390323 0.0447390000 9453917 955859216 1766051840 0.0349078923 -0.0358389132 0.0186408442 46 1.8000000000 0.0199894197 0.0182028900 0.0295376219 0.0109505120 0.0601550000 9455171 955859216 1765343232 0.0617479384 -0.0279073194 0.0122919157 47 1.8400000000 0.0200188179 0.0182415267 0.0295376219 0.0108603564 0.1013080000 9456425 955859216 1765081088 0.1221635118 -0.0312155075 0.0012529930 48 1.8800000000 0.0231042020 0.0183428325 0.0295376219 0.0110192351 0.0586350000 9457679 955859216 1765081088 0.1248477325 -0.0345050432 0.0026421081 49 1.9200000000 0.0250922572 0.0184805758 0.0295376219 0.0111830491 0.0517690000 9458933 955859216 1765081088 0.1275950223 -0.0374243632 0.0034653901 50 1.9600000000 0.0273797624 0.0186585596 0.0295376219 0.0112862191 0.0679160000 9460187 955859216 1765085184 0.1305473000 -0.0398276895 0.0043749255 51 2.0000000000 0.0287473388 0.0188563788 0.0295376219 0.0113608672 0.0440920000 9461441 955859216 1766432768 0.1335802078 -0.0421378128 0.0046135359 52 2.0400000000 0.0299904179 0.0190704949 0.0299904179 0.0114280025 0.0566620000 9462695 955859216 1765679104 0.1370790899 -0.0441925600 0.0049701706 53 2.0800000000 0.0311232936 0.0192979062 0.0311232936 0.0114657258 0.0913800000 9463949 955859216 1765068800 0.1388859600 -0.0461070687 0.0052956548 54 2.1200000000 0.0332000926 0.0195553541 0.0332000926 0.0115029690 0.0465780000 9465203 955859216 1765060608 0.1425495297 -0.0477099903 0.0054310337 55 2.1600000000 0.0236718263 0.0196301990 0.0332000926 0.0115175283 0.1010740000 9466457 955859216 1765060608 0.1446222514 -0.0364219733 0.0016929936 56 2.2000000000 0.0255985595 0.0197367769 0.0332000926 0.0115954310 0.0612130000 9467711 955859216 1765060608 0.1459102929 -0.0398318022 0.0022105370 57 2.2400000000 0.0264054872 0.0198537718 0.0332000926 0.0117549114 0.0657290000 9468965 955859216 1765060608 0.1458701491 -0.0431513190 0.0029995907 58 2.2800000000 0.0282652956 0.0199987981 0.0332000926 0.0119248242 0.0431930000 9470219 955859216 1766424576 0.1479232013 -0.0460739583 0.0032172427 59 2.3200000000 0.0305284131 0.0201772662 0.0332000926 0.0121803583 0.0551530000 9471473 955859216 1765933056 0.1503403187 -0.0486482941 0.0033204781 60 2.3600000000 0.0321142450 0.0203762158 0.0332000926 0.0123587017 0.0569060000 9472727 955859216 1765064704 0.1535867304 -0.0509391129 0.0027047694 61 2.4000000000 0.0339794010 0.0205992188 0.0339794010 0.0126412365 0.0718550000 9473981 955859216 1766424576 0.1563457698 -0.0528893843 0.0028274392 62 2.4400000000 0.0309406165 0.0207660156 0.0339794010 0.0128607019 0.0545530000 9475235 955859216 1766424576 0.1592462510 -0.0501579195 0.0008121133 63 2.4800000000 0.0299964976 0.0209125312 0.0339794010 0.0130699568 0.0454610000 9476489 955859216 1766080512 0.1624391675 -0.0487330705 -0.0004859380 64 2.5200000000 0.0307255257 0.0210658592 0.0339794010 0.0132109113 0.0525920000 9477743 955859216 1765044224 0.1658957005 -0.0514673367 -0.0018378645 65 2.5600000000 0.0297957733 0.0212001656 0.0339794010 0.0133118961 0.0472240000 9484117 955859216 1766424576 0.1698714942 -0.0502882227 -0.0039653294 66 2.6000000000 0.0291447137 0.0213205375 0.0339794010 0.0133965982 0.0586160000 9495867 955859216 1765806080 0.1740944237 -0.0506279469 -0.0063675120 67 2.6400000000 0.0289838463 0.0214349153 0.0339794010 0.0135040719 0.0744110000 9497121 955859216 1765048320 0.1773279607 -0.0509690382 -0.0084119998 68 2.6800000000 0.0290368404 0.0215467083 0.0339794010 0.0136200002 0.0861310000 9498375 955859216 1765060608 0.1819518954 -0.0507465154 -0.0112060243 69 2.7200000000 0.0297561008 0.0216656850 0.0339794010 0.0137324627 0.0526120000 9499629 955859216 1765060608 0.1851086766 -0.0535208434 -0.0128259808 70 2.7600000000 0.0308403783 0.0217967520 0.0339794010 0.0139153858 0.0796610000 9500883 955859216 1765429248 0.1879554689 -0.0558685847 -0.0135697443 71 2.8000000000 0.0298459511 0.0219101210 0.0339794010 0.0140274289 0.0724880000 9502137 955859216 1766424576 0.1918339580 -0.0543578491 -0.0160676837 72 2.8400000000 0.0294829514 0.0220152992 0.0339794010 0.0141872357 0.0919060000 9503391 955859216 1765056512 0.1943810135 -0.0541096739 -0.0176118091 73 2.8800000000 0.0310418811 0.0221389510 0.0339794010 0.0143170387 0.0620130000 9504645 955859216 1766424576 0.1970794350 -0.0561476611 -0.0185335837 74 2.9200000000 0.0298123006 0.0222426449 0.0339794010 0.0143981957 0.0505220000 9505899 955859216 1765773312 0.2011820227 -0.0553198270 -0.0215372872 75 2.9600000000 0.0317442492 0.0223693330 0.0339794010 0.0145428908 0.0501340000 9507153 955859216 1765072896 0.2033572346 -0.0570424534 -0.0220567640 76 3.0000000000 0.0296961218 0.0224657381 0.0339794010 0.0145751404 0.0650220000 9508407 955859216 1765060608 0.2075458169 -0.0576509610 -0.0254655629 77 3.0400000000 0.0306237750 0.0225716866 0.0339794010 0.0146435145 0.0926720000 9509661 955859216 1765060608 0.2104699016 -0.0598574802 -0.0272936225 78 3.0800000000 0.0299243033 0.0226659510 0.0339794010 0.0146618803 0.0692170000 9510915 955859216 1765060608 0.2152118385 -0.0600395165 -0.0308750570 79 3.1200000000 0.0298908483 0.0227574054 0.0339794010 0.0147129137 0.0742920000 9512169 955859216 1765060608 0.2192703336 -0.0603663400 -0.0334483609 80 3.1600000000 0.0299441591 0.0228472398 0.0339794010 0.0151448218 0.0574910000 9513423 955859216 1765060608 0.2279101908 -0.0615422688 -0.0396110453 81 3.2000000000 0.0299822204 0.0229353260 0.0339794010 0.0151709761 0.0857400000 9514677 955859216 1765060608 0.2319724560 -0.0619044602 -0.0421113707 82 3.2400000000 0.0296111107 0.0230167380 0.0339794010 0.0151716932 0.0626980000 9515931 955859216 1766535168 0.2344152778 -0.0646003708 -0.0443199165 83 3.2800000000 0.0300010312 0.0231008861 0.0339794010 0.0152241833 0.0842520000 9517185 955859216 1765912576 0.2384057194 -0.0651681200 -0.0465028323 84 3.3200000000 0.0296198111 0.0231784923 0.0339794010 0.0152125331 0.0539560000 9518439 955859216 1765408768 0.2399598062 -0.0678275451 -0.0478037708 85 3.3600000000 0.0298301466 0.0232567471 0.0339794010 0.0152282517 0.0731140000 9519693 955859216 1765011456 0.2440173775 -0.0692629069 -0.0501463749 86 3.4000000000 0.0307210051 0.0233435408 0.0339794010 0.0152666776 0.0991790000 9520947 955859216 1765044224 0.2459912151 -0.0713634118 -0.0511550233 87 3.4400000000 0.0303148385 0.0234236706 0.0339794010 0.0152947524 0.0837820000 9522201 955859216 1765044224 0.2500442266 -0.0713499263 -0.0536457412 88 3.4800000000 0.0304859933 0.0235039243 0.0339794010 0.0153170693 0.0847100000 9523455 955859216 1765044224 0.2538948059 -0.0706724375 -0.0562353209 89 3.5200000000 0.0313452557 0.0235920292 0.0339794010 0.0153157163 0.0896380000 9524709 955859216 1765060608 0.2561940849 -0.0721705481 -0.0579949543 90 3.5600000000 0.0311192200 0.0236756646 0.0339794010 0.0153233461 0.0591880000 9525963 955859216 1765060608 0.2582778037 -0.0740363672 -0.0595265776 91 3.6000000000 0.0318650045 0.0237656574 0.0339794010 0.0153406602 0.0521290000 9527217 955859216 1765060608 0.2610258758 -0.0755090341 -0.0609825552 92 3.6400000000 0.0311689451 0.0238461279 0.0339794010 0.0153413929 0.0588150000 9528471 955859216 1766535168 0.2646772861 -0.0738304183 -0.0633284748 93 3.6800000000 0.0312500335 0.0239257398 0.0339794010 0.0153011371 0.0485470000 9529725 955859216 1766060032 0.2658570707 -0.0754372850 -0.0649321377 94 3.7200000000 0.0318918191 0.0240104853 0.0339794010 0.0152626157 0.0525350000 9530979 955859216 1765191680 0.2685692608 -0.0766077861 -0.0661800057 95 3.7600000000 0.0327624716 0.0241026115 0.0339794010 0.0152198478 0.0765860000 9532233 955859216 1765076992 0.2717723250 -0.0771641061 -0.0681255534 96 3.8000000000 0.0329549313 0.0241948231 0.0339794010 0.0151749819 0.0578280000 9533487 955859216 1766408192 0.2743037343 -0.0776913539 -0.0703868568 97 3.8400000000 0.0332573988 0.0242882517 0.0339794010 0.0151380183 0.0585180000 9534741 955859216 1765564416 0.2767025530 -0.0782577097 -0.0723291188 98 3.8800000000 0.0330579542 0.0243777385 0.0339794010 0.0150961923 0.0556190000 9535995 955859216 1765048320 0.2777725458 -0.0791306421 -0.0730309337 99 3.9200000000 0.0330836438 0.0244656769 0.0339794010 0.0150407236 0.0674140000 9537249 955859216 1765060608 0.2799616158 -0.0798599198 -0.0750762224 100 3.9600000000 0.0328144431 0.0245491646 0.0339794010 0.0149885453 0.0830770000 9538503 955859216 1765060608 0.2814555466 -0.0809827149 -0.0763584599 101 4.0000000000 0.0344581529 0.0246472734 0.0344581529 0.0149380382 0.0639940000 9539757 955859216 1765060608 0.2843367755 -0.0807896182 -0.0776491314 102 4.0400000000 0.0348562188 0.0247473611 0.0348562188 0.0148923719 0.0784480000 9541011 955859216 1766424576 0.2864713669 -0.0805564150 -0.0791656002 103 4.0800000000 0.0350649506 0.0248475319 0.0350649506 0.0148463878 0.0496600000 9542265 955859216 1766424576 0.2887719572 -0.0802703351 -0.0803980455 104 4.1200000000 0.0354900919 0.0249498642 0.0354900919 0.0147929149 0.0515220000 9543519 955859216 1766207488 0.2905998230 -0.0797006562 -0.0816365629 105 4.1600000000 0.0359483548 0.0250546117 0.0359483548 0.0147448540 0.0526660000 9544773 955859216 1765171200 0.2930701971 -0.0789369419 -0.0833959579 106 4.2000000000 0.0357858539 0.0251558498 0.0359483548 0.0146884225 0.0559390000 9546027 955859216 1766551552 0.2947001755 -0.0782741010 -0.0846156180 107 4.2400000000 0.0353920497 0.0252515153 0.0359483548 0.0146255167 0.0502970000 9547281 955859216 1765806080 0.2954908013 -0.0778841823 -0.0853674114 108 4.2800000000 0.0361860730 0.0253527612 0.0361860730 0.0145614828 0.0661840000 9548535 955859216 1765011456 0.2986221910 -0.0764303952 -0.0879991204 109 4.3200000000 0.0360291936 0.0254507101 0.0361860730 0.0144944155 0.0515770000 9549789 955859216 1766424576 0.3001803458 -0.0756184235 -0.0892639831 110 4.3600000000 0.0363505334 0.0255497994 0.0363505334 0.0144302242 0.0897360000 9551043 955859216 1765687296 0.3011173606 -0.0748457387 -0.0903185979 111 4.4000000000 0.0371715575 0.0256544999 0.0371715575 0.0143664138 0.0546390000 9552297 955859216 1767051264 0.3023555279 -0.0735429302 -0.0915344357 112 4.4400000000 0.0380390733 0.0257650765 0.0380390733 0.0143084720 0.0933500000 9553551 955859216 1769074688 0.3045635521 -0.0717836022 -0.0935546458 113 4.4800000000 0.0385801457 0.0258784841 0.0385801457 0.0142454502 0.0565300000 9554805 955859216 1770725376 0.3061221540 -0.0698743761 -0.0945931002 114 4.5200000000 0.0383342728 0.0259877455 0.0385801457 0.0141823678 0.0940190000 9556059 955859216 1772503040 0.3069591224 -0.0681022257 -0.0956586152 115 4.5600000000 0.0387237854 0.0260984936 0.0387237854 0.0141223289 0.0597340000 9557313 955859216 1774161920 0.3081030548 -0.0660209432 -0.0970758125 116 4.6000000000 0.0384742357 0.0262051811 0.0387237854 0.0140652479 0.0570590000 9558567 955859216 1775812608 0.3085245192 -0.0643107966 -0.0981390849 117 4.6400000000 0.0388397351 0.0263131687 0.0388397351 0.0140230245 0.0737850000 9559821 955859216 1777606656 0.3093152046 -0.0621342957 -0.0994431898 118 4.6800000000 0.0378730074 0.0264111334 0.0388397351 0.0139879494 0.0494270000 9561075 955859216 1779240960 0.3096328378 -0.0606550947 -0.1001162380 119 4.7200000000 0.0387356617 0.0265147009 0.0388397351 0.0139488481 0.0566530000 9562329 955859216 1780891648 0.3100832701 -0.0588080063 -0.1004495993 120 4.7600000000 0.0384395309 0.0266140745 0.0388397351 0.0139025283 0.0575280000 9563583 955859216 1782521856 0.3098049164 -0.0575353391 -0.1014089584 121 4.8000000000 0.0386010781 0.0267131406 0.0388397351 0.0138585239 0.0740780000 9564837 955859216 1784168448 0.3092084527 -0.0563641340 -0.1010246351 122 4.8400000000 0.0406089537 0.0268270407 0.0406089537 0.0138324288 0.0495550000 9566091 955859216 1785946112 0.3085420728 -0.0536287576 -0.1013793871 123 4.8800000000 0.0407903604 0.0269405637 0.0407903604 0.0137863415 0.0527090000 9567345 955859216 1787596800 0.3078602254 -0.0515527874 -0.1011574641 124 4.9200000000 0.0401100218 0.0270467690 0.0407903604 0.0137457598 0.0611290000 9568599 955859216 1785438208 0.3068835437 -0.0498898812 -0.1012937352 125 4.9600000000 0.0408546329 0.0271572319 0.0408546329 0.0137045796 0.0522370000 9569853 955859216 1784221696 0.3066101670 -0.0476988181 -0.1008079723 126 5.0000000000 0.0406216234 0.0272640921 0.0408546329 0.0136656170 0.0687800000 9571107 955859216 1783074816 0.3062320054 -0.0456118584 -0.1009198353 127 5.0400000000 0.0397990420 0.0273627925 0.0408546329 0.0136370374 0.0649050000 9572361 955859216 1784438784 0.3048307598 -0.0432727784 -0.1004193872 128 5.0800000000 0.0377606042 0.0274440254 0.0408546329 0.0136101068 0.0650530000 9573615 955859216 1783549952 0.3032692075 -0.0397412181 -0.1002101675 129 5.1200000000 0.0369092152 0.0275173990 0.0408546329 0.0135831739 0.0885930000 9585109 955859216 1782804480 0.3028786778 -0.0362175107 -0.1004684791 130 5.1600000000 0.0364854038 0.0275863836 0.0408546329 0.0135608247 0.0770000000 9607355 955859216 1781788672 0.3016096056 -0.0349454880 -0.0993744507 131 5.2000000000 0.0356974229 0.0276483000 0.0408546329 0.0135432642 0.0482890000 9608609 955859216 1780662272 0.2991473377 -0.0340882353 -0.0981609151 132 5.2400000000 0.0353938788 0.0277069786 0.0408546329 0.0135241740 0.0859860000 9609863 955859216 1779511296 0.2970599830 -0.0335174426 -0.0970243886 133 5.2800000000 0.0355006866 0.0277655779 0.0408546329 0.0134930964 0.0650200000 9611117 955859216 1778376704 0.2958822250 -0.0328004137 -0.0953826085 134 5.3200000000 0.0362647586 0.0278290046 0.0408546329 0.0134560988 0.0882210000 9612371 955859216 1777491968 0.2943656743 -0.0318487585 -0.0938626379 135 5.3600000000 0.0359174758 0.0278889192 0.0408546329 0.0134203787 0.0851110000 9613625 955859216 1778851840 0.2918642163 -0.0312177129 -0.0917753503 136 5.4000000000 0.0362748243 0.0279505803 0.0408546329 0.0133876205 0.0612110000 9614879 955859216 1777709056 0.2904520035 -0.0299800020 -0.0904134214 137 5.4400000000 0.0369796082 0.0280164856 0.0408546329 0.0133556230 0.0761830000 9616133 955859216 1776979968 0.2897549570 -0.0280594751 -0.0891567469 138 5.4800000000 0.0354865342 0.0280706164 0.0408546329 0.0134168327 0.0480700000 9617387 955859216 1775947776 0.2859247029 -0.0266708098 -0.0862413123 139 5.5200000000 0.0355951227 0.0281247495 0.0408546329 0.0133857301 0.0683450000 9618641 955859216 1774931968 0.2839146554 -0.0259842426 -0.0844841599 140 5.5600000000 0.0358780324 0.0281801301 0.0408546329 0.0133666099 0.0610960000 9619895 955859216 1776312320 0.2828905284 -0.0244059749 -0.0831656903 141 5.6000000000 0.0361053906 0.0282363376 0.0408546329 0.0133434458 0.0622100000 9621149 955859216 1775542272 0.2813479006 -0.0228690561 -0.0816012993 142 5.6400000000 0.0365349986 0.0282947789 0.0408546329 0.0133174909 0.0601950000 9622403 955859216 1774551040 0.2801668346 -0.0207672622 -0.0802108198 143 5.6800000000 0.0356817916 0.0283464364 0.0408546329 0.0132995529 0.0789520000 9623657 955859216 1773502464 0.2776929736 -0.0194765627 -0.0787310451 144 5.7200000000 0.0352472067 0.0283943584 0.0408546329 0.0132702621 0.0681730000 9624911 955859216 1772519424 0.2749683559 -0.0188139006 -0.0774069428 145 5.7600000000 0.0366301723 0.0284511571 0.0408546329 0.0132395641 0.0781120000 9626165 955859216 1773899776 0.2737097442 -0.0166426655 -0.0755961910 146 5.8000000000 0.0358526707 0.0285018524 0.0408546329 0.0132117052 0.0761010000 9627419 955859216 1772883968 0.2713295817 -0.0152124362 -0.0743082911 147 5.8400000000 0.0356082581 0.0285501953 0.0408546329 0.0131891773 0.1042290000 9628673 955859216 1770360832 0.2684826553 -0.0139833484 -0.0721146241 148 5.8800000000 0.0354363993 0.0285967237 0.0408546329 0.0131695745 0.0706690000 9629927 955859216 1771741184 0.2666744590 -0.0126291104 -0.0713683516 149 5.9200000000 0.0348568223 0.0286387378 0.0408546329 0.0131487793 0.0539000000 9631181 955859216 1770897408 0.2634599507 -0.0120396474 -0.0694178566 150 5.9600000000 0.0339872800 0.0286743947 0.0408546329 0.0131302100 0.0658260000 9632435 955859216 1770012672 0.2595303953 -0.0124517223 -0.0672309920 151 6.0000000000 0.0343105793 0.0287117204 0.0408546329 0.0131073197 0.0967230000 9633689 955859216 1768964096 0.2560040057 -0.0124770775 -0.0650656596 152 6.0400000000 0.0336041600 0.0287439075 0.0408546329 0.0130906982 0.0860490000 9634943 955859216 1767948288 0.2524676621 -0.0130977109 -0.0627977327 153 6.0800000000 0.0349767692 0.0287846452 0.0408546329 0.0130731193 0.0662710000 9636197 955859216 1767079936 0.2490011752 -0.0122164143 -0.0601741634 154 6.1200000000 0.0352502838 0.0288266299 0.0408546329 0.0130658912 0.0804680000 9637451 955859216 1767206912 0.2462105006 -0.0108057940 -0.0584431365 155 6.1600000000 0.0344064273 0.0288626286 0.0408546329 0.0130606955 0.0550140000 9638705 955859216 1766535168 0.2418533266 -0.0106823491 -0.0560857765 156 6.2000000000 0.0347687528 0.0289004883 0.0408546329 0.0130574870 0.0602860000 9639959 955859216 1765662720 0.2376066446 -0.0101515902 -0.0534004048 157 6.2400000000 0.0354345702 0.0289421067 0.0408546329 0.0130590382 0.0525170000 9641213 955859216 1765052416 0.2336549014 -0.0088006193 -0.0516086705 158 6.2800000000 0.0353148095 0.0289824403 0.0408546329 0.0130740571 0.0638860000 9642467 955859216 1766408192 0.2307812721 -0.0075173732 -0.0500638373 159 6.3200000000 0.0350060388 0.0290203245 0.0408546329 0.0130811492 0.0600610000 9643721 955859216 1765789696 0.2269601226 -0.0070548765 -0.0483457670 160 6.3600000000 0.0353431925 0.0290598424 0.0408546329 0.0130807770 0.0621950000 9644975 955859216 1765031936 0.2240648717 -0.0061562117 -0.0467543863 161 6.4000000000 0.0355035402 0.0290998654 0.0408546329 0.0130818384 0.0645710000 9646229 955859216 1766408192 0.2212908864 -0.0051322062 -0.0454348065 162 6.4400000000 0.0348433927 0.0291353193 0.0408546329 0.0130947398 0.0711290000 9647483 955859216 1766408192 0.2167937160 -0.0051094540 -0.0438748747 163 6.4800000000 0.0346176699 0.0291689533 0.0408546329 0.0130933932 0.0554640000 9648737 955859216 1766162432 0.2126593739 -0.0055326922 -0.0419755243 164 6.5200000000 0.0342394784 0.0291998712 0.0408546329 0.0130872804 0.0624760000 9649991 955859216 1765302272 0.2093892545 -0.0063728457 -0.0403353535 165 6.5600000000 0.0362903066 0.0292428435 0.0408546329 0.0130726740 0.0587490000 9651245 955859216 1765040128 0.2064358741 -0.0049614664 -0.0383645147 166 6.6000000000 0.0350701138 0.0292779475 0.0408546329 0.0130847636 0.0724390000 9652499 955859216 1765027840 0.2005596459 -0.0051061823 -0.0358639657 167 6.6400000000 0.0349456780 0.0293118861 0.0408546329 0.0131020223 0.0623920000 9653753 955859216 1766391808 0.1964536756 -0.0052128020 -0.0337705612 168 6.6800000000 0.0362211429 0.0293530126 0.0408546329 0.0131001303 0.0754780000 9655007 955859216 1765789696 0.1934810132 -0.0039550983 -0.0318843350 169 6.7200000000 0.0350230969 0.0293865634 0.0408546329 0.0131442012 0.0715050000 9656261 955859216 1765031936 0.1891376674 -0.0040340889 -0.0302572809 170 6.7600000000 0.0347060375 0.0294178544 0.0408546329 0.0131626980 0.0565010000 9657515 955859216 1765044224 0.1851859689 -0.0048009562 -0.0288569722 171 6.8000000000 0.0363511182 0.0294583998 0.0408546329 0.0131710093 0.0676100000 9658769 955859216 1765044224 0.1836905330 -0.0036190306 -0.0278940294 172 6.8400000000 0.0363503508 0.0294984693 0.0408546329 0.0131902640 0.0640460000 9660023 955859216 1766772736 0.1815565675 -0.0026420276 -0.0269135088 173 6.8800000000 0.0356580056 0.0295340735 0.0408546329 0.0132167302 0.0774980000 9661277 955859216 1766420480 0.1803902388 -0.0024874636 -0.0265991408 174 6.9200000000 0.0346653871 0.0295635639 0.0408546329 0.0132487705 0.0579040000 9662531 955859216 1765404672 0.1785937846 -0.0034371002 -0.0252424348 175 6.9600000000 0.0354616344 0.0295972671 0.0408546329 0.0132886227 0.0608920000 9663785 955859216 1765056512 0.1787364930 -0.0032569312 -0.0248459373 176 7.0000000000 0.0361096933 0.0296342695 0.0408546329 0.0132975071 0.0606600000 9665039 955859216 1765040128 0.1788982302 -0.0025017676 -0.0249023102 177 7.0400000000 0.0367751494 0.0296746135 0.0408546329 0.0133379630 0.0703990000 9666293 955859216 1766404096 0.1769520938 -0.0011067628 -0.0240169410 178 7.0800000000 0.0363194197 0.0297119439 0.0408546329 0.0133811801 0.0843650000 9667547 955859216 1766518784 0.1744843125 -0.0003569957 -0.0235680602 179 7.1200000000 0.0351026505 0.0297420595 0.0408546329 0.0134443863 0.0716620000 9668801 955859216 1766408192 0.1722307205 -0.0009012966 -0.0229739249 180 7.1600000000 0.0362113640 0.0297780001 0.0408546329 0.0134734193 0.0662700000 9670055 955859216 1765761024 0.1716843843 -0.0003336210 -0.0226653032 181 7.2000000000 0.0363046192 0.0298140588 0.0408546329 0.0134633806 0.0866060000 9671309 955859216 1765048320 0.1690521687 -0.0001635878 -0.0219923388 182 7.2400000000 0.0367755666 0.0298523088 0.0408546329 0.0134570379 0.0609580000 9672563 955859216 1765044224 0.1688200682 0.0005968050 -0.0220012795 183 7.2800000000 0.0369303599 0.0298909867 0.0408546329 0.0134428159 0.0876460000 9673817 955859216 1765044224 0.1645278931 0.0012037256 -0.0208193269 184 7.3200000000 0.0358571187 0.0299234113 0.0408546329 0.0134471718 0.0814900000 9675071 955859216 1765044224 0.1621303260 0.0008802908 -0.0205809120 185 7.3600000000 0.0364425816 0.0299586501 0.0408546329 0.0134342732 0.0624280000 9676325 955859216 1765044224 0.1575041711 0.0008297736 -0.0201522838 186 7.4000000000 0.0360316336 0.0299913005 0.0408546329 0.0134493728 0.0955900000 9677579 955859216 1765044224 0.1569998115 0.0008256946 -0.0196955744 187 7.4400000000 0.0353457779 0.0300199341 0.0408546329 0.0134684315 0.0685240000 9678833 955859216 1765044224 0.1542751938 -0.0002025204 -0.0195064638 188 7.4800000000 0.0354755148 0.0300489532 0.0408546329 0.0134841157 0.0852650000 9680087 955859216 1765044224 0.1514088511 -0.0011534641 -0.0185511988 189 7.5200000000 0.0365574807 0.0300833898 0.0408546329 0.0135165438 0.0646910000 9681341 955859216 1765027840 0.1495739222 -0.0007558513 -0.0177180078 190 7.5600000000 0.0356723443 0.0301128054 0.0408546329 0.0135722041 0.0683040000 9682595 955859216 1766391808 0.1464830488 -0.0015494054 -0.0170279201 191 7.6000000000 0.0370169394 0.0301489527 0.0408546329 0.0136086502 0.1053690000 9683849 955859216 1764753408 0.1456189007 -0.0006898601 -0.0167494379 192 7.6400000000 0.0366550758 0.0301828387 0.0408546329 0.0136315774 0.0698680000 9685103 955859216 1766150144 0.1428427249 -0.0006838504 -0.0164781753 193 7.6800000000 0.0368604176 0.0302174376 0.0408546329 0.0136653768 0.0625420000 9686357 955859216 1765502976 0.1415510625 -0.0001862116 -0.0159724001 194 7.7200000000 0.0362027138 0.0302482895 0.0408546329 0.0136710660 0.0655500000 9687611 955859216 1765044224 0.1389494538 -0.0011120398 -0.0162795018 195 7.7600000000 0.0373649225 0.0302847851 0.0408546329 0.0136659182 0.0624690000 9688865 955859216 1765044224 0.1400895417 -0.0000799226 -0.0161562674 196 7.8000000000 0.0369987935 0.0303190402 0.0408546329 0.0136527901 0.0712970000 9690119 955859216 1765044224 0.1364781708 -0.0002967288 -0.0162658710 197 7.8400000000 0.0343590342 0.0303395478 0.0408546329 0.0136716451 0.1050070000 9691373 955859216 1765044224 0.1389021277 0.0026311462 -0.0162223317 198 7.8800000000 0.0360405110 0.0303683405 0.0408546329 0.0136738091 0.0661350000 9692627 955859216 1766502400 0.1375794858 0.0016620612 -0.0160477050 199 7.9200000000 0.0343405977 0.0303883016 0.0408546329 0.0137027657 0.0686140000 9693881 955859216 1766264832 0.1415913254 0.0044304118 -0.0158434156 200 7.9600000000 0.0361301005 0.0304170106 0.0408546329 0.0137132500 0.0676660000 9695135 955859216 1765105664 0.1410780251 0.0040504020 -0.0157625042 201 8.0000000000 0.0362659767 0.0304461100 0.0408546329 0.0137291201 0.0613130000 9696389 955859216 1765044224 0.1430045217 0.0042899922 -0.0154564232 202 8.0400000000 0.0354187936 0.0304707272 0.0408546329 0.0137331708 0.0789050000 9697643 955859216 1765044224 0.1396152079 0.0042730346 -0.0154553149 203 8.0800000000 0.0353910923 0.0304949655 0.0408546329 0.0137165749 0.0666360000 9698897 955859216 1766408192 0.1358138174 0.0053849216 -0.0151405483 204 8.1200000000 0.0351686366 0.0305178756 0.0408546329 0.0136883907 0.0698160000 9700151 955859216 1765900288 0.1335998923 0.0075406898 -0.0145535506 205 8.1600000000 0.0337896980 0.0305338357 0.0408546329 0.0136653343 0.0626990000 9701405 955859216 1765031936 0.1308346987 0.0071563227 -0.0140124047 206 8.1999999990 0.0329950973 0.0305457836 0.0408546329 0.0136502137 0.0755780000 9702659 955859216 1765027840 0.1278688759 0.0054460149 -0.0125763016 207 8.2400000000 0.0337523930 0.0305612745 0.0408546329 0.0136439410 0.0681820000 9703913 955859216 1766391808 0.1259342730 0.0062009948 -0.0116752395 208 8.2799999990 0.0320483372 0.0305684238 0.0408546329 0.0136665415 0.0786480000 9705167 955859216 1765900288 0.1249909997 0.0049693850 -0.0099576171 209 8.3200000000 0.0331691317 0.0305808674 0.0408546329 0.0136769407 0.0845300000 9706421 955859216 1765031936 0.1236906201 0.0058615170 -0.0092985881 210 8.3599999990 0.0343200825 0.0305986732 0.0408546329 0.0136885123 0.0783050000 9707675 955859216 1765027840 0.1215974838 0.0083906511 -0.0086064022 211 8.4000000000 0.0337148458 0.0306134417 0.0408546329 0.0137240389 0.0717380000 9708929 955859216 1765027840 0.1193471476 0.0094821425 -0.0077757426 212 8.4399999990 0.0319279209 0.0306196421 0.0408546329 0.0137550015 0.0730160000 9710183 955859216 1765027840 0.1185884699 0.0081988173 -0.0058989078 213 8.4800000000 0.0333662145 0.0306325368 0.0408546329 0.0137634313 0.0729110000 9711437 955859216 1765027840 0.1158117652 0.0082824305 -0.0050129793 214 8.5200000000 0.0329410098 0.0306433241 0.0408546329 0.0137812592 0.0700660000 9712691 955859216 1765027840 0.1140881106 0.0085616298 -0.0035685638 215 8.5600000000 0.0322852917 0.0306509611 0.0408546329 0.0138158559 0.0757170000 9713945 955859216 1766391808 0.1123684794 0.0074778073 -0.0023423154 216 8.6000000000 0.0328216851 0.0306610108 0.0408546329 0.0138340720 0.1108730000 9715199 955859216 1765007360 0.1136799827 0.0107888617 -0.0000341367 217 8.6400000000 0.0326005332 0.0306699487 0.0408546329 0.0138368650 0.0841000000 9716453 955859216 1765019648 0.1137569249 0.0125770429 0.0013562589 218 8.6800000000 0.0314591974 0.0306735691 0.0408546329 0.0138490674 0.0707050000 9717707 955859216 1766502400 0.1151380762 0.0128583862 0.0035443138 219 8.7200000000 0.0309758503 0.0306749494 0.0408546329 0.0138770725 0.0695760000 9718961 955859216 1765773312 0.1167905182 0.0125595927 0.0069969343 220 8.7600000000 0.0307022501 0.0306750735 0.0408546329 0.0138909114 0.0773620000 9720215 955859216 1765015552 0.1174218729 0.0108813029 0.0103711095 221 8.8000000000 0.0311193950 0.0306770840 0.0408546329 0.0139167864 0.0926660000 9721469 955859216 1765027840 0.1186900586 0.0108839022 0.0126830656 222 8.8400000000 0.0319292694 0.0306827244 0.0408546329 0.0139438935 0.0688960000 9722723 955859216 1765027840 0.1182822511 0.0122151347 0.0144152800 223 8.8800000000 0.0315094441 0.0306864317 0.0408546329 0.0139835300 0.0787380000 9723977 955859216 1765027840 0.1172684878 0.0115135191 0.0164195690 224 8.9200000000 0.0319347940 0.0306920048 0.0408546329 0.0140014636 0.1028260000 9725231 955859216 1765027840 0.1143524498 0.0109042823 0.0175097696 225 8.9600000000 0.0311418958 0.0306940043 0.0408546329 0.0141444391 0.1150880000 9726485 955859216 1765027840 0.0727536231 0.0061184708 0.0028962791 226 9.0000000000 0.0330444314 0.0307044044 0.0408546329 0.0141475334 0.0699310000 9727739 955859216 1765027840 0.0682219341 0.0074652662 0.0020510396 227 9.0400000000 0.0324983522 0.0307123072 0.0408546329 0.0141552511 0.0798910000 9728993 955859216 1765027840 0.0646736771 0.0067762071 0.0025978815 228 9.0800000000 0.0327668563 0.0307213184 0.0408546329 0.0141629423 0.0716790000 9730247 955859216 1765027840 0.0610796176 0.0065976689 0.0027463420 229 9.1200000000 0.0327948332 0.0307303731 0.0408546329 0.0141691953 0.0870690000 9731501 955859216 1765027840 0.0569171272 0.0061355899 0.0024978367 230 9.1600000000 0.0330691598 0.0307405417 0.0408546329 0.0141786384 0.1075990000 9732755 955859216 1765027840 0.0524318069 0.0062433430 0.0025427497 231 9.2000000000 0.0329615884 0.0307501566 0.0408546329 0.0141839376 0.0870790000 9734009 955859216 1765027840 0.0485030413 0.0059291511 0.0020080525 232 9.2400000000 0.0329289362 0.0307595479 0.0408546329 0.0141901042 0.0905830000 9735263 955859216 1765011456 0.0448182821 0.0053075044 0.0023640089 233 9.2800000000 0.0331943892 0.0307699979 0.0408546329 0.0142023025 0.1109170000 9736517 955859216 1765011456 0.0419250354 0.0059491829 0.0015475492 234 9.3200000000 0.0332046710 0.0307804025 0.0408546329 0.0142059086 0.0860510000 9737771 955859216 1765130240 0.0380797982 0.0060559646 0.0008277874 235 9.3600000000 0.0330115147 0.0307898966 0.0408546329 0.0142261681 0.0893070000 9739025 955859216 1765036032 0.0352196544 0.0055055143 0.0007496168 236 9.4000000000 0.0329149477 0.0307989010 0.0408546329 0.0142640409 0.0796130000 9740279 955859216 1766400000 0.0325469673 0.0044983071 0.0004649637 237 9.4400000000 0.0326163135 0.0308065694 0.0408546329 0.0142952214 0.0837630000 9741533 955859216 1766400000 0.0297360327 0.0020267351 0.0000735084 238 9.4800000000 0.0323743559 0.0308131568 0.0408546329 0.0143208749 0.0799660000 9742787 955859216 1766273024 0.0263550505 -0.0016770657 -0.0001661871 239 9.5200000000 0.0330807716 0.0308226447 0.0408546329 0.0143331865 0.0836260000 9744041 955859216 1765613568 0.0238535460 -0.0020895782 -0.0006136801 240 9.5600000000 0.0320799798 0.0308278836 0.0408546329 0.0144873705 0.1103900000 9745295 955859216 1764478976 0.0211368557 -0.0072206496 0.0005456056 241 9.6000000000 0.0330266692 0.0308370072 0.0408546329 0.0144848428 0.0881090000 9746549 955859216 1764503552 0.0185551066 -0.0081694890 -0.0003490546 242 9.6400000000 0.0327036642 0.0308447206 0.0408546329 0.0144989377 0.0884530000 9747803 955859216 1764495360 0.0171701293 -0.0102432128 0.0001666369 243 9.6800000000 0.0326161124 0.0308520103 0.0408546329 0.0145145993 0.1101780000 9749057 955859216 1764622336 0.0153778465 -0.0127782756 -0.0001005018 244 9.7200000000 0.0329207219 0.0308604886 0.0408546329 0.0145241006 0.0878690000 9750311 955859216 1764876288 0.0137717649 -0.0137740914 0.0002694107 245 9.7600000000 0.0332578644 0.0308702739 0.0408546329 0.0145224425 0.0889160000 9751565 955859216 1765003264 0.0119514233 -0.0133132879 0.0000261907 246 9.8000000000 0.0329327583 0.0308786579 0.0408546329 0.0145270514 0.1101720000 9752819 955859216 1765130240 0.0100847986 -0.0143221654 0.0000290377 247 9.8400000000 0.0330596641 0.0308874879 0.0408546329 0.0145335717 0.0882890000 9754073 955859216 1765036032 0.0071557648 -0.0149154570 -0.0008237718 248 9.8800000000 0.0326441787 0.0308945713 0.0408546329 0.0145315070 0.0834770000 9755327 955859216 1765019648 0.0039740889 -0.0178184491 -0.0012225274 249 9.9200000000 0.0326136239 0.0309014752 0.0408546329 0.0145335150 0.1202130000 9756581 955859216 1765019648 0.0001708609 -0.0208457373 -0.0029914232 250 9.9600000000 0.0330969803 0.0309102572 0.0408546329 0.0145265697 0.0791720000 9757835 955859216 1765130240 -0.0027860140 -0.0213092305 -0.0037657095 251 10.0000000000 0.0328189582 0.0309178616 0.0408546329 0.0145277889 0.0892530000 9759089 955859216 1765036032 -0.0059798867 -0.0233844239 -0.0047856225 252 10.0400000000 0.0328753553 0.0309256294 0.0408546329 0.0145339672 0.0785560000 9760343 955859216 1766400000 -0.0094461646 -0.0255110189 -0.0061039398 253 10.0800000000 0.0329707824 0.0309337130 0.0408546329 0.0145312016 0.0817950000 9761597 955859216 1766400000 -0.0123441825 -0.0262383763 -0.0070074322 254 10.1200000000 0.0324400999 0.0309396437 0.0408546329 0.0145294098 0.1092030000 9762851 955859216 1764761600 -0.0149956718 -0.0275487620 -0.0074625215 255 10.1600000000 0.0322657637 0.0309448441 0.0408546329 0.0145235863 0.0854510000 9764105 955859216 1764761600 -0.0177132878 -0.0284077078 -0.0086330036 256 10.2000000000 0.0324626751 0.0309507732 0.0408546329 0.0145224939 0.0816750000 9765359 955859216 1764761600 -0.0201505907 -0.0297734104 -0.0090703499 257 10.2400000000 0.0323616154 0.0309562628 0.0408546329 0.0146315422 0.1093730000 9787093 955859216 1764761600 -0.0242770445 -0.0331976861 -0.0101097757 258 10.2800000000 0.0325746723 0.0309625357 0.0408546329 0.0146344090 0.0962390000 9830331 955859216 1765003264 -0.0271000639 -0.0343449339 -0.0115967896 259 10.3200000000 0.0326223485 0.0309689443 0.0408546329 0.0146259290 0.0822940000 9831585 955859216 1765130240 -0.0291801598 -0.0355266407 -0.0125329727 260 10.3600000000 0.0324966684 0.0309748201 0.0408546329 0.0146151931 0.0828240000 9832839 955859216 1765036032 -0.0311247911 -0.0371876098 -0.0132841095 261 10.4000000000 0.0325058140 0.0309806860 0.0408546329 0.0145971173 0.1095200000 9834093 955859216 1765003264 -0.0329796635 -0.0384606197 -0.0142719727 262 10.4400000000 0.0323605686 0.0309859528 0.0408546329 0.0145792195 0.0900660000 9835347 955859216 1765003264 -0.0351135395 -0.0400305726 -0.0151914814 263 10.4800000000 0.0323465429 0.0309911261 0.0408546329 0.0145617600 0.0856440000 9836601 955859216 1765130240 -0.0372313559 -0.0411911085 -0.0163067896 264 10.5200000000 0.0323254466 0.0309961803 0.0408546329 0.0145457755 0.0829790000 9837855 955859216 1766621184 -0.0389579646 -0.0424698889 -0.0167724732 265 10.5600000000 0.0322376974 0.0310008653 0.0408546329 0.0145310535 0.1092330000 9839109 955859216 1765019648 -0.0417598747 -0.0443590842 -0.0190028325 266 10.6000000000 0.0322329067 0.0310054970 0.0408546329 0.0145223772 0.0882690000 9840363 955859216 1765019648 -0.0445416011 -0.0464477390 -0.0206106585 267 10.6400000000 0.0325014554 0.0310110999 0.0408546329 0.0145246564 0.0889330000 9841617 955859216 1765130240 -0.0469246991 -0.0475096256 -0.0220938325 268 10.6800000000 0.0323817879 0.0310162144 0.0408546329 0.0145309101 0.1099390000 9842871 955859216 1765036032 -0.0494294353 -0.0491404571 -0.0237720739 269 10.7200000000 0.0323725268 0.0310212564 0.0408546329 0.0145426440 0.0880570000 9844125 955859216 1765036032 -0.0517910644 -0.0510294735 -0.0253661349 270 10.7600000000 0.0323853046 0.0310263085 0.0408546329 0.0145488078 0.0895550000 9845379 955859216 1765003264 -0.0544211231 -0.0528095588 -0.0278195739 271 10.8000000000 0.0324094109 0.0310314122 0.0408546329 0.0145540201 0.1084100000 9846633 955859216 1765130240 -0.0567995794 -0.0546723828 -0.0295850113 272 10.8400000000 0.0324860662 0.0310367602 0.0408546329 0.0145710821 0.1065700000 9847887 955859216 1765036032 -0.0591769405 -0.0564433634 -0.0316046216 273 10.8800000000 0.0325177573 0.0310421851 0.0408546329 0.0145872573 0.0888270000 9849141 955859216 1765019648 -0.0617428347 -0.0583073199 -0.0338571072 274 10.9200000000 0.0326068550 0.0310478955 0.0408546329 0.0145979191 0.0879510000 9850395 955859216 1765019648 -0.0637150630 -0.0599426404 -0.0353263207 275 10.9600000000 0.0325331539 0.0310532965 0.0408546329 0.0146065121 0.0707170000 9851649 955859216 1766494208 -0.0658158287 -0.0619183145 -0.0369960777 276 11.0000000000 0.0328656696 0.0310598631 0.0408546329 0.0146061825 0.0820910000 9852903 955859216 1765765120 -0.0677407235 -0.0628011301 -0.0388106592 277 11.0400000000 0.0317552760 0.0310623736 0.0408546329 0.0149351523 0.0838130000 9854157 955859216 1765027840 -0.0757986754 -0.0690480545 -0.0456535295 278 11.0800000000 0.0324585699 0.0310673959 0.0408546329 0.0149275770 0.0808970000 9855411 955859216 1764986880 -0.0775970519 -0.0718946159 -0.0473905914 279 11.1200000000 0.0326867998 0.0310732002 0.0408546329 0.0149144262 0.1049800000 9856665 955859216 1765019648 -0.0790885016 -0.0745519623 -0.0482796878 280 11.1600000000 0.0331456102 0.0310806016 0.0408546329 0.0149056118 0.0712510000 9857919 955859216 1766367232 -0.0801817402 -0.0759916306 -0.0489455760 281 11.2000000000 0.0330780074 0.0310877098 0.0408546329 0.0149043577 0.0829180000 9859173 955859216 1768398848 -0.0814117491 -0.0781654939 -0.0498976745 282 11.2400000000 0.0335146710 0.0310963161 0.0408546329 0.0149026323 0.1058510000 9860427 955859216 1770049536 -0.0826848000 -0.0794522390 -0.0512657985 283 11.2800000000 0.0333507881 0.0311042824 0.0408546329 0.0148953649 0.0713270000 9861681 955859216 1771700224 -0.0836646184 -0.0815621316 -0.0520823300 284 11.3200000000 0.0336637087 0.0311132945 0.0408546329 0.0149015348 0.0815060000 9862935 955859216 1773477888 -0.0848151073 -0.0832364783 -0.0531569943 285 11.3600000000 0.0336738713 0.0311222790 0.0408546329 0.0148980551 0.1027770000 9864189 955859216 1775128576 -0.0858968422 -0.0851483196 -0.0543348044 286 11.4000000000 0.0336550400 0.0311311348 0.0408546329 0.0148863956 0.0717860000 9865443 955859216 1776906240 -0.0867514908 -0.0874798894 -0.0552391559 287 11.4400000000 0.0339749977 0.0311410437 0.0408546329 0.0148702118 0.0811920000 9866697 955859216 1778556928 -0.0874577910 -0.0892915502 -0.0559881479 288 11.4800000000 0.0339142196 0.0311506728 0.0408546329 0.0148495023 0.0924250000 9867951 955859216 1780207616 -0.0885014459 -0.0914549902 -0.0572373159 289 11.5200000000 0.0340135284 0.0311605789 0.0408546329 0.0148347239 0.0784450000 9869205 955859216 1781985280 -0.0889215022 -0.0939247757 -0.0578163937 290 11.5600000000 0.0346079394 0.0311724663 0.0408546329 0.0148201306 0.0724220000 9870459 955859216 1783635968 -0.0895154253 -0.0955149382 -0.0584657043 291 11.6000000000 0.0346177258 0.0311843057 0.0408546329 0.0147979974 0.0783040000 9871713 955859216 1785278464 -0.0898809507 -0.0972694382 -0.0587908067 292 11.6400000000 0.0344814323 0.0311955972 0.0408546329 0.0147733682 0.0729600000 9872967 955859216 1787072512 -0.0906255767 -0.0992574543 -0.0600073412 293 11.6800000000 0.0346100368 0.0312072506 0.0408546329 0.0147481032 0.0855090000 9874221 955859216 1786187776 -0.0909231305 -0.1012580842 -0.0603713468 294 11.7200000000 0.0350284763 0.0312202480 0.0408546329 0.0147242604 0.0823100000 9875475 955859216 1785421824 -0.0911046043 -0.1027024612 -0.0611002110 295 11.7600000000 0.0340379141 0.0312297994 0.0408546329 0.0147070657 0.0812460000 9876729 955859216 1783672832 -0.0912011564 -0.1065454334 -0.0611985587 296 11.8000000000 0.0345576070 0.0312410420 0.0408546329 0.0146874004 0.1112850000 9877983 955859216 1782788096 -0.0911982059 -0.1092364341 -0.0614718460 297 11.8400000000 0.0352707431 0.0312546100 0.0408546329 0.0146733483 0.0834260000 9879237 955859216 1784152064 -0.0915490612 -0.1109396070 -0.0623388737 298 11.8800000000 0.0348879136 0.0312668023 0.0408546329 0.0147068647 0.0714250000 9880491 955859216 1786040320 -0.0925419033 -0.1142521948 -0.0641902164 299 11.9200000000 0.0354072861 0.0312806500 0.0408546329 0.0147097818 0.0812610000 9881745 955859216 1787691008 -0.0933312103 -0.1163897812 -0.0655194670 300 11.9600000000 0.0355920903 0.0312950215 0.0408546329 0.0147225516 0.0859050000 9882999 955859216 1786699776 -0.0936904624 -0.1184376553 -0.0661211088 301 12.0000000000 0.0356883965 0.0313096174 0.0408546329 0.0147284466 0.1087610000 9884253 955859216 1783767040 -0.0943710431 -0.1204466373 -0.0672455356 302 12.0400000000 0.0356107131 0.0313238595 0.0408546329 0.0147644844 0.1006820000 9885507 955859216 1782771712 -0.0962327719 -0.1235211045 -0.0703504160 303 12.0800000000 0.0359415598 0.0313390994 0.0408546329 0.0147500136 0.0785770000 9886761 955859216 1781645312 -0.0976650640 -0.1255474240 -0.0724460483 304 12.1200000000 0.0360849053 0.0313547106 0.0408546329 0.0147377360 0.1063070000 9888015 955859216 1780613120 -0.0991341472 -0.1275343001 -0.0748956725 305 12.1600000000 0.0364915021 0.0313715526 0.0408546329 0.0147308025 0.1099070000 9889269 955859216 1779486720 -0.1004023105 -0.1290644705 -0.0768749639 306 12.2000000000 0.0363221094 0.0313877309 0.0408546329 0.0147312723 0.0793190000 9890523 955859216 1778454528 -0.1012104824 -0.1310543716 -0.0784729421 307 12.2400000000 0.0365847908 0.0314046594 0.0408546329 0.0147440758 0.0801850000 9891777 955859216 1779834880 -0.1025140509 -0.1330000013 -0.0805129185 308 12.2800000000 0.0368259326 0.0314222609 0.0408546329 0.0147602723 0.0702720000 9893031 955859216 1779068928 -0.1040459201 -0.1348244399 -0.0830727667 309 12.3200000000 0.0368351080 0.0314397782 0.0408546329 0.0147591181 0.0697490000 9894285 955859216 1777836032 -0.1056903824 -0.1365747899 -0.0860662833 310 12.3600000000 0.0369671062 0.0314576083 0.0408546329 0.0147591168 0.0790800000 9895539 955859216 1776771072 -0.1073325872 -0.1383032352 -0.0891593173 311 12.4000000000 0.0372217037 0.0314761424 0.0408546329 0.0147587438 0.0715320000 9896793 955859216 1775677440 -0.1086161360 -0.1396729052 -0.0919948071 312 12.4400000000 0.0373100936 0.0314948409 0.0408546329 0.0147518109 0.0884900000 9898047 955859216 1775382528 -0.1098966375 -0.1408779323 -0.0946857482 313 12.4800000000 0.0373263694 0.0315134720 0.0408546329 0.0147437030 0.0745210000 9899301 955859216 1775644672 -0.1111749709 -0.1422705501 -0.0971619785 314 12.5200000000 0.0373971201 0.0315322098 0.0408546329 0.0147423058 0.0708010000 9900555 955859216 1773985792 -0.1122135818 -0.1436420530 -0.0993556231 315 12.5600000000 0.0376004390 0.0315514740 0.0408546329 0.0147444858 0.0687970000 9901809 955859216 1772744704 -0.1135619208 -0.1447667927 -0.1018711776 316 12.6000000000 0.0376010127 0.0315706181 0.0408546329 0.0147424425 0.0677280000 9903063 955859216 1771724800 -0.1148271635 -0.1459109187 -0.1043975353 317 12.6400000000 0.0377583615 0.0315901378 0.0408546329 0.0147319558 0.0716490000 9904317 955859216 1770598400 -0.1160673425 -0.1468473822 -0.1069967896 318 12.6800000000 0.0378096327 0.0316096959 0.0408546329 0.0147175270 0.0767490000 9905571 955859216 1771962368 -0.1173543334 -0.1476866156 -0.1094451249 319 12.7200000000 0.0379078127 0.0316294393 0.0408546329 0.0147334733 0.0911110000 9906825 955859216 1769312256 -0.1193907410 -0.1491113901 -0.1140704602 320 12.7600000000 0.0378713943 0.0316489454 0.0408546329 0.0147225629 0.0790670000 9908079 955859216 1770692608 -0.1204826981 -0.1499669552 -0.1162444279 321 12.8000000000 0.0381362475 0.0316691550 0.0408546329 0.0147105802 0.0761760000 9909333 955859216 1769914368 -0.1217612699 -0.1504373699 -0.1186081246 322 12.8400000000 0.0380795524 0.0316890631 0.0408546329 0.0146965880 0.1112250000 9910587 955859216 1768448000 -0.1231229231 -0.1510503888 -0.1207290664 323 12.8800000000 0.0382606573 0.0317094086 0.0408546329 0.0146828331 0.0896700000 9911841 955859216 1767407616 -0.1241626292 -0.1515109986 -0.1224019229 324 12.9200000000 0.0385674126 0.0317305753 0.0408546329 0.0146695076 0.1088940000 9913095 955859216 1766391808 -0.1254547238 -0.1517140865 -0.1245271116 325 12.9600000000 0.0387022570 0.0317520266 0.0408546329 0.0146498283 0.0780150000 9914349 955859216 1767772160 -0.1266628355 -0.1515752077 -0.1264664233 326 13.0000000000 0.0386930406 0.0317733181 0.0408546329 0.0146302697 0.0696380000 9915603 955859216 1766756352 -0.1280645281 -0.1514336765 -0.1285736561 327 13.0400000000 0.0391085595 0.0317957500 0.0408546329 0.0146106330 0.0685930000 9916857 955859216 1766264832 -0.1293494105 -0.1506766379 -0.1302856356 328 13.0800000000 0.0393536985 0.0318187925 0.0408546329 0.0145904982 0.0633800000 9918111 955859216 1765146624 -0.1307272464 -0.1497802138 -0.1322738528 329 13.1200000000 0.0397673622 0.0318429523 0.0408546329 0.0145729134 0.0746220000 9919365 955859216 1765036032 -0.1319586486 -0.1484379619 -0.1339004636 330 13.1600000000 0.0399734154 0.0318675901 0.0408546329 0.0145556657 0.0761410000 9920619 955859216 1766400000 -0.1332685798 -0.1468431503 -0.1354119778 331 13.2000000000 0.0401652083 0.0318926584 0.0408546329 0.0145401109 0.0694810000 9921873 955859216 1766400000 -0.1344500929 -0.1449746788 -0.1370127499 332 13.2400000000 0.0404002629 0.0319182837 0.0408546329 0.0145230926 0.0703440000 9923127 955859216 1766113280 -0.1356925368 -0.1428065002 -0.1381574273 333 13.2800000000 0.0405539125 0.0319442165 0.0408546329 0.0145106946 0.0629630000 9924381 955859216 1765130240 -0.1369893402 -0.1403671950 -0.1396478862 334 13.3200000000 0.0419400223 0.0319741441 0.0419400223 0.0145355179 0.0860940000 9925635 955859216 1765036032 -0.1391936541 -0.1362009048 -0.1418443620 335 13.3600000000 0.0411947630 0.0320016683 0.0419400223 0.0145235140 0.1099740000 9926889 955859216 1765036032 -0.1401685774 -0.1325311363 -0.1426427662 336 13.4000000000 0.0406860597 0.0320275147 0.0419400223 0.0145119616 0.0890100000 9928143 955859216 1765036032 -0.1412069499 -0.1291230917 -0.1433381736 337 13.4400000000 0.0396657363 0.0320501801 0.0419400223 0.0145011175 0.0670430000 9929397 955859216 1765130240 -0.1421383321 -0.1256205887 -0.1439243257 338 13.4800000000 0.0388425216 0.0320702758 0.0419400223 0.0145025203 0.0931830000 9930651 955859216 1765036032 -0.1429544091 -0.1226174980 -0.1444121003 339 13.5200000000 0.0384201780 0.0320890070 0.0419400223 0.0145134219 0.0821620000 9931905 955859216 1766383616 -0.1440202743 -0.1195705757 -0.1448870152 340 13.5600000000 0.0379792787 0.0321063314 0.0419400223 0.0145151569 0.0681850000 9933159 955859216 1766383616 -0.1448340565 -0.1168388948 -0.1447869390 341 13.6000000000 0.0376852304 0.0321226918 0.0419400223 0.0145109592 0.1095290000 9934413 955859216 1765765120 -0.1456449181 -0.1139221564 -0.1448664218 342 13.6400000000 0.0375468880 0.0321385520 0.0419400223 0.0145051728 0.1080420000 9935667 955859216 1765122048 -0.1468544751 -0.1107729971 -0.1454615742 343 13.6800000000 0.0371517912 0.0321531679 0.0419400223 0.0145135143 0.0907330000 9936921 955859216 1765130240 -0.1477716416 -0.1080401242 -0.1455975175 344 13.7200000000 0.0369844921 0.0321672124 0.0419400223 0.0145264784 0.0679640000 9938175 955859216 1766494208 -0.1485115141 -0.1050846279 -0.1457723826 345 13.7600000000 0.0370560251 0.0321813829 0.0419400223 0.0146778271 0.0786540000 9939429 955859216 1766019072 -0.1501362175 -0.0995622128 -0.1458279192 346 13.8000000000 0.0380376838 0.0321983086 0.0419400223 0.0146788813 0.1127810000 9940683 955859216 1765003264 -0.1507901400 -0.0981363356 -0.1457368135 347 13.8400000000 0.0360818245 0.0322095003 0.0419400223 0.0146888158 0.0832120000 9941937 955859216 1766383616 -0.1516654938 -0.0935360044 -0.1462479383 348 13.8800000000 0.0366947316 0.0322223889 0.0419400223 0.0146738627 0.0782720000 9943191 955859216 1768271872 -0.1525119841 -0.0911808535 -0.1463851929 349 13.9200000000 0.0361887924 0.0322337539 0.0419400223 0.0146536541 0.0728860000 9944445 955859216 1769922560 -0.1533078700 -0.0870686173 -0.1465916336 350 13.9600000000 0.0366914161 0.0322464901 0.0419400223 0.0146372607 0.0813260000 9945699 955859216 1771573248 -0.1541138589 -0.0850480497 -0.1467887908 351 14.0000000000 0.0359643139 0.0322570822 0.0419400223 0.0146369598 0.1134470000 9946953 955859216 1773350912 -0.1548053771 -0.0810091421 -0.1467455924 352 14.0400000000 0.0365941375 0.0322694034 0.0419400223 0.0146318759 0.0867750000 9948207 955859216 1775001600 -0.1555569023 -0.0786816701 -0.1466922909 353 14.0800000000 0.0357940942 0.0322793883 0.0419400223 0.0146446202 0.0815020000 9949461 955859216 1776644096 -0.1561997533 -0.0743939131 -0.1463488042 354 14.1200000000 0.0364401713 0.0322911420 0.0419400223 0.0146683859 0.0714300000 9950715 955859216 1778421760 -0.1567302942 -0.0719925836 -0.1460561603 355 14.1600000000 0.0363909155 0.0323026906 0.0419400223 0.0146908600 0.0890390000 9951969 955859216 1780072448 -0.1572431922 -0.0690348223 -0.1456384361 356 14.2000000000 0.0357653648 0.0323124172 0.0419400223 0.0147021979 0.0860910000 9953223 955859216 1781850112 -0.1577277333 -0.0649957359 -0.1454419792 357 14.2400000000 0.0364084058 0.0323238906 0.0419400223 0.0147034109 0.0711690000 9954477 955859216 1783500800 -0.1582183838 -0.0627145246 -0.1449929178 358 14.2800000000 0.0362552553 0.0323348721 0.0419400223 0.0147080668 0.0856930000 9955731 955859216 1785151488 -0.1586518735 -0.0600228198 -0.1443132013 359 14.3200000000 0.0356156752 0.0323440108 0.0419400223 0.0147167058 0.0898010000 9956985 955859216 1786929152 -0.1588918716 -0.0563433096 -0.1435736716 360 14.3600000000 0.0360889509 0.0323544134 0.0419400223 0.0147164211 0.0802320000 9958239 955859216 1786060800 -0.1591453999 -0.0538991392 -0.1431885660 361 14.4000000000 0.0354541540 0.0323629999 0.0419400223 0.0147141100 0.1050420000 9959493 955859216 1785085952 -0.1592123508 -0.0503822006 -0.1421649754 362 14.4400000000 0.0357069150 0.0323722373 0.0419400223 0.0147175240 0.1099470000 9960747 955859216 1786421248 -0.1593471766 -0.0481285974 -0.1415300220 363 14.4800000000 0.0356337987 0.0323812223 0.0419400223 0.0147197114 0.0673080000 9962001 955859216 1785720832 -0.1593259722 -0.0461046174 -0.1407483667 364 14.5200000000 0.0357091688 0.0323903650 0.0419400223 0.0147226514 0.0781400000 9963255 955859216 1784688640 -0.1594174206 -0.0433376133 -0.1401281059 365 14.5600000000 0.0355775282 0.0323990970 0.0419400223 0.0147287503 0.1095320000 9964509 955859216 1783549952 -0.1593498141 -0.0413519442 -0.1393304169 366 14.6000000000 0.0352673978 0.0324069338 0.0419400223 0.0148225263 0.0887440000 9965763 955859216 1782407168 -0.1584729403 -0.0347977355 -0.1372635961 367 14.6400000000 0.0354554020 0.0324152403 0.0419400223 0.0148355686 0.0802130000 9967017 955859216 1781374976 -0.1581597328 -0.0321751311 -0.1365452409 368 14.6800000000 0.0354898758 0.0324235953 0.0419400223 0.0148465546 0.0980480000 9968271 955859216 1780359168 -0.1573399603 -0.0293935463 -0.1348761171 369 14.7200000000 0.0350721851 0.0324307730 0.0419400223 0.0148695058 0.1204770000 9969525 955859216 1779232768 -0.1555623710 -0.0216983128 -0.1317774951 370 14.7600000000 0.0355913527 0.0324393151 0.0419400223 0.0148751015 0.0704950000 9970779 955859216 1780596736 -0.1543776542 -0.0191254076 -0.1297307909 371 14.8000000000 0.0357909538 0.0324483492 0.0419400223 0.0148767576 0.0796720000 9972033 955859216 1782358016 -0.1531423032 -0.0168639664 -0.1275381148 372 14.8400000000 0.0358550735 0.0324575071 0.0419400223 0.0148756692 0.0917870000 9973287 955859216 1784135680 -0.1520265788 -0.0148135796 -0.1250893921 373 14.8800000000 0.0360472314 0.0324671310 0.0419400223 0.0148711217 0.0694990000 9974541 955859216 1785786368 -0.1505659670 -0.0120608471 -0.1224113926 374 14.9200000000 0.0347203501 0.0324731556 0.0419400223 0.0148644133 0.0864110000 9975795 955859216 1787437056 -0.1487337947 -0.0073204520 -0.1195030585 375 14.9600000000 0.0357729346 0.0324819551 0.0419400223 0.0148590970 0.0894860000 9977049 955859216 1786572800 -0.1474857777 -0.0057410682 -0.1171532422 376 15.0000000000 0.0358258858 0.0324908485 0.0419400223 0.0148677509 0.0780160000 9978303 955859216 1784786944 -0.1459015012 -0.0034928340 -0.1145857945 377 15.0400000000 0.0358429886 0.0324997401 0.0419400223 0.0148890772 0.0858420000 9979557 955859216 1783672832 -0.1440089196 -0.0012301030 -0.1119636893 378 15.0800000000 0.0359558947 0.0325088834 0.0419400223 0.0149014937 0.1081350000 9980811 955859216 1782136832 -0.1420974731 0.0015185899 -0.1097913086 379 15.1200000000 0.0358860120 0.0325177940 0.0419400223 0.0148988676 0.1084620000 9982065 955859216 1783517184 -0.1399439573 0.0040715346 -0.1073519588 380 15.1600000000 0.0355241895 0.0325257056 0.0419400223 0.0149063148 0.1071650000 9983319 955859216 1785405440 -0.1378038526 0.0064022997 -0.1048645899 381 15.2000000000 0.0351678506 0.0325326403 0.0419400223 0.0149126111 0.0873450000 9984573 955859216 1787056128 -0.1357789338 0.0084463041 -0.1029030383 382 15.2400000000 0.0350063071 0.0325391159 0.0419400223 0.0149095605 0.0830740000 9985827 955859216 1786077184 -0.1336153597 0.0102110179 -0.1007529423 383 15.2800000000 0.0349713229 0.0325454663 0.0419400223 0.0149067067 0.0840260000 9987081 955859216 1785294848 -0.1315978020 0.0118550714 -0.0987560377 384 15.3200000000 0.0347947069 0.0325513237 0.0419400223 0.0149260125 0.1091400000 9988335 955859216 1783541760 -0.1295031607 0.0133031458 -0.0967048556 385 15.3600000000 0.0346090943 0.0325566686 0.0419400223 0.0149304158 0.1125940000 9989589 955859216 1782771712 -0.1270651519 0.0140361497 -0.0945646763 386 15.4000000000 0.0348854475 0.0325627017 0.0419400223 0.0149313063 0.0853920000 9990843 955859216 1782140928 -0.1248081326 0.0158560220 -0.0926647335 387 15.4400000000 0.0346777290 0.0325681669 0.0419400223 0.0149331254 0.0837470000 9992097 955859216 1781633024 -0.1221119314 0.0168663301 -0.0900315568 388 15.4800000000 0.0345770307 0.0325733443 0.0419400223 0.0149436247 0.1120850000 9993351 955859216 1781018624 -0.1192200705 0.0176965408 -0.0875372589 389 15.5200000000 0.0347347520 0.0325789007 0.0419400223 0.0149485108 0.0874200000 9994605 955859216 1780125696 -0.1169399172 0.0191585366 -0.0857192203 390 15.5600000000 0.0345481262 0.0325839500 0.0419400223 0.0149422831 0.0853000000 9995859 955859216 1779236864 -0.1139513478 0.0195897464 -0.0826161280 391 15.6000000000 0.0345622934 0.0325890097 0.0419400223 0.0149412628 0.1097380000 9997113 955859216 1778221056 -0.1115372330 0.0202918276 -0.0803782940 392 15.6400000000 0.0343722776 0.0325935588 0.0419400223 0.0149417581 0.0847260000 9998367 955859216 1777184768 -0.1085043922 0.0202406030 -0.0776470229 393 15.6800000000 0.0344003700 0.0325981563 0.0419400223 0.0149413737 0.0848780000 9999621 955859216 1778565120 -0.1059505790 0.0206598099 -0.0755412877 394 15.7200000000 0.0345811173 0.0326031892 0.0419400223 0.0149462785 0.1100910000 10000875 955859216 1775312896 -0.1031532735 0.0218848400 -0.0736429542 395 15.7600000000 0.0343410745 0.0326075889 0.0419400223 0.0149519546 0.0906570000 10002129 955859216 1774264320 -0.1004065052 0.0221266020 -0.0717181191 396 15.8000000000 0.0344605781 0.0326122682 0.0419400223 0.0149468056 0.0855770000 10003383 955859216 1773137920 -0.0974248052 0.0228143092 -0.0699786618 397 15.8400000000 0.0346138850 0.0326173100 0.0419400223 0.0149383792 0.0827940000 10004637 955859216 1774501888 -0.0941269994 0.0241391808 -0.0676518008 398 15.8800000000 0.0345520638 0.0326221712 0.0419400223 0.0149333994 0.0864930000 10005891 955859216 1773752320 -0.0925271660 0.0249454267 -0.0676959977 399 15.9200000000 0.0346025191 0.0326271345 0.0419400223 0.0149292828 0.1099350000 10007145 955859216 1770446848 -0.0893339068 0.0257602092 -0.0656969771 400 15.9600000000 0.0343482010 0.0326314372 0.0419400223 0.0149247241 0.0884240000 10008399 955859216 1769451520 -0.0874525979 0.0252920277 -0.0649129152 401 16.0000000000 0.0343914889 0.0326358263 0.0419400223 0.0149131200 0.0838390000 10009653 955859216 1770819584 -0.0855187923 0.0246080961 -0.0635475516 402 16.0400000000 0.0345525369 0.0326405943 0.0419400223 0.0149058590 0.0874450000 10010907 955859216 1770180608 -0.0834638551 0.0246701092 -0.0623782650 403 16.0800000000 0.0341202505 0.0326442659 0.0419400223 0.0149057809 0.1096680000 10012161 955859216 1766780928 -0.0818682089 0.0233960617 -0.0615327805 404 16.1200000000 0.0344059318 0.0326486264 0.0419400223 0.0149134250 0.0879590000 10013415 955859216 1765756928 -0.0800710469 0.0231424458 -0.0608753711 405 16.1600000000 0.0347325504 0.0326537719 0.0419400223 0.0149164574 0.0861470000 10014669 955859216 1764999168 -0.0777008533 0.0241915863 -0.0599798448 406 16.2000000000 0.0345381908 0.0326584133 0.0419400223 0.0149137508 0.1090430000 10015923 955859216 1765011456 -0.0753764883 0.0246260688 -0.0586016439 407 16.2400000000 0.0344147347 0.0326627286 0.0419400223 0.0149204374 0.0881000000 10017177 955859216 1765011456 -0.0725300387 0.0248167887 -0.0571811870 408 16.2800000000 0.0344501585 0.0326671096 0.0419400223 0.0149254576 0.0881750000 10018431 955859216 1765122048 -0.0698617175 0.0251412988 -0.0561311543 409 16.3200000000 0.0344368666 0.0326714366 0.0419400223 0.0149172942 0.0891770000 10019685 955859216 1765122048 -0.0667562559 0.0253499690 -0.0543377437 410 16.3600000000 0.0342204198 0.0326752146 0.0419400223 0.0149201240 0.0870940000 10020939 955859216 1764990976 -0.0636498854 0.0249744859 -0.0524893887 411 16.3999999990 0.0339244492 0.0326782541 0.0419400223 0.0149300365 0.1114040000 10022193 955859216 1765003264 -0.0605138876 0.0236501619 -0.0506574288 412 16.4400000000 0.0342230499 0.0326820036 0.0419400223 0.0149340313 0.0865150000 10023447 955859216 1765003264 -0.0584220327 0.0232713502 -0.0495167188 413 16.4800000000 0.0339240916 0.0326850111 0.0419400223 0.0149393173 0.0880250000 10024701 955859216 1765113856 -0.0556275845 0.0220113751 -0.0475014672 414 16.5200000000 0.0342251919 0.0326887313 0.0419400223 0.0149334103 0.1122390000 10025955 955859216 1765130240 -0.0534706563 0.0218518786 -0.0465537272 415 16.5599999990 0.0344331302 0.0326929347 0.0419400223 0.0149242736 0.0857670000 10027209 955859216 1765130240 -0.0513459630 0.0222153291 -0.0457052179 416 16.6000000000 0.0344062708 0.0326970533 0.0419400223 0.0149122202 0.0889830000 10028463 955859216 1765130240 -0.0498845167 0.0224639680 -0.0451030470 417 16.6400000000 0.0344437957 0.0327012421 0.0419400223 0.0149037668 0.0874310000 10029717 955859216 1765130240 -0.0477024652 0.0229639504 -0.0440868735 418 16.6800000000 0.0341408849 0.0327046863 0.0419400223 0.0148944994 0.0902370000 10030971 955859216 1765130240 -0.0468194112 0.0222305413 -0.0438171178 419 16.7199999990 0.0341503099 0.0327081364 0.0419400223 0.0148883547 0.0875300000 10032225 955859216 1765130240 -0.0446728691 0.0214868672 -0.0427343994 420 16.7600000000 0.0339253508 0.0327110346 0.0419400223 0.0148861560 0.0876730000 10033479 955859216 1765113856 -0.0428821258 0.0201669764 -0.0412099510 421 16.8000000000 0.0337857716 0.0327135874 0.0419400223 0.0148859042 0.0870460000 10034733 955859216 1766604800 -0.0408120751 0.0186016597 -0.0395531505 422 16.8400000000 0.0343195274 0.0327173929 0.0419400223 0.0148811155 0.0877920000 10035987 955859216 1766125568 -0.0391615257 0.0186597947 -0.0387963280 423 16.8799999990 0.0340264551 0.0327204876 0.0419400223 0.0148769546 0.1088910000 10037241 955859216 1764876288 -0.0371586233 0.0179298054 -0.0376930572 424 16.9200000000 0.0339106321 0.0327232946 0.0419400223 0.0148678656 0.0899940000 10038495 955859216 1764888576 -0.0346147791 0.0168228578 -0.0364790373 425 16.9600000000 0.0340679064 0.0327264584 0.0419400223 0.0148741734 0.0882810000 10039749 955859216 1764888576 -0.0321957134 0.0165470634 -0.0343130827 426 17.0000000000 0.0332552455 0.0327276997 0.0419400223 0.0148688731 0.0877600000 10041003 955859216 1764986880 -0.0298339855 0.0134469373 -0.0326822326 427 17.0400000000 0.0336977392 0.0327299714 0.0419400223 0.0148646593 0.1099600000 10042257 955859216 1765113856 -0.0269911643 0.0119947698 -0.0317418836 428 17.0800000000 0.0339312963 0.0327327782 0.0419400223 0.0148593517 0.0926700000 10043511 955859216 1765130240 -0.0241781007 0.0115783568 -0.0303539932 429 17.1200000000 0.0338671096 0.0327354224 0.0419400223 0.0148531013 0.0814070000 10044765 955859216 1765113856 -0.0217311457 0.0110456282 -0.0292352252 430 17.1600000000 0.0344583504 0.0327394292 0.0419400223 0.0148450829 0.0880100000 10046019 955859216 1765113856 -0.0193556882 0.0128383674 -0.0286937673 431 17.2000000000 0.0340393744 0.0327424453 0.0419400223 0.0148387732 0.1083740000 10047273 955859216 1765130240 -0.0169168152 0.0130664157 -0.0283244886 432 17.2400000000 0.0329546183 0.0327429364 0.0419400223 0.0148386967 0.1103840000 10048527 955859216 1765130240 -0.0143680479 0.0094259102 -0.0269148573 433 17.2800000000 0.0328203328 0.0327431152 0.0419400223 0.0148507107 0.0775740000 10049781 955859216 1765130240 -0.0128944833 0.0055106794 -0.0250887405 434 17.3200000000 0.0331448354 0.0327440408 0.0419400223 0.0148552202 0.1224000000 10051035 955859216 1765130240 -0.0105134081 0.0029692713 -0.0233937521 435 17.3600000000 0.0329211652 0.0327444480 0.0419400223 0.0148596219 0.0986060000 10052289 955859216 1765130240 -0.0082608312 -0.0002248317 -0.0223380029 436 17.4000000000 0.0331511497 0.0327453808 0.0419400223 0.0148584975 0.0888780000 10053543 955859216 1765130240 -0.0068440014 -0.0021822730 -0.0211801920 437 17.4400000000 0.0333491601 0.0327467624 0.0419400223 0.0148543092 0.0892950000 10054797 955859216 1765130240 -0.0061377948 -0.0031008823 -0.0207913164 438 17.4800000000 0.0333739035 0.0327481943 0.0419400223 0.0148692717 0.0967300000 10056051 955859216 1764954112 -0.0058666547 -0.0035065594 -0.0195637476 439 17.5200000000 0.0331566110 0.0327491246 0.0419400223 0.0148782451 0.0815780000 10057305 955859216 1765003264 -0.0061896332 -0.0043456261 -0.0187990721 440 17.5600000000 0.0331730172 0.0327500880 0.0419400223 0.0148819456 0.0889100000 10058559 955859216 1765003264 -0.0075148675 -0.0048371959 -0.0184730850 441 17.6000000000 0.0330618285 0.0327507949 0.0419400223 0.0148943269 0.0885060000 10059813 955859216 1765003264 -0.0088436613 -0.0053881989 -0.0173683167 442 17.6400000000 0.0326336399 0.0327505298 0.0419400223 0.0149870341 0.0886370000 10061067 955859216 1765130240 -0.0162442084 -0.0079488242 -0.0174437091 443 17.6800000000 0.0331234932 0.0327513717 0.0419400223 0.0149960086 0.0888880000 10062321 955859216 1765130240 -0.0210444462 -0.0080707911 -0.0174982715 444 17.7200000000 0.0330143571 0.0327519640 0.0419400223 0.0150009756 0.1086860000 10063575 955859216 1765130240 -0.0240793806 -0.0081871795 -0.0167021137 445 17.7600000000 0.0320793726 0.0327504526 0.0419400223 0.0150058969 0.0896440000 10064829 955859216 1765130240 -0.0262543708 -0.0114027690 -0.0158728212 446 17.8000000000 0.0322777629 0.0327493928 0.0419400223 0.0150144895 0.0888950000 10066083 955859216 1764999168 -0.0281571522 -0.0136564272 -0.0149622988 447 17.8400000000 0.0317034535 0.0327470529 0.0419400223 0.0150128698 0.0904890000 10067337 955859216 1765003264 -0.0278831385 -0.0175047815 -0.0131901577 448 17.8800000000 0.0318056010 0.0327449514 0.0419400223 0.0150043058 0.1079420000 10068591 955859216 1764986880 -0.0272238702 -0.0204375703 -0.0118962638 449 17.9200000000 0.0318383053 0.0327429321 0.0419400223 0.0149954312 0.0871380000 10069845 955859216 1764986880 -0.0284334328 -0.0233049057 -0.0097952848 450 17.9600000000 0.0316367559 0.0327404740 0.0419400223 0.0149825974 0.0883650000 10071099 955859216 1765240832 -0.0281552020 -0.0263912547 -0.0080499370 451 18.0000000000 0.0319318213 0.0327386810 0.0419400223 0.0149749609 0.1180890000 10072353 955859216 1765113856 -0.0278301593 -0.0274142046 -0.0050379797 452 18.0400000000 0.0315987915 0.0327361591 0.0419400223 0.0149690657 0.0800460000 10073607 955859216 1765130240 -0.0275514238 -0.0293691400 -0.0019361996 453 18.0800000000 0.0315778553 0.0327336021 0.0419400223 0.0149587302 0.0908790000 10074861 955859216 1765130240 -0.0267521553 -0.0308311936 0.0013275523 454 18.1200000000 0.0316026062 0.0327311109 0.0419400223 0.0149466527 0.0860310000 10076115 955859216 1765130240 -0.0261945464 -0.0314364731 0.0053073233 455 18.1600000000 0.0311896056 0.0327277230 0.0419400223 0.0149315600 0.0869430000 10077369 955859216 1765130240 -0.0248974878 -0.0326349698 0.0092223212 456 18.2000000000 0.0311293285 0.0327242178 0.0419400223 0.0149224914 0.1095730000 10078623 955859216 1765130240 -0.0237347111 -0.0336914584 0.0142412772 457 18.2400000000 0.0308631193 0.0327201453 0.0419400223 0.0149161172 0.0885750000 10079877 955859216 1765081088 -0.0220628660 -0.0302945040 0.0186561365 458 18.2800000000 0.0307898112 0.0327159306 0.0419400223 0.0149049806 0.0888100000 10081131 955859216 1765130240 -0.0208947714 -0.0294733476 0.0248755813 459 18.3200000000 0.0306635089 0.0327114591 0.0419400223 0.0148900054 0.1092760000 10082385 955859216 1765130240 -0.0185942426 -0.0291828848 0.0309956335 460 18.3600000000 0.0306534749 0.0327069852 0.0419400223 0.0148756225 0.0880740000 10083639 955859216 1765130240 -0.0171114858 -0.0254877955 0.0374623761 461 18.4000000000 0.0305222347 0.0327022461 0.0419400223 0.0148606270 0.0881240000 10084893 955859216 1765130240 -0.0163165517 -0.0255607776 0.0447013937 462 18.4400000000 0.0304812808 0.0326974388 0.0419400223 0.0148451025 0.0878170000 10086147 955859216 1765130240 -0.0128216771 -0.0249297637 0.0523648411 463 18.4800000000 0.0305160638 0.0326927274 0.0419400223 0.0148322329 0.0909310000 10087401 955859216 1765130240 -0.0120514352 -0.0226707086 0.0604053587 464 18.5200000000 0.0306111071 0.0326882412 0.0419400223 0.0148190917 0.0843360000 10088655 955859216 1765130240 -0.0109570967 -0.0206602253 0.0695033893 465 18.5600000000 0.0303927995 0.0326833047 0.0419400223 0.0148073238 0.0879780000 10089909 955859216 1765130240 -0.0068343664 -0.0138881598 0.0889661238 466 18.6000000000 0.0303865150 0.0326783760 0.0419400223 0.0147925559 0.1093860000 10091163 955859216 1765130240 -0.0041216956 -0.0099732224 0.0992851928 467 18.6400000000 0.0302614681 0.0326732006 0.0419400223 0.0147774683 0.0873380000 10092417 955859216 1765113856 -0.0013057317 -0.0088586872 0.1102276593 468 18.6800000000 0.0301748700 0.0326678623 0.0419400223 0.0147639715 0.0701220000 10093671 955859216 1766477824 0.0006469168 -0.0039832033 0.1212923154 469 18.7200000000 0.0300485846 0.0326622775 0.0419400223 0.0147529913 0.0670530000 10094925 955859216 1766137856 0.0022360680 -0.0005421452 0.1327929348 470 18.7600000000 0.0298667885 0.0326563296 0.0419400223 0.0147462696 0.0856550000 10096179 955859216 1765142528 0.0042609260 0.0047776015 0.1445310563 471 18.8000000000 0.0296751037 0.0326500001 0.0419400223 0.0147391266 0.1084270000 10097433 955859216 1765130240 0.0056897057 0.0107759740 0.1568459868 472 18.8400000000 0.0295184925 0.0326433655 0.0419400223 0.0147242051 0.1113440000 10098687 955859216 1765130240 0.0088196434 0.0171355512 0.1685839146 473 18.8800000000 0.0290903170 0.0326358538 0.0419400223 0.0147088560 0.0887080000 10099941 955859216 1766604800 0.0113804303 0.0250721108 0.1804012507 474 18.9200000000 0.0292813163 0.0326287767 0.0419400223 0.0146970863 0.0861090000 10101195 955859216 1768636416 0.0148111694 0.0311382841 0.1915768832 475 18.9600000000 0.0290870219 0.0326213204 0.0419400223 0.0146890055 0.0878770000 10102449 955859216 1770287104 0.0184298102 0.0361812301 0.2041860372 476 19.0000000000 0.0288878232 0.0326134769 0.0419400223 0.0146793106 0.1121450000 10103703 955859216 1771937792 0.0216766968 0.0391367972 0.2161754966 477 19.0400000000 0.0285519585 0.0326049622 0.0419400223 0.0146663304 0.1054500000 10104957 955859216 1773715456 0.0233312082 0.0462192968 0.2278868258 478 19.0800000000 0.0283569600 0.0325960751 0.0419400223 0.0146535122 0.0868030000 10106211 955859216 1775366144 0.0269014351 0.0537625700 0.2389751971 479 19.1200000000 0.0284860861 0.0325874948 0.0419400223 0.0146429081 0.0884690000 10107465 955859216 1777143808 0.0304735135 0.0569227263 0.2507549524 480 19.1600000000 0.0283455215 0.0325786573 0.0419400223 0.0146341766 0.1107360000 10108719 955859216 1778921472 0.0341204554 0.0618545115 0.2618886530 481 19.2000000000 0.0278451703 0.0325688164 0.0419400223 0.0146206583 0.0887670000 10109973 955859216 1780572160 0.0350938141 0.0724246427 0.2720271349 482 19.2400000000 0.0279432684 0.0325592198 0.0419400223 0.0146187126 0.0879720000 10111227 955859216 1782222848 0.0388975255 0.0766429305 0.2835516036 483 19.2800000000 0.0276953857 0.0325491498 0.0419400223 0.0146203499 0.1112090000 10112481 955859216 1784000512 0.0413533971 0.0775582120 0.2950678766 484 19.3200000000 0.0275505055 0.0325388220 0.0419400223 0.0146185892 0.1035950000 10113735 955859216 1785651200 0.0447807983 0.0789867267 0.3062252998 485 19.3600000000 0.0275269039 0.0325284882 0.0419400223 0.0146060219 0.1106670000 10114989 955859216 1787301888 0.0468929671 0.0826175883 0.3173456192 486 19.4000000000 0.0272015054 0.0325175273 0.0419400223 0.0145909736 0.0871120000 10116243 955859216 1786413056 0.0500586815 0.0898503065 0.3273664117 487 19.4400000000 0.0273209158 0.0325068566 0.0419400223 0.0145761547 0.0857900000 10117497 955859216 1784664064 0.0504187606 0.0937706679 0.3390373588 488 19.4800000000 0.0271495115 0.0324958785 0.0419400223 0.0145614565 0.1093030000 10118751 955859216 1782915072 0.0523974001 0.0966403782 0.3500519991 489 19.5200000000 0.0268362816 0.0324843046 0.0419400223 0.0145471198 0.0894200000 10120005 955859216 1781764096 0.0532024018 0.1046505198 0.3605284095 490 19.5600000000 0.0269757919 0.0324730628 0.0419400223 0.0145329510 0.0878260000 10121259 955859216 1780731904 0.0535211042 0.1098340824 0.3712317646 491 19.6000000000 0.0266146529 0.0324611312 0.0419400223 0.0145183674 0.0890470000 10122513 955859216 1779716096 0.0564347394 0.1163817048 0.3814286590 492 19.6400000000 0.0266478974 0.0324493157 0.0419400223 0.0145036065 0.1058100000 10123767 955859216 1778589696 0.0567731299 0.1207232475 0.3916295171 493 19.6800000000 0.0265171081 0.0324372828 0.0419400223 0.0144891569 0.1151570000 10125021 955859216 1777557504 0.0573055483 0.1234253943 0.4025077224 494 19.7200000000 0.0263464246 0.0324249531 0.0419400223 0.0144744890 0.1423070000 10126275 955859216 1776668672 0.0576574840 0.1247564107 0.4137157798 495 19.7600000000 0.0262237489 0.0324124254 0.0419400223 0.0144609214 0.1282540000 10127529 955859216 1775546368 0.0583452061 0.1296967864 0.4248045087 496 19.8000000000 0.0261464529 0.0323997924 0.0419400223 0.0144480773 0.0893220000 10128783 955859216 1774399488 0.0584217757 0.1364940554 0.4352093935 497 19.8400000000 0.0260197632 0.0323869554 0.0419400223 0.0144358211 0.0892500000 10130037 955859216 1773367296 0.0583284795 0.1427985877 0.4461478293 498 19.8800000000 0.0258951392 0.0323739196 0.0419400223 0.0144266613 0.0880180000 10131291 955859216 1772351488 0.0570303872 0.1497736275 0.4567999244 499 19.9200000000 0.0257416330 0.0323606284 0.0419400223 0.0144185904 0.0896760000 10132545 955859216 1771335680 0.0563071929 0.1562231928 0.4683884084 500 19.9600000000 0.0255370699 0.0323469813 0.0419400223 0.0144084650 0.1265780000 10133799 955859216 1770319872 0.0552371964 0.1583139449 0.4795413911 501 20.0000000000 0.0254358277 0.0323331866 0.0419400223 0.0143994041 0.1298100000 10135053 955859216 1771700224 0.0537928417 0.1613836288 0.4903180301 502 20.0400000000 0.0253442582 0.0323192644 0.0419400223 0.0143897221 0.1101290000 10136307 955859216 1773461504 0.0523760431 0.1662094295 0.5013244152 503 20.0800000000 0.0252334867 0.0323051774 0.0419400223 0.0143776455 0.0870520000 10137561 955859216 1775112192 0.0502121709 0.1728224754 0.5120357275 504 20.1200000000 0.0250516031 0.0322907854 0.0419400223 0.0143634062 0.0888910000 10138815 955859216 1776889856 0.0475406460 0.1780369878 0.5228506923 505 20.1600000000 0.0249401405 0.0322762296 0.0419400223 0.0143494353 0.1102330000 10140069 955859216 1778540544 0.0459275022 0.1845063120 0.5333980918 506 20.2000000000 0.0246982668 0.0322612534 0.0419400223 0.0143387185 0.0880880000 10141323 955859216 1780318208 0.0441232324 0.1939302981 0.5432559252 507 20.2400000000 0.0246307570 0.0322462031 0.0419400223 0.0143349507 0.0886830000 10142577 955859216 1782095872 0.0412592292 0.1990768760 0.5536779761 508 20.2800000000 0.0245079398 0.0322309703 0.0419400223 0.0143333060 0.0881530000 10143831 955859216 1783746560 0.0390500426 0.2038273215 0.5637043118 509 20.3200000000 0.0243818909 0.0322155498 0.0419400223 0.0143443217 0.0896940000 10145085 955859216 1785397248 0.0364342481 0.2105707079 0.5731514692 510 20.3600000000 0.0242486577 0.0321999284 0.0419400223 0.0143455408 0.0884200000 10146339 955859216 1787174912 0.0325543098 0.2152974457 0.5825409293 511 20.4000000000 0.0241348371 0.0321841454 0.0419400223 0.0143436692 0.0876610000 10147593 955859216 1786179584 0.0304890331 0.2202281058 0.5912075043 512 20.4400000000 0.0240330063 0.0321682252 0.0419400223 0.0143489530 0.1076050000 10148847 955859216 1784061952 0.0301349349 0.2268680483 0.5991038084 513 20.4800000000 0.0238864925 0.0321520815 0.0419400223 0.0143496408 0.0905830000 10191061 955859216 1782890496 0.0285480283 0.2312557101 0.6073322892 514 20.5200000000 0.0237522330 0.0321357394 0.0419400223 0.0143527904 0.1066330000 10276283 955859216 1781874688 0.0271762237 0.2335676551 0.6157903075 515 20.5600000000 0.0236916430 0.0321193431 0.0419400223 0.0143588998 0.1082730000 10277537 955859216 1780748288 0.0269192178 0.2355321646 0.6228289008 516 20.6000000000 0.0236480366 0.0321029258 0.0419400223 0.0143733934 0.1088960000 10278791 955859216 1779716096 0.0268995296 0.2411446273 0.6299501061 517 20.6400000000 0.0235272795 0.0320863385 0.0419400223 0.0143875270 0.0886700000 10280045 955859216 1779437568 0.0271627083 0.2448752373 0.6364695430 518 20.6800000000 0.0234388392 0.0320696445 0.0419400223 0.0144057251 0.1061430000 10281299 955859216 1777557504 0.0272867475 0.2480411232 0.6429027319 519 20.7200000000 0.0234021693 0.0320529442 0.0419400223 0.0144246534 0.1142180000 10282553 955859216 1776431104 0.0292444844 0.2518182993 0.6485418677 520 20.7600000000 0.0233215764 0.0320361531 0.0419400223 0.0144527080 0.1107220000 10283807 955859216 1775398912 0.0304647107 0.2548657656 0.6540402174 521 20.8000000000 0.0232430603 0.0320192757 0.0419400223 0.0144777412 0.0826670000 10285061 955859216 1774383104 0.0324181356 0.2556348145 0.6593680382 522 20.8400000000 0.0232309010 0.0320024398 0.0419400223 0.0145057643 0.1028450000 10286315 955859216 1773387776 0.0339784510 0.2559182346 0.6645466089 523 20.8800000000 0.0238802135 0.0319869097 0.0419400223 0.0145348653 0.0924120000 10287569 955859216 1772240896 0.0362385809 0.2550382316 0.6690046787 524 20.9200000000 0.0232569668 0.0319702495 0.0419400223 0.0145687813 0.0874150000 10288823 955859216 1771208704 0.0385347381 0.2591468692 0.6731756330 525 20.9600000000 0.0240446366 0.0319551531 0.0419400223 0.0145856881 0.0878760000 10290077 955859216 1770340352 0.0414090119 0.2599215209 0.6770036817 526 21.0000000000 0.0239006784 0.0319398404 0.0419400223 0.0145975653 0.1147980000 10291331 955859216 1769304064 0.0444353819 0.2595238984 0.6807201505 527 21.0400000000 0.0245370716 0.0319257934 0.0419400223 0.0146147756 0.0844470000 10292585 955859216 1768288256 0.0474111475 0.2604302168 0.6841720343 528 21.0800000000 0.0245694742 0.0319118610 0.0419400223 0.0146252750 0.0868260000 10293839 955859216 1767272448 0.0510350205 0.2620215416 0.6871381402 529 21.1200000000 0.0242591575 0.0318973946 0.0419400223 0.0146280407 0.1138040000 10295093 955859216 1766404096 0.0538402982 0.2624754012 0.6901085973 530 21.1600000000 0.0245108679 0.0318834578 0.0419400223 0.0146331855 0.0846030000 10296347 955859216 1765367808 0.0571932197 0.2633726597 0.6928396821 531 21.2000000000 0.0242644195 0.0318691093 0.0419400223 0.0146431072 0.0865730000 10297601 955859216 1764999168 0.0608735718 0.2638231218 0.6954577565 532 21.2400000000 0.0241829082 0.0318546616 0.0419400223 0.0146580598 0.1086670000 10298855 955859216 1765003264 0.0645093396 0.2632714212 0.6978124976 533 21.2800000000 0.0243681222 0.0318406155 0.0419400223 0.0146758783 0.0890150000 10300109 955859216 1765003264 0.0684088916 0.2632981539 0.7000427842 534 21.3200000000 0.0244129505 0.0318267060 0.0419400223 0.0146925788 0.0874210000 10301363 955859216 1765003264 0.0724185184 0.2632206678 0.7022866607 535 21.3600000000 0.0246151704 0.0318132265 0.0419400223 0.0147094190 0.0880730000 10302617 955859216 1765130240 0.0761183873 0.2634434700 0.7046349049 536 21.4000000000 0.0247500297 0.0318000489 0.0419400223 0.0147262650 0.1085200000 10303871 955859216 1765130240 0.0798218027 0.2637984753 0.7067927718 537 21.4400000000 0.0248963945 0.0317871930 0.0419400223 0.0147452453 0.0892930000 10305125 955859216 1765130240 0.0843223184 0.2642304599 0.7090610862 538 21.4800000000 0.0250670537 0.0317747020 0.0419400223 0.0147542813 0.0871970000 10306379 955859216 1765130240 0.0889870897 0.2649700046 0.7109810114 539 21.5200000000 0.0251638964 0.0317624370 0.0419400223 0.0147644897 0.0887370000 10307633 955859216 1764999168 0.0940256268 0.2660661936 0.7126228809 540 21.5600000000 0.0247395355 0.0317494317 0.0419400223 0.0147665175 0.1109700000 10308887 955859216 1764954112 0.0977645591 0.2668400109 0.7148324251 541 21.6000000000 0.0247515868 0.0317364967 0.0419400223 0.0147701703 0.0862260000 10310141 955859216 1764986880 0.1023221314 0.2669350803 0.7166931033 542 21.6400000000 0.0253988095 0.0317248035 0.0419400223 0.0147778391 0.0875460000 10311395 955859216 1764986880 0.1062345877 0.2676663995 0.7185849547 543 21.6800000000 0.0253544301 0.0317130717 0.0419400223 0.0147944670 0.1091890000 10312649 955859216 1765130240 0.1101252660 0.2684534490 0.7206618190 544 21.7200000000 0.0253596343 0.0317013926 0.0419400223 0.0148092230 0.0885220000 10313903 955859216 1765130240 0.1132269651 0.2690202296 0.7228319049 545 21.7600000000 0.0257494729 0.0316904716 0.0419400223 0.0148237668 0.0877190000 10315157 955859216 1765130240 0.1175350398 0.2704279721 0.7249608040 546 21.8000000000 0.0236097351 0.0316756717 0.0419400223 0.0148997844 0.1089630000 10316411 955859216 1765130240 0.1227497011 0.2738059461 0.7295401096 547 21.8400000000 0.0248777643 0.0316632441 0.0419400223 0.0149084124 0.0697160000 10317665 955859216 1766604800 0.1268368959 0.2733910978 0.7316895127 548 21.8800000000 0.0258914232 0.0316527116 0.0419400223 0.0149217143 0.0843550000 10318919 955859216 1766121472 0.1311775446 0.2742208838 0.7334430218 549 21.9200000000 0.0260958131 0.0316425898 0.0419400223 0.0149428964 0.1101400000 10320173 955859216 1765126144 0.1348187774 0.2757553160 0.7355865240 550 21.9600000000 0.0258505326 0.0316320587 0.0419400223 0.0149598199 0.0871080000 10321427 955859216 1765113856 0.1399901062 0.2769933939 0.7371681333 551 22.0000000000 0.0264931023 0.0316227321 0.0419400223 0.0149872080 0.0701200000 10322681 955859216 1766477824 0.1433896422 0.2788061500 0.7387517095 552 22.0400000000 0.0260931924 0.0316127149 0.0419400223 0.0149982520 0.1067870000 10323935 955859216 1766002688 0.1478577256 0.2816272080 0.7401246428 553 22.0800000000 0.0249347277 0.0316006389 0.0419400223 0.0149948521 0.0878950000 10325189 955859216 1767383040 0.1521641463 0.2826936841 0.7417089343 554 22.1200000000 0.0250284001 0.0315887757 0.0419400223 0.0149883613 0.0914130000 10326443 955859216 1769144320 0.1555016041 0.2817900181 0.7437967062 555 22.1600000000 0.0267877653 0.0315801252 0.0419400223 0.0149805947 0.0685170000 10327697 955859216 1770921984 0.1614642441 0.2817946374 0.7449183464 556 22.2000000000 0.0278217811 0.0315733656 0.0419400223 0.0149797528 0.0694850000 10328951 955859216 1772572672 0.1669659764 0.2837433219 0.7461389899 557 22.2400000000 0.0273334086 0.0315657535 0.0419400223 0.0149760233 0.0848310000 10330205 955859216 1774223360 0.1715071946 0.2859783173 0.7476525903 558 22.2800000000 0.0275232829 0.0315585089 0.0419400223 0.0149754603 0.0720930000 10331459 955859216 1776001024 0.1767375022 0.2886584401 0.7491651177 559 22.3200000000 0.0273781847 0.0315510307 0.0419400223 0.0149724979 0.0689100000 10332713 955859216 1777795072 0.1822449714 0.2914297581 0.7505736947 560 22.3600000000 0.0266249869 0.0315422342 0.0419400223 0.0149687880 0.0694420000 10333967 955859216 1779429376 0.1864221245 0.2931146622 0.7530338764 561 22.4000000000 0.0272517465 0.0315345862 0.0419400223 0.0149651753 0.0684060000 10335221 955859216 1781080064 0.1905282438 0.2947592139 0.7548162937 562 22.4400000000 0.0279015359 0.0315281217 0.0419400223 0.0149628587 0.0694180000 10336475 955859216 1782857728 0.1956876069 0.2973471284 0.7560079694 563 22.4800000000 0.0276424643 0.0315212200 0.0419400223 0.0149558206 0.0682940000 10337729 955859216 1784508416 0.2015754282 0.3011143208 0.7566533685 564 22.5200000000 0.0263879336 0.0315121185 0.0419400223 0.0149464953 0.0694990000 10338983 955859216 1786159104 0.2060269713 0.3041663170 0.7582451105 565 22.5600000000 0.0257053059 0.0315018409 0.0419400223 0.0149366624 0.0682810000 10340237 955859216 1787936768 0.2095048279 0.3058577180 0.7599077821 566 22.6000000000 0.0266048685 0.0314931890 0.0419400223 0.0149275307 0.0845810000 10341491 955859216 1786929152 0.2145256698 0.3080821335 0.7612422705 567 22.6400000000 0.0262444634 0.0314839320 0.0419400223 0.0149163696 0.0896430000 10342745 955859216 1785667584 0.2192137986 0.3105756938 0.7622851133 568 22.6800000000 0.0260155853 0.0314743046 0.0419400223 0.0149067899 0.0827210000 10343999 955859216 1783906304 0.2235963643 0.3126455247 0.7636928558 569 22.7200000000 0.0259043649 0.0314645157 0.0419400223 0.0148954456 0.0699510000 10345253 955859216 1782140928 0.2285277098 0.3141598403 0.7641866207 570 22.7600000000 0.0266921204 0.0314561430 0.0419400223 0.0148848168 0.0843600000 10346507 955859216 1781256192 0.2329251319 0.3161723316 0.7650150061 571 22.8000000000 0.0268854406 0.0314481383 0.0419400223 0.0148727537 0.0902900000 10347761 955859216 1780224000 0.2379738092 0.3186519146 0.7657720447 572 22.8400000000 0.0269304812 0.0314402403 0.0419400223 0.0148602225 0.1077340000 10349015 955859216 1779048448 0.2434258014 0.3214862347 0.7655471563 573 22.8800000000 0.0262649115 0.0314312083 0.0419400223 0.0148488957 0.1093320000 10350269 955859216 1778065408 0.2480331659 0.3244328201 0.7660881281 574 22.9200000000 0.0261417162 0.0314219932 0.0419400223 0.0148376571 0.0860520000 10351523 955859216 1779445760 0.2521951199 0.3276494741 0.7663465738 575 22.9600000000 0.0256974772 0.0314120375 0.0419400223 0.0148249162 0.0719010000 10352777 955859216 1781207040 0.2561430931 0.3309167922 0.7669646144 576 23.0000000000 0.0262262467 0.0314030344 0.0419400223 0.0148121132 0.0897870000 10354031 955859216 1782984704 0.2596957386 0.3337249756 0.7675668597 577 23.0400000000 0.0263093393 0.0313942065 0.0419400223 0.0147992715 0.0824120000 10355285 955859216 1784635392 0.2634511292 0.3371741176 0.7679529190 578 23.0800000000 0.0256479550 0.0313842649 0.0419400223 0.0147866250 0.0716740000 10356539 955859216 1786286080 0.2662902176 0.3396307528 0.7683482766 579 23.1200000000 0.0269323811 0.0313765760 0.0419400223 0.0147743674 0.0689020000 10357793 955859216 1788063744 0.2698299289 0.3418489397 0.7681606412 580 23.1600000000 0.0276444647 0.0313701413 0.0419400223 0.0147622608 0.0844600000 10359047 955859216 1787187200 0.2744296193 0.3468960524 0.7679353952 581 23.2000000000 0.0266348924 0.0313619911 0.0419400223 0.0147496737 0.0917420000 10360301 955859216 1785921536 0.2780725956 0.3525342941 0.7676259279 582 23.2400000000 0.0255786199 0.0313520540 0.0419400223 0.0147371160 0.0825470000 10361555 955859216 1784778752 0.2806989551 0.3570850492 0.7675213218 583 23.2800000000 0.0258544534 0.0313426242 0.0419400223 0.0147245821 0.0692280000 10362809 955859216 1783001088 0.2838326395 0.3618259132 0.7675954700 584 23.3200000000 0.0247364510 0.0313313123 0.0419400223 0.0147131368 0.0688350000 10364063 955859216 1781874688 0.2861833274 0.3658627272 0.7669085264 585 23.3600000000 0.0241660587 0.0313190640 0.0419400223 0.0147011702 0.0839730000 10365317 955859216 1780858880 0.2886732221 0.3685164452 0.7664808631 586 23.4000000000 0.0245698933 0.0313075466 0.0419400223 0.0146890531 0.0906760000 10366571 955859216 1779732480 0.2910050452 0.3710289598 0.7664741278 587 23.4400000000 0.0248062350 0.0312964711 0.0419400223 0.0146765632 0.0838970000 10367825 955859216 1778589696 0.2931733727 0.3740125299 0.7662360072 588 23.4800000000 0.0244017486 0.0312847454 0.0419400223 0.0146641698 0.0735700000 10369079 955859216 1777557504 0.2953486443 0.3771862388 0.7661107779 589 23.5200000000 0.0241208281 0.0312725825 0.0419400223 0.0146518257 0.0855010000 10370333 955859216 1776799744 0.2979789972 0.3802357614 0.7659364939 590 23.5600000000 0.0235736128 0.0312595334 0.0419400223 0.0146394485 0.0864960000 10371587 955859216 1775927296 0.2999498844 0.3826063573 0.7661614418 591 23.6000000000 0.0239851382 0.0312472248 0.0419400223 0.0146271559 0.0856590000 10372841 955859216 1777397760 0.3018579483 0.3849147260 0.7666885257 592 23.6400000000 0.0239539910 0.0312349052 0.0419400223 0.0146157305 0.0960000000 10374095 955859216 1774510080 0.3040655255 0.3875863254 0.7663705349 593 23.6800000000 0.0221520588 0.0312195884 0.0419400223 0.0146066579 0.0802290000 10375349 955859216 1776001024 0.3092468977 0.3930304646 0.7659574747 594 23.7200000000 0.0223618951 0.0312046765 0.0419400223 0.0145943568 0.0687290000 10376603 955859216 1775407104 0.3103324175 0.3934107423 0.7667655945 595 23.7600000000 0.0233463366 0.0311914692 0.0419400223 0.0145823797 0.0678060000 10377857 955859216 1774637056 0.3115130067 0.3942781687 0.7672954798 596 23.8000000000 0.0239732452 0.0311793581 0.0419400223 0.0145702005 0.0817540000 10379111 955859216 1773768704 0.3129228354 0.3960219920 0.7680330276 597 23.8400000000 0.0238177758 0.0311670271 0.0419400223 0.0145582491 0.0953500000 10380365 955859216 1772732416 0.3141347468 0.3982738554 0.7684867382 598 23.8800000000 0.0230519157 0.0311534567 0.0419400223 0.0145469929 0.0840670000 10381619 955859216 1771606016 0.3147774637 0.4001149535 0.7692467570 599 23.9200000000 0.0232173428 0.0311402077 0.0419400223 0.0145369036 0.0694520000 10382873 955859216 1772969984 0.3155086637 0.4017834961 0.7701480389 600 23.9600000000 0.0229960065 0.0311266341 0.0419400223 0.0145270614 0.0673940000 10384127 955859216 1772253184 0.3157106340 0.4037607312 0.7709167004 601 24.0000000000 0.0223019850 0.0311119508 0.0419400223 0.0145180612 0.0868120000 10385381 955859216 1771368448 0.3174601197 0.4082435369 0.7718541026 602 24.0400000000 0.0225124862 0.0310976660 0.0419400223 0.0145075987 0.0879090000 10386635 955859216 1770319872 0.3172769547 0.4082724154 0.7729872465 603 24.0800000000 0.0230238829 0.0310842766 0.0419400223 0.0144971640 0.0688910000 10387889 955859216 1769304064 0.3177688122 0.4089080691 0.7738897204 604 24.1200000000 0.0235249922 0.0310717612 0.0419400223 0.0144853594 0.0696720000 10389143 955859216 1768284160 0.3184442520 0.4096570015 0.7747761607 605 24.1600000000 0.0240570698 0.0310601667 0.0419400223 0.0144734872 0.0903050000 10390397 955859216 1767419904 0.3203087747 0.4135972857 0.7755514383 606 24.2000000000 0.0236315262 0.0310479082 0.0419400223 0.0144615236 0.0699200000 10391651 955859216 1768779776 0.3203511834 0.4155900180 0.7767964602 607 24.2400000000 0.0234994181 0.0310354725 0.0419400223 0.0144498665 0.0735710000 10392905 955859216 1768026112 0.3209480047 0.4173513949 0.7773337960 608 24.2800000000 0.0234250128 0.0310229553 0.0419400223 0.0144381434 0.0866350000 10394159 955859216 1767165952 0.3214110732 0.4184304476 0.7782812119 609 24.3200000000 0.0234205183 0.0310104718 0.0419400223 0.0144264888 0.0910970000 10395413 955859216 1766129664 0.3219166398 0.4197248518 0.7787165642 610 24.3600000000 0.0241647791 0.0309992494 0.0419400223 0.0144147360 0.0867570000 10396667 955859216 1765261312 0.3225092590 0.4217295647 0.7791420221 611 24.4000000000 0.0243953113 0.0309884409 0.0419400223 0.0144029444 0.0703220000 10397921 955859216 1764999168 0.3231944740 0.4238926768 0.7795662880 612 24.4400000000 0.0239805412 0.0309769901 0.0419400223 0.0143911801 0.0882980000 10399175 955859216 1764999168 0.3229533136 0.4261099398 0.7804663181 613 24.4800000000 0.0242474806 0.0309660121 0.0419400223 0.0143796768 0.0671300000 10400429 955859216 1764999168 0.3233693242 0.4283400774 0.7810882330 614 24.5200000000 0.0239047688 0.0309545117 0.0419400223 0.0143685496 0.0697110000 10401683 955859216 1765113856 0.3231777847 0.4304823875 0.7818975449 615 24.5600000000 0.0238424279 0.0309429474 0.0419400223 0.0143577571 0.0871440000 10402937 955859216 1765113856 0.3224132657 0.4332676232 0.7828938365 616 24.6000000000 0.0235259589 0.0309309068 0.0419400223 0.0143467577 0.1074680000 10404191 955859216 1765130240 0.3215209842 0.4354857206 0.7842056751 617 24.6400000000 0.0237825364 0.0309193211 0.0419400223 0.0143353695 0.0878060000 10405445 955859216 1765130240 0.3203105330 0.4371801317 0.7856032252 618 24.6800000000 0.0240571611 0.0309082173 0.0419400223 0.0143259270 0.0919870000 10406699 955859216 1765130240 0.3193162382 0.4387765527 0.7871292233 619 24.7200000000 0.0241387635 0.0308972812 0.0419400223 0.0143166777 0.0837370000 10407953 955859216 1765130240 0.3178843558 0.4415172338 0.7884733677 620 24.7600000000 0.0238399711 0.0308858984 0.0419400223 0.0143081857 0.0704830000 10409207 955859216 1766604800 0.3161312044 0.4433758259 0.7898960114 621 24.8000000000 0.0244310107 0.0308755041 0.0419400223 0.0143002621 0.0675570000 10410461 955859216 1766273024 0.3139814734 0.4445731640 0.7919229865 622 24.8400000000 0.0247956384 0.0308657294 0.0419400223 0.0142931153 0.0855340000 10411715 955859216 1765265408 0.3118571937 0.4461556375 0.7942691445 623 24.8800000000 0.0257429201 0.0308575066 0.0419400223 0.0142887266 0.1117220000 10412969 955859216 1765007360 0.3098072112 0.4485077262 0.7964717746 624 24.9200000000 0.0250860415 0.0308482574 0.0419400223 0.0142825664 0.1049080000 10414223 955859216 1765007360 0.3083341718 0.4501857758 0.7983121872 625 24.9600000000 0.0257078558 0.0308400328 0.0419400223 0.0142756396 0.1097960000 10415477 955859216 1764962304 0.3062458336 0.4520241916 0.8004162312 626 25.0000000000 0.0257595740 0.0308319170 0.0419400223 0.0142690102 0.1054730000 10416731 955859216 1764990976 0.3040877581 0.4554294646 0.8023306131 627 25.0400000000 0.0224524215 0.0308185526 0.0419400223 0.0142668484 0.1073060000 10417985 955859216 1764995072 0.3051604927 0.4624403119 0.8018308282 628 25.0800000000 0.0230730921 0.0308062191 0.0419400223 0.0142662676 0.0918940000 10419239 955859216 1765027840 0.3016068041 0.4640802741 0.8043664694 629 25.1200000000 0.0239904448 0.0307953832 0.0419400223 0.0142686246 0.0852390000 10420493 955859216 1765011456 0.2994276881 0.4652636647 0.8059613109 630 25.1600000000 0.0241218340 0.0307847903 0.0419400223 0.0142630308 0.0889620000 10421747 955859216 1765011456 0.2963971496 0.4666943550 0.8081167936 631 25.2000000000 0.0247187875 0.0307751769 0.0419400223 0.0142574686 0.0874570000 10423001 955859216 1765011456 0.2935864627 0.4683828056 0.8099280596 632 25.2400000000 0.0240700524 0.0307645676 0.0419400223 0.0142510760 0.0673590000 10424255 955859216 1766612992 0.2906309962 0.4691759944 0.8124094605 633 25.2800000000 0.0245596264 0.0307547651 0.0419400223 0.0142425856 0.0860740000 10425509 955859216 1766137856 0.2868721783 0.4702406228 0.8145976067 634 25.3200000000 0.0251120646 0.0307458650 0.0419400223 0.0142340917 0.0915720000 10426763 955859216 1765089280 0.2833696902 0.4724296927 0.8170852661 635 25.3600000000 0.0248210169 0.0307365345 0.0419400223 0.0142267023 0.0684550000 10428017 955859216 1765027840 0.2795501351 0.4749494791 0.8198035955 636 25.4000000000 0.0242445618 0.0307263270 0.0419400223 0.0142205456 0.0851360000 10429271 955859216 1765027840 0.2756977975 0.4766933322 0.8221765161 637 25.4400000000 0.0241797715 0.0307160498 0.0419400223 0.0142140074 0.0917350000 10430525 955859216 1765027840 0.2715857029 0.4778919816 0.8250137568 638 25.4800000000 0.0238950886 0.0307053587 0.0419400223 0.0142066826 0.0861110000 10431779 955859216 1765122048 0.2669903636 0.4793303907 0.8282331228 639 25.5200000000 0.0232455470 0.0306936845 0.0419400223 0.0141995915 0.0702120000 10433033 955859216 1765122048 0.2626477778 0.4803429544 0.8313401937 640 25.5600000000 0.0225669928 0.0306809865 0.0419400223 0.0141912538 0.1069970000 10434287 955859216 1765027840 0.2582084537 0.4803822041 0.8347434998 641 25.6000000000 0.0227094758 0.0306685505 0.0419400223 0.0141831429 0.0879200000 10435541 955859216 1765011456 0.2533879876 0.4803911150 0.8379271626 642 25.6400000000 0.0234959144 0.0306573781 0.0419400223 0.0141790664 0.0913180000 10436795 955859216 1765011456 0.2490147501 0.4820175171 0.8408999443 643 25.6800000000 0.0234850645 0.0306462237 0.0419400223 0.0141765551 0.0853150000 10438049 955859216 1765122048 0.2443032116 0.4831746221 0.8439894915 644 25.7200000000 0.0230771545 0.0306344705 0.0419400223 0.0141731120 0.0696030000 10439303 955859216 1766612992 0.2400176525 0.4835534692 0.8467988372 645 25.7600000000 0.0236577541 0.0306236539 0.0419400223 0.0141671983 0.1053780000 10440557 955859216 1766232064 0.2357168794 0.4847912192 0.8493815064 646 25.8000000000 0.0237565320 0.0306130236 0.0419400223 0.0141616018 0.0916450000 10441811 955859216 1767628800 0.2313720286 0.4862631559 0.8522520065 647 25.8400000000 0.0234735850 0.0306019890 0.0419400223 0.0141555601 0.0847640000 10443065 955859216 1769533440 0.2266353965 0.4867991805 0.8553159237 648 25.8800000000 0.0245020464 0.0305925755 0.0419400223 0.0141479412 0.0880780000 10444319 955859216 1771184128 0.2220665812 0.4876983464 0.8580896854 649 25.9200000000 0.0248623304 0.0305837461 0.0419400223 0.0141401254 0.0933640000 10445573 955859216 1772834816 0.2176379561 0.4891446829 0.8608069420 650 25.9600000000 0.0216627549 0.0305700215 0.0419400223 0.0141340950 0.0862310000 10446827 955859216 1774612480 0.2150950283 0.4962192774 0.8625127077 651 26.0000000000 0.0218331199 0.0305566008 0.0419400223 0.0141330980 0.0871440000 10448081 955859216 1776263168 0.2116955072 0.4979220629 0.8647574782 652 26.0400000000 0.0218231250 0.0305432059 0.0419400223 0.0141299904 0.1113310000 10449335 955859216 1777913856 0.2079180926 0.5000939965 0.8666222692 653 26.0800000000 0.0224134047 0.0305307559 0.0419400223 0.0141288906 0.0857670000 10450589 955859216 1779691520 0.2024266720 0.5008861423 0.8691780567 654 26.1200000000 0.0218833890 0.0305175337 0.0419400223 0.0141287612 0.0888310000 10451843 955859216 1781342208 0.1988687515 0.5028089881 0.8712590933 655 26.1600000000 0.0214135740 0.0305036345 0.0419400223 0.0141246520 0.1128010000 10453097 955859216 1782992896 0.1962730885 0.5067378283 0.8727889061 656 26.2000000000 0.0227979999 0.0304918881 0.0419400223 0.0141203731 0.0865850000 10454351 955859216 1784770560 0.1862250417 0.5085178614 0.8767011166 657 26.2400000000 0.0216082465 0.0304783666 0.0419400223 0.0141183805 0.1273470000 10455605 955859216 1786421248 0.1837436259 0.5101687312 0.8783191442 658 26.2800000000 0.0216183532 0.0304649015 0.0419400223 0.0141114131 0.1293750000 10456859 955859216 1786576896 0.1800519973 0.5120806694 0.8798832893 659 26.3200000000 0.0212073419 0.0304508536 0.0419400223 0.0141072214 0.0894180000 10458113 955859216 1786437632 0.1768759340 0.5162815452 0.8811652660 660 26.3600000000 0.0213799812 0.0304371099 0.0419400223 0.0141047478 0.0845430000 10459367 955859216 1785548800 0.1729573011 0.5170353651 0.8827005625 661 26.4000000000 0.0215212181 0.0304236214 0.0419400223 0.0141031581 0.0872960000 10460621 955859216 1784778752 0.1701779366 0.5206926465 0.8834141493 662 26.4400000000 0.0214040130 0.0304099966 0.0419400223 0.0140975779 0.0852970000 10461875 955859216 1783025664 0.1676345468 0.5236918926 0.8841950297 663 26.4800000000 0.0216224529 0.0303967424 0.0419400223 0.0140943403 0.0857060000 10463129 955859216 1781866496 0.1630972475 0.5230714679 0.8858478069 664 26.5200000000 0.0213476997 0.0303831143 0.0419400223 0.0140930526 0.0878060000 10464383 955859216 1780117504 0.1614404470 0.5250518918 0.8866599798 665 26.5600000000 0.0229434017 0.0303719268 0.0419400223 0.0140908844 0.1051280000 10465637 955859216 1778466816 0.1574921310 0.5254933238 0.8879728913 666 26.6000000000 0.0232554711 0.0303612414 0.0419400223 0.0140860852 0.0872510000 10466891 955859216 1780215808 0.1545127332 0.5263276696 0.8889992833 667 26.6400000000 0.0235959403 0.0303510985 0.0419400223 0.0140807142 0.0888080000 10468145 955859216 1781850112 0.1505750269 0.5279102921 0.8899589777 668 26.6800000000 0.0234654527 0.0303407907 0.0419400223 0.0140754354 0.1106320000 10469399 955859216 1783500800 0.1466711611 0.5300307870 0.8909872770 669 26.7200000000 0.0209806636 0.0303267995 0.0419400223 0.0140724568 0.0887930000 10470653 955859216 1785278464 0.1436789781 0.5346286297 0.8916766047 670 26.7600000000 0.0216351617 0.0303138269 0.0419400223 0.0140658614 0.0868810000 10471907 955859216 1786929152 0.1387454271 0.5329414606 0.8930117488 671 26.8000000000 0.0211279094 0.0303001370 0.0419400223 0.0140611317 0.1114930000 10473161 955859216 1784803328 0.1357843578 0.5328025818 0.8944694400 672 26.8400000000 0.0221331082 0.0302879836 0.0419400223 0.0140532756 0.1048250000 10474415 955859216 1783787520 0.1312379092 0.5316510201 0.8960310221 673 26.8800000000 0.0211718380 0.0302744381 0.0419400223 0.0140443162 0.1024960000 10475669 955859216 1782644736 0.1280711144 0.5327742100 0.8972263932 674 26.9200000000 0.0208737385 0.0302604905 0.0419400223 0.0140405166 0.0835640000 10476923 955859216 1781518336 0.1241190657 0.5325238705 0.8987414837 675 26.9600000000 0.0214370973 0.0302474188 0.0419400223 0.0140366335 0.0758260000 10478177 955859216 1780486144 0.1196216121 0.5318164229 0.8998908401 676 27.0000000000 0.0218143295 0.0302349438 0.0419400223 0.0140287643 0.0866180000 10479431 955859216 1779470336 0.1152079180 0.5316802859 0.9007531404 677 27.0400000000 0.0215403344 0.0302221010 0.0419400223 0.0140219376 0.1080800000 10480685 955859216 1778343936 0.1105420068 0.5320984721 0.9014919400 678 27.0800000000 0.0214717463 0.0302091948 0.0419400223 0.0140145838 0.0868520000 10481939 955859216 1777311744 0.1058444902 0.5318170190 0.9024917483 679 27.1200000000 0.0213961620 0.0301962154 0.0419400223 0.0140058227 0.0886420000 10483193 955859216 1776185344 0.1006694436 0.5307916403 0.9035170078 680 27.1600000000 0.0208889637 0.0301825283 0.0419400223 0.0140003096 0.1097550000 10484447 955859216 1775153152 0.0961945727 0.5307983160 0.9047921896 681 27.2000000000 0.0208851919 0.0301688758 0.0419400223 0.0139953918 0.0880600000 10485701 955859216 1774137344 0.0936973542 0.5305576324 0.9055225849 682 27.2400000000 0.0208223015 0.0301551711 0.0419400223 0.0139903673 0.0888680000 10486955 955859216 1773142016 0.0900649205 0.5300194025 0.9062935710 683 27.2800000000 0.0208199993 0.0301415032 0.0419400223 0.0139852407 0.1087020000 10488209 955859216 1771986944 0.0874329582 0.5288898349 0.9072452784 684 27.3200000000 0.0221730974 0.0301298535 0.0419400223 0.0139758900 0.1067130000 10489463 955859216 1770954752 0.0813674256 0.5279679298 0.9084356427 685 27.3600000000 0.0211820155 0.0301167910 0.0419400223 0.0139699683 0.1274120000 10490717 955859216 1769938944 0.0788460821 0.5300603509 0.9092213511 686 27.4000000000 0.0217746701 0.0301046305 0.0419400223 0.0139649667 0.1058520000 10491971 955859216 1768923136 0.0745362714 0.5285286903 0.9104118943 687 27.4400000000 0.0210511498 0.0300914522 0.0419400223 0.0139614113 0.1300570000 10493225 955859216 1767907328 0.0711783096 0.5300922394 0.9117273092 688 27.4800000000 0.0209518112 0.0300781678 0.0419400223 0.0139586920 0.1058640000 10494479 955859216 1766756352 0.0691351071 0.5306642652 0.9127711654 689 27.5200000000 0.0226518698 0.0300673894 0.0419400223 0.0139542829 0.0899070000 10495733 955859216 1765892096 0.0647963881 0.5295471549 0.9136024714 690 27.5600000000 0.0233365428 0.0300576346 0.0419400223 0.0139478921 0.1122960000 10496987 955859216 1765081088 0.0613061227 0.5297636390 0.9146686792 691 27.6000000000 0.0211711209 0.0300447742 0.0419400223 0.0139431600 0.1056970000 10498241 955859216 1765130240 0.0585712902 0.5322856903 0.9155864716 692 27.6400000000 0.0223529860 0.0300336589 0.0419400223 0.0139374125 0.0864330000 10499495 955859216 1765130240 0.0545416810 0.5319012403 0.9168398380 693 27.6800000000 0.0223011449 0.0300225009 0.0419400223 0.0139314646 0.0891820000 10500749 955859216 1765130240 0.0502997972 0.5313594937 0.9178773761 694 27.7200000000 0.0211428683 0.0300097060 0.0419400223 0.0139242914 0.0991010000 10502003 955859216 1765130240 0.0482971221 0.5329594612 0.9190887213 695 27.7600000000 0.0210171342 0.0299967671 0.0419400223 0.0139186142 0.0892070000 10503257 955859216 1765130240 0.0456145257 0.5333501697 0.9201583862 696 27.8000000000 0.0210691337 0.0299839400 0.0419400223 0.0139133046 0.0940180000 10504511 955859216 1765130240 0.0413888134 0.5316986442 0.9214540124 697 27.8400000000 0.0219468791 0.0299724091 0.0419400223 0.0139095439 0.0897240000 10505765 955859216 1765130240 0.0376485139 0.5313909054 0.9224734902 698 27.8800000000 0.0209165234 0.0299594350 0.0419400223 0.0139061012 0.0879310000 10507019 955859216 1765130240 0.0354238711 0.5326696038 0.9235177636 699 27.9200000000 0.0214563422 0.0299472704 0.0419400223 0.0139009150 0.0868610000 10508273 955859216 1765130240 0.0313266590 0.5327885747 0.9245603085 700 27.9600000000 0.0215873681 0.0299353277 0.0419400223 0.0138982932 0.1080700000 10509527 955859216 1765113856 0.0274590831 0.5327455997 0.9256365895 701 28.0000000000 0.0222153068 0.0299243148 0.0419400223 0.0138947707 0.1271940000 10510781 955859216 1764999168 0.0241990462 0.5328406096 0.9265689254 702 28.0400000000 0.0236028787 0.0299153099 0.0419400223 0.0138901890 0.0733760000 10512035 955859216 1765003264 0.0195300095 0.5335298777 0.9271610379 703 28.0800000000 0.0232447665 0.0299058212 0.0419400223 0.0138859666 0.0828380000 10513289 955859216 1765003264 0.0166923515 0.5343301296 0.9283733368 704 28.1200000000 0.0227864683 0.0298957085 0.0419400223 0.0138812816 0.1076040000 10514543 955859216 1765113856 0.0136416517 0.5346730947 0.9294312596 705 28.1600000000 0.0226476677 0.0298854276 0.0419400223 0.0138767624 0.0880050000 10515797 955859216 1765130240 0.0104853129 0.5345584154 0.9308976531 706 28.2000000000 0.0220909677 0.0298743873 0.0419400223 0.0138722736 0.0886460000 10517051 955859216 1765130240 0.0077090515 0.5339932442 0.9320504665 707 28.2400000000 0.0219021179 0.0298631111 0.0419400223 0.0138677058 0.0982470000 10518305 955859216 1765130240 0.0035663010 0.5337765813 0.9332271218 708 28.2800000000 0.0218681786 0.0298518188 0.0419400223 0.0138619491 0.0790180000 10519559 955859216 1765130240 0.0008816586 0.5332645774 0.9344214201 709 28.3200000000 0.0229569059 0.0298420940 0.0419400223 0.0138547017 0.0865860000 10520813 955859216 1765081088 -0.0026861678 0.5334745049 0.9354516864 710 28.3600000000 0.0227643382 0.0298321253 0.0419400223 0.0138485055 0.1086820000 10522067 955859216 1765130240 -0.0067921705 0.5337751508 0.9364249706 711 28.4000000000 0.0228220578 0.0298222659 0.0419400223 0.0138435465 0.0874570000 10523321 955859216 1765130240 -0.0108048767 0.5334105492 0.9377105236 712 28.4400000000 0.0231877752 0.0298129478 0.0419400223 0.0138370367 0.0883740000 10524575 955859216 1765130240 -0.0156592764 0.5330542922 0.9385999441 713 28.4800000000 0.0235528685 0.0298041678 0.0419400223 0.0138305117 0.1111210000 10525829 955859216 1765130240 -0.0200775899 0.5334368348 0.9395865798 714 28.5200000000 0.0229953360 0.0297946317 0.0419400223 0.0138245674 0.0865050000 10527083 955859216 1765130240 -0.0240528118 0.5332493782 0.9410170317 715 28.5600000000 0.0231572632 0.0297853486 0.0419400223 0.0138167796 0.1038380000 10528337 955859216 1765130240 -0.0285246577 0.5334707499 0.9422737360 716 28.6000000000 0.0226383116 0.0297753667 0.0419400223 0.0138114825 0.1319590000 10529591 955859216 1765130240 -0.0330758318 0.5329174995 0.9434517622 717 28.6400000000 0.0232191123 0.0297662227 0.0419400223 0.0138044248 0.1036990000 10530845 955859216 1765130240 -0.0375953726 0.5326431990 0.9442779422 718 28.6800000000 0.0234595630 0.0297574391 0.0419400223 0.0137982444 0.0897980000 10532099 955859216 1765081088 -0.0426811092 0.5330840349 0.9450933337 719 28.7200000000 0.0227854438 0.0297477423 0.0419400223 0.0137953413 0.0884870000 10533353 955859216 1765130240 -0.0471159257 0.5323644876 0.9460067749 720 28.7600000000 0.0235574078 0.0297391446 0.0419400223 0.0137962565 0.1246790000 10534607 955859216 1765130240 -0.0511392467 0.5318452716 0.9468786716 721 28.8000000000 0.0229416266 0.0297297167 0.0419400223 0.0137931787 0.0887090000 10535861 955859216 1766494208 -0.0548223145 0.5313719511 0.9481047392 722 28.8400000000 0.0226072818 0.0297198518 0.0419400223 0.0137886527 0.1099640000 10537115 955859216 1768509440 -0.0597781613 0.5306227803 0.9489830136 723 28.8800000000 0.0232086089 0.0297108460 0.0419400223 0.0137823297 0.1271920000 10538369 955859216 1770160128 -0.0638837218 0.5302591920 0.9498666525 724 28.9200000000 0.0230931044 0.0297017054 0.0419400223 0.0137753411 0.0886300000 10539623 955859216 1771810816 -0.0690835714 0.5298073888 0.9505767226 725 28.9600000000 0.0227607843 0.0296921317 0.0419400223 0.0137683066 0.0881580000 10540877 955859216 1773588480 -0.0732312649 0.5292984843 0.9518235922 726 29.0000000000 0.0231952537 0.0296831829 0.0419400223 0.0137617159 0.1107110000 10542131 955859216 1775239168 -0.0769528896 0.5289076567 0.9525428414 727 29.0400000000 0.0233594719 0.0296744845 0.0419400223 0.0137574747 0.0871160000 10543385 955859216 1776889856 -0.0805676207 0.5286970735 0.9533797503 728 29.0800000000 0.0230853818 0.0296654335 0.0419400223 0.0137543680 0.0874900000 10544639 955859216 1778667520 -0.0835009813 0.5279466510 0.9541264772 729 29.1200000000 0.0231805369 0.0296565379 0.0419400223 0.0137539877 0.1110930000 10545893 955859216 1780318208 -0.0865696371 0.5277904868 0.9547842145 730 29.1600000000 0.0230146013 0.0296474394 0.0419400223 0.0137519467 0.1272220000 10547147 955859216 1782112256 -0.0891657099 0.5268496275 0.9556940794 731 29.2000000000 0.0230158195 0.0296383674 0.0419400223 0.0137494957 0.1102480000 10548401 955859216 1783746560 -0.0932087302 0.5257523656 0.9559656382 732 29.2400000000 0.0232145526 0.0296295917 0.0419400223 0.0137460702 0.0862940000 10549655 955859216 1785397248 -0.0969097167 0.5257219076 0.9563518763 733 29.2800000000 0.0227164309 0.0296201604 0.0419400223 0.0137421244 0.0880050000 10550909 955859216 1787174912 -0.0998286381 0.5245871544 0.9570392966 734 29.3200000000 0.0230274908 0.0296111785 0.0419400223 0.0137352856 0.1095300000 10552163 955859216 1784668160 -0.1023425534 0.5236920118 0.9574303031 735 29.3600000000 0.0230851751 0.0296022996 0.0419400223 0.0137280640 0.1095340000 10553417 955859216 1783529472 -0.1056488603 0.5234260559 0.9575262070 736 29.4000000000 0.0225937106 0.0295927771 0.0419400223 0.0137228496 0.1180450000 10554671 955859216 1782382592 -0.1087843552 0.5224147439 0.9576739669 737 29.4400000000 0.0225562844 0.0295832296 0.0419400223 0.0137175705 0.0955860000 10555925 955859216 1781366784 -0.1116194725 0.5206364989 0.9578791261 738 29.4800000000 0.0222809538 0.0295733349 0.0419400223 0.0137106540 0.0888180000 10557179 955859216 1780240384 -0.1132688820 0.5193540454 0.9584717751 739 29.5200000000 0.0219786800 0.0295630580 0.0419400223 0.0137049801 0.0875910000 10558433 955859216 1779208192 -0.1147565991 0.5176131129 0.9588965178 740 29.5600000000 0.0226138476 0.0295536672 0.0419400223 0.0137016686 0.1096970000 10559687 955859216 1778192384 -0.1162034795 0.5152904391 0.9590902925 741 29.6000000000 0.0225018337 0.0295441505 0.0419400223 0.0136997277 0.0874590000 10560941 955859216 1777065984 -0.1181335896 0.5140977502 0.9595382214 742 29.6400000000 0.0220546536 0.0295340569 0.0419400223 0.0136962171 0.0867670000 10562195 955859216 1776033792 -0.1197771505 0.5132601261 0.9600185752 743 29.6800000000 0.0219502226 0.0295238498 0.0419400223 0.0136936201 0.1089730000 10563449 955859216 1775017984 -0.1210620925 0.5118795633 0.9601345062 744 29.7200000000 0.0219282005 0.0295136406 0.0419400223 0.0136946996 0.0879440000 10564703 955859216 1773891584 -0.1241645887 0.5081319213 0.9609272480 745 29.7600000000 0.0221569929 0.0295037659 0.0419400223 0.0136876104 0.0874480000 10565957 955859216 1772990464 -0.1250676364 0.5055853128 0.9615247846 746 29.8000000000 0.0226329789 0.0294945557 0.0419400223 0.0136797938 0.0904500000 10567211 955859216 1771859968 -0.1264207363 0.5044831634 0.9618225694 747 29.8400000000 0.0222175047 0.0294848140 0.0419400223 0.0136721486 0.0841800000 10568465 955859216 1770827776 -0.1276308745 0.5032416582 0.9623844028 748 29.8800000000 0.0223495644 0.0294752749 0.0419400223 0.0136630250 0.0858280000 10569719 955859216 1772208128 -0.1283746511 0.5016713142 0.9627695084 749 29.9200000000 0.0221543778 0.0294655007 0.0419400223 0.0136540420 0.0869290000 10570973 955859216 1771442176 -0.1294870377 0.5006280541 0.9631518126 750 29.9600000000 0.0220132638 0.0294555644 0.0419400223 0.0136449972 0.0865080000 10572227 955859216 1770807296 -0.1306676716 0.5003007650 0.9634976983 751 30.0000000000 0.0215021148 0.0294449739 0.0419400223 0.0136360933 0.0866650000 10573481 955859216 1769156608 -0.1311030239 0.4974317253 0.9642834067 752 30.0400000000 0.0220322888 0.0294351166 0.0419400223 0.0136273075 0.1072480000 10574735 955859216 1767174144 -0.1315300614 0.4951629043 0.9651178122 753 30.0800000000 0.0219018124 0.0294251122 0.0419400223 0.0136206932 0.1086100000 10575989 955859216 1766129664 -0.1323462874 0.4941689968 0.9659200907 754 30.1200000000 0.0215925779 0.0294147243 0.0419400223 0.0136143446 0.1213940000 10577243 955859216 1765081088 -0.1320440471 0.4926786721 0.9669193625 755 30.1600000000 0.0214464944 0.0294041703 0.0419400223 0.0136079874 0.0763350000 10578497 955859216 1765130240 -0.1321845353 0.4914599061 0.9681175947 756 30.2000000000 0.0206449088 0.0293925840 0.0419400223 0.0136000232 0.0811610000 10579751 955859216 1765130240 -0.1324735433 0.4912708402 0.9689744115 757 30.2400000000 0.0203199629 0.0293805990 0.0419400223 0.0135932839 0.0916750000 10581005 955859216 1765130240 -0.1327966452 0.4898721874 0.9700973630 758 30.2800000000 0.0202726778 0.0293685833 0.0419400223 0.0135882582 0.0849320000 10582259 955859216 1765130240 -0.1335685104 0.4911902249 0.9711767435 759 30.3200000000 0.0200776849 0.0293563423 0.0419400223 0.0135843271 0.0891130000 10583513 955859216 1765130240 -0.1340042651 0.4903537035 0.9723238945 760 30.3600000000 0.0202215761 0.0293443229 0.0419400223 0.0135835773 0.1068000000 10584767 955859216 1765130240 -0.1335980892 0.4880354404 0.9735246897 761 30.4000000000 0.0201486014 0.0293322392 0.0419400223 0.0135782911 0.1051040000 10586021 955859216 1764999168 -0.1330892146 0.4878078997 0.9750668406 762 30.4400000000 0.0199941564 0.0293199845 0.0419400223 0.0135696067 0.0902100000 10587275 955859216 1765003264 -0.1323248297 0.4873396158 0.9764783382 763 30.4800000000 0.0200631507 0.0293078523 0.0419400223 0.0135608916 0.0885970000 10588529 955859216 1765003264 -0.1312448829 0.4848677814 0.9781422019 764 30.5200000000 0.0198652167 0.0292954928 0.0419400223 0.0135557186 0.1269470000 10589783 955859216 1765113856 -0.1222640499 0.4830436110 0.9800538421 765 30.5600000000 0.0197247211 0.0292829820 0.0419400223 0.0135500288 0.0754310000 10591037 955859216 1765130240 -0.1240353510 0.4816277027 0.9816803336 766 30.6000000000 0.0198792778 0.0292707056 0.0419400223 0.0135478630 0.0773300000 10592291 955859216 1765130240 -0.1239061207 0.4800592959 0.9831592441 767 30.6400000000 0.0199846942 0.0292585987 0.0419400223 0.0135528210 0.0875320000 10593545 955859216 1765130240 -0.1220959276 0.4771327674 0.9848866463 768 30.6800000000 0.0196620021 0.0292461031 0.0419400223 0.0135609896 0.1278210000 10594799 955859216 1765130240 -0.1118993536 0.4762080908 0.9872069359 769 30.7200000000 0.0195890423 0.0292335452 0.0419400223 0.0136152305 0.1082510000 10596053 955859216 1765130240 -0.1052068844 0.4740435779 0.9909651279 770 30.7600000000 0.0194576215 0.0292208492 0.0419400223 0.0136501976 0.0865120000 10597307 955859216 1765130240 -0.1065379977 0.4695447981 0.9920448065 771 30.8000000000 0.0195081104 0.0292082516 0.0419400223 0.0136699383 0.0897530000 10598561 955859216 1765130240 -0.0975062773 0.4670680463 0.9939135909 772 30.8400000000 0.0193496533 0.0291954814 0.0419400223 0.0136954585 0.0871030000 10599815 955859216 1765130240 -0.0997018814 0.4660505652 0.9944106340 773 30.8800000000 0.0195290372 0.0291829763 0.0419400223 0.0137220428 0.1079150000 10601069 955859216 1765081088 -0.0989231244 0.4631900191 0.9957371354 774 30.9200000000 0.0193890408 0.0291703226 0.0419400223 0.0137420876 0.1270600000 10602323 955859216 1765113856 -0.0878351033 0.4589613378 0.9978182316 775 30.9600000000 0.0191132724 0.0291573458 0.0419400223 0.0137659931 0.0881870000 10603577 955859216 1766731776 -0.0893860683 0.4572391808 0.9982525706 776 31.0000000000 0.0192576516 0.0291445885 0.0419400223 0.0137868877 0.1304690000 10604831 955859216 1768763392 -0.0806083977 0.4543081820 1.0005532503 777 31.0400000000 0.0188963730 0.0291313990 0.0419400223 0.0138027134 0.1053760000 10606085 955859216 1770414080 -0.0819654092 0.4526359439 1.0014650822 778 31.0800000000 0.0191481039 0.0291185670 0.0419400223 0.0138081733 0.1493200000 10607339 955859216 1772191744 -0.0743090287 0.4487627745 1.0037719011 779 31.1200000000 0.0187201481 0.0291052186 0.0419400223 0.0138107701 0.1299710000 10608593 955859216 1773985792 -0.0758105218 0.4458276629 1.0051059723 780 31.1600000000 0.0191462021 0.0290924506 0.0419400223 0.0138082215 0.0751960000 10609847 955859216 1775620096 -0.0755469874 0.4430271685 1.0065906048 781 31.2000000000 0.0190723408 0.0290796208 0.0419400223 0.0138073699 0.0985080000 10611101 955859216 1777270784 -0.0663039461 0.4388297200 1.0095503330 782 31.2400000000 0.0186124705 0.0290662357 0.0419400223 0.0138071457 0.1107750000 10612355 955859216 1779048448 -0.0681146905 0.4353002906 1.0109673738 783 31.2800000000 0.0189612191 0.0290533301 0.0419400223 0.0138038871 0.0887790000 10613609 955859216 1780699136 -0.0607493967 0.4308218956 1.0139911175 784 31.3200000000 0.0184731465 0.0290398350 0.0419400223 0.0138016097 0.0862080000 10614863 955859216 1782476800 -0.0626224056 0.4262832701 1.0151052475 785 31.3600000000 0.0186996236 0.0290266628 0.0419400223 0.0137968197 0.1109450000 10616117 955859216 1784127488 -0.0625194758 0.4218660891 1.0165091753 786 31.4000000000 0.0188887920 0.0290137647 0.0419400223 0.0137900453 0.1085730000 10617371 955859216 1785921536 -0.0615412630 0.4182904661 1.0178325176 787 31.4400000000 0.0188319236 0.0290008272 0.0419400223 0.0137866642 0.0882270000 10618625 955859216 1787555840 -0.0535596646 0.4116086960 1.0208327770 788 31.4800000000 0.0183050931 0.0289872539 0.0419400223 0.0137859064 0.0844440000 10619879 955859216 1786564608 -0.0551233701 0.4072250724 1.0219827890 789 31.5200000000 0.0185431261 0.0289740167 0.0419400223 0.0137854043 0.1090670000 10621133 955859216 1784692736 -0.0552948639 0.4025757611 1.0232800245 790 31.5600000000 0.0187275428 0.0289610465 0.0419400223 0.0137851329 0.1269370000 10622387 955859216 1783672832 -0.0487033166 0.3955244720 1.0263578892 791 31.6000000000 0.0183617044 0.0289476466 0.0419400223 0.0138174699 0.0794840000 10623641 955859216 1782525952 -0.0522998497 0.3872388005 1.0279983282 792 31.6400000000 0.0182476901 0.0289341365 0.0419400223 0.0138149883 0.0882030000 10624895 955859216 1781383168 -0.0521839783 0.3832357526 1.0298731327 793 31.6800000000 0.0185641646 0.0289210597 0.0419400223 0.0138123515 0.0943140000 10626149 955859216 1780350976 -0.0462042205 0.3761762083 1.0332620144 794 31.7200000000 0.0181271918 0.0289074654 0.0419400223 0.0138083295 0.0894000000 10627403 955859216 1779335168 -0.0481154732 0.3751018643 1.0342631340 795 31.7600000000 0.0184469074 0.0288943074 0.0419400223 0.0138036842 0.1363550000 10628657 955859216 1778208768 -0.0462022834 0.3734844029 1.0364526510 796 31.8000000000 0.0185595211 0.0288813240 0.0419400223 0.0138005406 0.0944880000 10629911 955859216 1777176576 -0.0458086208 0.3681110144 1.0387209654 797 31.8400000000 0.0185396038 0.0288683482 0.0419400223 0.0138011892 0.0822400000 10631165 955859216 1776160768 -0.0457514226 0.3623784184 1.0413523912 798 31.8800000000 0.0186043307 0.0288554860 0.0419400223 0.0138682255 0.0956060000 10632419 955859216 1775292416 -0.0444436856 0.3442531228 1.0478366613 799 31.9200000000 0.0180863384 0.0288420078 0.0419400223 0.0138853304 0.0865740000 10633673 955859216 1774235648 -0.0455898382 0.3363454342 1.0501995087 800 31.9600000000 0.0180474706 0.0288285146 0.0419400223 0.0138918238 0.0889940000 10634927 955859216 1773387776 -0.0464856997 0.3320689499 1.0524108410 801 32.0000000000 0.0177963190 0.0288147416 0.0419400223 0.0138865914 0.1070250000 10636181 955859216 1772498944 -0.0470672548 0.3283977211 1.0553710461 802 32.0400000000 0.0177745540 0.0288009757 0.0419400223 0.0138780245 0.1078110000 10637435 955859216 1771610112 -0.0479421653 0.3204704821 1.0580862761 803 32.0800000000 0.0177300107 0.0287871887 0.0419400223 0.0138695521 0.0885510000 10638689 955859216 1770831872 -0.0486822762 0.3112002313 1.0613012314 804 32.1199999990 0.0181650743 0.0287739772 0.0419400223 0.0138627278 0.0890040000 10639943 955859216 1770070016 -0.0490304083 0.2957811058 1.0687381029 805 32.1600000000 0.0179136395 0.0287604861 0.0419400223 0.0138550492 0.0885160000 10641197 955859216 1769050112 -0.0503459536 0.2918900251 1.0717567205 806 32.2000000000 0.0176384617 0.0287466870 0.0419400223 0.0138464538 0.0858020000 10642451 955859216 1768181760 -0.0523474365 0.2869174182 1.0750132799 807 32.2400000000 0.0178709179 0.0287332102 0.0419400223 0.0138386446 0.0894460000 10643705 955859216 1767145472 -0.0527857654 0.2783914208 1.0789695978 808 32.2800000000 0.0174308307 0.0287192221 0.0419400223 0.0138304785 0.0846440000 10644959 955859216 1766129664 -0.0554948412 0.2727031112 1.0823433399 809 32.3200000000 0.0178574026 0.0287057959 0.0419400223 0.0138229813 0.0901590000 10646213 955859216 1765244928 -0.0552516207 0.2586925328 1.0877369642 810 32.3600000000 0.0178060997 0.0286923395 0.0419400223 0.0138144678 0.1077390000 10647467 955859216 1764999168 -0.0564014800 0.2470017970 1.0920884609 811 32.4000000000 0.0176698975 0.0286787483 0.0419400223 0.0138067727 0.0823140000 10648721 955859216 1765003264 -0.0589771941 0.2436118722 1.0957403183 812 32.4399999990 0.0177155472 0.0286652468 0.0419400223 0.0138006780 0.0880180000 10649975 955859216 1765003264 -0.0605574436 0.2372096926 1.1002451181 813 32.4800000000 0.0176355969 0.0286516802 0.0419400223 0.0137933404 0.0884170000 10651229 955859216 1765113856 -0.0620093606 0.2277769446 1.1051845551 814 32.5200000000 0.0176046621 0.0286381090 0.0419400223 0.0137853590 0.1096260000 10652483 955859216 1765130240 -0.0630525276 0.2167193890 1.1103518009 815 32.5600000000 0.0175860766 0.0286245482 0.0419400223 0.0137779405 0.0964920000 10653737 955859216 1765130240 -0.0641332045 0.2069648355 1.1153802872 816 32.6000000000 0.0176283587 0.0286110725 0.0419400223 0.0137698176 0.0788160000 10654991 955859216 1765130240 -0.0652409270 0.1999299228 1.1206278801 817 32.6400000000 0.0176045615 0.0285976006 0.0419400223 0.0137635435 0.0871550000 10656245 955859216 1765130240 -0.0661484227 0.1871002167 1.1276420355 818 32.6800000000 0.0175585710 0.0285841054 0.0419400223 0.0137551650 0.1088180000 10657499 955859216 1765105664 -0.0669761375 0.1708306819 1.1345524788 819 32.7200000000 0.0172948856 0.0285703213 0.0419400223 0.0137475911 0.0949620000 10658753 955859216 1765113856 -0.0681031421 0.1609287858 1.1397334337 820 32.7599999990 0.0172843654 0.0285565579 0.0419400223 0.0137393691 0.0992630000 10660007 955859216 1765113856 -0.0701997131 0.1547342986 1.1439074278 821 32.7999999990 0.0174056645 0.0285429758 0.0419400223 0.0137311694 0.1054200000 10661261 955859216 1765126144 -0.0714275464 0.1460022777 1.1487261057 822 32.8400000000 0.0173539072 0.0285293638 0.0419400223 0.0137239642 0.0905880000 10662515 955859216 1765126144 -0.0715470016 0.1343976110 1.1542905569 823 32.8800000000 0.0173075814 0.0285157286 0.0419400223 0.0137175823 0.0877730000 10663769 955859216 1765126144 -0.0714453980 0.1225476563 1.1600431204 824 32.9200000000 0.0172443632 0.0285020498 0.0419400223 0.0137101737 0.0885600000 10665023 955859216 1765126144 -0.0711353347 0.1118178666 1.1657874584 825 32.9600000000 0.0172760319 0.0284884425 0.0419400223 0.0137021874 0.0879960000 10666277 955859216 1765130240 -0.0713639334 0.1022230536 1.1706222296 826 33.0000000000 0.0168714430 0.0284743783 0.0419400223 0.0136949534 0.0869440000 10667531 955859216 1765130240 -0.0728517175 0.0937279835 1.1750802994 827 33.0400000000 0.0170851070 0.0284606065 0.0419400223 0.0136882433 0.1012400000 10668785 955859216 1765130240 -0.0720418990 0.0836176798 1.1800347567 828 33.0800000000 0.0171587095 0.0284469569 0.0419400223 0.0136817740 0.0775050000 10670039 955859216 1765130240 -0.0718659684 0.0759459585 1.1838330030 829 33.1199999990 0.0171068665 0.0284332777 0.0419400223 0.0136786156 0.0853630000 10671293 955859216 1765130240 -0.0716948807 0.0651411787 1.1881732941 830 33.1600000000 0.0171735901 0.0284197118 0.0419400223 0.0136746460 0.0882420000 10672547 955859216 1765130240 -0.0711602122 0.0519731678 1.1933757067 831 33.2000000000 0.0172238220 0.0284062390 0.0419400223 0.0136680915 0.0876150000 10673801 955859216 1765130240 -0.0705456659 0.0404424146 1.1978176832 832 33.2400000000 0.0168141667 0.0283923062 0.0419400223 0.0136640371 0.0879290000 10675055 955859216 1764999168 -0.0711335316 0.0323528238 1.2006391287 833 33.2800000000 0.0170656741 0.0283787088 0.0419400223 0.0136593023 0.1089850000 10676309 955859216 1765003264 -0.0705902949 0.0222744625 1.2043600082 834 33.3200000000 0.0170554332 0.0283651317 0.0419400223 0.0136517116 0.0895320000 10677563 955859216 1765003264 -0.0702420399 0.0132937990 1.2073588371 835 33.3600000000 0.0171023477 0.0283516434 0.0419400223 0.0136439506 0.0856020000 10678817 955859216 1765113856 -0.0693517998 0.0060612075 1.2098190784 836 33.4000000000 0.0170795918 0.0283381601 0.0419400223 0.0136400308 0.0876050000 10680071 955859216 1765130240 -0.0678522363 -0.0022121407 1.2129575014 837 33.4399999990 0.0171916056 0.0283248428 0.0419400223 0.0136390896 0.0881680000 10681325 955859216 1765130240 -0.0667017326 -0.0130133778 1.2165062428 838 33.4800000000 0.0171726514 0.0283115347 0.0419400223 0.0136343393 0.1090690000 10682579 955859216 1765113856 -0.0656117499 -0.0229692031 1.2194434404 839 33.5200000000 0.0170343947 0.0282980935 0.0419400223 0.0136264163 0.0874760000 10683833 955859216 1765113856 -0.0652626231 -0.0313867740 1.2213696241 840 33.5600000000 0.0170033276 0.0282846474 0.0419400223 0.0136185478 0.1066920000 10685087 955859216 1764999168 -0.0650181621 -0.0378135554 1.2225533724 841 33.6000000000 0.0174595080 0.0282717756 0.0419400223 0.0136177216 0.1032280000 10686341 955859216 1765003264 -0.0620437749 -0.0503921621 1.2267143726 842 33.6400000000 0.0174034443 0.0282588679 0.0419400223 0.0136101965 0.0910640000 10687595 955859216 1765003264 -0.0605866462 -0.0634217635 1.2308151722 843 33.6800000000 0.0181870200 0.0282469202 0.0419400223 0.0136024766 0.0878780000 10688849 955859216 1765113856 -0.0583387837 -0.0696568266 1.2318671942 844 33.7200000000 0.0180103946 0.0282347916 0.0419400223 0.0136000400 0.0880860000 10690103 955859216 1765130240 -0.0576459356 -0.0765229389 1.2326714993 845 33.7599999990 0.0178793930 0.0282225367 0.0419400223 0.0136023411 0.0894150000 10691357 955859216 1765130240 -0.0578313693 -0.0872802585 1.2342877388 846 33.7999999990 0.0179543011 0.0282103993 0.0419400223 0.0135994762 0.0868920000 10692611 955859216 1765130240 -0.0571803376 -0.0927006900 1.2346901894 847 33.8400000000 0.0178375877 0.0281981528 0.0419400223 0.0135991582 0.1097790000 10693865 955859216 1765113856 -0.0570410639 -0.0977887362 1.2347066402 848 33.8800000000 0.0179508291 0.0281860687 0.0419400223 0.0135965366 0.0872330000 10695119 955859216 1765113856 -0.0555039532 -0.1093302220 1.2379857302 849 33.9200000000 0.0187747385 0.0281749835 0.0419400223 0.0135896794 0.0874750000 10696373 955859216 1765130240 -0.0539773218 -0.1168727577 1.2395327091 850 33.9600000000 0.0195968300 0.0281648916 0.0419400223 0.0135842214 0.1079890000 10697627 955859216 1765130240 -0.0537913889 -0.1210429892 1.2390053272 851 34.0000000000 0.0193041638 0.0281544794 0.0419400223 0.0135775644 0.0873130000 10698881 955859216 1765130240 -0.0550042875 -0.1278564185 1.2394219637 852 34.0400000000 0.0195972230 0.0281444357 0.0419400223 0.0135704289 0.0879670000 10700135 955859216 1765130240 -0.0554474816 -0.1326653212 1.2390868664 853 34.0800000000 0.0194924939 0.0281342927 0.0419400223 0.0135675806 0.1024700000 10701389 955859216 1765130240 -0.0559344999 -0.1369722933 1.2385885715 854 34.1199999990 0.0191476438 0.0281237697 0.0419400223 0.0135664482 0.1273910000 10702643 955859216 1765130240 -0.0566720888 -0.1442052275 1.2388671637 855 34.1600000000 0.0195318479 0.0281137207 0.0419400223 0.0135602831 0.1302990000 10703897 955859216 1765130240 -0.0564409010 -0.1498851478 1.2392796278 856 34.2000000000 0.0188252870 0.0281028697 0.0419400223 0.0135536571 0.1032810000 10705151 955859216 1764954112 -0.0573246889 -0.1512214839 1.2377228737 857 34.2400000000 0.0192430951 0.0280925316 0.0419400223 0.0135513069 0.0880850000 10706405 955859216 1766604800 -0.0567736179 -0.1541024894 1.2365232706 858 34.2800000000 0.0190481301 0.0280819903 0.0419400223 0.0135515507 0.1090940000 10707659 955859216 1768779776 -0.0559305772 -0.1571203917 1.2357807159 859 34.3200000000 0.0193563383 0.0280718324 0.0419400223 0.0135559335 0.0869390000 10708913 955859216 1770430464 -0.0549596399 -0.1592540145 1.2342655659 860 34.3600000000 0.0192255490 0.0280615461 0.0419400223 0.0135546040 0.1086200000 10710167 955859216 1772208128 -0.0536925085 -0.1613497883 1.2331109047 861 34.4000000000 0.0193797164 0.0280514626 0.0419400223 0.0135519503 0.1264530000 10711421 955859216 1773985792 -0.0512659587 -0.1625853032 1.2325745821 862 34.4400000000 0.0192505997 0.0280412528 0.0419400223 0.0135619088 0.0881230000 10712675 955859216 1775636480 -0.0493816249 -0.1654464304 1.2321357727 863 34.4800000000 0.0195299014 0.0280313903 0.0419400223 0.0135720607 0.0877030000 10713929 955859216 1777414144 -0.0478945598 -0.1695428044 1.2318594456 864 34.5200000000 0.0204042736 0.0280225626 0.0419400223 0.0135795780 0.1105900000 10715183 955859216 1779048448 -0.0469284356 -0.1699543148 1.2296906710 865 34.5600000000 0.0196706895 0.0280129073 0.0419400223 0.0135827983 0.0896340000 10716437 955859216 1780826112 -0.0463468917 -0.1705495417 1.2280980349 866 34.6000000000 0.0192848891 0.0280028287 0.0419400223 0.0135820582 0.0884460000 10717691 955859216 1782493184 -0.0454732329 -0.1743070930 1.2275614738 867 34.6400000000 0.0201113187 0.0279937266 0.0419400223 0.0135777489 0.0850430000 10718945 955859216 1784143872 -0.0438585095 -0.1767516732 1.2268064022 868 34.6800000000 0.0202897694 0.0279848511 0.0419400223 0.0135719387 0.0885370000 10720199 955859216 1785921536 -0.0425235815 -0.1777732819 1.2253074646 869 34.7200000000 0.0199260600 0.0279755775 0.0419400223 0.0135657651 0.1087780000 10721453 955859216 1787572224 -0.0420862325 -0.1800042689 1.2245004177 870 34.7600000000 0.0198107287 0.0279661926 0.0419400223 0.0135591137 0.0864780000 10722707 955859216 1786810368 -0.0415271670 -0.1826527864 1.2237465382 871 34.8000000000 0.0197334737 0.0279567406 0.0419400223 0.0135541418 0.0850950000 10723961 955859216 1785049088 -0.0414222144 -0.1861284822 1.2228816748 872 34.8400000000 0.0198495854 0.0279474434 0.0419400223 0.0135487444 0.1084750000 10725215 955859216 1783042048 -0.0417664051 -0.1903624237 1.2227737904 873 34.8800000000 0.0203315914 0.0279387196 0.0419400223 0.0135416048 0.1114610000 10726469 955859216 1781891072 -0.0413593687 -0.1935121417 1.2222964764 874 34.9200000000 0.0204930026 0.0279302005 0.0419400223 0.0135347838 0.0854530000 10727723 955859216 1780731904 -0.0409104265 -0.1954601854 1.2212218046 875 34.9600000000 0.0201561581 0.0279213158 0.0419400223 0.0135281459 0.0870140000 10728977 955859216 1779716096 -0.0412861370 -0.1982831359 1.2206093073 876 35.0000000000 0.0202949662 0.0279126100 0.0419400223 0.0135206527 0.1095920000 10730231 955859216 1778700288 -0.0408431552 -0.2012000978 1.2204501629 877 35.0400000000 0.0204012189 0.0279040451 0.0419400223 0.0135130435 0.0881850000 10731485 955859216 1777573888 -0.0407117568 -0.2034782916 1.2193419933 878 35.0800000000 0.0201306678 0.0278951916 0.0419400223 0.0135056256 0.0858640000 10732739 955859216 1776541696 -0.0408229828 -0.2068039328 1.2184954882 879 35.1200000000 0.0203710571 0.0278866317 0.0419400223 0.0134980634 0.0879930000 10733993 955859216 1775673344 -0.0406768695 -0.2102271020 1.2179511786 880 35.1600000000 0.0211334731 0.0278789577 0.0419400223 0.0134908640 0.1101340000 10735247 955859216 1774637056 -0.0401520617 -0.2155868709 1.2157452106 881 35.2000000000 0.0208955612 0.0278710310 0.0419400223 0.0134839448 0.1075150000 10736501 955859216 1773510656 -0.0404750705 -0.2166637182 1.2140341997 882 35.2400000000 0.0201465301 0.0278622731 0.0419400223 0.0134789865 0.1102570000 10737755 955859216 1772367872 -0.0411162265 -0.2186075598 1.2127425671 883 35.2800000000 0.0201815255 0.0278535746 0.0419400223 0.0134750033 0.0842300000 10739009 955859216 1771466752 -0.0416200720 -0.2213399559 1.2113444805 884 35.3200000000 0.0203646012 0.0278451029 0.0419400223 0.0134745783 0.0868260000 10740263 955859216 1770446848 -0.0424062982 -0.2236732841 1.2093933821 885 35.3600000000 0.0202671550 0.0278365402 0.0419400223 0.0134778026 0.1088410000 10741517 955859216 1769431040 -0.0438354313 -0.2257516086 1.2077001333 886 35.4000000000 0.0204254258 0.0278281756 0.0419400223 0.0134814557 0.0876440000 10742771 955859216 1768415232 -0.0456636958 -0.2277310491 1.2059258223 887 35.4400000000 0.0206594896 0.0278200936 0.0419400223 0.0134866489 0.1080380000 10744025 955859216 1767546880 -0.0473996773 -0.2289103270 1.2040281296 888 35.4800000000 0.0201989468 0.0278115112 0.0419400223 0.0134901040 0.0874330000 10745279 955859216 1766658048 -0.0493798703 -0.2305825204 1.2021398544 889 35.5200000000 0.0205004197 0.0278032873 0.0419400223 0.0134996596 0.0871980000 10746533 955859216 1765621760 -0.0505085289 -0.2323400229 1.2004595995 890 35.5600000000 0.0207293071 0.0277953390 0.0419400223 0.0135068355 0.1083500000 10747787 955859216 1765122048 -0.0520059839 -0.2328989655 1.1986478567 891 35.6000000000 0.0199681055 0.0277865542 0.0419400223 0.0135131146 0.0879890000 10749041 955859216 1765130240 -0.0539911911 -0.2351444960 1.1972812414 892 35.6400000000 0.0207322091 0.0277786458 0.0419400223 0.0135236643 0.1069050000 10750295 955859216 1765085184 -0.0554290637 -0.2371010035 1.1953684092 893 35.6800000000 0.0208347049 0.0277708698 0.0419400223 0.0135355716 0.1090230000 10751549 955859216 1765130240 -0.0574156009 -0.2377268672 1.1934717894 894 35.7200000000 0.0203152001 0.0277625301 0.0419400223 0.0135494665 0.0853540000 10752803 955859216 1765130240 -0.0595482662 -0.2393983155 1.1921428442 895 35.7600000000 0.0206161700 0.0277545454 0.0419400223 0.0135665504 0.0881370000 10754057 955859216 1765130240 -0.0615493022 -0.2419338822 1.1909061670 896 35.8000000000 0.0215742104 0.0277476477 0.0419400223 0.0135909906 0.1271350000 10755311 955859216 1764999168 -0.0632864758 -0.2429900318 1.1891460419 897 35.8400000000 0.0217824746 0.0277409975 0.0419400223 0.0136095848 0.0886260000 10756565 955859216 1765003264 -0.0648967177 -0.2427440882 1.1880328655 898 35.8800000000 0.0212942567 0.0277338185 0.0419400223 0.0136202642 0.0866860000 10757819 955859216 1765003264 -0.0664161146 -0.2428947091 1.1866827011 899 35.9200000000 0.0214981604 0.0277268823 0.0419400223 0.0136309099 0.1085190000 10759073 955859216 1765003264 -0.0674123839 -0.2432388663 1.1864202023 900 35.9600000000 0.0216448717 0.0277201245 0.0419400223 0.0136355202 0.0874830000 10760327 955859216 1765113856 -0.0684793219 -0.2438315302 1.1855393648 901 36.0000000000 0.0199192408 0.0277114665 0.0419400223 0.0136454894 0.0897490000 10761581 955859216 1765081088 -0.0597396940 -0.2431683391 1.1876398325 902 36.0400000000 0.0201351289 0.0277030670 0.0419400223 0.0136638206 0.0853380000 10762835 955859216 1765130240 -0.0643805712 -0.2442466915 1.1857513189 903 36.0800000000 0.0202819221 0.0276948487 0.0419400223 0.0136793230 0.1268600000 10764089 955859216 1765130240 -0.0681962445 -0.2446644604 1.1834791899 904 36.1200000000 0.0201925542 0.0276865497 0.0419400223 0.0137018380 0.1078370000 10765343 955859216 1765130240 -0.0708393976 -0.2453777045 1.1823143959 905 36.1600000000 0.0204715617 0.0276785773 0.0419400223 0.0137254471 0.0848710000 10766597 955859216 1765130240 -0.0724861547 -0.2460309267 1.1809866428 906 36.2000000000 0.0204926468 0.0276706458 0.0419400223 0.0137514526 0.0868190000 10767851 955859216 1765130240 -0.0742028132 -0.2458753139 1.1799052954 907 36.2400000000 0.0200064592 0.0276621958 0.0419400223 0.0137744063 0.1098980000 10769105 955859216 1765130240 -0.0755339712 -0.2466872633 1.1793323755 908 36.2800000000 0.0204177368 0.0276542173 0.0419400223 0.0137897118 0.0865790000 10770359 955859216 1766494208 -0.0765929446 -0.2470233589 1.1787186861 909 36.3200000000 0.0202023014 0.0276460194 0.0419400223 0.0137993052 0.1083980000 10771613 955859216 1768398848 -0.0780020505 -0.2470885217 1.1780284643 910 36.3600000000 0.0199566558 0.0276375695 0.0419400223 0.0138066828 0.1271060000 10772867 955859216 1770033152 -0.0794014037 -0.2474277914 1.1774983406 911 36.4000000000 0.0197424777 0.0276289031 0.0419400223 0.0138142330 0.1274270000 10774121 955859216 1771700224 -0.0805927962 -0.2482909411 1.1771497726 912 36.4400000000 0.0198668856 0.0276203922 0.0419400223 0.0138197130 0.1302290000 10775375 955859216 1773477888 -0.0819690377 -0.2498780638 1.1770305634 913 36.4800000000 0.0198811963 0.0276119155 0.0419400223 0.0138705492 0.1079340000 10776629 955859216 1775128576 -0.0784525424 -0.2497685552 1.1787666082 914 36.5200000000 0.0193771906 0.0276029059 0.0419400223 0.0139002465 0.0864740000 10777883 955859216 1776906240 -0.0821581483 -0.2502246201 1.1773952246 915 36.5600000000 0.0194154065 0.0275939579 0.0419400223 0.0139213010 0.0880580000 10779137 955859216 1778683904 -0.0849506035 -0.2506098151 1.1767377853 916 36.6000000000 0.0194476098 0.0275850645 0.0419400223 0.0139408339 0.1108260000 10780391 955859216 1780334592 -0.0875082463 -0.2507709563 1.1759191751 917 36.6400000000 0.0194227342 0.0275761633 0.0419400223 0.0139547048 0.0851510000 10781645 955859216 1782095872 -0.0899414420 -0.2511124015 1.1752837896 918 36.6800000000 0.0193860065 0.0275672416 0.0419400223 0.0139693928 0.0893080000 10782899 955859216 1783762944 -0.0920429975 -0.2515698373 1.1748149395 919 36.7200000000 0.0193850137 0.0275583382 0.0419400223 0.0139873405 0.1081730000 10784153 955859216 1785397248 -0.0937856436 -0.2520999908 1.1746107340 920 36.7600000000 0.0194950439 0.0275495737 0.0419400223 0.0140049152 0.0880220000 10785407 955859216 1787174912 -0.0953322873 -0.2520256042 1.1741404533 921 36.8000000000 0.0190637466 0.0275403600 0.0419400223 0.0140167087 0.1071220000 10786661 955859216 1784516608 -0.0973661467 -0.2521329522 1.1740772724 922 36.8400000000 0.0191543512 0.0275312646 0.0419400223 0.0140254717 0.0871350000 10787915 955859216 1783525376 -0.0994519517 -0.2529718280 1.1742401123 923 36.8800000000 0.0195501707 0.0275226177 0.0419400223 0.0140314731 0.0874370000 10789169 955859216 1782398976 -0.1014377475 -0.2538652122 1.1746902466 924 36.9200000000 0.0198809430 0.0275143475 0.0419400223 0.0140342922 0.1097700000 10790423 955859216 1781366784 -0.1032878160 -0.2548205554 1.1746823788 925 36.9600000000 0.0200942885 0.0275063258 0.0419400223 0.0140376625 0.1085090000 10791677 955859216 1780240384 -0.1049405262 -0.2551783025 1.1747440100 926 37.0000000000 0.0198125094 0.0274980171 0.0419400223 0.0140421844 0.1043170000 10792931 955859216 1779208192 -0.1063078940 -0.2550376952 1.1747697592 927 37.0400000000 0.0194092244 0.0274892913 0.0419400223 0.0140493648 0.1016940000 10794185 955859216 1778192384 -0.1075481996 -0.2553112805 1.1751968861 928 37.0800000000 0.0197110791 0.0274809097 0.0419400223 0.0140599330 0.0945750000 10795439 955859216 1777197056 -0.1088876203 -0.2552959025 1.1753535271 929 37.1200000000 0.0194775499 0.0274722946 0.0419400223 0.0140726063 0.1070850000 10796693 955859216 1776050176 -0.1106362864 -0.2542554438 1.1746778488 930 37.1600000000 0.0189523809 0.0274631334 0.0419400223 0.0140831070 0.0883730000 10797947 955859216 1775017984 -0.1126114875 -0.2531882524 1.1739735603 931 37.2000000000 0.0202475935 0.0274553831 0.0419400223 0.0140918212 0.1066790000 10799201 955859216 1774002176 -0.1076723039 -0.2540565729 1.1782228947 932 37.2400000000 0.0194168445 0.0274467581 0.0419400223 0.0141219682 0.0885980000 10800455 955859216 1772986368 -0.1121097207 -0.2542227805 1.1756180525 933 37.2800000000 0.0192033239 0.0274379227 0.0419400223 0.0141577109 0.1102860000 10801709 955859216 1771970560 -0.1154605523 -0.2536651492 1.1730954647 934 37.3200000000 0.0190404002 0.0274289317 0.0419400223 0.0141896139 0.0863040000 10802963 955859216 1770954752 -0.1185332090 -0.2522330582 1.1715060472 935 37.3600000000 0.0204893555 0.0274215097 0.0419400223 0.0141998893 0.0888660000 10804217 955859216 1769938944 -0.1150340587 -0.2521019280 1.1739475727 936 37.4000000000 0.0189721882 0.0274124827 0.0419400223 0.0142259664 0.1063790000 10805471 955859216 1769070592 -0.1198989749 -0.2512422204 1.1707983017 937 37.4400000000 0.0205919035 0.0274052035 0.0419400223 0.0142309186 0.1074410000 10806725 955859216 1768054784 -0.1180130318 -0.2503892183 1.1727528572 938 37.4800000000 0.0185173489 0.0273957282 0.0419400223 0.0142443223 0.0900560000 10807979 955859216 1767018496 -0.1229586899 -0.2490953803 1.1695722342 939 37.5200000000 0.0206604153 0.0273885553 0.0419400223 0.0142484244 0.0840680000 10809233 955859216 1766002688 -0.1205883473 -0.2502138019 1.1719746590 940 37.5600000000 0.0190689918 0.0273797047 0.0419400223 0.0142585461 0.0832660000 10810487 955859216 1767383040 -0.1250171661 -0.2494416684 1.1688978672 941 37.6000000000 0.0207408983 0.0273726497 0.0419400223 0.0142618397 0.1096290000 10811741 955859216 1764978688 -0.1232566908 -0.2495084703 1.1703320742 942 37.6400000000 0.0186792221 0.0273634210 0.0419400223 0.0142702796 0.0831760000 10812995 955859216 1765003264 -0.1279311627 -0.2482592463 1.1662420034 943 37.6800000000 0.0208186675 0.0273564806 0.0419400223 0.0142754341 0.1305970000 10814249 955859216 1765113856 -0.1256089509 -0.2497093678 1.1684635878 944 37.7200000000 0.0187273771 0.0273473396 0.0419400223 0.0142853856 0.0871790000 10815503 955859216 1765113856 -0.1297255903 -0.2489169389 1.1657903194 945 37.7600000000 0.0182351135 0.0273376971 0.0419400223 0.0142909707 0.0697160000 10816757 955859216 1765027840 -0.1323092431 -0.2484618723 1.1658908129 946 37.8000000000 0.0208807699 0.0273308716 0.0419400223 0.0142944103 0.0884910000 10818011 955859216 1764995072 -0.1293878704 -0.2501555383 1.1693629026 947 37.8400000000 0.0195179805 0.0273226214 0.0419400223 0.0143020357 0.0851580000 10819265 955859216 1764995072 -0.1330399960 -0.2493901849 1.1668676138 948 37.8800000000 0.0185823385 0.0273134017 0.0419400223 0.0143036989 0.0861980000 10820519 955859216 1765122048 -0.1357132792 -0.2488298714 1.1672441959 949 37.9200000000 0.0208041612 0.0273065427 0.0419400223 0.0143066947 0.1110730000 10821773 955859216 1765027840 -0.1334757209 -0.2439034283 1.1795343161 950 37.9600000000 0.0194944311 0.0272983194 0.0419400223 0.0143116575 0.0819560000 10823027 955859216 1765011456 -0.1375181675 -0.2399798632 1.1853914261 951 38.0000000000 0.0206214599 0.0272912985 0.0419400223 0.0143166525 0.1080690000 10824281 955859216 1765011456 -0.1365541965 -0.2375403941 1.1923508644 952 38.0400000000 0.0193350539 0.0272829411 0.0419400223 0.0143228631 0.0876090000 10825535 955859216 1765122048 -0.1398645192 -0.2364823222 1.1902962923 953 38.0800000000 0.0187194273 0.0272739552 0.0419400223 0.0143207109 0.0907740000 10826789 955859216 1765027840 -0.1421268433 -0.2359243631 1.1896580458 954 38.1200000000 0.0206400398 0.0272670015 0.0419400223 0.0143230156 0.0849890000 10828043 955859216 1765011456 -0.1397547275 -0.2360353321 1.1942685843 955 38.1600000000 0.0197407696 0.0272591206 0.0419400223 0.0143299763 0.0676970000 10829297 955859216 1766375424 -0.1425174475 -0.2362885475 1.1911675930 956 38.2000000000 0.0194564685 0.0272509588 0.0419400223 0.0143328089 0.0679430000 10830551 955859216 1765851136 -0.1444088370 -0.2355847955 1.1907024384 957 38.2400000000 0.0197368935 0.0272431071 0.0419400223 0.0143319945 0.1047920000 10831805 955859216 1765126144 -0.1461264938 -0.2348512411 1.1902372837 958 38.2800000000 0.0215497520 0.0272371642 0.0419400223 0.0143357345 0.0893730000 10833059 955859216 1765027840 -0.1439419091 -0.2364202887 1.1900995970 959 38.3200000000 0.0211438108 0.0272308103 0.0419400223 0.0143379032 0.0693540000 10834313 955859216 1765027840 -0.1466731429 -0.2365131080 1.1889894009 960 38.3600000000 0.0215464309 0.0272248891 0.0419400223 0.0143385575 0.0838060000 10835567 955859216 1765027840 -0.1487353742 -0.2353769839 1.1904294491 961 38.4000000000 0.0255136453 0.0272231084 0.0419400223 0.0143472017 0.0895220000 10836821 955859216 1765027840 -0.1475763321 -0.2353553474 1.1949987411 962 38.4400000000 0.0281530973 0.0272240751 0.0419400223 0.0143459494 0.0695810000 10838075 955859216 1765122048 -0.1505018920 -0.2353360355 1.1975368261 963 38.4800000000 0.0387543328 0.0272360484 0.0419400223 0.0143583697 0.0976340000 10839329 955859216 1765023744 -0.1500675529 -0.2365171611 1.2069518566 964 38.5200000000 0.0420572236 0.0272514230 0.0420572236 0.0143604006 0.0793270000 10840583 955859216 1765011456 -0.1532800347 -0.2351403236 1.2116783857 965 38.5600000000 0.0544879958 0.0272796475 0.0544879958 0.0143798876 0.1044570000 10841837 955859216 1765011456 -0.1527692229 -0.2350895703 1.2232346535 966 38.6000000000 0.0611286685 0.0273146879 0.0611286685 0.0143847315 0.0681840000 10843091 955859216 1765027840 -0.1560541093 -0.2336214185 1.2297655344 967 38.6400000000 0.0747459754 0.0273637378 0.0747459754 0.0144077052 0.1075020000 10844345 955859216 1765011456 -0.1555114836 -0.2329341173 1.2459195852 968 38.6800000000 0.0878883526 0.0274262632 0.0878883526 0.0144208477 0.0981690000 10845599 955859216 1765011456 -0.1568683684 -0.2340287268 1.2569403648 969 38.7200000000 0.0944621265 0.0274954437 0.0944621265 0.0144334703 0.1153870000 10846853 955859216 1765122048 -0.1600447297 -0.2323680520 1.2641481161 970 38.7600000000 0.1130111814 0.0275836042 0.1130111814 0.0144607383 0.0865530000 10848107 955859216 1765027840 -0.1596349180 -0.2329306006 1.2813311815 971 38.8000000000 0.1271217614 0.0276861152 0.1271217614 0.0144725852 0.0870020000 10849361 955859216 1765027840 -0.1611267924 -0.2334326506 1.2934007645 972 38.8400000000 0.1407684833 0.0278024551 0.1407684833 0.0144835207 0.1287690000 10850615 955859216 1765027840 -0.1626615971 -0.2324396670 1.3066771030 973 38.8800000000 0.1568536907 0.0279350874 0.1568536907 0.0144978325 0.1094700000 10851869 955859216 1765122048 -0.1638529897 -0.2322219312 1.3216536045 974 38.9200000000 0.1708597243 0.0280818273 0.1708597243 0.0145066873 0.0888910000 10853123 955859216 1765027840 -0.1651542634 -0.2311330587 1.3358985186 975 38.9600000000 0.1883657724 0.0282462211 0.1883657724 0.0145231192 0.0852780000 10854377 955859216 1764962304 -0.1665209830 -0.2298774421 1.3529261351 976 39.0000000000 0.2061034888 0.0284284519 0.2061034888 0.0145384875 0.1047510000 10855631 955859216 1764995072 -0.1679156721 -0.2302574962 1.3690781593 977 39.0400000000 0.2207030356 0.0286252529 0.2207030356 0.0145458865 0.0878730000 10856885 955859216 1766486016 -0.1691221893 -0.2290493995 1.3831974268 978 39.0800000000 0.2406444699 0.0288420415 0.2406444699 0.0145658702 0.0886240000 10858139 955859216 1768517632 -0.1703117788 -0.2285558432 1.4012302160 979 39.1200000000 0.2603680491 0.0290785338 0.2603680491 0.0145856826 0.0867050000 10859393 955859216 1770168320 -0.1714057624 -0.2291978002 1.4181824923 980 39.1600000000 0.2807495594 0.0293353410 0.2807495594 0.0146047781 0.0956410000 10860647 955859216 1771819008 -0.1727774441 -0.2282230556 1.4368607998 981 39.2000000000 0.3020610511 0.0296133488 0.3020610511 0.0146266195 0.1234480000 10861901 955859216 1773596672 -0.1739104688 -0.2278745770 1.4575912952 982 39.2400000000 0.3235783279 0.0299127022 0.3235783279 0.0146427024 0.0797940000 10863155 955859216 1775247360 -0.1751863509 -0.2271354496 1.4773861170 983 39.2800000000 0.3471520245 0.0302354278 0.3471520245 0.0146610282 0.1062480000 10864409 955859216 1777041408 -0.1764418930 -0.2258710563 1.4994648695 984 39.3200000000 0.3763842881 0.0305872051 0.3763842881 0.0147113481 0.0966710000 10865663 955859216 1778675712 -0.1774495393 -0.2252071053 1.5277873278 985 39.3600000000 0.4134958386 0.0309759449 0.4134958386 0.0147613874 0.0756270000 10866917 955859216 1780326400 -0.1788297296 -0.2241294235 1.5622808933 986 39.4000000000 0.4541856647 0.0314051636 0.4541856647 0.0148533964 0.1007260000 10868171 955859216 1782104064 -0.1796372831 -0.2233951092 1.6013756990 987 39.4400000000 0.4902174771 0.0318700191 0.4902174771 0.0148988940 0.1081840000 10869425 955859216 1783754752 -0.1810335070 -0.2226488292 1.6357355118 988 39.4800000000 0.5506071448 0.0323950566 0.5506071448 0.0150796830 0.1047870000 10870679 955859216 1785405440 -0.1815849245 -0.2227582186 1.6946551800 989 39.5200000000 0.6099643111 0.0329790498 0.6099643111 0.0151867748 0.0896530000 10871933 955859216 1787183104 -0.1838202029 -0.2208460122 1.7514190674 990 39.5600000000 0.6897273660 0.0336424320 0.6897273660 0.0153929826 0.0761750000 10873187 955859216 1786183680 -0.1861136109 -0.2182574123 1.8299504519 991 39.6000000000 0.7666941881 0.0343821411 0.7666941881 0.0155971460 0.1043430000 10874441 955859216 1785438208 -0.1884665936 -0.2162894458 1.9042237997 992 39.6400000000 0.8251281977 0.0351792641 0.8251281977 0.0157146315 0.0963610000 10875695 955859216 1786818560 -0.1902814209 -0.2145078629 1.9606157541 993 39.6800000000 0.8719388247 0.0360219223 0.8719388247 0.0158572632 0.0855690000 10876949 955859216 1785933824 -0.1905218661 -0.2157893479 2.0055549145 994 39.7200000000 0.9084015489 0.0368995678 0.9084015489 0.0158863717 0.1026390000 10878203 955859216 1784303616 -0.1915361583 -0.2159245759 2.0384695530 995 39.7600000000 0.9320040941 0.0377991704 0.9320040941 0.0158934503 0.0937330000 10879457 955859216 1783169024 -0.1929506063 -0.2131741345 2.0589334965 996 39.8000000000 0.9574824572 0.0387225471 0.9574824572 0.0159139025 0.1479420000 10880711 955859216 1782136832 -0.1949785948 -0.2096384764 2.0819449425 997 39.8400000000 0.9780011773 0.0396646521 0.9780011773 0.0159287080 0.0913180000 10881965 955859216 1781010432 -0.1961705983 -0.2073411196 2.1008777618 998 39.8800000000 0.9981594682 0.0406250677 0.9981594682 0.0159422964 0.0851090000 10883219 955859216 1780125696 -0.1971821040 -0.2051050216 2.1189408302 999 39.9200000000 1.0276118517 0.0416130425 1.0276118517 0.0160920673 0.1264770000 10884473 955859216 1779236864 -0.1964941025 -0.2067039311 2.1437726021 1000 39.9600000000 1.0340963602 0.0426055258 1.0340963602 0.0160860535 0.0882950000 10885727 955859216 1778200576 -0.1987514645 -0.2021578848 2.1483607292 1001 40.0000000000 1.0420687199 0.0436039905 1.0420687199 0.0160796990 0.0748730000 10886981 955859216 1777442816 -0.2002727687 -0.1989894658 2.1538982391 1002 40.0400000000 1.0562705994 0.0446146359 1.0562705994 0.0161800184 0.0927750000 10888235 955859216 1776422912 -0.1981042773 -0.2034853250 2.1660048962 1003 40.0800000000 1.0597903728 0.0456267752 1.0597903728 0.0161721364 0.0781610000 10889489 955859216 1775427584 -0.1997340024 -0.1992245167 2.1678066254 1004 40.1200000000 1.0672533512 0.0466443315 1.0672533512 0.0161655713 0.0755260000 10890743 955859216 1774391296 -0.2009744346 -0.1962253451 2.1718094349 1005 40.1600000000 1.0710592270 0.0476636498 1.0710592270 0.0161587850 0.0887470000 10891997 955859216 1773375488 -0.2018482536 -0.1932223886 2.1747894287 1006 40.2000000000 1.0794416666 0.0486892741 1.0794416666 0.0162926975 0.0859500000 10893251 955859216 1772359680 -0.1990845054 -0.2006036490 2.1806495190 1007 40.2400000000 1.0819417238 0.0497153441 1.0819417238 0.0162867275 0.0855730000 10894505 955859216 1771343872 -0.2005503029 -0.1958793104 2.1796262264 1008 40.2800000000 1.0850296021 0.0507424415 1.0850296021 0.0162802826 0.0719360000 10895759 955859216 1770475520 -0.2017753720 -0.1919667274 2.1803839207 1009 40.3200000000 1.0941174030 0.0517765099 1.0941174030 0.0163586669 0.1076380000 10897013 955859216 1769439232 -0.1996848285 -0.1981370896 2.1866023540 1010 40.3600000000 1.0981523991 0.0528125256 1.0981523991 0.0163538024 0.0892140000 10898267 955859216 1768423424 -0.2014269978 -0.1920786202 2.1870265007 1011 40.4000000000 1.1049995422 0.0538532645 1.1049995422 0.0163474093 0.0701080000 10899521 955859216 1769803776 -0.2024617791 -0.1875774562 2.1899924278 1012 40.4400000000 1.1114747524 0.0548983450 1.1114747524 0.0163420494 0.0857790000 10900775 955859216 1768931328 -0.2032375187 -0.1832960248 2.1934957504 1013 40.4800000000 1.1204364300 0.0559502089 1.1204364300 0.0164941379 0.1395460000 10902029 955859216 1767374848 -0.2003989071 -0.1930479407 2.2000591755 1014 40.5200000000 1.1212661266 0.0570008163 1.1212661266 0.0164865684 0.0885240000 10903283 955859216 1768771584 -0.2018476725 -0.1866414696 2.1985888481 1015 40.5600000000 1.1226083040 0.0580506759 1.1226083040 0.0164787744 0.0768840000 10904537 955859216 1770668032 -0.2031882852 -0.1801017225 2.1976191998 1016 40.6000000000 1.1241047382 0.0590999417 1.1241047382 0.0164714804 0.0933090000 10905791 955859216 1772318720 -0.2041515708 -0.1749161035 2.1973423958 1017 40.6400000000 1.1268104315 0.0601498045 1.1268104315 0.0164647267 0.1117290000 10907045 955859216 1773969408 -0.2048145831 -0.1704877168 2.1972990036 1018 40.6800000000 1.1300624609 0.0612007993 1.1300624609 0.0164594730 0.0852440000 10908299 955859216 1775747072 -0.2055703849 -0.1656966954 2.1983997822 1019 40.7200000000 1.1339038610 0.0622535010 1.1339038610 0.0166352769 0.0791700000 10909553 955859216 1777397760 -0.2040805072 -0.1764455736 2.2004594803 1020 40.7600000000 1.1316881180 0.0633019663 1.1339038610 0.0166271142 0.0812040000 10910807 955859216 1779048448 -0.2053720653 -0.1706864238 2.1967327595 1021 40.8000000000 1.1315380335 0.0643482308 1.1339038610 0.0166197324 0.0775610000 10912061 955859216 1780826112 -0.2062881738 -0.1660191864 2.1944148540 1022 40.8400000000 1.1312476397 0.0653921637 1.1339038610 0.0166127262 0.1128420000 10913315 955859216 1782476800 -0.2070930153 -0.1619485617 2.1929430962 1023 40.8800000000 1.1310138702 0.0664338272 1.1339038610 0.0166058250 0.0833850000 10914569 955859216 1784254464 -0.2079225332 -0.1573529989 2.1915473938 1024 40.9200000000 1.1318124533 0.0674742360 1.1339038610 0.0166026217 0.0707790000 10915823 955859216 1785905152 -0.2087337375 -0.1533661336 2.1906838417 1025 40.9600000000 1.1328293085 0.0685136068 1.1339038610 0.0166020581 0.1080490000 10998997 955859216 1787555840 -0.2093730420 -0.1489516199 2.1903667450 1026 41.0000000000 1.1354705095 0.0695535258 1.1354705095 0.0165978050 0.1089380000 11168187 955859216 1784664064 -0.2103962451 -0.1421753317 2.1903157234 1027 41.0400000000 1.1372759342 0.0705931776 1.1372759342 0.0165959052 0.0866760000 11169441 955859216 1783541760 -0.2113084495 -0.1376460493 2.1899700165 1028 41.0800000000 1.1378307343 0.0716313464 1.1378307343 0.0165936179 0.0891450000 11170695 955859216 1782398976 -0.2120488584 -0.1324456185 2.1891319752 1029 41.1200000000 1.1394087076 0.0726690309 1.1394087076 0.0165896537 0.0695640000 11171949 955859216 1783762944 -0.2126922309 -0.1281618923 2.1886227131 1030 41.1600000000 1.1398196220 0.0737050995 1.1398196220 0.0165872325 0.0797080000 11173203 955859216 1783033856 -0.2132475525 -0.1261371970 2.1870980263 1031 41.2000000000 1.1411536932 0.0747404521 1.1411536932 0.0165851379 0.0894550000 11174457 955859216 1781891072 -0.2139338553 -0.1216187328 2.1861779690 1032 41.2400000000 1.1417431831 0.0757743695 1.1417431831 0.0165800560 0.0832100000 11175711 955859216 1780826112 -0.2142264247 -0.1184886470 2.1849455833 1033 41.2800000000 1.1417394876 0.0768062815 1.1417431831 0.0165745211 0.0873990000 11176965 955859216 1779843072 -0.2146282196 -0.1167511418 2.1836073399 1034 41.3200000000 1.1438441277 0.0778382330 1.1438441277 0.0165779062 0.0871170000 11178219 955859216 1778716672 -0.2154804766 -0.1095166057 2.1823871136 1035 41.3600000000 1.1422748566 0.0788666742 1.1438441277 0.0165733112 0.0928300000 11179473 955859216 1777684480 -0.2156572044 -0.1091012955 2.1798319817 1036 41.4000000000 1.1420171261 0.0798928812 1.1438441277 0.0165716829 0.0821800000 11180727 955859216 1776668672 -0.2163637578 -0.1059418172 2.1777663231 1037 41.4400000000 1.1419657469 0.0809170595 1.1438441277 0.0165707386 0.0865690000 11181981 955859216 1775652864 -0.2168415636 -0.1022357196 2.1765460968 1038 41.4800000000 1.1424092054 0.0819396916 1.1438441277 0.0165676059 0.0893410000 11183235 955859216 1774526464 -0.2174041122 -0.0994815454 2.1751174927 1039 41.5200000000 1.1426094770 0.0829605480 1.1438441277 0.0165663214 0.1092560000 11184489 955859216 1773383680 -0.2179962248 -0.0952793881 2.1737654209 1040 41.5600000000 1.1418554783 0.0839787162 1.1438441277 0.0165650523 0.0871920000 11185743 955859216 1772478464 -0.2183424234 -0.0919221565 2.1716606617 1041 41.6000000000 1.1416958570 0.0849947749 1.1438441277 0.0165622437 0.0874100000 11186997 955859216 1771335680 -0.2187708914 -0.0880484506 2.1704478264 1042 41.6400000000 1.1410123110 0.0860082275 1.1438441277 0.0165611555 0.0846350000 11188251 955859216 1770414080 -0.2190606594 -0.0841949284 2.1684467793 1043 41.6800000000 1.1406815052 0.0870194195 1.1438441277 0.0165611042 0.0698950000 11189505 955859216 1769431040 -0.2192608863 -0.0800431520 2.1666650772 1044 41.7200000000 1.1405919790 0.0880285886 1.1438441277 0.0165598572 0.1036980000 11190759 955859216 1768415232 -0.2194090635 -0.0774078071 2.1657743454 1045 41.7600000000 1.1402944326 0.0890355416 1.1438441277 0.0165585398 0.1077880000 11192013 955859216 1767399424 -0.2196656764 -0.0750732571 2.1653614044 1046 41.8000000000 1.1405889988 0.0900408508 1.1438441277 0.0165580016 0.0891040000 11193267 955859216 1766531072 -0.2199014276 -0.0736582652 2.1647269726 1047 41.8400000000 1.1411520243 0.0910447774 1.1438441277 0.0165567886 0.0848150000 11194521 955859216 1765494784 -0.2200130969 -0.0739326254 2.1649878025 1048 41.8800000000 1.1413247585 0.0920469530 1.1438441277 0.0165511695 0.1031280000 11195775 955859216 1764995072 -0.2202984542 -0.0720869303 2.1641421318 1049 41.9200000000 1.1409391165 0.0930468502 1.1438441277 0.0165471631 0.0888120000 11197029 955859216 1765003264 -0.2204763591 -0.0700602829 2.1625084877 1050 41.9600000000 1.1398997307 0.0940438529 1.1438441277 0.0165412860 0.0845910000 11198283 955859216 1765003264 -0.2205522507 -0.0675201789 2.1604332924 1051 42.0000000000 1.1382513046 0.0950373900 1.1438441277 0.0165356701 0.0544470000 11199537 955859216 1765113856 -0.2204423994 -0.0665748119 2.1579351425 1052 42.0400000000 1.1378111839 0.0960286198 1.1438441277 0.0165305616 0.0635890000 11200791 955859216 1766604800 -0.2205734551 -0.0651871860 2.1570816040 1053 42.0800000000 1.1373226643 0.0970175030 1.1438441277 0.0165252549 0.0674930000 11202045 955859216 1766129664 -0.2206890881 -0.0627889410 2.1555027962 1054 42.1200000000 1.1367001534 0.0980039192 1.1438441277 0.0165213165 0.0825550000 11203299 955859216 1765113856 -0.2207695395 -0.0622574426 2.1543495655 1055 42.1600000000 1.1370880604 0.0989888331 1.1438441277 0.0165165999 0.0580400000 11204553 955859216 1765130240 -0.2211452872 -0.0599522479 2.1545164585 1056 42.2000000000 1.1368901730 0.0999716942 1.1438441277 0.0165147064 0.0623860000 11205807 955859216 1766494208 -0.2213638276 -0.0574829914 2.1542363167 1057 42.2400000000 1.1366719007 0.1009524891 1.1438441277 0.0165129710 0.0839550000 11207061 955859216 1766010880 -0.2214917988 -0.0567314252 2.1536004543 1058 42.2800000000 1.1357247829 0.1019305348 1.1438441277 0.0165078324 0.0898880000 11208315 955859216 1765126144 -0.2217140049 -0.0563867427 2.1530556679 1059 42.3200000000 1.1353687048 0.1029063971 1.1438441277 0.0165035669 0.0641590000 11209569 955859216 1765130240 -0.2219986618 -0.0562929474 2.1530015469 1060 42.3600000000 1.1362109184 0.1038812126 1.1438441277 0.0164999512 0.0791010000 11210823 955859216 1765130240 -0.2223889530 -0.0560639910 2.1540949345 1061 42.4000000000 1.1371551752 0.1048550807 1.1438441277 0.0164953452 0.0907340000 11212077 955859216 1765130240 -0.2227657437 -0.0551584288 2.1555433273 1062 42.4400000000 1.1250145435 0.1058156828 1.1438441277 0.0164913524 0.1155400000 11213331 955859216 1765130240 -0.2225930095 -0.0530820265 2.1459147930 1063 42.4800000000 1.1267788410 0.1067761373 1.1438441277 0.0164901178 0.0689680000 11214585 955859216 1765081088 -0.2226258665 -0.0536332875 2.1486647129 1064 42.5200000000 1.1233426332 0.1077315569 1.1438441277 0.0164859528 0.0968600000 11215839 955859216 1765113856 -0.2223845422 -0.0523418076 2.1461653709 1065 42.5600000000 1.1252108812 0.1086869366 1.1438441277 0.0164831489 0.0830700000 11217093 955859216 1764999168 -0.2223413438 -0.0521936454 2.1493911743 1066 42.6000000000 1.1263308525 0.1096415744 1.1438441277 0.0164783105 0.0693720000 11218347 955859216 1765003264 -0.2222430259 -0.0508507565 2.1513090134 1067 42.6400000000 1.1273362637 0.1105953651 1.1438441277 0.0164753589 0.0881740000 11219601 955859216 1765003264 -0.2221320421 -0.0499665514 2.1533050537 1068 42.6800000000 1.1273610592 0.1115473929 1.1438441277 0.0164732296 0.1077730000 11220855 955859216 1765003264 -0.2217821181 -0.0499821082 2.1544654369 1069 42.7200000000 1.1272565126 0.1124975418 1.1438441277 0.0164713665 0.1096340000 11222109 955859216 1764999168 -0.2213624716 -0.0496482886 2.1550276279 1070 42.7600000000 1.1271963120 0.1134458584 1.1438441277 0.0164678074 0.0992540000 11223363 955859216 1765003264 -0.2210671008 -0.0486977324 2.1553843021 1071 42.8000000000 1.1166540384 0.1143825607 1.1438441277 0.0164683150 0.0891670000 11224617 955859216 1765478400 -0.2205896974 -0.0479663685 2.1466414928 1072 42.8400000000 1.1158347130 0.1153167511 1.1438441277 0.0164653356 0.0864170000 11225871 955859216 1765224448 -0.2206033468 -0.0485493839 2.1474339962 1073 42.8800000000 1.1138292551 0.1162473313 1.1438441277 0.0164588923 0.1054270000 11227125 955859216 1764954112 -0.2204546332 -0.0479527116 2.1459562778 1074 42.9200000000 1.1183005571 0.1171803417 1.1438441277 0.0164619118 0.0896190000 11228379 955859216 1766350848 -0.2205936611 -0.0474889949 2.1509532928 1075 42.9600000000 1.1119141579 0.1181056755 1.1438441277 0.0164621029 0.1242120000 11229633 955859216 1768382464 -0.2202879488 -0.0468549319 2.1450111866 1076 43.0000000000 1.1109123230 0.1190283583 1.1438441277 0.0164555398 0.0788350000 11230887 955859216 1770160128 -0.2200973481 -0.0471898280 2.1459436417 1077 43.0400000000 1.1100381613 0.1199485159 1.1438441277 0.0164496572 0.1019470000 11232141 955859216 1771810816 -0.2198927552 -0.0475357026 2.1478779316 1078 43.0800000000 1.1105418205 0.1208674337 1.1438441277 0.0164443959 0.0869400000 11233395 955859216 1773461504 -0.2196164280 -0.0465522744 2.1506068707 1079 43.1200000000 1.1131515503 0.1217870668 1.1438441277 0.0164417472 0.0686360000 11234649 955859216 1775239168 -0.2194164097 -0.0458167009 2.1563820839 1080 43.1600000000 1.1098816395 0.1227019692 1.1438441277 0.0164347012 0.0873540000 11235903 955859216 1776889856 -0.2192322463 -0.0455999486 2.1552622318 1081 43.2000000000 1.1090557575 0.1236144148 1.1438441277 0.0164297694 0.0688820000 11237157 955859216 1778540544 -0.2190580815 -0.0464140959 2.1571190357 1082 43.2400000000 1.1116021872 0.1245275274 1.1438441277 0.0164297542 0.0669100000 11238411 955859216 1780318208 -0.2189508379 -0.0456695035 2.1618030071 1083 43.2800000000 1.1054086685 0.1254332348 1.1438441277 0.0164230310 0.0860420000 11239665 955859216 1781968896 -0.2187914252 -0.0467814654 2.1578359604 1084 43.3200000000 1.1078014374 0.1263394785 1.1438441277 0.0164200965 0.0687280000 11240919 955859216 1783762944 -0.2183123231 -0.0465038419 2.1617188454 1085 43.3600000000 1.1094704866 0.1272455901 1.1438441277 0.0164145775 0.0868690000 11242173 955859216 1785397248 -0.2179414779 -0.0465679280 2.1647253036 1086 43.4000000000 1.1104454994 0.1281509307 1.1438441277 0.0164094923 0.0827330000 11243427 955859216 1787047936 -0.2174845636 -0.0459974222 2.1671745777 1087 43.4400000000 1.1027010679 0.1290474810 1.1438441277 0.0164077928 0.0899260000 11244681 955859216 1786052608 -0.2174833715 -0.0449202545 2.1613798141 1088 43.4800000000 1.1053708792 0.1299448370 1.1438441277 0.0164033651 0.0896880000 11245935 955859216 1783255040 -0.2169766873 -0.0450589694 2.1655302048 1089 43.5200000000 1.1037282944 0.1308390367 1.1438441277 0.0163970919 0.1018360000 11247189 955859216 1782255616 -0.2166333050 -0.0438099615 2.1659796238 1090 43.5600000000 1.1014809608 0.1317295339 1.1438441277 0.0163903952 0.0934500000 11248443 955859216 1781129216 -0.2161362618 -0.0437583067 2.1652572155 1091 43.6000000000 1.1053749323 0.1326219678 1.1438441277 0.0163893274 0.0844830000 11249697 955859216 1779986432 -0.2152104676 -0.0444980450 2.1711249352 1092 43.6400000000 1.1010540724 0.1335088104 1.1438441277 0.0163852809 0.0994450000 11250951 955859216 1778921472 -0.2148916423 -0.0435461923 2.1692695618 1093 43.6800000000 1.1028463840 0.1343956700 1.1438441277 0.0163807065 0.0846630000 11252205 955859216 1777938432 -0.2141030729 -0.0432066619 2.1739747524 1094 43.7200000000 1.1039407253 0.1352819086 1.1438441277 0.0163751421 0.1111320000 11253459 955859216 1776922624 -0.2132889628 -0.0423681550 2.1773524284 1095 43.7600000000 1.1080390215 0.1361702713 1.1438441277 0.0163794768 0.0938940000 11254713 955859216 1775796224 -0.2122575045 -0.0441666767 2.1842925549 1096 43.8000000000 1.1116396189 0.1370602981 1.1438441277 0.0163796271 0.0875370000 11255967 955859216 1774764032 -0.2111484408 -0.0457902662 2.1905870438 1097 43.8400000000 1.1028354168 0.1379406765 1.1438441277 0.0163999296 0.0947630000 11257221 955859216 1773748224 -0.2115394622 -0.0419311896 2.1839704514 1098 43.8800000000 1.1068065166 0.1388230680 1.1438441277 0.0163974143 0.0770490000 11258475 955859216 1772621824 -0.2104850709 -0.0427096933 2.1902244091 1099 43.9200000000 1.1101175547 0.1397068664 1.1438441277 0.0163935589 0.0893120000 11259729 955859216 1771589632 -0.2093715072 -0.0429528244 2.1952738762 1100 43.9600000000 1.1040918827 0.1405835800 1.1438441277 0.0163954943 0.1048450000 11260983 955859216 1770573824 -0.2094527483 -0.0394237787 2.1915829182 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-19 06:07:29 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0562030000 8929769 955859216 1769836544 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0003012840 0.0001506420 0.0003012840 0.0020374763 0.0631980000 9095551 955859216 1767575552 0.0002577147 0.0005514526 0.0001830395 3 0.0800000000 0.0004729226 0.0002580689 0.0004729226 0.0017208448 0.0516380000 9097129 955859216 1768071168 0.0003186495 -0.0019856594 -0.0006928600 4 0.1200000000 0.0004425067 0.0003041783 0.0004729226 0.0014734975 0.0536170000 9098711 955859216 1766932480 0.0004839354 -0.0013270257 -0.0006141628 5 0.1600000000 0.0006832334 0.0003799893 0.0006832334 0.0014633632 0.0837230000 9100285 955859216 1766064128 0.0005459327 -0.0009056352 -0.0004289765 6 0.2000000000 0.0006676085 0.0004279259 0.0006832334 0.0016078580 0.0639250000 9102195 955859216 1765179392 0.0006305756 -0.0019286295 -0.0007419488 7 0.2400000000 0.0007889742 0.0004795042 0.0007889742 0.0015986499 0.0565410000 9103449 955859216 1766535168 0.0006585474 -0.0021320917 -0.0008135838 8 0.2800000000 0.0007749581 0.0005164359 0.0007889742 0.0016071529 0.0637600000 9104703 955859216 1766031360 0.0005146636 -0.0008790736 -0.0003783810 9 0.3200000000 0.0007888140 0.0005467002 0.0007889742 0.0015120177 0.0916410000 9106597 955859216 1765429248 0.0007089394 -0.0008115403 -0.0003082162 10 0.3600000000 0.0007741907 0.0005694492 0.0007889742 0.0014525783 0.0784220000 9109163 955859216 1765011456 0.0007107475 -0.0014930045 -0.0004732510 11 0.4000000000 0.0007991215 0.0005903285 0.0007991215 0.0013882322 0.0898290000 9110417 955859216 1765392384 0.0006084199 -0.0008682336 -0.0003005653 12 0.4400000000 0.0008265935 0.0006100173 0.0008265935 0.0013400639 0.0605420000 9111671 955859216 1764995072 0.0006540985 -0.0000601398 -0.0000060157 13 0.4800000000 0.0007931333 0.0006241031 0.0008265935 0.0013124384 0.0681730000 9112925 955859216 1765027840 0.0005724947 0.0004243007 0.0003153346 14 0.5200000000 0.0007878663 0.0006358005 0.0008265935 0.0014152547 0.0509590000 9114179 955859216 1765044224 0.0007189481 0.0005157207 0.0004012349 15 0.5600000000 0.0008436546 0.0006496574 0.0008436546 0.0015036261 0.0581320000 9115433 955859216 1766408192 0.0007729750 0.0005973673 0.0004765516 16 0.6000000000 0.0008263640 0.0006607016 0.0008436546 0.0014882820 0.0515380000 9116687 955859216 1765937152 0.0010689194 0.0005510510 0.0004210324 17 0.6400000000 0.0008907183 0.0006742320 0.0008907183 0.0014533667 0.0527060000 9119221 955859216 1765048320 0.0010332572 0.0003903625 0.0004592208 18 0.6800000000 0.0009085388 0.0006872490 0.0009085388 0.0014282903 0.0597950000 9123099 955859216 1765044224 0.0010221229 -0.0002598291 0.0002172282 19 0.7200000000 0.0008489251 0.0006957583 0.0009085388 0.0015647238 0.0550890000 9124353 955859216 1766408192 0.0008865500 -0.0001893363 0.0001461147 20 0.7600000000 0.0008302625 0.0007024835 0.0009085388 0.0017812830 0.0498760000 9125607 955859216 1765916672 0.0006752172 -0.0004219941 0.0000478339 21 0.8000000000 0.0009730385 0.0007153671 0.0009730385 0.0019819879 0.0635980000 9126861 955859216 1765052416 0.0007486077 -0.0005231758 -0.0000895096 22 0.8400000000 0.0008559184 0.0007217558 0.0009730385 0.0020034834 0.0536560000 9128115 955859216 1765044224 0.0007177059 -0.0003643166 0.0000081540 23 0.8800000000 0.0009347111 0.0007310147 0.0009730385 0.0020133712 0.0549820000 9129369 955859216 1766408192 0.0004881036 -0.0005045814 -0.0000560699 24 0.9200000000 0.0010035135 0.0007423688 0.0010035135 0.0019786627 0.0767570000 9130623 955859216 1766043648 0.0005683378 -0.0003315037 -0.0000476096 25 0.9600000000 0.0009954718 0.0007524929 0.0010035135 0.0019394431 0.0787330000 9131877 955859216 1765502976 0.0002744884 -0.0003076888 -0.0000486001 26 1.0000000000 0.0009921145 0.0007617092 0.0010035135 0.0019022888 0.0609130000 9133131 955859216 1765376000 0.0004272564 -0.0000536087 -0.0000006648 27 1.0400000000 0.0009625802 0.0007691488 0.0010035135 0.0018727513 0.0609560000 9134385 955859216 1765044224 0.0001246327 -0.0000707222 -0.0000260389 28 1.0800000000 0.0009517138 0.0007756690 0.0010035135 0.0018671072 0.0579890000 9135639 955859216 1765044224 0.0000055504 -0.0001900203 0.0000088703 29 1.1200000000 0.0009490582 0.0007816479 0.0010035135 0.0018444966 0.0552230000 9136893 955859216 1766408192 -0.0003454637 0.0000608231 0.0001161155 30 1.1600000000 0.0009219712 0.0007863254 0.0010035135 0.0018341342 0.0770570000 9138147 955859216 1765912576 -0.0001608776 0.0004659212 0.0000896392 31 1.2000000000 0.0009733767 0.0007923593 0.0010035135 0.0018278601 0.0879200000 9139401 955859216 1765404672 -0.0003275652 0.0002657369 0.0000670233 32 1.2400000000 0.0009924116 0.0007986109 0.0010035135 0.0018050372 0.0582680000 9140655 955859216 1766039552 -0.0005394309 -0.0001520057 0.0000328647 33 1.2800000000 0.0009951177 0.0008045657 0.0010035135 0.0018216305 0.0824160000 9144469 955859216 1765154816 -0.0007768046 -0.0000119624 0.0001894435 34 1.3200000000 0.0009927759 0.0008101013 0.0010035135 0.0018256363 0.0537960000 9150971 955859216 1765044224 -0.0012337607 -0.0003266331 0.0002604686 35 1.3600000000 0.0010074334 0.0008157393 0.0010074334 0.0018169208 0.0562610000 9152225 955859216 1765044224 -0.0015798763 -0.0011187026 0.0000287286 36 1.4000000000 0.0010810111 0.0008231080 0.0010810111 0.0018005182 0.0706910000 9153479 955859216 1765027840 -0.0018424132 -0.0013039075 0.0000057629 37 1.4400000000 0.0009875835 0.0008275533 0.0010810111 0.0017767833 0.0652380000 9154733 955859216 1766518784 -0.0020518256 -0.0008762724 0.0002445869 38 1.4800000000 0.0010677495 0.0008338742 0.0010810111 0.0017528102 0.0797870000 9155987 955859216 1766154240 -0.0022134762 -0.0013140672 0.0002752414 39 1.5200000000 0.0010863335 0.0008403475 0.0010863335 0.0017438998 0.0905180000 9157241 955859216 1765519360 -0.0027726812 -0.0028563968 -0.0000490483 40 1.5600000000 0.0010347029 0.0008452064 0.0010863335 0.0018685463 0.0616480000 9158495 955859216 1766154240 -0.0030618480 -0.0024857698 0.0003499978 41 1.6000000000 0.0010500411 0.0008502024 0.0010863335 0.0020490371 0.0883900000 9159749 955859216 1765302272 -0.0034103659 -0.0012635464 0.0010605933 42 1.6400000000 0.0010958797 0.0008560519 0.0010958797 0.0021356772 0.0615720000 9161003 955859216 1765040128 -0.0039411681 -0.0015365729 0.0014204464 43 1.6800000000 0.0010738849 0.0008611177 0.0010958797 0.0021588102 0.0946520000 9162257 955859216 1765040128 -0.0041769091 -0.0016657218 0.0019556070 44 1.7200000000 0.0010843659 0.0008661916 0.0010958797 0.0021461222 0.0736030000 9163511 955859216 1765040128 -0.0046061659 -0.0013051269 0.0026030017 45 1.7600000000 0.0011153766 0.0008717290 0.0011153766 0.0021521787 0.0874750000 9164765 955859216 1765044224 -0.0048924773 -0.0017598188 0.0031581903 46 1.8000000000 0.0010783479 0.0008762207 0.0011153766 0.0022883824 0.0674630000 9166019 955859216 1765044224 -0.0052134735 -0.0028815325 0.0037049453 47 1.8400000000 0.0010867018 0.0008806990 0.0011153766 0.0024665482 0.0730770000 9167273 955859216 1765027840 -0.0052516921 -0.0032795155 0.0045966986 48 1.8800000000 0.0010894390 0.0008850478 0.0011153766 0.0026829947 0.0763450000 9168527 955859216 1765060608 -0.0055659646 -0.0033736138 0.0060328227 49 1.9200000000 0.0011143114 0.0008897266 0.0011153766 0.0030011511 0.0847060000 9169781 955859216 1765044224 -0.0055168276 -0.0047491947 0.0070752488 50 1.9600000000 0.0010803123 0.0008935384 0.0011153766 0.0033003592 0.0836920000 9171035 955859216 1765044224 -0.0055113891 -0.0053100218 0.0085826647 51 2.0000000000 0.0010824709 0.0008972429 0.0011153766 0.0034948828 0.0665940000 9172289 955859216 1765044224 -0.0054237731 -0.0051629706 0.0104812114 52 2.0400000000 0.0010944145 0.0009010347 0.0011153766 0.0036495259 0.0715610000 9173543 955859216 1765060608 -0.0048518451 -0.0052808998 0.0124029750 53 2.0800000000 0.0011062736 0.0009049071 0.0011153766 0.0037192216 0.0827940000 9174797 955859216 1765060608 -0.0044623674 -0.0064949999 0.0140539184 54 2.1200000000 0.0010730169 0.0009080203 0.0011153766 0.0037949866 0.0637870000 9176051 955859216 1766424576 -0.0035303985 -0.0072155362 0.0158404913 55 2.1600000000 0.0010632337 0.0009108423 0.0011153766 0.0037995644 0.0901090000 9177305 955859216 1765789696 -0.0031661827 -0.0069893645 0.0183326770 56 2.2000000000 0.0010738149 0.0009137525 0.0011153766 0.0037839699 0.0720260000 9178559 955859216 1766297600 -0.0026632971 -0.0067147180 0.0208459087 57 2.2400000000 0.0010504236 0.0009161503 0.0011153766 0.0038055225 0.0562380000 9179813 955859216 1765629952 -0.0015422184 -0.0068534776 0.0232618526 58 2.2800000000 0.0010809674 0.0009189920 0.0011153766 0.0038656294 0.0571540000 9181067 955859216 1765040128 -0.0008413374 -0.0058203191 0.0261076484 59 2.3200000000 0.0010760863 0.0009216546 0.0011153766 0.0039767503 0.0916950000 9182321 955859216 1765044224 0.0004152678 -0.0060554724 0.0287543498 60 2.3600000000 0.0011005076 0.0009246355 0.0011153766 0.0042841239 0.0818780000 9183575 955859216 1765044224 0.0013451033 -0.0073329848 0.0311655290 61 2.4000000000 0.0010790157 0.0009271663 0.0011153766 0.0045525333 0.0709030000 9184829 955859216 1765060608 0.0026160753 -0.0073736338 0.0340867750 62 2.4400000000 0.0010576680 0.0009292711 0.0011153766 0.0048138206 0.0588380000 9186083 955859216 1765060608 0.0038696527 -0.0074399849 0.0370000266 63 2.4800000000 0.0010793012 0.0009316526 0.0011153766 0.0050056506 0.0983640000 9187337 955859216 1765060608 0.0053092572 -0.0080876881 0.0397019573 64 2.5200000000 0.0010285923 0.0009331673 0.0011153766 0.0051427160 0.0593080000 9188591 955859216 1765044224 0.0068525518 -0.0077770134 0.0428452343 65 2.5600000000 0.0010681158 0.0009352434 0.0011153766 0.0054008944 0.0617090000 9194965 955859216 1765044224 0.0080771577 -0.0081107123 0.0457005203 66 2.6000000000 0.0010479691 0.0009369514 0.0011153766 0.0057552516 0.0578360000 9206715 955859216 1766408192 0.0098246345 -0.0090791360 0.0482511595 67 2.6400000000 0.0012215484 0.0009411991 0.0012215484 0.0060398866 0.0710470000 9207969 955859216 1765801984 0.0120466407 -0.0074855913 0.0516166724 68 2.6800000000 0.0010553619 0.0009428779 0.0012215484 0.0064603208 0.0972190000 9209223 955859216 1764360192 0.0122839650 -0.0074105505 0.0544141009 69 2.7200000000 0.0010365611 0.0009442357 0.0012215484 0.0066810771 0.0885400000 9210477 955859216 1766010880 0.0140606714 -0.0082395039 0.0570893027 70 2.7600000000 0.0010506653 0.0009457561 0.0012215484 0.0068092600 0.0587080000 9211731 955859216 1767534592 0.0155695695 -0.0089592785 0.0595712997 71 2.8000000000 0.0010329863 0.0009469847 0.0012215484 0.0068353046 0.0832620000 9212985 955859216 1769185280 0.0168163292 -0.0082584461 0.0625935942 72 2.8400000000 0.0010046858 0.0009477861 0.0012215484 0.0068264656 0.0567520000 9214239 955859216 1770962944 0.0182612929 -0.0085346634 0.0652756318 73 2.8800000000 0.0010368363 0.0009490060 0.0012215484 0.0068159605 0.0589200000 9215493 955859216 1772613632 0.0196050256 -0.0090258671 0.0677439943 74 2.9200000000 0.0010314783 0.0009501204 0.0012215484 0.0068312374 0.0613820000 9216747 955859216 1774264320 0.0211053062 -0.0082003977 0.0706301108 75 2.9600000000 0.0010299140 0.0009511844 0.0012215484 0.0069010702 0.0674640000 9218001 955859216 1776041984 0.0224450827 -0.0078450600 0.0733385980 76 3.0000000000 0.0010680100 0.0009527215 0.0012215484 0.0070769427 0.0555570000 9219255 955859216 1777692672 0.0239503738 -0.0090373382 0.0755395368 77 3.0400000000 0.0010945644 0.0009545637 0.0012215484 0.0072408983 0.0564870000 9220509 955859216 1779470336 0.0250705164 -0.0101639749 0.0776423812 78 3.0800000000 0.0010415275 0.0009556786 0.0012215484 0.0074731439 0.0649310000 9221763 955859216 1781121024 0.0265535433 -0.0095191672 0.0804639906 79 3.1200000000 0.0010421799 0.0009567735 0.0012215484 0.0076772595 0.0765840000 9223017 955859216 1782771712 0.0273544099 -0.0092812264 0.0831955820 80 3.1600000000 0.0010810717 0.0009583273 0.0012215484 0.0078212427 0.0763430000 9224271 955859216 1784549376 0.0284426622 -0.0103060137 0.0854349136 81 3.2000000000 0.0010373957 0.0009593034 0.0012215484 0.0079750457 0.0575980000 9225525 955859216 1786327040 0.0297308452 -0.0105705997 0.0879576579 82 3.2400000000 0.0010446680 0.0009603444 0.0012215484 0.0081525533 0.0592040000 9226779 955859216 1787977728 0.0302726217 -0.0108145624 0.0904758275 83 3.2800000000 0.0010505532 0.0009614313 0.0012215484 0.0083404941 0.0858160000 9228033 955859216 1786970112 0.0313579887 -0.0117141884 0.0928767249 84 3.3200000000 0.0010449573 0.0009624256 0.0012215484 0.0084483136 0.0660760000 9229287 955859216 1785716736 0.0321085900 -0.0119163832 0.0954195783 85 3.3600000000 0.0009950162 0.0009628091 0.0012215484 0.0085185735 0.0626250000 9230541 955859216 1784299520 0.0326547474 -0.0115517434 0.0981885791 86 3.4000000000 0.0009864419 0.0009630839 0.0012215484 0.0085818681 0.0831390000 9231795 955859216 1783316480 0.0334368907 -0.0116890995 0.1007674634 87 3.4400000000 0.0009694964 0.0009631576 0.0012215484 0.0086551739 0.0562140000 9233049 955859216 1782296576 0.0342729799 -0.0116327554 0.1036152691 88 3.4800000000 0.0009894732 0.0009634566 0.0012215484 0.0087430433 0.0831160000 9234303 955859216 1781301248 0.0350728035 -0.0119608361 0.1063814908 89 3.5200000000 0.0009630953 0.0009634526 0.0012215484 0.0088272400 0.0660170000 9235557 955859216 1780412416 0.0358528048 -0.0119328145 0.1092840359 90 3.5600000000 0.0009746888 0.0009635774 0.0012215484 0.0089454003 0.0586950000 9236811 955859216 1781755904 0.0363119282 -0.0118923588 0.1122482941 91 3.6000000000 0.0009650369 0.0009635934 0.0012215484 0.0090854407 0.0614170000 9238065 955859216 1780224000 0.0375215933 -0.0124581186 0.1152558401 92 3.6400000000 0.0009847739 0.0009638237 0.0012215484 0.0091758800 0.0600990000 9239319 955859216 1779634176 0.0380643271 -0.0126731573 0.1184273437 93 3.6800000000 0.0009698368 0.0009638883 0.0012215484 0.0091789397 0.0695590000 9240573 955859216 1778597888 0.0385062583 -0.0131914914 0.1213704348 94 3.7200000000 0.0009074847 0.0009632883 0.0012215484 0.0091577404 0.0786250000 9241827 955859216 1777582080 0.0392427295 -0.0130197862 0.1245473400 95 3.7600000000 0.0009337522 0.0009629774 0.0012215484 0.0091467453 0.0748960000 9243081 955859216 1776934912 0.0400864631 -0.0131962961 0.1276184767 96 3.8000000000 0.0008803033 0.0009621162 0.0012215484 0.0091673136 0.0685600000 9244335 955859216 1778073600 0.0409693159 -0.0130826654 0.1308627725 97 3.8400000000 0.0008392393 0.0009608494 0.0012215484 0.0092847179 0.0864610000 9245589 955859216 1777311744 0.0414896421 -0.0116578238 0.1344798058 98 3.8800000000 0.0009106455 0.0009603371 0.0012215484 0.0094096200 0.0596330000 9246843 955859216 1776533504 0.0421125740 -0.0117013426 0.1376447380 99 3.9200000000 0.0008872197 0.0009595986 0.0012215484 0.0095394536 0.0867360000 9248097 955859216 1775677440 0.0431262963 -0.0116974050 0.1408695728 100 3.9600000000 0.0008246378 0.0009582490 0.0012215484 0.0096522930 0.0702160000 9249351 955859216 1774809088 0.0433109440 -0.0101406137 0.1444680989 101 4.0000000000 0.0008754734 0.0009574294 0.0012215484 0.0097022110 0.0758460000 9250605 955859216 1773867008 0.0438418724 -0.0095119867 0.1478536278 102 4.0400000000 0.0009151272 0.0009570147 0.0012215484 0.0097156138 0.0790820000 9251859 955859216 1773031424 0.0445473641 -0.0097856345 0.1508188397 103 4.0800000000 0.0008345408 0.0009558256 0.0012215484 0.0097285855 0.0639410000 9253113 955859216 1774391296 0.0448297895 -0.0086453799 0.1542005837 104 4.1200000000 0.0008933826 0.0009552252 0.0012215484 0.0097355030 0.0662810000 9254367 955859216 1773793280 0.0456604548 -0.0085304156 0.1573382020 105 4.1600000000 0.0008792480 0.0009545016 0.0012215484 0.0097412884 0.0633500000 9255621 955859216 1772904448 0.0461275391 -0.0084211975 0.1600836813 106 4.2000000000 0.0008341541 0.0009533662 0.0012215484 0.0097310922 0.0617180000 9256875 955859216 1772015616 0.0462062359 -0.0077233603 0.1629085094 107 4.2400000000 0.0009110549 0.0009529708 0.0012215484 0.0097073308 0.0654310000 9258129 955859216 1773375488 0.0468384437 -0.0082987193 0.1653673947 108 4.2800000000 0.0008221025 0.0009517591 0.0012215484 0.0096957183 0.0669740000 9259383 955859216 1772756992 0.0469287336 -0.0074617630 0.1681148261 109 4.3200000000 0.0008200551 0.0009505508 0.0012215484 0.0096790011 0.0668440000 9260637 955859216 1771888640 0.0470955744 -0.0065728719 0.1707965583 110 4.3600000000 0.0008347790 0.0009494983 0.0012215484 0.0096427218 0.0822000000 9261891 955859216 1771003904 0.0474627353 -0.0062130517 0.1733506322 111 4.4000000000 0.0008339432 0.0009484573 0.0012215484 0.0096106977 0.0865900000 9263145 955859216 1770110976 0.0479403399 -0.0059869508 0.1758714020 112 4.4400000000 0.0008093126 0.0009472149 0.0012215484 0.0095794472 0.0653910000 9264399 955859216 1769222144 0.0483821370 -0.0057861861 0.1782717556 113 4.4800000000 0.0008061363 0.0009459664 0.0012215484 0.0095464481 0.0686820000 9265653 955859216 1768316928 0.0480283499 -0.0050668870 0.1806872636 114 4.5200000000 0.0008826515 0.0009454110 0.0012215484 0.0095149733 0.0658120000 9266907 955859216 1769693184 0.0483160056 -0.0051530702 0.1830928475 115 4.5600000000 0.0008840037 0.0009448771 0.0012215484 0.0094858600 0.0670420000 9268161 955859216 1769099264 0.0486364327 -0.0052123112 0.1854236126 116 4.6000000000 0.0008843595 0.0009443554 0.0012215484 0.0094652767 0.0976670000 9269415 955859216 1768214528 0.0484314598 -0.0045385654 0.1879849732 117 4.6400000000 0.0009660066 0.0009445404 0.0012215484 0.0094347192 0.1054610000 9270669 955859216 1769566208 0.0485990196 -0.0047448864 0.1904001981 118 4.6800000000 0.0009894681 0.0009449211 0.0012215484 0.0094076340 0.0707940000 9271923 955859216 1771454464 0.0485467128 -0.0045691421 0.1930424720 119 4.7200000000 0.0011002475 0.0009462264 0.0012215484 0.0093821754 0.0679720000 9273177 955859216 1773105152 0.0489096195 -0.0043832338 0.1959365308 120 4.7600000000 0.0011778903 0.0009481569 0.0012215484 0.0093575976 0.0719860000 9274431 955859216 1774882816 0.0489871390 -0.0045910436 0.1986739337 121 4.8000000000 0.0012760514 0.0009508668 0.0012760514 0.0093444813 0.0787360000 9275685 955859216 1776533504 0.0490810908 -0.0044022417 0.2016460299 122 4.8400000000 0.0013881825 0.0009544514 0.0013881825 0.0093509401 0.0721220000 9276939 955859216 1778327552 0.0490087681 -0.0042977156 0.2046709657 123 4.8800000000 0.0014959235 0.0009588536 0.0014959235 0.0093367103 0.0772490000 9278193 955859216 1779961856 0.0489796065 -0.0041164341 0.2077519149 124 4.9200000000 0.0015810315 0.0009638711 0.0015810315 0.0093142741 0.0658310000 9279447 955859216 1781612544 0.0489427298 -0.0037745081 0.2107782960 125 4.9600000000 0.0017654968 0.0009702842 0.0017654968 0.0092936563 0.0683580000 9280701 955859216 1783390208 0.0490808710 -0.0033720862 0.2139913589 126 5.0000000000 0.0019070792 0.0009777190 0.0019070792 0.0092812029 0.0660720000 9281955 955859216 1785040896 0.0492459163 -0.0033516721 0.2170808762 127 5.0400000000 0.0020422328 0.0009861010 0.0020422328 0.0092831113 0.0692990000 9283209 955859216 1786691584 0.0496121384 -0.0032261135 0.2202662677 128 5.0800000000 0.0021465875 0.0009951673 0.0021465875 0.0093004151 0.0662250000 9284463 955859216 1785864192 0.0499869287 -0.0026894212 0.2233984172 129 5.1200000000 0.0022890118 0.0010051971 0.0022890118 0.0092854553 0.0712870000 9295957 955859216 1784832000 0.0504240543 -0.0025904728 0.2264439166 130 5.1600000000 0.0023591251 0.0010156120 0.0023591251 0.0092738343 0.0674900000 9318203 955859216 1783803904 0.0510005988 -0.0032630693 0.2290739566 131 5.2000000000 0.0024094994 0.0010262523 0.0024094994 0.0092640734 0.0696810000 9319457 955859216 1782788096 0.0515091345 -0.0031003049 0.2317949831 132 5.2400000000 0.0024962446 0.0010373886 0.0024962446 0.0092433843 0.0673000000 9320711 955859216 1784168448 0.0517264493 -0.0026094287 0.2346589118 133 5.2800000000 0.0027185269 0.0010500288 0.0027185269 0.0092382037 0.0711860000 9321965 955859216 1783521280 0.0522815026 -0.0030185389 0.2371222973 134 5.3200000000 0.0028464124 0.0010634346 0.0028464124 0.0092651969 0.1021940000 9323219 955859216 1782923264 0.0527369231 -0.0024143239 0.2400358319 135 5.3600000000 0.0029611986 0.0010774921 0.0029611986 0.0092674163 0.1054710000 9324473 955859216 1784279040 0.0532045141 -0.0026095910 0.2423020303 136 5.4000000000 0.0031532280 0.0010927549 0.0031532280 0.0092748038 0.0713690000 9325727 955859216 1786183680 0.0537868552 -0.0032823854 0.2444494665 137 5.4400000000 0.0033199976 0.0011090121 0.0033199976 0.0092735820 0.0716190000 9326981 955859216 1787834368 0.0543921590 -0.0035776806 0.2467865497 138 5.4800000000 0.0033371090 0.0011251578 0.0033371090 0.0092547609 0.0677030000 9328235 955859216 1786974208 0.0548175536 -0.0035378016 0.2490542233 139 5.5200000000 0.0035112211 0.0011423237 0.0035112211 0.0092439194 0.0719230000 9329489 955859216 1785716736 0.0550669879 -0.0036818800 0.2511997521 140 5.5600000000 0.0037847837 0.0011611984 0.0037847837 0.0092362765 0.1042780000 9330743 955859216 1784832000 0.0551664494 -0.0040334184 0.2532848716 141 5.6000000000 0.0021196101 0.0011679956 0.0037847837 0.0092997313 0.0837260000 9331997 955859216 1786200064 0.0566001423 -0.0046667699 0.2588242292 142 5.6400000000 0.0033047090 0.0011830429 0.0037847837 0.0092962279 0.0716500000 9333251 955859216 1787961344 0.0554785468 -0.0051726541 0.2596768439 143 5.6800000000 0.0037966797 0.0012013201 0.0037966797 0.0092962632 0.0700880000 9334505 955859216 1787101184 0.0549678132 -0.0055706967 0.2611632049 144 5.7200000000 0.0039876709 0.0012206698 0.0039876709 0.0092920247 0.0718070000 9335759 955859216 1785815040 0.0543543994 -0.0055772779 0.2629390955 145 5.7600000000 0.0041320645 0.0012407483 0.0041320645 0.0092816670 0.0690130000 9337013 955859216 1784668160 0.0536442809 -0.0055598789 0.2646010220 146 5.8000000000 0.0043959799 0.0012623595 0.0043959799 0.0092816842 0.0782890000 9338267 955859216 1783832576 0.0528703742 -0.0053309011 0.2662898004 147 5.8400000000 0.0046404675 0.0012853399 0.0046404675 0.0092733108 0.0707860000 9339521 955859216 1782796288 0.0520657264 -0.0060396781 0.2676740587 148 5.8800000000 0.0046884967 0.0013083342 0.0046884967 0.0092554241 0.0737820000 9340775 955859216 1784160256 0.0511648692 -0.0068219565 0.2690016329 149 5.9200000000 0.0048579858 0.0013321573 0.0048579858 0.0092382794 0.1104980000 9342029 955859216 1781526528 0.0501192845 -0.0070308279 0.2705674469 150 5.9600000000 0.0051126094 0.0013573603 0.0051126094 0.0092216681 0.0801240000 9343283 955859216 1782906880 0.0490587503 -0.0072924169 0.2723291218 151 6.0000000000 0.0051893257 0.0013827376 0.0051893257 0.0092032972 0.0693140000 9344537 955859216 1782022144 0.0478889719 -0.0075158547 0.2740008533 152 6.0400000000 0.0053839921 0.0014090616 0.0053839921 0.0091880882 0.0796310000 9345791 955859216 1781420032 0.0466910750 -0.0077351183 0.2757160962 153 6.0800000000 0.0057295701 0.0014373002 0.0057295701 0.0091747807 0.1050380000 9347045 955859216 1780383744 0.0454278775 -0.0079417601 0.2776728868 154 6.1200000000 0.0058589280 0.0014660121 0.0058589280 0.0091593278 0.1213620000 9348299 955859216 1779122176 0.0441264771 -0.0083318772 0.2795414925 155 6.1600000000 0.0058764070 0.0014944663 0.0058764070 0.0091406601 0.1263970000 9349553 955859216 1778229248 0.0426971465 -0.0085600177 0.2815219462 156 6.2000000000 0.0066739284 0.0015276680 0.0066739284 0.0091467001 0.0766750000 9350807 955859216 1777201152 0.0394827276 -0.0093857795 0.2849591672 157 6.2400000000 0.0064849206 0.0015592428 0.0066739284 0.0091304232 0.0717940000 9352061 955859216 1776185344 0.0381786823 -0.0096221929 0.2873994708 158 6.2800000000 0.0065393439 0.0015907624 0.0066739284 0.0091137962 0.0855680000 9353315 955859216 1775316992 0.0366995186 -0.0100266719 0.2893723547 159 6.3200000000 0.0066206311 0.0016223968 0.0066739284 0.0091008593 0.1084040000 9354569 955859216 1774432256 0.0350340530 -0.0102754384 0.2912738323 160 6.3600000000 0.0067810188 0.0016546382 0.0067810188 0.0090852629 0.0916220000 9355823 955859216 1773539328 0.0334214978 -0.0102420328 0.2932435274 161 6.4000000000 0.0069110305 0.0016872866 0.0069110305 0.0090768269 0.0769930000 9357077 955859216 1774899200 0.0317086950 -0.0102631608 0.2950598001 162 6.4400000000 0.0069239056 0.0017196114 0.0069239056 0.0090849039 0.0706680000 9358331 955859216 1774252032 0.0299366880 -0.0105270809 0.2968567610 163 6.4800000000 0.0069900868 0.0017519456 0.0069900868 0.0090772964 0.0771690000 9359585 955859216 1773539328 0.0283705294 -0.0106652100 0.2984820604 164 6.5200000000 0.0072357673 0.0017853836 0.0072357673 0.0090629354 0.1119220000 9360839 955859216 1772650496 0.0267563555 -0.0106656812 0.3001582325 165 6.5600000000 0.0074272472 0.0018195767 0.0074272472 0.0090552379 0.0773820000 9362093 955859216 1771851776 0.0251119640 -0.0108544920 0.3019333780 166 6.6000000000 0.0074820803 0.0018536882 0.0074820803 0.0090405842 0.0818510000 9363347 955859216 1771216896 0.0236513317 -0.0110416180 0.3036476076 167 6.6400000000 0.0076410118 0.0018883428 0.0076410118 0.0090292717 0.1099600000 9364601 955859216 1769598976 0.0220992006 -0.0108242230 0.3056380451 168 6.6800000000 0.0076675932 0.0019227431 0.0076675932 0.0090142216 0.0878670000 9365855 955859216 1768566784 0.0206267312 -0.0112613766 0.3071234524 169 6.7200000000 0.0076459092 0.0019566080 0.0076675932 0.0090000445 0.0778930000 9367109 955859216 1769947136 0.0191790070 -0.0115429517 0.3085962534 170 6.7600000000 0.0078319758 0.0019911690 0.0078319758 0.0089850519 0.0710190000 9368363 955859216 1769426944 0.0179997850 -0.0117168482 0.3101311028 171 6.8000000000 0.0079899663 0.0020262496 0.0079899663 0.0089721473 0.0789610000 9369617 955859216 1768439808 0.0169241447 -0.0123485932 0.3114573658 172 6.8400000000 0.0079175225 0.0020605012 0.0079899663 0.0089559756 0.0998300000 9370871 955859216 1767555072 0.0157779772 -0.0130061330 0.3125787079 173 6.8800000000 0.0078869788 0.0020941803 0.0079899663 0.0089415966 0.0705720000 9372125 955859216 1767157760 0.0148325870 -0.0136177856 0.3135330677 174 6.9200000000 0.0080134133 0.0021281989 0.0080134133 0.0089504119 0.0790360000 9373379 955859216 1766158336 0.0139694018 -0.0141489599 0.3144347072 175 6.9600000000 0.0081573585 0.0021626512 0.0081573585 0.0089665142 0.0994870000 9374633 955859216 1765285888 0.0130700842 -0.0147073837 0.3153934181 176 7.0000000000 0.0080981934 0.0021963759 0.0081573585 0.0089759594 0.0712700000 9375887 955859216 1764880384 0.0122419652 -0.0152292848 0.3160551786 177 7.0400000000 0.0082539469 0.0022305995 0.0082539469 0.0090006694 0.0778740000 9377141 955859216 1765023744 0.0115955640 -0.0157720279 0.3167624772 178 7.0800000000 0.0083315894 0.0022648747 0.0083315894 0.0090065957 0.0997530000 9378395 955859216 1765023744 0.0109917158 -0.0162852090 0.3173907101 179 7.1200000000 0.0083983634 0.0022991400 0.0083983634 0.0090134698 0.1117670000 9379649 955859216 1765023744 0.0104895448 -0.0166478232 0.3180858791 180 7.1600000000 0.0084692156 0.0023334182 0.0084692156 0.0090400426 0.0865930000 9380903 955859216 1766629376 0.0100388704 -0.0171078909 0.3188533187 181 7.2000000000 0.0084066745 0.0023669721 0.0084692156 0.0090595325 0.0803370000 9382157 955859216 1768660992 0.0095159076 -0.0175112765 0.3193436563 182 7.2400000000 0.0084222108 0.0024002426 0.0084692156 0.0090777714 0.0842870000 9383411 955859216 1770311680 0.0090287486 -0.0177533384 0.3197849989 183 7.2800000000 0.0084480112 0.0024332905 0.0084692156 0.0091024018 0.0897030000 9384665 955859216 1772089344 0.0086138360 -0.0179990511 0.3199319839 184 7.3200000000 0.0080473758 0.0024638019 0.0084692156 0.0092517959 0.0848840000 9385919 955859216 1773740032 0.0079360586 -0.0181586277 0.3210165501 185 7.3600000000 0.0080167931 0.0024938180 0.0084692156 0.0092734839 0.0792990000 9387173 955859216 1775517696 0.0076448452 -0.0183666442 0.3212662637 186 7.4000000000 0.0083394861 0.0025252464 0.0084692156 0.0092698397 0.0737450000 9388427 955859216 1777168384 0.0070635271 -0.0188396908 0.3218049705 187 7.4400000000 0.0080282949 0.0025546744 0.0084692156 0.0092590794 0.0790350000 9389681 955859216 1778819072 0.0067670173 -0.0188155435 0.3234944940 188 7.4800000000 0.0082544629 0.0025849924 0.0084692156 0.0092450558 0.0729740000 9390935 955859216 1780596736 0.0065034362 -0.0192118157 0.3245079219 189 7.5200000000 0.0082242833 0.0026148300 0.0084692156 0.0092406478 0.0748760000 9392189 955859216 1782247424 0.0063249245 -0.0194977522 0.3258901536 190 7.5600000000 0.0082293889 0.0026443803 0.0084692156 0.0092522629 0.0741800000 9393443 955859216 1784025088 0.0063160965 -0.0193592086 0.3274078071 191 7.6000000000 0.0080939084 0.0026729118 0.0084692156 0.0092437113 0.0787230000 9394697 955859216 1785675776 0.0066182376 -0.0192491282 0.3290165067 192 7.6400000000 0.0080475602 0.0027009048 0.0084692156 0.0092322516 0.0824740000 9395951 955859216 1787326464 0.0067057214 -0.0194833092 0.3308427632 193 7.6800000000 0.0079497909 0.0027281011 0.0084692156 0.0092218693 0.1103000000 9397205 955859216 1784819712 0.0067038089 -0.0197671484 0.3324545920 194 7.7200000000 0.0079125585 0.0027548251 0.0084692156 0.0092097835 0.0793490000 9398459 955859216 1784942592 0.0068617100 -0.0198685694 0.3338451982 195 7.7600000000 0.0078865467 0.0027811416 0.0084692156 0.0091961643 0.0784480000 9399713 955859216 1785040896 0.0070820311 -0.0200352930 0.3350358307 196 7.8000000000 0.0078414269 0.0028069594 0.0084692156 0.0091826996 0.1061480000 9400967 955859216 1782644736 0.0072483653 -0.0202993806 0.3360704184 197 7.8400000000 0.0079022190 0.0028328237 0.0084692156 0.0091695875 0.1100200000 9402221 955859216 1781628928 0.0074689630 -0.0206562188 0.3369072080 198 7.8800000000 0.0078468462 0.0028581470 0.0084692156 0.0091557265 0.0907080000 9403475 955859216 1780633600 0.0076936875 -0.0207817815 0.3379873633 199 7.9200000000 0.0077058240 0.0028825072 0.0084692156 0.0091454421 0.0749360000 9404729 955859216 1781993472 0.0079658190 -0.0209988505 0.3386026323 200 7.9600000000 0.0077995006 0.0029070922 0.0084692156 0.0091398098 0.0786540000 9405983 955859216 1781370880 0.0081992000 -0.0213740673 0.3392843008 201 8.0000000000 0.0078415573 0.0029316417 0.0084692156 0.0091277506 0.1070870000 9407237 955859216 1778577408 0.0083388733 -0.0215939265 0.3400198519 202 8.0400000000 0.0077976934 0.0029557311 0.0084692156 0.0091186937 0.1006480000 9408491 955859216 1777565696 0.0086090118 -0.0217101108 0.3404761255 203 8.0800000000 0.0076430528 0.0029788214 0.0084692156 0.0091129916 0.0942660000 9409745 955859216 1776549888 0.0087158121 -0.0217415355 0.3410230875 204 8.1200000000 0.0077611334 0.0030022641 0.0084692156 0.0091113632 0.0799630000 9410999 955859216 1775665152 0.0088383267 -0.0217259899 0.3414435983 205 8.1600000000 0.0078000459 0.0030256679 0.0084692156 0.0091125488 0.1095390000 9412253 955859216 1774792704 0.0089133848 -0.0216949098 0.3419578075 206 8.1999999990 0.0078606475 0.0030491387 0.0084692156 0.0091138101 0.0816650000 9413507 955859216 1776156672 0.0089267157 -0.0215262063 0.3420108259 207 8.2400000000 0.0078306217 0.0030722376 0.0084692156 0.0091434210 0.0810730000 9414761 955859216 1775407104 0.0090089049 -0.0214297157 0.3424022496 208 8.2799999990 0.0076853102 0.0030944158 0.0084692156 0.0091789521 0.1097770000 9416015 955859216 1772867584 0.0090000825 -0.0214018021 0.3427100480 209 8.3200000000 0.0077278721 0.0031165855 0.0084692156 0.0092061930 0.1082700000 9417269 955859216 1771999232 0.0089752590 -0.0215770379 0.3426128626 210 8.3599999990 0.0077665816 0.0031387283 0.0084692156 0.0092042043 0.0902290000 9418523 955859216 1771114496 0.0088669481 -0.0215418711 0.3427283168 211 8.4000000000 0.0077606509 0.0031606332 0.0084692156 0.0091956621 0.0810570000 9419777 955859216 1772470272 0.0088552702 -0.0214019008 0.3426109850 212 8.4399999990 0.0077130138 0.0031821067 0.0084692156 0.0091934984 0.0937500000 9421031 955859216 1769332736 0.0088468697 -0.0212564860 0.3421378732 213 8.4800000000 0.0077517396 0.0032035603 0.0084692156 0.0092038154 0.0817420000 9422285 955859216 1770676224 0.0088669686 -0.0212827306 0.3417930603 214 8.5200000000 0.0077262404 0.0032246944 0.0084692156 0.0092007337 0.0771010000 9423539 955859216 1770070016 0.0088871680 -0.0212428533 0.3413040042 215 8.5600000000 0.0077649290 0.0032458117 0.0084692156 0.0091917843 0.0797880000 9424793 955859216 1769046016 0.0088070007 -0.0209499393 0.3408167660 216 8.6000000000 0.0077718813 0.0032667658 0.0084692156 0.0091968295 0.1074480000 9426047 955859216 1766670336 0.0087259058 -0.0207070429 0.3402830660 217 8.6400000000 0.0077494183 0.0032874231 0.0084692156 0.0092066942 0.0892690000 9427301 955859216 1766514688 0.0085731158 -0.0204491671 0.3398530781 218 8.6800000000 0.0077443901 0.0033078680 0.0084692156 0.0092217642 0.0826320000 9428555 955859216 1766502400 0.0084628901 -0.0201675631 0.3393373489 219 8.7200000000 0.0077102412 0.0033279701 0.0084692156 0.0092353109 0.0800110000 9429809 955859216 1765105664 0.0083463090 -0.0198200662 0.3389686644 220 8.7600000000 0.0077078529 0.0033478787 0.0084692156 0.0092455186 0.1105180000 9431063 955859216 1764626432 0.0082305763 -0.0194473621 0.3383989632 221 8.8000000000 0.0077366782 0.0033677375 0.0084692156 0.0092601906 0.0869800000 9432317 955859216 1764630528 0.0081446832 -0.0192389581 0.3379745185 222 8.8400000000 0.0076703657 0.0033871187 0.0084692156 0.0092649416 0.0900170000 9433571 955859216 1764868096 0.0079722479 -0.0188948195 0.3374930322 223 8.8800000000 0.0077584223 0.0034067210 0.0084692156 0.0092759796 0.0878250000 9434825 955859216 1764995072 0.0076841842 -0.0185434557 0.3366523087 224 8.9200000000 0.0077443197 0.0034260852 0.0084692156 0.0093033505 0.0836130000 9436079 955859216 1766486016 0.0074046282 -0.0185051095 0.3360145390 225 8.9600000000 0.0076836054 0.0034450075 0.0084692156 0.0093238280 0.0793370000 9437333 955859216 1766391808 0.0070625343 -0.0181654729 0.3352581859 226 9.0000000000 0.0076286695 0.0034635193 0.0084692156 0.0093536802 0.1108720000 9438587 955859216 1764880384 0.0067453999 -0.0178908482 0.3345315754 227 9.0400000000 0.0076265708 0.0034818588 0.0084692156 0.0093721997 0.0847760000 9439841 955859216 1764892672 0.0063442127 -0.0175678506 0.3337390125 228 9.0800000000 0.0076524587 0.0035001509 0.0084692156 0.0094011556 0.0790320000 9441095 955859216 1764892672 0.0059893089 -0.0173169281 0.3329098821 229 9.1200000000 0.0076048188 0.0035180752 0.0084692156 0.0094319420 0.1168970000 9442349 955859216 1764995072 0.0055964091 -0.0173120145 0.3320017159 230 9.1600000000 0.0076701264 0.0035361276 0.0084692156 0.0094418228 0.0831550000 9443603 955859216 1765122048 0.0051616859 -0.0170942228 0.3308981955 231 9.2000000000 0.0076515167 0.0035539431 0.0084692156 0.0094586742 0.0899200000 9444857 955859216 1765138432 0.0046181800 -0.0167698432 0.3298968077 232 9.2400000000 0.0077026715 0.0035718256 0.0084692156 0.0094793591 0.0759340000 9446111 955859216 1766486016 0.0040925103 -0.0164933149 0.3288886547 233 9.2800000000 0.0076623475 0.0035893815 0.0084692156 0.0095077060 0.0796190000 9447365 955859216 1766109184 0.0034843842 -0.0161092393 0.3282178342 234 9.3200000000 0.0075784065 0.0036064286 0.0084692156 0.0095372343 0.1060070000 9448619 955859216 1764864000 0.0028943880 -0.0157721136 0.3270650208 235 9.3600000000 0.0076563261 0.0036236622 0.0084692156 0.0095492075 0.1017440000 9449873 955859216 1764872192 0.0022732466 -0.0155397020 0.3260123134 236 9.4000000000 0.0076403036 0.0036406818 0.0084692156 0.0095529705 0.0780580000 9451127 955859216 1764986880 0.0015673373 -0.0150879193 0.3249311149 237 9.4400000000 0.0077264295 0.0036579213 0.0084692156 0.0095627363 0.0880990000 9452381 955859216 1765113856 0.0008033577 -0.0148722194 0.3238302767 238 9.4800000000 0.0081229322 0.0036766818 0.0084692156 0.0096419455 0.1100350000 9453635 955859216 1765130240 -0.0009835145 -0.0141583458 0.3213695884 239 9.5200000000 0.0080774641 0.0036950951 0.0084692156 0.0096707430 0.0859980000 9454889 955859216 1765130240 -0.0019452365 -0.0133524379 0.3202595711 240 9.5600000000 0.0082311006 0.0037139952 0.0084692156 0.0096991290 0.0813650000 9456143 955859216 1765130240 -0.0030131354 -0.0124237053 0.3189378083 241 9.6000000000 0.0084645459 0.0037337070 0.0084692156 0.0097678357 0.1098060000 9457397 955859216 1764999168 -0.0040723910 -0.0120572122 0.3178734183 242 9.6400000000 0.0086185262 0.0037538922 0.0086185262 0.0098401741 0.0898830000 9458651 955859216 1764986880 -0.0051322989 -0.0116296513 0.3167684972 243 9.6800000000 0.0088322191 0.0037747907 0.0088322191 0.0098976601 0.0687820000 9459905 955859216 1766350848 -0.0061478880 -0.0111645283 0.3151673675 244 9.7200000000 0.0091129784 0.0037966685 0.0091129784 0.0099516973 0.0792380000 9461159 955859216 1766023168 -0.0072778235 -0.0106234178 0.3137922287 245 9.7600000000 0.0090892883 0.0038182710 0.0091129784 0.0099967288 0.1071150000 9462413 955859216 1765134336 -0.0082861707 -0.0101068318 0.3124704957 246 9.8000000000 0.0093432087 0.0038407301 0.0093432087 0.0100244126 0.0913600000 9463667 955859216 1766494208 -0.0094115846 -0.0095933340 0.3109077811 247 9.8400000000 0.0095131258 0.0038636953 0.0095131258 0.0100639088 0.0687280000 9464921 955859216 1768382464 -0.0105258143 -0.0088067707 0.3095245957 248 9.8800000000 0.0095021706 0.0038864311 0.0095131258 0.0101144182 0.0780060000 9466175 955859216 1770033152 -0.0116227120 -0.0078137368 0.3078423142 249 9.9200000000 0.0094354860 0.0039087164 0.0095131258 0.0101673518 0.1064370000 9467429 955859216 1771683840 -0.0125978831 -0.0070040743 0.3062641919 250 9.9600000000 0.0090522412 0.0039292905 0.0095131258 0.0102109809 0.1254090000 9468683 955859216 1773461504 -0.0136253489 -0.0056160083 0.3049755991 251 10.0000000000 0.0085135791 0.0039475546 0.0095131258 0.0102547482 0.0803610000 9469937 955859216 1775112192 -0.0147450306 -0.0034773883 0.3036210239 252 10.0400000000 0.0080924965 0.0039640028 0.0095131258 0.0103141592 0.0723750000 9471191 955859216 1776889856 -0.0158102084 -0.0017053505 0.3021515012 253 10.0800000000 0.0080800261 0.0039802717 0.0095131258 0.0103505775 0.0693210000 9472445 955859216 1778540544 -0.0166857652 -0.0007807344 0.3004787266 254 10.1200000000 0.0081138648 0.0039965457 0.0095131258 0.0103861717 0.0700270000 9473699 955859216 1780318208 -0.0176873878 0.0002897709 0.2988786697 255 10.1600000000 0.0081892107 0.0040129875 0.0095131258 0.0104368157 0.0689710000 9474953 955859216 1781968896 -0.0187156908 0.0010705270 0.2973521054 256 10.2000000000 0.0082320888 0.0040294683 0.0095131258 0.0104803516 0.0702760000 9476207 955859216 1783611392 -0.0196111649 0.0018533207 0.2958177924 257 10.2400000000 0.0083458750 0.0040462637 0.0095131258 0.0105235002 0.0694690000 9497941 955859216 1785389056 -0.0205993466 0.0026494323 0.2943226397 258 10.2800000000 0.0083452342 0.0040629264 0.0095131258 0.0105363696 0.0697670000 9541179 955859216 1787166720 -0.0214259867 0.0034980215 0.2927294672 259 10.3200000000 0.0083353091 0.0040794221 0.0095131258 0.0105384705 0.0675460000 9542433 955859216 1786281984 -0.0223301593 0.0042982586 0.2911951542 260 10.3600000000 0.0085620470 0.0040966629 0.0095131258 0.0105574633 0.0692430000 9543687 955859216 1785569280 -0.0233381130 0.0051680882 0.2896051705 261 10.4000000000 0.0085441172 0.0041137030 0.0095131258 0.0105906503 0.0734990000 9544941 955859216 1784532992 -0.0242030881 0.0058256760 0.2881085873 262 10.4400000000 0.0085816598 0.0041307563 0.0095131258 0.0106024781 0.0847900000 9546195 955859216 1783517184 -0.0250372309 0.0065071322 0.2864305377 263 10.4800000000 0.0086289039 0.0041478595 0.0095131258 0.0106021890 0.0667220000 9547449 955859216 1784881152 -0.0259612110 0.0073234299 0.2848786414 264 10.5200000000 0.0086813346 0.0041650317 0.0095131258 0.0106063002 0.0774730000 9548703 955859216 1784279040 -0.0269388277 0.0080384081 0.2832970321 265 10.5600000000 0.0087176794 0.0041822115 0.0095131258 0.0106311713 0.1093970000 9549957 955859216 1783283712 -0.0278519467 0.0082384460 0.2819402218 266 10.6000000000 0.0086619668 0.0041990527 0.0095131258 0.0106301775 0.0905640000 9551211 955859216 1784643584 -0.0285849813 0.0086675780 0.2803940773 267 10.6400000000 0.0086987484 0.0042159055 0.0095131258 0.0106137737 0.0687210000 9552465 955859216 1786404864 -0.0294664800 0.0093551297 0.2786807716 268 10.6800000000 0.0086974064 0.0042326275 0.0095131258 0.0106045476 0.0683630000 9553719 955859216 1785683968 -0.0303478856 0.0097497143 0.2769843638 269 10.7200000000 0.0086988471 0.0042492306 0.0095131258 0.0106029737 0.0687950000 9554973 955859216 1784688640 -0.0312330369 0.0099884914 0.2756089866 270 10.7600000000 0.0087915780 0.0042660541 0.0095131258 0.0106078801 0.0647390000 9556227 955859216 1783644160 -0.0320423692 0.0101872915 0.2738806009 271 10.8000000000 0.0088871727 0.0042831062 0.0095131258 0.0106022038 0.0737140000 9557481 955859216 1782775808 -0.0327281021 0.0106604658 0.2717423141 272 10.8400000000 0.0089258300 0.0043001750 0.0095131258 0.0105885963 0.0683850000 9558735 955859216 1784135680 -0.0336622410 0.0111865159 0.2700963020 273 10.8800000000 0.0090652807 0.0043176296 0.0095131258 0.0105937875 0.0689670000 9559989 955859216 1783390208 -0.0345964283 0.0114571461 0.2682319582 274 10.9200000000 0.0090272743 0.0043348181 0.0095131258 0.0105929686 0.0671980000 9561243 955859216 1782521856 -0.0354515575 0.0116754053 0.2666550279 275 10.9600000000 0.0089957146 0.0043517668 0.0095131258 0.0105795132 0.0722800000 9562497 955859216 1781506048 -0.0359839499 0.0117704673 0.2647017539 276 11.0000000000 0.0089963218 0.0043685949 0.0095131258 0.0105645293 0.0682400000 9563751 955859216 1782865920 -0.0367463715 0.0118603837 0.2629778087 277 11.0400000000 0.0090543805 0.0043855111 0.0095131258 0.0105554919 0.0689610000 9565005 955859216 1782267904 -0.0376170985 0.0119259534 0.2614085674 278 11.0800000000 0.0091288006 0.0044025733 0.0095131258 0.0105483269 0.0635290000 9566259 955859216 1781235712 -0.0383597501 0.0119541306 0.2596812546 279 11.1200000000 0.0090159932 0.0044191089 0.0095131258 0.0105336353 0.0750960000 9567513 955859216 1780215808 -0.0390035845 0.0119678183 0.2581264377 280 11.1600000000 0.0091130240 0.0044358728 0.0095131258 0.0105157054 0.0687320000 9568767 955859216 1781596160 -0.0397640727 0.0122675002 0.2564146519 281 11.2000000000 0.0092165470 0.0044528859 0.0095131258 0.0104995177 0.0691640000 9570021 955859216 1780977664 -0.0405515954 0.0124741066 0.2547270954 282 11.2400000000 0.0092602372 0.0044699333 0.0095131258 0.0104832724 0.1008510000 9571275 955859216 1780109312 -0.0414522961 0.0127281891 0.2531112134 283 11.2800000000 0.0093227252 0.0044870809 0.0095131258 0.0104658258 0.0826810000 9572529 955859216 1779073024 -0.0423939638 0.0129960543 0.2515332401 284 11.3200000000 0.0093165739 0.0045040862 0.0095131258 0.0104477437 0.1105790000 9573783 955859216 1778057216 -0.0432226285 0.0131020406 0.2501225173 285 11.3600000000 0.0093286224 0.0045210144 0.0095131258 0.0104296839 0.0842100000 9575037 955859216 1777188864 -0.0442044586 0.0132741071 0.2483936995 286 11.4000000000 0.0092637688 0.0045375975 0.0095131258 0.0104117320 0.0794310000 9576291 955859216 1776119808 -0.0451691411 0.0134006534 0.2465656996 287 11.4400000000 0.0093056560 0.0045542109 0.0095131258 0.0103938556 0.0759710000 9577545 955859216 1775284224 -0.0461818129 0.0132679511 0.2448710650 288 11.4800000000 0.0093757659 0.0045709524 0.0095131258 0.0103761843 0.0940630000 9578799 955859216 1774399488 -0.0472242273 0.0130679663 0.2428821921 289 11.5200000000 0.0093663093 0.0045875453 0.0095131258 0.0103590483 0.0790090000 9580053 955859216 1773359104 -0.0488762856 0.0127949398 0.2415194958 290 11.5600000000 0.0094901044 0.0046044507 0.0095131258 0.0103415213 0.0718520000 9581307 955859216 1772490752 -0.0502055809 0.0124000162 0.2395323515 291 11.6000000000 0.0095751062 0.0046215320 0.0095751062 0.0103280484 0.0621890000 9582561 955859216 1771601920 -0.0517412536 0.0120661799 0.2377771586 292 11.6400000000 0.0093883481 0.0046378567 0.0095751062 0.0103106526 0.0765760000 9583815 955859216 1770713088 -0.0532924756 0.0116303014 0.2362662852 293 11.6800000000 0.0092825061 0.0046537088 0.0095751062 0.0102995717 0.0791440000 9585069 955859216 1772072960 -0.0548611023 0.0112184677 0.2346431911 294 11.7200000000 0.0094021223 0.0046698598 0.0095751062 0.0102825074 0.0708680000 9586323 955859216 1771450368 -0.0567147210 0.0108695356 0.2327428460 295 11.7600000000 0.0094636837 0.0046861101 0.0095751062 0.0102670901 0.1083350000 9587577 955859216 1770438656 -0.0587695800 0.0106575824 0.2311844975 296 11.8000000000 0.0094648367 0.0047022544 0.0095751062 0.0102503727 0.0822820000 9588831 955859216 1771819008 -0.0608520024 0.0104872277 0.2295931131 297 11.8400000000 0.0094363606 0.0047181942 0.0095751062 0.0102333374 0.1063200000 9590085 955859216 1773580288 -0.0629567429 0.0103764674 0.2280778736 298 11.8800000000 0.0093284855 0.0047336650 0.0095751062 0.0102208440 0.1115920000 9591339 955859216 1775357952 -0.0650131851 0.0103226835 0.2265077978 299 11.9200000000 0.0094198780 0.0047493379 0.0095751062 0.0102112855 0.0764850000 9592593 955859216 1777008640 -0.0673657805 0.0103278542 0.2250466943 300 11.9600000000 0.0094442517 0.0047649876 0.0095751062 0.0101969548 0.0721610000 9593847 955859216 1778802688 -0.0697310939 0.0100482926 0.2235049307 301 12.0000000000 0.0095460424 0.0047808715 0.0095751062 0.0101862419 0.0694040000 9595101 955859216 1780436992 -0.0720945001 0.0100420024 0.2219331115 302 12.0400000000 0.0096690999 0.0047970577 0.0096690999 0.0101736400 0.0701050000 9596355 955859216 1782087680 -0.0745804980 0.0101581886 0.2204470485 303 12.0800000000 0.0096576503 0.0048130993 0.0096690999 0.0101598966 0.0894960000 9597609 955859216 1783865344 -0.0769753829 0.0101895323 0.2187791467 304 12.1200000000 0.0095408903 0.0048286512 0.0096690999 0.0101491667 0.0689470000 9598863 955859216 1785516032 -0.0793675184 0.0101526054 0.2173504382 305 12.1600000000 0.0096203098 0.0048443616 0.0096690999 0.0101410478 0.0711230000 9600117 955859216 1787166720 -0.0818627849 0.0103998538 0.2157048732 306 12.2000000000 0.0096783368 0.0048601589 0.0096783368 0.0101269547 0.0762950000 9601371 955859216 1786429440 -0.0844373628 0.0106117455 0.2143170685 307 12.2400000000 0.0096904784 0.0048758928 0.0096904784 0.0101106619 0.0864710000 9602625 955859216 1785516032 -0.0868965611 0.0106594115 0.2127563357 308 12.2800000000 0.0095267361 0.0048909930 0.0096904784 0.0100949054 0.0907750000 9603879 955859216 1784532992 -0.0892579928 0.0103568165 0.2114667445 309 12.3200000000 0.0094830561 0.0049058540 0.0096904784 0.0100851810 0.0689530000 9605133 955859216 1783517184 -0.0916319788 0.0100666462 0.2101233006 310 12.3600000000 0.0096328277 0.0049211023 0.0096904784 0.0100761662 0.0693240000 9606387 955859216 1782648832 -0.0941087976 0.0099979341 0.2086651772 311 12.4000000000 0.0098128151 0.0049368313 0.0098128151 0.0100603230 0.0684100000 9607641 955859216 1781612544 -0.0966025293 0.0095744468 0.2076961249 312 12.4400000000 0.0097168386 0.0049521518 0.0098128151 0.0100444133 0.0694730000 9608895 955859216 1782992896 -0.0991349295 0.0093150008 0.2065771669 313 12.4800000000 0.0097766975 0.0049675657 0.0098128151 0.0100296786 0.0689900000 9610149 955859216 1782394880 -0.1015074551 0.0089581683 0.2054232955 314 12.5200000000 0.0098408349 0.0049830857 0.0098408349 0.0100140961 0.0694220000 9611403 955859216 1781358592 -0.1041430235 0.0084940214 0.2045390457 315 12.5600000000 0.0097772703 0.0049983053 0.0098408349 0.0099997848 0.0690720000 9612657 955859216 1780490240 -0.1062131450 0.0074560307 0.2036666572 316 12.6000000000 0.0096353488 0.0050129795 0.0098408349 0.0099887776 0.0693020000 9613911 955859216 1781850112 -0.1087310240 0.0069438927 0.2029272169 317 12.6400000000 0.0094989510 0.0050271308 0.0098408349 0.0099785444 0.0691090000 9615165 955859216 1781252096 -0.1107419878 0.0061731506 0.2019667327 318 12.6800000000 0.0094725620 0.0050411102 0.0098408349 0.0099805922 0.0719180000 9616419 955859216 1780215808 -0.1126936376 0.0054190443 0.2011806071 319 12.7200000000 0.0096594235 0.0050555876 0.0098408349 0.0099765702 0.0681020000 9617673 955859216 1779212288 -0.1145758033 0.0048687882 0.1999230683 320 12.7600000000 0.0099766152 0.0050709658 0.0099766152 0.0099622750 0.0788250000 9618927 955859216 1780580352 -0.1161867157 0.0041035824 0.1987419575 321 12.8000000000 0.0100314002 0.0050864189 0.0100314002 0.0099470705 0.1102200000 9620181 955859216 1777582080 -0.1176709682 0.0032846136 0.1974373609 322 12.8400000000 0.0099357096 0.0051014788 0.0100314002 0.0099345283 0.1103530000 9621435 955859216 1776533504 -0.1190712452 0.0021468992 0.1963377297 323 12.8800000000 0.0101510296 0.0051171121 0.0101510296 0.0099282108 0.0872740000 9622689 955859216 1775665152 -0.1206188649 0.0015629536 0.1950044334 324 12.9200000000 0.0102062998 0.0051328195 0.0102062998 0.0099167072 0.0692420000 9623943 955859216 1777025024 -0.1222771779 0.0010399575 0.1934595406 325 12.9600000000 0.0101249283 0.0051481798 0.0102062998 0.0099041451 0.0688570000 9625197 955859216 1776279552 -0.1238211170 0.0003149780 0.1920411587 326 13.0000000000 0.0100575052 0.0051632391 0.0102062998 0.0098945642 0.0761320000 9626451 955859216 1775411200 -0.1251171231 -0.0004636570 0.1905115694 327 13.0400000000 0.0101464642 0.0051784783 0.0102062998 0.0098856526 0.0719670000 9627705 955859216 1774522368 -0.1265233755 -0.0011310129 0.1888595521 328 13.0800000000 0.0102213752 0.0051938530 0.0102213752 0.0098736585 0.0697580000 9628959 955859216 1775882240 -0.1277457774 -0.0018500810 0.1874180585 329 13.1200000000 0.0101989675 0.0052090661 0.0102213752 0.0098637166 0.0846470000 9630213 955859216 1775259648 -0.1289653033 -0.0025131498 0.1856517196 330 13.1600000000 0.0102392323 0.0052243090 0.0102392323 0.0098534042 0.1079360000 9631467 955859216 1772990464 -0.1303237975 -0.0032912721 0.1838848889 331 13.2000000000 0.0103402603 0.0052397651 0.0103402603 0.0098435291 0.0884600000 9632721 955859216 1772736512 -0.1316584498 -0.0038833800 0.1818838269 332 13.2400000000 0.0102965469 0.0052549964 0.0103402603 0.0098347237 0.0692990000 9633975 955859216 1772961792 -0.1329625696 -0.0045671454 0.1799572110 333 13.2800000000 0.0104449093 0.0052705817 0.0104449093 0.0098296909 0.1012500000 9635229 955859216 1771851776 -0.1341096908 -0.0049065491 0.1775042415 334 13.3200000000 0.0104243448 0.0052860121 0.0104449093 0.0098197423 0.1115440000 9636483 955859216 1770717184 -0.1354550868 -0.0051466846 0.1751887649 335 13.3600000000 0.0100501701 0.0053002335 0.0104449093 0.0098113457 0.0909250000 9637737 955859216 1769824256 -0.1365911067 -0.0062360070 0.1732422113 336 13.4000000000 0.0102699250 0.0053150242 0.0104449093 0.0098366475 0.0668730000 9638991 955859216 1771184128 -0.1376042813 -0.0065326006 0.1706409156 337 13.4400000000 0.0105317840 0.0053305042 0.0105317840 0.0098456784 0.0693730000 9640245 955859216 1770565632 -0.1388514936 -0.0063614156 0.1672706008 338 13.4800000000 0.0104764206 0.0053457288 0.0105317840 0.0098431953 0.0621550000 9641499 955859216 1769697280 -0.1401616782 -0.0065359371 0.1648648977 339 13.5200000000 0.0106481211 0.0053613701 0.0106481211 0.0098416877 0.0738330000 9642753 955859216 1768808448 -0.1414011717 -0.0063341255 0.1621599346 340 13.5600000000 0.0108242864 0.0053774375 0.0108242864 0.0098294122 0.0669660000 9644007 955859216 1770151936 -0.1426243484 -0.0060301656 0.1593893915 341 13.6000000000 0.0108212838 0.0053934019 0.0108242864 0.0098149602 0.0694280000 9645261 955859216 1769697280 -0.1438653767 -0.0058464282 0.1568783820 342 13.6400000000 0.0106693925 0.0054088287 0.0108242864 0.0098005810 0.0642990000 9646515 955859216 1768808448 -0.1450692415 -0.0058934842 0.1542261541 343 13.6800000000 0.0104925288 0.0054236500 0.0108242864 0.0097867912 0.0754160000 9647769 955859216 1767919616 -0.1460604519 -0.0062771942 0.1516479254 344 13.7200000000 0.0105621433 0.0054385875 0.0108242864 0.0097805198 0.0669610000 9649023 955859216 1769279488 -0.1470220983 -0.0062849573 0.1483754218 345 13.7600000000 0.0107150991 0.0054538817 0.0108242864 0.0097719459 0.0700630000 9650277 955859216 1768681472 -0.1480108351 -0.0061342344 0.1452650875 346 13.8000000000 0.0106733236 0.0054689668 0.0108242864 0.0097582693 0.0604010000 9651531 955859216 1767792640 -0.1490073204 -0.0059922305 0.1424672753 347 13.8400000000 0.0106262332 0.0054838293 0.0108242864 0.0097442003 0.0772980000 9652785 955859216 1766903808 -0.1499039829 -0.0061457003 0.1395543665 348 13.8800000000 0.0105100721 0.0054982725 0.0108242864 0.0097306555 0.0681290000 9654039 955859216 1768263680 -0.1509102136 -0.0063678562 0.1370194852 349 13.9200000000 0.0105445106 0.0055127316 0.0108242864 0.0097184782 0.0693170000 9655293 955859216 1767792640 -0.1517621279 -0.0067954198 0.1341774911 350 13.9600000000 0.0105577148 0.0055271459 0.0108242864 0.0097082916 0.0617830000 9656547 955859216 1766903808 -0.1524171382 -0.0071475715 0.1309705228 351 14.0000000000 0.0105094081 0.0055413403 0.0108242864 0.0096976964 0.0762820000 9657801 955859216 1766014976 -0.1531516612 -0.0076235845 0.1281759441 352 14.0400000000 0.0105133317 0.0055554653 0.0108242864 0.0096909194 0.0826350000 9659055 955859216 1767383040 -0.1538482308 -0.0079534696 0.1250972301 353 14.0800000000 0.0105059734 0.0055694894 0.0108242864 0.0096828128 0.0875370000 9660309 955859216 1766621184 -0.1546066105 -0.0082065240 0.1222811043 354 14.1200000000 0.0106382621 0.0055838080 0.0108242864 0.0096714798 0.0693350000 9661563 955859216 1766252544 -0.1554803550 -0.0081177345 0.1194105744 355 14.1600000000 0.0105531206 0.0055978061 0.0108242864 0.0096579597 0.0686910000 9662817 955859216 1765515264 -0.1562309265 -0.0081285825 0.1169919148 356 14.2000000000 0.0105528161 0.0056117246 0.0108242864 0.0096444595 0.0746810000 9664071 955859216 1764995072 -0.1569727361 -0.0082572624 0.1143070310 357 14.2400000000 0.0107036401 0.0056259877 0.0108242864 0.0096311473 0.0777260000 9665325 955859216 1765003264 -0.1576907039 -0.0082068173 0.1116390005 358 14.2800000000 0.0106684230 0.0056400727 0.0108242864 0.0096216967 0.0760140000 9666579 955859216 1765113856 -0.1585459709 -0.0080274884 0.1095082089 359 14.3200000000 0.0103757856 0.0056532641 0.0108242864 0.0096145268 0.0729080000 9667833 955859216 1765130240 -0.1591571271 -0.0086010443 0.1069687307 360 14.3600000000 0.0103084520 0.0056661952 0.0108242864 0.0096022812 0.0687700000 9669087 955859216 1766494208 -0.1594011635 -0.0094652800 0.1046500355 361 14.4000000000 0.0104084611 0.0056793317 0.0108242864 0.0095989083 0.0780690000 9670341 955859216 1766383616 -0.1598832458 -0.0097206989 0.1024024636 362 14.4400000000 0.0104601942 0.0056925385 0.0108242864 0.0095879403 0.1090460000 9671595 955859216 1764999168 -0.1603462845 -0.0098037152 0.0995992720 363 14.4800000000 0.0102267638 0.0057050294 0.0108242864 0.0095752895 0.1082780000 9672849 955859216 1764986880 -0.1607820839 -0.0102038393 0.0975386798 364 14.5200000000 0.0101467725 0.0057172320 0.0108242864 0.0095671005 0.0830760000 9674103 955859216 1765113856 -0.1609700471 -0.0104803462 0.0951333568 365 14.5600000000 0.0100273732 0.0057290406 0.0108242864 0.0095565642 0.0833610000 9675357 955859216 1765113856 -0.1614377946 -0.0097840941 0.0926780403 366 14.6000000000 0.0097902119 0.0057401367 0.0108242864 0.0095468228 0.0924470000 9676611 955859216 1765130240 -0.1618951559 -0.0093249287 0.0902153924 367 14.6400000000 0.0096881734 0.0057508943 0.0108242864 0.0095379778 0.0862710000 9677865 955859216 1765130240 -0.1620022804 -0.0104314070 0.0878790542 368 14.6800000000 0.0098797828 0.0057621141 0.0108242864 0.0095285659 0.0700350000 9679119 955859216 1766494208 -0.1622096747 -0.0112560419 0.0854519606 369 14.7200000000 0.0098057156 0.0057730724 0.0108242864 0.0095192093 0.0691900000 9680373 955859216 1766150144 -0.1625511050 -0.0111717610 0.0832405761 370 14.7600000000 0.0096012475 0.0057834188 0.0108242864 0.0095072821 0.0690860000 9681627 955859216 1765261312 -0.1629344225 -0.0105191302 0.0810341090 371 14.8000000000 0.0095353452 0.0057935318 0.0108242864 0.0094947035 0.0685440000 9682881 955859216 1764999168 -0.1635325551 -0.0098243086 0.0782928169 372 14.8400000000 0.0094616534 0.0058033924 0.0108242864 0.0094881372 0.0693030000 9684135 955859216 1766363136 -0.1639350206 -0.0097488137 0.0753592476 373 14.8800000000 0.0096173575 0.0058136175 0.0108242864 0.0094814856 0.0697570000 9685389 955859216 1765720064 -0.1644076109 -0.0095907310 0.0725846812 374 14.9200000000 0.0098032700 0.0058242850 0.0108242864 0.0094864495 0.0766330000 9686643 955859216 1765081088 -0.1651712805 -0.0094938986 0.0702576339 375 14.9600000000 0.0097629102 0.0058347880 0.0108242864 0.0095003574 0.0719890000 9687897 955859216 1765130240 -0.1656875014 -0.0106037855 0.0683641061 376 15.0000000000 0.0098870331 0.0058455652 0.0108242864 0.0094908830 0.0684380000 9689151 955859216 1765130240 -0.1662197858 -0.0113335587 0.0659977347 377 15.0400000000 0.0101883858 0.0058570847 0.0108242864 0.0094789892 0.0709530000 9690405 955859216 1765130240 -0.1670336872 -0.0107335085 0.0636331141 378 15.0800000000 0.0100316266 0.0058681284 0.0108242864 0.0094888432 0.0671960000 9691659 955859216 1766494208 -0.1674543023 -0.0109782480 0.0608636327 379 15.1200000000 0.0098635759 0.0058786705 0.0108242864 0.0094845589 0.0690770000 9692913 955859216 1766023168 -0.1679960638 -0.0117432382 0.0584651828 380 15.1600000000 0.0100474684 0.0058896410 0.0108242864 0.0094720955 0.0599570000 9694167 955859216 1765134336 -0.1686045080 -0.0118373949 0.0556153692 381 15.2000000000 0.0100025646 0.0059004361 0.0108242864 0.0094609631 0.0772560000 9695421 955859216 1765130240 -0.1695436388 -0.0117709944 0.0535039939 382 15.2400000000 0.0099985395 0.0059111641 0.0108242864 0.0094497978 0.0687110000 9696675 955859216 1766494208 -0.1699583530 -0.0121801160 0.0505679548 383 15.2800000000 0.0101211313 0.0059221562 0.0108242864 0.0094375387 0.0839700000 9697929 955859216 1766150144 -0.1707247943 -0.0122109009 0.0483936109 384 15.3200000000 0.0101670753 0.0059332107 0.0108242864 0.0094261189 0.0924120000 9699183 955859216 1765261312 -0.1718334407 -0.0120307431 0.0458194315 385 15.3600000000 0.0101803634 0.0059442422 0.0108242864 0.0094163249 0.0795710000 9700437 955859216 1764999168 -0.1730511785 -0.0117123853 0.0435440168 386 15.4000000000 0.0101561183 0.0059551538 0.0108242864 0.0094057081 0.0713960000 9701691 955859216 1764986880 -0.1738289297 -0.0115818353 0.0406551361 387 15.4400000000 0.0102226743 0.0059661810 0.0108242864 0.0093939931 0.0874870000 9702945 955859216 1764986880 -0.1748015434 -0.0111634927 0.0380250178 388 15.4800000000 0.0102496743 0.0059772210 0.0108242864 0.0093859119 0.0869480000 9704199 955859216 1765113856 -0.1764172614 -0.0104847336 0.0359444171 389 15.5200000000 0.0102071473 0.0059880948 0.0108242864 0.0093825566 0.1056590000 9705453 955859216 1765130240 -0.1772475690 -0.0100397635 0.0331865475 390 15.5600000000 0.0101769930 0.0059988356 0.0108242864 0.0093763386 0.1070530000 9706707 955859216 1765130240 -0.1787216067 -0.0096939690 0.0309494585 391 15.6000000000 0.0103561645 0.0060099796 0.0108242864 0.0093673689 0.1108030000 9707961 955859216 1765130240 -0.1802706420 -0.0089182081 0.0286164787 392 15.6400000000 0.0103366887 0.0060210171 0.0108242864 0.0093679104 0.0880050000 9709215 955859216 1766494208 -0.1815684140 -0.0082966313 0.0261120871 393 15.6800000000 0.0103726489 0.0060320900 0.0108242864 0.0093660776 0.0707250000 9710469 955859216 1768382464 -0.1825416535 -0.0080614742 0.0237186290 394 15.7200000000 0.0104506025 0.0060433045 0.0108242864 0.0093616890 0.0881630000 9711723 955859216 1770033152 -0.1838056892 -0.0076636681 0.0214266479 395 15.7600000000 0.0105794081 0.0060547883 0.0108242864 0.0093553597 0.0735920000 9712977 955859216 1771683840 -0.1855525672 -0.0069697108 0.0188341420 396 15.8000000000 0.0106497854 0.0060663918 0.0108242864 0.0093512621 0.0733320000 9714231 955859216 1773461504 -0.1865022033 -0.0061803753 0.0159778409 397 15.8400000000 0.0106020784 0.0060778167 0.0108242864 0.0093555251 0.0892910000 9715485 955859216 1775112192 -0.1878769100 -0.0054448261 0.0138932932 398 15.8800000000 0.0103597958 0.0060885755 0.0108242864 0.0093648202 0.0856640000 9716739 955859216 1776762880 -0.1890503019 -0.0055969120 0.0114085190 399 15.9200000000 0.0103616500 0.0060992849 0.0108242864 0.0093572733 0.0709230000 9717993 955859216 1778540544 -0.1901793033 -0.0057110251 0.0091994954 400 15.9600000000 0.0106842713 0.0061107474 0.0108242864 0.0093468322 0.0691180000 9719247 955859216 1780191232 -0.1913724840 -0.0049323272 0.0067169718 401 16.0000000000 0.0105727846 0.0061218747 0.0108242864 0.0093512248 0.0699470000 9720501 955859216 1781985280 -0.1923540682 -0.0046294229 0.0044176532 402 16.0400000000 0.0106082624 0.0061330349 0.0108242864 0.0093477076 0.0683390000 9721755 955859216 1783619584 -0.1935449541 -0.0043141730 0.0022402487 403 16.0800000000 0.0107569173 0.0061445085 0.0108242864 0.0093500328 0.0696670000 9723009 955859216 1785270272 -0.1945714653 -0.0037925395 0.0000186972 404 16.1200000000 0.0108782733 0.0061562257 0.0108782733 0.0093667101 0.0686560000 9724263 955859216 1787047936 -0.1949165761 -0.0034557492 -0.0025776944 405 16.1600000000 0.0106181633 0.0061672429 0.0108782733 0.0093870334 0.0813270000 9725517 955859216 1786163200 -0.1959580332 -0.0034099824 -0.0043260190 406 16.2000000000 0.0109664509 0.0061790636 0.0109664509 0.0093828051 0.1094620000 9726771 955859216 1784803328 -0.1965759546 -0.0024016381 -0.0067188325 407 16.2400000000 0.0108059179 0.0061904318 0.0109664509 0.0093983697 0.0971120000 9728025 955859216 1783799808 -0.1975156963 -0.0020614725 -0.0084815668 408 16.2800000000 0.0108775422 0.0062019198 0.0109664509 0.0094036559 0.0799630000 9729279 955859216 1782763520 -0.1979282647 -0.0020053098 -0.0105790524 409 16.3200000000 0.0109410714 0.0062135070 0.0109664509 0.0093969815 0.0690490000 9730533 955859216 1784143872 -0.1985728592 -0.0020151529 -0.0126595376 410 16.3600000000 0.0113602309 0.0062260599 0.0113602309 0.0093878818 0.0688950000 9731787 955859216 1783525376 -0.1989884824 -0.0013496018 -0.0148148900 411 16.3999999990 0.0113595678 0.0062385502 0.0113602309 0.0093947293 0.0640100000 9733041 955859216 1782657024 -0.1995071918 -0.0008503266 -0.0169076025 412 16.4400000000 0.0113720922 0.0062510103 0.0113720922 0.0094003113 0.0743310000 9734295 955859216 1781620736 -0.2000534236 -0.0002195439 -0.0190994646 413 16.4800000000 0.0113398181 0.0062633319 0.0113720922 0.0093987510 0.0682210000 9735549 955859216 1783001088 -0.2007420212 -0.0000457605 -0.0211078599 414 16.5200000000 0.0114043457 0.0062757498 0.0114043457 0.0093911733 0.0686900000 9736803 955859216 1782382592 -0.2010970116 0.0000696816 -0.0232854821 415 16.5599999990 0.0117662819 0.0062889800 0.0117662819 0.0093805976 0.0818800000 9738057 955859216 1781514240 -0.2014184594 0.0005494616 -0.0258057024 416 16.6000000000 0.0117243342 0.0063020457 0.0117662819 0.0093738996 0.1099890000 9739311 955859216 1780477952 -0.2018955499 0.0007448397 -0.0279839970 417 16.6400000000 0.0119238347 0.0063155272 0.0119238347 0.0093687140 0.1109960000 9740565 955859216 1779556352 -0.2026170939 0.0011392049 -0.0303677507 418 16.6800000000 0.0120269405 0.0063291909 0.0120269405 0.0093684574 0.1220500000 9741819 955859216 1777819648 -0.2036998570 0.0020146184 -0.0328258574 419 16.7199999990 0.0121222660 0.0063430168 0.0121222660 0.0093808844 0.0887790000 9743073 955859216 1779462144 -0.2041612417 0.0031665515 -0.0355688594 420 16.7600000000 0.0115489829 0.0063554120 0.0121222660 0.0094021187 0.0875340000 9744327 955859216 1780953088 -0.2043287009 0.0037411461 -0.0380913951 421 16.8000000000 0.0116266208 0.0063679327 0.0121222660 0.0093989426 0.0705160000 9745581 955859216 1782603776 -0.2047019899 0.0042989235 -0.0408604927 422 16.8400000000 0.0117350323 0.0063806509 0.0121222660 0.0093941728 0.0687170000 9746835 955859216 1784254464 -0.2044007033 0.0049389405 -0.0437138192 423 16.8799999990 0.0116814319 0.0063931823 0.0121222660 0.0093892478 0.0695420000 9748089 955859216 1786032128 -0.2051176280 0.0056061796 -0.0462475643 424 16.9200000000 0.0118320351 0.0064060098 0.0121222660 0.0093842681 0.0686480000 9749343 955859216 1787682816 -0.2054516971 0.0064704581 -0.0492667966 425 16.9600000000 0.0115781194 0.0064181795 0.0121222660 0.0094003405 0.0836250000 9750597 955859216 1786691584 -0.2052075267 0.0070625464 -0.0523488000 426 17.0000000000 0.0112923058 0.0064296211 0.0121222660 0.0093989245 0.0931320000 9751851 955859216 1785667584 -0.2050415576 0.0074837501 -0.0552509539 427 17.0400000000 0.0110794613 0.0064405107 0.0121222660 0.0093886621 0.0838620000 9753105 955859216 1785032704 -0.2050415277 0.0074068438 -0.0580512099 428 17.0800000000 0.0113371611 0.0064519514 0.0121222660 0.0093778499 0.0693740000 9754359 955859216 1784127488 -0.2036554068 0.0077705965 -0.0615011901 429 17.1200000000 0.0112420283 0.0064631171 0.0121222660 0.0093679514 0.0683920000 9755613 955859216 1783029760 -0.2031176686 0.0080379760 -0.0646636635 430 17.1600000000 0.0112929381 0.0064743492 0.0121222660 0.0093573223 0.0733840000 9756867 955859216 1781993472 -0.2034485936 0.0082545290 -0.0676087812 431 17.2000000000 0.0116028907 0.0064862484 0.0121222660 0.0093466024 0.0835450000 9758121 955859216 1781125120 -0.2030664980 0.0087401215 -0.0711404383 432 17.2400000000 0.0116068805 0.0064981017 0.0121222660 0.0093410041 0.0889460000 9759375 955859216 1780088832 -0.2030061930 0.0091746431 -0.0740937218 433 17.2800000000 0.0114767458 0.0065095998 0.0121222660 0.0093386035 0.1095930000 9760629 955859216 1779220480 -0.2030876726 0.0096312677 -0.0773560181 434 17.3200000000 0.0115450649 0.0065212022 0.0121222660 0.0093317031 0.0875480000 9761883 955859216 1778184192 -0.2028571367 0.0099341143 -0.0804618299 435 17.3600000000 0.0119712576 0.0065337311 0.0121222660 0.0093225635 0.1099250000 9763137 955859216 1777315840 -0.2029848844 0.0108362138 -0.0839059874 436 17.4000000000 0.0116566522 0.0065454809 0.0121222660 0.0093303542 0.1089550000 9764391 955859216 1776279552 -0.2023076117 0.0116231702 -0.0871061087 437 17.4400000000 0.0113425106 0.0065564581 0.0121222660 0.0093455645 0.0899090000 9765645 955859216 1775411200 -0.2016526312 0.0122489175 -0.0899434686 438 17.4800000000 0.0112134358 0.0065670904 0.0121222660 0.0093427040 0.0793020000 9766899 955859216 1776754688 -0.2005924135 0.0127206910 -0.0931695551 439 17.5200000000 0.0111614987 0.0065775561 0.0121222660 0.0093412152 0.0705060000 9768153 955859216 1776144384 -0.1985356212 0.0132510643 -0.0963110849 440 17.5600000000 0.0110708671 0.0065877681 0.0121222660 0.0093456452 0.0685460000 9769407 955859216 1775284224 -0.1977462620 0.0136044743 -0.0989583284 441 17.6000000000 0.0110962400 0.0065979914 0.0121222660 0.0093500538 0.0668080000 9770661 955859216 1774395392 -0.1969944537 0.0141207157 -0.1015759557 442 17.6400000000 0.0109078661 0.0066077423 0.0121222660 0.0093607253 0.0902180000 9771915 955859216 1773506560 -0.1967494637 0.0140266996 -0.1042901799 443 17.6800000000 0.0107541159 0.0066171020 0.0121222660 0.0093631908 0.1086990000 9773169 955859216 1772617728 -0.1965328008 0.0136291683 -0.1066219062 444 17.7200000000 0.0109576769 0.0066268781 0.0121222660 0.0093563379 0.0879740000 9774423 955859216 1771728896 -0.1963990778 0.0133584412 -0.1092838421 445 17.7600000000 0.0113900099 0.0066375818 0.0121222660 0.0093458466 0.0697690000 9775677 955859216 1773088768 -0.1964418292 0.0136579257 -0.1121223941 446 17.8000000000 0.0113051347 0.0066480471 0.0121222660 0.0093360966 0.0688730000 9776931 955859216 1772490752 -0.1963828504 0.0138910394 -0.1148029417 447 17.8400000000 0.0115043288 0.0066589113 0.0121222660 0.0093293419 0.0628900000 9778185 955859216 1771601920 -0.1965750754 0.0142395357 -0.1173740253 448 17.8800000000 0.0112744328 0.0066692138 0.0121222660 0.0093202859 0.0783360000 9779439 955859216 1770713088 -0.1961855888 0.0145261129 -0.1198175028 449 17.9200000000 0.0107906591 0.0066783930 0.0121222660 0.0093127312 0.0798990000 9780693 955859216 1772056576 -0.1956582218 0.0140617592 -0.1219965294 450 17.9600000000 0.0115370462 0.0066891900 0.0121222660 0.0093024981 0.0836700000 9781947 955859216 1771184128 -0.1957383752 0.0141788423 -0.1270718426 451 18.0000000000 0.0112127187 0.0066992200 0.0121222660 0.0093085050 0.1112860000 9783201 955859216 1768185856 -0.1958737373 0.0143114440 -0.1296565384 452 18.0400000000 0.0107241077 0.0067081246 0.0121222660 0.0093147215 0.0895890000 9784455 955859216 1767284736 -0.1961977035 0.0136607196 -0.1317353398 453 18.0800000000 0.0107782036 0.0067171093 0.0121222660 0.0093198357 0.1062370000 9785709 955859216 1766395904 -0.1963536739 0.0129785454 -0.1340877414 454 18.1200000000 0.0111908866 0.0067269634 0.0121222660 0.0093153212 0.0899080000 9786963 955859216 1765507072 -0.1967818141 0.0130483219 -0.1369565129 455 18.1600000000 0.0117219025 0.0067379413 0.0121222660 0.0093051951 0.1079390000 9788217 955859216 1765134336 -0.1973793209 0.0136538455 -0.1400029808 456 18.2000000000 0.0117359972 0.0067489020 0.0121222660 0.0092957407 0.0872870000 9789471 955859216 1765122048 -0.1978027821 0.0146071371 -0.1427026540 457 18.2400000000 0.0110975271 0.0067584176 0.0121222660 0.0092974970 0.0880790000 9790725 955859216 1765122048 -0.1982477605 0.0150470221 -0.1450823694 458 18.2800000000 0.0113014644 0.0067683369 0.0121222660 0.0092946632 0.1103210000 9791979 955859216 1765089280 -0.1989988387 0.0155719547 -0.1478943080 459 18.3200000000 0.0110313874 0.0067776246 0.0121222660 0.0093104964 0.0870030000 9793233 955859216 1765122048 -0.1999706477 0.0160288122 -0.1504802555 460 18.3600000000 0.0108220698 0.0067864169 0.0121222660 0.0093159135 0.0703890000 9794487 955859216 1766486016 -0.2002906799 0.0164086912 -0.1533668786 461 18.4000000000 0.0108886957 0.0067953155 0.0121222660 0.0093129689 0.0821370000 9795741 955859216 1766141952 -0.2010895014 0.0166308861 -0.1562144011 462 18.4400000000 0.0104583809 0.0068032442 0.0121222660 0.0093338640 0.0719100000 9796995 955859216 1765253120 -0.2015024424 0.0163196512 -0.1586665809 463 18.4800000000 0.0105915759 0.0068114264 0.0121222660 0.0093400970 0.0687970000 9798249 955859216 1765138432 -0.2020128965 0.0163302533 -0.1616218537 464 18.5200000000 0.0103294561 0.0068190083 0.0121222660 0.0093405890 0.0696330000 9799503 955859216 1765138432 -0.2028217763 0.0159756057 -0.1641055197 465 18.5600000000 0.0105715040 0.0068270782 0.0121222660 0.0093384131 0.0681570000 9800757 955859216 1766502400 -0.2035734802 0.0161407348 -0.1672215164 466 18.6000000000 0.0110693220 0.0068361817 0.0121222660 0.0093295840 0.0852550000 9802011 955859216 1766375424 -0.2049277276 0.0168732479 -0.1705901176 467 18.6400000000 0.0113094458 0.0068457605 0.0121222660 0.0093196307 0.1092250000 9803265 955859216 1764974592 -0.2062356174 0.0177906659 -0.1737517118 468 18.6800000000 0.0113950744 0.0068554812 0.0121222660 0.0093103666 0.0871420000 9804519 955859216 1764995072 -0.2074044943 0.0188586116 -0.1768884212 469 18.7200000000 0.0110418489 0.0068644074 0.0121222660 0.0093098070 0.0709670000 9805773 955859216 1766342656 -0.2082749605 0.0196452532 -0.1797173470 470 18.7600000000 0.0117419111 0.0068747850 0.0121222660 0.0093006594 0.0827320000 9807027 955859216 1765593088 -0.2097336203 0.0215784442 -0.1831901073 471 18.8000000000 0.0106037045 0.0068827021 0.0121222660 0.0093288634 0.0844850000 9808281 955859216 1765113856 -0.2104678452 0.0225630794 -0.1857551783 472 18.8400000000 0.0102801211 0.0068899000 0.0121222660 0.0094175068 0.0718480000 9809535 955859216 1765122048 -0.2113296539 0.0240857173 -0.1887269467 473 18.8800000000 0.0096844574 0.0068958081 0.0121222660 0.0094815286 0.0691420000 9810789 955859216 1765122048 -0.2123141885 0.0244141929 -0.1916415989 474 18.9200000000 0.0100795096 0.0069025248 0.0121222660 0.0094824176 0.0836490000 9812043 955859216 1765138432 -0.2140575796 0.0244550183 -0.1944756210 475 18.9600000000 0.0105567062 0.0069102178 0.0121222660 0.0094788821 0.0721610000 9813297 955859216 1765138432 -0.2154441476 0.0252622366 -0.1973757893 476 19.0000000000 0.0105767986 0.0069179207 0.0121222660 0.0094952728 0.0684150000 9814551 955859216 1766502400 -0.2165708542 0.0268777311 -0.2002276927 477 19.0400000000 0.0107468292 0.0069259478 0.0121222660 0.0094943196 0.0683380000 9815805 955859216 1766129664 -0.2173621804 0.0286545493 -0.2032935321 478 19.0800000000 0.0111352494 0.0069347539 0.0121222660 0.0094859547 0.0827450000 9817059 955859216 1765392384 -0.2184296399 0.0303936638 -0.2059955448 479 19.1200000000 0.0108078551 0.0069428397 0.0121222660 0.0094840649 0.0726340000 9818313 955859216 1765117952 -0.2196755707 0.0317014530 -0.2084290981 480 19.1600000000 0.0105948942 0.0069504481 0.0121222660 0.0094858951 0.0757090000 9819567 955859216 1765122048 -0.2206766307 0.0328786634 -0.2110324651 481 19.2000000000 0.0104999971 0.0069578276 0.0121222660 0.0094826987 0.0720920000 9820821 955859216 1765105664 -0.2216192633 0.0337286033 -0.2134112418 482 19.2400000000 0.0105313370 0.0069652416 0.0121222660 0.0094803737 0.0889960000 9822075 955859216 1765122048 -0.2227270603 0.0347290151 -0.2159831524 483 19.2800000000 0.0098870136 0.0069712908 0.0121222660 0.0094994873 0.0837570000 9823329 955859216 1765122048 -0.2235274464 0.0347645991 -0.2179890573 484 19.3200000000 0.0101141334 0.0069777842 0.0121222660 0.0094976308 0.0870990000 9824583 955859216 1765122048 -0.2241311818 0.0349212699 -0.2200589180 485 19.3600000000 0.0102202604 0.0069844698 0.0121222660 0.0094895128 0.0890830000 9825837 955859216 1765138432 -0.2244638205 0.0350415744 -0.2218810171 486 19.4000000000 0.0104582738 0.0069916175 0.0121222660 0.0094810515 0.1075580000 9827091 955859216 1765122048 -0.2247735113 0.0354411528 -0.2239509076 487 19.4400000000 0.0106307138 0.0069990900 0.0121222660 0.0094749252 0.0920580000 9828345 955859216 1765122048 -0.2252995074 0.0363036357 -0.2260240614 488 19.4800000000 0.0105659096 0.0070063990 0.0121222660 0.0094712149 0.0851980000 9829599 955859216 1765122048 -0.2256319374 0.0371042415 -0.2281710058 489 19.5200000000 0.0100995749 0.0070127246 0.0121222660 0.0094747058 0.0698370000 9830853 955859216 1766486016 -0.2258702815 0.0372279920 -0.2299235463 490 19.5600000000 0.0102959070 0.0070194249 0.0121222660 0.0094699114 0.0816920000 9832107 955859216 1766014976 -0.2260501087 0.0377415344 -0.2319719344 491 19.6000000000 0.0104375537 0.0070263865 0.0121222660 0.0094621596 0.0719050000 9833361 955859216 1765199872 -0.2268736511 0.0378606021 -0.2339544296 492 19.6400000000 0.0106897242 0.0070338323 0.0121222660 0.0094537608 0.0797500000 9834615 955859216 1765138432 -0.2267101109 0.0385307223 -0.2360280752 493 19.6800000000 0.0103902845 0.0070406405 0.0121222660 0.0094487731 0.0830280000 9835869 955859216 1765138432 -0.2268725187 0.0389756933 -0.2378669977 494 19.7200000000 0.0106361071 0.0070479188 0.0121222660 0.0094413404 0.1110070000 9837123 955859216 1765138432 -0.2265499681 0.0397136584 -0.2398998439 495 19.7600000000 0.0101394048 0.0070541642 0.0121222660 0.0094430989 0.1087600000 9838377 955859216 1765122048 -0.2274326831 0.0397718921 -0.2418570817 496 19.8000000000 0.0101838019 0.0070604740 0.0121222660 0.0094438388 0.1104020000 9839631 955859216 1765122048 -0.2287874073 0.0398174077 -0.2442576438 497 19.8400000000 0.0100765079 0.0070665425 0.0121222660 0.0094405894 0.0855200000 9840885 955859216 1765597184 -0.2292934656 0.0393987894 -0.2462107986 498 19.8800000000 0.0097563788 0.0070719437 0.0121222660 0.0094353007 0.0712800000 9842139 955859216 1765117952 -0.2284045666 0.0380058102 -0.2475418001 499 19.9200000000 0.0102877431 0.0070783882 0.0121222660 0.0094265571 0.0680770000 9843393 955859216 1765122048 -0.2277819663 0.0375936814 -0.2498281449 500 19.9600000000 0.0105833597 0.0070853982 0.0121222660 0.0094174374 0.0805580000 9844647 955859216 1765122048 -0.2270356566 0.0378564149 -0.2522374392 501 20.0000000000 0.0096207950 0.0070904588 0.0121222660 0.0094299050 0.0719160000 9845901 955859216 1765105664 -0.2274728566 0.0368029699 -0.2543574572 502 20.0400000000 0.0095958719 0.0070954497 0.0121222660 0.0094475622 0.0881060000 9847155 955859216 1765105664 -0.2283605933 0.0360190421 -0.2571436763 503 20.0800000000 0.0102976821 0.0071018160 0.0121222660 0.0094401024 0.0694500000 9848409 955859216 1766723584 -0.2280879319 0.0364232883 -0.2601743340 504 20.1200000000 0.0105681643 0.0071086936 0.0121222660 0.0094313786 0.1011810000 9849663 955859216 1766383616 -0.2276532501 0.0367713980 -0.2625794113 505 20.1600000000 0.0109444521 0.0071162892 0.0121222660 0.0094230493 0.0714340000 9850917 955859216 1767747584 -0.2274071574 0.0375562981 -0.2653926313 506 20.2000000000 0.0110541526 0.0071240715 0.0121222660 0.0094147588 0.0688460000 9852171 955859216 1769517056 -0.2276063114 0.0384339355 -0.2678221166 507 20.2400000000 0.0103298798 0.0071303946 0.0121222660 0.0094096818 0.0868440000 9853425 955859216 1771294720 -0.2280793041 0.0380279608 -0.2701610327 508 20.2800000000 0.0104407100 0.0071369110 0.0121222660 0.0094032433 0.0925460000 9854679 955859216 1772945408 -0.2279215157 0.0378778130 -0.2729600370 509 20.3200000000 0.0102947680 0.0071431150 0.0121222660 0.0094001878 0.0824330000 9855933 955859216 1774739456 -0.2271093428 0.0375422128 -0.2750685811 510 20.3600000000 0.0106815193 0.0071500531 0.0121222660 0.0094028098 0.0716560000 9857187 955859216 1776373760 -0.2267119735 0.0381377637 -0.2774783373 511 20.4000000000 0.0107903248 0.0071571769 0.0121222660 0.0093959381 0.0873190000 9858441 955859216 1778024448 -0.2266453505 0.0385524780 -0.2801198065 512 20.4400000000 0.0108749447 0.0071644382 0.0121222660 0.0093876954 0.0883920000 9859695 955859216 1779802112 -0.2263847888 0.0390892960 -0.2829713821 513 20.4800000000 0.0112888198 0.0071724779 0.0121222660 0.0093803703 0.0717200000 9901909 955859216 1781452800 -0.2240306288 0.0401649550 -0.2860220671 514 20.5200000000 0.0107941162 0.0071795239 0.0121222660 0.0093748380 0.0696370000 9987131 955859216 1783230464 -0.2230727822 0.0405926146 -0.2889208496 515 20.5600000000 0.0105989249 0.0071861635 0.0121222660 0.0093683278 0.0688820000 9988385 955859216 1785008128 -0.2216850221 0.0402415507 -0.2916623652 516 20.6000000000 0.0106129097 0.0071928045 0.0121222660 0.0093650969 0.0684960000 9989639 955859216 1786785792 -0.2193740755 0.0397477783 -0.2943626642 517 20.6400000000 0.0108725382 0.0071999220 0.0121222660 0.0093578956 0.0828980000 9990893 955859216 1785831424 -0.2172641307 0.0398030989 -0.2968809903 518 20.6800000000 0.0110206958 0.0072072980 0.0121222660 0.0093527023 0.1107610000 9992147 955859216 1784799232 -0.2153987437 0.0404232182 -0.2994405031 519 20.7200000000 0.0110072065 0.0072146196 0.0121222660 0.0093480682 0.0707000000 9993401 955859216 1786167296 -0.2139760107 0.0410394333 -0.3020569384 520 20.7600000000 0.0105761290 0.0072210840 0.0121222660 0.0093431304 0.0681050000 9994655 955859216 1788055552 -0.2130863667 0.0411229245 -0.3043324053 521 20.8000000000 0.0110651087 0.0072284622 0.0121222660 0.0093351126 0.0821370000 9995909 955859216 1787179008 -0.2121696919 0.0417724214 -0.3066892028 522 20.8400000000 0.0115090255 0.0072366625 0.0121222660 0.0093271796 0.0708680000 9997163 955859216 1786040320 -0.2115759552 0.0433519222 -0.3091726601 523 20.8800000000 0.0111571159 0.0072441586 0.0121222660 0.0093187721 0.0690780000 9998417 955859216 1784807424 -0.2108805776 0.0442087129 -0.3113699257 524 20.9200000000 0.0110092638 0.0072513439 0.0121222660 0.0093112254 0.0824220000 9999671 955859216 1783771136 -0.2104916871 0.0443715639 -0.3137536645 525 20.9600000000 0.0111853182 0.0072588372 0.0121222660 0.0093053268 0.1130680000 10000925 955859216 1782902784 -0.2099734247 0.0444060341 -0.3161200881 526 21.0000000000 0.0114264134 0.0072667603 0.0121222660 0.0093010088 0.1140850000 10002179 955859216 1782013952 -0.2094717175 0.0447439030 -0.3183870316 527 21.0400000000 0.0115214875 0.0072748338 0.0121222660 0.0092960473 0.0856780000 10003433 955859216 1780350976 -0.2090024352 0.0448712111 -0.3203082085 528 21.0800000000 0.0118298857 0.0072834608 0.0121222660 0.0092972748 0.0715270000 10004687 955859216 1779707904 -0.2081374228 0.0448380299 -0.3222361505 529 21.1200000000 0.0116736302 0.0072917598 0.0121222660 0.0092962769 0.0874110000 10005941 955859216 1778839552 -0.2074215561 0.0440986417 -0.3240577877 530 21.1600000000 0.0117661320 0.0073002020 0.0121222660 0.0092974056 0.0693310000 10007195 955859216 1777803264 -0.2075065076 0.0438776724 -0.3258878887 531 21.2000000000 0.0119561963 0.0073089704 0.0121222660 0.0093038501 0.0694810000 10008449 955859216 1776934912 -0.2070023715 0.0439512432 -0.3277958035 532 21.2400000000 0.0117025860 0.0073172290 0.0121222660 0.0093145456 0.0707420000 10009703 955859216 1778294784 -0.2062495798 0.0428197421 -0.3293657005 533 21.2800000000 0.0118330428 0.0073257015 0.0121222660 0.0093226463 0.0827110000 10010957 955859216 1777516544 -0.2057468742 0.0423085727 -0.3309725821 534 21.3200000000 0.0116179297 0.0073337394 0.0121222660 0.0093168216 0.0897050000 10012211 955859216 1776898048 -0.2051763088 0.0416559801 -0.3323222399 535 21.3600000000 0.0115357311 0.0073415936 0.0121222660 0.0093140199 0.0665600000 10013465 955859216 1775116288 -0.2049595714 0.0407289453 -0.3336578310 536 21.4000000000 0.0119510060 0.0073501932 0.0121222660 0.0093125642 0.0686470000 10014719 955859216 1774247936 -0.2047165334 0.0404504910 -0.3353120089 537 21.4400000000 0.0116067035 0.0073581197 0.0121222660 0.0093110954 0.0615400000 10015973 955859216 1773379584 -0.2047806978 0.0398155674 -0.3364807367 538 21.4800000000 0.0120590348 0.0073668574 0.0121222660 0.0093215659 0.0766020000 10017227 955859216 1772490752 -0.2042864561 0.0392178483 -0.3377833962 539 21.5200000000 0.0119573260 0.0073753741 0.0121222660 0.0093385414 0.0674440000 10018481 955859216 1773850624 -0.2039557248 0.0382928997 -0.3390109837 540 21.5600000000 0.0120742908 0.0073840758 0.0121222660 0.0093462076 0.0693350000 10019735 955859216 1773379584 -0.2037509829 0.0378706902 -0.3402553499 541 21.6000000000 0.0120585002 0.0073927161 0.0121222660 0.0093505911 0.0616790000 10020989 955859216 1772490752 -0.2039664984 0.0375859290 -0.3415159583 542 21.6400000000 0.0117536634 0.0074007621 0.0121222660 0.0093513453 0.0766070000 10022243 955859216 1771601920 -0.2040188015 0.0365198031 -0.3426256776 543 21.6800000000 0.0116809411 0.0074086446 0.0121222660 0.0093540287 0.0874100000 10023497 955859216 1770713088 -0.2045756727 0.0356037281 -0.3437072039 544 21.7200000000 0.0115420166 0.0074162427 0.0121222660 0.0093510304 0.0861140000 10024751 955859216 1769934848 -0.2050603628 0.0346570499 -0.3448966146 545 21.7600000000 0.0114793191 0.0074236979 0.0121222660 0.0093462020 0.0863010000 10026005 955859216 1771294720 -0.2052877694 0.0333748423 -0.3458984792 546 21.8000000000 0.0116454009 0.0074314300 0.0121222660 0.0093521064 0.0923030000 10027259 955859216 1768296448 -0.2055939287 0.0322665609 -0.3468950689 547 21.8400000000 0.0118173389 0.0074394481 0.0121222660 0.0093756968 0.0859390000 10028513 955859216 1767411712 -0.2054491639 0.0306223035 -0.3479364812 548 21.8800000000 0.0117851999 0.0074473783 0.0121222660 0.0093894460 0.1060130000 10029767 955859216 1766522880 -0.2057471424 0.0295814965 -0.3490359485 549 21.9200000000 0.0115449950 0.0074548421 0.0121222660 0.0094005193 0.0859390000 10031021 955859216 1765634048 -0.2062414736 0.0263510477 -0.3499877155 550 21.9600000000 0.0117726400 0.0074626926 0.0121222660 0.0094091540 0.1102300000 10032275 955859216 1765113856 -0.2069101483 0.0252640918 -0.3510440588 551 22.0000000000 0.0120883128 0.0074710876 0.0121222660 0.0094062417 0.0891670000 10033529 955859216 1765122048 -0.2074646056 0.0251020677 -0.3521995544 552 22.0400000000 0.0117389932 0.0074788193 0.0121222660 0.0094034502 0.0851260000 10034783 955859216 1765122048 -0.2081074566 0.0245483518 -0.3530142903 553 22.0800000000 0.0116342502 0.0074863336 0.0121222660 0.0094037472 0.0877720000 10036037 955859216 1765122048 -0.2088768631 0.0226628706 -0.3538627923 554 22.1200000000 0.0119669633 0.0074944214 0.0121222660 0.0094114769 0.1096510000 10037291 955859216 1765122048 -0.2093415260 0.0220909510 -0.3547436893 555 22.1600000000 0.0123583283 0.0075031852 0.0123583283 0.0094142641 0.1050130000 10038545 955859216 1765122048 -0.2096507102 0.0229932014 -0.3558583558 556 22.2000000000 0.0121353520 0.0075115164 0.0123583283 0.0094080058 0.0905750000 10039799 955859216 1765122048 -0.2097814232 0.0229480136 -0.3567461669 557 22.2400000000 0.0114850057 0.0075186502 0.0123583283 0.0094009944 0.0890270000 10041053 955859216 1765122048 -0.2099146694 0.0220155027 -0.3573785424 558 22.2800000000 0.0115440246 0.0075258641 0.0123583283 0.0093995580 0.1046800000 10042307 955859216 1765122048 -0.2097056061 0.0215140767 -0.3580125868 559 22.3200000000 0.0116589796 0.0075332579 0.0123583283 0.0094027772 0.0919590000 10043561 955859216 1765122048 -0.2099179626 0.0210044626 -0.3588552177 560 22.3600000000 0.0117373774 0.0075407652 0.0123583283 0.0094003025 0.0895770000 10044815 955859216 1765122048 -0.2102354467 0.0210532919 -0.3596007824 561 22.4000000000 0.0116227651 0.0075480415 0.0123583283 0.0093981065 0.1071160000 10046069 955859216 1765122048 -0.2100381404 0.0205383468 -0.3603048623 562 22.4400000000 0.0115013076 0.0075550758 0.0123583283 0.0093950228 0.0884170000 10047323 955859216 1765122048 -0.2104717493 0.0200075489 -0.3609150350 563 22.4800000000 0.0115727130 0.0075622119 0.0123583283 0.0093923417 0.0900070000 10048577 955859216 1765072896 -0.2105367184 0.0194680002 -0.3615973592 564 22.5200000000 0.0115716644 0.0075693209 0.0123583283 0.0093926177 0.1090810000 10049831 955859216 1765122048 -0.2106287628 0.0193580743 -0.3621209562 565 22.5600000000 0.0115384609 0.0075763459 0.0123583283 0.0093954484 0.0873170000 10051085 955859216 1765138432 -0.2111368328 0.0185030680 -0.3627656400 566 22.6000000000 0.0115616871 0.0075833871 0.0123583283 0.0093951712 0.0889670000 10052339 955859216 1765138432 -0.2110447288 0.0182217155 -0.3632953465 567 22.6400000000 0.0116002662 0.0075904716 0.0123583283 0.0093936222 0.1289930000 10053593 955859216 1765138432 -0.2111420482 0.0177809708 -0.3640776575 568 22.6800000000 0.0115534617 0.0075974487 0.0123583283 0.0093931071 0.0874370000 10054847 955859216 1765138432 -0.2115304321 0.0171800572 -0.3644044697 569 22.7200000000 0.0119288452 0.0076050610 0.0123583283 0.0093989898 0.0880920000 10056101 955859216 1765138432 -0.2116814405 0.0164579265 -0.3650225103 570 22.7600000000 0.0119262356 0.0076126420 0.0123583283 0.0094019800 0.1286390000 10057355 955859216 1765122048 -0.2120116204 0.0160893742 -0.3655383587 571 22.8000000000 0.0121162878 0.0076205293 0.0123583283 0.0094070429 0.1303260000 10058609 955859216 1765122048 -0.2121152580 0.0148624238 -0.3662602603 572 22.8400000000 0.0122899432 0.0076286926 0.0123583283 0.0094172714 0.0875710000 10059863 955859216 1766469632 -0.2120886147 0.0149660753 -0.3669458926 573 22.8800000000 0.0121467290 0.0076365775 0.0123583283 0.0094170277 0.0880780000 10061117 955859216 1768501248 -0.2122186422 0.0146413594 -0.3676764071 574 22.9200000000 0.0119997337 0.0076441788 0.0123583283 0.0094192593 0.1251050000 10062371 955859216 1770278912 -0.2119134218 0.0139636528 -0.3686638772 575 22.9600000000 0.0118924882 0.0076515671 0.0123583283 0.0094241184 0.0890570000 10063625 955859216 1771929600 -0.2118257135 0.0134269428 -0.3694638908 576 23.0000000000 0.0119058089 0.0076589530 0.0123583283 0.0094317878 0.0892490000 10064879 955859216 1773707264 -0.2119561732 0.0125502655 -0.3704196215 577 23.0400000000 0.0117889270 0.0076661106 0.0123583283 0.0094398640 0.1287180000 10066133 955859216 1775484928 -0.2116450965 0.0116366828 -0.3712662756 578 23.0800000000 0.0116506061 0.0076730042 0.0123583283 0.0094489437 0.1482300000 10067387 955859216 1777135616 -0.2115471512 0.0107164308 -0.3720270991 579 23.1200000000 0.0114462860 0.0076795211 0.0123583283 0.0094554753 0.0894700000 10068641 955859216 1778786304 -0.2114878744 0.0100588622 -0.3728331029 580 23.1600000000 0.0112996008 0.0076857626 0.0123583283 0.0094624730 0.0900010000 10069895 955859216 1780563968 -0.2116007954 0.0095778154 -0.3735288680 581 23.2000000000 0.0109495446 0.0076913802 0.0123583283 0.0094661550 0.0876060000 10071149 955859216 1782214656 -0.2116788179 0.0090102646 -0.3739945889 582 23.2400000000 0.0108400527 0.0076967903 0.0123583283 0.0094681214 0.0888350000 10072403 955859216 1783865344 -0.2110614926 0.0086826198 -0.3745745718 583 23.2800000000 0.0112197343 0.0077028330 0.0123583283 0.0094745680 0.1303330000 10073657 955859216 1785643008 -0.2102629393 0.0083460817 -0.3752448261 584 23.3200000000 0.0108362501 0.0077081985 0.0123583283 0.0094761029 0.1071200000 10074911 955859216 1787293696 -0.2104814053 0.0074099777 -0.3756486773 585 23.3600000000 0.0109603135 0.0077137577 0.0123583283 0.0094866309 0.1219670000 10076165 955859216 1784786944 -0.2100240886 0.0067918221 -0.3759273291 586 23.4000000000 0.0113370456 0.0077199407 0.0123583283 0.0095021234 0.0943200000 10077419 955859216 1783660544 -0.2096337676 0.0065969382 -0.3763427436 587 23.4400000000 0.0111957956 0.0077258621 0.0123583283 0.0095072351 0.0896170000 10078673 955859216 1782775808 -0.2094531208 0.0062786019 -0.3766750991 588 23.4800000000 0.0111177182 0.0077316306 0.0123583283 0.0095131584 0.1076330000 10079927 955859216 1781628928 -0.2089441866 0.0057734135 -0.3766033053 589 23.5200000000 0.0111988541 0.0077375172 0.0123583283 0.0095201796 0.1105170000 10081181 955859216 1780584448 -0.2087471336 0.0055315723 -0.3768806458 590 23.5600000000 0.0111817084 0.0077433548 0.0123583283 0.0095248913 0.1057510000 10082435 955859216 1779580928 -0.2086325139 0.0052954047 -0.3771442175 591 23.6000000000 0.0108232498 0.0077485662 0.0123583283 0.0095250677 0.1293220000 10083689 955859216 1778565120 -0.2086997628 0.0042490261 -0.3770946264 592 23.6400000000 0.0110096764 0.0077540748 0.0123583283 0.0095355984 0.0777740000 10084943 955859216 1777549312 -0.2087107599 0.0034172430 -0.3773190677 593 23.6800000000 0.0110372258 0.0077596113 0.0123583283 0.0095407914 0.0791920000 10086197 955859216 1776533504 -0.2087227404 0.0030256861 -0.3774045706 594 23.7200000000 0.0109832585 0.0077650383 0.0123583283 0.0095395609 0.0880600000 10087451 955859216 1775517696 -0.2086415738 0.0027062967 -0.3777990937 595 23.7600000000 0.0109075587 0.0077703199 0.0123583283 0.0095410508 0.0886450000 10088705 955859216 1774649344 -0.2086281180 0.0019064352 -0.3778818548 596 23.8000000000 0.0110210320 0.0077757741 0.0123583283 0.0095452532 0.1153490000 10089959 955859216 1773613056 -0.2090874314 0.0013370509 -0.3779611290 597 23.8400000000 0.0110995881 0.0077813416 0.0123583283 0.0095449836 0.0990600000 10091213 955859216 1772597248 -0.2090468258 0.0010560339 -0.3778893054 598 23.8800000000 0.0110125476 0.0077867450 0.0123583283 0.0095422748 0.0907160000 10092467 955859216 1771741184 -0.2090920806 0.0006307286 -0.3779452741 599 23.9200000000 0.0106726317 0.0077915628 0.0123583283 0.0095367834 0.1125930000 10093721 955859216 1770692608 -0.2090245485 -0.0001810380 -0.3778206408 600 23.9600000000 0.0106306020 0.0077962945 0.0123583283 0.0095317142 0.0852990000 10094975 955859216 1769824256 -0.2088052779 -0.0010809490 -0.3778696954 601 24.0000000000 0.0108097997 0.0078013087 0.0123583283 0.0095286151 0.0856180000 10096229 955859216 1771184128 -0.2087730616 -0.0020363149 -0.3777561486 602 24.0400000000 0.0108516542 0.0078063757 0.0123583283 0.0095286986 0.0887770000 10097483 955859216 1770561536 -0.2085848004 -0.0031454847 -0.3776076436 603 24.0800000000 0.0110814190 0.0078118070 0.0123583283 0.0095362312 0.1054960000 10098737 955859216 1767378944 -0.2083655149 -0.0041381456 -0.3772827983 604 24.1200000000 0.0110964207 0.0078172451 0.0123583283 0.0095398221 0.1257780000 10099991 955859216 1766522880 -0.2081570178 -0.0046399729 -0.3769204617 605 24.1600000000 0.0112108802 0.0078228544 0.0123583283 0.0095373670 0.0778550000 10101245 955859216 1765486592 -0.2081916183 -0.0048251897 -0.3766996264 606 24.2000000000 0.0109992763 0.0078280960 0.0123583283 0.0095311805 0.0828220000 10102499 955859216 1765134336 -0.2079842389 -0.0051926295 -0.3766044974 607 24.2400000000 0.0110086156 0.0078333357 0.0123583283 0.0095245583 0.0862000000 10103753 955859216 1765122048 -0.2076173872 -0.0055853687 -0.3765152395 608 24.2800000000 0.0109662618 0.0078384886 0.0123583283 0.0095177146 0.0891110000 10105007 955859216 1765105664 -0.2071944475 -0.0059717456 -0.3764103353 609 24.3200000000 0.0107565736 0.0078432802 0.0123583283 0.0095110142 0.1084130000 10106261 955859216 1765138432 -0.2077876776 -0.0070090955 -0.3762999773 610 24.3600000000 0.0112584038 0.0078488787 0.0123583283 0.0095101346 0.0875210000 10107515 955859216 1765138432 -0.2074199766 -0.0076620700 -0.3763621747 611 24.4000000000 0.0112269744 0.0078544075 0.0123583283 0.0095049107 0.0887700000 10108769 955859216 1765138432 -0.2071153373 -0.0085856644 -0.3760864735 612 24.4400000000 0.0113808541 0.0078601697 0.0123583283 0.0095021089 0.1085120000 10110023 955859216 1765138432 -0.2069288343 -0.0089330189 -0.3763381243 613 24.4800000000 0.0116826706 0.0078664054 0.0123583283 0.0094969545 0.0884660000 10111277 955859216 1765138432 -0.2060303837 -0.0083184298 -0.3761653900 614 24.5200000000 0.0117545733 0.0078727379 0.0123583283 0.0094893732 0.0881220000 10112531 955859216 1765122048 -0.2056633085 -0.0084315808 -0.3758452237 615 24.5600000000 0.0118124234 0.0078791439 0.0123583283 0.0094822460 0.0880300000 10113785 955859216 1765122048 -0.2058322728 -0.0098126568 -0.3756200969 616 24.6000000000 0.0118212253 0.0078855434 0.0123583283 0.0094803648 0.0886990000 10115039 955859216 1765122048 -0.2059484571 -0.0114795733 -0.3757642806 617 24.6400000000 0.0118823247 0.0078920212 0.0123583283 0.0094821095 0.1120960000 10116293 955859216 1765076992 -0.2055904269 -0.0119550647 -0.3757692277 618 24.6800000000 0.0117391944 0.0078982464 0.0123583283 0.0094826476 0.0859820000 10117547 955859216 1765122048 -0.2051586062 -0.0125356205 -0.3760360479 619 24.7200000000 0.0119815823 0.0079048431 0.0123583283 0.0094952640 0.0876050000 10118801 955859216 1765122048 -0.2044218332 -0.0128138447 -0.3760369718 620 24.7600000000 0.0121100610 0.0079116257 0.0123583283 0.0095004483 0.1136000000 10120055 955859216 1765122048 -0.2040630877 -0.0122285765 -0.3767262995 621 24.8000000000 0.0118479747 0.0079179644 0.0123583283 0.0094936608 0.0804790000 10121309 955859216 1765122048 -0.2034091800 -0.0120437667 -0.3769928217 622 24.8400000000 0.0117790401 0.0079241719 0.0123583283 0.0094860549 0.1267990000 10122563 955859216 1765122048 -0.2022421807 -0.0125280097 -0.3769242764 623 24.8800000000 0.0118374461 0.0079304532 0.0123583283 0.0094786619 0.0867820000 10123817 955859216 1765122048 -0.2013420314 -0.0129711516 -0.3768023252 624 24.9200000000 0.0118998308 0.0079368144 0.0123583283 0.0094714915 0.0884610000 10125071 955859216 1765122048 -0.2006557286 -0.0137583269 -0.3769055605 625 24.9600000000 0.0118102515 0.0079430119 0.0123583283 0.0094659513 0.1289960000 10126325 955859216 1765122048 -0.1995348483 -0.0136335725 -0.3770675361 626 25.0000000000 0.0120345401 0.0079495479 0.0123583283 0.0094585746 0.1455840000 10127579 955859216 1765072896 -0.1981392950 -0.0134712625 -0.3767949939 627 25.0400000000 0.0120759690 0.0079561291 0.0123583283 0.0094511005 0.1302390000 10128833 955859216 1766469632 -0.1968685538 -0.0142429052 -0.3766306043 628 25.0800000000 0.0122626210 0.0079629866 0.0123583283 0.0094465938 0.1273410000 10130087 955859216 1768374272 -0.1954170763 -0.0141196642 -0.3766149879 629 25.1200000000 0.0124714905 0.0079701543 0.0124714905 0.0094401216 0.1296090000 10131341 955859216 1770024960 -0.1936452091 -0.0129146669 -0.3769360483 630 25.1600000000 0.0121910702 0.0079768542 0.0124714905 0.0094367514 0.0880020000 10132595 955859216 1771675648 -0.1925260872 -0.0128868194 -0.3767271638 631 25.2000000000 0.0120089417 0.0079832442 0.0124714905 0.0094304718 0.0882890000 10133849 955859216 1773453312 -0.1908411086 -0.0133804940 -0.3764947951 632 25.2400000000 0.0121571487 0.0079898485 0.0124714905 0.0094230346 0.1286250000 10135103 955859216 1775104000 -0.1891632676 -0.0135205183 -0.3763297200 633 25.2800000000 0.0124470899 0.0079968899 0.0124714905 0.0094156370 0.1309610000 10136357 955859216 1776881664 -0.1875250489 -0.0126954904 -0.3761798143 634 25.3200000000 0.0123120025 0.0080036961 0.0124714905 0.0094099864 0.0876010000 10137611 955859216 1778532352 -0.1856413633 -0.0127013614 -0.3756341934 635 25.3600000000 0.0122830095 0.0080104352 0.0124714905 0.0094047102 0.0880730000 10138865 955859216 1780183040 -0.1836022288 -0.0130283358 -0.3749178648 636 25.4000000000 0.0124854688 0.0080174714 0.0124854688 0.0093985071 0.1115590000 10140119 955859216 1781960704 -0.1816989332 -0.0130006066 -0.3748600185 637 25.4400000000 0.0124463392 0.0080244241 0.0124854688 0.0093927265 0.0869670000 10141373 955859216 1783611392 -0.1795220971 -0.0127805192 -0.3745545745 638 25.4800000000 0.0123180980 0.0080311540 0.0124854688 0.0093888264 0.0879080000 10142627 955859216 1785389056 -0.1777831763 -0.0136406226 -0.3739480674 639 25.5200000000 0.0124783097 0.0080381135 0.0124854688 0.0093815432 0.1281130000 10143881 955859216 1787039744 -0.1754979789 -0.0137779480 -0.3738726676 640 25.5600000000 0.0125532905 0.0080451685 0.0125532905 0.0093746049 0.1244470000 10145135 955859216 1784680448 -0.1731220633 -0.0135105941 -0.3733519018 641 25.6000000000 0.0125385104 0.0080521784 0.0125532905 0.0093678420 0.0915470000 10146389 955859216 1783644160 -0.1703825146 -0.0130743720 -0.3728536665 642 25.6400000000 0.0124837337 0.0080590811 0.0125532905 0.0093625363 0.0900860000 10147643 955859216 1782517760 -0.1682110727 -0.0134514738 -0.3725046813 643 25.6800000000 0.0126362136 0.0080661995 0.0126362136 0.0093552667 0.1092930000 10148897 955859216 1781506048 -0.1657147855 -0.0130175520 -0.3723995984 644 25.7200000000 0.0125513086 0.0080731640 0.0126362136 0.0093487696 0.0880840000 10150151 955859216 1780469760 -0.1632677913 -0.0131757148 -0.3717340529 645 25.7600000000 0.0125017092 0.0080800299 0.0126362136 0.0093416088 0.0877490000 10151405 955859216 1779601408 -0.1607244760 -0.0137912184 -0.3710954487 646 25.8000000000 0.0127127515 0.0080872013 0.0127127515 0.0093361831 0.1106490000 10152659 955859216 1778454528 -0.1582025290 -0.0135611966 -0.3706412017 647 25.8400000000 0.0127145182 0.0080943533 0.0127145182 0.0093289630 0.0883160000 10153913 955859216 1777422336 -0.1555455476 -0.0131275384 -0.3699244857 648 25.8800000000 0.0126055581 0.0081013150 0.0127145182 0.0093227119 0.0857060000 10155167 955859216 1776406528 -0.1533429921 -0.0135696242 -0.3690445423 649 25.9200000000 0.0126147429 0.0081082695 0.0127145182 0.0093155297 0.0885740000 10156421 955859216 1775390720 -0.1507629156 -0.0139878858 -0.3686200678 650 25.9600000000 0.0127276490 0.0081153762 0.0127276490 0.0093088593 0.1095760000 10157675 955859216 1774522368 -0.1481589079 -0.0136681879 -0.3680911064 651 26.0000000000 0.0127692753 0.0081225251 0.0127692753 0.0093017147 0.0881450000 10158929 955859216 1773613056 -0.1456496418 -0.0131717855 -0.3675496876 652 26.0400000000 0.0127058951 0.0081295548 0.0127692753 0.0092947496 0.0879210000 10160183 955859216 1772625920 -0.1432426721 -0.0129407682 -0.3675700128 653 26.0800000000 0.0126956636 0.0081365473 0.0127692753 0.0092877352 0.1107840000 10161437 955859216 1771589632 -0.1409924477 -0.0131351044 -0.3674112558 654 26.1200000000 0.0126204025 0.0081434033 0.0127692753 0.0092814218 0.0909140000 10162691 955859216 1770721280 -0.1358423084 -0.0124715287 -0.3666099608 655 26.1600000000 0.0126020750 0.0081502105 0.0127692753 0.0092744914 0.0833020000 10163945 955859216 1769684992 -0.1333014220 -0.0129494760 -0.3655665219 656 26.2000000000 0.0127425566 0.0081572110 0.0127692753 0.0092677472 0.0879570000 10165199 955859216 1768816640 -0.1304424554 -0.0126779871 -0.3646480441 657 26.2400000000 0.0127399201 0.0081641862 0.0127692753 0.0092607272 0.1094820000 10166453 955859216 1767927808 -0.1277462393 -0.0127497306 -0.3635548949 658 26.2800000000 0.0127833234 0.0081712062 0.0127833234 0.0092537926 0.0879020000 10167707 955859216 1767038976 -0.1250941604 -0.0129567040 -0.3627545834 659 26.3200000000 0.0129577806 0.0081784695 0.0129577806 0.0092476673 0.0868980000 10168961 955859216 1766002688 -0.1224664524 -0.0126647325 -0.3624799848 660 26.3600000000 0.0128060486 0.0081854810 0.0129577806 0.0092406501 0.0887180000 10170215 955859216 1765134336 -0.1199392453 -0.0129458187 -0.3617771268 661 26.4000000000 0.0127913719 0.0081924491 0.0129577806 0.0092341494 0.1075670000 10171469 955859216 1765081088 -0.1171048656 -0.0132640479 -0.3607090414 662 26.4400000000 0.0128696701 0.0081995144 0.0129577806 0.0092286000 0.1104830000 10172723 955859216 1765113856 -0.1143494248 -0.0131748961 -0.3599871993 663 26.4800000000 0.0127068199 0.0082063127 0.0129577806 0.0092216408 0.1037260000 10173977 955859216 1765130240 -0.1118520275 -0.0135717466 -0.3594373167 664 26.5200000000 0.0125892544 0.0082129135 0.0129577806 0.0092150573 0.1448330000 10175231 955859216 1765130240 -0.1095105782 -0.0145964902 -0.3587493300 665 26.5600000000 0.0125654098 0.0082194587 0.0129577806 0.0092104138 0.1303430000 10176485 955859216 1765126144 -0.1073376983 -0.0161662754 -0.3584137261 666 26.6000000000 0.0127089955 0.0082261997 0.0129577806 0.0092103652 0.1293020000 10177739 955859216 1765130240 -0.1048177332 -0.0169375073 -0.3580216467 667 26.6400000000 0.0127301309 0.0082329522 0.0129577806 0.0092087883 0.1063240000 10178993 955859216 1765130240 -0.1023877785 -0.0176359583 -0.3577836752 668 26.6800000000 0.0126840221 0.0082396155 0.0129577806 0.0092048286 0.1332090000 10180247 955859216 1765130240 -0.0999885425 -0.0182302408 -0.3573677838 669 26.7200000000 0.0125996750 0.0082461328 0.0129577806 0.0092000292 0.1436250000 10181501 955859216 1766477824 -0.0977023095 -0.0192254428 -0.3573148549 670 26.7600000000 0.0126497699 0.0082527054 0.0129577806 0.0091995562 0.0901180000 10182755 955859216 1768509440 -0.0953578949 -0.0196839143 -0.3575354517 671 26.8000000000 0.0127064539 0.0082593428 0.0129577806 0.0091962209 0.0881230000 10184009 955859216 1770160128 -0.0928190202 -0.0194652081 -0.3580037057 672 26.8400000000 0.0125652691 0.0082657505 0.0129577806 0.0091897352 0.1107530000 10185263 955859216 1771937792 -0.0905395374 -0.0206149779 -0.3581857681 673 26.8800000000 0.0126523413 0.0082722684 0.0129577806 0.0091917648 0.1047710000 10186517 955859216 1773588480 -0.0880578309 -0.0215152875 -0.3584129810 674 26.9200000000 0.0128808115 0.0082791060 0.0129577806 0.0091989236 0.0895580000 10187771 955859216 1775239168 -0.0853139386 -0.0210760608 -0.3587471843 675 26.9600000000 0.0128365876 0.0082858579 0.0129577806 0.0091945268 0.0888130000 10189025 955859216 1777016832 -0.0826888680 -0.0209991802 -0.3596036434 676 27.0000000000 0.0126593765 0.0082923276 0.0129577806 0.0091883218 0.1285600000 10190279 955859216 1778667520 -0.0802490488 -0.0221460685 -0.3597973883 677 27.0400000000 0.0127503704 0.0082989126 0.0129577806 0.0091851131 0.1311910000 10191533 955859216 1780445184 -0.0775326192 -0.0223132819 -0.3608417809 678 27.0800000000 0.0127372630 0.0083054588 0.0129577806 0.0091805572 0.0876480000 10192787 955859216 1782095872 -0.0748603567 -0.0226165745 -0.3615102470 679 27.1200000000 0.0127610080 0.0083120207 0.0129577806 0.0091776112 0.0881120000 10194041 955859216 1783873536 -0.0723952949 -0.0230811946 -0.3623765409 680 27.1600000000 0.0128847146 0.0083187453 0.0129577806 0.0091762536 0.1112020000 10195295 955859216 1785524224 -0.0695945919 -0.0228310805 -0.3636237383 681 27.2000000000 0.0128362384 0.0083253789 0.0129577806 0.0091699355 0.1056080000 10196549 955859216 1787174912 -0.0669097304 -0.0228654705 -0.3646788001 682 27.2400000000 0.0128294080 0.0083319830 0.0129577806 0.0091638208 0.1195060000 10197803 955859216 1784668160 -0.0642758980 -0.0231332667 -0.3660814464 683 27.2800000000 0.0128459726 0.0083385921 0.0129577806 0.0091587432 0.0977120000 10199057 955859216 1783652352 -0.0614779480 -0.0231979340 -0.3674412370 684 27.3200000000 0.0128206406 0.0083451448 0.0129577806 0.0091521972 0.0882990000 10200311 955859216 1782636544 -0.0587216355 -0.0233341642 -0.3692117333 685 27.3600000000 0.0125834150 0.0083513321 0.0129577806 0.0091455598 0.0882920000 10201565 955859216 1781620736 -0.0561932623 -0.0249693450 -0.3705573678 686 27.4000000000 0.0126373693 0.0083575799 0.0129577806 0.0091447577 0.1122590000 10202819 955859216 1780576256 -0.0536117256 -0.0259410441 -0.3723560572 687 27.4400000000 0.0126988031 0.0083638990 0.0129577806 0.0091467173 0.0855450000 10204073 955859216 1779589120 -0.0506671593 -0.0259448178 -0.3744727671 688 27.4800000000 0.0126970578 0.0083701972 0.0129577806 0.0091474320 0.0880170000 10205327 955859216 1778573312 -0.0476537496 -0.0260085575 -0.3765476644 689 27.5200000000 0.0126400348 0.0083763944 0.0129577806 0.0091482566 0.1064050000 10206581 955859216 1777557504 -0.0448936857 -0.0263239909 -0.3786561191 690 27.5600000000 0.0121668968 0.0083818879 0.0129577806 0.0091543719 0.1302640000 10207835 955859216 1776541696 -0.0418222956 -0.0249269903 -0.3816229701 691 27.6000000000 0.0124657759 0.0083877980 0.0129577806 0.0091477953 0.1024880000 10209089 955859216 1775673344 -0.0383879691 -0.0243894923 -0.3834739029 692 27.6400000000 0.0123322625 0.0083934981 0.0129577806 0.0091446001 0.1324870000 10210343 955859216 1774637056 -0.0352818333 -0.0241240133 -0.3858269751 693 27.6800000000 0.0122938519 0.0083991263 0.0129577806 0.0091409217 0.0874330000 10211597 955859216 1773768704 -0.0323680528 -0.0248606186 -0.3878656030 694 27.7200000000 0.0123148067 0.0084047685 0.0129577806 0.0091343248 0.0877860000 10212851 955859216 1772732416 -0.0293909572 -0.0252031144 -0.3901626170 695 27.7600000000 0.0122833177 0.0084103491 0.0129577806 0.0091279786 0.0893590000 10214105 955859216 1771810816 -0.0263982210 -0.0256912634 -0.3920822442 696 27.8000000000 0.0122688515 0.0084158930 0.0129577806 0.0091235014 0.0894290000 10215359 955859216 1770827776 -0.0235344060 -0.0260639526 -0.3937029243 697 27.8400000000 0.0119346622 0.0084209414 0.0129577806 0.0091217765 0.1262920000 10216613 955859216 1769959424 -0.0180347804 -0.0247118846 -0.3992207944 698 27.8800000000 0.0121616973 0.0084263007 0.0129577806 0.0091153194 0.1288720000 10217867 955859216 1771319296 -0.0154190026 -0.0261366852 -0.4004094005 699 27.9200000000 0.0118617490 0.0084312155 0.0129577806 0.0091349799 0.1054600000 10219121 955859216 1773350912 -0.0110381227 -0.0259969644 -0.4050159156 700 27.9600000000 0.0121379197 0.0084365107 0.0129577806 0.0091292161 0.0900240000 10220375 955859216 1774985216 -0.0087024048 -0.0270401165 -0.4063675404 701 28.0000000000 0.0121632870 0.0084418271 0.0129577806 0.0091259173 0.1114130000 10221629 955859216 1776635904 -0.0065318439 -0.0280917753 -0.4076113403 702 28.0400000000 0.0122315260 0.0084472256 0.0129577806 0.0091309869 0.1060860000 10222883 955859216 1778413568 -0.0045099501 -0.0290856268 -0.4089662433 703 28.0800000000 0.0124323433 0.0084528943 0.0129577806 0.0091492949 0.1296290000 10224137 955859216 1780064256 -0.0023475322 -0.0291067418 -0.4109263420 704 28.1200000000 0.0124411983 0.0084585595 0.0129577806 0.0091558089 0.1296090000 10225391 955859216 1781841920 -0.0000370244 -0.0290566050 -0.4126334488 705 28.1600000000 0.0123131378 0.0084640270 0.0129577806 0.0091561162 0.1292660000 10226645 955859216 1783492608 0.0018784482 -0.0297789946 -0.4140354693 706 28.2000000000 0.0123795280 0.0084695730 0.0129577806 0.0091620864 0.0838020000 10227899 955859216 1785143296 0.0039628022 -0.0302951187 -0.4154665768 707 28.2400000000 0.0124893188 0.0084752586 0.0129577806 0.0091668118 0.0873780000 10229153 955859216 1786920960 0.0063813394 -0.0296471119 -0.4170258343 708 28.2800000000 0.0123611335 0.0084807472 0.0129577806 0.0091605211 0.1275010000 10230407 955859216 1785692160 0.0088935727 -0.0292601399 -0.4185931385 709 28.3200000000 0.0121636549 0.0084859417 0.0129577806 0.0091541256 0.0872090000 10231661 955859216 1787064320 0.0110449446 -0.0300382301 -0.4194803536 710 28.3600000000 0.0123365717 0.0084913651 0.0129577806 0.0091517821 0.0869150000 10232915 955859216 1786437632 0.0133478483 -0.0306706242 -0.4203858674 711 28.4000000000 0.0125277210 0.0084970421 0.0129577806 0.0091495965 0.1012850000 10234169 955859216 1784016896 0.0159084592 -0.0302975290 -0.4216735959 712 28.4400000000 0.0123168100 0.0085024070 0.0129577806 0.0091431666 0.0938390000 10235423 955859216 1783037952 0.0181922689 -0.0308730043 -0.4222961366 713 28.4800000000 0.0122726876 0.0085076949 0.0129577806 0.0091377923 0.0889480000 10236677 955859216 1781993472 0.0204597153 -0.0316392668 -0.4227900207 714 28.5200000000 0.0124918725 0.0085132750 0.0129577806 0.0091359256 0.1119470000 10237931 955859216 1780977664 0.0230572820 -0.0314729363 -0.4236172736 715 28.5600000000 0.0126146842 0.0085190112 0.0129577806 0.0091304619 0.0850390000 10239185 955859216 1779961856 0.0259614885 -0.0306375548 -0.4244152904 716 28.6000000000 0.0125292223 0.0085246120 0.0129577806 0.0091253839 0.0880950000 10240439 955859216 1778946048 0.0287551954 -0.0300792325 -0.4248379469 717 28.6400000000 0.0123954080 0.0085300106 0.0129577806 0.0091219685 0.1226490000 10241693 955859216 1777930240 0.0314987786 -0.0301805139 -0.4251754582 718 28.6800000000 0.0124602569 0.0085354845 0.0129577806 0.0091159494 0.0915390000 10242947 955859216 1776914432 0.0341847353 -0.0303881820 -0.4252432883 719 28.7200000000 0.0124967378 0.0085409939 0.0129577806 0.0091096140 0.0895080000 10244201 955859216 1775898624 0.0370105170 -0.0307754278 -0.4249958098 720 28.7600000000 0.0126427012 0.0085466907 0.0129577806 0.0091061018 0.1099350000 10245455 955859216 1775030272 0.0400860794 -0.0311921537 -0.4245534241 721 28.8000000000 0.0116427913 0.0085509849 0.0129577806 0.0091095968 0.1198870000 10246709 955859216 1774014464 0.0438200310 -0.0285547897 -0.4240265489 722 28.8400000000 0.0125304237 0.0085564966 0.0129577806 0.0091034139 0.1463660000 10247963 955859216 1773125632 0.0469744764 -0.0293996166 -0.4238982201 723 28.8800000000 0.0127189737 0.0085622538 0.0129577806 0.0090973991 0.0886730000 10249217 955859216 1772834816 0.0502615385 -0.0294393133 -0.4233888686 724 28.9200000000 0.0127203129 0.0085679970 0.0129577806 0.0090911971 0.0867470000 10250471 955859216 1771945984 0.0536376536 -0.0292306710 -0.4226049185 725 28.9600000000 0.0127329351 0.0085737417 0.0129577806 0.0090850312 0.1263580000 10251725 955859216 1770217472 0.0572149754 -0.0292016901 -0.4216506183 726 29.0000000000 0.0127086798 0.0085794372 0.0129577806 0.0090800828 0.1469100000 10252979 955859216 1769185280 0.0605382808 -0.0292641129 -0.4207613468 727 29.0400000000 0.0116985673 0.0085837277 0.0129577806 0.0090825260 0.1310490000 10254233 955859216 1768300544 0.0649823174 -0.0268692318 -0.4190790355 728 29.0800000000 0.0126490425 0.0085893119 0.0129577806 0.0090766597 0.1055270000 10255487 955859216 1769644032 0.0683644190 -0.0274314582 -0.4185632467 729 29.1200000000 0.0127339540 0.0085949973 0.0129577806 0.0090704399 0.1306950000 10256741 955859216 1771548672 0.0716407299 -0.0280849319 -0.4174678326 730 29.1600000000 0.0117273638 0.0085992882 0.0129577806 0.0090756906 0.1054270000 10257995 955859216 1773199360 0.0756084919 -0.0267805066 -0.4155617356 731 29.2000000000 0.0117193768 0.0086035564 0.0129577806 0.0090802211 0.0909000000 10259249 955859216 1774977024 0.0795382559 -0.0261760596 -0.4140733778 732 29.2400000000 0.0127854832 0.0086092694 0.0129577806 0.0090771867 0.1074800000 10260503 955859216 1776627712 0.0824282616 -0.0273836255 -0.4135348797 733 29.2800000000 0.0117671322 0.0086135776 0.0129577806 0.0090757582 0.1301530000 10261757 955859216 1778278400 0.0864485651 -0.0255546439 -0.4121353626 734 29.3200000000 0.0117354775 0.0086178308 0.0129577806 0.0090710370 0.0885150000 10263011 955859216 1780056064 0.0899904072 -0.0252438765 -0.4109464586 735 29.3600000000 0.0125075690 0.0086231230 0.0129577806 0.0090649687 0.0877490000 10264265 955859216 1781706752 0.0925764963 -0.0264752861 -0.4104286134 736 29.4000000000 0.0126878303 0.0086286457 0.0129577806 0.0090588624 0.1295860000 10265519 955859216 1783357440 0.0954043716 -0.0270602945 -0.4094049037 737 29.4400000000 0.0128869098 0.0086344235 0.0129577806 0.0090543941 0.0886180000 10266773 955859216 1785135104 0.0982428417 -0.0273424070 -0.4084683061 738 29.4800000000 0.0118322130 0.0086387566 0.0129577806 0.0090513321 0.0888520000 10268027 955859216 1786785792 0.1019488126 -0.0254757367 -0.4068496823 739 29.5200000000 0.0124664139 0.0086439361 0.0129577806 0.0090452792 0.0872960000 10269281 955859216 1785683968 0.1041234583 -0.0269582197 -0.4061073065 740 29.5600000000 0.0127252331 0.0086494514 0.0129577806 0.0090425564 0.1047430000 10270535 955859216 1784164352 0.1064739376 -0.0281390604 -0.4049704075 741 29.6000000000 0.0130368173 0.0086553722 0.0130368173 0.0090495866 0.1100760000 10271789 955859216 1785786368 0.1087273583 -0.0287100151 -0.4039648473 742 29.6400000000 0.0131971277 0.0086614932 0.0131971277 0.0090519265 0.1081430000 10273043 955859216 1787420672 0.1113454327 -0.0285906270 -0.4031290412 743 29.6800000000 0.0131335827 0.0086675122 0.0131971277 0.0090490414 0.1118400000 10274297 955859216 1784803328 0.1137897074 -0.0283427853 -0.4022349417 744 29.7200000000 0.0129973907 0.0086733319 0.0131971277 0.0090441164 0.0864800000 10275551 955859216 1783660544 0.1161033809 -0.0283453166 -0.4012772441 745 29.7600000000 0.0131875258 0.0086793912 0.0131971277 0.0090402154 0.0852440000 10276805 955859216 1782628352 0.1186015010 -0.0278314240 -0.4004522860 746 29.8000000000 0.0129462751 0.0086851109 0.0131971277 0.0090362211 0.0888890000 10278059 955859216 1781633024 0.1210519373 -0.0268505793 -0.3997590840 747 29.8400000000 0.0125174560 0.0086902412 0.0131971277 0.0090360589 0.1141380000 10279313 955859216 1780744192 0.1229026988 -0.0272126961 -0.3986837864 748 29.8800000000 0.0132319033 0.0086963129 0.0132319033 0.0090434911 0.0834890000 10280567 955859216 1779597312 0.1257835180 -0.0280106291 -0.3978312016 749 29.9200000000 0.0131536396 0.0087022640 0.0132319033 0.0090375900 0.0872200000 10281821 955859216 1778565120 0.1283341199 -0.0274608862 -0.3967442811 750 29.9600000000 0.0130043682 0.0087080001 0.0132319033 0.0090320125 0.1072710000 10283075 955859216 1777549312 0.1303748190 -0.0272047222 -0.3958049119 751 30.0000000000 0.0131281186 0.0087138858 0.0132319033 0.0090260452 0.0858420000 10284329 955859216 1776680960 0.1324224174 -0.0267864168 -0.3951960206 752 30.0400000000 0.0130326236 0.0087196288 0.0132319033 0.0090224508 0.0879870000 10285583 955859216 1775644672 0.1343768239 -0.0261291508 -0.3947645128 753 30.0800000000 0.0128407720 0.0087251017 0.0132319033 0.0090193739 0.1093890000 10286837 955859216 1774776320 0.1359871775 -0.0262338500 -0.3943498135 754 30.1200000000 0.0130774342 0.0087308741 0.0132319033 0.0090134157 0.0877320000 10288091 955859216 1773740032 0.1378046274 -0.0262832865 -0.3940796852 755 30.1600000000 0.0130058741 0.0087365363 0.0132319033 0.0090080770 0.0875880000 10289345 955859216 1772818432 0.1394255310 -0.0262039490 -0.3937442005 756 30.2000000000 0.0129016768 0.0087420458 0.0132319033 0.0090021902 0.1209220000 10290599 955859216 1771835392 0.1408119649 -0.0269511584 -0.3931477964 757 30.2400000000 0.0131552266 0.0087478756 0.0132319033 0.0090024685 0.0932210000 10291853 955859216 1770967040 0.1423307061 -0.0281014964 -0.3925683498 758 30.2800000000 0.0136582851 0.0087543537 0.0136582851 0.0090191541 0.0897960000 10293107 955859216 1769930752 0.1440631449 -0.0286190026 -0.3924714923 759 30.3200000000 0.0123853581 0.0087591376 0.0136582851 0.0090367350 0.0886390000 10294361 955859216 1769062400 0.1467295885 -0.0262880735 -0.3921014965 760 30.3600000000 0.0132301981 0.0087650206 0.0136582851 0.0090387897 0.0886590000 10295615 955859216 1768026112 0.1484078169 -0.0278636273 -0.3917047977 761 30.4000000000 0.0136034796 0.0087713786 0.0136582851 0.0090469997 0.1123530000 10296869 955859216 1767157760 0.1504035145 -0.0287234709 -0.3914438486 762 30.4400000000 0.0139551237 0.0087781814 0.0139551237 0.0090620460 0.0868030000 10298123 955859216 1766268928 0.1525049508 -0.0290816538 -0.3910022080 763 30.4800000000 0.0125489281 0.0087831235 0.0139551237 0.0090775781 0.1030710000 10299377 955859216 1765380096 0.1555469781 -0.0266987160 -0.3906908333 764 30.5200000000 0.0134555968 0.0087892393 0.0139551237 0.0090833214 0.0888850000 10300631 955859216 1765117952 0.1574673951 -0.0284085907 -0.3905031383 765 30.5600000000 0.0139749553 0.0087960180 0.0139749553 0.0090993238 0.1092310000 10301885 955859216 1765105664 0.1595252305 -0.0292695090 -0.3903188109 766 30.6000000000 0.0126766134 0.0088010840 0.0139749553 0.0091199128 0.1068640000 10303139 955859216 1765105664 0.1625876576 -0.0266010575 -0.3901872337 767 30.6400000000 0.0135938274 0.0088073327 0.0139749553 0.0091186571 0.0858430000 10304393 955859216 1765105664 0.1648400426 -0.0275492501 -0.3903236091 768 30.6800000000 0.0137492698 0.0088137675 0.0139749553 0.0091164694 0.0897460000 10305647 955859216 1765138432 0.1671050638 -0.0280473065 -0.3901556730 769 30.7200000000 0.0141311698 0.0088206822 0.0141311698 0.0091176967 0.1268880000 10306901 955859216 1765122048 0.1694725901 -0.0280575324 -0.3903239965 770 30.7600000000 0.0141049847 0.0088275449 0.0141311698 0.0091137636 0.0894120000 10308155 955859216 1765122048 0.1717869639 -0.0274598729 -0.3905667961 771 30.8000000000 0.0136793321 0.0088338378 0.0141311698 0.0091081541 0.0768140000 10309409 955859216 1765122048 0.1739705503 -0.0275306720 -0.3905510008 772 30.8400000000 0.0140491659 0.0088405934 0.0141311698 0.0091107738 0.0806760000 10310663 955859216 1765122048 0.1759772897 -0.0281307846 -0.3905704021 773 30.8800000000 0.0143182892 0.0088476797 0.0143182892 0.0091102199 0.0875770000 10311917 955859216 1765122048 0.1784787029 -0.0279231220 -0.3905849457 774 30.9200000000 0.0141720781 0.0088545588 0.0143182892 0.0091048118 0.1074970000 10313171 955859216 1765105664 0.1806415617 -0.0276255477 -0.3906267285 775 30.9600000000 0.0142638488 0.0088615385 0.0143182892 0.0090990719 0.1271860000 10314425 955859216 1765138432 0.1825479567 -0.0273503922 -0.3908140063 776 31.0000000000 0.0140435370 0.0088682163 0.0143182892 0.0090960657 0.1280720000 10315679 955859216 1765122048 0.1844450831 -0.0268894508 -0.3909362555 777 31.0400000000 0.0139781935 0.0088747929 0.0143182892 0.0090919826 0.0886800000 10316933 955859216 1765122048 0.1860444844 -0.0269040707 -0.3910123110 778 31.0800000000 0.0143689252 0.0088818547 0.0143689252 0.0090868259 0.0879930000 10318187 955859216 1765122048 0.1877299696 -0.0263349060 -0.3916022182 779 31.1200000000 0.0140610915 0.0088885033 0.0143689252 0.0090969869 0.1271990000 10319441 955859216 1765122048 0.1892061979 -0.0250004362 -0.3922240734 780 31.1600000000 0.0135714328 0.0088945071 0.0143689252 0.0091297984 0.0886930000 10320695 955859216 1766486016 0.1904725134 -0.0239213947 -0.3924683630 781 31.2000000000 0.0134685449 0.0089003637 0.0143689252 0.0091644832 0.0885180000 10321949 955859216 1768501248 0.1917087436 -0.0235415194 -0.3926724195 782 31.2400000000 0.0135224452 0.0089062743 0.0143689252 0.0091970729 0.0879060000 10323203 955859216 1770278912 0.1928368658 -0.0232466254 -0.3928133249 783 31.2800000000 0.0133921299 0.0089120034 0.0143689252 0.0092276737 0.0887490000 10324457 955859216 1771929600 0.1935562938 -0.0231145509 -0.3931423128 784 31.3200000000 0.0133744013 0.0089176952 0.0143689252 0.0092433128 0.0877940000 10325711 955859216 1773580288 0.1941495389 -0.0233779605 -0.3933339715 785 31.3600000000 0.0135779791 0.0089236319 0.0143689252 0.0092417445 0.0889920000 10326965 955859216 1775357952 0.1947867572 -0.0239818804 -0.3934245408 786 31.4000000000 0.0139503591 0.0089300272 0.0143689252 0.0092362027 0.1277870000 10328219 955859216 1777008640 0.1956981421 -0.0238033142 -0.3938117027 787 31.4400000000 0.0138081955 0.0089362256 0.0143689252 0.0092363689 0.1286900000 10329473 955859216 1778659328 0.1966085285 -0.0229313243 -0.3940733671 788 31.4800000000 0.0136270532 0.0089421784 0.0143689252 0.0092390258 0.1283800000 10330727 955859216 1780436992 0.1972932667 -0.0222253762 -0.3943211734 789 31.5200000000 0.0136414915 0.0089481345 0.0143689252 0.0092432317 0.1299480000 10331981 955859216 1782087680 0.1981850415 -0.0212219413 -0.3946985602 790 31.5600000000 0.0132640125 0.0089535976 0.0143689252 0.0092719615 0.0887290000 10333235 955859216 1783738368 0.1989246756 -0.0198792983 -0.3949120343 791 31.6000000000 0.0130062122 0.0089587210 0.0143689252 0.0093060495 0.0879190000 10334489 955859216 1785516032 0.1997326314 -0.0192872696 -0.3950657845 792 31.6400000000 0.0131376199 0.0089639974 0.0143689252 0.0093182345 0.1291480000 10335743 955859216 1787166720 0.2007324845 -0.0190084763 -0.3949666917 793 31.6800000000 0.0132747917 0.0089694335 0.0143689252 0.0093284621 0.1236930000 10336997 955859216 1784786944 0.2018042505 -0.0183262229 -0.3948217332 794 31.7200000000 0.0132386070 0.0089748103 0.0143689252 0.0093505112 0.0941680000 10338251 955859216 1783660544 0.2028734833 -0.0172090866 -0.3946973085 795 31.7600000000 0.0130827269 0.0089799775 0.0143689252 0.0093793289 0.0828760000 10339505 955859216 1782628352 0.2035659254 -0.0164160021 -0.3943634927 796 31.8000000000 0.0130669503 0.0089851118 0.0143689252 0.0094128030 0.0876690000 10340759 955859216 1781612544 0.2042895555 -0.0155066103 -0.3941073716 797 31.8400000000 0.0129192648 0.0089900480 0.0143689252 0.0094929168 0.1099940000 10342013 955859216 1780744192 0.2052389383 -0.0142767662 -0.3936936557 798 31.8800000000 0.0128895808 0.0089949347 0.0143689252 0.0095942031 0.0859570000 10343267 955859216 1779707904 0.2057262510 -0.0137792137 -0.3933615386 799 31.9200000000 0.0129525326 0.0089998879 0.0143689252 0.0096496946 0.0902880000 10344521 955859216 1778692096 0.2061357647 -0.0136815654 -0.3930949569 800 31.9600000000 0.0130784865 0.0090049861 0.0143689252 0.0096697819 0.1088390000 10345775 955859216 1777549312 0.2067982107 -0.0136106797 -0.3927736282 801 32.0000000000 0.0131737441 0.0090101906 0.0143689252 0.0096730891 0.0868910000 10347029 955859216 1776680960 0.2076228708 -0.0134890918 -0.3921660781 802 32.0400000000 0.0132370805 0.0090154610 0.0143689252 0.0096756561 0.0853570000 10348283 955859216 1775644672 0.2086209953 -0.0132678719 -0.3915470541 803 32.0800000000 0.0133905271 0.0090209094 0.0143689252 0.0096742602 0.0882400000 10349537 955859216 1774628864 0.2096469998 -0.0129967388 -0.3909446597 804 32.1199999990 0.0134543916 0.0090264237 0.0143689252 0.0096733467 0.1099970000 10350791 955859216 1773760512 0.2104876786 -0.0127949482 -0.3901257813 805 32.1600000000 0.0135050248 0.0090319872 0.0143689252 0.0096743245 0.0887570000 10352045 955859216 1772724224 0.2112538666 -0.0125681097 -0.3895188570 806 32.2000000000 0.0135295093 0.0090375672 0.0143689252 0.0096736120 0.0854840000 10353299 955859216 1771855872 0.2119954377 -0.0126101719 -0.3887362778 807 32.2400000000 0.0136203244 0.0090432460 0.0143689252 0.0096686881 0.0886820000 10354553 955859216 1770819584 0.2128074765 -0.0126330964 -0.3881411552 808 32.2800000000 0.0136678638 0.0090489695 0.0143689252 0.0096635432 0.1080280000 10355807 955859216 1769951232 0.2134719938 -0.0124590993 -0.3874518871 809 32.3200000000 0.0136392452 0.0090546435 0.0143689252 0.0096596949 0.1081960000 10357061 955859216 1768902656 0.2142072022 -0.0122900838 -0.3867980838 810 32.3600000000 0.0136696538 0.0090603411 0.0143689252 0.0096563155 0.1073780000 10358315 955859216 1768046592 0.2149526179 -0.0124154510 -0.3858318925 811 32.4000000000 0.0137675507 0.0090661453 0.0143689252 0.0096506501 0.1249570000 10359569 955859216 1767157760 0.2158260494 -0.0126157403 -0.3848895133 812 32.4399999990 0.0139331296 0.0090721391 0.0143689252 0.0096449318 0.0998710000 10360823 955859216 1766268928 0.2168124765 -0.0129114324 -0.3837536573 813 32.4800000000 0.0140142543 0.0090782179 0.0143689252 0.0096397620 0.0763410000 10362077 955859216 1765380096 0.2178464830 -0.0128908511 -0.3828452528 814 32.5200000000 0.0140538653 0.0090843305 0.0143689252 0.0096368357 0.0888890000 10363331 955859216 1765117952 0.2186487764 -0.0131297223 -0.3817383349 815 32.5600000000 0.0141619854 0.0090905608 0.0143689252 0.0096386300 0.0863290000 10364585 955859216 1765117952 0.2195037454 -0.0133621935 -0.3806030154 816 32.6000000000 0.0142288329 0.0090968577 0.0143689252 0.0096412490 0.0870050000 10365839 955859216 1765117952 0.2203864604 -0.0132236723 -0.3796634674 817 32.6400000000 0.0142031880 0.0091031078 0.0143689252 0.0096434805 0.0890980000 10367093 955859216 1765122048 0.2211508006 -0.0132770278 -0.3785425425 818 32.6800000000 0.0141510414 0.0091092789 0.0143689252 0.0096470782 0.1103020000 10368347 955859216 1765072896 0.2217948139 -0.0132054174 -0.3775271475 819 32.7200000000 0.0139983650 0.0091152484 0.0143689252 0.0096490072 0.0866990000 10369601 955859216 1765105664 0.2223731130 -0.0130589278 -0.3763468266 820 32.7599999990 0.0141463252 0.0091213839 0.0143689252 0.0096518213 0.0882720000 10370855 955859216 1765122048 0.2227364928 -0.0134262154 -0.3751824200 821 32.7999999990 0.0142507479 0.0091276316 0.0143689252 0.0096551287 0.0877480000 10372109 955859216 1765122048 0.2229591310 -0.0136573669 -0.3743164837 822 32.8400000000 0.0142609552 0.0091338765 0.0143689252 0.0096584121 0.1060900000 10373363 955859216 1765122048 0.2229025513 -0.0142130340 -0.3732833564 823 32.8800000000 0.0143033238 0.0091401577 0.0143689252 0.0096697504 0.1051840000 10374617 955859216 1765122048 0.2230321318 -0.0147403479 -0.3721601665 824 32.9200000000 0.0143703651 0.0091465051 0.0143703651 0.0096785248 0.0900180000 10375871 955859216 1765122048 0.2229978442 -0.0153217195 -0.3710787594 825 32.9600000000 0.0143918144 0.0091528630 0.0143918144 0.0096900953 0.0888620000 10377125 955859216 1765122048 0.2228432894 -0.0157778747 -0.3702077866 826 33.0000000000 0.0144591592 0.0091592871 0.0144591592 0.0097010998 0.1282610000 10378379 955859216 1765122048 0.2227118611 -0.0158854518 -0.3694241345 827 33.0400000000 0.0143713374 0.0091655895 0.0144591592 0.0097063041 0.0874610000 10379633 955859216 1765122048 0.2224204391 -0.0161931776 -0.3686493933 828 33.0800000000 0.0143225938 0.0091718177 0.0144591592 0.0097147468 0.0875200000 10380887 955859216 1765105664 0.2218504101 -0.0167117883 -0.3681105375 829 33.1199999990 0.0144063560 0.0091781320 0.0144591592 0.0097236971 0.1267830000 10382141 955859216 1765105664 0.2213460952 -0.0167824849 -0.3675616682 830 33.1600000000 0.0142380884 0.0091842284 0.0144591592 0.0097241177 0.1301330000 10383395 955859216 1765122048 0.2208117098 -0.0167773701 -0.3666879535 831 33.2000000000 0.0146141360 0.0091907625 0.0146141360 0.0097270068 0.1293980000 10384649 955859216 1766486016 0.2201607525 -0.0167676508 -0.3645178080 832 33.2400000000 0.0141865071 0.0091967670 0.0146141360 0.0097219849 0.1079210000 10385903 955859216 1768374272 0.2193180621 -0.0167537313 -0.3640432060 833 33.2800000000 0.0142506724 0.0092028342 0.0146141360 0.0097175399 0.0895040000 10387157 955859216 1770024960 0.2186217308 -0.0169990882 -0.3630439937 834 33.3200000000 0.0143543547 0.0092090110 0.0146141360 0.0097134066 0.0868340000 10388411 955859216 1771675648 0.2179532945 -0.0169341546 -0.3620207906 835 33.3600000000 0.0142476652 0.0092150454 0.0146141360 0.0097077395 0.0876300000 10389665 955859216 1773453312 0.2174059302 -0.0167598259 -0.3609274328 836 33.4000000000 0.0142362239 0.0092210515 0.0146141360 0.0097020458 0.1303970000 10390919 955859216 1775104000 0.2165816128 -0.0170382727 -0.3597188890 837 33.4399999990 0.0142835956 0.0092271000 0.0146141360 0.0096971830 0.1456690000 10392173 955859216 1776881664 0.2155460566 -0.0174529161 -0.3588212132 838 33.4800000000 0.0142849563 0.0092331356 0.0146141360 0.0096924019 0.1482810000 10393427 955859216 1778532352 0.2144304961 -0.0175980218 -0.3582516313 839 33.5200000000 0.0142123979 0.0092390704 0.0146141360 0.0096868776 0.1499620000 10394681 955859216 1780183040 0.2131797820 -0.0177172441 -0.3578805625 840 33.5600000000 0.0140739251 0.0092448262 0.0146141360 0.0096816379 0.1022330000 10395935 955859216 1781960704 0.2118500471 -0.0183876473 -0.3572788537 841 33.6000000000 0.0140962433 0.0092505948 0.0146141360 0.0096792222 0.0897600000 10397189 955859216 1783611392 0.2104136944 -0.0194677152 -0.3561826050 842 33.6400000000 0.0143595682 0.0092566624 0.0146141360 0.0096844335 0.0888260000 10398443 955859216 1785262080 0.2092089504 -0.0202957485 -0.3553265631 843 33.6800000000 0.0145174619 0.0092629030 0.0146141360 0.0096855953 0.1053260000 10399697 955859216 1787039744 0.2080982774 -0.0205358639 -0.3544287980 844 33.7200000000 0.0144255189 0.0092690199 0.0146141360 0.0096830010 0.0890130000 10400951 955859216 1786150912 0.2068537623 -0.0209052507 -0.3533037007 845 33.7599999990 0.0146284373 0.0092753624 0.0146284373 0.0096836879 0.1155340000 10402205 955859216 1783521280 0.2055862248 -0.0212968681 -0.3527639508 846 33.7999999990 0.0147304554 0.0092818105 0.0147304554 0.0096836099 0.0826640000 10403459 955859216 1782648832 0.2043256909 -0.0212634522 -0.3521476388 847 33.8400000000 0.0146224899 0.0092881159 0.0147304554 0.0096798192 0.0870370000 10404713 955859216 1781612544 0.2031430155 -0.0210736655 -0.3512538970 848 33.8800000000 0.0145448670 0.0092943149 0.0147304554 0.0096742420 0.1090930000 10405967 955859216 1780596736 0.2019360363 -0.0208325386 -0.3504141569 849 33.9200000000 0.0135709113 0.0092993521 0.0147304554 0.0096715479 0.0882340000 10407221 955859216 1779470336 0.1988583654 -0.0195211042 -0.3536102772 850 33.9600000000 0.0138954660 0.0093047593 0.0147304554 0.0096675878 0.0869250000 10408475 955859216 1778585600 0.1989010125 -0.0200797487 -0.3498640358 851 34.0000000000 0.0135335270 0.0093097285 0.0147304554 0.0096645199 0.1067560000 10409729 955859216 1777549312 0.1962559074 -0.0197174791 -0.3522877097 852 34.0400000000 0.0134781413 0.0093146210 0.0147304554 0.0096609812 0.1075680000 10410983 955859216 1776422912 0.1944734305 -0.0198019929 -0.3526457548 853 34.0800000000 0.0135540823 0.0093195910 0.0147304554 0.0096581714 0.0988590000 10412237 955859216 1775521792 0.1942407787 -0.0204451103 -0.3497075140 854 34.1199999990 0.0135078188 0.0093244953 0.0147304554 0.0096544344 0.1033860000 10413491 955859216 1774501888 0.1918415278 -0.0208129659 -0.3512974381 855 34.1600000000 0.0134276226 0.0093292942 0.0147304554 0.0096498896 0.0994760000 10414745 955859216 1773486080 0.1914104074 -0.0222088210 -0.3479720354 856 34.2000000000 0.0137534933 0.0093344627 0.0147304554 0.0096474116 0.0904090000 10415999 955859216 1772617728 0.1903041154 -0.0235505737 -0.3460777700 857 34.2400000000 0.0140814586 0.0093400018 0.0147304554 0.0096480174 0.1170550000 10417253 955859216 1771581440 0.1892558783 -0.0239339583 -0.3450365067 858 34.2800000000 0.0140198451 0.0093454561 0.0147304554 0.0096437183 0.0800800000 10418507 955859216 1770565632 0.1880218089 -0.0244182944 -0.3437097669 859 34.3200000000 0.0140866637 0.0093509756 0.0147304554 0.0096410463 0.0870770000 10419761 955859216 1769697280 0.1866459697 -0.0249781739 -0.3420807421 860 34.3600000000 0.0142000951 0.0093566141 0.0147304554 0.0096371007 0.1159920000 10421015 955859216 1768660992 0.1852827221 -0.0249575730 -0.3407378495 861 34.4000000000 0.0140874516 0.0093621087 0.0147304554 0.0096316312 0.0972550000 10422269 955859216 1767645184 0.1838536710 -0.0249712002 -0.3393469453 862 34.4400000000 0.0141201196 0.0093676284 0.0147304554 0.0096261460 0.0899270000 10423523 955859216 1766760448 0.1823530793 -0.0251490548 -0.3377400339 863 34.4800000000 0.0142435189 0.0093732784 0.0147304554 0.0096206269 0.0881980000 10424777 955859216 1765888000 0.1808325499 -0.0250377692 -0.3362421393 864 34.5200000000 0.0142282024 0.0093788975 0.0147304554 0.0096155758 0.0877260000 10426031 955859216 1765109760 0.1789786071 -0.0247278176 -0.3342463076 865 34.5600000000 0.0141094252 0.0093843663 0.0147304554 0.0096117682 0.1065990000 10427285 955859216 1765122048 0.1771268845 -0.0248795152 -0.3321181238 866 34.6000000000 0.0141680418 0.0093898902 0.0147304554 0.0096062644 0.1009130000 10428539 955859216 1765122048 0.1750889570 -0.0252316352 -0.3297156096 867 34.6400000000 0.0143743800 0.0093956393 0.0147304554 0.0096010471 0.0770520000 10429793 955859216 1765122048 0.1729447246 -0.0249560066 -0.3279776275 868 34.6800000000 0.0143258031 0.0094013192 0.0147304554 0.0095971171 0.0866360000 10431047 955859216 1765122048 0.1706858128 -0.0243556164 -0.3259611130 869 34.7200000000 0.0143281110 0.0094069887 0.0147304554 0.0095946929 0.1080700000 10432301 955859216 1765122048 0.1683990061 -0.0236034486 -0.3238964677 870 34.7600000000 0.0142259849 0.0094125278 0.0147304554 0.0095973430 0.0871520000 10433555 955859216 1765122048 0.1658607125 -0.0229928307 -0.3214590251 871 34.8000000000 0.0140699791 0.0094178750 0.0147304554 0.0096003568 0.0895920000 10434809 955859216 1765072896 0.1631799340 -0.0233066678 -0.3189624846 872 34.8400000000 0.0142504517 0.0094234170 0.0147304554 0.0095948760 0.0863900000 10436063 955859216 1765122048 0.1602699161 -0.0240519512 -0.3161551058 873 34.8800000000 0.0147313895 0.0094294971 0.0147313895 0.0095934006 0.0883050000 10437317 955859216 1765122048 0.1575009376 -0.0234500505 -0.3139917254 874 34.9200000000 0.0146980733 0.0094355252 0.0147313895 0.0095886871 0.1082390000 10438571 955859216 1765122048 0.1547297984 -0.0221183281 -0.3118922114 875 34.9600000000 0.0144602805 0.0094412678 0.0147313895 0.0095918592 0.0877950000 10439825 955859216 1765122048 0.1518179625 -0.0213982463 -0.3096354902 876 35.0000000000 0.0143980924 0.0094469263 0.0147313895 0.0095951919 0.0873700000 10441079 955859216 1765122048 0.1488444656 -0.0210093129 -0.3073778152 877 35.0400000000 0.0144558540 0.0094526377 0.0147313895 0.0095963905 0.0885730000 10442333 955859216 1765122048 0.1458566338 -0.0204479732 -0.3050538898 878 35.0800000000 0.0143285282 0.0094581911 0.0147313895 0.0096011540 0.1166170000 10443587 955859216 1765122048 0.1427646726 -0.0204245318 -0.3026444912 879 35.1200000000 0.0144405374 0.0094638593 0.0147313895 0.0095994622 0.0791680000 10444841 955859216 1765122048 0.1397613436 -0.0199986957 -0.3006248772 880 35.1600000000 0.0144598484 0.0094695366 0.0147313895 0.0096060321 0.0876280000 10446095 955859216 1765122048 0.1368251443 -0.0190524496 -0.2981472015 881 35.2000000000 0.0143835377 0.0094751144 0.0147313895 0.0096225598 0.1432360000 10447349 955859216 1765138432 0.1334600449 -0.0191461686 -0.2966122329 882 35.2400000000 0.0144508919 0.0094807558 0.0147313895 0.0096240611 0.1315240000 10448603 955859216 1765138432 0.1307279170 -0.0191707630 -0.2937175632 883 35.2800000000 0.0144443605 0.0094863771 0.0147313895 0.0096201733 0.1038600000 10449857 955859216 1766502400 0.1273119301 -0.0190914869 -0.2919248343 884 35.3200000000 0.0144723095 0.0094920173 0.0147313895 0.0096157119 0.0914200000 10451111 955859216 1768501248 0.1245275587 -0.0182094183 -0.2900218666 885 35.3600000000 0.0144433631 0.0094976121 0.0147313895 0.0096123393 0.0892920000 10452365 955859216 1770151936 0.1216295063 -0.0177254342 -0.2880533338 886 35.4000000000 0.0144350929 0.0095031848 0.0147313895 0.0096079135 0.1224140000 10453619 955859216 1771929600 0.1186194271 -0.0177889746 -0.2858571112 887 35.4400000000 0.0144557813 0.0095087684 0.0147313895 0.0096026496 0.1285520000 10454873 955859216 1773580288 0.1157189384 -0.0177536421 -0.2839786410 888 35.4800000000 0.0144685870 0.0095143538 0.0147313895 0.0095973400 0.1093450000 10456127 955859216 1775230976 0.1128945500 -0.0177227817 -0.2821163237 889 35.5200000000 0.0144923618 0.0095199533 0.0147313895 0.0095936564 0.0894580000 10457381 955859216 1777008640 0.1102729961 -0.0172119569 -0.2803707719 890 35.5600000000 0.0145029314 0.0095255522 0.0147313895 0.0095888759 0.0885610000 10458635 955859216 1778659328 0.1077079922 -0.0166127160 -0.2785624862 891 35.6000000000 0.0145198284 0.0095311574 0.0147313895 0.0095836156 0.1077450000 10459889 955859216 1780453376 0.1051407307 -0.0158217978 -0.2769114077 892 35.6400000000 0.0145178474 0.0095367479 0.0147313895 0.0095783220 0.1265150000 10461143 955859216 1782087680 0.1026142314 -0.0153640127 -0.2752963305 893 35.6800000000 0.0145008517 0.0095423068 0.0147313895 0.0095730161 0.1291350000 10462397 955859216 1783738368 0.1000710279 -0.0148723777 -0.2737359703 894 35.7200000000 0.0145117827 0.0095478655 0.0147313895 0.0095678466 0.1076340000 10463651 955859216 1785516032 0.0975829735 -0.0143789630 -0.2723187804 895 35.7600000000 0.0145451371 0.0095534490 0.0147313895 0.0095630086 0.0908670000 10464905 955859216 1787166720 0.0951001793 -0.0140289655 -0.2710617483 896 35.8000000000 0.0145486416 0.0095590240 0.0147313895 0.0095579313 0.0872290000 10466159 955859216 1786171392 0.0926469788 -0.0139057655 -0.2696366608 897 35.8400000000 0.0145059861 0.0095645390 0.0147313895 0.0095527115 0.0856090000 10467413 955859216 1784512512 0.0902717784 -0.0133852353 -0.2684696317 898 35.8800000000 0.0145216743 0.0095700592 0.0147313895 0.0095476704 0.0851700000 10468667 955859216 1783627776 0.0878325477 -0.0127001395 -0.2674049437 899 35.9200000000 0.0145292869 0.0095755756 0.0147313895 0.0095430328 0.0850440000 10469921 955859216 1782484992 0.0852358714 -0.0125283375 -0.2665985823 900 35.9600000000 0.0145788388 0.0095811348 0.0147313895 0.0095378108 0.0864210000 10471175 955859216 1780858880 0.0827003121 -0.0128543377 -0.2661890686 901 36.0000000000 0.0145434663 0.0095866424 0.0147313895 0.0095342949 0.0872270000 10472429 955859216 1779974144 0.0803336352 -0.0126583148 -0.2660101354 902 36.0400000000 0.0145273842 0.0095921199 0.0147313895 0.0095290628 0.0885900000 10473683 955859216 1778946048 0.0779759437 -0.0123125175 -0.2657534182 903 36.0800000000 0.0145592187 0.0095976206 0.0147313895 0.0095238627 0.0869260000 10474937 955859216 1777819648 0.0754317418 -0.0123779252 -0.2654805779 904 36.1200000000 0.0144309094 0.0096029671 0.0147313895 0.0095186689 0.0875100000 10476191 955859216 1776934912 0.0730402917 -0.0121825514 -0.2649914920 905 36.1600000000 0.0144871548 0.0096083640 0.0147313895 0.0095137932 0.1087950000 10477445 955859216 1775898624 0.0705988556 -0.0117383869 -0.2645721138 906 36.2000000000 0.0144066699 0.0096136602 0.0147313895 0.0095103240 0.1074630000 10478699 955859216 1777278976 0.0679838136 -0.0116586741 -0.2643518448 907 36.2400000000 0.0143891526 0.0096189253 0.0147313895 0.0095068059 0.1272010000 10479953 955859216 1779040256 0.0653569996 -0.0118719451 -0.2647664547 908 36.2800000000 0.0143811731 0.0096241701 0.0147313895 0.0095016494 0.1313690000 10481207 955859216 1780690944 0.0626969188 -0.0120372372 -0.2651896179 909 36.3200000000 0.0143883768 0.0096294112 0.0147313895 0.0094964266 0.0865330000 10482461 955859216 1782468608 0.0600622930 -0.0120526804 -0.2651125789 910 36.3600000000 0.0144097591 0.0096346644 0.0147313895 0.0094912588 0.0881050000 10483715 955859216 1784119296 0.0574440211 -0.0118767926 -0.2650524378 911 36.4000000000 0.0143754818 0.0096398683 0.0147313895 0.0094864618 0.1103680000 10484969 955859216 1785769984 0.0547850393 -0.0121321194 -0.2653868794 912 36.4400000000 0.0143945888 0.0096450818 0.0147313895 0.0094812778 0.0863990000 10486223 955859216 1787547648 0.0522697717 -0.0119717196 -0.2652375102 913 36.4800000000 0.0143624060 0.0096502487 0.0147313895 0.0094763387 0.0864390000 10487477 955859216 1786556416 0.0498202853 -0.0116028609 -0.2650968730 914 36.5200000000 0.0143545009 0.0096553956 0.0147313895 0.0094728097 0.0848510000 10488731 955859216 1784782848 0.0471730642 -0.0117728664 -0.2650597394 915 36.5600000000 0.0143405274 0.0096605159 0.0147313895 0.0094689923 0.0871110000 10489985 955859216 1784008704 0.0447250456 -0.0119776521 -0.2654271722 916 36.6000000000 0.0143559938 0.0096656420 0.0147313895 0.0094640437 0.0852020000 10491239 955859216 1783111680 0.0423414856 -0.0121413916 -0.2653827667 917 36.6400000000 0.0143252928 0.0096707234 0.0147313895 0.0094588840 0.0863020000 10492493 955859216 1781379072 0.0399191715 -0.0127492025 -0.2656186819 918 36.6800000000 0.0143389553 0.0096758086 0.0147313895 0.0094540452 0.0874470000 10493747 955859216 1780604928 0.0376633033 -0.0128402784 -0.2653637528 919 36.7200000000 0.0143756876 0.0096809227 0.0147313895 0.0094489035 0.0883170000 10495001 955859216 1779478528 0.0355999805 -0.0126502896 -0.2650876045 920 36.7600000000 0.0143782841 0.0096860286 0.0147313895 0.0094440342 0.0874200000 10496255 955859216 1778446336 0.0335518792 -0.0128504094 -0.2650801539 921 36.8000000000 0.0143445618 0.0096910867 0.0147313895 0.0094389411 0.0886030000 10497509 955859216 1777319936 0.0317401960 -0.0126296869 -0.2649105489 922 36.8400000000 0.0144233527 0.0096962193 0.0147313895 0.0094342545 0.0872010000 10498763 955859216 1776435200 0.0301130265 -0.0122152520 -0.2644505799 923 36.8800000000 0.0144122737 0.0097013288 0.0147313895 0.0094304932 0.0882440000 10500017 955859216 1775398912 0.0285324268 -0.0120976921 -0.2641898394 924 36.9200000000 0.0143772298 0.0097063893 0.0147313895 0.0094280347 0.1091720000 10501271 955859216 1774383104 0.0270662308 -0.0122903315 -0.2643967271 925 36.9600000000 0.0143945515 0.0097114576 0.0147313895 0.0094237497 0.1260100000 10502525 955859216 1775763456 0.0255219527 -0.0125482315 -0.2641715109 926 37.0000000000 0.0144173065 0.0097165395 0.0147313895 0.0094187403 0.1280160000 10503779 955859216 1777524736 0.0242325570 -0.0123054674 -0.2641576231 927 37.0400000000 0.0144293699 0.0097216234 0.0147313895 0.0094142056 0.1282010000 10505033 955859216 1779302400 0.0230820235 -0.0121773677 -0.2641494870 928 37.0800000000 0.0144034382 0.0097266685 0.0147313895 0.0094111364 0.1473240000 10506287 955859216 1780953088 0.0220390689 -0.0113586234 -0.2634918690 929 37.1200000000 0.0144180991 0.0097317185 0.0147313895 0.0094102459 0.1496440000 10507541 955859216 1782730752 0.0210474636 -0.0111969244 -0.2631534934 930 37.1600000000 0.0144322952 0.0097367729 0.0147313895 0.0094095209 0.0858630000 10508795 955859216 1784381440 0.0202032961 -0.0110017164 -0.2628985345 931 37.2000000000 0.0144325560 0.0097418167 0.0147313895 0.0094078021 0.0873540000 10510049 955859216 1786032128 0.0193842482 -0.0106857568 -0.2625918686 932 37.2400000000 0.0144646121 0.0097468840 0.0147313895 0.0094049034 0.1306690000 10511303 955859216 1787809792 0.0187198594 -0.0105585121 -0.2624906898 933 37.2800000000 0.0144375330 0.0097519115 0.0147313895 0.0094019557 0.1429830000 10512557 955859216 1784782848 0.0180107858 -0.0101151019 -0.2620216906 934 37.3200000000 0.0144358715 0.0097569265 0.0147313895 0.0093996553 0.1455800000 10513811 955859216 1783779328 0.0174862985 -0.0094032474 -0.2615342140 935 37.3600000000 0.0144278500 0.0097619221 0.0147313895 0.0093995479 0.1454870000 10515065 955859216 1782239232 0.0170922931 -0.0090127299 -0.2614019513 936 37.4000000000 0.0143746529 0.0097668503 0.0147313895 0.0093978044 0.1504110000 10516319 955859216 1783762944 0.0166693088 -0.0088217799 -0.2612969577 937 37.4400000000 0.0144563923 0.0097718551 0.0147313895 0.0093943892 0.1047390000 10517573 955859216 1785524224 0.0163891986 -0.0089371018 -0.2612977922 938 37.4800000000 0.0144725600 0.0097768665 0.0147313895 0.0093910391 0.1073300000 10518827 955859216 1787301888 0.0161085315 -0.0090089049 -0.2613087296 939 37.5200000000 0.0145065654 0.0097819035 0.0147313895 0.0093867544 0.1105020000 10520081 955859216 1784795136 0.0161024239 -0.0088540260 -0.2615596652 940 37.5600000000 0.0145197157 0.0097869437 0.0147313895 0.0093825308 0.1270290000 10521335 955859216 1783799808 0.0160915144 -0.0085751712 -0.2616652846 941 37.6000000000 0.0145352585 0.0097919897 0.0147313895 0.0093789357 0.1275940000 10522589 955859216 1782652928 0.0160265714 -0.0080831805 -0.2615050375 942 37.6400000000 0.0145792281 0.0097970717 0.0147313895 0.0093758301 0.1270520000 10523843 955859216 1781768192 0.0161504727 -0.0076575172 -0.2615839541 943 37.6800000000 0.0145594012 0.0098021219 0.0147313895 0.0093742390 0.0895020000 10525097 955859216 1783128064 0.0162493773 -0.0074073803 -0.2618192136 944 37.7200000000 0.0145648448 0.0098071672 0.0147313895 0.0093719959 0.0875230000 10526351 955859216 1784889344 0.0163751058 -0.0069355466 -0.2619610727 945 37.7600000000 0.0145528121 0.0098121890 0.0147313895 0.0093695996 0.0873280000 10527605 955859216 1786667008 0.0165258460 -0.0066425437 -0.2621326149 946 37.8000000000 0.0145483054 0.0098171955 0.0147313895 0.0093672402 0.0869640000 10528859 955859216 1785581568 0.0165375248 -0.0064830710 -0.2622258961 947 37.8400000000 0.0145627856 0.0098222067 0.0147313895 0.0093638745 0.0871320000 10530113 955859216 1783914496 0.0166797265 -0.0062322989 -0.2621389925 948 37.8800000000 0.0145700043 0.0098272149 0.0147313895 0.0093612645 0.0834350000 10531367 955859216 1782136832 0.0167814139 -0.0060504903 -0.2621960938 949 37.9200000000 0.0145854857 0.0098322289 0.0147313895 0.0093583525 0.0876100000 10532621 955859216 1781968896 0.0169903729 -0.0057944693 -0.2623626590 950 37.9600000000 0.0146034108 0.0098372512 0.0147313895 0.0093544371 0.0876500000 10533875 955859216 1780985856 0.0172486268 -0.0053856620 -0.2626565993 951 38.0000000000 0.0145961652 0.0098422553 0.0147313895 0.0093502226 0.0868510000 10535129 955859216 1779859456 0.0174541306 -0.0051199780 -0.2627145052 952 38.0400000000 0.0145959612 0.0098472487 0.0147313895 0.0093478813 0.0887070000 10536383 955859216 1778827264 0.0175914541 -0.0048746085 -0.2626029849 953 38.0800000000 0.0146090584 0.0098522453 0.0147313895 0.0093437760 0.1269450000 10537637 955859216 1777811456 0.0179474168 -0.0046334164 -0.2629638314 954 38.1200000000 0.0146129206 0.0098572355 0.0147313895 0.0093389992 0.1285910000 10538891 955859216 1779191808 0.0181891080 -0.0042886715 -0.2629884481 955 38.1600000000 0.0146228261 0.0098622257 0.0147313895 0.0093344799 0.1279740000 10540145 955859216 1780953088 0.0183554944 -0.0042809169 -0.2630276978 956 38.2000000000 0.0146346530 0.0098672178 0.0147313895 0.0093296388 0.0883930000 10541399 955859216 1782730752 0.0186610464 -0.0039411201 -0.2632434070 957 38.2400000000 0.0146103017 0.0098721740 0.0147313895 0.0093248875 0.0885440000 10542653 955859216 1784381440 0.0187902395 -0.0040427414 -0.2634589374 958 38.2800000000 0.0146501893 0.0098771615 0.0147313895 0.0093201914 0.0876260000 10543907 955859216 1786032128 0.0189492181 -0.0038804680 -0.2634500265 959 38.3200000000 0.0146607300 0.0098821495 0.0147313895 0.0093154790 0.0889030000 10545161 955859216 1787809792 0.0192302279 -0.0038723501 -0.2637643516 960 38.3600000000 0.0146471886 0.0098871131 0.0147313895 0.0093108912 0.1095840000 10546415 955859216 1784774656 0.0193894655 -0.0037558645 -0.2635764182 961 38.4000000000 0.0146573866 0.0098920770 0.0147313895 0.0093063706 0.0865700000 10547669 955859216 1783779328 0.0196956638 -0.0036300460 -0.2637885511 962 38.4400000000 0.0146647580 0.0098970382 0.0147313895 0.0093017291 0.0876190000 10548923 955859216 1782652928 0.0199578926 -0.0035206259 -0.2640555501 963 38.4800000000 0.0146400128 0.0099019634 0.0147313895 0.0092969956 0.1101350000 10550177 955859216 1781620736 0.0202293694 -0.0036361516 -0.2641581297 964 38.5200000000 0.0146709336 0.0099069105 0.0147313895 0.0092922424 0.1203070000 10551431 955859216 1780604928 0.0205584206 -0.0034609651 -0.2642865479 965 38.5600000000 0.0146489413 0.0099118245 0.0147313895 0.0092875083 0.1422590000 10552685 955859216 1779589120 0.0208328720 -0.0033732078 -0.2642414272 966 38.6000000000 0.0146300728 0.0099167088 0.0147313895 0.0092829104 0.1297800000 10553939 955859216 1780953088 0.0210925303 -0.0033740520 -0.2643961012 967 38.6400000000 0.0146371098 0.0099215903 0.0147313895 0.0092781415 0.0862750000 10555193 955859216 1782476800 0.0213866998 -0.0033561164 -0.2645479739 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-19 06:09:09 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0598230000 8923125 955859216 1771614208 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0025752268 0.0012876134 0.0025752268 0.0016431226 0.0786280000 9088907 955859216 1769709568 0.0001475579 -0.0015264887 0.0011166616 3 0.0800000000 0.0054430887 0.0026727718 0.0054430887 0.0017192722 0.0728280000 9090485 955859216 1769127936 -0.0038318646 -0.0031151343 0.0017624131 4 0.1200000000 0.0071020788 0.0037800986 0.0071020788 0.0015485467 0.0630890000 9092067 955859216 1768239104 -0.0022695232 -0.0055576218 0.0010869699 5 0.1600000000 0.0088641653 0.0047969119 0.0088641653 0.0013752144 0.0751210000 9093641 955859216 1767206912 -0.0046069017 -0.0063595572 0.0030346569 6 0.2000000000 0.0102949962 0.0057132593 0.0102949962 0.0012637319 0.0778850000 9095551 955859216 1766187008 -0.0038687084 -0.0083256084 0.0025956517 7 0.2400000000 0.0119190756 0.0065998045 0.0119190756 0.0012485981 0.0877420000 9096805 955859216 1765318656 -0.0037822886 -0.0100387419 0.0033189708 8 0.2800000000 0.0135721471 0.0074713473 0.0135721471 0.0012153601 0.0760950000 9098059 955859216 1765056512 -0.0048508532 -0.0114322798 0.0035875798 9 0.3200000000 0.0145241236 0.0082549891 0.0145241236 0.0012414429 0.0437150000 9099953 955859216 1765044224 -0.0065808552 -0.0129288891 0.0038882240 10 0.3600000000 0.0164575148 0.0090752417 0.0164575148 0.0012866144 0.0801230000 9102519 955859216 1765044224 -0.0065611973 -0.0136464555 0.0049732681 11 0.4000000000 0.0168754328 0.0097843500 0.0168754328 0.0015194634 0.0864590000 9103773 955859216 1765044224 -0.0073827649 -0.0149024474 0.0057871044 12 0.4400000000 0.0184440073 0.0105059881 0.0184440073 0.0018456307 0.0508350000 9105027 955859216 1766535168 -0.0073275422 -0.0166499503 0.0053982846 13 0.4800000000 0.0195238609 0.0111996706 0.0195238609 0.0019769412 0.0778070000 9106281 955859216 1766207488 -0.0093030622 -0.0178189762 0.0062185288 14 0.5200000000 0.0216732863 0.0119477860 0.0216732863 0.0019380178 0.0740810000 9107535 955859216 1765175296 -0.0092591327 -0.0188367907 0.0061802622 15 0.5600000000 0.0230075251 0.0126851020 0.0230075251 0.0018714597 0.0594290000 9108789 955859216 1765076992 -0.0118039949 -0.0189502221 0.0072314856 16 0.6000000000 0.0226826966 0.0133099516 0.0230075251 0.0018583132 0.0728720000 9110043 955859216 1765076992 -0.0113932267 -0.0204836484 0.0061568902 17 0.6400000000 0.0235749185 0.0139137732 0.0235749185 0.0018261288 0.0569390000 9112577 955859216 1765076992 -0.0131504443 -0.0226375088 0.0049379757 18 0.6800000000 0.0242691208 0.0144890703 0.0242691208 0.0017723705 0.1031660000 9116455 955859216 1765076992 -0.0144604184 -0.0231519341 0.0060674706 19 0.7200000000 0.0251664948 0.0150510400 0.0251664948 0.0017817018 0.0811350000 9117709 955859216 1765011456 -0.0158801451 -0.0237470530 0.0058745728 20 0.7600000000 0.0248312354 0.0155400498 0.0251664948 0.0018946246 0.0491200000 9118963 955859216 1765060608 -0.0188180786 -0.0246588457 0.0053929128 21 0.8000000000 0.0255986452 0.0160190305 0.0255986452 0.0018558586 0.0435640000 9120217 955859216 1766424576 -0.0216097590 -0.0244772136 0.0059106573 22 0.8400000000 0.0260306560 0.0164741044 0.0260306560 0.0018324958 0.0745810000 9121471 955859216 1765933056 -0.0269832555 -0.0256769434 0.0055112932 23 0.8800000000 0.0264499094 0.0169078350 0.0264499094 0.0017921326 0.0821580000 9122725 955859216 1765048320 -0.0269340593 -0.0270482525 0.0040385360 24 0.9200000000 0.0290522892 0.0174138540 0.0290522892 0.0017803555 0.0587030000 9123979 955859216 1765048320 -0.0342034586 -0.0279725175 0.0039185127 25 0.9600000000 0.0310425777 0.0179590029 0.0310425777 0.0017814102 0.0774820000 9125233 955859216 1765048320 -0.0355943628 -0.0287297145 0.0036775856 26 1.0000000000 0.0305353925 0.0184427102 0.0310425777 0.0017504821 0.0939160000 9126487 955859216 1765048320 -0.0414848998 -0.0297203436 0.0043620123 27 1.0400000000 0.0317087807 0.0189340462 0.0317087807 0.0018671473 0.0697960000 9127741 955859216 1764532224 -0.0470252186 -0.0315560736 0.0024862895 28 1.0800000000 0.0337589718 0.0194635078 0.0337589718 0.0020556981 0.0485790000 9128995 955859216 1765031936 -0.0515055247 -0.0317430757 0.0026680089 29 1.1200000000 0.0356607288 0.0200220326 0.0356607288 0.0022444701 0.0680800000 9130249 955859216 1765076992 -0.0572011098 -0.0333480872 0.0003456818 30 1.1600000000 0.0348133035 0.0205150750 0.0356607288 0.0022606804 0.1238190000 9131503 955859216 1765011456 -0.0664383769 -0.0332583375 0.0020127622 31 1.2000000000 0.0365490578 0.0210323003 0.0365490578 0.0022735444 0.0508750000 9132757 955859216 1765044224 -0.0729282573 -0.0342248827 0.0006663823 32 1.2400000000 0.0382569768 0.0215705714 0.0382569768 0.0023182576 0.0832830000 9134011 955859216 1765171200 -0.0794122517 -0.0355019756 -0.0012500864 33 1.2800000000 0.0381702892 0.0220735932 0.0382569768 0.0023846962 0.0603230000 9137825 955859216 1765171200 -0.0849457309 -0.0357992426 -0.0015525278 34 1.3200000000 0.0219253302 0.0220692325 0.0382569768 0.0027761463 0.0757550000 9144327 955859216 1765056512 -0.1155823767 -0.0208627097 -0.0059182332 35 1.3600000000 0.0269333776 0.0222082081 0.0382569768 0.0031661186 0.0523530000 9145581 955859216 1766424576 -0.1185342446 -0.0249655843 -0.0073470618 36 1.4000000000 0.0309108645 0.0224499485 0.0382569768 0.0037758840 0.1040930000 9146835 955859216 1765806080 -0.1235100329 -0.0279109441 -0.0082319947 37 1.4400000000 0.0267256424 0.0225655078 0.0382569768 0.0037808914 0.0782290000 9148089 955859216 1767186432 -0.1348759979 -0.0259272344 -0.0080182571 38 1.4800000000 0.0257815011 0.0226501392 0.0382569768 0.0037357472 0.0467020000 9149343 955859216 1769074688 -0.1467392445 -0.0255405884 -0.0075350404 39 1.5200000000 0.0296740122 0.0228302385 0.0382569768 0.0036953976 0.0633900000 9150597 955859216 1770725376 -0.1497304291 -0.0299832355 -0.0098977825 40 1.5600000000 0.0271159504 0.0229373813 0.0382569768 0.0036935975 0.0410130000 9151851 955859216 1772376064 -0.1597606093 -0.0291391406 -0.0098994458 41 1.6000000000 0.0262865163 0.0230190675 0.0382569768 0.0037115898 0.0586250000 9153105 955859216 1774153728 -0.1702417284 -0.0294550899 -0.0083994083 42 1.6400000000 0.0271578245 0.0231176094 0.0382569768 0.0036682015 0.0863480000 9154359 955859216 1775804416 -0.1833976358 -0.0288198106 -0.0060198735 43 1.6800000000 0.0303460341 0.0232857123 0.0382569768 0.0036348627 0.0715990000 9155613 955859216 1777455104 -0.1894261837 -0.0313906036 -0.0020237900 44 1.7200000000 0.0335653871 0.0235193412 0.0382569768 0.0036439920 0.0476310000 9156867 955859216 1779232768 -0.1955449730 -0.0352345556 -0.0032768045 45 1.7600000000 0.0372914374 0.0238253878 0.0382569768 0.0036355122 0.0448250000 9158121 955859216 1780883456 -0.2029316127 -0.0367096625 0.0011319666 46 1.8000000000 0.0399933644 0.0241768656 0.0399933644 0.0036282180 0.0944120000 9159375 955859216 1782677504 -0.2087761164 -0.0388133824 0.0019313451 47 1.8400000000 0.0405579880 0.0245254001 0.0405579880 0.0037269127 0.0800150000 9160629 955859216 1784311808 -0.2119520754 -0.0412479192 0.0018194187 48 1.8800000000 0.0420217253 0.0248899069 0.0420217253 0.0037506537 0.0595090000 9161883 955859216 1785962496 -0.2160214484 -0.0428805239 0.0032212180 49 1.9200000000 0.0443818979 0.0252877026 0.0443818979 0.0037146476 0.0729200000 9163137 955859216 1787740160 -0.2228528112 -0.0440502279 0.0045234114 50 1.9600000000 0.0251910239 0.0252857690 0.0443818979 0.0038262705 0.0906400000 9164391 955859216 1785081856 -0.2402621657 -0.0259346273 0.0049331752 51 2.0000000000 0.0294293761 0.0253670162 0.0443818979 0.0038207485 0.0559540000 9165645 955859216 1786232832 -0.2385592461 -0.0302562471 0.0030524731 52 2.0400000000 0.0334962197 0.0255233471 0.0443818979 0.0037913675 0.0940950000 9166899 955859216 1785327616 -0.2414321154 -0.0337237418 0.0031720498 53 2.0800000000 0.0354705453 0.0257110300 0.0443818979 0.0038139948 0.0553000000 9168153 955859216 1785090048 -0.2432938367 -0.0380094945 0.0004923158 54 2.1200000000 0.0258937534 0.0257144138 0.0443818979 0.0040133565 0.0435150000 9169407 955859216 1783709696 -0.2575123608 -0.0303255431 0.0039325040 55 2.1600000000 0.0309323091 0.0258092846 0.0443818979 0.0040588026 0.0541230000 9170661 955859216 1782693888 -0.2591545284 -0.0344483629 0.0048150276 56 2.2000000000 0.0258636754 0.0258102559 0.0443818979 0.0041007816 0.0699650000 9171915 955859216 1781678080 -0.2797074914 -0.0291114338 0.0127289137 57 2.2400000000 0.0278081223 0.0258453062 0.0443818979 0.0040720917 0.0563840000 9173169 955859216 1780551680 -0.2843045294 -0.0336708426 0.0137768555 58 2.2800000000 0.0279452298 0.0258815118 0.0443818979 0.0040757799 0.0465890000 9174423 955859216 1781915648 -0.2935937643 -0.0344457403 0.0165766086 59 2.3200000000 0.0289224610 0.0259330533 0.0443818979 0.0042118899 0.1180230000 9175677 955859216 1781317632 -0.3075568974 -0.0330539495 0.0224320795 60 2.3600000000 0.0308898799 0.0260156671 0.0443818979 0.0043339621 0.0568130000 9176931 955859216 1782677504 -0.3106787801 -0.0366962254 0.0210323054 61 2.4000000000 0.0326194540 0.0261239259 0.0443818979 0.0044635986 0.0831840000 9178185 955859216 1784438784 -0.3167937398 -0.0397784375 0.0211329702 62 2.4400000000 0.0260432083 0.0261226240 0.0443818979 0.0045536843 0.0711240000 9179439 955859216 1786089472 -0.3417771459 -0.0328836106 0.0299037267 63 2.4800000000 0.0272044353 0.0261397956 0.0443818979 0.0047034947 0.0672910000 9180693 955859216 1787867136 -0.3502493501 -0.0351428613 0.0313198566 64 2.5200000000 0.0282165520 0.0261722449 0.0443818979 0.0050605829 0.0785210000 9181947 955859216 1785716736 -0.3625955880 -0.0349116102 0.0360459238 65 2.5600000000 0.0282819513 0.0262047019 0.0443818979 0.0053565944 0.0633460000 9188321 955859216 1784832000 -0.3763550222 -0.0351301543 0.0397614092 66 2.6000000000 0.0293407254 0.0262522174 0.0443818979 0.0054465738 0.0614570000 9200071 955859216 1783091200 -0.3868562579 -0.0348501951 0.0419132039 67 2.6400000000 0.0304937009 0.0263155231 0.0443818979 0.0055017751 0.0834550000 9201325 955859216 1782206464 -0.3969120085 -0.0334754698 0.0443831831 68 2.6800000000 0.0304186139 0.0263758627 0.0443818979 0.0054819461 0.0802720000 9202579 955859216 1781161984 -0.4080622196 -0.0336128622 0.0436479636 69 2.7200000000 0.0301476903 0.0264305269 0.0443818979 0.0054434027 0.0491820000 9203833 955859216 1780146176 -0.4176522493 -0.0330800973 0.0480481386 70 2.7600000000 0.0359784774 0.0265669262 0.0443818979 0.0054103313 0.0743360000 9205087 955859216 1779277824 -0.4255234599 -0.0368842781 0.0489437692 71 2.8000000000 0.0408574827 0.0267682016 0.0443818979 0.0054323976 0.0592980000 9206341 955859216 1778356224 -0.4319719374 -0.0410022512 0.0469322056 72 2.8400000000 0.0275322497 0.0267788134 0.0443818979 0.0063414064 0.0826470000 9207595 955859216 1777856512 -0.4500074387 -0.0230089873 0.0466995761 73 2.8800000000 0.0308593791 0.0268347116 0.0443818979 0.0063846071 0.1041000000 9208849 955859216 1775722496 -0.4595458210 -0.0248555951 0.0490920097 74 2.9200000000 0.0377848595 0.0269826865 0.0443818979 0.0064304619 0.0586010000 9210103 955859216 1777082368 -0.4606541991 -0.0298698880 0.0474836640 75 2.9600000000 0.0447894074 0.0272201095 0.0447894074 0.0064504961 0.0523450000 9211357 955859216 1776336896 -0.4608745575 -0.0329501480 0.0461756289 76 3.0000000000 0.0293084271 0.0272475873 0.0447894074 0.0065970149 0.0789330000 9212611 955859216 1775321088 -0.4613790810 -0.0149124758 0.0346033387 77 3.0400000000 0.0325392000 0.0273163096 0.0447894074 0.0065948606 0.0533360000 9213865 955859216 1774305280 -0.4612692297 -0.0177160483 0.0284724832 78 3.0800000000 0.0292391460 0.0273409613 0.0447894074 0.0065641835 0.0593840000 9215119 955859216 1774305280 -0.4601774812 -0.0132879438 0.0205586459 79 3.1200000000 0.0370875895 0.0274643364 0.0447894074 0.0065428427 0.0774980000 9216373 955859216 1774669824 -0.4658156633 -0.0177889857 0.0200928692 80 3.1600000000 0.0434501208 0.0276641587 0.0447894074 0.0065231182 0.0494630000 9217627 955859216 1773289472 -0.4683822691 -0.0210992899 0.0177513212 81 3.2000000000 0.0289590862 0.0276801454 0.0447894074 0.0065043678 0.1048920000 9218881 955859216 1772290048 -0.4826558232 -0.0080987019 0.0175694209 82 3.2400000000 0.0303263757 0.0277124165 0.0447894074 0.0065125964 0.0631320000 9220135 955859216 1770860544 -0.4906954467 -0.0093076844 0.0173308700 83 3.2800000000 0.0311553888 0.0277538981 0.0447894074 0.0065521784 0.0952770000 9221389 955859216 1770135552 -0.4982013106 -0.0080279857 0.0143043250 84 3.3200000000 0.0306558535 0.0277884452 0.0447894074 0.0065407993 0.0727820000 9222643 955859216 1768685568 -0.5108960271 -0.0086848112 0.0144773424 85 3.3600000000 0.0290264897 0.0278030104 0.0447894074 0.0065213524 0.0694090000 9223897 955859216 1767960576 -0.5249082446 -0.0061646728 0.0145546645 86 3.4000000000 0.0297992881 0.0278262230 0.0447894074 0.0065633094 0.0511520000 9225151 955859216 1766924288 -0.5395131111 -0.0061911293 0.0186801422 87 3.4400000000 0.0293654576 0.0278439153 0.0447894074 0.0066822378 0.0600400000 9226405 955859216 1766039552 -0.5493969917 -0.0069057308 0.0182812344 88 3.4800000000 0.0293260533 0.0278607578 0.0447894074 0.0068284074 0.0717930000 9227659 955859216 1767415808 -0.5624454618 -0.0065314472 0.0185420383 89 3.5200000000 0.0291542597 0.0278752915 0.0447894074 0.0069590553 0.0492680000 9228913 955859216 1766653952 -0.5718225837 -0.0061634043 0.0186318476 90 3.5600000000 0.0287583247 0.0278851030 0.0447894074 0.0070496881 0.0558790000 9230167 955859216 1765548032 -0.5794040561 -0.0075751985 0.0173410904 91 3.6000000000 0.0286592785 0.0278936104 0.0447894074 0.0070887225 0.0768750000 9231421 955859216 1765179392 -0.5939219594 -0.0087322732 0.0203071535 92 3.6400000000 0.0288924575 0.0279044675 0.0447894074 0.0070969959 0.0585800000 9232675 955859216 1765163008 -0.6090345979 -0.0068292567 0.0254769642 93 3.6800000000 0.0288074147 0.0279141766 0.0447894074 0.0070755019 0.0740660000 9233929 955859216 1765163008 -0.6138184071 -0.0076761367 0.0220610052 94 3.7200000000 0.0306569915 0.0279433555 0.0447894074 0.0070493640 0.0460720000 9235183 955859216 1766526976 -0.6200986505 -0.0117200483 0.0218626112 95 3.7600000000 0.0290216506 0.0279547059 0.0447894074 0.0070271392 0.0585840000 9236437 955859216 1766182912 -0.6339745522 -0.0089097545 0.0281622410 96 3.8000000000 0.0289374404 0.0279649428 0.0447894074 0.0069979743 0.0934920000 9237691 955859216 1765113856 -0.6441246867 -0.0093755173 0.0276910700 97 3.8400000000 0.0300426539 0.0279863625 0.0447894074 0.0069625666 0.0659070000 9238945 955859216 1765163008 -0.6491665244 -0.0131207006 0.0297267903 98 3.8800000000 0.0289210975 0.0279959006 0.0447894074 0.0069338497 0.0571520000 9240199 955859216 1765163008 -0.6642088294 -0.0126967747 0.0336550176 99 3.9200000000 0.0318174213 0.0280345018 0.0447894074 0.0069085086 0.0541560000 9241453 955859216 1766637568 -0.6686002016 -0.0140063167 0.0370337069 100 3.9600000000 0.0330060571 0.0280842173 0.0447894074 0.0068740796 0.0506860000 9242707 955859216 1766047744 -0.6763681173 -0.0155807985 0.0411866903 101 4.0000000000 0.0329388529 0.0281322830 0.0447894074 0.0068411032 0.0729520000 9243961 955859216 1765163008 -0.6850050092 -0.0172138996 0.0471873656 102 4.0400000000 0.0336382240 0.0281862629 0.0447894074 0.0068167952 0.0487320000 9245215 955859216 1765163008 -0.6883245111 -0.0193187743 0.0489151180 103 4.0800000000 0.0302237961 0.0282060447 0.0447894074 0.0067863171 0.0632870000 9246469 955859216 1766526976 -0.7005788088 -0.0166040026 0.0552224703 104 4.1200000000 0.0292107724 0.0282157056 0.0447894074 0.0067575634 0.0541090000 9247723 955859216 1766182912 -0.7136473060 -0.0173982419 0.0679342598 105 4.1600000000 0.0312595852 0.0282446949 0.0447894074 0.0067602634 0.0481670000 9248977 955859216 1765146624 -0.7153867483 -0.0195093378 0.0698767006 106 4.2000000000 0.0325070806 0.0282849061 0.0447894074 0.0067689762 0.0662640000 9250231 955859216 1765163008 -0.7212480903 -0.0200392697 0.0749842674 107 4.2400000000 0.0298196357 0.0282992494 0.0447894074 0.0067455336 0.0600520000 9251485 955859216 1766526976 -0.7229463458 -0.0208578724 0.0711671114 108 4.2800000000 0.0293677412 0.0283091428 0.0447894074 0.0067144700 0.0660910000 9252739 955859216 1766129664 -0.7326748371 -0.0213955734 0.0795598179 109 4.3200000000 0.0318723172 0.0283418325 0.0447894074 0.0066976438 0.0756900000 9253993 955859216 1765273600 -0.7332726717 -0.0236706436 0.0808078498 110 4.3600000000 0.0319216475 0.0283743762 0.0447894074 0.0067019675 0.0566050000 9255247 955859216 1765179392 -0.7411254644 -0.0242829602 0.0891635641 111 4.4000000000 0.0317543000 0.0284048260 0.0447894074 0.0067006321 0.0731130000 9256501 955859216 1765179392 -0.7474570274 -0.0254190452 0.0958500654 112 4.4400000000 0.0327147916 0.0284433078 0.0447894074 0.0067024514 0.0559620000 9257755 955859216 1766543360 -0.7548277974 -0.0257366281 0.1037279740 113 4.4800000000 0.0332050733 0.0284854474 0.0447894074 0.0067082022 0.0904530000 9259009 955859216 1765163008 -0.7586857080 -0.0262922011 0.1079545766 114 4.5200000000 0.0300512183 0.0284991822 0.0447894074 0.0067396861 0.0615080000 9260263 955859216 1766526976 -0.7710561752 -0.0235692486 0.1201086938 115 4.5600000000 0.0315476358 0.0285256905 0.0447894074 0.0067636403 0.0987170000 9261517 955859216 1765810176 -0.7710309625 -0.0249476340 0.1220065802 116 4.6000000000 0.0301398616 0.0285396058 0.0447894074 0.0067961281 0.0591460000 9262771 955859216 1767174144 -0.7820373774 -0.0210772865 0.1339302063 117 4.6400000000 0.0327923745 0.0285759542 0.0447894074 0.0068082341 0.0725480000 9264025 955859216 1769050112 -0.7884740829 -0.0206006654 0.1443489194 118 4.6800000000 0.0333522260 0.0286164311 0.0447894074 0.0067801192 0.0866210000 9265279 955859216 1770700800 -0.7933746576 -0.0226204079 0.1485233903 119 4.7200000000 0.0343645439 0.0286647346 0.0447894074 0.0067547458 0.0575480000 9266533 955859216 1772478464 -0.7992938757 -0.0240051895 0.1555602551 120 4.7600000000 0.0357102752 0.0287234474 0.0447894074 0.0067276181 0.0935930000 9267787 955859216 1774129152 -0.8054306507 -0.0239892788 0.1637777984 121 4.8000000000 0.0309171919 0.0287415775 0.0447894074 0.0067149471 0.0620750000 9269041 955859216 1775906816 -0.8171604872 -0.0199404508 0.1815945953 122 4.8400000000 0.0342481956 0.0287867137 0.0447894074 0.0066893530 0.1001340000 9270295 955859216 1777557504 -0.8170647025 -0.0216100402 0.1822919697 123 4.8800000000 0.0368869640 0.0288525694 0.0447894074 0.0066684647 0.0729130000 9271549 955859216 1779208192 -0.8214340210 -0.0199196115 0.1885136962 124 4.9200000000 0.0301722158 0.0288632117 0.0447894074 0.0066435017 0.0586190000 9272803 955859216 1780985856 -0.8339188099 -0.0128905186 0.2046226561 125 4.9600000000 0.0321932361 0.0288898519 0.0447894074 0.0066359077 0.0552810000 9274057 955859216 1782636544 -0.8371088505 -0.0149261318 0.2095135599 126 5.0000000000 0.0338725671 0.0289293973 0.0447894074 0.0066178015 0.0632280000 9275311 955859216 1784287232 -0.8411903381 -0.0153230680 0.2167584896 127 5.0400000000 0.0308342092 0.0289443958 0.0447894074 0.0065931113 0.0793270000 9276565 955859216 1786064896 -0.8520814180 -0.0115282405 0.2338031083 128 5.0800000000 0.0331256203 0.0289770616 0.0447894074 0.0065680904 0.0909310000 9277819 955859216 1787715584 -0.8563070297 -0.0138198743 0.2394539863 129 5.1200000000 0.0339723378 0.0290157847 0.0447894074 0.0065443036 0.0879120000 9289313 955859216 1786834944 -0.8599318266 -0.0142517462 0.2461009473 130 5.1600000000 0.0305131245 0.0290273027 0.0447894074 0.0065334943 0.1145560000 9311559 955859216 1783943168 -0.8701952696 -0.0110751633 0.2643533349 131 5.2000000000 0.0317922011 0.0290484088 0.0447894074 0.0065642376 0.0801740000 9312813 955859216 1782272000 -0.8730909824 -0.0116804354 0.2683075070 132 5.2400000000 0.0302181728 0.0290572706 0.0447894074 0.0065723665 0.0858370000 9314067 955859216 1783795712 -0.8742496371 -0.0105259279 0.2661353350 133 5.2800000000 0.0299357604 0.0290638758 0.0447894074 0.0065709321 0.0773050000 9315321 955859216 1785556992 -0.8845793009 -0.0100295627 0.2851836979 134 5.3200000000 0.0298947878 0.0290700767 0.0447894074 0.0065978955 0.0608470000 9316575 955859216 1787207680 -0.8932970762 -0.0075311605 0.3015023172 135 5.3600000000 0.0294860732 0.0290731581 0.0447894074 0.0066160413 0.0968600000 9317829 955859216 1784803328 -0.8967195153 -0.0067659160 0.3054528236 136 5.4000000000 0.0292122476 0.0290741808 0.0447894074 0.0066497422 0.0763380000 9319083 955859216 1783398400 -0.9037229419 -0.0064290622 0.3175468743 137 5.4400000000 0.0299094915 0.0290802780 0.0447894074 0.0067027630 0.0571960000 9320337 955859216 1784795136 -0.9085720181 -0.0067250272 0.3266102672 138 5.4800000000 0.0288528800 0.0290786302 0.0447894074 0.0067412096 0.0578350000 9321591 955859216 1786699776 -0.9146753550 -0.0065421183 0.3314490616 139 5.5200000000 0.0285201985 0.0290746127 0.0447894074 0.0067821602 0.0587350000 9322845 955859216 1785724928 -0.9208137393 -0.0082572745 0.3367063701 140 5.5600000000 0.0285273846 0.0290707039 0.0447894074 0.0068511725 0.0808450000 9324099 955859216 1784344576 -0.9300594330 -0.0075220168 0.3509261012 141 5.6000000000 0.0285255872 0.0290668378 0.0447894074 0.0068833831 0.0867930000 9325353 955859216 1783193600 -0.9354525208 -0.0062798532 0.3563894033 142 5.6400000000 0.0282966569 0.0290614140 0.0447894074 0.0069164119 0.0638720000 9326607 955859216 1784557568 -0.9446340799 -0.0060037561 0.3710072339 143 5.6800000000 0.0298117362 0.0290666610 0.0447894074 0.0069933644 0.0647900000 9327861 955859216 1783955456 -0.9491668344 -0.0051940661 0.3807351589 144 5.7200000000 0.0284109339 0.0290621074 0.0447894074 0.0070331516 0.0562720000 9329115 955859216 1782812672 -0.9560337663 -0.0021403080 0.3887231648 145 5.7600000000 0.0279466361 0.0290544145 0.0447894074 0.0070317009 0.0770960000 9330369 955859216 1781780480 -0.9617149234 -0.0025845170 0.3954502940 146 5.8000000000 0.0279505216 0.0290468536 0.0447894074 0.0070222949 0.0720640000 9331623 955859216 1780785152 -0.9674881101 -0.0024827998 0.4048387110 147 5.8400000000 0.0278408714 0.0290386496 0.0447894074 0.0070051021 0.0574070000 9332877 955859216 1782145024 -0.9776292443 -0.0031363219 0.4256519675 148 5.8800000000 0.0276108962 0.0290290026 0.0447894074 0.0069837251 0.0891350000 9334131 955859216 1779597312 -0.9790627360 -0.0030584554 0.4289862812 149 5.9200000000 0.0299523640 0.0290351997 0.0447894074 0.0069675785 0.0715220000 9335385 955859216 1781248000 -0.9823952317 -0.0045433305 0.4396927357 150 5.9600000000 0.0304435696 0.0290445888 0.0447894074 0.0069485847 0.0560370000 9336639 955859216 1782755328 -0.9858523607 -0.0052720811 0.4483896196 151 6.0000000000 0.0311164223 0.0290583096 0.0447894074 0.0069293526 0.0585950000 9337893 955859216 1784406016 -0.9888864756 -0.0054874383 0.4580111206 152 6.0400000000 0.0318554081 0.0290767115 0.0447894074 0.0069155930 0.0847330000 9339147 955859216 1786183680 -0.9916504622 -0.0048401654 0.4686290622 153 6.0800000000 0.0308074895 0.0290880238 0.0447894074 0.0069035889 0.0605820000 9340401 955859216 1787834368 -0.9955406785 -0.0048450492 0.4772075117 154 6.1200000000 0.0279158223 0.0290804121 0.0447894074 0.0069174340 0.0799880000 9341655 955859216 1786818560 -1.0010316372 -0.0026508889 0.4897781610 155 6.1600000000 0.0270498972 0.0290673120 0.0447894074 0.0069755495 0.0783400000 9342909 955859216 1785053184 -1.0030249357 -0.0026785042 0.4975199103 156 6.2000000000 0.0271620210 0.0290550986 0.0447894074 0.0070837794 0.0962160000 9344163 955859216 1783033856 -1.0075290203 -0.0016333535 0.5121878982 157 6.2400000000 0.0271596182 0.0290430255 0.0447894074 0.0071710723 0.0561370000 9345417 955859216 1784422400 -1.0096436739 -0.0009579955 0.5228983760 158 6.2800000000 0.0268516261 0.0290291559 0.0447894074 0.0072443844 0.0649850000 9346671 955859216 1783771136 -1.0127214193 -0.0003121346 0.5392343998 159 6.3200000000 0.0267218929 0.0290146448 0.0447894074 0.0072724718 0.0734710000 9347925 955859216 1782677504 -1.0135017633 -0.0008283257 0.5471576452 160 6.3600000000 0.0279833321 0.0290081991 0.0447894074 0.0073116491 0.0499940000 9349179 955859216 1782161408 -1.0138715506 -0.0005790181 0.5619916916 161 6.4000000000 0.0294636413 0.0290110279 0.0447894074 0.0072967884 0.0577010000 9350433 955859216 1782513664 -1.0135507584 -0.0015805848 0.5728267431 162 6.4400000000 0.0295988899 0.0290146567 0.0447894074 0.0072764943 0.0601810000 9351687 955859216 1781391360 -1.0135629177 -0.0034737142 0.5839294195 163 6.4800000000 0.0314619876 0.0290296710 0.0447894074 0.0072595055 0.0740510000 9352941 955859216 1780396032 -1.0138598680 -0.0039786063 0.5966799855 164 6.5200000000 0.0333554223 0.0290560475 0.0447894074 0.0072411154 0.0689010000 9354195 955859216 1779359744 -1.0135128498 -0.0045018829 0.6085218191 165 6.5600000000 0.0264708214 0.0290403795 0.0447894074 0.0072374089 0.0609740000 9355449 955859216 1778233344 -1.0164180994 0.0034697726 0.6266235709 166 6.6000000000 0.0315797366 0.0290556768 0.0447894074 0.0072471092 0.0775160000 9356703 955859216 1777348608 -1.0143928528 -0.0008884333 0.6379972696 167 6.6400000000 0.0347935408 0.0290900353 0.0447894074 0.0072493354 0.0605150000 9357957 955859216 1777197056 -1.0124539137 -0.0021126678 0.6481723785 168 6.6800000000 0.0353636444 0.0291273782 0.0447894074 0.0072485045 0.0627070000 9359211 955859216 1777565696 -1.0115002394 -0.0024603866 0.6601967812 169 6.7200000000 0.0335480459 0.0291535360 0.0447894074 0.0072349914 0.0596930000 9360465 955859216 1776947200 -1.0116860867 -0.0028310120 0.6743142605 170 6.7600000000 0.0265203808 0.0291380468 0.0447894074 0.0072252684 0.0832990000 9361719 955859216 1775951872 -1.0158898830 0.0060981847 0.6922477484 171 6.8000000000 0.0298954081 0.0291424758 0.0447894074 0.0072201295 0.0709460000 9362973 955859216 1774919680 -1.0141695738 0.0055656699 0.7016941309 172 6.8400000000 0.0312880352 0.0291549500 0.0447894074 0.0072015173 0.0669830000 9364227 955859216 1773924352 -1.0129163265 0.0055020717 0.7138374448 173 6.8800000000 0.0326088592 0.0291749148 0.0447894074 0.0071817879 0.0626460000 9365481 955859216 1775288320 -1.0126951933 0.0058090803 0.7273227572 174 6.9200000000 0.0334732607 0.0291996180 0.0447894074 0.0071616925 0.0914420000 9366735 955859216 1774534656 -1.0134825706 0.0067451177 0.7397431731 175 6.9600000000 0.0262624305 0.0291828340 0.0447894074 0.0071440044 0.0936060000 9367989 955859216 1773518848 -1.0152407885 0.0146796014 0.7525626421 176 7.0000000000 0.0268152189 0.0291693817 0.0447894074 0.0071274240 0.0734000000 9369243 955859216 1774899200 -1.0164570808 0.0145117017 0.7671075463 177 7.0400000000 0.0265237130 0.0291544344 0.0447894074 0.0071372209 0.0584830000 9370497 955859216 1776660480 -1.0155208111 0.0124121644 0.7742393613 178 7.0800000000 0.0293693896 0.0291556420 0.0447894074 0.0071215173 0.1012230000 9371751 955859216 1778438144 -1.0136682987 0.0090981862 0.7817052603 179 7.1200000000 0.0271862429 0.0291446398 0.0447894074 0.0071062201 0.0886380000 9373005 955859216 1780088832 -1.0138051510 0.0138601307 0.7948950529 180 7.1600000000 0.0308517236 0.0291541236 0.0447894074 0.0070880128 0.0608390000 9374259 955859216 1781739520 -1.0118570328 0.0126791336 0.8072870970 181 7.2000000000 0.0326101407 0.0291732176 0.0447894074 0.0070720018 0.0891720000 9375513 955859216 1783517184 -1.0094701052 0.0116352076 0.8184012771 182 7.2400000000 0.0334272049 0.0291965911 0.0447894074 0.0070540812 0.1001530000 9376767 955859216 1785167872 -1.0091969967 0.0111456588 0.8315523863 183 7.2800000000 0.0255837571 0.0291768489 0.0447894074 0.0070452661 0.0801920000 9378021 955859216 1786818560 -1.0133359432 0.0193610974 0.8488386869 184 7.3200000000 0.0281970184 0.0291715237 0.0447894074 0.0070266776 0.0707620000 9379275 955859216 1785864192 -1.0105170012 0.0163995270 0.8593489528 185 7.3600000000 0.0300603863 0.0291763284 0.0447894074 0.0070107680 0.0546170000 9380529 955859216 1784979456 -1.0081403255 0.0149465874 0.8736820221 186 7.4000000000 0.0251648948 0.0291547615 0.0447894074 0.0069975739 0.0728940000 9381783 955859216 1783836672 -1.0099133253 0.0194755755 0.8928850889 187 7.4400000000 0.0256942678 0.0291362562 0.0447894074 0.0069908014 0.0734590000 9383037 955859216 1782804480 -1.0066654682 0.0190277267 0.9013057947 188 7.4800000000 0.0299728103 0.0291407060 0.0447894074 0.0070029076 0.0780920000 9384291 955859216 1784168448 -1.0030101538 0.0184143055 0.9159898758 189 7.5200000000 0.0248511583 0.0291180100 0.0447894074 0.0069873876 0.1091750000 9385545 955859216 1780883456 -1.0023629665 0.0261621680 0.9341148138 190 7.5600000000 0.0283415914 0.0291139235 0.0447894074 0.0069747029 0.0680410000 9386799 955859216 1782247424 -0.9989944100 0.0216423441 0.9481792450 191 7.6000000000 0.0244761743 0.0290896421 0.0447894074 0.0069620676 0.0791720000 9388053 955859216 1781399552 -0.9988859296 0.0277138669 0.9650294185 192 7.6400000000 0.0312584117 0.0291009378 0.0447894074 0.0069607724 0.0854060000 9389307 955859216 1780514816 -0.9934419394 0.0271574650 0.9794657230 193 7.6800000000 0.0242685061 0.0290758993 0.0447894074 0.0069677874 0.1013710000 9390561 955859216 1779482624 -0.9952771068 0.0344405696 0.9981005192 194 7.7200000000 0.0246354025 0.0290530101 0.0447894074 0.0069628854 0.0697080000 9391815 955859216 1778573312 -0.9954438210 0.0300137587 1.0141192675 195 7.7600000000 0.0246660300 0.0290305128 0.0447894074 0.0069652252 0.0696540000 9393069 955859216 1777467392 -0.9942318797 0.0297256466 1.0269998312 196 7.8000000000 0.0251538362 0.0290107338 0.0447894074 0.0070009812 0.0587700000 9394323 955859216 1776435200 -0.9922188520 0.0328545906 1.0435745716 197 7.8400000000 0.0250960458 0.0289908623 0.0447894074 0.0070252809 0.1130270000 9395577 955859216 1775415296 -0.9904613495 0.0364154577 1.0555180311 198 7.8800000000 0.0250445325 0.0289709314 0.0447894074 0.0070428816 0.1072410000 9396831 955859216 1774399488 -0.9893105626 0.0401594900 1.0719947815 199 7.9200000000 0.0243908241 0.0289479158 0.0447894074 0.0070352997 0.0810540000 9398085 955859216 1773404160 -0.9874492288 0.0418027788 1.0876941681 200 7.9600000000 0.0237476490 0.0289219144 0.0447894074 0.0070250663 0.0690550000 9399339 955859216 1772367872 -0.9875001311 0.0409193523 1.1016069651 201 8.0000000000 0.0237435177 0.0288961513 0.0447894074 0.0070396703 0.0848120000 9400593 955859216 1771499520 -0.9868320823 0.0413994826 1.1200935841 202 8.0400000000 0.0235052835 0.0288694638 0.0447894074 0.0070558483 0.0728040000 9401847 955859216 1770463232 -0.9841033220 0.0424933136 1.1306478977 203 8.0800000000 0.0238123257 0.0288445518 0.0447894074 0.0070647759 0.0650570000 9403101 955859216 1771843584 -0.9817476273 0.0440045185 1.1475843191 204 8.1200000000 0.0233083870 0.0288174137 0.0447894074 0.0070562385 0.0945190000 9404355 955859216 1771225088 -0.9799934626 0.0439737290 1.1601778269 205 8.1600000000 0.0243010130 0.0287953825 0.0447894074 0.0070480173 0.0652020000 9405609 955859216 1769811968 -0.9767708778 0.0419785082 1.1713664532 206 8.1999999990 0.0265086293 0.0287842818 0.0447894074 0.0070392088 0.0530960000 9406863 955859216 1769086976 -0.9728455544 0.0399521627 1.1841523647 207 8.2400000000 0.0301012136 0.0287906437 0.0447894074 0.0070334166 0.0541490000 9408117 955859216 1768054784 -0.9674605131 0.0394073948 1.1974526644 208 8.2799999990 0.0337080136 0.0288142849 0.0447894074 0.0070193846 0.0559080000 9409371 955859216 1769418752 -0.9623631835 0.0380217656 1.2099524736 209 8.3200000000 0.0375041179 0.0288558631 0.0447894074 0.0070138562 0.0722580000 9410625 955859216 1768833024 -0.9568693042 0.0361961238 1.2227214575 210 8.3599999990 0.0407828502 0.0289126583 0.0447894074 0.0070322722 0.0845290000 9411879 955859216 1767944192 -0.9504387379 0.0337521210 1.2343785763 211 8.4000000000 0.0417042971 0.0289732822 0.0447894074 0.0070486503 0.0577120000 9413133 955859216 1767034880 -0.9451197982 0.0310428068 1.2473456860 212 8.4399999990 0.0435999259 0.0290422758 0.0447894074 0.0070338624 0.0687980000 9414387 955859216 1766023168 -0.9374964237 0.0321253054 1.2594839334 213 8.4800000000 0.0478454418 0.0291305535 0.0478454418 0.0070315143 0.0568730000 9415641 955859216 1767387136 -0.9299761653 0.0318078101 1.2732278109 214 8.5200000000 0.0235136282 0.0291043062 0.0478454418 0.0071655643 0.0832110000 9416895 955859216 1766653952 -0.9291864634 0.0555585064 1.2874957323 215 8.5600000000 0.0281711426 0.0290999659 0.0478454418 0.0071698546 0.0649300000 9418149 955859216 1765785600 -0.9202060103 0.0504741110 1.2983707190 216 8.6000000000 0.0232328288 0.0290728032 0.0478454418 0.0071564722 0.0713190000 9419403 955859216 1765154816 -0.9121884108 0.0596619472 1.3096100092 217 8.6400000000 0.0261222087 0.0290592060 0.0478454418 0.0071748062 0.0769430000 9420657 955859216 1765146624 -0.9025529027 0.0598199330 1.3261226416 218 8.6800000000 0.0262016226 0.0290460979 0.0478454418 0.0072213316 0.0719570000 9421911 955859216 1765146624 -0.8940137625 0.0594965369 1.3357087374 219 8.7200000000 0.0325619690 0.0290621521 0.0478454418 0.0072174850 0.0901180000 9423165 955859216 1765257216 -0.8824007511 0.0560443550 1.3470075130 220 8.7600000000 0.0402552411 0.0291130297 0.0478454418 0.0072161298 0.0606450000 9424419 955859216 1766383616 -0.8699641228 0.0533641167 1.3588267565 221 8.8000000000 0.0449203774 0.0291845562 0.0478454418 0.0072449651 0.0758600000 9425673 955859216 1765134336 -0.8591125607 0.0499148630 1.3705643415 222 8.8400000000 0.0473979041 0.0292665983 0.0478454418 0.0072484784 0.0728560000 9426927 955859216 1765134336 -0.8492738008 0.0490983725 1.3842821121 223 8.8800000000 0.0500380732 0.0293597439 0.0500380732 0.0072468915 0.0939680000 9428181 955859216 1765097472 -0.8380544782 0.0496072508 1.3950266838 224 8.9200000000 0.0533159375 0.0294666912 0.0533159375 0.0072488185 0.0665300000 9429435 955859216 1765146624 -0.8265473843 0.0493322238 1.4058146477 225 8.9600000000 0.0544388406 0.0295776786 0.0544388406 0.0072443224 0.0975320000 9430689 955859216 1765146624 -0.8158932924 0.0508796312 1.4142760038 226 9.0000000000 0.0542926043 0.0296870366 0.0544388406 0.0072296663 0.1101690000 9431943 955859216 1765146624 -0.8056606650 0.0549153462 1.4250007868 227 9.0400000000 0.0308266189 0.0296920568 0.0544388406 0.0072566704 0.0682130000 9433197 955859216 1766510592 -0.7992880344 0.0837033540 1.4338767529 228 9.0800000000 0.0325494185 0.0297045891 0.0544388406 0.0072642203 0.0581120000 9434451 955859216 1768398848 -0.7874410152 0.0877963230 1.4475638866 229 9.1200000000 0.0307574831 0.0297091869 0.0544388406 0.0073233207 0.0638810000 9435705 955859216 1770049536 -0.7772703767 0.0935842991 1.4551271200 230 9.1600000000 0.0298779104 0.0297099205 0.0544388406 0.0074219515 0.0818790000 9436959 955859216 1771827200 -0.7666385770 0.0985630974 1.4619940519 231 9.2000000000 0.0292914864 0.0297081091 0.0544388406 0.0076279364 0.0729590000 9438213 955859216 1773477888 -0.7575098276 0.1001883373 1.4694626331 232 9.2400000000 0.0287292674 0.0297038899 0.0544388406 0.0077875230 0.0817660000 9439467 955859216 1775128576 -0.7481849790 0.1037032530 1.4778287411 233 9.2800000000 0.0278866161 0.0296960905 0.0544388406 0.0079280429 0.0803670000 9440721 955859216 1776906240 -0.7387847900 0.1074045077 1.4851849079 234 9.3200000000 0.0267443378 0.0296834761 0.0544388406 0.0080304365 0.0724510000 9441975 955859216 1778556928 -0.7291059494 0.1122773364 1.4921240807 235 9.3600000000 0.0253339838 0.0296649677 0.0544388406 0.0081072244 0.0621540000 9443229 955859216 1780334592 -0.7193922997 0.1170351282 1.4993889332 236 9.4000000000 0.0243109837 0.0296422813 0.0544388406 0.0081662580 0.0844190000 9444483 955859216 1781985280 -0.7102335691 0.1207646877 1.5079287291 237 9.4400000000 0.0240996554 0.0296188947 0.0544388406 0.0081934320 0.1016080000 9445737 955859216 1783635968 -0.7003540397 0.1251781732 1.5142441988 238 9.4800000000 0.0239269175 0.0295949788 0.0544388406 0.0082135415 0.0713700000 9446991 955859216 1785413632 -0.6895806193 0.1313283890 1.5219988823 239 9.5200000000 0.0237398911 0.0295704805 0.0544388406 0.0082554123 0.0760370000 9448245 955859216 1787191296 -0.6789265275 0.1367676556 1.5294373035 240 9.5600000000 0.0234772302 0.0295450920 0.0544388406 0.0083075531 0.0901050000 9449499 955859216 1786195968 -0.6688531041 0.1418141425 1.5381004810 241 9.6000000000 0.0235001687 0.0295200093 0.0544388406 0.0083591882 0.0726790000 9450753 955859216 1785810944 -0.6595619321 0.1426744163 1.5467954874 242 9.6400000000 0.0233755838 0.0294946191 0.0544388406 0.0083786818 0.0855380000 9452007 955859216 1785176064 -0.6498337984 0.1454259455 1.5553231239 243 9.6800000000 0.0228320546 0.0294672012 0.0544388406 0.0083922345 0.1220290000 9453261 955859216 1783382016 -0.6390504837 0.1519518346 1.5630480051 244 9.7200000000 0.0226610657 0.0294393072 0.0544388406 0.0084361225 0.0848390000 9454515 955859216 1782771712 -0.6278023124 0.1585500687 1.5711091757 245 9.7600000000 0.0258360617 0.0294246001 0.0544388406 0.0084911254 0.0527460000 9455769 955859216 1781374976 -0.6165975332 0.1580176800 1.5793211460 246 9.8000000000 0.0261890367 0.0294114474 0.0544388406 0.0085082944 0.0584570000 9457023 955859216 1780269056 -0.6061696410 0.1605174094 1.5880388021 247 9.8400000000 0.0252473280 0.0293945886 0.0544388406 0.0085128179 0.0722630000 9458277 955859216 1778454528 -0.5969817042 0.1616363227 1.5975476503 248 9.8800000000 0.0248770490 0.0293763727 0.0544388406 0.0084974347 0.0796370000 9459531 955859216 1776828416 -0.5877698660 0.1637417674 1.6058928967 249 9.9200000000 0.0242322404 0.0293557135 0.0544388406 0.0084813258 0.0731780000 9460785 955859216 1778454528 -0.5779573917 0.1666493714 1.6131805182 250 9.9600000000 0.0227067433 0.0293291176 0.0544388406 0.0084649591 0.0554750000 9462039 955859216 1779978240 -0.5687411427 0.1703594476 1.6228195429 251 10.0000000000 0.0225528572 0.0293021206 0.0544388406 0.0084484397 0.0641770000 9463293 955859216 1781612544 -0.5587185025 0.1735681742 1.6314599514 252 10.0400000000 0.0223662164 0.0292745972 0.0544388406 0.0084343843 0.0920820000 9464547 955859216 1783390208 -0.5502328873 0.1728400290 1.6417968273 253 10.0800000000 0.0220988709 0.0292462346 0.0544388406 0.0084186228 0.0657740000 9465801 955859216 1785040896 -0.5427179933 0.1699835658 1.6515951157 254 10.1200000000 0.0231705792 0.0292223147 0.0544388406 0.0084375833 0.0693420000 9467055 955859216 1786691584 -0.5327085853 0.1726791263 1.6595977545 255 10.1600000000 0.0233497564 0.0291992851 0.0544388406 0.0084530335 0.0493150000 9468309 955859216 1785708544 -0.5218034983 0.1794091910 1.6687403917 256 10.2000000000 0.0228353646 0.0291744260 0.0544388406 0.0084400820 0.0506920000 9469563 955859216 1785339904 -0.5107611418 0.1848143637 1.6775765419 257 10.2400000000 0.0225069765 0.0291484826 0.0544388406 0.0084254593 0.0534900000 9491297 955859216 1785692160 -0.5014865398 0.1848373264 1.6861449480 258 10.2800000000 0.0238919146 0.0291281083 0.0544388406 0.0084092340 0.0468530000 9534535 955859216 1784582144 -0.4908037484 0.1886035800 1.6949943304 259 10.3200000000 0.0245805234 0.0291105501 0.0544388406 0.0084016931 0.0902700000 9535789 955859216 1783549952 -0.4801802635 0.1917888820 1.7013347149 260 10.3600000000 0.0214324389 0.0290810189 0.0544388406 0.0084096844 0.0711470000 9537043 955859216 1782407168 -0.4710643589 0.1964699328 1.7099626064 261 10.4000000000 0.0230585653 0.0290579443 0.0544388406 0.0084073211 0.0492500000 9538297 955859216 1783771136 -0.4610628188 0.1943885684 1.7163296938 262 10.4400000000 0.0236976258 0.0290374851 0.0544388406 0.0083942097 0.0584380000 9539551 955859216 1783042048 -0.4513773024 0.1940366924 1.7234942913 263 10.4800000000 0.0234992951 0.0290164274 0.0544388406 0.0083800686 0.0857270000 9540805 955859216 1782026240 -0.4405955672 0.1957426518 1.7297228575 264 10.5200000000 0.0232460834 0.0289945700 0.0544388406 0.0083691519 0.0651980000 9542059 955859216 1780883456 -0.4303295910 0.1956641227 1.7358083725 265 10.5600000000 0.0227669794 0.0289710697 0.0544388406 0.0083535662 0.0854200000 9543313 955859216 1779867648 -0.4191914201 0.1980396658 1.7425460815 266 10.6000000000 0.0212716032 0.0289421243 0.0544388406 0.0083431444 0.0825470000 9544567 955859216 1781248000 -0.4076558948 0.2017985731 1.7466093302 267 10.6400000000 0.0210966971 0.0289127407 0.0544388406 0.0083391701 0.1125190000 9545821 955859216 1778122752 -0.3964578211 0.2010491490 1.7506999969 268 10.6800000000 0.0220348034 0.0288870767 0.0544388406 0.0083313091 0.0630270000 9547075 955859216 1779486720 -0.3847845793 0.1996692866 1.7573585510 269 10.7200000000 0.0218870956 0.0288610545 0.0544388406 0.0083196524 0.0708970000 9548329 955859216 1778614272 -0.3728769422 0.1997679919 1.7601580620 270 10.7600000000 0.0207111724 0.0288308697 0.0544388406 0.0083113484 0.0637040000 9549583 955859216 1777729536 -0.3479502201 0.2055275738 1.7698334455 271 10.8000000000 0.0206434075 0.0288006577 0.0544388406 0.0083272677 0.0701220000 9550837 955859216 1776697344 -0.3336392939 0.2093383968 1.7731623650 272 10.8400000000 0.0205194000 0.0287702119 0.0544388406 0.0083875798 0.0790880000 9552091 955859216 1775566848 -0.3216942847 0.2076255828 1.7769840956 273 10.8800000000 0.0204545762 0.0287397517 0.0544388406 0.0083953424 0.0914600000 9553345 955859216 1774534656 -0.3091032207 0.2084194124 1.7815289497 274 10.9200000000 0.0203686375 0.0287092002 0.0544388406 0.0084032776 0.0666240000 9554599 955859216 1775915008 -0.2958539426 0.2097208053 1.7852554321 275 10.9600000000 0.0203133505 0.0286786698 0.0544388406 0.0084081732 0.0889830000 9555853 955859216 1775263744 -0.2829605043 0.2097781301 1.7880839109 276 11.0000000000 0.0201960076 0.0286479355 0.0544388406 0.0084049511 0.0550940000 9557107 955859216 1774170112 -0.2695256472 0.2117701918 1.7919553518 277 11.0400000000 0.0200166628 0.0286167757 0.0544388406 0.0084103667 0.1152360000 9558361 955859216 1773285376 -0.2560275495 0.2134043425 1.7952556610 278 11.0800000000 0.0199244507 0.0285855084 0.0544388406 0.0084154113 0.0657260000 9559615 955859216 1772253184 -0.2424538136 0.2152785063 1.7989001274 279 11.1200000000 0.0198144540 0.0285540709 0.0544388406 0.0084246508 0.0706650000 9560869 955859216 1771257856 -0.2285422534 0.2171503454 1.8027099371 280 11.1600000000 0.0197159592 0.0285225062 0.0544388406 0.0084324679 0.0900470000 9562123 955859216 1770364928 -0.2145600319 0.2197573036 1.8059501648 281 11.2000000000 0.0196661092 0.0284909888 0.0544388406 0.0084380842 0.0665100000 9563377 955859216 1771724800 -0.2014052719 0.2206810564 1.8088228703 282 11.2400000000 0.0196106825 0.0284594983 0.0544388406 0.0084330409 0.0863370000 9564631 955859216 1771126784 -0.1895615011 0.2197671384 1.8134033680 283 11.2800000000 0.0203160327 0.0284307228 0.0544388406 0.0084182615 0.0645960000 9565885 955859216 1770090496 -0.1768957525 0.2205834240 1.8166686296 284 11.3200000000 0.0195180625 0.0283993402 0.0544388406 0.0084073005 0.0887280000 9567139 955859216 1769074688 -0.1646814644 0.2233489454 1.8214659691 285 11.3600000000 0.0192318428 0.0283671736 0.0544388406 0.0084044364 0.1014380000 9568393 955859216 1768206336 -0.1531777382 0.2247183025 1.8256992102 286 11.4000000000 0.0190147497 0.0283344728 0.0544388406 0.0083958371 0.0851400000 9569647 955859216 1767190528 -0.1427004337 0.2249435037 1.8297230005 287 11.4400000000 0.0188931935 0.0283015763 0.0544388406 0.0083812922 0.0684970000 9570901 955859216 1766301696 -0.1332181394 0.2246799320 1.8338549137 288 11.4800000000 0.0187785160 0.0282685102 0.0544388406 0.0083674611 0.0820150000 9572155 955859216 1765265408 -0.1243687496 0.2247190922 1.8378906250 289 11.5200000000 0.0186742507 0.0282353120 0.0544388406 0.0083540790 0.0698400000 9573409 955859216 1765171200 -0.1158756688 0.2246933728 1.8443636894 290 11.5600000000 0.0185850076 0.0282020351 0.0544388406 0.0083449633 0.0843030000 9574663 955859216 1765171200 -0.1075794846 0.2252220213 1.8501993418 291 11.6000000000 0.0184370745 0.0281684786 0.0544388406 0.0083336807 0.0912040000 9575917 955859216 1765171200 -0.1000844464 0.2244428545 1.8572345972 292 11.6400000000 0.0182921495 0.0281346555 0.0544388406 0.0083210088 0.0686080000 9577171 955859216 1766535168 -0.0920819938 0.2256178111 1.8630529642 293 11.6800000000 0.0182165764 0.0281008054 0.0544388406 0.0083068073 0.0767770000 9578425 955859216 1766154240 -0.0851335675 0.2259484380 1.8698381186 294 11.7200000000 0.0181575920 0.0280669850 0.0544388406 0.0082939371 0.0843270000 9579679 955859216 1765285888 -0.0790406615 0.2252577841 1.8770166636 295 11.7600000000 0.0184707399 0.0280344553 0.0544388406 0.0082852402 0.0858510000 9580933 955859216 1765171200 -0.0733597949 0.2248854637 1.8837064505 296 11.8000000000 0.0190196726 0.0280040000 0.0544388406 0.0082760796 0.0889820000 9582187 955859216 1765105664 -0.0674671307 0.2244690657 1.8898060322 297 11.8400000000 0.0194321219 0.0279751384 0.0544388406 0.0082672571 0.0639520000 9583441 955859216 1765138432 -0.0625835210 0.2235361040 1.8968145847 298 11.8800000000 0.0200103372 0.0279484109 0.0544388406 0.0082618956 0.0757090000 9584695 955859216 1765138432 -0.0576824211 0.2222675085 1.9040676355 299 11.9200000000 0.0178009458 0.0279144729 0.0544388406 0.0082520157 0.0660360000 9585949 955859216 1765154816 -0.0528581589 0.2247055918 1.9140290022 300 11.9600000000 0.0194810703 0.0278863615 0.0544388406 0.0082397125 0.1059660000 9587203 955859216 1765154816 -0.0477473922 0.2237006277 1.9210795164 301 12.0000000000 0.0179121830 0.0278532247 0.0544388406 0.0082262464 0.0716010000 9588457 955859216 1765629952 -0.0432867445 0.2256858647 1.9312678576 302 12.0400000000 0.0176735688 0.0278195173 0.0544388406 0.0082149714 0.0637970000 9589711 955859216 1765150720 -0.0393666103 0.2257627994 1.9411962032 303 12.0800000000 0.0175165124 0.0277855140 0.0544388406 0.0082084150 0.0630480000 9590965 955859216 1765154816 -0.0352224968 0.2262511402 1.9511044025 304 12.1200000000 0.0173074733 0.0277510467 0.0544388406 0.0082062014 0.0913510000 9592219 955859216 1765154816 -0.0313841216 0.2266986519 1.9613318443 305 12.1600000000 0.0170910284 0.0277160958 0.0544388406 0.0082024674 0.0919080000 9593473 955859216 1765154816 -0.0277724899 0.2268535644 1.9726848602 306 12.2000000000 0.0168695208 0.0276806495 0.0544388406 0.0081950510 0.0672240000 9594727 955859216 1766518784 -0.0242328085 0.2270546556 1.9842194319 307 12.2400000000 0.0167173371 0.0276449384 0.0544388406 0.0081960659 0.1004510000 9595981 955859216 1765281792 -0.0210308805 0.2279175371 1.9957135916 308 12.2800000000 0.0166101828 0.0276091113 0.0544388406 0.0081989465 0.0716330000 9597235 955859216 1766645760 -0.0184516702 0.2281529605 2.0073273182 309 12.3200000000 0.0162519999 0.0275723569 0.0544388406 0.0082093555 0.0660110000 9598489 955859216 1765924864 -0.0166046247 0.2281845808 2.0184082985 310 12.3600000000 0.0160695780 0.0275352511 0.0544388406 0.0082270337 0.0677780000 9599743 955859216 1765142528 -0.0150038404 0.2278444022 2.0303208828 311 12.4000000000 0.0159052331 0.0274978556 0.0544388406 0.0082397680 0.0673870000 9600997 955859216 1765154816 -0.0128521146 0.2288338840 2.0410807133 312 12.4400000000 0.0155448401 0.0274595446 0.0544388406 0.0082743123 0.0734950000 9602251 955859216 1765154816 -0.0106368875 0.2289569825 2.0650300980 313 12.4800000000 0.0153095648 0.0274207268 0.0544388406 0.0082674686 0.0697400000 9603505 955859216 1766629376 -0.0101039764 0.2289980948 2.0756664276 314 12.5200000000 0.0150913065 0.0273814611 0.0544388406 0.0082590026 0.0802600000 9604759 955859216 1766141952 -0.0101092765 0.2281047255 2.0882632732 315 12.5600000000 0.0147348046 0.0273413130 0.0544388406 0.0082577782 0.0700030000 9606013 955859216 1765277696 -0.0097523537 0.2287321240 2.0997443199 316 12.6000000000 0.0144222472 0.0273004299 0.0544388406 0.0082468030 0.0687960000 9607267 955859216 1765167104 -0.0096408194 0.2293588072 2.1120312214 317 12.6400000000 0.0139741246 0.0272583911 0.0544388406 0.0082338198 0.0704920000 9608521 955859216 1765154816 -0.0100194002 0.2292208076 2.1237382889 318 12.6800000000 0.0138802705 0.0272163215 0.0544388406 0.0082208354 0.0694860000 9609775 955859216 1765134336 -0.0106859645 0.2288441062 2.1350069046 319 12.7200000000 0.0135859046 0.0271735929 0.0544388406 0.0082079282 0.0895010000 9611029 955859216 1765154816 -0.0114694275 0.2293532342 2.1450707912 320 12.7600000000 0.0133057181 0.0271302558 0.0544388406 0.0081950917 0.0682090000 9612283 955859216 1766518784 -0.0127167581 0.2298600078 2.1553387642 321 12.8000000000 0.0130310375 0.0270863330 0.0544388406 0.0081851841 0.0700130000 9613537 955859216 1765900288 -0.0148961786 0.2290809453 2.1659047604 322 12.8400000000 0.0127407564 0.0270417815 0.0544388406 0.0081750251 0.0683690000 9614791 955859216 1765142528 -0.0165661611 0.2297834754 2.1751687527 323 12.8800000000 0.0124439225 0.0269965869 0.0544388406 0.0081666227 0.0692790000 9616045 955859216 1765154816 -0.0185658056 0.2290534675 2.1837790012 324 12.9200000000 0.0121529587 0.0269507733 0.0544388406 0.0081553643 0.0685310000 9617299 955859216 1766518784 -0.0205921680 0.2288043350 2.1928858757 325 12.9600000000 0.0118838055 0.0269044134 0.0544388406 0.0081430926 0.0682080000 9618553 955859216 1766133760 -0.0220105648 0.2300225645 2.2018120289 326 13.0000000000 0.0116593996 0.0268576495 0.0544388406 0.0081315535 0.0688430000 9619807 955859216 1765158912 -0.0239975844 0.2300054431 2.2089300156 327 13.0400000000 0.0113948043 0.0268103625 0.0544388406 0.0081210628 0.0782400000 9621061 955859216 1765154816 -0.0260333512 0.2307749987 2.2185308933 328 13.0800000000 0.0111791780 0.0267627065 0.0544388406 0.0081094314 0.1093970000 9622315 955859216 1765154816 -0.0266149733 0.2338010371 2.2247989178 329 13.1200000000 0.0109668560 0.0267146948 0.0544388406 0.0080980878 0.0805140000 9623569 955859216 1765154816 -0.0282688513 0.2349449694 2.2338411808 330 13.1600000000 0.0107871210 0.0266664294 0.0544388406 0.0080874978 0.1055590000 9624823 955859216 1765154816 -0.0302060060 0.2355541140 2.2420418262 331 13.2000000000 0.0106576607 0.0266180645 0.0544388406 0.0080758226 0.0900190000 9626077 955859216 1765154816 -0.0319854096 0.2365057170 2.2522788048 332 13.2400000000 0.0106116422 0.0265698524 0.0544388406 0.0080650427 0.0694940000 9627331 955859216 1765154816 -0.0338560715 0.2372783124 2.2612035275 333 13.2800000000 0.0104988003 0.0265215910 0.0544388406 0.0080533760 0.0865030000 9628585 955859216 1765154816 -0.0360155702 0.2378750592 2.2710828781 334 13.3200000000 0.0104233501 0.0264733927 0.0544388406 0.0080424599 0.1136570000 9629839 955859216 1765154816 -0.0383317433 0.2381086051 2.2795746326 335 13.3600000000 0.0103047751 0.0264251282 0.0544388406 0.0080304724 0.0881690000 9631093 955859216 1765376000 -0.0404390357 0.2393414080 2.2884712219 336 13.4000000000 0.0101731904 0.0263767593 0.0544388406 0.0080185492 0.0696690000 9632347 955859216 1765376000 -0.0419571474 0.2414819598 2.2964303493 337 13.4400000000 0.0100450162 0.0263282971 0.0544388406 0.0080180513 0.0873180000 9633601 955859216 1765171200 -0.0436869971 0.2440928668 2.3039844036 338 13.4800000000 0.0098986076 0.0262796886 0.0544388406 0.0080255155 0.0898010000 9634855 955859216 1765171200 -0.0455307364 0.2459466606 2.3103041649 339 13.5200000000 0.0097963512 0.0262310652 0.0544388406 0.0080430900 0.0812610000 9636109 955859216 1765105664 -0.0479673967 0.2461332679 2.3159146309 340 13.5600000000 0.0097205127 0.0261825047 0.0544388406 0.0080399264 0.0840740000 9637363 955859216 1765138432 -0.0503534824 0.2466882169 2.3210268021 341 13.6000000000 0.0096741160 0.0261340930 0.0544388406 0.0080334860 0.0910830000 9638617 955859216 1765146624 -0.0525199324 0.2472673357 2.3258628845 342 13.6400000000 0.0095886262 0.0260857145 0.0544388406 0.0080256760 0.0820140000 9639871 955859216 1765146624 -0.0546554662 0.2477694899 2.3315658569 343 13.6800000000 0.0095252488 0.0260374332 0.0544388406 0.0080141271 0.0860280000 9641125 955859216 1765146624 -0.0566344932 0.2481788695 2.3364350796 344 13.7200000000 0.0094881840 0.0259893250 0.0544388406 0.0080025149 0.0900720000 9642379 955859216 1765146624 -0.0577320009 0.2499208748 2.3419773579 345 13.7600000000 0.0094218701 0.0259413033 0.0544388406 0.0079949416 0.0834390000 9643633 955859216 1765146624 -0.0596587472 0.2499145865 2.3474981785 346 13.8000000000 0.0093690995 0.0258934068 0.0544388406 0.0079897163 0.0886900000 9644887 955859216 1765146624 -0.0613328330 0.2498915344 2.3525652885 347 13.8400000000 0.0093070231 0.0258456074 0.0544388406 0.0079788081 0.0719520000 9646141 955859216 1765146624 -0.0636676922 0.2486499399 2.3571200371 348 13.8800000000 0.0092488360 0.0257979156 0.0544388406 0.0079681320 0.0755410000 9647395 955859216 1765163008 -0.0642561316 0.2509402037 2.3628866673 349 13.9200000000 0.0091546578 0.0257502271 0.0544388406 0.0079659140 0.0815950000 9648649 955859216 1765146624 -0.0659269840 0.2507604659 2.3686614037 350 13.9600000000 0.0090804826 0.0257025993 0.0544388406 0.0079569473 0.0885090000 9649903 955859216 1765130240 -0.0679434910 0.2494715452 2.3774900436 351 14.0000000000 0.0090774149 0.0256552341 0.0544388406 0.0079463743 0.1069100000 9651157 955859216 1765130240 -0.0680249780 0.2501945794 2.3817830086 352 14.0400000000 0.0092813931 0.0256087175 0.0544388406 0.0079375488 0.1020300000 9652411 955859216 1765171200 -0.0686987862 0.2496255934 2.3867080212 353 14.0800000000 0.0092342505 0.0255623309 0.0544388406 0.0079262772 0.1158020000 9653665 955859216 1765171200 -0.0690698549 0.2487178445 2.3909852505 354 14.1200000000 0.0090165222 0.0255155913 0.0544388406 0.0079151465 0.0873410000 9654919 955859216 1765171200 -0.0687032640 0.2494948059 2.3956174850 355 14.1600000000 0.0091915177 0.0254696080 0.0544388406 0.0079042597 0.0794470000 9656173 955859216 1765171200 -0.0693480298 0.2479364872 2.4006214142 356 14.2000000000 0.0089769075 0.0254232802 0.0544388406 0.0078949498 0.0877780000 9657427 955859216 1765171200 -0.0689967498 0.2480237782 2.4050834179 357 14.2400000000 0.0089538954 0.0253771475 0.0544388406 0.0078843154 0.0841770000 9658681 955859216 1765154816 -0.0686733201 0.2485515177 2.4107046127 358 14.2800000000 0.0090647927 0.0253315823 0.0544388406 0.0078741628 0.0864760000 9659935 955859216 1765154816 -0.0690739900 0.2470973134 2.4162967205 359 14.3200000000 0.0089756073 0.0252860224 0.0544388406 0.0078644617 0.0908290000 9661189 955859216 1765138432 -0.0696957409 0.2454434335 2.4217510223 360 14.3600000000 0.0090047466 0.0252407967 0.0544388406 0.0078559250 0.0698150000 9662443 955859216 1766629376 -0.0698775128 0.2441295832 2.4279136658 361 14.4000000000 0.0089880796 0.0251957753 0.0544388406 0.0078514977 0.0857600000 9663697 955859216 1766260736 -0.0700180084 0.2440253496 2.4343914986 362 14.4400000000 0.0089377416 0.0251508636 0.0544388406 0.0078446866 0.0886120000 9664951 955859216 1765113856 -0.0700520128 0.2443159819 2.4409458637 363 14.4800000000 0.0089239040 0.0251061612 0.0544388406 0.0078342033 0.0813640000 9666205 955859216 1764868096 -0.0699537471 0.2452107370 2.4481348991 364 14.5200000000 0.0085306242 0.0250606240 0.0544388406 0.0078245979 0.0706870000 9667459 955859216 1764995072 -0.0702327639 0.2448946089 2.4549992085 365 14.5600000000 0.0086212726 0.0250155847 0.0544388406 0.0078139573 0.0808170000 9668713 955859216 1764884480 -0.0708627179 0.2440936565 2.4623143673 366 14.6000000000 0.0087035494 0.0249710163 0.0544388406 0.0078035575 0.0839210000 9669967 955859216 1765011456 -0.0710428432 0.2448171675 2.4702258110 367 14.6400000000 0.0081993863 0.0249253171 0.0544388406 0.0077933183 0.1077760000 9671221 955859216 1765138432 -0.0708705857 0.2460310310 2.4768109322 368 14.6800000000 0.0082160477 0.0248799114 0.0544388406 0.0077838129 0.0864240000 9672475 955859216 1764732928 -0.0711386576 0.2468603849 2.4848697186 369 14.7200000000 0.0082958778 0.0248349682 0.0544388406 0.0077827723 0.0869990000 9673729 955859216 1764851712 -0.0719964430 0.2465949804 2.4924902916 370 14.7600000000 0.0082457913 0.0247901326 0.0544388406 0.0077803077 0.0895900000 9674983 955859216 1765138432 -0.0722322464 0.2470509410 2.5003912449 371 14.8000000000 0.0082031479 0.0247454238 0.0544388406 0.0077738557 0.1060720000 9676237 955859216 1765023744 -0.0723180026 0.2468303740 2.5076386929 372 14.8400000000 0.0081639290 0.0247008499 0.0544388406 0.0077696403 0.0888540000 9677491 955859216 1766387712 -0.0725514218 0.2463985085 2.5146856308 373 14.8800000000 0.0081309266 0.0246564265 0.0544388406 0.0077693093 0.0854520000 9678745 955859216 1768280064 -0.0727087930 0.2462646067 2.5220348835 374 14.9200000000 0.0080924481 0.0246121378 0.0544388406 0.0077652922 0.0903600000 9679999 955859216 1769930752 -0.0729107484 0.2456338406 2.5293810368 375 14.9600000000 0.0080618421 0.0245680037 0.0544388406 0.0077682162 0.0901790000 9681253 955859216 1771581440 -0.0726805031 0.2452571988 2.5363652706 376 15.0000000000 0.0080225272 0.0245239997 0.0544388406 0.0077677610 0.0908040000 9682507 955859216 1773359104 -0.0717158243 0.2466006875 2.5437674522 377 15.0400000000 0.0079715215 0.0244800939 0.0544388406 0.0077602673 0.1109800000 9683761 955859216 1775009792 -0.0694680661 0.2477849573 2.5569705963 378 15.0800000000 0.0078933183 0.0244362136 0.0544388406 0.0077500307 0.0819470000 9685015 955859216 1776787456 -0.0675332919 0.2490346283 2.5634274483 379 15.1200000000 0.0078178402 0.0243923656 0.0544388406 0.0077398180 0.0938010000 9686269 955859216 1778438144 -0.0656490698 0.2496014833 2.5690813065 380 15.1600000000 0.0077691013 0.0243486202 0.0544388406 0.0077307480 0.1288150000 9687523 955859216 1780215808 -0.0628950894 0.2507529259 2.5744340420 381 15.2000000000 0.0077501577 0.0243050547 0.0544388406 0.0077208148 0.1109760000 9688777 955859216 1781866496 -0.0605419129 0.2517853677 2.5795290470 382 15.2400000000 0.0077173598 0.0242616314 0.0544388406 0.0077121679 0.0891460000 9690031 955859216 1783517184 -0.0583194718 0.2522690296 2.5843331814 383 15.2800000000 0.0076710014 0.0242183138 0.0544388406 0.0077028083 0.0992550000 9691285 955859216 1785294848 -0.0556469187 0.2533212006 2.5888447762 384 15.3200000000 0.0076235156 0.0241750982 0.0544388406 0.0076927820 0.0925190000 9692539 955859216 1786945536 -0.0528324842 0.2540414929 2.5926532745 385 15.3600000000 0.0075996779 0.0241320452 0.0544388406 0.0076834874 0.1057450000 9693793 955859216 1784713216 -0.0503225476 0.2536543608 2.5952258110 386 15.4000000000 0.0075563043 0.0240891028 0.0544388406 0.0076799058 0.0924650000 9695047 955859216 1783566336 -0.0472696424 0.2543455958 2.5973575115 387 15.4400000000 0.0075040385 0.0240462474 0.0544388406 0.0076797997 0.1063530000 9696301 955859216 1782517760 -0.0435761921 0.2565032244 2.5994875431 388 15.4800000000 0.0074447826 0.0240034601 0.0544388406 0.0076702300 0.1080530000 9697555 955859216 1781407744 -0.0405467153 0.2577922642 2.6003854275 389 15.5200000000 0.0074029737 0.0239607853 0.0544388406 0.0076608261 0.0919610000 9698809 955859216 1780375552 -0.0379220322 0.2579597533 2.6013669968 390 15.5600000000 0.0073190844 0.0239181143 0.0544388406 0.0076510518 0.1062940000 9700063 955859216 1779359744 -0.0340533257 0.2610708475 2.6025254726 391 15.6000000000 0.0072912253 0.0238755903 0.0544388406 0.0076560907 0.1082630000 9701317 955859216 1778233344 -0.0308691002 0.2614266574 2.6038641930 392 15.6400000000 0.0071877665 0.0238330193 0.0544388406 0.0076469144 0.1087720000 9702571 955859216 1777201152 -0.0280327555 0.2612252533 2.6041984558 393 15.6800000000 0.0069668381 0.0237901028 0.0544388406 0.0076378684 0.0912080000 9703825 955859216 1776074752 -0.0258723907 0.2596966326 2.6045305729 394 15.7200000000 0.0066024661 0.0237464794 0.0544388406 0.0076303234 0.1060320000 9705079 955859216 1775042560 -0.0239019897 0.2578026354 2.6049623489 395 15.7600000000 0.0071977517 0.0237045839 0.0544388406 0.0076340524 0.1302250000 9706333 955859216 1774026752 -0.0206181519 0.2580694854 2.6063964367 396 15.8000000000 0.0082842810 0.0236656437 0.0544388406 0.0076281394 0.0946730000 9707587 955859216 1772982272 -0.0170589965 0.2581860721 2.6081783772 397 15.8400000000 0.0376431048 0.0237008514 0.0544388406 0.0077483168 0.1019030000 9708841 955859216 1771995136 -0.0150355734 0.2577745020 2.6392731667 398 15.8800000000 0.0666726530 0.0238088208 0.0666726530 0.0078516465 0.0906700000 9710095 955859216 1771106304 -0.0126805874 0.2559373677 2.6679131985 399 15.9200000000 0.1065504253 0.0240161932 0.1065504253 0.0080800604 0.1066090000 9711349 955859216 1770110976 -0.0090582743 0.2580977082 2.7064249516 400 15.9600000000 0.1053906232 0.0242196293 0.1065504253 0.0080735871 0.1236380000 9712603 955859216 1769222144 -0.0047474839 0.2589049935 2.7057757378 401 16.0000000000 0.1033762023 0.0244170272 0.1065504253 0.0080692302 0.0910240000 9713857 955859216 1768185856 -0.0001713857 0.2594925463 2.7044167519 402 16.0400000000 0.1023630574 0.0246109228 0.1065504253 0.0080616866 0.0891680000 9715111 955859216 1767170048 0.0054079727 0.2600292861 2.7036936283 403 16.0800000000 0.1018082798 0.0248024795 0.1065504253 0.0080569393 0.1016200000 9716365 955859216 1766154240 0.0100554498 0.2595311701 2.7047796249 404 16.1200000000 0.1012544185 0.0249917170 0.1065504253 0.0080487611 0.0911450000 9717619 955859216 1765285888 0.0150174825 0.2599490285 2.7033629417 405 16.1600000000 0.1007707864 0.0251788258 0.1065504253 0.0080407613 0.1029600000 9718873 955859216 1765105664 0.0204179808 0.2603693604 2.7044363022 406 16.2000000000 0.1005069241 0.0253643630 0.1065504253 0.0080324927 0.0905060000 9720127 955859216 1766502400 0.0262913108 0.2620097697 2.7068102360 407 16.2400000000 0.1000787988 0.0255479366 0.1065504253 0.0080251402 0.0890460000 9721381 955859216 1768280064 0.0313842110 0.2627585232 2.7083942890 408 16.2800000000 0.0998525620 0.0257300557 0.1065504253 0.0080269538 0.0899820000 9722635 955859216 1770057728 0.0366409980 0.2632685006 2.7110433578 409 16.3200000000 0.0996047482 0.0259106784 0.1065504253 0.0080295810 0.1089050000 9723889 955859216 1771708416 0.0432565138 0.2667473257 2.7134208679 410 16.3600000000 0.0994164646 0.0260899609 0.1065504253 0.0080214568 0.0891150000 9725143 955859216 1773359104 0.0493585877 0.2697800398 2.7176380157 411 16.3999999990 0.0993094519 0.0262681105 0.1065504253 0.0080163008 0.0887620000 9726397 955859216 1775136768 0.0527809598 0.2683741450 2.7192049026 412 16.4400000000 0.0991723463 0.0264450625 0.1065504253 0.0080317959 0.0889810000 9727651 955859216 1776787456 0.0578763485 0.2681901753 2.7253232002 413 16.4800000000 0.0989905670 0.0266207175 0.1065504253 0.0080458633 0.1097220000 9728905 955859216 1778438144 0.0640148520 0.2695344985 2.7319302559 414 16.5200000000 0.0989174619 0.0267953473 0.1065504253 0.0080424445 0.0874680000 9730159 955859216 1780215808 0.0687657818 0.2673737705 2.7354118824 415 16.5599999990 0.0988320038 0.0269689296 0.1065504253 0.0080561151 0.0878310000 9731413 955859216 1781866496 0.0718340054 0.2615036368 2.7409060001 416 16.6000000000 0.0985250846 0.0271409396 0.1065504253 0.0081324374 0.1244590000 9732667 955859216 1783644160 0.0780609921 0.2613914013 2.7462859154 417 16.6400000000 0.0981484428 0.0273112214 0.1065504253 0.0081622463 0.0865480000 9733921 955859216 1785294848 0.0842715874 0.2627252042 2.7475121021 418 16.6800000000 0.0978777111 0.0274800407 0.1065504253 0.0081653275 0.0861140000 9735175 955859216 1786945536 0.0864220262 0.2590692043 2.7466487885 419 16.7199999990 0.0974910036 0.0276471313 0.1065504253 0.0081932189 0.1104600000 9736429 955859216 1784713216 0.0940383673 0.2616816759 2.7519092560 420 16.7600000000 0.0966003612 0.0278113057 0.1065504253 0.0081839287 0.0965930000 9737683 955859216 1783676928 0.1013426930 0.2620238066 2.7508881092 421 16.8000000000 0.0963163376 0.0279740255 0.1065504253 0.0081949566 0.0816080000 9738937 955859216 1782550528 0.1052459031 0.2562422156 2.7514841557 422 16.8400000000 0.2103492916 0.0284061943 0.2103492916 0.0087031548 0.1072660000 9740191 955859216 1781407744 0.1114484593 0.4126239121 2.7986257076 423 16.8799999990 0.2954979241 0.0290376169 0.2954979241 0.0088250889 0.0844050000 9741445 955859216 1780375552 0.1196275577 0.5023655295 2.8199338913 424 16.9200000000 0.3939609230 0.0298982850 0.3939609230 0.0090139969 0.1188610000 9742699 955859216 1779380224 0.1223601177 0.6022878885 2.8367545605 425 16.9600000000 0.4351308346 0.0308517734 0.4351308346 0.0090496265 0.0856600000 9743953 955859216 1778343936 0.1322029233 0.6444389820 2.8432960510 426 17.0000000000 0.4606616199 0.0318607167 0.4606616199 0.0090449146 0.0836920000 9745207 955859216 1777217536 0.1409378350 0.6711045504 2.8458197117 427 17.0400000000 0.4752162695 0.0328990201 0.4752162695 0.0090361049 0.1064470000 9746461 955859216 1776185344 0.1462733895 0.6815989017 2.8452122211 428 17.0800000000 0.4802996516 0.0339443487 0.4802996516 0.0090257491 0.0887100000 9747715 955859216 1775169536 0.1565091461 0.6844794750 2.8438847065 429 17.1200000000 0.4794126749 0.0349827364 0.4802996516 0.0090161841 0.1098140000 9748969 955859216 1774153728 0.1691192538 0.6818062663 2.8434937000 430 17.1600000000 0.4749610126 0.0360059417 0.4802996516 0.0090100739 0.0891970000 9750223 955859216 1773137920 0.1794188321 0.6724356413 2.8381469250 431 17.2000000000 0.4728690386 0.0370195452 0.4802996516 0.0090010688 0.0870710000 9751477 955859216 1772122112 0.1915101260 0.6650175452 2.8362667561 432 17.2400000000 0.4694608152 0.0380205666 0.4802996516 0.0090024084 0.0869830000 9752731 955859216 1773502464 0.2066884488 0.6592782140 2.8325564861 433 17.2800000000 0.4688484371 0.0390155501 0.4802996516 0.0089959551 0.0875950000 9753985 955859216 1772724224 0.2205807269 0.6564888358 2.8282272816 434 17.3200000000 0.4788806736 0.0400290643 0.4802996516 0.0089867380 0.1133950000 9755239 955859216 1769734144 0.2283027470 0.6618002057 2.8222143650 435 17.3600000000 0.4733364880 0.0410251733 0.4802996516 0.0089998786 0.1268080000 9756493 955859216 1768833024 0.2407796830 0.6548320651 2.8166434765 436 17.4000000000 0.4697827399 0.0420085622 0.4802996516 0.0090096177 0.0801260000 9757747 955859216 1767796736 0.2565017939 0.6553229094 2.8084325790 437 17.4400000000 0.4682442248 0.0429839298 0.4802996516 0.0090005102 0.0775410000 9759001 955859216 1766780928 0.2728819549 0.6597874165 2.7985453606 438 17.4800000000 0.4674655497 0.0439530660 0.4802996516 0.0090637173 0.1015010000 9760255 955859216 1765765120 0.2859777510 0.6602000594 2.7904171944 439 17.5200000000 0.4721004963 0.0449283448 0.4802996516 0.0091557835 0.0887570000 9761509 955859216 1765154816 0.2897244394 0.6591624618 2.7811434269 440 17.5600000000 0.4624844790 0.0458773361 0.4802996516 0.0091747016 0.0807280000 9762763 955859216 1765146624 0.2974227965 0.6392244101 2.7739093304 441 17.6000000000 0.4600118995 0.0468164167 0.4802996516 0.0091729097 0.0805060000 9764017 955859216 1765146624 0.3021537364 0.6291700602 2.7670998573 442 17.6400000000 0.4567868114 0.0477439515 0.4802996516 0.0092311651 0.0669740000 9765271 955859216 1766494208 0.3134698868 0.6268404126 2.7573494911 443 17.6800000000 0.4524827003 0.0486575830 0.4802996516 0.0092697421 0.0825870000 9766525 955859216 1766293504 0.3373740017 0.6267656088 2.7387177944 444 17.7200000000 0.4507233799 0.0495631366 0.4802996516 0.0092610963 0.0918060000 9767779 955859216 1765257216 0.3490113020 0.6235738397 2.7287828922 445 17.7600000000 0.4475731552 0.0504575412 0.4802996516 0.0092536235 0.0864650000 9769033 955859216 1765163008 0.3543552756 0.6177740097 2.7196857929 446 17.8000000000 0.4445445538 0.0513411443 0.4802996516 0.0092445424 0.0708480000 9770287 955859216 1765163008 0.3638711572 0.6146829128 2.7102825642 447 17.8400000000 0.4423910975 0.0522159764 0.4802996516 0.0092366525 0.0870990000 9771541 955859216 1765163008 0.3714199662 0.6089599133 2.7031133175 448 17.8800000000 0.4409490228 0.0530836841 0.4802996516 0.0092275727 0.0883740000 9772795 955859216 1765163008 0.3786925375 0.6052912474 2.6959562302 449 17.9200000000 0.4380895495 0.0539411582 0.4802996516 0.0092201623 0.1096530000 9774049 955859216 1765146624 0.3825025856 0.6006880403 2.6865983009 450 17.9600000000 0.4378395379 0.0547942657 0.4802996516 0.0092133690 0.0844690000 9775303 955859216 1765146624 0.3943784535 0.5949568152 2.6832771301 451 18.0000000000 0.4355832040 0.0556385871 0.4802996516 0.0092183661 0.0907650000 9776557 955859216 1765146624 0.4020319581 0.5925915241 2.6764392853 452 18.0400000000 0.4336571693 0.0564749114 0.4802996516 0.0092133339 0.0672910000 9777811 955859216 1765146624 0.4156597555 0.5903227925 2.6703984737 453 18.0800000000 0.4321108758 0.0573041299 0.4802996516 0.0092038438 0.1274730000 9779065 955859216 1765130240 0.4243051708 0.5848867297 2.6644856930 454 18.1200000000 0.4313360453 0.0581279887 0.4802996516 0.0092041390 0.1277520000 9780319 955859216 1765130240 0.4334513545 0.5836495161 2.6583235264 455 18.1600000000 0.4289684892 0.0589430228 0.4802996516 0.0091971394 0.0888040000 9781573 955859216 1766621184 0.4453047514 0.5801254511 2.6527452469 456 18.2000000000 0.4261386395 0.0597482763 0.4802996516 0.0091909554 0.1086560000 9782827 955859216 1768652800 0.4560154974 0.5737735629 2.6461722851 457 18.2400000000 0.4225847423 0.0605422292 0.4802996516 0.0091957761 0.1074800000 9784081 955859216 1770303488 0.4656763971 0.5677887201 2.6397640705 458 18.2800000000 0.4201084077 0.0613273082 0.4802996516 0.0092102552 0.0690440000 9785335 955859216 1772081152 0.4777262211 0.5669311881 2.6356825829 459 18.3200000000 0.4168772399 0.0621019268 0.4802996516 0.0092066673 0.0921950000 9786589 955859216 1773731840 0.4912894368 0.5668879151 2.6271395683 460 18.3600000000 0.4152908325 0.0628697287 0.4802996516 0.0092013952 0.1188600000 9787843 955859216 1775509504 0.5009439588 0.5608181357 2.6238043308 461 18.4000000000 0.4148277640 0.0636331952 0.4802996516 0.0091933846 0.1063130000 9789097 955859216 1777160192 0.5118973255 0.5585068464 2.6206784248 462 18.4400000000 0.4102601111 0.0643834699 0.4802996516 0.0091890124 0.0842210000 9790351 955859216 1778810880 0.5243113637 0.5556224585 2.6124918461 463 18.4800000000 0.4133220613 0.0651371170 0.4802996516 0.0091873831 0.1526460000 9791605 955859216 1780588544 0.5328725576 0.5540818572 2.6116375923 464 18.5200000000 0.4305578172 0.0659246616 0.4802996516 0.0092960075 0.1377220000 9792859 955859216 1782239232 0.5418524742 0.5540791750 2.6361339092 465 18.5600000000 0.4235681891 0.0666937874 0.4802996516 0.0093491938 0.0980560000 9794113 955859216 1783889920 0.5468965769 0.5523117781 2.6162621975 466 18.6000000000 0.4263688922 0.0674656224 0.4802996516 0.0093590864 0.1366380000 9795367 955859216 1785667584 0.5666608214 0.5489429235 2.6258373260 467 18.6400000000 0.4225641191 0.0682260047 0.4802996516 0.0093713639 0.1296710000 9796621 955859216 1787318272 0.5707229376 0.5484791398 2.6141152382 468 18.6800000000 0.4230779409 0.0689842353 0.4802996516 0.0093685830 0.1055980000 9797875 955859216 1784700928 0.5821445584 0.5449100137 2.6146364212 469 18.7200000000 0.4233025610 0.0697397115 0.4802996516 0.0093820264 0.0895930000 9799129 955859216 1783541760 0.5928270221 0.5428792238 2.6145553589 470 18.7600000000 0.4334179759 0.0705134950 0.4802996516 0.0093860760 0.0885880000 9800383 955859216 1782525952 0.6143929362 0.5435618162 2.6265959740 471 18.8000000000 0.4920701385 0.0714085197 0.4920701385 0.0095633294 0.0861020000 9801637 955859216 1781399552 0.6306159496 0.6101773977 2.6237037182 472 18.8400000000 0.4739516079 0.0722613652 0.4920701385 0.0096429679 0.1083480000 9802891 955859216 1780514816 0.6394810081 0.5891423225 2.6218426228 473 18.8800000000 0.4480023980 0.0730557438 0.4920701385 0.0097265992 0.1049260000 9804145 955859216 1779367936 0.6523509026 0.5559822321 2.6223781109 474 18.9200000000 0.4830094278 0.0739206249 0.4920701385 0.0098098680 0.0888620000 9805399 955859216 1778335744 0.6381151676 0.5763673186 2.6464312077 475 18.9600000000 0.4574150145 0.0747279816 0.4920701385 0.0098912776 0.0681160000 9806653 955859216 1779716096 0.6491611600 0.5573476553 2.6236085892 476 19.0000000000 0.4439369142 0.0755036306 0.4920701385 0.0099333071 0.0684690000 9807907 955859216 1778970624 0.6703535318 0.5467525721 2.6117374897 477 19.0400000000 0.4389074147 0.0762654834 0.4920701385 0.0099363468 0.0881740000 9809161 955859216 1777954816 0.6825590730 0.5419383645 2.6016409397 478 19.0800000000 0.4354326129 0.0770168790 0.4920701385 0.0099301460 0.0765280000 9810415 955859216 1776939008 0.6913957000 0.5393304825 2.6016492844 479 19.1200000000 0.4335514307 0.0777612100 0.4920701385 0.0099215856 0.0944310000 9811669 955859216 1775808512 0.6962259412 0.5352964997 2.5991883278 480 19.1600000000 0.4349806309 0.0785054172 0.4920701385 0.0099190148 0.0719180000 9812923 955859216 1774669824 0.7084165215 0.5342831612 2.6020338535 481 19.2000000000 0.4347665906 0.0792460849 0.4920701385 0.0099276864 0.0914570000 9814177 955859216 1773637632 0.7174519300 0.5355210304 2.5965266228 482 19.2400000000 0.4345447719 0.0799832191 0.4920701385 0.0099178045 0.0859860000 9815431 955859216 1775017984 0.7272070050 0.5353077650 2.5971586704 483 19.2800000000 0.4604142904 0.0807708611 0.4920701385 0.0102197314 0.0861100000 9816685 955859216 1774379008 0.6605494618 0.5437874198 2.6200125217 484 19.3200000000 0.4329067469 0.0814984145 0.4920701385 0.0105461598 0.0609930000 9817939 955859216 1772744704 0.7369405627 0.5315284133 2.5902853012 485 19.3600000000 0.4648698568 0.0822888711 0.4920701385 0.0109040741 0.0719610000 9819193 955859216 1771483136 0.6631975174 0.5445644259 2.6186435223 486 19.4000000000 0.4291419387 0.0830025606 0.4920701385 0.0112453408 0.0807450000 9820447 955859216 1770610688 0.7501836419 0.5354824662 2.5799744129 487 19.4400000000 0.4270087779 0.0837089388 0.4920701385 0.0112631021 0.0919010000 9821701 955859216 1769574400 0.7576640844 0.5297535658 2.5769214630 488 19.4800000000 0.4256357551 0.0844096085 0.4920701385 0.0112556021 0.0776280000 9822955 955859216 1768558592 0.7574803829 0.5251549482 2.5699350834 489 19.5200000000 0.4243432581 0.0851047694 0.4920701385 0.0112444478 0.0590330000 9824209 955859216 1769938944 0.7636519074 0.5229637623 2.5657534599 490 19.5600000000 0.4235247970 0.0857954225 0.4920701385 0.0112336594 0.0677430000 9825463 955859216 1769287680 0.7655699849 0.5202283263 2.5589380264 491 19.6000000000 0.4839598536 0.0866063480 0.4920701385 0.0123587531 0.0886930000 9826717 955859216 1768304640 0.5995059609 0.5323908329 2.5909125805 492 19.6400000000 0.5182572007 0.0874836872 0.5182572007 0.0125522292 0.1039430000 9827971 955859216 1767288832 0.5147175193 0.5324717760 2.5780007839 493 19.6800000000 0.5134915709 0.0883478005 0.5182572007 0.0125396942 0.0876370000 9829225 955859216 1766273024 0.5151700974 0.5269773602 2.5624039173 494 19.7200000000 0.5101810694 0.0892017140 0.5182572007 0.0125282394 0.1103360000 9830479 955859216 1765257216 0.5188496709 0.5197600722 2.5542314053 495 19.7600000000 0.8285709023 0.0906953891 0.8285709023 0.0182116544 0.0894680000 9831733 955859216 1766637568 0.1180177629 0.5379648209 2.6257143021 496 19.8000000000 0.8311993480 0.0921883407 0.8311993480 0.0181998579 0.0673440000 9832987 955859216 1768525824 0.1127245128 0.5397760272 2.6149542332 497 19.8400000000 0.8351368308 0.0936832068 0.8351368308 0.0181855923 0.1102630000 9834241 955859216 1770176512 0.1054494604 0.5320655704 2.6030511856 498 19.8800000000 0.8357072473 0.0951732150 0.8357072473 0.0181707727 0.1073130000 9835495 955859216 1771827200 0.1022958979 0.5306983590 2.5904879570 499 19.9200000000 0.8434496522 0.0966727669 0.8434496522 0.0181646711 0.0890540000 9836749 955859216 1773604864 0.0880087018 0.5281661153 2.5734305382 500 19.9600000000 0.8437176943 0.0981668568 0.8437176943 0.0181529985 0.0716440000 9838003 955859216 1775255552 0.0812497437 0.5204139948 2.5567226410 501 20.0000000000 0.8407230973 0.0996490050 0.8437176943 0.0181378970 0.1036460000 9839257 955859216 1777049600 0.0798251927 0.5091920495 2.5437309742 502 20.0400000000 0.8434524536 0.1011306851 0.8437176943 0.0181240296 0.0858490000 9840511 955859216 1778683904 0.0804408267 0.5095013380 2.5357089043 503 20.0800000000 0.8361806870 0.1025920172 0.8437176943 0.0181124002 0.0905790000 9841765 955859216 1780461568 0.0923439413 0.5070405602 2.5281078815 504 20.1200000000 0.8323385715 0.1040399270 0.8437176943 0.0180954808 0.0722560000 9843019 955859216 1782112256 0.0970114917 0.5033626556 2.5202560425 505 20.1600000000 0.8297175765 0.1054769124 0.8437176943 0.0180841310 0.0652680000 9844273 955859216 1783889920 0.0970635712 0.5026979446 2.5073776245 506 20.2000000000 0.8253481984 0.1068995830 0.8437176943 0.0180758803 0.0695170000 9845527 955859216 1785540608 0.0998371914 0.5003613830 2.4987835884 507 20.2400000000 0.8226498365 0.1083113192 0.8437176943 0.0180593021 0.0890360000 9846781 955859216 1787191296 0.1038821563 0.5018116236 2.4880876541 508 20.2800000000 0.8447993398 0.1097610987 0.8447993398 0.0181335639 0.1265750000 9848035 955859216 1784684544 0.0647737235 0.4752050638 2.4939486980 509 20.3200000000 0.8198757172 0.1111562159 0.8447993398 0.0182082922 0.0707320000 9849289 955859216 1783558144 0.1018614918 0.4931499660 2.4708292484 510 20.3600000000 0.8149482608 0.1125362003 0.8447993398 0.0181958234 0.0658750000 9850543 955859216 1784905728 0.1124454215 0.4925374985 2.4578015804 511 20.4000000000 0.8108277321 0.1139027199 0.8447993398 0.0181805071 0.0689720000 9851797 955859216 1784193024 0.1200415716 0.4953145683 2.4459791183 512 20.4400000000 0.8401631117 0.1153211972 0.8447993398 0.0183200618 0.1309110000 9853051 955859216 1783160832 0.0770205334 0.4655682147 2.4553411007 513 20.4800000000 0.8413228989 0.1167364052 0.8447993398 0.0183058939 0.1031840000 9895265 955859216 1781620736 0.0850964338 0.4682080746 2.4490969181 514 20.5200000000 0.8130474687 0.1180910960 0.8447993398 0.0183911431 0.1083100000 9980487 955859216 1783144448 0.1187390909 0.4840945899 2.4188356400 515 20.5600000000 0.8073637486 0.1194294895 0.8447993398 0.0183751757 0.1096490000 9981741 955859216 1785032704 0.1311035603 0.4855503440 2.4071440697 516 20.6000000000 0.8003185987 0.1207490420 0.8447993398 0.0183593701 0.0915540000 9982995 955859216 1786810368 0.1415867507 0.4818446040 2.3939671516 517 20.6400000000 0.7990188599 0.1220609759 0.8447993398 0.0183425767 0.0847140000 9984249 955859216 1785708544 0.1383788735 0.4797584414 2.3936798573 518 20.6800000000 0.7960385680 0.1233620910 0.8447993398 0.0183274441 0.0896160000 9985503 955859216 1784713216 0.1593268067 0.4802330434 2.3782632351 519 20.7200000000 0.7932021618 0.1246527269 0.8447993398 0.0183118785 0.0765650000 9986757 955859216 1783508992 0.1509227604 0.4822497964 2.3774266243 520 20.7600000000 0.7914252281 0.1259349817 0.8447993398 0.0182950480 0.0885400000 9988011 955859216 1782525952 0.1444433630 0.4835602045 2.3749446869 521 20.8000000000 0.7892287374 0.1272080984 0.8447993398 0.0182808124 0.0668290000 9989265 955859216 1781510144 0.1446554512 0.4808616638 2.3677318096 522 20.8400000000 0.7888500094 0.1284756116 0.8447993398 0.0182638033 0.1091100000 9990519 955859216 1780494336 0.1482325196 0.4770263135 2.3635349274 523 20.8800000000 0.7854465246 0.1297317701 0.8447993398 0.0182513060 0.0859990000 9991773 955859216 1779367936 0.1391576976 0.4762583375 2.3633182049 524 20.9200000000 0.7832039595 0.1309788545 0.8447993398 0.0182403681 0.1283980000 9993027 955859216 1778335744 0.1611858010 0.4735507071 2.3492569923 525 20.9600000000 0.7816708684 0.1322182678 0.8447993398 0.0182244521 0.0885260000 9994281 955859216 1777319936 0.1627439708 0.4725669324 2.3444900513 526 21.0000000000 0.7798364162 0.1334494810 0.8447993398 0.0182095450 0.0901170000 9995535 955859216 1776193536 0.1741482764 0.4672198594 2.3356137276 527 21.0400000000 0.7775154710 0.1346716176 0.8447993398 0.0182022799 0.1091530000 9996789 955859216 1775161344 0.1780368090 0.4666120410 2.3273057938 528 21.0800000000 0.7767359018 0.1358876485 0.8447993398 0.0181868883 0.0853980000 9998043 955859216 1775017984 0.1819952577 0.4647146761 2.3241248131 529 21.1200000000 0.7728655338 0.1370917655 0.8447993398 0.0181758736 0.1088490000 9999297 955859216 1773150208 0.2004023641 0.4566545486 2.3098998070 530 21.1600000000 0.7717068791 0.1382891525 0.8447993398 0.0181634185 0.0884260000 10000551 955859216 1772113920 0.1974225491 0.4552982152 2.3078527451 531 21.2000000000 0.7693073153 0.1394775106 0.8447993398 0.0181500336 0.0899090000 10001805 955859216 1771098112 0.2093201280 0.4509301484 2.2967276573 532 21.2400000000 0.7674506307 0.1406579112 0.8447993398 0.0181365776 0.0851320000 10003059 955859216 1770082304 0.2123147547 0.4484971166 2.2899453640 533 21.2800000000 0.7659510970 0.1418310691 0.8447993398 0.0181221050 0.0864000000 10004313 955859216 1771462656 0.2124033123 0.4465316832 2.2850723267 534 21.3200000000 0.7633119822 0.1429948911 0.8447993398 0.0181103570 0.0872880000 10005567 955859216 1770446848 0.2240807116 0.4422605634 2.2736086845 535 21.3600000000 0.7598646879 0.1441479187 0.8447993398 0.0180997598 0.1083450000 10006821 955859216 1767309312 0.2337979674 0.4415469170 2.2609312534 536 21.4000000000 0.7583635449 0.1452938434 0.8447993398 0.0180831894 0.1089680000 10008075 955859216 1766273024 0.2326056361 0.4395490587 2.2569227219 537 21.4400000000 0.7552964091 0.1464297886 0.8447993398 0.0180690113 0.0898480000 10009329 955859216 1765257216 0.2452337593 0.4348184466 2.2438676357 538 21.4800000000 0.7529335022 0.1475571189 0.8447993398 0.0180545280 0.0857700000 10010583 955859216 1765146624 0.2476945519 0.4326649606 2.2361638546 539 21.5200000000 0.7503246069 0.1486754259 0.8447993398 0.0180397208 0.1083130000 10011837 955859216 1765146624 0.2482206076 0.4297871590 2.2287747860 540 21.5600000000 0.7470350266 0.1497834993 0.8447993398 0.0180267039 0.0882790000 10013091 955859216 1765146624 0.2550917566 0.4280909896 2.2162184715 541 21.6000000000 0.7438800335 0.1508816444 0.8447993398 0.0180110923 0.0886800000 10014345 955859216 1765146624 0.2589900196 0.4276515245 2.2070188522 542 21.6400000000 0.7748768926 0.1520329272 0.8447993398 0.0180691515 0.1078200000 10015599 955859216 1765163008 0.2349259853 0.4227135479 2.2170178890 543 21.6800000000 0.7745978832 0.1531794557 0.8447993398 0.0180537112 0.0952040000 10016853 955859216 1765146624 0.2383058071 0.4225903153 2.2129685879 544 21.7200000000 0.7642371058 0.1543027234 0.8447993398 0.0180539081 0.1210650000 10018107 955859216 1765146624 0.2474133968 0.4202607572 2.1978495121 545 21.7600000000 0.7532845736 0.1554017727 0.8447993398 0.0180509013 0.1082000000 10019361 955859216 1765146624 0.2607445121 0.4159076512 2.1829576492 546 21.8000000000 0.7453252077 0.1564822185 0.8447993398 0.0180502758 0.1115930000 10020615 955859216 1765163008 0.2707894742 0.4177103043 2.1732234955 547 21.8400000000 0.7416223884 0.1575519446 0.8447993398 0.0180392950 0.1036340000 10021869 955859216 1765097472 0.2769085169 0.4166774452 2.1621260643 548 21.8800000000 0.7397418022 0.1586143349 0.8447993398 0.0180240022 0.0875510000 10023123 955859216 1765130240 0.2753378749 0.4162670076 2.1576604843 549 21.9200000000 0.7379454374 0.1596695828 0.8447993398 0.0180091917 0.0902760000 10024377 955859216 1765130240 0.2785916030 0.4138661027 2.1521582603 550 21.9600000000 0.7353975177 0.1607163608 0.8447993398 0.0179951266 0.1062750000 10025631 955859216 1765003264 0.2802887857 0.4144347310 2.1451754570 551 22.0000000000 0.7334115505 0.1617557350 0.8447993398 0.0179790776 0.1257560000 10026885 955859216 1766494208 0.2830487788 0.4130299985 2.1379449368 552 22.0400000000 0.7319331169 0.1627886651 0.8447993398 0.0179634022 0.1114970000 10028139 955859216 1768652800 0.2882060111 0.4128189087 2.1312363148 553 22.0800000000 0.7312984467 0.1638167117 0.8447993398 0.0179471873 0.0875750000 10029393 955859216 1770430464 0.2874001265 0.4119122028 2.1288483143 554 22.1200000000 0.7298515439 0.1648384352 0.8447993398 0.0179312877 0.0911550000 10030647 955859216 1772081152 0.2899846733 0.4084596336 2.1232085228 555 22.1600000000 0.7272787094 0.1658518411 0.8447993398 0.0179181996 0.0848230000 10031901 955859216 1773858816 0.2927960455 0.4090723097 2.1154558659 556 22.2000000000 0.7245724201 0.1668567343 0.8447993398 0.0179024800 0.1103700000 10033155 955859216 1775509504 0.2953056097 0.4097155035 2.1068043709 557 22.2400000000 0.7238298059 0.1678566859 0.8447993398 0.0178893609 0.1096560000 10034409 955859216 1777160192 0.2957597077 0.4061041474 2.1036720276 558 22.2800000000 0.7222891450 0.1688502925 0.8447993398 0.0178737982 0.1080910000 10035663 955859216 1778937856 0.2956512868 0.4019320607 2.0983755589 559 22.3200000000 0.7205042839 0.1698371511 0.8447993398 0.0178626615 0.0866750000 10036917 955859216 1780588544 0.2965185940 0.4030819237 2.0929033756 560 22.3600000000 0.7193477750 0.1708184201 0.8447993398 0.0178470570 0.0719620000 10038171 955859216 1782366208 0.2962861955 0.4021675587 2.0896224976 561 22.4000000000 0.7177709341 0.1717933800 0.8447993398 0.0178316833 0.0691320000 10039425 955859216 1784016896 0.3018048704 0.3995228708 2.0831437111 562 22.4400000000 0.7162697911 0.1727621992 0.8447993398 0.0178168260 0.0863140000 10040679 955859216 1785667584 0.3015153408 0.3998929858 2.0794780254 563 22.4800000000 0.7141152620 0.1737237500 0.8447993398 0.0178014186 0.1104290000 10041933 955859216 1787445248 0.3061528802 0.3980899751 2.0714375973 564 22.5200000000 0.7129560709 0.1746798357 0.8447993398 0.0177857783 0.1100060000 10043187 955859216 1784811520 0.3082430959 0.3948247135 2.0667169094 565 22.5600000000 0.7110789418 0.1756292146 0.8447993398 0.0177715374 0.0876010000 10044441 955859216 1783668736 0.3147858083 0.3899461925 2.0578577518 566 22.6000000000 0.7096490264 0.1765727125 0.8447993398 0.0177601506 0.0883550000 10045695 955859216 1782542336 0.3174039721 0.3874993622 2.0522694588 567 22.6400000000 0.7083361745 0.1775105669 0.8447993398 0.0177477509 0.0866080000 10046949 955859216 1781510144 0.3206700981 0.3856872618 2.0469460487 568 22.6800000000 0.7068472505 0.1784424977 0.8447993398 0.0177341426 0.1093250000 10048203 955859216 1780494336 0.3255133629 0.3818098605 2.0399932861 569 22.7200000000 0.7047415376 0.1793674521 0.8447993398 0.0177226600 0.0888140000 10049457 955859216 1779478528 0.3306129575 0.3779962361 2.0313143730 570 22.7600000000 0.7014791965 0.1802834376 0.8447993398 0.0177130167 0.1289880000 10050711 955859216 1778352128 0.3324623406 0.3779231906 2.0213251114 571 22.8000000000 0.6988079548 0.1811915366 0.8447993398 0.0176981405 0.1273590000 10051965 955859216 1779716096 0.3338158727 0.3771829903 2.0128092766 572 22.8400000000 0.6972125173 0.1820936712 0.8447993398 0.0176841697 0.1110940000 10053219 955859216 1781477376 0.3363600969 0.3712526262 2.0058617592 573 22.8800000000 0.6948448420 0.1829885249 0.8447993398 0.0176726917 0.1373820000 10054473 955859216 1783255040 0.3385944068 0.3684352040 1.9972813129 574 22.9200000000 0.6922705173 0.1838757757 0.8447993398 0.0176588875 0.1038450000 10055727 955859216 1784905728 0.3381153345 0.3680797219 1.9897892475 575 22.9600000000 0.6900235415 0.1847560327 0.8447993398 0.0176446178 0.1003960000 10056981 955859216 1786683392 0.3398160338 0.3627375364 1.9813758135 576 23.0000000000 0.6884712577 0.1856305383 0.8447993398 0.0176311921 0.0858520000 10058235 955859216 1785597952 0.3411887586 0.3573450446 1.9753671885 577 23.0400000000 0.6854590774 0.1864967923 0.8447993398 0.0176230199 0.1297500000 10059489 955859216 1784565760 0.3426296115 0.3568414152 1.9657146931 578 23.0800000000 0.6829392910 0.1873556893 0.8447993398 0.0176089129 0.0892160000 10060743 955859216 1785937920 0.3446230590 0.3537689149 1.9568949938 579 23.1200000000 0.6809508204 0.1882081852 0.8447993398 0.0175948199 0.0883730000 10061997 955859216 1787699200 0.3468670547 0.3492066264 1.9488773346 580 23.1600000000 0.6784209609 0.1890533797 0.8447993398 0.0175818385 0.1077510000 10063251 955859216 1784791040 0.3494207263 0.3455662429 1.9395856857 581 23.2000000000 0.6757076383 0.1898909946 0.8447993398 0.0175679827 0.0872060000 10064505 955859216 1783685120 0.3508021832 0.3436219692 1.9304049015 582 23.2400000000 0.6729782224 0.1907210414 0.8447993398 0.0175536923 0.0866400000 10065759 955859216 1782542336 0.3528211117 0.3388048708 1.9203549623 583 23.2800000000 0.6711549759 0.1915451133 0.8447993398 0.0175396695 0.1097440000 10067013 955859216 1781510144 0.3554189205 0.3335874677 1.9124342203 584 23.3200000000 0.6677700281 0.1923605669 0.8447993398 0.0175311642 0.0868680000 10068267 955859216 1780494336 0.3569693267 0.3309192359 1.9013676643 585 23.3600000000 0.6647961140 0.1931681491 0.8447993398 0.0175190468 0.1101150000 10069521 955859216 1779478528 0.3591226637 0.3275076747 1.8906708956 586 23.4000000000 0.6625303626 0.1939691085 0.8447993398 0.0175070140 0.0889410000 10070775 955859216 1778352128 0.3620576262 0.3217070401 1.8811624050 587 23.4400000000 0.6600036621 0.1947630344 0.8447993398 0.0175019587 0.0904180000 10072029 955859216 1777319936 0.3636474013 0.3187624514 1.8720408678 588 23.4800000000 0.6524398923 0.1955413965 0.8447993398 0.0175141856 0.1279270000 10073283 955859216 1776271360 0.3693171740 0.3144290149 1.8454272747 589 23.5200000000 0.6494379640 0.1963120188 0.8447993398 0.0175006558 0.0929150000 10074537 955859216 1775288320 0.3704707623 0.3134915829 1.8354144096 590 23.5600000000 0.6458252072 0.1970739056 0.8447993398 0.0174869668 0.0727710000 10075791 955859216 1774272512 0.3717274666 0.3121174574 1.8236849308 591 23.6000000000 0.6433055401 0.1978289506 0.8447993398 0.0174751366 0.1075150000 10077045 955859216 1773256704 0.3739929199 0.3071759939 1.8134645224 592 23.6400000000 0.6401974559 0.1985761947 0.8447993398 0.0174617316 0.0860890000 10078299 955859216 1772240896 0.3770605326 0.3015523851 1.8009299040 593 23.6800000000 0.6368992329 0.1993153567 0.8447993398 0.0174508594 0.0868120000 10079553 955859216 1771372544 0.3790607750 0.2984100282 1.7889486551 594 23.7200000000 0.6338260174 0.2000468561 0.8447993398 0.0174397457 0.0870380000 10080807 955859216 1770336256 0.3812059760 0.2954242229 1.7775583267 595 23.7600000000 0.6312843561 0.2007716250 0.8447993398 0.0174285746 0.1092390000 10082061 955859216 1769320448 0.3814707994 0.2921665907 1.7686061859 596 23.8000000000 0.6276905537 0.2014879319 0.8447993398 0.0174197971 0.1096010000 10083315 955859216 1768304640 0.3836497664 0.2905109525 1.7557563782 597 23.8400000000 0.6243525743 0.2021962479 0.8447993398 0.0174072665 0.0887570000 10084569 955859216 1767288832 0.3841608167 0.2894749343 1.7448624372 598 23.8800000000 0.6209158301 0.2028964479 0.8447993398 0.0173943244 0.0843270000 10085823 955859216 1768652800 0.3866439164 0.2860653698 1.7318108082 599 23.9200000000 0.6175488234 0.2035886889 0.8447993398 0.0173809764 0.0876860000 10087077 955859216 1767923712 0.3867778480 0.2854430079 1.7210501432 600 23.9600000000 0.6145746708 0.2042736656 0.8447993398 0.0173684741 0.1079380000 10088331 955859216 1765150720 0.3881962895 0.2830049098 1.7099459171 601 24.0000000000 0.6115040183 0.2049512535 0.8447993398 0.0173556247 0.1084480000 10089585 955859216 1765146624 0.3884359300 0.2802776098 1.6995453835 602 24.0400000000 0.6084918976 0.2056215868 0.8447993398 0.0173430174 0.0872450000 10090839 955859216 1765146624 0.3901926279 0.2773984969 1.6874629259 603 24.0800000000 0.6054702401 0.2062846857 0.8447993398 0.0173300030 0.0904570000 10092093 955859216 1765146624 0.3897227943 0.2752836943 1.6779947281 604 24.1200000000 0.6029523611 0.2069414203 0.8447993398 0.0173166669 0.1067610000 10093347 955859216 1765146624 0.3889279962 0.2737906575 1.6694240570 605 24.1600000000 0.6004824042 0.2075919013 0.8447993398 0.0173033942 0.0886320000 10094601 955859216 1765146624 0.3888718188 0.2707310915 1.6607165337 606 24.2000000000 0.5988600254 0.2082375582 0.8447993398 0.0172897644 0.0888080000 10095855 955859216 1765146624 0.3887523115 0.2663192153 1.6536986828 607 24.2400000000 0.5957704782 0.2088759980 0.8447993398 0.0172771823 0.1077300000 10097109 955859216 1765130240 0.3905033171 0.2627244294 1.6414238214 608 24.2800000000 0.5928233862 0.2095074904 0.8447993398 0.0172642981 0.0992030000 10098363 955859216 1765130240 0.3902045786 0.2618254423 1.6320712566 609 24.3200000000 0.5909985900 0.2101339125 0.8447993398 0.0172517241 0.0795470000 10099617 955859216 1765130240 0.3913767636 0.2569167614 1.6238435507 610 24.3600000000 0.5894832611 0.2107557967 0.8447993398 0.0172383774 0.1053490000 10100871 955859216 1765146624 0.3919314444 0.2509694695 1.6166340113 611 24.4000000000 0.5865280032 0.2113708085 0.8447993398 0.0172284248 0.1047260000 10102125 955859216 1765146624 0.3946978152 0.2469822615 1.6038546562 612 24.4400000000 0.5838985443 0.2119795140 0.8447993398 0.0172169060 0.0893180000 10103379 955859216 1765621760 0.3946462572 0.2452111840 1.5944453478 613 24.4800000000 0.5823490024 0.2125837056 0.8447993398 0.0172032693 0.0876550000 10104633 955859216 1765621760 0.3947818875 0.2412531972 1.5875818729 614 24.5200000000 0.5795910954 0.2131814375 0.8447993398 0.0171903761 0.0870840000 10105887 955859216 1765367808 0.3969618380 0.2358027548 1.5754588842 615 24.5600000000 0.5779594183 0.2137745725 0.8447993398 0.0171775371 0.1046400000 10107141 955859216 1765097472 0.3981391191 0.2324150205 1.5677498579 616 24.6000000000 0.5759788156 0.2143625664 0.8447993398 0.0171649596 0.1597400000 10108395 955859216 1764737024 0.4000173807 0.2270444483 1.5578368902 617 24.6400000000 0.5736370683 0.2149448589 0.8447993398 0.0171551739 0.1496300000 10109649 955859216 1766264832 0.4014641941 0.2228324413 1.5476113558 618 24.6800000000 0.5712823272 0.2155214568 0.8447993398 0.0171459593 0.1284240000 10110903 955859216 1767899136 0.4042471051 0.2179850787 1.5358681679 619 24.7200000000 0.5683192611 0.2160914047 0.8447993398 0.0171383601 0.1385110000 10112157 955859216 1769549824 0.4077114761 0.2135984302 1.5216560364 620 24.7600000000 0.5657597780 0.2166553860 0.8447993398 0.0171294958 0.1064000000 10113411 955859216 1771200512 0.4076269269 0.2120494843 1.5123678446 621 24.8000000000 0.5635925531 0.2172140610 0.8447993398 0.0171171863 0.1199100000 10114665 955859216 1772978176 0.4091017246 0.2089803815 1.5025132895 622 24.8400000000 0.5615089536 0.2177675897 0.8447993398 0.0171048639 0.1663830000 10115919 955859216 1774628864 0.4104920328 0.2044656277 1.4924489260 623 24.8800000000 0.5588937998 0.2183151439 0.8447993398 0.0170950511 0.1742870000 10117173 955859216 1776279552 0.4114929438 0.2023880035 1.4817461967 624 24.9200000000 0.5560277700 0.2188563500 0.8447993398 0.0170835077 0.1316330000 10118427 955859216 1778057216 0.4119950831 0.2003495693 1.4704476595 625 24.9600000000 0.5538493991 0.2193923389 0.8447993398 0.0170711969 0.1222250000 10119681 955859216 1779707904 0.4123232365 0.1961538047 1.4608505964 626 25.0000000000 0.5521719456 0.2199239357 0.8447993398 0.0170591838 0.1638930000 10120935 955859216 1781501952 0.4132825434 0.1918352842 1.4521394968 627 25.0400000000 0.5497954488 0.2204500465 0.8447993398 0.0170498769 0.1429360000 10122189 955859216 1783136256 0.4136170745 0.1891159266 1.4420726299 628 25.0800000000 0.5467920303 0.2209696994 0.8447993398 0.0170395011 0.1054390000 10123443 955859216 1784913920 0.4129019082 0.1882974207 1.4315903187 629 25.1200000000 0.5451527238 0.2214850937 0.8447993398 0.0170268439 0.1706010000 10124697 955859216 1786564608 0.4123203456 0.1858762950 1.4251475334 630 25.1600000000 0.5425277352 0.2219946852 0.8447993398 0.0170150742 0.1046980000 10125951 955859216 1785606144 0.4114855826 0.1831555814 1.4152277708 631 25.2000000000 0.5397934914 0.2224983283 0.8447993398 0.0170031803 0.1252440000 10127205 955859216 1786970112 0.4102656543 0.1818068177 1.4058830738 632 25.2400000000 0.5379906893 0.2229975251 0.8447993398 0.0169908797 0.1081970000 10128459 955859216 1784692736 0.4084501863 0.1790522635 1.3996399641 633 25.2800000000 0.5348864198 0.2234902406 0.8447993398 0.0169794157 0.0919280000 10129713 955859216 1783566336 0.4078269899 0.1771507859 1.3883877993 634 25.3200000000 0.5318376422 0.2239765929 0.8447993398 0.0169676411 0.1057870000 10130967 955859216 1782554624 0.4052585959 0.1763429344 1.3791528940 635 25.3600000000 0.5299766064 0.2244584827 0.8447993398 0.0169567881 0.1080950000 10132221 955859216 1781407744 0.4030306637 0.1747395843 1.3729671240 636 25.4000000000 0.5278353691 0.2249354904 0.8447993398 0.0169464876 0.1080370000 10133475 955859216 1780375552 0.4025309682 0.1706727594 1.3638321161 637 25.4400000000 0.5254572630 0.2254072671 0.8447993398 0.0169344968 0.0914640000 10134729 955859216 1779359744 0.4003795683 0.1689937115 1.3559155464 638 25.4800000000 0.5236590505 0.2258747464 0.8447993398 0.0169231406 0.1061370000 10135983 955859216 1778343936 0.3995867670 0.1652520746 1.3480139971 639 25.5200000000 0.5218365788 0.2263379105 0.8447993398 0.0169112016 0.1082080000 10137237 955859216 1777217536 0.3963973820 0.1615801901 1.3417445421 640 25.5600000000 0.5200933218 0.2267969033 0.8447993398 0.0168994598 0.1073770000 10138491 955859216 1776185344 0.3942239881 0.1586887389 1.3354216814 641 25.6000000000 0.5179678202 0.2272511481 0.8447993398 0.0168878385 0.0909030000 10139745 955859216 1775169536 0.3913567066 0.1557458192 1.3281928301 642 25.6400000000 0.5159547329 0.2277008422 0.8447993398 0.0168761221 0.1058900000 10140999 955859216 1774149632 0.3877137303 0.1529968679 1.3223235607 643 25.6800000000 0.5140889287 0.2281462358 0.8447993398 0.0168641143 0.1077190000 10142253 955859216 1773137920 0.3852312863 0.1493914425 1.3153183460 644 25.7200000000 0.5120261312 0.2285870430 0.8447993398 0.0168518946 0.1077230000 10143507 955859216 1772122112 0.3812821805 0.1468533128 1.3093611002 645 25.7600000000 0.5102781653 0.2290237735 0.8447993398 0.0168395164 0.1085980000 10144761 955859216 1771253760 0.3783764243 0.1431346089 1.3027164936 646 25.8000000000 0.5082218051 0.2294559686 0.8447993398 0.0168271405 0.1080510000 10146015 955859216 1770217472 0.3734314740 0.1400613934 1.2976633310 647 25.8400000000 0.5054057837 0.2298824752 0.8447993398 0.0168153063 0.1082880000 10147269 955859216 1769201664 0.3681225777 0.1387808174 1.2901997566 648 25.8800000000 0.5030511022 0.2303040318 0.8447993398 0.0168035948 0.0915830000 10148523 955859216 1768185856 0.3630327582 0.1365284026 1.2843447924 649 25.9200000000 0.5009981990 0.2307211260 0.8447993398 0.0167923028 0.1051010000 10149777 955859216 1767317504 0.3576239944 0.1322857589 1.2785395384 650 25.9600000000 0.4974325895 0.2311314513 0.8447993398 0.0167844629 0.1076900000 10151031 955859216 1766428672 0.3468726277 0.1224105656 1.2680786848 651 26.0000000000 0.4912756681 0.2315310584 0.8447993398 0.0167874792 0.0917140000 10152285 955859216 1765412864 0.3332799375 0.1187657863 1.2536361217 652 26.0400000000 0.4879346788 0.2319243155 0.8447993398 0.0167764476 0.0977080000 10153539 955859216 1765150720 0.3259792924 0.1175168604 1.2456197739 653 26.0800000000 0.4838634431 0.2323101335 0.8447993398 0.0167650918 0.0938240000 10154793 955859216 1765150720 0.3175014257 0.1186601371 1.2378180027 654 26.1200000000 0.4805435240 0.2326896952 0.8447993398 0.0167572434 0.0899820000 10156047 955859216 1765150720 0.3087570667 0.1168092638 1.2315629721 655 26.1600000000 0.4773917496 0.2330632862 0.8447993398 0.0167465623 0.1265200000 10157301 955859216 1765150720 0.3015294075 0.1124905571 1.2238014936 656 26.2000000000 0.4739304185 0.2334304617 0.8447993398 0.0167382425 0.1063290000 10158555 955859216 1765154816 0.2924358547 0.1113188341 1.2168107033 657 26.2400000000 0.4707544744 0.2337916854 0.8447993398 0.0167298751 0.0963790000 10159809 955859216 1765154816 0.2833456099 0.1100163385 1.2105488777 658 26.2800000000 0.4667783976 0.2341457686 0.8447993398 0.0167231638 0.0954810000 10161063 955859216 1765154816 0.2740222514 0.1094536856 1.2026565075 659 26.3200000000 0.4625935555 0.2344924268 0.8447993398 0.0167143093 0.0897980000 10162317 955859216 1765154816 0.2637632787 0.1104377806 1.1955957413 660 26.3600000000 0.4589139819 0.2348324595 0.8447993398 0.0167036547 0.1053690000 10163571 955859216 1765105664 0.2545397580 0.1098646969 1.1887935400 661 26.4000000000 0.4545004666 0.2351647863 0.8447993398 0.0166931086 0.1074470000 10164825 955859216 1765138432 0.2442644984 0.1103449762 1.1809140444 662 26.4400000000 0.4504726231 0.2354900247 0.8447993398 0.0166834817 0.1077180000 10166079 955859216 1766502400 0.2334121615 0.1123298556 1.1752715111 663 26.4800000000 0.4472302496 0.2358093915 0.8447993398 0.0166834729 0.0919720000 10167333 955859216 1768534016 0.2242584378 0.1103070155 1.1690596342 664 26.5200000000 0.4443920851 0.2361235221 0.8447993398 0.0166791733 0.1029510000 10168587 955859216 1770311680 0.2162313312 0.1054308787 1.1616380215 665 26.5600000000 0.4409965575 0.2364316019 0.8447993398 0.0166680933 0.0913050000 10169841 955859216 1771962368 0.2070526779 0.1044392213 1.1556758881 666 26.6000000000 0.4370283484 0.2367327982 0.8447993398 0.0166573237 0.1082420000 10171095 955859216 1773740032 0.1975599676 0.1048488840 1.1485204697 667 26.6400000000 0.4334455132 0.2370277198 0.8447993398 0.0166479681 0.1061530000 10172349 955859216 1775390720 0.1878360361 0.1065140963 1.1433775425 668 26.6800000000 0.4291685522 0.2373153558 0.8447993398 0.0166454330 0.1081940000 10173603 955859216 1777041408 0.1782846004 0.1089210138 1.1361244917 669 26.7200000000 0.4255364239 0.2375967027 0.8447993398 0.0166547138 0.0917430000 10174857 955859216 1778819072 0.1687090695 0.1087507308 1.1298761368 670 26.7600000000 0.4226132333 0.2378728467 0.8447993398 0.0166604010 0.0893610000 10176111 955859216 1780469760 0.1604281217 0.1070043817 1.1243695021 671 26.8000000000 0.4195021987 0.2381435313 0.8447993398 0.0166544749 0.1070460000 10177365 955859216 1782120448 0.1524847299 0.1057092696 1.1179848909 672 26.8400000000 0.4159281254 0.2384080917 0.8447993398 0.0166441200 0.1083970000 10178619 955859216 1783898112 0.1445526928 0.1065156162 1.1108047962 673 26.8800000000 0.4128560126 0.2386673011 0.8447993398 0.0166338950 0.0938230000 10179873 955859216 1785548800 0.1371727735 0.1054651216 1.1045588255 674 26.9200000000 0.4098898172 0.2389213405 0.8447993398 0.0166230865 0.1042110000 10181127 955859216 1787199488 0.1298980415 0.1049392968 1.0983071327 675 26.9600000000 0.4068773985 0.2391701642 0.8447993398 0.0166121417 0.1098180000 10182381 955859216 1784803328 0.1224277020 0.1055662110 1.0927575827 676 27.0000000000 0.4031552076 0.2394127457 0.8447993398 0.0166018009 0.1064680000 10183635 955859216 1783693312 0.1147831902 0.1082007140 1.0858017206 677 27.0400000000 0.3998306990 0.2396496998 0.8447993398 0.0165964329 0.1074050000 10184889 955859216 1782538240 0.1070721224 0.1101561114 1.0806701183 678 27.0800000000 0.3969876766 0.2398817617 0.8447993398 0.0165938962 0.1470380000 10186143 955859216 1781510144 0.1001860425 0.1106391922 1.0749292374 679 27.1200000000 0.3938172162 0.2401084708 0.8447993398 0.0165909289 0.1111990000 10187397 955859216 1780494336 0.0928635746 0.1110912412 1.0683231354 680 27.1600000000 0.3911273777 0.2403305574 0.8447993398 0.0165848435 0.0891620000 10188651 955859216 1779478528 0.0868900716 0.1092777923 1.0615493059 681 27.2000000000 0.3884063363 0.2405479961 0.8447993398 0.0165740452 0.1267150000 10189905 955859216 1778352128 0.0802479610 0.1091487110 1.0557614565 682 27.2400000000 0.3850256205 0.2407598402 0.8447993398 0.0165635531 0.0882070000 10191159 955859216 1779716096 0.0736606121 0.1110375375 1.0486822128 683 27.2800000000 0.3817698956 0.2409662971 0.8447993398 0.0165557508 0.0894290000 10192413 955859216 1781477376 0.0674381331 0.1120974794 1.0415512323 684 27.3200000000 0.3789292276 0.2411679973 0.8447993398 0.0165508786 0.0868390000 10193667 955859216 1783255040 0.0607775487 0.1116096005 1.0350013971 685 27.3600000000 0.3760458827 0.2413648993 0.8447993398 0.0165436515 0.1085720000 10194921 955859216 1784905728 0.0550885536 0.1105020866 1.0274530649 686 27.4000000000 0.3724027574 0.2415559166 0.8447993398 0.0165341773 0.0859010000 10196175 955859216 1786683392 0.0486059338 0.1120190471 1.0190019608 687 27.4400000000 0.3689117432 0.2417412962 0.8447993398 0.0165305404 0.0873070000 10197429 955859216 1785597952 0.0425414965 0.1134896949 1.0105621815 688 27.4800000000 0.3658901453 0.2419217451 0.8447993398 0.0165338874 0.0854680000 10198683 955859216 1783930880 0.0362066925 0.1132657006 1.0028263330 689 27.5200000000 0.3625807762 0.2420968671 0.8447993398 0.0165337342 0.0884200000 10199937 955859216 1783287808 0.0300211757 0.1129281819 0.9946286082 690 27.5600000000 0.3594335914 0.2422669203 0.8447993398 0.0165292405 0.0883570000 10201191 955859216 1782161408 0.0245936606 0.1121646464 0.9857182503 691 27.6000000000 0.3556753397 0.2424310425 0.8447993398 0.0165237741 0.1060280000 10202445 955859216 1781129216 0.0180117227 0.1142838076 0.9764426351 692 27.6400000000 0.3518857658 0.2425892140 0.8447993398 0.0165265035 0.0899350000 10203699 955859216 1782509568 0.0117176883 0.1156748310 0.9669775367 693 27.6800000000 0.3490476310 0.2427428337 0.8447993398 0.0165386129 0.0887020000 10204953 955859216 1784270848 0.0064267470 0.1138730422 0.9579523206 694 27.7200000000 0.3463204801 0.2428920810 0.8447993398 0.0165410090 0.0887180000 10206207 955859216 1785921536 0.0018404529 0.1107073426 0.9483487010 695 27.7600000000 0.3440403044 0.2430376180 0.8447993398 0.0165336433 0.1066740000 10207461 955859216 1787699200 -0.0026865362 0.1077226549 0.9398617744 696 27.8000000000 0.3408528864 0.2431781572 0.8447993398 0.0165237757 0.0889060000 10208715 955859216 1786699776 -0.0077634165 0.1076946855 0.9301614761 697 27.8400000000 0.3374573886 0.2433134215 0.8447993398 0.0165145514 0.0868880000 10209969 955859216 1785176064 -0.0132746194 0.1086388156 0.9205033183 698 27.8800000000 0.3335378766 0.2434426829 0.8447993398 0.0165072921 0.1060420000 10211223 955859216 1782398976 -0.0197499301 0.1107330620 0.9106698036 699 27.9200000000 0.3301204443 0.2435666855 0.8447993398 0.0165049580 0.1081360000 10212477 955859216 1781383168 -0.0258111060 0.1125607118 0.9016528130 700 27.9600000000 0.3266105652 0.2436853196 0.8447993398 0.0165072530 0.1468820000 10213731 955859216 1780256768 -0.0319568478 0.1133341491 0.8920192719 701 28.0000000000 0.3236366510 0.2437993728 0.8447993398 0.0165113204 0.1279310000 10214985 955859216 1779224576 -0.0378896557 0.1135370582 0.8835012317 702 28.0400000000 0.3208384812 0.2439091151 0.8447993398 0.0165134701 0.0890640000 10216239 955859216 1778827264 -0.0435805209 0.1126489639 0.8751169443 703 28.0800000000 0.3184098601 0.2440150906 0.8447993398 0.0165096280 0.0898920000 10217493 955859216 1777811456 -0.0489406697 0.1120426953 0.8683486581 704 28.1200000000 0.3146997392 0.2441154949 0.8447993398 0.0165042030 0.0840190000 10218747 955859216 1776017408 -0.0560329035 0.1163949370 0.8602757454 705 28.1600000000 0.3114751577 0.2442110405 0.8447993398 0.0165112559 0.1026310000 10220001 955859216 1774284800 -0.0627285689 0.1188492402 0.8528504372 706 28.2000000000 0.3093718886 0.2443033364 0.8447993398 0.0165182177 0.0905770000 10221255 955859216 1775906816 -0.0682872087 0.1172433496 0.8470635414 707 28.2400000000 0.3064796925 0.2443912803 0.8447993398 0.0165125814 0.1054370000 10222509 955859216 1777668096 -0.0746111721 0.1192089841 0.8402648568 708 28.2800000000 0.3033268452 0.2444745226 0.8447993398 0.0165046613 0.1087860000 10223763 955859216 1779318784 -0.0815331861 0.1221259311 0.8339545131 709 28.3200000000 0.3020930588 0.2445557899 0.8447993398 0.0164957277 0.0899310000 10225017 955859216 1781112832 -0.0865653008 0.1183145642 0.8299244046 710 28.3600000000 0.2999833524 0.2446338569 0.8447993398 0.0164858002 0.1052550000 10226271 955859216 1782747136 -0.0920014828 0.1181515902 0.8244988322 711 28.4000000000 0.2962459326 0.2447064478 0.8447993398 0.0164758980 0.1082290000 10227525 955859216 1784397824 -0.0995460898 0.1247671321 0.8183409572 712 28.4400000000 0.2937723696 0.2447753606 0.8447993398 0.0164682271 0.0918320000 10228779 955859216 1786175488 -0.1062454730 0.1259140968 0.8133292794 713 28.4800000000 0.2930766940 0.2448431044 0.8447993398 0.0164572693 0.1083950000 10230033 955859216 1787826176 -0.1107539907 0.1221548691 0.8118479252 714 28.5200000000 0.2895361185 0.2449056996 0.8447993398 0.0164626267 0.1091480000 10231287 955859216 1784934400 -0.1185479760 0.1286019385 0.8069099188 715 28.5600000000 0.2861070633 0.2449633239 0.8447993398 0.0164524753 0.1067500000 10232541 955859216 1783812096 -0.1267761141 0.1344827712 0.8022997379 716 28.6000000000 0.2843565643 0.2450183424 0.8447993398 0.0164468946 0.1074840000 10233795 955859216 1782669312 -0.1337606460 0.1361739635 0.8019159436 717 28.6400000000 0.2827295959 0.2450709383 0.8447993398 0.0164377324 0.1468400000 10235049 955859216 1781637120 -0.1407303959 0.1378872693 0.8021599054 718 28.6800000000 0.2803640068 0.2451200930 0.8447993398 0.0164273695 0.1289570000 10236303 955859216 1780621312 -0.1485759467 0.1425164640 0.8015410900 719 28.7200000000 0.2780832648 0.2451659389 0.8447993398 0.0164204494 0.0900200000 10237557 955859216 1782001664 -0.1565391421 0.1455855221 0.8003569841 720 28.7600000000 0.2761807442 0.2452090150 0.8447993398 0.0164125551 0.1062070000 10238811 955859216 1783762944 -0.1647619009 0.1482074559 0.8010202050 721 28.8000000000 0.2747726738 0.2452500187 0.8447993398 0.0164021521 0.1495360000 10240065 955859216 1785540608 -0.1727190614 0.1496888846 0.8030661941 722 28.8400000000 0.2728978693 0.2452883121 0.8447993398 0.0163914120 0.1307570000 10241319 955859216 1787191296 -0.1814538836 0.1524354517 0.8041630983 723 28.8800000000 0.2713699639 0.2453243863 0.8447993398 0.0163805382 0.1048630000 10242573 955859216 1784684544 -0.1903835982 0.1543872356 0.8066165447 724 28.9200000000 0.2695614696 0.2453578629 0.8447993398 0.0163698735 0.1088700000 10243827 955859216 1783558144 -0.1998259872 0.1572716981 0.8085038662 725 28.9600000000 0.2676987350 0.2453886779 0.8447993398 0.0163599784 0.1488100000 10245081 955859216 1782415360 -0.2097494006 0.1605591923 0.8106135130 726 29.0000000000 0.2661736012 0.2454173073 0.8447993398 0.0163554066 0.1266950000 10246335 955859216 1781383168 -0.2192883343 0.1627730876 0.8133910894 727 29.0400000000 0.2643587887 0.2454433616 0.8447993398 0.0163504172 0.1286800000 10247589 955859216 1780367360 -0.2298053652 0.1655616909 0.8156649470 728 29.0800000000 0.2627248168 0.2454670999 0.8447993398 0.0163446012 0.0896900000 10248843 955859216 1781731328 -0.2401646376 0.1687715948 0.8186105490 729 29.1200000000 0.2611632943 0.2454886310 0.8447993398 0.0163356849 0.0891450000 10250097 955859216 1783635968 -0.2506115437 0.1723022759 0.8219174743 730 29.1600000000 0.2597991526 0.2455082344 0.8447993398 0.0163253397 0.1082320000 10251351 955859216 1785286656 -0.2610033453 0.1744329631 0.8251457214 731 29.2000000000 0.2581329346 0.2455255049 0.8447993398 0.0163148995 0.1094860000 10252605 955859216 1786937344 -0.2717766762 0.1777849942 0.8276462555 732 29.2400000000 0.2561489940 0.2455400179 0.8447993398 0.0163051041 0.0869200000 10253859 955859216 1786068992 -0.2833376825 0.1827331930 0.8297172785 733 29.2800000000 0.2546845376 0.2455524933 0.8447993398 0.0162954238 0.1041770000 10255113 955859216 1784328192 -0.2949655056 0.1871265620 0.8335644007 734 29.3200000000 0.2534750700 0.2455632870 0.8447993398 0.0162858640 0.0928610000 10256367 955859216 1783177216 -0.3064181805 0.1921544671 0.8383350968 735 29.3600000000 0.2523643076 0.2455725401 0.8447993398 0.0162767026 0.1052900000 10257621 955859216 1782145024 -0.3174531758 0.1968885213 0.8427538276 736 29.4000000000 0.2513312995 0.2455803645 0.8447993398 0.0162676274 0.1081050000 10258875 955859216 1781018624 -0.3283634782 0.2025246918 0.8474073410 737 29.4400000000 0.2505306602 0.2455870813 0.8447993398 0.0162578267 0.1072070000 10260129 955859216 1779859456 -0.3388281763 0.2071263939 0.8520374894 738 29.4800000000 0.2497447729 0.2455927151 0.8447993398 0.0162518764 0.0916340000 10261383 955859216 1778843648 -0.3495216966 0.2119903564 0.8566120863 739 29.5200000000 0.2492953986 0.2455977255 0.8447993398 0.0162571102 0.1051360000 10262637 955859216 1777827840 -0.3595963418 0.2163811773 0.8616971374 740 29.5600000000 0.2490091920 0.2456023356 0.8447993398 0.0162628722 0.0906090000 10263891 955859216 1776812032 -0.3687360585 0.2207062691 0.8670828938 741 29.6000000000 0.2485808730 0.2456063552 0.8447993398 0.0162738878 0.1069700000 10265145 955859216 1775685632 -0.3781587780 0.2264256775 0.8717478514 742 29.6400000000 0.2485486120 0.2456103205 0.8447993398 0.0162826004 0.0890120000 10266399 955859216 1774653440 -0.3867745697 0.2317336351 0.8772494197 743 29.6800000000 0.2490357012 0.2456149307 0.8447993398 0.0162769094 0.1057640000 10267653 955859216 1773637632 -0.3938702941 0.2344200313 0.8831036687 744 29.7200000000 0.2492900640 0.2456198704 0.8447993398 0.0162664152 0.1160390000 10268907 955859216 1772769280 -0.4007143378 0.2374914587 0.8876702785 745 29.7600000000 0.2493019104 0.2456248127 0.8447993398 0.0162566474 0.0818970000 10270161 955859216 1771732992 -0.4075868130 0.2412446439 0.8914288878 746 29.8000000000 0.2494795620 0.2456299799 0.8447993398 0.0162461913 0.1148730000 10271415 955859216 1770704896 -0.4140649140 0.2442550957 0.8953503370 747 29.8400000000 0.2493683547 0.2456349845 0.8447993398 0.0162367682 0.0807650000 10272669 955859216 1769701376 -0.4207811654 0.2483049035 0.8983609676 748 29.8800000000 0.2493016422 0.2456398864 0.8447993398 0.0162307455 0.0890270000 10273923 955859216 1768833024 -0.4273279309 0.2528701425 0.9014475942 749 29.9200000000 0.2494377196 0.2456449569 0.8447993398 0.0162239470 0.1072620000 10275177 955859216 1767796736 -0.4330809116 0.2567845881 0.9047274590 750 29.9600000000 0.2495564520 0.2456501723 0.8447993398 0.0162177785 0.1074910000 10276431 955859216 1766780928 -0.4385215938 0.2605151534 0.9076769352 751 30.0000000000 0.2497170269 0.2456555875 0.8447993398 0.0162117220 0.0894130000 10277685 955859216 1765912576 -0.4435417950 0.2634615898 0.9103442430 752 30.0400000000 0.2498610169 0.2456611798 0.8447993398 0.0162051804 0.0853570000 10278939 955859216 1765134336 -0.4482734799 0.2667021155 0.9126549959 753 30.0800000000 0.2488554269 0.2456654219 0.8447993398 0.0161972494 0.1063550000 10280193 955859216 1765146624 -0.4520263672 0.2713627219 0.9143998623 754 30.1200000000 0.2485317886 0.2456692234 0.8447993398 0.0161954263 0.1069240000 10281447 955859216 1765146624 -0.4562250972 0.2748149335 0.9160899520 755 30.1600000000 0.2482003868 0.2456725760 0.8447993398 0.0161975024 0.0879280000 10282701 955859216 1765097472 -0.4608815312 0.2774049640 0.9174073935 756 30.2000000000 0.2481631190 0.2456758703 0.8447993398 0.0162000522 0.0898970000 10283955 955859216 1765163008 -0.4661090374 0.2804337144 0.9187346101 757 30.2400000000 0.2477875352 0.2456786598 0.8447993398 0.0161954018 0.0868850000 10285209 955859216 1765163008 -0.4714784324 0.2838189304 0.9195393920 758 30.2800000000 0.2474685758 0.2456810212 0.8447993398 0.0161913224 0.0887650000 10286463 955859216 1765163008 -0.4770177603 0.2865538001 0.9207779169 759 30.3200000000 0.2489785850 0.2456853658 0.8447993398 0.0162130687 0.1112300000 10287717 955859216 1765163008 -0.4848802090 0.2863956690 0.9219129682 760 30.3600000000 0.2471073568 0.2456872369 0.8447993398 0.0162126035 0.0852330000 10288971 955859216 1765163008 -0.4907239377 0.2935956717 0.9215357304 761 30.4000000000 0.2458556443 0.2456874582 0.8447993398 0.0162131622 0.1085920000 10290225 955859216 1765146624 -0.4969942272 0.2986512780 0.9211872816 762 30.4400000000 0.2447847575 0.2456862735 0.8447993398 0.0162085081 0.1066200000 10291479 955859216 1765146624 -0.5037265420 0.3029631078 0.9204760790 763 30.4800000000 0.2461885512 0.2456869318 0.8447993398 0.0162143938 0.0882310000 10292733 955859216 1765146624 -0.5133202672 0.3028769493 0.9194982648 764 30.5200000000 0.2442141473 0.2456850041 0.8447993398 0.0162059975 0.0902220000 10293987 955859216 1765163008 -0.5200299621 0.3083595335 0.9188112020 765 30.5600000000 0.2447145283 0.2456837355 0.8447993398 0.0162044023 0.1251330000 10295241 955859216 1765130240 -0.5293419957 0.3103045821 0.9170956016 766 30.6000000000 0.2428741902 0.2456800677 0.8447993398 0.0161955411 0.0698240000 10296495 955859216 1765130240 -0.5360459089 0.3154392838 0.9168812037 767 30.6400000000 0.2433167994 0.2456769865 0.8447993398 0.0161951141 0.0864980000 10297749 955859216 1765130240 -0.5460602641 0.3173894584 0.9143633842 768 30.6800000000 0.2423333675 0.2456726328 0.8447993398 0.0161897274 0.0873310000 10299003 955859216 1765163008 -0.5542398691 0.3212812245 0.9131228328 769 30.7200000000 0.2420650125 0.2456679415 0.8447993398 0.0161867816 0.0902670000 10300257 955859216 1765146624 -0.5632084608 0.3247282803 0.9114341736 770 30.7600000000 0.2415037602 0.2456625335 0.8447993398 0.0161802366 0.0857960000 10301511 955859216 1765146624 -0.5718725920 0.3287167847 0.9098836184 771 30.8000000000 0.2408969253 0.2456563524 0.8447993398 0.0161727151 0.0890620000 10302765 955859216 1765146624 -0.5804471374 0.3321360350 0.9080376625 772 30.8400000000 0.2404148430 0.2456495629 0.8447993398 0.0161658803 0.0867800000 10304019 955859216 1765146624 -0.5888940692 0.3343665302 0.9065711498 773 30.8800000000 0.2399568856 0.2456421985 0.8447993398 0.0161597574 0.0888430000 10305273 955859216 1765146624 -0.5975193977 0.3371160626 0.9049753547 774 30.9200000000 0.2396809906 0.2456344967 0.8447993398 0.0161564748 0.0879380000 10306527 955859216 1765146624 -0.6058080792 0.3393334746 0.9039343596 775 30.9600000000 0.2389120162 0.2456258225 0.8447993398 0.0161524044 0.0881210000 10307781 955859216 1765126144 -0.6138494015 0.3410357535 0.9026929140 776 31.0000000000 0.2369750440 0.2456146746 0.8447993398 0.0161467982 0.0900330000 10309035 955859216 1765138432 -0.6209036112 0.3443035483 0.9020191431 777 31.0400000000 0.2384475023 0.2456054504 0.8447993398 0.0161605919 0.0848750000 10310289 955859216 1765138432 -0.6312478781 0.3449987471 0.8988561630 778 31.0800000000 0.2361774743 0.2455933322 0.8447993398 0.0161522891 0.0856770000 10311543 955859216 1766621184 -0.6376700997 0.3498826325 0.8977128267 779 31.1200000000 0.2377908379 0.2455833162 0.8447993398 0.0161532220 0.1095550000 10312797 955859216 1765036032 -0.6474387646 0.3498806953 0.8952310085 780 31.1600000000 0.2376294285 0.2455731189 0.8447993398 0.0161474247 0.0876180000 10314051 955859216 1765036032 -0.6551929712 0.3521444201 0.8936758637 781 31.2000000000 0.2373357415 0.2455625717 0.8447993398 0.0161409042 0.0884530000 10315305 955859216 1765036032 -0.6628579497 0.3540875912 0.8916529417 782 31.2400000000 0.2372153103 0.2455518974 0.8447993398 0.0161321707 0.1127470000 10316559 955859216 1765036032 -0.6701029539 0.3551076949 0.8903055191 783 31.2800000000 0.2371596992 0.2455411794 0.8447993398 0.0161230088 0.0832080000 10317813 955859216 1765130240 -0.6773707271 0.3565149605 0.8890351653 784 31.3200000000 0.2371510565 0.2455304777 0.8447993398 0.0161142563 0.0886150000 10319067 955859216 1765163008 -0.6841156483 0.3575164080 0.8879902363 785 31.3600000000 0.2371361256 0.2455197843 0.8447993398 0.0161045712 0.1258080000 10320321 955859216 1765146624 -0.6905285120 0.3579038084 0.8870288134 786 31.4000000000 0.2371707559 0.2455091621 0.8447993398 0.0160949769 0.1093740000 10321575 955859216 1765146624 -0.6969579458 0.3586044610 0.8861035109 787 31.4400000000 0.2372259200 0.2454986370 0.8447993398 0.0160853953 0.0874140000 10322829 955859216 1765146624 -0.7028332949 0.3603107631 0.8849477172 788 31.4800000000 0.2374569923 0.2454884319 0.8447993398 0.0160760641 0.1049010000 10324083 955859216 1765163008 -0.7082341909 0.3611824214 0.8847401738 789 31.5200000000 0.2375430912 0.2454783617 0.8447993398 0.0160668660 0.1300860000 10325337 955859216 1765163008 -0.7136198282 0.3610826135 0.8841828704 790 31.5600000000 0.2377589792 0.2454685904 0.8447993398 0.0160570592 0.0888280000 10326591 955859216 1764757504 -0.7189213634 0.3612080514 0.8839722276 791 31.6000000000 0.2379128188 0.2454590382 0.8447993398 0.0160478531 0.0868110000 10327845 955859216 1764876288 -0.7238491774 0.3613591790 0.8835899234 792 31.6400000000 0.2357427627 0.2454467702 0.8447993398 0.0160383347 0.0928410000 10329099 955859216 1765163008 -0.7260529995 0.3628211021 0.8856492639 793 31.6800000000 0.2383170575 0.2454377794 0.8447993398 0.0160313737 0.1208090000 10330353 955859216 1765122048 -0.7322496772 0.3603084385 0.8839833140 794 31.7200000000 0.2366561294 0.2454267194 0.8447993398 0.0160271701 0.1058290000 10331607 955859216 1765130240 -0.7340210676 0.3603643477 0.8865366578 795 31.7600000000 0.2388150543 0.2454184028 0.8447993398 0.0160223508 0.0800620000 10332861 955859216 1765146624 -0.7392521501 0.3583756685 0.8850675821 796 31.8000000000 0.2376977354 0.2454087035 0.8447993398 0.0160266581 0.1193430000 10334115 955859216 1765146624 -0.7413238883 0.3579747975 0.8878501654 797 31.8400000000 0.2395470440 0.2454013488 0.8447993398 0.0160292655 0.1063990000 10335369 955859216 1765146624 -0.7454438806 0.3565639257 0.8870517612 798 31.8800000000 0.2387418002 0.2453930035 0.8447993398 0.0160344179 0.0713100000 10336623 955859216 1765146624 -0.7474728823 0.3546441793 0.8902698755 799 31.9200000000 0.2400965244 0.2453863746 0.8447993398 0.0160346425 0.0821400000 10337877 955859216 1765146624 -0.7514166832 0.3535146415 0.8886918426 800 31.9600000000 0.2398882955 0.2453795020 0.8447993398 0.0160327994 0.0872150000 10339131 955859216 1765146624 -0.7534942627 0.3508066535 0.8920276165 801 32.0000000000 0.2405688465 0.2453734962 0.8447993398 0.0160335380 0.0881670000 10340385 955859216 1765146624 -0.7561208606 0.3488361239 0.8942800164 802 32.0400000000 0.2407438010 0.2453677235 0.8447993398 0.0160313906 0.1068020000 10341639 955859216 1765163008 -0.7584015131 0.3474787772 0.8957471251 803 32.0800000000 0.2413953394 0.2453627766 0.8447993398 0.0160319735 0.0891030000 10342893 955859216 1765146624 -0.7599446774 0.3480121195 0.8975149393 804 32.1199999990 0.2414466888 0.2453579058 0.8447993398 0.0160343571 0.0888570000 10344147 955859216 1765146624 -0.7611476183 0.3482267857 0.8993263245 805 32.1600000000 0.2415049225 0.2453531195 0.8447993398 0.0160368187 0.1098520000 10345401 955859216 1765146624 -0.7622839212 0.3474469781 0.9017188549 806 32.2000000000 0.2435586005 0.2453508931 0.8447993398 0.0160375604 0.1044260000 10346655 955859216 1765163008 -0.7655026317 0.3460338712 0.9010612369 807 32.2400000000 0.2431455702 0.2453481603 0.8447993398 0.0160418511 0.0710370000 10347909 955859216 1765163008 -0.7657620907 0.3432981968 0.9049906731 808 32.2800000000 0.2433257401 0.2453456573 0.8447993398 0.0160407958 0.0882550000 10349163 955859216 1765163008 -0.7671126127 0.3411345780 0.9081923962 809 32.3200000000 0.2440880090 0.2453441028 0.8447993398 0.0160381915 0.0871330000 10350417 955859216 1765163008 -0.7681638598 0.3380041420 0.9111499786 810 32.3600000000 0.2450058907 0.2453436852 0.8447993398 0.0160354325 0.1069460000 10351671 955859216 1765146624 -0.7698016763 0.3353324234 0.9139232635 811 32.4000000000 0.2457518876 0.2453441886 0.8447993398 0.0160285436 0.1271000000 10352925 955859216 1765097472 -0.7716252208 0.3319248557 0.9162814021 812 32.4399999990 0.2468181252 0.2453460037 0.8447993398 0.0160220566 0.1056090000 10354179 955859216 1765130240 -0.7734580040 0.3288439512 0.9184390903 813 32.4800000000 0.2482549548 0.2453495818 0.8447993398 0.0160166256 0.0678390000 10355433 955859216 1765130240 -0.7751010656 0.3266610205 0.9213263988 814 32.5200000000 0.2491437942 0.2453542430 0.8447993398 0.0160115332 0.0868760000 10356687 955859216 1765163008 -0.7766004801 0.3243213296 0.9244844317 815 32.5600000000 0.2499787956 0.2453599173 0.8447993398 0.0160042936 0.0741530000 10357941 955859216 1765163008 -0.7782263160 0.3215402365 0.9278841615 816 32.6000000000 0.2511653900 0.2453670318 0.8447993398 0.0159982752 0.0866130000 10359195 955859216 1765163008 -0.7796595693 0.3177779913 0.9319345355 817 32.6400000000 0.2522466481 0.2453754524 0.8447993398 0.0159903582 0.1078180000 10360449 955859216 1765163008 -0.7814807296 0.3142812550 0.9355983138 818 32.6800000000 0.2536084652 0.2453855172 0.8447993398 0.0159819979 0.0954890000 10361703 955859216 1765146624 -0.7834677100 0.3113654852 0.9393662214 819 32.7200000000 0.2553550601 0.2453976900 0.8447993398 0.0159748193 0.0843580000 10362957 955859216 1765146624 -0.7854279280 0.3100045621 0.9434018135 820 32.7599999990 0.2565573156 0.2454112993 0.8447993398 0.0159684830 0.0850860000 10364211 955859216 1765146624 -0.7872756720 0.3086835146 0.9476544857 821 32.7999999990 0.2584399283 0.2454271686 0.8447993398 0.0159680211 0.0867160000 10365465 955859216 1765130240 -0.7886629701 0.3080980778 0.9530240297 822 32.8400000000 0.2591988742 0.2454439225 0.8447993398 0.0159804764 0.1085370000 10366719 955859216 1765163008 -0.7897503376 0.3072854280 0.9584258199 823 32.8800000000 0.2602097392 0.2454618639 0.8447993398 0.0159819045 0.1184330000 10367973 955859216 1765163008 -0.7913482189 0.3058154881 0.9645964503 824 32.9200000000 0.2610801756 0.2454808182 0.8447993398 0.0159895674 0.1123910000 10369227 955859216 1765163008 -0.7927421927 0.3102510571 0.9676893950 825 32.9600000000 0.2621120512 0.2455009773 0.8447993398 0.0159954657 0.0716730000 10370481 955859216 1765163008 -0.7941468358 0.3089365959 0.9746624827 826 33.0000000000 0.2644889355 0.2455239651 0.8447993398 0.0159932413 0.0816750000 10371735 955859216 1765146624 -0.7970255017 0.3092743456 0.9798330069 827 33.0400000000 0.2654707730 0.2455480846 0.8447993398 0.0160011424 0.0932150000 10372989 955859216 1765146624 -0.7986275554 0.3076255023 0.9864323139 828 33.0800000000 0.2671186626 0.2455741360 0.8447993398 0.0160112533 0.0986460000 10374243 955859216 1765146624 -0.8005651236 0.3040202260 0.9934719801 829 33.1199999990 0.2698478401 0.2456034167 0.8447993398 0.0160270392 0.1159310000 10375497 955859216 1765146624 -0.8040019870 0.3036477268 0.9978024960 830 33.1600000000 0.2715959251 0.2456347330 0.8447993398 0.0160383030 0.1288620000 10376751 955859216 1765097472 -0.8063359261 0.3017102778 1.0038164854 831 33.2000000000 0.2736692727 0.2456684689 0.8447993398 0.0160519597 0.0893930000 10378005 955859216 1765130240 -0.8082507849 0.2985371947 1.0112568140 832 33.2400000000 0.2756166160 0.2457044643 0.8447993398 0.0160600700 0.1060770000 10379259 955859216 1765130240 -0.8108478189 0.2960657775 1.0179141760 833 33.2800000000 0.2777121067 0.2457428888 0.8447993398 0.0160601562 0.0881940000 10380513 955859216 1765478400 -0.8138676882 0.2936798632 1.0250954628 834 33.3200000000 0.2797075510 0.2457836138 0.8447993398 0.0160613859 0.1079620000 10381767 955859216 1765105664 -0.8165841103 0.2904547453 1.0319299698 835 33.3600000000 0.2815038264 0.2458263925 0.8447993398 0.0160669934 0.0894850000 10383021 955859216 1765130240 -0.8196451068 0.2896933556 1.0376086235 836 33.4000000000 0.2835763097 0.2458715479 0.8447993398 0.0160722632 0.0881080000 10384275 955859216 1765146624 -0.8224664927 0.2870269716 1.0447428226 837 33.4399999990 0.2854926586 0.2459188850 0.8447993398 0.0160849600 0.0879500000 10385529 955859216 1765146624 -0.8254497051 0.2866801023 1.0504618883 838 33.4800000000 0.2872170806 0.2459681668 0.8447993398 0.0161028315 0.0877940000 10386783 955859216 1765146624 -0.8275118470 0.2828045785 1.0575083494 839 33.5200000000 0.2893543541 0.2460198786 0.8447993398 0.0161268325 0.1134420000 10388037 955859216 1765146624 -0.8300222158 0.2824811935 1.0634188652 840 33.5600000000 0.2906683683 0.2460730316 0.8447993398 0.0161381038 0.0932290000 10389291 955859216 1765146624 -0.8334994912 0.2810089588 1.0675551891 841 33.6000000000 0.2923083901 0.2461280082 0.8447993398 0.0161363217 0.0804030000 10390545 955859216 1765146624 -0.8364917040 0.2802665532 1.0725195408 842 33.6400000000 0.2926799953 0.2461832956 0.8447993398 0.0161299629 0.0847310000 10391799 955859216 1765146624 -0.8383219838 0.2780062258 1.0788122416 843 33.6800000000 0.2953705788 0.2462416435 0.8447993398 0.0161271473 0.1122620000 10393053 955859216 1765146624 -0.8418821096 0.2771278024 1.0827214718 844 33.7200000000 0.2961304188 0.2463007534 0.8447993398 0.0161267994 0.0837170000 10394307 955859216 1765146624 -0.8434125781 0.2722202539 1.0892956257 845 33.7599999990 0.2984946668 0.2463625214 0.8447993398 0.0161341105 0.0897510000 10395561 955859216 1765146624 -0.8457179666 0.2716107368 1.0936758518 846 33.7999999990 0.2998425066 0.2464257365 0.8447993398 0.0161367235 0.1015220000 10396815 955859216 1765146624 -0.8481962681 0.2704148889 1.0980128050 847 33.8400000000 0.2994643748 0.2464883559 0.8447993398 0.0161303555 0.1059140000 10398069 955859216 1765163008 -0.8487485647 0.2655957639 1.1037924290 848 33.8800000000 0.3000974357 0.2465515742 0.8447993398 0.0161213205 0.1229900000 10399323 955859216 1765097472 -0.8502992988 0.2619118989 1.1091867685 849 33.9200000000 0.3008923233 0.2466155797 0.8447993398 0.0161124329 0.0877690000 10400577 955859216 1765130240 -0.8518434763 0.2577000856 1.1137466431 850 33.9600000000 0.3021369278 0.2466808990 0.8447993398 0.0161030122 0.0877530000 10401831 955859216 1765130240 -0.8539043069 0.2543000877 1.1179820299 851 34.0000000000 0.3037139773 0.2467479179 0.8447993398 0.0160938408 0.1103610000 10403085 955859216 1765163008 -0.8564389944 0.2520754933 1.1218739748 852 34.0400000000 0.3057015836 0.2468171123 0.8447993398 0.0160852832 0.0860300000 10404339 955859216 1766526976 -0.8580262661 0.2483875602 1.1261637211 853 34.0800000000 0.3059968054 0.2468864906 0.8447993398 0.0160781859 0.0879280000 10405593 955859216 1768398848 -0.8592728972 0.2444095463 1.1304205656 854 34.1199999990 0.3066119552 0.2469564268 0.8447993398 0.0160717803 0.1272900000 10406847 955859216 1770049536 -0.8602541089 0.2419101149 1.1348949671 855 34.1600000000 0.3071912229 0.2470268768 0.8447993398 0.0160674371 0.1307660000 10408101 955859216 1771700224 -0.8604665995 0.2400408536 1.1392359734 856 34.2000000000 0.3070974946 0.2470970528 0.8447993398 0.0160611889 0.0878240000 10409355 955859216 1773477888 -0.8607786298 0.2382081151 1.1430244446 857 34.2400000000 0.3077947795 0.2471678786 0.8447993398 0.0160523843 0.0878030000 10410609 955859216 1775128576 -0.8625024557 0.2381060719 1.1455780268 858 34.2800000000 0.3091920912 0.2472401679 0.8447993398 0.0160435717 0.1083730000 10411863 955859216 1776779264 -0.8649318218 0.2374909967 1.1471209526 859 34.3200000000 0.3110352159 0.2473144345 0.8447993398 0.0160350649 0.1274570000 10413117 955859216 1778556928 -0.8663124442 0.2332223356 1.1492942572 860 34.3600000000 0.3114519119 0.2473890130 0.8447993398 0.0160260762 0.1314350000 10414371 955859216 1780207616 -0.8674058318 0.2281143367 1.1519367695 861 34.4000000000 0.3127145171 0.2474648847 0.8447993398 0.0160177334 0.0873060000 10415625 955859216 1781985280 -0.8690299392 0.2243950665 1.1549856663 862 34.4400000000 0.3138460815 0.2475418930 0.8447993398 0.0160087188 0.0882070000 10416879 955859216 1783635968 -0.8702758551 0.2207304239 1.1574263573 863 34.4800000000 0.3143202960 0.2476192724 0.8447993398 0.0160002342 0.1079670000 10418133 955859216 1785286656 -0.8707340360 0.2152642757 1.1598590612 864 34.5200000000 0.3147571981 0.2476969783 0.8447993398 0.0159918240 0.1274450000 10419387 955859216 1787064320 -0.8710743189 0.2112660557 1.1628556252 865 34.5600000000 0.3144726753 0.2477741756 0.8447993398 0.0159826424 0.1351890000 10420641 955859216 1784811520 -0.8717828393 0.2097228914 1.1651784182 866 34.6000000000 0.3145562708 0.2478512912 0.8447993398 0.0159740484 0.0863270000 10421895 955859216 1783685120 -0.8730677962 0.2087378204 1.1662309170 867 34.6400000000 0.3163876235 0.2479303412 0.8447993398 0.0159649189 0.0829360000 10423149 955859216 1782542336 -0.8746278286 0.2073337138 1.1672742367 868 34.6800000000 0.3170330822 0.2480099527 0.8447993398 0.0159568205 0.0876280000 10424403 955859216 1781510144 -0.8757991791 0.2043575794 1.1682626009 869 34.7200000000 0.3177473247 0.2480902028 0.8447993398 0.0159485207 0.1087210000 10425657 955859216 1780494336 -0.8758833408 0.2012505978 1.1700658798 870 34.7600000000 0.3169660568 0.2481693705 0.8447993398 0.0159396374 0.0875280000 10426911 955859216 1779478528 -0.8760753274 0.1983800977 1.1715662479 871 34.8000000000 0.3168183863 0.2482481868 0.8447993398 0.0159305704 0.0875940000 10428165 955859216 1778352128 -0.8768860102 0.1965734363 1.1726199389 872 34.8400000000 0.3170366585 0.2483270726 0.8447993398 0.0159222255 0.0871830000 10429419 955859216 1777319936 -0.8781623840 0.1940655112 1.1734343767 873 34.8800000000 0.3178693652 0.2484067316 0.8447993398 0.0159139422 0.0881940000 10430673 955859216 1776304128 -0.8794233203 0.1921578348 1.1748725176 874 34.9200000000 0.3184011877 0.2484868168 0.8447993398 0.0159059608 0.0874040000 10431927 955859216 1775288320 -0.8806749582 0.1907529235 1.1760959625 875 34.9600000000 0.3187227249 0.2485670864 0.8447993398 0.0158983397 0.0866050000 10433181 955859216 1774145536 -0.8825191259 0.1909270585 1.1770877838 876 35.0000000000 0.3197033405 0.2486482922 0.8447993398 0.0158907830 0.0856590000 10434435 955859216 1775525888 -0.8841941953 0.1909568757 1.1777369976 877 35.0400000000 0.3204546273 0.2487301694 0.8447993398 0.0158819979 0.0868070000 10435689 955859216 1774510080 -0.8857797980 0.1912294477 1.1785633564 878 35.0800000000 0.3208596408 0.2488123214 0.8447993398 0.0158729488 0.1111000000 10436943 955859216 1771479040 -0.8872008920 0.1919693649 1.1791242361 879 35.1200000000 0.3212269545 0.2488947044 0.8447993398 0.0158639116 0.1132860000 10438197 955859216 1770463232 -0.8883263469 0.1916940957 1.1800327301 880 35.1600000000 0.3217288554 0.2489774705 0.8447993398 0.0158550667 0.0817740000 10439451 955859216 1769447424 -0.8895263076 0.1923983544 1.1809139252 881 35.2000000000 0.3223017752 0.2490606990 0.8447993398 0.0158463185 0.0863600000 10440705 955859216 1768431616 -0.8910327554 0.1931906343 1.1815247536 882 35.2400000000 0.3231604099 0.2491447123 0.8447993398 0.0158376372 0.1135930000 10441959 955859216 1767415808 -0.8912403584 0.1902613938 1.1827020645 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-19 06:10:45 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0722040000 9033933 955859216 1771188224 -0.0000000000 0.0000000000 -0.0000000000 2 0.0400000000 0.0003964737 0.0001982368 0.0003964737 0.0010248341 0.0860370000 9363555 955859216 1769410560 -0.0001980127 0.0036694212 0.0017793722 3 0.0800000000 0.0007566700 0.0003843812 0.0007566700 0.0018723195 0.0663810000 9365133 955859216 1768828928 -0.0019371730 -0.0019830137 0.0017652622 4 0.1200000000 0.0008909514 0.0005110237 0.0008909514 0.0023449316 0.0639210000 9366715 955859216 1767940096 -0.0023126691 -0.0007440012 0.0006165215 5 0.1600000000 0.0010882578 0.0006264706 0.0010882578 0.0042310228 0.0725400000 9368289 955859216 1767051264 -0.0001116577 0.0057229260 0.0036422110 6 0.2000000000 0.0012545865 0.0007311565 0.0012545865 0.0040549452 0.1019940000 9370199 955859216 1766162432 0.0030103859 -0.0043637548 0.0027586326 7 0.2400000000 0.0013044926 0.0008130617 0.0013044926 0.0039142341 0.0796130000 9371453 955859216 1765384192 0.0032241049 -0.0143835014 -0.0003576893 8 0.2800000000 0.0012412750 0.0008665884 0.0013044926 0.0036343695 0.0697930000 9372707 955859216 1765249024 0.0010237879 -0.0127391545 -0.0012698706 9 0.3200000000 0.0011032075 0.0008928794 0.0013044926 0.0045075067 0.0640470000 9374601 955859216 1766502400 -0.0001122485 -0.0090157390 0.0016667220 10 0.3600000000 0.0015316510 0.0009567565 0.0015316510 0.0042745869 0.0686740000 9377167 955859216 1765908480 -0.0020110516 -0.0159454308 -0.0001116242 11 0.4000000000 0.0013769809 0.0009949587 0.0015316510 0.0041148731 0.0639150000 9378421 955859216 1765130240 -0.0019420680 -0.0125515154 -0.0013928518 12 0.4400000000 0.0015508180 0.0010412804 0.0015508180 0.0041784620 0.0735690000 9379675 955859216 1765126144 -0.0009496158 -0.0024078512 0.0015381359 13 0.4800000000 0.0015484233 0.0010802913 0.0015508180 0.0040043992 0.0689280000 9380929 955859216 1765126144 0.0010158021 -0.0045428951 0.0015773703 14 0.5200000000 0.0017278782 0.0011265476 0.0017278782 0.0039614864 0.0694780000 9382183 955859216 1765142528 0.0039468389 -0.0120559931 -0.0011747052 15 0.5600000000 0.0013678342 0.0011426333 0.0017278782 0.0039245041 0.0635530000 9383437 955859216 1766506496 0.0065135527 -0.0107216723 -0.0013733283 16 0.6000000000 0.0015086863 0.0011655116 0.0017278782 0.0037999973 0.0672680000 9384691 955859216 1765879808 0.0077376012 -0.0094077131 -0.0010772251 17 0.6400000000 0.0017138193 0.0011977650 0.0017278782 0.0037011987 0.0633620000 9387225 955859216 1765146624 0.0074893832 -0.0128902178 -0.0029001629 18 0.6800000000 0.0015406918 0.0012168165 0.0017278782 0.0035930601 0.0686370000 9391103 955859216 1765142528 0.0066682249 -0.0120457904 -0.0042962395 19 0.7200000000 0.0018213419 0.0012486336 0.0018213419 0.0036639808 0.1025460000 9392357 955859216 1765142528 0.0073523675 -0.0077414983 -0.0040929336 20 0.7600000000 0.0017031844 0.0012713612 0.0018213419 0.0039405240 0.0682830000 9393611 955859216 1765011456 0.0067596775 -0.0090707196 -0.0066877143 21 0.8000000000 0.0019010345 0.0013013456 0.0019010345 0.0041286288 0.0718300000 9394865 955859216 1765015552 0.0094267000 -0.0058451067 -0.0064893793 22 0.8400000000 0.0017444509 0.0013214868 0.0019010345 0.0040644712 0.0742710000 9396119 955859216 1765015552 0.0095317280 -0.0033047311 -0.0061314558 23 0.8800000000 0.0019485595 0.0013487508 0.0019485595 0.0040391139 0.0861180000 9397373 955859216 1765142528 0.0122308657 -0.0094036153 -0.0100616179 24 0.9200000000 0.0017837159 0.0013668744 0.0019485595 0.0040296927 0.1078190000 9398627 955859216 1765142528 0.0142400842 -0.0083871139 -0.0099133095 25 0.9600000000 0.0019223528 0.0013890935 0.0019485595 0.0039468976 0.0727200000 9399881 955859216 1765142528 0.0143090645 -0.0110609801 -0.0129512083 26 1.0000000000 0.0019205249 0.0014095332 0.0019485595 0.0038678987 0.1168640000 9401135 955859216 1765150720 0.0126443841 -0.0114827855 -0.0139688756 27 1.0400000000 0.0020354348 0.0014327147 0.0020354348 0.0038071458 0.0676670000 9402389 955859216 1765150720 0.0137112737 -0.0154176550 -0.0164140034 28 1.0800000000 0.0020118493 0.0014533981 0.0020354348 0.0037396344 0.0680310000 9403643 955859216 1765150720 0.0125817703 -0.0176332183 -0.0178439841 29 1.1200000000 0.0020275055 0.0014731949 0.0020354348 0.0037609092 0.0824790000 9404897 955859216 1765019648 0.0137594966 -0.0196812842 -0.0190365706 30 1.1600000000 0.0018738803 0.0014865511 0.0020354348 0.0037300503 0.0679640000 9406151 955859216 1765023744 0.0169760324 -0.0189730432 -0.0194333661 31 1.2000000000 0.0021686514 0.0015085543 0.0021686514 0.0037375704 0.0730700000 9407405 955859216 1766387712 0.0218944084 -0.0174390413 -0.0208298303 32 1.2400000000 0.0018978072 0.0015207185 0.0021686514 0.0037828141 0.0925750000 9408659 955859216 1765109760 0.0221814327 -0.0146377645 -0.0219471995 33 1.2800000000 0.0021813570 0.0015407378 0.0021813570 0.0040306445 0.0697430000 9412473 955859216 1766498304 0.0235123895 -0.0102614434 -0.0220305566 34 1.3200000000 0.0022212907 0.0015607541 0.0022212907 0.0042431123 0.0749840000 9418975 955859216 1766014976 0.0317841060 -0.0078274840 -0.0243424047 35 1.3600000000 0.0021220490 0.0015767911 0.0022212907 0.0041835418 0.0799370000 9420229 955859216 1764986880 0.0309609324 -0.0092367744 -0.0259304568 36 1.4000000000 0.0021566970 0.0015928996 0.0022212907 0.0041339966 0.0643130000 9421483 955859216 1764986880 0.0313503407 -0.0115103107 -0.0293313712 37 1.4400000000 0.0021417965 0.0016077346 0.0022212907 0.0040771848 0.0673970000 9422737 955859216 1764765696 0.0339528397 -0.0126083707 -0.0316066258 38 1.4800000000 0.0021792697 0.0016227750 0.0022212907 0.0040224050 0.0659840000 9423991 955859216 1764765696 0.0338554271 -0.0126130506 -0.0318749547 39 1.5200000000 0.0021544506 0.0016364077 0.0022212907 0.0039948045 0.0683340000 9425245 955859216 1764880384 0.0346421637 -0.0119017381 -0.0328091010 40 1.5600000000 0.0021415683 0.0016490367 0.0022212907 0.0041943499 0.0649050000 9426499 955859216 1765007360 0.0376228467 -0.0116060777 -0.0336479694 41 1.6000000000 0.0023739089 0.0016667166 0.0023739089 0.0044601259 0.0730080000 9427753 955859216 1766752256 0.0432815664 -0.0096338540 -0.0342823118 42 1.6400000000 0.0022488814 0.0016805776 0.0023739089 0.0044224867 0.0633270000 9429007 955859216 1766248448 0.0436248444 -0.0098959599 -0.0355477110 43 1.6800000000 0.0022471277 0.0016937532 0.0023739089 0.0044088619 0.0680640000 9430261 955859216 1765646336 0.0454254933 -0.0100816265 -0.0370683186 44 1.7200000000 0.0022016554 0.0017052964 0.0023739089 0.0043790332 0.1008650000 9431515 955859216 1765142528 0.0473883450 -0.0092306826 -0.0372776091 45 1.7600000000 0.0021554278 0.0017152994 0.0023739089 0.0045664906 0.0669830000 9432769 955859216 1765625856 0.0492111519 -0.0076891240 -0.0384234749 46 1.8000000000 0.0022332266 0.0017265586 0.0023739089 0.0046601193 0.0670870000 9434023 955859216 1765146624 0.0507033616 -0.0068474663 -0.0391074717 47 1.8400000000 0.0021564947 0.0017357062 0.0023739089 0.0046660033 0.0659420000 9435277 955859216 1765150720 0.0524218120 -0.0044704438 -0.0395061634 48 1.8800000000 0.0021656563 0.0017446635 0.0023739089 0.0046522413 0.0772940000 9436531 955859216 1765150720 0.0543592125 -0.0033002293 -0.0393027924 49 1.9200000000 0.0022826267 0.0017556424 0.0023739089 0.0046843733 0.0719200000 9437785 955859216 1765150720 0.0554847978 -0.0054863165 -0.0411574021 50 1.9600000000 0.0023294140 0.0017671178 0.0023739089 0.0046582463 0.0728960000 9439039 955859216 1765150720 0.0509143844 -0.0034912154 -0.0431830660 51 2.0000000000 0.0022781754 0.0017771385 0.0023739089 0.0046557472 0.0682820000 9440293 955859216 1766514688 0.0501321554 0.0006886342 -0.0423179269 52 2.0400000000 0.0023752227 0.0017886401 0.0023752227 0.0046303886 0.0646110000 9441547 955859216 1766170624 0.0501671582 -0.0009892872 -0.0425419323 53 2.0800000000 0.0024665606 0.0018014311 0.0024665606 0.0045968050 0.0693740000 9442801 955859216 1765281792 0.0504418798 -0.0051486460 -0.0448369682 54 2.1200000000 0.0022520192 0.0018097753 0.0024665606 0.0046180501 0.0633340000 9444055 955859216 1765019648 0.0507741943 -0.0043558381 -0.0444344468 55 2.1600000000 0.0022019017 0.0018169049 0.0024665606 0.0046104422 0.0656060000 9445309 955859216 1765007360 0.0516638644 -0.0022651884 -0.0443648472 56 2.2000000000 0.0022780627 0.0018251399 0.0024665606 0.0046185987 0.0624950000 9446563 955859216 1766498304 0.0530539788 -0.0027712672 -0.0452479422 57 2.2400000000 0.0023608189 0.0018345377 0.0024665606 0.0046352537 0.0645930000 9447817 955859216 1766125568 0.0533398241 -0.0052603870 -0.0475366004 58 2.2800000000 0.0025816835 0.0018474196 0.0025816835 0.0048068545 0.0653040000 9449071 955859216 1765535744 0.0571424849 -0.0035739541 -0.0470081642 59 2.3200000000 0.0026137498 0.0018604082 0.0026137498 0.0049675110 0.0734630000 9450325 955859216 1765015552 0.0609207638 -0.0007790870 -0.0477230400 60 2.3600000000 0.0026350468 0.0018733188 0.0026350468 0.0050175128 0.0678230000 9451579 955859216 1765023744 0.0642536059 -0.0051179249 -0.0503242016 61 2.4000000000 0.0025815743 0.0018849296 0.0026350468 0.0050068593 0.0646970000 9452833 955859216 1766498304 0.0640261918 -0.0078493254 -0.0517079309 62 2.4400000000 0.0024188643 0.0018935414 0.0026350468 0.0050512371 0.0619930000 9454087 955859216 1766277120 0.0660937503 -0.0071658487 -0.0511834584 63 2.4800000000 0.0026886149 0.0019061617 0.0026886149 0.0050877789 0.0689830000 9455341 955859216 1765646336 0.0724301264 -0.0050379201 -0.0512465462 64 2.5200000000 0.0026779049 0.0019182201 0.0026886149 0.0050635768 0.0626030000 9456595 955859216 1765142528 0.0747876093 -0.0091710296 -0.0551545173 65 2.5600000000 0.0024919838 0.0019270473 0.0026886149 0.0050535869 0.0744650000 9462969 955859216 1765150720 0.0759595633 -0.0087931352 -0.0549796112 66 2.6000000000 0.0025887038 0.0019370724 0.0026886149 0.0050159148 0.0615590000 9474719 955859216 1766514688 0.0728050396 -0.0126019772 -0.0567823909 67 2.6400000000 0.0024555891 0.0019448114 0.0026886149 0.0050473565 0.0635570000 9475973 955859216 1766170624 0.0730802789 -0.0143999513 -0.0585795343 68 2.6800000000 0.0027691852 0.0019569346 0.0027691852 0.0051293313 0.0659950000 9477227 955859216 1765384192 0.0783828124 -0.0166492146 -0.0590007715 69 2.7200000000 0.0023776938 0.0019630325 0.0027691852 0.0051470971 0.0610920000 9478481 955859216 1765138432 0.0797870234 -0.0166739114 -0.0601111054 70 2.7600000000 0.0027752586 0.0019746358 0.0027752586 0.0052009274 0.0672370000 9479735 955859216 1766502400 0.0824600533 -0.0145894103 -0.0608555600 71 2.8000000000 0.0027620513 0.0019857261 0.0027752586 0.0052442923 0.0649370000 9480989 955859216 1765662720 0.0849830136 -0.0138981948 -0.0625944883 72 2.8400000000 0.0023794491 0.0019911945 0.0027752586 0.0052607431 0.0647800000 9482243 955859216 1765134336 0.0865487829 -0.0147178024 -0.0634103194 73 2.8800000000 0.0027656136 0.0020018030 0.0027752586 0.0053133119 0.0702000000 9483497 955859216 1765142528 0.0893011987 -0.0116584040 -0.0657272413 74 2.9200000000 0.0028527922 0.0020133028 0.0028527922 0.0054317740 0.0710650000 9484751 955859216 1765142528 0.0912284255 -0.0117762191 -0.0687627867 75 2.9600000000 0.0028746848 0.0020247879 0.0028746848 0.0054735366 0.0645100000 9486005 955859216 1765253120 0.0968117863 -0.0118265776 -0.0702120215 76 3.0000000000 0.0028410386 0.0020355281 0.0028746848 0.0054936839 0.0667180000 9487259 955859216 1766506496 0.1002189144 -0.0103415456 -0.0719317421 77 3.0400000000 0.0022909401 0.0020388451 0.0028746848 0.0055141889 0.0628920000 9488513 955859216 1765892096 0.1028766409 -0.0105381636 -0.0728542358 78 3.0800000000 0.0029014603 0.0020499043 0.0029014603 0.0054887507 0.0657950000 9489767 955859216 1765130240 0.1061244085 -0.0120681338 -0.0764967501 79 3.1200000000 0.0028863302 0.0020604919 0.0029014603 0.0055118676 0.0665880000 9491021 955859216 1765126144 0.1098619327 -0.0106933070 -0.0769855380 80 3.1600000000 0.0028522897 0.0020703894 0.0029014603 0.0054954892 0.0653530000 9492275 955859216 1766490112 0.1136251539 -0.0110219223 -0.0798516050 81 3.2000000000 0.0029578856 0.0020813462 0.0029578856 0.0054750781 0.0620780000 9493529 955859216 1766268928 0.1192866340 -0.0123937754 -0.0814539194 82 3.2400000000 0.0029541396 0.0020919900 0.0029578856 0.0054486071 0.0660170000 9494783 955859216 1765634048 0.1233464405 -0.0138530219 -0.0837722272 83 3.2800000000 0.0021368372 0.0020925303 0.0029578856 0.0054315966 0.0617580000 9496037 955859216 1765134336 0.1247448847 -0.0148216216 -0.0857051685 84 3.3200000000 0.0029296493 0.0021024960 0.0029578856 0.0054118355 0.0670530000 9497291 955859216 1765142528 0.1314385384 -0.0143910963 -0.0886922926 85 3.3600000000 0.0029079581 0.0021119720 0.0029578856 0.0053824390 0.0998650000 9498545 955859216 1765142528 0.1419905573 -0.0111302054 -0.0887692943 86 3.4000000000 0.0018632088 0.0021090794 0.0029578856 0.0054087901 0.0652160000 9499799 955859216 1766617088 0.1440512687 -0.0102040842 -0.0908344984 87 3.4400000000 0.0017785887 0.0021052807 0.0029578856 0.0054056293 0.0690370000 9501053 955859216 1766268928 0.1459871978 -0.0104995137 -0.0936284959 88 3.4800000000 0.0029094936 0.0021144195 0.0029578856 0.0053775309 0.0682490000 9502307 955859216 1765785600 0.1522599012 -0.0068477080 -0.0946399644 89 3.5200000000 0.0019465598 0.0021125334 0.0029578856 0.0053573254 0.0775770000 9503561 955859216 1765011456 0.1546697915 -0.0074859844 -0.0956151187 90 3.5600000000 0.0017897384 0.0021089468 0.0029578856 0.0053300538 0.0576100000 9504815 955859216 1764966400 0.1575296074 -0.0075640557 -0.0970887318 91 3.6000000000 0.0028626488 0.0021172292 0.0029578856 0.0053759869 0.0740520000 9506069 955859216 1764999168 0.1644352973 -0.0060109198 -0.0983099192 92 3.6400000000 0.0029079127 0.0021258236 0.0029578856 0.0054525597 0.0851640000 9507323 955859216 1765134336 0.1738368869 -0.0032049040 -0.0982882529 93 3.6800000000 0.0028885726 0.0021340252 0.0029578856 0.0054676889 0.0895530000 9508577 955859216 1765134336 0.1819677651 0.0007760535 -0.0997459516 94 3.7200000000 0.0030095149 0.0021433390 0.0030095149 0.0054440368 0.0809460000 9509831 955859216 1765134336 0.1903076917 0.0002307770 -0.1023093611 95 3.7600000000 0.0030285737 0.0021526572 0.0030285737 0.0054166524 0.0561050000 9511085 955859216 1765134336 0.1964401901 0.0002241214 -0.1047849432 96 3.8000000000 0.0030947537 0.0021624707 0.0030947537 0.0054015507 0.0630000000 9512339 955859216 1766498304 0.2039292902 -0.0009804294 -0.1067662314 97 3.8400000000 0.0030657353 0.0021717827 0.0030947537 0.0053757746 0.0630740000 9513593 955859216 1766027264 0.2118447125 0.0004736669 -0.1098676398 98 3.8800000000 0.0031389061 0.0021816513 0.0031389061 0.0053490489 0.0630810000 9514847 955859216 1765138432 0.2203864753 0.0006245929 -0.1106910184 99 3.9200000000 0.0031565423 0.0021914987 0.0031565423 0.0053590958 0.0632760000 9516101 955859216 1765134336 0.2286100090 0.0000092317 -0.1125916168 100 3.9600000000 0.0031909086 0.0022014928 0.0031909086 0.0053340354 0.0601160000 9517355 955859216 1766498304 0.2362661809 0.0004286054 -0.1130127013 101 4.0000000000 0.0031627517 0.0022110102 0.0031909086 0.0053234834 0.0625540000 9518609 955859216 1766121472 0.2448983341 0.0025024395 -0.1143310964 102 4.0400000000 0.0019671363 0.0022086193 0.0031909086 0.0053441488 0.0567930000 9519863 955859216 1765629952 0.2483469695 0.0012819488 -0.1158789471 103 4.0800000000 0.0031187828 0.0022174558 0.0031909086 0.0053182971 0.0655540000 9521117 955859216 1765126144 0.2576094866 0.0051739514 -0.1156243756 104 4.1200000000 0.0031615330 0.0022265335 0.0031909086 0.0052936423 0.0601050000 9522371 955859216 1766498304 0.2680411637 0.0078430185 -0.1163266227 105 4.1600000000 0.0032033180 0.0022358362 0.0032033180 0.0052856960 0.0633020000 9523625 955859216 1765982208 0.2746466994 0.0092122220 -0.1165761501 106 4.2000000000 0.0032599829 0.0022454980 0.0032599829 0.0052980395 0.0713750000 9524879 955859216 1765249024 0.2815700471 0.0075210924 -0.1191007569 107 4.2400000000 0.0032767053 0.0022551354 0.0032767053 0.0052752727 0.0752880000 9526133 955859216 1765150720 0.2894918919 0.0065994593 -0.1203111410 108 4.2800000000 0.0032629024 0.0022644666 0.0032767053 0.0052589361 0.0630820000 9527387 955859216 1765150720 0.2981471419 0.0067544635 -0.1220761240 109 4.3200000000 0.0034410600 0.0022752610 0.0034410600 0.0052390342 0.0739750000 9528641 955859216 1766514688 0.3153162599 0.0065666614 -0.1246552020 110 4.3600000000 0.0032959695 0.0022845402 0.0034410600 0.0052354765 0.0787150000 9529895 955859216 1766129664 0.3273371458 0.0074717710 -0.1253701746 111 4.4000000000 0.0033535543 0.0022941710 0.0034410600 0.0052119696 0.0862740000 9531149 955859216 1765621760 0.3371150792 0.0067730010 -0.1270636320 112 4.4400000000 0.0026052659 0.0022969486 0.0034410600 0.0051918096 0.0608580000 9532403 955859216 1765875712 0.3409542441 0.0028861833 -0.1290736198 113 4.4800000000 0.0033019157 0.0023058421 0.0034410600 0.0051694590 0.0971140000 9533657 955859216 1765212160 0.3518323600 0.0019478016 -0.1304065138 114 4.5200000000 0.0033179468 0.0023147202 0.0034410600 0.0051533311 0.0663490000 9534911 955859216 1765625856 0.3628003895 0.0018474481 -0.1312976331 115 4.5600000000 0.0033476572 0.0023237023 0.0034410600 0.0051405060 0.0592000000 9536165 955859216 1765150720 0.3727871180 -0.0000067204 -0.1325944513 116 4.6000000000 0.0033988759 0.0023329710 0.0034410600 0.0051203996 0.0667530000 9537419 955859216 1765134336 0.3806814849 -0.0029324014 -0.1341947168 117 4.6400000000 0.0034140407 0.0023422109 0.0034410600 0.0051249410 0.0886660000 9538673 955859216 1765134336 0.3881574571 -0.0054502799 -0.1353449523 118 4.6800000000 0.0033855443 0.0023510527 0.0034410600 0.0051382134 0.0633430000 9539927 955859216 1765150720 0.3974285126 -0.0055677965 -0.1357127130 119 4.7200000000 0.0033989626 0.0023598587 0.0034410600 0.0051767067 0.0547840000 9541181 955859216 1766514688 0.4115526080 -0.0048878985 -0.1338303834 120 4.7600000000 0.0034067135 0.0023685825 0.0034410600 0.0051552768 0.1081450000 9542435 955859216 1766027264 0.4228001535 -0.0029966999 -0.1324208081 121 4.8000000000 0.0035076761 0.0023779965 0.0035076761 0.0051508058 0.0909880000 9543689 955859216 1767387136 0.4312426746 -0.0040894095 -0.1339141279 122 4.8400000000 0.0035111033 0.0023872843 0.0035111033 0.0051497656 0.0638370000 9544943 955859216 1769275392 0.4402815998 -0.0036227480 -0.1344348788 123 4.8800000000 0.0035222212 0.0023965114 0.0035222212 0.0051296151 0.0822700000 9546197 955859216 1770926080 0.4517479539 -0.0013660918 -0.1324640661 124 4.9200000000 0.0036482699 0.0024066062 0.0036482699 0.0051102551 0.0586120000 9547451 955859216 1772703744 0.4582377970 0.0001586787 -0.1292470992 125 4.9600000000 0.0036994144 0.0024169487 0.0036994144 0.0051019939 0.0617170000 9548705 955859216 1774354432 0.4616680145 -0.0000552274 -0.1277971864 126 5.0000000000 0.0036544323 0.0024267700 0.0036994144 0.0050878956 0.0684190000 9549959 955859216 1776005120 0.4709730148 -0.0000285106 -0.1260663718 127 5.0400000000 0.0036927306 0.0024367382 0.0036994144 0.0050706163 0.0705930000 9551213 955859216 1777782784 0.4811802208 -0.0001645628 -0.1238933951 128 5.0800000000 0.0036904442 0.0024465327 0.0036994144 0.0050647352 0.0857470000 9552467 955859216 1779433472 0.4930640459 0.0010933354 -0.1205558479 129 5.1200000000 0.0037163780 0.0024563765 0.0037163780 0.0050574333 0.0710660000 9563961 955859216 1781084160 0.5042033792 0.0024255870 -0.1170093864 130 5.1600000000 0.0037831494 0.0024665825 0.0037831494 0.0050394655 0.0723240000 9586207 955859216 1782861824 0.5108797550 0.0033522449 -0.1145469248 131 5.2000000000 0.0039220070 0.0024776926 0.0039220070 0.0050739812 0.0854670000 9587461 955859216 1784512512 0.5175790191 0.0026664757 -0.1114240140 132 5.2400000000 0.0038319093 0.0024879518 0.0039220070 0.0050600503 0.0675850000 9588715 955859216 1786290176 0.5283151865 0.0030644853 -0.1076141894 133 5.2800000000 0.0038391785 0.0024981114 0.0039220070 0.0050409861 0.0653170000 9589969 955859216 1787940864 0.5389289260 0.0039468938 -0.1031931043 134 5.3200000000 0.0039294655 0.0025087931 0.0039294655 0.0050882466 0.0893280000 9591223 955859216 1787068416 0.5475175977 0.0037419677 -0.1005036682 135 5.3600000000 0.0039013908 0.0025191087 0.0039294655 0.0051021987 0.0659760000 9592477 955859216 1785655296 0.5573112965 0.0046911221 -0.0970838517 136 5.4000000000 0.0040616114 0.0025304506 0.0040616114 0.0051291933 0.0697280000 9593731 955859216 1784553472 0.5714329481 0.0125616863 -0.0908373818 137 5.4400000000 0.0038923318 0.0025403913 0.0040616114 0.0051257299 0.0566340000 9594985 955859216 1783668736 0.5766453147 0.0160931479 -0.0870523751 138 5.4800000000 0.0040265187 0.0025511604 0.0040616114 0.0051713639 0.0849200000 9596239 955859216 1782640640 0.5802239180 0.0152858924 -0.0841877237 139 5.5200000000 0.0039084186 0.0025609248 0.0040616114 0.0051529217 0.0767510000 9597493 955859216 1781755904 0.5890896916 0.0157741122 -0.0792167783 140 5.5600000000 0.0039169970 0.0025706111 0.0040616114 0.0051364220 0.0681410000 9598747 955859216 1780736000 0.5975167155 0.0169994012 -0.0740929395 141 5.6000000000 0.0039258306 0.0025802225 0.0040616114 0.0051183745 0.0974460000 9600001 955859216 1779867648 0.6061505079 0.0179664381 -0.0692376047 142 5.6400000000 0.0039410382 0.0025898058 0.0040616114 0.0051034724 0.0625290000 9601255 955859216 1778978816 0.6170780659 0.0184272379 -0.0640327781 143 5.6800000000 0.0039689695 0.0025994503 0.0040616114 0.0050935559 0.0692560000 9602509 955859216 1778089984 0.6261461377 0.0204022620 -0.0587844290 144 5.7200000000 0.0040531172 0.0026095452 0.0040616114 0.0051120781 0.0624560000 9603763 955859216 1779453952 0.6321468353 0.0205442905 -0.0543447509 145 5.7600000000 0.0040008686 0.0026191405 0.0040616114 0.0050992250 0.0698820000 9605017 955859216 1778831360 0.6401079893 0.0209253300 -0.0490521193 146 5.8000000000 0.0039835623 0.0026284859 0.0040616114 0.0050840666 0.0595930000 9606271 955859216 1777909760 0.6499031186 0.0223864168 -0.0428852737 147 5.8400000000 0.0039231624 0.0026372932 0.0040616114 0.0050668146 0.0675900000 9607525 955859216 1777074176 0.6592577100 0.0262552686 -0.0367677808 148 5.8800000000 0.0040878579 0.0026470943 0.0040878579 0.0050900867 0.0647580000 9608779 955859216 1778434048 0.6635408998 0.0261688456 -0.0320651531 149 5.9200000000 0.0040214923 0.0026563184 0.0040878579 0.0050753902 0.0696430000 9610033 955859216 1777963008 0.6692844629 0.0255281106 -0.0276741385 150 5.9600000000 0.0039024672 0.0026646261 0.0040878579 0.0050807189 0.0585880000 9611287 955859216 1776926720 0.6772238612 0.0284982491 -0.0216741282 151 6.0000000000 0.0038618294 0.0026725546 0.0040878579 0.0050776251 0.0688270000 9612541 955859216 1776058368 0.6849858165 0.0306878835 -0.0169175565 152 6.0400000000 0.0040521147 0.0026816306 0.0040878579 0.0050858790 0.0689840000 9613795 955859216 1777418240 0.6983650923 0.0303514022 -0.0079062888 153 6.0800000000 0.0039623366 0.0026900013 0.0040878579 0.0051044101 0.0776220000 9615049 955859216 1776947200 0.7060893774 0.0313360058 -0.0024995806 154 6.1200000000 0.0040326365 0.0026987197 0.0040878579 0.0050880094 0.0893940000 9616303 955859216 1776062464 0.7123168707 0.0330521911 0.0025281012 155 6.1600000000 0.0040739719 0.0027075923 0.0040878579 0.0050877464 0.0736040000 9617557 955859216 1775169536 0.7165600061 0.0331146158 0.0067737699 156 6.2000000000 0.0039869561 0.0027157933 0.0040878579 0.0051010650 0.0700910000 9618811 955859216 1774284800 0.7251743674 0.0345573872 0.0124230981 157 6.2400000000 0.0041124402 0.0027246892 0.0041124402 0.0051110645 0.1084800000 9620065 955859216 1773203456 0.7319717407 0.0357606709 0.0183873177 158 6.2800000000 0.0041151177 0.0027334893 0.0041151177 0.0051205162 0.1180970000 9621319 955859216 1772351488 0.7365779877 0.0366670005 0.0241546333 159 6.3200000000 0.0040577878 0.0027418183 0.0041151177 0.0051502584 0.0678340000 9622573 955859216 1773719552 0.7438734174 0.0387689322 0.0310120322 160 6.3600000000 0.0042759827 0.0027514068 0.0042759827 0.0052044478 0.0955960000 9623827 955859216 1775607808 0.7575187683 0.0424920879 0.0452459194 161 6.4000000000 0.0041270866 0.0027599514 0.0042759827 0.0052293079 0.0783050000 9625081 955859216 1777258496 0.7614268661 0.0448197015 0.0521177426 162 6.4400000000 0.0040249685 0.0027677601 0.0042759827 0.0052193202 0.0585090000 9626335 955859216 1779036160 0.7664766908 0.0471830703 0.0598546639 163 6.4800000000 0.0039739530 0.0027751601 0.0042759827 0.0052283358 0.0621700000 9627589 955859216 1780686848 0.7729184031 0.0480247810 0.0679446459 164 6.5200000000 0.0039499374 0.0027823234 0.0042759827 0.0052388214 0.0586700000 9628843 955859216 1782464512 0.7806518674 0.0479381420 0.0760326460 165 6.5600000000 0.0039530434 0.0027894186 0.0042759827 0.0052453984 0.0617360000 9630097 955859216 1784115200 0.7893399596 0.0507139303 0.0848535821 166 6.6000000000 0.0039779129 0.0027965782 0.0042759827 0.0052677403 0.0666900000 9631351 955859216 1785765888 0.7973413467 0.0546767376 0.0939095095 167 6.6400000000 0.0040503116 0.0028040856 0.0042759827 0.0053187333 0.0689620000 9632605 955859216 1787543552 0.8017301559 0.0566054955 0.1020730138 168 6.6800000000 0.0039044304 0.0028106353 0.0042759827 0.0053232030 0.0588820000 9633859 955859216 1786654720 0.8086909056 0.0589824915 0.1108879596 169 6.7200000000 0.0039320015 0.0028172706 0.0042759827 0.0053171780 0.0619350000 9635113 955859216 1785765888 0.8174921870 0.0635496303 0.1214936674 170 6.7600000000 0.0039296257 0.0028238139 0.0042759827 0.0053306624 0.0553980000 9636367 955859216 1784913920 0.8231589198 0.0649644434 0.1297670603 171 6.8000000000 0.0039502764 0.0028304014 0.0042759827 0.0053151646 0.0646550000 9637621 955859216 1783918592 0.8325690627 0.0677875951 0.1400102079 172 6.8400000000 0.0040445398 0.0028374603 0.0042759827 0.0052996957 0.0949590000 9638875 955859216 1783025664 0.8407451510 0.0704881251 0.1502685547 173 6.8800000000 0.0039885249 0.0028441139 0.0042759827 0.0052848796 0.0700880000 9640129 955859216 1781989376 0.8445386291 0.0704648271 0.1574927270 174 6.9200000000 0.0039222199 0.0028503099 0.0042759827 0.0052772130 0.1079100000 9641383 955859216 1781121024 0.8528720140 0.0726886019 0.1672851443 175 6.9600000000 0.0038990832 0.0028563029 0.0042759827 0.0052650719 0.0658900000 9642637 955859216 1782480896 0.8625801802 0.0764524862 0.1777729541 176 7.0000000000 0.0040658722 0.0028631754 0.0042759827 0.0052501961 0.0597560000 9643891 955859216 1781735424 0.8695573807 0.0790079013 0.1876990646 177 7.0400000000 0.0040227259 0.0028697266 0.0042759827 0.0052897652 0.0875590000 9645145 955859216 1780867072 0.8742182851 0.0788906813 0.1958875358 178 7.0800000000 0.0039778715 0.0028759521 0.0042759827 0.0053180168 0.0704360000 9646399 955859216 1779978240 0.8784900904 0.0788909122 0.2037301362 179 7.1200000000 0.0039420985 0.0028819082 0.0042759827 0.0053037161 0.0604220000 9647653 955859216 1779089408 0.8844857812 0.0814167783 0.2129354477 180 7.1600000000 0.0038196980 0.0028871182 0.0042759827 0.0052943596 0.0728250000 9648907 955859216 1778184192 0.8906505704 0.0827514827 0.2220864594 181 7.2000000000 0.0039293207 0.0028928762 0.0042759827 0.0052798672 0.0904930000 9650161 955859216 1777311744 0.8945619464 0.0835353062 0.2309063971 182 7.2400000000 0.0037111037 0.0028973719 0.0042759827 0.0052665473 0.0689240000 9651415 955859216 1778671616 0.9001384377 0.0853678957 0.2395828962 183 7.2800000000 0.0037541213 0.0029020536 0.0042759827 0.0052522824 0.0656600000 9652669 955859216 1778036736 0.9054355025 0.0875913277 0.2489496469 184 7.3200000000 0.0036402030 0.0029060653 0.0042759827 0.0052447220 0.1022210000 9653923 955859216 1776930816 0.9108104110 0.0882339031 0.2565333843 185 7.3600000000 0.0021539063 0.0029019996 0.0042759827 0.0052407464 0.0668570000 9655177 955859216 1776640000 0.9126283526 0.0875076503 0.2631361783 186 7.4000000000 0.0036190671 0.0029058548 0.0042759827 0.0052266680 0.0570990000 9656431 955859216 1775534080 0.9199718237 0.0894029438 0.2720215619 187 7.4400000000 0.0037115146 0.0029101631 0.0042759827 0.0052258911 0.0822420000 9657685 955859216 1774645248 0.9250248075 0.0904687271 0.2793034315 188 7.4800000000 0.0037965048 0.0029148777 0.0042759827 0.0052125690 0.1099630000 9658939 955859216 1773756416 0.9292524457 0.0913882777 0.2859683931 189 7.5200000000 0.0027752782 0.0029141391 0.0042759827 0.0052009234 0.0734880000 9660193 955859216 1772867584 0.9313461781 0.0908836499 0.2925774455 190 7.5600000000 0.0037234672 0.0029183987 0.0042759827 0.0051951408 0.0618200000 9661447 955859216 1771962368 0.9374621511 0.0919825584 0.3004239202 191 7.6000000000 0.0039498433 0.0029237989 0.0042759827 0.0051852182 0.0724460000 9662701 955859216 1771089920 0.9414781928 0.0939286873 0.3085876703 192 7.6400000000 0.0041104620 0.0029299795 0.0042759827 0.0051720813 0.0895270000 9663955 955859216 1770311680 0.9444394708 0.0955025852 0.3169963360 193 7.6800000000 0.0043576001 0.0029373765 0.0043576001 0.0051595660 0.0850630000 9665209 955859216 1771687936 0.9501524568 0.0974030793 0.3323278725 194 7.7200000000 0.0041186386 0.0029434655 0.0043576001 0.0051461892 0.0629240000 9666463 955859216 1770799104 0.9535640478 0.0998417735 0.3411477208 195 7.7600000000 0.0040604901 0.0029491938 0.0043576001 0.0051330532 0.0708930000 9667717 955859216 1770201088 0.9582284093 0.1014356837 0.3597716093 196 7.8000000000 0.0043727537 0.0029564569 0.0043727537 0.0051258807 0.0695250000 9668971 955859216 1769422848 0.9588940740 0.1004482955 0.3683651388 197 7.8400000000 0.0043604965 0.0029635840 0.0043727537 0.0051139916 0.0707170000 9670225 955859216 1768550400 0.9614732265 0.1012455449 0.3785589337 198 7.8800000000 0.0044420916 0.0029710512 0.0044420916 0.0051011205 0.0633340000 9671479 955859216 1769910272 0.9636173844 0.1019203216 0.3895007670 199 7.9200000000 0.0045093307 0.0029787812 0.0045093307 0.0050958268 0.0688410000 9672733 955859216 1769312256 0.9638144970 0.1010632142 0.3995245397 200 7.9600000000 0.0045341142 0.0029865579 0.0045341142 0.0050849696 0.0695010000 9673987 955859216 1768534016 0.9659753442 0.1019096598 0.4104843140 201 8.0000000000 0.0041579385 0.0029923856 0.0045341142 0.0050734664 0.0727940000 9675241 955859216 1767608320 0.9679573774 0.1017009690 0.4221283495 202 8.0400000000 0.0041489410 0.0029981112 0.0045341142 0.0050616105 0.0790990000 9676495 955859216 1766756352 0.9676931500 0.1020480543 0.4324425161 203 8.0800000000 0.0041622058 0.0030038456 0.0045341142 0.0050493897 0.0700570000 9677749 955859216 1768124416 0.9675445557 0.1023536846 0.4431102574 204 8.1200000000 0.0041458108 0.0030094435 0.0045341142 0.0050401226 0.0690250000 9679003 955859216 1767653376 0.9676736593 0.1037573591 0.4538049996 205 8.1600000000 0.0041777077 0.0030151423 0.0045341142 0.0050515614 0.0756190000 9680257 955859216 1766768640 0.9688224792 0.1055767387 0.4655368626 206 8.1999999990 0.0041865846 0.0030208290 0.0045341142 0.0050585837 0.0876930000 9681511 955859216 1765875712 0.9694786072 0.1077083871 0.4777146578 207 8.2400000000 0.0042024944 0.0030265375 0.0045341142 0.0050543261 0.1146290000 9682765 955859216 1765097472 0.9703602791 0.1100945547 0.4905156493 208 8.2799999990 0.0041924696 0.0030321429 0.0045341142 0.0050549765 0.0880930000 9684019 955859216 1764950016 0.9700275660 0.1131498367 0.5022574663 209 8.3200000000 0.0046434100 0.0030398523 0.0046434100 0.0050502486 0.0743860000 9685273 955859216 1764950016 0.9706338644 0.1147644445 0.5137469172 210 8.3599999990 0.0042373165 0.0030455546 0.0046434100 0.0050387574 0.0739850000 9686527 955859216 1764446208 0.9708842039 0.1162248626 0.5259901881 211 8.4000000000 0.0042182836 0.0030511125 0.0046434100 0.0050348658 0.1128600000 9687781 955859216 1765060608 0.9713106155 0.1183398664 0.5383681059 212 8.4399999990 0.0042273761 0.0030566609 0.0046434100 0.0050279573 0.0970630000 9689035 955859216 1766457344 0.9703744054 0.1200894862 0.5507295132 213 8.4800000000 0.0042188037 0.0030621170 0.0046434100 0.0050200421 0.0867270000 9690289 955859216 1768361984 0.9690973163 0.1220656931 0.5622525215 214 8.5200000000 0.0042094090 0.0030674782 0.0046434100 0.0050157222 0.0783280000 9691543 955859216 1770139648 0.9683660269 0.1242424175 0.5735747218 215 8.5600000000 0.0042208694 0.0030728428 0.0046434100 0.0050066584 0.0758560000 9692797 955859216 1771790336 0.9685183167 0.1274841130 0.5857228041 216 8.6000000000 0.0041973386 0.0030780488 0.0046434100 0.0049981312 0.1058420000 9694051 955859216 1773441024 0.9691624641 0.1297062486 0.5980755687 217 8.6400000000 0.0041950401 0.0030831962 0.0046434100 0.0049914749 0.0839170000 9695305 955859216 1775218688 0.9680318236 0.1312970370 0.6089679003 218 8.6800000000 0.0041856491 0.0030882533 0.0046434100 0.0049861717 0.0743500000 9696559 955859216 1776869376 0.9663401246 0.1328057498 0.6196507215 219 8.7200000000 0.0041815103 0.0030932454 0.0046434100 0.0049794200 0.0746830000 9697813 955859216 1778520064 0.9635617137 0.1338527352 0.6299829483 220 8.7600000000 0.0041860947 0.0030982129 0.0046434100 0.0049698215 0.0765410000 9699067 955859216 1780297728 0.9602384567 0.1341667473 0.6395568252 221 8.8000000000 0.0041831685 0.0031031222 0.0046434100 0.0049589892 0.0792310000 9700321 955859216 1781948416 0.9605851173 0.1364943087 0.6516378522 222 8.8400000000 0.0041790260 0.0031079686 0.0046434100 0.0049499218 0.1131650000 9701575 955859216 1783599104 0.9589862823 0.1371854693 0.6623795629 223 8.8800000000 0.0045888023 0.0031146091 0.0046434100 0.0049389187 0.0760960000 9702829 955859216 1785376768 0.9566648006 0.1372220069 0.6717525721 224 8.9200000000 0.0041810847 0.0031193701 0.0046434100 0.0049285476 0.0786290000 9704083 955859216 1787027456 0.9545747638 0.1377476454 0.6823624969 225 8.9600000000 0.0043956288 0.0031250424 0.0046434100 0.0049213548 0.0910800000 9705337 955859216 1786286080 0.9545756578 0.1393942088 0.6935669780 226 9.0000000000 0.0041681244 0.0031296578 0.0046434100 0.0049108443 0.0774520000 9706591 955859216 1785266176 0.9553623796 0.1416764557 0.7155781984 227 9.0400000000 0.0044229510 0.0031353551 0.0046434100 0.0048999755 0.0753660000 9707845 955859216 1783480320 0.9558579326 0.1438657492 0.7261586189 228 9.0800000000 0.0044649569 0.0031411867 0.0046434100 0.0048908295 0.0866280000 9709099 955859216 1782345728 0.9534621835 0.1454354525 0.7351948023 229 9.1200000000 0.0044270828 0.0031468020 0.0046434100 0.0049023718 0.0695610000 9710353 955859216 1781710848 0.9536702633 0.1471843123 0.7463586926 230 9.1600000000 0.0043631583 0.0031520905 0.0046434100 0.0048993892 0.0753090000 9711607 955859216 1780604928 0.9543003440 0.1485519856 0.7566002607 231 9.2000000000 0.0041765524 0.0031565254 0.0046434100 0.0048948833 0.1082760000 9712861 955859216 1779662848 0.9534339309 0.1498436183 0.7753649354 232 9.2400000000 0.0043580793 0.0031617045 0.0046434100 0.0048876780 0.0740600000 9714115 955859216 1777905664 0.9542878270 0.1523593515 0.7872348428 233 9.2800000000 0.0043174531 0.0031666648 0.0046434100 0.0048886951 0.0772120000 9715369 955859216 1777426432 0.9550045133 0.1549172997 0.7993031740 234 9.3200000000 0.0042971931 0.0031714961 0.0046434100 0.0048877614 0.1087050000 9716623 955859216 1776394240 0.9540495872 0.1575889438 0.8100887537 235 9.3600000000 0.0042489078 0.0031760809 0.0046434100 0.0048859123 0.0703000000 9717877 955859216 1777774592 0.9538896680 0.1588250250 0.8209257126 236 9.4000000000 0.0042160880 0.0031804877 0.0046434100 0.0048807574 0.0785100000 9719131 955859216 1779662848 0.9553182721 0.1595704556 0.8304784894 237 9.4400000000 0.0042929444 0.0031851816 0.0046434100 0.0048883294 0.0905360000 9720385 955859216 1781313536 0.9561813474 0.1621334404 0.8414689898 238 9.4800000000 0.0043091294 0.0031899040 0.0046434100 0.0048864939 0.0911710000 9721639 955859216 1783091200 0.9569595456 0.1637839824 0.8522561789 239 9.5200000000 0.0042663119 0.0031944078 0.0046434100 0.0048928141 0.0741140000 9722893 955859216 1784741888 0.9587600827 0.1659690142 0.8630261421 240 9.5600000000 0.0043277233 0.0031991300 0.0046434100 0.0048904720 0.0736720000 9724147 955859216 1786535936 0.9585380554 0.1668644845 0.8725341558 241 9.6000000000 0.0042990022 0.0032036938 0.0046434100 0.0048803405 0.0742410000 9725401 955859216 1785630720 0.9567935467 0.1683135927 0.8822663426 242 9.6400000000 0.0041362098 0.0032075471 0.0046434100 0.0048828343 0.0828780000 9726655 955859216 1784778752 0.9577980638 0.1708419919 0.8945492506 243 9.6800000000 0.0042174803 0.0032117032 0.0046434100 0.0048736410 0.0904370000 9727909 955859216 1783758848 0.9609177113 0.1731679738 0.9081038237 244 9.7200000000 0.0042126938 0.0032158057 0.0046434100 0.0048636066 0.0711370000 9729163 955859216 1782743040 0.9622687697 0.1769199222 0.9201504588 245 9.7600000000 0.0041923779 0.0032197917 0.0046434100 0.0048557827 0.0946390000 9730417 955859216 1781874688 0.9621686935 0.1777480245 0.9298100471 246 9.8000000000 0.0041653058 0.0032236352 0.0046434100 0.0048458730 0.1025730000 9731671 955859216 1780838400 0.9638277888 0.1804506034 0.9414995909 247 9.8400000000 0.0042037927 0.0032276035 0.0046434100 0.0048362230 0.0919000000 9732925 955859216 1782218752 0.9640528560 0.1831470728 0.9531674385 248 9.8800000000 0.0041219001 0.0032312095 0.0046434100 0.0048306456 0.0727130000 9734179 955859216 1784107008 0.9638868570 0.1862728745 0.9632828832 249 9.9200000000 0.0041432106 0.0032348722 0.0046434100 0.0048209414 0.0742080000 9735433 955859216 1785757696 0.9653201699 0.1874360144 0.9740312696 250 9.9600000000 0.0041505257 0.0032385348 0.0046434100 0.0048117067 0.0698610000 9736687 955859216 1787408384 0.9658702612 0.1893135905 0.9848642349 251 10.0000000000 0.0041118022 0.0032420139 0.0046434100 0.0048037626 0.0788330000 9737941 955859216 1786646528 0.9653556943 0.1901213527 0.9940453172 252 10.0400000000 0.0040190229 0.0032450973 0.0046434100 0.0047942136 0.1064270000 9739195 955859216 1784926208 0.9657801986 0.1917178035 1.0036517382 253 10.0800000000 0.0040015974 0.0032480874 0.0046434100 0.0047853747 0.0914150000 9740449 955859216 1783885824 0.9659687281 0.1935054660 1.0130643845 254 10.1200000000 0.0039561479 0.0032508751 0.0046434100 0.0047799544 0.0820970000 9741703 955859216 1785266176 0.9662506580 0.1954824328 1.0223877430 255 10.1600000000 0.0039421362 0.0032535859 0.0046434100 0.0047708874 0.0749270000 9742957 955859216 1784647680 0.9655604959 0.1972429454 1.0315556526 256 10.2000000000 0.0040178811 0.0032565714 0.0046434100 0.0047706387 0.0915460000 9744211 955859216 1783746560 0.9646630883 0.1978695691 1.0389394760 257 10.2400000000 0.0038412041 0.0032588463 0.0046434100 0.0047836901 0.0861580000 9765945 955859216 1783488512 0.9635328054 0.1997056901 1.0480170250 258 10.2800000000 0.0038110632 0.0032609866 0.0046434100 0.0047850686 0.1171080000 9809183 955859216 1780047872 0.9637444019 0.2015206367 1.0576329231 259 10.3200000000 0.0040983595 0.0032642197 0.0046434100 0.0047926914 0.1035970000 9810437 955859216 1779208192 0.9633848071 0.2025019228 1.0652652979 260 10.3600000000 0.0042131837 0.0032678696 0.0046434100 0.0047994760 0.1091430000 9811691 955859216 1778266112 0.9613284469 0.2032823414 1.0727152824 261 10.4000000000 0.0037928568 0.0032698810 0.0046434100 0.0047918349 0.0846390000 9812945 955859216 1777414144 0.9593864083 0.2059780657 1.0828535557 262 10.4400000000 0.0037989481 0.0032719004 0.0046434100 0.0047826869 0.0708190000 9814199 955859216 1776533504 0.9602748156 0.2073191404 1.0919948816 263 10.4800000000 0.0038419417 0.0032740678 0.0046434100 0.0047735811 0.1029680000 9815453 955859216 1775644672 0.9597991705 0.2089910507 1.1015843153 264 10.5200000000 0.0039766934 0.0032767293 0.0046434100 0.0047670606 0.0597410000 9816707 955859216 1774755840 0.9582095742 0.2096319795 1.1093306541 265 10.5600000000 0.0038587044 0.0032789254 0.0046434100 0.0047596489 0.0617110000 9817961 955859216 1776115712 0.9567576647 0.2098252326 1.1168675423 266 10.6000000000 0.0037770797 0.0032807982 0.0046434100 0.0047511608 0.0705180000 9819215 955859216 1775222784 0.9573810697 0.2108889073 1.1256418228 267 10.6400000000 0.0038159043 0.0032828023 0.0046434100 0.0047441570 0.0903220000 9820469 955859216 1774227456 0.9566010833 0.2122447193 1.1342653036 268 10.6800000000 0.0038248347 0.0032848248 0.0046434100 0.0047379550 0.0881350000 9821723 955859216 1773359104 0.9554643631 0.2143543363 1.1436491013 269 10.7200000000 0.0038248959 0.0032868325 0.0046434100 0.0047340105 0.0674090000 9822977 955859216 1772470272 0.9537420273 0.2151379287 1.1528518200 270 10.7600000000 0.0038187222 0.0032888025 0.0046434100 0.0047279395 0.0695730000 9824231 955859216 1771581440 0.9517043829 0.2175295353 1.1619659662 271 10.8000000000 0.0038521406 0.0032908812 0.0046434100 0.0047208263 0.1000470000 9825485 955859216 1770676224 0.9496211410 0.2194791436 1.1719069481 272 10.8400000000 0.0038631186 0.0032929851 0.0046434100 0.0047121087 0.0687050000 9826739 955859216 1769803776 0.9468187690 0.2213474810 1.1811454296 273 10.8800000000 0.0051260577 0.0032996996 0.0051260577 0.0047058859 0.0865690000 9827993 955859216 1769025536 0.9439453483 0.2226339728 1.1893192530 274 10.9200000000 0.0036703052 0.0033010522 0.0051260577 0.0046979509 0.0894410000 9829247 955859216 1768153088 0.9413281083 0.2238159031 1.2006084919 275 10.9600000000 0.0038683794 0.0033031152 0.0051260577 0.0046920903 0.0685090000 9830501 955859216 1769512960 0.9389235377 0.2275447547 1.2101019621 276 11.0000000000 0.0053424607 0.0033105041 0.0053424607 0.0046891238 0.0565960000 9831755 955859216 1768914944 0.9363201857 0.2277961969 1.2171130180 277 11.0400000000 0.0036881333 0.0033118674 0.0053424607 0.0046825638 0.0822520000 9833009 955859216 1768136704 0.9347642660 0.2289079130 1.2292981148 278 11.0800000000 0.0037045733 0.0033132800 0.0053424607 0.0046741042 0.1096050000 9834263 955859216 1767264256 0.9296919107 0.2300132364 1.2382380962 279 11.1200000000 0.0056388453 0.0033216154 0.0056388453 0.0046668603 0.0997500000 9835517 955859216 1766375424 0.9263899922 0.2313104272 1.2464015484 280 11.1600000000 0.0036981986 0.0033229603 0.0056388453 0.0046611476 0.1114210000 9836771 955859216 1765433344 0.9224576354 0.2325915098 1.2582763433 281 11.2000000000 0.0037159631 0.0033243589 0.0056388453 0.0046530703 0.0874550000 9838025 955859216 1765113856 0.9203790426 0.2363673896 1.2677216530 282 11.2400000000 0.0037224893 0.0033257707 0.0056388453 0.0046454548 0.0824480000 9839279 955859216 1765101568 0.9169465899 0.2374277562 1.2764154673 283 11.2800000000 0.0037004291 0.0033270946 0.0056388453 0.0046381041 0.1046700000 9840533 955859216 1765101568 0.9137697816 0.2405717969 1.2859818935 284 11.3200000000 0.0037202800 0.0033284790 0.0056388453 0.0046308708 0.1108100000 9841787 955859216 1766703104 0.9087991118 0.2432392538 1.2969739437 285 11.3600000000 0.0055590635 0.0033363057 0.0056388453 0.0046267985 0.0807440000 9843041 955859216 1768734720 0.9054133892 0.2450622469 1.3048361540 286 11.4000000000 0.0036857373 0.0033375274 0.0056388453 0.0046266759 0.0922950000 9844295 955859216 1770385408 0.9052704573 0.2472950816 1.3163683414 287 11.4400000000 0.0037138804 0.0033388388 0.0056388453 0.0046194438 0.0995410000 9845549 955859216 1772036096 0.9027841687 0.2507066429 1.3253593445 288 11.4800000000 0.0037193361 0.0033401600 0.0056388453 0.0046115316 0.0831290000 9846803 955859216 1773813760 0.8957222700 0.2516710460 1.3320950270 289 11.5200000000 0.0056206873 0.0033480511 0.0056388453 0.0046092616 0.0710880000 9848057 955859216 1775464448 0.8914517760 0.2516694367 1.3384225368 290 11.5600000000 0.0037170157 0.0033493233 0.0056388453 0.0046070897 0.0815460000 9849311 955859216 1777115136 0.8872513771 0.2512000501 1.3482147455 291 11.6000000000 0.0038532920 0.0033510552 0.0056388453 0.0045993827 0.0752300000 9850565 955859216 1778892800 0.8849570751 0.2537786663 1.3565167189 292 11.6400000000 0.0052244533 0.0033574709 0.0056388453 0.0045925095 0.0639460000 9851819 955859216 1780543488 0.8828924298 0.2552817166 1.3635097742 293 11.6800000000 0.0049912101 0.0033630468 0.0056388453 0.0045849906 0.0737020000 9853073 955859216 1782194176 0.8811707497 0.2570182383 1.3700911999 294 11.7200000000 0.0055178688 0.0033703762 0.0056388453 0.0045816804 0.0861340000 9854327 955859216 1783971840 0.8773813248 0.2568450570 1.3764469624 295 11.7600000000 0.0038825916 0.0033721125 0.0056388453 0.0045884341 0.0856620000 9855581 955859216 1785622528 0.8748898506 0.2564567327 1.3850293159 296 11.8000000000 0.0045693466 0.0033761572 0.0056388453 0.0046017818 0.0708800000 9856835 955859216 1787400192 0.8729727268 0.2572914064 1.3923276663 297 11.8400000000 0.0048708441 0.0033811898 0.0056388453 0.0046285163 0.0611560000 9858089 955859216 1786515456 0.8689061403 0.2573673427 1.3994581699 298 11.8800000000 0.0037083034 0.0033822875 0.0056388453 0.0046463175 0.0676150000 9859343 955859216 1785679872 0.8651060462 0.2563697100 1.4088945389 299 11.9200000000 0.0035596378 0.0033828807 0.0056388453 0.0046451978 0.0870880000 9860597 955859216 1784795136 0.8631607294 0.2559264898 1.4170758724 300 11.9600000000 0.0034924061 0.0033832457 0.0056388453 0.0046439901 0.0893240000 9861851 955859216 1783750656 0.8613804579 0.2552747726 1.4247297049 301 12.0000000000 0.0034998164 0.0033836330 0.0056388453 0.0046395887 0.0655060000 9863105 955859216 1782829056 0.8604961634 0.2559607327 1.4343068600 302 12.0400000000 0.0034610627 0.0033838894 0.0056388453 0.0046329893 0.0673290000 9864359 955859216 1781866496 0.8598186970 0.2562895715 1.4429597855 303 12.0800000000 0.0034245979 0.0033840238 0.0056388453 0.0046270514 0.0881170000 9865613 955859216 1780977664 0.8577677011 0.2555744648 1.4505199194 304 12.1200000000 0.0033822388 0.0033840179 0.0056388453 0.0046212292 0.0717530000 9866867 955859216 1779941376 0.8566557765 0.2564027905 1.4601212740 305 12.1600000000 0.0034222682 0.0033841433 0.0056388453 0.0046137742 0.0898530000 9868121 955859216 1779073024 0.8556972146 0.2574357390 1.4697622061 306 12.2000000000 0.0033518679 0.0033840378 0.0056388453 0.0046063189 0.0713860000 9869375 955859216 1780432896 0.8529841304 0.2584055662 1.4786407948 307 12.2400000000 0.0032524525 0.0033836092 0.0056388453 0.0046003877 0.0690010000 9870629 955859216 1779912704 0.8509057760 0.2601701617 1.4882478714 308 12.2800000000 0.0032299559 0.0033831103 0.0056388453 0.0045991258 0.0787770000 9871883 955859216 1779310592 0.8498524427 0.2609317899 1.4979928732 309 12.3200000000 0.0031832582 0.0033824636 0.0056388453 0.0045974138 0.0774490000 9873137 955859216 1778438144 0.8484184146 0.2615640461 1.5071241856 310 12.3600000000 0.0031781362 0.0033818044 0.0056388453 0.0046058855 0.0683770000 9874391 955859216 1777549312 0.8473824859 0.2641870975 1.5171247721 311 12.4000000000 0.0032418978 0.0033813546 0.0056388453 0.0046244176 0.0858510000 9875645 955859216 1776766976 0.8461681008 0.2664886713 1.5273379087 312 12.4400000000 0.0029715761 0.0033800412 0.0056388453 0.0046345259 0.0668070000 9876899 955859216 1775755264 0.8450943232 0.2650474310 1.5350962877 313 12.4800000000 0.0030039570 0.0033788396 0.0056388453 0.0046348078 0.0686610000 9878153 955859216 1774882816 0.8440409899 0.2662245333 1.5446983576 314 12.5200000000 0.0029874449 0.0033775932 0.0056388453 0.0046328826 0.0644050000 9879407 955859216 1776242688 0.8424503803 0.2673847079 1.5539184809 315 12.5600000000 0.0028230979 0.0033758329 0.0056388453 0.0046290894 0.0668710000 9880661 955859216 1775771648 0.8411247730 0.2682183981 1.5621087551 316 12.6000000000 0.0027390588 0.0033738178 0.0056388453 0.0046218263 0.0645450000 9881915 955859216 1774882816 0.8419890404 0.2676634490 1.5701167583 317 12.6400000000 0.0027417303 0.0033718238 0.0056388453 0.0046149842 0.0710470000 9883169 955859216 1773993984 0.8413703442 0.2688745856 1.5790820122 318 12.6800000000 0.0027818657 0.0033699686 0.0056388453 0.0046101764 0.0865460000 9884423 955859216 1773105152 0.8410918713 0.2705276310 1.5880558491 319 12.7200000000 0.0025874362 0.0033675155 0.0056388453 0.0046048549 0.0754970000 9885677 955859216 1774465024 0.8384352326 0.2731350660 1.5985645056 320 12.7600000000 0.0027572911 0.0033656085 0.0056388453 0.0046030472 0.0671290000 9886931 955859216 1773821952 0.8361713886 0.2744556665 1.6075133085 321 12.8000000000 0.0027140791 0.0033635789 0.0056388453 0.0046138867 0.0583370000 9888185 955859216 1773088768 0.8342698812 0.2764996290 1.6168384552 322 12.8400000000 0.0026301502 0.0033613011 0.0056388453 0.0046199278 0.0761820000 9889439 955859216 1772216320 0.8330714107 0.2787256539 1.6258460283 323 12.8800000000 0.0025849910 0.0033588977 0.0056388453 0.0046335160 0.1053440000 9890693 955859216 1771274240 0.8318890929 0.2801550925 1.6337947845 324 12.9200000000 0.0025293601 0.0033563374 0.0056388453 0.0046470018 0.0921160000 9891947 955859216 1770438656 0.8307344317 0.2802481949 1.6407556534 325 12.9600000000 0.0024893545 0.0033536698 0.0056388453 0.0046586614 0.0778500000 9893201 955859216 1769549824 0.8304302096 0.2806853354 1.6479516029 326 13.0000000000 0.0025028803 0.0033510600 0.0056388453 0.0046695889 0.0832040000 9894455 955859216 1768771584 0.8293935657 0.2813799381 1.6561074257 327 13.0400000000 0.0024990709 0.0033484545 0.0056388453 0.0047734688 0.0827520000 9895709 955859216 1767899136 0.8257895112 0.2859406769 1.6756454706 328 13.0800000000 0.0024929184 0.0033458462 0.0056388453 0.0047936266 0.0674390000 9896963 955859216 1769259008 0.8239612579 0.2865743041 1.6835124493 329 13.1200000000 0.0024825092 0.0033432220 0.0056388453 0.0047983026 0.0826140000 9898217 955859216 1768632320 0.8217537403 0.2875386178 1.6914502382 330 13.1600000000 0.0024900082 0.0033406365 0.0056388453 0.0047979384 0.0749740000 9899471 955859216 1767759872 0.8204968572 0.2878329754 1.6987063885 331 13.2000000000 0.0024913761 0.0033380708 0.0056388453 0.0047984271 0.0716330000 9900725 955859216 1766875136 0.8197153807 0.2877658308 1.7054468393 332 13.2400000000 0.0024702514 0.0033354569 0.0056388453 0.0047944081 0.0789720000 9901979 955859216 1766105088 0.8186008930 0.2891946435 1.7131298780 333 13.2800000000 0.0024147197 0.0033326919 0.0056388453 0.0047909040 0.0786010000 9903233 955859216 1765232640 0.8175602555 0.2906436324 1.7206363678 334 13.3200000000 0.0023950231 0.0033298845 0.0056388453 0.0047909226 0.0716730000 9904487 955859216 1765101568 0.8169733286 0.2907741070 1.7266902924 335 13.3600000000 0.0023907116 0.0033270810 0.0056388453 0.0047986762 0.0654640000 9905741 955859216 1765101568 0.8147943616 0.2936033607 1.7354093790 336 13.4000000000 0.0024008465 0.0033243244 0.0056388453 0.0048079484 0.0932920000 9906995 955859216 1765101568 0.8125028610 0.2944718003 1.7415696383 337 13.4400000000 0.0024069217 0.0033216021 0.0056388453 0.0048256140 0.0680020000 9908249 955859216 1766576128 0.8109552860 0.2937297821 1.7466825247 338 13.4800000000 0.0024133683 0.0033189150 0.0056388453 0.0048523523 0.0677100000 9909503 955859216 1766215680 0.8075112104 0.2937855422 1.7521243095 339 13.5200000000 0.0024318220 0.0033162982 0.0056388453 0.0048737586 0.0683170000 9910757 955859216 1765724160 0.8056268096 0.2954280376 1.7597163916 340 13.5600000000 0.0024245880 0.0033136755 0.0056388453 0.0048937860 0.0654410000 9912011 955859216 1765109760 0.8011302948 0.2956114113 1.7654169798 341 13.6000000000 0.0024264776 0.0033110738 0.0056388453 0.0049068072 0.0575020000 9913265 955859216 1766465536 0.7974378467 0.2966489792 1.7726858854 342 13.6400000000 0.0024348937 0.0033085119 0.0056388453 0.0049149264 0.0736750000 9914519 955859216 1765994496 0.7938013673 0.2988479137 1.7808003426 343 13.6800000000 0.0024311491 0.0033059540 0.0056388453 0.0049275549 0.0888270000 9915773 955859216 1765105664 0.7894829512 0.3022477925 1.7892313004 344 13.7200000000 0.0024397341 0.0033034359 0.0056388453 0.0049309984 0.0893580000 9917027 955859216 1765101568 0.7855153680 0.3041866422 1.7950810194 345 13.7600000000 0.0024276357 0.0033008973 0.0056388453 0.0049319747 0.0696370000 9918281 955859216 1765101568 0.7838802338 0.3032108247 1.7997474670 346 13.8000000000 0.0012021282 0.0032948315 0.0056388453 0.0049314421 0.0505580000 9919535 955859216 1765117952 0.7795897722 0.3034670353 1.8036968708 347 13.8400000000 0.0024016495 0.0032922575 0.0056388453 0.0049411174 0.0675790000 9920789 955859216 1766481920 0.7774021626 0.3028960824 1.8094618320 348 13.8800000000 0.0023917204 0.0032896697 0.0056388453 0.0049535763 0.0680770000 9922043 955859216 1765855232 0.7727951407 0.3033594489 1.8161296844 349 13.9200000000 0.0016473666 0.0032849640 0.0056388453 0.0049501919 0.0610420000 9923297 955859216 1765089280 0.7659639716 0.3034504652 1.8232754469 350 13.9600000000 0.0023426416 0.0032822717 0.0056388453 0.0049843839 0.0683150000 9924551 955859216 1765212160 0.7606672049 0.3050103486 1.8311228752 351 14.0000000000 0.0023538023 0.0032796264 0.0056388453 0.0049875357 0.0718320000 9925805 955859216 1765101568 0.7552435994 0.3066177368 1.8375972509 352 14.0400000000 0.0012964462 0.0032739924 0.0056388453 0.0049805447 0.0625990000 9927059 955859216 1766465536 0.7480213046 0.3062758446 1.8412317038 353 14.0800000000 0.0022986843 0.0032712295 0.0056388453 0.0049934525 0.0827170000 9928313 955859216 1766002688 0.7453048229 0.3051833808 1.8467521667 354 14.1200000000 0.0022944871 0.0032684703 0.0056388453 0.0049944710 0.0806690000 9929567 955859216 1765113856 0.7392754555 0.3074641228 1.8558418751 355 14.1600000000 0.0011336794 0.0032624568 0.0056388453 0.0049920617 0.0626160000 9930821 955859216 1765109760 0.7318823338 0.3081943095 1.8607456684 356 14.2000000000 0.0022843054 0.0032597092 0.0056388453 0.0050160372 0.0683730000 9932075 955859216 1765109760 0.7271323800 0.3083276451 1.8653728962 357 14.2400000000 0.0023009602 0.0032570237 0.0056388453 0.0050128864 0.0709140000 9933329 955859216 1765109760 0.7196101546 0.3095895648 1.8717602491 358 14.2800000000 0.0023110753 0.0032543813 0.0056388453 0.0050065364 0.0675890000 9934583 955859216 1766457344 0.7141611576 0.3097978532 1.8773082495 359 14.3200000000 0.0023028927 0.0032517310 0.0056388453 0.0050001378 0.0696860000 9935837 955859216 1766002688 0.7051773667 0.3133743703 1.8848782778 360 14.3600000000 0.0022877627 0.0032490533 0.0056388453 0.0050008114 0.0686180000 9937091 955859216 1765113856 0.6892241836 0.3165392280 1.8967930079 361 14.4000000000 0.0022735796 0.0032463511 0.0056388453 0.0049948977 0.0592400000 9938345 955859216 1765109760 0.6792799830 0.3214628696 1.9054465294 362 14.4400000000 0.0023222074 0.0032437982 0.0056388453 0.0049903064 0.0775020000 9939599 955859216 1765109760 0.6624133587 0.3208061755 1.9117224216 363 14.4800000000 0.0020644816 0.0032405494 0.0056388453 0.0049848377 0.0631630000 9940853 955859216 1766711296 0.6564199328 0.3195172548 1.9156463146 364 14.5200000000 0.0028385012 0.0032394449 0.0056388453 0.0049859515 0.0582280000 9942107 955859216 1766367232 0.6498314142 0.3190865517 1.9218142033 365 14.5600000000 0.0031670956 0.0032392467 0.0056388453 0.0049793902 0.0493810000 9943361 955859216 1765494784 0.6418403983 0.3191458881 1.9270229340 366 14.6000000000 0.0023238810 0.0032367457 0.0056388453 0.0049956594 0.0850940000 9944615 955859216 1765122048 0.6241181493 0.3265459836 1.9414650202 367 14.6400000000 0.0025546323 0.0032348871 0.0056388453 0.0050087890 0.0613300000 9945869 955859216 1766473728 0.6147999167 0.3298009336 1.9466197491 368 14.6800000000 0.0021931524 0.0032320563 0.0056388453 0.0050074842 0.0832690000 9947123 955859216 1766002688 0.6051861644 0.3312628567 1.9505749941 369 14.7200000000 0.0025336407 0.0032301635 0.0056388453 0.0050112063 0.0623910000 9948377 955859216 1765220352 0.5958165526 0.3304755986 1.9519953728 370 14.7600000000 0.0023733808 0.0032278479 0.0056388453 0.0050044260 0.0770630000 9949631 955859216 1765060608 0.5878812075 0.3288666606 1.9535012245 371 14.8000000000 0.0023446647 0.0032254674 0.0056388453 0.0050094625 0.0670010000 9950885 955859216 1765093376 0.5795591474 0.3291994631 1.9601514339 372 14.8400000000 0.0027507215 0.0032241912 0.0056388453 0.0050105773 0.0615770000 9952139 955859216 1766584320 0.5711530447 0.3307905495 1.9653861523 373 14.8800000000 0.0030520181 0.0032237296 0.0056388453 0.0050154222 0.0657570000 9953393 955859216 1766211584 0.5615411997 0.3322921991 1.9700689316 374 14.9200000000 0.0030950457 0.0032233855 0.0056388453 0.0050122676 0.0707820000 9954647 955859216 1765367808 0.5503123403 0.3333327770 1.9734038115 375 14.9600000000 0.0026997714 0.0032219892 0.0056388453 0.0050214133 0.0685010000 9955901 955859216 1765105664 0.5393962264 0.3334207237 1.9746074677 376 15.0000000000 0.0026130113 0.0032203696 0.0056388453 0.0050148593 0.0682940000 9957155 955859216 1765105664 0.5302087665 0.3328014612 1.9797812700 377 15.0400000000 0.0030936231 0.0032200334 0.0056388453 0.0050084785 0.0650840000 9958409 955859216 1766469632 0.5097720623 0.3333831131 1.9867880344 378 15.0800000000 0.0028097192 0.0032189479 0.0056388453 0.0050019933 0.0825750000 9959663 955859216 1766129664 0.5004046559 0.3340551853 1.9905521870 379 15.1200000000 0.0025096952 0.0032170765 0.0056388453 0.0049960830 0.0850370000 9960917 955859216 1765240832 0.4925073385 0.3339021802 1.9934432507 380 15.1600000000 0.0023798072 0.0032148732 0.0056388453 0.0049943938 0.0704660000 9962171 955859216 1765126144 0.4848238826 0.3328495622 1.9971241951 381 15.2000000000 0.0023693836 0.0032126540 0.0056388453 0.0050036936 0.0897230000 9963425 955859216 1765126144 0.4766710401 0.3341561258 2.0033276081 382 15.2400000000 0.0022893606 0.0032102370 0.0056388453 0.0050140479 0.0843590000 9964679 955859216 1765093376 0.4660427868 0.3342396617 2.0043396950 383 15.2800000000 0.0022547019 0.0032077422 0.0056388453 0.0050268229 0.0700720000 9965933 955859216 1765109760 0.4574501216 0.3340263665 2.0065546036 384 15.3200000000 0.0023174954 0.0032054238 0.0056388453 0.0050367696 0.0911840000 9967187 955859216 1765109760 0.4491692185 0.3348236084 2.0122373104 385 15.3600000000 0.0023139655 0.0032031083 0.0056388453 0.0050399013 0.0737670000 9968441 955859216 1765109760 0.4408132732 0.3354160488 2.0145740509 386 15.4000000000 0.0022968012 0.0032007604 0.0056388453 0.0050365891 0.0906190000 9969695 955859216 1765109760 0.4338553548 0.3350330293 2.0181081295 387 15.4400000000 0.0023454595 0.0031985503 0.0056388453 0.0050419562 0.0891730000 9970949 955859216 1765109760 0.4273348153 0.3360116184 2.0213644505 388 15.4800000000 0.0023007991 0.0031962365 0.0056388453 0.0050467823 0.0679480000 9972203 955859216 1766473728 0.4210478663 0.3365259469 2.0256731510 389 15.5200000000 0.0023651968 0.0031941002 0.0056388453 0.0050491486 0.0883670000 9973457 955859216 1766129664 0.4131905437 0.3377240598 2.0291590691 390 15.5600000000 0.0023103156 0.0031918341 0.0056388453 0.0050605361 0.0895930000 9974711 955859216 1765240832 0.4051128924 0.3380497098 2.0328087807 391 15.6000000000 0.0023093035 0.0031895770 0.0056388453 0.0050579604 0.0683820000 9975965 955859216 1765126144 0.3983531892 0.3383772969 2.0362250805 392 15.6400000000 0.0023142588 0.0031873440 0.0056388453 0.0050645393 0.1075440000 9977219 955859216 1765060608 0.3916024566 0.3390953839 2.0411133766 393 15.6800000000 0.0024434049 0.0031854510 0.0056388453 0.0050605950 0.0652160000 9978473 955859216 1765093376 0.3845849335 0.3392415941 2.0433936119 394 15.7200000000 0.0023576086 0.0031833499 0.0056388453 0.0050581313 0.0549960000 9979727 955859216 1765109760 0.3782827258 0.3390255868 2.0473351479 395 15.7600000000 0.0023715750 0.0031812948 0.0056388453 0.0050581955 0.0743580000 9980981 955859216 1766473728 0.3717522323 0.3397211432 2.0535039902 396 15.8000000000 0.0024000132 0.0031793218 0.0056388453 0.0050556135 0.0837190000 9982235 955859216 1766473728 0.3645983040 0.3414019048 2.0586311817 397 15.8400000000 0.0026085756 0.0031778842 0.0056388453 0.0050549296 0.0539920000 9983489 955859216 1766223872 0.3581391573 0.3413354754 2.0606315136 398 15.8800000000 0.0024521556 0.0031760608 0.0056388453 0.0050503823 0.0721130000 9984743 955859216 1765605376 0.3533068001 0.3412030339 2.0683932304 399 15.9200000000 0.0025577382 0.0031745111 0.0056388453 0.0050538017 0.0873430000 9985997 955859216 1765101568 0.3451451063 0.3431923687 2.0715353489 400 15.9600000000 0.0025259408 0.0031728897 0.0056388453 0.0050509876 0.0661260000 9987251 955859216 1765109760 0.3401043713 0.3416598141 2.0753757954 401 16.0000000000 0.0025545647 0.0031713477 0.0056388453 0.0050477687 0.0735610000 9988505 955859216 1765109760 0.3341211975 0.3410078287 2.0790359974 402 16.0400000000 0.0026191431 0.0031699741 0.0056388453 0.0050503617 0.0817360000 9989759 955859216 1765109760 0.3285378218 0.3413352072 2.0865159035 403 16.0800000000 0.0026766933 0.0031687500 0.0056388453 0.0050466982 0.0683930000 9991013 955859216 1766473728 0.3224212825 0.3419758677 2.0925817490 404 16.1200000000 0.0027387533 0.0031676857 0.0056388453 0.0050423091 0.0579550000 9992267 955859216 1765949440 0.3152943850 0.3419990242 2.0965616703 405 16.1600000000 0.0027804810 0.0031667296 0.0056388453 0.0050383716 0.0682000000 9993521 955859216 1765113856 0.3101636767 0.3408382535 2.1011619568 406 16.2000000000 0.0028465777 0.0031659411 0.0056388453 0.0050478077 0.0728230000 9994775 955859216 1765109760 0.3039817810 0.3418493271 2.1096658707 407 16.2400000000 0.0029201980 0.0031653373 0.0056388453 0.0050505345 0.0542230000 9996029 955859216 1766473728 0.2964913547 0.3439409137 2.1150958538 408 16.2800000000 0.0029787684 0.0031648800 0.0056388453 0.0050547006 0.0742660000 9997283 955859216 1766129664 0.2911423445 0.3444216847 2.1197128296 409 16.3200000000 0.0028930430 0.0031642154 0.0056388453 0.0050607321 0.0616180000 9998537 955859216 1765351424 0.2840526998 0.3454422355 2.1265540123 410 16.3600000000 0.0027901046 0.0031633029 0.0056388453 0.0050591589 0.0713620000 9999791 955859216 1766727680 0.2786405981 0.3459869623 2.1304953098 411 16.3999999990 0.0024264827 0.0031615101 0.0056388453 0.0050558674 0.0703420000 10001045 955859216 1766359040 0.2722199559 0.3462475538 2.1337597370 412 16.4400000000 0.0021074223 0.0031589517 0.0056388453 0.0050542824 0.0688480000 10002299 955859216 1765728256 0.2660637796 0.3462252617 2.1390993595 413 16.4800000000 0.0018667391 0.0031558228 0.0056388453 0.0050652889 0.0839150000 10003553 955859216 1765117952 0.2595707476 0.3475800753 2.1462621689 414 16.5200000000 0.0018231270 0.0031526038 0.0056388453 0.0050724325 0.1067860000 10004807 955859216 1765109760 0.2529319823 0.3491994441 2.1515941620 415 16.5599999990 0.0019665975 0.0031497459 0.0056388453 0.0050868218 0.0941110000 10006061 955859216 1765060608 0.2466168404 0.3515135348 2.1582741737 416 16.6000000000 0.0022539045 0.0031475925 0.0056388453 0.0050890389 0.0849790000 10007315 955859216 1765101568 0.2412186265 0.3527950346 2.1622517109 417 16.6400000000 0.0019473077 0.0031447141 0.0056388453 0.0050934291 0.0677110000 10008569 955859216 1765101568 0.2358126491 0.3534140885 2.1660134792 418 16.6800000000 0.0024884730 0.0031431441 0.0056388453 0.0051069152 0.0764770000 10009823 955859216 1765101568 0.2252055258 0.3551473320 2.1750979424 419 16.7199999990 0.0024679624 0.0031415327 0.0056388453 0.0051137935 0.0799560000 10011077 955859216 1765101568 0.2190181613 0.3568178415 2.1814920902 420 16.7600000000 0.0020418870 0.0031389145 0.0056388453 0.0051219259 0.0894920000 10012331 955859216 1765101568 0.2125869393 0.3587439954 2.1873629093 421 16.8000000000 0.0014865883 0.0031349897 0.0056388453 0.0051285062 0.0810350000 10013585 955859216 1765101568 0.2064375728 0.3595349491 2.1924691200 422 16.8400000000 0.0014068469 0.0031308946 0.0056388453 0.0051372959 0.0706150000 10014839 955859216 1766576128 0.2006535381 0.3596999645 2.1972076893 423 16.8799999990 0.0015260627 0.0031271007 0.0056388453 0.0051520277 0.0866980000 10016093 955859216 1766248448 0.1955735981 0.3595442772 2.2024366856 424 16.9200000000 0.0016165838 0.0031235381 0.0056388453 0.0052369020 0.0861810000 10017347 955859216 1765470208 0.1836239994 0.3613384962 2.2120876312 425 16.9600000000 0.0018255491 0.0031204841 0.0056388453 0.0052436050 0.0733460000 10018601 955859216 1765212160 0.1787314564 0.3620107174 2.2156181335 426 17.0000000000 0.0018180901 0.0031174268 0.0056388453 0.0052636614 0.0867890000 10019855 955859216 1765052416 0.1731547564 0.3635275066 2.2206442356 427 17.0400000000 0.0018371958 0.0031144286 0.0056388453 0.0052745247 0.0670070000 10021109 955859216 1765085184 0.1676684916 0.3652450740 2.2250757217 428 17.0800000000 0.0018662288 0.0031115122 0.0056388453 0.0052837124 0.1057810000 10022363 955859216 1765101568 0.1627048105 0.3672426343 2.2289836407 429 17.1200000000 0.0018605075 0.0031085961 0.0056388453 0.0052887110 0.1000310000 10023617 955859216 1765101568 0.1576792151 0.3675481677 2.2311940193 430 17.1600000000 0.0019132012 0.0031058162 0.0056388453 0.0052928993 0.1191830000 10024871 955859216 1765101568 0.1528200656 0.3678823709 2.2346105576 431 17.2000000000 0.0019409271 0.0031031134 0.0056388453 0.0052970633 0.0838470000 10026125 955859216 1765101568 0.1481807083 0.3674837649 2.2382817268 432 17.2400000000 0.0019643228 0.0031004773 0.0056388453 0.0052978278 0.0703180000 10027379 955859216 1765101568 0.1428996027 0.3680628240 2.2427656651 433 17.2800000000 0.0019634862 0.0030978515 0.0056388453 0.0052981530 0.0576960000 10028633 955859216 1765101568 0.1390882730 0.3694905639 2.2465009689 434 17.3200000000 0.0019613351 0.0030952328 0.0056388453 0.0052978377 0.0772570000 10029887 955859216 1765117952 0.1335742474 0.3706542850 2.2488665581 435 17.3600000000 0.0019435337 0.0030925852 0.0056388453 0.0052965988 0.0867960000 10031141 955859216 1765117952 0.1283494234 0.3692098260 2.2503092289 436 17.4000000000 0.0019413161 0.0030899446 0.0056388453 0.0053002291 0.0814240000 10032395 955859216 1766449152 0.1233789772 0.3689225614 2.2530791759 437 17.4400000000 0.0019327758 0.0030872967 0.0056388453 0.0052993010 0.0845130000 10033649 955859216 1766354944 0.1171521246 0.3702148199 2.2561039925 438 17.4800000000 0.0019617246 0.0030847269 0.0056388453 0.0052989867 0.0869500000 10034903 955859216 1766354944 0.1120874807 0.3688100576 2.2583765984 439 17.5200000000 0.0019468776 0.0030821350 0.0056388453 0.0052979996 0.0984160000 10036157 955859216 1764806656 0.1072376668 0.3687097132 2.2607092857 440 17.5600000000 0.0019357925 0.0030795296 0.0056388453 0.0052971322 0.0973860000 10037411 955859216 1764839424 0.1021010429 0.3684025109 2.2627346516 441 17.6000000000 0.0019113284 0.0030768806 0.0056388453 0.0052956427 0.0877970000 10038665 955859216 1764839424 0.0964151248 0.3680558205 2.2641427517 442 17.6400000000 0.0044133454 0.0030799043 0.0056388453 0.0053086292 0.0681580000 10039919 955859216 1766322176 0.0898960084 0.3682327271 2.2636730671 443 17.6800000000 0.0019369592 0.0030773243 0.0056388453 0.0053082319 0.0833990000 10041173 955859216 1766084608 0.0857227817 0.3677753508 2.2671022415 444 17.7200000000 0.0044677230 0.0030804558 0.0056388453 0.0053157869 0.1109030000 10042427 955859216 1765109760 0.0789809525 0.3688420057 2.2677886486 445 17.7600000000 0.0019986071 0.0030780247 0.0056388453 0.0053201812 0.1094300000 10043681 955859216 1766465536 0.0754928589 0.3670808077 2.2710368633 446 17.8000000000 0.0039987643 0.0030800892 0.0056388453 0.0053347880 0.0882840000 10044935 955859216 1768353792 0.0688782707 0.3673704267 2.2712075710 447 17.8400000000 0.0020550033 0.0030777959 0.0056388453 0.0053362897 0.0692890000 10046189 955859216 1770004480 0.0643228143 0.3657768369 2.2759981155 448 17.8800000000 0.0042137438 0.0030803315 0.0056388453 0.0053466429 0.0677860000 10047443 955859216 1771782144 0.0566606261 0.3670822680 2.2764265537 449 17.9200000000 0.0057320055 0.0030862372 0.0057320055 0.0053466361 0.0484900000 10048697 955859216 1773432832 0.0506490842 0.3672241867 2.2765717506 450 17.9600000000 0.0065969825 0.0030940389 0.0065969825 0.0053437892 0.0737930000 10049951 955859216 1775083520 0.0451426730 0.3665000498 2.2775652409 451 18.0000000000 0.0021430156 0.0030919302 0.0065969825 0.0053633695 0.0909730000 10051205 955859216 1776861184 0.0338449478 0.3620592654 2.2842686176 452 18.0400000000 0.0045286082 0.0030951087 0.0065969825 0.0053683223 0.0653360000 10052459 955859216 1778511872 0.0270590764 0.3633734584 2.2848954201 453 18.0800000000 0.0056313812 0.0031007075 0.0065969825 0.0053733711 0.0676890000 10053713 955859216 1780162560 0.0203330088 0.3626188040 2.2865469456 454 18.1200000000 0.0022133416 0.0030987530 0.0065969825 0.0053763475 0.0713970000 10054967 955859216 1781940224 0.0144239031 0.3603050709 2.2923622131 455 18.1600000000 0.0043487367 0.0031015002 0.0065969825 0.0053788051 0.0678510000 10056221 955859216 1783590912 0.0067815227 0.3618882000 2.2942492962 456 18.2000000000 0.0056977933 0.0031071938 0.0065969825 0.0053784548 0.0656590000 10057475 955859216 1785241600 0.0007948950 0.3615176082 2.2950954437 457 18.2400000000 0.0065475618 0.0031147220 0.0065969825 0.0053731589 0.0603440000 10058729 955859216 1787019264 -0.0063002892 0.3618488610 2.2971143723 458 18.2800000000 0.0022986308 0.0031129401 0.0065969825 0.0054271260 0.0830940000 10059983 955859216 1786130432 -0.0118726538 0.3590877354 2.3017530441 459 18.3200000000 0.0043320265 0.0031155961 0.0065969825 0.0054220130 0.0679570000 10061237 955859216 1784381440 -0.0189172979 0.3594184220 2.3015825748 460 18.3600000000 0.0054095783 0.0031205830 0.0065969825 0.0054166668 0.0656980000 10062491 955859216 1783402496 -0.0250642803 0.3590914011 2.3024747372 461 18.4000000000 0.0057866047 0.0031263661 0.0065969825 0.0054115097 0.0537540000 10063745 955859216 1782501376 -0.0322134979 0.3580669165 2.3048529625 462 18.4400000000 0.0024199847 0.0031248371 0.0065969825 0.0054336036 0.0851590000 10064999 955859216 1781465088 -0.0381342880 0.3552152514 2.3105046749 463 18.4800000000 0.0035663457 0.0031257907 0.0065969825 0.0054291749 0.0673850000 10066253 955859216 1782845440 -0.0440786295 0.3560747802 2.3100039959 464 18.5200000000 0.0044246977 0.0031285901 0.0065969825 0.0054280707 0.0689560000 10067507 955859216 1782226944 -0.0510680825 0.3552770913 2.3100967407 465 18.5600000000 0.0024610343 0.0031271545 0.0065969825 0.0054337463 0.0698910000 10068761 955859216 1781211136 -0.0570828542 0.3528712690 2.3146440983 466 18.6000000000 0.0048083141 0.0031307621 0.0065969825 0.0054375762 0.0685590000 10070015 955859216 1780342784 -0.0638764277 0.3532442749 2.3156616688 467 18.6400000000 0.0061444184 0.0031372154 0.0065969825 0.0054395937 0.0671020000 10071269 955859216 1781702656 -0.0702032447 0.3545790017 2.3158380985 468 18.6800000000 0.0067392900 0.0031449121 0.0067392900 0.0054406811 0.0696960000 10072523 955859216 1781084160 -0.0754319504 0.3541445434 2.3152344227 469 18.7200000000 0.0026194993 0.0031437918 0.0067392900 0.0054589162 0.0677490000 10073777 955859216 1780215808 -0.0807467178 0.3513172269 2.3203988075 470 18.7600000000 0.0038874513 0.0031453741 0.0067392900 0.0054556857 0.0503980000 10075031 955859216 1781575680 -0.0869639367 0.3511328399 2.3200061321 471 18.8000000000 0.0026900792 0.0031444074 0.0067392900 0.0054630883 0.0755130000 10076285 955859216 1780944896 -0.1003661081 0.3461448550 2.3221645355 472 18.8400000000 0.0048373439 0.0031479941 0.0067392900 0.0054707493 0.0668240000 10077539 955859216 1780342784 -0.1056910455 0.3464234769 2.3218998909 473 18.8800000000 0.0066989069 0.0031555014 0.0067392900 0.0054800210 0.0522130000 10078793 955859216 1779453952 -0.1080345809 0.3457505703 2.3194844723 474 18.9200000000 0.0078498079 0.0031654050 0.0078498079 0.0054875854 0.0656250000 10080047 955859216 1780813824 -0.1104547754 0.3446545601 2.3188025951 475 18.9600000000 0.0028139683 0.0031646651 0.0078498079 0.0055044591 0.0889510000 10081301 955859216 1780195328 -0.1128423139 0.3404011130 2.3240380287 476 19.0000000000 0.0027785457 0.0031638539 0.0078498079 0.0055208775 0.0881090000 10082555 955859216 1779433472 -0.1179049909 0.3376932740 2.3243272305 477 19.0400000000 0.0046830671 0.0031670389 0.0078498079 0.0055550235 0.0727460000 10083809 955859216 1778438144 -0.1205579191 0.3366305828 2.3221492767 478 19.0800000000 0.0028301037 0.0031663340 0.0078498079 0.0055675309 0.1038140000 10085063 955859216 1777549312 -0.1262430251 0.3332258165 2.3297514915 479 19.1200000000 0.0066733635 0.0031736555 0.0078498079 0.0056045878 0.0690040000 10086317 955859216 1776771072 -0.1274829060 0.3358352482 2.3272390366 480 19.1600000000 0.0028987553 0.0031730828 0.0078498079 0.0056086247 0.0983490000 10087571 955859216 1775898624 -0.1266941726 0.3326995373 2.3294162750 481 19.2000000000 0.0068301433 0.0031806859 0.0078498079 0.0056797113 0.0673210000 10088825 955859216 1775009792 -0.1290066689 0.3346146047 2.3276593685 482 19.2400000000 0.0030163799 0.0031803450 0.0078498079 0.0056836331 0.1067570000 10090079 955859216 1774104576 -0.1288064271 0.3323622048 2.3311333656 483 19.2800000000 0.0070357244 0.0031883271 0.0078498079 0.0057555576 0.0904700000 10091333 955859216 1773232128 -0.1304595172 0.3339041770 2.3294801712 484 19.3200000000 0.0032466997 0.0031884477 0.0078498079 0.0057650817 0.1276040000 10092587 955859216 1772343296 -0.1291498244 0.3309397697 2.3335146904 485 19.3600000000 0.0032463339 0.0031885671 0.0078498079 0.0057884648 0.0877140000 10093841 955859216 1770696704 -0.1287614852 0.3308870792 2.3336999416 486 19.4000000000 0.0032385876 0.0031886700 0.0078498079 0.0058006824 0.0870230000 10095095 955859216 1770274816 -0.1297866255 0.3309433460 2.3367900848 487 19.4400000000 0.0033324852 0.0031889653 0.0078498079 0.0058125064 0.0900570000 10096349 955859216 1769422848 -0.1291664094 0.3311782777 2.3390271664 488 19.4800000000 0.0033051206 0.0031892033 0.0078498079 0.0058273824 0.0866460000 10097603 955859216 1768534016 -0.1292185932 0.3300981820 2.3417484760 489 19.5200000000 0.0033339956 0.0031894994 0.0078498079 0.0058367464 0.0889820000 10098857 955859216 1767645184 -0.1314878464 0.3306106925 2.3473179340 490 19.5600000000 0.0093954243 0.0032021646 0.0093954243 0.0059357489 0.0887820000 10100111 955859216 1766866944 -0.1312469244 0.3354106545 2.3436863422 491 19.6000000000 0.0034442774 0.0032026577 0.0093954243 0.0059638440 0.0907480000 10101365 955859216 1766068224 -0.1301405579 0.3318566978 2.3519032001 492 19.6400000000 0.0032713360 0.0032027973 0.0093954243 0.0059673792 0.0814390000 10102619 955859216 1765232640 -0.1293132901 0.3319225609 2.3550612926 493 19.6800000000 0.0032117947 0.0032028155 0.0093954243 0.0059760468 0.0895560000 10103873 955859216 1765117952 -0.1271530837 0.3334531784 2.3553757668 494 19.7200000000 0.0030989342 0.0032026052 0.0093954243 0.0059997401 0.1093180000 10105127 955859216 1765117952 -0.1281746477 0.3332147300 2.3604700565 495 19.7600000000 0.0103197442 0.0032169833 0.0103197442 0.0061656135 0.0655020000 10106381 955859216 1766481920 -0.1295953393 0.3378067911 2.3604345322 496 19.8000000000 0.0167506393 0.0032442689 0.0167506393 0.0062723994 0.0698260000 10107635 955859216 1768480768 -0.1302726269 0.3429674804 2.3602347374 497 19.8400000000 0.0034116453 0.0032446057 0.0167506393 0.0064769400 0.0889440000 10108889 955859216 1770131456 -0.1278733313 0.3353422284 2.3721151352 498 19.8800000000 0.0099325366 0.0032580353 0.0167506393 0.0065857406 0.0686830000 10110143 955859216 1771909120 -0.1275334060 0.3402713835 2.3695445061 499 19.9200000000 0.0032543514 0.0032580279 0.0167506393 0.0066451437 0.0868510000 10111397 955859216 1773559808 -0.1269016266 0.3353942633 2.3794691563 500 19.9600000000 0.0029627800 0.0032574374 0.0167506393 0.0066463124 0.0861790000 10112651 955859216 1775210496 -0.1263833344 0.3362812996 2.3824954033 501 20.0000000000 0.0029438827 0.0032568115 0.0167506393 0.0066502715 0.0898540000 10113905 955859216 1776988160 -0.1257339269 0.3368208706 2.3851420879 502 20.0400000000 0.0029387292 0.0032561779 0.0167506393 0.0066568190 0.0924210000 10115159 955859216 1778638848 -0.1255027652 0.3372721672 2.3885793686 503 20.0800000000 0.0029807591 0.0032556303 0.0167506393 0.0066635155 0.1268500000 10116413 955859216 1780289536 -0.1265626252 0.3382546902 2.3920714855 504 20.1200000000 0.0036699255 0.0032564524 0.0167506393 0.0066732895 0.0906520000 10117667 955859216 1782067200 -0.1267420202 0.3392002285 2.3953807354 505 20.1600000000 0.0038208496 0.0032575700 0.0167506393 0.0066814925 0.0871580000 10118921 955859216 1783717888 -0.1272682101 0.3401953280 2.3978941441 506 20.2000000000 0.0039082388 0.0032588559 0.0167506393 0.0066891597 0.0890300000 10120175 955859216 1785368576 -0.1268870980 0.3404771388 2.4002292156 507 20.2400000000 0.0040676841 0.0032604512 0.0167506393 0.0066963043 0.1087100000 10121429 955859216 1787146240 -0.1274481565 0.3402610123 2.4030649662 508 20.2800000000 0.0044230651 0.0032627398 0.0167506393 0.0067055157 0.0863500000 10122683 955859216 1786277888 -0.1293308586 0.3401082158 2.4066684246 509 20.3200000000 0.0046858815 0.0032655358 0.0167506393 0.0067152657 0.1073970000 10123937 955859216 1784664064 -0.1292237639 0.3398429453 2.4096162319 510 20.3600000000 0.0050700535 0.0032690740 0.0167506393 0.0067193891 0.1252140000 10125191 955859216 1783590912 -0.1287602633 0.3408368230 2.4093859196 511 20.4000000000 0.0133397337 0.0032887818 0.0167506393 0.0068659969 0.0914550000 10126445 955859216 1782755328 -0.1297327727 0.3464461863 2.4044418335 512 20.4400000000 0.0060632033 0.0032942006 0.0167506393 0.0069207899 0.1081010000 10127699 955859216 1781719040 -0.1321781129 0.3417936563 2.4131338596 513 20.4800000000 0.0086460290 0.0033046330 0.0167506393 0.0069276019 0.1079540000 10169913 955859216 1780850688 -0.1322226971 0.3446275294 2.4128556252 514 20.5200000000 0.0135737490 0.0033246118 0.0167506393 0.0070246047 0.0911160000 10255135 955859216 1779961856 -0.1336213350 0.3477176428 2.4086740017 515 20.5600000000 0.0075264024 0.0033327706 0.0167506393 0.0070738005 0.0850990000 10256389 955859216 1779183616 -0.1350915432 0.3434022069 2.4150037766 516 20.6000000000 0.0084477756 0.0033426834 0.0167506393 0.0070753675 0.0805970000 10257643 955859216 1778311168 -0.1366077513 0.3442524672 2.4148621559 517 20.6400000000 0.0100350911 0.0033556281 0.0167506393 0.0070781272 0.1119290000 10258897 955859216 1777422336 -0.1376970559 0.3454099000 2.4138729572 518 20.6800000000 0.0182586201 0.0033843984 0.0182586201 0.0071017186 0.0996290000 10260151 955859216 1776533504 -0.1392064691 0.3529522419 2.4139070511 519 20.7200000000 0.0184210949 0.0034133708 0.0184210949 0.0071027843 0.0906160000 10261405 955859216 1775591424 -0.1422986686 0.3530097008 2.4149417877 520 20.7600000000 0.0186388381 0.0034426506 0.0186388381 0.0071043417 0.0733700000 10262659 955859216 1774739456 -0.1441001892 0.3516021073 2.4154312611 521 20.8000000000 0.0227382947 0.0034796864 0.0227382947 0.0071127278 0.0867590000 10263913 955859216 1773867008 -0.1462852210 0.3550771475 2.4144799709 522 20.8400000000 0.0270921420 0.0035249209 0.0270921420 0.0071259242 0.0867950000 10265167 955859216 1772978176 -0.1491541117 0.3581908643 2.4146683216 523 20.8800000000 0.0487307124 0.0036113565 0.0487307124 0.0072049678 0.1091600000 10266421 955859216 1772089344 -0.1496516168 0.3804086149 2.4093699455 524 20.9200000000 0.0596157387 0.0037182351 0.0596157387 0.0072978954 0.0676500000 10267675 955859216 1773449216 -0.1508226097 0.3893332481 2.4033629894 525 20.9600000000 0.0596014187 0.0038246792 0.0596157387 0.0073085565 0.0676950000 10268929 955859216 1772851200 -0.1538262665 0.3865499794 2.4005131721 526 21.0000000000 0.0562096871 0.0039242705 0.0596157387 0.0073846585 0.0717750000 10270183 955859216 1771962368 -0.1573567539 0.3842605650 2.4048595428 527 21.0400000000 0.0589848608 0.0040287498 0.0596157387 0.0073853319 0.0749240000 10271437 955859216 1771073536 -0.1600074321 0.3869398832 2.4009053707 528 21.0800000000 0.0631286800 0.0041406815 0.0631286800 0.0074333115 0.0757450000 10272691 955859216 1770184704 -0.1638720334 0.3885518610 2.3956005573 529 21.1200000000 0.0560126789 0.0042387382 0.0631286800 0.0074812510 0.0924650000 10273945 955859216 1769406464 -0.1685564220 0.3807780743 2.3990235329 530 21.1600000000 0.0599646270 0.0043438814 0.0631286800 0.0074967910 0.1053500000 10275199 955859216 1768517632 -0.1708946079 0.3851715326 2.3913407326 531 21.2000000000 0.0608135164 0.0044502272 0.0631286800 0.0075033733 0.0847490000 10276453 955859216 1767645184 -0.1740685552 0.3847377300 2.3861413002 532 21.2400000000 0.0685721338 0.0045707571 0.0685721338 0.0075332405 0.1104140000 10277707 955859216 1766866944 -0.1784203500 0.3915864527 2.3809337616 533 21.2800000000 0.0724291354 0.0046980711 0.0724291354 0.0075440367 0.0897030000 10278961 955859216 1765994496 -0.1820847988 0.3946154416 2.3770732880 534 21.3200000000 0.0591330230 0.0048000093 0.0724291354 0.0075485991 0.0828000000 10280215 955859216 1767354368 -0.1859749407 0.3790185452 2.3779242039 535 21.3600000000 0.0540406890 0.0048920479 0.0724291354 0.0076724412 0.0872100000 10281469 955859216 1766465536 -0.1921260059 0.3733855784 2.3846623898 536 21.4000000000 0.0685308874 0.0050107771 0.0724291354 0.0077027088 0.0901710000 10282723 955859216 1764990976 -0.1958373785 0.3871690631 2.3770439625 537 21.4400000000 0.0660299882 0.0051244069 0.0724291354 0.0076992250 0.0669120000 10283977 955859216 1766354944 -0.2000734955 0.3851002455 2.3722860813 538 21.4800000000 0.0667266026 0.0052389091 0.0724291354 0.0076947996 0.0679400000 10285231 955859216 1765851136 -0.2048843652 0.3861713111 2.3676586151 539 21.5200000000 0.0701842234 0.0053594014 0.0724291354 0.0076958621 0.0518700000 10286485 955859216 1765089280 -0.2091811001 0.3882364929 2.3638322353 540 21.5600000000 0.0661855787 0.0054720424 0.0724291354 0.0076967919 0.0659910000 10287739 955859216 1766465536 -0.2141520083 0.3838096857 2.3612608910 541 21.6000000000 0.0562420487 0.0055658872 0.0724291354 0.0078005307 0.0881330000 10288993 955859216 1765941248 -0.2196311355 0.3737032115 2.3663494587 542 21.6400000000 0.0628969073 0.0056716640 0.0724291354 0.0078311605 0.0697440000 10290247 955859216 1765105664 -0.2233886719 0.3769900799 2.3609545231 543 21.6800000000 0.0594900735 0.0057707771 0.0724291354 0.0079021440 0.0862350000 10291501 955859216 1765101568 -0.2280861735 0.3718308508 2.3609728813 544 21.7200000000 0.0574363954 0.0058657506 0.0724291354 0.0079939106 0.0889920000 10292755 955859216 1765101568 -0.2357013524 0.3664478064 2.3520174026 545 21.7600000000 0.0664946437 0.0059769963 0.0724291354 0.0079928541 0.0903100000 10294009 955859216 1765117952 -0.2404660434 0.3776404858 2.3442058563 546 21.8000000000 0.0630252883 0.0060814803 0.0724291354 0.0079910979 0.1040940000 10295263 955859216 1765117952 -0.2449307889 0.3733852208 2.3401892185 547 21.8400000000 0.0561546236 0.0061730217 0.0724291354 0.0080008875 0.0919730000 10296517 955859216 1765117952 -0.2495004535 0.3641505539 2.3369457722 548 21.8800000000 0.0675454512 0.0062850152 0.0724291354 0.0080016690 0.0834010000 10297771 955859216 1765212160 -0.2552897632 0.3799041510 2.3283379078 549 21.9200000000 0.0794453770 0.0064182764 0.0794453770 0.0080207888 0.0703370000 10299025 955859216 1765101568 -0.2603833079 0.3944249749 2.3211913109 550 21.9600000000 0.0932652205 0.0065761799 0.0932652205 0.0080615159 0.0686400000 10300279 955859216 1765101568 -0.2637203038 0.4007037282 2.3171679974 551 22.0000000000 0.0977617204 0.0067416709 0.0977617204 0.0080773720 0.0698620000 10301533 955859216 1765085184 -0.2680730820 0.4038306773 2.3116745949 552 22.0400000000 0.1060312837 0.0069215434 0.1060312837 0.0080751816 0.0667980000 10302787 955859216 1766449152 -0.2736722827 0.4183529913 2.3032283783 553 22.0800000000 0.1004613414 0.0070906931 0.1060312837 0.0080694672 0.0672980000 10304041 955859216 1765965824 -0.2777312398 0.4138955474 2.2984108925 554 22.1200000000 0.1007881984 0.0072598222 0.1060312837 0.0080672653 0.0680350000 10305295 955859216 1765232640 -0.2818552852 0.4119340181 2.2932953835 555 22.1600000000 0.1063200831 0.0074383091 0.1063200831 0.0080657874 0.0768940000 10306549 955859216 1765117952 -0.2857489586 0.4181790352 2.2863061428 556 22.2000000000 0.0907810554 0.0075882062 0.1063200831 0.0080710296 0.0908740000 10307803 955859216 1765117952 -0.2890639007 0.4009983540 2.2827005386 557 22.2400000000 0.0933905095 0.0077422498 0.1063200831 0.0080692689 0.0897180000 10309057 955859216 1765117952 -0.2934464514 0.4056725502 2.2753701210 558 22.2800000000 0.0865606666 0.0078835014 0.1063200831 0.0081015959 0.0725850000 10310311 955859216 1765101568 -0.2975669205 0.3978857100 2.2726297379 559 22.3200000000 0.0940941498 0.0080377244 0.1063200831 0.0081091627 0.0759690000 10311565 955859216 1765101568 -0.3005584478 0.4036213458 2.2644047737 560 22.3600000000 0.0853270516 0.0081757411 0.1063200831 0.0081164561 0.0896270000 10312819 955859216 1765101568 -0.3037880957 0.3938637078 2.2581024170 561 22.4000000000 0.0802315995 0.0083041829 0.1063200831 0.0081100698 0.0873470000 10314073 955859216 1765101568 -0.3069418371 0.3884002268 2.2513718605 562 22.4400000000 0.0641594678 0.0084035695 0.1063200831 0.0081181124 0.1100050000 10315327 955859216 1765085184 -0.3104001880 0.3679056466 2.2485179901 563 22.4800000000 0.0606875047 0.0084964362 0.1063200831 0.0081159094 0.0878060000 10316581 955859216 1765085184 -0.3132823408 0.3624746203 2.2427482605 564 22.5200000000 0.0594620034 0.0085868007 0.1063200831 0.0081105960 0.0898550000 10317835 955859216 1765322752 -0.3163545728 0.3622181714 2.2358543873 565 22.5600000000 0.0132043092 0.0085949733 0.1063200831 0.0082152293 0.0873650000 10319089 955859216 1766338560 -0.3235093057 0.3178130686 2.2225649357 566 22.6000000000 0.0085427770 0.0085948810 0.1063200831 0.0082224679 0.1049460000 10320343 955859216 1765072896 -0.3270908892 0.3079720438 2.2148625851 567 22.6400000000 0.0085085509 0.0085947288 0.1063200831 0.0082176084 0.1105400000 10321597 955859216 1765101568 -0.3303789496 0.3069257736 2.2079668045 568 22.6800000000 0.0104642324 0.0085980202 0.1063200831 0.0082189348 0.0874520000 10322851 955859216 1765101568 -0.3337161541 0.3115989864 2.2004430294 569 22.7200000000 0.0077580283 0.0085965439 0.1063200831 0.0082131972 0.0912060000 10324105 955859216 1765101568 -0.3372542858 0.3076017499 2.1928877831 570 22.7600000000 0.0062785484 0.0085924772 0.1063200831 0.0082175872 0.0849790000 10325359 955859216 1765101568 -0.3404153883 0.3023386598 2.1885976791 571 22.8000000000 0.0103184450 0.0085954999 0.1063200831 0.0082186193 0.0673400000 10326613 955859216 1766465536 -0.3427987993 0.3040946722 2.1812677383 572 22.8400000000 0.0077482718 0.0085940188 0.1063200831 0.0082228507 0.0640970000 10327867 955859216 1766068224 -0.3458964527 0.3052710593 2.1725986004 573 22.8800000000 0.0073774578 0.0085918956 0.1063200831 0.0082235478 0.0884850000 10329121 955859216 1765109760 -0.3500297368 0.3039398491 2.1668083668 574 22.9200000000 0.0179335847 0.0086081704 0.1063200831 0.0082477603 0.1110690000 10330375 955859216 1765101568 -0.3546889722 0.3158775866 2.1592884064 575 22.9600000000 0.1156316698 0.0087942982 0.1156316698 0.0089622980 0.0870030000 10331629 955859216 1764696064 -0.3572965562 0.4100941122 2.1302731037 576 23.0000000000 0.1024503559 0.0089568955 0.1156316698 0.0090663804 0.0865960000 10332883 955859216 1764438016 -0.3607287407 0.3930760622 2.1299138069 577 23.0400000000 0.0771339089 0.0090750532 0.1156316698 0.0092086154 0.1070770000 10334137 955859216 1765089280 -0.3648490012 0.3652464449 2.1266381741 578 23.0800000000 0.0772606730 0.0091930214 0.1156316698 0.0092290021 0.1048860000 10335391 955859216 1766576128 -0.3670825064 0.3662728667 2.1198291779 579 23.1200000000 0.0648846030 0.0092892072 0.1156316698 0.0092554457 0.0871480000 10336645 955859216 1768607744 -0.3686159551 0.3526374400 2.1117455959 580 23.1600000000 0.0657145604 0.0093864923 0.1156316698 0.0092798632 0.0907630000 10337899 955859216 1770258432 -0.3698437512 0.3531098962 2.1036281586 581 23.2000000000 0.1178611070 0.0095731956 0.1178611070 0.0095139900 0.0880220000 10339153 955859216 1771909120 -0.3749576211 0.4053685367 2.0920047760 582 23.2400000000 0.0813291594 0.0096964877 0.1178611070 0.0097130995 0.1002750000 10340407 955859216 1773686784 -0.3821426928 0.3649596870 2.0961110592 583 23.2800000000 0.0817958862 0.0098201573 0.1178611070 0.0098175272 0.1091760000 10341661 955859216 1775337472 -0.3843833208 0.3659206629 2.0949590206 584 23.3200000000 0.0953641459 0.0099666367 0.1178611070 0.0098660018 0.0949960000 10342915 955859216 1776988160 -0.3878868818 0.3793191612 2.0938246250 585 23.3600000000 0.0868794173 0.0100981116 0.1178611070 0.0098859126 0.0885750000 10344169 955859216 1778765824 -0.3942726851 0.3686069846 2.0851278305 586 23.4000000000 0.1152504981 0.0102775525 0.1178611070 0.0099783655 0.1026000000 10345423 955859216 1780416512 -0.3975099921 0.3955352008 2.0830214024 587 23.4400000000 0.1137372479 0.0104538041 0.1178611070 0.0099748432 0.0968930000 10346677 955859216 1782067200 -0.4020732045 0.3938758373 2.0774919987 588 23.4800000000 0.1142305508 0.0106302952 0.1178611070 0.0099709035 0.1078020000 10347931 955859216 1783844864 -0.4089652300 0.3924707174 2.0706579685 589 23.5200000000 0.1151913553 0.0108078182 0.1178611070 0.0099650385 0.1115530000 10349185 955859216 1785495552 -0.4153406322 0.3905028105 2.0631642342 590 23.5600000000 0.1161525100 0.0109863685 0.1178611070 0.0099586299 0.1058360000 10350439 955859216 1787273216 -0.4214241505 0.3893549144 2.0554766655 591 23.6000000000 0.1190683991 0.0111692484 0.1190683991 0.0099588883 0.0863030000 10351693 955859216 1786388480 -0.4269003570 0.3903290629 2.0464098454 592 23.6400000000 0.1189729050 0.0113513492 0.1190683991 0.0099535451 0.0869350000 10352947 955859216 1784614912 -0.4341474473 0.3899353445 2.0400609970 593 23.6800000000 0.1286489666 0.0115491530 0.1286489666 0.0099539883 0.1133240000 10354201 955859216 1782992896 -0.4402293265 0.3998307884 2.0327458382 594 23.7200000000 0.1198462173 0.0117314712 0.1286489666 0.0099516250 0.0834990000 10355455 955859216 1782120448 -0.4475561976 0.3883242607 2.0257482529 595 23.7600000000 0.1241463795 0.0119204039 0.1286489666 0.0099488484 0.1078660000 10356709 955859216 1781084160 -0.4561710358 0.3889238834 2.0176739693 596 23.8000000000 0.1379870623 0.0121319251 0.1379870623 0.0099570574 0.0792200000 10357963 955859216 1780215808 -0.4627472162 0.4000454843 2.0079007149 597 23.8400000000 0.1388818026 0.0123442365 0.1388818026 0.0099504545 0.0722570000 10359217 955859216 1781575680 -0.4666437507 0.4013454318 1.9996672869 598 23.8800000000 0.1423313171 0.0125616062 0.1423313171 0.0099489170 0.0863180000 10360471 955859216 1780953088 -0.4748108685 0.4041348398 1.9908863306 599 23.9200000000 0.1423231065 0.0127782364 0.1423313171 0.0099477865 0.1144740000 10361725 955859216 1778417664 -0.4846232533 0.4037788510 1.9852675200 600 23.9600000000 0.1377597749 0.0129865389 0.1423313171 0.0099432660 0.1001500000 10362979 955859216 1777422336 -0.4906699657 0.3980017006 1.9772713184 601 24.0000000000 0.1383575350 0.0131951429 0.1423313171 0.0099384659 0.0913030000 10364233 955859216 1776533504 -0.4982602000 0.3975169659 1.9692144394 602 24.0400000000 0.1423961520 0.0134097625 0.1423961520 0.0099449092 0.0885960000 10365487 955859216 1775644672 -0.5147450566 0.3998710811 1.9526646137 603 24.0800000000 0.1423781514 0.0136236405 0.1423961520 0.0099403825 0.1056450000 10366741 955859216 1774755840 -0.5239998698 0.3988809884 1.9449220896 604 24.1200000000 0.1436503083 0.0138389164 0.1436503083 0.0099385726 0.0904480000 10367995 955859216 1773867008 -0.5358856916 0.3977912664 1.9361777306 605 24.1600000000 0.1436581016 0.0140534936 0.1436581016 0.0099389456 0.0833630000 10369249 955859216 1772978176 -0.5422284007 0.3976066709 1.9281113148 606 24.2000000000 0.1444456577 0.0142686622 0.1444456577 0.0099345317 0.0913340000 10370503 955859216 1772089344 -0.5476147532 0.3981221020 1.9196084738 607 24.2400000000 0.1442666203 0.0144828268 0.1444456577 0.0099286133 0.1077050000 10371757 955859216 1771200512 -0.5545536280 0.3965704441 1.9109951258 608 24.2800000000 0.1456099600 0.0146984965 0.1456099600 0.0099230654 0.1039210000 10373011 955859216 1770422272 -0.5627246499 0.3965212703 1.9019131660 609 24.3200000000 0.1465010494 0.0149149210 0.1465010494 0.0099181450 0.0937800000 10374265 955859216 1769533440 -0.5709350109 0.3970898688 1.8937999010 610 24.3600000000 0.1475168914 0.0151323013 0.1475168914 0.0099137339 0.1119990000 10375519 955859216 1768771584 -0.5759998560 0.3974133134 1.8856420517 611 24.4000000000 0.1482150853 0.0153501127 0.1482150853 0.0099083418 0.0861670000 10376773 955859216 1767899136 -0.5808492303 0.3973387480 1.8771188259 612 24.4400000000 0.1485912949 0.0155678271 0.1485912949 0.0099033953 0.1250360000 10378027 955859216 1767010304 -0.5875107050 0.3962423503 1.8684313297 613 24.4800000000 0.1503282636 0.0157876647 0.1503282636 0.0098993494 0.0987800000 10379281 955859216 1766121472 -0.5946712494 0.3973564506 1.8595471382 614 24.5200000000 0.1510707587 0.0160079954 0.1510707587 0.0098950792 0.0909180000 10380535 955859216 1765232640 -0.6013901830 0.3972465396 1.8518471718 615 24.5600000000 0.1521495283 0.0162293638 0.1521495283 0.0098905238 0.1042350000 10381789 955859216 1765117952 -0.6070680022 0.3977324367 1.8431555033 616 24.6000000000 0.1533930302 0.0164520321 0.1533930302 0.0098858080 0.0721750000 10383043 955859216 1765117952 -0.6145247221 0.3981744349 1.8337002993 617 24.6400000000 0.1544338018 0.0166756654 0.1544338018 0.0098814526 0.0870410000 10384297 955859216 1765117952 -0.6217142940 0.3988413215 1.8246912956 618 24.6800000000 0.1558918357 0.0169009343 0.1558918357 0.0098768605 0.1086170000 10385551 955859216 1765101568 -0.6261014342 0.4002063572 1.8159363270 619 24.7200000000 0.1569269598 0.0171271476 0.1569269598 0.0098709618 0.1283640000 10386805 955859216 1765101568 -0.6294794679 0.4014387131 1.8084532022 620 24.7600000000 0.1591604203 0.0173562335 0.1591604203 0.0098755047 0.1102400000 10388059 955859216 1765101568 -0.6419209242 0.4025430977 1.7895008326 621 24.8000000000 0.1603453308 0.0175864897 0.1603453308 0.0098706830 0.0849340000 10389313 955859216 1765576704 -0.6464197636 0.4025070965 1.7810217142 622 24.8400000000 0.1616294682 0.0178180700 0.1616294682 0.0098656602 0.0888990000 10390567 955859216 1764954112 -0.6533852220 0.4016273618 1.7710403204 623 24.8800000000 0.1627532691 0.0180507108 0.1627532691 0.0098598325 0.0858530000 10391821 955859216 1765576704 -0.6587702036 0.4015574753 1.7618789673 624 24.9200000000 0.1640079170 0.0182846166 0.1640079170 0.0098534968 0.0876240000 10393075 955859216 1764843520 -0.6644129753 0.4014781117 1.7524470091 625 24.9600000000 0.1653884202 0.0185199827 0.1653884202 0.0098469797 0.1078700000 10394329 955859216 1764438016 -0.6700846553 0.4017739892 1.7418390512 626 25.0000000000 0.1666800529 0.0187566601 0.1666800529 0.0098407094 0.0897150000 10395583 955859216 1766211584 -0.6771451831 0.4022804499 1.7312668562 627 25.0400000000 0.1678528935 0.0189944531 0.1678528935 0.0098354153 0.0864030000 10396837 955859216 1768226816 -0.6822924614 0.4022586942 1.7212685347 628 25.0800000000 0.1691261828 0.0192335164 0.1691261828 0.0098296962 0.0749290000 10398091 955859216 1769877504 -0.6877025366 0.4017480314 1.7111703157 629 25.1200000000 0.1706975102 0.0194743177 0.1706975102 0.0098234328 0.0941620000 10399345 955859216 1771655168 -0.6947211027 0.4028622508 1.6987904310 630 25.1600000000 0.1719114035 0.0197162813 0.1719114035 0.0098194597 0.0917450000 10400599 955859216 1773305856 -0.6990674138 0.4032313526 1.6887629032 631 25.2000000000 0.1731402874 0.0199594255 0.1731402874 0.0098120095 0.1101120000 10401853 955859216 1774956544 -0.7023217082 0.4034056067 1.6786415577 632 25.2400000000 0.1746941358 0.0202042589 0.1746941358 0.0098046054 0.1101130000 10403107 955859216 1776734208 -0.7093465328 0.4035718441 1.6658257246 633 25.2800000000 0.1762242019 0.0204507359 0.1762242019 0.0097989004 0.1073880000 10404361 955859216 1778384896 -0.7157018185 0.4034766555 1.6536700726 634 25.3200000000 0.1775293052 0.0206984939 0.1775293052 0.0097924055 0.1078990000 10405615 955859216 1780035584 -0.7187411189 0.4034074843 1.6434625387 635 25.3600000000 0.1786304712 0.0209472057 0.1786304712 0.0097863720 0.0882110000 10406869 955859216 1781813248 -0.7195961475 0.4036341310 1.6349233389 636 25.4000000000 0.1803312898 0.0211978096 0.1803312898 0.0097913422 0.0902790000 10408123 955859216 1783463936 -0.7289183736 0.4039677680 1.6207726002 637 25.4400000000 0.1820776761 0.0214503683 0.1820776761 0.0097845424 0.0882990000 10409377 955859216 1785114624 -0.7380531430 0.4058237970 1.6066764593 638 25.4800000000 0.1832157522 0.0217039190 0.1832157522 0.0097808524 0.0889450000 10410631 955859216 1786892288 -0.7381903529 0.4071161151 1.5972592831 639 25.5200000000 0.1846261472 0.0219588834 0.1846261472 0.0097738763 0.0868000000 10411885 955859216 1785937920 -0.7427017093 0.4078491628 1.5856471062 640 25.5600000000 0.1862366050 0.0222155673 0.1862366050 0.0097678699 0.0867890000 10413139 955859216 1784373248 -0.7469442487 0.4083625972 1.5731577873 641 25.6000000000 0.1876284629 0.0224736218 0.1876284629 0.0097610835 0.0876270000 10414393 955859216 1783877632 -0.7494103312 0.4089080989 1.5620675087 642 25.6400000000 0.1891671270 0.0227332690 0.1891671270 0.0097540736 0.0831930000 10415647 955859216 1781981184 -0.7527092099 0.4088305235 1.5500767231 643 25.6800000000 0.1905604750 0.0229942755 0.1905604750 0.0097472276 0.0871780000 10416901 955859216 1781354496 -0.7554300427 0.4085972011 1.5383391380 644 25.7200000000 0.1919281483 0.0232565952 0.1919281483 0.0097409138 0.0875170000 10418155 955859216 1780469760 -0.7590576410 0.4078688920 1.5269947052 645 25.7600000000 0.1934756488 0.0235205007 0.1934756488 0.0097346350 0.1087400000 10419409 955859216 1779580928 -0.7644357085 0.4082689583 1.5146116018 646 25.8000000000 0.1949950904 0.0237859412 0.1949950904 0.0097284438 0.0869070000 10420663 955859216 1780924416 -0.7673354149 0.4087108076 1.5025258064 647 25.8400000000 0.1964821815 0.0240528597 0.1964821815 0.0097222862 0.0890610000 10421917 955859216 1782702080 -0.7698933482 0.4099799693 1.4910206795 648 25.8800000000 0.1976007372 0.0243206805 0.1976007372 0.0097158698 0.1097050000 10423171 955859216 1784352768 -0.7703783512 0.4094637036 1.4818397760 649 25.9200000000 0.1990215927 0.0245898653 0.1990215927 0.0097112097 0.0878450000 10424425 955859216 1786130432 -0.7747337222 0.4091572464 1.4698945284 650 25.9600000000 0.2005532086 0.0248605781 0.2005532086 0.0097061038 0.1109560000 10425679 955859216 1787781120 -0.7788801193 0.4085720778 1.4577455521 651 26.0000000000 0.2019978464 0.0251326784 0.2019978464 0.0097008901 0.0860150000 10426933 955859216 1787027456 -0.7812722325 0.4076712430 1.4474906921 652 26.0400000000 0.2033795118 0.0254060631 0.2033795118 0.0096964727 0.0852660000 10428187 955859216 1785249792 -0.7834735513 0.4071759284 1.4362157583 653 26.0800000000 0.2049016356 0.0256809414 0.2049016356 0.0096923612 0.1105690000 10429441 955859216 1783631872 -0.7880960703 0.4055803418 1.4239004850 654 26.1200000000 0.2062811702 0.0259570886 0.2062811702 0.0096877600 0.1046020000 10430695 955859216 1782640640 -0.7913042307 0.4040030539 1.4128909111 655 26.1600000000 0.2075938582 0.0262343966 0.2075938582 0.0096829831 0.0893160000 10431949 955859216 1781723136 -0.7946770787 0.4018277824 1.4017403126 656 26.2000000000 0.2089393586 0.0265129103 0.2089393586 0.0096791829 0.1068690000 10433203 955859216 1780703232 -0.7990125418 0.4006650746 1.3903621435 657 26.2400000000 0.2103875130 0.0267927803 0.2103875130 0.0096738626 0.0863260000 10434457 955859216 1779945472 -0.8044062257 0.3989142179 1.3785520792 658 26.2800000000 0.2116208822 0.0270736741 0.2116208822 0.0096680517 0.0850540000 10435711 955859216 1779073024 -0.8067110181 0.3973897398 1.3687065840 659 26.3200000000 0.2130367905 0.0273558639 0.2130367905 0.0096632400 0.0872250000 10436965 955859216 1778184192 -0.8109687567 0.3968669772 1.3571439981 660 26.3600000000 0.2143843472 0.0276392404 0.2143843472 0.0096574647 0.0885160000 10438219 955859216 1777303552 -0.8141701818 0.3956452608 1.3459073305 661 26.4000000000 0.2158224285 0.0279239351 0.2158224285 0.0096532414 0.1088610000 10439473 955859216 1776414720 -0.8181895614 0.3951139450 1.3342385292 662 26.4400000000 0.2172848284 0.0282099787 0.2172848284 0.0096488038 0.0987540000 10440727 955859216 1775525888 -0.8236070871 0.3947765827 1.3219418526 663 26.4800000000 0.2189256847 0.0284976344 0.2189256847 0.0096435038 0.0736140000 10441981 955859216 1774637056 -0.8288320899 0.3953576088 1.3087350130 664 26.5200000000 0.2204315513 0.0287866915 0.2204315513 0.0096388435 0.0902000000 10443235 955859216 1773748224 -0.8330788612 0.3945537210 1.2966569662 665 26.5600000000 0.2235575169 0.0290795800 0.2235575169 0.0096464615 0.1098130000 10444489 955859216 1772732416 -0.8416014910 0.3957711458 1.2721527815 666 26.6000000000 0.2251816839 0.0293740276 0.2251816839 0.0096415844 0.0885860000 10445743 955859216 1771954176 -0.8466864824 0.3973547220 1.2584766150 667 26.6400000000 0.2265629619 0.0296696632 0.2265629619 0.0096360741 0.0889310000 10446997 955859216 1771081728 -0.8501132131 0.3982163966 1.2465783358 668 26.6800000000 0.2281538993 0.0299667953 0.2281538993 0.0096307871 0.0867110000 10448251 955859216 1770192896 -0.8557011485 0.3990764618 1.2330052853 669 26.7200000000 0.2295984775 0.0302651984 0.2295984775 0.0096269466 0.0867300000 10449505 955859216 1769304064 -0.8589963317 0.4005114436 1.2208443880 670 26.7600000000 0.2311007082 0.0305649529 0.2311007082 0.0096209977 0.0850400000 10450759 955859216 1770663936 -0.8620678186 0.4029537141 1.2084670067 671 26.8000000000 0.2327459306 0.0308662658 0.2327459306 0.0096160589 0.0867570000 10452013 955859216 1770024960 -0.8677392006 0.4029878676 1.1953006983 672 26.8400000000 0.2344242930 0.0311691795 0.2344242930 0.0096121926 0.1109940000 10453267 955859216 1767268352 -0.8727859855 0.4025056958 1.1825953722 673 26.8800000000 0.2361489236 0.0314737557 0.2361489236 0.0096082796 0.1045900000 10454521 955859216 1766383616 -0.8766448498 0.4019788206 1.1697077751 674 26.9200000000 0.2375773042 0.0317795473 0.2375773042 0.0096030514 0.0895000000 10455775 955859216 1765625856 -0.8776250482 0.4016765654 1.1580845118 675 26.9600000000 0.2391944528 0.0320868286 0.2391944528 0.0096010686 0.1084240000 10457029 955859216 1765101568 -0.8792288303 0.4009625614 1.1458344460 676 27.0000000000 0.2407105714 0.0323954436 0.2407105714 0.0096013060 0.1015660000 10458283 955859216 1765109760 -0.8829575777 0.4011472166 1.1326965094 677 27.0400000000 0.2421898097 0.0327053319 0.2421898097 0.0095994853 0.0723760000 10459537 955859216 1765109760 -0.8866648674 0.4014855921 1.1203556061 678 27.0800000000 0.2434213161 0.0330161224 0.2434213161 0.0095965171 0.0893940000 10460791 955859216 1765126144 -0.8897171021 0.4022081196 1.1098093987 679 27.1200000000 0.2448724359 0.0333281347 0.2448724359 0.0095941916 0.1174220000 10462045 955859216 1765126144 -0.8926128745 0.4021390378 1.0988250971 680 27.1600000000 0.2464249432 0.0336415123 0.2464249432 0.0095899046 0.0799760000 10463299 955859216 1765126144 -0.8954261541 0.4029375315 1.0895076990 681 27.2000000000 0.2472808957 0.0339552266 0.2472808957 0.0095872045 0.1202610000 10464553 955859216 1765109760 -0.8984030485 0.4030819833 1.0791412592 682 27.2400000000 0.2485035211 0.0342698135 0.2485035211 0.0095851921 0.0897520000 10465807 955859216 1765109760 -0.9023234248 0.4041728973 1.0676862001 683 27.2800000000 0.2499413490 0.0345855844 0.2499413490 0.0095801265 0.0872460000 10467061 955859216 1765109760 -0.9076170325 0.4052801728 1.0558613539 684 27.3200000000 0.2517052293 0.0349030108 0.2517052293 0.0095761580 0.1028880000 10468315 955859216 1765109760 -0.9085191488 0.4048226774 1.0465269089 685 27.3600000000 0.2526684701 0.0352209166 0.2526684701 0.0095735938 0.0906370000 10469569 955859216 1765109760 -0.9089626670 0.4051163793 1.0368676186 686 27.4000000000 0.2535226345 0.0355391407 0.2535226345 0.0095748892 0.0997180000 10470823 955859216 1765109760 -0.9148553014 0.4051046073 1.0239057541 687 27.4400000000 0.2552967668 0.0358590208 0.2552967668 0.0095707361 0.0924230000 10472077 955859216 1765109760 -0.9187911153 0.4047575891 1.0125721693 688 27.4800000000 0.2560940385 0.0361791298 0.2560940385 0.0095654245 0.0839150000 10473331 955859216 1765109760 -0.9211534262 0.4053468406 1.0031690598 689 27.5200000000 0.2580284774 0.0365011172 0.2580284774 0.0095617121 0.0860990000 10474585 955859216 1765109760 -0.9264448285 0.4063942730 0.9899606705 690 27.5600000000 0.2592678070 0.0368239675 0.2592678070 0.0095571033 0.1110900000 10475839 955859216 1765109760 -0.9272511601 0.4070830345 0.9795385003 691 27.6000000000 0.2606100142 0.0371478258 0.2606100142 0.0095515113 0.1065430000 10477093 955859216 1765076992 -0.9292711020 0.4071839452 0.9688038826 692 27.6400000000 0.2620848417 0.0374728793 0.2620848417 0.0095455216 0.1083730000 10478347 955859216 1766473728 -0.9319155812 0.4062156081 0.9562802315 693 27.6800000000 0.2634549141 0.0377989717 0.2634549141 0.0095391513 0.1061190000 10479601 955859216 1768235008 -0.9342101216 0.4066929519 0.9442195296 694 27.7200000000 0.2650966942 0.0381264900 0.2650966942 0.0095333712 0.1102450000 10480855 955859216 1770012672 -0.9362184405 0.4061421752 0.9320423007 695 27.7600000000 0.2665830255 0.0384552044 0.2665830255 0.0095278517 0.0885460000 10482109 955859216 1771663360 -0.9387520552 0.4043545127 0.9194686413 696 27.8000000000 0.2680445015 0.0387850741 0.2680445015 0.0095215826 0.1068300000 10483363 955859216 1773314048 -0.9412298203 0.4038721919 0.9067357183 697 27.8400000000 0.2715000212 0.0391189549 0.2715000212 0.0095184349 0.1116940000 10484617 955859216 1775091712 -0.9457632303 0.3996319175 0.8799903393 698 27.8800000000 0.2729546130 0.0394539631 0.2729546130 0.0095133621 0.0872560000 10485871 955859216 1776742400 -0.9460409284 0.3976215422 0.8690667152 699 27.9200000000 0.2744938731 0.0397902147 0.2744938731 0.0095186038 0.0862700000 10487125 955859216 1778520064 -0.9490805268 0.4007095098 0.8548042774 700 27.9600000000 0.2762239873 0.0401279772 0.2762239873 0.0095118925 0.0887340000 10488379 955859216 1780170752 -0.9501543641 0.4030864239 0.8400380611 701 28.0000000000 0.2777617872 0.0404669698 0.2777617872 0.0095086803 0.1089540000 10489633 955859216 1781821440 -0.9485515952 0.4034119844 0.8279259205 702 28.0400000000 0.2792228162 0.0408070779 0.2792228162 0.0095021014 0.1113380000 10490887 955859216 1783599104 -0.9487904310 0.4054094553 0.8150773048 703 28.0800000000 0.2811239660 0.0411489227 0.2811239660 0.0094960683 0.0860290000 10492141 955859216 1785249792 -0.9521736503 0.4051845968 0.7999957204 704 28.1200000000 0.2828529775 0.0414922523 0.2828529775 0.0094945058 0.0880390000 10493395 955859216 1786900480 -0.9516746402 0.4032769799 0.7869195938 705 28.1600000000 0.2848508954 0.0418374419 0.2848508954 0.0094884732 0.1105280000 10494649 955859216 1784795136 -0.9521536231 0.4008947015 0.7726511359 706 28.2000000000 0.2866151035 0.0421841524 0.2866151035 0.0094835980 0.0865470000 10495903 955859216 1783758848 -0.9528180957 0.3986001015 0.7589381933 707 28.2400000000 0.2883094549 0.0425322787 0.2883094549 0.0094831881 0.0879440000 10497157 955859216 1782890496 -0.9531033039 0.4001388252 0.7443948388 708 28.2800000000 0.2901175022 0.0428819754 0.2901175022 0.0094806974 0.0950770000 10498411 955859216 1782001664 -0.9563463926 0.4031725824 0.7290710807 709 28.3200000000 0.2920399606 0.0432333971 0.2920399606 0.0094789032 0.0818130000 10499665 955859216 1780965376 -0.9568671584 0.4020180106 0.7150640488 710 28.3600000000 0.2932121158 0.0435854798 0.2932121158 0.0094733257 0.0843890000 10500919 955859216 1782345728 -0.9540630579 0.4020971656 0.7050120831 711 28.4000000000 0.2947912812 0.0439387932 0.2947912812 0.0094691483 0.0874600000 10502173 955859216 1781694464 -0.9555001259 0.4024812877 0.6921634674 712 28.4400000000 0.2962139845 0.0442931122 0.2962139845 0.0094632909 0.1088570000 10503427 955859216 1778696192 -0.9558684826 0.4014793038 0.6804097295 713 28.4800000000 0.2975853682 0.0446483608 0.2975853682 0.0094579693 0.1072390000 10504681 955859216 1777811456 -0.9542700052 0.3996452689 0.6699193716 714 28.5200000000 0.2988280058 0.0450043547 0.2988280058 0.0094586940 0.0889010000 10505935 955859216 1776922624 -0.9551245570 0.4002946913 0.6585221291 715 28.5600000000 0.3004682660 0.0453616469 0.3004682660 0.0094578921 0.0885180000 10507189 955859216 1776033792 -0.9571409822 0.4038942158 0.6439610124 716 28.6000000000 0.3021510243 0.0457202913 0.3021510243 0.0094531179 0.1095980000 10508443 955859216 1775144960 -0.9574733973 0.4048926532 0.6311494112 717 28.6400000000 0.3052344322 0.0460822357 0.3052344322 0.0094507541 0.0891060000 10509697 955859216 1774256128 -0.9561702013 0.4037730992 0.6222028136 718 28.6800000000 0.3047311008 0.0464424709 0.3052344322 0.0094457722 0.0861660000 10510951 955859216 1773367296 -0.9568325281 0.4024029970 0.6136261821 719 28.7200000000 0.3059073389 0.0468033400 0.3059073389 0.0094433042 0.0882400000 10512205 955859216 1772478464 -0.9598246217 0.4026707709 0.6007723808 720 28.7600000000 0.3060064316 0.0471633443 0.3060064316 0.0094374620 0.0842880000 10513459 955859216 1771589632 -0.9617741704 0.4016375244 0.5899952650 721 28.8000000000 0.3083454072 0.0475255940 0.3083454072 0.0094350058 0.1057630000 10514713 955859216 1770700800 -0.9609672427 0.4052490294 0.5788618922 722 28.8400000000 0.3102914989 0.0478895357 0.3102914989 0.0094336432 0.0848080000 10515967 955859216 1769922560 -0.9668559432 0.4092736840 0.5664252639 723 28.8800000000 0.3112670481 0.0482538200 0.3112670481 0.0094306206 0.1273240000 10517221 955859216 1769050112 -0.9727916718 0.4098014235 0.5551211834 724 28.9200000000 0.3095684350 0.0486147518 0.3112670481 0.0094312658 0.1025270000 10518475 955859216 1768271872 -0.9758428931 0.4083173573 0.5468553305 725 28.9600000000 0.3141938746 0.0489810678 0.3141938746 0.0094284379 0.0920500000 10519729 955859216 1767399424 -0.9806105494 0.4134523869 0.5343126655 726 29.0000000000 0.3153890669 0.0493480210 0.3153890669 0.0094282728 0.1052240000 10520983 955859216 1766510592 -0.9833641052 0.4124170244 0.5209096670 727 29.0400000000 0.3180973828 0.0497176900 0.3180973828 0.0094267589 0.1084360000 10522237 955859216 1765621760 -0.9940951467 0.4139254391 0.5007383823 728 29.0800000000 0.3197219968 0.0500885750 0.3197219968 0.0094251689 0.1116330000 10523491 955859216 1765101568 -1.0051114559 0.4146980643 0.4864257276 729 29.1200000000 0.3212292790 0.0504605101 0.3212292790 0.0094423221 0.1042460000 10524745 955859216 1765060608 -1.0081931353 0.4103988409 0.4781302810 730 29.1600000000 0.3220046759 0.0508324884 0.3220046759 0.0094374444 0.0885630000 10525999 955859216 1765093376 -1.0110609531 0.4109363258 0.4691911340 731 29.2000000000 0.3237181604 0.0512057930 0.3237181604 0.0094325570 0.1192310000 10527253 955859216 1765101568 -1.0198479891 0.4151795208 0.4553169608 732 29.2400000000 0.3245441318 0.0515792061 0.3245441318 0.0094335995 0.0765310000 10528507 955859216 1766465536 -1.0254493952 0.4171389043 0.4445674121 733 29.2800000000 0.3256497085 0.0519531085 0.3256497085 0.0094313867 0.0868920000 10529761 955859216 1768353792 -1.0290274620 0.4208979607 0.4346870482 734 29.3200000000 0.3277449608 0.0523288467 0.3277449608 0.0094271251 0.1106210000 10531015 955859216 1770004480 -1.0373675823 0.4270527661 0.4225100577 735 29.3600000000 0.3286679387 0.0527048183 0.3286679387 0.0094461275 0.0839580000 10532269 955859216 1771782144 -1.0423840284 0.4260592461 0.4128885269 736 29.4000000000 0.3296413422 0.0530810907 0.3296413422 0.0094471911 0.0863200000 10533523 955859216 1773432832 -1.0451062918 0.4278557897 0.4048543870 737 29.4400000000 0.3314552903 0.0534588034 0.3314552903 0.0094417580 0.0896470000 10534777 955859216 1775210496 -1.0505461693 0.4343170226 0.3928372860 738 29.4800000000 0.3321927190 0.0538364916 0.3321927190 0.0094556254 0.1089450000 10536031 955859216 1776861184 -1.0554355383 0.4360845387 0.3825838566 739 29.5200000000 0.3326151669 0.0542137293 0.3326151669 0.0094693372 0.0910840000 10537285 955859216 1778638848 -1.0558853149 0.4346202016 0.3770369291 740 29.5600000000 0.3342669904 0.0545921797 0.3342669904 0.0094645400 0.1054530000 10538539 955859216 1780289536 -1.0585335493 0.4357562065 0.3679257333 741 29.6000000000 0.3354527950 0.0549712088 0.3354527950 0.0094591251 0.1099790000 10539793 955859216 1782067200 -1.0608017445 0.4372504950 0.3572566211 742 29.6400000000 0.3366141617 0.0553507816 0.3366141617 0.0094546816 0.0885310000 10541047 955859216 1783717888 -1.0633133650 0.4394308925 0.3472517133 743 29.6800000000 0.3339849114 0.0557257938 0.3366141617 0.0094532940 0.0890740000 10542301 955859216 1785368576 -1.0664846897 0.4388972223 0.3395018876 744 29.7200000000 0.3392252028 0.0561068414 0.3392252028 0.0094506721 0.0871930000 10543555 955859216 1787146240 -1.0730077028 0.4458816051 0.3300049007 745 29.7600000000 0.3393918276 0.0564870897 0.3393918276 0.0094591071 0.0869820000 10544809 955859216 1786277888 -1.0761295557 0.4466025531 0.3245900273 746 29.8000000000 0.3402486145 0.0568674671 0.3402486145 0.0094638634 0.1225870000 10546063 955859216 1784143872 -1.0810453892 0.4483213723 0.3164979219 747 29.8400000000 0.3415465057 0.0572485636 0.3415465057 0.0094820685 0.0917810000 10547317 955859216 1783263232 -1.0762863159 0.4481977820 0.3111070096 748 29.8800000000 0.3420465291 0.0576293095 0.3420465291 0.0094793550 0.0914690000 10548571 955859216 1782226944 -1.0741686821 0.4455949664 0.3078617752 749 29.9200000000 0.3397721052 0.0580060022 0.3420465291 0.0094742009 0.0876010000 10549825 955859216 1781358592 -1.0781800747 0.4433948994 0.3001731932 750 29.9600000000 0.3442080319 0.0583876049 0.3442080319 0.0094700372 0.1039270000 10551079 955859216 1780469760 -1.0817151070 0.4503744543 0.2899506390 751 30.0000000000 0.3430166543 0.0587666049 0.3442080319 0.0094746742 0.0928230000 10552333 955859216 1779433472 -1.0829756260 0.4478524923 0.2851592898 752 30.0400000000 0.3429683745 0.0591445328 0.3442080319 0.0094705175 0.0867750000 10553587 955859216 1778675712 -1.0854473114 0.4466265142 0.2812658548 753 30.0800000000 0.3463104367 0.0595258952 0.3463104367 0.0094654359 0.0875730000 10554841 955859216 1777803264 -1.0901122093 0.4534581304 0.2720904648 754 30.1200000000 0.3472548127 0.0599074986 0.3472548127 0.0094743403 0.0834920000 10556095 955859216 1776914432 -1.0890390873 0.4513163865 0.2669502199 755 30.1600000000 0.3482151330 0.0602893630 0.3482151330 0.0094727027 0.1102860000 10557349 955859216 1776025600 -1.0849530697 0.4493988454 0.2644817829 756 30.2000000000 0.3462525010 0.0606676211 0.3482151330 0.0094666470 0.0869500000 10558603 955859216 1775136768 -1.0870393515 0.4471729398 0.2573064864 757 30.2400000000 0.3465223610 0.0610452363 0.3482151330 0.0094619955 0.1084050000 10559857 955859216 1774231552 -1.0891109705 0.4465557039 0.2505385578 758 30.2800000000 0.3465471566 0.0614218880 0.3482151330 0.0094573344 0.1069190000 10561111 955859216 1773359104 -1.0915886164 0.4469425082 0.2440889478 759 30.3200000000 0.3504952788 0.0618027488 0.3504952788 0.0094523609 0.0989420000 10562365 955859216 1772470272 -1.0931006670 0.4534842074 0.2341220826 760 30.3600000000 0.3517159522 0.0621842136 0.3517159522 0.0094574146 0.1311100000 10563619 955859216 1771581440 -1.0896124840 0.4520024955 0.2283884585 761 30.4000000000 0.3515941501 0.0625645157 0.3517159522 0.0094545220 0.0909660000 10564873 955859216 1770692608 -1.0891977549 0.4504970610 0.2236224860 762 30.4400000000 0.3509047329 0.0629429149 0.3517159522 0.0094497483 0.1111360000 10566127 955859216 1769914368 -1.0923444033 0.4497354627 0.2161748409 763 30.4800000000 0.3532996774 0.0633234612 0.3532996774 0.0094498370 0.1273050000 10567381 955859216 1769041920 -1.0928585529 0.4494722486 0.2081676424 764 30.5200000000 0.3532938957 0.0637030036 0.3532996774 0.0094460885 0.1072410000 10568635 955859216 1767235584 -1.0918720961 0.4507268965 0.2014608085 765 30.5600000000 0.3559527695 0.0640850295 0.3559527695 0.0094413217 0.1069430000 10569889 955859216 1768988672 -1.0912886858 0.4522505701 0.1924849451 766 30.6000000000 0.3584733307 0.0644693484 0.3584733307 0.0094385085 0.0880990000 10571143 955859216 1770766336 -1.0866234303 0.4492917657 0.1881235093 767 30.6400000000 0.3579295278 0.0648519562 0.3584733307 0.0094326691 0.0880010000 10572397 955859216 1772417024 -1.0865079165 0.4488724470 0.1781471521 768 30.6800000000 0.3591803908 0.0652351963 0.3591803908 0.0094281730 0.0896000000 10573651 955859216 1774194688 -1.0862810612 0.4488426447 0.1687972993 769 30.7200000000 0.3599649370 0.0656184600 0.3599649370 0.0094271339 0.0869350000 10574905 955859216 1775845376 -1.0800414085 0.4434947968 0.1658857912 770 30.7600000000 0.3595846593 0.0660002343 0.3599649370 0.0094225588 0.1083300000 10576159 955859216 1777496064 -1.0791206360 0.4426594675 0.1581907868 771 30.8000000000 0.3607573211 0.0663825392 0.3607573211 0.0094180374 0.1293200000 10577413 955859216 1779273728 -1.0791574717 0.4418338835 0.1481812596 772 30.8400000000 0.3627398908 0.0667664217 0.3627398908 0.0094131577 0.1266180000 10578667 955859216 1780924416 -1.0728423595 0.4395081699 0.1419151723 773 30.8800000000 0.3638265133 0.0671507168 0.3638265133 0.0094109001 0.1299010000 10579921 955859216 1782702080 -1.0675431490 0.4386327863 0.1350878328 774 30.9200000000 0.3618967831 0.0675315257 0.3638265133 0.0094118460 0.0860300000 10581175 955859216 1784352768 -1.0689038038 0.4376614988 0.1260651201 775 30.9600000000 0.3628142178 0.0679125356 0.3638265133 0.0094091226 0.0706920000 10582429 955859216 1786003456 -1.0708222389 0.4379924238 0.1179051101 776 31.0000000000 0.3635858297 0.0682935579 0.3638265133 0.0094047024 0.0881200000 10583683 955859216 1787781120 -1.0720984936 0.4386543930 0.1112491190 777 31.0400000000 0.3658840656 0.0686765573 0.3658840656 0.0094003573 0.0878350000 10584937 955859216 1787027456 -1.0684618950 0.4398322403 0.1045899093 778 31.0800000000 0.3657409847 0.0690583882 0.3658840656 0.0093966349 0.1046070000 10586191 955859216 1784020992 -1.0690234900 0.4395985305 0.0971165895 779 31.1200000000 0.3654980361 0.0694389269 0.3658840656 0.0093938093 0.0884940000 10587445 955859216 1782988800 -1.0687646866 0.4423492551 0.0894025639 780 31.1600000000 0.3699463904 0.0698241928 0.3699463904 0.0094005190 0.1089220000 10588699 955859216 1782120448 -1.0686212778 0.4523881972 0.0807454363 781 31.2000000000 0.3708565533 0.0702096376 0.3708565533 0.0093955283 0.0854070000 10589953 955859216 1781231616 -1.0636274815 0.4537114203 0.0730377436 782 31.2400000000 0.3711825311 0.0705945134 0.3711825311 0.0093909862 0.1072580000 10591207 955859216 1780342784 -1.0596157312 0.4522765279 0.0662701577 783 31.2800000000 0.3721803725 0.0709796805 0.3721803725 0.0093864443 0.1452140000 10592461 955859216 1779437568 -1.0548874140 0.4532394409 0.0619068816 784 31.3200000000 0.3712773025 0.0713627132 0.3721803725 0.0093806282 0.1484220000 10593715 955859216 1778565120 -1.0541788340 0.4521485269 0.0530290119 785 31.3600000000 0.3717930019 0.0717454270 0.3721803725 0.0093761881 0.1280690000 10594969 955859216 1779924992 -1.0551708937 0.4508954585 0.0471423604 786 31.4000000000 0.3748058081 0.0721310000 0.3748058081 0.0093725604 0.1293550000 10596223 955859216 1781813248 -1.0514243841 0.4492116868 0.0426159538 787 31.4400000000 0.3750926256 0.0725159576 0.3750926256 0.0093670923 0.1286170000 10597477 955859216 1783463936 -1.0483078957 0.4466178119 0.0385356657 788 31.4800000000 0.3745656908 0.0728992694 0.3750926256 0.0093613199 0.1085260000 10598731 955859216 1785114624 -1.0458132029 0.4457532465 0.0333631001 789 31.5200000000 0.3745059371 0.0732815339 0.3750926256 0.0093556400 0.1081540000 10599985 955859216 1786892288 -1.0442494154 0.4455291629 0.0270189624 790 31.5600000000 0.3741371334 0.0736623638 0.3750926256 0.0093498337 0.0836530000 10601239 955859216 1785749504 -1.0424690247 0.4448830187 0.0237746276 791 31.6000000000 0.3734492362 0.0740413611 0.3750926256 0.0093440544 0.0705770000 10602493 955859216 1784913920 -1.0433889627 0.4460580945 0.0168967582 792 31.6400000000 0.3756670654 0.0744222016 0.3756670654 0.0093400467 0.0895060000 10603747 955859216 1783877632 -1.0437915325 0.4453527927 0.0113372477 793 31.6800000000 0.3767229021 0.0748034131 0.3767229021 0.0093344869 0.1051930000 10605001 955859216 1783009280 -1.0411156416 0.4432958663 0.0099818297 794 31.7200000000 0.3764355779 0.0751833025 0.3767229021 0.0093294354 0.0872170000 10606255 955859216 1781972992 -1.0429335833 0.4440574944 0.0021490983 795 31.7600000000 0.3775783479 0.0755636736 0.3775783479 0.0093247405 0.1078980000 10607509 955859216 1781104640 -1.0443137884 0.4443102479 -0.0031684705 796 31.8000000000 0.3789461851 0.0759448074 0.3789461851 0.0093195306 0.1105910000 10608763 955859216 1779826688 -1.0415871143 0.4434787333 -0.0060814563 797 31.8400000000 0.3789705336 0.0763250153 0.3789705336 0.0093137195 0.0888920000 10610017 955859216 1778941952 -1.0396550894 0.4431845844 -0.0105411857 798 31.8800000000 0.3791661263 0.0767045155 0.3791661263 0.0093079726 0.0811960000 10611271 955859216 1780305920 -1.0401513577 0.4408927858 -0.0139802210 799 31.9200000000 0.3823104203 0.0770870009 0.3823104203 0.0093103047 0.0890900000 10612525 955859216 1779658752 -1.0432779789 0.4493012130 -0.0225658081 800 31.9600000000 0.3831706047 0.0774696055 0.3831706047 0.0093095264 0.0704300000 10613779 955859216 1778511872 -1.0448129177 0.4450268447 -0.0280822515 801 32.0000000000 0.3830260932 0.0778510742 0.3831706047 0.0093111267 0.0821790000 10615033 955859216 1777782784 -1.0393403769 0.4340430200 -0.0258060917 802 32.0400000000 0.3822515309 0.0782306259 0.3831706047 0.0093138532 0.0893630000 10616287 955859216 1776914432 -1.0393003225 0.4324963391 -0.0303560086 803 32.0800000000 0.3821474910 0.0786091027 0.3831706047 0.0093137693 0.0900320000 10617541 955859216 1776025600 -1.0407615900 0.4335636795 -0.0378975123 804 32.1199999990 0.3835567236 0.0789883908 0.3835567236 0.0093093845 0.0848150000 10618795 955859216 1775136768 -1.0407534838 0.4317642748 -0.0411922224 805 32.1600000000 0.3852227032 0.0793688061 0.3852227032 0.0093078471 0.0874030000 10620049 955859216 1774100480 -1.0412156582 0.4294118881 -0.0462747179 806 32.2000000000 0.3852607608 0.0797483246 0.3852607608 0.0093180186 0.0704060000 10621303 955859216 1773232128 -1.0382684469 0.4325291812 -0.0633299500 807 32.2400000000 0.3851562738 0.0801267732 0.3852607608 0.0093159251 0.0688070000 10622557 955859216 1772453888 -1.0370967388 0.4339682162 -0.0686802641 808 32.2800000000 0.3837880790 0.0805025916 0.3852607608 0.0093142166 0.0678530000 10623811 955859216 1773830144 -1.0377951860 0.4387409389 -0.0769763812 809 32.3200000000 0.3856098354 0.0808797328 0.3856098354 0.0093098278 0.0679780000 10625065 955859216 1773084672 -1.0406402349 0.4398281276 -0.0844744667 810 32.3600000000 0.3902955055 0.0812617276 0.3902955055 0.0093153636 0.0901590000 10626319 955859216 1772220416 -1.0446221828 0.4403026402 -0.0893955678 811 32.4000000000 0.3915963471 0.0816443843 0.3915963471 0.0093104628 0.0815190000 10627573 955859216 1771274240 -1.0451540947 0.4353153706 -0.0956335962 812 32.4399999990 0.3914968371 0.0820259760 0.3915963471 0.0093115954 0.0910220000 10628827 955859216 1770438656 -1.0447747707 0.4273896813 -0.0972668976 813 32.4800000000 0.3929472268 0.0824084130 0.3929472268 0.0093379516 0.1038110000 10630081 955859216 1769549824 -1.0460748672 0.4392009676 -0.1089090332 814 32.5200000000 0.3950830400 0.0827925342 0.3950830400 0.0093430097 0.1109750000 10631335 955859216 1768771584 -1.0527986288 0.4518619478 -0.1250962317 815 32.5600000000 0.3955343068 0.0831762664 0.3955343068 0.0093635307 0.1081650000 10632589 955859216 1767354368 -1.0545998812 0.4432011247 -0.1276522577 816 32.6000000000 0.3949313164 0.0835583192 0.3955343068 0.0093583961 0.0837600000 10633843 955859216 1768878080 -1.0541523695 0.4391253889 -0.1321439743 817 32.6400000000 0.3941662908 0.0839385003 0.3955343068 0.0093529143 0.0711250000 10635097 955859216 1770639360 -1.0564726591 0.4385846555 -0.1396662295 818 32.6800000000 0.3953399658 0.0843191867 0.3955343068 0.0093483481 0.0675110000 10636351 955859216 1772417024 -1.0608705282 0.4368694127 -0.1479553878 819 32.7200000000 0.3979078531 0.0847020788 0.3979078531 0.0093451539 0.0690060000 10637605 955859216 1774067712 -1.0632442236 0.4327017367 -0.1535450518 820 32.7599999990 0.3973664641 0.0850833768 0.3979078531 0.0093401223 0.0860070000 10638859 955859216 1775718400 -1.0635640621 0.4328306019 -0.1600270271 821 32.7999999990 0.3978258073 0.0854643055 0.3979078531 0.0093357168 0.0885230000 10640113 955859216 1777496064 -1.0663111210 0.4341927469 -0.1684418768 822 32.8400000000 0.3992008567 0.0858459801 0.3992008567 0.0093310234 0.0701900000 10641367 955859216 1779146752 -1.0692064762 0.4336346984 -0.1754063964 823 32.8800000000 0.3995006382 0.0862270915 0.3995006382 0.0093262666 0.0684940000 10642621 955859216 1780924416 -1.0706404448 0.4347550273 -0.1817259640 824 32.9200000000 0.3999106586 0.0866077754 0.3999106586 0.0093212873 0.0694580000 10643875 955859216 1782575104 -1.0744440556 0.4366219342 -0.1908933222 825 32.9600000000 0.4029737711 0.0869912494 0.4029737711 0.0093203716 0.0679340000 10645129 955859216 1784225792 -1.0752435923 0.4336460233 -0.1956039369 826 33.0000000000 0.4021915495 0.0873728478 0.4029737711 0.0093152764 0.0852190000 10646383 955859216 1786003456 -1.0742144585 0.4340656102 -0.2011951953 827 33.0400000000 0.4039780200 0.0877556836 0.4039780200 0.0093107907 0.0719220000 10647637 955859216 1787654144 -1.0778139830 0.4337689281 -0.2107699811 828 33.0800000000 0.4055714309 0.0881395190 0.4055714309 0.0093144869 0.1063430000 10648891 955859216 1784872960 -1.0792800188 0.4256357551 -0.2139011770 829 33.1199999990 0.4041166604 0.0885206736 0.4055714309 0.0093148278 0.1089210000 10650145 955859216 1783877632 -1.0774581432 0.4258576035 -0.2194904089 830 33.1600000000 0.4077190459 0.0889052499 0.4077190459 0.0093291880 0.1120610000 10651399 955859216 1783009280 -1.0865737200 0.4342965186 -0.2322420478 831 33.2000000000 0.4082622230 0.0892895544 0.4082622230 0.0093247964 0.0812830000 10652653 955859216 1781977088 -1.0868275166 0.4312177002 -0.2371638268 832 33.2400000000 0.4091524482 0.0896740049 0.4091524482 0.0093209232 0.0838310000 10653907 955859216 1781104640 -1.0838193893 0.4276836812 -0.2393936515 833 33.2800000000 0.4086477458 0.0900569266 0.4091524482 0.0093183891 0.1101450000 10655161 955859216 1780215808 -1.0828553438 0.4267047644 -0.2466317266 834 33.3200000000 0.4086664617 0.0904389524 0.4091524482 0.0093155803 0.1072340000 10656415 955859216 1779326976 -1.0856666565 0.4252160788 -0.2539148629 835 33.3600000000 0.4091274738 0.0908206153 0.4091524482 0.0093123488 0.1113270000 10657669 955859216 1778438144 -1.0876286030 0.4254721403 -0.2624710798 836 33.4000000000 0.4096762538 0.0912020216 0.4096762538 0.0093090287 0.0845550000 10658923 955859216 1777549312 -1.0883326530 0.4268843830 -0.2703243494 837 33.4399999990 0.4111468792 0.0915842735 0.4111468792 0.0093051674 0.0879240000 10660177 955859216 1776771072 -1.0882766247 0.4266781211 -0.2772021592 838 33.4800000000 0.4125492871 0.0919672867 0.4125492871 0.0093007643 0.0883460000 10661431 955859216 1775898624 -1.0875266790 0.4248300791 -0.2838572860 839 33.5200000000 0.4132593870 0.0923502331 0.4132593870 0.0092979290 0.0868430000 10662685 955859216 1775009792 -1.0854158401 0.4266017973 -0.2946011126 840 33.5600000000 0.4160034060 0.0927355345 0.4160034060 0.0092944232 0.1112300000 10663939 955859216 1774120960 -1.0793236494 0.4231537879 -0.3003696203 841 33.6000000000 0.4164905548 0.0931204989 0.4164905548 0.0092900793 0.0853350000 10665193 955859216 1773215744 -1.0755989552 0.4205569327 -0.3070505261 842 33.6400000000 0.4168905318 0.0935050239 0.4168905318 0.0092906394 0.0865490000 10666447 955859216 1772343296 -1.0742465258 0.4196370542 -0.3157538772 843 33.6800000000 0.4194763899 0.0938917040 0.4194763899 0.0093014965 0.1102330000 10667701 955859216 1771454464 -1.0673177242 0.4185613096 -0.3323706686 844 33.7200000000 0.4197278023 0.0942777657 0.4197278023 0.0092985141 0.1052390000 10668955 955859216 1770676224 -1.0653108358 0.4177085161 -0.3420205712 845 33.7599999990 0.4196972251 0.0946628775 0.4197278023 0.0092978991 0.1060770000 10670209 955859216 1769803776 -1.0651977062 0.4198211432 -0.3524242938 846 33.7999999990 0.4241299033 0.0950523185 0.4241299033 0.0093053135 0.1282430000 10671463 955859216 1768914944 -1.0654640198 0.4296978712 -0.3637838066 847 33.8400000000 0.4252454638 0.0954421569 0.4252454638 0.0093021162 0.0731970000 10672717 955859216 1768136704 -1.0609756708 0.4321724474 -0.3742900193 848 33.8800000000 0.4265233874 0.0958325829 0.4265233874 0.0093010201 0.0945940000 10673971 955859216 1767264256 -1.0523990393 0.4315743148 -0.3823587298 849 33.9200000000 0.4270841777 0.0962227496 0.4270841777 0.0092968741 0.1280420000 10675225 955859216 1766322176 -1.0506185293 0.4280042052 -0.3908546567 850 33.9600000000 0.4288760126 0.0966141064 0.4288760126 0.0092918168 0.0707570000 10676479 955859216 1765486592 -1.0433223248 0.4271385372 -0.4004274905 851 34.0000000000 0.4299139380 0.0970057631 0.4299139380 0.0092864685 0.0880430000 10677733 955859216 1765113856 -1.0361900330 0.4251537919 -0.4082155228 852 34.0400000000 0.4311291575 0.0973979267 0.4311291575 0.0092820028 0.0842430000 10678987 955859216 1766465536 -1.0328950882 0.4261899292 -0.4179430008 853 34.0800000000 0.4323214889 0.0977905686 0.4323214889 0.0092772227 0.0881240000 10680241 955859216 1766080512 -1.0274960995 0.4292861819 -0.4276981354 854 34.1199999990 0.4326136410 0.0981826331 0.4326136410 0.0092727634 0.0880090000 10681495 955859216 1766080512 -1.0244833231 0.4293088615 -0.4357752204 855 34.1600000000 0.4345378578 0.0985760310 0.4345378578 0.0092679271 0.1064100000 10682749 955859216 1764827136 -1.0203108788 0.4283201396 -0.4442529976 856 34.2000000000 0.4355134070 0.0989696495 0.4355134070 0.0092646857 0.0871120000 10684003 955859216 1764843520 -1.0135657787 0.4287542403 -0.4518688917 857 34.2400000000 0.4354741275 0.0993623035 0.4355134070 0.0092594358 0.1082840000 10685257 955859216 1764843520 -1.0097458363 0.4269892275 -0.4594564736 858 34.2800000000 0.4363731742 0.0997550900 0.4363731742 0.0092546065 0.0898650000 10686511 955859216 1764843520 -1.0049207211 0.4253260195 -0.4657332301 859 34.3200000000 0.4362994730 0.1001468763 0.4363731742 0.0092526902 0.0834080000 10687765 955859216 1765101568 -1.0007724762 0.4272780120 -0.4748614430 860 34.3600000000 0.4374155104 0.1005390491 0.4374155104 0.0092482493 0.0882170000 10689019 955859216 1765101568 -0.9968703389 0.4283071458 -0.4839408100 861 34.4000000000 0.4391984344 0.1009323817 0.4391984344 0.0092438160 0.1090340000 10690273 955859216 1765101568 -0.9919075966 0.4270277321 -0.4914358556 862 34.4400000000 0.4402370155 0.1013260066 0.4402370155 0.0092390622 0.0887210000 10691527 955859216 1765101568 -0.9874113202 0.4265087843 -0.4988277256 863 34.4800000000 0.4403693080 0.1017188725 0.4403693080 0.0092340729 0.0852260000 10692781 955859216 1765101568 -0.9818203449 0.4277486503 -0.5060335398 864 34.5200000000 0.4410776198 0.1021116489 0.4410776198 0.0092296654 0.0890910000 10694035 955859216 1765101568 -0.9779300094 0.4305846989 -0.5148707628 865 34.5600000000 0.4440200925 0.1025069187 0.4440200925 0.0092290431 0.0884280000 10695289 955859216 1765101568 -0.9730008841 0.4276749492 -0.5215995908 866 34.6000000000 0.4462646246 0.1029038676 0.4462646246 0.0092259587 0.0866170000 10696543 955859216 1765101568 -0.9699176550 0.4186701179 -0.5252768993 867 34.6400000000 0.4453079998 0.1032987974 0.4462646246 0.0092327717 0.0860650000 10697797 955859216 1765101568 -0.9651494622 0.4147472978 -0.5411924124 868 34.6800000000 0.4459010065 0.1036935004 0.4462646246 0.0092303726 0.0696080000 10699051 955859216 1766576128 -0.9592622519 0.4132717848 -0.5479921103 869 34.7200000000 0.4458994865 0.1040872932 0.4462646246 0.0092286286 0.0896390000 10700305 955859216 1766322176 -0.9570330381 0.4133569002 -0.5558295846 870 34.7600000000 0.4475805163 0.1044821130 0.4475805163 0.0092271321 0.0866070000 10701559 955859216 1765486592 -0.9526153803 0.4136065245 -0.5649874210 871 34.8000000000 0.4495182931 0.1048782510 0.4495182931 0.0092237084 0.1056710000 10702813 955859216 1765113856 -0.9466874599 0.4119275212 -0.5707683563 872 34.8400000000 0.4495507777 0.1052735177 0.4495507777 0.0092232649 0.1092980000 10704067 955859216 1766465536 -0.9445355535 0.4101725817 -0.5774660707 873 34.8800000000 0.4489469826 0.1056671872 0.4495507777 0.0092238290 0.1276780000 10705321 955859216 1768480768 -0.9369465709 0.4140178859 -0.5854946971 874 34.9200000000 0.4501284659 0.1060613076 0.4501284659 0.0092213664 0.1294440000 10706575 955859216 1770131456 -0.9355913997 0.4159090221 -0.5938532352 875 34.9600000000 0.4503571987 0.1064547886 0.4503571987 0.0092180663 0.1282790000 10707829 955859216 1771909120 -0.9308792353 0.4198956788 -0.6014821529 876 35.0000000000 0.4524207711 0.1068497270 0.4524207711 0.0092139930 0.1250830000 10709083 955859216 1773559808 -0.9263643622 0.4205526710 -0.6089543104 877 35.0400000000 0.4555961490 0.1072473854 0.4555961490 0.0092099607 0.1295500000 10710337 955859216 1775210496 -0.9181118608 0.4198484421 -0.6139094830 878 35.0800000000 0.4558244944 0.1076443980 0.4558244944 0.0092054082 0.1269540000 10711591 955859216 1776988160 -0.9140798450 0.4165938497 -0.6194812059 879 35.1200000000 0.4538462162 0.1080382568 0.4558244944 0.0092040968 0.1277080000 10712845 955859216 1778638848 -0.9105334878 0.4185679555 -0.6284375191 880 35.1600000000 0.4560161829 0.1084336862 0.4560161829 0.0092000119 0.1274930000 10714099 955859216 1780289536 -0.9030143619 0.4182938933 -0.6357135177 881 35.2000000000 0.4568410218 0.1088291542 0.4568410218 0.0091952143 0.1278190000 10715353 955859216 1782067200 -0.8979716301 0.4164501131 -0.6404294968 882 35.2400000000 0.4565066099 0.1092233464 0.4568410218 0.0091905989 0.0855930000 10716607 955859216 1783717888 -0.8910340667 0.4161064923 -0.6481078267 883 35.2800000000 0.4569084644 0.1096171008 0.4569084644 0.0091860692 0.0868980000 10717861 955859216 1785511936 -0.8885911703 0.4160239100 -0.6568959355 884 35.3200000000 0.4579988420 0.1100111977 0.4579988420 0.0091818735 0.0891330000 10719115 955859216 1787146240 -0.8809234500 0.4168982506 -0.6634480953 885 35.3600000000 0.4617538452 0.1104086471 0.4617538452 0.0091791295 0.0866810000 10720369 955859216 1786257408 -0.8740229011 0.4128937423 -0.6693211794 886 35.4000000000 0.4640676081 0.1108078107 0.4640676081 0.0091755129 0.1091660000 10721623 955859216 1784291328 -0.8727608323 0.4073569477 -0.6760666966 887 35.4400000000 0.4628166854 0.1112046640 0.4640676081 0.0091710718 0.0888880000 10722877 955859216 1783242752 -0.8697001338 0.4053218365 -0.6856670976 888 35.4800000000 0.4640524685 0.1116020151 0.4640676081 0.0091666653 0.0852190000 10724131 955859216 1782226944 -0.8651150465 0.4020774961 -0.6933328509 889 35.5200000000 0.4644083381 0.1119988726 0.4644083381 0.0091637015 0.0874350000 10725385 955859216 1781358592 -0.8609158993 0.3993613422 -0.7006179094 890 35.5600000000 0.4636253715 0.1123939586 0.4644083381 0.0091647367 0.0685800000 10726639 955859216 1782718464 -0.8561853170 0.3993189335 -0.7089757323 891 35.6000000000 0.4634577632 0.1127879696 0.4644083381 0.0091650515 0.0854810000 10727893 955859216 1782099968 -0.8501761556 0.4005797803 -0.7200876474 892 35.6400000000 0.4648153782 0.1131826191 0.4648153782 0.0091623508 0.0872400000 10729147 955859216 1781084160 -0.8461719751 0.4019559324 -0.7291004062 893 35.6800000000 0.4677466452 0.1135796673 0.4677466452 0.0091602340 0.0709150000 10730401 955859216 1780215808 -0.8398987055 0.4020244479 -0.7365171909 894 35.7200000000 0.4682632983 0.1139764052 0.4682632983 0.0091583328 0.0846320000 10731655 955859216 1779326976 -0.8319702744 0.4039497674 -0.7429369092 895 35.7600000000 0.4686725140 0.1143727137 0.4686725140 0.0091561187 0.1109620000 10732909 955859216 1778384896 -0.8263136148 0.4052572846 -0.7527894974 896 35.8000000000 0.4685610533 0.1147680131 0.4686725140 0.0091525678 0.0833080000 10734163 955859216 1777532928 -0.8210214376 0.4068967104 -0.7606654763 897 35.8400000000 0.4677190483 0.1151614926 0.4686725140 0.0091497970 0.0891520000 10735417 955859216 1776660480 -0.8132246733 0.4130839705 -0.7705228925 898 35.8800000000 0.4707575440 0.1155574793 0.4707575440 0.0091521327 0.0707790000 10736671 955859216 1775771648 -0.8060213327 0.4167967737 -0.7779335976 899 35.9200000000 0.4734492004 0.1159555791 0.4734492004 0.0091544824 0.0900780000 10737925 955859216 1774882816 -0.7994070649 0.4172308147 -0.7861248851 900 35.9600000000 0.4770428836 0.1163567872 0.4770428836 0.0091567286 0.0876380000 10739179 955859216 1773993984 -0.7913650870 0.4130522013 -0.7921680212 901 36.0000000000 0.4779368341 0.1167580969 0.4779368341 0.0091545455 0.0891660000 10740433 955859216 1773105152 -0.7882580161 0.4073869288 -0.7978689671 902 36.0400000000 0.4769893587 0.1171574664 0.4779368341 0.0091522697 0.0843200000 10741687 955859216 1772326912 -0.7812206149 0.4068068564 -0.8090592027 903 36.0800000000 0.4799887538 0.1175592729 0.4799887538 0.0091535616 0.0886240000 10742941 955859216 1771454464 -0.7762857676 0.4059890509 -0.8182190657 904 36.1200000000 0.4801785648 0.1179604004 0.4801785648 0.0091506138 0.0828350000 10744195 955859216 1770565632 -0.7637800574 0.4050766230 -0.8156047463 905 36.1600000000 0.4829474986 0.1183637011 0.4829474986 0.0091724914 0.1089240000 10745449 955859216 1769660416 -0.7400350571 0.4068724513 -0.8418712020 906 36.2000000000 0.4816710055 0.1187647025 0.4829474986 0.0091683550 0.1060830000 10746703 955859216 1768787968 -0.7319514751 0.4034563005 -0.8487774134 907 36.2400000000 0.4823560119 0.1191655750 0.4829474986 0.0091645517 0.0947250000 10747957 955859216 1768009728 -0.7256988287 0.3989717066 -0.8544338346 908 36.2800000000 0.4859928489 0.1195695697 0.4859928489 0.0091705073 0.1008820000 10749211 955859216 1767137280 -0.7228047252 0.4032215178 -0.8627381325 909 36.3200000000 0.4839765131 0.1199704575 0.4859928489 0.0091667597 0.0673080000 10750465 955859216 1768497152 -0.7124785781 0.4046134353 -0.8656291962 910 36.3600000000 0.4849613011 0.1203715463 0.4859928489 0.0091645879 0.0847780000 10751719 955859216 1767907328 -0.7037738562 0.4046591520 -0.8673816323 911 36.4000000000 0.4860596359 0.1207729602 0.4860596359 0.0091615660 0.0880630000 10752973 955859216 1767133184 -0.6981847286 0.4034149945 -0.8695665002 912 36.4400000000 0.4857786596 0.1211731858 0.4860596359 0.0091580311 0.0692780000 10754227 955859216 1766248448 -0.6903950572 0.4036030471 -0.8750735521 913 36.4800000000 0.4866161644 0.1215734519 0.4866161644 0.0091550111 0.0832140000 10755481 955859216 1765359616 -0.6831179261 0.4033535123 -0.8800683022 914 36.5200000000 0.4874514937 0.1219737561 0.4874514937 0.0091513785 0.1105740000 10756735 955859216 1765097472 -0.6775125861 0.4010470510 -0.8845694661 915 36.5600000000 0.4872142971 0.1223729261 0.4874514937 0.0091476712 0.1082980000 10757989 955859216 1765052416 -0.6692921519 0.4007610381 -0.8873913884 916 36.6000000000 0.4861023724 0.1227700107 0.4874514937 0.0091440839 0.1078610000 10759243 955859216 1765068800 -0.6601541638 0.4017393589 -0.8914917111 917 36.6400000000 0.4880675077 0.1231683722 0.4880675077 0.0091400432 0.1077130000 10760497 955859216 1765085184 -0.6536318660 0.3990919292 -0.8955057263 918 36.6800000000 0.4886471331 0.1235664972 0.4886471331 0.0091369204 0.1103630000 10761751 955859216 1765117952 -0.6476764083 0.3950961232 -0.9003441334 919 36.7200000000 0.4869136810 0.1239618695 0.4886471331 0.0091327707 0.0848460000 10763005 955859216 1765117952 -0.6400820017 0.3954260349 -0.9033101797 920 36.7600000000 0.4864486456 0.1243558769 0.4886471331 0.0091282909 0.0699120000 10764259 955859216 1765117952 -0.6335141063 0.3961784840 -0.9084791541 921 36.8000000000 0.4920583069 0.1247551195 0.4920583069 0.0091274162 0.0942400000 10765513 955859216 1765101568 -0.6238675117 0.4044277370 -0.9129534364 922 36.8400000000 0.4933168590 0.1251548611 0.4933168590 0.0091280490 0.1044620000 10766767 955859216 1765101568 -0.6145166755 0.4010161459 -0.9161835909 923 36.8800000000 0.4927474260 0.1255531195 0.4933168590 0.0091232686 0.0992950000 10768021 955859216 1765101568 -0.6069854498 0.3981793225 -0.9177882671 924 36.9200000000 0.4931813478 0.1259509856 0.4933168590 0.0091207298 0.0963020000 10769275 955859216 1765101568 -0.5954528451 0.4021410644 -0.9240664244 925 36.9600000000 0.4931900203 0.1263480008 0.4933168590 0.0091203425 0.0787090000 10770529 955859216 1765101568 -0.5846505165 0.4018886983 -0.9290607572 926 37.0000000000 0.4936721027 0.1267446790 0.4936721027 0.0091217917 0.0880230000 10771783 955859216 1765101568 -0.5682304502 0.4037184119 -0.9361782670 927 37.0400000000 0.4936099350 0.1271404344 0.4936721027 0.0091209430 0.1055710000 10773037 955859216 1765101568 -0.5564209819 0.4044782519 -0.9400380850 928 37.0800000000 0.4946046472 0.1275364088 0.4946046472 0.0091171829 0.0904000000 10774291 955859216 1765101568 -0.5482590795 0.4010259509 -0.9432570338 929 37.1200000000 0.4947384000 0.1279316747 0.4947384000 0.0091129094 0.0860810000 10775545 955859216 1765101568 -0.5389373302 0.3981018364 -0.9469237328 930 37.1600000000 0.4945082963 0.1283258431 0.4947384000 0.0091088407 0.0879560000 10776799 955859216 1765101568 -0.5285750031 0.3975896537 -0.9502568245 931 37.2000000000 0.4951872528 0.1287198940 0.4951872528 0.0091045469 0.1083010000 10778053 955859216 1765101568 -0.5206451416 0.3956729770 -0.9544596672 932 37.2400000000 0.4949776232 0.1291128744 0.4951872528 0.0091014786 0.0890860000 10779307 955859216 1765101568 -0.5105359554 0.3970484436 -0.9560468793 933 37.2800000000 0.4953248799 0.1295053846 0.4953248799 0.0090985488 0.0657560000 10780561 955859216 1766703104 -0.4993160665 0.3989845216 -0.9599783421 934 37.3200000000 0.4960319102 0.1298978113 0.4960319102 0.0090962425 0.0664330000 10781815 955859216 1766195200 -0.4883540571 0.4008163214 -0.9639681578 935 37.3600000000 0.4964188039 0.1302898124 0.4964188039 0.0090952252 0.0891750000 10783069 955859216 1765613568 -0.4773993194 0.4015610814 -0.9661055207 936 37.4000000000 0.4971087277 0.1306817129 0.4971087277 0.0090923699 0.1054080000 10784323 955859216 1765093376 -0.4672133029 0.4002753794 -0.9667404294 937 37.4400000000 0.4976308644 0.1310733342 0.4976308644 0.0090889498 0.1077270000 10785577 955859216 1765085184 -0.4558180273 0.3989957869 -0.9679397345 938 37.4800000000 0.4975403845 0.1314640240 0.4976308644 0.0090845115 0.0933270000 10786831 955859216 1765101568 -0.4468854964 0.3959557414 -0.9702225327 939 37.5200000000 0.4948956072 0.1318510651 0.4976308644 0.0090802709 0.0806730000 10788085 955859216 1765101568 -0.4351281822 0.3963380158 -0.9730418921 940 37.5600000000 0.4939814508 0.1322363102 0.4976308644 0.0090767200 0.0703830000 10789339 955859216 1766584320 -0.4242968559 0.3975188732 -0.9736311436 941 37.6000000000 0.4948177636 0.1326216252 0.4976308644 0.0090723969 0.0850270000 10790593 955859216 1766129664 -0.4151174724 0.3960007131 -0.9755359888 942 37.6400000000 0.4960602224 0.1330074412 0.4976308644 0.0090683672 0.0896090000 10791847 955859216 1765240832 -0.4060963988 0.3940979242 -0.9781882167 943 37.6800000000 0.4967034757 0.1333931209 0.4976308644 0.0090654612 0.0856460000 10793101 955859216 1765126144 -0.3954750299 0.3941041529 -0.9796755314 944 37.7200000000 0.4969019294 0.1337781938 0.4976308644 0.0090613607 0.0704740000 10794355 955859216 1765093376 -0.3875080943 0.3928694725 -0.9795116782 945 37.7600000000 0.4975885749 0.1341631784 0.4976308644 0.0090577074 0.0841260000 10795609 955859216 1765109760 -0.3766664863 0.3919588923 -0.9794791937 946 37.8000000000 0.4976871014 0.1345474531 0.4976871014 0.0090540802 0.0899500000 10796863 955859216 1765109760 -0.3664906323 0.3902598321 -0.9803241491 947 37.8400000000 0.4977082014 0.1349309386 0.4977082014 0.0090545579 0.0868070000 10798117 955859216 1765109760 -0.3560772240 0.3882600665 -0.9827716947 948 37.8800000000 0.4979834259 0.1353139054 0.4979834259 0.0090533386 0.0694060000 10799371 955859216 1765126144 -0.3462446034 0.3861650825 -0.9843981266 949 37.9200000000 0.4969573021 0.1356949838 0.4979834259 0.0090522373 0.0699650000 10800625 955859216 1765126144 -0.3357859850 0.3850780427 -0.9869905710 950 37.9600000000 0.4967958331 0.1360750899 0.4979834259 0.0090490370 0.0862630000 10801879 955859216 1765126144 -0.3256867528 0.3846125007 -0.9889960885 951 38.0000000000 0.4975655079 0.1364552060 0.4979834259 0.0090455368 0.0668200000 10803133 955859216 1766584320 -0.3165396750 0.3834249973 -0.9903037548 952 38.0400000000 0.4978695214 0.1368348429 0.4979834259 0.0090433575 0.0683220000 10804387 955859216 1766256640 -0.3064993918 0.3812625706 -0.9927465320 953 38.0800000000 0.4977894127 0.1372135990 0.4979834259 0.0090410133 0.0877150000 10805641 955859216 1765367808 -0.2967107594 0.3806214631 -0.9939121008 954 38.1200000000 0.4977347851 0.1375915038 0.4979834259 0.0090380759 0.0842430000 10806895 955859216 1765105664 -0.2860778570 0.3797039092 -0.9957261682 955 38.1600000000 0.4961261153 0.1379669327 0.4979834259 0.0090360181 0.0873000000 10808149 955859216 1765093376 -0.2760204375 0.3790679574 -0.9970092177 956 38.2000000000 0.4959223568 0.1383413631 0.4979834259 0.0090323988 0.1093440000 10809403 955859216 1765093376 -0.2643992603 0.3783392310 -0.9990795851 957 38.2400000000 0.4956225455 0.1387146977 0.4979834259 0.0090281744 0.0865480000 10810657 955859216 1765109760 -0.2529777586 0.3775780797 -1.0016368628 958 38.2800000000 0.4959799349 0.1390876259 0.4979834259 0.0090240259 0.1111550000 10811911 955859216 1765109760 -0.2437499911 0.3760997355 -1.0041773319 959 38.3200000000 0.4941669106 0.1394578858 0.4979834259 0.0090200965 0.0856940000 10813165 955859216 1765109760 -0.2328694016 0.3769579828 -1.0060311556 960 38.3600000000 0.5024806261 0.1398360345 0.5024806261 0.0090211902 0.0900130000 10814419 955859216 1765126144 -0.2219415605 0.3888450563 -1.0117874146 961 38.4000000000 0.5036870241 0.1402146516 0.5036870241 0.0090281881 0.0895250000 10815673 955859216 1765126144 -0.2123898417 0.3838033378 -1.0119440556 962 38.4400000000 0.5033949018 0.1405921778 0.5036870241 0.0090262776 0.0822950000 10816927 955859216 1765126144 -0.2020241320 0.3810046613 -1.0122531652 963 38.4800000000 0.5032831430 0.1409688039 0.5036870241 0.0090280080 0.0864620000 10818181 955859216 1765126144 -0.1911753714 0.3786563873 -1.0157827139 964 38.5200000000 0.5033605695 0.1413447290 0.5036870241 0.0090274297 0.1295470000 10819435 955859216 1765060608 -0.1811665446 0.3766388595 -1.0166462660 965 38.5600000000 0.5034304857 0.1417199474 0.5036870241 0.0090242692 0.1041160000 10820689 955859216 1765060608 -0.1704560369 0.3742740154 -1.0200773478 966 38.6000000000 0.5009382963 0.1420918091 0.5036870241 0.0090200059 0.1103040000 10821943 955859216 1766457344 -0.1604570150 0.3697442114 -1.0202951431 967 38.6400000000 0.4982052147 0.1424600752 0.5036870241 0.0090169181 0.1277530000 10823197 955859216 1768488960 -0.1496322006 0.3658885360 -1.0205109119 968 38.6800000000 0.4964736700 0.1428257918 0.5036870241 0.0090132899 0.1088700000 10824451 955859216 1770139648 -0.1399637461 0.3622546792 -1.0217715502 969 38.7200000000 0.4953744411 0.1431896191 0.5036870241 0.0090092561 0.0875940000 10825705 955859216 1771917312 -0.1302346885 0.3609513044 -1.0218352079 970 38.7600000000 0.4952765405 0.1435525953 0.5036870241 0.0090052241 0.0901250000 10826959 955859216 1773568000 -0.1238221973 0.3586705923 -1.0230289698 971 38.8000000000 0.4950986505 0.1439146406 0.5036870241 0.0090015178 0.1224380000 10828213 955859216 1775218688 -0.1145521626 0.3584430814 -1.0237817764 972 38.8400000000 0.4963396788 0.1442772178 0.5036870241 0.0090015299 0.0870530000 10829467 955859216 1776996352 -0.1060078740 0.3594562411 -1.0239384174 973 38.8800000000 0.4983913600 0.1446411584 0.5036870241 0.0090085369 0.0687250000 10830721 955859216 1778647040 -0.0972934589 0.3612771928 -1.0234014988 974 38.9200000000 0.5003255606 0.1450063374 0.5036870241 0.0090141978 0.0858760000 10831975 955859216 1780297728 -0.0901027620 0.3610405326 -1.0224567652 975 38.9600000000 0.5006662011 0.1453711168 0.5036870241 0.0090122462 0.1069530000 10833229 955859216 1782075392 -0.0823784098 0.3594986498 -1.0210196972 976 39.0000000000 0.5003971457 0.1457348730 0.5036870241 0.0090079378 0.1283620000 10834483 955859216 1783726080 -0.0764979869 0.3571816087 -1.0190078020 977 39.0400000000 0.4990141690 0.1460964690 0.5036870241 0.0090045682 0.0905000000 10835737 955859216 1785520128 -0.0664834231 0.3555823267 -1.0213563442 978 39.0800000000 0.4979319572 0.1464562190 0.5036870241 0.0090006851 0.0660620000 10836991 955859216 1787154432 -0.0573445782 0.3527976573 -1.0209739208 979 39.1200000000 0.4958341420 0.1468130912 0.5036870241 0.0090008772 0.0859420000 10838245 955859216 1786286080 -0.0491317138 0.3486445248 -1.0204269886 980 39.1600000000 0.4943623245 0.1471677333 0.5036870241 0.0089986719 0.0857770000 10839499 955859216 1784643584 -0.0378995277 0.3469969332 -1.0195435286 981 39.2000000000 0.4923056364 0.1475195558 0.5036870241 0.0089945470 0.0658010000 10840753 955859216 1783869440 -0.0258892532 0.3463203609 -1.0175740719 982 39.2400000000 0.4918316007 0.1478701791 0.5036870241 0.0089908467 0.0864470000 10842007 955859216 1782710272 -0.0205459986 0.3444944620 -1.0160816908 983 39.2800000000 0.4919022024 0.1482201608 0.5036870241 0.0089880433 0.1110430000 10843261 955859216 1781727232 -0.0113283386 0.3433308303 -1.0165024996 984 39.3200000000 0.4910626709 0.1485685780 0.5036870241 0.0089846062 0.1028220000 10844515 955859216 1780568064 0.0000423714 0.3425163925 -1.0177644491 985 39.3600000000 0.4915784001 0.1489168113 0.5036870241 0.0089813579 0.1109570000 10845769 955859216 1781964800 0.0079139695 0.3406467438 -1.0190423727 986 39.4000000000 0.4912129641 0.1492639676 0.5036870241 0.0089777379 0.0661300000 10847023 955859216 1783726080 0.0161445681 0.3391202390 -1.0182247162 987 39.4400000000 0.4909015298 0.1496101050 0.5036870241 0.0089745475 0.0681290000 10848277 955859216 1785503744 0.0257077515 0.3376687467 -1.0173406601 988 39.4800000000 0.4906451702 0.1499552822 0.5036870241 0.0089707734 0.0670500000 10849531 955859216 1787154432 0.0363047160 0.3365989923 -1.0174639225 989 39.5200000000 0.4894534349 0.1502985563 0.5036870241 0.0089667279 0.0879610000 10850785 955859216 1786286080 0.0451814942 0.3346383572 -1.0171931982 990 39.5600000000 0.4883643985 0.1506400370 0.5036870241 0.0089626670 0.0842890000 10852039 955859216 1784647680 0.0548529737 0.3338046670 -1.0172027349 991 39.6000000000 0.4875357449 0.1509799923 0.5036870241 0.0089593391 0.0852110000 10853293 955859216 1783869440 0.0646823198 0.3349114358 -1.0152387619 992 39.6400000000 0.4864283502 0.1513181459 0.5036870241 0.0089566637 0.0844900000 10854547 955859216 1782075392 0.0743430704 0.3361861706 -1.0140603781 993 39.6800000000 0.4859663248 0.1516551531 0.5036870241 0.0089581448 0.0660660000 10855801 955859216 1780334592 0.0835529491 0.3378568888 -1.0115113258 994 39.7200000000 0.4861870110 0.1519917043 0.5036870241 0.0089598211 0.0871440000 10857055 955859216 1780060160 0.0930633917 0.3387786746 -1.0105375051 995 39.7600000000 0.4877212942 0.1523291209 0.5036870241 0.0089611099 0.1060700000 10858309 955859216 1779208192 0.1013373286 0.3389256001 -1.0111653805 996 39.8000000000 0.4890999198 0.1526672442 0.5036870241 0.0089593139 0.0841870000 10859563 955859216 1778319360 0.1107305884 0.3391424716 -1.0120154619 997 39.8400000000 0.4961044490 0.1530117149 0.5036870241 0.0089589773 0.1116080000 10860817 955859216 1777430528 0.1211450174 0.3458651900 -1.0173230171 998 39.8800000000 0.4957191348 0.1533551091 0.5036870241 0.0089564356 0.0849350000 10862071 955859216 1778790400 0.1302588284 0.3444554806 -1.0167220831 999 39.9200000000 0.4949137270 0.1536970096 0.5036870241 0.0089532484 0.0884580000 10863325 955859216 1780551680 0.1429423988 0.3478792608 -1.0142937899 1000 39.9600000000 0.4938285351 0.1540371411 0.5036870241 0.0089528986 0.0865130000 10864579 955859216 1782202368 0.1518490911 0.3460745215 -1.0148711205 1001 40.0000000000 0.4925139546 0.1543752798 0.5036870241 0.0089492062 0.0888290000 10865833 955859216 1783980032 0.1612935811 0.3435348570 -1.0142077208 1002 40.0400000000 0.4908153117 0.1547110483 0.5036870241 0.0089453835 0.0864030000 10867087 955859216 1785630720 0.1720798314 0.3430131972 -1.0116028786 1003 40.0800000000 0.4893005192 0.1550446370 0.5036870241 0.0089425053 0.0877850000 10868341 955859216 1787408384 0.1835534722 0.3438692093 -1.0095603466 1004 40.1200000000 0.4903258979 0.1553785825 0.5036870241 0.0089431024 0.0869980000 10869595 955859216 1786523648 0.1921132654 0.3438787162 -1.0079472065 1005 40.1600000000 0.4895034730 0.1557110450 0.5036870241 0.0089398688 0.0842020000 10870849 955859216 1784774656 0.2016723901 0.3432833552 -1.0064783096 1006 40.2000000000 0.4880410433 0.1560413929 0.5036870241 0.0089368144 0.0858660000 10872103 955859216 1783869440 0.2119815201 0.3441056609 -1.0036327839 1007 40.2400000000 0.4871982634 0.1563702478 0.5036870241 0.0089348381 0.1074180000 10873357 955859216 1782104064 0.2218020260 0.3446104527 -1.0003496408 1008 40.2800000000 0.4874437749 0.1566986938 0.5036870241 0.0089330531 0.1067920000 10874611 955859216 1783615488 0.2298628837 0.3443884850 -0.9971590638 1009 40.3200000000 0.4866269231 0.1570256792 0.5036870241 0.0089300501 0.1085170000 10875865 955859216 1785376768 0.2386233509 0.3441012502 -0.9936153889 1010 40.3600000000 0.4856670797 0.1573510667 0.5036870241 0.0089276775 0.0890880000 10877119 955859216 1787027456 0.2487477809 0.3438000381 -0.9903014898 1011 40.4000000000 0.4852547646 0.1576754027 0.5036870241 0.0089254579 0.0813140000 10878373 955859216 1786286080 0.2568675280 0.3426641226 -0.9880797863 1012 40.4400000000 0.4842322171 0.1579980873 0.5036870241 0.0089211990 0.0851190000 10879627 955859216 1785503744 0.2651748955 0.3401528597 -0.9869443774 1013 40.4800000000 0.4823331535 0.1583182601 0.5036870241 0.0089172740 0.0703530000 10880881 955859216 1784541184 0.2745442390 0.3390203118 -0.9831235409 1014 40.5200000000 0.4803809226 0.1586358761 0.5036870241 0.0089130297 0.1049620000 10882135 955859216 1783644160 0.2821365297 0.3370420337 -0.9796504974 1015 40.5600000000 0.4789563715 0.1589514628 0.5036870241 0.0089093071 0.1095620000 10883389 955859216 1782607872 0.2904824018 0.3342129886 -0.9785791039 1016 40.6000000000 0.4783583879 0.1592658397 0.5036870241 0.0089052235 0.1088950000 10884643 955859216 1783988224 0.2981334925 0.3314217031 -0.9774475098 1017 40.6400000000 0.4771795571 0.1595784393 0.5036870241 0.0089021695 0.0889570000 10885897 955859216 1785876480 0.3053314090 0.3307943344 -0.9742583632 1018 40.6800000000 0.4776390791 0.1598908760 0.5036870241 0.0088981733 0.1019990000 10887151 955859216 1787527168 0.3138319850 0.3310953677 -0.9718600512 1019 40.7200000000 0.4777850211 0.1602028428 0.5036870241 0.0088940741 0.0853410000 10888405 955859216 1786789888 0.3207672238 0.3316508532 -0.9679579139 1020 40.7600000000 0.4778129756 0.1605142253 0.5036870241 0.0088901501 0.1099580000 10889659 955859216 1784262656 0.3295210004 0.3317221105 -0.9645099044 1021 40.8000000000 0.4774082601 0.1608246014 0.5036870241 0.0088862760 0.1007120000 10890913 955859216 1783373824 0.3376660645 0.3317872584 -0.9607903957 1022 40.8400000000 0.4763983488 0.1611333820 0.5036870241 0.0088820020 0.0980610000 10892167 955859216 1782353920 0.3451407850 0.3316470385 -0.9549801946 1023 40.8800000000 0.4754187763 0.1614406013 0.5036870241 0.0088777845 0.0974140000 10893421 955859216 1781485568 0.3525210321 0.3309674859 -0.9497185349 1024 40.9200000000 0.4743633568 0.1617461900 0.5036870241 0.0088740966 0.1077000000 10894675 955859216 1780596736 0.3618500829 0.3307127953 -0.9454435706 1025 40.9600000000 0.4745008945 0.1620513165 0.5036870241 0.0088709271 0.1097610000 10981169 955859216 1779707904 0.3715146482 0.3314799964 -0.9404642582 1026 41.0000000000 0.4749056995 0.1623562428 0.5036870241 0.0088684347 0.0818160000 11147039 955859216 1778819072 0.3777671456 0.3316601217 -0.9352484345 1027 41.0400000000 0.4744871557 0.1626601678 0.5036870241 0.0088643730 0.0848250000 11148293 955859216 1780178944 0.3861632347 0.3298899233 -0.9329056740 1028 41.0800000000 0.4727497101 0.1629618113 0.5036870241 0.0088607640 0.1127890000 11149547 955859216 1777291264 0.3972204030 0.3299799562 -0.9266961217 1029 41.1200000000 0.4713463783 0.1632615047 0.5036870241 0.0088579854 0.0872000000 11150801 955859216 1776406528 0.4058827460 0.3285381496 -0.9230105877 1030 41.1600000000 0.4713076055 0.1635605786 0.5036870241 0.0088562235 0.0897130000 11152055 955859216 1775501312 0.4140980840 0.3281154037 -0.9194399714 1031 41.2000000000 0.4725672305 0.1638602941 0.5036870241 0.0088559738 0.0844060000 11153309 955859216 1774628864 0.4231879413 0.3285591602 -0.9160544276 1032 41.2400000000 0.4733643830 0.1641602012 0.5036870241 0.0088554500 0.0895890000 11154563 955859216 1773740032 0.4319662750 0.3291804790 -0.9129733443 1033 41.2800000000 0.4737218916 0.1644598737 0.5036870241 0.0088548425 0.1027180000 11155817 955859216 1772851200 0.4420683086 0.3306232989 -0.9087308645 1034 41.3200000000 0.4744910598 0.1647597104 0.5036870241 0.0088561353 0.0858040000 11157071 955859216 1771962368 0.4523497224 0.3318764865 -0.9031916857 1035 41.3600000000 0.4748350978 0.1650593001 0.5036870241 0.0088612073 0.0870230000 11158325 955859216 1771073536 0.4586258829 0.3320633173 -0.9012000561 1036 41.4000000000 0.4752917290 0.1653587523 0.5036870241 0.0088589098 0.1093130000 11159579 955859216 1770184704 0.4652664959 0.3301039636 -0.8985903859 1037 41.4400000000 0.4736106098 0.1656560058 0.5036870241 0.0088551995 0.1094870000 11160833 955859216 1769406464 0.4747501016 0.3275801539 -0.8944061995 1038 41.4800000000 0.4709635675 0.1659501364 0.5036870241 0.0088514284 0.0957280000 11162087 955859216 1768534016 0.4840135872 0.3268225491 -0.8883676529 1039 41.5200000000 0.4688528776 0.1662416693 0.5036870241 0.0088473771 0.0966290000 11163341 955859216 1767628800 0.4931046367 0.3264603913 -0.8827158213 1040 41.5600000000 0.4663164914 0.1665302028 0.5036870241 0.0088436960 0.1045720000 11164595 955859216 1766756352 0.5003085732 0.3267642856 -0.8764998913 1041 41.6000000000 0.4651227295 0.1668170352 0.5036870241 0.0088402987 0.0867890000 11165849 955859216 1765867520 0.5073895454 0.3256270289 -0.8727865815 1042 41.6400000000 0.4644394219 0.1671026613 0.5036870241 0.0088392695 0.1108120000 11167103 955859216 1765089280 0.5176777244 0.3268853426 -0.8667566776 1043 41.6800000000 0.4643368721 0.1673876414 0.5036870241 0.0088459166 0.0849900000 11168357 955859216 1765101568 0.5239670277 0.3281154633 -0.8618848324 1044 41.7200000000 0.4669618607 0.1676745898 0.5036870241 0.0088798206 0.1071180000 11169611 955859216 1765101568 0.5380573273 0.3312447667 -0.8563699126 1045 41.7600000000 0.4675585330 0.1679615601 0.5036870241 0.0088870168 0.1075370000 11170865 955859216 1765101568 0.5456927419 0.3320162892 -0.8540754914 1046 41.8000000000 0.4660037458 0.1682464953 0.5036870241 0.0088890910 0.0876440000 11172119 955859216 1765101568 0.5510777235 0.3315737545 -0.8482746482 1047 41.8400000000 0.4636627734 0.1685286503 0.5036870241 0.0088861471 0.1079610000 11173373 955859216 1765101568 0.5573005676 0.3292347193 -0.8432130218 1048 41.8800000000 0.4616776407 0.1688083726 0.5036870241 0.0088831971 0.1018880000 11174627 955859216 1765101568 0.5651475787 0.3280428648 -0.8357227445 1049 41.9200000000 0.4594881535 0.1690854744 0.5036870241 0.0088816186 0.0881150000 11175881 955859216 1765101568 0.5717206597 0.3263384700 -0.8286687732 1050 41.9600000000 0.4564585984 0.1693591631 0.5036870241 0.0088781821 0.1076890000 11177135 955859216 1765101568 0.5767771006 0.3239146173 -0.8224929571 1051 42.0000000000 0.4551779926 0.1696311125 0.5036870241 0.0088746329 0.1109730000 11178389 955859216 1765117952 0.5840480924 0.3217890859 -0.8169296384 1052 42.0400000000 0.4528919458 0.1699003718 0.5036870241 0.0088714208 0.0866860000 11179643 955859216 1766481920 0.5905324221 0.3209680021 -0.8096817732 1053 42.0800000000 0.4499830902 0.1701663573 0.5036870241 0.0088676779 0.0668170000 11180897 955859216 1768353792 0.5956740379 0.3197521865 -0.8028833270 1054 42.1200000000 0.4486212134 0.1704305460 0.5036870241 0.0088641733 0.0867040000 11182151 955859216 1770004480 0.6014105082 0.3186814189 -0.7965090275 1055 42.1600000000 0.4453305304 0.1706911147 0.5036870241 0.0088605242 0.1076010000 11183405 955859216 1771782144 0.6115652919 0.3156556785 -0.7850649357 1056 42.2000000000 0.4437854290 0.1709497268 0.5036870241 0.0088565018 0.1111730000 11184659 955859216 1773432832 0.6173967123 0.3143002689 -0.7773738503 1057 42.2400000000 0.4421446919 0.1712062972 0.5036870241 0.0088523732 0.0851960000 11185913 955859216 1775083520 0.6228051782 0.3133231699 -0.7696057558 1058 42.2800000000 0.4404797852 0.1714608090 0.5036870241 0.0088493321 0.1084750000 11187167 955859216 1776861184 0.6283173561 0.3129864037 -0.7605917454 1059 42.3200000000 0.4380867481 0.1717125804 0.5036870241 0.0088468839 0.1117410000 11188421 955859216 1778511872 0.6313936114 0.3128948808 -0.7536276579 1060 42.3600000000 0.4371044934 0.1719629502 0.5036870241 0.0088444981 0.0811950000 11189675 955859216 1780162560 0.6354609132 0.3129039407 -0.7467514277 1061 42.4000000000 0.4355723560 0.1722114039 0.5036870241 0.0088411609 0.0714600000 11190929 955859216 1781940224 0.6397044063 0.3124737740 -0.7403239608 1062 42.4400000000 0.4343150556 0.1724582058 0.5036870241 0.0088385753 0.0859850000 11192183 955859216 1783590912 0.6440408230 0.3125233650 -0.7330825329 1063 42.4800000000 0.4336654246 0.1727039323 0.5036870241 0.0088380986 0.0897960000 11193437 955859216 1785241600 0.6489247084 0.3128105998 -0.7260065675 1064 42.5200000000 0.4332539439 0.1729488101 0.5036870241 0.0088380916 0.0860070000 11194691 955859216 1787019264 0.6532552838 0.3128815591 -0.7196955085 1065 42.5600000000 0.4319988787 0.1731920496 0.5036870241 0.0088361128 0.0860300000 11195945 955859216 1786150912 0.6568114161 0.3125815690 -0.7139973640 1066 42.6000000000 0.4301918447 0.1734331376 0.5036870241 0.0088332251 0.0828310000 11197199 955859216 1784381440 0.6606445909 0.3123706281 -0.7071951032 1067 42.6400000000 0.4291508794 0.1736727981 0.5036870241 0.0088313940 0.1062360000 11198453 955859216 1782575104 0.6644898057 0.3122731447 -0.7011241913 1068 42.6800000000 0.4271399081 0.1739101268 0.5036870241 0.0088283778 0.0880900000 11199707 955859216 1784225792 0.6667028666 0.3120273054 -0.6948086023 1069 42.7200000000 0.4252299666 0.1741452249 0.5036870241 0.0088280433 0.1074790000 11200961 955859216 1786003456 0.6726582646 0.3129714727 -0.6870982647 1070 42.7600000000 0.4306365252 0.1743849364 0.5036870241 0.0088313167 0.1293500000 11202215 955859216 1787654144 0.6815697551 0.3235465884 -0.6828901768 1071 42.8000000000 0.4266842604 0.1746205100 0.5036870241 0.0088380100 0.0849830000 11203469 955859216 1786916864 0.6858631968 0.3218575120 -0.6741763949 1072 42.8400000000 0.4265787601 0.1748555457 0.5036870241 0.0088339403 0.1073250000 11204723 955859216 1784385536 0.6910103559 0.3245106041 -0.6676604152 1073 42.8800000000 0.4262931645 0.1750898771 0.5036870241 0.0088316886 0.1122940000 11205977 955859216 1783517184 0.6940505505 0.3254218102 -0.6605387330 1074 42.9200000000 0.4251833260 0.1753227388 0.5036870241 0.0088290122 0.0978030000 11207231 955859216 1782480896 0.6998346448 0.3268908262 -0.6536239386 1075 42.9600000000 0.4237863421 0.1755538677 0.5036870241 0.0088260728 0.0908130000 11208485 955859216 1781612544 0.7040513158 0.3282231390 -0.6453832984 1076 43.0000000000 0.4202504456 0.1757812809 0.5036870241 0.0088259483 0.0817650000 11209739 955859216 1780707328 0.7065995932 0.3276000023 -0.6386964321 1077 43.0400000000 0.4228150249 0.1760106530 0.5036870241 0.0088243971 0.0907790000 11210993 955859216 1779834880 0.7139788270 0.3323976099 -0.6339989305 1078 43.0800000000 0.4204900563 0.1762374428 0.5036870241 0.0088240984 0.1081860000 11212247 955859216 1778946048 0.7158733010 0.3317497969 -0.6279277802 1079 43.1200000000 0.4186286926 0.1764620871 0.5036870241 0.0088219156 0.1085400000 11213501 955859216 1777909760 0.7190622091 0.3317538202 -0.6216137409 1080 43.1600000000 0.4186689854 0.1766863528 0.5036870241 0.0088182037 0.0873020000 11214755 955859216 1777041408 0.7262800336 0.3341378272 -0.6135002375 1081 43.2000000000 0.4166840911 0.1769083673 0.5036870241 0.0088160901 0.1061560000 11216009 955859216 1776152576 0.7292712331 0.3328585327 -0.6055432558 1082 43.2400000000 0.4125988185 0.1771261959 0.5036870241 0.0088124403 0.1270890000 11217263 955859216 1775263744 0.7318646908 0.3311250806 -0.5984405279 1083 43.2800000000 0.4140781164 0.1773449880 0.5036870241 0.0088084641 0.1275390000 11218517 955859216 1774374912 0.7377479672 0.3340301812 -0.5890179873 1084 43.3200000000 0.4133841395 0.1775627363 0.5036870241 0.0088048467 0.0879540000 11219771 955859216 1773432832 0.7434670925 0.3347714245 -0.5794046521 1085 43.3600000000 0.4073790610 0.1777745486 0.5036870241 0.0088014492 0.0860700000 11221025 955859216 1772597248 0.7457730174 0.3318401873 -0.5731452703 1086 43.4000000000 0.4051814377 0.1779839472 0.5036870241 0.0087975345 0.1078880000 11222279 955859216 1771819008 0.7492491007 0.3312639594 -0.5659924746 1087 43.4400000000 0.4033818245 0.1781913050 0.5036870241 0.0087936620 0.1293490000 11223533 955859216 1770946560 0.7531262636 0.3310667276 -0.5577360988 1088 43.4800000000 0.4014930725 0.1783965456 0.5036870241 0.0087897929 0.1290800000 11224787 955859216 1772306432 0.7551863194 0.3300923705 -0.5511643887 1089 43.5200000000 0.4004774392 0.1786004766 0.5036870241 0.0087858435 0.1282920000 11226041 955859216 1774067712 0.7582760453 0.3298203647 -0.5435691476 1090 43.5600000000 0.3985891342 0.1788023010 0.5036870241 0.0087819885 0.0825490000 11227295 955859216 1775845376 0.7624192238 0.3296909332 -0.5342826247 1091 43.6000000000 0.3976687789 0.1790029119 0.5036870241 0.0087802628 0.0705760000 11228549 955859216 1777496064 0.7660671473 0.3301611245 -0.5253230929 1092 43.6400000000 0.3957438767 0.1792013927 0.5036870241 0.0087780953 0.0906470000 11229803 955859216 1779146752 0.7682695985 0.3307515085 -0.5173979402 1093 43.6800000000 0.3946629167 0.1793985212 0.5036870241 0.0087768350 0.1220860000 11231057 955859216 1780924416 0.7717406154 0.3312581480 -0.5082449913 1094 43.7200000000 0.3926142454 0.1795934168 0.5036870241 0.0087749863 0.1291810000 11232311 955859216 1782575104 0.7731238604 0.3317715526 -0.5009939075 1095 43.7600000000 0.3913509250 0.1797868026 0.5036870241 0.0087719183 0.1289190000 11233565 955859216 1784225792 0.7732118368 0.3318091631 -0.4946398437 1096 43.8000000000 0.3894954324 0.1799781426 0.5036870241 0.0087682277 0.1279420000 11234819 955859216 1786003456 0.7753272653 0.3318932950 -0.4870467484 1097 43.8400000000 0.3875009120 0.1801673156 0.5036870241 0.0087648205 0.1277450000 11236073 955859216 1787654144 0.7788639665 0.3321561217 -0.4769939482 1098 43.8800000000 0.3874563277 0.1803561034 0.5036870241 0.0087675934 0.1249210000 11237327 955859216 1784872960 0.7824303508 0.3332407475 -0.4661585391 1099 43.9200000000 0.3860462904 0.1805432646 0.5036870241 0.0087695567 0.0915030000 11238581 955859216 1783877632 0.7835177779 0.3339353800 -0.4587132931 1100 43.9600000000 0.3830446899 0.1807273569 0.5036870241 0.0087669747 0.0953710000 11239835 955859216 1782829056 0.7847759724 0.3334251046 -0.4517413378 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 06:12:36 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 nan 0.0573950000 9378113 955859216 1771376640 -0.0000000000 0.0000000000 -0.0000000000 2 1305031229.5644419193 0.0543001406 0.0574594922 0.0606188439 0.0575126074 0.1514070000 10035927 955859216 1767477248 0.0013291052 0.0021773300 0.0096043535 3 1305031229.5966169834 0.0526696481 0.0558628775 0.0606188439 0.0579676036 0.1072820000 10038017 955859216 1766715392 0.0134074325 -0.0028640786 0.0144224335 4 1305031229.6287899017 0.0486809313 0.0540673910 0.0606188439 0.0479748104 0.0731510000 10040079 955859216 1765842944 0.0181316137 0.0010182944 0.0209811907 5 1305031229.6646571159 0.0491838790 0.0530906886 0.0606188439 0.0428264870 0.0682130000 10042197 955859216 1765068800 0.0175183322 -0.0027363396 0.0255012102 6 1305031229.6968429089 0.0501782075 0.0526052751 0.0606188439 0.0383596115 0.0540890000 10044651 955859216 1765076992 0.0196018014 -0.0042391689 0.0289257541 7 1305031229.7290771008 0.0478465967 0.0519254639 0.0606188439 0.0365923164 0.0534320000 10046385 955859216 1765076992 0.0188563652 -0.0036094973 0.0343016312 8 1305031229.7648689747 0.0481443480 0.0514528244 0.0606188439 0.0339887198 0.0790420000 10048215 955859216 1765076992 0.0209808536 -0.0045182002 0.0390049666 9 1305031229.7969229221 0.0484983064 0.0511245446 0.0606188439 0.0320880572 0.0756430000 10050621 955859216 1765076992 0.0224419665 -0.0050774822 0.0428243838 10 1305031229.8256299496 0.0478111953 0.0507932097 0.0606188439 0.0303571522 0.0514260000 10053635 955859216 1766440960 0.0242758971 -0.0046921624 0.0481726974 11 1305031229.8630619049 0.0489657111 0.0506270734 0.0606188439 0.0293571164 0.0501440000 10055529 955859216 1766096896 0.0272049569 -0.0042869463 0.0526917763 12 1305031229.8969380856 0.0514226444 0.0506933710 0.0606188439 0.0295570976 0.0927640000 10057295 955859216 1765212160 0.0292495005 -0.0042686784 0.0566212460 13 1305031229.9262549877 0.0545396172 0.0509892361 0.0606188439 0.0285076724 0.0875660000 10059029 955859216 1765031936 0.0354210623 -0.0009633061 0.0630948246 14 1305031229.9662408829 0.0574342832 0.0514495966 0.0606188439 0.0275792757 0.0571660000 10060923 955859216 1766428672 0.0361351818 -0.0010730318 0.0666284636 15 1305031229.9979310036 0.0596217103 0.0519944042 0.0606188439 0.0274324376 0.0749630000 10062657 955859216 1768329216 0.0372185633 -0.0007749144 0.0704460889 16 1305031230.0300021172 0.0623163842 0.0526395279 0.0623163842 0.0266501929 0.0484740000 10064423 955859216 1769979904 0.0380258597 -0.0008578690 0.0736914203 17 1305031230.0656960011 0.0661099181 0.0534319038 0.0661099181 0.0260564368 0.0549490000 10067533 955859216 1771757568 0.0387095399 -0.0020693978 0.0765562281 18 1305031230.0982739925 0.0683818832 0.0542624582 0.0683818832 0.0254823052 0.0506030000 10071923 955859216 1773408256 0.0387345180 -0.0019861204 0.0788540617 19 1305031230.1299350262 0.0698066577 0.0550805740 0.0698066577 0.0248008034 0.0691960000 10073689 955859216 1775058944 0.0379532464 -0.0012072688 0.0807038173 20 1305031230.1657800674 0.0730139166 0.0559772411 0.0730139166 0.0243089032 0.0487110000 10075519 955859216 1776836608 0.0373936035 -0.0017170884 0.0830473006 21 1305031230.1977820396 0.0752804354 0.0568964409 0.0752804354 0.0238640293 0.0564550000 10077285 955859216 1778487296 0.0367164388 -0.0025859028 0.0849391744 22 1305031230.2298529148 0.0773513690 0.0578262103 0.0773513690 0.0234082677 0.0538600000 10079051 955859216 1780264960 0.0355338082 -0.0030098548 0.0865833014 23 1305031230.2655899525 0.0797970891 0.0587814659 0.0797970891 0.0230293370 0.1058040000 10080881 955859216 1781915648 0.0341749564 -0.0036792746 0.0885201693 24 1305031230.2979929447 0.0815957412 0.0597320607 0.0815957412 0.0225715280 0.0524990000 10082647 955859216 1783566336 0.0326367505 -0.0035876711 0.0906741694 25 1305031230.3351120949 0.0849031359 0.0607389037 0.0849031359 0.0222194424 0.0554300000 10084509 955859216 1785344000 0.0318389758 -0.0050589503 0.0928333551 26 1305031230.3656799793 0.0852987021 0.0616835114 0.0852987021 0.0218165263 0.0670420000 10086243 955859216 1786994688 0.0296905451 -0.0044747670 0.0946569666 27 1305031230.3973290920 0.0858250037 0.0625776407 0.0858250037 0.0213993468 0.0510890000 10088041 955859216 1786109952 0.0267902855 -0.0054990612 0.0965175331 28 1305031230.4368140697 0.0883344635 0.0634975272 0.0883344635 0.0220980384 0.0632880000 10089903 955859216 1785376768 0.0244052634 -0.0068205013 0.0983555019 29 1305031230.4653120041 0.0901628807 0.0644170222 0.0901628807 0.0219397353 0.0535230000 10091605 955859216 1784381440 0.0206750277 -0.0107772173 0.0995759368 30 1305031230.4972999096 0.0904881358 0.0652860593 0.0904881358 0.0217098531 0.0664890000 10093403 955859216 1785724928 0.0155938249 -0.0135472147 0.0997455418 31 1305031230.5301918983 0.0906844586 0.0661053625 0.0906844586 0.0214267286 0.0701590000 10095137 955859216 1785106432 0.0099288039 -0.0174654853 0.0991366655 32 1305031230.5661149025 0.0899561197 0.0668506987 0.0906844586 0.0225002135 0.0627610000 10096999 955859216 1784381440 0.0030464290 -0.0188447628 0.0959463269 33 1305031230.5988430977 0.0806317702 0.0672683069 0.0906844586 0.0222831072 0.0795740000 10101325 955859216 1783345152 -0.0114573305 -0.0189675521 0.0835702419 34 1305031230.6319139004 0.0792556480 0.0676208758 0.0906844586 0.0220408725 0.1057260000 10108371 955859216 1782476800 -0.0173181184 -0.0187818371 0.0777556598 35 1305031230.6660470963 0.0728006735 0.0677688700 0.0906844586 0.0222360313 0.0740820000 10110169 955859216 1781444608 -0.0278311446 -0.0112354215 0.0643783659 36 1305031230.6979451180 0.0743500516 0.0679516806 0.0906844586 0.0222190251 0.0666770000 10111903 955859216 1780572160 -0.0284093097 -0.0077661704 0.0594918355 37 1305031230.7336409092 0.0798565224 0.0682734331 0.0906844586 0.0237318826 0.0842740000 10113701 955859216 1779535872 -0.0278007258 0.0093977423 0.0400989838 38 1305031230.7659239769 0.0849684477 0.0687127755 0.0906844586 0.0240615951 0.0704700000 10115499 955859216 1778520064 -0.0273072645 0.0128188068 0.0333755314 39 1305031230.7973229885 0.0881450996 0.0692110403 0.0906844586 0.0240413687 0.0751260000 10117265 955859216 1777651712 -0.0292381365 0.0146171851 0.0263342652 40 1305031230.8317570686 0.0903638452 0.0697398604 0.0906844586 0.0239404081 0.0789890000 10119063 955859216 1779011584 -0.0337653309 0.0155913802 0.0178865027 41 1305031230.8655419350 0.0962544754 0.0703865583 0.0962544754 0.0247291827 0.1093800000 10120829 955859216 1775472640 -0.0479216874 0.0210272316 -0.0032277028 42 1305031230.8973939419 0.1005638614 0.0711050655 0.1005638614 0.0245365764 0.0681270000 10122627 955859216 1776836608 -0.0504744984 0.0202751085 -0.0103811426 43 1305031230.9373099804 0.1214776039 0.0722765199 0.1214776039 0.0245965923 0.0790630000 10124489 955859216 1774436352 -0.0612641498 0.0383694246 -0.0394437648 44 1305031230.9650349617 0.1211183965 0.0733865626 0.1214776039 0.0245951987 0.0778300000 10126191 955859216 1773535232 -0.0614128970 0.0401653126 -0.0391382612 45 1305031230.9971239567 0.1215394065 0.0744566258 0.1215394065 0.0243713533 0.0682550000 10127989 955859216 1772281856 -0.0627885684 0.0424899645 -0.0394803248 46 1305031231.0367500782 0.1218760014 0.0754874818 0.1218760014 0.0241639221 0.0732310000 10129851 955859216 1771663360 -0.0652871430 0.0440757908 -0.0400304049 47 1305031231.0644741058 0.1216955483 0.0764706321 0.1218760014 0.0239422939 0.1203040000 10131521 955859216 1770668032 -0.0671696588 0.0439280868 -0.0399765335 48 1305031231.0967879295 0.1201729029 0.0773810961 0.1218760014 0.0237770285 0.0759110000 10133319 955859216 1772032000 -0.0682646483 0.0420785025 -0.0381451659 49 1305031231.1347110271 0.1183439344 0.0782170724 0.1218760014 0.0235442692 0.0720300000 10135149 955859216 1773789184 -0.0692596957 0.0385895222 -0.0358364396 50 1305031231.1652760506 0.1168776229 0.0789902834 0.1218760014 0.0234044772 0.0684860000 10136915 955859216 1775566848 -0.0687396452 0.0361375101 -0.0332910493 51 1305031231.1977710724 0.1158937961 0.0797138817 0.1218760014 0.0235201914 0.0734850000 10138713 955859216 1777217536 -0.0652385950 0.0385838673 -0.0292234868 52 1305031231.2344679832 0.1162847281 0.0804171672 0.1218760014 0.0248500741 0.0922210000 10140543 955859216 1778868224 -0.0610330962 0.0404825881 -0.0256485306 53 1305031231.2656350136 0.1171368510 0.0811099914 0.1218760014 0.0252158155 0.0734850000 10142277 955859216 1780645888 -0.0567207858 0.0435771793 -0.0227568913 54 1305031231.2978610992 0.1127127334 0.0816952274 0.1218760014 0.0271134531 0.0785970000 10144075 955859216 1782296576 -0.0548882931 0.0430392809 -0.0158667248 55 1305031231.3351519108 0.0878736526 0.0818075624 0.1218760014 0.0290423099 0.0975410000 10145905 955859216 1783947264 -0.0539884977 0.0293661207 0.0120816994 56 1305031231.3650770187 0.0828274861 0.0818257753 0.1218760014 0.0295229421 0.0917530000 10147639 955859216 1785724928 -0.0483855717 0.0319928266 0.0215941723 57 1305031231.3973300457 0.0555882528 0.0813654679 0.1218760014 0.0332225030 0.0879330000 10149437 955859216 1787375616 -0.0558926836 -0.0114856074 0.0724963099 58 1305031231.4368579388 0.0723928288 0.0812107672 0.1218760014 0.0338774647 0.0923310000 10151299 955859216 1784999936 -0.0381506421 -0.0267913453 0.1056168303 59 1305031231.4649889469 0.0764537677 0.0811301401 0.1218760014 0.0335906103 0.0906880000 10153001 955859216 1785012224 -0.0295944698 -0.0259457808 0.1110520363 60 1305031231.4992439747 0.0798706487 0.0811091486 0.1218760014 0.0333145196 0.0838300000 10154767 955859216 1784963072 -0.0191557240 -0.0212092567 0.1176575869 61 1305031231.5331959724 0.0856528804 0.0811836360 0.1218760014 0.0330788976 0.0884190000 10156629 955859216 1782554624 -0.0091584157 -0.0180576071 0.1254706234 62 1305031231.5650680065 0.0873636454 0.0812833136 0.1218760014 0.0329340906 0.1143690000 10158363 955859216 1781059584 -0.0044978610 -0.0166243427 0.1288254410 63 1305031231.6013169289 0.0915332362 0.0814460107 0.1218760014 0.0326806020 0.0889470000 10160193 955859216 1780191232 0.0030655414 -0.0128507446 0.1352769881 64 1305031231.6331589222 0.0937981382 0.0816390127 0.1218760014 0.0325411844 0.1066060000 10161991 955859216 1779154944 0.0081176534 -0.0117101567 0.1383079290 65 1305031231.6650550365 0.0958488211 0.0818576252 0.1218760014 0.0323175579 0.0789800000 10168845 955859216 1778139136 0.0130416118 -0.0092317741 0.1406724006 66 1305031231.7035079002 0.0922738463 0.0820154467 0.1218760014 0.0322581155 0.1036770000 10181235 955859216 1777270784 0.0158893932 -0.0027342238 0.1390959918 67 1305031231.7339379787 0.0795324147 0.0819783865 0.1218760014 0.0320544095 0.1157950000 10182937 955859216 1778634752 0.0102575151 0.0037445142 0.1282770932 68 1305031231.7655088902 0.0802862719 0.0819535025 0.1218760014 0.0318548080 0.0783220000 10184703 955859216 1780391936 0.0134499231 0.0041981065 0.1282224357 69 1305031231.8011910915 0.0802837759 0.0819293035 0.1218760014 0.0316833469 0.0675400000 10186533 955859216 1782161408 0.0166883394 0.0054814559 0.1268620044 70 1305031231.8332920074 0.0666846335 0.0817115225 0.1218760014 0.0316056107 0.0820600000 10188299 955859216 1783812096 0.0068166056 0.0072533963 0.1129387021 71 1305031231.8649590015 0.0670287833 0.0815047234 0.1218760014 0.0314583093 0.0609790000 10190065 955859216 1785462784 0.0097906021 0.0067134481 0.1105781794 72 1305031231.9012699127 0.0685649067 0.0813250037 0.1218760014 0.0315160618 0.0623480000 10191895 955859216 1787240448 0.0116340583 0.0037459754 0.1074064225 73 1305031231.9330461025 0.0686107874 0.0811508364 0.1218760014 0.0313782687 0.0713060000 10193661 955859216 1786368000 0.0114689097 0.0004504676 0.1036337465 74 1305031231.9650299549 0.0673950016 0.0809649467 0.1218760014 0.0311740237 0.0974470000 10195427 955859216 1783971840 0.0100637097 -0.0016944332 0.0985261127 75 1305031232.0007200241 0.0657285079 0.0807617942 0.1218760014 0.0310410919 0.0842330000 10197257 955859216 1785368576 0.0067934329 -0.0029586647 0.0930176973 76 1305031232.0332028866 0.0644605756 0.0805473045 0.1218760014 0.0309784648 0.0608430000 10199055 955859216 1787113472 0.0043990347 -0.0045285369 0.0878930464 77 1305031232.0651450157 0.0633719787 0.0803242483 0.1218760014 0.0308300098 0.0705230000 10200789 955859216 1786376192 -0.0084941806 -0.0063655260 0.0751919523 78 1305031232.1007990837 0.0633004308 0.0801059942 0.1218760014 0.0307256374 0.0737340000 10202619 955859216 1785233408 -0.0099927243 -0.0063415538 0.0717174411 79 1305031232.1328380108 0.0644885451 0.0799083050 0.1218760014 0.0305931987 0.0697760000 10204417 955859216 1784209408 -0.0124480687 -0.0072173038 0.0673418045 80 1305031232.1650519371 0.0656553209 0.0797301427 0.1218760014 0.0304240571 0.0481710000 10206151 955859216 1783361536 -0.0155252591 -0.0080208546 0.0627331063 81 1305031232.1992239952 0.0671027750 0.0795742493 0.1218760014 0.0302832525 0.0535900000 10207949 955859216 1782956032 -0.0183081236 -0.0082410434 0.0584141053 82 1305031232.2364680767 0.0688289627 0.0794432092 0.1218760014 0.0301241790 0.0497980000 10209811 955859216 1783447552 -0.0213022958 -0.0090679526 0.0543783158 83 1305031232.2626979351 0.0718827024 0.0793521187 0.1218760014 0.0301176469 0.0592220000 10211481 955859216 1782722560 -0.0240750350 -0.0102523407 0.0500830263 84 1305031232.2980248928 0.0727233440 0.0792732048 0.1218760014 0.0301711858 0.0950100000 10213311 955859216 1781833728 -0.0244965423 -0.0091231186 0.0454551354 85 1305031232.3321430683 0.0749309212 0.0792221191 0.1218760014 0.0300363323 0.0788260000 10215109 955859216 1780801536 -0.0247312877 -0.0089179026 0.0404768437 86 1305031232.3647489548 0.0762183443 0.0791871915 0.1218760014 0.0298994986 0.0827660000 10216843 955859216 1779781632 -0.0258848239 -0.0077824760 0.0362552367 87 1305031232.4008779526 0.0775717124 0.0791686227 0.1218760014 0.0297604801 0.0590020000 10218705 955859216 1778913280 -0.0276794229 -0.0073523493 0.0332719646 88 1305031232.4331440926 0.0778747201 0.0791539193 0.1218760014 0.0295945219 0.0712880000 10220503 955859216 1777881088 -0.0292414762 -0.0060139634 0.0306301955 89 1305031232.4647209644 0.0791188851 0.0791535257 0.1218760014 0.0294294819 0.0639160000 10222205 955859216 1779257344 -0.0314943530 -0.0055850092 0.0282306988 90 1305031232.5015261173 0.0804206282 0.0791676046 0.1218760014 0.0292692935 0.0885390000 10224067 955859216 1778606080 -0.0322733894 -0.0060454872 0.0255123414 91 1305031232.5324640274 0.0829200819 0.0792088406 0.1218760014 0.0291142943 0.0972600000 10225833 955859216 1777606656 -0.0335500799 -0.0073701395 0.0222943444 92 1305031232.5647449493 0.0853460655 0.0792755496 0.1218760014 0.0289826646 0.0670030000 10227599 955859216 1776832512 -0.0355850868 -0.0085218502 0.0188992284 93 1305031232.6003499031 0.0880217329 0.0793695945 0.1218760014 0.0288378704 0.0859550000 10229397 955859216 1775939584 -0.0377804339 -0.0096997516 0.0154321669 94 1305031232.6294269562 0.0910615101 0.0794939766 0.1218760014 0.0287233704 0.0781450000 10231099 955859216 1774542848 -0.0407255739 -0.0108715659 0.0116583453 95 1305031232.6647078991 0.0941911191 0.0796486834 0.1218760014 0.0285767204 0.0647990000 10232961 955859216 1773527040 -0.0458739847 -0.0119686909 0.0079290401 96 1305031232.7005090714 0.0983836353 0.0798438391 0.1218760014 0.0284457443 0.0866100000 10234759 955859216 1772531712 -0.0514975078 -0.0125710117 0.0038715638 97 1305031232.7327980995 0.1014654785 0.0800667426 0.1218760014 0.0283578362 0.0736100000 10236525 955859216 1771659264 -0.0550162382 -0.0127059547 0.0000200484 98 1305031232.7684600353 0.1041903496 0.0803129019 0.1218760014 0.0282876954 0.0946090000 10238355 955859216 1770770432 -0.0590545274 -0.0134505015 -0.0032286565 99 1305031232.8045380116 0.1092075631 0.0806047671 0.1218760014 0.0281762805 0.0722410000 10240185 955859216 1769885696 -0.0660116673 -0.0165118016 -0.0069224499 100 1305031232.8346450329 0.1119972318 0.0809186918 0.1218760014 0.0280813165 0.0580470000 10241919 955859216 1768939520 -0.0699209645 -0.0163469352 -0.0105941119 101 1305031232.8685569763 0.1144424453 0.0812506101 0.1218760014 0.0279870073 0.0818290000 10243749 955859216 1768103936 -0.0736876726 -0.0165134761 -0.0137772616 102 1305031232.9041829109 0.1163092554 0.0815943224 0.1218760014 0.0278842014 0.0688340000 10245547 955859216 1767215104 -0.0777751580 -0.0162230767 -0.0164391063 103 1305031232.9330000877 0.1177583709 0.0819454296 0.1218760014 0.0277931387 0.1074120000 10247249 955859216 1766436864 -0.0800653547 -0.0148734068 -0.0185487606 104 1305031232.9683640003 0.1170545593 0.0822830174 0.1218760014 0.0276583426 0.0697970000 10249111 955859216 1767800832 -0.0802900344 -0.0141457813 -0.0202122945 105 1305031233.0011510849 0.1151721179 0.0825962469 0.1218760014 0.0275809855 0.0629780000 10250877 955859216 1769574400 -0.0791353062 -0.0115847141 -0.0207103789 106 1305031233.0330219269 0.1102861166 0.0828574721 0.1218760014 0.0277485161 0.0875210000 10252643 955859216 1771352064 -0.0803208351 -0.0007024420 -0.0189750344 107 1305031233.0688428879 0.1050402597 0.0830647879 0.1218760014 0.0279074742 0.0893510000 10254409 955859216 1773002752 -0.0768089443 0.0032403998 -0.0171844736 108 1305031233.1004469395 0.0969527066 0.0831933797 0.1218760014 0.0278287706 0.1003610000 10256143 955859216 1774653440 -0.0711660534 0.0135294646 -0.0130562689 109 1305031233.1328918934 0.0912879631 0.0832676420 0.1218760014 0.0282343596 0.0824590000 10257909 955859216 1776431104 -0.0614416711 0.0092615392 -0.0102332952 110 1305031233.1684799194 0.0857940540 0.0832906093 0.1218760014 0.0282696816 0.0708240000 10259739 955859216 1778081792 -0.0475761816 0.0086663002 -0.0077602873 111 1305031233.2006340027 0.0856857374 0.0833121871 0.1218760014 0.0281938359 0.0710160000 10261505 955859216 1779859456 -0.0476704501 0.0067891595 -0.0046825418 112 1305031233.2330091000 0.0845635459 0.0833233599 0.1218760014 0.0281873711 0.0964810000 10263271 955859216 1781510144 -0.0485601835 0.0060991300 -0.0009773282 113 1305031233.2684679031 0.0819469094 0.0833111789 0.1218760014 0.0288330397 0.1096720000 10265101 955859216 1783160832 -0.0505134799 0.0100168372 0.0036983059 114 1305031233.3003950119 0.0742948353 0.0832320882 0.1218760014 0.0290220663 0.0839840000 10266867 955859216 1784938496 -0.0477902815 0.0175865702 0.0108827259 115 1305031233.3325300217 0.0726324841 0.0831399177 0.1218760014 0.0289603474 0.0786840000 10268633 955859216 1786589184 -0.0492554642 0.0048494902 0.0230962299 116 1305031233.3686299324 0.0649798587 0.0829833655 0.1218760014 0.0288927113 0.0661300000 10270399 955859216 1785749504 -0.0270274207 0.0145613588 0.0312585719 117 1305031233.4008929729 0.0656676292 0.0828353678 0.1218760014 0.0288242691 0.0675010000 10272197 955859216 1784864768 -0.0197889842 0.0144082885 0.0387376845 118 1305031233.4330079556 0.0688776448 0.0827170820 0.1218760014 0.0288948100 0.0797270000 10273995 955859216 1783869440 -0.0211492516 0.0064590788 0.0442892946 119 1305031233.4687869549 0.0718512610 0.0826257726 0.1218760014 0.0288864505 0.0593650000 10275761 955859216 1782968320 -0.0229454562 0.0010403428 0.0483375899 120 1305031233.5007359982 0.0735619292 0.0825502405 0.1218760014 0.0288067988 0.0637910000 10277559 955859216 1781952512 -0.0248641670 -0.0021620423 0.0509496890 121 1305031233.5341610909 0.0758506879 0.0824948723 0.1218760014 0.0287987343 0.0517200000 10279357 955859216 1783312384 -0.0260926131 -0.0046887617 0.0530731156 122 1305031233.5697269440 0.0767061561 0.0824474238 0.1218760014 0.0287027014 0.0573570000 10281155 955859216 1782693888 -0.0268442258 -0.0059200977 0.0557853803 123 1305031233.6012749672 0.0783268064 0.0824139229 0.1218760014 0.0286457006 0.0578560000 10282921 955859216 1781678080 -0.0273486190 -0.0079229819 0.0580681786 124 1305031233.6330409050 0.0781610087 0.0823796252 0.1218760014 0.0286062351 0.0645730000 10284687 955859216 1780809728 -0.0280978642 -0.0082917279 0.0603853837 125 1305031233.6717829704 0.0768025294 0.0823350084 0.1218760014 0.0285313944 0.0768400000 10286581 955859216 1779773440 -0.0180483907 -0.0040657283 0.0720439702 126 1305031233.7022960186 0.0758238658 0.0822833327 0.1218760014 0.0285703494 0.1044920000 10288347 955859216 1778888704 -0.0189865250 -0.0035779658 0.0737677664 127 1305031233.7312009335 0.0735021457 0.0822141895 0.1218760014 0.0286520479 0.0716290000 10290049 955859216 1780252672 -0.0191886909 -0.0013272258 0.0753439292 128 1305031233.7691600323 0.0714277625 0.0821299205 0.1218760014 0.0287174836 0.0847150000 10291879 955859216 1779515392 -0.0175585318 0.0013020564 0.0770904422 129 1305031233.7997679710 0.0711957887 0.0820451598 0.1218760014 0.0286239181 0.0740430000 10303853 955859216 1778868224 -0.0152651202 0.0021787342 0.0784132257 130 1305031233.8338310719 0.0723823458 0.0819708305 0.1218760014 0.0285526589 0.0708280000 10326643 955859216 1778094080 -0.0129941488 0.0001034005 0.0791411921 131 1305031233.8655700684 0.0735768452 0.0819067542 0.1218760014 0.0284848513 0.0655080000 10328409 955859216 1777328128 -0.0117941415 -0.0011966398 0.0791221112 132 1305031233.8986968994 0.0729366988 0.0818387993 0.1218760014 0.0283777314 0.0690240000 10330239 955859216 1776476160 -0.0113499612 -0.0010159860 0.0793014541 133 1305031233.9320030212 0.0725610629 0.0817690419 0.1218760014 0.0283083437 0.0643700000 10332005 955859216 1775595520 -0.0102860667 -0.0011674714 0.0797660574 134 1305031233.9681589603 0.0713368952 0.0816911900 0.1218760014 0.0282199533 0.0538150000 10333835 955859216 1776959488 -0.0090323919 -0.0003669114 0.0798214301 135 1305031233.9989380836 0.0713478848 0.0816145729 0.1218760014 0.0281488116 0.0592430000 10335601 955859216 1776357376 -0.0068757362 -0.0003338892 0.0796685889 136 1305031234.0370678902 0.0696696043 0.0815267423 0.1218760014 0.0280560357 0.0570280000 10337463 955859216 1775468544 -0.0051976987 0.0019758188 0.0790572539 137 1305031234.0687561035 0.0679937527 0.0814279613 0.1218760014 0.0279595997 0.0675950000 10339197 955859216 1774579712 -0.0033992955 0.0044381837 0.0787849799 138 1305031234.0997409821 0.0671017095 0.0813241479 0.1218760014 0.0278690780 0.0900480000 10340963 955859216 1773690880 -0.0021868404 0.0065093162 0.0775433928 139 1305031234.1350688934 0.0659922287 0.0812138463 0.1218760014 0.0277856784 0.0676480000 10342761 955859216 1775050752 -0.0016743646 0.0083423760 0.0760047063 140 1305031234.1659009457 0.0614229999 0.0810724832 0.1218760014 0.0277814930 0.0881810000 10344527 955859216 1774403584 -0.0004736405 0.0161536932 0.0769720748 141 1305031234.2010040283 0.0615524054 0.0809340429 0.1218760014 0.0277483269 0.0651920000 10346325 955859216 1774542848 -0.0001314237 0.0156377759 0.0763867050 142 1305031234.2385749817 0.0601785220 0.0807878773 0.1218760014 0.0276504697 0.0778290000 10348219 955859216 1773891584 -0.0006717616 0.0169561263 0.0757653341 143 1305031234.2655100822 0.0553903654 0.0806102723 0.1218760014 0.0275881326 0.0629180000 10349857 955859216 1772908544 -0.0006744589 0.0254754834 0.0773524791 144 1305031234.3024549484 0.0551695898 0.0804336009 0.1218760014 0.0274923976 0.0514860000 10351751 955859216 1772040192 -0.0006332055 0.0251205489 0.0772794038 145 1305031234.3384580612 0.0549764670 0.0802580344 0.1218760014 0.0274288583 0.0571310000 10353581 955859216 1773400064 -0.0010081382 0.0255326610 0.0766287372 146 1305031234.3661808968 0.0519788899 0.0800643417 0.1218760014 0.0273639710 0.0608630000 10355251 955859216 1772781568 -0.0026173890 0.0290150549 0.0769703239 147 1305031234.4000349045 0.0512925200 0.0798686150 0.1218760014 0.0272714674 0.0700990000 10357049 955859216 1771913216 -0.0029376377 0.0303995535 0.0767381489 148 1305031234.4367709160 0.0516015030 0.0796776210 0.1218760014 0.0272510363 0.0695120000 10358911 955859216 1771024384 -0.0017876518 0.0304375086 0.0759083927 149 1305031234.4676060677 0.0516157001 0.0794892859 0.1218760014 0.0271633949 0.0678650000 10360645 955859216 1772384256 -0.0009598578 0.0316239260 0.0749152005 150 1305031234.4977810383 0.0510569811 0.0792997372 0.1218760014 0.0270751669 0.0649710000 10362379 955859216 1771356160 -0.0004826509 0.0340928510 0.0743195564 151 1305031234.5376710892 0.0525943227 0.0791228802 0.1218760014 0.0271525774 0.0629910000 10364273 955859216 1770242048 0.0012581229 0.0327368118 0.0715357885 152 1305031234.5690369606 0.0524895117 0.0789476607 0.1218760014 0.0271347294 0.0652150000 10366007 955859216 1769357312 0.0015702297 0.0352563523 0.0699204654 153 1305031234.5982480049 0.0521965697 0.0787728169 0.1218760014 0.0270492648 0.0728270000 10367773 955859216 1768472576 0.0022635930 0.0373442881 0.0692346543 154 1305031234.6336491108 0.0540774129 0.0786124572 0.1218760014 0.0269732096 0.0616290000 10369539 955859216 1769844736 0.0054600807 0.0379102826 0.0685443133 155 1305031234.6658589840 0.0546080247 0.0784575899 0.1218760014 0.0269155819 0.0614280000 10371337 955859216 1769246720 0.0064841015 0.0400651991 0.0679547712 156 1305031234.6987318993 0.0596164502 0.0783368133 0.1218760014 0.0268593615 0.1165030000 10373135 955859216 1768361984 0.0145733561 0.0487274341 0.0757876411 157 1305031234.7344369888 0.0630973428 0.0782397466 0.1218760014 0.0267920082 0.0594160000 10374901 955859216 1767690240 0.0177503228 0.0484770462 0.0754622221 158 1305031234.7689719200 0.0685799941 0.0781786090 0.1218760014 0.0267272394 0.0673920000 10376731 955859216 1766694912 0.0235653780 0.0482314192 0.0761748329 159 1305031234.8015530109 0.0716112778 0.0781373050 0.1218760014 0.0267559215 0.0595940000 10378529 955859216 1765928960 0.0260105208 0.0494460091 0.0765995011 160 1305031234.8378078938 0.0747990012 0.0781164406 0.1218760014 0.0266865318 0.0755640000 10380391 955859216 1765044224 0.0286831241 0.0496779457 0.0772674382 161 1305031234.8693211079 0.0764759555 0.0781062512 0.1218760014 0.0266323178 0.0714850000 10382093 955859216 1766408192 0.0296241045 0.0496010222 0.0765026584 162 1305031234.9019980431 0.0762609467 0.0780948605 0.1218760014 0.0265530135 0.0782480000 10383891 955859216 1765920768 0.0283981282 0.0517997704 0.0776752532 163 1305031234.9381608963 0.0693624392 0.0780412873 0.1218760014 0.0266129861 0.0856120000 10385721 955859216 1765539840 0.0183165744 0.0593064725 0.0793154687 164 1305031234.9730799198 0.0664661527 0.0779707072 0.1218760014 0.0265353531 0.0605380000 10387551 955859216 1765920768 0.0148178143 0.0592426732 0.0808670968 165 1305031235.0050830841 0.0606823638 0.0778659294 0.1218760014 0.0265679436 0.0717620000 10389285 955859216 1765163008 0.0068013854 0.0649840608 0.0862579271 166 1305031235.0399720669 0.0570491180 0.0777405269 0.1218760014 0.0264937341 0.0692810000 10391115 955859216 1765068800 0.0041093435 0.0617964268 0.0869531035 167 1305031235.0729401112 0.0504210293 0.0775769371 0.1218760014 0.0264367251 0.0740560000 10392881 955859216 1764552704 -0.0039573824 0.0608751029 0.0869182646 168 1305031235.0995910168 0.0459981896 0.0773889684 0.1218760014 0.0263843269 0.0701020000 10394583 955859216 1765052416 -0.0076403962 0.0585072786 0.0872782394 169 1305031235.1362709999 0.0435363874 0.0771886573 0.1218760014 0.0263404083 0.0635880000 10396413 955859216 1765068800 -0.0101818414 0.0544273183 0.0865784660 170 1305031235.1663711071 0.0405140929 0.0769729245 0.1218760014 0.0263120389 0.0669460000 10398147 955859216 1765163008 -0.0160563029 0.0529584624 0.0858986229 171 1305031235.1998469830 0.0382432751 0.0767464353 0.1218760014 0.0262879720 0.0672940000 10399881 955859216 1766653952 -0.0250735432 0.0544501022 0.0848877206 172 1305031235.2375700474 0.0371701345 0.0765163406 0.1218760014 0.0262764442 0.0672550000 10401743 955859216 1766432768 -0.0283025317 0.0536514856 0.0858360007 173 1305031235.2690389156 0.0364196040 0.0762845675 0.1218760014 0.0262268228 0.0678610000 10403509 955859216 1765945344 -0.0329251364 0.0527302399 0.0868248567 174 1305031235.3064870834 0.0370449759 0.0760590526 0.1218760014 0.0262332862 0.0755350000 10405371 955859216 1765060608 -0.0362829827 0.0529449172 0.0883051455 175 1305031235.3380000591 0.0389824584 0.0758471864 0.1218760014 0.0261723614 0.1090630000 10407105 955859216 1765052416 -0.0425964445 0.0522917658 0.0890946388 176 1305031235.3698880672 0.0424272120 0.0756573002 0.1218760014 0.0261337584 0.0959400000 10408871 955859216 1765003264 -0.0463622883 0.0491615348 0.0889174566 177 1305031235.4060161114 0.0449449793 0.0754837842 0.1218760014 0.0262068077 0.1022080000 10410701 955859216 1765163008 -0.0481532589 0.0493052602 0.0909675956 178 1305031235.4381530285 0.0449054539 0.0753119959 0.1218760014 0.0261707454 0.1181030000 10412467 955859216 1765036032 -0.0527416319 0.0510049164 0.0949331522 179 1305031235.4700589180 0.0407272428 0.0751187849 0.1218760014 0.0261128426 0.1210050000 10414233 955859216 1766526976 -0.0467305817 0.0495181121 0.1006697416 180 1305031235.5059850216 0.0386599675 0.0749162360 0.1218760014 0.0260672231 0.0750580000 10416063 955859216 1768288256 -0.0421620347 0.0497684963 0.1066046730 181 1305031235.5385539532 0.0373210572 0.0747085278 0.1218760014 0.0260024527 0.0657070000 10417829 955859216 1770065920 -0.0397556461 0.0502451025 0.1106061712 182 1305031235.5703649521 0.0349747464 0.0744902103 0.1218760014 0.0259368146 0.0897260000 10419595 955859216 1771716608 -0.0302514844 0.0480093956 0.1189305037 183 1305031235.6060059071 0.0321100987 0.0742586250 0.1218760014 0.0259493259 0.0675110000 10421457 955859216 1773367296 -0.0249588471 0.0514424741 0.1277296096 184 1305031235.6389510632 0.0376634635 0.0740597383 0.1218760014 0.0259011742 0.0649460000 10423223 955859216 1775144960 -0.0262217224 0.0474255234 0.1302696317 185 1305031235.6705160141 0.0426720679 0.0738900752 0.1218760014 0.0258412987 0.0657760000 10424957 955859216 1776922624 -0.0288100298 0.0445784442 0.1330368370 186 1305031235.7057778835 0.0517003424 0.0737707755 0.1218760014 0.0257740588 0.1095400000 10426787 955859216 1778446336 -0.0309182256 0.0394520760 0.1359588653 187 1305031235.7387969494 0.0613101944 0.0737041414 0.1218760014 0.0257617983 0.0701000000 10428585 955859216 1780224000 -0.0335775502 0.0329671614 0.1392475069 188 1305031235.7696299553 0.0652761534 0.0736593117 0.1218760014 0.0257105840 0.0595150000 10430319 955859216 1781874688 -0.0372242667 0.0331974179 0.1403890252 189 1305031235.8072249889 0.0717326626 0.0736491178 0.1218760014 0.0256500762 0.0537850000 10432245 955859216 1783525376 -0.0407686941 0.0325567275 0.1408674717 190 1305031235.8388121128 0.0776301324 0.0736700705 0.1218760014 0.0256203313 0.0862530000 10434011 955859216 1785303040 -0.0443437546 0.0308128074 0.1428587884 191 1305031235.8700668812 0.0830989778 0.0737194365 0.1218760014 0.0255914752 0.0588160000 10435809 955859216 1786953728 -0.0472541787 0.0293256678 0.1452979296 192 1305031235.9061110020 0.0887556449 0.0737977501 0.1218760014 0.0255279063 0.0815210000 10437671 955859216 1786081280 -0.0491125546 0.0285340697 0.1476562321 193 1305031235.9382328987 0.0939333811 0.0739020798 0.1218760014 0.0254733400 0.0986600000 10439501 955859216 1784061952 -0.0505147651 0.0268786680 0.1503384411 194 1305031235.9700109959 0.0975063220 0.0740237511 0.1218760014 0.0254197263 0.0904730000 10441267 955859216 1783414784 -0.0520258807 0.0267662313 0.1532265991 195 1305031236.0068531036 0.1029791310 0.0741722402 0.1218760014 0.0253623291 0.0671140000 10443161 955859216 1784430592 -0.0534648076 0.0256705899 0.1565677375 196 1305031236.0380480289 0.1069759801 0.0743396063 0.1218760014 0.0253028911 0.0880470000 10444927 955859216 1783779328 -0.0548901148 0.0253790878 0.1595648080 197 1305031236.0698781013 0.1106694266 0.0745240216 0.1218760014 0.0252921910 0.0918330000 10446725 955859216 1782796288 -0.0565260276 0.0250802580 0.1627026498 198 1305031236.1058719158 0.1153734177 0.0747303317 0.1218760014 0.0252371173 0.0700370000 10448587 955859216 1782018048 -0.0577624179 0.0239553228 0.1659425646 199 1305031236.1383249760 0.1186160222 0.0749508628 0.1218760014 0.0251772078 0.0506420000 10450417 955859216 1781022720 -0.0591055378 0.0232841857 0.1684555411 200 1305031236.1709330082 0.1212012172 0.0751821146 0.1218760014 0.0251147593 0.0634040000 10452215 955859216 1780027392 -0.0600943714 0.0231764596 0.1701245159 201 1305031236.2071900368 0.1226129681 0.0754180890 0.1226129681 0.0250624933 0.0697520000 10454109 955859216 1779134464 -0.0604420006 0.0240241885 0.1717451513 202 1305031236.2383749485 0.1245304868 0.0756612196 0.1245304868 0.0250265606 0.0521980000 10455907 955859216 1780494336 -0.0613574274 0.0227383934 0.1739860177 203 1305031236.2699589729 0.1270992160 0.0759146088 0.1270992160 0.0249658661 0.0597220000 10457673 955859216 1779896320 -0.0622416325 0.0200417954 0.1752797514 204 1305031236.3069939613 0.1279467195 0.0761696681 0.1279467195 0.0249665352 0.0868880000 10459567 955859216 1778864128 -0.0620125644 0.0171381012 0.1758599728 205 1305031236.3392169476 0.1296975315 0.0764307797 0.1296975315 0.0249198531 0.0768540000 10461365 955859216 1777991680 -0.0612882525 0.0131344572 0.1759442687 206 1305031236.3700959682 0.1299867183 0.0766907600 0.1299867183 0.0248758316 0.0548480000 10463131 955859216 1777070080 -0.0599846989 0.0097919926 0.1741429865 207 1305031236.4058690071 0.1281713992 0.0769394587 0.1299867183 0.0248674224 0.0574850000 10464993 955859216 1776091136 -0.0582388230 0.0069338717 0.1718224138 208 1305031236.4387879372 0.1258440763 0.0771745771 0.1299867183 0.0248074390 0.0790260000 10466791 955859216 1775198208 -0.0555564351 0.0045737177 0.1690827310 209 1305031236.4751410484 0.1218640059 0.0773884021 0.1299867183 0.0247495828 0.0548040000 10468685 955859216 1776558080 -0.0515655018 0.0029831233 0.1658660769 210 1305031236.5077209473 0.1170723513 0.0775773733 0.1299867183 0.0246957332 0.0801950000 10470515 955859216 1774694400 -0.0470448844 0.0025644565 0.1623384207 211 1305031236.5386450291 0.1140179038 0.0777500772 0.1299867183 0.0246568228 0.0626710000 10472281 955859216 1774145536 -0.0433259048 0.0006229207 0.1586332619 212 1305031236.5740950108 0.1088359654 0.0778967087 0.1299867183 0.0245995774 0.0713200000 10474143 955859216 1773146112 -0.0401901267 -0.0005523152 0.1540770382 213 1305031236.6057569981 0.1068927497 0.0780328404 0.1299867183 0.0245453062 0.0965320000 10475909 955859216 1772277760 -0.0371449254 -0.0035738184 0.1497735232 214 1305031236.6384010315 0.1035985202 0.0781523062 0.1299867183 0.0245183744 0.0936980000 10477707 955859216 1771388928 -0.0337277502 -0.0048034899 0.1440889835 215 1305031236.6751470566 0.0978101268 0.0782437379 0.1299867183 0.0244777398 0.0612740000 10479537 955859216 1770500096 -0.0308286771 -0.0048024976 0.1382220834 216 1305031236.7033619881 0.0940761343 0.0783170360 0.1299867183 0.0244256317 0.0538100000 10481239 955859216 1769943040 -0.0265908949 -0.0050206129 0.1331946403 217 1305031236.7339220047 0.0838948339 0.0783427402 0.1299867183 0.0244069465 0.0633290000 10482973 955859216 1770717184 -0.0255257487 0.0019600270 0.1220390350 218 1305031236.7740409374 0.0801240653 0.0783509114 0.1299867183 0.0243916100 0.0545700000 10484867 955859216 1770119168 -0.0230207574 0.0010616319 0.1159062311 219 1305031236.8025879860 0.0772121176 0.0783457114 0.1299867183 0.0244686789 0.0624710000 10486633 955859216 1769082880 -0.0208621025 0.0028749469 0.1076993495 220 1305031236.8364150524 0.0705550164 0.0783102992 0.1299867183 0.0244149104 0.0648940000 10488399 955859216 1770463232 -0.0181110371 0.0064718025 0.1008092165 221 1305031236.8743979931 0.0662698150 0.0782558173 0.1299867183 0.0243731436 0.0676140000 10490261 955859216 1769828352 -0.0158389695 0.0077577368 0.0935975760 222 1305031236.9060690403 0.0641492903 0.0781922744 0.1299867183 0.0243746433 0.0789520000 10492027 955859216 1769230336 -0.0131147560 0.0092006847 0.0865518972 223 1305031236.9344370365 0.0637645572 0.0781275761 0.1299867183 0.0243337799 0.0856500000 10493729 955859216 1768345600 -0.0114539601 0.0092949914 0.0792445764 224 1305031236.9744000435 0.0619175062 0.0780552098 0.1299867183 0.0242861899 0.0847900000 10495591 955859216 1767460864 -0.0095046749 0.0096365167 0.0728238076 225 1305031237.0074260235 0.0618885681 0.0779833580 0.1299867183 0.0242328884 0.0684920000 10497421 955859216 1766674432 -0.0111118080 0.0079648551 0.0638187677 226 1305031237.0370240211 0.0605245940 0.0779061069 0.1299867183 0.0242109881 0.0814330000 10499155 955859216 1765789696 -0.0103108371 0.0098950900 0.0579647869 227 1305031237.0734269619 0.0609653927 0.0778314782 0.1299867183 0.0241632889 0.1117350000 10500953 955859216 1765163008 -0.0077866097 0.0086430293 0.0525579639 228 1305031237.1059679985 0.0632311702 0.0777674417 0.1299867183 0.0241180415 0.0689980000 10502751 955859216 1765367808 -0.0051594148 0.0077181850 0.0465196110 229 1305031237.1378319263 0.0653139800 0.0777130598 0.1299867183 0.0240701671 0.0669730000 10504517 955859216 1765163008 -0.0017698747 0.0084778266 0.0401471145 230 1305031237.1712269783 0.0648203269 0.0776570044 0.1299867183 0.0240854728 0.0673740000 10506315 955859216 1765163008 -0.0002121557 0.0116175255 0.0355681889 231 1305031237.2042291164 0.0657466426 0.0776054444 0.1299867183 0.0240894358 0.0685210000 10508049 955859216 1765163008 0.0022449789 0.0113547640 0.0299014989 232 1305031237.2375690937 0.0671067908 0.0775601916 0.1299867183 0.0240935147 0.0768010000 10509879 955859216 1766637568 0.0050918479 0.0169289336 0.0262516532 233 1305031237.2746589184 0.0697868392 0.0775268296 0.1299867183 0.0240567790 0.0897760000 10511709 955859216 1765036032 0.0096139563 0.0174774379 0.0231302418 234 1305031237.3058099747 0.0734931380 0.0775095916 0.1299867183 0.0240204072 0.0735260000 10513475 955859216 1766400000 0.0147554558 0.0219647679 0.0218376275 235 1305031237.3371419907 0.0778816640 0.0775111749 0.1299867183 0.0240146234 0.0680150000 10515241 955859216 1766010880 0.0187192410 0.0224254373 0.0188132264 236 1305031237.3741660118 0.0823665336 0.0775317484 0.1299867183 0.0239758793 0.0659980000 10517039 955859216 1765167104 0.0235844161 0.0238920581 0.0163173657 237 1305031237.4057340622 0.0841358602 0.0775596139 0.1299867183 0.0239840217 0.0674380000 10518837 955859216 1765163008 0.0253628232 0.0260873251 0.0137983123 238 1305031237.4377219677 0.0882739797 0.0776046322 0.1299867183 0.0239800728 0.0778300000 10520603 955859216 1765163008 0.0291224457 0.0275852811 0.0119300550 239 1305031237.4741280079 0.0912092477 0.0776615553 0.1299867183 0.0239543039 0.0640880000 10522401 955859216 1766637568 0.0324013121 0.0292005707 0.0104146590 240 1305031237.5060451031 0.0929355323 0.0777251969 0.1299867183 0.0239339933 0.0658960000 10524199 955859216 1765527552 0.0343160965 0.0310220253 0.0097170221 241 1305031237.5376501083 0.0957183763 0.0777998574 0.1299867183 0.0238865802 0.0690730000 10525965 955859216 1765023744 0.0374398790 0.0326701477 0.0087252986 242 1305031237.5739479065 0.0980130732 0.0778833830 0.1299867183 0.0238535136 0.0795880000 10527763 955859216 1765036032 0.0395255573 0.0332796052 0.0077405386 243 1305031237.6068129539 0.0986349732 0.0779687805 0.1299867183 0.0238146587 0.0888670000 10529593 955859216 1765036032 0.0404920578 0.0352724008 0.0078996262 244 1305031237.6378550529 0.0992691517 0.0780560771 0.1299867183 0.0237753280 0.0606540000 10531327 955859216 1765146624 0.0407879911 0.0375688821 0.0078856647 245 1305031237.6752760410 0.0997348949 0.0781445621 0.1299867183 0.0237400920 0.0816310000 10533157 955859216 1765163008 0.0405843444 0.0393214412 0.0079152444 246 1305031237.7071180344 0.0992486998 0.0782303513 0.1299867183 0.0236951978 0.0609290000 10534955 955859216 1766526976 0.0394765958 0.0411217883 0.0077451803 247 1305031237.7416670322 0.0964302570 0.0783040351 0.1299867183 0.0236664184 0.0783010000 10536753 955859216 1765163008 0.0356931910 0.0432979129 0.0079883179 248 1305031237.7743060589 0.0980848297 0.0783837964 0.1299867183 0.0236989358 0.0646990000 10538487 955859216 1766764544 0.0378046371 0.0427620374 0.0087274034 249 1305031237.8064959049 0.0980946943 0.0784629566 0.1299867183 0.0236628799 0.0702610000 10540285 955859216 1766547456 0.0389699303 0.0404789187 0.0081565091 250 1305031237.8430309296 0.0934670195 0.0785229729 0.1299867183 0.0236850765 0.0834780000 10542147 955859216 1765113856 0.0321637020 0.0436793976 0.0079255998 251 1305031237.8754220009 0.0958770290 0.0785921125 0.1299867183 0.0238833544 0.0667110000 10543881 955859216 1765163008 0.0360244885 0.0421872176 0.0081362762 252 1305031237.9077839851 0.0952064469 0.0786580424 0.1299867183 0.0238708764 0.0659520000 10545679 955859216 1765163008 0.0366754867 0.0387521684 0.0075015426 253 1305031237.9441869259 0.0922635943 0.0787118193 0.1299867183 0.0239567067 0.0705410000 10547509 955859216 1765163008 0.0323705971 0.0417403243 0.0087970831 254 1305031237.9738099575 0.0922811776 0.0787652420 0.1299867183 0.0239145037 0.0881460000 10549179 955859216 1765163008 0.0312817395 0.0440227650 0.0115850726 255 1305031238.0069320202 0.0898489580 0.0788087075 0.1299867183 0.0238765832 0.1043050000 10551009 955859216 1765163008 0.0288590603 0.0435805395 0.0150750410 256 1305031238.0431399345 0.0874643326 0.0788425186 0.1299867183 0.0240650168 0.0675040000 10552839 955859216 1765163008 0.0267354175 0.0422062911 0.0174495634 257 1305031238.0740320683 0.0826682150 0.0788574046 0.1299867183 0.0240904388 0.0810720000 10575053 955859216 1766637568 0.0204074886 0.0436761305 0.0201360527 258 1305031238.1065878868 0.0736632273 0.0788372721 0.1299867183 0.0240735694 0.1085450000 10618803 955859216 1765036032 0.0094112139 0.0398288481 0.0154825654 259 1305031238.1433279514 0.0700624213 0.0788033924 0.1299867183 0.0241009322 0.0885200000 10620633 955859216 1765036032 0.0025212513 0.0367245562 0.0137668112 260 1305031238.1723001003 0.0606915243 0.0787337313 0.1299867183 0.0240762567 0.0750630000 10622399 955859216 1766400000 -0.0130602308 0.0428537615 0.0157762207 261 1305031238.2054259777 0.0575095341 0.0786524126 0.1299867183 0.0240334948 0.0843910000 10624133 955859216 1765146624 -0.0170445666 0.0342276618 0.0157226548 262 1305031238.2401471138 0.0547750369 0.0785612775 0.1299867183 0.0240117106 0.1087470000 10625963 955859216 1765031936 -0.0207907669 0.0289747566 0.0176470969 263 1305031238.2725269794 0.0520745926 0.0784605677 0.1299867183 0.0239695529 0.0882000000 10627761 955859216 1765031936 -0.0250264201 0.0275875945 0.0210169405 264 1305031238.3060529232 0.0491750129 0.0783496376 0.1299867183 0.0241470094 0.0805140000 10629527 955859216 1765031936 -0.0316023454 0.0289417561 0.0250128601 265 1305031238.3425960541 0.0495363288 0.0782409081 0.1299867183 0.0241454384 0.0868390000 10631357 955859216 1765146624 -0.0295995716 0.0268957466 0.0295725092 266 1305031238.3741040230 0.0503282137 0.0781359732 0.1299867183 0.0241840172 0.0899570000 10633123 955859216 1765163008 -0.0237645283 0.0254806075 0.0387304723 267 1305031238.4060359001 0.0543225817 0.0780467844 0.1299867183 0.0241392853 0.1006980000 10634889 955859216 1765163008 -0.0125798648 0.0263582729 0.0495288260 268 1305031238.4434239864 0.0588797107 0.0779752655 0.1299867183 0.0240996494 0.0894630000 10636719 955859216 1765163008 -0.0084286388 0.0247866772 0.0538585484 269 1305031238.4740819931 0.0602744780 0.0779094633 0.1299867183 0.0240589860 0.0710580000 10638485 955859216 1766764544 -0.0078001069 0.0231741723 0.0581569225 270 1305031238.5058109760 0.0615901910 0.0778490216 0.1299867183 0.0240756295 0.0691650000 10640251 955859216 1766383616 -0.0089021157 0.0194059964 0.0611036420 271 1305031238.5432639122 0.0653140172 0.0778027669 0.1299867183 0.0240342600 0.0646880000 10642113 955859216 1765801984 -0.0104969228 0.0141302776 0.0624784380 272 1305031238.5741839409 0.0661684722 0.0777599938 0.1299867183 0.0239933819 0.0637580000 10643815 955859216 1765023744 -0.0127149466 0.0120658875 0.0652343556 273 1305031238.6058249474 0.0681415349 0.0777247613 0.1299867183 0.0239536862 0.0623970000 10645613 955859216 1765036032 -0.0146364644 0.0095895547 0.0674821138 274 1305031238.6427590847 0.0697726607 0.0776957391 0.1299867183 0.0239172660 0.0668140000 10647475 955859216 1766510592 -0.0168434177 0.0076588858 0.0702142268 275 1305031238.6738131046 0.0726307705 0.0776773210 0.1299867183 0.0238796633 0.0685700000 10649177 955859216 1766055936 -0.0193948988 0.0062807640 0.0720386505 276 1305031238.7051889896 0.0736124068 0.0776625931 0.1299867183 0.0238373529 0.0706360000 10650943 955859216 1765277696 -0.0223062616 0.0060987114 0.0739452541 277 1305031238.7413070202 0.0756821781 0.0776554436 0.1299867183 0.0238233889 0.0642940000 10652805 955859216 1765031936 -0.0243414529 0.0051104594 0.0752786249 278 1305031238.7717959881 0.0782873854 0.0776577167 0.1299867183 0.0238008795 0.0625040000 10654571 955859216 1766395904 -0.0268155485 0.0033574509 0.0763889253 279 1305031238.8070189953 0.0808927789 0.0776693119 0.1299867183 0.0237786398 0.0575930000 10656401 955859216 1765928960 -0.0291220136 0.0033071274 0.0774409845 280 1305031238.8429400921 0.0820571333 0.0776849827 0.1299867183 0.0237400261 0.0667390000 10658263 955859216 1765150720 -0.0312083643 0.0031428356 0.0791356191 281 1305031238.8737230301 0.0865341201 0.0777164743 0.1299867183 0.0237413845 0.0701460000 10660061 955859216 1765163008 -0.0317445509 0.0002867831 0.0805812851 282 1305031238.9061720371 0.0900721624 0.0777602888 0.1299867183 0.0237161720 0.0628310000 10661827 955859216 1766526976 -0.0323272087 -0.0024666702 0.0823055953 283 1305031238.9427859783 0.0924368799 0.0778121496 0.1299867183 0.0236744176 0.0622540000 10663721 955859216 1766129664 -0.0329979584 -0.0036010770 0.0840057284 284 1305031238.9723079205 0.0948111266 0.0778720051 0.1299867183 0.0236442176 0.0676180000 10665487 955859216 1765277696 -0.0334666669 -0.0051828036 0.0853472352 285 1305031239.0104830265 0.0974973515 0.0779408660 0.1299867183 0.0236392082 0.0681270000 10667381 955859216 1765031936 -0.0339097530 -0.0061039431 0.0867231563 286 1305031239.0408790112 0.0990255848 0.0780145888 0.1299867183 0.0236015279 0.0743160000 10669147 955859216 1765031936 -0.0343743749 -0.0066271829 0.0880397484 287 1305031239.0746610165 0.1017547548 0.0780973071 0.1299867183 0.0236086852 0.0925640000 10670977 955859216 1765031936 -0.0346894301 -0.0086717885 0.0890954360 288 1305031239.1109058857 0.1043045223 0.0781883044 0.1299867183 0.0235676420 0.0737240000 10672871 955859216 1766510592 -0.0350459665 -0.0111207319 0.0901052952 289 1305031239.1417789459 0.1058531031 0.0782840303 0.1299867183 0.0235381501 0.0790740000 10674637 955859216 1766289408 -0.0356151760 -0.0133797675 0.0906161591 290 1305031239.1757500172 0.1082056314 0.0783872083 0.1299867183 0.0235185146 0.0692320000 10676467 955859216 1765908480 -0.0354363285 -0.0164720230 0.0904712528 291 1305031239.2096450329 0.1085386798 0.0784908216 0.1299867183 0.0234838393 0.0674470000 10678297 955859216 1765146624 -0.0347449668 -0.0171898045 0.0896538347 292 1305031239.2417099476 0.1088043302 0.0785946350 0.1299867183 0.0234567604 0.0801510000 10680095 955859216 1765163008 -0.0339888670 -0.0182290897 0.0888431668 293 1305031239.2738199234 0.1081933379 0.0786956544 0.1299867183 0.0234427176 0.0649890000 10681893 955859216 1765163008 -0.0329726711 -0.0188901983 0.0877856165 294 1305031239.3101770878 0.1077882946 0.0787946090 0.1299867183 0.0234038194 0.0757380000 10683787 955859216 1765031936 -0.0319877118 -0.0194152929 0.0863948315 295 1305031239.3419699669 0.1065084934 0.0788885544 0.1299867183 0.0233672030 0.0666620000 10685585 955859216 1766400000 -0.0310376789 -0.0192248914 0.0847466812 296 1305031239.3750240803 0.1045661047 0.0789753028 0.1299867183 0.0233486707 0.0883080000 10687351 955859216 1765928960 -0.0297814384 -0.0186490547 0.0825853497 297 1305031239.4106309414 0.1021336541 0.0790532771 0.1299867183 0.0233125695 0.1027640000 10689181 955859216 1765150720 -0.0287203640 -0.0171995722 0.0802842453 298 1305031239.4415419102 0.1010734737 0.0791271704 0.1299867183 0.0232779122 0.0890600000 10690947 955859216 1766526976 -0.0272324160 -0.0171452966 0.0779288039 299 1305031239.4733181000 0.0975183249 0.0791886792 0.1299867183 0.0232397634 0.0886890000 10692713 955859216 1768415232 -0.0262900461 -0.0146451835 0.0754086822 300 1305031239.5097389221 0.0938064754 0.0792374052 0.1299867183 0.0232029334 0.0951090000 10694543 955859216 1770065920 -0.0248315893 -0.0114655830 0.0722707137 301 1305031239.5438020229 0.0906329453 0.0792752642 0.1299867183 0.0231737570 0.0686010000 10696373 955859216 1771843584 -0.0236565825 -0.0093822833 0.0693901554 302 1305031239.5761160851 0.0874017477 0.0793021730 0.1299867183 0.0231459243 0.0690920000 10698139 955859216 1773494272 -0.0224983152 -0.0064097759 0.0663282871 303 1305031239.6111609936 0.0850626975 0.0793211847 0.1299867183 0.0231130254 0.0999450000 10699969 955859216 1775144960 -0.0214802288 -0.0043335357 0.0632296130 304 1305031239.6414220333 0.0838738084 0.0793361604 0.1299867183 0.0230777849 0.0702220000 10701703 955859216 1776922624 -0.0203043427 -0.0033495463 0.0598489195 305 1305031239.6710560322 0.0811036527 0.0793419555 0.1299867183 0.0230533956 0.0590030000 10703405 955859216 1778573312 -0.0193241891 -0.0004699004 0.0567486621 306 1305031239.7075550556 0.0794964135 0.0793424602 0.1299867183 0.0230651883 0.0691360000 10705235 955859216 1780350976 -0.0178708993 0.0004011112 0.0533888340 307 1305031239.7417550087 0.0793530121 0.0793424946 0.1299867183 0.0230289620 0.0991150000 10707065 955859216 1782001664 -0.0160395466 0.0003485376 0.0497988835 308 1305031239.7712600231 0.0791850090 0.0793419833 0.1299867183 0.0229969499 0.0821420000 10708767 955859216 1783652352 -0.0135993501 0.0005800590 0.0465345420 309 1305031239.8060870171 0.0793981329 0.0793421650 0.1299867183 0.0230770337 0.0993000000 10710565 955859216 1785430016 -0.0103099868 -0.0010785755 0.0434565097 310 1305031239.8392889500 0.0765778497 0.0793332479 0.1299867183 0.0230597211 0.0964850000 10712363 955859216 1787080704 -0.0107303830 0.0016178552 0.0394376405 311 1305031239.8744299412 0.0731876194 0.0793134870 0.1299867183 0.0230317119 0.1077200000 10714129 955859216 1784979456 -0.0121176764 0.0031401971 0.0369919203 312 1305031239.9090619087 0.0719767287 0.0792899717 0.1299867183 0.0230409428 0.0988730000 10715959 955859216 1783939072 -0.0108978227 0.0042598890 0.0347165242 313 1305031239.9403729439 0.0708483979 0.0792630019 0.1299867183 0.0230191211 0.0773180000 10717693 955859216 1783070720 -0.0110283960 0.0051005874 0.0312975012 314 1305031239.9710669518 0.0697762892 0.0792327894 0.1299867183 0.0230167483 0.0838260000 10719459 955859216 1784414208 -0.0108478935 0.0069459942 0.0281922370 315 1305031240.0088651180 0.0705306157 0.0792051634 0.1299867183 0.0230554119 0.0880090000 10721353 955859216 1783795712 -0.0096482811 0.0054400507 0.0239386130 316 1305031240.0396599770 0.0711410791 0.0791796442 0.1299867183 0.0230270135 0.0674470000 10723055 955859216 1783033856 -0.0084605440 0.0060269684 0.0202784576 317 1305031240.0711870193 0.0728350803 0.0791596298 0.1299867183 0.0229918383 0.0687350000 10724821 955859216 1782308864 -0.0064082593 0.0057307067 0.0169209838 318 1305031240.1093459129 0.0754824057 0.0791480662 0.1299867183 0.0229996769 0.0790570000 10726683 955859216 1781420032 -0.0019691638 0.0044792891 0.0136628971 319 1305031240.1435019970 0.0804033726 0.0791520013 0.1299867183 0.0229994955 0.0702580000 10728513 955859216 1780383744 0.0064644157 0.0049419762 0.0125520835 320 1305031240.1775770187 0.0815446600 0.0791594784 0.1299867183 0.0229881283 0.0682600000 10730279 955859216 1781764096 0.0085566035 0.0076412363 0.0100656655 321 1305031240.2093310356 0.0879738554 0.0791869375 0.1299867183 0.0229997206 0.1033440000 10732077 955859216 1779863552 0.0194942839 0.0082505606 0.0127982013 322 1305031240.2410049438 0.0937498584 0.0792321640 0.1299867183 0.0230310294 0.1238410000 10733811 955859216 1779007488 0.0262346379 0.0092514064 0.0095633017 323 1305031240.2774341106 0.0946997702 0.0792800513 0.1299867183 0.0230151194 0.1168260000 10735641 955859216 1777971200 0.0286497027 0.0111859329 0.0082058134 324 1305031240.3089289665 0.1013301685 0.0793481072 0.1299867183 0.0229828636 0.0951090000 10737375 955859216 1777086464 0.0374011882 0.0149087012 0.0101904096 325 1305031240.3422729969 0.1046030968 0.0794258149 0.1299867183 0.0229647382 0.0676700000 10739173 955859216 1776214016 0.0414772406 0.0165131819 0.0093451524 326 1305031240.3774259090 0.1015551016 0.0794936961 0.1299867183 0.0229895243 0.0881080000 10741003 955859216 1775325184 0.0368711650 0.0372581482 0.0159902927 327 1305031240.4091110229 0.1016109362 0.0795613329 0.1299867183 0.0229572310 0.0958480000 10742737 955859216 1774436352 0.0364138708 0.0398025960 0.0125058871 328 1305031240.4417860508 0.1010294855 0.0796267846 0.1299867183 0.0229221455 0.0691000000 10744535 955859216 1773547520 0.0347022116 0.0425600484 0.0113234799 329 1305031240.4776389599 0.0973001644 0.0796805031 0.1299867183 0.0228982509 0.0859530000 10746365 955859216 1772658688 0.0234310944 0.0573954582 0.0122195426 330 1305031240.5084490776 0.0980503336 0.0797361693 0.1299867183 0.0228840573 0.0757640000 10748067 955859216 1771757568 0.0224171244 0.0607233122 0.0125278253 331 1305031240.5412700176 0.0969385058 0.0797881401 0.1299867183 0.0228824248 0.1101430000 10749865 955859216 1770889216 0.0173946898 0.0656104758 0.0128943920 332 1305031240.5759088993 0.0981613621 0.0798434811 0.1299867183 0.0228583003 0.1070930000 10751695 955859216 1770000384 0.0153486459 0.0693750232 0.0139580239 333 1305031240.6101338863 0.0966260582 0.0798938792 0.1299867183 0.0228378141 0.0892450000 10753493 955859216 1769058304 0.0118139656 0.0708319470 0.0143020935 334 1305031240.6398229599 0.0951696411 0.0799396150 0.1299867183 0.0228278398 0.0681430000 10755195 955859216 1768222720 0.0089261131 0.0715287849 0.0161970574 335 1305031240.6747570038 0.0925310105 0.0799772013 0.1299867183 0.0227980474 0.1051100000 10757025 955859216 1767333888 0.0119387433 0.0652604327 0.0171350744 336 1305031240.7079319954 0.0895863995 0.0800058001 0.1299867183 0.0227960161 0.0847090000 10758823 955859216 1766445056 0.0116389962 0.0611735620 0.0187552571 337 1305031240.7439579964 0.0871730596 0.0800270679 0.1299867183 0.0227810630 0.0878450000 10760589 955859216 1765666816 0.0120875733 0.0574377403 0.0195921510 338 1305031240.7768330574 0.0840029195 0.0800388308 0.1299867183 0.0227537297 0.0823760000 10762419 955859216 1765163008 0.0121982927 0.0505543426 0.0175245255 339 1305031240.8096249104 0.0821719542 0.0800451232 0.1299867183 0.0227314485 0.1294910000 10764185 955859216 1765060608 0.0126886889 0.0453454554 0.0187167097 340 1305031240.8425960541 0.0778117925 0.0800385546 0.1299867183 0.0227086646 0.1085360000 10765951 955859216 1765060608 0.0080046514 0.0439659767 0.0186960977 341 1305031240.8794100285 0.0752209798 0.0800244268 0.1299867183 0.0226888050 0.0886840000 10767813 955859216 1765060608 0.0050861118 0.0410688147 0.0173887797 342 1305031240.9084498882 0.0709610954 0.0799979258 0.1299867183 0.0226677927 0.1153620000 10769547 955859216 1764995072 -0.0004844861 0.0379304700 0.0158029292 343 1305031240.9423189163 0.0641604364 0.0799517524 0.1299867183 0.0226626965 0.0871580000 10771313 955859216 1765154816 -0.0236412846 0.0347841866 0.0029133428 344 1305031240.9779360294 0.0640501603 0.0799055268 0.1299867183 0.0226305324 0.0704860000 10773143 955859216 1765060608 -0.0269885324 0.0313515812 0.0029610123 345 1305031241.0083029270 0.0616118312 0.0798525016 0.1299867183 0.0227098548 0.0792940000 10774877 955859216 1765044224 -0.0346227325 0.0334193446 0.0049844664 346 1305031241.0401480198 0.0598002449 0.0797945471 0.1299867183 0.0227603638 0.0697760000 10776579 955859216 1766408192 -0.0440481380 0.0329947062 0.0063811159 347 1305031241.0759329796 0.0613881312 0.0797415027 0.1299867183 0.0227499707 0.1075040000 10778441 955859216 1766064128 -0.0494718440 0.0305115301 0.0069032670 348 1305031241.1065559387 0.0649673343 0.0796990482 0.1299867183 0.0227253791 0.0815590000 10780175 955859216 1767424000 -0.0601471625 0.0273272395 0.0066602407 349 1305031241.1400520802 0.0709786639 0.0796740614 0.1299867183 0.0227232387 0.0827390000 10781941 955859216 1769312256 -0.0700466409 0.0250337496 0.0056895767 350 1305031241.1781818867 0.0758383274 0.0796631022 0.1299867183 0.0227781787 0.0845360000 10783803 955859216 1770962944 -0.0779879615 0.0259026922 0.0070191342 351 1305031241.2106790543 0.0777956992 0.0796577819 0.1299867183 0.0227504231 0.1108020000 10785601 955859216 1772740608 -0.0819118023 0.0260413643 0.0094253067 352 1305031241.2393150330 0.0766239539 0.0796491631 0.1299867183 0.0227693818 0.0875220000 10787271 955859216 1774391296 -0.0770033225 0.0227261074 0.0129332319 353 1305031241.2768468857 0.0723020881 0.0796283499 0.1299867183 0.0227697552 0.0841480000 10789165 955859216 1776041984 -0.0682623386 0.0223374721 0.0185946450 354 1305031241.3063299656 0.0489443950 0.0795416720 0.1299867183 0.0227912344 0.0885870000 10790899 955859216 1777819648 -0.0231795367 0.0320502445 0.0526393317 355 1305031241.3424758911 0.0512403995 0.0794619501 0.1299867183 0.0227723669 0.0889630000 10792729 955859216 1779470336 -0.0121631296 0.0333410800 0.0653200448 356 1305031241.3795149326 0.0554601289 0.0793945293 0.1299867183 0.0228140631 0.0669980000 10794559 955859216 1781121024 -0.0135577749 0.0294176824 0.0660106540 357 1305031241.4096820354 0.0596231446 0.0793391473 0.1299867183 0.0228119401 0.0680720000 10796293 955859216 1782898688 -0.0157375410 0.0260123201 0.0668004453 358 1305031241.4455459118 0.0638418421 0.0792958587 0.1299867183 0.0227992441 0.0659880000 10798123 955859216 1784549376 -0.0178396627 0.0241087973 0.0695808008 359 1305031241.4775071144 0.0674449876 0.0792628479 0.1299867183 0.0230232008 0.0685340000 10799889 955859216 1786327040 -0.0184448864 0.0213153902 0.0711924136 360 1305031241.5098490715 0.0705739558 0.0792387121 0.1299867183 0.0230219423 0.0884570000 10801655 955859216 1787977728 -0.0193545800 0.0185711198 0.0716937780 361 1305031241.5477299690 0.0728776827 0.0792210915 0.1299867183 0.0229936345 0.0858300000 10803549 955859216 1787228160 -0.0200923290 0.0159320142 0.0713760555 362 1305031241.5783948898 0.0734696910 0.0792052037 0.1299867183 0.0229766970 0.0881390000 10805251 955859216 1785323520 -0.0204718746 0.0152082006 0.0707325935 363 1305031241.6092638969 0.0743580759 0.0791918507 0.1299867183 0.0229716503 0.0646440000 10806985 955859216 1784295424 -0.0201273169 0.0136367418 0.0695606396 364 1305031241.6475839615 0.0763713866 0.0791841022 0.1299867183 0.0229438256 0.0616550000 10808879 955859216 1783586816 -0.0191706717 0.0106737707 0.0675834939 365 1305031241.6783659458 0.0731497854 0.0791675698 0.1299867183 0.0229627018 0.0919400000 10810645 955859216 1782697984 -0.0186812207 0.0137685491 0.0661511794 366 1305031241.7098269463 0.0716319904 0.0791469808 0.1299867183 0.0229425922 0.0842830000 10812347 955859216 1781661696 -0.0177475233 0.0153592089 0.0646700710 367 1305031241.7471020222 0.0701151416 0.0791223709 0.1299867183 0.0229166952 0.0883420000 10814241 955859216 1780793344 -0.0171370208 0.0164495260 0.0634228736 368 1305031241.7782680988 0.0701535791 0.0790979992 0.1299867183 0.0229052904 0.0730890000 10816007 955859216 1779757056 -0.0163736884 0.0163179860 0.0623469688 369 1305031241.8098289967 0.0684537739 0.0790691530 0.1299867183 0.0229044738 0.1135160000 10817709 955859216 1778741248 -0.0162518118 0.0184217151 0.0616196953 370 1305031241.8464360237 0.0699306279 0.0790444543 0.1299867183 0.0229082224 0.0639110000 10819571 955859216 1777872896 -0.0161406957 0.0161940344 0.0601563379 371 1305031241.8787989616 0.0699456930 0.0790199293 0.1299867183 0.0229888259 0.0678560000 10821369 955859216 1776836608 -0.0168083739 0.0163756981 0.0590198413 372 1305031241.9114871025 0.0674860775 0.0789889244 0.1299867183 0.0230181996 0.0696260000 10823135 955859216 1775968256 -0.0175512247 0.0192228947 0.0591992289 373 1305031241.9477050304 0.0682680905 0.0789601822 0.1299867183 0.0230213476 0.0857800000 10824965 955859216 1775063040 -0.0177228637 0.0183952060 0.0587623939 374 1305031241.9783430099 0.0681983158 0.0789314071 0.1299867183 0.0231597765 0.0896820000 10826731 955859216 1774190592 -0.0188374817 0.0183872245 0.0579959750 375 1305031242.0105700493 0.0677944869 0.0789017087 0.1299867183 0.0232721816 0.0841940000 10828465 955859216 1775550464 -0.0204603951 0.0188645814 0.0572068542 376 1305031242.0463600159 0.0688690245 0.0788750260 0.1299867183 0.0233681076 0.0843500000 10830295 955859216 1774661632 -0.0219673160 0.0178707037 0.0558178350 377 1305031242.0795490742 0.0705685169 0.0788529928 0.1299867183 0.0235004461 0.0855540000 10832061 955859216 1774026752 -0.0238262024 0.0160117932 0.0539281853 378 1305031242.1105840206 0.0725122541 0.0788362184 0.1299867183 0.0236077082 0.1063720000 10833827 955859216 1771470848 -0.0263776388 0.0130818877 0.0515511744 379 1305031242.1466050148 0.0747589394 0.0788254604 0.1299867183 0.0237642247 0.1273850000 10835657 955859216 1770635264 -0.0287917163 0.0101684099 0.0491441339 380 1305031242.1797080040 0.0772488788 0.0788213115 0.1299867183 0.0238667143 0.0696830000 10837455 955859216 1769746432 -0.0315691791 0.0064951740 0.0465959497 381 1305031242.2087249756 0.0793806836 0.0788227797 0.1299867183 0.0239172215 0.0652430000 10839157 955859216 1771106304 -0.0345569514 0.0025191968 0.0443015508 382 1305031242.2478089333 0.0816108361 0.0788300782 0.1299867183 0.0239927674 0.0656360000 10841051 955859216 1770508288 -0.0368222035 -0.0015587728 0.0422471203 383 1305031242.2794981003 0.0829570517 0.0788408536 0.1299867183 0.0240490911 0.0600310000 10842817 955859216 1769619456 -0.0393015929 -0.0040952018 0.0398688689 384 1305031242.3097639084 0.0846013352 0.0788558549 0.1299867183 0.0240909940 0.0852980000 10844519 955859216 1768714240 -0.0411578715 -0.0071971477 0.0374244042 385 1305031242.3471269608 0.0861653015 0.0788748405 0.1299867183 0.0242123975 0.0726620000 10846413 955859216 1770090496 -0.0430235527 -0.0104404464 0.0346484371 386 1305031242.3784790039 0.0866394937 0.0788949561 0.1299867183 0.0243333572 0.0904340000 10848179 955859216 1767206912 -0.0445402749 -0.0121107679 0.0327899680 387 1305031242.4109969139 0.0877544060 0.0789178488 0.1299867183 0.0244054535 0.1052010000 10849945 955859216 1766318080 -0.0455515310 -0.0143324574 0.0305610821 388 1305031242.4470989704 0.0888357759 0.0789434104 0.1299867183 0.0245654687 0.1068770000 10851807 955859216 1765429248 -0.0468815006 -0.0167451669 0.0276498552 389 1305031242.4776470661 0.0903529674 0.0789727409 0.1299867183 0.0246798032 0.1090100000 10853573 955859216 1765167104 -0.0483241156 -0.0185372625 0.0241124071 390 1305031242.5097260475 0.0922650695 0.0790068238 0.1299867183 0.0249518643 0.0839840000 10855339 955859216 1765167104 -0.0500634275 -0.0207467545 0.0199080277 391 1305031242.5485460758 0.0932129622 0.0790431567 0.1299867183 0.0254220159 0.0692030000 10857233 955859216 1765167104 -0.0531241670 -0.0210692324 0.0159417056 392 1305031242.5748429298 0.0944934636 0.0790825707 0.1299867183 0.0255901274 0.0667180000 10858871 955859216 1766645760 -0.0560199805 -0.0208103899 0.0118329236 393 1305031242.6061151028 0.0965759158 0.0791270830 0.1299867183 0.0256987624 0.1072780000 10860669 955859216 1766391808 -0.0588917732 -0.0220258441 0.0078019463 394 1305031242.6438109875 0.0992262959 0.0791780963 0.1299867183 0.0259563166 0.0869180000 10862531 955859216 1767804928 -0.0622785836 -0.0233116895 0.0040039001 395 1305031242.6752018929 0.1004847065 0.0792320370 0.1299867183 0.0262816324 0.0681490000 10864329 955859216 1769693184 -0.0658632442 -0.0234113280 0.0012833179 396 1305031242.7139821053 0.1026163772 0.0792910884 0.1299867183 0.0266801620 0.0666300000 10866255 955859216 1771343872 -0.0699193254 -0.0230242442 -0.0018855932 397 1305031242.7452580929 0.1053990498 0.0793568515 0.1299867183 0.0267772323 0.0673260000 10868021 955859216 1772994560 -0.0739701837 -0.0229765344 -0.0057642893 398 1305031242.7775399685 0.1079035774 0.0794285770 0.1299867183 0.0269498869 0.0877660000 10869819 955859216 1774772224 -0.0782354325 -0.0235359557 -0.0087290667 399 1305031242.8140709400 0.1103316620 0.0795060283 0.1299867183 0.0271751011 0.0883720000 10871681 955859216 1776422912 -0.0824148878 -0.0227751564 -0.0105831167 400 1305031242.8443179131 0.1125978753 0.0795887579 0.1299867183 0.0272294929 0.1073530000 10873447 955859216 1778073600 -0.0859651342 -0.0219648778 -0.0125338174 401 1305031242.8740880489 0.1156452596 0.0796786744 0.1299867183 0.0272832450 0.0903440000 10875245 955859216 1779851264 -0.0894919038 -0.0219271965 -0.0142769888 402 1305031242.9137070179 0.1200439185 0.0797790855 0.1299867183 0.0273885792 0.0856070000 10877203 955859216 1781501952 -0.0946311280 -0.0215534978 -0.0170369260 403 1305031242.9444379807 0.1213278323 0.0798821841 0.1299867183 0.0275699385 0.1051940000 10878969 955859216 1783152640 -0.0991224796 -0.0188508313 -0.0182915423 404 1305031242.9760620594 0.1225113645 0.0799877019 0.1299867183 0.0276320787 0.0855440000 10880735 955859216 1784930304 -0.1048148870 -0.0157848615 -0.0202553626 405 1305031243.0141661167 0.1248777658 0.0800985415 0.1299867183 0.0276950355 0.0910580000 10882629 955859216 1786580992 -0.1099725813 -0.0139408596 -0.0215729456 406 1305031243.0469100475 0.1261254102 0.0802119082 0.1299867183 0.0276988759 0.0656410000 10884523 955859216 1785733120 -0.1144488454 -0.0122366678 -0.0224913992 407 1305031243.0780448914 0.1269918531 0.0803268466 0.1299867183 0.0276914435 0.0671970000 10886321 955859216 1784848384 -0.1178913489 -0.0096668303 -0.0243353732 408 1305031243.1136150360 0.1269178540 0.0804410403 0.1299867183 0.0276991109 0.0687490000 10888151 955859216 1783820288 -0.1210524887 -0.0066837794 -0.0256992429 409 1305031243.1458160877 0.1266804338 0.0805540950 0.1299867183 0.0276670904 0.0878110000 10889981 955859216 1782951936 -0.1238120720 -0.0037984634 -0.0276439674 410 1305031243.1780760288 0.1255241036 0.0806637780 0.1299867183 0.0276599331 0.0654870000 10891779 955859216 1784311808 -0.1254537255 -0.0027613232 -0.0282713063 411 1305031243.2136580944 0.1247322708 0.0807710006 0.1299867183 0.0276972432 0.0871280000 10893641 955859216 1783713792 -0.1248166189 -0.0049857213 -0.0274773687 412 1305031243.2455608845 0.1261395812 0.0808811185 0.1299867183 0.0279986969 0.0897470000 10895439 955859216 1782677504 -0.1233638078 -0.0084767155 -0.0277398452 413 1305031243.2781798840 0.1273997873 0.0809937545 0.1299867183 0.0281099875 0.0794730000 10897269 955859216 1781661696 -0.1217979565 -0.0132118072 -0.0270954520 414 1305031243.3142709732 0.1276598126 0.0811064745 0.1299867183 0.0281878172 0.0820850000 10899099 955859216 1780740096 -0.1186203584 -0.0157268476 -0.0252443850 415 1305031243.3460359573 0.1282593012 0.0812200957 0.1299867183 0.0285490619 0.0912050000 10900929 955859216 1779757056 -0.1152213141 -0.0175861288 -0.0240407903 416 1305031243.3789350986 0.1282241940 0.0813330863 0.1299867183 0.0286069714 0.0964910000 10902759 955859216 1778888704 -0.1126451567 -0.0185974427 -0.0214580260 417 1305031243.4139740467 0.1176136881 0.0814200902 0.1299867183 0.0286838997 0.1296120000 10904589 955859216 1777074176 -0.0989232808 -0.0096988278 -0.0113867596 418 1305031243.4470911026 0.1202732548 0.0815130403 0.1299867183 0.0289359488 0.0853740000 10906419 955859216 1778724864 -0.0997861102 -0.0109690838 -0.0113524469 419 1305031243.4780371189 0.1198886633 0.0816046289 0.1299867183 0.0289780576 0.1032700000 10908185 955859216 1780359168 -0.0987561047 -0.0077026905 -0.0097409366 420 1305031243.5154008865 0.1178021729 0.0816908136 0.1299867183 0.0291100495 0.1080260000 10910079 955859216 1782136832 -0.0992851332 -0.0017214401 -0.0079403147 421 1305031243.5459430218 0.1191655099 0.0817798271 0.1299867183 0.0291938494 0.0897840000 10911877 955859216 1783787520 -0.1015073732 -0.0011710530 -0.0077509275 422 1305031243.5779840946 0.1153480113 0.0818593726 0.1299867183 0.0292029079 0.1047100000 10913611 955859216 1785565184 -0.1011550725 0.0050363606 -0.0057347976 423 1305031243.6140549183 0.1142348722 0.0819359104 0.1299867183 0.0294893283 0.1269640000 10915441 955859216 1787215872 -0.1013047621 0.0083374586 -0.0048248842 424 1305031243.6461870670 0.1165882349 0.0820176376 0.1299867183 0.0298186362 0.0815810000 10917271 955859216 1786470400 -0.1029299796 0.0053767622 -0.0063152267 425 1305031243.6782801151 0.1190361902 0.0821047400 0.1299867183 0.0298837237 0.0674200000 10919037 955859216 1785573376 -0.1044591591 0.0022714906 -0.0074107200 426 1305031243.7142961025 0.1102013513 0.0821706945 0.1299867183 0.0302229358 0.0999020000 10920835 955859216 1784827904 -0.0971730947 0.0108898673 -0.0024991333 427 1305031243.7473781109 0.1116276532 0.0822396804 0.1299867183 0.0305496864 0.1091300000 10922633 955859216 1783590912 -0.0964776799 0.0067385072 -0.0029561892 428 1305031243.7790360451 0.1130341068 0.0823116300 0.1299867183 0.0307806814 0.0846460000 10924367 955859216 1783406592 -0.0961340666 0.0022194383 -0.0028254092 429 1305031243.8141930103 0.1029694751 0.0823597835 0.1299867183 0.0312654609 0.0873640000 10926165 955859216 1783795712 -0.0829772577 0.0077679865 0.0048999484 430 1305031243.8462920189 0.1050148606 0.0824124697 0.1299867183 0.0316544978 0.0818220000 10927931 955859216 1783033856 -0.0774553195 0.0030227941 0.0049543674 431 1305031243.8788089752 0.0983616635 0.0824494748 0.1299867183 0.0318038488 0.1097580000 10929729 955859216 1780514816 -0.0655326694 0.0065736957 0.0126650874 432 1305031243.9140000343 0.0950503722 0.0824786435 0.1299867183 0.0321109113 0.0860650000 10931495 955859216 1779515392 -0.0623191968 0.0070151612 0.0143056083 433 1305031243.9470779896 0.0845343620 0.0824833911 0.1299867183 0.0322332466 0.1146130000 10933325 955859216 1778626560 -0.0511240214 0.0175062995 0.0236825850 434 1305031243.9816520214 0.0822103396 0.0824827620 0.1299867183 0.0323777426 0.0797330000 10935123 955859216 1777590272 -0.0506894737 0.0187003314 0.0239871927 435 1305031244.0112700462 0.0795165151 0.0824759430 0.1299867183 0.0324507590 0.1076260000 10936857 955859216 1776721920 -0.0498531051 0.0209284611 0.0248701498 436 1305031244.0438230038 0.0710664988 0.0824497746 0.1299867183 0.0324538871 0.1451480000 10938623 955859216 1775833088 -0.0506188236 0.0328737982 0.0281756967 437 1305031244.0818090439 0.0670162439 0.0824144576 0.1299867183 0.0324826633 0.0888850000 10940485 955859216 1774944256 -0.0492200963 0.0380400345 0.0317264087 438 1305031244.1127901077 0.0677799433 0.0823810454 0.1299867183 0.0325515039 0.0870010000 10942251 955859216 1774055424 -0.0483682305 0.0378182940 0.0325180665 439 1305031244.1484949589 0.0645426661 0.0823404113 0.1299867183 0.0325493695 0.1091280000 10944081 955859216 1773166592 -0.0524931252 0.0436454862 0.0332530849 440 1305031244.1824309826 0.0621163584 0.0822944476 0.1299867183 0.0326210076 0.0846080000 10945847 955859216 1772277760 -0.0534933433 0.0462293476 0.0354290828 441 1305031244.2124009132 0.0613275990 0.0822469037 0.1299867183 0.0327328567 0.1044940000 10947613 955859216 1771335680 -0.0531661958 0.0493206605 0.0367699564 442 1305031244.2473471165 0.0574383214 0.0821907757 0.1299867183 0.0328882802 0.0882340000 10949411 955859216 1770500096 -0.0531534031 0.0560649857 0.0388989337 443 1305031244.2831470966 0.0561343953 0.0821319577 0.1299867183 0.0330283406 0.1288280000 10951241 955859216 1769611264 -0.0512513369 0.0594143979 0.0400080755 444 1305031244.3137950897 0.0480384678 0.0820551705 0.1299867183 0.0331460704 0.1022750000 10952943 955859216 1770971136 -0.0448394790 0.0699673519 0.0460433625 445 1305031244.3459599018 0.0427594110 0.0819668654 0.1299867183 0.0333115816 0.0899520000 10954741 955859216 1772732416 -0.0350375734 0.0792793334 0.0528650098 446 1305031244.3808560371 0.0434162617 0.0818804291 0.1299867183 0.0334911656 0.0850810000 10956539 955859216 1774510080 -0.0318450369 0.0826134160 0.0518912934 447 1305031244.4130189419 0.0432446972 0.0817939957 0.1299867183 0.0337008563 0.0898440000 10958305 955859216 1776160768 -0.0187536608 0.0908910409 0.0605123192 448 1305031244.4451670647 0.0411654301 0.0817033069 0.1299867183 0.0337719067 0.0877790000 10960071 955859216 1777938432 -0.0173619408 0.1001142412 0.0614396967 449 1305031244.4806590080 0.0403491929 0.0816112042 0.1299867183 0.0338470815 0.0873260000 10961901 955859216 1779589120 -0.0198950339 0.1045110077 0.0584935397 450 1305031244.5142281055 0.0408799425 0.0815206903 0.1299867183 0.0339469022 0.1075500000 10963699 955859216 1781239808 -0.0214202367 0.1090479642 0.0574472360 451 1305031244.5462141037 0.0374275595 0.0814229228 0.1299867183 0.0339262469 0.1288570000 10965465 955859216 1783017472 -0.0237050168 0.1181096137 0.0599406213 452 1305031244.5808050632 0.0364832729 0.0813234988 0.1299867183 0.0339757788 0.1274660000 10967263 955859216 1784668160 -0.0266694427 0.1193405315 0.0599965677 453 1305031244.6132769585 0.0363926142 0.0812243137 0.1299867183 0.0340600472 0.1097610000 10969061 955859216 1786445824 -0.0284816530 0.1206003129 0.0604880452 454 1305031244.6428399086 0.0348060839 0.0811220709 0.1299867183 0.0340520413 0.0858350000 10970763 955859216 1788096512 -0.0302951355 0.1229872406 0.0617154241 455 1305031244.6806099415 0.0332967229 0.0810169602 0.1299867183 0.0341096029 0.0860670000 10972593 955859216 1787219968 -0.0302743278 0.1268832237 0.0651241913 456 1305031244.7152500153 0.0321463235 0.0809097878 0.1299867183 0.0341319220 0.0847690000 10974423 955859216 1785573376 -0.0337888822 0.1285200566 0.0652956441 457 1305031244.7458879948 0.0325132832 0.0808038873 0.1299867183 0.0343166572 0.1082080000 10976157 955859216 1783422976 -0.0358568206 0.1289212704 0.0650095344 458 1305031244.7818510532 0.0329709686 0.0806994486 0.1299867183 0.0344049458 0.0888270000 10978019 955859216 1783300096 -0.0359104425 0.1294506788 0.0647229627 459 1305031244.8140940666 0.0287387744 0.0805862445 0.1299867183 0.0352704799 0.0861950000 10979785 955859216 1783525376 -0.0304690599 0.1332967728 0.0692187250 460 1305031244.8418219090 0.0273381397 0.0804704878 0.1299867183 0.0352560734 0.0847950000 10981455 955859216 1782923264 -0.0274508521 0.1362882704 0.0706659853 461 1305031244.8818008900 0.0268492624 0.0803541728 0.1299867183 0.0352260591 0.0849670000 10983349 955859216 1781125120 -0.0289191529 0.1390879899 0.0688225478 462 1305031244.9149079323 0.0259429216 0.0802363995 0.1299867183 0.0352057284 0.0851710000 10985115 955859216 1779220480 -0.0290578529 0.1423028558 0.0685277134 463 1305031244.9458680153 0.0242133252 0.0801153993 0.1299867183 0.0351684672 0.0862690000 10986849 955859216 1778462720 -0.0276548993 0.1471866220 0.0700846538 464 1305031244.9818000793 0.0249562506 0.0799965219 0.1299867183 0.0351926551 0.0836330000 10988679 955859216 1777319936 -0.0272809956 0.1499703079 0.0708602741 465 1305031245.0140550137 0.0241558552 0.0798764344 0.1299867183 0.0351571631 0.1273670000 10990445 955859216 1776472064 -0.0250995401 0.1508230567 0.0728502274 466 1305031245.0464398861 0.0246761795 0.0797579789 0.1299867183 0.0351225237 0.1273730000 10992211 955859216 1777827840 -0.0256677568 0.1525264680 0.0731369928 467 1305031245.0817689896 0.0240121633 0.0796386089 0.1299867183 0.0351026519 0.0850930000 10994041 955859216 1779589120 -0.0240779426 0.1532721221 0.0762945712 468 1305031245.1143150330 0.0256764293 0.0795233051 0.1299867183 0.0351022167 0.0708640000 10995775 955859216 1781366784 -0.0231159795 0.1524066329 0.0774534047 469 1305031245.1457099915 0.0274749398 0.0794123277 0.1299867183 0.0350868829 0.0847110000 10997573 955859216 1783017472 -0.0237502195 0.1517808437 0.0783472434 470 1305031245.1818709373 0.0296847504 0.0793065244 0.1299867183 0.0350978982 0.0907870000 10999371 955859216 1784668160 -0.0221278481 0.1485686302 0.0800179318 471 1305031245.2140939236 0.0341154337 0.0792105773 0.1299867183 0.0351776476 0.0872600000 11001137 955859216 1786445824 -0.0207049940 0.1430408806 0.0797710419 472 1305031245.2487950325 0.0323371701 0.0791112692 0.1299867183 0.0355287885 0.0866990000 11002967 955859216 1785741312 -0.0335863531 0.1420167387 0.0711680651 473 1305031245.2807950974 0.0347690098 0.0790175224 0.1299867183 0.0356094029 0.0839640000 11004701 955859216 1783836672 -0.0326449461 0.1362344027 0.0704071894 474 1305031245.3143179417 0.0370913222 0.0789290705 0.1299867183 0.0357552460 0.1056330000 11006467 955859216 1783414784 -0.0307708625 0.1299277544 0.0700450242 475 1305031245.3491809368 0.0365435742 0.0788398378 0.1299867183 0.0360047269 0.1282100000 11008329 955859216 1784811520 -0.0372255333 0.1241165251 0.0625708401 476 1305031245.3806860447 0.0389847830 0.0787561087 0.1299867183 0.0362169581 0.1079330000 11010031 955859216 1786572800 -0.0387312919 0.1160459071 0.0562066063 477 1305031245.4133110046 0.0414460748 0.0786778906 0.1299867183 0.0363774377 0.1241570000 11011797 955859216 1785810944 -0.0426986739 0.1094357893 0.0486909300 478 1305031245.4489970207 0.0472063795 0.0786120507 0.1299867183 0.0363689676 0.1267190000 11013595 955859216 1787224064 -0.0415099300 0.0984115377 0.0412286110 479 1305031245.4846711159 0.0484343804 0.0785490493 0.1299867183 0.0366113675 0.0885280000 11015425 955859216 1786580992 -0.0395041704 0.0953801274 0.0393171273 480 1305031245.5124320984 0.0509496704 0.0784915505 0.1299867183 0.0366959861 0.1046370000 11017127 955859216 1783660544 -0.0460578576 0.0899197757 0.0308846273 481 1305031245.5481460094 0.0522051975 0.0784369012 0.1299867183 0.0368571321 0.0878390000 11018925 955859216 1782669312 -0.0476207137 0.0862543583 0.0274691246 482 1305031245.5786890984 0.0552515835 0.0783887988 0.1299867183 0.0368726574 0.1103520000 11020691 955859216 1781800960 -0.0526863746 0.0804872438 0.0205390882 483 1305031245.6104750633 0.0588982850 0.0783484458 0.1299867183 0.0369501273 0.0861340000 11022425 955859216 1780764672 -0.0548787341 0.0750131011 0.0152095947 484 1305031245.6494629383 0.0593361147 0.0783091641 0.1299867183 0.0371384730 0.1034490000 11024287 955859216 1779896320 -0.0594893806 0.0726434663 0.0118126487 485 1305031245.6802349091 0.0597014762 0.0782707978 0.1299867183 0.0371660844 0.0915240000 11026053 955859216 1778860032 -0.0599888936 0.0708268434 0.0116186524 486 1305031245.7110319138 0.0629990846 0.0782393745 0.1299867183 0.0371709072 0.1149460000 11027819 955859216 1777864704 -0.0642913729 0.0657015964 0.0071018338 487 1305031245.7497749329 0.0630248711 0.0782081332 0.1299867183 0.0372518600 0.0795550000 11029681 955859216 1776975872 -0.0635495558 0.0653320923 0.0074422574 488 1305031245.7818500996 0.0642074198 0.0781794432 0.1299867183 0.0373038002 0.0845590000 11031479 955859216 1776087040 -0.0618513897 0.0649683550 0.0070066443 489 1305031245.8135690689 0.0655459464 0.0781536079 0.1299867183 0.0374124627 0.0855110000 11033213 955859216 1775198208 -0.0617113449 0.0643771589 0.0064261355 490 1305031245.8491089344 0.0678237453 0.0781325265 0.1299867183 0.0374448126 0.1085250000 11035043 955859216 1774309376 -0.0602973253 0.0620093644 0.0054408163 491 1305031245.8820281029 0.0697711259 0.0781154972 0.1299867183 0.0374720271 0.0887800000 11036841 955859216 1773420544 -0.0592034906 0.0590998456 0.0047623618 492 1305031245.9126079082 0.0725503191 0.0781041858 0.1299867183 0.0374835937 0.0851340000 11038575 955859216 1772531712 -0.0576325133 0.0557252951 0.0038211392 493 1305031245.9458959103 0.0747002661 0.0780972813 0.1299867183 0.0375376314 0.0836140000 11040341 955859216 1773891584 -0.0575526357 0.0518636405 0.0026456527 494 1305031245.9808180332 0.0764250308 0.0780938962 0.1299867183 0.0375720046 0.1095870000 11042171 955859216 1770860544 -0.0586977340 0.0491115004 0.0005837529 495 1305031246.0110030174 0.0793794692 0.0780964933 0.1299867183 0.0375881834 0.1065560000 11043905 955859216 1769938944 -0.0595804006 0.0451538824 -0.0024578888 496 1305031246.0483930111 0.0828041211 0.0781059845 0.1299867183 0.0376677352 0.0881690000 11045799 955859216 1769324544 -0.0624747947 0.0399919525 -0.0065449253 497 1305031246.0805249214 0.0857100263 0.0781212844 0.1299867183 0.0377382903 0.0827480000 11047501 955859216 1770590208 -0.0641003475 0.0364892855 -0.0093651135 498 1305031246.1123559475 0.0882889479 0.0781417014 0.1299867183 0.0378414340 0.1105210000 11049299 955859216 1768435712 -0.0656358749 0.0333549865 -0.0118854009 499 1305031246.1484489441 0.0908976793 0.0781672645 0.1299867183 0.0379559889 0.0844150000 11051097 955859216 1768574976 -0.0671194866 0.0304431263 -0.0145574491 500 1305031246.1805961132 0.0929877684 0.0781969055 0.1299867183 0.0380141847 0.0678410000 11052831 955859216 1768812544 -0.0699214414 0.0283304583 -0.0176538080 501 1305031246.2111370564 0.0992764309 0.0782389804 0.1299867183 0.0380965979 0.1046160000 11054597 955859216 1768198144 -0.0800195932 0.0201838426 -0.0256763473 502 1305031246.2469689846 0.1007455215 0.0782838141 0.1299867183 0.0382351991 0.0898010000 11056427 955859216 1767923712 -0.0814639851 0.0190003924 -0.0274175070 503 1305031246.2796959877 0.1066610962 0.0783402302 0.1299867183 0.0382991144 0.0846580000 11058193 955859216 1768304640 -0.0881154016 0.0128065860 -0.0336936414 504 1305031246.3124730587 0.1075256690 0.0783981378 0.1299867183 0.0384362592 0.0678770000 11059991 955859216 1767550976 -0.0892598405 0.0140252430 -0.0350763462 505 1305031246.3482720852 0.1135158911 0.0784676779 0.1299867183 0.0385497022 0.0855140000 11061821 955859216 1766764544 -0.0964436233 0.0087193958 -0.0405761860 506 1305031246.3782060146 0.1137360334 0.0785373782 0.1299867183 0.0387131898 0.0683660000 11063555 955859216 1765928960 -0.0987248123 0.0111247590 -0.0415240489 507 1305031246.4156370163 0.1149954796 0.0786092877 0.1299867183 0.0388771013 0.0851940000 11065449 955859216 1765150720 -0.1023219153 0.0128133344 -0.0422847755 508 1305031246.4452888966 0.1153304130 0.0786815734 0.1299867183 0.0389806259 0.0870610000 11067183 955859216 1765163008 -0.1039507091 0.0156664755 -0.0425722301 509 1305031246.4774649143 0.1197709367 0.0787622990 0.1299867183 0.0390738299 0.1063270000 11069013 955859216 1765163008 -0.1117203757 0.0138944201 -0.0467910990 510 1305031246.5163950920 0.1197418943 0.0788426512 0.1299867183 0.0392127774 0.0672610000 11070907 955859216 1765031936 -0.1136011779 0.0177982189 -0.0462420732 511 1305031246.5491750240 0.1202708110 0.0789237239 0.1299867183 0.0393433991 0.0705630000 11072737 955859216 1765036032 -0.1167747751 0.0198793337 -0.0464299805 512 1305031246.5795109272 0.1197151989 0.0790033948 0.1299867183 0.0394420775 0.0855860000 11074503 955859216 1765036032 -0.1190487146 0.0234159846 -0.0460538752 513 1305031246.6164529324 0.1259366125 0.0790948825 0.1299867183 0.0395024196 0.1039560000 11117357 955859216 1765163008 -0.1283515990 0.0212860499 -0.0511454195 514 1305031246.6477630138 0.1254434735 0.0791850549 0.1299867183 0.0395651446 0.0732410000 11203123 955859216 1765163008 -0.1292014718 0.0260951631 -0.0511582084 515 1305031246.6807579994 0.1240745559 0.0792722189 0.1299867183 0.0396612820 0.0840710000 11204953 955859216 1765031936 -0.1301640570 0.0298881419 -0.0503171533 516 1305031246.7169740200 0.1247172430 0.0793602907 0.1299867183 0.0397987978 0.1036600000 11206847 955859216 1765019648 -0.1316630542 0.0324436612 -0.0509923697 517 1305031246.7491660118 0.1240711063 0.0794467720 0.1299867183 0.0398909362 0.0872490000 11208645 955859216 1765019648 -0.1327438802 0.0367065258 -0.0518062115 518 1305031246.7808170319 0.1240855008 0.0795329471 0.1299867183 0.0399585908 0.1030580000 11210475 955859216 1765146624 -0.1349751055 0.0393145233 -0.0526911765 519 1305031246.8168079853 0.1262961626 0.0796230497 0.1299867183 0.0400285895 0.0862960000 11212369 955859216 1765163008 -0.1370943636 0.0426815674 -0.0560623854 520 1305031246.8488121033 0.1262008697 0.0797126224 0.1299867183 0.0400564138 0.0680800000 11214199 955859216 1766526976 -0.1395139247 0.0452937819 -0.0574944466 521 1305031246.8806428909 0.1313132197 0.0798116638 0.1313132197 0.0401188252 0.0864830000 11216029 955859216 1765892096 -0.1497937143 0.0437433980 -0.0634530410 522 1305031246.9166710377 0.1289864331 0.0799058684 0.1313132197 0.0402066076 0.0829640000 11217923 955859216 1765511168 -0.1486619264 0.0479579382 -0.0644963160 523 1305031246.9495339394 0.1364233643 0.0800139324 0.1364233643 0.0401971258 0.1066060000 11219753 955859216 1765130240 -0.1558640897 0.0464013442 -0.0720499530 524 1305031246.9775969982 0.1368135810 0.0801223287 0.1368135810 0.0401817582 0.0838710000 11221487 955859216 1765031936 -0.1562036574 0.0477515310 -0.0737583041 525 1305031247.0167899132 0.1338068843 0.0802245850 0.1368135810 0.0402734372 0.1049890000 11223413 955859216 1765019648 -0.1556778848 0.0517721958 -0.0740522593 526 1305031247.0479340553 0.1390797794 0.0803364770 0.1390797794 0.0402456143 0.1256430000 11225243 955859216 1765146624 -0.1633873135 0.0494476259 -0.0805824697 527 1305031247.0778899193 0.1339005679 0.0804381166 0.1390797794 0.0402375554 0.1076130000 11227041 955859216 1765163008 -0.1614832133 0.0545461699 -0.0802304968 528 1305031247.1162130833 0.1305252463 0.0805329786 0.1390797794 0.0402092538 0.1263140000 11228967 955859216 1765163008 -0.1610513031 0.0585996248 -0.0816030726 529 1305031247.1473660469 0.1312829256 0.0806289143 0.1390797794 0.0401971398 0.1133160000 11230797 955859216 1765163008 -0.1617992818 0.0595055521 -0.0845968872 530 1305031247.1796920300 0.1359733194 0.0807333377 0.1390797794 0.0401612925 0.0813150000 11232627 955859216 1765163008 -0.1663691103 0.0541546009 -0.0881804302 531 1305031247.2169430256 0.1333476156 0.0808324229 0.1390797794 0.0401327317 0.0894050000 11234553 955859216 1765163008 -0.1649604589 0.0552771762 -0.0878066421 532 1305031247.2487928867 0.1310033649 0.0809267292 0.1390797794 0.0401087359 0.1228660000 11236351 955859216 1765163008 -0.1635814011 0.0551936477 -0.0865767747 533 1305031247.2794220448 0.1328546554 0.0810241550 0.1390797794 0.0400888827 0.1057580000 11238149 955859216 1765113856 -0.1635249406 0.0529632270 -0.0879786834 534 1305031247.3166429996 0.1360680014 0.0811272333 0.1390797794 0.0401006123 0.1080540000 11240075 955859216 1765163008 -0.1636471897 0.0474602766 -0.0885414556 535 1305031247.3477900028 0.1389057338 0.0812352305 0.1390797794 0.0401696129 0.1076870000 11241905 955859216 1765163008 -0.1638079882 0.0445227474 -0.0884044096 536 1305031247.3786110878 0.1405368298 0.0813458678 0.1405368298 0.0401881677 0.1065650000 11243703 955859216 1765158912 -0.1642948091 0.0412659235 -0.0881784409 537 1305031247.4168620110 0.1378904730 0.0814511651 0.1405368298 0.0402241520 0.1249650000 11245661 955859216 1765163008 -0.1584685594 0.0425111093 -0.0840279311 538 1305031247.4487700462 0.1379353851 0.0815561543 0.1405368298 0.0403574673 0.1091280000 11247491 955859216 1765163008 -0.1566449702 0.0429144539 -0.0820548460 539 1305031247.4802629948 0.1358548403 0.0816568940 0.1405368298 0.0404221222 0.0849080000 11249257 955859216 1765163008 -0.1547375768 0.0446185693 -0.0784071013 540 1305031247.5178461075 0.1399400383 0.0817648257 0.1405368298 0.0405221016 0.0730140000 11251215 955859216 1765163008 -0.1561845243 0.0420185402 -0.0782461166 541 1305031247.5459010601 0.1358125210 0.0818647291 0.1405368298 0.0405999587 0.0820920000 11252949 955859216 1765163008 -0.1495587379 0.0446236767 -0.0730522648 542 1305031247.5779209137 0.1345950365 0.0819620174 0.1405368298 0.0406701391 0.0870130000 11254747 955859216 1765113856 -0.1463929713 0.0453786962 -0.0705864280 543 1305031247.6152799129 0.1341778487 0.0820581792 0.1405368298 0.0408188460 0.1039480000 11256609 955859216 1765146624 -0.1427974701 0.0456092544 -0.0683936998 544 1305031247.6484000683 0.1365558654 0.0821583588 0.1405368298 0.0409574477 0.0720920000 11258439 955859216 1765163008 -0.1442235112 0.0420624055 -0.0690489113 545 1305031247.6835579872 0.1310339421 0.0822480387 0.1405368298 0.0411000220 0.0867980000 11260269 955859216 1765163008 -0.1355240345 0.0446084104 -0.0634320602 546 1305031247.7159609795 0.1278447360 0.0823315492 0.1405368298 0.0412863344 0.1048650000 11262067 955859216 1765163008 -0.1292084306 0.0461173654 -0.0594820417 547 1305031247.7469019890 0.1253525466 0.0824101982 0.1405368298 0.0415276881 0.1081840000 11263865 955859216 1765163008 -0.1242299154 0.0455125719 -0.0564359315 548 1305031247.7822608948 0.1287154108 0.0824946967 0.1405368298 0.0417306495 0.1056860000 11265695 955859216 1765163008 -0.1266120821 0.0364427418 -0.0581285655 549 1305031247.8139829636 0.1308935583 0.0825828549 0.1405368298 0.0420150731 0.1281180000 11267397 955859216 1765163008 -0.1242197081 0.0309005119 -0.0599816740 550 1305031247.8484420776 0.1242452860 0.0826586048 0.1405368298 0.0421751313 0.1267900000 11269291 955859216 1765163008 -0.1086160913 0.0362023041 -0.0526551381 551 1305031247.8820719719 0.1273160726 0.0827396529 0.1405368298 0.0422500841 0.0855910000 11271057 955859216 1766510592 -0.1104210913 0.0306561813 -0.0578358695 552 1305031247.9173319340 0.1227440983 0.0828121247 0.1405368298 0.0422312048 0.0893070000 11272887 955859216 1768542208 -0.1065581664 0.0376845486 -0.0598569661 553 1305031247.9496860504 0.1211124957 0.0828813839 0.1405368298 0.0423023714 0.0695570000 11274621 955859216 1770319872 -0.1035764515 0.0391917937 -0.0615567639 554 1305031247.9861450195 0.1228615344 0.0829535503 0.1405368298 0.0424765350 0.0676160000 11276483 955859216 1771970560 -0.0997755677 0.0338392928 -0.0651448742 555 1305031248.0181560516 0.1208430603 0.0830218197 0.1405368298 0.0424526670 0.0853860000 11278217 955859216 1773621248 -0.0955422893 0.0350598432 -0.0663256645 556 1305031248.0499138832 0.1158015877 0.0830807761 0.1405368298 0.0424778372 0.1072610000 11279983 955859216 1775398912 -0.0861505046 0.0409535244 -0.0631563887 557 1305031248.0857460499 0.1149588004 0.0831380077 0.1405368298 0.0426847464 0.1094070000 11281781 955859216 1777049600 -0.0825948566 0.0374573544 -0.0666067302 558 1305031248.1175789833 0.1132977009 0.0831920574 0.1405368298 0.0427081237 0.0878990000 11283547 955859216 1778700288 -0.0669697747 0.0409431979 -0.0608937852 559 1305031248.1493461132 0.1099682823 0.0832399576 0.1405368298 0.0427185621 0.0858130000 11285313 955859216 1780477952 -0.0668088272 0.0419741608 -0.0637606159 560 1305031248.1848630905 0.1064047888 0.0832813233 0.1405368298 0.0428934468 0.1283850000 11287111 955859216 1782128640 -0.0690684915 0.0405270196 -0.0671942309 561 1305031248.2167689800 0.1043115109 0.0833188103 0.1405368298 0.0429272686 0.1262080000 11288877 955859216 1783906304 -0.0686455593 0.0413903408 -0.0695801526 562 1305031248.2488510609 0.1026878208 0.0833532747 0.1405368298 0.0429509707 0.1081290000 11290611 955859216 1785556992 -0.0682112202 0.0409349054 -0.0708876476 563 1305031248.2847399712 0.0962310284 0.0833761482 0.1405368298 0.0430111714 0.0871300000 11292473 955859216 1787207680 -0.0595080294 0.0512153171 -0.0649990886 564 1305031248.3161809444 0.0929169208 0.0833930645 0.1405368298 0.0430622841 0.0859530000 11294239 955859216 1786449920 -0.0533566438 0.0590016283 -0.0611755624 565 1305031248.3488430977 0.0956189111 0.0834147031 0.1405368298 0.0431271112 0.0833260000 11295973 955859216 1784696832 -0.0495839939 0.0553395189 -0.0624411069 566 1305031248.3881969452 0.0951693207 0.0834354710 0.1405368298 0.0431325821 0.0856560000 11297867 955859216 1783062528 -0.0463603139 0.0572248772 -0.0617923625 567 1305031248.4155070782 0.0947526395 0.0834554307 0.1405368298 0.0431637211 0.1238680000 11299569 955859216 1781149696 -0.0439254120 0.0599315390 -0.0615219437 568 1305031248.4482519627 0.0953746513 0.0834764153 0.1405368298 0.0431790713 0.1212610000 11301335 955859216 1782923264 -0.0419058688 0.0612866245 -0.0627769679 569 1305031248.4852969646 0.0964319110 0.0834991842 0.1405368298 0.0432173107 0.0773740000 11303165 955859216 1784287232 -0.0388173237 0.0633115098 -0.0636926368 570 1305031248.5154309273 0.0931890681 0.0835161840 0.1405368298 0.0431875572 0.1026440000 11304931 955859216 1786064896 -0.0391862057 0.0718945116 -0.0625894591 571 1305031248.5470030308 0.0908998176 0.0835291150 0.1405368298 0.0432154394 0.1305440000 11306697 955859216 1787715584 -0.0368693657 0.0812603161 -0.0600294992 572 1305031248.5860579014 0.0928674340 0.0835454407 0.1405368298 0.0432628963 0.0858660000 11308559 955859216 1786855424 -0.0311248749 0.0835886225 -0.0602107458 573 1305031248.6180379391 0.0935231298 0.0835628538 0.1405368298 0.0433181298 0.0846880000 11310293 955859216 1785061376 -0.0316575058 0.0849363580 -0.0627474338 574 1305031248.6494390965 0.0945601314 0.0835820128 0.1405368298 0.0433107138 0.0860910000 11312059 955859216 1783795712 -0.0293578394 0.0883715451 -0.0633989722 575 1305031248.6860280037 0.0935943499 0.0835994256 0.1405368298 0.0433391466 0.0863610000 11313921 955859216 1782779904 -0.0238954276 0.1005073488 -0.0569328442 576 1305031248.7199230194 0.0941792950 0.0836177934 0.1405368298 0.0433358442 0.0860140000 11315687 955859216 1781764096 -0.0193517152 0.1094301790 -0.0528431199 577 1305031248.7498369217 0.0974149853 0.0836417054 0.1405368298 0.0433864499 0.0859230000 11317421 955859216 1780494336 -0.0117302909 0.1166188866 -0.0470189974 578 1305031248.7856750488 0.0996997952 0.0836694875 0.1405368298 0.0434296077 0.0919960000 11319251 955859216 1779351552 -0.0054353648 0.1210572273 -0.0447795875 579 1305031248.8181409836 0.1001028940 0.0836978699 0.1405368298 0.0434013976 0.0948430000 11321017 955859216 1777831936 -0.0011004471 0.1335475892 -0.0368343517 580 1305031248.8496789932 0.0977776051 0.0837221453 0.1405368298 0.0434489759 0.0886290000 11322783 955859216 1776975872 0.0004772861 0.1333580166 -0.0389989428 581 1305031248.8855929375 0.0941132605 0.0837400302 0.1405368298 0.0434790506 0.1277350000 11324613 955859216 1776087040 0.0022089630 0.1336083114 -0.0406985953 582 1305031248.9178819656 0.0897812247 0.0837504103 0.1405368298 0.0434637288 0.0856550000 11326379 955859216 1775198208 0.0019128715 0.1345662028 -0.0412224196 583 1305031248.9526810646 0.0853192434 0.0837531012 0.1405368298 0.0434834602 0.0887100000 11328209 955859216 1774419968 0.0014948882 0.1371460557 -0.0422087535 584 1305031248.9845540524 0.0778809786 0.0837430462 0.1405368298 0.0434668127 0.1074270000 11329975 955859216 1773019136 -0.0030153994 0.1485900879 -0.0393014662 585 1305031249.0169510841 0.0741351470 0.0837266225 0.1405368298 0.0434696073 0.0855030000 11331741 955859216 1772150784 -0.0043102535 0.1483154446 -0.0391887240 586 1305031249.0523660183 0.0704507753 0.0837039674 0.1405368298 0.0434489399 0.0870740000 11333571 955859216 1771261952 -0.0055207200 0.1492510140 -0.0370894745 587 1305031249.0845029354 0.0690835118 0.0836790604 0.1405368298 0.0434272579 0.1059040000 11335337 955859216 1770373120 -0.0047262162 0.1522845626 -0.0321848877 588 1305031249.1168839931 0.0666872039 0.0836501626 0.1405368298 0.0433928077 0.0874260000 11337103 955859216 1769467904 -0.0064224601 0.1520362943 -0.0297355503 589 1305031249.1534469128 0.0639622509 0.0836167367 0.1405368298 0.0433732790 0.1076900000 11338933 955859216 1768595456 -0.0128007494 0.1596303284 -0.0248837546 590 1305031249.1847391129 0.0625409409 0.0835810150 0.1405368298 0.0433493851 0.0858680000 11340699 955859216 1768701952 -0.0129262302 0.1579785943 -0.0213049911 591 1305031249.2168650627 0.0622875690 0.0835449854 0.1405368298 0.0433184598 0.1090480000 11342465 955859216 1766670336 -0.0121778622 0.1562438607 -0.0186586920 592 1305031249.2532238960 0.0625016019 0.0835094392 0.1405368298 0.0432938031 0.0845540000 11344295 955859216 1765801984 -0.0114527429 0.1565242857 -0.0142971259 593 1305031249.2848041058 0.0662956983 0.0834804110 0.1405368298 0.0432704958 0.0759080000 11346029 955859216 1767161856 -0.0054396912 0.1574078798 -0.0091040470 594 1305031249.3174340725 0.0657237321 0.0834505176 0.1405368298 0.0432447608 0.0929480000 11347827 955859216 1766572032 -0.0060412213 0.1573670506 -0.0066432767 595 1305031249.3527359962 0.0649125054 0.0834193612 0.1405368298 0.0432117698 0.0868870000 11349625 955859216 1766273024 -0.0068786833 0.1577941775 -0.0037600398 596 1305031249.3847539425 0.0666841269 0.0833912820 0.1405368298 0.0431890541 0.0872330000 11351391 955859216 1765892096 -0.0056619458 0.1549073011 -0.0042073391 597 1305031249.4178340435 0.0686884746 0.0833666542 0.1405368298 0.0432175004 0.1058520000 11353157 955859216 1765117952 -0.0041978750 0.1529370099 -0.0041891746 598 1305031249.4537220001 0.0704225227 0.0833450085 0.1405368298 0.0432453497 0.1266330000 11354987 955859216 1765146624 -0.0048158411 0.1496475339 -0.0050004981 599 1305031249.4859149456 0.0712366030 0.0833247941 0.1405368298 0.0432772910 0.1276280000 11356753 955859216 1765146624 -0.0050657354 0.1448513418 -0.0069316328 600 1305031249.5177340508 0.0707490221 0.0833038345 0.1405368298 0.0432827034 0.1282130000 11358519 955859216 1765163008 -0.0082070716 0.1369147450 -0.0140842646 601 1305031249.5543251038 0.0735612437 0.0832876238 0.1405368298 0.0433750832 0.0869260000 11360349 955859216 1766526976 -0.0070143924 0.1278320998 -0.0191073250 602 1305031249.5859050751 0.0749402791 0.0832737578 0.1405368298 0.0434775815 0.0865360000 11362083 955859216 1768415232 -0.0074583311 0.1236393973 -0.0210853666 603 1305031249.6180789471 0.0727549791 0.0832563137 0.1405368298 0.0435045119 0.1082470000 11363849 955859216 1770065920 -0.0145354327 0.1134923026 -0.0291229263 604 1305031249.6542129517 0.0750155896 0.0832426702 0.1405368298 0.0437258189 0.1259760000 11365647 955859216 1771843584 -0.0131334066 0.1108190864 -0.0293837003 605 1305031249.6856739521 0.0701770633 0.0832210741 0.1405368298 0.0438376197 0.1295340000 11367413 955859216 1773494272 -0.0255654901 0.1086911485 -0.0359488130 606 1305031249.7177898884 0.0669203624 0.0831941753 0.1405368298 0.0439082498 0.1045630000 11369179 955859216 1775271936 -0.0349589214 0.1010397896 -0.0413240157 607 1305031249.7539620399 0.0696361437 0.0831718391 0.1405368298 0.0439839276 0.0752950000 11370977 955859216 1776922624 -0.0338777490 0.0999472886 -0.0413128920 608 1305031249.7854170799 0.0683034062 0.0831473845 0.1405368298 0.0440400150 0.0905990000 11372711 955859216 1778573312 -0.0469201766 0.0968794674 -0.0481395312 609 1305031249.8186020851 0.0708244592 0.0831271498 0.1405368298 0.0440513491 0.1311440000 11374541 955859216 1780350976 -0.0509615950 0.0910819396 -0.0515299290 610 1305031249.8537468910 0.0723407045 0.0831094671 0.1405368298 0.0441697078 0.1282870000 11376307 955859216 1782001664 -0.0533582978 0.0901320428 -0.0532641038 611 1305031249.8855249882 0.0739201456 0.0830944273 0.1405368298 0.0441883856 0.1303460000 11378073 955859216 1783779328 -0.0610930286 0.0874422640 -0.0569537804 612 1305031249.9170649052 0.0763465464 0.0830834013 0.1405368298 0.0441910736 0.1277620000 11379871 955859216 1785438208 -0.0641381294 0.0809322000 -0.0595446080 613 1305031249.9533979893 0.0799602047 0.0830783064 0.1405368298 0.0441875031 0.1063830000 11381669 955859216 1787088896 -0.0674942508 0.0728393868 -0.0629260689 614 1305031249.9851789474 0.0817044005 0.0830760688 0.1405368298 0.0441844110 0.0831110000 11383435 955859216 1786331136 -0.0693676695 0.0704692975 -0.0638317615 615 1305031250.0164399147 0.0835899934 0.0830769044 0.1405368298 0.0441689439 0.0864630000 11385201 955859216 1785245696 -0.0711344108 0.0679928139 -0.0648080036 616 1305031250.0531940460 0.0882397592 0.0830852857 0.1405368298 0.0442328496 0.0856580000 11387031 955859216 1783836672 -0.0759360790 0.0593326725 -0.0681263581 617 1305031250.0845069885 0.0903584883 0.0830970737 0.1405368298 0.0443002897 0.1046640000 11388765 955859216 1782050816 -0.0805243403 0.0572433174 -0.0690296069 618 1305031250.1208500862 0.0920527503 0.0831115651 0.1405368298 0.0443844816 0.1256110000 11390627 955859216 1783676928 -0.0836401582 0.0571262650 -0.0684697405 619 1305031250.1532480717 0.0941416472 0.0831293843 0.1405368298 0.0446366070 0.0870940000 11392361 955859216 1785057280 -0.0895248279 0.0568141043 -0.0670966133 620 1305031250.1853280067 0.0961231142 0.0831503419 0.1405368298 0.0446450555 0.0879480000 11394095 955859216 1786707968 -0.0917836949 0.0524493605 -0.0660393164 621 1305031250.2214460373 0.0994648337 0.0831766132 0.1405368298 0.0446471790 0.1103940000 11395957 955859216 1785733120 -0.0949642733 0.0463746823 -0.0662301406 622 1305031250.2537350655 0.1011638343 0.0832055316 0.1405368298 0.0447421129 0.1231240000 11397723 955859216 1787088896 -0.0966013893 0.0421903506 -0.0638378635 623 1305031250.2852239609 0.1034889668 0.0832380892 0.1405368298 0.0447588758 0.1134940000 11399457 955859216 1784946688 -0.1006659791 0.0370425135 -0.0632309690 624 1305031250.3208620548 0.1063525900 0.0832751317 0.1405368298 0.0447833398 0.0999260000 11401255 955859216 1784094720 -0.1032968238 0.0334313028 -0.0629456416 625 1305031250.3517000675 0.1091794595 0.0833165786 0.1405368298 0.0447953096 0.1132550000 11402989 955859216 1783058432 -0.1069393978 0.0299789142 -0.0632711649 626 1305031250.3851490021 0.1131731421 0.0833642728 0.1405368298 0.0448106646 0.0809300000 11404755 955859216 1782190080 -0.1110134199 0.0289137308 -0.0641630813 627 1305031250.4215359688 0.1168218181 0.0834176341 0.1405368298 0.0448216021 0.0918430000 11406617 955859216 1781153792 -0.1163954735 0.0269512646 -0.0653534532 628 1305031250.4540181160 0.1177694947 0.0834723346 0.1405368298 0.0449039624 0.0815000000 11408447 955859216 1780137984 -0.1199673265 0.0289423093 -0.0636577085 629 1305031250.4856131077 0.1179637909 0.0835271699 0.1405368298 0.0449037392 0.1058330000 11410181 955859216 1779269632 -0.1231648996 0.0300602559 -0.0614112653 630 1305031250.5215380192 0.1237630248 0.0835910364 0.1405368298 0.0448820144 0.1281290000 11412043 955859216 1778380800 -0.1321379393 0.0261602234 -0.0636418834 631 1305031250.5536580086 0.1255581975 0.0836575454 0.1405368298 0.0448696385 0.0694860000 11413873 955859216 1777344512 -0.1352796704 0.0274263397 -0.0620187931 632 1305031250.5853788853 0.1254372001 0.0837236524 0.1405368298 0.0448588922 0.0856750000 11415639 955859216 1776476160 -0.1382423341 0.0286877118 -0.0598885193 633 1305031250.6213030815 0.1264856756 0.0837912069 0.1405368298 0.0448406863 0.1392320000 11417501 955859216 1775697920 -0.1414113194 0.0301943105 -0.0587587357 634 1305031250.6535439491 0.1296904832 0.0838636033 0.1405368298 0.0448596908 0.0913190000 11419363 955859216 1774825472 -0.1455161422 0.0306008346 -0.0584734082 635 1305031250.6852970123 0.1292897314 0.0839351405 0.1405368298 0.0448836431 0.0697170000 11421129 955859216 1773936640 -0.1479862928 0.0330896862 -0.0558656231 636 1305031250.7216401100 0.1289592534 0.0840059331 0.1405368298 0.0448617105 0.0844400000 11422991 955859216 1773047808 -0.1507066637 0.0357032865 -0.0538054965 637 1305031250.7534279823 0.1365459859 0.0840884136 0.1405368298 0.0448318516 0.0885440000 11424789 955859216 1772158976 -0.1600289196 0.0323019996 -0.0562799238 638 1305031250.7853651047 0.1356007159 0.0841691539 0.1405368298 0.0448063772 0.0855820000 11426587 955859216 1771270144 -0.1604443491 0.0344273448 -0.0540981516 639 1305031250.8217930794 0.1338217109 0.0842468574 0.1405368298 0.0447746993 0.1083350000 11428513 955859216 1770381312 -0.1606594175 0.0360814855 -0.0517451353 640 1305031250.8538279533 0.1328095496 0.0843227366 0.1405368298 0.0447429572 0.1146460000 11430343 955859216 1769476096 -0.1605417281 0.0368602164 -0.0507300496 641 1305031250.8820140362 0.1319060624 0.0843969696 0.1405368298 0.0447094413 0.0804290000 11432077 955859216 1768714240 -0.1590615362 0.0373136252 -0.0498575866 642 1305031250.9217998981 0.1313899904 0.0844701674 0.1405368298 0.0446776390 0.0831490000 11434003 955859216 1770090496 -0.1582013816 0.0382350497 -0.0502006672 643 1305031250.9535419941 0.1317591071 0.0845437116 0.1405368298 0.0446569065 0.1092440000 11435833 955859216 1767206912 -0.1591756940 0.0380345210 -0.0518650450 644 1305031250.9853079319 0.1315575838 0.0846167145 0.1405368298 0.0446262343 0.0849410000 11437599 955859216 1766318080 -0.1589698493 0.0366395265 -0.0519818328 645 1305031251.0214879513 0.1318341196 0.0846899198 0.1405368298 0.0446046050 0.0868430000 11439461 955859216 1765429248 -0.1581547856 0.0356749445 -0.0531076752 646 1305031251.0534679890 0.1310249716 0.0847616459 0.1405368298 0.0446093008 0.1128730000 11441259 955859216 1765167104 -0.1573551297 0.0336699300 -0.0540459268 647 1305031251.0851860046 0.1305402070 0.0848324010 0.1405368298 0.0446079672 0.0824390000 11443057 955859216 1765060608 -0.1561256647 0.0306950212 -0.0553008504 648 1305031251.1214449406 0.1313790977 0.0849042324 0.1405368298 0.0446083317 0.0853340000 11444919 955859216 1765060608 -0.1543321013 0.0271287728 -0.0576747879 649 1305031251.1537809372 0.1314316690 0.0849759233 0.1405368298 0.0447052678 0.1080550000 11446749 955859216 1765122048 -0.1526264250 0.0234737694 -0.0609727986 650 1305031251.1851599216 0.1321801096 0.0850485451 0.1405368298 0.0447325313 0.0865770000 11448515 955859216 1765040128 -0.1505737156 0.0183955170 -0.0633843094 651 1305031251.2204658985 0.1253859848 0.0851105074 0.1405368298 0.0447457572 0.0861070000 11450345 955859216 1765044224 -0.1382441968 0.0187787823 -0.0607695878 652 1305031251.2524240017 0.1268577129 0.0851745369 0.1405368298 0.0448034933 0.0853860000 11452111 955859216 1765044224 -0.1363473386 0.0148515897 -0.0645618290 653 1305031251.2844820023 0.1280154735 0.0852401432 0.1405368298 0.0450055597 0.0859640000 11453909 955859216 1765060608 -0.1327915341 0.0100962222 -0.0680857003 654 1305031251.3190040588 0.1209832430 0.0852947963 0.1405368298 0.0450801997 0.1255840000 11455739 955859216 1765060608 -0.1181697398 0.0122013893 -0.0640840977 655 1305031251.3532440662 0.1219056025 0.0853506906 0.1405368298 0.0451775901 0.0705690000 11457505 955859216 1765060608 -0.1155043691 0.0074020312 -0.0665740818 656 1305031251.3870069981 0.1125638634 0.0853921741 0.1405368298 0.0452142397 0.0877090000 11459303 955859216 1765154816 -0.1010113806 0.0151900528 -0.0598354079 657 1305031251.4210500717 0.1154933125 0.0854379902 0.1405368298 0.0453026575 0.0841790000 11461101 955859216 1765040128 -0.0981927440 0.0093747117 -0.0626855791 658 1305031251.4496629238 0.1106844693 0.0854763587 0.1405368298 0.0453619718 0.1056430000 11462803 955859216 1765044224 -0.0875228792 0.0119506679 -0.0578926951 659 1305031251.4890139103 0.1065134630 0.0855082814 0.1405368298 0.0454507253 0.1449460000 11464665 955859216 1765027840 -0.0807595998 0.0141549464 -0.0550935753 660 1305031251.5207729340 0.1065011173 0.0855400888 0.1405368298 0.0455567447 0.1116830000 11466463 955859216 1765163008 -0.0793107972 0.0103938123 -0.0556773357 661 1305031251.5530450344 0.1049985811 0.0855695267 0.1405368298 0.0456668762 0.0874200000 11468229 955859216 1766526976 -0.0746283084 0.0096171973 -0.0548979603 662 1305031251.5887598991 0.0980425477 0.0855883681 0.1405368298 0.0456854725 0.1048250000 11470027 955859216 1768288256 -0.0662903562 0.0182274077 -0.0487410985 663 1305031251.6208739281 0.0979290605 0.0856069816 0.1405368298 0.0457397292 0.0892490000 11471825 955859216 1770065920 -0.0643627420 0.0161818787 -0.0488058962 664 1305031251.6528749466 0.0970264971 0.0856241796 0.1405368298 0.0458160548 0.0877790000 11473591 955859216 1771716608 -0.0599657036 0.0164369233 -0.0479211509 665 1305031251.6897680759 0.0918331891 0.0856335165 0.1405368298 0.0458403648 0.1054480000 11475421 955859216 1773367296 -0.0546291471 0.0237714332 -0.0427214541 666 1305031251.7204608917 0.0909994543 0.0856415734 0.1405368298 0.0459009533 0.0882910000 11477187 955859216 1775144960 -0.0508562475 0.0234227404 -0.0402322710 667 1305031251.7531440258 0.0916498527 0.0856505814 0.1405368298 0.0459878387 0.1473760000 11478953 955859216 1776795648 -0.0452476181 0.0221146308 -0.0387577266 668 1305031251.7892498970 0.0880624503 0.0856541919 0.1405368298 0.0460181532 0.1468070000 11480783 955859216 1778446336 -0.0415412262 0.0289855637 -0.0340758637 669 1305031251.8209791183 0.0876960531 0.0856572441 0.1405368298 0.0460549898 0.0894390000 11482549 955859216 1780224000 -0.0408939980 0.0278144926 -0.0331711173 670 1305031251.8537969589 0.0878402814 0.0856605023 0.1405368298 0.0461510629 0.1058320000 11484315 955859216 1781874688 -0.0314043537 0.0299629960 -0.0262245648 671 1305031251.8896539211 0.0874292329 0.0856631383 0.1405368298 0.0461391834 0.1073800000 11486113 955859216 1783525376 -0.0235942267 0.0368748233 -0.0191743672 672 1305031251.9219300747 0.0836690292 0.0856601709 0.1405368298 0.0461268918 0.1289260000 11487911 955859216 1785303040 -0.0206527580 0.0476137474 -0.0117047327 673 1305031251.9538369179 0.0829721987 0.0856561768 0.1405368298 0.0461402927 0.0882600000 11489645 955859216 1786953728 -0.0193167180 0.0506647453 -0.0089734234 674 1305031251.9898068905 0.0799995884 0.0856477843 0.1405368298 0.0461352348 0.1051780000 11491475 955859216 1784958976 -0.0184827279 0.0574466325 -0.0041496675 675 1305031252.0221600533 0.0798431560 0.0856391848 0.1405368298 0.0461655937 0.0901330000 11493273 955859216 1783939072 -0.0162158776 0.0587643050 -0.0022430187 676 1305031252.0537619591 0.0749132931 0.0856233181 0.1405368298 0.0461791033 0.1046310000 11495039 955859216 1782923264 -0.0143872052 0.0701533630 0.0042259083 677 1305031252.0895619392 0.0719014108 0.0856030494 0.1405368298 0.0462313507 0.0898490000 11496837 955859216 1781796864 -0.0125040840 0.0801318139 0.0086598825 678 1305031252.1221520901 0.0678190738 0.0855768194 0.1405368298 0.0462850105 0.1047490000 11498635 955859216 1780912128 -0.0134624671 0.0863213763 0.0081117246 679 1305031252.1539709568 0.0627233461 0.0855431618 0.1405368298 0.0463917262 0.1244420000 11500337 955859216 1779765248 -0.0133094843 0.0989309996 0.0114844143 680 1305031252.1897890568 0.0540966094 0.0854969169 0.1405368298 0.0463770501 0.1053790000 11502167 955859216 1778733056 -0.0231268164 0.1134086847 0.0088033853 681 1305031252.2220859528 0.0497714765 0.0854444566 0.1405368298 0.0463610454 0.0957760000 11503965 955859216 1777864704 -0.0313350335 0.1248273849 0.0082863998 682 1305031252.2530639172 0.0466840528 0.0853876232 0.1405368298 0.0464550648 0.0991420000 11505731 955859216 1776828416 -0.0301455222 0.1259909719 0.0101786135 683 1305031252.2888779640 0.0453873537 0.0853290576 0.1405368298 0.0465068573 0.1283490000 11507497 955859216 1775812608 -0.0288784541 0.1261342615 0.0103710471 684 1305031252.3206090927 0.0450871028 0.0852702244 0.1405368298 0.0464845730 0.1057860000 11509263 955859216 1774891008 -0.0280382559 0.1284151226 0.0111424075 685 1305031252.3528549671 0.0465302318 0.0852136696 0.1405368298 0.0464835400 0.1081590000 11510997 955859216 1774055424 -0.0220647138 0.1336459816 0.0179597866 686 1305031252.3893189430 0.0460456721 0.0851565734 0.1405368298 0.0464689473 0.0740490000 11512827 955859216 1775415296 -0.0229699854 0.1327203363 0.0158686396 687 1305031252.4217019081 0.0460384376 0.0850996329 0.1405368298 0.0464553334 0.0967040000 11514625 955859216 1777176576 -0.0245025493 0.1334272921 0.0143795218 688 1305031252.4538249969 0.0466264151 0.0850437125 0.1405368298 0.0464320924 0.0891590000 11516391 955859216 1778827264 -0.0239731837 0.1344796717 0.0157750715 689 1305031252.4895589352 0.0471389554 0.0849886984 0.1405368298 0.0464019857 0.1066810000 11518157 955859216 1780604928 -0.0246795677 0.1353207529 0.0164467394 690 1305031252.5221700668 0.0478349067 0.0849348523 0.1405368298 0.0463750153 0.1282760000 11519955 955859216 1782255616 -0.0248904526 0.1351984739 0.0169002526 691 1305031252.5537741184 0.0484556481 0.0848820604 0.1405368298 0.0463492087 0.1468410000 11521721 955859216 1783906304 -0.0262624398 0.1350440383 0.0164064672 692 1305031252.5897459984 0.0479559973 0.0848286990 0.1405368298 0.0463199529 0.1482310000 11523519 955859216 1785683968 -0.0283498019 0.1360975951 0.0163380429 693 1305031252.6221249104 0.0494214855 0.0847776064 0.1405368298 0.0462933533 0.1093290000 11525317 955859216 1787334656 -0.0264066346 0.1372426003 0.0198360533 694 1305031252.6578559875 0.0521218367 0.0847305520 0.1405368298 0.0462754471 0.1223520000 11527115 955859216 1784938496 -0.0248622485 0.1377424151 0.0223173536 695 1305031252.6889979839 0.0541995913 0.0846866225 0.1405368298 0.0462899343 0.0865090000 11528849 955859216 1783939072 -0.0237898026 0.1361273676 0.0244785920 696 1305031252.7216539383 0.0565402806 0.0846461824 0.1405368298 0.0463573794 0.1059540000 11530615 955859216 1782923264 -0.0241729990 0.1337253600 0.0238886420 697 1305031252.7578220367 0.0562497824 0.0846054415 0.1405368298 0.0464719246 0.1452060000 11532477 955859216 1781796864 -0.0279467180 0.1275103539 0.0181367602 698 1305031252.7896919250 0.0576957203 0.0845668889 0.1405368298 0.0465918967 0.1064940000 11534211 955859216 1780912128 -0.0299012195 0.1229987144 0.0124902558 699 1305031252.8224050999 0.0577728450 0.0845285569 0.1405368298 0.0466908419 0.1065040000 11536009 955859216 1779765248 -0.0365988724 0.1202551275 0.0050261710 700 1305031252.8539779186 0.0609553158 0.0844948809 0.1405368298 0.0466845810 0.1306580000 11537711 955859216 1778483200 -0.0341076553 0.1151167229 0.0039313585 701 1305031252.8897290230 0.0630337372 0.0844642658 0.1405368298 0.0467116582 0.0838160000 11539541 955859216 1777610752 -0.0346810073 0.1114876270 0.0014728252 702 1305031252.9206719398 0.0645515993 0.0844359002 0.1405368298 0.0467198551 0.0895170000 11541307 955859216 1776574464 -0.0376885459 0.1066289246 -0.0017813351 703 1305031252.9578649998 0.0662802383 0.0844100742 0.1405368298 0.0467982843 0.0875100000 11543201 955859216 1775706112 -0.0417124070 0.1004148796 -0.0048445319 704 1305031252.9894239902 0.0675985888 0.0843861943 0.1405368298 0.0468518038 0.1049030000 11544903 955859216 1774669824 -0.0505854078 0.0951555595 -0.0106933527 705 1305031253.0196959972 0.0685896724 0.0843637879 0.1405368298 0.0469273107 0.1262960000 11546669 955859216 1773654016 -0.0549092963 0.0915321559 -0.0118811969 706 1305031253.0574259758 0.0730090663 0.0843477047 0.1405368298 0.0469660807 0.1446760000 11548531 955859216 1772785664 -0.0649454370 0.0830047876 -0.0190445762 707 1305031253.0895500183 0.0750161707 0.0843345059 0.1405368298 0.0470030967 0.1302480000 11550265 955859216 1771655168 -0.0653940067 0.0780668557 -0.0201521385 708 1305031253.1197240353 0.0795365050 0.0843277291 0.1405368298 0.0470158679 0.1011770000 11552031 955859216 1770627072 -0.0677464232 0.0718906373 -0.0230893884 709 1305031253.1573839188 0.0864088312 0.0843306643 0.1405368298 0.0470835109 0.1082790000 11553861 955859216 1769590784 -0.0790738910 0.0627181977 -0.0321885012 710 1305031253.1892180443 0.0858773887 0.0843328428 0.1405368298 0.0471125350 0.1058880000 11555595 955859216 1768722432 -0.0823836997 0.0621725619 -0.0312590376 711 1305031253.2180271149 0.0837534815 0.0843320280 0.1405368298 0.0471025268 0.1262140000 11557361 955859216 1767833600 -0.0820210800 0.0628006458 -0.0281297844 712 1305031253.2578470707 0.0851132870 0.0843331252 0.1405368298 0.0470814237 0.1300350000 11559255 955859216 1766944768 -0.0853278190 0.0596062541 -0.0287499428 713 1305031253.2897419930 0.0854771584 0.0843347298 0.1405368298 0.0470507184 0.0862080000 11560989 955859216 1768304640 -0.0830035061 0.0563763343 -0.0264426917 714 1305031253.3220069408 0.0854991078 0.0843363605 0.1405368298 0.0470266681 0.1065950000 11562787 955859216 1770065920 -0.0778833926 0.0530827120 -0.0234855544 715 1305031253.3578300476 0.0866700336 0.0843396244 0.1405368298 0.0469987133 0.1086790000 11564585 955859216 1771843584 -0.0723142773 0.0505399667 -0.0212261770 716 1305031253.3880970478 0.0856191814 0.0843414115 0.1405368298 0.0469663699 0.0865050000 11566319 955859216 1773494272 -0.0712555200 0.0510515720 -0.0191422570 717 1305031253.4213519096 0.0859614313 0.0843436710 0.1405368298 0.0469350434 0.0886340000 11568117 955859216 1775271936 -0.0699005798 0.0508146696 -0.0179915465 718 1305031253.4579629898 0.0861030519 0.0843461214 0.1405368298 0.0469044875 0.0867530000 11569947 955859216 1776922624 -0.0696426556 0.0519458801 -0.0169628542 719 1305031253.4896900654 0.0852488875 0.0843473769 0.1405368298 0.0468723781 0.0880020000 11571713 955859216 1778573312 -0.0724841505 0.0535387807 -0.0169502012 720 1305031253.5207340717 0.0862315968 0.0843499939 0.1405368298 0.0468418359 0.0871710000 11573479 955859216 1780350976 -0.0724979565 0.0526522584 -0.0172138177 721 1305031253.5578539371 0.0872845128 0.0843540640 0.1405368298 0.0468113739 0.0869520000 11575309 955859216 1782001664 -0.0746444836 0.0525503904 -0.0179031473 722 1305031253.5898048878 0.0858149976 0.0843560874 0.1405368298 0.0467845971 0.1058800000 11577075 955859216 1783652352 -0.0829185843 0.0561053604 -0.0195542295 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 06:13:52 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 nan 0.0778270000 9399065 955859216 1771368448 -0.0000000000 0.0000000000 -0.0000000000 2 1305031102.2112140656 0.0217163358 0.0235575829 0.0253988300 0.0240789484 0.1040690000 10056943 955859216 1767469056 -0.0023057188 0.0007948904 0.0125143249 3 1305031102.2432110310 0.0218869653 0.0230007103 0.0253988300 0.0192105562 0.0813910000 10059033 955859216 1769082880 -0.0037555362 0.0053054742 0.0258695055 4 1305031102.2753260136 0.0166602228 0.0214155884 0.0253988300 0.0157436866 0.0857050000 10061127 955859216 1768476672 -0.0044986624 0.0041056862 0.0388874039 5 1305031102.3112668991 0.0125689600 0.0196462628 0.0253988300 0.0141430064 0.0555690000 10063277 955859216 1767989248 -0.0033507748 0.0037889318 0.0516047254 6 1305031102.3432331085 0.0089124609 0.0178572958 0.0253988300 0.0148728411 0.0978640000 10065699 955859216 1767096320 -0.0042445916 0.0023637896 0.0636266321 7 1305031102.3753290176 0.0087025641 0.0165494770 0.0253988300 0.0137474957 0.0699340000 10067433 955859216 1766338560 -0.0045749177 0.0031395825 0.0755108595 8 1305031102.4112579823 0.0069137691 0.0153450135 0.0253988300 0.0147529752 0.0758420000 10069295 955859216 1764655104 -0.0065156580 0.0048665055 0.0872651413 9 1305031102.4432709217 0.0075910469 0.0144834616 0.0253988300 0.0167567272 0.0770260000 10071701 955859216 1765060608 -0.0082676969 0.0075824326 0.0996247455 10 1305031102.4753179550 0.0111135747 0.0141464729 0.0253988300 0.0160541025 0.0669180000 10074747 955859216 1764184064 -0.0071157557 0.0112032387 0.1126657799 11 1305031102.5112190247 0.0133435437 0.0140734794 0.0253988300 0.0161391015 0.0544100000 10076577 955859216 1764687872 -0.0073608062 0.0107506867 0.1251640469 12 1305031102.5432200432 0.0163709521 0.0142649354 0.0253988300 0.0153912958 0.0819240000 10078375 955859216 1764892672 -0.0085299658 0.0107820062 0.1370540112 13 1305031102.5752859116 0.0188265778 0.0146158310 0.0253988300 0.0158701001 0.0875060000 10080109 955859216 1765068800 -0.0114118708 0.0102430070 0.1486853808 14 1305031102.6112329960 0.0235444605 0.0152535903 0.0253988300 0.0167522403 0.0580580000 10081939 955859216 1765068800 -0.0129834432 0.0076751029 0.1597731560 15 1305031102.6432650089 0.0261454843 0.0159797165 0.0261454843 0.0169535238 0.0867160000 10083705 955859216 1765068800 -0.0159860570 0.0083160019 0.1706590205 16 1305031102.6752851009 0.0239375550 0.0164770814 0.0261454843 0.0170160787 0.0794060000 10085471 955859216 1765068800 -0.0179017056 0.0152708413 0.1823408604 17 1305031102.7112629414 0.0265389662 0.0170689570 0.0265389662 0.0168146568 0.0698590000 10088581 955859216 1765068800 -0.0183671825 0.0179016106 0.1947541237 18 1305031102.7432339191 0.0301277675 0.0177944465 0.0301277675 0.0164356704 0.0828090000 10093003 955859216 1765068800 -0.0191902500 0.0194283482 0.2075121999 19 1305031102.7754719257 0.0298178848 0.0184272590 0.0301277675 0.0165069468 0.0864810000 10094737 955859216 1765068800 -0.0187081899 0.0254294463 0.2203724235 20 1305031102.8112320900 0.0337676406 0.0191942781 0.0337676406 0.0161370775 0.0857930000 10096567 955859216 1765068800 -0.0199204832 0.0273364838 0.2330048680 21 1305031102.8432900906 0.0353407599 0.0199631582 0.0353407599 0.0157383984 0.0556040000 10098365 955859216 1765068800 -0.0219802111 0.0307062417 0.2455423772 22 1305031102.8753631115 0.0383023173 0.0207967563 0.0383023173 0.0154332382 0.0732670000 10100099 955859216 1765019648 -0.0247151051 0.0325025842 0.2572779059 23 1305031102.9111850262 0.0410987660 0.0216794524 0.0410987660 0.0151304061 0.0603640000 10101929 955859216 1765179392 -0.0272428785 0.0351275131 0.2687968910 24 1305031102.9432289600 0.0426365957 0.0225526667 0.0426365957 0.0152249305 0.0830970000 10103727 955859216 1765068800 -0.0292200670 0.0386310518 0.2801075578 25 1305031102.9752030373 0.0453521833 0.0234646474 0.0453521833 0.0161974450 0.0664030000 10105429 955859216 1766543360 -0.0328826457 0.0411657281 0.2913644016 26 1305031103.0112149715 0.0483128056 0.0244203458 0.0483128056 0.0158849207 0.0506900000 10107291 955859216 1766178816 -0.0335730128 0.0441906601 0.3029495776 27 1305031103.0432269573 0.0512440205 0.0254138152 0.0512440205 0.0155895103 0.0465700000 10109089 955859216 1765191680 -0.0334136412 0.0471086577 0.3143700957 28 1305031103.0753190517 0.0541915148 0.0264415902 0.0541915148 0.0159666856 0.0666050000 10110823 955859216 1765081088 -0.0323097669 0.0496917553 0.3251510262 29 1305031103.1112399101 0.0580528714 0.0275316344 0.0580528714 0.0159010348 0.1006820000 10112653 955859216 1765068800 -0.0319502875 0.0512614399 0.3349372149 30 1305031103.1433179379 0.0572046638 0.0285207353 0.0580528714 0.0156606558 0.0627070000 10114419 955859216 1765068800 -0.0317782201 0.0575084276 0.3443081975 31 1305031103.1754519939 0.0596277751 0.0295241882 0.0596277751 0.0154195464 0.0598260000 10116185 955859216 1765068800 -0.0325591452 0.0595756657 0.3532649875 32 1305031103.2112200260 0.0603772290 0.0304883458 0.0603772290 0.0161057213 0.0572170000 10118015 955859216 1765068800 -0.0330611020 0.0643604919 0.3620288372 33 1305031103.2432160378 0.0616985187 0.0314341086 0.0616985187 0.0158924293 0.0710810000 10122373 955859216 1766543360 -0.0329630822 0.0682063103 0.3710338473 34 1305031103.2753698826 0.0645286962 0.0324074788 0.0645286962 0.0160638250 0.0600030000 10129355 955859216 1766211584 -0.0328799002 0.0698044822 0.3792884946 35 1305031103.3112099171 0.0699867457 0.0334811721 0.0699867457 0.0166300009 0.0732180000 10131185 955859216 1764552704 -0.0339858867 0.0672911704 0.3866486251 36 1305031103.3432230949 0.0762725398 0.0346698212 0.0762725398 0.0173760157 0.0901130000 10132983 955859216 1765441536 -0.0338167325 0.0623866357 0.3917614222 37 1305031103.3753271103 0.0769597813 0.0358127931 0.0769597813 0.0173502228 0.0857300000 10134717 955859216 1764798464 -0.0325149000 0.0623947158 0.3943508863 38 1305031103.4112598896 0.0775328875 0.0369106904 0.0775328875 0.0172756817 0.0744770000 10136547 955859216 1766416384 -0.0310780890 0.0614149459 0.3950715065 39 1305031103.4432799816 0.0795016661 0.0380027667 0.0795016661 0.0171849210 0.0625860000 10138345 955859216 1766670336 -0.0316766910 0.0579429530 0.3937094212 40 1305031103.4752740860 0.0805332586 0.0390660290 0.0805332586 0.0169896306 0.0618180000 10140079 955859216 1766227968 -0.0316893831 0.0543966517 0.3908644617 41 1305031103.5113329887 0.0843580812 0.0401707132 0.0843580812 0.0169719187 0.0784830000 10141909 955859216 1765584896 -0.0295004081 0.0473159999 0.3869663179 42 1305031103.5434439182 0.0841163695 0.0412170383 0.0843580812 0.0168975504 0.0769410000 10143707 955859216 1765068800 -0.0293477178 0.0425358415 0.3802960217 43 1305031103.5754740238 0.0832312852 0.0421941138 0.0843580812 0.0167458757 0.0560040000 10145441 955859216 1765068800 -0.0287670400 0.0377179086 0.3721604347 44 1305031103.6112229824 0.0809803158 0.0430756184 0.0843580812 0.0166599667 0.0769850000 10147271 955859216 1765068800 -0.0275087077 0.0347001925 0.3629992604 45 1305031103.6434450150 0.0791885257 0.0438781275 0.0843580812 0.0164785735 0.0700600000 10149069 955859216 1765068800 -0.0264301058 0.0302136019 0.3532450795 46 1305031103.6755230427 0.0770674497 0.0445996345 0.0843580812 0.0163539243 0.0549050000 10150803 955859216 1766543360 -0.0242160354 0.0260921083 0.3428219557 47 1305031103.7116100788 0.0747929439 0.0452420453 0.0843580812 0.0161947890 0.0491390000 10152633 955859216 1766322176 -0.0218297783 0.0223163124 0.3316771388 48 1305031103.7433259487 0.0722460523 0.0458046288 0.0843580812 0.0160736557 0.0493040000 10154431 955859216 1765445632 -0.0195092726 0.0181606021 0.3199562430 49 1305031103.7753419876 0.0699896887 0.0462982014 0.0843580812 0.0159065038 0.0472320000 10156165 955859216 1765081088 -0.0184489395 0.0126590570 0.3073991537 50 1305031103.8112421036 0.0666717738 0.0467056729 0.0843580812 0.0161652266 0.0618370000 10157995 955859216 1765085184 -0.0174093191 0.0103846239 0.2941653728 51 1305031103.8432509899 0.0629437417 0.0470240664 0.0843580812 0.0161888222 0.0732110000 10159793 955859216 1765068800 -0.0156507511 0.0082171652 0.2813550532 52 1305031103.8753609657 0.0604497790 0.0472822532 0.0843580812 0.0161739785 0.0681250000 10161527 955859216 1765085184 -0.0159446076 0.0048937872 0.2690971792 53 1305031103.9112210274 0.0644332990 0.0476058578 0.0843580812 0.0172093398 0.0621790000 10163357 955859216 1765068800 -0.0159081593 -0.0060980916 0.2567050755 54 1305031103.9432110786 0.0646125078 0.0479207958 0.0843580812 0.0171133017 0.0619410000 10165155 955859216 1766670336 -0.0139509365 -0.0137277413 0.2432539016 55 1305031103.9753730297 0.0611767843 0.0481618137 0.0843580812 0.0170817055 0.0495960000 10166921 955859216 1766072320 -0.0130862081 -0.0169770177 0.2288467139 56 1305031104.0112318993 0.0606534667 0.0483848790 0.0843580812 0.0172888101 0.0564480000 10168719 955859216 1765191680 -0.0109541789 -0.0223616660 0.2144789249 57 1305031104.0432488918 0.0579930656 0.0485534437 0.0843580812 0.0172460168 0.0643920000 10170517 955859216 1765085184 -0.0079441005 -0.0279757604 0.1995955110 58 1305031104.0754249096 0.0522636995 0.0486174136 0.0843580812 0.0172718942 0.1036330000 10172251 955859216 1765068800 -0.0053895204 -0.0290095676 0.1839393079 59 1305031104.1112349033 0.0477019064 0.0486018965 0.0843580812 0.0171878791 0.0598790000 10174081 955859216 1765068800 -0.0059456709 -0.0298124943 0.1689519435 60 1305031104.1432299614 0.0440557189 0.0485261269 0.0843580812 0.0171369237 0.1003610000 10175879 955859216 1765068800 -0.0059644603 -0.0349251889 0.1544946879 61 1305031104.1754240990 0.0401996113 0.0483896266 0.0843580812 0.0170885796 0.0786720000 10177613 955859216 1765068800 -0.0061133183 -0.0383607000 0.1403337568 62 1305031104.2112829685 0.0390015841 0.0482382066 0.0843580812 0.0169943548 0.0827560000 10179443 955859216 1765068800 -0.0059870207 -0.0408138447 0.1267053634 63 1305031104.2431960106 0.0354503803 0.0480352252 0.0843580812 0.0168775275 0.0833740000 10181241 955859216 1765068800 -0.0054008742 -0.0440081321 0.1132616103 64 1305031104.2755460739 0.0320924595 0.0477861195 0.0843580812 0.0167533432 0.0830970000 10182975 955859216 1765068800 -0.0035539218 -0.0459876880 0.1003703475 65 1305031104.3112189770 0.0311004575 0.0475294170 0.0843580812 0.0166671027 0.0810240000 10189925 955859216 1765068800 -0.0023559791 -0.0472386964 0.0876727775 66 1305031104.3433420658 0.0276549347 0.0472282885 0.0843580812 0.0165929572 0.0830310000 10202219 955859216 1765068800 -0.0005749764 -0.0477959290 0.0755094588 67 1305031104.3758370876 0.0267700162 0.0469229411 0.0843580812 0.0165420211 0.0550770000 10203953 955859216 1765068800 0.0010120485 -0.0479277559 0.0637396649 68 1305031104.4115090370 0.0244632009 0.0465926508 0.0843580812 0.0164977211 0.0615670000 10205783 955859216 1765068800 0.0004236409 -0.0480553024 0.0525531024 69 1305031104.4432880878 0.0223842598 0.0462418046 0.0843580812 0.0164336113 0.0591400000 10207549 955859216 1765068800 -0.0007927325 -0.0485333353 0.0420311540 70 1305031104.4754559994 0.0211536232 0.0458834020 0.0843580812 0.0163719399 0.0642670000 10209315 955859216 1766543360 -0.0030109263 -0.0492120124 0.0323425308 71 1305031104.5113289356 0.0234453883 0.0455673736 0.0843580812 0.0164818303 0.0625130000 10211145 955859216 1765937152 -0.0048790285 -0.0510527082 0.0231739469 72 1305031104.5433681011 0.0227860436 0.0452509663 0.0843580812 0.0164690158 0.0589280000 10212943 955859216 1765052416 -0.0042738426 -0.0544427335 0.0135237267 73 1305031104.5753428936 0.0218543429 0.0449304646 0.0843580812 0.0165860856 0.0645090000 10214645 955859216 1765068800 -0.0030502107 -0.0561226010 0.0035220007 74 1305031104.6113359928 0.0239756219 0.0446472910 0.0843580812 0.0173367140 0.0742730000 10216507 955859216 1765068800 0.0005872509 -0.0595668815 -0.0078674210 75 1305031104.6432430744 0.0215499476 0.0443393265 0.0843580812 0.0173411989 0.0944490000 10218273 955859216 1765019648 0.0049515907 -0.0625989363 -0.0213260818 76 1305031104.6755249500 0.0220377576 0.0440458848 0.0843580812 0.0172342675 0.0989790000 10220039 955859216 1765052416 0.0072493451 -0.0575944334 -0.0354486108 77 1305031104.7112770081 0.0247782823 0.0437956562 0.0843580812 0.0174462629 0.0828750000 10221869 955859216 1766526976 0.0099513279 -0.0553652830 -0.0497360863 78 1305031104.7432799339 0.0290437397 0.0436065290 0.0843580812 0.0173619987 0.0708850000 10223635 955859216 1768464384 0.0122635774 -0.0504428558 -0.0638725236 79 1305031104.7753269672 0.0369435400 0.0435221874 0.0843580812 0.0172819134 0.0879490000 10225369 955859216 1770094592 0.0165403783 -0.0437929220 -0.0759259239 80 1305031104.8114650249 0.0439803079 0.0435279139 0.0843580812 0.0172160575 0.0706860000 10227231 955859216 1771892736 0.0193719324 -0.0379249975 -0.0862305388 81 1305031104.8432579041 0.0519888029 0.0436323693 0.0843580812 0.0171482183 0.0616440000 10228997 955859216 1773543424 0.0240278486 -0.0313235931 -0.0943510011 82 1305031104.8753499985 0.0549283922 0.0437701257 0.0843580812 0.0171951293 0.0704770000 10230763 955859216 1775173632 0.0243385136 -0.0281884000 -0.0995191187 83 1305031104.9115340710 0.0584179573 0.0439466056 0.0843580812 0.0171434869 0.0546930000 10232593 955859216 1776971776 0.0247216318 -0.0239989087 -0.1021823660 84 1305031104.9432621002 0.0620451085 0.0441620640 0.0843580812 0.0170519126 0.0620570000 10234359 955859216 1778622464 0.0257163588 -0.0199213382 -0.1022764295 85 1305031104.9752020836 0.0637280867 0.0443922525 0.0843580812 0.0170633485 0.0914680000 10236125 955859216 1780252672 0.0259648599 -0.0170201920 -0.0995870382 86 1305031105.0112900734 0.0713428855 0.0447056319 0.0843580812 0.0171875863 0.0962310000 10237955 955859216 1782018048 0.0252352227 -0.0068122884 -0.0932125598 87 1305031105.0433731079 0.0720703751 0.0450201692 0.0843580812 0.0171501216 0.0633700000 10239721 955859216 1783701504 0.0233460050 -0.0035104416 -0.0854261145 88 1305031105.0753200054 0.0687930658 0.0452903158 0.0843580812 0.0170877007 0.0601460000 10241487 955859216 1785331712 0.0197694525 -0.0038585030 -0.0761834383 89 1305031105.1112990379 0.0656133145 0.0455186641 0.0843580812 0.0170035620 0.0647750000 10243317 955859216 1787129856 0.0165532120 -0.0041048042 -0.0657307506 90 1305031105.1431059837 0.0598646775 0.0456780642 0.0843580812 0.0169954200 0.0636580000 10245083 955859216 1786236928 0.0114403749 -0.0063490137 -0.0541261621 91 1305031105.1751589775 0.0610420890 0.0458468996 0.0843580812 0.0174718948 0.0654160000 10246849 955859216 1785004032 0.0064271097 -0.0005065980 -0.0391103923 92 1305031105.2112679482 0.0564476289 0.0459621250 0.0843580812 0.0175075395 0.0686100000 10248679 955859216 1784229888 -0.0004863594 -0.0006771593 -0.0231509451 93 1305031105.2432699203 0.0450065620 0.0459518501 0.0843580812 0.0175286338 0.0636900000 10250445 955859216 1783345152 -0.0042461189 -0.0082019866 -0.0088855093 94 1305031105.2752881050 0.0397114158 0.0458854625 0.0843580812 0.0176815873 0.1020150000 10252211 955859216 1782579200 -0.0092486246 -0.0088946074 0.0063766134 95 1305031105.3112900257 0.0329422057 0.0457492177 0.0843580812 0.0176789030 0.0927510000 10254041 955859216 1781800960 -0.0140533233 -0.0107690459 0.0219171066 96 1305031105.3433020115 0.0243174601 0.0455259702 0.0843580812 0.0176203585 0.1021250000 10255807 955859216 1780391936 -0.0159008354 -0.0148143172 0.0369934067 97 1305031105.3753380775 0.0155442087 0.0452168799 0.0843580812 0.0178040592 0.0703410000 10257573 955859216 1781891072 -0.0154855195 -0.0194852650 0.0510068759 98 1305031105.4112861156 0.0111440811 0.0448691983 0.0843580812 0.0178359077 0.0939640000 10259403 955859216 1778499584 -0.0154980086 -0.0197314583 0.0650443137 99 1305031105.4433159828 0.0104713468 0.0445217452 0.0843580812 0.0177489654 0.0738520000 10261169 955859216 1779863552 -0.0175620243 -0.0156156430 0.0792851523 100 1305031105.4752800465 0.0059116334 0.0441356441 0.0843580812 0.0176925519 0.0660790000 10262935 955859216 1779408896 -0.0179842226 -0.0178299341 0.0931643471 101 1305031105.5113320351 0.0056306478 0.0437544065 0.0843580812 0.0176754729 0.0632720000 10264765 955859216 1778253824 -0.0189865585 -0.0165285449 0.1070400551 102 1305031105.5432820320 0.0073464471 0.0433974657 0.0843580812 0.0176173722 0.1015940000 10266531 955859216 1777483776 -0.0191168450 -0.0153658278 0.1209924594 103 1305031105.5754489899 0.0092663569 0.0430660957 0.0843580812 0.0175386989 0.1052600000 10268297 955859216 1776611328 -0.0208406784 -0.0154532874 0.1345181316 104 1305031105.6113779545 0.0114514790 0.0427621090 0.0843580812 0.0174601710 0.0798240000 10270127 955859216 1775833088 -0.0222827401 -0.0138509870 0.1482133120 105 1305031105.6432731152 0.0156582966 0.0425039775 0.0843580812 0.0174329359 0.0765250000 10271893 955859216 1775071232 -0.0232904647 -0.0142900310 0.1620711833 106 1305031105.6751658916 0.0176794771 0.0422697841 0.0843580812 0.0174011279 0.0951240000 10273659 955859216 1774309376 -0.0243661925 -0.0117841531 0.1762181371 107 1305031105.7113089561 0.0204295833 0.0420656701 0.0843580812 0.0174986109 0.0674760000 10275489 955859216 1773547520 -0.0237680003 -0.0091957524 0.1898090988 108 1305031105.7433118820 0.0239961240 0.0418983595 0.0843580812 0.0174288914 0.0627450000 10277255 955859216 1772810240 -0.0244539361 -0.0083704256 0.2035825700 109 1305031105.7753388882 0.0228573289 0.0417236711 0.0843580812 0.0173574398 0.1003930000 10279021 955859216 1772023808 -0.0249475762 -0.0025958279 0.2174154073 110 1305031105.8112831116 0.0271689426 0.0415913554 0.0843580812 0.0172935361 0.0928670000 10280851 955859216 1771388928 -0.0252864398 -0.0012763737 0.2311431915 111 1305031105.8432710171 0.0293121971 0.0414807323 0.0843580812 0.0172176680 0.0632590000 10282617 955859216 1770651648 -0.0259963814 0.0016337755 0.2449365854 112 1305031105.8753368855 0.0303088594 0.0413809835 0.0843580812 0.0171674196 0.0930500000 10284383 955859216 1769865216 -0.0254109837 0.0061681001 0.2584495246 113 1305031105.9112620354 0.0318126194 0.0412963077 0.0843580812 0.0171998406 0.0696000000 10286213 955859216 1769746432 -0.0251751207 0.0121850027 0.2724480927 114 1305031105.9432721138 0.0344881900 0.0412365874 0.0843580812 0.0171387215 0.0887440000 10287979 955859216 1770004480 -0.0243455898 0.0155758196 0.2857016325 115 1305031105.9753289223 0.0358796492 0.0411900053 0.0843580812 0.0171197334 0.1020020000 10289745 955859216 1767071744 -0.0253603086 0.0209083725 0.2985294461 116 1305031106.0112850666 0.0403659157 0.0411829011 0.0843580812 0.0170675610 0.0902190000 10291575 955859216 1766309888 -0.0245838277 0.0242771972 0.3113268316 117 1305031106.0433549881 0.0425697118 0.0411947542 0.0843580812 0.0169965046 0.0699700000 10293373 955859216 1767796736 -0.0252130423 0.0283994917 0.3236002922 118 1305031106.0753300190 0.0460152403 0.0412356057 0.0843580812 0.0169357855 0.0639680000 10295107 955859216 1767309312 -0.0253919661 0.0316085666 0.3356227577 119 1305031106.1113269329 0.0488884412 0.0412999153 0.0843580812 0.0169340497 0.0776920000 10296937 955859216 1766465536 -0.0289961416 0.0360721163 0.3470175862 120 1305031106.1433548927 0.0507161207 0.0413783836 0.0843580812 0.0168703616 0.0580520000 10298735 955859216 1765675008 -0.0296043791 0.0403547958 0.3585243821 121 1305031106.1755340099 0.0559750199 0.0414990170 0.0843580812 0.0168044140 0.0834060000 10300469 955859216 1765048320 -0.0310508404 0.0410903990 0.3694925904 122 1305031106.2112751007 0.0601113811 0.0416515774 0.0843580812 0.0167392602 0.0621420000 10302299 955859216 1765052416 -0.0325470939 0.0429833122 0.3793531358 123 1305031106.2432670593 0.0651953742 0.0418429904 0.0843580812 0.0166752286 0.0522290000 10304097 955859216 1765052416 -0.0339242294 0.0430705510 0.3884104490 124 1305031106.2763850689 0.0673646554 0.0420488102 0.0843580812 0.0166146794 0.1032600000 10305863 955859216 1765052416 -0.0344921611 0.0459008627 0.3960984051 125 1305031106.3112380505 0.0675183237 0.0422525663 0.0843580812 0.0165617787 0.0547610000 10307661 955859216 1765052416 -0.0343057103 0.0499814078 0.4029961228 126 1305031106.3432579041 0.0690401867 0.0424651665 0.0843580812 0.0165847235 0.0672850000 10309459 955859216 1765052416 -0.0341721363 0.0524685606 0.4091732502 127 1305031106.3753879070 0.0688031539 0.0426725522 0.0843580812 0.0166138152 0.0576020000 10311193 955859216 1765052416 -0.0350523405 0.0557033829 0.4137856066 128 1305031106.4113199711 0.0698757619 0.0428850773 0.0843580812 0.0166590995 0.0823230000 10313023 955859216 1765052416 -0.0356385559 0.0565514117 0.4166499674 129 1305031106.4432780743 0.0806387663 0.0431777416 0.0843580812 0.0168379491 0.0626720000 10325029 955859216 1765052416 -0.0368221179 0.0455840044 0.4185374081 130 1305031106.4753448963 0.0812825933 0.0434708558 0.0843580812 0.0168987656 0.0514430000 10347787 955859216 1766526976 -0.0386325829 0.0434171706 0.4162040949 131 1305031106.5111289024 0.0820814595 0.0437655932 0.0843580812 0.0169136808 0.0589550000 10349521 955859216 1766043648 -0.0403262526 0.0400517546 0.4119937420 132 1305031106.5433020592 0.0857079923 0.0440833387 0.0857079923 0.0168775190 0.0758150000 10351319 955859216 1765933056 -0.0394581631 0.0323147252 0.4062043726 133 1305031106.5752820969 0.0840053335 0.0443835041 0.0857079923 0.0168290164 0.0799560000 10353053 955859216 1765531648 -0.0379153416 0.0291686151 0.3976015151 134 1305031106.6111509800 0.0816088393 0.0446613051 0.0857079923 0.0168480458 0.0606630000 10354883 955859216 1765552128 -0.0380746759 0.0266291387 0.3877234459 135 1305031106.6432070732 0.0797576159 0.0449212777 0.0857079923 0.0168232382 0.0731320000 10356681 955859216 1765179392 -0.0379289016 0.0232652854 0.3773941696 136 1305031106.6752789021 0.0812071860 0.0451880859 0.0857079923 0.0167838665 0.0699330000 10358415 955859216 1765068800 -0.0375114307 0.0159734990 0.3662353754 137 1305031106.7115080357 0.0788855553 0.0454340528 0.0857079923 0.0168043379 0.0526770000 10360245 955859216 1765044224 -0.0368911140 0.0136360787 0.3534515798 138 1305031106.7433409691 0.0789747536 0.0456771014 0.0857079923 0.0167988068 0.0641300000 10362043 955859216 1765044224 -0.0361957513 0.0075135273 0.3408173621 139 1305031106.7753899097 0.0776022971 0.0459067790 0.0857079923 0.0167432856 0.0986460000 10363777 955859216 1765044224 -0.0346158408 0.0030187331 0.3272825778 140 1305031106.8112890720 0.0760468841 0.0461220655 0.0857079923 0.0167101455 0.0795010000 10365607 955859216 1765044224 -0.0323592909 -0.0000263117 0.3128820360 141 1305031106.8434159756 0.0731765181 0.0463139411 0.0857079923 0.0166878364 0.0708850000 10367373 955859216 1765044224 -0.0303535238 -0.0029879324 0.2983021140 142 1305031106.8759050369 0.0740210712 0.0465090617 0.0857079923 0.0168329741 0.0757360000 10369139 955859216 1765044224 -0.0298351478 -0.0117269792 0.2829775214 143 1305031106.9112429619 0.0718519092 0.0466862844 0.0857079923 0.0168439422 0.0689080000 10370969 955859216 1765044224 -0.0286848042 -0.0151099600 0.2656084001 144 1305031106.9434390068 0.0650662705 0.0468139232 0.0857079923 0.0168014867 0.0963800000 10372735 955859216 1765044224 -0.0279198438 -0.0154303918 0.2478875816 145 1305031106.9755470753 0.0638563558 0.0469314572 0.0857079923 0.0168052933 0.0781980000 10374501 955859216 1765044224 -0.0291178077 -0.0228531137 0.2305211127 146 1305031107.0115759373 0.0619518496 0.0470343366 0.0857079923 0.0167714327 0.0912560000 10376363 955859216 1764995072 -0.0303620882 -0.0279693678 0.2122186720 147 1305031107.0432810783 0.0525689125 0.0470719868 0.0857079923 0.0167975373 0.0653270000 10378129 955859216 1765044224 -0.0292301010 -0.0245321970 0.1940907836 148 1305031107.0754320621 0.0503699854 0.0470942706 0.0857079923 0.0168399909 0.1167390000 10379863 955859216 1765044224 -0.0304282811 -0.0309122987 0.1777959764 149 1305031107.1112289429 0.0499201603 0.0471132363 0.0857079923 0.0167902737 0.0789440000 10381693 955859216 1766518784 -0.0311883930 -0.0362805463 0.1613505185 150 1305031107.1432600021 0.0437794328 0.0470910109 0.0857079923 0.0167827734 0.0744660000 10383491 955859216 1768456192 -0.0289617926 -0.0358187854 0.1453334838 151 1305031107.1753990650 0.0392358936 0.0470389903 0.0857079923 0.0167369357 0.0731800000 10385225 955859216 1770086400 -0.0280860048 -0.0371997729 0.1305015236 152 1305031107.2113580704 0.0406517945 0.0469969692 0.0857079923 0.0168207488 0.0586190000 10387055 955859216 1771884544 -0.0286829583 -0.0437315591 0.1161169037 153 1305031107.2433779240 0.0365206338 0.0469284965 0.0857079923 0.0167753234 0.0664730000 10388821 955859216 1773535232 -0.0271745250 -0.0467705391 0.1016045138 154 1305031107.2753980160 0.0321456194 0.0468325038 0.0857079923 0.0167335970 0.0582690000 10390587 955859216 1775165440 -0.0248902719 -0.0472782850 0.0877737105 155 1305031107.3112258911 0.0313808098 0.0467328154 0.0857079923 0.0167199771 0.0621360000 10392417 955859216 1776963584 -0.0253394116 -0.0501002222 0.0740537345 156 1305031107.3435089588 0.0280533377 0.0466130752 0.0857079923 0.0167794783 0.0625340000 10394215 955859216 1778614272 -0.0257846992 -0.0538617745 0.0605015084 157 1305031107.3754129410 0.0235819928 0.0464663804 0.0857079923 0.0168341039 0.0825420000 10395949 955859216 1780232192 -0.0244331192 -0.0538491160 0.0478221662 158 1305031107.4112710953 0.0198809281 0.0462981180 0.0857079923 0.0168133547 0.0700460000 10397779 955859216 1782022144 -0.0196017660 -0.0501079820 0.0375563391 159 1305031107.4434189796 0.0172725506 0.0461155673 0.0857079923 0.0167644736 0.0682250000 10399577 955859216 1783672832 -0.0178938471 -0.0485859141 0.0294672064 160 1305031107.4753770828 0.0180086363 0.0459398990 0.0857079923 0.0167231916 0.0590200000 10401343 955859216 1785470976 -0.0161133409 -0.0465572812 0.0237314738 161 1305031107.5113520622 0.0208600387 0.0457841234 0.0857079923 0.0167008334 0.0640130000 10403141 955859216 1787121664 -0.0142140491 -0.0448634252 0.0198272783 162 1305031107.5436050892 0.0243973620 0.0456521064 0.0857079923 0.0167180103 0.0697300000 10404939 955859216 1786228736 -0.0125808520 -0.0409657657 0.0183183420 163 1305031107.5754539967 0.0247579440 0.0455239213 0.0857079923 0.0166925067 0.0728400000 10406673 955859216 1785217024 -0.0100358976 -0.0407681987 0.0177905094 164 1305031107.6112709045 0.0231072754 0.0453872345 0.0857079923 0.0166531194 0.0901300000 10408503 955859216 1784332288 -0.0074390108 -0.0418661684 0.0176742431 165 1305031107.6433229446 0.0230202712 0.0452516771 0.0857079923 0.0166425355 0.0626150000 10410301 955859216 1783570432 -0.0048171701 -0.0379274301 0.0192531478 166 1305031107.6755681038 0.0220809933 0.0451120947 0.0857079923 0.0166135304 0.0924750000 10412035 955859216 1782685696 -0.0038482519 -0.0369300395 0.0209118854 167 1305031107.7113070488 0.0208072364 0.0449665566 0.0857079923 0.0165715523 0.1010330000 10413865 955859216 1781919744 -0.0039548366 -0.0360223204 0.0229349695 168 1305031107.7435379028 0.0208598487 0.0448230643 0.0857079923 0.0165527112 0.1001270000 10415631 955859216 1781157888 -0.0041178097 -0.0332575738 0.0253991205 169 1305031107.7758018970 0.0209348816 0.0446817141 0.0857079923 0.0165110366 0.1163340000 10417397 955859216 1780420608 -0.0053126342 -0.0309979469 0.0278533809 170 1305031107.8115959167 0.0199448634 0.0445362032 0.0857079923 0.0164639074 0.0671890000 10419227 955859216 1781784576 -0.0052810526 -0.0311203785 0.0303699579 171 1305031107.8433320522 0.0193877034 0.0443891360 0.0857079923 0.0164237475 0.0631770000 10420993 955859216 1783672832 -0.0047280937 -0.0303725731 0.0328748450 172 1305031107.8753581047 0.0190090369 0.0442415773 0.0857079923 0.0164029170 0.0613300000 10422759 955859216 1785470976 -0.0041849809 -0.0306437984 0.0348949768 173 1305031107.9115409851 0.0193968844 0.0440979663 0.0857079923 0.0163882725 0.0639090000 10424589 955859216 1787121664 -0.0025651904 -0.0320234746 0.0364643931 174 1305031107.9431219101 0.0213029627 0.0439669605 0.0857079923 0.0163931130 0.0650200000 10426355 955859216 1786355712 -0.0012588390 -0.0322167166 0.0377461649 175 1305031107.9758069515 0.0246246271 0.0438564329 0.0857079923 0.0163888510 0.0681980000 10428121 955859216 1785217024 0.0023104406 -0.0315247923 0.0387417227 176 1305031108.0113201141 0.0276151691 0.0437641530 0.0857079923 0.0163579657 0.0619780000 10429951 955859216 1784332288 0.0065678237 -0.0312742740 0.0401621535 177 1305031108.0434179306 0.0295220744 0.0436836893 0.0857079923 0.0163245542 0.0702450000 10431717 955859216 1785819136 0.0140738022 -0.0272744391 0.0417640954 178 1305031108.0753519535 0.0317665711 0.0436167392 0.0857079923 0.0162913414 0.0676140000 10433451 955859216 1783959552 0.0225052722 -0.0234654751 0.0437429473 179 1305031108.1113779545 0.0408240408 0.0436011375 0.0857079923 0.0162539362 0.0641880000 10435281 955859216 1782710272 0.0269224253 -0.0239781849 0.0458042882 180 1305031108.1433339119 0.0440479182 0.0436036196 0.0857079923 0.0162270358 0.0796020000 10437047 955859216 1781919744 0.0350273512 -0.0222786050 0.0484878570 181 1305031108.1760580540 0.0491873734 0.0436344691 0.0857079923 0.0162732919 0.0913880000 10438813 955859216 1781157888 0.0454794914 -0.0179065019 0.0516845174 182 1305031108.2114748955 0.0522779524 0.0436819608 0.0857079923 0.0162742238 0.0903490000 10440643 955859216 1780396032 0.0541156046 -0.0139519889 0.0559825525 183 1305031108.2433469296 0.0525840111 0.0437306059 0.0857079923 0.0162820356 0.0820560000 10442409 955859216 1779523584 0.0642823353 -0.0173350964 0.0591949262 184 1305031108.2753579617 0.0523972847 0.0437777074 0.0857079923 0.0162405818 0.0834240000 10444175 955859216 1778745344 0.0753383711 -0.0205219444 0.0618735477 185 1305031108.3113319874 0.0577209108 0.0438530760 0.0857079923 0.0163871617 0.0838820000 10446005 955859216 1777983488 0.0844085142 -0.0149386851 0.0656022653 186 1305031108.3432779312 0.0587354936 0.0439330890 0.0857079923 0.0163709335 0.0755270000 10447803 955859216 1777221632 0.0937799960 -0.0122035984 0.0696023479 187 1305031108.3754100800 0.0576001257 0.0440061748 0.0857079923 0.0163431140 0.0770650000 10449537 955859216 1776336896 0.1052514836 -0.0119264126 0.0733093992 188 1305031108.4113609791 0.0599342026 0.0440908984 0.0857079923 0.0163062567 0.1015960000 10451367 955859216 1775534080 0.1171050221 -0.0127255917 0.0768991858 189 1305031108.4436099529 0.0574256778 0.0441614527 0.0857079923 0.0163169525 0.0732260000 10453165 955859216 1774809088 0.1308160424 -0.0141005032 0.0798627883 190 1305031108.4754710197 0.0568607971 0.0442282914 0.0857079923 0.0163222742 0.0862840000 10454899 955859216 1774047232 0.1428829730 -0.0150732556 0.0824400187 191 1305031108.5113780499 0.0607788600 0.0443149436 0.0857079923 0.0165853177 0.0818200000 10456729 955859216 1773309952 0.1550141722 -0.0178881008 0.0836030096 192 1305031108.5437369347 0.0625832751 0.0444100911 0.0857079923 0.0166189668 0.0759970000 10458527 955859216 1772523520 0.1656393558 -0.0203331336 0.0835103840 193 1305031108.5754139423 0.0648160651 0.0445158216 0.0857079923 0.0166532671 0.0663800000 10460261 955859216 1771909120 0.1750357449 -0.0191636719 0.0840787739 194 1305031108.6114070415 0.0708340108 0.0446514824 0.0857079923 0.0166465204 0.0859140000 10462091 955859216 1771126784 0.1828756034 -0.0118534518 0.0853759423 195 1305031108.6433029175 0.0732678324 0.0447982329 0.0857079923 0.0166175602 0.0695040000 10463889 955859216 1770512384 0.1919163764 -0.0114590432 0.0865791291 196 1305031108.6753749847 0.0753211081 0.0449539618 0.0857079923 0.0166166384 0.0936900000 10465623 955859216 1769730048 0.2005020976 -0.0073534497 0.0883360654 197 1305031108.7114109993 0.0796142444 0.0451299023 0.0857079923 0.0166270377 0.0634760000 10467421 955859216 1771216896 0.2096143365 -0.0047040335 0.0897812545 198 1305031108.7435019016 0.0817949772 0.0453150795 0.0857079923 0.0166012647 0.0670440000 10469219 955859216 1770635264 0.2174609900 -0.0059502944 0.0906045139 199 1305031108.7754929066 0.0824512467 0.0455016934 0.0857079923 0.0165616704 0.0887770000 10470953 955859216 1769693184 0.2254323959 -0.0061309421 0.0910304040 200 1305031108.8112440109 0.0834980831 0.0456916753 0.0857079923 0.0165228401 0.0967310000 10472783 955859216 1768960000 0.2335122973 -0.0047109737 0.0910772979 201 1305031108.8432641029 0.0840035304 0.0458822816 0.0857079923 0.0179469308 0.1074340000 10474581 955859216 1767706624 0.2408184409 -0.0054439888 0.0900157541 202 1305031108.8765149117 0.0771016479 0.0460368329 0.0857079923 0.0179782906 0.0886220000 10476347 955859216 1766928384 0.2479426265 -0.0059159733 0.0880752802 203 1305031108.9113640785 0.0719544068 0.0461645057 0.0857079923 0.0180641116 0.0866940000 10478145 955859216 1766166528 0.2532785237 -0.0059900014 0.0856466666 204 1305031108.9432430267 0.0706568658 0.0462845663 0.0857079923 0.0181285440 0.1063160000 10479943 955859216 1765404672 0.2557696700 -0.0095657036 0.0825076252 205 1305031108.9752678871 0.0692018121 0.0463963577 0.0857079923 0.0181081069 0.0896770000 10481709 955859216 1765048320 0.2544952631 -0.0103178378 0.0800222084 206 1305031109.0112690926 0.0618837513 0.0464715392 0.0857079923 0.0180832286 0.0762510000 10483507 955859216 1766637568 0.2545295060 -0.0052518514 0.0780558363 207 1305031109.0432770252 0.0595373660 0.0465346592 0.0857079923 0.0180609218 0.0639380000 10485305 955859216 1766158336 0.2510879040 -0.0074594608 0.0761538595 208 1305031109.0754098892 0.0583837107 0.0465916258 0.0857079923 0.0180548127 0.0693760000 10487039 955859216 1765158912 0.2451778650 -0.0079795988 0.0749048665 209 1305031109.1112821102 0.0530880950 0.0466227093 0.0857079923 0.0180293732 0.0947530000 10488869 955859216 1765036032 0.2381580621 -0.0042256829 0.0746945217 210 1305031109.1433339119 0.0504973195 0.0466411599 0.0857079923 0.0180074121 0.0709480000 10490667 955859216 1765036032 0.2316433936 -0.0073441863 0.0737215877 211 1305031109.1754639149 0.0488988459 0.0466518598 0.0857079923 0.0180172635 0.0663570000 10492401 955859216 1765031936 0.2233851105 -0.0090700779 0.0729497001 212 1305031109.2113790512 0.0418518782 0.0466292184 0.0857079923 0.0180235626 0.0668650000 10494231 955859216 1765036032 0.2152840346 -0.0052599260 0.0735320523 213 1305031109.2432899475 0.0376436859 0.0465870328 0.0857079923 0.0179887776 0.0651320000 10496029 955859216 1766510592 0.2075066864 -0.0028503020 0.0752152950 214 1305031109.2753078938 0.0371379852 0.0465428784 0.0857079923 0.0181040970 0.0860770000 10497763 955859216 1766068224 0.1973432750 -0.0069274148 0.0754710287 215 1305031109.3113288879 0.0340935588 0.0464849745 0.0857079923 0.0181708775 0.1054670000 10499593 955859216 1765277696 0.1866018474 -0.0130285574 0.0746742338 216 1305031109.3432478905 0.0300139915 0.0464087200 0.0857079923 0.0182032967 0.0722440000 10501391 955859216 1766891520 0.1759572774 -0.0092732254 0.0751392692 217 1305031109.3753969669 0.0281935614 0.0463247792 0.0857079923 0.0181704515 0.0697680000 10503125 955859216 1768796160 0.1642171890 -0.0083007682 0.0761910751 218 1305031109.4113290310 0.0251057055 0.0462274440 0.0857079923 0.0181309480 0.0661500000 10504955 955859216 1770467328 0.1526197046 -0.0112668332 0.0762547106 219 1305031109.4433019161 0.0232923664 0.0461227176 0.0857079923 0.0181132196 0.0687630000 10506721 955859216 1772118016 0.1409854293 -0.0094550597 0.0766860843 220 1305031109.4753630161 0.0236121658 0.0460203969 0.0857079923 0.0181032311 0.0732440000 10508455 955859216 1773916160 0.1281839758 -0.0098150400 0.0765953213 221 1305031109.5112729073 0.0240500122 0.0459209834 0.0857079923 0.0180852165 0.0708420000 10510285 955859216 1775566848 0.1144496277 -0.0131143127 0.0755267665 222 1305031109.5432939529 0.0260164533 0.0458313233 0.0857079923 0.0180650993 0.0884100000 10512083 955859216 1777197056 0.1008087322 -0.0157292522 0.0736451745 223 1305031109.5753619671 0.0245292969 0.0457357986 0.0857079923 0.0180273358 0.0650580000 10513849 955859216 1778995200 0.0890361592 -0.0142242145 0.0717984214 224 1305031109.6113100052 0.0217581335 0.0456287554 0.0857079923 0.0180119192 0.0722850000 10515647 955859216 1780625408 0.0766709000 -0.0124233197 0.0700424090 225 1305031109.6432290077 0.0218153689 0.0455229181 0.0857079923 0.0179726900 0.0657050000 10517445 955859216 1782423552 0.0648823828 -0.0117212422 0.0686314777 226 1305031109.6752629280 0.0203420408 0.0454114983 0.0857079923 0.0179353964 0.0688920000 10519179 955859216 1784074240 0.0544579104 -0.0097469138 0.0679402873 227 1305031109.7113120556 0.0190681964 0.0452954485 0.0857079923 0.0179555880 0.0714200000 10521009 955859216 1785704448 0.0428956822 -0.0083469758 0.0677988678 228 1305031109.7432739735 0.0188553073 0.0451794830 0.0857079923 0.0179167393 0.0773210000 10522807 955859216 1787502592 0.0305527598 -0.0052049002 0.0685310066 229 1305031109.7752768993 0.0199535526 0.0450693261 0.0857079923 0.0179010487 0.0655390000 10524541 955859216 1786732544 0.0195229854 -0.0064257425 0.0695773140 230 1305031109.8113710880 0.0200670939 0.0449606208 0.0857079923 0.0178722427 0.0689490000 10526371 955859216 1785470976 0.0066859955 -0.0066658459 0.0705708191 231 1305031109.8432960510 0.0202451684 0.0448536275 0.0857079923 0.0178402263 0.0751660000 10528169 955859216 1784602624 -0.0056083230 -0.0046135215 0.0721123442 232 1305031109.8753058910 0.0210128091 0.0447508653 0.0857079923 0.0178106455 0.0769660000 10529903 955859216 1783713792 -0.0185631923 -0.0037874039 0.0745735541 233 1305031109.9112648964 0.0233933870 0.0446592023 0.0857079923 0.0177916954 0.0760500000 10531733 955859216 1782935552 -0.0297709480 -0.0049755946 0.0770823285 234 1305031109.9432990551 0.0251527373 0.0445758413 0.0857079923 0.0177861046 0.0714810000 10533531 955859216 1782198272 -0.0436163880 -0.0046782028 0.0803136155 235 1305031109.9752581120 0.0257125013 0.0444955718 0.0857079923 0.0177526345 0.0672980000 10535265 955859216 1783562240 -0.0541932210 -0.0002714805 0.0837664381 236 1305031110.0112559795 0.0287906975 0.0444290257 0.0857079923 0.0177188666 0.0729120000 10537095 955859216 1782927360 -0.0680655539 -0.0020375836 0.0872058272 237 1305031110.0432989597 0.0296561345 0.0443666929 0.0857079923 0.0176827846 0.1070960000 10538893 955859216 1781694464 -0.0821098685 -0.0014228281 0.0906676129 238 1305031110.0753190517 0.0311987884 0.0443113655 0.0857079923 0.0176579940 0.0736010000 10540627 955859216 1783058432 -0.0952672660 -0.0017209966 0.0942094475 239 1305031110.1113250256 0.0333062373 0.0442653190 0.0857079923 0.0176705485 0.0661430000 10542457 955859216 1784942592 -0.1074773967 -0.0005494049 0.0977632701 240 1305031110.1434319019 0.0358254798 0.0442301530 0.0857079923 0.0176961702 0.0762780000 10544255 955859216 1786740736 -0.1215115786 -0.0038564561 0.1013555676 241 1305031110.1756410599 0.0382097550 0.0442051721 0.0857079923 0.0176599202 0.0699880000 10545989 955859216 1785692160 -0.1310976297 -0.0047982619 0.1042544469 242 1305031110.2116370201 0.0407996848 0.0441910998 0.0857079923 0.0176326578 0.1036040000 10547851 955859216 1784856576 -0.1405380070 -0.0026057698 0.1069721431 243 1305031110.2433230877 0.0442632176 0.0441913966 0.0857079923 0.0176339721 0.0671950000 10549617 955859216 1783193600 -0.1509302408 -0.0063819373 0.1095651537 244 1305031110.2793209553 0.0480472893 0.0442071994 0.0857079923 0.0176192147 0.0667550000 10551447 955859216 1782677504 -0.1586547196 -0.0079671238 0.1107335165 245 1305031110.3114039898 0.0483796746 0.0442242299 0.0857079923 0.0175848516 0.0744330000 10553181 955859216 1781919744 -0.1687769890 -0.0075691473 0.1112374216 246 1305031110.3433549404 0.0501624793 0.0442483692 0.0857079923 0.0175548625 0.0608810000 10554947 955859216 1781047296 -0.1765420437 -0.0069629466 0.1117629930 247 1305031110.3792810440 0.0516041368 0.0442781496 0.0857079923 0.0175477260 0.0720400000 10556777 955859216 1782517760 -0.1877855062 -0.0047059879 0.1119905040 248 1305031110.4114689827 0.0530471094 0.0443135083 0.0857079923 0.0175303624 0.1110050000 10558543 955859216 1780162560 -0.1983382553 -0.0039175861 0.1126929596 249 1305031110.4432599545 0.0541770644 0.0443531210 0.0857079923 0.0174998000 0.0895370000 10560309 955859216 1779388416 -0.2082513422 0.0005872175 0.1137381271 250 1305031110.4793310165 0.0583009645 0.0444089124 0.0857079923 0.0175313308 0.0785310000 10562171 955859216 1780752384 -0.2195610404 0.0001800824 0.1151932329 251 1305031110.5114290714 0.0616447181 0.0444775809 0.0857079923 0.0175141418 0.0722260000 10563905 955859216 1780154368 -0.2297767699 -0.0026628019 0.1172454581 252 1305031110.5434079170 0.0632093325 0.0445519133 0.0857079923 0.0174900091 0.0712620000 10565703 955859216 1779089408 -0.2398893982 -0.0010816883 0.1184774339 253 1305031110.5794260502 0.0657130033 0.0446355539 0.0857079923 0.0174889138 0.0672530000 10567533 955859216 1778245632 -0.2507121563 0.0021948591 0.1201582551 254 1305031110.6113069057 0.0674252212 0.0447252770 0.0857079923 0.0175072412 0.0633120000 10569267 955859216 1777475584 -0.2616820931 0.0020602439 0.1223144531 255 1305031110.6434180737 0.0709464625 0.0448281052 0.0857079923 0.0175344439 0.0674650000 10571065 955859216 1776713728 -0.2701589763 -0.0034912378 0.1244781017 256 1305031110.6796059608 0.0725238025 0.0449362915 0.0857079923 0.0175449332 0.0666900000 10572863 955859216 1778077696 -0.2774022520 -0.0029882099 0.1246434972 257 1305031110.7114119530 0.0726628900 0.0450441771 0.0857079923 0.0175149399 0.0822630000 10595109 955859216 1777631232 -0.2839476764 -0.0000634398 0.1252349317 258 1305031110.7432489395 0.0727885440 0.0451517134 0.0857079923 0.0175213274 0.0741970000 10638859 955859216 1776840704 -0.2915467620 -0.0020801409 0.1260023117 259 1305031110.7791929245 0.0736303404 0.0452616695 0.0857079923 0.0174887006 0.0668990000 10640689 955859216 1776078848 -0.2977660000 -0.0038730199 0.1265108138 260 1305031110.8113861084 0.0736880302 0.0453710017 0.0857079923 0.0174562715 0.0816060000 10642455 955859216 1775316992 -0.3005582690 -0.0029427488 0.1268355697 261 1305031110.8432180882 0.0729163513 0.0454765394 0.0857079923 0.0174341155 0.0983250000 10644221 955859216 1774555136 -0.3045315444 -0.0023536384 0.1271569133 262 1305031110.8793129921 0.0729639009 0.0455814530 0.0857079923 0.0174019913 0.0816660000 10646051 955859216 1773793280 -0.3074021637 -0.0044912496 0.1275093108 263 1305031110.9113330841 0.0730680525 0.0456859648 0.0857079923 0.0173830513 0.0903090000 10647817 955859216 1773031424 -0.3080069423 -0.0043371725 0.1283409894 264 1305031110.9438619614 0.0726416931 0.0457880698 0.0857079923 0.0173721561 0.0610790000 10649615 955859216 1772388352 -0.3080313504 -0.0048098508 0.1289057881 265 1305031110.9793450832 0.0715849698 0.0458854166 0.0857079923 0.0174005134 0.0927620000 10651381 955859216 1771651072 -0.3056351542 -0.0039260294 0.1294185221 266 1305031111.0114309788 0.0696332306 0.0459746941 0.0857079923 0.0173949993 0.1038000000 10653179 955859216 1770864640 -0.3003728390 -0.0009691752 0.1292090118 267 1305031111.0433270931 0.0699376240 0.0460644429 0.0857079923 0.0173639872 0.0916360000 10654945 955859216 1770250240 -0.2929299772 -0.0019458496 0.1293724328 268 1305031111.0792829990 0.0684790313 0.0461480794 0.0857079923 0.0173525111 0.1048670000 10656743 955859216 1769467904 -0.2820158601 -0.0000417028 0.1290334016 269 1305031111.1115078926 0.0682326108 0.0462301781 0.0857079923 0.0173309533 0.0875010000 10658541 955859216 1768706048 -0.2772221863 -0.0012954249 0.1295588166 270 1305031111.1432569027 0.0682669207 0.0463117956 0.0857079923 0.0173118263 0.0732270000 10660307 955859216 1770192896 -0.2699887156 -0.0031634099 0.1293729693 271 1305031111.1793260574 0.0670790002 0.0463884274 0.0857079923 0.0173686145 0.0891630000 10662137 955859216 1769586688 -0.2558860481 -0.0029547438 0.1286546290 272 1305031111.2114329338 0.0646293759 0.0464554897 0.0857079923 0.0173536071 0.0838700000 10663871 955859216 1768828928 -0.2446201593 -0.0011771714 0.1268492788 273 1305031111.2432360649 0.0631430075 0.0465166161 0.0857079923 0.0173887546 0.1067390000 10665637 955859216 1765883904 -0.2365404665 -0.0012969339 0.1262896806 274 1305031111.2793080807 0.0613898374 0.0465708980 0.0857079923 0.0174300838 0.1254770000 10667467 955859216 1765150720 -0.2309835553 -0.0046095811 0.1252841055 275 1305031111.3115470409 0.0589928776 0.0466160688 0.0857079923 0.0174367389 0.1275150000 10669233 955859216 1765040128 -0.2151614428 -0.0031421483 0.1238869503 276 1305031111.3433969021 0.0565160960 0.0466519385 0.0857079923 0.0175770530 0.1240160000 10670999 955859216 1765036032 -0.2095777839 -0.0003636331 0.1239725947 277 1305031111.3791339397 0.0563438945 0.0466869275 0.0857079923 0.0176875508 0.1254490000 10672829 955859216 1766510592 -0.2028842121 -0.0026923160 0.1238515601 278 1305031111.4112958908 0.0577160418 0.0467266005 0.0857079923 0.0176611124 0.0879140000 10674563 955859216 1768427520 -0.1823676229 -0.0063963276 0.1247234493 279 1305031111.4433860779 0.0538499430 0.0467521322 0.0857079923 0.0176525967 0.0782320000 10676361 955859216 1770078208 -0.1729527414 -0.0021292251 0.1239035055 280 1305031111.4792590141 0.0534718297 0.0467761312 0.0857079923 0.0180966699 0.1309210000 10678191 955859216 1771843584 -0.1568146646 -0.0041279867 0.1240519211 281 1305031111.5112640858 0.0509402379 0.0467909500 0.0857079923 0.0180967726 0.1259120000 10679925 955859216 1773527040 -0.1431428492 -0.0043694619 0.1219764352 282 1305031111.5432500839 0.0496325642 0.0468010267 0.0857079923 0.0180762112 0.0680280000 10681723 955859216 1775157248 -0.1353667676 -0.0058128498 0.1202214807 283 1305031111.5792369843 0.0472987331 0.0468027854 0.0857079923 0.0180979237 0.0778100000 10683553 955859216 1776934912 -0.1185445189 -0.0063538849 0.1182787418 284 1305031111.6112709045 0.0443218611 0.0467940497 0.0857079923 0.0181813359 0.0899510000 10685255 955859216 1778606080 -0.1077006832 -0.0035234690 0.1170743555 285 1305031111.6433949471 0.0475069247 0.0467965510 0.0857079923 0.0181975970 0.0688160000 10687053 955859216 1780383744 -0.1005412042 -0.0078252777 0.1168365628 286 1305031111.6793200970 0.0453152508 0.0467913717 0.0857079923 0.0184161246 0.0984550000 10688851 955859216 1782034432 -0.0787505433 -0.0093002748 0.1157251373 287 1305031111.7117600441 0.0388154387 0.0467635810 0.0857079923 0.0184360034 0.0894210000 10690649 955859216 1783664640 -0.0637613609 -0.0025164497 0.1140279472 288 1305031111.7433860302 0.0391265862 0.0467370636 0.0857079923 0.0185179585 0.0880470000 10692415 955859216 1785462784 -0.0501830727 -0.0052896324 0.1130884960 289 1305031111.7794229984 0.0372504219 0.0467042379 0.0857079923 0.0186109842 0.0847270000 10694245 955859216 1787113472 -0.0348335765 -0.0038074034 0.1118535399 290 1305031111.8114058971 0.0382927023 0.0466752326 0.0857079923 0.0186376086 0.0726070000 10695979 955859216 1786318848 -0.0280393511 -0.0028107886 0.1106016114 291 1305031111.8432989120 0.0417154916 0.0466581888 0.0857079923 0.0186190955 0.0894500000 10697745 955859216 1785208832 -0.0216523949 -0.0030825310 0.1091478467 292 1305031111.8794419765 0.0404753573 0.0466370147 0.0857079923 0.0186096158 0.1022850000 10699543 955859216 1783451648 -0.0075891144 0.0015743878 0.1087125987 293 1305031111.9113540649 0.0438118540 0.0466273725 0.0857079923 0.0186320171 0.0879600000 10701341 955859216 1785110528 0.0013910591 -0.0002544131 0.1093358770 294 1305031111.9433000088 0.0456031412 0.0466238887 0.0857079923 0.0186007850 0.0868750000 10703107 955859216 1786585088 0.0134150768 -0.0032882770 0.1098013744 295 1305031111.9794490337 0.0450726636 0.0466186303 0.0857079923 0.0187518313 0.0671750000 10704905 955859216 1785495552 0.0293517280 -0.0016969052 0.1100943387 296 1305031112.0114328861 0.0418813750 0.0466026261 0.0857079923 0.0187745468 0.0832590000 10706703 955859216 1784832000 0.0431264900 0.0007832228 0.1089677215 297 1305031112.0432701111 0.0468252264 0.0466033756 0.0857079923 0.0187440763 0.0683580000 10708469 955859216 1783947264 0.0493413694 -0.0004927618 0.1078150123 298 1305031112.0793390274 0.0505307354 0.0466165547 0.0857079923 0.0187865939 0.1003480000 10710299 955859216 1783197696 0.0601050816 0.0012905812 0.1065436825 299 1305031112.1114230156 0.0543289334 0.0466423486 0.0857079923 0.0188425696 0.1076810000 10712033 955859216 1782435840 0.0675683916 0.0006359555 0.1054184958 300 1305031112.1443419456 0.0568413623 0.0466763453 0.0857079923 0.0188223477 0.0687100000 10713799 955859216 1781633024 0.0768191367 0.0014515445 0.1051045433 301 1305031112.1793899536 0.0621972606 0.0467279098 0.0857079923 0.0188995455 0.0864170000 10715565 955859216 1780924416 0.0875177085 0.0029312989 0.1047767028 302 1305031112.2112538815 0.0674214736 0.0467964315 0.0857079923 0.0188944527 0.1078340000 10717331 955859216 1780002816 0.0961270183 -0.0003322968 0.1047150493 303 1305031112.2433691025 0.0722784251 0.0468805305 0.0857079923 0.0189085963 0.0837660000 10719129 955859216 1779245056 0.1056878790 -0.0065752445 0.1035388410 304 1305031112.2793529034 0.0781567544 0.0469834128 0.0857079923 0.0188920427 0.0680980000 10720927 955859216 1780731904 0.1161830574 -0.0064087776 0.1025188193 305 1305031112.3113119602 0.0792465732 0.0470891937 0.0857079923 0.0188824285 0.0797440000 10722725 955859216 1780142080 0.1272744238 -0.0070085423 0.1014685184 306 1305031112.3433229923 0.0789154470 0.0471932010 0.0857079923 0.0188614670 0.0904900000 10724491 955859216 1779372032 0.1394547820 -0.0073525212 0.1001204476 307 1305031112.3793599606 0.0810728595 0.0473035582 0.0857079923 0.0188369863 0.0787820000 10726353 955859216 1778610176 0.1517806500 -0.0043081678 0.0992470086 308 1305031112.4114420414 0.0794822946 0.0474080347 0.0857079923 0.0188182282 0.0690220000 10728087 955859216 1777737728 0.1642891616 -0.0031185397 0.0988806486 309 1305031112.4433910847 0.0772491544 0.0475046079 0.0857079923 0.0188044773 0.0889300000 10729885 955859216 1776975872 0.1772587150 -0.0031559132 0.0981873944 310 1305031112.4794180393 0.0786158368 0.0476049667 0.0857079923 0.0187876393 0.0874590000 10731715 955859216 1776160768 0.1894746423 -0.0040526269 0.0972221717 311 1305031112.5115039349 0.0756101832 0.0476950156 0.0857079923 0.0187715263 0.0795170000 10733449 955859216 1775435776 0.2013802081 -0.0026623115 0.0963492244 312 1305031112.5432119370 0.0737555623 0.0477785430 0.0857079923 0.0187539750 0.0763460000 10735215 955859216 1774563328 0.2122778893 -0.0034127354 0.0955682248 313 1305031112.5792520046 0.0746234357 0.0478643094 0.0857079923 0.0187261166 0.0732600000 10737013 955859216 1776160768 0.2226219475 -0.0026180465 0.0951722264 314 1305031112.6112608910 0.0724725202 0.0479426795 0.0857079923 0.0187735010 0.0795850000 10738779 955859216 1775321088 0.2328807265 -0.0008481763 0.0949333310 315 1305031112.6432459354 0.0713705644 0.0480170537 0.0857079923 0.0188041931 0.1094060000 10740577 955859216 1772261376 0.2409528792 0.0023222838 0.0952635556 316 1305031112.6799519062 0.0744691044 0.0481007628 0.0857079923 0.0187994209 0.0857480000 10742407 955859216 1771499520 0.2454448491 0.0029003695 0.0955809578 317 1305031112.7112510204 0.0756218657 0.0481875801 0.0857079923 0.0187937766 0.0826500000 10744141 955859216 1770885120 0.2487147003 0.0032055131 0.0963035524 318 1305031112.7432448864 0.0759839192 0.0482749900 0.0857079923 0.0187874852 0.0765630000 10745939 955859216 1772351488 0.2507708669 0.0062347250 0.0978282392 319 1305031112.7793099880 0.0747379214 0.0483579459 0.0857079923 0.0187869722 0.0815070000 10747769 955859216 1771638784 0.2519768178 0.0104734125 0.0999844894 320 1305031112.8113100529 0.0727557689 0.0484341891 0.0857079923 0.0187962863 0.0836130000 10749503 955859216 1770319872 0.2528719008 0.0084731998 0.1008505449 321 1305031112.8432860374 0.0715261921 0.0485061268 0.0857079923 0.0188066364 0.1001490000 10751269 955859216 1767424000 0.2515348792 0.0080487821 0.1024813205 322 1305031112.8794209957 0.0676196963 0.0485654857 0.0857079923 0.0188232954 0.1107080000 10753099 955859216 1766801408 0.2506611645 0.0095075713 0.1041908711 323 1305031112.9114110470 0.0637623593 0.0486125348 0.0857079923 0.0187975235 0.0854700000 10754897 955859216 1766039552 0.2500560582 0.0100631155 0.1051116213 324 1305031112.9433209896 0.0606387816 0.0486496529 0.0857079923 0.0187716623 0.0880590000 10756663 955859216 1765277696 0.2474825382 0.0093980953 0.1055660769 325 1305031112.9792780876 0.0562945902 0.0486731758 0.0857079923 0.0187872131 0.0640680000 10758493 955859216 1766891520 0.2435568273 0.0072600027 0.1056004539 326 1305031113.0113530159 0.0541744977 0.0486900510 0.0857079923 0.0187636775 0.0682420000 10760227 955859216 1766322176 0.2386682928 0.0056263297 0.1054334193 327 1305031113.0432310104 0.0517872907 0.0486995227 0.0857079923 0.0187445462 0.0775400000 10762025 955859216 1765679104 0.2319374382 0.0057339086 0.1053717956 328 1305031113.0792510509 0.0494654179 0.0487018577 0.0857079923 0.0187542787 0.0876010000 10763855 955859216 1765044224 0.2226007730 0.0013165781 0.1043158919 329 1305031113.1113159657 0.0491045453 0.0487030817 0.0857079923 0.0187475859 0.0697630000 10765589 955859216 1765036032 0.2140426338 -0.0032937485 0.1023728102 330 1305031113.1433060169 0.0468443669 0.0486974492 0.0857079923 0.0187316142 0.0662740000 10767387 955859216 1766510592 0.2035691738 -0.0005664206 0.1015956402 331 1305031113.1793429852 0.0417057909 0.0486763264 0.0857079923 0.0187483834 0.0670280000 10769217 955859216 1766002688 0.1936070323 -0.0013575274 0.1006803885 332 1305031113.2112588882 0.0426068828 0.0486580449 0.0857079923 0.0187361408 0.0770950000 10770951 955859216 1765433344 0.1832908541 -0.0070078173 0.0987735763 333 1305031113.2432270050 0.0386552550 0.0486280065 0.0857079923 0.0187325466 0.0696690000 10772749 955859216 1765048320 0.1732321084 -0.0057888445 0.0980694219 334 1305031113.2793118954 0.0329627134 0.0485811045 0.0857079923 0.0187512654 0.0673860000 10774547 955859216 1765036032 0.1619398296 -0.0069442405 0.0978370681 335 1305031113.3114519119 0.0352218635 0.0485412261 0.0857079923 0.0188180763 0.0834610000 10776313 955859216 1765036032 0.1496806741 -0.0145822931 0.0966037810 336 1305031113.3432519436 0.0317896977 0.0484913704 0.0857079923 0.0188302469 0.0691030000 10778079 955859216 1766510592 0.1368790567 -0.0144770909 0.0953724384 337 1305031113.3793120384 0.0204116553 0.0484080478 0.0857079923 0.0188755194 0.0766370000 10779877 955859216 1766510592 0.1239428669 -0.0077746683 0.0970973447 338 1305031113.4116249084 0.0219841357 0.0483298705 0.0857079923 0.0188980139 0.0687730000 10781675 955859216 1765912576 0.1082936451 -0.0121387579 0.0985221863 339 1305031113.4432659149 0.0217625536 0.0482515009 0.0857079923 0.0188810292 0.0673320000 10783441 955859216 1765052416 0.0930071548 -0.0146389399 0.0991548076 340 1305031113.4793109894 0.0167240538 0.0481587731 0.0857079923 0.0189069431 0.0850920000 10785239 955859216 1765036032 0.0758577287 -0.0113001382 0.1013713479 341 1305031113.5115230083 0.0177731086 0.0480696656 0.0857079923 0.0188868185 0.1036060000 10787037 955859216 1765036032 0.0602622330 -0.0128580071 0.1033979356 342 1305031113.5432419777 0.0202317964 0.0479882683 0.0857079923 0.0188799117 0.1085620000 10788803 955859216 1765036032 0.0433587022 -0.0161803700 0.1043268070 343 1305031113.5793011189 0.0204131939 0.0479078745 0.0857079923 0.0188550315 0.0857510000 10790601 955859216 1765036032 0.0258575492 -0.0181514751 0.1047513336 344 1305031113.6112680435 0.0203915238 0.0478278851 0.0857079923 0.0188304937 0.1026450000 10792399 955859216 1765036032 0.0112082120 -0.0161109157 0.1059788465 345 1305031113.6432220936 0.0217231531 0.0477522192 0.0857079923 0.0188079633 0.0679740000 10794165 955859216 1764630528 -0.0015081760 -0.0166219808 0.1066536680 346 1305031113.6792879105 0.0227291565 0.0476798982 0.0857079923 0.0187892522 0.0806320000 10796027 955859216 1765036032 -0.0149375936 -0.0181235317 0.1071031690 347 1305031113.7119309902 0.0240114722 0.0476116895 0.0857079923 0.0187650126 0.0895570000 10797761 955859216 1765031936 -0.0295798145 -0.0184393562 0.1071316898 348 1305031113.7435901165 0.0238842946 0.0475435073 0.0857079923 0.0187395907 0.0680130000 10799559 955859216 1765036032 -0.0432779416 -0.0185028650 0.1073475927 349 1305031113.7793200016 0.0237327125 0.0474752815 0.0857079923 0.0187286104 0.0854500000 10801357 955859216 1765036032 -0.0565398484 -0.0178738404 0.1077385768 350 1305031113.8112370968 0.0249346364 0.0474108797 0.0857079923 0.0187035190 0.1102250000 10803091 955859216 1765036032 -0.0716028884 -0.0184104312 0.1087316051 351 1305031113.8432950974 0.0241463874 0.0473445991 0.0857079923 0.0186881066 0.0848250000 10804889 955859216 1765036032 -0.0845856741 -0.0149158537 0.1095841378 352 1305031113.8792810440 0.0252455100 0.0472818176 0.0857079923 0.0187285182 0.0865390000 10806719 955859216 1765036032 -0.0982672125 -0.0159426834 0.1106378585 353 1305031113.9112899303 0.0272922888 0.0472251900 0.0857079923 0.0187021460 0.0694480000 10808485 955859216 1765036032 -0.1124098301 -0.0182399936 0.1117399931 354 1305031113.9432909489 0.0270448513 0.0471681834 0.0857079923 0.0186891418 0.0856820000 10810251 955859216 1765052416 -0.1220797822 -0.0156445671 0.1123113930 355 1305031113.9792931080 0.0275512319 0.0471129244 0.0857079923 0.0186662907 0.0811020000 10812081 955859216 1765052416 -0.1366886646 -0.0139917927 0.1128761768 356 1305031114.0112569332 0.0270581879 0.0470565909 0.0857079923 0.0186578627 0.1092750000 10813847 955859216 1765031936 -0.1548887044 -0.0113592353 0.1138195768 357 1305031114.0433011055 0.0286135394 0.0470049297 0.0857079923 0.0186636389 0.0661470000 10815613 955859216 1766510592 -0.1713191569 -0.0098111341 0.1155103892 358 1305031114.0792849064 0.0295137856 0.0469560717 0.0857079923 0.0186615095 0.0767140000 10817443 955859216 1766031360 -0.1834137440 -0.0105500510 0.1167499050 359 1305031114.1112630367 0.0308271311 0.0469111443 0.0857079923 0.0186413368 0.1083150000 10819209 955859216 1765154816 -0.1992678195 -0.0085853292 0.1186929941 360 1305031114.1432840824 0.0317245983 0.0468689595 0.0857079923 0.0186201123 0.0868470000 10821007 955859216 1766764544 -0.2100868821 -0.0062148590 0.1204237491 361 1305031114.1793370247 0.0333105177 0.0468314015 0.0857079923 0.0186312012 0.0888730000 10822837 955859216 1768574976 -0.2222384959 -0.0062247445 0.1222713143 362 1305031114.2113029957 0.0341220573 0.0467962928 0.0857079923 0.0186280445 0.0799600000 10824571 955859216 1770196992 -0.2339217812 -0.0043663364 0.1239910498 363 1305031114.2433369160 0.0362280235 0.0467671791 0.0857079923 0.0186394708 0.0711400000 10826337 955859216 1771974656 -0.2514655590 0.0018318761 0.1270474792 364 1305031114.2793900967 0.0369923636 0.0467403252 0.0857079923 0.0186923389 0.0675220000 10828167 955859216 1773625344 -0.2631727457 -0.0007178849 0.1296555251 365 1305031114.3114290237 0.0396670215 0.0467209463 0.0857079923 0.0186731921 0.0788520000 10829933 955859216 1775423488 -0.2737310231 0.0003519976 0.1329296827 366 1305031114.3433310986 0.0420916416 0.0467082979 0.0857079923 0.0186601532 0.1296190000 10831731 955859216 1777074176 -0.2809253931 0.0023595535 0.1353026032 367 1305031114.3793199062 0.0446696989 0.0467027431 0.0857079923 0.0186444264 0.0864390000 10833561 955859216 1778704384 -0.2888788879 0.0030035374 0.1372667700 368 1305031114.4113969803 0.0458756611 0.0467004956 0.0857079923 0.0186280417 0.0817470000 10835327 955859216 1780502528 -0.2988427579 0.0021383052 0.1390780956 369 1305031114.4433450699 0.0468365997 0.0467008645 0.0857079923 0.0186193396 0.1091780000 10837093 955859216 1782153216 -0.3108358681 0.0017679185 0.1413496137 370 1305031114.4793319702 0.0487937145 0.0467065208 0.0857079923 0.0186282651 0.0813220000 10838923 955859216 1783783424 -0.3201388717 0.0003062245 0.1435883045 371 1305031114.5112659931 0.0500726067 0.0467155938 0.0857079923 0.0186064095 0.0862860000 10840657 955859216 1785548800 -0.3289702833 -0.0007366305 0.1465580314 372 1305031114.5432360172 0.0521622337 0.0467302353 0.0857079923 0.0185925449 0.1054440000 10842455 955859216 1787211776 -0.3341744244 0.0002656551 0.1492573172 373 1305031114.5792369843 0.0531404279 0.0467474208 0.0857079923 0.0185735055 0.1093150000 10844285 955859216 1785327616 -0.3395610750 -0.0032226471 0.1511319578 374 1305031114.6113910675 0.0541841500 0.0467673051 0.0857079923 0.0185548198 0.0887520000 10846019 955859216 1784569856 -0.3435606360 -0.0041685677 0.1530283093 375 1305031114.6441500187 0.0554385632 0.0467904285 0.0857079923 0.0185393858 0.1058630000 10847817 955859216 1783439360 -0.3487895429 -0.0036404287 0.1551581472 376 1305031114.6792509556 0.0564151444 0.0468160262 0.0857079923 0.0185328164 0.0896650000 10849583 955859216 1782554624 -0.3554962575 -0.0070335446 0.1569897979 377 1305031114.7113060951 0.0574520938 0.0468442385 0.0857079923 0.0185292734 0.1159600000 10851317 955859216 1781776384 -0.3591898978 -0.0110091586 0.1579069495 378 1305031114.7432758808 0.0587670840 0.0468757805 0.0857079923 0.0185085487 0.0788080000 10853115 955859216 1780756480 -0.3608805835 -0.0129749505 0.1584746093 379 1305031114.7792890072 0.0593035668 0.0469085714 0.0857079923 0.0184913419 0.0862680000 10854945 955859216 1779888128 -0.3618097901 -0.0139753455 0.1583162099 380 1305031114.8113029003 0.0595194623 0.0469417580 0.0857079923 0.0184762577 0.1140620000 10856679 955859216 1779105792 -0.3607995510 -0.0128035843 0.1580314338 381 1305031114.8432080746 0.0597808361 0.0469754564 0.0857079923 0.0184529823 0.0811490000 10858477 955859216 1778974720 -0.3602571785 -0.0123869106 0.1579605341 382 1305031114.8792810440 0.0588161424 0.0470064529 0.0857079923 0.0184287639 0.0851750000 10860275 955859216 1779122176 -0.3590502441 -0.0115406225 0.1573446244 383 1305031114.9128789902 0.0588819608 0.0470374595 0.0857079923 0.0184089222 0.1075610000 10862105 955859216 1776160768 -0.3555841148 -0.0101377470 0.1572946012 384 1305031114.9432640076 0.0582135990 0.0470665640 0.0857079923 0.0183859395 0.0885410000 10863807 955859216 1775169536 -0.3518992662 -0.0072506610 0.1576980352 385 1305031114.9792799950 0.0567065105 0.0470916028 0.0857079923 0.0183669745 0.0669430000 10865637 955859216 1776549888 -0.3457500637 -0.0045498926 0.1575614214 386 1305031115.0113000870 0.0559057221 0.0471144373 0.0857079923 0.0183511112 0.0681180000 10867403 955859216 1776091136 -0.3394494951 -0.0013811180 0.1582648903 387 1305031115.0435299873 0.0550512150 0.0471349458 0.0857079923 0.0183441764 0.0803520000 10869201 955859216 1774931968 -0.3321068585 0.0001960937 0.1590726227 388 1305031115.0792379379 0.0539874993 0.0471526070 0.0857079923 0.0183229077 0.0892470000 10871031 955859216 1774157824 -0.3170679212 0.0001103990 0.1604052484 389 1305031115.1112298965 0.0526992753 0.0471668658 0.0857079923 0.0183165077 0.0706500000 10872765 955859216 1773522944 -0.3091400564 0.0011381917 0.1613968909 390 1305031115.1432940960 0.0510723591 0.0471768799 0.0857079923 0.0183079029 0.1062440000 10874563 955859216 1772503040 -0.2908989787 0.0023152509 0.1620105058 391 1305031115.1794400215 0.0488967746 0.0471812786 0.0857079923 0.0183127486 0.1083830000 10876393 955859216 1771745280 -0.2828651071 0.0015479849 0.1638216525 392 1305031115.2113740444 0.0485995226 0.0471848966 0.0857079923 0.0183108021 0.1093980000 10878127 955859216 1771130880 -0.2747215629 -0.0002236013 0.1657958180 393 1305031115.2432971001 0.0478310995 0.0471865409 0.0857079923 0.0183181891 0.0874860000 10879925 955859216 1770348544 -0.2523530722 -0.0035283957 0.1678489596 394 1305031115.2799661160 0.0447770134 0.0471804253 0.0857079923 0.0183412261 0.0862430000 10881723 955859216 1769586688 -0.2398710251 -0.0007937195 0.1702849418 395 1305031115.3117039204 0.0433702208 0.0471707792 0.0857079923 0.0183631808 0.1078420000 10883521 955859216 1768824832 -0.2244262695 0.0002565552 0.1725632846 396 1305031115.3434259892 0.0426208600 0.0471592895 0.0857079923 0.0183479965 0.0912630000 10885287 955859216 1767952384 -0.2068124264 -0.0020458698 0.1741753966 397 1305031115.3791658878 0.0392846689 0.0471394542 0.0857079923 0.0185814821 0.0833830000 10887053 955859216 1767174144 -0.1958534420 0.0057978551 0.1763337404 398 1305031115.4112370014 0.0445244052 0.0471328837 0.0857079923 0.0185675382 0.0677480000 10888819 955859216 1768660992 -0.1897421032 0.0041053034 0.1804694831 399 1305031115.4431591034 0.0436277427 0.0471240989 0.0857079923 0.0186229827 0.0884520000 10890585 955859216 1768091648 -0.1638349146 0.0021484829 0.1844918728 400 1305031115.4792408943 0.0455412976 0.0471201419 0.0857079923 0.0186057303 0.0849910000 10892415 955859216 1767264256 -0.1466375738 0.0022001788 0.1876025200 401 1305031115.5112531185 0.0473962650 0.0471208305 0.0857079923 0.0186851678 0.0868020000 10894149 955859216 1766666240 -0.1279224902 0.0002114903 0.1898486167 402 1305031115.5436201096 0.0475931838 0.0471220055 0.0857079923 0.0187168546 0.0816720000 10895947 955859216 1765646336 -0.1071481332 -0.0015005060 0.1903450489 403 1305031115.5793149471 0.0484348349 0.0471252631 0.0857079923 0.0186954808 0.0854960000 10897777 955859216 1765036032 -0.0915829241 -0.0016208459 0.1894823760 404 1305031115.6114239693 0.0493978597 0.0471308884 0.0857079923 0.0186754312 0.1099660000 10899511 955859216 1765027840 -0.0768940821 -0.0026310626 0.1886871606 405 1305031115.6432540417 0.0482864492 0.0471337416 0.0857079923 0.0186544358 0.0871210000 10901277 955859216 1765769216 -0.0593608916 -0.0031521507 0.1873183697 406 1305031115.6792409420 0.0510977693 0.0471435052 0.0857079923 0.0186378701 0.0840350000 10903107 955859216 1766170624 -0.0442276634 -0.0041662045 0.1860321313 407 1305031115.7113199234 0.0496800803 0.0471497376 0.0857079923 0.0186568403 0.0823830000 10904873 955859216 1765789696 -0.0265427958 -0.0037471505 0.1845257133 408 1305031115.7432498932 0.0458208472 0.0471464805 0.0857079923 0.0186966234 0.1095960000 10906671 955859216 1765036032 -0.0077606277 -0.0013859812 0.1826184988 409 1305031115.7794249058 0.0483824089 0.0471495024 0.0857079923 0.0186951441 0.0860810000 10908501 955859216 1765027840 0.0079454891 -0.0024736279 0.1806039363 410 1305031115.8112769127 0.0492348373 0.0471545885 0.0857079923 0.0186942758 0.0781720000 10910235 955859216 1765027840 0.0189500432 -0.0014520959 0.1790025979 411 1305031115.8432240486 0.0459199660 0.0471515846 0.0857079923 0.0186839844 0.0802070000 10912033 955859216 1766502400 0.0345678888 0.0025447980 0.1775935739 412 1305031115.8791980743 0.0522198603 0.0471638862 0.0857079923 0.0186757119 0.0684910000 10913799 955859216 1766375424 0.0463401899 -0.0001257844 0.1768373102 413 1305031115.9111180305 0.0542636663 0.0471810770 0.0857079923 0.0186650590 0.0879010000 10915565 955859216 1765933056 0.0568722673 0.0002454389 0.1761602163 414 1305031115.9433109760 0.0514401048 0.0471913645 0.0857079923 0.0186612614 0.0867960000 10917299 955859216 1765289984 0.0702416599 0.0053606112 0.1761436462 415 1305031115.9807400703 0.0564599596 0.0472136985 0.0857079923 0.0186538149 0.0838470000 10919129 955859216 1765023744 0.0807212517 0.0069580479 0.1770207882 416 1305031116.0113790035 0.0564242117 0.0472358391 0.0857079923 0.0186992299 0.0851670000 10920863 955859216 1765027840 0.0924858004 0.0097153643 0.1776519567 417 1305031116.0431640148 0.0577102080 0.0472609575 0.0857079923 0.0186814298 0.1090770000 10922661 955859216 1765027840 0.1020447388 0.0124899298 0.1788384169 418 1305031116.0800299644 0.0638684258 0.0473006883 0.0857079923 0.0186786292 0.1034100000 10924491 955859216 1764995072 0.1108245179 0.0146128489 0.1807401627 419 1305031116.1112999916 0.0649121851 0.0473427205 0.0857079923 0.0186596903 0.0866830000 10926225 955859216 1765027840 0.1209490001 0.0170368254 0.1829633266 420 1305031116.1434469223 0.0682018325 0.0473923850 0.0857079923 0.0186404283 0.0678610000 10927991 955859216 1766375424 0.1301220953 0.0165586248 0.1851598620 421 1305031116.1795721054 0.0733039305 0.0474539327 0.0857079923 0.0186225026 0.0894190000 10929821 955859216 1765785600 0.1397743821 0.0165756475 0.1870025843 422 1305031116.2113199234 0.0742860883 0.0475175160 0.0857079923 0.0186027159 0.0885440000 10931587 955859216 1765015552 0.1491945088 0.0184883084 0.1889073402 423 1305031116.2433199883 0.0753940046 0.0475834178 0.0857079923 0.0185867774 0.0846360000 10933353 955859216 1765027840 0.1592597514 0.0184394289 0.1899433732 424 1305031116.2793850899 0.0798258409 0.0476594613 0.0857079923 0.0186022729 0.0685580000 10935215 955859216 1765027840 0.1677271873 0.0185300894 0.1896447092 425 1305031116.3113360405 0.0811082274 0.0477381643 0.0857079923 0.0185984610 0.0904860000 10936949 955859216 1765027840 0.1750361025 0.0193057265 0.1898102164 426 1305031116.3432919979 0.0811347663 0.0478165600 0.0857079923 0.0185813936 0.1166810000 10938715 955859216 1764253696 0.1823481023 0.0192320943 0.1886314005 427 1305031116.3793840408 0.0831795111 0.0478993773 0.0857079923 0.0185650151 0.1082500000 10940513 955859216 1765896192 0.1875945926 0.0177466087 0.1860355884 428 1305031116.4113330841 0.0826778486 0.0479806354 0.0857079923 0.0185464496 0.0880030000 10942311 955859216 1767657472 0.1928096861 0.0169852115 0.1841123551 429 1305031116.4433689117 0.0788587183 0.0480526123 0.0857079923 0.0185335720 0.0857460000 10944109 955859216 1769295872 0.1979369521 0.0189579725 0.1826203912 430 1305031116.4798500538 0.0750400648 0.0481153738 0.0857079923 0.0185170140 0.0577610000 10945939 955859216 1771106304 0.1997854561 0.0202399064 0.1802415997 431 1305031116.5112049580 0.0738040656 0.0481749763 0.0857079923 0.0184983934 0.1172140000 10947673 955859216 1772756992 0.1979184598 0.0189695079 0.1778686941 432 1305031116.5432620049 0.0727577135 0.0482318808 0.0857079923 0.0184774800 0.0680680000 10949439 955859216 1774387200 0.1940932423 0.0170956273 0.1760854125 433 1305031116.5793130398 0.0668456405 0.0482748687 0.0857079923 0.0184834574 0.0676550000 10951269 955859216 1776185344 0.1886123866 0.0184917022 0.1744444668 434 1305031116.6112608910 0.0637375861 0.0483104971 0.0857079923 0.0184783170 0.0686040000 10953003 955859216 1777836032 0.1813713163 0.0179702360 0.1728245467 435 1305031116.6433548927 0.0611972436 0.0483401218 0.0857079923 0.0184720174 0.0781780000 10954769 955859216 1779466240 0.1721223146 0.0175392628 0.1713844240 436 1305031116.6792809963 0.0558547452 0.0483573571 0.0857079923 0.0184588815 0.0768920000 10956663 955859216 1781264384 0.1621799320 0.0162785053 0.1705704033 437 1305031116.7116339207 0.0550516099 0.0483726758 0.0857079923 0.0184395160 0.0673690000 10958397 955859216 1782915072 0.1497761607 0.0148234246 0.1696390361 438 1305031116.7432909012 0.0551320463 0.0483881082 0.0857079923 0.0184333529 0.0761900000 10960163 955859216 1784545280 0.1356416494 0.0137386471 0.1692091227 439 1305031116.7792980671 0.0526848659 0.0483978958 0.0857079923 0.0184324505 0.0826160000 10961993 955859216 1786322944 0.1212397292 0.0119348429 0.1687262952 440 1305031116.8113429546 0.0541233756 0.0484109082 0.0857079923 0.0184718379 0.0799890000 10963759 955859216 1787961344 0.1063337922 0.0092175901 0.1677142829 441 1305031116.8460888863 0.0516107418 0.0484181641 0.0857079923 0.0185672129 0.0619630000 10965557 955859216 1787244544 0.0918315947 0.0072310707 0.1662200242 442 1305031116.8801651001 0.0498226695 0.0484213417 0.0857079923 0.0185465983 0.0625660000 10967355 955859216 1785937920 0.0784277469 0.0084500136 0.1654114425 443 1305031116.9120440483 0.0506029837 0.0484262664 0.0857079923 0.0185372143 0.0703410000 10969121 955859216 1785073664 0.0644352362 0.0072883340 0.1650854349 444 1305031116.9432959557 0.0482064858 0.0484257714 0.0857079923 0.0185299814 0.0888420000 10970887 955859216 1784205312 0.0504757389 0.0091434661 0.1646535099 445 1305031116.9793510437 0.0473617949 0.0484233804 0.0857079923 0.0185295589 0.1031870000 10972685 955859216 1783422976 0.0347445346 0.0102330884 0.1641754955 446 1305031117.0113821030 0.0477723666 0.0484219208 0.0857079923 0.0185249693 0.0696520000 10974483 955859216 1782554624 0.0197246335 0.0112591460 0.1636890471 447 1305031117.0432610512 0.0466216505 0.0484178933 0.0857079923 0.0185050688 0.0874280000 10976249 955859216 1781776384 0.0043500843 0.0150429560 0.1635498106 448 1305031117.0795199871 0.0473168120 0.0484154355 0.0857079923 0.0185085110 0.1076130000 10978079 955859216 1781014528 -0.0105243456 0.0177483261 0.1641589701 449 1305031117.1112380028 0.0499292165 0.0484188070 0.0857079923 0.0185085045 0.1201370000 10979813 955859216 1780252672 -0.0202702731 0.0178779475 0.1653503776 450 1305031117.1432180405 0.0519361533 0.0484266233 0.0857079923 0.0184909451 0.1087740000 10981611 955859216 1781739520 -0.0300592892 0.0190925617 0.1667822003 451 1305031117.1792640686 0.0516259372 0.0484337171 0.0857079923 0.0184771981 0.0872450000 10983441 955859216 1783529472 -0.0408788398 0.0229318868 0.1678797454 452 1305031117.2113609314 0.0530327931 0.0484438921 0.0857079923 0.0184797578 0.0674660000 10985207 955859216 1785327616 -0.0481001362 0.0231277607 0.1695461720 453 1305031117.2432770729 0.0538653322 0.0484558599 0.0857079923 0.0184764490 0.0884270000 10986973 955859216 1786978304 -0.0529380254 0.0241194032 0.1715922207 454 1305031117.2792990208 0.0539389849 0.0484679373 0.0857079923 0.0184617432 0.0658430000 10988803 955859216 1785937920 -0.0570104942 0.0248542428 0.1733815074 455 1305031117.3111999035 0.0554274321 0.0484832329 0.0857079923 0.0184499125 0.0849830000 10990537 955859216 1785073664 -0.0617851317 0.0231503844 0.1747752875 456 1305031117.3432428837 0.0575575754 0.0485031328 0.0857079923 0.0184397256 0.0885030000 10992335 955859216 1784205312 -0.0658239648 0.0197045822 0.1754980981 457 1305031117.3794538975 0.0583061203 0.0485245835 0.0857079923 0.0184301440 0.1249000000 10994165 955859216 1783427072 -0.0680817813 0.0157964025 0.1755831242 458 1305031117.4112210274 0.0588613115 0.0485471528 0.0857079923 0.0184111328 0.1072590000 10995931 955859216 1784913920 -0.0698801503 0.0116121937 0.1751594394 459 1305031117.4432740211 0.0583697036 0.0485685527 0.0857079923 0.0183922724 0.1087040000 10997697 955859216 1786691584 -0.0709927678 0.0073723998 0.1744207144 460 1305031117.4794030190 0.0550247431 0.0485825879 0.0857079923 0.0183772772 0.0778560000 10999527 955859216 1785733120 -0.0707123056 0.0037952717 0.1735469103 461 1305031117.5113248825 0.0534933247 0.0485932402 0.0857079923 0.0183589693 0.0688300000 11001293 955859216 1784946688 -0.0713877603 -0.0013584048 0.1726144850 462 1305031117.5442850590 0.0512419939 0.0485989735 0.0857079923 0.0183415098 0.0881030000 11003027 955859216 1784078336 -0.0712932944 -0.0063207112 0.1717947572 463 1305031117.5791549683 0.0456537269 0.0485926122 0.0857079923 0.0183234930 0.1065480000 11004889 955859216 1783189504 -0.0719389096 -0.0100121712 0.1715892553 464 1305031117.6111590862 0.0426526964 0.0485798107 0.0857079923 0.0183048713 0.1084810000 11006623 955859216 1782411264 -0.0721623600 -0.0142955799 0.1727912277 465 1305031117.6432840824 0.0410451256 0.0485636071 0.0857079923 0.0182873829 0.0781970000 11008421 955859216 1783787520 -0.0727182403 -0.0203756168 0.1746759564 466 1305031117.6792619228 0.0365206413 0.0485377638 0.0857079923 0.0182725917 0.0698350000 11010251 955859216 1785708544 -0.0727958083 -0.0260464586 0.1773905903 467 1305031117.7112150192 0.0354801789 0.0485098032 0.0857079923 0.0182540697 0.0887970000 11011985 955859216 1787326464 -0.0725437701 -0.0327744894 0.1808485389 468 1305031117.7431840897 0.0373411663 0.0484859386 0.0857079923 0.0182412717 0.1065030000 11013751 955859216 1785454592 -0.0689587817 -0.0440770239 0.1856163591 469 1305031117.7794671059 0.0318912156 0.0484505554 0.0857079923 0.0182218928 0.0646170000 11015581 955859216 1786945536 -0.0701917186 -0.0498121381 0.1887692362 470 1305031117.8113200665 0.0296607614 0.0484105771 0.0857079923 0.0182050911 0.0669890000 11017347 955859216 1786212352 -0.0697574019 -0.0566386133 0.1925735772 471 1305031117.8433070183 0.0328593552 0.0483775597 0.0857079923 0.0182010840 0.0867950000 11019049 955859216 1784967168 -0.0665834621 -0.0695638582 0.1975079328 472 1305031117.8794670105 0.0258255638 0.0483297800 0.0857079923 0.0181843548 0.0859890000 11020879 955859216 1783930880 -0.0680004433 -0.0747441724 0.2005658895 473 1305031117.9114069939 0.0243476313 0.0482790778 0.0857079923 0.0181665248 0.0861480000 11022613 955859216 1783062528 -0.0698271021 -0.0818164721 0.2042949647 474 1305031117.9432721138 0.0266092364 0.0482333608 0.0857079923 0.0181488762 0.1038610000 11024379 955859216 1782026240 -0.0684438199 -0.0930604190 0.2098677456 475 1305031117.9792630672 0.0210354757 0.0481761021 0.0857079923 0.0181434838 0.0877950000 11026209 955859216 1780899840 -0.0709362254 -0.0979897231 0.2141224146 476 1305031118.0112280846 0.0242669899 0.0481258729 0.0857079923 0.0181313550 0.0798180000 11027943 955859216 1780125696 -0.0711356327 -0.1094147786 0.2202248126 477 1305031118.0435490608 0.0266681854 0.0480808882 0.0857079923 0.0181142312 0.0698690000 11029741 955859216 1778995200 -0.0720262825 -0.1200120449 0.2256989032 478 1305031118.0793690681 0.0229905471 0.0480283980 0.0857079923 0.0180978216 0.0850430000 11031571 955859216 1777963008 -0.0735947564 -0.1259958744 0.2300356328 479 1305031118.1112170219 0.0249978956 0.0479803176 0.0857079923 0.0180877114 0.0795280000 11033305 955859216 1777041408 -0.0719676390 -0.1365210265 0.2355450094 480 1305031118.1432559490 0.0262280572 0.0479350004 0.0857079923 0.0180710138 0.0775480000 11035103 955859216 1776316416 -0.0737620369 -0.1449745595 0.2399408221 481 1305031118.1793229580 0.0256217364 0.0478886111 0.0857079923 0.0180541133 0.0879180000 11036933 955859216 1775443968 -0.0752427876 -0.1533114910 0.2440870106 482 1305031118.2112019062 0.0297721904 0.0478510251 0.0857079923 0.0180454337 0.0865050000 11038667 955859216 1774665728 -0.0766548663 -0.1652494520 0.2486481071 483 1305031118.2431728840 0.0304783061 0.0478150568 0.0857079923 0.0180365996 0.0798200000 11040433 955859216 1776152576 -0.0787816420 -0.1722393036 0.2517297566 484 1305031118.2791941166 0.0303797722 0.0477790335 0.0857079923 0.0180419800 0.1104610000 11042263 955859216 1773412352 -0.0785308778 -0.1811717600 0.2553820312 485 1305031118.3112990856 0.0330221169 0.0477486068 0.0857079923 0.0180243918 0.1064890000 11044029 955859216 1772634112 -0.0795439929 -0.1902860701 0.2588564456 486 1305031118.3433239460 0.0323264450 0.0477168740 0.0857079923 0.0180167890 0.0902280000 11045795 955859216 1771872256 -0.0792080164 -0.1948966980 0.2616495490 487 1305031118.3792080879 0.0324719250 0.0476855702 0.0857079923 0.0180003709 0.0791450000 11047625 955859216 1771237376 -0.0815712139 -0.1988814473 0.2649490237 488 1305031118.4112958908 0.0349290185 0.0476594297 0.0857079923 0.0179968953 0.0678160000 11049391 955859216 1772724224 -0.0846491829 -0.2029438466 0.2686087191 489 1305031118.4457030296 0.0338956378 0.0476312829 0.0857079923 0.0179800688 0.0694440000 11051189 955859216 1772142592 -0.0817058980 -0.2051190138 0.2717375457 490 1305031118.4792850018 0.0342131071 0.0476038989 0.0857079923 0.0179621757 0.1057630000 11052955 955859216 1771491328 -0.0810889527 -0.2075108439 0.2750673890 491 1305031118.5112550259 0.0354854129 0.0475792176 0.0857079923 0.0179465175 0.0693990000 11054721 955859216 1770856448 -0.0805626363 -0.2094397247 0.2773904502 492 1305031118.5451989174 0.0351072028 0.0475538680 0.0857079923 0.0179406485 0.1037070000 11056519 955859216 1769836544 -0.0798031166 -0.2078072578 0.2794696093 493 1305031118.5792849064 0.0323330089 0.0475229941 0.0857079923 0.0179227352 0.1099090000 11058349 955859216 1769078784 -0.0746550933 -0.2035778463 0.2799593508 494 1305031118.6161420345 0.0355457552 0.0474987486 0.0857079923 0.0179074218 0.0861660000 11060179 955859216 1768316928 -0.0755317062 -0.2019762397 0.2802207172 495 1305031118.6453309059 0.0321552120 0.0474677516 0.0857079923 0.0178920027 0.1074110000 11061913 955859216 1767297024 -0.0726387650 -0.1958480328 0.2789951265 496 1305031118.6792950630 0.0353614427 0.0474433437 0.0857079923 0.0178789282 0.1079510000 11063743 955859216 1766539264 -0.0733455271 -0.1919589788 0.2783472240 497 1305031118.7114210129 0.0376687832 0.0474236766 0.0857079923 0.0178717414 0.1264220000 11065477 955859216 1765924864 -0.0742825419 -0.1877169609 0.2763465047 498 1305031118.7468008995 0.0433043912 0.0474154049 0.0857079923 0.0178682166 0.1278010000 11067307 955859216 1767264256 -0.0747812167 -0.1839900464 0.2737567723 499 1305031118.7792770863 0.0363260321 0.0473931817 0.0857079923 0.0178989532 0.0871000000 11069105 955859216 1769201664 -0.0728288144 -0.1687424779 0.2701324821 500 1305031118.8112208843 0.0346533433 0.0473677021 0.0857079923 0.0179065143 0.0844260000 11070839 955859216 1770852352 -0.0681697577 -0.1597771049 0.2665487826 501 1305031118.8467741013 0.0437726602 0.0473605263 0.0857079923 0.0179219490 0.1117390000 11072669 955859216 1772470272 -0.0679339319 -0.1573760509 0.2615138590 502 1305031118.8792080879 0.0379070081 0.0473416946 0.0857079923 0.0179730231 0.1085440000 11074467 955859216 1774280704 -0.0665471181 -0.1416222751 0.2548277974 503 1305031118.9111769199 0.0360294953 0.0473192052 0.0857079923 0.0179778374 0.1076970000 11076201 955859216 1775931392 -0.0656421632 -0.1301116496 0.2486011535 504 1305031118.9470090866 0.0416600890 0.0473079768 0.0857079923 0.0179622003 0.1068380000 11078031 955859216 1777549312 -0.0668668747 -0.1220373735 0.2418139428 505 1305031118.9793939590 0.0390646309 0.0472916533 0.0857079923 0.0179573308 0.1061630000 11079829 955859216 1779326976 -0.0676822364 -0.1091382354 0.2350168824 506 1305031119.0113630295 0.0384856127 0.0472742501 0.0857079923 0.0179459419 0.1097470000 11081563 955859216 1781010432 -0.0687984899 -0.0978390723 0.2288035154 507 1305031119.0471799374 0.0442219302 0.0472682297 0.0857079923 0.0179324146 0.0865890000 11083393 955859216 1782628352 -0.0710247904 -0.0896785408 0.2222650647 508 1305031119.0792229176 0.0458571687 0.0472654520 0.0857079923 0.0179197990 0.0865530000 11085127 955859216 1784438784 -0.0728819072 -0.0813410506 0.2156298757 509 1305031119.1113278866 0.0459996574 0.0472629652 0.0857079923 0.0179053879 0.1108630000 11086925 955859216 1786068992 -0.0739981532 -0.0719301030 0.2088817358 510 1305031119.1476290226 0.0486834385 0.0472657504 0.0857079923 0.0178934530 0.1090090000 11088755 955859216 1787707392 -0.0735897273 -0.0617497675 0.2022980303 511 1305031119.1792619228 0.0486244671 0.0472684094 0.0857079923 0.0178874146 0.0840570000 11090521 955859216 1786707968 -0.0742140412 -0.0524153374 0.1958940923 512 1305031119.2113640308 0.0490238480 0.0472718380 0.0857079923 0.0178754048 0.0855200000 11092287 955859216 1785688064 -0.0732475370 -0.0441818088 0.1896460354 513 1305031119.2476599216 0.0501809753 0.0472775088 0.0857079923 0.0178648571 0.1266080000 11135077 955859216 1783832576 -0.0731975809 -0.0326309539 0.1834800392 514 1305031119.2792439461 0.0498238318 0.0472824627 0.0857079923 0.0178497585 0.1266800000 11220811 955859216 1782788096 -0.0738141388 -0.0229248777 0.1781699657 515 1305031119.3112120628 0.0532733612 0.0472940955 0.0857079923 0.0178336506 0.1068440000 11222577 955859216 1781993472 -0.0738569871 -0.0176852532 0.1742244661 516 1305031119.3477499485 0.0545515940 0.0473081605 0.0857079923 0.0178189033 0.0845220000 11224407 955859216 1781010432 -0.0741997883 -0.0065800608 0.1689984649 517 1305031119.3792390823 0.0538267232 0.0473207689 0.0857079923 0.0178073398 0.0870770000 11226173 955859216 1780252672 -0.0733713508 0.0037230849 0.1646648496 518 1305031119.4114921093 0.0538390689 0.0473333525 0.0857079923 0.0177971652 0.1089300000 11227939 955859216 1779232768 -0.0723882541 0.0138832349 0.1607297361 519 1305031119.4477260113 0.0608540513 0.0473594039 0.0857079923 0.0177813320 0.0857420000 11229801 955859216 1778106368 -0.0718319193 0.0195678025 0.1577225178 520 1305031119.4792668819 0.0594030209 0.0473825647 0.0857079923 0.0177685616 0.1278550000 11231503 955859216 1777332224 -0.0742524415 0.0311613306 0.1525929570 521 1305031119.5112578869 0.0591670349 0.0474051837 0.0857079923 0.0177562324 0.1266260000 11233269 955859216 1778708480 -0.0746192783 0.0427319370 0.1488931626 522 1305031119.5474140644 0.0662141591 0.0474412162 0.0857079923 0.0177392572 0.0885360000 11235131 955859216 1780469760 -0.0747654215 0.0485563315 0.1462584883 523 1305031119.5795691013 0.0636909977 0.0474722865 0.0857079923 0.0177384102 0.0890830000 11236897 955859216 1782120448 -0.0754626915 0.0631696954 0.1423847973 524 1305031119.6150240898 0.0678249076 0.0475111274 0.0857079923 0.0177281762 0.0858180000 11238727 955859216 1783898112 -0.0760583952 0.0694909096 0.1406186521 525 1305031119.6488890648 0.0704426542 0.0475548065 0.0857079923 0.0177278035 0.1272040000 11240525 955859216 1785548800 -0.0786192939 0.0816739872 0.1375741363 526 1305031119.6792080402 0.0706098825 0.0475986374 0.0857079923 0.0177197398 0.1092440000 11242227 955859216 1787359232 -0.0795346051 0.0934119448 0.1355377585 527 1305031119.7152490616 0.0752942860 0.0476511909 0.0857079923 0.0177055587 0.0834170000 11244057 955859216 1786314752 -0.0799450651 0.0991649032 0.1350348890 528 1305031119.7471930981 0.0821934342 0.0477166118 0.0857079923 0.0176986692 0.0682770000 11245855 955859216 1785335808 -0.0822453424 0.1040566713 0.1340202391 529 1305031119.7791690826 0.0814825371 0.0477804415 0.0857079923 0.0176841706 0.1051110000 11247621 955859216 1784438784 -0.0842686594 0.1163479388 0.1319862306 530 1305031119.8145709038 0.0865432024 0.0478535788 0.0865432024 0.0176742424 0.1077290000 11249387 955859216 1782657024 -0.0843334422 0.1202437431 0.1315652877 531 1305031119.8474450111 0.0876027942 0.0479284361 0.0876027942 0.0176645311 0.0890820000 11251217 955859216 1784295424 -0.0832769349 0.1330360770 0.1296174526 532 1305031119.8792319298 0.0914574936 0.0480102576 0.0914574936 0.0176583734 0.0840710000 11252951 955859216 1785929728 -0.0847391784 0.1364488453 0.1280627251 533 1305031119.9114239216 0.0890016034 0.0480871644 0.0914574936 0.0176666612 0.0889340000 11254717 955859216 1787580416 -0.0859069005 0.1490331292 0.1251257360 534 1305031119.9474620819 0.0938686579 0.0481728976 0.0938686579 0.0176540625 0.0658560000 11256579 955859216 1786826752 -0.0867024437 0.1535002142 0.1239535734 535 1305031119.9795460701 0.0958611742 0.0482620345 0.0958611742 0.0176406174 0.0832580000 11258345 955859216 1785606144 -0.0877397954 0.1578083932 0.1224519685 536 1305031120.0152831078 0.0969451442 0.0483528612 0.0969451442 0.0176441176 0.0897110000 11260143 955859216 1784565760 -0.0880787447 0.1632998884 0.1214482486 537 1305031120.0473101139 0.0989100635 0.0484470087 0.0989100635 0.0176400797 0.0793510000 11261941 955859216 1783549952 -0.0902325436 0.1676868796 0.1204663217 538 1305031120.0794179440 0.1001818180 0.0485431701 0.1001818180 0.0176381995 0.0709500000 11263707 955859216 1782681600 -0.0925750658 0.1683253646 0.1195188612 539 1305031120.1152489185 0.1000608355 0.0486387502 0.1001818180 0.0176289984 0.0857340000 11265505 955859216 1781534720 -0.0931326225 0.1697360128 0.1190446541 540 1305031120.1481750011 0.0980544761 0.0487302608 0.1001818180 0.0176276932 0.1070160000 11267303 955859216 1780502528 -0.0929054767 0.1708904356 0.1187407821 541 1305031120.1792609692 0.0965609625 0.0488186724 0.1001818180 0.0176181807 0.0665940000 11269037 955859216 1779486720 -0.0924916491 0.1691221744 0.1182577312 542 1305031120.2152600288 0.0946246982 0.0489031854 0.1001818180 0.0176033859 0.0768630000 11270867 955859216 1778470912 -0.0920657516 0.1656173170 0.1176318824 543 1305031120.2480180264 0.0896583498 0.0489782409 0.1001818180 0.0175884321 0.0570100000 11272665 955859216 1779851264 -0.0917870477 0.1630966067 0.1172449887 544 1305031120.2794411182 0.0854888409 0.0490453560 0.1001818180 0.0175729535 0.0705540000 11274431 955859216 1778946048 -0.0930799991 0.1596570909 0.1170864850 545 1305031120.3152129650 0.0813851878 0.0491046952 0.1001818180 0.0175570463 0.0855320000 11276229 955859216 1778233344 -0.0940054655 0.1552526653 0.1175798327 546 1305031120.3477969170 0.0752107799 0.0491525085 0.1001818180 0.0175411789 0.0890530000 11278027 955859216 1777201152 -0.0950521007 0.1494152993 0.1188365668 547 1305031120.3794460297 0.0720699281 0.0491944051 0.1001818180 0.0175257218 0.0880870000 11279793 955859216 1776185344 -0.0951484367 0.1429098845 0.1213700920 548 1305031120.4154899120 0.0759054571 0.0492431479 0.1001818180 0.0175573231 0.0842890000 11281591 955859216 1775058944 -0.0933033526 0.1253058612 0.1262926757 549 1305031120.4474329948 0.0675616041 0.0492765148 0.1001818180 0.0175472365 0.0673900000 11283389 955859216 1774174208 -0.0933261067 0.1204094440 0.1288319528 550 1305031120.4794321060 0.0639653504 0.0493032218 0.1001818180 0.0175315101 0.0517510000 11285155 955859216 1773395968 -0.0920409113 0.1154906452 0.1326776892 551 1305031120.5148770809 0.0618359447 0.0493259672 0.1001818180 0.0175205265 0.0644620000 11286953 955859216 1774772224 -0.0906150565 0.1067182943 0.1365311593 552 1305031120.5478069782 0.0569906160 0.0493398524 0.1001818180 0.0175072684 0.0678260000 11288751 955859216 1774026752 -0.0892222896 0.0984674841 0.1407787055 553 1305031120.5795590878 0.0550161228 0.0493501169 0.1001818180 0.0174963250 0.0985410000 11290517 955859216 1773010944 -0.0869752318 0.0920168310 0.1455958337 554 1305031120.6152710915 0.0550705269 0.0493604426 0.1001818180 0.0174895154 0.1114990000 11292283 955859216 1771995136 -0.0813042819 0.0821639597 0.1510424018 555 1305031120.6473538876 0.0492554456 0.0493602534 0.1001818180 0.0174764348 0.0853800000 11294081 955859216 1771200512 -0.0821039751 0.0758773983 0.1546406001 556 1305031120.6793179512 0.0470932499 0.0493561760 0.1001818180 0.0174847321 0.0886640000 11295815 955859216 1770475520 -0.0802368000 0.0704752430 0.1591169536 557 1305031120.7145531178 0.0451250225 0.0493485797 0.1001818180 0.0174695015 0.1057700000 11297645 955859216 1769455616 -0.0791588649 0.0636119843 0.1635433882 558 1305031120.7473959923 0.0425899513 0.0493364675 0.1001818180 0.0174584662 0.0991790000 11299443 955859216 1768312832 -0.0761225075 0.0535343140 0.1686190069 559 1305031120.7799079418 0.0408563241 0.0493212973 0.1001818180 0.0174460553 0.0914310000 11301241 955859216 1767297024 -0.0761902556 0.0461834446 0.1722435206 560 1305031120.8149440289 0.0398925096 0.0493044602 0.1001818180 0.0174394553 0.1068170000 11303039 955859216 1766539264 -0.0762173831 0.0386257209 0.1760565042 561 1305031120.8479421139 0.0353112742 0.0492795169 0.1001818180 0.0174242667 0.1092110000 11304837 955859216 1765666816 -0.0768949836 0.0325382650 0.1796291769 562 1305031120.8834540844 0.0372848697 0.0492581741 0.1001818180 0.0174165850 0.0840560000 11306635 955859216 1765036032 -0.0762060881 0.0194981638 0.1834509373 563 1305031120.9154539108 0.0348177776 0.0492325251 0.1001818180 0.0174123941 0.0658210000 11308401 955859216 1766391808 -0.0778444856 0.0143330814 0.1862285435 564 1305031120.9475090504 0.0321974866 0.0492023211 0.1001818180 0.0173974044 0.0837230000 11310167 955859216 1765740544 -0.0793729573 0.0056519681 0.1893300563 565 1305031120.9833900928 0.0320493951 0.0491719619 0.1001818180 0.0173849020 0.0863670000 11311997 955859216 1765015552 -0.0804507807 -0.0029368885 0.1924200207 566 1305031121.0150289536 0.0328757279 0.0491431700 0.1001818180 0.0173764227 0.0679970000 11313731 955859216 1765027840 -0.0817474946 -0.0125248954 0.1951963603 567 1305031121.0477550030 0.0284637474 0.0491066984 0.1001818180 0.0173617430 0.0839760000 11315561 955859216 1765027840 -0.0827461034 -0.0180227868 0.1974080950 568 1305031121.0831170082 0.0305558071 0.0490740383 0.1001818180 0.0173514842 0.1105420000 11317359 955859216 1765027840 -0.0843185410 -0.0295709930 0.2002264708 569 1305031121.1148779392 0.0288697351 0.0490385299 0.1001818180 0.0173371607 0.0839130000 11319093 955859216 1765027840 -0.0847985074 -0.0362792723 0.2018806934 570 1305031121.1473550797 0.0253011342 0.0489968853 0.1001818180 0.0173230679 0.1072580000 11320891 955859216 1765027840 -0.0853260458 -0.0431957282 0.2039508820 571 1305031121.1832809448 0.0273888297 0.0489590429 0.1001818180 0.0173079916 0.1279610000 11322721 955859216 1765027840 -0.0874506384 -0.0539253131 0.2066332847 572 1305031121.2114310265 0.0256731715 0.0489183333 0.1001818180 0.0172949115 0.0857380000 11324391 955859216 1766502400 -0.0877952576 -0.0605416670 0.2086597234 573 1305031121.2472009659 0.0225488022 0.0488723132 0.1001818180 0.0172812853 0.0719250000 11326221 955859216 1768534016 -0.0879336521 -0.0671523586 0.2114105076 574 1305031121.2828760147 0.0251697488 0.0488310195 0.1001818180 0.0172662712 0.0822840000 11328051 955859216 1770311680 -0.0897939056 -0.0778976157 0.2150490582 575 1305031121.3135879040 0.0251585729 0.0487898500 0.1001818180 0.0172582022 0.0705480000 11329785 955859216 1771962368 -0.0889779106 -0.0878902450 0.2181634903 576 1305031121.3475399017 0.0243945085 0.0487474970 0.1001818180 0.0172474725 0.0859680000 11331583 955859216 1773613056 -0.0900971889 -0.0955503359 0.2216850519 577 1305031121.3832480907 0.0241046119 0.0487047884 0.1001818180 0.0172409881 0.0700040000 11333413 955859216 1775390720 -0.0906874165 -0.1022764444 0.2246289253 578 1305031121.4143280983 0.0242679007 0.0486625100 0.1001818180 0.0172274200 0.0841760000 11335147 955859216 1777041408 -0.0904589295 -0.1122203320 0.2275237739 579 1305031121.4473190308 0.0248483904 0.0486213803 0.1001818180 0.0172188106 0.0706320000 11336945 955859216 1778704384 -0.0922228172 -0.1177550703 0.2306455374 580 1305031121.4830150604 0.0250930395 0.0485808142 0.1001818180 0.0172180398 0.0876290000 11338743 955859216 1780469760 -0.0922279879 -0.1249585226 0.2332722396 581 1305031121.5141639709 0.0270600021 0.0485437732 0.1001818180 0.0172079224 0.0866030000 11340477 955859216 1782120448 -0.0937199965 -0.1354478449 0.2361808121 582 1305031121.5472700596 0.0284636877 0.0485092713 0.1001818180 0.0172014998 0.0867750000 11342307 955859216 1783783424 -0.0954852179 -0.1406085044 0.2388652712 583 1305031121.5832130909 0.0293710697 0.0484764442 0.1001818180 0.0171893484 0.1101000000 11344137 955859216 1785548800 -0.0966901258 -0.1492107660 0.2418213487 584 1305031121.6147189140 0.0308562201 0.0484462726 0.1001818180 0.0171758782 0.0853700000 11345871 955859216 1787199488 -0.0981651694 -0.1588473320 0.2443324775 585 1305031121.6471829414 0.0311657451 0.0484167332 0.1001818180 0.0171681073 0.0692380000 11347637 955859216 1786212352 -0.0978928730 -0.1644012332 0.2461388111 586 1305031121.6832110882 0.0334181525 0.0483911384 0.1001818180 0.0171598458 0.0673220000 11349499 955859216 1784967168 -0.0998946801 -0.1696934998 0.2490309030 587 1305031121.7145280838 0.0362290666 0.0483704194 0.1001818180 0.0171458145 0.0872780000 11351233 955859216 1783930880 -0.1024658531 -0.1791168749 0.2517452240 588 1305031121.7471449375 0.0361155309 0.0483495777 0.1001818180 0.0171330330 0.0681350000 11352999 955859216 1783062528 -0.1007501334 -0.1874997616 0.2554515600 589 1305031121.7828710079 0.0366255082 0.0483296727 0.1001818180 0.0171190259 0.0658120000 11354829 955859216 1784422400 -0.1001176611 -0.1938009262 0.2589545548 590 1305031121.8115448952 0.0372473560 0.0483108891 0.1001818180 0.0171085273 0.0666000000 11356531 955859216 1783451648 -0.0991686136 -0.1996530592 0.2619698644 591 1305031121.8473351002 0.0373657756 0.0482923694 0.1001818180 0.0170955206 0.0670360000 11358361 955859216 1782792192 -0.0968717784 -0.2042424083 0.2652663589 592 1305031121.8821229935 0.0369662158 0.0482732374 0.1001818180 0.0170811233 0.0841480000 11360159 955859216 1781661696 -0.0954188779 -0.2081924677 0.2679134905 593 1305031121.9149429798 0.0375907235 0.0482552231 0.1001818180 0.0170676609 0.0995810000 11361957 955859216 1780629504 -0.0955973491 -0.2105959654 0.2697221935 594 1305031121.9473180771 0.0391721688 0.0482399317 0.1001818180 0.0170550466 0.0763010000 11363723 955859216 1779503104 -0.0964501947 -0.2124895602 0.2707681060 595 1305031121.9829349518 0.0381392725 0.0482229558 0.1001818180 0.0170414373 0.0675660000 11365553 955859216 1780867072 -0.0950747356 -0.2115970850 0.2713223994 596 1305031122.0144240856 0.0387781784 0.0482071089 0.1001818180 0.0170280333 0.0822950000 11367319 955859216 1779961856 -0.0960082412 -0.2093651444 0.2709994614 597 1305031122.0473060608 0.0407561623 0.0481946282 0.1001818180 0.0170142436 0.1088920000 11369085 955859216 1778978816 -0.0969376341 -0.2068875283 0.2698810995 598 1305031122.0829689503 0.0416446142 0.0481836750 0.1001818180 0.0170000681 0.1079960000 11370915 955859216 1780359168 -0.0973041654 -0.2023884505 0.2679090798 599 1305031122.1146879196 0.0422757193 0.0481738120 0.1001818180 0.0169866714 0.1091090000 11372649 955859216 1782247424 -0.0976628140 -0.1964166164 0.2651650012 600 1305031122.1507480145 0.0387776047 0.0481581517 0.1001818180 0.0169820876 0.1072790000 11374479 955859216 1784025088 -0.0980707556 -0.1797813177 0.2611171305 601 1305031122.1830520630 0.0402740128 0.0481450333 0.1001818180 0.0169805298 0.0859420000 11376277 955859216 1785675776 -0.0970098451 -0.1752893478 0.2578392923 602 1305031122.2149689198 0.0373225994 0.0481270558 0.1001818180 0.0170131223 0.1066390000 11378011 955859216 1787326464 -0.0991988257 -0.1575942636 0.2538770139 603 1305031122.2513549328 0.0407995060 0.0481149040 0.1001818180 0.0170005079 0.0866950000 11379873 955859216 1786462208 -0.0984709933 -0.1509923041 0.2505617440 604 1305031122.2838659286 0.0395100079 0.0481006575 0.1001818180 0.0169923012 0.1071780000 11381671 955859216 1783771136 -0.0985744148 -0.1396631300 0.2453856021 605 1305031122.3143088818 0.0375664383 0.0480832456 0.1001818180 0.0170115845 0.0873560000 11383373 955859216 1782677504 -0.1004018337 -0.1237712502 0.2415934652 606 1305031122.3513510227 0.0425568298 0.0480741261 0.1001818180 0.0170050461 0.1061230000 11385203 955859216 1781645312 -0.0995581895 -0.1185696870 0.2375111133 607 1305031122.3826780319 0.0398943760 0.0480606504 0.1001818180 0.0169949050 0.1246380000 11387001 955859216 1780629504 -0.0962821916 -0.1081445515 0.2320280373 608 1305031122.4150080681 0.0430899300 0.0480524748 0.1001818180 0.0169933358 0.1285760000 11388703 955859216 1779503104 -0.0951208025 -0.1034610122 0.2269632518 609 1305031122.4512720108 0.0439857468 0.0480457971 0.1001818180 0.0169822374 0.1257460000 11390565 955859216 1778470912 -0.0929080918 -0.0924517736 0.2207998484 610 1305031122.4833879471 0.0424747281 0.0480366642 0.1001818180 0.0169712354 0.1084190000 11392331 955859216 1779851264 -0.0902468190 -0.0825476050 0.2152613699 611 1305031122.5151350498 0.0457188413 0.0480328707 0.1001818180 0.0169634621 0.0830290000 11394097 955859216 1781612544 -0.0895230472 -0.0770816356 0.2106410414 612 1305031122.5515100956 0.0453427583 0.0480284751 0.1001818180 0.0169546027 0.0892990000 11395927 955859216 1783390208 -0.0867583975 -0.0636928901 0.2044949234 613 1305031122.5832169056 0.0461797081 0.0480254592 0.1001818180 0.0169418252 0.1020080000 11397693 955859216 1785049088 -0.0873150602 -0.0546335056 0.1991454661 614 1305031122.6150169373 0.0505967438 0.0480296469 0.1001818180 0.0169343104 0.1288330000 11399427 955859216 1786699776 -0.0883742496 -0.0500714630 0.1945955157 615 1305031122.6488099098 0.0525234416 0.0480369539 0.1001818180 0.0169210242 0.1253120000 11401257 955859216 1785724928 -0.0885847285 -0.0387410857 0.1884602606 616 1305031122.6834199429 0.0519418642 0.0480432931 0.1001818180 0.0169075175 0.0887900000 11403055 955859216 1787088896 -0.0883297622 -0.0276977979 0.1833671778 617 1305031122.7152190208 0.0527955629 0.0480509953 0.1001818180 0.0168958759 0.0865540000 11404789 955859216 1786195968 -0.0878750533 -0.0183699932 0.1791237444 618 1305031122.7513089180 0.0555180125 0.0480630778 0.1001818180 0.0168913377 0.0857370000 11406651 955859216 1784573952 -0.0871682912 -0.0067027453 0.1751100570 619 1305031122.7834379673 0.0538578853 0.0480724394 0.1001818180 0.0168825026 0.0827510000 11408417 955859216 1782779904 -0.0861292481 0.0065256469 0.1718125045 620 1305031122.8125650883 0.0579705685 0.0480884041 0.1001818180 0.0168706914 0.0821350000 11410151 955859216 1781764096 -0.0872962400 0.0124478918 0.1698915511 621 1305031122.8514859676 0.0631189346 0.0481126079 0.1001818180 0.0168705739 0.0957890000 11412013 955859216 1780764672 -0.0872409046 0.0190869905 0.1674679071 622 1305031122.8837749958 0.0611771718 0.0481336120 0.1001818180 0.0168636499 0.1179190000 11413811 955859216 1779351552 -0.0888412371 0.0315310992 0.1640024632 623 1305031122.9145851135 0.0654340908 0.0481613816 0.1001818180 0.0168564156 0.0881470000 11415513 955859216 1778372608 -0.0907477960 0.0352568440 0.1620373875 624 1305031122.9514129162 0.0709382966 0.0481978831 0.1001818180 0.0168444949 0.0886070000 11417375 955859216 1777225728 -0.0922781229 0.0400499962 0.1596967280 625 1305031122.9830000401 0.0692772344 0.0482316101 0.1001818180 0.0168361219 0.0845770000 11419141 955859216 1776193536 -0.0934274048 0.0508657768 0.1565094441 626 1305031123.0154619217 0.0727815852 0.0482708273 0.1001818180 0.0168233430 0.0670880000 11420875 955859216 1777573888 -0.0932547674 0.0549054369 0.1546062380 627 1305031123.0518379211 0.0773295388 0.0483171729 0.1001818180 0.0168150308 0.0854500000 11422737 955859216 1776828416 -0.0920874253 0.0601209328 0.1519275904 628 1305031123.0829920769 0.0747443959 0.0483592545 0.1001818180 0.0168061435 0.0870970000 11424503 955859216 1775812608 -0.0924757794 0.0720276460 0.1480569988 629 1305031123.1139390469 0.0738648549 0.0483998039 0.1001818180 0.0168003932 0.0854440000 11426205 955859216 1774686208 -0.0923918262 0.0827214122 0.1455909908 630 1305031123.1508400440 0.0803043321 0.0484504460 0.1001818180 0.0167875762 0.0894560000 11428067 955859216 1773654016 -0.0929191038 0.0869263932 0.1445930302 631 1305031123.1821761131 0.0799549744 0.0485003740 0.1001818180 0.0167855147 0.0841910000 11429833 955859216 1772785664 -0.0931954160 0.0982756913 0.1424754262 632 1305031123.2147240639 0.0800594985 0.0485503093 0.1001818180 0.0167757779 0.0870220000 11431599 955859216 1771880448 -0.0924457237 0.1095126197 0.1411954314 633 1305031123.2506411076 0.0873826370 0.0486116558 0.1001818180 0.0167799637 0.0887740000 11433429 955859216 1770860544 -0.0932050645 0.1150600538 0.1414422989 634 1305031123.2823629379 0.0882540047 0.0486741831 0.1001818180 0.0167692571 0.1082530000 11435195 955859216 1769844736 -0.0945147648 0.1263401210 0.1409232020 635 1305031123.3209919930 0.0958819687 0.0487485261 0.1001818180 0.0167602383 0.0864960000 11437057 955859216 1770209280 -0.0956451744 0.1306382567 0.1411174238 636 1305031123.3504929543 0.0996228382 0.0488285172 0.1001818180 0.0167499727 0.0820150000 11438791 955859216 1768939520 -0.0954033211 0.1365938932 0.1411955506 637 1305031123.3822629452 0.0978521407 0.0489054773 0.1001818180 0.0167388670 0.0866030000 11440557 955859216 1767686144 -0.0943855196 0.1493801773 0.1392624229 638 1305031123.4213430882 0.1053151339 0.0489938937 0.1053151339 0.0167273472 0.0668620000 11442419 955859216 1766780928 -0.0952351615 0.1524494290 0.1389300525 639 1305031123.4512660503 0.1095893756 0.0490887223 0.1095893756 0.0167198291 0.0671100000 11444121 955859216 1765785600 -0.0954496190 0.1564760655 0.1385501176 640 1305031123.4836049080 0.1130857691 0.0491887177 0.1130857691 0.0167091264 0.1003700000 11445919 955859216 1765023744 -0.0957621336 0.1616163552 0.1379773468 641 1305031123.5197250843 0.1186737344 0.0492971187 0.1186737344 0.0166980482 0.0692240000 11447717 955859216 1765036032 -0.0960287824 0.1663167626 0.1374186724 642 1305031123.5515730381 0.1214979589 0.0494095810 0.1214979589 0.0166854618 0.0700450000 11449515 955859216 1765019648 -0.0958632603 0.1710212082 0.1365585178 643 1305031123.5796160698 0.1133481786 0.0495090190 0.1214979589 0.0166801755 0.0865310000 11451185 955859216 1765019648 -0.0915805921 0.1892672330 0.1326484233 644 1305031123.6203870773 0.1200043261 0.0496184837 0.1214979589 0.0166717208 0.0868940000 11453079 955859216 1765052416 -0.0925410166 0.1912293583 0.1327039450 645 1305031123.6524300575 0.1228123009 0.0497319625 0.1228123009 0.0166604011 0.1046630000 11454845 955859216 1765052416 -0.0919869095 0.1954892278 0.1325259507 646 1305031123.6837849617 0.1250501871 0.0498485542 0.1250501871 0.0166476607 0.1099180000 11456611 955859216 1765052416 -0.0907553583 0.1999161988 0.1323589385 647 1305031123.7199749947 0.1284634918 0.0499700611 0.1284634918 0.0166351755 0.0833400000 11458441 955859216 1765052416 -0.0900786668 0.2042877972 0.1319824904 648 1305031123.7519800663 0.1292839795 0.0500924591 0.1292839795 0.0166284838 0.0691200000 11460207 955859216 1765036032 -0.0895810276 0.2076381743 0.1312679946 649 1305031123.7841379642 0.1294234246 0.0502146948 0.1294234246 0.0166200513 0.0853330000 11461941 955859216 1765036032 -0.0888896883 0.2099882066 0.1304144412 650 1305031123.8196959496 0.1291233301 0.0503360927 0.1294234246 0.0166085710 0.0871240000 11463803 955859216 1765036032 -0.0874633044 0.2122181803 0.1294397116 651 1305031123.8515510559 0.1276479065 0.0504548512 0.1294234246 0.0165960547 0.0838830000 11465569 955859216 1765036032 -0.0863349661 0.2135357261 0.1284175962 652 1305031123.8838191032 0.1265671849 0.0505715879 0.1294234246 0.0165856190 0.0902030000 11467335 955859216 1765052416 -0.0859899521 0.2133687884 0.1277910918 653 1305031123.9157938957 0.1240110174 0.0506840526 0.1294234246 0.0165750205 0.0818810000 11469069 955859216 1766400000 -0.0851473734 0.2122620046 0.1269689202 654 1305031123.9515299797 0.1208830774 0.0507913906 0.1294234246 0.0165748614 0.0859920000 11470931 955859216 1765036032 -0.0855144709 0.2118250430 0.1265181899 655 1305031123.9834210873 0.1190409884 0.0508955884 0.1294234246 0.0165701408 0.0823020000 11472697 955859216 1766510592 -0.0870728716 0.2097220123 0.1271158457 656 1305031124.0197370052 0.1157127097 0.0509943950 0.1294234246 0.0165773211 0.1113440000 11474527 955859216 1765015552 -0.0886073261 0.2053301483 0.1281020343 657 1305031124.0515310764 0.1128927544 0.0510886087 0.1294234246 0.0165772365 0.0862880000 11476261 955859216 1765036032 -0.0883826241 0.2019409239 0.1290731877 658 1305031124.0839018822 0.1099421754 0.0511780518 0.1294234246 0.0165675398 0.0643180000 11478027 955859216 1766400000 -0.0890120566 0.1986698955 0.1305473894 659 1305031124.1196689606 0.1055149511 0.0512605053 0.1294234246 0.0165717066 0.0690540000 11479857 955859216 1765888000 -0.0896246359 0.1928280592 0.1325365752 660 1305031124.1474580765 0.1026800796 0.0513384138 0.1294234246 0.0165744637 0.0670040000 11481591 955859216 1765023744 -0.0877512544 0.1886654794 0.1346441358 661 1305031124.1827070713 0.0993757248 0.0514110875 0.1294234246 0.0165649798 0.0845590000 11483389 955859216 1765036032 -0.0874947235 0.1842397004 0.1366109252 662 1305031124.2171790600 0.0951667130 0.0514771836 0.1294234246 0.0165717208 0.1046510000 11485187 955859216 1764986880 -0.0875149444 0.1771910936 0.1387096792 663 1305031124.2493400574 0.0927692875 0.0515394643 0.1294234246 0.0165812585 0.1095940000 11486921 955859216 1765036032 -0.0862436816 0.1709741801 0.1407448202 664 1305031124.2825551033 0.0895440876 0.0515967002 0.1294234246 0.0165694245 0.0833660000 11488719 955859216 1765257216 -0.0865637884 0.1657709330 0.1425137222 665 1305031124.3167819977 0.0855643675 0.0516477794 0.1294234246 0.0165746281 0.1100970000 11490517 955859216 1765036032 -0.0874058306 0.1577481180 0.1443183571 666 1305031124.3503708839 0.0842840746 0.0516967828 0.1294234246 0.0165667882 0.0818170000 11492283 955859216 1766510592 -0.0863111094 0.1495605260 0.1464429498 667 1305031124.3824319839 0.0823137015 0.0517426852 0.1294234246 0.0165580147 0.0683200000 11494081 955859216 1768542208 -0.0843897462 0.1417340785 0.1484602094 668 1305031124.4185550213 0.0827959701 0.0517891722 0.1294234246 0.0165650550 0.1094680000 11495943 955859216 1770319872 -0.0785182416 0.1264731139 0.1522039771 669 1305031124.4502561092 0.0780806094 0.0518284718 0.1294234246 0.0165529279 0.0887610000 11497645 955859216 1772097536 -0.0801048875 0.1196672246 0.1520542651 670 1305031124.4801259041 0.0743877590 0.0518621424 0.1294234246 0.0165406467 0.0868140000 11499411 955859216 1773748224 -0.0807828605 0.1119306684 0.1525604129 671 1305031124.5167369843 0.0679439455 0.0518861093 0.1294234246 0.0165288259 0.0835580000 11501241 955859216 1775398912 -0.0812662244 0.1037795171 0.1533947289 672 1305031124.5505030155 0.0642901510 0.0519045677 0.1294234246 0.0165166141 0.0681940000 11503039 955859216 1777168384 -0.0809137523 0.0959642008 0.1550214887 673 1305031124.5846059322 0.0646085963 0.0519234444 0.1294234246 0.0165052095 0.0884930000 11504837 955859216 1778819072 -0.0787191615 0.0831411406 0.1583802104 674 1305031124.6176528931 0.0568779334 0.0519307953 0.1294234246 0.0165056472 0.0665040000 11506635 955859216 1780596736 -0.0800204352 0.0750264376 0.1599741131 675 1305031124.6513130665 0.0539458320 0.0519337805 0.1294234246 0.0164994359 0.1071680000 11508401 955859216 1782247424 -0.0801308900 0.0666404292 0.1629563123 676 1305031124.6854729652 0.0542391092 0.0519371908 0.1294234246 0.0164951907 0.1089220000 11510199 955859216 1783898112 -0.0768755749 0.0527968556 0.1670001894 677 1305031124.7157909870 0.0464301072 0.0519290562 0.1294234246 0.0164835700 0.0806940000 11511965 955859216 1785675776 -0.0777946338 0.0457539111 0.1696033180 678 1305031124.7499411106 0.0450393148 0.0519188944 0.1294234246 0.0164719331 0.1043160000 11513763 955859216 1787326464 -0.0767452717 0.0346720181 0.1738543957 679 1305031124.7851779461 0.0439353213 0.0519071365 0.1294234246 0.0164605337 0.1119800000 11515561 955859216 1784815616 -0.0766258985 0.0231010076 0.1780537814 680 1305031124.8166410923 0.0360308476 0.0518837890 0.1294234246 0.0164496985 0.0851030000 11517327 955859216 1783693312 -0.0778368041 0.0161927342 0.1822602749 681 1305031124.8505589962 0.0357603095 0.0518601129 0.1294234246 0.0164379134 0.1066740000 11519125 955859216 1782681600 -0.0776857585 0.0043894388 0.1881900877 682 1305031124.8835940361 0.0354759619 0.0518360892 0.1294234246 0.0164335814 0.0830010000 11520891 955859216 1781534720 -0.0772918537 -0.0073311990 0.1940936148 683 1305031124.9187700748 0.0304889642 0.0518048342 0.1294234246 0.0164347510 0.1173520000 11522721 955859216 1780502528 -0.0792599693 -0.0151934968 0.1999464184 684 1305031124.9507479668 0.0299466178 0.0517728778 0.1294234246 0.0164245071 0.0892430000 11524455 955859216 1779486720 -0.0805848017 -0.0233438835 0.2061855197 685 1305031124.9864599705 0.0312634706 0.0517429370 0.1294234246 0.0164543220 0.0819550000 11526285 955859216 1778360320 -0.0808784813 -0.0395043045 0.2125198692 686 1305031125.0194671154 0.0332217440 0.0517159382 0.1294234246 0.0164472432 0.0921430000 11528083 955859216 1777328128 -0.0836173818 -0.0498892143 0.2178543508 687 1305031125.0507979393 0.0297956113 0.0516840309 0.1294234246 0.0164460800 0.0882930000 11529817 955859216 1776312320 -0.0823337063 -0.0546337329 0.2230679989 688 1305031125.0834798813 0.0295803398 0.0516519034 0.1294234246 0.0164364352 0.1048420000 11531615 955859216 1775296512 -0.0827432796 -0.0623315163 0.2284375429 689 1305031125.1190290451 0.0292288829 0.0516193591 0.1294234246 0.0164308237 0.1135810000 11533445 955859216 1774280704 -0.0844946802 -0.0734667704 0.2331883758 690 1305031125.1510369778 0.0288757291 0.0515863974 0.1294234246 0.0164220712 0.0779860000 11535179 955859216 1773285376 -0.0852954388 -0.0818062201 0.2369686365 691 1305031125.1870639324 0.0246311333 0.0515473883 0.1294234246 0.0164221115 0.0854760000 11537041 955859216 1772249088 -0.0862528384 -0.0857221261 0.2410492599 692 1305031125.2190179825 0.0258782096 0.0515102941 0.1294234246 0.0164138209 0.1114620000 11538807 955859216 1771380736 -0.0892046317 -0.0931849778 0.2445363253 693 1305031125.2506420612 0.0289597176 0.0514777536 0.1294234246 0.0164050555 0.1015700000 11540541 955859216 1770344448 -0.0920963809 -0.1041231975 0.2475565523 694 1305031125.2863960266 0.0280902199 0.0514440540 0.1294234246 0.0163952536 0.0865670000 11542371 955859216 1770065920 -0.0929499939 -0.1127240285 0.2507955432 695 1305031125.3191399574 0.0266765356 0.0514084173 0.1294234246 0.0163866399 0.1091240000 11544169 955859216 1768312832 -0.0932161659 -0.1180899292 0.2534705102 696 1305031125.3488988876 0.0292404070 0.0513765667 0.1294234246 0.0163763867 0.1054960000 11545871 955859216 1767444480 -0.0961584225 -0.1266941428 0.2564758062 697 1305031125.3867919445 0.0280827284 0.0513431465 0.1294234246 0.0163760281 0.1066020000 11547765 955859216 1766408192 -0.0977009088 -0.1298784167 0.2595469058 698 1305031125.4195740223 0.0273009837 0.0513087022 0.1294234246 0.0163653940 0.0848690000 11549531 955859216 1765392384 -0.0969995931 -0.1347652078 0.2625602782 699 1305031125.4512319565 0.0299566574 0.0512781556 0.1294234246 0.0163606518 0.0846380000 11551297 955859216 1766756352 -0.0992863327 -0.1406710446 0.2660096586 700 1305031125.4869990349 0.0329844318 0.0512520217 0.1294234246 0.0163596615 0.1091890000 11553127 955859216 1765027840 -0.0996847227 -0.1506837606 0.2684012949 701 1305031125.5193541050 0.0331881717 0.0512262530 0.1294234246 0.0163540894 0.0862240000 11554925 955859216 1765027840 -0.0998349637 -0.1535386890 0.2706466913 702 1305031125.5510499477 0.0339098834 0.0512015858 0.1294234246 0.0163449179 0.0860460000 11556659 955859216 1765027840 -0.1002942324 -0.1560156941 0.2720083892 703 1305031125.5853030682 0.0348255448 0.0511782913 0.1294234246 0.0163333396 0.0866350000 11558457 955859216 1765027840 -0.1003940254 -0.1582520306 0.2728900611 704 1305031125.6178700924 0.0378382914 0.0511593425 0.1294234246 0.0163410067 0.1089170000 11560255 955859216 1765027840 -0.1011306122 -0.1624468863 0.2727039158 705 1305031125.6505749226 0.0424055308 0.0511469257 0.1294234246 0.0163326559 0.1131850000 11562021 955859216 1765023744 -0.1024329364 -0.1674110293 0.2714039683 706 1305031125.6846020222 0.0435647964 0.0511361861 0.1294234246 0.0163290700 0.0772650000 11563787 955859216 1765027840 -0.1028054878 -0.1669742316 0.2694037259 707 1305031125.7156689167 0.0437778085 0.0511257783 0.1294234246 0.0163467186 0.0876490000 11565553 955859216 1765027840 -0.1019181162 -0.1645488292 0.2669370174 708 1305031125.7512919903 0.0376892649 0.0511068001 0.1294234246 0.0163459596 0.0938080000 11567383 955859216 1764978688 -0.0980250537 -0.1554713994 0.2633986175 709 1305031125.7868049145 0.0399744771 0.0510910987 0.1294234246 0.0163383411 0.0748900000 11569213 955859216 1765011456 -0.0988726914 -0.1507570744 0.2605642974 710 1305031125.8194499016 0.0398465283 0.0510752613 0.1294234246 0.0163304290 0.1041070000 11571011 955859216 1765011456 -0.0977051035 -0.1449599415 0.2571053207 711 1305031125.8547739983 0.0356957950 0.0510536305 0.1294234246 0.0163261632 0.0864150000 11572777 955859216 1765027840 -0.0978284478 -0.1312113255 0.2531218231 712 1305031125.8866450787 0.0413065925 0.0510399408 0.1294234246 0.0163227165 0.0673180000 11574575 955859216 1766391808 -0.0985484198 -0.1277269870 0.2494795173 713 1305031125.9193339348 0.0396314114 0.0510239401 0.1294234246 0.0163262055 0.1049310000 11576373 955859216 1765167104 -0.0994988307 -0.1148830503 0.2465620637 714 1305031125.9552519321 0.0445215367 0.0510148331 0.1294234246 0.0163242697 0.1092930000 11578171 955859216 1765044224 -0.1000370309 -0.1121230721 0.2436092794 715 1305031125.9870939255 0.0446161628 0.0510058839 0.1294234246 0.0163183194 0.0863900000 11579937 955859216 1765044224 -0.0971458107 -0.1010656580 0.2402080297 716 1305031126.0195720196 0.0427305810 0.0509943262 0.1294234246 0.0163104311 0.0864870000 11581735 955859216 1765044224 -0.0951895043 -0.0888780504 0.2375544906 717 1305031126.0550379753 0.0410885774 0.0509805107 0.1294234246 0.0163054798 0.1028010000 11583533 955859216 1765044224 -0.0916711390 -0.0771090537 0.2351962030 718 1305031126.0870759487 0.0467869453 0.0509746701 0.1294234246 0.0162965897 0.0912300000 11585299 955859216 1765044224 -0.0884326175 -0.0699638724 0.2330104262 719 1305031126.1194519997 0.0456143543 0.0509672148 0.1294234246 0.0162874695 0.1256690000 11587097 955859216 1765027840 -0.0876598507 -0.0561661236 0.2301935405 720 1305031126.1549999714 0.0492692627 0.0509648565 0.1294234246 0.0162782960 0.1078850000 11588863 955859216 1765027840 -0.0851868168 -0.0491420366 0.2287975401 721 1305031126.1871740818 0.0502222255 0.0509638265 0.1294234246 0.0162766526 0.1381120000 11590661 955859216 1765027840 -0.0845440701 -0.0321623906 0.2267906815 722 1305031126.2194728851 0.0554755442 0.0509700755 0.1294234246 0.0162858721 0.0875790000 11592459 955859216 1766629376 -0.0813668445 -0.0264785122 0.2247831523 723 1305031126.2552359104 0.0537579320 0.0509739314 0.1294234246 0.0162845101 0.1064060000 11594289 955859216 1768660992 -0.0772902220 -0.0120551493 0.2218401432 724 1305031126.2871050835 0.0614292435 0.0509883725 0.1294234246 0.0162772617 0.0872170000 11596023 955859216 1770311680 -0.0758222565 -0.0043152254 0.2199486941 725 1305031126.3197870255 0.0598213486 0.0510005559 0.1294234246 0.0162712285 0.0968780000 11597821 955859216 1771962368 -0.0758725181 0.0108074276 0.2168789208 726 1305031126.3554151058 0.0645890683 0.0510192728 0.1294234246 0.0162626151 0.0939450000 11599619 955859216 1773740032 -0.0756329447 0.0171186421 0.2150320262 727 1305031126.3874828815 0.0673687756 0.0510417618 0.1294234246 0.0162597833 0.1091850000 11601417 955859216 1775390720 -0.0792937428 0.0293492656 0.2115823328 728 1305031126.4197928905 0.0715235174 0.0510698961 0.1294234246 0.0162497220 0.0852830000 11603151 955859216 1777041408 -0.0795640573 0.0357773155 0.2098132372 729 1305031126.4553799629 0.0755114853 0.0511034237 0.1294234246 0.0162493838 0.0889580000 11604949 955859216 1778819072 -0.0803065896 0.0421032570 0.2075292021 730 1305031126.4903860092 0.0821570903 0.0511459629 0.1294234246 0.0162470870 0.0893380000 11606779 955859216 1780469760 -0.0808882490 0.0488104336 0.2047666758 731 1305031126.5223209858 0.0786898285 0.0511836426 0.1294234246 0.0162505727 0.0837050000 11608545 955859216 1782247424 -0.0819369778 0.0634927973 0.2009422779 732 1305031126.5582089424 0.0851622596 0.0512300615 0.1294234246 0.0162494431 0.0683510000 11610375 955859216 1783898112 -0.0811217204 0.0692896917 0.1997532994 733 1305031126.5901761055 0.0872516483 0.0512792042 0.1294234246 0.0162386928 0.0891290000 11612141 955859216 1785548800 -0.0794347227 0.0753687322 0.1979626864 734 1305031126.6186869144 0.0891777202 0.0513308371 0.1294234246 0.0162277253 0.1037090000 11613843 955859216 1787326464 -0.0789012760 0.0817959011 0.1965416074 735 1305031126.6544740200 0.0911299512 0.0513849855 0.1294234246 0.0162304068 0.1094530000 11615705 955859216 1784803328 -0.0785205588 0.0865811259 0.1947552562 736 1305031126.6900219917 0.0954587609 0.0514448684 0.1294234246 0.0162202588 0.0865290000 11617535 955859216 1783676928 -0.0777247027 0.0905297622 0.1928784549 737 1305031126.7157700062 0.0961229727 0.0515054899 0.1294234246 0.0162104816 0.0834610000 11619173 955859216 1782661120 -0.0766167417 0.0955696553 0.1907344908 738 1305031126.7553739548 0.0971807837 0.0515673806 0.1294234246 0.0162010863 0.0869360000 11621067 955859216 1781645312 -0.0758643597 0.0988890901 0.1882747561 739 1305031126.7875649929 0.0988615081 0.0516313781 0.1294234246 0.0161919630 0.0844760000 11622833 955859216 1780629504 -0.0747604445 0.1024326012 0.1857336611 740 1305031126.8199288845 0.0985617489 0.0516947975 0.1294234246 0.0161838986 0.0885550000 11624599 955859216 1779503104 -0.0736293718 0.1064549834 0.1831694394 741 1305031126.8583779335 0.0986566469 0.0517581738 0.1294234246 0.0161732459 0.1063570000 11626493 955859216 1778470912 -0.0725002289 0.1102066338 0.1806430221 742 1305031126.8881540298 0.0980523527 0.0518205649 0.1294234246 0.0161630099 0.1060470000 11628227 955859216 1777455104 -0.0724905133 0.1128463745 0.1782590598 743 1305031126.9194090366 0.0971149653 0.0518815264 0.1294234246 0.0161523725 0.0872820000 11629961 955859216 1776439296 -0.0724741295 0.1148878336 0.1762932092 744 1305031126.9555010796 0.0964628309 0.0519414475 0.1294234246 0.0161442315 0.0794120000 11631791 955859216 1775312896 -0.0723691881 0.1164192408 0.1746710986 745 1305031126.9873158932 0.0962363631 0.0520009037 0.1294234246 0.0161341583 0.0674080000 11633589 955859216 1776676864 -0.0726847500 0.1169320345 0.1732943356 746 1305031127.0195240974 0.0957861841 0.0520595971 0.1294234246 0.0161239397 0.0685560000 11635323 955859216 1776078848 -0.0723868459 0.1168605313 0.1722770631 747 1305031127.0533180237 0.0947309360 0.0521167208 0.1294234246 0.0161167619 0.0836110000 11637121 955859216 1774931968 -0.0716335624 0.1173995733 0.1716950983 748 1305031127.0886490345 0.0926535651 0.0521709144 0.1294234246 0.0161093291 0.1075090000 11638951 955859216 1774047232 -0.0713673234 0.1179965958 0.1715345532 749 1305031127.1209630966 0.0920631662 0.0522241751 0.1294234246 0.0161047576 0.1071290000 11640685 955859216 1773010944 -0.0719286650 0.1169945225 0.1715907305 750 1305031127.1576919556 0.0908794105 0.0522757154 0.1294234246 0.0160944806 0.1037720000 11642547 955859216 1771872256 -0.0721361041 0.1155947819 0.1716672182 751 1305031127.1875000000 0.0897639245 0.0523256331 0.1294234246 0.0160867780 0.1151570000 11644281 955859216 1770852352 -0.0715362504 0.1146780849 0.1721566617 752 1305031127.2218310833 0.0883242488 0.0523735036 0.1294234246 0.0160795480 0.1047320000 11646079 955859216 1769836544 -0.0711360052 0.1142980456 0.1728012562 753 1305031127.2597610950 0.0862027034 0.0524184295 0.1294234246 0.0160736971 0.0884770000 11647941 955859216 1768820736 -0.0714169964 0.1123510748 0.1735312343 754 1305031127.2870380878 0.0851289779 0.0524618122 0.1294234246 0.0160706441 0.0768430000 11649611 955859216 1767952384 -0.0713263601 0.1109590307 0.1745836884 755 1305031127.3204679489 0.0839064121 0.0525034607 0.1294234246 0.0160613663 0.0861470000 11651409 955859216 1766936576 -0.0721487328 0.1098663360 0.1759291887 756 1305031127.3534069061 0.0839589015 0.0525450684 0.1294234246 0.0160541185 0.1077400000 11653175 955859216 1765900288 -0.0728295594 0.1065020710 0.1772796363 757 1305031127.3837130070 0.0833968669 0.0525858238 0.1294234246 0.0160453756 0.1044130000 11654941 955859216 1765031936 -0.0727851689 0.1045044065 0.1788426489 758 1305031127.4196500778 0.0818146169 0.0526243842 0.1294234246 0.0160364333 0.1020790000 11656739 955859216 1765027840 -0.0727338269 0.1034366265 0.1807046682 759 1305031127.4542460442 0.0816171020 0.0526625827 0.1294234246 0.0160352369 0.1252030000 11658569 955859216 1765027840 -0.0733496696 0.1010452509 0.1823070943 760 1305031127.4872000217 0.0808793455 0.0526997101 0.1294234246 0.0160374358 0.1485910000 11660335 955859216 1765027840 -0.0736352131 0.0996872410 0.1840484887 761 1305031127.5218999386 0.0806008726 0.0527363739 0.1294234246 0.0160276054 0.1054980000 11662165 955859216 1766391808 -0.0733832568 0.0993805304 0.1859236509 762 1305031127.5537250042 0.0813084096 0.0527738700 0.1294234246 0.0160260643 0.1089800000 11663899 955859216 1768153088 -0.0740333572 0.0967921466 0.1875899434 763 1305031127.5866320133 0.0813295692 0.0528112955 0.1294234246 0.0160168429 0.1062570000 11665697 955859216 1769930752 -0.0737680420 0.0952512100 0.1888761669 764 1305031127.6206569672 0.0811091363 0.0528483346 0.1294234246 0.0160071070 0.0872160000 11667495 955859216 1771581440 -0.0734087229 0.0950885862 0.1903441548 765 1305031127.6546559334 0.0817698836 0.0528861405 0.1294234246 0.0159976773 0.0876390000 11669261 955859216 1773359104 -0.0735894293 0.0936730281 0.1914704740 766 1305031127.6871099472 0.0820504054 0.0529242140 0.1294234246 0.0159874760 0.0673790000 11671059 955859216 1775009792 -0.0732203424 0.0917909220 0.1922685951 767 1305031127.7232100964 0.0815429762 0.0529615266 0.1294234246 0.0159785450 0.0841910000 11672889 955859216 1776787456 -0.0727599040 0.0918774083 0.1929950267 768 1305031127.7546939850 0.0813338608 0.0529984697 0.1294234246 0.0159690724 0.0700390000 11674623 955859216 1778438144 -0.0727683082 0.0912396461 0.1935157478 769 1305031127.7876410484 0.0816246644 0.0530356950 0.1294234246 0.0159639944 0.0853860000 11676453 955859216 1780088832 -0.0731159598 0.0892655775 0.1937796026 770 1305031127.8201279640 0.0810095221 0.0530720246 0.1294234246 0.0159549618 0.0865080000 11678187 955859216 1781866496 -0.0729538724 0.0888514593 0.1937149316 771 1305031127.8551321030 0.0806501433 0.0531077939 0.1294234246 0.0159446042 0.0682110000 11679985 955859216 1783517184 -0.0736281276 0.0886741504 0.1937984526 772 1305031127.8871219158 0.0806039572 0.0531434107 0.1294234246 0.0159355079 0.0846890000 11681783 955859216 1785167872 -0.0745514333 0.0876514390 0.1938966811 773 1305031127.9225599766 0.0807893798 0.0531791752 0.1294234246 0.0159264450 0.0887170000 11683613 955859216 1786945536 -0.0751026496 0.0871895552 0.1944570839 774 1305031127.9550879002 0.0802760124 0.0532141840 0.1294234246 0.0159179434 0.0851380000 11685379 955859216 1785950208 -0.0751973093 0.0875160694 0.1953646988 775 1305031127.9870929718 0.0793216303 0.0532478711 0.1294234246 0.0159077971 0.0846210000 11687145 955859216 1784180736 -0.0754383281 0.0874564424 0.1966505200 776 1305031128.0217759609 0.0789723769 0.0532810212 0.1294234246 0.0159003349 0.0858430000 11688975 955859216 1783025664 -0.0752604529 0.0873308256 0.1983718723 777 1305031128.0557179451 0.0787760019 0.0533138333 0.1294234246 0.0158934436 0.0782550000 11690741 955859216 1781264384 -0.0750821456 0.0864536539 0.2005945444 778 1305031128.0872058868 0.0798928291 0.0533479965 0.1294234246 0.0158846884 0.0886140000 11692507 955859216 1780502528 -0.0754098743 0.0841227397 0.2023237348 779 1305031128.1247460842 0.0804713517 0.0533828147 0.1294234246 0.0158754350 0.1039690000 11694369 955859216 1779486720 -0.0747219026 0.0826155767 0.2040049583 780 1305031128.1577820778 0.0805125311 0.0534175964 0.1294234246 0.0158666984 0.1275540000 11696167 955859216 1780867072 -0.0735709220 0.0815850645 0.2056752592 781 1305031128.1872210503 0.0813151598 0.0534533167 0.1294234246 0.0158588999 0.0840500000 11697869 955859216 1782628352 -0.0733969808 0.0795772746 0.2066593021 782 1305031128.2254419327 0.0814742893 0.0534891491 0.1294234246 0.0158517630 0.0695660000 11699731 955859216 1784279040 -0.0720628351 0.0786359906 0.2074496746 783 1305031128.2560069561 0.0808676332 0.0535241153 0.1294234246 0.0158422402 0.1056970000 11701465 955859216 1786056704 -0.0713040307 0.0786730945 0.2080739737 784 1305031128.2912750244 0.0813826844 0.0535596491 0.1294234246 0.0158349822 0.1093070000 11703295 955859216 1787707392 -0.0715187564 0.0775746629 0.2085038573 785 1305031128.3241701126 0.0812541842 0.0535949288 0.1294234246 0.0158260518 0.0830150000 11705061 955859216 1786699776 -0.0714383572 0.0772193819 0.2085695416 786 1305031128.3552060127 0.0807924047 0.0536295312 0.1294234246 0.0158164309 0.1060980000 11706827 955859216 1784594432 -0.0715694875 0.0772871152 0.2085418105 787 1305031128.3913969994 0.0807359666 0.0536639739 0.1294234246 0.0158064990 0.0890960000 11708657 955859216 1783439360 -0.0728153586 0.0765885636 0.2084699422 788 1305031128.4236090183 0.0807999372 0.0536984104 0.1294234246 0.0157965501 0.1053300000 11710423 955859216 1782407168 -0.0732932016 0.0757408366 0.2083230466 789 1305031128.4554989338 0.0804762095 0.0537323493 0.1294234246 0.0157882411 0.0831950000 11712189 955859216 1781280768 -0.0738795474 0.0754337460 0.2081825882 790 1305031128.4895229340 0.0803530142 0.0537660464 0.1294234246 0.0157787310 0.0667810000 11714019 955859216 1782644736 -0.0742621347 0.0748194531 0.2081562579 791 1305031128.5236039162 0.0802233741 0.0537994943 0.1294234246 0.0157689346 0.0884820000 11715785 955859216 1781915648 -0.0746746957 0.0739573687 0.2081369013 792 1305031128.5556390285 0.0799697563 0.0538325376 0.1294234246 0.0157596328 0.1077970000 11717551 955859216 1780977664 -0.0749918073 0.0734167993 0.2079973817 793 1305031128.5914599895 0.0803248137 0.0538659453 0.1294234246 0.0157508893 0.1042840000 11719381 955859216 1782390784 -0.0754026547 0.0720102713 0.2077913284 794 1305031128.6233680248 0.0803932473 0.0538993550 0.1294234246 0.0157418520 0.0901040000 11721147 955859216 1784279040 -0.0755174756 0.0708906278 0.2074904740 795 1305031128.6555540562 0.0801059008 0.0539323192 0.1294234246 0.0157338707 0.0821860000 11722913 955859216 1785929728 -0.0752603114 0.0706267282 0.2073209137 796 1305031128.6904489994 0.0799631178 0.0539650212 0.1294234246 0.0157253931 0.0694420000 11724743 955859216 1787707392 -0.0751378760 0.0701583177 0.2069576234 797 1305031128.7229759693 0.0796737522 0.0539972781 0.1294234246 0.0157166632 0.0871280000 11726509 955859216 1786834944 -0.0747308582 0.0697375759 0.2065835446 798 1305031128.7546460629 0.0791323632 0.0540287757 0.1294234246 0.0157080034 0.1036610000 11728275 955859216 1783652352 -0.0747145116 0.0697602704 0.2060492635 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 06:15:14 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 nan 0.1280200000 16661933 955859216 1776246784 -0.0000000000 0.0000000000 -0.0000000000 2 1311867718.6768438816 0.0027224415 0.0023125467 0.0027224415 0.0021564565 0.1380020000 27150179 955859216 1769136128 0.0005140036 -0.0010962028 0.0001806884 3 1311867718.7114279270 0.0032007154 0.0026086029 0.0032007154 0.0034754149 0.0871210000 27152301 955859216 1768247296 0.0005431200 -0.0010950742 0.0002253659 4 1311867718.7410299778 0.0041615274 0.0029968341 0.0041615274 0.0042902517 0.0730420000 27154331 955859216 1767231488 0.0010361911 -0.0015528316 0.0003020797 5 1311867718.7767970562 0.0055256747 0.0035026022 0.0055256747 0.0043372507 0.1366970000 27156481 955859216 1766469632 0.0021326202 -0.0026201177 0.0001482273 6 1311867718.8094089031 0.0056276894 0.0038567834 0.0056276894 0.0041723840 0.0833580000 27158903 955859216 1762881536 0.0020866522 -0.0026646771 0.0002599266 7 1311867718.8408079147 0.0062838425 0.0042035061 0.0062838425 0.0038612485 0.0889140000 27160637 955859216 1762631680 0.0027294329 -0.0024183709 0.0003479942 8 1311867718.8767778873 0.0070376233 0.0045577708 0.0070376233 0.0036759457 0.1301240000 27162467 955859216 1764413440 0.0030003176 -0.0028127788 0.0004571371 9 1311867718.9088680744 0.0079892315 0.0049390442 0.0079892315 0.0035488961 0.1346670000 27164841 955859216 1766068224 0.0037140562 -0.0027769618 0.0006488235 10 1311867718.9438331127 0.0086718872 0.0053123285 0.0086718872 0.0033954166 0.0951800000 27167983 955859216 1767567360 0.0044403458 -0.0027975212 0.0010433124 11 1311867718.9784109592 0.0095667141 0.0056990908 0.0095667141 0.0033691947 0.0953150000 27169813 955859216 1769345024 0.0048778094 -0.0037225201 0.0012519627 12 1311867719.0091300011 0.0099385362 0.0060523779 0.0099385362 0.0032162853 0.0825040000 27171515 955859216 1770995712 0.0048309024 -0.0041620648 0.0013781030 13 1311867719.0441620350 0.0108212680 0.0064192156 0.0108212680 0.0031157755 0.0881170000 27173345 955859216 1772646400 0.0056099542 -0.0042239940 0.0016285209 14 1311867719.0776190758 0.0119057437 0.0068111105 0.0119057437 0.0031024589 0.0953160000 27175143 955859216 1774424064 0.0065995497 -0.0046419380 0.0017780266 15 1311867719.1086950302 0.0124929417 0.0071898992 0.0124929417 0.0029926855 0.0996960000 27176909 955859216 1776074752 0.0069174822 -0.0050395895 0.0020176345 16 1311867719.1437010765 0.0134427231 0.0075807007 0.0134427231 0.0029043833 0.0940240000 27178707 955859216 1777741824 0.0076666935 -0.0050717769 0.0022302468 17 1311867719.1810290813 0.0144231226 0.0079831961 0.0144231226 0.0028898081 0.0932860000 27181817 955859216 1779503104 0.0082698008 -0.0055703828 0.0025842369 18 1311867719.2127099037 0.0148914382 0.0083669874 0.0148914382 0.0028248629 0.0794090000 27186207 955859216 1781153792 0.0084538274 -0.0058915387 0.0028541584 19 1311867719.2412090302 0.0157150719 0.0087537286 0.0157150719 0.0028017261 0.0956270000 27187909 955859216 1782820864 0.0087315934 -0.0063771317 0.0030933439 20 1311867719.2779469490 0.0170094371 0.0091665141 0.0170094371 0.0031245486 0.1192830000 27189707 955859216 1784582144 0.0094250562 -0.0066686976 0.0032754815 21 1311867719.3104898930 0.0180543177 0.0095897428 0.0180543177 0.0031021083 0.0662550000 27191505 955859216 1783746560 0.0102188690 -0.0067417971 0.0034068092 22 1311867719.3413150311 0.0194102973 0.0100361317 0.0194102973 0.0032204036 0.0576840000 27193271 955859216 1782566912 0.0111630093 -0.0071335598 0.0034870096 23 1311867719.3772718906 0.0210511927 0.0105150473 0.0210511927 0.0032573989 0.1126290000 27195069 955859216 1779646464 0.0122258328 -0.0079090148 0.0034767892 24 1311867719.4105761051 0.0215996895 0.0109769074 0.0215996895 0.0032132498 0.0926840000 27196867 955859216 1780183040 0.0124940258 -0.0081549576 0.0034890412 25 1311867719.4427709579 0.0226410665 0.0114434738 0.0226410665 0.0032977199 0.0809790000 27198665 955859216 1775951872 0.0133473817 -0.0086085005 0.0035952912 26 1311867719.4787840843 0.0232707895 0.0118983706 0.0232707895 0.0033796328 0.1105470000 27200463 955859216 1777623040 0.0132523216 -0.0100179929 0.0035420551 27 1311867719.5104370117 0.0230278987 0.0123105753 0.0232707895 0.0035876617 0.0939330000 27202229 955859216 1779249152 0.0126073882 -0.0103750424 0.0036515314 28 1311867719.5449650288 0.0236945264 0.0127171450 0.0236945264 0.0036217483 0.1167630000 27204027 955859216 1780899840 0.0126721840 -0.0101460051 0.0040007061 29 1311867719.5771939754 0.0249818936 0.0131400674 0.0249818936 0.0036318029 0.0763280000 27205825 955859216 1782566912 0.0133736245 -0.0108825890 0.0040476345 30 1311867719.6112511158 0.0255276989 0.0135529884 0.0255276989 0.0035919062 0.0593120000 27207623 955859216 1784328192 0.0132226087 -0.0112108374 0.0043090256 31 1311867719.6421909332 0.0261626896 0.0139597530 0.0261626896 0.0035472486 0.0843340000 27209357 955859216 1785978880 0.0136106294 -0.0106609939 0.0046823919 32 1311867719.6770479679 0.0270486474 0.0143687809 0.0270486474 0.0034958954 0.0824530000 27211187 955859216 1784238080 0.0138304792 -0.0110277077 0.0051504504 33 1311867719.7107939720 0.0278931465 0.0147786102 0.0278931465 0.0034462233 0.0781220000 27215513 955859216 1782439936 0.0142856045 -0.0106934467 0.0056507573 34 1311867719.7442650795 0.0289757922 0.0151961743 0.0289757922 0.0034015914 0.0948240000 27222527 955859216 1782083584 0.0150826434 -0.0100031495 0.0061893892 35 1311867719.7861878872 0.0304863844 0.0156330375 0.0304863844 0.0033783448 0.1159630000 27224485 955859216 1781198848 0.0157820750 -0.0103675742 0.0066399230 36 1311867719.8099169731 0.0313405655 0.0160693577 0.0313405655 0.0033441787 0.1061590000 27226091 955859216 1780183040 0.0160489101 -0.0108077358 0.0070279990 37 1311867719.8454990387 0.0328067578 0.0165217199 0.0328067578 0.0034070598 0.1232020000 27227921 955859216 1775706112 0.0168588459 -0.0118007110 0.0070706327 38 1311867719.8771090508 0.0328145586 0.0169504788 0.0328145586 0.0033637559 0.1062050000 27229687 955859216 1777381376 0.0166863650 -0.0120142857 0.0073766587 39 1311867719.9114089012 0.0345037989 0.0174005639 0.0345037989 0.0033556071 0.0748960000 27231517 955859216 1778995200 0.0177306533 -0.0124593526 0.0076803700 40 1311867719.9461970329 0.0354935825 0.0178528894 0.0354935825 0.0033187065 0.0772110000 27233315 955859216 1780645888 0.0184123237 -0.0132941427 0.0080125127 41 1311867719.9807810783 0.0374682918 0.0183313138 0.0374682918 0.0032989749 0.1160870000 27235113 955859216 1782312960 0.0196977165 -0.0139800766 0.0080928598 42 1311867720.0117020607 0.0390346684 0.0188242509 0.0390346684 0.0032681351 0.1001220000 27236879 955859216 1784074240 0.0209143236 -0.0141415531 0.0083362991 43 1311867720.0452380180 0.0417878702 0.0193582885 0.0417878702 0.0032446245 0.1192210000 27238645 955859216 1785724928 0.0233919863 -0.0141231641 0.0086757960 44 1311867720.0772819519 0.0448100455 0.0199367375 0.0448100455 0.0032726019 0.0986770000 27240443 955859216 1785024512 0.0261985753 -0.0145127987 0.0091114510 45 1311867720.1172130108 0.0467431247 0.0205324350 0.0467431247 0.0032613990 0.0731700000 27242337 955859216 1783865344 0.0280038957 -0.0147172837 0.0095905792 46 1311867720.1451559067 0.0470762551 0.0211094746 0.0470762551 0.0032265556 0.0759340000 27244007 955859216 1782861824 0.0281643346 -0.0150216157 0.0100285495 47 1311867720.1781630516 0.0480789654 0.0216832935 0.0480789654 0.0031982237 0.0997320000 27245773 955859216 1780809728 0.0292472262 -0.0148157785 0.0103744157 48 1311867720.2094950676 0.0490012802 0.0222524183 0.0490012802 0.0031703005 0.0920810000 27247539 955859216 1776091136 0.0301232487 -0.0146491313 0.0108557036 49 1311867720.2421469688 0.0500635915 0.0228199932 0.0500635915 0.0031398890 0.0777070000 27249337 955859216 1775312896 0.0311483163 -0.0142696248 0.0113368239 50 1311867720.2770779133 0.0517314486 0.0233982223 0.0517314486 0.0031778145 0.0859120000 27251135 955859216 1777094656 0.0324730240 -0.0142874746 0.0120474407 51 1311867720.3094570637 0.0526087284 0.0239709774 0.0526087284 0.0031539159 0.0767200000 27252901 955859216 1778769920 0.0334282592 -0.0135821663 0.0129432436 52 1311867720.3430728912 0.0541844256 0.0245520052 0.0541844256 0.0031611484 0.1197690000 27254699 955859216 1780137984 0.0348227322 -0.0134268440 0.0138207320 53 1311867720.3779859543 0.0560565740 0.0251464310 0.0560565740 0.0032257717 0.0742670000 27256465 955859216 1781788672 0.0360145308 -0.0146805886 0.0142021161 54 1311867720.4096798897 0.0582246333 0.0257589903 0.0582246333 0.0034578201 0.0775390000 27258231 955859216 1783439360 0.0371998139 -0.0155695872 0.0146393925 55 1311867720.4461109638 0.0593719929 0.0263701358 0.0593719929 0.0034509823 0.1007020000 27260093 955859216 1785217024 0.0382712558 -0.0155465966 0.0152041754 56 1311867720.4799289703 0.0609353371 0.0269873716 0.0609353371 0.0035126902 0.0769840000 27261891 955859216 1784119296 0.0395005532 -0.0158276353 0.0152641293 57 1311867720.5104389191 0.0614503026 0.0275919844 0.0614503026 0.0035454405 0.0757750000 27263625 955859216 1783091200 0.0399820618 -0.0161704160 0.0151904179 58 1311867720.5467319489 0.0631123558 0.0282044046 0.0631123558 0.0036294067 0.0974880000 27265487 955859216 1780801536 0.0407283455 -0.0163129456 0.0155901425 59 1311867720.5793280602 0.0634720400 0.0288021611 0.0634720400 0.0036715218 0.0925800000 27267253 955859216 1780297728 0.0410405211 -0.0168026034 0.0158076100 60 1311867720.6121249199 0.0653617978 0.0294114884 0.0653617978 0.0036583092 0.0786130000 27269019 955859216 1778753536 0.0422362834 -0.0172573179 0.0158933066 61 1311867720.6463210583 0.0660455450 0.0300120467 0.0660455450 0.0036503774 0.0949490000 27270849 955859216 1778032640 0.0422367826 -0.0175752863 0.0162879173 62 1311867720.6798269749 0.0669273958 0.0306074556 0.0669273958 0.0036339766 0.1050960000 27272583 955859216 1777016832 0.0424578376 -0.0180388857 0.0162946489 63 1311867720.7102439404 0.0682350472 0.0312047189 0.0682350472 0.0036266673 0.1035900000 27274349 955859216 1776001024 0.0430184416 -0.0190021116 0.0162234958 64 1311867720.7451629639 0.0691364333 0.0317974020 0.0691364333 0.0036215602 0.1165310000 27276147 955859216 1772781568 0.0430414900 -0.0192310009 0.0163088832 65 1311867720.7790179253 0.1113034487 0.0330205719 0.1113034487 0.0049898039 0.1301500000 27283097 955859216 1773826048 0.0858235359 -0.0169427339 0.0258460138 66 1311867720.8115909100 0.1123329327 0.0342222744 0.1123329327 0.0049642410 0.1112130000 27295359 955859216 1772810240 0.0860368386 -0.0182983615 0.0259760264 67 1311867720.8467299938 0.1132908463 0.0354024023 0.1132908463 0.0049549646 0.1114750000 27297189 955859216 1771266048 0.0864576921 -0.0188075099 0.0265758112 68 1311867720.8813319206 0.1134822816 0.0365506358 0.1134822816 0.0049428263 0.0946620000 27298987 955859216 1772892160 0.0862996206 -0.0191011410 0.0269599073 69 1311867720.9149661064 0.1145751178 0.0376814254 0.1145751178 0.0049167802 0.0975450000 27300753 955859216 1774542848 0.0868278965 -0.0199039839 0.0272755288 70 1311867720.9500010014 0.1151560023 0.0387882051 0.1151560023 0.0048838094 0.1178440000 27302551 955859216 1776340992 0.0870665610 -0.0203928091 0.0275969096 71 1311867720.9797990322 0.1155635715 0.0398695483 0.1155635715 0.0048561071 0.1343200000 27304253 955859216 1777971200 0.0872272700 -0.0206098482 0.0277760811 72 1311867721.0093889236 0.1155881733 0.0409211958 0.1155881733 0.0048223941 0.1207700000 27305987 955859216 1779621888 0.0870370120 -0.0210721567 0.0277709607 73 1311867721.0478379726 0.1162151173 0.0419526194 0.1162151173 0.0047910691 0.1350230000 27307881 955859216 1781403648 0.0872798115 -0.0214137249 0.0278076492 74 1311867721.0794439316 0.1170974299 0.0429680898 0.1170974299 0.0047646768 0.1179300000 27309615 955859216 1783033856 0.0878633931 -0.0218961928 0.0279899072 75 1311867721.1103579998 0.1175828353 0.0439629531 0.1175828353 0.0047413918 0.1353760000 27311381 955859216 1784684544 0.0879754424 -0.0221907292 0.0281305276 76 1311867721.1467890739 0.1189038828 0.0449490180 0.1189038828 0.0047309618 0.1375750000 27313211 955859216 1783980032 0.0884941593 -0.0227261037 0.0280745439 77 1311867721.1774179935 0.1198132485 0.0459212807 0.1198132485 0.0047615347 0.0876450000 27314977 955859216 1782824960 0.0895036831 -0.0230955966 0.0282133594 78 1311867721.2112360001 0.1200157404 0.0468712097 0.1200157404 0.0047327230 0.1061160000 27316743 955859216 1781809152 0.0892673954 -0.0236638915 0.0283566751 79 1311867721.2469010353 0.1210227236 0.0478098364 0.1210227236 0.0047221556 0.1223120000 27318573 955859216 1777238016 0.0899926201 -0.0242708698 0.0284169149 80 1311867721.2800450325 0.1218085587 0.0487348205 0.1218085587 0.0047084287 0.1074870000 27320339 955859216 1778884608 0.0901695862 -0.0249059908 0.0285009984 81 1311867721.3099579811 0.1227742955 0.0496488880 0.1227742955 0.0046942981 0.1564580000 27322073 955859216 1780649984 0.0907730088 -0.0255318135 0.0286468845 82 1311867721.3483059406 0.1241086945 0.0505569345 0.1241086945 0.0046727377 0.1159380000 27323935 955859216 1782018048 0.0916894078 -0.0258217473 0.0287299044 83 1311867721.3790040016 0.1249420866 0.0514531411 0.1249420866 0.0046469002 0.0950820000 27325637 955859216 1783668736 0.0920739919 -0.0257871561 0.0288311876 84 1311867721.4092550278 0.1252303720 0.0523314415 0.1252303720 0.0046213125 0.1181750000 27327371 955859216 1785466880 0.0917752981 -0.0262326151 0.0291166566 85 1311867721.4478130341 0.1259486228 0.0531975260 0.1259486228 0.0045944779 0.1050780000 27329297 955859216 1784340480 0.0918935984 -0.0265701991 0.0294915792 86 1311867721.4768960476 0.1265584528 0.0540505600 0.1265584528 0.0045711916 0.0880770000 27330999 955859216 1783332864 0.0920311585 -0.0268919170 0.0297621302 87 1311867721.5093359947 0.1271475405 0.0548907552 0.1271475405 0.0045615196 0.0976740000 27332733 955859216 1782190080 0.0921455175 -0.0273676999 0.0299757719 88 1311867721.5451331139 0.1288145930 0.0557307988 0.1288145930 0.0045397529 0.1119910000 27334531 955859216 1781174272 0.0932708979 -0.0281879250 0.0301010758 89 1311867721.5769670010 0.1296527982 0.0565613831 0.1296527982 0.0045179660 0.1311400000 27336233 955859216 1776828416 0.0938336849 -0.0282268319 0.0304295756 90 1311867721.6129651070 0.1306564510 0.0573846616 0.1306564510 0.0045372756 0.0903160000 27338031 955859216 1774432256 0.0942681432 -0.0287889615 0.0303715877 91 1311867721.6496050358 0.1311938614 0.0581957517 0.1311938614 0.0045593784 0.0735810000 27339893 955859216 1776062464 0.0944357738 -0.0292138513 0.0301323570 92 1311867721.6800351143 0.1316138804 0.0589937748 0.1316138804 0.0045599499 0.0752290000 27341627 955859216 1777729536 0.0945490748 -0.0288515352 0.0302859880 93 1311867721.7162289619 0.1316586882 0.0597751180 0.1316586882 0.0045516898 0.0762870000 27343489 955859216 1779351552 0.0945325419 -0.0289634299 0.0305169467 94 1311867721.7467949390 0.1326513439 0.0605503970 0.1326513439 0.0045875179 0.0757990000 27345223 955859216 1781002240 0.0946145281 -0.0299517754 0.0304934308 95 1311867721.7787001133 0.1328385025 0.0613113244 0.1328385025 0.0045641509 0.1194250000 27346989 955859216 1782779904 0.0945059285 -0.0299906880 0.0306388605 96 1311867721.8154830933 0.1335112751 0.0620634072 0.1335112751 0.0045431543 0.1156010000 27348819 955859216 1784430592 0.0946832225 -0.0303621981 0.0306727029 97 1311867721.8485159874 0.1339734942 0.0628047483 0.1339734942 0.0045225926 0.1009970000 27350617 955859216 1783721984 0.0945662782 -0.0311534144 0.0304694325 98 1311867721.8778810501 0.1339341700 0.0635305588 0.1339734942 0.0045019760 0.1072670000 27352351 955859216 1782571008 0.0942420736 -0.0311139133 0.0303657204 99 1311867721.9146931171 0.1343515068 0.0642459219 0.1343515068 0.0044793469 0.0850250000 27354053 955859216 1779625984 0.0943809301 -0.0311784204 0.0302866735 100 1311867721.9467151165 0.1346466243 0.0649499289 0.1346466243 0.0044573245 0.1151950000 27355819 955859216 1780158464 0.0942880213 -0.0316155329 0.0301179569 101 1311867721.9773728848 0.1349419653 0.0656429194 0.1349419653 0.0044609098 0.0964290000 27357585 955859216 1779015680 0.0945377424 -0.0316492505 0.0299140476 102 1311867722.0166850090 0.1354904324 0.0663276989 0.1354904324 0.0044892353 0.1154400000 27359383 955859216 1777983488 0.0944667384 -0.0321843214 0.0298129786 103 1311867722.0475180149 0.1359332949 0.0670034814 0.1359332949 0.0044953574 0.1345860000 27361053 955859216 1776455680 0.0949426293 -0.0325906761 0.0295276791 104 1311867722.0800709724 0.1365969926 0.0676726498 0.1365969926 0.0044853283 0.0980400000 27362851 955859216 1777971200 0.0951702446 -0.0329650119 0.0295450799 105 1311867722.1161251068 0.1372261643 0.0683350642 0.1372261643 0.0044708981 0.0753000000 27364681 955859216 1779470336 0.0951740146 -0.0338802896 0.0295150746 106 1311867722.1479530334 0.1375098974 0.0689876570 0.1375098974 0.0044664616 0.0987290000 27366415 955859216 1781121024 0.0949516445 -0.0343752280 0.0293462668 107 1311867722.1798410416 0.1386263669 0.0696384860 0.1386263669 0.0044472591 0.0755050000 27368181 955859216 1782788096 0.0957743898 -0.0342750251 0.0298867263 108 1311867722.2146399021 0.1389399320 0.0702801661 0.1389399320 0.0044474641 0.0764560000 27370011 955859216 1784549376 0.0958382860 -0.0349125452 0.0297673605 109 1311867722.2469589710 0.1399262398 0.0709191209 0.1399262398 0.0044300163 0.0822780000 27371777 955859216 1783451648 0.0964936987 -0.0354647525 0.0298270751 110 1311867722.2780389786 0.1406394988 0.0715529425 0.1406394988 0.0044115910 0.0973040000 27373543 955859216 1781776384 0.0970548093 -0.0352945440 0.0302424040 111 1311867722.3154170513 0.1405773610 0.0721747841 0.1406394988 0.0043920296 0.0968930000 27375373 955859216 1781039104 0.0968358815 -0.0356312282 0.0302412249 112 1311867722.3488469124 0.1412484646 0.0727915134 0.1412484646 0.0043821309 0.0978760000 27377139 955859216 1780043776 0.0971176773 -0.0363901183 0.0301816929 113 1311867722.3777940273 0.1408895701 0.0733941511 0.1412484646 0.0043663866 0.1311460000 27378873 955859216 1778888704 0.0966698974 -0.0362635069 0.0303336456 114 1311867722.4150679111 0.1415307969 0.0739918409 0.1415307969 0.0043496449 0.0945960000 27380607 955859216 1774428160 0.0968804657 -0.0368516482 0.0305286553 115 1311867722.4467909336 0.1416819245 0.0745804504 0.1416819245 0.0043783061 0.0737780000 27382373 955859216 1772789760 0.0966967642 -0.0376768969 0.0308690574 116 1311867722.4777851105 0.1429547518 0.0751698840 0.1429547518 0.0044124374 0.0744230000 27384107 955859216 1774436352 0.0974547565 -0.0375832692 0.0312984362 117 1311867722.5147399902 0.1437048465 0.0757556529 0.1437048465 0.0043970848 0.0754840000 27385905 955859216 1776095232 0.0978382528 -0.0380165949 0.0319400094 118 1311867722.5469911098 0.1437687576 0.0763320351 0.1437687576 0.0043821099 0.0985060000 27387671 955859216 1777446912 0.0976819023 -0.0382406376 0.0321810506 119 1311867722.5802359581 0.1439949274 0.0769006309 0.1439949274 0.0043708108 0.0985610000 27389437 955859216 1779224576 0.0976946205 -0.0387675539 0.0325978100 120 1311867722.6146309376 0.1453593522 0.0774711202 0.1453593522 0.0043553210 0.1122430000 27391235 955859216 1780875264 0.0988734514 -0.0395302102 0.0328183956 121 1311867722.6560258865 0.1461094022 0.0780383788 0.1461094022 0.0043414615 0.1161380000 27393161 955859216 1782673408 0.0993785784 -0.0402125940 0.0328223445 122 1311867722.6778230667 0.1471214443 0.0786046334 0.1471214443 0.0043325839 0.0960320000 27394799 955859216 1784303616 0.1001983210 -0.0406731665 0.0330090933 123 1311867722.7252709866 0.1477466077 0.0791667633 0.1477466077 0.0043978568 0.1201290000 27396789 955859216 1785954304 0.1004081666 -0.0409788378 0.0331577919 124 1311867722.7449109554 0.1478740424 0.0797208542 0.1478740424 0.0044140969 0.1398290000 27398331 955859216 1784987648 0.1005187333 -0.0413127095 0.0327015519 125 1311867722.7770080566 0.1479221284 0.0802664644 0.1479221284 0.0044495387 0.0939370000 27400129 955859216 1783205888 0.1001852006 -0.0413034558 0.0327380411 126 1311867722.8162860870 0.1470073462 0.0807961540 0.1479221284 0.0044330816 0.1171520000 27401959 955859216 1782697984 0.0988234356 -0.0412906669 0.0328649059 127 1311867722.8466939926 0.1481312811 0.0813263518 0.1481312811 0.0044563700 0.1288580000 27403693 955859216 1779884032 0.0991805941 -0.0426867455 0.0335550196 128 1311867722.8819770813 0.1494693905 0.0818587193 0.1494693905 0.0044437345 0.0960730000 27405523 955859216 1780412416 0.0996259227 -0.0436257906 0.0344974659 129 1311867722.9150629044 0.1521117687 0.0824033166 0.1521117687 0.0044432930 0.1335240000 27417433 955859216 1779396608 0.1017331183 -0.0431530885 0.0357051790 130 1311867722.9485991001 0.1528734714 0.0829453947 0.1528734714 0.0044597864 0.1562310000 27440255 955859216 1778253824 0.1020247266 -0.0439662263 0.0360520631 131 1311867722.9821140766 0.1534787565 0.0834838173 0.1534787565 0.0044440252 0.1349380000 27442021 955859216 1779879936 0.1018019244 -0.0448645055 0.0368080474 132 1311867723.0147259235 0.1545239836 0.0840220004 0.1545239836 0.0044281453 0.1112810000 27443787 955859216 1781510144 0.1025785953 -0.0442982465 0.0377275869 133 1311867723.0460629463 0.1553066373 0.0845579751 0.1553066373 0.0044419131 0.1050380000 27445521 955859216 1783160832 0.1025834382 -0.0450042635 0.0384272486 134 1311867723.0845439434 0.1577475369 0.0851041659 0.1577475369 0.0044408212 0.0726940000 27447383 955859216 1784938496 0.1041499004 -0.0463417582 0.0393461809 135 1311867723.1140980721 0.1587425619 0.0856496355 0.1587425619 0.0044268296 0.0944720000 27449117 955859216 1784098816 0.1044148430 -0.0468581282 0.0401302129 136 1311867723.1505160332 0.1603687555 0.0861990407 0.1603687555 0.0044187294 0.0974270000 27450947 955859216 1781764096 0.1052105278 -0.0477830023 0.0405903570 137 1311867723.1811029911 0.1608667523 0.0867440605 0.1608667523 0.0044052318 0.1173010000 27452681 955859216 1781571584 0.1047998369 -0.0490112901 0.0408776104 138 1311867723.2201359272 0.1619440317 0.0872889879 0.1619440317 0.0043894229 0.0860180000 27454543 955859216 1780539392 0.1050428450 -0.0498916321 0.0418821909 139 1311867723.2486810684 0.1644665003 0.0878442218 0.1644665003 0.0043874837 0.0970380000 27456245 955859216 1779412992 0.1070371792 -0.0507038236 0.0423366278 140 1311867723.2846419811 0.1597180814 0.0883576065 0.1644665003 0.0044244422 0.1692200000 27458075 955859216 1778126848 0.1019765586 -0.0507184565 0.0397380553 141 1311867723.3132460117 0.1584215462 0.0888545139 0.1644665003 0.0044114075 0.1100160000 27459777 955859216 1779605504 0.1003940776 -0.0509747043 0.0389988087 142 1311867723.3499810696 0.1577867717 0.0893399523 0.1644665003 0.0043992418 0.0781030000 27461639 955859216 1781256192 0.0992221609 -0.0507582426 0.0390697196 143 1311867723.3822429180 0.1583711505 0.0898226879 0.1644665003 0.0043884700 0.0769080000 27463437 955859216 1783054336 0.0993594676 -0.0511742607 0.0396963619 144 1311867723.4193739891 0.1590004563 0.0903030891 0.1644665003 0.0044061618 0.1214370000 27465267 955859216 1784684544 0.0998271778 -0.0515925698 0.0405431613 145 1311867723.4455900192 0.1588687748 0.0907759559 0.1644665003 0.0043953734 0.0942940000 27466937 955859216 1783824384 0.0994061232 -0.0514665619 0.0403603688 146 1311867723.4825348854 0.1593689620 0.0912457710 0.1644665003 0.0043947020 0.0794850000 27468799 955859216 1782697984 0.0990051106 -0.0516003408 0.0408295766 147 1311867723.5147960186 0.1596285850 0.0917109602 0.1644665003 0.0043813876 0.1166840000 27470533 955859216 1781682176 0.0988093913 -0.0516340286 0.0409566462 148 1311867723.5451340675 0.1599998921 0.0921723719 0.1644665003 0.0043689319 0.1109290000 27472299 955859216 1780666368 0.0985153168 -0.0519321337 0.0414254926 149 1311867723.5809938908 0.1604256630 0.0926304477 0.1644665003 0.0043577431 0.1162470000 27474129 955859216 1776594944 0.0982956588 -0.0522984415 0.0417812131 150 1311867723.6132669449 0.1622229666 0.0930943978 0.1644665003 0.0043496550 0.1100920000 27475927 955859216 1778253824 0.0996639207 -0.0525660813 0.0425424427 151 1311867723.6453940868 0.1619074792 0.0935501136 0.1644665003 0.0043362735 0.1168060000 27477661 955859216 1779736576 0.0990439504 -0.0525363535 0.0427089147 152 1311867723.6809489727 0.1624556184 0.0940034393 0.1644665003 0.0043235244 0.0990760000 27479491 955859216 1781374976 0.0991946235 -0.0531202406 0.0428432189 153 1311867723.7130429745 0.1631542146 0.0944554051 0.1644665003 0.0043121848 0.1376280000 27481257 955859216 1783025664 0.0993687287 -0.0536019728 0.0434158035 154 1311867723.7471990585 0.1641068310 0.0949076871 0.1644665003 0.0043006734 0.1341250000 27483055 955859216 1784803328 0.0999578610 -0.0538267307 0.0432252586 155 1311867723.7809250355 0.1647391617 0.0953582128 0.1647391617 0.0042907087 0.0990040000 27484853 955859216 1783943168 0.0999184102 -0.0546571240 0.0432113931 156 1311867723.8157649040 0.1663689166 0.0958134096 0.1663689166 0.0042843026 0.1165120000 27486651 955859216 1782816768 0.1009275392 -0.0553792454 0.0431136712 157 1311867723.8468959332 0.1679149121 0.0962726548 0.1679149121 0.0042727534 0.1166940000 27488417 955859216 1781800960 0.1022043079 -0.0553562008 0.0434667282 158 1311867723.8826351166 0.1667061150 0.0967184362 0.1679149121 0.0042720023 0.1104280000 27490215 955859216 1780674560 0.1004832685 -0.0558687188 0.0427067578 159 1311867723.9172909260 0.1671136767 0.0971611736 0.1679149121 0.0042659353 0.0898240000 27491949 955859216 1782284288 0.1005492583 -0.0559960753 0.0426694378 160 1311867723.9490020275 0.1673028022 0.0975995588 0.1679149121 0.0042551364 0.0782360000 27493683 955859216 1783914496 0.1007252187 -0.0551693514 0.0424862802 161 1311867723.9839010239 0.1689201295 0.0980425437 0.1689201295 0.0042556868 0.0785240000 27495513 955859216 1785565184 0.1018426269 -0.0560899265 0.0428935252 162 1311867724.0132899284 0.1686230004 0.0984782255 0.1689201295 0.0042544935 0.1190480000 27497215 955859216 1784721408 0.1014629602 -0.0560049824 0.0426274203 163 1311867724.0475380421 0.1700473726 0.0989173000 0.1700473726 0.0042444136 0.1508140000 27499045 955859216 1783689216 0.1027000770 -0.0559197068 0.0429596826 164 1311867724.0824530125 0.1703009754 0.0993525663 0.1703009754 0.0042371337 0.0994160000 27500843 955859216 1782562816 0.1026199684 -0.0562747419 0.0429976955 165 1311867724.1132431030 0.1695133448 0.0997777832 0.1703009754 0.0042255907 0.1177100000 27502609 955859216 1784037376 0.1016277224 -0.0562142879 0.0425698124 166 1311867724.1547191143 0.1698914319 0.1002001546 0.1703009754 0.0042214204 0.0755530000 27504535 955859216 1785819136 0.1018939242 -0.0557450801 0.0422676019 167 1311867724.1810541153 0.1701644063 0.1006191022 0.1703009754 0.0042131772 0.0786140000 27506205 955859216 1784848384 0.1018757373 -0.0559388138 0.0425884612 168 1311867724.2139430046 0.1701660901 0.1010330723 0.1703009754 0.0042047384 0.1136460000 27508003 955859216 1783832576 0.1014800444 -0.0563449636 0.0428292677 169 1311867724.2507870197 0.1697060913 0.1014394216 0.1703009754 0.0042008553 0.0960950000 27509833 955859216 1782816768 0.1007169485 -0.0559017956 0.0426416844 170 1311867724.2855930328 0.1709964275 0.1018485804 0.1709964275 0.0041944597 0.1126640000 27511631 955859216 1781673984 0.1018019393 -0.0559098870 0.0429465100 171 1311867724.3144888878 0.1713309139 0.1022549099 0.1713309139 0.0041832288 0.0961860000 27513333 955859216 1778851840 0.1018572450 -0.0564005822 0.0424202234 172 1311867724.3517999649 0.1714278609 0.1026570782 0.1714278609 0.0041858576 0.0930290000 27515227 955859216 1777074176 0.1015336663 -0.0567142554 0.0427428707 173 1311867724.3888330460 0.1709969789 0.1030521065 0.1714278609 0.0041799766 0.0906100000 27517025 955859216 1777479680 0.1009095758 -0.0566709116 0.0425240621 174 1311867724.4160330296 0.1714081317 0.1034449572 0.1714278609 0.0041766066 0.0795520000 27518727 955859216 1776721920 0.1013155952 -0.0569456369 0.0423551202 175 1311867724.4509639740 0.1715192348 0.1038339531 0.1715192348 0.0041666141 0.0943280000 27520525 955859216 1775431680 0.1010696366 -0.0576579943 0.0419264138 176 1311867724.4830689430 0.1719551682 0.1042210055 0.1719551682 0.0041554921 0.1058240000 27522291 955859216 1774690304 0.1011844128 -0.0581718832 0.0414986275 177 1311867724.5208630562 0.1709138453 0.1045978012 0.1719551682 0.0041467090 0.1447800000 27524089 955859216 1773674496 0.0995503366 -0.0586526915 0.0412866250 178 1311867724.5523910522 0.1705144644 0.1049681195 0.1719551682 0.0041379934 0.1111980000 27525887 955859216 1772130304 0.0990746841 -0.0590738840 0.0401785411 179 1311867724.5861799717 0.1688975692 0.1053252673 0.1719551682 0.0041359816 0.0969110000 27527653 955859216 1773776896 0.0970727205 -0.0595205389 0.0390955471 180 1311867724.6193559170 0.1683125794 0.1056751968 0.1719551682 0.0041689701 0.0965000000 27529419 955859216 1775407104 0.0963458493 -0.0595280528 0.0381175466 181 1311867724.6529819965 0.1669110805 0.1060135166 0.1719551682 0.0041730869 0.0982660000 27531217 955859216 1777057792 0.0943563282 -0.0594998822 0.0379117578 182 1311867724.6818330288 0.1638555229 0.1063313298 0.1719551682 0.0041643268 0.0981840000 27532919 955859216 1778827264 0.0907971263 -0.0598765872 0.0362371951 183 1311867724.7153129578 0.1606009752 0.1066278852 0.1719551682 0.0041809751 0.1204190000 27534717 955859216 1780477952 0.0871420205 -0.0590145811 0.0351791307 184 1311867724.7518899441 0.1578473896 0.1069062521 0.1719551682 0.0041924410 0.0753780000 27536547 955859216 1782145024 0.0839346498 -0.0578831993 0.0348557718 185 1311867724.7853860855 0.1553277224 0.1071679898 0.1719551682 0.0041944993 0.0759630000 27538345 955859216 1783906304 0.0809681043 -0.0576795191 0.0341828614 186 1311867724.8179960251 0.1526985914 0.1074127780 0.1719551682 0.0041839282 0.1165250000 27540111 955859216 1785556992 0.0778961107 -0.0576167107 0.0330155492 187 1311867724.8547580242 0.1505354494 0.1076433805 0.1719551682 0.0042239074 0.1022280000 27541909 955859216 1784848384 0.0752164498 -0.0574352518 0.0326890424 188 1311867724.8830249310 0.1481963992 0.1078590880 0.1719551682 0.0042221674 0.1071550000 27543611 955859216 1783697408 0.0725126863 -0.0571149439 0.0321392454 189 1311867724.9137279987 0.1466650367 0.1080644105 0.1719551682 0.0042183169 0.1441780000 27545377 955859216 1779257344 0.0704429001 -0.0573763400 0.0311092045 190 1311867724.9535229206 0.1447062343 0.1082572622 0.1719551682 0.0042201888 0.1321450000 27547239 955859216 1780912128 0.0683076754 -0.0570166633 0.0301212240 191 1311867724.9843940735 0.1431968212 0.1084401918 0.1719551682 0.0042103000 0.0734920000 27549005 955859216 1782509568 0.0666984841 -0.0568687730 0.0291994065 192 1311867725.0159099102 0.1418470889 0.1086141861 0.1719551682 0.0042242119 0.0769010000 27550739 955859216 1784307712 0.0652661845 -0.0570748225 0.0287527274 193 1311867725.0518310070 0.1400519311 0.1087770760 0.1719551682 0.0042193776 0.1177360000 27552569 955859216 1785937920 0.0628942028 -0.0574495010 0.0285102148 194 1311867725.0813930035 0.1389290541 0.1089324985 0.1719551682 0.0042118380 0.1398380000 27554303 955859216 1785094144 0.0614455976 -0.0572786219 0.0283269696 195 1311867725.1151220798 0.1379711181 0.1090814145 0.1719551682 0.0042013537 0.1157250000 27556101 955859216 1784078336 0.0601313002 -0.0578060970 0.0275758468 196 1311867725.1557130814 0.1363765448 0.1092206754 0.1719551682 0.0042014780 0.1099730000 27557995 955859216 1782951936 0.0580167733 -0.0578191355 0.0272563770 197 1311867725.1843969822 0.1350448132 0.1093517624 0.1719551682 0.0042003812 0.1312860000 27559697 955859216 1781919744 0.0562005378 -0.0579888783 0.0270406660 198 1311867725.2150099277 0.1333830655 0.1094731326 0.1719551682 0.0041929443 0.1350730000 27561463 955859216 1783414784 0.0538386926 -0.0587475151 0.0260341391 199 1311867725.2516539097 0.1313461363 0.1095830472 0.1719551682 0.0041915455 0.1139670000 27563325 955859216 1785176064 0.0511659235 -0.0586932413 0.0257764850 200 1311867725.2816410065 0.1292552650 0.1096814083 0.1719551682 0.0041860386 0.0998780000 27565059 955859216 1784332288 0.0487407744 -0.0587069020 0.0249013957 201 1311867725.3196239471 0.1281524003 0.1097733038 0.1719551682 0.0041825374 0.0971930000 27566889 955859216 1782525952 0.0470839739 -0.0588744469 0.0242413227 202 1311867725.3517010212 0.1263845861 0.1098555379 0.1719551682 0.0041871480 0.0967150000 27568623 955859216 1781919744 0.0446402952 -0.0591032431 0.0245997123 203 1311867725.3837459087 0.1252881140 0.1099315604 0.1719551682 0.0042223687 0.0805380000 27570325 955859216 1780776960 0.0435192995 -0.0587150864 0.0243205912 204 1311867725.4178969860 0.1243974045 0.1100024714 0.1719551682 0.0042254844 0.0905350000 27572155 955859216 1778974720 0.0421169028 -0.0588482693 0.0240761954 205 1311867725.4492449760 0.1228699014 0.1100652393 0.1719551682 0.0042408440 0.1186210000 27573889 955859216 1778364416 0.0398419984 -0.0586441755 0.0241299905 206 1311867725.4836509228 0.1221013144 0.1101236669 0.1719551682 0.0042698337 0.1062960000 27575687 955859216 1777348608 0.0383394137 -0.0584699735 0.0239829086 207 1311867725.5178139210 0.1211005449 0.1101766953 0.1719551682 0.0042670487 0.1189140000 27577549 955859216 1776332800 0.0367999375 -0.0582205877 0.0231634453 208 1311867725.5497610569 0.1203004643 0.1102253673 0.1719551682 0.0042570645 0.1338280000 27579283 955859216 1777811456 0.0349818505 -0.0586592853 0.0231309421 209 1311867725.5815479755 0.1193053573 0.1102688122 0.1719551682 0.0042481166 0.0787640000 27581049 955859216 1779609600 0.0332414024 -0.0584526360 0.0227409247 210 1311867725.6194949150 0.1190700978 0.1103107231 0.1719551682 0.0042399454 0.0772490000 27582911 955859216 1781239808 0.0321966074 -0.0587899461 0.0225488003 211 1311867725.6515610218 0.1186224297 0.1103501150 0.1719551682 0.0043038284 0.0779500000 27584677 955859216 1782906880 0.0307815745 -0.0593386404 0.0224711969 212 1311867725.6834650040 0.1182772070 0.1103875070 0.1719551682 0.0043010085 0.1186000000 27586443 955859216 1784668160 0.0293994751 -0.0597305894 0.0232730303 213 1311867725.7201809883 0.1177812591 0.1104222194 0.1719551682 0.0042927129 0.1202970000 27588273 955859216 1783824384 0.0278572738 -0.0602023005 0.0238292962 214 1311867725.7515070438 0.1178263575 0.1104568182 0.1719551682 0.0042826695 0.0929920000 27590039 955859216 1782681600 0.0269483067 -0.0610531941 0.0236683227 215 1311867725.7835409641 0.1056961343 0.1104346755 0.1719551682 0.0043177129 0.1311440000 27591773 955859216 1781665792 0.0126759168 -0.0594348572 0.0221265424 216 1311867725.8211829662 0.1025491878 0.1103981686 0.1719551682 0.0043417368 0.1303080000 27593667 955859216 1780649984 0.0075064516 -0.0604488961 0.0212557726 217 1311867725.8517971039 0.1011673659 0.1103556303 0.1719551682 0.0043321339 0.0757810000 27595433 955859216 1782128640 0.0048920731 -0.0609160624 0.0205479749 218 1311867725.8837900162 0.1002722755 0.1103093764 0.1719551682 0.0043512762 0.0767310000 27597135 955859216 1783779328 0.0031353123 -0.0605168045 0.0208002627 219 1311867725.9192690849 0.1003446504 0.1102638754 0.1719551682 0.0043426171 0.1352820000 27598965 955859216 1785577472 0.0017639261 -0.0612886064 0.0212286990 220 1311867725.9511859417 0.1006585732 0.1102202149 0.1719551682 0.0043347468 0.1008700000 27600731 955859216 1784586240 0.0006661844 -0.0622579008 0.0221484099 221 1311867725.9829630852 0.1012503728 0.1101796274 0.1719551682 0.0043346547 0.0969860000 27602465 955859216 1782784000 0.0004772018 -0.0623921454 0.0232165251 222 1311867726.0219368935 0.1034712791 0.1101494096 0.1719551682 0.0043286349 0.0924730000 27604359 955859216 1782157312 0.0006799424 -0.0639509410 0.0259727817 223 1311867726.0504179001 0.1051692814 0.1101270772 0.1719551682 0.0043207854 0.1057110000 27606029 955859216 1781030912 0.0003759852 -0.0658338293 0.0280659273 224 1311867726.0845088959 0.1068133637 0.1101122838 0.1719551682 0.0043244170 0.1462600000 27607859 955859216 1776435200 0.0001388746 -0.0673541203 0.0310924985 225 1311867726.1199669838 0.1090884209 0.1101077333 0.1719551682 0.0043160916 0.0930550000 27609657 955859216 1776177152 0.0003463514 -0.0692841485 0.0336199328 226 1311867726.1506989002 0.1102328524 0.1101082870 0.1719551682 0.0043137088 0.0768330000 27611423 955859216 1774907392 0.0001956159 -0.0703171864 0.0349935703 227 1311867726.1824700832 0.1116517037 0.1101150862 0.1719551682 0.0043206289 0.1096380000 27613189 955859216 1776074752 -0.0004058522 -0.0716617852 0.0375358760 228 1311867726.2198660374 0.1131031811 0.1101281918 0.1719551682 0.0043430565 0.1511830000 27615019 955859216 1772642304 -0.0006753169 -0.0728289858 0.0395299420 229 1311867726.2506690025 0.1155520380 0.1101518768 0.1719551682 0.0043390851 0.0914730000 27616785 955859216 1773920256 -0.0005368190 -0.0749380589 0.0420753211 230 1311867726.2845950127 0.1182830408 0.1101872296 0.1719551682 0.0043438930 0.0763900000 27618551 955859216 1772630016 -0.0005718074 -0.0770693794 0.0455338173 231 1311867726.3187239170 0.1209024042 0.1102336157 0.1719551682 0.0043451380 0.0987320000 27620381 955859216 1771761664 -0.0001373440 -0.0787325799 0.0480348878 232 1311867726.3524029255 0.1234642267 0.1102906442 0.1719551682 0.0043440990 0.1081060000 27622179 955859216 1770872832 0.0003698338 -0.0799579471 0.0510489494 233 1311867726.3835608959 0.1261678636 0.1103587868 0.1719551682 0.0043388903 0.0986040000 27623913 955859216 1769857024 0.0003543180 -0.0817412660 0.0538893454 234 1311867726.4218099117 0.1282906532 0.1104354187 0.1719551682 0.0043375006 0.1352560000 27625807 955859216 1768841216 0.0005096435 -0.0825889483 0.0564161651 235 1311867726.4504199028 0.1310263425 0.1105230396 0.1719551682 0.0043325356 0.1340780000 27627509 955859216 1770319872 0.0004144674 -0.0842121691 0.0597468168 236 1311867726.4843189716 0.1332632601 0.1106193965 0.1719551682 0.0043287963 0.0774020000 27629307 955859216 1772097536 0.0001832666 -0.0856858194 0.0622754917 237 1311867726.5207901001 0.1364833117 0.1107285269 0.1719551682 0.0043292130 0.0767480000 27631137 955859216 1773748224 0.0003291727 -0.0876297876 0.0658018216 238 1311867726.5524380207 0.1396728903 0.1108501419 0.1719551682 0.0043327221 0.0785600000 27632903 955859216 1775546368 0.0015229504 -0.0891171992 0.0687539130 239 1311867726.5874860287 0.1426828504 0.1109833331 0.1719551682 0.0043314224 0.0767610000 27634733 955859216 1777176576 0.0016712697 -0.0907406732 0.0722485110 240 1311867726.6204600334 0.1446533054 0.1111236247 0.1719551682 0.0043463163 0.1164810000 27636499 955859216 1778843648 0.0025303531 -0.0915918052 0.0741700754 241 1311867726.6509370804 0.1466317773 0.1112709614 0.1719551682 0.0043520393 0.1361570000 27638233 955859216 1780604928 0.0033181980 -0.0928429812 0.0756292641 242 1311867726.6916151047 0.1471151561 0.1114190779 0.1719551682 0.0043430936 0.1190020000 27640159 955859216 1782255616 0.0035937866 -0.0932590216 0.0757317916 243 1311867726.7201170921 0.1474871039 0.1115675060 0.1719551682 0.0043364612 0.1192040000 27641829 955859216 1783922688 0.0044521447 -0.0934059173 0.0754986033 244 1311867726.7513859272 0.1464482099 0.1117104597 0.1719551682 0.0043322992 0.0918430000 27643595 955859216 1785683968 0.0041609751 -0.0932510346 0.0742244720 245 1311867726.7880010605 0.1445914060 0.1118446677 0.1719551682 0.0043332806 0.0811480000 27645457 955859216 1784856576 0.0038124525 -0.0927062109 0.0720208362 246 1311867726.8198299408 0.1425539553 0.1119695022 0.1719551682 0.0043246821 0.0778990000 27647191 955859216 1783963648 0.0034714988 -0.0915891230 0.0699397996 247 1311867726.8500390053 0.1416252255 0.1120895658 0.1719551682 0.0043185486 0.0945000000 27648925 955859216 1781497856 0.0037084729 -0.0910400078 0.0686182082 248 1311867726.8927390575 0.1410814077 0.1122064684 0.1719551682 0.0043098846 0.0949010000 27650883 955859216 1781538816 0.0037921346 -0.0909456015 0.0678479522 249 1311867726.9216780663 0.1400526315 0.1123183004 0.1719551682 0.0043030951 0.1156110000 27652585 955859216 1780523008 0.0036697597 -0.0901048407 0.0671290010 250 1311867726.9543499947 0.1386324763 0.1124235571 0.1719551682 0.0043121711 0.1309820000 27654351 955859216 1777319936 0.0038845185 -0.0890557393 0.0659671575 251 1311867726.9902989864 0.1371724457 0.1125221583 0.1719551682 0.0043069022 0.1077320000 27656149 955859216 1778110464 0.0031496976 -0.0886868387 0.0644656569 252 1311867727.0208179951 0.1356561333 0.1126139597 0.1719551682 0.0043030486 0.1210580000 27657915 955859216 1777094656 0.0034147655 -0.0876099020 0.0625419766 253 1311867727.0536949635 0.1339837611 0.1126984254 0.1719551682 0.0043022165 0.1133590000 27659681 955859216 1772744704 0.0032661902 -0.0869216993 0.0607533939 254 1311867727.0911629200 0.1329761297 0.1127782588 0.1719551682 0.0042984002 0.1130640000 27661543 955859216 1774419968 0.0033084301 -0.0862712860 0.0599284284 255 1311867727.1196689606 0.1310247332 0.1128498136 0.1719551682 0.0042954215 0.1351250000 27663181 955859216 1776033792 0.0028599498 -0.0855216905 0.0576550998 256 1311867727.1514298916 0.1290648133 0.1129131535 0.1719551682 0.0042911648 0.0983450000 27664979 955859216 1777811456 0.0019322839 -0.0848679543 0.0561411791 257 1311867727.1904149055 0.1282856464 0.1129729686 0.1719551682 0.0042976368 0.1190080000 27687289 955859216 1779589120 0.0023603991 -0.0839983821 0.0558955371 258 1311867727.2208960056 0.1266319752 0.1130259105 0.1719551682 0.0042905617 0.0942400000 27731039 955859216 1781239808 0.0016505276 -0.0831798837 0.0549206622 259 1311867727.2544560432 0.1240206137 0.1130683611 0.1719551682 0.0042904359 0.0771920000 27732805 955859216 1783037952 0.0003038547 -0.0823038965 0.0523286983 260 1311867727.2870850563 0.1220187470 0.1131027857 0.1719551682 0.0042846551 0.1399640000 27734603 955859216 1784668160 -0.0002540224 -0.0812892318 0.0505788550 261 1311867727.3192501068 0.1199019030 0.1131288359 0.1719551682 0.0042826580 0.0931890000 27736369 955859216 1783840768 -0.0005418216 -0.0804202035 0.0481853411 262 1311867727.3502039909 0.1175842360 0.1131458413 0.1719551682 0.0042923176 0.0982070000 27738103 955859216 1782149120 -0.0010597970 -0.0796264336 0.0453767292 263 1311867727.3894629478 0.1144371778 0.1131507513 0.1719551682 0.0042969804 0.1518260000 27739933 955859216 1781411840 -0.0013919147 -0.0774542913 0.0424315929 264 1311867727.4182970524 0.1104192138 0.1131404046 0.1719551682 0.0042959685 0.1107860000 27741667 955859216 1778081792 -0.0022000158 -0.0751393288 0.0387015790 265 1311867727.4495580196 0.1068393141 0.1131166269 0.1719551682 0.0043000791 0.1137300000 27743369 955859216 1778896896 -0.0031182340 -0.0729256719 0.0352981947 266 1311867727.4858360291 0.1040188298 0.1130824246 0.1719551682 0.0042942410 0.1169360000 27745231 955859216 1777864704 -0.0037870845 -0.0707257092 0.0332317613 267 1311867727.5198891163 0.1014171317 0.1130387344 0.1719551682 0.0042953129 0.0944350000 27746997 955859216 1776848896 -0.0046098907 -0.0690597296 0.0308415610 268 1311867727.5494980812 0.0991172120 0.1129867884 0.1719551682 0.0042970030 0.1162600000 27748731 955859216 1778327552 -0.0054963492 -0.0682339892 0.0281697270 269 1311867727.5905909538 0.0961386561 0.1129241559 0.1719551682 0.0042977186 0.0952240000 27750657 955859216 1779994624 -0.0067052171 -0.0671170503 0.0258729644 270 1311867727.6176431179 0.0940304399 0.1128541792 0.1719551682 0.0042906389 0.0793610000 27752327 955859216 1781755904 -0.0077106138 -0.0661831722 0.0239345450 271 1311867727.6497650146 0.0915520862 0.1127755737 0.1719551682 0.0042920292 0.0956920000 27754093 955859216 1783406592 -0.0088912165 -0.0651376545 0.0215306357 272 1311867727.6884338856 0.0887309238 0.1126871743 0.1719551682 0.0042920710 0.0975940000 27755859 955859216 1785184256 -0.0108129736 -0.0642935261 0.0191076286 273 1311867727.7184689045 0.0858338773 0.1125888105 0.1719551682 0.0042860381 0.1011720000 27757625 955859216 1784213504 -0.0131717781 -0.0632393211 0.0165384170 274 1311867727.7523269653 0.0829384699 0.1124805976 0.1719551682 0.0042812020 0.0983910000 27759423 955859216 1783197696 -0.0170559566 -0.0633274391 0.0144646270 275 1311867727.7856590748 0.0801796913 0.1123631398 0.1719551682 0.0042878292 0.0871860000 27761189 955859216 1782181888 -0.0211222153 -0.0630551875 0.0142855812 276 1311867727.8181309700 0.0776440576 0.1122373460 0.1719551682 0.0042988887 0.0799610000 27762987 955859216 1781039104 -0.0243918393 -0.0622418970 0.0131829791 277 1311867727.8548729420 0.0752571896 0.1121038436 0.1719551682 0.0042972155 0.1058940000 27764817 955859216 1780023296 -0.0276265554 -0.0617158636 0.0120040905 278 1311867727.8882629871 0.0729458705 0.1119629876 0.1719551682 0.0042952200 0.1397720000 27766615 955859216 1779007488 -0.0310950428 -0.0613607578 0.0112433964 279 1311867727.9193139076 0.0713741705 0.1118175080 0.1719551682 0.0042928702 0.0948980000 27768349 955859216 1777737728 -0.0333979279 -0.0609121360 0.0108228493 280 1311867727.9556980133 0.0693384632 0.1116657971 0.1719551682 0.0042887391 0.0986970000 27770179 955859216 1775824896 -0.0362449251 -0.0603685826 0.0097311744 281 1311867727.9869389534 0.0674779117 0.1115085448 0.1719551682 0.0042838911 0.0920630000 27771977 955859216 1775452160 -0.0385971852 -0.0597196519 0.0084690535 282 1311867728.0179219246 0.0662065446 0.1113478995 0.1719551682 0.0042805010 0.0781860000 27773679 955859216 1774436352 -0.0403628759 -0.0594018176 0.0079830289 283 1311867728.0555219650 0.0642100945 0.1111813348 0.1719551682 0.0042781470 0.0930990000 27775541 955859216 1773420544 -0.0427687429 -0.0584844090 0.0071017267 284 1311867728.0892169476 0.0626470521 0.1110104394 0.1719551682 0.0042742812 0.0778510000 27777339 955859216 1772531712 -0.0445491411 -0.0577320680 0.0062845927 285 1311867728.1177880764 0.0612750947 0.1108359294 0.1719551682 0.0042803820 0.0944290000 27779073 955859216 1771003904 -0.0468639880 -0.0570954308 0.0054701013 286 1311867728.1556169987 0.0602072999 0.1106589062 0.1719551682 0.0042819229 0.0992450000 27780903 955859216 1770246144 -0.0489668027 -0.0566656031 0.0048471596 287 1311867728.1882989407 0.0592600554 0.1104798162 0.1719551682 0.0042758245 0.1296750000 27782733 955859216 1769230336 -0.0508678071 -0.0562143102 0.0038668774 288 1311867728.2182519436 0.0585762411 0.1102995954 0.1719551682 0.0042723912 0.0978200000 27784467 955859216 1768230912 -0.0525694601 -0.0559290238 0.0030498656 289 1311867728.2558999062 0.0578081906 0.1101179643 0.1719551682 0.0042675896 0.1143050000 27786297 955859216 1769840640 -0.0549387522 -0.0555458143 0.0022846367 290 1311867728.2875900269 0.0572755337 0.1099357490 0.1719551682 0.0042797722 0.0780080000 27788063 955859216 1771470848 -0.0609961934 -0.0556269512 0.0019535348 291 1311867728.3226509094 0.0564447269 0.1097519310 0.1719551682 0.0042784594 0.0962990000 27789893 955859216 1773121536 -0.0643437356 -0.0549936555 0.0014354010 292 1311867728.3597300053 0.0565804541 0.1095698369 0.1719551682 0.0042791085 0.0978430000 27791691 955859216 1774899200 -0.0670724511 -0.0550480895 0.0006307121 293 1311867728.3861401081 0.0556723326 0.1093858864 0.1719551682 0.0042782388 0.1357370000 27793393 955859216 1776549888 -0.0701962486 -0.0538117662 -0.0012289491 294 1311867728.4175701141 0.0566076934 0.1092063688 0.1719551682 0.0043337629 0.1178850000 27795159 955859216 1778348032 -0.0723064020 -0.0539555177 -0.0021301263 295 1311867728.4568250179 0.0567639805 0.1090285979 0.1719551682 0.0043285429 0.0779030000 27797021 955859216 1779978240 -0.0753012598 -0.0534583256 -0.0033971872 296 1311867728.4875330925 0.0561289340 0.1088498829 0.1719551682 0.0043252397 0.0956950000 27798755 955859216 1781628928 -0.0762887597 -0.0525621325 -0.0043909345 297 1311867728.5187420845 0.0569501854 0.1086751364 0.1719551682 0.0043199654 0.1000220000 27800489 955859216 1783427072 -0.0795921832 -0.0524263531 -0.0046605282 298 1311867728.5550920963 0.0579717532 0.1085049908 0.1719551682 0.0043246600 0.1353700000 27802351 955859216 1785057280 -0.0835541487 -0.0519723557 -0.0053360951 299 1311867728.5878560543 0.0592820533 0.1083403656 0.1719551682 0.0043234732 0.1007130000 27804149 955859216 1784201216 -0.0874497667 -0.0514831990 -0.0064896531 300 1311867728.6187679768 0.0616108589 0.1081846006 0.1719551682 0.0043301384 0.0763010000 27805851 955859216 1783070720 -0.0927753225 -0.0510857180 -0.0072260192 301 1311867728.6580820084 0.0648469925 0.1080406218 0.1719551682 0.0043454459 0.0948830000 27807745 955859216 1781268480 -0.0987118557 -0.0506946221 -0.0083830878 302 1311867728.6893489361 0.0686963946 0.1079103429 0.1719551682 0.0043462139 0.0951170000 27809511 955859216 1780785152 -0.1047968641 -0.0505507700 -0.0095704794 303 1311867728.7210168839 0.0722618327 0.1077926911 0.1719551682 0.0043444986 0.1310300000 27811277 955859216 1779769344 -0.1103996187 -0.0503218733 -0.0104986327 304 1311867728.7584259510 0.0761038214 0.1076884514 0.1719551682 0.0043505426 0.0956310000 27813107 955859216 1778753536 -0.1154270992 -0.0502229705 -0.0115380147 305 1311867728.7858450413 0.0791880041 0.1075950073 0.1719551682 0.0043516304 0.0755810000 27814841 955859216 1780232192 -0.1192234084 -0.0504363403 -0.0117212096 306 1311867728.8203740120 0.0791201741 0.1075019523 0.1719551682 0.0043453245 0.1169700000 27816607 955859216 1781874688 -0.1190762520 -0.0500524268 -0.0124029890 307 1311867728.8545160294 0.0810861737 0.1074159074 0.1719551682 0.0043412695 0.1365290000 27818405 955859216 1783541760 -0.1217247099 -0.0495281592 -0.0135723213 308 1311867728.8860759735 0.0820968002 0.1073337025 0.1719551682 0.0043356473 0.1557210000 27820203 955859216 1785303040 -0.1229604036 -0.0492080972 -0.0152611919 309 1311867728.9193949699 0.0832351521 0.1072557137 0.1719551682 0.0043298583 0.0983720000 27821937 955859216 1784451072 -0.1245089024 -0.0486967415 -0.0156364143 310 1311867728.9585559368 0.0840712339 0.1071809250 0.1719551682 0.0043531368 0.0769890000 27823895 955859216 1783316480 -0.1253625602 -0.0480487421 -0.0166137349 311 1311867728.9886839390 0.0861527249 0.1071133102 0.1719551682 0.0043506006 0.1011020000 27825565 955859216 1782300672 -0.1272407919 -0.0484405532 -0.0169985853 312 1311867729.0231020451 0.0876970887 0.1070510788 0.1719551682 0.0043479860 0.0883020000 27827395 955859216 1781284864 -0.1287238300 -0.0481760055 -0.0170003138 313 1311867729.0583839417 0.0893144980 0.1069944124 0.1719551682 0.0043468659 0.0987910000 27829225 955859216 1780142080 -0.1308097094 -0.0474601090 -0.0172672048 314 1311867729.0882170200 0.0913872421 0.1069447080 0.1719551682 0.0043421537 0.1340260000 27830959 955859216 1779126272 -0.1331413984 -0.0476313382 -0.0168850292 315 1311867729.1263229847 0.0914548188 0.1068955338 0.1719551682 0.0043560785 0.1518510000 27832821 955859216 1778110464 -0.1341515481 -0.0466087125 -0.0167484321 316 1311867729.1556320190 0.0922914222 0.1068493182 0.1719551682 0.0043504773 0.1126460000 27834523 955859216 1779589120 -0.1360844970 -0.0457638428 -0.0166532323 317 1311867729.1888830662 0.0939872712 0.1068087439 0.1719551682 0.0043775171 0.1171490000 27836321 955859216 1781239808 -0.1387273371 -0.0455597863 -0.0166084133 318 1311867729.2240469456 0.0961711481 0.1067752924 0.1719551682 0.0043823664 0.0972820000 27838119 955859216 1783017472 -0.1412463486 -0.0452948771 -0.0168011151 319 1311867729.2579979897 0.0991777703 0.1067514757 0.1719551682 0.0043769105 0.1390760000 27839949 955859216 1784668160 -0.1444155723 -0.0456247702 -0.0164008029 320 1311867729.2880148888 0.1028164849 0.1067391788 0.1719551682 0.0043741884 0.1179980000 27841683 955859216 1783824384 -0.1481113434 -0.0461525694 -0.0162396729 321 1311867729.3236539364 0.1071553528 0.1067404753 0.1719551682 0.0043758765 0.0957410000 27843481 955859216 1782808576 -0.1525363177 -0.0459349938 -0.0162035841 322 1311867729.3580930233 0.1113569140 0.1067548121 0.1719551682 0.0043906269 0.0772270000 27845311 955859216 1781665792 -0.1562943757 -0.0458731055 -0.0165582485 323 1311867729.3882780075 0.1144994870 0.1067787894 0.1719551682 0.0043894875 0.1345060000 27847013 955859216 1780649984 -0.1590681225 -0.0456734896 -0.0164106749 324 1311867729.4253289700 0.1179959327 0.1068134102 0.1719551682 0.0043888556 0.0918200000 27848875 955859216 1779523584 -0.1624593586 -0.0449220017 -0.0167810060 325 1311867729.4572670460 0.1204508767 0.1068553717 0.1719551682 0.0043879980 0.1353690000 27850641 955859216 1778491392 -0.1644035876 -0.0443050154 -0.0180517882 326 1311867729.4887750149 0.1225449517 0.1069034992 0.1719551682 0.0043993935 0.0960230000 27852439 955859216 1780117504 -0.1662354022 -0.0439481698 -0.0190998688 327 1311867729.5223650932 0.1257802993 0.1069612264 0.1719551682 0.0043976404 0.0776860000 27854205 955859216 1781747712 -0.1691383868 -0.0440335236 -0.0194568187 328 1311867729.5603790283 0.1284358799 0.1070266979 0.1719551682 0.0043956250 0.1188150000 27856067 955859216 1783398400 -0.1714396179 -0.0441081189 -0.0201834626 329 1311867729.5890150070 0.1296203732 0.1070953717 0.1719551682 0.0043895269 0.0958800000 27857769 955859216 1785196544 -0.1723371893 -0.0441549867 -0.0207751654 330 1311867729.6254830360 0.1319506317 0.1071706907 0.1719551682 0.0043869312 0.1571480000 27859599 955859216 1784205312 -0.1745540500 -0.0438827835 -0.0206875689 331 1311867729.6614611149 0.1341741085 0.1072522720 0.1719551682 0.0043821630 0.0933790000 27861429 955859216 1783189504 -0.1766137332 -0.0439484268 -0.0207109675 332 1311867729.6888220310 0.1352169365 0.1073365029 0.1719551682 0.0043772232 0.0947480000 27863067 955859216 1782046720 -0.1775600910 -0.0438743494 -0.0211827122 333 1311867729.7230739594 0.1376659572 0.1074275824 0.1719551682 0.0043733056 0.0955820000 27864897 955859216 1780883456 -0.1798663437 -0.0439282134 -0.0215012245 334 1311867729.7570610046 0.1398346424 0.1075246095 0.1719551682 0.0043706560 0.1159460000 27866599 955859216 1780015104 -0.1816343963 -0.0439054891 -0.0214810353 335 1311867729.7899730206 0.1430005282 0.1076305078 0.1719551682 0.0043655904 0.0933570000 27868397 955859216 1778999296 -0.1845115274 -0.0442775488 -0.0215686895 336 1311867729.8264250755 0.1458549351 0.1077442709 0.1719551682 0.0043664361 0.0967760000 27870195 955859216 1777983488 -0.1871464550 -0.0440257788 -0.0213460475 337 1311867729.8550031185 0.1492267847 0.1078673645 0.1719551682 0.0043648358 0.1161900000 27871897 955859216 1776713728 -0.1904439330 -0.0436345749 -0.0209153537 338 1311867729.8881840706 0.1512449533 0.1079957005 0.1719551682 0.0043620168 0.1337660000 27873727 955859216 1778192384 -0.1922782063 -0.0438125618 -0.0211241599 339 1311867729.9233629704 0.1547992229 0.1081337640 0.1719551682 0.0043586773 0.0978210000 27875525 955859216 1779990528 -0.1957946569 -0.0433927551 -0.0211579204 340 1311867729.9569330215 0.1587500423 0.1082826354 0.1719551682 0.0043623772 0.1178820000 27877323 955859216 1781620736 -0.1997885406 -0.0432714559 -0.0204785261 341 1311867729.9865698814 0.1612883806 0.1084380775 0.1719551682 0.0043612604 0.1382510000 27879025 955859216 1783287808 -0.2021741420 -0.0434815995 -0.0206804946 342 1311867730.0230469704 0.1644854248 0.1086019586 0.1719551682 0.0043571667 0.1334160000 27880855 955859216 1785049088 -0.2052933723 -0.0432473719 -0.0207412075 343 1311867730.0557899475 0.1675300598 0.1087737607 0.1719551682 0.0043544086 0.0995270000 27882653 955859216 1784193024 -0.2083978504 -0.0428865775 -0.0201233495 344 1311867730.0871100426 0.1703264415 0.1089526929 0.1719551682 0.0043506026 0.1330270000 27884419 955859216 1783062528 -0.2110106200 -0.0428951085 -0.0203402564 345 1311867730.1231229305 0.1714750677 0.1091339171 0.1719551682 0.0043457024 0.1167590000 27886249 955859216 1778614272 -0.2120260894 -0.0428623557 -0.0198931694 346 1311867730.1568520069 0.1733629405 0.1093195502 0.1733629405 0.0043404064 0.1337800000 27888047 955859216 1780273152 -0.2139036506 -0.0428047180 -0.0192401111 347 1311867730.1882419586 0.1757553816 0.1095110079 0.1757553816 0.0043382307 0.1102110000 27889781 955859216 1781874688 -0.2162283659 -0.0421959646 -0.0195553172 348 1311867730.2224810123 0.1782507747 0.1097085359 0.1782507747 0.0043335414 0.0980250000 27891611 955859216 1783525376 -0.2187922895 -0.0417484939 -0.0191081837 349 1311867730.2575879097 0.1801902801 0.1099104894 0.1801902801 0.0043283659 0.1180310000 27893409 955859216 1785323520 -0.2208730578 -0.0410833061 -0.0189881101 350 1311867730.2914879322 0.1803537458 0.1101117558 0.1803537458 0.0043234627 0.1176930000 27895207 955859216 1784467456 -0.2209909260 -0.0404882766 -0.0190784093 351 1311867730.3230810165 0.1807077229 0.1103128839 0.1807077229 0.0043202428 0.0951900000 27896973 955859216 1783443456 -0.2213157117 -0.0402401164 -0.0193135068 352 1311867730.3554260731 0.1832084358 0.1105199736 0.1832084358 0.0043223959 0.1266620000 27898739 955859216 1782300672 -0.2234818041 -0.0404955857 -0.0190741643 353 1311867730.3982920647 0.1827552468 0.1107246061 0.1832084358 0.0043196481 0.0966960000 27900665 955859216 1781284864 -0.2228640616 -0.0399870835 -0.0187694225 354 1311867730.4225230217 0.1837105304 0.1109307810 0.1837105304 0.0043204657 0.1173620000 27902335 955859216 1780142080 -0.2240751237 -0.0392622575 -0.0183180403 355 1311867730.4600110054 0.1840624660 0.1111367857 0.1840624660 0.0043148932 0.1331790000 27904165 955859216 1781768192 -0.2244233936 -0.0393973738 -0.0182916671 356 1311867730.4948410988 0.1857704371 0.1113464308 0.1857704371 0.0043164572 0.1563490000 27905963 955859216 1783398400 -0.2258634269 -0.0396496281 -0.0179739073 357 1311867730.5300729275 0.1870418787 0.1115584629 0.1870418787 0.0043111291 0.0950960000 27907761 955859216 1785049088 -0.2269322425 -0.0395530760 -0.0178558175 358 1311867730.5597670078 0.1866803169 0.1117683005 0.1870418787 0.0043058332 0.0797370000 27909495 955859216 1784205312 -0.2264284641 -0.0392659977 -0.0181357563 359 1311867730.5940020084 0.1893212795 0.1119843255 0.1893212795 0.0043041900 0.1344980000 27911325 955859216 1783189504 -0.2288813144 -0.0393306389 -0.0178861022 360 1311867730.6230149269 0.1892183125 0.1121988643 0.1893212795 0.0043039321 0.0922350000 27912995 955859216 1782046720 -0.2286119014 -0.0385022312 -0.0180386603 361 1311867730.6614060402 0.1925391257 0.1124214135 0.1925391257 0.0043015767 0.1180510000 27914857 955859216 1781030912 -0.2315537781 -0.0386047773 -0.0173896942 362 1311867730.6922950745 0.1934278011 0.1126451881 0.1934278011 0.0042959137 0.1230360000 27916623 955859216 1782509568 -0.2320581526 -0.0384850018 -0.0174830928 363 1311867730.7275629044 0.1949100047 0.1128718129 0.1949100047 0.0042957563 0.0859280000 27918421 955859216 1784160256 -0.2331868112 -0.0382949375 -0.0177960545 364 1311867730.7572948933 0.1958322525 0.1130997262 0.1958322525 0.0042907857 0.0776430000 27920155 955859216 1785937920 -0.2337527126 -0.0375040695 -0.0177218094 365 1311867730.7932779789 0.1973765045 0.1133306215 0.1973765045 0.0042855685 0.0970500000 27922017 955859216 1785077760 -0.2346638143 -0.0372706391 -0.0180816427 366 1311867730.8240480423 0.1967536360 0.1135585532 0.1973765045 0.0042810587 0.0957990000 27923719 955859216 1783951360 -0.2330152094 -0.0380140170 -0.0186792910 367 1311867730.8591129780 0.1965214461 0.1137846102 0.1973765045 0.0042765342 0.0961880000 27925549 955859216 1782824960 -0.2321160436 -0.0375441387 -0.0189300478 368 1311867730.8922739029 0.1975613236 0.1140122643 0.1975613236 0.0042730528 0.0922470000 27927251 955859216 1781792768 -0.2325923890 -0.0366169252 -0.0183398575 369 1311867730.9270720482 0.1985406131 0.1142413384 0.1985406131 0.0042729363 0.0791370000 27929081 955859216 1780666368 -0.2328391224 -0.0360212252 -0.0177375358 370 1311867730.9611239433 0.2002608627 0.1144738236 0.2002608627 0.0042736739 0.1313320000 27930847 955859216 1779634176 -0.2339359969 -0.0355041958 -0.0172882657 371 1311867730.9928169250 0.2007876039 0.1147064753 0.2007876039 0.0042743852 0.1196570000 27932613 955859216 1776558080 -0.2337572873 -0.0356771424 -0.0166161805 372 1311867731.0221049786 0.2024937272 0.1149424625 0.2024937272 0.0042714382 0.1171110000 27934347 955859216 1777348608 -0.2348439246 -0.0358590968 -0.0166206732 373 1311867731.0609729290 0.2046813965 0.1151830495 0.2046813965 0.0042686380 0.0899480000 27936209 955859216 1776332800 -0.2363347113 -0.0353695080 -0.0163433254 374 1311867731.0900061131 0.2045493573 0.1154219968 0.2046813965 0.0042675244 0.0952720000 27937911 955859216 1775333376 -0.2355798483 -0.0352651812 -0.0167417843 375 1311867731.1276559830 0.2049817741 0.1156608229 0.2049817741 0.0042630413 0.1110790000 27939773 955859216 1772609536 -0.2351127565 -0.0357045867 -0.0170749128 376 1311867731.1551880836 0.2063633353 0.1159020530 0.2063633353 0.0042580419 0.0951750000 27941475 955859216 1772371968 -0.2361733615 -0.0349636152 -0.0162878353 377 1311867731.1935870647 0.2071071267 0.1161439763 0.2071071267 0.0042551234 0.0926050000 27943305 955859216 1771888640 -0.2363671511 -0.0346637666 -0.0157737434 378 1311867731.2235820293 0.2077579200 0.1163863412 0.2077579200 0.0042498924 0.0779380000 27945071 955859216 1770872832 -0.2364719659 -0.0345601402 -0.0150371939 379 1311867731.2602028847 0.2095506489 0.1166321573 0.2095506489 0.0042482812 0.1291770000 27946869 955859216 1769984000 -0.2373925447 -0.0346209817 -0.0145215560 380 1311867731.2900059223 0.2113031894 0.1168812916 0.2113031894 0.0042879676 0.0960500000 27948603 955859216 1768968192 -0.2379081994 -0.0349267684 -0.0136149880 381 1311867731.3230779171 0.2092621475 0.1171237610 0.2113031894 0.0043817512 0.1280770000 27950401 955859216 1767714816 -0.2354844362 -0.0348821320 -0.0142997056 382 1311867731.3570859432 0.2071469575 0.1173594239 0.2113031894 0.0044118807 0.1419470000 27952231 955859216 1766809600 -0.2326341122 -0.0348551832 -0.0153094539 383 1311867731.3915760517 0.2065033913 0.1175921757 0.2113031894 0.0044080985 0.1150530000 27953997 955859216 1765539840 -0.2312313020 -0.0362580009 -0.0140320100 384 1311867731.4279849529 0.2077121884 0.1178268633 0.2113031894 0.0044266511 0.1092050000 27955859 955859216 1765031936 -0.2318247110 -0.0367414393 -0.0150667541 385 1311867731.4602010250 0.2089842707 0.1180636358 0.2113031894 0.0044470139 0.0955500000 27957625 955859216 1765158912 -0.2325149775 -0.0371777639 -0.0164710768 386 1311867731.4926180840 0.2103158236 0.1183026311 0.2113031894 0.0044562534 0.0965890000 27959391 955859216 1765031936 -0.2332849652 -0.0376150534 -0.0164117087 387 1311867731.5259540081 0.2134949267 0.1185486060 0.2134949267 0.0044584054 0.0980190000 27961157 955859216 1765031936 -0.2357046008 -0.0385058559 -0.0147506762 388 1311867731.5589148998 0.2168086916 0.1188018536 0.2168086916 0.0044601803 0.0919780000 27962923 955859216 1765269504 -0.2381511033 -0.0390493274 -0.0141318515 389 1311867731.5967359543 0.2198806256 0.1190616962 0.2198806256 0.0044703825 0.0956310000 27964817 955859216 1765031936 -0.2410646230 -0.0400860608 -0.0125976652 390 1311867731.6247410774 0.2236905247 0.1193299753 0.2236905247 0.0044880173 0.1153770000 27966487 955859216 1765158912 -0.2443364412 -0.0409240425 -0.0115927607 391 1311867731.6616659164 0.2273871154 0.1196063363 0.2273871154 0.0045088668 0.1316300000 27968349 955859216 1765031936 -0.2473969311 -0.0415424816 -0.0104612261 392 1311867731.6925039291 0.2313157916 0.1198913094 0.2313157916 0.0045053069 0.0962510000 27970083 955859216 1766637568 -0.2511025667 -0.0416533276 -0.0095350882 393 1311867731.7299311161 0.2338636667 0.1201813154 0.2338636667 0.0045086629 0.0770730000 27971945 955859216 1768288256 -0.2530424595 -0.0419511087 -0.0092294673 394 1311867731.7615330219 0.2362339497 0.1204758652 0.2362339497 0.0045043611 0.1366430000 27973711 955859216 1769938944 -0.2548891306 -0.0424915701 -0.0089521548 395 1311867731.7939310074 0.2383611500 0.1207743089 0.2383611500 0.0045017228 0.0777140000 27975477 955859216 1771716608 -0.2564481497 -0.0428235903 -0.0085587287 396 1311867731.8252151012 0.2398769855 0.1210750733 0.2398769855 0.0044965396 0.0767960000 27977211 955859216 1773367296 -0.2574485540 -0.0441122018 -0.0080078989 397 1311867731.8593230247 0.2400760502 0.1213748238 0.2400760502 0.0045074805 0.0944530000 27979009 955859216 1775165440 -0.2568575740 -0.0448169783 -0.0073193540 398 1311867731.8910930157 0.2393510491 0.1216712465 0.2400760502 0.0045137442 0.0976240000 27980807 955859216 1776795648 -0.2558324337 -0.0453130901 -0.0064875046 399 1311867731.9224479198 0.2375924289 0.1219617758 0.2400760502 0.0045119675 0.0954630000 27982573 955859216 1778573312 -0.2535939813 -0.0460759252 -0.0064636995 400 1311867731.9598410130 0.2357786596 0.1222463180 0.2400760502 0.0045104602 0.0767140000 27984371 955859216 1780224000 -0.2511443794 -0.0467886813 -0.0055916756 401 1311867731.9915709496 0.2340979874 0.1225252499 0.2400760502 0.0045077974 0.1170210000 27986137 955859216 1782022144 -0.2488943487 -0.0474999398 -0.0038844647 402 1311867732.0239229202 0.2320079505 0.1227975949 0.2400760502 0.0045198769 0.1184840000 27987903 955859216 1783652352 -0.2459728569 -0.0487119108 -0.0028517919 403 1311867732.0619950294 0.2282160521 0.1230591791 0.2400760502 0.0045288084 0.0864830000 27989765 955859216 1785303040 -0.2414764166 -0.0498824939 -0.0021928996 404 1311867732.0918290615 0.2246452272 0.1233106298 0.2400760502 0.0045299362 0.0982550000 27991499 955859216 1783812096 -0.2369868457 -0.0505979508 -0.0014616175 405 1311867732.1221950054 0.2209733129 0.1235517722 0.2400760502 0.0045447167 0.1132930000 27993265 955859216 1783189504 -0.2327051014 -0.0520262197 -0.0006950721 406 1311867732.1605980396 0.2184193879 0.1237854363 0.2400760502 0.0045556483 0.1368670000 27995095 955859216 1782173696 -0.2295763046 -0.0528455786 -0.0002155416 407 1311867732.1931400299 0.2167694271 0.1240138982 0.2400760502 0.0045627074 0.1105790000 27996893 955859216 1780776960 -0.2269235700 -0.0533353612 0.0001182594 408 1311867732.2232089043 0.2152931243 0.1242376218 0.2400760502 0.0046130186 0.0883700000 27998595 955859216 1779761152 -0.2253362387 -0.0541637726 0.0001940802 409 1311867732.2590498924 0.2134204358 0.1244556726 0.2400760502 0.0046386404 0.1237050000 28000425 955859216 1778745344 -0.2225227952 -0.0543060601 0.0004228838 410 1311867732.2903969288 0.2111382782 0.1246670936 0.2400760502 0.0047047561 0.1361830000 28002191 955859216 1777983488 -0.2200583220 -0.0543762520 0.0004681721 411 1311867732.3218240738 0.2103030533 0.1248754536 0.2400760502 0.0047289835 0.1414010000 28003957 955859216 1779462144 -0.2184855938 -0.0549517535 0.0000546202 412 1311867732.3607840538 0.2099660784 0.1250819843 0.2400760502 0.0047251130 0.1361710000 28005819 955859216 1781112832 -0.2172226757 -0.0551982969 0.0001282245 413 1311867732.3899528980 0.2110631764 0.1252901712 0.2400760502 0.0047223124 0.1544150000 28007521 955859216 1782910976 -0.2176584452 -0.0558030531 0.0006682016 414 1311867732.4218940735 0.2117564380 0.1254990269 0.2400760502 0.0047277854 0.1332800000 28009319 955859216 1784541184 -0.2172690034 -0.0568673499 0.0004015379 415 1311867732.4593050480 0.2120957375 0.1257076937 0.2400760502 0.0047293325 0.1182510000 28011149 955859216 1783713792 -0.2169348300 -0.0573513024 0.0005339087 416 1311867732.4918489456 0.2130419761 0.1259176318 0.2400760502 0.0047280149 0.0987870000 28012947 955859216 1782554624 -0.2169175744 -0.0582697876 0.0003855155 417 1311867732.5229809284 0.2147802711 0.1261307317 0.2400760502 0.0047272836 0.0980340000 28014681 955859216 1781538816 -0.2177495509 -0.0588451587 0.0007119551 418 1311867732.5698928833 0.2158363611 0.1263453385 0.2400760502 0.0047233276 0.0807250000 28016671 955859216 1780523008 -0.2178990841 -0.0589936338 0.0013239197 419 1311867732.5926280022 0.2168429792 0.1265613233 0.2400760502 0.0047186341 0.0841790000 28018309 955859216 1779380224 -0.2185212821 -0.0593316257 0.0016912892 420 1311867732.6242370605 0.2175375670 0.1267779334 0.2400760502 0.0047258104 0.0836450000 28020075 955859216 1778364416 -0.2186326087 -0.0597983338 0.0012810117 421 1311867732.6630299091 0.2182346582 0.1269951703 0.2400760502 0.0047289858 0.0905220000 28021937 955859216 1777475584 -0.2186685354 -0.0602240562 0.0018268118 422 1311867732.6922440529 0.2180232555 0.1272108766 0.2400760502 0.0047296407 0.1161860000 28023671 955859216 1776459776 -0.2182147503 -0.0597462393 0.0022414960 423 1311867732.7260940075 0.2189672887 0.1274277949 0.2400760502 0.0047279658 0.1534660000 28025469 955859216 1775443968 -0.2186855972 -0.0603500754 0.0023416842 424 1311867732.7601239681 0.2198718935 0.1276458234 0.2400760502 0.0047239077 0.1290480000 28027235 955859216 1777070080 -0.2192215621 -0.0609344877 0.0023963565 425 1311867732.7919039726 0.2209175080 0.1278652862 0.2400760502 0.0047224822 0.1169680000 28029033 955859216 1778700288 -0.2201350629 -0.0606297366 0.0024982465 426 1311867732.8280360699 0.2194604874 0.1280802984 0.2400760502 0.0047278307 0.0780290000 28030831 955859216 1780477952 -0.2184879631 -0.0602084175 0.0019233078 427 1311867732.8589270115 0.2173579037 0.1282893794 0.2400760502 0.0047288704 0.0768820000 28032597 955859216 1782128640 -0.2163926810 -0.0598696247 0.0014934801 428 1311867732.8912909031 0.2142259181 0.1284901657 0.2400760502 0.0047365727 0.0952440000 28034363 955859216 1783779328 -0.2132138014 -0.0590360351 0.0011169427 429 1311867732.9262781143 0.2133108675 0.1286878830 0.2400760502 0.0047357142 0.0960490000 28036193 955859216 1785556992 -0.2121261954 -0.0585574284 0.0015534684 430 1311867732.9602870941 0.2138402462 0.1288859118 0.2400760502 0.0047382652 0.1193410000 28037959 955859216 1784709120 -0.2122515142 -0.0593432039 0.0018569045 431 1311867732.9987640381 0.2142041773 0.1290838660 0.2400760502 0.0047337758 0.0955530000 28039853 955859216 1783570432 -0.2124541402 -0.0595539920 0.0022847578 432 1311867733.0276939869 0.2151716053 0.1292831431 0.2400760502 0.0047285533 0.1149920000 28041587 955859216 1782554624 -0.2133775204 -0.0592217110 0.0030548612 433 1311867733.0607628822 0.2162660807 0.1294840275 0.2400760502 0.0047441644 0.1582580000 28043353 955859216 1778970624 -0.2141583711 -0.0600415915 0.0030788518 434 1311867733.0977020264 0.2183871269 0.1296888734 0.2400760502 0.0047425128 0.0921050000 28045183 955859216 1780142080 -0.2160731405 -0.0603062361 0.0034981743 435 1311867733.1263020039 0.2199201137 0.1298963015 0.2400760502 0.0047382345 0.0760530000 28046885 955859216 1779126272 -0.2176808864 -0.0597504154 0.0039437562 436 1311867733.1625030041 0.2224771827 0.1301086430 0.2400760502 0.0047402950 0.1320630000 28048715 955859216 1778110464 -0.2198659778 -0.0609070808 0.0038371272 437 1311867733.1926651001 0.2250419706 0.1303258817 0.2400760502 0.0047359903 0.0972820000 28050449 955859216 1777094656 -0.2223606110 -0.0611484535 0.0040615019 438 1311867733.2259631157 0.2273298055 0.1305473519 0.2400760502 0.0047324371 0.0926400000 28052247 955859216 1778573312 -0.2244313508 -0.0608379170 0.0045133722 439 1311867733.2618060112 0.2297285646 0.1307732772 0.2400760502 0.0047345752 0.0784220000 28054077 955859216 1780350976 -0.2265427113 -0.0609913506 0.0045903847 440 1311867733.2919199467 0.2310472727 0.1310011726 0.2400760502 0.0047339504 0.0940960000 28055779 955859216 1782001664 -0.2277138680 -0.0610465817 0.0043011941 441 1311867733.3300418854 0.2330633253 0.1312326061 0.2400760502 0.0047427981 0.0793600000 28057641 955859216 1783652352 -0.2294235826 -0.0609967709 0.0044214763 442 1311867733.3602790833 0.2354059368 0.1314682923 0.2400760502 0.0047453863 0.0961090000 28059407 955859216 1785430016 -0.2313759029 -0.0614398830 0.0041958834 443 1311867733.3923840523 0.2382805794 0.1317094036 0.2400760502 0.0047409548 0.1171810000 28061173 955859216 1784598528 -0.2338022888 -0.0616537221 0.0039482974 444 1311867733.4289550781 0.2411710918 0.1319559389 0.2411710918 0.0047422817 0.0959280000 28063003 955859216 1783169024 -0.2363858670 -0.0611089766 0.0040043029 445 1311867733.4588150978 0.2436818480 0.1322070084 0.2436818480 0.0047387491 0.0953690000 28064673 955859216 1782300672 -0.2387626171 -0.0608851351 0.0038460903 446 1311867733.4956119061 0.2466043383 0.1324635046 0.2466043383 0.0047352185 0.1331390000 28066439 955859216 1781174272 -0.2414792925 -0.0608204417 0.0039498960 447 1311867733.5290400982 0.2484491467 0.1327229804 0.2484491467 0.0047334623 0.0974530000 28068237 955859216 1780142080 -0.2432095557 -0.0603443682 0.0041563367 448 1311867733.5630290508 0.2516219914 0.1329883799 0.2516219914 0.0047331828 0.1327200000 28070035 955859216 1781620736 -0.2460901886 -0.0604004003 0.0039837738 449 1311867733.5922229290 0.2546572983 0.1332593575 0.2546572983 0.0047300100 0.0989590000 28071737 955859216 1783418880 -0.2487796694 -0.0611066669 0.0039169113 450 1311867733.6283020973 0.2563796937 0.1335329582 0.2563796937 0.0047285728 0.0774410000 28073567 955859216 1785049088 -0.2502187788 -0.0612120405 0.0038701261 451 1311867733.6601879597 0.2587535083 0.1338106091 0.2587535083 0.0047244821 0.0973090000 28075333 955859216 1784193024 -0.2523708344 -0.0612908639 0.0042697191 452 1311867733.6917510033 0.2614588439 0.1340930167 0.2614588439 0.0047217358 0.0958020000 28077099 955859216 1783062528 -0.2547727525 -0.0614035912 0.0041680597 453 1311867733.7288239002 0.2635011971 0.1343786860 0.2635011971 0.0047215530 0.1060640000 28078929 955859216 1782046720 -0.2563395798 -0.0613829680 0.0040087812 454 1311867733.7597820759 0.2661502957 0.1346689318 0.2661502957 0.0047177842 0.0836440000 28080631 955859216 1780920320 -0.2585903406 -0.0615885742 0.0041940995 455 1311867733.7924160957 0.2682527304 0.1349625226 0.2682527304 0.0047472883 0.0956570000 28082397 955859216 1779888128 -0.2604029179 -0.0613012053 0.0042826165 456 1311867733.8282589912 0.2707864642 0.1352603821 0.2707864642 0.0047439153 0.0945050000 28084227 955859216 1778872320 -0.2620581985 -0.0621330030 0.0037936866 457 1311867733.8608579636 0.2738421261 0.1355636244 0.2738421261 0.0047414380 0.0778320000 28085929 955859216 1777856512 -0.2647080123 -0.0622236058 0.0036287867 458 1311867733.8918149471 0.2760975361 0.1358704670 0.2760975361 0.0047364831 0.0759760000 28087631 955859216 1776840704 -0.2665670812 -0.0620606840 0.0035547279 459 1311867733.9289460182 0.2795844078 0.1361835693 0.2795844078 0.0047336579 0.0929910000 28089461 955859216 1775841280 -0.2694534659 -0.0623834617 0.0032870360 460 1311867733.9595899582 0.2821955085 0.1365009866 0.2821955085 0.0047378220 0.0960030000 28091227 955859216 1774936064 -0.2717803717 -0.0624831878 0.0031417161 461 1311867733.9941790104 0.2854283750 0.1368240395 0.2854283750 0.0047545732 0.1064690000 28093025 955859216 1773920256 -0.2740860283 -0.0629351512 0.0037225033 462 1311867734.0275731087 0.2877567112 0.1371507336 0.2877567112 0.0047546579 0.0742360000 28094855 955859216 1772904448 -0.2762736976 -0.0633234456 0.0038706847 463 1311867734.0599920750 0.2889771461 0.1374786524 0.2889771461 0.0047496428 0.0858480000 28096589 955859216 1771888640 -0.2772703767 -0.0628203675 0.0038142204 464 1311867734.0956780910 0.2922228575 0.1378121528 0.2922228575 0.0047470373 0.0961600000 28098419 955859216 1770872832 -0.2802376747 -0.0627063662 0.0041494821 465 1311867734.1274170876 0.2947831750 0.1381497249 0.2947831750 0.0047451674 0.1037790000 28100217 955859216 1769984000 -0.2823640108 -0.0634674057 0.0036205130 466 1311867734.1618878841 0.2961062491 0.1384886874 0.2961062491 0.0047418639 0.0861140000 28101983 955859216 1768968192 -0.2833470404 -0.0633010119 0.0033990182 467 1311867734.1942350864 0.2985396683 0.1388314090 0.2985396683 0.0047384982 0.0788720000 28103781 955859216 1768079360 -0.2854198217 -0.0629014075 0.0035190880 468 1311867734.2291829586 0.3005658388 0.1391769954 0.3005658388 0.0047425474 0.1032980000 28105547 955859216 1767190528 -0.2870131433 -0.0638052002 0.0032238737 469 1311867734.2607750893 0.3020487130 0.1395242698 0.3020487130 0.0047377785 0.1256840000 28107313 955859216 1766174720 -0.2881627679 -0.0638627559 0.0031895062 470 1311867734.2941219807 0.3039222062 0.1398740527 0.3039222062 0.0047330178 0.1497190000 28109079 955859216 1765285888 -0.2898655534 -0.0634097382 0.0033723675 471 1311867734.3263280392 0.3065571487 0.1402279446 0.3065571487 0.0047321813 0.0965640000 28110845 955859216 1766764544 -0.2922090292 -0.0636391193 0.0037428085 472 1311867734.3610401154 0.3077891171 0.1405829471 0.3077891171 0.0047291393 0.1167960000 28112643 955859216 1768415232 -0.2932412028 -0.0633412898 0.0038240068 473 1311867734.3941841125 0.3081441522 0.1409371991 0.3081441522 0.0047286856 0.0970770000 28114441 955859216 1770082304 -0.2935604155 -0.0623872131 0.0041434304 474 1311867734.4276480675 0.3100614846 0.1412940014 0.3100614846 0.0047246664 0.1155830000 28116239 955859216 1771843584 -0.2951892614 -0.0631027669 0.0044663195 475 1311867734.4586091042 0.3114432096 0.1416522103 0.3114432096 0.0047228053 0.0932280000 28117973 955859216 1773494272 -0.2963134944 -0.0639215708 0.0045936913 476 1311867734.4938759804 0.3121623993 0.1420104249 0.3121623993 0.0047180393 0.0795060000 28119803 955859216 1775292416 -0.2968055308 -0.0633470491 0.0050874245 477 1311867734.5300569534 0.3126769960 0.1423682165 0.3126769960 0.0047154803 0.0780180000 28121633 955859216 1776922624 -0.2970343232 -0.0634548664 0.0053888727 478 1311867734.5595300198 0.3144614995 0.1427282443 0.3144614995 0.0047187829 0.1175800000 28123335 955859216 1778573312 -0.2983284891 -0.0637875497 0.0056791953 479 1311867734.5953910351 0.3140830398 0.1430859787 0.3144614995 0.0047154324 0.1338730000 28125133 955859216 1780371456 -0.2981574535 -0.0636482462 0.0060156961 480 1311867734.6285231113 0.3146077096 0.1434433157 0.3146077096 0.0047119151 0.0984120000 28126931 955859216 1782001664 -0.2981215715 -0.0639665797 0.0061350297 481 1311867734.6593229771 0.3149613142 0.1437999019 0.3149613142 0.0047071241 0.1372810000 28128665 955859216 1783652352 -0.2983959913 -0.0645390898 0.0061328020 482 1311867734.6947479248 0.3154489994 0.1441560204 0.3154489994 0.0047025959 0.0759480000 28130463 955859216 1785430016 -0.2989103198 -0.0651899278 0.0061302278 483 1311867734.7310240269 0.3172591627 0.1445144120 0.3172591627 0.0047033945 0.0791220000 28132325 955859216 1784475648 -0.3003371656 -0.0652290508 0.0062725479 484 1311867734.7607629299 0.3165300488 0.1448698162 0.3172591627 0.0046992326 0.1038160000 28134027 955859216 1783443456 -0.2992178202 -0.0645792633 0.0062383502 485 1311867734.7976419926 0.3170084059 0.1452247411 0.3172591627 0.0046955956 0.0846630000 28135889 955859216 1782427648 -0.2995151281 -0.0644995347 0.0063855918 486 1311867734.8298120499 0.3176931739 0.1455796145 0.3176931739 0.0046911740 0.0782990000 28137655 955859216 1781411840 -0.2999186814 -0.0643718392 0.0065035722 487 1311867734.8645250797 0.3181308210 0.1459339290 0.3181308210 0.0046866036 0.0761950000 28139453 955859216 1780285440 -0.3000884056 -0.0642319545 0.0070536239 488 1311867734.8943901062 0.3187267184 0.1462880126 0.3187267184 0.0046840401 0.1164980000 28141219 955859216 1779253248 -0.3003574908 -0.0645643622 0.0070321569 489 1311867734.9263660908 0.3196750879 0.1466425874 0.3196750879 0.0046792965 0.0887320000 28142953 955859216 1778237440 -0.3009599447 -0.0649456531 0.0072057117 490 1311867734.9631719589 0.3210221827 0.1469984642 0.3210221827 0.0046774171 0.0771950000 28144655 955859216 1777348608 -0.3017803133 -0.0647870675 0.0071749496 491 1311867734.9948470592 0.3208542168 0.1473525492 0.3210221827 0.0046800137 0.0750290000 28146421 955859216 1776332800 -0.3018826544 -0.0652404800 0.0068117874 492 1311867735.0292239189 0.3216551244 0.1477068227 0.3216551244 0.0046805725 0.0793520000 28148283 955859216 1772892160 -0.3023449183 -0.0650211275 0.0067818505 493 1311867735.0596508980 0.3216103315 0.1480595682 0.3216551244 0.0046767340 0.1291780000 28149953 955859216 1774047232 -0.3024386466 -0.0648265108 0.0068153185 494 1311867735.0952830315 0.3225822747 0.1484128530 0.3225822747 0.0046734180 0.0976080000 28151783 955859216 1773031424 -0.3033513427 -0.0652815253 0.0068561658 495 1311867735.1313030720 0.3244406283 0.1487684647 0.3244406283 0.0046734190 0.1324710000 28153613 955859216 1771376640 -0.3051064014 -0.0655134246 0.0073264013 496 1311867735.1603751183 0.3244849145 0.1491227317 0.3244849145 0.0046692647 0.0962070000 28155315 955859216 1772986368 -0.3050633967 -0.0653944239 0.0074924976 497 1311867735.1994349957 0.3245623112 0.1494757288 0.3245623112 0.0046683885 0.0767250000 28157177 955859216 1774637056 -0.3049216866 -0.0658437088 0.0074234465 498 1311867735.2263538837 0.3241076171 0.1498263953 0.3245623112 0.0046656674 0.1184340000 28158911 955859216 1776435200 -0.3044380546 -0.0652874708 0.0077867503 499 1311867735.2655019760 0.3243781328 0.1501761984 0.3245623112 0.0046617981 0.1369130000 28160741 955859216 1778073600 -0.3045409620 -0.0650790706 0.0083557637 500 1311867735.2961549759 0.3251345456 0.1505261151 0.3251345456 0.0046622765 0.1156650000 28162507 955859216 1779740672 -0.3052114546 -0.0654991865 0.0087007359 501 1311867735.3321089745 0.3257112503 0.1508757860 0.3257112503 0.0046629049 0.1139320000 28164337 955859216 1781501952 -0.3056638241 -0.0654597506 0.0091549214 502 1311867735.3666970730 0.3258347511 0.1512243098 0.3258347511 0.0046687244 0.0961370000 28166071 955859216 1783152640 -0.3056091070 -0.0654451996 0.0094275204 503 1311867735.3943350315 0.3265442252 0.1515728584 0.3265442252 0.0046762895 0.0972480000 28167741 955859216 1784950784 -0.3061339855 -0.0654037744 0.0097749606 504 1311867735.4322299957 0.3276219666 0.1519221622 0.3276219666 0.0046747561 0.1193110000 28169635 955859216 1784070144 -0.3071230650 -0.0652064011 0.0102808969 505 1311867735.4628560543 0.3305287957 0.1522758387 0.3305287957 0.0046888607 0.1353960000 28171369 955859216 1782960128 -0.3091735542 -0.0660701990 0.0108077088 506 1311867735.4973869324 0.3308519423 0.1526287559 0.3308519423 0.0046934137 0.1121430000 28173199 955859216 1778479104 -0.3097650409 -0.0664843619 0.0113178873 507 1311867735.5293200016 0.3312040567 0.1529809754 0.3312040567 0.0046895344 0.1107490000 28174933 955859216 1780137984 -0.3098891973 -0.0665263608 0.0117748985 508 1311867735.5632629395 0.3317167461 0.1533328175 0.3317167461 0.0046855037 0.0969270000 28176763 955859216 1781755904 -0.3101589978 -0.0668021291 0.0120698540 509 1311867735.5976569653 0.3324124217 0.1536846438 0.3324124217 0.0046821716 0.1176580000 28178561 955859216 1783554048 -0.3105787039 -0.0672863647 0.0124422004 510 1311867735.6363260746 0.3324498534 0.1540351638 0.3324498534 0.0046815285 0.1343540000 28180391 955859216 1785184256 -0.3104072511 -0.0674692318 0.0125170685 511 1311867735.6626520157 0.3325670362 0.1543845412 0.3325670362 0.0046806079 0.0943710000 28182093 955859216 1784356864 -0.3102018237 -0.0684685260 0.0122233592 512 1311867735.6952130795 0.3346418142 0.1547366062 0.3346418142 0.0046774530 0.1157400000 28183859 955859216 1783324672 -0.3120425045 -0.0697313324 0.0122692669 513 1311867735.7291250229 0.3356984258 0.1550893583 0.3356984258 0.0046758523 0.1380190000 28226617 955859216 1778728960 -0.3129132092 -0.0697245821 0.0121727381 514 1311867735.7631659508 0.3358266354 0.1554409873 0.3358266354 0.0046731110 0.1487990000 28312415 955859216 1780498432 -0.3130457997 -0.0690871850 0.0122350566 515 1311867735.7963778973 0.3366749883 0.1557928979 0.3366749883 0.0046711722 0.1127420000 28314181 955859216 1782284288 -0.3136279881 -0.0694005787 0.0121816061 516 1311867735.8277759552 0.3375352621 0.1561451118 0.3375352621 0.0046745678 0.1342160000 28315915 955859216 1783914496 -0.3143667281 -0.0686951503 0.0123357121 517 1311867735.8638889790 0.3373685479 0.1564956407 0.3375352621 0.0046708599 0.0982190000 28317649 955859216 1785565184 -0.3141583800 -0.0678580850 0.0127374185 518 1311867735.8951849937 0.3380151093 0.1568460644 0.3380151093 0.0046663747 0.1379230000 28319415 955859216 1784844288 -0.3148040175 -0.0674940720 0.0132099371 519 1311867735.9322230816 0.3385576904 0.1571961831 0.3385576904 0.0046625391 0.1143160000 28321277 955859216 1783705600 -0.3153592050 -0.0670508742 0.0138097676 520 1311867735.9623689651 0.3380508721 0.1575439806 0.3385576904 0.0046615793 0.1567510000 28323011 955859216 1779240960 -0.3150499761 -0.0667265356 0.0142732020 521 1311867735.9945859909 0.3381090760 0.1578905547 0.3385576904 0.0046588998 0.1068810000 28324745 955859216 1780916224 -0.3152250946 -0.0665314049 0.0146908443 522 1311867736.0290079117 0.3381425142 0.1582358650 0.3385576904 0.0046568752 0.0769140000 28326575 955859216 1782517760 -0.3153504431 -0.0664075539 0.0151767191 523 1311867736.0642199516 0.3384750783 0.1585804906 0.3385576904 0.0046543814 0.0764950000 28328405 955859216 1784315904 -0.3157058358 -0.0663150325 0.0154500445 524 1311867736.0946779251 0.3390416503 0.1589248821 0.3390416503 0.0046504381 0.0775190000 28330107 955859216 1785946112 -0.3163667619 -0.0663433298 0.0159492902 525 1311867736.1299190521 0.3400635719 0.1592699082 0.3400635719 0.0046565084 0.1187560000 28331937 955859216 1785102336 -0.3175072968 -0.0662457943 0.0162996817 526 1311867736.1631360054 0.3397381902 0.1596130038 0.3400635719 0.0046529173 0.1293680000 28333767 955859216 1784086528 -0.3175907135 -0.0662868321 0.0163238328 527 1311867736.1942429543 0.3404942453 0.1599562320 0.3404942453 0.0046536707 0.0907070000 28335469 955859216 1782960128 -0.3184596002 -0.0661903769 0.0163860470 528 1311867736.2298679352 0.3418907225 0.1603008049 0.3418907225 0.0046516246 0.0950240000 28337299 955859216 1778475008 -0.3204499185 -0.0664367303 0.0168605968 529 1311867736.2633900642 0.3427538872 0.1606457067 0.3427538872 0.0046525489 0.1128970000 28339097 955859216 1780133888 -0.3214979470 -0.0665234849 0.0171016436 530 1311867736.2995250225 0.3426043093 0.1609890248 0.3427538872 0.0046525873 0.0929470000 28340927 955859216 1781755904 -0.3215139508 -0.0669090450 0.0169845354 531 1311867736.3304500580 0.3435725272 0.1613328732 0.3435725272 0.0046487698 0.0974390000 28342629 955859216 1783554048 -0.3226709962 -0.0669054985 0.0175674986 532 1311867736.3637149334 0.3453895450 0.1616788444 0.3453895450 0.0046462373 0.1093190000 28344427 955859216 1785184256 -0.3245101571 -0.0674207434 0.0179325100 533 1311867736.3943159580 0.3472802043 0.1620270646 0.3472802043 0.0046438574 0.0876900000 28346129 955859216 1784475648 -0.3262947202 -0.0684265420 0.0178431030 534 1311867736.4313519001 0.3482511044 0.1623757988 0.3482511044 0.0046515770 0.1063820000 28348023 955859216 1783324672 -0.3271211386 -0.0685611144 0.0180807505 535 1311867736.4625089169 0.3506609499 0.1627277336 0.3506609499 0.0046501475 0.0989830000 28349789 955859216 1782308864 -0.3296647370 -0.0692704692 0.0183537118 536 1311867736.4987530708 0.3527735770 0.1630822968 0.3527735770 0.0046474767 0.0987110000 28351587 955859216 1781293056 -0.3316003978 -0.0701593086 0.0184341259 537 1311867736.5321619511 0.3550121486 0.1634397081 0.3550121486 0.0046483161 0.1142220000 28353385 955859216 1780150272 -0.3337373137 -0.0702728927 0.0186668467 538 1311867736.5634689331 0.3551858366 0.1637961135 0.3551858366 0.0046453837 0.0921320000 28355151 955859216 1781645312 -0.3340011835 -0.0704762712 0.0188146215 539 1311867736.5958600044 0.3570896685 0.1641547286 0.3570896685 0.0046417166 0.0780460000 28356917 955859216 1783406592 -0.3359074593 -0.0719737411 0.0189197324 540 1311867736.6320459843 0.3588043749 0.1645151909 0.3588043749 0.0046496417 0.0776560000 28358747 955859216 1785057280 -0.3373041153 -0.0720723495 0.0193022508 541 1311867736.6635379791 0.3590242565 0.1648747271 0.3590242565 0.0046589671 0.0785590000 28360513 955859216 1784213504 -0.3379488885 -0.0725241527 0.0192645881 542 1311867736.6945500374 0.3621715605 0.1652387434 0.3621715605 0.0046637333 0.1071840000 28362215 955859216 1783197696 -0.3409610391 -0.0741207004 0.0190390535 543 1311867736.7332150936 0.3638614416 0.1656045311 0.3638614416 0.0046597091 0.0827110000 28364077 955859216 1782054912 -0.3425815403 -0.0749808624 0.0191139784 544 1311867736.7636179924 0.3647878468 0.1659706769 0.3647878468 0.0046584629 0.1321940000 28365843 955859216 1781039104 -0.3428710103 -0.0751886815 0.0192871317 545 1311867736.7952749729 0.3670468628 0.1663396240 0.3670468628 0.0046702220 0.1345930000 28367577 955859216 1779896320 -0.3452311456 -0.0758857578 0.0190123636 546 1311867736.8325269222 0.3730727434 0.1667182561 0.3730727434 0.0046882693 0.1320290000 28369407 955859216 1781391360 -0.3511130214 -0.0749811158 0.0198357198 547 1311867736.8640279770 0.3748498261 0.1670987525 0.3748498261 0.0046868019 0.1202340000 28371205 955859216 1783152640 -0.3526237905 -0.0753236562 0.0199134443 548 1311867736.8945000172 0.3773311973 0.1674823884 0.3773311973 0.0046854099 0.0884920000 28372907 955859216 1784803328 -0.3547733128 -0.0762278363 0.0203980822 549 1311867736.9362800121 0.3813089728 0.1678718722 0.3813089728 0.0046912479 0.0802130000 28374833 955859216 1783959552 -0.3583332896 -0.0765263364 0.0205043852 550 1311867736.9632000923 0.3841441274 0.1682650944 0.3841441274 0.0046873470 0.0940530000 28376535 955859216 1782943744 -0.3611943126 -0.0760345608 0.0213737637 551 1311867736.9954400063 0.3881236017 0.1686641117 0.3881236017 0.0046864311 0.0947870000 28378301 955859216 1781800960 -0.3649898171 -0.0760917962 0.0220507868 552 1311867737.0307478905 0.3897830844 0.1690646895 0.3897830844 0.0046844337 0.0924210000 28380099 955859216 1780785152 -0.3664161265 -0.0777681917 0.0220406447 553 1311867737.0629029274 0.3879319131 0.1694604711 0.3897830844 0.0046811801 0.1164870000 28381897 955859216 1779769344 -0.3644008040 -0.0776939616 0.0225142483 554 1311867737.0977239609 0.3870854676 0.1698532960 0.3897830844 0.0046787396 0.1147720000 28383695 955859216 1778753536 -0.3634796143 -0.0781251118 0.0224077106 555 1311867737.1300530434 0.3868484497 0.1702442783 0.3897830844 0.0046746764 0.0928630000 28385429 955859216 1774432256 -0.3631909788 -0.0784698650 0.0222924855 556 1311867737.1655049324 0.3855978847 0.1706316049 0.3897830844 0.0046707547 0.0941970000 28387259 955859216 1776091136 -0.3619093299 -0.0778897777 0.0223027356 557 1311867737.1952710152 0.3850514591 0.1710165598 0.3897830844 0.0046666982 0.1197600000 28388993 955859216 1777692672 -0.3611766398 -0.0778610110 0.0221797992 558 1311867737.2333149910 0.3860342801 0.1714018962 0.3897830844 0.0046630145 0.1309670000 28390887 955859216 1779470336 -0.3620094657 -0.0782326460 0.0221913792 559 1311867737.2693018913 0.3848397434 0.1717837170 0.3897830844 0.0046658138 0.1183840000 28392685 955859216 1781121024 -0.3601857126 -0.0778203160 0.0221959520 560 1311867737.2957379818 0.3851584792 0.1721647434 0.3897830844 0.0046621037 0.0921910000 28394355 955859216 1782788096 -0.3602923155 -0.0777274594 0.0225851703 561 1311867737.3316531181 0.3855114579 0.1725450406 0.3897830844 0.0046582132 0.0789460000 28396217 955859216 1784549376 -0.3604346812 -0.0777941868 0.0227866061 562 1311867737.3659460545 0.3853278458 0.1729236577 0.3897830844 0.0046541147 0.1184030000 28397983 955859216 1783705600 -0.3603848517 -0.0774878711 0.0231136829 563 1311867737.3967239857 0.3862187862 0.1733025122 0.3897830844 0.0046524641 0.0935820000 28399749 955859216 1782689792 -0.3610408902 -0.0776110962 0.0235339869 564 1311867737.4355359077 0.3870052993 0.1736814179 0.3897830844 0.0046494409 0.0938430000 28401611 955859216 1781547008 -0.3617160022 -0.0775975212 0.0240561366 565 1311867737.4691100121 0.3879197240 0.1740606007 0.3897830844 0.0046453339 0.1128850000 28403409 955859216 1780531200 -0.3624847829 -0.0777501315 0.0244552717 566 1311867737.4959459305 0.3883544803 0.1744392118 0.3897830844 0.0046412887 0.1121850000 28405079 955859216 1779515392 -0.3629673421 -0.0779853091 0.0250546653 567 1311867737.5353999138 0.3888781071 0.1748174109 0.3897830844 0.0046377321 0.0940850000 28406973 955859216 1778237440 -0.3632240295 -0.0782806054 0.0254651178 568 1311867737.5654399395 0.3883672953 0.1751933790 0.3897830844 0.0046342769 0.0969250000 28408675 955859216 1777221632 -0.3621751368 -0.0782741606 0.0257076696 569 1311867737.5958089828 0.3890193701 0.1755691716 0.3897830844 0.0046317207 0.1082590000 28410441 955859216 1776205824 -0.3625004292 -0.0784258842 0.0262766872 570 1311867737.6330978870 0.3905723989 0.1759463703 0.3905723989 0.0046286856 0.0739390000 28412303 955859216 1775190016 -0.3637384772 -0.0786307231 0.0267695207 571 1311867737.6624519825 0.3920881748 0.1763249023 0.3920881748 0.0046255567 0.0821850000 28414037 955859216 1774174208 -0.3649788201 -0.0793146193 0.0272899065 572 1311867737.7032339573 0.3928466141 0.1767034368 0.3928466141 0.0046230311 0.0957100000 28415899 955859216 1773158400 -0.3653728664 -0.0802450180 0.0274484716 573 1311867737.7314720154 0.3933726251 0.1770815680 0.3933726251 0.0046192953 0.0772490000 28417601 955859216 1772269568 -0.3655530214 -0.0806572139 0.0278646946 574 1311867737.7658560276 0.3936852813 0.1774589264 0.3936852813 0.0046154639 0.1180140000 28419399 955859216 1771253760 -0.3655854762 -0.0808105022 0.0280731134 575 1311867737.8011269569 0.3937001228 0.1778349981 0.3937001228 0.0046123439 0.1294600000 28421229 955859216 1767436288 -0.3653259873 -0.0806592852 0.0285458211 576 1311867737.8323190212 0.3935075700 0.1782094296 0.3937001228 0.0046086758 0.1110470000 28422995 955859216 1769095168 -0.3649305999 -0.0807215199 0.0289405547 577 1311867737.8633110523 0.3945250809 0.1785843268 0.3945250809 0.0046104138 0.0943370000 28424729 955859216 1770594304 -0.3653824925 -0.0805079192 0.0295018125 578 1311867737.9004418850 0.3946023881 0.1789580604 0.3946023881 0.0046071443 0.0963910000 28426527 955859216 1772224512 -0.3649528325 -0.0812287405 0.0301241204 579 1311867737.9305500984 0.3950438201 0.1793312655 0.3950438201 0.0046092337 0.0969690000 28428261 955859216 1773891584 -0.3650231659 -0.0816186890 0.0307415053 580 1311867737.9630560875 0.3962928355 0.1797053372 0.3962928355 0.0046061314 0.0970150000 28430059 955859216 1775652864 -0.3659199476 -0.0816030949 0.0314177237 581 1311867737.9996941090 0.3975071013 0.1800802112 0.3975071013 0.0046041248 0.0975800000 28431889 955859216 1777303552 -0.3666888177 -0.0820864588 0.0320038721 582 1311867738.0315399170 0.3984150887 0.1804553570 0.3984150887 0.0046011668 0.1199150000 28433655 955859216 1779101696 -0.3672018349 -0.0818993822 0.0329110138 583 1311867738.0629770756 0.3973612785 0.1808274083 0.3984150887 0.0045973347 0.0916220000 28435421 955859216 1780731904 -0.3655622602 -0.0819075257 0.0338354781 584 1311867738.0998299122 0.3979839683 0.1811992517 0.3984150887 0.0045948191 0.0778030000 28437219 955859216 1782382592 -0.3655910790 -0.0821197852 0.0345151387 585 1311867738.1308510303 0.3972037137 0.1815684901 0.3984150887 0.0045939090 0.1201320000 28438953 955859216 1784180736 -0.3641801476 -0.0828331783 0.0352985412 586 1311867738.1635079384 0.3973486423 0.1819367157 0.3984150887 0.0045911783 0.1321940000 28440751 955859216 1785810944 -0.3638190031 -0.0835583732 0.0359002836 587 1311867738.1992070675 0.3988424242 0.1823062313 0.3988424242 0.0045885733 0.1198310000 28442549 955859216 1784967168 -0.3646589220 -0.0840815231 0.0367024094 588 1311867738.2306089401 0.3993406892 0.1826753376 0.3993406892 0.0045890262 0.0907960000 28444315 955859216 1783824384 -0.3647810221 -0.0850813091 0.0370744653 589 1311867738.2632689476 0.3998261392 0.1830440146 0.3998261392 0.0045915150 0.0937200000 28446113 955859216 1782808576 -0.3647691309 -0.0858761892 0.0370974168 590 1311867738.3008689880 0.4009002149 0.1834132624 0.4009002149 0.0045889729 0.1152250000 28447943 955859216 1781665792 -0.3652184010 -0.0868915692 0.0373716503 591 1311867738.3339769840 0.4030933678 0.1837849716 0.4030933678 0.0045885310 0.1344360000 28449709 955859216 1780633600 -0.3669202924 -0.0875752568 0.0375038944 592 1311867738.3651630878 0.4049538970 0.1841585677 0.4049538970 0.0045848616 0.0968680000 28451475 955859216 1782128640 -0.3685611188 -0.0880379379 0.0376562476 593 1311867738.3995900154 0.4059891403 0.1845326497 0.4059891403 0.0045815267 0.1371140000 28453305 955859216 1783779328 -0.3691299856 -0.0879082158 0.0377590358 594 1311867738.4334011078 0.4060413539 0.1849055599 0.4060413539 0.0045781295 0.1559360000 28455103 955859216 1785556992 -0.3690153360 -0.0877900422 0.0378656313 595 1311867738.4643430710 0.4080449343 0.1852805841 0.4080449343 0.0045748573 0.1139370000 28456837 955859216 1784709120 -0.3701873720 -0.0882749483 0.0379563086 596 1311867738.5000250340 0.4083520472 0.1856548651 0.4083520472 0.0045715156 0.0969350000 28458667 955859216 1783697408 -0.3698994517 -0.0880608559 0.0380601808 597 1311867738.5332009792 0.4084233642 0.1860280116 0.4084233642 0.0045682707 0.1359620000 28460433 955859216 1782554624 -0.3692345023 -0.0874884278 0.0383516736 598 1311867738.5634350777 0.4081354439 0.1863994287 0.4084233642 0.0045658659 0.0937340000 28462199 955859216 1781538816 -0.3682767153 -0.0878735930 0.0385327041 599 1311867738.6022439003 0.4080904126 0.1867695306 0.4084233642 0.0045638338 0.1141310000 28464061 955859216 1779757056 -0.3672723174 -0.0881849751 0.0385294035 600 1311867738.6328980923 0.4086351991 0.1871393067 0.4086351991 0.0045605018 0.1338310000 28465795 955859216 1781366784 -0.3668729961 -0.0882802010 0.0386863649 601 1311867738.6628730297 0.4093605280 0.1875090591 0.4093605280 0.0045585364 0.1560130000 28467561 955859216 1783017472 -0.3667326272 -0.0886412859 0.0388034657 602 1311867738.6996099949 0.4098018110 0.1878783162 0.4098018110 0.0045588614 0.1342970000 28469391 955859216 1784795136 -0.3662219644 -0.0891380236 0.0387478061 603 1311867738.7314729691 0.4104009271 0.1882473421 0.4104009271 0.0045614134 0.1386870000 28471157 955859216 1783951360 -0.3659899831 -0.0894303173 0.0389212891 604 1311867738.7626600266 0.4114217162 0.1886168361 0.4114217162 0.0045614007 0.1305760000 28472891 955859216 1782935552 -0.3661222160 -0.0890531316 0.0391295217 605 1311867738.8032259941 0.4122265875 0.1889864390 0.4122265875 0.0045668554 0.1332940000 28474785 955859216 1781792768 -0.3659312129 -0.0891101435 0.0393116474 606 1311867738.8306779861 0.4121614397 0.1893547145 0.4122265875 0.0045659089 0.0954080000 28476487 955859216 1783287808 -0.3652127385 -0.0894205198 0.0393314436 607 1311867738.8639259338 0.4108083844 0.1897195476 0.4122265875 0.0045621471 0.0984000000 28478285 955859216 1785049088 -0.3631328046 -0.0892560482 0.0392578840 608 1311867738.9000120163 0.4121716022 0.1900854227 0.4122265875 0.0045644814 0.1188770000 28480115 955859216 1784193024 -0.3637647033 -0.0891570598 0.0393226892 609 1311867738.9307610989 0.4132985175 0.1904519467 0.4132985175 0.0045697581 0.0944370000 28481849 955859216 1783062528 -0.3643361926 -0.0892721862 0.0396890193 610 1311867738.9664750099 0.4134415388 0.1908175034 0.4134415388 0.0045661290 0.0938680000 28483679 955859216 1782046720 -0.3639858067 -0.0891136676 0.0399291702 611 1311867738.9989941120 0.4145856500 0.1911837360 0.4145856500 0.0045629278 0.0811010000 28485477 955859216 1780903936 -0.3646502495 -0.0890270770 0.0399751365 612 1311867739.0329539776 0.4140206873 0.1915478487 0.4145856500 0.0045616809 0.1166700000 28487275 955859216 1779888128 -0.3635742962 -0.0899341777 0.0399847142 613 1311867739.0664470196 0.4125341475 0.1919083483 0.4145856500 0.0045637435 0.1292380000 28489041 955859216 1778872320 -0.3615906239 -0.0901456252 0.0399265885 614 1311867739.0997900963 0.4116300941 0.1922662014 0.4145856500 0.0045602494 0.1107960000 28490743 955859216 1780350976 -0.3603170216 -0.0899255350 0.0399306864 615 1311867739.1321549416 0.4113206267 0.1926223874 0.4145856500 0.0045586657 0.1142860000 28492477 955859216 1782149120 -0.3597113490 -0.0899144560 0.0401083007 616 1311867739.1687150002 0.4116138816 0.1929778931 0.4145856500 0.0045552083 0.0970200000 28494307 955859216 1783779328 -0.3599379361 -0.0896482095 0.0403580517 617 1311867739.1999289989 0.4120632410 0.1933329747 0.4145856500 0.0045525458 0.1185460000 28496041 955859216 1785430016 -0.3604005277 -0.0894349217 0.0408018753 618 1311867739.2313010693 0.4111762047 0.1936854718 0.4145856500 0.0045497113 0.0979390000 28497775 955859216 1784586240 -0.3594509363 -0.0897227898 0.0409485847 619 1311867739.2672259808 0.4109407365 0.1940364496 0.4145856500 0.0045472212 0.0951590000 28499637 955859216 1783570432 -0.3593586087 -0.0902221948 0.0411146842 620 1311867739.2996931076 0.4111248255 0.1943865922 0.4145856500 0.0045482809 0.1313190000 28501403 955859216 1782427648 -0.3596735597 -0.0906665325 0.0413428470 621 1311867739.3319859505 0.4102098644 0.1947341337 0.4145856500 0.0045452828 0.0974090000 28503169 955859216 1781411840 -0.3587379754 -0.0907173678 0.0416208357 622 1311867739.3670029640 0.4105067253 0.1950810349 0.4145856500 0.0045442184 0.1150660000 28504967 955859216 1780015104 -0.3593108058 -0.0904630125 0.0417989641 623 1311867739.3990058899 0.4090898335 0.1954245483 0.4145856500 0.0045412852 0.0943560000 28506765 955859216 1778999296 -0.3581093848 -0.0904318392 0.0420540385 624 1311867739.4311320782 0.4076143503 0.1957645960 0.4145856500 0.0045389264 0.1147690000 28508499 955859216 1777999872 -0.3566146791 -0.0903943926 0.0422938876 625 1311867739.4668490887 0.4092125297 0.1961061127 0.4145856500 0.0045357040 0.0911680000 28510329 955859216 1777094656 -0.3582478464 -0.0904870778 0.0428026691 626 1311867739.4988598824 0.4100853801 0.1964479326 0.4145856500 0.0045431021 0.0931870000 28512095 955859216 1776078848 -0.3590918183 -0.0908700004 0.0433053784 627 1311867739.5316400528 0.4095170200 0.1967877557 0.4145856500 0.0045397178 0.1353050000 28513829 955859216 1777557504 -0.3583427966 -0.0905688703 0.0437004380 628 1311867739.5670249462 0.4104677439 0.1971280105 0.4145856500 0.0045370540 0.0983880000 28515659 955859216 1779208192 -0.3592849672 -0.0902515724 0.0446043089 629 1311867739.5990490913 0.4115863740 0.1974689618 0.4145856500 0.0045336723 0.1166740000 28517425 955859216 1780985856 -0.3604407609 -0.0906682685 0.0452753343 630 1311867739.6325490475 0.4126443267 0.1978105100 0.4145856500 0.0045301580 0.0958530000 28519223 955859216 1782763520 -0.3617480993 -0.0902464464 0.0459574163 631 1311867739.6706740856 0.4138344824 0.1981528618 0.4145856500 0.0045283776 0.1182510000 28521085 955859216 1784541184 -0.3632520139 -0.0904262066 0.0465392321 632 1311867739.7001221180 0.4146001935 0.1984953417 0.4146001935 0.0045258853 0.0968500000 28522819 955859216 1783713792 -0.3641450107 -0.0901709348 0.0471361652 633 1311867739.7323939800 0.4140754938 0.1988359107 0.4146001935 0.0045233987 0.0955530000 28524585 955859216 1782554624 -0.3638004363 -0.0899216533 0.0479407907 634 1311867739.7662999630 0.4146069884 0.1991762436 0.4146069884 0.0045204048 0.0944910000 28526383 955859216 1781538816 -0.3645038605 -0.0899568945 0.0487146527 635 1311867739.8016180992 0.4146238863 0.1995155312 0.4146238863 0.0045179266 0.1310740000 28528213 955859216 1780396032 -0.3648275137 -0.0903692022 0.0491853766 636 1311867739.8325679302 0.4149404764 0.1998542497 0.4149404764 0.0045172910 0.1364750000 28529947 955859216 1779380224 -0.3654471040 -0.0899714679 0.0497191697 637 1311867739.8701560497 0.4150015414 0.2001920006 0.4150015414 0.0045142195 0.0966140000 28531777 955859216 1780875264 -0.3661005497 -0.0899073780 0.0502396673 638 1311867739.9036860466 0.4156178534 0.2005296586 0.4156178534 0.0045115642 0.1375670000 28533607 955859216 1782636544 -0.3674473464 -0.0906238407 0.0503880829 639 1311867739.9317240715 0.4162186086 0.2008672000 0.4162186086 0.0045083535 0.0929990000 28535309 955859216 1784287232 -0.3685475290 -0.0905892551 0.0506436899 640 1311867739.9668979645 0.4160930812 0.2012034905 0.4162186086 0.0045061125 0.1199630000 28537107 955859216 1786085376 -0.3688887358 -0.0902613699 0.0507745296 641 1311867739.9987080097 0.4180305004 0.2015417541 0.4180305004 0.0045038079 0.1395960000 28538905 955859216 1785204736 -0.3715122938 -0.0904782936 0.0513929129 642 1311867740.0328791142 0.4182405174 0.2018792911 0.4182405174 0.0045004434 0.1477240000 28540703 955859216 1784205312 -0.3723167479 -0.0906694606 0.0515991971 643 1311867740.0671849251 0.4172073603 0.2022141715 0.4182405174 0.0044975192 0.1091300000 28542469 955859216 1782403072 -0.3717127740 -0.0902358517 0.0516226441 644 1311867740.0992529392 0.4176578820 0.2025487114 0.4182405174 0.0044973049 0.0951480000 28544267 955859216 1784078336 -0.3724729121 -0.0908581391 0.0519523844 645 1311867740.1347720623 0.4186677337 0.2028837797 0.4186677337 0.0044953603 0.1559910000 28546033 955859216 1785430016 -0.3742444217 -0.0913446918 0.0520532094 646 1311867740.1666491032 0.4187061489 0.2032178700 0.4187061489 0.0044920865 0.1143350000 28547831 955859216 1784471552 -0.3744526207 -0.0909642056 0.0519439951 647 1311867740.1993310452 0.4182079732 0.2035501577 0.4187061489 0.0044890402 0.1190060000 28549629 955859216 1783316480 -0.3743847311 -0.0907680243 0.0521312132 648 1311867740.2383539677 0.4191124737 0.2038828156 0.4191124737 0.0044874452 0.1282740000 28551523 955859216 1778851840 -0.3757941425 -0.0912438408 0.0521050394 649 1311867740.2664349079 0.4184238017 0.2042133872 0.4191124737 0.0044867279 0.0875360000 28553193 955859216 1780527104 -0.3754799664 -0.0909207538 0.0520087406 650 1311867740.2981588840 0.4199496806 0.2045452892 0.4199496806 0.0044844299 0.0924790000 28554959 955859216 1782128640 -0.3773406744 -0.0903750882 0.0522234514 651 1311867740.3347120285 0.4189679325 0.2048746634 0.4199496806 0.0044812641 0.1351060000 28556821 955859216 1783779328 -0.3768019974 -0.0907899365 0.0519362092 652 1311867740.3665161133 0.4182667732 0.2052019520 0.4199496806 0.0044802906 0.1138750000 28558555 955859216 1785446400 -0.3763083220 -0.0906322598 0.0515373200 653 1311867740.3993780613 0.4176529944 0.2055272981 0.4199496806 0.0044780647 0.1004510000 28560321 955859216 1784725504 -0.3758153915 -0.0907780826 0.0512100309 654 1311867740.4346680641 0.4181846082 0.2058524622 0.4199496806 0.0044769906 0.0960830000 28562151 955859216 1783586816 -0.3762253523 -0.0907737911 0.0509108827 655 1311867740.4664289951 0.4187583327 0.2061775093 0.4199496806 0.0044746044 0.1175310000 28563917 955859216 1782554624 -0.3769301474 -0.0905823186 0.0506273285 656 1311867740.4993040562 0.4197610021 0.2065030939 0.4199496806 0.0044746761 0.0890680000 28565683 955859216 1781538816 -0.3775544167 -0.0905172974 0.0505088270 657 1311867740.5354259014 0.4210507572 0.2068296505 0.4210507572 0.0044771134 0.1151870000 28567513 955859216 1777074176 -0.3784518540 -0.0906317979 0.0503729805 658 1311867740.5666589737 0.4210810065 0.2071552605 0.4210810065 0.0044746258 0.1108250000 28569279 955859216 1778749440 -0.3783126175 -0.0904506221 0.0501387268 659 1311867740.6008880138 0.4228295982 0.2074825356 0.4228295982 0.0044743420 0.0937400000 28571077 955859216 1780350976 -0.3799168766 -0.0904027149 0.0502729826 660 1311867740.6346809864 0.4236638844 0.2078100831 0.4236638844 0.0044724026 0.0963120000 28572875 955859216 1782018048 -0.3808222711 -0.0905828401 0.0503345281 661 1311867740.6665890217 0.4234478772 0.2081363128 0.4236638844 0.0044692919 0.0963380000 28574641 955859216 1783779328 -0.3807806075 -0.0907106921 0.0500177890 662 1311867740.6994900703 0.4243039787 0.2084628500 0.4243039787 0.0044670451 0.0934620000 28576407 955859216 1785430016 -0.3818061948 -0.0909618139 0.0496355593 663 1311867740.7368240356 0.4242959917 0.2087883902 0.4243039787 0.0044659101 0.0993010000 28578173 955859216 1784725504 -0.3819462657 -0.0910026357 0.0494034141 664 1311867740.7668819427 0.4248811603 0.2091138311 0.4248811603 0.0044631475 0.0954340000 28579907 955859216 1783570432 -0.3827733397 -0.0911580995 0.0493315309 665 1311867740.7996399403 0.4267703891 0.2094411342 0.4267703891 0.0044608622 0.0951710000 28581705 955859216 1782554624 -0.3849699497 -0.0914593488 0.0497244745 666 1311867740.8349099159 0.4271135330 0.2097679697 0.4271135330 0.0044579085 0.0942620000 28583471 955859216 1781411840 -0.3856410980 -0.0910226479 0.0493829139 667 1311867740.8668210506 0.4277546108 0.2100947862 0.4277546108 0.0044555781 0.0947840000 28585269 955859216 1780396032 -0.3866427541 -0.0910893530 0.0494617745 668 1311867740.8993830681 0.4281813800 0.2104212631 0.4281813800 0.0044523916 0.0945560000 28587035 955859216 1779380224 -0.3877370656 -0.0914044678 0.0492838062 669 1311867740.9399120808 0.4279364944 0.2107463980 0.4281813800 0.0044514069 0.0850100000 28588961 955859216 1778364416 -0.3880997598 -0.0911053419 0.0488767549 670 1311867740.9665501118 0.4271696806 0.2110694178 0.4281813800 0.0044481835 0.1036360000 28590631 955859216 1777348608 -0.3877894282 -0.0907743275 0.0484716445 671 1311867741.0021579266 0.4281718731 0.2113929684 0.4281813800 0.0044456717 0.1177000000 28592461 955859216 1776349184 -0.3892917633 -0.0912759677 0.0483483002 672 1311867741.0367169380 0.4280266762 0.2117153400 0.4281813800 0.0044425687 0.1114420000 28594259 955859216 1775443968 -0.3894560933 -0.0913543403 0.0479189456 673 1311867741.0666699409 0.4277404249 0.2120363283 0.4281813800 0.0044403069 0.0769790000 28595993 955859216 1776922624 -0.3895178437 -0.0907894596 0.0475807711 674 1311867741.1009640694 0.4283676744 0.2123572947 0.4283676744 0.0044416225 0.0941490000 28597791 955859216 1778573312 -0.3906027973 -0.0915037766 0.0473173782 675 1311867741.1357901096 0.4280405641 0.2126768254 0.4283676744 0.0044389582 0.0949140000 28599589 955859216 1780240384 -0.3908160329 -0.0915903598 0.0465925932 676 1311867741.1675300598 0.4276069999 0.2129947695 0.4283676744 0.0044360737 0.1348710000 28601387 955859216 1782001664 -0.3904164732 -0.0920303762 0.0461198092 677 1311867741.2014830112 0.4280505776 0.2133124295 0.4283676744 0.0044375025 0.0973350000 28603153 955859216 1783652352 -0.3907889128 -0.0924192593 0.0457429849 678 1311867741.2411060333 0.4289396703 0.2136304637 0.4289396703 0.0044396337 0.1153040000 28605047 955859216 1785450496 -0.3918539882 -0.0931725278 0.0455504246 679 1311867741.2668209076 0.4296167195 0.2139485584 0.4296167195 0.0044394710 0.0972580000 28606717 955859216 1784459264 -0.3923751712 -0.0932125151 0.0454287380 680 1311867741.2997009754 0.4303815067 0.2142668421 0.4303815067 0.0044362403 0.0937490000 28608483 955859216 1783443456 -0.3929410875 -0.0932567790 0.0452642851 681 1311867741.3348419666 0.4310392737 0.2145851570 0.4310392737 0.0044331837 0.1135720000 28610313 955859216 1782427648 -0.3935380578 -0.0927870870 0.0448958650 682 1311867741.3701419830 0.4310708940 0.2149025848 0.4310708940 0.0044299547 0.1183420000 28612111 955859216 1781284864 -0.3932361305 -0.0922200680 0.0444756299 683 1311867741.4066278934 0.4314661622 0.2152196617 0.4314661622 0.0044283164 0.1361650000 28613973 955859216 1780269056 -0.3931839168 -0.0922345296 0.0443180948 684 1311867741.4393060207 0.4315818846 0.2155359808 0.4315818846 0.0044265145 0.1102070000 28615771 955859216 1781747712 -0.3930520117 -0.0915385783 0.0443308689 685 1311867741.4667329788 0.4309972227 0.2158505227 0.4315818846 0.0044235398 0.0972260000 28617441 955859216 1783398400 -0.3920943141 -0.0909437612 0.0440333933 686 1311867741.5025069714 0.4318147898 0.2161653395 0.4318147898 0.0044211433 0.1169420000 28619271 955859216 1785176064 -0.3923924863 -0.0903178155 0.0443785489 687 1311867741.5368049145 0.4319719374 0.2164794684 0.4319719374 0.0044195881 0.0969940000 28621069 955859216 1784205312 -0.3921684921 -0.0900644809 0.0441612303 688 1311867741.5688209534 0.4316879213 0.2167922714 0.4319719374 0.0044164265 0.0982370000 28622835 955859216 1783189504 -0.3914178908 -0.0895986706 0.0439557135 689 1311867741.6046030521 0.4322847724 0.2171050327 0.4322847724 0.0044215972 0.1493950000 28624633 955859216 1782173696 -0.3916408420 -0.0893720910 0.0441845022 690 1311867741.6355440617 0.4328089654 0.2174176471 0.4328089654 0.0044190998 0.1087750000 28626399 955859216 1780391936 -0.3916672766 -0.0892403051 0.0441212691 691 1311867741.6679561138 0.4323798418 0.2177287356 0.4328089654 0.0044162072 0.0941620000 28628197 955859216 1782018048 -0.3906653523 -0.0889860690 0.0438927859 692 1311867741.7048020363 0.4338388145 0.2180410334 0.4338388145 0.0044187982 0.1145740000 28630027 955859216 1783779328 -0.3912903666 -0.0886687264 0.0437736362 693 1311867741.7345991135 0.4333463013 0.2183517192 0.4338388145 0.0044169270 0.0959820000 28631729 955859216 1785577472 -0.3902559280 -0.0884954557 0.0433899462 694 1311867741.7702169418 0.4336056709 0.2186618834 0.4338388145 0.0044138021 0.1181540000 28633559 955859216 1784713216 -0.3897096813 -0.0885185897 0.0432340354 695 1311867741.8058650494 0.4336301088 0.2189711902 0.4338388145 0.0044106677 0.1067700000 28635389 955859216 1783697408 -0.3888909817 -0.0882235095 0.0428058356 696 1311867741.8388509750 0.4338220358 0.2192798840 0.4338388145 0.0044084695 0.1163710000 28637219 955859216 1782554624 -0.3884854019 -0.0882516131 0.0425253697 697 1311867741.8683021069 0.4343671799 0.2195884741 0.4343671799 0.0044059711 0.0943270000 28638921 955859216 1781538816 -0.3883866370 -0.0883242190 0.0423615128 698 1311867741.9065721035 0.4343931675 0.2198962172 0.4343931675 0.0044029195 0.1149630000 28640783 955859216 1779757056 -0.3877766132 -0.0879262164 0.0418555327 699 1311867741.9387769699 0.4351827800 0.2202042094 0.4351827800 0.0044006744 0.1353220000 28642581 955859216 1781366784 -0.3877109289 -0.0876700655 0.0415724367 700 1311867741.9665379524 0.4348766208 0.2205108843 0.4351827800 0.0043986483 0.1333840000 28644251 955859216 1783144448 -0.3867143691 -0.0876807570 0.0411458500 701 1311867742.0029959679 0.4352577031 0.2208172278 0.4352577031 0.0043961008 0.1122100000 28646081 955859216 1784795136 -0.3861207962 -0.0878911167 0.0410708189 702 1311867742.0344839096 0.4358385801 0.2211235260 0.4358385801 0.0043930441 0.0997130000 28647815 955859216 1784061952 -0.3859134614 -0.0875429958 0.0408452600 703 1311867742.0674400330 0.4356119633 0.2214286305 0.4358385801 0.0043905740 0.0960440000 28649581 955859216 1782935552 -0.3849033713 -0.0872933418 0.0405877493 704 1311867742.1030650139 0.4370856583 0.2217349615 0.4370856583 0.0043886595 0.0941050000 28651379 955859216 1781919744 -0.3851093948 -0.0868819505 0.0404245742 705 1311867742.1348879337 0.4374487996 0.2220409386 0.4374487996 0.0043867616 0.1139070000 28653113 955859216 1780776960 -0.3844385445 -0.0868195444 0.0401866883 706 1311867742.1672229767 0.4368058145 0.2223451381 0.4374487996 0.0043846722 0.0939280000 28654911 955859216 1779761152 -0.3833095431 -0.0863152370 0.0401039571 707 1311867742.2028279305 0.4369877577 0.2226487345 0.4374487996 0.0043824171 0.1178780000 28656773 955859216 1778761728 -0.3825672567 -0.0860012695 0.0399788469 708 1311867742.2362670898 0.4373999238 0.2229520554 0.4374487996 0.0043810707 0.1323930000 28658539 955859216 1780371456 -0.3821521997 -0.0857829526 0.0399512351 709 1311867742.2674059868 0.4377290308 0.2232549848 0.4377290308 0.0043788203 0.1386010000 28660305 955859216 1782001664 -0.3818840384 -0.0860924795 0.0399580002 710 1311867742.3028159142 0.4380474687 0.2235575094 0.4380474687 0.0043763016 0.1334000000 28662135 955859216 1783652352 -0.3818044960 -0.0861000121 0.0397246927 711 1311867742.3350739479 0.4387605786 0.2238601860 0.4387605786 0.0043734953 0.1136940000 28663869 955859216 1785430016 -0.3821434975 -0.0860174298 0.0394222774 712 1311867742.3694241047 0.4386306107 0.2241618299 0.4387605786 0.0043704659 0.1399060000 28665699 955859216 1784459264 -0.3818002641 -0.0862975717 0.0390820205 713 1311867742.4062991142 0.4399517179 0.2244644805 0.4399517179 0.0043674700 0.0915670000 28667529 955859216 1783443456 -0.3827349842 -0.0863691643 0.0385984480 714 1311867742.4346439838 0.4400159121 0.2247663733 0.4400159121 0.0043645115 0.0926990000 28669231 955859216 1782427648 -0.3825114369 -0.0864664838 0.0382542051 715 1311867742.4666969776 0.4406140447 0.2250682581 0.4406140447 0.0043621356 0.0933110000 28670997 955859216 1781284864 -0.3827582896 -0.0862790197 0.0379856676 716 1311867742.5047059059 0.4406231940 0.2253693125 0.4406231940 0.0043591550 0.1131310000 28672827 955859216 1780269056 -0.3823335171 -0.0861648992 0.0378880315 717 1311867742.5359389782 0.4409820735 0.2256700276 0.4409820735 0.0043564889 0.0968240000 28674593 955859216 1779253248 -0.3823076487 -0.0859406516 0.0378859006 718 1311867742.5678529739 0.4407711327 0.2259696114 0.4409820735 0.0043542095 0.0922080000 28676391 955859216 1778237440 -0.3816651404 -0.0856730118 0.0378215164 719 1311867742.6054639816 0.4409854412 0.2262686598 0.4409854412 0.0043514525 0.1155780000 28678221 955859216 1777238016 -0.3815473318 -0.0859034508 0.0377748162 720 1311867742.6347279549 0.4401023388 0.2265656510 0.4409854412 0.0043488566 0.0956940000 28679923 955859216 1778847744 -0.3804643452 -0.0855653509 0.0377324857 721 1311867742.6724960804 0.4406858683 0.2268626277 0.4409854412 0.0043462667 0.1353990000 28681817 955859216 1780477952 -0.3807389140 -0.0857635736 0.0379028730 722 1311867742.7046229839 0.4411115646 0.2271593714 0.4411115646 0.0043432583 0.1327760000 28683551 955859216 1782128640 -0.3809019625 -0.0860538706 0.0379400887 723 1311867742.7356119156 0.4407117069 0.2274547412 0.4411115646 0.0043403176 0.1563570000 28685317 955859216 1783906304 -0.3801735938 -0.0860554427 0.0377637744 724 1311867742.7726070881 0.4415993094 0.2277505210 0.4415993094 0.0043382521 0.1118110000 28687179 955859216 1785565184 -0.3805872202 -0.0864384845 0.0377551466 725 1311867742.8034689426 0.4421662092 0.2280462667 0.4421662092 0.0043385424 0.1365560000 28688945 955859216 1784721408 -0.3812295198 -0.0863446966 0.0376826115 726 1311867742.8352251053 0.4425051808 0.2283416647 0.4425051808 0.0043380968 0.0935980000 28690679 955859216 1783705600 -0.3808620870 -0.0866574124 0.0377245955 727 1311867742.8705639839 0.4432836473 0.2286373208 0.4432836473 0.0043354465 0.0933230000 28692477 955859216 1782562816 -0.3814302385 -0.0865646675 0.0377753675 728 1311867742.9046700001 0.4430093169 0.2289317878 0.4432836473 0.0043326029 0.1120350000 28694275 955859216 1781547008 -0.3807782233 -0.0866601318 0.0376219749 729 1311867742.9382069111 0.4425436258 0.2292248082 0.4432836473 0.0043526964 0.0946320000 28696105 955859216 1780404224 -0.3802755475 -0.0864289552 0.0375744253 730 1311867742.9707310200 0.4420639277 0.2295163686 0.4432836473 0.0043531044 0.1129290000 28697871 955859216 1779404800 -0.3794705272 -0.0862356797 0.0373081900 731 1311867743.0024189949 0.4427323937 0.2298080458 0.4432836473 0.0043546559 0.0926740000 28699605 955859216 1780994048 -0.3798707426 -0.0862631053 0.0374849066 732 1311867743.0345149040 0.4427745938 0.2300989837 0.4432836473 0.0043550795 0.0773820000 28701371 955859216 1782644736 -0.3795505464 -0.0859463066 0.0374782383 733 1311867743.0722420216 0.4429960251 0.2303894299 0.4432836473 0.0043536747 0.0935720000 28703233 955859216 1784438784 -0.3792815804 -0.0863294601 0.0373535901 734 1311867743.1045989990 0.4428552985 0.2306788929 0.4432836473 0.0043510280 0.1009220000 28704999 955859216 1783689216 -0.3788095117 -0.0864050835 0.0373732895 735 1311867743.1350400448 0.4433698654 0.2309682684 0.4433698654 0.0043497331 0.0953120000 28706733 955859216 1782562816 -0.3787085116 -0.0863892138 0.0372330248 736 1311867743.1704380512 0.4430636466 0.2312564415 0.4433698654 0.0043532696 0.1115030000 28708531 955859216 1781547008 -0.3782744706 -0.0867223740 0.0369209498 737 1311867743.2037980556 0.4428563416 0.2315435512 0.4433698654 0.0043510127 0.0787670000 28710329 955859216 1780531200 -0.3776628077 -0.0864893943 0.0366647243 738 1311867743.2358140945 0.4435829520 0.2318308675 0.4435829520 0.0043493048 0.1132100000 28712063 955859216 1779515392 -0.3778855503 -0.0863947794 0.0367462970 739 1311867743.2708129883 0.4432228506 0.2321169189 0.4435829520 0.0043516257 0.0924260000 28713893 955859216 1778499584 -0.3773537576 -0.0859429091 0.0368752629 740 1311867743.3032529354 0.4435038269 0.2324025769 0.4435829520 0.0043585637 0.0989980000 28715659 955859216 1775042560 -0.3775788844 -0.0859651715 0.0369277894 741 1311867743.3363931179 0.4436443746 0.2326876535 0.4436443746 0.0043558546 0.1217210000 28717425 955859216 1776230400 -0.3776159883 -0.0854142383 0.0370754041 742 1311867743.3707330227 0.4432923794 0.2329714874 0.4436443746 0.0043533635 0.0936180000 28719223 955859216 1775325184 -0.3771389425 -0.0849381909 0.0371343493 743 1311867743.4043838978 0.4437949061 0.2332552336 0.4437949061 0.0043505839 0.0958460000 28721021 955859216 1774309376 -0.3775903881 -0.0849080235 0.0373331755 744 1311867743.4352641106 0.4440231025 0.2335385237 0.4440231025 0.0043561093 0.1149480000 28722787 955859216 1775788032 -0.3778057992 -0.0851964653 0.0372404307 745 1311867743.4768960476 0.4439814985 0.2338209975 0.4440231025 0.0043553454 0.0946300000 28724681 955859216 1777586176 -0.3777035177 -0.0849297941 0.0371864289 746 1311867743.5035250187 0.4447685480 0.2341037690 0.4447685480 0.0043531151 0.0975240000 28726383 955859216 1779216384 -0.3782680035 -0.0848063976 0.0372900367 747 1311867743.5389750004 0.4449807703 0.2343860676 0.4449807703 0.0043542546 0.1163050000 28728181 955859216 1781014528 -0.3786868453 -0.0848878250 0.0371306837 748 1311867743.5749680996 0.4442231655 0.2346665984 0.4449807703 0.0043543205 0.0936750000 28730011 955859216 1782644736 -0.3773431182 -0.0841548741 0.0366706997 749 1311867743.6036109924 0.4448650181 0.2349472372 0.4449807703 0.0043581145 0.0780730000 28731713 955859216 1784295424 -0.3785015643 -0.0841561705 0.0368380100 750 1311867743.6354589462 0.4448819458 0.2352271501 0.4449807703 0.0043581785 0.0963960000 28733479 955859216 1783451648 -0.3786962032 -0.0839735419 0.0365476646 751 1311867743.6759150028 0.4443597198 0.2355056223 0.4449807703 0.0043554156 0.0989780000 28735373 955859216 1780248576 -0.3782773614 -0.0845423490 0.0362387598 752 1311867743.7034959793 0.4450937212 0.2357843298 0.4450937212 0.0043525907 0.1129860000 28737075 955859216 1781039104 -0.3792036772 -0.0845743939 0.0362792797 753 1311867743.7388861179 0.4442588687 0.2360611884 0.4450937212 0.0043506266 0.0912420000 28738905 955859216 1780023296 -0.3786066175 -0.0845638514 0.0356901139 754 1311867743.7733619213 0.4446306825 0.2363378058 0.4450937212 0.0043479631 0.0962750000 28740735 955859216 1779007488 -0.3792026937 -0.0851085782 0.0355064869 755 1311867743.8064749241 0.4450834692 0.2366142901 0.4450937212 0.0043454019 0.0922920000 28742469 955859216 1777348608 -0.3798405528 -0.0852539465 0.0352802463 756 1311867743.8391659260 0.4463473260 0.2368917148 0.4463473260 0.0043435718 0.0950920000 28744235 955859216 1779007488 -0.3813886344 -0.0857198685 0.0351451337 757 1311867743.8726658821 0.4449932277 0.2371666177 0.4463473260 0.0043414253 0.0946400000 28746065 955859216 1780359168 -0.3802821636 -0.0861067176 0.0346107334 758 1311867743.9031310081 0.4453616738 0.2374412814 0.4463473260 0.0043388056 0.0972840000 28747799 955859216 1782026240 -0.3805600107 -0.0861640424 0.0342737585 759 1311867743.9453630447 0.4465107918 0.2377167353 0.4465107918 0.0043365065 0.0960040000 28749725 955859216 1783787520 -0.3818753660 -0.0865724161 0.0341552794 760 1311867743.9741249084 0.4464509487 0.2379913856 0.4465107918 0.0043347719 0.0967680000 28751427 955859216 1785438208 -0.3819253445 -0.0861286223 0.0336252041 761 1311867744.0042529106 0.4459626377 0.2382646724 0.4465107918 0.0043335097 0.0995760000 28753129 955859216 1784479744 -0.3814576566 -0.0851138160 0.0333944000 762 1311867744.0407259464 0.4457970262 0.2385370245 0.4465107918 0.0043316063 0.0943050000 28754991 955859216 1783324672 -0.3813170791 -0.0848860219 0.0332896002 763 1311867744.0716118813 0.4452627599 0.2388079626 0.4465107918 0.0043292042 0.0960390000 28756725 955859216 1782308864 -0.3809176087 -0.0845254958 0.0331815779 764 1311867744.1111290455 0.4452169836 0.2390781315 0.4465107918 0.0043264119 0.1303910000 28758523 955859216 1781166080 -0.3809088469 -0.0843864009 0.0329468101 765 1311867744.1412119865 0.4454317391 0.2393478747 0.4465107918 0.0043240998 0.1172760000 28760257 955859216 1780150272 -0.3811599016 -0.0834013969 0.0326606967 766 1311867744.1734991074 0.4447781444 0.2396160605 0.4465107918 0.0043214638 0.1357090000 28762055 955859216 1781645312 -0.3802719414 -0.0826196969 0.0325234532 767 1311867744.2046771049 0.4461189210 0.2398852950 0.4465107918 0.0043239335 0.0912350000 28763789 955859216 1783406592 -0.3815942109 -0.0830332935 0.0324945748 768 1311867744.2400228977 0.4463557899 0.2401541367 0.4465107918 0.0043223217 0.0945640000 28765651 955859216 1785057280 -0.3819010556 -0.0831325799 0.0324127264 769 1311867744.2773048878 0.4459976554 0.2404218136 0.4465107918 0.0043197667 0.1009090000 28767481 955859216 1784201216 -0.3815021813 -0.0820838585 0.0322597548 770 1311867744.3032519817 0.4453683496 0.2406879780 0.4465107918 0.0043179724 0.0973820000 28769151 955859216 1779884032 -0.3810485303 -0.0823563859 0.0320163257 771 1311867744.3391230106 0.4457362592 0.2409539290 0.4465107918 0.0043176394 0.1283030000 28770981 955859216 1781673984 -0.3812533021 -0.0827317536 0.0321525596 772 1311867744.3707659245 0.4453488588 0.2412186893 0.4465107918 0.0043150479 0.1158710000 28772715 955859216 1783300096 -0.3806988299 -0.0822298303 0.0319503881 773 1311867744.4027431011 0.4463172555 0.2414840173 0.4465107918 0.0043131652 0.1360050000 28774513 955859216 1784930304 -0.3815217912 -0.0821442977 0.0321901627 774 1311867744.4383800030 0.4471413195 0.2417497244 0.4471413195 0.0043109112 0.1382270000 28776311 955859216 1784090624 -0.3823428750 -0.0823787451 0.0319423229 775 1311867744.4717690945 0.4479594529 0.2420158015 0.4479594529 0.0043094160 0.0908530000 28778109 955859216 1782943744 -0.3829919100 -0.0825334191 0.0322391689 776 1311867744.5026860237 0.4469608665 0.2422799060 0.4479594529 0.0043067545 0.0758530000 28779875 955859216 1781927936 -0.3819316626 -0.0817772523 0.0316270776 777 1311867744.5383169651 0.4471492469 0.2425435731 0.4479594529 0.0043066479 0.1336290000 28781705 955859216 1780785152 -0.3819872737 -0.0821616799 0.0313627422 778 1311867744.5726189613 0.4470886588 0.2428064845 0.4479594529 0.0043039755 0.0876790000 28783503 955859216 1779769344 -0.3818404973 -0.0829307511 0.0312056281 779 1311867744.6028740406 0.4477437735 0.2430695619 0.4479594529 0.0043043160 0.1140150000 28785237 955859216 1778114560 -0.3820071816 -0.0827500373 0.0311280936 780 1311867744.6386809349 0.4473247528 0.2433314275 0.4479594529 0.0043048358 0.1311520000 28787067 955859216 1779724288 -0.3819565475 -0.0826431066 0.0308679044 781 1311867744.6707758904 0.4460097849 0.2435909389 0.4479594529 0.0043023711 0.1389460000 28788833 955859216 1781374976 -0.3807111084 -0.0823980868 0.0303511918 782 1311867744.7029349804 0.4479493797 0.2438522668 0.4479594529 0.0043057345 0.0912590000 28790599 955859216 1783152640 -0.3819827735 -0.0823282897 0.0307172537 783 1311867744.7396171093 0.4459186196 0.2441103337 0.4479594529 0.0043095136 0.1159440000 28792429 955859216 1784803328 -0.3804849088 -0.0815649405 0.0303355325 784 1311867744.7705199718 0.4467001259 0.2443687390 0.4479594529 0.0043070472 0.1155050000 28794163 955859216 1784070144 -0.3812808990 -0.0821782500 0.0304976702 785 1311867744.8035891056 0.4471028149 0.2446269990 0.4479594529 0.0043077813 0.1348790000 28795961 955859216 1782943744 -0.3813066483 -0.0826836526 0.0304246843 786 1311867744.8424170017 0.4466449320 0.2448840192 0.4479594529 0.0043055937 0.1083480000 28797823 955859216 1781927936 -0.3806611598 -0.0828708336 0.0304555558 787 1311867744.8727390766 0.4465231299 0.2451402316 0.4479594529 0.0043067435 0.1155790000 28799589 955859216 1783406592 -0.3811565042 -0.0833411068 0.0301499665 788 1311867744.9029939175 0.4469463527 0.2453963307 0.4479594529 0.0043040917 0.1141960000 28801323 955859216 1785057280 -0.3816045523 -0.0840729773 0.0300423205 789 1311867744.9392940998 0.4469114542 0.2456517365 0.4479594529 0.0043058053 0.1003680000 28803185 955859216 1784201216 -0.3809176087 -0.0841871649 0.0298428684 790 1311867744.9708900452 0.4465328753 0.2459060164 0.4479594529 0.0043066758 0.0955240000 28804887 955859216 1783197696 -0.3810094893 -0.0840797871 0.0292922109 791 1311867745.0027489662 0.4467124641 0.2461598804 0.4479594529 0.0043104090 0.0946750000 28806653 955859216 1782054912 -0.3807153702 -0.0840093419 0.0287128873 792 1311867745.0384869576 0.4468488693 0.2464132756 0.4479594529 0.0043104972 0.1313220000 28808483 955859216 1781039104 -0.3811379075 -0.0842861757 0.0289437175 793 1311867745.0729780197 0.4462146759 0.2466652320 0.4479594529 0.0043107295 0.1360680000 28810281 955859216 1780023296 -0.3804053664 -0.0844882354 0.0287441723 794 1311867745.1118760109 0.4459065199 0.2469161656 0.4479594529 0.0043111307 0.0936190000 28812143 955859216 1781501952 -0.3803525269 -0.0840869248 0.0282782912 795 1311867745.1405589581 0.4449573159 0.2471652739 0.4479594529 0.0043098719 0.0758350000 28813845 955859216 1783152640 -0.3793032765 -0.0840643272 0.0279707126 796 1311867745.1729030609 0.4459480047 0.2474150010 0.4479594529 0.0043075550 0.1371570000 28815611 955859216 1784930304 -0.3801414371 -0.0847881362 0.0281662829 797 1311867745.2068369389 0.4468244910 0.2476652011 0.4479594529 0.0043050530 0.1353860000 28817409 955859216 1783959552 -0.3810415566 -0.0850065127 0.0282771178 798 1311867745.2430789471 0.4457174540 0.2479133869 0.4479594529 0.0043029381 0.0914090000 28819239 955859216 1782943744 -0.3797118962 -0.0845518485 0.0281873047 799 1311867745.2729060650 0.4477702081 0.2481635206 0.4479594529 0.0043009293 0.0926440000 28820973 955859216 1781927936 -0.3815991282 -0.0846629888 0.0285516828 800 1311867745.3112850189 0.4467791021 0.2484117901 0.4479594529 0.0042998034 0.0949610000 28822803 955859216 1780785152 -0.3806387484 -0.0845335722 0.0280447900 801 1311867745.3395059109 0.4461750388 0.2486586855 0.4479594529 0.0042972051 0.0942880000 28824537 955859216 1779769344 -0.3799432516 -0.0844372511 0.0276981890 802 1311867745.3733940125 0.4460162520 0.2489047673 0.4479594529 0.0042961460 0.1370160000 28826335 955859216 1778880512 -0.3797127306 -0.0843504593 0.0272792615 803 1311867745.4102098942 0.4457464516 0.2491499001 0.4479594529 0.0042938704 0.1537020000 28828165 955859216 1777991680 -0.3791491985 -0.0847562402 0.0270904601 804 1311867745.4433169365 0.4470804036 0.2493960823 0.4479594529 0.0042917979 0.1084320000 28829963 955859216 1779490816 -0.3803946972 -0.0845700204 0.0271397978 805 1311867745.4708619118 0.4454257786 0.2496395975 0.4479594529 0.0042894991 0.0969820000 28831633 955859216 1781121024 -0.3787974119 -0.0841953382 0.0265632607 806 1311867745.5099780560 0.4465797544 0.2498839401 0.4479594529 0.0042885420 0.1393900000 28833527 955859216 1782763520 -0.3797215223 -0.0843102932 0.0262934119 807 1311867745.5417380333 0.4466386139 0.2501277501 0.4479594529 0.0042875955 0.1141090000 28835293 955859216 1784541184 -0.3795378804 -0.0847043395 0.0262381695 808 1311867745.5704059601 0.4462257922 0.2503704457 0.4479594529 0.0042854154 0.1392120000 28836995 955859216 1783570432 -0.3792093694 -0.0854700580 0.0258134045 809 1311867745.6133821011 0.4459018111 0.2506121408 0.4479594529 0.0042838907 0.0927380000 28838953 955859216 1779851264 -0.3789317012 -0.0855100676 0.0253833793 810 1311867745.6438291073 0.4451394975 0.2508522981 0.4479594529 0.0042853240 0.1285540000 28840719 955859216 1781174272 -0.3781600296 -0.0853160098 0.0248259269 811 1311867745.6709001064 0.4460526109 0.2510929890 0.4479594529 0.0042897394 0.1138970000 28842357 955859216 1780142080 -0.3789662719 -0.0850850269 0.0248990506 812 1311867745.7088780403 0.4468562603 0.2513340767 0.4479594529 0.0042882025 0.0947980000 28844251 955859216 1781620736 -0.3793922961 -0.0850689337 0.0247291811 813 1311867745.7423269749 0.4458098710 0.2515732844 0.4479594529 0.0042885533 0.1151020000 28846017 955859216 1783398400 -0.3786070645 -0.0851434171 0.0243578553 814 1311867745.7760419846 0.4469558299 0.2518133121 0.4479594529 0.0042930864 0.0959640000 28847815 955859216 1785049088 -0.3792537153 -0.0856870338 0.0247690994 815 1311867745.8116889000 0.4462667704 0.2520519053 0.4479594529 0.0042962715 0.0976070000 28849645 955859216 1784205312 -0.3784888983 -0.0853510350 0.0249459743 816 1311867745.8389890194 0.4461623132 0.2522897857 0.4479594529 0.0042956931 0.1171850000 28851347 955859216 1783611392 -0.3784967363 -0.0855324194 0.0253102053 817 1311867745.8709759712 0.4477023482 0.2525289687 0.4479594529 0.0042937451 0.1183140000 28853081 955859216 1782034432 -0.3800584972 -0.0855110660 0.0256565455 818 1311867745.9108459949 0.4470966756 0.2527668266 0.4479594529 0.0042945423 0.1103260000 28854975 955859216 1782824960 -0.3792140484 -0.0850610584 0.0253472328 819 1311867745.9435789585 0.4478043914 0.2530049677 0.4479594529 0.0042949976 0.0938450000 28856773 955859216 1781809152 -0.3798651397 -0.0856243670 0.0251759291 820 1311867745.9732220173 0.4482197464 0.2532430345 0.4482197464 0.0042926818 0.1384700000 28858475 955859216 1780682752 -0.3799650669 -0.0869990662 0.0260873921 821 1311867746.0083909035 0.4480818510 0.2534803534 0.4482197464 0.0042915006 0.0885480000 28860273 955859216 1777971200 -0.3795401752 -0.0873447657 0.0264165848 822 1311867746.0391409397 0.4476691186 0.2537165927 0.4482197464 0.0042892826 0.1088220000 28862071 955859216 1778253824 -0.3789040446 -0.0875281021 0.0265825111 823 1311867746.0728518963 0.4473444223 0.2539518635 0.4482197464 0.0042869830 0.1374670000 28863837 955859216 1777238016 -0.3783117533 -0.0872774944 0.0262288563 824 1311867746.1113359928 0.4481961429 0.2541875968 0.4482197464 0.0042857125 0.1082140000 28865667 955859216 1775968256 -0.3786959350 -0.0876374543 0.0265510976 825 1311867746.1412689686 0.4496403337 0.2544245092 0.4496403337 0.0042837282 0.0783170000 28867433 955859216 1774952448 -0.3797447085 -0.0887403861 0.0273130685 826 1311867746.1721889973 0.4498955309 0.2546611570 0.4498955309 0.0042817081 0.1295030000 28869167 955859216 1773936640 -0.3798537850 -0.0887285918 0.0272888839 827 1311867746.2066209316 0.4494484365 0.2548966918 0.4498955309 0.0042793635 0.0962600000 28870965 955859216 1772920832 -0.3791736066 -0.0884090140 0.0270941574 828 1311867746.2386920452 0.4498670101 0.2551321632 0.4498955309 0.0042773769 0.0936820000 28872763 955859216 1768824832 -0.3798747361 -0.0892927423 0.0271795113 829 1311867746.2704648972 0.4499490857 0.2553671655 0.4499490857 0.0042748772 0.0927480000 28874529 955859216 1770508288 -0.3800835907 -0.0898682326 0.0272981077 830 1311867746.3068819046 0.4476886094 0.2555988781 0.4499490857 0.0042739189 0.1145610000 28876327 955859216 1771986944 -0.3781401217 -0.0892566144 0.0262138546 831 1311867746.3393440247 0.4474912882 0.2558297955 0.4499490857 0.0042753748 0.0946090000 28878125 955859216 1773764608 -0.3775473833 -0.0895516574 0.0263590962 832 1311867746.3797800541 0.4483559132 0.2560611971 0.4499490857 0.0042731357 0.0933540000 28880019 955859216 1775415296 -0.3786760271 -0.0897937790 0.0269348882 833 1311867746.4078478813 0.4483876228 0.2562920812 0.4499490857 0.0042714212 0.1172430000 28881721 955859216 1777192960 -0.3789572716 -0.0892848223 0.0264302827 834 1311867746.4389901161 0.4474282563 0.2565212612 0.4499490857 0.0042693090 0.0939840000 28883455 955859216 1778970624 -0.3781293631 -0.0887232944 0.0261163414 835 1311867746.4774639606 0.4465321004 0.2567488191 0.4499490857 0.0042690051 0.1140710000 28885349 955859216 1780621312 -0.3773887753 -0.0889910832 0.0260485597 836 1311867746.5066781044 0.4468958676 0.2569762678 0.4499490857 0.0042670078 0.0984220000 28887051 955859216 1782288384 -0.3776323795 -0.0888034776 0.0258160718 837 1311867746.5406761169 0.4464101493 0.2572025926 0.4499490857 0.0042661793 0.1153430000 28888849 955859216 1784049664 -0.3773838878 -0.0883800536 0.0258460194 838 1311867746.5748629570 0.4465891719 0.2574285909 0.4499490857 0.0042639259 0.0952810000 28890679 955859216 1785700352 -0.3776587844 -0.0885105580 0.0259141922 839 1311867746.6067559719 0.4459777474 0.2576533217 0.4499490857 0.0042614912 0.0957880000 28892413 955859216 1784856576 -0.3770711422 -0.0883133486 0.0259393416 840 1311867746.6396849155 0.4466071129 0.2578782667 0.4499490857 0.0042625741 0.0932920000 28894243 955859216 1783054336 -0.3777102232 -0.0884520933 0.0261880569 841 1311867746.6749529839 0.4458220601 0.2581017433 0.4499490857 0.0042637261 0.1006980000 28896041 955859216 1782444032 -0.3767872155 -0.0883829594 0.0258152932 842 1311867746.7095060349 0.4464205205 0.2583253998 0.4499490857 0.0042615096 0.1040320000 28897839 955859216 1781428224 -0.3772179484 -0.0890744030 0.0261921007 843 1311867746.7391049862 0.4469935894 0.2585492055 0.4499490857 0.0042597317 0.0979780000 28899541 955859216 1780412416 -0.3777090609 -0.0894813836 0.0264211148 844 1311867746.7751340866 0.4465817809 0.2587719929 0.4499490857 0.0042572849 0.1110000000 28901403 955859216 1778737152 -0.3773486018 -0.0895060897 0.0259943791 845 1311867746.8070099354 0.4455724657 0.2589930585 0.4499490857 0.0042557143 0.0933890000 28903169 955859216 1780412416 -0.3764531314 -0.0889540240 0.0251396187 846 1311867746.8401610851 0.4450291097 0.2592129593 0.4499490857 0.0042533193 0.0962740000 28904935 955859216 1781764096 -0.3756928742 -0.0899095014 0.0256373622 847 1311867746.8748359680 0.4454843104 0.2594328782 0.4499490857 0.0042530131 0.1159740000 28906765 955859216 1783562240 -0.3759276867 -0.0903242677 0.0256216526 848 1311867746.9086029530 0.4453526735 0.2596521233 0.4499490857 0.0042510372 0.1136870000 28908531 955859216 1785192448 -0.3755472600 -0.0898695886 0.0255259722 849 1311867746.9389610291 0.4454846382 0.2598710073 0.4499490857 0.0042490273 0.0981900000 28910297 955859216 1784229888 -0.3754643798 -0.0904659629 0.0257288665 850 1311867746.9748229980 0.4457560480 0.2600896956 0.4499490857 0.0042523890 0.0954890000 28912127 955859216 1783078912 -0.3749386966 -0.0905442759 0.0258612297 851 1311867747.0066559315 0.4447135329 0.2603066448 0.4499490857 0.0042569441 0.0944670000 28913861 955859216 1782063104 -0.3745644689 -0.0902925581 0.0252722055 852 1311867747.0389339924 0.4452546835 0.2605237200 0.4499490857 0.0042549460 0.1107310000 28915627 955859216 1780920320 -0.3750030696 -0.0904956385 0.0257209558 853 1311867747.0749640465 0.4448781013 0.2607398447 0.4499490857 0.0042548810 0.0971050000 28917489 955859216 1779904512 -0.3740366995 -0.0906886905 0.0257630832 854 1311867747.1066820621 0.4440254271 0.2609544648 0.4499490857 0.0042593574 0.1291040000 28919223 955859216 1779015680 -0.3736268580 -0.0906368345 0.0262300670 855 1311867747.1389479637 0.4437457621 0.2611682558 0.4499490857 0.0042568904 0.1135970000 28920989 955859216 1780494336 -0.3731242120 -0.0902077705 0.0263553262 856 1311867747.1744880676 0.4441624284 0.2613820341 0.4499490857 0.0042550480 0.0962360000 28922819 955859216 1782145024 -0.3732968271 -0.0906558707 0.0265405048 857 1311867747.2066030502 0.4449515343 0.2615962342 0.4499490857 0.0042527053 0.0968160000 28924585 955859216 1783922688 -0.3739154339 -0.0910708904 0.0271042436 858 1311867747.2385439873 0.4451154172 0.2618101260 0.4499490857 0.0042524439 0.0958980000 28926383 955859216 1785573376 -0.3736981452 -0.0913394541 0.0269295722 859 1311867747.2745490074 0.4436972439 0.2620218689 0.4499490857 0.0042774999 0.0988200000 28928213 955859216 1784713216 -0.3721437454 -0.0913689435 0.0262225866 860 1311867747.3064720631 0.4444516003 0.2622339965 0.4499490857 0.0042844170 0.0937320000 28929915 955859216 1783586816 -0.3729486465 -0.0916352645 0.0265432913 861 1311867747.3388469219 0.4448839426 0.2624461334 0.4499490857 0.0042916043 0.0929530000 28931745 955859216 1782571008 -0.3731688261 -0.0927808434 0.0274557322 862 1311867747.3758800030 0.4454476237 0.2626584322 0.4499490857 0.0042925848 0.1144900000 28933543 955859216 1781555200 -0.3733987808 -0.0927984416 0.0276318043 863 1311867747.4068729877 0.4447101355 0.2628693843 0.4499490857 0.0042908288 0.1141590000 28935309 955859216 1780428800 -0.3726878762 -0.0924707651 0.0277027935 864 1311867747.4396450520 0.4448083341 0.2630799618 0.4499490857 0.0042944988 0.1118350000 28937043 955859216 1782018048 -0.3726428747 -0.0926547498 0.0280130953 865 1311867747.4756069183 0.4459242523 0.2632913425 0.4499490857 0.0042952181 0.0950420000 28938873 955859216 1783668736 -0.3737803102 -0.0928858221 0.0282960981 866 1311867747.5095520020 0.4445145726 0.2635006072 0.4499490857 0.0042947593 0.0954130000 28940703 955859216 1785446400 -0.3724706769 -0.0920935795 0.0277562700 867 1311867747.5405330658 0.4447642863 0.2637096772 0.4499490857 0.0042959395 0.0987710000 28942437 955859216 1784713216 -0.3726116419 -0.0922030061 0.0274580754 868 1311867747.5766739845 0.4434818327 0.2639167879 0.4499490857 0.0042939625 0.0936780000 28944267 955859216 1783586816 -0.3712361753 -0.0925329849 0.0274415426 869 1311867747.6086390018 0.4451379776 0.2641253279 0.4499490857 0.0042921710 0.0930550000 28946033 955859216 1782444032 -0.3726782203 -0.0930612087 0.0284341425 870 1311867747.6432039738 0.4443513751 0.2643324842 0.4499490857 0.0042898694 0.0949150000 28947863 955859216 1781428224 -0.3719416559 -0.0926883072 0.0282171369 871 1311867747.6760280132 0.4439627826 0.2645387188 0.4499490857 0.0042951272 0.0947820000 28949629 955859216 1780412416 -0.3717505634 -0.0924870893 0.0278450884 872 1311867747.7068400383 0.4457021952 0.2647464751 0.4499490857 0.0042936697 0.0972530000 28951363 955859216 1779396608 -0.3735387027 -0.0928211212 0.0285878628 873 1311867747.7480750084 0.4455203414 0.2649535471 0.4499490857 0.0042992299 0.0854050000 28953353 955859216 1779396608 -0.3738626838 -0.0926686153 0.0281361938 874 1311867747.7826869488 0.4442704022 0.2651587151 0.4499490857 0.0042976366 0.1122800000 28955151 955859216 1778634752 -0.3729023337 -0.0923725143 0.0275290050 875 1311867747.8149020672 0.4445211291 0.2653637007 0.4499490857 0.0042963208 0.0984240000 28956917 955859216 1777872896 -0.3735759556 -0.0926853344 0.0275388099 876 1311867747.8466539383 0.4453857541 0.2655692054 0.4499490857 0.0042945007 0.1111490000 28958651 955859216 1779478528 -0.3742515147 -0.0930695534 0.0282839984 877 1311867747.8827810287 0.4454252720 0.2657742864 0.4499490857 0.0042952785 0.0923620000 28960513 955859216 1781276672 -0.3744091690 -0.0929789990 0.0285188705 878 1311867747.9150440693 0.4461666346 0.2659797446 0.4499490857 0.0042940161 0.0956120000 28962311 955859216 1782906880 -0.3758242726 -0.0923096091 0.0280799568 879 1311867747.9477820396 0.4458023608 0.2661843210 0.4499490857 0.0042917613 0.1143050000 28964077 955859216 1784557568 -0.3758054376 -0.0920419544 0.0278491564 880 1311867747.9826579094 0.4451210201 0.2663876582 0.4499490857 0.0042894835 0.1162620000 28965875 955859216 1783857152 -0.3755385578 -0.0919980705 0.0274747014 881 1311867748.0146598816 0.4457863867 0.2665912890 0.4499490857 0.0042877538 0.0979380000 28967641 955859216 1782951936 -0.3767473996 -0.0915635005 0.0275106877 882 1311867748.0469269753 0.4454196393 0.2667940422 0.4499490857 0.0042860007 0.1217430000 28969407 955859216 1781825536 -0.3769174814 -0.0905944631 0.0275916904 883 1311867748.0828750134 0.4452752173 0.2669961726 0.4499490857 0.0042836070 0.0950620000 28971269 955859216 1781047296 -0.3773569465 -0.0903460085 0.0271976441 884 1311867748.1150569916 0.4445735812 0.2671970520 0.4499490857 0.0042821884 0.1251320000 28973003 955859216 1779777536 -0.3769504428 -0.0899695680 0.0275686048 885 1311867748.1486010551 0.4467750192 0.2673999650 0.4499490857 0.0042810693 0.1234470000 28974801 955859216 1779015680 -0.3794659972 -0.0897499174 0.0276063494 886 1311867748.1831040382 0.4443055093 0.2675996327 0.4499490857 0.0042801096 0.1096810000 28976567 955859216 1778253824 -0.3775327206 -0.0886755958 0.0263422579 887 1311867748.2148320675 0.4457877576 0.2678005212 0.4499490857 0.0042788525 0.0942850000 28978365 955859216 1779859456 -0.3791191280 -0.0887713879 0.0270604789 888 1311867748.2466599941 0.4449041486 0.2679999622 0.4499490857 0.0042794025 0.0962100000 28980099 955859216 1781526528 -0.3783979416 -0.0886384174 0.0267955698 889 1311867748.2827599049 0.4445617795 0.2681985694 0.4499490857 0.0042780241 0.0960130000 28981929 955859216 1783287808 -0.3783077598 -0.0881204829 0.0264545940 890 1311867748.3148829937 0.4445991218 0.2683967723 0.4499490857 0.0042833987 0.0959720000 28983695 955859216 1784938496 -0.3783354163 -0.0882178769 0.0269522835 891 1311867748.3470869064 0.4449495375 0.2685949235 0.4499490857 0.0042879604 0.0971770000 28985461 955859216 1784225792 -0.3789008856 -0.0889511406 0.0265527219 892 1311867748.3826999664 0.4454938173 0.2687932407 0.4499490857 0.0042903171 0.0949640000 28987291 955859216 1783332864 -0.3793402910 -0.0890156999 0.0271887183 893 1311867748.4148259163 0.4455461502 0.2689911723 0.4499490857 0.0042888974 0.0897350000 28989025 955859216 1782444032 -0.3795432448 -0.0886065066 0.0266670883 894 1311867748.4520189762 0.4455333650 0.2691886468 0.4499490857 0.0042996756 0.1135770000 28990887 955859216 1781555200 -0.3800403178 -0.0888294131 0.0265985876 895 1311867748.4831318855 0.4455762506 0.2693857279 0.4499490857 0.0042974085 0.0931730000 28992653 955859216 1780793344 -0.3801375628 -0.0886666030 0.0265480131 896 1311867748.5149960518 0.4453950524 0.2695821669 0.4499490857 0.0042967408 0.0941610000 28994419 955859216 1780031488 -0.3797904849 -0.0883564278 0.0265911836 897 1311867748.5467929840 0.4457527399 0.2697785666 0.4499490857 0.0042950248 0.0945180000 28996153 955859216 1781657600 -0.3804782927 -0.0886262208 0.0269004703 898 1311867748.5827159882 0.4463775754 0.2699752248 0.4499490857 0.0042930259 0.0955320000 28997983 955859216 1783287808 -0.3812346160 -0.0886260569 0.0270403884 899 1311867748.6147999763 0.4461409152 0.2701711821 0.4499490857 0.0042922074 0.0963640000 28999781 955859216 1784938496 -0.3812767565 -0.0879848599 0.0271424912 900 1311867748.6470849514 0.4463598132 0.2703669473 0.4499490857 0.0043028583 0.0970810000 29001515 955859216 1784221696 -0.3814470172 -0.0880290717 0.0279065073 901 1311867748.6827559471 0.4462040067 0.2705621050 0.4499490857 0.0043008180 0.0967030000 29003345 955859216 1783459840 -0.3813446164 -0.0883954912 0.0280793011 902 1311867748.7147359848 0.4457274973 0.2707563016 0.4499490857 0.0043232425 0.0927380000 29005111 955859216 1782571008 -0.3810142279 -0.0889270157 0.0285772085 903 1311867748.7499361038 0.4458859563 0.2709502437 0.4499490857 0.0043211498 0.0932770000 29006909 955859216 1781698560 -0.3814287484 -0.0893065408 0.0286778212 904 1311867748.7828259468 0.4462606013 0.2711441710 0.4499490857 0.0043203339 0.0793620000 29008739 955859216 1780920320 -0.3819280863 -0.0895692483 0.0291359089 905 1311867748.8151619434 0.4455804229 0.2713369183 0.4499490857 0.0043179761 0.1058450000 29010505 955859216 1779904512 -0.3815340698 -0.0898744613 0.0290128700 906 1311867748.8466329575 0.4468072057 0.2715305941 0.4499490857 0.0043163493 0.1001430000 29012207 955859216 1779142656 -0.3830783665 -0.0901261568 0.0295388438 907 1311867748.8829579353 0.4464958310 0.2717234995 0.4499490857 0.0043163182 0.1333290000 29014037 955859216 1776955392 -0.3830734491 -0.0901367366 0.0296176113 908 1311867748.9149119854 0.4460203946 0.2719154565 0.4499490857 0.0043150405 0.0907440000 29015835 955859216 1777111040 -0.3834029138 -0.0892621726 0.0290644616 909 1311867748.9472498894 0.4467359781 0.2721077783 0.4499490857 0.0043127671 0.0757570000 29017601 955859216 1775452160 -0.3847198188 -0.0889205858 0.0287154187 910 1311867748.9829359055 0.4452987015 0.2722980980 0.4499490857 0.0043112300 0.1284810000 29019431 955859216 1775206400 -0.3842107654 -0.0876294076 0.0271401703 911 1311867749.0159859657 0.4439899027 0.2724865632 0.4499490857 0.0043089050 0.0965490000 29021197 955859216 1774190592 -0.3833262324 -0.0870115682 0.0264266971 912 1311867749.0467190742 0.4437277317 0.2726743276 0.4499490857 0.0043069538 0.0922720000 29022931 955859216 1769234432 -0.3835349977 -0.0865249783 0.0259326417 913 1311867749.0828969479 0.4437045157 0.2728616553 0.4499490857 0.0043049778 0.0941620000 29024761 955859216 1770864640 -0.3838146329 -0.0865412503 0.0262240022 914 1311867749.1158421040 0.4421487451 0.2730468710 0.4499490857 0.0043033869 0.1128930000 29026559 955859216 1772531712 -0.3824588060 -0.0860914141 0.0257821977 915 1311867749.1485249996 0.4420818388 0.2732316086 0.4499490857 0.0043010955 0.1055190000 29028357 955859216 1774018560 -0.3825331628 -0.0859782398 0.0259298831 916 1311867749.1829619408 0.4422064424 0.2734160790 0.4499490857 0.0042994504 0.1221320000 29030155 955859216 1775669248 -0.3832660913 -0.0857815072 0.0257257540 917 1311867749.2156000137 0.4418105483 0.2735997152 0.4499490857 0.0042972308 0.0957660000 29031889 955859216 1777467392 -0.3830845058 -0.0853863880 0.0253403001 918 1311867749.2468719482 0.4415917695 0.2737827131 0.4499490857 0.0042980792 0.1364760000 29033623 955859216 1779113984 -0.3828296363 -0.0859233588 0.0250298381 919 1311867749.2828478813 0.4419329166 0.2739656840 0.4499490857 0.0042996491 0.1134850000 29035453 955859216 1780875264 -0.3834121227 -0.0859343633 0.0254939683 920 1311867749.3148140907 0.4426799417 0.2741490690 0.4499490857 0.0043008599 0.1132340000 29037251 955859216 1782525952 -0.3843215406 -0.0854662210 0.0251694471 921 1311867749.3468968868 0.4426547885 0.2743320286 0.4499490857 0.0042995257 0.0967940000 29038985 955859216 1784303616 -0.3847589791 -0.0851125494 0.0251859576 922 1311867749.3828470707 0.4430047274 0.2745149707 0.4499490857 0.0042979254 0.1133580000 29040815 955859216 1785954304 -0.3854591846 -0.0850398168 0.0251150094 923 1311867749.4147930145 0.4422141016 0.2746966599 0.4499490857 0.0042960843 0.1189990000 29042613 955859216 1785094144 -0.3850276768 -0.0843776986 0.0247998945 924 1311867749.4467489719 0.4430513382 0.2748788620 0.4499490857 0.0042943819 0.0930170000 29044347 955859216 1784221696 -0.3861552775 -0.0837862119 0.0249038152 925 1311867749.4829080105 0.4409528375 0.2750584014 0.4499490857 0.0042932086 0.0925920000 29046177 955859216 1783332864 -0.3849028349 -0.0835186243 0.0244154781 926 1311867749.5159850121 0.4415407777 0.2752381880 0.4499490857 0.0042910021 0.0944720000 29047943 955859216 1782444032 -0.3859640658 -0.0840406939 0.0249233264 927 1311867749.5468530655 0.4417121708 0.2754177716 0.4499490857 0.0042900514 0.0910650000 29049709 955859216 1781682176 -0.3866849840 -0.0842439607 0.0251892358 928 1311867749.5830268860 0.4410087764 0.2755962102 0.4499490857 0.0042878703 0.0814240000 29051539 955859216 1780793344 -0.3866754472 -0.0843831599 0.0252542198 929 1311867749.6148250103 0.4399310052 0.2757731044 0.4499490857 0.0042861907 0.1116500000 29053273 955859216 1780031488 -0.3863726258 -0.0845119804 0.0248530805 930 1311867749.6469049454 0.4400645494 0.2759497619 0.4499490857 0.0042853134 0.0925830000 29055071 955859216 1779269632 -0.3867442906 -0.0849928781 0.0252074469 931 1311867749.6829149723 0.4399251342 0.2761258901 0.4499490857 0.0042838830 0.1173110000 29056901 955859216 1777999872 -0.3875569105 -0.0855421126 0.0251040012 932 1311867749.7160799503 0.4398767352 0.2763015885 0.4499490857 0.0042823454 0.0972040000 29058667 955859216 1777238016 -0.3879363537 -0.0858906806 0.0246164650 933 1311867749.7468609810 0.4398680031 0.2764769008 0.4499490857 0.0042847847 0.1251290000 29060433 955859216 1776476160 -0.3880615830 -0.0865075961 0.0246751048 934 1311867749.7828791142 0.4384517074 0.2766503214 0.4499490857 0.0042835950 0.0931660000 29062263 955859216 1772384256 -0.3872572184 -0.0867962167 0.0243744962 935 1311867749.8148949146 0.4382024109 0.2768231044 0.4499490857 0.0042830506 0.1128680000 29063997 955859216 1774170112 -0.3874834180 -0.0867620483 0.0244827308 936 1311867749.8469030857 0.4374736547 0.2769947396 0.4499490857 0.0042808351 0.1104730000 29065795 955859216 1775714304 -0.3870996535 -0.0865152180 0.0242033899 937 1311867749.8829030991 0.4387630522 0.2771673845 0.4499490857 0.0043021959 0.0996420000 29067625 955859216 1777065984 -0.3885652721 -0.0867064968 0.0243221708 938 1311867749.9149639606 0.4377882481 0.2773386221 0.4499490857 0.0043129611 0.1291420000 29069359 955859216 1778843648 -0.3883022070 -0.0864807442 0.0241002403 939 1311867749.9508709908 0.4365460873 0.2775081721 0.4499490857 0.0043113428 0.1351860000 29071189 955859216 1780494336 -0.3875253499 -0.0862739533 0.0237246547 940 1311867749.9827940464 0.4363355339 0.2776771374 0.4499490857 0.0043118996 0.1145320000 29072987 955859216 1782161408 -0.3877214491 -0.0864374489 0.0235480070 941 1311867750.0147750378 0.4353743494 0.2778447221 0.4499490857 0.0043099969 0.0930510000 29074753 955859216 1783922688 -0.3871824443 -0.0866878107 0.0231913943 942 1311867750.0470709801 0.4347777963 0.2780113177 0.4499490857 0.0043077982 0.0922030000 29076519 955859216 1785573376 -0.3869103789 -0.0869617015 0.0228582323 943 1311867750.0829339027 0.4351809621 0.2781779875 0.4499490857 0.0043070575 0.1010470000 29078349 955859216 1784598528 -0.3874895275 -0.0872464329 0.0231138021 944 1311867750.1156458855 0.4345225394 0.2783436068 0.4499490857 0.0043055557 0.0944960000 29080115 955859216 1783459840 -0.3872059882 -0.0871139318 0.0227904469 945 1311867750.1474790573 0.4355293512 0.2785099409 0.4499490857 0.0043052178 0.0941770000 29081881 955859216 1782697984 -0.3884403110 -0.0869650543 0.0230737776 946 1311867750.1828711033 0.4348692000 0.2786752255 0.4499490857 0.0043034895 0.1106380000 29083711 955859216 1781936128 -0.3880122304 -0.0869922638 0.0228300076 947 1311867750.2156589031 0.4339101017 0.2788391483 0.4499490857 0.0043014303 0.1143180000 29085477 955859216 1777487872 -0.3873985410 -0.0864843205 0.0225511957 948 1311867750.2469079494 0.4350796938 0.2790039590 0.4499490857 0.0043004129 0.1456480000 29087211 955859216 1779146752 -0.3887492716 -0.0863655731 0.0230682343 949 1311867750.2829968929 0.4350938797 0.2791684373 0.4499490857 0.0043002342 0.0955860000 29089041 955859216 1780793344 -0.3891211450 -0.0857534632 0.0233533978 950 1311867750.3150129318 0.4350630045 0.2793325369 0.4499490857 0.0042980206 0.1145100000 29090839 955859216 1782161408 -0.3893916011 -0.0854232311 0.0234535504 951 1311867750.3469090462 0.4333556294 0.2794944960 0.4499490857 0.0042970915 0.0945140000 29092573 955859216 1783922688 -0.3878875971 -0.0856321976 0.0230859388 952 1311867750.3828659058 0.4336110950 0.2796563831 0.4499490857 0.0042949099 0.1151450000 29094403 955859216 1785573376 -0.3882035613 -0.0849788487 0.0232260078 953 1311867750.4148640633 0.4329552948 0.2798172424 0.4499490857 0.0042929826 0.0994930000 29096201 955859216 1784598528 -0.3877711296 -0.0849567652 0.0232961942 954 1311867750.4469859600 0.4324071705 0.2799771900 0.4499490857 0.0042908302 0.0942050000 29097935 955859216 1783840768 -0.3875752091 -0.0852680057 0.0230762213 955 1311867750.4829618931 0.4322758913 0.2801366650 0.4499490857 0.0042893446 0.0942190000 29099733 955859216 1782951936 -0.3875375390 -0.0857491046 0.0226500798 956 1311867750.5148859024 0.4318417311 0.2802953523 0.4499490857 0.0042872077 0.0766630000 29101467 955859216 1781678080 -0.3873438537 -0.0856221840 0.0221441835 957 1311867750.5476069450 0.4313378036 0.2804531814 0.4499490857 0.0042851203 0.0924250000 29103265 955859216 1781047296 -0.3869967759 -0.0859512091 0.0219236016 958 1311867750.5827779770 0.4307183027 0.2806100344 0.4499490857 0.0042853330 0.1307220000 29105095 955859216 1780285440 -0.3866369724 -0.0855666250 0.0217772126 959 1311867750.6148829460 0.4307378829 0.2807665806 0.4499490857 0.0042845663 0.0960560000 29106829 955859216 1779269632 -0.3868964016 -0.0853565484 0.0216245633 960 1311867750.6469810009 0.4303862751 0.2809224345 0.4499490857 0.0042825166 0.0921190000 29108627 955859216 1780867072 -0.3869655132 -0.0853179693 0.0216532797 961 1311867750.6829319000 0.4297749102 0.2810773278 0.4499490857 0.0042834282 0.0922550000 29110457 955859216 1782644736 -0.3867934048 -0.0844883472 0.0216386486 962 1311867750.7149219513 0.4281644821 0.2812302250 0.4499490857 0.0042822939 0.1170260000 29112255 955859216 1784295424 -0.3853630424 -0.0841486007 0.0215259921 963 1311867750.7469151020 0.4282356799 0.2813828787 0.4499490857 0.0042808589 0.0935340000 29113989 955859216 1785962496 -0.3855916858 -0.0843312070 0.0219316632 964 1311867750.7832129002 0.4272236526 0.2815341658 0.4499490857 0.0042817679 0.1197790000 29115787 955859216 1785212928 -0.3848691583 -0.0842993781 0.0221090317 965 1311867750.8149549961 0.4263395667 0.2816842232 0.4499490857 0.0042797095 0.0942760000 29117489 955859216 1784340480 -0.3840806782 -0.0837578699 0.0225892942 966 1311867750.8468461037 0.4261626005 0.2818337867 0.4499490857 0.0042800693 0.1298480000 29119255 955859216 1783451648 -0.3840569556 -0.0837491527 0.0227015633 967 1311867750.8828840256 0.4259017408 0.2819827712 0.4499490857 0.0042779765 0.1303750000 29121117 955859216 1781665792 -0.3839914501 -0.0834323466 0.0225979388 968 1311867750.9147970676 0.4243466258 0.2821298413 0.4499490857 0.0042770436 0.1298380000 29122851 955859216 1783324672 -0.3825101554 -0.0832891092 0.0225980971 969 1311867750.9468770027 0.4246406257 0.2822769112 0.4499490857 0.0042760679 0.1131420000 29124617 955859216 1784950784 -0.3829086721 -0.0830384418 0.0226705801 970 1311867750.9830369949 0.4240771234 0.2824230970 0.4499490857 0.0042742962 0.0986980000 29126479 955859216 1783959552 -0.3825264573 -0.0831887200 0.0225454997 971 1311867751.0168409348 0.4237126708 0.2825686064 0.4499490857 0.0042733803 0.0937960000 29128277 955859216 1783197696 -0.3824732304 -0.0834668651 0.0221377462 972 1311867751.0470340252 0.4230587184 0.2827131435 0.4499490857 0.0042728517 0.1079510000 29130011 955859216 1782308864 -0.3821837604 -0.0835516378 0.0218957085 973 1311867751.0828599930 0.4217325151 0.2828560206 0.4499490857 0.0042706982 0.0942930000 29131809 955859216 1781547008 -0.3811249435 -0.0835171789 0.0213866681 974 1311867751.1174809933 0.4211405218 0.2829979964 0.4499490857 0.0042685769 0.1167900000 29133639 955859216 1780785152 -0.3808706105 -0.0837800056 0.0210314393 975 1311867751.1468789577 0.4214151204 0.2831399627 0.4499490857 0.0042698904 0.1115760000 29135341 955859216 1782411264 -0.3812507987 -0.0835749805 0.0206140876 976 1311867751.1835930347 0.4202619791 0.2832804566 0.4499490857 0.0042692342 0.0958510000 29137203 955859216 1784041472 -0.3806054592 -0.0834161192 0.0204130262 977 1311867751.2161049843 0.4207147360 0.2834211263 0.4499490857 0.0042674893 0.0956740000 29138969 955859216 1785692160 -0.3813390732 -0.0832626373 0.0202230364 978 1311867751.2468481064 0.4217126966 0.2835625287 0.4499490857 0.0042674404 0.0990940000 29140703 955859216 1784991744 -0.3822813630 -0.0833453536 0.0201020539 979 1311867751.2831909657 0.4213151336 0.2837032362 0.4499490857 0.0042687141 0.0940880000 29142565 955859216 1783832576 -0.3821543157 -0.0825255215 0.0199563503 980 1311867751.3149859905 0.4206813276 0.2838430097 0.4499490857 0.0042665979 0.0948380000 29144299 955859216 1783070720 -0.3816521764 -0.0823212937 0.0199438334 981 1311867751.3498640060 0.4210440218 0.2839828680 0.4499490857 0.0042646936 0.1108700000 29146129 955859216 1781927936 -0.3823285103 -0.0827593207 0.0196975749 982 1311867751.3834669590 0.4210521877 0.2841224498 0.4499490857 0.0042628461 0.0959510000 29147927 955859216 1781166080 -0.3826522827 -0.0825741887 0.0191559196 983 1311867751.4151160717 0.4205541313 0.2842612410 0.4499490857 0.0042626903 0.0939910000 29149693 955859216 1777582080 -0.3819149733 -0.0825381353 0.0187204033 984 1311867751.4513890743 0.4197469056 0.2843989296 0.4499490857 0.0042633306 0.0915270000 29151491 955859216 1778626560 -0.3815381825 -0.0829550996 0.0183842499 985 1311867751.4838130474 0.4193082154 0.2845358934 0.4499490857 0.0042612313 0.0954090000 29153289 955859216 1777864704 -0.3809348047 -0.0830880851 0.0177677125 986 1311867751.5149779320 0.4187920094 0.2846720558 0.4499490857 0.0042605462 0.1095610000 29155055 955859216 1777102848 -0.3808330595 -0.0829009861 0.0177336801 987 1311867751.5495769978 0.4177713394 0.2848069081 0.4499490857 0.0042588716 0.1156890000 29156853 955859216 1776087040 -0.3800114095 -0.0830141678 0.0176683348 988 1311867751.5829720497 0.4159306884 0.2849396245 0.4499490857 0.0042576100 0.0958310000 29158619 955859216 1777692672 -0.3779026866 -0.0828228965 0.0175542813 989 1311867751.6149520874 0.4151451886 0.2850712783 0.4499490857 0.0042561756 0.1146970000 29160385 955859216 1779343360 -0.3772289157 -0.0828665942 0.0173873305 990 1311867751.6501350403 0.4135513306 0.2852010561 0.4499490857 0.0042548494 0.0939450000 29162183 955859216 1781141504 -0.3761226833 -0.0830974355 0.0170351863 991 1311867751.6839730740 0.4135044813 0.2853305247 0.4499490857 0.0042527073 0.0942700000 29164013 955859216 1782771712 -0.3761784732 -0.0832859576 0.0168824214 992 1311867751.7150709629 0.4123120606 0.2854585303 0.4499490857 0.0042515415 0.1186110000 29165715 955859216 1784422400 -0.3750971258 -0.0833784565 0.0165524650 993 1311867751.7507519722 0.4113011956 0.2855852601 0.4499490857 0.0042495245 0.0981000000 29167545 955859216 1783730176 -0.3743436933 -0.0838405341 0.0164239574 994 1311867751.7830109596 0.4111594856 0.2857115923 0.4499490857 0.0042484553 0.1076160000 29169311 955859216 1782824960 -0.3744412363 -0.0838488713 0.0162275452 995 1311867751.8149600029 0.4102312922 0.2858367377 0.4499490857 0.0042477068 0.0846140000 29171077 955859216 1781936128 -0.3736124337 -0.0839468986 0.0161609948 996 1311867751.8509531021 0.4090250432 0.2859604208 0.4499490857 0.0042466367 0.1326820000 29172907 955859216 1781174272 -0.3726073802 -0.0838563070 0.0158912987 997 1311867751.8832330704 0.4088580012 0.2860836882 0.4499490857 0.0042455271 0.1494500000 29174673 955859216 1779904512 -0.3727649748 -0.0841234326 0.0159384757 998 1311867751.9149179459 0.4089518785 0.2862068026 0.4499490857 0.0042462357 0.1096630000 29176407 955859216 1775689728 -0.3733111620 -0.0837526545 0.0158887971 999 1311867751.9530611038 0.4076296687 0.2863283470 0.4499490857 0.0042444442 0.0951200000 29178301 955859216 1774026752 -0.3722126186 -0.0838682577 0.0156451184 1000 1311867751.9829521179 0.4087106586 0.2864507293 0.4499490857 0.0042439713 0.1291160000 29180035 955859216 1775697920 -0.3735489547 -0.0841806456 0.0158811361 1001 1311867752.0153670311 0.4082295299 0.2865723865 0.4499490857 0.0042449632 0.0950560000 29181769 955859216 1777381376 -0.3734354079 -0.0838286355 0.0157981962 1002 1311867752.0510330200 0.4069644511 0.2866925382 0.4499490857 0.0042440811 0.1370510000 29183599 955859216 1778843648 -0.3721354306 -0.0837811977 0.0156983268 1003 1311867752.0828928947 0.4052709043 0.2868107619 0.4499490857 0.0042427739 0.0912400000 29185397 955859216 1780494336 -0.3707103133 -0.0842427760 0.0154747078 1004 1311867752.1150529385 0.4033261240 0.2869268131 0.4499490857 0.0042407392 0.0940910000 29187131 955859216 1782161408 -0.3687029481 -0.0846990645 0.0149760693 1005 1311867752.1509859562 0.4023182988 0.2870416305 0.4499490857 0.0042397479 0.1171450000 29188961 955859216 1783922688 -0.3683938980 -0.0846485943 0.0146709830 1006 1311867752.1829679012 0.4026247859 0.2871565243 0.4499490857 0.0042406203 0.1138210000 29190759 955859216 1785573376 -0.3690933883 -0.0848044828 0.0145195872 1007 1311867752.2150039673 0.4031071365 0.2872716689 0.4499490857 0.0042393884 0.0998950000 29192525 955859216 1784598528 -0.3700595796 -0.0847352222 0.0143337250 1008 1311867752.2512340546 0.4027679861 0.2873862485 0.4499490857 0.0042385844 0.0949750000 29194323 955859216 1783730176 -0.3697752655 -0.0845397338 0.0142425979 1009 1311867752.2833271027 0.4032292962 0.2875010583 0.4499490857 0.0042377711 0.0926970000 29196089 955859216 1783078912 -0.3704077601 -0.0843817368 0.0143962950 1010 1311867752.3150799274 0.4015288353 0.2876139571 0.4499490857 0.0042381537 0.1085910000 29197823 955859216 1782206464 -0.3691513240 -0.0842782483 0.0140876248 1011 1311867752.3509979248 0.4019042253 0.2877270038 0.4499490857 0.0042385102 0.0912680000 29199653 955859216 1781428224 -0.3693277836 -0.0842851400 0.0142818689 1012 1311867752.3829851151 0.4019577503 0.2878398801 0.4499490857 0.0042365409 0.0911570000 29201451 955859216 1779773440 -0.3694502413 -0.0845867693 0.0142505970 1013 1311867752.4160280228 0.4000942707 0.2879506939 0.4499490857 0.0042349496 0.1095810000 29203217 955859216 1779142656 -0.3676081598 -0.0849955454 0.0138053671 1014 1311867752.4510710239 0.3998492956 0.2880610475 0.4499490857 0.0042406160 0.1188670000 29205047 955859216 1778380800 -0.3676840961 -0.0851590261 0.0136946160 1015 1311867752.4829080105 0.3997248709 0.2881710612 0.4499490857 0.0042405278 0.0915270000 29206813 955859216 1777618944 -0.3674061596 -0.0854660347 0.0134642050 1016 1311867752.5181159973 0.3988235593 0.2882799711 0.4499490857 0.0042404376 0.0914300000 29208611 955859216 1776349184 -0.3667600751 -0.0857282728 0.0130669773 1017 1311867752.5511059761 0.3984054029 0.2883882557 0.4499490857 0.0042402076 0.0988210000 29210377 955859216 1773293568 -0.3661217093 -0.0858971179 0.0128392726 1018 1311867752.5830090046 0.3978832960 0.2884958147 0.4499490857 0.0042383402 0.1080210000 29212175 955859216 1774317568 -0.3658998013 -0.0855572149 0.0125804469 1019 1311867752.6167891026 0.3972350657 0.2886025264 0.4499490857 0.0042366148 0.0945380000 29213941 955859216 1773301760 -0.3651073575 -0.0857486874 0.0121160969 1020 1311867752.6514921188 0.3969373405 0.2887087370 0.4499490857 0.0042368513 0.1183570000 29215739 955859216 1772556288 -0.3646658957 -0.0859199986 0.0120177045 1021 1311867752.6830079556 0.3973556459 0.2888151492 0.4499490857 0.0042389832 0.1114030000 29217505 955859216 1774292992 -0.3650895953 -0.0860533565 0.0117465109 1022 1311867752.7152869701 0.3955182433 0.2889195554 0.4499490857 0.0042412419 0.0972970000 29219303 955859216 1775923200 -0.3631401658 -0.0863817558 0.0111416504 1023 1311867752.7510609627 0.3957608938 0.2890239946 0.4499490857 0.0042393121 0.1153690000 29221069 955859216 1777573888 -0.3634333313 -0.0869163573 0.0108306408 1024 1311867752.7830440998 0.3949867785 0.2891274739 0.4499490857 0.0042461680 0.0967900000 29222867 955859216 1779372032 -0.3626754582 -0.0871177539 0.0102013489 1025 1311867752.8162839413 0.3939587176 0.2892297483 0.4499490857 0.0042441174 0.0916990000 29306553 955859216 1781129216 -0.3615783453 -0.0869982615 0.0096421773 1026 1311867752.8511059284 0.3935795128 0.2893314537 0.4499490857 0.0042420983 0.0943140000 29476287 955859216 1782906880 -0.3610631227 -0.0866569877 0.0091997236 1027 1311867752.8833000660 0.3936478496 0.2894330276 0.4499490857 0.0042405577 0.0970170000 29478085 955859216 1784684544 -0.3611868024 -0.0863240436 0.0091126328 1028 1311867752.9183809757 0.3925127983 0.2895332998 0.4499490857 0.0042385852 0.0966490000 29479915 955859216 1783951360 -0.3595564067 -0.0860040933 0.0088066822 1029 1311867752.9511129856 0.3923422396 0.2896332113 0.4499490857 0.0042412615 0.1339650000 29481649 955859216 1783078912 -0.3594065309 -0.0859781429 0.0086151967 1030 1311867752.9828579426 0.3918929994 0.2897324926 0.4499490857 0.0042398120 0.1131030000 29483447 955859216 1778851840 -0.3589626551 -0.0860129669 0.0083635682 1031 1311867753.0168170929 0.3911421299 0.2898308531 0.4499490857 0.0042378589 0.0906890000 29485213 955859216 1780535296 -0.3579482436 -0.0861875340 0.0080418596 1032 1311867753.0510199070 0.3914454877 0.2899293169 0.4499490857 0.0042358162 0.1131050000 29487011 955859216 1782190080 -0.3582817614 -0.0863164365 0.0075242883 1033 1311867753.0829060078 0.3910169601 0.2900271752 0.4499490857 0.0042365109 0.0967090000 29488745 955859216 1783541760 -0.3579832315 -0.0862510204 0.0070931986 1034 1311867753.1184310913 0.3901582360 0.2901240138 0.4499490857 0.0042345945 0.0958750000 29490607 955859216 1785339904 -0.3570839167 -0.0859414563 0.0065913042 1035 1311867753.1510760784 0.3900270164 0.2902205384 0.4499490857 0.0042326054 0.0976620000 29492341 955859216 1784221696 -0.3570732772 -0.0859991014 0.0062394738 1036 1311867753.1830070019 0.3893393874 0.2903162130 0.4499490857 0.0042317198 0.0956520000 29494075 955859216 1783459840 -0.3566712439 -0.0862600207 0.0060325190 1037 1311867753.2186999321 0.3882508576 0.2904106533 0.4499490857 0.0042311954 0.1043180000 29495937 955859216 1782444032 -0.3556222022 -0.0857850090 0.0057573249 1038 1311867753.2520470619 0.3867364526 0.2905034527 0.4499490857 0.0042292483 0.0728090000 29497671 955859216 1781555200 -0.3542831540 -0.0852480233 0.0055541848 1039 1311867753.2829909325 0.3862228990 0.2905955793 0.4499490857 0.0042272610 0.0833550000 29499437 955859216 1780793344 -0.3542010486 -0.0852236599 0.0053861588 1040 1311867753.3196740150 0.3845050037 0.2906858768 0.4499490857 0.0042302455 0.0961610000 29501299 955859216 1779777536 -0.3530621827 -0.0842883140 0.0048119649 1041 1311867753.3509368896 0.3828831613 0.2907744429 0.4499490857 0.0042284299 0.1311460000 29503001 955859216 1779015680 -0.3516380787 -0.0838659778 0.0047109276 1042 1311867753.3829340935 0.3832277358 0.2908631696 0.4499490857 0.0042270789 0.1180770000 29504799 955859216 1777745920 -0.3524798751 -0.0838287771 0.0045240368 1043 1311867753.4182109833 0.3839467168 0.2909524156 0.4499490857 0.0042262038 0.1333800000 29506629 955859216 1776984064 -0.3535911739 -0.0835779235 0.0043549836 1044 1311867753.4511721134 0.3831217289 0.2910407004 0.4499490857 0.0042250802 0.0909600000 29508363 955859216 1776222208 -0.3533685803 -0.0829978660 0.0038439929 1045 1311867753.4831509590 0.3821205795 0.2911278582 0.4499490857 0.0042238022 0.0934530000 29510161 955859216 1774952448 -0.3530078828 -0.0830471441 0.0031443015 1046 1311867753.5199849606 0.3816662133 0.2912144149 0.4499490857 0.0042226789 0.1327480000 29512023 955859216 1773936640 -0.3533541262 -0.0826031342 0.0025936887 1047 1311867753.5532789230 0.3809657991 0.2913001373 0.4499490857 0.0042208938 0.1146630000 29513789 955859216 1771241472 -0.3534032702 -0.0825045258 0.0020406991 1048 1311867753.5832290649 0.3806307018 0.2913853764 0.4499490857 0.0042196630 0.1302080000 29515523 955859216 1771778048 -0.3537308872 -0.0822414309 0.0017331690 1049 1311867753.6183180809 0.3789142966 0.2914688168 0.4499490857 0.0042186698 0.1076560000 29517353 955859216 1770778624 -0.3528929353 -0.0817112103 0.0012658685 1050 1311867753.6509299278 0.3781720102 0.2915513912 0.4499490857 0.0042167087 0.1184140000 29519119 955859216 1770127360 -0.3527646661 -0.0813927650 0.0012375565 1051 1311867753.6830120087 0.3768332005 0.2916325347 0.4499490857 0.0042147501 0.1117000000 29520853 955859216 1771732992 -0.3518866301 -0.0811113566 0.0009347796 1052 1311867753.7204821110 0.3764112890 0.2917131229 0.4499490857 0.0042129457 0.0940300000 29522747 955859216 1773531136 -0.3518921137 -0.0808866918 0.0007481724 1053 1311867753.7510209084 0.3757748008 0.2917929535 0.4499490857 0.0042113502 0.0965840000 29524449 955859216 1775161344 -0.3520569205 -0.0805338845 0.0006878302 1054 1311867753.7865459919 0.3732475340 0.2918702349 0.4499490857 0.0042135442 0.0956900000 29526279 955859216 1776812032 -0.3504182100 -0.0805419013 0.0004603937 1055 1311867753.8151860237 0.3735052049 0.2919476140 0.4499490857 0.0042152193 0.0957110000 29527981 955859216 1778610176 -0.3507630229 -0.0797698647 0.0004716516 1056 1311867753.8510670662 0.3724598289 0.2920238567 0.4499490857 0.0042169390 0.0957420000 29529811 955859216 1780240384 -0.3507253230 -0.0791477114 0.0004722923 1057 1311867753.8831698895 0.3714786470 0.2920990268 0.4499490857 0.0042209611 0.0971830000 29531609 955859216 1781891072 -0.3502542078 -0.0798388943 0.0003526509 1058 1311867753.9155960083 0.3710442781 0.2921736442 0.4499490857 0.0042205090 0.0959330000 29533343 955859216 1783668736 -0.3504681587 -0.0795751438 0.0002344176 1059 1311867753.9511620998 0.3716518283 0.2922486944 0.4499490857 0.0042221162 0.0962140000 29535173 955859216 1785319424 -0.3518192470 -0.0787127018 0.0004707276 1060 1311867753.9859020710 0.3712507188 0.2923232246 0.4499490857 0.0042205884 0.0981490000 29537003 955859216 1784594432 -0.3522707224 -0.0783706084 0.0005046725 1061 1311867754.0151760578 0.3694638312 0.2923959302 0.4499490857 0.0042197442 0.0926860000 29538705 955859216 1783459840 -0.3517383933 -0.0781696439 0.0005159453 1062 1311867754.0510439873 0.3692977726 0.2924683425 0.4499490857 0.0042270272 0.0942070000 29540567 955859216 1782571008 -0.3522616923 -0.0778424591 0.0008345023 1063 1311867754.0839149952 0.3681856692 0.2925395723 0.4499490857 0.0042261874 0.0942020000 29542333 955859216 1781555200 -0.3519043326 -0.0770827532 0.0009593964 1064 1311867754.1166028976 0.3679247499 0.2926104231 0.4499490857 0.0042242224 0.0957200000 29544099 955859216 1780793344 -0.3525942564 -0.0769157708 0.0012666284 1065 1311867754.1511039734 0.3674158156 0.2926806629 0.4499490857 0.0042313046 0.0944270000 29545865 955859216 1780031488 -0.3528402746 -0.0764698237 0.0014476181 1066 1311867754.1832261086 0.3667224348 0.2927501204 0.4499490857 0.0042301241 0.0932630000 29547663 955859216 1779015680 -0.3529388905 -0.0755523592 0.0018159747 1067 1311867754.2166349888 0.3641858995 0.2928170706 0.4499490857 0.0042343770 0.1101920000 29549429 955859216 1777999872 -0.3517236710 -0.0754075497 0.0018724874 1068 1311867754.2522869110 0.3636743128 0.2928834163 0.4499490857 0.0042367464 0.0931780000 29551259 955859216 1777364992 -0.3522326946 -0.0759415552 0.0021836089 1069 1311867754.2873370647 0.3634227216 0.2929494026 0.4499490857 0.0042505189 0.1180200000 29553089 955859216 1776095232 -0.3533211648 -0.0753869489 0.0022733286 1070 1311867754.3188319206 0.3650160730 0.2930167546 0.4499490857 0.0042489796 0.1084430000 29554855 955859216 1775079424 -0.3560709059 -0.0753350481 0.0025689823 1071 1311867754.3511719704 0.3660181165 0.2930849164 0.4499490857 0.0042548530 0.0983210000 29556621 955859216 1774317568 -0.3581458926 -0.0755270198 0.0028312393 1072 1311867754.3868899345 0.3677642941 0.2931545800 0.4499490857 0.0042539988 0.1105760000 29558419 955859216 1769988096 -0.3609746993 -0.0750152618 0.0030672143 1073 1311867754.4159760475 0.3674179018 0.2932237910 0.4499490857 0.0042535344 0.0906860000 29560185 955859216 1771663360 -0.3611790538 -0.0745726004 0.0032575279 1074 1311867754.4545960426 0.3675884008 0.2932930318 0.4499490857 0.0042599101 0.0935200000 29562015 955859216 1773412352 -0.3623743355 -0.0746140480 0.0037206302 1075 1311867754.4863700867 0.3681845367 0.2933626983 0.4499490857 0.0042743096 0.0949960000 29563781 955859216 1774780416 -0.3634482920 -0.0749842152 0.0041423035 1076 1311867754.5164580345 0.3696154356 0.2934335651 0.4499490857 0.0042752136 0.1117460000 29565515 955859216 1776431104 -0.3652973473 -0.0753038377 0.0045822859 1077 1311867754.5513699055 0.3698354661 0.2935045047 0.4499490857 0.0042748114 0.1327120000 29567281 955859216 1778229248 -0.3659251034 -0.0749844313 0.0049304371 1078 1311867754.5835940838 0.3704627752 0.2935758946 0.4499490857 0.0042749758 0.1106730000 29569079 955859216 1779859456 -0.3669703603 -0.0757167265 0.0051521026 1079 1311867754.6154909134 0.3706076145 0.2936472863 0.4499490857 0.0042740208 0.0968850000 29570813 955859216 1781510144 -0.3675195277 -0.0759110972 0.0054162182 1080 1311867754.6510920525 0.3704761863 0.2937184242 0.4499490857 0.0042722130 0.0964690000 29572611 955859216 1783287808 -0.3678116500 -0.0754964426 0.0056139603 1081 1311867754.6872758865 0.3700245321 0.2937890126 0.4499490857 0.0042716200 0.0946040000 29574441 955859216 1784938496 -0.3678758740 -0.0757789165 0.0057066535 1082 1311867754.7162959576 0.3698762357 0.2938593335 0.4499490857 0.0042696850 0.0982740000 29576143 955859216 1783971840 -0.3679535091 -0.0764109045 0.0059122927 1083 1311867754.7516000271 0.3690672219 0.2939287776 0.4499490857 0.0042693189 0.0966340000 29577973 955859216 1783078912 -0.3675147295 -0.0758371726 0.0062874183 1084 1311867754.7865269184 0.3676947355 0.2939968274 0.4499490857 0.0042682224 0.0929670000 29579771 955859216 1782054912 -0.3666423559 -0.0754992589 0.0064419587 1085 1311867754.8154470921 0.3665718734 0.2940637168 0.4499490857 0.0042673626 0.0912510000 29581473 955859216 1781039104 -0.3659528792 -0.0761394203 0.0063984804 1086 1311867754.8510210514 0.3653499484 0.2941293579 0.4499490857 0.0042791854 0.0948440000 29583303 955859216 1780277248 -0.3655432165 -0.0761043206 0.0065720901 1087 1311867754.8877389431 0.3641349077 0.2941937604 0.4499490857 0.0042779317 0.0926460000 29585165 955859216 1779261440 -0.3650222421 -0.0763010606 0.0065843873 1088 1311867754.9201259613 0.3639492691 0.2942578739 0.4499490857 0.0042759980 0.0947320000 29586931 955859216 1778245632 -0.3654938936 -0.0773867741 0.0065287389 1089 1311867754.9510319233 0.3629220128 0.2943209264 0.4499490857 0.0042752290 0.0913570000 29588665 955859216 1777483776 -0.3650934696 -0.0777007267 0.0065566255 1090 1311867754.9837870598 0.3610999584 0.2943821916 0.4499490857 0.0042755057 0.0897020000 29590463 955859216 1776340992 -0.3644340932 -0.0771766976 0.0068145287 1091 1311867755.0183880329 0.3596349061 0.2944420016 0.4499490857 0.0042741866 0.0937190000 29592261 955859216 1775325184 -0.3636521399 -0.0767625943 0.0072106780 1092 1311867755.0540831089 0.3586503565 0.2945008004 0.4499490857 0.0042746886 0.0938810000 29594091 955859216 1774309376 -0.3632166982 -0.0768477991 0.0076870364 1093 1311867755.0850980282 0.3583931029 0.2945592563 0.4499490857 0.0042752896 0.0947290000 29595857 955859216 1773547520 -0.3633519113 -0.0768144503 0.0080253417 1094 1311867755.1156959534 0.3585553765 0.2946177537 0.4499490857 0.0042787038 0.1087960000 29597559 955859216 1772548096 -0.3640533984 -0.0769965872 0.0083542624 1095 1311867755.1556220055 0.3579832017 0.2946756217 0.4499490857 0.0042768300 0.0934950000 29599453 955859216 1771642880 -0.3641353250 -0.0771415234 0.0085372338 1096 1311867755.1847031116 0.3580503464 0.2947334454 0.4499490857 0.0042754199 0.1153270000 29601219 955859216 1770627072 -0.3647073209 -0.0776596665 0.0085995989 1097 1311867755.2151238918 0.3578372300 0.2947909693 0.4499490857 0.0042736417 0.1089390000 29602921 955859216 1772122112 -0.3649671674 -0.0770506933 0.0088023525 1098 1311867755.2512340546 0.3572143018 0.2948478212 0.4499490857 0.0042735307 0.0933240000 29604751 955859216 1773883392 -0.3650286496 -0.0773007870 0.0089293206 1099 1311867755.2832889557 0.3573871553 0.2949047268 0.4499490857 0.0042726592 0.0960000000 29606517 955859216 1775534080 -0.3655223846 -0.0786924362 0.0087295845 1100 1311867755.3192110062 0.3574084342 0.2949615484 0.4499490857 0.0042719914 0.0947800000 29608347 955859216 1777332224 -0.3658584654 -0.0788631141 0.0086000841 1101 1311867755.3553090096 0.3565121591 0.2950174527 0.4499490857 0.0042703779 0.0960140000 29610209 955859216 1778962432 -0.3655293286 -0.0789374486 0.0082431734 1102 1311867755.3900220394 0.3569285274 0.2950736333 0.4499490857 0.0042685969 0.0952270000 29611975 955859216 1780613120 -0.3662851155 -0.0804399475 0.0078719584 1103 1311867755.4156589508 0.3575536013 0.2951302788 0.4499490857 0.0042689898 0.0953990000 29613677 955859216 1782411264 -0.3671861291 -0.0802748054 0.0077601993 1104 1311867755.4549160004 0.3566736281 0.2951860246 0.4499490857 0.0042676526 0.0946410000 29615539 955859216 1784041472 -0.3670209944 -0.0797139555 0.0077523780 1105 1311867755.4860870838 0.3569013476 0.2952418756 0.4499490857 0.0042658002 0.0798490000 29617273 955859216 1785692160 -0.3675847352 -0.0806947201 0.0077507868 1106 1311867755.5161950588 0.3566205502 0.2952973717 0.4499490857 0.0042644162 0.1163520000 29618975 955859216 1784848384 -0.3674786985 -0.0805693418 0.0078717526 1107 1311867755.5550999641 0.3560864627 0.2953522850 0.4499490857 0.0042625395 0.0929850000 29620869 955859216 1783832576 -0.3672779500 -0.0800741389 0.0079070581 1108 1311867755.5854589939 0.3562330306 0.2954072315 0.4499490857 0.0042606774 0.1159480000 29622635 955859216 1782689792 -0.3676504493 -0.0797045082 0.0078952089 1109 1311867755.6171119213 0.3556854427 0.2954615852 0.4499490857 0.0042593700 0.0882530000 29624369 955859216 1781673984 -0.3673946559 -0.0791514590 0.0077473749 1110 1311867755.6542940140 0.3555573821 0.2955157256 0.4499490857 0.0042576313 0.0918370000 29626231 955859216 1780674560 -0.3674711287 -0.0789273977 0.0077466145 1111 1311867755.6831719875 0.3558315337 0.2955700152 0.4499490857 0.0042557929 0.1163710000 29627933 955859216 1779769344 -0.3680145144 -0.0793835297 0.0074011041 1112 1311867755.7182741165 0.3554815054 0.2956238924 0.4499490857 0.0042541496 0.0929210000 29629763 955859216 1781248000 -0.3680401146 -0.0799099952 0.0069467500 1113 1311867755.7511448860 0.3559119701 0.2956780596 0.4499490857 0.0042531019 0.1125410000 29631529 955859216 1782898688 -0.3687855005 -0.0802005231 0.0064291358 1114 1311867755.7863750458 0.3556830287 0.2957319241 0.4499490857 0.0042512470 0.0946720000 29633327 955859216 1784565760 -0.3688313663 -0.0800594240 0.0060164863 1115 1311867755.8156878948 0.3547329605 0.2957848398 0.4499490857 0.0042494918 0.0985260000 29635093 955859216 1783705600 -0.3679748178 -0.0807372183 0.0058132471 1116 1311867755.8554079533 0.3538953662 0.2958369102 0.4499490857 0.0042490593 0.0956020000 29636923 955859216 1780121600 -0.3674232662 -0.0800041929 0.0058109560 1117 1311867755.8848359585 0.3535682559 0.2958885944 0.4499490857 0.0042474156 0.0871870000 29638689 955859216 1781288960 -0.3674834073 -0.0794412941 0.0058268476 1118 1311867755.9156229496 0.3531862497 0.2959398446 0.4499490857 0.0042463241 0.0932480000 29640455 955859216 1780277248 -0.3672921956 -0.0802169219 0.0055603497 1119 1311867755.9550359249 0.3530451357 0.2959908770 0.4499490857 0.0042461079 0.0954590000 29642285 955859216 1779277824 -0.3674989045 -0.0796575174 0.0056763534 1120 1311867755.9855198860 0.3528631926 0.2960416559 0.4499490857 0.0042453698 0.0929520000 29644019 955859216 1778262016 -0.3674318194 -0.0793316364 0.0057788682 1121 1311867756.0173881054 0.3531986475 0.2960926434 0.4499490857 0.0042436233 0.0939400000 29645753 955859216 1773903872 -0.3678752482 -0.0798624828 0.0057781623 1122 1311867756.0554430485 0.3527384102 0.2961431298 0.4499490857 0.0042425665 0.0936880000 29647583 955859216 1772261376 -0.3675158918 -0.0796422064 0.0058865864 1123 1311867756.0835959911 0.3525437415 0.2961933529 0.4499490857 0.0042409338 0.0912810000 29649317 955859216 1773932544 -0.3675077558 -0.0790769532 0.0059530055 1124 1311867756.1196908951 0.3527936339 0.2962437091 0.4499490857 0.0042407728 0.1064190000 29651147 955859216 1775579136 -0.3676458597 -0.0799126476 0.0058921617 1125 1311867756.1519339085 0.3523578346 0.2962935883 0.4499490857 0.0042389505 0.0957490000 29652817 955859216 1776930816 -0.3672008812 -0.0799307376 0.0058435020 1126 1311867756.1836869717 0.3526419103 0.2963436312 0.4499490857 0.0042375117 0.0791090000 29654519 955859216 1778708480 -0.3676033616 -0.0793529749 0.0059633236 1127 1311867756.2230648994 0.3531330824 0.2963940211 0.4499490857 0.0042402793 0.0936950000 29656285 955859216 1780486144 -0.3678795993 -0.0800671205 0.0061731320 1128 1311867756.2552509308 0.3528078198 0.2964440334 0.4499490857 0.0042421258 0.0952040000 29658051 955859216 1782136832 -0.3675254285 -0.0801224560 0.0061623547 1129 1311867756.2851591110 0.3529301584 0.2964940654 0.4499490857 0.0042416723 0.0966700000 29659817 955859216 1783803904 -0.3675454557 -0.0793283656 0.0064190351 1130 1311867756.3200058937 0.3526014090 0.2965437179 0.4499490857 0.0042407262 0.0923270000 29661615 955859216 1785565184 -0.3671470881 -0.0792125687 0.0063618775 1131 1311867756.3546419144 0.3530736864 0.2965937002 0.4499490857 0.0042390543 0.0974100000 29663445 955859216 1784590336 -0.3674266934 -0.0798106194 0.0063775936 1132 1311867756.3843090534 0.3532513678 0.2966437511 0.4499490857 0.0042376378 0.0942370000 29665147 955859216 1783451648 -0.3676364422 -0.0796022490 0.0065357243 1133 1311867756.4231688976 0.3528332710 0.2966933447 0.4499490857 0.0042360315 0.0939010000 29666977 955859216 1782435840 -0.3670646250 -0.0795103982 0.0066809393 1134 1311867756.4510979652 0.3529633284 0.2967429655 0.4499490857 0.0042345929 0.0934930000 29668647 955859216 1781420032 -0.3670819402 -0.0802109540 0.0067949169 1135 1311867756.4865350723 0.3526930511 0.2967922607 0.4499490857 0.0042380480 0.0939220000 29670509 955859216 1780404224 -0.3668130636 -0.0799691528 0.0069499523 1136 1311867756.5264549255 0.3531260788 0.2968418503 0.4499490857 0.0042369250 0.0934230000 29672371 955859216 1779388416 -0.3670048118 -0.0802826509 0.0071581397 1137 1311867756.5525779724 0.3529427946 0.2968911915 0.4499490857 0.0042351826 0.1073560000 29674073 955859216 1778626560 -0.3666528165 -0.0805850178 0.0072695715 1138 1311867756.5897810459 0.3525502384 0.2969401011 0.4499490857 0.0042335523 0.0973950000 29675935 955859216 1777864704 -0.3661373556 -0.0805623755 0.0073689334 1139 1311867756.6202929020 0.3529944718 0.2969893147 0.4499490857 0.0042318297 0.1350240000 29677637 955859216 1776594944 -0.3664533496 -0.0809335262 0.0074065886 1140 1311867756.6518390179 0.3531844020 0.2970386087 0.4499490857 0.0042299727 0.1099480000 29679403 955859216 1775579136 -0.3665506542 -0.0814565793 0.0077231620 1141 1311867756.6839349270 0.3525110185 0.2970872260 0.4499490857 0.0042288775 0.0936150000 29681137 955859216 1774563328 -0.3659732342 -0.0813342407 0.0079221865 1142 1311867756.7217059135 0.3522863686 0.2971355615 0.4499490857 0.0042298745 0.0907420000 29682967 955859216 1771995136 -0.3659190834 -0.0811848119 0.0081968317 1143 1311867756.7516939640 0.3521102071 0.2971836584 0.4499490857 0.0042282979 0.0938260000 29684701 955859216 1772150784 -0.3657123446 -0.0815356970 0.0083121760 1144 1311867756.7872660160 0.3519368470 0.2972315195 0.4499490857 0.0042265295 0.0930760000 29686531 955859216 1771261952 -0.3654690385 -0.0817945600 0.0083731310 1145 1311867756.8227219582 0.3518247902 0.2972791992 0.4499490857 0.0042247097 0.0938470000 29688361 955859216 1770246144 -0.3655241430 -0.0814210847 0.0085961306 1146 1311867756.8542120457 0.3517542183 0.2973267342 0.4499490857 0.0042322512 0.0936980000 29690095 955859216 1769357312 -0.3653504252 -0.0820674524 0.0087815505 1147 1311867756.8841960430 0.3517505527 0.2973741830 0.4499490857 0.0042404858 0.0932670000 29691861 955859216 1768341504 -0.3655528128 -0.0820638388 0.0091012884 1148 1311867756.9223539829 0.3509503305 0.2974208521 0.4499490857 0.0042397366 0.1087120000 29693691 955859216 1767452672 -0.3648962677 -0.0824214667 0.0092261704 1149 1311867756.9552440643 0.3512393832 0.2974676916 0.4499490857 0.0042380861 0.1082230000 29695489 955859216 1763635200 -0.3651968539 -0.0830271617 0.0092577552 1150 1311867756.9841780663 0.3507758677 0.2975140465 0.4499490857 0.0042365840 0.1089670000 29697191 955859216 1765294080 -0.3648804426 -0.0826465189 0.0093371309 1151 1311867757.0282740593 0.3504672647 0.2975600528 0.4499490857 0.0042373683 0.0917940000 29699149 955859216 1766899712 -0.3648549318 -0.0831238851 0.0094328048 1152 1311867757.0552940369 0.3508294523 0.2976062936 0.4499490857 0.0042357755 0.0944660000 29700851 955859216 1768677376 -0.3650731444 -0.0839197561 0.0093628149 1153 1311867757.0858569145 0.3506895602 0.2976523328 0.4499490857 0.0042343054 0.0930110000 29702585 955859216 1770455040 -0.3650007844 -0.0835890919 0.0094681606 1154 1311867757.1283040047 0.3505121171 0.2976981385 0.4499490857 0.0042402381 0.0953370000 29704479 955859216 1772105728 -0.3648374081 -0.0844958127 0.0093928147 1155 1311867757.1522068977 0.3509407938 0.2977442361 0.4499490857 0.0042394592 0.0950760000 29706085 955859216 1773772800 -0.3650604486 -0.0858497471 0.0091786114 1156 1311867757.1851921082 0.3517386317 0.2977909440 0.4499490857 0.0042377666 0.0963040000 29707883 955859216 1775529984 -0.3657378256 -0.0857641026 0.0092717269 1157 1311867757.2192370892 0.3527050316 0.2978384065 0.4499490857 0.0042369918 0.0942260000 29709713 955859216 1777184768 -0.3665139377 -0.0864629447 0.0091111949 1158 1311867757.2523930073 0.3533551395 0.2978863484 0.4499490857 0.0042541736 0.0951220000 29711479 955859216 1778982912 -0.3668108582 -0.0876703411 0.0086191352 1159 1311867757.2835690975 0.3534863889 0.2979343208 0.4499490857 0.0042555914 0.0951970000 29713213 955859216 1780613120 -0.3669111729 -0.0870693773 0.0082988562 1160 1311867757.3233768940 0.3544420898 0.2979830344 0.4499490857 0.0042639812 0.0942230000 29715107 955859216 1782263808 -0.3674653172 -0.0865319893 0.0081125116 1161 1311867757.3555359840 0.3553356230 0.2980324337 0.4499490857 0.0042622573 0.0951650000 29716905 955859216 1784041472 -0.3682552874 -0.0871004239 0.0080972975 1162 1311867757.3833439350 0.3559003174 0.2980822340 0.4499490857 0.0042615578 0.0965960000 29718575 955859216 1785692160 -0.3688241243 -0.0865838155 0.0083638225 1163 1311867757.4264349937 0.3563542366 0.2981323389 0.4499490857 0.0042629147 0.0810500000 29720469 955859216 1784459264 -0.3688620031 -0.0882461816 0.0078760032 ================================================ FILE: icra2018_results/tegra/violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 06:17:46 Properties: ================= frame-limit: 0 log-file: output//violons_libinfinitam-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libinfinitam-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 trackerType: ICP depthTrackerICPThreshold: 0.01 depthTrackerTerminationThreshold: 0.001 voxelSize: 0.005 viewFrustum_min: 0.2 viewFrustum_max: 3 mu: 0.02 trackingRegime: B,B,R,R,R noICPRunTillLevel: 0 maxW: 100 useSwapping: false useBilateralFilter: false useApproximateRaycast: false modelSensorNoise: false skipPoints: true stopIntegratingAtMaxW: false Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 nan 0.1024790000 16969741 955859216 1776545792 -0.0000000000 0.0000000000 -0.0000000000 2 1311867170.4941389561 0.0573715791 0.0578118116 0.0582520440 0.0124349492 0.1386140000 27457923 955859216 1767538688 -0.0004085616 -0.0012875802 -0.0024125730 3 1311867170.5264289379 0.0565348007 0.0573861413 0.0582520440 0.0101357584 0.0934150000 27460045 955859216 1768054784 -0.0017292867 -0.0022871140 -0.0047748750 4 1311867170.5623490810 0.0561600290 0.0570796132 0.0582520440 0.0096964818 0.1073640000 27462203 955859216 1767170048 0.0001750392 -0.0028360307 -0.0061330586 5 1311867170.5942170620 0.0564950667 0.0569627039 0.0582520440 0.0086592846 0.0896830000 27464257 955859216 1766408192 0.0032361590 -0.0038347614 -0.0071717864 6 1311867170.6260869503 0.0565173700 0.0568884816 0.0582520440 0.0085124457 0.0946580000 27466679 955859216 1765646336 0.0035818054 -0.0049946494 -0.0088235931 7 1311867170.6621398926 0.0566279218 0.0568512588 0.0582520440 0.0083968371 0.1264550000 27468541 955859216 1764114432 0.0042598960 -0.0060167732 -0.0103954244 8 1311867170.6942050457 0.0565226451 0.0568101821 0.0582520440 0.0080573217 0.0916190000 27470275 955859216 1765769216 0.0039563915 -0.0066648577 -0.0121139735 9 1311867170.7263879776 0.0572951511 0.0568640675 0.0582520440 0.0083562468 0.0913540000 27472681 955859216 1767505920 0.0047212164 -0.0067722304 -0.0132068722 10 1311867170.7620189190 0.0571066774 0.0568883285 0.0582520440 0.0084198534 0.0923630000 27475855 955859216 1769156608 0.0036940032 -0.0089362245 -0.0147687532 11 1311867170.7941920757 0.0576170422 0.0569545752 0.0582520440 0.0083760649 0.0931860000 27477557 955859216 1770840064 0.0046629449 -0.0111038424 -0.0163445342 12 1311867170.8262820244 0.0582868196 0.0570655956 0.0582868196 0.0084109249 0.1085720000 27479355 955859216 1772584960 0.0057382639 -0.0141976783 -0.0181468856 13 1311867170.8622210026 0.0583695062 0.0571658964 0.0583695062 0.0082274951 0.0782330000 27481185 955859216 1774235648 0.0054121087 -0.0167566817 -0.0205283836 14 1311867170.8943779469 0.0589024760 0.0572899378 0.0589024760 0.0079315308 0.0736640000 27482919 955859216 1775919104 0.0052009136 -0.0189088266 -0.0228568297 15 1311867170.9263520241 0.0592451803 0.0574202873 0.0592451803 0.0079863027 0.1167680000 27484717 955859216 1777664000 0.0049754023 -0.0210529361 -0.0255790185 16 1311867170.9621469975 0.0584840924 0.0574867751 0.0592451803 0.0077872465 0.0933770000 27486547 955859216 1779314688 0.0025200630 -0.0233214907 -0.0286666453 17 1311867170.9942629337 0.0581960864 0.0575284993 0.0592451803 0.0076123511 0.0776180000 27489561 955859216 1781092352 0.0015519669 -0.0249283444 -0.0317821130 18 1311867171.0262739658 0.0583935492 0.0575765576 0.0592451803 0.0073994415 0.0982680000 27493983 955859216 1782743040 0.0013804225 -0.0262854621 -0.0344605036 19 1311867171.0623519421 0.0577847175 0.0575875134 0.0592451803 0.0078910994 0.1039430000 27495813 955859216 1784393728 0.0006803693 -0.0291164704 -0.0373738967 20 1311867171.0942349434 0.0569526739 0.0575557714 0.0592451803 0.0077952537 0.0913240000 27497547 955859216 1783422976 0.0012557718 -0.0310258381 -0.0399186835 21 1311867171.1262509823 0.0568133704 0.0575204190 0.0592451803 0.0076722591 0.0867170000 27499345 955859216 1779326976 0.0016490094 -0.0313904472 -0.0420563146 22 1311867171.1622469425 0.0564999990 0.0574740363 0.0592451803 0.0076313355 0.0729800000 27501175 955859216 1781010432 0.0030276091 -0.0332010649 -0.0437421873 23 1311867171.1942689419 0.0555127300 0.0573887621 0.0592451803 0.0079611866 0.0769310000 27502909 955859216 1782661120 0.0048666080 -0.0332905427 -0.0448280163 24 1311867171.2262530327 0.0571290068 0.0573779390 0.0592451803 0.0080017406 0.0753970000 27504707 955859216 1784045568 0.0073609790 -0.0331379361 -0.0454733334 25 1311867171.2622439861 0.0565460660 0.0573446640 0.0592451803 0.0080372865 0.0922620000 27506537 955859216 1785790464 0.0080440082 -0.0333045982 -0.0465266332 26 1311867171.2943410873 0.0566184893 0.0573167342 0.0592451803 0.0079475528 0.0892340000 27508239 955859216 1784053760 0.0086006289 -0.0314714015 -0.0471883640 27 1311867171.3263869286 0.0564532876 0.0572847547 0.0592451803 0.0082466909 0.0906190000 27510037 955859216 1779834880 0.0059544644 -0.0306996591 -0.0485015139 28 1311867171.3622460365 0.0552348457 0.0572115437 0.0592451803 0.0081247639 0.0758140000 27511867 955859216 1778458624 0.0032593245 -0.0301588252 -0.0500441380 29 1311867171.3941431046 0.0556935221 0.0571591981 0.0592451803 0.0082742970 0.0865810000 27513601 955859216 1780228096 0.0016162544 -0.0285029598 -0.0511363186 30 1311867171.4262878895 0.0562989563 0.0571305234 0.0592451803 0.0082812831 0.0731090000 27515399 955859216 1781899264 0.0012114168 -0.0286443904 -0.0526703782 31 1311867171.4622440338 0.0560781211 0.0570965749 0.0592451803 0.0081830858 0.0766780000 27517229 955859216 1783377920 0.0002727638 -0.0299260244 -0.0547486134 32 1311867171.4944040775 0.0560403541 0.0570635680 0.0592451803 0.0081288478 0.0969010000 27518963 955859216 1785028608 0.0016345858 -0.0298455507 -0.0567162521 33 1311867171.5261778831 0.0557370074 0.0570233692 0.0592451803 0.0080090107 0.1167520000 27523321 955859216 1782632448 0.0005323175 -0.0294406191 -0.0586513802 34 1311867171.5622971058 0.0550453402 0.0569651919 0.0592451803 0.0078988430 0.0930180000 27530399 955859216 1780346880 0.0014482789 -0.0297248513 -0.0602273904 35 1311867171.5942931175 0.0556105301 0.0569264873 0.0592451803 0.0078333622 0.0748090000 27532133 955859216 1778307072 0.0025532066 -0.0281746592 -0.0610772073 36 1311867171.6263399124 0.0555907786 0.0568893843 0.0592451803 0.0077366514 0.0752100000 27533931 955859216 1776402432 0.0013492011 -0.0286805555 -0.0617126971 37 1311867171.6622560024 0.0552058928 0.0568438845 0.0592451803 0.0076355933 0.1109620000 27535761 955859216 1778188288 -0.0010736007 -0.0294410437 -0.0626084059 38 1311867171.6943440437 0.0560238361 0.0568223043 0.0592451803 0.0078541709 0.0921160000 27537495 955859216 1779867648 -0.0001882602 -0.0292442832 -0.0627675876 39 1311867171.7262439728 0.0563379377 0.0568098846 0.0592451803 0.0077877766 0.0739330000 27539293 955859216 1781346304 0.0001601818 -0.0294835456 -0.0632396787 40 1311867171.7621190548 0.0570938624 0.0568169841 0.0592451803 0.0077083359 0.1142220000 27541123 955859216 1782996992 0.0010133419 -0.0305386949 -0.0636952817 41 1311867171.7941710949 0.0574980602 0.0568335957 0.0592451803 0.0076964722 0.0936220000 27542857 955859216 1784774656 0.0009930196 -0.0316428021 -0.0645649061 42 1311867171.8262550831 0.0579850413 0.0568610110 0.0592451803 0.0076302310 0.0801090000 27544655 955859216 1783549952 -0.0001381574 -0.0320212096 -0.0655816942 43 1311867171.8623590469 0.0575391762 0.0568767823 0.0592451803 0.0075581236 0.0766940000 27546485 955859216 1781493760 -0.0036040789 -0.0323091336 -0.0670128390 44 1311867171.8944430351 0.0572140142 0.0568844467 0.0592451803 0.0076900007 0.0984680000 27548251 955859216 1781665792 -0.0061209719 -0.0326292366 -0.0679310635 45 1311867171.9262220860 0.0583486930 0.0569169855 0.0592451803 0.0076567532 0.0650780000 27550017 955859216 1780502528 -0.0067559211 -0.0319238529 -0.0681897998 46 1311867171.9624669552 0.0588420704 0.0569588352 0.0592451803 0.0076019482 0.0708540000 27551847 955859216 1778601984 -0.0080258073 -0.0316683464 -0.0685549304 47 1311867171.9946711063 0.0598712377 0.0570208012 0.0598712377 0.0076504083 0.0995150000 27553613 955859216 1778614272 -0.0088091521 -0.0309388023 -0.0681087151 48 1311867172.0262680054 0.0607703440 0.0570989167 0.0607703440 0.0077679727 0.0839740000 27555379 955859216 1776029696 -0.0100031132 -0.0300623216 -0.0675383657 49 1311867172.0622880459 0.0613030605 0.0571847155 0.0613030605 0.0077118773 0.0734210000 27557209 955859216 1774112768 -0.0115923546 -0.0295333080 -0.0668283552 50 1311867172.0941960812 0.0615672097 0.0572723654 0.0615672097 0.0076910673 0.0732880000 27558975 955859216 1772220416 -0.0134164989 -0.0292387959 -0.0661559477 51 1311867172.1263689995 0.0624067076 0.0573730388 0.0624067076 0.0076725481 0.0723290000 27560741 955859216 1773895680 -0.0147970635 -0.0294352341 -0.0652770400 52 1311867172.1623349190 0.0618266352 0.0574586849 0.0624067076 0.0076695924 0.0966130000 27562571 955859216 1775665152 -0.0177419148 -0.0296370797 -0.0650420487 53 1311867172.1944270134 0.0607757010 0.0575212701 0.0624067076 0.0076153360 0.0942740000 27564337 955859216 1777410048 -0.0217981916 -0.0292342044 -0.0648082271 54 1311867172.2264409065 0.0604772903 0.0575760112 0.0624067076 0.0077673812 0.1178680000 27566103 955859216 1779060736 -0.0255315695 -0.0290448163 -0.0646242723 55 1311867172.2622280121 0.0599702336 0.0576195425 0.0624067076 0.0077054503 0.0868330000 27567933 955859216 1780744192 -0.0287028886 -0.0282766055 -0.0641200244 56 1311867172.2944829464 0.0602932647 0.0576672875 0.0624067076 0.0076492909 0.0779030000 27569699 955859216 1782489088 -0.0310322233 -0.0276163146 -0.0636597574 57 1311867172.3263380527 0.0596756898 0.0577025227 0.0624067076 0.0076213638 0.1133550000 27571465 955859216 1784139776 -0.0344758928 -0.0272105485 -0.0633386075 58 1311867172.3624010086 0.0599851646 0.0577418786 0.0624067076 0.0075746246 0.0954650000 27573295 955859216 1783287808 -0.0369674042 -0.0270571336 -0.0632422641 59 1311867172.3942890167 0.0590362027 0.0577638163 0.0624067076 0.0075391121 0.0752300000 27575061 955859216 1782398976 -0.0399599522 -0.0272830948 -0.0634860620 60 1311867172.4265220165 0.0593330935 0.0577899709 0.0624067076 0.0075666370 0.1041580000 27576827 955859216 1781510144 -0.0423447751 -0.0279021878 -0.0638119727 61 1311867172.4623498917 0.0592697226 0.0578142291 0.0624067076 0.0075379094 0.1211200000 27578657 955859216 1780629504 -0.0447960719 -0.0283355787 -0.0641498640 62 1311867172.4952669144 0.0598422885 0.0578469397 0.0624067076 0.0075791177 0.0932060000 27580391 955859216 1779736576 -0.0459649116 -0.0280020591 -0.0641568452 63 1311867172.5263059139 0.0592797548 0.0578696828 0.0624067076 0.0075538856 0.0745100000 27582157 955859216 1777938432 -0.0488250293 -0.0291044265 -0.0648177415 64 1311867172.5624930859 0.0591935068 0.0578903676 0.0624067076 0.0074938833 0.1294750000 27583987 955859216 1776431104 -0.0510797687 -0.0300118662 -0.0654635876 65 1311867172.5945439339 0.0605003424 0.0579305210 0.0624067076 0.0074675787 0.0920150000 27590841 955859216 1778073600 -0.0504485779 -0.0297396146 -0.0659905374 66 1311867172.6263699532 0.0605431721 0.0579701067 0.0624067076 0.0074382245 0.1133300000 27603135 955859216 1779695616 -0.0523401387 -0.0297978818 -0.0666578114 67 1311867172.6624419689 0.0607955381 0.0580122773 0.0624067076 0.0073828936 0.1139360000 27604965 955859216 1781346304 -0.0541990921 -0.0297054630 -0.0673417449 68 1311867172.6945450306 0.0605269186 0.0580492573 0.0624067076 0.0074711737 0.0950960000 27606731 955859216 1783029760 -0.0564690977 -0.0296881180 -0.0676840395 69 1311867172.7263929844 0.0613701120 0.0580973856 0.0624067076 0.0074524326 0.0742200000 27608497 955859216 1784774656 -0.0586376339 -0.0290601756 -0.0680675283 70 1311867172.7623739243 0.0616224557 0.0581477438 0.0624067076 0.0074192320 0.0968810000 27610327 955859216 1783787520 -0.0613755360 -0.0282807108 -0.0685780570 71 1311867172.7944509983 0.0611647218 0.0581902364 0.0624067076 0.0073812416 0.1311020000 27612061 955859216 1782915072 -0.0647346750 -0.0287006442 -0.0692214966 72 1311867172.8263089657 0.0619113557 0.0582419186 0.0624067076 0.0073573165 0.1171840000 27613859 955859216 1782026240 -0.0673326403 -0.0287321042 -0.0699699149 73 1311867172.8632309437 0.0619427711 0.0582926152 0.0624067076 0.0073275259 0.1150410000 27615721 955859216 1783676928 -0.0702278689 -0.0294020101 -0.0707673728 74 1311867172.8944649696 0.0612723380 0.0583328818 0.0624067076 0.0072805052 0.0869550000 27617423 955859216 1785020416 -0.0727197602 -0.0297467411 -0.0714869276 75 1311867172.9263219833 0.0608071536 0.0583658721 0.0624067076 0.0072353218 0.0966350000 27619221 955859216 1783922688 -0.0753115192 -0.0308232661 -0.0721621886 76 1311867172.9623310566 0.0607526265 0.0583972767 0.0624067076 0.0071895249 0.0798460000 27621051 955859216 1783033856 -0.0765197799 -0.0314165093 -0.0727821961 77 1311867172.9945271015 0.0605456047 0.0584251771 0.0624067076 0.0071455531 0.0984830000 27622785 955859216 1782145024 -0.0778140575 -0.0316191539 -0.0731907263 78 1311867173.0262629986 0.0599414557 0.0584446166 0.0624067076 0.0071009439 0.1040690000 27624551 955859216 1781256192 -0.0791897774 -0.0322275870 -0.0736003742 79 1311867173.0624630451 0.0599504970 0.0584636783 0.0624067076 0.0070584480 0.0920930000 27626381 955859216 1780367360 -0.0802570581 -0.0325964093 -0.0738049001 80 1311867173.0945179462 0.0603769980 0.0584875948 0.0624067076 0.0070474711 0.0930280000 27628147 955859216 1779605504 -0.0806806833 -0.0327538997 -0.0738975480 81 1311867173.1267819405 0.0601334870 0.0585079145 0.0624067076 0.0070248415 0.0739590000 27629945 955859216 1778716672 -0.0822055042 -0.0329057910 -0.0742348582 82 1311867173.1622309685 0.0604893565 0.0585320784 0.0624067076 0.0070197959 0.0955320000 27631775 955859216 1777954816 -0.0830283314 -0.0321730487 -0.0740478784 83 1311867173.1943008900 0.0611636601 0.0585637842 0.0624067076 0.0069782384 0.1131870000 27633509 955859216 1777192960 -0.0838315710 -0.0313815773 -0.0739940256 84 1311867173.2264449596 0.0609302372 0.0585919563 0.0624067076 0.0069444320 0.1300190000 27635275 955859216 1778925568 -0.0858932063 -0.0316353478 -0.0739652812 85 1311867173.2622020245 0.0616029687 0.0586273799 0.0624067076 0.0069264439 0.0936760000 27637105 955859216 1780576256 -0.0869774520 -0.0308700129 -0.0738591701 86 1311867173.2942678928 0.0621973276 0.0586688910 0.0624067076 0.0068886160 0.0781480000 27638839 955859216 1782259712 -0.0885417387 -0.0306078605 -0.0738242045 87 1311867173.3262879848 0.0620881990 0.0587081934 0.0624067076 0.0068924870 0.0936210000 27640605 955859216 1784004608 -0.0905260369 -0.0310459808 -0.0740840584 88 1311867173.3623280525 0.0625556782 0.0587519148 0.0625556782 0.0068551545 0.0952090000 27642467 955859216 1785655296 -0.0920551866 -0.0308255609 -0.0742043704 89 1311867173.3942871094 0.0622884221 0.0587916508 0.0625556782 0.0068400845 0.0802610000 27644201 955859216 1784811520 -0.0942215249 -0.0313979797 -0.0744320974 90 1311867173.4262790680 0.0619394593 0.0588266265 0.0625556782 0.0068320007 0.0963140000 27645967 955859216 1784049664 -0.0963983238 -0.0322466902 -0.0748557150 91 1311867173.4622900486 0.0621208139 0.0588628263 0.0625556782 0.0068423643 0.0894110000 27647797 955859216 1781993472 -0.0980933383 -0.0327549055 -0.0752788410 92 1311867173.4943389893 0.0627041534 0.0589045799 0.0627041534 0.0069122451 0.0759160000 27649563 955859216 1781510144 -0.0998556018 -0.0332348309 -0.0755531564 93 1311867173.5263900757 0.0625486001 0.0589437629 0.0627041534 0.0068783801 0.0985980000 27651361 955859216 1780617216 -0.1021081433 -0.0332619101 -0.0759398490 94 1311867173.5624370575 0.0625190139 0.0589817975 0.0627041534 0.0068588844 0.0847640000 27653191 955859216 1779859456 -0.1041209102 -0.0327631943 -0.0760979801 95 1311867173.5943109989 0.0626279339 0.0590201779 0.0627041534 0.0068445877 0.0798170000 27654925 955859216 1775894528 -0.1061636135 -0.0327515788 -0.0763803199 96 1311867173.6263959408 0.0618133880 0.0590492738 0.0627041534 0.0068357906 0.1256640000 27656691 955859216 1777573888 -0.1087739766 -0.0333342329 -0.0769607723 97 1311867173.6623299122 0.0622304007 0.0590820689 0.0627041534 0.0068061003 0.0924910000 27658521 955859216 1779224576 -0.1100856960 -0.0332753547 -0.0772834569 98 1311867173.6943540573 0.0627712160 0.0591197133 0.0627712160 0.0067754441 0.1164000000 27660287 955859216 1780576256 -0.1110248417 -0.0336281173 -0.0778246373 99 1311867173.7267971039 0.0620409809 0.0591492210 0.0627712160 0.0067540316 0.1285870000 27662085 955859216 1782353920 -0.1136284173 -0.0340463482 -0.0788448378 100 1311867173.7623970509 0.0624226332 0.0591819552 0.0627712160 0.0067305981 0.0946630000 27663915 955859216 1784004608 -0.1146678925 -0.0334528722 -0.0794291422 101 1311867173.7943561077 0.0630552471 0.0592203046 0.0630552471 0.0066996787 0.0975410000 27665617 955859216 1785671680 -0.1154838055 -0.0331715532 -0.0798556209 102 1311867173.8265669346 0.0618598722 0.0592461827 0.0630552471 0.0066683488 0.0777050000 27667415 955859216 1784557568 -0.1186037883 -0.0343381241 -0.0809534490 103 1311867173.8635799885 0.0628763288 0.0592814268 0.0630552471 0.0066687269 0.0990910000 27669213 955859216 1783668736 -0.1192438230 -0.0340200923 -0.0815406293 104 1311867173.8946080208 0.0627030954 0.0593143275 0.0630552471 0.0066395835 0.0795220000 27670979 955859216 1782779904 -0.1207082346 -0.0343978927 -0.0823864192 105 1311867173.9266970158 0.0617120303 0.0593371628 0.0630552471 0.0066228549 0.1042550000 27672777 955859216 1781891072 -0.1231144145 -0.0357680917 -0.0837253481 106 1311867173.9625461102 0.0624730140 0.0593667463 0.0630552471 0.0066267282 0.1318330000 27674607 955859216 1781002240 -0.1240375638 -0.0351705551 -0.0841758624 107 1311867173.9944310188 0.0629060864 0.0593998242 0.0630552471 0.0066212019 0.0930950000 27676341 955859216 1780092928 -0.1252066344 -0.0349212289 -0.0845993385 108 1311867174.0264260769 0.0628859028 0.0594321027 0.0630552471 0.0066468905 0.1135660000 27678107 955859216 1781878784 -0.1265931278 -0.0355747715 -0.0857850686 109 1311867174.0624630451 0.0633961111 0.0594684698 0.0633961111 0.0066333083 0.1115350000 27679937 955859216 1783623680 -0.1280279607 -0.0340057760 -0.0860898122 110 1311867174.0945188999 0.0645884275 0.0595150148 0.0645884275 0.0066238823 0.0935890000 27681703 955859216 1785274368 -0.1283066571 -0.0327616222 -0.0860364437 111 1311867174.1264541149 0.0643835515 0.0595588755 0.0645884275 0.0066153192 0.0769790000 27683469 955859216 1784430592 -0.1307015568 -0.0333838649 -0.0867991298 112 1311867174.1624329090 0.0644226000 0.0596023016 0.0645884275 0.0066050744 0.0966650000 27685299 955859216 1783013376 -0.1327691674 -0.0329389833 -0.0871199220 113 1311867174.1943979263 0.0650773793 0.0596507536 0.0650773793 0.0065941642 0.0958120000 27687065 955859216 1782398976 -0.1333925873 -0.0319199786 -0.0871429294 114 1311867174.2267580032 0.0649854839 0.0596975495 0.0650773793 0.0065737192 0.0729380000 27688863 955859216 1781510144 -0.1354561448 -0.0326963402 -0.0877481103 115 1311867174.2626769543 0.0646039397 0.0597402138 0.0650773793 0.0065453805 0.0947740000 27690661 955859216 1779855360 -0.1381723583 -0.0327484421 -0.0882259235 116 1311867174.2945280075 0.0658806711 0.0597931488 0.0658806711 0.0065343381 0.1084840000 27692427 955859216 1779335168 -0.1382789314 -0.0319881029 -0.0884411782 117 1311867174.3265740871 0.0650772527 0.0598383120 0.0658806711 0.0065077716 0.0973260000 27694193 955859216 1778462720 -0.1409524679 -0.0325751379 -0.0890833661 118 1311867174.3624329567 0.0648318753 0.0598806304 0.0658806711 0.0064952303 0.0971620000 27696055 955859216 1777700864 -0.1430225968 -0.0323022939 -0.0891538784 119 1311867174.3946359158 0.0652721077 0.0599259369 0.0658806711 0.0064880966 0.1176930000 27697789 955859216 1776939008 -0.1442058831 -0.0319420360 -0.0892215371 120 1311867174.4266788960 0.0657014549 0.0599740662 0.0658806711 0.0064615600 0.0998140000 27699587 955859216 1778589696 -0.1452469528 -0.0322402157 -0.0894770175 121 1311867174.4630160332 0.0655702427 0.0600203156 0.0658806711 0.0064676297 0.0773810000 27701385 955859216 1779941376 -0.1470025927 -0.0327036344 -0.0900061131 122 1311867174.4945669174 0.0661499947 0.0600705589 0.0661499947 0.0064444345 0.0745000000 27703151 955859216 1781719040 -0.1481650174 -0.0321520194 -0.0898432285 123 1311867174.5267519951 0.0660639033 0.0601192853 0.0661499947 0.0064348006 0.0979350000 27704949 955859216 1783353344 -0.1503264010 -0.0326436684 -0.0900914446 124 1311867174.5623500347 0.0657397360 0.0601646115 0.0661499947 0.0064308000 0.0761250000 27706779 955859216 1785036800 -0.1524608433 -0.0321119800 -0.0901311114 125 1311867174.5944879055 0.0659157187 0.0602106203 0.0661499947 0.0064168868 0.1183510000 27708513 955859216 1783906304 -0.1541431397 -0.0314421728 -0.0897550061 126 1311867174.6265459061 0.0663165748 0.0602590803 0.0663165748 0.0064098505 0.0922880000 27710279 955859216 1781882880 -0.1558860391 -0.0312881358 -0.0895319432 127 1311867174.6624910831 0.0659405068 0.0603038159 0.0663165748 0.0063870504 0.1073000000 27712109 955859216 1781895168 -0.1579963565 -0.0318783708 -0.0896704793 128 1311867174.6945910454 0.0663355738 0.0603509390 0.0663355738 0.0063755649 0.0953550000 27713875 955859216 1780715520 -0.1593715996 -0.0311327428 -0.0891694576 129 1311867174.7265629768 0.0672285408 0.0604042538 0.0672285408 0.0063698656 0.1143740000 27725849 955859216 1779843072 -0.1606483012 -0.0311304312 -0.0888000801 130 1311867174.7623760700 0.0670626909 0.0604554725 0.0672285408 0.0063659673 0.0912780000 27748703 955859216 1775501312 -0.1627558917 -0.0321963839 -0.0891057327 131 1311867174.7944738865 0.0672410131 0.0605072706 0.0672410131 0.0063471772 0.0727740000 27750405 955859216 1773613056 -0.1644130647 -0.0319427811 -0.0890798122 132 1311867174.8273398876 0.0677815750 0.0605623789 0.0677815750 0.0063283881 0.1301940000 27752203 955859216 1775382528 -0.1654973477 -0.0322974436 -0.0892945006 133 1311867174.8624229431 0.0672552586 0.0606127013 0.0677815750 0.0063080352 0.1130150000 27754033 955859216 1777049600 -0.1675919592 -0.0325818062 -0.0900390893 134 1311867174.8944199085 0.0677972957 0.0606663177 0.0677972957 0.0062920322 0.0758410000 27755767 955859216 1778655232 -0.1680929214 -0.0317257941 -0.0909699425 135 1311867174.9270179272 0.0676958114 0.0607183880 0.0677972957 0.0062791240 0.0754400000 27757565 955859216 1780338688 -0.1699820906 -0.0312784724 -0.0914157405 136 1311867174.9626429081 0.0679444671 0.0607715210 0.0679444671 0.0062571181 0.1148190000 27759395 955859216 1782083584 -0.1719401479 -0.0315469988 -0.0920957029 137 1311867174.9943349361 0.0670922697 0.0608176578 0.0679444671 0.0062564606 0.0760500000 27761129 955859216 1783734272 -0.1745331436 -0.0311385617 -0.0929787010 138 1311867175.0265510082 0.0677382722 0.0608678072 0.0679444671 0.0062648960 0.0754990000 27762927 955859216 1785417728 -0.1759925783 -0.0294287428 -0.0929687247 139 1311867175.0633120537 0.0677195340 0.0609171002 0.0679444671 0.0062467277 0.1123850000 27764757 955859216 1784414208 -0.1779472232 -0.0295756273 -0.0931577012 140 1311867175.0947189331 0.0608984791 0.0609169672 0.0679444671 0.0062451318 0.0721110000 27766523 955859216 1783525376 -0.1883570999 -0.0271371938 -0.0940204933 141 1311867175.1265308857 0.0611948483 0.0609189380 0.0679444671 0.0062319279 0.0805890000 27768289 955859216 1780957184 -0.1895981431 -0.0276389681 -0.0934982598 142 1311867175.1625180244 0.0615464859 0.0609233573 0.0679444671 0.0062331262 0.0932990000 27770119 955859216 1781620736 -0.1903957129 -0.0275385864 -0.0934093967 143 1311867175.1946399212 0.0613432527 0.0609262937 0.0679444671 0.0062140150 0.0764880000 27771853 955859216 1779965952 -0.1919881105 -0.0274173226 -0.0932141840 144 1311867175.2270050049 0.0620543733 0.0609341275 0.0679444671 0.0062939428 0.0997670000 27773651 955859216 1779462144 -0.1925899833 -0.0265716016 -0.0926967710 145 1311867175.2624669075 0.0627736226 0.0609468137 0.0679444671 0.0063086350 0.0694410000 27775449 955859216 1778573312 -0.1931109875 -0.0259600393 -0.0924053937 146 1311867175.2944509983 0.0627406389 0.0609591002 0.0679444671 0.0062889929 0.0710370000 27777215 955859216 1777811456 -0.1943286210 -0.0258409288 -0.0922227874 147 1311867175.3267059326 0.0645251125 0.0609833588 0.0679444671 0.0062706189 0.0957070000 27779013 955859216 1777049600 -0.1940689087 -0.0243753083 -0.0913375020 148 1311867175.3625650406 0.0655608475 0.0610142878 0.0679444671 0.0062623806 0.1305660000 27780811 955859216 1776287744 -0.1956479847 -0.0240323450 -0.0907095075 149 1311867175.3945989609 0.0656351745 0.0610453004 0.0679444671 0.0062486241 0.0747850000 27782577 955859216 1775398912 -0.1979760975 -0.0240287129 -0.0905116051 150 1311867175.4266059399 0.0661406219 0.0610792692 0.0679444671 0.0062319976 0.0744250000 27784343 955859216 1774637056 -0.2001207322 -0.0228201710 -0.0902452320 151 1311867175.4625999928 0.0665725842 0.0611156488 0.0679444671 0.0062174592 0.1204340000 27786205 955859216 1770299392 -0.2031451613 -0.0225995742 -0.0899061114 152 1311867175.4945731163 0.0667302534 0.0611525870 0.0679444671 0.0062007071 0.0849410000 27787971 955859216 1772085248 -0.2062695175 -0.0225896426 -0.0897544175 153 1311867175.5264270306 0.0671664104 0.0611918930 0.0679444671 0.0061906237 0.0749330000 27789705 955859216 1773637632 -0.2091753185 -0.0220933016 -0.0896701515 154 1311867175.5625700951 0.0674868822 0.0612327696 0.0679444671 0.0061994064 0.1140610000 27791567 955859216 1775226880 -0.2115780413 -0.0206239726 -0.0894577578 155 1311867175.5946640968 0.0681193769 0.0612771993 0.0681193769 0.0062242644 0.0783220000 27793301 955859216 1776910336 -0.2142009735 -0.0195362885 -0.0893227756 156 1311867175.6264801025 0.0669932440 0.0613138406 0.0681193769 0.0062383117 0.1137450000 27795067 955859216 1778655232 -0.2180178612 -0.0194808953 -0.0892797709 157 1311867175.6624929905 0.0686266422 0.0613604190 0.0686266422 0.0062863662 0.0947830000 27796897 955859216 1780305920 -0.2190661728 -0.0190392341 -0.0888320133 158 1311867175.6947000027 0.0695362389 0.0614121647 0.0695362389 0.0063051815 0.1060670000 27798663 955859216 1781989376 -0.2207563370 -0.0196128674 -0.0888907611 159 1311867175.7273120880 0.0700160563 0.0614662772 0.0700160563 0.0062982700 0.0818480000 27800461 955859216 1783734272 -0.2229120731 -0.0200686846 -0.0887298360 160 1311867175.7624969482 0.0707754344 0.0615244594 0.0707754344 0.0062848463 0.0764950000 27802291 955859216 1785384960 -0.2246061862 -0.0190386679 -0.0887778476 161 1311867175.7948620319 0.0712305307 0.0615847456 0.0712305307 0.0062976614 0.1194220000 27804025 955859216 1784270848 -0.2269848287 -0.0193141196 -0.0889210999 162 1311867175.8287971020 0.0707631931 0.0616414027 0.0712305307 0.0062831148 0.1053730000 27805855 955859216 1783398400 -0.2303011268 -0.0196015276 -0.0893324390 163 1311867175.8625519276 0.0719057322 0.0617043740 0.0719057322 0.0062908954 0.0687500000 27807653 955859216 1782489088 -0.2324176431 -0.0192975551 -0.0894320533 164 1311867175.8946080208 0.0726152658 0.0617709038 0.0726152658 0.0062785080 0.0875060000 27809387 955859216 1780596736 -0.2347501665 -0.0195735004 -0.0899234712 165 1311867175.9282429218 0.0725369379 0.0618361525 0.0726152658 0.0062798253 0.0885800000 27811185 955859216 1780494336 -0.2377788424 -0.0201077349 -0.0906252339 166 1311867175.9629371166 0.0729296431 0.0619029808 0.0729296431 0.0062612296 0.0779390000 27812983 955859216 1779060736 -0.2401772738 -0.0194627754 -0.0908129141 167 1311867175.9983000755 0.0731614083 0.0619703965 0.0731614083 0.0062608195 0.0951910000 27814781 955859216 1778446336 -0.2426661849 -0.0189510956 -0.0908379555 168 1311867176.0268509388 0.0732895806 0.0620377726 0.0732895806 0.0062435769 0.1020160000 27816483 955859216 1777684480 -0.2448584735 -0.0203528330 -0.0913230702 169 1311867176.0627059937 0.0722356662 0.0620981152 0.0732895806 0.0062808273 0.1171990000 27818313 955859216 1776922624 -0.2479801178 -0.0209275838 -0.0920507610 170 1311867176.0946600437 0.0726404563 0.0621601289 0.0732895806 0.0063197026 0.0953100000 27820047 955859216 1774723072 -0.2494108826 -0.0205359384 -0.0924151912 171 1311867176.1268119812 0.0729664490 0.0622233238 0.0732895806 0.0063068371 0.1089870000 27821845 955859216 1775034368 -0.2511242032 -0.0205745734 -0.0930423588 172 1311867176.1625900269 0.0726564080 0.0622839813 0.0732895806 0.0063913322 0.1026980000 27823675 955859216 1774112768 -0.2529962957 -0.0202648472 -0.0937392786 173 1311867176.1946918964 0.0726402625 0.0623438442 0.0732895806 0.0064452103 0.1268370000 27825441 955859216 1773232128 -0.2543513179 -0.0186448731 -0.0943920165 174 1311867176.2265360355 0.0719317272 0.0623989469 0.0732895806 0.0064298781 0.1298580000 27827207 955859216 1774882816 -0.2567501068 -0.0176292602 -0.0949697644 175 1311867176.2625019550 0.0712804273 0.0624496983 0.0732895806 0.0064207252 0.1112220000 27829037 955859216 1776361472 -0.2592915595 -0.0172564611 -0.0959373415 176 1311867176.2946109772 0.0705419332 0.0624956769 0.0732895806 0.0064160068 0.0804130000 27830771 955859216 1778012160 -0.2620382011 -0.0160657447 -0.0964802429 177 1311867176.3266019821 0.0715390965 0.0625467696 0.0732895806 0.0064044056 0.0717250000 27832537 955859216 1779695616 -0.2628800273 -0.0146412104 -0.0969579965 178 1311867176.3624560833 0.0715434551 0.0625973128 0.0732895806 0.0063871862 0.1144130000 27834399 955859216 1781440512 -0.2647245526 -0.0150886700 -0.0978586823 179 1311867176.3952438831 0.0720676482 0.0626502197 0.0732895806 0.0063705851 0.0980930000 27836133 955859216 1783091200 -0.2655171454 -0.0139292078 -0.0985277817 180 1311867176.4268360138 0.0730576962 0.0627080390 0.0732895806 0.0063553484 0.1149660000 27837899 955859216 1784868864 -0.2656544149 -0.0126541825 -0.0991811007 181 1311867176.4629659653 0.0729805157 0.0627647930 0.0732895806 0.0064309021 0.1194130000 27839729 955859216 1783644160 -0.2674840093 -0.0121665234 -0.1000636369 182 1311867176.4945809841 0.0724467859 0.0628179908 0.0732895806 0.0064311243 0.0908490000 27841463 955859216 1782517760 -0.2698072493 -0.0118908416 -0.1011571139 183 1311867176.5266211033 0.0734036937 0.0628758362 0.0734036937 0.0064775081 0.0941690000 27843261 955859216 1781735424 -0.2709663212 -0.0107582891 -0.1018937901 184 1311867176.5636389256 0.0733727813 0.0629328848 0.0734036937 0.0064753601 0.1301060000 27845123 955859216 1780977664 -0.2729667127 -0.0110851694 -0.1028528810 185 1311867176.5946090221 0.0730307996 0.0629874681 0.0734036937 0.0064628154 0.1344830000 27846857 955859216 1780088832 -0.2751605213 -0.0113554234 -0.1040849686 186 1311867176.6283841133 0.0732444376 0.0630426131 0.0734036937 0.0064555871 0.1296460000 27848655 955859216 1781821440 -0.2770103216 -0.0105621899 -0.1049068272 187 1311867176.6625781059 0.0735158101 0.0630986195 0.0735158101 0.0064438470 0.0750010000 27850453 955859216 1783504896 -0.2793827653 -0.0097556096 -0.1057164669 188 1311867176.6945180893 0.0735193416 0.0631540489 0.0735193416 0.0064285856 0.0749900000 27852187 955859216 1785249792 -0.2815698087 -0.0092636207 -0.1065306216 189 1311867176.7265889645 0.0731838048 0.0632071164 0.0735193416 0.0064122076 0.1122870000 27853985 955859216 1784279040 -0.2845829427 -0.0087891333 -0.1072738692 190 1311867176.7632329464 0.0738659203 0.0632632153 0.0738659203 0.0063991603 0.0827470000 27855815 955859216 1779920896 -0.2866359651 -0.0088944351 -0.1077540591 191 1311867176.7947680950 0.0742952526 0.0633209747 0.0742952526 0.0063937968 0.0707030000 27857549 955859216 1781579776 -0.2884531319 -0.0086508645 -0.1083045751 192 1311867176.8266770840 0.0743420571 0.0633783762 0.0743420571 0.0063794273 0.1151970000 27859347 955859216 1783263232 -0.2908285260 -0.0087556569 -0.1089379787 193 1311867176.8627309799 0.0747164413 0.0634371226 0.0747164413 0.0063672653 0.1155880000 27861177 955859216 1784774656 -0.2929236591 -0.0082341079 -0.1092534512 194 1311867176.8949549198 0.0746926591 0.0634951408 0.0747164413 0.0063540730 0.0931850000 27862943 955859216 1783644160 -0.2954570353 -0.0079568839 -0.1097011417 195 1311867176.9268178940 0.0745325759 0.0635517431 0.0747164413 0.0063546910 0.0787210000 27864709 955859216 1781587968 -0.2979539931 -0.0081851082 -0.1102038324 196 1311867176.9650609493 0.0752834156 0.0636115986 0.0752834156 0.0063657128 0.0905720000 27866539 955859216 1781739520 -0.2997381985 -0.0071901884 -0.1104396209 197 1311867176.9947481155 0.0759193450 0.0636740744 0.0759193450 0.0063539306 0.0787340000 27868273 955859216 1780576256 -0.3011589944 -0.0068063885 -0.1108551472 198 1311867177.0267279148 0.0761084184 0.0637368741 0.0761084184 0.0063424782 0.0873090000 27870039 955859216 1778683904 -0.3034223318 -0.0075907735 -0.1111976132 199 1311867177.0626339912 0.0763519034 0.0638002662 0.0763519034 0.0063311063 0.0920560000 27871869 955859216 1778565120 -0.3056762218 -0.0069213235 -0.1114223227 200 1311867177.0946850777 0.0766396523 0.0638644632 0.0766396523 0.0063194624 0.1134610000 27873635 955859216 1777803264 -0.3070188463 -0.0066351611 -0.1119764522 201 1311867177.1266150475 0.0769213140 0.0639294226 0.0769213140 0.0063046793 0.0818420000 27875401 955859216 1777041408 -0.3090802133 -0.0071162414 -0.1122844741 202 1311867177.1627299786 0.0778120458 0.0639981485 0.0778120458 0.0062895558 0.0878380000 27877231 955859216 1776148480 -0.3106639683 -0.0065959375 -0.1125843897 203 1311867177.1946458817 0.0774070919 0.0640642024 0.0778120458 0.0062784993 0.0892710000 27878997 955859216 1775390720 -0.3130019903 -0.0058462527 -0.1129938886 204 1311867177.2264730930 0.0783708394 0.0641343330 0.0783708394 0.0062632114 0.1352390000 27880763 955859216 1773314048 -0.3145537972 -0.0059430045 -0.1134038195 205 1311867177.2638640404 0.0784300119 0.0642040680 0.0784300119 0.0062482530 0.0912150000 27882625 955859216 1773633536 -0.3173525631 -0.0054021692 -0.1137836874 206 1311867177.2946178913 0.0783114880 0.0642725506 0.0784300119 0.0062538341 0.0763690000 27884359 955859216 1772597248 -0.3193525672 -0.0056342427 -0.1144156605 207 1311867177.3276090622 0.0778103545 0.0643379506 0.0784300119 0.0062388538 0.1378790000 27886157 955859216 1771708416 -0.3221246600 -0.0055963709 -0.1149706244 208 1311867177.3627710342 0.0788371488 0.0644076583 0.0788371488 0.0062279283 0.1457110000 27887955 955859216 1770946560 -0.3233911991 -0.0045850803 -0.1152521446 209 1311867177.3946089745 0.0786537454 0.0644758214 0.0788371488 0.0062296179 0.1116750000 27889721 955859216 1772593152 -0.3258383870 -0.0048770616 -0.1157109812 210 1311867177.4312860966 0.0791491643 0.0645456945 0.0791491643 0.0062209019 0.1363090000 27891583 955859216 1774075904 -0.3278988898 -0.0042827153 -0.1159507856 211 1311867177.4626040459 0.0791727081 0.0646150168 0.0791727081 0.0062069398 0.1333330000 27893349 955859216 1775742976 -0.3300119936 -0.0036351662 -0.1164200306 212 1311867177.4946429729 0.0791245997 0.0646834582 0.0791727081 0.0061940713 0.1125900000 27895115 955859216 1777504256 -0.3319251835 -0.0032177067 -0.1168974116 213 1311867177.5276319981 0.0794081762 0.0647525884 0.0794081762 0.0061818983 0.1160040000 27896881 955859216 1779154944 -0.3333860636 -0.0024282152 -0.1174646318 214 1311867177.5626399517 0.0805962458 0.0648266242 0.0805962458 0.0061748224 0.1182160000 27898679 955859216 1780838400 -0.3348457813 -0.0021102782 -0.1176353693 215 1311867177.5947310925 0.0765892491 0.0648813340 0.0805962458 0.0061660974 0.1113970000 27900445 955859216 1782583296 -0.3406034410 -0.0020762195 -0.1190888360 216 1311867177.6311450005 0.0761626214 0.0649335622 0.0805962458 0.0061526475 0.1362360000 27902307 955859216 1784266752 -0.3432722688 -0.0017802129 -0.1197074503 217 1311867177.6624829769 0.0763728172 0.0649862777 0.0805962458 0.0061401774 0.0968770000 27904073 955859216 1783283712 -0.3443207443 -0.0009255279 -0.1203541830 218 1311867177.6945610046 0.0761361197 0.0650374237 0.0805962458 0.0061507168 0.0749560000 27905839 955859216 1782120448 -0.3462549746 -0.0009260607 -0.1209456474 219 1311867177.7305839062 0.0758230463 0.0650866732 0.0805962458 0.0061383393 0.0951880000 27907637 955859216 1778274304 -0.3480542004 0.0004840624 -0.1215066016 220 1311867177.7625379562 0.0765258670 0.0651386695 0.0805962458 0.0061319199 0.1117600000 27909403 955859216 1779953664 -0.3482232094 0.0006629312 -0.1220433041 221 1311867177.7945590019 0.0755951181 0.0651859837 0.0805962458 0.0061206114 0.1336020000 27911169 955859216 1781686272 -0.3500148654 0.0009459713 -0.1229576766 222 1311867177.8309149742 0.0760186166 0.0652347794 0.0805962458 0.0061100613 0.1077660000 27912999 955859216 1783353344 -0.3510490954 0.0011757120 -0.1237950549 223 1311867177.8625319004 0.0760691538 0.0652833640 0.0805962458 0.0060969473 0.0998680000 27914765 955859216 1785114624 -0.3518453538 0.0012738964 -0.1245633140 224 1311867177.8946919441 0.0763116479 0.0653325974 0.0805962458 0.0060856210 0.1192360000 27916499 955859216 1784143872 -0.3524452448 0.0018352903 -0.1250650138 225 1311867177.9317860603 0.0765645057 0.0653825170 0.0805962458 0.0060723994 0.0973890000 27918393 955859216 1783255040 -0.3534968197 0.0024124153 -0.1259477884 226 1311867177.9627909660 0.0765105560 0.0654317561 0.0805962458 0.0060721544 0.1251550000 27920127 955859216 1782345728 -0.3553368151 0.0026079854 -0.1268917322 227 1311867177.9947769642 0.0765294433 0.0654806446 0.0805962458 0.0060644891 0.0966000000 27921829 955859216 1777917952 -0.3564365804 0.0037831496 -0.1276348233 228 1311867178.0306100845 0.0771375671 0.0655317715 0.0805962458 0.0060564980 0.1065780000 27923659 955859216 1779576832 -0.3573879600 0.0037695738 -0.1286181659 229 1311867178.0634479523 0.0777276158 0.0655850284 0.0805962458 0.0060465218 0.1139710000 27925425 955859216 1781239808 -0.3583109379 0.0034217399 -0.1293179095 230 1311867178.0951139927 0.0780447498 0.0656392011 0.0805962458 0.0060335329 0.0896050000 27927191 955859216 1782829056 -0.3591842055 0.0046845810 -0.1298566908 231 1311867178.1307909489 0.0781627297 0.0656934156 0.0805962458 0.0060240932 0.1166360000 27929021 955859216 1784479744 -0.3614441156 0.0043096445 -0.1305285990 232 1311867178.1627469063 0.0780713856 0.0657467689 0.0805962458 0.0060399079 0.1179640000 27930787 955859216 1783365632 -0.3635391891 0.0041534659 -0.1312961578 233 1311867178.1950459480 0.0785980746 0.0658019247 0.0805962458 0.0060363304 0.0951260000 27932521 955859216 1779544064 -0.3650175631 0.0054224450 -0.1315693110 234 1311867178.2307190895 0.0791734532 0.0658590680 0.0805962458 0.0060320904 0.1105130000 27934351 955859216 1781223424 -0.3670831919 0.0042731091 -0.1323159039 235 1311867178.2628939152 0.0793238953 0.0659163651 0.0805962458 0.0060212918 0.1320130000 27936149 955859216 1782956032 -0.3689383268 0.0039964882 -0.1328253597 236 1311867178.2954900265 0.0800283700 0.0659761617 0.0805962458 0.0060132836 0.1174060000 27937915 955859216 1784606720 -0.3699347675 0.0048861145 -0.1330429912 237 1311867178.3306670189 0.0808974504 0.0660391208 0.0808974504 0.0060090179 0.1364360000 27939713 955859216 1783762944 -0.3716310859 0.0037402532 -0.1334250122 238 1311867178.3627231121 0.0808811858 0.0661014824 0.0808974504 0.0060018313 0.1217050000 27941511 955859216 1782874112 -0.3739601970 0.0041250959 -0.1336532831 239 1311867178.3949439526 0.0810749829 0.0661641330 0.0810749829 0.0059913865 0.1255730000 27943245 955859216 1778290688 -0.3758536279 0.0045358543 -0.1339268833 240 1311867178.4306581020 0.0811611339 0.0662266205 0.0811611339 0.0059891547 0.1301220000 27945075 955859216 1780043776 -0.3781842887 0.0050936784 -0.1339212358 241 1311867178.4628739357 0.0815023109 0.0662900051 0.0815023109 0.0059772490 0.1270810000 27946841 955859216 1781731328 -0.3799392581 0.0058322349 -0.1338535994 242 1311867178.4946439266 0.0811564103 0.0663514366 0.0815023109 0.0059688799 0.1097450000 27948607 955859216 1783209984 -0.3819358647 0.0053420900 -0.1340896338 243 1311867178.5306270123 0.0819663629 0.0664156955 0.0819663629 0.0059714549 0.0988250000 27950437 955859216 1784893440 -0.3834064901 0.0056562945 -0.1339416206 244 1311867178.5626420975 0.0826068670 0.0664820528 0.0826068670 0.0059598666 0.1373840000 27952235 955859216 1783762944 -0.3847755492 0.0058558867 -0.1339961886 245 1311867178.5947000980 0.0828919783 0.0665490321 0.0828919783 0.0059576173 0.1157200000 27954001 955859216 1782870016 -0.3861992061 0.0053865490 -0.1341142058 246 1311867178.6306900978 0.0831423774 0.0666164847 0.0831423774 0.0059550128 0.0881760000 27955799 955859216 1782112256 -0.3880395889 0.0057339189 -0.1340908855 247 1311867178.6626410484 0.0831136927 0.0666832750 0.0831423774 0.0059658820 0.0928250000 27957597 955859216 1781223424 -0.3892203569 0.0069308076 -0.1343784928 248 1311867178.6946120262 0.0826069936 0.0667474835 0.0831423774 0.0059581071 0.1148350000 27959331 955859216 1776742400 -0.3913375437 0.0064020278 -0.1348356903 249 1311867178.7307450771 0.0817483589 0.0668077280 0.0831423774 0.0059567079 0.1120290000 27961161 955859216 1778528256 -0.3935256600 0.0073324349 -0.1351320446 250 1311867178.7632350922 0.0818974078 0.0668680867 0.0831423774 0.0059500917 0.0925910000 27962959 955859216 1780207616 -0.3945190609 0.0073321089 -0.1352269351 251 1311867178.8006799221 0.0818823650 0.0669279046 0.0831423774 0.0059467947 0.1156330000 27964789 955859216 1781686272 -0.3956140280 0.0056197420 -0.1357030720 252 1311867178.8309500217 0.0820134059 0.0669877677 0.0831423774 0.0059410979 0.1371390000 27966523 955859216 1783369728 -0.3959169984 0.0072389832 -0.1359695494 253 1311867178.8627939224 0.0818650797 0.0670465713 0.0831423774 0.0059383596 0.1329520000 27968321 955859216 1785114624 -0.3968021274 0.0077868132 -0.1361851841 254 1311867178.8952279091 0.0814376250 0.0671032290 0.0831423774 0.0059394045 0.1372340000 27970087 955859216 1783869440 -0.3979354799 0.0057976744 -0.1369020790 255 1311867178.9306209087 0.0813488886 0.0671590943 0.0831423774 0.0059520645 0.0919190000 27971885 955859216 1783128064 -0.3985613286 0.0073777894 -0.1375183910 256 1311867178.9627609253 0.0804976746 0.0672111981 0.0831423774 0.0059488541 0.0937860000 27973683 955859216 1781473280 -0.4000204206 0.0085854409 -0.1381848305 257 1311867178.9946830273 0.0787366852 0.0672560444 0.0831423774 0.0059572241 0.1336460000 27995929 955859216 1780977664 -0.4028493166 0.0082164006 -0.1392138153 258 1311867179.0309159756 0.0787412450 0.0673005607 0.0831423774 0.0059811521 0.0930360000 28039743 955859216 1780215808 -0.4040920436 0.0082106153 -0.1400570422 259 1311867179.0628120899 0.0795487314 0.0673478509 0.0831423774 0.0059794642 0.0912250000 28041541 955859216 1781948416 -0.4045482278 0.0069743879 -0.1408416480 260 1311867179.0968201160 0.0793414712 0.0673939802 0.0831423774 0.0060624561 0.0961260000 28043307 955859216 1783615488 -0.4063378572 0.0049167741 -0.1417270303 261 1311867179.1310369968 0.0791902393 0.0674391766 0.0831423774 0.0060561476 0.1189050000 28045073 955859216 1785376768 -0.4070451856 0.0068724542 -0.1427152604 262 1311867179.1627540588 0.0793484226 0.0674846318 0.0831423774 0.0060728190 0.0943340000 28046839 955859216 1784406016 -0.4084605277 0.0067617870 -0.1440239102 263 1311867179.1957008839 0.0775710493 0.0675229831 0.0831423774 0.0060664115 0.1034490000 28048605 955859216 1783263232 -0.4116639495 0.0062200767 -0.1456756592 264 1311867179.2307469845 0.0771945715 0.0675596180 0.0831423774 0.0061122508 0.0950480000 28050403 955859216 1782484992 -0.4138454199 0.0083648991 -0.1467448920 265 1311867179.2634611130 0.0780262798 0.0675991148 0.0831423774 0.0061174158 0.0993970000 28052233 955859216 1781612544 -0.4145970047 0.0067607509 -0.1477621794 266 1311867179.2959330082 0.0780459270 0.0676383885 0.0831423774 0.0061123051 0.1117470000 28053967 955859216 1778409472 -0.4160044193 0.0060124863 -0.1486930251 267 1311867179.3307149410 0.0792870969 0.0676820166 0.0831423774 0.0061041842 0.0930910000 28055765 955859216 1778962432 -0.4160978794 0.0069390070 -0.1491261423 268 1311867179.3629300594 0.0795476809 0.0677262915 0.0831423774 0.0060930054 0.0880850000 28057595 955859216 1778184192 -0.4168305695 0.0075062094 -0.1495657414 269 1311867179.3948490620 0.0792081952 0.0677689752 0.0831423774 0.0060868340 0.1198650000 28059297 955859216 1777422336 -0.4183382988 0.0069245370 -0.1500827223 270 1311867179.4308040142 0.0797265470 0.0678132625 0.0831423774 0.0060914854 0.0949320000 28061159 955859216 1776660480 -0.4191605151 0.0074378336 -0.1503897309 271 1311867179.4637460709 0.0811152086 0.0678623471 0.0831423774 0.0060956811 0.0909170000 28062957 955859216 1774747648 -0.4190549254 0.0079250317 -0.1501458883 272 1311867179.4949469566 0.0818766654 0.0679138704 0.0831423774 0.0061079736 0.0898410000 28064691 955859216 1776517120 -0.4197846353 0.0071022999 -0.1502138227 273 1311867179.5307800770 0.0828119516 0.0679684421 0.0831423774 0.0061066919 0.0754690000 28066521 955859216 1778012160 -0.4203243554 0.0097695030 -0.1502886862 274 1311867179.5627610683 0.0832788944 0.0680243197 0.0832788944 0.0061252992 0.0754840000 28068287 955859216 1779789824 -0.4211539924 0.0102892043 -0.1503701508 275 1311867179.5946741104 0.0830201581 0.0680788500 0.0832788944 0.0061176295 0.0761930000 28070053 955859216 1781440512 -0.4227689505 0.0107993595 -0.1502337903 276 1311867179.6306900978 0.0837861672 0.0681357605 0.0837861672 0.0061304468 0.0755930000 28071851 955859216 1783107584 -0.4231202304 0.0116296364 -0.1502396613 277 1311867179.6625750065 0.0846771970 0.0681954769 0.0846771970 0.0061302574 0.1150420000 28073649 955859216 1784868864 -0.4233272672 0.0107320659 -0.1501296163 278 1311867179.6946051121 0.0850685388 0.0682561714 0.0850685388 0.0061381308 0.0792690000 28075383 955859216 1783771136 -0.4238416851 0.0118915411 -0.1501154602 279 1311867179.7309470177 0.0853887424 0.0683175785 0.0853887424 0.0061303964 0.0755860000 28077245 955859216 1781731328 -0.4243447483 0.0126913525 -0.1498880237 280 1311867179.7627270222 0.0850824714 0.0683774531 0.0853887424 0.0061525854 0.0896860000 28079011 955859216 1781866496 -0.4253153503 0.0118077798 -0.1500940621 281 1311867179.7948911190 0.0858257562 0.0684395467 0.0858257562 0.0061684529 0.1300730000 28080745 955859216 1780723712 -0.4247837961 0.0130853364 -0.1501048654 282 1311867179.8307530880 0.0868229866 0.0685047362 0.0868229866 0.0061602989 0.1360300000 28082607 955859216 1779961856 -0.4243898988 0.0135178166 -0.1499071270 283 1311867179.8627979755 0.0871330947 0.0685705608 0.0871330947 0.0061538641 0.1350910000 28084373 955859216 1781694464 -0.4252995253 0.0119318329 -0.1497746110 284 1311867179.8948040009 0.0875095874 0.0686372475 0.0875095874 0.0061476957 0.1135570000 28086139 955859216 1783377920 -0.4257135987 0.0117872432 -0.1495832801 285 1311867179.9309051037 0.0880107805 0.0687052248 0.0880107805 0.0061672013 0.0944210000 28087969 955859216 1785122816 -0.4257952273 0.0145031800 -0.1492566317 286 1311867179.9635379314 0.0879018009 0.0687723457 0.0880107805 0.0061653838 0.1181440000 28089767 955859216 1784152064 -0.4267326295 0.0138731971 -0.1490218490 287 1311867179.9958879948 0.0872671008 0.0688367873 0.0880107805 0.0061589601 0.0948020000 28091501 955859216 1783263232 -0.4281183481 0.0139314439 -0.1487412006 288 1311867180.0309770107 0.0877265781 0.0689023769 0.0880107805 0.0061560790 0.1050960000 28093331 955859216 1782353920 -0.4279005826 0.0158635899 -0.1483274251 289 1311867180.0626471043 0.0871273056 0.0689654389 0.0880107805 0.0061465026 0.1434850000 28095097 955859216 1777917952 -0.4294317365 0.0150253400 -0.1478933990 290 1311867180.0947730541 0.0848689750 0.0690202787 0.0880107805 0.0061371027 0.0897110000 28096831 955859216 1779572736 -0.4313565195 0.0163006280 -0.1487027556 291 1311867180.1307730675 0.0843536183 0.0690729706 0.0880107805 0.0061365766 0.0734340000 28098661 955859216 1781358592 -0.4316684008 0.0155853834 -0.1485556066 292 1311867180.1636900902 0.0842613876 0.0691249857 0.0880107805 0.0061535504 0.1340860000 28100491 955859216 1782710272 -0.4304216206 0.0159042627 -0.1489463449 293 1311867180.1949090958 0.0836229846 0.0691744670 0.0880107805 0.0061437151 0.0929180000 28102193 955859216 1784377344 -0.4302607477 0.0160776321 -0.1492293924 294 1311867180.2308139801 0.0830307305 0.0692215971 0.0880107805 0.0061407714 0.0805970000 28103991 955859216 1783255040 -0.4293344021 0.0164466277 -0.1502521038 295 1311867180.2637619972 0.0821347833 0.0692653706 0.0880107805 0.0061669907 0.0924110000 28105789 955859216 1781837824 -0.4294878244 0.0165328495 -0.1509105116 296 1311867180.2947549820 0.0811947361 0.0693056725 0.0880107805 0.0061566366 0.0982580000 28107523 955859216 1781096448 -0.4298678935 0.0164908338 -0.1515495628 297 1311867180.3308670521 0.0804276690 0.0693431203 0.0880107805 0.0061485780 0.1107990000 28109353 955859216 1780334592 -0.4299592972 0.0165047701 -0.1519425958 298 1311867180.3658289909 0.0795887262 0.0693775016 0.0880107805 0.0061480222 0.1118680000 28111151 955859216 1779318784 -0.4298012853 0.0171486363 -0.1523836851 299 1311867180.3964109421 0.0791355148 0.0694101370 0.0880107805 0.0061398042 0.1202270000 28112917 955859216 1778192384 -0.4295227826 0.0179983396 -0.1525013298 300 1311867180.4309151173 0.0783886462 0.0694400654 0.0880107805 0.0061317585 0.1008920000 28114715 955859216 1777160192 -0.4293273389 0.0174986385 -0.1531478018 301 1311867180.4670670033 0.0781022310 0.0694688434 0.0880107805 0.0061255941 0.1133010000 28116545 955859216 1776394240 -0.4285432994 0.0178985428 -0.1534793377 302 1311867180.4947559834 0.0780033395 0.0694971033 0.0880107805 0.0061278788 0.0886590000 28118215 955859216 1774596096 -0.4281196594 0.0176616497 -0.1536520720 303 1311867180.5308880806 0.0776943490 0.0695241569 0.0880107805 0.0061187216 0.0752740000 28120077 955859216 1776250880 -0.4271915257 0.0179293491 -0.1536704898 304 1311867180.5629510880 0.0775716454 0.0695506289 0.0880107805 0.0061091256 0.0753210000 28121843 955859216 1777876992 -0.4262328148 0.0180261321 -0.1535069793 305 1311867180.5946910381 0.0774513185 0.0695765328 0.0880107805 0.0061001495 0.1137050000 28123609 955859216 1779527680 -0.4249466062 0.0184222162 -0.1534738392 306 1311867180.6308128834 0.0771773905 0.0696013722 0.0880107805 0.0060911075 0.0966310000 28125439 955859216 1781305344 -0.4240943789 0.0181089900 -0.1533278376 307 1311867180.6640911102 0.0767850131 0.0696247717 0.0880107805 0.0060993802 0.1169670000 28127205 955859216 1782956032 -0.4232679605 0.0184612628 -0.1530857980 308 1311867180.6957859993 0.0768731609 0.0696483054 0.0880107805 0.0060898207 0.0757690000 28128971 955859216 1784733696 -0.4223334193 0.0176186226 -0.1527185142 309 1311867180.7309739590 0.0767694339 0.0696713511 0.0880107805 0.0060856227 0.0795530000 28130801 955859216 1783635968 -0.4209043682 0.0183839854 -0.1526896507 310 1311867180.7650830746 0.0772679076 0.0696958562 0.0880107805 0.0060907368 0.1056940000 28132599 955859216 1782489088 -0.4203836918 0.0181842390 -0.1523319930 311 1311867180.7949280739 0.0771308690 0.0697197630 0.0880107805 0.0060812898 0.0833940000 28134301 955859216 1781731328 -0.4201288521 0.0182121918 -0.1520612687 312 1311867180.8309240341 0.0773823708 0.0697443226 0.0880107805 0.0060721938 0.1132080000 28136163 955859216 1780842496 -0.4191117883 0.0189432167 -0.1516567469 313 1311867180.8652698994 0.0772643015 0.0697683481 0.0880107805 0.0060716044 0.1345420000 28137961 955859216 1779699712 -0.4179811180 0.0179701094 -0.1516854167 314 1311867180.8966469765 0.0770170093 0.0697914330 0.0880107805 0.0060643519 0.1341670000 28139727 955859216 1781329920 -0.4167924523 0.0183414929 -0.1516142786 315 1311867180.9306049347 0.0771774352 0.0698148806 0.0880107805 0.0060815548 0.1162360000 28141525 955859216 1782829056 -0.4162024558 0.0184350219 -0.1514720321 316 1311867180.9631829262 0.0768411756 0.0698371157 0.0880107805 0.0060819626 0.1343560000 28143291 955859216 1784479744 -0.4155229926 0.0181997865 -0.1514152139 317 1311867180.9948179722 0.0773060992 0.0698606772 0.0880107805 0.0060733327 0.1385510000 28145025 955859216 1783398400 -0.4137009382 0.0187206790 -0.1509163380 318 1311867181.0308310986 0.0777931288 0.0698856220 0.0880107805 0.0060661827 0.0985370000 28146855 955859216 1782349824 -0.4120256901 0.0174016710 -0.1506519169 319 1311867181.0627830029 0.0777686387 0.0699103337 0.0880107805 0.0060650159 0.0825040000 28148653 955859216 1781477376 -0.4101576507 0.0171767008 -0.1504421532 320 1311867181.0948719978 0.0779158324 0.0699353509 0.0880107805 0.0060637425 0.1346600000 28150419 955859216 1780572160 -0.4073114097 0.0173161868 -0.1502953917 321 1311867181.1311910152 0.0777581930 0.0699597211 0.0880107805 0.0060561316 0.1531080000 28152249 955859216 1779699712 -0.4044528902 0.0177594647 -0.1503036916 322 1311867181.1629528999 0.0769591033 0.0699814583 0.0880107805 0.0060579834 0.1086750000 28154015 955859216 1781321728 -0.4034018219 0.0170989707 -0.1504985988 323 1311867181.1972830296 0.0765311867 0.0700017361 0.0880107805 0.0060490845 0.1147120000 28155813 955859216 1783083008 -0.4015758634 0.0166513957 -0.1504906416 324 1311867181.2342460155 0.0761960670 0.0700208544 0.0880107805 0.0060422541 0.0986210000 28157675 955859216 1784733696 -0.3997412324 0.0162712950 -0.1506787986 325 1311867181.2629361153 0.0763450339 0.0700403134 0.0880107805 0.0060333156 0.0776570000 28159377 955859216 1783615488 -0.3979021609 0.0163182318 -0.1504085660 326 1311867181.2948091030 0.0764065757 0.0700598418 0.0880107805 0.0060244476 0.1195900000 28161111 955859216 1782857728 -0.3960367441 0.0167349800 -0.1503576040 327 1311867181.3317139149 0.0763441771 0.0700790600 0.0880107805 0.0060207141 0.1083940000 28162973 955859216 1781731328 -0.3941847086 0.0166869145 -0.1504155099 328 1311867181.3626708984 0.0766776130 0.0700991775 0.0880107805 0.0060233509 0.1353890000 28164707 955859216 1780842496 -0.3923314512 0.0183414537 -0.1498967707 329 1311867181.3948218822 0.0766158551 0.0701189850 0.0880107805 0.0060158004 0.1303540000 28166473 955859216 1782607872 -0.3911020756 0.0171142556 -0.1498435140 330 1311867181.4308950901 0.0758122653 0.0701362374 0.0880107805 0.0060073834 0.1548350000 28168239 955859216 1784352768 -0.3900787830 0.0167920887 -0.1497488916 331 1311867181.4628310204 0.0759264007 0.0701537303 0.0880107805 0.0060031629 0.0990580000 28170005 955859216 1783361536 -0.3877892792 0.0160919372 -0.1492760330 332 1311867181.4963610172 0.0761609823 0.0701718245 0.0880107805 0.0060137750 0.0981890000 28171803 955859216 1782239232 -0.3844667673 0.0160925519 -0.1492828429 333 1311867181.5359110832 0.0756805986 0.0701883673 0.0880107805 0.0060088839 0.0896830000 28173665 955859216 1781477376 -0.3831347525 0.0156678427 -0.1490145326 334 1311867181.5671720505 0.0750788748 0.0702030096 0.0880107805 0.0060040090 0.1096020000 28175399 955859216 1780334592 -0.3818370700 0.0150825707 -0.1493205726 335 1311867181.5948610306 0.0751767531 0.0702178566 0.0880107805 0.0060003732 0.0706820000 28177069 955859216 1779572736 -0.3801370859 0.0160669703 -0.1493361890 336 1311867181.6313591003 0.0757221282 0.0702342383 0.0880107805 0.0059994070 0.0838260000 28178931 955859216 1778556928 -0.3780593872 0.0153817628 -0.1494157761 337 1311867181.6628570557 0.0751545951 0.0702488388 0.0880107805 0.0059944752 0.0997480000 28180697 955859216 1777795072 -0.3767617643 0.0139422975 -0.1498695016 338 1311867181.6949229240 0.0748730302 0.0702625198 0.0880107805 0.0059873651 0.0843610000 28182431 955859216 1777033216 -0.3756291568 0.0142883072 -0.1501299590 339 1311867181.7310829163 0.0752369687 0.0702771937 0.0880107805 0.0059925441 0.1212680000 28184261 955859216 1776271360 -0.3734774590 0.0134335598 -0.1504141837 340 1311867181.7634840012 0.0746505037 0.0702900564 0.0880107805 0.0059842485 0.1328980000 28186059 955859216 1775128576 -0.3724275231 0.0122146504 -0.1509193629 341 1311867181.7948980331 0.0742168948 0.0703015721 0.0880107805 0.0059836414 0.1518240000 28187761 955859216 1776758784 -0.3705674112 0.0124920737 -0.1510774642 342 1311867181.8308010101 0.0739719048 0.0703123040 0.0880107805 0.0059796432 0.1102160000 28189591 955859216 1778257920 -0.3687585294 0.0111873886 -0.1512126774 343 1311867181.8627979755 0.0740514174 0.0703232052 0.0880107805 0.0059733725 0.0777030000 28191389 955859216 1779908608 -0.3672359288 0.0104042394 -0.1513804644 344 1311867181.8949289322 0.0735238120 0.0703325093 0.0880107805 0.0059677878 0.0761480000 28193123 955859216 1781592064 -0.3653275371 0.0106718326 -0.1511760205 345 1311867181.9307990074 0.0727996305 0.0703396604 0.0880107805 0.0059678264 0.0754680000 28194985 955859216 1783336960 -0.3641571999 0.0101911481 -0.1512229890 346 1311867181.9629189968 0.0723034665 0.0703453361 0.0880107805 0.0059633633 0.1148040000 28196751 955859216 1784987648 -0.3625027537 0.0097917616 -0.1510685086 347 1311867181.9955599308 0.0718409941 0.0703496464 0.0880107805 0.0059823785 0.0975900000 28198517 955859216 1783758848 -0.3611253202 0.0089142267 -0.1503825486 348 1311867182.0320639610 0.0718951076 0.0703540874 0.0880107805 0.0059747072 0.0950020000 28200347 955859216 1782493184 -0.3588096499 0.0081940945 -0.1500327438 349 1311867182.0629000664 0.0718571246 0.0703583941 0.0880107805 0.0059683320 0.1086800000 28202113 955859216 1781731328 -0.3570490479 0.0081405472 -0.1496604979 350 1311867182.0948839188 0.0724217966 0.0703642895 0.0880107805 0.0059709677 0.1415920000 28203847 955859216 1778782208 -0.3550837636 0.0076809200 -0.1494274139 351 1311867182.1314840317 0.0725125000 0.0703704098 0.0880107805 0.0059632832 0.1094790000 28205709 955859216 1779826688 -0.3534142673 0.0074243951 -0.1488848329 352 1311867182.1629920006 0.0719144419 0.0703747962 0.0880107805 0.0059559278 0.1338570000 28207475 955859216 1778810880 -0.3520275056 0.0077050156 -0.1486650407 353 1311867182.1994500160 0.0714400634 0.0703778140 0.0880107805 0.0059515156 0.0952400000 28209273 955859216 1775607808 -0.3512965143 0.0072250478 -0.1482021809 354 1311867182.2307739258 0.0712795183 0.0703803612 0.0880107805 0.0059482854 0.0936020000 28211007 955859216 1774338048 -0.3499892056 0.0067210714 -0.1477914751 355 1311867182.2629120350 0.0711744130 0.0703825979 0.0880107805 0.0059445561 0.1138970000 28212805 955859216 1775509504 -0.3489239812 0.0066992873 -0.1472584754 356 1311867182.2973539829 0.0713526532 0.0703853228 0.0880107805 0.0059412236 0.1288380000 28214603 955859216 1774350336 -0.3472209871 0.0053619514 -0.1471475810 357 1311867182.3308460712 0.0710533559 0.0703871940 0.0880107805 0.0059575881 0.1358450000 28216369 955859216 1775869952 -0.3463296294 0.0051248795 -0.1465688497 358 1311867182.3629670143 0.0704732016 0.0703874343 0.0880107805 0.0059771434 0.1368930000 28218167 955859216 1777369088 -0.3456560969 0.0047218711 -0.1460963935 359 1311867182.3990368843 0.0703459829 0.0703873188 0.0880107805 0.0059757106 0.1513800000 28219965 955859216 1779019776 -0.3443853557 0.0037320128 -0.1456400901 360 1311867182.4308118820 0.0702045411 0.0703868111 0.0880107805 0.0059737600 0.1180480000 28221731 955859216 1780703232 -0.3434841633 0.0021003385 -0.1456248760 361 1311867182.4629440308 0.0691253766 0.0703833168 0.0880107805 0.0059711795 0.1532550000 28223529 955859216 1782448128 -0.3430025578 0.0018279627 -0.1456305087 362 1311867182.4969599247 0.0685640723 0.0703782913 0.0880107805 0.0059682945 0.1133390000 28225295 955859216 1784098816 -0.3424068987 0.0005491413 -0.1455394328 363 1311867182.5309500694 0.0679129809 0.0703714998 0.0880107805 0.0059616938 0.0774390000 28227093 955859216 1785876480 -0.3414541781 -0.0004955465 -0.1460415125 364 1311867182.5629699230 0.0671246871 0.0703625800 0.0880107805 0.0059587268 0.0782220000 28228859 955859216 1784651776 -0.3403044343 -0.0005896715 -0.1463543475 365 1311867182.6036369801 0.0634621754 0.0703436748 0.0880107805 0.0059550871 0.1142310000 28230753 955859216 1783762944 -0.3421101570 -0.0011604400 -0.1474165320 366 1311867182.6308450699 0.0624735430 0.0703221717 0.0880107805 0.0059713239 0.0736480000 28232423 955859216 1782874112 -0.3420640826 -0.0021385562 -0.1478875130 367 1311867182.6635921001 0.0620465726 0.0702996224 0.0880107805 0.0059639162 0.0757360000 28234221 955859216 1781731328 -0.3406483233 -0.0024596115 -0.1480642110 368 1311867182.6970019341 0.0612995699 0.0702751657 0.0880107805 0.0059630500 0.1114690000 28235987 955859216 1780715520 -0.3392498493 -0.0030647377 -0.1483611315 369 1311867182.7330639362 0.0607010089 0.0702492195 0.0880107805 0.0059581271 0.0917680000 28237817 955859216 1779699712 -0.3370963037 -0.0035509598 -0.1488501728 370 1311867182.7631130219 0.0606976710 0.0702234045 0.0880107805 0.0059524457 0.1334800000 28239487 955859216 1775112192 -0.3353033960 -0.0037449058 -0.1487702280 371 1311867182.7970550060 0.0599967614 0.0701958394 0.0880107805 0.0059445728 0.1089600000 28241317 955859216 1776771072 -0.3342558146 -0.0048554069 -0.1489488184 372 1311867182.8306989670 0.0594995469 0.0701670859 0.0880107805 0.0059379298 0.0768360000 28243083 955859216 1778556928 -0.3326409161 -0.0054228851 -0.1492096484 373 1311867182.8641169071 0.0582733862 0.0701351993 0.0880107805 0.0059347772 0.0928140000 28244849 955859216 1779908608 -0.3315245509 -0.0056371591 -0.1492526978 374 1311867182.8969969749 0.0585592203 0.0701042475 0.0880107805 0.0059270337 0.0951040000 28246647 955859216 1781592064 -0.3291659355 -0.0062193857 -0.1490522623 375 1311867182.9318990707 0.0590212345 0.0700746928 0.0880107805 0.0059198888 0.0791490000 28248445 955859216 1783336960 -0.3263075650 -0.0056932070 -0.1489107758 376 1311867182.9630720615 0.0592390448 0.0700458746 0.0880107805 0.0059122339 0.1157950000 28250211 955859216 1784987648 -0.3239889145 -0.0055973469 -0.1486104280 377 1311867182.9983949661 0.0590388589 0.0700166783 0.0880107805 0.0059209057 0.1133530000 28252009 955859216 1784037376 -0.3230632246 -0.0062605031 -0.1482121795 378 1311867183.0308830738 0.0587379336 0.0699868403 0.0880107805 0.0059133733 0.0948420000 28253775 955859216 1782857728 -0.3214961886 -0.0069197658 -0.1477984935 379 1311867183.0628600121 0.0591585673 0.0699582697 0.0880107805 0.0059064282 0.0932940000 28255573 955859216 1781985280 -0.3186679184 -0.0062218588 -0.1474335641 380 1311867183.1000499725 0.0584478900 0.0699279792 0.0880107805 0.0059301259 0.1130890000 28257371 955859216 1780842496 -0.3172091544 -0.0072139734 -0.1471096277 381 1311867183.1344780922 0.0581112802 0.0698969643 0.0880107805 0.0059254215 0.0942840000 28259201 955859216 1779826688 -0.3158122301 -0.0069450713 -0.1467105746 382 1311867183.1673240662 0.0582026280 0.0698663508 0.0880107805 0.0059198208 0.1155640000 28260999 955859216 1777258496 -0.3140138388 -0.0062982459 -0.1461766660 383 1311867183.2004919052 0.0578580648 0.0698349976 0.0880107805 0.0059143874 0.1120970000 28262765 955859216 1778049024 -0.3132671416 -0.0075425794 -0.1456234902 384 1311867183.2311279774 0.0581972338 0.0698046909 0.0880107805 0.0059070311 0.1165260000 28264499 955859216 1777143808 -0.3115971684 -0.0080292597 -0.1451884508 385 1311867183.2633349895 0.0584514551 0.0697752020 0.0880107805 0.0059009072 0.1322490000 28266297 955859216 1774993408 -0.3094685972 -0.0077837193 -0.1449125856 386 1311867183.2991099358 0.0581921600 0.0697451941 0.0880107805 0.0058954821 0.1243400000 28268095 955859216 1775128576 -0.3085621595 -0.0092788609 -0.1448946744 387 1311867183.3320920467 0.0581962988 0.0697153520 0.0880107805 0.0058964270 0.1376980000 28269893 955859216 1774112768 -0.3070203662 -0.0090474477 -0.1447609961 388 1311867183.3695240021 0.0578992143 0.0696848980 0.0880107805 0.0058889454 0.1341880000 28271755 955859216 1775763456 -0.3057577610 -0.0093995649 -0.1444402188 389 1311867183.3986210823 0.0576572828 0.0696539787 0.0880107805 0.0058827922 0.1308530000 28273457 955859216 1777147904 -0.3046047390 -0.0107011897 -0.1447690874 390 1311867183.4311549664 0.0573799387 0.0696225068 0.0880107805 0.0058912081 0.1175380000 28275223 955859216 1778892800 -0.3032274544 -0.0104223704 -0.1445723474 391 1311867183.4667448997 0.0574172921 0.0695912914 0.0880107805 0.0058890600 0.1180860000 28277053 955859216 1780576256 -0.3011361659 -0.0103618158 -0.1441466808 392 1311867183.4988338947 0.0566296577 0.0695582260 0.0880107805 0.0059132972 0.1528180000 28278851 955859216 1782321152 -0.2998838723 -0.0116410600 -0.1442619860 393 1311867183.5321829319 0.0565568283 0.0695251436 0.0880107805 0.0059064809 0.1083820000 28280617 955859216 1784004608 -0.2980965078 -0.0122133233 -0.1439315677 394 1311867183.5661609173 0.0562357046 0.0694914141 0.0880107805 0.0059003324 0.0969490000 28282415 955859216 1785749504 -0.2965715826 -0.0116959149 -0.1435152292 395 1311867183.5985479355 0.0559951700 0.0694572464 0.0880107805 0.0058971737 0.1219530000 28284181 955859216 1784508416 -0.2944768965 -0.0126989400 -0.1433454156 396 1311867183.6310880184 0.0559893027 0.0694232364 0.0880107805 0.0059121316 0.0916490000 28285947 955859216 1780576256 -0.2927263081 -0.0131257698 -0.1428888887 397 1311867183.6649260521 0.0554329082 0.0693879963 0.0880107805 0.0059073907 0.1486390000 28287745 955859216 1782222848 -0.2913586497 -0.0135017009 -0.1421770304 398 1311867183.6993949413 0.0559317060 0.0693541865 0.0880107805 0.0059005319 0.0924180000 28289575 955859216 1783844864 -0.2886551023 -0.0145108411 -0.1417367756 399 1311867183.7308928967 0.0553554371 0.0693191019 0.0880107805 0.0058982796 0.0757110000 28291277 955859216 1785495552 -0.2871581316 -0.0145907188 -0.1413238198 400 1311867183.7676479816 0.0551541708 0.0692836896 0.0880107805 0.0059023295 0.1170220000 28293139 955859216 1784524800 -0.2844654918 -0.0150841568 -0.1406959295 401 1311867183.7971870899 0.0548350178 0.0692476580 0.0880107805 0.0058949663 0.0919220000 28294841 955859216 1783382016 -0.2832337916 -0.0158864539 -0.1400466114 402 1311867183.8309071064 0.0549399853 0.0692120668 0.0880107805 0.0058878380 0.0761570000 28296607 955859216 1782493184 -0.2812696993 -0.0166200232 -0.1393146962 403 1311867183.8655049801 0.0548732504 0.0691764866 0.0880107805 0.0058830118 0.0924680000 28298405 955859216 1781477376 -0.2792797089 -0.0178557672 -0.1391570121 404 1311867183.8970971107 0.0547141694 0.0691406888 0.0880107805 0.0058761893 0.0939590000 28300139 955859216 1780334592 -0.2779279351 -0.0181592293 -0.1387862265 405 1311867183.9314939976 0.0542155355 0.0691038365 0.0880107805 0.0058694171 0.1101090000 28301969 955859216 1779318784 -0.2770366073 -0.0184458680 -0.1381098628 406 1311867183.9658319950 0.0539813973 0.0690665891 0.0880107805 0.0058689845 0.0953370000 28303735 955859216 1778302976 -0.2751821876 -0.0193166509 -0.1379531175 407 1311867183.9966781139 0.0536274016 0.0690286550 0.0880107805 0.0058643509 0.1151380000 28305501 955859216 1773690880 -0.2743133008 -0.0200254228 -0.1374554932 408 1311867184.0309689045 0.0537782349 0.0689912765 0.0880107805 0.0058870949 0.1322850000 28307299 955859216 1775476736 -0.2733391821 -0.0202414580 -0.1369454414 409 1311867184.0647850037 0.0537855551 0.0689540987 0.0880107805 0.0058828093 0.1135400000 28309097 955859216 1777139712 -0.2718124092 -0.0212748982 -0.1364662796 410 1311867184.0968890190 0.0534341484 0.0689162452 0.0880107805 0.0058758129 0.1350250000 28310831 955859216 1778528256 -0.2705453038 -0.0216378029 -0.1359546930 411 1311867184.1312260628 0.0535972789 0.0688789728 0.0880107805 0.0058690076 0.1148260000 28312629 955859216 1780289536 -0.2688221931 -0.0216130149 -0.1353037208 412 1311867184.1650640965 0.0531337336 0.0688407562 0.0880107805 0.0058625731 0.1199210000 28314395 955859216 1781940224 -0.2676930428 -0.0226737615 -0.1350511760 413 1311867184.1969559193 0.0531511232 0.0688027667 0.0880107805 0.0058569068 0.0903480000 28316193 955859216 1783623680 -0.2656222880 -0.0222430918 -0.1345842779 414 1311867184.2309360504 0.0535566658 0.0687659404 0.0880107805 0.0058501282 0.1131440000 28317991 955859216 1785368576 -0.2631507218 -0.0220769625 -0.1339166611 415 1311867184.2681369781 0.0524530560 0.0687266323 0.0880107805 0.0058468584 0.1549670000 28319853 955859216 1784270848 -0.2623454630 -0.0234675873 -0.1337892413 416 1311867184.2983899117 0.0524637401 0.0686875388 0.0880107805 0.0058416405 0.0948260000 28321587 955859216 1783001088 -0.2606472075 -0.0230377614 -0.1332115829 417 1311867184.3314700127 0.0526677482 0.0686491220 0.0880107805 0.0058347418 0.1496730000 28323353 955859216 1782239232 -0.2578454316 -0.0226455871 -0.1326959431 418 1311867184.3697841167 0.0518581681 0.0686089523 0.0880107805 0.0058365154 0.1110900000 28325215 955859216 1783844864 -0.2564698458 -0.0238889568 -0.1325744390 419 1311867184.4000220299 0.0519657023 0.0685692309 0.0880107805 0.0058753859 0.0923230000 28326949 955859216 1785495552 -0.2544729710 -0.0236972235 -0.1321375221 420 1311867184.4310610294 0.0532798767 0.0685328277 0.0880107805 0.0058720840 0.0980800000 28328715 955859216 1784672256 -0.2507975698 -0.0231864229 -0.1316345930 421 1311867184.4655809402 0.0523339137 0.0684943504 0.0880107805 0.0058677540 0.0956280000 28330513 955859216 1783382016 -0.2502497733 -0.0249482784 -0.1317693740 422 1311867184.5037670135 0.0516576245 0.0684544530 0.0880107805 0.0059076995 0.1153010000 28332375 955859216 1782493184 -0.2484028190 -0.0260269158 -0.1320645064 423 1311867184.5310881138 0.0521491393 0.0684159061 0.0880107805 0.0059315450 0.1552840000 28334077 955859216 1778655232 -0.2457838058 -0.0253973119 -0.1325674057 424 1311867184.5682930946 0.0515506566 0.0683761296 0.0880107805 0.0059260221 0.1076600000 28335939 955859216 1780334592 -0.2434806675 -0.0256963503 -0.1330537796 425 1311867184.6018071175 0.0503707863 0.0683337641 0.0880107805 0.0059194315 0.1348170000 28337705 955859216 1781972992 -0.2420517504 -0.0267938413 -0.1334886998 426 1311867184.6367399693 0.0496209227 0.0682898372 0.0880107805 0.0059135624 0.1141890000 28339535 955859216 1783717888 -0.2405585349 -0.0269361231 -0.1328917146 427 1311867184.6662440300 0.0493530668 0.0682454888 0.0880107805 0.0059212966 0.0928810000 28341237 955859216 1785384960 -0.2377677709 -0.0280342773 -0.1326140463 428 1311867184.6994929314 0.0487674475 0.0681999794 0.0880107805 0.0059174027 0.0993210000 28343067 955859216 1784397824 -0.2356752753 -0.0294456221 -0.1324470192 429 1311867184.7359158993 0.0484180078 0.0681538676 0.0880107805 0.0059193426 0.0950550000 28344833 955859216 1783255040 -0.2332586646 -0.0291863419 -0.1317108721 430 1311867184.7690689564 0.0484254770 0.0681079876 0.0880107805 0.0059182958 0.0884490000 28346663 955859216 1782239232 -0.2313095480 -0.0307659376 -0.1308372617 431 1311867184.8001279831 0.0479022712 0.0680611066 0.0880107805 0.0059168807 0.0943540000 28348397 955859216 1781096448 -0.2291048318 -0.0312468391 -0.1300868541 432 1311867184.8348441124 0.0477545075 0.0680141006 0.0880107805 0.0059105246 0.1175380000 28350163 955859216 1780080640 -0.2262576669 -0.0312728435 -0.1290689558 433 1311867184.8690660000 0.0469631106 0.0679654840 0.0880107805 0.0059040429 0.1287990000 28351961 955859216 1779064832 -0.2243564576 -0.0323647037 -0.1282167435 434 1311867184.9055209160 0.0464283489 0.0679158592 0.0880107805 0.0058989093 0.1143570000 28353727 955859216 1780715520 -0.2215799838 -0.0329136029 -0.1271086484 435 1311867184.9332280159 0.0467287190 0.0678671532 0.0880107805 0.0058938793 0.0933130000 28355397 955859216 1782067200 -0.2182141691 -0.0328077227 -0.1254775673 436 1311867184.9656410217 0.0464557819 0.0678180445 0.0880107805 0.0058930820 0.0767530000 28357163 955859216 1783844864 -0.2161513120 -0.0342356600 -0.1240759194 437 1311867184.9983251095 0.0458218046 0.0677677099 0.0880107805 0.0058915930 0.0923290000 28358961 955859216 1785495552 -0.2133717835 -0.0352654159 -0.1227997392 438 1311867185.0360550880 0.0457126014 0.0677173557 0.0880107805 0.0058853273 0.1208590000 28360791 955859216 1784254464 -0.2099020481 -0.0355230905 -0.1210612208 439 1311867185.0652348995 0.0455411486 0.0676668405 0.0880107805 0.0058810410 0.0927750000 28362525 955859216 1783111680 -0.2076434940 -0.0366416797 -0.1196280420 440 1311867185.0991280079 0.0443113968 0.0676137599 0.0880107805 0.0058764391 0.0931710000 28364323 955859216 1781456896 -0.2061187327 -0.0366334058 -0.1182153299 441 1311867185.1360778809 0.0439771116 0.0675601621 0.0880107805 0.0058737211 0.0930290000 28366153 955859216 1780969472 -0.2033310533 -0.0369728245 -0.1162707508 442 1311867185.1648709774 0.0439500660 0.0675067456 0.0880107805 0.0058696189 0.0783040000 28367887 955859216 1779699712 -0.2004478425 -0.0381019637 -0.1145661101 443 1311867185.2000720501 0.0437239520 0.0674530598 0.0880107805 0.0058646774 0.0906100000 28369653 955859216 1778429952 -0.1971316487 -0.0382125564 -0.1127815992 444 1311867185.2342920303 0.0442315899 0.0674007592 0.0880107805 0.0058663885 0.1043070000 28371483 955859216 1777414144 -0.1936589479 -0.0382772461 -0.1107075065 445 1311867185.2663950920 0.0438791178 0.0673479016 0.0880107805 0.0058600486 0.1201830000 28373281 955859216 1776398336 -0.1911179572 -0.0403221995 -0.1091795415 446 1311867185.2970550060 0.0435363948 0.0672945125 0.0880107805 0.0058774259 0.1123640000 28375015 955859216 1775382528 -0.1880550086 -0.0405017622 -0.1076306477 447 1311867185.3360140324 0.0436055623 0.0672415171 0.0880107805 0.0058709786 0.0937250000 28376877 955859216 1776988160 -0.1852333695 -0.0408783033 -0.1058821157 448 1311867185.3681778908 0.0435947515 0.0671887342 0.0880107805 0.0058649743 0.0951800000 28378675 955859216 1778671616 -0.1819892228 -0.0421107337 -0.1046820581 449 1311867185.4036509991 0.0432004333 0.0671353081 0.0880107805 0.0058624468 0.0956960000 28380473 955859216 1780416512 -0.1792454273 -0.0425646901 -0.1034568548 450 1311867185.4386389256 0.0435864963 0.0670829774 0.0880107805 0.0058565324 0.0991370000 28382271 955859216 1782067200 -0.1757436544 -0.0423205793 -0.1019662321 451 1311867185.4655449390 0.0445146933 0.0670329369 0.0880107805 0.0058503537 0.1130140000 28383941 955859216 1783750656 -0.1733379960 -0.0435545295 -0.1008881852 452 1311867185.5013909340 0.0442306772 0.0669824894 0.0880107805 0.0058603245 0.0937350000 28385771 955859216 1785495552 -0.1703361273 -0.0446995571 -0.1001224145 453 1311867185.5336329937 0.0442699306 0.0669323513 0.0880107805 0.0058766342 0.0786990000 28387537 955859216 1784524800 -0.1677034646 -0.0442393832 -0.0989779159 454 1311867185.5666799545 0.0441628806 0.0668821983 0.0880107805 0.0058706441 0.0930700000 28389335 955859216 1782226944 -0.1661602706 -0.0453452989 -0.0981687903 455 1311867185.5970540047 0.0437741391 0.0668314113 0.0880107805 0.0058699215 0.1052840000 28391069 955859216 1782239232 -0.1632552147 -0.0466122366 -0.0978190750 456 1311867185.6329469681 0.0436075591 0.0667804818 0.0880107805 0.0058920650 0.0967080000 28392899 955859216 1780953088 -0.1610368788 -0.0461448990 -0.0968460515 457 1311867185.6664180756 0.0435512476 0.0667296520 0.0880107805 0.0058927991 0.0957690000 28394665 955859216 1779953664 -0.1575682610 -0.0467212610 -0.0960333496 458 1311867185.6973390579 0.0430767499 0.0666780081 0.0880107805 0.0058863678 0.1151860000 28396431 955859216 1775357952 -0.1545882672 -0.0475500152 -0.0953710973 459 1311867185.7351899147 0.0431331843 0.0666267122 0.0880107805 0.0058821013 0.0880800000 28398261 955859216 1777012736 -0.1513401419 -0.0471755750 -0.0937975645 460 1311867185.7649769783 0.0434830189 0.0665763998 0.0880107805 0.0058768997 0.0943330000 28400027 955859216 1778810880 -0.1487649977 -0.0486350656 -0.0925234258 461 1311867185.7989649773 0.0435742438 0.0665265036 0.0880107805 0.0058826738 0.0929630000 28401793 955859216 1780162560 -0.1457792521 -0.0498548783 -0.0916995630 462 1311867185.8327999115 0.0435993783 0.0664768778 0.0880107805 0.0058779980 0.0756280000 28403623 955859216 1781940224 -0.1424425840 -0.0496282764 -0.0905869529 463 1311867185.8649098873 0.0436620936 0.0664276018 0.0880107805 0.0058726066 0.1147790000 28405389 955859216 1783590912 -0.1394505650 -0.0507659502 -0.0894356892 464 1311867185.9030420780 0.0427813455 0.0663766400 0.0880107805 0.0058675994 0.0953320000 28407219 955859216 1785274368 -0.1370232105 -0.0516735129 -0.0885710791 465 1311867185.9396789074 0.0426485874 0.0663256120 0.0880107805 0.0058630826 0.1185920000 28409081 955859216 1784143872 -0.1348603219 -0.0517540202 -0.0870025232 466 1311867185.9650609493 0.0431710221 0.0662759240 0.0880107805 0.0058752766 0.0953360000 28410687 955859216 1779941376 -0.1319664121 -0.0535619222 -0.0859609246 467 1311867186.0039470196 0.0431088954 0.0662263158 0.0880107805 0.0058716649 0.1308270000 28412581 955859216 1781600256 -0.1292058676 -0.0545483120 -0.0850159377 468 1311867186.0396919250 0.0434323065 0.0661776107 0.0880107805 0.0058748556 0.0885140000 28414411 955859216 1783336960 -0.1270018220 -0.0543139577 -0.0836603865 469 1311867186.0653240681 0.0437479019 0.0661297861 0.0880107805 0.0058770203 0.0775940000 28416113 955859216 1784987648 -0.1254048795 -0.0560005344 -0.0827322677 470 1311867186.1047339439 0.0430076644 0.0660805901 0.0880107805 0.0058715055 0.1169830000 28417975 955859216 1784016896 -0.1240659878 -0.0574249625 -0.0822106525 471 1311867186.1361179352 0.0440830924 0.0660338863 0.0880107805 0.0058672392 0.0906890000 28419709 955859216 1782874112 -0.1206754968 -0.0579629838 -0.0813604742 472 1311867186.1649448872 0.0440405197 0.0659872902 0.0880107805 0.0058626012 0.0925000000 28421443 955859216 1781731328 -0.1191873997 -0.0593059286 -0.0808856115 473 1311867186.2044749260 0.0438634045 0.0659405166 0.0880107805 0.0058564706 0.1125620000 28423337 955859216 1780715520 -0.1169010028 -0.0599833839 -0.0805242285 474 1311867186.2359659672 0.0439525880 0.0658941286 0.0880107805 0.0058523086 0.1067540000 28425071 955859216 1779699712 -0.1150294170 -0.0603246614 -0.0797609240 475 1311867186.2674899101 0.0435930267 0.0658471789 0.0880107805 0.0058463439 0.1008770000 28426837 955859216 1778810880 -0.1139797941 -0.0614443682 -0.0791199058 476 1311867186.3030838966 0.0431578755 0.0657995123 0.0880107805 0.0058420428 0.0940770000 28428667 955859216 1780449280 -0.1119674742 -0.0617613010 -0.0784805492 477 1311867186.3349270821 0.0434821062 0.0657527253 0.0880107805 0.0058379413 0.0951690000 28430401 955859216 1782194176 -0.1089249998 -0.0619413033 -0.0772983953 478 1311867186.3670160770 0.0430191569 0.0657051655 0.0880107805 0.0058385257 0.0958250000 28432135 955859216 1783861248 -0.1075896025 -0.0637135133 -0.0765924305 479 1311867186.4019849300 0.0429240428 0.0656576058 0.0880107805 0.0058428378 0.0950310000 28433933 955859216 1785622528 -0.1055075303 -0.0639544800 -0.0756398141 480 1311867186.4360210896 0.0434542894 0.0656113489 0.0880107805 0.0058412561 0.0805170000 28435731 955859216 1784504320 -0.1025604904 -0.0636612847 -0.0739538670 481 1311867186.4659481049 0.0433709286 0.0655651110 0.0880107805 0.0058373203 0.1077390000 28437465 955859216 1783762944 -0.1013351157 -0.0654731542 -0.0727912188 482 1311867186.5031139851 0.0427455977 0.0655177676 0.0880107805 0.0058324825 0.0786580000 28439327 955859216 1782620160 -0.0997231081 -0.0665471703 -0.0719549954 483 1311867186.5363171101 0.0437488817 0.0654726974 0.0880107805 0.0058276853 0.0773590000 28441093 955859216 1778520064 -0.0967099965 -0.0661716387 -0.0703643933 484 1311867186.5651130676 0.0439740233 0.0654282787 0.0880107805 0.0058276026 0.1089560000 28442827 955859216 1780207616 -0.0951313674 -0.0676028579 -0.0696700141 485 1311867186.6014220715 0.0438836887 0.0653838569 0.0880107805 0.0058220296 0.0921550000 28444657 955859216 1781813248 -0.0937042609 -0.0685326755 -0.0694359988 486 1311867186.6362628937 0.0442816429 0.0653404367 0.0880107805 0.0058160563 0.1175670000 28446455 955859216 1783590912 -0.0916513875 -0.0689351037 -0.0691970214 487 1311867186.6650478840 0.0448573790 0.0652983770 0.0880107805 0.0058124398 0.1350220000 28448157 955859216 1785282560 -0.0899441317 -0.0686541423 -0.0689282417 488 1311867186.7043809891 0.0447106771 0.0652561891 0.0880107805 0.0058262814 0.1556290000 28450083 955859216 1784279040 -0.0882908404 -0.0690081194 -0.0692168325 489 1311867186.7337749004 0.0450468995 0.0652148613 0.0880107805 0.0058285217 0.0897240000 28451785 955859216 1783136256 -0.0863228142 -0.0677781925 -0.0693612248 490 1311867186.7673180103 0.0455701947 0.0651747701 0.0880107805 0.0058236581 0.0921720000 28453583 955859216 1782120448 -0.0842963457 -0.0670986399 -0.0692669228 491 1311867186.8047299385 0.0453891382 0.0651344735 0.0880107805 0.0058244248 0.0913000000 28455445 955859216 1780957184 -0.0828519017 -0.0680379122 -0.0699620694 492 1311867186.8340749741 0.0452650227 0.0650940885 0.0880107805 0.0058228298 0.0943540000 28457147 955859216 1779961856 -0.0815106183 -0.0667115226 -0.0702217296 493 1311867186.8775999546 0.0453977175 0.0650541364 0.0880107805 0.0058173646 0.0940500000 28459105 955859216 1778946048 -0.0790001824 -0.0652354658 -0.0703054890 494 1311867186.9052100182 0.0454173163 0.0650143858 0.0880107805 0.0058129592 0.0937660000 28460775 955859216 1777930240 -0.0776038095 -0.0648848116 -0.0704852343 495 1311867186.9334239960 0.0452810414 0.0649745204 0.0880107805 0.0058079398 0.0932310000 28462541 955859216 1776914432 -0.0758794472 -0.0643925741 -0.0706936494 496 1311867186.9663379192 0.0458215587 0.0649359056 0.0880107805 0.0058096810 0.0956170000 28464275 955859216 1775898624 -0.0733740330 -0.0624408498 -0.0704723895 497 1311867187.0017139912 0.0459818840 0.0648977687 0.0880107805 0.0058106031 0.0742740000 28466009 955859216 1774882816 -0.0709208250 -0.0621810928 -0.0706384629 498 1311867187.0336461067 0.0455542281 0.0648589263 0.0880107805 0.0058139310 0.0938180000 28467775 955859216 1773867008 -0.0691218972 -0.0612861775 -0.0709986016 499 1311867187.0749349594 0.0454394966 0.0648200096 0.0880107805 0.0058143920 0.0725060000 28469701 955859216 1773105152 -0.0677312016 -0.0593279526 -0.0706366822 500 1311867187.1016030312 0.0457566045 0.0647818827 0.0880107805 0.0058100413 0.0762260000 28471403 955859216 1771835392 -0.0648103952 -0.0585591272 -0.0704957619 501 1311867187.1342070103 0.0454210490 0.0647432384 0.0880107805 0.0058089346 0.1030340000 28473169 955859216 1770946560 -0.0634220019 -0.0599809028 -0.0708025321 502 1311867187.1710209846 0.0453816280 0.0647046694 0.0880107805 0.0058158633 0.1235290000 28474999 955859216 1769930752 -0.0615137294 -0.0589054562 -0.0707124844 503 1311867187.2041370869 0.0459948890 0.0646674730 0.0880107805 0.0058206489 0.1046180000 28476797 955859216 1768914944 -0.0587851740 -0.0582151450 -0.0707556009 504 1311867187.2331659794 0.0461028256 0.0646306384 0.0880107805 0.0058229059 0.0821040000 28478531 955859216 1770536960 -0.0556467138 -0.0590858944 -0.0714625567 505 1311867187.2707629204 0.0460350923 0.0645938156 0.0880107805 0.0058257863 0.1138050000 28480361 955859216 1772298240 -0.0533798002 -0.0579558685 -0.0717951059 506 1311867187.3015060425 0.0461017340 0.0645572699 0.0880107805 0.0058271265 0.0946620000 28482127 955859216 1773948928 -0.0513285547 -0.0579555370 -0.0721281618 507 1311867187.3336570263 0.0459997803 0.0645206674 0.0880107805 0.0058215307 0.1125170000 28483861 955859216 1775632384 -0.0497515202 -0.0586428195 -0.0728291646 508 1311867187.3707590103 0.0461761542 0.0644845562 0.0880107805 0.0058170168 0.0951170000 28485723 955859216 1777377280 -0.0483552106 -0.0585826002 -0.0732567683 509 1311867187.4033529758 0.0460749269 0.0644483879 0.0880107805 0.0058145845 0.0951840000 28487521 955859216 1779027968 -0.0468928404 -0.0586325899 -0.0738706663 510 1311867187.4335899353 0.0457939692 0.0644118106 0.0880107805 0.0058129120 0.0965840000 28489255 955859216 1780711424 -0.0451819636 -0.0591659695 -0.0744768158 511 1311867187.4763159752 0.0462187529 0.0643762078 0.0880107805 0.0058091544 0.0970240000 28491181 955859216 1782456320 -0.0426793136 -0.0588344112 -0.0748874843 512 1311867187.5056400299 0.0465725474 0.0643414350 0.0880107805 0.0058057228 0.0919330000 28492883 955859216 1784107008 -0.0400129333 -0.0593789779 -0.0755312592 513 1311867187.5342190266 0.0468392633 0.0643073177 0.0880107805 0.0058023585 0.1145030000 28535577 955859216 1783115776 -0.0372005068 -0.0598031245 -0.0763940141 514 1311867187.5709679127 0.0469314381 0.0642735125 0.0880107805 0.0057971187 0.0927790000 28621375 955859216 1781219328 -0.0344468504 -0.0600536689 -0.0772924796 515 1311867187.6045789719 0.0458074734 0.0642376561 0.0880107805 0.0058225909 0.1106940000 28623205 955859216 1781104640 -0.0331757516 -0.0601221696 -0.0786221102 516 1311867187.6353919506 0.0458576493 0.0642020359 0.0880107805 0.0058186685 0.1152880000 28624939 955859216 1780215808 -0.0304412767 -0.0605661795 -0.0798358992 517 1311867187.6707689762 0.0457099676 0.0641662679 0.0880107805 0.0058224322 0.1128190000 28626737 955859216 1775620096 -0.0273035411 -0.0596725568 -0.0808497444 518 1311867187.7035770416 0.0461943671 0.0641315731 0.0880107805 0.0058237867 0.0899300000 28628535 955859216 1777295360 -0.0247115400 -0.0593334548 -0.0815400705 519 1311867187.7345480919 0.0454226099 0.0640955250 0.0880107805 0.0058361158 0.1153630000 28630141 955859216 1779056640 -0.0228498559 -0.0610738806 -0.0830266103 520 1311867187.7707819939 0.0453105010 0.0640594000 0.0880107805 0.0058354203 0.1165430000 28631971 955859216 1780424704 -0.0202087909 -0.0596207827 -0.0837651342 521 1311867187.8017508984 0.0458001532 0.0640243534 0.0880107805 0.0058311063 0.0902530000 28633737 955859216 1782075392 -0.0173893441 -0.0589691587 -0.0845189020 522 1311867187.8339610100 0.0454421006 0.0639887553 0.0880107805 0.0058267685 0.0936780000 28635503 955859216 1783742464 -0.0153571675 -0.0589814223 -0.0853779241 523 1311867187.8708090782 0.0452047214 0.0639528393 0.0880107805 0.0058269283 0.1171320000 28637333 955859216 1785503744 -0.0124644944 -0.0580769964 -0.0859430581 524 1311867187.9038810730 0.0456273891 0.0639178671 0.0880107805 0.0058244850 0.1376910000 28639163 955859216 1784279040 -0.0091851633 -0.0573868901 -0.0864728391 525 1311867187.9363000393 0.0458156429 0.0638833867 0.0880107805 0.0058197852 0.0931770000 28640897 955859216 1783136256 -0.0060075582 -0.0570918210 -0.0871966928 526 1311867187.9713420868 0.0455787852 0.0638485870 0.0880107805 0.0058196921 0.1093670000 28642727 955859216 1782120448 -0.0030477769 -0.0578388087 -0.0883740559 527 1311867188.0047569275 0.0454626344 0.0638136991 0.0880107805 0.0058419681 0.0992050000 28644525 955859216 1781104640 -0.0004648396 -0.0568971485 -0.0893794894 528 1311867188.0333108902 0.0455913357 0.0637791870 0.0880107805 0.0058480596 0.1303280000 28646227 955859216 1776508928 0.0025866583 -0.0565105975 -0.0902371481 529 1311867188.0698699951 0.0453401692 0.0637443307 0.0880107805 0.0058425192 0.1120280000 28648025 955859216 1778294784 0.0057223313 -0.0576922968 -0.0916572958 530 1311867188.1088800430 0.0451590940 0.0637092642 0.0880107805 0.0058433237 0.1135160000 28649951 955859216 1779851264 0.0083651962 -0.0578629859 -0.0929633081 531 1311867188.1359970570 0.0439460948 0.0636720454 0.0880107805 0.0058504428 0.1356430000 28651621 955859216 1781313536 0.0120215677 -0.0569708608 -0.0940967873 532 1311867188.1703350544 0.0450414643 0.0636370255 0.0880107805 0.0058476504 0.1128930000 28653419 955859216 1782964224 0.0145003945 -0.0575900972 -0.0953803062 533 1311867188.2026720047 0.0447830856 0.0636016523 0.0880107805 0.0058491982 0.1530550000 28655217 955859216 1784647680 0.0163273681 -0.0581586063 -0.0967368037 534 1311867188.2352449894 0.0436166525 0.0635642272 0.0880107805 0.0058526294 0.0955150000 28656951 955859216 1783517184 0.0186485089 -0.0574770793 -0.0978971720 535 1311867188.2706460953 0.0443028174 0.0635282245 0.0880107805 0.0058499622 0.0944860000 28658781 955859216 1782374400 0.0218737051 -0.0572047234 -0.0990781635 536 1311867188.3047339916 0.0442581289 0.0634922729 0.0880107805 0.0058452479 0.0892100000 28660611 955859216 1781342208 0.0250867251 -0.0570760518 -0.1001989618 537 1311867188.3398799896 0.0441157706 0.0634561900 0.0880107805 0.0058407234 0.0929730000 28662441 955859216 1780342784 0.0273033921 -0.0563149303 -0.1010318473 538 1311867188.3718800545 0.0443945788 0.0634207595 0.0880107805 0.0058400744 0.0934130000 28664175 955859216 1779326976 0.0306045413 -0.0548934527 -0.1014998481 539 1311867188.4054470062 0.0442668162 0.0633852234 0.0880107805 0.0058410977 0.1138090000 28665941 955859216 1778184192 0.0338374488 -0.0543606989 -0.1020658687 540 1311867188.4398789406 0.0441451482 0.0633495937 0.0880107805 0.0058390144 0.1142040000 28667771 955859216 1777168384 0.0371375903 -0.0543378778 -0.1026916653 541 1311867188.4724500179 0.0445112027 0.0633147722 0.0880107805 0.0058417264 0.1502340000 28669537 955859216 1775878144 0.0394986607 -0.0524610989 -0.1028677151 542 1311867188.5049159527 0.0442999154 0.0632796895 0.0880107805 0.0058415356 0.1073980000 28671303 955859216 1771319296 0.0421402641 -0.0515270121 -0.1033002213 543 1311867188.5389990807 0.0441448689 0.0632444504 0.0880107805 0.0058433368 0.1139290000 28673133 955859216 1772974080 0.0447960794 -0.0517727882 -0.1039755195 544 1311867188.5723888874 0.0441308208 0.0632093150 0.0880107805 0.0058616323 0.1125530000 28674899 955859216 1774735360 0.0469272546 -0.0491706468 -0.1041218564 545 1311867188.6045958996 0.0447666645 0.0631754753 0.0880107805 0.0058563504 0.0923800000 28676665 955859216 1776107520 0.0494443960 -0.0485009030 -0.1040377989 546 1311867188.6398339272 0.0449520871 0.0631420991 0.0880107805 0.0058527109 0.0754800000 28678431 955859216 1777790976 0.0509334356 -0.0489110909 -0.1045935899 547 1311867188.6715080738 0.0454826802 0.0631098150 0.0880107805 0.0058528555 0.1156190000 28680229 955859216 1779535872 0.0537022837 -0.0479157567 -0.1050433218 548 1311867188.7038300037 0.0455107950 0.0630777000 0.0880107805 0.0058522034 0.0943130000 28681995 955859216 1781186560 0.0548598096 -0.0481771380 -0.1059096307 549 1311867188.7393829823 0.0453765839 0.0630454575 0.0880107805 0.0058573184 0.0935270000 28683793 955859216 1782964224 0.0561513975 -0.0487534627 -0.1071113050 550 1311867188.7721049786 0.0455420911 0.0630136332 0.0880107805 0.0058533937 0.1356730000 28685591 955859216 1784614912 0.0570665225 -0.0475933962 -0.1081641167 551 1311867188.8045220375 0.0463622324 0.0629834129 0.0880107805 0.0058535533 0.1379910000 28687389 955859216 1783369728 0.0592450798 -0.0462480746 -0.1089519188 552 1311867188.8402431011 0.0471819267 0.0629547870 0.0880107805 0.0058515589 0.0978860000 28689187 955859216 1782239232 0.0616392568 -0.0470016338 -0.1098726168 553 1311867188.8705990314 0.0476841964 0.0629271729 0.0880107805 0.0058490565 0.0839900000 28690921 955859216 1781223424 0.0632136315 -0.0465450510 -0.1108604819 554 1311867188.9016311169 0.0477642417 0.0628998030 0.0880107805 0.0058455403 0.0940460000 28692687 955859216 1780207616 0.0658182576 -0.0451899581 -0.1119455844 555 1311867188.9401769638 0.0483178422 0.0628735292 0.0880107805 0.0058439958 0.0940480000 28694581 955859216 1779191808 0.0695507675 -0.0457697287 -0.1131130755 556 1311867188.9709990025 0.0483354032 0.0628473815 0.0880107805 0.0058433432 0.0946640000 28696283 955859216 1778176000 0.0724069476 -0.0458200276 -0.1139359102 557 1311867189.0052258968 0.0485676341 0.0628217446 0.0880107805 0.0058390545 0.0938650000 28698113 955859216 1777160192 0.0763361454 -0.0449202210 -0.1143332347 558 1311867189.0400099754 0.0489892550 0.0627969552 0.0880107805 0.0058401365 0.0937200000 28699879 955859216 1776144384 0.0790005326 -0.0447598845 -0.1147527099 559 1311867189.0724329948 0.0488309897 0.0627719714 0.0880107805 0.0058387997 0.0937420000 28701709 955859216 1775112192 0.0822048411 -0.0447343662 -0.1149133667 560 1311867189.1026360989 0.0491751879 0.0627476914 0.0880107805 0.0058379612 0.0925220000 28703443 955859216 1774112768 0.0845787153 -0.0437320061 -0.1144069135 561 1311867189.1417639256 0.0494139604 0.0627239236 0.0880107805 0.0058335272 0.0933130000 28705337 955859216 1773096960 0.0869898498 -0.0436780863 -0.1136155948 562 1311867189.1717920303 0.0492350608 0.0626999221 0.0880107805 0.0058303521 0.0932820000 28707071 955859216 1772081152 0.0880240351 -0.0439693220 -0.1128553450 563 1311867189.2019069195 0.0494772829 0.0626764361 0.0880107805 0.0058257410 0.0929660000 28708805 955859216 1771065344 0.0903529227 -0.0437324382 -0.1116940230 564 1311867189.2390630245 0.0496000499 0.0626532510 0.0880107805 0.0058231642 0.0932910000 28710635 955859216 1770049536 0.0910096765 -0.0439338610 -0.1108968258 565 1311867189.2722640038 0.0495466478 0.0626300534 0.0880107805 0.0058184809 0.0929710000 28712401 955859216 1769160704 0.0925639793 -0.0446686260 -0.1100537702 566 1311867189.3046789169 0.0496609993 0.0626071399 0.0880107805 0.0058141708 0.0777840000 28714199 955859216 1768398848 0.0955805182 -0.0452370569 -0.1089540273 567 1311867189.3397970200 0.0491510145 0.0625834078 0.0880107805 0.0058175817 0.1047600000 28715997 955859216 1767383040 0.0972959399 -0.0466583520 -0.1082506701 568 1311867189.3720359802 0.0497474633 0.0625608093 0.0880107805 0.0058548009 0.1212180000 28717763 955859216 1766367232 0.0994391292 -0.0475852191 -0.1074350178 569 1311867189.4056949615 0.0497118682 0.0625382277 0.0880107805 0.0058586290 0.1142150000 28719561 955859216 1762021376 0.1035316885 -0.0472558662 -0.1059643179 570 1311867189.4405019283 0.0495848320 0.0625155024 0.0880107805 0.0058602900 0.0898960000 28721359 955859216 1763696640 0.1061354652 -0.0490154587 -0.1052605212 571 1311867189.4729130268 0.0503149405 0.0624941354 0.0880107805 0.0058565221 0.0924130000 28723157 955859216 1765457920 0.1089142710 -0.0507990345 -0.1045258790 572 1311867189.5060400963 0.0501632951 0.0624725780 0.0880107805 0.0058536472 0.0768860000 28724923 955859216 1766830080 0.1118536517 -0.0512223653 -0.1041638702 573 1311867189.5394289494 0.0502914116 0.0624513194 0.0880107805 0.0058493829 0.1155720000 28726689 955859216 1768513536 0.1153753549 -0.0534535460 -0.1039201543 574 1311867189.5720269680 0.0501055270 0.0624298111 0.0880107805 0.0058474761 0.1355170000 28728487 955859216 1770258432 0.1186418533 -0.0559569895 -0.1044373438 575 1311867189.6112909317 0.0506292991 0.0624092884 0.0880107805 0.0058450584 0.1083590000 28730349 955859216 1771909120 0.1233160570 -0.0563252978 -0.1044380367 576 1311867189.6424219608 0.0508034565 0.0623891394 0.0880107805 0.0058411443 0.1175890000 28732115 955859216 1773686784 0.1263496727 -0.0569592267 -0.1045517400 577 1311867189.6728401184 0.0508668348 0.0623691701 0.0880107805 0.0058363524 0.1320650000 28733881 955859216 1775337472 0.1290864944 -0.0584683344 -0.1047998890 578 1311867189.7065870762 0.0514817461 0.0623503337 0.0880107805 0.0058346743 0.1158280000 28735647 955859216 1777004544 0.1321580261 -0.0589718707 -0.1047184765 579 1311867189.7401719093 0.0513800755 0.0623313868 0.0880107805 0.0058301379 0.0936460000 28737445 955859216 1778765824 0.1366481483 -0.0587946251 -0.1041563600 580 1311867189.7729759216 0.0514806099 0.0623126786 0.0880107805 0.0058251630 0.1374290000 28739211 955859216 1780416512 0.1400294155 -0.0587270893 -0.1038602889 581 1311867189.8073968887 0.0510124676 0.0622932290 0.0880107805 0.0058235709 0.1314500000 28741009 955859216 1782099968 0.1432924569 -0.0597901009 -0.1033436581 582 1311867189.8405311108 0.0511751883 0.0622741258 0.0880107805 0.0058201502 0.1071510000 28742775 955859216 1783844864 0.1472202837 -0.0601828843 -0.1022689939 583 1311867189.8713529110 0.0508538671 0.0622545370 0.0880107805 0.0058162937 0.0760380000 28744541 955859216 1785528320 0.1513426006 -0.0611559190 -0.1014332026 584 1311867189.9102680683 0.0507531650 0.0622348429 0.0880107805 0.0058166127 0.0773210000 28746403 955859216 1784397824 0.1538394541 -0.0627394468 -0.1012456119 585 1311867189.9402260780 0.0504220352 0.0622146501 0.0880107805 0.0058130612 0.0931920000 28748169 955859216 1783255040 0.1577786207 -0.0628381521 -0.1009015888 586 1311867189.9727621078 0.0501166359 0.0621940050 0.0880107805 0.0058081899 0.0913580000 28749935 955859216 1782112256 0.1619320959 -0.0631140694 -0.1005781144 587 1311867190.0107009411 0.0503219813 0.0621737801 0.0880107805 0.0058062014 0.1111920000 28751765 955859216 1781096448 0.1652767956 -0.0637497902 -0.1004953682 588 1311867190.0402929783 0.0504663624 0.0621538695 0.0880107805 0.0058028885 0.1052820000 28753499 955859216 1780080640 0.1681002527 -0.0642165542 -0.1004237682 589 1311867190.0719039440 0.0506562665 0.0621343490 0.0880107805 0.0057985048 0.0751590000 28755265 955859216 1781686272 0.1707312465 -0.0650280342 -0.1004606634 590 1311867190.1096539497 0.0539907403 0.0621205462 0.0880107805 0.0058083757 0.0934600000 28757127 955859216 1783463936 0.1650573611 -0.0659066662 -0.1020769328 591 1311867190.1396369934 0.0549975447 0.0621084938 0.0880107805 0.0058066396 0.0773080000 28758893 955859216 1785114624 0.1661199331 -0.0655554757 -0.1026301160 592 1311867190.1706380844 0.0555958934 0.0620974928 0.0880107805 0.0058076541 0.0785730000 28760595 955859216 1783996416 0.1678515077 -0.0659636632 -0.1029816568 593 1311867190.2096021175 0.0564002767 0.0620878853 0.0880107805 0.0058035847 0.0933540000 28762489 955859216 1783001088 0.1689473540 -0.0678707212 -0.1037285775 594 1311867190.2394330502 0.0564672537 0.0620784230 0.0880107805 0.0058087516 0.0925950000 28764191 955859216 1781858304 0.1721891314 -0.0672959015 -0.1038670093 595 1311867190.2714810371 0.0568964481 0.0620697138 0.0880107805 0.0058103046 0.0941570000 28765989 955859216 1780842496 0.1742370576 -0.0675925985 -0.1041368246 596 1311867190.3072700500 0.0579299256 0.0620627678 0.0880107805 0.0058083922 0.0933550000 28767819 955859216 1779953664 0.1756745577 -0.0677674338 -0.1043319553 597 1311867190.3414731026 0.0575053729 0.0620551340 0.0880107805 0.0058054433 0.0931220000 28769617 955859216 1778937856 0.1794044077 -0.0678602308 -0.1041411608 598 1311867190.3716828823 0.0570107177 0.0620466985 0.0880107805 0.0058080718 0.0892930000 28771351 955859216 1777922048 0.1830766201 -0.0673643798 -0.1037017629 599 1311867190.4101090431 0.0578828938 0.0620397473 0.0880107805 0.0058060651 0.0757880000 28773181 955859216 1776906240 0.1845864356 -0.0676307455 -0.1037842184 600 1311867190.4394960403 0.0577468947 0.0620325925 0.0880107805 0.0058034449 0.1092410000 28774979 955859216 1775890432 0.1877593249 -0.0667658374 -0.1031779647 601 1311867190.4708199501 0.0578379147 0.0620256130 0.0880107805 0.0057993479 0.1215020000 28776681 955859216 1774858240 0.1903774291 -0.0672071055 -0.1027398556 602 1311867190.5097529888 0.0576149262 0.0620182863 0.0880107805 0.0057950880 0.1248800000 28778607 955859216 1773748224 0.1931035817 -0.0680753142 -0.1024010330 603 1311867190.5405189991 0.0582172200 0.0620119827 0.0880107805 0.0057971282 0.0849860000 28780309 955859216 1772589056 0.1953423619 -0.0670240521 -0.1021604016 604 1311867190.5708439350 0.0581713058 0.0620056240 0.0880107805 0.0057944586 0.0980040000 28782043 955859216 1771573248 0.1978594363 -0.0678044781 -0.1016076505 605 1311867190.6067750454 0.0583270788 0.0619995437 0.0880107805 0.0057901600 0.1162690000 28783873 955859216 1768030208 0.1999090910 -0.0684035793 -0.1014925838 606 1311867190.6389939785 0.0578686818 0.0619927271 0.0880107805 0.0057864578 0.1263570000 28785671 955859216 1769668608 0.2034605742 -0.0681625456 -0.1007369012 607 1311867190.6723659039 0.0577949248 0.0619858115 0.0880107805 0.0057825172 0.1090350000 28787437 955859216 1771147264 0.2067629397 -0.0692632645 -0.0999237746 608 1311867190.7114980221 0.0583787523 0.0619798788 0.0880107805 0.0057795829 0.0912530000 28789299 955859216 1772830720 0.2085820436 -0.0696670488 -0.0993064120 609 1311867190.7392649651 0.0578398071 0.0619730806 0.0880107805 0.0057751972 0.0771110000 28790969 955859216 1774575616 0.2114229947 -0.0701952949 -0.0984912142 610 1311867190.7751801014 0.0574976392 0.0619657439 0.0880107805 0.0057706805 0.0930420000 28792799 955859216 1776226304 0.2140978724 -0.0704693943 -0.0979161784 611 1311867190.8070900440 0.0575725287 0.0619585537 0.0880107805 0.0057669419 0.0966130000 28794597 955859216 1777909760 0.2166952193 -0.0707644969 -0.0970434099 612 1311867190.8414280415 0.0571774058 0.0619507413 0.0880107805 0.0057688452 0.0782520000 28796395 955859216 1779654656 0.2193392366 -0.0721125826 -0.0962743461 613 1311867190.8739249706 0.0576344728 0.0619437001 0.0880107805 0.0057648629 0.1159650000 28798161 955859216 1781305344 0.2209388912 -0.0731055066 -0.0956424177 614 1311867190.9076139927 0.0577487499 0.0619368679 0.0880107805 0.0057603227 0.1157700000 28799959 955859216 1782988800 0.2231560349 -0.0732171983 -0.0948305652 615 1311867190.9393599033 0.0571812093 0.0619291352 0.0880107805 0.0057571893 0.0743700000 28801693 955859216 1784733696 0.2263704538 -0.0746443495 -0.0939772353 616 1311867190.9741609097 0.0572055131 0.0619214669 0.0880107805 0.0057528519 0.0963990000 28803523 955859216 1783619584 0.2285716832 -0.0758609176 -0.0934175923 617 1311867191.0085949898 0.0573712140 0.0619140921 0.0880107805 0.0057557395 0.1336960000 28805321 955859216 1782493184 0.2313518226 -0.0749446601 -0.0924777761 618 1311867191.0396919250 0.0574988574 0.0619069477 0.0880107805 0.0057525279 0.1085150000 28807087 955859216 1777795072 0.2333980054 -0.0753596425 -0.0915031731 619 1311867191.0764329433 0.0578346066 0.0619003688 0.0880107805 0.0057504145 0.0912540000 28808917 955859216 1777639424 0.2347628176 -0.0774610862 -0.0911619365 620 1311867191.1103041172 0.0586929284 0.0618951955 0.0880107805 0.0057562279 0.0931580000 28810715 955859216 1778790400 0.2372995913 -0.0773107409 -0.0899060965 621 1311867191.1388139725 0.0577071048 0.0618884514 0.0880107805 0.0057682400 0.1388850000 28812449 955859216 1777795072 0.2414410710 -0.0777213499 -0.0887811482 622 1311867191.1742820740 0.0583808869 0.0618828123 0.0880107805 0.0057652281 0.1237830000 28814247 955859216 1776795648 0.2426100671 -0.0791612640 -0.0883169994 623 1311867191.2077920437 0.0587978549 0.0618778605 0.0880107805 0.0057607280 0.0793600000 28816045 955859216 1775620096 0.2452919185 -0.0787804946 -0.0873285234 624 1311867191.2408421040 0.0596282743 0.0618742554 0.0880107805 0.0057574057 0.1000030000 28817843 955859216 1774604288 0.2470106333 -0.0787752345 -0.0867190436 625 1311867191.2769579887 0.0602488667 0.0618716548 0.0880107805 0.0057551480 0.0930580000 28819641 955859216 1773604864 0.2491553128 -0.0794672817 -0.0861405581 626 1311867191.3085029125 0.0607298687 0.0618698308 0.0880107805 0.0057563303 0.0951210000 28821311 955859216 1769005056 0.2514647543 -0.0786454305 -0.0852514654 627 1311867191.3404779434 0.0606256388 0.0618678465 0.0880107805 0.0057531934 0.0935150000 28823077 955859216 1767235584 0.2543173134 -0.0792359337 -0.0843230858 628 1311867191.3794629574 0.0607237555 0.0618660247 0.0880107805 0.0057489573 0.0871640000 28824971 955859216 1769017344 0.2561985850 -0.0805855915 -0.0838624462 629 1311867191.4091579914 0.0602307878 0.0618634249 0.0880107805 0.0057459198 0.0747960000 28826673 955859216 1770684416 0.2593356967 -0.0812582746 -0.0830189958 630 1311867191.4415969849 0.0595377088 0.0618597333 0.0880107805 0.0057421831 0.0746290000 28828439 955859216 1772163072 0.2630209625 -0.0809378922 -0.0820771754 631 1311867191.4775309563 0.0599346384 0.0618566824 0.0880107805 0.0057427979 0.1143440000 28830237 955859216 1773846528 0.2639924884 -0.0823301151 -0.0817190632 632 1311867191.5075590611 0.0600444302 0.0618538150 0.0880107805 0.0057387925 0.0755090000 28831939 955859216 1775591424 0.2656361163 -0.0820076838 -0.0808870494 633 1311867191.5390620232 0.0595118105 0.0618501151 0.0880107805 0.0057345067 0.0754540000 28833705 955859216 1777242112 0.2685984075 -0.0822758526 -0.0800559893 634 1311867191.5764698982 0.0597928166 0.0618468702 0.0880107805 0.0057309914 0.0950750000 28835535 955859216 1778925568 0.2707164884 -0.0822315738 -0.0793182626 635 1311867191.6118669510 0.0597942285 0.0618436377 0.0880107805 0.0057559247 0.0769230000 28837365 955859216 1780670464 0.2733775675 -0.0815434903 -0.0782249719 636 1311867191.6451880932 0.0597754084 0.0618403857 0.0880107805 0.0057528857 0.1160510000 28839131 955859216 1782321152 0.2752591372 -0.0819663256 -0.0770588443 637 1311867191.6827919483 0.0586562753 0.0618353871 0.0880107805 0.0057569983 0.1149160000 28841025 955859216 1784004608 0.2785721719 -0.0827457085 -0.0757840946 638 1311867191.7119400501 0.0586729385 0.0618304303 0.0880107805 0.0057550294 0.0760050000 28842727 955859216 1785749504 0.2803899944 -0.0822004154 -0.0748346597 639 1311867191.7457199097 0.0588113517 0.0618257056 0.0880107805 0.0057703113 0.0949970000 28844461 955859216 1784635392 0.2804402411 -0.0827967748 -0.0743813589 640 1311867191.7763800621 0.0593172684 0.0618217862 0.0880107805 0.0057733990 0.0940590000 28846195 955859216 1783508992 0.2813978791 -0.0828644335 -0.0735339150 641 1311867191.8097250462 0.0582865477 0.0618162710 0.0880107805 0.0057718015 0.0942040000 28847993 955859216 1782366208 0.2848681509 -0.0828365386 -0.0717102066 642 1311867191.8395779133 0.0576862134 0.0618098379 0.0880107805 0.0057757874 0.0935870000 28849727 955859216 1781350400 0.2865262032 -0.0833725780 -0.0710990056 643 1311867191.8745219707 0.0579916276 0.0618038998 0.0880107805 0.0057776206 0.0940180000 28851525 955859216 1780334592 0.2875383198 -0.0828625634 -0.0701740012 644 1311867191.9077119827 0.0568030588 0.0617961345 0.0880107805 0.0057741982 0.0935470000 28853323 955859216 1779318784 0.2905215621 -0.0831671581 -0.0687383339 645 1311867191.9391601086 0.0575036928 0.0617894795 0.0880107805 0.0057708978 0.0944730000 28855089 955859216 1778302976 0.2906788886 -0.0842859745 -0.0680188239 646 1311867191.9755239487 0.0570034571 0.0617820708 0.0880107805 0.0057698676 0.0935200000 28856887 955859216 1777287168 0.2928202152 -0.0840630978 -0.0668401793 647 1311867192.0076289177 0.0573601127 0.0617752363 0.0880107805 0.0057664897 0.0915810000 28858653 955859216 1776271360 0.2937413156 -0.0840985179 -0.0658892542 648 1311867192.0447950363 0.0569128320 0.0617677326 0.0880107805 0.0057754309 0.1031010000 28860515 955859216 1775255552 0.2945773900 -0.0857885182 -0.0655398890 649 1311867192.0751929283 0.0573524162 0.0617609293 0.0880107805 0.0057740195 0.0809510000 28862217 955859216 1774239744 0.2950781584 -0.0855105445 -0.0649369732 650 1311867192.1073920727 0.0573269799 0.0617541078 0.0880107805 0.0057725391 0.0959500000 28864015 955859216 1773223936 0.2977569997 -0.0848381817 -0.0633265153 651 1311867192.1433029175 0.0580784194 0.0617484616 0.0880107805 0.0057771313 0.0890030000 28865845 955859216 1769754624 0.2970502079 -0.0862938240 -0.0633189082 652 1311867192.1754670143 0.0590211041 0.0617442785 0.0880107805 0.0057820235 0.0923630000 28867611 955859216 1770811392 0.2975272834 -0.0857665613 -0.0624935739 653 1311867192.2077538967 0.0589438975 0.0617399901 0.0880107805 0.0057787227 0.0952200000 28869409 955859216 1769795584 0.2997397482 -0.0854853764 -0.0613068566 654 1311867192.2451250553 0.0584511682 0.0617349613 0.0880107805 0.0057864632 0.0950090000 28871271 955859216 1768779776 0.3014568090 -0.0872427821 -0.0603248477 655 1311867192.2744629383 0.0590389483 0.0617308452 0.0880107805 0.0057843922 0.0937380000 28872973 955859216 1767763968 0.3024437726 -0.0863528401 -0.0596504584 656 1311867192.3067719936 0.0592047088 0.0617269944 0.0880107805 0.0057822346 0.0943440000 28874739 955859216 1766875136 0.3044862449 -0.0869419426 -0.0584667474 657 1311867192.3427391052 0.0596439019 0.0617238238 0.0880107805 0.0057790035 0.0918690000 28876569 955859216 1765859328 0.3053021133 -0.0884622782 -0.0580168143 658 1311867192.3755910397 0.0609611906 0.0617226648 0.0880107805 0.0057818240 0.0931850000 28878367 955859216 1764970496 0.3059664071 -0.0881483853 -0.0574706793 659 1311867192.4059340954 0.0606795959 0.0617210820 0.0880107805 0.0057778951 0.0928820000 28880069 955859216 1765224448 0.3084894121 -0.0889006257 -0.0567233488 660 1311867192.4447100163 0.0619101897 0.0617213685 0.0880107805 0.0057753129 0.0927860000 28881963 955859216 1764966400 0.3091185093 -0.0902459994 -0.0567735732 661 1311867192.4748210907 0.0634781942 0.0617240263 0.0880107805 0.0057749158 0.0934990000 28883697 955859216 1765076992 0.3094877601 -0.0899456888 -0.0564087406 662 1311867192.5077190399 0.0643371642 0.0617279737 0.0880107805 0.0057710628 0.0936600000 28885463 955859216 1764970496 0.3104089200 -0.0906840488 -0.0560393110 663 1311867192.5427820683 0.0643744543 0.0617319653 0.0880107805 0.0057695326 0.0956210000 28887293 955859216 1762021376 0.3115537167 -0.0923098996 -0.0561461262 664 1311867192.5787169933 0.0655963644 0.0617377852 0.0880107805 0.0057697803 0.0875070000 28889091 955859216 1761910784 0.3123785257 -0.0917635709 -0.0560376644 665 1311867192.6109929085 0.0681697354 0.0617474573 0.0880107805 0.0057666738 0.0942470000 28890857 955859216 1763680256 0.3107417226 -0.0913860425 -0.0561675280 666 1311867192.6435210705 0.0695486665 0.0617591709 0.0880107805 0.0057667439 0.0933290000 28892655 955859216 1765478400 0.3103561997 -0.0926552936 -0.0564055592 667 1311867192.6790139675 0.0700144544 0.0617715476 0.0880107805 0.0057639193 0.0941370000 28894485 955859216 1766830080 0.3118342161 -0.0924927294 -0.0558708273 668 1311867192.7113289833 0.0696410686 0.0617833283 0.0880107805 0.0057608062 0.0792860000 28896219 955859216 1768607744 0.3137872219 -0.0927195400 -0.0554831699 669 1311867192.7439620495 0.0704530776 0.0617962876 0.0880107805 0.0057602535 0.1134920000 28898017 955859216 1770258432 0.3139944375 -0.0936394557 -0.0552896149 670 1311867192.7760629654 0.0700993240 0.0618086802 0.0880107805 0.0057586029 0.0945700000 28899783 955859216 1771941888 0.3160515428 -0.0930109024 -0.0546984859 671 1311867192.8091869354 0.0702411234 0.0618212472 0.0880107805 0.0057544147 0.1332950000 28901581 955859216 1773686784 0.3172715306 -0.0936220214 -0.0542650074 672 1311867192.8422288895 0.0701125041 0.0618335853 0.0880107805 0.0057507932 0.0908380000 28903347 955859216 1775337472 0.3184789121 -0.0943713933 -0.0539282486 673 1311867192.8792889118 0.0708119497 0.0618469261 0.0880107805 0.0057514741 0.0762890000 28905209 955859216 1777115136 0.3191569746 -0.0935492516 -0.0533551499 674 1311867192.9092190266 0.0700793415 0.0618591404 0.0880107805 0.0057476111 0.0928910000 28906911 955859216 1778765824 0.3213185668 -0.0940942243 -0.0524395108 675 1311867192.9434111118 0.0698441267 0.0618709700 0.0880107805 0.0057447938 0.0784500000 28908741 955859216 1780449280 0.3225552738 -0.0956005156 -0.0522148423 676 1311867192.9776289463 0.0697629377 0.0618826445 0.0880107805 0.0057449860 0.0919970000 28910507 955859216 1782194176 0.3244538605 -0.0948760286 -0.0516300239 677 1311867193.0086810589 0.0697701350 0.0618942952 0.0880107805 0.0057428322 0.0924740000 28912273 955859216 1783844864 0.3253931403 -0.0950485468 -0.0511787459 678 1311867193.0430600643 0.0694433823 0.0619054295 0.0880107805 0.0057407234 0.0982420000 28914071 955859216 1785528320 0.3267637491 -0.0965586007 -0.0510749482 679 1311867193.0767369270 0.0700213164 0.0619173822 0.0880107805 0.0057460680 0.1175200000 28915837 955859216 1784397824 0.3279382288 -0.0953352973 -0.0509132072 680 1311867193.1105849743 0.0696851239 0.0619288054 0.0880107805 0.0057429272 0.1076650000 28917635 955859216 1783255040 0.3299323916 -0.0953132138 -0.0504079759 681 1311867193.1429219246 0.0686055124 0.0619386096 0.0880107805 0.0057439985 0.1364420000 28919433 955859216 1782112256 0.3314682245 -0.0968817845 -0.0503626764 682 1311867193.1767370701 0.0700809583 0.0619505486 0.0880107805 0.0057583925 0.1291410000 28921199 955859216 1783750656 0.3323821425 -0.0948384181 -0.0500467122 683 1311867193.2122681141 0.0702185333 0.0619626540 0.0880107805 0.0057586486 0.1150500000 28923029 955859216 1785495552 0.3337387443 -0.0953627601 -0.0495963544 684 1311867193.2432429790 0.0697034076 0.0619739709 0.0880107805 0.0057574481 0.1166930000 28924795 955859216 1784524800 0.3354664743 -0.0960986316 -0.0495626777 685 1311867193.2773900032 0.0704188272 0.0619862991 0.0880107805 0.0057554949 0.0923420000 28926593 955859216 1783382016 0.3362592459 -0.0950235575 -0.0494468957 686 1311867193.3139379025 0.0717383400 0.0620005149 0.0880107805 0.0057557286 0.1077050000 28928423 955859216 1782235136 0.3359875381 -0.0957809165 -0.0498181432 687 1311867193.3426671028 0.0714998320 0.0620143422 0.0880107805 0.0057554519 0.0966910000 28930125 955859216 1781223424 0.3375632465 -0.0955975950 -0.0495389365 688 1311867193.3788230419 0.0709459186 0.0620273241 0.0880107805 0.0057519729 0.0945840000 28931955 955859216 1780207616 0.3400799632 -0.0951048583 -0.0492246747 689 1311867193.4126739502 0.0714413747 0.0620409875 0.0880107805 0.0057582244 0.0947850000 28933721 955859216 1779191808 0.3407096267 -0.0962752104 -0.0493698455 690 1311867193.4440810680 0.0717857406 0.0620551103 0.0880107805 0.0057585173 0.0917790000 28935519 955859216 1774845952 0.3419598341 -0.0961107910 -0.0492857844 691 1311867193.4782969952 0.0719564259 0.0620694393 0.0880107805 0.0057553013 0.0912130000 28937317 955859216 1776652288 0.3436865807 -0.0955512226 -0.0490306057 692 1311867193.5199069977 0.0731448457 0.0620854442 0.0880107805 0.0057533527 0.0935910000 28939179 955859216 1778257920 0.3439774513 -0.0966793895 -0.0493140109 693 1311867193.5431120396 0.0723551214 0.0621002633 0.0880107805 0.0057527702 0.0962770000 28940849 955859216 1779941376 0.3460896015 -0.0967294052 -0.0491088033 694 1311867193.5765709877 0.0729117021 0.0621158418 0.0880107805 0.0057489625 0.0944760000 28942615 955859216 1781686272 0.3473529816 -0.0961085111 -0.0489644706 695 1311867193.6127800941 0.0732803866 0.0621319059 0.0880107805 0.0057449521 0.0954890000 28944477 955859216 1783369728 0.3482374847 -0.0971134976 -0.0492080562 696 1311867193.6461451054 0.0740311444 0.0621490025 0.0880107805 0.0057422279 0.0943640000 28946243 955859216 1785114624 0.3488597274 -0.0970063284 -0.0493536964 697 1311867193.6757860184 0.0742392167 0.0621663486 0.0880107805 0.0057387946 0.0959750000 28947977 955859216 1784143872 0.3506008387 -0.0959479734 -0.0490582809 698 1311867193.7122890949 0.0749096870 0.0621846055 0.0880107805 0.0057350883 0.0946300000 28949807 955859216 1783001088 0.3509149849 -0.0969166085 -0.0492818318 699 1311867193.7430191040 0.0758121163 0.0622041012 0.0880107805 0.0057328156 0.0937490000 28951541 955859216 1781858304 0.3513596654 -0.0962537080 -0.0493957028 700 1311867193.7760169506 0.0765250251 0.0622245597 0.0880107805 0.0057300830 0.0932770000 28953307 955859216 1780842496 0.3521601856 -0.0953564346 -0.0496706814 701 1311867193.8139710426 0.0772008300 0.0622459238 0.0880107805 0.0057275611 0.0942540000 28955201 955859216 1779826688 0.3530077040 -0.0966363028 -0.0494782589 702 1311867193.8436760902 0.0775029436 0.0622676575 0.0880107805 0.0057253691 0.0939080000 28956903 955859216 1778806784 0.3540198207 -0.0964844003 -0.0495690815 703 1311867193.8771181107 0.0775811449 0.0622894405 0.0880107805 0.0057223302 0.0943070000 28958701 955859216 1777795072 0.3558156788 -0.0959610492 -0.0494688675 704 1311867193.9151229858 0.0788373575 0.0623129461 0.0880107805 0.0057191420 0.0939130000 28960531 955859216 1776779264 0.3557494283 -0.0967629403 -0.0497257635 705 1311867193.9425311089 0.0789324790 0.0623365199 0.0880107805 0.0057170277 0.0936740000 28962265 955859216 1775763456 0.3568861187 -0.0961440057 -0.0497277640 706 1311867193.9781770706 0.0797024965 0.0623611176 0.0880107805 0.0057139592 0.0928010000 28964095 955859216 1774747648 0.3577199280 -0.0958539993 -0.0497582145 707 1311867194.0148570538 0.0818596333 0.0623886968 0.0880107805 0.0057123652 0.0765740000 28965893 955859216 1773731840 0.3565178812 -0.0964052752 -0.0504841469 708 1311867194.0433440208 0.0829745084 0.0624177728 0.0880107805 0.0057101482 0.1072970000 28967627 955859216 1772843008 0.3567341268 -0.0960084274 -0.0504351631 709 1311867194.0746119022 0.0820357203 0.0624454427 0.0880107805 0.0057066630 0.0797450000 28969361 955859216 1771823104 0.3591630757 -0.0958785042 -0.0499311425 710 1311867194.1131060123 0.0830357671 0.0624744432 0.0880107805 0.0057028524 0.1339820000 28971255 955859216 1770921984 0.3587851226 -0.0963824615 -0.0504418388 711 1311867194.1428558826 0.0841214657 0.0625048891 0.0880107805 0.0057010676 0.1263370000 28972989 955859216 1772544000 0.3585234582 -0.0957314149 -0.0503584407 712 1311867194.1758549213 0.0836370438 0.0625345691 0.0880107805 0.0057028541 0.1148260000 28974755 955859216 1774194688 0.3599108458 -0.0949554518 -0.0498655736 713 1311867194.2138450146 0.0843643844 0.0625651859 0.0880107805 0.0056999868 0.1341870000 28976617 955859216 1775878144 0.3595933318 -0.0958119705 -0.0501801632 714 1311867194.2451140881 0.0843562484 0.0625957056 0.0880107805 0.0056978172 0.0927100000 28978319 955859216 1777623040 0.3605089784 -0.0949583277 -0.0498572811 715 1311867194.2760241032 0.0837744027 0.0626253262 0.0880107805 0.0056942900 0.0925080000 28980053 955859216 1779273728 0.3618244231 -0.0950656533 -0.0493033975 716 1311867194.3139200211 0.0850053728 0.0626565832 0.0880107805 0.0056915954 0.0966400000 28981915 955859216 1781051392 0.3610396683 -0.0956588015 -0.0496147536 717 1311867194.3447821140 0.0847659856 0.0626874192 0.0880107805 0.0056919731 0.0947750000 28983681 955859216 1782702080 0.3619365394 -0.0947138369 -0.0491502918 718 1311867194.3802230358 0.0832373574 0.0627160403 0.0880107805 0.0056892093 0.0953740000 28985479 955859216 1784369152 0.3642791808 -0.0949105471 -0.0484881848 719 1311867194.4124519825 0.0835810453 0.0627450598 0.0880107805 0.0056875406 0.0968280000 28987213 955859216 1783382016 0.3641032875 -0.0961467177 -0.0482581258 720 1311867194.4447510242 0.0839790627 0.0627745514 0.0880107805 0.0056838758 0.0959160000 28989011 955859216 1782366208 0.3644083738 -0.0962342322 -0.0480017290 721 1311867194.4805839062 0.0839368477 0.0628039027 0.0880107805 0.0056804070 0.0914650000 28990777 955859216 1781223424 0.3651237786 -0.0959326923 -0.0478772596 722 1311867194.5174930096 0.0846402273 0.0628341470 0.0880107805 0.0056777550 0.0926630000 28992671 955859216 1780207616 0.3646765351 -0.0966975912 -0.0479017161 723 1311867194.5439500809 0.0848113447 0.0628645442 0.0880107805 0.0056758506 0.1061660000 28994309 955859216 1779191808 0.3647874594 -0.0963379741 -0.0479439981 724 1311867194.5795979500 0.0841274783 0.0628939129 0.0880107805 0.0056719952 0.0944800000 28996107 955859216 1778171904 0.3660711348 -0.0963551253 -0.0474107303 725 1311867194.6129479408 0.0834749192 0.0629223005 0.0880107805 0.0056685062 0.0938390000 28997905 955859216 1777160192 0.3672351241 -0.0971703529 -0.0468095876 726 1311867194.6493880749 0.0822082385 0.0629488651 0.0880107805 0.0056767709 0.0923710000 28999767 955859216 1778765824 0.3689366877 -0.0969713554 -0.0459616296 727 1311867194.6784319878 0.0814922601 0.0629743719 0.0880107805 0.0056757079 0.0960540000 29001469 955859216 1780543488 0.3700158298 -0.0970737338 -0.0456730500 728 1311867194.7133309841 0.0822172984 0.0630008044 0.0880107805 0.0056735725 0.1164630000 29003267 955859216 1782194176 0.3695808053 -0.0969029814 -0.0456188209 729 1311867194.7475099564 0.0824274495 0.0630274528 0.0880107805 0.0056700516 0.1121180000 29005065 955859216 1783861248 0.3700383306 -0.0965035781 -0.0451906174 730 1311867194.7784450054 0.0827794969 0.0630545104 0.0880107805 0.0056663606 0.0971430000 29006831 955859216 1785622528 0.3700733781 -0.0966050476 -0.0448621064 731 1311867194.8130390644 0.0827231780 0.0630814169 0.0880107805 0.0056624873 0.1126600000 29008629 955859216 1784504320 0.3703510463 -0.0965503231 -0.0445881523 732 1311867194.8476719856 0.0836539939 0.0631095215 0.0880107805 0.0056588683 0.1123770000 29010427 955859216 1783508992 0.3693145216 -0.0961364061 -0.0448213406 733 1311867194.8814148903 0.0839296505 0.0631379255 0.0880107805 0.0056554611 0.1377800000 29012225 955859216 1778802688 0.3687684834 -0.0956943557 -0.0447197482 734 1311867194.9104089737 0.0836020410 0.0631658058 0.0880107805 0.0056622315 0.1029050000 29013927 955859216 1780568064 0.3689239621 -0.0952399597 -0.0445806682 735 1311867194.9451448917 0.0834540427 0.0631934088 0.0880107805 0.0056592058 0.1153800000 29015757 955859216 1782366208 0.3683754504 -0.0955823809 -0.0442206040 736 1311867194.9787399769 0.0811870769 0.0632178567 0.0880107805 0.0056575476 0.1117780000 29017555 955859216 1783590912 0.3704540431 -0.0963891670 -0.0435050689 737 1311867195.0132799149 0.0802983195 0.0632410324 0.0880107805 0.0056556855 0.1159470000 29019353 955859216 1785241600 0.3704289794 -0.0960373133 -0.0431474298 738 1311867195.0464940071 0.0792869851 0.0632627749 0.0880107805 0.0056530056 0.0990250000 29021119 955859216 1784012800 0.3709596395 -0.0974494070 -0.0427045263 739 1311867195.0781710148 0.0788309425 0.0632838414 0.0880107805 0.0056497591 0.1121080000 29022885 955859216 1782984704 0.3710038364 -0.0965638384 -0.0425561257 740 1311867195.1115310192 0.0788719356 0.0633049064 0.0880107805 0.0056462488 0.0840100000 29024651 955859216 1781858304 0.3702903688 -0.0963158086 -0.0424035564 741 1311867195.1458311081 0.0790041685 0.0633260930 0.0880107805 0.0056425343 0.1007750000 29026481 955859216 1780842496 0.3690656424 -0.0968380496 -0.0425864756 742 1311867195.1780319214 0.0784037113 0.0633464132 0.0880107805 0.0056403442 0.1155300000 29028247 955859216 1776246784 0.3690433502 -0.0959138721 -0.0424073674 743 1311867195.2114748955 0.0769472271 0.0633647185 0.0880107805 0.0056370172 0.1063390000 29030013 955859216 1778012160 0.3691715002 -0.0960173830 -0.0422119834 744 1311867195.2436800003 0.0764525458 0.0633823097 0.0880107805 0.0056352581 0.0949610000 29031811 955859216 1779679232 0.3689759076 -0.0968893021 -0.0421838388 745 1311867195.2780399323 0.0758563131 0.0633990533 0.0880107805 0.0056321022 0.0935560000 29033609 955859216 1781084160 0.3685781360 -0.0969643891 -0.0420075096 746 1311867195.3123180866 0.0754129663 0.0634151578 0.0880107805 0.0056286787 0.0954830000 29035407 955859216 1782829056 0.3681958318 -0.0969128311 -0.0419769101 747 1311867195.3425979614 0.0760466978 0.0634320674 0.0880107805 0.0056292423 0.0956820000 29037141 955859216 1784479744 0.3658125699 -0.0983216241 -0.0426344313 748 1311867195.3782711029 0.0756871328 0.0634484512 0.0880107805 0.0056269396 0.0978120000 29038971 955859216 1783234560 0.3651286364 -0.0977261662 -0.0427639186 749 1311867195.4119830132 0.0751589686 0.0634640861 0.0880107805 0.0056260588 0.0940170000 29040737 955859216 1780449280 0.3642429113 -0.0974969938 -0.0431941636 750 1311867195.4435520172 0.0755056366 0.0634801415 0.0880107805 0.0056237511 0.0870480000 29042535 955859216 1781223424 0.3617008626 -0.0979997814 -0.0440389402 751 1311867195.4788239002 0.0742808059 0.0634945232 0.0880107805 0.0056209207 0.1092780000 29044333 955859216 1779937280 0.3618661165 -0.0972093642 -0.0440041013 752 1311867195.5113179684 0.0737946779 0.0635082202 0.0880107805 0.0056175237 0.0955690000 29046099 955859216 1778937856 0.3610564172 -0.0973345116 -0.0440491736 753 1311867195.5439620018 0.0733809769 0.0635213314 0.0880107805 0.0056140049 0.0911720000 29047897 955859216 1777922048 0.3591552377 -0.0981719270 -0.0442437828 754 1311867195.5782160759 0.0721549913 0.0635327819 0.0880107805 0.0056116254 0.0933490000 29049695 955859216 1776652288 0.3593555093 -0.0978148580 -0.0439118072 755 1311867195.6119859219 0.0723129138 0.0635444112 0.0880107805 0.0056095768 0.0963480000 29051493 955859216 1772433408 0.3572700322 -0.0978303552 -0.0442173854 756 1311867195.6430909634 0.0725318491 0.0635562994 0.0880107805 0.0056061250 0.1276900000 29053227 955859216 1774219264 0.3546946347 -0.0982260928 -0.0448040739 757 1311867195.6779129505 0.0724405572 0.0635680355 0.0880107805 0.0056027891 0.0935260000 29055057 955859216 1775845376 0.3529991806 -0.0979877040 -0.0448299013 758 1311867195.7107300758 0.0724873170 0.0635798024 0.0880107805 0.0056028143 0.1152890000 29056791 955859216 1777528832 0.3506644070 -0.0980411917 -0.0448637381 759 1311867195.7458300591 0.0713103488 0.0635899876 0.0880107805 0.0056009919 0.0943210000 29058621 955859216 1779273728 0.3499214053 -0.0988593251 -0.0448190495 760 1311867195.7821879387 0.0709146857 0.0635996253 0.0880107805 0.0055974642 0.0942560000 29060419 955859216 1780924416 0.3487458527 -0.0985523611 -0.0445603020 761 1311867195.8100500107 0.0717232004 0.0636103002 0.0880107805 0.0055943549 0.0956670000 29062121 955859216 1782607872 0.3458927274 -0.0988681465 -0.0447757542 762 1311867195.8458549976 0.0705098361 0.0636193547 0.0880107805 0.0055911166 0.0961070000 29063951 955859216 1784352768 0.3452213109 -0.0991040990 -0.0448296182 763 1311867195.8778660297 0.0699613988 0.0636276667 0.0880107805 0.0055898963 0.1150060000 29065749 955859216 1783382016 0.3441189229 -0.0980153158 -0.0447968394 764 1311867195.9098269939 0.0700092837 0.0636360196 0.0880107805 0.0055872523 0.0945180000 29067515 955859216 1782247424 0.3424273729 -0.0979181677 -0.0447936840 765 1311867195.9458460808 0.0698272288 0.0636441127 0.0880107805 0.0055841692 0.0929020000 29069313 955859216 1781231616 0.3405185044 -0.0982899517 -0.0449032001 766 1311867195.9778430462 0.0700187832 0.0636524347 0.0880107805 0.0055821001 0.0948740000 29071111 955859216 1780215808 0.3389776647 -0.0973069072 -0.0447795913 767 1311867196.0100569725 0.0694234148 0.0636599588 0.0880107805 0.0055792333 0.1283300000 29072877 955859216 1779200000 0.3383067548 -0.0974660963 -0.0445483252 768 1311867196.0498790741 0.0685034767 0.0636662654 0.0880107805 0.0055768255 0.1161590000 29074771 955859216 1778184192 0.3376073539 -0.0979335904 -0.0447659940 769 1311867196.0793108940 0.0688624978 0.0636730226 0.0880107805 0.0055777610 0.1314470000 29076537 955859216 1779789824 0.3359589577 -0.0967822373 -0.0446458831 770 1311867196.1113979816 0.0687708631 0.0636796431 0.0880107805 0.0055748774 0.1119680000 29078239 955859216 1781473280 0.3342047334 -0.0971946120 -0.0447860844 771 1311867196.1473290920 0.0680183619 0.0636852705 0.0880107805 0.0055715303 0.0967180000 29080101 955859216 1783218176 0.3332761526 -0.0976725966 -0.0447661541 772 1311867196.1811769009 0.0677626878 0.0636905522 0.0880107805 0.0055717481 0.0955770000 29081899 955859216 1784868864 0.3319920599 -0.0969742537 -0.0446858741 773 1311867196.2114949226 0.0684609041 0.0636967234 0.0880107805 0.0055695456 0.0983820000 29083601 955859216 1783881728 0.3294540346 -0.0976300761 -0.0449516252 774 1311867196.2462599277 0.0684075207 0.0637028097 0.0880107805 0.0055665775 0.1117650000 29085431 955859216 1782755328 0.3277359009 -0.0976049602 -0.0450949930 775 1311867196.2800569534 0.0682627708 0.0637086935 0.0880107805 0.0055631125 0.0848610000 29087229 955859216 1781739520 0.3262450099 -0.0973441973 -0.0450095870 776 1311867196.3111600876 0.0675592497 0.0637136556 0.0880107805 0.0055597504 0.0804190000 29088963 955859216 1780723712 0.3251653016 -0.0978305638 -0.0450978205 777 1311867196.3484730721 0.0677122772 0.0637188018 0.0880107805 0.0055567915 0.1117670000 29090825 955859216 1779707904 0.3232928514 -0.0975165963 -0.0452815667 778 1311867196.3842670918 0.0673941001 0.0637235258 0.0880107805 0.0055537391 0.0932170000 29092623 955859216 1778688000 0.3219999075 -0.0968422368 -0.0449661203 779 1311867196.4107549191 0.0674206764 0.0637282719 0.0880107805 0.0055517421 0.0952390000 29094293 955859216 1774981120 0.3202930391 -0.0975161046 -0.0449673310 780 1311867196.4463150501 0.0672019348 0.0637327253 0.0880107805 0.0055509384 0.0929400000 29096123 955859216 1773711360 0.3190009594 -0.0970107988 -0.0449248999 781 1311867196.4798319340 0.0665966123 0.0637363922 0.0880107805 0.0055474492 0.0906200000 29097921 955859216 1775538176 0.3184215128 -0.0965054259 -0.0444759913 782 1311867196.5113470554 0.0668461025 0.0637403688 0.0880107805 0.0055442741 0.0928450000 29099655 955859216 1776996352 0.3158653677 -0.0968918949 -0.0447369926 783 1311867196.5468420982 0.0661919415 0.0637434998 0.0880107805 0.0055418894 0.0953240000 29101485 955859216 1778647040 0.3142793477 -0.0960702896 -0.0445097238 784 1311867196.5795550346 0.0658393577 0.0637461731 0.0880107805 0.0055404009 0.0954930000 29103283 955859216 1780330496 0.3138060570 -0.0956552997 -0.0439984836 785 1311867196.6108930111 0.0651451498 0.0637479553 0.0880107805 0.0055400751 0.0970610000 29105017 955859216 1782075392 0.3125604093 -0.0965231955 -0.0437249988 786 1311867196.6521809101 0.0649313629 0.0637494609 0.0880107805 0.0055438026 0.0937470000 29106943 955859216 1783726080 0.3101681471 -0.0954741314 -0.0438405238 787 1311867196.6805100441 0.0642802194 0.0637501353 0.0880107805 0.0055520855 0.0950420000 29108645 955859216 1785503744 0.3089094162 -0.0944883004 -0.0433428511 788 1311867196.7112100124 0.0637626722 0.0637501512 0.0880107805 0.0055490339 0.0807420000 29110379 955859216 1784258560 0.3081143498 -0.0950755179 -0.0427385606 789 1311867196.7464900017 0.0639614463 0.0637504190 0.0880107805 0.0055455548 0.0925670000 29112209 955859216 1783246848 0.3057230711 -0.0944790319 -0.0424334072 790 1311867196.7783749104 0.0633931905 0.0637499668 0.0880107805 0.0055422280 0.0889620000 29114007 955859216 1782120448 0.3042968810 -0.0944266394 -0.0420264378 791 1311867196.8109180927 0.0631682053 0.0637492313 0.0880107805 0.0055403819 0.0940780000 29115709 955859216 1781100544 0.3022154272 -0.0945630446 -0.0419350006 792 1311867196.8488750458 0.0629907325 0.0637482736 0.0880107805 0.0055382842 0.0928800000 29117603 955859216 1780088832 0.2999384701 -0.0944971591 -0.0418390781 793 1311867196.8821749687 0.0625075176 0.0637467090 0.0880107805 0.0055351674 0.0933260000 29119369 955859216 1779073024 0.2985680401 -0.0941148847 -0.0414883569 794 1311867196.9115700722 0.0626735836 0.0637453574 0.0880107805 0.0055326411 0.0937340000 29121071 955859216 1778184192 0.2961369455 -0.0948876068 -0.0415059850 795 1311867196.9482440948 0.0622250997 0.0637434452 0.0880107805 0.0055292300 0.0931270000 29122933 955859216 1777041408 0.2941798568 -0.0948661342 -0.0414468609 796 1311867196.9809880257 0.0618046224 0.0637410095 0.0880107805 0.0055268843 0.0931560000 29124731 955859216 1776025600 0.2926917970 -0.0952114165 -0.0411910862 797 1311867197.0154891014 0.0615433007 0.0637382520 0.0880107805 0.0055241378 0.0793940000 29126497 955859216 1775005696 0.2909764946 -0.0956000537 -0.0413791500 798 1311867197.0490679741 0.0611871406 0.0637350551 0.0880107805 0.0055218208 0.1052400000 29128295 955859216 1773993984 0.2891829610 -0.0955861881 -0.0415346101 799 1311867197.0806479454 0.0607427694 0.0637313101 0.0880107805 0.0055190173 0.0963420000 29129997 955859216 1773105152 0.2877901793 -0.0959689990 -0.0416032039 800 1311867197.1148109436 0.0606441833 0.0637274511 0.0880107805 0.0055158439 0.0944560000 29131827 955859216 1772089344 0.2852154076 -0.0962909684 -0.0421267971 801 1311867197.1468429565 0.0606466159 0.0637236049 0.0880107805 0.0055133487 0.1318990000 29133593 955859216 1771073536 0.2832337618 -0.0956672356 -0.0422331095 802 1311867197.1792430878 0.0606816784 0.0637198120 0.0880107805 0.0055107815 0.0883400000 29135391 955859216 1772711936 0.2806755304 -0.0958654359 -0.0425497144 803 1311867197.2143619061 0.0605726242 0.0637158927 0.0880107805 0.0055098531 0.1133920000 29137189 955859216 1774456832 0.2784493268 -0.0955649093 -0.0426229574 804 1311867197.2459290028 0.0604642965 0.0637118484 0.0880107805 0.0055066166 0.1146080000 29138955 955859216 1776107520 0.2768854201 -0.0951656103 -0.0424710810 805 1311867197.2799959183 0.0596409142 0.0637067914 0.0880107805 0.0055049518 0.0892080000 29140785 955859216 1777790976 0.2757966816 -0.0955211744 -0.0422395840 806 1311867197.3157260418 0.0594421662 0.0637015003 0.0880107805 0.0055020308 0.0778950000 29142551 955859216 1779535872 0.2736090124 -0.0951712653 -0.0423784144 807 1311867197.3468708992 0.0589001440 0.0636955506 0.0880107805 0.0054996866 0.1118810000 29144317 955859216 1781186560 0.2723354399 -0.0951886773 -0.0422042347 808 1311867197.3784019947 0.0589747690 0.0636897081 0.0880107805 0.0054980237 0.0785280000 29146051 955859216 1782870016 0.2698957920 -0.0952302516 -0.0426652990 809 1311867197.4155099392 0.0590192638 0.0636839350 0.0880107805 0.0054950853 0.1136290000 29147881 955859216 1784614912 0.2675262392 -0.0951870978 -0.0430653244 810 1311867197.4478878975 0.0587162636 0.0636778020 0.0880107805 0.0054918722 0.0954920000 29149647 955859216 1783517184 0.2665358484 -0.0950963125 -0.0432328060 811 1311867197.4793179035 0.0584379137 0.0636713410 0.0880107805 0.0054891840 0.0938560000 29151349 955859216 1782501376 0.2644546628 -0.0955288708 -0.0440719761 812 1311867197.5150759220 0.0586288571 0.0636651311 0.0880107805 0.0054874867 0.0928900000 29153179 955859216 1781485568 0.2620346546 -0.0949106440 -0.0449308045 813 1311867197.5469260216 0.0584328212 0.0636586953 0.0880107805 0.0054842275 0.0937260000 29154913 955859216 1780453376 0.2608551383 -0.0944319144 -0.0452767983 814 1311867197.5802750587 0.0584039874 0.0636522398 0.0880107805 0.0054828279 0.0937390000 29156711 955859216 1779453952 0.2588041425 -0.0952954590 -0.0461255126 815 1311867197.6152749062 0.0599174537 0.0636476573 0.0880107805 0.0054842843 0.0928600000 29158509 955859216 1778438144 0.2543700933 -0.0941674709 -0.0475171879 816 1311867197.6470439434 0.0594143607 0.0636424694 0.0880107805 0.0054825327 0.0934550000 29160275 955859216 1777422336 0.2535235286 -0.0933617502 -0.0478303395 817 1311867197.6800849438 0.0597006157 0.0636376446 0.0880107805 0.0054816500 0.0935180000 29162073 955859216 1776279552 0.2505182922 -0.0940349028 -0.0488728955 818 1311867197.7143290043 0.0596692450 0.0636327933 0.0880107805 0.0054818453 0.1099120000 29163871 955859216 1775243264 0.2490125149 -0.0925437436 -0.0494781137 819 1311867197.7463419437 0.0596270598 0.0636279023 0.0880107805 0.0054801927 0.0922550000 29165637 955859216 1774374912 0.2471767515 -0.0921989754 -0.0501615368 820 1311867197.7793009281 0.0600677244 0.0636235606 0.0880107805 0.0054777441 0.1149610000 29167435 955859216 1769787392 0.2439640015 -0.0925249904 -0.0514025502 821 1311867197.8146750927 0.0597610697 0.0636188560 0.0880107805 0.0054788592 0.1057700000 29169265 955859216 1771462656 0.2432306558 -0.0911364183 -0.0519855879 822 1311867197.8467919827 0.0593149178 0.0636136200 0.0880107805 0.0054770250 0.1151720000 29170999 955859216 1773215744 0.2422101945 -0.0915942565 -0.0528343432 823 1311867197.8802978992 0.0594778582 0.0636085948 0.0880107805 0.0054747745 0.0954380000 29172765 955859216 1774481408 0.2394299507 -0.0914683640 -0.0539916083 824 1311867197.9148609638 0.0590948015 0.0636031169 0.0880107805 0.0054760169 0.1148820000 29174595 955859216 1776226304 0.2389092296 -0.0904088989 -0.0544030294 825 1311867197.9470140934 0.0586268976 0.0635970851 0.0880107805 0.0054798329 0.0929130000 29176361 955859216 1777876992 0.2371555716 -0.0907865092 -0.0551048815 826 1311867197.9812700748 0.0589772984 0.0635914922 0.0880107805 0.0054768552 0.0939220000 29178159 955859216 1779560448 0.2346009910 -0.0902390927 -0.0559882745 827 1311867198.0145471096 0.0583626330 0.0635851695 0.0880107805 0.0054745260 0.1170760000 29179989 955859216 1781305344 0.2340949923 -0.0893116593 -0.0562485717 828 1311867198.0463368893 0.0580225214 0.0635784513 0.0880107805 0.0054717439 0.0956210000 29181723 955859216 1782972416 0.2324809879 -0.0892669708 -0.0569788441 829 1311867198.0787069798 0.0580205619 0.0635717470 0.0880107805 0.0054705775 0.1147580000 29183521 955859216 1784733696 0.2309944481 -0.0888603106 -0.0574671999 830 1311867198.1143770218 0.0570425093 0.0635638804 0.0880107805 0.0054675856 0.0935640000 29185319 955859216 1783508992 0.2305384427 -0.0882408693 -0.0578262620 831 1311867198.1463611126 0.0572254024 0.0635562529 0.0880107805 0.0054643629 0.0914550000 29187085 955859216 1781964800 0.2279364765 -0.0879712552 -0.0587769151 832 1311867198.1822519302 0.0565970242 0.0635478884 0.0880107805 0.0054612551 0.1124470000 29188915 955859216 1781366784 0.2267081887 -0.0873665065 -0.0594868883 833 1311867198.2144989967 0.0569342189 0.0635399489 0.0880107805 0.0054642175 0.1329940000 29190681 955859216 1780191232 0.2244979888 -0.0868355855 -0.0601425692 834 1311867198.2464120388 0.0562932193 0.0635312597 0.0880107805 0.0054618870 0.1508240000 29192447 955859216 1781719040 0.2233785689 -0.0869269818 -0.0610773973 835 1311867198.2821578979 0.0558074191 0.0635220096 0.0880107805 0.0054591378 0.0929000000 29194277 955859216 1783463936 0.2220514268 -0.0862788558 -0.0616040640 836 1311867198.3159120083 0.0552036874 0.0635120595 0.0880107805 0.0054582913 0.0914880000 29196043 955859216 1785114624 0.2206371576 -0.0858015567 -0.0626025796 837 1311867198.3481218815 0.0546896644 0.0635015190 0.0880107805 0.0054554789 0.1157110000 29197809 955859216 1784143872 0.2192100734 -0.0859575197 -0.0634604245 838 1311867198.3828320503 0.0544985309 0.0634907756 0.0880107805 0.0054580177 0.0954570000 29199639 955859216 1779654656 0.2165822834 -0.0849489346 -0.0644615889 839 1311867198.4242680073 0.0536362156 0.0634790300 0.0880107805 0.0054637862 0.0896950000 29201437 955859216 1781329920 0.2149623036 -0.0844004825 -0.0654841959 840 1311867198.4497859478 0.0539305806 0.0634676628 0.0880107805 0.0054614228 0.1112960000 29203043 955859216 1783083008 0.2121663690 -0.0853110552 -0.0667512938 841 1311867198.4856219292 0.0544168241 0.0634569008 0.0880107805 0.0054669963 0.0939720000 29204809 955859216 1784766464 0.2089149952 -0.0842122212 -0.0679705143 842 1311867198.5190339088 0.0542404875 0.0634459549 0.0880107805 0.0054643775 0.1161630000 29206607 955859216 1783889920 0.2065464705 -0.0833025128 -0.0690146089 843 1311867198.5499279499 0.0535954982 0.0634342699 0.0880107805 0.0054644253 0.0936980000 29208373 955859216 1781596160 0.2043734789 -0.0836663246 -0.0702748746 844 1311867198.5824239254 0.0531553403 0.0634220911 0.0880107805 0.0054617260 0.0892160000 29210139 955859216 1781731328 0.2028166056 -0.0822861865 -0.0710404292 845 1311867198.6147489548 0.0526560806 0.0634093502 0.0880107805 0.0054618079 0.0936060000 29211905 955859216 1780461568 0.2008381188 -0.0820206404 -0.0719727725 846 1311867198.6482009888 0.0522050597 0.0633961064 0.0880107805 0.0054614617 0.1321280000 29213671 955859216 1779445760 0.1987007260 -0.0818241239 -0.0729049668 847 1311867198.6827540398 0.0524728037 0.0633832099 0.0880107805 0.0054596982 0.0941700000 29215469 955859216 1778429952 0.1953177005 -0.0806937963 -0.0741046295 848 1311867198.7146520615 0.0527686924 0.0633706928 0.0880107805 0.0054565468 0.0935000000 29217203 955859216 1780068352 0.1932501197 -0.0798671767 -0.0746277794 849 1311867198.7467699051 0.0529954620 0.0633584723 0.0880107805 0.0054546962 0.0953280000 29218937 955859216 1781813248 0.1910948753 -0.0796185136 -0.0754431039 850 1311867198.7842700481 0.0526043884 0.0633458204 0.0880107805 0.0054519960 0.0936110000 29220767 955859216 1783463936 0.1897570342 -0.0788233206 -0.0759418011 851 1311867198.8149418831 0.0532285385 0.0633339317 0.0880107805 0.0054489574 0.0950800000 29222501 955859216 1785147392 0.1858163625 -0.0783413351 -0.0772703066 852 1311867198.8464009762 0.0533465780 0.0633222095 0.0880107805 0.0054468281 0.0970120000 29224267 955859216 1784143872 0.1835876107 -0.0775293633 -0.0780861378 853 1311867198.8845369816 0.0533110723 0.0633104731 0.0880107805 0.0054446908 0.0935710000 29226065 955859216 1783001088 0.1826093495 -0.0768430755 -0.0786401853 854 1311867198.9147930145 0.0538613871 0.0632994086 0.0880107805 0.0054415236 0.0933560000 29227799 955859216 1781985280 0.1798596382 -0.0762287378 -0.0796730965 855 1311867198.9465179443 0.0539122894 0.0632884295 0.0880107805 0.0054384188 0.0932920000 29229565 955859216 1780969472 0.1781588048 -0.0751157179 -0.0805710033 856 1311867198.9839329720 0.0539676435 0.0632775407 0.0880107805 0.0054356926 0.0936630000 29231459 955859216 1779953664 0.1759899259 -0.0741996989 -0.0815499127 857 1311867199.0148730278 0.0544764660 0.0632672711 0.0880107805 0.0054373513 0.0917740000 29233193 955859216 1778937856 0.1733047962 -0.0730677322 -0.0826379284 858 1311867199.0468010902 0.0554841980 0.0632581999 0.0880107805 0.0054372879 0.0926290000 29234959 955859216 1777922048 0.1715104878 -0.0722547248 -0.0835962519 859 1311867199.0849320889 0.0556943752 0.0632493945 0.0880107805 0.0054371418 0.0942790000 29236853 955859216 1776906240 0.1704266220 -0.0710653439 -0.0843547210 860 1311867199.1149818897 0.0561061949 0.0632410885 0.0880107805 0.0054350900 0.0933240000 29238555 955859216 1775890432 0.1684086472 -0.0705003515 -0.0856585503 861 1311867199.1465420723 0.0570716113 0.0632339230 0.0880107805 0.0054327069 0.0936280000 29240321 955859216 1771925504 0.1658415943 -0.0693015382 -0.0870562866 862 1311867199.1823658943 0.0577441603 0.0632275544 0.0880107805 0.0054313643 0.0915440000 29242151 955859216 1770135552 0.1638189107 -0.0678941235 -0.0882564709 863 1311867199.2146680355 0.0585883036 0.0632221787 0.0880107805 0.0054285285 0.0909420000 29243949 955859216 1771806720 0.1611896008 -0.0673358589 -0.0897160992 864 1311867199.2467749119 0.0588948913 0.0632171702 0.0880107805 0.0054256454 0.0935770000 29245683 955859216 1773588480 0.1595765650 -0.0664067417 -0.0907541886 865 1311867199.2833590508 0.0592013672 0.0632125277 0.0880107805 0.0054225346 0.0951450000 29247545 955859216 1774829568 0.1577983797 -0.0654934868 -0.0918219388 866 1311867199.3159129620 0.0595429726 0.0632082903 0.0880107805 0.0054228043 0.0937450000 29249247 955859216 1776513024 0.1559848338 -0.0653112382 -0.0931832045 867 1311867199.3465209007 0.0595193580 0.0632040355 0.0880107805 0.0054197212 0.0942860000 29250981 955859216 1778257920 0.1547472328 -0.0648253337 -0.0944236517 868 1311867199.3829050064 0.0593839325 0.0631996344 0.0880107805 0.0054170485 0.0936990000 29252843 955859216 1779908608 0.1531999409 -0.0641210526 -0.0956134796 869 1311867199.4147589207 0.0593917258 0.0631952525 0.0880107805 0.0054139729 0.0945550000 29254577 955859216 1781686272 0.1511766464 -0.0642206296 -0.0968884900 870 1311867199.4512910843 0.0591313057 0.0631905813 0.0880107805 0.0054112120 0.0921940000 29256439 955859216 1783336960 0.1492276639 -0.0634457618 -0.0982701182 871 1311867199.4837360382 0.0588060431 0.0631855474 0.0880107805 0.0054095996 0.0973730000 29258205 955859216 1785114624 0.1477740109 -0.0635564029 -0.0991329104 872 1311867199.5150198936 0.0587710403 0.0631804849 0.0880107805 0.0054066242 0.0973910000 29259971 955859216 1784016896 0.1458225846 -0.0635075793 -0.1000629067 873 1311867199.5544059277 0.0583193600 0.0631749166 0.0880107805 0.0054052551 0.0932120000 29261865 955859216 1782730752 0.1441042870 -0.0628279597 -0.1009277925 874 1311867199.5835030079 0.0581815280 0.0631692033 0.0880107805 0.0054022876 0.0932330000 29263599 955859216 1781604352 0.1416742057 -0.0622618198 -0.1018270105 875 1311867199.6158308983 0.0577199794 0.0631629756 0.0880107805 0.0053995298 0.0926830000 29265301 955859216 1780588544 0.1396315545 -0.0617647283 -0.1024102643 876 1311867199.6538460255 0.0567099415 0.0631556092 0.0880107805 0.0053986709 0.0940650000 29267195 955859216 1779568640 0.1385131478 -0.0618359521 -0.1027960777 877 1311867199.6824479103 0.0567667894 0.0631483243 0.0880107805 0.0053958768 0.1065050000 29268897 955859216 1778556928 0.1361217946 -0.0614000894 -0.1034626812 878 1311867199.7146759033 0.0558431931 0.0631400041 0.0880107805 0.0053935864 0.0744340000 29270695 955859216 1777541120 0.1348657012 -0.0609673969 -0.1040356383 879 1311867199.7511539459 0.0556671359 0.0631315026 0.0880107805 0.0053921609 0.1229100000 29272493 955859216 1776525312 0.1325776130 -0.0605443716 -0.1043514386 880 1311867199.7826020718 0.0554675125 0.0631227935 0.0880107805 0.0053899124 0.1263290000 29274259 955859216 1775509504 0.1303336322 -0.0605787411 -0.1049756110 881 1311867199.8150150776 0.0549546331 0.0631135220 0.0880107805 0.0053941568 0.1100640000 29276025 955859216 1777115136 0.1282775849 -0.0604852140 -0.1055107042 882 1311867199.8519051075 0.0544784032 0.0631037316 0.0880107805 0.0053912040 0.0958410000 29277855 955859216 1778798592 0.1267415434 -0.0597275384 -0.1059166938 883 1311867199.8839609623 0.0542316064 0.0630936839 0.0880107805 0.0053913652 0.0951560000 29279653 955859216 1780543488 0.1245196015 -0.0602327511 -0.1063459814 884 1311867199.9148159027 0.0539663956 0.0630833589 0.0880107805 0.0053895139 0.0962340000 29281419 955859216 1782194176 0.1222763285 -0.0603783019 -0.1068815365 885 1311867199.9520709515 0.0536678173 0.0630727199 0.0880107805 0.0053869151 0.0923770000 29283249 955859216 1783877632 0.1208797395 -0.0598419383 -0.1071493104 886 1311867199.9828410149 0.0529857427 0.0630613351 0.0880107805 0.0053849003 0.0952290000 29284983 955859216 1785622528 0.1197561398 -0.0602913909 -0.1074317843 887 1311867200.0144031048 0.0527568534 0.0630497178 0.0880107805 0.0053821984 0.1152140000 29286749 955859216 1784651776 0.1174502447 -0.0598327368 -0.1078760847 888 1311867200.0539638996 0.0523509160 0.0630376696 0.0880107805 0.0053804285 0.0912120000 29288643 955859216 1783508992 0.1158224270 -0.0586996824 -0.1079967096 889 1311867200.0830330849 0.0518753566 0.0630251136 0.0880107805 0.0053777197 0.0958540000 29290345 955859216 1782493184 0.1145739555 -0.0592982881 -0.1081168354 890 1311867200.1174468994 0.0514591485 0.0630121181 0.0880107805 0.0053775077 0.1206220000 29292143 955859216 1781350400 0.1123472601 -0.0589346588 -0.1082020923 891 1311867200.1517000198 0.0510595329 0.0629987033 0.0880107805 0.0053762755 0.1344410000 29293941 955859216 1780314112 0.1107009426 -0.0584404878 -0.1080767959 892 1311867200.1853220463 0.0512430519 0.0629855243 0.0880107805 0.0053756527 0.1292300000 29295771 955859216 1782067200 0.1083541587 -0.0588562675 -0.1081217676 893 1311867200.2179059982 0.0505217686 0.0629715672 0.0880107805 0.0053744017 0.0894030000 29297537 955859216 1783717888 0.1080102399 -0.0580080636 -0.1078423560 894 1311867200.2522649765 0.0499928109 0.0629570495 0.0880107805 0.0053716323 0.0954360000 29299335 955859216 1785384960 0.1064926907 -0.0580985546 -0.1075423732 895 1311867200.2825429440 0.0497114398 0.0629422500 0.0880107805 0.0053693736 0.1360140000 29301069 955859216 1784397824 0.1043088213 -0.0579696782 -0.1073331907 896 1311867200.3148880005 0.0494086966 0.0629271456 0.0880107805 0.0053664948 0.0951110000 29302867 955859216 1782341632 0.1034335122 -0.0572982132 -0.1066898629 897 1311867200.3514990807 0.0490542501 0.0629116797 0.0880107805 0.0053656556 0.0921260000 29304665 955859216 1782239232 0.1013724953 -0.0579771250 -0.1064500511 898 1311867200.3837759495 0.0489953458 0.0628961827 0.0880107805 0.0053739928 0.1095460000 29306463 955859216 1780969472 0.0992370844 -0.0574961342 -0.1060267240 899 1311867200.4162800312 0.0487984121 0.0628805010 0.0880107805 0.0053716573 0.0940580000 29308197 955859216 1779953664 0.0981594771 -0.0574574396 -0.1055384502 900 1311867200.4522490501 0.0484211035 0.0628644350 0.0880107805 0.0053699000 0.0942730000 29310027 955859216 1777385472 0.0951340497 -0.0578753874 -0.1055928096 901 1311867200.4850699902 0.0481074303 0.0628480566 0.0880107805 0.0053707469 0.0940290000 29311793 955859216 1776369664 0.0925818607 -0.0577319190 -0.1053154394 902 1311867200.5143918991 0.0479137301 0.0628314997 0.0880107805 0.0053703149 0.0922910000 29313559 955859216 1776672768 0.0907876119 -0.0582197160 -0.1047504544 903 1311867200.5505030155 0.0474885441 0.0628145086 0.0880107805 0.0053751457 0.0935680000 29315389 955859216 1775366144 0.0872149467 -0.0580282360 -0.1044474542 904 1311867200.5832219124 0.0477703139 0.0627978668 0.0880107805 0.0053767747 0.0924810000 29317155 955859216 1774366720 0.0850608423 -0.0579988845 -0.1039107069 905 1311867200.6145610809 0.0475574359 0.0627810265 0.0880107805 0.0053756240 0.0916080000 29318889 955859216 1773350912 0.0824071616 -0.0582404658 -0.1035425365 906 1311867200.6504778862 0.0472142436 0.0627638446 0.0880107805 0.0053740396 0.1095360000 29320719 955859216 1772462080 0.0795090646 -0.0580700487 -0.1031247526 907 1311867200.6851279736 0.0469466411 0.0627464056 0.0880107805 0.0053713616 0.0949920000 29322549 955859216 1771446272 0.0768837035 -0.0578751005 -0.1028116867 908 1311867200.7189719677 0.0467996821 0.0627288431 0.0880107805 0.0053703277 0.0935480000 29324347 955859216 1766981632 0.0734952465 -0.0578646101 -0.1026359871 909 1311867200.7503669262 0.0465283804 0.0627110208 0.0880107805 0.0053691821 0.0906790000 29326081 955859216 1768640512 0.0711589679 -0.0576881953 -0.1022279337 910 1311867200.7832930088 0.0463874862 0.0626930829 0.0880107805 0.0053742037 0.0875960000 29327879 955859216 1770430464 0.0686666518 -0.0575204268 -0.1018777862 911 1311867200.8181068897 0.0458667912 0.0626746128 0.0880107805 0.0053732919 0.0933990000 29329677 955859216 1771782144 0.0657342747 -0.0578988791 -0.1015209109 912 1311867200.8501501083 0.0458771437 0.0626561945 0.0880107805 0.0053704150 0.0951000000 29331411 955859216 1773432832 0.0637825504 -0.0573723912 -0.1010050848 913 1311867200.8845369816 0.0462330692 0.0626382064 0.0880107805 0.0053710307 0.0940740000 29333273 955859216 1775210496 0.0604872331 -0.0573512726 -0.1004241258 914 1311867200.9194929600 0.0467554405 0.0626208292 0.0880107805 0.0053723171 0.0947100000 29335071 955859216 1776861184 0.0573876575 -0.0577168837 -0.0999378115 915 1311867200.9512679577 0.0463449433 0.0626030413 0.0880107805 0.0053722277 0.0936690000 29336805 955859216 1778544640 0.0552262366 -0.0579967424 -0.0995915979 916 1311867200.9856009483 0.0470164530 0.0625860254 0.0880107805 0.0053771550 0.0936090000 29338635 955859216 1780289536 0.0529412702 -0.0582585931 -0.0995657817 917 1311867201.0184400082 0.0472401753 0.0625692906 0.0880107805 0.0053745342 0.0943530000 29340401 955859216 1781940224 0.0510020182 -0.0585438907 -0.0995618477 918 1311867201.0555179119 0.0472486578 0.0625526014 0.0880107805 0.0053723418 0.0952400000 29342263 955859216 1783623680 0.0494469963 -0.0585112460 -0.0997288600 919 1311867201.0825428963 0.0475403816 0.0625362660 0.0880107805 0.0053713367 0.0951030000 29343933 955859216 1785368576 0.0475945845 -0.0588956773 -0.0998057649 920 1311867201.1193449497 0.0479039438 0.0625203613 0.0880107805 0.0053692805 0.0958080000 29345795 955859216 1784143872 0.0462312847 -0.0585943609 -0.0997057408 921 1311867201.1506710052 0.0482328571 0.0625048483 0.0880107805 0.0053665971 0.0946180000 29347497 955859216 1783001088 0.0446813330 -0.0583571978 -0.0997786000 922 1311867201.1830160618 0.0481478497 0.0624892767 0.0880107805 0.0053647271 0.0923590000 29349263 955859216 1781985280 0.0435392074 -0.0585870519 -0.0998948067 923 1311867201.2196528912 0.0480732843 0.0624736581 0.0880107805 0.0053651093 0.1066560000 29351061 955859216 1781096448 0.0421219282 -0.0585030057 -0.0999929905 924 1311867201.2503149509 0.0480840281 0.0624580849 0.0880107805 0.0053622163 0.0952170000 29352827 955859216 1780080640 0.0410756692 -0.0582438409 -0.0999092981 925 1311867201.2824099064 0.0479844138 0.0624424377 0.0880107805 0.0053600145 0.0942360000 29354593 955859216 1775484928 0.0394106433 -0.0581327789 -0.1000965461 926 1311867201.3180539608 0.0479022488 0.0624267355 0.0880107805 0.0053586995 0.0971180000 29356423 955859216 1774211072 0.0373750329 -0.0585895367 -0.1003423482 927 1311867201.3522200584 0.0477756597 0.0624109307 0.0880107805 0.0053573519 0.0885820000 29358221 955859216 1775869952 0.0355235413 -0.0577036105 -0.1007340029 928 1311867201.3842790127 0.0477210619 0.0623951011 0.0880107805 0.0053572665 0.0913460000 29359987 955859216 1777541120 0.0336419716 -0.0567021705 -0.1006979197 929 1311867201.4198760986 0.0467753895 0.0623782876 0.0880107805 0.0053768017 0.0937750000 29361753 955859216 1778892800 0.0309185386 -0.0572391786 -0.1012540534 930 1311867201.4558579922 0.0466184206 0.0623613416 0.0880107805 0.0053785927 0.0947500000 29363519 955859216 1780576256 0.0281004924 -0.0562643409 -0.1015042439 931 1311867201.4853110313 0.0467654690 0.0623445898 0.0880107805 0.0053773403 0.0956170000 29365253 955859216 1782321152 0.0251363833 -0.0548472255 -0.1015295312 932 1311867201.5198690891 0.0463042893 0.0623273792 0.0880107805 0.0053760761 0.0959400000 29367083 955859216 1783971840 0.0224754661 -0.0546882562 -0.1016921476 933 1311867201.5527739525 0.0458145887 0.0623096806 0.0880107805 0.0053766989 0.0951770000 29368817 955859216 1785655296 0.0204868577 -0.0546015501 -0.1018419266 934 1311867201.5840220451 0.0458104461 0.0622920155 0.0880107805 0.0053738639 0.0962140000 29370583 955859216 1784524800 0.0186060909 -0.0542094260 -0.1020279154 935 1311867201.6197049618 0.0458798073 0.0622744623 0.0880107805 0.0053717403 0.0938710000 29372413 955859216 1783635968 0.0164147001 -0.0539327934 -0.1023541540 936 1311867201.6515579224 0.0454264879 0.0622564623 0.0880107805 0.0053715352 0.0924650000 29374147 955859216 1782366208 0.0153542608 -0.0540493503 -0.1026309878 937 1311867201.6839449406 0.0453290902 0.0622383968 0.0880107805 0.0053688219 0.0944700000 29375945 955859216 1781350400 0.0129502183 -0.0534526892 -0.1030949205 938 1311867201.7189009190 0.0452542491 0.0622202901 0.0880107805 0.0053665277 0.0933460000 29377775 955859216 1780334592 0.0123818535 -0.0523937009 -0.1032730117 939 1311867201.7507290840 0.0450372547 0.0622019908 0.0880107805 0.0053642757 0.0925800000 29379541 955859216 1779318784 0.0100618359 -0.0523043014 -0.1036372185 940 1311867201.7858049870 0.0443050228 0.0621829514 0.0880107805 0.0053712751 0.0936310000 29381307 955859216 1778302976 0.0085565709 -0.0518438369 -0.1038732082 941 1311867201.8190178871 0.0446666665 0.0621643369 0.0880107805 0.0053762263 0.0929360000 29383137 955859216 1777287168 0.0073080179 -0.0503165126 -0.1038693786 942 1311867201.8505740166 0.0444466881 0.0621455283 0.0880107805 0.0053767251 0.0932170000 29384871 955859216 1776271360 0.0056322850 -0.0502911024 -0.1041705012 943 1311867201.8862850666 0.0442996137 0.0621266037 0.0880107805 0.0053740869 0.0929000000 29386669 955859216 1775255552 0.0050284439 -0.0501123555 -0.1044387966 944 1311867201.9195730686 0.0445737019 0.0621080096 0.0880107805 0.0053752380 0.0914440000 29388499 955859216 1774239744 0.0036204741 -0.0493411534 -0.1046659723 945 1311867201.9516520500 0.0443817154 0.0620892516 0.0880107805 0.0053732366 0.1093390000 29390201 955859216 1773223936 0.0026711270 -0.0494123176 -0.1052175686 946 1311867201.9894599915 0.0440931246 0.0620702282 0.0880107805 0.0053705820 0.0924740000 29392095 955859216 1772204032 0.0022792227 -0.0493918173 -0.1058371589 947 1311867202.0184879303 0.0440089628 0.0620511561 0.0880107805 0.0053678516 0.0923530000 29393797 955859216 1773846528 0.0010700643 -0.0489130057 -0.1064122617 948 1311867202.0507359505 0.0438742936 0.0620319822 0.0880107805 0.0053654224 0.0952580000 29395563 955859216 1775591424 0.0007433556 -0.0483595394 -0.1069727913 949 1311867202.0866351128 0.0439247042 0.0620129018 0.0880107805 0.0053629108 0.0942360000 29397393 955859216 1777242112 -0.0010857469 -0.0481179059 -0.1074420735 950 1311867202.1185920238 0.0434873700 0.0619934013 0.0880107805 0.0053613361 0.0957630000 29399159 955859216 1779019776 -0.0014873333 -0.0476005673 -0.1077432707 951 1311867202.1516621113 0.0436028317 0.0619740631 0.0880107805 0.0053593470 0.0956340000 29400957 955859216 1780670464 -0.0024313543 -0.0468032621 -0.1077629849 952 1311867202.1866259575 0.0434289686 0.0619545830 0.0880107805 0.0053565606 0.1097020000 29402755 955859216 1782353920 -0.0030203806 -0.0465692021 -0.1078341454 953 1311867202.2191269398 0.0431402288 0.0619348407 0.0880107805 0.0053538491 0.0935630000 29404521 955859216 1784098816 -0.0039634365 -0.0465774797 -0.1080480665 954 1311867202.2513220310 0.0429010354 0.0619148892 0.0880107805 0.0053515677 0.0964610000 29406255 955859216 1785749504 -0.0048340852 -0.0459143780 -0.1080029532 955 1311867202.2868280411 0.0429414846 0.0618950217 0.0880107805 0.0053509233 0.0973640000 29408085 955859216 1784762368 -0.0061534499 -0.0449269786 -0.1078749821 956 1311867202.3199880123 0.0428712219 0.0618751223 0.0880107805 0.0053504944 0.0965650000 29409851 955859216 1780940800 -0.0073093502 -0.0455897599 -0.1081068739 957 1311867202.3523900509 0.0426382460 0.0618550211 0.0880107805 0.0053480819 0.0878430000 29411617 955859216 1782620160 -0.0090117883 -0.0452318564 -0.1083348766 958 1311867202.3883628845 0.0423163585 0.0618346258 0.0880107805 0.0053453874 0.0923420000 29413447 955859216 1784131584 -0.0100615621 -0.0445303842 -0.1084106714 959 1311867202.4196391106 0.0425185636 0.0618144840 0.0880107805 0.0053444218 0.0960040000 29415213 955859216 1782980608 -0.0110738026 -0.0445278138 -0.1084397361 960 1311867202.4529430866 0.0427698530 0.0617946458 0.0880107805 0.0053421237 0.0923610000 29416979 955859216 1782112256 -0.0116912713 -0.0447002240 -0.1083887368 961 1311867202.4875710011 0.0432858914 0.0617753859 0.0880107805 0.0053423915 0.0923890000 29418777 955859216 1781096448 -0.0132035566 -0.0441031791 -0.1082137153 962 1311867202.5206449032 0.0432797335 0.0617561597 0.0880107805 0.0053584931 0.0922290000 29420543 955859216 1780080640 -0.0144196311 -0.0435199514 -0.1084447950 963 1311867202.5508940220 0.0435891598 0.0617372947 0.0880107805 0.0053558473 0.0932240000 29422277 955859216 1779064832 -0.0153337913 -0.0437253378 -0.1083128154 964 1311867202.5864949226 0.0440774448 0.0617189753 0.0880107805 0.0053676521 0.1089170000 29424139 955859216 1778049024 -0.0164050627 -0.0438741744 -0.1085749269 965 1311867202.6185030937 0.0441521071 0.0617007713 0.0880107805 0.0053714727 0.0938140000 29425905 955859216 1777033216 -0.0183121786 -0.0436420068 -0.1091808304 966 1311867202.6514449120 0.0439400822 0.0616823855 0.0880107805 0.0053756657 0.1326770000 29427671 955859216 1776001024 -0.0209732316 -0.0436146036 -0.1099402755 967 1311867202.6866559982 0.0437686555 0.0616638604 0.0880107805 0.0053733607 0.1099900000 29429501 955859216 1777623040 -0.0219461601 -0.0431761965 -0.1106548905 968 1311867202.7185359001 0.0438077152 0.0616454140 0.0880107805 0.0053710172 0.0777030000 29431267 955859216 1779273728 -0.0235047098 -0.0438763127 -0.1116422638 969 1311867202.7507350445 0.0437808670 0.0616269780 0.0880107805 0.0053690081 0.0952340000 29433033 955859216 1780957184 -0.0250799078 -0.0445263274 -0.1127493754 970 1311867202.7897169590 0.0438798405 0.0616086819 0.0880107805 0.0053665557 0.1332960000 29434927 955859216 1782702080 -0.0263378844 -0.0439854898 -0.1136599705 971 1311867202.8190000057 0.0435047857 0.0615900373 0.0880107805 0.0053649191 0.1075700000 29436661 955859216 1784352768 -0.0278571844 -0.0443179980 -0.1145319566 972 1311867202.8527579308 0.0427527502 0.0615706574 0.0880107805 0.0053621941 0.1000000000 29438427 955859216 1783382016 -0.0292008091 -0.0446828753 -0.1153152958 973 1311867202.8873219490 0.0421201997 0.0615506672 0.0880107805 0.0053612271 0.1421820000 29440225 955859216 1778802688 -0.0297098830 -0.0433174334 -0.1158708110 974 1311867202.9199879169 0.0421525836 0.0615307513 0.0880107805 0.0053593018 0.1085270000 29441991 955859216 1780461568 -0.0299293753 -0.0424974971 -0.1157735959 975 1311867202.9525690079 0.0423053317 0.0615110330 0.0880107805 0.0053611318 0.0934540000 29443789 955859216 1782222848 -0.0300440006 -0.0428378396 -0.1157161221 976 1311867202.9868710041 0.0423776060 0.0614914290 0.0880107805 0.0053635033 0.0939220000 29445587 955859216 1783590912 -0.0304535087 -0.0426411964 -0.1152464300 977 1311867203.0202019215 0.0423070639 0.0614717930 0.0880107805 0.0053607748 0.0940730000 29447353 955859216 1785241600 -0.0301362853 -0.0423341729 -0.1149599701 978 1311867203.0560851097 0.0424777493 0.0614523717 0.0880107805 0.0053623097 0.0974870000 29449183 955859216 1784143872 -0.0295111481 -0.0440461412 -0.1145990565 979 1311867203.0865778923 0.0431288667 0.0614336552 0.0880107805 0.0053609762 0.0960770000 29450917 955859216 1780432896 -0.0297832042 -0.0446756445 -0.1141670644 980 1311867203.1189930439 0.0434488952 0.0614153034 0.0880107805 0.0053638607 0.0888490000 29452683 955859216 1781858304 -0.0300589763 -0.0454001948 -0.1138392612 981 1311867203.1549820900 0.0436846316 0.0613972293 0.0880107805 0.0053702770 0.0867860000 29454513 955859216 1780699136 -0.0304545090 -0.0474151336 -0.1138377115 982 1311867203.1877939701 0.0443424396 0.0613798619 0.0880107805 0.0054028162 0.0970370000 29456279 955859216 1779572736 -0.0310908873 -0.0487823933 -0.1140361130 983 1311867203.2185909748 0.0445165001 0.0613627069 0.0880107805 0.0054015755 0.1370010000 29458045 955859216 1778536448 -0.0305749401 -0.0487305559 -0.1142652556 984 1311867203.2552030087 0.0447569638 0.0613458311 0.0880107805 0.0053999240 0.1317020000 29459875 955859216 1780195328 -0.0301457960 -0.0497728586 -0.1144727096 985 1311867203.2864799500 0.0448481292 0.0613290822 0.0880107805 0.0053997162 0.1299420000 29461609 955859216 1781940224 -0.0307991058 -0.0511908010 -0.1148771495 986 1311867203.3194670677 0.0446186550 0.0613121345 0.0880107805 0.0053971433 0.0985780000 29463439 955859216 1783590912 -0.0301459357 -0.0516960584 -0.1152617708 987 1311867203.3547461033 0.0441328660 0.0612947290 0.0880107805 0.0053950552 0.1030960000 29465205 955859216 1785368576 -0.0290375594 -0.0519291386 -0.1156386882 988 1311867203.3865599632 0.0437481180 0.0612769692 0.0880107805 0.0053975336 0.1024910000 29466971 955859216 1784266752 -0.0290086605 -0.0531043150 -0.1159988791 989 1311867203.4183609486 0.0433810242 0.0612588743 0.0880107805 0.0054029117 0.0900530000 29468769 955859216 1783238656 -0.0283907149 -0.0564391054 -0.1164181679 990 1311867203.4545118809 0.0431714095 0.0612406041 0.0880107805 0.0054021665 0.1298250000 29470599 955859216 1782239232 -0.0280565601 -0.0576667637 -0.1165851131 991 1311867203.4864439964 0.0431535728 0.0612223528 0.0880107805 0.0054021233 0.1073010000 29472333 955859216 1781223424 -0.0276813433 -0.0591116212 -0.1165630817 992 1311867203.5185539722 0.0431393646 0.0612041240 0.0880107805 0.0054042380 0.0826490000 29474131 955859216 1779953664 -0.0281665847 -0.0618523806 -0.1171028018 993 1311867203.5560259819 0.0433501713 0.0611861442 0.0880107805 0.0054018598 0.1246720000 29475961 955859216 1778937856 -0.0281338170 -0.0638767555 -0.1175161600 994 1311867203.5876550674 0.0433139950 0.0611681641 0.0880107805 0.0054000530 0.1057140000 29477727 955859216 1774329856 -0.0277920272 -0.0649767965 -0.1178508252 995 1311867203.6191980839 0.0432673953 0.0611501734 0.0880107805 0.0053983889 0.1108660000 29479493 955859216 1776005120 -0.0279152952 -0.0672272071 -0.1182081997 996 1311867203.6557719707 0.0431103893 0.0611320612 0.0880107805 0.0053957512 0.1101210000 29481291 955859216 1777778688 -0.0277106836 -0.0698282942 -0.1187375188 997 1311867203.6866750717 0.0429143794 0.0611137887 0.0880107805 0.0053931484 0.0938840000 29483057 955859216 1779146752 -0.0280724932 -0.0714774355 -0.1191606447 998 1311867203.7195260525 0.0431143790 0.0610957532 0.0880107805 0.0053908258 0.0943990000 29484823 955859216 1780797440 -0.0280644577 -0.0733757019 -0.1192424223 999 1311867203.7566421032 0.0435549282 0.0610781948 0.0880107805 0.0053884967 0.0948220000 29486685 955859216 1782480896 -0.0282531381 -0.0746078640 -0.1193497404 1000 1311867203.7867228985 0.0437891670 0.0610609058 0.0880107805 0.0053858543 0.0869190000 29488419 955859216 1784225792 -0.0287317708 -0.0764242634 -0.1196717024 1001 1311867203.8193860054 0.0438674837 0.0610437295 0.0880107805 0.0053832418 0.1238210000 29490185 955859216 1785876480 -0.0281450637 -0.0776702315 -0.1201404110 1002 1311867203.8572859764 0.0440293588 0.0610267491 0.0880107805 0.0053816655 0.1144600000 29492047 955859216 1784647680 -0.0283762943 -0.0788333789 -0.1207935661 1003 1311867203.8891890049 0.0440637469 0.0610098369 0.0880107805 0.0053797380 0.0910890000 29493813 955859216 1783627776 -0.0287848711 -0.0807711631 -0.1216570064 1004 1311867203.9188020229 0.0442388058 0.0609931327 0.0880107805 0.0053777212 0.1313810000 29495547 955859216 1782628352 -0.0295843221 -0.0819287002 -0.1224420071 1005 1311867203.9553489685 0.0441804789 0.0609764036 0.0880107805 0.0053754260 0.1116940000 29497377 955859216 1781612544 -0.0292687584 -0.0823643580 -0.1233179271 1006 1311867203.9866371155 0.0442311466 0.0609597583 0.0880107805 0.0053743250 0.1138730000 29499143 955859216 1783218176 -0.0295676030 -0.0839604959 -0.1242211312 1007 1311867204.0199849606 0.0443793088 0.0609432931 0.0880107805 0.0053728124 0.0950580000 29500909 955859216 1784868864 -0.0298504904 -0.0847907141 -0.1253487468 1008 1311867204.0551509857 0.0443871841 0.0609268684 0.0880107805 0.0053704817 0.0968990000 29502739 955859216 1783750656 -0.0304074008 -0.0858962685 -0.1265279651 1009 1311867204.0867509842 0.0441383794 0.0609102296 0.0880107805 0.0053693664 0.0924300000 29504505 955859216 1782755328 -0.0309714042 -0.0876646712 -0.1275866330 1010 1311867204.1191530228 0.0444744974 0.0608939566 0.0880107805 0.0053667778 0.0915440000 29506271 955859216 1781739520 -0.0313094109 -0.0889593735 -0.1285039634 1011 1311867204.1555769444 0.0445606820 0.0608778010 0.0880107805 0.0053644324 0.0789370000 29508069 955859216 1780723712 -0.0314087048 -0.0904467255 -0.1291964203 1012 1311867204.1876530647 0.0444867015 0.0608616043 0.0880107805 0.0053624763 0.1036740000 29509835 955859216 1779707904 -0.0321735367 -0.0920164436 -0.1298831850 1013 1311867204.2187769413 0.0447436981 0.0608456932 0.0880107805 0.0053605814 0.0928500000 29511601 955859216 1778692096 -0.0329854377 -0.0930550843 -0.1303218305 1014 1311867204.2566440105 0.0451350845 0.0608301996 0.0880107805 0.0053581471 0.1155900000 29513463 955859216 1774235648 -0.0331779048 -0.0942217186 -0.1307947636 1015 1311867204.2867140770 0.0452887602 0.0608148878 0.0880107805 0.0053555705 0.0901900000 29515197 955859216 1775910912 -0.0337889120 -0.0962510556 -0.1312334538 1016 1311867204.3204538822 0.0458836034 0.0608001916 0.0880107805 0.0053535308 0.1068470000 29516963 955859216 1777655808 -0.0348733738 -0.0971464366 -0.1316329092 1017 1311867204.3625741005 0.0465344228 0.0607861643 0.0880107805 0.0053510280 0.0930400000 29518921 955859216 1779027968 -0.0359307453 -0.0987031460 -0.1317966878 1018 1311867204.3869600296 0.0466801189 0.0607723077 0.0880107805 0.0053485805 0.0829600000 29520559 955859216 1780711424 -0.0367262028 -0.0999822840 -0.1321696788 1019 1311867204.4240970612 0.0474651866 0.0607592487 0.0880107805 0.0053463946 0.1284160000 29522421 955859216 1782456320 -0.0377643965 -0.1009697989 -0.1324881762 1020 1311867204.4549949169 0.0479957834 0.0607467355 0.0880107805 0.0053450332 0.0938370000 29524155 955859216 1784107008 -0.0385304242 -0.1017370299 -0.1326771528 1021 1311867204.4872748852 0.0484922193 0.0607347330 0.0880107805 0.0053428580 0.0940020000 29525921 955859216 1785884672 -0.0395825841 -0.1034312844 -0.1329666227 1022 1311867204.5237219334 0.0488346033 0.0607230891 0.0880107805 0.0053403599 0.0969630000 29527783 955859216 1784659968 -0.0401552767 -0.1045527235 -0.1333710700 1023 1311867204.5581860542 0.0491964817 0.0607118216 0.0880107805 0.0053387348 0.0928450000 29529581 955859216 1783517184 -0.0408135019 -0.1052750796 -0.1335969418 1024 1311867204.5878469944 0.0491966046 0.0607005763 0.0880107805 0.0053365104 0.0914840000 29531315 955859216 1782501376 -0.0414646231 -0.1069952920 -0.1337204278 1025 1311867204.6241528988 0.0490286089 0.0606891890 0.0880107805 0.0053340937 0.0927240000 29615065 955859216 1781612544 -0.0421757065 -0.1080635637 -0.1336810887 1026 1311867204.6541819572 0.0492829345 0.0606780718 0.0880107805 0.0053318825 0.1061180000 29784735 955859216 1780453376 -0.0426756740 -0.1101525202 -0.1335211396 1027 1311867204.6871540546 0.0496786200 0.0606673615 0.0880107805 0.0053296663 0.0926240000 29786501 955859216 1779453952 -0.0435886979 -0.1111829504 -0.1334131509 1028 1311867204.7225689888 0.0498809628 0.0606568689 0.0880107805 0.0053282978 0.0906820000 29788331 955859216 1774231552 -0.0437719934 -0.1117218658 -0.1331497729 1029 1311867204.7539510727 0.0499001481 0.0606464154 0.0880107805 0.0053258678 0.1289630000 29790097 955859216 1775984640 -0.0451743454 -0.1129426584 -0.1328375340 1030 1311867204.7878720760 0.0501132719 0.0606361890 0.0880107805 0.0053250867 0.1064440000 29791895 955859216 1777655808 -0.0468116328 -0.1145286039 -0.1320301890 1031 1311867204.8227200508 0.0499907583 0.0606258637 0.0880107805 0.0053226323 0.0933670000 29793693 955859216 1779187712 -0.0468207821 -0.1153721437 -0.1307411343 1032 1311867204.8542668819 0.0498320088 0.0606154045 0.0880107805 0.0053213882 0.0915330000 29795459 955859216 1780932608 -0.0470509715 -0.1168335751 -0.1294379234 1033 1311867204.8864960670 0.0501344129 0.0606052583 0.0880107805 0.0053198945 0.0952120000 29797225 955859216 1782583296 -0.0481615141 -0.1190391779 -0.1284588277 1034 1311867204.9220221043 0.0504898168 0.0605954755 0.0880107805 0.0053175033 0.0944880000 29799055 955859216 1784360960 -0.0495149493 -0.1210430264 -0.1272820234 1035 1311867204.9542920589 0.0504735075 0.0605856958 0.0880107805 0.0053154730 0.0971760000 29800821 955859216 1783246848 -0.0498756617 -0.1225292385 -0.1262888759 1036 1311867204.9865999222 0.0507303961 0.0605761830 0.0880107805 0.0053130818 0.0932600000 29802587 955859216 1782120448 -0.0504739769 -0.1252213269 -0.1254590452 1037 1311867205.0227239132 0.0509833097 0.0605669324 0.0880107805 0.0053147869 0.0923690000 29804417 955859216 1781104640 -0.0509113520 -0.1268067360 -0.1247160807 1038 1311867205.0550808907 0.0505052693 0.0605572391 0.0880107805 0.0053278290 0.0934940000 29806215 955859216 1780084736 -0.0512573496 -0.1277294159 -0.1238472760 1039 1311867205.0880999565 0.0507034212 0.0605477551 0.0880107805 0.0053255118 0.0933080000 29807917 955859216 1779073024 -0.0518282987 -0.1299780607 -0.1229805350 1040 1311867205.1232450008 0.0513580292 0.0605389189 0.0880107805 0.0053243974 0.0930060000 29809747 955859216 1778057216 -0.0518977977 -0.1314648688 -0.1221550182 1041 1311867205.1545319557 0.0520531498 0.0605307673 0.0880107805 0.0053354692 0.0927420000 29811481 955859216 1777041408 -0.0517202206 -0.1326349825 -0.1214348227 1042 1311867205.1863510609 0.0520577878 0.0605226358 0.0880107805 0.0053430391 0.0933470000 29813247 955859216 1776025600 -0.0518146046 -0.1350509524 -0.1206110120 1043 1311867205.2223129272 0.0516872518 0.0605141647 0.0880107805 0.0053418531 0.0934920000 29815077 955859216 1775009792 -0.0516263992 -0.1369590163 -0.1200441793 1044 1311867205.2541849613 0.0517993085 0.0605058171 0.0880107805 0.0053409840 0.0925240000 29816843 955859216 1773993984 -0.0518640019 -0.1384844929 -0.1193062067 1045 1311867205.2880499363 0.0522882268 0.0604979534 0.0880107805 0.0053389245 0.1277590000 29818641 955859216 1773248512 -0.0524819940 -0.1401096731 -0.1184810922 1046 1311867205.3218879700 0.0526940376 0.0604904927 0.0880107805 0.0053383775 0.1152450000 29820407 955859216 1769013248 -0.0529789962 -0.1417586058 -0.1177197322 1047 1311867205.3542900085 0.0530321114 0.0604833691 0.0880107805 0.0053424280 0.0885940000 29822205 955859216 1770692608 -0.0537694097 -0.1434703767 -0.1167928576 1048 1311867205.3862779140 0.0532201529 0.0604764386 0.0880107805 0.0053489016 0.0919960000 29823971 955859216 1772298240 -0.0544493683 -0.1447777599 -0.1159322336 1049 1311867205.4225649834 0.0533519872 0.0604696469 0.0880107805 0.0053510248 0.0929270000 29825801 955859216 1774075904 -0.0556483492 -0.1464882791 -0.1152066290 1050 1311867205.4540419579 0.0536247529 0.0604631280 0.0880107805 0.0053540851 0.0938490000 29827567 955859216 1775726592 -0.0560896359 -0.1476395875 -0.1142725721 1051 1311867205.4865119457 0.0528260656 0.0604558615 0.0880107805 0.0053567914 0.0942120000 29829333 955859216 1777393664 -0.0565515570 -0.1491733491 -0.1132703125 1052 1311867205.5230340958 0.0528591722 0.0604486403 0.0880107805 0.0053652881 0.0945720000 29831163 955859216 1779154944 -0.0576919653 -0.1510606557 -0.1123579815 1053 1311867205.5542900562 0.0533210561 0.0604418715 0.0880107805 0.0053843076 0.0955580000 29832929 955859216 1780805632 -0.0590641126 -0.1517821252 -0.1111951545 1054 1311867205.5866839886 0.0531631187 0.0604349656 0.0880107805 0.0053818199 0.0939540000 29834695 955859216 1782583296 -0.0601802953 -0.1531647593 -0.1101288721 1055 1311867205.6226179600 0.0524338931 0.0604273817 0.0880107805 0.0053857494 0.0924650000 29836525 955859216 1784266752 -0.0606479198 -0.1553838551 -0.1091818959 1056 1311867205.6555979252 0.0524429083 0.0604198206 0.0880107805 0.0053842326 0.0960490000 29838291 955859216 1783242752 -0.0622434355 -0.1578565687 -0.1083028391 1057 1311867205.6902959347 0.0525277033 0.0604123541 0.0880107805 0.0053817668 0.0948370000 29840121 955859216 1782226944 -0.0627357364 -0.1593755186 -0.1075406298 1058 1311867205.7222061157 0.0528108813 0.0604051693 0.0880107805 0.0053793442 0.0928100000 29841887 955859216 1781227520 -0.0643157884 -0.1617773324 -0.1070271358 1059 1311867205.7548348904 0.0530963913 0.0603982678 0.0880107805 0.0053772200 0.0913010000 29843685 955859216 1780215808 -0.0655813366 -0.1634889245 -0.1066172346 1060 1311867205.7906379700 0.0531582907 0.0603914376 0.0880107805 0.0053750648 0.1085710000 29845483 955859216 1779200000 -0.0664179102 -0.1651226133 -0.1060972810 1061 1311867205.8232109547 0.0536860004 0.0603851177 0.0880107805 0.0053818783 0.1097020000 29847281 955859216 1778176000 -0.0679126158 -0.1672583520 -0.1055748537 1062 1311867205.8554759026 0.0536697172 0.0603787943 0.0880107805 0.0053835705 0.1090360000 29849079 955859216 1779814400 -0.0689296722 -0.1688518822 -0.1051428169 1063 1311867205.8905880451 0.0539117381 0.0603727105 0.0880107805 0.0053828910 0.0920480000 29850845 955859216 1781559296 -0.0700945482 -0.1703466922 -0.1048075259 1064 1311867205.9223020077 0.0539180338 0.0603666441 0.0880107805 0.0053899296 0.0932370000 29852611 955859216 1783209984 -0.0708443895 -0.1717505157 -0.1044791266 1065 1311867205.9544939995 0.0538781583 0.0603605516 0.0880107805 0.0053876024 0.0935140000 29854377 955859216 1784893440 -0.0715764388 -0.1739688516 -0.1040703505 1066 1311867205.9905850887 0.0546813123 0.0603552240 0.0880107805 0.0053958965 0.0966910000 29856239 955859216 1783889920 -0.0730822086 -0.1745952368 -0.1035926044 1067 1311867206.0259850025 0.0545659848 0.0603497983 0.0880107805 0.0053970415 0.0925680000 29858037 955859216 1782874112 -0.0733709857 -0.1755435318 -0.1033459455 1068 1311867206.0604250431 0.0540668555 0.0603439154 0.0880107805 0.0054042592 0.0920640000 29859803 955859216 1781858304 -0.0737025589 -0.1782231182 -0.1032500565 1069 1311867206.0903289318 0.0537829474 0.0603377779 0.0880107805 0.0054018972 0.0927030000 29861537 955859216 1781096448 -0.0738781691 -0.1802701056 -0.1033021063 1070 1311867206.1227540970 0.0539749712 0.0603318314 0.0880107805 0.0053993889 0.0919050000 29863303 955859216 1779810304 -0.0739560351 -0.1822119057 -0.1028711274 1071 1311867206.1546130180 0.0544350334 0.0603263255 0.0880107805 0.0053971542 0.1054930000 29865069 955859216 1778810880 -0.0746004134 -0.1844521165 -0.1029870957 1072 1311867206.1903800964 0.0547508262 0.0603211245 0.0880107805 0.0053985653 0.0907410000 29866931 955859216 1777795072 -0.0760333985 -0.1870781183 -0.1030385941 1073 1311867206.2239561081 0.0547214150 0.0603159057 0.0880107805 0.0053965882 0.0889780000 29868729 955859216 1775996928 -0.0761316717 -0.1883517206 -0.1031656861 1074 1311867206.2553579807 0.0543056279 0.0603103096 0.0880107805 0.0053953421 0.1164690000 29870463 955859216 1775255552 -0.0760770515 -0.1901095212 -0.1034941301 1075 1311867206.2904770374 0.0541408099 0.0603045705 0.0880107805 0.0053929542 0.0936650000 29872261 955859216 1774239744 -0.0766364112 -0.1923706234 -0.1038488299 1076 1311867206.3222041130 0.0540812984 0.0602987868 0.0880107805 0.0053909106 0.0810640000 29873995 955859216 1773334528 -0.0771861523 -0.1935498267 -0.1042890400 1077 1311867206.3542530537 0.0540767424 0.0602930096 0.0880107805 0.0053894521 0.0976000000 29875793 955859216 1772335104 -0.0780146867 -0.1952486336 -0.1045276597 1078 1311867206.3900070190 0.0539474562 0.0602871232 0.0880107805 0.0053882219 0.0961480000 29877591 955859216 1771319296 -0.0781891048 -0.1971831024 -0.1046596989 1079 1311867206.4220259190 0.0537456572 0.0602810606 0.0880107805 0.0053867291 0.0933970000 29879357 955859216 1770303488 -0.0780478269 -0.1988468468 -0.1046900898 1080 1311867206.4542310238 0.0535937548 0.0602748687 0.0880107805 0.0053849852 0.0898260000 29881155 955859216 1765572608 -0.0783508644 -0.2006575316 -0.1046193391 1081 1311867206.4905378819 0.0531869493 0.0602683119 0.0880107805 0.0053931147 0.0901930000 29882953 955859216 1767247872 -0.0789815784 -0.2032070458 -0.1047329083 1082 1311867206.5250329971 0.0535245538 0.0602620792 0.0880107805 0.0053949260 0.0925200000 29884783 955859216 1768906752 -0.0797439665 -0.2055475563 -0.1048414633 1083 1311867206.5539300442 0.0535566546 0.0602558877 0.0880107805 0.0053988482 0.0923230000 29886517 955859216 1770274816 -0.0798309669 -0.2078575641 -0.1048254445 1084 1311867206.5921130180 0.0536275096 0.0602497729 0.0880107805 0.0053974209 0.0950550000 29888347 955859216 1772036096 -0.0798742324 -0.2097996473 -0.1050488502 1085 1311867206.6226360798 0.0547530241 0.0602447068 0.0880107805 0.0054096752 0.0962840000 29890081 955859216 1773686784 -0.0808755606 -0.2116204351 -0.1051932871 1086 1311867206.6566751003 0.0541924238 0.0602391338 0.0880107805 0.0054081102 0.0918610000 29891879 955859216 1775370240 -0.0811700076 -0.2136679143 -0.1053880751 1087 1311867206.6945209503 0.0540081374 0.0602334015 0.0880107805 0.0054066447 0.0946220000 29893741 955859216 1777115136 -0.0807983652 -0.2147176713 -0.1057281792 1088 1311867206.7248480320 0.0534171909 0.0602271366 0.0880107805 0.0054126572 0.0936140000 29895475 955859216 1778765824 -0.0810338929 -0.2169309258 -0.1060246974 1089 1311867206.7587969303 0.0545311235 0.0602219061 0.0880107805 0.0054534118 0.0949200000 29897305 955859216 1780449280 -0.0810074359 -0.2180355787 -0.1064212844 1090 1311867206.7902839184 0.0537723787 0.0602159891 0.0880107805 0.0054681661 0.0934410000 29899071 955859216 1782226944 -0.0815501139 -0.2197658420 -0.1068508998 1091 1311867206.8229770660 0.0545312800 0.0602107786 0.0880107805 0.0054665027 0.0793900000 29900837 955859216 1783971840 -0.0834385976 -0.2216627747 -0.1073833257 1092 1311867206.8605449200 0.0545261614 0.0602055729 0.0880107805 0.0054641828 0.1144320000 29902667 955859216 1785622528 -0.0837140307 -0.2235151380 -0.1080236211 1093 1311867206.8907771111 0.0541577749 0.0602000397 0.0880107805 0.0054627662 0.0966940000 29904401 955859216 1784524800 -0.0833589286 -0.2245431542 -0.1086439192 1094 1311867206.9225020409 0.0541990586 0.0601945543 0.0880107805 0.0054602772 0.0911060000 29906167 955859216 1783382016 -0.0836835355 -0.2263946980 -0.1092297211 1095 1311867206.9592480659 0.0553308241 0.0601901125 0.0880107805 0.0054594409 0.0927990000 29908029 955859216 1782366208 -0.0853482932 -0.2290434986 -0.1097472236 1096 1311867206.9948680401 0.0556976534 0.0601860136 0.0880107805 0.0054675085 0.0908460000 29909827 955859216 1781477376 -0.0859637037 -0.2311764657 -0.1099660993 1097 1311867207.0247550011 0.0563883148 0.0601825517 0.0880107805 0.0054705297 0.1086630000 29911593 955859216 1780461568 -0.0860545188 -0.2329529226 -0.1099993959 1098 1311867207.0597259998 0.0556637682 0.0601784362 0.0880107805 0.0054684490 0.0939620000 29913423 955859216 1775755264 -0.0857231542 -0.2352257818 -0.1104006991 1099 1311867207.0942800045 0.0558352917 0.0601744843 0.0880107805 0.0054718369 0.1226400000 29915189 955859216 1777410048 -0.0862994045 -0.2379781008 -0.1105447561 1100 1311867207.1229140759 0.0558074377 0.0601705143 0.0880107805 0.0054748202 0.0890380000 29916891 955859216 1779171328 -0.0857879072 -0.2390214205 -0.1107779369 1101 1311867207.1583549976 0.0563468151 0.0601670413 0.0880107805 0.0054790053 0.0905810000 29918721 955859216 1780543488 -0.0859478191 -0.2408827990 -0.1108413488 1102 1311867207.1904919147 0.0559721068 0.0601632347 0.0880107805 0.0054777791 0.0947290000 29920455 955859216 1782194176 -0.0860390440 -0.2426785380 -0.1109633893 1103 1311867207.2226181030 0.0557436794 0.0601592278 0.0880107805 0.0054774870 0.0937460000 29922253 955859216 1783971840 -0.0858097449 -0.2438747734 -0.1108850911 1104 1311867207.2604830265 0.0558842979 0.0601553556 0.0880107805 0.0054778444 0.0937410000 29924115 955859216 1785622528 -0.0862419605 -0.2452906072 -0.1106175482 1105 1311867207.2926900387 0.0555985719 0.0601512318 0.0880107805 0.0054773986 0.0972680000 29925881 955859216 1784377344 -0.0863861740 -0.2470486313 -0.1104710400 1106 1311867207.3235239983 0.0563344173 0.0601477808 0.0880107805 0.0054815619 0.0936380000 29927615 955859216 1783382016 -0.0873142481 -0.2485167235 -0.1098499894 1107 1311867207.3597478867 0.0558983311 0.0601439421 0.0880107805 0.0054802173 0.0921810000 29929477 955859216 1782366208 -0.0877338424 -0.2501687109 -0.1093916297 1108 1311867207.3901309967 0.0557804517 0.0601400039 0.0880107805 0.0054806173 0.0903590000 29931211 955859216 1781350400 -0.0883928910 -0.2524398863 -0.1088786200 1109 1311867207.4227840900 0.0555450097 0.0601358606 0.0880107805 0.0054783719 0.0901580000 29932977 955859216 1780318208 -0.0898048729 -0.2544280589 -0.1086855754 1110 1311867207.4586789608 0.0556798950 0.0601318462 0.0880107805 0.0054780109 0.0937640000 29934807 955859216 1779318784 -0.0904537961 -0.2553958595 -0.1082059070 1111 1311867207.4927639961 0.0557356551 0.0601278892 0.0880107805 0.0054772961 0.0921760000 29936605 955859216 1775353856 -0.0913975611 -0.2572892010 -0.1078827828 1112 1311867207.5237300396 0.0559050590 0.0601240917 0.0880107805 0.0054809453 0.0871110000 29938371 955859216 1773453312 -0.0922361165 -0.2588889301 -0.1075756177 1113 1311867207.5598409176 0.0561821759 0.0601205500 0.0880107805 0.0054792868 0.0899230000 29940169 955859216 1775128576 -0.0935692340 -0.2604097724 -0.1073560342 1114 1311867207.5944800377 0.0564671047 0.0601172704 0.0880107805 0.0054794014 0.0919320000 29941999 955859216 1776889856 -0.0948520824 -0.2621328831 -0.1071719304 1115 1311867207.6259219646 0.0552836210 0.0601129353 0.0880107805 0.0054771803 0.0933290000 29943733 955859216 1778163712 -0.0943799168 -0.2650546134 -0.1066436097 1116 1311867207.6592938900 0.0549813695 0.0601083372 0.0880107805 0.0054755128 0.0929080000 29945563 955859216 1779908608 -0.0946155414 -0.2666890025 -0.1065653637 1117 1311867207.6923089027 0.0557489060 0.0601044344 0.0880107805 0.0054750127 0.0937650000 29947329 955859216 1781559296 -0.0960231051 -0.2683689594 -0.1062964499 1118 1311867207.7238640785 0.0551722161 0.0601000227 0.0880107805 0.0054754312 0.0954790000 29949095 955859216 1783242752 -0.0961069986 -0.2710863948 -0.1061694250 1119 1311867207.7588050365 0.0552598275 0.0600956972 0.0880107805 0.0054737856 0.0938050000 29950829 955859216 1784987648 -0.0970083401 -0.2734579146 -0.1059743688 1120 1311867207.7921919823 0.0554240160 0.0600915261 0.0880107805 0.0054715462 0.0969210000 29952627 955859216 1783762944 -0.0979562029 -0.2747881711 -0.1059351116 1121 1311867207.8237760067 0.0554915555 0.0600874226 0.0880107805 0.0054691325 0.0929330000 29954393 955859216 1782747136 -0.0988237113 -0.2771206200 -0.1059000194 1122 1311867207.8608479500 0.0552701913 0.0600831292 0.0880107805 0.0054674967 0.0921590000 29956223 955859216 1781731328 -0.0983803794 -0.2789615393 -0.1056211591 1123 1311867207.8937089443 0.0555101149 0.0600790571 0.0880107805 0.0054652944 0.0896800000 29958021 955859216 1780715520 -0.0983549878 -0.2799438834 -0.1053552181 1124 1311867207.9244139194 0.0553354584 0.0600748368 0.0880107805 0.0054641729 0.0916600000 29959755 955859216 1779699712 -0.0988394022 -0.2821055949 -0.1050819755 1125 1311867207.9614970684 0.0552164838 0.0600705183 0.0880107805 0.0054632406 0.0937140000 29961521 955859216 1778683904 -0.0992256850 -0.2834766209 -0.1046884879 1126 1311867207.9914131165 0.0551838204 0.0600661784 0.0880107805 0.0054782444 0.1097420000 29963255 955859216 1773178880 -0.0987089649 -0.2848398983 -0.1045325845 1127 1311867208.0248498917 0.0545811616 0.0600613115 0.0880107805 0.0054936079 0.1231670000 29965085 955859216 1774845952 -0.0989182293 -0.2874888480 -0.1042604670 1128 1311867208.0618500710 0.0549906865 0.0600568162 0.0880107805 0.0054919188 0.0906910000 29966819 955859216 1776635904 -0.0992442891 -0.2891484499 -0.1039667055 1129 1311867208.0924620628 0.0550057366 0.0600523423 0.0880107805 0.0054895098 0.0931410000 29968553 955859216 1778257920 -0.0991601795 -0.2905296683 -0.1038043648 1130 1311867208.1276559830 0.0552466102 0.0600480894 0.0880107805 0.0054878834 0.0938690000 29970351 955859216 1780035584 -0.1000443920 -0.2926156223 -0.1037784070 1131 1311867208.1596069336 0.0552408136 0.0600438390 0.0880107805 0.0054855727 0.0949510000 29972117 955859216 1781686272 -0.1004266590 -0.2940533757 -0.1039456949 1132 1311867208.1905009747 0.0553148352 0.0600396614 0.0880107805 0.0054840634 0.0930450000 29973819 955859216 1783369728 -0.1008419171 -0.2952705622 -0.1043697521 1133 1311867208.2280850410 0.0554106422 0.0600355758 0.0880107805 0.0054821556 0.0948840000 29975713 955859216 1785114624 -0.1009297594 -0.2968297005 -0.1045230702 1134 1311867208.2581789494 0.0548272207 0.0600309829 0.0880107805 0.0054802158 0.0966370000 29977447 955859216 1784127488 -0.1007178724 -0.2985919714 -0.1048396528 1135 1311867208.2901990414 0.0547162779 0.0600263003 0.0880107805 0.0054781681 0.0932660000 29979181 955859216 1781321728 -0.1003119871 -0.2990765274 -0.1051557586 1136 1311867208.3270208836 0.0556921661 0.0600224850 0.0880107805 0.0054803269 0.0864090000 29981043 955859216 1782112256 -0.1012567654 -0.3000515103 -0.1054595858 1137 1311867208.3580970764 0.0559836328 0.0600189328 0.0880107805 0.0054807646 0.0900640000 29982809 955859216 1780842496 -0.1019779742 -0.3011922836 -0.1053769514 1138 1311867208.3910560608 0.0561452471 0.0600155289 0.0880107805 0.0054788968 0.1154240000 29984543 955859216 1779826688 -0.1023865417 -0.3023754060 -0.1054725274 1139 1311867208.4260230064 0.0559233502 0.0600119361 0.0880107805 0.0054769601 0.0874470000 29986373 955859216 1778810880 -0.1027354896 -0.3046583235 -0.1056168005 1140 1311867208.4577419758 0.0564764664 0.0600088348 0.0880107805 0.0054769670 0.0878700000 29988139 955859216 1776902144 -0.1030816734 -0.3064957559 -0.1054777727 1141 1311867208.4907650948 0.0564318746 0.0600056999 0.0880107805 0.0054747804 0.0940190000 29989937 955859216 1775632384 -0.1030076817 -0.3074803054 -0.1053025126 1142 1311867208.5257411003 0.0563850254 0.0600025294 0.0880107805 0.0054730458 0.0926150000 29991767 955859216 1775255552 -0.1037279442 -0.3087522388 -0.1050873697 1143 1311867208.5583798885 0.0565120503 0.0599994756 0.0880107805 0.0054707218 0.1061710000 29993533 955859216 1773985792 -0.1040627137 -0.3095459938 -0.1046149507 1144 1311867208.5904500484 0.0563638955 0.0599962977 0.0880107805 0.0054691277 0.0880910000 29995331 955859216 1773096960 -0.1040299535 -0.3110957742 -0.1039987504 1145 1311867208.6259779930 0.0560724363 0.0599928707 0.0880107805 0.0054669735 0.1214180000 29997097 955859216 1768513536 -0.1045350358 -0.3122728765 -0.1035953239 1146 1311867208.6582078934 0.0553440675 0.0599888142 0.0880107805 0.0054647856 0.1367430000 29998895 955859216 1770188800 -0.1040713266 -0.3136750758 -0.1030472517 1147 1311867208.6910300255 0.0542241000 0.0599837883 0.0880107805 0.0054676451 0.1071470000 30000661 955859216 1771933696 -0.1041395590 -0.3145411313 -0.1023210883 1148 1311867208.7262260914 0.0545481108 0.0599790534 0.0880107805 0.0054670670 0.0930340000 30002491 955859216 1773305856 -0.1043907776 -0.3159759641 -0.1019932628 1149 1311867208.7591009140 0.0547232665 0.0599744791 0.0880107805 0.0054647975 0.0942110000 30004257 955859216 1774989312 -0.1050840169 -0.3164144456 -0.1014191508 1150 1311867208.7909750938 0.0542883389 0.0599695347 0.0880107805 0.0054627562 0.0949230000 30005991 955859216 1776734208 -0.1049578786 -0.3170951307 -0.1009958163 1151 1311867208.8259930611 0.0544802733 0.0599647655 0.0880107805 0.0054615197 0.1129250000 30007821 955859216 1778384896 -0.1056955829 -0.3189111054 -0.1005381793 1152 1311867208.8588190079 0.0555721931 0.0599609525 0.0880107805 0.0054658078 0.0918660000 30009619 955859216 1780162560 -0.1071695834 -0.3199321032 -0.0999272019 1153 1311867208.8916258812 0.0545174554 0.0599562314 0.0880107805 0.0054760056 0.0932670000 30011353 955859216 1781940224 -0.1080600843 -0.3206253946 -0.0994731113 1154 1311867208.9275119305 0.0551789477 0.0599520916 0.0880107805 0.0054753542 0.0945970000 30013151 955859216 1783590912 -0.1086072549 -0.3227878511 -0.0994030386 1155 1311867208.9577760696 0.0557929464 0.0599484906 0.0880107805 0.0054731836 0.0936720000 30014885 955859216 1785274368 -0.1100064814 -0.3243860900 -0.0995992720 1156 1311867208.9911639690 0.0559942164 0.0599450700 0.0880107805 0.0054711183 0.0967580000 30016683 955859216 1784143872 -0.1101736575 -0.3250088096 -0.0998648405 1157 1311867209.0270779133 0.0563094579 0.0599419277 0.0880107805 0.0054704145 0.0945200000 30018513 955859216 1783001088 -0.1106271744 -0.3267856836 -0.0999568850 1158 1311867209.0579569340 0.0569770560 0.0599393674 0.0880107805 0.0054684007 0.0909800000 30020247 955859216 1782239232 -0.1117744520 -0.3277090788 -0.1006335095 1159 1311867209.0906980038 0.0568013601 0.0599366599 0.0880107805 0.0054664222 0.0924010000 30022045 955859216 1780969472 -0.1117733568 -0.3282135427 -0.1010841876 1160 1311867209.1260778904 0.0570137426 0.0599341401 0.0880107805 0.0054647896 0.0904310000 30023811 955859216 1779953664 -0.1126445830 -0.3294660449 -0.1016027704 1161 1311867209.1600620747 0.0575217642 0.0599320623 0.0880107805 0.0054631173 0.0891470000 30025641 955859216 1778937856 -0.1133179814 -0.3306619525 -0.1019799262 1162 1311867209.1917839050 0.0576624535 0.0599301091 0.0880107805 0.0054611889 0.0916780000 30027407 955859216 1777922048 -0.1134671718 -0.3309443891 -0.1024715677 1163 1311867209.2259531021 0.0579221398 0.0599283825 0.0880107805 0.0054589482 0.1072850000 30029173 955859216 1776906240 -0.1143688112 -0.3325346410 -0.1028658971 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 07:05:05 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000001192 0.0000001192 0.0000001192 nan 3.3372330000 1.2927590000 0.0648600000 0.1449770000 0.0000100000 1.8338690000 106105399 0 1699143680 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0071111759 0.0035556476 0.0071111759 0.0073250318 1.5181350000 1.3116590000 0.0520880000 0.1458490000 0.0000020000 0.0082640000 108526280 0 1701376000 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0160688832 0.0077267261 0.0160688832 0.0105654109 1.5124000000 1.3021020000 0.0567850000 0.1450190000 0.0000030000 0.0081550000 108528278 0 1703161856 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0069097765 0.0075224887 0.0160688832 0.0105835684 3.2821290000 1.2724250000 0.0517330000 0.1453010000 1.8042420000 0.0082300000 108530280 0 1711661056 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0087667508 0.0077713411 0.0160688832 0.0110948680 5.2654780000 1.2634880000 0.2550440000 0.1449880000 1.7878380000 1.8139250000 108532274 0 1713930240 4.0003609657 4.0041584969 3.9997615814 6 0.2000000000 0.0088930801 0.0079582976 0.0160688832 0.0099833752 3.2840000000 1.2636650000 0.2263850000 0.0000050000 1.7855420000 0.0082130000 108534604 0 1715699712 4.0005435944 3.9987919331 4.0005841255 7 0.2400000000 0.0089947032 0.0081063556 0.0160688832 0.0091706561 3.4152070000 1.2674440000 0.2088580000 0.1451980000 1.7852890000 0.0082150000 108536278 0 1717342208 4.0003771782 3.9986178875 4.0004816055 8 0.2800000000 0.0089769550 0.0082151805 0.0160688832 0.0085523286 3.2713600000 1.2643300000 0.2096640000 0.0000020000 1.7888630000 0.0082970000 108537952 0 1718992896 4.0010104179 4.0014648438 4.0004425049 9 0.3200000000 0.0089526102 0.0082971171 0.0160688832 0.0080187106 5.2763360000 1.2653640000 0.2452490000 0.1450400000 1.8077590000 1.8127040000 108540266 0 1720770560 4.0009670258 4.0013675690 4.0000157356 10 0.3600000000 0.0091746869 0.0083848741 0.0160688832 0.0075717002 3.3328780000 1.2685130000 0.2695300000 0.0000030000 1.7863680000 0.0082500000 108543252 0 1722556416 4.0024051666 4.0002002716 4.0001811981 11 0.4000000000 0.0092233662 0.0084611006 0.0160688832 0.0072054119 3.4738880000 1.2745620000 0.2602680000 0.1449720000 1.7855700000 0.0082950000 108544926 0 1724198912 4.0022978783 3.9996788502 4.0003643036 12 0.4400000000 0.0093294214 0.0085334607 0.0160688832 0.0068918983 3.3314620000 1.2649640000 0.2597400000 0.0000020000 1.7982480000 0.0082850000 108546600 0 1725849600 4.0025753975 4.0002422333 3.9998216629 13 0.4800000000 0.0092632920 0.0085896016 0.0160688832 0.0067038265 5.2763360000 1.2623880000 0.2700520000 0.1450760000 1.7931890000 1.8053910000 108548274 0 1727500288 4.0026903152 4.0017886162 3.9992966652 14 0.5200000000 0.0092733689 0.0086384421 0.0160688832 0.0065180099 3.3333860000 1.2653340000 0.2691120000 0.0000030000 1.7904800000 0.0082050000 108549948 0 1729277952 4.0027470589 4.0027580261 3.9991123676 15 0.5600000000 0.0092625180 0.0086800472 0.0160688832 0.0062904919 3.5077510000 1.2640400000 0.3033530000 0.1450980000 1.7867440000 0.0082760000 108551622 0 1730928640 4.0029349327 4.0034260750 3.9985947609 16 0.6000000000 0.0093272459 0.0087204971 0.0160688832 0.0060789167 3.3238510000 1.2725190000 0.2579540000 0.0000030000 1.7848580000 0.0082610000 108553296 0 1732706304 4.0029759407 4.0033111572 3.9983282089 17 0.6400000000 0.0093151079 0.0087554742 0.0160688832 0.0058993488 5.2662980000 1.2644780000 0.2590000000 0.1454770000 1.7921110000 1.8049690000 108556250 0 1734356992 4.0021777153 4.0039448738 3.9977540970 18 0.6800000000 0.0094566746 0.0087944298 0.0160688832 0.0057494444 3.2763910000 1.2636060000 0.2106440000 0.0000030000 1.7935750000 0.0082790000 108560548 0 1736007680 4.0026130676 4.0052156448 3.9974820614 19 0.7200000000 0.0094302790 0.0088278955 0.0160688832 0.0057144659 3.4681750000 1.2649980000 0.2592500000 0.1451520000 1.7902140000 0.0083050000 108562222 0 1737809920 4.0038146973 4.0056328773 3.9974064827 20 0.7600000000 0.0095032770 0.0088616646 0.0160688832 0.0055638826 3.2881990000 1.2713740000 0.2158750000 0.0000030000 1.7924100000 0.0082470000 108563896 0 1739444224 4.0043559074 4.0057172775 3.9969449043 21 0.8000000000 0.0095035536 0.0088922307 0.0160688832 0.0054230280 5.2846250000 1.2650650000 0.2623310000 0.1453880000 1.7992240000 1.8123340000 108565570 0 1741103104 4.0034112930 4.0065169334 3.9971871376 22 0.8400000000 0.0097120618 0.0089294958 0.0160688832 0.0052924843 3.2974380000 1.2699230000 0.2111540000 0.0000040000 1.8078180000 0.0082720000 108567244 0 1742864384 4.0030798912 4.0064830780 3.9969155788 23 0.8800000000 0.0096072489 0.0089589633 0.0160688832 0.0051708545 3.4831770000 1.2669400000 0.2628610000 0.1454200000 1.7994580000 0.0082200000 108568918 0 1744515072 4.0035953522 4.0055499077 3.9970748425 24 0.9200000000 0.0097363805 0.0089913557 0.0160688832 0.0050609100 3.2961450000 1.2712280000 0.2149340000 0.0000020000 1.8013910000 0.0083040000 108570592 0 1746292736 4.0043020248 4.0053038597 3.9974002838 25 0.9600000000 0.0098104551 0.0090241197 0.0160688832 0.0049609344 5.2674370000 1.2655020000 0.2268860000 0.1452900000 1.8090910000 1.8203840000 108572266 0 1747943424 4.0055880547 4.0052299500 3.9976959229 26 1.0000000000 0.0097855218 0.0090534044 0.0160688832 0.0048627690 3.3166860000 1.2693240000 0.2277470000 0.0000020000 1.8110490000 0.0082740000 108573940 0 1749594112 4.0052037239 4.0047206879 3.9974114895 27 1.0400000000 0.0098236399 0.0090819316 0.0160688832 0.0047731763 3.5073120000 1.2675680000 0.2761630000 0.1456050000 1.8094900000 0.0081880000 108575614 0 1751371776 4.0053739548 4.0054125786 3.9974815845 28 1.0800000000 0.0098545915 0.0091095266 0.0160688832 0.0047021797 3.3588530000 1.2661980000 0.2752920000 0.0000020000 1.8087900000 0.0082710000 108577288 0 1753149440 4.0071582794 4.0042724609 3.9975640774 29 1.1200000000 0.0098078623 0.0091336071 0.0160688832 0.0047713304 5.3641980000 1.2675420000 0.3119440000 0.1512390000 1.8070340000 1.8261260000 108578962 0 1754808320 4.0083990097 4.0047936440 3.9976212978 30 1.1600000000 0.0098478338 0.0091574147 0.0160688832 0.0049240860 3.3511160000 1.2681760000 0.2638460000 0.0000020000 1.8104770000 0.0082880000 108580636 0 1756450816 4.0077013969 4.0033111572 3.9978678226 31 1.2000000000 0.0098972395 0.0091812800 0.0160688832 0.0050150359 3.5101470000 1.2643420000 0.2734130000 0.1468950000 1.8169010000 0.0082640000 108582310 0 1758101504 4.0099463463 4.0036339760 3.9980354309 32 1.2400000000 0.0099963387 0.0092067506 0.0160688832 0.0052972694 3.3549440000 1.2693060000 0.2604500000 0.0000030000 1.8165260000 0.0082730000 108583984 0 1759879168 4.0116972923 4.0049090385 3.9983928204 33 1.2800000000 0.0100058373 0.0092309654 0.0160688832 0.0055428786 5.3430570000 1.2706570000 0.2688340000 0.1459580000 1.8191830000 1.8380370000 108588218 0 1761529856 4.0115017891 4.0043501854 3.9992032051 34 1.3200000000 0.0100321472 0.0092545295 0.0160688832 0.0056836947 3.3757340000 1.2775950000 0.2586220000 0.0000030000 1.8308190000 0.0082570000 108595140 0 1763307520 4.0110874176 4.0041394234 3.9999644756 35 1.3600000000 0.0100610945 0.0092775742 0.0160688832 0.0060318850 3.5161550000 1.2677550000 0.2572740000 0.1459690000 1.8364690000 0.0083490000 108596814 0 1764958208 4.0113348961 4.0047764778 4.0006184578 36 1.4000000000 0.0101701347 0.0093023676 0.0160688832 0.0063435469 3.3792570000 1.2705270000 0.2579050000 0.0000040000 1.8421170000 0.0082990000 108598488 0 1766735872 4.0127139091 4.0032401085 4.0015172958 37 1.4400000000 0.0101692872 0.0093257978 0.0160688832 0.0067314005 5.3357620000 1.2762960000 0.2003520000 0.1463090000 1.8438840000 1.8685180000 108600162 0 1768411136 4.0137395859 4.0032949448 4.0020494461 38 1.4800000000 0.0101772798 0.0093482053 0.0160688832 0.0085628980 3.4040990000 1.2729440000 0.2573520000 0.0000040000 1.8651560000 0.0082840000 108601836 0 1770172416 4.0152196884 4.0024051666 4.0038027763 39 1.5200000000 0.0102091599 0.0093702810 0.0160688832 0.0088483311 3.5779770000 1.2989180000 0.2549340000 0.1532060000 1.8622020000 0.0083060000 108603510 0 1771814912 4.0167479515 4.0026588440 4.0048265457 40 1.5600000000 0.0102477800 0.0093922185 0.0160688832 0.0089641852 3.4716910000 1.2687910000 0.3134620000 0.0000040000 1.8807990000 0.0082760000 108605184 0 1773592576 4.0180768967 4.0025229454 4.0051798820 41 1.6000000000 0.0102022914 0.0094119764 0.0160688832 0.0091032353 5.4665450000 1.2744260000 0.2660330000 0.1472650000 1.8756760000 1.9027720000 108606858 0 1775370240 4.0196781158 3.9989573956 4.0066695213 42 1.6400000000 0.0103014465 0.0094331542 0.0160688832 0.0092233151 3.4556210000 1.3012350000 0.2560890000 0.0000040000 1.8896670000 0.0082530000 108608532 0 1777020928 4.0214929581 3.9992210865 4.0070323944 43 1.6800000000 0.0102143679 0.0094513220 0.0160688832 0.0094675293 3.5766190000 1.2763540000 0.2543590000 0.1481980000 1.8891040000 0.0082040000 108610206 0 1778671616 4.0233268738 4.0014252663 4.0075707436 44 1.7200000000 0.0103022316 0.0094706609 0.0160688832 0.0097000259 3.4568910000 1.2681930000 0.2662620000 0.0000050000 1.9137740000 0.0082720000 108611880 0 1780449280 4.0246348381 4.0030369759 4.0085272789 45 1.7600000000 0.0103147170 0.0094894177 0.0160688832 0.0099991222 5.5279690000 1.2764660000 0.2642950000 0.1487640000 1.9110970000 1.9269390000 108613554 0 1782099968 4.0266590118 4.0009584427 4.0096268654 46 1.8000000000 0.0103837978 0.0095088607 0.0160688832 0.0112155592 3.4859780000 1.2819630000 0.2713410000 0.0000040000 1.9239900000 0.0082750000 108615228 0 1784012800 4.0545248985 4.0005717278 4.0058226585 47 1.8400000000 0.0104430048 0.0095287361 0.0160688832 0.0111216173 3.6017390000 1.2759620000 0.2580130000 0.1493050000 1.9098370000 0.0082080000 108616902 0 1785536512 4.1148023605 3.9972994328 3.9947812557 48 1.8800000000 0.0104271090 0.0095474522 0.0160688832 0.0112450442 3.4733090000 1.2735280000 0.2668630000 0.0000040000 1.9242010000 0.0083130000 108618576 0 1787305984 4.1174650192 3.9970276356 3.9951248169 49 1.9200000000 0.0104601709 0.0095660791 0.0160688832 0.0113767022 5.5584420000 1.2732280000 0.2544560000 0.1497270000 1.9326570000 1.9479560000 108620250 0 1784639488 4.1196913719 3.9959995747 3.9954023361 50 1.9600000000 0.0104677053 0.0095841116 0.0160688832 0.0114531740 3.4902740000 1.2722000000 0.2664220000 0.0000040000 1.9429880000 0.0082480000 108621924 0 1786290176 4.1222114563 3.9957602024 3.9956443310 51 2.0000000000 0.0104687028 0.0096014566 0.0160688832 0.0115119655 3.6387880000 1.2724040000 0.2642290000 0.1504180000 1.9430570000 0.0082500000 108623598 0 1787813888 4.1250858307 3.9947531223 3.9954459667 52 2.0400000000 0.0104829306 0.0096184080 0.0160688832 0.0115604529 3.4896700000 1.2753880000 0.2554020000 0.0000050000 1.9501700000 0.0081900000 108625272 0 1784893440 4.1281285286 3.9938502312 3.9954845905 53 2.0800000000 0.0105349403 0.0096357011 0.0160688832 0.0115826914 5.6318920000 1.2800780000 0.2637300000 0.1513040000 1.9591320000 1.9772080000 108626946 0 1786417152 4.1294484138 3.9930117130 3.9955623150 54 2.1200000000 0.0105561651 0.0096527467 0.0160688832 0.0116034864 3.5244950000 1.2842920000 0.2658630000 0.0000050000 1.9657090000 0.0081740000 108628620 0 1785790464 4.1326622963 3.9933793545 3.9951076508 55 2.1600000000 0.0106123677 0.0096701943 0.0160688832 0.0116329498 3.6673060000 1.2761850000 0.2631180000 0.1521960000 1.9672880000 0.0080770000 108630294 0 1787187200 4.1358542442 3.9955935478 3.9941720963 56 2.2000000000 0.0106679685 0.0096880117 0.0160688832 0.0116960432 3.4956320000 1.2692840000 0.2503930000 0.0000050000 1.9675200000 0.0079900000 108631968 0 1785020416 4.1371822357 3.9941425323 3.9940111637 57 2.2400000000 0.0107587613 0.0097067968 0.0160688832 0.0118338970 5.5955170000 1.2721470000 0.2044540000 0.1531880000 1.9596400000 2.0056340000 108633642 0 1786544128 4.1364464760 3.9915571213 3.9946134090 58 2.2800000000 0.0107768895 0.0097252467 0.0160688832 0.0119854406 3.5047020000 1.2716290000 0.2589430000 0.0000040000 1.9656910000 0.0079610000 108635316 0 1786036224 4.1382727623 3.9904210567 3.9942317009 59 2.3200000000 0.0111014983 0.0097485730 0.0160688832 0.0122076056 3.6552670000 1.2859350000 0.2450710000 0.1539470000 1.9619430000 0.0078920000 108636990 0 1787559936 4.1396307945 3.9901509285 3.9937362671 60 2.3600000000 0.0110533275 0.0097703189 0.0160688832 0.0123706253 3.5076950000 1.2723250000 0.2530180000 0.0000040000 1.9740540000 0.0078320000 108638664 0 1785401344 4.1425409317 3.9892649651 3.9925765991 61 2.4000000000 0.0108120712 0.0097873968 0.0160688832 0.0126404147 5.6615990000 1.2734930000 0.2515800000 0.1553030000 1.9651150000 2.0156270000 108640338 0 1787052032 4.1448173523 3.9888391495 3.9923005104 62 2.4400000000 0.0106511237 0.0098013279 0.0160688832 0.0128729745 3.5030960000 1.2721290000 0.2509520000 0.0000040000 1.9717510000 0.0077940000 108642012 0 1785274368 4.1487431526 3.9886186123 3.9910018444 63 2.4800000000 0.0105514014 0.0098132338 0.0160688832 0.0130842691 3.6325930000 1.2718600000 0.2389100000 0.1555140000 1.9581360000 0.0076680000 108643686 0 1786552320 4.1524200439 3.9891090393 3.9898686409 64 2.5200000000 0.0104780961 0.0098236223 0.0160688832 0.0132256230 3.5326350000 1.2796850000 0.2796620000 0.0000030000 1.9650990000 0.0076960000 108645360 0 1786036224 4.1564483643 3.9871284962 3.9881882668 65 2.5600000000 0.0103927441 0.0098323780 0.0160688832 0.0133255896 5.6700120000 1.2706470000 0.2455810000 0.1561620000 1.9638690000 2.0332340000 108652154 0 1787559936 4.1605525017 3.9873206615 3.9863097668 66 2.6000000000 0.0104167471 0.0098412321 0.0160688832 0.0134084448 3.4884520000 1.2730730000 0.2415680000 0.0000040000 1.9655720000 0.0076450000 108664324 0 1785163776 4.1650872231 3.9864206314 3.9840247631 67 2.6400000000 0.0104648611 0.0098505400 0.0160688832 0.0135122051 3.6454560000 1.2748480000 0.2446780000 0.1574030000 1.9603920000 0.0075750000 108665998 0 1786671104 4.1683754921 3.9859824181 3.9820263386 68 2.6800000000 0.0104658129 0.0098595881 0.0160688832 0.0136250274 3.4883470000 1.2750680000 0.2450250000 0.0000030000 1.9600600000 0.0076390000 108667672 0 1785417728 4.1730427742 3.9862694740 3.9792430401 69 2.7200000000 0.0104646264 0.0098683568 0.0160688832 0.0137342620 5.6548890000 1.2841780000 0.2329820000 0.1575490000 1.9535210000 2.0260850000 108669346 0 1786925056 4.1764063835 3.9842472076 3.9773898125 70 2.7600000000 0.0104937963 0.0098772916 0.0160688832 0.0139066488 3.4810560000 1.2810780000 0.2339930000 0.0000020000 1.9578750000 0.0075290000 108671020 0 1785171968 4.1786832809 3.9828846455 3.9764385223 71 2.8000000000 0.0105318120 0.0098865102 0.0160688832 0.0140155675 3.6126240000 1.2746370000 0.2221980000 0.1634420000 1.9442430000 0.0075190000 108672694 0 1786552320 4.1827249527 3.9834685326 3.9741666317 72 2.8400000000 0.0105681131 0.0098959769 0.0160688832 0.0141737282 3.4277180000 1.2737860000 0.1922470000 0.0000030000 1.9535900000 0.0074860000 108674368 0 1786052608 4.1854801178 3.9834361076 3.9726915359 73 2.8800000000 0.0105695138 0.0099052035 0.0160688832 0.0142969860 5.6242150000 1.2710890000 0.2308940000 0.1586450000 1.9348510000 2.0281500000 108676042 0 1787686912 4.1877651215 3.9828746319 3.9714303017 74 2.9200000000 0.0105851423 0.0099143918 0.0160688832 0.0143758647 3.4584810000 1.2763450000 0.2316600000 0.0000030000 1.9424060000 0.0074800000 108677716 0 1785147392 4.1921944618 3.9825420380 3.9686725140 75 2.9600000000 0.0106225852 0.0099238344 0.0160688832 0.0145126728 3.6044770000 1.2788100000 0.2304470000 0.1594040000 1.9277490000 0.0074730000 108679390 0 1786687488 4.1937499046 3.9826710224 3.9677965641 76 3.0000000000 0.0106387381 0.0099332410 0.0160688832 0.0145452256 3.4484360000 1.2701470000 0.2315520000 0.0000030000 1.9386680000 0.0074580000 108681064 0 1785290752 4.1987695694 3.9801747799 3.9646961689 77 3.0400000000 0.0106169619 0.0099421205 0.0160688832 0.0146117786 5.5500420000 1.2753320000 0.1790480000 0.1597640000 1.9256820000 2.0095310000 108682738 0 1786941440 4.2017192841 3.9788866043 3.9626331329 78 3.0800000000 0.0106513929 0.0099512138 0.0160688832 0.0146264029 3.4064690000 1.2773210000 0.1896230000 0.0000020000 1.9314690000 0.0074360000 108684412 0 1784901632 4.2062578201 3.9779863358 3.9592084885 79 3.1200000000 0.0106198015 0.0099596769 0.0160688832 0.0146746789 3.5849450000 1.2756700000 0.2290580000 0.1597230000 1.9123860000 0.0074980000 108686086 0 1786544128 4.2103152275 3.9775936604 3.9566621780 80 3.1600000000 0.0106659764 0.0099685056 0.0160688832 0.0150950349 3.4057930000 1.2766810000 0.2014020000 0.0000030000 1.9195750000 0.0074100000 108687760 0 1785925632 4.2188868523 3.9765057564 3.9505162239 81 3.2000000000 0.0106067220 0.0099763849 0.0160688832 0.0151188925 5.5742790000 1.2742320000 0.2286790000 0.1601630000 1.9095920000 2.0009740000 108689434 0 1787551744 4.2228736877 3.9761037827 3.9480273724 82 3.2400000000 0.0105665093 0.0099835815 0.0160688832 0.0151218845 3.4287530000 1.2738770000 0.2306090000 0.0000020000 1.9161570000 0.0074760000 108691108 0 1784758272 4.2262125015 3.9731545448 3.9456994534 83 3.2800000000 0.0105880601 0.0099908644 0.0160688832 0.0151679512 3.5778570000 1.2754350000 0.2296680000 0.1603450000 1.9043110000 0.0074560000 108692782 0 1786281984 4.2293891907 3.9728484154 3.9436085224 84 3.3200000000 0.0105673242 0.0099977270 0.0160688832 0.0151577058 3.4168110000 1.2760700000 0.2300810000 0.0000020000 1.9025190000 0.0074760000 108694456 0 1785520128 4.2316317558 3.9699096680 3.9422278404 85 3.3600000000 0.0105749061 0.0100045173 0.0160688832 0.0151677719 5.5473000000 1.2750810000 0.2252810000 0.1606070000 1.8938960000 1.9917280000 108696130 0 1786916864 4.2349805832 3.9685504436 3.9399809837 86 3.4000000000 0.0105892336 0.0100113164 0.0160688832 0.0152072628 3.4253330000 1.2796420000 0.2411940000 0.0000030000 1.8964410000 0.0073880000 108697804 0 1785139200 4.2370376587 3.9673931599 3.9387695789 87 3.4400000000 0.0105747106 0.0100177921 0.0160688832 0.0152299763 3.6056300000 1.2738400000 0.2704960000 0.1608680000 1.8923420000 0.0074270000 108699478 0 1786798080 4.2407011986 3.9668850899 3.9364330769 88 3.4800000000 0.0105111850 0.0100233989 0.0160688832 0.0152496589 3.4024850000 1.2733650000 0.2315980000 0.0000030000 1.8894470000 0.0073840000 108701152 0 1785036800 4.2443580627 3.9676392078 3.9338667393 89 3.5200000000 0.0105472011 0.0100292843 0.0160688832 0.0152526915 5.5008760000 1.2787940000 0.1898450000 0.1613000000 1.8781200000 1.9921490000 108702826 0 1786535936 4.2471599579 3.9671535492 3.9318203926 90 3.5600000000 0.0106039727 0.0100356697 0.0160688832 0.0152591827 3.3992600000 1.2784370000 0.2313050000 0.0000020000 1.8814160000 0.0074200000 108704500 0 1786155008 4.2493767738 3.9651291370 3.9302566051 91 3.6000000000 0.0105643477 0.0100414794 0.0160688832 0.0152747124 3.5643950000 1.2742790000 0.2456800000 0.1616380000 1.8747350000 0.0073670000 108706174 0 1787678720 4.2518324852 3.9643158913 3.9286930561 92 3.6400000000 0.0105856908 0.0100473947 0.0160688832 0.0152692392 3.3651000000 1.2747360000 0.2000110000 0.0000030000 1.8822400000 0.0074170000 108707848 0 1784918016 4.2548837662 3.9651725292 3.9266314507 93 3.6800000000 0.0105863977 0.0100531905 0.0160688832 0.0152323135 5.5191250000 1.2757310000 0.2291980000 0.1630120000 1.8705470000 1.9799240000 108709522 0 1786298368 4.2570352554 3.9638442993 3.9247620106 94 3.7200000000 0.0106380321 0.0100594122 0.0160688832 0.0151943138 3.4694410000 1.2765910000 0.3115330000 0.0000040000 1.8731680000 0.0074340000 108711196 0 1785012224 4.2595372200 3.9633355141 3.9234156609 95 3.7600000000 0.0106441490 0.0100655673 0.0160688832 0.0151522110 3.5461500000 1.2810580000 0.2295760000 0.1621770000 1.8651420000 0.0074880000 108712870 0 1786535936 4.2627401352 3.9636585712 3.9212791920 96 3.8000000000 0.0105481055 0.0100705937 0.0160688832 0.0151071250 3.3595520000 1.2775430000 0.1996170000 0.0000020000 1.8743150000 0.0073690000 108714544 0 1785417728 4.2653307915 3.9632306099 3.9189231396 97 3.8400000000 0.0105813146 0.0100758589 0.0160688832 0.0150701732 5.5022610000 1.2751250000 0.2293770000 0.1620530000 1.8603450000 1.9746120000 108716218 0 1786814464 4.2676529884 3.9629831314 3.9169054031 98 3.8800000000 0.0105433846 0.0100806296 0.0160688832 0.0150266384 3.3795740000 1.2738580000 0.2294630000 0.0000030000 1.8681190000 0.0074000000 108717892 0 1785155584 4.2686057091 3.9618370533 3.9162449837 99 3.9200000000 0.0106189782 0.0100860674 0.0160688832 0.0149726586 3.5803260000 1.2729940000 0.2803700000 0.1617180000 1.8570710000 0.0074170000 108719566 0 1786679296 4.2713317871 3.9612874985 3.9140286446 100 3.9600000000 0.0107000824 0.0100922076 0.0160688832 0.0149199110 3.3921770000 1.2811750000 0.2405670000 0.0000040000 1.8622450000 0.0074350000 108721240 0 1785409536 4.2728724480 3.9599635601 3.9127516747 101 4.0000000000 0.0107458262 0.0100986791 0.0160688832 0.0148707228 5.4961190000 1.2763530000 0.2402970000 0.1616850000 1.8568130000 1.9602220000 108722914 0 1786916864 4.2753400803 3.9618098736 3.9112627506 102 4.0400000000 0.0106474012 0.0101040587 0.0160688832 0.0148250334 3.3765290000 1.2742240000 0.2298700000 0.0000040000 1.8642280000 0.0074210000 108724588 0 1785044992 4.2774696350 3.9623336792 3.9096379280 103 4.0800000000 0.0107278274 0.0101101147 0.0160688832 0.0147794006 3.5242520000 1.2750830000 0.2288060000 0.1618180000 1.8503210000 0.0074220000 108726262 0 1786552320 4.2797608376 3.9629068375 3.9083690643 104 4.1200000000 0.0107161365 0.0101159418 0.0160688832 0.0147258944 3.3717600000 1.2813250000 0.2296680000 0.0000040000 1.8525180000 0.0074460000 108727936 0 1786187776 4.2814483643 3.9638636112 3.9070410728 105 4.1600000000 0.0108109135 0.0101225606 0.0160688832 0.0146790662 5.4777270000 1.2748910000 0.2286860000 0.1620180000 1.8535560000 1.9578050000 108729610 0 1787703296 4.2841567993 3.9652216434 3.9051322937 106 4.2000000000 0.0107546719 0.0101285239 0.0160688832 0.0146222613 3.3278540000 1.2734420000 0.1934760000 0.0000040000 1.8527200000 0.0074150000 108731284 0 1785688064 4.2857151031 3.9656414986 3.9039056301 107 4.2400000000 0.0107769724 0.0101345842 0.0160688832 0.0145592585 3.5172040000 1.2718110000 0.2265870000 0.1618070000 1.8488350000 0.0073950000 108732958 0 1787314176 4.2865705490 3.9656541348 3.9031789303 108 4.2800000000 0.0107808234 0.0101405679 0.0160688832 0.0144953753 3.3622810000 1.2749360000 0.2262380000 0.0000040000 1.8529120000 0.0073980000 108734632 0 1785552896 4.2902011871 3.9679791927 3.9002335072 109 4.3200000000 0.0108361263 0.0101469491 0.0160688832 0.0144285977 5.4683720000 1.2803970000 0.2260010000 0.1619910000 1.8443780000 1.9548140000 108736306 0 1787187200 4.2918057442 3.9686865807 3.8989710808 110 4.3600000000 0.0109155225 0.0101539362 0.0160688832 0.0143645687 3.3695060000 1.2839990000 0.2287630000 0.0000040000 1.8485510000 0.0074130000 108737980 0 1785552896 4.2926592827 3.9698572159 3.8979048729 111 4.4000000000 0.0109190457 0.0101608291 0.0160688832 0.0143013246 3.5254690000 1.2749670000 0.2267670000 0.1620180000 1.8534890000 0.0074540000 108739654 0 1787043840 4.2938814163 3.9719924927 3.8965489864 112 4.4400000000 0.0109880995 0.0101682154 0.0160688832 0.0142443482 3.3367610000 1.2746480000 0.1985150000 0.0000050000 1.8554060000 0.0074480000 108741328 0 1785139200 4.2963328362 3.9747169018 3.8942782879 113 4.4800000000 0.0110578155 0.0101760880 0.0160688832 0.0141816421 5.4572750000 1.2817100000 0.1939870000 0.1624440000 1.8506570000 1.9677330000 108743002 0 1786789888 4.2976436615 3.9772191048 3.8932437897 114 4.5200000000 0.0110403048 0.0101836688 0.0160688832 0.0141188741 3.3810820000 1.2789060000 0.2357370000 0.0000020000 1.8582740000 0.0074210000 108744676 0 1785528320 4.2985267639 3.9787378311 3.8922123909 115 4.5600000000 0.0110982843 0.0101916220 0.0160688832 0.0140588190 3.4924200000 1.2750730000 0.1849640000 0.1679280000 1.8563510000 0.0073580000 108746350 0 1787052032 4.2998361588 3.9812817574 3.8906805515 116 4.6000000000 0.0110596335 0.0101991049 0.0160688832 0.0140023222 3.3904870000 1.2771540000 0.2348290000 0.0000030000 1.8703140000 0.0074190000 108748024 0 1785139200 4.3002681732 3.9827077389 3.8896436691 117 4.6400000000 0.0112035694 0.0102076900 0.0160688832 0.0139593196 5.5914060000 1.2763790000 0.3157260000 0.1627590000 1.8581400000 1.9776220000 108749698 0 1786916864 4.3011460304 3.9854130745 3.8882753849 118 4.6800000000 0.0111802779 0.0102159323 0.0160688832 0.0139258043 3.3718480000 1.2716620000 0.2262850000 0.0000020000 1.8657820000 0.0073350000 108751372 0 1785012224 4.3016648293 3.9859123230 3.8877167702 119 4.7200000000 0.0111522982 0.0102238009 0.0160688832 0.0138859761 3.4991790000 1.2798830000 0.1861850000 0.1624720000 1.8623810000 0.0074240000 108753046 0 1786662912 4.3018999100 3.9885876179 3.8873434067 120 4.7600000000 0.0112168100 0.0102320760 0.0160688832 0.0138398617 3.3839530000 1.2730730000 0.2265450000 0.0000020000 1.8760880000 0.0074500000 108754720 0 1785266176 4.3018221855 3.9896497726 3.8863706589 121 4.8000000000 0.0112165194 0.0102402119 0.0160688832 0.0137962831 5.5113700000 1.2750050000 0.2260080000 0.1626790000 1.8632440000 1.9836460000 108756394 0 1786789888 4.3010401726 3.9909718037 3.8868179321 122 4.8400000000 0.0112654576 0.0102486155 0.0160688832 0.0137677484 3.4300920000 1.2736660000 0.2687860000 0.0000030000 1.8795150000 0.0073170000 108758068 0 1785266176 4.3001780510 3.9957599640 3.8861505985 123 4.8800000000 0.0113255987 0.0102573715 0.0160688832 0.0137216824 3.5433660000 1.2743360000 0.2279860000 0.1626560000 1.8701650000 0.0073340000 108759742 0 1787052032 4.2992796898 3.9980766773 3.8864514828 124 4.9200000000 0.0114385728 0.0102668973 0.0160688832 0.0136811717 3.4096650000 1.2815530000 0.2381820000 0.0000030000 1.8817320000 0.0073830000 108761416 0 1785139200 4.2985429764 3.9991986752 3.8863651752 125 4.9600000000 0.0114174467 0.0102761017 0.0160688832 0.0136396920 5.5376380000 1.2741910000 0.2281840000 0.1627960000 1.8819550000 1.9896920000 108763090 0 1786789888 4.2978644371 4.0021071434 3.8869581223 126 5.0000000000 0.0115057603 0.0102858609 0.0160688832 0.0136004236 3.4040520000 1.2748020000 0.2292290000 0.0000020000 1.8918490000 0.0073440000 108764764 0 1785266176 4.2977151871 4.0040774345 3.8868298531 127 5.0400000000 0.0115089100 0.0102954912 0.0160688832 0.0135719531 3.5600430000 1.2777030000 0.2282960000 0.1629450000 1.8828750000 0.0074180000 108766438 0 1787043840 4.2964506149 4.0056238174 3.8875222206 128 5.0800000000 0.0115568675 0.0103053457 0.0160688832 0.0135433039 3.4896420000 1.2806990000 0.3104050000 0.0000030000 1.8903510000 0.0073400000 108768112 0 1785266176 4.2954549789 4.0072183609 3.8879382610 129 5.1200000000 0.0115607716 0.0103150777 0.0160688832 0.0135147967 5.5560930000 1.2759990000 0.2286100000 0.1628410000 1.8919670000 1.9957940000 108780026 0 1786789888 4.2954745293 4.0099425316 3.8877637386 130 5.1600000000 0.0115260929 0.0103243932 0.0160688832 0.0134955015 3.4176470000 1.2815630000 0.2297660000 0.0000030000 1.8979960000 0.0073680000 108802692 0 1785409536 4.2936000824 4.0107049942 3.8891530037 131 5.2000000000 0.0115469499 0.0103337257 0.0160688832 0.0134756302 3.5702730000 1.2744870000 0.2300390000 0.1628870000 1.8946240000 0.0073400000 108804366 0 1787060224 4.2916564941 4.0108485222 3.8903765678 132 5.2400000000 0.0116135590 0.0103434214 0.0160688832 0.0134558845 3.4123300000 1.2720380000 0.2397190000 0.0000020000 1.8922200000 0.0073980000 108806040 0 1785307136 4.2897329330 4.0112061501 3.8915567398 133 5.2800000000 0.0116370758 0.0103531481 0.0160688832 0.0134245975 5.5773020000 1.2810170000 0.2390280000 0.1630290000 1.8924560000 2.0008570000 108807714 0 1786798080 4.2884044647 4.0120496750 3.8932731152 134 5.3200000000 0.0116132442 0.0103625518 0.0160688832 0.0133880543 3.4576300000 1.2815920000 0.2687270000 0.0000030000 1.8990070000 0.0073560000 108809388 0 1785425920 4.2865414619 4.0137157440 3.8947656155 135 5.3600000000 0.0115931593 0.0103716674 0.0160688832 0.0133521394 3.5857380000 1.2829750000 0.2273030000 0.1627050000 1.9044130000 0.0073890000 108811062 0 1786933248 4.2839789391 4.0139770508 3.8969669342 136 5.4000000000 0.0116890203 0.0103813539 0.0160688832 0.0133186521 3.4303310000 1.2743570000 0.2365160000 0.0000020000 1.9111880000 0.0073440000 108812736 0 1785282560 4.2825450897 4.0156822205 3.8983097076 137 5.4400000000 0.0116556603 0.0103906554 0.0160688832 0.0132866076 5.6339660000 1.2763530000 0.2768340000 0.1625530000 1.9028640000 2.0144120000 108814410 0 1786679296 4.2815742493 4.0182528496 3.8995616436 138 5.4800000000 0.0116682751 0.0103999135 0.0160688832 0.0133444153 3.4455590000 1.2804110000 0.2369220000 0.0000030000 1.9198160000 0.0073760000 108816084 0 1785409536 4.2780203819 4.0181937218 3.9027035236 139 5.5200000000 0.0116655994 0.0104090191 0.0160688832 0.0133133333 3.5973370000 1.2797000000 0.2370780000 0.1622520000 1.9099730000 0.0073760000 108817758 0 1786916864 4.2757058144 4.0189700127 3.9045996666 140 5.5600000000 0.0117112957 0.0104183211 0.0160688832 0.0132937478 3.4469340000 1.2754200000 0.2370470000 0.0000020000 1.9260980000 0.0074300000 108819432 0 1785282560 4.2746353149 4.0208854675 3.9059219360 141 5.6000000000 0.0118272314 0.0104283134 0.0160688832 0.0132704153 5.6227160000 1.2831920000 0.2365430000 0.1624490000 1.9225390000 2.0169670000 108821106 0 1786925056 4.2728066444 4.0227413177 3.9075675011 142 5.6400000000 0.0118221194 0.0104381289 0.0160688832 0.0132442014 3.4487410000 1.2757360000 0.2368160000 0.0000020000 1.9277030000 0.0075420000 108822780 0 1785139200 4.2714476585 4.0252571106 3.9089684486 143 5.6800000000 0.0117642712 0.0104474026 0.0160688832 0.0132263848 3.5942090000 1.2763940000 0.2270740000 0.1621660000 1.9201420000 0.0074340000 108824454 0 1786679296 4.2690553665 4.0256452560 3.9105892181 144 5.7200000000 0.0118554858 0.0104571810 0.0160688832 0.0131966488 3.4465400000 1.2808670000 0.2294160000 0.0000030000 1.9278100000 0.0074470000 108826128 0 1784918016 4.2664709091 4.0259885788 3.9119987488 145 5.7600000000 0.0118553936 0.0104668238 0.0160688832 0.0131663241 5.5753320000 1.2751760000 0.1872840000 0.1617110000 1.9304430000 2.0197160000 108827802 0 1786425344 4.2645378113 4.0294752121 3.9137876034 146 5.8000000000 0.0118697882 0.0104764332 0.0160688832 0.0131381045 3.4072760000 1.2751120000 0.1879380000 0.0000020000 1.9357290000 0.0074830000 108829476 0 1786044416 4.2624125481 4.0301713943 3.9151525497 147 5.8400000000 0.0118999109 0.0104861167 0.0160688832 0.0131156375 3.6157360000 1.2745730000 0.2381990000 0.1614150000 1.9331170000 0.0074360000 108831150 0 1787441152 4.2594456673 4.0311727524 3.9174742699 148 5.8800000000 0.0119028110 0.0104956890 0.0160688832 0.0130953350 3.4450230000 1.2738160000 0.2287320000 0.0000040000 1.9339880000 0.0074640000 108832824 0 1785536512 4.2578125000 4.0323920250 3.9182200432 149 5.9200000000 0.0119463438 0.0105054249 0.0160688832 0.0130744294 5.6412280000 1.2748340000 0.2350440000 0.1615590000 1.9336320000 2.0351960000 108834498 0 1787305984 4.2545704842 4.0324363708 3.9203085899 150 5.9600000000 0.0118466821 0.0105143666 0.0160688832 0.0130554658 3.4575490000 1.2826570000 0.2315390000 0.0000040000 1.9350010000 0.0074170000 108836172 0 1785020416 4.2508049011 4.0310688019 3.9225690365 151 6.0000000000 0.0119865956 0.0105241165 0.0160688832 0.0130325568 3.6158290000 1.2755040000 0.2307020000 0.1607810000 1.9403870000 0.0074840000 108837846 0 1786408960 4.2471599579 4.0314946175 3.9247500896 152 6.0400000000 0.0118060056 0.0105325500 0.0160688832 0.0130154243 3.4473840000 1.2723990000 0.2299470000 0.0000040000 1.9365640000 0.0075020000 108839520 0 1786028032 4.2437443733 4.0299935341 3.9270567894 153 6.0800000000 0.0120230634 0.0105422919 0.0160688832 0.0129990048 5.6323840000 1.2775880000 0.2300690000 0.1605780000 1.9363520000 2.0268230000 108841194 0 1787297792 4.2395195961 4.0323681831 3.9296584129 154 6.1200000000 0.0119335009 0.0105513257 0.0160688832 0.0129918506 3.4591750000 1.2757030000 0.2296960000 0.0000040000 1.9451630000 0.0075380000 108842868 0 1785520128 4.2365159988 4.0339412689 3.9313583374 155 6.1600000000 0.0120396055 0.0105609275 0.0160688832 0.0129858111 3.6226760000 1.2803790000 0.2289430000 0.1610470000 1.9438610000 0.0074430000 108844542 0 1787170816 4.2322659492 4.0333304405 3.9338638783 156 6.2000000000 0.0120801199 0.0105706659 0.0160688832 0.0129830998 3.5229210000 1.2787830000 0.2809050000 0.0000040000 1.9547970000 0.0074390000 108846216 0 1785012224 4.2276806831 4.0342092514 3.9365704060 157 6.2400000000 0.0118855080 0.0105790407 0.0160688832 0.0129849352 5.6613160000 1.2747480000 0.2399060000 0.1602250000 1.9505960000 2.0348380000 108847890 0 1786535936 4.2233681679 4.0359807014 3.9382851124 158 6.2800000000 0.0119803939 0.0105879100 0.0160688832 0.0129997704 3.4882110000 1.2763680000 0.2412710000 0.0000040000 1.9620250000 0.0075400000 108849564 0 1785401344 4.2205877304 4.0372614861 3.9398746490 159 6.3200000000 0.0118905390 0.0105961027 0.0160688832 0.0130064860 3.6327750000 1.2778610000 0.2311770000 0.1596910000 1.9554630000 0.0074870000 108851238 0 1786671104 4.2166700363 4.0373020172 3.9416499138 160 6.3600000000 0.0119344527 0.0106044674 0.0160688832 0.0130065102 3.4900950000 1.2803530000 0.2414650000 0.0000040000 1.9597720000 0.0074880000 108852912 0 1785012224 4.2135510445 4.0385522842 3.9432630539 161 6.4000000000 0.0118951090 0.0106124838 0.0160688832 0.0130076963 5.7153510000 1.2726890000 0.2826620000 0.1596740000 1.9663890000 2.0329160000 108854586 0 1786535936 4.2106127739 4.0396652222 3.9445962906 162 6.4400000000 0.0118824178 0.0106203229 0.0160688832 0.0130201621 3.4876220000 1.2759680000 0.2333050000 0.0000040000 1.9698080000 0.0075490000 108856260 0 1785774080 4.2061314583 4.0390062332 3.9462196827 163 6.4800000000 0.0118952645 0.0106281446 0.0160688832 0.0130182787 3.6537390000 1.2740110000 0.2425280000 0.1590780000 1.9695120000 0.0075770000 108857934 0 1787551744 4.2020368576 4.0383763313 3.9481561184 164 6.5200000000 0.0118652340 0.0106356878 0.0160688832 0.0130113538 3.4557000000 1.2769060000 0.2017250000 0.0000030000 1.9684320000 0.0075980000 108859608 0 1784758272 4.1988997459 4.0371489525 3.9498260021 165 6.5600000000 0.0117789330 0.0106426166 0.0160688832 0.0129999014 5.6768600000 1.2812950000 0.2328060000 0.1585970000 1.9693230000 2.0337990000 108861282 0 1786281984 4.1945991516 4.0402750969 3.9516522884 166 6.6000000000 0.0117265182 0.0106491461 0.0160688832 0.0130101999 3.5057290000 1.2803270000 0.2444230000 0.0000040000 1.9723800000 0.0075590000 108862956 0 1788084224 4.1890239716 4.0388917923 3.9542655945 167 6.6400000000 0.0117459828 0.0106557140 0.0160688832 0.0130276912 3.6634180000 1.2746150000 0.2449660000 0.1578620000 1.9770230000 0.0076480000 108864630 0 1785036800 4.1848521233 4.0386672020 3.9563956261 168 6.6800000000 0.0117914379 0.0106624742 0.0160688832 0.0130279268 3.5520670000 1.2760340000 0.2873350000 0.0000040000 1.9799540000 0.0076270000 108866304 0 1786535936 4.1810922623 4.0410842896 3.9582242966 169 6.7200000000 0.0118487682 0.0106694937 0.0160688832 0.0130714249 5.6747220000 1.2730820000 0.2368040000 0.1572440000 1.9720570000 2.0344340000 108867978 0 1785647104 4.1769471169 4.0398969650 3.9599463940 170 6.7600000000 0.0118293194 0.0106763162 0.0160688832 0.0130878065 3.5047320000 1.2743290000 0.2471890000 0.0000040000 1.9745070000 0.0076410000 108869652 0 1787043840 4.1732468605 4.0388388634 3.9613864422 171 6.8000000000 0.0119710267 0.0106838876 0.0160688832 0.0131019002 3.6580430000 1.2779160000 0.2375050000 0.1570850000 1.9765790000 0.0077590000 108871326 0 1784504320 4.1701126099 4.0414800644 3.9623317719 172 6.8400000000 0.0120876618 0.0106920491 0.0160688832 0.0131224884 3.5115940000 1.2734710000 0.2491460000 0.0000040000 1.9800460000 0.0077890000 108873000 0 1786028032 4.1675324440 4.0424661636 3.9633686543 173 6.8800000000 0.0123565765 0.0107016707 0.0160688832 0.0131491660 5.6344570000 1.2733330000 0.2083050000 0.1557850000 1.9771950000 2.0187160000 108874674 0 1787932672 4.1662464142 4.0421438217 3.9637598991 174 6.9200000000 0.0123417014 0.0107110961 0.0160688832 0.0131783469 3.5113930000 1.2685240000 0.2528890000 0.0000040000 1.9810070000 0.0078170000 108876348 0 1785434112 4.1648311615 4.0402417183 3.9651889801 175 6.9600000000 0.0123721035 0.0107205876 0.0160688832 0.0132181167 3.6513940000 1.2747630000 0.2438590000 0.1549010000 1.9688780000 0.0078470000 108878022 0 1786925056 4.1648111343 4.0412507057 3.9655282497 176 7.0000000000 0.0121160308 0.0107285163 0.0160688832 0.0132247734 3.5129470000 1.2778430000 0.2550260000 0.0000030000 1.9709780000 0.0079590000 108879696 0 1784655872 4.1652283669 4.0424971581 3.9654314518 177 7.0400000000 0.0120177167 0.0107357999 0.0160688832 0.0132649324 5.6469170000 1.2716380000 0.2471750000 0.1542770000 1.9740710000 1.9985610000 108881370 0 1786281984 4.1630959511 4.0444307327 3.9662873745 178 7.0800000000 0.0118732676 0.0107421901 0.0160688832 0.0133038005 3.5065060000 1.2734370000 0.2550870000 0.0000040000 1.9687740000 0.0080520000 108883044 0 1788059648 4.1612129211 4.0447010994 3.9667761326 179 7.1200000000 0.0118104657 0.0107481582 0.0160688832 0.0133598178 3.6692500000 1.2753320000 0.2632610000 0.1533070000 1.9680410000 0.0081340000 108884718 0 1785266176 4.1599144936 4.0430669785 3.9674737453 180 7.1600000000 0.0118057402 0.0107540336 0.0160688832 0.0133899078 3.5065320000 1.2727000000 0.2633490000 0.0000030000 1.9612200000 0.0080880000 108886392 0 1786789888 4.1589727402 4.0446591377 3.9677238464 181 7.2000000000 0.0117433975 0.0107594997 0.0160688832 0.0133792462 5.7031360000 1.2766170000 0.3090370000 0.1525920000 1.9831250000 1.9805520000 108888066 0 1786798080 4.1563754082 4.0448527336 3.9683945179 182 7.2400000000 0.0117956009 0.0107651926 0.0160688832 0.0133726762 3.4977150000 1.2729010000 0.2639120000 0.0000040000 1.9514990000 0.0082070000 108889740 0 1784799232 4.1560335159 4.0461282730 3.9683482647 183 7.2800000000 0.0118159214 0.0107709343 0.0160688832 0.0133582897 3.6439460000 1.2679430000 0.2700350000 0.1515180000 1.9450800000 0.0081800000 108891414 0 1786187776 4.1516251564 4.0468735695 3.9695508480 184 7.3200000000 0.0117890257 0.0107764674 0.0160688832 0.0133600537 3.4915420000 1.2714680000 0.2650790000 0.0000200000 1.9454950000 0.0083020000 108893088 0 1785655296 4.1498856544 4.0455818176 3.9698524475 185 7.3600000000 0.0118486667 0.0107822631 0.0160688832 0.0133477054 5.5975940000 1.2959330000 0.2648300000 0.1506950000 1.9297010000 1.9552420000 108894762 0 1787043840 4.1449513435 4.0460982323 3.9702620506 186 7.4000000000 0.0118564060 0.0107880380 0.0160688832 0.0133603812 3.4148210000 1.2719810000 0.2098700000 0.0000040000 1.9235560000 0.0082360000 108896436 0 1785139200 4.1448397636 4.0457868576 3.9707350731 187 7.4400000000 0.0118624968 0.0107937838 0.0160688832 0.0133776785 3.6035620000 1.2757140000 0.2558030000 0.1498060000 1.9127510000 0.0082840000 108898110 0 1786535936 4.1424312592 4.0441212654 3.9709656239 188 7.4800000000 0.0119127389 0.0107997357 0.0160688832 0.0133929038 3.4093480000 1.2672940000 0.2203970000 0.0000040000 1.9122430000 0.0082010000 108899784 0 1786155008 4.1395316124 4.0433382988 3.9719130993 189 7.5200000000 0.0117983101 0.0108050191 0.0160688832 0.0134266070 5.4972560000 1.2691820000 0.2556430000 0.1490500000 1.9042620000 1.9179010000 108901458 0 1787551744 4.1371722221 4.0445966721 3.9726552963 190 7.5600000000 0.0118057001 0.0108102859 0.0160688832 0.0134790585 3.4431970000 1.2752460000 0.2569490000 0.0000030000 1.9014850000 0.0082710000 108903132 0 1785044992 4.1344847679 4.0429883003 3.9733972549 191 7.6000000000 0.0119131943 0.0108160603 0.0160688832 0.0135181064 3.5690240000 1.2704470000 0.2559540000 0.1489900000 1.8841400000 0.0082040000 108904806 0 1786662912 4.1329464912 4.0451812744 3.9735939503 192 7.6400000000 0.0118829859 0.0108216172 0.0160688832 0.0135395241 3.4266240000 1.2756080000 0.2664610000 0.0000040000 1.8751040000 0.0082070000 108906480 0 1784926208 4.1302642822 4.0447945595 3.9738881588 193 7.6800000000 0.0117594199 0.0108264763 0.0160688832 0.0135735268 5.4312980000 1.2705590000 0.2667280000 0.1481310000 1.8661310000 1.8785090000 108908154 0 1786408960 4.1288666725 4.0453429222 3.9743556976 194 7.7200000000 0.0118204579 0.0108315999 0.0160688832 0.0135777509 3.3998200000 1.2716970000 0.2551380000 0.0000030000 1.8634920000 0.0082520000 108909828 0 1785774080 4.1264152527 4.0438308716 3.9740991592 195 7.7600000000 0.0119019598 0.0108370889 0.0160688832 0.0135743983 3.5412820000 1.2696570000 0.2655140000 0.1474520000 1.8491510000 0.0082470000 108911502 0 1787297792 4.1269736290 4.0459856987 3.9741404057 196 7.8000000000 0.0118080564 0.0108420428 0.0160688832 0.0135611163 3.3757040000 1.2726900000 0.2551660000 0.0000040000 1.8383000000 0.0082260000 108913176 0 1785393152 4.1232671738 4.0452427864 3.9740412235 197 7.8400000000 0.0118077993 0.0108469451 0.0160688832 0.0135723939 5.3538480000 1.2699480000 0.2611730000 0.1474030000 1.8278220000 1.8462290000 108914850 0 1786789888 4.1271486282 4.0458383560 3.9743161201 198 7.8800000000 0.0118582631 0.0108520528 0.0160688832 0.0135780925 3.3704720000 1.2795260000 0.2553230000 0.0000040000 1.8260740000 0.0083000000 108916524 0 1784901632 4.1249566078 4.0464048386 3.9743413925 199 7.9200000000 0.0117969681 0.0108568011 0.0160688832 0.0136016334 3.5232260000 1.2719820000 0.2555910000 0.1466580000 1.8390040000 0.0083680000 108918198 0 1786281984 4.1297039986 4.0475730896 3.9747247696 200 7.9600000000 0.0117916707 0.0108614755 0.0160688832 0.0136161783 3.3471440000 1.2694180000 0.2553980000 0.0000030000 1.8128220000 0.0082460000 108919872 0 1785901056 4.1284761429 4.0488338470 3.9745905399 201 8.0000000000 0.0117950579 0.0108661201 0.0160688832 0.0136302951 5.3039600000 1.2729190000 0.2670420000 0.1465180000 1.7984060000 1.8177910000 108921546 0 1787559936 4.1306986809 4.0493049622 3.9748935699 202 8.0400000000 0.0117858229 0.0108706731 0.0160688832 0.0136274511 3.4247950000 1.2768640000 0.3470380000 0.0000030000 1.7913460000 0.0082540000 108923220 0 1785139200 4.1293954849 4.0490159988 3.9749648571 203 8.0800000000 0.0117923245 0.0108752133 0.0160688832 0.0136101369 3.4808860000 1.2738730000 0.2653100000 0.1461600000 1.7859370000 0.0083190000 108924894 0 1786535936 4.1264672279 4.0503211021 3.9752912521 204 8.1200000000 0.0118307406 0.0108798972 0.0160688832 0.0135813324 3.3262000000 1.2674940000 0.2648980000 0.0000030000 1.7843100000 0.0082040000 108926568 0 1785139200 4.1253914833 4.0525546074 3.9759051800 205 8.1600000000 0.0118585927 0.0108846714 0.0160688832 0.0135566475 5.2226860000 1.2747530000 0.2541670000 0.1460400000 1.7634180000 1.7830010000 108928242 0 1786916864 4.1231718063 4.0508818626 3.9765288830 206 8.1999999990 0.0118889920 0.0108895467 0.0160688832 0.0135401610 3.3143570000 1.2730250000 0.2544880000 0.0000030000 1.7772780000 0.0082580000 108929916 0 1785393152 4.1206073761 4.0484552383 3.9780242443 207 8.2400000000 0.0117531354 0.0108937186 0.0160688832 0.0135349056 3.5211640000 1.2690100000 0.3450620000 0.1516810000 1.7457910000 0.0082790000 108931590 0 1786789888 4.1188721657 4.0498967171 3.9788599014 208 8.2799999990 0.0119001251 0.0108985571 0.0160688832 0.0135527885 3.2998090000 1.2692880000 0.2552950000 0.0000020000 1.7655540000 0.0083480000 108933264 0 1784774656 4.1191773415 4.0472707748 3.9807202816 209 8.3200000000 0.0119631886 0.0109036511 0.0160688832 0.0135647036 5.1700220000 1.2704620000 0.2667840000 0.1458530000 1.7307390000 1.7548620000 108934938 0 1786281984 4.1173233986 4.0492916107 3.9812901020 210 8.3599999990 0.0119032543 0.0109084111 0.0160688832 0.0135793568 3.2818860000 1.2703710000 0.2550670000 0.0000030000 1.7460850000 0.0082840000 108936612 0 1785446400 4.1144223213 4.0528125763 3.9819045067 211 8.4000000000 0.0120064951 0.0109136153 0.0160688832 0.0136124419 3.3982920000 1.2709260000 0.2603790000 0.1457530000 1.7115250000 0.0083530000 108938286 0 1784401920 4.1122283936 4.0533976555 3.9828102589 212 8.4399999990 0.0119705591 0.0109186008 0.0160688832 0.0136376175 3.2655030000 1.2693030000 0.2580430000 0.0000030000 1.7285560000 0.0082700000 108939960 0 1785901056 4.1127710342 4.0504488945 3.9847874641 213 8.4800000000 0.0120020285 0.0109236874 0.0160688832 0.0136493795 5.0915470000 1.2708320000 0.2649870000 0.1457850000 1.6909500000 1.7176170000 108941634 0 1787805696 4.1087322235 4.0518398285 3.9855895042 214 8.5200000000 0.0119342897 0.0109284098 0.0160688832 0.0136650407 3.2433440000 1.2699110000 0.2556420000 0.0000030000 1.7081650000 0.0082700000 108943308 0 1784774656 4.1076693535 4.0517249107 3.9870495796 215 8.5600000000 0.0120454086 0.0109336051 0.0160688832 0.0136985888 3.3575220000 1.2694930000 0.2607090000 0.1459690000 1.6717730000 0.0082370000 108944982 0 1786281984 4.1060447693 4.0500979424 3.9883003235 216 8.6000000000 0.0120539591 0.0109387920 0.0160688832 0.0137150823 3.2332740000 1.2713700000 0.2573260000 0.0000030000 1.6948370000 0.0083310000 108946656 0 1788059648 4.1088085175 4.0541806221 3.9906201363 217 8.6400000000 0.0121143814 0.0109442094 0.0160688832 0.0137174309 5.0061190000 1.2718360000 0.2546610000 0.1464620000 1.6533920000 1.6783930000 108948330 0 1785155584 4.1085662842 4.0557703972 3.9920456409 218 8.6800000000 0.0121420259 0.0109497040 0.0160688832 0.0137259656 3.2095100000 1.2707990000 0.2569370000 0.0000020000 1.6721710000 0.0082270000 108950004 0 1786535936 4.1110663414 4.0550379753 3.9943389893 219 8.7200000000 0.0121594407 0.0109552279 0.0160688832 0.0137517116 3.3201700000 1.2735270000 0.2609900000 0.1466430000 1.6292940000 0.0082610000 108951678 0 1786052608 4.1131744385 4.0543022156 3.9978256226 220 8.7600000000 0.0122434655 0.0109610835 0.0160688832 0.0137653216 3.2360000000 1.2725100000 0.3024000000 0.0000030000 1.6514810000 0.0082250000 108953352 0 1787432960 4.1133961678 4.0523815155 4.0012292862 221 8.8000000000 0.0120934742 0.0109662075 0.0160688832 0.0137906064 4.9158690000 1.2761320000 0.2553870000 0.1468050000 1.6058230000 1.6255640000 108955026 0 1785028608 4.1149916649 4.0526876450 4.0035142899 222 8.8400000000 0.0121381348 0.0109714864 0.0160688832 0.0138187701 3.1613700000 1.2733540000 0.2556430000 0.0000030000 1.6226760000 0.0082890000 108956700 0 1786408960 4.1137051582 4.0548152924 4.0051755905 223 8.8800000000 0.0121337548 0.0109766984 0.0160688832 0.0138575114 3.2810700000 1.2743560000 0.2547740000 0.1468840000 1.5953550000 0.0082300000 108958374 0 1785520128 4.1124992371 4.0536513329 4.0071630478 224 8.9200000000 0.0121171838 0.0109817899 0.0160688832 0.0138767621 3.1482670000 1.2778960000 0.2551620000 0.0000020000 1.6055550000 0.0082150000 108960048 0 1786916864 4.1086874008 4.0533542633 4.0082321167 225 8.9600000000 0.0121235289 0.0109868642 0.0160688832 0.0140209085 4.8528320000 1.2810060000 0.2600610000 0.1470200000 1.5726680000 1.5906600000 108961722 0 1784901632 4.0668263435 4.0477032661 3.9935517311 226 9.0000000000 0.0121093476 0.0109918310 0.0160688832 0.0140277137 3.1485750000 1.2804050000 0.2658530000 0.0000020000 1.5926660000 0.0082220000 108963396 0 1786408960 4.0616149902 4.0509238243 3.9926810265 227 9.0400000000 0.0121401167 0.0109968895 0.0160688832 0.0140347521 3.4347970000 1.2738730000 0.4457360000 0.1473010000 1.5581350000 0.0082230000 108965070 0 1785266176 4.0582361221 4.0497183800 3.9932205677 228 9.0800000000 0.0120613221 0.0110015581 0.0160688832 0.0140425731 3.1196470000 1.2711330000 0.2653890000 0.0000030000 1.5734570000 0.0082170000 108966744 0 1786933248 4.0544633865 4.0497097969 3.9933626652 229 9.1200000000 0.0121717332 0.0110066680 0.0160688832 0.0140487012 4.7759760000 1.2792870000 0.2656700000 0.1476770000 1.5318880000 1.5500230000 108968418 0 1785782272 4.0500369072 4.0493416786 3.9930670261 230 9.1600000000 0.0120839709 0.0110113519 0.0160688832 0.0140582806 3.1115800000 1.2792960000 0.2674210000 0.0000030000 1.5551260000 0.0082570000 108970092 0 1787543552 4.0452265739 4.0495972633 3.9931294918 231 9.2000000000 0.0121271759 0.0110161823 0.0160688832 0.0140629324 3.2593630000 1.2727100000 0.3094420000 0.1476790000 1.5198210000 0.0082430000 108971766 0 1784791040 4.0413966179 4.0492281914 3.9926009178 232 9.2400000000 0.0122173242 0.0110213597 0.0160688832 0.0140692693 3.1317730000 1.2747500000 0.3113520000 0.0000030000 1.5358880000 0.0083130000 108973440 0 1786298368 4.0376677513 4.0486516953 3.9929041862 233 9.2800000000 0.0121922614 0.0110263850 0.0160688832 0.0140812734 4.7463520000 1.2720570000 0.3158000000 0.1478720000 1.4951060000 1.5140570000 108975114 0 1785774080 4.0349688530 4.0495777130 3.9920904636 234 9.3200000000 0.0121813808 0.0110313209 0.0160688832 0.0140845942 3.0834140000 1.2743910000 0.2649580000 0.0000020000 1.5343270000 0.0082750000 108976788 0 1787187200 4.0306720734 4.0496125221 3.9913892746 235 9.3600000000 0.0122775268 0.0110366239 0.0160688832 0.0141044288 3.1714760000 1.2730460000 0.2650370000 0.1481180000 1.4755430000 0.0082360000 108978462 0 1785298944 4.0281476974 4.0490117073 3.9912955761 236 9.4000000000 0.0121922540 0.0110415206 0.0160688832 0.0141415433 3.0612560000 1.2819080000 0.2660500000 0.0000030000 1.5035750000 0.0082320000 108980136 0 1786806272 4.0254011154 4.0477957726 3.9910078049 237 9.4400000000 0.0121626519 0.0110462511 0.0160688832 0.0141705415 4.6322610000 1.2742570000 0.2655650000 0.1487050000 1.4650170000 1.4772360000 108981810 0 1785409536 4.0225725174 4.0449690819 3.9905695915 238 9.4800000000 0.0121908626 0.0110510604 0.0160688832 0.0141956058 3.0308940000 1.2725770000 0.2553660000 0.0000020000 1.4931750000 0.0082630000 108983484 0 1787187200 4.0189628601 4.0409903526 3.9902794361 239 9.5200000000 0.0121315252 0.0110555812 0.0160688832 0.0142084857 3.1794730000 1.2716100000 0.3091560000 0.1480070000 1.4408670000 0.0082420000 108985158 0 1785180160 4.0166635513 4.0412921906 3.9898455143 240 9.5600000000 0.0122832572 0.0110606965 0.0160688832 0.0143555414 3.0264450000 1.2743420000 0.2622730000 0.0000040000 1.4800780000 0.0082440000 108986832 0 1786798080 4.0138735771 4.0352373123 3.9909372330 241 9.6000000000 0.0122546284 0.0110656506 0.0160688832 0.0143541565 4.5206790000 1.2746400000 0.2521770000 0.1481650000 1.4104160000 1.4337590000 108988506 0 1784774656 4.0113096237 4.0352568626 3.9900317192 242 9.6400000000 0.0123365466 0.0110709022 0.0160688832 0.0143670115 2.9834030000 1.2726830000 0.2657880000 0.0000050000 1.4351580000 0.0082360000 108990180 0 1786298368 4.0101938248 4.0329627991 3.9905424118 243 9.6800000000 0.0123561863 0.0110761915 0.0160688832 0.0143818221 3.0829350000 1.2793810000 0.2543430000 0.1482300000 1.3911850000 0.0082780000 108991854 0 1785679872 4.0083017349 4.0303306580 3.9902327061 244 9.7200000000 0.0123100644 0.0110812483 0.0160688832 0.0143911821 2.9677960000 1.2747560000 0.2649570000 0.0000040000 1.4182550000 0.0082810000 108993528 0 1787187200 4.0066838264 4.0296034813 3.9906051159 245 9.7600000000 0.0122965015 0.0110862085 0.0160688832 0.0143894237 4.4331320000 1.2713650000 0.2525620000 0.1483150000 1.3699580000 1.3893720000 108995202 0 1785425920 4.0048260689 4.0304036140 3.9903790951 246 9.8000000000 0.0123938257 0.0110915241 0.0160688832 0.0143928873 2.9507630000 1.2800800000 0.2652040000 0.0000040000 1.3956610000 0.0082680000 108996876 0 1787060224 4.0028939247 4.0291371346 3.9903676510 247 9.8400000000 0.0124639841 0.0110970806 0.0160688832 0.0144000467 3.0539830000 1.2770490000 0.2632320000 0.1482100000 1.3556200000 0.0082630000 108998550 0 1785282560 3.9997079372 4.0287108421 3.9895260334 248 9.8800000000 0.0125772925 0.0111030492 0.0160688832 0.0143970355 2.9692590000 1.2750250000 0.3107170000 0.0000040000 1.3737270000 0.0082330000 109000224 0 1786933248 3.9964287281 4.0254607201 3.9890913963 249 9.9200000000 0.0125990743 0.0111090573 0.0160688832 0.0143984608 4.3714040000 1.2725920000 0.2684920000 0.1482170000 1.3315370000 1.3490030000 109001898 0 1785069568 3.9924299717 4.0223770142 3.9872860909 250 9.9600000000 0.0125605669 0.0111148633 0.0160688832 0.0143918305 2.9039170000 1.2703260000 0.2652270000 0.0000050000 1.3584900000 0.0083020000 109003572 0 1786544128 3.9895784855 4.0224075317 3.9865131378 251 10.0000000000 0.0125884451 0.0111207342 0.0160688832 0.0143924816 3.0141410000 1.2729090000 0.2654960000 0.1493680000 1.3164570000 0.0082940000 109005246 0 1786060800 3.9862968922 4.0200462341 3.9854764938 252 10.0400000000 0.0127254622 0.0111271022 0.0160688832 0.0143986443 2.8966480000 1.2794540000 0.2650480000 0.0000040000 1.3422800000 0.0082780000 109006920 0 1787568128 3.9826695919 4.0180859566 3.9841642380 253 10.0800000000 0.0126848919 0.0111332594 0.0160688832 0.0143954111 4.3571510000 1.2719460000 0.3099750000 0.1481720000 1.3006830000 1.3248040000 109008594 0 1784901632 3.9798817635 4.0174422264 3.9833106995 254 10.1200000000 0.0125822527 0.0111389641 0.0160688832 0.0143923426 2.9220940000 1.2747750000 0.3122240000 0.0000040000 1.3252340000 0.0082750000 109010268 0 1786298368 3.9772267342 4.0154600143 3.9828224182 255 10.1600000000 0.0125639290 0.0111445522 0.0160688832 0.0143859978 2.9819910000 1.2799620000 0.2544630000 0.1484180000 1.2892050000 0.0082880000 109011942 0 1785520128 3.9745185375 4.0143995285 3.9816386700 256 10.2000000000 0.0123989508 0.0111494522 0.0160688832 0.0143846877 2.8993010000 1.2722960000 0.3010500000 0.0000040000 1.3106740000 0.0137020000 109013616 0 1787170816 3.9720683098 4.0130710602 3.9812262058 257 10.2400000000 0.0123420851 0.0111540928 0.0160688832 0.0144931736 4.2471010000 1.2740820000 0.2662060000 0.1479170000 1.2708480000 1.2864070000 109035770 0 1785012224 3.9674973488 4.0093765259 3.9800822735 258 10.2800000000 0.0123228636 0.0111586229 0.0160688832 0.0144957492 2.8447650000 1.2780010000 0.2677100000 0.0000040000 1.2891550000 0.0082330000 109079428 0 1786789888 3.9649400711 4.0084962845 3.9786465168 259 10.3200000000 0.0121709462 0.0111625315 0.0160688832 0.0144869245 2.9593060000 1.2750440000 0.2648410000 0.1479810000 1.2612880000 0.0085280000 109081102 0 1784393728 3.9630594254 4.0072531700 3.9777321815 260 10.3600000000 0.0121508082 0.0111663326 0.0160688832 0.0144757855 2.8692300000 1.2727970000 0.3116060000 0.0000040000 1.2749210000 0.0082730000 109082776 0 1786179584 3.9611220360 4.0054335594 3.9769632816 261 10.4000000000 0.0121678123 0.0111701697 0.0160688832 0.0144576301 4.1786840000 1.2730630000 0.2538720000 0.1477970000 1.2446210000 1.2577170000 109084450 0 1787805696 3.9592859745 4.0041894913 3.9759752750 262 10.4400000000 0.0121677164 0.0111739771 0.0160688832 0.0144398605 2.8456120000 1.2728030000 0.2986860000 0.0000030000 1.2587870000 0.0136760000 109086124 0 1784918016 3.9570705891 4.0024409294 3.9749989510 263 10.4800000000 0.0122259818 0.0111779771 0.0160688832 0.0144223663 2.9630350000 1.2717660000 0.3091510000 0.1480650000 1.2241200000 0.0082790000 109087798 0 1786535936 3.9549596310 4.0013256073 3.9738814831 264 10.5200000000 0.0122294789 0.0111819601 0.0160688832 0.0144062098 2.8204970000 1.3030560000 0.2647790000 0.0000040000 1.2427450000 0.0082630000 109089472 0 1786171392 3.9533166885 4.0000452995 3.9734234810 265 10.5600000000 0.0122390045 0.0111859489 0.0160688832 0.0143915577 4.1465890000 1.2728750000 0.3077010000 0.1475240000 1.1995180000 1.2172390000 109091146 0 1787695104 3.9502875805 3.9980113506 3.9711110592 266 10.6000000000 0.0123140244 0.0111901898 0.0160688832 0.0143827942 2.7601830000 1.2787210000 0.2540780000 0.0000040000 1.2174260000 0.0082560000 109092820 0 1785282560 3.9474682808 3.9959812164 3.9694659710 267 10.6400000000 0.0121568833 0.0111938104 0.0160688832 0.0143848147 2.8712920000 1.2741640000 0.2535630000 0.1473120000 1.1863230000 0.0082000000 109094494 0 1786916864 3.9451394081 3.9950578213 3.9679992199 268 10.6800000000 0.0121605080 0.0111974175 0.0160688832 0.0143907146 2.7368540000 1.2752350000 0.2536190000 0.0000040000 1.1980000000 0.0082160000 109096168 0 1784918016 3.9425733089 3.9932844639 3.9663107395 269 10.7200000000 0.0121628121 0.0112010063 0.0160688832 0.0144018353 4.0185920000 1.2750400000 0.2532880000 0.1530660000 1.1585790000 1.1769340000 109097842 0 1786298368 3.9402561188 3.9913957119 3.9646966457 270 10.7600000000 0.0121844048 0.0112046485 0.0160688832 0.0144082191 2.7276630000 1.2757380000 0.2536800000 0.0000040000 1.1882870000 0.0082570000 109099516 0 1785901056 3.9375033379 3.9896171093 3.9622187614 271 10.8000000000 0.0122326259 0.0112084418 0.0160688832 0.0144131842 2.8268060000 1.2764740000 0.2534070000 0.1473740000 1.1396070000 0.0082130000 109101190 0 1787465728 3.9352006912 3.9878470898 3.9604597092 272 10.8400000000 0.0120373042 0.0112114891 0.0160688832 0.0144307079 2.7796490000 1.3270200000 0.2652970000 0.0000040000 1.1773810000 0.0082550000 109102864 0 1784655872 3.9327344894 3.9859259129 3.9584016800 273 10.8800000000 0.0120355431 0.0112145076 0.0160688832 0.0144466356 3.9409870000 1.2760670000 0.2556440000 0.1476500000 1.1203200000 1.1395930000 109104538 0 1786171392 3.9301373959 3.9840810299 3.9561243057 274 10.9200000000 0.0119201802 0.0112170830 0.0160688832 0.0144569640 2.6831940000 1.2801270000 0.2558190000 0.0000040000 1.1373490000 0.0082150000 109106212 0 1788059648 3.9282641411 3.9824509621 3.9547123909 275 10.9600000000 0.0119899008 0.0112198933 0.0160688832 0.0144657218 2.8055380000 1.2730700000 0.2650640000 0.1485140000 1.1088860000 0.0082140000 109107886 0 1784520704 3.9261286259 3.9804534912 3.9530143738 276 11.0000000000 0.0119529571 0.0112225493 0.0160688832 0.0144654278 2.7655710000 1.2762650000 0.3574710000 0.0000040000 1.1219180000 0.0082250000 109109560 0 1786028032 3.9241943359 3.9798891544 3.9512310028 277 11.0400000000 0.0120938169 0.0112256947 0.0160688832 0.0147809914 3.8639710000 1.2738950000 0.2990670000 0.1464390000 1.0634130000 1.0794070000 109111234 0 1787932672 3.9162425995 3.9725980759 3.9443035126 278 11.0800000000 0.0119616920 0.0112283422 0.0160688832 0.0147744410 2.6237740000 1.2708750000 0.2664700000 0.0000040000 1.0763690000 0.0083240000 109112908 0 1784377344 3.9143347740 3.9703459740 3.9425885677 279 11.1200000000 0.0119503336 0.0112309299 0.0160688832 0.0147612989 2.7440950000 1.2785310000 0.2649260000 0.1462550000 1.0443230000 0.0083210000 109114582 0 1785901056 3.9129126072 3.9679403305 3.9417397976 280 11.1600000000 0.0117144687 0.0112326569 0.0160688832 0.0147525187 2.6915020000 1.2728080000 0.3488280000 0.0000040000 1.0598170000 0.0082980000 109116256 0 1787822080 3.9118587971 3.9667644501 3.9411475658 281 11.2000000000 0.0116739627 0.0112342273 0.0160688832 0.0147511477 3.8105030000 1.2782600000 0.3111500000 0.1461800000 1.0249500000 1.0482250000 109117930 0 1783996416 3.9106049538 3.9644644260 3.9401712418 282 11.2400000000 0.0114806658 0.0112351012 0.0160688832 0.0147496478 2.6360660000 1.2797320000 0.3020290000 0.0000030000 1.0443500000 0.0082110000 109119604 0 1785655296 3.9092884064 3.9634377956 3.9388175011 283 11.2800000000 0.0112337228 0.0112350964 0.0160688832 0.0147414217 2.7440100000 1.2799330000 0.3012960000 0.1459810000 1.0067180000 0.0082540000 109121278 0 1787432960 3.9083652496 3.9609029293 3.9379425049 284 11.3200000000 0.0108747156 0.0112338274 0.0160688832 0.0147475184 2.5805700000 1.2762820000 0.2696030000 0.0000040000 1.0242240000 0.0082820000 109122952 0 1784655872 3.9071607590 3.9591715336 3.9368205070 285 11.3600000000 0.0107686296 0.0112321951 0.0160688832 0.0147441683 3.7142340000 1.2782480000 0.2690810000 0.1465810000 0.9958460000 1.0227220000 109124626 0 1786028032 3.9060888290 3.9571554661 3.9356064796 286 11.4000000000 0.0105878087 0.0112299420 0.0160688832 0.0147320198 2.5616360000 1.2723350000 0.2701720000 0.0000040000 1.0091090000 0.0082050000 109126300 0 1787805696 3.9052667618 3.9546170235 3.9346609116 287 11.4400000000 0.0104462290 0.0112272113 0.0160688832 0.0147159512 2.7711180000 1.2766090000 0.3503790000 0.1457170000 0.9883350000 0.0082210000 109127974 0 1784139776 3.9045839310 3.9530057907 3.9339246750 288 11.4800000000 0.0103480406 0.0112241587 0.0160688832 0.0146954983 2.6644680000 1.3069010000 0.3517800000 0.0000040000 0.9957060000 0.0083220000 109129648 0 1785520128 3.9034652710 3.9506409168 3.9325923920 289 11.5200000000 0.0100965118 0.0112202568 0.0160688832 0.0146801501 3.6983830000 1.2755850000 0.3096380000 0.1456170000 0.9724910000 0.9932640000 109131322 0 1787424768 3.9031465054 3.9480385780 3.9320557117 290 11.5600000000 0.0099030435 0.0112157147 0.0160688832 0.0146659675 2.5390100000 1.2725640000 0.2700950000 0.0000040000 0.9862650000 0.0082600000 109132996 0 1783996416 3.9025175571 3.9468829632 3.9314572811 291 11.6000000000 0.0100180926 0.0112115991 0.0160688832 0.0146439587 2.7072680000 1.2788000000 0.3135720000 0.1455360000 0.9592470000 0.0083080000 109134670 0 1785520128 3.9022073746 3.9452738762 3.9311637878 292 11.6400000000 0.0097695077 0.0112066604 0.0160688832 0.0146195328 2.5519810000 1.2969920000 0.2671900000 0.0000040000 0.9777620000 0.0082460000 109136344 0 1787297792 3.9014337063 3.9428508282 3.9298169613 293 11.6800000000 0.0096119745 0.0112012178 0.0160688832 0.0145945117 3.8849330000 1.2713770000 0.5412810000 0.1456820000 0.9517910000 0.9730080000 109138018 0 1783869440 3.9011986256 3.9408273697 3.9294342995 294 11.7200000000 0.0095546292 0.0111956172 0.0160688832 0.0145708958 2.7945050000 1.2770920000 0.5442580000 0.0000040000 0.9630990000 0.0082110000 109139692 0 1785393152 3.9010288715 3.9397752285 3.9287202358 295 11.7600000000 0.0091051431 0.0111885308 0.0160688832 0.0145532090 2.7167320000 1.2729790000 0.3468980000 0.1452950000 0.9415290000 0.0082910000 109141366 0 1787179008 3.9009249210 3.9343280792 3.9282763004 296 11.8000000000 0.0088671688 0.0111806884 0.0160688832 0.0145334224 2.6542320000 1.2787380000 0.4051890000 0.0000040000 0.9602730000 0.0081990000 109143040 0 1783767040 3.9009568691 3.9319510460 3.9280595779 297 11.8400000000 0.0086346511 0.0111721159 0.0160688832 0.0145201755 3.5668300000 1.2740880000 0.2545380000 0.1454390000 0.9317140000 0.9592230000 109144714 0 1785266176 3.9005467892 3.9307336807 3.9271349907 298 11.8800000000 0.0084867505 0.0111631046 0.0160688832 0.0145550887 2.5120270000 1.2735020000 0.2679500000 0.0000040000 0.9604360000 0.0083190000 109146388 0 1787043840 3.8993449211 3.9267470837 3.9250051975 299 11.9200000000 0.0083668195 0.0111537525 0.0160688832 0.0145582370 2.6747180000 1.2753420000 0.3131210000 0.1452070000 0.9309410000 0.0082610000 109148062 0 1783996416 3.8986268044 3.9250395298 3.9236655235 300 11.9600000000 0.0080872066 0.0111435306 0.0160688832 0.0145706591 2.5316510000 1.3139080000 0.2699190000 0.0000040000 0.9377460000 0.0082390000 109149736 0 1785647104 3.8983192444 3.9228711128 3.9230070114 301 12.0000000000 0.0079824822 0.0111330288 0.0160688832 0.0145772267 3.5431080000 1.2723170000 0.2739600000 0.1452950000 0.9144040000 0.9352870000 109151410 0 1787297792 3.8975756168 3.9208097458 3.9217903614 302 12.0400000000 0.0076262923 0.0111214171 0.0160688832 0.0146157251 2.6818960000 1.2704540000 0.4496670000 0.0000050000 0.9517110000 0.0081890000 109153084 0 1784520704 3.8954019547 3.9170703888 3.9181997776 303 12.0800000000 0.0076178033 0.0111098540 0.0160688832 0.0146009995 2.8670870000 1.2789250000 0.5366330000 0.1456850000 0.8958090000 0.0081890000 109154758 0 1785901056 3.8940858841 3.9153947830 3.9161262512 304 12.1200000000 0.0073845442 0.0110975997 0.0160688832 0.0145886296 2.4682420000 1.2719750000 0.2661170000 0.0000040000 0.9201270000 0.0081640000 109156432 0 1787805696 3.8926146030 3.9132690430 3.9135956764 305 12.1600000000 0.0073935702 0.0110854554 0.0160688832 0.0145819742 3.4520860000 1.2743070000 0.2560290000 0.1459330000 0.8763710000 0.8975800000 109158106 0 1784012800 3.8913304806 3.9121599197 3.9116148949 306 12.2000000000 0.0070887785 0.0110723943 0.0160688832 0.0145814284 2.4968700000 1.2731700000 0.3181360000 0.0000050000 0.8953740000 0.0083120000 109159780 0 1785520128 3.8905916214 3.9095895290 3.9098811150 307 12.2400000000 0.0071058143 0.0110594739 0.0160688832 0.0145954904 2.5941530000 1.2715580000 0.3099840000 0.1447700000 0.8575980000 0.0082800000 109161454 0 1787449344 3.8891716003 3.9078705311 3.9077017307 308 12.2800000000 0.0069860015 0.0110462483 0.0160688832 0.0146125223 2.5211910000 1.3116050000 0.3175200000 0.0000040000 0.8819270000 0.0081940000 109163128 0 1783894016 3.8875346184 3.9060392380 3.9049515724 309 12.3200000000 0.0069553396 0.0110330091 0.0160688832 0.0146113278 3.4245160000 1.2829970000 0.2988430000 0.1444480000 0.8369670000 0.8593920000 109164802 0 1785393152 3.8858640194 3.9042162895 3.9018712044 310 12.3600000000 0.0069029024 0.0110196862 0.0160688832 0.0146112909 2.4570780000 1.2777040000 0.3117000000 0.0000050000 0.8574140000 0.0083580000 109166476 0 1787187200 3.8842132092 3.9024534225 3.8985605240 311 12.4000000000 0.0068330625 0.0110062244 0.0160688832 0.0146108722 2.5440510000 1.2720900000 0.2989030000 0.1442410000 0.8186820000 0.0081960000 109168150 0 1783996416 3.8829624653 3.9012446404 3.8957257271 312 12.4400000000 0.0067469683 0.0109925729 0.0160688832 0.0146037130 2.4303730000 1.3184880000 0.2656920000 0.0000050000 0.8360210000 0.0082500000 109169824 0 1785520128 3.8817002773 3.8998146057 3.8927056789 313 12.4800000000 0.0067231576 0.0109789326 0.0160688832 0.0145955922 3.3103740000 1.2730010000 0.2644940000 0.1439530000 0.7995160000 0.8274950000 109171498 0 1787424768 3.8804299831 3.8983654976 3.8901264668 314 12.5200000000 0.0067542233 0.0109654781 0.0160688832 0.0145942070 2.3684030000 1.2756400000 0.2659050000 0.0000030000 0.8166480000 0.0082890000 109173172 0 1783996416 3.8794014454 3.8971264362 3.8879945278 315 12.5600000000 0.0068512904 0.0109524172 0.0160688832 0.0145971229 2.5246470000 1.2711160000 0.3104110000 0.1435770000 0.7894770000 0.0081910000 109174846 0 1785393152 3.8780319691 3.8962023258 3.8852617741 316 12.6000000000 0.0067981207 0.0109392707 0.0160688832 0.0145948021 2.3980110000 1.2784010000 0.3126960000 0.0000030000 0.7968060000 0.0081830000 109176520 0 1787187200 3.8768010139 3.8948278427 3.8825240135 317 12.6400000000 0.0067999181 0.0109262128 0.0160688832 0.0145845776 3.2807660000 1.2712670000 0.3099710000 0.1431150000 0.7692010000 0.7851950000 109178194 0 1784393728 3.8755619526 3.8940050602 3.8798394203 318 12.6800000000 0.0068007647 0.0109132397 0.0160688832 0.0145702743 2.3255200000 1.2726480000 0.2654260000 0.0000030000 0.7772810000 0.0082320000 109179868 0 1785901056 3.8742685318 3.8931007385 3.8772187233 319 12.7200000000 0.0070206677 0.0109010373 0.0160688832 0.0145875625 2.5253840000 1.2722940000 0.3555420000 0.1480380000 0.7392060000 0.0082720000 109181542 0 1787678720 3.8719902039 3.8916749954 3.8720490932 320 12.7600000000 0.0070844688 0.0108891105 0.0160688832 0.0145755894 2.3453650000 1.2732770000 0.3121830000 0.0000030000 0.7496970000 0.0081940000 109183216 0 1784037376 3.8711287975 3.8907701969 3.8698148727 321 12.8000000000 0.0071991603 0.0108776153 0.0160688832 0.0145640770 3.2063820000 1.2726190000 0.3118550000 0.1434000000 0.7311180000 0.7454350000 109184890 0 1785401344 3.8698379993 3.8905947208 3.8672542572 322 12.8400000000 0.0074988473 0.0108671223 0.0160688832 0.0145499325 2.4257620000 1.2740760000 0.4054440000 0.0000030000 0.7360220000 0.0082620000 109186564 0 1787187200 3.8684854507 3.8897836208 3.8645184040 323 12.8800000000 0.0074330531 0.0108564905 0.0160688832 0.0145363131 2.3597890000 1.2761000000 0.2203600000 0.1420210000 0.7111070000 0.0082330000 109188238 0 1784123392 3.8674657345 3.8894047737 3.8627531528 324 12.9200000000 0.0076203095 0.0108465023 0.0160688832 0.0145234747 2.4029950000 1.2691530000 0.4053570000 0.0000030000 0.7183690000 0.0081760000 109189912 0 1785647104 3.8661351204 3.8895032406 3.8602323532 325 12.9600000000 0.0075659989 0.0108364084 0.0160688832 0.0145041088 3.2925580000 1.2686290000 0.4558290000 0.1418260000 0.7023560000 0.7219390000 109191586 0 1787424768 3.8649592400 3.8898642063 3.8583557606 326 13.0000000000 0.0077931900 0.0108270734 0.0160688832 0.0144843273 2.3070410000 1.2720720000 0.3127150000 0.0000170000 0.7119960000 0.0081740000 109193260 0 1784520704 3.8635454178 3.8898029327 3.8557608128 327 13.0400000000 0.0083858520 0.0108196079 0.0160688832 0.0144643104 2.5209420000 1.2763600000 0.4046580000 0.1415380000 0.6881810000 0.0082250000 109194934 0 1785901056 3.8623039722 3.8908340931 3.8529975414 328 13.0800000000 0.0081547573 0.0108114833 0.0160688832 0.0144447217 2.2896280000 1.2706830000 0.3141680000 0.0000030000 0.6945100000 0.0082770000 109196608 0 1787805696 3.8609268665 3.8919198513 3.8511581421 329 13.1200000000 0.0085081048 0.0108044822 0.0160688832 0.0144271049 3.3360020000 1.2744030000 0.5414900000 0.1413080000 0.6786810000 0.6980790000 109198282 0 1783758848 3.8597600460 3.8935217857 3.8488481045 330 13.1600000000 0.0090534529 0.0107991760 0.0160688832 0.0144091285 2.4535460000 1.2702000000 0.4861300000 0.0000030000 0.6869350000 0.0082320000 109199956 0 1785266176 3.8584461212 3.8944759369 3.8462297916 331 13.2000000000 0.0088768210 0.0107933683 0.0160688832 0.0143942910 2.4341630000 1.2962290000 0.3123000000 0.1413010000 0.6740440000 0.0082300000 109201630 0 1787162624 3.8573210239 3.8964064121 3.8447539806 332 13.2400000000 0.0090753464 0.0107881935 0.0160688832 0.0143772820 2.5019000000 1.2782260000 0.5362620000 0.0000030000 0.6771980000 0.0081870000 109203304 0 1784004608 3.8561096191 3.8984413147 3.8432333469 333 13.2800000000 0.0084935343 0.0107813027 0.0160688832 0.0143659793 3.1324070000 1.2776210000 0.3545080000 0.1409500000 0.6705750000 0.6867270000 109204978 0 1785528320 3.8548119068 3.9007594585 3.8423702717 334 13.3200000000 0.0087627377 0.0107752591 0.0160688832 0.0143899973 2.4128890000 1.2689710000 0.4488680000 0.0000030000 0.6848250000 0.0081810000 109206652 0 1787305984 3.8525629044 3.9054932594 3.8397362232 335 13.3600000000 0.0085008927 0.0107684699 0.0160688832 0.0143789012 2.5361700000 1.2748000000 0.4491190000 0.1409610000 0.6609200000 0.0082380000 109208326 0 1784020992 3.8516557217 3.9080770016 3.8392295837 336 13.4000000000 0.0090722190 0.0107634216 0.0160688832 0.0143671916 2.3660320000 1.2792860000 0.4038390000 0.0000030000 0.6726860000 0.0081940000 109210000 0 1785393152 3.8506627083 3.9104540348 3.8379821777 337 13.4400000000 0.0089328131 0.0107579895 0.0160688832 0.0143572523 3.1498900000 1.2725690000 0.4066910000 0.1407430000 0.6547750000 0.6730940000 109211674 0 1787170816 3.8497629166 3.9126739502 3.8376739025 338 13.4800000000 0.0090157418 0.0107528349 0.0160688832 0.0143593877 2.3081040000 1.2708560000 0.3646130000 0.0000030000 0.6622530000 0.0082380000 109213348 0 1784266752 3.8489408493 3.9143154621 3.8371963501 339 13.5200000000 0.0090611624 0.0107478447 0.0160688832 0.0143710504 2.3356880000 1.2702420000 0.2659000000 0.1403690000 0.6488950000 0.0082440000 109215022 0 1785774080 3.8478915691 3.9169111252 3.8367249966 340 13.5600000000 0.0091951266 0.0107432779 0.0160688832 0.0143735517 2.4891060000 1.2704090000 0.5512510000 0.0000030000 0.6572100000 0.0081920000 109216696 0 1787551744 3.8470959663 3.9188451767 3.8367264271 341 13.6000000000 0.0092053590 0.0107387679 0.0160688832 0.0143699896 3.0783620000 1.2724610000 0.3581310000 0.1402250000 0.6430430000 0.6624120000 109218370 0 1784012800 3.8462657928 3.9214925766 3.8367197514 342 13.6400000000 0.0094336150 0.0107349516 0.0160688832 0.0143644160 2.3013040000 1.2754530000 0.3603660000 0.0000020000 0.6552150000 0.0082210000 109220044 0 1785393152 3.8450362682 3.9242815971 3.8359718323 343 13.6800000000 0.0094271963 0.0107311389 0.0160688832 0.0143736207 2.3310950000 1.2718240000 0.2682240000 0.1402720000 0.6404510000 0.0081940000 109221718 0 1787170816 3.8441662788 3.9267919064 3.8358414173 344 13.7200000000 0.0092947641 0.0107269634 0.0160688832 0.0143873719 2.3030280000 1.2722740000 0.3671000000 0.0000030000 0.6531960000 0.0082340000 109223392 0 1783885824 3.8434200287 3.9293165207 3.8358654976 345 13.7600000000 0.0095268954 0.0107234850 0.0160688832 0.0145373855 2.9820950000 1.2717200000 0.2678870000 0.1400760000 0.6401380000 0.6601800000 109225066 0 1785393152 3.8418197632 3.9347548485 3.8356249332 346 13.8000000000 0.0099682193 0.0107213021 0.0160688832 0.0145463907 2.3039380000 1.2735590000 0.3635200000 0.0000020000 0.6565270000 0.0081870000 109226740 0 1787170816 3.8411829472 3.9369926453 3.8351075649 347 13.8400000000 0.0101708164 0.0107197157 0.0160688832 0.0145447956 2.4164100000 1.2701340000 0.3598240000 0.1399170000 0.6360790000 0.0083410000 109228414 0 1784688640 3.8402864933 3.9396133423 3.8347551823 348 13.8800000000 0.0099448916 0.0107174892 0.0160688832 0.0145314543 2.2575190000 1.2750270000 0.3214150000 0.0000020000 0.6507260000 0.0082310000 109230088 0 1786179584 3.8394620419 3.9424965382 3.8348777294 349 13.9200000000 0.0095107062 0.0107140314 0.0160688832 0.0145112902 3.1799200000 1.2783180000 0.4543610000 0.1402710000 0.6423220000 0.6624960000 109231762 0 1788067840 3.8385975361 3.9459624290 3.8352406025 350 13.9600000000 0.0101112388 0.0107123091 0.0160688832 0.0144956192 2.3584990000 1.2778140000 0.4083620000 0.0000020000 0.6619440000 0.0082470000 109233436 0 1784901632 3.8378345966 3.9482634068 3.8346097469 351 14.0000000000 0.0100852819 0.0107105227 0.0160688832 0.0144931249 2.3458630000 1.2859180000 0.2698610000 0.1397990000 0.6398380000 0.0083290000 109235110 0 1786662912 3.8371484280 3.9517600536 3.8346860409 352 14.0400000000 0.0099715060 0.0107084232 0.0160688832 0.0144913486 2.3634070000 1.2760980000 0.4146130000 0.0000020000 0.6623570000 0.0081800000 109236784 0 1785425920 3.8364036083 3.9545745850 3.8350250721 353 14.0800000000 0.0099459337 0.0107062632 0.0160688832 0.0145011187 3.2222460000 1.2725580000 0.4979670000 0.1397730000 0.6440120000 0.6657780000 109238458 0 1786933248 3.8357446194 3.9582607746 3.8353514671 354 14.1200000000 0.0104429489 0.0107055194 0.0160688832 0.0145246730 2.3208000000 1.2795780000 0.3641160000 0.0000030000 0.6667160000 0.0082240000 109240132 0 1784393728 3.8352596760 3.9609763622 3.8353424072 355 14.1600000000 0.0102251088 0.0107041661 0.0160688832 0.0145476854 2.4274340000 1.2699520000 0.3613700000 0.1399060000 0.6457440000 0.0082890000 109241806 0 1785774080 3.8347330093 3.9639649391 3.8359918594 356 14.2000000000 0.0099673467 0.0107020964 0.0160688832 0.0145577333 2.4065340000 1.2757660000 0.4566680000 0.0000030000 0.6637760000 0.0081820000 109243480 0 1787805696 3.8341867924 3.9674844742 3.8364400864 357 14.2400000000 0.0100228861 0.0107001938 0.0160688832 0.0145598517 3.1022600000 1.2743450000 0.3617470000 0.1398790000 0.6509280000 0.6731830000 109245154 0 1785282560 3.8337268829 3.9702241421 3.8370537758 358 14.2800000000 0.0100641977 0.0106984173 0.0160688832 0.0145644681 2.4143780000 1.2795540000 0.4531650000 0.0000030000 0.6712120000 0.0082620000 109246828 0 1786916864 3.8333227634 3.9725830555 3.8377907276 359 14.3200000000 0.0095352866 0.0106951774 0.0160688832 0.0145701370 2.4095310000 1.2896100000 0.3125110000 0.1400840000 0.6569320000 0.0081920000 109248502 0 1784156160 3.8329970837 3.9758508205 3.8389847279 360 14.3600000000 0.0100963255 0.0106935139 0.0160688832 0.0145679697 2.2330940000 1.2795440000 0.2669600000 0.0000030000 0.6760930000 0.0082930000 109250176 0 1785790464 3.8328218460 3.9782209396 3.8391282558 361 14.4000000000 0.0101407049 0.0106919826 0.0160688832 0.0145639134 3.0746840000 1.2725150000 0.3020580000 0.1402110000 0.6672390000 0.6904900000 109251850 0 1787686912 3.8326783180 3.9812650681 3.8399875164 362 14.4400000000 0.0097229090 0.0106893056 0.0160688832 0.0145684269 2.5278540000 1.2819600000 0.5454280000 0.0000030000 0.6899000000 0.0082760000 109253524 0 1785171968 3.8326294422 3.9838922024 3.8412630558 363 14.4800000000 0.0097995419 0.0106868545 0.0160688832 0.0145701112 2.4135770000 1.2737820000 0.3124630000 0.1403480000 0.6765630000 0.0082120000 109255198 0 1786679296 3.8326649666 3.9857168198 3.8420820236 364 14.5200000000 0.0101446984 0.0106853650 0.0160688832 0.0145719095 2.5448780000 1.2864090000 0.5450620000 0.0000030000 0.7029910000 0.0081880000 109256872 0 1784520704 3.8325867653 3.9880502224 3.8425400257 365 14.5600000000 0.0098964106 0.0106832035 0.0160688832 0.0145775104 3.2209320000 1.2750400000 0.4041870000 0.1406500000 0.6835090000 0.7153230000 109258546 0 1785917440 3.8326628208 3.9897654057 3.8437445164 366 14.6000000000 0.0091713211 0.0106790727 0.0160688832 0.0146696960 2.3819560000 1.2807590000 0.3570070000 0.0000030000 0.7337530000 0.0082610000 109260220 0 1787805696 3.8333745003 3.9965794086 3.8463668823 367 14.6400000000 0.0085258791 0.0106732057 0.0160688832 0.0146855744 2.4648120000 1.2936220000 0.3106370000 0.1414370000 0.7085690000 0.0082300000 109261894 0 1785298944 3.8338077068 3.9998166561 3.8479180336 368 14.6800000000 0.0084435819 0.0106671469 0.0160688832 0.0146965530 2.5053100000 1.2721450000 0.4962990000 0.0000030000 0.7263610000 0.0081950000 109263568 0 1786916864 3.8346617222 4.0026478767 3.8498017788 369 14.7200000000 0.0080412626 0.0106600307 0.0160688832 0.0147180671 3.3090880000 1.2786150000 0.3983420000 0.1417010000 0.7346580000 0.7535650000 109265242 0 1784250368 3.8362312317 4.0101547241 3.8531222343 370 14.7600000000 0.0073504425 0.0106510858 0.0160688832 0.0147250699 2.3980070000 1.2757140000 0.3575080000 0.0000030000 0.7541850000 0.0083620000 109266916 0 1785790464 3.8376662731 4.0136785507 3.8562290668 371 14.8000000000 0.0061844229 0.0106390463 0.0160688832 0.0147289488 2.5528020000 1.2815710000 0.3628650000 0.1418350000 0.7561030000 0.0082220000 109268590 0 1787551744 3.8388679028 4.0174555779 3.8596668243 372 14.8400000000 0.0055189137 0.0106252825 0.0160688832 0.0147293545 2.3651950000 1.2721290000 0.3119980000 0.0000030000 0.7704930000 0.0083050000 109270264 0 1784901632 3.8399240971 4.0209331512 3.8631196022 373 14.8800000000 0.0053886333 0.0106112432 0.0160688832 0.0147264703 3.3282640000 1.2761450000 0.3175670000 0.1423900000 0.7836720000 0.8061670000 109271938 0 1786552320 3.8413891792 4.0252943039 3.8667156696 374 14.9200000000 0.0056653949 0.0105980191 0.0160688832 0.0147191354 2.3957430000 1.2711240000 0.3123640000 0.0000020000 0.8017450000 0.0082290000 109273612 0 1785655296 3.8428387642 4.0296669006 3.8697938919 375 14.9600000000 0.0064235874 0.0105868872 0.0160688832 0.0147142327 2.5640890000 1.2818650000 0.3122290000 0.1429390000 0.8166110000 0.0081930000 109275286 0 1787179008 3.8443961143 4.0339493752 3.8733415604 376 15.0000000000 0.0070031607 0.0105773561 0.0160688832 0.0147235475 2.4335170000 1.2724540000 0.3122030000 0.0000030000 0.8383680000 0.0082050000 109276960 0 1784250368 3.8459899426 4.0371227264 3.8764259815 377 15.0400000000 0.0074507482 0.0105690627 0.0160688832 0.0147446541 3.5139730000 1.3054720000 0.3573270000 0.1433250000 0.8410450000 0.8645270000 109278634 0 1786028032 3.8479180336 4.0400362015 3.8794729710 378 15.0800000000 0.0080776336 0.0105624716 0.0160688832 0.0147563192 2.4191470000 1.2728170000 0.2671740000 0.0000030000 0.8686060000 0.0082610000 109280308 0 1787805696 3.8498139381 4.0436582565 3.8820090294 379 15.1200000000 0.0084309420 0.0105568475 0.0160688832 0.0147530251 2.6012590000 1.2697950000 0.3110630000 0.1436750000 0.8659060000 0.0082810000 109281982 0 1785155584 3.8520245552 4.0465655327 3.8846523762 380 15.1600000000 0.0089014666 0.0105524912 0.0160688832 0.0147582837 2.4418690000 1.2705610000 0.2657200000 0.0000030000 0.8950220000 0.0082780000 109283656 0 1786535936 3.8542001247 4.0490365028 3.8872170448 381 15.2000000000 0.0093380529 0.0105493037 0.0160688832 0.0147634572 3.5349270000 1.3038900000 0.2655590000 0.1442710000 0.8976890000 0.9211960000 109285330 0 1783902208 3.8562586308 4.0511898994 3.8893053532 382 15.2400000000 0.0093874922 0.0105462623 0.0160688832 0.0147598132 2.4704240000 1.2776770000 0.2657150000 0.0000030000 0.9164130000 0.0083040000 109287004 0 1785520128 3.8585333824 4.0528612137 3.8913178444 383 15.2800000000 0.0094746333 0.0105434643 0.0160688832 0.0147563216 2.6116580000 1.2762330000 0.2547470000 0.1446920000 0.9253910000 0.0082810000 109288678 0 1787314176 3.8605940342 4.0545692444 3.8933038712 384 15.3200000000 0.0094706053 0.0105406704 0.0160688832 0.0147745882 2.4987480000 1.2767110000 0.2659170000 0.0000020000 0.9454730000 0.0083300000 109290352 0 1784139776 3.8627400398 4.0558295250 3.8952608109 385 15.3600000000 0.0095326900 0.0105380523 0.0160688832 0.0147783517 3.6516240000 1.3028580000 0.2652670000 0.1452590000 0.9538240000 0.9820850000 109292026 0 1785790464 3.8652644157 4.0564503670 3.8974027634 386 15.4000000000 0.0096337423 0.0105357095 0.0160688832 0.0147782496 2.5603660000 1.2744840000 0.3011290000 0.0000030000 0.9741610000 0.0082760000 109293700 0 1787449344 3.8675284386 4.0586676598 3.8992798328 387 15.4400000000 0.0098591624 0.0105339614 0.0160688832 0.0147790490 2.6885870000 1.2793890000 0.2660170000 0.1455210000 0.9870040000 0.0082200000 109295374 0 1784528896 3.8702776432 4.0597028732 3.9019320011 388 15.4800000000 0.0097651938 0.0105319800 0.0160688832 0.0147884766 2.5896820000 1.2755340000 0.3009240000 0.0000030000 1.0026530000 0.0082270000 109297048 0 1786036224 3.8732163906 4.0603218079 3.9043440819 389 15.5200000000 0.0097411592 0.0105299470 0.0160688832 0.0147930025 3.7672150000 1.3031860000 0.2664280000 0.1459830000 1.0159330000 1.0333380000 109298722 0 1787949056 3.8754274845 4.0618958473 3.9060842991 390 15.5600000000 0.0100008892 0.0105285905 0.0160688832 0.0147859609 2.5640110000 1.2748990000 0.2555420000 0.0000030000 1.0228610000 0.0083590000 109300396 0 1784123392 3.8785598278 4.0624351501 3.9092311859 391 15.6000000000 0.0100427028 0.0105273478 0.0160688832 0.0147844089 2.7268310000 1.2815530000 0.2550350000 0.1465420000 1.0330540000 0.0082810000 109302070 0 1785647104 3.8809175491 4.0631766319 3.9114019871 392 15.6400000000 0.0100716660 0.0105261853 0.0160688832 0.0147846514 2.5812450000 1.2708500000 0.2549410000 0.0000030000 1.0447580000 0.0083380000 109303744 0 1787551744 3.8840603828 4.0629692078 3.9141192436 393 15.6800000000 0.0100804735 0.0105250512 0.0160688832 0.0147839635 3.8559310000 1.3107740000 0.2661690000 0.1462870000 1.0554050000 1.0749170000 109305418 0 1784901632 3.8865778446 4.0634074211 3.9161415100 394 15.7200000000 0.0101616681 0.0105241289 0.0160688832 0.0147880506 2.6291780000 1.2769080000 0.2729930000 0.0000030000 1.0686080000 0.0082870000 109307092 0 1786281984 3.8894276619 4.0649075508 3.9180026054 395 15.7600000000 0.0103247678 0.0105236242 0.0160688832 0.0147930938 2.7824810000 1.2764670000 0.2661480000 0.1466220000 1.0824960000 0.0083570000 109308766 0 1785409536 3.8921957016 4.0650696754 3.9199271202 396 15.8000000000 0.0103114415 0.0105230884 0.0160688832 0.0147874642 2.6538730000 1.2770500000 0.2661560000 0.0000030000 1.0999020000 0.0083000000 109310440 0 1786789888 3.8952467442 4.0658721924 3.9216771126 397 15.8400000000 0.0103432741 0.0105226355 0.0160688832 0.0147785507 3.9711030000 1.3164550000 0.2556720000 0.1469620000 1.1114380000 1.1381490000 109312114 0 1783902208 3.8986377716 4.0673966408 3.9239835739 398 15.8800000000 0.0104245404 0.0105223890 0.0160688832 0.0147730561 2.6799700000 1.2752350000 0.2658750000 0.0000030000 1.1281370000 0.0082310000 109313788 0 1785528320 3.8999471664 4.0681633949 3.9238379002 399 15.9200000000 0.0103826234 0.0105220387 0.0160688832 0.0147686496 2.8787040000 1.2736160000 0.3010900000 0.1529050000 1.1403400000 0.0082870000 109315462 0 1787305984 3.9034702778 4.0690388680 3.9259095192 400 15.9600000000 0.0104330331 0.0105218162 0.0160688832 0.0147641403 2.7055350000 1.2763120000 0.2659260000 0.0000040000 1.1525420000 0.0083320000 109317136 0 1784655872 3.9051229954 4.0683097839 3.9266116619 401 16.0000000000 0.0104693351 0.0105216853 0.0160688832 0.0147525636 4.0735330000 1.3111580000 0.2651780000 0.1481520000 1.1639210000 1.1827260000 109318810 0 1786155008 3.9070870876 4.0676989555 3.9279487133 402 16.0400000000 0.0105245439 0.0105216924 0.0160688832 0.0147444175 2.7389530000 1.2759360000 0.2672500000 0.0000030000 1.1851340000 0.0082300000 109320484 0 1788059648 3.9091989994 4.0679860115 3.9290904999 403 16.0800000000 0.0106134638 0.0105219201 0.0160688832 0.0147443828 2.8887390000 1.2759410000 0.2658660000 0.1477410000 1.1883640000 0.0082870000 109322158 0 1784250368 3.9107553959 4.0663390160 3.9298477173 404 16.1200000000 0.0106585575 0.0105222584 0.0160688832 0.0147512236 2.7599640000 1.2735430000 0.2731280000 0.0000020000 1.2025890000 0.0082980000 109323832 0 1785647104 3.9126172066 4.0664300919 3.9304878712 405 16.1600000000 0.0107534369 0.0105228292 0.0160688832 0.0147533284 4.1299440000 1.2743340000 0.2560130000 0.1479630000 1.2125820000 1.2366480000 109325506 0 1787678720 3.9151153564 4.0679264069 3.9313750267 406 16.2000000000 0.0108925886 0.0105237399 0.0160688832 0.0147502168 2.7644060000 1.2732330000 0.2562940000 0.0000020000 1.2240770000 0.0083000000 109327180 0 1784520704 3.9174828529 4.0683102608 3.9327354431 407 16.2400000000 0.0109818624 0.0105248655 0.0160688832 0.0147567395 2.9328450000 1.2759870000 0.2563010000 0.1535460000 1.2361280000 0.0082920000 109328854 0 1785901056 3.9204747677 4.0684728622 3.9340844154 408 16.2800000000 0.0111071263 0.0105262926 0.0160688832 0.0147611798 2.7990090000 1.2722770000 0.2673860000 0.0000030000 1.2485540000 0.0082320000 109330528 0 1787805696 3.9231805801 4.0689697266 3.9350721836 409 16.3200000000 0.0110797333 0.0105276458 0.0160688832 0.0147531980 4.2833830000 1.2800600000 0.3126550000 0.1480160000 1.2607220000 1.2793670000 109332202 0 1784131584 3.9264078140 4.0691299438 3.9368181229 410 16.3600000000 0.0110991597 0.0105290397 0.0160688832 0.0147558245 2.8742790000 1.2723800000 0.3130220000 0.0000030000 1.2780630000 0.0083540000 109333876 0 1785528320 3.9295468330 4.0685458183 3.9386069775 411 16.3999999990 0.0111567155 0.0105305669 0.0160688832 0.0147659463 2.9717400000 1.2725320000 0.2564340000 0.1480230000 1.2839770000 0.0082870000 109335550 0 1787297792 3.9327142239 4.0669651031 3.9403891563 412 16.4400000000 0.0111405477 0.0105320474 0.0160688832 0.0147695431 2.7953260000 1.2775020000 0.2111830000 0.0000030000 1.2958230000 0.0083110000 109337224 0 1784504320 3.9345893860 4.0668406487 3.9414579868 413 16.4800000000 0.0112399124 0.0105337614 0.0160688832 0.0147748870 4.3572000000 1.3008730000 0.2668830000 0.1483220000 1.3126670000 1.3259020000 109338898 0 1785901056 3.9375739098 4.0653862953 3.9434571266 414 16.5200000000 0.0112481629 0.0105354870 0.0160688832 0.0147686991 2.8722800000 1.2736340000 0.2665800000 0.0000030000 1.3212850000 0.0082830000 109340572 0 1787678720 3.9396059513 4.0655221939 3.9443652630 415 16.5599999990 0.0113232546 0.0105373852 0.0160688832 0.0147592785 3.0244520000 1.2763740000 0.2562820000 0.1481030000 1.3328230000 0.0083680000 109342246 0 1783996416 3.9417438507 4.0661745071 3.9452157021 416 16.6000000000 0.0112928189 0.0105392012 0.0160688832 0.0147471146 2.9459760000 1.2720570000 0.3129110000 0.0000030000 1.3501750000 0.0082380000 109343920 0 1785393152 3.9430723190 4.0663456917 3.9457917213 417 16.6400000000 0.0113182198 0.0105410693 0.0160688832 0.0147386918 4.4702310000 1.2742170000 0.3130530000 0.1481340000 1.3555660000 1.3767720000 109345594 0 1787297792 3.9454908371 4.0669417381 3.9468443394 418 16.6800000000 0.0113429166 0.0105429876 0.0160688832 0.0147294265 2.9256850000 1.2805510000 0.2671310000 0.0000020000 1.3671570000 0.0082930000 109347268 0 1784520704 3.9460587502 4.0658774376 3.9470567703 419 16.7199999990 0.0113966381 0.0105450250 0.0160688832 0.0147232590 3.0735750000 1.2738080000 0.2568090000 0.1480420000 1.3839800000 0.0082430000 109348942 0 1785901056 3.9486584663 4.0652613640 3.9481337070 420 16.7600000000 0.0114548812 0.0105471913 0.0160688832 0.0147211567 2.9408230000 1.2735330000 0.2668960000 0.0000030000 1.3896970000 0.0082410000 109350616 0 1787719680 3.9503726959 4.0637512207 3.9496185780 421 16.8000000000 0.0114440778 0.0105493217 0.0160688832 0.0147209923 4.5179170000 1.2789830000 0.2684450000 0.1482570000 1.4009940000 1.4186380000 109352290 0 1783996416 3.9525771141 4.0620408058 3.9512636662 422 16.8400000000 0.0115052024 0.0105515868 0.0160688832 0.0147155627 2.9562520000 1.2722970000 0.2571780000 0.0000030000 1.4160310000 0.0082860000 109353964 0 1785393152 3.9541614056 4.0627040863 3.9519844055 423 16.8799999990 0.0116167236 0.0105541049 0.0160688832 0.0147116740 3.1588160000 1.2733630000 0.3024260000 0.1487220000 1.4233940000 0.0083080000 109355638 0 1787297792 3.9563050270 4.0618000031 3.9530754089 424 16.9200000000 0.0116243362 0.0105566290 0.0160688832 0.0147027215 3.0352850000 1.2848790000 0.3019250000 0.0000030000 1.4376860000 0.0083250000 109357312 0 1784520704 3.9590706825 4.0605955124 3.9542691708 425 16.9600000000 0.0116963042 0.0105593106 0.0160688832 0.0147087984 4.5943500000 1.2730640000 0.2570860000 0.1481110000 1.4512210000 1.4622460000 109358986 0 1785901056 3.9615159035 4.0605640411 3.9564249516 426 17.0000000000 0.0117255868 0.0105620483 0.0160688832 0.0147041114 3.0118960000 1.2732660000 0.2673490000 0.0000030000 1.4604750000 0.0082680000 109360660 0 1787805696 3.9639081955 4.0566425323 3.9579985142 427 17.0400000000 0.0116766477 0.0105646586 0.0160688832 0.0146996295 3.1649290000 1.2717460000 0.2680050000 0.1478540000 1.4663640000 0.0082920000 109362334 0 1783758848 3.9669723511 4.0556111336 3.9588885307 428 17.0800000000 0.0117629236 0.0105674583 0.0160688832 0.0146941214 3.0355800000 1.2730330000 0.2687040000 0.0000030000 1.4829500000 0.0082860000 109364008 0 1785139200 3.9698286057 4.0555310249 3.9602441788 429 17.1200000000 0.0117420405 0.0105701963 0.0160688832 0.0146880980 4.6847210000 1.2713310000 0.2688730000 0.1476830000 1.4855500000 1.5087220000 109365682 0 1787043840 3.9722414017 4.0549106598 3.9613666534 430 17.1600000000 0.0118466942 0.0105731649 0.0160688832 0.0146796562 3.0545820000 1.2803410000 0.2678250000 0.0000030000 1.4951710000 0.0084210000 109367356 0 1784545280 3.9746975899 4.0574431419 3.9619133472 431 17.2000000000 0.0118091824 0.0105760326 0.0160688832 0.0146736053 3.2121740000 1.2798170000 0.2682110000 0.1476240000 1.5056240000 0.0082820000 109369030 0 1785909248 3.9771974087 4.0572080612 3.9622869492 432 17.2400000000 0.0117742764 0.0105788064 0.0160688832 0.0146744048 3.0579270000 1.2711100000 0.2557210000 0.0000020000 1.5201910000 0.0083290000 109370704 0 1787805696 3.9797701836 4.0523939133 3.9636325836 433 17.2800000000 0.0118168686 0.0105816656 0.0160688832 0.0146866646 4.7482080000 1.2696930000 0.2568060000 0.1473440000 1.5243650000 1.5473890000 109372378 0 1783758848 3.9809966087 4.0483670235 3.9654595852 434 17.3200000000 0.0118358750 0.0105845555 0.0160688832 0.0146908831 3.0865990000 1.2731740000 0.2677150000 0.0000030000 1.5348940000 0.0082280000 109374052 0 1785266176 3.9836783409 4.0461883545 3.9670703411 435 17.3600000000 0.0118949683 0.0105875680 0.0160688832 0.0146954491 3.2384690000 1.2722550000 0.2568960000 0.1469830000 1.5514460000 0.0082980000 109375726 0 1787162624 3.9859807491 4.0428214073 3.9680864811 436 17.4000000000 0.0118920524 0.0105905599 0.0160688832 0.0146942326 3.0984400000 1.2744680000 0.2562600000 0.0000040000 1.5567820000 0.0083100000 109377400 0 1784496128 3.9872059822 4.0410904884 3.9692285061 437 17.4400000000 0.0118912216 0.0105935362 0.0160688832 0.0146898059 4.8908820000 1.2807130000 0.3024460000 0.1465840000 1.5701670000 1.5883700000 109379074 0 1786028032 3.9877760410 4.0403666496 3.9696094990 438 17.4800000000 0.0119464556 0.0105966251 0.0160688832 0.0147048271 3.1361630000 1.2779310000 0.2681040000 0.0000030000 1.5792040000 0.0082700000 109380748 0 1787695104 3.9879238605 4.0400452614 3.9708673954 439 17.5200000000 0.0119648566 0.0105997418 0.0160688832 0.0147137917 3.2815230000 1.2712700000 0.2575010000 0.1463190000 1.5954660000 0.0082960000 109382422 0 1784012800 3.9875485897 4.0390052795 3.9716184139 440 17.5600000000 0.0120094847 0.0106029458 0.0160688832 0.0147173638 3.1397930000 1.2717060000 0.2568540000 0.0000030000 1.6003040000 0.0082960000 109384096 0 1785528320 3.9859755039 4.0385627747 3.9719898701 441 17.6000000000 0.0120196277 0.0106061582 0.0160688832 0.0147297365 4.9327470000 1.2787600000 0.2581110000 0.1460100000 1.6171100000 1.6301170000 109385770 0 1787305984 3.9846172333 4.0379047394 3.9731016159 442 17.6400000000 0.0120358914 0.0106093929 0.0160688832 0.0148203219 3.1783100000 1.2747960000 0.2565320000 0.0000020000 1.6360540000 0.0082830000 109387444 0 1784520704 3.9752545357 4.0346817970 3.9732828140 443 17.6800000000 0.0119960103 0.0106125229 0.0160688832 0.0148292717 3.3382900000 1.2713270000 0.2578870000 0.1455290000 1.6525370000 0.0083580000 109389118 0 1785901056 3.9712142944 4.0351305008 3.9731059074 444 17.7200000000 0.0120165367 0.0106156851 0.0160688832 0.0148346048 3.2085470000 1.2708160000 0.2695310000 0.0000030000 1.6572690000 0.0082720000 109390792 0 1787678720 3.9687879086 4.0349941254 3.9738011360 445 17.7600000000 0.0120372726 0.0106188797 0.0160688832 0.0148407632 5.0422660000 1.2738360000 0.2717570000 0.1461350000 1.6652550000 1.6826120000 109392466 0 1784520704 3.9670534134 4.0308680534 3.9745707512 446 17.8000000000 0.0118708257 0.0106216868 0.0160688832 0.0148494742 3.2550780000 1.3145980000 0.2579000000 0.0000030000 1.6715040000 0.0084140000 109394140 0 1786028032 3.9653594494 4.0286750793 3.9754078388 447 17.8400000000 0.0120049668 0.0106247813 0.0160688832 0.0148487280 3.3805760000 1.2689480000 0.2687270000 0.1453880000 1.6864780000 0.0083020000 109395814 0 1787805696 3.9664306641 4.0244154930 3.9770734310 448 17.8800000000 0.0119216880 0.0106276762 0.0160688832 0.0148403429 3.2282460000 1.2717270000 0.2581520000 0.0000030000 1.6874400000 0.0082150000 109397488 0 1783996416 3.9672939777 4.0215106010 3.9782643318 449 17.9200000000 0.0119438376 0.0106306075 0.0160688832 0.0148312317 5.0883510000 1.2668780000 0.2633330000 0.1451760000 1.6965410000 1.7136800000 109399162 0 1785528320 3.9654021263 4.0186533928 3.9804487228 450 17.9600000000 0.0119075105 0.0106334451 0.0160688832 0.0148188174 3.2663970000 1.2822720000 0.2684780000 0.0000030000 1.7042050000 0.0084900000 109400836 0 1787297792 3.9662604332 4.0153503418 3.9820568562 451 18.0000000000 0.0119685382 0.0106364054 0.0160688832 0.0148112494 3.4016830000 1.2698870000 0.2590400000 0.1452310000 1.7164070000 0.0083390000 109402510 0 1784410112 3.9665105343 4.0146894455 3.9850916862 452 18.0400000000 0.0117940744 0.0106389666 0.0160688832 0.0148058684 3.2442600000 1.2667380000 0.2480520000 0.0000030000 1.7184530000 0.0082940000 109404184 0 1785774080 3.9668633938 4.0122189522 3.9881556034 453 18.0800000000 0.0117788147 0.0106414828 0.0160688832 0.0147957853 5.1936660000 1.2740330000 0.3053390000 0.1448600000 1.7244080000 1.7423230000 109405858 0 1787678720 3.9678473473 4.0107245445 3.9913768768 454 18.1200000000 0.0117699383 0.0106439684 0.0160688832 0.0147837815 3.4340800000 1.2990150000 0.3978290000 0.0000030000 1.7261850000 0.0082350000 109407532 0 1783869440 3.9682993889 4.0101337433 3.9953632355 455 18.1600000000 0.0118295401 0.0106465741 0.0160688832 0.0147689898 3.4629910000 1.2660120000 0.3038790000 0.1459910000 1.7360970000 0.0082160000 109409206 0 1785266176 3.9698832035 4.0085778236 3.9992589951 456 18.2000000000 0.0117388843 0.0106489695 0.0160688832 0.0147601742 3.2782050000 1.2748930000 0.2588400000 0.0000030000 1.7334200000 0.0083210000 109410880 0 1787170816 3.9710135460 4.0073628426 4.0042414665 457 18.2400000000 0.0117140664 0.0106513001 0.0160688832 0.0147531654 5.1929760000 1.2698760000 0.2728560000 0.1451760000 1.7488930000 1.7534310000 109412554 0 1784266752 3.9711029530 4.0103216171 4.0089359283 458 18.2800000000 0.0116774654 0.0106535407 0.0160688832 0.0147422763 3.2872190000 1.2715690000 0.2714170000 0.0000040000 1.7332390000 0.0082040000 109414228 0 1785909248 3.9722199440 4.0110239983 4.0151586533 459 18.3200000000 0.0116615687 0.0106557368 0.0160688832 0.0147275552 3.4321940000 1.2753180000 0.2598800000 0.1437170000 1.7421800000 0.0083650000 109415902 0 1787686912 3.9745764732 4.0111703873 4.0212550163 460 18.3600000000 0.0115475003 0.0106576754 0.0160688832 0.0147133099 3.2789370000 1.2641450000 0.2720420000 0.0000030000 1.7318320000 0.0082060000 109417576 0 1783869440 3.9760158062 4.0147461891 4.0277657509 461 18.4000000000 0.0116621712 0.0106598544 0.0160688832 0.0146985931 5.1651120000 1.2721160000 0.2614690000 0.1433700000 1.7334780000 1.7519360000 109419250 0 1785393152 3.9768002033 4.0146522522 4.0350093842 462 18.4400000000 0.0115428865 0.0106617657 0.0160688832 0.0146832439 3.2777970000 1.2720810000 0.2588970000 0.0000020000 1.7357960000 0.0083330000 109420924 0 1787297792 3.9801564217 4.0150966644 4.0427122116 463 18.4800000000 0.0115412036 0.0106636651 0.0160688832 0.0146705538 3.4244440000 1.2664180000 0.2599160000 0.1427500000 1.7443860000 0.0082080000 109422598 0 1784266752 3.9807569981 4.0173745155 4.0507774353 464 18.5200000000 0.0115517955 0.0106655792 0.0160688832 0.0146575826 3.2728940000 1.2633100000 0.2609330000 0.0000030000 1.7375820000 0.0082630000 109424272 0 1785774080 3.9814383984 4.0194239616 4.0598945618 465 18.5600000000 0.0114884805 0.0106673489 0.0160688832 0.0146461867 5.1574890000 1.2701270000 0.2593410000 0.1414860000 1.7332730000 1.7505190000 109425946 0 1787678720 3.9854381084 4.0258960724 4.0794296265 466 18.6000000000 0.0114824707 0.0106690981 0.0160688832 0.0146315622 3.2767510000 1.2676620000 0.2721520000 0.0000030000 1.7260210000 0.0081930000 109427620 0 1784156160 3.9881479740 4.0298113823 4.0898013115 467 18.6400000000 0.0115997111 0.0106710908 0.0160688832 0.0146167052 3.4026930000 1.2659630000 0.2604010000 0.1407300000 1.7245140000 0.0081960000 109429294 0 1785774080 3.9909000397 4.0309062004 4.1007924080 468 18.6800000000 0.0115783345 0.0106730294 0.0160688832 0.0146035530 3.2553250000 1.2667550000 0.2598810000 0.0000030000 1.7176620000 0.0082110000 109430968 0 1787576320 3.9929113388 4.0356931686 4.1118869781 469 18.7200000000 0.0115677612 0.0106749371 0.0160688832 0.0145926356 5.1406660000 1.2685540000 0.2711790000 0.1398470000 1.7205280000 1.7377400000 109432642 0 1784918016 3.9943959713 4.0389823914 4.1234474182 470 18.7600000000 0.0116844624 0.0106770850 0.0160688832 0.0145861435 3.2567070000 1.2683350000 0.2608770000 0.0000030000 1.7165600000 0.0082000000 109434316 0 1786408960 3.9964358807 4.0442490578 4.1352491379 471 18.8000000000 0.0116543518 0.0106791599 0.0160688832 0.0145793108 3.4030660000 1.2620340000 0.2637670000 0.1393520000 1.7268650000 0.0082180000 109435990 0 1785647104 3.9978234768 4.0500278473 4.1476597786 472 18.8400000000 0.0115797007 0.0106810678 0.0160688832 0.0145646912 3.1976290000 1.2644790000 0.2147550000 0.0000030000 1.7073490000 0.0082360000 109437664 0 1787424768 4.0010533333 4.0561871529 4.1595025063 473 18.8800000000 0.0116624627 0.0106831427 0.0160688832 0.0145494655 5.0957310000 1.2705340000 0.2707890000 0.1378040000 1.6986280000 1.7151040000 109439338 0 1785139200 4.0037155151 4.0637979507 4.1714110374 474 18.9200000000 0.0117099378 0.0106853089 0.0160688832 0.0145380011 3.1853480000 1.2715490000 0.2118870000 0.0000030000 1.6909120000 0.0082420000 109441012 0 1786679296 4.0070238113 4.0701122284 4.1826391220 475 18.9600000000 0.0116005568 0.0106872357 0.0160688832 0.0145299369 3.3666010000 1.2631760000 0.2587200000 0.1369000000 1.6967360000 0.0081960000 109442686 0 1784393728 4.0106778145 4.0748620033 4.1953268051 476 19.0000000000 0.0116841746 0.0106893301 0.0160688832 0.0145202610 3.1766330000 1.2641920000 0.2125590000 0.0000030000 1.6887980000 0.0083030000 109444360 0 1786044416 4.0140581131 4.0777244568 4.2073268890 477 19.0400000000 0.0117842983 0.0106916257 0.0160688832 0.0145073859 5.1195400000 1.2715270000 0.3191310000 0.1357600000 1.6860490000 1.7041440000 109446034 0 1787940864 4.0155525208 4.0845451355 4.2191596031 478 19.0800000000 0.0116416439 0.0106936132 0.0160688832 0.0144945803 3.2239030000 1.2720970000 0.2603070000 0.0000030000 1.6804290000 0.0082750000 109447708 0 1785180160 4.0192770958 4.0917882919 4.2303056717 479 19.1200000000 0.0118392799 0.0106960050 0.0160688832 0.0144843613 3.3466300000 1.2641840000 0.2599270000 0.1348440000 1.6764690000 0.0081990000 109449382 0 1786662912 4.0227632523 4.0952858925 4.2422089577 480 19.1600000000 0.0118077034 0.0106983210 0.0160688832 0.0144754128 3.2251620000 1.2642590000 0.2611640000 0.0000030000 1.6885090000 0.0082640000 109451056 0 1784774656 4.0265407562 4.1000761986 4.2533512115 481 19.2000000000 0.0117096566 0.0107004236 0.0160688832 0.0144618480 5.0153560000 1.2776680000 0.2631650000 0.1338430000 1.6614610000 1.6763040000 109452730 0 1786171392 4.0277194977 4.1100912094 4.2636265755 482 19.2400000000 0.0117255813 0.0107025504 0.0160688832 0.0144599558 3.2005610000 1.2743770000 0.2580790000 0.0000030000 1.6569410000 0.0082880000 109454404 0 1785647104 4.0315928459 4.1144571304 4.2752175331 483 19.2800000000 0.0117435632 0.0107047057 0.0160688832 0.0144615661 3.2835130000 1.2655670000 0.2131290000 0.1330180000 1.6606750000 0.0082450000 109456078 0 1787297792 4.0341248512 4.1151413918 4.2867283821 484 19.3200000000 0.0117507689 0.0107068670 0.0160688832 0.0144595614 3.1778430000 1.2604440000 0.2595930000 0.0000020000 1.6467520000 0.0081860000 109457752 0 1783996416 4.0376977921 4.1164526939 4.2979011536 485 19.3600000000 0.0116593726 0.0107088310 0.0160688832 0.0144472245 5.0179370000 1.2688580000 0.3149450000 0.1322260000 1.6408070000 1.6581850000 109459426 0 1785663488 4.0397248268 4.1199631691 4.3090658188 486 19.4000000000 0.0117074456 0.0107108857 0.0160688832 0.0144323240 3.2339500000 1.2718210000 0.3148480000 0.0000030000 1.6361090000 0.0082650000 109461100 0 1787449344 4.0427079201 4.1268911362 4.3191952705 487 19.4400000000 0.0116759241 0.0107128673 0.0160688832 0.0144176653 3.3086130000 1.2663140000 0.2607470000 0.1313850000 1.6390100000 0.0082280000 109462774 0 1784909824 4.0430707932 4.1309189796 4.3309397697 488 19.4800000000 0.0116889970 0.0107148676 0.0160688832 0.0144031750 3.1545150000 1.2655320000 0.2469560000 0.0000030000 1.6307780000 0.0083140000 109464448 0 1786425344 4.0451774597 4.1336522102 4.3419795036 489 19.5200000000 0.0117494147 0.0107169832 0.0160688832 0.0143890360 4.9250900000 1.2690660000 0.2603790000 0.1304420000 1.6225730000 1.6396890000 109466122 0 1785647104 4.0458469391 4.1413969994 4.3525910378 490 19.5600000000 0.0118453307 0.0107192860 0.0160688832 0.0143749797 3.1704970000 1.2690210000 0.2722900000 0.0000020000 1.6178800000 0.0083120000 109467796 0 1787060224 4.0461940765 4.1468491554 4.3633537292 491 19.6000000000 0.0116762780 0.0107212350 0.0160688832 0.0143606512 3.2835020000 1.2649430000 0.2589580000 0.1301980000 1.6181570000 0.0081970000 109469470 0 1784393728 4.0490846634 4.1528601646 4.3736376762 492 19.6400000000 0.0119162202 0.0107236639 0.0160688832 0.0143460804 3.1805590000 1.2644070000 0.2939650000 0.0000040000 1.6110210000 0.0082620000 109471144 0 1785917440 4.0492401123 4.1574621201 4.3839340210 493 19.6800000000 0.0118093481 0.0107258661 0.0160688832 0.0143318690 4.9043950000 1.2624520000 0.2741900000 0.1288050000 1.6090970000 1.6269140000 109472818 0 1787805696 4.0498218536 4.1599397659 4.3948292732 494 19.7200000000 0.0117429746 0.0107279250 0.0160688832 0.0143173430 3.1560060000 1.2636240000 0.2763470000 0.0000020000 1.6047410000 0.0082110000 109474492 0 1784791040 4.0499906540 4.1609892845 4.4060573578 495 19.7600000000 0.0118072582 0.0107301055 0.0160688832 0.0143040139 3.2677700000 1.2657270000 0.2598560000 0.1280320000 1.6028640000 0.0082120000 109476166 0 1786171392 4.0506873131 4.1658816338 4.4172053337 496 19.8000000000 0.0118116727 0.0107322861 0.0160688832 0.0142913614 3.1393370000 1.2677760000 0.2608650000 0.0000030000 1.5994750000 0.0082630000 109477840 0 1785688064 4.0507345200 4.1726160049 4.4277095795 497 19.8400000000 0.0117736906 0.0107343814 0.0160688832 0.0142792798 4.8823220000 1.2661060000 0.2705850000 0.1273560000 1.6007950000 1.6145040000 109479514 0 1787068416 4.0506167412 4.1787595749 4.4387063980 498 19.8800000000 0.0118550016 0.0107366317 0.0160688832 0.0142703885 3.0835470000 1.2629390000 0.2126140000 0.0000030000 1.5967230000 0.0082800000 109481188 0 1784901632 4.0492973328 4.1857023239 4.4494676590 499 19.9200000000 0.0118844612 0.0107389319 0.0160688832 0.0142623179 3.2170570000 1.2658060000 0.2242140000 0.1264670000 1.5892430000 0.0083430000 109482862 0 1786535936 4.0483727455 4.1919960976 4.4611325264 500 19.9600000000 0.0118159205 0.0107410859 0.0160688832 0.0142524300 3.1264240000 1.2722810000 0.2583120000 0.0000030000 1.5844750000 0.0083520000 109484536 0 1785028608 4.0473046303 4.1938047409 4.4722886086 501 20.0000000000 0.0117178131 0.0107430355 0.0160688832 0.0142434936 4.8347430000 1.2635930000 0.2604220000 0.1260150000 1.5850770000 1.5966270000 109486210 0 1786425344 4.0458045006 4.1966648102 4.4831204414 502 20.0400000000 0.0117792124 0.0107450996 0.0160688832 0.0142340958 3.0647670000 1.2630410000 0.2126590000 0.0000030000 1.5777710000 0.0081960000 109487884 0 1785774080 4.0443797112 4.2014694214 4.4941878319 503 20.0800000000 0.0118597094 0.0107473155 0.0160688832 0.0142221949 3.2246110000 1.2631710000 0.2585670000 0.1249240000 1.5665850000 0.0083120000 109489558 0 1787187200 4.0421667099 4.2080583572 4.5049934387 504 20.1200000000 0.0117577622 0.0107493203 0.0160688832 0.0142080911 3.1036660000 1.2615520000 0.2662420000 0.0000030000 1.5645450000 0.0082010000 109491232 0 1784520704 4.0395183563 4.2129969597 4.5158758163 505 20.1600000000 0.0118516311 0.0107515031 0.0160688832 0.0141942462 4.8002530000 1.2659670000 0.2604260000 0.1243070000 1.5608030000 1.5857210000 109492906 0 1786044416 4.0379748344 4.2194819450 4.5265007019 506 20.2000000000 0.0117774541 0.0107535307 0.0160688832 0.0141834747 3.1091020000 1.2656850000 0.2741650000 0.0000030000 1.5579060000 0.0082630000 109494580 0 1787957248 4.0359935760 4.2285594940 4.5364718437 507 20.2400000000 0.0117246313 0.0107554461 0.0160688832 0.0141801737 3.2177670000 1.2768520000 0.2500700000 0.1238090000 1.5556930000 0.0082920000 109496254 0 1784561664 4.0331306458 4.2335996628 4.5469522476 508 20.2800000000 0.0117402812 0.0107573847 0.0160688832 0.0141787749 3.0928030000 1.2651600000 0.2610300000 0.0000030000 1.5552870000 0.0082500000 109497928 0 1786155008 4.0309147835 4.2382502556 4.5570678711 509 20.3200000000 0.0117535284 0.0107593418 0.0160688832 0.0141902160 4.7648210000 1.2677730000 0.2507220000 0.1230710000 1.5480470000 1.5721380000 109499602 0 1787949056 4.0282912254 4.2448935509 4.5666208267 510 20.3600000000 0.0118173566 0.0107614163 0.0160688832 0.0141915443 3.0818400000 1.2643880000 0.2614950000 0.0000030000 1.5446940000 0.0082080000 109501276 0 1785028608 4.0243635178 4.2495489120 4.5760712624 511 20.4000000000 0.0118050603 0.0107634587 0.0160688832 0.0141898785 3.2095030000 1.2709510000 0.2618060000 0.1224950000 1.5428530000 0.0083320000 109502950 0 1786408960 4.0223093033 4.2543654442 4.5847964287 512 20.4400000000 0.0118203210 0.0107655229 0.0160688832 0.0141954066 3.1010370000 1.2678140000 0.2740430000 0.0000030000 1.5478820000 0.0082250000 109504624 0 1784885248 4.0219626427 4.2609357834 4.5927896500 513 20.4800000000 0.0118286908 0.0107675953 0.0160688832 0.0141962258 4.7584530000 1.2664660000 0.2698990000 0.1219180000 1.5388490000 1.5582190000 109547258 0 1786535936 4.0203137398 4.2651753426 4.6010651588 514 20.5200000000 0.0118579064 0.0107697166 0.0160688832 0.0141996398 3.0797840000 1.2698180000 0.2607210000 0.0000040000 1.5378590000 0.0082990000 109632900 0 1784377344 4.0189390182 4.2673807144 4.6095542908 515 20.5600000000 0.0117798122 0.0107716779 0.0160688832 0.0142056129 3.2069240000 1.2678400000 0.2604330000 0.1216360000 1.5456630000 0.0082530000 109634574 0 1786044416 4.0185666084 4.2691783905 4.6166319847 516 20.6000000000 0.0117939124 0.0107736590 0.0160688832 0.0142205317 3.0817500000 1.2720240000 0.2618360000 0.0000040000 1.5364770000 0.0082130000 109636248 0 1787957248 4.0185890198 4.2747879028 4.6238327026 517 20.6400000000 0.0118509512 0.0107757427 0.0160688832 0.0142347003 4.7468160000 1.2721920000 0.2604470000 0.1212570000 1.5356760000 1.5540790000 109637922 0 1785163776 4.0188093185 4.2784500122 4.6304020882 518 20.6800000000 0.0118355686 0.0107777887 0.0160688832 0.0142530799 3.0849970000 1.2748660000 0.2604600000 0.0000050000 1.5381480000 0.0083210000 109639596 0 1786781696 4.0189094543 4.2815093994 4.6368789673 519 20.7200000000 0.0118441526 0.0107798434 0.0160688832 0.0142720913 3.2182940000 1.2716080000 0.2709590000 0.1211410000 1.5431120000 0.0082200000 109641270 0 1784791040 4.0208344460 4.2852602005 4.6425790787 520 20.7600000000 0.0118028438 0.0107818107 0.0160688832 0.0143003330 3.0310140000 1.2671900000 0.2125780000 0.0000050000 1.5398710000 0.0082550000 109642944 0 1786408960 4.0220489502 4.2881860733 4.6481080055 521 20.8000000000 0.0117465453 0.0107836624 0.0160688832 0.0143252408 4.7709400000 1.2702760000 0.2759740000 0.1210450000 1.5416040000 1.5588960000 109644618 0 1785647104 4.0239496231 4.2888011932 4.6534442902 522 20.8400000000 0.0118171908 0.0107856423 0.0160688832 0.0143530214 3.0998970000 1.2688380000 0.2702390000 0.0000050000 1.5494010000 0.0081990000 109646292 0 1787297792 4.0253477097 4.2891020775 4.6586413383 523 20.8800000000 0.0117881540 0.0107875592 0.0160688832 0.0143823506 3.2055390000 1.2685760000 0.2592550000 0.1210060000 1.5452750000 0.0082020000 109647966 0 1784885248 4.0274515152 4.2888598442 4.6631679535 524 20.9200000000 0.0117982952 0.0107894881 0.0160688832 0.0144165472 3.0977590000 1.2757760000 0.2611280000 0.0000040000 1.5491940000 0.0083650000 109649640 0 1786408960 4.0298843384 4.2923426628 4.6673302650 525 20.9600000000 0.0118371565 0.0107914836 0.0160688832 0.0144337216 4.7391790000 1.2752580000 0.2128690000 0.1232390000 1.5557480000 1.5688920000 109651314 0 1785036800 4.0325632095 4.2939629555 4.6712360382 526 21.0000000000 0.0118432706 0.0107934832 0.0160688832 0.0144451924 3.0890570000 1.2736360000 0.2475070000 0.0000040000 1.5558530000 0.0085150000 109652988 0 1786417152 4.0355281830 4.2933988571 4.6749501228 527 21.0400000000 0.0118953735 0.0107955741 0.0160688832 0.0144620433 3.2223380000 1.2693290000 0.2688900000 0.1213320000 1.5513410000 0.0082460000 109654662 0 1785655296 4.0382571220 4.2949624062 4.6784501076 528 21.0800000000 0.0119594997 0.0107977785 0.0160688832 0.0144724353 3.1066200000 1.2729190000 0.2695840000 0.0000060000 1.5526970000 0.0082540000 109656336 0 1787297792 4.0417613983 4.2966175079 4.6814465523 529 21.1200000000 0.0119972322 0.0108000459 0.0160688832 0.0144746990 4.7932400000 1.2696380000 0.2681020000 0.1215120000 1.5601820000 1.5705740000 109658010 0 1784885248 4.0443372726 4.2967061996 4.6844229698 530 21.1600000000 0.0120421229 0.0108023894 0.0160688832 0.0144799090 3.0975900000 1.2731780000 0.2571360000 0.0000040000 1.5558390000 0.0082370000 109659684 0 1786408960 4.0475869179 4.2978844643 4.6871528625 531 21.2000000000 0.0120488489 0.0108047368 0.0160688832 0.0144903914 3.2329330000 1.2756370000 0.2687730000 0.1218940000 1.5551390000 0.0082740000 109661358 0 1785647104 4.0513763428 4.2981190681 4.6897392273 532 21.2400000000 0.0120147681 0.0108070113 0.0160688832 0.0145058210 3.1128370000 1.2699870000 0.2687760000 0.0000050000 1.5625650000 0.0082460000 109663032 0 1787170816 4.0550003052 4.2974338531 4.6920223236 533 21.2800000000 0.0120097632 0.0108092679 0.0160688832 0.0145244407 4.8442700000 1.2741810000 0.3045550000 0.1222730000 1.5581440000 1.5818120000 109664706 0 1784664064 4.0591487885 4.2977385521 4.6942381859 534 21.3200000000 0.0120177977 0.0108115310 0.0160688832 0.0145414468 3.1159770000 1.2750340000 0.2694360000 0.0000050000 1.5600610000 0.0081850000 109666380 0 1786171392 4.0632295609 4.2977390289 4.6964588165 535 21.3600000000 0.0120305587 0.0108138096 0.0160688832 0.0145587772 3.2427510000 1.2776680000 0.2702390000 0.1228430000 1.5603890000 0.0082470000 109668054 0 1785663488 4.0669898987 4.2982139587 4.6987824440 536 21.4000000000 0.0120879039 0.0108161866 0.0160688832 0.0145762341 3.1559970000 1.2713070000 0.3043130000 0.0000050000 1.5688210000 0.0081790000 109669728 0 1787195392 4.0707774162 4.2988009453 4.7009191513 537 21.4400000000 0.0121503500 0.0108186711 0.0160688832 0.0145954820 4.7683570000 1.2757120000 0.2127340000 0.1232380000 1.5648500000 1.5885580000 109671402 0 1784393728 4.0752587318 4.2994532585 4.7031688690 538 21.4800000000 0.0121393483 0.0108211259 0.0160688832 0.0146045875 3.1527120000 1.2719430000 0.3034100000 0.0000040000 1.5657380000 0.0081750000 109673076 0 1785917440 4.0800042152 4.3003864288 4.7051033974 539 21.5200000000 0.0122161368 0.0108237140 0.0160688832 0.0146148760 3.2547670000 1.2762790000 0.2744650000 0.1239720000 1.5685230000 0.0081870000 109674750 0 1787695104 4.0849957466 4.3016538620 4.7067427635 540 21.5600000000 0.0121143814 0.0108261042 0.0160688832 0.0146168218 3.1114960000 1.2744850000 0.2570820000 0.0000040000 1.5683370000 0.0082730000 109676424 0 1785028608 4.0888695717 4.3019156456 4.7089753151 541 21.6000000000 0.0122295516 0.0108286983 0.0160688832 0.0146204673 4.8348700000 1.2804240000 0.2678140000 0.1243840000 1.5707130000 1.5882960000 109678098 0 1786789888 4.0932989120 4.3021044731 4.7108058929 542 21.6400000000 0.0122705288 0.0108313585 0.0160688832 0.0146281508 3.1257180000 1.2823780000 0.2578680000 0.0000050000 1.5739740000 0.0082200000 109679772 0 1784377344 4.0970396996 4.3035311699 4.7127442360 543 21.6800000000 0.0122037353 0.0108338859 0.0160688832 0.0146446820 3.2465050000 1.2695590000 0.2583350000 0.1252820000 1.5818150000 0.0081780000 109681446 0 1785901056 4.1009945869 4.3042244911 4.7148466110 544 21.7200000000 0.0122318454 0.0108364557 0.0160688832 0.0146592810 3.1190020000 1.2731180000 0.2577180000 0.0000040000 1.5767090000 0.0081810000 109683120 0 1787695104 4.1040477753 4.3048162460 4.7170200348 545 21.7600000000 0.0122736571 0.0108390928 0.0160688832 0.0146737147 4.8883280000 1.2806720000 0.3038900000 0.1260300000 1.5784000000 1.5960310000 109684794 0 1784655872 4.1083059311 4.3066754341 4.7191843987 546 21.8000000000 0.0123642636 0.0108418861 0.0160688832 0.0147496765 3.0840500000 1.2805390000 0.2134020000 0.0000050000 1.5786100000 0.0081770000 109686468 0 1786417152 4.1139822006 4.3079633713 4.7236180305 547 21.8400000000 0.0123505257 0.0108446442 0.0160688832 0.0147577886 3.2546110000 1.2733240000 0.2573610000 0.1270190000 1.5853190000 0.0082600000 109688142 0 1785647104 4.1175971031 4.3087868690 4.7258734703 548 21.8800000000 0.0123095671 0.0108473174 0.0160688832 0.0147708450 3.1254090000 1.2741040000 0.2578910000 0.0000040000 1.5818170000 0.0081890000 109689816 0 1787043840 4.1217393875 4.3106093407 4.7276840210 549 21.9200000000 0.0123474393 0.0108500498 0.0160688832 0.0147916787 4.8169410000 1.2728660000 0.2177280000 0.1277590000 1.5954090000 1.5999190000 109691490 0 1783742464 4.1252326965 4.3123769760 4.7299065590 550 21.9600000000 0.0123138279 0.0108527113 0.0160688832 0.0148087092 3.0848740000 1.2711890000 0.2127090000 0.0000050000 1.5894320000 0.0082710000 109693164 0 1785266176 4.1305737495 4.3133549690 4.7314410210 551 22.0000000000 0.0122028096 0.0108551615 0.0160688832 0.0148357728 3.2762920000 1.2773180000 0.2695900000 0.1285150000 1.5892720000 0.0082030000 109694838 0 1787076608 4.1337747574 4.3156976700 4.7330937386 552 22.0400000000 0.0122418553 0.0108576737 0.0160688832 0.0148468853 3.0887500000 1.2801940000 0.2115470000 0.0000040000 1.5854770000 0.0081620000 109696512 0 1784631296 4.1384639740 4.3181986809 4.7344985008 553 22.0800000000 0.0122021120 0.0108601048 0.0160688832 0.0148435884 4.8102550000 1.2754620000 0.2000990000 0.1290030000 1.5967010000 1.6057040000 109698186 0 1786281984 4.1430525780 4.3180527687 4.7359943390 554 22.1200000000 0.0122314841 0.0108625802 0.0160688832 0.0148370608 3.0910780000 1.2733000000 0.2100240000 0.0000040000 1.5952860000 0.0082390000 109699860 0 1785569280 4.1463146210 4.3172545433 4.7380743027 555 22.1600000000 0.0121701509 0.0108649362 0.0160688832 0.0148295242 3.2195270000 1.2778500000 0.2093970000 0.1299120000 1.5907880000 0.0082060000 109701534 0 1784545280 4.1524500847 4.3190855980 4.7391405106 556 22.2000000000 0.0120731099 0.0108671092 0.0160688832 0.0148283536 3.0800190000 1.2766080000 0.1993970000 0.0000040000 1.5924800000 0.0082020000 109703208 0 1785909248 4.1576194763 4.3219723701 4.7404947281 557 22.2400000000 0.0121290274 0.0108693748 0.0160688832 0.0148246322 4.8184110000 1.2717760000 0.1993340000 0.1303450000 1.5987790000 1.6148060000 109704882 0 1787932672 4.1622095108 4.3237681389 4.7420320511 558 22.2800000000 0.0120364549 0.0108714663 0.0160688832 0.0148241596 3.0848060000 1.2734170000 0.2006650000 0.0000040000 1.5990880000 0.0082740000 109706556 0 1784537088 4.1675124168 4.3265762329 4.7435669899 559 22.3200000000 0.0120501304 0.0108735748 0.0160688832 0.0148211924 3.2210940000 1.2748540000 0.2110970000 0.1305990000 1.5928840000 0.0082630000 109708230 0 1785901056 4.1730136871 4.3292126656 4.7450065613 560 22.3600000000 0.0120193195 0.0108756208 0.0160688832 0.0148171029 3.1310560000 1.2753080000 0.2447930000 0.0000040000 1.5993640000 0.0082280000 109709904 0 1787932672 4.1769208908 4.3300261497 4.7475667000 561 22.4000000000 0.0120459897 0.0108777070 0.0160688832 0.0148139243 4.8209250000 1.2739300000 0.1994790000 0.1309870000 1.5938880000 1.6191380000 109711578 0 1784012800 4.1812071800 4.3323864937 4.7492637634 562 22.4400000000 0.0120060425 0.0108797147 0.0160688832 0.0148119941 3.0742360000 1.2710020000 0.1998030000 0.0000050000 1.5917770000 0.0081480000 109713252 0 1785520128 4.1865720749 4.3356637955 4.7504429817 563 22.4800000000 0.0120030856 0.0108817101 0.0160688832 0.0148052339 3.2256020000 1.2822330000 0.2093350000 0.1310550000 1.5913330000 0.0082220000 109714926 0 1787441152 4.1927685738 4.3392214775 4.7510495186 564 22.5200000000 0.0119905537 0.0108836761 0.0160688832 0.0147957365 3.0827310000 1.2758000000 0.1982340000 0.0000050000 1.5971060000 0.0081860000 109716600 0 1784410112 4.1970062256 4.3409118652 4.7527461052 565 22.5600000000 0.0120178256 0.0108856834 0.0160688832 0.0147860584 4.8533710000 1.2700520000 0.2439920000 0.1312230000 1.5884320000 1.6161800000 109718274 0 1785909248 4.2006249428 4.3419370651 4.7543663979 566 22.6000000000 0.0120169036 0.0108876821 0.0160688832 0.0147771305 3.0726620000 1.2750930000 0.1982360000 0.0000050000 1.5878150000 0.0081140000 109719948 0 1787813888 4.2057461739 4.3451280594 4.7556838989 567 22.6400000000 0.0120260352 0.0108896897 0.0160688832 0.0147660419 3.2299980000 1.2854830000 0.2146810000 0.1314170000 1.5867970000 0.0081390000 109721622 0 1784139776 4.2104291916 4.3472542763 4.7567505836 568 22.6800000000 0.0120952427 0.0108918122 0.0160688832 0.0147564534 3.0821750000 1.2732580000 0.2060580000 0.0000050000 1.5913290000 0.0081080000 109723296 0 1785647104 4.2146654129 4.3491292000 4.7582373619 569 22.7200000000 0.0121024773 0.0108939399 0.0160688832 0.0147454648 4.8474120000 1.2740540000 0.2432500000 0.1314530000 1.5855630000 1.6095520000 109724970 0 1787551744 4.2201809883 4.3506350517 4.7585210800 570 22.7600000000 0.0120983645 0.0108960529 0.0160688832 0.0147348309 3.0743930000 1.2805380000 0.1975130000 0.0000050000 1.5848580000 0.0081070000 109726644 0 1784520704 4.2242999077 4.3534226418 4.7594370842 571 22.8000000000 0.0121699059 0.0108982838 0.0160688832 0.0147229016 3.2494470000 1.2738790000 0.2427940000 0.1314620000 1.5897890000 0.0081040000 109728318 0 1785901056 4.2293972969 4.3561887741 4.7602109909 572 22.8400000000 0.0121008828 0.0109003863 0.0160688832 0.0147105622 3.0752120000 1.2733170000 0.2077860000 0.0000050000 1.5824940000 0.0081530000 109729992 0 1787822080 4.2352581024 4.3590645790 4.7598271370 573 22.8800000000 0.0121445954 0.0109025577 0.0160688832 0.0146991171 4.8439180000 1.2762160000 0.2417010000 0.1316350000 1.5835090000 1.6073260000 109731666 0 1783996416 4.2394094467 4.3612966537 4.7605824471 574 22.9200000000 0.0121681811 0.0109047626 0.0160688832 0.0146880836 3.0761790000 1.2756000000 0.2072420000 0.0000050000 1.5816060000 0.0081340000 109733340 0 1785520128 4.2437977791 4.3644509315 4.7607803345 575 22.9600000000 0.0121505074 0.0109069291 0.0160688832 0.0146754670 3.2489940000 1.2782880000 0.2414830000 0.1316060000 1.5861180000 0.0080320000 109735014 0 1787449344 4.2477946281 4.3672528267 4.7614250183 576 23.0000000000 0.0121772997 0.0109091346 0.0160688832 0.0146627933 3.0777420000 1.2731530000 0.2068850000 0.0000050000 1.5860000000 0.0081270000 109736688 0 1784512512 4.2515516281 4.3706755638 4.7619557381 577 23.0400000000 0.0122328131 0.0109114287 0.0160688832 0.0146500823 4.8424280000 1.2750760000 0.2463270000 0.1318250000 1.5794030000 1.6063330000 109738362 0 1785901056 4.2553672791 4.3742833138 4.7623686790 578 23.0800000000 0.0122610759 0.0109137637 0.0160688832 0.0146375591 3.0710780000 1.2772940000 0.1968160000 0.0000050000 1.5853530000 0.0081110000 109740036 0 1787695104 4.2582988739 4.3760957718 4.7627577782 579 23.1200000000 0.0122009153 0.0109159868 0.0160688832 0.0146254262 3.1890590000 1.2707510000 0.1964180000 0.1317840000 1.5784870000 0.0081030000 109741710 0 1784504320 4.2621736526 4.3796291351 4.7623705864 580 23.1600000000 0.0123004634 0.0109183738 0.0160688832 0.0146133796 3.0735660000 1.2769590000 0.2073770000 0.0000050000 1.5776780000 0.0080960000 109743384 0 1786028032 4.2665567398 4.3855028152 4.7622981071 581 23.2000000000 0.0122807212 0.0109207186 0.0160688832 0.0146008708 4.9048450000 1.2707250000 0.3080930000 0.1315810000 1.5848270000 1.6060940000 109745058 0 1787932672 4.2701978683 4.3900876045 4.7620944977 582 23.2400000000 0.0123240380 0.0109231298 0.0160688832 0.0145883780 3.1070020000 1.2732830000 0.2409540000 0.0000030000 1.5812590000 0.0080040000 109746732 0 1784647680 4.2727131844 4.3935766220 4.7621250153 583 23.2800000000 0.0123576066 0.0109255904 0.0160688832 0.0145759676 3.2306490000 1.2753140000 0.2383020000 0.1317140000 1.5737300000 0.0080560000 109748406 0 1786155008 4.2758145332 4.3986430168 4.7622394562 584 23.3200000000 0.0123217572 0.0109279810 0.0160688832 0.0145646299 3.0695630000 1.2796560000 0.2063240000 0.0000030000 1.5719870000 0.0080470000 109750080 0 1788059648 4.2783179283 4.4015078545 4.7615542412 585 23.3600000000 0.0123565663 0.0109304231 0.0160688832 0.0145527999 4.7787760000 1.2734970000 0.1945320000 0.1314880000 1.5759630000 1.5997430000 109751754 0 1784401920 4.2809329033 4.4036312103 4.7611455917 586 23.4000000000 0.0123695442 0.0109328789 0.0160688832 0.0145408265 3.0653670000 1.2742700000 0.2049180000 0.0000030000 1.5746310000 0.0079700000 109753428 0 1785790464 4.2832016945 4.4065713882 4.7611761093 587 23.4400000000 0.0123699065 0.0109353270 0.0160688832 0.0145284564 3.1800020000 1.2734700000 0.1954840000 0.1313220000 1.5681150000 0.0080380000 109755102 0 1787695104 4.2854843140 4.4098248482 4.7609229088 588 23.4800000000 0.0123651410 0.0109377587 0.0160688832 0.0145161842 3.0633220000 1.2731100000 0.2053080000 0.0000030000 1.5732320000 0.0080160000 109756776 0 1784918016 4.2876758575 4.4125890732 4.7609124184 589 23.5200000000 0.0123463748 0.0109401502 0.0160688832 0.0145039308 4.8239480000 1.2730220000 0.2495360000 0.1312150000 1.5654920000 1.6011270000 109758450 0 1786425344 4.2905173302 4.4153652191 4.7607631683 590 23.5600000000 0.0123823024 0.0109425945 0.0160688832 0.0144916456 3.1049940000 1.2778680000 0.2501260000 0.0000030000 1.5652630000 0.0080340000 109760124 0 1785409536 4.2922239304 4.4171710014 4.7611937523 591 23.6000000000 0.0123619251 0.0109449961 0.0160688832 0.0144794575 3.2396430000 1.2786210000 0.2495700000 0.1310310000 1.5687470000 0.0079960000 109761798 0 1787060224 4.2942152023 4.4199037552 4.7616734505 592 23.6400000000 0.0123196654 0.0109473182 0.0160688832 0.0144680281 3.0993400000 1.2727410000 0.2465480000 0.0000030000 1.5684660000 0.0080170000 109763472 0 1784901632 4.2971005440 4.4225964546 4.7611122131 593 23.6800000000 0.0122468481 0.0109495096 0.0160688832 0.0144594198 4.7951720000 1.2728950000 0.2382120000 0.1307520000 1.5570880000 1.5925470000 109765146 0 1786552320 4.3009610176 4.4259076118 4.7615628242 594 23.7200000000 0.0121790310 0.0109515795 0.0160688832 0.0144472409 3.0840970000 1.2772480000 0.2387820000 0.0000030000 1.5564010000 0.0079600000 109766820 0 1785688064 4.3020730019 4.4264416695 4.7623329163 595 23.7600000000 0.0121541517 0.0109536007 0.0160688832 0.0144353228 3.1895180000 1.2729690000 0.2197730000 0.1310550000 1.5540830000 0.0079670000 109768494 0 1787322368 4.3035855293 4.4283714294 4.7626018524 596 23.8000000000 0.0121100871 0.0109555411 0.0160688832 0.0144232633 3.0453650000 1.2769320000 0.2038810000 0.0000030000 1.5528930000 0.0079630000 109770168 0 1785012224 4.3048090935 4.4306936264 4.7634305954 597 23.8400000000 0.0121985432 0.0109576231 0.0160688832 0.0144114452 4.7911990000 1.2804570000 0.2480430000 0.1307150000 1.5487390000 1.5796520000 109771842 0 1786662912 4.3060193062 4.4328784943 4.7639403343 598 23.8800000000 0.0121659106 0.0109596437 0.0160688832 0.0144003223 3.0853750000 1.2793590000 0.2489830000 0.0000020000 1.5452790000 0.0079600000 109773516 0 1785028608 4.3066344261 4.4338927269 4.7648181915 599 23.9200000000 0.0120644895 0.0109614882 0.0160688832 0.0143903214 3.1695980000 1.2742910000 0.2045260000 0.1304930000 1.5486150000 0.0079620000 109775190 0 1786662912 4.3075661659 4.4356698990 4.7656702995 600 23.9600000000 0.0120619200 0.0109633222 0.0160688832 0.0143806769 3.0748490000 1.2752810000 0.2486480000 0.0000030000 1.5393480000 0.0079490000 109776864 0 1784664064 4.3076624870 4.4374065399 4.7665667534 601 24.0000000000 0.0119484635 0.0109649614 0.0160688832 0.0143719529 4.7106430000 1.2786460000 0.2018930000 0.1303280000 1.5322310000 1.5638600000 109778538 0 1786281984 4.3085989952 4.4409160614 4.7681984901 602 24.0400000000 0.0119070346 0.0109665263 0.0160688832 0.0143614234 3.0255620000 1.2734550000 0.2100790000 0.0000030000 1.5303170000 0.0080390000 109780212 0 1785536512 4.3092231750 4.4412727356 4.7688159943 603 24.0800000000 0.0118395044 0.0109679740 0.0160688832 0.0143511466 3.1963960000 1.2771500000 0.2466370000 0.1301030000 1.5308910000 0.0079590000 109781886 0 1787060224 4.3098320961 4.4423866272 4.7696199417 604 24.1200000000 0.0118816681 0.0109694868 0.0160688832 0.0143394601 3.0687790000 1.2821700000 0.2466600000 0.0000020000 1.5282060000 0.0080600000 109783560 0 1784877056 4.3106632233 4.4437160492 4.7703685760 605 24.1600000000 0.0118600111 0.0109709587 0.0160688832 0.0143277233 4.6962780000 1.2746530000 0.2026200000 0.1305750000 1.5283130000 1.5564580000 109785234 0 1786560512 4.3119387627 4.4481158257 4.7715735435 606 24.2000000000 0.0118153216 0.0109723520 0.0160688832 0.0143158794 3.0599490000 1.2739420000 0.2485840000 0.0000030000 1.5258820000 0.0079340000 109786908 0 1785782272 4.3125624657 4.4497070312 4.7725148201 607 24.2400000000 0.0117642898 0.0109736567 0.0160688832 0.0143043553 3.1810200000 1.2744730000 0.2459560000 0.1300790000 1.5187520000 0.0080410000 109788582 0 1787568128 4.3136544228 4.4513306618 4.7727322578 608 24.2800000000 0.0118407290 0.0109750828 0.0160688832 0.0142927396 3.0103730000 1.2791730000 0.2017810000 0.0000030000 1.5176570000 0.0080660000 109790256 0 1784647680 4.3141722679 4.4524154663 4.7736248970 609 24.3200000000 0.0117931003 0.0109764260 0.0160688832 0.0142812228 4.7348860000 1.2731220000 0.2598000000 0.1299630000 1.5195020000 1.5488310000 109791930 0 1786425344 4.3147101402 4.4536700249 4.7740998268 610 24.3600000000 0.0117561044 0.0109777042 0.0160688832 0.0142695708 3.0472470000 1.2733580000 0.2486020000 0.0000030000 1.5136380000 0.0079760000 109793604 0 1788059648 4.3152470589 4.4563951492 4.7744889259 611 24.4000000000 0.0117395772 0.0109789511 0.0160688832 0.0142578891 3.1799580000 1.2810780000 0.2448810000 0.1298450000 1.5123920000 0.0079220000 109795278 0 1784647680 4.3162150383 4.4587969780 4.7746820450 612 24.4400000000 0.0117453597 0.0109802034 0.0160688832 0.0142462369 3.0138770000 1.2732770000 0.2119940000 0.0000030000 1.5168250000 0.0079440000 109796952 0 1786298368 4.3158154488 4.4605989456 4.7758140564 613 24.4800000000 0.0117711956 0.0109814938 0.0160688832 0.0142348192 4.6602710000 1.2711800000 0.2040570000 0.1296770000 1.5068440000 1.5447780000 109798626 0 1785536512 4.3166527748 4.4631571770 4.7761387825 614 24.5200000000 0.0117770769 0.0109827895 0.0160688832 0.0142238246 2.9954850000 1.2750030000 0.2037530000 0.0000030000 1.5049700000 0.0080240000 109800300 0 1787060224 4.3163194656 4.4649491310 4.7771043777 615 24.5600000000 0.0117213782 0.0109839905 0.0160688832 0.0142131235 3.1368790000 1.2749980000 0.2193940000 0.1293690000 1.5013650000 0.0080210000 109801974 0 1784909824 4.3154506683 4.4676218033 4.7782578468 616 24.6000000000 0.0117695443 0.0109852657 0.0160688832 0.0142022192 3.0364250000 1.2745500000 0.2500780000 0.0000030000 1.4999420000 0.0081360000 109803648 0 1786433536 4.3146562576 4.4695773125 4.7795886993 617 24.6400000000 0.0117282094 0.0109864699 0.0160688832 0.0141909106 4.6985130000 1.2826780000 0.2591320000 0.1290720000 1.4961430000 1.5277170000 109805322 0 1785663488 4.3137640953 4.4715194702 4.7807884216 618 24.6800000000 0.0117315389 0.0109876755 0.0160688832 0.0141815526 3.0391590000 1.2809940000 0.2496390000 0.0000030000 1.4966870000 0.0080770000 109806996 0 1787297792 4.3129220009 4.4734072685 4.7821993828 619 24.7200000000 0.0116871577 0.0109888055 0.0160688832 0.0141724087 3.1703110000 1.2730500000 0.2597490000 0.1286380000 1.4970750000 0.0079580000 109808670 0 1784774656 4.3113055229 4.4761877060 4.7837152481 620 24.7600000000 0.0117160222 0.0109899784 0.0160688832 0.0141638708 3.0723830000 1.2763080000 0.2932730000 0.0000030000 1.4910700000 0.0079630000 109810344 0 1786155008 4.3099098206 4.4777970314 4.7849960327 621 24.8000000000 0.0117102722 0.0109911383 0.0160688832 0.0141560221 4.7110750000 1.2800700000 0.2939280000 0.1290710000 1.4861700000 1.5180690000 109812018 0 1788059648 4.3078622818 4.4796028137 4.7869110107 622 24.8400000000 0.0117021613 0.0109922814 0.0160688832 0.0141489208 3.0245720000 1.2737940000 0.2536840000 0.0000030000 1.4852130000 0.0081110000 109813692 0 1784139776 4.3059706688 4.4815750122 4.7891244888 623 24.8800000000 0.0117587037 0.0109935117 0.0160688832 0.0141445778 3.1413870000 1.2729450000 0.2478610000 0.1279470000 1.4808200000 0.0080590000 109815366 0 1785774080 4.3043756485 4.4849815369 4.7910327911 624 24.9200000000 0.0116888238 0.0109946259 0.0160688832 0.0141381636 3.0189280000 1.2796610000 0.2471000000 0.0000020000 1.4803170000 0.0079980000 109817040 0 1787678720 4.3032302856 4.4859294891 4.7927646637 625 24.9600000000 0.0116639631 0.0109956969 0.0160688832 0.0141313713 4.5960690000 1.2747210000 0.2040280000 0.1275600000 1.4820290000 1.5039050000 109818714 0 1784909824 4.3009428978 4.4883899689 4.7949666977 626 25.0000000000 0.0117234765 0.0109968595 0.0160688832 0.0141247766 3.0159540000 1.2765520000 0.2480140000 0.0000030000 1.4794510000 0.0080190000 109820388 0 1786535936 4.2987089157 4.4919395447 4.7970404625 627 25.0400000000 0.0117306979 0.0109980299 0.0160688832 0.0141222632 3.1324200000 1.2746450000 0.2485450000 0.1270260000 1.4702610000 0.0080930000 109822062 0 1785647104 4.2975406647 4.4953966141 4.7981357574 628 25.0800000000 0.0117524816 0.0109992312 0.0160688832 0.0141209395 3.0140540000 1.2771680000 0.2549350000 0.0000020000 1.4699890000 0.0081350000 109823736 0 1787297792 4.2956204414 4.4978942871 4.7997832298 629 25.1200000000 0.0116756111 0.0110003065 0.0160688832 0.0141231106 4.5668140000 1.2735030000 0.2057040000 0.1263030000 1.4627410000 1.4946730000 109825410 0 1784520704 4.2941842079 4.4999704361 4.8009567261 630 25.1600000000 0.0116923405 0.0110014050 0.0160688832 0.0141178277 3.0020250000 1.2758400000 0.2518550000 0.0000030000 1.4624260000 0.0080440000 109827084 0 1785901056 4.2904338837 4.5015268326 4.8035082817 631 25.2000000000 0.0117730591 0.0110026279 0.0160688832 0.0141122585 3.1308310000 1.2842140000 0.2510050000 0.1260350000 1.4575210000 0.0081260000 109828758 0 1787838464 4.2880711555 4.5039424896 4.8051199913 632 25.2400000000 0.0117217842 0.0110037658 0.0160688832 0.0141058339 2.9492140000 1.2714900000 0.2064430000 0.0000030000 1.4592800000 0.0081640000 109830432 0 1784774656 4.2847003937 4.5040020943 4.8078436852 633 25.2800000000 0.0116709955 0.0110048199 0.0160688832 0.0140974226 4.5370030000 1.2728870000 0.2071990000 0.1254190000 1.4540710000 1.4735790000 109832106 0 1786408960 4.2808938026 4.5055155754 4.8100466728 634 25.3200000000 0.0117206359 0.0110059489 0.0160688832 0.0140891211 3.0023030000 1.2817890000 0.2619020000 0.0000030000 1.4465930000 0.0081680000 109833780 0 1785155584 4.2772521973 4.5083155632 4.8126525879 635 25.3600000000 0.0117330654 0.0110070940 0.0160688832 0.0140816685 3.1105620000 1.2758240000 0.2480400000 0.1248850000 1.4498140000 0.0080960000 109835454 0 1786798080 4.2734255791 4.5105700493 4.8154921532 636 25.4000000000 0.0117210578 0.0110082166 0.0160688832 0.0140752792 2.9772130000 1.2744470000 0.2512180000 0.0000030000 1.4394120000 0.0081770000 109837128 0 1784164352 4.2698521614 4.5117402077 4.8178052902 637 25.4400000000 0.0116343172 0.0110091995 0.0160688832 0.0140687116 4.5054640000 1.2777850000 0.2068890000 0.1249330000 1.4352410000 1.4567490000 109838802 0 1785647104 4.2655768394 4.5127768517 4.8207178116 638 25.4800000000 0.0116313454 0.0110101746 0.0160688832 0.0140615364 2.9294680000 1.2744830000 0.2069560000 0.0000030000 1.4359230000 0.0081870000 109840476 0 1787678720 4.2604303360 4.5138664246 4.8242092133 639 25.5200000000 0.0115995826 0.0110110970 0.0160688832 0.0140543945 3.0478560000 1.2698830000 0.2173390000 0.1236010000 1.4249360000 0.0081440000 109842150 0 1784537088 4.2558465004 4.5141515732 4.8274650574 640 25.5600000000 0.0115967868 0.0110120122 0.0160688832 0.0140461113 2.9162440000 1.2799720000 0.2044570000 0.0000030000 1.4198470000 0.0081810000 109843824 0 1785901056 4.2509360313 4.5134162903 4.8310585022 641 25.6000000000 0.0116129639 0.0110129497 0.0160688832 0.0140381296 4.5512190000 1.2754500000 0.2957050000 0.1229820000 1.4183840000 1.4347590000 109845498 0 1787932672 4.2460126877 4.5135655403 4.8342900276 642 25.6400000000 0.0117017254 0.0110140225 0.0160688832 0.0140341981 2.9357640000 1.2734120000 0.2426620000 0.0000030000 1.4076090000 0.0081710000 109847172 0 1784504320 4.2418403625 4.5161275864 4.8372073174 643 25.6800000000 0.0116625205 0.0110150311 0.0160688832 0.0140316881 3.0235620000 1.2808090000 0.2082740000 0.1223710000 1.3999410000 0.0082750000 109848846 0 1786028032 4.2370996475 4.5172305107 4.8403091431 644 25.7200000000 0.0116422921 0.0110160051 0.0160688832 0.0140282159 2.9480060000 1.2811230000 0.2543010000 0.0000030000 1.4004750000 0.0082450000 109850520 0 1787932672 4.2327070236 4.5171442032 4.8431587219 645 25.7600000000 0.0116591183 0.0110170022 0.0160688832 0.0140223558 4.4338670000 1.2879810000 0.2197740000 0.1219430000 1.3863790000 1.4138770000 109852194 0 1783894016 4.2285580635 4.5190191269 4.8456830978 646 25.8000000000 0.0116395447 0.0110179659 0.0160688832 0.0140167313 2.9185600000 1.2711740000 0.2557230000 0.0000020000 1.3789920000 0.0085000000 109853868 0 1785401344 4.2242479324 4.5205779076 4.8485503197 647 25.8400000000 0.0116685536 0.0110189714 0.0160688832 0.0140106655 3.0433950000 1.2739120000 0.2558850000 0.1213110000 1.3801010000 0.0082540000 109855542 0 1787170816 4.2193946838 4.5208363533 4.8517003059 648 25.8800000000 0.0116227977 0.0110199032 0.0160688832 0.0140031345 2.8602020000 1.2756340000 0.2092200000 0.0000030000 1.3632380000 0.0081750000 109857216 0 1784504320 4.2149930000 4.5227560997 4.8543615341 649 25.9200000000 0.0115918145 0.0110207845 0.0160688832 0.0139953433 4.3971690000 1.2787090000 0.2681590000 0.1198550000 1.3545230000 1.3719340000 109858890 0 1786028032 4.2106013298 4.5245432854 4.8570775986 650 25.9600000000 0.0116661461 0.0110217773 0.0160688832 0.0139886732 2.8937480000 1.2731730000 0.2630530000 0.0000030000 1.3453780000 0.0082410000 109860564 0 1787932672 4.2063264847 4.5281114578 4.8595552444 651 26.0000000000 0.0116304159 0.0110227123 0.0160688832 0.0139875544 2.9962610000 1.2741210000 0.2571450000 0.1187940000 1.3340100000 0.0082530000 109862238 0 1784377344 4.2031211853 4.5300054550 4.8618044853 652 26.0400000000 0.0116098532 0.0110236128 0.0160688832 0.0139843963 2.8253770000 1.2767610000 0.2113730000 0.0000030000 1.3250030000 0.0081800000 109863912 0 1785901056 4.1993284225 4.5321469307 4.8637127876 653 26.0800000000 0.0116258776 0.0110245351 0.0160688832 0.0139830713 4.3061070000 1.2791030000 0.2563740000 0.1178050000 1.3178100000 1.3310660000 109865586 0 1787932672 4.1945676804 4.5337138176 4.8660278320 654 26.1200000000 0.0116240168 0.0110254517 0.0160688832 0.0139830388 2.8444450000 1.2713340000 0.2568580000 0.0000030000 1.3040350000 0.0082710000 109867260 0 1784631296 4.1901249886 4.5349049568 4.8683948517 655 26.1600000000 0.0115938550 0.0110263195 0.0160688832 0.0139787685 3.0060660000 1.2772370000 0.3033000000 0.1175800000 1.2957990000 0.0081940000 109868934 0 1786155008 4.1874585152 4.5383052826 4.8700833321 656 26.2000000000 0.0116493031 0.0110272692 0.0160688832 0.0139747483 2.7998040000 1.2697130000 0.2213330000 0.0000030000 1.2955030000 0.0082560000 109870608 0 1785323520 4.1775465012 4.5416169167 4.8739061356 657 26.2400000000 0.0116047626 0.0110281482 0.0160688832 0.0139724125 4.2390680000 1.2731760000 0.2675940000 0.1156140000 1.2799300000 1.2986410000 109872282 0 1783750656 4.1748170853 4.5419259071 4.8756132126 658 26.2800000000 0.0115170116 0.0110288911 0.0160688832 0.0139654008 3.1047030000 1.2859820000 0.5335970000 0.0000030000 1.2728460000 0.0083110000 109873956 0 1785139200 4.1713118553 4.5438127518 4.8772134781 659 26.3200000000 0.0115945423 0.0110297495 0.0160688832 0.0139610696 2.9398420000 1.2726980000 0.2674870000 0.1144610000 1.2722090000 0.0082020000 109875630 0 1787170816 4.1679744720 4.5476312637 4.8785953522 660 26.3600000000 0.0116481008 0.0110306864 0.0160688832 0.0139587133 2.9018930000 1.2710160000 0.3598770000 0.0000030000 1.2586770000 0.0083070000 109877304 0 1784266752 4.1639966965 4.5486044884 4.8801164627 661 26.4000000000 0.0115488525 0.0110314703 0.0160688832 0.0139571068 4.1843250000 1.2743010000 0.2727080000 0.1135510000 1.2517380000 1.2679590000 109878978 0 1785774080 4.1614685059 4.5523810387 4.8808774948 662 26.4400000000 0.0115684457 0.0110322814 0.0160688832 0.0139514685 2.8462420000 1.2707980000 0.3122190000 0.0000030000 1.2510190000 0.0082050000 109880652 0 1787678720 4.1589245796 4.5552840233 4.8816919327 663 26.4800000000 0.0113431420 0.0110327503 0.0160688832 0.0139481988 2.9064380000 1.2746580000 0.2667220000 0.1128710000 1.2398860000 0.0082670000 109882326 0 1784393728 4.1551737785 4.5548462868 4.8831834793 664 26.5200000000 0.0114146089 0.0110333254 0.0160688832 0.0139470000 2.8425670000 1.2743040000 0.3174730000 0.0000020000 1.2385350000 0.0082400000 109884000 0 1785774080 4.1527929306 4.5564460754 4.8841595650 665 26.5600000000 0.0114140464 0.0110338979 0.0160688832 0.0139452568 4.1502590000 1.2743420000 0.2666260000 0.1122500000 1.2341550000 1.2588660000 109885674 0 1787678720 4.1494932175 4.5586767197 4.8852996826 666 26.6000000000 0.0113376593 0.0110343540 0.0160688832 0.0139405057 2.8285400000 1.2719210000 0.3127220000 0.0000030000 1.2315760000 0.0081860000 109887348 0 1784393728 4.1467704773 4.5598173141 4.8862981796 667 26.6400000000 0.0114374999 0.0110349584 0.0160688832 0.0139354566 2.8976420000 1.2721570000 0.2658630000 0.1174770000 1.2298880000 0.0082150000 109889022 0 1785909248 4.1424694061 4.5617499352 4.8872952461 668 26.6800000000 0.0114804069 0.0110356252 0.0160688832 0.0139302547 2.8223720000 1.2721780000 0.3115380000 0.0000030000 1.2262750000 0.0082150000 109890696 0 1787703296 4.1383328438 4.5637202263 4.8883547783 669 26.7200000000 0.0113750910 0.0110361327 0.0160688832 0.0139264195 4.2135250000 1.2782950000 0.3588110000 0.1112160000 1.2215160000 1.2395420000 109892370 0 1783996416 4.1345024109 4.5654630661 4.8893256187 670 26.7600000000 0.0114747658 0.0110367873 0.0160688832 0.0139198821 2.8657120000 1.2700990000 0.3573190000 0.0000030000 1.2260420000 0.0082350000 109894044 0 1785393152 4.1299848557 4.5646476746 4.8905372620 671 26.8000000000 0.0114749875 0.0110374404 0.0160688832 0.0139149537 2.8703310000 1.2721860000 0.2569840000 0.1109130000 1.2179900000 0.0081750000 109895718 0 1787297792 4.1266913414 4.5639142990 4.8921036720 672 26.8400000000 0.0113697508 0.0110379349 0.0160688832 0.0139073399 2.8165710000 1.2755960000 0.3133680000 0.0000020000 1.2152380000 0.0082830000 109897392 0 1784283136 4.1226429939 4.5638055801 4.8935217857 673 26.8800000000 0.0114345057 0.0110385242 0.0160688832 0.0138982010 4.1306100000 1.3073460000 0.2553220000 0.1101460000 1.2149580000 1.2386830000 109899066 0 1785647104 4.1189346313 4.5638761520 4.8948445320 674 26.9200000000 0.0115468577 0.0110392784 0.0160688832 0.0138945153 2.7638570000 1.2702920000 0.2677480000 0.0000030000 1.2135570000 0.0081840000 109900740 0 1787678720 4.1147203445 4.5633502007 4.8963880539 675 26.9600000000 0.0114657460 0.0110399102 0.0160688832 0.0138906495 2.8713200000 1.2757040000 0.2656670000 0.1097050000 1.2078120000 0.0081950000 109902414 0 1784520704 4.1106710434 4.5632605553 4.8974618912 676 27.0000000000 0.0113436487 0.0110403595 0.0160688832 0.0138829891 3.0286910000 1.2706940000 0.5371730000 0.0000030000 1.2084410000 0.0081820000 109904088 0 1785901056 4.1064214706 4.5634379387 4.8983016014 677 27.0400000000 0.0114479819 0.0110409616 0.0160688832 0.0138761309 4.0797250000 1.2756430000 0.2677490000 0.1095890000 1.2024870000 1.2201310000 109905762 0 1787678720 4.1015081406 4.5636076927 4.8990674019 678 27.0800000000 0.0114304712 0.0110415361 0.0160688832 0.0138687128 2.8061370000 1.2784100000 0.3156980000 0.0000030000 1.1996430000 0.0082380000 109907436 0 1784397824 4.0969085693 4.5632705688 4.9000678062 679 27.1200000000 0.0121758170 0.0110432066 0.0160688832 0.0138607785 2.8551300000 1.2694660000 0.2673440000 0.1088820000 1.1971380000 0.0081780000 109909110 0 1785782272 4.0896549225 4.5620698929 4.9011807442 680 27.1600000000 0.0129768485 0.0110460502 0.0160688832 0.0138562591 2.8895670000 1.2748510000 0.4065390000 0.0000030000 1.1957820000 0.0082580000 109910784 0 1787830272 4.0834541321 4.5615358353 4.9026713371 681 27.2000000000 0.0130364271 0.0110489729 0.0160688832 0.0138514668 4.1039050000 1.2688510000 0.3124480000 0.1084660000 1.1984520000 1.2114560000 109912458 0 1784520704 4.0807299614 4.5612206459 4.9033784866 682 27.2400000000 0.0131468885 0.0110520490 0.0160688832 0.0138465444 2.8334100000 1.2701020000 0.3588570000 0.0000030000 1.1920210000 0.0081980000 109914132 0 1785901056 4.0769371986 4.5606503487 4.9041328430 683 27.2800000000 0.0132012879 0.0110551958 0.0160688832 0.0138413395 2.9040170000 1.2798380000 0.3123430000 0.1084110000 1.1909750000 0.0081860000 109915806 0 1787805696 4.0742368698 4.5595355034 4.9050660133 684 27.3200000000 0.0132509302 0.0110584060 0.0160688832 0.0138321551 2.9361110000 1.2716690000 0.4528140000 0.0000030000 1.1992150000 0.0082450000 109917480 0 1784520704 4.0684070587 4.5600910187 4.9061465263 685 27.3600000000 0.0119967135 0.0110597757 0.0160688832 0.0138249233 4.0422670000 1.2672980000 0.2645420000 0.1079120000 1.1908360000 1.2074170000 109919154 0 1786171392 4.0679717064 4.5610556602 4.9070363045 686 27.4000000000 0.0117004067 0.0110607096 0.0160688832 0.0138197467 2.7448550000 1.2749770000 0.2649540000 0.0000030000 1.1920460000 0.0087030000 109920828 0 1787949056 4.0645875931 4.5601835251 4.9081783295 687 27.4400000000 0.0115487892 0.0110614201 0.0160688832 0.0138159782 2.8849410000 1.2679590000 0.3108510000 0.1077100000 1.1859970000 0.0082080000 109922502 0 1784774656 4.0611333847 4.5608410835 4.9095373154 688 27.4800000000 0.0115036666 0.0110620629 0.0160688832 0.0138130279 2.7817970000 1.2744250000 0.3112620000 0.0000030000 1.1836060000 0.0083020000 109924176 0 1786155008 4.0592865944 4.5613460541 4.9106245041 689 27.5200000000 0.0114182821 0.0110625799 0.0160688832 0.0138089335 4.0853930000 1.2690400000 0.3115450000 0.1074870000 1.1906420000 1.2024380000 109925850 0 1785671680 4.0555477142 4.5620751381 4.9114041328 690 27.5600000000 0.0114939865 0.0110632051 0.0160688832 0.0138027422 2.7814010000 1.2686920000 0.3150490000 0.0000030000 1.1850600000 0.0082200000 109927524 0 1787179008 4.0520539284 4.5630664825 4.9124851227 691 27.6000000000 0.0114044072 0.0110636989 0.0160688832 0.0137971219 2.9268120000 1.2705860000 0.3561380000 0.1073560000 1.1802410000 0.0082420000 109929198 0 1785282560 4.0490336418 4.5632061958 4.9134860039 692 27.6400000000 0.0113312760 0.0110640855 0.0160688832 0.0137913086 2.7345730000 1.2673620000 0.2653580000 0.0000180000 1.1891790000 0.0083190000 109930872 0 1786789888 4.0457434654 4.5641970634 4.9147124290 693 27.6800000000 0.0113233076 0.0110644596 0.0160688832 0.0137855456 4.0144470000 1.2672250000 0.2650470000 0.1073400000 1.1763900000 1.1941960000 109932546 0 1784393728 4.0413365364 4.5635447502 4.9157319069 694 27.7200000000 0.0113067655 0.0110648087 0.0160688832 0.0137781701 2.7267150000 1.2732100000 0.2659790000 0.0000030000 1.1748010000 0.0084240000 109934220 0 1785917440 4.0389366150 4.5638151169 4.9169778824 695 27.7600000000 0.0113585880 0.0110652315 0.0160688832 0.0137725545 2.8151290000 1.2684400000 0.2542440000 0.1071390000 1.1728690000 0.0082050000 109935894 0 1787678720 4.0361170769 4.5640821457 4.9180464745 696 27.8000000000 0.0114030158 0.0110657168 0.0160688832 0.0137672143 2.7237270000 1.2729830000 0.2658250000 0.0000040000 1.1724710000 0.0082120000 109937568 0 1784918016 4.0322566032 4.5626363754 4.9193348885 697 27.8400000000 0.0114776548 0.0110663078 0.0160688832 0.0137638770 4.0294650000 1.2985410000 0.2552440000 0.1070330000 1.1764900000 1.1878680000 109939242 0 1786535936 4.0285849571 4.5633273125 4.9203329086 698 27.8800000000 0.0114469165 0.0110668531 0.0160688832 0.0137599556 2.7156120000 1.2706970000 0.2654050000 0.0000030000 1.1669480000 0.0082070000 109940916 0 1785409536 4.0259428024 4.5633893013 4.9214076996 699 27.9200000000 0.0114274258 0.0110673689 0.0160688832 0.0137549410 3.0113140000 1.2812830000 0.4473570000 0.1067290000 1.1633460000 0.0082140000 109942590 0 1787043840 4.0221548080 4.5641312599 4.9224495888 700 27.9600000000 0.0115906587 0.0110681165 0.0160688832 0.0137528082 2.7068670000 1.2710020000 0.2554680000 0.0000040000 1.1678480000 0.0082520000 109944264 0 1784791040 4.0180616379 4.5643134117 4.9235672951 701 28.0000000000 0.0116497930 0.0110689463 0.0160688832 0.0137495143 3.9827460000 1.2676860000 0.2663090000 0.1067140000 1.1596760000 1.1780720000 109945938 0 1786544128 4.0149469376 4.5651559830 4.9245061874 702 28.0400000000 0.0115977004 0.0110696995 0.0160688832 0.0137455618 2.6672890000 1.2723330000 0.2208570000 0.0000050000 1.1614430000 0.0082760000 109947612 0 1785655296 4.0103502274 4.5672240257 4.9250612259 703 28.0800000000 0.0116147036 0.0110704747 0.0160688832 0.0137411431 2.8103640000 1.2685260000 0.2668140000 0.1067900000 1.1555670000 0.0082740000 109949286 0 1787314176 4.0076613426 4.5677304268 4.9262928963 704 28.1200000000 0.0117525198 0.0110714435 0.0160688832 0.0137363285 2.7020740000 1.2766850000 0.2557940000 0.0000040000 1.1570470000 0.0082290000 109950960 0 1784664064 4.0046167374 4.5677490234 4.9273824692 705 28.1600000000 0.0117821880 0.0110724517 0.0160688832 0.0137316269 3.9891780000 1.2780420000 0.2677140000 0.1068400000 1.1600640000 1.1722070000 109952634 0 1786281984 4.0016937256 4.5675735474 4.9288506508 706 28.2000000000 0.0119163422 0.0110736470 0.0160688832 0.0137264913 2.7408710000 1.2737260000 0.3011180000 0.0000040000 1.1535240000 0.0082100000 109954308 0 1785409536 3.9999809265 4.5667905807 4.9300131798 707 28.2400000000 0.0118822362 0.0110747907 0.0160688832 0.0137217984 2.8117650000 1.2738470000 0.2695630000 0.1065980000 1.1491010000 0.0083100000 109955982 0 1787060224 3.9957716465 4.5663380623 4.9311656952 708 28.2800000000 0.0119051170 0.0110759635 0.0160688832 0.0137160666 2.6958320000 1.2666540000 0.2679450000 0.0000050000 1.1486380000 0.0082650000 109957656 0 1784758272 3.9934377670 4.5658669472 4.9323353767 709 28.3200000000 0.0118655292 0.0110770771 0.0160688832 0.0137089905 3.9859980000 1.3042270000 0.2568770000 0.1063270000 1.1485360000 1.1656790000 109959330 0 1786425344 3.9900724888 4.5671873093 4.9333553314 710 28.3600000000 0.0119010359 0.0110782376 0.0160688832 0.0137027102 2.7451470000 1.2667560000 0.3184370000 0.0000050000 1.1474110000 0.0082230000 109961004 0 1785647104 3.9860112667 4.5673418045 4.9343318939 711 28.4000000000 0.0118571920 0.0110793332 0.0160688832 0.0136977507 2.7826530000 1.2684210000 0.2547370000 0.1062710000 1.1406060000 0.0083210000 109962678 0 1787060224 3.9822816849 4.5670127869 4.9355936050 712 28.4400000000 0.0119411396 0.0110805436 0.0160688832 0.0136913714 2.6911190000 1.2719340000 0.2663850000 0.0000050000 1.1401350000 0.0083530000 109964352 0 1784688640 3.9772670269 4.5671191216 4.9365048409 713 28.4800000000 0.0119191734 0.0110817198 0.0160688832 0.0136848417 3.9631440000 1.2985080000 0.2554760000 0.1062520000 1.1377770000 1.1607730000 109966026 0 1786417152 3.9731552601 4.5678987503 4.9374842644 714 28.5200000000 0.0119888894 0.0110829903 0.0160688832 0.0136786419 2.6837930000 1.2685340000 0.2668250000 0.0000040000 1.1356250000 0.0084890000 109967700 0 1785647104 3.9693291187 4.5672349930 4.9389114380 715 28.5600000000 0.0119524812 0.0110842064 0.0160688832 0.0136709397 2.7984600000 1.2767090000 0.2713680000 0.1064000000 1.1312920000 0.0082250000 109969374 0 1787060224 3.9647231102 4.5675563812 4.9401888847 716 28.6000000000 0.0119919619 0.0110854742 0.0160688832 0.0136655612 2.6614530000 1.2653660000 0.2551510000 0.0000050000 1.1282560000 0.0083040000 109971048 0 1784901632 3.9602496624 4.5664868355 4.9413428307 717 28.6400000000 0.0120660970 0.0110868419 0.0160688832 0.0136588196 3.9418970000 1.3061470000 0.2555920000 0.1064640000 1.1242540000 1.1450830000 109972722 0 1786535936 3.9559204578 4.5668797493 4.9421601295 718 28.6800000000 0.0121222222 0.0110882839 0.0160688832 0.0136525017 2.6632130000 1.2672910000 0.2547030000 0.0000050000 1.1285600000 0.0082790000 109974396 0 1784901632 3.9511399269 4.5676784515 4.9429888725 719 28.7200000000 0.0121363476 0.0110897416 0.0160688832 0.0136493442 2.7747520000 1.2706000000 0.2651450000 0.1062790000 1.1201030000 0.0082330000 109976070 0 1786535936 3.9468982220 4.5662741661 4.9438643456 720 28.7600000000 0.0121111833 0.0110911603 0.0160688832 0.0136506241 2.6746350000 1.2676680000 0.2657380000 0.0000050000 1.1285120000 0.0083190000 109977744 0 1785790464 3.9434757233 4.5665612221 4.9447011948 721 28.8000000000 0.0121549135 0.0110926356 0.0160688832 0.0136470783 3.8838930000 1.2716760000 0.2440930000 0.1064610000 1.1171380000 1.1399930000 109979418 0 1787297792 3.9398989677 4.5655298233 4.9459428787 722 28.8400000000 0.0121961450 0.0110941640 0.0160688832 0.0136424040 2.6623850000 1.2686250000 0.2647730000 0.0000050000 1.1161850000 0.0083420000 109981092 0 1785180160 3.9341816902 4.5644135475 4.9468536377 723 28.8800000000 0.0122884018 0.0110958158 0.0160688832 0.0136363113 2.7132420000 1.2690440000 0.2091000000 0.1063920000 1.1160610000 0.0082380000 109982766 0 1786671104 3.9304218292 4.5647697449 4.9477291107 724 28.9200000000 0.0123286108 0.0110975186 0.0160688832 0.0136294548 2.7032560000 1.2721650000 0.3103350000 0.0000050000 1.1079780000 0.0083550000 109984440 0 1784782848 3.9248619080 4.5641865730 4.9484424591 725 28.9600000000 0.0123125426 0.0110991945 0.0160688832 0.0136222027 3.8785380000 1.2692020000 0.2652560000 0.1066670000 1.1106650000 1.1222670000 109986114 0 1786408960 3.9212477207 4.5633721352 4.9496831894 726 29.0000000000 0.0123562980 0.0111009260 0.0160688832 0.0136158249 2.6863440000 1.2692160000 0.3008440000 0.0000050000 1.1035010000 0.0083860000 109987788 0 1785536512 3.9176497459 4.5634913445 4.9504165649 727 29.0400000000 0.0123270629 0.0111026126 0.0160688832 0.0136117651 2.8086860000 1.2749600000 0.3126610000 0.1066210000 1.1017270000 0.0083040000 109989462 0 1787043840 3.9142122269 4.5634245872 4.9512376785 728 29.0800000000 0.0124176480 0.0111044190 0.0160688832 0.0136083360 2.6483760000 1.2714880000 0.2573640000 0.0000050000 1.1068130000 0.0082790000 109991136 0 1784901632 3.9116973877 4.5625247955 4.9519910812 729 29.1200000000 0.0123500777 0.0111061277 0.0160688832 0.0136079902 3.8570880000 1.2689550000 0.2577850000 0.1066780000 1.1004810000 1.1187420000 109992810 0 1786552320 3.9087707996 4.5623974800 4.9526348114 730 29.1600000000 0.0123929009 0.0111078904 0.0160688832 0.0136057834 2.6438050000 1.2711820000 0.2585520000 0.0000050000 1.1012130000 0.0084070000 109994484 0 1785425920 3.9064779282 4.5613527298 4.9535627365 731 29.2000000000 0.0123881670 0.0111096418 0.0160688832 0.0136034250 2.7574900000 1.2682610000 0.2686600000 0.1069230000 1.1008950000 0.0083010000 109996158 0 1787060224 3.9015350342 4.5602359772 4.9538297653 732 29.2400000000 0.0123484209 0.0111113341 0.0160688832 0.0136000395 2.6435110000 1.2740150000 0.2565490000 0.0000050000 1.1001630000 0.0082890000 109997832 0 1784680448 3.8983066082 4.5604066849 4.9542107582 733 29.2800000000 0.0123411585 0.0111130119 0.0160688832 0.0135955992 3.8716650000 1.2701440000 0.2676530000 0.1069960000 1.0992490000 1.1230770000 109999506 0 1786425344 3.8958153725 4.5587973595 4.9549059868 734 29.3200000000 0.0123373717 0.0111146800 0.0160688832 0.0135889821 2.7047560000 1.2744740000 0.3169070000 0.0000040000 1.1005460000 0.0082380000 110001180 0 1785561088 3.8931875229 4.5582370758 4.9552803040 735 29.3600000000 0.0123472102 0.0111163569 0.0160688832 0.0135817687 2.7987960000 1.2754610000 0.3032640000 0.1070960000 1.1002140000 0.0083130000 110002854 0 1787305984 3.8896286488 4.5580334663 4.9554190636 736 29.4000000000 0.0124260485 0.0111181364 0.0160688832 0.0135763715 2.6409120000 1.2692990000 0.2577750000 0.0000050000 1.1010430000 0.0082930000 110004528 0 1784918016 3.8866965771 4.5566215515 4.9555616379 737 29.4400000000 0.0123019535 0.0111197426 0.0160688832 0.0135711201 3.8668340000 1.2786360000 0.2585670000 0.1072100000 1.1004470000 1.1174100000 110006202 0 1786535936 3.8839421272 4.5547018051 4.9556984901 738 29.4800000000 0.0124605354 0.0111215594 0.0160688832 0.0135641388 2.6975900000 1.2708140000 0.3047030000 0.0000060000 1.1091810000 0.0082790000 110007876 0 1785663488 3.8826766014 4.5533099174 4.9563217163 739 29.5200000000 0.0124603854 0.0111233711 0.0160688832 0.0135583122 2.7989110000 1.2728550000 0.3053120000 0.1072490000 1.1005870000 0.0083030000 110009550 0 1787187200 3.8813233376 4.5512642860 4.9567375183 740 29.5600000000 0.0124245323 0.0111251294 0.0160688832 0.0135555516 2.7093320000 1.2709780000 0.3217020000 0.0000050000 1.1037650000 0.0082530000 110011224 0 1784664064 3.8799927235 4.5495638847 4.9568672180 741 29.6000000000 0.0124168908 0.0111268727 0.0160688832 0.0135537072 3.9195410000 1.2729500000 0.3046640000 0.1074350000 1.1035440000 1.1264400000 110012898 0 1786155008 3.8778116703 4.5482492447 4.9573078156 742 29.6400000000 0.0124671021 0.0111286789 0.0160688832 0.0135498850 2.6470480000 1.2710760000 0.2584250000 0.0000050000 1.1047900000 0.0082430000 110014572 0 1785266176 3.8762536049 4.5470266342 4.9577713013 743 29.6800000000 0.0123846987 0.0111303694 0.0160688832 0.0135473504 2.7712590000 1.2705060000 0.2691600000 0.1075500000 1.1111780000 0.0082280000 110016246 0 1786789888 3.8748974800 4.5454535484 4.9578642845 744 29.7200000000 0.0123900855 0.0111320626 0.0160688832 0.0135483266 2.6500710000 1.2715320000 0.2574970000 0.0000050000 1.1081750000 0.0083390000 110017920 0 1784393728 3.8717675209 4.5416841507 4.9586067200 745 29.7600000000 0.0123577230 0.0111337077 0.0160688832 0.0135412785 3.9402690000 1.2707370000 0.3145370000 0.1132950000 1.1111030000 1.1259520000 110019594 0 1786036224 3.8713212013 4.5393543243 4.9591560364 746 29.8000000000 0.0124700917 0.0111354991 0.0160688832 0.0135337341 2.9336870000 1.2707900000 0.5351800000 0.0000050000 1.1148400000 0.0082260000 110021268 0 1787686912 3.8697140217 4.5388422012 4.9594988823 747 29.8400000000 0.0124884592 0.0111373103 0.0160688832 0.0135260286 2.8052070000 1.2710620000 0.3033410000 0.1079010000 1.1100430000 0.0083230000 110022942 0 1785274368 3.8685257435 4.5372052193 4.9600453377 748 29.8800000000 0.0124586029 0.0111390768 0.0160688832 0.0135170340 2.7238330000 1.2695250000 0.3024470000 0.0000050000 1.1389880000 0.0083140000 110024616 0 1787043840 3.8677709103 4.5357275009 4.9603972435 749 29.9200000000 0.0125490688 0.0111409593 0.0160688832 0.0135081702 3.9205590000 1.3035200000 0.2566770000 0.1079880000 1.1157140000 1.1320370000 110026290 0 1784647680 3.8660736084 4.5345516205 4.9607782364 750 29.9600000000 0.0125626689 0.0111428549 0.0160688832 0.0134992266 2.6582710000 1.2777040000 0.2544180000 0.0000050000 1.1132200000 0.0082430000 110027964 0 1786044416 3.8648447990 4.5341038704 4.9611043930 751 30.0000000000 0.0125710201 0.0111447566 0.0160688832 0.0134905036 2.7796940000 1.2727230000 0.2675580000 0.1081330000 1.1184940000 0.0082760000 110029638 0 1788059648 3.8650040627 4.5307245255 4.9618549347 752 30.0400000000 0.0125759682 0.0111466598 0.0160688832 0.0134818860 2.6681060000 1.2709360000 0.2561510000 0.0000050000 1.1272040000 0.0089960000 110031312 0 1784647680 3.8646719456 4.5290036201 4.9626550674 753 30.0800000000 0.0126329232 0.0111486336 0.0160688832 0.0134753172 3.9357660000 1.2974840000 0.2675250000 0.1083990000 1.1244270000 1.1333410000 110032986 0 1786281984 3.8635518551 4.5279359818 4.9634408951 754 30.1200000000 0.0126454076 0.0111506187 0.0160688832 0.0134689374 2.6574600000 1.2715210000 0.2555790000 0.0000060000 1.1175360000 0.0082780000 110034660 0 1785536512 3.8643701077 4.5261502266 4.9644041061 755 30.1600000000 0.0126498938 0.0111526045 0.0160688832 0.0134626297 2.7856820000 1.2784720000 0.2651850000 0.1088590000 1.1203230000 0.0082870000 110036334 0 1786916864 3.8644633293 4.5247883797 4.9655704498 756 30.2000000000 0.0126530658 0.0111545892 0.0160688832 0.0134545316 2.8416780000 1.2721620000 0.4317950000 0.0000060000 1.1247840000 0.0082170000 110038008 0 1784520704 3.8640377522 4.5237956047 4.9664072990 757 30.2400000000 0.0126290461 0.0111565370 0.0160688832 0.0134474936 3.9526240000 1.2716120000 0.3057740000 0.1087860000 1.1230550000 1.1388030000 110039682 0 1786163200 3.8643336296 4.5220460892 4.9675273895 758 30.2800000000 0.0126172630 0.0111584640 0.0160688832 0.0134425340 2.6685050000 1.2764140000 0.2603740000 0.0000050000 1.1187980000 0.0082310000 110041356 0 1787830272 3.8640787601 4.5232868195 4.9686360359 759 30.3200000000 0.0126118632 0.0111603789 0.0160688832 0.0134381331 2.7813470000 1.2703390000 0.2727450000 0.1088830000 1.1165010000 0.0082670000 110043030 0 1784631296 3.8646676540 4.5221624374 4.9698343277 760 30.3600000000 0.0127024725 0.0111624080 0.0160688832 0.0134372158 2.7108180000 1.2761360000 0.3068070000 0.0000060000 1.1149240000 0.0082330000 110044704 0 1786028032 3.8661408424 4.5199398994 4.9710578918 761 30.4000000000 0.0128525877 0.0111646290 0.0160688832 0.0134319294 3.9440630000 1.2713640000 0.3076730000 0.1091100000 1.1197030000 1.1315300000 110046378 0 1787932672 3.8665623665 4.5198264122 4.9726219177 762 30.4400000000 0.0128010204 0.0111667765 0.0160688832 0.0134233082 2.7906730000 1.2731370000 0.3924510000 0.0000060000 1.1121190000 0.0083150000 110048052 0 1784647680 3.8673007488 4.5191526413 4.9740443230 763 30.4800000000 0.0128883477 0.0111690328 0.0160688832 0.0134146035 2.7648140000 1.2771440000 0.2579260000 0.1091500000 1.1077490000 0.0082370000 110049726 0 1786028032 3.8691372871 4.5166983604 4.9757432938 764 30.5200000000 0.0129092531 0.0111713106 0.0160688832 0.0134069947 2.6565180000 1.2715420000 0.2658660000 0.0000050000 1.1061920000 0.0082640000 110051400 0 1787932672 3.8717143536 4.5149040222 4.9773206711 765 30.5600000000 0.0129301948 0.0111736098 0.0160688832 0.0133997870 3.8850540000 1.2805950000 0.2664880000 0.1095620000 1.1030260000 1.1206370000 110053074 0 1784520704 3.8739876747 4.5134892464 4.9791636467 766 30.6000000000 0.0129542127 0.0111759343 0.0160688832 0.0133969609 2.6503720000 1.2721030000 0.2584940000 0.0000050000 1.1067760000 0.0082860000 110054748 0 1785901056 3.8760786057 4.5118446350 4.9807505608 767 30.6400000000 0.0131323077 0.0111784850 0.0160688832 0.0134013317 2.7624610000 1.2707090000 0.2694830000 0.1097390000 1.0996480000 0.0082370000 110056422 0 1787805696 3.8790543079 4.5089683533 4.9825668335 768 30.6800000000 0.0132153770 0.0111811372 0.0160688832 0.0134084835 2.6502440000 1.2780970000 0.2581970000 0.0000050000 1.1009070000 0.0083140000 110058096 0 1784520704 3.8822650909 4.5081872940 4.9844098091 769 30.7200000000 0.0132445395 0.0111838204 0.0160688832 0.0134620986 3.8567420000 1.2694270000 0.2586990000 0.1102540000 1.0972400000 1.1164300000 110059770 0 1786036224 3.8889911175 4.5059790611 4.9881477356 770 30.7600000000 0.0133257052 0.0111866021 0.0160688832 0.0134908791 2.5937640000 1.2735390000 0.2138750000 0.0000050000 1.0934530000 0.0082260000 110061444 0 1787703296 3.8932580948 4.5013470650 4.9896769524 771 30.8000000000 0.0134294359 0.0111895111 0.0160688832 0.0135119976 2.7548350000 1.2749310000 0.2585780000 0.1107960000 1.0976170000 0.0082350000 110063118 0 1784520704 3.8968441486 4.4991259575 4.9910235405 772 30.8400000000 0.0134851867 0.0111924848 0.0160688832 0.0135332924 2.6457100000 1.2713900000 0.2699760000 0.0000050000 1.0912610000 0.0082490000 110064792 0 1785901056 3.8990762234 4.4980597496 4.9919714928 773 30.8800000000 0.0135371378 0.0111955180 0.0160688832 0.0135567371 3.8550000000 1.2775410000 0.2607610000 0.1164480000 1.0894260000 1.1061360000 110066466 0 1787805696 3.9029726982 4.4948596954 4.9936389923 774 30.9200000000 0.0135375783 0.0111985439 0.0160688832 0.0135769176 2.6422690000 1.2694330000 0.2719140000 0.0000050000 1.0878250000 0.0083540000 110068140 0 1784156160 3.9066815376 4.4910216331 4.9948306084 775 30.9600000000 0.0135926642 0.0112016331 0.0160688832 0.0135957673 2.7607840000 1.2787660000 0.2712620000 0.1115350000 1.0862480000 0.0082780000 110069814 0 1785647104 3.9098494053 4.4890837669 4.9958448410 776 31.0000000000 0.0137030678 0.0112048566 0.0160688832 0.0136178264 2.6351500000 1.2723170000 0.2603010000 0.0000060000 1.0894840000 0.0083210000 110071488 0 1787551744 3.9139773846 4.4864063263 4.9975209236 777 31.0400000000 0.0136015257 0.0112079411 0.0160688832 0.0136287371 3.8415700000 1.2728280000 0.2716210000 0.1120120000 1.0815330000 1.0987680000 110073162 0 1784250368 3.9174335003 4.4842567444 4.9990968704 778 31.0800000000 0.0138387820 0.0112113226 0.0160688832 0.0136343377 2.6395730000 1.2759110000 0.2715980000 0.0000050000 1.0790300000 0.0083140000 110074836 0 1785901056 3.9203503132 4.4808869362 5.0006728172 779 31.1200000000 0.0136001091 0.0112143891 0.0160688832 0.0136333891 2.7918700000 1.2749540000 0.3158330000 0.1124460000 1.0756890000 0.0082310000 110076510 0 1787678720 3.9237043858 4.4772629738 5.0027532578 780 31.1600000000 0.0137974266 0.0112177007 0.0160688832 0.0136299840 2.6245840000 1.2800870000 0.2573140000 0.0000050000 1.0739850000 0.0083810000 110078184 0 1784418304 3.9265332222 4.4745616913 5.0046744347 781 31.2000000000 0.0138604846 0.0112210845 0.0160688832 0.0136253245 3.8161100000 1.2697680000 0.2684930000 0.1126710000 1.0699130000 1.0905500000 110079858 0 1785782272 3.9286007881 4.4709157944 5.0063552856 782 31.2400000000 0.0137876775 0.0112243666 0.0160688832 0.0136220944 2.6132190000 1.2781940000 0.2576370000 0.0000060000 1.0643710000 0.0082240000 110081532 0 1787686912 3.9317128658 4.4667787552 5.0086717606 783 31.2800000000 0.0137791149 0.0112276294 0.0160688832 0.0136170989 2.7346480000 1.2729630000 0.2743820000 0.1131200000 1.0611460000 0.0082520000 110083206 0 1784520704 3.9342634678 4.4627084732 5.0107192993 784 31.3200000000 0.0136404056 0.0112307069 0.0160688832 0.0136124432 2.6073220000 1.2732710000 0.2580290000 0.0000050000 1.0627090000 0.0085980000 110084880 0 1785901056 3.9366397858 4.4575619698 5.0126838684 785 31.3600000000 0.0136843771 0.0112338326 0.0160688832 0.0136072228 3.8559220000 1.3019470000 0.3070420000 0.1133150000 1.0553910000 1.0733860000 110086554 0 1787678720 3.9385581017 4.4531140327 5.0144500732 786 31.4000000000 0.0137762353 0.0112370672 0.0160688832 0.0136004082 2.6578230000 1.2748170000 0.3105740000 0.0000050000 1.0592840000 0.0082400000 110088228 0 1784410112 3.9401609898 4.4496946335 5.0159091949 787 31.4400000000 0.0138442852 0.0112403801 0.0160688832 0.0135930754 2.7282800000 1.2768790000 0.2736220000 0.1134280000 1.0513150000 0.0082770000 110089902 0 1785774080 3.9416339397 4.4434065819 5.0173711777 788 31.4800000000 0.0138183460 0.0112436516 0.0160688832 0.0135898021 2.6037250000 1.2733090000 0.2606070000 0.0000050000 1.0566030000 0.0083010000 110091576 0 1787695104 3.9437608719 4.4385371208 5.0193581581 789 31.5200000000 0.0136834932 0.0112467439 0.0160688832 0.0135884642 3.8013530000 1.3005360000 0.2704210000 0.1136340000 1.0471350000 1.0647440000 110093250 0 1784520704 3.9452092648 4.4337844849 5.0209946632 790 31.5600000000 0.0137187401 0.0112498730 0.0160688832 0.0135874052 2.5664890000 1.2798990000 0.2273870000 0.0000050000 1.0460980000 0.0082160000 110094924 0 1786028032 3.9466178417 4.4270677567 5.0227036476 791 31.6000000000 0.0136681031 0.0112529302 0.0160688832 0.0136121463 2.7185510000 1.2740980000 0.2691520000 0.1139000000 1.0483290000 0.0082500000 110096598 0 1787813888 3.9478228092 4.4182891846 5.0254812241 792 31.6400000000 0.0137979770 0.0112561437 0.0160688832 0.0136095413 2.6442820000 1.2724870000 0.3166850000 0.0000060000 1.0416920000 0.0083320000 110098272 0 1784164352 3.9483525753 4.4142313004 5.0274705887 793 31.6800000000 0.0135079930 0.0112589833 0.0160688832 0.0136057213 3.8022390000 1.3089510000 0.2720740000 0.1139450000 1.0449030000 1.0575520000 110099946 0 1785647104 3.9492280483 4.4073023796 5.0293707848 794 31.7200000000 0.0136443423 0.0112619876 0.0160688832 0.0136007374 2.5968930000 1.2736870000 0.2720640000 0.0000050000 1.0379770000 0.0082230000 110101620 0 1787551744 3.9494421482 4.4060626030 5.0309767723 795 31.7600000000 0.0135094225 0.0112648145 0.0160688832 0.0135956972 2.7114540000 1.2795340000 0.2703090000 0.1140740000 1.0343750000 0.0083250000 110103294 0 1784266752 3.9492146969 4.4044795036 5.0325570107 796 31.8000000000 0.0134510715 0.0112675611 0.0160688832 0.0135926809 2.5820020000 1.2708190000 0.2691810000 0.0000050000 1.0287970000 0.0082820000 110104968 0 1785765888 3.9496300220 4.3991503716 5.0347561836 797 31.8400000000 0.0132662207 0.0112700688 0.0160688832 0.0135933300 3.7642790000 1.3087210000 0.2705020000 0.1138150000 1.0243570000 1.0420460000 110106642 0 1787678720 3.9497179985 4.3931956291 5.0373182297 798 31.8800000000 0.0131624043 0.0112724401 0.0160688832 0.0136607146 2.5466610000 1.2703990000 0.2337350000 0.0000060000 1.0293070000 0.0083350000 110108316 0 1784664064 3.9510293007 4.3749737740 5.0435414314 799 31.9200000000 0.0131477881 0.0112747873 0.0160688832 0.0136756693 2.6937200000 1.2724110000 0.2701330000 0.1135230000 1.0245070000 0.0082260000 110109990 0 1786155008 3.9512591362 4.3666439056 5.0462131500 800 31.9600000000 0.0130082080 0.0112769540 0.0160688832 0.0136819165 2.6663020000 1.2747720000 0.3542040000 0.0000060000 1.0241130000 0.0083320000 110111664 0 1785266176 3.9507265091 4.3621840477 5.0484547615 801 32.0000000000 0.0129350750 0.0112790241 0.0160688832 0.0136766120 3.7708720000 1.2759340000 0.3123570000 0.1134480000 1.0237440000 1.0405260000 110113338 0 1786789888 3.9503529072 4.3581790924 5.0514345169 802 32.0400000000 0.0129564898 0.0112811157 0.0160688832 0.0136681627 2.5863390000 1.2805760000 0.2702810000 0.0000050000 1.0222410000 0.0082000000 110115012 0 1784291328 3.9493029118 4.3502330780 5.0540108681 803 32.0800000000 0.0130332150 0.0112832977 0.0160688832 0.0136598418 2.6956680000 1.2739300000 0.2701410000 0.1134430000 1.0250600000 0.0082870000 110116686 0 1785782272 3.9486298561 4.3409714699 5.0571203232 804 32.1199999990 0.0131017873 0.0112855595 0.0160688832 0.0136539770 2.6662690000 1.2746930000 0.3626700000 0.0000050000 1.0157580000 0.0082560000 110118360 0 1787576320 3.9469950199 4.3259019852 5.0638880730 805 32.1600000000 0.0140266698 0.0112889646 0.0160688832 0.0136465666 3.7415140000 1.3036350000 0.2670690000 0.1132340000 1.0205480000 1.0320990000 110120034 0 1784266752 3.9460816383 4.3227491379 5.0669946671 806 32.2000000000 0.0140242307 0.0112923582 0.0160688832 0.0136380985 2.6148890000 1.2720300000 0.3177690000 0.0000050000 1.0119370000 0.0082890000 110121708 0 1785774080 3.9445333481 4.3175158501 5.0702991486 807 32.2400000000 0.0135603389 0.0112951686 0.0160688832 0.0136301091 2.7767020000 1.2764050000 0.3658250000 0.1130140000 1.0080190000 0.0084600000 110123382 0 1787678720 3.9431736469 4.3086156845 5.0738134384 808 32.2800000000 0.0140817584 0.0112986173 0.0160688832 0.0136223507 2.7061400000 1.2742280000 0.4143560000 0.0000050000 1.0043280000 0.0082150000 110125056 0 1784410112 3.9413614273 4.3030962944 5.0774464607 809 32.3200000000 0.0140894828 0.0113020671 0.0160688832 0.0136143337 3.8097350000 1.3031990000 0.3676170000 0.1127740000 1.0019530000 1.0192950000 110126730 0 1785774080 3.9403069019 4.2893137932 5.0821981430 810 32.3600000000 0.0157076549 0.0113075061 0.0160688832 0.0136061541 2.5605790000 1.2738610000 0.2739420000 0.0000050000 0.9996010000 0.0082500000 110128404 0 1787568128 3.9392762184 4.2791981697 5.0864067078 811 32.4000000000 0.0160537101 0.0113133584 0.0160688832 0.0135986175 2.6639100000 1.2740750000 0.2687910000 0.1125640000 0.9952010000 0.0081980000 110130078 0 1784393728 3.9372494221 4.2760949135 5.0902013779 812 32.4399999990 0.0163813345 0.0113195997 0.0163813345 0.0135923807 2.5508060000 1.2756830000 0.2713190000 0.0000050000 0.9905630000 0.0083090000 110131752 0 1785774080 3.9354166985 4.2700037956 5.0945205688 813 32.4800000000 0.0165042076 0.0113259769 0.0165042076 0.0135852054 3.9638410000 1.3025260000 0.5510710000 0.1122460000 0.9852020000 1.0077960000 110133426 0 1787678720 3.9339861870 4.2605781555 5.0993409157 814 32.5200000000 0.0167605560 0.0113326532 0.0167605560 0.0135773331 2.8090580000 1.2751910000 0.5403950000 0.0000050000 0.9801550000 0.0082070000 110135100 0 1784418304 3.9329004288 4.2496924400 5.1043324471 815 32.5600000000 0.0169704426 0.0113395708 0.0169704426 0.0135700189 2.7012030000 1.2737720000 0.3185890000 0.1118490000 0.9837080000 0.0082750000 110136774 0 1785782272 3.9317054749 4.2400703430 5.1091675758 816 32.6000000000 0.0168968085 0.0113463811 0.0169704426 0.0135620074 2.6229980000 1.2737870000 0.3600670000 0.0000060000 0.9758100000 0.0082770000 110138448 0 1787703296 3.9304797649 4.2329525948 5.1142706871 817 32.6400000000 0.0160773192 0.0113521717 0.0169704426 0.0135562982 3.6336850000 1.2754640000 0.2759490000 0.1135080000 0.9738180000 0.9899090000 110140122 0 1784520704 3.9296135902 4.2192077637 5.1211419106 818 32.6800000000 0.0166156124 0.0113586063 0.0169704426 0.0135480162 2.8002350000 1.2726250000 0.5379550000 0.0000050000 0.9761640000 0.0084440000 110141796 0 1785901056 3.9286541939 4.2033333778 5.1277360916 819 32.7200000000 0.0174177960 0.0113660045 0.0174177960 0.0135410402 2.7347130000 1.2811210000 0.3575090000 0.1109150000 0.9719410000 0.0082740000 110143470 0 1787932672 3.9271023273 4.1938376427 5.1326966286 820 32.7599999990 0.0167764109 0.0113726026 0.0174177960 0.0135328453 2.8068780000 1.2739020000 0.5456910000 0.0000050000 0.9738820000 0.0082090000 110145144 0 1784266752 3.9254062176 4.1870317459 5.1369104385 821 32.7999999990 0.0167305656 0.0113791287 0.0174177960 0.0135247884 3.7004990000 1.2722050000 0.3644040000 0.1105320000 0.9646450000 0.9836820000 110146818 0 1785901056 3.9245448112 4.1783933640 5.1416764259 822 32.8400000000 0.0167492274 0.0113856617 0.0174177960 0.0135177055 2.5652130000 1.2812790000 0.3075610000 0.0000050000 0.9631600000 0.0081850000 110148492 0 1787805696 3.9245748520 4.1667180061 5.1471199989 823 32.8800000000 0.0166781209 0.0113920924 0.0174177960 0.0135113566 2.6306740000 1.2743730000 0.2701860000 0.1103280000 0.9624320000 0.0081950000 110150166 0 1784664064 3.9246492386 4.1546764374 5.1526970863 824 32.9200000000 0.0165052153 0.0113982976 0.0174177960 0.0135040004 2.5133850000 1.2834640000 0.2577030000 0.0000050000 0.9588360000 0.0082020000 110151840 0 1786028032 3.9248392582 4.1436181068 5.1582493782 825 32.9600000000 0.0158143435 0.0114036504 0.0174177960 0.0134963039 3.7123480000 1.2991220000 0.3594330000 0.1100610000 0.9573400000 0.9813820000 110153514 0 1788059648 3.9245080948 4.1332769394 5.1629014015 826 33.0000000000 0.0153044118 0.0114083729 0.0174177960 0.0134898920 2.7911540000 1.2746560000 0.5477900000 0.0000050000 0.9552970000 0.0082360000 110155188 0 1785290752 3.9243736267 4.1240162849 5.1677484512 827 33.0400000000 0.0153910825 0.0114131888 0.0174177960 0.0134827349 2.6702570000 1.2756680000 0.3185810000 0.1099380000 0.9527890000 0.0081980000 110156862 0 1786671104 3.9243845940 4.1140308380 5.1722550392 828 33.0800000000 0.0151979476 0.0114177597 0.0174177960 0.0134763945 2.4976090000 1.2758770000 0.2577010000 0.0000050000 0.9506740000 0.0081940000 110158536 0 1784631296 3.9243013859 4.1061453819 5.1758484840 829 33.1199999990 0.0150181474 0.0114221028 0.0174177960 0.0134734218 3.6251250000 1.2791310000 0.3171500000 0.1095870000 0.9486180000 0.9654650000 110160210 0 1786187776 3.9244699478 4.0950355530 5.1800479889 830 33.1600000000 0.0149706900 0.0114263782 0.0174177960 0.0134696485 2.4486090000 1.2756230000 0.2119720000 0.0000050000 0.9475410000 0.0082590000 110161884 0 1785647104 3.9249372482 4.0817952156 5.1850252151 831 33.2000000000 0.0140055567 0.0114294819 0.0174177960 0.0134635413 2.6146970000 1.2782150000 0.2673870000 0.1095060000 0.9462520000 0.0082770000 110163558 0 1787043840 3.9254734516 4.0692386627 5.1892466545 832 33.2400000000 0.0147555433 0.0114334796 0.0174177960 0.0134597599 2.5506920000 1.2742920000 0.3136000000 0.0000050000 0.9494830000 0.0082210000 110165232 0 1784520704 3.9253475666 4.0615220070 5.1921749115 833 33.2800000000 0.0147972768 0.0114375177 0.0174177960 0.0134549469 3.5777530000 1.3044450000 0.2582000000 0.1092020000 0.9412110000 0.9595480000 110166906 0 1786028032 3.9257371426 4.0516586304 5.1956715584 834 33.3200000000 0.0146532524 0.0114413735 0.0174177960 0.0134474906 2.5043810000 1.2738400000 0.2765120000 0.0000050000 0.9406960000 0.0082630000 110168580 0 1787932672 3.9260594845 4.0424542427 5.1985430717 835 33.3600000000 0.0145319905 0.0114450749 0.0174177960 0.0134399044 2.6044900000 1.2760830000 0.2721120000 0.1092290000 0.9336590000 0.0081930000 110170254 0 1785028608 3.9270105362 4.0351176262 5.2009186745 836 33.4000000000 0.0144359777 0.0114486525 0.0174177960 0.0134362764 2.5396490000 1.2779180000 0.3157870000 0.0000050000 0.9325260000 0.0082620000 110171928 0 1786425344 3.9286382198 4.0266947746 5.2040057182 837 33.4399999990 0.0148336701 0.0114526967 0.0174177960 0.0134349966 3.6535490000 1.2977540000 0.3630600000 0.1090720000 0.9304000000 0.9481700000 110173602 0 1784631296 3.9296324253 4.0163202286 5.2073354721 838 33.4800000000 0.0148933213 0.0114568025 0.0174177960 0.0134302736 2.5299240000 1.2773360000 0.3096010000 0.0000050000 0.9296430000 0.0081990000 110175276 0 1786187776 3.9305474758 4.0062890053 5.2100625038 839 33.5200000000 0.0146705844 0.0114606330 0.0174177960 0.0134225300 2.5951870000 1.2741250000 0.2646510000 0.1090370000 0.9339010000 0.0081830000 110176950 0 1787957248 3.9313070774 3.9975416660 5.2120652199 840 33.5600000000 0.0148455696 0.0114646627 0.0174177960 0.0134149226 2.4694980000 1.2727100000 0.2556120000 0.0000050000 0.9277210000 0.0081810000 110178624 0 1784926208 3.9325649738 3.9914066792 5.2135019302 841 33.6000000000 0.0144499047 0.0114682123 0.0174177960 0.0134119400 3.6549100000 1.3023250000 0.3669200000 0.1087600000 0.9288610000 0.9428730000 110180298 0 1786441728 3.9338495731 3.9784755707 5.2168722153 842 33.6400000000 0.0144749610 0.0114717832 0.0174177960 0.0134045074 2.7422760000 1.2714580000 0.5336020000 0.0000050000 0.9237170000 0.0082980000 110181972 0 1785647104 3.9354670048 3.9653513432 5.2208509445 843 33.6800000000 0.0144495293 0.0114753156 0.0174177960 0.0133978214 2.5860680000 1.2803230000 0.2582950000 0.1088440000 0.9251790000 0.0082230000 110183646 0 1787187200 3.9360377789 3.9594120979 5.2212514877 844 33.7200000000 0.0139475819 0.0114782448 0.0174177960 0.0133965353 2.5179810000 1.2719210000 0.3061800000 0.0000050000 0.9262880000 0.0082820000 110185320 0 1784520704 3.9374032021 3.9520282745 5.2222023010 845 33.7599999990 0.0138384206 0.0114810379 0.0174177960 0.0134001306 3.5320160000 1.2788330000 0.2695770000 0.1086680000 0.9253350000 0.9444020000 110186994 0 1785917440 3.9380087852 3.9411604404 5.2239179611 846 33.7999999990 0.0136053506 0.0114835489 0.0174177960 0.0133978124 2.5230850000 1.2751200000 0.3022610000 0.0000050000 0.9322330000 0.0081920000 110188668 0 1787822080 3.9392538071 3.9357175827 5.2244758606 847 33.8400000000 0.0135730384 0.0114860158 0.0174177960 0.0133980705 2.5911250000 1.2724610000 0.2694030000 0.1087340000 0.9271310000 0.0081920000 110190342 0 1784791040 3.9397821426 3.9305086136 5.2245450020 848 33.8800000000 0.0135320472 0.0114884286 0.0174177960 0.0133950979 2.4809740000 1.2740500000 0.2614700000 0.0000060000 0.9320420000 0.0081850000 110192016 0 1786425344 3.9407651424 3.9188289642 5.2274556160 849 33.9200000000 0.0135136973 0.0114908141 0.0174177960 0.0133880718 3.5440570000 1.2967860000 0.2572520000 0.1083010000 0.9292630000 0.9471310000 110193690 0 1785671680 3.9401390553 3.9114873409 5.2281970978 850 33.9600000000 0.0131848510 0.0114928071 0.0174177960 0.0133821760 2.5002190000 1.2804970000 0.2701820000 0.0000050000 0.9357720000 0.0083280000 110195364 0 1787195392 3.9389989376 3.9073536396 5.2271819115 851 34.0000000000 0.0130178547 0.0114945991 0.0174177960 0.0133759035 2.5848620000 1.2729660000 0.2579500000 0.1081570000 0.9322420000 0.0082290000 110197038 0 1784655872 3.9381844997 3.9001522064 5.2276539803 852 34.0400000000 0.0128849726 0.0114962310 0.0174177960 0.0133688834 2.4986790000 1.2794890000 0.2706670000 0.0000050000 0.9350820000 0.0081990000 110198712 0 1786171392 3.9375956059 3.8954689503 5.2271981239 853 34.0800000000 0.0127987023 0.0114977580 0.0174177960 0.0133663444 3.5829530000 1.3017170000 0.2712070000 0.1080210000 0.9363110000 0.9604940000 110200386 0 1785536512 3.9373812675 3.8910336494 5.2267346382 854 34.1199999990 0.0127660893 0.0114992431 0.0174177960 0.0133661449 2.4831580000 1.2745100000 0.2586410000 0.0000040000 0.9365070000 0.0082410000 110202060 0 1787170816 3.9370946884 3.8834888935 5.2270727158 855 34.1600000000 0.0128416857 0.0115008132 0.0174177960 0.0133598167 2.5921880000 1.2703840000 0.2573480000 0.1077590000 0.9432340000 0.0082390000 110203734 0 1784537088 3.9375221729 3.8784015179 5.2274909019 856 34.2000000000 0.0127185313 0.0115022358 0.0174177960 0.0133536098 2.4842700000 1.2738560000 0.2576900000 0.0000050000 0.9392380000 0.0082510000 110205408 0 1786171392 3.9378778934 3.8764915466 5.2262806892 857 34.2400000000 0.0126057509 0.0115035235 0.0174177960 0.0133513063 3.5834850000 1.2960530000 0.2685300000 0.1077750000 0.9461010000 0.9596590000 110207082 0 1787949056 3.9388926029 3.8741173744 5.2251858711 858 34.2800000000 0.0125092482 0.0115046956 0.0174177960 0.0133523772 2.4878820000 1.2726490000 0.2594110000 0.0000050000 0.9421920000 0.0081940000 110208756 0 1785282560 3.9400949478 3.8708338737 5.2245101929 859 34.3200000000 0.0125487726 0.0115059111 0.0174177960 0.0133553538 2.6121050000 1.2836610000 0.2627630000 0.1077270000 0.9443830000 0.0081940000 110210430 0 1786933248 3.9401814938 3.8688435555 5.2226910591 860 34.3600000000 0.0125818551 0.0115071622 0.0174177960 0.0133538401 2.4918720000 1.2703660000 0.2617380000 0.0000050000 0.9461810000 0.0082340000 110212104 0 1784647680 3.9411365986 3.8665068150 5.2214188576 861 34.4000000000 0.0127205420 0.0115085714 0.0174177960 0.0133506662 3.5879700000 1.3085300000 0.2476830000 0.1082080000 0.9505040000 0.9677320000 110213778 0 1786028032 3.9431710243 3.8654670715 5.2207584381 862 34.4400000000 0.0127039142 0.0115099582 0.0174177960 0.0133602675 2.5017400000 1.2708010000 0.2581370000 0.0000050000 0.9546120000 0.0082410000 110215452 0 1787957248 3.9447224140 3.8622865677 5.2201914787 863 34.4800000000 0.0127047282 0.0115113426 0.0174177960 0.0133700482 2.6199780000 1.2706400000 0.2711460000 0.1075450000 0.9571320000 0.0082320000 110217126 0 1785020416 3.9461388588 3.8584859371 5.2198433876 864 34.5200000000 0.0127473669 0.0115127732 0.0174177960 0.0133751986 2.4679050000 1.2731340000 0.2146300000 0.0000050000 0.9665900000 0.0082850000 110218800 0 1786679296 3.9462711811 3.8588731289 5.2174510956 865 34.5600000000 0.0128140943 0.0115142776 0.0174177960 0.0133803148 3.6010360000 1.2724540000 0.2720500000 0.1076540000 0.9626310000 0.9809080000 110220474 0 1785774080 3.9476432800 3.8577446938 5.2160692215 866 34.6000000000 0.0128401984 0.0115158087 0.0174177960 0.0133803348 2.5096470000 1.2787170000 0.2506450000 0.0000050000 0.9666840000 0.0081930000 110222148 0 1787424768 3.9487407207 3.8535876274 5.2155394554 867 34.6400000000 0.0130185876 0.0115175420 0.0174177960 0.0133749901 2.6353370000 1.2726740000 0.2694060000 0.1074730000 0.9721910000 0.0082490000 110223822 0 1784537088 3.9493916035 3.8519842625 5.2145304680 868 34.6800000000 0.0130060799 0.0115192569 0.0174177960 0.0133690619 2.5374190000 1.2794680000 0.2694860000 0.0000040000 0.9747480000 0.0082630000 110225496 0 1786171392 3.9504373074 3.8510489464 5.2129507065 869 34.7200000000 0.0130095482 0.0115209718 0.0174177960 0.0133633340 3.6531050000 1.3076000000 0.2497030000 0.1072760000 0.9796220000 1.0035530000 110227170 0 1787949056 3.9513812065 3.8485569954 5.2122454643 870 34.7600000000 0.0129747121 0.0115226428 0.0174177960 0.0133569716 2.8223790000 1.2754490000 0.5543610000 0.0000040000 0.9789650000 0.0082720000 110228844 0 1785282560 3.9526290894 3.8459591866 5.2116298676 871 34.8000000000 0.0129418187 0.0115242722 0.0174177960 0.0133524705 2.6370520000 1.2717740000 0.2583010000 0.1069710000 0.9863110000 0.0081850000 110230518 0 1786916864 3.9532892704 3.8425004482 5.2108530998 872 34.8400000000 0.0129063288 0.0115258571 0.0174177960 0.0133473601 2.5250720000 1.2763900000 0.2554620000 0.0000050000 0.9796760000 0.0082130000 110232192 0 1784918016 3.9535119534 3.8384957314 5.2108192444 873 34.8800000000 0.0128632132 0.0115273890 0.0174177960 0.0133401760 3.5786240000 1.2726200000 0.2101090000 0.1070460000 0.9860200000 0.9971370000 110233866 0 1786298368 3.9541749954 3.8359193802 5.2103667259 874 34.9200000000 0.0127465576 0.0115287839 0.0174177960 0.0133334194 2.5269530000 1.2752540000 0.2576720000 0.0000050000 0.9802750000 0.0082270000 110235540 0 1785544704 3.9544177055 3.8339779377 5.2092165947 875 34.9600000000 0.0126462262 0.0115300610 0.0174177960 0.0133271437 2.7739060000 1.2802400000 0.3922830000 0.1068960000 0.9807920000 0.0081910000 110237214 0 1787179008 3.9541568756 3.8306443691 5.2085728645 876 35.0000000000 0.0126167815 0.0115313016 0.0174177960 0.0133197029 2.5210280000 1.2713120000 0.2546580000 0.0000050000 0.9812960000 0.0083250000 110238888 0 1785171968 3.9551856518 3.8279652596 5.2085208893 877 35.0400000000 0.0124624474 0.0115323633 0.0174177960 0.0133122241 3.9221840000 1.3088010000 0.5205950000 0.1069060000 0.9815250000 0.9989460000 110240562 0 1786679296 3.9548354149 3.8255298138 5.2072439194 878 35.0800000000 0.0124266585 0.0115333819 0.0174177960 0.0133049775 2.5300180000 1.2732020000 0.2605920000 0.0000050000 0.9824760000 0.0082620000 110242236 0 1785028608 3.9546792507 3.8217983246 5.2063407898 879 35.1200000000 0.0124976682 0.0115344789 0.0174177960 0.0132974478 2.6285910000 1.2714220000 0.2535590000 0.1068940000 0.9831190000 0.0082340000 110243910 0 1786789888 3.9551954269 3.8187930584 5.2058377266 880 35.1600000000 0.0124455811 0.0115355142 0.0174177960 0.0132909271 2.4848570000 1.2739090000 0.2138330000 0.0000050000 0.9835270000 0.0081940000 110245584 0 1784791040 3.9549372196 3.8140823841 5.2033944130 881 35.2000000000 0.0121966023 0.0115362646 0.0174177960 0.0132839497 3.6341910000 1.2749300000 0.2645960000 0.1070330000 0.9820520000 1.0001330000 110247258 0 1786281984 3.9548280239 3.8124976158 5.2017068863 882 35.2400000000 0.0121826883 0.0115369975 0.0174177960 0.0132782796 2.5212590000 1.2782020000 0.2462710000 0.0000050000 0.9829810000 0.0081820000 110248932 0 1785790464 3.9547894001 3.8097310066 5.2004895210 883 35.2800000000 0.0122721279 0.0115378301 0.0174177960 0.0132745660 2.5883520000 1.2750850000 0.2100930000 0.1070650000 0.9824100000 0.0082390000 110250606 0 1787187200 3.9542620182 3.8071029186 5.1990294456 884 35.3200000000 0.0121611189 0.0115385351 0.0174177960 0.0132739800 2.5383960000 1.2835480000 0.2587480000 0.0000050000 0.9823510000 0.0081780000 110252280 0 1785028608 3.9537854195 3.8049089909 5.1971092224 885 35.3600000000 0.0120783113 0.0115391451 0.0174177960 0.0132753349 3.6517190000 1.3049890000 0.2500290000 0.1072390000 0.9859700000 0.9979730000 110253954 0 1786535936 3.9534804821 3.8027656078 5.1956124306 886 35.4000000000 0.0120167071 0.0115396841 0.0174177960 0.0132779029 2.5285360000 1.2762340000 0.2607180000 0.0000050000 0.9777300000 0.0082330000 110255628 0 1785815040 3.9524471760 3.8009676933 5.1939859390 887 35.4400000000 0.0119901365 0.0115401919 0.0174177960 0.0132810478 2.6778440000 1.2723300000 0.3085770000 0.1074190000 0.9758480000 0.0082620000 110257302 0 1787559936 3.9520106316 3.8000540733 5.1923670769 888 35.4800000000 0.0119389864 0.0115406410 0.0174177960 0.0132830802 2.5179310000 1.2738940000 0.2591950000 0.0000050000 0.9712250000 0.0082270000 110258976 0 1785163776 3.9505131245 3.7977542877 5.1905546188 889 35.5200000000 0.0118760578 0.0115410183 0.0174177960 0.0132915040 3.5813880000 1.3015740000 0.2126800000 0.1080000000 0.9680540000 0.9855470000 110260650 0 1786679296 3.9500200748 3.7962620258 5.1890182495 890 35.5600000000 0.0118209859 0.0115413329 0.0174177960 0.0132977445 2.5178020000 1.2755550000 0.2581260000 0.0000050000 0.9703350000 0.0082910000 110262324 0 1785171968 3.9490995407 3.7958810329 5.1873459816 891 35.6000000000 0.0117495917 0.0115415666 0.0174177960 0.0133020453 2.6143610000 1.2725300000 0.2584180000 0.1081800000 0.9614690000 0.0082710000 110263998 0 1786789888 3.9473676682 3.7926082611 5.1860046387 892 35.6400000000 0.0117482813 0.0115417983 0.0174177960 0.0133133347 2.5071150000 1.2737100000 0.2570710000 0.0000050000 0.9626150000 0.0081720000 110265672 0 1784791040 3.9460957050 3.7915670872 5.1841721535 893 35.6800000000 0.0117060719 0.0115419823 0.0174177960 0.0133243282 3.5131440000 1.2738990000 0.1996960000 0.1085860000 0.9525000000 0.9729910000 110267346 0 1786298368 3.9444389343 3.7909970284 5.1823801994 894 35.7200000000 0.0115899080 0.0115420359 0.0174177960 0.0133352547 2.4557210000 1.2745220000 0.2169610000 0.0000050000 0.9505800000 0.0082050000 110269020 0 1785774080 3.9428939819 3.7885036469 5.1811919212 895 35.7600000000 0.0115689868 0.0115420660 0.0174177960 0.0133515470 2.5979670000 1.2749270000 0.2573480000 0.1089830000 0.9428550000 0.0081760000 110270694 0 1787060224 3.9413125515 3.7862565517 5.1800990105 896 35.8000000000 0.0115124946 0.0115420330 0.0174177960 0.0133745543 2.4424850000 1.2802740000 0.2110490000 0.0000050000 0.9374990000 0.0082280000 110272368 0 1785012224 3.9404060841 3.7861697674 5.1786231995 897 35.8400000000 0.0114953360 0.0115419810 0.0174177960 0.0133896446 3.4965780000 1.3010740000 0.2003740000 0.1094610000 0.9314770000 0.9486200000 110274042 0 1786662912 3.9399704933 3.7863845825 5.1779170036 898 35.8800000000 0.0115582021 0.0115419990 0.0174177960 0.0133987018 2.4293320000 1.2798360000 0.2102210000 0.0000050000 0.9255200000 0.0082140000 110275716 0 1785790464 3.9386510849 3.7856976986 5.1766958237 899 35.9200000000 0.0115483040 0.0115420060 0.0174177960 0.0134067668 2.5321900000 1.2760950000 0.2103750000 0.1099170000 0.9221480000 0.0081630000 110277390 0 1787559936 3.9386386871 3.7853231430 5.1768293381 900 35.9600000000 0.0115456907 0.0115420101 0.0174177960 0.0134108177 2.4075720000 1.2803150000 0.1995440000 0.0000050000 0.9139280000 0.0082960000 110279064 0 1784799232 3.9378020763 3.7848703861 5.1761255264 901 36.0000000000 0.0115147745 0.0115419799 0.0174177960 0.0134171049 3.4480220000 1.2752460000 0.2105260000 0.1102490000 0.9117590000 0.9344570000 110280738 0 1786306560 3.9369571209 3.7841725349 5.1752142906 902 36.0400000000 0.0115148211 0.0115419498 0.0174177960 0.0134267362 2.4329190000 1.2700390000 0.2465580000 0.0000050000 0.9025170000 0.0082500000 110282412 0 1785663488 3.9358961582 3.7838315964 5.1745605469 903 36.0800000000 0.0115613928 0.0115419713 0.0174177960 0.0134369697 2.5454680000 1.2731370000 0.2459110000 0.1106270000 0.9020850000 0.0082430000 110284086 0 1787297792 3.9341332912 3.7835547924 5.1730403900 904 36.1200000000 0.0115881022 0.0115420224 0.0174177960 0.0134533434 2.3811970000 1.2742210000 0.2014250000 0.0000040000 0.8916970000 0.0081830000 110285760 0 1785171968 3.9332199097 3.7824916840 5.1725530624 905 36.1600000000 0.0115819573 0.0115420665 0.0174177960 0.0134761038 3.4339790000 1.2763840000 0.2463270000 0.1109790000 0.8911080000 0.9036330000 110287434 0 1786662912 3.9318370819 3.7821404934 5.1714119911 906 36.2000000000 0.0116061606 0.0115421372 0.0174177960 0.0134993761 2.4248270000 1.2737650000 0.2578670000 0.0000050000 0.8793510000 0.0081770000 110289108 0 1784774656 3.9307274818 3.7822241783 5.1706452370 907 36.2400000000 0.0116136549 0.0115422161 0.0174177960 0.0135200514 2.5246150000 1.2788060000 0.2467500000 0.1113830000 0.8738790000 0.0082720000 110290782 0 1786298368 3.9295830727 3.7808017731 5.1702151299 908 36.2800000000 0.0116340602 0.0115423172 0.0174177960 0.0135370574 2.4148900000 1.2735640000 0.2568130000 0.0000050000 0.8704830000 0.0082830000 110292456 0 1785774080 3.9281294346 3.7811534405 5.1695523262 909 36.3200000000 0.0116510345 0.0115424368 0.0174177960 0.0135462461 3.3857190000 1.2777650000 0.2454600000 0.1115670000 0.8639920000 0.8814290000 110294130 0 1787170816 3.9266295433 3.7809007168 5.1689004898 910 36.3600000000 0.0116675207 0.0115425743 0.0174177960 0.0135536095 2.3583680000 1.2725940000 0.2117280000 0.0000050000 0.8601940000 0.0082090000 110295804 0 1784901632 3.9249341488 3.7803888321 5.1683168411 911 36.4000000000 0.0116646597 0.0115427083 0.0174177960 0.0135602326 2.4614680000 1.2817720000 0.2001720000 0.1118700000 0.8538260000 0.0082510000 110297478 0 1786535936 3.9238629341 3.7792701721 5.1680746078 912 36.4400000000 0.0116556725 0.0115428322 0.0174177960 0.0135664339 2.3829880000 1.2747070000 0.2458250000 0.0000050000 0.8486160000 0.0082630000 110299152 0 1785688064 3.9221773148 3.7779314518 5.1678977013 913 36.4800000000 0.0116775408 0.0115429797 0.0174177960 0.0136434825 3.3057550000 1.2840620000 0.2120940000 0.1122610000 0.8365040000 0.8551740000 110300826 0 1787449344 3.9188370705 3.7777941227 5.1665415764 914 36.5200000000 0.0116631575 0.0115431112 0.0174177960 0.0136622806 2.3406870000 1.2737340000 0.2118670000 0.0000060000 0.8411990000 0.0081560000 110302500 0 1785044992 3.9177927971 3.7772958279 5.1664748192 915 36.5600000000 0.0116857709 0.0115432671 0.0174177960 0.0136796204 2.4399780000 1.2749970000 0.2119170000 0.1126460000 0.8265700000 0.0082860000 110304174 0 1786679296 3.9160275459 3.7770905495 5.1663703918 916 36.6000000000 0.0116858520 0.0115434228 0.0174177960 0.0136958954 2.3700690000 1.2751610000 0.2580660000 0.0000050000 0.8230740000 0.0081760000 110305848 0 1784647680 3.9143030643 3.7770040035 5.1660184860 917 36.6400000000 0.0116896732 0.0115435822 0.0174177960 0.0137075547 3.2641950000 1.2827420000 0.2108660000 0.1129560000 0.8168310000 0.8351330000 110307522 0 1786281984 3.9124643803 3.7766387463 5.1657562256 918 36.6800000000 0.0117147509 0.0115437687 0.0174177960 0.0137198736 2.3128450000 1.2715080000 0.2105410000 0.0000050000 0.8161910000 0.0088460000 110309196 0 1785663488 3.9109528065 3.7761445045 5.1656546593 919 36.7200000000 0.0116634127 0.0115438989 0.0174177960 0.0137364784 2.4577170000 1.2689410000 0.2569650000 0.1130290000 0.8048690000 0.0083160000 110310870 0 1787330560 3.9094102383 3.7755742073 5.1656327248 920 36.7600000000 0.0117050465 0.0115440741 0.0174177960 0.0137542449 2.3027420000 1.2728420000 0.2107420000 0.0000050000 0.8051950000 0.0083000000 110312544 0 1784647680 3.9077756405 3.7758672237 5.1652030945 921 36.8000000000 0.0116978036 0.0115442410 0.0174177960 0.0137634955 3.2098160000 1.2753450000 0.2108460000 0.1133770000 0.7930200000 0.8115370000 110314218 0 1786281984 3.9061937332 3.7751984596 5.1654224396 922 36.8400000000 0.0117434310 0.0115444570 0.0174177960 0.0137709579 2.2956260000 1.2784580000 0.2159330000 0.0000040000 0.7873080000 0.0081810000 110315892 0 1785536512 3.9044837952 3.7744913101 5.1659026146 923 36.8800000000 0.0117521761 0.0115446821 0.0174177960 0.0137766847 2.4684890000 1.3060820000 0.2555080000 0.1136520000 0.7792720000 0.0082410000 110317566 0 1787187200 3.9026608467 3.7741138935 5.1666283607 924 36.9200000000 0.0117608653 0.0115449160 0.0174177960 0.0137794329 2.3225160000 1.2750750000 0.2555710000 0.0000050000 0.7779980000 0.0082200000 110319240 0 1784537088 3.9008522034 3.7736022472 5.1667914391 925 36.9600000000 0.0117495600 0.0115451373 0.0174177960 0.0137827645 3.1512270000 1.2729600000 0.2096660000 0.1139420000 0.7651330000 0.7838840000 110320914 0 1786290176 3.8991122246 3.7735478878 5.1669783592 926 37.0000000000 0.0117207747 0.0115453269 0.0174177960 0.0137868909 2.3066390000 1.2772170000 0.2553450000 0.0000060000 0.7601540000 0.0083120000 110322588 0 1787830272 3.8975396156 3.7733852863 5.1669626236 927 37.0400000000 0.0115636541 0.0115453467 0.0174177960 0.0137929114 2.3609600000 1.2693600000 0.2102060000 0.1142460000 0.7531780000 0.0081680000 110324262 0 1784901632 3.8962705135 3.7724988461 5.1673521996 928 37.0800000000 0.0113551207 0.0115451417 0.0174177960 0.0138043523 2.3028910000 1.2811020000 0.2615760000 0.0000060000 0.7463680000 0.0081790000 110325936 0 1786314752 3.8945686817 3.7727608681 5.1673722267 929 37.1200000000 0.0112087559 0.0115447796 0.0174177960 0.0138153816 3.1472420000 1.2733890000 0.2562380000 0.1145340000 0.7391940000 0.7581750000 110327610 0 1785520128 3.8929541111 3.7733738422 5.1667833328 930 37.1600000000 0.0110924281 0.0115442932 0.0174177960 0.0138237156 2.3469060000 1.3081410000 0.2922400000 0.0000040000 0.7325460000 0.0081750000 110329284 0 1787297792 3.8911790848 3.7736742496 5.1661329269 931 37.2000000000 0.0109358486 0.0115436397 0.0174177960 0.0138308632 2.3822040000 1.2719760000 0.2569240000 0.1148370000 0.7244400000 0.0082270000 110330958 0 1784647680 3.8895304203 3.7731537819 5.1658787727 932 37.2400000000 0.0107560512 0.0115427946 0.0174177960 0.0138474421 2.2726540000 1.2814130000 0.2577710000 0.0000050000 0.7195130000 0.0081810000 110332632 0 1786155008 3.8876817226 3.7727234364 5.1650300026 933 37.2800000000 0.0105261160 0.0115417049 0.0174177960 0.0138738193 3.0922860000 1.2731340000 0.2576440000 0.1160790000 0.7098560000 0.7289240000 110334306 0 1785311232 3.8858642578 3.7730841637 5.1635470390 934 37.3200000000 0.0104311565 0.0115405159 0.0174177960 0.0138993949 2.2536580000 1.2789540000 0.2583120000 0.0000050000 0.7024110000 0.0082730000 110335980 0 1785012224 3.8838615417 3.7743265629 5.1627616882 935 37.3600000000 0.0103597092 0.0115392530 0.0174177960 0.0139143217 2.3536570000 1.2731750000 0.2572320000 0.1158740000 0.6935380000 0.0081710000 110337654 0 1786425344 3.8820559978 3.7747695446 5.1612353325 936 37.4000000000 0.0103795789 0.0115380141 0.0174177960 0.0139256862 2.2421330000 1.2799950000 0.2584630000 0.0000050000 0.6896520000 0.0081850000 110339328 0 1785425920 3.8805103302 3.7750372887 5.1606187820 937 37.4400000000 0.0103907483 0.0115367897 0.0174177960 0.0139335001 3.0238050000 1.2734280000 0.2566120000 0.1161010000 0.6765830000 0.6953860000 110341002 0 1787043840 3.8789565563 3.7766144276 5.1599721909 938 37.4800000000 0.0104374839 0.0115356177 0.0174177960 0.0139369954 2.2151090000 1.2759050000 0.2573270000 0.0000050000 0.6677530000 0.0081750000 110342676 0 1784807424 3.8776123524 3.7767908573 5.1595764160 939 37.5200000000 0.0104863448 0.0115345003 0.0174177960 0.0139412677 2.3208260000 1.2739010000 0.2568030000 0.1172030000 0.6589250000 0.0081710000 110344350 0 1786433536 3.8762459755 3.7769160271 5.1591181755 940 37.5600000000 0.0104852365 0.0115333840 0.0174177960 0.0139432347 2.2129080000 1.2743810000 0.2731870000 0.0000050000 0.6513630000 0.0082230000 110346024 0 1785274368 3.8748581409 3.7771484852 5.1586661339 941 37.6000000000 0.0104859173 0.0115322709 0.0174177960 0.0139446228 2.9656450000 1.2719520000 0.2670660000 0.1171840000 0.6422770000 0.6614560000 110347698 0 1786814464 3.8734726906 3.7776665688 5.1573214531 942 37.6400000000 0.0105380015 0.0115312154 0.0174177960 0.0139461180 2.1799040000 1.2745870000 0.2566780000 0.0000050000 0.6346930000 0.0081680000 110349372 0 1784647680 3.8721249104 3.7779409885 5.1560115814 943 37.6800000000 0.0105472934 0.0115301720 0.0174177960 0.0139472519 2.3087660000 1.2951390000 0.2565760000 0.1173330000 0.6257500000 0.0082390000 110351046 0 1786281984 3.8710074425 3.7775428295 5.1551876068 944 37.7200000000 0.0105656004 0.0115291502 0.0174177960 0.0139495454 2.1769030000 1.2735700000 0.2678260000 0.0000050000 0.6214560000 0.0083000000 110352720 0 1785647104 3.8698213100 3.7771925926 5.1548910141 945 37.7600000000 0.0105666025 0.0115281316 0.0174177960 0.0139526305 2.8865390000 1.2695940000 0.2563270000 0.1179390000 0.6084330000 0.6284710000 110354394 0 1787187200 3.8683624268 3.7774949074 5.1561536789 946 37.8000000000 0.0105798906 0.0115271293 0.0174177960 0.0139556948 2.1588150000 1.2691670000 0.2678800000 0.0000050000 0.6076500000 0.0082540000 110356068 0 1784410112 3.8671052456 3.7770595551 5.1555953026 947 37.8400000000 0.0105904918 0.0115261402 0.0174177960 0.0139575752 2.2632760000 1.2709480000 0.2671570000 0.1180150000 0.5932720000 0.0081590000 110357742 0 1785901056 3.8655643463 3.7774443626 5.1552128792 948 37.8800000000 0.0106993625 0.0115252681 0.0174177960 0.0139572993 2.1421870000 1.2692100000 0.2671820000 0.0000050000 0.5864170000 0.0136170000 110359416 0 1787822080 3.8642165661 3.7775425911 5.1568174362 949 37.9200000000 0.0107979644 0.0115245017 0.0174177960 0.0139584980 2.8297970000 1.2711980000 0.2585320000 0.1181420000 0.5782060000 0.5978660000 110361090 0 1784520704 3.8628559113 3.7834441662 5.1657028198 950 37.9600000000 0.0110320309 0.0115239833 0.0174177960 0.0139591545 2.1135860000 1.2701410000 0.2577140000 0.0000050000 0.5716810000 0.0082840000 110362764 0 1786028032 3.8610429764 3.7880854607 5.1752367020 951 38.0000000000 0.0110554313 0.0115234906 0.0174177960 0.0139615764 2.2315980000 1.2764600000 0.2586810000 0.1182560000 0.5642380000 0.0081580000 110364438 0 1787949056 3.8597352505 3.7898876667 5.1785526276 952 38.0400000000 0.0111277644 0.0115230749 0.0174177960 0.0139625346 2.1443890000 1.2709260000 0.3017420000 0.0000050000 0.5577080000 0.0082200000 110366112 0 1784672256 3.8586640358 3.7908213139 5.1786570549 953 38.0800000000 0.0111883981 0.0115227237 0.0174177960 0.0139595659 2.8348520000 1.2762860000 0.3119040000 0.1185590000 0.5509460000 0.5713450000 110367786 0 1786163200 3.8575186729 3.7909338474 5.1785168648 954 38.1200000000 0.0110286037 0.0115222058 0.0174177960 0.0139582137 2.1669580000 1.2924350000 0.3130820000 0.0000050000 0.5467920000 0.0082370000 110369460 0 1788067840 3.8564605713 3.7911539078 5.1798596382 955 38.1600000000 0.0109366085 0.0115215926 0.0174177960 0.0139598544 2.3054670000 1.2723850000 0.3600200000 0.1192220000 0.5396320000 0.0083010000 110371134 0 1784655872 3.8556609154 3.7904894352 5.1778664589 956 38.2000000000 0.0108200125 0.0115208587 0.0174177960 0.0139611318 2.1741750000 1.2665470000 0.3584870000 0.0000050000 0.5350130000 0.0082580000 110372808 0 1786028032 3.8543674946 3.7910673618 5.1778583527 957 38.2400000000 0.0106658628 0.0115199653 0.0174177960 0.0139595418 2.7381400000 1.2761010000 0.2554950000 0.1202890000 0.5300500000 0.5503490000 110374482 0 1788059648 3.8530461788 3.7914288044 5.1764774323 958 38.2800000000 0.0106015131 0.0115190066 0.0174177960 0.0139568462 2.1214770000 1.2699140000 0.3133240000 0.0000040000 0.5240910000 0.0081610000 110376156 0 1784647680 3.8522148132 3.7895221710 5.1722784042 959 38.3200000000 0.0102924174 0.0115177276 0.0174177960 0.0139559173 2.2470090000 1.2817670000 0.3129230000 0.1198080000 0.5183980000 0.0082880000 110377830 0 1786155008 3.8510115147 3.7891116142 5.1721320152 960 38.3600000000 0.0095993225 0.0115157292 0.0174177960 0.0139555089 2.2553010000 1.2677370000 0.4603480000 0.0000050000 0.5130860000 0.0081770000 110379504 0 1788059648 3.8495454788 3.7905914783 5.1759223938 961 38.4000000000 0.0099353883 0.0115140848 0.0174177960 0.0139543158 2.9857320000 1.2716290000 0.5509920000 0.1198280000 0.5083610000 0.5290530000 110381178 0 1784520704 3.8484280109 3.7901022434 5.1787447929 962 38.4400000000 0.0165690333 0.0115193394 0.0174177960 0.0139568320 2.1021520000 1.2690580000 0.3164040000 0.0000050000 0.5024720000 0.0081610000 110382852 0 1785901056 3.8469550610 3.7899858952 5.1885423660 963 38.4800000000 0.0415582173 0.0115505324 0.0415582173 0.0139855336 2.4587950000 1.2693150000 0.5572150000 0.1195650000 0.4985680000 0.0082670000 110384526 0 1787932672 3.8453590870 3.7888474464 5.2124958038 964 38.5200000000 0.0747959316 0.0116161397 0.0747959316 0.0140462839 2.3137990000 1.2675180000 0.5391110000 0.0000050000 0.4929360000 0.0082110000 110386200 0 1784664064 3.8433098793 3.7907130718 5.2470808029 965 38.5600000000 0.1054028720 0.0117133280 0.1054028720 0.0140892495 2.9530260000 1.2720490000 0.5576870000 0.1193490000 0.4882840000 0.5097810000 110387874 0 1786028032 3.8416299820 3.7910032272 5.2761821747 966 38.6000000000 0.1272954196 0.0118329782 0.1272954196 0.0141132989 2.3191720000 1.2708480000 0.5517670000 0.0000040000 0.4823720000 0.0082540000 110389548 0 1788059648 3.8401415348 3.7914431095 5.2974863052 967 38.6400000000 0.1406409442 0.0119661819 0.1406409442 0.0141203348 2.4502950000 1.2797880000 0.5594710000 0.1188730000 0.4780260000 0.0082270000 110391222 0 1784545280 3.8385481834 3.7925388813 5.3131422997 968 38.6800000000 0.1919181943 0.0121520827 0.1919181943 0.0142581916 2.0160440000 1.2683470000 0.2611920000 0.0000050000 0.4723430000 0.0082410000 110392896 0 1786036224 3.8362963200 3.7920484543 5.3620243073 969 38.7200000000 0.2394323200 0.0123866340 0.2394323200 0.0143685868 2.6115730000 1.2658540000 0.2577570000 0.1181390000 0.4741260000 0.4896970000 110394570 0 1787932672 3.8339719772 3.7933936119 5.4099693298 970 38.7600000000 0.2906818986 0.0126735364 0.2906818986 0.0144898179 2.0048460000 1.2690380000 0.2576740000 0.0000050000 0.4639060000 0.0081670000 110396244 0 1784664064 3.8318912983 3.7937881947 5.4597301483 971 38.8000000000 0.3439143896 0.0130146701 0.3439143896 0.0146215756 2.0704170000 1.2650470000 0.2148290000 0.1173580000 0.4590160000 0.0082280000 110397918 0 1786155008 3.8295180798 3.7932584286 5.5107994080 972 38.8400000000 0.3963143528 0.0134090113 0.3963143528 0.0147391548 2.0057740000 1.2750330000 0.2599480000 0.0000050000 0.4565340000 0.0082550000 110399592 0 1788076032 3.8270692825 3.7941887379 5.5627288818 973 38.8800000000 0.4485793114 0.0138562573 0.4485793114 0.0148582207 2.5738740000 1.2682970000 0.2586760000 0.1166850000 0.4512930000 0.4729640000 110401266 0 1784774656 3.8251013756 3.7941212654 5.6137804985 974 38.9200000000 0.4975744784 0.0143528879 0.4975744784 0.0149571212 1.9444500000 1.2705710000 0.2118960000 0.0000050000 0.4476840000 0.0081710000 110402940 0 1786171392 3.8229806423 3.7949860096 5.6629495621 975 38.9600000000 0.5490197539 0.0149012642 0.5490197539 0.0150673102 2.0555800000 1.2698280000 0.2118440000 0.1161980000 0.4435520000 0.0082250000 110404614 0 1787932672 3.8208448887 3.7958345413 5.7138366699 976 39.0000000000 0.5964893103 0.0154971536 0.5964893103 0.0151612979 1.9386740000 1.2668920000 0.2117380000 0.0000050000 0.4458370000 0.0082190000 110406288 0 1784410112 3.8187971115 3.7950525284 5.7596545219 977 39.0400000000 0.6427427530 0.0161391654 0.6427427530 0.0152403851 2.4996900000 1.2688470000 0.2109820000 0.1157960000 0.4381960000 0.4598100000 110407962 0 1785774080 3.8168296814 3.7959382534 5.8053870201 978 39.0800000000 0.6898359656 0.0168280170 0.6898359656 0.0153307372 1.9296070000 1.2683460000 0.2115300000 0.0000050000 0.4354880000 0.0082180000 110409636 0 1787932672 3.8150260448 3.7960162163 5.8505158424 979 39.1200000000 0.7406005859 0.0175673148 0.7406005859 0.0154363074 2.0476790000 1.2720650000 0.2120080000 0.1167020000 0.4327010000 0.0082140000 110411310 0 1784537088 3.8132095337 3.7949464321 5.8984661102 980 39.1600000000 0.7878982425 0.0183533668 0.7878982425 0.0155237103 1.9255010000 1.2713230000 0.2104300000 0.0000060000 0.4294820000 0.0082140000 110412984 0 1785901056 3.8112566471 3.7954390049 5.9440169334 981 39.2000000000 0.8336387277 0.0191844426 0.8336387277 0.0156087030 2.4837650000 1.2738260000 0.2118760000 0.1150620000 0.4275910000 0.4493960000 110414658 0 1787932672 3.8095488548 3.7953147888 5.9891414642 982 39.2400000000 0.8294855356 0.0200095964 0.8336387277 0.0156042203 1.9154640000 1.2634940000 0.2110510000 0.0000050000 0.4265970000 0.0081980000 110416332 0 1784393728 3.8089616299 3.7956573963 5.9832410812 983 39.2800000000 0.8779904246 0.0208824152 0.8779904246 0.0156949373 2.0367910000 1.2686810000 0.2095900000 0.1154260000 0.4288790000 0.0082290000 110418006 0 1786036224 3.8071589470 3.7964062691 6.0302143097 984 39.3200000000 0.9241600633 0.0218003803 0.9241600633 0.0157821669 1.9192960000 1.2704440000 0.2127340000 0.0000050000 0.4218440000 0.0082610000 110419680 0 1787813888 3.8056030273 3.7966928482 6.0754451752 985 39.3600000000 0.9228019118 0.0227151026 0.9241600633 0.0157751830 2.4483110000 1.2640640000 0.2003930000 0.1157290000 0.4210700000 0.4410620000 110421354 0 1784647680 3.8053398132 3.7971060276 6.0714483261 986 39.4000000000 0.9720640182 0.0236779311 0.9720640182 0.0158818887 1.9606080000 1.2736570000 0.2555010000 0.0000050000 0.4172510000 0.0081980000 110423028 0 1786281984 3.8039205074 3.7976965904 6.1190829277 987 39.4400000000 0.9620243311 0.0246286367 0.9720640182 0.0158778720 2.0242540000 1.2669270000 0.2104840000 0.1166450000 0.4159310000 0.0082670000 110424702 0 1785520128 3.8043341637 3.7975881100 6.1073684692 988 39.4800000000 1.0103716850 0.0256263524 1.0103716850 0.0159763016 1.9054490000 1.2625030000 0.2149620000 0.0000050000 0.4137560000 0.0082260000 110426376 0 1786916864 3.8028194904 3.7981226444 6.1542110443 989 39.5200000000 1.0624151230 0.0266746726 1.0624151230 0.0160837974 2.4938630000 1.2692560000 0.2541270000 0.1164620000 0.4122910000 0.4356030000 110428050 0 1784266752 3.8013949394 3.7981507778 6.2036418915 990 39.5600000000 1.0665631294 0.0277250650 1.0665631294 0.0160775209 1.9047270000 1.2668900000 0.2123460000 0.0000050000 0.4112250000 0.0082080000 110429724 0 1785774080 3.8012895584 3.7987911701 6.2065610886 991 39.6000000000 1.1169528961 0.0288241849 1.1169528961 0.0161800996 2.0182320000 1.2714620000 0.2062370000 0.1166250000 0.4095360000 0.0082620000 110431398 0 1787678720 3.7997288704 3.7991101742 6.2542519569 992 39.6400000000 1.1262063980 0.0299304170 1.1262063980 0.0161769824 1.8905140000 1.2669490000 0.2008900000 0.0000060000 0.4082650000 0.0082060000 110433072 0 1784410112 3.7992289066 3.7997093201 6.2614741325 993 39.6800000000 1.1670464277 0.0310755489 1.1670464277 0.0162416140 2.4945820000 1.2793340000 0.2548840000 0.1168180000 0.4081230000 0.4292990000 110434746 0 1785774080 3.7978720665 3.7997183800 6.3004212379 994 39.7200000000 1.1669607162 0.0322182906 1.1670464277 0.0162344780 1.8901010000 1.2708920000 0.1969620000 0.0000050000 0.4079360000 0.0081450000 110436420 0 1787678720 3.7977507114 3.7994546890 6.2967967987 995 39.7600000000 1.1601992846 0.0333519398 1.1670464277 0.0162306214 2.0239540000 1.2690420000 0.2108160000 0.1179960000 0.4118440000 0.0082040000 110438094 0 1784393728 3.7972855568 3.8014674187 6.2869000435 996 39.8000000000 1.1986936331 0.0345219616 1.1986936331 0.0162947010 1.8937630000 1.2665670000 0.2071580000 0.0000060000 0.4057760000 0.0081580000 110439768 0 1785901056 3.7955732346 3.8034319878 6.3229246140 997 39.8400000000 1.2314360142 0.0357224772 1.2314360142 0.0163401668 2.4325210000 1.2662490000 0.2097310000 0.1180840000 0.4053020000 0.4269820000 110441442 0 1787678720 3.7943055630 3.8049015999 6.3540792465 998 39.8800000000 1.2143346071 0.0369034513 1.2314360142 0.0163440422 1.9013650000 1.2725850000 0.2100400000 0.0000060000 0.4044260000 0.0082030000 110443116 0 1784520704 3.7947521210 3.8061921597 6.3349051476 999 39.9200000000 1.2781933546 0.0381459837 1.2781933546 0.0165422011 2.0560240000 1.2652330000 0.2533710000 0.1186780000 0.4041970000 0.0081950000 110444790 0 1785901056 3.7917485237 3.8102734089 6.3940334320 1000 39.9600000000 1.3076769114 0.0394155146 1.3076769114 0.0165761585 1.8972730000 1.2626930000 0.2154370000 0.0000050000 0.4048620000 0.0081620000 110446464 0 1787830272 3.7905361652 3.8119876385 6.4216480255 1001 40.0000000000 1.2853047848 0.0406601592 1.3076769114 0.0165865223 2.4831440000 1.2630250000 0.2546110000 0.1193040000 0.4076740000 0.4322860000 110448138 0 1784291328 3.7910556793 3.8133642673 6.3968839645 1002 40.0400000000 1.3116791248 0.0419286412 1.3116791248 0.0166179429 1.8976550000 1.2685960000 0.2118690000 0.0000050000 0.4028800000 0.0082180000 110449812 0 1785655296 3.7892489433 3.8165125847 6.4210243225 1003 40.0800000000 1.3392897844 0.0432221219 1.3392897844 0.0166541409 2.0202850000 1.2719880000 0.2113030000 0.1192520000 0.4033380000 0.0081660000 110451486 0 1787551744 3.7881600857 3.8187310696 6.4469213486 1004 40.1200000000 1.3682967424 0.0445419174 1.3682967424 0.0166897891 1.8924490000 1.2631700000 0.2111660000 0.0000050000 0.4037740000 0.0082390000 110453160 0 1784647680 3.7871534824 3.8202571869 6.4724745750 1005 40.1600000000 1.3244564533 0.0458154642 1.3682967424 0.0167602654 2.4325740000 1.2709290000 0.2076140000 0.1200250000 0.4027700000 0.4250330000 110454834 0 1786028032 3.7888033390 3.8206512928 6.4278678894 1006 40.2000000000 1.3580985069 0.0471199205 1.3682967424 0.0168096646 1.9417050000 1.2682440000 0.2553540000 0.0000050000 0.4037140000 0.0082530000 110456508 0 1787805696 3.7865815163 3.8248679638 6.4587602615 1007 40.2400000000 1.3936164379 0.0484570571 1.3936164379 0.0168622993 2.0526880000 1.2655740000 0.2434690000 0.1203150000 0.4088350000 0.0081800000 110458182 0 1784410112 3.7855486870 3.8264923096 6.4907665253 1008 40.2800000000 1.4310389757 0.0498286661 1.4310389757 0.0169146415 1.8909160000 1.2646920000 0.2074680000 0.0000050000 0.4043720000 0.0082430000 110459856 0 1785774080 3.7843794823 3.8280873299 6.5258731842 1009 40.3200000000 1.3579696417 0.0511251388 1.4310389757 0.0171148254 2.4657320000 1.2647150000 0.2480290000 0.1213430000 0.4017470000 0.4236780000 110461530 0 1787678720 3.7872717381 3.8267533779 6.4499201775 1010 40.3600000000 1.3996275663 0.0524602897 1.4310389757 0.0171931647 1.9482790000 1.2665830000 0.2637790000 0.0000050000 0.4034240000 0.0081640000 110463204 0 1784410112 3.7844841480 3.8338773251 6.4878368378 1011 40.4000000000 1.4273709059 0.0538202409 1.4310389757 0.0172285894 2.0651010000 1.2660430000 0.2584900000 0.1219420000 0.4038740000 0.0082170000 110464878 0 1785774080 3.7835049629 3.8365347385 6.5117006302 1012 40.4400000000 1.4530273676 0.0552028566 1.4530273676 0.0172590931 1.8893060000 1.2640220000 0.2065760000 0.0000050000 0.4042990000 0.0082300000 110466552 0 1787695104 3.7824702263 3.8398404121 6.5343718529 1013 40.4800000000 1.4802222252 0.0566095885 1.4802222252 0.0172899929 2.4792830000 1.2628490000 0.2572890000 0.1222030000 0.4044040000 0.4262070000 110468226 0 1784393728 3.7813766003 3.8429090977 6.5589160919 1014 40.5200000000 1.5060453415 0.0580390123 1.5060453415 0.0173175297 1.9417990000 1.2611940000 0.2557650000 0.0000060000 0.4103940000 0.0082710000 110469900 0 1785901056 3.7800695896 3.8465857506 6.5824222565 1015 40.5600000000 1.5317747593 0.0594909687 1.5317747593 0.0173456744 2.1175540000 1.2659750000 0.3110370000 0.1227210000 0.4032630000 0.0082190000 110471574 0 1787805696 3.7784152031 3.8515012264 6.6058101654 1016 40.6000000000 1.3918834925 0.0608023787 1.5317747593 0.0180616080 1.9246100000 1.2623940000 0.2461660000 0.0000050000 0.4015670000 0.0082380000 110473248 0 1784291328 3.7847511768 3.8471229076 6.4644680023 1017 40.6400000000 1.4189832211 0.0621378564 1.5317747593 0.0181019546 2.4297870000 1.2653180000 0.2086100000 0.1237080000 0.4020670000 0.4236870000 110474922 0 1785782272 3.7805151939 3.8599622250 6.4884071350 1018 40.6800000000 1.4377046824 0.0634891008 1.5317747593 0.0181171541 2.0266630000 1.2607880000 0.3486290000 0.0000050000 0.4027600000 0.0082690000 110476596 0 1787576320 3.7795476913 3.8637742996 6.5049719810 1019 40.7200000000 1.4501532316 0.0648499096 1.5317747593 0.0181248159 2.1304360000 1.2667850000 0.3217620000 0.1240640000 0.4031780000 0.0081640000 110478270 0 1784655872 3.7786445618 3.8677539825 6.5152864456 1020 40.7600000000 1.4592454433 0.0662169640 1.5317747593 0.0181261538 1.9490030000 1.2625340000 0.2696080000 0.0000050000 0.4024650000 0.0081710000 110479944 0 1786171392 3.7777962685 3.8713481426 6.5228657722 1021 40.8000000000 1.4684840441 0.0675903892 1.5317747593 0.0181270428 2.4893750000 1.2687300000 0.2576930000 0.1242380000 0.4024780000 0.4299340000 110481618 0 1785520128 3.7768964767 3.8751854897 6.5299053192 1022 40.8400000000 1.4759010077 0.0689683839 1.5317747593 0.0181253938 1.9823990000 1.2617350000 0.3038220000 0.0000050000 0.4023260000 0.0081730000 110483292 0 1787314176 3.7759187222 3.8790555000 6.5360994339 1023 40.8800000000 1.4838407040 0.0703514458 1.5317747593 0.0181246509 2.0613720000 1.2614220000 0.2581980000 0.1246230000 0.4025080000 0.0081550000 110484966 0 1785028608 3.7748830318 3.8832800388 6.5428423882 1024 40.9200000000 1.4891664982 0.0717370074 1.5317747593 0.0181267865 1.9498310000 1.2637540000 0.2692690000 0.0000050000 0.4021060000 0.0082290000 110486640 0 1786662912 3.7741112709 3.8873150349 6.5464620590 1025 40.9600000000 1.4939320087 0.0731245147 1.5317747593 0.0181312114 2.4881200000 1.2639780000 0.2682190000 0.1246980000 0.4015560000 0.4231740000 110570234 0 1784901632 3.7734506130 3.8917329311 6.5498294830 1026 41.0000000000 1.5044040680 0.0745195240 1.5317747593 0.0181368733 1.8959710000 1.2666670000 0.2131710000 0.0000050000 0.4014690000 0.0081700000 110739844 0 1786408960 3.7721993923 3.8979945183 6.5575661659 1027 41.0400000000 1.5149768591 0.0759221115 1.5317747593 0.0181459325 2.0703490000 1.2615130000 0.2685900000 0.1249420000 0.4008420000 0.0082350000 110741518 0 1785393152 3.7711961269 3.9026119709 6.5659384727 1028 41.0800000000 1.5223342180 0.0773291272 1.5317747593 0.0181503894 2.0240250000 1.2583810000 0.3499440000 0.0000050000 0.4010840000 0.0082210000 110743192 0 1787043840 3.7704579830 3.9080009460 6.5718526840 1029 41.1200000000 1.5312092304 0.0787420330 1.5317747593 0.0181517278 2.5350470000 1.2640890000 0.3162830000 0.1252380000 0.4008500000 0.4223210000 110744866 0 1784758272 3.7695627213 3.9125952721 6.5785989761 1030 41.1600000000 1.5368129015 0.0801576358 1.5368129015 0.0181508624 1.9407580000 1.2595140000 0.2673450000 0.0000050000 0.3993920000 0.0082280000 110746540 0 1786281984 3.7689485550 3.9153831005 6.5822210312 1031 41.2000000000 1.5442221165 0.0815776789 1.5442221165 0.0181527496 2.0746820000 1.2678640000 0.2673850000 0.1257220000 0.3992550000 0.0082510000 110748214 0 1785647104 3.7680265903 3.9204244614 6.5873236656 1032 41.2400000000 1.5533180237 0.0830037839 1.5533180237 0.0181527387 2.2171830000 1.2595900000 0.5441460000 0.0000050000 0.3989290000 0.0082290000 110749888 0 1787035648 3.7673118114 3.9242675304 6.5945420265 1033 41.2800000000 1.5597145557 0.0844333200 1.5597145557 0.0181493622 2.6683510000 1.2621030000 0.4566250000 0.1258040000 0.3985140000 0.4190560000 110751562 0 1785401344 3.7666528225 3.9266331196 6.5995740891 1034 41.3200000000 1.5672812462 0.0858674089 1.5672812462 0.0181657997 2.1658040000 1.2613870000 0.4938540000 0.0000050000 0.3957210000 0.0082830000 110753236 0 1786830848 3.7657408714 3.9321563244 6.6038842201 1035 41.3600000000 1.5636903048 0.0872952571 1.5672812462 0.0181578336 2.1612280000 1.2616340000 0.3622770000 0.1264510000 0.3962840000 0.0082100000 110754910 0 1784791040 3.7656068802 3.9331352711 6.5992889404 1036 41.4000000000 1.5594398975 0.0887162461 1.5672812462 0.0181525892 2.2103350000 1.2605490000 0.5398170000 0.0000050000 0.3952460000 0.0081750000 110756584 0 1786314752 3.7651200294 3.9355614185 6.5932626724 1037 41.4400000000 1.5412915945 0.0901169938 1.5672812462 0.0181542008 2.7451030000 1.2630510000 0.5354640000 0.1260630000 0.3988390000 0.4152260000 110758258 0 1785663488 3.7649202347 3.9603199959 6.5725331306 1038 41.4800000000 1.5576679707 0.0915308194 1.5672812462 0.0181962574 2.2045770000 1.2605840000 0.5343410000 0.0000050000 0.3948330000 0.0081880000 110759932 0 1787203584 3.7636125088 3.9291744232 6.5890932083 1039 41.5200000000 1.5210409164 0.0929066713 1.5672812462 0.0182573652 2.3366670000 1.2590240000 0.5394080000 0.1261300000 0.3973530000 0.0081640000 110761606 0 1785044992 3.7645950317 3.9785528183 6.5478878021 1040 41.5600000000 1.5221389532 0.0942809331 1.5672812462 0.0182524826 1.9493870000 1.2593870000 0.2830790000 0.0000050000 0.3921490000 0.0081650000 110763280 0 1786568704 3.7645950317 3.9785528183 6.5478878021 1041 41.6000000000 1.6744582653 0.0957988748 1.6744582653 0.0209577208 2.7118120000 1.2610530000 0.5251570000 0.1253920000 0.3861470000 0.4075650000 110764954 0 1785790464 3.7610697746 3.7138545513 6.6975479126 1042 41.6400000000 1.9981929064 0.0976245889 1.9981929064 0.0257521871 2.0896640000 1.2674160000 0.4613680000 0.0000050000 0.3458850000 0.0082270000 110766628 0 1787441152 3.7557907104 3.3105514050 6.9483642578 1043 41.6800000000 1.9847053289 0.0994338705 1.9981929064 0.0259797747 2.2124680000 1.2607870000 0.4942860000 0.1233810000 0.3191880000 0.0082250000 110768302 0 1784918016 3.7579956055 3.2018320560 6.8971920013 1044 41.7200000000 1.9768391848 0.1012321514 1.9981929064 0.0259734369 2.0241860000 1.2666710000 0.4232300000 0.0000050000 0.3194530000 0.0082790000 110769976 0 1786314752 3.7579963207 3.2079687119 6.8894953728 1045 41.7600000000 1.9734187126 0.1030237175 1.9981929064 0.0259678740 2.2579920000 1.2579420000 0.2071980000 0.1236540000 0.3208150000 0.3419390000 110771650 0 1785647104 3.7579419613 3.2107887268 6.8860192299 1046 41.8000000000 1.9724348783 0.1048109175 1.9981929064 0.0259606330 1.8621940000 1.2665860000 0.2528730000 0.0000050000 0.3279260000 0.0082660000 110773324 0 1787314176 3.7577984333 3.2136406898 6.8843421936 1047 41.8400000000 1.9693622589 0.1065917688 1.9981929064 0.0259528652 2.2324710000 1.2580050000 0.5117770000 0.1235660000 0.3244740000 0.0082000000 110774998 0 1784647680 3.7580125332 3.2152996063 6.8811383247 1048 41.8800000000 1.9670250416 0.1083669914 1.9981929064 0.0259428058 2.1111910000 1.2586200000 0.5121610000 0.0000050000 0.3257110000 0.0081970000 110776672 0 1786290176 3.7579131126 3.2180118561 6.8778104782 1049 41.9200000000 1.9651163816 0.1101370099 1.9981929064 0.0259350796 2.4139830000 1.2666130000 0.3406150000 0.1239260000 0.3275070000 0.3488550000 110778346 0 1788067840 3.7578382492 3.2210512161 6.8750181198 1050 41.9600000000 1.9623247385 0.1119009982 1.9981929064 0.0259280734 2.1146610000 1.2585510000 0.5119660000 0.0000050000 0.3293090000 0.0082810000 110780020 0 1785147392 3.7578768730 3.2240710258 6.8714642525 1051 42.0000000000 1.9606622458 0.1136600479 1.9981929064 0.0259204215 2.1604290000 1.2633790000 0.4274530000 0.1234020000 0.3313300000 0.0082600000 110781694 0 1786535936 3.7580716610 3.2256357670 6.8689522743 1052 42.0400000000 1.9586957693 0.1154138842 1.9981929064 0.0259119012 2.1238440000 1.2595230000 0.5174160000 0.0000050000 0.3320920000 0.0082430000 110783368 0 1785393152 3.7580730915 3.2269706726 6.8664493561 1053 42.0800000000 1.9584850073 0.1171641891 1.9981929064 0.0259038320 2.6030510000 1.2581270000 0.5253870000 0.1233800000 0.3342110000 0.3551970000 110785042 0 1787043840 3.7579855919 3.2284121513 6.8650341034 1054 42.1200000000 1.9549869299 0.1189078540 1.9981929064 0.0258951593 2.1238310000 1.2558480000 0.5179230000 0.0000050000 0.3352880000 0.0081810000 110786716 0 1784647680 3.7580859661 3.2304182053 6.8610515594 1055 42.1600000000 1.9542075396 0.1206474745 1.9981929064 0.0258856501 2.2587920000 1.2563840000 0.5258900000 0.1233440000 0.3382460000 0.0082190000 110788390 0 1786408960 3.7578079700 3.2322711945 6.8598308563 1056 42.2000000000 1.9522798061 0.1223819748 1.9981929064 0.0258797841 2.1346200000 1.2599370000 0.5213610000 0.0000050000 0.3385090000 0.0083070000 110790064 0 1787949056 3.7577044964 3.2346532345 6.8577551842 1057 42.2400000000 1.9484560490 0.1241095757 1.9981929064 0.0258729900 2.5668120000 1.2543090000 0.4778190000 0.1230770000 0.3389150000 0.3660900000 110791738 0 1785298944 3.7577900887 3.2367444038 6.8536648750 1058 42.2800000000 1.9450414181 0.1258306833 1.9981929064 0.0258632964 2.1362910000 1.2572370000 0.5244530000 0.0000050000 0.3396930000 0.0081930000 110793412 0 1787043840 3.7577462196 3.2389030457 6.8505401611 1059 42.3200000000 1.9421569109 0.1275458166 1.9981929064 0.0258543154 2.2638980000 1.2596340000 0.5258590000 0.1228370000 0.3406970000 0.0083010000 110795086 0 1784631296 3.7576806545 3.2391402721 6.8476414680 1060 42.3600000000 1.9395279884 0.1292552338 1.9981929064 0.0258444719 2.1461540000 1.2663720000 0.5237700000 0.0000200000 0.3410910000 0.0082390000 110796760 0 1786155008 3.7575013638 3.2401227951 6.8450999260 1061 42.4000000000 1.9365521669 0.1309586239 1.9981929064 0.0258343262 2.5272480000 1.2557020000 0.4350220000 0.1224140000 0.3437580000 0.3636770000 110798434 0 1785520128 3.7573516369 3.2419202328 6.8425478935 1062 42.4400000000 1.9335498810 0.1326559791 1.9981929064 0.0258321510 2.1409800000 1.2615320000 0.5218260000 0.0000040000 0.3427080000 0.0082230000 110800108 0 1787043840 3.7570064068 3.2439332008 6.8416929245 1063 42.4800000000 1.9268805981 0.1343438668 1.9981929064 0.0258258188 2.2572170000 1.2536680000 0.5242060000 0.1214690000 0.3430290000 0.0082350000 110801782 0 1785155584 3.7573683262 3.2458331585 6.8358616829 1064 42.5200000000 1.9245566130 0.1360263976 1.9981929064 0.0258154031 2.1463160000 1.2601500000 0.5270520000 0.0000050000 0.3439980000 0.0081810000 110803456 0 1786925056 3.7574701309 3.2472758293 6.8344669342 1065 42.5600000000 1.9227129221 0.1377040375 1.9981929064 0.0258053398 2.5298910000 1.2535370000 0.4386880000 0.1210050000 0.3441430000 0.3657950000 110805130 0 1784528896 3.7577068806 3.2475569248 6.8334870338 1066 42.6000000000 1.9196163416 0.1393756251 1.9981929064 0.0257945543 2.0142490000 1.2549600000 0.3990380000 0.0000050000 0.3453130000 0.0081670000 110806804 0 1785925632 3.7579281330 3.2502713203 6.8311429024 1067 42.6400000000 1.9179039001 0.1410424744 1.9981929064 0.0257849245 1.9982450000 1.2559290000 0.2607110000 0.1206200000 0.3461080000 0.0081600000 110808478 0 1787932672 3.7581217289 3.2523064613 6.8305535316 1068 42.6800000000 1.9167730808 0.1427051435 1.9981929064 0.0257770297 2.0086030000 1.2509900000 0.3956790000 0.0000050000 0.3470230000 0.0082340000 110810152 0 1784774656 3.7585115433 3.2531893253 6.8304920197 1069 42.7200000000 1.9152606726 0.1443632872 1.9981929064 0.0257695037 2.5423820000 1.2580180000 0.4391650000 0.1202300000 0.3485700000 0.3695620000 110811826 0 1786408960 3.7589247227 3.2551133633 6.8299050331 1070 42.7600000000 1.9137772322 0.1460169450 1.9981929064 0.0257606772 2.1466900000 1.2521750000 0.5295860000 0.0000050000 0.3499970000 0.0082490000 110813500 0 1785409536 3.7591936588 3.2573919296 6.8289861679 1071 42.8000000000 1.9144419432 0.1476681355 1.9981929064 0.0257517811 2.2732860000 1.2588530000 0.5283380000 0.1199410000 0.3512530000 0.0082430000 110815174 0 1786916864 3.7591660023 3.2585306168 6.8314814568 1072 42.8400000000 1.9123711586 0.1493143137 1.9981929064 0.0257421557 2.0555930000 1.2508790000 0.4370200000 0.0000060000 0.3527740000 0.0082360000 110816848 0 1784631296 3.7591257095 3.2601914406 6.8313074112 1073 42.8800000000 1.9105067253 0.1509556859 1.9981929064 0.0257314190 2.4157020000 1.2493870000 0.3086500000 0.1191580000 0.3558080000 0.3760400000 110818522 0 1786281984 3.7590873241 3.2633059025 6.8302683830 1074 42.9200000000 1.9068287611 0.1525905771 1.9981929064 0.0257216919 1.9294650000 1.2518680000 0.3059280000 0.0000060000 0.3566850000 0.0082980000 110820196 0 1788059648 3.7589271069 3.2638869286 6.8268008232 1075 42.9600000000 1.9010058641 0.1542170099 1.9981929064 0.0257131621 2.2428360000 1.2539370000 0.4904830000 0.1201670000 0.3633910000 0.0082070000 110821870 0 1785139200 3.7589709759 3.2640452385 6.8205113411 1076 43.0000000000 1.8952679634 0.1558350870 1.9981929064 0.0257035330 2.0748230000 1.2582990000 0.4430420000 0.0000060000 0.3585360000 0.0081840000 110823544 0 1786662912 3.7590630054 3.2648727894 6.8163924217 1077 43.0400000000 1.8885040283 0.1574438790 1.9981929064 0.0256956342 2.6795200000 1.2739960000 0.5373990000 0.1177500000 0.3583510000 0.3797350000 110825218 0 1784504320 3.7592213154 3.2632048130 6.8112211227 1078 43.0800000000 1.8845421076 0.1590460109 1.9981929064 0.0256853877 2.1580940000 1.2514340000 0.5320000000 0.0000050000 0.3596350000 0.0082550000 110826892 0 1785774080 3.7594389915 3.2652420998 6.8094649315 1079 43.1200000000 1.8793081045 0.1606403224 1.9981929064 0.0256759683 2.2745700000 1.2507380000 0.5315110000 0.1174840000 0.3598370000 0.0082470000 110828566 0 1787822080 3.7596633434 3.2671706676 6.8071527481 1080 43.1600000000 1.8726979494 0.1622255609 1.9981929064 0.0256673640 2.1249450000 1.2591310000 0.4901750000 0.0000060000 0.3606730000 0.0082450000 110830240 0 1784528896 3.7599489689 3.2675833702 6.8020811081 1081 43.2000000000 1.8707052469 0.1638060232 1.9981929064 0.0256586221 2.6488100000 1.2506580000 0.5327900000 0.1166280000 0.3605330000 0.3814330000 110831914 0 1785909248 3.7600877285 3.2671253681 6.8025293350 1082 43.2400000000 1.8729840517 0.1653856701 1.9981929064 0.0256489683 2.1580800000 1.2566890000 0.5254700000 0.0000060000 0.3608780000 0.0082400000 110833588 0 1787703296 3.7600741386 3.2682337761 6.8070945740 1083 43.2800000000 1.8745012283 0.1669638009 1.9981929064 0.0256405685 2.2685160000 1.2520790000 0.5233610000 0.1161850000 0.3618210000 0.0081600000 110835262 0 1784393728 3.7602648735 3.2698018551 6.8114185333 1084 43.3200000000 1.8734358549 0.1685380371 1.9981929064 0.0256295707 2.1725640000 1.2534510000 0.5410730000 0.0000060000 0.3629490000 0.0081670000 110836936 0 1785774080 3.7606534958 3.2716026306 6.8120279312 1085 43.3600000000 1.8741762638 0.1701100539 1.9981929064 0.0256181871 2.6511210000 1.2480220000 0.5342630000 0.1164910000 0.3623560000 0.3832690000 110838610 0 1787805696 3.7609360218 3.2725865841 6.8141160011 1086 43.4000000000 1.8720908165 0.1716772553 1.9981929064 0.0256075231 2.1719880000 1.2504000000 0.5429510000 0.0000050000 0.3636360000 0.0081600000 110840284 0 1784266752 3.7614054680 3.2733774185 6.8131766319 1087 43.4400000000 1.8718653917 0.1732413658 1.9981929064 0.0255965447 2.2726210000 1.2504880000 0.5299370000 0.1152540000 0.3619800000 0.0081660000 110841958 0 1785774080 3.7617602348 3.2743999958 6.8149471283 1088 43.4800000000 1.8678743839 0.1747989329 1.9981929064 0.0255860330 2.1686440000 1.2520910000 0.5351400000 0.0000060000 0.3664260000 0.0082490000 110843632 0 1787551744 3.7622151375 3.2771003246 6.8125033379 1089 43.5200000000 1.8609443903 0.1763472759 1.9981929064 0.0255774792 2.6520750000 1.2510930000 0.5367450000 0.1149770000 0.3604990000 0.3819360000 110845306 0 1784250368 3.7629559040 3.2771933079 6.8068585396 1090 43.5600000000 1.8598606586 0.1778917836 1.9981929064 0.0255666384 2.0238300000 1.2537500000 0.3949380000 0.0000060000 0.3600760000 0.0082590000 110846980 0 1785774080 3.7637405396 3.2787747383 6.8075280190 1091 43.6000000000 1.8667545319 0.1794397788 1.9981929064 0.0255564812 2.2760730000 1.2567320000 0.5302430000 0.1142750000 0.3598070000 0.0082480000 110848654 0 1787568128 3.7644019127 3.2800409794 6.8168530464 1092 43.6400000000 1.8739616871 0.1809915387 1.9981929064 0.0255477289 2.1481400000 1.2465200000 0.5271960000 0.0000050000 0.3592430000 0.0081670000 110850328 0 1784520704 3.7650918961 3.2819745541 6.8277001381 1093 43.6800000000 1.8786009550 0.1825447038 1.9981929064 0.0255379862 2.6508260000 1.2575100000 0.5317130000 0.1133100000 0.3598430000 0.3816540000 110852002 0 1786028032 3.7657327652 3.2838315964 6.8358335495 1094 43.7200000000 1.8790187836 0.1840954114 1.9981929064 0.0255274375 2.1562240000 1.2532130000 0.5262840000 0.0000050000 0.3615730000 0.0081740000 110853676 0 1787932672 3.7664098740 3.2848908901 6.8386249542 1095 43.7600000000 1.8771153688 0.1856415483 1.9981929064 0.0255169696 2.2794110000 1.2588820000 0.5307750000 0.1128740000 0.3617690000 0.0082730000 110855350 0 1784528896 3.7669265270 3.2864930630 6.8398394585 1096 43.8000000000 1.8723261356 0.1871804941 1.9981929064 0.0255068860 2.1647920000 1.2534820000 0.5334040000 0.0000050000 0.3628340000 0.0081690000 110857024 0 1785909248 3.7675917149 3.2875409126 6.8374361992 1097 43.8400000000 1.8693782091 0.1887139469 1.9981929064 0.0254963581 2.6656810000 1.2538760000 0.5382880000 0.1123930000 0.3687850000 0.3854830000 110858698 0 1787686912 3.7681899071 3.2881700993 6.8367438316 1098 43.8800000000 1.8660464287 0.1902415721 1.9981929064 0.0254858991 1.9874060000 1.2539990000 0.3531200000 0.0000060000 0.3651850000 0.0082240000 110860372 0 1784504320 3.7688095570 3.2895982265 6.8355307579 1099 43.9200000000 1.8610826731 0.1917619007 1.9981929064 0.0254760523 2.1119120000 1.2587540000 0.3540850000 0.1170270000 0.3669120000 0.0082620000 110862046 0 1785901056 3.7694520950 3.2914197445 6.8320097923 1100 43.9600000000 1.8575911522 0.1932762909 1.9981929064 0.0254659640 2.1717330000 1.2580920000 0.5311210000 0.0000050000 0.3674110000 0.0081660000 110863720 0 1787568128 3.7701563835 3.2936747074 6.8311238289 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 08:03:17 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002853 0.0000002853 0.0000002853 nan 2.6574650000 1.3130320000 0.0737290000 0.1323700000 0.0000100000 1.1378260000 105980039 0 1763852288 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0004263568 0.0002133210 0.0004263568 0.0040680924 1.4980830000 1.3040300000 0.0528770000 0.1327040000 0.0000020000 0.0082210000 108236892 0 1766146048 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0024013643 0.0009426688 0.0024013643 0.0044545736 1.4646490000 1.2713430000 0.0528320000 0.1320960000 0.0000030000 0.0081460000 108238890 0 1767923712 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0017003767 0.0011320958 0.0024013643 0.0049657424 2.5597450000 1.2658570000 0.0533640000 0.1322650000 1.0998580000 0.0082590000 108240892 0 1776558080 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0009065330 0.0010869832 0.0024013643 0.0044320788 4.0664060000 1.2706130000 0.4578680000 0.1323210000 1.0909160000 1.1145210000 108242886 0 1778835456 4.0000848770 3.9995701313 4.0000095367 6 0.2000000000 0.0008840567 0.0010531621 0.0024013643 0.0040876587 2.6951520000 1.2643840000 0.3294230000 0.0000020000 1.0929580000 0.0082310000 108245216 0 1780477952 4.0001263618 3.9984500408 3.9996976852 7 0.2400000000 0.0009241536 0.0010347323 0.0024013643 0.0037765396 2.8533590000 1.2662520000 0.3605260000 0.1328420000 1.0853320000 0.0082160000 108246890 0 1782128640 4.0001130104 3.9982912540 3.9996080399 8 0.2800000000 0.0010749736 0.0010397625 0.0024013643 0.0035588516 2.6513920000 1.2841060000 0.2694580000 0.0000020000 1.0893460000 0.0082950000 108248564 0 1784033280 4.0004034042 3.9995920658 4.0000348091 9 0.3200000000 0.0010729767 0.0010434530 0.0024013643 0.0033320940 3.8482810000 1.2641250000 0.2686820000 0.1323810000 1.0834340000 1.0994670000 108250878 0 1785565184 4.0005893707 3.9996206760 4.0000782013 10 0.3600000000 0.0011573778 0.0010548455 0.0024013643 0.0031521884 2.6331060000 1.2584060000 0.2755720000 0.0000030000 1.0907320000 0.0082150000 108253864 0 1787207680 4.0006341934 3.9989976883 3.9999096394 11 0.4000000000 0.0011061265 0.0010595074 0.0024013643 0.0029931919 2.7070310000 1.2582850000 0.2244620000 0.1321680000 1.0837130000 0.0082130000 108255538 0 1785430016 4.0004959106 3.9995486736 4.0000967979 12 0.4400000000 0.0010838739 0.0010615379 0.0024013643 0.0028619509 2.6906610000 1.2744130000 0.3244890000 0.0000030000 1.0833890000 0.0081740000 108257212 0 1787215872 4.0005831718 4.0002684593 4.0004057884 13 0.4800000000 0.0011524699 0.0010685327 0.0024013643 0.0027523511 4.1086020000 1.2578360000 0.5333160000 0.1321220000 1.0813860000 1.1037360000 108258886 0 1784168448 4.0004267693 4.0009284019 4.0007166862 14 0.5200000000 0.0011287788 0.0010728360 0.0024013643 0.0027276346 2.7104210000 1.2588980000 0.3621390000 0.0000020000 1.0808860000 0.0082940000 108260560 0 1785810944 4.0006046295 4.0009522438 4.0007972717 15 0.5600000000 0.0011157219 0.0010756950 0.0024013643 0.0027161138 2.7679570000 1.2669420000 0.2730480000 0.1326630000 1.0869200000 0.0081740000 108262234 0 1787588608 4.0006380081 4.0009722710 4.0008926392 16 0.6000000000 0.0011511294 0.0010804097 0.0024013643 0.0026448283 2.6115970000 1.2962990000 0.2233290000 0.0000050000 1.0835280000 0.0082220000 108263908 0 1784541184 4.0010671616 4.0008993149 4.0008115768 17 0.6400000000 0.0012706184 0.0010915984 0.0024013643 0.0025679439 3.8130380000 1.2570990000 0.2292990000 0.1375970000 1.0866510000 1.1021580000 108266862 0 1786064896 4.0009837151 4.0008897781 4.0008578300 18 0.6800000000 0.0013085885 0.0011036534 0.0024013643 0.0025014821 2.5809690000 1.2584600000 0.2279200000 0.0000040000 1.0861820000 0.0081730000 108271160 0 1787842560 4.0010824203 4.0001606941 4.0006117821 19 0.7200000000 0.0012404835 0.0011108550 0.0024013643 0.0025390232 2.7625790000 1.2649860000 0.2721900000 0.1321890000 1.0847350000 0.0082310000 108272834 0 1784414208 4.0010032654 4.0001630783 4.0005259514 20 0.7600000000 0.0012224437 0.0011164345 0.0024013643 0.0026346410 2.6568350000 1.2852280000 0.2740950000 0.0000020000 1.0890150000 0.0082410000 108274508 0 1785937920 4.0007801056 3.9999024868 4.0004491806 21 0.8000000000 0.0013098217 0.0011256434 0.0024013643 0.0027449825 3.8502120000 1.2635870000 0.2707880000 0.1324120000 1.0835910000 1.0995600000 108276182 0 1787842560 4.0007948875 3.9998397827 4.0002937317 22 0.8400000000 0.0012810376 0.0011327067 0.0024013643 0.0027258760 2.6234720000 1.2666730000 0.2624500000 0.0000200000 1.0857460000 0.0083170000 108277856 0 1784541184 4.0008220673 4.0000267029 4.0004067421 23 0.8800000000 0.0012887456 0.0011394910 0.0024013643 0.0027024875 2.8079700000 1.2593640000 0.3262460000 0.1322030000 1.0816700000 0.0082250000 108279530 0 1785946112 4.0005874634 3.9997994900 4.0003352165 24 0.9200000000 0.0013760220 0.0011493465 0.0024013643 0.0026495249 2.8332410000 1.2873950000 0.4556690000 0.0000040000 1.0816680000 0.0082200000 108281204 0 1787850752 4.0006713867 4.0000166893 4.0003342628 25 0.9600000000 0.0013912527 0.0011590227 0.0024013643 0.0025961165 3.7973910000 1.2590980000 0.2196040000 0.1326550000 1.0878530000 1.0979000000 108282878 0 1784160256 4.0004811287 3.9999401569 4.0003433228 26 1.0000000000 0.0014210518 0.0011691008 0.0024013643 0.0025454135 2.9247800000 1.2573090000 0.5770730000 0.0000040000 1.0819010000 0.0081980000 108284552 0 1785683968 4.0006232262 4.0002741814 4.0003814697 27 1.0400000000 0.0015453736 0.0011830368 0.0024013643 0.0025017583 2.7155640000 1.2620760000 0.2275200000 0.1321620000 1.0852220000 0.0083030000 108286226 0 1787461632 4.0004601479 4.0003190041 4.0003733635 28 1.0800000000 0.0015380066 0.0011957143 0.0024013643 0.0024757305 2.6124960000 1.2932860000 0.2269000000 0.0000050000 1.0837950000 0.0082130000 108287900 0 1784414208 4.0003800392 4.0001549721 4.0004057884 29 1.1200000000 0.0014713308 0.0012052183 0.0024013643 0.0024411417 3.7891720000 1.2658250000 0.2079950000 0.1323170000 1.0830490000 1.0996090000 108289574 0 1785937920 4.0000190735 4.0003018379 4.0005135536 30 1.1600000000 0.0015675952 0.0012172976 0.0024013643 0.0024123758 2.5873810000 1.2601600000 0.2269310000 0.0000050000 1.0917290000 0.0082370000 108291248 0 1787842560 4.0002756119 4.0008268356 4.0004901886 31 1.2000000000 0.0014951236 0.0012262597 0.0024013643 0.0023903066 2.8070200000 1.2596120000 0.3222130000 0.1321880000 1.0844380000 0.0082300000 108292922 0 1784414208 4.0000343323 4.0005135536 4.0004625320 32 1.2400000000 0.0014779625 0.0012341254 0.0024013643 0.0023572076 2.6045420000 1.2802560000 0.2290710000 0.0000040000 1.0865890000 0.0082390000 108294596 0 1785937920 3.9997665882 4.0001144409 4.0004196167 33 1.2800000000 0.0015023635 0.0012422538 0.0024013643 0.0023522998 3.8132880000 1.2626660000 0.2232460000 0.1326490000 1.0873990000 1.1069950000 108298830 0 1787842560 3.9995865822 4.0002036095 4.0005879402 34 1.3200000000 0.0016294258 0.0012536412 0.0024013643 0.0023410475 2.5789320000 1.2587100000 0.2263610000 0.0000040000 1.0853480000 0.0081680000 108305752 0 1784549376 3.9991922379 4.0000429153 4.0006513596 35 1.3600000000 0.0014812556 0.0012601445 0.0024013643 0.0023239095 2.8042220000 1.2572270000 0.3154660000 0.1324370000 1.0906060000 0.0081670000 108307426 0 1785946112 3.9987943172 3.9990282059 4.0004086494 36 1.4000000000 0.0015137712 0.0012671897 0.0024013643 0.0022975471 2.9430540000 1.2942330000 0.5546820000 0.0000050000 1.0856140000 0.0081690000 108309100 0 1787850752 3.9983792305 3.9989931583 4.0003929138 37 1.4400000000 0.0013916824 0.0012705544 0.0024013643 0.0022661737 3.9581610000 1.2579530000 0.3861300000 0.1322180000 1.0823170000 1.0991980000 108310774 0 1784414208 3.9980821609 3.9994897842 4.0005965233 38 1.4800000000 0.0013100910 0.0012715948 0.0024013643 0.0022353568 2.6850820000 1.2570490000 0.3319780000 0.0000030000 1.0875580000 0.0081620000 108312448 0 1785937920 3.9977526665 3.9989538193 4.0006341934 39 1.5200000000 0.0012513357 0.0012710753 0.0024013643 0.0022164747 2.7744710000 1.2616450000 0.2766250000 0.1324630000 1.0951210000 0.0082420000 108314122 0 1787842560 3.9970283508 3.9974632263 4.0002694130 40 1.5600000000 0.0011237465 0.0012673921 0.0024013643 0.0022930251 2.6650490000 1.2820730000 0.2716720000 0.0000040000 1.1027620000 0.0081790000 108315796 0 1784541184 3.9966278076 3.9978203773 4.0006837845 41 1.6000000000 0.0011373149 0.0012642195 0.0024013643 0.0024316016 3.9367620000 1.2593240000 0.3558990000 0.1322240000 1.0856520000 1.1032650000 108317470 0 1785937920 3.9962587357 3.9990520477 4.0014181137 42 1.6400000000 0.0011788175 0.0012621861 0.0024013643 0.0025062671 2.6762130000 1.2647700000 0.3178950000 0.0000040000 1.0849230000 0.0082570000 108319144 0 1787842560 3.9956028461 3.9988555908 4.0017681122 43 1.6800000000 0.0012126364 0.0012610338 0.0024013643 0.0025111085 2.8110100000 1.2570920000 0.3257410000 0.1322090000 1.0873510000 0.0082370000 108320818 0 1784414208 3.9952816963 3.9988088608 4.0023140907 44 1.7200000000 0.0012438796 0.0012606439 0.0024013643 0.0024928794 2.7721190000 1.2558170000 0.4242720000 0.0000030000 1.0834320000 0.0082150000 108322492 0 1786191872 3.9948809147 3.9991953373 4.0029859543 45 1.7600000000 0.0012339201 0.0012600501 0.0024013643 0.0024873984 3.9961000000 1.2556300000 0.4165910000 0.1323350000 1.0899710000 1.1011990000 108324166 0 1787969536 3.9946842194 3.9986560345 4.0035066605 46 1.8000000000 0.0012832446 0.0012605543 0.0024013643 0.0026044645 2.6688360000 1.2555620000 0.3166560000 0.0000040000 1.0879270000 0.0082780000 108325840 0 1784930304 3.9944627285 3.9975690842 4.0040473938 47 1.8400000000 0.0012792776 0.0012609527 0.0024013643 0.0027657383 2.8613140000 1.2664420000 0.3712140000 0.1322050000 1.0828700000 0.0081700000 108327514 0 1786445824 3.9944076538 3.9971714020 4.0049514771 48 1.8800000000 0.0011731120 0.0012591226 0.0024013643 0.0029388844 2.6853970000 1.2592430000 0.3258740000 0.0000040000 1.0916710000 0.0082190000 108329188 0 1785430016 3.9940617085 3.9970040321 4.0063672066 49 1.9200000000 0.0011811951 0.0012575323 0.0024013643 0.0032188523 3.9017090000 1.2573900000 0.3241530000 0.1320750000 1.0853280000 1.1023630000 108330862 0 1786953728 3.9940645695 3.9956116676 4.0073890686 50 1.9600000000 0.0012035741 0.0012564531 0.0024013643 0.0035102977 2.6877390000 1.2632230000 0.3211690000 0.0000040000 1.0947000000 0.0082130000 108332536 0 1784786944 3.9940495491 3.9951133728 4.0089087486 51 2.0000000000 0.0012400602 0.0012561317 0.0024013643 0.0036864855 2.7504880000 1.2614670000 0.2616660000 0.1326770000 1.0859750000 0.0082890000 108334210 0 1786183680 3.9941513538 3.9953293800 4.0108194351 52 2.0400000000 0.0012970845 0.0012569192 0.0024013643 0.0038229460 2.6843410000 1.3105630000 0.2757180000 0.0000050000 1.0894810000 0.0081640000 108335884 0 1785176064 3.9947862625 3.9952330589 4.0127401352 53 2.0800000000 0.0013278736 0.0012582580 0.0024013643 0.0038898796 3.8985700000 1.2623350000 0.3115770000 0.1321760000 1.0892260000 1.1028340000 108337558 0 1786572800 3.9951386452 3.9940469265 4.0143909454 54 2.1200000000 0.0013529465 0.0012600115 0.0024013643 0.0039552349 2.6275190000 1.2592730000 0.2699980000 0.0000040000 1.0895610000 0.0082400000 108339232 0 1784795136 3.9961600304 3.9933362007 4.0161700249 55 2.1600000000 0.0013255253 0.0012612027 0.0024013643 0.0039588758 2.8017290000 1.2646180000 0.3157080000 0.1317830000 1.0810070000 0.0081610000 108340906 0 1786318848 3.9964456558 3.9935939312 4.0186829567 56 2.2000000000 0.0012309154 0.0012606618 0.0024013643 0.0039377415 2.7819390000 1.2781980000 0.4135790000 0.0000040000 1.0815520000 0.0081780000 108342580 0 1785556992 3.9968538284 3.9937720299 4.0211906433 57 2.2400000000 0.0012839193 0.0012610698 0.0024013643 0.0039533126 3.8478340000 1.2652520000 0.2812500000 0.1321020000 1.0752490000 1.0935410000 108344254 0 1787215872 3.9980306625 3.9937183857 4.0235977173 58 2.2800000000 0.0013251501 0.0012621747 0.0024013643 0.0040122771 2.6140380000 1.2587520000 0.2695310000 0.0000040000 1.0771480000 0.0081580000 108345928 0 1784803328 3.9987237453 3.9947879314 4.0264468193 59 2.3200000000 0.0013967961 0.0012644564 0.0024013643 0.0041114977 2.7414970000 1.2604170000 0.2740940000 0.1314410000 1.0668520000 0.0082290000 108347602 0 1786445824 4.0000014305 3.9945945740 4.0290918350 60 2.3600000000 0.0014043533 0.0012667880 0.0024013643 0.0044120475 2.6371000000 1.2910630000 0.2711470000 0.0000040000 1.0662490000 0.0081500000 108349276 0 1785556992 4.0009651184 3.9932782650 4.0314917564 61 2.4000000000 0.0014580747 0.0012699239 0.0024013643 0.0046757555 3.8130390000 1.2599900000 0.2671290000 0.1315140000 1.0663590000 1.0875530000 108350950 0 1786953728 4.0024132729 3.9932467937 4.0344181061 62 2.4400000000 0.0014683448 0.0012731242 0.0024013643 0.0049255673 2.5993980000 1.2572070000 0.2674960000 0.0000040000 1.0660250000 0.0081890000 108352624 0 1784668160 4.0036821365 3.9931936264 4.0373225212 63 2.4800000000 0.0015936021 0.0012782111 0.0024013643 0.0051087327 2.7909750000 1.2569630000 0.3273690000 0.1309960000 1.0669210000 0.0082400000 108354298 0 1786191872 4.0051698685 3.9926531315 4.0400338173 64 2.5200000000 0.0015805634 0.0012829354 0.0024013643 0.0052471533 2.6437970000 1.2900130000 0.2786080000 0.0000050000 1.0664270000 0.0082450000 108355972 0 1785430016 4.0067801476 3.9929549694 4.0431928635 65 2.5600000000 0.0015852067 0.0012875857 0.0024013643 0.0054883229 3.8062870000 1.2578700000 0.2770980000 0.1309060000 1.0644460000 1.0754540000 108362766 0 1787080704 4.0081076622 3.9925065041 4.0460486412 66 2.6000000000 0.0013673026 0.0012887936 0.0024013643 0.0058370365 2.6537800000 1.2592210000 0.3131820000 0.0000040000 1.0726280000 0.0082420000 108374936 0 1784795136 4.0096707344 3.9914131165 4.0485529900 67 2.6400000000 0.0013208720 0.0012892723 0.0024013643 0.0061138422 2.6814570000 1.2648680000 0.2171520000 0.1305630000 1.0602010000 0.0081600000 108376610 0 1786445824 4.0117025375 3.9928610325 4.0518717766 68 2.6800000000 0.0013324241 0.0012899069 0.0024013643 0.0065269765 2.6677630000 1.2604920000 0.3274280000 0.0000040000 1.0710650000 0.0082130000 108378284 0 1785303040 4.0120267868 3.9930982590 4.0547242165 69 2.7200000000 0.0013738980 0.0012911242 0.0024013643 0.0067398772 3.7845410000 1.2553850000 0.2736750000 0.1305140000 1.0542720000 1.0701320000 108379958 0 1786961920 4.0139617920 3.9922256470 4.0573906898 70 2.7600000000 0.0014154649 0.0012929005 0.0024013643 0.0068650857 2.6188320000 1.2660160000 0.2762920000 0.0000030000 1.0678510000 0.0081640000 108381632 0 1784803328 4.0155153275 3.9915113449 4.0598707199 71 2.8000000000 0.0014367831 0.0012949270 0.0024013643 0.0068882901 2.7811480000 1.2612460000 0.3218060000 0.1308110000 1.0584880000 0.0082900000 108383306 0 1786445824 4.0168256760 3.9922175407 4.0629100800 72 2.8400000000 0.0013804557 0.0012961149 0.0024013643 0.0068801039 2.6085520000 1.2629100000 0.2738750000 0.0000030000 1.0629950000 0.0082320000 108384980 0 1786589184 4.0181646347 3.9919652939 4.0655770302 73 2.8800000000 0.0012835033 0.0012959421 0.0024013643 0.0068667339 3.7780740000 1.2632540000 0.2641930000 0.1309070000 1.0479900000 1.0711870000 108386654 0 1785573376 4.0193524361 3.9914050102 4.0680389404 74 2.9200000000 0.0012839002 0.0012957794 0.0024013643 0.0068791953 2.6087510000 1.2630290000 0.2735710000 0.0000040000 1.0634360000 0.0081690000 108388328 0 1787088896 4.0208892822 3.9922394753 4.0709209442 75 2.9600000000 0.0013874945 0.0012970023 0.0024013643 0.0069511719 2.7235970000 1.2575770000 0.2714160000 0.1305040000 1.0553570000 0.0082060000 108390002 0 1784803328 4.0222945213 3.9926764965 4.0736188889 76 3.0000000000 0.0013653586 0.0012979017 0.0024013643 0.0071177632 2.5978390000 1.2976340000 0.2259450000 0.0000050000 1.0655490000 0.0081750000 108391676 0 1786318848 4.0237431526 3.9914441109 4.0757980347 77 3.0400000000 0.0013549171 0.0012986422 0.0024013643 0.0072807617 3.7867060000 1.2611320000 0.2776770000 0.1306870000 1.0497930000 1.0668580000 108393350 0 1785303040 4.0248894691 3.9902615547 4.0779099464 78 3.0800000000 0.0012408828 0.0012979017 0.0024013643 0.0075049724 2.6660000000 1.2606530000 0.3201110000 0.0000040000 1.0764140000 0.0082620000 108395024 0 1786826752 4.0261330605 3.9909477234 4.0807328224 79 3.1200000000 0.0012245585 0.0012969733 0.0024013643 0.0077075992 2.7254580000 1.2590200000 0.2739370000 0.1306230000 1.0531690000 0.0081570000 108396698 0 1784541184 4.0268464088 3.9911725521 4.0834579468 80 3.1600000000 0.0012725734 0.0012966683 0.0024013643 0.0078493383 2.6816490000 1.2870520000 0.3086130000 0.0000040000 1.0771720000 0.0082180000 108398372 0 1786064896 4.0280351639 3.9901247025 4.0856819153 81 3.2000000000 0.0013630410 0.0012974877 0.0024013643 0.0079956590 3.8486950000 1.2647170000 0.3164200000 0.1308790000 1.0596560000 1.0764070000 108400046 0 1788104704 4.0295166969 3.9899263382 4.0882034302 82 3.2400000000 0.0013778878 0.0012984682 0.0024013643 0.0081717961 2.6732640000 1.2704130000 0.3181540000 0.0000030000 1.0758920000 0.0082260000 108401720 0 1784549376 4.0299239159 3.9897511005 4.0907130241 83 3.2800000000 0.0013322969 0.0012988757 0.0024013643 0.0083557117 2.7823150000 1.2648180000 0.3160030000 0.1315740000 1.0611830000 0.0081540000 108403394 0 1786200064 4.0309634209 3.9888005257 4.0931072235 84 3.3200000000 0.0013257721 0.0012991959 0.0024013643 0.0084569103 2.6489190000 1.3029350000 0.2590480000 0.0000040000 1.0781470000 0.0082210000 108405068 0 1787969536 4.0315895081 3.9886281490 4.0956401825 85 3.3600000000 0.0013107267 0.0012993316 0.0024013643 0.0085284389 3.9120700000 1.2630780000 0.3620830000 0.1312860000 1.0687300000 1.0862990000 108406742 0 1784541184 4.0320835114 3.9890186787 4.0984067917 86 3.4000000000 0.0014478849 0.0013010590 0.0024013643 0.0085864801 2.6744860000 1.2664770000 0.3162360000 0.0000040000 1.0829710000 0.0082150000 108408416 0 1786191872 4.0330944061 3.9889757633 4.1009817123 87 3.4400000000 0.0013895978 0.0013020766 0.0024013643 0.0086592880 2.7469860000 1.2712310000 0.2686540000 0.1317070000 1.0666290000 0.0081630000 108410090 0 1787969536 4.0338988304 3.9889798164 4.1038312912 88 3.4800000000 0.0014544397 0.0013038080 0.0024013643 0.0087449400 2.6096820000 1.2937150000 0.2237840000 0.0000040000 1.0833850000 0.0081490000 108411764 0 1784557568 4.0346322060 3.9887180328 4.1065893173 89 3.5200000000 0.0014209887 0.0013051247 0.0024013643 0.0088266005 3.8148710000 1.2740940000 0.2600970000 0.1320380000 1.0641560000 1.0838380000 108413438 0 1786064896 4.0354809761 3.9887092113 4.1094937325 90 3.5600000000 0.0014092994 0.0013062822 0.0024013643 0.0089449453 2.6422080000 1.2755040000 0.2730950000 0.0000040000 1.0847180000 0.0082730000 108415112 0 1787969536 4.0357699394 3.9887392521 4.1124577522 91 3.6000000000 0.0014171288 0.0013075003 0.0024013643 0.0090821784 2.6966710000 1.2674850000 0.2245480000 0.1324100000 1.0633490000 0.0082360000 108416786 0 1784287232 4.0370988846 3.9881706238 4.1154551506 92 3.6400000000 0.0014565085 0.0013091199 0.0024013643 0.0091690196 2.7182310000 1.3022680000 0.3285360000 0.0000040000 1.0786080000 0.0081640000 108418460 0 1785937920 4.0375514030 3.9879798889 4.1186304092 93 3.6800000000 0.0014021070 0.0013101198 0.0024013643 0.0091713909 3.9238940000 1.2692360000 0.3642480000 0.1328540000 1.0661110000 1.0908220000 108420134 0 1787850752 4.0379061699 3.9874179363 4.1215672493 94 3.7200000000 0.0015588644 0.0013127660 0.0024013643 0.0091495313 2.9143690000 1.2720100000 0.5506540000 0.0000040000 1.0827470000 0.0082370000 108421808 0 1784541184 4.0389323235 3.9877629280 4.1247510910 95 3.7600000000 0.0014536049 0.0013142485 0.0024013643 0.0091381378 3.0327190000 1.2699750000 0.5524920000 0.1333550000 1.0680220000 0.0082140000 108423482 0 1786064896 4.0397133827 3.9874565601 4.1278061867 96 3.8000000000 0.0015087818 0.0013162749 0.0024013643 0.0091577247 2.7270240000 1.2693390000 0.3622440000 0.0000040000 1.0865260000 0.0082250000 108425156 0 1787969536 4.0406141281 3.9876656532 4.1310510635 97 3.8400000000 0.0014279501 0.0013174262 0.0024013643 0.0092710556 3.8211380000 1.2718920000 0.2599310000 0.1335480000 1.0677560000 1.0873510000 108426830 0 1784795136 4.0411725044 3.9890332222 4.1346859932 98 3.8800000000 0.0015518038 0.0013198178 0.0024013643 0.0093969347 2.6863580000 1.2703520000 0.3209750000 0.0000030000 1.0854820000 0.0088920000 108428504 0 1786064896 4.0417308807 3.9890353680 4.1378297806 99 3.9200000000 0.0015219898 0.0013218600 0.0024013643 0.0095269952 2.7509250000 1.2697850000 0.2713030000 0.1339340000 1.0669870000 0.0082480000 108430178 0 1787969536 4.0426878929 3.9890172482 4.1410512924 100 3.9600000000 0.0015323148 0.0013239645 0.0024013643 0.0096388369 2.6299860000 1.2735030000 0.2614190000 0.0000040000 1.0861700000 0.0082150000 108431852 0 1784414208 4.0428590775 3.9906470776 4.1446652412 101 4.0000000000 0.0016132710 0.0013268289 0.0024013643 0.0096906842 3.8312700000 1.2705680000 0.2704680000 0.1342980000 1.0677070000 1.0875590000 108433526 0 1785810944 4.0433764458 3.9912881851 4.1480398178 102 4.0400000000 0.0016122990 0.0013296276 0.0024013643 0.0097042514 2.6841880000 1.2765980000 0.3176380000 0.0000040000 1.0810250000 0.0082420000 108435200 0 1787715584 4.0439996719 3.9909729958 4.1509828568 103 4.0800000000 0.0015712548 0.0013319735 0.0024013643 0.0097159267 2.7589670000 1.2681610000 0.2691050000 0.1350390000 1.0778040000 0.0081610000 108436874 0 1784287232 4.0444107056 3.9921488762 4.1543822289 104 4.1200000000 0.0015324868 0.0013339016 0.0024013643 0.0097213403 2.6839100000 1.2747110000 0.3161880000 0.0000040000 1.0840510000 0.0082740000 108438548 0 1785946112 4.0452294350 3.9921469688 4.1575198174 105 4.1600000000 0.0016266237 0.0013366894 0.0024013643 0.0097301704 3.8902390000 1.2735840000 0.3160990000 0.1349580000 1.0752910000 1.0896160000 108440222 0 1787596800 4.0456233025 3.9923665524 4.1602540016 106 4.2000000000 0.0016418200 0.0013395680 0.0024013643 0.0097217766 2.9046330000 1.2738720000 0.5408720000 0.0000040000 1.0808670000 0.0082620000 108441896 0 1784287232 4.0452642441 3.9929819107 4.1630806923 107 4.2400000000 0.0015701681 0.0013417231 0.0024013643 0.0096968894 2.7573290000 1.2775200000 0.2689920000 0.1356230000 1.0662160000 0.0082330000 108443570 0 1785810944 4.0461316109 3.9923443794 4.1655511856 108 4.2800000000 0.0018237872 0.0013461867 0.0024013643 0.0096897089 2.6268640000 1.2733340000 0.2586600000 0.0000030000 1.0859240000 0.0082470000 108445244 0 1787604992 4.0456166267 3.9932427406 4.1683020592 109 4.3200000000 0.0018596713 0.0013508975 0.0024013643 0.0096735540 3.8206580000 1.2706970000 0.2581520000 0.1355960000 1.0674160000 1.0880720000 108446918 0 1784287232 4.0457425117 3.9941132069 4.1709747314 110 4.3600000000 0.0020507530 0.0013572599 0.0024013643 0.0096376921 2.6434420000 1.2756130000 0.2691610000 0.0000040000 1.0896810000 0.0082560000 108448592 0 1785810944 4.0457267761 3.9943444729 4.1735262871 111 4.4000000000 0.0021199866 0.0013641313 0.0024013643 0.0096055208 2.7495160000 1.2706880000 0.2662650000 0.1360010000 1.0675700000 0.0082740000 108450266 0 1787588608 4.0460729599 3.9944746494 4.1760773659 112 4.4400000000 0.0024814017 0.0013741069 0.0024814017 0.0095742852 2.6369510000 1.2803470000 0.2580000000 0.0000040000 1.0896680000 0.0081780000 108451940 0 1784287232 4.0461564064 3.9947733879 4.1784787178 113 4.4800000000 0.0020867749 0.0013804137 0.0024814017 0.0095405577 3.9244740000 1.2732550000 0.3486240000 0.1368970000 1.0699280000 1.0949880000 108453614 0 1785810944 4.0461387634 3.9952518940 4.1809267998 114 4.5200000000 0.0024054402 0.0013894052 0.0024814017 0.0095095899 2.6420160000 1.2724480000 0.2680330000 0.0000040000 1.0923380000 0.0083690000 108455288 0 1787715584 4.0461974144 3.9951968193 4.1833348274 115 4.5600000000 0.0021322479 0.0013958647 0.0024814017 0.0094793744 2.7612200000 1.2717190000 0.2725720000 0.1377450000 1.0702410000 0.0081900000 108456962 0 1784287232 4.0468420982 3.9950282574 4.1857061386 116 4.6000000000 0.0023860910 0.0014044011 0.0024814017 0.0094605942 2.6258050000 1.2732580000 0.2577340000 0.0000040000 1.0858550000 0.0081930000 108458636 0 1785946112 4.0464501381 3.9957993031 4.1882734299 117 4.6400000000 0.0023124062 0.0014121618 0.0024814017 0.0094293585 3.8932000000 1.2783520000 0.3131020000 0.1375290000 1.0708260000 1.0926210000 108460310 0 1787723776 4.0467095375 3.9954390526 4.1907277107 118 4.6800000000 0.0021914898 0.0014187663 0.0024814017 0.0094017925 2.6016470000 1.2738800000 0.2236890000 0.0000040000 1.0945040000 0.0087980000 108461984 0 1784287232 4.0469446182 3.9956831932 4.1934227943 119 4.7200000000 0.0025073423 0.0014279140 0.0025073423 0.0093770574 2.8071510000 1.2739030000 0.3156380000 0.1377460000 1.0708400000 0.0082750000 108463658 0 1785810944 4.0470800400 3.9958128929 4.1963715553 120 4.7600000000 0.0022617709 0.0014348628 0.0025073423 0.0093508600 2.6497180000 1.2746600000 0.2691370000 0.0000040000 1.0968230000 0.0083090000 108465332 0 1787715584 4.0474128723 3.9954149723 4.1991481781 121 4.8000000000 0.0024933901 0.0014436110 0.0025073423 0.0093396739 3.8363600000 1.2758510000 0.2582760000 0.1382450000 1.0716450000 1.0915580000 108467006 0 1784287232 4.0474867821 3.9957754612 4.2021937370 122 4.8400000000 0.0025645059 0.0014527986 0.0025645059 0.0093452685 2.6381070000 1.2792660000 0.2596290000 0.0000040000 1.0901560000 0.0082610000 108468680 0 1785810944 4.0474400520 3.9958200455 4.2052774429 123 4.8800000000 0.0023644168 0.0014602102 0.0025645059 0.0093291643 2.8076280000 1.2793020000 0.3052180000 0.1385210000 1.0755400000 0.0082530000 108470354 0 1787588608 4.0477652550 3.9959681034 4.2084546089 124 4.9200000000 0.0024475299 0.0014681724 0.0025645059 0.0093066018 2.6399220000 1.2734410000 0.2711590000 0.0000040000 1.0862310000 0.0082950000 108472028 0 1784287232 4.0477471352 3.9963319302 4.2115178108 125 4.9600000000 0.0024212685 0.0014757972 0.0025645059 0.0092853056 3.8387630000 1.2754370000 0.2586520000 0.1388560000 1.0744780000 1.0905430000 108473702 0 1785810944 4.0480747223 3.9966552258 4.2148184776 126 5.0000000000 0.0023604482 0.0014828182 0.0025645059 0.0092713731 2.6328850000 1.2724090000 0.2601090000 0.0000030000 1.0913180000 0.0082210000 108475376 0 1787715584 4.0484437943 3.9966351986 4.2179613113 127 5.0400000000 0.0023670997 0.0014897811 0.0025645059 0.0092721268 2.7613900000 1.2767470000 0.2577860000 0.1400670000 1.0777230000 0.0082590000 108477050 0 1784549376 4.0488543510 3.9966106415 4.2212238312 128 5.0800000000 0.0024333226 0.0014971525 0.0025645059 0.0092884882 2.5931020000 1.2758020000 0.2135430000 0.0000040000 1.0946300000 0.0082760000 108478724 0 1785819136 4.0492563248 3.9971370697 4.2243976593 129 5.1200000000 0.0024591563 0.0015046099 0.0025645059 0.0092731902 3.8606350000 1.2800100000 0.2668250000 0.1394540000 1.0763530000 1.0971420000 108490638 0 1787596800 4.0498332977 3.9972651005 4.2275195122 130 5.1600000000 0.0025020547 0.0015122825 0.0025645059 0.0092611828 2.6394530000 1.2779900000 0.2586090000 0.0000030000 1.0937360000 0.0082370000 108513304 0 1784303616 4.0504469872 3.9966120720 4.2301383018 131 5.2000000000 0.0024045298 0.0015190936 0.0025645059 0.0092503384 2.7555210000 1.2735870000 0.2582820000 0.1397460000 1.0748410000 0.0082000000 108514978 0 1785810944 4.0510869026 3.9967231750 4.2329359055 132 5.2400000000 0.0024719392 0.0015263121 0.0025645059 0.0092299961 2.5944900000 1.2813450000 0.2138980000 0.0000040000 1.0901340000 0.0082450000 108516652 0 1787715584 4.0513725281 3.9973120689 4.2358841896 133 5.2800000000 0.0025425637 0.0015339531 0.0025645059 0.0092236486 3.8019470000 1.2710080000 0.2123410000 0.1401700000 1.0758030000 1.1017680000 108518326 0 1784287232 4.0520386696 3.9968414307 4.2384142876 134 5.3200000000 0.0025779437 0.0015417441 0.0025779437 0.0092499019 2.6460150000 1.2726970000 0.2711090000 0.0000040000 1.0931470000 0.0081950000 108520000 0 1785937920 4.0526041985 3.9975199699 4.2414574623 135 5.3600000000 0.0025266989 0.0015490400 0.0025779437 0.0092504040 2.7816660000 1.2760660000 0.2701210000 0.1402330000 1.0860760000 0.0082930000 108521674 0 1787715584 4.0531134605 3.9970972538 4.2437319756 136 5.4000000000 0.0024817213 0.0015558980 0.0025779437 0.0092558904 2.6767860000 1.3094480000 0.2597010000 0.0000040000 1.0985420000 0.0081970000 108523348 0 1784287232 4.0538821220 3.9963407516 4.2460188866 137 5.4400000000 0.0025073655 0.0015628430 0.0025779437 0.0092542236 3.8131350000 1.2744450000 0.2167220000 0.1406430000 1.0805460000 1.0999000000 108525022 0 1785810944 4.0546565056 3.9961516857 4.2485232353 138 5.4800000000 0.0025533212 0.0015700204 0.0025779437 0.0092359415 2.6573690000 1.2741180000 0.2714100000 0.0000030000 1.1026850000 0.0082620000 108526696 0 1787715584 4.0550823212 3.9962947369 4.2508382797 139 5.5200000000 0.0024624302 0.0015764406 0.0025779437 0.0092255649 2.7641660000 1.2745270000 0.2575270000 0.1410610000 1.0818660000 0.0082480000 108528370 0 1784311808 4.0554828644 3.9959902763 4.2530980110 140 5.5600000000 0.0024853190 0.0015829326 0.0025779437 0.0092189171 2.6287190000 1.2971780000 0.2113770000 0.0000030000 1.1109720000 0.0082810000 108530044 0 1785819136 4.0557508469 3.9955625534 4.2553658485 141 5.6000000000 0.0025796050 0.0015900012 0.0025796050 0.0092719655 3.8640570000 1.2727910000 0.2547930000 0.1414190000 1.0871450000 1.1069710000 108531718 0 1787715584 4.0558142662 3.9952907562 4.2596349716 142 5.6400000000 0.0025666337 0.0015968789 0.0025796050 0.0092796083 2.6593650000 1.2787280000 0.2589040000 0.0000040000 1.1126010000 0.0082030000 108533392 0 1784414208 4.0557303429 3.9948031902 4.2616829872 143 5.6800000000 0.0025251165 0.0016033700 0.0025796050 0.0092834962 2.7740860000 1.2748530000 0.2567900000 0.1418730000 1.0913800000 0.0082950000 108535066 0 1785937920 4.0555734634 3.9943013191 4.2635846138 144 5.7200000000 0.0025953688 0.0016102589 0.0025953688 0.0092812477 2.6977800000 1.3164280000 0.2589980000 0.0000040000 1.1131560000 0.0082100000 108536740 0 1787731968 4.0550909042 3.9944808483 4.2655692101 145 5.7600000000 0.0025807563 0.0016169520 0.0025953688 0.0092713878 3.9055580000 1.2742730000 0.2683720000 0.1419000000 1.1033680000 1.1167210000 108538414 0 1784287232 4.0544676781 3.9944615364 4.2673373222 146 5.8000000000 0.0026284482 0.0016238801 0.0026284482 0.0092739890 2.6007630000 1.2710070000 0.2011940000 0.0000040000 1.1194040000 0.0081810000 108540088 0 1785937920 4.0538578033 3.9947476387 4.2692809105 147 5.8400000000 0.0026047581 0.0016305527 0.0026284482 0.0092660306 2.7385740000 1.2764620000 0.2099250000 0.1421130000 1.1008630000 0.0082640000 108541762 0 1787715584 4.0531806946 3.9937934875 4.2708163261 148 5.8800000000 0.0026979407 0.0016377648 0.0026979407 0.0092484274 2.6525140000 1.3127380000 0.2117520000 0.0000030000 1.1188210000 0.0082610000 108543436 0 1784414208 4.0522837639 3.9931917191 4.2722153664 149 5.9200000000 0.0027180559 0.0016450151 0.0027180559 0.0092321743 3.8617000000 1.2819270000 0.2106840000 0.1421680000 1.1032970000 1.1226810000 108545110 0 1785937920 4.0513277054 3.9931163788 4.2739710808 150 5.9600000000 0.0028053594 0.0016527507 0.0028053594 0.0092163598 2.6732940000 1.2769800000 0.2587760000 0.0000030000 1.1283850000 0.0082040000 108546784 0 1787715584 4.0504040718 3.9929766655 4.2760043144 151 6.0000000000 0.0027624043 0.0016600994 0.0028053594 0.0091978632 2.8022890000 1.2847160000 0.2586400000 0.1428320000 1.1068900000 0.0081940000 108548458 0 1784709120 4.0492768288 3.9927341938 4.2777671814 152 6.0400000000 0.0027962811 0.0016675743 0.0028053594 0.0091836224 2.7049250000 1.3109130000 0.2608240000 0.0000040000 1.1239570000 0.0082540000 108550132 0 1786064896 4.0481705666 3.9925553799 4.2796673775 153 6.0800000000 0.0028423676 0.0016752527 0.0028423676 0.0091720630 3.8705670000 1.2741610000 0.2104560000 0.1421910000 1.1087500000 1.1340570000 108551806 0 1787969536 4.0470952988 3.9923603535 4.2819900513 154 6.1200000000 0.0028744540 0.0016830397 0.0028744540 0.0091567662 2.6593500000 1.2743830000 0.2482680000 0.0000030000 1.1274780000 0.0082530000 108553480 0 1784414208 4.0458440781 3.9919602871 4.2839722633 155 6.1600000000 0.0028101341 0.0016903113 0.0028744540 0.0091379338 2.7572500000 1.2760310000 0.2127100000 0.1422800000 1.1169690000 0.0082680000 108555154 0 1785810944 4.0444250107 3.9916677475 4.2859954834 156 6.2000000000 0.0029124545 0.0016981455 0.0029124545 0.0091488753 2.7216580000 1.3074660000 0.2703870000 0.0000040000 1.1345620000 0.0082590000 108556828 0 1787715584 4.0415396690 3.9908585548 4.2901768684 157 6.2400000000 0.0029970810 0.0017064190 0.0029970810 0.0091323164 3.9224280000 1.2729050000 0.2637890000 0.1421140000 1.1112280000 1.1313570000 108558502 0 1784430592 4.0401263237 3.9908435345 4.2924990654 158 6.2800000000 0.0031251975 0.0017153986 0.0031251975 0.0091156548 2.6668810000 1.2746780000 0.2501330000 0.0000050000 1.1327670000 0.0082600000 108560176 0 1786064896 4.0386281013 3.9905359745 4.2944812775 159 6.3200000000 0.0032099339 0.0017247982 0.0032099339 0.0091026688 2.7964860000 1.2743290000 0.2587910000 0.1420220000 1.1120030000 0.0081910000 108561850 0 1787715584 4.0369825363 3.9904100895 4.2965149879 160 6.3600000000 0.0032992135 0.0017346383 0.0032992135 0.0090869648 2.6764080000 1.2727180000 0.2613200000 0.0000040000 1.1330350000 0.0081990000 108563524 0 1785065472 4.0354213715 3.9905860424 4.2986502647 161 6.4000000000 0.0033144045 0.0017444505 0.0033144045 0.0090774380 3.9186540000 1.2758650000 0.2590510000 0.1419720000 1.1109190000 1.1298240000 108565198 0 1786699776 4.0337409973 3.9905240536 4.3005404472 162 6.4400000000 0.0034290969 0.0017548496 0.0034290969 0.0090848848 2.6794330000 1.2798590000 0.2612270000 0.0000040000 1.1290780000 0.0081920000 108566872 0 1785708544 4.0319609642 3.9904124737 4.3023762703 163 6.4800000000 0.0035023552 0.0017655704 0.0035023552 0.0090770958 2.7543990000 1.2735870000 0.2130540000 0.1419270000 1.1165320000 0.0082280000 108568546 0 1787342848 4.0304012299 3.9904737473 4.3040761948 164 6.5200000000 0.0036559326 0.0017770970 0.0036559326 0.0090632474 2.6217240000 1.2705480000 0.2130060000 0.0000040000 1.1289020000 0.0082630000 108570220 0 1784803328 4.0288863182 3.9906477928 4.3061304092 165 6.5600000000 0.0037286114 0.0017889244 0.0037286114 0.0090551661 3.9744580000 1.2737820000 0.3045580000 0.1420670000 1.1200460000 1.1329410000 108571894 0 1786318848 4.0273022652 3.9904966354 4.3082036972 166 6.6000000000 0.0039638155 0.0018020262 0.0039638155 0.0090413372 2.7119390000 1.2926990000 0.2769810000 0.0000040000 1.1329790000 0.0082520000 108573568 0 1785303040 4.0258455276 3.9906508923 4.3101015091 167 6.6400000000 0.0039747818 0.0018150367 0.0039747818 0.0090316208 2.7594190000 1.2790060000 0.2122580000 0.1423210000 1.1165420000 0.0082700000 108575242 0 1786826752 4.0243563652 3.9909961224 4.3123865128 168 6.6800000000 0.0041104578 0.0018286999 0.0041104578 0.0090160813 2.6760230000 1.2727100000 0.2615820000 0.0000040000 1.1324810000 0.0082250000 108576916 0 1784922112 4.0228691101 3.9905366898 4.3138990402 169 6.7200000000 0.0042344695 0.0018429352 0.0042344695 0.0090019185 3.8861380000 1.2802690000 0.2131750000 0.1416010000 1.1166070000 1.1334400000 108578590 0 1786445824 4.0213818550 3.9904575348 4.3153729439 170 6.7600000000 0.0042837551 0.0018572930 0.0042837551 0.0089878073 2.6471960000 1.2778520000 0.2258110000 0.0000040000 1.1341680000 0.0081790000 108580264 0 1785430016 4.0202550888 3.9903273582 4.3171529770 171 6.8000000000 0.0042995801 0.0018715754 0.0042995801 0.0089752000 2.8125360000 1.2739390000 0.2715880000 0.1412700000 1.1164360000 0.0082670000 108581938 0 1787080704 4.0192270279 3.9895689487 4.3186616898 172 6.8400000000 0.0043758936 0.0018861353 0.0043758936 0.0089588968 2.6846030000 1.2789440000 0.2618210000 0.0000040000 1.1345190000 0.0082620000 108583612 0 1784287232 4.0180702209 3.9890863895 4.3197855949 173 6.8800000000 0.0043259175 0.0019002381 0.0043758936 0.0089445213 3.9355910000 1.2743000000 0.2597020000 0.1411160000 1.1173050000 1.1421220000 108585286 0 1785937920 4.0171208382 3.9885294437 4.3207707405 174 6.9200000000 0.0043556457 0.0019143497 0.0043758936 0.0089539120 2.6317220000 1.2725430000 0.2135560000 0.0000200000 1.1362430000 0.0082290000 108586960 0 1787867136 4.0162816048 3.9880478382 4.3218297958 175 6.9600000000 0.0043569440 0.0019283074 0.0043758936 0.0089723367 2.8022580000 1.2687110000 0.2641120000 0.1408060000 1.1193080000 0.0082060000 108588634 0 1784692736 4.0154452324 3.9874649048 4.3229789734 176 7.0000000000 0.0043589510 0.0019421178 0.0043758936 0.0089814496 2.6837690000 1.2737920000 0.2609260000 0.0000040000 1.1396840000 0.0082390000 108590308 0 1786327040 4.0145950317 3.9869697094 4.3236436844 177 7.0400000000 0.0044148634 0.0019560881 0.0044148634 0.0090077622 3.9379870000 1.2794100000 0.2592620000 0.1404410000 1.1189020000 1.1388900000 108591982 0 1787969536 4.0139942169 3.9864079952 4.3245382309 178 7.0800000000 0.0044583287 0.0019701457 0.0044583287 0.0090146409 2.6900430000 1.2735530000 0.2603230000 0.0000040000 1.1468390000 0.0081980000 108593656 0 1784668160 4.0134119987 3.9858615398 4.3252987862 179 7.1200000000 0.0044251904 0.0019838610 0.0044583287 0.0090220553 2.7952830000 1.2698480000 0.2577510000 0.1400080000 1.1183070000 0.0082660000 108595330 0 1786191872 4.0129280090 3.9854402542 4.3260741234 180 7.1600000000 0.0044376221 0.0019974930 0.0044583287 0.0090504109 2.6676000000 1.2969850000 0.2188140000 0.0000030000 1.1424840000 0.0081800000 108597004 0 1785556992 4.0125212669 3.9849281311 4.3270339966 181 7.2000000000 0.0044563948 0.0020110781 0.0044583287 0.0090699828 3.9581780000 1.2829330000 0.2682030000 0.1398170000 1.1210710000 1.1450180000 108598678 0 1787080704 4.0120010376 3.9845833778 4.3275451660 182 7.2400000000 0.0045610452 0.0020250889 0.0045610452 0.0090891468 2.6469020000 1.2697600000 0.2237470000 0.0000040000 1.1439920000 0.0081870000 108600352 0 1784414208 4.0115175247 3.9844505787 4.3280797005 183 7.2800000000 0.0046032444 0.0020391772 0.0046032444 0.0091156620 2.9981670000 1.2733370000 0.4451190000 0.1395490000 1.1306500000 0.0083810000 108602026 0 1786064896 4.0111250877 3.9841251373 4.3284101486 184 7.3200000000 0.0048283562 0.0020543358 0.0048283562 0.0092585297 2.7473540000 1.3157390000 0.2580710000 0.0000040000 1.1642250000 0.0081840000 108603700 0 1787969536 4.0103945732 3.9837362766 4.3292126656 185 7.3600000000 0.0050405604 0.0020704775 0.0050405604 0.0092828092 3.9397420000 1.2746100000 0.2603050000 0.1389560000 1.1233870000 1.1413410000 108605374 0 1784692736 4.0100793839 3.9835739136 4.3297429085 186 7.4000000000 0.0052298065 0.0020874632 0.0052298065 0.0092851312 2.6926650000 1.2739740000 0.2589860000 0.0000040000 1.1503390000 0.0082280000 108607048 0 1786073088 4.0095582008 3.9832804203 4.3310689926 187 7.4400000000 0.0052768197 0.0021045186 0.0052768197 0.0092724272 2.8052620000 1.2697730000 0.2676300000 0.1387380000 1.1196800000 0.0082810000 108608722 0 1787842560 4.0092334747 3.9830226898 4.3326134682 188 7.4800000000 0.0053376253 0.0021217159 0.0053376253 0.0092590148 2.6884020000 1.2706680000 0.2598050000 0.0000040000 1.1484650000 0.0082480000 108610396 0 1784684544 4.0090222359 3.9827702045 4.3340773582 189 7.5200000000 0.0053646299 0.0021388742 0.0053646299 0.0092531380 3.9048760000 1.2698230000 0.2467260000 0.1386760000 1.1138140000 1.1346630000 108612070 0 1786318848 4.0088744164 3.9824581146 4.3355731964 190 7.5600000000 0.0053998926 0.0021560375 0.0053998926 0.0092628462 2.6846340000 1.2754830000 0.2595120000 0.0000030000 1.1401750000 0.0082220000 108613744 0 1785319424 4.0088801384 3.9825773239 4.3371920586 191 7.6000000000 0.0055971900 0.0021740540 0.0055971900 0.0092525247 2.7477840000 1.2695790000 0.2107200000 0.1385980000 1.1195140000 0.0082060000 108615418 0 1786826752 4.0091714859 3.9824535847 4.3389053345 192 7.6400000000 0.0059350734 0.0021936426 0.0059350734 0.0092415220 2.6796670000 1.2657980000 0.2592440000 0.0000030000 1.1452150000 0.0082470000 108617092 0 1785683968 4.0092411041 3.9822039604 4.3411660194 193 7.6800000000 0.0065519535 0.0022162245 0.0065519535 0.0092311949 3.9363220000 1.2682240000 0.2676830000 0.1401090000 1.1219640000 1.1371670000 108618766 0 1787334656 4.0092306137 3.9821460247 4.3435406685 194 7.7200000000 0.0071619027 0.0022417177 0.0071619027 0.0092191252 2.8246610000 1.2696010000 0.4010150000 0.0000040000 1.1445260000 0.0082040000 108620440 0 1784811520 4.0093603134 3.9821541309 4.3456726074 195 7.7600000000 0.0076548927 0.0022694776 0.0076548927 0.0092063750 2.8633600000 1.2758670000 0.3150840000 0.1398750000 1.1231860000 0.0081650000 108622114 0 1786445824 4.0095529556 3.9820072651 4.3474564552 196 7.8000000000 0.0085749784 0.0023016485 0.0085749784 0.0091960065 2.8938390000 1.2695080000 0.4596180000 0.0000040000 1.1552670000 0.0082460000 108623788 0 1785303040 4.0096774101 3.9817950726 4.3495440483 197 7.8400000000 0.0101667503 0.0023415729 0.0101667503 0.0091888030 4.2533270000 1.2716110000 0.5512820000 0.1407070000 1.1307970000 1.1577310000 108625462 0 1786961920 4.0098304749 3.9815378189 4.3522534370 198 7.8800000000 0.0100697726 0.0023806042 0.0101667503 0.0091737098 2.7151500000 1.2772210000 0.2708200000 0.0000040000 1.1576840000 0.0081640000 108627136 0 1784549376 4.0100564957 3.9814291000 4.3531541824 199 7.9200000000 0.0103926864 0.0024208659 0.0103926864 0.0091636744 2.9281510000 1.2695860000 0.3619570000 0.1418440000 1.1453310000 0.0081930000 108628810 0 1786191872 4.0103282928 3.9811904430 4.3539733887 200 7.9600000000 0.0099192504 0.0024583578 0.0103926864 0.0091559566 2.7995930000 1.2701450000 0.3547760000 0.0000030000 1.1652610000 0.0081950000 108630484 0 1785430016 4.0105476379 3.9809319973 4.3542470932 201 8.0000000000 0.0095888199 0.0024938328 0.0103926864 0.0091428105 4.0119540000 1.2694010000 0.2700360000 0.1426920000 1.1543550000 1.1742550000 108632158 0 1786953728 4.0106744766 3.9807658195 4.3547029495 202 8.0400000000 0.0104953106 0.0025334441 0.0104953106 0.0091371729 2.7278550000 1.2723890000 0.2722160000 0.0000040000 1.1738200000 0.0082120000 108633832 0 1784668160 4.0109124184 3.9806873798 4.3560943604 203 8.0800000000 0.0099779163 0.0025701163 0.0104953106 0.0091280782 2.9060840000 1.2773450000 0.3170910000 0.1440250000 1.1581250000 0.0082330000 108635506 0 1786191872 4.0110206604 3.9807457924 4.3558835983 204 8.1200000000 0.0099270940 0.0026061799 0.0104953106 0.0091267513 2.7762800000 1.3042720000 0.2717500000 0.0000040000 1.1907990000 0.0082260000 108637180 0 1785556992 4.0111317635 3.9808101654 4.3563795090 205 8.1600000000 0.0104216337 0.0026443041 0.0104953106 0.0091305358 4.2407070000 1.2699140000 0.4574200000 0.1454220000 1.1706730000 1.1959940000 108638854 0 1786953728 4.0111942291 3.9808967113 4.3575139046 206 8.1999999990 0.0104104755 0.0026820040 0.0104953106 0.0091316200 2.7555110000 1.2769580000 0.2716310000 0.0000040000 1.1974310000 0.0082400000 108640528 0 1784922112 4.0111861229 3.9812095165 4.3576459885 207 8.2400000000 0.0098457709 0.0027166115 0.0104953106 0.0091569825 2.9271550000 1.2696340000 0.3061050000 0.1469420000 1.1950220000 0.0082050000 108642202 0 1786318848 4.0112934113 3.9812986851 4.3573679924 208 8.2799999990 0.0100227883 0.0027517374 0.0104953106 0.0091918155 2.8138930000 1.2737850000 0.3177890000 0.0000040000 1.2128030000 0.0082590000 108643876 0 1785819136 4.0112810135 3.9814376831 4.3576507568 209 8.3200000000 0.0096661858 0.0027848209 0.0104953106 0.0092171995 4.1611290000 1.2706640000 0.3211030000 0.1479460000 1.1991120000 1.2210230000 108645550 0 1787342848 4.0112605095 3.9813036919 4.3572387695 210 8.3599999990 0.0094394479 0.0028165096 0.0104953106 0.0092141902 2.8293440000 1.2734130000 0.3192970000 0.0000030000 1.2270990000 0.0082440000 108647224 0 1784541184 4.0111308098 3.9814100266 4.3571467400 211 8.4000000000 0.0091202594 0.0028463852 0.0104953106 0.0092043577 3.1940580000 1.2713840000 0.5500970000 0.1490310000 1.2140850000 0.0081720000 108648898 0 1786064896 4.0111341476 3.9815471172 4.3566408157 212 8.4399999990 0.0094163967 0.0028773758 0.0104953106 0.0092028072 2.7921250000 1.2714740000 0.2751800000 0.0000040000 1.2359680000 0.0081570000 108650572 0 1787969536 4.0111141205 3.9818537235 4.3564596176 213 8.4800000000 0.0093067130 0.0029075605 0.0104953106 0.0092126692 4.2735220000 1.2729690000 0.3614840000 0.1499380000 1.2283680000 1.2594940000 108652246 0 1784541184 4.0111370087 3.9818542004 4.3560328484 214 8.5200000000 0.0089483485 0.0029357885 0.0104953106 0.0092076661 2.7894440000 1.2710700000 0.2588360000 0.0000040000 1.2499890000 0.0081990000 108653920 0 1786064896 4.0111770630 3.9819221497 4.3551044464 215 8.5600000000 0.0093892151 0.0029658044 0.0104953106 0.0092005100 2.9486290000 1.2711860000 0.2737990000 0.1507100000 1.2434140000 0.0082220000 108655594 0 1787969536 4.0110712051 3.9823443890 4.3551812172 216 8.6000000000 0.0092992764 0.0029951260 0.0104953106 0.0092047911 2.8130750000 1.2773670000 0.2578960000 0.0000040000 1.2683130000 0.0081900000 108657268 0 1784668160 4.0110030174 3.9826877117 4.3545317650 217 8.6400000000 0.0088667758 0.0030221843 0.0104953106 0.0092120548 4.3726910000 1.2791890000 0.3957610000 0.1516040000 1.2612920000 1.2835470000 108658942 0 1786191872 4.0108618736 3.9829862118 4.3535971642 218 8.6800000000 0.0088106683 0.0030487370 0.0104953106 0.0092260762 3.0790760000 1.2738620000 0.5083650000 0.0000040000 1.2873040000 0.0081780000 108660616 0 1787969536 4.0107512474 3.9833936691 4.3529877663 219 8.7200000000 0.0091387117 0.0030765451 0.0104953106 0.0092413195 3.2644570000 1.2715620000 0.5444780000 0.1524490000 1.2863440000 0.0082690000 108662290 0 1784819712 4.0106158257 3.9838140011 4.3529543877 220 8.7600000000 0.0084640430 0.0031010337 0.0104953106 0.0092475518 2.8887820000 1.2708680000 0.3036230000 0.0000040000 1.3047250000 0.0081650000 108663964 0 1786327040 4.0105605125 3.9841806889 4.3515801430 221 8.8000000000 0.0086313002 0.0031260576 0.0104953106 0.0092635167 4.3209610000 1.2735550000 0.2681740000 0.1531480000 1.3034410000 1.3213080000 108665638 0 1787969536 4.0104627609 3.9843912125 4.3513698578 222 8.8400000000 0.0082664294 0.0031492124 0.0104953106 0.0092657416 2.9743380000 1.2888670000 0.3440580000 0.0000040000 1.3318840000 0.0082000000 108667312 0 1784541184 4.0103487968 3.9847486019 4.3504118919 223 8.8800000000 0.0080561042 0.0031712164 0.0104953106 0.0092765615 3.0103330000 1.2758860000 0.2569260000 0.1536760000 1.3141630000 0.0083120000 108668986 0 1786064896 4.0100450516 3.9852063656 4.3495135307 224 8.9200000000 0.0080287652 0.0031929019 0.0104953106 0.0093024617 2.8934870000 1.2740530000 0.2693560000 0.0000040000 1.3404920000 0.0081900000 108670660 0 1787969536 4.0097455978 3.9854972363 4.3487925529 225 8.9600000000 0.0080483230 0.0032144815 0.0104953106 0.0093222020 4.6029000000 1.2714670000 0.5014180000 0.1543000000 1.3232040000 1.3511470000 108672334 0 1784922112 4.0094013214 3.9860818386 4.3479862213 226 9.0000000000 0.0075069238 0.0032334746 0.0104953106 0.0093470675 2.9502510000 1.2772880000 0.3152700000 0.0000040000 1.3480850000 0.0081920000 108674008 0 1786572800 4.0091567039 3.9863941669 4.3465456963 227 9.0400000000 0.0076788864 0.0032530579 0.0104953106 0.0093666504 3.0065200000 1.2813770000 0.2215580000 0.1546060000 1.3392980000 0.0082430000 108675682 0 1785446400 4.0087604523 3.9868490696 4.3459281921 228 9.0800000000 0.0080679040 0.0032741757 0.0104953106 0.0093978697 3.1891350000 1.2742240000 0.5404390000 0.0000050000 1.3648100000 0.0082370000 108677356 0 1786953728 4.0083665848 3.9873237610 4.3455758095 229 9.1200000000 0.0079699196 0.0032946811 0.0104953106 0.0094276513 4.5112130000 1.2768200000 0.3503220000 0.1553640000 1.3522400000 1.3750390000 108679030 0 1784311808 4.0079545975 3.9873976707 4.3445081711 230 9.1600000000 0.0077064699 0.0033138628 0.0104953106 0.0094341644 2.8850310000 1.2815210000 0.2243390000 0.0000040000 1.3695720000 0.0081900000 108680704 0 1785819136 4.0074925423 3.9881458282 4.3428773880 231 9.2000000000 0.0075330138 0.0033321275 0.0104953106 0.0094497456 3.1817140000 1.2949920000 0.3519270000 0.1555430000 1.3695390000 0.0082590000 108682378 0 1787723776 4.0069484711 3.9885926247 4.3416905403 232 9.2400000000 0.0076039257 0.0033505404 0.0104953106 0.0094689801 2.9367590000 1.2725210000 0.2712730000 0.0000040000 1.3833540000 0.0082000000 108684052 0 1784414208 4.0064306259 3.9892363548 4.3407130241 233 9.2800000000 0.0080057289 0.0033705198 0.0104953106 0.0094987028 4.5130180000 1.2732900000 0.3104350000 0.1563470000 1.3745160000 1.3969570000 108685726 0 1785810944 4.0058259964 3.9898915291 4.3403415680 234 9.3200000000 0.0077936132 0.0033894219 0.0104953106 0.0095247979 2.9660840000 1.2810120000 0.2743570000 0.0000030000 1.4009640000 0.0083010000 108687400 0 1787842560 4.0051980019 3.9905145168 4.3386187553 235 9.3600000000 0.0077927937 0.0034081597 0.0104953106 0.0095371813 3.0733780000 1.2747540000 0.2505940000 0.1564500000 1.3819730000 0.0081920000 108689074 0 1784414208 4.0045771599 3.9907498360 4.3377194405 236 9.4000000000 0.0077854833 0.0034267076 0.0104953106 0.0095403518 2.9000660000 1.2776540000 0.2146630000 0.0000040000 1.3980430000 0.0082360000 108690748 0 1785810944 4.0038657188 3.9913802147 4.3365216255 237 9.4400000000 0.0077634468 0.0034450061 0.0104953106 0.0095496701 4.6405710000 1.2755420000 0.4005540000 0.1564340000 1.3942810000 1.4123480000 108692422 0 1787842560 4.0030956268 3.9918003082 4.3354601860 238 9.4800000000 0.0078745605 0.0034636177 0.0104953106 0.0096224956 2.9657250000 1.2735140000 0.2696000000 0.0000040000 1.4128860000 0.0082430000 108694096 0 1784287232 4.0012736320 3.9939486980 4.3329453468 239 9.5200000000 0.0078184837 0.0034818389 0.0104953106 0.0096510516 3.0576050000 1.2777650000 0.2112650000 0.1564800000 1.4024250000 0.0081760000 108695770 0 1785937920 4.0003185272 3.9946882725 4.3317594528 240 9.5600000000 0.0079238620 0.0035003473 0.0104953106 0.0096765498 2.9790400000 1.2807240000 0.2612910000 0.0000040000 1.4272960000 0.0081950000 108697444 0 1787850752 3.9992482662 3.9963219166 4.3302574158 241 9.6000000000 0.0079608597 0.0035188557 0.0104953106 0.0097439479 4.5827650000 1.2680520000 0.3014260000 0.1567430000 1.4124380000 1.4425820000 108699118 0 1784303616 3.9981892109 3.9971671104 4.3292813301 242 9.6400000000 0.0081964741 0.0035381847 0.0104953106 0.0098151075 2.9717380000 1.2710090000 0.2583930000 0.0000040000 1.4326120000 0.0081690000 108700792 0 1785810944 3.9971749783 3.9982025623 4.3282446861 243 9.6800000000 0.0083131688 0.0035578348 0.0104953106 0.0098706704 3.1314570000 1.2712440000 0.2669890000 0.1567500000 1.4267720000 0.0082340000 108702466 0 1787842560 3.9960982800 3.9992239475 4.3266606331 244 9.7200000000 0.0084280837 0.0035777948 0.0104953106 0.0099248463 2.9756000000 1.2704160000 0.2577930000 0.0000040000 1.4376700000 0.0082510000 108704140 0 1784414208 3.9949843884 4.0002608299 4.3254785538 245 9.7600000000 0.0082851443 0.0035970085 0.0104953106 0.0099684981 4.5695200000 1.2800570000 0.2566800000 0.1569320000 1.4243030000 1.4500660000 108705814 0 1785810944 3.9940135479 4.0007586479 4.3239459991 246 9.8000000000 0.0084398901 0.0036166950 0.0104953106 0.0099946119 3.0792970000 1.2752610000 0.3544480000 0.0000040000 1.4399440000 0.0081670000 108707488 0 1787715584 3.9928214550 4.0018558502 4.3224425316 247 9.8400000000 0.0084168157 0.0036361287 0.0104953106 0.0100329308 3.1759550000 1.2708380000 0.3044050000 0.1569340000 1.4340320000 0.0081580000 108709162 0 1784541184 3.9918076992 4.0029950142 4.3209815025 248 9.8800000000 0.0084140683 0.0036553946 0.0104953106 0.0100827293 3.0309590000 1.2719160000 0.3058040000 0.0000040000 1.4435070000 0.0082340000 108710836 0 1785802752 3.9907205105 4.0040440559 4.3192067146 249 9.9200000000 0.0085537024 0.0036750665 0.0104953106 0.0101356984 4.5819290000 1.2710400000 0.2562250000 0.1569790000 1.4384710000 1.4577230000 108712510 0 1787842560 3.9897122383 4.0048651695 4.3176765442 250 9.9600000000 0.0085324189 0.0036944959 0.0104953106 0.0101792821 2.9559210000 1.2767760000 0.2123190000 0.0000030000 1.4571320000 0.0081810000 108714184 0 1784295424 3.9887051582 4.0057582855 4.3161892891 251 10.0000000000 0.0084937662 0.0037136165 0.0104953106 0.0102222111 3.1320390000 1.2712670000 0.2571120000 0.1571750000 1.4368050000 0.0081620000 108715858 0 1785946112 3.9876174927 4.0070986748 4.3145394325 252 10.0400000000 0.0086309100 0.0037331296 0.0104953106 0.0102825589 2.9562980000 1.2771200000 0.2112000000 0.0000040000 1.4582760000 0.0081990000 108717532 0 1787715584 3.9866418839 4.0082182884 4.3129935265 253 10.0800000000 0.0086794440 0.0037526802 0.0104953106 0.0103179056 4.5708390000 1.2692460000 0.2217110000 0.1572110000 1.4498290000 1.4713270000 108719206 0 1784303616 3.9857673645 4.0093073845 4.3112435341 254 10.1200000000 0.0087611200 0.0037723985 0.0104953106 0.0103532434 3.0159040000 1.2721930000 0.2692010000 0.0000040000 1.4648540000 0.0081450000 108720880 0 1785937920 3.9848160744 4.0105481148 4.3096470833 255 10.1600000000 0.0088567268 0.0037923371 0.0104953106 0.0104018027 3.1624520000 1.2781130000 0.2551580000 0.1580910000 1.4613980000 0.0081830000 108722554 0 1787715584 3.9837808609 4.0116724968 4.3080182076 256 10.2000000000 0.0086875763 0.0038114591 0.0104953106 0.0104430287 3.0132420000 1.2699860000 0.2573610000 0.0000030000 1.4761620000 0.0081220000 108724228 0 1784684544 3.9829542637 4.0125689507 4.3061542511 257 10.2400000000 0.0087541593 0.0038306914 0.0104953106 0.0104858999 4.6242950000 1.2700590000 0.2546600000 0.1576440000 1.4525470000 1.4877630000 108746382 0 1786064896 3.9819815159 4.0136127472 4.3047561646 258 10.2800000000 0.0086185010 0.0038492488 0.0104953106 0.0104974927 3.0100770000 1.2734440000 0.2567990000 0.0000050000 1.4701470000 0.0080640000 108790040 0 1788096512 3.9812059402 4.0144929886 4.3028860092 259 10.3200000000 0.0085653709 0.0038674577 0.0104953106 0.0104990329 3.1611090000 1.2747810000 0.2555980000 0.1636130000 1.4574160000 0.0080740000 108791714 0 1784430592 3.9803020954 4.0153341293 4.3012142181 260 10.3600000000 0.0087010469 0.0038860485 0.0104953106 0.0105167072 3.0119920000 1.2722930000 0.2546620000 0.0000040000 1.4752390000 0.0081570000 108793388 0 1786073088 3.9792866707 4.0167131424 4.2995934486 261 10.4000000000 0.0087178499 0.0039045611 0.0104953106 0.0105498470 4.6353190000 1.2774200000 0.2514750000 0.1582280000 1.4586480000 1.4879040000 108795062 0 1787850752 3.9785063267 4.0174040794 4.2980761528 262 10.4400000000 0.0085175987 0.0039221681 0.0104953106 0.0105613308 3.0295990000 1.2763700000 0.2658930000 0.0000030000 1.4776050000 0.0080820000 108796736 0 1784430592 3.9776647091 4.0179624557 4.2962555885 263 10.4800000000 0.0085889529 0.0039399126 0.0104953106 0.0105612880 3.1609330000 1.2731920000 0.2516950000 0.1585290000 1.4677990000 0.0080360000 108798410 0 1785937920 3.9768006802 4.0188965797 4.2947802544 264 10.5200000000 0.0084913177 0.0039571527 0.0104953106 0.0105643423 3.0256280000 1.2717670000 0.2625990000 0.0000040000 1.4815240000 0.0080880000 108800084 0 1787842560 3.9758760929 4.0197353363 4.2929673195 265 10.5600000000 0.0085719554 0.0039745671 0.0104953106 0.0105897067 4.6763370000 1.2720700000 0.2655350000 0.1589260000 1.4725160000 1.5055910000 108801758 0 1784430592 3.9749910831 4.0199947357 4.2917156219 266 10.6000000000 0.0085957665 0.0039919400 0.0104953106 0.0105879526 3.0344080000 1.2731190000 0.2528650000 0.0000050000 1.4986620000 0.0080480000 108803432 0 1785937920 3.9742574692 4.0205111504 4.2899670601 267 10.6400000000 0.0086161783 0.0040092593 0.0104953106 0.0105717955 3.2123610000 1.3013950000 0.2611030000 0.1591940000 1.4810540000 0.0080100000 108805106 0 1784041472 3.9733903408 4.0212168694 4.2883987427 268 10.6800000000 0.0085172364 0.0040260801 0.0104953106 0.0105622635 3.0273180000 1.2772270000 0.2421660000 0.0000040000 1.4981390000 0.0079940000 108806780 0 1785708544 3.9725630283 4.0216174126 4.2865176201 269 10.7200000000 0.0086046821 0.0040431009 0.0104953106 0.0105605048 4.6999340000 1.2714500000 0.2508550000 0.1595030000 1.4944030000 1.5220630000 108808454 0 1787469824 3.9716954231 4.0219621658 4.2851400375 270 10.7600000000 0.0087052910 0.0040603683 0.0104953106 0.0105654502 3.0479550000 1.2719030000 0.2534680000 0.0000040000 1.5130160000 0.0079540000 108810128 0 1784438784 3.9708778858 4.0223946571 4.2835001945 271 10.8000000000 0.0086842868 0.0040774307 0.0104953106 0.0105594415 3.1964850000 1.2703590000 0.2645490000 0.1596610000 1.4921130000 0.0080470000 108811802 0 1785962496 3.9701666832 4.0230050087 4.2813115120 272 10.8400000000 0.0086843986 0.0040943681 0.0104953106 0.0105456926 3.0462120000 1.2727000000 0.2521550000 0.0000050000 1.5116860000 0.0079910000 108813476 0 1787715584 3.9692640305 4.0236282349 4.2796034813 273 10.8800000000 0.0086266650 0.0041109699 0.0104953106 0.0105505194 4.7408970000 1.2704700000 0.2495370000 0.1603100000 1.4988810000 1.5600710000 108815150 0 1784922112 3.9684991837 4.0240807533 4.2776689529 274 10.9200000000 0.0086619603 0.0041275794 0.0104953106 0.0105493580 3.1133920000 1.2763570000 0.3051880000 0.0000200000 1.5221500000 0.0079970000 108816824 0 1786699776 3.9676008224 4.0243129730 4.2760381699 275 10.9600000000 0.0088058421 0.0041445912 0.0104953106 0.0105360302 3.3463220000 1.2847660000 0.3828370000 0.1603530000 1.5087580000 0.0079320000 108818498 0 1785556992 3.9670183659 4.0244493484 4.2741498947 276 11.0000000000 0.0087906262 0.0041614247 0.0104953106 0.0105210441 3.1573940000 1.2711860000 0.3488000000 0.0000040000 1.5277660000 0.0078670000 108820172 0 1786843136 3.9663941860 4.0246233940 4.2723426819 277 11.0400000000 0.0086554401 0.0041776486 0.0104953106 0.0105120010 4.8051200000 1.2726420000 0.2922250000 0.1606250000 1.5175890000 1.5603460000 108821846 0 1785049088 3.9654564857 4.0246191025 4.2707190514 278 11.0800000000 0.0087026227 0.0041939254 0.0104953106 0.0105050059 3.0754000000 1.2700520000 0.2593660000 0.0000050000 1.5363790000 0.0079050000 108823520 0 1786699776 3.9647283554 4.0247659683 4.2690901756 279 11.1200000000 0.0086684786 0.0042099633 0.0104953106 0.0104902116 3.2242000000 1.2758950000 0.2587090000 0.1608500000 1.5191350000 0.0078950000 108825194 0 1784320000 3.9641253948 4.0247173309 4.2673730850 280 11.1600000000 0.0086143166 0.0042256931 0.0104953106 0.0104722553 3.0748390000 1.2699780000 0.2617820000 0.0000040000 1.5334340000 0.0078780000 108826868 0 1786089472 3.9633965492 4.0251641273 4.2655615807 281 11.2000000000 0.0086981636 0.0042416094 0.0104953106 0.0104563604 4.8194760000 1.2719460000 0.2908010000 0.1610320000 1.5275440000 1.5664190000 108828542 0 1787715584 3.9625623226 4.0254263878 4.2641201019 282 11.2400000000 0.0086390655 0.0042572032 0.0104953106 0.0104400917 3.0706750000 1.2767520000 0.2450540000 0.0000050000 1.5392400000 0.0078690000 108830216 0 1784684544 3.9618480206 4.0257740021 4.2623476982 283 11.2800000000 0.0085234493 0.0042722783 0.0104953106 0.0104227015 3.3277250000 1.2692680000 0.3430570000 0.1618360000 1.5440190000 0.0077960000 108831890 0 1786208256 3.9605739117 4.0258665085 4.2607922554 284 11.3200000000 0.0086254617 0.0042876064 0.0104953106 0.0104047173 3.0767290000 1.2731580000 0.2434490000 0.0000040000 1.5504860000 0.0078600000 108833564 0 1787969536 3.9599051476 4.0261726379 4.2592601776 285 11.3600000000 0.0087287007 0.0043031892 0.0104953106 0.0103867452 4.8425400000 1.2799610000 0.2530740000 0.1617880000 1.5519340000 1.5940030000 108835238 0 1785319424 3.9588680267 4.0264463425 4.2575640678 286 11.4000000000 0.0086938012 0.0043185410 0.0104953106 0.0103690821 3.1044520000 1.2841110000 0.2431490000 0.0000040000 1.5676320000 0.0077770000 108836912 0 1786843136 3.9580857754 4.0265660286 4.2554302216 287 11.4400000000 0.0087607354 0.0043340190 0.0104953106 0.0103512875 3.2566870000 1.2727880000 0.2412500000 0.1621320000 1.5709710000 0.0077690000 108838586 0 1784573952 3.9570498466 4.0265011787 4.2538814545 288 11.4800000000 0.0086635454 0.0043490521 0.0104953106 0.0103337565 3.0997730000 1.2696820000 0.2424830000 0.0000040000 1.5781420000 0.0076980000 108840260 0 1785954304 3.9561450481 4.0264959335 4.2514681816 289 11.5200000000 0.0087485556 0.0043642753 0.0104953106 0.0103166949 4.9058920000 1.2776430000 0.2513630000 0.1623120000 1.5857630000 1.6269740000 108841934 0 1787867136 3.9543864727 4.0262694359 4.2502412796 290 11.5600000000 0.0086819548 0.0043791638 0.0104953106 0.0102995788 3.1400170000 1.2752310000 0.2567930000 0.0000050000 1.5984370000 0.0077630000 108843608 0 1784803328 3.9532272816 4.0261998177 4.2478628159 291 11.6000000000 0.0086683370 0.0043939032 0.0104953106 0.0102862995 3.2980880000 1.2703200000 0.2500810000 0.1626840000 1.6054480000 0.0077460000 108845282 0 1786335232 3.9517757893 4.0259099007 4.2461676598 292 11.6400000000 0.0085338484 0.0044080811 0.0104953106 0.0102690898 3.1339730000 1.2724840000 0.2396030000 0.0000050000 1.6123020000 0.0077030000 108846956 0 1785683968 3.9502625465 4.0251965523 4.2443456650 293 11.6800000000 0.0085585965 0.0044222467 0.0104953106 0.0102580153 4.9635850000 1.2695380000 0.2487770000 0.1682750000 1.6163680000 1.6588020000 108848630 0 1787097088 3.9485161304 4.0246620178 4.2427334785 294 11.7200000000 0.0085535282 0.0044362987 0.0104953106 0.0102412486 3.1637560000 1.2708370000 0.2507000000 0.0000050000 1.6327210000 0.0076610000 108850304 0 1784684544 3.9466679096 4.0246548653 4.2406463623 295 11.7600000000 0.0084881485 0.0044500338 0.0104953106 0.0102258161 3.3231900000 1.2702090000 0.2487730000 0.1630760000 1.6315720000 0.0076600000 108851978 0 1786208256 3.9445867538 4.0245194435 4.2390456200 296 11.8000000000 0.0085110143 0.0044637533 0.0104953106 0.0102091866 3.1755820000 1.2753380000 0.2484530000 0.0000050000 1.6422370000 0.0077560000 108853652 0 1787969536 3.9425435066 4.0243763924 4.2374277115 297 11.8400000000 0.0086729974 0.0044779258 0.0104953106 0.0101921849 5.0085750000 1.2671670000 0.2356220000 0.1630140000 1.6513520000 1.6895760000 108855326 0 1784922112 3.9403569698 4.0243406296 4.2360711098 298 11.8800000000 0.0085750800 0.0044916747 0.0104953106 0.0101800583 3.2176410000 1.3011400000 0.2474950000 0.0000050000 1.6594970000 0.0076750000 108857000 0 1786445824 3.9383294582 4.0241160393 4.2342934608 299 11.9200000000 0.0085638789 0.0045052941 0.0104953106 0.0101705495 3.3448410000 1.2692620000 0.2474000000 0.1632000000 1.6554990000 0.0076040000 108858674 0 1785581568 3.9358520508 4.0242414474 4.2329201698 300 11.9600000000 0.0084736804 0.0045185220 0.0104953106 0.0101564969 3.2070440000 1.2753470000 0.2472560000 0.0000040000 1.6750340000 0.0075770000 108860348 0 1787088896 3.9335191250 4.0239391327 4.2312502861 301 12.0000000000 0.0085909916 0.0045320518 0.0104953106 0.0101460018 5.0619110000 1.2753680000 0.2358810000 0.1633300000 1.6737980000 1.7116660000 108862022 0 1784795136 3.9311122894 4.0241985321 4.2297635078 302 12.0400000000 0.0085324459 0.0045452982 0.0104953106 0.0101340030 3.2009610000 1.2679700000 0.2371030000 0.0000030000 1.6863880000 0.0076280000 108863696 0 1786318848 3.9286041260 4.0245146751 4.2280845642 303 12.0800000000 0.0085406927 0.0045584843 0.0104953106 0.0101201323 3.3660210000 1.2676120000 0.2445680000 0.1630650000 1.6812690000 0.0076390000 108865370 0 1785556992 3.9261927605 4.0244860649 4.2265505791 304 12.1200000000 0.0085319737 0.0045715550 0.0104953106 0.0101092910 3.2173110000 1.2780710000 0.2354700000 0.0000050000 1.6942930000 0.0076010000 108867044 0 1786953728 3.9237828255 4.0243010521 4.2251014709 305 12.1600000000 0.0085308393 0.0045845362 0.0104953106 0.0101012242 5.1070510000 1.2667730000 0.2345560000 0.1630730000 1.6991330000 1.7416180000 108868718 0 1784557568 3.9212486744 4.0246801376 4.2235121727 306 12.2000000000 0.0085841082 0.0045976067 0.0104953106 0.0100877055 3.2354260000 1.2788080000 0.2348530000 0.0000040000 1.7123080000 0.0075600000 108870392 0 1785937920 3.9186966419 4.0251083374 4.2219195366 307 12.2400000000 0.0086084688 0.0046106714 0.0104953106 0.0100714857 3.4212270000 1.2682690000 0.2755130000 0.1632790000 1.7046470000 0.0076170000 108872066 0 1787969536 3.9162001610 4.0252270699 4.2202820778 308 12.2800000000 0.0085258996 0.0046233832 0.0104953106 0.0100556796 3.2324010000 1.2727410000 0.2339440000 0.0000050000 1.7161390000 0.0075540000 108873740 0 1784668160 3.9138731956 4.0245780945 4.2190608978 309 12.3200000000 0.0085372971 0.0046360496 0.0104953106 0.0100458915 5.1490290000 1.2690740000 0.2344190000 0.1629850000 1.7194660000 1.7612100000 108875414 0 1786200064 3.9113719463 4.0242857933 4.2177581787 310 12.3600000000 0.0085612228 0.0046487115 0.0104953106 0.0100372539 3.2570720000 1.2676390000 0.2464730000 0.0000050000 1.7334690000 0.0075670000 108877088 0 1787969536 3.9088790417 4.0245156288 4.2162837982 311 12.4000000000 0.0085589821 0.0046612847 0.0104953106 0.0100214824 3.4066980000 1.2691560000 0.2431620000 0.1630190000 1.7217860000 0.0076560000 108878762 0 1784541184 3.9061346054 4.0245485306 4.2152152061 312 12.4400000000 0.0085396301 0.0046737153 0.0104953106 0.0100057028 3.2617670000 1.2711700000 0.2441780000 0.0000040000 1.7367640000 0.0076050000 108880436 0 1786191872 3.9037404060 4.0241007805 4.2139868736 313 12.4800000000 0.0086556636 0.0046864372 0.0104953106 0.0099910702 5.1888680000 1.2671490000 0.2347030000 0.1628540000 1.7389200000 1.7833370000 108882110 0 1787969536 3.9013128281 4.0239400864 4.2129154205 314 12.5200000000 0.0085952263 0.0046988855 0.0104953106 0.0099754806 3.3483880000 1.2652470000 0.3196160000 0.0000040000 1.7538890000 0.0076890000 108883784 0 1784684544 3.8984949589 4.0235204697 4.2121224403 315 12.5600000000 0.0085364683 0.0047110683 0.0104953106 0.0099612363 3.4634730000 1.2698710000 0.2768240000 0.1635710000 1.7435430000 0.0076310000 108885458 0 1786191872 3.8962059021 4.0224499702 4.2112503052 316 12.6000000000 0.0086570336 0.0047235556 0.0104953106 0.0099503545 3.2943330000 1.2762630000 0.2460620000 0.0000040000 1.7624640000 0.0075880000 108887132 0 1787969536 3.8938274384 4.0218501091 4.2104263306 317 12.6400000000 0.0086269695 0.0047358692 0.0104953106 0.0099399711 5.3195190000 1.2660400000 0.3176130000 0.1628060000 1.7624380000 1.8087240000 108888806 0 1784287232 3.8917729855 4.0208716393 4.2094931602 318 12.6800000000 0.0086728781 0.0047482497 0.0104953106 0.0099421799 3.3438080000 1.2701540000 0.2926190000 0.0000040000 1.7714920000 0.0075850000 108890480 0 1785946112 3.8896317482 4.0201544762 4.2086734772 319 12.7200000000 0.0087313037 0.0047607358 0.0104953106 0.0099383450 3.7127280000 1.2727210000 0.4952470000 0.1626930000 1.7724570000 0.0076320000 108892154 0 1787596800 3.8875482082 4.0199337006 4.2075347900 320 12.7600000000 0.0087468792 0.0047731925 0.0104953106 0.0099243106 3.4307160000 1.2695230000 0.3749610000 0.0000060000 1.7765990000 0.0076400000 108893828 0 1784303616 3.8856496811 4.0197730064 4.2063050270 321 12.8000000000 0.0087517761 0.0047855868 0.0104953106 0.0099092030 5.2879440000 1.2705170000 0.2474750000 0.1633090000 1.7753770000 1.8292540000 108895502 0 1785810944 3.8840143681 4.0190601349 4.2049822807 322 12.8400000000 0.0089073386 0.0047983873 0.0104953106 0.0098967511 3.3671060000 1.2814420000 0.2913710000 0.0000050000 1.7846110000 0.0076060000 108897176 0 1787731968 3.8825645447 4.0179553032 4.2038650513 323 12.8800000000 0.0089246575 0.0048111621 0.0104953106 0.0098907235 3.5621010000 1.2678780000 0.3337540000 0.1624890000 1.7883110000 0.0076840000 108898850 0 1784557568 3.8808367252 4.0176935196 4.2025809288 324 12.9200000000 0.0089703025 0.0048239990 0.0104953106 0.0098792746 3.3657130000 1.2688980000 0.2889950000 0.0000050000 1.7981660000 0.0075960000 108900524 0 1786064896 3.8789939880 4.0172758102 4.2010836601 325 12.9600000000 0.0090314476 0.0048369450 0.0104953106 0.0098666784 5.3786650000 1.2743400000 0.2870850000 0.1622780000 1.7926940000 1.8602630000 108902198 0 1787969536 3.8775339127 4.0164890289 4.1996917725 326 13.0000000000 0.0087770857 0.0048490313 0.0104953106 0.0098570092 3.3732380000 1.2691100000 0.2889610000 0.0000050000 1.8055110000 0.0076040000 108903872 0 1784692736 3.8760969639 4.0153560638 4.1981267929 327 13.0400000000 0.0088487705 0.0048612629 0.0104953106 0.0098482863 3.5363070000 1.2668770000 0.2882720000 0.1679360000 1.8035150000 0.0076950000 108905546 0 1785946112 3.8743703365 4.0149173737 4.1965003014 328 13.0800000000 0.0089955665 0.0048738675 0.0104953106 0.0098363398 3.3827920000 1.2651290000 0.2925690000 0.0000040000 1.8153310000 0.0076450000 108907220 0 1787842560 3.8728899956 4.0144519806 4.1951422691 329 13.1200000000 0.0091034863 0.0048867235 0.0104953106 0.0098264746 5.4848260000 1.2672340000 0.3745630000 0.1625710000 1.8069730000 1.8714830000 108908894 0 1784176640 3.8713901043 4.0138673782 4.1934328079 330 13.1600000000 0.0092376145 0.0048999080 0.0104953106 0.0098163259 3.3860720000 1.2683770000 0.2935550000 0.0000040000 1.8144230000 0.0076890000 108910568 0 1785810944 3.8699941635 4.0132651329 4.1916513443 331 13.2000000000 0.0092389155 0.0049130168 0.0104953106 0.0098065026 3.5473010000 1.2705430000 0.2920170000 0.1618160000 1.8131770000 0.0076880000 108912242 0 1787715584 3.8685655594 4.0128035545 4.1896986961 332 13.2400000000 0.0092037236 0.0049259406 0.0104953106 0.0097977099 3.4822900000 1.2698960000 0.3775050000 0.0000050000 1.8251730000 0.0076570000 108913916 0 1784176640 3.8670930862 4.0120100975 4.1877412796 333 13.2800000000 0.0090976311 0.0049384682 0.0104953106 0.0097928312 5.4198280000 1.2665610000 0.2901230000 0.1617810000 1.8184660000 1.8808240000 108915590 0 1785700352 3.8659405708 4.0117878914 4.1852412224 334 13.3200000000 0.0090979394 0.0049509217 0.0104953106 0.0097828623 3.4101840000 1.2712060000 0.2907710000 0.0000050000 1.8384460000 0.0076100000 108917264 0 1787588608 3.8645677567 4.0115084648 4.1829452515 335 13.3600000000 0.0092659714 0.0049638024 0.0104953106 0.0097739812 3.7568940000 1.2705320000 0.4930480000 0.1624190000 1.8210790000 0.0077530000 108918938 0 1784692736 3.8632714748 4.0100369453 4.1810169220 336 13.4000000000 0.0092820656 0.0049766544 0.0104953106 0.0098002711 3.3994840000 1.2720990000 0.2896590000 0.0000040000 1.8280110000 0.0076720000 108920612 0 1786073088 3.8621151447 4.0100665092 4.1783652306 337 13.4400000000 0.0093600955 0.0049896616 0.0104953106 0.0098097576 5.5693430000 1.2711660000 0.4183810000 0.1618410000 1.8317660000 1.8841330000 108922286 0 1787969536 3.8607528210 4.0106821060 4.1750206947 338 13.4800000000 0.0092887310 0.0050023808 0.0104953106 0.0098070069 3.3725800000 1.2687030000 0.2499690000 0.0000050000 1.8442100000 0.0076090000 108923960 0 1784176640 3.8594417572 4.0103507042 4.1726188660 339 13.5200000000 0.0092275720 0.0050148445 0.0104953106 0.0098056442 3.7758550000 1.2711910000 0.4977310000 0.1615410000 1.8355650000 0.0076090000 108925634 0 1785810944 3.8580565453 4.0107254982 4.1699590683 340 13.5600000000 0.0093824081 0.0050276903 0.0104953106 0.0097936716 3.4558680000 1.2692390000 0.3396640000 0.0000050000 1.8372100000 0.0076720000 108927308 0 1787588608 3.8565275669 4.0114183426 4.1671457291 341 13.6000000000 0.0094377715 0.0050406230 0.0104953106 0.0097792770 5.6690300000 1.2668770000 0.5199760000 0.1608380000 1.8329520000 1.8863130000 108928982 0 1784430592 3.8552532196 4.0116529465 4.1646766663 342 13.6400000000 0.0096272584 0.0050540343 0.0104953106 0.0097649648 3.6450140000 1.2736490000 0.5278700000 0.0000050000 1.8336510000 0.0076630000 108930656 0 1785937920 3.8538708687 4.0115814209 4.1620011330 343 13.6800000000 0.0098831728 0.0050681134 0.0104953106 0.0097512392 3.7002300000 1.2681220000 0.4231970000 0.1606120000 1.8385050000 0.0076340000 108932330 0 1787969536 3.8529808521 4.0112133026 4.1594138145 344 13.7200000000 0.0099618891 0.0050823395 0.0104953106 0.0097452084 3.6242690000 1.2694410000 0.5047410000 0.0000050000 1.8403020000 0.0076300000 108934004 0 1784184832 3.8521113396 4.0113840103 4.1561274529 345 13.7600000000 0.0097097103 0.0050957521 0.0104953106 0.0097366840 5.5103420000 1.2678740000 0.3345060000 0.1635130000 1.8439430000 1.8970310000 108935678 0 1785810944 3.8510606289 4.0115003586 4.1530156136 346 13.8000000000 0.0097689489 0.0051092585 0.0104953106 0.0097230262 3.3323510000 1.2701820000 0.2148590000 0.0000040000 1.8374770000 0.0077130000 108937352 0 1787588608 3.8501548767 4.0116300583 4.1502256393 347 13.8400000000 0.0098825702 0.0051230144 0.0104953106 0.0097090100 3.5298810000 1.2742550000 0.2506710000 0.1602930000 1.8347840000 0.0077480000 108939026 0 1784430592 3.8491427898 4.0115208626 4.1473536491 348 13.8800000000 0.0099436929 0.0051368670 0.0104953106 0.0096955144 3.6205400000 1.2683380000 0.5010200000 0.0000050000 1.8413260000 0.0076110000 108940700 0 1785937920 3.8480832577 4.0111894608 4.1447196007 349 13.9200000000 0.0097982194 0.0051502233 0.0104953106 0.0096833262 5.4968360000 1.2683260000 0.3358550000 0.1598350000 1.8349500000 1.8957750000 108942374 0 1787842560 3.8471941948 4.0106616020 4.1419100761 350 13.9600000000 0.0098380810 0.0051636171 0.0104953106 0.0096733114 3.4113020000 1.2674220000 0.2926890000 0.0000040000 1.8413520000 0.0077010000 108944048 0 1784811520 3.8463952541 4.0103802681 4.1386861801 351 14.0000000000 0.0098957522 0.0051770990 0.0104953106 0.0096627219 3.5677610000 1.2703460000 0.2938280000 0.1596130000 1.8340510000 0.0076300000 108945722 0 1786191872 3.8456199169 4.0098791122 4.1358828545 352 14.0400000000 0.0100687705 0.0051909958 0.0104953106 0.0096561355 3.4603580000 1.2744320000 0.3374490000 0.0000050000 1.8376420000 0.0076620000 108947396 0 1785102336 3.8447945118 4.0097212791 4.1328010559 353 14.0800000000 0.0099581247 0.0052045004 0.0104953106 0.0096478982 5.5413370000 1.2702850000 0.3783400000 0.1593600000 1.8419140000 1.8892870000 108949070 0 1783914496 3.8441371918 4.0093398094 4.1300296783 354 14.1200000000 0.0098254113 0.0052175538 0.0104953106 0.0096366985 3.3752660000 1.2682070000 0.2527190000 0.0000040000 1.8445360000 0.0076510000 108950744 0 1785430016 3.8430166245 4.0094766617 4.1270914078 355 14.1600000000 0.0099847792 0.0052309826 0.0104953106 0.0096232381 3.6662860000 1.2681610000 0.3902520000 0.1590830000 1.8389490000 0.0076890000 108952418 0 1787334656 3.8422057629 4.0095028877 4.1246900558 356 14.2000000000 0.0099286456 0.0052441783 0.0104953106 0.0096097912 3.3255510000 1.2748510000 0.2021930000 0.0000050000 1.8386770000 0.0076550000 108954092 0 1784303616 3.8413012028 4.0093007088 4.1219425201 357 14.2400000000 0.0098716393 0.0052571404 0.0104953106 0.0095964989 5.4595490000 1.2662720000 0.2987850000 0.1589900000 1.8433780000 1.8899280000 108955766 0 1785810944 3.8406338692 4.0095081329 4.1193046570 358 14.2800000000 0.0102065261 0.0052709655 0.0104953106 0.0095870308 3.5069620000 1.2678500000 0.3856200000 0.0000050000 1.8436500000 0.0076590000 108957440 0 1787715584 3.8399441242 4.0099563599 4.1172881126 359 14.3200000000 0.0101606818 0.0052845859 0.0104953106 0.0095802023 3.5362050000 1.2709900000 0.2509670000 0.1594330000 1.8450180000 0.0076300000 108959114 0 1784303616 3.8395452499 4.0089454651 4.1146917343 360 14.3600000000 0.0101691177 0.0052981540 0.0104953106 0.0095679508 3.4196990000 1.2665550000 0.2964530000 0.0000050000 1.8467650000 0.0077320000 108960788 0 1785810944 3.8393492699 4.0079913139 4.1124033928 361 14.4000000000 0.0101198144 0.0053115104 0.0104953106 0.0095647679 5.4775590000 1.2754640000 0.2945110000 0.1586550000 1.8493120000 1.8974230000 108962462 0 1787740160 3.8386869431 4.0078196526 4.1101236343 362 14.4400000000 0.0102006868 0.0053250164 0.0104953106 0.0095538648 3.3826730000 1.2720990000 0.2464280000 0.0000050000 1.8542920000 0.0076360000 108964136 0 1784311808 3.8383033276 4.0079030991 4.1073193550 363 14.4800000000 0.0100423200 0.0053380118 0.0104953106 0.0095411265 3.6342440000 1.2903130000 0.3191610000 0.1581940000 1.8567130000 0.0076480000 108965810 0 1785810944 3.8378021717 4.0069966316 4.1052327156 364 14.5200000000 0.0101698413 0.0053512860 0.0104953106 0.0095329536 3.4378460000 1.2678080000 0.2912770000 0.0000040000 1.8689780000 0.0075850000 108967484 0 1787715584 3.8374550343 4.0067276955 4.1028342247 365 14.5600000000 0.0103778411 0.0053650574 0.0104953106 0.0095224848 5.4495690000 1.2672080000 0.2459350000 0.1579390000 1.8570060000 1.9192050000 108969158 0 1784320000 3.8367934227 4.0074400902 4.1003413200 366 14.6000000000 0.0103088720 0.0053785651 0.0104953106 0.0095132925 3.5318520000 1.3018310000 0.3322710000 0.0000040000 1.8876590000 0.0078440000 108970832 0 1785810944 3.8368532658 4.0074572563 4.0980014801 367 14.6400000000 0.0102575300 0.0053918593 0.0104953106 0.0095045682 3.6353890000 1.2743990000 0.3317660000 0.1575300000 1.8617640000 0.0076790000 108972506 0 1787858944 3.8366200924 4.0061535835 4.0956058502 368 14.6800000000 0.0102131600 0.0054049606 0.0104953106 0.0094952304 3.4876670000 1.2685360000 0.3319930000 0.0000040000 1.8771240000 0.0076010000 108974180 0 1784700928 3.8362398148 4.0055460930 4.0932397842 369 14.7200000000 0.0103063053 0.0054182434 0.0104953106 0.0094861146 5.4667910000 1.2691130000 0.2455710000 0.1570300000 1.8679620000 1.9248510000 108975854 0 1786208256 3.8354876041 4.0056009293 4.0908451080 370 14.7600000000 0.0102521069 0.0054313079 0.0104953106 0.0094740296 3.4108840000 1.2662370000 0.2479240000 0.0000040000 1.8867520000 0.0076730000 108977528 0 1785581568 3.8352494240 4.0058593750 4.0887179375 371 14.8000000000 0.0101803988 0.0054441087 0.0104953106 0.0094615595 3.8073050000 1.2681880000 0.4967290000 0.1565050000 1.8760040000 0.0076050000 108979202 0 1787105280 3.8344726562 4.0063629150 4.0860309601 372 14.8400000000 0.0104616527 0.0054575967 0.0104953106 0.0094548279 3.4491020000 1.2714560000 0.2790150000 0.0000050000 1.8886350000 0.0076060000 108980876 0 1784827904 3.8339102268 4.0065994263 4.0830917358 373 14.8800000000 0.0103385421 0.0054706824 0.0104953106 0.0094482522 5.5657410000 1.2667460000 0.3190310000 0.1561870000 1.8869540000 1.9344940000 108982550 0 1786335232 3.8337409496 4.0068907738 4.0803623199 374 14.9200000000 0.0103567261 0.0054837466 0.0104953106 0.0094527990 3.4192560000 1.2645710000 0.2455050000 0.0000050000 1.8992070000 0.0076640000 108984224 0 1785683968 3.8330173492 4.0072798729 4.0780320168 375 14.9600000000 0.0104895448 0.0054970954 0.0104953106 0.0094660200 3.5762700000 1.2700170000 0.2435650000 0.1555180000 1.8972310000 0.0076480000 108985898 0 1787224064 3.8320915699 4.0062198639 4.0760297775 376 15.0000000000 0.0104673533 0.0055103142 0.0104953106 0.0094566071 3.4541750000 1.2675110000 0.2799420000 0.0000050000 1.8966540000 0.0075800000 108987572 0 1784827904 3.8319509029 4.0056629181 4.0737471581 377 15.0400000000 0.0103577161 0.0055231720 0.0104953106 0.0094445488 5.5525120000 1.2685780000 0.2948340000 0.1550890000 1.8914670000 1.9401860000 108989246 0 1786462208 3.8306531906 4.0066080093 4.0713000298 378 15.0800000000 0.0105276508 0.0055364114 0.0105276508 0.0094542339 3.4585760000 1.2711000000 0.2808990000 0.0000050000 1.8966720000 0.0075760000 108990920 0 1785708544 3.8305082321 4.0063133240 4.0685272217 379 15.1200000000 0.0108050620 0.0055503129 0.0108050620 0.0094499820 3.5707200000 1.2672440000 0.2452860000 0.1545420000 1.8936590000 0.0076250000 108992594 0 1787232256 3.8302483559 4.0055551529 4.0661406517 380 15.1600000000 0.0105557060 0.0055634849 0.0108050620 0.0094375440 3.5838380000 1.2638080000 0.4110750000 0.0000060000 1.8990670000 0.0075760000 108994268 0 1784692736 3.8294916153 4.0055041313 4.0632753372 381 15.2000000000 0.0108747436 0.0055774253 0.0108747436 0.0094263066 5.5112680000 1.2716820000 0.2452620000 0.1535130000 1.8932520000 1.9452300000 108995942 0 1786208256 3.8285121918 4.0058169365 4.0610804558 382 15.2400000000 0.0110068629 0.0055916384 0.0110068629 0.0094151409 3.4651270000 1.2675800000 0.2888210000 0.0000050000 1.8988490000 0.0075560000 108997616 0 1785430016 3.8282198906 4.0055584908 4.0581550598 383 15.2800000000 0.0105847185 0.0056046752 0.0110068629 0.0094029686 3.5743670000 1.2670880000 0.2515500000 0.1528790000 1.8929610000 0.0075450000 108999290 0 1786953728 3.8273186684 4.0052843094 4.0560016632 384 15.3200000000 0.0108217699 0.0056182614 0.0110068629 0.0093914045 3.4766140000 1.2672350000 0.2888770000 0.0000050000 1.9106170000 0.0075470000 109000964 0 1784684544 3.8260059357 4.0057826042 4.0533380508 385 15.3600000000 0.0106868092 0.0056314264 0.0110068629 0.0093817340 5.5902600000 1.2673110000 0.3293340000 0.1521820000 1.8952100000 1.9438610000 109002638 0 1786208256 3.8248541355 4.0059962273 4.0510787964 386 15.4000000000 0.0107538281 0.0056446969 0.0110068629 0.0093711404 3.4242660000 1.2666780000 0.2462940000 0.0000040000 1.9014170000 0.0075390000 109004312 0 1785200640 3.8241105080 4.0061850548 4.0481548309 387 15.4400000000 0.0108648119 0.0056581856 0.0110068629 0.0093593299 3.8133920000 1.2727040000 0.4840880000 0.1516210000 1.8950320000 0.0075600000 109005986 0 1786961920 3.8228058815 4.0068240166 4.0453882217 388 15.4800000000 0.0107603054 0.0056713354 0.0110068629 0.0093514498 3.6894560000 1.2680300000 0.5036490000 0.0000050000 1.9078660000 0.0075330000 109007660 0 1784795136 3.8214552402 4.0074505806 4.0434188843 389 15.5200000000 0.0105997035 0.0056840047 0.0110068629 0.0093483569 5.5365480000 1.2671430000 0.2859580000 0.1509720000 1.8975350000 1.9325430000 109009334 0 1786335232 3.8205127716 4.0076870918 4.0406751633 390 15.5600000000 0.0107986555 0.0056971192 0.0110068629 0.0093418750 3.6847160000 1.2664450000 0.5026690000 0.0000040000 1.9056850000 0.0075270000 109011008 0 1785303040 3.8188421726 4.0081930161 4.0384116173 391 15.6000000000 0.0104552889 0.0057092884 0.0110068629 0.0093328050 3.6125510000 1.2675140000 0.2893880000 0.1506040000 1.8950640000 0.0076000000 109012682 0 1786826752 3.8174343109 4.0089192390 4.0358805656 392 15.6400000000 0.0105738705 0.0057216981 0.0110068629 0.0093332602 3.4549630000 1.2637660000 0.2874220000 0.0000050000 1.8938480000 0.0075180000 109014356 0 1784938496 3.8159532547 4.0096306801 4.0334806442 393 15.6800000000 0.0106063103 0.0057341271 0.0110068629 0.0093311371 5.4779690000 1.2639960000 0.2510230000 0.1502470000 1.8872090000 1.9230820000 109016030 0 1786462208 3.8152318001 4.0099687576 4.0310115814 394 15.7200000000 0.0105810855 0.0057464290 0.0110068629 0.0093264480 3.6729940000 1.2697490000 0.5022450000 0.0000040000 1.8909490000 0.0076290000 109017704 0 1785462784 3.8138895035 4.0104746819 4.0286478996 395 15.7600000000 0.0106421141 0.0057588232 0.0110068629 0.0093196768 3.7746210000 1.2674650000 0.4594000000 0.1498030000 1.8880340000 0.0074980000 109019378 0 1786961920 3.8117384911 4.0114126205 4.0259866714 396 15.8000000000 0.0105691738 0.0057709705 0.0110068629 0.0093154228 3.6596500000 1.2648910000 0.4960280000 0.0000040000 1.8887730000 0.0075200000 109021052 0 1784811520 3.8111033440 4.0122618675 4.0231270790 397 15.8400000000 0.0105656730 0.0057830479 0.0110068629 0.0093197402 5.4578510000 1.2662570000 0.2468280000 0.1494120000 1.8778050000 1.9151270000 109022726 0 1786335232 3.8095459938 4.0129241943 4.0211043358 398 15.8800000000 0.0105854338 0.0057951142 0.0110068629 0.0093291684 3.4822100000 1.2638840000 0.3302870000 0.0000040000 1.8779520000 0.0076450000 109024400 0 1785556992 3.8083374500 4.0124592781 4.0184764862 399 15.9200000000 0.0105955917 0.0058071454 0.0110068629 0.0093216743 3.6847330000 1.2723660000 0.3779160000 0.1503900000 1.8740630000 0.0075380000 109026074 0 1786970112 3.8071303368 4.0123658180 4.0162963867 400 15.9600000000 0.0105794165 0.0058190761 0.0110068629 0.0093109542 3.4056000000 1.2645670000 0.2474280000 0.0000050000 1.8834850000 0.0075610000 109027748 0 1784811520 3.8056871891 4.0135936737 4.0137643814 401 16.0000000000 0.0104671409 0.0058306673 0.0110068629 0.0093157347 5.4336750000 1.2676960000 0.2458030000 0.1491350000 1.8658210000 1.9027660000 109029422 0 1786335232 3.8049860001 4.0136499405 4.0114336014 402 16.0400000000 0.0103895189 0.0058420077 0.0110068629 0.0093121401 3.6518640000 1.2630500000 0.4972060000 0.0000050000 1.8815780000 0.0074860000 109031096 0 1785683968 3.8035030365 4.0139341354 4.0092167854 403 16.0800000000 0.0103395535 0.0058531679 0.0110068629 0.0093139774 3.5313460000 1.2655930000 0.2449000000 0.1487820000 1.8621200000 0.0075080000 109032770 0 1787232256 3.8022468090 4.0146169662 4.0069394112 404 16.1200000000 0.0105305314 0.0058647455 0.0110068629 0.0093294578 3.4002880000 1.2726270000 0.2457680000 0.0000050000 1.8718300000 0.0074920000 109034444 0 1784819712 3.8021109104 4.0153441429 4.0043802261 405 16.1600000000 0.0104890382 0.0058761635 0.0110068629 0.0093506566 5.5797200000 1.2672810000 0.4087430000 0.1479340000 1.8664660000 1.8868290000 109036118 0 1786310656 3.8007788658 4.0149693489 4.0026125908 406 16.2000000000 0.0105311815 0.0058876291 0.0110068629 0.0093456790 3.5206310000 1.2631300000 0.3725900000 0.0000050000 1.8748210000 0.0076160000 109037792 0 1785430016 3.8002834320 4.0165305138 4.0002002716 407 16.2400000000 0.0106548928 0.0058993423 0.0110068629 0.0093612745 3.7717960000 1.2653930000 0.4917150000 0.1474890000 1.8571440000 0.0075800000 109039466 0 1786970112 3.7993907928 4.0167865753 3.9984076023 408 16.2800000000 0.0106023718 0.0059108693 0.0110068629 0.0093662536 3.6280910000 1.2644910000 0.4945350000 0.0000050000 1.8590220000 0.0075520000 109041140 0 1784922112 3.7988126278 4.0168862343 3.9962580204 409 16.3200000000 0.0106531903 0.0059224642 0.0110068629 0.0093594869 5.5092870000 1.2707480000 0.3720880000 0.1477610000 1.8461120000 1.8701050000 109042814 0 1786462208 3.7978699207 4.0169892311 3.9942276478 410 16.3600000000 0.0105360849 0.0059337170 0.0110068629 0.0093500164 3.5492640000 1.2713850000 0.4164050000 0.0000050000 1.8514120000 0.0075740000 109044488 0 1785430016 3.7974545956 4.0180878639 3.9920148849 411 16.3999999990 0.0104980320 0.0059448223 0.0110068629 0.0093569324 3.5576410000 1.2645130000 0.2875850000 0.1469420000 1.8484510000 0.0075920000 109046162 0 1786970112 3.7971932888 4.0185585022 3.9899914265 412 16.4400000000 0.0104447836 0.0059557446 0.0110068629 0.0093625135 3.6297790000 1.2663060000 0.5001620000 0.0000050000 1.8532160000 0.0075530000 109047836 0 1785217024 3.7969346046 4.0191760063 3.9877932072 413 16.4800000000 0.0103578120 0.0059664033 0.0110068629 0.0093609457 5.3556660000 1.2662630000 0.2442520000 0.1467180000 1.8339270000 1.8616260000 109049510 0 1786716160 3.7961957455 4.0192265511 3.9857275486 414 16.5200000000 0.0105081368 0.0059773737 0.0110068629 0.0093531727 3.6149020000 1.2649750000 0.5010820000 0.0000070000 1.8386530000 0.0075470000 109051184 0 1785573376 3.7960770130 4.0195960999 3.9835851192 415 16.5599999990 0.0105765881 0.0059884562 0.0110068629 0.0093424122 3.7274240000 1.2733500000 0.4688100000 0.1468700000 1.8282350000 0.0076110000 109052858 0 1787080704 3.7956228256 4.0205926895 3.9811053276 416 16.6000000000 0.0104647763 0.0059992165 0.0110068629 0.0093358617 3.4507890000 1.2648610000 0.3366890000 0.0000050000 1.8391150000 0.0075700000 109054532 0 1784684544 3.7953004837 4.0206255913 3.9789378643 417 16.6400000000 0.0104824519 0.0060099677 0.0110068629 0.0093303012 5.4743230000 1.2668330000 0.3786220000 0.1469000000 1.8320190000 1.8474170000 109056206 0 1786081280 3.7944557667 4.0212850571 3.9765701294 418 16.6800000000 0.0105201891 0.0060207577 0.0110068629 0.0093298200 3.5348380000 1.2675980000 0.4194100000 0.0000050000 1.8375110000 0.0077340000 109057880 0 1788096512 3.7935624123 4.0223398209 3.9741435051 419 16.7199999990 0.0105017591 0.0060314522 0.0110068629 0.0093417778 3.5017140000 1.2703750000 0.2477130000 0.1460460000 1.8273310000 0.0076100000 109059554 0 1784541184 3.7929334641 4.0235834122 3.9713976383 420 16.7600000000 0.0108704194 0.0060429736 0.0110068629 0.0093637884 3.6204050000 1.2726460000 0.5033160000 0.0000060000 1.8342170000 0.0076880000 109061228 0 1786191872 3.7933030128 4.0238513947 3.9689300060 421 16.8000000000 0.0108157145 0.0060543102 0.0110068629 0.0093604090 5.3553300000 1.2695780000 0.2920640000 0.1455740000 1.8159630000 1.8295850000 109062902 0 1788121088 3.7924587727 4.0244388580 3.9661586285 422 16.8400000000 0.0109428586 0.0060658945 0.0110068629 0.0093553629 3.3787860000 1.2663140000 0.2890720000 0.0000040000 1.8130540000 0.0076640000 109064576 0 1784557568 3.7931365967 4.0253543854 3.9633185863 423 16.8799999990 0.0109021878 0.0060773278 0.0110068629 0.0093504348 3.5066670000 1.2706000000 0.2897650000 0.1456280000 1.7904010000 0.0076690000 109066250 0 1785954304 3.7922894955 4.0259227753 3.9607326984 424 16.9200000000 0.0108528212 0.0060885908 0.0110068629 0.0093451510 3.5808460000 1.2741850000 0.5068600000 0.0000050000 1.7894820000 0.0076730000 109067924 0 1787842560 3.7922260761 4.0269556046 3.9576773643 425 16.9600000000 0.0108879711 0.0060998834 0.0110068629 0.0093618044 5.4424560000 1.2704550000 0.4276230000 0.1449190000 1.7878600000 1.8090450000 109069598 0 1784811520 3.7921717167 4.0272474289 3.9546267986 426 17.0000000000 0.0109659303 0.0061113061 0.0110068629 0.0093607728 3.4913780000 1.2717670000 0.4244640000 0.0000040000 1.7847280000 0.0077240000 109071272 0 1786318848 3.7924623489 4.0274105072 3.9517464638 427 17.0400000000 0.0109331179 0.0061225984 0.0110068629 0.0093506593 3.5148090000 1.2749430000 0.2986550000 0.1458320000 1.7850020000 0.0078250000 109072946 0 1785573376 3.7923831940 4.0270347595 3.9489052296 428 17.0800000000 0.0110348277 0.0061340755 0.0110348277 0.0093398488 3.4015000000 1.2650170000 0.3462500000 0.0000050000 1.7798590000 0.0077790000 109074620 0 1787080704 3.7939918041 4.0278167725 3.9455184937 429 17.1200000000 0.0110169165 0.0061454574 0.0110348277 0.0093300637 5.3411610000 1.2772750000 0.3861510000 0.1447400000 1.7554300000 1.7749170000 109076294 0 1784811520 3.7944123745 4.0279431343 3.9423322678 430 17.1600000000 0.0110661862 0.0061569010 0.0110661862 0.0093194503 3.4324140000 1.2751100000 0.3886960000 0.0000050000 1.7582280000 0.0077650000 109077968 0 1786454016 3.7941238880 4.0282826424 3.9393720627 431 17.2000000000 0.0109694051 0.0061680669 0.0110661862 0.0093087551 3.4390450000 1.2685560000 0.2610890000 0.1439780000 1.7550440000 0.0076890000 109079642 0 1785438208 3.7942228317 4.0290346146 3.9358592033 432 17.2400000000 0.0110958619 0.0061794738 0.0110958619 0.0093030313 3.5438980000 1.2707860000 0.5124030000 0.0000050000 1.7503510000 0.0077350000 109081316 0 1786826752 3.7940714359 4.0295705795 3.9329171181 433 17.2800000000 0.0110075902 0.0061906242 0.0110958619 0.0093007755 5.4273270000 1.2691400000 0.5090120000 0.1435110000 1.7398260000 1.7632060000 109082990 0 1784320000 3.7938470840 4.0297923088 3.9295539856 434 17.3200000000 0.0110938670 0.0062019220 0.0110958619 0.0092936931 3.2730490000 1.2686620000 0.2559600000 0.0000050000 1.7379880000 0.0078000000 109084664 0 1785937920 3.7944302559 4.0302872658 3.9265587330 435 17.3600000000 0.0109585710 0.0062128568 0.0110958619 0.0092842506 3.5553190000 1.2719060000 0.3909090000 0.1439190000 1.7382020000 0.0077810000 109086338 0 1787715584 3.7945456505 4.0315976143 3.9230988026 436 17.4000000000 0.0111100739 0.0062240890 0.0111100739 0.0092922171 3.5372720000 1.2709550000 0.5136820000 0.0000050000 1.7422780000 0.0077060000 109088012 0 1784303616 3.7955415249 4.0321760178 3.9198932648 437 17.4400000000 0.0111390678 0.0062353361 0.0111390678 0.0093082999 5.1773630000 1.2664650000 0.2937040000 0.1430620000 1.7240570000 1.7474410000 109089686 0 1785810944 3.7961854935 4.0324392319 3.9171445370 438 17.4800000000 0.0108947502 0.0062459740 0.0111390678 0.0093058895 3.3379740000 1.2670990000 0.3405720000 0.0000040000 1.7198930000 0.0077510000 109091360 0 1787715584 3.7971529961 4.0325007439 3.9138581753 439 17.5200000000 0.0108966976 0.0062565679 0.0111390678 0.0093044702 3.4769330000 1.2736700000 0.3404450000 0.1427040000 1.7096920000 0.0077650000 109093034 0 1784700928 3.7994265556 4.0329546928 3.9107587337 440 17.5600000000 0.0110056708 0.0062673613 0.0111390678 0.0093087075 3.4997140000 1.2685120000 0.5092380000 0.0000040000 1.7116000000 0.0077280000 109094708 0 1786200064 3.8001396656 4.0333118439 3.9080841541 441 17.6000000000 0.0109894127 0.0062780689 0.0111390678 0.0093129420 5.1647510000 1.2670390000 0.3396500000 0.1424920000 1.6928080000 1.7201120000 109096382 0 1788096512 3.8006980419 4.0338435173 3.9054322243 442 17.6400000000 0.0109039359 0.0062885347 0.0111390678 0.0093241827 3.3098070000 1.2660360000 0.3399790000 0.0000050000 1.6932680000 0.0077280000 109098056 0 1784557568 3.8007867336 4.0334057808 3.9026994705 443 17.6800000000 0.0109788459 0.0062991223 0.0111390678 0.0093266641 3.5353470000 1.2748410000 0.4271910000 0.1422190000 1.6806550000 0.0077820000 109099730 0 1786064896 3.8009338379 4.0329027176 3.9003617764 444 17.7200000000 0.0111159366 0.0063099710 0.0111390678 0.0093196291 3.4816810000 1.2696030000 0.5229110000 0.0000040000 1.6786420000 0.0077870000 109101404 0 1787969536 3.8006603718 4.0329484940 3.8977751732 445 17.7600000000 0.0107874954 0.0063200328 0.0111390678 0.0093091482 5.2810230000 1.2655830000 0.4930070000 0.1428150000 1.6823080000 1.6946230000 109103078 0 1784303616 3.8015487194 4.0335254669 3.8949370384 446 17.8000000000 0.0110345623 0.0063306035 0.0111390678 0.0092995830 3.4798970000 1.2672660000 0.5225970000 0.0000040000 1.6795130000 0.0078100000 109104752 0 1785810944 3.8007547855 4.0338487625 3.8921980858 447 17.8400000000 0.0108975852 0.0063408205 0.0111390678 0.0092929628 3.3908640000 1.2704350000 0.2953280000 0.1417610000 1.6728590000 0.0078100000 109106426 0 1787588608 3.8013367653 4.0343351364 3.8897280693 448 17.8800000000 0.0112025421 0.0063516725 0.0112025421 0.0092840456 3.4635620000 1.2716380000 0.5088250000 0.0000050000 1.6725680000 0.0078120000 109108100 0 1784160256 3.8009057045 4.0346026421 3.8872275352 449 17.9200000000 0.0111370860 0.0063623305 0.0112025421 0.0092769646 5.2909050000 1.2693730000 0.5133140000 0.1416860000 1.6758570000 1.6879270000 109109774 0 1785946112 3.8019547462 4.0335536003 3.8850030899 450 17.9600000000 0.0111445114 0.0063729576 0.0112025421 0.0092669140 3.2146650000 1.2687880000 0.2607700000 0.0000040000 1.6745360000 0.0077990000 109111448 0 1787588608 3.8016538620 4.0346069336 3.8798806667 451 18.0000000000 0.0112025524 0.0063836662 0.0112025524 0.0092735985 3.6011400000 1.2681190000 0.5195950000 0.1418130000 1.6610200000 0.0078630000 109113122 0 1784287232 3.8019292355 4.0343909264 3.8773870468 452 18.0400000000 0.0111297416 0.0063941664 0.0112025524 0.0092809200 3.4621660000 1.2730380000 0.5198470000 0.0000050000 1.6587410000 0.0078240000 109114796 0 1785810944 3.8017222881 4.0330896378 3.8752553463 453 18.0800000000 0.0112172822 0.0064048134 0.0112172822 0.0092858311 5.2756050000 1.2764770000 0.5260980000 0.1417000000 1.6550570000 1.6735460000 109116470 0 1787588608 3.8010640144 4.0324969292 3.8729641438 454 18.1200000000 0.0111652119 0.0064152989 0.0112172822 0.0092806117 3.1523970000 1.2702180000 0.2182270000 0.0000050000 1.6533960000 0.0077610000 109118144 0 1784176640 3.8009240627 4.0330433846 3.8701066971 455 18.1600000000 0.0110300407 0.0064254412 0.0112172822 0.0092705672 3.3826420000 1.2671940000 0.3094880000 0.1410240000 1.6544170000 0.0077940000 109119818 0 1785810944 3.8006033897 4.0341577530 3.8671119213 456 18.2000000000 0.0113054346 0.0064361429 0.0113054346 0.0092610653 3.4585190000 1.2683330000 0.5323250000 0.0000040000 1.6471530000 0.0078610000 109121492 0 1787588608 3.7994980812 4.0353660583 3.8643634319 457 18.2400000000 0.0112071596 0.0064465828 0.0113054346 0.0092640548 5.2318210000 1.2688900000 0.5187290000 0.1406360000 1.6403610000 1.6604710000 109123166 0 1784184832 3.7994868755 4.0350198746 3.8619127274 458 18.2800000000 0.0113083003 0.0064571979 0.0113083003 0.0092606789 3.4351020000 1.2755110000 0.5096130000 0.0000050000 1.6393360000 0.0078840000 109124840 0 1785819136 3.7983334064 4.0358505249 3.8590853214 459 18.3200000000 0.0111627299 0.0064674496 0.0113083003 0.0092775091 3.3032450000 1.2685880000 0.2520190000 0.1404740000 1.6308460000 0.0085010000 109126514 0 1787588608 3.7977821827 4.0358819962 3.8565146923 460 18.3600000000 0.0111972988 0.0064777319 0.0113083003 0.0092831274 3.1994550000 1.2685070000 0.2974570000 0.0000040000 1.6228610000 0.0078380000 109128188 0 1784557568 3.7973642349 4.0360498428 3.8535640240 461 18.4000000000 0.0112004522 0.0064879764 0.0113083003 0.0092800922 4.9566280000 1.2734690000 0.2964610000 0.1401630000 1.6126000000 1.6311730000 109129862 0 1786064896 3.7964987755 4.0363454819 3.8507986069 462 18.4400000000 0.0112554505 0.0064982956 0.0113083003 0.0093019095 3.4108040000 1.2767750000 0.5133000000 0.0000040000 1.6101570000 0.0077770000 109131536 0 1787842560 3.7961597443 4.0355682373 3.8482968807 463 18.4800000000 0.0112440716 0.0065085456 0.0113083003 0.0093076359 3.4902480000 1.2703860000 0.4700390000 0.1400090000 1.5991710000 0.0078410000 109133210 0 1784176640 3.7956519127 4.0357270241 3.8453426361 464 18.5200000000 0.0112678120 0.0065188027 0.0113083003 0.0093084148 3.1690650000 1.2677260000 0.2989230000 0.0000040000 1.5917560000 0.0078630000 109134884 0 1785810944 3.7947437763 4.0351076126 3.8427960873 465 18.5600000000 0.0112373596 0.0065289501 0.0113083003 0.0093057868 4.9044310000 1.2751220000 0.3026230000 0.1403310000 1.5822490000 1.6012540000 109136558 0 1787588608 3.7940802574 4.0355291367 3.8397274017 466 18.6000000000 0.0111841261 0.0065389397 0.0113083003 0.0092966643 3.2150700000 1.2757840000 0.3496180000 0.0000050000 1.5789720000 0.0078620000 109138232 0 1784557568 3.7927646637 4.0367884636 3.8364307880 467 18.6400000000 0.0112294918 0.0065489838 0.0113083003 0.0092867923 3.2698890000 1.2716650000 0.2662060000 0.1395730000 1.5817760000 0.0078530000 109139906 0 1786200064 3.7914235592 4.0380334854 3.8333127499 468 18.6800000000 0.0112911155 0.0065591165 0.0113083003 0.0092775925 3.3924410000 1.2700910000 0.5392430000 0.0000050000 1.5723860000 0.0078120000 109141580 0 1787850752 3.7898108959 4.0392236710 3.8301184177 469 18.7200000000 0.0112922676 0.0065692085 0.0113083003 0.0092773218 5.1052870000 1.2704370000 0.5331680000 0.1401700000 1.5698290000 1.5888620000 109143254 0 1784541184 3.7892925739 4.0396561623 3.8272569180 470 18.7600000000 0.0112858424 0.0065792439 0.0113083003 0.0092678311 3.3806400000 1.2725710000 0.5299610000 0.0000050000 1.5673880000 0.0078360000 109144928 0 1785937920 3.7872705460 4.0423464775 3.8238341808 471 18.8000000000 0.0112679545 0.0065891987 0.0113083003 0.0092997228 3.3272770000 1.2698880000 0.3455390000 0.1391540000 1.5620440000 0.0078280000 109146602 0 1787842560 3.7873873711 4.0420746803 3.8211860657 472 18.8400000000 0.0112661552 0.0065991075 0.0113083003 0.0093887522 3.1433180000 1.2695570000 0.3022820000 0.0000050000 1.5607450000 0.0078550000 109148276 0 1784430592 3.7865662575 4.0432476997 3.8181483746 473 18.8800000000 0.0112344939 0.0066089075 0.0113083003 0.0094551664 4.7892420000 1.2685270000 0.3076640000 0.1393290000 1.5242280000 1.5466820000 109149950 0 1785937920 3.7855732441 4.0428447723 3.8151450157 474 18.9200000000 0.0112707363 0.0066187426 0.0113083003 0.0094550917 3.1567910000 1.2703960000 0.3548840000 0.0000040000 1.5206950000 0.0079490000 109151624 0 1787842560 3.7837822437 4.0433835983 3.8123717308 475 18.9600000000 0.0112384511 0.0066284683 0.0113083003 0.0094507413 3.2844150000 1.2705570000 0.3495780000 0.1390820000 1.5143460000 0.0079930000 109153298 0 1784414208 3.7826187611 4.0447173119 3.8095726967 476 19.0000000000 0.0113121271 0.0066383079 0.0113121271 0.0094663971 3.1537620000 1.2771390000 0.3480160000 0.0000050000 1.5175930000 0.0080470000 109154972 0 1785937920 3.7812910080 4.0464429855 3.8066892624 477 19.0400000000 0.0112453382 0.0066479662 0.0113121271 0.0094650977 4.7501680000 1.2748640000 0.3051950000 0.1391110000 1.5051650000 1.5228860000 109156646 0 1787867136 3.7805118561 4.0483531952 3.8036315441 478 19.0800000000 0.0112807741 0.0066576583 0.0113121271 0.0094564742 3.0942990000 1.2710160000 0.3089940000 0.0000050000 1.5034040000 0.0078840000 109158320 0 1784430592 3.7794258595 4.0505428314 3.8010859489 479 19.1200000000 0.0112170968 0.0066671770 0.0113121271 0.0094549402 3.1631390000 1.2696920000 0.2577370000 0.1387020000 1.4859870000 0.0080070000 109159994 0 1785937920 3.7780826092 4.0514597893 3.7984693050 480 19.1600000000 0.0113357054 0.0066769031 0.0113357054 0.0094569991 3.2977810000 1.2741710000 0.5271780000 0.0000050000 1.4855240000 0.0079300000 109161668 0 1787731968 3.7769641876 4.0524878502 3.7959234715 481 19.2000000000 0.0112199141 0.0066863480 0.0113357054 0.0094539804 4.7196970000 1.2711730000 0.3047070000 0.1385730000 1.4813490000 1.5210280000 109163342 0 1784160256 3.7760350704 4.0531291962 3.7934310436 482 19.2400000000 0.0112756500 0.0066958694 0.0113357054 0.0094515165 3.0711800000 1.2701170000 0.3071470000 0.0000050000 1.4830090000 0.0079050000 109165016 0 1785683968 3.7752697468 4.0542616844 3.7908694744 483 19.2800000000 0.0113256183 0.0067054548 0.0113357054 0.0094725047 3.1397100000 1.2695180000 0.2622270000 0.1382500000 1.4589020000 0.0079140000 109166690 0 1787461632 3.7742068768 4.0535817146 3.7888360023 484 19.3200000000 0.0113188922 0.0067149867 0.0113357054 0.0094701208 3.0524160000 1.2715660000 0.3059910000 0.0000050000 1.4639440000 0.0079680000 109168364 0 1784430592 3.7737679482 4.0539999008 3.7867457867 485 19.3600000000 0.0113183428 0.0067244781 0.0113357054 0.0094619606 4.6461400000 1.2672250000 0.3098900000 0.1383390000 1.4499880000 1.4777700000 109170038 0 1785937920 3.7735257149 4.0542488098 3.7850358486 486 19.4000000000 0.0113065811 0.0067339063 0.0113357054 0.0094533655 2.9925140000 1.2692660000 0.2635510000 0.0000050000 1.4486020000 0.0081850000 109171712 0 1787842560 3.7734136581 4.0549063683 3.7829272747 487 19.4400000000 0.0113883773 0.0067434638 0.0113883773 0.0094469408 3.4016280000 1.2752850000 0.5362710000 0.1379070000 1.4412610000 0.0079720000 109173386 0 1784565760 3.7728188038 4.0560393333 3.7809410095 488 19.4800000000 0.0114324158 0.0067530723 0.0114324158 0.0094432037 2.9918580000 1.2716380000 0.2626310000 0.0000040000 1.4467010000 0.0079780000 109175060 0 1785946112 3.7722246647 4.0567803383 3.7788097858 489 19.5200000000 0.0113973385 0.0067625697 0.0114324158 0.0094477458 4.6528540000 1.2717350000 0.3430300000 0.1377030000 1.4343930000 1.4630470000 109176734 0 1787715584 3.7725410461 4.0564236641 3.7769033909 490 19.5600000000 0.0113851111 0.0067720035 0.0114324158 0.0094427101 2.9816770000 1.2701180000 0.2632950000 0.0000050000 1.4374680000 0.0079280000 109178408 0 1784160256 3.7724111080 4.0571441650 3.7749092579 491 19.6000000000 0.0114821354 0.0067815964 0.0114821354 0.0094345760 3.2083400000 1.2704750000 0.3541070000 0.1373700000 1.4354820000 0.0079290000 109180082 0 1785810944 3.7711706161 4.0574927330 3.7729754448 492 19.6400000000 0.0115054492 0.0067911978 0.0115054492 0.0094262439 3.0682590000 1.2755450000 0.3502770000 0.0000040000 1.4314220000 0.0080600000 109181756 0 1787588608 3.7715215683 4.0584268570 3.7710635662 493 19.6800000000 0.0115068266 0.0068007629 0.0115068266 0.0094214644 4.8111500000 1.2820750000 0.5243560000 0.1371860000 1.4209500000 1.4436930000 109183430 0 1784287232 3.7712132931 4.0585532188 3.7691190243 494 19.7200000000 0.0115111405 0.0068102981 0.0115111405 0.0094137994 2.9700470000 1.2750330000 0.2608670000 0.0000040000 1.4232720000 0.0079690000 109185104 0 1785810944 3.7714464664 4.0595121384 3.7671463490 495 19.7600000000 0.0115179289 0.0068198085 0.0115179289 0.0094162548 3.2400680000 1.2815630000 0.3921540000 0.1371830000 1.4181960000 0.0079830000 109186778 0 1787461632 3.7704410553 4.0590867996 3.7650198936 496 19.8000000000 0.0115279257 0.0068293006 0.0115279257 0.0094167983 3.0477030000 1.2694070000 0.3491600000 0.0000040000 1.4182810000 0.0079420000 109188452 0 1784414208 3.7691538334 4.0592184067 3.7626161575 497 19.8400000000 0.0116069708 0.0068389137 0.0116069708 0.0094138127 4.5414850000 1.2689490000 0.3102260000 0.1369450000 1.3998300000 1.4225850000 109190126 0 1786073088 3.7688448429 4.0587153435 3.7607474327 498 19.8800000000 0.0116623072 0.0068485992 0.0116623072 0.0094092069 3.2273080000 1.2704690000 0.5386880000 0.0000040000 1.4071480000 0.0080240000 109191800 0 1787850752 3.7698025703 4.0569033623 3.7594783306 499 19.9200000000 0.0116588408 0.0068582390 0.0116623072 0.0094004912 3.3560450000 1.2695030000 0.5463840000 0.1368230000 1.3923040000 0.0079970000 109193474 0 1784819712 3.7706804276 4.0571193695 3.7573230267 500 19.9600000000 0.0116526689 0.0068678278 0.0116623072 0.0093915654 2.9525720000 1.2748490000 0.2707290000 0.0000050000 1.3960290000 0.0079380000 109195148 0 1786191872 3.7720186710 4.0576992035 3.7550058365 501 20.0000000000 0.0116800154 0.0068774330 0.0116800154 0.0094058927 4.5167530000 1.2716280000 0.3077270000 0.1371100000 1.3911700000 1.4060880000 109196822 0 1788096512 3.7707443237 4.0556411743 3.7525568008 502 20.0400000000 0.0116594592 0.0068869589 0.0116800154 0.0094230730 2.9386700000 1.2715970000 0.2612170000 0.0000040000 1.3948870000 0.0080120000 109198496 0 1784176640 3.7699341774 4.0548515320 3.7496905327 503 20.0800000000 0.0117803914 0.0068966874 0.0117803914 0.0094149537 3.3374040000 1.2695080000 0.5386540000 0.1369570000 1.3811750000 0.0079550000 109200170 0 1785683968 3.7699213028 4.0559844971 3.7469687462 504 20.1200000000 0.0117523801 0.0069063217 0.0117803914 0.0094064006 2.9893360000 1.2729250000 0.3189730000 0.0000040000 1.3864860000 0.0080130000 109201844 0 1787588608 3.7708461285 4.0565929413 3.7446815968 505 20.1600000000 0.0116975997 0.0069158094 0.0117803914 0.0093983321 4.4659260000 1.2711980000 0.2654110000 0.1366000000 1.3801440000 1.4095590000 109203518 0 1784541184 3.7714357376 4.0577607155 3.7419223785 506 20.2000000000 0.0117262751 0.0069253163 0.0117803914 0.0093900515 2.9818470000 1.2708600000 0.3104630000 0.0000050000 1.3893260000 0.0079540000 109205192 0 1786064896 3.7712030411 4.0587983131 3.7395250797 507 20.2400000000 0.0117223579 0.0069347779 0.0117803914 0.0093855361 3.1054930000 1.2745040000 0.2968080000 0.1364140000 1.3868420000 0.0079640000 109206866 0 1787842560 3.7704896927 4.0576491356 3.7369520664 508 20.2800000000 0.0117627960 0.0069442819 0.0117803914 0.0093791287 2.9463730000 1.2715370000 0.2619370000 0.0000050000 1.4020150000 0.0079380000 109208540 0 1784549376 3.7707920074 4.0576429367 3.7342216969 509 20.3200000000 0.0117577054 0.0069537385 0.0117803914 0.0093765817 4.4602210000 1.2713990000 0.2599410000 0.1365970000 1.3856430000 1.4035510000 109210214 0 1786064896 3.7719507217 4.0570907593 3.7321453094 510 20.3600000000 0.0117712943 0.0069631847 0.0117803914 0.0093779496 2.9867060000 1.2777350000 0.3082090000 0.0000040000 1.3895580000 0.0080250000 109211888 0 1787969536 3.7722251415 4.0581521988 3.7297832966 511 20.4000000000 0.0118626235 0.0069727726 0.0118626235 0.0093707409 3.0564790000 1.2718940000 0.2614030000 0.1365060000 1.3755950000 0.0079610000 109213562 0 1784557568 3.7720634937 4.0587882996 3.7271485329 512 20.4400000000 0.0118418923 0.0069822826 0.0118626235 0.0093624715 2.9240660000 1.2712870000 0.2659990000 0.0000040000 1.3756650000 0.0080350000 109215236 0 1786191872 3.7723553181 4.0594000816 3.7243080139 513 20.4800000000 0.0118787447 0.0069918274 0.0118787447 0.0093548936 4.4875430000 1.2703470000 0.3209990000 0.1365090000 1.3667280000 1.3896620000 109257870 0 1787985920 3.7751393318 4.0608515739 3.7214748859 514 20.5200000000 0.0118596489 0.0070012978 0.0118787447 0.0093495969 3.0202780000 1.2738220000 0.3600070000 0.0000040000 1.3753250000 0.0080220000 109343512 0 1785049088 3.7757749557 4.0608358383 3.7183160782 515 20.5600000000 0.0119274985 0.0070108633 0.0119274985 0.0093433207 3.0417420000 1.2720670000 0.2672000000 0.1364010000 1.3548930000 0.0080470000 109345186 0 1786699776 3.7771582603 4.0602741241 3.7156059742 516 20.6000000000 0.0119272117 0.0070203911 0.0119274985 0.0093401074 2.9552930000 1.2751170000 0.3141510000 0.0000040000 1.3549160000 0.0080540000 109346860 0 1784668160 3.7797346115 4.0597329140 3.7129654884 517 20.6400000000 0.0119979912 0.0070300189 0.0119979912 0.0093326196 4.4972670000 1.2699030000 0.3630000000 0.1362690000 1.3525450000 1.3724740000 109348534 0 1786191872 3.7818646431 4.0601139069 3.7105355263 518 20.6800000000 0.0119692413 0.0070395541 0.0119979912 0.0093272343 2.9950930000 1.2741690000 0.3612140000 0.0000060000 1.3485400000 0.0080810000 109350208 0 1787994112 3.7837548256 4.0608725548 3.7079961300 519 20.7200000000 0.0119785573 0.0070490705 0.0119979912 0.0093224724 3.1180230000 1.2730910000 0.3500050000 0.1363330000 1.3475440000 0.0080060000 109351882 0 1785057280 3.7850837708 4.0615134239 3.7053589821 520 20.7600000000 0.0120486980 0.0070586852 0.0120486980 0.0093178723 3.1671030000 1.2740930000 0.5338160000 0.0000040000 1.3479800000 0.0081250000 109353556 0 1786318848 3.7858915329 4.0612311363 3.7029650211 521 20.8000000000 0.0120615335 0.0070682876 0.0120615335 0.0093095912 4.4690490000 1.2734120000 0.3629420000 0.1360840000 1.3317640000 1.3617650000 109355230 0 1785430016 3.7867262363 4.0623531342 3.7007944584 522 20.8400000000 0.0120663317 0.0070778624 0.0120663317 0.0093013884 2.9866680000 1.2730450000 0.3635260000 0.0000050000 1.3388390000 0.0080620000 109356904 0 1786953728 3.7873611450 4.0644412041 3.6983933449 523 20.8800000000 0.0120856445 0.0070874375 0.0120856445 0.0092931966 3.3118030000 1.2755130000 0.5593060000 0.1359420000 1.3297970000 0.0080180000 109358578 0 1784684544 3.7882308960 4.0649299622 3.6961367130 524 20.9200000000 0.0121373199 0.0070970747 0.0121373199 0.0092853743 3.0234930000 1.2712400000 0.4060960000 0.0000050000 1.3348210000 0.0080990000 109360252 0 1786208256 3.7881937027 4.0649728775 3.6936707497 525 20.9600000000 0.0121154049 0.0071066334 0.0121373199 0.0092796510 4.4498350000 1.2769310000 0.3564790000 0.1359130000 1.3255400000 1.3517010000 109361926 0 1785573376 3.7888054848 4.0651555061 3.6913502216 526 21.0000000000 0.0121626332 0.0071162455 0.0121626332 0.0092757787 3.0301080000 1.2807850000 0.4031270000 0.0000040000 1.3349400000 0.0080840000 109363600 0 1787080704 3.7896056175 4.0658130646 3.6892032623 527 21.0400000000 0.0122011276 0.0071258943 0.0122011276 0.0092708876 3.0637610000 1.2737340000 0.3103090000 0.1361250000 1.3321750000 0.0080740000 109365274 0 1784430592 3.7900612354 4.0660386086 3.6873605251 528 21.0800000000 0.0121791530 0.0071354648 0.0122011276 0.0092726825 2.8897050000 1.2742380000 0.2655440000 0.0000050000 1.3386210000 0.0080530000 109366948 0 1786073088 3.7912490368 4.0662899017 3.6855425835 529 21.1200000000 0.0122133624 0.0071450639 0.0122133624 0.0092715116 4.3788010000 1.2720110000 0.2661840000 0.1360720000 1.3419650000 1.3593210000 109368622 0 1787850752 3.7919139862 4.0654335022 3.6836767197 530 21.1600000000 0.0123068057 0.0071548030 0.0123068057 0.0092728271 2.9036770000 1.2716430000 0.2648860000 0.0000050000 1.3558690000 0.0080150000 109370296 0 1784811520 3.7916002274 4.0654478073 3.6818363667 531 21.2000000000 0.0123578915 0.0071646017 0.0123578915 0.0092795729 3.1190820000 1.2704410000 0.3540150000 0.1361560000 1.3471330000 0.0080630000 109371970 0 1786318848 3.7921371460 4.0657529831 3.6800231934 532 21.2400000000 0.0123265861 0.0071743047 0.0123578915 0.0092892122 3.0218560000 1.2798500000 0.3627540000 0.0000050000 1.3678900000 0.0079700000 109373644 0 1785446400 3.7929985523 4.0642967224 3.6784040928 533 21.2800000000 0.0123646371 0.0071840426 0.0123646371 0.0092977262 4.4296310000 1.2707130000 0.2623320000 0.1364600000 1.3628720000 1.3940100000 109375318 0 1786826752 3.7935585976 4.0640115738 3.6767992973 534 21.3200000000 0.0124507081 0.0071939053 0.0124507081 0.0092917486 3.0179410000 1.2760720000 0.3581140000 0.0000050000 1.3724020000 0.0080500000 109376992 0 1784938496 3.7940192223 4.0632047653 3.6754169464 535 21.3600000000 0.0124490764 0.0072037280 0.0124507081 0.0092888431 3.1012760000 1.2786060000 0.3094090000 0.1366690000 1.3652600000 0.0079870000 109378666 0 1786572800 3.7941994667 4.0622196198 3.6740357876 536 21.4000000000 0.0125495512 0.0072137016 0.0125495512 0.0092880924 3.0261920000 1.2713690000 0.3589580000 0.0000050000 1.3845520000 0.0080180000 109380340 0 1785810944 3.7943634987 4.0625052452 3.6724793911 537 21.4400000000 0.0125486562 0.0072236363 0.0125495512 0.0092861784 4.7268310000 1.2718370000 0.5336100000 0.1371420000 1.3783930000 1.4025480000 109382014 0 1787207680 3.7944626808 4.0615339279 3.6712441444 538 21.4800000000 0.0125691425 0.0072335722 0.0125691425 0.0092972723 2.9363950000 1.2661800000 0.2636780000 0.0000050000 1.3951210000 0.0079700000 109383688 0 1784692736 3.7948646545 4.0613832474 3.6700909138 539 21.5200000000 0.0125497887 0.0072434353 0.0125691425 0.0093139728 3.1205250000 1.2713500000 0.3056030000 0.1370700000 1.3950040000 0.0081820000 109385362 0 1786327040 3.7954666615 4.0603990555 3.6687934399 540 21.5600000000 0.0127454791 0.0072536243 0.0127454791 0.0093214913 2.9456260000 1.2696890000 0.2623560000 0.0000040000 1.4022930000 0.0079820000 109387036 0 1785565184 3.7949764729 4.0602569580 3.6675713062 541 21.6000000000 0.0126975030 0.0072636869 0.0127454791 0.0093259036 4.5117910000 1.2769290000 0.2616420000 0.1374160000 1.4040280000 1.4284040000 109388710 0 1787224064 3.7948796749 4.0599794388 3.6662147045 542 21.6400000000 0.0126949092 0.0072737076 0.0127454791 0.0093267702 3.2442570000 1.2723790000 0.5379480000 0.0000040000 1.4224960000 0.0081090000 109390384 0 1784541184 3.7954056263 4.0586500168 3.6650505066 543 21.6800000000 0.0127458805 0.0072837853 0.0127458805 0.0093289486 3.3678030000 1.2707470000 0.5283040000 0.1380140000 1.4193190000 0.0080740000 109392058 0 1786191872 3.7943966389 4.0577297211 3.6638641357 544 21.7200000000 0.0127374437 0.0072938104 0.0127458805 0.0093262102 3.0673360000 1.2757780000 0.3503940000 0.0000040000 1.4298140000 0.0079910000 109393732 0 1787985920 3.7944345474 4.0566744804 3.6626904011 545 21.7600000000 0.0127748679 0.0073038674 0.0127748679 0.0093212117 4.6707590000 1.2703590000 0.3948690000 0.1441620000 1.4181460000 1.4397570000 109395406 0 1784938496 3.7940068245 4.0553431511 3.6616604328 546 21.8000000000 0.0127608040 0.0073138618 0.0127748679 0.0093273631 3.0414120000 1.2781890000 0.3070970000 0.0000050000 1.4447580000 0.0080070000 109397080 0 1786589184 3.7938003540 4.0544261932 3.6607043743 547 21.8400000000 0.0126996310 0.0073237078 0.0127748679 0.0093506358 3.1090810000 1.2713780000 0.2609160000 0.1392320000 1.4261000000 0.0080920000 109398754 0 1785700352 3.7938952446 4.0529041290 3.6596837044 548 21.8800000000 0.0127162198 0.0073335481 0.0127748679 0.0093641731 3.0080740000 1.2825130000 0.2648530000 0.0000050000 1.4492000000 0.0081320000 109400428 0 1787207680 3.7935540676 4.0519084930 3.6584596634 549 21.9200000000 0.0126715004 0.0073432712 0.0127748679 0.0093743421 4.6195560000 1.2706620000 0.3092470000 0.1398890000 1.4387210000 1.4576340000 109402102 0 1785200640 3.7928900719 4.0483827591 3.6573953629 550 21.9600000000 0.0126794484 0.0073529733 0.0127748679 0.0093832308 3.1793090000 1.2697350000 0.4428320000 0.0000050000 1.4553150000 0.0080600000 109403776 0 1786716160 3.7920832634 4.0476021767 3.6562950611 551 22.0000000000 0.0127351163 0.0073627413 0.0127748679 0.0093807091 3.1703870000 1.2780610000 0.3062690000 0.1402800000 1.4341930000 0.0081540000 109405450 0 1784811520 3.7915141582 4.0478701591 3.6551504135 552 22.0400000000 0.0125299934 0.0073721022 0.0127748679 0.0093771953 3.0005280000 1.2712200000 0.2627610000 0.0000050000 1.4550800000 0.0080680000 109407124 0 1786208256 3.7908246517 4.0467600822 3.6541631222 553 22.0800000000 0.0125995325 0.0073815551 0.0127748679 0.0093772750 4.6240940000 1.2703200000 0.3089580000 0.1408090000 1.4358800000 1.4647400000 109408798 0 1785683968 3.7898168564 4.0448560715 3.6532495022 554 22.1200000000 0.0126652690 0.0073910925 0.0127748679 0.0093853554 3.0497720000 1.2781940000 0.3091460000 0.0000050000 1.4508970000 0.0081260000 109410472 0 1787097088 3.7891156673 4.0447239876 3.6524105072 555 22.1600000000 0.0125996871 0.0074004774 0.0127748679 0.0093884876 3.1716950000 1.2766190000 0.3075690000 0.1419310000 1.4339260000 0.0082040000 109412146 0 1784938496 3.7887766361 4.0460219383 3.6512768269 556 22.2000000000 0.0126757184 0.0074099652 0.0127748679 0.0093823667 2.9968340000 1.2704200000 0.2643240000 0.0000040000 1.4505550000 0.0081320000 109413820 0 1786335232 3.7889256477 4.0458264351 3.6503691673 557 22.2400000000 0.0127242077 0.0074195060 0.0127748679 0.0093751180 4.6164290000 1.2745510000 0.3090790000 0.1417270000 1.4339890000 1.4536370000 109415494 0 1785319424 3.7887122631 4.0442333221 3.6496453285 558 22.2800000000 0.0127082365 0.0074289840 0.0127748679 0.0093735020 3.0478900000 1.2811010000 0.3099160000 0.0000040000 1.4451490000 0.0081850000 109417168 0 1786970112 3.7889463902 4.0437746048 3.6490824223 559 22.3200000000 0.0127083128 0.0074384283 0.0127748679 0.0093769178 3.2660000000 1.2715620000 0.4014680000 0.1420030000 1.4392370000 0.0081900000 109418842 0 1784709120 3.7886583805 4.0434398651 3.6480846405 560 22.3600000000 0.0127036367 0.0074478304 0.0127748679 0.0093743771 3.0021490000 1.2785420000 0.2674260000 0.0000050000 1.4445420000 0.0081950000 109420516 0 1786200064 3.7883267403 4.0435853004 3.6473164558 561 22.4000000000 0.0127518307 0.0074572850 0.0127748679 0.0093719362 4.8543530000 1.2836070000 0.5315590000 0.1421800000 1.4350530000 1.4585190000 109422190 0 1787985920 3.7884519100 4.0429906845 3.6466364861 562 22.4400000000 0.0127249826 0.0074666581 0.0127748679 0.0093686115 3.0066830000 1.2804700000 0.2659660000 0.0000050000 1.4487010000 0.0081150000 109423864 0 1785065472 3.7879815102 4.0423345566 3.6458859444 563 22.4800000000 0.0127311358 0.0074760089 0.0127748679 0.0093658478 3.1363480000 1.2736690000 0.2660700000 0.1424980000 1.4425390000 0.0081480000 109425538 0 1786572800 3.7879283428 4.0418729782 3.6453263760 564 22.5200000000 0.0127669154 0.0074853899 0.0127748679 0.0093659688 3.0014090000 1.2721720000 0.2666430000 0.0000050000 1.4509800000 0.0081160000 109427212 0 1785827328 3.7877762318 4.0418114662 3.6447231770 565 22.5600000000 0.0127501953 0.0074947081 0.0127748679 0.0093685978 4.6388660000 1.2712160000 0.3115990000 0.1428050000 1.4466390000 1.4629890000 109428886 0 1787334656 3.7870502472 4.0409379005 3.6438832283 566 22.6000000000 0.0128023699 0.0075040856 0.0128023699 0.0093682178 3.0474770000 1.2739170000 0.3032730000 0.0000040000 1.4585190000 0.0081370000 109430560 0 1784700928 3.7872672081 4.0407223701 3.6434822083 567 22.6400000000 0.0128244516 0.0075134690 0.0128244516 0.0093664699 3.2736700000 1.2711350000 0.4067680000 0.1430040000 1.4410770000 0.0082020000 109432234 0 1786343424 3.7868609428 4.0403738022 3.6426224709 568 22.6800000000 0.0128034772 0.0075227824 0.0128244516 0.0093657982 3.0937310000 1.2765640000 0.3519450000 0.0000050000 1.4535660000 0.0081870000 109433908 0 1785692160 3.7865936756 4.0396995544 3.6422479153 569 22.7200000000 0.0129058966 0.0075322431 0.0129058966 0.0093723645 4.7263930000 1.2713650000 0.3965040000 0.1431780000 1.4480050000 1.4637790000 109435582 0 1787224064 3.7862744331 4.0395035744 3.6416275501 570 22.7600000000 0.0128965518 0.0075416541 0.0129058966 0.0093751338 3.1573660000 1.2746540000 0.4085840000 0.0000050000 1.4622930000 0.0082080000 109437256 0 1784938496 3.7857992649 4.0391354561 3.6410107613 571 22.8000000000 0.0129019134 0.0075510416 0.0129058966 0.0093803762 3.1900800000 1.2736620000 0.3167550000 0.1433970000 1.4445300000 0.0082500000 109438930 0 1786564608 3.7856385708 4.0381169319 3.6403055191 572 22.8400000000 0.0128891002 0.0075603739 0.0129058966 0.0093905949 3.1004710000 1.2729970000 0.3518670000 0.0000050000 1.4638150000 0.0082840000 109440604 0 1785462784 3.7855296135 4.0384073257 3.6395552158 573 22.8800000000 0.0129121104 0.0075697137 0.0129121104 0.0093899338 4.6465310000 1.2746190000 0.3134550000 0.1437160000 1.4419660000 1.4693010000 109442278 0 1786953728 3.7851591110 4.0379500389 3.6387047768 574 22.9200000000 0.0129631516 0.0075791100 0.0129631516 0.0093918488 3.0528710000 1.2721480000 0.3159110000 0.0000050000 1.4530070000 0.0082140000 109443952 0 1784668160 3.7854883671 4.0371494293 3.6377139091 575 22.9600000000 0.0129705053 0.0075884863 0.0129705053 0.0093962098 3.1925510000 1.2791320000 0.3147620000 0.1439910000 1.4428160000 0.0082180000 109445626 0 1786318848 3.7854907513 4.0364966393 3.6368691921 576 23.0000000000 0.0129491687 0.0075977931 0.0129705053 0.0094034495 3.0578310000 1.2719030000 0.3157430000 0.0000050000 1.4583970000 0.0082880000 109447300 0 1785573376 3.7851331234 4.0356049538 3.6358184814 577 23.0400000000 0.0130794616 0.0076072933 0.0130794616 0.0094112456 4.6863500000 1.2741850000 0.3603100000 0.1443250000 1.4379810000 1.4659190000 109448974 0 1787359232 3.7855143547 4.0346846581 3.6350235939 578 23.0800000000 0.0131733529 0.0076169232 0.0131733529 0.0094198277 3.0050410000 1.2713680000 0.2702410000 0.0000040000 1.4516310000 0.0082800000 109450648 0 1784549376 3.7856173515 4.0336909294 3.6342654228 579 23.1200000000 0.0131733883 0.0076265199 0.0131733883 0.0094255479 3.1910720000 1.2737530000 0.3154060000 0.1447730000 1.4454020000 0.0082450000 109452322 0 1786191872 3.7856073380 4.0327992439 3.6334211826 580 23.1600000000 0.0132073974 0.0076361421 0.0132073974 0.0094319628 3.1512730000 1.2735500000 0.4105510000 0.0000050000 1.4552870000 0.0083060000 109453996 0 1787985920 3.7854585648 4.0321760178 3.6326880455 581 23.2000000000 0.0130737368 0.0076455011 0.0132073974 0.0094344024 4.6982270000 1.2805720000 0.3612270000 0.1449580000 1.4431120000 1.4647610000 109455670 0 1784938496 3.7852830887 4.0310754776 3.6321265697 582 23.2400000000 0.0130571742 0.0076547995 0.0132073974 0.0094358867 3.0654950000 1.2771700000 0.3170910000 0.0000050000 1.4593840000 0.0082940000 109457344 0 1786572800 3.7859711647 4.0306096077 3.6315498352 583 23.2800000000 0.0131007954 0.0076641408 0.0132073974 0.0094429181 3.1980250000 1.2720370000 0.3153350000 0.1451500000 1.4536400000 0.0082910000 109459018 0 1785556992 3.7867755890 4.0307469368 3.6309285164 584 23.3200000000 0.0132021615 0.0076736237 0.0132073974 0.0094434890 3.0694480000 1.2759990000 0.3172040000 0.0000040000 1.4643560000 0.0082740000 109460692 0 1786970112 3.7862982750 4.0294346809 3.6303672791 585 23.3600000000 0.0131801050 0.0076830365 0.0132073974 0.0094540309 4.6718910000 1.2758320000 0.3200500000 0.1455670000 1.4521790000 1.4746360000 109462366 0 1784922112 3.7869369984 4.0289626122 3.6301603317 586 23.4000000000 0.0132230800 0.0076924905 0.0132230800 0.0094700197 3.0770960000 1.2737050000 0.3170860000 0.0000040000 1.4744740000 0.0082240000 109464040 0 1786335232 3.7871313095 4.0292301178 3.6296517849 587 23.4400000000 0.0131233335 0.0077017424 0.0132230800 0.0094744369 3.2098610000 1.2758450000 0.3157550000 0.1467240000 1.4594500000 0.0083890000 109465714 0 1785344000 3.7870869637 4.0286512375 3.6290929317 588 23.4800000000 0.0131856436 0.0077110688 0.0132230800 0.0094799720 3.0777270000 1.2760250000 0.3164490000 0.0000040000 1.4732530000 0.0082810000 109467388 0 1786961920 3.7877104282 4.0281167030 3.6292450428 589 23.5200000000 0.0131870108 0.0077203658 0.0132230800 0.0094867722 4.6403120000 1.2732760000 0.2678260000 0.1462640000 1.4670590000 1.4822830000 109469062 0 1784541184 3.7876811028 4.0279583931 3.6288125515 590 23.5600000000 0.0132293776 0.0077297031 0.0132293776 0.0094910928 3.0383510000 1.2757480000 0.2691980000 0.0000040000 1.4815130000 0.0082870000 109470736 0 1786191872 3.7878234386 4.0277233124 3.6286015511 591 23.6000000000 0.0131946336 0.0077389500 0.0132293776 0.0094905478 3.2575840000 1.2726900000 0.3618460000 0.1464770000 1.4645640000 0.0083070000 109472410 0 1785556992 3.7876651287 4.0262141228 3.6285421848 592 23.6400000000 0.0132348696 0.0077482336 0.0132348696 0.0095010614 3.0873460000 1.2733830000 0.3220770000 0.0000040000 1.4799420000 0.0082930000 109474084 0 1787080704 3.7875597477 4.0256185532 3.6282672882 593 23.6800000000 0.0132630160 0.0077575335 0.0132630160 0.0095062220 4.7040780000 1.2701640000 0.3154010000 0.1467190000 1.4720720000 1.4959970000 109475758 0 1784795136 3.7874743938 4.0252962112 3.6280536652 594 23.7200000000 0.0131380241 0.0077665915 0.0132630160 0.0095047001 3.0840500000 1.2733360000 0.3174760000 0.0000040000 1.4811620000 0.0084260000 109477432 0 1786208256 3.7874133587 4.0247716904 3.6275019646 595 23.7600000000 0.0131779574 0.0077756862 0.0132630160 0.0095058293 3.2333270000 1.2818600000 0.3178970000 0.1479540000 1.4736650000 0.0083080000 109479106 0 1785556992 3.7874057293 4.0239214897 3.6274030209 596 23.8000000000 0.0132430047 0.0077848596 0.0132630160 0.0095100419 3.0013690000 1.2736620000 0.2240820000 0.0000050000 1.4916540000 0.0083180000 109480780 0 1787207680 3.7868781090 4.0235118866 3.6272492409 597 23.8400000000 0.0132457279 0.0077940068 0.0132630160 0.0095097974 4.6797470000 1.2751450000 0.2719290000 0.1473740000 1.4768550000 1.5047660000 109482454 0 1784819712 3.7870478630 4.0233373642 3.6274476051 598 23.8800000000 0.0132366903 0.0078031083 0.0132630160 0.0095068754 3.0448100000 1.2739780000 0.2716800000 0.0000040000 1.4871730000 0.0082930000 109484128 0 1786580992 3.7869303226 4.0227727890 3.6272730827 599 23.9200000000 0.0131703326 0.0078120686 0.0132630160 0.0095010233 3.1758970000 1.2723000000 0.2590820000 0.1530250000 1.4795250000 0.0083540000 109485802 0 1785430016 3.7869553566 4.0214819908 3.6273097992 600 23.9600000000 0.0132377902 0.0078211114 0.0132630160 0.0094958534 3.0787070000 1.2722690000 0.3073700000 0.0000040000 1.4871060000 0.0082760000 109487476 0 1786970112 3.7871880531 4.0205554962 3.6273238659 601 24.0000000000 0.0133288279 0.0078302757 0.0133288279 0.0094930809 4.6776430000 1.2786090000 0.2700200000 0.1478990000 1.4778920000 1.4994790000 109489150 0 1784684544 3.7869963646 4.0199122429 3.6271638870 602 24.0400000000 0.0133098569 0.0078393780 0.0133288279 0.0094930094 3.0453070000 1.2812010000 0.2611870000 0.0000040000 1.4908690000 0.0082780000 109490824 0 1786208256 3.7872109413 4.0188097954 3.6273245811 603 24.0800000000 0.0133723300 0.0078485537 0.0133723300 0.0095008858 3.1925270000 1.2751630000 0.2698520000 0.1483670000 1.4870820000 0.0082820000 109492498 0 1785430016 3.7873063087 4.0181517601 3.6275098324 604 24.1200000000 0.0132928807 0.0078575675 0.0133723300 0.0095039627 3.0494200000 1.2733010000 0.2706780000 0.0000040000 1.4933400000 0.0082360000 109494172 0 1786826752 3.7875156403 4.0175342560 3.6279199123 605 24.1600000000 0.0133183897 0.0078665936 0.0133723300 0.0095015167 4.7352600000 1.2790000000 0.3177730000 0.1485970000 1.4829590000 1.5031500000 109495846 0 1784320000 3.7871353626 4.0174674988 3.6277368069 606 24.2000000000 0.0133725591 0.0078756794 0.0133725591 0.0094951692 3.1450990000 1.2731850000 0.3693810000 0.0000040000 1.4905050000 0.0083180000 109497520 0 1786064896 3.7873702049 4.0168848038 3.6278133392 607 24.2400000000 0.0133975688 0.0078847764 0.0133975688 0.0094885490 3.1730580000 1.2735810000 0.2587860000 0.1489000000 1.4797670000 0.0083340000 109499194 0 1787756544 3.7878062725 4.0164847374 3.6280014515 608 24.2800000000 0.0134450160 0.0078939215 0.0134450160 0.0094817156 3.0552090000 1.2823780000 0.2714120000 0.0000050000 1.4893100000 0.0082330000 109500868 0 1784692736 3.7882945538 4.0160822868 3.6281046867 609 24.3200000000 0.0134973396 0.0079031225 0.0134973396 0.0094748913 4.6777300000 1.2719480000 0.2701270000 0.1491950000 1.4839580000 1.4987590000 109502542 0 1786208256 3.7875037193 4.0148258209 3.6279480457 610 24.3600000000 0.0135611780 0.0079123980 0.0135611780 0.0094746074 3.0954540000 1.2714880000 0.3179550000 0.0000040000 1.4940340000 0.0082210000 109504216 0 1785192448 3.7877399921 4.0147895813 3.6277263165 611 24.4000000000 0.0135152098 0.0079215680 0.0135611780 0.0094692280 3.2318210000 1.2753090000 0.3154310000 0.1495250000 1.4795770000 0.0082720000 109505890 0 1786826752 3.7879679203 4.0137500763 3.6279363632 612 24.4400000000 0.0135319587 0.0079307353 0.0135611780 0.0094664555 3.0534030000 1.2803950000 0.2697160000 0.0000050000 1.4912340000 0.0082180000 109507564 0 1784827904 3.7880673409 4.0135774612 3.6275565624 613 24.4800000000 0.0135748284 0.0079399426 0.0135748284 0.0094615317 4.6800020000 1.2736760000 0.2685820000 0.1497980000 1.4841840000 1.4999270000 109509238 0 1786445824 3.7890672684 4.0145916939 3.6278407574 614 24.5200000000 0.0137465000 0.0079493995 0.0137465000 0.0094539023 3.0344490000 1.2733940000 0.2586070000 0.0000040000 1.4904340000 0.0082680000 109510912 0 1785462784 3.7891209126 4.0146336555 3.6277716160 615 24.5600000000 0.0137965856 0.0079589071 0.0137965856 0.0094466874 3.2342330000 1.2806250000 0.3060470000 0.1501350000 1.4852950000 0.0082670000 109512586 0 1786970112 3.7885234356 4.0131626129 3.6275033951 616 24.6000000000 0.0137890894 0.0079683717 0.0137965856 0.0094446203 3.0954200000 1.2748840000 0.3160460000 0.0000050000 1.4924520000 0.0082860000 109514260 0 1784938496 3.7882838249 4.0113801956 3.6271700859 617 24.6400000000 0.0138387596 0.0079778861 0.0138387596 0.0094463964 4.6673330000 1.2721110000 0.2684500000 0.1501960000 1.4716140000 1.5011780000 109515934 0 1786580992 3.7887210846 4.0110960007 3.6272683144 618 24.6800000000 0.0139542352 0.0079875566 0.0139542352 0.0094467544 3.0821980000 1.2696240000 0.3164040000 0.0000040000 1.4841970000 0.0082250000 109517608 0 1785556992 3.7892811298 4.0105247498 3.6271145344 619 24.7200000000 0.0139524890 0.0079971930 0.0139542352 0.0094593550 3.1719970000 1.2803970000 0.2569980000 0.1504000000 1.4721470000 0.0082280000 109519282 0 1787207680 3.7898263931 4.0104112625 3.6268553734 620 24.7600000000 0.0140605411 0.0080069726 0.0140605411 0.0094644553 3.0469350000 1.2733940000 0.2685750000 0.0000040000 1.4927420000 0.0082020000 109520956 0 1784557568 3.7899909019 4.0111756325 3.6258628368 621 24.8000000000 0.0140860910 0.0080167618 0.0140860910 0.0094575684 4.6907950000 1.2739620000 0.3005470000 0.1506170000 1.4696020000 1.4922290000 109522630 0 1786064896 3.7906758785 4.0111131668 3.6256055832 622 24.8400000000 0.0142947119 0.0080268550 0.0142947119 0.0094499764 3.0342260000 1.2789930000 0.2671660000 0.0000040000 1.4760350000 0.0082050000 109524304 0 1787969536 3.7918395996 4.0106997490 3.6256482601 623 24.8800000000 0.0142467925 0.0080368388 0.0142947119 0.0094426042 3.2229930000 1.2727370000 0.3159330000 0.1506900000 1.4715240000 0.0082450000 109525978 0 1784684544 3.7927372456 4.0102391243 3.6257500648 624 24.9200000000 0.0142997028 0.0080468755 0.0142997028 0.0094353969 3.0331510000 1.2737650000 0.2724660000 0.0000040000 1.4746940000 0.0083910000 109527652 0 1786064896 3.7932271957 4.0094447136 3.6253197193 625 24.9600000000 0.0144061409 0.0080570503 0.0144061409 0.0094298809 4.6416760000 1.2772440000 0.2683420000 0.1508910000 1.4598080000 1.4815510000 109529326 0 1787969536 3.7946379185 4.0097479820 3.6255927086 626 25.0000000000 0.0145000694 0.0080673427 0.0145000694 0.0094225366 3.0130630000 1.2766290000 0.2579570000 0.0000040000 1.4663400000 0.0083190000 109531000 0 1784684544 3.7958829403 4.0101952553 3.6256051064 627 25.0400000000 0.0144908149 0.0080775874 0.0145000694 0.0094150564 3.1604410000 1.2747810000 0.2662540000 0.1508400000 1.4565330000 0.0082020000 109532674 0 1786200064 3.7970061302 4.0093255043 3.6255450249 628 25.0800000000 0.0145956911 0.0080879666 0.0145956911 0.0094107176 3.0591970000 1.2788810000 0.3046140000 0.0000050000 1.4635520000 0.0082660000 109534348 0 1787994112 3.7984232903 4.0098280907 3.6254777908 629 25.1200000000 0.0146072153 0.0080983311 0.0146072153 0.0094043516 4.6241860000 1.2739540000 0.2662530000 0.1509330000 1.4566560000 1.4724450000 109536022 0 1784541184 3.8001704216 4.0112738609 3.6250820160 630 25.1600000000 0.0147176543 0.0081088379 0.0147176543 0.0094011376 3.0581040000 1.2779180000 0.3082290000 0.0000040000 1.4598740000 0.0082180000 109537696 0 1786191872 3.8012833595 4.0109896660 3.6252889633 631 25.2000000000 0.0147759635 0.0081194039 0.0147759635 0.0093949719 3.1514250000 1.2735490000 0.2690650000 0.1509560000 1.4457010000 0.0082900000 109539370 0 1788096512 3.8030741215 4.0103902817 3.6256673336 632 25.2400000000 0.0147812506 0.0081299448 0.0147812506 0.0093875381 3.0077300000 1.2751080000 0.2682340000 0.0000050000 1.4522150000 0.0083020000 109541044 0 1784303616 3.8046171665 4.0104136467 3.6256029606 633 25.2800000000 0.0148455380 0.0081405539 0.0148455380 0.0093801330 4.6305860000 1.2772730000 0.2661070000 0.1513710000 1.4584230000 1.4735060000 109542718 0 1785810944 3.8062112331 4.0115818977 3.6256759167 634 25.3200000000 0.0149478503 0.0081512910 0.0149478503 0.0093745703 3.0077840000 1.2759130000 0.2677430000 0.0000050000 1.4519990000 0.0082730000 109544392 0 1787715584 3.8081505299 4.0115356445 3.6262946129 635 25.3600000000 0.0149910627 0.0081620623 0.0149910627 0.0093693164 3.1453380000 1.2794970000 0.2684420000 0.1507870000 1.4343610000 0.0083170000 109546066 0 1784287232 3.8102118969 4.0112290382 3.6270678043 636 25.4000000000 0.0151000330 0.0081729711 0.0151000330 0.0093628909 2.9885360000 1.2738470000 0.2574240000 0.0000040000 1.4449940000 0.0082950000 109547740 0 1785810944 3.8119797707 4.0114941597 3.6268174648 637 25.4400000000 0.0151515296 0.0081839264 0.0151515296 0.0093571479 4.6216350000 1.2750510000 0.3130070000 0.1507170000 1.4258430000 1.4531070000 109549414 0 1787613184 3.8142039776 4.0117859840 3.6272273064 638 25.4800000000 0.0152055994 0.0081949322 0.0152055994 0.0093533315 2.9872570000 1.2761070000 0.2677610000 0.0000050000 1.4312170000 0.0082100000 109551088 0 1784311808 3.8159091473 4.0107817650 3.6277577877 639 25.5200000000 0.0151528399 0.0082058209 0.0152055994 0.0093460448 3.1591020000 1.3036950000 0.2660190000 0.1565420000 1.4205960000 0.0082160000 109552762 0 1785810944 3.8182034492 4.0108218193 3.6278538704 640 25.5600000000 0.0152848633 0.0082168819 0.0152848633 0.0093390730 3.0151130000 1.2751660000 0.3038360000 0.0000040000 1.4238530000 0.0083070000 109554436 0 1787588608 3.8206400871 4.0113472939 3.6284215450 641 25.6000000000 0.0153263863 0.0082279732 0.0153263863 0.0093323234 4.5388890000 1.2782960000 0.2580500000 0.1505850000 1.4131450000 1.4348830000 109556110 0 1784287232 3.8234679699 4.0118565559 3.6290955544 642 25.6400000000 0.0154221021 0.0082391790 0.0154221021 0.0093270439 3.0706240000 1.2804910000 0.3615440000 0.0000040000 1.4164760000 0.0082150000 109557784 0 1785683968 3.8255414963 4.0114064217 3.6292471886 643 25.6800000000 0.0153992707 0.0082503144 0.0154221021 0.0093197843 3.1767390000 1.2790940000 0.3222670000 0.1509210000 1.4123440000 0.0082040000 109559458 0 1787715584 3.8280611038 4.0120601654 3.6294648647 644 25.7200000000 0.0155008854 0.0082615731 0.0155008854 0.0093133332 3.0028090000 1.2731250000 0.3090800000 0.0000040000 1.4082960000 0.0083300000 109561132 0 1784303616 3.8306152821 4.0119256973 3.6302807331 645 25.7600000000 0.0154651953 0.0082727415 0.0155008854 0.0093062093 4.5804380000 1.2695490000 0.3296580000 0.1562860000 1.4003260000 1.4205960000 109562806 0 1785810944 3.8331892490 4.0112161636 3.6310081482 646 25.8000000000 0.0154980049 0.0082839261 0.0155008854 0.0093009228 2.9592280000 1.2741460000 0.2636210000 0.0000040000 1.4092200000 0.0083320000 109564480 0 1787715584 3.8356578350 4.0117259026 3.6313440800 647 25.8400000000 0.0154484455 0.0082949996 0.0155008854 0.0092937313 3.1131100000 1.2733930000 0.2827390000 0.1499850000 1.3948470000 0.0082010000 109566154 0 1784311808 3.8383941650 4.0121202469 3.6323075294 648 25.8800000000 0.0155035537 0.0083061239 0.0155035537 0.0092875303 3.0045280000 1.2792660000 0.3123010000 0.0000050000 1.4006760000 0.0082840000 109567828 0 1785819136 3.8405654430 4.0115513802 3.6331112385 649 25.9200000000 0.0155383125 0.0083172675 0.0155383125 0.0092803716 4.5183200000 1.2751090000 0.2790190000 0.1498870000 1.3965790000 1.4137460000 109569502 0 1787715584 3.8431172371 4.0111856461 3.6334562302 650 25.9600000000 0.0154780410 0.0083282840 0.0155383125 0.0092737127 2.9554850000 1.2754460000 0.2748510000 0.0000040000 1.3929710000 0.0082560000 109571176 0 1784287232 3.8458178043 4.0116004944 3.6342134476 651 26.0000000000 0.0154843340 0.0083392764 0.0155383125 0.0092665921 3.0926050000 1.2776030000 0.2663210000 0.1497440000 1.3866040000 0.0083440000 109572850 0 1785937920 3.8482949734 4.0121450424 3.6346540451 652 26.0400000000 0.0156214638 0.0083504454 0.0156214638 0.0092596495 2.9553830000 1.2700090000 0.2765300000 0.0000050000 1.3966660000 0.0082070000 109574524 0 1787842560 3.8506538868 4.0123972893 3.6345870495 653 26.0800000000 0.0156290438 0.0083615918 0.0156290438 0.0092526787 4.5420780000 1.2732050000 0.3177200000 0.1494480000 1.3851450000 1.4125140000 109576198 0 1784303616 3.8528909683 4.0122003555 3.6347455978 654 26.1200000000 0.0156465024 0.0083727308 0.0156465024 0.0092461156 2.9406730000 1.2723020000 0.2719270000 0.0000040000 1.3841350000 0.0082980000 109577872 0 1785937920 3.8586080074 4.0130062103 3.6367549896 655 26.1600000000 0.0156842452 0.0083838934 0.0156842452 0.0092391436 3.1879070000 1.2716680000 0.3655140000 0.1493490000 1.3890940000 0.0082700000 109579546 0 1787731968 3.8608489037 4.0124034882 3.6371378899 656 26.2000000000 0.0156327300 0.0083949435 0.0156842452 0.0092324675 2.9776830000 1.2715490000 0.3097840000 0.0000050000 1.3840260000 0.0082860000 109581220 0 1784287232 3.8637771606 4.0128078461 3.6381790638 657 26.2400000000 0.0156996138 0.0084060617 0.0156996138 0.0092254665 4.4489370000 1.2808270000 0.2286840000 0.1491240000 1.3819540000 1.4043130000 109582894 0 1785937920 3.8664379120 4.0127873421 3.6393313408 658 26.2800000000 0.0157460757 0.0084172168 0.0157460757 0.0092185667 2.8996730000 1.2816710000 0.2217820000 0.0000040000 1.3839360000 0.0082650000 109584568 0 1787723776 3.8690001965 4.0126228333 3.6399438381 659 26.3200000000 0.0157612730 0.0084283610 0.0157612730 0.0092125688 3.0807770000 1.2716070000 0.2682630000 0.1489500000 1.3796330000 0.0082490000 109586242 0 1784295424 3.8715591431 4.0131225586 3.6400732994 660 26.3600000000 0.0158191323 0.0084395591 0.0158191323 0.0092055802 2.9085650000 1.2830140000 0.2328000000 0.0000040000 1.3804210000 0.0082820000 109587916 0 1785810944 3.8741521835 4.0127043724 3.6409304142 661 26.4000000000 0.0158471297 0.0084507658 0.0158471297 0.0091991044 4.5200680000 1.2720560000 0.3118390000 0.1487440000 1.3839930000 1.3993010000 109589590 0 1787731968 3.8771221638 4.0124440193 3.6422488689 662 26.4400000000 0.0158824287 0.0084619918 0.0158824287 0.0091935505 3.0707370000 1.2738180000 0.3996760000 0.0000050000 1.3849570000 0.0082550000 109591264 0 1784684544 3.8798043728 4.0126299858 3.6429009438 663 26.4800000000 0.0157933328 0.0084730497 0.0158824287 0.0091866320 3.1816690000 1.2718980000 0.3693340000 0.1486280000 1.3794910000 0.0081980000 109592938 0 1786191872 3.8822748661 4.0119328499 3.6434316635 664 26.5200000000 0.0159316901 0.0084842826 0.0159316901 0.0091800505 2.9468440000 1.2748730000 0.2803690000 0.0000040000 1.3792120000 0.0082150000 109594612 0 1787969536 3.8846852779 4.0109171867 3.6442587376 665 26.5600000000 0.0159760267 0.0084955483 0.0159760267 0.0091753360 4.5166950000 1.2720420000 0.3063920000 0.1491470000 1.3788410000 1.4061720000 109596286 0 1784320000 3.8867490292 4.0093321800 3.6444184780 666 26.6000000000 0.0160043482 0.0085068228 0.0160043482 0.0091753951 2.9373880000 1.2737720000 0.2677180000 0.0000050000 1.3835280000 0.0082150000 109597960 0 1785810944 3.8892731667 4.0087757111 3.6448752880 667 26.6400000000 0.0159798283 0.0085180267 0.0160043482 0.0091737450 3.0761030000 1.2768000000 0.2570910000 0.1492070000 1.3806580000 0.0082710000 109599634 0 1787715584 3.8916585445 4.0080361366 3.6450057030 668 26.6800000000 0.0160859432 0.0085293559 0.0160859432 0.0091695941 2.9759530000 1.2727710000 0.3045570000 0.0000040000 1.3861130000 0.0082510000 109601308 0 1784438784 3.8940753937 4.0074801445 3.6455252171 669 26.7200000000 0.0161180515 0.0085406993 0.0161180515 0.0091646897 4.4895370000 1.2780800000 0.2687970000 0.1484540000 1.3836120000 1.4064520000 109602982 0 1785937920 3.8963260651 4.0063815117 3.6454906464 670 26.7600000000 0.0162111614 0.0085521477 0.0162111614 0.0091641300 2.9419740000 1.2774360000 0.2593700000 0.0000040000 1.3927390000 0.0082060000 109604656 0 1787715584 3.8986890316 4.0060877800 3.6453061104 671 26.8000000000 0.0162706226 0.0085636507 0.0162706226 0.0091608129 3.0901930000 1.2710870000 0.2605690000 0.1483850000 1.3977750000 0.0082630000 109606330 0 1784430592 3.9012732506 4.0064601898 3.6448960304 672 26.8400000000 0.0162417665 0.0085750764 0.0162706226 0.0091542608 2.9792630000 1.2719540000 0.3054420000 0.0000040000 1.3894380000 0.0082440000 109608004 0 1785937920 3.9035146236 4.0050687790 3.6447033882 673 26.8800000000 0.0162484441 0.0085864782 0.0162706226 0.0091560966 4.4956990000 1.2715110000 0.2610460000 0.1484250000 1.3932010000 1.4172090000 109609678 0 1787715584 3.9060196877 4.0042939186 3.6445624828 674 26.9200000000 0.0163514595 0.0085979989 0.0163514595 0.0091636813 3.0007220000 1.2699700000 0.3169500000 0.0000040000 1.4013860000 0.0082800000 109611352 0 1784414208 3.9087543488 4.0051336288 3.6441655159 675 26.9600000000 0.0164111238 0.0086095739 0.0164111238 0.0091592830 3.0374830000 1.2744120000 0.2141350000 0.1480220000 1.3885580000 0.0082290000 109613026 0 1785937920 3.9112884998 4.0051579475 3.6431341171 676 27.0000000000 0.0164075624 0.0086211094 0.0164111238 0.0091529646 2.9373310000 1.2818010000 0.2504620000 0.0000040000 1.3925250000 0.0083490000 109614700 0 1787715584 3.9137952328 4.0037961006 3.6431057453 677 27.0400000000 0.0164374970 0.0086326550 0.0164374970 0.0091498143 4.5076870000 1.2791670000 0.2724300000 0.1478660000 1.3934440000 1.4106700000 109616374 0 1784430592 3.9164795876 4.0037641525 3.6420054436 678 27.0800000000 0.0165357254 0.0086443115 0.0165357254 0.0091452824 2.8921940000 1.2745440000 0.2123600000 0.0000040000 1.3928540000 0.0082710000 109618048 0 1786073088 3.9191813469 4.0035395622 3.6413733959 679 27.1200000000 0.0164894350 0.0086558654 0.0165357254 0.0091423220 3.0562970000 1.2831050000 0.2260650000 0.1476190000 1.3871120000 0.0082560000 109619722 0 1787723776 3.9214909077 4.0029973984 3.6402082443 680 27.1600000000 0.0165970791 0.0086675437 0.0165970791 0.0091411918 2.9569060000 1.2710440000 0.2752310000 0.0000040000 1.3981920000 0.0082010000 109621396 0 1784430592 3.9242575169 4.0035367012 3.6388697624 681 27.2000000000 0.0165501665 0.0086791187 0.0165970791 0.0091348471 4.4739190000 1.2735590000 0.2615780000 0.1477420000 1.3830260000 1.4038210000 109623070 0 1785937920 3.9268956184 4.0033516884 3.6377620697 682 27.2400000000 0.0165785421 0.0086907015 0.0165970791 0.0091287883 2.9365980000 1.2796190000 0.2589380000 0.0000040000 1.3854920000 0.0082410000 109624744 0 1787715584 3.9294507504 4.0030636787 3.6361362934 683 27.2800000000 0.0167039111 0.0087024338 0.0167039111 0.0091237631 3.0776670000 1.2747360000 0.2628470000 0.1470820000 1.3804250000 0.0082150000 109626418 0 1784303616 3.9323120117 4.0032057762 3.6348958015 684 27.3200000000 0.0167119596 0.0087141437 0.0167119596 0.0091172422 2.9366500000 1.2723540000 0.2756460000 0.0000040000 1.3761900000 0.0082700000 109628092 0 1785810944 3.9351248741 4.0030589104 3.6331889629 685 27.3600000000 0.0167722721 0.0087259074 0.0167722721 0.0091106471 4.5061550000 1.2793520000 0.3130700000 0.1473690000 1.3703910000 1.3917450000 109629766 0 1787715584 3.9377455711 4.0012521744 3.6320576668 686 27.4000000000 0.0167540535 0.0087376102 0.0167722721 0.0091096725 2.9331530000 1.2734830000 0.2730430000 0.0000050000 1.3740600000 0.0082660000 109631440 0 1784430592 3.9404811859 4.0003414154 3.6305553913 687 27.4400000000 0.0168057624 0.0087493542 0.0168057624 0.0091115784 3.0716320000 1.2709080000 0.2687520000 0.1466970000 1.3727470000 0.0082930000 109633114 0 1785937920 3.9435088634 4.0005302429 3.6285634041 688 27.4800000000 0.0167754851 0.0087610201 0.0168057624 0.0091120804 2.8785130000 1.2773240000 0.2140730000 0.0000040000 1.3746680000 0.0082060000 109634788 0 1787715584 3.9465634823 4.0004630089 3.6266398430 689 27.5200000000 0.0167975463 0.0087726842 0.0168057624 0.0091127141 4.4166530000 1.2731180000 0.2250930000 0.1463120000 1.3760350000 1.3917580000 109636462 0 1784438784 3.9493241310 4.0001053810 3.6245129108 690 27.5600000000 0.0168661047 0.0087844138 0.0168661047 0.0091169209 2.9666130000 1.2694500000 0.3094550000 0.0000040000 1.3752090000 0.0082690000 109638136 0 1785946112 3.9526352882 4.0009837151 3.6222720146 691 27.6000000000 0.0168557838 0.0087960945 0.0168661047 0.0091104383 3.0788090000 1.2786730000 0.2753480000 0.1460750000 1.3661850000 0.0083120000 109639810 0 1787715584 3.9559228420 4.0019307137 3.6198420525 692 27.6400000000 0.0169134736 0.0088078248 0.0169134736 0.0091071765 2.9693890000 1.2764510000 0.3090370000 0.0000040000 1.3713030000 0.0082450000 109641484 0 1784303616 3.9589908123 4.0021047592 3.6173295975 693 27.6800000000 0.0168878883 0.0088194843 0.0169134736 0.0091036251 4.4344960000 1.2722100000 0.2654310000 0.1457900000 1.3605360000 1.3862010000 109643158 0 1785810944 3.9619572163 4.0012922287 3.6155045033 694 27.7200000000 0.0169235524 0.0088311617 0.0169235524 0.0090970562 2.9129100000 1.2732000000 0.2661030000 0.0000040000 1.3611500000 0.0082050000 109644832 0 1787715584 3.9649474621 4.0010361671 3.6132044792 695 27.7600000000 0.0169525184 0.0088428471 0.0169525184 0.0090907187 3.1105580000 1.2731940000 0.3110030000 0.1454560000 1.3683100000 0.0082070000 109646506 0 1784700928 3.9679622650 4.0005440712 3.6113028526 696 27.8000000000 0.0168869793 0.0088544047 0.0169525184 0.0090862270 2.9061500000 1.2691060000 0.2604530000 0.0000040000 1.3640600000 0.0082410000 109648180 0 1786318848 3.9708008766 4.0000953674 3.6096372604 697 27.8400000000 0.0168208778 0.0088658344 0.0169525184 0.0090835199 4.3978260000 1.2777420000 0.2246510000 0.1452280000 1.3621930000 1.3826940000 109649854 0 1785208832 3.9765551090 4.0009737015 3.6048159599 698 27.8800000000 0.0169197731 0.0088773730 0.0169525184 0.0090770110 2.9730650000 1.2733840000 0.3253340000 0.0000040000 1.3617210000 0.0082120000 109651528 0 1784573952 3.9790716171 3.9999654293 3.6032330990 699 27.9200000000 0.0168655571 0.0088888010 0.0169525184 0.0090943270 3.0416700000 1.2723070000 0.2490690000 0.1449420000 1.3626220000 0.0082170000 109653202 0 1786343424 3.9836413860 3.9996545315 3.5991930962 700 27.9600000000 0.0168008246 0.0089001039 0.0169525184 0.0090889005 2.9153160000 1.2873220000 0.2276240000 0.0000040000 1.3877380000 0.0082010000 109654876 0 1785454592 3.9857220650 3.9989330769 3.5971384048 701 28.0000000000 0.0168269910 0.0089114119 0.0169525184 0.0090856173 4.4448790000 1.2777660000 0.2616570000 0.1447870000 1.3734870000 1.3827680000 109656550 0 1786978304 3.9878897667 3.9979372025 3.5958795547 702 28.0400000000 0.0168130193 0.0089226677 0.0169525184 0.0090907560 2.9196930000 1.2780310000 0.2588390000 0.0000040000 1.3702100000 0.0083010000 109658224 0 1784811520 3.9898278713 3.9970083237 3.5943148136 703 28.0800000000 0.0166553557 0.0089336673 0.0169525184 0.0091092484 3.0529910000 1.2718830000 0.2589900000 0.1447130000 1.3646560000 0.0082030000 109659898 0 1786335232 3.9919874668 3.9971122742 3.5923318863 704 28.1200000000 0.0166376606 0.0089446104 0.0169525184 0.0091153796 2.8820310000 1.2733370000 0.2164040000 0.0000040000 1.3797180000 0.0082410000 109661572 0 1785573376 3.9943811893 3.9971914291 3.5908141136 705 28.1600000000 0.0166801531 0.0089555828 0.0169525184 0.0091155963 4.4025970000 1.2725140000 0.2164920000 0.1446670000 1.3707100000 1.3938420000 109663246 0 1786970112 3.9963200092 3.9963548183 3.5894527435 706 28.2000000000 0.0166289229 0.0089664516 0.0169525184 0.0091212696 2.9234680000 1.2704640000 0.2635330000 0.0000050000 1.3767480000 0.0082390000 109664920 0 1784922112 3.9984469414 3.9958581924 3.5881133080 707 28.2400000000 0.0166520812 0.0089773224 0.0169525184 0.0091260300 3.1123510000 1.2728370000 0.3072070000 0.1499080000 1.3696920000 0.0082810000 109666594 0 1786462208 4.0008363724 3.9966969490 3.5864894390 708 28.2800000000 0.0166481491 0.0089881569 0.0169525184 0.0091197431 2.8750960000 1.2725940000 0.2200450000 0.0000040000 1.3698220000 0.0082610000 109668268 0 1785446400 4.0033588409 3.9969108105 3.5849404335 709 28.3200000000 0.0166623462 0.0089989808 0.0169525184 0.0091134272 4.4669080000 1.2905000000 0.2705590000 0.1442830000 1.3682770000 1.3889700000 109669942 0 1787097088 4.0055232048 3.9958870411 3.5841574669 710 28.3600000000 0.0166536886 0.0090097621 0.0169525184 0.0091111509 2.9293790000 1.2810530000 0.2629790000 0.0000040000 1.3726260000 0.0082610000 109671616 0 1784819712 4.0079383850 3.9954793453 3.5834825039 711 28.4000000000 0.0167281441 0.0090206178 0.0169525184 0.0091092485 3.0506080000 1.2725350000 0.2524300000 0.1442470000 1.3686770000 0.0083080000 109673290 0 1786335232 4.0105266571 3.9961969852 3.5821473598 712 28.4400000000 0.0166906603 0.0090313903 0.0169525184 0.0091028527 2.9166730000 1.2791320000 0.2542010000 0.0000040000 1.3706280000 0.0082690000 109674964 0 1785573376 4.0129060745 3.9953005314 3.5818336010 713 28.4800000000 0.0166504178 0.0090420762 0.0169525184 0.0090974183 4.4590780000 1.2732330000 0.2602140000 0.1440850000 1.3766150000 1.4005480000 109676638 0 1787097088 4.0152301788 3.9944312572 3.5814960003 714 28.5200000000 0.0165796522 0.0090526330 0.0169525184 0.0090956724 2.8989180000 1.2765370000 0.2237960000 0.0000050000 1.3858830000 0.0082940000 109678312 0 1784573952 4.0178370476 3.9948132038 3.5806996822 715 28.5600000000 0.0165906083 0.0090631756 0.0169525184 0.0090902268 3.0636090000 1.2712720000 0.2598500000 0.1448360000 1.3749630000 0.0082690000 109679986 0 1786064896 4.0208625793 3.9958240986 3.5801193714 716 28.6000000000 0.0165613350 0.0090736479 0.0169525184 0.0090853238 2.9285760000 1.2728350000 0.2620070000 0.0000040000 1.3809570000 0.0083120000 109681660 0 1787858944 4.0237526894 3.9962232113 3.5799214840 717 28.6400000000 0.0165642835 0.0090840951 0.0169525184 0.0090821311 4.4047860000 1.2728040000 0.2132200000 0.1435800000 1.3731890000 1.3975180000 109683334 0 1784938496 4.0265903473 3.9959266186 3.5797865391 718 28.6800000000 0.0165844392 0.0090945413 0.0169525184 0.0090761283 2.8740550000 1.2729630000 0.2132510000 0.0000050000 1.3751340000 0.0082760000 109685008 0 1786335232 4.0293407440 3.9958071709 3.5798444748 719 28.7200000000 0.0165322572 0.0091048858 0.0169525184 0.0090698381 3.0628020000 1.2722470000 0.2507510000 0.1492380000 1.3778850000 0.0082670000 109686682 0 1785683968 4.0322351456 3.9953832626 3.5802636147 720 28.7600000000 0.0164589714 0.0091150998 0.0169525184 0.0090662544 2.8791640000 1.2713450000 0.2133620000 0.0000040000 1.3817530000 0.0082080000 109688356 0 1787342848 4.0354399681 3.9950375557 3.5809926987 721 28.8000000000 0.0164290946 0.0091252440 0.0169525184 0.0090678187 4.4709320000 1.2798710000 0.2606660000 0.1434980000 1.3813350000 1.4009320000 109690030 0 1784201216 4.0387568474 3.9962708950 3.5809884071 722 28.8400000000 0.0164221786 0.0091353506 0.0169525184 0.0090616239 2.9374750000 1.2798640000 0.2607490000 0.0000040000 1.3841250000 0.0082830000 109691704 0 1785810944 4.0423212051 3.9966251850 3.5816786289 723 28.8800000000 0.0163727924 0.0091453609 0.0169525184 0.0090556848 3.0250080000 1.2729610000 0.2142380000 0.1431030000 1.3818830000 0.0082750000 109693378 0 1787715584 4.0457139015 3.9967446327 3.5823805332 724 28.9200000000 0.0164000802 0.0091553812 0.0169525184 0.0090495233 2.9410170000 1.2795830000 0.2621050000 0.0000030000 1.3866010000 0.0083010000 109695052 0 1784287232 4.0491604805 3.9969425201 3.5832750797 725 28.9600000000 0.0163263194 0.0091652722 0.0169525184 0.0090433788 4.4663120000 1.2730460000 0.2508070000 0.1426080000 1.3911870000 1.4040810000 109696726 0 1785683968 4.0528326035 3.9968583584 3.5844469070 726 29.0000000000 0.0162542444 0.0091750366 0.0169525184 0.0090383774 2.9307450000 1.2730160000 0.2513420000 0.0000050000 1.3936980000 0.0082630000 109698400 0 1787715584 4.0560517311 3.9966886044 3.5852277279 727 29.0400000000 0.0162787866 0.0091848079 0.0169525184 0.0090389100 3.0407270000 1.2727270000 0.2236060000 0.1426020000 1.3889820000 0.0082540000 109700074 0 1784700928 4.0600438118 3.9976820946 3.5864264965 728 29.0800000000 0.0162515752 0.0091945150 0.0169525184 0.0090332563 2.9075080000 1.2729980000 0.2232290000 0.0000040000 1.3984660000 0.0082870000 109701748 0 1786318848 4.0638985634 3.9983854294 3.5875058174 729 29.1200000000 0.0162000041 0.0092041247 0.0169525184 0.0090271399 4.4894690000 1.2723000000 0.2608390000 0.1423030000 1.3926240000 1.4167740000 109703422 0 1785683968 4.0673890114 3.9977054596 3.5889689922 730 29.1600000000 0.0161524881 0.0092136430 0.0169525184 0.0090302805 2.8984950000 1.2730630000 0.2144110000 0.0000040000 1.3981790000 0.0082170000 109705096 0 1787097088 4.0707058907 3.9975593090 3.5901570320 731 29.2000000000 0.0162393823 0.0092232542 0.0169525184 0.0090347910 3.0433280000 1.2718280000 0.2183480000 0.1424540000 1.3978180000 0.0082680000 109706770 0 1784692736 4.0746555328 3.9981985092 3.5916919708 732 29.2400000000 0.0162447244 0.0092328463 0.0169525184 0.0090326003 2.9045400000 1.2730210000 0.2139270000 0.0000040000 1.4048090000 0.0082950000 109708444 0 1786343424 4.0782046318 3.9984400272 3.5929658413 733 29.2800000000 0.0162132196 0.0092423694 0.0169525184 0.0090296558 4.4621410000 1.2790220000 0.2129820000 0.1423020000 1.4023140000 1.4209690000 109710118 0 1787985920 4.0816326141 3.9987819195 3.5937821865 734 29.3200000000 0.0161062814 0.0092517207 0.0169525184 0.0090248628 2.9659180000 1.2851000000 0.2597210000 0.0000040000 1.4083180000 0.0082840000 109711792 0 1785319424 4.0851678848 3.9988996983 3.5950195789 735 29.3600000000 0.0161697417 0.0092611330 0.0169525184 0.0090188852 3.1018920000 1.2746930000 0.2592460000 0.1418110000 1.4133230000 0.0081980000 109713466 0 1786716160 4.0883336067 3.9988193512 3.5961210728 736 29.4000000000 0.0160879027 0.0092704085 0.0169525184 0.0090128575 2.9509530000 1.2747860000 0.2466170000 0.0000030000 1.4166530000 0.0082770000 109715140 0 1784811520 4.0913357735 3.9983344078 3.5974121094 737 29.4400000000 0.0161377639 0.0092797265 0.0169525184 0.0090085570 4.5830670000 1.2764560000 0.3063510000 0.1416670000 1.4216630000 1.4323110000 109716814 0 1786335232 4.0942521095 3.9983363152 3.5983965397 738 29.4800000000 0.0160925202 0.0092889579 0.0169525184 0.0090040907 2.9258950000 1.2722980000 0.2126870000 0.0000040000 1.4280100000 0.0083510000 109718488 0 1785683968 4.0973200798 3.9986135960 3.5994908810 739 29.5200000000 0.0160643235 0.0092981262 0.0169525184 0.0089981371 3.0608130000 1.2752240000 0.2120460000 0.1412630000 1.4194130000 0.0082660000 109720162 0 1787113472 4.0999770164 3.9980149269 3.6006791592 740 29.5600000000 0.0159841161 0.0093071613 0.0169525184 0.0089955609 2.9299320000 1.2715940000 0.2191500000 0.0000040000 1.4262900000 0.0082890000 109721836 0 1784573952 4.1023349762 3.9970960617 3.6018648148 741 29.6000000000 0.0159557890 0.0093161339 0.0169525184 0.0090030796 4.5517450000 1.2725860000 0.2593200000 0.1410930000 1.4249110000 1.4491730000 109723510 0 1786232832 4.1045665741 3.9969201088 3.6028177738 742 29.6400000000 0.0159364808 0.0093250562 0.0169525184 0.0090053622 2.9993970000 1.2737350000 0.2701930000 0.0000030000 1.4425470000 0.0082660000 109725184 0 1787994112 4.1073122025 3.9972023964 3.6038107872 743 29.6800000000 0.0158730336 0.0093338690 0.0169525184 0.0090022708 3.0781230000 1.2798730000 0.2139440000 0.1409150000 1.4304910000 0.0082560000 109726858 0 1784938496 4.1096286774 3.9972896576 3.6045985222 744 29.7200000000 0.0159002803 0.0093426949 0.0169525184 0.0089972092 2.9925410000 1.2753300000 0.2615730000 0.0000040000 1.4428200000 0.0082740000 109728532 0 1786318848 4.1118025780 3.9971051216 3.6054670811 745 29.7600000000 0.0159188714 0.0093515219 0.0169525184 0.0089934840 4.5213190000 1.2720290000 0.2129960000 0.1409510000 1.4344940000 1.4562290000 109730206 0 1785430016 4.1141386032 3.9978921413 3.6061053276 746 29.8000000000 0.0159362052 0.0093603486 0.0169525184 0.0089894700 2.9942050000 1.2797050000 0.2653570000 0.0000040000 1.4361710000 0.0082620000 109731880 0 1786826752 4.1161279678 3.9985237122 3.6063911915 747 29.8400000000 0.0159273893 0.0093691398 0.0169525184 0.0089899079 3.0730570000 1.2728660000 0.2051520000 0.1406800000 1.4415300000 0.0082060000 109733554 0 1784684544 4.1177592278 3.9974505901 3.6073453426 748 29.8800000000 0.0158377308 0.0093777877 0.0169525184 0.0089975898 3.0022890000 1.2760110000 0.2711160000 0.0000050000 1.4422770000 0.0082620000 109735228 0 1786183680 4.1216778755 3.9975802898 3.6091740131 749 29.9200000000 0.0159083474 0.0093865067 0.0169525184 0.0089916120 4.5904270000 1.2809350000 0.2661300000 0.1416130000 1.4395150000 1.4576040000 109736902 0 1788096512 4.1238384247 3.9980788231 3.6099104881 750 29.9600000000 0.0158949718 0.0093951847 0.0169525184 0.0089860151 2.9998070000 1.2739850000 0.2730250000 0.0000050000 1.4397820000 0.0082610000 109738576 0 1784557568 4.1254425049 3.9980740547 3.6104831696 751 30.0000000000 0.0158727542 0.0094038099 0.0169525184 0.0089800499 3.1379690000 1.2735310000 0.2701590000 0.1405480000 1.4408090000 0.0082690000 109740250 0 1786327040 4.1273980141 3.9986202717 3.6110153198 752 30.0400000000 0.0159192625 0.0094124741 0.0169525184 0.0089765500 2.9453040000 1.2774710000 0.2143780000 0.0000050000 1.4405660000 0.0082770000 109741924 0 1788121088 4.1294126511 3.9991636276 3.6115210056 753 30.0800000000 0.0158385821 0.0094210081 0.0169525184 0.0089738765 4.5424550000 1.2743750000 0.2138400000 0.1402470000 1.4487400000 1.4605800000 109743598 0 1784303616 4.1311964989 3.9986841679 3.6121730804 754 30.1200000000 0.0158790275 0.0094295731 0.0169525184 0.0089679991 3.0017460000 1.2724230000 0.2626890000 0.0000050000 1.4537580000 0.0082480000 109745272 0 1785810944 4.1332206726 3.9990191460 3.6126222610 755 30.1600000000 0.0158369727 0.0094380597 0.0169525184 0.0089628156 3.0899950000 1.2750060000 0.2140050000 0.1402550000 1.4477030000 0.0082590000 109746946 0 1787715584 4.1350059509 3.9989240170 3.6131410599 756 30.2000000000 0.0158695616 0.0094465670 0.0169525184 0.0089570445 3.0044450000 1.2740520000 0.2607330000 0.0000050000 1.4566480000 0.0082050000 109748620 0 1784303616 4.1365532875 3.9980211258 3.6139316559 757 30.2400000000 0.0157703720 0.0094549208 0.0169525184 0.0089574929 4.6073810000 1.2723800000 0.2591110000 0.1402420000 1.4537520000 1.4772050000 109750294 0 1785810944 4.1383605003 3.9971008301 3.6147511005 758 30.2800000000 0.0158035569 0.0094632963 0.0169525184 0.0089752419 3.0201940000 1.2734650000 0.2709330000 0.0000050000 1.4629190000 0.0081960000 109751968 0 1787715584 4.1402649879 3.9973201752 3.6149482727 759 30.3200000000 0.0157563984 0.0094715876 0.0169525184 0.0089877921 3.1504640000 1.2795070000 0.2578920000 0.1411350000 1.4588820000 0.0083120000 109753642 0 1784303616 4.1426987648 3.9976329803 3.6153507233 760 30.3600000000 0.0157348774 0.0094798288 0.0169525184 0.0089914578 2.9841740000 1.2735450000 0.2239170000 0.0000050000 1.4737790000 0.0082440000 109755316 0 1785810944 4.1447858810 3.9973247051 3.6159400940 761 30.4000000000 0.0156908594 0.0094879904 0.0169525184 0.0090003641 4.6696440000 1.2741390000 0.3067790000 0.1401580000 1.4629050000 1.4808960000 109756990 0 1787740160 4.1467738152 3.9969439507 3.6161754131 762 30.4400000000 0.0156970527 0.0094961388 0.0169525184 0.0090161027 2.9803010000 1.2800920000 0.2137540000 0.0000060000 1.4735240000 0.0082350000 109758664 0 1784311808 4.1492171288 3.9970443249 3.6168403625 763 30.4800000000 0.0156589970 0.0095042160 0.0169525184 0.0090264558 3.1215320000 1.2714830000 0.2243100000 0.1397860000 1.4729080000 0.0083090000 109760338 0 1785810944 4.1518173218 3.9972372055 3.6170785427 764 30.5200000000 0.0156460870 0.0095122550 0.0169525184 0.0090344625 3.0227620000 1.2722850000 0.2608470000 0.0000050000 1.4765910000 0.0081860000 109762012 0 1787715584 4.1542878151 3.9968855381 3.6175262928 765 30.5600000000 0.0156319458 0.0095202546 0.0169525184 0.0090517646 4.6316440000 1.2797860000 0.2489900000 0.1404010000 1.4699780000 1.4876630000 109763686 0 1784287232 4.1566171646 3.9967253208 3.6178712845 766 30.6000000000 0.0155944675 0.0095281844 0.0169525184 0.0090669197 2.9873370000 1.2741290000 0.2181930000 0.0000060000 1.4819490000 0.0082810000 109765360 0 1785810944 4.1591095924 3.9974002838 3.6178109646 767 30.6400000000 0.0155636501 0.0095360534 0.0169525184 0.0090673246 3.1714590000 1.2754220000 0.2706310000 0.1393630000 1.4729960000 0.0081950000 109767034 0 1787604992 4.1617054939 3.9978501797 3.6177270412 768 30.6800000000 0.0156639926 0.0095440324 0.0169525184 0.0090654690 3.0433780000 1.2791840000 0.2719640000 0.0000050000 1.4791540000 0.0081960000 109768708 0 1784176640 4.1637821198 3.9976751804 3.6177489758 769 30.7200000000 0.0156784039 0.0095520095 0.0169525184 0.0090673596 4.6542430000 1.2744260000 0.2617270000 0.1392330000 1.4808510000 1.4931610000 109770382 0 1785810944 4.1661052704 3.9982042313 3.6175944805 770 30.7600000000 0.0156263504 0.0095598983 0.0169525184 0.0090633491 3.0430830000 1.2769030000 0.2641030000 0.0000050000 1.4890120000 0.0082830000 109772056 0 1787715584 4.1683220863 3.9986753464 3.6173524857 771 30.8000000000 0.0154933929 0.0095675941 0.0169525184 0.0090576262 3.1727580000 1.2734880000 0.2703070000 0.1390310000 1.4768040000 0.0082140000 109773730 0 1784176640 4.1701540947 3.9978160858 3.6172480583 772 30.8400000000 0.0154403262 0.0095752013 0.0169525184 0.0090610556 3.0537800000 1.2757190000 0.2831040000 0.0000050000 1.4819280000 0.0082520000 109775404 0 1785946112 4.1717462540 3.9976785183 3.6169416904 773 30.8800000000 0.0154510513 0.0095828026 0.0169525184 0.0090610770 4.6576280000 1.2710930000 0.2665980000 0.1385520000 1.4775300000 1.4990960000 109777078 0 1787604992 4.1739339828 3.9982533455 3.6166813374 774 30.9200000000 0.0155185703 0.0095904716 0.0169525184 0.0090556259 3.0304670000 1.2735000000 0.2679520000 0.0000060000 1.4757830000 0.0082030000 109778752 0 1784287232 4.1758141518 3.9983496666 3.6165134907 775 30.9600000000 0.0155594880 0.0095981735 0.0169525184 0.0090499414 3.4318400000 1.2813740000 0.5250640000 0.1384360000 1.4737550000 0.0081970000 109780426 0 1785937920 4.1774415970 3.9987277985 3.6161808968 776 31.0000000000 0.0156111158 0.0096059222 0.0169525184 0.0090472745 3.0287990000 1.2747240000 0.2623200000 0.0000040000 1.4786680000 0.0081780000 109782100 0 1787588608 4.1792840958 3.9988381863 3.6161088943 777 31.0400000000 0.0155576337 0.0096135820 0.0169525184 0.0090433688 4.6654350000 1.2753910000 0.2808680000 0.1386540000 1.4714560000 1.4942340000 109783774 0 1784303616 4.1808013916 3.9986348152 3.6160109043 778 31.0800000000 0.0155817959 0.0096212533 0.0169525184 0.0090380648 3.0329380000 1.2741210000 0.2757560000 0.0000050000 1.4698280000 0.0082600000 109785448 0 1785683968 4.1823163033 3.9997465611 3.6152913570 779 31.1200000000 0.0157248359 0.0096290884 0.0169525184 0.0090489598 3.1655590000 1.2735310000 0.2704630000 0.1383710000 1.4701130000 0.0082740000 109787122 0 1787588608 4.1835684776 4.0006756783 3.6146123409 780 31.1600000000 0.0158218648 0.0096370279 0.0169525184 0.0090836217 3.0236790000 1.2756070000 0.2632030000 0.0000050000 1.4717510000 0.0082450000 109788796 0 1784668160 4.1845569611 4.0010190010 3.6142961979 781 31.2000000000 0.0157940928 0.0096449114 0.0169525184 0.0091184180 4.6601070000 1.2802140000 0.2737810000 0.1386530000 1.4729080000 1.4895920000 109790470 0 1786208256 4.1853060722 4.0011119843 3.6137368679 782 31.2400000000 0.0157681126 0.0096527416 0.0169525184 0.0091505217 3.0406110000 1.2802970000 0.2745880000 0.0000050000 1.4726100000 0.0082820000 109792144 0 1788002304 4.1861562729 4.0014300346 3.6133558750 783 31.2800000000 0.0157890152 0.0096605785 0.0169525184 0.0091811204 3.1683460000 1.2727700000 0.2643210000 0.1382270000 1.4798460000 0.0082630000 109793818 0 1784860672 4.1869688034 4.0014495850 3.6130297184 784 31.3200000000 0.0157134198 0.0096682990 0.0169525184 0.0091966027 3.0722220000 1.2736430000 0.3106620000 0.0000050000 1.4746950000 0.0082300000 109795492 0 1786572800 4.1875796318 4.0011363029 3.6128096581 785 31.3600000000 0.0157693978 0.0096760711 0.0169525184 0.0091946898 4.6542020000 1.2831210000 0.2629980000 0.1388830000 1.4732620000 1.4909390000 109797166 0 1785446400 4.1883320808 4.0009179115 3.6127729416 786 31.4000000000 0.0157782119 0.0096838346 0.0169525184 0.0091890127 2.9818710000 1.2708590000 0.2244030000 0.0000060000 1.4734080000 0.0083300000 109798840 0 1787080704 4.1893692017 4.0017027855 3.6124122143 787 31.4400000000 0.0158163328 0.0096916268 0.0169525184 0.0091893940 3.1053680000 1.2757990000 0.2046760000 0.1385150000 1.4732150000 0.0081910000 109800514 0 1784684544 4.1902956963 4.0023775101 3.6121902466 788 31.4800000000 0.0157983899 0.0096993765 0.0169525184 0.0091923458 3.0358020000 1.2775890000 0.2721120000 0.0000050000 1.4729690000 0.0082990000 109802188 0 1786191872 4.1912145615 4.0028228760 3.6121289730 789 31.5200000000 0.0157933962 0.0097071003 0.0169525184 0.0091964344 4.6598140000 1.2732810000 0.2728340000 0.1381190000 1.4786650000 1.4918710000 109803862 0 1787985920 4.1922421455 4.0038871765 3.6118402481 790 31.5600000000 0.0157889705 0.0097147988 0.0169525184 0.0092263354 2.9796220000 1.2758780000 0.2127630000 0.0000050000 1.4777790000 0.0082290000 109805536 0 1784668160 4.1930909157 4.0046625137 3.6117541790 791 31.6000000000 0.0158731248 0.0097225843 0.0169525184 0.0092608679 3.1538780000 1.2739660000 0.2578450000 0.1379310000 1.4709700000 0.0082470000 109807210 0 1786081280 4.1941094398 4.0049624443 3.6117398739 792 31.6400000000 0.0158822853 0.0097303617 0.0169525184 0.0092723255 3.0096460000 1.2701460000 0.2544690000 0.0000050000 1.4718150000 0.0083210000 109808884 0 1787994112 4.1952118874 4.0054688454 3.6118960381 793 31.6800000000 0.0158945415 0.0097381350 0.0169525184 0.0092819314 4.6550660000 1.2721980000 0.2729080000 0.1384580000 1.4703720000 1.4961960000 109810558 0 1784328192 4.1959686279 4.0062575340 3.6118183136 794 31.7200000000 0.0158456098 0.0097458270 0.0169525184 0.0093039989 3.0254290000 1.2809740000 0.2626440000 0.0000060000 1.4686190000 0.0082890000 109812232 0 1785937920 4.1968970299 4.0072078705 3.6118793488 795 31.7600000000 0.0157860126 0.0097534247 0.0169525184 0.0093330713 3.1661090000 1.2801810000 0.2722040000 0.1377840000 1.4626660000 0.0082150000 109813906 0 1787715584 4.1976146698 4.0076880455 3.6122455597 796 31.8000000000 0.0158511046 0.0097610851 0.0169525184 0.0093660096 3.0205250000 1.2783560000 0.2619400000 0.0000050000 1.4670380000 0.0082630000 109815580 0 1784684544 4.1982674599 4.0086131096 3.6124415398 797 31.8400000000 0.0157753788 0.0097686313 0.0169525184 0.0094464761 4.6077580000 1.2718160000 0.2603590000 0.1376720000 1.4543340000 1.4786200000 109817254 0 1786064896 4.1990509033 4.0094580650 3.6127758026 798 31.8800000000 0.0159502365 0.0097763777 0.0169525184 0.0095463061 2.9979090000 1.2761950000 0.2598710000 0.0000050000 1.4485860000 0.0082140000 109818928 0 1787969536 4.1992201805 4.0099186897 3.6128861904 799 31.9200000000 0.0159429908 0.0097840956 0.0169525184 0.0096007987 3.1376360000 1.2727650000 0.2622640000 0.1374910000 1.4519570000 0.0082370000 109820602 0 1784303616 4.1997923851 4.0101995468 3.6132359505 800 31.9600000000 0.0158262476 0.0097916483 0.0169525184 0.0096203542 3.0002000000 1.2746450000 0.2726710000 0.0000250000 1.4396070000 0.0082070000 109822276 0 1785937920 4.2003273964 4.0103254318 3.6134700775 801 32.0000000000 0.0158594921 0.0097992236 0.0169525184 0.0096234208 4.5722880000 1.2777380000 0.2611420000 0.1373590000 1.4355680000 1.4554440000 109823950 0 1787604992 4.2010884285 4.0105843544 3.6140275002 802 32.0400000000 0.0158294998 0.0098067427 0.0169525184 0.0096258106 2.9757080000 1.2811460000 0.2487070000 0.0000050000 1.4325060000 0.0082600000 109825624 0 1784311808 4.2018446922 4.0107736588 3.6144475937 803 32.0800000000 0.0158546027 0.0098142742 0.0169525184 0.0096242184 3.0636380000 1.2722320000 0.2124160000 0.1373130000 1.4284140000 0.0082160000 109827298 0 1785946112 4.2026872635 4.0111694336 3.6148760319 804 32.1199999990 0.0159451384 0.0098218997 0.0169525184 0.0096231054 2.9753180000 1.2784970000 0.2596580000 0.0000050000 1.4238810000 0.0082160000 109828972 0 1787723776 4.2034091949 4.0114846230 3.6155469418 805 32.1600000000 0.0158571210 0.0098293969 0.0169525184 0.0096240315 4.4989710000 1.2731410000 0.2219640000 0.1373280000 1.4242910000 1.4372410000 109830646 0 1784176640 4.2040162086 4.0116357803 3.6160345078 806 32.2000000000 0.0159149002 0.0098369471 0.0169525184 0.0096231741 2.9762870000 1.2725570000 0.2709610000 0.0000060000 1.4195210000 0.0082840000 109832320 0 1785810944 4.2046184540 4.0116453171 3.6166784763 807 32.2400000000 0.0159488488 0.0098445207 0.0169525184 0.0096181557 3.0927480000 1.2732500000 0.2587470000 0.1371250000 1.4100750000 0.0084570000 109833994 0 1787604992 4.2054996490 4.0118451118 3.6172499657 808 32.2800000000 0.0159920957 0.0098521291 0.0169525184 0.0096130013 2.9677110000 1.2716060000 0.2691870000 0.0000050000 1.4136350000 0.0082600000 109835668 0 1784303616 4.2060508728 4.0120878220 3.6178169250 809 32.3200000000 0.0159419794 0.0098596567 0.0169525184 0.0096091998 4.5039990000 1.2723630000 0.2598010000 0.1371710000 1.4025740000 1.4270430000 109837342 0 1785810944 4.2067823410 4.0121769905 3.6184430122 810 32.3600000000 0.0159722492 0.0098672031 0.0169525184 0.0096057997 2.9099630000 1.2724980000 0.2231440000 0.0000050000 1.4009700000 0.0083550000 109839016 0 1787588608 4.2073874474 4.0120325089 3.6192691326 811 32.4000000000 0.0160187948 0.0098747883 0.0169525184 0.0096001047 3.0919400000 1.2771500000 0.2552820000 0.1372220000 1.4089030000 0.0083280000 109840690 0 1784193024 4.2081456184 4.0119771957 3.6200547218 812 32.4399999990 0.0160388704 0.0098823796 0.0169525184 0.0095944360 3.0423870000 1.2758940000 0.3503090000 0.0000060000 1.3970340000 0.0081970000 109842364 0 1785810944 4.2089157104 4.0118346214 3.6209497452 813 32.4800000000 0.0160931237 0.0098900189 0.0169525184 0.0095893461 4.4689150000 1.2706280000 0.2574080000 0.1373070000 1.3902210000 1.4082800000 109844038 0 1787613184 4.2098584175 4.0120325089 3.6217072010 814 32.5200000000 0.0161524732 0.0098977123 0.0169525184 0.0095864684 2.9400420000 1.2811080000 0.2582580000 0.0000050000 1.3873030000 0.0083000000 109845712 0 1784184832 4.2106084824 4.0118904114 3.6227130890 815 32.5600000000 0.0162252393 0.0099054761 0.0169525184 0.0095884199 3.0719190000 1.2729530000 0.2579590000 0.1377380000 1.3898500000 0.0082340000 109847386 0 1785810944 4.2113685608 4.0118741989 3.6237006187 816 32.6000000000 0.0161902942 0.0099131781 0.0169525184 0.0095909519 2.9437700000 1.2799030000 0.2682190000 0.0000050000 1.3823570000 0.0082420000 109849060 0 1787588608 4.2121667862 4.0120368004 3.6245357990 817 32.6400000000 0.0162247363 0.0099209034 0.0169525184 0.0095930999 4.5434480000 1.2716710000 0.3455270000 0.1374710000 1.3831960000 1.4003910000 109850734 0 1784176640 4.2128281593 4.0119538307 3.6255204678 818 32.6800000000 0.0163073745 0.0099287108 0.0169525184 0.0095966648 2.8819630000 1.2712870000 0.2127780000 0.0000050000 1.3845540000 0.0082190000 109852408 0 1785810944 4.2135004997 4.0120191574 3.6264517307 819 32.7200000000 0.0162591580 0.0099364403 0.0169525184 0.0095983114 3.0600520000 1.2725630000 0.2583270000 0.1376360000 1.3781930000 0.0082260000 109854082 0 1787588608 4.2140288353 4.0118937492 3.6275475025 820 32.7599999990 0.0163480267 0.0099442593 0.0169525184 0.0096014864 2.9376180000 1.2783890000 0.2682940000 0.0000050000 1.3774830000 0.0082570000 109855756 0 1784557568 4.2142128944 4.0117540359 3.6284303665 821 32.7999999990 0.0162598845 0.0099519519 0.0169525184 0.0096048002 4.4053240000 1.2747210000 0.2128500000 0.1378410000 1.3753860000 1.3994080000 109857430 0 1785954304 4.2143874168 4.0115828514 3.6291990280 822 32.8400000000 0.0163100678 0.0099596868 0.0169525184 0.0096081175 2.9303600000 1.2719440000 0.2712240000 0.0000050000 1.3738540000 0.0082160000 109859104 0 1787858944 4.2143211365 4.0110912323 3.6301209927 823 32.8800000000 0.0162259731 0.0099673008 0.0169525184 0.0096192627 3.0617190000 1.2771690000 0.2591160000 0.1380840000 1.3738950000 0.0082810000 109860778 0 1784852480 4.2146210670 4.0106735229 3.6313872337 824 32.9200000000 0.0162027068 0.0099748680 0.0169525184 0.0096280773 2.9108520000 1.2710190000 0.2482130000 0.0000050000 1.3782900000 0.0082560000 109862452 0 1786580992 4.2145080566 4.0101404190 3.6323053837 825 32.9600000000 0.0161216166 0.0099823186 0.0169525184 0.0096392650 4.3928350000 1.2715680000 0.2126360000 0.1381740000 1.3735370000 1.3917110000 109864126 0 1785462784 4.2144885063 4.0097250938 3.6332852840 826 33.0000000000 0.0160545148 0.0099896700 0.0169525184 0.0096501450 2.9246900000 1.2777830000 0.2600900000 0.0000050000 1.3734520000 0.0082310000 109865800 0 1786953728 4.2142610550 4.0096311569 3.6338927746 827 33.0400000000 0.0160465278 0.0099969939 0.0169525184 0.0096547976 3.0197010000 1.2751490000 0.2129030000 0.1385270000 1.3796630000 0.0082990000 109867474 0 1784573952 4.2140655518 4.0092282295 3.6347851753 828 33.0800000000 0.0160334762 0.0100042843 0.0169525184 0.0096628196 2.8739560000 1.2706800000 0.2144380000 0.0000050000 1.3754940000 0.0081980000 109869148 0 1786318848 4.2135853767 4.0086951256 3.6353886127 829 33.1199999990 0.0160690732 0.0100116001 0.0169525184 0.0096716509 4.4048900000 1.2728290000 0.2190790000 0.1387030000 1.3750300000 1.3940710000 109870822 0 1787985920 4.2131400108 4.0088276863 3.6359620094 830 33.1600000000 0.0160989519 0.0100189342 0.0169525184 0.0096715999 2.9432410000 1.2743310000 0.2759300000 0.0000050000 1.3794830000 0.0081890000 109872496 0 1785319424 4.2128911018 4.0087866783 3.6371569633 831 33.2000000000 0.0161309056 0.0100262892 0.0169525184 0.0096751096 3.0123280000 1.2731850000 0.2135450000 0.1388520000 1.3732780000 0.0081850000 109874170 0 1786843136 4.2114706039 4.0088987350 3.6383123398 832 33.2400000000 0.0161847342 0.0100336912 0.0169525184 0.0096697484 2.8822370000 1.2776940000 0.2194280000 0.0000050000 1.3716360000 0.0081820000 109875844 0 1784938496 4.2112073898 4.0087542534 3.6394693851 833 33.2800000000 0.0161724817 0.0100410607 0.0169525184 0.0096653391 4.3998880000 1.2796750000 0.2134640000 0.1388740000 1.3690370000 1.3936620000 109877518 0 1786335232 4.2103772163 4.0084986687 3.6402373314 834 33.3200000000 0.0162028596 0.0100484489 0.0169525184 0.0096613086 2.8529010000 1.2698330000 0.2021590000 0.0000050000 1.3674720000 0.0082460000 109879192 0 1785708544 4.2096619606 4.0087380409 3.6411318779 835 33.3600000000 0.0162619203 0.0100558902 0.0169525184 0.0096556506 3.0095480000 1.2805040000 0.2120390000 0.1392040000 1.3643040000 0.0082000000 109880866 0 1787232256 4.2091617584 4.0088577271 3.6422414780 836 33.4000000000 0.0162658393 0.0100633184 0.0169525184 0.0096500159 2.9126080000 1.2732970000 0.2577170000 0.0000060000 1.3680670000 0.0081740000 109882540 0 1784827904 4.2081689835 4.0084609985 3.6431682110 837 33.4399999990 0.0163461845 0.0100708248 0.0169525184 0.0096452366 4.3893370000 1.3043940000 0.1991110000 0.1391070000 1.3614450000 1.3799860000 109884214 0 1786597376 4.2071638107 4.0082416534 3.6439676285 838 33.4800000000 0.0163156707 0.0100782769 0.0169525184 0.0096404055 2.9213920000 1.2780040000 0.2707800000 0.0000050000 1.3590380000 0.0083000000 109885888 0 1785446400 4.2061572075 4.0081830025 3.6446502209 839 33.5200000000 0.0163579490 0.0100857616 0.0169525184 0.0096348828 3.0020610000 1.2747370000 0.2118240000 0.1393490000 1.3625990000 0.0082390000 109887562 0 1787113472 4.2049927711 4.0080752373 3.6450583935 840 33.5600000000 0.0163688324 0.0100932414 0.0169525184 0.0096295563 2.9116160000 1.2719930000 0.2639200000 0.0000050000 1.3621750000 0.0083130000 109889236 0 1785049088 4.2038273811 4.0073275566 3.6458609104 841 33.6000000000 0.0163456202 0.0101006759 0.0169525184 0.0096269665 4.4194000000 1.2754400000 0.2627580000 0.1394780000 1.3622050000 1.3741680000 109890910 0 1786732544 4.2024989128 4.0063238144 3.6471190453 842 33.6400000000 0.0163974017 0.0101081542 0.0169525184 0.0096325908 2.8697940000 1.2732710000 0.2145080000 0.0000050000 1.3683270000 0.0081960000 109892584 0 1785430016 4.2012724876 4.0059456825 3.6478097439 843 33.6800000000 0.0164387021 0.0101156637 0.0169525184 0.0096339589 3.0513220000 1.2743000000 0.2699500000 0.1396230000 1.3539200000 0.0083060000 109894258 0 1787224064 4.2001018524 4.0059561729 3.6485114098 844 33.7200000000 0.0165304262 0.0101232642 0.0169525184 0.0096313080 2.9227020000 1.2728740000 0.2777920000 0.0000050000 1.3584220000 0.0082000000 109895932 0 1784430592 4.1987943649 4.0055308342 3.6494889259 845 33.7599999990 0.0165517777 0.0101308719 0.0169525184 0.0096323290 4.3982750000 1.2739070000 0.2581250000 0.1399520000 1.3479490000 1.3730370000 109897606 0 1786089472 4.1973953247 4.0053896904 3.6496658325 846 33.7999999990 0.0165881515 0.0101385046 0.0169525184 0.0096322805 2.8565620000 1.2762270000 0.2121010000 0.0000050000 1.3547850000 0.0081740000 109899280 0 1787850752 4.1962122917 4.0056767464 3.6503033638 847 33.8400000000 0.0166576244 0.0101462013 0.0169525184 0.0096283786 3.0324110000 1.2782690000 0.2570310000 0.1404720000 1.3429450000 0.0081810000 109900954 0 1784446976 4.1951241493 4.0058455467 3.6512923241 848 33.8800000000 0.0167030301 0.0101539334 0.0169525184 0.0096229025 2.8938920000 1.2754690000 0.2610160000 0.0000060000 1.3439280000 0.0081860000 109902628 0 1785937920 4.1937656403 4.0059642792 3.6517961025 849 33.9200000000 0.0167876333 0.0101617470 0.0169525184 0.0096174154 4.3775830000 1.2799930000 0.2614590000 0.1397500000 1.3360420000 1.3550210000 109904302 0 1787858944 4.1925973892 4.0062565804 3.6522841454 850 33.9600000000 0.0167324767 0.0101694772 0.0169525184 0.0096125796 2.8863480000 1.2787320000 0.2616060000 0.0000050000 1.3323940000 0.0081820000 109905976 0 1784827904 4.1913766861 4.0061302185 3.6535181999 851 34.0000000000 0.0167489611 0.0101772087 0.0169525184 0.0096089859 3.0141470000 1.2732010000 0.2586670000 0.1396500000 1.3290210000 0.0082030000 109907650 0 1786208256 4.1900014877 4.0059671402 3.6536431313 852 34.0400000000 0.0167440325 0.0101849162 0.0169525184 0.0096055693 2.8675930000 1.2740770000 0.2598950000 0.0000050000 1.3200680000 0.0082740000 109909324 0 1785192448 4.1882581711 4.0057997704 3.6533496380 853 34.0800000000 0.0167615190 0.0101926262 0.0169525184 0.0096017788 4.3399900000 1.2893660000 0.2576000000 0.1394310000 1.3181620000 1.3300460000 109910998 0 1786699776 4.1868648529 4.0054292679 3.6537621021 854 34.1199999990 0.0167513695 0.0102003062 0.0169525184 0.0095974246 2.8810250000 1.2759640000 0.2717930000 0.0000060000 1.3195780000 0.0081770000 109912672 0 1785446400 4.1856045723 4.0048365593 3.6546771526 855 34.1600000000 0.0167240780 0.0102079364 0.0169525184 0.0095924954 2.9407700000 1.2723230000 0.2131900000 0.1390500000 1.3026400000 0.0082320000 109914346 0 1787088896 4.1842956543 4.0034632683 3.6559817791 856 34.2000000000 0.0168164782 0.0102156566 0.0169525184 0.0095904887 2.9622670000 1.2718980000 0.3531950000 0.0000060000 1.3236220000 0.0082190000 109916020 0 1784422400 4.1831674576 4.0026884079 3.6576485634 857 34.2400000000 0.0167949162 0.0102233337 0.0169525184 0.0095913434 4.2976000000 1.2795420000 0.2592700000 0.1390540000 1.2955930000 1.3188020000 109917694 0 1785954304 4.1821284294 4.0027661324 3.6586573124 858 34.2800000000 0.0168465730 0.0102310531 0.0169525184 0.0095869569 2.8546640000 1.2754890000 0.2571840000 0.0000050000 1.3084940000 0.0081830000 109919368 0 1787842560 4.1808819771 4.0021915436 3.6600539684 859 34.3200000000 0.0169022996 0.0102388194 0.0169525184 0.0095842700 2.9726790000 1.2713850000 0.2563690000 0.1442960000 1.2869230000 0.0083100000 109921042 0 1784684544 4.1794929504 4.0017566681 3.6616828442 860 34.3600000000 0.0169439130 0.0102466160 0.0169525184 0.0095804429 2.8415380000 1.2728590000 0.2580610000 0.0000060000 1.2970310000 0.0082250000 109922716 0 1786191872 4.1781101227 4.0019693375 3.6629464626 861 34.4000000000 0.0169533584 0.0102544055 0.0169533584 0.0095750484 4.2543850000 1.2779210000 0.2570740000 0.1387280000 1.2785020000 1.2966830000 109924390 0 1788096512 4.1766405106 4.0017614365 3.6643772125 862 34.4400000000 0.0170744471 0.0102623174 0.0170744471 0.0095695781 2.9281570000 1.2719800000 0.3559650000 0.0000050000 1.2865440000 0.0082710000 109926064 0 1784684544 4.1751894951 4.0017218590 3.6661090851 863 34.4800000000 0.0170021467 0.0102701272 0.0170744471 0.0095640802 2.9548630000 1.2725400000 0.2573810000 0.1385870000 1.2727660000 0.0082570000 109927738 0 1786191872 4.1736888885 4.0019268990 3.6677241325 864 34.5200000000 0.0170192178 0.0102779386 0.0170744471 0.0095590941 2.8286220000 1.2769920000 0.2589330000 0.0000060000 1.2791160000 0.0081730000 109929412 0 1785556992 4.1717987061 4.0021929741 3.6697123051 865 34.5600000000 0.0171716399 0.0102859082 0.0171716399 0.0095553232 4.2345430000 1.2726320000 0.2590430000 0.1385130000 1.2722570000 1.2866530000 109931086 0 1787097088 4.1699295044 4.0019741058 3.6718361378 866 34.6000000000 0.0171462614 0.0102938301 0.0171716399 0.0095498702 2.8181580000 1.2720070000 0.2570530000 0.0000050000 1.2754840000 0.0081800000 109932760 0 1784819712 4.1678318977 4.0016484261 3.6741688251 867 34.6400000000 0.0171453077 0.0103017326 0.0171716399 0.0095447280 2.9508680000 1.2791120000 0.2567820000 0.1385080000 1.2627660000 0.0081920000 109934434 0 1786343424 4.1656842232 4.0022072792 3.6758661270 868 34.6800000000 0.0172274578 0.0103097115 0.0172274578 0.0095408613 2.8202590000 1.2721780000 0.2602010000 0.0000050000 1.2741330000 0.0081890000 109936108 0 1785311232 4.1634135246 4.0027885437 3.6779596806 869 34.7200000000 0.0172137804 0.0103176564 0.0172274578 0.0095384806 4.2332820000 1.2957700000 0.2585240000 0.1383120000 1.2560170000 1.2791710000 109937782 0 1786699776 4.1611118317 4.0034937859 3.6799767017 870 34.7600000000 0.0172188655 0.0103255888 0.0172274578 0.0095413626 2.7741000000 1.2821930000 0.2136570000 0.0000050000 1.2645340000 0.0082740000 109939456 0 1785446400 4.1584987640 4.0039105415 3.6824486256 871 34.8000000000 0.0172195807 0.0103335038 0.0172274578 0.0095446507 2.9401320000 1.2727530000 0.2589040000 0.1383230000 1.2565060000 0.0082160000 109941130 0 1786970112 4.1557574272 4.0033102036 3.6849284172 872 34.8400000000 0.0172235165 0.0103414052 0.0172274578 0.0095391960 2.8205920000 1.2734100000 0.2752530000 0.0000060000 1.2581510000 0.0081770000 109942804 0 1784430592 4.1528511047 4.0028014183 3.6877648830 873 34.8800000000 0.0172237717 0.0103492888 0.0172274578 0.0095382045 4.2366850000 1.3089580000 0.2582200000 0.1383530000 1.2559970000 1.2696960000 109944478 0 1785827328 4.1501359940 4.0041213036 3.6899502277 874 34.9200000000 0.0173452981 0.0103572934 0.0173452981 0.0095334715 2.8296530000 1.2735070000 0.2633180000 0.0000050000 1.2790970000 0.0081840000 109946152 0 1787842560 4.1473579407 4.0055022240 3.6919958591 875 34.9600000000 0.0173531882 0.0103652887 0.0173531882 0.0095369973 2.9397770000 1.2770070000 0.2599160000 0.1384990000 1.2506470000 0.0082270000 109947826 0 1784320000 4.1443710327 4.0058403015 3.6942541599 876 35.0000000000 0.0174231026 0.0103733456 0.0174231026 0.0095402975 2.8075790000 1.2710900000 0.2607310000 0.0000050000 1.2620160000 0.0082750000 109949500 0 1785937920 4.1413578987 4.0061807632 3.6965634823 877 35.0400000000 0.0173836369 0.0103813391 0.0174231026 0.0095412536 4.1741780000 1.2721050000 0.2500330000 0.1383650000 1.2459850000 1.2621520000 109951174 0 1787883520 4.1383624077 4.0067677498 3.6988368034 878 35.0800000000 0.0175375063 0.0103894896 0.0175375063 0.0095460570 2.8532730000 1.2787170000 0.3088520000 0.0000050000 1.2517930000 0.0081670000 109952848 0 1784438784 4.1352362633 4.0067067146 3.7012069225 879 35.1200000000 0.0174101647 0.0103974767 0.0175375063 0.0095443670 2.8917520000 1.2766520000 0.2154900000 0.1382630000 1.2476040000 0.0082210000 109954522 0 1785937920 4.1321787834 4.0071487427 3.7031633854 880 35.1600000000 0.0175037067 0.0104055520 0.0175375063 0.0095508340 2.8092710000 1.2758560000 0.2734790000 0.0000050000 1.2461390000 0.0081890000 109956196 0 1787842560 4.1292405128 4.0081858635 3.7057287693 881 35.2000000000 0.0175209250 0.0104136285 0.0175375063 0.0095676224 4.1182510000 1.2738520000 0.2182930000 0.1382890000 1.2317770000 1.2503730000 109957870 0 1784446976 4.1261653900 4.0080637932 3.7076585293 882 35.2400000000 0.0175552536 0.0104217255 0.0175552536 0.0095687252 2.7554140000 1.2718500000 0.2264480000 0.0000050000 1.2434190000 0.0081690000 109959544 0 1785810944 4.1231565475 4.0080413818 3.7102003098 883 35.2800000000 0.0174976699 0.0104297391 0.0175552536 0.0095650349 2.9143270000 1.2781880000 0.2597160000 0.1379470000 1.2247600000 0.0082540000 109961218 0 1787715584 4.1199879646 4.0081214905 3.7124931812 884 35.3200000000 0.0175233576 0.0104377635 0.0175552536 0.0095606575 2.7845420000 1.2724920000 0.2593060000 0.0000050000 1.2389660000 0.0082120000 109962892 0 1784303616 4.1172080040 4.0090608597 3.7145037651 885 35.3600000000 0.0174664594 0.0104457055 0.0175552536 0.0095574187 4.1482600000 1.2717560000 0.2680690000 0.1376680000 1.2187880000 1.2463410000 109964566 0 1785810944 4.1142745018 4.0094695091 3.7165369987 886 35.4000000000 0.0175118074 0.0104536808 0.0175552536 0.0095530361 2.7318640000 1.2786350000 0.2123520000 0.0000060000 1.2271900000 0.0081560000 109966240 0 1787715584 4.1112885475 4.0094356537 3.7187263966 887 35.4400000000 0.0175252128 0.0104616532 0.0175552536 0.0095478114 2.8999060000 1.2727040000 0.2562540000 0.1374500000 1.2197480000 0.0081750000 109967914 0 1784320000 4.1083564758 4.0095028877 3.7205533981 888 35.4800000000 0.0177337341 0.0104698425 0.0177337341 0.0095425403 2.7635950000 1.2710960000 0.2569490000 0.0000050000 1.2217330000 0.0082490000 109969588 0 1785946112 4.1056032181 4.0097355843 3.7225036621 889 35.5200000000 0.0177230127 0.0104780013 0.0177337341 0.0095389334 4.1150570000 1.2711510000 0.2631560000 0.1372800000 1.2099550000 1.2278550000 109971262 0 1787740160 4.1029787064 4.0102515221 3.7239947319 890 35.5600000000 0.0176122040 0.0104860173 0.0177337341 0.0095341271 2.7831970000 1.2715720000 0.2720200000 0.0000050000 1.2258010000 0.0082090000 109972936 0 1784414208 4.1003308296 4.0107617378 3.7256906033 891 35.6000000000 0.0175948478 0.0104939958 0.0177337341 0.0095288677 2.8793100000 1.2724850000 0.2585330000 0.1363900000 1.1979720000 0.0083580000 109974610 0 1785937920 4.0977196693 4.0115323067 3.7274827957 892 35.6400000000 0.0176590886 0.0105020284 0.0177337341 0.0095235844 2.8113840000 1.2716670000 0.3110890000 0.0000050000 1.2148420000 0.0081990000 109976284 0 1787715584 4.0951824188 4.0120387077 3.7292273045 893 35.6800000000 0.0176185723 0.0105099976 0.0177337341 0.0095183138 4.0713220000 1.2700320000 0.2568150000 0.1358980000 1.1894530000 1.2134100000 109977958 0 1784430592 4.0926146507 4.0124783516 3.7307069302 894 35.7200000000 0.0177602582 0.0105181075 0.0177602582 0.0095131721 2.7547420000 1.2693160000 0.2692050000 0.0000050000 1.2024210000 0.0081630000 109979632 0 1785937920 4.0901288986 4.0131072998 3.7322952747 895 35.7600000000 0.0176929515 0.0105261241 0.0177602582 0.0095083976 2.8585660000 1.2682820000 0.2569860000 0.1350180000 1.1843870000 0.0082190000 109981306 0 1787715584 4.0876336098 4.0133976936 3.7335941792 896 35.8000000000 0.0178248826 0.0105342701 0.0178248826 0.0095033344 2.7495350000 1.2701260000 0.2704690000 0.0000060000 1.1950360000 0.0081730000 109982980 0 1784303616 4.0852098465 4.0136523247 3.7350003719 897 35.8400000000 0.0178262852 0.0105423994 0.0178262852 0.0094981587 4.0884930000 1.3067050000 0.2694750000 0.1343420000 1.1761470000 1.1959650000 109984654 0 1785810944 4.0828194618 4.0141477585 3.7361447811 898 35.8800000000 0.0179502983 0.0105506487 0.0179502983 0.0094931693 2.7967050000 1.2684350000 0.3177990000 0.0000050000 1.1965830000 0.0082760000 109986328 0 1787715584 4.0803666115 4.0149407387 3.7373838425 899 35.9200000000 0.0179161932 0.0105588418 0.0179502983 0.0094885457 2.8396010000 1.2649770000 0.2567800000 0.1339130000 1.1699950000 0.0081670000 109988002 0 1784455168 4.0777730942 4.0150914192 3.7380385399 900 35.9600000000 0.0179371499 0.0105670399 0.0179502983 0.0094833079 2.7839100000 1.2645290000 0.3118740000 0.0000060000 1.1937220000 0.0081960000 109989676 0 1785946112 4.0752267838 4.0147700310 3.7387864590 901 36.0000000000 0.0178657845 0.0105751406 0.0179502983 0.0094797467 4.0355120000 1.2619780000 0.2691720000 0.1336230000 1.1703050000 1.1948140000 109991350 0 1787723776 4.0728507042 4.0148758888 3.7388939857 902 36.0400000000 0.0179786030 0.0105833484 0.0179786030 0.0094745954 2.7381210000 1.2626640000 0.2721440000 0.0000050000 1.1892800000 0.0082330000 109993024 0 1784303616 4.0704922676 4.0153303146 3.7389457226 903 36.0800000000 0.0179904476 0.0105915512 0.0179904476 0.0094694554 2.9355000000 1.2585140000 0.3514260000 0.1337840000 1.1778470000 0.0082550000 109994698 0 1785810944 4.0679197311 4.0152444839 3.7394530773 904 36.1200000000 0.0180737451 0.0105998280 0.0180737451 0.0094642877 2.6796780000 1.2641020000 0.2121410000 0.0000050000 1.1896080000 0.0081590000 109996372 0 1787715584 4.0654878616 4.0153923035 3.7395265102 905 36.1600000000 0.0179744102 0.0106079767 0.0180737451 0.0094595729 4.1369180000 1.3116430000 0.3045490000 0.1354600000 1.1808020000 1.1986110000 109998046 0 1784320000 4.0630016327 4.0157284737 3.7402176857 906 36.2000000000 0.0180890728 0.0106162340 0.0180890728 0.0094560753 2.7409700000 1.2623970000 0.2594260000 0.0000050000 1.2051770000 0.0081650000 109999720 0 1785810944 4.0604019165 4.0158300400 3.7402846813 907 36.2400000000 0.0181105901 0.0106244968 0.0181105901 0.0094526040 2.9042920000 1.2670500000 0.3039560000 0.1356650000 1.1837600000 0.0082040000 110001394 0 1787715584 4.0577888489 4.0156011581 3.7397627831 908 36.2800000000 0.0180771668 0.0106327045 0.0181105901 0.0094474907 2.7080570000 1.2636280000 0.2280850000 0.0000050000 1.2022980000 0.0082360000 110003068 0 1784303616 4.0551233292 4.0154142380 3.7392134666 909 36.3200000000 0.0180560555 0.0106408710 0.0181105901 0.0094423072 4.1164370000 1.2635100000 0.3129060000 0.1359100000 1.1866960000 1.2116960000 110004742 0 1785810944 4.0524911880 4.0154209137 3.7391049862 910 36.3600000000 0.0180672351 0.0106490319 0.0181105901 0.0094371767 2.7976140000 1.2645710000 0.3148440000 0.0000060000 1.2041940000 0.0082140000 110006416 0 1787731968 4.0498695374 4.0156645775 3.7390975952 911 36.4000000000 0.0181220472 0.0106572350 0.0181220472 0.0094323914 2.8919090000 1.2682880000 0.2693770000 0.1368400000 1.2034510000 0.0082720000 110008090 0 1784328192 4.0472207069 4.0154185295 3.7387266159 912 36.4400000000 0.0181136224 0.0106654108 0.0181220472 0.0094272256 2.7465420000 1.2616230000 0.2583760000 0.0000050000 1.2125180000 0.0081970000 110009764 0 1785819136 4.0447225571 4.0156116486 3.7389173508 913 36.4800000000 0.0181057025 0.0106735601 0.0181220472 0.0094223645 4.1353940000 1.2940800000 0.2687350000 0.1379790000 1.2044930000 1.2242910000 110011438 0 1787604992 4.0422344208 4.0159020424 3.7392842770 914 36.5200000000 0.0181161966 0.0106817030 0.0181220472 0.0094188684 2.7311600000 1.2689200000 0.2228940000 0.0000060000 1.2253300000 0.0082460000 110013112 0 1784287232 4.0395879745 4.0157303810 3.7391884327 915 36.5600000000 0.0181684047 0.0106898852 0.0181684047 0.0094150159 2.8529160000 1.2783830000 0.2146660000 0.1379030000 1.2080120000 0.0082200000 110014786 0 1785937920 4.0371527672 4.0155773163 3.7386977673 916 36.6000000000 0.0181125477 0.0106979886 0.0181684047 0.0094101530 2.7802430000 1.2695740000 0.2737900000 0.0000050000 1.2227440000 0.0081550000 110016460 0 1787715584 4.0347490311 4.0153827667 3.7388451099 917 36.6400000000 0.0181299951 0.0107060933 0.0181684047 0.0094050256 4.2759230000 1.2682160000 0.4037010000 0.1388310000 1.2150110000 1.2442920000 110018134 0 1784303616 4.0323185921 4.0147190094 3.7387573719 918 36.6800000000 0.0181412678 0.0107141926 0.0181684047 0.0094001770 2.8183270000 1.2697390000 0.3074040000 0.0000060000 1.2272150000 0.0081580000 110019808 0 1785937920 4.0300602913 4.0146794319 3.7391035557 919 36.7200000000 0.0181433931 0.0107222766 0.0181684047 0.0093951176 2.9251310000 1.2687020000 0.2775920000 0.1399980000 1.2248070000 0.0081660000 110021482 0 1787604992 4.0280222893 4.0149946213 3.7386870384 920 36.7600000000 0.0181690399 0.0107303709 0.0181690399 0.0093903355 2.8267730000 1.2690910000 0.3067090000 0.0000050000 1.2369870000 0.0082040000 110023156 0 1784160256 4.0259776115 4.0147938728 3.7390413284 921 36.8000000000 0.0181769114 0.0107384562 0.0181769114 0.0093852632 4.1720880000 1.2744700000 0.2703770000 0.1400110000 1.2285280000 1.2529960000 110024830 0 1785937920 4.0241632462 4.0150003433 3.7391309738 922 36.8400000000 0.0182165541 0.0107465669 0.0182165541 0.0093806700 2.9343940000 1.2684230000 0.4101200000 0.0000060000 1.2418060000 0.0082190000 110026504 0 1787723776 4.0225234032 4.0155344009 3.7398996353 923 36.8800000000 0.0182560720 0.0107547029 0.0182560720 0.0093767965 2.9275440000 1.2696590000 0.2718070000 0.1403220000 1.2317690000 0.0081520000 110028178 0 1784184832 4.0209541321 4.0157055855 3.7399444580 924 36.9200000000 0.0182810612 0.0107628483 0.0182810612 0.0093740220 2.7988630000 1.2750240000 0.2631310000 0.0000060000 1.2466880000 0.0082080000 110029852 0 1785810944 4.0195198059 4.0155096054 3.7391514778 925 36.9600000000 0.0183112901 0.0107710088 0.0183112901 0.0093697790 4.2671860000 1.2686910000 0.3545690000 0.1407450000 1.2408950000 1.2565060000 110031526 0 1787604992 4.0179800987 4.0153055191 3.7395670414 926 37.0000000000 0.0182832368 0.0107791213 0.0183112901 0.0093647720 2.8055710000 1.2709640000 0.2758910000 0.0000040000 1.2447390000 0.0082080000 110033200 0 1784541184 4.0167074203 4.0155835152 3.7390313148 927 37.0400000000 0.0182797611 0.0107872126 0.0183112901 0.0093602909 2.9336970000 1.2753410000 0.2625660000 0.1411770000 1.2406720000 0.0081610000 110034874 0 1786064896 4.0155825615 4.0157108307 3.7391734123 928 37.0800000000 0.0183388069 0.0107953501 0.0183388069 0.0093570101 2.8158250000 1.2733600000 0.2726700000 0.0000050000 1.2555240000 0.0084620000 110036548 0 1787842560 4.0145702362 4.0165529251 3.7395927906 929 37.1200000000 0.0183068085 0.0108034357 0.0183388069 0.0093562043 4.1476290000 1.2695280000 0.2254980000 0.1415420000 1.2418010000 1.2633240000 110038222 0 1784176640 4.0135493279 4.0167112350 3.7400240898 930 37.1600000000 0.0183498524 0.0108115501 0.0183498524 0.0093552153 2.8064370000 1.2775410000 0.2626150000 0.0000040000 1.2521410000 0.0083000000 110039896 0 1785683968 4.0127286911 4.0169763565 3.7401323318 931 37.2000000000 0.0183480307 0.0108196451 0.0183498524 0.0093534464 2.9344060000 1.2702450000 0.2595730000 0.1417190000 1.2432860000 0.0135690000 110041570 0 1787604992 4.0119457245 4.0172996521 3.7404479980 932 37.2400000000 0.0183651615 0.0108277412 0.0183651615 0.0093504664 2.7563490000 1.2670550000 0.2271930000 0.0000040000 1.2480490000 0.0081970000 110043244 0 1784532992 4.0113091469 4.0175046921 3.7404875755 933 37.2800000000 0.0183395091 0.0108357924 0.0183651615 0.0093474099 4.1613100000 1.2943400000 0.2117890000 0.1416530000 1.2461250000 1.2615410000 110044918 0 1786200064 4.0106134415 4.0179095268 3.7409045696 934 37.3200000000 0.0183712225 0.0108438603 0.0183712225 0.0093449619 2.7978180000 1.2697810000 0.2701750000 0.0000050000 1.2436420000 0.0082410000 110046592 0 1787977728 4.0100841522 4.0186548233 3.7412593365 935 37.3600000000 0.0182805471 0.0108518140 0.0183712225 0.0093445900 2.9259080000 1.2761640000 0.2568480000 0.1416150000 1.2371810000 0.0082130000 110048266 0 1784827904 4.0097041130 4.0189418793 3.7412941456 936 37.4000000000 0.0183465984 0.0108598212 0.0183712225 0.0093428136 2.9277970000 1.2693070000 0.3958190000 0.0000050000 1.2483980000 0.0083410000 110049940 0 1786572800 4.0092768669 4.0191521645 3.7412965298 937 37.4400000000 0.0183624420 0.0108678283 0.0183712225 0.0093393487 4.1727850000 1.2699040000 0.2696700000 0.1422150000 1.2321470000 1.2529490000 110051614 0 1785446400 4.0090136528 4.0191540718 3.7413055897 938 37.4800000000 0.0184007622 0.0108758591 0.0184007622 0.0093359915 3.0576690000 1.2761550000 0.5323850000 0.0000060000 1.2349210000 0.0082710000 110053288 0 1786826752 4.0087227821 4.0191783905 3.7412421703 939 37.5200000000 0.0183532685 0.0108838223 0.0184007622 0.0093316891 2.8830630000 1.2684750000 0.2222680000 0.1416130000 1.2365080000 0.0082590000 110054962 0 1784700928 4.0087237358 4.0193514824 3.7410001755 940 37.5600000000 0.0183184948 0.0108917315 0.0184007622 0.0093274935 2.7756650000 1.2694030000 0.2626650000 0.0000050000 1.2293400000 0.0082720000 110056636 0 1786318848 4.0087227821 4.0196151733 3.7409701347 941 37.6000000000 0.0183574297 0.0108996653 0.0184007622 0.0093238196 4.1634970000 1.2660310000 0.2791970000 0.1414810000 1.2248350000 1.2449540000 110058310 0 1785221120 4.0086622238 4.0201849937 3.7410311699 942 37.6400000000 0.0183494817 0.0109075738 0.0184007622 0.0093205785 2.9240740000 1.2702700000 0.4074570000 0.0000050000 1.2321920000 0.0082460000 110059984 0 1784811520 4.0088291168 4.0206499100 3.7409076691 943 37.6800000000 0.0182801448 0.0109153920 0.0184007622 0.0093190564 2.9168380000 1.2697370000 0.2720000000 0.1411990000 1.2198670000 0.0081680000 110061658 0 1786486784 4.0089154243 4.0208015442 3.7407410145 944 37.7200000000 0.0182811748 0.0109231948 0.0184007622 0.0093167508 2.7638640000 1.2704960000 0.2566780000 0.0000060000 1.2224790000 0.0082570000 110063332 0 1785454592 4.0090336800 4.0212955475 3.7405967712 945 37.7600000000 0.0182742700 0.0109309737 0.0184007622 0.0093143511 4.2516060000 1.2679960000 0.3760040000 0.1428930000 1.2178430000 1.2409430000 110065006 0 1786970112 4.0091643333 4.0215830803 3.7404093742 946 37.8000000000 0.0182826482 0.0109387450 0.0184007622 0.0093119121 2.7154970000 1.2699890000 0.2139360000 0.0000050000 1.2172740000 0.0082140000 110066680 0 1784684544 4.0091695786 4.0217432976 3.7401900291 947 37.8400000000 0.0183567442 0.0109465782 0.0184007622 0.0093084496 2.9574730000 1.2688420000 0.3108520000 0.1467390000 1.2167060000 0.0082440000 110068354 0 1786208256 4.0093159676 4.0221080780 3.7401871681 948 37.8800000000 0.0182758942 0.0109543095 0.0184007622 0.0093057689 2.8541120000 1.2694280000 0.3585890000 0.0000050000 1.2118580000 0.0082350000 110070028 0 1785573376 4.0094208717 4.0222268105 3.7400841713 949 37.9200000000 0.0182800237 0.0109620289 0.0184007622 0.0093027953 4.0689560000 1.2759590000 0.2156770000 0.1412610000 1.2049020000 1.2251790000 110071702 0 1786970112 4.0096297264 4.0225214958 3.7398676872 950 37.9600000000 0.0182979573 0.0109697509 0.0184007622 0.0092989364 2.8356310000 1.2640940000 0.3456120000 0.0000050000 1.2116280000 0.0082910000 110073376 0 1785192448 4.0098748207 4.0229516029 3.7397239208 951 38.0000000000 0.0182759520 0.0109774336 0.0184007622 0.0092946943 2.8462150000 1.2672250000 0.2223440000 0.1405090000 1.2018680000 0.0081710000 110075050 0 1786732544 4.0100808144 4.0231990814 3.7395350933 952 38.0400000000 0.0182697996 0.0109850936 0.0184007622 0.0092922881 2.7992260000 1.2744620000 0.3065150000 0.0000050000 1.2038730000 0.0082470000 110076724 0 1785192448 4.0102324486 4.0234303474 3.7396185398 953 38.0800000000 0.0182760954 0.0109927442 0.0184007622 0.0092882055 4.0848960000 1.2920220000 0.2229890000 0.1402800000 1.1987540000 1.2247550000 110078398 0 1786843136 4.0105762482 4.0236997604 3.7393412590 954 38.1200000000 0.0183151644 0.0110004197 0.0184007622 0.0092834128 2.7334630000 1.2694200000 0.2512360000 0.0000060000 1.1984560000 0.0082100000 110080072 0 1785073664 4.0108656883 4.0240888596 3.7390310764 955 38.1600000000 0.0182813630 0.0110080437 0.0184007622 0.0092789711 2.9400410000 1.2672860000 0.3231240000 0.1402180000 1.1951340000 0.0081760000 110081746 0 1786613760 4.0109963417 4.0240731239 3.7392766476 956 38.2000000000 0.0183511078 0.0110157248 0.0184007622 0.0092741300 2.7052800000 1.2686240000 0.2265330000 0.0000050000 1.1957770000 0.0082150000 110083420 0 1785430016 4.0113368034 4.0245165825 3.7387495041 957 38.2400000000 0.0183626674 0.0110234018 0.0184007622 0.0092694000 4.0554200000 1.2789670000 0.2265440000 0.1401360000 1.1919770000 1.2116540000 110085094 0 1786843136 4.0114626884 4.0243873596 3.7384905815 958 38.2800000000 0.0183372144 0.0110310363 0.0184007622 0.0092647162 2.7490640000 1.2688110000 0.2668850000 0.0000060000 1.1989860000 0.0082320000 110086768 0 1784954880 4.0116014481 4.0245976448 3.7385649681 959 38.3200000000 0.0183564350 0.0110386749 0.0184007622 0.0092600449 2.8880320000 1.2702590000 0.2749650000 0.1400650000 1.1884140000 0.0081730000 110088442 0 1786605568 4.0118966103 4.0246114731 3.7382118702 960 38.3600000000 0.0183832031 0.0110463254 0.0184007622 0.0092555270 2.8941220000 1.2724100000 0.4205500000 0.0000050000 1.1868690000 0.0082280000 110090116 0 1785683968 4.0120663643 4.0247788429 3.7382793427 961 38.4000000000 0.0183755234 0.0110539520 0.0184007622 0.0092510445 4.1079560000 1.2924470000 0.2677100000 0.1399830000 1.1864470000 1.2152230000 110091790 0 1787478016 4.0123744011 4.0248951912 3.7379298210 962 38.4400000000 0.0183913894 0.0110615793 0.0184007622 0.0092464342 2.6943690000 1.2690620000 0.2189450000 0.0000050000 1.1920390000 0.0082520000 110093464 0 1784430592 4.0126347542 4.0250105858 3.7377231121 963 38.4800000000 0.0184025615 0.0110692024 0.0184025615 0.0092417341 2.9004350000 1.2761750000 0.2811150000 0.1398750000 1.1888530000 0.0082440000 110095138 0 1785970688 4.0129084587 4.0248832703 3.7376239300 964 38.5200000000 0.0184144024 0.0110768219 0.0184144024 0.0092370159 2.7493380000 1.2689160000 0.2784080000 0.0000050000 1.1877420000 0.0081780000 110096812 0 1787842560 4.0132393837 4.0251016617 3.7374432087 965 38.5600000000 0.0184193589 0.0110844307 0.0184193589 0.0092322901 4.0808980000 1.2746680000 0.2746570000 0.1395900000 1.1814000000 1.2045400000 110098486 0 1784455168 4.0135345459 4.0251851082 3.7374308109 966 38.6000000000 0.0184112731 0.0110920154 0.0184193589 0.0092277029 2.6854160000 1.2681160000 0.2215310000 0.0000050000 1.1812560000 0.0081820000 110100160 0 1785819136 4.0138034821 4.0251560211 3.7372593880 967 38.6400000000 0.0183713064 0.0110995431 0.0184193589 0.0092229554 2.8318740000 1.2681020000 0.2327460000 0.1393070000 1.1773490000 0.0081800000 110101834 0 1787613184 4.0140814781 4.0251536369 3.7372579575 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 08:58:14 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 nan 3.4492590000 1.2784360000 0.0661550000 0.1514530000 0.0000100000 1.9527320000 105973239 0 1771278336 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378715 1.5413300000 1.3324150000 0.0528170000 0.1477560000 0.0000030000 0.0081190000 108230300 0 1770143744 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728951 1.4799290000 1.2732370000 0.0514740000 0.1467370000 0.0000020000 0.0082510000 108232298 0 1771667456 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723570 3.4127410000 1.2737150000 0.0525090000 0.1516660000 1.9265590000 0.0081480000 108234300 0 1780428800 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276572 0.0024566334 0.0055015511 0.0048988422 5.5507210000 1.2678400000 0.3105270000 0.1469760000 1.8999510000 1.9252610000 108236294 0 1782706176 3.9957129955 4.0020360947 4.0009112358 6 0.2000000000 0.0021158110 0.0023998297 0.0055015511 0.0043899979 3.4471590000 1.3046430000 0.2280610000 0.0000020000 1.9060730000 0.0082110000 108238624 0 1784348672 3.9965538979 4.0017571449 4.0000624657 7 0.2400000000 0.0020491821 0.0023497372 0.0055015511 0.0040164879 3.5459980000 1.2671630000 0.2190850000 0.1470800000 1.9041530000 0.0083480000 108240298 0 1786126336 3.9963860512 4.0014791489 4.0003576279 8 0.2800000000 0.0021295445 0.0023222131 0.0055015511 0.0037228078 3.4112400000 1.2626810000 0.2295270000 0.0000030000 1.9106610000 0.0082030000 108241972 0 1787777024 3.9949586391 4.0019369125 4.0002703667 9 0.3200000000 0.0021676212 0.0023050362 0.0055015511 0.0035287651 5.4599250000 1.2623370000 0.2183710000 0.1469730000 1.9041360000 1.9279150000 108244286 0 1784483840 3.9930224419 4.0012898445 4.0003123283 10 0.3600000000 0.0022070820 0.0022952408 0.0055015511 0.0033890221 3.3911190000 1.2617860000 0.2183150000 0.0000030000 1.9026400000 0.0081970000 108247272 0 1785880576 3.9929070473 4.0026335716 4.0009012222 11 0.4000000000 0.0022589520 0.0022919418 0.0055015511 0.0033576532 3.5852290000 1.2570600000 0.2691710000 0.1467680000 1.9037850000 0.0082540000 108248946 0 1787650048 3.9919445515 4.0017886162 4.0016002655 12 0.4400000000 0.0022641739 0.0022896278 0.0055015511 0.0034313691 3.4008480000 1.2640270000 0.2229490000 0.0000030000 1.9054620000 0.0081970000 108250620 0 1784602624 3.9918572903 4.0017395020 4.0008211136 13 0.4800000000 0.0022805610 0.0022889304 0.0055015511 0.0034363556 5.4660710000 1.2650930000 0.2189940000 0.1468370000 1.9108210000 1.9241290000 108252294 0 1786126336 3.9894258976 4.0015444756 4.0013942719 14 0.5200000000 0.0023245795 0.0022914767 0.0055015511 0.0033244423 3.7395220000 1.2633780000 0.5539610000 0.0000030000 1.9137770000 0.0082030000 108253968 0 1787904000 3.9894297123 4.0028066635 4.0008144379 15 0.5600000000 0.0023152155 0.0022930593 0.0055015511 0.0032123239 3.5731180000 1.2608330000 0.2543850000 0.1468520000 1.9026260000 0.0081940000 108255642 0 1784856576 3.9863409996 4.0038952827 4.0015859604 16 0.6000000000 0.0023966364 0.0022995329 0.0055015511 0.0031281966 3.5066140000 1.2674290000 0.3254620000 0.0000040000 1.9052530000 0.0082510000 108257316 0 1786380288 3.9871170521 4.0023283958 4.0005326271 17 0.6400000000 0.0024171770 0.0023064531 0.0055015511 0.0030499340 5.4984950000 1.2595050000 0.2541290000 0.1468740000 1.9131640000 1.9245880000 108260270 0 1785618432 3.9851157665 4.0009016991 3.9991016388 18 0.6800000000 0.0024460810 0.0023142102 0.0055015511 0.0029601350 3.4480590000 1.2685680000 0.2588310000 0.0000040000 1.9119790000 0.0084370000 108264568 0 1787269120 3.9835417271 4.0011630058 4.0000801086 19 0.7200000000 0.0024325005 0.0023204360 0.0055015511 0.0029193315 3.5865810000 1.2662280000 0.2531620000 0.1468650000 1.9118890000 0.0082050000 108266242 0 1784483840 3.9820523262 4.0014052391 3.9996454716 20 0.7600000000 0.0025416587 0.0023314972 0.0055015511 0.0029369214 3.3967790000 1.2633510000 0.2181630000 0.0000040000 1.9068030000 0.0082060000 108267916 0 1786134528 3.9790830612 4.0002136230 3.9993202686 21 0.8000000000 0.0025807053 0.0023433642 0.0055015511 0.0028726179 5.5180750000 1.2700340000 0.2667000000 0.1469400000 1.9080000000 1.9261200000 108269590 0 1788030976 3.9761929512 4.0010929108 3.9996607304 22 0.8400000000 0.0028562606 0.0023666777 0.0055015511 0.0028130427 3.4218140000 1.2688500000 0.2323360000 0.0000040000 1.9120880000 0.0082640000 108271264 0 1785126912 3.9707212448 4.0004558563 3.9992079735 23 0.8800000000 0.0028551938 0.0023879175 0.0055015511 0.0027484005 3.6067040000 1.2605100000 0.2752420000 0.1470770000 1.9153300000 0.0082810000 108272938 0 1786634240 3.9713082314 3.9995715618 3.9975645542 24 0.9200000000 0.0028111078 0.0024055505 0.0055015511 0.0026883514 3.4147830000 1.2649700000 0.2177730000 0.0000040000 1.9234710000 0.0083030000 108274612 0 1784602624 3.9629046917 4.0010108948 3.9969229698 25 0.9600000000 0.0027976024 0.0024212325 0.0055015511 0.0026601993 5.4875970000 1.2649560000 0.2198730000 0.1472020000 1.9158260000 1.9394600000 108276286 0 1786253312 3.9617183208 4.0022773743 3.9961576462 26 1.0000000000 0.0028472953 0.0024376196 0.0055015511 0.0026079241 3.4569930000 1.2663780000 0.2656820000 0.0000030000 1.9164230000 0.0082340000 108277960 0 1785491456 3.9554529190 4.0008077621 3.9970505238 27 1.0400000000 0.0026989488 0.0024472984 0.0055015511 0.0026330934 3.5970650000 1.2670650000 0.2560130000 0.1474330000 1.9180100000 0.0082560000 108279634 0 1787015168 3.9496526718 4.0000433922 3.9948580265 28 1.0800000000 0.0027757999 0.0024590306 0.0055015511 0.0027071754 3.5174590000 1.2625420000 0.3193870000 0.0000030000 1.9269940000 0.0082470000 108281308 0 1784737792 3.9448726177 4.0019135475 3.9945604801 29 1.1200000000 0.0027224279 0.0024681133 0.0055015511 0.0027850038 5.5800970000 1.2625260000 0.3051020000 0.1479590000 1.9250830000 1.9391260000 108282982 0 1786253312 3.9388141632 4.0020322800 3.9917833805 30 1.1600000000 0.0029723723 0.0024849219 0.0055015511 0.0027877342 3.4807420000 1.2707080000 0.2713390000 0.0000030000 1.9301380000 0.0082550000 108284656 0 1785491456 3.9293599129 4.0014410019 3.9938361645 31 1.2000000000 0.0028923196 0.0024980638 0.0055015511 0.0027641013 3.6681860000 1.2670930000 0.3185950000 0.1483620000 1.9256170000 0.0082070000 108286330 0 1787015168 3.9227764606 4.0022115707 3.9920413494 32 1.2400000000 0.0029370915 0.0025117834 0.0055015511 0.0027640958 3.4830570000 1.2734370000 0.2713410000 0.0000040000 1.9297100000 0.0082730000 108288004 0 1784729600 3.9160673618 4.0025391579 3.9897453785 33 1.2800000000 0.0029342324 0.0025245849 0.0055015511 0.0028064692 5.5654240000 1.2673530000 0.2702520000 0.1481420000 1.9323920000 1.9469420000 108292238 0 1786380288 3.9104619026 4.0022311211 3.9895095825 34 1.3200000000 0.0028950730 0.0025354816 0.0055015511 0.0027797302 3.4865260000 1.2705160000 0.2669250000 0.0000040000 1.9404530000 0.0082910000 108299160 0 1785618432 3.8820011616 4.0016937256 3.9892096519 35 1.3600000000 0.0030741547 0.0025508723 0.0055015511 0.0030460747 3.6186320000 1.2680150000 0.2560410000 0.1484180000 1.9376170000 0.0082150000 108300834 0 1787015168 3.8787074089 4.0025601387 3.9865641594 36 1.4000000000 0.0030332129 0.0025642706 0.0055015511 0.0035563026 3.4749180000 1.2675490000 0.2647470000 0.0000020000 1.9340220000 0.0082700000 108302508 0 1784864768 3.8730514050 4.0033059120 3.9847660065 37 1.4400000000 0.0030157461 0.0025764726 0.0055015511 0.0035938844 5.6074100000 1.2709260000 0.3025720000 0.1491540000 1.9344650000 1.9499550000 108304182 0 1786507264 3.8621103764 4.0013189316 3.9860284328 38 1.4800000000 0.0032005347 0.0025928953 0.0055015511 0.0035536250 3.4926740000 1.2724380000 0.2755900000 0.0000030000 1.9359870000 0.0082840000 108305856 0 1785618432 3.8505403996 4.0007658005 3.9867577553 39 1.5200000000 0.0032575962 0.0026099389 0.0055015511 0.0035108870 3.5874730000 1.2708740000 0.2179830000 0.1489860000 1.9409560000 0.0083110000 108307530 0 1787269120 3.8474044800 4.0001392365 3.9834115505 40 1.5600000000 0.0033195622 0.0026276795 0.0055015511 0.0034941379 3.4370510000 1.2699900000 0.2171170000 0.0000030000 1.9413870000 0.0082040000 108309204 0 1784729600 3.8375029564 3.9985287189 3.9840970039 41 1.6000000000 0.0033402247 0.0026450587 0.0055015511 0.0035146009 5.6061320000 1.2751880000 0.2735150000 0.1496100000 1.9413390000 1.9661290000 108310878 0 1786380288 3.8271043301 3.9974167347 3.9858510494 42 1.6400000000 0.0033453396 0.0026617320 0.0055015511 0.0034757898 3.4408850000 1.2701580000 0.2148480000 0.0000030000 1.9473270000 0.0081890000 108312552 0 1785618432 3.8137385845 3.9989142418 3.9880647659 43 1.6800000000 0.0033309176 0.0026772945 0.0055015511 0.0034549304 3.6444290000 1.2751450000 0.2567860000 0.1496340000 1.9541980000 0.0082780000 108314226 0 1786888192 3.8069241047 3.9993524551 3.9914381504 44 1.7200000000 0.0033258300 0.0026920339 0.0055015511 0.0034860819 3.4492290000 1.2727550000 0.2172090000 0.0000030000 1.9503720000 0.0085390000 108315900 0 1784475648 3.8006076813 3.9986841679 3.9893238544 45 1.7600000000 0.0033450893 0.0027065463 0.0055015511 0.0035048537 5.5955110000 1.2728710000 0.2675120000 0.1493320000 1.9397700000 1.9656680000 108317574 0 1786134528 3.7922329903 4.0006747246 3.9930381775 46 1.8000000000 0.0034082141 0.0027217999 0.0055015511 0.0035113863 3.4943250000 1.2690590000 0.2708360000 0.0000040000 1.9457470000 0.0082690000 108319248 0 1787904000 3.7862722874 4.0012898445 3.9931361675 47 1.8400000000 0.0034266224 0.0027367961 0.0055015511 0.0036170883 3.5784520000 1.2694700000 0.2133220000 0.1493650000 1.9376460000 0.0082700000 108320922 0 1784729600 3.7832624912 3.9994781017 3.9928357601 48 1.8800000000 0.0033781717 0.0027501581 0.0055015511 0.0036605056 3.4912410000 1.2764060000 0.2664680000 0.0000040000 1.9397830000 0.0082080000 108322596 0 1786126336 3.7786982059 3.9991884232 3.9939424992 49 1.9200000000 0.0035794692 0.0027670828 0.0055015511 0.0036223008 5.5499400000 1.2704890000 0.2292250000 0.1494470000 1.9432740000 1.9571160000 108324270 0 1785483264 3.7715673447 4.0004119873 3.9947512150 50 1.9600000000 0.0035761660 0.0027832645 0.0055015511 0.0036079526 3.4822510000 1.2702180000 0.2603020000 0.0000050000 1.9430600000 0.0082850000 108325944 0 1787142144 3.7572417259 4.0000801086 3.9996907711 51 2.0000000000 0.0035184498 0.0027976799 0.0055015511 0.0035822304 3.6352940000 1.2697300000 0.2651320000 0.1496220000 1.9421910000 0.0082150000 108327618 0 1784094720 3.7588238716 3.9999413490 3.9966940880 52 2.0400000000 0.0035658584 0.0028124526 0.0055015511 0.0035470927 3.4910610000 1.2735530000 0.2678990000 0.0000050000 1.9409630000 0.0082500000 108329292 0 1785745408 3.7548794746 4.0003604889 3.9959802628 53 2.0800000000 0.0034984914 0.0028253967 0.0055015511 0.0035916463 5.6310900000 1.2685490000 0.3098470000 0.1497060000 1.9408610000 1.9617220000 108330966 0 1787785216 3.7528636456 3.9979722500 3.9927272797 54 2.1200000000 0.0036599229 0.0028408509 0.0055015511 0.0036670535 3.4412080000 1.2742460000 0.2189970000 0.0000040000 1.9392690000 0.0082590000 108332640 0 1784356864 3.7398264408 3.9965598583 3.9985260963 55 2.1600000000 0.0035320045 0.0028534173 0.0055015511 0.0037614745 3.6648170000 1.2965100000 0.2656780000 0.1496650000 1.9442330000 0.0083230000 108334314 0 1785999360 3.7374927998 3.9971909523 3.9982166290 56 2.2000000000 0.0036828937 0.0028682294 0.0055015511 0.0037688538 3.4815630000 1.2710600000 0.2648220000 0.0000040000 1.9369650000 0.0083000000 108335988 0 1787904000 3.7176365852 3.9976880550 4.0073919296 57 2.2400000000 0.0038219409 0.0028849612 0.0055015511 0.0037478186 5.5838230000 1.2737410000 0.2644920000 0.1493960000 1.9345910000 1.9611870000 108337662 0 1784729600 3.7128336430 3.9951205254 4.0079889297 58 2.2800000000 0.0036937215 0.0028989053 0.0055015511 0.0037568808 3.4744790000 1.2705910000 0.2597180000 0.0000040000 1.9354710000 0.0082560000 108339336 0 1786126336 3.7034838200 3.9942696095 4.0107660294 59 2.3200000000 0.0038727783 0.0029154116 0.0055015511 0.0038958474 3.5735930000 1.2752560000 0.2069290000 0.1492400000 1.9334580000 0.0082870000 108341010 0 1788030976 3.6893458366 3.9967958927 4.0165219307 60 2.3600000000 0.0038597416 0.0029311505 0.0055015511 0.0040110055 3.4482690000 1.2703160000 0.2262980000 0.0000040000 1.9428750000 0.0083250000 108342684 0 1784602624 3.6862196922 3.9950752258 4.0145807266 61 2.4000000000 0.0038700569 0.0029465424 0.0055015511 0.0041278596 5.5743590000 1.2714570000 0.2535300000 0.1494300000 1.9364950000 1.9629880000 108344358 0 1785999360 3.6794519424 3.9935913086 4.0143718719 62 2.4400000000 0.0038843427 0.0029616682 0.0055015511 0.0042928803 3.4776840000 1.2717640000 0.2520710000 0.0000030000 1.9398770000 0.0133930000 108346032 0 1788166144 3.6557705402 3.9940500259 4.0246839523 63 2.4800000000 0.0039063301 0.0029766628 0.0055015511 0.0044369098 3.6348520000 1.2747660000 0.2634150000 0.1496910000 1.9383360000 0.0081940000 108347706 0 1783840768 3.6470942497 3.9929685593 4.0258569717 64 2.5200000000 0.0039120424 0.0029912781 0.0055015511 0.0047971143 3.4940770000 1.2719810000 0.2700110000 0.0000020000 1.9434480000 0.0081930000 108349380 0 1785364480 3.6345658302 3.9940986633 4.0304179192 65 2.5600000000 0.0039092205 0.0030054003 0.0055015511 0.0051042144 5.5939970000 1.2720230000 0.2641110000 0.1501480000 1.9461240000 1.9611140000 108356174 0 1787269120 3.6207087040 3.9939813614 4.0341448784 66 2.6000000000 0.0040721400 0.0030215630 0.0055015511 0.0051950972 3.4454530000 1.2684770000 0.2162230000 0.0000040000 1.9520140000 0.0082560000 108368344 0 1784475648 3.6102135181 3.9952826500 4.0361313820 67 2.6400000000 0.0041016834 0.0030376842 0.0055015511 0.0052462320 3.6589470000 1.2725050000 0.2784200000 0.1520890000 1.9470690000 0.0083730000 108370018 0 1785872384 3.6000037193 3.9977262020 4.0384044647 68 2.6800000000 0.0043081949 0.0030563682 0.0055015511 0.0052293942 3.5140220000 1.2864670000 0.2681840000 0.0000040000 1.9505870000 0.0082870000 108371692 0 1787904000 3.5890214443 3.9976375103 4.0377349854 69 2.7200000000 0.0043247179 0.0030747501 0.0055015511 0.0051927442 5.6093520000 1.2696140000 0.2647560000 0.1569510000 1.9477990000 1.9697300000 108373366 0 1784475648 3.5794913769 3.9978690147 4.0422301292 70 2.7600000000 0.0044273194 0.0030940725 0.0055015511 0.0051651158 3.5012120000 1.2764840000 0.2637370000 0.0000040000 1.9523050000 0.0081970000 108375040 0 1785872384 3.5706284046 3.9997220039 4.0418829918 71 2.8000000000 0.0044263359 0.0031128368 0.0055015511 0.0052162375 3.6029330000 1.2721500000 0.2147980000 0.1523260000 1.9549120000 0.0081940000 108376714 0 1787912192 3.5634377003 4.0003209114 4.0388045311 72 2.8400000000 0.0047300691 0.0031352984 0.0055015511 0.0058997064 3.4912060000 1.2723670000 0.2607790000 0.0000040000 1.9495110000 0.0080420000 108378388 0 1784475648 3.5476479530 4.0055451393 4.0417685509 73 2.8800000000 0.0047880821 0.0031579392 0.0055015511 0.0059716767 5.6259540000 1.2785730000 0.2593340000 0.1525570000 1.9498920000 1.9850960000 108380062 0 1785872384 3.5377209187 4.0069355965 4.0434455872 74 2.9200000000 0.0048688161 0.0031810592 0.0055015511 0.0060621677 3.5055830000 1.2729280000 0.2720900000 0.0000040000 1.9520050000 0.0080460000 108381736 0 1787777024 3.5356769562 4.0086240768 4.0402965546 75 2.9600000000 0.0050445120 0.0032059052 0.0055015511 0.0061161689 3.6605340000 1.2773540000 0.2683680000 0.1533850000 1.9528570000 0.0080400000 108383410 0 1784348672 3.5345199108 4.0122652054 4.0375251770 76 3.0000000000 0.0050753532 0.0032305032 0.0055015511 0.0061503586 3.5017930000 1.2714210000 0.2552660000 0.0000040000 1.9665490000 0.0080410000 108385084 0 1785872384 3.5365347862 4.0153913498 4.0294241905 77 3.0400000000 0.0048940112 0.0032521072 0.0055015511 0.0061735305 5.6004790000 1.2723930000 0.2076760000 0.1541150000 1.9627680000 2.0030110000 108386758 0 1787650048 3.5357229710 4.0158758163 4.0226511955 78 3.0800000000 0.0045078169 0.0032682061 0.0055015511 0.0061426535 3.5093570000 1.2732850000 0.2519380000 0.0000040000 1.9756620000 0.0079320000 108388432 0 1784602624 3.5368659496 4.0172095299 4.0154652596 79 3.1200000000 0.0043801977 0.0032822819 0.0055015511 0.0061045496 3.6216980000 1.2722290000 0.2161600000 0.1553180000 1.9695490000 0.0079170000 108390106 0 1785999360 3.5297675133 4.0203051567 4.0133032799 80 3.1600000000 0.0041195103 0.0032927473 0.0055015511 0.0060691167 3.5247100000 1.2795370000 0.2591180000 0.0000040000 1.9776140000 0.0078980000 108391780 0 1788039168 3.5258750916 4.0231771469 4.0096049309 81 3.2000000000 0.0041722963 0.0033036059 0.0055015511 0.0060410882 5.9441040000 1.2728930000 0.5161000000 0.1566880000 1.9788360000 2.0190230000 108393454 0 1784983552 3.5140287876 4.0221834183 4.0126156807 82 3.2400000000 0.0044058184 0.0033170475 0.0055015511 0.0060492175 3.5555330000 1.2727640000 0.2942070000 0.0000040000 1.9801510000 0.0078460000 108395128 0 1786507264 3.5058395863 4.0223259926 4.0121946335 83 3.2800000000 0.0043075490 0.0033289813 0.0055015511 0.0060867313 3.6301890000 1.2713490000 0.2143820000 0.1578230000 1.9783620000 0.0077060000 108396802 0 1785745408 3.4979178905 4.0244045258 4.0090570450 84 3.3200000000 0.0042933626 0.0033404620 0.0055015511 0.0060775965 3.5144220000 1.2738670000 0.2570620000 0.0000040000 1.9752710000 0.0076680000 108398476 0 1787523072 3.4851734638 4.0234212875 4.0093340874 85 3.3600000000 0.0045061954 0.0033541765 0.0055015511 0.0060684256 5.7257470000 1.2788030000 0.2850580000 0.1598180000 1.9701840000 2.0313180000 108400150 0 1785237504 3.4719917774 4.0243120193 4.0097441673 86 3.4000000000 0.0045118984 0.0033676384 0.0055015511 0.0061073185 3.5111300000 1.2792540000 0.2508470000 0.0000040000 1.9728420000 0.0075890000 108401824 0 1786888192 3.4569852352 4.0252122879 4.0138039589 87 3.4400000000 0.0041984711 0.0033771882 0.0055015511 0.0062320206 3.7174730000 1.2741850000 0.2987000000 0.1608080000 1.9755530000 0.0076220000 108403498 0 1784475648 3.4468982220 4.0239338875 4.0134758949 88 3.4800000000 0.0038761455 0.0033828582 0.0055015511 0.0063827057 3.4727110000 1.2727060000 0.2110540000 0.0000030000 1.9807560000 0.0075350000 108405172 0 1786261504 3.4334392548 4.0241994858 4.0137124062 89 3.5200000000 0.0040151877 0.0033899630 0.0055015511 0.0065286942 5.7363120000 1.2733610000 0.2871650000 0.1623930000 1.9680400000 2.0447780000 108406846 0 1787904000 3.4244003296 4.0244159698 4.0138211250 90 3.5600000000 0.0044031981 0.0034012211 0.0055015511 0.0066375687 3.4950250000 1.2703620000 0.2436570000 0.0000030000 1.9728180000 0.0076050000 108408520 0 1785364480 3.4174854755 4.0226683617 4.0125918388 91 3.6000000000 0.0041566924 0.0034095230 0.0055015511 0.0066781023 3.6537100000 1.2762170000 0.2400590000 0.1626750000 1.9665840000 0.0075640000 108410194 0 1787142144 3.4026193619 4.0213522911 4.0156269073 92 3.6400000000 0.0042276653 0.0034184159 0.0055015511 0.0066900380 3.4988580000 1.2751890000 0.2400450000 0.0000020000 1.9755120000 0.0075080000 108411868 0 1784602624 3.3875219822 4.0234832764 4.0208239555 93 3.6800000000 0.0041637290 0.0034264300 0.0055015511 0.0066694254 5.6925590000 1.2702970000 0.2452770000 0.1635920000 1.9691420000 2.0436100000 108413542 0 1786126336 3.3825414181 4.0226359367 4.0174231529 94 3.7200000000 0.0040693246 0.0034332693 0.0055015511 0.0066415357 3.5403720000 1.2745530000 0.2850630000 0.0000030000 1.9727000000 0.0074580000 108415216 0 1785364480 3.3752577305 4.0201745033 4.0169801712 95 3.7600000000 0.0041937376 0.0034412742 0.0055015511 0.0066270256 3.6569330000 1.2747480000 0.2484580000 0.1644730000 1.9611930000 0.0074390000 108416890 0 1786888192 3.3623626232 4.0215334892 4.0235376358 96 3.8000000000 0.0041481135 0.0034486371 0.0055015511 0.0065993253 3.5389820000 1.2783230000 0.2878860000 0.0000030000 1.9646260000 0.0074790000 108418564 0 1784983552 3.3520479202 4.0210266113 4.0231170654 97 3.8400000000 0.0042966479 0.0034573795 0.0055015511 0.0065655487 5.7050240000 1.2770720000 0.2537300000 0.1704900000 1.9596780000 2.0434150000 108420238 0 1786642432 3.3467411995 4.0183119774 4.0250158310 98 3.8800000000 0.0042435187 0.0034654013 0.0055015511 0.0065401504 3.4937040000 1.2830520000 0.2367310000 0.0000040000 1.9657180000 0.0074640000 108421912 0 1784602624 3.3321287632 4.0176334381 4.0290899277 99 3.9200000000 0.0043203272 0.0034740370 0.0055015511 0.0065129653 3.6581740000 1.2746410000 0.2458970000 0.1658600000 1.9636060000 0.0075490000 108423586 0 1785999360 3.3266921043 4.0190477371 4.0322299004 100 3.9600000000 0.0044253892 0.0034835505 0.0055015511 0.0064802095 3.4879180000 1.2777800000 0.2458680000 0.0000040000 1.9562120000 0.0074150000 108425260 0 1787793408 3.3185496330 4.0186219215 4.0362696648 101 4.0000000000 0.0041726893 0.0034903736 0.0055015511 0.0064505257 5.7734420000 1.2801970000 0.3302030000 0.1659880000 1.9502560000 2.0461420000 108426934 0 1785237504 3.3094899654 4.0169072151 4.0422902107 102 4.0400000000 0.0041463682 0.0034968050 0.0055015511 0.0064299181 3.4723310000 1.2754850000 0.2388660000 0.0000050000 1.9499180000 0.0074220000 108428608 0 1786634240 3.3058989048 4.0154061317 4.0439100266 103 4.0800000000 0.0041686101 0.0035033273 0.0055015511 0.0063992406 3.6397940000 1.2787280000 0.2395640000 0.1669950000 1.9464360000 0.0074230000 108430282 0 1784602624 3.2951936722 4.0149874687 4.0505418777 104 4.1200000000 0.0042536259 0.0035105418 0.0055015511 0.0063736877 3.4681560000 1.2728470000 0.2397600000 0.0000040000 1.9474390000 0.0074480000 108431956 0 1786126336 3.2826068401 4.0132412910 4.0633516312 105 4.1600000000 0.0042670611 0.0035177467 0.0055015511 0.0063732691 5.6598850000 1.2730830000 0.2459090000 0.1669530000 1.9375750000 2.0357050000 108433630 0 1785753600 3.2798745632 4.0129694939 4.0651140213 106 4.2000000000 0.0042519546 0.0035246732 0.0055015511 0.0063807443 3.4761230000 1.2727070000 0.2504920000 0.0000050000 1.9448760000 0.0073770000 108435304 0 1787531264 3.2734243870 4.0136265755 4.0701704025 107 4.2400000000 0.0043523684 0.0035324087 0.0055015511 0.0063642786 3.6365600000 1.2843560000 0.2406330000 0.1671940000 1.9361620000 0.0074920000 108436978 0 1784999936 3.2732272148 4.0103826523 4.0664892197 108 4.2800000000 0.0040824749 0.0035375019 0.0055015511 0.0063354952 3.4711410000 1.2806540000 0.2456260000 0.0000040000 1.9366540000 0.0075160000 108438652 0 1786380288 3.2631123066 4.0093379021 4.0749449730 109 4.3200000000 0.0042370302 0.0035439196 0.0055015511 0.0063172096 5.6822320000 1.2746830000 0.2754880000 0.1676180000 1.9366120000 2.0271440000 108440326 0 1785364480 3.2616040707 4.0093727112 4.0760278702 110 4.3600000000 0.0045651752 0.0035532037 0.0055015511 0.0063272315 3.5070720000 1.3039750000 0.2340810000 0.0000050000 1.9609070000 0.0074120000 108442000 0 1787015168 3.2542734146 4.0088281631 4.0843935013 111 4.4000000000 0.0043248455 0.0035601554 0.0055015511 0.0063263663 3.6531090000 1.2740390000 0.2756870000 0.1686500000 1.9266730000 0.0073630000 108443674 0 1784602624 3.2475299835 4.0074939728 4.0910854340 112 4.4400000000 0.0043372642 0.0035670939 0.0055015511 0.0063277111 3.4405740000 1.2760860000 0.2318830000 0.0000030000 1.9244710000 0.0074200000 108445348 0 1786380288 3.2396156788 4.0080847740 4.0989565849 113 4.4800000000 0.0044071907 0.0035745284 0.0055015511 0.0063347185 5.6154220000 1.2722460000 0.2469910000 0.1683980000 1.9152540000 2.0118290000 108447022 0 1785491456 3.2355160713 4.0079350471 4.1031627655 114 4.5200000000 0.0044070743 0.0035818314 0.0055015511 0.0063809506 3.4289650000 1.2757750000 0.2323610000 0.0000030000 1.9127100000 0.0074000000 108448696 0 1787023360 3.2246799469 4.0078353882 4.1154494286 115 4.5600000000 0.0044499314 0.0035893801 0.0055015511 0.0064042003 3.5942170000 1.2755640000 0.2312630000 0.1689050000 1.9103230000 0.0074470000 108450370 0 1784737792 3.2240977287 4.0077090263 4.1172904968 116 4.6000000000 0.0044587501 0.0035968747 0.0055015511 0.0064448114 3.3826720000 1.2732230000 0.2001570000 0.0000030000 1.9011890000 0.0073760000 108452044 0 1786253312 3.2136869431 4.0103359222 4.1293349266 117 4.6400000000 0.0045406483 0.0036049411 0.0055015511 0.0064524149 5.5361460000 1.2775230000 0.2036270000 0.1692320000 1.8885510000 1.9964500000 108453718 0 1785491456 3.2061164379 4.0132846832 4.1397881508 118 4.6800000000 0.0045140842 0.0036126457 0.0055015511 0.0064252177 3.4118000000 1.2715580000 0.2410390000 0.0000030000 1.8910410000 0.0074070000 108455392 0 1787015168 3.2004292011 4.0117287636 4.1439862251 119 4.7200000000 0.0043879850 0.0036191612 0.0055015511 0.0064032608 3.5752160000 1.2790840000 0.2336680000 0.1696020000 1.8847220000 0.0074060000 108457066 0 1784602624 3.1939742565 4.0112414360 4.1509838104 120 4.7600000000 0.0043916288 0.0036255984 0.0055015511 0.0063785318 3.6565690000 1.2754480000 0.4860540000 0.0000040000 1.8869190000 0.0074000000 108458740 0 1786253312 3.1871032715 4.0125875473 4.1592216492 121 4.8000000000 0.0042435504 0.0036307055 0.0055015511 0.0063613516 5.5835970000 1.2784360000 0.2868100000 0.1697840000 1.8683810000 1.9794380000 108460414 0 1788030976 3.1776585579 4.0120449066 4.1769504547 122 4.8400000000 0.0044044182 0.0036370474 0.0055015511 0.0063388848 3.3762390000 1.2746690000 0.2224490000 0.0000040000 1.8709840000 0.0073770000 108462088 0 1784983552 3.1762087345 4.0135517120 4.1777997017 123 4.8800000000 0.0044389884 0.0036435672 0.0055015511 0.0063167960 3.6064630000 1.2789180000 0.2857750000 0.1702120000 1.8634650000 0.0073200000 108463762 0 1786642432 3.1705729961 4.0177226067 4.1841802597 124 4.9200000000 0.0046380409 0.0036515872 0.0055015511 0.0062967959 3.4258940000 1.2711560000 0.2873040000 0.0000030000 1.8592740000 0.0073700000 108465436 0 1785491456 3.1614503860 4.0186834335 4.2000870705 125 4.9600000000 0.0045913346 0.0036591051 0.0055015511 0.0062866603 5.5064730000 1.2747540000 0.2318240000 0.1704090000 1.8570330000 1.9716870000 108467110 0 1787015168 3.1570639610 4.0184330940 4.2050824165 126 5.0000000000 0.0044073695 0.0036650437 0.0055015511 0.0062673605 3.4177380000 1.2716060000 0.2785220000 0.0000040000 1.8595360000 0.0073100000 108468784 0 1784602624 3.1520702839 4.0195240974 4.2123732567 127 5.0400000000 0.0045736600 0.0036721982 0.0055015511 0.0062431228 3.5768450000 1.2770850000 0.2820060000 0.1706770000 1.8389870000 0.0073090000 108470458 0 1786253312 3.1427550316 4.0205140114 4.2293567657 128 5.0800000000 0.0045452821 0.0036790192 0.0055015511 0.0062205707 3.3681050000 1.2785970000 0.2433660000 0.0000040000 1.8378640000 0.0074140000 108472132 0 1785491456 3.1372530460 4.0203313828 4.2351417542 129 5.1200000000 0.0045614997 0.0036858601 0.0055015511 0.0061976414 5.4644460000 1.2708160000 0.2429980000 0.1713260000 1.8368470000 1.9415980000 108484046 0 1786888192 3.1333074570 4.0207028389 4.2418150902 130 5.1600000000 0.0044154618 0.0036914724 0.0055015511 0.0061928190 3.3464620000 1.2749940000 0.2323920000 0.0000040000 1.8308850000 0.0073140000 108506712 0 1784745984 3.1245503426 4.0204782486 4.2598104477 131 5.2000000000 0.0045687803 0.0036981694 0.0055015511 0.0062237597 3.5142190000 1.2720680000 0.2409760000 0.1715090000 1.8215510000 0.0072890000 108508386 0 1786253312 3.1211049557 4.0210752487 4.2639212608 132 5.2400000000 0.0045208689 0.0037044020 0.0055015511 0.0062357813 3.3502220000 1.2742340000 0.2423650000 0.0000030000 1.8254960000 0.0072930000 108510060 0 1785753600 3.1206190586 4.0208129883 4.2616024017 133 5.2800000000 0.0044301837 0.0037098590 0.0055015511 0.0062356252 5.4293190000 1.2735360000 0.2455960000 0.1721900000 1.8139120000 1.9232770000 108511734 0 1787023360 3.1102237701 4.0209903717 4.2807135582 134 5.3200000000 0.0049340990 0.0037189951 0.0055015511 0.0062678243 3.2980530000 1.2833250000 0.1987110000 0.0000020000 1.8077700000 0.0073230000 108513408 0 1784475648 3.1016879082 4.0238051414 4.2973456383 135 5.3600000000 0.0051022214 0.0037292412 0.0055015511 0.0062886789 3.4877670000 1.2794090000 0.2291660000 0.1730990000 1.7979390000 0.0072890000 108515082 0 1785872384 3.0985486507 4.0243096352 4.3013424873 136 5.4000000000 0.0052532940 0.0037404475 0.0055015511 0.0063254152 3.3023860000 1.2738900000 0.2324290000 0.0000030000 1.7878530000 0.0073370000 108516756 0 1787777024 3.0917990208 4.0244421959 4.3133816719 137 5.4400000000 0.0051915315 0.0037510394 0.0055015511 0.0063784796 5.3673540000 1.2773960000 0.2433680000 0.1736580000 1.7775380000 1.8945610000 108518430 0 1784475648 3.0864050388 4.0248098373 4.3226256371 138 5.4800000000 0.0051984102 0.0037615276 0.0055015511 0.0064211453 3.2974340000 1.2792390000 0.2319130000 0.0000030000 1.7781480000 0.0072780000 108520104 0 1785872384 3.0808227062 4.0239696503 4.3273200989 139 5.5200000000 0.0050529870 0.0037708186 0.0055015511 0.0064635392 3.4604920000 1.2721100000 0.2290100000 0.1748110000 1.7764560000 0.0072730000 108521778 0 1787777024 3.0747067928 4.0218219757 4.3325204849 140 5.5600000000 0.0050764335 0.0037801445 0.0055015511 0.0065356983 3.2784650000 1.2728600000 0.2289230000 0.0000030000 1.7684000000 0.0073820000 108523452 0 1784348672 3.0654485226 4.0225520134 4.3467998505 141 5.6000000000 0.0050843447 0.0037893941 0.0055015511 0.0065695191 5.3227500000 1.2798340000 0.2284520000 0.1759300000 1.7590010000 1.8786730000 108525126 0 1786007552 3.0600781441 4.0237693787 4.3522653580 142 5.6400000000 0.0051300060 0.0037988350 0.0055015511 0.0066040490 3.2466190000 1.2808260000 0.1986200000 0.0000030000 1.7589440000 0.0073620000 108526800 0 1787650048 3.0508432388 4.0238862038 4.3669824600 143 5.6800000000 0.0051584858 0.0038083431 0.0055015511 0.0066805644 3.4448510000 1.2742240000 0.2305820000 0.1766640000 1.7551550000 0.0073360000 108528474 0 1784602624 3.0456042290 4.0261387825 4.3769927025 144 5.7200000000 0.0052303863 0.0038182184 0.0055015511 0.0067244477 3.2631210000 1.2736050000 0.2323880000 0.0000030000 1.7489640000 0.0072500000 108530148 0 1785999360 3.0393848419 4.0278863907 4.3848695755 145 5.7600000000 0.0052119293 0.0038278302 0.0055015511 0.0067244793 5.3000200000 1.2821080000 0.2302650000 0.1774100000 1.7399120000 1.8694530000 108531822 0 1787904000 3.0338294506 4.0269498825 4.3916187286 146 5.8000000000 0.0052597173 0.0038376376 0.0055015511 0.0067157561 3.2627090000 1.2726790000 0.2412430000 0.0000030000 1.7406520000 0.0072440000 108533496 0 1784602624 3.0279932022 4.0271134377 4.4010844231 147 5.8400000000 0.0052874377 0.0038475002 0.0055015511 0.0066992867 3.4222490000 1.2702560000 0.2336980000 0.1787780000 1.7313800000 0.0072440000 108535170 0 1785999360 3.0178065300 4.0263466835 4.4220204353 148 5.8800000000 0.0053258152 0.0038574888 0.0055015511 0.0066787131 3.2615870000 1.2734700000 0.2395990000 0.0000030000 1.7402990000 0.0072920000 108536844 0 1787904000 3.0163846016 4.0262718201 4.4253993034 149 5.9200000000 0.0052909576 0.0038671094 0.0055015511 0.0066620850 5.2677580000 1.2708560000 0.2299100000 0.1787070000 1.7275700000 1.8598200000 108538518 0 1784221696 3.0120275021 4.0269570351 4.4364581108 150 5.9600000000 0.0053383503 0.0038769177 0.0055015511 0.0066437052 3.2490360000 1.2759330000 0.2321430000 0.0000050000 1.7327640000 0.0072830000 108540192 0 1785880576 3.0084500313 4.0267443657 4.4451808929 151 6.0000000000 0.0053814831 0.0038868817 0.0055015511 0.0066250831 3.4153170000 1.2765200000 0.2292340000 0.1792450000 1.7220600000 0.0073590000 108541866 0 1787531264 3.0051531792 4.0272583961 4.4549136162 152 6.0400000000 0.0053532743 0.0038965290 0.0055015511 0.0066115981 3.2415200000 1.2720130000 0.2312580000 0.0000050000 1.7300660000 0.0072550000 108543540 0 1784475648 3.0020453930 4.0285611153 4.4656977654 153 6.0800000000 0.0054403264 0.0039066192 0.0055015511 0.0066008653 5.2425090000 1.2751330000 0.2212900000 0.1798320000 1.7159180000 1.8494060000 108545214 0 1785872384 2.9984090328 4.0276021957 4.4742846489 154 6.1200000000 0.0054078642 0.0039163675 0.0055015511 0.0066196666 3.2001640000 1.2767480000 0.1982070000 0.0000040000 1.7170560000 0.0072210000 108546888 0 1787777024 2.9939262867 4.0269155502 4.4866042137 155 6.1600000000 0.0053848973 0.0039258419 0.0055015511 0.0066830260 3.4159060000 1.2785690000 0.2393810000 0.1808440000 1.7089510000 0.0072200000 108548562 0 1784475648 2.9922735691 4.0259833336 4.4942073822 156 6.2000000000 0.0054017566 0.0039353029 0.0055015511 0.0067947543 3.2709880000 1.2742280000 0.2709510000 0.0000040000 1.7176230000 0.0072510000 108550236 0 1785872384 2.9875745773 4.0271224976 4.5091648102 157 6.2400000000 0.0054253852 0.0039447939 0.0055015511 0.0068855944 5.2178580000 1.2733140000 0.2289870000 0.1805770000 1.7011190000 1.8328520000 108551910 0 1787777024 2.9853200912 4.0277442932 4.5200910568 158 6.2800000000 0.0054243957 0.0039541585 0.0055015511 0.0069624338 3.1834410000 1.2750680000 0.1992930000 0.0000050000 1.7008710000 0.0072490000 108553584 0 1784475648 2.9823272228 4.0280370712 4.5365991592 159 6.3200000000 0.0054579903 0.0039636165 0.0055015511 0.0069929541 3.3896150000 1.2753110000 0.2294020000 0.1812140000 1.6954700000 0.0072650000 108555258 0 1785753600 2.9817621708 4.0274462700 4.5443158150 160 6.3600000000 0.0054670470 0.0039730130 0.0055015511 0.0070307137 3.2122920000 1.2740760000 0.2299150000 0.0000050000 1.7001320000 0.0072030000 108556932 0 1787658240 2.9806263447 4.0288314819 4.5597958565 161 6.4000000000 0.0055451156 0.0039827776 0.0055451156 0.0070159694 5.1830590000 1.2711740000 0.2280790000 0.1807100000 1.6858820000 1.8162590000 108558606 0 1784348672 2.9807460308 4.0293331146 4.5706205368 162 6.4400000000 0.0056404737 0.0039930103 0.0056404737 0.0069964035 3.2002950000 1.2759140000 0.2288930000 0.0000050000 1.6872090000 0.0073030000 108560280 0 1785745408 2.9806492329 4.0276541710 4.5817890167 163 6.4800000000 0.0055858828 0.0040027825 0.0056404737 0.0069796318 3.3351740000 1.2767090000 0.1871160000 0.1816980000 1.6814280000 0.0072400000 108561954 0 1787650048 2.9796733856 4.0289230347 4.5947990417 164 6.5200000000 0.0055936826 0.0040124831 0.0056404737 0.0069631761 3.2382620000 1.2735110000 0.2690410000 0.0000050000 1.6875410000 0.0071810000 108563628 0 1784221696 2.9795687199 4.0302939415 4.6066241264 165 6.5600000000 0.0056372429 0.0040223301 0.0056404737 0.0069536574 5.1673220000 1.2707950000 0.2361220000 0.1832250000 1.6733750000 1.8028260000 108565302 0 1785745408 2.9785389900 4.0315456390 4.6246185303 166 6.6000000000 0.0056491503 0.0040321303 0.0056491503 0.0069707461 3.1842760000 1.2749220000 0.2271400000 0.0000040000 1.6739100000 0.0072980000 108566976 0 1787650048 2.9793138504 4.0322647095 4.6359190941 167 6.6400000000 0.0056326739 0.0040417144 0.0056491503 0.0069781288 3.3627070000 1.2779190000 0.2269300000 0.1818010000 1.6678020000 0.0072610000 108568650 0 1784348672 2.9803650379 4.0341715813 4.6462898254 168 6.6800000000 0.0056979922 0.0040515731 0.0056979922 0.0069804052 3.1834310000 1.2722150000 0.2282080000 0.0000040000 1.6747880000 0.0071940000 108570324 0 1785880576 2.9808826447 4.0344500542 4.6587238312 169 6.7200000000 0.0057120374 0.0040613984 0.0057120374 0.0069669111 5.1505620000 1.2780190000 0.2304730000 0.1809530000 1.6658490000 1.7941810000 108571998 0 1787658240 2.9809489250 4.0322737694 4.6731190681 170 6.7600000000 0.0057127099 0.0040711120 0.0057127099 0.0069590058 3.1739260000 1.2742500000 0.2282460000 0.0000040000 1.6631220000 0.0073220000 108573672 0 1784475648 2.9790518284 4.0343317986 4.6902108192 171 6.8000000000 0.0057170046 0.0040807371 0.0057170046 0.0069521871 3.3581600000 1.2776640000 0.2308410000 0.1815560000 1.6598830000 0.0071940000 108575346 0 1785872384 2.9801149368 4.0371308327 4.6994032860 172 6.8400000000 0.0057815122 0.0040906253 0.0057815122 0.0069339435 3.1745080000 1.2719560000 0.2305620000 0.0000040000 1.6637410000 0.0072050000 108577020 0 1787777024 2.9806330204 4.0384221077 4.7124533653 173 6.8800000000 0.0057613156 0.0041002825 0.0057815122 0.0069147561 5.1744230000 1.2731540000 0.2820940000 0.1810280000 1.6556280000 1.7814630000 108578694 0 1784475648 2.9802680016 4.0400028229 4.7263722420 174 6.9200000000 0.0058372878 0.0041102653 0.0058372878 0.0068953522 3.1607580000 1.2707420000 0.2285440000 0.0000200000 1.6531300000 0.0072900000 108580368 0 1785872384 2.9792184830 4.0418081284 4.7390394211 175 6.9600000000 0.0058148773 0.0041200059 0.0058372878 0.0068755765 3.3458110000 1.2795600000 0.2276120000 0.1802480000 1.6501500000 0.0072010000 108582042 0 1787777024 2.9796950817 4.0427293777 4.7508597374 176 7.0000000000 0.0058151642 0.0041296375 0.0058372878 0.0068598381 3.1698240000 1.2763740000 0.2314790000 0.0000030000 1.6537500000 0.0071830000 108583716 0 1784475648 2.9784328938 4.0430684090 4.7653713226 177 7.0400000000 0.0058493884 0.0041393536 0.0058493884 0.0068703855 5.0961640000 1.2708910000 0.2338640000 0.1797490000 1.6433050000 1.7672710000 108585390 0 1786007552 2.9794783592 4.0406761169 4.7724809647 178 7.0800000000 0.0058938609 0.0041492104 0.0058938609 0.0068562044 3.1548810000 1.2756250000 0.2303910000 0.0000040000 1.6405180000 0.0072470000 108587064 0 1787912192 2.9807314873 4.0402455330 4.7797713280 179 7.1200000000 0.0057937284 0.0041583976 0.0058938609 0.0068422031 3.3340800000 1.2733150000 0.2345590000 0.1795340000 1.6383050000 0.0073060000 108588738 0 1785110528 2.9809319973 4.0426254272 4.7934212685 180 7.1600000000 0.0058475710 0.0041677819 0.0058938609 0.0068239074 3.1564510000 1.2715230000 0.2353880000 0.0000040000 1.6411780000 0.0073080000 108590412 0 1786634240 2.9817256927 4.0451145172 4.8064718246 181 7.2000000000 0.0058467402 0.0041770579 0.0058938609 0.0068091723 5.0350720000 1.2748930000 0.1926380000 0.1793080000 1.6341590000 1.7530250000 108592086 0 1784856576 2.9838731289 4.0457701683 4.8172841072 182 7.2400000000 0.0058718156 0.0041863698 0.0058938609 0.0067923163 3.1072090000 1.2754710000 0.1910920000 0.0000040000 1.6322030000 0.0072870000 108593760 0 1786761216 2.9835515022 4.0460495949 4.8312544823 183 7.2800000000 0.0058787907 0.0041956180 0.0058938609 0.0067772016 3.3414410000 1.2747770000 0.2445350000 0.1840900000 1.6297410000 0.0072200000 108595434 0 1784348672 2.9818632603 4.0466232300 4.8474369049 184 7.3200000000 0.0058910772 0.0042048324 0.0058938609 0.0067592741 3.1546150000 1.2738960000 0.2452090000 0.0000040000 1.6272330000 0.0072040000 108597108 0 1785999360 2.9840569496 4.0462040901 4.8580355644 185 7.3600000000 0.0058561838 0.0042137587 0.0058938609 0.0067436215 5.0664740000 1.2901700000 0.2306530000 0.1792660000 1.6268490000 1.7384410000 108598782 0 1787904000 2.9855935574 4.0464515686 4.8734321594 186 7.4000000000 0.0058046882 0.0042223121 0.0058938609 0.0067312103 3.1523860000 1.2805480000 0.2394510000 0.0000040000 1.6240090000 0.0072550000 108600456 0 1785110528 2.9854605198 4.0460834503 4.8915376663 187 7.4400000000 0.0057758940 0.0042306200 0.0058938609 0.0067247987 3.3690090000 1.2759090000 0.2771440000 0.1794660000 1.6281530000 0.0072410000 108602130 0 1786769408 2.9885911942 4.0460863113 4.8999261856 188 7.4800000000 0.0057976991 0.0042389555 0.0058938609 0.0067332562 3.1332710000 1.2730990000 0.2284640000 0.0000040000 1.6233080000 0.0072180000 108603804 0 1784610816 2.9909634590 4.0496478081 4.9153881073 189 7.5200000000 0.0057881367 0.0042471522 0.0058938609 0.0067171288 5.0017210000 1.2865760000 0.1864800000 0.1796310000 1.6199440000 1.7279970000 108605478 0 1786126336 2.9931201935 4.0523738861 4.9329953194 190 7.5600000000 0.0058489027 0.0042555825 0.0058938609 0.0067070910 3.1361510000 1.2795540000 0.2279370000 0.0000040000 1.6202790000 0.0072380000 108607152 0 1787904000 2.9953892231 4.0513386726 4.9477715492 191 7.6000000000 0.0058529708 0.0042639458 0.0058938609 0.0066954102 3.3114470000 1.2728790000 0.2294250000 0.1797170000 1.6211450000 0.0071780000 108608826 0 1785110528 2.9966988564 4.0535979271 4.9640827179 192 7.6400000000 0.0059405942 0.0042726783 0.0059405942 0.0066882240 3.1265080000 1.2725730000 0.2277050000 0.0000030000 1.6178630000 0.0071620000 108610500 0 1786634240 3.0003650188 4.0597529411 4.9791641235 193 7.6800000000 0.0060042208 0.0042816501 0.0060042208 0.0066895812 5.0636820000 1.2783440000 0.2663360000 0.1798150000 1.6145730000 1.7234890000 108612174 0 1784729600 3.0003859997 4.0602555275 4.9974579811 194 7.7200000000 0.0061026351 0.0042910366 0.0061026351 0.0066869382 3.1317720000 1.2772890000 0.2276620000 0.0000040000 1.6185160000 0.0071630000 108613848 0 1786253312 3.0001204014 4.0562448502 5.0137495995 195 7.7600000000 0.0060891667 0.0043002578 0.0061026351 0.0066901231 3.2674020000 1.2737550000 0.1857410000 0.1804400000 1.6191840000 0.0071640000 108615522 0 1785364480 3.0013499260 4.0558104515 5.0267858505 196 7.8000000000 0.0060746432 0.0043093107 0.0061026351 0.0067269574 3.1261640000 1.2736710000 0.2270330000 0.0000040000 1.6171120000 0.0071470000 108617196 0 1787015168 3.0032200813 4.0594630241 5.0435671806 197 7.8400000000 0.0061573023 0.0043186914 0.0061573023 0.0067525664 5.0193780000 1.2800540000 0.2257890000 0.1807400000 1.6118470000 1.7197260000 108618870 0 1784754176 3.0050678253 4.0629320145 5.0556378365 198 7.8800000000 0.0060380050 0.0043273748 0.0061573023 0.0067704246 3.1192050000 1.2790360000 0.2177190000 0.0000050000 1.6140480000 0.0072120000 108620544 0 1786380288 3.0061933994 4.0666270256 5.0721654892 199 7.9200000000 0.0060632247 0.0043360977 0.0061573023 0.0067636545 3.3030220000 1.2733990000 0.2255010000 0.1811730000 1.6146480000 0.0071450000 108622218 0 1785491456 3.0082638264 4.0675625801 5.0879802704 200 7.9600000000 0.0062610083 0.0043457222 0.0062610083 0.0067543027 3.1198680000 1.2725870000 0.2262240000 0.0000050000 1.6126240000 0.0071860000 108623892 0 1787142144 3.0084490776 4.0661687851 5.1020402908 201 8.0000000000 0.0061986842 0.0043549409 0.0062610083 0.0067696529 5.0141270000 1.2755270000 0.2255210000 0.1873750000 1.6090150000 1.7155300000 108625566 0 1784729600 3.0090851784 4.0665450096 5.1207580566 202 8.0400000000 0.0061783455 0.0043639677 0.0062610083 0.0067867785 3.1391970000 1.2733650000 0.2371540000 0.0000050000 1.6204290000 0.0070780000 108627240 0 1786253312 3.0118985176 4.0674633980 5.1310186386 203 8.0800000000 0.0062717712 0.0043733657 0.0062717712 0.0067962560 3.3043550000 1.2815510000 0.2260880000 0.1821040000 1.6063350000 0.0071090000 108628914 0 1785491456 3.0141985416 4.0692620277 5.1484475136 204 8.1200000000 0.0061448915 0.0043820497 0.0062717712 0.0067884557 3.1252410000 1.2794700000 0.2264330000 0.0000040000 1.6110660000 0.0071100000 108630588 0 1787133952 3.0160853863 4.0686817169 5.1607265472 205 8.1600000000 0.0062117437 0.0043909750 0.0062717712 0.0067805760 5.0152850000 1.2714990000 0.2282250000 0.1824590000 1.6156700000 1.7162350000 108632262 0 1784856576 3.0190021992 4.0676693916 5.1724872589 206 8.1999999990 0.0062133577 0.0043998216 0.0062717712 0.0067713425 3.1565560000 1.2701600000 0.2651060000 0.0000040000 1.6130220000 0.0070560000 108633936 0 1786642432 3.0223686695 4.0677299500 5.1860399246 207 8.2400000000 0.0062038908 0.0044085369 0.0062717712 0.0067640516 3.2940600000 1.2736590000 0.2259380000 0.1818880000 1.6042690000 0.0071110000 108635610 0 1785626624 3.0268919468 4.0706119537 5.1996178627 208 8.2799999990 0.0061709578 0.0044170100 0.0062717712 0.0067513544 3.1539210000 1.2795060000 0.2636690000 0.0000050000 1.6023270000 0.0071400000 108637284 0 1787142144 3.0311090946 4.0727357864 5.2122311592 209 8.3200000000 0.0062781195 0.0044259149 0.0062781195 0.0067487276 4.9522260000 1.2726470000 0.1842190000 0.1818370000 1.6089810000 1.7033170000 108638958 0 1784983552 3.0356693268 4.0745925903 5.2253561020 210 8.3599999990 0.0062834104 0.0044347601 0.0062834104 0.0067726188 3.1232640000 1.2729080000 0.2318000000 0.0000050000 1.6102840000 0.0070610000 108640632 0 1786380288 3.0413033962 4.0754232407 5.2363662720 211 8.4000000000 0.0063373982 0.0044437773 0.0063373982 0.0067924135 3.2826350000 1.2690020000 0.2214160000 0.1815300000 1.6023790000 0.0070650000 108642306 0 1785745408 3.0463533401 4.0736045837 5.2501225471 212 8.4399999990 0.0063816868 0.0044529184 0.0063816868 0.0067785403 3.0863770000 1.2796160000 0.1939460000 0.0000050000 1.6045770000 0.0070160000 108643980 0 1787015168 3.0536408424 4.0765614510 5.2617449760 213 8.4800000000 0.0064191553 0.0044621496 0.0064191553 0.0067801231 4.9945770000 1.2695410000 0.2294040000 0.1813530000 1.6089650000 1.7040700000 108645654 0 1784856576 3.0600745678 4.0804648399 5.2762432098 214 8.5200000000 0.0064530550 0.0044714529 0.0064530550 0.0068429535 3.1185620000 1.2759990000 0.2215140000 0.0000050000 1.6127570000 0.0070550000 108647328 0 1786380288 3.0671315193 4.0807375908 5.2883849144 215 8.5600000000 0.0064731357 0.0044807630 0.0064731357 0.0068523890 3.3008420000 1.2794160000 0.2238020000 0.1807490000 1.6085530000 0.0070180000 108649002 0 1785618432 3.0750112534 4.0800528526 5.2988901138 216 8.6000000000 0.0065567396 0.0044903740 0.0065567396 0.0068376068 3.1184400000 1.2749290000 0.2269110000 0.0000050000 1.6082590000 0.0070930000 108650676 0 1787150336 3.0843217373 4.0845680237 5.3104977608 217 8.6400000000 0.0066856914 0.0045004907 0.0066856914 0.0068615085 4.9877960000 1.2730760000 0.2201760000 0.1799390000 1.6114560000 1.7018290000 108652350 0 1784881152 3.0933165550 4.0876088142 5.3273582458 218 8.6800000000 0.0065396228 0.0045098445 0.0066856914 0.0069121430 3.1096200000 1.2722690000 0.2197190000 0.0000050000 1.6092440000 0.0071120000 108654024 0 1786507264 3.1017422676 4.0873403549 5.3364295959 219 8.7200000000 0.0066964929 0.0045198292 0.0066964929 0.0069122109 3.2887250000 1.2769590000 0.2207460000 0.1791180000 1.6035440000 0.0070950000 108655698 0 1785618432 3.1119105816 4.0902094841 5.3467597961 220 8.7600000000 0.0068431790 0.0045303899 0.0068431790 0.0069154469 3.1255170000 1.2723570000 0.2299680000 0.0000050000 1.6148130000 0.0071050000 108657372 0 1787269120 3.1224982738 4.0952267647 5.3585247993 221 8.8000000000 0.0067451247 0.0045404113 0.0068431790 0.0069528878 4.9725190000 1.2712140000 0.2198550000 0.1784540000 1.6023610000 1.6993720000 108659046 0 1784856576 3.1321575642 4.0963530540 5.3703017235 222 8.8400000000 0.0069276472 0.0045511646 0.0069276472 0.0069614125 3.0744240000 1.2733110000 0.1821590000 0.0000050000 1.6105350000 0.0071340000 108660720 0 1786507264 3.1414620876 4.0982007980 5.3848562241 223 8.8800000000 0.0069411499 0.0045618820 0.0069411499 0.0069621969 3.2886540000 1.2781500000 0.2204890000 0.1778320000 1.6037180000 0.0071810000 108662394 0 1785364480 3.1521151066 4.1013650894 5.3942303658 224 8.9200000000 0.0069078892 0.0045723553 0.0069411499 0.0069681242 3.1185970000 1.2730800000 0.2219230000 0.0000060000 1.6152280000 0.0070810000 108664068 0 1787015168 3.1628322601 4.1044430733 5.4048418999 225 8.9600000000 0.0069334880 0.0045828492 0.0069411499 0.0069654689 4.9981130000 1.2714110000 0.2601650000 0.1772790000 1.5998230000 1.6881570000 108665742 0 1784881152 3.1733043194 4.1071119308 5.4128870964 226 9.0000000000 0.0072617098 0.0045947026 0.0072617098 0.0069518744 3.1077620000 1.2728770000 0.2223690000 0.0000050000 1.6039760000 0.0071700000 108667416 0 1786515456 3.1837577820 4.1113362312 5.4245338440 227 9.0400000000 0.0070939055 0.0046057123 0.0072617098 0.0069380760 3.2435990000 1.2771050000 0.1836740000 0.1774020000 1.5968770000 0.0072120000 108669090 0 1785745408 3.1957333088 4.1171150208 5.4329285622 228 9.0800000000 0.0072634732 0.0046173691 0.0072634732 0.0069493081 3.1070090000 1.2675140000 0.2239500000 0.0000050000 1.6069590000 0.0072140000 108670764 0 1787396096 3.2072908878 4.1231794357 5.4464344978 229 9.1200000000 0.0072194398 0.0046287319 0.0072634732 0.0070086316 4.9201500000 1.2697910000 0.2242310000 0.1755870000 1.5858460000 1.6633480000 108672438 0 1784856576 3.2178654671 4.1272563934 5.4538664818 230 9.1600000000 0.0072506536 0.0046401315 0.0072634732 0.0071099718 3.1076660000 1.2709030000 0.2359010000 0.0000050000 1.5922800000 0.0072550000 108674112 0 1786507264 3.2287573814 4.1313409805 5.4607300758 231 9.2000000000 0.0071157701 0.0046508486 0.0072634732 0.0073229198 3.2245030000 1.2706580000 0.1876470000 0.1744810000 1.5829910000 0.0073130000 108675786 0 1785491456 3.2380080223 4.1321730614 5.4681630135 232 9.2400000000 0.0072320555 0.0046619745 0.0072634732 0.0074875967 3.0982570000 1.2732200000 0.2311410000 0.0000040000 1.5851070000 0.0074530000 108677460 0 1786888192 3.2475297451 4.1352376938 5.4765243530 233 9.2800000000 0.0071868454 0.0046728108 0.0072634732 0.0076314129 4.8310180000 1.2721690000 0.1904340000 0.1733050000 1.5658200000 1.6279780000 108679134 0 1784856576 3.2571361065 4.1380004883 5.4838261604 234 9.3200000000 0.0072243507 0.0046837149 0.0072634732 0.0077352719 3.0854830000 1.2739440000 0.2310510000 0.0000050000 1.5717260000 0.0074340000 108680808 0 1786253312 3.2670898438 4.1417474747 5.4907226562 235 9.3600000000 0.0071833511 0.0046943516 0.0072634732 0.0078123871 3.2502540000 1.2717380000 0.2324060000 0.1726490000 1.5645610000 0.0074890000 108682482 0 1785499648 3.2771916389 4.1449508667 5.4980082512 236 9.4000000000 0.0073455707 0.0047055856 0.0073455707 0.0078735154 3.0852490000 1.2692470000 0.2430900000 0.0000050000 1.5639400000 0.0076080000 108684156 0 1787277312 3.2866625786 4.1479277611 5.5063867569 237 9.4400000000 0.0072606211 0.0047163663 0.0073455707 0.0079018576 4.7974990000 1.2766010000 0.1929230000 0.1717930000 1.5524770000 1.6023350000 108685830 0 1784729600 3.2966377735 4.1519007683 5.5128464699 238 9.4800000000 0.0074522495 0.0047278616 0.0074522495 0.0079238125 3.0815640000 1.2760220000 0.2368650000 0.0000050000 1.5595180000 0.0077390000 108687504 0 1786380288 3.3075277805 4.1581296921 5.5206341743 239 9.5200000000 0.0073819705 0.0047389667 0.0074522495 0.0079675928 3.2657030000 1.2915070000 0.2420490000 0.1703710000 1.5524620000 0.0079260000 108689178 0 1785618432 3.3182523251 4.1632189751 5.5281701088 240 9.5600000000 0.0074214106 0.0047501435 0.0074522495 0.0080216078 3.0282200000 1.2717910000 0.1988810000 0.0000050000 1.5482120000 0.0079740000 108690852 0 1787015168 3.3284628391 4.1680369377 5.5367369652 241 9.6000000000 0.0073843924 0.0047610740 0.0074522495 0.0080763473 4.8004530000 1.2737080000 0.2537900000 0.1688880000 1.5366010000 1.5660820000 108692526 0 1784348672 3.3377621174 4.1687760353 5.5454578400 242 9.6400000000 0.0072675091 0.0047714312 0.0074522495 0.0080971280 3.0815840000 1.2701990000 0.2591050000 0.0000050000 1.5427470000 0.0081400000 108694200 0 1785872384 3.3475120068 4.1711721420 5.5540022850 243 9.6800000000 0.0072645382 0.0047816909 0.0074522495 0.0081114728 3.2677840000 1.2682680000 0.3009930000 0.1680810000 1.5208510000 0.0082050000 108695874 0 1787777024 3.3584938049 4.1771435738 5.5617599487 244 9.7200000000 0.0072634993 0.0047918623 0.0074522495 0.0081583377 3.0723490000 1.2704770000 0.2675060000 0.0000050000 1.5246160000 0.0082710000 108697548 0 1784365056 3.3697884083 4.1835832596 5.5698757172 245 9.7600000000 0.0071288454 0.0048014010 0.0074522495 0.0082216576 4.7524920000 1.2678730000 0.2688490000 0.1675860000 1.5129180000 1.5338690000 108699222 0 1786007552 3.3800208569 4.1859502792 5.5777807236 246 9.8000000000 0.0071295248 0.0048108649 0.0074522495 0.0082414008 3.0181530000 1.2695150000 0.2229890000 0.0000040000 1.5160430000 0.0081830000 108700896 0 1787785216 3.3903644085 4.1888170242 5.5867514610 247 9.8400000000 0.0072109434 0.0048205818 0.0074522495 0.0082465259 3.1971770000 1.2686720000 0.2599000000 0.1671640000 1.4917760000 0.0082660000 108702570 0 1784602624 3.3998820782 4.1891589165 5.5967364311 248 9.8800000000 0.0071984339 0.0048301699 0.0074522495 0.0082317205 3.0500530000 1.2706710000 0.2709400000 0.0000050000 1.4987850000 0.0082390000 108704244 0 1786126336 3.4092133045 4.1909103394 5.6052317619 249 9.9200000000 0.0071728956 0.0048395784 0.0074522495 0.0082162940 4.7022810000 1.2672140000 0.2596140000 0.1673090000 1.4839190000 1.5228240000 108705918 0 1788030976 3.4192438126 4.1931743622 5.6128840446 250 9.9600000000 0.0071871225 0.0048489686 0.0074522495 0.0082001174 3.0281270000 1.2707770000 0.2598120000 0.0000030000 1.4877880000 0.0082920000 108707592 0 1784602624 3.4289274216 4.1953811646 5.6218380928 251 10.0000000000 0.0072706095 0.0048586166 0.0074522495 0.0081839730 3.2038810000 1.2742820000 0.2698500000 0.1672570000 1.4828050000 0.0082510000 108709266 0 1785999360 3.4390454292 4.1985454559 5.6306185722 252 10.0400000000 0.0072192885 0.0048679843 0.0074522495 0.0081708227 3.0366240000 1.2654240000 0.2703080000 0.0000040000 1.4912680000 0.0081950000 108710940 0 1788030976 3.4475769997 4.1975812912 5.6410908699 253 10.0800000000 0.0071596620 0.0048770424 0.0074522495 0.0081555316 4.7986260000 1.2692050000 0.3556050000 0.1677960000 1.4835120000 1.5210710000 108712614 0 1784475648 3.4551205635 4.1944413185 5.6509113312 254 10.1200000000 0.0072314618 0.0048863117 0.0074522495 0.0081757976 3.0296700000 1.2710530000 0.2607850000 0.0000040000 1.4880930000 0.0082000000 108714288 0 1785999360 3.4649107456 4.1983122826 5.6597952843 255 10.1600000000 0.0072321631 0.0048955111 0.0074522495 0.0081910445 3.2126900000 1.2697770000 0.2724640000 0.1734770000 1.4872720000 0.0082600000 108715962 0 1788166144 3.4757940769 4.2051801682 5.6687030792 256 10.2000000000 0.0072652982 0.0049047681 0.0074522495 0.0081785495 2.9754180000 1.2662230000 0.2155890000 0.0000040000 1.4838740000 0.0081980000 108717636 0 1784483840 3.4869959354 4.2101140022 5.6771597862 257 10.2400000000 0.0072123022 0.0049137469 0.0074522495 0.0081642683 4.7086310000 1.2747430000 0.2739150000 0.1671360000 1.4798920000 1.5113960000 108739790 0 1785872384 3.4963631630 4.2097663879 5.6859660149 258 10.2800000000 0.0072267223 0.0049227119 0.0074522495 0.0081484136 3.0344580000 1.2740810000 0.2722730000 0.0000050000 1.4783130000 0.0082010000 108783448 0 1787904000 3.5067136288 4.2148523331 5.6947937012 259 10.3200000000 0.0072493460 0.0049316950 0.0074522495 0.0081425861 3.2002850000 1.2714030000 0.2714290000 0.1672090000 1.4804890000 0.0081790000 108785122 0 1784492032 3.5171959400 4.2187533379 5.7012019157 260 10.3600000000 0.0072519951 0.0049406192 0.0074522495 0.0081486138 3.0115570000 1.2709740000 0.2590190000 0.0000040000 1.4718420000 0.0081750000 108786796 0 1785872384 3.5271730423 4.2203540802 5.7094364166 261 10.4000000000 0.0071925232 0.0049492472 0.0074522495 0.0081483325 4.6828820000 1.2750470000 0.2646640000 0.1667770000 1.4702940000 1.5046020000 108788470 0 1787904000 3.5367360115 4.2198190689 5.7162728310 262 10.4400000000 0.0072121145 0.0049578841 0.0074522495 0.0081359505 3.0277910000 1.2669740000 0.2731050000 0.0000050000 1.4779890000 0.0081310000 108790144 0 1784492032 3.5462644100 4.2201099396 5.7234826088 263 10.4800000000 0.0071829641 0.0049663445 0.0074522495 0.0081224802 3.1858330000 1.2697590000 0.2696990000 0.1662600000 1.4703680000 0.0081850000 108791818 0 1785872384 3.5570573807 4.2215270996 5.7290954590 264 10.5200000000 0.0071723033 0.0049747004 0.0074522495 0.0081122057 3.1687570000 1.2757740000 0.4119300000 0.0000050000 1.4712430000 0.0081690000 108793492 0 1787777024 3.5673718452 4.2211647034 5.7350811958 265 10.5600000000 0.0072257533 0.0049831950 0.0074522495 0.0080970837 4.6837340000 1.2711430000 0.2627990000 0.1655900000 1.4745890000 1.5080170000 108795166 0 1784516608 3.5786204338 4.2230968475 5.7412815094 266 10.6000000000 0.0071348231 0.0049912838 0.0074522495 0.0080862795 3.0648510000 1.2718360000 0.3051180000 0.0000050000 1.4781480000 0.0081760000 108796840 0 1785872384 3.5906050205 4.2253236771 5.7456026077 267 10.6400000000 0.0071600103 0.0049994064 0.0074522495 0.0080825913 3.1757720000 1.2741460000 0.2679270000 0.1646550000 1.4593180000 0.0081830000 108798514 0 1787777024 3.6018710136 4.2244324684 5.7496213913 268 10.6800000000 0.0071790912 0.0050075395 0.0074522495 0.0080758278 3.0624080000 1.2664260000 0.3251550000 0.0000050000 1.4610630000 0.0081670000 108800188 0 1784492032 3.6132102013 4.2238888741 5.7556648254 269 10.7200000000 0.0071298629 0.0050154292 0.0074522495 0.0080648506 4.6524450000 1.2691860000 0.2615970000 0.1635880000 1.4565140000 1.4999920000 108801862 0 1785872384 3.6251096725 4.2236847878 5.7579913139 270 10.7600000000 0.0071178875 0.0050232161 0.0074522495 0.0080555959 3.0024650000 1.2719210000 0.2691740000 0.0000050000 1.4514700000 0.0082060000 108803536 0 1787650048 3.6505076885 4.2284135818 5.7683362961 271 10.8000000000 0.0071071233 0.0050309058 0.0074522495 0.0080726265 3.1424070000 1.2780190000 0.2557020000 0.1618430000 1.4370090000 0.0081990000 108805210 0 1784492032 3.6648347378 4.2321515083 5.7716712952 272 10.8400000000 0.0071172761 0.0050385762 0.0074522495 0.0081345927 2.9733490000 1.2735740000 0.2563680000 0.0000050000 1.4337010000 0.0081500000 108806884 0 1785872384 3.6767871380 4.2302832603 5.7751111984 273 10.8800000000 0.0071191038 0.0050461972 0.0074522495 0.0081430377 4.5797860000 1.2712180000 0.2683730000 0.1607370000 1.4179870000 1.4597820000 108808558 0 1787650048 3.6893951893 4.2310099602 5.7796678543 274 10.9200000000 0.0071475259 0.0050538663 0.0074522495 0.0081519052 2.9627870000 1.2707980000 0.2696620000 0.0000040000 1.4124380000 0.0082440000 108810232 0 1784238080 3.7026751041 4.2322463989 5.7833566666 275 10.9600000000 0.0071270289 0.0050614051 0.0074522495 0.0081575559 3.0733450000 1.2697220000 0.2228560000 0.1596780000 1.4112980000 0.0081630000 108811906 0 1785880576 3.7155640125 4.2321867943 5.7861218452 276 11.0000000000 0.0071478086 0.0050689645 0.0074522495 0.0081547484 2.9391990000 1.2674250000 0.2610580000 0.0000050000 1.4008190000 0.0082510000 108813580 0 1787658240 3.7290294170 4.2340888977 5.7898845673 277 11.0400000000 0.0071679186 0.0050765420 0.0074522495 0.0081603347 4.5230310000 1.2722530000 0.2608390000 0.1600140000 1.3989630000 1.4293060000 108815254 0 1784238080 3.7425992489 4.2355880737 5.7932372093 278 11.0800000000 0.0071917605 0.0050841507 0.0074522495 0.0081662052 2.9460340000 1.2727930000 0.2745860000 0.0000050000 1.3887410000 0.0081800000 108816928 0 1785745408 3.7561869621 4.2373499870 5.7966256142 279 11.1200000000 0.0071720122 0.0050916340 0.0074522495 0.0081755239 3.0859930000 1.2712420000 0.2688720000 0.1571690000 1.3787920000 0.0082330000 108818602 0 1787650048 3.7701401711 4.2390966415 5.8006148338 280 11.1600000000 0.0071711019 0.0050990607 0.0074522495 0.0081838331 2.9254850000 1.2754570000 0.2696130000 0.0000050000 1.3704430000 0.0082660000 108820276 0 1784238080 3.7841420174 4.2415952682 5.8037881851 281 11.2000000000 0.0072021643 0.0051065451 0.0074522495 0.0081901937 4.4670020000 1.2728610000 0.2702690000 0.1559220000 1.3698230000 1.3964530000 108821950 0 1785745408 3.7972922325 4.2424721718 5.8063907623 282 11.2400000000 0.0071795178 0.0051138960 0.0074522495 0.0081855197 2.9141890000 1.2698500000 0.2715790000 0.0000050000 1.3628370000 0.0082410000 108823624 0 1787523072 3.8091387749 4.2414684296 5.8109889030 283 11.2800000000 0.0071693873 0.0051211592 0.0074522495 0.0081712139 3.0722130000 1.2671250000 0.2751900000 0.1551920000 1.3644460000 0.0084690000 108825298 0 1784492032 3.8214337826 4.2427735329 5.8134727478 284 11.3200000000 0.0072012139 0.0051284834 0.0074522495 0.0081603273 2.9187640000 1.2760190000 0.2720060000 0.0000060000 1.3608080000 0.0082610000 108826972 0 1785872384 3.8340234756 4.2448945045 5.8188323975 285 11.3600000000 0.0073052407 0.0051361211 0.0074522495 0.0081575676 4.4644400000 1.2715840000 0.3059900000 0.1540610000 1.3451690000 1.3859400000 108828646 0 1787801600 3.8456349373 4.2461028099 5.8229665756 286 11.4000000000 0.0071966816 0.0051433259 0.0074522495 0.0081495025 2.9421700000 1.2725140000 0.3201570000 0.0000050000 1.3395320000 0.0082810000 108830320 0 1784373248 3.8561344147 4.2459516525 5.8269910812 287 11.4400000000 0.0072420673 0.0051506386 0.0074522495 0.0081353266 3.0426000000 1.2714370000 0.2670270000 0.1586340000 1.3355190000 0.0082690000 108831994 0 1785753600 3.8656661510 4.2456107140 5.8311882019 288 11.4800000000 0.0071690185 0.0051576468 0.0074522495 0.0081220324 2.8930750000 1.2756480000 0.2747350000 0.0000040000 1.3327710000 0.0082390000 108833668 0 1787650048 3.8745107651 4.2454223633 5.8351383209 289 11.5200000000 0.0072287126 0.0051648132 0.0074522495 0.0081093310 4.4292200000 1.2765050000 0.3096900000 0.1517320000 1.3295800000 1.3600010000 108835342 0 1784365056 3.8830618858 4.2453570366 5.8417048454 290 11.5600000000 0.0072377468 0.0051719612 0.0074522495 0.0081010784 3.1775170000 1.2773640000 0.5592360000 0.0000040000 1.3309310000 0.0082350000 108837016 0 1785745408 3.8913807869 4.2457695007 5.8474531174 291 11.6000000000 0.0072773378 0.0051791962 0.0074522495 0.0080908989 3.3103630000 1.2714550000 0.5431500000 0.1509800000 1.3347670000 0.0082640000 108838690 0 1787650048 3.8989372253 4.2449045181 5.8545756340 292 11.6400000000 0.0072736288 0.0051863689 0.0074522495 0.0080787840 2.9331250000 1.2680600000 0.3278560000 0.0000040000 1.3271950000 0.0082760000 108840364 0 1784492032 3.9069783688 4.2458882332 5.8603420258 293 11.6800000000 0.0072658053 0.0051934659 0.0074522495 0.0080650595 4.3214000000 1.2694500000 0.2201390000 0.1498920000 1.3282520000 1.3519460000 108842038 0 1785872384 3.9139490128 4.2461404800 5.8672003746 294 11.7200000000 0.0073064989 0.0052006531 0.0074522495 0.0080527569 2.8908140000 1.2710460000 0.2774620000 0.0000040000 1.3322800000 0.0083070000 108843712 0 1787650048 3.9200761318 4.2454543114 5.8745656013 295 11.7600000000 0.0072983028 0.0052077638 0.0074522495 0.0080448674 2.9706120000 1.2731990000 0.2126170000 0.1496110000 1.3252230000 0.0081940000 108845386 0 1784365056 3.9257638454 4.2454032898 5.8815135956 296 11.8000000000 0.0072825886 0.0052147733 0.0074522495 0.0080358231 2.8284060000 1.2716340000 0.2119270000 0.0000040000 1.3347850000 0.0083250000 108847060 0 1785880576 3.9316146374 4.2455763817 5.8880434036 297 11.8400000000 0.0073231547 0.0052218723 0.0074522495 0.0080273263 4.3823430000 1.2727510000 0.2596200000 0.1496930000 1.3311070000 1.3674360000 108848734 0 1787658240 3.9365198612 4.2451448441 5.8955979347 298 11.8800000000 0.0073448555 0.0052289964 0.0074522495 0.0080228102 2.9061650000 1.2978780000 0.2616960000 0.0000040000 1.3366410000 0.0081990000 108850408 0 1785880576 3.9414150715 4.2445263863 5.9035639763 299 11.9200000000 0.0073230099 0.0052359998 0.0074522495 0.0080138120 3.0533770000 1.2726450000 0.2782490000 0.1499520000 1.3424370000 0.0083170000 108852082 0 1787658240 3.9464573860 4.2445235252 5.9116935730 300 11.9600000000 0.0073280609 0.0052429733 0.0074522495 0.0080012795 2.8899280000 1.2697010000 0.2673200000 0.0000040000 1.3428660000 0.0082710000 108853756 0 1784373248 3.9514734745 4.2453432083 5.9199895859 301 12.0000000000 0.0073247417 0.0052498895 0.0074522495 0.0079882075 4.4149700000 1.2789650000 0.2670930000 0.1504910000 1.3432410000 1.3734270000 108855430 0 1785753600 3.9561090469 4.2456231117 5.9292144775 302 12.0400000000 0.0073758853 0.0052569292 0.0074522495 0.0079775854 2.8929730000 1.2769580000 0.2595150000 0.0000040000 1.3464550000 0.0082530000 108857104 0 1787650048 3.9600841999 4.2455153465 5.9391050339 303 12.0800000000 0.0073278230 0.0052637638 0.0074522495 0.0079716625 3.0358270000 1.2685770000 0.2580350000 0.1502840000 1.3489160000 0.0081900000 108858778 0 1784365056 3.9642703533 4.2457637787 5.9490609169 304 12.1200000000 0.0074398522 0.0052709220 0.0074522495 0.0079706556 2.9900000000 1.2757910000 0.3512720000 0.0000040000 1.3529050000 0.0082790000 108860452 0 1785745408 3.9682104588 4.2461347580 5.9593229294 305 12.1600000000 0.0073896488 0.0052778687 0.0074522495 0.0079677369 4.4350870000 1.2737130000 0.2604720000 0.1504590000 1.3613790000 1.3871950000 108862126 0 1787650048 3.9718677998 4.2459445000 5.9706048965 306 12.2000000000 0.0074207559 0.0052848716 0.0074522495 0.0079611405 2.9232830000 1.2727450000 0.2777590000 0.0000040000 1.3627840000 0.0082550000 108863800 0 1784483840 3.9754848480 4.2459397316 5.9821190834 307 12.2400000000 0.0074666901 0.0052919785 0.0074666901 0.0079630015 3.0613830000 1.2720850000 0.2689110000 0.1508110000 1.3595670000 0.0082610000 108865474 0 1785753600 3.9787690639 4.2467131615 5.9937586784 308 12.2800000000 0.0074947071 0.0052991302 0.0074947071 0.0079670440 2.8638850000 1.2683840000 0.2123520000 0.0000050000 1.3732220000 0.0081910000 108867148 0 1787650048 3.9814045429 4.2468442917 6.0053315163 309 12.3200000000 0.0074623125 0.0053061308 0.0074947071 0.0079784327 4.4737590000 1.2725310000 0.2681740000 0.1510850000 1.3720450000 1.4081630000 108868822 0 1784348672 3.9833178520 4.2464199066 6.0162644386 310 12.3600000000 0.0075107105 0.0053132423 0.0075107105 0.0079973935 2.9701360000 1.2719880000 0.3065230000 0.0000040000 1.3814490000 0.0083580000 108870496 0 1785745408 3.9849948883 4.2459454536 6.0282244682 311 12.4000000000 0.0075397096 0.0053204014 0.0075397096 0.0080113032 3.1568700000 1.2816680000 0.3150920000 0.1520070000 1.3980120000 0.0082440000 108872170 0 1787777024 3.9872174263 4.2467899323 6.0390157700 312 12.4400000000 0.0075825392 0.0053276518 0.0075825392 0.0080484792 2.9337340000 1.2704930000 0.2621520000 0.0000030000 1.3910070000 0.0082280000 108873844 0 1784619008 3.9895761013 4.2465453148 6.0628619194 313 12.4800000000 0.0075840126 0.0053348606 0.0075840126 0.0080423368 4.5055850000 1.2779360000 0.2635700000 0.1522540000 1.3889040000 1.4210780000 108875518 0 1785999360 3.9901640415 4.2463455200 6.0736198425 314 12.5200000000 0.0076331748 0.0053421801 0.0076331748 0.0080346759 2.9392210000 1.2783860000 0.2604930000 0.0000030000 1.3902210000 0.0082220000 108877192 0 1788030976 3.9902260303 4.2452583313 6.0861778259 315 12.5600000000 0.0076627689 0.0053495471 0.0076627689 0.0080350000 3.0882220000 1.2727930000 0.2579150000 0.1521380000 1.3952540000 0.0082480000 108878866 0 1784619008 3.9906795025 4.2455143929 6.0975279808 316 12.6000000000 0.0076559964 0.0053568459 0.0076627689 0.0080247947 2.9343280000 1.2711030000 0.2681160000 0.0000040000 1.3851000000 0.0081840000 108880540 0 1786126336 3.9908633232 4.2457528114 6.1096925735 317 12.6400000000 0.0076000774 0.0053639224 0.0076627689 0.0080122405 4.4746170000 1.2684880000 0.2574670000 0.1571120000 1.3808440000 1.4088640000 108882214 0 1788039168 3.9905433655 4.2450342178 6.1213445663 318 12.6800000000 0.0076019154 0.0053709601 0.0076627689 0.0079995948 2.9259750000 1.2736810000 0.2581660000 0.0000040000 1.3839660000 0.0082420000 108883888 0 1784492032 3.9899044037 4.2445130348 6.1327033043 319 12.7200000000 0.0075516575 0.0053777961 0.0076627689 0.0079870200 3.1128160000 1.2745700000 0.3078390000 0.1529030000 1.3674290000 0.0082280000 108885562 0 1786126336 3.9891736507 4.2445731163 6.1427402496 320 12.7600000000 0.0075067328 0.0053844491 0.0076627689 0.0079744980 3.1875820000 1.2755220000 0.5427540000 0.0000040000 1.3591480000 0.0082860000 108887236 0 1788030976 3.9879767895 4.2446594238 6.1529741287 321 12.8000000000 0.0074471394 0.0053908749 0.0076627689 0.0079644547 4.4653380000 1.2668850000 0.3156050000 0.1489480000 1.3558840000 1.3760780000 108888910 0 1784872960 3.9858322144 4.2435078621 6.1637806892 322 12.8400000000 0.0073677176 0.0053970142 0.0076627689 0.0079542197 2.8881650000 1.2711650000 0.2695580000 0.0000040000 1.3372820000 0.0081800000 108890584 0 1786380288 3.9841904640 4.2437772751 6.1732726097 323 12.8800000000 0.0073185833 0.0054029633 0.0076627689 0.0079453868 3.0262180000 1.2759650000 0.2689500000 0.1472050000 1.3240290000 0.0081800000 108892258 0 1785618432 3.9822340012 4.2426195145 6.1820073128 324 12.9200000000 0.0072594946 0.0054086933 0.0076627689 0.0079340715 2.8537260000 1.2701390000 0.2573540000 0.0000040000 1.3160340000 0.0082140000 108893932 0 1787015168 3.9802505970 4.2419195175 6.1912312508 325 12.9600000000 0.0071518151 0.0054140568 0.0076627689 0.0079220269 4.3347990000 1.2682080000 0.3045170000 0.1453070000 1.2961980000 1.3186850000 108895606 0 1784602624 3.9788503647 4.2426457405 6.2003426552 326 13.0000000000 0.0071157739 0.0054192768 0.0076627689 0.0079104256 2.8263320000 1.2768980000 0.2588830000 0.0000040000 1.2804430000 0.0082300000 108897280 0 1786126336 3.9768946171 4.2422628403 6.2076134682 327 13.0400000000 0.0071357801 0.0054245260 0.0076627689 0.0078996777 2.9951570000 1.2672400000 0.3056130000 0.1428340000 1.2687570000 0.0088280000 108898954 0 1788039168 3.9749619961 4.2426605225 6.2173676491 328 13.0800000000 0.0071374890 0.0054297485 0.0076627689 0.0078887908 2.7702920000 1.2664450000 0.2487600000 0.0000040000 1.2449580000 0.0081780000 108900628 0 1785135104 3.9744465351 4.2453622818 6.2239398956 329 13.1200000000 0.0070991991 0.0054348228 0.0076627689 0.0078773547 4.1011100000 1.2681030000 0.2121870000 0.1401850000 1.2322180000 1.2465180000 108902302 0 1786634240 3.9728412628 4.2461037636 6.2330222130 330 13.1600000000 0.0070643243 0.0054397607 0.0076627689 0.0078665423 2.7605800000 1.2669410000 0.2690650000 0.0000050000 1.2143350000 0.0083010000 108903976 0 1784745984 3.9709384441 4.2463316917 6.2410817146 331 13.2000000000 0.0071178414 0.0054448304 0.0076627689 0.0078550393 2.8732020000 1.2708780000 0.2585650000 0.1378660000 1.1956030000 0.0082420000 108905650 0 1786142720 3.9692430496 4.2469496727 6.2511324883 332 13.2400000000 0.0072558019 0.0054502851 0.0076627689 0.0078453212 2.7215510000 1.2749930000 0.2467920000 0.0000040000 1.1896380000 0.0081920000 108907324 0 1785491456 3.9674959183 4.2475519180 6.2597260475 333 13.2800000000 0.0072096349 0.0054555685 0.0076627689 0.0078345602 4.0176820000 1.2664790000 0.2579420000 0.1354290000 1.1673680000 1.1885460000 108908998 0 1786904576 3.9653933048 4.2477545738 6.2690534592 334 13.3200000000 0.0072346549 0.0054608951 0.0076627689 0.0078233388 2.7459370000 1.2741650000 0.3066270000 0.0000040000 1.1543910000 0.0086450000 108910672 0 1784762368 3.9631817341 4.2476758957 6.2770218849 335 13.3600000000 0.0072150007 0.0054661312 0.0076627689 0.0078118017 2.7668680000 1.2709710000 0.2114510000 0.1333570000 1.1409390000 0.0081840000 108912346 0 1786142720 3.9611356258 4.2486381531 6.2856168747 336 13.4000000000 0.0072189872 0.0054713480 0.0076627689 0.0078002079 2.6561530000 1.2691560000 0.2588320000 0.0000030000 1.1179820000 0.0081870000 108914020 0 1785491456 3.9596889019 4.2505207062 6.2934331894 337 13.4400000000 0.0072143795 0.0054765202 0.0076627689 0.0077988643 3.8400260000 1.2717410000 0.2118610000 0.1302920000 1.1056940000 1.1184640000 108915694 0 1786888192 3.9580142498 4.2529163361 6.3008594513 338 13.4800000000 0.0072399084 0.0054817374 0.0076627689 0.0078049492 2.5724980000 1.2703750000 0.2117740000 0.0000030000 1.0801630000 0.0081950000 108917368 0 1784729600 3.9562518597 4.2545413971 6.3070588112 339 13.5200000000 0.0072447229 0.0054869379 0.0076627689 0.0078208700 2.7327520000 1.2763660000 0.2576860000 0.1277500000 1.0607110000 0.0082410000 108919042 0 1786404864 3.9538493156 4.2545394897 6.3125114441 340 13.5600000000 0.0072507169 0.0054921255 0.0076627689 0.0078173312 2.5821590000 1.2689210000 0.2579840000 0.0000040000 1.0450540000 0.0082040000 108920716 0 1785516032 3.9514639378 4.2548909187 6.3176636696 341 13.6000000000 0.0072872741 0.0054973899 0.0076627689 0.0078106923 3.7430350000 1.2778000000 0.2576130000 0.1253560000 1.0303170000 1.0498670000 108922390 0 1787031552 3.9493308067 4.2552785873 6.3225140572 342 13.6400000000 0.0072570872 0.0055025352 0.0076627689 0.0078023378 2.5665860000 1.2686580000 0.2735890000 0.0000040000 1.0141060000 0.0082490000 108924064 0 1784872960 3.9472148418 4.2555971146 6.3280315399 343 13.6800000000 0.0073236814 0.0055078446 0.0076627689 0.0077913427 2.6480320000 1.2678700000 0.2480910000 0.1234670000 0.9983600000 0.0082360000 108925738 0 1786380288 3.9453268051 4.2559208870 6.3327622414 344 13.7200000000 0.0073504359 0.0055132010 0.0076627689 0.0077801239 2.5428570000 1.2924170000 0.2578150000 0.0000040000 0.9824470000 0.0082060000 108927412 0 1785618432 3.9442799091 4.2575616837 6.3382978439 345 13.7600000000 0.0073706242 0.0055185848 0.0076627689 0.0077721946 3.6103890000 1.2724900000 0.2681300000 0.1211990000 0.9629700000 0.9835440000 108929086 0 1787031552 3.9424061775 4.2574424744 6.3437123299 346 13.8000000000 0.0073606237 0.0055239087 0.0076627689 0.0077664018 2.4387450000 1.2691860000 0.2119800000 0.0000040000 0.9473570000 0.0082100000 108930760 0 1784872960 3.9407672882 4.2572979927 6.3487062454 347 13.8400000000 0.0073113427 0.0055290598 0.0076627689 0.0077556310 2.6009090000 1.2727510000 0.2588910000 0.1192860000 0.9397100000 0.0082220000 108932434 0 1786380288 3.9383950233 4.2558760643 6.3533043861 348 13.8800000000 0.0072756214 0.0055340786 0.0076627689 0.0077450929 2.5360370000 1.2974320000 0.3059030000 0.0000030000 0.9224210000 0.0082480000 108934108 0 1785618432 3.9378304482 4.2580494881 6.3590946198 349 13.9200000000 0.0072617154 0.0055390289 0.0076627689 0.0077421653 3.4334950000 1.2705990000 0.2010070000 0.1173820000 0.9140870000 0.9283700000 108935782 0 1787142144 3.9361925125 4.2576866150 6.3648004532 350 13.9600000000 0.0072434186 0.0055438986 0.0076627689 0.0077340608 2.4827650000 1.2740580000 0.3047050000 0.0000040000 0.8937360000 0.0082040000 108937456 0 1784872960 3.9341740608 4.2562904358 6.3736276627 351 14.0000000000 0.0070969337 0.0055483232 0.0076627689 0.0077238962 2.6051450000 1.2736710000 0.3222270000 0.1154620000 0.8834790000 0.0081940000 108939130 0 1786642432 3.9339237213 4.2568340302 6.3782744408 352 14.0400000000 0.0070985453 0.0055527272 0.0076627689 0.0077156438 2.4155820000 1.2725950000 0.2576930000 0.0000040000 0.8748960000 0.0082420000 108940804 0 1784500224 3.9333453178 4.2564272881 6.3830418587 353 14.0800000000 0.0070973034 0.0055571028 0.0076627689 0.0077047202 3.5132730000 1.2703570000 0.3654270000 0.1148400000 0.8706060000 0.8899560000 108942478 0 1785888768 3.9330096245 4.2554168701 6.3873362541 354 14.1200000000 0.0071167722 0.0055615086 0.0076627689 0.0076938476 2.4193110000 1.2737490000 0.2702240000 0.0000040000 0.8650570000 0.0082040000 108944152 0 1787777024 3.9333386421 4.2559657097 6.3921685219 355 14.1600000000 0.0071326909 0.0055659345 0.0076627689 0.0076833601 2.5305230000 1.2794020000 0.2680900000 0.1140760000 0.8584470000 0.0083570000 108945826 0 1784889344 3.9328324795 4.2545471191 6.3969006538 356 14.2000000000 0.0070842579 0.0055701994 0.0076627689 0.0076747821 2.4435850000 1.2742080000 0.3050910000 0.0000030000 0.8539590000 0.0082390000 108947500 0 1786396672 3.9331068993 4.2543325424 6.4015531540 357 14.2400000000 0.0070021180 0.0055742104 0.0076627689 0.0076644649 3.3626940000 1.2771200000 0.2591290000 0.1130550000 0.8463900000 0.8649140000 108949174 0 1785524224 3.9333889484 4.2547664642 6.4071655273 358 14.2800000000 0.0070239045 0.0055782598 0.0076627689 0.0076544865 2.3854050000 1.2705790000 0.2598910000 0.0000040000 0.8445610000 0.0082670000 108950848 0 1787031552 3.9331119061 4.2533917427 6.4125437737 359 14.3200000000 0.0070107710 0.0055822501 0.0076627689 0.0076453076 2.4912990000 1.2729350000 0.2607700000 0.1123940000 0.8349270000 0.0081890000 108952522 0 1784619008 3.9324841499 4.2515754700 6.4179844856 360 14.3600000000 0.0069696219 0.0055861039 0.0076627689 0.0076369454 2.4352420000 1.2702400000 0.3182340000 0.0000040000 0.8364050000 0.0082240000 108954196 0 1786269696 3.9323134422 4.2502422333 6.4240989685 361 14.4000000000 0.0069768042 0.0055899563 0.0076627689 0.0076334856 3.3335550000 1.2747820000 0.2707470000 0.1119640000 0.8270260000 0.8469180000 108955870 0 1785872384 3.9322104454 4.2500591278 6.4305858612 362 14.4400000000 0.0069821794 0.0055938022 0.0076627689 0.0076273309 2.3322820000 1.2680860000 0.2307670000 0.0000050000 0.8231520000 0.0082100000 108957544 0 1787523072 3.9322147369 4.2502670288 6.4370932579 363 14.4800000000 0.0069857878 0.0055976369 0.0076627689 0.0076171635 2.5259920000 1.2692960000 0.3205300000 0.1113960000 0.8144410000 0.0081860000 108959218 0 1785237504 3.9323682785 4.2511520386 6.4442567825 364 14.5200000000 0.0069812750 0.0056014381 0.0076627689 0.0076075360 2.4502720000 1.2716410000 0.3590520000 0.0000050000 0.8092860000 0.0081650000 108960892 0 1786785792 3.9320137501 4.2504825592 6.4514527321 365 14.5600000000 0.0070006009 0.0056052714 0.0076627689 0.0075974210 3.4176160000 1.2718040000 0.4054900000 0.1111450000 0.8040960000 0.8230240000 108962566 0 1784610816 3.9314577579 4.2495641708 6.4584574699 366 14.6000000000 0.0070107733 0.0056091116 0.0076627689 0.0075870420 2.4009920000 1.2741660000 0.3184200000 0.0000040000 0.7981290000 0.0081430000 108964240 0 1786142720 3.9313700199 4.2504720688 6.4662842751 367 14.6400000000 0.0070817950 0.0056131243 0.0076627689 0.0075768468 2.5055720000 1.2717870000 0.3186280000 0.1110850000 0.7939170000 0.0080230000 108965914 0 1785380864 3.9314548969 4.2514376640 6.4735078812 368 14.6800000000 0.0071296813 0.0056172454 0.0076627689 0.0075691365 2.3754340000 1.2788940000 0.2917040000 0.0000050000 0.7946430000 0.0079650000 108967588 0 1787031552 3.9312844276 4.2519574165 6.4812521935 369 14.7200000000 0.0071361098 0.0056213616 0.0076627689 0.0075689496 3.4356310000 1.2761440000 0.4385830000 0.1113460000 0.7918340000 0.8155440000 108969262 0 1784635392 3.9305109978 4.2516884804 6.4886808395 370 14.7600000000 0.0071625384 0.0056255269 0.0076627689 0.0075670590 2.4275070000 1.2739650000 0.3562320000 0.0000050000 0.7871900000 0.0079560000 108970936 0 1786142720 3.9303269386 4.2520580292 6.4966125488 371 14.8000000000 0.0071894312 0.0056297423 0.0076627689 0.0075613587 2.4412870000 1.2715320000 0.2623940000 0.1112680000 0.7860150000 0.0079190000 108972610 0 1785380864 3.9303123951 4.2517518997 6.5037527084 372 14.8400000000 0.0071969805 0.0056339553 0.0076627689 0.0075576563 2.3715340000 1.2653310000 0.3057420000 0.0000040000 0.7904100000 0.0078400000 108974284 0 1787031552 3.9301071167 4.2512269020 6.5107831955 373 14.8800000000 0.0072060931 0.0056381701 0.0076627689 0.0075583781 3.2179690000 1.2738250000 0.2150460000 0.1119770000 0.7952140000 0.8197170000 108975958 0 1785126912 3.9299986362 4.2509851456 6.5180435181 374 14.9200000000 0.0072514424 0.0056424837 0.0076627689 0.0075551127 2.3874310000 1.2708240000 0.3039460000 0.0000050000 0.8026900000 0.0078060000 108977632 0 1786777600 3.9298830032 4.2503099442 6.5252370834 375 14.9600000000 0.0072938399 0.0056468873 0.0076627689 0.0075578553 2.5426110000 1.2981550000 0.3022430000 0.1134320000 0.8181310000 0.0084090000 108979306 0 1784635392 3.9301724434 4.2499403954 6.5321822166 376 15.0000000000 0.0073193358 0.0056513353 0.0076627689 0.0075573566 2.6266530000 1.2695680000 0.5214570000 0.0000050000 0.8257130000 0.0077540000 108980980 0 1786126336 3.9311859608 4.2513103485 6.5395946503 377 15.0400000000 0.0073556160 0.0056558560 0.0076627689 0.0075502890 3.3644190000 1.2707490000 0.2483600000 0.1157330000 0.8577090000 0.8697000000 108982654 0 1788055552 3.9335205555 4.2523975372 6.5526885986 378 15.0800000000 0.0074648526 0.0056606417 0.0076627689 0.0075403540 2.3893460000 1.2680130000 0.2471590000 0.0000040000 0.8642280000 0.0077710000 108984328 0 1785372672 3.9355585575 4.2536468506 6.5589942932 379 15.1200000000 0.0074539180 0.0056653733 0.0076627689 0.0075304365 2.5657200000 1.3069030000 0.2582090000 0.1180390000 0.8724520000 0.0078510000 108986002 0 1786896384 3.9374108315 4.2540788651 6.5646796227 380 15.1600000000 0.0075074434 0.0056702208 0.0076627689 0.0075216520 2.4141940000 1.2726670000 0.2485250000 0.0000050000 0.8828220000 0.0078760000 108987676 0 1784762368 3.9402046204 4.2551727295 6.5701074600 381 15.2000000000 0.0075301253 0.0056751025 0.0076627689 0.0075118984 3.7378650000 1.2969410000 0.5168710000 0.1191370000 0.8911740000 0.9115240000 108989350 0 1786269696 3.9425880909 4.2561450005 6.5751838684 382 15.2400000000 0.0075547704 0.0056800231 0.0076627689 0.0075032375 2.4233590000 1.2656660000 0.2398140000 0.0000050000 0.9078150000 0.0078230000 108991024 0 1785651200 3.9448330402 4.2565097809 6.5799937248 383 15.2800000000 0.0076007764 0.0056850381 0.0076627689 0.0074940351 2.5639610000 1.2712610000 0.2502710000 0.1208400000 0.9114740000 0.0078890000 108992698 0 1787158528 3.9475266933 4.2574987411 6.5845751762 384 15.3200000000 0.0076105674 0.0056900525 0.0076627689 0.0074843383 2.4725950000 1.2724770000 0.2606730000 0.0000050000 0.9293660000 0.0079210000 108994372 0 1784729600 3.9503438473 4.2581462860 6.5884013176 385 15.3600000000 0.0076878355 0.0056952415 0.0076878355 0.0074755962 3.5701810000 1.2964380000 0.2516940000 0.1227100000 0.9401720000 0.9568970000 108996046 0 1786396672 3.9529061317 4.2577929497 6.5909423828 386 15.4000000000 0.0076856571 0.0057003980 0.0076878355 0.0074732034 2.4898250000 1.2748090000 0.2527150000 0.0000040000 0.9520410000 0.0079750000 108997720 0 1785651200 3.9559402466 4.2583465576 6.5931320190 387 15.4400000000 0.0077194255 0.0057056152 0.0077194255 0.0074750890 2.6682850000 1.2673520000 0.2988520000 0.1251300000 0.9665690000 0.0079830000 108999394 0 1787142144 3.9596500397 4.2604770660 6.5953454971 388 15.4800000000 0.0077018975 0.0057107602 0.0077194255 0.0074661091 2.5319280000 1.2744110000 0.2571880000 0.0000050000 0.9898320000 0.0081810000 109001068 0 1784762368 3.9626536369 4.2616333961 6.5963912010 389 15.5200000000 0.0077023325 0.0057158799 0.0077194255 0.0074573060 3.6834650000 1.2908180000 0.2122340000 0.1282520000 1.0123190000 1.0376350000 109002742 0 1786388480 3.9652695656 4.2617406845 6.5973954201 390 15.5600000000 0.0076882304 0.0057209373 0.0077194255 0.0074478400 2.5582950000 1.2651090000 0.2487730000 0.0000050000 1.0339030000 0.0081800000 109004416 0 1785634816 3.9691381454 4.2647838593 6.5986447334 391 15.6000000000 0.0076335049 0.0057258287 0.0077194255 0.0074552403 2.7266640000 1.2675350000 0.2591150000 0.1312850000 1.0581220000 0.0083030000 109006090 0 1787039744 3.9722745419 4.2649917603 6.5999870300 392 15.6400000000 0.0076483279 0.0057307331 0.0077194255 0.0074466717 2.6162510000 1.2693740000 0.2588050000 0.0000040000 1.0775110000 0.0082380000 109007764 0 1785110528 3.9751212597 4.2647948265 6.6003880501 393 15.6800000000 0.0075890552 0.0057354616 0.0077194255 0.0074374410 3.8959420000 1.2675530000 0.2601610000 0.1347850000 1.1086310000 1.1225150000 109009438 0 1786793984 3.9771900177 4.2632145882 6.6010417938 394 15.7200000000 0.0076347082 0.0057402820 0.0077194255 0.0074293456 2.6682500000 1.2645740000 0.2596020000 0.0000040000 1.1334670000 0.0082000000 109011112 0 1784745984 3.9792432785 4.2614583969 6.6020536423 395 15.7600000000 0.0076740584 0.0057451777 0.0077194255 0.0074314234 2.8555220000 1.2740750000 0.2710430000 0.1385610000 1.1612160000 0.0082740000 109012786 0 1786269696 3.9825804234 4.2619152069 6.6026530266 396 15.8000000000 0.0076937070 0.0057500982 0.0077194255 0.0074259848 2.7354160000 1.2707680000 0.2601130000 0.0000050000 1.1940430000 0.0081880000 109014460 0 1785491456 3.9863536358 4.2621889114 6.6028771400 397 15.8400000000 0.0076584839 0.0057549052 0.0077194255 0.0074289457 4.1378360000 1.2688610000 0.2594000000 0.1423740000 1.2213020000 1.2435070000 109016134 0 1787015168 3.9892146587 4.2613630295 6.6028413773 398 15.8800000000 0.0076428894 0.0057596489 0.0077194255 0.0074238326 2.8093830000 1.2757130000 0.2599370000 0.0000050000 1.2630420000 0.0082460000 109017808 0 1784635392 3.9921364784 4.2595458031 6.6021585464 399 15.9200000000 0.0076055545 0.0057642752 0.0077194255 0.0074159751 2.9209060000 1.2707360000 0.2126880000 0.1463900000 1.2805660000 0.0081720000 109019482 0 1786380288 3.9966549873 4.2611703873 6.6007132530 400 15.9600000000 0.0075764745 0.0057688057 0.0077194255 0.0074089479 2.8412370000 1.2718280000 0.2594880000 0.0000040000 1.2989740000 0.0084720000 109021156 0 1785516032 4.0009775162 4.2621760368 6.6008901596 401 16.0000000000 0.0075333454 0.0057732061 0.0077194255 0.0074035393 4.3604350000 1.2717070000 0.2593300000 0.1505550000 1.3273510000 1.3491420000 109022830 0 1787142144 4.0053119659 4.2625432014 6.6012797356 402 16.0400000000 0.0075439289 0.0057776109 0.0077194255 0.0073951350 2.8471900000 1.2711080000 0.2119870000 0.0000040000 1.3535090000 0.0081890000 109024504 0 1784745984 4.0108447075 4.2631597519 6.6009812355 403 16.0800000000 0.0075731566 0.0057820663 0.0077194255 0.0073896557 3.0617940000 1.2732420000 0.2569140000 0.1547450000 1.3664260000 0.0081010000 109026178 0 1786507264 4.0154662132 4.2626538277 6.6022620201 404 16.1200000000 0.0076727555 0.0057867462 0.0077194255 0.0073811642 2.9280910000 1.2697580000 0.2548970000 0.0000040000 1.3930050000 0.0080520000 109027852 0 1785618432 4.0204443932 4.2631616592 6.6009855270 405 16.1600000000 0.0078435419 0.0057918247 0.0078435419 0.0073725478 4.5168000000 1.2707710000 0.2078690000 0.1590670000 1.4050240000 1.4717130000 109029526 0 1787142144 4.0258893967 4.2636623383 6.6018996239 406 16.2000000000 0.0080567291 0.0057974033 0.0080567291 0.0073639269 2.9106980000 1.2709450000 0.2060920000 0.0000040000 1.4233560000 0.0078960000 109031200 0 1784872960 4.0318436623 4.2653570175 6.6040358543 407 16.2400000000 0.0081006531 0.0058030624 0.0081006531 0.0073561865 3.0846390000 1.2759100000 0.1929070000 0.1658520000 1.4396900000 0.0079100000 109032874 0 1786507264 4.0370230675 4.2662658691 6.6059393883 408 16.2800000000 0.0081569226 0.0058088317 0.0081569226 0.0073589622 2.9948610000 1.2739340000 0.2454150000 0.0000040000 1.4652480000 0.0078600000 109034548 0 1785634816 4.0423245430 4.2668743134 6.6086673737 409 16.3200000000 0.0081139896 0.0058144678 0.0081569226 0.0073620638 4.7644570000 1.2769420000 0.2521620000 0.1729980000 1.4800040000 1.5799650000 109036222 0 1787523072 4.0489864349 4.2704229355 6.6114912033 410 16.3600000000 0.0082096523 0.0058203097 0.0082096523 0.0073533156 3.0284250000 1.2780350000 0.2400910000 0.0000050000 1.5002760000 0.0075830000 109037896 0 1784770560 4.0551881790 4.2735543251 6.6157226562 411 16.3999999990 0.0082468465 0.0058262137 0.0082468465 0.0073473429 3.2221700000 1.2721220000 0.2368390000 0.1823860000 1.5208830000 0.0075520000 109039570 0 1786261504 4.0587201118 4.2723546028 6.6174755096 412 16.4400000000 0.0082164165 0.0058320151 0.0082468465 0.0073632662 3.0805440000 1.2942630000 0.2341930000 0.0000050000 1.5422080000 0.0074620000 109041244 0 1785618432 4.0639348030 4.2722005844 6.6239361763 413 16.4800000000 0.0082758823 0.0058379325 0.0082758823 0.0073776265 4.9563610000 1.2776880000 0.2323970000 0.1927230000 1.5584990000 1.6926190000 109042918 0 1786920960 4.0702853203 4.2736711502 6.6310191154 414 16.5200000000 0.0083110565 0.0058439062 0.0083110565 0.0073738807 3.1045380000 1.2782510000 0.2333560000 0.0000040000 1.5830720000 0.0074290000 109044592 0 1784872960 4.0751180649 4.2716112137 6.6345601082 415 16.5599999990 0.0084124431 0.0058500954 0.0084124431 0.0073886387 3.3301800000 1.2721080000 0.2415420000 0.2011230000 1.6054910000 0.0074700000 109046266 0 1786253312 4.0783305168 4.2659163475 6.6401190758 416 16.6000000000 0.0084734894 0.0058564017 0.0084734894 0.0074715498 3.1379400000 1.2706070000 0.2309350000 0.0000040000 1.6265280000 0.0074230000 109047940 0 1785618432 4.0846705437 4.2659611702 6.6458311081 417 16.6400000000 0.0085199438 0.0058627891 0.0085199438 0.0075049679 5.1442990000 1.2703720000 0.2330800000 0.2076740000 1.6406050000 1.7900540000 109049614 0 1787031552 4.0909886360 4.2676324844 6.6474504471 418 16.6800000000 0.0085936869 0.0058693223 0.0085936869 0.0075096532 3.1862270000 1.2784350000 0.2302190000 0.0000040000 1.6677370000 0.0073610000 109051288 0 1784872960 4.0932092667 4.2645311356 6.6467661858 419 16.7199999990 0.0087128561 0.0058761088 0.0087128561 0.0075417747 3.4170740000 1.2689130000 0.2374680000 0.2138140000 1.6869840000 0.0073440000 109052962 0 1786269696 4.1010608673 4.2676153183 6.6524896622 420 16.7600000000 0.0087171048 0.0058828731 0.0087171048 0.0075331530 3.2181940000 1.2732180000 0.2300550000 0.0000040000 1.7050270000 0.0073880000 109054636 0 1785643008 4.1084156036 4.2703595161 6.6524300575 421 16.8000000000 0.0088086836 0.0058898227 0.0088086836 0.0075443556 5.3405440000 1.2721300000 0.2437380000 0.2188530000 1.7266110000 1.8767560000 109056310 0 1787031552 4.1123614311 4.2659273148 6.6533546448 422 16.8400000000 0.0089181960 0.0058969990 0.0089181960 0.0075418085 3.2796490000 1.2774150000 0.2289680000 0.0000040000 1.7634080000 0.0073590000 109057984 0 1784872960 4.1212506294 4.2593774796 6.6553716660 423 16.8799999990 0.0088921823 0.0059040798 0.0089181960 0.0075381471 3.5051950000 1.2736220000 0.2240740000 0.2250680000 1.7726350000 0.0072990000 109059658 0 1786269696 4.1283082962 4.2582983971 6.6553301811 424 16.9200000000 0.0087310262 0.0059107471 0.0089181960 0.0075297762 3.3020460000 1.2719670000 0.2365880000 0.0000050000 1.7837160000 0.0072580000 109061332 0 1785507840 4.1335697174 4.2552947998 6.6530423164 425 16.9600000000 0.0085994247 0.0059170734 0.0089181960 0.0075293328 5.5411940000 1.2772350000 0.2739700000 0.2283170000 1.7861620000 1.9730260000 109063006 0 1787269120 4.1412768364 4.2557783127 6.6503987312 426 17.0000000000 0.0086050453 0.0059233832 0.0089181960 0.0075216692 3.3721900000 1.2801660000 0.2750110000 0.0000040000 1.8070990000 0.0073100000 109064680 0 1784872960 4.1501483917 4.2558650970 6.6496934891 427 17.0400000000 0.0086005945 0.0059296530 0.0089181960 0.0075197293 3.6644470000 1.2680620000 0.3429390000 0.2309940000 1.8126280000 0.0072860000 109066354 0 1786396672 4.1560244560 4.2520909309 6.6452260017 428 17.0800000000 0.0086204102 0.0059359398 0.0089181960 0.0075115350 3.4242450000 1.2716750000 0.3137740000 0.0000040000 1.8289250000 0.0072570000 109068028 0 1785618432 4.1657738686 4.2503361702 6.6419091225 429 17.1200000000 0.0084286584 0.0059417504 0.0089181960 0.0075047274 5.7033880000 1.2725410000 0.3404510000 0.2347440000 1.8233140000 2.0298700000 109069702 0 1787277312 4.1761202812 4.2491674423 6.6403446198 430 17.1600000000 0.0087202508 0.0059482120 0.0089181960 0.0075022604 3.5093110000 1.2737200000 0.3909160000 0.0000040000 1.8349890000 0.0071850000 109071376 0 1784856576 4.1845679283 4.2454924583 6.6335859299 431 17.2000000000 0.0088937087 0.0059550461 0.0089181960 0.0074936321 3.6684290000 1.2780120000 0.3103280000 0.2353330000 1.8349740000 0.0072350000 109073050 0 1786396672 4.1941518784 4.2412075996 6.6301689148 432 17.2400000000 0.0090794573 0.0059622785 0.0090794573 0.0074924093 3.6105840000 1.2711920000 0.4702120000 0.0000040000 1.8594790000 0.0071590000 109074724 0 1785491456 4.2063007355 4.2399358749 6.6254606247 433 17.2800000000 0.0088274963 0.0059688957 0.0090794573 0.0074852145 5.6882500000 1.2713820000 0.2314000000 0.2381390000 1.8653480000 2.0793810000 109076398 0 1787142144 4.2174706459 4.2383785248 6.6197938919 434 17.3200000000 0.0087692654 0.0059753481 0.0090794573 0.0074766432 3.5839560000 1.2702610000 0.4248390000 0.0000050000 1.8792080000 0.0071030000 109078072 0 1784872960 4.2272243500 4.2337832451 6.6112680435 435 17.3600000000 0.0087260501 0.0059816716 0.0090794573 0.0074880429 3.8216700000 1.2711200000 0.4211260000 0.2398300000 1.8798670000 0.0070800000 109079746 0 1786396672 4.2401418686 4.2329711914 6.6059007645 436 17.4000000000 0.0086771818 0.0059878540 0.0090794573 0.0074933085 3.4861390000 1.2776690000 0.3080610000 0.0000040000 1.8907490000 0.0070910000 109081420 0 1785618432 4.2560286522 4.2366919518 6.5988845825 437 17.4400000000 0.0087483181 0.0059941708 0.0090794573 0.0074908415 5.8798390000 1.2722440000 0.3470690000 0.2478860000 1.8862460000 2.1238130000 109083094 0 1787277312 4.2733974457 4.2422451973 6.5902757645 438 17.4800000000 0.0087195002 0.0060003930 0.0090794573 0.0075952736 3.5534420000 1.2757050000 0.3843930000 0.0000040000 1.8836860000 0.0070500000 109084768 0 1784619008 4.2867550850 4.2435059547 6.5822343826 439 17.5200000000 0.0085875550 0.0060062863 0.0090794573 0.0077365647 3.8302080000 1.2708920000 0.4225660000 0.2395030000 1.8875800000 0.0071060000 109086442 0 1786126336 4.2942094803 4.2380313873 6.5713586807 440 17.5600000000 0.0085441396 0.0060120542 0.0090794573 0.0077660244 3.5619870000 1.2698080000 0.3860970000 0.0000050000 1.8964970000 0.0070360000 109088116 0 1788030976 4.3001880646 4.2294182777 6.5629100800 441 17.6000000000 0.0086300829 0.0060179907 0.0090794573 0.0077624536 6.0269710000 1.2722220000 0.4584960000 0.2400930000 1.8961210000 2.1574840000 109089790 0 1784856576 4.3080935478 4.2225933075 6.5553550720 442 17.6400000000 0.0084841857 0.0060235704 0.0090794573 0.0078219983 3.5690720000 1.2669530000 0.3803310000 0.0000050000 1.9120490000 0.0070420000 109091464 0 1786380288 4.3215126991 4.2234792709 6.5462846756 443 17.6800000000 0.0083239563 0.0060287631 0.0090794573 0.0078446397 3.7600530000 1.2760630000 0.3014750000 0.2410170000 1.9317620000 0.0071380000 109093138 0 1785618432 4.3469595909 4.2275595665 6.5288176537 444 17.7200000000 0.0079187891 0.0060330199 0.0090794573 0.0078397457 3.6042110000 1.2698910000 0.3851870000 0.0000050000 1.9391730000 0.0072550000 109094812 0 1787015168 4.3558850288 4.2268161774 6.5169577599 445 17.7600000000 0.0079138950 0.0060372466 0.0090794573 0.0078359007 5.9426670000 1.2755200000 0.2653600000 0.2421990000 1.9445100000 2.2125340000 109096486 0 1784627200 4.3660268784 4.2239899635 6.5088376999 446 17.8000000000 0.0079869479 0.0060416181 0.0090794573 0.0078271082 3.6931100000 1.2716740000 0.4585840000 0.0000050000 1.9531780000 0.0070000000 109098160 0 1786261504 4.3761386871 4.2241845131 6.4997181892 447 17.8400000000 0.0077400990 0.0060454179 0.0090794573 0.0078227270 3.9216580000 1.2695100000 0.4443600000 0.2429330000 1.9552070000 0.0069640000 109099834 0 1788030976 4.3836417198 4.2211713791 6.4918909073 448 17.8800000000 0.0078881392 0.0060495311 0.0090794573 0.0078140484 3.4636030000 1.2691470000 0.2234200000 0.0000050000 1.9613930000 0.0070240000 109101508 0 1784856576 4.3914341927 4.2192277908 6.4844193459 449 17.9200000000 0.0079689426 0.0060538060 0.0090794573 0.0078055459 6.2196840000 1.2766830000 0.4444500000 0.2445160000 1.9696580000 2.2817710000 109103182 0 1786380288 4.3995780945 4.2173810005 6.4764008522 450 17.9600000000 0.0079440009 0.0060580064 0.0090794573 0.0077980712 3.7284080000 1.2740660000 0.4420550000 0.0000050000 2.0026720000 0.0069650000 109104856 0 1785364480 4.4062438011 4.2131805420 6.4706401825 451 18.0000000000 0.0077311913 0.0060617163 0.0090794573 0.0078013402 3.9728240000 1.2773990000 0.4394160000 0.2481130000 1.9982420000 0.0069990000 109106530 0 1786777600 4.4154171944 4.2127289772 6.4646806717 452 18.0400000000 0.0078791380 0.0060657372 0.0090794573 0.0077952941 3.6581940000 1.2681420000 0.3673200000 0.0000050000 2.0131020000 0.0068970000 109108204 0 1785507840 4.4255142212 4.2128386497 6.4581212997 453 18.0800000000 0.0078375591 0.0060696485 0.0090794573 0.0077866749 6.1658780000 1.2700400000 0.2890700000 0.2477300000 2.0185270000 2.3378590000 109109878 0 1787150336 4.4329919815 4.2095122337 6.4515128136 454 18.1200000000 0.0077363825 0.0060733197 0.0090794573 0.0077858903 3.7087470000 1.2687050000 0.4014970000 0.0000050000 2.0289940000 0.0068670000 109111552 0 1784500224 4.4428639412 4.2087306976 6.4458842278 455 18.1600000000 0.0076971794 0.0060768886 0.0090794573 0.0077785275 3.9940970000 1.2679810000 0.4375320000 0.2486270000 2.0304200000 0.0068630000 109113226 0 1785888768 4.4531130791 4.2077531815 6.4406323433 456 18.2000000000 0.0077954773 0.0060806575 0.0090794573 0.0077715964 3.5305380000 1.2695240000 0.2162140000 0.0000050000 2.0353060000 0.0068020000 109114900 0 1787904000 4.4618468285 4.2046122551 6.4341011047 457 18.2400000000 0.0077342293 0.0060842758 0.0090794573 0.0077727003 6.3050140000 1.2742330000 0.3595330000 0.2494170000 2.0391490000 2.3800120000 109116574 0 1784602624 4.4709215164 4.2017898560 6.4291224480 458 18.2800000000 0.0077174995 0.0060878418 0.0090794573 0.0077872276 3.7616630000 1.2726090000 0.4280290000 0.0000040000 2.0514560000 0.0067780000 109118248 0 1786253312 4.4826593399 4.2030367851 6.4261727333 459 18.3200000000 0.0079222871 0.0060918384 0.0090794573 0.0077807204 4.0248730000 1.2762650000 0.4346240000 0.2514090000 2.0529840000 0.0067890000 109119922 0 1785491456 4.4960880280 4.2054381371 6.4199371338 460 18.3600000000 0.0076758079 0.0060952818 0.0090794573 0.0077804991 3.6688820000 1.2711750000 0.3241670000 0.0000040000 2.0639420000 0.0067920000 109121596 0 1786888192 4.5040311813 4.2014441490 6.4160890579 461 18.4000000000 0.0076110540 0.0060985698 0.0090794573 0.0077730252 6.4287510000 1.2689750000 0.4291000000 0.2512340000 2.0700410000 2.4066910000 109123270 0 1784389632 4.5151567459 4.1995701790 6.4131245613 462 18.4400000000 0.0075714472 0.0061017579 0.0090794573 0.0077656473 3.6400250000 1.2689710000 0.2920150000 0.0000040000 2.0695110000 0.0068330000 109124944 0 1785880576 4.5262980461 4.2004556656 6.4074015617 463 18.4800000000 0.0075690649 0.0061049270 0.0090794573 0.0077599624 3.8944930000 1.2706580000 0.2852180000 0.2517680000 2.0772730000 0.0068460000 109126618 0 1787793408 4.5355601311 4.1984210014 6.4012217522 464 18.5200000000 0.0076140771 0.0061081795 0.0090794573 0.0077536943 3.6443830000 1.2672210000 0.2849240000 0.0000040000 2.0825920000 0.0068160000 109128292 0 1784619008 4.5434207916 4.1948924065 6.3982439041 465 18.5600000000 0.0076214573 0.0061114338 0.0090794573 0.0077495534 6.2723120000 1.2752450000 0.2118260000 0.2538630000 2.0878070000 2.4408630000 109129966 0 1786126336 4.5513796806 4.1908006668 6.3951702118 466 18.6000000000 0.0074381633 0.0061142809 0.0090794573 0.0077661180 3.5912810000 1.2668740000 0.2124180000 0.0000050000 2.1024280000 0.0067570000 109131640 0 1788030976 4.5629687309 4.1917657852 6.3920450211 467 18.6400000000 0.0072975825 0.0061168147 0.0090794573 0.0077612619 3.8914040000 1.2753850000 0.2454320000 0.2566690000 2.1044110000 0.0067770000 109133314 0 1784619008 4.5739188194 4.1901316643 6.3893814087 468 18.6800000000 0.0074229334 0.0061196056 0.0090794573 0.0077628785 3.7600220000 1.2682020000 0.3574130000 0.0000050000 2.1248870000 0.0067860000 109134988 0 1786142720 4.5840311050 4.1866521835 6.3885841370 469 18.7200000000 0.0073964875 0.0061223281 0.0090794573 0.0077849489 6.3988120000 1.2695380000 0.2416860000 0.2594020000 2.1307420000 2.4937240000 109136662 0 1785147392 4.5933413506 4.1851148605 6.3872714043 470 18.7600000000 0.0074338629 0.0061251186 0.0090794573 0.0078035372 3.6382480000 1.2664150000 0.2145470000 0.0000040000 2.1479120000 0.0067100000 109138336 0 1784229888 4.6014971733 4.1817908287 6.3867878914 471 18.8000000000 0.0073887184 0.0061278014 0.0090794573 0.0078552561 3.9313030000 1.2667070000 0.2395010000 0.2623830000 2.1533120000 0.0067360000 109140010 0 1785872384 4.6127247810 4.1800227165 6.3846788406 472 18.8400000000 0.0073478334 0.0061303862 0.0090794573 0.0078988672 3.7398750000 1.2730030000 0.2817950000 0.0000040000 2.1753380000 0.0070150000 109141684 0 1787650048 4.6234731674 4.1803021431 6.3816890717 473 18.8800000000 0.0074433326 0.0061331620 0.0090794573 0.0079077749 6.4482940000 1.2771030000 0.2085270000 0.2644830000 2.1688870000 2.5266500000 109143358 0 1784602624 4.6331834793 4.1803708076 6.3776183128 474 18.9200000000 0.0073927585 0.0061358194 0.0090794573 0.0079054120 3.7001610000 1.2673720000 0.2392170000 0.0000040000 2.1840290000 0.0068640000 109145032 0 1785999360 4.6384968758 4.1789021492 6.3700647354 475 18.9600000000 0.0074229557 0.0061385292 0.0090794573 0.0079041138 3.9331130000 1.2652790000 0.2116990000 0.2660980000 2.1803920000 0.0068620000 109146706 0 1787904000 4.6472420692 4.1769795418 6.3679132462 476 19.0000000000 0.0074668420 0.0061413197 0.0090794573 0.0079100028 3.7179420000 1.2740910000 0.2411230000 0.0000050000 2.1931180000 0.0069090000 109148380 0 1784492032 4.6566367149 4.1767740250 6.3651766777 477 19.0400000000 0.0073910477 0.0061439397 0.0090794573 0.0079080865 6.5122570000 1.2678850000 0.2494570000 0.2678350000 2.1974330000 2.5268460000 109150054 0 1786007552 4.6648879051 4.1767964363 6.3572649956 478 19.0800000000 0.0074772048 0.0061467290 0.0090794573 0.0079020448 3.7412570000 1.2706410000 0.2549340000 0.0000050000 2.2057690000 0.0071070000 109151728 0 1787904000 4.6777138710 4.1761651039 6.3603577614 479 19.1200000000 0.0075273761 0.0061496113 0.0090794573 0.0078949726 3.9719610000 1.2664170000 0.2184310000 0.2696230000 2.2073770000 0.0073400000 109153402 0 1784492032 4.6849865913 4.1734147072 6.3590855598 480 19.1600000000 0.0076288655 0.0061526931 0.0090794573 0.0079002060 3.7498720000 1.2657080000 0.2535510000 0.0000050000 2.2203570000 0.0074120000 109155076 0 1785872384 4.6954445839 4.1714668274 6.3609519005 481 19.2000000000 0.0079591516 0.0061564487 0.0090794573 0.0079157926 6.5354600000 1.2628510000 0.2653850000 0.2717720000 2.2059950000 2.5267060000 109156750 0 1787777024 4.7033801079 4.1736927032 6.3550715446 482 19.2400000000 0.0079204720 0.0061601085 0.0090794573 0.0079081120 3.9609630000 1.2658480000 0.4672100000 0.0000040000 2.2175570000 0.0076070000 109158424 0 1784475648 4.7131752968 4.1732668877 6.3562622070 483 19.2800000000 0.0078128465 0.0061635304 0.0090794573 0.0079001429 3.9954920000 1.2643950000 0.2349530000 0.2735710000 2.2121210000 0.0076340000 109160098 0 1785872384 4.7217888832 4.1709227562 6.3550362587 484 19.3200000000 0.0080095157 0.0061673444 0.0090794573 0.0078967715 3.9797970000 1.2686590000 0.4866980000 0.0000050000 2.2141060000 0.0075840000 109161772 0 1787777024 4.7269902229 4.1708064079 6.3505024910 485 19.3600000000 0.0081890719 0.0061715129 0.0090794573 0.0078938708 6.6621720000 1.2714600000 0.3961340000 0.2748420000 2.2024510000 2.5145400000 109163446 0 1784500224 4.7366104126 4.1739530563 6.3460893631 486 19.4000000000 0.0079572638 0.0061751873 0.0090794573 0.0078966927 3.7602940000 1.2635530000 0.2847450000 0.0000040000 2.2015590000 0.0075380000 109165120 0 1785872384 4.7453589439 4.1768641472 6.3437070847 487 19.4400000000 0.0080984822 0.0061791365 0.0090794573 0.0079389604 4.0350200000 1.2770750000 0.2823310000 0.2751610000 2.1901320000 0.0075260000 109166794 0 1787777024 4.7514324188 4.1737442017 6.3408212662 488 19.4800000000 0.0080428831 0.0061829557 0.0090794573 0.0079383130 3.7529890000 1.2746840000 0.2762770000 0.0000040000 2.1917070000 0.0075450000 109168468 0 1784475648 4.7512655258 4.1711091995 6.3332662582 489 19.5200000000 0.0080663227 0.0061868072 0.0090794573 0.0079303350 6.4448240000 1.2667430000 0.2291270000 0.2751020000 2.1898960000 2.4811230000 109170142 0 1785872384 4.7562575340 4.1705827713 6.3289475441 490 19.5600000000 0.0080370177 0.0061905831 0.0090794573 0.0079225105 3.7111220000 1.2710110000 0.2403450000 0.0000040000 2.1893900000 0.0074960000 109171816 0 1787777024 4.7603154182 4.1698513031 6.3206639290 491 19.6000000000 0.0080146668 0.0061942981 0.0090794573 0.0079146481 4.0496150000 1.2679330000 0.3176280000 0.2758140000 2.1780330000 0.0074210000 109173490 0 1784475648 4.7660984993 4.1690673828 6.3163089752 492 19.6400000000 0.0081710005 0.0061983158 0.0090794573 0.0079066789 3.7436910000 1.2701200000 0.2826130000 0.0000050000 2.1805680000 0.0075080000 109175164 0 1785872384 4.7664332390 4.1695756912 6.3046445847 493 19.6800000000 0.0081096422 0.0062021928 0.0090794573 0.0079039696 6.4304750000 1.2678810000 0.2801180000 0.2748480000 2.1524050000 2.4523830000 109176838 0 1787785216 4.7684588432 4.1687507629 6.2936353683 494 19.7200000000 0.0079703191 0.0062057720 0.0090794573 0.0079053869 3.6836490000 1.2679540000 0.2382570000 0.0000040000 2.1672030000 0.0074670000 109178512 0 1784111104 4.7697768211 4.1637020111 6.2863974571 495 19.7600000000 0.0080013890 0.0062093995 0.0090794573 0.0078987683 3.9621410000 1.2719400000 0.2676470000 0.2747350000 2.1373840000 0.0073930000 109180186 0 1785618432 4.7696151733 4.1607680321 6.2757983208 496 19.8000000000 0.0080496566 0.0062131097 0.0090794573 0.0078948874 3.7092000000 1.2744740000 0.2846890000 0.0000050000 2.1397240000 0.0074660000 109181860 0 1787396096 4.7682695389 4.1609444618 6.2685499191 497 19.8400000000 0.0079942551 0.0062166935 0.0090794573 0.0078873837 6.3109740000 1.2653820000 0.2402890000 0.2790110000 2.1241210000 2.3993760000 109183534 0 1784475648 4.7715940475 4.1578450203 6.2622623444 498 19.8800000000 0.0080317790 0.0062203382 0.0090794573 0.0078806702 3.6836920000 1.2730680000 0.2741700000 0.0000040000 2.1260720000 0.0074790000 109185208 0 1785872384 4.7698917389 4.1567616463 6.2513036728 499 19.9200000000 0.0081244577 0.0062241541 0.0090794573 0.0078728314 3.9592700000 1.2787680000 0.2806590000 0.2779860000 2.1116070000 0.0073890000 109186882 0 1787650048 4.7708573341 4.1555547714 6.2447314262 500 19.9600000000 0.0081285667 0.0062279629 0.0090794573 0.0078651817 3.6787370000 1.2682290000 0.2820470000 0.0000040000 2.1180310000 0.0074420000 109188556 0 1784475648 4.7706613541 4.1541810036 6.2344241142 501 20.0000000000 0.0082097463 0.0062319186 0.0090794573 0.0078580479 6.3524530000 1.2677130000 0.3640510000 0.2708350000 2.0973590000 2.3496050000 109190230 0 1786007552 4.7715978622 4.1525206566 6.2237896919 502 20.0400000000 0.0081516560 0.0062357427 0.0090794573 0.0078503053 3.6097750000 1.2680930000 0.2313450000 0.0000050000 2.1001220000 0.0073820000 109191904 0 1787658240 4.7749137878 4.1501407623 6.2177805901 503 20.0800000000 0.0080561284 0.0062393618 0.0090794573 0.0078436046 3.9539220000 1.2679360000 0.3236300000 0.2698310000 2.0816130000 0.0080260000 109193578 0 1784365056 4.7769436836 4.1501746178 6.2049722672 504 20.1200000000 0.0082188575 0.0062432894 0.0090794573 0.0078367393 3.7722210000 1.2682480000 0.4125800000 0.0000040000 2.0809440000 0.0075210000 109195252 0 1785745408 4.7756347656 4.1470985413 6.1944022179 505 20.1600000000 0.0081761554 0.0062471168 0.0090794573 0.0078324304 6.3001650000 1.2749940000 0.3645860000 0.2691340000 2.0665110000 2.3218580000 109196926 0 1787777024 4.7716088295 4.1452097893 6.1814727783 506 20.2000000000 0.0084002577 0.0062513720 0.0090794573 0.0078291050 3.6803320000 1.2713790000 0.3252160000 0.0000050000 2.0734460000 0.0074320000 109198600 0 1784729600 4.7708783150 4.1480145454 6.1724867821 507 20.2400000000 0.0084299045 0.0062556689 0.0090794573 0.0078277108 3.8776730000 1.2746400000 0.2727400000 0.2677730000 2.0521090000 0.0074230000 109200274 0 1786269696 4.7710633278 4.1490311623 6.1611466408 508 20.2800000000 0.0083312467 0.0062597547 0.0090794573 0.0078330097 3.6146570000 1.2694750000 0.2744440000 0.0000040000 2.0603450000 0.0075100000 109201948 0 1785618432 4.7637200356 4.1464433670 6.1515812874 509 20.3200000000 0.0083405832 0.0062638428 0.0090794573 0.0078269280 6.1504850000 1.2661550000 0.2882520000 0.2663400000 2.0466930000 2.2801550000 109203622 0 1787150336 4.7674002647 4.1452651024 6.1419920921 510 20.3600000000 0.0083983978 0.0062680282 0.0090794573 0.0078195303 3.6159940000 1.2684050000 0.2875270000 0.0000050000 2.0496320000 0.0074520000 109205296 0 1785118720 4.7717919350 4.1464409828 6.1271224022 511 20.4000000000 0.0084128818 0.0062722256 0.0090794573 0.0078129917 3.8160250000 1.2697320000 0.2460320000 0.2645320000 2.0252850000 0.0074470000 109206970 0 1786642432 4.7746782303 4.1503462791 6.1147861481 512 20.4400000000 0.0084278202 0.0062764357 0.0090794573 0.0078243824 3.6352950000 1.2756110000 0.3243520000 0.0000040000 2.0249460000 0.0074590000 109208644 0 1784999936 4.7713546753 4.1509451866 6.1018671989 513 20.4800000000 0.0085400315 0.0062808482 0.0090794573 0.0078310505 6.0278130000 1.2678700000 0.2461960000 0.2629000000 2.0077030000 2.2399870000 109251278 0 1786761216 4.7760653496 4.1494555473 6.0906310081 514 20.5200000000 0.0085883271 0.0062853374 0.0090794573 0.0078251554 3.5821020000 1.2760680000 0.2838210000 0.0000040000 2.0117540000 0.0074680000 109336920 0 1784602624 4.7775177956 4.1510009766 6.0790376663 515 20.5600000000 0.0086272741 0.0062898849 0.0090794573 0.0078249484 3.8220640000 1.2689060000 0.2824060000 0.2669840000 1.9930880000 0.0074760000 109338594 0 1786269696 4.7827425003 4.1531772614 6.0666589737 516 20.6000000000 0.0086661801 0.0062944901 0.0090794573 0.0078348553 3.6006480000 1.2674180000 0.3230800000 0.0000050000 1.9995690000 0.0074870000 109340268 0 1785507840 4.7856755257 4.1523671150 6.0530877113 517 20.6400000000 0.0087058339 0.0062991542 0.0090794573 0.0078380949 6.0064800000 1.2704390000 0.2832050000 0.2604980000 1.9755050000 2.2137690000 109341942 0 1787031552 4.7814054489 4.1500425339 6.0542421341 518 20.6800000000 0.0086082993 0.0063036120 0.0090794573 0.0078307826 3.5887840000 1.2645990000 0.3289130000 0.0000040000 1.9846580000 0.0074820000 109343616 0 1785024512 4.7956347466 4.1502017975 6.0334339142 519 20.7200000000 0.0087022800 0.0063082337 0.0090794573 0.0078244443 3.7344450000 1.2703600000 0.2301060000 0.2594270000 1.9638720000 0.0074670000 109345290 0 1786650624 4.7865595818 4.1529798508 6.0375413895 520 20.7600000000 0.0087389937 0.0063129083 0.0090794573 0.0078287823 3.6589400000 1.2747050000 0.4073100000 0.0000050000 1.9662380000 0.0076190000 109346964 0 1784619008 4.7795109749 4.1547760963 6.0377154350 521 20.8000000000 0.0086526861 0.0063173992 0.0090794573 0.0078427154 5.9450130000 1.2672690000 0.2832970000 0.2585500000 1.9557310000 2.1770530000 109348638 0 1786142720 4.7772140503 4.1526002884 6.0301318169 522 20.8400000000 0.0087283254 0.0063220179 0.0090794573 0.0078397156 3.4863620000 1.2717770000 0.2488870000 0.0000050000 1.9550800000 0.0075350000 109350312 0 1785364480 4.7788648605 4.1489825249 6.0235671997 523 20.8800000000 0.0086725960 0.0063265123 0.0090794573 0.0078328228 3.7250340000 1.2657690000 0.2440930000 0.2583990000 1.9461840000 0.0074530000 109351986 0 1786904576 4.7684655190 4.1477622986 6.0293197632 524 20.9200000000 0.0087284269 0.0063310961 0.0090794573 0.0078287616 3.5098540000 1.2711440000 0.2864330000 0.0000040000 1.9416100000 0.0075250000 109353660 0 1785016320 4.7852277756 4.1480784416 6.0077586174 525 20.9600000000 0.0086390404 0.0063354922 0.0090794573 0.0078213121 5.8756400000 1.2753940000 0.2437780000 0.2574510000 1.9284910000 2.1674160000 109355334 0 1786523648 4.7850131989 4.1473379135 6.0027852058 526 21.0000000000 0.0085648829 0.0063397305 0.0090794573 0.0078142977 3.5012550000 1.2724600000 0.2855210000 0.0000050000 1.9326010000 0.0075020000 109357008 0 1784770560 4.7930006981 4.1437888145 5.9897956848 527 21.0400000000 0.0085892733 0.0063439991 0.0090794573 0.0078148008 3.7868560000 1.2754110000 0.3237880000 0.2567050000 1.9202240000 0.0075800000 109358682 0 1786531840 4.7940521240 4.1442999840 5.9806847572 528 21.0800000000 0.0086992718 0.0063484599 0.0090794573 0.0078075900 3.5399230000 1.2688810000 0.3249020000 0.0000040000 1.9354630000 0.0075090000 109360356 0 1785618432 4.7967176437 4.1438465118 5.9758853912 529 21.1200000000 0.0085943127 0.0063527053 0.0090794573 0.0078011337 5.9039510000 1.2688470000 0.3230760000 0.2550200000 1.9099110000 2.1439850000 109362030 0 1787142144 4.8099246025 4.1417236328 5.9553256035 530 21.1600000000 0.0085865688 0.0063569202 0.0090794573 0.0077964699 3.5260660000 1.2663230000 0.3245150000 0.0000040000 1.9244770000 0.0075820000 109363704 0 1784872960 4.8065433502 4.1419487000 5.9535436630 531 21.2000000000 0.0086742733 0.0063612843 0.0090794573 0.0077898267 3.7168660000 1.2707040000 0.2825590000 0.2540210000 1.8988060000 0.0075910000 109365378 0 1786380288 4.8145928383 4.1408424377 5.9383711815 532 21.2400000000 0.0086733615 0.0063656303 0.0090794573 0.0077837490 3.5129790000 1.2701040000 0.3260420000 0.0000040000 1.9060680000 0.0075930000 109367052 0 1785364480 4.8150548935 4.1394972801 5.9303050041 533 21.2800000000 0.0086125117 0.0063698458 0.0090794573 0.0077777009 5.7894360000 1.2706020000 0.2427830000 0.2530320000 1.8997650000 2.1199720000 109368726 0 1787015168 4.8136262894 4.1384301186 5.9252276421 534 21.3200000000 0.0087243263 0.0063742550 0.0090794573 0.0077729123 3.4683830000 1.2681860000 0.2897680000 0.0000040000 1.8996580000 0.0075140000 109370400 0 1784500224 4.8209576607 4.1368837357 5.9098768234 535 21.3600000000 0.0087085627 0.0063786182 0.0090794573 0.0077688082 3.7055140000 1.2671070000 0.2858110000 0.2520780000 1.8897700000 0.0075750000 109372074 0 1786007552 4.8265933990 4.1390342712 5.8949985504 536 21.4000000000 0.0086747212 0.0063829020 0.0090794573 0.0077624735 3.4479520000 1.2652700000 0.2853000000 0.0000040000 1.8866280000 0.0074820000 109373748 0 1787777024 4.8241934776 4.1381821632 5.8911223412 537 21.4400000000 0.0089281052 0.0063876416 0.0090794573 0.0077553365 5.8493100000 1.2752680000 0.3294160000 0.2509340000 1.8733450000 2.1171570000 109375422 0 1784745984 4.8319683075 4.1367268562 5.8738775253 538 21.4800000000 0.0089320196 0.0063923710 0.0090794573 0.0077483365 3.5016220000 1.2757210000 0.3320800000 0.0000040000 1.8831010000 0.0075160000 109377096 0 1786269696 4.8320755959 4.1366691589 5.8656373024 539 21.5200000000 0.0091064228 0.0063974063 0.0091064228 0.0077412694 3.9037030000 1.2686230000 0.5050300000 0.2507910000 1.8684550000 0.0074850000 109378770 0 1785618432 4.8303666115 4.1363644600 5.8576583862 540 21.5600000000 0.0093353633 0.0064028470 0.0093353633 0.0077351902 3.4817630000 1.2686350000 0.3307950000 0.0000050000 1.8715030000 0.0076300000 109380444 0 1787142144 4.8334941864 4.1376256943 5.8430066109 541 21.6000000000 0.0091679934 0.0064079581 0.0093353633 0.0077284444 5.6975420000 1.2697850000 0.2471310000 0.2480040000 1.8531820000 2.0762230000 109382118 0 1784999936 4.8340725899 4.1392955780 5.8337244987 542 21.6400000000 0.0090744635 0.0064128779 0.0093353633 0.0077261271 3.4684040000 1.2683280000 0.3279140000 0.0000040000 1.8613920000 0.0074980000 109383792 0 1786507264 4.8364415169 4.1373152733 5.8208737373 543 21.6800000000 0.0090871481 0.0064178029 0.0093353633 0.0077191087 3.6636740000 1.2692640000 0.2892060000 0.2470000000 1.8472720000 0.0075610000 109385466 0 1785802752 4.8373899460 4.1347479820 5.8156003952 544 21.7200000000 0.0091756051 0.0064228724 0.0093353633 0.0077188737 3.4685250000 1.2741150000 0.3335840000 0.0000050000 1.8498740000 0.0075330000 109387140 0 1787420672 4.8379735947 4.1355772018 5.8053793907 545 21.7600000000 0.0093433652 0.0064282311 0.0093433652 0.0077154261 5.7204300000 1.2741560000 0.2903420000 0.2463300000 1.8500820000 2.0562000000 109388814 0 1785253888 4.8407979012 4.1341834068 5.7932586670 546 21.8000000000 0.0093878480 0.0064336516 0.0093878480 0.0077198365 3.4218260000 1.2669720000 0.2891690000 0.0000040000 1.8547560000 0.0075550000 109390488 0 1786777600 4.8422794342 4.1348481178 5.7865934372 547 21.8400000000 0.0095299333 0.0064393121 0.0095299333 0.0077178628 3.7111560000 1.2715450000 0.3362870000 0.2452220000 1.8472220000 0.0076090000 109392162 0 1784745984 4.8443036079 4.1367683411 5.7748060226 548 21.8800000000 0.0095353927 0.0064449619 0.0095353927 0.0077109655 3.4574350000 1.2677650000 0.3345660000 0.0000040000 1.8441810000 0.0076340000 109393836 0 1786523648 4.8410010338 4.1370596886 5.7714676857 549 21.9200000000 0.0091721350 0.0064499294 0.0095353927 0.0077043889 5.6996760000 1.2758280000 0.2911270000 0.2450230000 1.8382130000 2.0462020000 109395510 0 1785618432 4.8420982361 4.1360774040 5.7651391029 550 21.9600000000 0.0092588747 0.0064550366 0.0095353927 0.0076980025 3.3736600000 1.2722730000 0.2492850000 0.0000040000 1.8411850000 0.0076300000 109397184 0 1787142144 4.8416457176 4.1383662224 5.7583069801 551 22.0000000000 0.0093462095 0.0064602837 0.0095353927 0.0076923374 3.6908070000 1.2710130000 0.3292400000 0.2434900000 1.8360970000 0.0075740000 109398858 0 1784872960 4.8421311378 4.1383805275 5.7502760887 552 22.0400000000 0.0096814390 0.0064661191 0.0096814390 0.0076855627 3.3652710000 1.2686460000 0.2498370000 0.0000040000 1.8358060000 0.0075830000 109400532 0 1786642432 4.8454408646 4.1399774551 5.7419185638 553 22.0800000000 0.0097437240 0.0064720461 0.0097437240 0.0076820600 5.7052580000 1.2791940000 0.3265050000 0.2430280000 1.8210340000 2.0321710000 109402206 0 1785364480 4.8440279961 4.1400318146 5.7395181656 554 22.1200000000 0.0095358109 0.0064775764 0.0097437240 0.0076761067 3.3947720000 1.2665340000 0.2893540000 0.0000040000 1.8279170000 0.0076450000 109403880 0 1787015168 4.8444013596 4.1382098198 5.7326302528 555 22.1600000000 0.0095110284 0.0064830420 0.0097437240 0.0076697823 3.6304880000 1.2725120000 0.2902120000 0.2419250000 1.8147240000 0.0078190000 109405554 0 1784745984 4.8451309204 4.1407427788 5.7245073318 556 22.2000000000 0.0099614635 0.0064892982 0.0099614635 0.0076660393 3.3901940000 1.2683860000 0.2878750000 0.0000040000 1.8228840000 0.0077200000 109407228 0 1786126336 4.8449687958 4.1436367035 5.7156581879 557 22.2400000000 0.0101104947 0.0064957994 0.0101104947 0.0076735902 5.5646710000 1.2666740000 0.2340790000 0.2418710000 1.8063470000 2.0114520000 109408902 0 1785393152 4.8444976807 4.1410202980 5.7114443779 558 22.2800000000 0.0102195879 0.0065024729 0.0102195879 0.0076668460 3.3417310000 1.2688540000 0.2486790000 0.0000050000 1.8132890000 0.0076210000 109410576 0 1784872960 4.8424611092 4.1385378838 5.7053966522 559 22.3200000000 0.0100591136 0.0065088354 0.0102195879 0.0076621223 3.5581400000 1.2678200000 0.2353400000 0.2403220000 1.8037350000 0.0075940000 109412250 0 1786380288 4.8419384956 4.1408176422 5.7001366615 560 22.3600000000 0.0102498857 0.0065155158 0.0102498857 0.0076564949 3.3436750000 1.2681800000 0.2514260000 0.0000040000 1.8130720000 0.0076660000 109413924 0 1785634816 4.8406820297 4.1408824921 5.6967124939 561 22.4000000000 0.0103688817 0.0065223846 0.0103688817 0.0076506553 5.5643020000 1.2663480000 0.2463350000 0.2403180000 1.8050790000 2.0028020000 109415598 0 1787277312 4.8441009521 4.1399006844 5.6882915497 562 22.4400000000 0.0108543811 0.0065300928 0.0108543811 0.0076440521 3.3823430000 1.2693080000 0.2893250000 0.0000050000 1.8126100000 0.0075900000 109417272 0 1784238080 4.8426299095 4.1416478157 5.6850142479 563 22.4800000000 0.0109749753 0.0065379878 0.0109749753 0.0076397101 3.6001120000 1.2669930000 0.2871110000 0.2384510000 1.7966050000 0.0076390000 109418946 0 1785872384 4.8448214531 4.1417379379 5.6756763458 564 22.5200000000 0.0108660320 0.0065456616 0.0109749753 0.0076364336 3.3172920000 1.2730520000 0.2350020000 0.0000040000 1.7981690000 0.0077110000 109420620 0 1787777024 4.8450379372 4.1396203041 5.6699624062 565 22.5600000000 0.0108243609 0.0065532345 0.0109749753 0.0076297626 5.4904450000 1.2665010000 0.2446400000 0.2364010000 1.7802950000 1.9592410000 109422294 0 1784619008 4.8483862877 4.1370391846 5.6585249901 566 22.6000000000 0.0110828988 0.0065612375 0.0110828988 0.0076246149 3.5584680000 1.2679340000 0.4972450000 0.0000050000 1.7821470000 0.0077530000 109423968 0 1785999360 4.8492078781 4.1363353729 5.6516776085 567 22.6400000000 0.0110615585 0.0065691745 0.0110828988 0.0076186952 3.5190680000 1.2669910000 0.2457520000 0.2348210000 1.7603930000 0.0076680000 109425642 0 1788030976 4.8505697250 4.1357679367 5.6452751160 568 22.6800000000 0.0112673128 0.0065774459 0.0112673128 0.0076122618 3.3741780000 1.2680360000 0.3357200000 0.0000040000 1.7592180000 0.0077940000 109427316 0 1784619008 4.8528447151 4.1337852478 5.6363430023 569 22.7200000000 0.0115430858 0.0065861729 0.0115430858 0.0076078624 5.3843670000 1.2740680000 0.2398310000 0.2333840000 1.7341860000 1.8994780000 109428990 0 1786134528 4.8549785614 4.1323876381 5.6257247925 570 22.7600000000 0.0117355119 0.0065952068 0.0117355119 0.0076041896 3.2751560000 1.2738460000 0.2539830000 0.0000050000 1.7361410000 0.0077980000 109430664 0 1787912192 4.8538870811 4.1350898743 5.6158113480 571 22.8000000000 0.0117738787 0.0066042763 0.0117738787 0.0075989932 3.5270550000 1.2681220000 0.2975430000 0.2309560000 1.7191680000 0.0078120000 109432338 0 1784492032 4.8526082039 4.1364183426 5.6073307991 572 22.8400000000 0.0119783245 0.0066136715 0.0119783245 0.0075970959 3.2413470000 1.2694390000 0.2428140000 0.0000040000 1.7178160000 0.0077750000 109434012 0 1785872384 4.8525514603 4.1325974464 5.5988001823 573 22.8800000000 0.0114461659 0.0066221051 0.0119783245 0.0075926255 5.2996390000 1.2753610000 0.2439410000 0.2290970000 1.6974950000 1.8503280000 109435686 0 1787904000 4.8516535759 4.1318726540 5.5901117325 574 22.9200000000 0.0110351853 0.0066297934 0.0119783245 0.0075860809 3.2623680000 1.3012490000 0.2463660000 0.0000050000 1.7034490000 0.0078600000 109437360 0 1784365056 4.8487544060 4.1331419945 5.5837349892 575 22.9600000000 0.0105857030 0.0066366733 0.0119783245 0.0075812714 3.4568040000 1.2719920000 0.2545520000 0.2276170000 1.6913740000 0.0078480000 109439034 0 1785872384 4.8474006653 4.1297044754 5.5744562149 576 23.0000000000 0.0106474170 0.0066436364 0.0119783245 0.0075764921 3.2676280000 1.2701810000 0.2987610000 0.0000040000 1.6873060000 0.0078360000 109440708 0 1787650048 4.8464722633 4.1262736320 5.5671954155 577 23.0400000000 0.0107254563 0.0066507106 0.0119783245 0.0075777390 5.2356070000 1.2770090000 0.2457560000 0.2261000000 1.6740090000 1.8092650000 109442382 0 1784365056 4.8451218605 4.1279501915 5.5576353073 578 23.0800000000 0.0108700981 0.0066580106 0.0119783245 0.0075711920 3.2250480000 1.2756480000 0.2605280000 0.0000050000 1.6775150000 0.0079040000 109444056 0 1786007552 4.8441772461 4.1274199486 5.5480566025 579 23.1200000000 0.0108436160 0.0066652396 0.0119783245 0.0075647423 3.4167990000 1.2703160000 0.2490810000 0.2246270000 1.6614490000 0.0078680000 109445730 0 1787785216 4.8436136246 4.1246709824 5.5389466286 580 23.1600000000 0.0111008566 0.0066728872 0.0119783245 0.0075598762 3.2829150000 1.2689300000 0.3376000000 0.0000040000 1.6650600000 0.0078690000 109447404 0 1784356864 4.8429994583 4.1238985062 5.5285887718 581 23.2000000000 0.0109663615 0.0066802770 0.0119783245 0.0075536816 5.1617230000 1.2759620000 0.2547580000 0.2229420000 1.6396020000 1.7649560000 109449078 0 1785745408 4.8414130211 4.1239871979 5.5193209648 582 23.2400000000 0.0109229442 0.0066875668 0.0119783245 0.0075476538 3.1748080000 1.2741980000 0.2540280000 0.0000040000 1.6351170000 0.0079640000 109450752 0 1787650048 4.8400173187 4.1217613220 5.5082421303 583 23.2800000000 0.0110914102 0.0066951206 0.0119783245 0.0075416219 3.3945410000 1.2695570000 0.2517940000 0.2238590000 1.6379420000 0.0078500000 109452426 0 1784348672 4.8399615288 4.1185798645 5.4987025261 584 23.3200000000 0.0113400426 0.0067030742 0.0119783245 0.0075421008 3.1610730000 1.2717440000 0.2492060000 0.0000050000 1.6286610000 0.0079880000 109454100 0 1785872384 4.8379111290 4.1192889214 5.4873762131 585 23.3600000000 0.0114483321 0.0067111858 0.0119783245 0.0075370203 5.1447310000 1.2781020000 0.3037040000 0.2198050000 1.6133340000 1.7263240000 109455774 0 1787650048 4.8366351128 4.1186108589 5.4759469032 586 23.4000000000 0.0115495780 0.0067194424 0.0119783245 0.0075328304 3.1534670000 1.2762320000 0.2488060000 0.0000050000 1.6169850000 0.0079160000 109457448 0 1784238080 4.8362627029 4.1154193878 5.4648027420 587 23.4400000000 0.0116118724 0.0067277770 0.0119783245 0.0075370279 3.3616310000 1.2718300000 0.2592540000 0.2180970000 1.6010130000 0.0079610000 109459122 0 1785745408 4.8348498344 4.1149101257 5.4552230835 588 23.4800000000 0.0118454034 0.0067364805 0.0119783245 0.0075447891 3.1292310000 1.2717300000 0.2514780000 0.0000050000 1.5945540000 0.0079700000 109460796 0 1787658240 4.8321723938 4.1171689034 5.4275970459 589 23.5200000000 0.0119325211 0.0067453023 0.0119783245 0.0075390303 4.9805200000 1.2741820000 0.2634760000 0.2146950000 1.5654300000 1.6591840000 109462470 0 1784508416 4.8303079605 4.1187047958 5.4177122116 590 23.5600000000 0.0120968865 0.0067543728 0.0120968865 0.0075365471 3.1135240000 1.2745060000 0.2673580000 0.0000050000 1.5600720000 0.0079440000 109464144 0 1786126336 4.8279957771 4.1205081940 5.4060864449 591 23.6000000000 0.0120778531 0.0067633803 0.0120968865 0.0075408106 3.2638240000 1.2666310000 0.2202220000 0.2131750000 1.5523020000 0.0079670000 109465818 0 1788030976 4.8267908096 4.1182136536 5.3948793411 592 23.6400000000 0.0121738436 0.0067725196 0.0121738436 0.0075347130 3.0818280000 1.2717940000 0.2562960000 0.0000050000 1.5420980000 0.0080610000 109467492 0 1785253888 4.8257002831 4.1157250404 5.3807764053 593 23.6800000000 0.0122826770 0.0067818116 0.0122826770 0.0075304147 4.8906740000 1.2764960000 0.2642190000 0.2113760000 1.5271520000 1.6078750000 109469166 0 1786777600 4.8238911629 4.1156997681 5.3681716919 594 23.7200000000 0.0124468366 0.0067913487 0.0124468366 0.0075262191 3.3653150000 1.2777160000 0.5439970000 0.0000050000 1.5318220000 0.0080490000 109470840 0 1784762368 4.8224201202 4.1157155037 5.3562254906 595 23.7600000000 0.0122996606 0.0068006064 0.0124468366 0.0075230408 3.2629790000 1.2717560000 0.2549350000 0.2087730000 1.5158830000 0.0080860000 109472514 0 1786380288 4.8198056221 4.1146788597 5.3472671509 596 23.8000000000 0.0123004187 0.0068098343 0.0124468366 0.0075222995 3.0527820000 1.2685030000 0.2671420000 0.0000050000 1.5054120000 0.0080640000 109474188 0 1785618432 4.8180127144 4.1160445213 5.3343167305 597 23.8400000000 0.0124155506 0.0068192241 0.0124468366 0.0075162667 4.7969550000 1.2675470000 0.2738330000 0.2067650000 1.4886200000 1.5565240000 109475862 0 1787293696 4.8152585030 4.1178212166 5.3236961365 598 23.8800000000 0.0125357322 0.0068287834 0.0125357322 0.0075108590 3.0285430000 1.2682350000 0.2592170000 0.0000040000 1.4893190000 0.0080950000 109477536 0 1784500224 4.8135781288 4.1177158356 5.3099336624 599 23.9200000000 0.0124884667 0.0068382320 0.0125357322 0.0075050046 3.2200810000 1.2769470000 0.2596550000 0.2046940000 1.4670720000 0.0081080000 109479210 0 1786015744 4.8105511665 4.1197004318 5.2997269630 600 23.9600000000 0.0127305342 0.0068480525 0.0127305342 0.0075021042 3.0534660000 1.2763660000 0.3051100000 0.0000060000 1.4602120000 0.0081800000 109480884 0 1787777024 4.8085322380 4.1200265884 5.2883410454 601 24.0000000000 0.0126738502 0.0068577460 0.0127305342 0.0074965171 4.6929070000 1.2661040000 0.2591340000 0.2025410000 1.4541310000 1.5073110000 109482558 0 1784745984 4.8054857254 4.1201286316 5.2780737877 602 24.0400000000 0.0127276797 0.0068674967 0.0127305342 0.0074903715 2.9928330000 1.2711400000 0.2596030000 0.0000050000 1.4504040000 0.0081130000 109484232 0 1786253312 4.8034777641 4.1201486588 5.2654466629 603 24.0800000000 0.0126787480 0.0068771340 0.0127305342 0.0074841985 3.1774450000 1.2695450000 0.2600160000 0.2009130000 1.4352260000 0.0081040000 109485906 0 1785618432 4.8000588417 4.1204471588 5.2565178871 604 24.1200000000 0.0126009611 0.0068866105 0.0127305342 0.0074780008 2.9830540000 1.2700410000 0.2666070000 0.0000040000 1.4345510000 0.0081050000 109487580 0 1787015168 4.7966871262 4.1212267876 5.2485780716 605 24.1600000000 0.0124297719 0.0068957727 0.0127305342 0.0074721873 4.6454250000 1.2721310000 0.2595010000 0.1994730000 1.4244320000 1.4862740000 109489254 0 1784492032 4.7938156128 4.1201357841 5.2399601936 606 24.2000000000 0.0123964176 0.0069048497 0.0127305342 0.0074662234 2.9298040000 1.2709180000 0.2253870000 0.0000050000 1.4217840000 0.0081440000 109490928 0 1785999360 4.7913208008 4.1177244186 5.2324485779 607 24.2400000000 0.0123813711 0.0069138720 0.0127305342 0.0074605022 3.1320180000 1.2881650000 0.2246820000 0.1980470000 1.4093390000 0.0081560000 109492602 0 1787928576 4.7891464233 4.1171088219 5.2197074890 608 24.2800000000 0.0124233942 0.0069229337 0.0127305342 0.0074547346 3.0661660000 1.2715310000 0.3758370000 0.0000050000 1.4070010000 0.0081920000 109494276 0 1784610816 4.7860608101 4.1186356544 5.2109460831 609 24.3200000000 0.0124132680 0.0069319490 0.0127305342 0.0074504654 4.5656560000 1.2724400000 0.2620220000 0.1964610000 1.3894940000 1.4416060000 109495950 0 1785999360 4.7844085693 4.1158614159 5.2019119263 610 24.3600000000 0.0126943002 0.0069413955 0.0127305342 0.0074446522 2.9467580000 1.2752290000 0.2714760000 0.0000050000 1.3881610000 0.0081210000 109497624 0 1787904000 4.7823872566 4.1120867729 5.1934404373 611 24.4000000000 0.0127232904 0.0069508585 0.0127305342 0.0074431763 3.1139480000 1.2682730000 0.2596530000 0.1944270000 1.3796790000 0.0081420000 109499298 0 1784475648 4.7810168266 4.1113605499 5.1798768044 612 24.4400000000 0.0127491951 0.0069603329 0.0127491951 0.0074382681 2.9717540000 1.2713230000 0.3186940000 0.0000040000 1.3699200000 0.0082030000 109500972 0 1785872384 4.7781300545 4.1117691994 5.1706209183 613 24.4800000000 0.0127762444 0.0069698205 0.0127762444 0.0074329127 4.4963230000 1.2752990000 0.2749340000 0.1928130000 1.3559790000 1.3935910000 109502646 0 1787777024 4.7759637833 4.1098222733 5.1632514000 614 24.5200000000 0.0129244057 0.0069795186 0.0129244057 0.0074269546 2.9007060000 1.2705120000 0.2670590000 0.0000040000 1.3512240000 0.0082340000 109504320 0 1784365056 4.7741193771 4.1075258255 5.1500010490 615 24.5600000000 0.0129511068 0.0069892285 0.0129511068 0.0074212953 3.0832210000 1.2722490000 0.2637780000 0.1912800000 1.3439950000 0.0082060000 109505994 0 1785872384 4.7727317810 4.1062316895 5.1416678429 616 24.6000000000 0.0130418455 0.0069990541 0.0130418455 0.0074161344 2.8947710000 1.2776450000 0.2629760000 0.0000050000 1.3422370000 0.0082470000 109507668 0 1787777024 4.7712149620 4.1034417152 5.1305217743 617 24.6400000000 0.0130254915 0.0070088215 0.0130418455 0.0074151300 4.4169410000 1.2695860000 0.2718340000 0.1897600000 1.3297720000 1.3522400000 109509342 0 1784483840 4.7693080902 4.1018404961 5.1196470261 618 24.6800000000 0.0131899007 0.0070188232 0.0131899007 0.0074153943 2.8722820000 1.2740630000 0.2623260000 0.0000050000 1.3238910000 0.0082900000 109511016 0 1785999360 4.7681951523 4.1001267433 5.1067051888 619 24.7200000000 0.0130484644 0.0070285641 0.0131899007 0.0074168373 3.0835830000 1.2770240000 0.3086850000 0.1873030000 1.2986310000 0.0082850000 109512690 0 1787785216 4.7670149803 4.0992531776 5.0915675163 620 24.7600000000 0.0131921778 0.0070385055 0.0131921778 0.0074140967 2.9146360000 1.2705530000 0.3193310000 0.0000040000 1.3127960000 0.0082130000 109514364 0 1784492032 4.7641077042 4.1002211571 5.0825543404 621 24.8000000000 0.0132231070 0.0070484646 0.0132231070 0.0074082529 4.3248080000 1.2771170000 0.2614820000 0.1854320000 1.2842500000 1.3128550000 109516038 0 1785872384 4.7624006271 4.0996932983 5.0722155571 622 24.8400000000 0.0131218582 0.0070582289 0.0132231070 0.0074025275 2.8965900000 1.2743070000 0.3204930000 0.0000050000 1.2897510000 0.0082240000 109517712 0 1787650048 4.7604913712 4.0975770950 5.0613851547 623 24.8800000000 0.0134630194 0.0070685094 0.0134630194 0.0073999028 3.0136030000 1.2696600000 0.2737190000 0.1839200000 1.2742800000 0.0082940000 109519386 0 1784365056 4.7581710815 4.0983438492 5.0503978729 624 24.9200000000 0.0136141619 0.0070789992 0.0136141619 0.0073945764 2.8325160000 1.2737940000 0.2747350000 0.0000040000 1.2719310000 0.0082050000 109521060 0 1785872384 4.7552161217 4.0992355347 5.0391192436 625 24.9600000000 0.0137421861 0.0070896603 0.0137421861 0.0073887855 4.2713240000 1.2777670000 0.2755580000 0.1829630000 1.2532410000 1.2780400000 109522734 0 1787650048 4.7524328232 4.0976366997 5.0290641785 626 25.0000000000 0.0138227772 0.0071004161 0.0138227772 0.0073837419 2.8204010000 1.2711940000 0.2727110000 0.0000040000 1.2644820000 0.0082740000 109524408 0 1784365056 4.7504820824 4.0956211090 5.0196619034 627 25.0400000000 0.0139265070 0.0071113030 0.0139265070 0.0073806081 2.9715720000 1.2717580000 0.2696440000 0.1803250000 1.2379070000 0.0081990000 109526082 0 1785872384 4.7476840019 4.0953240395 5.0092725754 628 25.0800000000 0.0139482012 0.0071221898 0.0139482012 0.0073750582 2.8297750000 1.3013380000 0.2724590000 0.0000060000 1.2439400000 0.0082880000 109527756 0 1787650048 4.7438631058 4.0972185135 4.9996991158 629 25.1200000000 0.0138526466 0.0071328901 0.0139482012 0.0073718317 4.1939420000 1.2742640000 0.2705270000 0.1782430000 1.2191020000 1.2479980000 109529430 0 1784373248 4.7412581444 4.0965361595 4.9936194420 630 25.1600000000 0.0139854988 0.0071437672 0.0139854988 0.0073667257 2.8255840000 1.2699590000 0.3193730000 0.0000050000 1.2242660000 0.0082540000 109531104 0 1785880576 4.7373509407 4.0965852737 4.9841380119 631 25.2000000000 0.0138984472 0.0071544719 0.0139854988 0.0073631875 2.9806050000 1.2764130000 0.3163080000 0.1763590000 1.1995520000 0.0082440000 109532778 0 1787777024 4.7333831787 4.0973820686 4.9755210876 632 25.2400000000 0.0140605019 0.0071653992 0.0140605019 0.0073621338 2.8224620000 1.2875030000 0.3192180000 0.0000060000 1.2037310000 0.0082220000 109534452 0 1784999936 4.7295989990 4.0965003967 4.9697928429 633 25.2800000000 0.0137566812 0.0071758120 0.0140605019 0.0073580041 4.1120820000 1.2763500000 0.2709780000 0.1753000000 1.1800820000 1.2056400000 109536126 0 1786523648 4.7255563736 4.0974745750 4.9597678185 634 25.3200000000 0.0145118870 0.0071873831 0.0145118870 0.0073548448 2.7914870000 1.2773360000 0.3199310000 0.0000060000 1.1821280000 0.0082710000 109537800 0 1785413632 4.7203645706 4.0991883278 4.9509487152 635 25.3600000000 0.0144732827 0.0071988569 0.0145118870 0.0073574598 3.1179320000 1.2681340000 0.5065210000 0.1712310000 1.1598950000 0.0082310000 109539474 0 1787142144 4.7163348198 4.0990581512 4.9454607964 636 25.4000000000 0.0144046089 0.0072101867 0.0145118870 0.0073575789 2.7792760000 1.2800510000 0.3215230000 0.0000050000 1.1656640000 0.0082240000 109541148 0 1784762368 4.7128620148 4.0974082947 4.9364004135 637 25.4400000000 0.0145247839 0.0072216696 0.0145247839 0.0073524469 4.0233960000 1.2698580000 0.2706040000 0.1687760000 1.1473460000 1.1629790000 109542822 0 1786380288 4.7083802223 4.0978665352 4.9292950630 638 25.4800000000 0.0145278377 0.0072331213 0.0145278377 0.0073481237 2.6495990000 1.2678490000 0.2239290000 0.0000060000 1.1458260000 0.0081890000 109544496 0 1785634816 4.7050552368 4.0962104797 4.9213562012 639 25.5200000000 0.0146980351 0.0072448035 0.0146980351 0.0073425354 2.8990170000 1.2738190000 0.3180110000 0.1669480000 1.1282200000 0.0081660000 109546170 0 1787142144 4.6999282837 4.0941734314 4.9154157639 640 25.5600000000 0.0148569457 0.0072566974 0.0148569457 0.0073375574 2.7336050000 1.2660050000 0.3225220000 0.0000040000 1.1330320000 0.0082290000 109547844 0 1785143296 4.6958174706 4.0928068161 4.9091615677 641 25.6000000000 0.0148014389 0.0072684677 0.0148569457 0.0073324831 3.9678400000 1.2699880000 0.2749470000 0.1654600000 1.1158140000 1.1376500000 109549518 0 1786896384 4.6907310486 4.0917210579 4.9027824402 642 25.6400000000 0.0150983576 0.0072806638 0.0150983576 0.0073278334 2.7755970000 1.2718430000 0.3720510000 0.0000040000 1.1194990000 0.0083290000 109551192 0 1784635392 4.6853470802 4.0906453133 4.8976039886 643 25.6800000000 0.0150376027 0.0072927275 0.0150983576 0.0073224312 2.8103800000 1.2650350000 0.2627590000 0.1640770000 1.1064040000 0.0082210000 109552866 0 1786507264 4.6806797981 4.0890107155 4.8911547661 644 25.7200000000 0.0154016260 0.0073053189 0.0154016260 0.0073168487 2.6686250000 1.2706680000 0.2749790000 0.0000040000 1.1108340000 0.0082690000 109554540 0 1785524224 4.6749734879 4.0881247520 4.8858370781 645 25.7600000000 0.0155193228 0.0073180538 0.0155193228 0.0073114098 4.1247050000 1.2636610000 0.4670540000 0.1630590000 1.1046580000 1.1223570000 109556214 0 1787142144 4.6699934006 4.0861492157 4.8794832230 646 25.8000000000 0.0157419927 0.0073310940 0.0157419927 0.0073057842 2.6972910000 1.2602550000 0.3220620000 0.0000050000 1.1028400000 0.0082280000 109557888 0 1784729600 4.6635665894 4.0845699310 4.8753185272 647 25.8400000000 0.0158140268 0.0073442051 0.0158140268 0.0073001959 2.8534110000 1.2682570000 0.3232850000 0.1617180000 1.0880640000 0.0082040000 109559562 0 1786380288 4.6562261581 4.0850596428 4.8696370125 648 25.8800000000 0.0160986781 0.0073577151 0.0160986781 0.0072979135 2.7038230000 1.2864130000 0.3147790000 0.0000050000 1.0904640000 0.0081750000 109561236 0 1785618432 4.6494998932 4.0844326019 4.8649673462 649 25.9200000000 0.0161314923 0.0073712340 0.0161314923 0.0072966633 3.9829020000 1.2664020000 0.3737310000 0.1605350000 1.0784890000 1.0998860000 109562910 0 1787031552 4.6423892975 4.0814542770 4.8599114418 650 25.9600000000 0.0166477300 0.0073855056 0.0166477300 0.0072926494 2.7784260000 1.2584960000 0.4207200000 0.0000040000 1.0871480000 0.0081710000 109564584 0 1784872960 4.6283202171 4.0748252869 4.8507766724 651 26.0000000000 0.0171030648 0.0074004327 0.0171030648 0.0072935114 2.7646640000 1.2603710000 0.2714600000 0.1581060000 1.0625670000 0.0082350000 109566258 0 1786413056 4.6108598709 4.0750327110 4.8402199745 652 26.0400000000 0.0174796674 0.0074158917 0.0174796674 0.0072880437 2.6180540000 1.2640610000 0.2742730000 0.0000050000 1.0676070000 0.0081820000 109567932 0 1785659392 4.6014690399 4.0759034157 4.8341512680 653 26.0800000000 0.0175618734 0.0074314291 0.0175618734 0.0072849813 4.1214270000 1.2599790000 0.5661880000 0.1566430000 1.0538720000 1.0807920000 109569606 0 1787293696 4.5912570953 4.0787196159 4.8294572830 654 26.1200000000 0.0180788543 0.0074477096 0.0180788543 0.0072914475 2.5946230000 1.2563110000 0.2732860000 0.0000060000 1.0528380000 0.0082370000 109571280 0 1784872960 4.5809164047 4.0787196159 4.8255386353 655 26.1600000000 0.0188820194 0.0074651666 0.0188820194 0.0072869330 3.0307110000 1.2555160000 0.5659420000 0.1556980000 1.0413460000 0.0081840000 109572954 0 1786523648 4.5714616776 4.0764088631 4.8187170029 656 26.2000000000 0.0183589794 0.0074817730 0.0188820194 0.0072856147 2.7247130000 1.2584870000 0.4069830000 0.0000050000 1.0470690000 0.0081680000 109574628 0 1785380864 4.5606446266 4.0769591331 4.8152980804 657 26.2400000000 0.0185507629 0.0074986208 0.0188820194 0.0072855821 4.0200250000 1.2645340000 0.5115590000 0.1541830000 1.0315790000 1.0542840000 109576302 0 1786888192 4.5500335693 4.0773582458 4.8115425110 658 26.2800000000 0.0182862971 0.0075150154 0.0188820194 0.0072871601 2.5844980000 1.2591710000 0.2742220000 0.0000060000 1.0388510000 0.0081730000 109577976 0 1784619008 4.5388126373 4.0786695480 4.8072938919 659 26.3200000000 0.0186495762 0.0075319116 0.0188820194 0.0072844975 2.9485910000 1.2553270000 0.5115410000 0.1533390000 1.0161360000 0.0081680000 109579650 0 1786253312 4.5270309448 4.0814943314 4.8037261963 660 26.3600000000 0.0182665028 0.0075481761 0.0188820194 0.0072794728 2.6532440000 1.2971900000 0.3231670000 0.0000040000 1.0206500000 0.0081690000 109581324 0 1785491456 4.5162024498 4.0826301575 4.8006467819 661 26.4000000000 0.0184690747 0.0075646979 0.0188820194 0.0072743633 3.7771420000 1.2631490000 0.3195700000 0.1518420000 1.0061690000 1.0324860000 109582998 0 1786888192 4.5041251183 4.0852246284 4.7965812683 662 26.4400000000 0.0184525084 0.0075811447 0.0188820194 0.0072732831 2.8363850000 1.2595850000 0.5576710000 0.0000060000 1.0069930000 0.0081620000 109584672 0 1784745984 4.4922747612 4.0885891914 4.7951250076 663 26.4800000000 0.0185971279 0.0075977601 0.0188820194 0.0072906583 2.7418530000 1.2601590000 0.3189880000 0.1506190000 0.9999570000 0.0081670000 109586346 0 1786380288 4.4815917015 4.0880451202 4.7914094925 664 26.5200000000 0.0188318212 0.0076146789 0.0188820194 0.0072983873 2.6175060000 1.2859600000 0.3229300000 0.0000050000 0.9964420000 0.0082130000 109588020 0 1785626624 4.4714140892 4.0851073265 4.7854771614 665 26.5600000000 0.0189423878 0.0076317130 0.0189423878 0.0072934719 3.9715590000 1.2619910000 0.5661840000 0.1500310000 0.9839480000 1.0053950000 109589694 0 1787023360 4.4608459473 4.0856447220 4.7824273109 666 26.6000000000 0.0184475686 0.0076479530 0.0189423878 0.0072896522 2.8241390000 1.2585020000 0.5602830000 0.0000050000 0.9930750000 0.0083120000 109591368 0 1784745984 4.4497270584 4.0878591537 4.7795605659 667 26.6400000000 0.0189563669 0.0076649072 0.0189563669 0.0072935325 2.6141390000 1.2597210000 0.2187090000 0.1483260000 0.9752110000 0.0082050000 109593042 0 1786269696 4.4390711784 4.0908708572 4.7775049210 668 26.6800000000 0.0186435152 0.0076813422 0.0189563669 0.0073154961 2.5532890000 1.2901540000 0.2736100000 0.0000050000 0.9772960000 0.0082570000 109594716 0 1785618432 4.4280161858 4.0950160027 4.7747707367 669 26.7200000000 0.0189973302 0.0076982570 0.0189973302 0.0073583707 3.7714580000 1.2597100000 0.4154100000 0.1471920000 0.9617930000 0.9833650000 109596390 0 1787015168 4.4170727730 4.0963926315 4.7714400291 670 26.7600000000 0.0184376314 0.0077142859 0.0189973302 0.0073951497 2.6145150000 1.2663240000 0.3691170000 0.0000050000 0.9669170000 0.0081620000 109598064 0 1784492032 4.4074149132 4.0959873199 4.7691855431 671 26.8000000000 0.0185998529 0.0077305088 0.0189973302 0.0074020639 2.7067960000 1.2672460000 0.3239390000 0.1469050000 0.9564620000 0.0081640000 109599738 0 1785999360 4.3979039192 4.0964074135 4.7653136253 672 26.8400000000 0.0186689571 0.0077467863 0.0189973302 0.0073980115 2.7357040000 1.2994710000 0.4653220000 0.0000050000 0.9586610000 0.0081760000 109601412 0 1787904000 4.3883233070 4.0989894867 4.7611188889 673 26.8800000000 0.0179509260 0.0077619484 0.0189973302 0.0073940406 3.8044440000 1.2618320000 0.4619950000 0.1455230000 0.9570190000 0.9739410000 109603086 0 1784897536 4.3793210983 4.0995278358 4.7584743500 674 26.9200000000 0.0183114931 0.0077776006 0.0189973302 0.0073886276 2.5562500000 1.2651040000 0.3208960000 0.0000040000 0.9580710000 0.0081700000 109604760 0 1786261504 4.3705677986 4.1005640030 4.7541651726 675 26.9600000000 0.0179690477 0.0077926990 0.0189973302 0.0073831929 2.9350860000 1.2710080000 0.5573930000 0.1448730000 0.9495620000 0.0082090000 109606434 0 1785626624 4.3618321419 4.1025319099 4.7519187927 676 27.0000000000 0.0183542073 0.0078083225 0.0189973302 0.0073788669 2.5562930000 1.2662310000 0.3211170000 0.0000050000 0.9565830000 0.0082640000 109608108 0 1787015168 4.3527765274 4.1068391800 4.7479195595 677 27.0400000000 0.0183912776 0.0078239547 0.0189973302 0.0073874688 3.8794970000 1.2701200000 0.5551600000 0.1444880000 0.9419270000 0.9637620000 109609782 0 1784492032 4.3440504074 4.1099672318 4.7461152077 678 27.0800000000 0.0178999491 0.0078388160 0.0189973302 0.0074004220 2.6933810000 1.2662660000 0.4671610000 0.0000050000 0.9476850000 0.0082290000 109611456 0 1786126336 4.3358178139 4.1119489670 4.7436408997 679 27.1200000000 0.0183243807 0.0078542587 0.0189973302 0.0074101932 2.6718190000 1.2654150000 0.3188920000 0.1436920000 0.9314650000 0.0083050000 109613130 0 1787793408 4.3269524574 4.1140775681 4.7392792702 680 27.1600000000 0.0175422132 0.0078685057 0.0189973302 0.0074125111 2.5577740000 1.2855380000 0.3250730000 0.0000050000 0.9348300000 0.0083100000 109614804 0 1784872960 4.3191170692 4.1139750481 4.7356081009 681 27.2000000000 0.0185578149 0.0078842022 0.0189973302 0.0074073079 3.8575200000 1.2672860000 0.5587140000 0.1432560000 0.9285960000 0.9553800000 109616478 0 1786253312 4.3111577034 4.1152124405 4.7306399345 682 27.2400000000 0.0185396932 0.0078998261 0.0189973302 0.0074021954 2.4877680000 1.2719570000 0.2740150000 0.0000060000 0.9294300000 0.0082940000 109618152 0 1785618432 4.3029112816 4.1188330650 4.7266063690 683 27.2800000000 0.0192832034 0.0079164928 0.0192832034 0.0074012946 2.6865290000 1.2828550000 0.3203040000 0.1430920000 0.9278960000 0.0082170000 109619826 0 1787031552 4.2950153351 4.1217131615 4.7213296890 684 27.3200000000 0.0189131983 0.0079325698 0.0192832034 0.0074064687 2.5546010000 1.2977480000 0.3203800000 0.0000050000 0.9241190000 0.0081810000 109621500 0 1784754176 4.2866744995 4.1227931976 4.7175626755 685 27.3600000000 0.0196382497 0.0079496584 0.0196382497 0.0074057889 3.6015630000 1.2688420000 0.3200890000 0.1420650000 0.9241800000 0.9422840000 109623174 0 1786023936 4.2790107727 4.1236166954 4.7111535072 686 27.4000000000 0.0195418298 0.0079665566 0.0196382497 0.0074025476 2.6229550000 1.2709740000 0.4158420000 0.0000050000 0.9237040000 0.0081870000 109624848 0 1787904000 4.2704701424 4.1271314621 4.7058224678 687 27.4400000000 0.0192410555 0.0079829678 0.0196382497 0.0074094122 2.7611190000 1.2758210000 0.4147070000 0.1415130000 0.9166950000 0.0082570000 109626522 0 1784492032 4.2622632980 4.1307024956 4.7007007599 688 27.4800000000 0.0196503345 0.0079999262 0.0196503345 0.0074251223 2.5520490000 1.2978670000 0.3188890000 0.0000050000 0.9229310000 0.0082050000 109628196 0 1785872384 4.2539796829 4.1323890686 4.6947326660 689 27.5200000000 0.0195495505 0.0080166891 0.0196503345 0.0074349455 3.6370370000 1.2757200000 0.3659520000 0.1410960000 0.9148000000 0.9353760000 109629870 0 1787904000 4.2456011772 4.1340522766 4.6892580986 690 27.5600000000 0.0193770397 0.0080331534 0.0196503345 0.0074360852 2.5325510000 1.2721800000 0.3191090000 0.0000050000 0.9288630000 0.0081840000 109631544 0 1784492032 4.2376713753 4.1354408264 4.6827507019 691 27.6000000000 0.0196566600 0.0080499747 0.0196566600 0.0074362231 2.6117140000 1.2713750000 0.2717660000 0.1406000000 0.9154890000 0.0082540000 109633218 0 1785872384 4.2288031578 4.1397638321 4.6762032509 692 27.6400000000 0.0202053245 0.0080675402 0.0202053245 0.0074506119 2.5291780000 1.3145320000 0.2730680000 0.0000050000 0.9292000000 0.0082570000 109634892 0 1787777024 4.2201418877 4.1435890198 4.6692156792 693 27.6800000000 0.0205774195 0.0080855920 0.0205774195 0.0074809789 3.5403760000 1.2709810000 0.2721540000 0.1401370000 0.9161980000 0.9366920000 109636566 0 1784365056 4.2123045921 4.1440525055 4.6614847183 694 27.7200000000 0.0213405341 0.0081046913 0.0213405341 0.0074956375 2.7713160000 1.2759930000 0.5590890000 0.0000040000 0.9238050000 0.0081920000 109638240 0 1785872384 4.2048287392 4.1434230804 4.6524386406 695 27.7600000000 0.0216509365 0.0081241823 0.0216509365 0.0074954913 2.7586300000 1.2678210000 0.4157530000 0.1398740000 0.9227890000 0.0082790000 109639914 0 1787650048 4.1977238655 4.1426577568 4.6447620392 696 27.8000000000 0.0223182980 0.0081445762 0.0223182980 0.0074914497 2.5999400000 1.2934570000 0.3668700000 0.0000050000 0.9272400000 0.0082010000 109641588 0 1784500224 4.1899757385 4.1451759338 4.6366262436 697 27.8400000000 0.0229828637 0.0081658649 0.0229828637 0.0074885990 3.7212790000 1.2718430000 0.4139570000 0.1394520000 0.9386660000 0.9531740000 109643262 0 1785880576 4.1818537712 4.1486473083 4.6288852692 698 27.8800000000 0.0233255364 0.0081875837 0.0233255364 0.0074907795 2.5018360000 1.2777780000 0.2725900000 0.0000050000 0.9389790000 0.0082410000 109644936 0 1787785216 4.1728520393 4.1532044411 4.6220803261 699 27.9200000000 0.0233693104 0.0082093029 0.0233693104 0.0075016422 2.6918350000 1.2762660000 0.3201350000 0.1391260000 0.9437320000 0.0083650000 109646610 0 1784619008 4.1644630432 4.1573052406 4.6159667969 700 27.9600000000 0.0232330821 0.0082307654 0.0233693104 0.0075186439 2.5334880000 1.3062340000 0.2619270000 0.0000050000 0.9528880000 0.0082430000 109648284 0 1785999360 4.1557674408 4.1605191231 4.6094379425 701 28.0000000000 0.0229373705 0.0082517449 0.0233693104 0.0075377062 3.6118910000 1.2764180000 0.2723290000 0.1386700000 0.9498670000 0.9704050000 109649958 0 1787904000 4.1475324631 4.1628174782 4.6036839485 702 28.0400000000 0.0222415440 0.0082716734 0.0233693104 0.0075528994 2.5108560000 1.2711340000 0.2607730000 0.0000060000 0.9664600000 0.0082800000 109651632 0 1784619008 4.1394782066 4.1639685631 4.5983066559 703 28.0800000000 0.0212697219 0.0082901628 0.0233693104 0.0075614454 2.6548320000 1.2728930000 0.2711660000 0.1383480000 0.9599010000 0.0082500000 109653306 0 1785999360 4.1322522163 4.1650352478 4.5948348045 704 28.1200000000 0.0201460011 0.0083070035 0.0233693104 0.0075686453 2.5566070000 1.3062850000 0.2625890000 0.0000050000 0.9751750000 0.0083620000 109654980 0 1787904000 4.1233367920 4.1713418961 4.5921044350 705 28.1600000000 0.0192846898 0.0083225746 0.0233693104 0.0075929856 3.6840160000 1.2719030000 0.3197140000 0.1380100000 0.9649140000 0.9850200000 109656654 0 1784221696 4.1148819923 4.1755914688 4.5890727043 706 28.2000000000 0.0186472852 0.0083371989 0.0233693104 0.0076141692 2.5427910000 1.2820290000 0.2738490000 0.0000050000 0.9744970000 0.0082020000 109658328 0 1785745408 4.1076078415 4.1756563187 4.5861067772 707 28.2400000000 0.0181920566 0.0083511379 0.0233693104 0.0076166469 2.7529480000 1.2768490000 0.3556780000 0.1375530000 0.9703710000 0.0082330000 109660002 0 1787523072 4.0997776985 4.1791043282 4.5828323364 708 28.2800000000 0.0175846424 0.0083641795 0.0233693104 0.0076140869 2.6192460000 1.3084030000 0.3174070000 0.0000050000 0.9809250000 0.0082570000 109661676 0 1784627200 4.0914998055 4.1835408211 4.5809783936 709 28.3200000000 0.0165094249 0.0083756679 0.0233693104 0.0076097647 3.6695650000 1.2726570000 0.2709250000 0.1372650000 0.9792240000 1.0052040000 109663350 0 1785880576 4.0851435661 4.1805686951 4.5794315338 710 28.3600000000 0.0157195143 0.0083860113 0.0233693104 0.0076061804 2.5865780000 1.2713330000 0.3192500000 0.0000050000 0.9835400000 0.0082110000 109665024 0 1787777024 4.0782618523 4.1815438271 4.5773053169 711 28.4000000000 0.0153552108 0.0083958133 0.0233693104 0.0076012020 2.6847860000 1.2713630000 0.2743350000 0.1365530000 0.9899320000 0.0082800000 109666698 0 1784492032 4.0697097778 4.1894388199 4.5762910843 712 28.4400000000 0.0150241647 0.0084051228 0.0233693104 0.0075982977 2.5674620000 1.2931830000 0.2722530000 0.0000050000 0.9894730000 0.0082230000 109668372 0 1785872384 4.0618209839 4.1916913986 4.5742125511 713 28.4800000000 0.0148514910 0.0084141640 0.0233693104 0.0075952507 3.6880570000 1.2717300000 0.2811110000 0.1361010000 0.9881520000 1.0066700000 109670046 0 1787777024 4.0568084717 4.1882390976 4.5736880302 714 28.5200000000 0.0148753636 0.0084232133 0.0233693104 0.0076140718 2.5328730000 1.2705280000 0.2636130000 0.0000050000 0.9861440000 0.0082230000 109671720 0 1784492032 4.0484609604 4.1957659721 4.5732064247 715 28.5600000000 0.0147471698 0.0084320580 0.0233693104 0.0076093014 2.7339420000 1.2789000000 0.3200940000 0.1355930000 0.9868150000 0.0082300000 109673394 0 1785872384 4.0396952629 4.2026000023 4.5731863976 716 28.6000000000 0.0147222048 0.0084408431 0.0233693104 0.0076098931 2.5841600000 1.3042180000 0.2626550000 0.0000050000 1.0046360000 0.0082870000 109675068 0 1787777024 4.0329465866 4.2043600082 4.5753068924 717 28.6400000000 0.0146736484 0.0084495360 0.0233693104 0.0076072539 3.7147600000 1.2715150000 0.3194850000 0.1348470000 0.9816170000 1.0028310000 109676742 0 1784492032 4.0264973640 4.2059350014 4.5780806541 718 28.6800000000 0.0147305345 0.0084582839 0.0233693104 0.0076025271 2.5776230000 1.2799890000 0.2987760000 0.0000050000 0.9861450000 0.0082300000 109678416 0 1785864192 4.0191636086 4.2106437683 4.5808029175 719 28.7200000000 0.0147121744 0.0084669819 0.0233693104 0.0076013945 2.7049560000 1.2738620000 0.3079560000 0.1343330000 0.9761160000 0.0082560000 109680090 0 1787641856 4.0114264488 4.2139096260 4.5830101967 720 28.7600000000 0.0147334980 0.0084756854 0.0233693104 0.0075992651 2.5963540000 1.2804710000 0.3202270000 0.0000050000 0.9830270000 0.0082140000 109681764 0 1784619008 4.0039739609 4.2162666321 4.5866484642 721 28.8000000000 0.0147736380 0.0084844205 0.0233693104 0.0075944636 3.6413300000 1.2703600000 0.2612900000 0.1337850000 0.9724660000 0.9990260000 109683438 0 1785880576 3.9970932007 4.2171821594 4.5912637711 722 28.8400000000 0.0147931324 0.0084931583 0.0233693104 0.0075892199 2.5270880000 1.2765610000 0.2616460000 0.0000050000 0.9762690000 0.0082260000 109685112 0 1787785216 3.9892511368 4.2196540833 4.5956439972 723 28.8800000000 0.0147822006 0.0085018568 0.0233693104 0.0075840173 2.6689580000 1.2749160000 0.2719010000 0.1330230000 0.9764790000 0.0082810000 109686786 0 1784365056 3.9815678596 4.2209277153 4.6011719704 724 28.9200000000 0.0147313699 0.0085104611 0.0233693104 0.0075788096 2.5420690000 1.2894390000 0.2728570000 0.0000050000 0.9671220000 0.0083260000 109688460 0 1785872384 3.9732983112 4.2232828140 4.6065559387 725 28.9600000000 0.0146980211 0.0085189957 0.0233693104 0.0075761412 3.6860090000 1.2733100000 0.3195310000 0.1322990000 0.9708910000 0.9856070000 109690134 0 1787650048 3.9646506310 4.2259259224 4.6122989655 726 29.0000000000 0.0147499312 0.0085275782 0.0233693104 0.0075811733 2.5779730000 1.2755450000 0.3205870000 0.0000050000 0.9690910000 0.0082720000 109691808 0 1784348672 3.9565458298 4.2273602486 4.6183729172 727 29.0400000000 0.0146939037 0.0085360601 0.0233693104 0.0075855495 2.6477690000 1.2774360000 0.2707790000 0.1315690000 0.9553440000 0.0082790000 109693482 0 1785872384 3.9473669529 4.2294187546 4.6242876053 728 29.0800000000 0.0147639019 0.0085446148 0.0233693104 0.0075892831 2.5162490000 1.2731840000 0.2722350000 0.0000050000 0.9582440000 0.0082340000 109695156 0 1787650048 3.9385991096 4.2318854332 4.6308741570 729 29.1200000000 0.0147403022 0.0085531137 0.0233693104 0.0075889043 3.6510630000 1.2798690000 0.3198550000 0.1306310000 0.9476550000 0.9686460000 109696830 0 1784254464 3.9298355579 4.2344932556 4.6378769875 730 29.1600000000 0.0148683386 0.0085617647 0.0233693104 0.0075854045 2.6531320000 1.2731580000 0.4208690000 0.0000040000 0.9464160000 0.0082000000 109698504 0 1785745408 3.9210867882 4.2358307838 4.6446852684 731 29.2000000000 0.0149022359 0.0085704384 0.0233693104 0.0075808523 2.6739340000 1.2758710000 0.3112140000 0.1299780000 0.9441550000 0.0082100000 109700178 0 1787650048 3.9117221832 4.2384805679 4.6511173248 732 29.2400000000 0.0150538245 0.0085792955 0.0233693104 0.0075767226 2.5341140000 1.3016620000 0.2724550000 0.0000050000 0.9472630000 0.0083270000 109701852 0 1784619008 3.9016208649 4.2428665161 4.6576476097 733 29.2800000000 0.0149742924 0.0085880199 0.0233693104 0.0075720277 3.5793060000 1.2701330000 0.2606110000 0.1287980000 0.9470220000 0.9681480000 109703526 0 1786134528 3.8918752670 4.2461223602 4.6660337448 734 29.3200000000 0.0148875779 0.0085966024 0.0233693104 0.0075676177 2.5112090000 1.2865820000 0.2611250000 0.0000050000 0.9506980000 0.0082540000 109705200 0 1787912192 3.8827590942 4.2497658730 4.6752820015 735 29.3600000000 0.0147520406 0.0086049772 0.0233693104 0.0075645928 2.6299770000 1.2718810000 0.2720920000 0.1278030000 0.9453590000 0.0082910000 109706874 0 1784254464 3.8738784790 4.2531814575 4.6840386391 736 29.4000000000 0.0146059440 0.0086131307 0.0233693104 0.0075613893 2.5247250000 1.2965340000 0.2617640000 0.0000050000 0.9536540000 0.0082670000 109708548 0 1785618432 3.8652796745 4.2574086189 4.6932306290 737 29.4400000000 0.0144027472 0.0086209863 0.0233693104 0.0075566915 3.5844250000 1.2746930000 0.2613540000 0.1269470000 0.9502390000 0.9667910000 109710222 0 1787523072 3.8569979668 4.2605566978 4.7020359039 738 29.4800000000 0.0142703224 0.0086286412 0.0233693104 0.0075553441 2.5120980000 1.2719340000 0.2703750000 0.0000040000 0.9570700000 0.0082820000 109711896 0 1784492032 3.8484971523 4.2640304565 4.7108139992 739 29.5200000000 0.0141555322 0.0086361201 0.0233693104 0.0075704394 2.5725220000 1.2745110000 0.2178780000 0.1259330000 0.9414000000 0.0082270000 109713570 0 1785872384 3.8406593800 4.2669076920 4.7196741104 740 29.5600000000 0.0142026087 0.0086436424 0.0233693104 0.0075899292 2.5376580000 1.3110140000 0.2605320000 0.0000050000 0.9534070000 0.0082580000 109715244 0 1787777024 3.8335852623 4.2696242332 4.7282729149 741 29.6000000000 0.0142655279 0.0086512293 0.0233693104 0.0076141480 3.5454220000 1.2746590000 0.2617620000 0.1252310000 0.9301200000 0.9491640000 109716918 0 1784492032 3.8263399601 4.2740077972 4.7367448807 742 29.6400000000 0.0143202031 0.0086588694 0.0233693104 0.0076325876 2.5423870000 1.2732850000 0.3078770000 0.0000040000 0.9484140000 0.0083990000 109718592 0 1785872384 3.8201432228 4.2777056694 4.7457237244 743 29.6800000000 0.0142595656 0.0086664074 0.0233693104 0.0076322097 2.6050610000 1.2802050000 0.2703840000 0.1247100000 0.9169450000 0.0083460000 109720266 0 1787777024 3.8153119087 4.2787113190 4.7539167404 744 29.7200000000 0.0142611507 0.0086739272 0.0233693104 0.0076275790 2.5531700000 1.2902700000 0.3216550000 0.0000040000 0.9283470000 0.0082100000 109721940 0 1784475648 3.8103444576 4.2806911469 4.7609229088 745 29.7600000000 0.0142777842 0.0086814491 0.0233693104 0.0076253696 3.5160220000 1.2785930000 0.2727500000 0.1242330000 0.9076530000 0.9283110000 109723614 0 1786134528 3.8051667213 4.2834129333 4.7673640251 746 29.8000000000 0.0142868413 0.0086889631 0.0233693104 0.0076214044 2.5257620000 1.2715050000 0.3261900000 0.0000050000 0.9151580000 0.0082300000 109725288 0 1787785216 3.8003439903 4.2852926254 4.7737021446 747 29.8400000000 0.0142702423 0.0086964347 0.0233693104 0.0076164957 2.6249770000 1.2740990000 0.3173220000 0.1236590000 0.8969170000 0.0082300000 109726962 0 1785151488 3.7950966358 4.2883706093 4.7794384956 748 29.8800000000 0.0142405797 0.0087038466 0.0233693104 0.0076136875 2.5448040000 1.3078240000 0.3072660000 0.0000230000 0.9168550000 0.0082270000 109728636 0 1786650624 3.7901051044 4.2918910980 4.7853784561 749 29.9200000000 0.0142369745 0.0087112340 0.0233693104 0.0076102356 3.4423110000 1.2704720000 0.2591300000 0.1232440000 0.8822410000 0.9025240000 109730310 0 1784745984 3.7858092785 4.2947807312 4.7910304070 750 29.9600000000 0.0142502226 0.0087186193 0.0233693104 0.0076071822 2.4686610000 1.2813320000 0.2716180000 0.0000050000 0.9028890000 0.0082290000 109731984 0 1786142720 3.7817599773 4.2976012230 4.7962622643 751 30.0000000000 0.0142857917 0.0087260323 0.0233693104 0.0076041673 2.5490100000 1.2734310000 0.2699380000 0.1227820000 0.8700590000 0.0082710000 109733658 0 1785491456 3.7779879570 4.2997789383 4.8008775711 752 30.0400000000 0.0143338554 0.0087334895 0.0233693104 0.0076013039 2.4683520000 1.2978260000 0.2708200000 0.0000040000 0.8869170000 0.0082710000 109735332 0 1787031552 3.7744204998 4.3025026321 4.8051819801 753 30.0800000000 0.0143381786 0.0087409327 0.0233693104 0.0076005077 3.4015290000 1.2738090000 0.2577440000 0.1225520000 0.8571930000 0.8855730000 109737006 0 1784619008 3.7707209587 4.3044571877 4.8089098930 754 30.1200000000 0.0143690901 0.0087483971 0.0233693104 0.0076060515 2.4253790000 1.2745700000 0.2604110000 0.0000040000 0.8775350000 0.0083200000 109738680 0 1786380288 3.7671706676 4.3065896034 4.8124732971 755 30.1600000000 0.0144225769 0.0087559125 0.0233693104 0.0076173642 2.5284120000 1.2718770000 0.2675310000 0.1222490000 0.8538870000 0.0082980000 109740354 0 1785507840 3.7631173134 4.3080658913 4.8157248497 756 30.2000000000 0.0144339520 0.0087634232 0.0233693104 0.0076287580 2.4763390000 1.2794770000 0.3162470000 0.0000040000 0.8677120000 0.0082710000 109742028 0 1786904576 3.7588453293 4.3108158112 4.8192920685 757 30.2400000000 0.0144033078 0.0087708735 0.0233693104 0.0076304260 3.3488180000 1.2736770000 0.2582630000 0.1238160000 0.8370000000 0.8514690000 109743702 0 1784745984 3.7540376186 4.3138704300 4.8223214149 758 30.2800000000 0.0144016780 0.0087783020 0.0233693104 0.0076335510 2.3986740000 1.2716960000 0.2695570000 0.0000050000 0.8446010000 0.0082470000 109745376 0 1786388480 3.7491457462 4.3156046867 4.8257699013 759 30.3200000000 0.0144499354 0.0087857745 0.0233693104 0.0076505359 2.5307370000 1.3248520000 0.2581240000 0.1220160000 0.8128430000 0.0082070000 109747050 0 1785516032 3.7436280251 4.3186674118 4.8292541504 760 30.3600000000 0.0144668231 0.0087932495 0.0233693104 0.0076633916 2.4515700000 1.2788030000 0.3180050000 0.0000040000 0.8417990000 0.0082660000 109748724 0 1787142144 3.7373237610 4.3235306740 4.8322677612 761 30.4000000000 0.0144896079 0.0088007349 0.0233693104 0.0076724191 3.2980630000 1.2940860000 0.2691870000 0.1217120000 0.7940770000 0.8143140000 109750398 0 1784889344 3.7309958935 4.3270201683 4.8349957466 762 30.4400000000 0.0144887455 0.0088081995 0.0233693104 0.0076737432 2.4120590000 1.2692170000 0.3172710000 0.0000040000 0.8127660000 0.0082070000 109752072 0 1786269696 3.7242047787 4.3306474686 4.8371882439 763 30.4800000000 0.0145474933 0.0088157215 0.0233693104 0.0076725753 2.4571540000 1.2769660000 0.2685970000 0.1206710000 0.7779140000 0.0082920000 109753746 0 1785618432 3.7170071602 4.3347287178 4.8393964767 764 30.5200000000 0.0146061666 0.0088233006 0.0233693104 0.0076723334 2.4311440000 1.2705280000 0.3541230000 0.0000210000 0.7935300000 0.0081910000 109755420 0 1787285504 3.7092664242 4.3386144638 4.8415837288 765 30.5600000000 0.0145867653 0.0088308346 0.0233693104 0.0076700834 3.2000480000 1.2800370000 0.2696590000 0.1203570000 0.7524290000 0.7728710000 109757094 0 1784508416 3.7015819550 4.3426270485 4.8438749313 766 30.6000000000 0.0146691184 0.0088384563 0.0233693104 0.0076691088 2.3263370000 1.2735160000 0.2709900000 0.0000040000 0.7688940000 0.0082210000 109758768 0 1786142720 3.6938967705 4.3462667465 4.8461651802 767 30.6400000000 0.0146469940 0.0088460294 0.0233693104 0.0076677747 2.4214980000 1.2732340000 0.2699920000 0.1198430000 0.7455410000 0.0082500000 109760442 0 1787920384 3.6853957176 4.3502573967 4.8480038643 768 30.6800000000 0.0146919647 0.0088536413 0.0233693104 0.0076689126 2.3010980000 1.2719260000 0.2700370000 0.0000050000 0.7461700000 0.0083200000 109762116 0 1785126912 3.6770803928 4.3539361954 4.8500814438 769 30.7200000000 0.0147156101 0.0088612641 0.0233693104 0.0076695517 3.1433890000 1.2768960000 0.2703010000 0.1192650000 0.7262890000 0.7459860000 109763790 0 1786523648 3.6687109470 4.3582029343 4.8522005081 770 30.7600000000 0.0147206699 0.0088688738 0.0233693104 0.0076667500 2.2946270000 1.2716190000 0.2707700000 0.0000040000 0.7393490000 0.0082380000 109765464 0 1785507840 3.6603252888 4.3624868393 4.8542947769 771 30.8000000000 0.0147286709 0.0088764740 0.0233693104 0.0076630639 2.3799480000 1.2729780000 0.2595320000 0.1186380000 0.7146730000 0.0093230000 109767138 0 1787293696 3.6518669128 4.3662872314 4.8560028076 772 30.8400000000 0.0147875221 0.0088841308 0.0233693104 0.0076607030 2.2728730000 1.2740480000 0.2703180000 0.0000050000 0.7098740000 0.0132630000 109768812 0 1784770560 3.6435639858 4.3688941002 4.8577904701 773 30.8800000000 0.0147882877 0.0088917688 0.0233693104 0.0076593150 3.0752030000 1.2750520000 0.2696950000 0.1180780000 0.6945320000 0.7131450000 109770486 0 1786507264 3.6350460052 4.3719677925 4.8596258163 774 30.9200000000 0.0148269599 0.0088994370 0.0233693104 0.0076626843 2.2958930000 1.2708860000 0.3167610000 0.0000050000 0.6953180000 0.0082340000 109772160 0 1785634816 3.6269841194 4.3744192123 4.8616580963 775 30.9600000000 0.0148694767 0.0089071403 0.0233693104 0.0076679730 2.3518610000 1.2728380000 0.2603570000 0.1177120000 0.6880230000 0.0082470000 109773834 0 1787158528 3.6186897755 4.3759965897 4.8631310463 776 31.0000000000 0.0148783056 0.0089148351 0.0233693104 0.0076756184 2.2505800000 1.2708130000 0.2704160000 0.0000040000 0.6963230000 0.0083200000 109775508 0 1784872960 3.6101200581 4.3779516220 4.8646559715 777 31.0400000000 0.0149183562 0.0089225616 0.0233693104 0.0076863912 2.9735660000 1.2714610000 0.2118120000 0.1173170000 0.6742000000 0.6940120000 109777182 0 1786380288 3.6016497612 4.3811888695 4.8659424782 778 31.0800000000 0.0149413059 0.0089302978 0.0233693104 0.0076874158 2.2449210000 1.2806440000 0.2709070000 0.0000040000 0.6803230000 0.0082330000 109778856 0 1785618432 3.5933198929 4.3845462799 4.8671045303 779 31.1200000000 0.0149571439 0.0089380344 0.0233693104 0.0076859197 2.3724250000 1.2703210000 0.3180090000 0.1167600000 0.6542490000 0.0082770000 109780530 0 1787142144 3.5854511261 4.3867969513 4.8686356544 780 31.1600000000 0.0149664572 0.0089457632 0.0233693104 0.0076849203 2.2099750000 1.2688140000 0.2701820000 0.0000040000 0.6579150000 0.0083190000 109782204 0 1784619008 3.5777456760 4.3894200325 4.8701696396 781 31.2000000000 0.0150178447 0.0089535379 0.0233693104 0.0076827174 2.9798780000 1.2799270000 0.2603720000 0.1164630000 0.6493290000 0.6690530000 109783878 0 1785999360 3.5700445175 4.3918442726 4.8709273338 782 31.2400000000 0.0150063215 0.0089612781 0.0233693104 0.0076786658 2.4816580000 1.2705730000 0.5511770000 0.0000040000 0.6468600000 0.0082840000 109785552 0 1788030976 3.5627467632 4.3931670189 4.8722014427 783 31.2800000000 0.0150046302 0.0089689963 0.0233693104 0.0076741283 2.3571690000 1.2713260000 0.3228190000 0.1158780000 0.6341000000 0.0083090000 109787226 0 1784492032 3.5555510521 4.3948450089 4.8735671043 784 31.3200000000 0.0150431953 0.0089767440 0.0233693104 0.0076693886 2.2288530000 1.2726370000 0.3106390000 0.0000060000 0.6325830000 0.0082670000 109788900 0 1785999360 3.5489165783 4.3961439133 4.8749837875 785 31.3600000000 0.0150384242 0.0089844658 0.0233693104 0.0076646614 2.9535460000 1.2791990000 0.2747180000 0.1154900000 0.6295750000 0.6497830000 109790574 0 1787928576 3.5425136089 4.3967452049 4.8761134148 786 31.4000000000 0.0150563847 0.0089921909 0.0233693104 0.0076614730 2.1818190000 1.2746330000 0.2641820000 0.0000050000 0.6300100000 0.0082530000 109792248 0 1785245696 3.5360994339 4.3976659775 4.8773546219 787 31.4400000000 0.0150465434 0.0089998839 0.0233693104 0.0076581448 2.3080700000 1.2926220000 0.2744690000 0.1178130000 0.6098450000 0.0082810000 109793922 0 1786769408 3.5303225517 4.3996214867 4.8785305023 788 31.4800000000 0.0150725478 0.0090075903 0.0233693104 0.0076562881 2.2202020000 1.2718190000 0.3248720000 0.0000050000 0.6103180000 0.0082850000 109795596 0 1784492032 3.5251045227 4.4005274773 4.8801441193 789 31.5200000000 0.0150972446 0.0090153085 0.0233693104 0.0076548025 2.9071400000 1.2768990000 0.2759400000 0.1147660000 0.6080120000 0.6267470000 109797270 0 1785872384 3.5198073387 4.4005999565 4.8812255859 790 31.5600000000 0.0150878383 0.0090229953 0.0233693104 0.0076511012 2.2048330000 1.2723450000 0.3122320000 0.0000050000 0.6071350000 0.0083640000 109798944 0 1787777024 3.5146977901 4.4007749557 4.8826870918 791 31.6000000000 0.0150778638 0.0090306500 0.0233693104 0.0076464155 2.3234950000 1.2766360000 0.3115900000 0.1145170000 0.6076210000 0.0083080000 109800618 0 1784619008 3.5098500252 4.4010181427 4.8838939667 792 31.6400000000 0.0150792059 0.0090382870 0.0233693104 0.0076416244 2.2657410000 1.2735090000 0.3701030000 0.0000060000 0.6089600000 0.0082750000 109802292 0 1785999360 3.5055871010 4.4006376266 4.8852868080 793 31.6800000000 0.0150815230 0.0090459077 0.0233693104 0.0076384642 2.9124370000 1.2750640000 0.2756110000 0.1142890000 0.6112520000 0.6314470000 109803966 0 1787904000 3.5017304420 4.3998527527 4.8865003586 794 31.7200000000 0.0150813488 0.0090535091 0.0233693104 0.0076411072 2.1783510000 1.2751780000 0.2755670000 0.0000050000 0.6144430000 0.0082460000 109805640 0 1784602624 3.4984278679 4.3987588882 4.8879089355 795 31.7600000000 0.0150773879 0.0090610863 0.0233693104 0.0076503647 2.3337590000 1.3141280000 0.2750520000 0.1139340000 0.6174870000 0.0082470000 109807314 0 1786253312 3.4951715469 4.3977341652 4.8892030716 796 31.8000000000 0.0150712933 0.0090686368 0.0233693104 0.0076677920 2.1751190000 1.2737230000 0.2671860000 0.0000060000 0.6212310000 0.0082160000 109808988 0 1788030976 3.4920067787 4.3966321945 4.8908700943 797 31.8400000000 0.0151108848 0.0090762180 0.0233693104 0.0076874704 2.9358540000 1.2813110000 0.2638930000 0.1139400000 0.6260090000 0.6458650000 109810662 0 1785237504 3.4896378517 4.3955550194 4.8924827576 798 31.8800000000 0.0150994761 0.0090837660 0.0233693104 0.0077056723 2.1811300000 1.2726730000 0.2625960000 0.0000050000 0.6328240000 0.0082660000 109812336 0 1786761216 3.4867904186 4.3940620422 4.8937869072 799 31.9200000000 0.0151236467 0.0090913253 0.0233693104 0.0077160531 2.2783370000 1.2849670000 0.2263230000 0.1137570000 0.6401240000 0.0082250000 109814010 0 1784365056 3.4841840267 4.3922977448 4.8951926231 800 31.9600000000 0.0150836250 0.0090988156 0.0233693104 0.0077237581 2.1964230000 1.2730500000 0.2623050000 0.0000050000 0.6479050000 0.0083000000 109815684 0 1786134528 3.4818089008 4.3902735710 4.8967194557 801 32.0000000000 0.0150763141 0.0091062782 0.0233693104 0.0077367605 2.9374660000 1.2726040000 0.2217110000 0.1134740000 0.6527840000 0.6720030000 109817358 0 1787801600 3.4798355103 4.3885803223 4.8987646103 802 32.0400000000 0.0150994305 0.0091137509 0.0233693104 0.0077426366 2.1987990000 1.2754330000 0.2529610000 0.0000050000 0.6570650000 0.0083250000 109819032 0 1785135104 3.4777402878 4.3865170479 4.9005670547 803 32.0800000000 0.0150809977 0.0091211821 0.0233693104 0.0077538340 2.3589300000 1.3076120000 0.2649560000 0.1137530000 0.6594360000 0.0082810000 109820706 0 1786507264 3.4768724442 4.3861727715 4.9031581879 804 32.1199999990 0.0151085760 0.0091286291 0.0233693104 0.0077703298 2.2141110000 1.2729610000 0.2657780000 0.0000040000 0.6620350000 0.0082380000 109822380 0 1785507840 3.4757614136 4.3854274750 4.9051699638 805 32.1600000000 0.0150745129 0.0091360153 0.0233693104 0.0077864211 3.0106740000 1.2696580000 0.2651890000 0.1189650000 0.6663840000 0.6854040000 109824054 0 1787142144 3.4747655392 4.3837075233 4.9073700905 806 32.2000000000 0.0150907254 0.0091434033 0.0233693104 0.0078031138 2.2359650000 1.2740270000 0.2657710000 0.0000050000 0.6830170000 0.0082480000 109825728 0 1784745984 3.4735286236 4.3821597099 4.9090924263 807 32.2400000000 0.0151012000 0.0091507860 0.0233693104 0.0078205320 2.3003120000 1.2735440000 0.2214920000 0.1127220000 0.6793760000 0.0082950000 109827402 0 1786253312 3.4729356766 4.3791012764 4.9110860825 808 32.2800000000 0.0151083432 0.0091581592 0.0233693104 0.0078296331 2.2365880000 1.2763620000 0.2629370000 0.0000050000 0.6839820000 0.0084100000 109829076 0 1785618432 3.4717373848 4.3766894341 4.9133563042 809 32.3200000000 0.0150923152 0.0091654943 0.0233693104 0.0078356506 3.0547490000 1.2698720000 0.2630700000 0.1125820000 0.6944200000 0.7098680000 109830750 0 1787015168 3.4715175629 4.3729820251 4.9157819748 810 32.3600000000 0.0151218101 0.0091728478 0.0233693104 0.0078424823 2.2592900000 1.2737760000 0.2740260000 0.0000040000 0.6981410000 0.0082790000 109832424 0 1784872960 3.4707345963 4.3706388474 4.9178895950 811 32.4000000000 0.0151127875 0.0091801720 0.0233693104 0.0078410395 2.6280180000 1.2967680000 0.5057090000 0.1123910000 0.6998460000 0.0083180000 109834098 0 1786380288 3.4696514606 4.3668241501 4.9199771881 812 32.4399999990 0.0151227629 0.0091874905 0.0233693104 0.0078400742 2.3161110000 1.2714840000 0.3249320000 0.0000050000 0.7063560000 0.0082370000 109835772 0 1785618432 3.4688858986 4.3633122444 4.9221916199 813 32.4800000000 0.0150861172 0.0091947459 0.0233693104 0.0078402261 3.0591030000 1.2734930000 0.2321470000 0.1123770000 0.7089700000 0.7270680000 109837446 0 1787158528 3.4686751366 4.3607325554 4.9252429008 814 32.5200000000 0.0151042743 0.0092020057 0.0233693104 0.0078407500 2.2752900000 1.2721090000 0.2754370000 0.0000050000 0.7144110000 0.0083140000 109839120 0 1785008128 3.4681029320 4.3579130173 4.9280805588 815 32.5600000000 0.0150692333 0.0092092048 0.0233693104 0.0078383439 2.4002430000 1.2788590000 0.2743620000 0.1129510000 0.7206990000 0.0082570000 109840794 0 1786388480 3.4672837257 4.3548851013 4.9308133125 816 32.6000000000 0.0150853489 0.0092164059 0.0233693104 0.0078363753 2.2925440000 1.2755760000 0.2737360000 0.0000040000 0.7298320000 0.0083120000 109842468 0 1785643008 3.4670374393 4.3506155014 4.9341297150 817 32.6400000000 0.0150385862 0.0092235322 0.0233693104 0.0078326312 3.1959870000 1.2714940000 0.3155910000 0.1120720000 0.7365440000 0.7552830000 109844142 0 1787142144 3.4662725925 4.3471593857 4.9370203018 818 32.6800000000 0.0150277810 0.0092306279 0.0233693104 0.0078280860 2.2944910000 1.2755560000 0.2628550000 0.0000050000 0.7427890000 0.0083030000 109845816 0 1784856576 3.4656209946 4.3435134888 4.9407272339 819 32.7200000000 0.0150458198 0.0092377283 0.0233693104 0.0078247438 2.4205300000 1.2771650000 0.2730630000 0.1117990000 0.7451270000 0.0083200000 109847490 0 1786396672 3.4654161930 4.3415923119 4.9449858665 820 32.7599999990 0.0150278388 0.0092447894 0.0233693104 0.0078219244 2.3083640000 1.2718090000 0.2726810000 0.0000040000 0.7505840000 0.0083060000 109849164 0 1785397248 3.4648189545 4.3391666412 4.9492535591 821 32.7999999990 0.0149445869 0.0092517319 0.0233693104 0.0078259269 3.1935250000 1.2792240000 0.2725330000 0.1120730000 0.7524660000 0.7721090000 109850838 0 1787015168 3.4653384686 4.3370995522 4.9548087120 822 32.8400000000 0.0149839846 0.0092587054 0.0233693104 0.0078495429 2.3070360000 1.2739140000 0.2633980000 0.0000040000 0.7562590000 0.0082770000 109852512 0 1784619008 3.4650681019 4.3345575333 4.9596982002 823 32.8800000000 0.0149158454 0.0092655792 0.0233693104 0.0078594911 2.4363780000 1.2789520000 0.2724070000 0.1112610000 0.7604250000 0.0083220000 109854186 0 1785999360 3.4644520283 4.3324737549 4.9647083282 824 32.9200000000 0.0149801066 0.0092725143 0.0233693104 0.0078638877 2.4096750000 1.2735400000 0.3564310000 0.0000050000 0.7664210000 0.0083030000 109855860 0 1788030976 3.4640932083 4.3316640854 4.9705529213 825 32.9600000000 0.0148888323 0.0092793220 0.0233693104 0.0078765868 3.2152850000 1.2788420000 0.2633280000 0.1107670000 0.7684290000 0.7888790000 109857534 0 1784872960 3.4637937546 4.3292131424 4.9765734673 826 33.0000000000 0.0147816725 0.0092859834 0.0233693104 0.0078844969 2.3353990000 1.2727750000 0.2746370000 0.0000040000 0.7746460000 0.0083280000 109859208 0 1786253312 3.4633510113 4.3278470039 4.9827499390 827 33.0400000000 0.0147074070 0.0092925390 0.0233693104 0.0079010767 2.4858310000 1.3097790000 0.2752290000 0.1104810000 0.7768520000 0.0082920000 109860882 0 1785389056 3.4628052711 4.3246302605 4.9886021614 828 33.0800000000 0.0146640735 0.0092990263 0.0233693104 0.0079280717 2.3453130000 1.2738130000 0.2735360000 0.0000050000 0.7844720000 0.0083190000 109862556 0 1786896384 3.4625027180 4.3208184242 4.9941692352 829 33.1199999990 0.0146185681 0.0093054431 0.0233693104 0.0079491673 3.2721630000 1.2782240000 0.2723920000 0.1099680000 0.7936830000 0.8128110000 109864230 0 1784348672 3.4617781639 4.3175988197 5.0003819466 830 33.1600000000 0.0144990450 0.0093117005 0.0233693104 0.0079649161 2.3562350000 1.2737960000 0.2608900000 0.0000050000 0.8082080000 0.0082900000 109865904 0 1785745408 3.4611358643 4.3140869141 5.0062456131 831 33.2000000000 0.0143541321 0.0093177684 0.0233693104 0.0079825401 2.5647190000 1.2739690000 0.3553360000 0.1107620000 0.8113530000 0.0082360000 109867578 0 1787650048 3.4612631798 4.3090028763 5.0130510330 832 33.2400000000 0.0142000820 0.0093236366 0.0233693104 0.0079923479 2.3304310000 1.2760020000 0.2138270000 0.0000050000 0.8272710000 0.0082960000 109869252 0 1784619008 3.4605574608 4.3047990799 5.0195288658 833 33.2800000000 0.0140416771 0.0093293005 0.0233693104 0.0079953028 3.3305470000 1.2717110000 0.2718750000 0.1090790000 0.8275120000 0.8452920000 109870926 0 1785999360 3.4596035480 4.3013081551 5.0264167786 834 33.3200000000 0.0139854262 0.0093348834 0.0233693104 0.0079993943 2.4477290000 1.2736550000 0.3263580000 0.0000050000 0.8343220000 0.0082400000 109872600 0 1787904000 3.4588162899 4.2961740494 5.0329356194 835 33.3600000000 0.0138121331 0.0093402453 0.0233693104 0.0080059038 2.5241990000 1.2911180000 0.2725260000 0.1085700000 0.8385460000 0.0082480000 109874274 0 1784483840 3.4574918747 4.2933759689 5.0391163826 836 33.4000000000 0.0137129314 0.0093454758 0.0233693104 0.0080150924 2.4547840000 1.2798010000 0.3138100000 0.0000040000 0.8476850000 0.0083510000 109875948 0 1785999360 3.4566063881 4.2896914482 5.0458130836 837 33.4399999990 0.0135642942 0.0093505162 0.0233693104 0.0080304648 3.3942950000 1.3025590000 0.2606770000 0.1080770000 0.8500420000 0.8678840000 109877622 0 1787904000 3.4554550648 4.2870016098 5.0522079468 838 33.4800000000 0.0134956948 0.0093554627 0.0233693104 0.0080597389 2.4102390000 1.2773690000 0.2619330000 0.0000050000 0.8575940000 0.0082600000 109879296 0 1784745984 3.4550502300 4.2821083069 5.0581912994 839 33.5200000000 0.0133399973 0.0093602119 0.0233693104 0.0080907182 2.5379070000 1.3040190000 0.2494630000 0.1075210000 0.8634740000 0.0083780000 109880970 0 1786261504 3.4545118809 4.2794966698 5.0646400452 840 33.5600000000 0.0131419133 0.0093647139 0.0233693104 0.0081118189 2.4370080000 1.2787580000 0.2712630000 0.0000050000 0.8735590000 0.0082450000 109882644 0 1785245696 3.4522821903 4.2768306732 5.0692968369 841 33.6000000000 0.0129416222 0.0093689671 0.0233693104 0.0081143904 3.3753140000 1.2745170000 0.2130150000 0.1069880000 0.8760990000 0.8995590000 109884318 0 1786761216 3.4508712292 4.2746305466 5.0747771263 842 33.6400000000 0.0127652418 0.0093730007 0.0233693104 0.0081128441 2.4314210000 1.2739090000 0.2612000000 0.0000050000 0.8828820000 0.0083130000 109885992 0 1784619008 3.4494554996 4.2723340988 5.0798459053 843 33.6800000000 0.0125822928 0.0093768076 0.0233693104 0.0081127357 2.5653990000 1.2746550000 0.2764160000 0.1069970000 0.8939470000 0.0083180000 109887666 0 1785999360 3.4484152794 4.2687788010 5.0850934982 844 33.7200000000 0.0124070542 0.0093803980 0.0233693104 0.0081178445 2.4615390000 1.2951220000 0.2614220000 0.0000050000 0.8915530000 0.0083710000 109889340 0 1787904000 3.4476938248 4.2637267113 5.0899710655 845 33.7599999990 0.0122193629 0.0093837577 0.0233693104 0.0081287463 3.4643520000 1.2712880000 0.2616890000 0.1064750000 0.9031470000 0.9165350000 109891014 0 1784492032 3.4476165771 4.2603950500 5.0951676369 846 33.7999999990 0.0118134469 0.0093866297 0.0233693104 0.0081358226 2.4502840000 1.2726430000 0.2602370000 0.0000050000 0.9038230000 0.0083080000 109892688 0 1785872384 3.4464263916 4.2577400208 5.0997443199 847 33.8400000000 0.0115060592 0.0093891320 0.0233693104 0.0081346799 2.5818540000 1.2748640000 0.2773720000 0.1062270000 0.9099620000 0.0082840000 109894362 0 1787777024 3.4456276894 4.2527379990 5.1033816338 848 33.8800000000 0.0112230452 0.0093912946 0.0233693104 0.0081302249 2.4940760000 1.2975170000 0.2693810000 0.0000050000 0.9136300000 0.0083130000 109896036 0 1784492032 3.4447698593 4.2490601540 5.1074643135 849 33.9200000000 0.0108477399 0.0093930101 0.0233693104 0.0081254640 3.4956480000 1.2789540000 0.2493150000 0.1057070000 0.9199110000 0.9366330000 109897710 0 1785872384 3.4439835548 4.2433199883 5.1110320091 850 33.9600000000 0.0105895316 0.0093944177 0.0233693104 0.0081210102 2.4778950000 1.2777070000 0.2623400000 0.0000060000 0.9244410000 0.0083080000 109899384 0 1787777024 3.4432113171 4.2394275665 5.1147017479 851 34.0000000000 0.0103733558 0.0093955681 0.0233693104 0.0081162644 2.5977480000 1.2778980000 0.2742630000 0.1055970000 0.9264970000 0.0083360000 109901058 0 1784492032 3.4423193932 4.2363882065 5.1186451912 852 34.0400000000 0.0102177160 0.0093965330 0.0233693104 0.0081115198 2.5125990000 1.2948490000 0.2737210000 0.0000050000 0.9306340000 0.0082580000 109902732 0 1786007552 3.4426393509 4.2310776711 5.1225075722 853 34.0800000000 0.0098932879 0.0093971154 0.0233693104 0.0081090676 3.4988760000 1.2783810000 0.2235050000 0.1053250000 0.9339220000 0.9525190000 109904406 0 1787785216 3.4416892529 4.2269358635 5.1255040169 854 34.1199999990 0.0095655806 0.0093973127 0.0233693104 0.0081074011 2.5002970000 1.2716530000 0.2698610000 0.0000050000 0.9452300000 0.0082580000 109906080 0 1784365056 3.4414541721 4.2241187096 5.1290535927 855 34.1600000000 0.0091393366 0.0093970109 0.0233693104 0.0081082645 2.5956160000 1.2740130000 0.2602910000 0.1051310000 0.9426370000 0.0082520000 109907754 0 1785872384 3.4417259693 4.2204108238 5.1325621605 856 34.2000000000 0.0087689776 0.0093962773 0.0233693104 0.0081081970 2.5302070000 1.3039720000 0.2652480000 0.0000050000 0.9474700000 0.0083410000 109909428 0 1787777024 3.4412283897 4.2172222137 5.1353878975 857 34.2400000000 0.0084114727 0.0093951281 0.0233693104 0.0081040992 3.5623040000 1.2692930000 0.2701430000 0.1048070000 0.9475190000 0.9653230000 109911102 0 1784365056 3.4401760101 4.2158646584 5.1382551193 858 34.2800000000 0.0081300205 0.0093936536 0.0233693104 0.0080995254 2.5667070000 1.2800100000 0.3247520000 0.0000040000 0.9483590000 0.0083120000 109912776 0 1785872384 3.4390196800 4.2133703232 5.1406388283 859 34.3200000000 0.0079799220 0.0093920079 0.0233693104 0.0080951031 2.6157920000 1.2753500000 0.2729190000 0.1046220000 0.9493440000 0.0083230000 109914450 0 1787777024 3.4393334389 4.2072253227 5.1425828934 860 34.3600000000 0.0076315338 0.0093899608 0.0233693104 0.0080906649 2.4819550000 1.2981780000 0.2159870000 0.0000060000 0.9542570000 0.0083100000 109916124 0 1784635392 3.4387030602 4.2020611763 5.1440482140 861 34.4000000000 0.0072593265 0.0093874862 0.0233693104 0.0080863561 3.5767570000 1.2723780000 0.2606990000 0.1045530000 0.9548320000 0.9790360000 109917798 0 1786269696 3.4383656979 4.1983637810 5.1465411186 862 34.4400000000 0.0068950788 0.0093845948 0.0233693104 0.0080816889 2.5047860000 1.2723090000 0.2611610000 0.0000040000 0.9577140000 0.0082420000 109919472 0 1785507840 3.4382414818 4.1940221786 5.1484904289 863 34.4800000000 0.0065457951 0.0093813053 0.0233693104 0.0080773228 2.6780720000 1.2720830000 0.3256810000 0.1044560000 0.9622780000 0.0083120000 109921146 0 1787015168 3.4381020069 4.1874318123 5.1496992111 864 34.5200000000 0.0061307303 0.0093775431 0.0233693104 0.0080729995 2.5169060000 1.2741690000 0.2631090000 0.0000040000 0.9660800000 0.0083080000 109922820 0 1784659968 3.4382913113 4.1837210655 5.1514630318 865 34.5600000000 0.0059204008 0.0093735464 0.0233693104 0.0080683315 3.7104360000 1.2741960000 0.3730590000 0.1043810000 0.9681810000 0.9853490000 109924494 0 1786150912 3.4373452663 4.1824555397 5.1531710625 866 34.6000000000 0.0058479165 0.0093694752 0.0233693104 0.0080658430 2.5187710000 1.2720120000 0.2641830000 0.0000040000 0.9689950000 0.0083210000 109926168 0 1785618432 3.4361112118 4.1809530258 5.1542916298 867 34.6400000000 0.0056989104 0.0093652416 0.0233693104 0.0080625760 2.6351300000 1.2791590000 0.2681750000 0.1042360000 0.9700240000 0.0082400000 109927842 0 1787015168 3.4363446236 4.1781558990 5.1559195518 868 34.6800000000 0.0056951931 0.0093610134 0.0233693104 0.0080584631 2.5098530000 1.3008720000 0.2180130000 0.0000050000 0.9775060000 0.0082220000 109929516 0 1784745984 3.4357166290 4.1743774414 5.1566758156 869 34.7200000000 0.0055068042 0.0093565782 0.0233693104 0.0080542212 3.6554300000 1.2717490000 0.3081950000 0.1042930000 0.9752560000 0.9906210000 109931190 0 1786269696 3.4363169670 4.1708850861 5.1577272415 870 34.7600000000 0.0054125446 0.0093520448 0.0233693104 0.0080498649 2.4838170000 1.2776620000 0.2151580000 0.0000050000 0.9775020000 0.0082380000 109932864 0 1785618432 3.4353568554 4.1682305336 5.1582002640 871 34.8000000000 0.0053942543 0.0093475008 0.0233693104 0.0080452383 2.5701080000 1.2717140000 0.2034050000 0.1041980000 0.9771580000 0.0083420000 109934538 0 1787031552 3.4343841076 4.1663928032 5.1589331627 872 34.8400000000 0.0053039030 0.0093428637 0.0233693104 0.0080409890 2.5013380000 1.2963200000 0.2111070000 0.0000040000 0.9803470000 0.0082340000 109936212 0 1784889344 3.4333021641 4.1631903648 5.1595611572 873 34.8800000000 0.0051816576 0.0093380971 0.0233693104 0.0080365369 3.6190050000 1.2722730000 0.2586010000 0.1041550000 0.9804960000 0.9981240000 109937886 0 1786380288 3.4328958988 4.1610970497 5.1609368324 874 34.9200000000 0.0052349963 0.0093334025 0.0233693104 0.0080326437 2.5251620000 1.2713320000 0.2574480000 0.0000040000 0.9827680000 0.0083180000 109939560 0 1785634816 3.4322025776 4.1598906517 5.1621236801 875 34.9600000000 0.0051028957 0.0093285676 0.0233693104 0.0080291266 2.6019870000 1.2723240000 0.2218110000 0.1051960000 0.9889410000 0.0082460000 109941234 0 1787174912 3.4306726456 4.1598997116 5.1636023521 876 35.0000000000 0.0051769000 0.0093238283 0.0233693104 0.0080253928 2.5405260000 1.2709950000 0.2717530000 0.0000050000 0.9841730000 0.0082740000 109942908 0 1784913920 3.4298968315 4.1590914726 5.1649479866 877 35.0400000000 0.0051118680 0.0093190256 0.0233693104 0.0080208282 3.6024420000 1.2736310000 0.2256740000 0.1040210000 0.9892620000 1.0044400000 109944582 0 1786404864 3.4290096760 4.1587514877 5.1663455963 878 35.0800000000 0.0052246437 0.0093143623 0.0233693104 0.0080164031 2.5411350000 1.2728110000 0.2706490000 0.0000040000 0.9840220000 0.0082490000 109946256 0 1785643008 3.4279835224 4.1590933800 5.1675024033 879 35.1200000000 0.0051958514 0.0093096769 0.0233693104 0.0080118610 2.7034450000 1.2765960000 0.3256430000 0.1044740000 0.9830740000 0.0082460000 109947930 0 1787269120 3.4271342754 4.1580257416 5.1685914993 880 35.1600000000 0.0051589999 0.0093049602 0.0233693104 0.0080076717 2.5625520000 1.2878060000 0.2783680000 0.0000050000 0.9826000000 0.0082510000 109949604 0 1784889344 3.4265069962 4.1589326859 5.1699333191 881 35.2000000000 0.0052261213 0.0093003304 0.0233693104 0.0080038104 3.5920810000 1.2792030000 0.2238020000 0.1042820000 0.9810120000 0.9983700000 109951278 0 1786396672 3.4254601002 4.1588172913 5.1712379456 882 35.2400000000 0.0051149307 0.0092955850 0.0233693104 0.0080004380 2.5463110000 1.2738430000 0.2702310000 0.0000040000 0.9875850000 0.0082930000 109952952 0 1785524224 3.4260122776 4.1547617912 5.1718707085 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 09:49:10 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002920 0.0000002920 0.0000002920 nan 3.1256310000 1.2871140000 0.0674250000 0.1441660000 0.0000100000 1.6262150000 106083959 0 1771466752 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0040127714 0.0020065317 0.0040127714 0.0032323198 1.5082860000 1.3056180000 0.0545000000 0.1397800000 0.0000030000 0.0081010000 108504764 0 1772879872 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0039232424 0.0026454353 0.0040127714 0.0045263772 1.4766890000 1.2696270000 0.0537180000 0.1449380000 0.0000020000 0.0081600000 108506762 0 1774657536 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0033563883 0.0028231735 0.0040127714 0.0050261360 3.0779010000 1.2735220000 0.0535040000 0.1397900000 1.6027680000 0.0081590000 108508764 0 1783164928 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0020580813 0.0026701551 0.0040127714 0.0052619023 4.8744360000 1.2670840000 0.2838270000 0.1392790000 1.5825270000 1.6015390000 108510758 0 1785569280 4.0005683899 4.0062360764 4.0028858185 6 0.2000000000 0.0022257280 0.0025960839 0.0040127714 0.0049518959 3.1652110000 1.2609970000 0.3099500000 0.0000060000 1.5858790000 0.0082050000 108513088 0 1787219968 4.0035066605 3.9963691235 4.0019783974 7 0.2400000000 0.0022985039 0.0025535725 0.0040127714 0.0047228898 3.2702810000 1.2625700000 0.2709370000 0.1394830000 1.5888510000 0.0082570000 108514762 0 1784299520 4.0037336349 3.9863731861 3.9988577366 8 0.2800000000 0.0024037436 0.0025348439 0.0040127714 0.0043794021 3.1429610000 1.2613450000 0.2710850000 0.0000160000 1.6021240000 0.0082060000 108516436 0 1785688064 4.0014567375 3.9884219170 3.9979786873 9 0.3200000000 0.0023832549 0.0025180007 0.0040127714 0.0050602410 4.8573600000 1.2614030000 0.2740160000 0.1393910000 1.5801170000 1.6022290000 108518750 0 1787592704 4.0003561974 3.9923226833 4.0009708405 10 0.3600000000 0.0024723008 0.0025134307 0.0040127714 0.0047859766 3.1362470000 1.2609000000 0.2799970000 0.0000020000 1.5869280000 0.0082190000 108521736 0 1784680448 3.9983148575 3.9848935604 3.9990823269 11 0.4000000000 0.0026058198 0.0025218297 0.0040127714 0.0045839115 3.4043870000 1.2594130000 0.4032430000 0.1450780000 1.5882160000 0.0082110000 108523410 0 1786077184 3.9983010292 3.9888927937 3.9978272915 12 0.4400000000 0.0026437505 0.0025319898 0.0040127714 0.0046245112 3.1349510000 1.2608970000 0.2819720000 0.0000030000 1.5836020000 0.0082680000 108525084 0 1787727872 3.9992921352 3.9987778664 4.0008053780 13 0.4800000000 0.0025806068 0.0025357295 0.0040127714 0.0044316174 4.8512690000 1.2672630000 0.2689670000 0.1394650000 1.5802640000 1.5950880000 108526758 0 1784434688 4.0013046265 3.9965150356 4.0008144379 14 0.5200000000 0.0027118695 0.0025483110 0.0040127714 0.0043591000 3.1858460000 1.2689230000 0.3225680000 0.0000030000 1.5858710000 0.0082610000 108528432 0 1786068992 4.0040988922 3.9890573025 3.9980893135 15 0.5600000000 0.0027320797 0.0025605622 0.0040127714 0.0042933362 3.3969110000 1.2572550000 0.4025710000 0.1394990000 1.5890420000 0.0082960000 108530106 0 1787846656 4.0069055557 3.9907152653 3.9979007244 16 0.6000000000 0.0027423620 0.0025719247 0.0040127714 0.0041517715 3.1333910000 1.2613850000 0.2777410000 0.0000030000 1.5857510000 0.0082900000 108531780 0 1784672256 4.0079178810 3.9920563698 3.9981825352 17 0.6400000000 0.0027842496 0.0025844144 0.0040127714 0.0040370768 4.8715160000 1.2654990000 0.2786550000 0.1397200000 1.5862520000 1.6011350000 108534734 0 1786068992 4.0076704025 3.9883072376 3.9963226318 18 0.6800000000 0.0028498175 0.0025991590 0.0040127714 0.0039179233 3.1759480000 1.2646400000 0.3101390000 0.0000040000 1.5925650000 0.0083640000 108539032 0 1788100608 4.0069384575 3.9893968105 3.9949452877 19 0.7200000000 0.0028617827 0.0026129813 0.0040127714 0.0039445254 3.3293390000 1.2652460000 0.3236750000 0.1399330000 1.5918270000 0.0084140000 108540706 0 1784926208 4.0073871613 3.9935777187 3.9951608181 20 0.7600000000 0.0029032738 0.0026274959 0.0040127714 0.0042035944 3.1318770000 1.2591520000 0.2755200000 0.0000030000 1.5886640000 0.0082630000 108542380 0 1786585088 4.0069413185 3.9922835827 3.9925365448 21 0.8000000000 0.0029300905 0.0026419052 0.0040127714 0.0043503276 4.8716810000 1.2650400000 0.2753380000 0.1403810000 1.5856310000 1.6050270000 108544054 0 1785434112 4.0093951225 3.9955039024 3.9927725792 22 0.8400000000 0.0029452394 0.0026556931 0.0040127714 0.0042738572 3.2199130000 1.2680970000 0.3566140000 0.0000050000 1.5867270000 0.0082120000 108545728 0 1786957824 4.0094900131 3.9983544350 3.9931786060 23 0.8800000000 0.0030378522 0.0026723087 0.0040127714 0.0042448744 3.2663460000 1.2613850000 0.2609300000 0.1401660000 1.5953320000 0.0082660000 108547402 0 1784672256 4.0121722221 3.9920444489 3.9892232418 24 0.9200000000 0.0032717185 0.0026972841 0.0040127714 0.0042405192 3.1579830000 1.2640450000 0.2836050000 0.0000020000 1.6017910000 0.0082740000 108549076 0 1786195968 4.0143861771 3.9935014248 3.9894285202 25 0.9600000000 0.0032618549 0.0027198670 0.0040127714 0.0041528128 4.8835250000 1.2635650000 0.2726820000 0.1401530000 1.5963900000 1.6104450000 108550750 0 1788100608 4.0145554543 3.9904434681 3.9862995148 26 1.0000000000 0.0033034820 0.0027423137 0.0040127714 0.0040694733 3.1652960000 1.2602460000 0.2816260000 0.0000030000 1.6149100000 0.0082010000 108552424 0 1785180160 4.0128374100 3.9902224541 3.9853107929 27 1.0400000000 0.0033007052 0.0027629949 0.0040127714 0.0040029011 3.3330420000 1.2638600000 0.3170940000 0.1402970000 1.6032690000 0.0082100000 108554098 0 1786703872 4.0138897896 3.9860484600 3.9828357697 28 1.0800000000 0.0033158856 0.0027827410 0.0040127714 0.0039327680 3.1712520000 1.2687830000 0.2795500000 0.0000030000 1.6142820000 0.0083400000 108555772 0 1785307136 4.0126276016 3.9840130806 3.9814455509 29 1.1200000000 0.0033202458 0.0028012756 0.0040127714 0.0039431738 4.9166530000 1.2648630000 0.2655610000 0.1406480000 1.6198930000 1.6253760000 108557446 0 1787084800 4.0137238503 3.9820182323 3.9802532196 30 1.1600000000 0.0034097221 0.0028215572 0.0040127714 0.0039087800 3.1703090000 1.2613460000 0.2771790000 0.0000020000 1.6231190000 0.0083130000 108559120 0 1784553472 4.0170245171 3.9830451012 3.9798843861 31 1.2000000000 0.0035719061 0.0028457620 0.0040127714 0.0039119562 3.2602740000 1.2652290000 0.2275310000 0.1410170000 1.6179090000 0.0082450000 108560794 0 1786068992 4.0219502449 3.9843261242 3.9785234928 32 1.2400000000 0.0035986223 0.0028692889 0.0040127714 0.0039571916 3.1605200000 1.2689930000 0.2642100000 0.0000020000 1.6187580000 0.0082280000 108562468 0 1787973632 4.0223512650 3.9875774384 3.9773926735 33 1.2800000000 0.0036618249 0.0028933051 0.0040127714 0.0041813123 4.9047440000 1.2600930000 0.2642880000 0.1411060000 1.6154250000 1.6234890000 108566702 0 1784418304 4.0236768723 3.9915442467 3.9773106575 34 1.3200000000 0.0036396727 0.0029152571 0.0040127714 0.0043691429 3.1759130000 1.2629970000 0.2600850000 0.0000050000 1.6442480000 0.0081790000 108573624 0 1785942016 4.0318427086 3.9939959049 3.9749903679 35 1.3600000000 0.0035959275 0.0029347048 0.0040127714 0.0043071850 3.3059920000 1.2661120000 0.2616990000 0.1413320000 1.6283240000 0.0081850000 108575298 0 1787846656 4.0310935974 3.9926095009 3.9733877182 36 1.4000000000 0.0036858793 0.0029555708 0.0040127714 0.0042547053 3.1482300000 1.2704500000 0.2250910000 0.0000180000 1.6440820000 0.0082630000 108576972 0 1784545280 4.0315022469 3.9903364182 3.9700069427 37 1.4400000000 0.0035902276 0.0029727237 0.0040127714 0.0041965139 4.9636870000 1.2747870000 0.2597900000 0.1423710000 1.6368970000 1.6494780000 108578646 0 1785942016 4.0340147018 3.9892373085 3.9676899910 38 1.4800000000 0.0038709145 0.0029963603 0.0040127714 0.0041397781 3.1990590000 1.2666430000 0.2723860000 0.0000040000 1.6513570000 0.0082660000 108580320 0 1787846656 4.0341849327 3.9894330502 3.9674475193 39 1.5200000000 0.0037616780 0.0030159838 0.0040127714 0.0041058759 3.3367240000 1.2682030000 0.2719140000 0.1420600000 1.6458370000 0.0083470000 108581994 0 1784553472 4.0347752571 3.9901700020 3.9665145874 40 1.5600000000 0.0039191856 0.0030385638 0.0040127714 0.0043025131 3.2072900000 1.2677290000 0.2788730000 0.0000040000 1.6520800000 0.0082400000 108583668 0 1785950208 4.0378737450 3.9905858040 3.9656794071 41 1.6000000000 0.0039454997 0.0030606842 0.0040127714 0.0045480703 4.9813160000 1.2679040000 0.2593630000 0.1428310000 1.6502950000 1.6605490000 108585342 0 1787719680 4.0434808731 3.9923052788 3.9650857449 42 1.6400000000 0.0044117551 0.0030928526 0.0044117551 0.0045182077 3.1998980000 1.2695030000 0.2615900000 0.0000040000 1.6601600000 0.0082900000 108587016 0 1784291328 4.0444545746 3.9923734665 3.9638378620 43 1.6800000000 0.0042237355 0.0031191522 0.0044117551 0.0044995174 3.3376220000 1.2661380000 0.2705230000 0.1431270000 1.6491670000 0.0082600000 108588690 0 1785815040 4.0460581779 3.9921064377 3.9622678757 44 1.7200000000 0.0044255182 0.0031488423 0.0044255182 0.0044687707 3.2128310000 1.2676920000 0.2770930000 0.0000040000 1.6594920000 0.0081890000 108590364 0 1787736064 4.0482454300 3.9931316376 3.9621040821 45 1.7600000000 0.0045949672 0.0031809784 0.0045949672 0.0046641275 4.9973600000 1.2677550000 0.2605310000 0.1435750000 1.6570820000 1.6680430000 108592038 0 1784291328 4.0502977371 3.9947748184 3.9609951973 46 1.8000000000 0.0046160738 0.0032121761 0.0046160738 0.0047516532 3.3033270000 1.3028090000 0.3210040000 0.0000050000 1.6709250000 0.0082120000 108593712 0 1785815040 4.0517005920 3.9956302643 3.9602918625 47 1.8400000000 0.0042895125 0.0032350982 0.0046160738 0.0047469249 3.3477110000 1.2690360000 0.2712000000 0.1439040000 1.6549150000 0.0082800000 108595386 0 1787592704 4.0530548096 3.9980163574 3.9598884583 48 1.8800000000 0.0045014708 0.0032614810 0.0046160738 0.0047342330 3.2133030000 1.2702840000 0.2616470000 0.0000030000 1.6727670000 0.0081850000 108597060 0 1784545280 4.0552101135 3.9992558956 3.9601180553 49 1.9200000000 0.0044528679 0.0032857950 0.0046160738 0.0047598009 5.0312480000 1.2709880000 0.2708600000 0.1443370000 1.6599510000 1.6847140000 108598734 0 1786077184 4.0561499596 3.9968554974 3.9582495689 50 1.9600000000 0.0045659491 0.0033113981 0.0046160738 0.0047330333 3.2629370000 1.2707150000 0.3113630000 0.0000030000 1.6721460000 0.0083200000 108600408 0 1787854848 4.0514616966 3.9992833138 3.9562702179 51 2.0000000000 0.0044319918 0.0033333705 0.0046160738 0.0047263124 3.3670900000 1.2757520000 0.2713980000 0.1449310000 1.6663670000 0.0082210000 108602082 0 1784545280 4.0505089760 4.0037045479 3.9571368694 52 2.0400000000 0.0046651941 0.0033589825 0.0046651941 0.0047018593 3.2188590000 1.2692420000 0.2617200000 0.0000040000 1.6792340000 0.0082620000 108603756 0 1785942016 4.0509786606 4.0014719963 3.9568984509 53 2.0800000000 0.0045975368 0.0033823514 0.0046651941 0.0046665297 5.1387230000 1.2780230000 0.3558020000 0.1456920000 1.6670270000 1.6917660000 108605430 0 1787846656 4.0511894226 3.9970266819 3.9545514584 54 2.1200000000 0.0045515518 0.0034040033 0.0046651941 0.0046837771 3.2642050000 1.2699610000 0.3089570000 0.0000020000 1.6766160000 0.0082480000 108607104 0 1784418304 4.0513310432 3.9984078407 3.9549872875 55 2.1600000000 0.0044735703 0.0034234500 0.0046651941 0.0046735819 3.3789820000 1.2768900000 0.2707120000 0.1461650000 1.6765240000 0.0082530000 108608778 0 1785942016 4.0520610809 4.0006961823 3.9550163746 56 2.2000000000 0.0043945801 0.0034407916 0.0046651941 0.0046762054 3.2861750000 1.2694630000 0.3206940000 0.0000030000 1.6872900000 0.0082040000 108610452 0 1787719680 4.0533785820 3.9998571873 3.9541127682 57 2.2400000000 0.0045140395 0.0034596205 0.0046651941 0.0046966911 5.0612600000 1.2725880000 0.2594980000 0.1468980000 1.6775260000 1.7043140000 108612126 0 1784291328 4.0539035797 3.9971239567 3.9518072605 58 2.2800000000 0.0045527942 0.0034784683 0.0046651941 0.0048540683 3.2421300000 1.2698950000 0.2718070000 0.0000030000 1.6918060000 0.0081840000 108613800 0 1785950208 4.0575060844 3.9987406731 3.9523811340 59 2.3200000000 0.0047499174 0.0035000183 0.0047499174 0.0050196567 3.3830770000 1.2764830000 0.2602450000 0.1474730000 1.6897450000 0.0086900000 108615474 0 1787719680 4.0615081787 4.0015850067 3.9516859055 60 2.3600000000 0.0049295914 0.0035238445 0.0049295914 0.0050715313 3.3048770000 1.2771320000 0.3185510000 0.0000030000 1.7004140000 0.0082560000 108617148 0 1784418304 4.0651254654 3.9972069263 3.9490852356 61 2.4000000000 0.0049403422 0.0035470658 0.0049403422 0.0050616553 5.1107420000 1.2737610000 0.2686730000 0.1484730000 1.7032340000 1.7161440000 108618822 0 1785815040 4.0648918152 3.9946091175 3.9476447105 62 2.4400000000 0.0046706637 0.0035651883 0.0049403422 0.0050981442 3.2704600000 1.2718110000 0.2720090000 0.0000030000 1.7179540000 0.0082340000 108620496 0 1787592704 4.0665531158 3.9957418442 3.9481971264 63 2.4800000000 0.0050036944 0.0035880218 0.0050036944 0.0051365410 3.4001220000 1.2747120000 0.2698700000 0.1488910000 1.6979990000 0.0081770000 108622170 0 1784545280 4.0733299255 3.9973235130 3.9481494427 64 2.5200000000 0.0049076881 0.0036086415 0.0050036944 0.0051106729 3.2571640000 1.2725400000 0.2649660000 0.0000030000 1.7109960000 0.0081710000 108623844 0 1785942016 4.0755014420 3.9931840897 3.9442296028 65 2.5600000000 0.0049645752 0.0036295021 0.0050036944 0.0051015022 5.3304390000 1.2710730000 0.4557720000 0.1497320000 1.7224300000 1.7309360000 108630638 0 1787846656 4.0765681267 3.9943201542 3.9443922043 66 2.6000000000 0.0050748531 0.0036514013 0.0050748531 0.0050634301 3.2249440000 1.2716500000 0.2233320000 0.0000030000 1.7211760000 0.0082590000 108642808 0 1784545280 4.0738797188 3.9897677898 3.9425456524 67 2.6400000000 0.0051379795 0.0036735891 0.0051379795 0.0050955579 3.4074080000 1.2726110000 0.2590230000 0.1505020000 1.7165460000 0.0081810000 108644482 0 1786077184 4.0741090775 3.9883649349 3.9407329559 68 2.6800000000 0.0051945224 0.0036959557 0.0051945224 0.0051675742 3.3237480000 1.2801080000 0.3073950000 0.0000020000 1.7275700000 0.0081860000 108646156 0 1787854848 4.0791978836 3.9858884811 3.9403719902 69 2.7200000000 0.0049870391 0.0037146671 0.0051945224 0.0051844887 5.1592310000 1.2719700000 0.2581060000 0.1513030000 1.7331990000 1.7441450000 108647830 0 1784418304 4.0803499222 3.9865257740 3.9391894341 70 2.7600000000 0.0050978372 0.0037344266 0.0051945224 0.0052330789 3.2813910000 1.2722700000 0.2609490000 0.0000030000 1.7394140000 0.0082530000 108649504 0 1785942016 4.0830755234 3.9879860878 3.9385199547 71 2.8000000000 0.0052164793 0.0037553006 0.0052164793 0.0052793656 3.4239210000 1.2728010000 0.2598580000 0.1517870000 1.7306950000 0.0082390000 108651178 0 1787719680 4.0858325958 3.9886486530 3.9367847443 72 2.8400000000 0.0051630540 0.0037748528 0.0052164793 0.0052989830 3.2378630000 1.2770490000 0.2139380000 0.0000020000 1.7381700000 0.0081870000 108652852 0 1784291328 4.0873804092 3.9884064198 3.9358890057 73 2.8800000000 0.0051232595 0.0037933241 0.0052164793 0.0053405903 5.1362570000 1.2723060000 0.2133570000 0.1524920000 1.7415770000 1.7559950000 108654526 0 1785815040 4.0898027420 3.9910202026 3.9336428642 74 2.9200000000 0.0051765055 0.0038120157 0.0052164793 0.0054583045 3.2934560000 1.2726200000 0.2615310000 0.0000040000 1.7504570000 0.0082560000 108656200 0 1787719680 4.0917606354 3.9908297062 3.9306180477 75 2.9600000000 0.0052650268 0.0038313892 0.0052650268 0.0055000720 3.4357300000 1.2733250000 0.2593540000 0.1530430000 1.7412790000 0.0081760000 108657874 0 1784545280 4.0974507332 3.9907920361 3.9291729927 76 3.0000000000 0.0052186688 0.0038496429 0.0052650268 0.0055206647 3.2485060000 1.2781420000 0.2134420000 0.0000040000 1.7481140000 0.0082420000 108659548 0 1786068992 4.1008591652 3.9922549725 3.9274497032 77 3.0400000000 0.0051018842 0.0038659058 0.0052650268 0.0055431723 5.1706950000 1.2738700000 0.2215990000 0.1535600000 1.7524420000 1.7677930000 108661222 0 1785585664 4.1035289764 3.9928443432 3.9264137745 78 3.0800000000 0.0050238110 0.0038807507 0.0052650268 0.0055144954 3.2971210000 1.2698960000 0.2601060000 0.0000040000 1.7584160000 0.0081340000 108662896 0 1785180160 4.1065611839 3.9903264046 3.9228413105 79 3.1200000000 0.0049572675 0.0038943775 0.0052650268 0.0055357411 3.4025960000 1.2730850000 0.2101600000 0.1541740000 1.7564430000 0.0081660000 108664570 0 1786703872 4.1102128029 3.9917142391 3.9223747253 80 3.1600000000 0.0049892832 0.0039080638 0.0052650268 0.0055197046 3.3164880000 1.2807450000 0.2685990000 0.0000040000 1.7583220000 0.0082100000 108666244 0 1784926208 4.1140680313 3.9913563728 3.9194998741 81 3.2000000000 0.0049953857 0.0039214875 0.0052650268 0.0054985061 5.1805080000 1.2728870000 0.2056900000 0.1547800000 1.7640720000 1.7825240000 108667918 0 1786195968 4.1196789742 3.9899172783 3.9178886414 82 3.2400000000 0.0049624629 0.0039341824 0.0052650268 0.0054714208 3.3094300000 1.2728390000 0.2550620000 0.0000040000 1.7728090000 0.0081170000 108669592 0 1785561088 4.1236543655 3.9884650707 3.9155747890 83 3.2800000000 0.0050063250 0.0039470997 0.0052650268 0.0054583454 3.4515710000 1.2721800000 0.2540690000 0.1553730000 1.7613130000 0.0080500000 108671266 0 1787084800 4.1255664825 3.9883008003 3.9134457111 84 3.3200000000 0.0050155809 0.0039598198 0.0052650268 0.0054345661 3.2686280000 1.2814570000 0.2081370000 0.0000030000 1.7703660000 0.0080350000 108672940 0 1784680448 4.1318182945 3.9879744053 3.9106562138 85 3.3600000000 0.0050340910 0.0039724582 0.0052650268 0.0054049757 5.1976130000 1.2728030000 0.2070010000 0.1556960000 1.7695790000 1.7919220000 108674614 0 1786314752 4.1422972679 3.9913556576 3.9105970860 86 3.4000000000 0.0050735450 0.0039852616 0.0052650268 0.0054190471 3.3104440000 1.2714790000 0.2538990000 0.0000040000 1.7763860000 0.0080090000 108676288 0 1785815040 4.1448655128 3.9936747551 3.9082915783 87 3.4400000000 0.0051057683 0.0039981410 0.0052650268 0.0054137709 3.4476320000 1.2748170000 0.2426720000 0.1560400000 1.7653710000 0.0081210000 108677962 0 1787211776 4.1470656395 3.9930250645 3.9054136276 88 3.4800000000 0.0050740670 0.0040103674 0.0052650268 0.0053888448 3.2754620000 1.2839160000 0.2180790000 0.0000040000 1.7646760000 0.0081090000 108679636 0 1784807424 4.1524453163 3.9958250523 3.9047403336 89 3.5200000000 0.0050697261 0.0040222703 0.0052650268 0.0053717268 5.2365360000 1.2722680000 0.2424340000 0.1563620000 1.7691060000 1.7957180000 108681310 0 1786441728 4.1554970741 3.9961383343 3.9035372734 90 3.5600000000 0.0053034946 0.0040365061 0.0053034946 0.0053449906 3.3215160000 1.2739260000 0.2630790000 0.0000040000 1.7759120000 0.0079510000 108682984 0 1785552896 4.1586503983 3.9964368343 3.9019556046 91 3.6000000000 0.0053609977 0.0040510610 0.0053609977 0.0053807305 3.4690100000 1.2735900000 0.2637120000 0.1564380000 1.7665950000 0.0080140000 108684658 0 1787076608 4.1651024818 3.9967052937 3.9009866714 92 3.6400000000 0.0052826237 0.0040644475 0.0053609977 0.0054539238 3.2996460000 1.2742760000 0.2543480000 0.0000040000 1.7623060000 0.0080180000 108686332 0 1784807424 4.1743283272 3.9995200634 3.9010283947 93 3.6800000000 0.0052634985 0.0040773406 0.0053609977 0.0054680188 5.2424140000 1.2771240000 0.2584670000 0.1570360000 1.7577120000 1.7914180000 108688006 0 1786441728 4.1824026108 4.0035538673 3.8995795250 94 3.7200000000 0.0052424734 0.0040897356 0.0053609977 0.0054449555 3.2582030000 1.2743530000 0.2125460000 0.0000050000 1.7627610000 0.0079090000 108689680 0 1785679872 4.1906847954 4.0027942657 3.8970134258 95 3.7600000000 0.0052336399 0.0041017767 0.0053609977 0.0054176891 3.4364720000 1.2731290000 0.2386780000 0.1564750000 1.7595650000 0.0079720000 108691354 0 1787211776 4.1967449188 4.0028204918 3.8945453167 96 3.8000000000 0.0052941893 0.0041141977 0.0053609977 0.0054025109 3.2473600000 1.2749260000 0.2044060000 0.0000030000 1.7593500000 0.0079680000 108693028 0 1784799232 4.2042822838 4.0015487671 3.8925466537 97 3.8400000000 0.0052658548 0.0041260704 0.0053609977 0.0053765825 5.1859430000 1.2732690000 0.2100150000 0.1566080000 1.7548960000 1.7904890000 108694702 0 1786441728 4.2121472359 4.0030889511 3.8894484043 98 3.8800000000 0.0052937861 0.0041379859 0.0053609977 0.0053498221 3.2943580000 1.2787150000 0.2512700000 0.0000030000 1.7557750000 0.0079290000 108696376 0 1785679872 4.2206368446 4.0032143593 3.8886246681 99 3.9200000000 0.0052947011 0.0041496699 0.0053609977 0.0053599080 3.3998560000 1.2716620000 0.2045280000 0.1565420000 1.7583670000 0.0080790000 108698050 0 1787076608 4.2288546562 4.0025663376 3.8867127895 100 3.9600000000 0.0053558405 0.0041617316 0.0053609977 0.0053348276 3.2878110000 1.2721060000 0.2515430000 0.0000040000 1.7555710000 0.0079050000 108699724 0 1784918016 4.2364687920 4.0030870438 3.8862869740 101 4.0000000000 0.0053395927 0.0041733936 0.0053609977 0.0053242278 5.2324210000 1.2785070000 0.2492400000 0.1572500000 1.7555110000 1.7911440000 108701398 0 1786441728 4.2450776100 4.0052161217 3.8849749565 102 4.0400000000 0.0054647503 0.0041860539 0.0054647503 0.0053349134 3.2933230000 1.2787270000 0.2517710000 0.0000050000 1.7541940000 0.0079450000 108703072 0 1785696256 4.2498030663 4.0046334267 3.8829152584 103 4.0800000000 0.0054654814 0.0041984755 0.0054654814 0.0053095867 3.4488850000 1.2717350000 0.2544340000 0.1564170000 1.7576590000 0.0079440000 108704746 0 1787203584 4.2578473091 4.0080614090 3.8836951256 104 4.1200000000 0.0054948498 0.0042109407 0.0054948498 0.0052849076 3.2910790000 1.2758580000 0.2544990000 0.0000040000 1.7520800000 0.0079100000 108706420 0 1784815616 4.2683148384 4.0106930733 3.8829586506 105 4.1600000000 0.0055246069 0.0042234518 0.0055246069 0.0052771440 5.1862720000 1.2872220000 0.2064480000 0.1563150000 1.7485520000 1.7870440000 108708094 0 1786441728 4.2748765945 4.0120434761 3.8827342987 106 4.2000000000 0.0056006224 0.0042364440 0.0056006224 0.0052893331 3.2939490000 1.2799240000 0.2528930000 0.0000050000 1.7524680000 0.0079490000 108709768 0 1785679872 4.2819299698 4.0102224350 3.8801748753 107 4.2400000000 0.0055412622 0.0042486385 0.0056006224 0.0052667560 3.4064210000 1.2742870000 0.2088970000 0.1560640000 1.7585290000 0.0079020000 108711442 0 1787203584 4.2897663116 4.0092849731 3.8789689541 108 4.2800000000 0.0055894232 0.0042610532 0.0056006224 0.0052508037 3.2900160000 1.2720450000 0.2571360000 0.0000040000 1.7521090000 0.0079610000 108713116 0 1785188352 4.2984471321 4.0095062256 3.8772029877 109 4.3200000000 0.0055090738 0.0042725029 0.0056006224 0.0052309003 5.2151220000 1.2808190000 0.2496470000 0.1557710000 1.7455410000 1.7826330000 108714790 0 1786822656 4.3154878616 4.0090909004 3.8746531010 110 4.3600000000 0.0056746425 0.0042852497 0.0056746425 0.0052282539 3.2331620000 1.2779280000 0.2012380000 0.0000040000 1.7451980000 0.0080010000 108716464 0 1784934400 4.3276209831 4.0103373528 3.8738794327 111 4.4000000000 0.0056739897 0.0042977608 0.0056746425 0.0052047993 3.4471420000 1.2749120000 0.2570210000 0.1554140000 1.7510080000 0.0080070000 108718138 0 1786314752 4.3374385834 4.0094943047 3.8721792698 112 4.4400000000 0.0056494251 0.0043098293 0.0056746425 0.0051897729 3.2417200000 1.2723790000 0.2129900000 0.0000040000 1.7477170000 0.0079180000 108719812 0 1785679872 4.3432354927 4.0052833557 3.8694489002 113 4.4800000000 0.0056229881 0.0043214501 0.0056746425 0.0051665628 5.1757350000 1.2772870000 0.2086830000 0.1571650000 1.7524340000 1.7794340000 108721486 0 1787211776 4.3522467613 4.0045695305 3.8688044548 114 4.5200000000 0.0056888205 0.0043334446 0.0056888205 0.0051502724 3.2851510000 1.2761410000 0.2538660000 0.0000030000 1.7464300000 0.0079900000 108723160 0 1784926208 4.3631143570 4.0046486855 3.8679349422 115 4.5600000000 0.0056267232 0.0043446905 0.0056888205 0.0051372369 3.4477360000 1.2722330000 0.2545670000 0.1550750000 1.7571450000 0.0079810000 108724834 0 1786441728 4.3730731010 4.0026659966 3.8666353226 116 4.6000000000 0.0056091659 0.0043555912 0.0056888205 0.0051171264 3.2914720000 1.2714100000 0.2619270000 0.0000030000 1.7494560000 0.0079450000 108726508 0 1785552896 4.3809514046 3.9996457100 3.8650288582 117 4.6400000000 0.0056403591 0.0043665721 0.0056888205 0.0051212822 5.1832200000 1.2793960000 0.2159990000 0.1549510000 1.7469890000 1.7851230000 108728182 0 1787203584 4.3884057999 3.9971787930 3.8638873100 118 4.6800000000 0.0056635765 0.0043775636 0.0056888205 0.0051346305 3.2361550000 1.2724440000 0.2058820000 0.0000020000 1.7491170000 0.0079410000 108729856 0 1784791040 4.3975467682 3.9972615242 3.8635478020 119 4.7200000000 0.0056115785 0.0043879335 0.0056888205 0.0051731929 3.4356710000 1.2713700000 0.2515560000 0.1543650000 1.7495740000 0.0079370000 108731530 0 1786314752 4.4116563797 3.9979147911 3.8654174805 120 4.7600000000 0.0057089161 0.0043989417 0.0057089161 0.0051517705 3.2797890000 1.2709810000 0.2559080000 0.0000030000 1.7441510000 0.0079570000 108733204 0 1785679872 4.4229149818 3.9999063015 3.8668241501 121 4.8000000000 0.0056681833 0.0044094313 0.0057089161 0.0051475345 5.2009220000 1.2693260000 0.2541990000 0.1542160000 1.7454700000 1.7769400000 108734878 0 1787076608 4.4314246178 3.9985044003 3.8652968407 122 4.8400000000 0.0057453415 0.0044203814 0.0057453415 0.0051463419 3.2329430000 1.2750760000 0.2072020000 0.0000020000 1.7418320000 0.0080390000 108736552 0 1785044992 4.4404873848 3.9990701675 3.8647594452 123 4.8800000000 0.0056935539 0.0044307324 0.0057453415 0.0051261386 3.3853350000 1.2750620000 0.2062380000 0.1592740000 1.7360040000 0.0079590000 108738226 0 1786449920 4.4517550468 4.0015182495 3.8667833805 124 4.9200000000 0.0058000023 0.0044417749 0.0058000023 0.0051069254 3.2725850000 1.2711500000 0.2518920000 0.0000030000 1.7407950000 0.0079460000 108739900 0 1785688064 4.4581680298 4.0030899048 3.8700363636 125 4.9600000000 0.0057393257 0.0044521553 0.0058000023 0.0050988927 5.1909570000 1.2755920000 0.2513180000 0.1531820000 1.7431590000 1.7668990000 108741574 0 1787076608 4.4616293907 4.0026497841 3.8714597225 126 5.0000000000 0.0058959113 0.0044636137 0.0058959113 0.0050852471 3.2155790000 1.2738940000 0.2044910000 0.0000030000 1.7283470000 0.0080370000 108743248 0 1784791040 4.4710617065 4.0028610229 3.8731489182 127 5.0400000000 0.0058941511 0.0044748777 0.0058959113 0.0050679437 3.4298400000 1.2737890000 0.2698170000 0.1525630000 1.7248710000 0.0079690000 108744922 0 1786441728 4.4812288284 4.0027222633 3.8753187656 128 5.0800000000 0.0059098229 0.0044860883 0.0059098229 0.0050619820 3.2704500000 1.2776620000 0.2564780000 0.0000030000 1.7274630000 0.0080140000 108746596 0 1785552896 4.4930205345 4.0041375160 3.8786976337 129 5.1200000000 0.0058653597 0.0044967803 0.0059098229 0.0050543121 5.1949530000 1.2721140000 0.2992110000 0.1518640000 1.7170620000 1.7537970000 108758510 0 1787203584 4.5040831566 4.0054645538 3.8822600842 130 5.1600000000 0.0059704236 0.0045081160 0.0059704236 0.0050364698 3.2534550000 1.2765520000 0.2524930000 0.0000030000 1.7155960000 0.0079820000 108781176 0 1784537088 4.5107889175 4.0063886642 3.8847126961 131 5.2000000000 0.0060052737 0.0045195447 0.0060052737 0.0050724308 3.3964270000 1.2793460000 0.2443180000 0.1510880000 1.7127610000 0.0080390000 108782850 0 1786187776 4.5174379349 4.0055346489 3.8878500462 132 5.2400000000 0.0059300405 0.0045302303 0.0060052737 0.0050580694 3.2635210000 1.2720800000 0.2656560000 0.0000030000 1.7168750000 0.0079930000 108784524 0 1788100608 4.5281476974 4.0060276985 3.8916606903 133 5.2800000000 0.0058729006 0.0045403255 0.0060052737 0.0050390085 5.1350560000 1.2788760000 0.2545060000 0.1505160000 1.7067380000 1.7435740000 108786198 0 1785180160 4.5387206078 4.0069260597 3.8960809708 134 5.3200000000 0.0059298724 0.0045506953 0.0060052737 0.0050862662 3.2522660000 1.2778480000 0.2562780000 0.0000030000 1.7091770000 0.0081280000 108787872 0 1786712064 4.5474166870 4.0064826012 3.8987255096 135 5.3600000000 0.0059755654 0.0045612499 0.0060052737 0.0051003836 3.3458460000 1.2852590000 0.2004860000 0.1496270000 1.7015760000 0.0080200000 108789546 0 1784664064 4.5571312904 4.0076584816 3.9021744728 136 5.4000000000 0.0059771221 0.0045716607 0.0060052737 0.0051268630 3.2463330000 1.2754400000 0.2596630000 0.0000030000 1.7022530000 0.0080980000 108791220 0 1786314752 4.5712308884 4.0152897835 3.9084393978 137 5.4400000000 0.0059501929 0.0045817230 0.0060052737 0.0051231958 5.0618200000 1.2779940000 0.2104930000 0.1491340000 1.6956950000 1.7276380000 108792894 0 1785425920 4.5763235092 4.0192775726 3.9122960567 138 5.4800000000 0.0060420046 0.0045923047 0.0060420046 0.0051686436 3.2417530000 1.2727620000 0.2666230000 0.0000030000 1.6933690000 0.0080290000 108794568 0 1786822656 4.5800738335 4.0181002617 3.9150669575 139 5.5200000000 0.0060398532 0.0046027187 0.0060420046 0.0051501059 3.3908160000 1.2798920000 0.2622440000 0.1482820000 1.6913910000 0.0080830000 108796242 0 1784680448 4.5889396667 4.0188279152 3.9200241566 140 5.5600000000 0.0060991556 0.0046134076 0.0060991556 0.0051337443 3.2344390000 1.2717280000 0.2613300000 0.0000030000 1.6924000000 0.0081060000 108797916 0 1786187776 4.5973229408 4.0202054977 3.9251697063 141 5.6000000000 0.0060553700 0.0046236343 0.0060991556 0.0051156887 5.1030510000 1.2820440000 0.2702720000 0.1479440000 1.6850150000 1.7168950000 108799590 0 1788227584 4.6059932709 4.0210461617 3.9299957752 142 5.6400000000 0.0060183299 0.0046334561 0.0060991556 0.0051008176 3.2253270000 1.2744210000 0.2588990000 0.0000020000 1.6828770000 0.0081620000 108801264 0 1784934400 4.6169342995 4.0214128494 3.9351553917 143 5.6800000000 0.0060173008 0.0046431333 0.0060991556 0.0050910835 3.4025900000 1.3080920000 0.2580210000 0.1471850000 1.6802120000 0.0080820000 108802938 0 1786441728 4.6258587837 4.0235233307 3.9404747486 144 5.7200000000 0.0060309907 0.0046527712 0.0060991556 0.0051100650 3.2238280000 1.2729590000 0.2597580000 0.0000030000 1.6820000000 0.0081590000 108804612 0 1785442304 4.6318893433 4.0234813690 3.9449138641 145 5.7600000000 0.0060101864 0.0046621327 0.0060991556 0.0050973025 5.0124350000 1.2718180000 0.2161080000 0.1464250000 1.6738490000 1.7032810000 108806286 0 1786949632 4.6398377419 4.0239601135 3.9502167702 146 5.8000000000 0.0060380870 0.0046715570 0.0060991556 0.0050822984 3.2159370000 1.3091990000 0.2235410000 0.0000040000 1.6741540000 0.0080860000 108807960 0 1784680448 4.6495952606 4.0255808830 3.9563992023 147 5.8400000000 0.0059330729 0.0046801388 0.0060991556 0.0050650692 3.3621840000 1.2735780000 0.2651210000 0.1452760000 1.6690960000 0.0081420000 108809634 0 1786187776 4.6589207649 4.0294561386 3.9625163078 148 5.8800000000 0.0060393102 0.0046893224 0.0060991556 0.0050885433 3.2113080000 1.2698020000 0.2589050000 0.0000030000 1.6735470000 0.0081060000 108811308 0 1787965440 4.6632227898 4.0291461945 3.9671945572 149 5.9200000000 0.0060896403 0.0046987205 0.0060991556 0.0050735986 5.0400960000 1.2719580000 0.2651220000 0.1447560000 1.6644010000 1.6928690000 108812982 0 1784934400 4.6690368652 4.0285825729 3.9715540409 150 5.9600000000 0.0060349382 0.0047076286 0.0060991556 0.0050797567 3.2084720000 1.2756630000 0.2612530000 0.0000030000 1.6623810000 0.0081660000 108814656 0 1786568704 4.6769723892 4.0318031311 3.9775695801 151 6.0000000000 0.0059632757 0.0047159441 0.0060991556 0.0050765737 3.3703060000 1.2816420000 0.2730930000 0.1444110000 1.6619850000 0.0081880000 108816330 0 1785688064 4.6847882271 4.0338435173 3.9822685719 152 6.0400000000 0.0059673875 0.0047241773 0.0060991556 0.0050837903 3.1621390000 1.2729220000 0.2158890000 0.0000030000 1.6640500000 0.0081170000 108818004 0 1787076608 4.6980023384 4.0334296227 3.9913582802 153 6.0800000000 0.0059739244 0.0047323456 0.0060991556 0.0051028020 5.0300950000 1.2713950000 0.2760940000 0.1437140000 1.6559210000 1.6819920000 108819678 0 1784537088 4.7057681084 4.0345129967 3.9967329502 154 6.1200000000 0.0059562027 0.0047402927 0.0060991556 0.0050864624 3.2438470000 1.2740890000 0.3080360000 0.0000030000 1.6524920000 0.0081550000 108821352 0 1786060800 4.7119526863 4.0361466408 4.0017738342 155 6.1600000000 0.0059409365 0.0047480388 0.0060991556 0.0050860708 3.3077110000 1.2734000000 0.2246200000 0.1482970000 1.6521510000 0.0082090000 108823026 0 1787981824 4.7162342072 4.0360169411 4.0059814453 156 6.2000000000 0.0059451107 0.0047557123 0.0060991556 0.0050986726 3.2023240000 1.2748600000 0.2662610000 0.0000050000 1.6519360000 0.0082310000 108824700 0 1784553472 4.7249398232 4.0374894142 4.0115885735 157 6.2400000000 0.0059602875 0.0047633848 0.0060991556 0.0051091614 5.0439680000 1.2788980000 0.3114830000 0.1421510000 1.6448700000 1.6655850000 108826374 0 1785933824 4.7316102982 4.0387167931 4.0176305771 158 6.2800000000 0.0059713875 0.0047710304 0.0060991556 0.0051186501 3.1882970000 1.2753050000 0.2615540000 0.0000050000 1.6422340000 0.0082310000 108828048 0 1787965440 4.7362084389 4.0396423340 4.0234012604 159 6.3200000000 0.0059596072 0.0047785057 0.0060991556 0.0051481155 3.3445910000 1.2793230000 0.2650320000 0.1432350000 1.6477570000 0.0081800000 108829722 0 1784451072 4.7435493469 4.0417428017 4.0302281380 160 6.3600000000 0.0058959364 0.0047854896 0.0060991556 0.0052037550 3.1996710000 1.2924830000 0.2635960000 0.0000040000 1.6342670000 0.0082240000 108831396 0 1785815040 4.7568807602 4.0455393791 4.0446176529 161 6.4000000000 0.0059668962 0.0047928276 0.0060991556 0.0052268877 4.9759840000 1.2851310000 0.2737020000 0.1403100000 1.6283940000 1.6473990000 108833070 0 1787854848 4.7610673904 4.0478024483 4.0513424873 162 6.4400000000 0.0058703166 0.0047994787 0.0060991556 0.0052167877 3.3091310000 1.2791820000 0.3944820000 0.0000050000 1.6261960000 0.0082350000 108834744 0 1784426496 4.7661499977 4.0501513481 4.0590715408 163 6.4800000000 0.0058354321 0.0048058343 0.0060991556 0.0052253993 3.2722280000 1.2757840000 0.2159310000 0.1397810000 1.6314430000 0.0082490000 108836418 0 1785806848 4.7726869583 4.0508513451 4.0670971870 164 6.5200000000 0.0057720272 0.0048117257 0.0060991556 0.0052359184 3.1846470000 1.2743620000 0.2647040000 0.0000040000 1.6362980000 0.0082180000 108838092 0 1787711488 4.7804560661 4.0506520271 4.0751552582 165 6.5600000000 0.0057811644 0.0048176011 0.0060991556 0.0052422425 4.9812930000 1.2786950000 0.3037120000 0.1388980000 1.6220050000 1.6369710000 108839766 0 1784410112 4.7890911102 4.0535573959 4.0839939117 166 6.6000000000 0.0057572853 0.0048232618 0.0060991556 0.0052644067 3.1715970000 1.2777040000 0.2742510000 0.0000050000 1.6102850000 0.0082810000 108841440 0 1785933824 4.7970719337 4.0574855804 4.0930643082 167 6.6400000000 0.0057394933 0.0048287483 0.0060991556 0.0053159699 3.3064470000 1.2767460000 0.2640640000 0.1380000000 1.6183450000 0.0082570000 108843114 0 1787584512 4.8014225960 4.0593209267 4.1012530327 168 6.6800000000 0.0057057231 0.0048339683 0.0060991556 0.0053196174 3.1492490000 1.2721310000 0.2632830000 0.0000050000 1.6046420000 0.0081710000 108844788 0 1784561664 4.8085122108 4.0617208481 4.1100020409 169 6.7200000000 0.0056861932 0.0048390111 0.0060991556 0.0053134881 4.8574270000 1.2778970000 0.2157560000 0.1375740000 1.6038140000 1.6213010000 108846462 0 1786068992 4.8172588348 4.0663189888 4.1206364632 170 6.7600000000 0.0057042134 0.0048441005 0.0060991556 0.0053271777 3.1565920000 1.2779290000 0.2750640000 0.0000040000 1.5942870000 0.0082490000 108848136 0 1787838464 4.8229641914 4.0676684380 4.1289138794 171 6.8000000000 0.0056475778 0.0048487992 0.0060991556 0.0053116744 3.2911730000 1.2717520000 0.2769590000 0.1362870000 1.5968170000 0.0082190000 108849810 0 1784553472 4.8323202133 4.0704994202 4.1391701698 172 6.8400000000 0.0056371391 0.0048533826 0.0060991556 0.0052962288 3.0727620000 1.2729020000 0.2039960000 0.0000040000 1.5864390000 0.0082330000 108851484 0 1785933824 4.8403759003 4.0731968880 4.1494617462 173 6.8800000000 0.0056170481 0.0048577968 0.0060991556 0.0052813946 4.8544840000 1.2721130000 0.2680440000 0.1356920000 1.5797550000 1.5977260000 108853158 0 1787711488 4.8442263603 4.0731406212 4.1566758156 174 6.9200000000 0.0056401319 0.0048622930 0.0060991556 0.0052745319 3.1297060000 1.2731020000 0.2667840000 0.0000050000 1.5804370000 0.0082760000 108854832 0 1784553472 4.8526687622 4.0754060745 4.1664252281 175 6.9600000000 0.0056093782 0.0048665621 0.0060991556 0.0052623323 3.2639090000 1.2738920000 0.2762350000 0.1347080000 1.5697780000 0.0081790000 108856506 0 1785933824 4.8623561859 4.0791730881 4.1769204140 176 7.0000000000 0.0056322371 0.0048709125 0.0060991556 0.0052474619 3.1106370000 1.2781970000 0.2617950000 0.0000040000 1.5613840000 0.0081690000 108858180 0 1787711488 4.8692088127 4.0816965103 4.1868734360 177 7.0400000000 0.0055448608 0.0048747201 0.0060991556 0.0052881015 4.8106340000 1.2732230000 0.2632670000 0.1337230000 1.5618230000 1.5774020000 108859854 0 1784426496 4.8738970757 4.0814394951 4.1950497627 178 7.0800000000 0.0054767248 0.0048781022 0.0060991556 0.0053157752 3.1020930000 1.2694870000 0.2664900000 0.0000050000 1.5567670000 0.0082430000 108861528 0 1785942016 4.8781695366 4.0814094543 4.2028799057 179 7.1200000000 0.0054644071 0.0048813776 0.0060991556 0.0053013627 3.2318390000 1.2741270000 0.2679950000 0.1329980000 1.5473290000 0.0082510000 108863202 0 1787719680 4.8842363358 4.0839228630 4.2120680809 180 7.1600000000 0.0054492066 0.0048845322 0.0060991556 0.0052916842 3.1061040000 1.2771950000 0.2765710000 0.0000040000 1.5430360000 0.0081800000 108864876 0 1784426496 4.8905668259 4.0852026939 4.2211656570 181 7.2000000000 0.0054484261 0.0048876477 0.0060991556 0.0052772454 4.7713790000 1.2708890000 0.2656550000 0.1322790000 1.5442990000 1.5571130000 108866550 0 1785806848 4.8943538666 4.0859732628 4.2300105095 182 7.2400000000 0.0054738969 0.0048908688 0.0060991556 0.0052636115 3.0925740000 1.2769120000 0.2663530000 0.0000050000 1.5400020000 0.0081550000 108868224 0 1787584512 4.9002046585 4.0878381729 4.2386245728 183 7.2800000000 0.0053914250 0.0048936041 0.0060991556 0.0052493735 3.2078230000 1.2734470000 0.2629920000 0.1316280000 1.5303150000 0.0081920000 108869898 0 1784553472 4.9054665565 4.0899333954 4.2479820251 184 7.3200000000 0.0053481380 0.0048960744 0.0060991556 0.0052417825 3.0758890000 1.2721000000 0.2633280000 0.0000050000 1.5310100000 0.0081950000 108871572 0 1785933824 4.9109311104 4.0905594826 4.2555375099 185 7.3600000000 0.0053738523 0.0048986570 0.0060991556 0.0052323431 4.7518900000 1.2724660000 0.2779630000 0.1309790000 1.5216550000 1.5476510000 108873246 0 1787838464 4.9146423340 4.0901627541 4.2616734505 186 7.4000000000 0.0053737769 0.0049012114 0.0060991556 0.0052191817 3.0290520000 1.2713920000 0.2285920000 0.0000050000 1.5195990000 0.0082690000 108874920 0 1784553472 4.9200682640 4.0917940140 4.2710614204 187 7.4400000000 0.0052999821 0.0049033438 0.0060991556 0.0052190133 3.1982120000 1.2781890000 0.2662150000 0.1303100000 1.5140610000 0.0082570000 108876594 0 1785933824 4.9250178337 4.0927400589 4.2783470154 188 7.4800000000 0.0052824710 0.0049053605 0.0060991556 0.0052057276 3.1175560000 1.2693430000 0.3238690000 0.0000040000 1.5148910000 0.0082680000 108878268 0 1787879424 4.9291610718 4.0936255455 4.2850432396 189 7.5200000000 0.0052784830 0.0049073347 0.0060991556 0.0051927219 4.7173980000 1.2704820000 0.2768280000 0.1297580000 1.5067650000 1.5323340000 108879942 0 1784418304 4.9322481155 4.0934958458 4.2914609909 190 7.5600000000 0.0052357116 0.0049090630 0.0060991556 0.0051842040 3.0595250000 1.2809090000 0.2679790000 0.0000050000 1.5012030000 0.0082680000 108881616 0 1785806848 4.9373941422 4.0942201614 4.2995023727 191 7.6000000000 0.0051759514 0.0049104603 0.0060991556 0.0051750657 3.2013880000 1.2772160000 0.2789980000 0.1348130000 1.5009170000 0.0082380000 108883290 0 1787838464 4.9411087036 4.0960874557 4.3077535629 192 7.6400000000 0.0052053947 0.0049119964 0.0060991556 0.0051620815 3.0942010000 1.2707180000 0.3258440000 0.0000040000 1.4882580000 0.0081960000 108884964 0 1784426496 4.9438695908 4.0977115631 4.3162078857 193 7.6800000000 0.0051312922 0.0049131326 0.0060991556 0.0051499664 4.6540070000 1.2802640000 0.2733310000 0.1281430000 1.4777340000 1.4932630000 108886638 0 1785806848 4.9492883682 4.0995302200 4.3316249847 194 7.7200000000 0.0051637744 0.0049144246 0.0060991556 0.0051366340 3.0419340000 1.2780700000 0.2784490000 0.0000050000 1.4760240000 0.0081730000 108888312 0 1787727872 4.9529905319 4.1020174026 4.3403801918 195 7.7600000000 0.0050470382 0.0049151047 0.0060991556 0.0051235833 3.1340550000 1.2719340000 0.2630010000 0.1269510000 1.4626430000 0.0082790000 108889986 0 1784426496 4.9577560425 4.1034259796 4.3589477539 196 7.8000000000 0.0051648812 0.0049163791 0.0060991556 0.0051172735 2.9995810000 1.2709870000 0.2640770000 0.0000040000 1.4550780000 0.0082360000 108891660 0 1785806848 4.9580502510 4.1025795937 4.3676519394 197 7.8400000000 0.0051521654 0.0049175759 0.0060991556 0.0051054683 4.5836730000 1.2729060000 0.2732690000 0.1262330000 1.4471300000 1.4629030000 108893334 0 1787584512 4.9606990814 4.1033291817 4.3778572083 198 7.8800000000 0.0050266846 0.0049181270 0.0060991556 0.0050926846 2.9989310000 1.2736690000 0.2668980000 0.0000040000 1.4488240000 0.0083170000 108895008 0 1784324096 4.9626574516 4.1039104462 4.3887948990 199 7.9200000000 0.0051192655 0.0049191377 0.0060991556 0.0050875037 3.1544970000 1.2709720000 0.3132160000 0.1254540000 1.4353780000 0.0081680000 108896682 0 1785815040 4.9628186226 4.1031332016 4.3988504410 200 7.9600000000 0.0051193465 0.0049201388 0.0060991556 0.0050767396 3.0303570000 1.2777520000 0.3157980000 0.0000030000 1.4273700000 0.0081640000 108898356 0 1787600896 4.9650087357 4.1039519310 4.4098229408 201 8.0000000000 0.0050080242 0.0049205760 0.0060991556 0.0050648713 4.5341810000 1.2704670000 0.2747670000 0.1245790000 1.4257330000 1.4373590000 108900030 0 1784156160 4.9673113823 4.1037120819 4.4213333130 202 8.0400000000 0.0050214855 0.0049210756 0.0060991556 0.0050529626 2.9562960000 1.2710690000 0.2640290000 0.0000030000 1.4116540000 0.0081820000 108901704 0 1785679872 4.9670453072 4.1040925980 4.4316506386 203 8.0800000000 0.0050306641 0.0049216154 0.0060991556 0.0050407691 3.1027990000 1.2873850000 0.2765380000 0.1239450000 1.4054560000 0.0081870000 108903378 0 1787600896 4.9669337273 4.1043586731 4.4423098564 204 8.1200000000 0.0050898138 0.0049224399 0.0060991556 0.0050317566 2.9664460000 1.2712200000 0.2770840000 0.0000040000 1.4086700000 0.0081890000 108905052 0 1784537088 4.9671297073 4.1058182716 4.4530200958 205 8.1600000000 0.0051868814 0.0049237299 0.0060991556 0.0050438949 4.4886920000 1.2762480000 0.2746150000 0.1230960000 1.3957140000 1.4177410000 108906726 0 1785933824 4.9684138298 4.1076197624 4.4647183418 206 8.1999999990 0.0051339464 0.0049247504 0.0060991556 0.0050511840 2.9460970000 1.2709270000 0.2748910000 0.0000040000 1.3907440000 0.0082300000 108908400 0 1787838464 4.9690728188 4.1096701622 4.4768719673 207 8.2400000000 0.0050665783 0.0049254355 0.0060991556 0.0050463983 3.1273770000 1.2767540000 0.3307270000 0.1251350000 1.3852200000 0.0082570000 108910074 0 1784553472 4.9698319435 4.1120543480 4.4897251129 208 8.2799999990 0.0051114238 0.0049263297 0.0060991556 0.0050474026 2.9231440000 1.2736060000 0.2668550000 0.0000050000 1.3732120000 0.0081680000 108911748 0 1786068992 4.9695191383 4.1151709557 4.5014758110 209 8.3200000000 0.0051863333 0.0049275737 0.0060991556 0.0050415436 4.4209100000 1.2796260000 0.2658330000 0.1236330000 1.3665760000 1.3839690000 108913422 0 1787863040 4.9697561264 4.1167178154 4.5131168365 210 8.3599999990 0.0050587547 0.0049281984 0.0060991556 0.0050303726 2.9136330000 1.2797070000 0.2664140000 0.0000030000 1.3579260000 0.0082580000 108915096 0 1784426496 4.9703598022 4.1181421280 4.5251936913 211 8.4000000000 0.0050901240 0.0049289658 0.0060991556 0.0050266574 2.9680550000 1.2751820000 0.2166640000 0.1207090000 1.3460350000 0.0081780000 108916770 0 1785806848 4.9707856178 4.1203374863 4.5376024246 212 8.4399999990 0.0050438405 0.0049295077 0.0060991556 0.0050192243 2.8876020000 1.2767030000 0.2629720000 0.0000030000 1.3383860000 0.0082070000 108918444 0 1787727872 4.9697508812 4.1220970154 4.5499944687 213 8.4800000000 0.0050854515 0.0049302398 0.0060991556 0.0050114123 4.3459160000 1.2690350000 0.2639350000 0.1198360000 1.3411240000 1.3506490000 108920118 0 1784299520 4.9685626030 4.1240568161 4.5615000725 214 8.5200000000 0.0052002580 0.0049315016 0.0060991556 0.0050080459 2.8815950000 1.2720760000 0.2777420000 0.0000060000 1.3221370000 0.0082430000 108921792 0 1785806848 4.9679861069 4.1262817383 4.5728135109 215 8.5600000000 0.0052047623 0.0049327726 0.0060991556 0.0049990291 3.0870140000 1.2776820000 0.3635190000 0.1190680000 1.3171580000 0.0082290000 108923466 0 1787838464 4.9681735039 4.1294693947 4.5849618912 216 8.6000000000 0.0049843243 0.0049330112 0.0060991556 0.0049910927 2.8654100000 1.2710730000 0.2733140000 0.0000040000 1.3114430000 0.0081770000 108925140 0 1784680448 4.9686169624 4.1316146851 4.5973286629 217 8.6400000000 0.0050325333 0.0049334698 0.0060991556 0.0049843337 4.2831760000 1.2706590000 0.2714060000 0.1181460000 1.2993070000 1.3222970000 108926814 0 1786187776 4.9674906731 4.1332750320 4.6082339287 218 8.6800000000 0.0050660567 0.0049340780 0.0060991556 0.0049786756 2.8981140000 1.2743950000 0.3115070000 0.0000020000 1.3026100000 0.0082610000 108928488 0 1787965440 4.9658999443 4.1347384453 4.6188874245 219 8.7200000000 0.0051476662 0.0049350533 0.0060991556 0.0049719767 3.0118870000 1.2702510000 0.3229860000 0.1175040000 1.2915270000 0.0082370000 108930162 0 1784832000 4.9632091522 4.1358165741 4.6292352676 220 8.7600000000 0.0051628170 0.0049360886 0.0060991556 0.0049623758 2.8290700000 1.2746000000 0.2681280000 0.0000040000 1.2767020000 0.0082580000 108931836 0 1786449920 4.9599070549 4.1361241341 4.6388015747 221 8.8000000000 0.0051405481 0.0049370138 0.0060991556 0.0049516387 4.2250240000 1.2763150000 0.2660880000 0.1176110000 1.2726920000 1.2909570000 108933510 0 1785679872 4.9602608681 4.1384253502 4.6508827209 222 8.8400000000 0.0050197900 0.0049373866 0.0060991556 0.0049429244 3.0083850000 1.2715080000 0.4557160000 0.0000040000 1.2715260000 0.0082520000 108935184 0 1787076608 4.9585814476 4.1390342712 4.6616182327 223 8.8800000000 0.0049970960 0.0049376544 0.0060991556 0.0049318166 2.9292500000 1.2726000000 0.2687800000 0.1170780000 1.2611540000 0.0082730000 108936858 0 1784791040 4.9558181763 4.1389880180 4.6712112427 224 8.9200000000 0.0049115457 0.0049375378 0.0060991556 0.0049218374 2.8508960000 1.2741190000 0.3140270000 0.0000040000 1.2531680000 0.0081760000 108938532 0 1786441728 4.9540858269 4.1395273209 4.6816344261 225 8.9600000000 0.0048018130 0.0049369346 0.0060991556 0.0049140645 4.1846370000 1.2722420000 0.2772640000 0.1156660000 1.2477840000 1.2702930000 108940206 0 1785679872 4.9537949562 4.1410870552 4.6929664612 226 9.0000000000 0.0049378457 0.0049369387 0.0060991556 0.0049039117 2.7778660000 1.2721190000 0.2622510000 0.0000030000 1.2337730000 0.0082980000 108941880 0 1787076608 4.9550161362 4.1433882713 4.7148385048 227 9.0400000000 0.0047760992 0.0049362301 0.0060991556 0.0048931441 2.8929600000 1.2736890000 0.2657690000 0.1151440000 1.2286920000 0.0082380000 108943554 0 1784823808 4.9551119804 4.1454486847 4.7255988121 228 9.0800000000 0.0049054888 0.0049360953 0.0060991556 0.0048844209 2.7562300000 1.3072060000 0.2185700000 0.0000040000 1.2206180000 0.0082110000 108945228 0 1786568704 4.9528608322 4.1470007896 4.7345962524 229 9.1200000000 0.0048131053 0.0049355582 0.0060991556 0.0048954878 4.1121890000 1.2778610000 0.2675420000 0.1140750000 1.2162920000 1.2349920000 108946902 0 1785425920 4.9530401230 4.1487126350 4.7457566261 230 9.1600000000 0.0046986365 0.0049345281 0.0060991556 0.0048922381 2.7239840000 1.2776670000 0.2288230000 0.0000040000 1.2078030000 0.0082480000 108948576 0 1787084800 4.9536247253 4.1500310898 4.7560043335 231 9.2000000000 0.0046099918 0.0049331232 0.0060991556 0.0048871216 2.9165200000 1.2725340000 0.3237900000 0.1131510000 1.1972090000 0.0083360000 108950250 0 1784688640 4.9529190063 4.1512756348 4.7746534348 232 9.2400000000 0.0046391711 0.0049318562 0.0060991556 0.0048801377 2.7430800000 1.2779730000 0.2670020000 0.0000040000 1.1884700000 0.0082170000 108951924 0 1786187776 4.9537124634 4.1536617279 4.7866358757 233 9.2800000000 0.0045460146 0.0049302002 0.0060991556 0.0048816417 4.0850190000 1.2719330000 0.3210180000 0.1121400000 1.1829180000 1.1955660000 108953598 0 1787965440 4.9543228149 4.1562547684 4.7987232208 234 9.3200000000 0.0046750573 0.0049291098 0.0060991556 0.0048800925 2.7460020000 1.2705920000 0.2989500000 0.0000040000 1.1668280000 0.0081800000 108955272 0 1785315328 4.9535846710 4.1589088440 4.8094577789 235 9.3600000000 0.0045030280 0.0049272967 0.0060991556 0.0048784803 2.8731710000 1.2774500000 0.3194970000 0.1114140000 1.1550940000 0.0081810000 108956946 0 1786822656 4.9533019066 4.1600933075 4.8202896118 236 9.4000000000 0.0046327924 0.0049260488 0.0060991556 0.0048728227 2.7619390000 1.2953290000 0.3103090000 0.0000040000 1.1466780000 0.0081850000 108958620 0 1784664064 4.9549260139 4.1608467102 4.8297972679 237 9.4400000000 0.0046127755 0.0049247270 0.0060991556 0.0048809815 3.9402710000 1.2803480000 0.2633640000 0.1105180000 1.1330520000 1.1514890000 108960294 0 1786314752 4.9556202888 4.1634817123 4.8408565521 238 9.4800000000 0.0045612608 0.0049231998 0.0060991556 0.0048788766 2.6784990000 1.2716030000 0.2693440000 0.0000040000 1.1278960000 0.0081800000 108961968 0 1785679872 4.9564137459 4.1650156975 4.8516607285 239 9.5200000000 0.0046279249 0.0049219644 0.0060991556 0.0048847533 2.8193160000 1.2716860000 0.3125660000 0.1097340000 1.1156700000 0.0081790000 108963642 0 1786966016 4.9583234787 4.1672482491 4.8624157906 240 9.5600000000 0.0045057507 0.0049202301 0.0060991556 0.0048831395 2.6185730000 1.2792830000 0.2175900000 0.0000050000 1.1119010000 0.0082280000 108965316 0 1784807424 4.9579415321 4.1680488586 4.8719525337 241 9.6000000000 0.0044720089 0.0049183703 0.0060991556 0.0048729984 3.9783490000 1.2718540000 0.3590030000 0.1091700000 1.1080760000 1.1287130000 108966990 0 1786466304 4.9562158585 4.1695003510 4.8817043304 242 9.6400000000 0.0043963278 0.0049162131 0.0060991556 0.0048763418 2.6533260000 1.2703860000 0.2743190000 0.0000040000 1.0989220000 0.0082100000 108968664 0 1785577472 4.9574193954 4.1718697548 4.8938627243 243 9.6800000000 0.0044434629 0.0049142676 0.0060991556 0.0048670778 2.7514790000 1.2706170000 0.2701140000 0.1087990000 1.0922180000 0.0082250000 108970338 0 1787084800 4.9604225159 4.1743559837 4.9075427055 244 9.7200000000 0.0043026595 0.0049117610 0.0060991556 0.0048570692 2.6410920000 1.2697350000 0.2760040000 0.0000040000 1.0855880000 0.0082680000 108972012 0 1784807424 4.9617037773 4.1779685020 4.9195985794 245 9.7600000000 0.0044098953 0.0049097126 0.0060991556 0.0048489099 3.8168480000 1.2755090000 0.2658560000 0.1077060000 1.0746980000 1.0915680000 108973686 0 1786314752 4.9617753029 4.1787538528 4.9292140007 246 9.8000000000 0.0041945977 0.0049068056 0.0060991556 0.0048390370 2.6230000000 1.2717870000 0.2679470000 0.0000040000 1.0735190000 0.0082490000 108975360 0 1785679872 4.9632387161 4.1814279556 4.9409465790 247 9.8400000000 0.0042409385 0.0049041098 0.0060991556 0.0048294113 2.7573480000 1.2694230000 0.3133820000 0.1068770000 1.0578070000 0.0083320000 108977034 0 1787076608 4.9635324478 4.1840434074 4.9526343346 248 9.8800000000 0.0043479740 0.0049018673 0.0060991556 0.0048244619 2.5698520000 1.2742440000 0.2287860000 0.0000040000 1.0570340000 0.0081720000 108978708 0 1784807424 4.9635701180 4.1872124672 4.9626889229 249 9.9200000000 0.0041210135 0.0048987314 0.0060991556 0.0048148587 3.7633730000 1.2736330000 0.2762300000 0.1062540000 1.0385150000 1.0672010000 108980382 0 1786331136 4.9648008347 4.1882157326 4.9734516144 250 9.9600000000 0.0042129620 0.0048959883 0.0060991556 0.0048055710 2.5426950000 1.2740570000 0.2255820000 0.0000050000 1.0332420000 0.0082570000 108982056 0 1785569280 4.9654712677 4.1900744438 4.9843349457 251 10.0000000000 0.0041206698 0.0048928994 0.0060991556 0.0047978272 2.7295980000 1.2719030000 0.3206760000 0.1054160000 1.0218560000 0.0082300000 108983730 0 1787076608 4.9649076462 4.1908335686 4.9934525490 252 10.0400000000 0.0040419041 0.0048895224 0.0060991556 0.0047882778 2.5879600000 1.3031330000 0.2627230000 0.0000040000 1.0122960000 0.0082530000 108985404 0 1784442880 4.9653182030 4.1924815178 5.0030517578 253 10.0800000000 0.0041772583 0.0048867071 0.0060991556 0.0047792654 3.7300440000 1.2731240000 0.3216160000 0.1049070000 1.0087100000 1.0201230000 108987078 0 1786085376 4.9657292366 4.1942138672 5.0124669075 254 10.1200000000 0.0041159708 0.0048836727 0.0060991556 0.0047736407 2.5972640000 1.2715960000 0.3214380000 0.0000040000 0.9944310000 0.0081670000 108988752 0 1787838464 4.9659647942 4.1962347031 5.0217928886 255 10.1600000000 0.0041295877 0.0048807155 0.0060991556 0.0047645248 2.9288750000 1.2733400000 0.5577750000 0.1046090000 0.9833680000 0.0081530000 108990426 0 1785204736 4.9653458595 4.1979341507 5.0309600830 256 10.2000000000 0.0039613033 0.0048771241 0.0060991556 0.0047662773 2.6039310000 1.2920620000 0.3253910000 0.0000050000 0.9766290000 0.0082260000 108992100 0 1786585088 4.9640898705 4.1987051964 5.0385985374 257 10.2400000000 0.0039155558 0.0048733826 0.0060991556 0.0047768250 3.6113590000 1.2767890000 0.2766920000 0.1035370000 0.9672700000 0.9854500000 109014254 0 1785044992 4.9631857872 4.2003846169 5.0474238396 258 10.2800000000 0.0039899629 0.0048699585 0.0060991556 0.0047781871 2.5219200000 1.2723890000 0.2754250000 0.0000030000 0.9642670000 0.0082390000 109057912 0 1786822656 4.9636440277 4.2020254135 5.0570545197 259 10.3200000000 0.0041223820 0.0048670721 0.0060991556 0.0047886644 2.6641370000 1.2739770000 0.3254190000 0.1033190000 0.9516340000 0.0081710000 109059586 0 1784680448 4.9632058144 4.2028994560 5.0650691986 260 10.3600000000 0.0043018116 0.0048648980 0.0060991556 0.0047911512 2.5746610000 1.2946720000 0.3218890000 0.0000060000 0.9482330000 0.0082670000 109061260 0 1786204160 4.9610300064 4.2043452263 5.0726232529 261 10.4000000000 0.0042105843 0.0048623910 0.0060991556 0.0047831392 3.5896870000 1.2714660000 0.3215280000 0.1023610000 0.9381760000 0.9545600000 109062934 0 1787965440 4.9597702026 4.2061152458 5.0822482109 262 10.4400000000 0.0044486709 0.0048608120 0.0060991556 0.0047740984 2.4926750000 1.2770190000 0.2757290000 0.0000050000 0.9299760000 0.0083040000 109064608 0 1785221120 4.9609022141 4.2074728012 5.0913801193 263 10.4800000000 0.0042847828 0.0048586217 0.0060991556 0.0047650156 2.6216670000 1.2712310000 0.3141870000 0.1018900000 0.9245540000 0.0081990000 109066282 0 1786712064 4.9602761269 4.2089724541 5.1009850502 264 10.5200000000 0.0042951996 0.0048564876 0.0060991556 0.0047589334 2.5966400000 1.3019280000 0.3689010000 0.0000050000 0.9159370000 0.0082530000 109067956 0 1784696832 4.9586133957 4.2094898224 5.1088933945 265 10.5600000000 0.0044812132 0.0048550714 0.0060991556 0.0047511181 3.4957630000 1.2729330000 0.2731120000 0.1012240000 0.9107610000 0.9361040000 109069630 0 1786339328 4.9574790001 4.2096858025 5.1163678169 266 10.6000000000 0.0044127633 0.0048534086 0.0060991556 0.0047423305 2.5149370000 1.2709680000 0.3255600000 0.0000050000 0.9085480000 0.0082400000 109071304 0 1785450496 4.9581089020 4.2107696533 5.1249980927 267 10.6400000000 0.0043927683 0.0048516834 0.0060991556 0.0047352124 2.7064840000 1.2685630000 0.4236060000 0.1007130000 0.9037080000 0.0082510000 109072978 0 1786966016 4.9572510719 4.2121624947 5.1336550713 268 10.6800000000 0.0043152794 0.0048496819 0.0060991556 0.0047291538 2.5161490000 1.3001950000 0.3145060000 0.0000050000 0.8916230000 0.0081730000 109074652 0 1785077760 4.9560542107 4.2141914368 5.1430544853 269 10.7200000000 0.0042794612 0.0048475621 0.0060991556 0.0047248592 3.4352930000 1.2707730000 0.2650990000 0.1001910000 0.8909850000 0.9065970000 109076326 0 1786712064 4.9542927742 4.2149834633 5.1522641182 270 10.7600000000 0.0043648737 0.0048457744 0.0060991556 0.0047186178 2.4358980000 1.2699960000 0.2769520000 0.0000050000 0.8789990000 0.0082250000 109078000 0 1784553472 4.9523987770 4.2172560692 5.1613607407 271 10.8000000000 0.0042470335 0.0048435650 0.0060991556 0.0047116467 2.7275120000 1.2771400000 0.4693220000 0.0995610000 0.8715530000 0.0082600000 109079674 0 1786204160 4.9501776695 4.2191472054 5.1713066101 272 10.8400000000 0.0041820831 0.0048411331 0.0060991556 0.0047029497 2.4384710000 1.3005060000 0.2638510000 0.0000050000 0.8643000000 0.0081750000 109081348 0 1787965440 4.9473052025 4.2209763527 5.1805329323 273 10.8800000000 0.0039892322 0.0048380125 0.0060991556 0.0046945328 3.3931020000 1.2771690000 0.2754800000 0.0990170000 0.8615240000 0.8782130000 109083022 0 1785077760 4.9433193207 4.2213950157 5.1895093918 274 10.9200000000 0.0037976792 0.0048342157 0.0060991556 0.0046869459 2.4043970000 1.2757510000 0.2648630000 0.0000050000 0.8538840000 0.0082280000 109084696 0 1786712064 4.9416055679 4.2234725952 5.1999516487 275 10.9600000000 0.0038096909 0.0048304902 0.0060991556 0.0046807445 2.4913020000 1.2701040000 0.2741350000 0.0984410000 0.8385880000 0.0082430000 109086370 0 1784950784 4.9390244484 4.2271456718 5.2095661163 276 11.0000000000 0.0038264289 0.0048268523 0.0060991556 0.0046739882 2.3989460000 1.2694640000 0.2780890000 0.0000050000 0.8415310000 0.0081600000 109088044 0 1786601472 4.9354028702 4.2263460159 5.2174024582 277 11.0400000000 0.0037517257 0.0048229709 0.0060991556 0.0046696915 3.3167460000 1.2697000000 0.2760020000 0.0978940000 0.8265930000 0.8448490000 109089718 0 1785823232 4.9349713326 4.2285718918 5.2286601067 278 11.0800000000 0.0037781107 0.0048192124 0.0060991556 0.0046612562 2.4290130000 1.2727630000 0.3260790000 0.0000060000 0.8202360000 0.0082330000 109091392 0 1787482112 4.9298973083 4.2296967506 5.2375946045 279 11.1200000000 0.0036824711 0.0048151381 0.0060991556 0.0046541151 2.5057780000 1.3050860000 0.2772010000 0.0976020000 0.8159170000 0.0082540000 109093066 0 1785085952 4.9250702858 4.2296938896 5.2468400002 280 11.1600000000 0.0036191226 0.0048108666 0.0060991556 0.0046458149 2.4646820000 1.2698630000 0.3785270000 0.0000060000 0.8061720000 0.0083090000 109094740 0 1786593280 4.9225239754 4.2322206497 5.2576594353 281 11.2000000000 0.0036692151 0.0048068038 0.0060991556 0.0046378588 3.2684850000 1.2713800000 0.2754420000 0.0969640000 0.8028090000 0.8201280000 109096414 0 1785823232 4.9204659462 4.2360291481 5.2671175003 282 11.2400000000 0.0036166718 0.0048025835 0.0060991556 0.0046301989 2.4110870000 1.2806110000 0.3265920000 0.0000050000 0.7939190000 0.0082400000 109098088 0 1787346944 4.9169816971 4.2370605469 5.2758078575 283 11.2800000000 0.0035308274 0.0047980896 0.0060991556 0.0046227698 2.4411720000 1.2686720000 0.2784140000 0.0964740000 0.7876070000 0.0082620000 109099762 0 1785077760 4.9137840271 4.2400774956 5.2853598595 284 11.3200000000 0.0035668579 0.0047937543 0.0060991556 0.0046156141 2.4886410000 1.2796150000 0.4147860000 0.0000050000 0.7842900000 0.0082240000 109101436 0 1786458112 4.9088029861 4.2428207397 5.2963876724 285 11.3600000000 0.0036514059 0.0047897461 0.0060991556 0.0046080781 3.2101370000 1.2676930000 0.2767970000 0.0960390000 0.7757510000 0.7920720000 109103110 0 1785806848 4.9041318893 4.2434597015 5.3052287102 286 11.4000000000 0.0036396461 0.0047857247 0.0060991556 0.0046123938 2.3813420000 1.2768250000 0.3258310000 0.0000050000 0.7687430000 0.0082140000 109104784 0 1787346944 4.9054331779 4.2467784882 5.3157911301 287 11.4400000000 0.0036179505 0.0047816558 0.0060991556 0.0046053314 2.4036480000 1.2700750000 0.2724350000 0.0954510000 0.7556820000 0.0082280000 109106458 0 1785077760 4.9028596878 4.2502574921 5.3247632980 288 11.4800000000 0.0036240027 0.0047776362 0.0060991556 0.0045974389 2.3554430000 1.2763040000 0.3209130000 0.0000050000 0.7482700000 0.0082330000 109108132 0 1786585088 4.8958153725 4.2511830330 5.3315110207 289 11.5200000000 0.0034995715 0.0047732138 0.0060991556 0.0045899853 3.1593250000 1.2712980000 0.2786370000 0.0950500000 0.7444260000 0.7681690000 109109806 0 1785839616 4.8901109695 4.2497320175 5.3387894630 290 11.5600000000 0.0033859441 0.0047684302 0.0060991556 0.0045828667 2.4451510000 1.2720190000 0.4260360000 0.0000050000 0.7371260000 0.0082250000 109111480 0 1787203584 4.8870906830 4.2507424355 5.3476796150 291 11.6000000000 0.0033472779 0.0047635465 0.0060991556 0.0045753078 2.6303960000 1.2686400000 0.5196610000 0.0946350000 0.7374890000 0.0081650000 109113154 0 1784975360 4.8846321106 4.2532572746 5.3560767174 292 11.6400000000 0.0032826532 0.0047584749 0.0060991556 0.0045677316 2.5635500000 1.2704590000 0.5565120000 0.0000050000 0.7265510000 0.0082410000 109114828 0 1786466304 4.8815121651 4.2538156509 5.3638181686 293 11.6800000000 0.0031274620 0.0047529083 0.0060991556 0.0045599507 3.2994890000 1.2697520000 0.4647940000 0.0945200000 0.7265910000 0.7420330000 109116502 0 1785831424 4.8796281815 4.2559790611 5.3703351021 294 11.7200000000 0.0030340906 0.0047470620 0.0060991556 0.0045582895 2.3951070000 1.3005930000 0.3662730000 0.0000050000 0.7180500000 0.0084120000 109118176 0 1787363328 4.8755164146 4.2551832199 5.3768420219 295 11.7600000000 0.0029542451 0.0047409847 0.0060991556 0.0045585843 2.3668600000 1.2695780000 0.2760040000 0.0993560000 0.7118070000 0.0083160000 109119850 0 1785061376 4.8740992546 4.2559361458 5.3846502304 296 11.8000000000 0.0029528770 0.0047349438 0.0060991556 0.0045769913 2.2068370000 1.2710090000 0.2176000000 0.0000040000 0.7081560000 0.0081820000 109121524 0 1786458112 4.8716869354 4.2562909126 5.3924202919 297 11.8400000000 0.0029208558 0.0047288357 0.0060991556 0.0046042514 3.1215580000 1.2688940000 0.3259120000 0.0935150000 0.7083960000 0.7230400000 109123198 0 1785806848 4.8673639297 4.2561717033 5.3996820450 298 11.8800000000 0.0027656122 0.0047222477 0.0060991556 0.0046170313 2.3464800000 1.2698710000 0.3684860000 0.0000050000 0.6979910000 0.0082180000 109124872 0 1787346944 4.8643841743 4.2556996346 5.4085097313 299 11.9200000000 0.0026865401 0.0047154393 0.0060991556 0.0046155013 2.4320320000 1.2661760000 0.3712220000 0.0929830000 0.6915680000 0.0082190000 109126546 0 1785331712 4.8624553680 4.2553687096 5.4166336060 300 11.9600000000 0.0025702633 0.0047082887 0.0060991556 0.0046143764 2.2360240000 1.2695790000 0.2709910000 0.0000040000 0.6853590000 0.0081780000 109128220 0 1786839040 4.8605842590 4.2547802925 5.4242830276 301 12.0000000000 0.0025083304 0.0047009799 0.0060991556 0.0046097586 3.0664220000 1.2703130000 0.3187700000 0.0923880000 0.6849240000 0.6981680000 109129894 0 1784823808 4.8595495224 4.2555704117 5.4338665009 302 12.0400000000 0.0024125036 0.0046934022 0.0060991556 0.0046032930 2.2232240000 1.2689170000 0.2717010000 0.0000050000 0.6724800000 0.0082850000 109131568 0 1786331136 4.8588218689 4.2558646202 5.4424996376 303 12.0800000000 0.0023986618 0.0046858288 0.0060991556 0.0045973652 2.3634190000 1.2692670000 0.3239550000 0.0918590000 0.6682750000 0.0082200000 109133242 0 1785679872 4.8568339348 4.2550978661 5.4500627518 304 12.1200000000 0.0023212063 0.0046780504 0.0060991556 0.0045912946 2.2617680000 1.2711460000 0.3188860000 0.0000050000 0.6616390000 0.0082510000 109134916 0 1787092992 4.8556437492 4.2559828758 5.4596691132 305 12.1600000000 0.0022119619 0.0046699649 0.0060991556 0.0045838353 3.0163060000 1.2693610000 0.3200320000 0.0914380000 0.6595590000 0.6740690000 109136590 0 1784848384 4.8544750214 4.2570300102 5.4693269730 306 12.2000000000 0.0022349074 0.0046620072 0.0060991556 0.0045764411 2.2427190000 1.2686000000 0.3170980000 0.0000040000 0.6469520000 0.0082290000 109138264 0 1786449920 4.8518424034 4.2580456734 5.4781646729 307 12.2400000000 0.0021173458 0.0046537184 0.0060991556 0.0045705830 2.3034800000 1.2999230000 0.2653370000 0.0908810000 0.6372770000 0.0082140000 109139938 0 1785688064 4.8497028351 4.2598519325 5.4877514839 308 12.2800000000 0.0020070451 0.0046451253 0.0060991556 0.0045688615 2.1741240000 1.2666050000 0.2712500000 0.0000050000 0.6261540000 0.0082350000 109141612 0 1787211776 4.8485884666 4.2605299950 5.4974889755 309 12.3200000000 0.0020235663 0.0046366413 0.0060991556 0.0045669473 2.8966790000 1.2706680000 0.2715630000 0.0901110000 0.6240110000 0.6384400000 109143286 0 1784934400 4.8472223282 4.2611670494 5.5066146851 310 12.3600000000 0.0020595037 0.0046283279 0.0060991556 0.0045743466 2.1627180000 1.2692650000 0.2733700000 0.0000040000 0.6099520000 0.0082560000 109144960 0 1786458112 4.8461823463 4.2638449669 5.5166063309 311 12.4000000000 0.0020519788 0.0046200438 0.0060991556 0.0045943080 2.2934270000 1.2682970000 0.3196610000 0.0893720000 0.6060190000 0.0082250000 109146634 0 1785679872 4.8449368477 4.2660446167 5.5268273354 312 12.4400000000 0.0020291330 0.0046117396 0.0060991556 0.0046011824 2.1420540000 1.2677920000 0.2713520000 0.0000060000 0.5927730000 0.0082310000 109148308 0 1787203584 4.8438954353 4.2649407387 5.5345144272 313 12.4800000000 0.0018791524 0.0046030093 0.0060991556 0.0046022667 2.8629380000 1.2652400000 0.3181860000 0.0889550000 0.5817040000 0.6069440000 109149982 0 1784934400 4.8426384926 4.2659950256 5.5441503525 314 12.5200000000 0.0017476132 0.0045939157 0.0060991556 0.0046009015 2.1685540000 1.2672700000 0.3184720000 0.0000060000 0.5727110000 0.0081940000 109151656 0 1786441728 4.8408832550 4.2671184540 5.5534081459 315 12.5600000000 0.0017138999 0.0045847728 0.0060991556 0.0045959549 2.2225960000 1.2873360000 0.2709220000 0.0883190000 0.5658970000 0.0082260000 109153330 0 1785679872 4.8394746780 4.2681336403 5.5615634918 316 12.6000000000 0.0017904255 0.0045759299 0.0060991556 0.0045889101 2.2606780000 1.2717290000 0.4173100000 0.0000050000 0.5615580000 0.0081740000 109155004 0 1787203584 4.8400955200 4.2677774429 5.5694952011 317 12.6400000000 0.0017193141 0.0045669185 0.0060991556 0.0045820193 2.7633080000 1.2648890000 0.2746820000 0.0878910000 0.5575780000 0.5763300000 109156678 0 1784823808 4.8393087387 4.2689261436 5.5784411430 318 12.6800000000 0.0018775519 0.0045584614 0.0060991556 0.0045776396 2.1082990000 1.2713620000 0.2767940000 0.0000040000 0.5499860000 0.0081720000 109158352 0 1786441728 4.8390502930 4.2707152367 5.5874285698 319 12.7200000000 0.0019988329 0.0045504375 0.0060991556 0.0045716315 2.2301330000 1.2665510000 0.3208660000 0.0874600000 0.5451020000 0.0082190000 109160026 0 1785679872 4.8364324570 4.2735238075 5.5978446007 320 12.7600000000 0.0019995510 0.0045424660 0.0060991556 0.0045713676 2.1375940000 1.2702120000 0.3208320000 0.0000040000 0.5364520000 0.0081600000 109161700 0 1787338752 4.8342843056 4.2745785713 5.6068620682 321 12.8000000000 0.0020314385 0.0045346434 0.0060991556 0.0045824494 2.7912950000 1.2622330000 0.3664560000 0.0870160000 0.5268310000 0.5468050000 109163374 0 1784926208 4.8327150345 4.2766113281 5.6161746979 322 12.8400000000 0.0020568839 0.0045269485 0.0060991556 0.0045877263 2.1711590000 1.2718280000 0.3674740000 0.0000060000 0.5212260000 0.0086350000 109165048 0 1786458112 4.8316397667 4.2789216042 5.6251368523 323 12.8800000000 0.0020583533 0.0045193058 0.0060991556 0.0045998337 2.2375560000 1.2638980000 0.3668150000 0.0865460000 0.5101720000 0.0081580000 109166722 0 1785679872 4.8304276466 4.2803883553 5.6330437660 324 12.9200000000 0.0019914233 0.0045115037 0.0060991556 0.0046120023 2.1980110000 1.2659290000 0.4196000000 0.0000030000 0.5022800000 0.0081700000 109168396 0 1787203584 4.8292660713 4.2805361748 5.6400170326 325 12.9600000000 0.0019991416 0.0045037734 0.0060991556 0.0046242861 2.6800070000 1.2621730000 0.3183030000 0.0862020000 0.4950850000 0.5162670000 109170070 0 1784664064 4.8288764954 4.2809967995 5.6471819878 326 13.0000000000 0.0021209221 0.0044964640 0.0060991556 0.0046329071 2.0964180000 1.2681450000 0.3258200000 0.0000030000 0.4922700000 0.0082260000 109171744 0 1786187776 4.8277020454 4.2818498611 5.6553401947 327 13.0400000000 0.0020708684 0.0044890463 0.0060991556 0.0047402588 2.0953510000 1.2635800000 0.2629020000 0.0855680000 0.4731250000 0.0082290000 109173418 0 1787965440 4.8240337372 4.2863850594 5.6748785973 328 13.0800000000 0.0021268250 0.0044818444 0.0060991556 0.0047588921 2.0520180000 1.2590070000 0.3185370000 0.0000040000 0.4642480000 0.0082130000 109175092 0 1784823808 4.8221573830 4.2871031761 5.6827192307 329 13.1200000000 0.0021195419 0.0044746642 0.0060991556 0.0047641544 2.6116780000 1.2663720000 0.3198280000 0.0852930000 0.4593740000 0.4788460000 109176766 0 1786441728 4.8200335503 4.2880840302 5.6906833649 330 13.1600000000 0.0022097903 0.0044678009 0.0060991556 0.0047633498 2.0855030000 1.2562540000 0.3655850000 0.0000030000 0.4535310000 0.0081490000 109178440 0 1785679872 4.8185911179 4.2884821892 5.6979002953 331 13.2000000000 0.0022027236 0.0044609578 0.0060991556 0.0047631062 2.1704680000 1.2641830000 0.3658820000 0.0851590000 0.4450400000 0.0082220000 109180114 0 1787076608 4.8178405762 4.2884230614 5.7046394348 332 13.2400000000 0.0022678457 0.0044543520 0.0060991556 0.0047600161 2.0732100000 1.2584480000 0.3663340000 0.0000030000 0.4381970000 0.0082030000 109181788 0 1784553472 4.8168301582 4.2899332047 5.7123250961 333 13.2800000000 0.0022406485 0.0044477042 0.0060991556 0.0047551139 2.5554860000 1.2595120000 0.3247090000 0.0846660000 0.4326030000 0.4519820000 109183462 0 1786060800 4.8157978058 4.2913670540 5.7198181152 334 13.3200000000 0.0021933883 0.0044409548 0.0060991556 0.0047573186 2.0136830000 1.2591520000 0.3189240000 0.0000030000 0.4253660000 0.0082130000 109185136 0 1787981824 4.8153786659 4.2914443016 5.7258896828 335 13.3600000000 0.0021501058 0.0044341164 0.0060991556 0.0047629994 2.0997940000 1.2583190000 0.3213500000 0.0845480000 0.4253010000 0.0082360000 109186810 0 1784832000 4.8132410049 4.2942385674 5.7346038818 336 13.4000000000 0.0021075015 0.0044271920 0.0060991556 0.0047767242 1.9526160000 1.2576640000 0.2722280000 0.0000030000 0.4123940000 0.0082660000 109188484 0 1786322944 4.8112115860 4.2950048447 5.7408127785 337 13.4400000000 0.0019639060 0.0044198825 0.0060991556 0.0048014455 2.4540310000 1.2563470000 0.2731190000 0.0843590000 0.4085100000 0.4296770000 109190158 0 1785688064 4.8098945618 4.2940382957 5.7460150719 338 13.4800000000 0.0019385347 0.0044125413 0.0060991556 0.0048291837 2.0208480000 1.2959750000 0.3091320000 0.0000030000 0.4054490000 0.0082410000 109191832 0 1787076608 4.8064389229 4.2940926552 5.7514643669 339 13.5200000000 0.0019594182 0.0044053049 0.0060991556 0.0048506819 2.0153470000 1.2601860000 0.2615750000 0.0842100000 0.3990530000 0.0082660000 109193506 0 1784442880 4.8044962883 4.2958011627 5.7590370178 340 13.5600000000 0.0019660837 0.0043981307 0.0060991556 0.0048751399 1.9898090000 1.2639290000 0.3199110000 0.0000030000 0.3957120000 0.0082180000 109195180 0 1786060800 4.7999010086 4.2960677147 5.7647404671 341 13.6000000000 0.0018934199 0.0043907855 0.0060991556 0.0048844621 2.5155610000 1.2574870000 0.3658220000 0.0839760000 0.3931380000 0.4130860000 109196854 0 1787854848 4.7961683273 4.2970395088 5.7720036507 342 13.6400000000 0.0020521823 0.0043839475 0.0060991556 0.0048976446 1.9393400000 1.2581420000 0.2730980000 0.0000040000 0.3977160000 0.0082120000 109198528 0 1785061376 4.7925391197 4.2994213104 5.7800979614 343 13.6800000000 0.0021625259 0.0043774711 0.0060991556 0.0049162751 2.0076990000 1.2570070000 0.2726030000 0.0838270000 0.3834330000 0.0087260000 109200202 0 1786568704 4.7883243561 4.3029122353 5.7885370255 344 13.7200000000 0.0022036014 0.0043711517 0.0060991556 0.0049205013 1.9142800000 1.2688650000 0.2602290000 0.0000030000 0.3748400000 0.0082470000 109201876 0 1785569280 4.7843790054 4.3048868179 5.7943902016 345 13.7600000000 0.0022476013 0.0043649965 0.0060991556 0.0049226725 2.4360860000 1.2667900000 0.3187550000 0.0836290000 0.3722370000 0.3926010000 109203550 0 1787076608 4.7826251984 4.3040075302 5.7990365028 346 13.8000000000 0.0023358248 0.0043591318 0.0060991556 0.0049233966 2.1919570000 1.2550340000 0.5562920000 0.0000030000 0.3703010000 0.0082300000 109205224 0 1784410112 4.7801012993 4.3044338226 5.8030056953 347 13.8400000000 0.0023952692 0.0043534723 0.0060991556 0.0049313689 1.9914550000 1.2597460000 0.2717540000 0.0842070000 0.3655300000 0.0081860000 109206898 0 1786060800 4.7762546539 4.3038287163 5.8087382317 348 13.8800000000 0.0025088326 0.0043481716 0.0060991556 0.0049447792 1.9509710000 1.2587480000 0.3198090000 0.0000030000 0.3622390000 0.0081650000 109208572 0 1787965440 4.7717437744 4.3043823242 5.8153896332 349 13.9200000000 0.0025712708 0.0043430802 0.0060991556 0.0049533681 2.4032100000 1.2579300000 0.3199560000 0.0834380000 0.3572950000 0.3825540000 109210246 0 1784791040 4.7656731606 4.3048477173 5.8227381706 350 13.9600000000 0.0027704819 0.0043385870 0.0060991556 0.0049627186 1.9430180000 1.2592790000 0.3210500000 0.0000030000 0.3523500000 0.0083090000 109211920 0 1786314752 4.7600769997 4.3061347008 5.8303351402 351 14.0000000000 0.0027667040 0.0043341087 0.0060991556 0.0049629168 2.0202250000 1.2604320000 0.3195970000 0.0832770000 0.3465600000 0.0083170000 109213594 0 1785552896 4.7547965050 4.3076300621 5.8368034363 352 14.0400000000 0.0028268499 0.0043298268 0.0060991556 0.0049634968 1.9413650000 1.2661600000 0.3186730000 0.0000040000 0.3462180000 0.0081720000 109215268 0 1787084800 4.7491917610 4.3073239326 5.8405246735 353 14.0800000000 0.0028201214 0.0043255500 0.0060991556 0.0049617286 2.3228330000 1.2592380000 0.2721300000 0.0833560000 0.3422920000 0.3636690000 109216942 0 1784418304 4.7448329926 4.3063311577 5.8459267616 354 14.1200000000 0.0028852734 0.0043214814 0.0060991556 0.0049630162 1.8845050000 1.2595560000 0.2778620000 0.0000030000 0.3368020000 0.0081620000 109218616 0 1785942016 4.7388038635 4.3086948395 5.8550033569 355 14.1600000000 0.0030481354 0.0043178945 0.0060991556 0.0049596395 1.9925030000 1.2594280000 0.3080080000 0.0833770000 0.3313840000 0.0082110000 109220290 0 1787838464 4.7330856323 4.3096079826 5.8600873947 356 14.2000000000 0.0031986469 0.0043147505 0.0060991556 0.0049565873 2.0065570000 1.2576370000 0.4097670000 0.0000030000 0.3288580000 0.0081380000 109221964 0 1784680448 4.7271218300 4.3096113205 5.8644824028 357 14.2400000000 0.0033014570 0.0043119122 0.0060991556 0.0049533972 2.3330660000 1.2641550000 0.3155720000 0.0830210000 0.3244640000 0.3437490000 109223638 0 1786187776 4.7197527885 4.3108544350 5.8708276749 358 14.2800000000 0.0033874463 0.0043093299 0.0060991556 0.0049471098 1.9047380000 1.2598570000 0.3135760000 0.0000030000 0.3211200000 0.0080320000 109225312 0 1788092416 4.7144303322 4.3110389709 5.8763384819 359 14.3200000000 0.0034198288 0.0043068522 0.0060991556 0.0049406313 1.9803750000 1.2613340000 0.3109050000 0.0828290000 0.3152230000 0.0079330000 109226986 0 1784934400 4.7054696083 4.3146443367 5.8838782310 360 14.3600000000 0.0036271757 0.0043049642 0.0060991556 0.0049419491 1.8314220000 1.2584260000 0.2618860000 0.0000020000 0.3012420000 0.0077020000 109228660 0 1786441728 4.6897673607 4.3178744316 5.8957576752 361 14.4000000000 0.0040656747 0.0043043013 0.0060991556 0.0049352098 2.1515890000 1.2611460000 0.2103610000 0.0827860000 0.2887830000 0.3063350000 109230334 0 1785425920 4.6807031631 4.3223829269 5.9043474197 362 14.4400000000 0.0041378355 0.0043038415 0.0060991556 0.0049304414 1.7989930000 1.2674270000 0.2418300000 0.0000040000 0.2803130000 0.0072460000 109232008 0 1786949632 4.6639361382 4.3215970993 5.9105954170 363 14.4800000000 0.0040607923 0.0043031719 0.0060991556 0.0049263877 1.9068140000 1.2592760000 0.2789480000 0.0823780000 0.2769120000 0.0071210000 109233682 0 1784537088 4.6579666138 4.3206005096 5.9145369530 364 14.5200000000 0.0039707250 0.0043022586 0.0060991556 0.0049196420 2.0251700000 1.2602590000 0.4848330000 0.0000030000 0.2708440000 0.0070480000 109235356 0 1786060800 4.6502060890 4.3211832047 5.9206337929 365 14.5600000000 0.0041633761 0.0043018781 0.0060991556 0.0049129170 2.3529710000 1.2572660000 0.4641020000 0.0822120000 0.2663200000 0.2808570000 109237030 0 1787965440 4.6421761513 4.3212256432 5.9257192612 366 14.6000000000 0.0043510608 0.0043020125 0.0060991556 0.0049069868 1.7997150000 1.2590560000 0.2653440000 0.0000040000 0.2666840000 0.0064030000 109238704 0 1784553472 4.6258230209 4.3274269104 5.9402785301 367 14.6400000000 0.0047764359 0.0043033052 0.0060991556 0.0049006807 1.9362180000 1.2660460000 0.2859940000 0.0819240000 0.2937730000 0.0062760000 109240378 0 1785933824 4.6166276932 4.3313636780 5.9453511238 368 14.6800000000 0.0050582895 0.0043053568 0.0060991556 0.0048956177 1.7769500000 1.2585260000 0.2071720000 0.0000030000 0.3027630000 0.0062920000 109242052 0 1787965440 4.6080060005 4.3316054344 5.9491858482 369 14.7200000000 0.0051631951 0.0043076815 0.0060991556 0.0048909634 2.2106610000 1.2610740000 0.2408190000 0.0818130000 0.3090390000 0.3156870000 109243726 0 1784688640 4.5996065140 4.3292598724 5.9505968094 370 14.7600000000 0.0050913966 0.0043097997 0.0060991556 0.0048850788 1.8472170000 1.2584810000 0.2761340000 0.0000040000 0.3041780000 0.0062030000 109245400 0 1786068992 4.5914630890 4.3280725479 5.9522347450 371 14.8000000000 0.0049667656 0.0043115705 0.0060991556 0.0048800962 1.9092760000 1.2603270000 0.2441290000 0.0817640000 0.3146100000 0.0061350000 109247074 0 1787973632 4.5819859505 4.3302483559 5.9589414597 372 14.8400000000 0.0050898665 0.0043136627 0.0060991556 0.0048741092 2.0310060000 1.2651330000 0.4135060000 0.0000030000 0.3440180000 0.0060910000 109248748 0 1784815616 4.5733900070 4.3315591812 5.9641156197 373 14.8800000000 0.0053072032 0.0043163263 0.0060991556 0.0048698996 2.4307470000 1.2603470000 0.3436440000 0.0818810000 0.3660880000 0.3765360000 109250422 0 1786187776 4.5637645721 4.3326044083 5.9687666893 374 14.9200000000 0.0059256717 0.0043206294 0.0060991556 0.0048644134 1.9311680000 1.2655600000 0.2724290000 0.0000020000 0.3838970000 0.0060890000 109252096 0 1785327616 4.5531611443 4.3330922127 5.9720563889 375 14.9600000000 0.0060454579 0.0043252289 0.0060991556 0.0048621467 2.0942840000 1.2591160000 0.3439040000 0.0816040000 0.4012700000 0.0061420000 109253770 0 1784426496 4.5428447723 4.3326439857 5.9733839035 376 15.0000000000 0.0062058251 0.0043302305 0.0062058251 0.0048559599 1.9491450000 1.2595400000 0.2402800000 0.0000030000 0.4408790000 0.0060980000 109255444 0 1785806848 4.5338439941 4.3321809769 5.9786925316 377 15.0400000000 0.0061462629 0.0043350476 0.0062058251 0.0048533259 2.5198980000 1.2710700000 0.2418470000 0.0814490000 0.4564220000 0.4668650000 109257118 0 1787838464 4.5127911568 4.3334646225 5.9859528542 378 15.0800000000 0.0068351985 0.0043416617 0.0068351985 0.0048508756 2.0537240000 1.2610290000 0.3137810000 0.0000030000 0.4704380000 0.0061970000 109258792 0 1784664064 4.5044145584 4.3338518143 5.9899525642 379 15.1200000000 0.0073523670 0.0043496055 0.0073523670 0.0048455094 2.0726180000 1.2654240000 0.2467910000 0.0815620000 0.4702340000 0.0063550000 109260466 0 1786187776 4.4973902702 4.3333287239 5.9929890633 380 15.1600000000 0.0076755560 0.0043583580 0.0076755560 0.0048421456 2.1658320000 1.2604790000 0.4269050000 0.0000900000 0.4698130000 0.0062820000 109262140 0 1787965440 4.4902586937 4.3320460320 5.9966869354 381 15.2000000000 0.0081004836 0.0043681799 0.0081004836 0.0048476831 2.7352810000 1.2668430000 0.4340150000 0.0814390000 0.4701060000 0.4805310000 109263814 0 1784553472 4.4825758934 4.3331255913 6.0027194023 382 15.2400000000 0.0087974537 0.0043797749 0.0087974537 0.0048477475 2.1709670000 1.2612940000 0.4342090000 0.0000030000 0.4667430000 0.0063350000 109265488 0 1785933824 4.4730229378 4.3325500488 6.0036258698 383 15.2800000000 0.0088559072 0.0043914619 0.0088559072 0.0048604187 2.2605330000 1.2620350000 0.4457960000 0.0814680000 0.4624710000 0.0064640000 109267162 0 1787854848 4.4645442963 4.3324537277 6.0062489510 384 15.3200000000 0.0084556285 0.0044020457 0.0088559072 0.0048803467 1.9499110000 1.2656380000 0.2231140000 0.0000030000 0.4523290000 0.0065080000 109268836 0 1784426496 4.4555602074 4.3342528343 6.0115456581 385 15.3600000000 0.0086587481 0.0044131020 0.0088559072 0.0048802398 2.6983500000 1.2621820000 0.4430550000 0.0815950000 0.4505940000 0.4586250000 109270510 0 1785942016 4.4478359222 4.3342013359 6.0143308640 386 15.4000000000 0.0084341550 0.0044235193 0.0088559072 0.0048834863 2.1662190000 1.2628430000 0.4505890000 0.0000030000 0.4439670000 0.0065030000 109272184 0 1787846656 4.4402422905 4.3348517418 6.0174117088 387 15.4400000000 0.0084120082 0.0044338254 0.0088559072 0.0048880742 2.2579970000 1.2614750000 0.4532480000 0.0816840000 0.4526600000 0.0065160000 109273858 0 1784426496 4.4338264465 4.3355622292 6.0212893486 388 15.4800000000 0.0080844359 0.0044432342 0.0088559072 0.0048976888 2.2254760000 1.3120820000 0.4587580000 0.0000040000 0.4456360000 0.0066730000 109275532 0 1785806848 4.4270162582 4.3368630409 6.0250148773 389 15.5200000000 0.0082587320 0.0044530427 0.0088559072 0.0048980782 2.7106190000 1.2634150000 0.4645220000 0.0819340000 0.4433680000 0.4550580000 109277206 0 1787711488 4.4192800522 4.3379087448 6.0290603638 390 15.5600000000 0.0081768176 0.0044625908 0.0088559072 0.0049158734 2.1682180000 1.2581960000 0.4613140000 0.0000030000 0.4396290000 0.0067400000 109278880 0 1784410112 4.4111471176 4.3385710716 6.0322051048 391 15.6000000000 0.0078008706 0.0044711286 0.0088559072 0.0049188757 2.0524000000 1.2635180000 0.2679000000 0.0818760000 0.4299970000 0.0067570000 109280554 0 1785806848 4.4038515091 4.3394351006 6.0356264114 392 15.6400000000 0.0075958767 0.0044790999 0.0088559072 0.0049317376 2.1734290000 1.2685900000 0.4685950000 0.0000030000 0.4270770000 0.0068150000 109282228 0 1787600896 4.3967823982 4.3404712677 6.0405244827 393 15.6800000000 0.0079429718 0.0044879139 0.0088559072 0.0049277766 2.6805790000 1.2628700000 0.4662690000 0.0820690000 0.4266850000 0.4402950000 109283902 0 1784426496 4.3903064728 4.3402714729 6.0434350967 394 15.7200000000 0.0078198053 0.0044963704 0.0088559072 0.0049305012 2.1720030000 1.2667260000 0.4716260000 0.0000030000 0.4243730000 0.0069430000 109285576 0 1785806848 4.3833947182 4.3410339355 6.0467190742 395 15.7600000000 0.0077864071 0.0045046996 0.0088559072 0.0049330997 2.2531680000 1.2648280000 0.4751440000 0.0822040000 0.4216970000 0.0069200000 109287250 0 1787584512 4.3767223358 4.3419146538 6.0528926849 396 15.8000000000 0.0080248471 0.0045135889 0.0088559072 0.0049301030 2.1758870000 1.2633700000 0.4841230000 0.0000030000 0.4189910000 0.0070130000 109288924 0 1784553472 4.3697462082 4.3437042236 6.0580568314 397 15.8400000000 0.0078499028 0.0045219927 0.0088559072 0.0049290536 2.5445960000 1.2642870000 0.3558870000 0.0823190000 0.4128680000 0.4268600000 109290598 0 1785933824 4.3632144928 4.3433022499 6.0605955124 398 15.8800000000 0.0073160967 0.0045290131 0.0088559072 0.0049321043 2.1791210000 1.2656510000 0.4911380000 0.0000030000 0.4129080000 0.0070530000 109292272 0 1787727872 4.3570995331 4.3442721367 6.0677847862 399 15.9200000000 0.0073064305 0.0045359740 0.0088559072 0.0049352440 2.2154450000 1.2666210000 0.4486160000 0.0824540000 0.4080750000 0.0072920000 109293946 0 1784410112 4.3489246368 4.3460655212 6.0713515282 400 15.9600000000 0.0069183381 0.0045419299 0.0088559072 0.0049399240 2.1674360000 1.2626230000 0.4890610000 0.0000030000 0.4061370000 0.0071630000 109295620 0 1785933824 4.3426361084 4.3454265594 6.0746726990 401 16.0000000000 0.0061470112 0.0045459326 0.0088559072 0.0049466114 2.6639810000 1.2697740000 0.4917920000 0.0825910000 0.4006860000 0.4167440000 109297294 0 1787846656 4.3349623680 4.3449096680 6.0788683891 402 16.0400000000 0.0057745464 0.0045489889 0.0088559072 0.0049602651 2.1238780000 1.2669070000 0.4549620000 0.0000040000 0.3924250000 0.0072290000 109298968 0 1784164352 4.3266887665 4.3457441330 6.0855803490 403 16.0800000000 0.0058169393 0.0045521352 0.0088559072 0.0049565020 2.2509170000 1.2728990000 0.4968410000 0.0826920000 0.3888220000 0.0073530000 109300642 0 1785679872 4.3211598396 4.3463120461 6.0917253494 404 16.1200000000 0.0059729274 0.0045556520 0.0088559072 0.0049520248 2.0642700000 1.2658720000 0.4130170000 0.0000040000 0.3757000000 0.0072900000 109302316 0 1787457536 4.3141822815 4.3461542130 6.0960993767 405 16.1600000000 0.0064017265 0.0045602102 0.0088559072 0.0049594213 2.6125080000 1.2724230000 0.4995540000 0.0827490000 0.3697250000 0.3857100000 109303990 0 1784664064 4.3068056107 4.3458819389 6.1001176834 406 16.2000000000 0.0068307547 0.0045658027 0.0088559072 0.0049795103 2.1505820000 1.2672400000 0.5003570000 0.0000040000 0.3734430000 0.0072310000 109305664 0 1786060800 4.3009481430 4.3474473953 6.1086406708 407 16.2400000000 0.0074548144 0.0045729010 0.0088559072 0.0049909183 2.2133940000 1.2694490000 0.4983370000 0.0828030000 0.3533270000 0.0071230000 109307338 0 1787838464 4.2943363190 4.3501505852 6.1141490936 408 16.2800000000 0.0081359837 0.0045816340 0.0088559072 0.0050031962 1.9004200000 1.2644970000 0.2845540000 0.0000030000 0.3418020000 0.0071630000 109309012 0 1784918016 4.2893710136 4.3513474464 6.1187200546 409 16.3200000000 0.0087153381 0.0045917409 0.0088559072 0.0050167839 2.4399970000 1.2665750000 0.4064600000 0.0830640000 0.3356540000 0.3458060000 109310686 0 1786568704 4.2829518318 4.3528051376 6.1255617142 410 16.3600000000 0.0093474835 0.0046033402 0.0093474835 0.0050179613 1.9585720000 1.2661490000 0.3606180000 0.0000030000 0.3221170000 0.0071380000 109312360 0 1785458688 4.2779254913 4.3538384438 6.1295170784 411 16.3999999990 0.0101083135 0.0046167343 0.0101083135 0.0050213045 1.9092060000 1.2605570000 0.2391560000 0.0830560000 0.3168370000 0.0071170000 109314034 0 1786966016 4.2725801468 4.3547682762 6.1328277588 412 16.4400000000 0.0100654401 0.0046299594 0.0101083135 0.0050154881 1.9615540000 1.2706340000 0.3569540000 0.0000030000 0.3243650000 0.0071360000 109315708 0 1784696832 4.2678503990 4.3544497490 6.1381878853 413 16.4800000000 0.0103205126 0.0046437379 0.0103205126 0.0050243723 2.3031240000 1.2619080000 0.2777840000 0.0831700000 0.3312540000 0.3464580000 109317382 0 1786204160 4.2623567581 4.3558564186 6.1453895569 414 16.5200000000 0.0124768149 0.0046626584 0.0124768149 0.0050371583 1.9041580000 1.2662820000 0.2856460000 0.0000030000 0.3426280000 0.0070460000 109319056 0 1785425920 4.2587399483 4.3582673073 6.1508946419 415 16.5599999990 0.0127830524 0.0046822256 0.0127830524 0.0050376364 2.1862120000 1.2651780000 0.4720210000 0.0835430000 0.3560520000 0.0069370000 109320730 0 1786966016 4.2534656525 4.3599877357 6.1575875282 416 16.6000000000 0.0151885683 0.0047074813 0.0151885683 0.0050773769 1.9131450000 1.2632650000 0.2767690000 0.0000030000 0.3636280000 0.0069640000 109322404 0 1785061376 4.2491655350 4.3631949425 6.1616964340 417 16.6400000000 0.0099299997 0.0047200053 0.0151885683 0.0050811865 2.4885650000 1.2711360000 0.3846050000 0.0836900000 0.3658230000 0.3808490000 109324078 0 1786703872 4.2368912697 4.3617868423 6.1651935577 418 16.6800000000 0.0129028205 0.0047395814 0.0151885683 0.0051797999 2.0574080000 1.2644430000 0.3954580000 0.0000040000 0.3881680000 0.0068480000 109325752 0 1784578048 4.2269892693 4.3662056923 6.1743721962 419 16.7199999990 0.0163047630 0.0047671833 0.0163047630 0.0052101468 2.2148560000 1.2712900000 0.4579180000 0.0844120000 0.3919570000 0.0067470000 109327426 0 1786085376 4.2293443680 4.3660922050 6.1809077263 420 16.7600000000 0.0249688756 0.0048152825 0.0249688756 0.0053545833 1.9262860000 1.2671250000 0.2390900000 0.0000030000 0.4108150000 0.0067230000 109329100 0 1787965440 4.2308168411 4.3726673126 6.1870288849 421 16.8000000000 0.0220147427 0.0048561363 0.0249688756 0.0053598388 2.4365050000 1.2645770000 0.2242860000 0.0851500000 0.4256480000 0.4343070000 109330774 0 1785204736 4.2223448753 4.3728227615 6.1922149658 422 16.8400000000 0.0166176502 0.0048840072 0.0249688756 0.0053620622 1.9607460000 1.2629500000 0.2532440000 0.0000030000 0.4353450000 0.0066920000 109332448 0 1786695680 4.2129292488 4.3698911667 6.1968946457 423 16.8799999990 0.0178065468 0.0049145570 0.0249688756 0.0054292203 2.0128710000 1.2670150000 0.2186770000 0.0857930000 0.4321500000 0.0066940000 109334122 0 1784680448 4.2082619667 4.3715510368 6.2021856308 424 16.9200000000 0.0148284743 0.0049379389 0.0249688756 0.0054525451 2.1948720000 1.2742680000 0.4566090000 0.0000030000 0.4547550000 0.0067020000 109335796 0 1786314752 4.1944017410 4.3714809418 6.2117815018 425 16.9600000000 0.0119710742 0.0049544874 0.0249688756 0.0054478452 2.7134220000 1.2697030000 0.4479520000 0.0867210000 0.4467180000 0.4597940000 109337470 0 1785806848 4.1879072189 4.3703041077 6.2153019905 426 17.0000000000 0.0114729330 0.0049697889 0.0249688756 0.0054616934 2.2131510000 1.2764020000 0.4497800000 0.0000030000 0.4777250000 0.0066720000 109339144 0 1787346944 4.1817364693 4.3717007637 6.2203283310 427 17.0400000000 0.0109869335 0.0049838806 0.0249688756 0.0054661108 2.0881100000 1.2670380000 0.2229980000 0.0875880000 0.5012860000 0.0065890000 109340818 0 1785044992 4.1758389473 4.3732018471 6.2247848511 428 17.0800000000 0.0113940667 0.0049988577 0.0249688756 0.0054754840 2.1478070000 1.2843110000 0.3358620000 0.0000030000 0.5183800000 0.0066250000 109342492 0 1786712064 4.1709132195 4.3757009506 6.2287416458 429 17.1200000000 0.0110441139 0.0050129492 0.0249688756 0.0054754084 2.8487140000 1.2648790000 0.4468430000 0.0882180000 0.5167850000 0.5294300000 109344166 0 1785552896 4.1655507088 4.3757901192 6.2309732437 430 17.1600000000 0.0111448532 0.0050272094 0.0249688756 0.0054781383 2.0269490000 1.2720450000 0.2219590000 0.0000030000 0.5226740000 0.0076920000 109345840 0 1787092992 4.1606583595 4.3762674332 6.2344913483 431 17.2000000000 0.0106777884 0.0050403198 0.0249688756 0.0054755690 2.1433650000 1.2674910000 0.2587250000 0.0890280000 0.5189820000 0.0065580000 109347514 0 1784680448 4.1558241844 4.3754138947 6.2381501198 432 17.2400000000 0.0107377246 0.0050535082 0.0249688756 0.0054756546 2.2185110000 1.2690790000 0.4136250000 0.0000040000 0.5265860000 0.0066460000 109349188 0 1786449920 4.1505508423 4.3760490417 6.2426991463 433 17.2800000000 0.0103264945 0.0050656860 0.0249688756 0.0054734243 2.7479770000 1.2699970000 0.3322600000 0.0898290000 0.5200270000 0.5332710000 109350862 0 1785450496 4.1465592384 4.3770728111 6.2464590073 434 17.3200000000 0.0107427500 0.0050787668 0.0249688756 0.0054754822 2.0252700000 1.2655830000 0.2232190000 0.0000040000 0.5272810000 0.0066160000 109352536 0 1786957824 4.1411089897 4.3786864281 6.2488694191 435 17.3600000000 0.0105590858 0.0050913653 0.0249688756 0.0054734448 2.3352430000 1.2667880000 0.4485470000 0.0905260000 0.5201580000 0.0066290000 109354210 0 1784815616 4.1357698441 4.3770675659 6.2503633499 436 17.4000000000 0.0109501211 0.0051048028 0.0249688756 0.0054791429 2.0585620000 1.2673700000 0.2610000000 0.0000030000 0.5208480000 0.0066390000 109355884 0 1786204160 4.1307945251 4.3772039413 6.2531433105 437 17.4400000000 0.0107503301 0.0051177216 0.0249688756 0.0054772396 2.7245160000 1.2747560000 0.2991490000 0.0912430000 0.5216330000 0.5351290000 109357558 0 1785552896 4.1244492531 4.3782978058 6.2562031746 438 17.4800000000 0.0104277348 0.0051298449 0.0249688756 0.0054766313 2.2461320000 1.2641330000 0.4522490000 0.0000030000 0.5204110000 0.0067090000 109359232 0 1787092992 4.1193127632 4.3765220642 6.2585611343 439 17.5200000000 0.0100389589 0.0051410274 0.0249688756 0.0054744365 2.1919480000 1.2724360000 0.3019570000 0.0919610000 0.5163180000 0.0066590000 109360906 0 1785077760 4.1143574715 4.3760123253 6.2608976364 440 17.5600000000 0.0103254402 0.0051528102 0.0249688756 0.0054749768 2.0568070000 1.2667400000 0.2653990000 0.0000030000 0.5152490000 0.0066600000 109362580 0 1786585088 4.1091437340 4.3760814667 6.2630476952 441 17.6000000000 0.0104372771 0.0051647931 0.0249688756 0.0054737936 2.6756230000 1.2726360000 0.2662400000 0.0933190000 0.5138050000 0.5269450000 109364254 0 1784934400 4.1033306122 4.3759207726 6.2644782066 442 17.6400000000 0.0106898574 0.0051772932 0.0249688756 0.0054730669 2.0577040000 1.2705630000 0.2660230000 0.0000030000 0.5116690000 0.0067470000 109365928 0 1786712064 4.0981040001 4.3748750687 6.2655878067 443 17.6800000000 0.0106680524 0.0051896877 0.0249688756 0.0054732295 2.1952520000 1.2667190000 0.3127480000 0.0938030000 0.5126670000 0.0066790000 109367602 0 1785679872 4.0923619270 4.3759846687 6.2674336433 444 17.7200000000 0.0104939798 0.0052016343 0.0249688756 0.0054707462 2.2527810000 1.2711090000 0.4633390000 0.0000030000 0.5089510000 0.0067420000 109369276 0 1787076608 4.0868682861 4.3753461838 6.2698760033 445 17.7600000000 0.0104951868 0.0052135300 0.0249688756 0.0054681216 2.8513970000 1.2664640000 0.4595720000 0.0939720000 0.5099010000 0.5188190000 109370950 0 1784823808 4.0819191933 4.3751215935 6.2715244293 446 17.8000000000 0.0114642577 0.0052275450 0.0249688756 0.0054697558 2.0505070000 1.3121570000 0.2304390000 0.0000040000 0.4985100000 0.0067530000 109372624 0 1786331136 4.0762715340 4.3752865791 6.2730383873 447 17.8400000000 0.0114674242 0.0052415045 0.0249688756 0.0054695106 2.1064960000 1.2674760000 0.2326110000 0.0946550000 0.5022890000 0.0067860000 109374298 0 1785704448 4.0705952644 4.3748893738 6.2764739990 448 17.8800000000 0.0114471326 0.0052553563 0.0249688756 0.0054687137 2.0871380000 1.2685300000 0.3127780000 0.0000030000 0.4963630000 0.0067750000 109375972 0 1787228160 4.0639472008 4.3747491837 6.2783913612 449 17.9200000000 0.0114589315 0.0052691728 0.0249688756 0.0054666862 2.8492640000 1.2691350000 0.4746300000 0.0951770000 0.4931410000 0.5145190000 109377646 0 1784934400 4.0585017204 4.3738074303 6.2794108391 450 17.9600000000 0.0109907687 0.0052818874 0.0249688756 0.0054629214 2.0861090000 1.2690360000 0.3167980000 0.0000030000 0.4906770000 0.0069190000 109379320 0 1786458112 4.0529932976 4.3720321655 6.2807731628 451 18.0000000000 0.0104501778 0.0052933471 0.0249688756 0.0054648852 2.3459020000 1.2705720000 0.4887140000 0.0956730000 0.4813490000 0.0069060000 109380994 0 1785679872 4.0396623611 4.3701100349 6.2847161293 452 18.0400000000 0.0054034428 0.0052935906 0.0249688756 0.0054615372 2.2604120000 1.2747660000 0.4989280000 0.0000030000 0.4771570000 0.0069060000 109382668 0 1787330560 4.0337934494 4.3637666702 6.2871289253 453 18.0800000000 0.0041994941 0.0052911754 0.0249688756 0.0054565273 2.8363210000 1.2710110000 0.5010560000 0.0961210000 0.4742750000 0.4911420000 109384342 0 1784918016 4.0274100304 4.3592824936 6.2893233299 454 18.1200000000 0.0048743528 0.0052902573 0.0249688756 0.0054531681 2.2538120000 1.3123320000 0.4600000000 0.0000030000 0.4718230000 0.0069590000 109386016 0 1786568704 4.0200119019 4.3561153412 6.2927761078 455 18.1600000000 0.0055841492 0.0052909032 0.0249688756 0.0054486600 2.1399800000 1.2689110000 0.2914690000 0.0967420000 0.4731460000 0.0069700000 109387690 0 1785679872 4.0132737160 4.3551259041 6.2963032722 456 18.2000000000 0.0089012682 0.0052988207 0.0249688756 0.0054451488 2.0083580000 1.2742870000 0.2529260000 0.0000030000 0.4713550000 0.0070530000 109389364 0 1787203584 4.0077071190 4.3495187759 6.2979168892 457 18.2400000000 0.0090165250 0.0053069557 0.0249688756 0.0054421670 2.8386990000 1.2719270000 0.5118130000 0.0968370000 0.4684020000 0.4869740000 109391038 0 1785061376 4.0008001328 4.3491435051 6.3005714417 458 18.2800000000 0.0154280104 0.0053290541 0.0249688756 0.0054518713 2.0524170000 1.2744640000 0.3037140000 0.0000030000 0.4643720000 0.0070600000 109392712 0 1786458112 3.9935870171 4.3424806595 6.3023142815 459 18.3200000000 0.0176173691 0.0053558260 0.0249688756 0.0054518026 2.3515260000 1.2687950000 0.5167020000 0.0972000000 0.4589760000 0.0071060000 109394386 0 1785679872 3.9872326851 4.3391733170 6.3037576675 460 18.3600000000 0.0351559557 0.0054206089 0.0351559557 0.0054965459 2.0936710000 1.2716780000 0.3609350000 0.0000030000 0.4511030000 0.0071600000 109396060 0 1787330560 3.9814260006 4.3203339577 6.3054680824 461 18.4000000000 0.0308014229 0.0054756649 0.0351559557 0.0054977639 2.7250390000 1.2681800000 0.4507380000 0.0975940000 0.4431990000 0.4625310000 109397734 0 1784545280 3.9743199348 4.3234138489 6.3081665039 462 18.4400000000 0.5855139494 0.0067311590 0.5855139494 0.0262938214 2.1704550000 1.2706070000 0.4837800000 0.0000030000 0.4061150000 0.0071510000 109399408 0 1786195968 3.9668524265 3.7678294182 6.3082575798 463 18.4800000000 0.7399888039 0.0083148688 0.7399888039 0.0272434637 2.3487260000 1.2679490000 0.5605500000 0.0971720000 0.4131000000 0.0071890000 109401082 0 1788092416 3.9622118473 3.6135220528 6.3105106354 464 18.5200000000 0.7078096867 0.0098224008 0.7399888039 0.0272629854 2.2386680000 1.2692750000 0.5472610000 0.0000030000 0.4121410000 0.0072400000 109402756 0 1784934400 3.9557468891 3.6442737579 6.3112974167 465 18.5600000000 0.6996774077 0.0113059599 0.7399888039 0.0272400428 2.5388820000 1.2683800000 0.3390640000 0.0975810000 0.4066340000 0.4244180000 109404430 0 1786314752 3.9490063190 3.6512405872 6.3142771721 466 18.6000000000 0.7008354068 0.0127856368 0.7399888039 0.0272112206 1.9447170000 1.2704140000 0.2578720000 0.0000040000 0.4063030000 0.0072820000 109406104 0 1785679872 3.9427969456 3.6488182545 6.3170843124 467 18.6400000000 0.6708989143 0.0141948730 0.7399888039 0.0272253766 2.3372350000 1.2747440000 0.5520780000 0.0978030000 0.4024870000 0.0073240000 109407778 0 1787076608 3.9367301464 3.6792070866 6.3182826042 468 18.6800000000 0.8059988022 0.0158867617 0.8059988022 0.0278875001 2.2830590000 1.2701190000 0.5602370000 0.0000040000 0.4423620000 0.0074440000 109409452 0 1784553472 3.9316658974 3.5431799889 6.3176403046 469 18.7200000000 0.7996913195 0.0175579868 0.8059988022 0.0278622453 2.5989660000 1.2782610000 0.3102690000 0.0980460000 0.4459810000 0.4635970000 109411126 0 1785933824 3.9249737263 3.5494823456 6.3197946548 470 18.7600000000 0.8328990340 0.0192927550 0.8328990340 0.0278725191 2.2755550000 1.2688440000 0.5393480000 0.0000040000 0.4569090000 0.0076640000 109412800 0 1787838464 3.9190626144 3.5152571201 6.3204021454 471 18.8000000000 0.7969820499 0.0209439000 0.8328990340 0.0279185044 2.1684020000 1.2715280000 0.3300300000 0.0984490000 0.4580440000 0.0075580000 109414474 0 1784553472 3.9053168297 3.5469317436 6.3215589523 472 18.8400000000 0.7724652886 0.0225361063 0.8328990340 0.0279176510 2.2822740000 1.2663320000 0.5544890000 0.0000030000 0.4509110000 0.0076450000 109416148 0 1785933824 3.9004280567 3.5702834129 6.3230676651 473 18.8800000000 0.7518031001 0.0240778970 0.8328990340 0.0279100982 2.8465110000 1.2692400000 0.5530190000 0.0987760000 0.4509930000 0.4715950000 109417822 0 1787838464 3.8984596729 3.5888617039 6.3218431473 474 18.9200000000 0.7459369302 0.0256008063 0.8328990340 0.0278853860 2.1180130000 1.3004980000 0.3557550000 0.0000040000 0.4512580000 0.0076910000 109419496 0 1784426496 3.8961772919 3.5929014683 6.3221254349 475 18.9600000000 0.7118917704 0.0270456294 0.8328990340 0.0279084143 2.3696560000 1.2700920000 0.5448070000 0.0991470000 0.4450130000 0.0077490000 109421170 0 1786060800 3.8926134109 3.6261353493 6.3237423897 476 19.0000000000 0.6378069520 0.0283287414 0.8328990340 0.0281289264 2.2694750000 1.2680710000 0.5656770000 0.0000030000 0.4250650000 0.0078340000 109422844 0 1787719680 3.8874197006 3.6975357533 6.3241806030 477 19.0400000000 0.6686985493 0.0296712358 0.8328990340 0.0281310265 2.8273330000 1.2718950000 0.5470170000 0.1000120000 0.4436790000 0.4618520000 109424518 0 1784688640 3.8851535320 3.6643483639 6.3235316277 478 19.0800000000 0.6173581481 0.0309007063 0.8328990340 0.0282363610 1.9962760000 1.2695840000 0.2841350000 0.0000030000 0.4317710000 0.0079370000 109426192 0 1786068992 3.8789288998 3.7134244442 6.3296418190 479 19.1200000000 0.6129044890 0.0321157455 0.8328990340 0.0282100571 2.2181260000 1.2682190000 0.3977140000 0.1005920000 0.4407780000 0.0078920000 109427866 0 1787981824 3.8784365654 3.7178838253 6.3300428391 480 19.1600000000 0.6421769857 0.0333867065 0.8328990340 0.0282064492 2.2918050000 1.2711500000 0.5557140000 0.0000030000 0.4541550000 0.0079730000 109429540 0 1784553472 3.8783941269 3.6879978180 6.3292450905 481 19.2000000000 0.5946366191 0.0345535462 0.8328990340 0.0282858493 2.8548670000 1.2714750000 0.5620890000 0.1015730000 0.4470680000 0.4698150000 109431214 0 1785933824 3.8768281937 3.7347879410 6.3305830956 482 19.2400000000 0.5864313841 0.0356985210 0.8328990340 0.0282683724 2.3046400000 1.2945110000 0.5487020000 0.0000030000 0.4505910000 0.0080190000 109432888 0 1787965440 3.8760378361 3.7432594299 6.3309707642 483 19.2800000000 0.5879274011 0.0368418520 0.8328990340 0.0282432720 2.3851970000 1.2689110000 0.5407440000 0.1018870000 0.4627240000 0.0080840000 109434562 0 1784664064 3.8751282692 3.7405512333 6.3324031830 484 19.3200000000 0.5671964884 0.0379376260 0.8328990340 0.0282432784 2.2843530000 1.2673880000 0.5465090000 0.0000030000 0.4595130000 0.0079550000 109436236 0 1786060800 3.8755331039 3.7608120441 6.3333640099 485 19.3600000000 0.5459066033 0.0389849847 0.8328990340 0.0282508788 2.8748540000 1.2699640000 0.5460190000 0.1028470000 0.4644870000 0.4886690000 109437910 0 1787965440 3.8758347034 3.7820310593 6.3335433006 486 19.4000000000 0.2964442372 0.0395147363 0.8328990340 0.0305468395 2.3014430000 1.2671200000 0.5769340000 0.0000040000 0.4463720000 0.0080410000 109439584 0 1784537088 3.8747060299 4.0315423012 6.3370833397 487 19.4400000000 0.7395424843 0.0409521649 0.8328990340 0.0363806116 2.1988300000 1.2964470000 0.2565780000 0.1041990000 0.5306940000 0.0080230000 109441258 0 1785933824 3.8751313686 3.5885584354 6.3372783661 488 19.4800000000 0.2698608041 0.0414212400 0.8328990340 0.0423315601 2.2910320000 1.2735840000 0.5516560000 0.0000050000 0.4548950000 0.0080030000 109442932 0 1787965440 3.8755171299 4.0571923256 6.3419733047 489 19.5200000000 0.7069671750 0.0427822746 0.8328990340 0.0465713099 2.9218180000 1.2682850000 0.4567970000 0.1042040000 0.5294170000 0.5601690000 109444606 0 1784950784 3.8726303577 3.6205401421 6.3453993797 490 19.5600000000 0.7077039480 0.0441392576 0.8328990340 0.0465343916 2.2786860000 1.2703350000 0.4676640000 0.0000050000 0.5297120000 0.0080580000 109446280 0 1786593280 3.8726303577 3.6205401421 6.3453993797 491 19.6000000000 0.7081319094 0.0454915848 0.8328990340 0.0465001793 2.2652380000 1.2693600000 0.4544670000 0.0000040000 0.5303720000 0.0081150000 109447954 0 1785815040 3.8726303577 3.6205401421 6.3453993797 492 19.6400000000 0.7083985806 0.0468389568 0.8328990340 0.0464639355 2.2674800000 1.2722100000 0.4524490000 0.0000060000 0.5317820000 0.0080840000 109449628 0 1787101184 3.8726303577 3.6205401421 6.3453993797 493 19.6800000000 0.7099820375 0.0481840746 0.8328990340 0.0464275438 2.8402840000 1.2822110000 0.4708290000 0.0000030000 0.5295450000 0.5547390000 109451302 0 1784823808 3.8726303577 3.6205401421 6.3453993797 494 19.7200000000 0.7099336982 0.0495236487 0.8328990340 0.0463995548 2.2757260000 1.2770400000 0.4579960000 0.0000030000 0.5296420000 0.0080690000 109452976 0 1786331136 3.8726303577 3.6205401421 6.3453993797 495 19.7600000000 0.7099314332 0.0508578059 0.8328990340 0.0463705842 2.2929880000 1.2936290000 0.4585870000 0.0000040000 0.5297880000 0.0080130000 109454650 0 1785315328 3.8726303577 3.6205401421 6.3453993797 496 19.8000000000 0.7108371258 0.0521884093 0.8328990340 0.0463389145 2.2606670000 1.2787010000 0.4413160000 0.0000040000 0.5293170000 0.0082980000 109456324 0 1786839040 3.8726303577 3.6205401421 6.3453993797 497 19.8400000000 0.7121461034 0.0535162920 0.8328990340 0.0463033590 2.7885310000 1.2701000000 0.4313020000 0.0000030000 0.5294780000 0.5546730000 109457998 0 1784918016 3.8726303577 3.6205401421 6.3453993797 498 19.8800000000 0.7128450871 0.0548402454 0.8328990340 0.0462689354 2.2523410000 1.2753530000 0.4365990000 0.0000030000 0.5294250000 0.0079920000 109459672 0 1786441728 3.8726303577 3.6205401421 6.3453993797 499 19.9200000000 0.7126660347 0.0561585336 0.8328990340 0.0462369601 2.2407920000 1.2693480000 0.4309560000 0.0000030000 0.5294930000 0.0079940000 109461346 0 1785679872 3.8726303577 3.6205401421 6.3453993797 500 19.9600000000 0.7139804363 0.0574741774 0.8328990340 0.0462020063 2.2330520000 1.2748500000 0.4173480000 0.0000040000 0.5297760000 0.0080710000 109463020 0 1787203584 3.8726303577 3.6205401421 6.3453993797 501 20.0000000000 0.7146553397 0.0587859162 0.8328990340 0.0461710763 2.7622230000 1.2696580000 0.4056010000 0.0000040000 0.5295170000 0.5544070000 109464694 0 1784553472 3.8726303577 3.6205401421 6.3453993797 502 20.0400000000 0.7152876258 0.0600936886 0.8328990340 0.0461432463 2.1955080000 1.2777590000 0.3773110000 0.0000040000 0.5294610000 0.0079920000 109466368 0 1786060800 3.8726303577 3.6205401421 6.3453993797 503 20.0800000000 0.7164087892 0.0613984900 0.8328990340 0.0461145307 2.1873930000 1.2737210000 0.3732980000 0.0000040000 0.5292980000 0.0080860000 109468042 0 1787965440 3.8726303577 3.6205401421 6.3453993797 504 20.1200000000 0.7168497443 0.0626989885 0.8328990340 0.0460877239 2.1934410000 1.2697770000 0.3823900000 0.0000040000 0.5302470000 0.0080320000 109469716 0 1784934400 3.8726303577 3.6205401421 6.3453993797 505 20.1600000000 0.7178567052 0.0639963305 0.8328990340 0.0460607316 2.7082520000 1.2711570000 0.3499430000 0.0000040000 0.5294850000 0.5546800000 109471390 0 1786322944 3.8726303577 3.6205401421 6.3453993797 506 20.2000000000 0.7182233334 0.0652892692 0.8328990340 0.0460350835 2.1675810000 1.2711260000 0.3503320000 0.0000040000 0.5349860000 0.0080860000 109473064 0 1785307136 3.8726303577 3.6205401421 6.3453993797 507 20.2400000000 0.7180660367 0.0665767974 0.8328990340 0.0460077759 2.1301380000 1.2677830000 0.3206770000 0.0000040000 0.5305210000 0.0081010000 109474738 0 1786822656 3.8726303577 3.6205401421 6.3453993797 508 20.2800000000 0.7178546190 0.0678588403 0.8328990340 0.0459800010 2.1191130000 1.2706860000 0.3069250000 0.0000040000 0.5304390000 0.0080430000 109476412 0 1784553472 3.8726303577 3.6205401421 6.3453993797 509 20.3200000000 0.7175819874 0.0691353102 0.8328990340 0.0459548144 2.6988160000 1.2745470000 0.3361830000 0.0000040000 0.5302740000 0.5546780000 109478086 0 1786060800 3.8726303577 3.6205401421 6.3453993797 510 20.3600000000 0.7181630731 0.0704079136 0.8328990340 0.0459243128 2.1231450000 1.2705000000 0.3113360000 0.0000040000 0.5301650000 0.0080900000 109479760 0 1787838464 3.8726303577 3.6205401421 6.3453993797 511 20.4000000000 0.7179374695 0.0716750947 0.8328990340 0.0458946973 2.1438710000 1.2756820000 0.3274220000 0.0000040000 0.5296350000 0.0081050000 109481434 0 1784545280 3.8726303577 3.6205401421 6.3453993797 512 20.4400000000 0.7185947895 0.0729386098 0.8328990340 0.0458635085 2.0669600000 1.2687630000 0.2575100000 0.0000040000 0.5294520000 0.0080720000 109483108 0 1785925632 3.8726303577 3.6205401421 6.3453993797 513 20.4800000000 0.7187823057 0.0741975643 0.8328990340 0.0458299755 2.5979090000 1.2743360000 0.2353070000 0.0000050000 0.5303290000 0.5547230000 109525742 0 1787854848 3.8726303577 3.6205401421 6.3453993797 514 20.5200000000 0.7191399932 0.0754523162 0.8328990340 0.0457965381 2.1354820000 1.2653030000 0.3294200000 0.0000040000 0.5295170000 0.0081420000 109611384 0 1784553472 3.8726303577 3.6205401421 6.3453993797 515 20.5600000000 0.7190058827 0.0767019347 0.8328990340 0.0457603160 2.1445140000 1.2690170000 0.3341790000 0.0000050000 0.5300580000 0.0081700000 109613058 0 1785933824 3.8726303577 3.6205401421 6.3453993797 516 20.6000000000 0.7189013362 0.0779465072 0.8328990340 0.0457226501 2.1550560000 1.2752890000 0.3386460000 0.0000050000 0.5298300000 0.0081920000 109614732 0 1787965440 3.8726303577 3.6205401421 6.3453993797 517 20.6400000000 0.7183590531 0.0791852162 0.8328990340 0.0456843582 2.6383150000 1.2677520000 0.2769850000 0.0000050000 0.5297180000 0.5606020000 109616406 0 1784553472 3.8726303577 3.6205401421 6.3453993797 518 20.6800000000 0.7176628709 0.0804177985 0.8328990340 0.0456473633 2.0947820000 1.2700100000 0.2836910000 0.0000040000 0.5296510000 0.0082080000 109618080 0 1785933824 3.8726303577 3.6205401421 6.3453993797 519 20.7200000000 0.7177083492 0.0816457187 0.8328990340 0.0456109119 2.0971830000 1.2678280000 0.2884370000 0.0000040000 0.5294860000 0.0082280000 109619754 0 1787838464 3.8726303577 3.6205401421 6.3453993797 520 20.7600000000 0.7161721587 0.0828659618 0.8328990340 0.0455733448 2.0868040000 1.2741400000 0.2717510000 0.0000040000 0.5294290000 0.0082850000 109621428 0 1784578048 3.8726303577 3.6205401421 6.3453993797 521 20.8000000000 0.7154984474 0.0840802276 0.8328990340 0.0455353096 2.6273680000 1.2675230000 0.2717470000 0.0000050000 0.5297570000 0.5552050000 109623102 0 1785942016 3.8726303577 3.6205401421 6.3453993797 522 20.8400000000 0.3706025481 0.0846291210 0.8328990340 0.0593120653 2.4046940000 1.2736160000 0.5065990000 0.0000050000 0.6131250000 0.0081950000 109624776 0 1787863040 3.8510818481 4.0300431252 6.6316890717 523 20.8800000000 0.2692656815 0.0849821546 0.8328990340 0.0594407862 2.3482090000 1.2682860000 0.4672510000 0.1201290000 0.4810270000 0.0083210000 109626450 0 1784426496 3.8504471779 4.1497979164 6.6088190079 524 20.9200000000 0.2867882550 0.0853672807 0.8328990340 0.0593879240 2.2562800000 1.2760980000 0.4868240000 0.0000040000 0.4819300000 0.0082930000 109628124 0 1785806848 3.8487169743 4.1353893280 6.6200637817 525 20.9600000000 0.2851961553 0.0857479071 0.8328990340 0.0593314825 2.8519380000 1.2685800000 0.4722510000 0.1205480000 0.4834720000 0.5039050000 109629798 0 1787711488 3.8455893993 4.1337947845 6.6189131737 526 21.0000000000 0.2856784761 0.0861280033 0.8328990340 0.0592750610 2.2353430000 1.2758420000 0.4417700000 0.0000060000 0.5063090000 0.0082060000 109631472 0 1784410112 3.8428528309 4.1332821846 6.6156778336 527 21.0400000000 0.2850918770 0.0865055438 0.8328990340 0.0592193619 2.4140230000 1.3000880000 0.4834670000 0.1211710000 0.4978870000 0.0082090000 109633146 0 1785933824 3.8402235508 4.1342873573 6.6118946075 528 21.0800000000 0.2824049592 0.0868765654 0.8328990340 0.0591638164 2.3009830000 1.2757660000 0.4908990000 0.0000060000 0.5228750000 0.0082490000 109634820 0 1787711488 3.8359656334 4.1342005730 6.6103096008 529 21.1200000000 0.2824085355 0.0872461911 0.8328990340 0.0591079553 2.8894610000 1.2690080000 0.4516710000 0.1222730000 0.5114380000 0.5317710000 109636494 0 1784315904 3.8317761421 4.1324896812 6.6079182625 530 21.1600000000 0.2758044004 0.0876019613 0.8328990340 0.0590537191 2.3224130000 1.2756630000 0.4986180000 0.0000050000 0.5365950000 0.0082060000 109638168 0 1786060800 3.8291835785 4.1415543556 6.6022558212 531 21.2000000000 0.2737948000 0.0879526069 0.8328990340 0.0589983467 2.4188270000 1.2682070000 0.4999230000 0.1223940000 0.5167760000 0.0082130000 109639842 0 1787744256 3.8258605003 4.1426143646 6.5986027718 532 21.2400000000 0.2718564272 0.0882982908 0.8328990340 0.0589436415 2.3260530000 1.2699390000 0.5051350000 0.0000050000 0.5394720000 0.0082660000 109641516 0 1785315328 3.8214068413 4.1443371773 6.5962009430 533 21.2800000000 0.2704459131 0.0886400312 0.8328990340 0.0588887797 2.9829620000 1.2664290000 0.5046920000 0.1231660000 0.5326750000 0.5527280000 109643190 0 1786839040 3.8177175522 4.1452550888 6.5933198929 534 21.3200000000 0.2660274208 0.0889722173 0.8328990340 0.0588349921 2.3507970000 1.2782610000 0.5113920000 0.0000050000 0.5495640000 0.0083230000 109644864 0 1784848384 3.8137125969 4.1486082077 6.5910167694 535 21.3600000000 0.2641323507 0.0892996194 0.8328990340 0.0587801842 2.4880090000 1.3051740000 0.5092370000 0.1236190000 0.5384140000 0.0082480000 109646538 0 1786339328 3.8084287643 4.1488175392 6.5897593498 536 21.4000000000 0.2601811290 0.0896184282 0.8328990340 0.0587255415 2.3645760000 1.2753980000 0.5131590000 0.0000050000 0.5645120000 0.0082010000 109648212 0 1785704448 3.8046071529 4.1496763229 6.5826387405 537 21.4400000000 0.2600272596 0.0899357631 0.8328990340 0.0586707822 2.9828950000 1.2659340000 0.4683090000 0.1241710000 0.5495880000 0.5716130000 109649886 0 1787092992 3.8003158569 4.1497268677 6.5775685310 538 21.4800000000 0.2565290630 0.0902454161 0.8328990340 0.0586164996 2.3713640000 1.2745330000 0.5182530000 0.0000050000 0.5670010000 0.0082030000 109651560 0 1784918016 3.7956032753 4.1531424522 6.5718512535 539 21.5200000000 0.2544142306 0.0905499964 0.8328990340 0.0585621534 2.4750540000 1.2658800000 0.5166630000 0.1244810000 0.5564910000 0.0082480000 109653234 0 1786331136 3.7912807465 4.1535787582 6.5683460236 540 21.5600000000 0.2526616752 0.0908502033 0.8328990340 0.0585081771 2.3832990000 1.2735140000 0.5197130000 0.0000040000 0.5785380000 0.0082630000 109654908 0 1785806848 3.7863156796 4.1546888351 6.5651297569 541 21.6000000000 0.2491627634 0.0911428328 0.8328990340 0.0584543153 2.9920760000 1.2759260000 0.4354300000 0.1266610000 0.5661250000 0.5845790000 109656582 0 1787092992 3.7814772129 4.1563773155 6.5613470078 542 21.6400000000 0.2441767603 0.0914251832 0.8328990340 0.0584010065 2.3601530000 1.2737210000 0.4789140000 0.0000040000 0.5959740000 0.0082560000 109658256 0 1785061376 3.7774343491 4.1572599411 6.5569062233 543 21.6800000000 0.2434027344 0.0917050682 0.8328990340 0.0583477905 2.4071780000 1.2622930000 0.4342240000 0.1259330000 0.5732100000 0.0082090000 109659930 0 1786712064 3.7731819153 4.1532654762 6.5512351990 544 21.7200000000 0.2430267632 0.0919832330 0.8328990340 0.0583001914 2.4302370000 1.2721910000 0.5306840000 0.0000040000 0.6157890000 0.0082410000 109661604 0 1785585664 3.7656002045 4.1453685760 6.5369086266 545 21.7600000000 0.2572595179 0.0922864923 0.8328990340 0.0582509593 3.1029310000 1.2661730000 0.5264480000 0.1260770000 0.5770440000 0.6038790000 109663278 0 1787219968 3.7607014179 4.1282172203 6.5318670273 546 21.8000000000 0.2628101110 0.0925988066 0.8328990340 0.0581983683 2.3936890000 1.2664660000 0.5314160000 0.0000040000 0.5842890000 0.0082090000 109664952 0 1784807424 3.7562479973 4.1190748215 6.5263700485 547 21.8400000000 0.2597550452 0.0929043939 0.8328990340 0.0581461134 2.5173690000 1.2633650000 0.5319010000 0.1260060000 0.5846010000 0.0081920000 109666626 0 1786458112 3.7516016960 4.1194434166 6.5205612183 548 21.8800000000 0.2695503235 0.0932267405 0.8328990340 0.0580943570 2.4051230000 1.2688410000 0.5357500000 0.0000050000 0.5889400000 0.0081880000 109668300 0 1785704448 3.7458095551 4.1111664772 6.5147523880 549 21.9200000000 0.2690351605 0.0935469744 0.8328990340 0.0580422568 3.1174420000 1.2649180000 0.5366830000 0.1263220000 0.5843830000 0.6017750000 109669974 0 1787228160 3.7405908108 4.1151962280 6.5100202560 550 21.9600000000 0.2755631506 0.0938779129 0.8328990340 0.0579916467 2.4051420000 1.2638890000 0.5376340000 0.0000030000 0.5919980000 0.0082130000 109671648 0 1784942592 3.7371809483 4.0986137390 6.5066137314 551 22.0000000000 0.2780254483 0.0942121189 0.8328990340 0.0579404697 2.5549530000 1.2965980000 0.5367230000 0.1316860000 0.5782380000 0.0082550000 109673322 0 1786458112 3.7329471111 4.0938754082 6.5003347397 552 22.0400000000 0.2829559445 0.0945540462 0.8328990340 0.0578881262 2.4023660000 1.2627900000 0.5401620000 0.0000040000 0.5878480000 0.0082450000 109674996 0 1785679872 3.7274596691 4.0944604874 6.4931206703 553 22.0800000000 0.2789455652 0.0948874847 0.8328990340 0.0578364527 3.1314060000 1.2707280000 0.5424620000 0.1265170000 0.5862050000 0.6020330000 109676670 0 1787076608 3.7233452797 4.1004657745 6.4874000549 554 22.1200000000 0.2824967802 0.0952261297 0.8328990340 0.0577842704 2.4129970000 1.2610470000 0.5420580000 0.0000060000 0.5983380000 0.0081950000 109678344 0 1784807424 3.7192006111 4.0919027328 6.4808712006 555 22.1600000000 0.2878511846 0.0955732018 0.8328990340 0.0577323060 2.5268600000 1.2626980000 0.5454420000 0.1273320000 0.5797620000 0.0083030000 109680018 0 1786331136 3.7152330875 4.0870561600 6.4760165215 556 22.2000000000 0.2886949778 0.0959205431 0.8328990340 0.0576802988 2.4132720000 1.2633400000 0.5415700000 0.0000040000 0.5966870000 0.0081950000 109681692 0 1788092416 3.7121293545 4.0825209618 6.4687962532 557 22.2400000000 0.2892853916 0.0962676973 0.8328990340 0.0576286426 3.1264010000 1.2654160000 0.5501990000 0.1273220000 0.5799390000 0.6000970000 109683366 0 1785077760 3.7076005936 4.0827693939 6.4606814384 558 22.2800000000 0.3062111735 0.0966439401 0.8328990340 0.0575807505 2.4008310000 1.2630650000 0.5457250000 0.0000040000 0.5804900000 0.0081810000 109685040 0 1786695680 3.7043709755 4.0692739487 6.4665870667 559 22.3200000000 0.2996155620 0.0970070378 0.8328990340 0.0575299657 2.5349670000 1.2690000000 0.5479560000 0.1274060000 0.5789260000 0.0082910000 109686714 0 1784680448 3.7009367943 4.0730338097 6.4567036629 560 22.3600000000 0.3041473925 0.0973769313 0.8328990340 0.0574790300 2.4334860000 1.2646810000 0.5482140000 0.0000040000 0.6088190000 0.0083370000 109688388 0 1786204160 3.6979243755 4.0627107620 6.4437932968 561 22.4000000000 0.2449721694 0.0976400244 0.8328990340 0.0575154796 3.1233090000 1.2697190000 0.5412560000 0.1280910000 0.5791690000 0.6016160000 109690062 0 1788116992 3.6951923370 4.0925021172 6.3738436699 562 22.4400000000 0.1828019619 0.0977915581 0.8328990340 0.0576400590 2.5287750000 1.2674460000 0.5443110000 0.0000030000 0.7052130000 0.0082650000 109691736 0 1784815616 3.6929774284 4.1225652695 6.2764673233 563 22.4800000000 0.1703531593 0.0979204419 0.8328990340 0.0576080999 2.4818560000 1.2709870000 0.5212760000 0.1287880000 0.5490310000 0.0081710000 109693410 0 1786339328 3.6903569698 4.1322264671 6.2368087769 564 22.5200000000 0.1992878765 0.0981001714 0.8328990340 0.0576047862 2.3635130000 1.2637890000 0.5461110000 0.0000040000 0.5419960000 0.0081820000 109695084 0 1785552896 3.6866128445 4.1068611145 6.2766938210 565 22.5600000000 0.1999211162 0.0982803855 0.8328990340 0.0575581276 3.0629550000 1.2723500000 0.5543480000 0.1298100000 0.5403200000 0.5627010000 109696758 0 1787330560 3.6792049408 4.1095485687 6.2665553093 566 22.6000000000 0.1939520985 0.0984494168 0.8328990340 0.0575310115 2.2029830000 1.2952520000 0.3592120000 0.0000040000 0.5368210000 0.0082690000 109698432 0 1784934400 3.6751141548 4.1223793030 6.2936625481 567 22.6400000000 0.1934660673 0.0986169946 0.8328990340 0.0574809729 2.5024300000 1.2712660000 0.5518360000 0.1303640000 0.5373550000 0.0082090000 109700106 0 1786331136 3.6717686653 4.1218872070 6.2865080833 568 22.6800000000 0.2039506286 0.0988024412 0.8328990340 0.0574521700 2.3605870000 1.2663270000 0.5453850000 0.0000040000 0.5371310000 0.0083120000 109701780 0 1785679872 3.6679041386 4.1301164627 6.3143687248 569 22.7200000000 0.1991990358 0.0989788851 0.8328990340 0.0574035611 2.9171950000 1.2726060000 0.4125060000 0.1313740000 0.5372710000 0.5600070000 109703454 0 1787092992 3.6642885208 4.1353626251 6.3064517975 570 22.7600000000 0.2198400944 0.0991909223 0.8328990340 0.0573792760 2.3697040000 1.2655120000 0.5465410000 0.0000040000 0.5459580000 0.0082240000 109705128 0 1784934400 3.6605696678 4.1336946487 6.3383049965 571 22.8000000000 0.2017442584 0.0993705253 0.8328990340 0.0573338941 2.5070780000 1.2682000000 0.5553800000 0.1321580000 0.5397600000 0.0081630000 109706802 0 1786331136 3.6582705975 4.1468887329 6.3233141899 572 22.8400000000 0.2444696873 0.0996241952 0.8328990340 0.0573267251 2.3742920000 1.2665690000 0.5464240000 0.0000050000 0.5495550000 0.0081940000 109708476 0 1785696256 3.6543529034 4.1460876465 6.3679757118 573 22.8800000000 0.2751697302 0.0999305574 0.8328990340 0.0573050341 3.0664000000 1.2663500000 0.5466940000 0.1329760000 0.5481630000 0.5687790000 109710150 0 1787203584 3.6494958401 4.1509513855 6.4041194916 574 22.9200000000 0.2695738375 0.1002261032 0.8328990340 0.0572577206 2.3859920000 1.2658540000 0.5570780000 0.0000050000 0.5513210000 0.0082130000 109711824 0 1784807424 3.6448779106 4.1543745995 6.3932447433 575 22.9600000000 0.2593768835 0.1005028872 0.8328990340 0.0572252955 2.5485820000 1.2952950000 0.5582730000 0.1342710000 0.5490880000 0.0082140000 109713498 0 1785569280 3.6421318054 4.1867337227 6.3923301697 576 23.0000000000 0.2583977580 0.1007770102 0.8328990340 0.0571763716 2.4086100000 1.2680230000 0.5550390000 0.0000040000 0.5738070000 0.0082300000 109715172 0 1786966016 3.6386690140 4.1864094734 6.3875617981 577 23.0400000000 0.2638197839 0.1010595800 0.8328990340 0.0571289854 3.0978770000 1.2710340000 0.5585040000 0.1353600000 0.5524280000 0.5770640000 109716846 0 1784451072 3.6344447136 4.1864576340 6.3874168396 578 23.0800000000 0.2831153870 0.1013745554 0.8328990340 0.0570889593 2.3098240000 1.2735160000 0.4703140000 0.0000050000 0.5543170000 0.0081980000 109718520 0 1785942016 3.6318836212 4.1885261536 6.4011721611 579 23.1200000000 0.2894850373 0.1016994440 0.8328990340 0.0570406197 2.2145620000 1.2964530000 0.2187740000 0.1361630000 0.5514940000 0.0082210000 109720194 0 1787838464 3.6302163601 4.1913437843 6.4007134438 580 23.1600000000 0.2985615134 0.1020388614 0.8328990340 0.0569948589 2.4105230000 1.2643100000 0.5586360000 0.0000050000 0.5759230000 0.0081660000 109721868 0 1784934400 3.6287643909 4.1995086670 6.4058375359 581 23.2000000000 0.3173088431 0.1024093777 0.8328990340 0.0569621254 3.1172860000 1.2695770000 0.5538000000 0.1377500000 0.5626190000 0.5900510000 109723542 0 1786441728 3.6233208179 4.2163619995 6.4235849380 582 23.2400000000 0.3307844102 0.1028017746 0.8328990340 0.0569179700 2.4248120000 1.2684150000 0.5675800000 0.0000050000 0.5771690000 0.0081580000 109725216 0 1785679872 3.6159160137 4.2104978561 6.4311404228 583 23.2800000000 0.3486230671 0.1032234235 0.8328990340 0.0568761317 2.5357480000 1.2675310000 0.5564510000 0.1393620000 0.5606190000 0.0082390000 109726890 0 1787203584 3.6134901047 4.2119469643 6.4429249763 584 23.3200000000 0.3645700812 0.1036709349 0.8328990340 0.0568301969 2.4281260000 1.2700990000 0.5628370000 0.0000050000 0.5835170000 0.0081530000 109728564 0 1784680448 3.6098275185 4.2003622055 6.4500360489 585 23.3600000000 0.3776356280 0.1041392506 0.8328990340 0.0567845254 3.1240710000 1.2695210000 0.5570270000 0.1412030000 0.5620260000 0.5907200000 109730238 0 1786187776 3.6032154560 4.1965026855 6.4560780525 586 23.4000000000 0.3877618611 0.1046232483 0.8328990340 0.0567378184 2.4337770000 1.2749010000 0.5601080000 0.0000050000 0.5870750000 0.0081620000 109731912 0 1788092416 3.5999186039 4.1938295364 6.4602484703 587 23.4400000000 0.3982483745 0.1051234614 0.8328990340 0.0566935914 2.5772500000 1.2896920000 0.5660890000 0.1431510000 0.5665870000 0.0082160000 109733586 0 1784680448 3.5951569080 4.1975140572 6.4656767845 588 23.4800000000 0.3984804749 0.1056223679 0.8328990340 0.0566463680 2.4418780000 1.2771460000 0.5562700000 0.0000050000 0.5966800000 0.0082170000 109735260 0 1786322944 3.5883111954 4.1839513779 6.4565963745 589 23.5200000000 0.4033417106 0.1061278337 0.8328990340 0.0565984105 3.1830650000 1.3053910000 0.5536360000 0.1448080000 0.5727250000 0.6029460000 109736934 0 1788100608 3.5819585323 4.1715965271 6.4519715309 590 23.5600000000 0.4022077024 0.1066296640 0.8328990340 0.0565507410 2.4359230000 1.2733540000 0.5575360000 0.0000050000 0.5932430000 0.0082020000 109738608 0 1784680448 3.5759434700 4.1653714180 6.4423332214 591 23.6000000000 0.4038800001 0.1071326256 0.8328990340 0.0565028807 2.5487300000 1.2687870000 0.5525020000 0.1461230000 0.5694660000 0.0082550000 109740282 0 1786187776 3.5695481300 4.1593232155 6.4358878136 592 23.6400000000 0.4018628895 0.1076304808 0.8328990340 0.0564559203 2.3808080000 1.2748120000 0.5111310000 0.0000060000 0.5820170000 0.0082020000 109741956 0 1785200640 3.5633015633 4.1608061790 6.4264407158 593 23.6800000000 0.4013013542 0.1081257099 0.8328990340 0.0564091520 3.0421110000 1.2682030000 0.4621670000 0.1475940000 0.5626130000 0.5978550000 109743630 0 1783918592 3.5573198795 4.1599349976 6.4179606438 594 23.7200000000 0.4003228545 0.1086176243 0.8328990340 0.0563629398 2.2915890000 1.2768470000 0.4177630000 0.0000050000 0.5852090000 0.0082340000 109745304 0 1785425920 3.5500459671 4.1587667465 6.4103121758 595 23.7600000000 0.3991323411 0.1091058843 0.8328990340 0.0563166913 2.2621770000 1.2721360000 0.2745590000 0.1496390000 0.5540760000 0.0082070000 109746978 0 1787203584 3.5415053368 4.1572303772 6.4020781517 596 23.8000000000 0.3955568373 0.1095865067 0.8328990340 0.0562705075 2.3208810000 1.2741230000 0.4693550000 0.0000050000 0.5655320000 0.0082770000 109748652 0 1784569856 3.5340855122 4.1582937241 6.3917284012 597 23.8400000000 0.3933171928 0.1100617675 0.8328990340 0.0562236409 2.9968910000 1.2687980000 0.4536560000 0.1508290000 0.5440920000 0.5758020000 109750326 0 1785933824 3.5302278996 4.1614999771 6.3821859360 598 23.8800000000 0.3932222724 0.1105352801 0.8328990340 0.0561772915 2.1595560000 1.2716830000 0.3202960000 0.0000050000 0.5557710000 0.0082010000 109752000 0 1787727872 3.5216898918 4.1599836349 6.3738584518 599 23.9200000000 0.3914055228 0.1110041786 0.8328990340 0.0561317687 2.3691440000 1.3002640000 0.3689940000 0.1523240000 0.5357210000 0.0082480000 109753674 0 1784537088 3.5132863522 4.1618719101 6.3638906479 600 23.9600000000 0.3892295063 0.1114678875 0.8328990340 0.0560864972 2.4017160000 1.2768640000 0.5582340000 0.0000050000 0.5548310000 0.0081980000 109755348 0 1786060800 3.5073671341 4.1640567780 6.3546314240 601 24.0000000000 0.3875654340 0.1119272844 0.8328990340 0.0560416016 3.0841990000 1.2708360000 0.5574110000 0.1541370000 0.5329420000 0.5651650000 109757022 0 1787711488 3.4998962879 4.1645350456 6.3452548981 602 24.0400000000 0.3833329082 0.1123781244 0.8328990340 0.0560021314 2.4055290000 1.2750860000 0.5581410000 0.0000050000 0.5604180000 0.0082920000 109758696 0 1784561664 3.4836156368 4.1692538261 6.3255820274 603 24.0800000000 0.3830616474 0.1128270191 0.8328990340 0.0559574181 2.2821200000 1.2734290000 0.3075850000 0.1562520000 0.5330900000 0.0081450000 109760370 0 1786068992 3.4744195938 4.1668052673 6.3171572685 604 24.1200000000 0.3814857304 0.1132718183 0.8328990340 0.0559135244 2.1054540000 1.2707270000 0.2784410000 0.0000050000 0.5444750000 0.0082190000 109762044 0 1787711488 3.4626004696 4.1682372093 6.3078145981 605 24.1600000000 0.3757810891 0.1137057179 0.8328990340 0.0558698773 2.8565030000 1.2706010000 0.3173170000 0.1579090000 0.5336160000 0.5734230000 109763718 0 1784299520 3.4563388824 4.1752405167 6.2954235077 606 24.2000000000 0.3743379116 0.1141358040 0.8328990340 0.0558250763 2.0688460000 1.2737380000 0.2299970000 0.0000050000 0.5532130000 0.0081630000 109765392 0 1785806848 3.4510040283 4.1779379845 6.2860856056 607 24.2400000000 0.3740348816 0.1145639738 0.8328990340 0.0557798724 2.2101170000 1.2679210000 0.2264430000 0.1593910000 0.5444070000 0.0081610000 109767066 0 1787711488 3.4440836906 4.1768860817 6.2772593498 608 24.2800000000 0.3737735152 0.1149903053 0.8328990340 0.0557347897 2.0775810000 1.2796780000 0.2281160000 0.0000050000 0.5578610000 0.0081750000 109768740 0 1784299520 3.4359514713 4.1761579514 6.2680096626 609 24.3200000000 0.3710605800 0.1154107820 0.8328990340 0.0556904456 2.9905830000 1.2734580000 0.4174010000 0.1604090000 0.5449600000 0.5907170000 109770414 0 1785806848 3.4278006554 4.1780953407 6.2575201988 610 24.3600000000 0.3862399161 0.1158547641 0.8328990340 0.0556571042 2.4184960000 1.3121580000 0.5247520000 0.0000050000 0.5697560000 0.0081660000 109772088 0 1787600896 3.4226405621 4.1539268494 6.2594904900 611 24.4000000000 0.3860293031 0.1162969483 0.8328990340 0.0556126357 2.3663180000 1.2734880000 0.3681050000 0.1618340000 0.5510030000 0.0082320000 109773762 0 1784537088 3.4178366661 4.1529188156 6.2506842613 612 24.4400000000 0.3785191774 0.1167254160 0.8328990340 0.0555710079 2.4198740000 1.2792690000 0.5620900000 0.0000060000 0.5666550000 0.0081820000 109775436 0 1786060800 3.4113838673 4.1503405571 6.2340645790 613 24.4800000000 0.3775855303 0.1171509627 0.8328990340 0.0555278556 2.9996690000 1.2732660000 0.4106110000 0.1628760000 0.5532420000 0.5959960000 109777110 0 1787965440 3.4042689800 4.1515536308 6.2245573997 614 24.5200000000 0.3866731226 0.1175899239 0.8328990340 0.0554854695 2.3254150000 1.2781380000 0.4608980000 0.0000040000 0.5744110000 0.0081870000 109778784 0 1784553472 3.3974847794 4.1442565918 6.2245230675 615 24.5600000000 0.3881745636 0.1180298989 0.8328990340 0.0554413656 2.5998130000 1.3062660000 0.5533930000 0.1645200000 0.5636230000 0.0082610000 109780458 0 1785933824 3.3918509483 4.1401948929 6.2163825035 616 24.6000000000 0.3885719180 0.1184690905 0.8328990340 0.0553977362 2.1909600000 1.2802880000 0.3202170000 0.0000050000 0.5784840000 0.0082400000 109782132 0 1787990016 3.3843705654 4.1388263702 6.2072234154 617 24.6400000000 0.3894893825 0.1189083454 0.8328990340 0.0553538396 3.1789790000 1.2707140000 0.5529410000 0.1658950000 0.5720260000 0.6136970000 109783806 0 1784307712 3.3772625923 4.1354351044 6.1981697083 618 24.6800000000 0.3905348778 0.1193478706 0.8328990340 0.0553100791 2.4254310000 1.2686470000 0.5576030000 0.0000050000 0.5872720000 0.0082420000 109785480 0 1785815040 3.3728826046 4.1337981224 6.1899614334 619 24.7200000000 0.3901545405 0.1197853611 0.8328990340 0.0552660357 2.5917710000 1.2716290000 0.5525190000 0.1667830000 0.5889180000 0.0082330000 109787154 0 1787600896 3.3695855141 4.1313090324 6.1811885834 620 24.7600000000 0.3936964273 0.1202271532 0.8328990340 0.0552262834 2.3010210000 1.3106800000 0.3687590000 0.0000050000 0.6095920000 0.0082550000 109788828 0 1784188928 3.3572053909 4.1263237000 6.1645102501 621 24.8000000000 0.3949571550 0.1206695525 0.8328990340 0.0551828449 3.0497170000 1.2705890000 0.3165720000 0.1687890000 0.6123440000 0.6776980000 109790502 0 1785679872 3.3526999950 4.1231212616 6.1568942070 622 24.8400000000 0.3940266967 0.1211090335 0.8328990340 0.0551393401 2.4651570000 1.2725270000 0.5544340000 0.0000050000 0.6261540000 0.0082100000 109792176 0 1787584512 3.3458244801 4.1190223694 6.1454057693 623 24.8800000000 0.3955918252 0.1215496158 0.8328990340 0.0550955663 2.5032840000 1.2753760000 0.4097400000 0.1694070000 0.6366950000 0.0081980000 109793850 0 1784553472 3.3404667377 4.1158747673 6.1372308731 624 24.9200000000 0.3962415457 0.1219898272 0.8328990340 0.0550515971 2.2892520000 1.2729980000 0.3674720000 0.0000040000 0.6367700000 0.0081880000 109795524 0 1785933824 3.3348708153 4.1118922234 6.1276435852 625 24.9600000000 0.3977743089 0.1224310824 0.8328990340 0.0550077723 3.1636290000 1.2724290000 0.3694250000 0.1700660000 0.6399840000 0.7079380000 109797198 0 1787838464 3.3292453289 4.1097278595 6.1182961464 626 25.0000000000 0.3978582025 0.1228710618 0.8328990340 0.0549640302 2.3525380000 1.2818380000 0.4188850000 0.0000050000 0.6397810000 0.0082820000 109798872 0 1784537088 3.3222749233 4.1069331169 6.1070089340 627 25.0400000000 0.3996339738 0.1233124700 0.8328990340 0.0549209363 2.5585870000 1.2718930000 0.4617240000 0.1756580000 0.6372400000 0.0081990000 109800546 0 1786060800 3.3171539307 4.1033906937 6.0980687141 628 25.0800000000 0.4006030262 0.1237540155 0.8328990340 0.0548775848 2.4932930000 1.2806610000 0.5581320000 0.0000050000 0.6425190000 0.0082010000 109802220 0 1787711488 3.3118512630 4.0992479324 6.0882892609 629 25.1200000000 0.4031385183 0.1241981880 0.8328990340 0.0548343227 3.3851200000 1.3029250000 0.5630920000 0.1698560000 0.6362260000 0.7091510000 109803894 0 1784578048 3.3048257828 4.0962529182 6.0774679184 630 25.1600000000 0.4025825262 0.1246400679 0.8328990340 0.0547913351 2.2850120000 1.2688290000 0.3661580000 0.0000040000 0.6380270000 0.0081990000 109805568 0 1785942016 3.3006033897 4.0934414864 6.0661234856 631 25.2000000000 0.4034981728 0.1250819983 0.8328990340 0.0547478965 2.5800230000 1.3036120000 0.4640410000 0.1694110000 0.6308300000 0.0082370000 109807242 0 1787711488 3.2973268032 4.0903887749 6.0562705994 632 25.2400000000 0.4044349790 0.1255240125 0.8328990340 0.0547045611 2.3695900000 1.2710370000 0.4614150000 0.0000050000 0.6249490000 0.0082210000 109808916 0 1784545280 3.2904353142 4.0867958069 6.0435295105 633 25.2800000000 0.4055230021 0.1259663490 0.8328990340 0.0546618369 3.1299860000 1.2794240000 0.3652040000 0.1686470000 0.6212010000 0.6916690000 109810590 0 1785933824 3.2841694355 4.0820655823 6.0314249992 634 25.3200000000 0.4063689411 0.1264086244 0.8328990340 0.0546190999 2.4537450000 1.2703540000 0.5542770000 0.0000050000 0.6170990000 0.0081980000 109812264 0 1787711488 3.2811625004 4.0789704323 6.0215497017 635 25.3600000000 0.4066593945 0.1268499642 0.8328990340 0.0545767286 2.4412250000 1.2791630000 0.3683600000 0.1691160000 0.6123730000 0.0083470000 109813938 0 1784426496 3.2804067135 4.0762553215 6.0126461983 636 25.4000000000 0.4091110229 0.1272937709 0.8328990340 0.0545378238 2.2546700000 1.2706170000 0.3678110000 0.0000050000 0.6040920000 0.0082020000 109815612 0 1785806848 3.2710995674 4.0723457336 6.0000591278 637 25.4400000000 0.4104285538 0.1277382525 0.8328990340 0.0544949741 3.2627540000 1.2777640000 0.5550990000 0.1668470000 0.5972420000 0.6619310000 109817286 0 1787711488 3.2620465755 4.0693101883 5.9858398438 638 25.4800000000 0.4103492498 0.1281812164 0.8328990340 0.0544529938 2.2024200000 1.2722390000 0.3174460000 0.0000050000 0.6005430000 0.0083340000 109818960 0 1784410112 3.2619798183 4.0679421425 5.9756259918 639 25.5200000000 0.4121108949 0.1286255508 0.8328990340 0.0544103702 2.4533260000 1.3043750000 0.3674930000 0.1671600000 0.6022230000 0.0082020000 109820634 0 1785933824 3.2576017380 4.0649695396 5.9649105072 640 25.5600000000 0.4137461483 0.1290710517 0.8328990340 0.0543682022 2.2963680000 1.2706560000 0.4130090000 0.0000050000 0.6005430000 0.0082230000 109822308 0 1787711488 3.2535126209 4.0608229637 5.9529266357 641 25.6000000000 0.4146980941 0.1295166477 0.8328990340 0.0543258732 2.9898040000 1.2769400000 0.2713690000 0.1665120000 0.6020430000 0.6690500000 109823982 0 1784410112 3.2510361671 4.0580801964 5.9420557022 642 25.6400000000 0.4147323966 0.1299609090 0.8328990340 0.0542835054 2.2532440000 1.2714350000 0.3677500000 0.0000050000 0.6018320000 0.0082660000 109825656 0 1785806848 3.2478339672 4.0541853905 5.9291739464 643 25.6800000000 0.4172897339 0.1304077657 0.8328990340 0.0542412548 2.4236700000 1.2778540000 0.3677270000 0.1661610000 0.5998080000 0.0082530000 109827330 0 1787736064 3.2451982498 4.0496106148 5.9190497398 644 25.7200000000 0.4180894196 0.1308544763 0.8328990340 0.0541991978 2.2145660000 1.2763590000 0.3205370000 0.0000050000 0.6054460000 0.0083200000 109829004 0 1784942592 3.2416841984 4.0451474190 5.9076657295 645 25.7600000000 0.4190465510 0.1313012857 0.8328990340 0.0541572409 3.0421230000 1.2767330000 0.3213190000 0.1673790000 0.6038770000 0.6688920000 109830678 0 1786585088 3.2363853455 4.0419845581 5.8953876495 646 25.8000000000 0.4207414389 0.1317493355 0.8328990340 0.0541155638 2.2160420000 1.2759340000 0.3199740000 0.0000050000 0.6078770000 0.0083730000 109832352 0 1784553472 3.2334892750 4.0387091637 5.8841896057 647 25.8400000000 0.4220690429 0.1321980522 0.8328990340 0.0540738987 2.4616940000 1.3121200000 0.3655880000 0.1659970000 0.6057730000 0.0082860000 109834026 0 1786077184 3.2310256958 4.0364851952 5.8731188774 648 25.8800000000 0.4229538441 0.1326467494 0.8328990340 0.0540323102 2.2619700000 1.2700100000 0.3635610000 0.0000050000 0.6161730000 0.0082200000 109835700 0 1787854848 3.2305564880 4.0332636833 5.8643078804 649 25.9200000000 0.4249803126 0.1330971864 0.8328990340 0.0539912790 3.0586370000 1.2794630000 0.3183420000 0.1663880000 0.6119160000 0.6785920000 109837374 0 1785077760 3.2262592316 4.0286731720 5.8533091545 650 25.9600000000 0.4268918633 0.1335491782 0.8328990340 0.0539501862 2.3660640000 1.2715890000 0.4567050000 0.0000050000 0.6256330000 0.0082150000 109839048 0 1786712064 3.2222125530 4.0242662430 5.8422970772 651 26.0000000000 0.4288004339 0.1340027131 0.8328990340 0.0539092916 2.4903710000 1.2792400000 0.4090500000 0.1668460000 0.6229980000 0.0083010000 109840722 0 1785569280 3.2198762894 4.0196499825 5.8332824707 652 26.0400000000 0.4294174016 0.1344558031 0.8328990340 0.0538686818 2.2846960000 1.2738520000 0.3649760000 0.0000050000 0.6336130000 0.0082030000 109842396 0 1787203584 3.2177543640 4.0157618523 5.8218464851 653 26.0800000000 0.4311812818 0.1349102066 0.8328990340 0.0538280174 3.1429200000 1.2784180000 0.3635730000 0.1671100000 0.6319620000 0.6979150000 109844070 0 1784680448 3.2132239342 4.0104312897 5.8106179237 654 26.1200000000 0.4325998724 0.1353653896 0.8328990340 0.0537875493 2.2960970000 1.2684760000 0.3637160000 0.0000060000 0.6516950000 0.0082590000 109845744 0 1786060800 3.2099990845 4.0059008598 5.8006529808 655 26.1600000000 0.4342666566 0.1358217274 0.8328990340 0.0537470278 2.5564410000 1.2775830000 0.4561230000 0.1675120000 0.6430090000 0.0082860000 109847418 0 1787981824 3.2067141533 4.0004901886 5.7907037735 656 26.2000000000 0.4360090196 0.1362793300 0.8328990340 0.0537069490 2.4048350000 1.2747610000 0.4600950000 0.0000060000 0.6576750000 0.0082670000 109849092 0 1785188352 3.2024629116 3.9955828190 5.7802505493 657 26.2400000000 0.4385209680 0.1367393629 0.8328990340 0.0536663099 3.3559590000 1.2710300000 0.5532910000 0.1680820000 0.6467370000 0.7128430000 109850766 0 1786720256 3.1971449852 3.9894478321 5.7699866295 658 26.2800000000 0.4394993782 0.1371994845 0.8328990340 0.0536258503 2.4969900000 1.2691260000 0.5593740000 0.0000050000 0.6562270000 0.0082750000 109852440 0 1784705024 3.1948711872 3.9852364063 5.7607283592 659 26.3200000000 0.4412473440 0.1376608622 0.8328990340 0.0535855636 2.6604010000 1.2720600000 0.5551370000 0.1676370000 0.6533300000 0.0082630000 109854114 0 1786204160 3.1906440258 3.9809679985 5.7500028610 660 26.3600000000 0.4425122738 0.1381227582 0.8328990340 0.0535453097 2.5316510000 1.3014340000 0.5542610000 0.0000060000 0.6636120000 0.0082200000 109855788 0 1785569280 3.1876060963 3.9767923355 5.7395229340 661 26.4000000000 0.4444634914 0.1385862087 0.8328990340 0.0535052925 3.2380750000 1.2778240000 0.4131440000 0.1678380000 0.6560070000 0.7192450000 109857462 0 1786966016 3.1835453510 3.9721891880 5.7287921906 662 26.4400000000 0.4462856650 0.1390510115 0.8328990340 0.0534655268 2.2277970000 1.2775550000 0.2742400000 0.0000050000 0.6637200000 0.0082580000 109859136 0 1784696832 3.1782875061 3.9677643776 5.7172241211 663 26.4800000000 0.4480391145 0.1395170569 0.8328990340 0.0534254830 2.6788790000 1.2702980000 0.5616480000 0.1680450000 0.6662790000 0.0084890000 109860810 0 1786331136 3.1731376648 3.9640109539 5.7045164108 664 26.5200000000 0.4495675564 0.1399840004 0.8328990340 0.0533858703 2.5167660000 1.2769910000 0.5546880000 0.0000050000 0.6728620000 0.0082180000 109862484 0 1785442304 3.1689829826 3.9596285820 5.6931686401 665 26.5600000000 0.4525933564 0.1404540897 0.8328990340 0.0533494250 3.4136010000 1.2720770000 0.5600380000 0.1675150000 0.6718430000 0.7380870000 109864158 0 1787203584 3.1607615948 3.9531664848 5.6695203781 666 26.6000000000 0.4544214904 0.1409255122 0.8328990340 0.0533096633 2.5225200000 1.2731870000 0.5567270000 0.0000050000 0.6802670000 0.0083090000 109865832 0 1784553472 3.1557509899 3.9501516819 5.6560878754 667 26.6400000000 0.4553802013 0.1413969585 0.8328990340 0.0532699765 2.4651290000 1.2716430000 0.3181090000 0.1793480000 0.6837440000 0.0082130000 109867506 0 1785933824 3.1523177624 3.9477679729 5.6441831589 668 26.6800000000 0.4577129185 0.1418704854 0.8328990340 0.0532303617 2.5277430000 1.2764260000 0.5576870000 0.0000060000 0.6813190000 0.0082050000 109869180 0 1787965440 3.1469972134 3.9437355995 5.6313176155 669 26.7200000000 0.4588561654 0.1423443055 0.8328990340 0.0531911724 3.4509160000 1.2940980000 0.5542160000 0.1682970000 0.6866760000 0.7435640000 109870854 0 1784823808 3.1437890530 3.9415097237 5.6190567017 670 26.7600000000 0.4599904120 0.1428184042 0.8328990340 0.0531519194 2.2947890000 1.2697100000 0.3194760000 0.0000060000 0.6931130000 0.0082060000 109872528 0 1786322944 3.1407036781 3.9401631355 5.6064119339 671 26.8000000000 0.4617922604 0.1432937751 0.8328990340 0.0531126753 2.7009440000 1.2713910000 0.5579870000 0.1692030000 0.6899930000 0.0082930000 109874202 0 1785688064 3.1352407932 3.9360084534 5.5938539505 672 26.8400000000 0.4634571075 0.1437702086 0.8328990340 0.0530741531 2.5364800000 1.2708600000 0.5521100000 0.0000050000 0.7012170000 0.0082320000 109875876 0 1787092992 3.1301803589 3.9315006733 5.5817861557 673 26.8800000000 0.4652721584 0.1442479232 0.8328990340 0.0530355587 3.4503290000 1.2964590000 0.5059660000 0.1692030000 0.7029670000 0.7716560000 109877550 0 1784934400 3.1264491081 3.9268958569 5.5697135925 674 26.9200000000 0.4670832157 0.1447269073 0.8328990340 0.0529965137 2.5474840000 1.2702420000 0.5516590000 0.0000060000 0.7132360000 0.0082480000 109879224 0 1786331136 3.1255469322 3.9227018356 5.5588302612 675 26.9600000000 0.4689523578 0.1452072413 0.8328990340 0.0529582794 2.5820800000 1.2726880000 0.4097660000 0.1699260000 0.7174880000 0.0081380000 109880898 0 1785569280 3.1240746975 3.9180068970 5.5475163460 676 27.0000000000 0.4707514346 0.1456888156 0.8328990340 0.0529212154 2.5746890000 1.2739130000 0.5503520000 0.0000060000 0.7382110000 0.0081760000 109882572 0 1787203584 3.1204640865 3.9141426086 5.5349378586 677 27.0400000000 0.4723563790 0.1461713378 0.8328990340 0.0528835991 3.4560080000 1.2709740000 0.4567600000 0.1707490000 0.7378110000 0.8155290000 109884246 0 1784680448 3.1168134212 3.9106431007 5.5230083466 678 27.0800000000 0.4737275243 0.1466544591 0.8328990340 0.0528460922 2.5927420000 1.2711590000 0.5531670000 0.0000060000 0.7561350000 0.0080730000 109885920 0 1786060800 3.1138451099 3.9081149101 5.5127515793 679 27.1200000000 0.4752707183 0.1471384300 0.8328990340 0.0528085539 2.7093240000 1.2677980000 0.4991420000 0.1718270000 0.7582700000 0.0080750000 109887594 0 1787965440 3.1109809875 3.9044773579 5.5023255348 680 27.1600000000 0.4764120579 0.1476226559 0.8328990340 0.0527707629 2.6059240000 1.2774910000 0.5449870000 0.0000060000 0.7712930000 0.0080540000 109889268 0 1784664064 3.1082136631 3.9019696712 5.4931893349 681 27.2000000000 0.4777430892 0.1481074143 0.8328990340 0.0527332780 3.5098170000 1.2959520000 0.4041780000 0.1724370000 0.7704950000 0.8626430000 109890942 0 1786060800 3.1053011417 3.8993139267 5.4831094742 682 27.2400000000 0.4792829752 0.1485930089 0.8328990340 0.0526957123 2.2851810000 1.2678920000 0.2223440000 0.0000060000 0.7826970000 0.0080600000 109892616 0 1787863040 3.1014623642 3.8965597153 5.4717350006 683 27.2800000000 0.4808562994 0.1490794852 0.8328990340 0.0526574383 2.7777330000 1.2673260000 0.5429130000 0.1725070000 0.7826710000 0.0081420000 109894290 0 1784561664 3.0963356495 3.8938925266 5.4601330757 684 27.3200000000 0.4821747243 0.1495664665 0.8328990340 0.0526200555 2.6115980000 1.2692970000 0.5425850000 0.0000060000 0.7874780000 0.0081170000 109895964 0 1786068992 3.0954823494 3.8899028301 5.4513754845 685 27.3600000000 0.4835323989 0.1500540080 0.8328990340 0.0525828678 3.6938710000 1.3042130000 0.5437840000 0.1726130000 0.7928490000 0.8762430000 109897638 0 1787965440 3.0952789783 3.8874552250 5.4421472549 686 27.4000000000 0.4848700464 0.1505420781 0.8328990340 0.0525467564 2.6188700000 1.2692820000 0.5466990000 0.0000060000 0.7906900000 0.0080550000 109899312 0 1784791040 3.0893294811 3.8840866089 5.4290204048 687 27.4400000000 0.4866150916 0.1510312673 0.8328990340 0.0525091089 2.7877400000 1.2737810000 0.5429470000 0.1731140000 0.7857570000 0.0080470000 109900986 0 1786314752 3.0854763985 3.8798470497 5.4185085297 688 27.4800000000 0.4880284667 0.1515210888 0.8328990340 0.0524714618 2.6228280000 1.2695670000 0.5483620000 0.0000060000 0.7926940000 0.0080790000 109902660 0 1788092416 3.0831043720 3.8776955605 5.4094052315 689 27.5200000000 0.4897995591 0.1520120590 0.8328990340 0.0524335641 3.7223730000 1.3057340000 0.5594560000 0.1726820000 0.7958010000 0.8845380000 109904334 0 1784664064 3.0777153969 3.8742749691 5.3966150284 690 27.5600000000 0.4909306467 0.1525032454 0.8328990340 0.0523961108 2.6336020000 1.2716520000 0.5464370000 0.0000060000 0.8034000000 0.0078730000 109906008 0 1786060800 3.0769579411 3.8718571663 5.3862457275 691 27.6000000000 0.4922783375 0.1529949604 0.8328990340 0.0523583190 2.5699660000 1.2738650000 0.3118850000 0.1726010000 0.7995420000 0.0079280000 109907682 0 1788092416 3.0749917030 3.8687014580 5.3758683205 692 27.6400000000 0.4941728711 0.1534879921 0.8328990340 0.0523205389 2.6261790000 1.2726370000 0.5403360000 0.0000050000 0.8011650000 0.0078540000 109909356 0 1784807424 3.0727307796 3.8640835285 5.3643021584 693 27.6800000000 0.4954767525 0.1539814824 0.8328990340 0.0522828104 3.6667490000 1.2694990000 0.5285770000 0.1724300000 0.7979220000 0.8941280000 109911030 0 1786314752 3.0702569485 3.8609459400 5.3522248268 694 27.7200000000 0.4971090257 0.1544759025 0.8328990340 0.0522452746 2.4353590000 1.2763110000 0.3472890000 0.0000060000 0.7998020000 0.0077510000 109912704 0 1785696256 3.0685365200 3.8567876816 5.3408021927 695 27.7600000000 0.4993099272 0.1549720665 0.8328990340 0.0522083482 2.6378200000 1.2700140000 0.3890380000 0.1713670000 0.7954620000 0.0076610000 109914378 0 1787228160 3.0660948753 3.8509476185 5.3293552399 696 27.8000000000 0.5009574890 0.1554691720 0.8328990340 0.0521710442 2.5970740000 1.2741330000 0.5170870000 0.0000050000 0.7939660000 0.0076640000 109916052 0 1784815616 3.0637991428 3.8467063904 5.3170852661 697 27.8400000000 0.5051544905 0.1559708726 0.8328990340 0.0521357184 3.6701890000 1.2992920000 0.5282100000 0.1700760000 0.7913900000 0.8770060000 109917726 0 1786331136 3.0593268871 3.8343927860 5.2928905487 698 27.8800000000 0.5071214437 0.1564739537 0.8328990340 0.0520984193 2.4022620000 1.2656240000 0.3381760000 0.0000060000 0.7866910000 0.0075390000 109919400 0 1785679872 3.0592293739 3.8288073540 5.2831802368 699 27.9200000000 0.5087493658 0.1569779242 0.8328990340 0.0520650007 2.7523630000 1.2681110000 0.5254120000 0.1695120000 0.7775370000 0.0074690000 109921074 0 1787203584 3.0563676357 3.8275873661 5.2684769630 700 27.9600000000 0.5105336308 0.1574830038 0.8328990340 0.0520280491 2.3956630000 1.2687180000 0.3408470000 0.0000050000 0.7744000000 0.0074740000 109922748 0 1784807424 3.0554606915 3.8252582550 5.2534728050 701 28.0000000000 0.5124061108 0.1579893135 0.8328990340 0.0519923307 3.4615660000 1.2972660000 0.3368520000 0.1687060000 0.7825640000 0.8717790000 109924422 0 1786441728 3.0571897030 3.8215689659 5.2419462204 702 28.0400000000 0.5137580037 0.1584961065 0.8328990340 0.0519554398 2.5760210000 1.2664400000 0.5162990000 0.0000060000 0.7815460000 0.0074930000 109926096 0 1785696256 3.0569984913 3.8197913170 5.2288761139 703 28.0800000000 0.5162518024 0.1590050051 0.8328990340 0.0519187598 2.6135450000 1.2740530000 0.3831780000 0.1670780000 0.7774020000 0.0074700000 109927770 0 1787203584 3.0536291599 3.8146326542 5.2147278786 704 28.1200000000 0.5183731318 0.1595154712 0.8328990340 0.0518840136 2.3578710000 1.2718890000 0.2935340000 0.0000060000 0.7806730000 0.0075230000 109929444 0 1784918016 3.0541598797 3.8086552620 5.2028908730 705 28.1600000000 0.5206708312 0.1600277483 0.8328990340 0.0518474678 3.5180550000 1.2752710000 0.4275070000 0.1666490000 0.7785150000 0.8657890000 109931118 0 1786712064 3.0538380146 3.8020398617 5.1902961731 706 28.2000000000 0.5230683088 0.1605419700 0.8328990340 0.0518107414 2.5860940000 1.2725510000 0.5205740000 0.0000060000 0.7810560000 0.0075270000 109932792 0 1785442304 3.0531582832 3.7951865196 5.1778678894 707 28.2400000000 0.5251758099 0.1610577180 0.8328990340 0.0517751690 2.7403170000 1.2671320000 0.5195920000 0.1658840000 0.7758930000 0.0075700000 109934466 0 1787084800 3.0531313419 3.7921268940 5.1636199951 708 28.2800000000 0.5267279148 0.1615742014 0.8328990340 0.0517391290 2.6062060000 1.2920430000 0.5246130000 0.0000050000 0.7776950000 0.0074450000 109936140 0 1784705024 3.0499835014 3.7906827927 5.1478400230 709 28.3200000000 0.5291897058 0.1620927000 0.8328990340 0.0517050268 3.5062910000 1.2711200000 0.4253980000 0.1650930000 0.7785380000 0.8618590000 109937814 0 1786212352 3.0495092869 3.7847683430 5.1350045204 710 28.3600000000 0.5308063626 0.1626120150 0.8328990340 0.0516690129 2.5841020000 1.2755150000 0.5112310000 0.0000050000 0.7855060000 0.0075610000 109939488 0 1785425920 3.0523755550 3.7815554142 5.1254334450 711 28.4000000000 0.5327434540 0.1631325937 0.8328990340 0.0516327437 2.7476120000 1.2663450000 0.5160360000 0.1648360000 0.7886760000 0.0074420000 109941162 0 1786822656 3.0510358810 3.7778596878 5.1131005287 712 28.4400000000 0.5346099138 0.1636543315 0.8328990340 0.0515965981 2.5779860000 1.2683510000 0.5117910000 0.0000050000 0.7860700000 0.0074530000 109942836 0 1784680448 3.0507326126 3.7732572556 5.1021733284 713 28.4800000000 0.5364603996 0.1641772011 0.8328990340 0.0515603969 3.6124220000 1.2714520000 0.5116020000 0.1641970000 0.7920290000 0.8687560000 109944510 0 1786204160 3.0524277687 3.7681474686 5.0928936005 714 28.5200000000 0.5380534530 0.1647008373 0.8328990340 0.0515258469 2.5850120000 1.2697740000 0.5142050000 0.0000060000 0.7891760000 0.0075420000 109946184 0 1785425920 3.0515999794 3.7653720379 5.0817193985 715 28.5600000000 0.5397244692 0.1652253459 0.8328990340 0.0514912320 2.5850440000 1.2740080000 0.3489610000 0.1635940000 0.7866530000 0.0074400000 109947858 0 1787092992 3.0496954918 3.7643895149 5.0664677620 716 28.6000000000 0.5415384769 0.1657509229 0.8328990340 0.0514556206 2.6271990000 1.3087940000 0.5136910000 0.0000050000 0.7928160000 0.0074290000 109949532 0 1784823808 3.0495057106 3.7613000870 5.0540356636 717 28.6400000000 0.5432445407 0.1662774133 0.8328990340 0.0514215352 3.5844710000 1.2751630000 0.4656830000 0.1635930000 0.7962050000 0.8794680000 109951206 0 1786331136 3.0509445667 3.7556443214 5.0466971397 718 28.6800000000 0.5445377231 0.1668042383 0.8328990340 0.0513864082 2.6029560000 1.2712800000 0.5106470000 0.0000060000 0.8090940000 0.0075870000 109952880 0 1785593856 3.0502655506 3.7530672550 5.0381226540 719 28.7200000000 0.5464654565 0.1673322789 0.8328990340 0.0513512461 2.5870170000 1.2691900000 0.3411340000 0.1633150000 0.8011780000 0.0074280000 109954554 0 1787084800 3.0473663807 3.7496461868 5.0258183479 720 28.7600000000 0.5482665896 0.1678613543 0.8328990340 0.0513159054 2.6288920000 1.2929740000 0.5096120000 0.0000060000 0.8143320000 0.0076020000 109956228 0 1784807424 3.0456457138 3.7463064194 5.0150203705 721 28.8000000000 0.5495715737 0.1683907721 0.8328990340 0.0512810221 3.6583270000 1.2696110000 0.5113010000 0.1634340000 0.8123580000 0.8972810000 109957902 0 1786314752 3.0465333462 3.7454507351 5.0040426254 722 28.8400000000 0.5510805845 0.1689208134 0.8328990340 0.0512470901 2.6179760000 1.2740900000 0.5123930000 0.0000060000 0.8196820000 0.0074500000 109959576 0 1785696256 3.0406854153 3.7449440956 4.9910721779 723 28.8800000000 0.5527452826 0.1694516909 0.8328990340 0.0512124905 2.6837720000 1.2714550000 0.4194950000 0.1633660000 0.8176730000 0.0074170000 109961250 0 1787203584 3.0348877907 3.7424197197 4.9799594879 724 28.9200000000 0.5541245937 0.1699830071 0.8328990340 0.0511777879 2.6492100000 1.3122480000 0.4982090000 0.0000050000 0.8268550000 0.0074200000 109962924 0 1784553472 3.0318243504 3.7407004833 4.9709248543 725 28.9600000000 0.5556435585 0.1705149527 0.8328990340 0.0511427456 3.4275140000 1.2705050000 0.2485820000 0.1633640000 0.8242520000 0.9164270000 109964598 0 1786060800 3.0270688534 3.7390239239 4.9591550827 726 29.0000000000 0.5577678680 0.1710483589 0.8328990340 0.0511093927 2.3591960000 1.2687400000 0.2474850000 0.0000060000 0.8312080000 0.0074120000 109966272 0 1787965440 3.0243084431 3.7342777252 4.9463748932 727 29.0400000000 0.5611097813 0.1715848946 0.8328990340 0.0510756737 2.8083230000 1.2689910000 0.5036670000 0.1692650000 0.8547070000 0.0072530000 109967946 0 1784934400 3.0138370991 3.7289109230 4.9269280434 728 29.0800000000 0.5633948445 0.1721230951 0.8328990340 0.0510418487 2.7047300000 1.2937600000 0.4935250000 0.0000060000 0.9057640000 0.0072050000 109969620 0 1786314752 3.0029580593 3.7252447605 4.9129910469 729 29.1200000000 0.5651665926 0.1726622494 0.8328990340 0.0510174014 3.8461190000 1.2701540000 0.4861510000 0.1642080000 0.9169200000 1.0041570000 109971294 0 1785831424 2.9996948242 3.7182095051 4.9066648483 730 29.1600000000 0.5665142536 0.1732017727 0.8328990340 0.0509828798 2.6963370000 1.2661970000 0.4877170000 0.0000050000 0.9308530000 0.0070660000 109972968 0 1787338752 2.9968848228 3.7161397934 4.8977565765 731 29.2000000000 0.5681655407 0.1737420788 0.8328990340 0.0509480988 2.8884310000 1.2682850000 0.4940710000 0.1625620000 0.9519820000 0.0070210000 109974642 0 1784299520 2.9883201122 3.7159934044 4.8831558228 732 29.2400000000 0.5696546435 0.1742829429 0.8328990340 0.0509156535 2.7379350000 1.2711060000 0.4816820000 0.0000050000 0.9736040000 0.0069760000 109976316 0 1785806848 2.9826090336 3.7148590088 4.8719325066 733 29.2800000000 0.5710489154 0.1748242335 0.8328990340 0.0508818906 3.9591860000 1.2696040000 0.4831280000 0.1622430000 0.9774380000 1.0622920000 109977990 0 1787584512 2.9790718555 3.7152078152 4.8613657951 734 29.3200000000 0.5718215108 0.1753651017 0.8328990340 0.0508474246 2.7798810000 1.2759900000 0.4891050000 0.0000060000 1.0034020000 0.0069540000 109979664 0 1784537088 2.9709260464 3.7172842026 4.8478422165 735 29.3600000000 0.5736740232 0.1759070186 0.8328990340 0.0508217507 2.8990720000 1.2673620000 0.4261410000 0.1619480000 1.0322080000 0.0069120000 109981338 0 1786060800 2.9657764435 3.7132523060 4.8388051987 736 29.4000000000 0.5750566125 0.1764493414 0.8328990340 0.0507897780 2.8045130000 1.2681110000 0.4694720000 0.0000050000 1.0553810000 0.0069250000 109983012 0 1787854848 2.9631147385 3.7121844292 4.8307065964 737 29.4400000000 0.5759961009 0.1769914673 0.8328990340 0.0507553165 4.0531970000 1.2706950000 0.3706150000 0.1614820000 1.0816420000 1.1643060000 109984686 0 1784807424 2.9578576088 3.7147130966 4.8173170090 738 29.4800000000 0.5774380565 0.1775340778 0.8328990340 0.0507266348 2.8690220000 1.2701980000 0.4697010000 0.0000050000 1.1177540000 0.0068790000 109986360 0 1786441728 2.9528980255 3.7135453224 4.8065729141 739 29.5200000000 0.5783166289 0.1780764088 0.8328990340 0.0506987293 2.9920030000 1.2701300000 0.4514120000 0.1610460000 1.0980670000 0.0067950000 109988034 0 1785679872 2.9523448944 3.7108461857 4.8014369011 740 29.5600000000 0.5797227621 0.1786191741 0.8328990340 0.0506649694 2.8957790000 1.2690270000 0.4637730000 0.0000050000 1.1517720000 0.0067430000 109989708 0 1787203584 2.9500215054 3.7085037231 4.7927551270 741 29.6000000000 0.5809612274 0.1791621458 0.8328990340 0.0506310043 4.2319540000 1.2698410000 0.3842300000 0.1609210000 1.1572690000 1.2551930000 109991382 0 1784307712 2.9475617409 3.7069571018 4.7818465233 742 29.6400000000 0.5827630162 0.1797060823 0.8328990340 0.0505970985 2.9324040000 1.2697460000 0.4623070000 0.0000060000 1.1891630000 0.0067120000 109993056 0 1785806848 2.9454627037 3.7056951523 4.7719039917 743 29.6800000000 0.5836244226 0.1802497140 0.8328990340 0.0505634920 2.9280480000 1.2707660000 0.2723320000 0.1665690000 1.2071310000 0.0067490000 109994730 0 1787600896 2.9417724609 3.7059366703 4.7624950409 744 29.7200000000 0.5848158598 0.1807934857 0.8328990340 0.0505301857 3.0020730000 1.2694120000 0.4615410000 0.0000060000 1.2598420000 0.0066990000 109996404 0 1784664064 2.9357821941 3.7060019970 4.7534031868 745 29.7600000000 0.5852954388 0.1813364414 0.8328990340 0.0504997669 4.4200920000 1.2757740000 0.3007070000 0.1610210000 1.2742400000 1.4038040000 109998078 0 1786077184 2.9324870110 3.7056369781 4.7475237846 746 29.8000000000 0.5864884257 0.1818795405 0.8328990340 0.0504683220 3.0325580000 1.2743000000 0.4546080000 0.0000060000 1.2924700000 0.0066810000 109999752 0 1787838464 2.9277198315 3.7048902512 4.7392649651 747 29.8400000000 0.5869097710 0.1824217497 0.8328990340 0.0504423234 3.1697110000 1.2724690000 0.4406750000 0.1606750000 1.2845490000 0.0066870000 110001426 0 1784553472 2.9322173595 3.7028954029 4.7341508865 748 29.8800000000 0.5874219537 0.1829631938 0.8328990340 0.0504096079 2.7831180000 1.2710610000 0.2198940000 0.0000050000 1.2808880000 0.0067270000 110003100 0 1785933824 2.9343109131 3.6993744373 4.7315621376 749 29.9200000000 0.5889332891 0.1835052099 0.8328990340 0.0503769741 4.5885290000 1.2694230000 0.4544960000 0.1612330000 1.2901100000 1.4087560000 110004774 0 1787838464 2.9303872585 3.6977438927 4.7238807678 750 29.9600000000 0.5897066593 0.1840468119 0.8328990340 0.0503434999 3.0264230000 1.2672270000 0.4612240000 0.0000050000 1.2866520000 0.0066320000 110006448 0 1784553472 2.9269843102 3.6986522675 4.7130675316 751 30.0000000000 0.5909751058 0.1845886605 0.8328990340 0.0503123734 3.1671780000 1.2695730000 0.4405820000 0.1608780000 1.2849500000 0.0066270000 110008122 0 1786068992 2.9254834652 3.6959621906 4.7085886002 752 30.0400000000 0.5915095806 0.1851297787 0.8328990340 0.0502796320 3.0259660000 1.2705490000 0.4474880000 0.0000060000 1.2966590000 0.0066700000 110009796 0 1787846656 2.9229509830 3.6942589283 4.7049975395 753 30.0800000000 0.5925593972 0.1856708539 0.8328990340 0.0502462558 4.4989490000 1.2676080000 0.3095350000 0.1610500000 1.3058020000 1.4503350000 110011470 0 1784410112 2.9184238911 3.6956291199 4.6948542595 754 30.1200000000 0.5933521986 0.1862115453 0.8328990340 0.0502180056 2.9187240000 1.2668660000 0.3300850000 0.0000060000 1.3105330000 0.0066700000 110013144 0 1785933824 2.9194123745 3.6919910908 4.6905717850 755 30.1600000000 0.5938302875 0.1867514377 0.8328990340 0.0501861278 2.9961100000 1.2749600000 0.2543790000 0.1612250000 1.2942450000 0.0066320000 110014818 0 1787838464 2.9236655235 3.6889691353 4.6890997887 756 30.2000000000 0.5953118205 0.1872918615 0.8328990340 0.0501531645 3.0395050000 1.2688620000 0.4525750000 0.0000050000 1.3068260000 0.0066040000 110016492 0 1784426496 2.9215137959 3.6869521141 4.6819825172 757 30.2400000000 0.5963041186 0.1878321683 0.8328990340 0.0501203837 4.4075390000 1.2680070000 0.2231410000 0.1613390000 1.3057930000 1.4446900000 110018166 0 1785933824 2.9193871021 3.6848721504 4.6753931046 758 30.2800000000 0.5969624519 0.1883719180 0.8328990340 0.0500875119 3.0459890000 1.2732610000 0.4464770000 0.0000050000 1.3149900000 0.0066410000 110019840 0 1787965440 2.9169189930 3.6841669083 4.6685972214 759 30.3200000000 0.5978819132 0.1889114569 0.8328990340 0.0500546273 3.0297170000 1.2673190000 0.2666890000 0.1609440000 1.3235130000 0.0066170000 110021514 0 1785077760 2.9154677391 3.6850857735 4.6580991745 760 30.3600000000 0.5993119478 0.1894514575 0.8328990340 0.0500257119 3.0330630000 1.2695850000 0.4383670000 0.0000060000 1.3137730000 0.0066150000 110023188 0 1786585088 2.9188840389 3.6809301376 4.6533212662 761 30.4000000000 0.6001275182 0.1899911107 0.8328990340 0.0499937319 4.6434280000 1.2733100000 0.4392740000 0.1619380000 1.3108560000 1.4533840000 110024862 0 1785610240 2.9192264080 3.6787211895 4.6489396095 762 30.4400000000 0.6010865569 0.1905306060 0.8328990340 0.0499612276 2.9479220000 1.2690260000 0.3436910000 0.0000050000 1.3238320000 0.0067570000 110026536 0 1787084800 2.9159588814 3.6773436069 4.6413302422 763 30.4800000000 0.6022899151 0.1910702644 0.8328990340 0.0499309954 3.2053760000 1.2681980000 0.4436130000 0.1614940000 1.3207880000 0.0066700000 110028210 0 1784807424 2.9154949188 3.6735463142 4.6341972351 764 30.5200000000 0.6035199761 0.1916101200 0.8328990340 0.0498985111 3.0560810000 1.2734280000 0.4499090000 0.0000040000 1.3213920000 0.0067210000 110029884 0 1786568704 2.9166109562 3.6730110645 4.6271524429 765 30.5600000000 0.6046944857 0.1921500996 0.8328990340 0.0498665948 4.6673680000 1.2690210000 0.4473790000 0.1608560000 1.3221070000 1.4632330000 110031558 0 1785806848 2.9171977043 3.6704454422 4.6186480522 766 30.6000000000 0.6057895422 0.1926900989 0.8328990340 0.0498359790 3.0394800000 1.2689120000 0.4473530000 0.0000030000 1.3118260000 0.0066570000 110033232 0 1787473920 2.9221088886 3.6645321846 4.6162195206 767 30.6400000000 0.6070302725 0.1932303077 0.8328990340 0.0498036126 3.1994020000 1.2712840000 0.4557520000 0.1607720000 1.3001520000 0.0066950000 110034906 0 1784950784 2.9220347404 3.6629631519 4.6061229706 768 30.6800000000 0.6096259356 0.1937724895 0.8328990340 0.0497719085 3.0362290000 1.2691540000 0.4550050000 0.0000040000 1.3005630000 0.0066950000 110036580 0 1786695680 2.9226312637 3.6590194702 4.5978965759 769 30.7200000000 0.6102654338 0.1943140928 0.8328990340 0.0497419757 4.4779580000 1.2679630000 0.3369280000 0.1609730000 1.2804480000 1.4269450000 110038254 0 1785585664 2.9287998676 3.6529517174 4.5968265533 770 30.7600000000 0.6116503477 0.1948560879 0.8328990340 0.0497105909 3.0137580000 1.2699060000 0.4566730000 0.0000030000 1.2756170000 0.0068460000 110039928 0 1787076608 2.9299466610 3.6509451866 4.5894403458 771 30.8000000000 0.6138299704 0.1953995041 0.8328990340 0.0496785209 3.1734840000 1.2732670000 0.4585350000 0.1607430000 1.2693430000 0.0068490000 110041602 0 1784721408 2.9301712513 3.6468188763 4.5805425644 772 30.8400000000 0.6152427197 0.1959433425 0.8328990340 0.0496465140 2.9896250000 1.2678820000 0.4524670000 0.0000030000 1.2577320000 0.0068220000 110043276 0 1786195968 2.9364581108 3.6413257122 4.5757803917 773 30.8800000000 0.6163675189 0.1964872289 0.8328990340 0.0496158896 4.4912590000 1.2699750000 0.4554770000 0.1612870000 1.2302190000 1.3694640000 110044950 0 1785569280 2.9421737194 3.6383502483 4.5697960854 774 30.9200000000 0.6180763841 0.1970319177 0.8328990340 0.0495876331 2.7558170000 1.2776380000 0.2307260000 0.0000040000 1.2357690000 0.0068580000 110046624 0 1787092992 2.9406599998 3.6370456219 4.5605378151 775 30.9600000000 0.6192613244 0.1975767298 0.8328990340 0.0495567930 3.1407120000 1.2699370000 0.4588050000 0.1613820000 1.2389340000 0.0068490000 110048298 0 1785061376 2.9388263226 3.6352286339 4.5527887344 776 31.0000000000 0.6203275323 0.1981215118 0.8328990340 0.0495255443 2.7494290000 1.2696180000 0.2301570000 0.0000040000 1.2380030000 0.0069060000 110049972 0 1786712064 2.9374036789 3.6336266994 4.5460629463 777 31.0400000000 0.6212280393 0.1986660504 0.8328990340 0.0494940070 4.4825670000 1.2700460000 0.4676530000 0.1614390000 1.2226250000 1.3560130000 110051646 0 1784569856 2.9414877892 3.6316025257 4.5399541855 778 31.0800000000 0.6227871776 0.1992111933 0.8328990340 0.0494629637 2.7036700000 1.2710560000 0.1914460000 0.0000060000 1.2295500000 0.0068980000 110053320 0 1786331136 2.9406430721 3.6295399666 4.5325760841 779 31.1200000000 0.6234984398 0.1997558496 0.8328990340 0.0494333606 3.0521810000 1.2696960000 0.3934640000 0.1618970000 1.2154410000 0.0069840000 110054994 0 1787981824 2.9411058426 3.6311435699 4.5239100456 780 31.1600000000 0.6246939898 0.2003006421 0.8328990340 0.0494033702 2.8583160000 1.2726210000 0.3569430000 0.0000050000 1.2170790000 0.0069680000 110056668 0 1784918016 2.9413676262 3.6342790127 4.5139145851 781 31.2000000000 0.6251888275 0.2008446730 0.8328990340 0.0493719192 4.4391530000 1.2692460000 0.4676090000 0.1615110000 1.1909600000 1.3451450000 110058342 0 1786449920 2.9461984634 3.6337261200 4.5058307648 782 31.2400000000 0.6270228028 0.2013896578 0.8328990340 0.0493404519 2.9310910000 1.2733190000 0.4662160000 0.0000050000 1.1797600000 0.0070800000 110060016 0 1785307136 2.9508292675 3.6303184032 4.5001640320 783 31.2800000000 0.6273659468 0.2019336889 0.8328990340 0.0493094734 2.8285500000 1.2729380000 0.2326960000 0.1625440000 1.1483920000 0.0071030000 110061690 0 1786830848 2.9550771713 3.6295244694 4.4956140518 784 31.3200000000 0.6289904714 0.2024784042 0.8328990340 0.0492783515 2.8263860000 1.2682300000 0.3950870000 0.0000050000 1.1511830000 0.0071490000 110063364 0 1784553472 2.9561657906 3.6273822784 4.4868516922 785 31.3600000000 0.6298992038 0.2030228892 0.8328990340 0.0492476605 4.1334860000 1.2771280000 0.2732410000 0.1619270000 1.1414250000 1.2750110000 110065038 0 1786187776 2.9548079967 3.6247594357 4.4815540314 786 31.4000000000 0.6308794618 0.2035672360 0.8328990340 0.0492175893 2.8984860000 1.2711410000 0.4740150000 0.0000050000 1.1412680000 0.0072970000 110066712 0 1788092416 2.9587314129 3.6194622517 4.4785881042 787 31.4400000000 0.6316744685 0.2041112096 0.8328990340 0.0491867269 3.0480240000 1.2683310000 0.4723610000 0.1626590000 1.1325680000 0.0073230000 110068386 0 1784807424 2.9618532658 3.6161053181 4.4755301476 788 31.4800000000 0.6324397326 0.2046547738 0.8328990340 0.0491559712 2.7037500000 1.2713700000 0.2777410000 0.0000050000 1.1424310000 0.0074070000 110070060 0 1786441728 2.9644515514 3.6148030758 4.4704155922 789 31.5200000000 0.6332110763 0.2051979376 0.8328990340 0.0491252303 4.2610270000 1.2661710000 0.3991940000 0.1631020000 1.1477430000 1.2798830000 110071734 0 1785696256 2.9659376144 3.6136109829 4.4640393257 790 31.5600000000 0.6340966225 0.2057408474 0.8328990340 0.0490945593 2.6823530000 1.2678200000 0.2395310000 0.0000050000 1.1628120000 0.0074170000 110073408 0 1787076608 2.9675769806 3.6122646332 4.4609379768 791 31.6000000000 0.6350687742 0.2062836134 0.8328990340 0.0490643150 2.9750270000 1.2721050000 0.3639070000 0.1637100000 1.1629960000 0.0073870000 110075082 0 1784553472 2.9666287899 3.6125032902 4.4533333778 792 31.6400000000 0.6362342238 0.2068264803 0.8328990340 0.0490339585 2.9464770000 1.2678350000 0.4828390000 0.0000050000 1.1835480000 0.0073810000 110076756 0 1785933824 2.9661352634 3.6086726189 4.4489269257 793 31.6800000000 0.6365345716 0.2073683569 0.8328990340 0.0490031345 4.2704120000 1.2665070000 0.3207990000 0.1653830000 1.1828080000 1.3300850000 110078430 0 1787863040 2.9691410065 3.6057093143 4.4486556053 794 31.7200000000 0.6372542977 0.2079097749 0.8328990340 0.0489731476 2.9685660000 1.2722440000 0.4936520000 0.0000050000 1.1904480000 0.0074070000 110080104 0 1784418304 2.9669816494 3.6054828167 4.4401764870 795 31.7600000000 0.6387078762 0.2084516593 0.8328990340 0.0489427183 2.9249730000 1.2692300000 0.2811970000 0.1641200000 1.1981640000 0.0073380000 110081778 0 1785933824 2.9655995369 3.6030278206 4.4353942871 796 31.8000000000 0.6390383244 0.2089925973 0.8328990340 0.0489122228 2.8495740000 1.2648670000 0.3672950000 0.0000050000 1.2050720000 0.0074410000 110083452 0 1787711488 2.9684123993 3.6006338596 4.4330916405 797 31.8400000000 0.6398656368 0.2095332160 0.8328990340 0.0488816509 4.5089430000 1.2681830000 0.4989230000 0.1642670000 1.2098310000 1.3627640000 110085126 0 1784569856 2.9704430103 3.5993006229 4.4287428856 798 31.8800000000 0.6405031681 0.2100732786 0.8328990340 0.0488510824 2.9997840000 1.2676630000 0.4928220000 0.0000060000 1.2269110000 0.0074490000 110086800 0 1786060800 2.9696362019 3.5964593887 4.4261145592 799 31.9200000000 0.6412395239 0.2106129109 0.8328990340 0.0488226458 3.0435240000 1.2701060000 0.3759630000 0.1651280000 1.2199880000 0.0074030000 110088474 0 1787965440 2.9670312405 3.5999729633 4.4160742760 800 31.9600000000 0.6426898241 0.2111530071 0.8328990340 0.0487942487 2.8791140000 1.2722140000 0.3663910000 0.0000050000 1.2282800000 0.0073310000 110090148 0 1784680448 2.9647498131 3.5938982964 4.4121837616 801 32.0000000000 0.6434715390 0.2116927306 0.8328990340 0.0487670440 4.4166730000 1.2739040000 0.3310220000 0.1650540000 1.2373610000 1.4044840000 110091822 0 1786060800 2.9707889557 3.5838994980 4.4180417061 802 32.0400000000 0.6443102360 0.2122321539 0.8328990340 0.0487397316 2.9301660000 1.2676770000 0.4067510000 0.0000060000 1.2433880000 0.0073870000 110093496 0 1787965440 2.9704048634 3.5821399689 4.4136004448 803 32.0800000000 0.6456400752 0.2127718898 0.8328990340 0.0487113196 3.0236680000 1.2745560000 0.3281670000 0.1650990000 1.2435830000 0.0073710000 110095170 0 1784688640 2.9690685272 3.5815737247 4.4058375359 804 32.1199999990 0.6463236213 0.2133111332 0.8328990340 0.0486812430 2.8655220000 1.2677430000 0.3264240000 0.0000050000 1.2591320000 0.0073530000 110096844 0 1786068992 2.9690861702 3.5779755116 4.4035787582 805 32.1600000000 0.6477092505 0.2138507582 0.8328990340 0.0486514194 4.4316180000 1.2700740000 0.3221290000 0.1651810000 1.2527790000 1.4164020000 110098518 0 1787838464 2.9686872959 3.5730316639 4.4000244141 806 32.2000000000 0.6501061916 0.2143920181 0.8328990340 0.0486286184 2.8966190000 1.2746000000 0.3318590000 0.0000060000 1.2779070000 0.0073400000 110100192 0 1784537088 2.9737315178 3.5728123188 4.3824491501 807 32.2400000000 0.6509936452 0.2149330362 0.8328990340 0.0486004056 3.2140740000 1.2677150000 0.4836030000 0.1655360000 1.2849410000 0.0074160000 110101866 0 1786060800 2.9730682373 3.5728924274 4.3763751984 808 32.2800000000 0.6521005034 0.2154740850 0.8328990340 0.0485741569 3.0692790000 1.2730460000 0.4906490000 0.0000050000 1.2932170000 0.0073370000 110103540 0 1787854848 2.9713025093 3.5765464306 4.3657531738 809 32.3200000000 0.6533133388 0.2160152955 0.8328990340 0.0485452298 4.7032850000 1.2732950000 0.4810170000 0.1666930000 1.2992960000 1.4779070000 110105214 0 1784807424 2.9665329456 3.5743079185 4.3581900597 810 32.3600000000 0.6543925405 0.2165565020 0.8328990340 0.0485172665 2.8854670000 1.2656810000 0.2833780000 0.0000060000 1.3240200000 0.0073420000 110106888 0 1786314752 2.9660737514 3.5698246956 4.3559141159 811 32.4000000000 0.6561683416 0.2170985634 0.8328990340 0.0484892812 3.0979440000 1.2752020000 0.3217480000 0.1674290000 1.3211140000 0.0074440000 110108562 0 1785552896 2.9625489712 3.5622155666 4.3511171341 812 32.4399999990 0.6571155190 0.2176404562 0.8328990340 0.0484613599 2.9524630000 1.2732050000 0.3206460000 0.0000050000 1.3462860000 0.0073970000 110110236 0 1787076608 2.9655127525 3.5546891689 4.3526329994 813 32.4800000000 0.6579689980 0.2181820657 0.8328990340 0.0484436516 4.7089180000 1.2662210000 0.4115290000 0.1678810000 1.3399580000 1.5183570000 110111910 0 1784561664 2.9649794102 3.5623772144 4.3379707336 814 32.5200000000 0.6597150564 0.2187244896 0.8328990340 0.0484185278 2.9247010000 1.2653900000 0.2911190000 0.0000050000 1.3557980000 0.0073940000 110113584 0 1786195968 2.9585585594 3.5690996647 4.3186230659 815 32.5600000000 0.6608600616 0.2192669872 0.8328990340 0.0483973544 3.1528930000 1.2657660000 0.3614260000 0.1685670000 1.3446910000 0.0074650000 110115258 0 1787854848 2.9565351009 3.5600738525 4.3189425468 816 32.6000000000 0.6619750261 0.2198095216 0.8328990340 0.0483686231 3.1377240000 1.2694810000 0.4869100000 0.0000060000 1.3688450000 0.0074900000 110116932 0 1784807424 2.9554061890 3.5556244850 4.3150262833 817 32.6400000000 0.6633648872 0.2203524290 0.8328990340 0.0483401472 4.6256790000 1.2657900000 0.2784270000 0.1691980000 1.3569630000 1.5503540000 110118606 0 1786204160 2.9519283772 3.5540795326 4.3070626259 818 32.6800000000 0.6651595831 0.2208962030 0.8328990340 0.0483112445 3.0973590000 1.2685880000 0.4432330000 0.0000060000 1.3730200000 0.0074310000 110120280 0 1788092416 2.9470925331 3.5494451523 4.2996125221 819 32.7200000000 0.6666314006 0.2214404462 0.8328990340 0.0482831394 3.1875600000 1.2749960000 0.3628530000 0.1701300000 1.3671100000 0.0074390000 110121954 0 1784426496 2.9449949265 3.5420637131 4.2965378761 820 32.7599999990 0.6675851345 0.2219845251 0.8328990340 0.0482543712 2.9920510000 1.2674000000 0.3260770000 0.0000060000 1.3861570000 0.0074670000 110123628 0 1785933824 2.9453427792 3.5414774418 4.2899999619 821 32.7999999990 0.6691141129 0.2225291409 0.8328990340 0.0482257020 4.7069290000 1.2676520000 0.3257980000 0.1700070000 1.3732400000 1.5651700000 110125302 0 1787838464 2.9419016838 3.5404303074 4.2811927795 822 32.8400000000 0.6704013348 0.2230739976 0.8328990340 0.0481968356 3.0394200000 1.2680300000 0.3669890000 0.0000050000 1.3919550000 0.0074360000 110126976 0 1784410112 2.9389834404 3.5372538567 4.2749385834 823 32.8800000000 0.6715101004 0.2236188774 0.8328990340 0.0481682792 3.1648770000 1.2699430000 0.3221240000 0.1757060000 1.3845860000 0.0075250000 110128650 0 1786068992 2.9374401569 3.5365762711 4.2683753967 824 32.9200000000 0.6728166342 0.2241640204 0.8328990340 0.0481398132 3.0465730000 1.2688760000 0.3647300000 0.0000060000 1.4004780000 0.0075260000 110130324 0 1787846656 2.9331884384 3.5361437798 4.2584819794 825 32.9600000000 0.6740247607 0.2247093061 0.8328990340 0.0481129420 4.7856090000 1.2738140000 0.3604450000 0.1711390000 1.3962060000 1.5790170000 110131998 0 1784680448 2.9329955578 3.5296678543 4.2562379837 826 33.0000000000 0.6750013828 0.2252544539 0.8328990340 0.0480843807 3.1828910000 1.2723620000 0.4873070000 0.0000050000 1.4106480000 0.0075950000 110133672 0 1786060800 2.9348468781 3.5295562744 4.2505617142 827 33.0400000000 0.6767616868 0.2258004119 0.8328990340 0.0480558714 3.2270290000 1.2696200000 0.3645920000 0.1713640000 1.4089060000 0.0075540000 110135346 0 1788092416 2.9301147461 3.5256192684 4.2413039207 828 33.0800000000 0.6780766845 0.2263466392 0.8328990340 0.0480297717 3.0644000000 1.2678910000 0.3645510000 0.0000060000 1.4194410000 0.0074450000 110137020 0 1784680448 2.9308521748 3.5160117149 4.2422437668 829 33.1199999990 0.6789795756 0.2268926380 0.8328990340 0.0480042219 4.9092450000 1.2732310000 0.4425400000 0.1731500000 1.4167650000 1.5985300000 110138694 0 1786060800 2.9321546555 3.5163075924 4.2358813286 830 33.1600000000 0.6802646518 0.2274388693 0.8328990340 0.0479809879 2.9953530000 1.2659480000 0.2907530000 0.0000050000 1.4260930000 0.0074550000 110140368 0 1787973632 2.9240825176 3.5188548565 4.2219958305 831 33.2000000000 0.6815693974 0.2279853561 0.8328990340 0.0479533318 3.2331920000 1.2681040000 0.3580190000 0.1724840000 1.4219640000 0.0075140000 110142042 0 1784672256 2.9225020409 3.5141756535 4.2178292274 832 33.2400000000 0.6822418571 0.2285313375 0.8328990340 0.0479252766 3.0875660000 1.2730640000 0.3633320000 0.0000040000 1.4385230000 0.0074700000 110143716 0 1786060800 2.9262223244 3.5096194744 4.2173652649 833 33.2800000000 0.6836336851 0.2290776788 0.8328990340 0.0478981808 4.9016360000 1.2689890000 0.4018150000 0.1730190000 1.4394270000 1.6133100000 110145390 0 1787863040 2.9270107746 3.5075638294 4.2102022171 834 33.3200000000 0.6847887039 0.2296240949 0.8328990340 0.0478713464 3.1296900000 1.2676010000 0.3998800000 0.0000040000 1.4495370000 0.0074760000 110147064 0 1784197120 2.9235682487 3.5048267841 4.2030024529 835 33.3600000000 0.6864060163 0.2301711391 0.8328990340 0.0478441763 3.2898510000 1.2675810000 0.3969370000 0.1736210000 1.4390700000 0.0075320000 110148738 0 1785679872 2.9218637943 3.5027532578 4.1946549416 836 33.4000000000 0.6875213385 0.2307182087 0.8328990340 0.0478169497 3.1781100000 1.2729420000 0.4397360000 0.0000050000 1.4526810000 0.0075310000 110150412 0 1787600896 2.9214999676 3.5021407604 4.1866650581 837 33.4399999990 0.6886923313 0.2312653702 0.8328990340 0.0477890728 4.8445260000 1.2678010000 0.3166920000 0.1742350000 1.4540170000 1.6266260000 110152086 0 1784299520 2.9218008518 3.4993228912 4.1805372238 838 33.4800000000 0.6899480224 0.2318127242 0.8328990340 0.0477611163 3.1053630000 1.2692240000 0.3577270000 0.0000040000 1.4657860000 0.0075210000 110153760 0 1785806848 2.9228489399 3.4950346947 4.1750898361 839 33.5200000000 0.6917404532 0.2323609098 0.8328990340 0.0477337911 3.2690330000 1.2675940000 0.3645080000 0.1744100000 1.4497230000 0.0074490000 110155434 0 1787584512 2.9254438877 3.4938333035 4.1642847061 840 33.5600000000 0.6930040121 0.2329092944 0.8328990340 0.0477061389 3.1460000000 1.2703080000 0.4040060000 0.0000060000 1.4590540000 0.0075120000 110157108 0 1784553472 2.9322931767 3.4870467186 4.1611032486 841 33.6000000000 0.6944547296 0.2334581000 0.8328990340 0.0476783462 4.9265410000 1.2653810000 0.4016210000 0.1747300000 1.4538190000 1.6258910000 110158782 0 1785933824 2.9357798100 3.4826619625 4.1553368568 842 33.6400000000 0.6959983110 0.2340074351 0.8328990340 0.0476522809 3.1501760000 1.2753550000 0.4029600000 0.0000050000 1.4590670000 0.0074890000 110160456 0 1787854848 2.9368841648 3.4796462059 4.1468896866 843 33.6800000000 0.6988580227 0.2345588593 0.8328990340 0.0476287832 3.3064540000 1.2680180000 0.4036270000 0.1748110000 1.4473390000 0.0074840000 110162130 0 1784688640 2.9444141388 3.4730293751 4.1318526268 844 33.7200000000 0.7006621957 0.2351111144 0.8328990340 0.0476017395 3.1758700000 1.2660990000 0.4571420000 0.0000040000 1.4399670000 0.0075230000 110163804 0 1785942016 2.9464957714 3.4699370861 4.1225724220 845 33.7599999990 0.7020498514 0.2356637047 0.8328990340 0.0475761152 4.9732860000 1.2671700000 0.4939580000 0.1748340000 1.4261080000 1.6060740000 110165478 0 1787838464 2.9464757442 3.4700024128 4.1111736298 846 33.7999999990 0.7033561468 0.2362165326 0.8328990340 0.0475500017 3.2008420000 1.2658910000 0.4917180000 0.0000040000 1.4299130000 0.0075560000 110167152 0 1784537088 2.9470613003 3.4730918407 4.0989518166 847 33.8400000000 0.7048591971 0.2367698297 0.8328990340 0.0475222690 3.3654970000 1.2721170000 0.4871270000 0.1750410000 1.4184880000 0.0074560000 110168826 0 1786060800 2.9517238140 3.4724426270 4.0881910324 848 33.8800000000 0.7064636350 0.2373237139 0.8328990340 0.0474956035 3.1978430000 1.2680870000 0.4896650000 0.0000050000 1.4275160000 0.0074060000 110170500 0 1787838464 2.9604737759 3.4689455032 4.0810432434 849 33.9200000000 0.7081402540 0.2378782682 0.8328990340 0.0474679065 4.9458060000 1.2717560000 0.4901280000 0.1746700000 1.4145570000 1.5893430000 110172174 0 1784442880 2.9621994495 3.4634077549 4.0737614632 850 33.9600000000 0.7100431919 0.2384337563 0.8328990340 0.0474400071 3.1916770000 1.2667790000 0.4990690000 0.0000050000 1.4132240000 0.0073930000 110173848 0 1785806848 2.9695980549 3.4588186741 4.0653891563 851 34.0000000000 0.7114451528 0.2389895864 0.8328990340 0.0474121183 3.3628160000 1.2703770000 0.4983000000 0.1743640000 1.4071720000 0.0073860000 110175522 0 1787711488 2.9767799377 3.4545214176 4.0586829185 852 34.0400000000 0.7130131721 0.2395459521 0.8328990340 0.0473843529 3.1906490000 1.2690400000 0.4984340000 0.0000050000 1.4103520000 0.0075260000 110177196 0 1784410112 2.9800865650 3.4524772167 4.0491619110 853 34.0800000000 0.7143068314 0.2401025299 0.8328990340 0.0473565950 4.9185020000 1.2683740000 0.5014540000 0.1737050000 1.4002390000 1.5694900000 110178870 0 1785942016 2.9855406284 3.4524149895 4.0388131142 854 34.1199999990 0.7156551480 0.2406593831 0.8328990340 0.0473291372 3.1751360000 1.2660270000 0.4959180000 0.0000040000 1.4006180000 0.0074140000 110180544 0 1787719680 2.9884569645 3.4505555630 4.0307011604 855 34.1600000000 0.7174215317 0.2412169997 0.8328990340 0.0473015862 3.3485680000 1.2712840000 0.4964960000 0.1739960000 1.3940780000 0.0074240000 110182218 0 1784426496 2.9928607941 3.4459831715 4.0235939026 856 34.2000000000 0.7186449766 0.2417747426 0.8328990340 0.0472743793 3.1783580000 1.2663160000 0.4987050000 0.0000050000 1.4007300000 0.0073430000 110183892 0 1785933824 2.9996824265 3.4440112114 4.0162830353 857 34.2400000000 0.7198635340 0.2423326059 0.8328990340 0.0472469938 4.8928250000 1.2650320000 0.4957720000 0.1733040000 1.3927850000 1.5606210000 110185566 0 1787711488 3.0033779144 3.4410052299 4.0090332031 858 34.2800000000 0.7210283279 0.2428905263 0.8328990340 0.0472197395 3.1754390000 1.2672140000 0.4952070000 0.0000050000 1.4003020000 0.0073250000 110187240 0 1784823808 3.0082275867 3.4373683929 4.0036416054 859 34.3200000000 0.7223750353 0.2434487155 0.8328990340 0.0471939565 3.3473240000 1.2735930000 0.4916130000 0.1736450000 1.3958010000 0.0073970000 110188914 0 1786441728 3.0120744705 3.4373924732 3.9935810566 860 34.3600000000 0.7237120271 0.2440071612 0.8328990340 0.0471668216 3.0980340000 1.2661670000 0.4108590000 0.0000050000 1.4083280000 0.0073080000 110190588 0 1785569280 3.0161499977 3.4356551170 3.9846105576 861 34.4000000000 0.7252596021 0.2445661071 0.8328990340 0.0471397364 4.9122300000 1.2726610000 0.4887730000 0.1732720000 1.4036650000 1.5685500000 110192262 0 1787076608 3.0213205814 3.4311811924 3.9784421921 862 34.4400000000 0.7263696790 0.2451250440 0.8328990340 0.0471126311 3.1837600000 1.2669530000 0.4931500000 0.0000040000 1.4109240000 0.0073260000 110193936 0 1784832000 3.0257582664 3.4284141064 3.9714686871 863 34.4800000000 0.7273293138 0.2456837974 0.8328990340 0.0470855952 3.3612410000 1.2679150000 0.4950820000 0.1735230000 1.4120600000 0.0073080000 110195610 0 1786449920 3.0314817429 3.4281280041 3.9638741016 864 34.5200000000 0.7288909554 0.2462430650 0.8328990340 0.0470588192 3.1861050000 1.2664870000 0.4855120000 0.0000050000 1.4214500000 0.0073610000 110197284 0 1785569280 3.0350465775 3.4280855656 3.9542534351 865 34.5600000000 0.7302044630 0.2468025579 0.8328990340 0.0470335751 4.9536460000 1.2833510000 0.4849900000 0.1738250000 1.4249430000 1.5811900000 110198958 0 1787076608 3.0403113365 3.4214432240 3.9498682022 866 34.6000000000 0.7319496870 0.2473627740 0.8328990340 0.0470079372 3.2045350000 1.2721250000 0.4803570000 0.0000040000 1.4392570000 0.0073600000 110200632 0 1784823808 3.0434877872 3.4098827839 3.9502344131 867 34.6400000000 0.7348645329 0.2479250598 0.8328990340 0.0469894782 3.3361910000 1.2647510000 0.4350170000 0.1796830000 1.4440630000 0.0073470000 110202306 0 1786458112 3.0473389626 3.4036760330 3.9343187809 868 34.6800000000 0.7358193398 0.2484871500 0.8328990340 0.0469638594 3.2148850000 1.2684680000 0.4762470000 0.0000050000 1.4575480000 0.0073190000 110203980 0 1785679872 3.0539901257 3.4007132053 3.9285778999 869 34.7200000000 0.7369928956 0.2490492970 0.8328990340 0.0469391412 4.9991890000 1.2719470000 0.4714470000 0.1749290000 1.4584160000 1.6170790000 110205654 0 1787330560 3.0555915833 3.3991847038 3.9199914932 870 34.7600000000 0.7386164665 0.2496120179 0.8328990340 0.0469131594 3.1924470000 1.2744520000 0.4350700000 0.0000050000 1.4702960000 0.0072020000 110207328 0 1785061376 3.0605170727 3.3960475922 3.9116785526 871 34.8000000000 0.7396323085 0.2501746129 0.8328990340 0.0468865081 3.3296130000 1.2671630000 0.3983760000 0.1754210000 1.4761150000 0.0071910000 110209002 0 1786585088 3.0670266151 3.3917214870 3.9075965881 872 34.8400000000 0.7410818338 0.2507375799 0.8328990340 0.0468614135 3.1144070000 1.2672870000 0.3570700000 0.0000050000 1.4774110000 0.0071810000 110210676 0 1784705024 3.0686066151 3.3884053230 3.9010109901 873 34.8800000000 0.7420214415 0.2513003335 0.8328990340 0.0468369748 4.8765110000 1.2718070000 0.3187200000 0.1749520000 1.4788700000 1.6267050000 110212350 0 1786187776 3.0765838623 3.3909645081 3.8915073872 874 34.9200000000 0.7433782816 0.2518633517 0.8328990340 0.0468110598 3.1289620000 1.2735930000 0.3577740000 0.0000050000 1.4848540000 0.0073590000 110214024 0 1787981824 3.0773398876 3.3899068832 3.8824672699 875 34.9600000000 0.7441604733 0.2524259770 0.8328990340 0.0467851641 3.2238770000 1.2659250000 0.2761380000 0.1753870000 1.4938610000 0.0071750000 110215698 0 1785204736 3.0822327137 3.3920924664 3.8736355305 876 35.0000000000 0.7452924848 0.2529886100 0.8328990340 0.0467587081 3.0936860000 1.2676350000 0.3142880000 0.0000040000 1.4988160000 0.0073240000 110217372 0 1786712064 3.0871951580 3.3894670010 3.8669404984 877 35.0400000000 0.7459322810 0.2535506894 0.8328990340 0.0467321653 4.9158480000 1.2730620000 0.3140900000 0.1752270000 1.5013470000 1.6466050000 110219046 0 1784680448 3.0958185196 3.3851850033 3.8639295101 878 35.0800000000 0.7473884821 0.2541131471 0.8328990340 0.0467059099 3.1122010000 1.2659720000 0.3249860000 0.0000040000 1.5086920000 0.0070660000 110220720 0 1786331136 3.0991151333 3.3802793026 3.8589634895 879 35.1200000000 0.7483474612 0.2546754159 0.8328990340 0.0466819632 3.2092040000 1.2705010000 0.2347250000 0.1751440000 1.5163300000 0.0070770000 110222394 0 1785806848 3.1020503044 3.3821868896 3.8472878933 880 35.1600000000 0.7493798733 0.2552375801 0.8328990340 0.0466555546 3.0756320000 1.2691390000 0.2719040000 0.0000040000 1.5221480000 0.0070860000 110224068 0 1787330560 3.1105132103 3.3788113594 3.8415446281 881 35.2000000000 0.7501979470 0.2557993966 0.8328990340 0.0466293144 4.9593720000 1.2682290000 0.3088540000 0.1751960000 1.5327530000 1.6688870000 110225742 0 1785212928 3.1152524948 3.3753445148 3.8374817371 882 35.2400000000 0.7512636781 0.2563611475 0.8328990340 0.0466035209 3.1686190000 1.2649550000 0.3457150000 0.0000040000 1.5455520000 0.0070700000 110227416 0 1786593280 3.1218810081 3.3737645149 3.8290185928 883 35.2800000000 0.7528886795 0.2569234663 0.8328990340 0.0465776706 3.2602520000 1.2654880000 0.2659530000 0.1755020000 1.5408690000 0.0069800000 110229090 0 1784569856 3.1235454082 3.3712701797 3.8196091652 884 35.3200000000 0.7537171841 0.2574854502 0.8328990340 0.0465515586 3.1014870000 1.2723000000 0.2671760000 0.0000040000 1.5496000000 0.0070410000 110230764 0 1786204160 3.1317746639 3.3698139191 3.8133621216 885 35.3600000000 0.7547210455 0.2580472983 0.8328990340 0.0465264062 4.9611190000 1.2683690000 0.2658320000 0.1752340000 1.5572080000 1.6889740000 110232438 0 1787981824 3.1393210888 3.3618257046 3.8108141422 886 35.4000000000 0.7567204237 0.2586101348 0.8328990340 0.0465012514 3.0743570000 1.2693240000 0.2289320000 0.0000050000 1.5636380000 0.0070470000 110234112 0 1785204736 3.1401708126 3.3526160717 3.8064603806 887 35.4400000000 0.7582541704 0.2591734313 0.8328990340 0.0464758855 3.3137320000 1.2664420000 0.3047870000 0.1753170000 1.5546670000 0.0069240000 110235786 0 1786822656 3.1425886154 3.3497514725 3.7957653999 888 35.4800000000 0.7597450018 0.2597371381 0.8328990340 0.0464499771 3.2642170000 1.2728660000 0.4209410000 0.0000050000 1.5580900000 0.0069170000 110237460 0 1784807424 3.1476588249 3.3440659046 3.7898499966 889 35.5200000000 0.7612056732 0.2603012196 0.8328990340 0.0464246919 5.0815140000 1.2671760000 0.3808300000 0.1755390000 1.5628660000 1.6896010000 110239134 0 1786314752 3.1519119740 3.3396091461 3.7833054066 890 35.5600000000 0.7627977133 0.2608658224 0.8328990340 0.0464012237 3.1085030000 1.2688600000 0.2663390000 0.0000040000 1.5609350000 0.0069810000 110240808 0 1785585664 3.1560652256 3.3381588459 3.7739107609 891 35.6000000000 0.7644582987 0.2614310216 0.8328990340 0.0463775219 3.2769800000 1.2697150000 0.2665290000 0.1748570000 1.5533280000 0.0069140000 110242482 0 1787338752 3.1621613503 3.3374581337 3.7619376183 892 35.6400000000 0.7662283182 0.2619969379 0.8328990340 0.0463523895 3.1016500000 1.2711940000 0.2643440000 0.0000040000 1.5536970000 0.0070050000 110244156 0 1785069568 3.1663129330 3.3353984356 3.7530601025 893 35.6800000000 0.7673640847 0.2625628585 0.8328990340 0.0463270139 5.0069440000 1.2657880000 0.3386480000 0.1748140000 1.5475220000 1.6746320000 110245830 0 1786822656 3.1736023426 3.3316586018 3.7477684021 894 35.7200000000 0.7683743238 0.2631286432 0.8328990340 0.0463023124 3.1398620000 1.2704890000 0.3086450000 0.0000040000 1.5481920000 0.0069870000 110247504 0 1784696832 3.1817259789 3.3316030502 3.7410254478 895 35.7600000000 0.7699584365 0.2636949335 0.8328990340 0.0462777529 3.2536380000 1.2675500000 0.2648160000 0.1744970000 1.5341770000 0.0070580000 110249178 0 1786441728 3.1870782375 3.3304467201 3.7303261757 896 35.8000000000 0.7712737322 0.2642614276 0.8328990340 0.0462530122 3.1275870000 1.2654290000 0.3069860000 0.0000040000 1.5427490000 0.0069660000 110250852 0 1785696256 3.1925222874 3.3303341866 3.7217381001 897 35.8400000000 0.7722852230 0.2648277864 0.8328990340 0.0462289186 4.9106560000 1.2673650000 0.2681710000 0.1743170000 1.5304800000 1.6647170000 110252526 0 1787092992 3.2000234127 3.3349606991 3.7088062763 898 35.8800000000 0.7732081413 0.2653939115 0.8328990340 0.0462055319 3.0772120000 1.2645910000 0.2683400000 0.0000050000 1.5316100000 0.0070120000 110254200 0 1784807424 3.2079603672 3.3344047070 3.7021374702 899 35.9200000000 0.7746085525 0.2659603349 0.8328990340 0.0461826480 3.2545530000 1.2742030000 0.2660500000 0.1743150000 1.5273390000 0.0070330000 110255874 0 1786331136 3.2146289349 3.3307039738 3.6951510906 900 35.9600000000 0.7761413455 0.2665272027 0.8328990340 0.0461599099 3.0923870000 1.2679390000 0.2696320000 0.0000040000 1.5420750000 0.0071060000 110257548 0 1785696256 3.2235064507 3.3223505020 3.6931118965 901 36.0000000000 0.7778770328 0.2670947386 0.8328990340 0.0461361242 4.9497300000 1.2651310000 0.3064460000 0.1744390000 1.5342370000 1.6639020000 110259222 0 1787355136 3.2267735004 3.3149023056 3.6900568008 902 36.0400000000 0.7800251245 0.2676633976 0.8328990340 0.0461136299 3.0894010000 1.2675100000 0.2678420000 0.0000050000 1.5414050000 0.0070810000 110260896 0 1785188352 3.2323083878 3.3125324249 3.6768093109 903 36.0800000000 0.7817149758 0.2682326684 0.8328990340 0.0460902897 3.2632670000 1.2745930000 0.2640010000 0.1754640000 1.5364940000 0.0070330000 110262570 0 1787076608 3.2385170460 3.3074765205 3.6707696915 904 36.1200000000 0.7813006639 0.2688002215 0.8328990340 0.0460664011 3.0586570000 1.2673170000 0.2294760000 0.0000050000 1.5493160000 0.0069660000 110264244 0 1784696832 3.2512433529 3.3071935177 3.6744277477 905 36.1600000000 0.7858446240 0.2693715413 0.8328990340 0.0460574301 4.8959270000 1.2700970000 0.2687120000 0.1741990000 1.5275430000 1.6498200000 110265918 0 1786314752 3.2747073174 3.3009481430 3.6483869553 906 36.2000000000 0.7873550057 0.2699432670 0.8328990340 0.0460334761 3.2734890000 1.2707210000 0.4614710000 0.0000050000 1.5286000000 0.0070130000 110267592 0 1785569280 3.2818069458 3.2970962524 3.6405944824 907 36.2400000000 0.7889258862 0.2705154639 0.8328990340 0.0460092526 3.2484050000 1.2697540000 0.2721740000 0.1739940000 1.5197740000 0.0070900000 110269266 0 1787076608 3.2881116867 3.2910070419 3.6370375156 908 36.2800000000 0.7897425890 0.2710872999 0.8328990340 0.0459872177 3.0745570000 1.2701450000 0.2695150000 0.0000040000 1.5222240000 0.0070600000 110270940 0 1784807424 3.2921645641 3.2905673981 3.6302545071 909 36.3200000000 0.7898410559 0.2716579861 0.8328990340 0.0459636312 4.9283050000 1.2771390000 0.3463920000 0.1738580000 1.5059260000 1.6192270000 110272614 0 1786314752 3.3021891117 3.2931911945 3.6253790855 910 36.3600000000 0.7901799679 0.2722277905 0.8328990340 0.0459398755 3.0665420000 1.2755770000 0.2702110000 0.0000050000 1.5079090000 0.0071960000 110274288 0 1785737216 3.3109002113 3.2919695377 3.6242148876 911 36.4000000000 0.7908676863 0.2727970988 0.8328990340 0.0459161679 3.1936420000 1.2684460000 0.2311300000 0.1734140000 1.5078210000 0.0072140000 110275962 0 1787101184 3.3159446716 3.2889785767 3.6223473549 912 36.4400000000 0.7916370630 0.2733660023 0.8328990340 0.0458922244 3.0548850000 1.2684980000 0.2706690000 0.0000040000 1.5028400000 0.0072150000 110277636 0 1784934400 3.3232417107 3.2883257866 3.6158070564 913 36.4800000000 0.7927116156 0.2739348365 0.8328990340 0.0458681943 4.8149140000 1.2730970000 0.2708000000 0.1731370000 1.4916870000 1.6005250000 110279310 0 1786474496 3.3304421902 3.2860848904 3.6112642288 914 36.5200000000 0.7936145663 0.2745034139 0.8328990340 0.0458438834 3.0167620000 1.2747320000 0.2314110000 0.0000200000 1.4977170000 0.0072490000 110280984 0 1785688064 3.3361339569 3.2822766304 3.6078746319 915 36.5600000000 0.7936437726 0.2750707804 0.8328990340 0.0458194458 3.3068300000 1.2741470000 0.3505460000 0.1729620000 1.4961660000 0.0072870000 110282658 0 1787219968 3.3449654579 3.2820904255 3.6056933403 916 36.6000000000 0.7942111492 0.2756375275 0.8328990340 0.0457954936 3.0844830000 1.2725630000 0.3141970000 0.0000040000 1.4847640000 0.0072840000 110284332 0 1784918016 3.3536989689 3.2830588818 3.6001231670 917 36.6400000000 0.7952021956 0.2762041193 0.8328990340 0.0457709976 4.8541050000 1.2669700000 0.3502480000 0.1775770000 1.4749360000 1.5785960000 110286006 0 1786331136 3.3600687981 3.2779200077 3.5977981091 918 36.6800000000 0.7964015603 0.2767707832 0.8328990340 0.0457468673 3.0439110000 1.2731590000 0.2745190000 0.0000050000 1.4832320000 0.0072730000 110287680 0 1785696256 3.3660387993 3.2725200653 3.5945248604 919 36.7200000000 0.7968392968 0.2773366902 0.8328990340 0.0457229924 3.1986340000 1.2750380000 0.2743450000 0.1712230000 1.4649830000 0.0073190000 110289354 0 1787363328 3.3735594749 3.2737035751 3.5904679298 920 36.7600000000 0.7977790236 0.2779023884 0.8328990340 0.0456986282 3.0355850000 1.2783380000 0.2776540000 0.0000050000 1.4664990000 0.0073080000 110291028 0 1785069568 3.3793659210 3.2735047340 3.5837659836 921 36.8000000000 0.7974717617 0.2784665245 0.8328990340 0.0456742990 4.7414340000 1.2708600000 0.2700160000 0.1706030000 1.4662860000 1.5579380000 110292702 0 1786593280 3.3910012245 3.2762739658 3.5816862583 922 36.8400000000 0.7985254526 0.2790305797 0.8328990340 0.0456511751 3.0636380000 1.2665310000 0.3201420000 0.0000040000 1.4638310000 0.0073420000 110294376 0 1785806848 3.4009552002 3.2710981369 3.5810739994 923 36.8800000000 0.7985401750 0.2795934287 0.8328990340 0.0456266242 3.1507540000 1.2720440000 0.2422840000 0.1701040000 1.4532400000 0.0074150000 110296050 0 1787219968 3.4081807137 3.2688782215 3.5795040131 924 36.9200000000 0.7995320559 0.2801561328 0.8328990340 0.0456027630 2.9822230000 1.2680900000 0.2489900000 0.0000050000 1.4517100000 0.0074250000 110297724 0 1784934400 3.4192569256 3.2706332207 3.5716536045 925 36.9600000000 0.8003838062 0.2807185411 0.8328990340 0.0455794375 4.7133640000 1.2699970000 0.2831290000 0.1689550000 1.4431320000 1.5424530000 110299398 0 1786458112 3.4299962521 3.2693789005 3.5666413307 926 37.0000000000 0.8013738394 0.2812808039 0.8328990340 0.0455578604 2.9979780000 1.2684910000 0.2760820000 0.0000050000 1.4401880000 0.0075010000 110301072 0 1785679872 3.4461066723 3.2691280842 3.5586671829 927 37.0400000000 0.8017901182 0.2818423026 0.8328990340 0.0455340487 3.1721500000 1.2752590000 0.2847170000 0.1679800000 1.4308500000 0.0075470000 110302746 0 1787219968 3.4588685036 3.2693700790 3.5557327271 928 37.0800000000 0.8025629520 0.2824034240 0.8328990340 0.0455100474 2.9989310000 1.2683350000 0.2856850000 0.0000050000 1.4316210000 0.0075670000 110304420 0 1784934400 3.4665248394 3.2646043301 3.5536053181 929 37.1200000000 0.8034978509 0.2829643437 0.8328990340 0.0454860695 4.6495600000 1.2707480000 0.2855030000 0.1672610000 1.4150030000 1.5053110000 110306094 0 1786568704 3.4759678841 3.2607908249 3.5510699749 930 37.1600000000 0.8039904833 0.2835245869 0.8328990340 0.0454622575 2.9423880000 1.2688910000 0.2446360000 0.0000050000 1.4153830000 0.0076200000 110307768 0 1785593856 3.4862802029 3.2598495483 3.5476870537 931 37.2000000000 0.8048154116 0.2840845126 0.8328990340 0.0454383176 3.1526570000 1.2719720000 0.2837210000 0.1663800000 1.4171670000 0.0075600000 110309442 0 1787211776 3.4934709072 3.2564859390 3.5434544086 932 37.2400000000 0.8050365448 0.2846434740 0.8328990340 0.0454143725 2.9471580000 1.2712320000 0.2469470000 0.0000050000 1.4155750000 0.0076130000 110311116 0 1784545280 3.5046510696 3.2578094006 3.5428409576 933 37.2800000000 0.8054736257 0.2852017056 0.8328990340 0.0453907961 4.6422840000 1.2778810000 0.2887570000 0.1654610000 1.4145020000 1.4898940000 110312790 0 1786187776 3.5154199600 3.2585408688 3.5378513336 934 37.3200000000 0.8061850071 0.2857595036 0.8328990340 0.0453675390 3.0005270000 1.2766320000 0.2898140000 0.0000050000 1.4207110000 0.0076840000 110314464 0 1787965440 3.5259373188 3.2587001324 3.5332567692 935 37.3600000000 0.8066280484 0.2863165823 0.8328990340 0.0453443061 3.1186130000 1.2710300000 0.2480890000 0.1649400000 1.4210090000 0.0076650000 110316138 0 1784791040 3.5373935699 3.2586209774 3.5319969654 936 37.4000000000 0.8063730001 0.2868721981 0.8328990340 0.0453205929 3.0567640000 1.2758110000 0.3297660000 0.0000050000 1.4377660000 0.0075660000 110317812 0 1786441728 3.5483238697 3.2572946548 3.5331368446 937 37.4400000000 0.8067089319 0.2874269865 0.8328990340 0.0452970118 4.6817900000 1.2727490000 0.3295240000 0.1643660000 1.4245810000 1.4848420000 110319486 0 1785679872 3.5596621037 3.2554812431 3.5329182148 938 37.4800000000 0.8078427911 0.2879818008 0.8328990340 0.0452732769 2.9877030000 1.2706800000 0.2776400000 0.0000040000 1.4258110000 0.0077160000 110321160 0 1787203584 3.5671987534 3.2515957355 3.5303823948 939 37.5200000000 0.8079333901 0.2885355299 0.8328990340 0.0452501540 3.1431730000 1.2713490000 0.2910350000 0.1631570000 1.4041610000 0.0076910000 110322834 0 1784553472 3.5786795616 3.2539484501 3.5259430408 940 37.5600000000 0.8078635931 0.2890880065 0.8328990340 0.0452265095 2.9931000000 1.2822250000 0.2951540000 0.0000050000 1.4022040000 0.0076760000 110324508 0 1786187776 3.5904166698 3.2558872700 3.5257694721 941 37.6000000000 0.8085229397 0.2896400096 0.8328990340 0.0452028724 4.5343360000 1.2720100000 0.2502780000 0.1621510000 1.3904190000 1.4535980000 110326182 0 1787990016 3.5988454819 3.2530443668 3.5240774155 942 37.6400000000 0.8093649149 0.2901917346 0.8328990340 0.0451793799 3.0118330000 1.2713460000 0.3382410000 0.0000040000 1.3886740000 0.0077170000 110327856 0 1784553472 3.6069097519 3.2492692471 3.5216674805 943 37.6800000000 0.8093718886 0.2907422968 0.8328990340 0.0451560537 3.1327570000 1.2782040000 0.2992960000 0.1637440000 1.3776590000 0.0079230000 110329530 0 1785933824 3.6183826923 3.2487208843 3.5214886665 944 37.7200000000 0.8093482256 0.2912916675 0.8328990340 0.0451325854 2.9596860000 1.2702650000 0.2980960000 0.0000050000 1.3776080000 0.0077900000 110331204 0 1787965440 3.6266260147 3.2475442886 3.5226156712 945 37.7600000000 0.8089877963 0.2918394941 0.8328990340 0.0451091743 4.5001000000 1.2715080000 0.2992870000 0.1599300000 1.3561030000 1.4074210000 110332878 0 1784553472 3.6382861137 3.2465665340 3.5241878033 946 37.8000000000 0.8096187711 0.2923868295 0.8328990340 0.0450860124 2.9394060000 1.2724830000 0.3012750000 0.0000040000 1.3518530000 0.0078870000 110334552 0 1785933824 3.6477990150 3.2442731857 3.5235228539 947 37.8400000000 0.8101267219 0.2929335453 0.8328990340 0.0450639793 3.0433690000 1.2719700000 0.2578360000 0.1585020000 1.3412440000 0.0079150000 110336226 0 1787838464 3.6571130753 3.2416431904 3.5203530788 948 37.8800000000 0.8105563521 0.2934795609 0.8328990340 0.0450416253 2.9171030000 1.2711200000 0.3039490000 0.0000050000 1.3281210000 0.0079480000 110337900 0 1784061952 3.6669306755 3.2391033173 3.5196936131 949 37.9200000000 0.8112703562 0.2940251782 0.8328990340 0.0450195583 4.3971530000 1.2760150000 0.3064770000 0.1569220000 1.3079120000 1.3439660000 110339574 0 1785552896 3.6763441563 3.2380580902 3.5158832073 950 37.9600000000 0.8115230799 0.2945699128 0.8328990340 0.0449968239 2.9014040000 1.2713430000 0.3071500000 0.0000050000 1.3088140000 0.0081300000 110341248 0 1787584512 3.6865036488 3.2374596596 3.5140419006 951 38.0000000000 0.8121222854 0.2951141319 0.8328990340 0.0449738505 3.0400480000 1.2722130000 0.3060720000 0.1554570000 1.2922560000 0.0080600000 110342922 0 1784451072 3.6954402924 3.2351276875 3.5134150982 952 38.0400000000 0.8130574226 0.2956581900 0.8328990340 0.0449511668 2.8952510000 1.2772990000 0.3100060000 0.0000050000 1.2940760000 0.0080760000 110344596 0 1785815040 3.7049801350 3.2320282459 3.5115125179 953 38.0800000000 0.8131489754 0.2962012024 0.8328990340 0.0449285738 4.2978450000 1.2694230000 0.2646390000 0.1543350000 1.2915950000 1.3118900000 110346270 0 1787727872 3.7150025368 3.2314126492 3.5107312202 954 38.1200000000 0.8137417436 0.2967436977 0.8328990340 0.0449057141 2.8881110000 1.2720870000 0.3119530000 0.0000050000 1.2899910000 0.0080870000 110347944 0 1784426496 3.7256205082 3.2300796509 3.5093805790 955 38.1600000000 0.8140184283 0.2972853466 0.8328990340 0.0448836218 3.0494450000 1.2810350000 0.3098470000 0.1535480000 1.2909510000 0.0081580000 110349618 0 1785806848 3.7353880405 3.2305684090 3.5071952343 956 38.2000000000 0.8146808147 0.2978265553 0.8328990340 0.0448608523 2.9002970000 1.2701220000 0.3109830000 0.0000050000 1.3050880000 0.0082000000 110351292 0 1787727872 3.7463500500 3.2293694019 3.5045561790 957 38.2400000000 0.8156036139 0.2983675971 0.8328990340 0.0448378353 4.3736760000 1.2762100000 0.3134030000 0.1530060000 1.3006150000 1.3244270000 110352966 0 1784299520 3.7570562363 3.2280914783 3.5015914440 958 38.2800000000 0.8164732456 0.2989084172 0.8328990340 0.0448148340 2.8677220000 1.2748960000 0.2676800000 0.0000050000 1.3109710000 0.0081190000 110354640 0 1785806848 3.7654752731 3.2255063057 3.4987776279 959 38.3200000000 0.8166942000 0.2994483398 0.8328990340 0.0447921791 3.0665460000 1.2696620000 0.3116190000 0.1526660000 1.3184990000 0.0082060000 110356314 0 1787711488 3.7765800953 3.2276878357 3.4961550236 960 38.3600000000 0.8165502548 0.2999869877 0.8328990340 0.0447695735 2.8829340000 1.2759230000 0.2681520000 0.0000060000 1.3246970000 0.0081870000 110357988 0 1784426496 3.7901275158 3.2312874794 3.4942765236 961 38.4000000000 0.8170556426 0.3005250404 0.8328990340 0.0447501291 4.3878430000 1.2731520000 0.2726370000 0.1520110000 1.3313260000 1.3526950000 110359662 0 1785942016 3.7989509106 3.2252154350 3.4955072403 962 38.4400000000 0.8173651695 0.3010622962 0.8328990340 0.0447281304 2.8991030000 1.2701630000 0.2684170000 0.0000050000 1.3463880000 0.0081440000 110361336 0 1787592704 3.8086814880 3.2226517200 3.4952325821 963 38.4800000000 0.8178070784 0.3015988952 0.8328990340 0.0447064130 3.0849950000 1.2742020000 0.3050270000 0.1514770000 1.3400690000 0.0082310000 110363010 0 1784299520 3.8205475807 3.2202103138 3.4937026501 964 38.5200000000 0.8180840611 0.3021346682 0.8328990340 0.0446846363 2.9025160000 1.2784100000 0.2615570000 0.0000050000 1.3484950000 0.0081670000 110364684 0 1785806848 3.8306882381 3.2180778980 3.4938473701 965 38.5600000000 0.8187032938 0.3026699724 0.8328990340 0.0446621644 4.4716450000 1.2716400000 0.3114310000 0.1511900000 1.3572730000 1.3741410000 110366358 0 1787727872 3.8412566185 3.2151088715 3.4908220768 966 38.6000000000 0.8190783262 0.3032045567 0.8328990340 0.0446397160 2.9685520000 1.2733490000 0.3166500000 0.0000050000 1.3643790000 0.0081910000 110368032 0 1784315904 3.8507134914 3.2126865387 3.4896235466 967 38.6400000000 0.8192040324 0.3037381652 0.8328990340 0.0446180599 3.0792200000 1.2798370000 0.2700970000 0.1506440000 1.3644150000 0.0081970000 110369706 0 1785679872 3.8617799282 3.2114634514 3.4890129566 968 38.6800000000 0.8199499846 0.3042714419 0.8328990340 0.0445960348 2.9966040000 1.2799940000 0.3177710000 0.0000040000 1.3844190000 0.0081850000 110371380 0 1787490304 3.8713719845 3.2087197304 3.4861216545 969 38.7200000000 0.8197690845 0.3048034312 0.8328990340 0.0445735974 4.5368910000 1.2768320000 0.3180080000 0.1506620000 1.3806220000 1.4047760000 110373054 0 1784553472 3.8816430569 3.2086477280 3.4855241776 970 38.7600000000 0.8205582500 0.3053351372 0.8328990340 0.0445511496 2.9961750000 1.2726670000 0.3172380000 0.0000050000 1.3920770000 0.0081840000 110374728 0 1785933824 3.8893692493 3.2057211399 3.4819748402 971 38.8000000000 0.8209465742 0.3058661479 0.8328990340 0.0445288082 3.1042690000 1.2699650000 0.2700630000 0.1499310000 1.3998530000 0.0082400000 110376402 0 1787854848 3.8999092579 3.2051610947 3.4791066647 972 38.8400000000 0.8210008740 0.3063961219 0.8328990340 0.0445075297 2.9693810000 1.2749990000 0.2740910000 0.0000050000 1.4060320000 0.0082150000 110378076 0 1784578048 3.9097638130 3.2047526836 3.4771752357 973 38.8800000000 0.8210393786 0.3069250462 0.8328990340 0.0444885578 4.5278640000 1.2789680000 0.2627920000 0.1495850000 1.4057940000 1.4246390000 110379750 0 1785942016 3.9202060699 3.2044422626 3.4759387970 974 38.9200000000 0.8209336996 0.3074527758 0.8328990340 0.0444692610 3.0137630000 1.2768030000 0.3089730000 0.0000040000 1.4137020000 0.0081830000 110381424 0 1787854848 3.9283564091 3.2025997639 3.4773011208 975 38.9600000000 0.8209301233 0.3079794192 0.8328990340 0.0444476970 3.1231880000 1.2720390000 0.2713440000 0.1491510000 1.4162330000 0.0081920000 110383098 0 1784553472 3.9374420643 3.2009179592 3.4776668549 976 39.0000000000 0.8209761381 0.3085050306 0.8328990340 0.0444256964 2.9909510000 1.2773920000 0.2725600000 0.0000040000 1.4264650000 0.0081840000 110384772 0 1785933824 3.9469413757 3.1991403103 3.4773037434 977 39.0400000000 0.8209726214 0.3090295624 0.8328990340 0.0444035253 4.5916360000 1.2736720000 0.2719240000 0.1490460000 1.4396140000 1.4512950000 110386446 0 1787838464 3.9573540688 3.1988625526 3.4766492844 978 39.0800000000 0.8205019832 0.3095525404 0.8328990340 0.0443813750 3.0010270000 1.2729780000 0.2702440000 0.0000040000 1.4434410000 0.0081770000 110388120 0 1784442880 3.9666385651 3.1977179050 3.4786629677 979 39.1200000000 0.8209881186 0.3100749465 0.8328990340 0.0443608523 3.1510520000 1.2742100000 0.2730750000 0.1490450000 1.4402710000 0.0082660000 110389794 0 1785806848 3.9749531746 3.1951038837 3.4763646126 980 39.1600000000 0.8210418224 0.3105963412 0.8328990340 0.0443397170 3.0542360000 1.2714700000 0.3145840000 0.0000050000 1.4538580000 0.0082550000 110391468 0 1787854848 3.9863119125 3.1945469379 3.4743571281 981 39.2000000000 0.8206589818 0.3111162828 0.8328990340 0.0443178904 4.6394440000 1.2726660000 0.2711880000 0.1489440000 1.4574970000 1.4830500000 110393142 0 1784442880 3.9984738827 3.1958456039 3.4736547470 982 39.2400000000 0.8204931617 0.3116349965 0.8328990340 0.0442960367 3.0251210000 1.2711400000 0.2694140000 0.0000050000 1.4702730000 0.0082030000 110394816 0 1785942016 4.0044751167 3.1947271824 3.4747762680 983 39.2800000000 0.8204917312 0.3121526534 0.8328990340 0.0442743125 3.1840010000 1.2805910000 0.2690020000 0.1495030000 1.4705570000 0.0081200000 110396490 0 1787727872 4.0142259598 3.1935889721 3.4754364491 984 39.3200000000 0.8205069304 0.3126692736 0.8328990340 0.0442526065 3.0945310000 1.2751390000 0.3164150000 0.0000050000 1.4886100000 0.0081390000 110398164 0 1784426496 4.0255947113 3.1933977604 3.4745347500 985 39.3600000000 0.8207939267 0.3131851362 0.8328990340 0.0442308567 4.7455970000 1.2731230000 0.3146190000 0.1495220000 1.4869360000 1.5152090000 110399838 0 1785806848 4.0338139534 3.1909313202 3.4746332169 986 39.4000000000 0.8203374147 0.3136994894 0.8328990340 0.0442089721 3.0527810000 1.2753660000 0.2665950000 0.0000040000 1.4966020000 0.0081160000 110401512 0 1787727872 4.0416736603 3.1903254986 3.4776291847 987 39.4400000000 0.8202759624 0.3142127381 0.8328990340 0.0441872322 3.2497590000 1.2716250000 0.3177940000 0.1497570000 1.4963620000 0.0081330000 110403186 0 1784426496 4.0512804985 3.1893265247 3.4792308807 988 39.4800000000 0.8202299476 0.3147249013 0.8328990340 0.0441653702 3.0576650000 1.2736920000 0.2662690000 0.0000050000 1.5033760000 0.0080390000 110404860 0 1785806848 4.0617523193 3.1884813309 3.4796433449 989 39.5200000000 0.8203066587 0.3152361063 0.8328990340 0.0441434822 4.7843930000 1.2801510000 0.3094210000 0.1497300000 1.5065630000 1.5323480000 110406534 0 1787600896 4.0706386566 3.1876592636 3.4798922539 990 39.5600000000 0.8200780749 0.3157460477 0.8328990340 0.0441215043 3.1033820000 1.2786960000 0.2985880000 0.0000050000 1.5117420000 0.0080370000 110408208 0 1784299520 4.0803971291 3.1881053448 3.4804716110 991 39.6000000000 0.8191634417 0.3162540370 0.8328990340 0.0440995588 3.2710010000 1.2736800000 0.3144420000 0.1497120000 1.5189450000 0.0080010000 110409882 0 1785806848 4.0901179314 3.1906688213 3.4833889008 992 39.6400000000 0.8186115623 0.3167604458 0.8328990340 0.0440778280 3.1597080000 1.2700580000 0.3576200000 0.0000040000 1.5178320000 0.0080710000 110411556 0 1787719680 4.0997929573 3.1932995319 3.4842402935 993 39.6800000000 0.8176569939 0.3172648733 0.8328990340 0.0440570413 4.8234050000 1.2832630000 0.3126340000 0.1500760000 1.5236100000 1.5475500000 110413230 0 1784172544 4.1089539528 3.1961181164 3.4882712364 994 39.7200000000 0.8171243668 0.3177677501 0.8328990340 0.0440364710 3.1334450000 1.2774550000 0.3121770000 0.0000050000 1.5295590000 0.0080270000 110414904 0 1785679872 4.1185655594 3.1972701550 3.4902653694 995 39.7600000000 0.8168815970 0.3182693720 0.8328990340 0.0440159315 3.3316390000 1.2730070000 0.3572490000 0.1495230000 1.5374980000 0.0079610000 110416578 0 1787711488 4.1269421577 3.1963348389 3.4923586845 996 39.8000000000 0.8164492249 0.3187695526 0.8328990340 0.0439944801 3.0892880000 1.2726040000 0.2680240000 0.0000040000 1.5342900000 0.0080200000 110418252 0 1784188928 4.1364235878 3.1959264278 3.4950826168 997 39.8400000000 0.8160069585 0.3192682862 0.8328990340 0.0439730322 4.8442990000 1.2749570000 0.3186440000 0.1491870000 1.5346090000 1.5606690000 110419926 0 1785679872 4.1470050812 3.1963086128 3.4969835281 998 39.8800000000 0.8156973124 0.3197657101 0.8328990340 0.0439517106 3.1415330000 1.2728460000 0.3175870000 0.0000040000 1.5366920000 0.0079900000 110421600 0 1787727872 4.1561808586 3.1957926750 3.4985365868 999 39.9200000000 0.8146563172 0.3202610961 0.8328990340 0.0439300277 3.2909050000 1.2719410000 0.3143250000 0.1493020000 1.5410460000 0.0080740000 110423274 0 1784791040 4.1688494682 3.2006244659 3.5013277531 1000 39.9600000000 0.8144268394 0.3207552618 0.8328990340 0.0439090250 3.1860940000 1.2755510000 0.3563720000 0.0000040000 1.5399280000 0.0079280000 110424948 0 1786585088 4.1777534485 3.2000415325 3.5015785694 1001 40.0000000000 0.8144027591 0.3212484162 0.8328990340 0.0438873795 4.8987130000 1.2721680000 0.3512450000 0.1487790000 1.5486600000 1.5716060000 110426622 0 1785593856 4.1868934631 3.1990711689 3.5029079914 1002 40.0400000000 0.8137966394 0.3217399813 0.8328990340 0.0438658161 3.1504540000 1.2733100000 0.3084360000 0.0000050000 1.5543850000 0.0079260000 110428296 0 1787211776 4.1974291801 3.2007331848 3.5056641102 1003 40.0800000000 0.8129475713 0.3222297196 0.8328990340 0.0438444057 3.2896630000 1.2730260000 0.3080510000 0.1485000000 1.5458530000 0.0080010000 110429970 0 1784664064 4.2087850571 3.2033703327 3.5070195198 1004 40.1200000000 0.8124091029 0.3227179461 0.8328990340 0.0438240950 3.1485650000 1.2772470000 0.3074770000 0.0000040000 1.5496050000 0.0078700000 110431644 0 1786187776 4.2175078392 3.2029809952 3.5093059540 1005 40.1600000000 0.8119286895 0.3232047230 0.8328990340 0.0438026318 4.8686790000 1.2729200000 0.3065570000 0.1483020000 1.5556800000 1.5787850000 110433318 0 1788092416 4.2269549370 3.2033240795 3.5104007721 1006 40.2000000000 0.8104186654 0.3236890311 0.8328990340 0.0437810984 3.2484300000 1.2720310000 0.4050110000 0.0000190000 1.5570920000 0.0078260000 110434992 0 1784840192 4.2371740341 3.2061383724 3.5126042366 1007 40.2400000000 0.8093025088 0.3241712689 0.8328990340 0.0437599052 3.4800000000 1.2747760000 0.4897550000 0.1482050000 1.5531010000 0.0078330000 110436666 0 1786441728 4.2469363213 3.2082133293 3.5155341625 1008 40.2800000000 0.8086124659 0.3246518653 0.8328990340 0.0437389583 3.3868820000 1.2791330000 0.5357840000 0.0000040000 1.5578410000 0.0078800000 110438340 0 1785348096 4.2549104691 3.2084295750 3.5184779167 1009 40.3200000000 0.8078204393 0.3251307241 0.8328990340 0.0437177044 5.1068890000 1.2715810000 0.5308330000 0.1480360000 1.5632600000 1.5868470000 110440014 0 1786949632 4.2634177208 3.2093827724 3.5214540958 1010 40.3600000000 0.8069702387 0.3256077930 0.8328990340 0.0436966051 3.3844280000 1.2738150000 0.5274980000 0.0000040000 1.5689200000 0.0077880000 110441688 0 1784680448 4.2733411789 3.2108514309 3.5246028900 1011 40.4000000000 0.8068052530 0.3260837548 0.8328990340 0.0436756983 3.3958780000 1.2734390000 0.3939250000 0.1482020000 1.5662800000 0.0077550000 110443362 0 1786228736 4.2811608315 3.2103447914 3.5265338421 1012 40.4400000000 0.8065586686 0.3265585324 0.8328990340 0.0436543924 3.3840500000 1.2795130000 0.5207980000 0.0000040000 1.5696030000 0.0077340000 110445036 0 1788116992 4.2890605927 3.2089164257 3.5276489258 1013 40.4800000000 0.8052856326 0.3270311159 0.8328990340 0.0436333560 5.1265300000 1.2728110000 0.5247140000 0.1483100000 1.5749050000 1.5995020000 110446710 0 1785077760 4.2980508804 3.2103352547 3.5313115120 1014 40.5200000000 0.8055623174 0.3275030402 0.8328990340 0.0436120231 3.2575330000 1.2742000000 0.3892430000 0.0000040000 1.5799950000 0.0078000000 110448384 0 1786839040 4.3051490784 3.2116472721 3.5368709564 1015 40.5600000000 0.8053855300 0.3279738604 0.8328990340 0.0435911736 3.4466920000 1.2754990000 0.4331850000 0.1484860000 1.5754690000 0.0077050000 110450058 0 1784537088 4.3130960464 3.2101209164 3.5374667645 1016 40.6000000000 0.8046860099 0.3284430653 0.8328990340 0.0435702306 3.1767110000 1.2800880000 0.3004680000 0.0000050000 1.5819640000 0.0077250000 110451732 0 1785966592 4.3204741478 3.2078866959 3.5376050472 1017 40.6400000000 0.8035636544 0.3289102438 0.8328990340 0.0435494465 5.0848730000 1.2733870000 0.4373660000 0.1492510000 1.5862960000 1.6320370000 110453406 0 1787838464 4.3275003433 3.2093608379 3.5411889553 1018 40.6800000000 0.8026143909 0.3293755721 0.8328990340 0.0435283018 3.3222640000 1.2807700000 0.4370730000 0.0000040000 1.5902780000 0.0076560000 110455080 0 1784950784 4.3359847069 3.2096531391 3.5433022976 1019 40.7200000000 0.8021152616 0.3298394972 0.8328990340 0.0435071920 3.4075560000 1.2713160000 0.3899050000 0.1489160000 1.5833350000 0.0076680000 110456754 0 1786585088 4.3427958488 3.2110440731 3.5482110977 1020 40.7600000000 0.8005984426 0.3303010255 0.8328990340 0.0434861534 3.3996530000 1.2797940000 0.5224090000 0.0000040000 1.5833060000 0.0077160000 110458428 0 1785577472 4.3515286446 3.2116460800 3.5506782532 1021 40.8000000000 0.7996208668 0.3307606924 0.8328990340 0.0434650452 5.1585340000 1.2734740000 0.5299400000 0.1487910000 1.5838130000 1.6161440000 110460102 0 1787117568 4.3596119881 3.2131299973 3.5549488068 1022 40.8400000000 0.7980081439 0.3312178817 0.8328990340 0.0434439548 3.4049070000 1.2747830000 0.5309090000 0.0000040000 1.5851870000 0.0076930000 110461776 0 1784680448 4.3669204712 3.2150750160 3.5599565506 1023 40.8800000000 0.7985010743 0.3316746590 0.8328990340 0.0434230172 3.5487730000 1.2793580000 0.5166470000 0.1489800000 1.5896990000 0.0077390000 110463450 0 1786204160 4.3740320206 3.2172241211 3.5686204433 1024 40.9200000000 0.7960768938 0.3321281768 0.8328990340 0.0434025874 3.3524010000 1.2740260000 0.4779320000 0.0000040000 1.5863690000 0.0077660000 110465124 0 1788108800 4.3832859993 3.2180080414 3.5691020489 1025 40.9600000000 0.7958385348 0.3325805771 0.8328990340 0.0433819924 5.1571740000 1.2823570000 0.5145580000 0.1486500000 1.5860060000 1.6188380000 110552038 0 1785044992 4.3928170204 3.2203960419 3.5769116879 1026 41.0000000000 0.7948480844 0.3330311303 0.8328990340 0.0433615065 3.2731390000 1.2807930000 0.3887460000 0.0000040000 1.5894050000 0.0076630000 110718328 0 1787076608 4.3988542557 3.2213513851 3.5824551582 1027 41.0400000000 0.7940987945 0.3334800764 0.8328990340 0.0433407361 3.5433700000 1.2704670000 0.5142720000 0.1490000000 1.5955050000 0.0076460000 110720002 0 1784664064 4.4071226120 3.2199630737 3.5830419064 1028 41.0800000000 0.7933151722 0.3339273868 0.8328990340 0.0433201023 3.3988340000 1.2750060000 0.5152730000 0.0000040000 1.5943340000 0.0076600000 110721676 0 1786331136 4.4180779457 3.2238593102 3.5917830467 1029 41.1200000000 0.7924890518 0.3343730250 0.8328990340 0.0432996175 5.1754270000 1.2789670000 0.5141910000 0.1493140000 1.5952140000 1.6313340000 110723350 0 1788100608 4.4266538620 3.2238855362 3.5931503773 1030 41.1600000000 0.7922559381 0.3348175715 0.8328990340 0.0432794575 3.2960180000 1.2819340000 0.3840080000 0.0000040000 1.6158720000 0.0077440000 110725024 0 1784832000 4.4346675873 3.2242953777 3.5972452164 1031 41.2000000000 0.7908829451 0.3352599239 0.8328990340 0.0432596757 3.3889670000 1.2733520000 0.3404340000 0.1492940000 1.6117240000 0.0076360000 110726698 0 1786576896 4.4435396194 3.2242324352 3.6007502079 1032 41.2400000000 0.7902033925 0.3357007606 0.8328990340 0.0432399771 3.1471020000 1.2733420000 0.2533880000 0.0000040000 1.6062340000 0.0076410000 110728372 0 1785696256 4.4521002769 3.2252779007 3.6059508324 1033 41.2800000000 0.7888878584 0.3361394703 0.8328990340 0.0432201771 5.1088990000 1.2790610000 0.4307070000 0.1502660000 1.6025340000 1.6396370000 110730046 0 1787203584 4.4620079994 3.2274441719 3.6107966900 1034 41.3200000000 0.7878745794 0.3365763514 0.8328990340 0.0432012285 3.2885110000 1.2849710000 0.3847830000 0.0000050000 1.6043840000 0.0076890000 110731720 0 1784950784 4.4720931053 3.2288448811 3.6158859730 1035 41.3600000000 0.7872563601 0.3370117911 0.8328990340 0.0431828221 3.4345080000 1.2735850000 0.3848590000 0.1491360000 1.6127700000 0.0077290000 110733394 0 1786441728 4.4781918526 3.2297677994 3.6199712753 1036 41.4000000000 0.7867196202 0.3374458720 0.8328990340 0.0431626518 3.3231560000 1.2735870000 0.4244480000 0.0000040000 1.6106920000 0.0076390000 110735068 0 1785696256 4.4846200943 3.2279019356 3.6229557991 1037 41.4400000000 0.7864430547 0.3378788490 0.8328990340 0.0431423126 5.0249150000 1.2822620000 0.3378190000 0.1489270000 1.6070050000 1.6424090000 110736742 0 1787330560 4.4941711426 3.2278604507 3.6271069050 1038 41.4800000000 0.7849298716 0.3383095340 0.8328990340 0.0431219341 3.3294060000 1.2780300000 0.4253280000 0.0000040000 1.6117460000 0.0076910000 110738416 0 1784934400 4.5035223961 3.2306928635 3.6316239834 1039 41.5200000000 0.7839315534 0.3387384291 0.8328990340 0.0431014433 3.5186840000 1.2737220000 0.4657160000 0.1495020000 1.6155400000 0.0077250000 110740090 0 1786576896 4.5127735138 3.2330262661 3.6352314949 1040 41.5600000000 0.7829363346 0.3391655425 0.8328990340 0.0430809710 3.2844790000 1.2754900000 0.3809120000 0.0000040000 1.6138190000 0.0076970000 110741764 0 1785831424 4.5201969147 3.2365834713 3.6395320892 1041 41.6000000000 0.7829333544 0.3395918324 0.8328990340 0.0430605324 5.0913450000 1.2816400000 0.3794780000 0.1489910000 1.6205870000 1.6540810000 110743438 0 1787330560 4.5275349617 3.2366652489 3.6410415173 1042 41.6400000000 0.7818226814 0.3400162382 0.8328990340 0.0430407895 3.2562420000 1.2803110000 0.3381480000 0.0000040000 1.6233920000 0.0076620000 110745112 0 1784967168 4.5376491547 3.2397785187 3.6468112469 1043 41.6800000000 0.7808417678 0.3404388897 0.8328990340 0.0430230618 3.4097830000 1.2743420000 0.3370820000 0.1492260000 1.6348910000 0.0076460000 110746786 0 1786695680 4.5438146591 3.2419333458 3.6513450146 1044 41.7200000000 0.7800118327 0.3408599366 0.8328990340 0.0430135366 3.2628180000 1.2701470000 0.3403840000 0.0000040000 1.6379770000 0.0076850000 110748460 0 1785569280 4.5574784279 3.2432539463 3.6559848785 1045 41.7600000000 0.7792764902 0.3412794740 0.8328990340 0.0429962800 5.0911240000 1.2803360000 0.3373780000 0.1494990000 1.6411670000 1.6760490000 110750134 0 1787076608 4.5647687912 3.2441759109 3.6595513821 1046 41.8000000000 0.7779839635 0.3416969735 0.8328990340 0.0429774499 3.2760300000 1.2826070000 0.3348720000 0.0000040000 1.6442380000 0.0077030000 110751808 0 1784823808 4.5701365471 3.2468581200 3.6660017967 1047 41.8400000000 0.7777301669 0.3421134331 0.8328990340 0.0429572985 3.4236500000 1.2740790000 0.3354010000 0.1496370000 1.6501160000 0.0076980000 110753482 0 1786314752 4.5769219398 3.2469537258 3.6685461998 1048 41.8800000000 0.7767521143 0.3425281647 0.8328990340 0.0429372657 3.2670550000 1.2708600000 0.3345000000 0.0000040000 1.6472760000 0.0076530000 110755156 0 1785679872 4.5849223137 3.2488744259 3.6748971939 1049 41.9200000000 0.7759600878 0.3429413505 0.8328990340 0.0429173651 5.1109670000 1.2817380000 0.3333060000 0.1494770000 1.6526220000 1.6872510000 110756830 0 1787338752 4.5920815468 3.2498438358 3.6787984371 1050 41.9600000000 0.7755558491 0.3433533643 0.8328990340 0.0428970800 3.4105190000 1.2800590000 0.4599690000 0.0000040000 1.6561850000 0.0076810000 110758504 0 1785204736 4.5980591774 3.2506005764 3.6813356876 1051 42.0000000000 0.7747809887 0.3437638568 0.8328990340 0.0428768558 3.4806520000 1.2769630000 0.3815650000 0.1504180000 1.6574450000 0.0076890000 110760178 0 1786695680 4.6057953835 3.2504422665 3.6845223904 1052 42.0400000000 0.7739877701 0.3441728149 0.8328990340 0.0428567529 3.4610830000 1.2735950000 0.5031130000 0.0000040000 1.6700540000 0.0076820000 110761852 0 1784696832 4.6125478745 3.2528243065 3.6904163361 1053 42.0800000000 0.7729419470 0.3445800030 0.8328990340 0.0428365618 5.1820710000 1.2781420000 0.3738530000 0.1501920000 1.6644420000 1.7088360000 110763526 0 1786187776 4.6186237335 3.2549512386 3.6931302547 1054 42.1200000000 0.7725819349 0.3449860770 0.8328990340 0.0428165113 3.2955990000 1.2762470000 0.3329940000 0.0000040000 1.6719260000 0.0077010000 110765200 0 1785569280 4.6249060631 3.2561032772 3.6986517906 1055 42.1600000000 0.7710069418 0.3453898882 0.8328990340 0.0427968866 3.4484130000 1.2779800000 0.3300480000 0.1507700000 1.6752660000 0.0077380000 110766874 0 1786949632 4.6367564201 3.2574899197 3.7053782940 1056 42.2000000000 0.7705367804 0.3457924894 0.8328990340 0.0427767871 3.3930970000 1.2760050000 0.4164410000 0.0000050000 1.6861340000 0.0076870000 110768548 0 1785061376 4.6432423592 3.2584080696 3.7104907036 1057 42.2400000000 0.7694008350 0.3461932542 0.8328990340 0.0427566808 5.2013630000 1.2737040000 0.3701470000 0.1500510000 1.6786380000 1.7221740000 110770222 0 1786695680 4.6493721008 3.2600185871 3.7158117294 1058 42.2800000000 0.7682129741 0.3465921386 0.8328990340 0.0427368098 3.4725970000 1.2753120000 0.5000760000 0.0000040000 1.6827660000 0.0076510000 110771896 0 1784721408 4.6556253433 3.2626929283 3.7231020927 1059 42.3200000000 0.7670406699 0.3469891627 0.8328990340 0.0427169877 3.6363330000 1.2857690000 0.4998850000 0.1505910000 1.6857420000 0.0077370000 110773570 0 1786322944 4.6599779129 3.2659730911 3.7271556854 1060 42.3600000000 0.7668315768 0.3473852405 0.8328990340 0.0426973514 3.3951250000 1.2707260000 0.4146580000 0.0000050000 1.6953020000 0.0076790000 110775244 0 1787998208 4.6645340919 3.2677378654 3.7334656715 1061 42.4000000000 0.7656313181 0.3477794404 0.8328990340 0.0426774655 5.3153520000 1.2754070000 0.4566940000 0.1502300000 1.6967620000 1.7295800000 110776918 0 1785188352 4.6697182655 3.2698366642 3.7379426956 1062 42.4400000000 0.7648536563 0.3481721656 0.8328990340 0.0426578352 3.4091360000 1.2803020000 0.4129540000 0.0000050000 1.7014690000 0.0076860000 110778592 0 1786728448 4.6745781898 3.2721788883 3.7444558144 1063 42.4800000000 0.7638303041 0.3485631893 0.8328990340 0.0426388309 3.5070600000 1.2737370000 0.3707290000 0.1502660000 1.6978000000 0.0077290000 110780266 0 1784934400 4.6802110672 3.2742791176 3.7503960133 1064 42.5200000000 0.7631255984 0.3489528156 0.8328990340 0.0426199822 3.4089810000 1.2775840000 0.4147300000 0.0000050000 1.7021430000 0.0076910000 110781940 0 1786331136 4.6851167679 3.2756991386 3.7560648918 1065 42.5600000000 0.7627886534 0.3493413938 0.8328990340 0.0426005806 5.2511890000 1.2766180000 0.3707690000 0.1502530000 1.7094620000 1.7374230000 110783614 0 1785552896 4.6891851425 3.2772660255 3.7612524033 1066 42.6000000000 0.7614595294 0.3497279962 0.8328990340 0.0425809306 3.4516780000 1.2715850000 0.4530720000 0.0000040000 1.7125600000 0.0077010000 110785288 0 1787219968 4.6937336922 3.2801327705 3.7667448521 1067 42.6400000000 0.7611366510 0.3501135713 0.8328990340 0.0425616256 3.5170010000 1.2728920000 0.3709180000 0.1503770000 1.7083650000 0.0076500000 110786962 0 1785323520 4.6983304024 3.2815186977 3.7718863487 1068 42.6800000000 0.7602102160 0.3504975570 0.8328990340 0.0425419463 3.4184700000 1.2799360000 0.4130470000 0.0000050000 1.7109760000 0.0077800000 110788636 0 1786720256 4.7010660172 3.2841260433 3.7771260738 1069 42.7200000000 0.7589585781 0.3508796533 0.8328990340 0.0425230044 5.3967740000 1.2721900000 0.4994460000 0.1501760000 1.7209550000 1.7471890000 110790310 0 1784791040 4.7080588341 3.2884042263 3.7835063934 1070 42.7600000000 0.7572546005 0.3512594430 0.8328990340 0.0425055518 3.4318810000 1.2741390000 0.4171640000 0.0000040000 1.7261300000 0.0076860000 110791984 0 1786331136 4.7135682106 3.2941310406 3.7894787788 1071 42.8000000000 0.7572361827 0.3516385063 0.8328990340 0.0424880912 3.4550910000 1.2737920000 0.2853230000 0.1502140000 1.7312350000 0.0077840000 110793658 0 1785933824 4.7184395790 3.2972373962 3.7988026142 1072 42.8400000000 0.7550473213 0.3520148204 0.8328990340 0.0424683230 3.5212390000 1.2715620000 0.5092720000 0.0000050000 1.7258210000 0.0076870000 110795332 0 1787363328 4.7234897614 3.3012712002 3.8035168648 1073 42.8800000000 0.7540508509 0.3523895045 0.8328990340 0.0424490930 5.3029090000 1.2722270000 0.3809990000 0.1498160000 1.7298890000 1.7632310000 110797006 0 1785188352 4.7260527611 3.3035480976 3.8109600544 1074 42.9200000000 0.7529733777 0.3527624877 0.8328990340 0.0424297158 3.3595380000 1.2792380000 0.3333660000 0.0000040000 1.7323310000 0.0076870000 110798680 0 1786585088 4.7319345474 3.3071477413 3.8174288273 1075 42.9600000000 0.7508081198 0.3531327627 0.8328990340 0.0424102520 3.5520930000 1.2764020000 0.3735040000 0.1499600000 1.7376740000 0.0077310000 110800354 0 1785823232 4.7359762192 3.3113410473 3.8242702484 1076 43.0000000000 0.7498703599 0.3535014779 0.8328990340 0.0423912753 3.5240390000 1.2721090000 0.5027030000 0.0000050000 1.7345160000 0.0078240000 110802028 0 1787514880 4.7400374413 3.3154366016 3.8295490742 1077 43.0400000000 0.7505685091 0.3538701567 0.8328990340 0.0423725202 5.3977500000 1.2787410000 0.4599390000 0.1493800000 1.7357600000 1.7670890000 110803702 0 1785180160 4.7457699776 3.3175301552 3.8365991116 1078 43.0800000000 0.7494200468 0.3542370861 0.8328990340 0.0423537412 3.4090800000 1.2797590000 0.3776670000 0.0000040000 1.7368750000 0.0077550000 110805376 0 1786728448 4.7489681244 3.3204262257 3.8413290977 1079 43.1200000000 0.7469764948 0.3546010707 0.8328990340 0.0423346559 3.6555690000 1.2797050000 0.4724440000 0.1497790000 1.7389950000 0.0077660000 110807050 0 1784791040 4.7531309128 3.3236770630 3.8447062969 1080 43.1600000000 0.7462551594 0.3549637134 0.8328990340 0.0423153310 3.5409420000 1.2705860000 0.5073200000 0.0000050000 1.7483560000 0.0078230000 110808724 0 1786314752 4.7586445808 3.3267498016 3.8540589809 1081 43.2000000000 0.7459149957 0.3553253704 0.8328990340 0.0422962302 5.4483450000 1.2768410000 0.5049850000 0.1487960000 1.7374290000 1.7733140000 110810398 0 1788092416 4.7624397278 3.3285226822 3.8622500896 1082 43.2400000000 0.7437252998 0.3556843352 0.8328990340 0.0422768365 3.4570750000 1.2764270000 0.4274720000 0.0000060000 1.7384590000 0.0077520000 110812072 0 1785315328 4.7650594711 3.3325426579 3.8680248260 1083 43.2800000000 0.7440999746 0.3560429831 0.8328990340 0.0422573755 3.5098350000 1.2784890000 0.3297640000 0.1488240000 1.7379780000 0.0077940000 110813746 0 1787092992 4.7699532509 3.3345782757 3.8796093464 1084 43.3200000000 0.7450534105 0.3564018488 0.8328990340 0.0422379766 3.4513180000 1.2731230000 0.4177140000 0.0000040000 1.7456550000 0.0077770000 110815420 0 1784840192 4.7754969597 3.3365004063 3.8914494514 1085 43.3600000000 0.7403559685 0.3567557236 0.8328990340 0.0422192036 5.4547650000 1.2721270000 0.5057420000 0.1480370000 1.7491210000 1.7726750000 110817094 0 1786703872 4.7791838646 3.3422584534 3.8929584026 1086 43.4000000000 0.7398592234 0.3571084892 0.8328990340 0.0421998027 3.5415930000 1.2756230000 0.5005010000 0.0000060000 1.7505910000 0.0078110000 110818768 0 1785458688 4.7833099365 3.3447148800 3.8998022079 1087 43.4400000000 0.7415866256 0.3574621950 0.8328990340 0.0421804260 3.5996190000 1.2741910000 0.4173460000 0.1478840000 1.7453220000 0.0078500000 110820442 0 1786839040 4.7865877151 3.3464136124 3.9111247063 1088 43.4800000000 0.7395711541 0.3578133981 0.8328990340 0.0421611502 3.4178610000 1.2800190000 0.3740270000 0.0000040000 1.7489410000 0.0078070000 110822116 0 1784950784 4.7893810272 3.3487827778 3.9158318043 1089 43.5200000000 0.7387418747 0.3581631946 0.8328990340 0.0421418264 5.4174380000 1.2785130000 0.4514520000 0.1475800000 1.7556150000 1.7772590000 110823790 0 1786822656 4.7933306694 3.3503768444 3.9225447178 1090 43.5600000000 0.7408644557 0.3585142967 0.8328990340 0.0421225580 3.4545440000 1.3041850000 0.3785390000 0.0000040000 1.7569620000 0.0078290000 110825464 0 1785679872 4.7967801094 3.3522467613 3.9355144501 1091 43.6000000000 0.7388454080 0.3588629045 0.8328990340 0.0421037956 3.6962330000 1.2737550000 0.5033320000 0.1473240000 1.7570910000 0.0078550000 110827138 0 1787330560 4.8012304306 3.3550307751 3.9425013065 1092 43.6400000000 0.7370533347 0.3592092328 0.8328990340 0.0420848491 3.5143150000 1.2819210000 0.4601520000 0.0000040000 1.7571080000 0.0080280000 110828812 0 1784680448 4.8040666580 3.3588094711 3.9486286640 1093 43.6800000000 0.7356530428 0.3595536461 0.8328990340 0.0420662560 5.4790040000 1.2733210000 0.5080920000 0.1473890000 1.7591740000 1.7840950000 110830486 0 1786466304 4.8076090813 3.3617398739 3.9571845531 1094 43.7200000000 0.7350866795 0.3598969121 0.8328990340 0.0420474016 3.3856330000 1.2789240000 0.3334260000 0.0000040000 1.7583400000 0.0079470000 110832160 0 1785466880 4.8087100983 3.3654897213 3.9648354053 1095 43.7600000000 0.7319588661 0.3602366948 0.8328990340 0.0420284100 3.7109790000 1.2742370000 0.5065900000 0.1469250000 1.7680940000 0.0078780000 110833834 0 1786974208 4.8095531464 3.3683543205 3.9681117535 1096 43.8000000000 0.7294031978 0.3605735255 0.8328990340 0.0420093398 3.5494160000 1.2725730000 0.5007140000 0.0000040000 1.7611540000 0.0079750000 110835508 0 1785077760 4.8125910759 3.3720705509 3.9737203121 1097 43.8400000000 0.7283887863 0.3609088174 0.8328990340 0.0419903930 5.4063890000 1.2780970000 0.4150920000 0.1465860000 1.7641160000 1.7955270000 110837182 0 1786585088 4.8159761429 3.3753526211 3.9837839603 1098 43.8800000000 0.7265442014 0.3612418187 0.8328990340 0.0419731451 3.5525030000 1.2734380000 0.4991010000 0.0000040000 1.7649830000 0.0079170000 110838856 0 1784569856 4.8204336166 3.3779861927 3.9934267998 1099 43.9200000000 0.7275828719 0.3615751591 0.8328990340 0.0419557254 3.7041430000 1.2773970000 0.5004210000 0.1468360000 1.7645470000 0.0080110000 110840530 0 1786314752 4.8213782310 3.3796429634 4.0015563965 1100 43.9600000000 0.7274342179 0.3619077582 0.8328990340 0.0419369586 3.4328260000 1.2747830000 0.3706280000 0.0000040000 1.7722680000 0.0080240000 110842204 0 1787854848 4.8218507767 3.3821349144 4.0088663101 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 10:46:06 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188253 0.0606188253 0.0606188253 nan 2.4481420000 0.9090340000 0.0545170000 0.1159810000 0.0000090000 1.3670420000 106428375 0 1770766336 4.0000000000 4.0000000000 4.0000000000 2 1305031229.5644419193 0.0642096773 0.0624142513 0.0642096773 0.1658526063 1.1084880000 0.9439950000 0.0412580000 0.1158940000 0.0000020000 0.0069170000 109177604 0 1769758720 4.0000000000 4.0000000000 4.0000000000 3 1305031229.5966169834 0.0662607327 0.0636964117 0.0662607327 0.1252030593 1.0645200000 0.9006010000 0.0409200000 0.1157480000 0.0000030000 0.0068490000 109180114 0 1771155456 4.0000000000 4.0000000000 4.0000000000 4 1305031229.6287899017 0.0688454211 0.0649836641 0.0688454211 0.1129914361 2.3629920000 0.9073660000 0.0413810000 0.1159180000 1.2910160000 0.0070620000 109182596 0 1780297728 4.0000000000 4.0000000000 4.0000000000 5 1305031229.6646571159 0.0660009906 0.0651871294 0.0688454211 0.1146828825 3.7148890000 0.9026260000 0.3995230000 0.1174240000 1.1337820000 1.1612500000 109185134 0 1782329344 3.9731409550 4.0052924156 4.0138816833 6 1305031229.6968429089 0.0563660786 0.0637169542 0.0688454211 0.1026617663 2.4915210000 0.9134420000 0.4004200000 0.0000030000 1.1702760000 0.0071120000 109188008 0 1783963648 3.9885725975 3.9999763966 4.0209732056 7 1305031229.7290771008 0.0504580960 0.0618228316 0.0688454211 0.0944324161 2.4714010000 0.9234080000 0.4044470000 0.1167890000 1.0192640000 0.0071430000 109190162 0 1785741312 3.9916918278 4.0025815964 4.0272111893 8 1305031229.7648689747 0.0483699813 0.0601412253 0.0688454211 0.0875849680 2.2741710000 0.9314440000 0.2700540000 0.0000030000 1.0651150000 0.0072780000 109192412 0 1787392000 3.9982845783 3.9968996048 4.0331091881 9 1305031229.7969229221 0.0485966839 0.0588584985 0.0688454211 0.0820246057 3.3347450000 0.9509700000 0.4057280000 0.1179070000 0.9057110000 0.9541260000 109195238 0 1784725504 3.9983441830 3.9944641590 4.0363526344 10 1305031229.8256299496 0.0431757681 0.0572902255 0.0688454211 0.0773875145 2.1603850000 0.9411170000 0.2416460000 0.0000030000 0.9700430000 0.0072730000 109198672 0 1786122240 4.0013890266 3.9980561733 4.0419950485 11 1305031229.8630619049 0.0423466638 0.0559317199 0.0688454211 0.0737733632 2.3656750000 0.9989070000 0.4088290000 0.1200680000 0.8302030000 0.0073690000 109200986 0 1787899904 4.0051550865 3.9987044334 4.0450439453 12 1305031229.8969380856 0.0430087671 0.0548548071 0.0688454211 0.0708056168 2.0954290000 0.9771670000 0.2089370000 0.0000060000 0.9016430000 0.0073600000 109203172 0 1784598528 4.0110373497 4.0005750656 4.0481500626 13 1305031229.9262549877 0.0434661098 0.0539787535 0.0688454211 0.0678461132 3.1721980000 0.9842680000 0.4142880000 0.1223510000 0.7922990000 0.8586590000 109205326 0 1785995264 4.0163807869 4.0022959709 4.0533380508 14 1305031229.9662408829 0.0455673262 0.0533779373 0.0688454211 0.0652208650 2.3042090000 0.9817560000 0.4260240000 0.0000050000 0.8887230000 0.0073930000 109207640 0 1788035072 4.0200529099 4.0031991005 4.0585145950 15 1305031229.9979310036 0.0476748757 0.0529977332 0.0688454211 0.0632078279 2.1888840000 0.9798540000 0.3114120000 0.1239810000 0.7659130000 0.0074020000 109209794 0 1784479744 4.0226144791 4.0032200813 4.0627489090 16 1305031230.0300021172 0.0505405031 0.0528441563 0.0688454211 0.0611116775 2.2402450000 0.9747410000 0.4279820000 0.0000040000 0.8298350000 0.0073430000 109211980 0 1785876480 4.0252823830 4.0038352013 4.0670242310 17 1305031230.0656960011 0.0552398823 0.0529850813 0.0688454211 0.0592807765 3.0069880000 0.9726090000 0.3494430000 0.1248320000 0.7470540000 0.8127020000 109215510 0 1787899904 4.0275554657 4.0024290085 4.0702757835 18 1305031230.0982739925 0.0571156740 0.0532145587 0.0688454211 0.0575974812 2.0326660000 0.9721660000 0.2486350000 0.0000030000 0.8042630000 0.0072550000 109220320 0 1784725504 4.0274138451 4.0023121834 4.0726714134 19 1305031230.1299350262 0.0597089007 0.0535563662 0.0688454211 0.0559950801 2.2689570000 0.9749000000 0.4212780000 0.1254860000 0.7396770000 0.0072650000 109222506 0 1786376192 4.0282998085 4.0031056404 4.0757756233 20 1305031230.1657800674 0.0646792650 0.0541125111 0.0688454211 0.0545690767 2.1978350000 0.9840140000 0.4317410000 0.0000030000 0.7743820000 0.0073350000 109224756 0 1788153856 4.0298671722 4.0024428368 4.0791015625 21 1305031230.1977820396 0.0679935664 0.0547735138 0.0688454211 0.0532461929 2.9515710000 0.9888580000 0.3175430000 0.1261530000 0.7285770000 0.7900740000 109226942 0 1785106432 4.0303006172 4.0010695457 4.0815205574 22 1305031230.2298529148 0.0680308193 0.0553761186 0.0688454211 0.0520177736 2.1786210000 0.9729500000 0.4309990000 0.0000030000 0.7669040000 0.0074030000 109229128 0 1786503168 4.0269823074 4.0007295609 4.0821390152 23 1305031230.2655899525 0.0682528242 0.0559359753 0.0688454211 0.0509023660 2.2693280000 0.9967210000 0.3935990000 0.1271270000 0.7441080000 0.0074120000 109231378 0 1785614336 4.0229816437 3.9992043972 4.0824165344 24 1305031230.2979929447 0.0692197308 0.0564894651 0.0692197308 0.0497987258 2.0996180000 0.9806620000 0.3252970000 0.0000040000 0.7858870000 0.0074070000 109233564 0 1787011072 4.0208272934 3.9994969368 4.0840935707 25 1305031230.3351120949 0.0718950778 0.0571056896 0.0718950778 0.0487962705 3.1140130000 0.9922440000 0.3565870000 0.1280370000 0.7815980000 0.8551660000 109235846 0 1784725504 4.0190200806 3.9967234135 4.0856904984 26 1305031230.3656799793 0.0700170323 0.0576022797 0.0718950778 0.0478359869 2.2503040000 0.9927070000 0.4381920000 0.0000040000 0.8115650000 0.0074360000 109238000 0 1786249216 4.0146636963 3.9976353645 4.0862083435 27 1305031230.3973290920 0.0693284497 0.0580365823 0.0718950778 0.0469100171 2.3830300000 1.0352070000 0.3951870000 0.1278550000 0.8169370000 0.0074410000 109240218 0 1788153856 4.0104990005 3.9964916706 4.0877747536 28 1305031230.4368140697 0.0725219548 0.0585539171 0.0725219548 0.0465487219 2.2841490000 0.9854910000 0.4387100000 0.0000040000 0.8521770000 0.0073750000 109242500 0 1785004032 4.0091047287 3.9956612587 4.0906915665 29 1305031230.4653120041 0.0704984516 0.0589657976 0.0725219548 0.0458260630 3.1794650000 0.9882490000 0.2851820000 0.1285040000 0.8608620000 0.9162460000 109244622 0 1786511360 4.0008912086 3.9912579060 4.0885863304 30 1305031230.4972999096 0.0672340915 0.0592414074 0.0725219548 0.0450827470 2.2068510000 0.9912430000 0.2911330000 0.0000030000 0.9165690000 0.0075060000 109246840 0 1785360384 3.9915728569 3.9890182018 4.0858449936 31 1305031230.5301918983 0.0661993772 0.0594658580 0.0725219548 0.0443580984 2.4929000000 0.9985690000 0.4208260000 0.1281930000 0.9375370000 0.0073690000 109248994 0 1786884096 3.9839267731 3.9854371548 4.0843529701 32 1305031230.5661149025 0.0672308952 0.0597085154 0.0725219548 0.0440596886 2.3243670000 0.9989850000 0.3245450000 0.0000030000 0.9930090000 0.0074240000 109251276 0 1784725504 3.9769978523 3.9823527336 4.0850973129 33 1305031230.5988430977 0.0647715777 0.0598619415 0.0725219548 0.0433980444 3.6133950000 1.0028030000 0.4162680000 0.1265530000 1.0131280000 1.0542020000 109256022 0 1786122240 3.9668979645 3.9797532558 4.0820484161 34 1305031230.6319139004 0.0626429319 0.0599437354 0.0725219548 0.0428705034 2.3775820000 0.9803820000 0.3176430000 0.0000030000 1.0718100000 0.0073190000 109263488 0 1787899904 3.9532177448 3.9748387337 4.0805039406 35 1305031230.6660470963 0.0582885966 0.0598964457 0.0725219548 0.0423572619 2.5950180000 0.9617730000 0.4044110000 0.1266260000 1.0945050000 0.0072560000 109265706 0 1784852480 3.9399368763 3.9758005142 4.0765290260 36 1305031230.6979451180 0.0602404587 0.0599060016 0.0725219548 0.0418108931 2.3502290000 0.9587070000 0.2379920000 0.0000040000 1.1459560000 0.0071240000 109267860 0 1786376192 3.9316365719 3.9710834026 4.0788712502 37 1305031230.7336409092 0.0608481355 0.0599314647 0.0725219548 0.0414436737 3.8271120000 0.9543170000 0.3930270000 0.1246880000 1.1619660000 1.1926530000 109270078 0 1785741312 3.9235775471 3.9693584442 4.0755014420 38 1305031230.7659239769 0.0649072379 0.0600624061 0.0725219548 0.0408977137 2.5703650000 0.9596840000 0.3959140000 0.0000020000 1.2071720000 0.0071500000 109272296 0 1787011072 3.9147830009 3.9637444019 4.0738596916 39 1305031230.7973229885 0.0690710917 0.0602933980 0.0725219548 0.0404164029 2.6034640000 0.9433350000 0.2873460000 0.1243440000 1.2409280000 0.0070620000 109274482 0 1784471552 3.9065630436 3.9583132267 4.0711636543 40 1305031230.8317570686 0.0749419928 0.0606596129 0.0749419928 0.0399384296 2.6746840000 0.9903360000 0.3885520000 0.0000030000 1.2882050000 0.0071240000 109276700 0 1786122240 3.8970949650 3.9516031742 4.0700778961 41 1305031230.8655419350 0.0765458494 0.0610470821 0.0765458494 0.0396842026 4.0049450000 0.9400390000 0.2504370000 0.1243140000 1.3286850000 1.3609800000 109278886 0 1788035072 3.8880987167 3.9491767883 4.0701293945 42 1305031230.8973939419 0.0843636543 0.0616022386 0.0843636543 0.0392720462 2.7124050000 0.9424130000 0.3803630000 0.0000030000 1.3819100000 0.0070770000 109281104 0 1784987648 3.8805048466 3.9413206577 4.0767660141 43 1305031230.9373099804 0.1041208804 0.0625910442 0.1041208804 0.0394639969 2.8673910000 0.9273430000 0.3811950000 0.1244880000 1.4267710000 0.0071050000 109283386 0 1786630144 3.8625977039 3.9255459309 4.0899190903 44 1305031230.9650349617 0.1131963581 0.0637411650 0.1131963581 0.0396666571 2.7770340000 0.9656160000 0.3495420000 0.0000030000 1.4543420000 0.0070350000 109285508 0 1785741312 3.8538897038 3.9240691662 4.1106057167 45 1305031230.9971239567 0.1246432438 0.0650945445 0.1246432438 0.0395961004 4.3690030000 0.9193300000 0.3690610000 0.1251660000 1.4637070000 1.4912380000 109287726 0 1787265024 3.8470995426 3.9217536449 4.1293635368 46 1305031231.0367500782 0.1309673339 0.0665265617 0.1309673339 0.0392952790 2.7337390000 0.8809400000 0.3712910000 0.0000030000 1.4741280000 0.0068680000 109290008 0 1784725504 3.8432614803 3.9203910828 4.1384291649 47 1305031231.0644741058 0.1294130534 0.0678645721 0.1309673339 0.0388867583 2.8419440000 0.8691770000 0.3665300000 0.1245470000 1.4742960000 0.0068840000 109292098 0 1786249216 3.8420255184 3.9223144054 4.1382036209 48 1305031231.0967879295 0.1218401268 0.0689890628 0.1309673339 0.0384877059 2.6069110000 0.8776150000 0.2519220000 0.0000030000 1.4699550000 0.0068140000 109294316 0 1788289024 3.8433136940 3.9294962883 4.1356616020 49 1305031231.1347110271 0.1261243224 0.0701550885 0.1309673339 0.0380926965 4.3327710000 0.8685910000 0.3696860000 0.1246560000 1.4674720000 1.5018460000 109296566 0 1784598528 3.8438766003 3.9250044823 4.1388072968 50 1305031231.1652760506 0.1281107515 0.0713142018 0.1309673339 0.0377543219 2.7282370000 0.8877010000 0.3694290000 0.0000030000 1.4637010000 0.0068760000 109298752 0 1786122240 3.8444130421 3.9239008427 4.1416110992 51 1305031231.1977710724 0.1144766361 0.0721605240 0.1309673339 0.0374706782 2.8945690000 0.9265710000 0.3858930000 0.1252830000 1.4492950000 0.0070060000 109300970 0 1788026880 3.8489649296 3.9348893166 4.1350703239 52 1305031231.2344679832 0.1091644093 0.0728721372 0.1309673339 0.0376588640 2.6556360000 0.9356170000 0.2929390000 0.0000020000 1.4194910000 0.0070650000 109303220 0 1784987648 3.8561203480 3.9331769943 4.1259942055 53 1305031231.2656350136 0.0881408527 0.0731602262 0.1309673339 0.0374722771 4.1596040000 0.9493800000 0.2973540000 0.1241490000 1.3808540000 1.4073230000 109305374 0 1786384384 3.8629484177 3.9476885796 4.1051754951 54 1305031231.2978610992 0.0730153844 0.0731575439 0.1309673339 0.0374146105 2.5992600000 0.9585390000 0.3078820000 0.0000020000 1.3251890000 0.0071160000 109307592 0 1785360384 3.8672945499 3.9632341862 4.0783653259 55 1305031231.3351519108 0.0651802793 0.0730125028 0.1309673339 0.0373470721 2.5793820000 0.9501510000 0.2333620000 0.1236640000 1.2645680000 0.0071090000 109309842 0 1786757120 3.8777532578 3.9753012657 4.0661864281 56 1305031231.3650770187 0.0593404509 0.0727683590 0.1309673339 0.0370812716 2.5462840000 0.9630890000 0.3710030000 0.0000030000 1.2044870000 0.0071600000 109311996 0 1784979456 3.8857891560 3.9851386547 4.0620183945 57 1305031231.3973300457 0.0521850958 0.0724072491 0.1309673339 0.0367887668 3.8123530000 0.9530510000 0.4118960000 0.1240390000 1.1431850000 1.1796190000 109314214 0 1786249216 3.8971030712 3.9903032780 4.0661525726 58 1305031231.4368579388 0.0469461940 0.0719682654 0.1309673339 0.0365456139 2.3626740000 0.9570520000 0.3171160000 0.0000030000 1.0807930000 0.0071400000 109316496 0 1788153856 3.9111680984 3.9886300564 4.0800442696 59 1305031231.4649889469 0.0454037227 0.0715180189 0.1309673339 0.0362911808 2.5015700000 0.9764750000 0.3579220000 0.1248720000 1.0345200000 0.0072130000 109318618 0 1784725504 3.9192624092 3.9904017448 4.0828542709 60 1305031231.4992439747 0.0405568704 0.0710019998 0.1309673339 0.0360817737 2.3958500000 0.9811930000 0.3986970000 0.0000040000 1.0081500000 0.0072280000 109320804 0 1786122240 3.9296698570 3.9982309341 4.0825929642 61 1305031231.5331959724 0.0387300365 0.0704729512 0.1309673339 0.0358404886 3.4969650000 0.9895450000 0.4379220000 0.1256660000 0.9595470000 0.9837090000 109323086 0 1788026880 3.9374113083 4.0022048950 4.0852489471 62 1305031231.5650680065 0.0377612896 0.0699453437 0.1309673339 0.0356324653 2.3784030000 0.9961240000 0.4420730000 0.0000050000 0.9322260000 0.0073880000 109325240 0 1784725504 3.9465401173 4.0050568581 4.0914616585 63 1305031231.6013169289 0.0357287228 0.0694022228 0.1309673339 0.0353526265 2.4781390000 1.0013140000 0.4497900000 0.1267750000 0.8923190000 0.0073720000 109327490 0 1786122240 3.9510357380 4.0101161003 4.0925664902 64 1305031231.6331589222 0.0353531390 0.0688702058 0.1309673339 0.0351423040 2.2866930000 1.0018880000 0.4099390000 0.0000040000 0.8668640000 0.0074020000 109329708 0 1788026880 3.9560866356 4.0131030083 4.0944361687 65 1305031231.6650550365 0.0368341431 0.0683773433 0.1309673339 0.0348750042 3.1790390000 0.9962700000 0.3702940000 0.1322420000 0.8245650000 0.8543050000 109336982 0 1784606720 3.9644742012 4.0163698196 4.0982098579 66 1305031231.7035079002 0.0374214388 0.0679083145 0.1309673339 0.0348071509 2.1756390000 0.9979630000 0.3737360000 0.0000040000 0.7958790000 0.0074450000 109349792 0 1786130432 3.9683079720 4.0168910027 4.1011648178 67 1305031231.7339379787 0.0372299105 0.0674504279 0.1309673339 0.0346468967 2.1918100000 0.9959940000 0.3021110000 0.1266490000 0.7590000000 0.0074530000 109351914 0 1787908096 3.9708902836 4.0179023743 4.1018300056 68 1305031231.7655088902 0.0375987589 0.0670114327 0.1309673339 0.0344449598 2.0704180000 0.9921100000 0.3376420000 0.0000050000 0.7325530000 0.0073620000 109354100 0 1784852480 3.9747614861 4.0195236206 4.1035180092 69 1305031231.8011910915 0.0409265943 0.0666333916 0.1309673339 0.0342178854 2.7766600000 0.9956690000 0.2620590000 0.1261760000 0.6846320000 0.7074840000 109356350 0 1786249216 3.9796752930 4.0179653168 4.1039013863 70 1305031231.8332920074 0.0407982469 0.0662643181 0.1309673339 0.0341671595 1.9477360000 0.9937100000 0.2987150000 0.0000040000 0.6473440000 0.0073370000 109358536 0 1788153856 3.9799957275 4.0168442726 4.1001005173 71 1305031231.8649590015 0.0412265100 0.0659116729 0.1309673339 0.0339642892 2.1718220000 0.9850830000 0.4534620000 0.1255090000 0.5996810000 0.0074690000 109360722 0 1784725504 3.9811105728 4.0162148476 4.0958304405 72 1305031231.9012699127 0.0461223125 0.0656368207 0.1309673339 0.0340273151 1.9327590000 0.9949730000 0.3796860000 0.0000040000 0.5500510000 0.0074000000 109362972 0 1786122240 3.9722290039 4.0085601807 4.0855531693 73 1305031231.9330461025 0.0496264584 0.0654175006 0.1309673339 0.0338582690 2.6356560000 0.9930590000 0.4585420000 0.1245380000 0.5167650000 0.5421140000 109365158 0 1788153856 3.9777433872 4.0058536530 4.0843987465 74 1305031231.9650299549 0.0507837795 0.0652197477 0.1309673339 0.0336472183 1.9702680000 0.9965010000 0.4539070000 0.0000050000 0.5118960000 0.0072990000 109367344 0 1784725504 3.9768879414 4.0051021576 4.0803084373 75 1305031232.0007200241 0.0515631810 0.0650376601 0.1309673339 0.0335607669 2.0654750000 0.9795980000 0.4449250000 0.1234680000 0.5094860000 0.0073640000 109369594 0 1786122240 3.9763031006 4.0051622391 4.0772743225 76 1305031232.0332028866 0.0539408624 0.0648916496 0.1309673339 0.0334575049 1.9596690000 0.9822970000 0.4497640000 0.0000040000 0.5195180000 0.0072980000 109371812 0 1788026880 3.9741301537 4.0032434464 4.0729532242 77 1305031232.0651450157 0.0564413220 0.0647819051 0.1309673339 0.0332803352 2.6209990000 0.9812530000 0.4450380000 0.1224210000 0.5239790000 0.5476310000 109373966 0 1784725504 3.9704596996 4.0026969910 4.0679774284 78 1305031232.1007990837 0.0592935570 0.0647115417 0.1309673339 0.0331458236 1.9124910000 0.9828150000 0.3694300000 0.0000050000 0.5522730000 0.0072910000 109376216 0 1786122240 3.9653966427 4.0029702187 4.0627770424 79 1305031232.1328380108 0.0631275550 0.0646914912 0.1309673339 0.0329904991 2.1101480000 0.9800850000 0.4429590000 0.1208030000 0.5582910000 0.0073020000 109378434 0 1787899904 3.9620835781 4.0014405251 4.0585289001 80 1305031232.1650519371 0.0655325726 0.0647020047 0.1309673339 0.0328047093 1.8956520000 0.9815590000 0.3324800000 0.0000040000 0.5735620000 0.0073680000 109380588 0 1784496128 3.9596970081 4.0011782646 4.0547618866 81 1305031232.1992239952 0.0665334314 0.0647246149 0.1309673339 0.0326422661 2.5642760000 0.9766780000 0.2586590000 0.1194960000 0.5935440000 0.6151880000 109382806 0 1786003456 3.9595298767 4.0023207664 4.0515046120 82 1305031232.2364680767 0.0679535717 0.0647639924 0.1309673339 0.0324756072 1.8874600000 0.9711300000 0.2933320000 0.0000040000 0.6149840000 0.0073450000 109385088 0 1787908096 3.9587488174 4.0026330948 4.0482845306 83 1305031232.2626979351 0.0710995868 0.0648403249 0.1309673339 0.0324299718 2.0875040000 0.9605190000 0.3685420000 0.1176280000 0.6327440000 0.0072740000 109387178 0 1784725504 3.9580576420 4.0005073547 4.0453248024 84 1305031232.2980248928 0.0714124590 0.0649185646 0.1309673339 0.0323921310 2.0303350000 0.9373320000 0.4277690000 0.0000050000 0.6572920000 0.0072350000 109389428 0 1786249216 3.9578855038 4.0016694069 4.0424876213 85 1305031232.3321430683 0.0765234828 0.0650550930 0.1309673339 0.0322734705 2.8761510000 0.9352010000 0.4286900000 0.1162410000 0.6905890000 0.7046980000 109391646 0 1785614336 3.9542043209 3.9986059666 4.0386919975 86 1305031232.3647489548 0.0775267333 0.0652001121 0.1309673339 0.0321220186 2.0584680000 0.9154060000 0.4223220000 0.0000040000 0.7128310000 0.0071700000 109393800 0 1787138048 3.9517469406 4.0014915466 4.0352168083 87 1305031232.4008779526 0.0804835185 0.0653757834 0.1309673339 0.0319551861 2.0360730000 0.9067390000 0.2775110000 0.1156540000 0.7283570000 0.0070760000 109396082 0 1784979456 3.9480748177 4.0028009415 4.0315451622 88 1305031232.4331440926 0.0819082409 0.0655636523 0.1309673339 0.0317730321 1.9364800000 0.9075640000 0.2726840000 0.0000040000 0.7484620000 0.0070410000 109398300 0 1786376192 3.9464488029 4.0033440590 4.0289721489 89 1305031232.4647209644 0.0856194869 0.0657889987 0.1309673339 0.0315953211 2.9657700000 0.9073030000 0.4129510000 0.1156430000 0.7550440000 0.7741100000 109400422 0 1785741312 3.9410939217 4.0042824745 4.0260357857 90 1305031232.5015261173 0.0898438841 0.0660562752 0.1309673339 0.0314256572 1.9015280000 0.9032360000 0.2031620000 0.0000040000 0.7873640000 0.0070220000 109402704 0 1787265024 3.9381906986 4.0001277924 4.0233511925 91 1305031232.5324640274 0.0990239158 0.0664185570 0.1309673339 0.0312576734 2.1813020000 0.9117050000 0.3096240000 0.1157780000 0.8362770000 0.0071770000 109404890 0 1785233408 3.9297523499 3.9938156605 4.0196404457 92 1305031232.5647449493 0.1071952581 0.0668617820 0.1309673339 0.0311220182 2.1447540000 0.9055160000 0.3510950000 0.0000040000 0.8802250000 0.0071650000 109407076 0 1786884096 3.9215962887 3.9892942905 4.0161581039 93 1305031232.6003499031 0.1178521737 0.0674100658 0.1309673339 0.0309779569 3.1558440000 0.9041660000 0.3072540000 0.1160140000 0.9013340000 0.9263210000 109409294 0 1784725504 3.9124479294 3.9816710949 4.0125079155 94 1305031232.6294269562 0.1231366917 0.0680029022 0.1309673339 0.0308457562 2.1694330000 0.9230480000 0.2738150000 0.0000040000 0.9647640000 0.0070510000 109411416 0 1786376192 3.9074614048 3.9796414375 4.0087909698 95 1305031232.6647078991 0.1259185672 0.0686125408 0.1309673339 0.0306852229 2.3710990000 0.9558470000 0.3382820000 0.1167920000 0.9521830000 0.0071370000 109413698 0 1785614336 3.9021070004 3.9814004898 4.0058846474 96 1305031232.7005090714 0.1332522780 0.0692858714 0.1332522780 0.0305357528 2.2171330000 0.9246500000 0.2806670000 0.0000040000 1.0038990000 0.0071640000 109415916 0 1787146240 3.8940587044 3.9794874191 4.0023279190 97 1305031232.7327980995 0.1360677630 0.0699743445 0.1360677630 0.0304209731 3.3716180000 0.9170710000 0.3085270000 0.1177530000 0.9905550000 1.0367930000 109418102 0 1784860672 3.8911368847 3.9804017544 3.9986882210 98 1305031232.7684600353 0.1405115277 0.0706941117 0.1405115277 0.0303347808 2.2802410000 0.9363720000 0.2795620000 0.0000040000 1.0563560000 0.0071720000 109420352 0 1786503168 3.8865673542 3.9775609970 3.9964363575 99 1305031232.8045380116 0.1473014951 0.0714679237 0.1473014951 0.0301968452 2.4136440000 0.9258330000 0.3096790000 0.1193070000 1.0509230000 0.0071180000 109422602 0 1785741312 3.8795454502 3.9729225636 3.9933907986 100 1305031232.8346450329 0.1510812193 0.0722640566 0.1510812193 0.0300862006 2.3441450000 0.9214180000 0.3106130000 0.0000050000 1.1041750000 0.0071520000 109424756 0 1787392000 3.8743705750 3.9747650623 3.9896814823 101 1305031232.8685569763 0.1543062478 0.0730763555 0.1543062478 0.0299732645 3.5972230000 0.9072250000 0.2701050000 0.1206280000 1.0978670000 1.2005960000 109427006 0 1784852480 3.8701510429 3.9747304916 3.9868130684 102 1305031232.9041829109 0.1578883231 0.0739078454 0.1578883231 0.0298542423 2.3232580000 0.9054850000 0.2731110000 0.0000040000 1.1367330000 0.0071280000 109429224 0 1786503168 3.8651990891 3.9744126797 3.9844455719 103 1305031232.9330000877 0.1593457907 0.0747373400 0.1593457907 0.0297532942 2.5507630000 0.8864880000 0.4059630000 0.1213930000 1.1290310000 0.0070420000 109431346 0 1784852480 3.8630549908 3.9767935276 3.9822247028 104 1305031232.9683640003 0.1582161933 0.0755400213 0.1593457907 0.0296088609 2.3598150000 0.8784770000 0.3400330000 0.0000050000 1.1333310000 0.0071540000 109433628 0 1786376192 3.8637249470 3.9771685600 3.9805421829 105 1305031233.0011510849 0.1548928320 0.0762957624 0.1593457907 0.0295111024 3.7030440000 0.8933090000 0.3114850000 0.1216370000 1.1281530000 1.2476530000 109435814 0 1785487360 3.8655123711 3.9830818176 3.9795215130 106 1305031233.0330219269 0.1525190622 0.0770148501 0.1593457907 0.0296740660 2.3139790000 0.9066430000 0.2887960000 0.0000030000 1.1106510000 0.0070670000 109438000 0 1787265024 3.8635301590 3.9889645576 3.9824445248 107 1305031233.0688428879 0.1465753466 0.0776649482 0.1593457907 0.0298148097 2.3599760000 0.9165910000 0.2809200000 0.1201480000 1.0343280000 0.0071710000 109440186 0 1785106432 3.8675603867 3.9923093319 3.9838206768 108 1305031233.1004469395 0.1358390301 0.0782035971 0.1593457907 0.0297643560 2.1936800000 0.9159380000 0.2856690000 0.0000030000 0.9841170000 0.0071340000 109442340 0 1786630144 3.8750977516 4.0035796165 3.9881043434 109 1305031233.1328918934 0.1286979318 0.0786668479 0.1593457907 0.0301091548 3.2023290000 0.9142230000 0.2736740000 0.1178120000 0.9324570000 0.9633290000 109444526 0 1784733696 3.8849406242 3.9985446930 3.9898192883 110 1305031233.1684799194 0.1171746254 0.0790169186 0.1593457907 0.0301042311 2.1484170000 0.8979500000 0.3452180000 0.0000040000 0.8973810000 0.0070310000 109446776 0 1786257408 3.9010331631 4.0020670891 3.9902410507 111 1305031233.2006340027 0.1138460934 0.0793306949 0.1593457907 0.0300084097 2.1060370000 0.9097170000 0.2034380000 0.1169370000 0.8679880000 0.0071080000 109448962 0 1788035072 3.9044501781 4.0020060539 3.9933862686 112 1305031233.2330091000 0.1110843420 0.0796142096 0.1593457907 0.0299819811 2.0437520000 0.9093330000 0.2763740000 0.0000040000 0.8500300000 0.0071630000 109451148 0 1785233408 3.9043681622 4.0035228729 3.9972040653 113 1305031233.2684679031 0.1097043380 0.0798804940 0.1593457907 0.0306277319 2.9229060000 0.9214780000 0.2783690000 0.1163070000 0.7905540000 0.8153390000 109453398 0 1786757120 3.9012444019 4.0040221214 4.0019869804 114 1305031233.3003950119 0.0953635499 0.0800163102 0.1593457907 0.0308790417 2.0628180000 0.9072210000 0.4059590000 0.0000040000 0.7416450000 0.0071340000 109455584 0 1784725504 3.9099318981 4.0133233070 4.0098452568 115 1305031233.3325300217 0.0879843682 0.0800855977 0.1593457907 0.0307623660 2.0456760000 0.9103400000 0.3166000000 0.1157670000 0.6949930000 0.0071060000 109457770 0 1786249216 3.9129228592 4.0039844513 4.0231232643 116 1305031233.3686299324 0.0699630007 0.0799983339 0.1593457907 0.0307270645 1.9813770000 0.9338760000 0.4000700000 0.0000040000 0.6393680000 0.0071890000 109459956 0 1788026880 3.9360351562 4.0127692223 4.0283346176 117 1305031233.4008929729 0.0577536263 0.0798082082 0.1593457907 0.0307033617 2.6981140000 0.9562430000 0.4148810000 0.1192510000 0.5915620000 0.6152970000 109462174 0 1785233408 3.9623236656 4.0259966850 4.0356721878 118 1305031233.4330079556 0.0597231239 0.0796379957 0.1593457907 0.0307250342 1.9791510000 0.9795620000 0.4223860000 0.0000040000 0.5689780000 0.0073400000 109464392 0 1786884096 3.9580211639 4.0162830353 4.0408239365 119 1305031233.4687869549 0.0623641722 0.0794928375 0.1593457907 0.0307374574 1.8995400000 0.9781790000 0.2503560000 0.1220800000 0.5406550000 0.0073780000 109466578 0 1784725504 3.9566335678 4.0094838142 4.0451078415 120 1305031233.5007359982 0.0639175475 0.0793630434 0.1593457907 0.0306389288 1.9597070000 0.9709200000 0.4344590000 0.0000040000 0.5461410000 0.0072910000 109468796 0 1786376192 3.9531235695 4.0067410469 4.0468363762 121 1305031233.5341610909 0.0647616684 0.0792423709 0.1593457907 0.0306114439 2.4679660000 0.9797850000 0.2858610000 0.1227690000 0.5273860000 0.5512610000 109471014 0 1785614336 3.9536690712 4.0053844452 4.0496912003 122 1305031233.5697269440 0.0637672469 0.0791155256 0.1593457907 0.0305116796 1.7973490000 0.9809530000 0.2859670000 0.0000050000 0.5221330000 0.0074060000 109473232 0 1787011072 3.9548420906 4.0054497719 4.0536184311 123 1305031233.6012749672 0.0660951734 0.0790096691 0.1593457907 0.0304473983 1.9623860000 0.9883720000 0.3226740000 0.1241780000 0.5189180000 0.0073480000 109475418 0 1784979456 3.9537899494 4.0024609566 4.0548777580 124 1305031233.6330409050 0.0663487092 0.0789075646 0.1593457907 0.0303811828 1.8533680000 1.0086680000 0.3248730000 0.0000050000 0.5116180000 0.0072890000 109477604 0 1786376192 3.9546732903 3.9995648861 4.0594077110 125 1305031233.6717829704 0.0653804243 0.0787993474 0.1593457907 0.0302617777 2.6271410000 0.9901720000 0.4425030000 0.1248060000 0.5254640000 0.5432750000 109479918 0 1785749504 3.9518227577 3.9997227192 4.0609803200 126 1305031233.7022960186 0.0626768172 0.0786713908 0.1593457907 0.0303158941 1.8231450000 0.9851320000 0.2913020000 0.0000050000 0.5384770000 0.0072980000 109482104 0 1787146240 3.9530317783 4.0015478134 4.0646667480 127 1305031233.7312009335 0.0558259860 0.0784915058 0.1593457907 0.0304948109 1.8614020000 0.9630610000 0.2170070000 0.1254080000 0.5476670000 0.0073180000 109484226 0 1784733696 3.9606144428 4.0096139908 4.0718064308 128 1305031233.7691600323 0.0526222587 0.0782894023 0.1593457907 0.0305449894 1.8292550000 0.9748820000 0.2951330000 0.0000040000 0.5510250000 0.0072750000 109486476 0 1786257408 3.9635312557 4.0138492584 4.0741791725 129 1305031233.7997679710 0.0530043505 0.0780933941 0.1593457907 0.0304387540 2.6660430000 0.9773820000 0.4450230000 0.1251920000 0.5462640000 0.5712210000 109498870 0 1788026880 3.9622557163 4.0124325752 4.0731978416 130 1305031233.8338310719 0.0561799034 0.0779248288 0.1593457907 0.0303915965 1.9280630000 0.9766570000 0.3984080000 0.0000040000 0.5447580000 0.0072660000 109522080 0 1785360384 3.9582121372 4.0067052841 4.0698633194 131 1305031233.8655700684 0.0581520014 0.0777738912 0.1593457907 0.0303199334 2.0434830000 0.9431700000 0.4306300000 0.1249270000 0.5364640000 0.0073140000 109524266 0 1787011072 3.9587650299 4.0048208237 4.0691123009 132 1305031233.8986968994 0.0571230613 0.0776174455 0.1593457907 0.0302049279 1.9330730000 0.9495690000 0.4335330000 0.0000040000 0.5417300000 0.0072740000 109526516 0 1784598528 3.9591693878 4.0058217049 4.0692052841 133 1305031233.9320030212 0.0570675582 0.0774629351 0.1593457907 0.0301314492 2.6100090000 0.9551010000 0.4325100000 0.1252470000 0.5361930000 0.5599780000 109528702 0 1786122240 3.9651999474 4.0059547424 4.0720338821 134 1305031233.9681589603 0.0554925688 0.0772989771 0.1593457907 0.0300376080 1.8762050000 0.9677400000 0.3643990000 0.0000040000 0.5357770000 0.0072920000 109530952 0 1787899904 3.9707064629 4.0084366798 4.0739192963 135 1305031233.9989380836 0.0562712997 0.0771432165 0.1593457907 0.0299682997 2.0976100000 0.9809750000 0.4428950000 0.1252520000 0.5401400000 0.0073590000 109533138 0 1784852480 3.9715404510 4.0072908401 4.0724673271 136 1305031234.0370678902 0.0541726090 0.0769743150 0.1593457907 0.0298705862 1.9906250000 0.9763410000 0.4433330000 0.0000050000 0.5624960000 0.0074640000 109535420 0 1786376192 3.9775328636 4.0114030838 4.0744032860 137 1305031234.0687561035 0.0532472432 0.0768011247 0.1593457907 0.0297634233 2.6790020000 0.9807550000 0.3348880000 0.1256100000 0.5980910000 0.6386660000 109537574 0 1788153856 3.9791762829 4.0127935410 4.0736870766 138 1305031234.0997409821 0.0540050864 0.0766359360 0.1593457907 0.0296613285 1.8776070000 0.9745230000 0.2584550000 0.0000050000 0.6362410000 0.0073420000 109539760 0 1785106432 3.9858670235 4.0154666901 4.0754203796 139 1305031234.1350688934 0.0538586713 0.0764720708 0.1593457907 0.0295675591 2.1610570000 0.9755880000 0.3673520000 0.1255000000 0.6842400000 0.0073790000 109541978 0 1786630144 3.9881522655 4.0173802376 4.0748400688 140 1305031234.1659009457 0.0499583669 0.0762826872 0.1593457907 0.0295286682 2.1296450000 0.9634320000 0.4353830000 0.0000030000 0.7224680000 0.0073350000 109544164 0 1785614336 3.9877259731 4.0230860710 4.0747656822 141 1305031234.2010040283 0.0499848463 0.0760961777 0.1593457907 0.0294802937 2.9690460000 0.9730890000 0.3586500000 0.1258200000 0.7206920000 0.7897920000 109546382 0 1787146240 3.9870092869 4.0223736763 4.0735244751 142 1305031234.2385749817 0.0490644686 0.0759058136 0.1593457907 0.0293786740 2.1842940000 0.9673570000 0.4349830000 0.0000040000 0.7735430000 0.0073540000 109548696 0 1784479744 3.9891533852 4.0254306793 4.0743551254 143 1305031234.2655100822 0.0460067093 0.0756967289 0.1593457907 0.0293007067 2.1862310000 0.9771950000 0.2810270000 0.1263130000 0.7933620000 0.0073010000 109550754 0 1785995264 3.9911894798 4.0330576897 4.0771751404 144 1305031234.3024549484 0.0456886776 0.0754883397 0.1593457907 0.0291982473 2.1583590000 0.9698310000 0.3558720000 0.0000040000 0.8242790000 0.0073580000 109553068 0 1787772928 3.9914517403 4.0332083702 4.0772900581 145 1305031234.3384580612 0.0448641442 0.0752771383 0.1593457907 0.0291165816 3.2536090000 0.9722090000 0.4236940000 0.1269600000 0.8242880000 0.9053540000 109555318 0 1784725504 3.9900891781 4.0345063210 4.0762991905 146 1305031234.3661808968 0.0427424498 0.0750542980 0.1593457907 0.0290618156 2.1022470000 0.9794830000 0.2490380000 0.0000040000 0.8652330000 0.0074280000 109557408 0 1786249216 3.9916086197 4.0400161743 4.0791287422 147 1305031234.4000349045 0.0438688062 0.0748421518 0.1593457907 0.0289629179 2.3872280000 0.9800340000 0.4249520000 0.1278870000 0.8459250000 0.0073690000 109559626 0 1788026880 3.9942500591 4.0414304733 4.0806102753 148 1305031234.4367709160 0.0462975055 0.0746492826 0.1593457907 0.0289328287 2.1306660000 0.9801220000 0.2495630000 0.0000040000 0.8924410000 0.0074630000 109561908 0 1784725504 3.9983711243 4.0411505699 4.0812096596 149 1305031234.4676060677 0.0473098457 0.0744657964 0.1593457907 0.0288444728 3.2524870000 0.9880820000 0.2460010000 0.1294400000 0.8997020000 0.9882040000 109564062 0 1786122240 4.0006222725 4.0438327789 4.0812616348 150 1305031234.4977810383 0.0480931886 0.0742899790 0.1593457907 0.0287535076 2.2744420000 0.9891650000 0.3245000000 0.0000040000 0.9521730000 0.0075340000 109566216 0 1788026880 4.0021719933 4.0478310585 4.0815038681 151 1305031234.5376710892 0.0521461815 0.0741433313 0.1593457907 0.0288347796 2.4564140000 0.9838600000 0.3516280000 0.1312210000 0.9811720000 0.0074770000 109568530 0 1784852480 4.0064373016 4.0445570946 4.0783071518 152 1305031234.5690369606 0.0557221510 0.0740221394 0.1593457907 0.0288410389 2.4701710000 0.9864630000 0.4286550000 0.0000040000 1.0464600000 0.0075000000 109570684 0 1786249216 4.0114049911 4.0509815216 4.0809941292 153 1305031234.5982480049 0.0602071770 0.0739318455 0.1593457907 0.0287508150 3.6972590000 0.9932480000 0.3475820000 0.1340700000 1.0694220000 1.1518590000 109572870 0 1788153856 4.0159831047 4.0557198524 4.0822105408 154 1305031234.6336491108 0.0621629916 0.0738554244 0.1593457907 0.0286879203 2.4848670000 0.9894550000 0.3576350000 0.0000030000 1.1292480000 0.0074670000 109575056 0 1784471552 4.0173811913 4.0551843643 4.0787057877 155 1305031234.6658589840 0.0654069334 0.0738009180 0.1593457907 0.0286195424 2.7234460000 0.9959190000 0.4228540000 0.1367550000 1.1593120000 0.0074700000 109577274 0 1786130432 4.0195131302 4.0585122108 4.0772814751 156 1305031234.6987318993 0.0664881393 0.0737540412 0.1593457907 0.0285423532 2.6999960000 1.0407030000 0.4338320000 0.0000040000 1.2168620000 0.0075020000 109579492 0 1787908096 4.0176801682 4.0596737862 4.0717782974 157 1305031234.7344369888 0.0679036826 0.0737167778 0.1593457907 0.0284626977 4.1539020000 1.0069090000 0.4242870000 0.1390640000 1.2488460000 1.3336650000 109581678 0 1784852480 4.0150294304 4.0634713173 4.0667428970 158 1305031234.7689719200 0.0710732788 0.0737000468 0.1593457907 0.0283765220 2.6777410000 0.9970910000 0.3630270000 0.0000050000 1.3089780000 0.0075250000 109583928 0 1786249216 4.0153932571 4.0680484772 4.0649399757 159 1305031234.8015530109 0.0749741346 0.0737080599 0.1593457907 0.0284085492 2.7778490000 1.0169900000 0.2844070000 0.1426400000 1.3251590000 0.0075560000 109586146 0 1788026880 4.0112409592 4.0820240974 4.0672526360 160 1305031234.8378078938 0.0775489882 0.0737320657 0.1593457907 0.0283323611 2.8352120000 1.0173690000 0.4503090000 0.0000040000 1.3588160000 0.0076030000 109588428 0 1784725504 4.0085611343 4.0887660980 4.0687766075 161 1305031234.8693211079 0.0799787417 0.0737708649 0.1593457907 0.0282615757 4.4178240000 1.0019520000 0.4330300000 0.1427520000 1.3779290000 1.4610610000 109590550 0 1786122240 4.0028681755 4.0947980881 4.0651912689 162 1305031234.9019980431 0.0841823816 0.0738351335 0.1593457907 0.0281852960 2.8442930000 0.9908780000 0.4472160000 0.0000050000 1.3972720000 0.0077870000 109592768 0 1788026880 4.0004110336 4.1028704643 4.0700039864 163 1305031234.9381608963 0.0861272514 0.0739105453 0.1593457907 0.0282730001 2.9636250000 0.9823560000 0.4390910000 0.1437360000 1.3898050000 0.0075220000 109595018 0 1784725504 3.9940464497 4.1099114418 4.0759344101 164 1305031234.9730799198 0.0874232948 0.0739929401 0.1593457907 0.0281892448 2.7240580000 1.0176330000 0.3258320000 0.0000040000 1.3719830000 0.0074820000 109597268 0 1786122240 3.9924669266 4.1128640175 4.0820059776 165 1305031235.0050830841 0.0862323493 0.0740671184 0.1593457907 0.0282532411 4.3095480000 1.0111480000 0.4085960000 0.1420670000 1.3438770000 1.4027440000 109599422 0 1788162048 3.9927179813 4.1133918762 4.0908379555 166 1305031235.0399720669 0.0818507969 0.0741140080 0.1593457907 0.0281741502 2.7353820000 1.0068060000 0.4115180000 0.0000040000 1.3083420000 0.0074990000 109601672 0 1783971840 3.9982781410 4.1062712669 4.0963602066 167 1305031235.0729401112 0.0783914328 0.0741396213 0.1593457907 0.0281329197 2.7997770000 1.0105580000 0.3744830000 0.1408070000 1.2652280000 0.0075250000 109603858 0 1785487360 4.0016832352 4.1017036438 4.1051144600 168 1305031235.0995910168 0.0701139048 0.0741156587 0.1593457907 0.0280569424 2.7038850000 1.0105520000 0.4516610000 0.0000040000 1.2330030000 0.0075460000 109605980 0 1787265024 4.0037932396 4.0915517807 4.1066374779 169 1305031235.1362709999 0.0628825277 0.0740491905 0.1593457907 0.0280235255 4.0254160000 0.9911910000 0.4462480000 0.1392070000 1.2109140000 1.2367040000 109608230 0 1784852480 4.0074567795 4.0791077614 4.1066184044 170 1305031235.1663711071 0.0583538897 0.0739568652 0.1593457907 0.0280161774 2.6263540000 0.9919740000 0.4418230000 0.0000050000 1.1839180000 0.0074760000 109610384 0 1786503168 4.0053629875 4.0769710541 4.1102180481 171 1305031235.1998469830 0.0567027442 0.0738559639 0.1593457907 0.0279406789 2.7224560000 1.0010000000 0.4427190000 0.1370300000 1.1330570000 0.0074870000 109612538 0 1785741312 4.0084724426 4.0727429390 4.1171565056 172 1305031235.2375700474 0.0530568250 0.0737350387 0.1593457907 0.0279283787 2.4694710000 1.0363580000 0.3310080000 0.0000040000 1.0933630000 0.0075630000 109614820 0 1787138048 4.0072531700 4.0718855858 4.1205835342 173 1305031235.2690389156 0.0503896736 0.0736000944 0.1593457907 0.0278492256 3.7070390000 1.0038560000 0.4390960000 0.1356830000 1.0514370000 1.0757640000 109617006 0 1785106432 4.0056147575 4.0719451904 4.1256928444 174 1305031235.3064870834 0.0473027900 0.0734489604 0.1593457907 0.0278768542 2.4534110000 0.9928370000 0.4361250000 0.0000050000 1.0158090000 0.0074560000 109619288 0 1786630144 4.0021910667 4.0756793022 4.1305098534 175 1305031235.3380000591 0.0385510325 0.0732495437 0.1593457907 0.0277990268 2.4495980000 0.9929560000 0.3574530000 0.1330530000 0.9574930000 0.0074590000 109621442 0 1784852480 3.9936664104 4.0764975548 4.1305823326 176 1305031235.3698880672 0.0288661141 0.0729973651 0.1593457907 0.0277676901 2.3425680000 0.9914930000 0.4313760000 0.0000040000 0.9108440000 0.0075660000 109623628 0 1786503168 3.9845287800 4.0752305984 4.1260318756 177 1305031235.4060161114 0.0234053191 0.0727171841 0.1593457907 0.0278158717 3.3028920000 0.9927060000 0.4368940000 0.1302310000 0.8602890000 0.8815600000 109625878 0 1785876480 3.9797732830 4.0750379562 4.1249680519 178 1305031235.4381530285 0.0193786360 0.0724175293 0.1593457907 0.0277687449 2.2358360000 0.9943560000 0.4285990000 0.0000040000 0.8040760000 0.0074440000 109628064 0 1787273216 3.9713957310 4.0778822899 4.1249399185 179 1305031235.4700589180 0.0186457448 0.0721171283 0.1593457907 0.0277578960 2.2611100000 1.0216680000 0.3634610000 0.1275180000 0.7395950000 0.0075430000 109630250 0 1784606720 3.9669640064 4.0689921379 4.1182298660 180 1305031235.5059850216 0.0226687677 0.0718424152 0.1593457907 0.0276929879 2.0092250000 0.9879190000 0.3223400000 0.0000040000 0.6902960000 0.0074480000 109632500 0 1786249216 3.9621319771 4.0665960312 4.1174817085 181 1305031235.5385539532 0.0229160953 0.0715721040 0.1593457907 0.0276243909 2.7829400000 0.9779330000 0.4269150000 0.1255040000 0.6137250000 0.6376240000 109634686 0 1787899904 3.9618752003 4.0648260117 4.1195831299 182 1305031235.5703649521 0.0249439441 0.0713159053 0.1593457907 0.0275591795 1.8041060000 0.9818140000 0.2405960000 0.0000050000 0.5731400000 0.0073270000 109636872 0 1784852480 3.9639811516 4.0601658821 4.1222248077 183 1305031235.6060059071 0.0290127639 0.0710847406 0.1593457907 0.0275199978 2.0832730000 0.9886940000 0.4336270000 0.1243400000 0.5279400000 0.0073160000 109639154 0 1786376192 3.9600014687 4.0595870018 4.1245679855 184 1305031235.6389510632 0.0360121764 0.0708941288 0.1593457907 0.0274785727 1.7125900000 0.9964920000 0.2146250000 0.0000040000 0.4927730000 0.0074570000 109641340 0 1788026880 3.9579463005 4.0541234016 4.1259875298 185 1305031235.6705160141 0.0405577756 0.0707301486 0.1593457907 0.0274117656 2.3620180000 0.9949130000 0.2894080000 0.1233810000 0.4680210000 0.4850330000 109643494 0 1784725504 3.9558722973 4.0519266129 4.1288318634 186 1305031235.7057778835 0.0451436080 0.0705925865 0.1593457907 0.0273378274 1.7039370000 0.9963630000 0.2510750000 0.0000050000 0.4478490000 0.0073990000 109645744 0 1786376192 3.9611332417 4.0473256111 4.1361474991 187 1305031235.7387969494 0.0529207289 0.0704980846 0.1593457907 0.0272987733 1.8741400000 0.9951960000 0.2564830000 0.1235830000 0.4902730000 0.0073500000 109647962 0 1788153856 3.9586656094 4.0428123474 4.1396484375 188 1305031235.7696299553 0.0586634167 0.0704351342 0.1593457907 0.0272355802 1.9109450000 1.0014960000 0.3261210000 0.0000050000 0.5745910000 0.0074380000 109650116 0 1784979456 3.9539573193 4.0416584015 4.1420607567 189 1305031235.8072249889 0.0688904971 0.0704269616 0.1593457907 0.0271755129 2.5760270000 0.9961540000 0.3515480000 0.1234200000 0.5329420000 0.5706840000 109652462 0 1786376192 3.9497032166 4.0373368263 4.1438531876 190 1305031235.8388121128 0.0756954178 0.0704546903 0.1593457907 0.0271345405 1.9708450000 1.0111810000 0.3336570000 0.0000040000 0.6173220000 0.0074160000 109654648 0 1785360384 3.9473853111 4.0342941284 4.1477837563 191 1305031235.8700668812 0.0820125714 0.0705152027 0.1593457907 0.0270912048 2.0671850000 1.0193400000 0.3579190000 0.1239420000 0.5572470000 0.0074480000 109656866 0 1786884096 3.9450361729 4.0318498611 4.1518478394 192 1305031235.9061110020 0.0892670527 0.0706128686 0.1593457907 0.0270248380 1.9127670000 1.0124950000 0.2568220000 0.0000050000 0.6347210000 0.0074440000 109659148 0 1784725504 3.9439585209 4.0292153358 4.1557798386 193 1305031235.9382328987 0.0991194621 0.0707605712 0.1593457907 0.0269802824 2.8299730000 1.0289490000 0.4328340000 0.1250420000 0.5945650000 0.6472800000 109661398 0 1786249216 3.9451518059 4.0221042633 4.1617760658 194 1305031235.9700109959 0.1022566855 0.0709229223 0.1593457907 0.0269141139 1.9517150000 1.0170860000 0.2631100000 0.0000040000 0.6626930000 0.0075350000 109663584 0 1787908096 3.9394567013 4.0240669250 4.1624073982 195 1305031236.0068531036 0.1116452515 0.0711317547 0.1593457907 0.0268564196 2.2301690000 1.0205000000 0.4412230000 0.1259140000 0.6338180000 0.0074140000 109665898 0 1784733696 3.9404227734 4.0185832977 4.1696281433 196 1305031236.0380480289 0.1170744076 0.0713661560 0.1593457907 0.0267939302 2.2063970000 1.0181000000 0.4590640000 0.0000050000 0.7204690000 0.0074660000 109668084 0 1785995264 3.9366116524 4.0177459717 4.1713500023 197 1305031236.0698781013 0.1260028630 0.0716434997 0.1593457907 0.0268070188 2.8834840000 1.0238360000 0.3666040000 0.1264440000 0.6474300000 0.7177940000 109670302 0 1787899904 3.9310555458 4.0134673119 4.1735873222 198 1305031236.1058719158 0.1301867366 0.0719391726 0.1593457907 0.0267451818 2.1792770000 1.0113190000 0.4471650000 0.0000050000 0.7120310000 0.0074120000 109672584 0 1784725504 3.9318647385 4.0126504898 4.1785941124 199 1305031236.1383249760 0.1346191466 0.0722541474 0.1593457907 0.0266849379 2.1120280000 1.0326040000 0.2998520000 0.1271460000 0.6437380000 0.0073460000 109674834 0 1786249216 3.9285514355 4.0114674568 4.1798415184 200 1305031236.1709330082 0.1364406347 0.0725750798 0.1593457907 0.0266182726 2.1401460000 1.0061430000 0.4525310000 0.0000040000 0.6727340000 0.0074040000 109677052 0 1788153856 3.9293603897 4.0120339394 4.1837191582 201 1305031236.2071900368 0.1386926472 0.0729040229 0.1593457907 0.0265589148 2.9426570000 1.0083760000 0.4587790000 0.1287520000 0.6405910000 0.7047660000 109679366 0 1784725504 3.9277932644 4.0125117302 4.1851234436 202 1305031236.2383749485 0.1427399665 0.0732497454 0.1593457907 0.0265259362 2.1159030000 0.9985680000 0.4500030000 0.0000050000 0.6585470000 0.0074350000 109681584 0 1786122240 3.9274482727 4.0094418526 4.1896867752 203 1305031236.2699589729 0.1458610445 0.0736074366 0.1593457907 0.0264620637 2.2326700000 1.0005540000 0.4619440000 0.1270750000 0.6343880000 0.0073370000 109683770 0 1788026880 3.9269556999 4.0062451363 4.1913638115 204 1305031236.3069939613 0.1462812573 0.0739636808 0.1593457907 0.0264408878 2.0891460000 1.0100540000 0.4612050000 0.0000050000 0.6090880000 0.0074170000 109686084 0 1784598528 3.9284169674 4.0037221909 4.1931366920 205 1305031236.3392169476 0.1483960301 0.0743267654 0.1593457907 0.0263849526 2.8273710000 1.0114780000 0.4601420000 0.1274890000 0.5908060000 0.6360660000 109688302 0 1786122240 3.9298365116 3.9991879463 4.1934776306 206 1305031236.3700959682 0.1453163624 0.0746713751 0.1593457907 0.0263289088 1.9054660000 1.0146720000 0.3032850000 0.0000040000 0.5785140000 0.0074730000 109690488 0 1788026880 3.9318580627 3.9986424446 4.1896529198 207 1305031236.4058690071 0.1387599409 0.0749809817 0.1593457907 0.0263154493 2.1739700000 1.0118460000 0.4657600000 0.1266580000 0.5609530000 0.0073840000 109692770 0 1784598528 3.9360272884 3.9995718002 4.1851325035 208 1305031236.4387879372 0.1304838657 0.0752478225 0.1593457907 0.0262569849 2.0524150000 1.0199670000 0.4670760000 0.0000050000 0.5565230000 0.0074630000 109694988 0 1785995264 3.9447402954 4.0016875267 4.1818900108 209 1305031236.4751410484 0.1213447079 0.0754683818 0.1593457907 0.0261973802 2.7370340000 1.0155870000 0.4629730000 0.1262630000 0.5491280000 0.5817000000 109697302 0 1787908096 3.9518680573 4.0045070648 4.1767883301 210 1305031236.5077209473 0.1142710224 0.0756531562 0.1593457907 0.0261416472 2.0386860000 1.0210310000 0.4635010000 0.0000050000 0.5453530000 0.0074170000 109699552 0 1784987648 3.9549345970 4.0062036514 4.1706032753 211 1305031236.5386450291 0.1105396375 0.0758184950 0.1593457907 0.0260952822 2.1641700000 1.0234630000 0.4668640000 0.1254190000 0.5395980000 0.0074420000 109701738 0 1786376192 3.9527180195 4.0049848557 4.1605901718 212 1305031236.5740950108 0.1026082486 0.0759448618 0.1593457907 0.0260400872 1.9538310000 1.0205510000 0.3914710000 0.0000050000 0.5330250000 0.0074220000 109704020 0 1785741312 3.9515309334 4.0068335533 4.1511592865 213 1305031236.6057569981 0.1021767333 0.0760680161 0.1593457907 0.0259802230 2.5610160000 1.0207860000 0.3425800000 0.1245990000 0.5224030000 0.5491800000 109706206 0 1787138048 3.9528238773 4.0022563934 4.1461386681 214 1305031236.6384010315 0.0969682038 0.0761656805 0.1593457907 0.0259571722 1.9203460000 1.0142640000 0.3766640000 0.0000050000 0.5204770000 0.0075060000 109708424 0 1785360384 3.9547877312 4.0028562546 4.1393675804 215 1305031236.6751470566 0.0908702910 0.0762340741 0.1593457907 0.0259120380 2.0886290000 1.0026640000 0.4498580000 0.1236680000 0.5036690000 0.0073310000 109710674 0 1786884096 3.9565627575 4.0029368401 4.1331892014 216 1305031236.7033619881 0.0870450065 0.0762841247 0.1593457907 0.0258561081 1.8383730000 0.9937830000 0.3371980000 0.0000050000 0.4985960000 0.0073480000 109712796 0 1784852480 3.9637308121 4.0019111633 4.1305942535 217 1305031236.7339220047 0.0780807734 0.0762924042 0.1593457907 0.0258349768 2.4089670000 1.0089440000 0.2606080000 0.1239510000 0.4942290000 0.5198070000 109714950 0 1786376192 3.9635779858 4.0076665878 4.1196432114 218 1305031236.7740409374 0.0709734559 0.0762680053 0.1593457907 0.0258008292 1.8311700000 1.0063570000 0.3371750000 0.0000040000 0.4788300000 0.0073790000 109717264 0 1785614336 3.9638593197 4.0099806786 4.1113228798 219 1305031236.8025879860 0.0690563396 0.0762350753 0.1593457907 0.0258572246 2.0562690000 0.9955440000 0.4532910000 0.1241840000 0.4743770000 0.0074260000 109719450 0 1787011072 3.9636290073 4.0109934807 4.1020960808 220 1305031236.8364150524 0.0607834645 0.0761648407 0.1593457907 0.0258009327 1.9310140000 0.9918080000 0.4504680000 0.0000040000 0.4798940000 0.0074080000 109721636 0 1784725504 3.9662070274 4.0154428482 4.0953574181 221 1305031236.8743979931 0.0558272265 0.0760728153 0.1593457907 0.0257561960 2.4789210000 0.9932770000 0.3356650000 0.1247120000 0.4975350000 0.5262590000 109723918 0 1786376192 3.9672191143 4.0166058540 4.0878615379 222 1305031236.9060690403 0.0535133034 0.0759711959 0.1593457907 0.0257452742 1.9446750000 0.9887030000 0.4123540000 0.0000040000 0.5348330000 0.0073560000 109726104 0 1788153856 3.9694848061 4.0175971985 4.0806093216 223 1305031236.9344370365 0.0518412068 0.0758629897 0.1593457907 0.0257021933 2.1454580000 0.9745540000 0.4455230000 0.1251330000 0.5914620000 0.0073390000 109728226 0 1785360384 3.9715256691 4.0184464455 4.0744295120 224 1305031236.9744000435 0.0472671688 0.0757353298 0.1593457907 0.0256476580 2.0700220000 0.9794540000 0.4433580000 0.0000040000 0.6383320000 0.0073840000 109730508 0 1786884096 3.9756362438 4.0214166641 4.0698380470 225 1305031237.0074260235 0.0480160601 0.0756121330 0.1593457907 0.0256015898 2.8374500000 0.9598050000 0.2924780000 0.1271620000 0.7128680000 0.7436240000 109732758 0 1785114624 3.9847271442 4.0237030983 4.0678067207 226 1305031237.0370240211 0.0490467399 0.0754945870 0.1593457907 0.0255761962 2.1827720000 0.9838820000 0.4058690000 0.0000050000 0.7841420000 0.0073870000 109734912 0 1786638336 3.9897542000 4.0281896591 4.0642852783 227 1305031237.0734269619 0.0518368073 0.0753903677 0.1593457907 0.0255228629 2.3243360000 0.9811320000 0.3654320000 0.1289850000 0.8398130000 0.0074710000 109737130 0 1784733696 3.9945731163 4.0291171074 4.0604686737 228 1305031237.1059679985 0.0581046529 0.0753145532 0.1593457907 0.0254814438 2.2557370000 0.9780740000 0.3723860000 0.0000040000 0.8962190000 0.0074890000 109739348 0 1786257408 4.0021047592 4.0295820236 4.0584173203 229 1305031237.1378319263 0.0656806231 0.0752724836 0.1593457907 0.0254373754 3.3686450000 0.9863940000 0.2942890000 0.1317970000 0.9602830000 0.9943400000 109741534 0 1788026880 4.0108299255 4.0310606956 4.0561618805 230 1305031237.1712269783 0.0718011037 0.0752573907 0.1593457907 0.0254800378 2.2995610000 0.9891260000 0.2922870000 0.0000050000 1.0092140000 0.0074320000 109743752 0 1785487360 4.0177483559 4.0380430222 4.0569729805 231 1305031237.2042291164 0.0780902430 0.0752696541 0.1593457907 0.0254831467 2.4711560000 0.9814400000 0.2922780000 0.1344350000 1.0539160000 0.0075830000 109745906 0 1786757120 4.0245366096 4.0359945297 4.0534086227 232 1305031237.2375690937 0.0865278021 0.0753181806 0.1593457907 0.0254610302 2.3639930000 0.9950220000 0.2539030000 0.0000040000 1.1060050000 0.0074700000 109748156 0 1784852480 4.0324954987 4.0374155045 4.0517301559 233 1305031237.2746589184 0.0885839909 0.0753751154 0.1593457907 0.0254287259 3.8030770000 0.9998560000 0.3362210000 0.1372190000 1.1447630000 1.1834830000 109750406 0 1786376192 4.0337815285 4.0387892723 4.0454249382 234 1305031237.3058099747 0.0903736055 0.0754392115 0.1593457907 0.0253802434 2.4462480000 0.9883100000 0.2596700000 0.0000050000 1.1891620000 0.0075750000 109752592 0 1788153856 4.0344777107 4.0389308929 4.0366978645 235 1305031237.3371419907 0.0925093815 0.0755118505 0.1593457907 0.0253625913 2.6235770000 0.9937110000 0.2569550000 0.1390580000 1.2245110000 0.0077880000 109754778 0 1785360384 4.0346231461 4.0387539864 4.0284876823 236 1305031237.3741660118 0.0933822319 0.0755875725 0.1593457907 0.0253289089 2.6356870000 0.9915240000 0.3766150000 0.0000030000 1.2585360000 0.0074670000 109756996 0 1787138048 4.0319843292 4.0424075127 4.0187425613 237 1305031237.4057340622 0.0929512903 0.0756608371 0.1593457907 0.0253280807 4.2229210000 1.0186780000 0.4487350000 0.1407700000 1.2917570000 1.3214330000 109759214 0 1784852480 4.0269804001 4.0515580177 4.0142164230 238 1305031237.4377219677 0.0976521894 0.0757532378 0.1593457907 0.0253242854 2.5668310000 0.9909290000 0.2572940000 0.0000030000 1.3096090000 0.0074540000 109761400 0 1786765312 4.0289607048 4.0554909706 4.0108261108 239 1305031237.4741280079 0.0991207659 0.0758510099 0.1593457907 0.0252941584 2.9016130000 0.9989740000 0.4116110000 0.1426130000 1.3393760000 0.0074830000 109763618 0 1784479744 4.0252261162 4.0617189407 4.0045399666 240 1305031237.5060451031 0.1014065072 0.0759574911 0.1593457907 0.0252791231 2.7153110000 0.9873550000 0.3376410000 0.0000020000 1.3812080000 0.0075470000 109765836 0 1786122240 4.0210714340 4.0720705986 4.0046491623 241 1305031237.5376501083 0.1031564847 0.0760703500 0.1593457907 0.0252356520 4.2941080000 0.9892630000 0.3020510000 0.1437700000 1.4014950000 1.4559680000 109768022 0 1787899904 4.0221934319 4.0723276138 3.9997851849 242 1305031237.5739479065 0.1040662900 0.0761860357 0.1593457907 0.0251942854 2.7389090000 0.9993670000 0.2988420000 0.0000040000 1.4315630000 0.0075810000 109770240 0 1785233408 4.0176520348 4.0754737854 3.9940042496 243 1305031237.6068129539 0.1092211306 0.0763219826 0.1593457907 0.0251675485 3.0013210000 0.9794310000 0.4134150000 0.1446280000 1.4540870000 0.0081900000 109772490 0 1786757120 4.0174422264 4.0868425369 3.9992594719 244 1305031237.6378550529 0.1116870195 0.0764669213 0.1593457907 0.0251253120 2.8771860000 0.9721710000 0.4371350000 0.0000030000 1.4586990000 0.0076150000 109774644 0 1784725504 4.0166082382 4.0911517143 3.9989395142 245 1305031237.6752760410 0.1149626374 0.0766240466 0.1593457907 0.0250897358 4.4037780000 0.9698670000 0.2875880000 0.1451950000 1.4678000000 1.5317320000 109776894 0 1786249216 4.0132250786 4.0978460312 4.0002999306 246 1305031237.7071180344 0.1158051714 0.0767833195 0.1593457907 0.0250413512 2.8292900000 0.9783090000 0.3636850000 0.0000030000 1.4781900000 0.0075050000 109779112 0 1788153856 4.0108971596 4.0999145508 3.9990820885 247 1305031237.7416670322 0.1174123362 0.0769478094 0.1593457907 0.0250225992 2.7982220000 0.9580950000 0.2197930000 0.1456380000 1.4655850000 0.0075070000 109781330 0 1785233408 4.0076680183 4.1054520607 4.0032753944 248 1305031237.7743060589 0.1175516173 0.0771115345 0.1593457907 0.0250567359 2.8891250000 0.9699970000 0.4390250000 0.0000030000 1.4708420000 0.0075970000 109783484 0 1786757120 4.0114746094 4.1024212837 4.0025334358 249 1305031237.8064959049 0.1147784591 0.0772628073 0.1593457907 0.0250142048 4.4380430000 0.9753790000 0.2905270000 0.1459080000 1.4746980000 1.5499310000 109785702 0 1784606720 4.0075149536 4.0999031067 3.9965932369 250 1305031237.8430309296 0.1196209714 0.0774322399 0.1593457907 0.0250892433 2.8992670000 0.9730160000 0.4512290000 0.0000030000 1.4658210000 0.0075860000 109787984 0 1786003456 4.0050234795 4.1093811989 4.0064902306 251 1305031237.8754220009 0.1167676523 0.0775889547 0.1593457907 0.0252812419 3.0348970000 0.9767370000 0.4481500000 0.1451450000 1.4557380000 0.0075140000 109790138 0 1787772928 4.0106935501 4.1017174721 4.0025238991 252 1305031237.9077839851 0.1134802699 0.0777313806 0.1593457907 0.0252482615 2.7263050000 0.9844100000 0.2573690000 0.0000030000 1.4754170000 0.0074770000 109792356 0 1785106432 4.0072388649 4.0979990959 3.9961521626 253 1305031237.9441869259 0.1218994707 0.0779059580 0.1593457907 0.0254224934 4.3820950000 0.9941610000 0.2603670000 0.1454310000 1.4578070000 1.5226620000 109794606 0 1786503168 4.0094380379 4.1110200882 4.0130786896 254 1305031237.9738099575 0.1244602650 0.0780892427 0.1593457907 0.0253882979 2.7887580000 1.0037410000 0.3423970000 0.0000030000 1.4333130000 0.0076630000 109796696 0 1785487360 4.0167813301 4.1102476120 4.0213813782 255 1305031238.0069320202 0.1220174730 0.0782615102 0.1593457907 0.0253529772 2.8965670000 1.0025060000 0.3372270000 0.1443530000 1.4031740000 0.0075720000 109798946 0 1787011072 4.0207638741 4.1052360535 4.0278587341 256 1305031238.0431399345 0.1228673235 0.0784357517 0.1593457907 0.0255404034 2.7168850000 1.0134920000 0.3344050000 0.0000020000 1.3597620000 0.0075900000 109801196 0 1784725504 4.0307435989 4.0996789932 4.0398635864 257 1305031238.0740320683 0.1157152876 0.0785808083 0.1593457907 0.0255702286 4.1383460000 1.0078790000 0.3306360000 0.1424640000 1.3150790000 1.3405980000 109823830 0 1786122240 4.0366511345 4.0840821266 4.0429134369 258 1305031238.1065878868 0.1071914583 0.0786917022 0.1593457907 0.0255904861 2.7020030000 0.9886630000 0.4423180000 0.0000030000 1.2618120000 0.0075100000 109868000 0 1788153856 4.0394983292 4.0670495033 4.0448861122 259 1305031238.1433279514 0.1045490205 0.0787915375 0.1593457907 0.0256399783 2.6981400000 0.9826990000 0.3606650000 0.1397350000 1.2058890000 0.0074410000 109870250 0 1784979456 4.0413932800 4.0582895279 4.0505099297 260 1305031238.1723001003 0.1001895815 0.0788738376 0.1593457907 0.0256156047 2.4888740000 0.9851470000 0.3528480000 0.0000030000 1.1415540000 0.0075160000 109872436 0 1786638336 4.0343704224 4.0628228188 4.0621457100 261 1305031238.2054259777 0.0992254689 0.0789518132 0.1593457907 0.0264126222 3.7653230000 1.0262450000 0.4244490000 0.0000060000 1.1452340000 1.1676950000 109874590 0 1784479744 4.0343704224 4.0628228188 4.0621457100 262 1305031238.2401471138 0.0846620798 0.0789736081 0.1593457907 0.0268118490 2.3853030000 1.0084090000 0.3373810000 0.0000040000 1.0302700000 0.0075050000 109876840 0 1786122240 4.0209422112 4.0580816269 4.0645823479 263 1305031238.2725269794 0.0716793537 0.0789458733 0.1593457907 0.0267669856 2.5119740000 0.9814330000 0.4232710000 0.1339890000 0.9640670000 0.0074880000 109879058 0 1787772928 4.0068664551 4.0585956573 4.0605955124 264 1305031238.3060529232 0.0651388541 0.0788935740 0.1593457907 0.0269357690 2.2117990000 0.9773400000 0.3178640000 0.0000040000 0.9074330000 0.0074710000 109881244 0 1784852480 3.9963328838 4.0659246445 4.0607705116 265 1305031238.3425960541 0.0530566275 0.0787960761 0.1593457907 0.0270020736 3.2202040000 0.9736330000 0.4195570000 0.1298110000 0.8356840000 0.8597900000 109883494 0 1786249216 3.9874870777 4.0556879044 4.0543756485 266 1305031238.3741040230 0.0486351438 0.0786826891 0.1593457907 0.0269747505 2.1882500000 0.9717970000 0.4326220000 0.0000040000 0.7746680000 0.0074440000 109885680 0 1788280832 3.9823603630 4.0497965813 4.0506186485 267 1305031238.4060359001 0.0457419157 0.0785593155 0.1593457907 0.0269258835 2.1675800000 0.9693710000 0.3553280000 0.1274320000 0.7063840000 0.0073320000 109887866 0 1784360960 3.9805538654 4.0459003448 4.0532803535 268 1305031238.4434239864 0.0452895686 0.0784351746 0.1593457907 0.0268812102 1.8513920000 0.9623150000 0.2454570000 0.0000040000 0.6344400000 0.0074060000 109890116 0 1785868288 3.9777872562 4.0413789749 4.0529136658 269 1305031238.4740819931 0.0461193770 0.0783150415 0.1593457907 0.0268444384 2.5681420000 0.9769820000 0.2443420000 0.1258870000 0.5976870000 0.6214800000 109892302 0 1787772928 3.9781000614 4.0369453430 4.0558094978 270 1305031238.5058109760 0.0467595719 0.0781981694 0.1593457907 0.0268672597 1.8613440000 0.9761620000 0.3214770000 0.0000050000 0.5544050000 0.0074380000 109894488 0 1784598528 3.9758477211 4.0315904617 4.0574541092 271 1305031238.5432639122 0.0502091534 0.0780948889 0.1593457907 0.0268196797 1.9749830000 0.9848360000 0.3270630000 0.1255680000 0.5284630000 0.0073190000 109896770 0 1786122240 3.9728870392 4.0252952576 4.0577683449 272 1305031238.5741839409 0.0490935221 0.0779882662 0.1593457907 0.0267770296 1.7344960000 0.9812830000 0.2150060000 0.0000040000 0.5290240000 0.0074000000 109898892 0 1788153856 3.9702732563 4.0255618095 4.0606374741 273 1305031238.6058249474 0.0504508950 0.0778873968 0.1593457907 0.0267315924 2.5021630000 0.9738690000 0.3245770000 0.1250360000 0.5246060000 0.5522890000 109901110 0 1784733696 3.9666430950 4.0228657722 4.0624122620 274 1305031238.6427590847 0.0515923053 0.0777914293 0.1593457907 0.0266873564 1.7669040000 0.9775440000 0.2529410000 0.0000040000 0.5270920000 0.0074640000 109903392 0 1786257408 3.9661211967 4.0216841698 4.0664358139 275 1305031238.6738131046 0.0542749017 0.0777059146 0.1593457907 0.0266448345 1.9574190000 0.9689440000 0.3229580000 0.1250630000 0.5314280000 0.0072750000 109905514 0 1787908096 3.9629442692 4.0207581520 4.0679259300 276 1305031238.7051889896 0.0545192324 0.0776219049 0.1593457907 0.0265977123 1.9646240000 0.9784730000 0.4451570000 0.0000040000 0.5318540000 0.0073630000 109907700 0 1784733696 3.9610099792 4.0218896866 4.0704650879 277 1305031238.7413070202 0.0588525608 0.0775541455 0.1593457907 0.0265867421 2.6331840000 0.9798550000 0.4345460000 0.1251210000 0.5324350000 0.5594170000 109909982 0 1786249216 3.9579846859 4.0181722641 4.0718908310 278 1305031238.7717959881 0.0636265650 0.0775040463 0.1593457907 0.0265665972 1.9846520000 0.9918440000 0.4459040000 0.0000040000 0.5377170000 0.0073220000 109912168 0 1788153856 3.9543623924 4.0146036148 4.0721888542 279 1305031238.8070189953 0.0656435490 0.0774615356 0.1593457907 0.0265420942 1.9620240000 0.9940420000 0.2928750000 0.1253440000 0.5406140000 0.0073780000 109914418 0 1784725504 3.9523837566 4.0156145096 4.0736203194 280 1305031238.8429400921 0.0685070753 0.0774295554 0.1593457907 0.0264982503 2.0137850000 1.0069890000 0.4493780000 0.0000040000 0.5481970000 0.0074090000 109916700 0 1786122240 3.9518916607 4.0135073662 4.0776162148 281 1305031238.8737230301 0.0778393373 0.0774310137 0.1593457907 0.0265081086 2.6932290000 1.0144270000 0.4107770000 0.1259850000 0.5560220000 0.5842190000 109918918 0 1788026880 3.9516158104 4.0054578781 4.0806174278 282 1305031238.9061720371 0.0828464851 0.0774502175 0.1593457907 0.0264739154 1.8456790000 1.0123600000 0.2632360000 0.0000050000 0.5607060000 0.0073940000 109921104 0 1784598528 3.9519143105 4.0012869835 4.0840191841 283 1305031238.9427859783 0.0837391913 0.0774724400 0.1593457907 0.0264272757 2.1060670000 1.0187450000 0.3873150000 0.1267390000 0.5639930000 0.0073890000 109923418 0 1786122240 3.9504439831 4.0019726753 4.0838994980 284 1305031238.9723079205 0.0887744278 0.0775122357 0.1593457907 0.0263900805 2.0476230000 1.0139330000 0.4606440000 0.0000040000 0.5637990000 0.0073940000 109925604 0 1788026880 3.9522373676 3.9977014065 4.0887761116 285 1305031239.0104830265 0.0899652839 0.0775559306 0.1593457907 0.0263657640 2.6636810000 1.0215660000 0.3515970000 0.1272190000 0.5671820000 0.5942800000 109927918 0 1784598528 3.9510190487 3.9984977245 4.0879340172 286 1305031239.0408790112 0.0929545313 0.0776097719 0.1593457907 0.0263260261 1.9447470000 1.0191000000 0.3467130000 0.0000040000 0.5696110000 0.0074360000 109930104 0 1786122240 3.9493463039 3.9964714050 4.0892701149 287 1305031239.0746610165 0.1005626097 0.0776897469 0.1593457907 0.0263273087 2.0960820000 1.0012570000 0.3804620000 0.1276010000 0.5775050000 0.0074220000 109932354 0 1787899904 3.9496665001 3.9895186424 4.0936980247 288 1305031239.1109058857 0.1031942219 0.0777783041 0.1593457907 0.0262820642 2.0280080000 0.9938250000 0.4512140000 0.0000050000 0.5737100000 0.0073940000 109934668 0 1784987648 3.9490129948 3.9871323109 4.0940337181 289 1305031239.1417789459 0.1044983938 0.0778707612 0.1593457907 0.0262476449 2.6223480000 1.0039530000 0.3054440000 0.1281630000 0.5748120000 0.6080940000 109936854 0 1786257408 3.9479172230 3.9852581024 4.0938639641 290 1305031239.1757500172 0.1047863066 0.0779635734 0.1593457907 0.0262377896 2.0728230000 1.0125270000 0.4649200000 0.0000040000 0.5861420000 0.0073780000 109939104 0 1785495552 3.9468660355 3.9842677116 4.0900077820 291 1305031239.2096450329 0.1014571041 0.0780443072 0.1593457907 0.0262013461 2.1768940000 1.0071910000 0.4613490000 0.1274730000 0.5716060000 0.0074220000 109941354 0 1786884096 3.9477310181 3.9871804714 4.0877428055 292 1305031239.2417099476 0.1016843691 0.0781252663 0.1593457907 0.0261721924 1.9885740000 1.0239170000 0.3836440000 0.0000050000 0.5716460000 0.0074070000 109943572 0 1784598528 3.9474000931 3.9860639572 4.0856657028 293 1305031239.2738199234 0.0991496742 0.0781970220 0.1593457907 0.0261466242 2.7760890000 1.0137310000 0.4686900000 0.1271050000 0.5682430000 0.5964310000 109945790 0 1785995264 3.9481837749 3.9872486591 4.0833210945 294 1305031239.3101770878 0.0975958481 0.0782630044 0.1593457907 0.0261028300 2.0664500000 1.0261160000 0.4655590000 0.0000050000 0.5654630000 0.0074660000 109948104 0 1787899904 3.9485783577 3.9878196716 4.0807785988 295 1305031239.3419699669 0.0941903964 0.0783169955 0.1593457907 0.0260637555 2.0561350000 1.0209000000 0.3398770000 0.1263740000 0.5596790000 0.0073810000 109950322 0 1784725504 3.9497470856 3.9901893139 4.0783314705 296 1305031239.3750240803 0.0910008550 0.0783598464 0.1593457907 0.0260336096 1.9739790000 1.0236820000 0.3804510000 0.0000050000 0.5604990000 0.0074680000 109952508 0 1786249216 3.9502415657 3.9918830395 4.0755009651 297 1305031239.4106309414 0.0870760307 0.0783891938 0.1593457907 0.0259908233 2.6980520000 1.0005110000 0.4518150000 0.1259570000 0.5456820000 0.5721900000 109954758 0 1788026880 3.9513859749 3.9947409630 4.0732731819 298 1305031239.4415419102 0.0874024108 0.0784194395 0.1593457907 0.0259501180 1.9941190000 0.9960220000 0.4487960000 0.0000040000 0.5398940000 0.0074340000 109956944 0 1784725504 3.9534964561 3.9930157661 4.0723004341 299 1305031239.4733181000 0.0800023153 0.0784247334 0.1593457907 0.0259096211 1.9967940000 0.9931070000 0.3341990000 0.1254280000 0.5347110000 0.0074530000 109959130 0 1786122240 3.9544639587 3.9994642735 4.0692529678 300 1305031239.5097389221 0.0744941384 0.0784116314 0.1593457907 0.0258721800 1.9839990000 0.9975280000 0.4433980000 0.0000050000 0.5338110000 0.0073710000 109961380 0 1788026880 3.9576931000 4.0045766830 4.0672001839 301 1305031239.5438020229 0.0706150159 0.0783857291 0.1593457907 0.0258373270 2.5555790000 0.9684720000 0.3733390000 0.1250650000 0.5308660000 0.5559170000 109963630 0 1784725504 3.9585745335 4.0075139999 4.0637459755 302 1305031239.5761160851 0.0687004998 0.0783536588 0.1593457907 0.0258020914 1.9589810000 0.9754110000 0.4451730000 0.0000040000 0.5290960000 0.0073790000 109965816 0 1786122240 3.9594504833 4.0089831352 4.0608439445 303 1305031239.6111609936 0.0670005456 0.0783161898 0.1593457907 0.0257632151 1.9360140000 0.9808450000 0.2936230000 0.1250090000 0.5272850000 0.0073390000 109968066 0 1787899904 3.9607470036 4.0105342865 4.0579223633 304 1305031239.6414220333 0.0668895841 0.0782786022 0.1593457907 0.0257236473 1.8525150000 0.9887920000 0.3334620000 0.0000050000 0.5209330000 0.0073610000 109970220 0 1784733696 3.9620704651 4.0104961395 4.0546360016 305 1305031239.6710560322 0.0636518151 0.0782306456 0.1593457907 0.0256969827 2.6187440000 0.9764090000 0.4508910000 0.1251330000 0.5219640000 0.5423160000 109972342 0 1786003456 3.9621031284 4.0140452385 4.0512089729 306 1305031239.7075550556 0.0627149716 0.0781799407 0.1593457907 0.0256923277 1.9692630000 0.9848900000 0.4467280000 0.0000050000 0.5282670000 0.0073180000 109974592 0 1787899904 3.9680020809 4.0149087906 4.0506563187 307 1305031239.7417550087 0.0631024987 0.0781308286 0.1593457907 0.0256515772 2.1113690000 0.9731580000 0.4419720000 0.1255760000 0.5611390000 0.0073210000 109976842 0 1784598528 3.9688260555 4.0141859055 4.0464649200 308 1305031239.7712600231 0.0634660944 0.0780832158 0.1593457907 0.0256114992 2.0303130000 0.9671750000 0.4452740000 0.0000050000 0.6086190000 0.0072820000 109978964 0 1785995264 3.9761347771 4.0153388977 4.0465817451 309 1305031239.8060870171 0.0649244636 0.0780406308 0.1593457907 0.0256514840 2.7885840000 0.9719750000 0.3660580000 0.1268610000 0.6496210000 0.6720320000 109981182 0 1787899904 3.9836673737 4.0149111748 4.0461220741 310 1305031239.8392889500 0.0605075806 0.0779840726 0.1593457907 0.0256632692 1.9907520000 0.9590060000 0.2958700000 0.0000040000 0.7265230000 0.0073720000 109983400 0 1784471552 3.9835350513 4.0223827362 4.0434336662 311 1305031239.8744299412 0.0587985851 0.0779223829 0.1593457907 0.0256290002 2.3327070000 0.9709420000 0.4364580000 0.1288650000 0.7870250000 0.0074190000 109985586 0 1785995264 3.9841258526 4.0257716179 4.0421500206 312 1305031239.9090619087 0.0614400096 0.0778695548 0.1593457907 0.0256340884 2.1439510000 0.9602300000 0.3252270000 0.0000040000 0.8490810000 0.0074240000 109987836 0 1787899904 3.9903442860 4.0281243324 4.0429868698 313 1305031239.9403729439 0.0635404810 0.0778237750 0.1593457907 0.0256198059 3.3255840000 0.9745170000 0.4037840000 0.1310700000 0.8945760000 0.9196110000 109989990 0 1784725504 3.9945361614 4.0320072174 4.0432982445 314 1305031239.9710669518 0.0673787370 0.0777905106 0.1593457907 0.0256327857 2.2214870000 0.9731560000 0.2909620000 0.0000040000 0.9479610000 0.0073870000 109992176 0 1786249216 4.0001897812 4.0358347893 4.0458397865 315 1305031240.0088651180 0.0722640306 0.0777729662 0.1593457907 0.0256578053 2.4358070000 0.9792890000 0.3285000000 0.1333010000 0.9851980000 0.0074210000 109994490 0 1788026880 4.0057048798 4.0337381363 4.0443406105 316 1305031240.0396599770 0.0785427615 0.0777754022 0.1593457907 0.0256233299 2.4591550000 0.9751480000 0.4359520000 0.0000050000 1.0385680000 0.0074900000 109996612 0 1784725504 4.0126805305 4.0340018272 4.0439400673 317 1305031240.0711870193 0.0863539875 0.0778024640 0.1593457907 0.0255836902 3.7298910000 0.9747210000 0.4425990000 0.1356140000 1.0741620000 1.1007540000 109998798 0 1786122240 4.0212821960 4.0321106911 4.0452871323 318 1305031240.1093459129 0.0925385505 0.0778488039 0.1593457907 0.0255967473 2.4455930000 0.9854630000 0.3276590000 0.0000050000 1.1228980000 0.0075210000 110001080 0 1788035072 4.0279903412 4.0274906158 4.0417032242 319 1305031240.1435019970 0.1004937440 0.0779197912 0.1593457907 0.0256175164 2.7484490000 0.9809660000 0.4404200000 0.1385430000 1.1789140000 0.0075090000 110003330 0 1784352768 4.0362291336 4.0222144127 4.0351157188 320 1305031240.1775770187 0.1040542051 0.0780014612 0.1593457907 0.0255890787 2.5424940000 0.9845260000 0.3267760000 0.0000040000 1.2216770000 0.0074860000 110005516 0 1785868288 4.0397477150 4.0289220810 4.0353922844 321 1305031240.2093310356 0.1089890897 0.0780979959 0.1593457907 0.0256352963 4.1512620000 1.0019050000 0.4409610000 0.1411560000 1.2676430000 1.2975250000 110007734 0 1787645952 4.0447201729 4.0289387703 4.0290660858 322 1305031240.2410049438 0.1113301739 0.0782012014 0.1593457907 0.0256208126 2.5860040000 0.9947970000 0.2577970000 0.0000040000 1.3238300000 0.0075430000 110009888 0 1784471552 4.0449218750 4.0368657112 4.0208559036 323 1305031240.2774341106 0.1143953353 0.0783132576 0.1593457907 0.0255898166 2.9637000000 1.0017060000 0.4503030000 0.1439970000 1.3578760000 0.0077180000 110012138 0 1785995264 4.0450830460 4.0516176224 4.0248746872 324 1305031240.3089289665 0.1151505411 0.0784269529 0.1593457907 0.0255631726 2.7297990000 1.0109110000 0.3020110000 0.0000040000 1.4072160000 0.0076110000 110014292 0 1788026880 4.0412302017 4.0602197647 4.0165433884 325 1305031240.3422729969 0.1186062768 0.0785505816 0.1593457907 0.0255540079 4.4818190000 1.0312280000 0.3386360000 0.1458070000 1.4561680000 1.5079160000 110016510 0 1785487360 4.0341720581 4.0796661377 4.0194473267 326 1305031240.3774259090 0.1254353672 0.0786943999 0.1593457907 0.0255647511 2.8779810000 1.0023580000 0.3728920000 0.0000040000 1.4931040000 0.0075130000 110018760 0 1787265024 4.0271253586 4.0982999802 4.0226621628 327 1305031240.4091110229 0.1271122247 0.0788424667 0.1593457907 0.0255339938 3.1180790000 0.9984850000 0.4393960000 0.1469490000 1.5235980000 0.0075940000 110020914 0 1785106432 4.0141978264 4.1108207703 4.0174570084 328 1305031240.4417860508 0.1372109205 0.0790204193 0.1593457907 0.0255050726 2.9897240000 0.9952420000 0.4430230000 0.0000040000 1.5418270000 0.0075730000 110023132 0 1786630144 4.0060415268 4.1273570061 4.0226078033 329 1305031240.4776389599 0.1479731947 0.0792300022 0.1593457907 0.0254764731 4.7128530000 0.9734550000 0.4317240000 0.1478330000 1.5531330000 1.6046110000 110025382 0 1784860672 3.9990303516 4.1422042847 4.0281100273 330 1305031240.5084490776 0.1531092376 0.0794538787 0.1593457907 0.0254506280 2.8777870000 0.9696140000 0.3299870000 0.0000040000 1.5686060000 0.0074880000 110027504 0 1786257408 3.9954414368 4.1486024857 4.0279188156 331 1305031240.5412700176 0.1633374989 0.0797073035 0.1633374989 0.0254539099 3.1210810000 0.9638340000 0.4285290000 0.1485390000 1.5704350000 0.0076590000 110029722 0 1785487360 3.9881448746 4.1612401009 4.0350756645 332 1305031240.5759088993 0.1691608876 0.0799767420 0.1691608876 0.0254296842 2.7482990000 0.9566930000 0.2129340000 0.0000050000 1.5692370000 0.0073250000 110031972 0 1786884096 3.9890327454 4.1661310196 4.0405011177 333 1305031240.6101338863 0.1672586203 0.0802388497 0.1691608876 0.0254007647 4.6486570000 0.9559940000 0.3481780000 0.1487540000 1.5629750000 1.6306550000 110034190 0 1784979456 3.9908468723 4.1637868881 4.0414314270 334 1305031240.6398229599 0.1638723463 0.0804892494 0.1691608876 0.0253864299 2.9632480000 0.9681180000 0.4349750000 0.0000040000 1.5506460000 0.0074000000 110036312 0 1786630144 3.9955158234 4.1586909294 4.0440344810 335 1305031240.6747570038 0.1545404196 0.0807102977 0.1691608876 0.0253562561 3.0974290000 0.9804490000 0.4360210000 0.1472290000 1.5240750000 0.0074260000 110038562 0 1784598528 4.0040030479 4.1464567184 4.0436058044 336 1305031240.7079319954 0.1490643322 0.0809137323 0.1691608876 0.0253537053 2.8421540000 0.9883990000 0.3334710000 0.0000050000 1.5106430000 0.0075090000 110040780 0 1785995264 4.0062522888 4.1399726868 4.0457501411 337 1305031240.7439579964 0.1464972645 0.0811083422 0.1691608876 0.0253258503 4.5698450000 1.0022340000 0.4416820000 0.1466320000 1.4657630000 1.5113460000 110042966 0 1787772928 4.0118966103 4.1354932785 4.0512609482 338 1305031240.7768330574 0.1351042688 0.0812680935 0.1691608876 0.0252976310 2.7704320000 0.9869620000 0.3329810000 0.0000050000 1.4407620000 0.0076160000 110045216 0 1785360384 4.0159454346 4.1214218140 4.0462870598 339 1305031240.8096249104 0.1320544928 0.0814179059 0.1691608876 0.0252802070 3.0135720000 1.0019770000 0.4415710000 0.1455730000 1.4147370000 0.0075890000 110047402 0 1787138048 4.0175914764 4.1174664497 4.0496826172 340 1305031240.8425960541 0.1274879873 0.0815534061 0.1691608876 0.0252657628 2.7547920000 1.0007160000 0.3698610000 0.0000050000 1.3745540000 0.0075150000 110049588 0 1784606720 4.0210905075 4.1106414795 4.0542392731 341 1305031240.8794100285 0.1141034141 0.0816488607 0.1691608876 0.0252440454 4.2015220000 0.9988540000 0.3331870000 0.1498420000 1.3462320000 1.3712650000 110051870 0 1786257408 4.0236711502 4.0927090645 4.0470285416 342 1305031240.9084498882 0.1080816016 0.0817261494 0.1691608876 0.0252260025 2.7718760000 0.9976490000 0.4502280000 0.0000040000 1.3142940000 0.0075360000 110054024 0 1787899904 4.0239892006 4.0849766731 4.0490531921 343 1305031240.9423189163 0.0885591134 0.0817460706 0.1691608876 0.0252405444 2.8501900000 0.9894790000 0.4426320000 0.1415730000 1.2667610000 0.0075800000 110056210 0 1785233408 4.0090751648 4.0729193687 4.0402975082 344 1305031240.9779360294 0.0794427618 0.0817393749 0.1691608876 0.0252146782 2.6549390000 0.9854960000 0.4374360000 0.0000040000 1.2222250000 0.0075180000 110058460 0 1786757120 4.0074648857 4.0601925850 4.0385818481 345 1305031241.0083029270 0.0734405890 0.0817153205 0.1691608876 0.0253063025 3.8813050000 0.9814880000 0.3924840000 0.1386030000 1.1720470000 1.1945120000 110060614 0 1784725504 4.0033040047 4.0599598885 4.0444364548 346 1305031241.0401480198 0.0691831782 0.0816791004 0.1691608876 0.0252860951 2.3689120000 0.9754670000 0.2798360000 0.0000040000 1.1039950000 0.0074280000 110062736 0 1786249216 4.0002470016 4.0637478828 4.0564455986 347 1305031241.0759329796 0.0610412620 0.0816196253 0.1691608876 0.0252718631 2.5065910000 0.9861390000 0.3230150000 0.1350820000 1.0525670000 0.0076280000 110065018 0 1788026880 3.9938364029 4.0616350174 4.0547657013 348 1305031241.1065559387 0.0546019115 0.0815419882 0.1691608876 0.0252443415 2.3145970000 0.9916080000 0.3214580000 0.0000050000 0.9918740000 0.0074500000 110067172 0 1785233408 3.9862167835 4.0641784668 4.0580682755 349 1305031241.1400520802 0.0497032441 0.0814507597 0.1691608876 0.0252365891 3.3983660000 0.9913270000 0.3904240000 0.1321690000 0.9263580000 0.9557900000 110069358 0 1786884096 3.9804999828 4.0654296875 4.0586123466 350 1305031241.1781818867 0.0446671583 0.0813456637 0.1691608876 0.0252395927 2.2907500000 0.9874440000 0.4280520000 0.0000040000 0.8655050000 0.0075450000 110071640 0 1784606720 3.9776284695 4.0626311302 4.0585494041 351 1305031241.2106790543 0.0386278592 0.0812239606 0.1691608876 0.0252098201 2.3334550000 0.9928490000 0.3905330000 0.1293090000 0.8111340000 0.0074220000 110073858 0 1786130432 3.9701793194 4.0592961311 4.0556702614 352 1305031241.2393150330 0.0381518230 0.0811015966 0.1691608876 0.0252532138 1.9474310000 0.9863610000 0.2107230000 0.0000050000 0.7407350000 0.0074130000 110075948 0 1787772928 3.9707067013 4.0531258583 4.0546631813 353 1305031241.2768468857 0.0374056101 0.0809778119 0.1691608876 0.0252411156 2.9083360000 0.9691970000 0.4261460000 0.1271510000 0.6777370000 0.7058750000 110078262 0 1785106432 3.9702951908 4.0496158600 4.0549187660 354 1305031241.3063299656 0.0358879752 0.0808504395 0.1691608876 0.0252071907 2.0255050000 0.9701260000 0.4271650000 0.0000050000 0.6186290000 0.0073160000 110080416 0 1786503168 3.9684379101 4.0501041412 4.0564999580 355 1305031241.3424758911 0.0354926176 0.0807226710 0.1691608876 0.0251944623 2.0978030000 0.9686970000 0.4269680000 0.1254200000 0.5670590000 0.0073390000 110082666 0 1785614336 3.9726741314 4.0477385521 4.0626907349 356 1305031241.3795149326 0.0401036516 0.0806085726 0.1691608876 0.0252345449 1.9663390000 0.9874630000 0.4430100000 0.0000050000 0.5262420000 0.0073100000 110084916 0 1787011072 3.9703919888 4.0410776138 4.0622200966 357 1305031241.4096820354 0.0438968353 0.0805057386 0.1691608876 0.0252167908 2.6158420000 0.9915830000 0.4439830000 0.1250020000 0.5158740000 0.5371050000 110087070 0 1784725504 3.9699995518 4.0382857323 4.0645742416 358 1305031241.4455459118 0.0470740981 0.0804123541 0.1691608876 0.0251949445 1.8174640000 0.9894200000 0.2989930000 0.0000040000 0.5192690000 0.0073430000 110089320 0 1786376192 3.9699339867 4.0375123024 4.0694050789 359 1305031241.4775071144 0.0510258861 0.0803304977 0.1691608876 0.0253690899 1.9286380000 0.9813990000 0.2893470000 0.1252460000 0.5230400000 0.0073120000 110091506 0 1788153856 3.9683856964 4.0334773064 4.0717968941 360 1305031241.5098490715 0.0550870448 0.0802603770 0.1691608876 0.0253635723 1.9005010000 0.9674450000 0.4013330000 0.0000050000 0.5221560000 0.0073130000 110093692 0 1785106432 3.9650731087 4.0293931961 4.0711460114 361 1305031241.5477299690 0.0579816550 0.0801986631 0.1691608876 0.0253398854 2.5984370000 0.9682080000 0.4391050000 0.1254030000 0.5189260000 0.5445140000 110096006 0 1786503168 3.9610579014 4.0269131660 4.0671820641 362 1305031241.5783948898 0.0579620972 0.0801372361 0.1691608876 0.0253218796 1.8886380000 0.9621750000 0.4026400000 0.0000050000 0.5142640000 0.0072870000 110098128 0 1785741312 3.9624366760 4.0268774033 4.0683140755 363 1305031241.6092638969 0.0592635684 0.0800797329 0.1691608876 0.0253202842 2.0641100000 0.9691640000 0.4444000000 0.1255200000 0.5154590000 0.0072640000 110100282 0 1787138048 3.9628567696 4.0255117416 4.0656800270 364 1305031241.6475839615 0.0619515367 0.0800299301 0.1691608876 0.0252903180 1.7980750000 0.9811850000 0.2939280000 0.0000050000 0.5133040000 0.0073530000 110102596 0 1784725504 3.9632203579 4.0218367577 4.0631752014 365 1305031241.6783659458 0.0556920171 0.0799632509 0.1691608876 0.0253212502 2.5859450000 0.9933910000 0.4058540000 0.1249420000 0.5202210000 0.5392360000 110104782 0 1786249216 3.9649853706 4.0282678604 4.0627532005 366 1305031241.7098269463 0.0551264957 0.0798953909 0.1691608876 0.0252931131 1.8198340000 0.9676390000 0.3280390000 0.0000050000 0.5144660000 0.0072750000 110106904 0 1788289024 3.9650084972 4.0287761688 4.0605096817 367 1305031241.7471020222 0.0532323532 0.0798227396 0.1691608876 0.0252632145 1.9412410000 0.9647960000 0.3275000000 0.1250090000 0.5143120000 0.0073170000 110109218 0 1784733696 3.9656391144 4.0302042961 4.0594596863 368 1305031241.7782680988 0.0535815097 0.0797514319 0.1691608876 0.0252437516 1.8632590000 0.9714380000 0.3669930000 0.0000050000 0.5151020000 0.0072930000 110111404 0 1786130432 3.9661619663 4.0297961235 4.0580277443 369 1305031241.8098289967 0.0506209508 0.0796724875 0.1691608876 0.0252429303 2.5745810000 0.9556660000 0.4369030000 0.1251160000 0.5167160000 0.5378480000 110113526 0 1788026880 3.9657785892 4.0328722000 4.0577616692 370 1305031241.8464360237 0.0535727814 0.0796019478 0.1691608876 0.0252504675 1.8400540000 0.9723030000 0.3363980000 0.0000040000 0.5217240000 0.0072900000 110115808 0 1784852480 3.9651322365 4.0293607712 4.0549445152 371 1305031241.8787989616 0.0527731329 0.0795296329 0.1691608876 0.0253220972 2.0945670000 0.9818600000 0.4489430000 0.1258400000 0.5282540000 0.0073210000 110118026 0 1786249216 3.9637289047 4.0304880142 4.0537061691 372 1305031241.9114871025 0.0478338227 0.0794444291 0.1691608876 0.0253515491 1.8969190000 0.9768480000 0.3721420000 0.0000040000 0.5382470000 0.0073410000 110120212 0 1785614336 3.9661309719 4.0359096527 4.0567026138 373 1305031241.9477050304 0.0488531888 0.0793624151 0.1691608876 0.0253365077 2.6564930000 0.9804210000 0.4502030000 0.1254580000 0.5380960000 0.5599190000 110122462 0 1787138048 3.9663560390 4.0349898338 4.0560822487 374 1305031241.9783430099 0.0480289012 0.0792786356 0.1691608876 0.0254432745 1.9777590000 0.9692130000 0.4595330000 0.0000040000 0.5392180000 0.0072980000 110124648 0 1784852480 3.9665660858 4.0362553596 4.0563325882 375 1305031242.0105700493 0.0467310734 0.0791918421 0.1691608876 0.0255249849 1.9423810000 0.9646730000 0.3049370000 0.1254860000 0.5375080000 0.0073710000 110126802 0 1786376192 3.9635488987 4.0378088951 4.0549702644 376 1305031242.0463600159 0.0477007031 0.0791080891 0.1691608876 0.0255792749 1.9560350000 0.9557640000 0.4556310000 0.0000040000 0.5350300000 0.0072540000 110129052 0 1785487360 3.9595947266 4.0367283821 4.0524682999 377 1305031242.0795490742 0.0501569100 0.0790312955 0.1691608876 0.0256633732 2.5297540000 0.9578460000 0.3429740000 0.1252910000 0.5402010000 0.5610580000 110131238 0 1787011072 3.9536190033 4.0343341827 4.0481410027 378 1305031242.1105840206 0.0536001213 0.0789640173 0.1691608876 0.0257227324 1.7571460000 0.9488990000 0.2650730000 0.0000050000 0.5335700000 0.0072100000 110133424 0 1784725504 3.9490463734 4.0307440758 4.0445384979 379 1305031242.1466050148 0.0575010888 0.0789073869 0.1691608876 0.0258154367 1.9924020000 0.9494750000 0.3783370000 0.1249190000 0.5299150000 0.0073000000 110135674 0 1786249216 3.9454772472 4.0266346931 4.0415730476 380 1305031242.1797080040 0.0635266155 0.0788669111 0.1691608876 0.0258952392 1.7846090000 0.9486820000 0.2996250000 0.0000050000 0.5266000000 0.0072150000 110137892 0 1788026880 3.9391646385 4.0205855370 4.0371427536 381 1305031242.2087249756 0.0678741634 0.0788380588 0.1691608876 0.0259209163 2.6048360000 0.9438320000 0.4481110000 0.1250850000 0.5275670000 0.5578430000 110140014 0 1785233408 3.9359135628 4.0151257515 4.0348711014 382 1305031242.2478089333 0.0716092214 0.0788191351 0.1691608876 0.0259652063 1.7753520000 0.9338660000 0.3023340000 0.0000050000 0.5295540000 0.0071930000 110142328 0 1786757120 3.9332430363 4.0102400780 4.0327095985 383 1305031242.2794981003 0.0730411783 0.0788040491 0.1691608876 0.0259980624 2.0558630000 0.9404560000 0.4499150000 0.1249660000 0.5307990000 0.0072340000 110144514 0 1784860672 3.9319598675 4.0084514618 4.0310702324 384 1305031242.3097639084 0.0759702697 0.0787966694 0.1691608876 0.0260041012 1.9311920000 0.9365070000 0.4524700000 0.0000040000 0.5325120000 0.0072850000 110146636 0 1786384384 3.9306817055 4.0045289993 4.0289864540 385 1305031242.3471269608 0.0772882774 0.0787927515 0.1691608876 0.0260843458 2.5709730000 0.9302860000 0.4140040000 0.1252870000 0.5340450000 0.5649110000 110148950 0 1785495552 3.9309337139 4.0016031265 4.0275049210 386 1305031242.3784790039 0.0770163462 0.0787881495 0.1691608876 0.0261759772 1.7346520000 0.9265340000 0.2620040000 0.0000050000 0.5365000000 0.0072010000 110151136 0 1787138048 3.9303746223 4.0007638931 4.0267376900 387 1305031242.4109969139 0.0787134096 0.0787879563 0.1691608876 0.0262193990 2.0106190000 0.9269210000 0.4104070000 0.1259860000 0.5375900000 0.0072880000 110153322 0 1784852480 3.9302237034 3.9975676537 4.0250873566 388 1305031242.4470989704 0.0795666799 0.0787899633 0.1691608876 0.0263382723 1.9015950000 0.9328020000 0.4175040000 0.0000050000 0.5415700000 0.0072150000 110155604 0 1786376192 3.9288389683 3.9954245090 4.0224637985 389 1305031242.4776470661 0.0804227218 0.0787941607 0.1691608876 0.0264181893 2.5226090000 0.9592070000 0.3045500000 0.1255900000 0.5461980000 0.5846330000 110157790 0 1788026880 3.9277851582 3.9945671558 4.0193567276 390 1305031242.5097260475 0.0841014311 0.0788077691 0.1691608876 0.0266110296 1.9616490000 0.9351950000 0.4612970000 0.0000050000 0.5554950000 0.0072170000 110159976 0 1785233408 3.9238004684 3.9912161827 4.0140724182 391 1305031242.5485460758 0.0825776234 0.0788174106 0.1691608876 0.0270213171 1.9632280000 0.9500210000 0.3158920000 0.1255720000 0.5619570000 0.0072880000 110162290 0 1786884096 3.9223101139 3.9930961132 4.0118045807 392 1305031242.5748429298 0.0838367119 0.0788302150 0.1691608876 0.0271340234 1.7996130000 0.9477850000 0.2724630000 0.0000050000 0.5695580000 0.0072360000 110164348 0 1784598528 3.9196879864 3.9934573174 4.0086016655 393 1305031242.6061151028 0.0895507783 0.0788574938 0.1691608876 0.0271883779 2.6832020000 0.9253280000 0.4492420000 0.1256250000 0.5733180000 0.6071610000 110166566 0 1785995264 3.9119906425 3.9908852577 4.0021896362 394 1305031242.6438109875 0.0918221623 0.0788903990 0.1691608876 0.0273861205 1.9743300000 0.9278950000 0.4568610000 0.0000050000 0.5795710000 0.0073880000 110168848 0 1788026880 3.9086210728 3.9903683662 3.9985983372 395 1305031242.6752018929 0.0909835026 0.0789210145 0.1691608876 0.0276628834 2.0340520000 0.9390770000 0.3856270000 0.1253110000 0.5740710000 0.0073470000 110171066 0 1785233408 3.9076664448 3.9914233685 3.9976422787 396 1305031242.7139821053 0.0917515904 0.0789534149 0.1691608876 0.0279869794 1.8091810000 0.9473420000 0.2730770000 0.0000050000 0.5788100000 0.0074120000 110173412 0 1786884096 3.9047102928 3.9921815395 3.9960598946 397 1305031242.7452580929 0.0947657004 0.0789932443 0.1691608876 0.0280390054 2.7205390000 0.9444760000 0.4574460000 0.1249990000 0.5789270000 0.6121780000 110175598 0 1784725504 3.9004580975 3.9921102524 3.9926707745 398 1305031242.7775399685 0.0989046916 0.0790432731 0.1691608876 0.0281671731 1.9781800000 0.9302040000 0.4518110000 0.0000050000 0.5863740000 0.0072130000 110177816 0 1786376192 3.8940231800 3.9902353287 3.9892792702 399 1305031242.8140709400 0.0962897390 0.0790864973 0.1691608876 0.0283605798 2.1113360000 0.9408840000 0.4519860000 0.1246650000 0.5839900000 0.0072900000 110180098 0 1788162048 3.8968811035 3.9940915108 3.9911053181 400 1305031242.8443179131 0.0992131159 0.0791368139 0.1691608876 0.0283880949 1.9825770000 0.9397970000 0.4465870000 0.0000050000 0.5864470000 0.0072590000 110182284 0 1785114624 3.8919789791 3.9939665794 3.9893255234 401 1305031242.8740880489 0.1046546251 0.0792004493 0.1691608876 0.0284121610 2.7208100000 0.9330820000 0.4537690000 0.1243230000 0.5880790000 0.6190250000 110184502 0 1786503168 3.8853323460 3.9909234047 3.9876255989 402 1305031242.9137070179 0.1120540872 0.0792821748 0.1691608876 0.0284718315 1.9866860000 0.9330530000 0.4490490000 0.0000050000 0.5946300000 0.0072810000 110186880 0 1785741312 3.8758752346 3.9902510643 3.9833014011 403 1305031242.9444379807 0.1110578179 0.0793610225 0.1691608876 0.0286090285 2.0876790000 0.9366810000 0.4193310000 0.1232710000 0.5986330000 0.0072280000 110189066 0 1787265024 3.8751747608 3.9947726727 3.9837474823 404 1305031242.9760620594 0.1144248769 0.0794478142 0.1691608876 0.0286455505 2.0057570000 0.9464010000 0.4540790000 0.0000050000 0.5952880000 0.0073490000 110191252 0 1784725504 3.8665702343 3.9976952076 3.9812960625 405 1305031243.0141661167 0.1182218269 0.0795435525 0.1691608876 0.0286896914 2.6713190000 0.9349890000 0.4053580000 0.1226130000 0.5849130000 0.6209250000 110193566 0 1786376192 3.8602325916 3.9985113144 3.9805819988 406 1305031243.0469100475 0.1172645837 0.0796364615 0.1691608876 0.0286840308 1.9802870000 0.9391130000 0.4446960000 0.0000050000 0.5865900000 0.0072310000 110195880 0 1788026880 3.8591692448 4.0013523102 3.9817564487 407 1305031243.0780448914 0.1180906743 0.0797309436 0.1691608876 0.0286702540 1.9176800000 0.9428020000 0.2604690000 0.1224690000 0.5821080000 0.0072840000 110198098 0 1785233408 3.8562192917 4.0036182404 3.9811964035 408 1305031243.1136150360 0.1192611679 0.0798278314 0.1691608876 0.0286693095 1.8673300000 0.9312060000 0.3334790000 0.0000050000 0.5927880000 0.0073110000 110200348 0 1786757120 3.8519623280 4.0063366890 3.9798772335 409 1305031243.1458160877 0.1217616200 0.0799303590 0.1691608876 0.0286391299 2.6834490000 0.9258490000 0.4309380000 0.1219080000 0.5868420000 0.6153370000 110202598 0 1784471552 3.8463165760 4.0090823174 3.9768781662 410 1305031243.1780760288 0.1209146753 0.0800303207 0.1691608876 0.0286261258 1.7889770000 0.9376170000 0.2456460000 0.0000050000 0.5958820000 0.0072920000 110204816 0 1785995264 3.8449168205 4.0108900070 3.9759805202 411 1305031243.2136580944 0.1153397784 0.0801162318 0.1691608876 0.0286367616 1.9713920000 0.9301460000 0.3300930000 0.1219770000 0.5792550000 0.0072670000 110207098 0 1787772928 3.8512892723 4.0095472336 3.9800140858 412 1305031243.2455608845 0.1174483746 0.0802068438 0.1691608876 0.0288972588 1.8919180000 0.9279480000 0.3775770000 0.0000050000 0.5765480000 0.0072720000 110209316 0 1784725504 3.8519690037 4.0052499771 3.9794955254 413 1305031243.2781798840 0.1105515584 0.0802803177 0.1691608876 0.0289622832 2.7082140000 0.9493910000 0.4501420000 0.1225430000 0.5770310000 0.6065260000 110211566 0 1786122240 3.8642263412 4.0052151680 3.9824960232 414 1305031243.3142709732 0.1139515713 0.0803616492 0.1691608876 0.0290014146 2.0046480000 0.9293360000 0.4852110000 0.0000040000 0.5802060000 0.0072150000 110213816 0 1788026880 3.8617644310 3.9994707108 3.9843125343 415 1305031243.3460359573 0.1143420264 0.0804435297 0.1691608876 0.0293092310 2.1041720000 0.9417700000 0.4516670000 0.1241750000 0.5766350000 0.0073300000 110216066 0 1784979456 3.8650548458 3.9972343445 3.9853043556 416 1305031243.3789350986 0.1076773778 0.0805089956 0.1691608876 0.0293424041 1.9855150000 0.9399010000 0.4588480000 0.0000060000 0.5769000000 0.0072720000 110218316 0 1786765312 3.8770489693 4.0009045601 3.9895269871 417 1305031243.4139740467 0.1127150208 0.0805862283 0.1691608876 0.0294196743 2.6817990000 0.9242790000 0.4463260000 0.1243440000 0.5771170000 0.6070660000 110220566 0 1784479744 3.8678479195 4.0000224113 3.9889321327 418 1305031243.4470911026 0.1062041000 0.0806475151 0.1691608876 0.0296182042 1.8969720000 0.9492610000 0.3690190000 0.0000050000 0.5687830000 0.0072590000 110222816 0 1786122240 3.8795773983 4.0044364929 3.9934108257 419 1305031243.4780371189 0.1070884764 0.0807106200 0.1691608876 0.0296460224 2.1201350000 0.9481690000 0.4713390000 0.1245910000 0.5659330000 0.0073600000 110225002 0 1787772928 3.8782384396 4.0076169968 3.9934093952 420 1305031243.5154008865 0.1080259904 0.0807756566 0.1691608876 0.0297476205 1.9916250000 0.9458840000 0.4686680000 0.0000040000 0.5668680000 0.0074120000 110227316 0 1784598528 3.8727173805 4.0121331215 3.9934031963 421 1305031243.5459430218 0.1068995148 0.0808377085 0.1691608876 0.0297990660 2.6931130000 0.9467200000 0.4530230000 0.1246100000 0.5669120000 0.5992050000 110229534 0 1786249216 3.8736913204 4.0152530670 3.9942426682 422 1305031243.5779840946 0.1019139364 0.0808876522 0.1691608876 0.0297896077 1.8353320000 0.9579180000 0.3121870000 0.0000040000 0.5552090000 0.0073820000 110231688 0 1788153856 3.8761332035 4.0211420059 3.9975993633 423 1305031243.6140549183 0.0999045596 0.0809326094 0.1691608876 0.0300371226 2.0495320000 0.9421500000 0.4241380000 0.1250220000 0.5482970000 0.0072970000 110233938 0 1784598528 3.8774185181 4.0250968933 3.9990768433 424 1305031243.6461870670 0.1026882082 0.0809839198 0.1691608876 0.0303021136 2.0107050000 0.9733790000 0.4794220000 0.0000050000 0.5478650000 0.0073950000 110236188 0 1786122240 3.8755733967 4.0227808952 3.9967358112 425 1305031243.6782801151 0.1067893803 0.0810446385 0.1691608876 0.0303288180 2.5811980000 0.9677220000 0.3297260000 0.1249920000 0.5651850000 0.5908930000 110238374 0 1788153856 3.8708665371 4.0188345909 3.9947824478 426 1305031243.7142961025 0.0975207090 0.0810833148 0.1691608876 0.0306478616 2.0495360000 0.9682360000 0.4773540000 0.0000050000 0.5939190000 0.0073510000 110240592 0 1784852480 3.8801052570 4.0276408195 3.9992737770 427 1305031243.7473781109 0.0977712423 0.0811223966 0.1691608876 0.0308888144 2.1884240000 0.9708260000 0.4827860000 0.1253840000 0.5993360000 0.0074400000 110242810 0 1786503168 3.8837351799 4.0252308846 3.9991302490 428 1305031243.7790360451 0.0982179940 0.0811623395 0.1691608876 0.0310257995 1.9021600000 0.9684800000 0.3025180000 0.0000050000 0.6209960000 0.0075080000 110244964 0 1785741312 3.8844413757 4.0202169418 4.0009927750 429 1305031243.8141930103 0.0887837559 0.0811801051 0.1691608876 0.0314577046 2.7582730000 0.9857720000 0.3369870000 0.1260340000 0.6368770000 0.6699260000 110247182 0 1787138048 3.8993623257 4.0245509148 4.0072021484 430 1305031243.8462920189 0.0875536203 0.0811949272 0.1691608876 0.0317535664 2.1864040000 0.9902860000 0.5121430000 0.0000050000 0.6738120000 0.0074660000 110249368 0 1784598528 3.9083695412 4.0225853920 4.0093021393 431 1305031243.8788089752 0.0817439258 0.0811962010 0.1691608876 0.0318511621 2.3537290000 0.9878870000 0.5088670000 0.1267830000 0.7200160000 0.0075000000 110251586 0 1786249216 3.9168677330 4.0250320435 4.0144519806 432 1305031243.9140000343 0.0737876669 0.0811790516 0.1691608876 0.0320491084 2.0787650000 0.9723550000 0.3343970000 0.0000050000 0.7616900000 0.0075960000 110253772 0 1787908096 3.9260449409 4.0292792320 4.0211253166 433 1305031243.9470779896 0.0644167736 0.0811403396 0.1691608876 0.0321551331 3.2150010000 0.9807730000 0.4938460000 0.1292610000 0.7941890000 0.8142010000 110256022 0 1784733696 3.9369487762 4.0374350548 4.0302095413 434 1305031243.9816520214 0.0566093661 0.0810838167 0.1691608876 0.0322329575 2.2895920000 0.9779510000 0.4765560000 0.0000050000 0.8248070000 0.0075880000 110258240 0 1786122240 3.9453678131 4.0444035530 4.0396461487 435 1305031244.0112700462 0.0537556224 0.0810209932 0.1691608876 0.0322828530 2.4484170000 0.9854340000 0.4748710000 0.1300120000 0.8477630000 0.0074650000 110260394 0 1788153856 3.9519062042 4.0490703583 4.0446157455 436 1305031244.0438230038 0.0494253300 0.0809485261 0.1691608876 0.0322900144 2.2726500000 0.9666480000 0.4299520000 0.0000050000 0.8657170000 0.0074320000 110262580 0 1784725504 3.9522302151 4.0590691566 4.0469274521 437 1305031244.0818090439 0.0466927439 0.0808701376 0.1691608876 0.0323259195 3.3204640000 0.9640620000 0.4633310000 0.1315950000 0.8680930000 0.8906650000 110264862 0 1786122240 3.9491820335 4.0644907951 4.0463085175 438 1305031244.1127901077 0.0484921150 0.0807962152 0.1691608876 0.0324076539 2.2140300000 0.9764140000 0.3546060000 0.0000040000 0.8727830000 0.0074060000 110267048 0 1788153856 3.9540600777 4.0641865730 4.0479574203 439 1305031244.1484949589 0.0461128876 0.0807172099 0.1691608876 0.0323987656 2.3333220000 0.9948220000 0.3182380000 0.1313730000 0.8786050000 0.0075130000 110269298 0 1784852480 3.9548208714 4.0694684982 4.0508441925 440 1305031244.1824309826 0.0430777185 0.0806316656 0.1691608876 0.0324610991 2.3117670000 0.9576060000 0.4664690000 0.0000040000 0.8773940000 0.0073900000 110271484 0 1786376192 3.9576444626 4.0752320290 4.0558166504 441 1305031244.2124009132 0.0435887873 0.0805476681 0.1691608876 0.0325662069 3.1829010000 0.9655560000 0.3156640000 0.1317870000 0.8730870000 0.8940030000 110273670 0 1785487360 3.9613854885 4.0778598785 4.0580134392 442 1305031244.2473471165 0.0413408987 0.0804589650 0.1691608876 0.0327139696 2.1524740000 0.9533220000 0.3136380000 0.0000040000 0.8752610000 0.0074460000 110275888 0 1787265024 3.9642312527 4.0831708908 4.0606584549 443 1305031244.2831470966 0.0388255231 0.0803649843 0.1691608876 0.0328282861 2.2614430000 0.9658250000 0.2772700000 0.1319060000 0.8763050000 0.0073470000 110278138 0 1784979456 3.9689736366 4.0883188248 4.0642590523 444 1305031244.3137950897 0.0382273495 0.0802700797 0.1691608876 0.0329475874 2.1205290000 0.9590900000 0.2791750000 0.0000050000 0.8718910000 0.0075030000 110280260 0 1786630144 3.9739315510 4.0958681107 4.0673227310 445 1305031244.3459599018 0.0397804528 0.0801790918 0.1691608876 0.0331043046 3.1160380000 0.9613300000 0.2779340000 0.1315360000 0.8618840000 0.8805400000 110282478 0 1784860672 3.9797828197 4.1040973663 4.0702524185 446 1305031244.3808560371 0.0388635136 0.0800864560 0.1691608876 0.0332344280 2.1291600000 0.9565520000 0.3177390000 0.0000050000 0.8447120000 0.0073280000 110284696 0 1786638336 3.9812912941 4.1093463898 4.0691232681 447 1305031244.4130189419 0.0434455946 0.0800044854 0.1691608876 0.0334187520 2.2187760000 0.9622350000 0.2802160000 0.1313550000 0.8347690000 0.0073930000 110286882 0 1784479744 3.9898457527 4.1169247627 4.0721120834 448 1305031244.4451670647 0.0451807976 0.0799267539 0.1691608876 0.0334811503 2.0809060000 0.9676840000 0.2797310000 0.0000040000 0.8233040000 0.0073840000 110289068 0 1786003456 3.9908614159 4.1271567345 4.0710282326 449 1305031244.4806590080 0.0448644012 0.0798486641 0.1691608876 0.0335307252 3.0182480000 0.9616040000 0.2762130000 0.1365680000 0.8117520000 0.8292210000 110291318 0 1787772928 3.9891288280 4.1328015327 4.0685515404 450 1305031244.5142281055 0.0461548604 0.0797737889 0.1691608876 0.0336284838 2.2012060000 0.9558520000 0.4277240000 0.0000050000 0.8074820000 0.0073370000 110293536 0 1785233408 3.9883298874 4.1372675896 4.0665178299 451 1305031244.5462141037 0.0461324602 0.0796991962 0.1691608876 0.0336111110 2.3725340000 0.9581530000 0.4655050000 0.1313850000 0.8073580000 0.0073430000 110295722 0 1786757120 3.9853034019 4.1443777084 4.0671954155 452 1305031244.5808050632 0.0441348441 0.0796205140 0.1691608876 0.0336507358 2.0746760000 0.9620810000 0.3072100000 0.0000040000 0.7952060000 0.0073690000 110297940 0 1784725504 3.9820721149 4.1462702751 4.0671114922 453 1305031244.6132769585 0.0431478582 0.0795400004 0.1691608876 0.0337271708 3.1529470000 0.9514380000 0.4613580000 0.1305590000 0.7970900000 0.8096570000 110300158 0 1786249216 3.9803404808 4.1475992203 4.0668182373 454 1305031244.6428399086 0.0431661755 0.0794598819 0.1691608876 0.0337096179 2.2183410000 0.9607200000 0.4568380000 0.0000040000 0.7905070000 0.0073290000 110302280 0 1785614336 3.9781885147 4.1528186798 4.0684518814 455 1305031244.6806099415 0.0425175838 0.0793786900 0.1691608876 0.0337615110 2.3714910000 0.9869700000 0.4584430000 0.1302470000 0.7855200000 0.0073930000 110304530 0 1787011072 3.9780585766 4.1558198929 4.0713691711 456 1305031244.7152500153 0.0402369983 0.0792928530 0.1691608876 0.0337689881 2.2072290000 0.9601910000 0.4592260000 0.0000050000 0.7775300000 0.0074310000 110306780 0 1784844288 3.9748399258 4.1589384079 4.0722613335 457 1305031244.7458879948 0.0384002812 0.0792033725 0.1691608876 0.0339397207 3.1136070000 0.9559960000 0.4599360000 0.1291150000 0.7763010000 0.7894050000 110308934 0 1786376192 3.9757399559 4.1576294899 4.0737314224 458 1305031244.7818510532 0.0359517708 0.0791089367 0.1691608876 0.0340427245 2.1982520000 0.9470760000 0.4664960000 0.0000040000 0.7743680000 0.0073440000 110311216 0 1785614336 3.9731259346 4.1552457809 4.0702562332 459 1305031244.8140940666 0.0271078106 0.0789956445 0.1691608876 0.0348784561 2.3421100000 0.9526100000 0.4645600000 0.1287560000 0.7859260000 0.0073900000 110313402 0 1787011072 3.9756643772 4.1598672867 4.0714349747 460 1305031244.8418219090 0.0306352898 0.0788905133 0.1691608876 0.0348761844 2.2246730000 0.9524160000 0.4624590000 0.0000050000 0.7995220000 0.0074160000 110315492 0 1784987648 3.9744505882 4.1617093086 4.0667676926 461 1305031244.8818008900 0.0356443785 0.0787967039 0.1691608876 0.0348471928 3.1747980000 0.9403470000 0.4485120000 0.1291420000 0.8200070000 0.8339010000 110317806 0 1786384384 3.9665560722 4.1673831940 4.0605025291 462 1305031244.9149079323 0.0356443785 0.0787033006 0.1691608876 0.0348093771 2.2052940000 0.9389190000 0.4426650000 0.0000050000 0.8134940000 0.0073250000 110319992 0 1785622528 3.9665560722 4.1673831940 4.0605025291 463 1305031244.9458680153 0.0348921940 0.0786086761 0.1691608876 0.0347824286 2.2671350000 0.9817000000 0.4604120000 0.0000050000 0.8147640000 0.0073520000 110322146 0 1787011072 3.9665560722 4.1673831940 4.0605025291 464 1305031244.9818000793 0.0388853773 0.0785230656 0.1691608876 0.0348952458 2.2101460000 0.9212580000 0.4499500000 0.0000050000 0.8287830000 0.0072750000 110324396 0 1784852480 3.9745576382 4.1827731133 4.0714135170 465 1305031245.0140550137 0.0388853773 0.0784378232 0.1691608876 0.0348576229 3.0791290000 0.9449810000 0.4472420000 0.0000040000 0.8348250000 0.8491710000 110326582 0 1786249216 3.9745576382 4.1827731133 4.0714135170 466 1305031245.0464398861 0.0433022678 0.0783624250 0.1691608876 0.0348280741 2.2145810000 0.9402280000 0.4277500000 0.0000040000 0.8362230000 0.0073550000 110328768 0 1788153856 3.9724161625 4.1888942719 4.0714383125 467 1305031245.0817689896 0.0441802964 0.0782892299 0.1691608876 0.0347941370 2.2149820000 0.9318920000 0.4297250000 0.0000040000 0.8430810000 0.0072880000 110331018 0 1784725504 3.9724161625 4.1888942719 4.0714383125 468 1305031245.1143150330 0.0461744741 0.0782206086 0.1691608876 0.0347620666 2.2475750000 0.9531480000 0.4423110000 0.0000050000 0.8417570000 0.0073360000 110333172 0 1786376192 3.9724161625 4.1888942719 4.0714383125 469 1305031245.1457099915 0.0495609716 0.0781595007 0.1691608876 0.0347256098 3.0967700000 0.9560800000 0.4386310000 0.0000040000 0.8425490000 0.8565730000 110335390 0 1788153856 3.9724161625 4.1888942719 4.0714383125 470 1305031245.1818709373 0.0532294177 0.0781064579 0.1691608876 0.0346967480 2.2349360000 0.9558790000 0.4316330000 0.0000050000 0.8371120000 0.0073500000 110337608 0 1784725504 3.9724161625 4.1888942719 4.0714383125 471 1305031245.2140939236 0.0590290502 0.0780659539 0.1691608876 0.0346849637 2.2796660000 0.9660540000 0.4600280000 0.0000050000 0.8429590000 0.0074300000 110339794 0 1786122240 3.9724161625 4.1888942719 4.0714383125 472 1305031245.2487950325 0.0634476244 0.0780349829 0.1691608876 0.0346917737 2.3147990000 0.9690680000 0.4960020000 0.0000050000 0.8393240000 0.0074320000 110342044 0 1788026880 3.9724161625 4.1888942719 4.0714383125 473 1305031245.2807950974 0.0507638007 0.0779773271 0.1691608876 0.0363817089 3.3984160000 0.9621710000 0.5132050000 0.1351220000 0.8865260000 0.8983770000 110344198 0 1784852480 3.9696178436 4.1663913727 4.0684876442 474 1305031245.3143179417 0.0549661219 0.0779287802 0.1691608876 0.0365301467 2.3400210000 0.9675660000 0.4726880000 0.0000040000 0.8892560000 0.0075120000 110346384 0 1786511360 3.9699141979 4.1659712791 4.0705184937 475 1305031245.3491809368 0.0542942062 0.0778790232 0.1691608876 0.0367427357 2.5019420000 0.9677390000 0.4871910000 0.1336770000 0.9027970000 0.0075580000 110348666 0 1784098816 3.9684543610 4.1598711014 4.0681653023 476 1305031245.3806860447 0.0518900976 0.0778244247 0.1691608876 0.0369255167 2.3548240000 0.9603540000 0.4766280000 0.0000050000 0.9074770000 0.0073950000 110350788 0 1785749504 3.9652609825 4.1513037682 4.0619778633 477 1305031245.4133110046 0.0507736206 0.0777677144 0.1691608876 0.0370806329 3.1801230000 0.9540200000 0.2744750000 0.1338370000 0.9016840000 0.9131130000 110352974 0 1787518976 3.9622635841 4.1431608200 4.0575685501 478 1305031245.4489970207 0.0511727370 0.0777120763 0.1691608876 0.0370631685 2.1623960000 0.9517270000 0.3063780000 0.0000040000 0.8939260000 0.0073960000 110355192 0 1784852480 3.9674060345 4.1300840378 4.0529403687 479 1305031245.4846711159 0.0538007244 0.0776621570 0.1691608876 0.0372676102 2.3810820000 0.9844460000 0.3244980000 0.1330150000 0.9287180000 0.0074200000 110357442 0 1786249216 3.9671683311 4.1277456284 4.0497965813 480 1305031245.5124320984 0.0516015515 0.0776078641 0.1691608876 0.0373536766 2.1572910000 0.9474470000 0.2687520000 0.0000040000 0.9307100000 0.0073960000 110359564 0 1788153856 3.9617743492 4.1232862473 4.0444102287 481 1305031245.5481460094 0.0506398007 0.0775517974 0.1691608876 0.0374869032 3.2357030000 0.9558430000 0.2679740000 0.1328530000 0.9322630000 0.9437700000 110361782 0 1784979456 3.9572362900 4.1177458763 4.0395102501 482 1305031245.5786890984 0.0515255108 0.0774978010 0.1691608876 0.0374943242 2.2280400000 0.9582100000 0.3458750000 0.0000050000 0.9135310000 0.0073970000 110363968 0 1786630144 3.9578464031 4.1133580208 4.0376062393 483 1305031245.6104750633 0.0513205566 0.0774436038 0.1691608876 0.0375514252 2.3640320000 0.9576880000 0.3536860000 0.1323150000 0.9099240000 0.0074300000 110366122 0 1784598528 3.9538054466 4.1062521935 4.0312275887 484 1305031245.6494629383 0.0510759912 0.0773891253 0.1691608876 0.0377053260 2.3308240000 0.9592930000 0.4575290000 0.0000050000 0.9035850000 0.0073470000 110368404 0 1785995264 3.9519460201 4.1031303406 4.0294299126 485 1305031245.6802349091 0.0507319719 0.0773341621 0.1691608876 0.0377279302 3.3467560000 0.9643450000 0.4626780000 0.1318610000 0.8832520000 0.9016240000 110370590 0 1787899904 3.9498102665 4.1023926735 4.0292186737 486 1305031245.7110319138 0.0505403727 0.0772790308 0.1691608876 0.0377324205 2.1774100000 0.9606920000 0.3430430000 0.0000050000 0.8633030000 0.0073570000 110372776 0 1784852480 3.9462094307 4.0994939804 4.0257658958 487 1305031245.7497749329 0.0505474769 0.0772241406 0.1691608876 0.0377938590 2.2736870000 0.9808070000 0.3093290000 0.1305150000 0.8425750000 0.0073610000 110375058 0 1786122240 3.9438889027 4.0994410515 4.0247693062 488 1305031245.7818500996 0.0511022918 0.0771706122 0.1691608876 0.0378264404 2.2624820000 0.9750970000 0.4595490000 0.0000050000 0.8174010000 0.0074420000 110377276 0 1788162048 3.9386830330 4.0971670151 4.0199375153 489 1305031245.8135690689 0.0529358909 0.0771210524 0.1691608876 0.0379083476 3.1809370000 0.9792260000 0.4663800000 0.1289560000 0.7925370000 0.8107920000 110379430 0 1784733696 3.9341087341 4.0951170921 4.0158100128 490 1305031245.8491089344 0.0544669926 0.0770748196 0.1691608876 0.0379364577 2.2051590000 0.9706110000 0.4569490000 0.0000060000 0.7670960000 0.0073920000 110381680 0 1786249216 3.9311833382 4.0891313553 4.0120177269 491 1305031245.8820281029 0.0564832985 0.0770328817 0.1691608876 0.0379534893 2.3134310000 0.9776960000 0.4524720000 0.1272910000 0.7455300000 0.0073990000 110383898 0 1788153856 3.9258241653 4.0823631287 4.0079026222 492 1305031245.9126079082 0.0589001961 0.0769960267 0.1691608876 0.0379570580 2.1489410000 0.9608090000 0.4533700000 0.0000050000 0.7243320000 0.0074160000 110386052 0 1784598528 3.9250884056 4.0782742500 4.0054368973 493 1305031245.9458959103 0.0615092851 0.0769646134 0.1691608876 0.0379901026 2.8114110000 0.9746780000 0.2683990000 0.1314690000 0.7078610000 0.7259350000 110388238 0 1786122240 3.9212763309 4.0724143982 4.0020084381 494 1305031245.9808180332 0.0625009760 0.0769353348 0.1691608876 0.0380055314 2.1203600000 0.9619110000 0.4570370000 0.0000050000 0.6909010000 0.0074210000 110390488 0 1788153856 3.9235548973 4.0697693825 4.0012869835 495 1305031246.0110030174 0.0644738898 0.0769101601 0.1691608876 0.0380120726 2.1158950000 0.9544090000 0.3454200000 0.1305130000 0.6749000000 0.0073700000 110392642 0 1784852480 3.9274888039 4.0669980049 4.0002579689 496 1305031246.0483930111 0.0664994493 0.0768891708 0.1691608876 0.0380793732 2.0861870000 0.9532640000 0.4583910000 0.0000050000 0.6641300000 0.0073040000 110394956 0 1786503168 3.9265174866 4.0630211830 3.9977891445 497 1305031246.0805249214 0.0689655468 0.0768732279 0.1691608876 0.0381382412 2.8786200000 0.9513770000 0.4595260000 0.1249550000 0.6623730000 0.6773050000 110397078 0 1785741312 3.9243569374 4.0591988564 3.9950191975 498 1305031246.1123559475 0.0698627084 0.0768591505 0.1691608876 0.0382292875 2.0868330000 0.9508730000 0.4692490000 0.0000060000 0.6563150000 0.0073120000 110399296 0 1787138048 3.9279980659 4.0582065582 3.9959416389 499 1305031246.1484489441 0.0729713291 0.0768513593 0.1691608876 0.0383014941 2.0114700000 0.9487370000 0.2676160000 0.1257410000 0.6588000000 0.0072810000 110401514 0 1784725504 3.9218246937 4.0546970367 3.9905157089 500 1305031246.1805961132 0.0762975588 0.0768502517 0.1691608876 0.0383352031 1.9280860000 0.9536480000 0.3032080000 0.0000230000 0.6607420000 0.0073970000 110403668 0 1786122240 3.9140093327 4.0513243675 3.9847037792 501 1305031246.2111370564 0.0802544653 0.0768570466 0.1691608876 0.0384125289 2.7436240000 0.9388270000 0.3409270000 0.1258920000 0.6571150000 0.6777030000 110405854 0 1788026880 3.9077031612 4.0450172424 3.9801766872 502 1305031246.2469689846 0.0840558931 0.0768713869 0.1691608876 0.0385074306 1.9937190000 0.9445440000 0.3810110000 0.0000050000 0.6576820000 0.0073040000 110408104 0 1784725504 3.9008090496 4.0413537025 3.9752562046 503 1305031246.2796959877 0.0877419785 0.0768929984 0.1691608876 0.0385528179 2.0144060000 0.9434860000 0.2757800000 0.1261230000 0.6586720000 0.0072420000 110410290 0 1786257408 3.8989286423 4.0373601913 3.9719820023 504 1305031246.3124730587 0.0902727470 0.0769195455 0.1691608876 0.0386514800 1.9252380000 0.9350390000 0.3121360000 0.0000050000 0.6670210000 0.0079180000 110412508 0 1785495552 3.8936946392 4.0356173515 3.9692564011 505 1305031246.3482720852 0.0918337479 0.0769490786 0.1691608876 0.0387574092 2.8680250000 0.9246180000 0.4669010000 0.1261140000 0.6634510000 0.6838180000 110414758 0 1786892288 3.8938694000 4.0339002609 3.9690451622 506 1305031246.3782060146 0.0933604017 0.0769815120 0.1691608876 0.0388925733 2.0720240000 0.9202670000 0.4588450000 0.0000060000 0.6824960000 0.0072230000 110416912 0 1784725504 3.8882627487 4.0341844559 3.9672234058 507 1305031246.4156370163 0.0943987966 0.0770158657 0.1691608876 0.0390401537 2.1905460000 0.9177270000 0.4504730000 0.1259160000 0.6861050000 0.0071900000 110419226 0 1786122240 3.8814961910 4.0336718559 3.9672150612 508 1305031246.4452888966 0.1000663638 0.0770612407 0.1691608876 0.0390963509 1.9287520000 0.9163220000 0.3047230000 0.0000050000 0.6972720000 0.0073090000 110421380 0 1788026880 3.8705310822 4.0289564133 3.9635019302 509 1305031246.4774649143 0.1043810397 0.0771149141 0.1691608876 0.0391662907 2.7614760000 0.9281290000 0.2661600000 0.1251420000 0.7081610000 0.7306720000 110423630 0 1784598528 3.8623237610 4.0286531448 3.9602434635 510 1305031246.5163950920 0.1043077782 0.0771682335 0.1691608876 0.0392740333 2.0464930000 0.9298690000 0.3877860000 0.0000060000 0.7183930000 0.0072480000 110425944 0 1786122240 3.8620646000 4.0328578949 3.9606819153 511 1305031246.5491750240 0.1037687138 0.0772202892 0.1691608876 0.0393813468 2.2699140000 0.9542500000 0.4587100000 0.1250300000 0.7214390000 0.0072950000 110428194 0 1788153856 3.8601245880 4.0369486809 3.9610714912 512 1305031246.5795109272 0.1041200310 0.0772728278 0.1691608876 0.0394567895 2.1429090000 0.9603290000 0.4573780000 0.0000060000 0.7146650000 0.0073260000 110430380 0 1784852480 3.8553009033 4.0399665833 3.9607520103 513 1305031246.6164529324 0.1058844402 0.0773286009 0.1691608876 0.0395046125 2.9623340000 0.9644500000 0.4366750000 0.1243420000 0.7069860000 0.7266340000 110473654 0 1786376192 3.8550250530 4.0426506996 3.9594755173 514 1305031246.6477630138 0.1066524982 0.0773856513 0.1691608876 0.0395469015 2.1512370000 0.9763230000 0.4639030000 0.0000040000 0.7001750000 0.0074360000 110559840 0 1785614336 3.8518924713 4.0457735062 3.9588522911 515 1305031246.6807579994 0.1061227545 0.0774414515 0.1691608876 0.0396205991 2.2767250000 0.9835560000 0.4651920000 0.1245790000 0.6926430000 0.0074300000 110562090 0 1787011072 3.8492372036 4.0481419563 3.9591903687 516 1305031246.7169740200 0.1102267131 0.0775049888 0.1691608876 0.0397247468 2.1502840000 0.9881100000 0.4588510000 0.0000050000 0.6925420000 0.0074070000 110564404 0 1784598528 3.8404157162 4.0499215126 3.9553854465 517 1305031246.7491660118 0.1120434031 0.0775717943 0.1691608876 0.0397890894 3.0079890000 0.9896900000 0.4692960000 0.1292200000 0.6973980000 0.7190870000 110566622 0 1786122240 3.8364109993 4.0534296036 3.9525728226 518 1305031246.7808170319 0.1119681522 0.0776381965 0.1691608876 0.0398381987 2.1387090000 0.9945020000 0.4296500000 0.0000040000 0.7038450000 0.0074850000 110568872 0 1788035072 3.8349835873 4.0559668541 3.9519782066 519 1305031246.8168079853 0.1196749881 0.0777191922 0.1691608876 0.0398647857 2.3081680000 0.9995010000 0.4646090000 0.1230090000 0.7103390000 0.0073860000 110571186 0 1784225792 3.8247163296 4.0559654236 3.9460382462 520 1305031246.8488121033 0.1155901998 0.0777920211 0.1691608876 0.0398795330 2.1028540000 0.9870380000 0.3919510000 0.0000050000 0.7131860000 0.0074430000 110573436 0 1785749504 3.8299744129 4.0623049736 3.9466729164 521 1305031246.8806428909 0.1112729982 0.0778562840 0.1691608876 0.0399398995 3.0148950000 0.9716810000 0.4694580000 0.1222450000 0.7093440000 0.7389240000 110575686 0 1787645952 3.8342866898 4.0671772957 3.9479119778 522 1305031246.9166710377 0.1105272025 0.0779188720 0.1691608876 0.0399982968 2.1615450000 0.9884610000 0.4665500000 0.0000050000 0.6957290000 0.0074460000 110578000 0 1784471552 3.8329393864 4.0694980621 3.9459643364 523 1305031246.9495339394 0.1147570089 0.0779893082 0.1691608876 0.0399865364 2.2748460000 0.9921160000 0.4612270000 0.1225690000 0.6882260000 0.0074420000 110580250 0 1785995264 3.8286397457 4.0718359947 3.9406454563 524 1305031246.9775969982 0.1161952764 0.0780622203 0.1691608876 0.0399665222 2.1281440000 0.9900400000 0.4641940000 0.0000050000 0.6630770000 0.0074860000 110582404 0 1787899904 3.8264439106 4.0726361275 3.9382522106 525 1305031247.0167899132 0.1123028845 0.0781274406 0.1691608876 0.0400424111 2.8805910000 0.9881770000 0.4315480000 0.1219870000 0.6478260000 0.6877580000 110584750 0 1784725504 3.8283028603 4.0759358406 3.9388880730 526 1305031247.0479340553 0.1153229550 0.0781981545 0.1691608876 0.0400154688 1.9637300000 1.0007370000 0.3103390000 0.0000050000 0.6418030000 0.0074280000 110587000 0 1786122240 3.8228166103 4.0764331818 3.9340910912 527 1305031247.0778899193 0.1132089496 0.0782645887 0.1691608876 0.0400024381 2.1387610000 0.9824760000 0.3861000000 0.1219560000 0.6374930000 0.0074530000 110589218 0 1788153856 3.8218789101 4.0785937309 3.9331648350 528 1305031247.1162130833 0.1143203303 0.0783328761 0.1691608876 0.0399688726 2.0834490000 0.9763150000 0.4553720000 0.0000050000 0.6410690000 0.0073120000 110591564 0 1784725504 3.8158068657 4.0811848640 3.9295775890 529 1305031247.1473660469 0.1164634079 0.0784049565 0.1691608876 0.0399546835 2.8620710000 0.9717310000 0.4404310000 0.1217880000 0.6459500000 0.6788480000 110593814 0 1786122240 3.8128969669 4.0824756622 3.9260048866 530 1305031247.1796920300 0.1179959401 0.0784796565 0.1691608876 0.0399194908 2.0767080000 0.9827130000 0.4319830000 0.0000050000 0.6512880000 0.0074060000 110596064 0 1788026880 3.8113782406 4.0790343285 3.9247019291 531 1305031247.2169430256 0.1135832071 0.0785457648 0.1691608876 0.0398911920 2.1362260000 0.9543810000 0.3979270000 0.1216760000 0.6515490000 0.0073010000 110598410 0 1784852480 3.8156578541 4.0805335045 3.9260232449 532 1305031247.2487928867 0.1095049679 0.0786039588 0.1691608876 0.0398669120 2.0784670000 0.9691010000 0.4506440000 0.0000050000 0.6479570000 0.0073470000 110600628 0 1786130432 3.8186509609 4.0804886818 3.9284133911 533 1305031247.2794220448 0.1139350981 0.0786702461 0.1691608876 0.0398472713 2.8578230000 0.9648530000 0.4559720000 0.1219250000 0.6400490000 0.6716720000 110602846 0 1788035072 3.8151938915 4.0780496597 3.9249248505 534 1305031247.3166429996 0.1124410853 0.0787334874 0.1691608876 0.0398423629 2.0512040000 0.9716480000 0.4321720000 0.0000050000 0.6367130000 0.0073390000 110605192 0 1784606720 3.8205041885 4.0745491982 3.9263765812 535 1305031247.3477900028 0.1150975749 0.0788014577 0.1691608876 0.0398918866 2.1949590000 0.9599060000 0.4707920000 0.1220690000 0.6315420000 0.0073180000 110607442 0 1785995264 3.8188235760 4.0717363358 3.9261322021 536 1305031247.3786110878 0.1127729267 0.0788648373 0.1691608876 0.0398965522 1.9747750000 0.9713930000 0.3584190000 0.0000050000 0.6341950000 0.0073270000 110609660 0 1787899904 3.8233077526 4.0704526901 3.9285554886 537 1305031247.4168620110 0.1148721799 0.0789318901 0.1691608876 0.0399300493 2.7304020000 0.9886240000 0.3319720000 0.1226920000 0.6225040000 0.6611630000 110612038 0 1784598528 3.8223705292 4.0668816566 3.9294610023 538 1305031247.4487700462 0.1156698093 0.0790001762 0.1691608876 0.0400452029 1.9220830000 0.9682140000 0.3208500000 0.0000050000 0.6222500000 0.0073370000 110614288 0 1786122240 3.8227548599 4.0657129288 3.9311637878 539 1305031247.4802629948 0.1120184362 0.0790614345 0.1691608876 0.0400905356 2.2198550000 0.9837780000 0.4825580000 0.1226990000 0.6200780000 0.0074160000 110616474 0 1787899904 3.8273272514 4.0679025650 3.9354677200 540 1305031247.5178461075 0.1130972132 0.0791244637 0.1691608876 0.0401591082 2.1070820000 0.9748380000 0.4973570000 0.0000050000 0.6240560000 0.0074940000 110618852 0 1785487360 3.8287665844 4.0673704147 3.9374909401 541 1305031247.5459010601 0.1125167534 0.0791861870 0.1691608876 0.0402344347 2.8577710000 0.9762010000 0.4894800000 0.1232610000 0.6144120000 0.6510340000 110621006 0 1787011072 3.8307604790 4.0657467842 3.9403076172 542 1305031247.5779209137 0.1115392521 0.0792458790 0.1691608876 0.0402886400 2.0977950000 0.9777610000 0.4919290000 0.0000040000 0.6172600000 0.0073540000 110623224 0 1784598528 3.8327715397 4.0653738976 3.9426116943 543 1305031247.6152799129 0.1113886237 0.0793050738 0.1691608876 0.0404189296 2.2312950000 0.9853110000 0.4884930000 0.1236410000 0.6230060000 0.0074480000 110625506 0 1786376192 3.8361151218 4.0648703575 3.9444668293 544 1305031247.6484000683 0.1113832667 0.0793640410 0.1691608876 0.0405251784 2.0001230000 0.9862370000 0.3709350000 0.0000050000 0.6321260000 0.0074290000 110627756 0 1788026880 3.8378360271 4.0635914803 3.9453232288 545 1305031247.6835579872 0.1097319499 0.0794197620 0.1691608876 0.0406608616 2.9287950000 0.9809400000 0.4983510000 0.1296030000 0.6412700000 0.6751980000 110630006 0 1785368576 3.8409504890 4.0627140999 3.9470648766 546 1305031247.7159609795 0.1066148430 0.0794695698 0.1691608876 0.0408290731 2.1452360000 0.9823510000 0.4982450000 0.0000060000 0.6537040000 0.0074180000 110632224 0 1787019264 3.8461978436 4.0620160103 3.9512555599 547 1305031247.7469019890 0.1042036563 0.0795147875 0.1691608876 0.0410141670 2.1370960000 0.9672020000 0.3806210000 0.1303690000 0.6480500000 0.0073160000 110634442 0 1784852480 3.8488378525 4.0609383583 3.9533317089 548 1305031247.7822608948 0.1061647758 0.0795634189 0.1691608876 0.0411385266 2.0756300000 0.9699140000 0.4237990000 0.0000050000 0.6711450000 0.0073410000 110636692 0 1786376192 3.8465702534 4.0535402298 3.9526088238 549 1305031247.8139829636 0.1060894504 0.0796117359 0.1691608876 0.0413754690 2.9610050000 0.9730720000 0.4860450000 0.1269700000 0.6723180000 0.6991860000 110638814 0 1785614336 3.8526332378 4.0488061905 3.9527850151 550 1305031247.8484420776 0.1036758870 0.0796554889 0.1691608876 0.0415266828 2.1523350000 0.9831300000 0.4769300000 0.0000050000 0.6813520000 0.0074460000 110641128 0 1787138048 3.8654181957 4.0514655113 3.9525117874 551 1305031247.8820719719 0.1073569730 0.0797057638 0.1691608876 0.0415597505 2.2966200000 0.9951150000 0.4731630000 0.1279000000 0.6896300000 0.0073660000 110643314 0 1784852480 3.8622181416 4.0424652100 3.9496419430 552 1305031247.9173319340 0.1026349366 0.0797473022 0.1691608876 0.0415378608 2.1183620000 0.9707970000 0.4011010000 0.0000050000 0.7355380000 0.0074650000 110645564 0 1786503168 3.8591349125 4.0498142242 3.9452352524 553 1305031247.9496860504 0.0953419507 0.0797755022 0.1691608876 0.0416057757 3.0244870000 0.9775570000 0.3554650000 0.1292520000 0.7617580000 0.7969790000 110647718 0 1785614336 3.8700373173 4.0570025444 3.9481098652 554 1305031247.9861450195 0.0983081535 0.0798089547 0.1691608876 0.0417689357 2.1399950000 0.9879390000 0.3593980000 0.0000050000 0.7816880000 0.0074090000 110650000 0 1787138048 3.8742098808 4.0519986153 3.9426395893 555 1305031248.0181560516 0.0972343981 0.0798403519 0.1691608876 0.0417387480 2.4234410000 0.9863760000 0.4859550000 0.1307250000 0.8093540000 0.0075000000 110652154 0 1784852480 3.8705646992 4.0555295944 3.9365856647 556 1305031248.0499138832 0.0932802483 0.0798645243 0.1691608876 0.0417577404 2.2778820000 0.9856350000 0.4370320000 0.0000050000 0.8442960000 0.0074350000 110654340 0 1786249216 3.8767447472 4.0588803291 3.9368381500 557 1305031248.0857460499 0.0896282941 0.0798820536 0.1691608876 0.0419131543 3.2436690000 0.9978520000 0.3217620000 0.1321350000 0.8810070000 0.9074110000 110656558 0 1785741312 3.8888196945 4.0589323044 3.9381337166 558 1305031248.1175789833 0.0867321864 0.0798943298 0.1691608876 0.0419262304 2.1911110000 0.9784680000 0.2814000000 0.0000050000 0.9202360000 0.0075070000 110658744 0 1787138048 3.9034273624 4.0597434044 3.9429297447 559 1305031248.1493461132 0.0809541494 0.0798962257 0.1691608876 0.0419192471 2.5221930000 0.9870380000 0.4286190000 0.1338790000 0.9617380000 0.0074100000 110660930 0 1785114624 3.9152896404 4.0620188713 3.9513382912 560 1305031248.1848630905 0.0799462348 0.0798963150 0.1691608876 0.0420434742 2.4533510000 0.9821620000 0.4711880000 0.0000050000 0.9888350000 0.0076790000 110663148 0 1786638336 3.9319851398 4.0657367706 3.9594981670 561 1305031248.2167689800 0.0760414377 0.0798894436 0.1691608876 0.0420723965 3.4563380000 1.0236640000 0.4278300000 0.0000040000 0.9924550000 1.0088190000 110665334 0 1784471552 3.9319851398 4.0657367706 3.9594981670 562 1305031248.2488510609 0.0727217197 0.0798766896 0.1691608876 0.0421159926 2.4865290000 0.9807900000 0.5077910000 0.0000050000 0.9869100000 0.0075170000 110667488 0 1786122240 3.9319851398 4.0657367706 3.9594981670 563 1305031248.2847399712 0.0692704171 0.0798578508 0.1691608876 0.0421108212 2.4818060000 0.9804310000 0.5027640000 0.0000050000 0.9875770000 0.0075000000 110669770 0 1787899904 3.9319851398 4.0657367706 3.9594981670 564 1305031248.3161809444 0.0670388266 0.0798351220 0.1691608876 0.0420939699 2.3653490000 0.9789870000 0.3885900000 0.0000050000 0.9866200000 0.0075280000 110671956 0 1784979456 3.9319851398 4.0657367706 3.9594981670 565 1305031248.3488430977 0.0885732025 0.0798505876 0.1691608876 0.0429554843 3.8803070000 0.9798950000 0.5989450000 0.1375210000 1.0681210000 1.0922330000 110674110 0 1786630144 3.9692199230 4.0835008621 3.9715609550 566 1305031248.3881969452 0.0934856534 0.0798746778 0.1691608876 0.0429481002 2.4322980000 0.9806300000 0.3607700000 0.0000040000 1.0795850000 0.0075100000 110676424 0 1785868288 3.9784235954 4.0864682198 3.9791915417 567 1305031248.4155070782 0.0983229876 0.0799072145 0.1691608876 0.0429787613 2.6283890000 0.9836810000 0.3953520000 0.1384900000 1.0996990000 0.0074500000 110678546 0 1787392000 3.9849240780 4.0909705162 3.9812610149 568 1305031248.4482519627 0.1023435965 0.0799467152 0.1691608876 0.0429894557 2.4640700000 0.9978900000 0.3566290000 0.0000040000 1.0982860000 0.0074280000 110680732 0 1785122816 3.9898879528 4.0931243896 3.9810268879 569 1305031248.4852969646 0.1057564244 0.0799920750 0.1691608876 0.0430427783 3.6816540000 0.9711290000 0.3141670000 0.1390790000 1.1140290000 1.1394830000 110682982 0 1786503168 3.9933593273 4.0948109627 3.9770624638 570 1305031248.5154309273 0.1053697094 0.0800365972 0.1691608876 0.0430131366 2.5309480000 0.9670720000 0.4229480000 0.0000050000 1.1296910000 0.0074200000 110685168 0 1785868288 3.9926190376 4.1040787697 3.9773099422 571 1305031248.5470030308 0.1082712784 0.0800860449 0.1691608876 0.0430311126 2.5776930000 0.9860790000 0.3098430000 0.1394720000 1.1310880000 0.0075240000 110687354 0 1787265024 3.9959933758 4.1118955612 3.9792499542 572 1305031248.5860579014 0.1061349735 0.0801315850 0.1691608876 0.0430718427 2.6292130000 1.0010330000 0.4747780000 0.0000050000 1.1421410000 0.0075010000 110689636 0 1785257984 3.9938254356 4.1172251701 3.9717381001 573 1305031248.6180379391 0.0979172960 0.0801626247 0.1691608876 0.0431220270 3.8252710000 0.9772610000 0.3544960000 0.1398260000 1.1620480000 1.1879030000 110691790 0 1786544128 3.9797003269 4.1229391098 3.9572262764 574 1305031248.6494390965 0.0977263898 0.0801932235 0.1691608876 0.0431116730 2.5062400000 0.9654330000 0.3500390000 0.0000060000 1.1796210000 0.0074210000 110693976 0 1784614912 3.9774158001 4.1287064552 3.9529044628 575 1305031248.6860280037 0.0979625359 0.0802241267 0.1691608876 0.0431430874 2.6690600000 0.9655860000 0.3539710000 0.1406920000 1.1977000000 0.0074640000 110696258 0 1786249216 3.9763274193 4.1384520531 3.9520120621 576 1305031248.7199230194 0.0982384905 0.0802554016 0.1691608876 0.0431482478 2.5918470000 0.9821280000 0.3922190000 0.0000050000 1.2064320000 0.0074370000 110698444 0 1788026880 3.9740364552 4.1463918686 3.9482886791 577 1305031248.7498369217 0.0981683359 0.0802864466 0.1691608876 0.0432153648 3.9049690000 0.9533800000 0.3522690000 0.1409670000 1.2192070000 1.2354510000 110700598 0 1785360384 3.9711647034 4.1530890465 3.9445271492 578 1305031248.7856750488 0.0981502235 0.0803173528 0.1691608876 0.0432734264 2.5893280000 0.9554130000 0.3866180000 0.0000050000 1.2362990000 0.0073750000 110702848 0 1787011072 3.9629144669 4.1613378525 3.9345285892 579 1305031248.8181409836 0.1005880311 0.0803523626 0.1691608876 0.0432505235 2.6866520000 0.9554490000 0.3382820000 0.1414360000 1.2405310000 0.0073460000 110705034 0 1784844288 3.9570934772 4.1772918701 3.9356753826 580 1305031248.8496789932 0.0971381813 0.0803813036 0.1691608876 0.0432410898 2.6600230000 0.9554710000 0.4543570000 0.0000050000 1.2391710000 0.0073780000 110707220 0 1786494976 3.9570934772 4.1772918701 3.9356753826 581 1305031248.8855929375 0.0931521058 0.0804032844 0.1691608876 0.0432478677 3.9135770000 0.9674520000 0.4401000000 0.0000040000 1.2394440000 1.2628800000 110709470 0 1785614336 3.9570934772 4.1772918701 3.9356753826 582 1305031248.9178819656 0.0901314840 0.0804199995 0.1691608876 0.0432181406 2.6480950000 0.9667840000 0.4304300000 0.0000040000 1.2396540000 0.0074520000 110711656 0 1787265024 3.9570934772 4.1772918701 3.9356753826 583 1305031248.9526810646 0.0868892297 0.0804310959 0.1691608876 0.0432125957 2.6859540000 0.9685480000 0.4429350000 0.0000050000 1.2631640000 0.0075870000 110713906 0 1785106432 3.9570934772 4.1772918701 3.9356753826 584 1305031248.9845540524 0.0838356540 0.0804369257 0.1691608876 0.0431919086 2.6528790000 0.9650300000 0.4335500000 0.0000060000 1.2432170000 0.0073760000 110716092 0 1786638336 3.9570934772 4.1772918701 3.9356753826 585 1305031249.0169510841 0.0829546452 0.0804412295 0.1691608876 0.0431645164 3.9273100000 0.9495230000 0.4631360000 0.0000050000 1.2410060000 1.2699810000 110718278 0 1784606720 3.9570934772 4.1772918701 3.9356753826 586 1305031249.0523660183 0.0825493038 0.0804448269 0.1691608876 0.0431355881 2.6201370000 0.9357880000 0.4331820000 0.0000060000 1.2400980000 0.0073350000 110720528 0 1786122240 3.9570934772 4.1772918701 3.9356753826 587 1305031249.0845029354 0.0837857351 0.0804505183 0.1691608876 0.0431052571 2.6225720000 0.9279730000 0.4351980000 0.0000040000 1.2483790000 0.0072390000 110722714 0 1787899904 3.9570934772 4.1772918701 3.9356753826 588 1305031249.1168839931 0.0851438344 0.0804585002 0.1691608876 0.0430687264 2.6023980000 0.9174270000 0.4347610000 0.0000060000 1.2392260000 0.0073010000 110724900 0 1785233408 3.9570934772 4.1772918701 3.9356753826 589 1305031249.1534469128 0.0880807415 0.0804714412 0.1691608876 0.0430572412 3.9369970000 0.9462900000 0.4837830000 0.0000050000 1.2404440000 1.2627110000 110727150 0 1786757120 3.9570934772 4.1772918701 3.9356753826 590 1305031249.1847391129 0.0899675116 0.0804875362 0.1691608876 0.0430283946 2.6968630000 0.9592130000 0.4821460000 0.0000050000 1.2445330000 0.0072980000 110729336 0 1784725504 3.9570934772 4.1772918701 3.9356753826 591 1305031249.2168650627 0.0915870443 0.0805063171 0.1691608876 0.0430155995 2.6815680000 0.9359110000 0.4942280000 0.0000040000 1.2402710000 0.0073470000 110731522 0 1786376192 3.9570934772 4.1772918701 3.9356753826 592 1305031249.2532238960 0.0938475057 0.0805288529 0.1691608876 0.0430677619 2.7123050000 0.9460050000 0.5094370000 0.0000060000 1.2456980000 0.0073650000 110733772 0 1788026880 3.9570934772 4.1772918701 3.9356753826 593 1305031249.2848041058 0.0952136144 0.0805536164 0.1691608876 0.0430585915 3.9787620000 0.9479570000 0.5221770000 0.0000040000 1.2404640000 1.2644350000 110735926 0 1785360384 3.9570934772 4.1772918701 3.9356753826 594 1305031249.3174340725 0.0965138003 0.0805804854 0.1691608876 0.0430401031 2.6684980000 0.9549070000 0.4636720000 0.0000060000 1.2388230000 0.0072890000 110738144 0 1786884096 3.9570934772 4.1772918701 3.9356753826 595 1305031249.3527359962 0.0975759998 0.0806090493 0.1691608876 0.0430091067 2.6283660000 0.9286470000 0.4441580000 0.0000040000 1.2445270000 0.0073130000 110740362 0 1784733696 3.9570934772 4.1772918701 3.9356753826 596 1305031249.3847539425 0.0988197625 0.0806396042 0.1691608876 0.0429814577 2.6387730000 0.9340500000 0.4525880000 0.0000050000 1.2410500000 0.0072640000 110742548 0 1786257408 3.9570934772 4.1772918701 3.9356753826 597 1305031249.4178340435 0.0987689346 0.0806699716 0.1691608876 0.0429773689 3.9029430000 0.9364500000 0.4546230000 0.0000050000 1.2445620000 1.2635560000 110744734 0 1787899904 3.9570934772 4.1772918701 3.9356753826 598 1305031249.4537220001 0.1011260748 0.0807041791 0.1691608876 0.0430249513 2.6408980000 0.9412020000 0.4493090000 0.0000060000 1.2392700000 0.0073330000 110746984 0 1785233408 3.9570934772 4.1772918701 3.9356753826 599 1305031249.4859149456 0.1017108634 0.0807392487 0.1691608876 0.0430833814 2.6342620000 0.9497060000 0.4342910000 0.0000050000 1.2390760000 0.0072860000 110749170 0 1786757120 3.9570934772 4.1772918701 3.9356753826 600 1305031249.5177340508 0.1021549776 0.0807749416 0.1691608876 0.0431379984 2.6271920000 0.9668040000 0.4092330000 0.0000050000 1.2399120000 0.0073450000 110751356 0 1784393728 3.9570934772 4.1772918701 3.9356753826 601 1305031249.5543251038 0.1033876985 0.0808125668 0.1691608876 0.0432467182 3.8622780000 0.9641240000 0.3897160000 0.0000050000 1.2414940000 1.2630890000 110753606 0 1785868288 3.9570934772 4.1772918701 3.9356753826 602 1305031249.5859050751 0.1049840674 0.0808527188 0.1691608876 0.0433434949 2.5968190000 0.9576150000 0.3812630000 0.0000050000 1.2468090000 0.0073100000 110755760 0 1787899904 3.9570934772 4.1772918701 3.9356753826 603 1305031249.6180789471 0.2263861597 0.0810940678 0.2263861597 0.0433800293 2.7618000000 0.9679470000 0.4063860000 0.1399010000 1.2363170000 0.0073840000 110757946 0 1785106432 3.7950232029 4.1570734978 3.8319637775 604 1305031249.6542129517 0.2294680178 0.0813397200 0.2294680178 0.0437738027 2.6844340000 0.9931360000 0.4475890000 0.0000050000 1.2324560000 0.0073670000 110760164 0 1786630144 3.7805962563 4.1727628708 3.8434975147 605 1305031249.6856739521 0.2241510749 0.0815757718 0.2294680178 0.0439156546 3.9702400000 0.9583630000 0.4329970000 0.1387130000 1.1979140000 1.2384680000 110762350 0 1785614336 3.7792613506 4.1663584709 3.8491847515 606 1305031249.7177898884 0.2017439753 0.0817740692 0.2294680178 0.0440524442 2.5679170000 0.9656170000 0.4454560000 0.0000060000 1.1455100000 0.0073670000 110764536 0 1787138048 3.7944519520 4.1578202248 3.8631637096 607 1305031249.7539620399 0.2026090622 0.0819731384 0.2294680178 0.0443918673 2.5741120000 0.9708290000 0.4409340000 0.0000040000 1.1511180000 0.0074510000 110766754 0 1784733696 3.7944519520 4.1578202248 3.8631637096 608 1305031249.7854170799 0.2021997422 0.0821708795 0.2294680178 0.0445619737 2.6313560000 1.0045320000 0.4702260000 0.0000050000 1.1453580000 0.0074190000 110768908 0 1786257408 3.7944519520 4.1578202248 3.8631637096 609 1305031249.8186020851 0.2027934045 0.0823689460 0.2294680178 0.0446907633 3.7843430000 0.9579140000 0.4952190000 0.0000040000 1.1513250000 1.1760630000 110771158 0 1787899904 3.7944519520 4.1578202248 3.8631637096 610 1305031249.8537468910 0.0806427822 0.0823661163 0.2294680178 0.0471436315 2.5235940000 0.9700230000 0.5000640000 0.0000060000 1.0422250000 0.0074440000 110773344 0 1784852480 3.9415690899 4.1290078163 3.9492766857 611 1305031249.8855249882 0.0833170041 0.0823676725 0.2294680178 0.0471497635 2.5902150000 0.9516780000 0.4592560000 0.1306980000 1.0373490000 0.0073290000 110775530 0 1786249216 3.9326736927 4.1245718002 3.9431066513 612 1305031249.9170649052 0.0854535252 0.0823727148 0.2294680178 0.0471528820 2.4604970000 0.9650490000 0.4447560000 0.0000050000 1.0395210000 0.0073440000 110777748 0 1785614336 3.9259958267 4.1194214821 3.9390139580 613 1305031249.9533979893 0.0891025588 0.0823836933 0.2294680178 0.0471545874 3.5771060000 0.9284560000 0.4018530000 0.1280090000 1.0403470000 1.0744570000 110779966 0 1787265024 3.9205589294 4.1160864830 3.9355902672 614 1305031249.9851789474 0.0920015723 0.0823993576 0.2294680178 0.0471542418 2.4088480000 0.9097650000 0.4326030000 0.0000060000 1.0553730000 0.0072450000 110782152 0 1784725504 3.9139988422 4.1146440506 3.9334490299 615 1305031250.0164399147 0.0942759663 0.0824186692 0.2294680178 0.0471370482 2.4896060000 0.9097960000 0.3927580000 0.1274490000 1.0482690000 0.0072780000 110784338 0 1786138624 3.9111874104 4.1116962433 3.9316883087 616 1305031250.0531940460 0.0971762240 0.0824426263 0.2294680178 0.0471777876 2.4026260000 0.8918960000 0.4290350000 0.0000050000 1.0701710000 0.0073560000 110786588 0 1787789312 3.9089498520 4.1050014496 3.9283118248 617 1305031250.0845069885 0.0994439647 0.0824701811 0.2294680178 0.0472300032 3.6094590000 0.8804340000 0.4355250000 0.1278070000 1.0619000000 1.0998910000 110788742 0 1784471552 3.9055480957 4.1037378311 3.9275109768 618 1305031250.1208500862 0.0996575654 0.0824979924 0.2294680178 0.0473061311 2.2426880000 0.8883630000 0.2877540000 0.0000060000 1.0555130000 0.0071490000 110791024 0 1785995264 3.8998856544 4.1004538536 3.9286477566 619 1305031250.1532480717 0.0984789133 0.0825238097 0.2294680178 0.0474960824 2.3380040000 0.9162450000 0.2528920000 0.1286170000 1.0291380000 0.0072750000 110793178 0 1788026880 3.8983113766 4.0953578949 3.9317882061 620 1305031250.1853280067 0.0946301296 0.0825433360 0.2294680178 0.0474962812 2.3640240000 0.9214180000 0.4445690000 0.0000050000 0.9868880000 0.0072740000 110795332 0 1784987648 3.9008235931 4.0878300667 3.9365627766 621 1305031250.2214460373 0.0923478827 0.0825591244 0.2294680178 0.0475002870 3.3504740000 0.9142980000 0.3561450000 0.1284640000 0.9626750000 0.9849360000 110797614 0 1786384384 3.8940174580 4.0766463280 3.9386358261 622 1305031250.2537350655 0.0913910940 0.0825733237 0.2294680178 0.0475761408 2.2884510000 0.9154440000 0.4258720000 0.0000060000 0.9360240000 0.0071950000 110799800 0 1785368576 3.8969473839 4.0731940269 3.9427437782 623 1305031250.2852239609 0.0917463079 0.0825880476 0.2294680178 0.0475812127 2.3057180000 0.9189770000 0.3258740000 0.1283510000 0.9213730000 0.0071940000 110801954 0 1786884096 3.8980972767 4.0692315102 3.9446454048 624 1305031250.3208620548 0.0884275958 0.0825974058 0.2294680178 0.0476211739 2.2132230000 0.9276650000 0.3658390000 0.0000060000 0.9084000000 0.0072220000 110804172 0 1784725504 3.8971884251 4.0673413277 3.9503109455 625 1305031250.3517000675 0.0862828940 0.0826033026 0.2294680178 0.0476442202 3.3044580000 0.9111540000 0.4484320000 0.1285040000 0.8954220000 0.9170460000 110806326 0 1786122240 3.9033398628 4.0701899529 3.9564902782 626 1305031250.3851490021 0.0861772224 0.0826090117 0.2294680178 0.0476586618 2.2585180000 0.9170630000 0.4383320000 0.0000060000 0.8919370000 0.0072600000 110808512 0 1788026880 3.8976037502 4.0664620399 3.9585289955 627 1305031250.4215359688 0.0890202671 0.0826192370 0.2294680178 0.0476672053 2.3924490000 0.9147250000 0.4422590000 0.1282990000 0.8959380000 0.0072060000 110810794 0 1784852480 3.8940007687 4.0676069260 3.9570965767 628 1305031250.4540181160 0.0897649899 0.0826306156 0.2294680178 0.0477404362 2.2598290000 0.9172680000 0.4369330000 0.0000050000 0.8944510000 0.0072760000 110813044 0 1786376192 3.8917193413 4.0700802803 3.9588527679 629 1305031250.4856131077 0.0902167186 0.0826426762 0.2294680178 0.0477375650 3.2721660000 0.9085790000 0.4372310000 0.1272820000 0.8853600000 0.9097870000 110815198 0 1785487360 3.8919610977 4.0732975006 3.9611322880 630 1305031250.5215380192 0.0912858471 0.0826563955 0.2294680178 0.0477153457 2.2300860000 0.9109270000 0.4304890000 0.0000050000 0.8775160000 0.0071940000 110817480 0 1786884096 3.8866178989 4.0727653503 3.9609858990 631 1305031250.5536580086 0.0930442289 0.0826728580 0.2294680178 0.0476999491 2.3617200000 0.9226600000 0.4298420000 0.1261380000 0.8718710000 0.0072840000 110819730 0 1784725504 3.8822412491 4.0727968216 3.9615788460 632 1305031250.5853788853 0.0956679136 0.0826934198 0.2294680178 0.0476813099 2.1487870000 0.9176400000 0.3548860000 0.0000230000 0.8651070000 0.0071840000 110821916 0 1786122240 3.8784663677 4.0767035484 3.9598925114 633 1305031250.6213030815 0.0974778980 0.0827167760 0.2294680178 0.0476593793 3.2251110000 0.9198460000 0.4323320000 0.1254140000 0.8592200000 0.8842700000 110824198 0 1788153856 3.8768982887 4.0799698830 3.9599452019 634 1305031250.6535439491 0.0970725417 0.0827394192 0.2294680178 0.0476748731 2.1422200000 0.9149050000 0.3603040000 0.0000250000 0.8555530000 0.0072090000 110826480 0 1784512512 3.8758258820 4.0807242393 3.9625871181 635 1305031250.6852970123 0.0948957801 0.0827585630 0.2294680178 0.0476895594 2.3412700000 0.9243030000 0.4336500000 0.1249600000 0.8468600000 0.0073970000 110828666 0 1786003456 3.8803565502 4.0850977898 3.9674911499 636 1305031250.7216401100 0.0927384347 0.0827742547 0.2294680178 0.0476679941 2.2349190000 0.9533820000 0.4402550000 0.0000060000 0.8298100000 0.0072370000 110830948 0 1788035072 3.8793888092 4.0864338875 3.9711210728 637 1305031250.7534279823 0.0919540897 0.0827886657 0.2294680178 0.0476457887 3.1251050000 0.9175310000 0.4297930000 0.1234730000 0.8156170000 0.8347270000 110833166 0 1784344576 3.8692712784 4.0802516937 3.9732606411 638 1305031250.7853651047 0.0901343599 0.0828001793 0.2294680178 0.0476235962 2.1689070000 0.9340350000 0.4199190000 0.0000060000 0.8036680000 0.0072950000 110835384 0 1785868288 3.8590734005 4.0725650787 3.9778194427 639 1305031250.8217930794 0.0899342895 0.0828113438 0.2294680178 0.0475911977 2.2818660000 0.9351310000 0.4198090000 0.1227020000 0.7928170000 0.0073820000 110837730 0 1787645952 3.8557713032 4.0737605095 3.9786300659 640 1305031250.8538279533 0.0886426643 0.0828204553 0.2294680178 0.0475584585 2.1558770000 0.9324450000 0.4211700000 0.0000050000 0.7905930000 0.0073040000 110839980 0 1784520704 3.8573980331 4.0748500824 3.9798851013 641 1305031250.8820140362 0.0882341638 0.0828289010 0.2294680178 0.0475233463 3.0682440000 0.9386500000 0.4219720000 0.1224900000 0.7810440000 0.7999550000 110842134 0 1785884672 3.8576910496 4.0747990608 3.9806256294 642 1305031250.9217998981 0.0903373733 0.0828405964 0.2294680178 0.0474887165 2.1629530000 0.9557280000 0.4210740000 0.0000050000 0.7746540000 0.0073450000 110844480 0 1787645952 3.8562023640 4.0743474960 3.9782366753 643 1305031250.9535419941 0.0931942016 0.0828566984 0.2294680178 0.0474675832 2.2840840000 0.9606620000 0.4177800000 0.1226680000 0.7716890000 0.0072390000 110846730 0 1784598528 3.8512573242 4.0733475685 3.9744589329 644 1305031250.9853079319 0.0906643048 0.0828688221 0.2294680178 0.0474342431 2.1593570000 0.9472370000 0.4242160000 0.0000050000 0.7764440000 0.0072850000 110848916 0 1785995264 3.8549909592 4.0736665726 3.9761419296 645 1305031251.0214879513 0.0904962271 0.0828806475 0.2294680178 0.0474097551 3.0695800000 0.9464830000 0.4352640000 0.1234000000 0.7706290000 0.7896710000 110851198 0 1787789312 3.8572747707 4.0730228424 3.9755752087 646 1305031251.0534679890 0.0923360214 0.0828952843 0.2294680178 0.0474117314 2.1513110000 0.9363310000 0.4398490000 0.0000050000 0.7635420000 0.0073240000 110853416 0 1784758272 3.8545134068 4.0708637238 3.9720063210 647 1305031251.0851860046 0.0912426412 0.0829081859 0.2294680178 0.0474042448 2.2736910000 0.9359720000 0.4426400000 0.1239900000 0.7596830000 0.0073230000 110855634 0 1786122240 3.8559069633 4.0668783188 3.9715876579 648 1305031251.1214449406 0.0903329104 0.0829196438 0.2294680178 0.0473975074 2.1733520000 0.9417270000 0.4543490000 0.0000050000 0.7649140000 0.0073050000 110857916 0 1785434112 3.8600528240 4.0646090508 3.9708335400 649 1305031251.1537809372 0.0879271999 0.0829273596 0.2294680178 0.0474671898 2.9255420000 0.9335370000 0.3029630000 0.1247690000 0.7706580000 0.7894800000 110860166 0 1784225792 3.8657855988 4.0628409386 3.9701311588 650 1305031251.1851599216 0.0877034068 0.0829347074 0.2294680178 0.0474819521 2.1197820000 0.9339810000 0.3938600000 0.0000050000 0.7801690000 0.0074740000 110862352 0 1785614336 3.8699858189 4.0577344894 3.9688045979 651 1305031251.2204658985 0.0848633498 0.0829376700 0.2294680178 0.0474856681 2.3279050000 0.9340420000 0.4677500000 0.1261200000 0.7884660000 0.0073540000 110864602 0 1787408384 3.8758568764 4.0556054115 3.9694344997 652 1305031251.2524240017 0.0828542784 0.0829375421 0.2294680178 0.0475266086 2.2000000000 0.9230920000 0.4657630000 0.0000060000 0.7995720000 0.0073020000 110866788 0 1784758272 3.8817009926 4.0521640778 3.9699354172 653 1305031251.2844820023 0.0834340528 0.0829383024 0.2294680178 0.0476893902 3.1550160000 0.9328360000 0.4729360000 0.1277610000 0.7985280000 0.8187180000 110869006 0 1786122240 3.8861968517 4.0479512215 3.9672646523 654 1305031251.3190040588 0.0821026489 0.0829370247 0.2294680178 0.0477570312 2.2462190000 0.9308690000 0.4855090000 0.0000060000 0.8182760000 0.0072500000 110871256 0 1785249792 3.8952283859 4.0461840630 3.9681673050 655 1305031251.3532440662 0.0793470740 0.0829315438 0.2294680178 0.0478141713 2.2618220000 0.9328290000 0.3563130000 0.1286900000 0.8324950000 0.0072890000 110873442 0 1786757120 3.9032056332 4.0438542366 3.9705784321 656 1305031251.3870069981 0.0771035701 0.0829226597 0.2294680178 0.0478392795 2.2560580000 0.9264610000 0.4670880000 0.0000060000 0.8509520000 0.0072760000 110875660 0 1784520704 3.9120371342 4.0451674461 3.9743919373 657 1305031251.4210500717 0.0791802481 0.0829169635 0.2294680178 0.0479176890 3.2872890000 0.9355910000 0.4735210000 0.1295990000 0.8627290000 0.8815910000 110877878 0 1785995264 3.9147326946 4.0410542488 3.9710152149 658 1305031251.4496629238 0.0779896230 0.0829094752 0.2294680178 0.0479630779 2.2392410000 0.9354570000 0.4046280000 0.0000060000 0.8876660000 0.0072750000 110880000 0 1787916288 3.9264283180 4.0415253639 3.9769127369 659 1305031251.4890139103 0.0760341436 0.0828990422 0.2294680178 0.0480363042 2.3420170000 0.9380190000 0.3616150000 0.1303290000 0.9003800000 0.0073020000 110882282 0 1784758272 3.9325709343 4.0430436134 3.9792323112 660 1305031251.5207729340 0.0763147548 0.0828890660 0.2294680178 0.0481139435 2.3084420000 0.9376470000 0.4370570000 0.0000060000 0.9221170000 0.0073760000 110884500 0 1786122240 3.9412713051 4.0449976921 3.9820220470 661 1305031251.5530450344 0.0763779506 0.0828792156 0.2294680178 0.0482005083 3.3618060000 0.9456560000 0.4029850000 0.1305430000 0.9294320000 0.9488610000 110886686 0 1785249792 3.9474503994 4.0474805832 3.9826416969 662 1305031251.5887598991 0.0742374361 0.0828661615 0.2294680178 0.0482254752 2.4017310000 0.9626960000 0.4837990000 0.0000050000 0.9434960000 0.0074590000 110888904 0 1787019264 3.9488635063 4.0547099113 3.9834737778 663 1305031251.6208739281 0.0735833496 0.0828521603 0.2294680178 0.0482534834 2.4183790000 0.9589010000 0.3638360000 0.1317440000 0.9520880000 0.0074420000 110891122 0 1784258560 3.9530673027 4.0576596260 3.9860551357 664 1305031251.6528749466 0.0728939027 0.0828371629 0.2294680178 0.0483096044 2.3643630000 0.9707370000 0.4156320000 0.0000050000 0.9662510000 0.0074900000 110893308 0 1785749504 3.9558243752 4.0621528625 3.9866905212 665 1305031251.6897680759 0.0728607774 0.0828221609 0.2294680178 0.0483384562 3.5511610000 0.9829290000 0.4575730000 0.1332450000 0.9767190000 0.9963900000 110895558 0 1787662336 3.9567298889 4.0670547485 3.9864976406 666 1305031251.7204608917 0.0740927607 0.0828090537 0.2294680178 0.0483898087 2.3165410000 0.9853700000 0.3338890000 0.0000060000 0.9855670000 0.0074180000 110897744 0 1784737792 3.9619410038 4.0674214363 3.9892568588 667 1305031251.7531440258 0.0776947588 0.0828013860 0.2294680178 0.0484752217 2.4990920000 0.9794780000 0.3746230000 0.1343820000 0.9988510000 0.0074400000 110899930 0 1786122240 3.9702000618 4.0633311272 3.9909052849 668 1305031251.7892498970 0.0826473907 0.0828011555 0.2294680178 0.0485065555 2.4102520000 0.9977340000 0.3789760000 0.0000050000 1.0217280000 0.0075060000 110902180 0 1785266176 3.9781954288 4.0667419434 3.9956314564 669 1305031251.8209791183 0.0856122822 0.0828053575 0.2294680178 0.0485360654 3.6449400000 0.9825300000 0.4158640000 0.1362260000 1.0392190000 1.0667120000 110904366 0 1786757120 3.9844336510 4.0685276985 4.0008645058 670 1305031251.8537969589 0.0931934863 0.0828208622 0.2294680178 0.0486404532 2.5029860000 0.9770310000 0.4490230000 0.0000060000 1.0650820000 0.0075100000 110906552 0 1784631296 3.9956116676 4.0660309792 4.0055990219 671 1305031251.8896539211 0.1024094373 0.0828500553 0.2294680178 0.0486324616 2.6386170000 0.9786820000 0.4001140000 0.1383430000 1.1096540000 0.0074210000 110908770 0 1785995264 4.0068321228 4.0687503815 4.0121955872 672 1305031251.9219300747 0.1033408642 0.0828805476 0.2294680178 0.0486210319 2.6224000000 1.0033040000 0.4721240000 0.0000050000 1.1351230000 0.0074000000 110910988 0 1787916288 4.0085406303 4.0781197548 4.0187983513 673 1305031251.9538369179 0.1032234654 0.0829107748 0.2294680178 0.0486205492 3.8254210000 0.9615160000 0.3991820000 0.1408610000 1.1476350000 1.1718640000 110913142 0 1784504320 4.0088109970 4.0860362053 4.0232272148 674 1305031251.9898068905 0.1040406302 0.0829421247 0.2294680178 0.0486131147 2.4060640000 0.9644950000 0.2728270000 0.0000060000 1.1569200000 0.0073820000 110915392 0 1786122240 4.0108971596 4.0886411667 4.0258455276 675 1305031252.0221600533 0.1052733064 0.0829752079 0.2294680178 0.0486309339 2.6447730000 0.9753400000 0.3523680000 0.1399900000 1.1651930000 0.0075050000 110917610 0 1785384960 4.0134229660 4.0944967270 4.0294346809 676 1305031252.0537619591 0.1074839011 0.0830114634 0.2294680178 0.0486258121 2.5859080000 0.9995880000 0.3965380000 0.0000060000 1.1779420000 0.0073870000 110919796 0 1786757120 4.0172686577 4.1064271927 4.0368132591 677 1305031252.0895619392 0.1055032536 0.0830446861 0.2294680178 0.0486644343 3.8223800000 0.9553070000 0.3632370000 0.1403250000 1.1680350000 1.1910410000 110922014 0 1784631296 4.0153918266 4.1191654205 4.0378341675 678 1305031252.1221520901 0.0991839767 0.0830684904 0.2294680178 0.0487137160 2.4597150000 0.9632850000 0.3241850000 0.0000060000 1.1604710000 0.0073700000 110924232 0 1786122240 4.0102734566 4.1277995110 4.0338339806 679 1305031252.1539709568 0.0954139754 0.0830866723 0.2294680178 0.0488175073 2.7511500000 0.9670570000 0.4789060000 0.1400300000 1.1532570000 0.0073990000 110926354 0 1788043264 4.0068068504 4.1415247917 4.0322046280 680 1305031252.1897890568 0.0909237191 0.0830981973 0.2294680178 0.0487979394 2.6126810000 0.9744790000 0.4738770000 0.0000060000 1.1523310000 0.0074020000 110928604 0 1784504320 3.9907877445 4.1623373032 4.0262227058 681 1305031252.2220859528 0.0881186500 0.0831055695 0.2294680178 0.0487742981 3.7923730000 0.9712050000 0.3931570000 0.1401510000 1.1276670000 1.1557750000 110930822 0 1786122240 3.9738953114 4.1763143539 4.0202875137 682 1305031252.2530639172 0.0827852339 0.0831050998 0.2294680178 0.0487427557 2.5846710000 0.9670270000 0.4734930000 0.0000050000 1.1322790000 0.0074210000 110933008 0 1787932672 3.9738953114 4.1763143539 4.0202875137 683 1305031252.2888779640 0.2269727886 0.0833157406 0.2294680178 0.0501040727 2.6428800000 0.9581560000 0.4241560000 0.1405170000 1.1081610000 0.0073410000 110935194 0 1784250368 3.7757065296 4.1909151077 3.8983364105 684 1305031252.3206090927 0.3086669147 0.0836452014 0.3086669147 0.0505394055 2.5937700000 0.9904570000 0.4265130000 0.0000050000 1.1649920000 0.0074010000 110937380 0 1785757696 3.7159700394 4.1675643921 3.8296637535 685 1305031252.3528549671 0.3830251396 0.0840822524 0.3830251396 0.0507315993 3.9962190000 0.9637040000 0.4072190000 0.1457360000 1.2130830000 1.2620730000 110939534 0 1787518976 3.6583211422 4.1646466255 3.7821030617 686 1305031252.3893189430 0.3985192180 0.0845406153 0.3985192180 0.0507439919 2.5877720000 0.9523860000 0.4102660000 0.0000050000 1.2132550000 0.0072980000 110941784 0 1784508416 3.6506533623 4.1591877937 3.7661261559 687 1305031252.4217019081 0.3919381499 0.0849880644 0.3985192180 0.0507340302 2.7033030000 0.9528890000 0.4018270000 0.1393310000 1.1973420000 0.0073580000 110944002 0 1785892864 3.6571140289 4.1636095047 3.7686440945 688 1305031252.4538249969 0.4113978744 0.0854624973 0.4113978744 0.0507280172 2.5789360000 0.9502710000 0.3947750000 0.0000040000 1.2221490000 0.0072610000 110946188 0 1787924480 3.6411521435 4.1645336151 3.7548983097 689 1305031252.4895589352 0.4177321792 0.0859447465 0.4177321792 0.0506991286 3.9810630000 0.9364130000 0.3886480000 0.1395890000 1.2241940000 1.2877830000 110948374 0 1784979456 3.6353828907 4.1686286926 3.7516353130 690 1305031252.5221700668 0.4498161674 0.0864720964 0.4498161674 0.0506882848 2.5686050000 0.9276290000 0.3770240000 0.0000040000 1.2523310000 0.0072390000 110950592 0 1786273792 3.6069607735 4.1657285690 3.7329320908 691 1305031252.5537741184 0.4676690698 0.0870237562 0.4676690698 0.0506568070 2.7430700000 0.9394060000 0.3758830000 0.1393200000 1.2766650000 0.0072470000 110952778 0 1785257984 3.5911986828 4.1663556099 3.7226009369 692 1305031252.5897459984 0.4548831880 0.0875553450 0.4676690698 0.0506244126 2.6470360000 0.9808520000 0.3792260000 0.0000040000 1.2750850000 0.0074630000 110954996 0 1786662912 3.6027979851 4.1684823036 3.7289655209 693 1305031252.6221249104 0.4243366122 0.0880413209 0.4676690698 0.0505938481 4.0753440000 0.9371650000 0.3854630000 0.1397520000 1.2740430000 1.3343350000 110957214 0 1784614912 3.6291489601 4.1668043137 3.7450981140 694 1305031252.6578559875 0.3913626075 0.0884783832 0.4676690698 0.0505628978 2.5883760000 0.9489740000 0.3846980000 0.0000050000 1.2427520000 0.0073460000 110959432 0 1786249216 3.6584458351 4.1676406860 3.7632808685 695 1305031252.6889979839 0.3801091313 0.0888979958 0.4676690698 0.0505780357 2.7632430000 0.9542050000 0.4047430000 0.1407450000 1.2516690000 0.0072990000 110961586 0 1788043264 3.6669661999 4.1632394791 3.7693867683 696 1305031252.7216539383 0.3631474376 0.0892920324 0.4676690698 0.0506680626 2.6416370000 0.9717570000 0.4216120000 0.0000050000 1.2362990000 0.0074510000 110963772 0 1784995840 3.6774477959 4.1593718529 3.7806193829 697 1305031252.7578220367 0.3580248058 0.0896775887 0.4676690698 0.0508484693 4.0574170000 0.9722300000 0.4319860000 0.1388890000 1.2292450000 1.2805840000 110966054 0 1786646528 3.6764905453 4.1553940773 3.7853293419 698 1305031252.7896919250 0.3771161139 0.0900893918 0.4676690698 0.0509960294 2.6458720000 0.9716560000 0.4426920000 0.0000050000 1.2196000000 0.0073580000 110968208 0 1785765888 3.6560065746 4.1498336792 3.7754065990 699 1305031252.8224050999 0.4064223468 0.0905419425 0.4676690698 0.0511586379 2.7700330000 0.9611170000 0.4323890000 0.1379590000 1.2264230000 0.0074530000 110970426 0 1787432960 3.6275029182 4.1461272240 3.7603249550 700 1305031252.8539779186 0.4186983109 0.0910107373 0.4676690698 0.0511675184 2.6234430000 0.9750020000 0.4123170000 0.0000040000 1.2240720000 0.0073890000 110972548 0 1784614912 3.6162154675 4.1382699013 3.7522940636 701 1305031252.8897290230 0.4316469431 0.0914966663 0.4676690698 0.0511735184 4.0306580000 0.9512530000 0.4001410000 0.1366640000 1.2337450000 1.3041400000 110974798 0 1786011648 3.6047039032 4.1253242493 3.7431793213 702 1305031252.9206719398 0.4343201518 0.0919850188 0.4676690698 0.0512129875 2.6221410000 0.9603110000 0.4101130000 0.0000050000 1.2384190000 0.0074410000 110976984 0 1787789312 3.6006231308 4.1225390434 3.7418577671 703 1305031252.9578649998 0.4448886514 0.0924870155 0.4676690698 0.0513567204 2.7942900000 0.9592590000 0.4178750000 0.1359500000 1.2691310000 0.0073230000 110979298 0 1784725504 3.5865347385 4.1166214943 3.7376618385 704 1305031252.9894239902 0.4596392810 0.0930085386 0.4676690698 0.0514792340 2.6745700000 0.9586740000 0.4160820000 0.0000050000 1.2878230000 0.0073220000 110981420 0 1786265600 3.5684726238 4.1114301682 3.7328655720 705 1305031253.0196959972 0.4531224668 0.0935193385 0.4676690698 0.0516195929 4.2003340000 0.9556410000 0.4238810000 0.1353800000 1.3055750000 1.3752390000 110983606 0 1785249792 3.5676400661 4.1048555374 3.7405052185 706 1305031253.0574259758 0.4627960026 0.0940423932 0.4676690698 0.0516854577 2.6906220000 0.9552090000 0.4076420000 0.0000050000 1.3157840000 0.0073780000 110985888 0 1786646528 3.5555098057 4.0894393921 3.7361423969 707 1305031253.0895500183 0.4603252113 0.0945604736 0.4676690698 0.0517420718 2.8389960000 0.9606650000 0.4039190000 0.1343610000 1.3280810000 0.0073660000 110988042 0 1784520704 3.5553371906 4.0763907433 3.7369987965 708 1305031253.1197240353 0.4714253545 0.0950927686 0.4714253545 0.0518055835 2.7624080000 0.9786470000 0.4163410000 0.0000050000 1.3554900000 0.0074010000 110990228 0 1785884672 3.5426518917 4.0748372078 3.7313919067 709 1305031253.1573839188 0.4690946937 0.0956202749 0.4714253545 0.0517867564 4.1755420000 0.9612870000 0.4037220000 0.0000050000 1.3563920000 1.4496030000 110992478 0 1787908096 3.5426518917 4.0748372078 3.7313919067 710 1305031253.1892180443 0.4685430229 0.0961455182 0.4714253545 0.0517601074 2.7504140000 0.9664620000 0.4165540000 0.0000050000 1.3554400000 0.0073980000 110994632 0 1784893440 3.5426518917 4.0748372078 3.7313919067 711 1305031253.2180271149 0.4682571888 0.0966688820 0.4714253545 0.0517424240 2.7889040000 0.9838600000 0.4308990000 0.0000050000 1.3621180000 0.0074190000 110996818 0 1786273792 3.5426518917 4.0748372078 3.7313919067 712 1305031253.2578470707 0.4681853354 0.0971906748 0.4714253545 0.0517584788 2.8038860000 0.9815100000 0.4549180000 0.0000040000 1.3554640000 0.0073950000 110999132 0 1785503744 3.5426518917 4.0748372078 3.7313919067 713 1305031253.2897419930 0.4686712921 0.0977116854 0.4714253545 0.0517366099 4.2469080000 0.9834920000 0.4596400000 0.0000040000 1.3559130000 1.4432910000 111001286 0 1786789888 3.5426518917 4.0748372078 3.7313919067 714 1305031253.3220069408 0.4692133069 0.0982319958 0.4714253545 0.0517071150 2.7878100000 0.9667730000 0.4472610000 0.0000040000 1.3616960000 0.0073700000 111003504 0 1784614912 3.5426518917 4.0748372078 3.7313919067 715 1305031253.3578300476 0.0712606981 0.0981942737 0.4714253545 0.0543242151 2.5340120000 0.9718810000 0.4391340000 0.1336280000 0.9772190000 0.0073770000 111005722 0 1786249216 3.9498612881 4.0812644958 4.0102057457 716 1305031253.3880970478 0.0702728927 0.0981552774 0.4714253545 0.0542870972 2.2852810000 0.9808220000 0.2893820000 0.0000040000 1.0021470000 0.0073500000 111007876 0 1785757696 3.9470553398 4.0860853195 4.0082154274 717 1305031253.4213519096 0.0727078617 0.0981197859 0.4714253545 0.0542507191 3.3673980000 0.9747190000 0.2138620000 0.1345880000 1.0094470000 1.0300800000 111010094 0 1785614336 3.9504189491 4.0848593712 4.0100698471 718 1305031253.4579629898 0.0732209459 0.0980851078 0.4714253545 0.0542149044 2.4230390000 0.9649350000 0.4236980000 0.0000050000 1.0225110000 0.0073770000 111012344 0 1787138048 3.9501552582 4.0861430168 4.0111527443 719 1305031253.4896900654 0.0714094639 0.0980480068 0.4714253545 0.0541775883 2.3636900000 0.9443700000 0.2468010000 0.1353430000 1.0251840000 0.0074720000 111014530 0 1784852480 3.9460124969 4.0890955925 4.0106449127 720 1305031253.5207340717 0.0720575228 0.0980119089 0.4714253545 0.0541417418 2.3250610000 0.9628810000 0.3196710000 0.0000040000 1.0306220000 0.0073840000 111016716 0 1786376192 3.9453201294 4.0865526199 4.0095248222 721 1305031253.5578539371 0.0721155554 0.0979759916 0.4714253545 0.0541064938 3.4105740000 0.9572830000 0.2137970000 0.1366200000 1.0403540000 1.0579580000 111018966 0 1785741312 3.9420211315 4.0883984566 4.0079255104 722 1305031253.5898048878 0.0696899220 0.0979368142 0.4714253545 0.0540745034 2.4556550000 0.9702200000 0.4380090000 0.0000050000 1.0353110000 0.0073840000 111021152 0 1787146240 3.9393703938 4.0911679268 4.0114159584 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 11:16:42 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253987648 0.0253987648 0.0253987648 nan 2.5541610000 0.9495920000 0.0554780000 0.1174420000 0.0000080000 1.4300110000 106449111 0 1770606592 4.0000000000 4.0000000000 4.0000000000 2 1305031102.2112140656 0.0277590584 0.0265789116 0.0277590584 0.0329534858 1.1037450000 0.9363370000 0.0424740000 0.1173590000 0.0000020000 0.0071560000 109198308 0 1772630016 4.0000000000 4.0000000000 4.0000000000 3 1305031102.2432110310 0.0337214470 0.0289597567 0.0337214470 0.0304148611 1.1240540000 0.9563610000 0.0426300000 0.1173440000 0.0000020000 0.0073100000 109200818 0 1774407680 4.0000000000 4.0000000000 4.0000000000 4 1305031102.2753260136 0.0413634107 0.0320606702 0.0413634107 0.0283056894 2.3468880000 0.9748970000 0.0426000000 0.1171050000 1.2047620000 0.0071720000 109203332 0 1783169024 4.0000000000 4.0000000000 4.0000000000 5 1305031102.3112668991 0.0195325762 0.0295550514 0.0413634107 0.0301328891 3.5507680000 0.9495830000 0.2402750000 0.1163650000 1.1169010000 1.1273260000 109205902 0 1785454592 3.9956083298 3.9985203743 4.0339026451 6 1305031102.3432331085 0.0165487379 0.0273873325 0.0413634107 0.0279495239 2.2839290000 0.9587590000 0.2441830000 0.0000030000 1.0734960000 0.0071830000 109208744 0 1787105280 3.9933271408 3.9974977970 4.0460596085 7 1305031102.3753290176 0.0143050468 0.0255184345 0.0413634107 0.0256323720 2.2843790000 0.9148360000 0.2398460000 0.1154250000 1.0067170000 0.0072240000 109210898 0 1785454592 3.9915554523 3.9987471104 4.0578465462 8 1305031102.4112579823 0.0161135532 0.0243428244 0.0413634107 0.0248950037 2.1008990000 0.9116820000 0.2026920000 0.0000030000 0.9790330000 0.0071290000 109213180 0 1787359232 3.9903795719 4.0006742477 4.0697312355 9 1305031102.4432709217 0.0140174208 0.0231955573 0.0413634107 0.0252536668 3.1751410000 0.9491360000 0.2759600000 0.1147570000 0.9093820000 0.9255610000 109216006 0 1787240448 3.9873242378 4.0034241676 4.0821056366 10 1305031102.4753179550 0.0116250403 0.0220385056 0.0413634107 0.0240300652 2.0388230000 0.9429540000 0.2128310000 0.0000030000 0.8754210000 0.0072920000 109219472 0 1785208832 3.9876480103 4.0076684952 4.0952630043 11 1305031102.5112190247 0.0164535064 0.0215307784 0.0413634107 0.0234075941 2.1837850000 0.9698200000 0.2761270000 0.1141460000 0.8161400000 0.0072170000 109221722 0 1786986496 3.9874100685 4.0066928864 4.1077718735 12 1305031102.5432200432 0.0179979354 0.0212363748 0.0413634107 0.0223196347 2.1360750000 0.9410330000 0.3858810000 0.0000060000 0.8015370000 0.0072820000 109223940 0 1785344000 3.9864935875 4.0065870285 4.1198072433 13 1305031102.5752859116 0.0202989932 0.0211642685 0.0413634107 0.0221625691 2.9826130000 0.9359630000 0.4187790000 0.1134000000 0.7479720000 0.7661430000 109226094 0 1786986496 3.9835627079 4.0057673454 4.1314249039 14 1305031102.6112329960 0.0283836257 0.0216799369 0.0413634107 0.0226180302 2.0238690000 0.9389580000 0.3520590000 0.0000050000 0.7252490000 0.0072470000 109228344 0 1785716736 3.9843041897 4.0026168823 4.1423964500 15 1305031102.6432650089 0.0308780223 0.0222931426 0.0413634107 0.0225169905 2.0198730000 0.9388400000 0.2793780000 0.1128680000 0.6812350000 0.0071970000 109230530 0 1787240448 3.9798440933 4.0030741692 4.1535253525 16 1305031102.6752851009 0.0282497071 0.0226654279 0.0413634107 0.0223324317 1.8771220000 0.9220900000 0.2769880000 0.0000030000 0.6705230000 0.0071630000 109232716 0 1785335808 3.9765012264 4.0097045898 4.1653256416 17 1305031102.7112629414 0.0316527896 0.0231940962 0.0413634107 0.0218753423 2.7666490000 0.9267590000 0.4101710000 0.1120740000 0.6494390000 0.6677680000 109236246 0 1787105280 3.9767916203 4.0127487183 4.1776680946 18 1305031102.7432339191 0.0347458757 0.0238358617 0.0413634107 0.0212933797 1.9785250000 0.9139330000 0.4166410000 0.0000020000 0.6403710000 0.0072030000 109241088 0 1785327616 3.9764461517 4.0140328407 4.1902947426 19 1305031102.7754719257 0.0331696235 0.0243271124 0.0413634107 0.0211189351 1.9785970000 0.9501690000 0.2906880000 0.1116470000 0.6183360000 0.0073720000 109243242 0 1786978304 3.9771418571 4.0198831558 4.2032251358 20 1305031102.8112320900 0.0379328988 0.0250074017 0.0413634107 0.0206063612 1.8437550000 0.9509370000 0.2855500000 0.0000030000 0.5995300000 0.0073300000 109245492 0 1785454592 3.9762976170 4.0221457481 4.2156286240 21 1305031102.8432900906 0.0390094444 0.0256741656 0.0413634107 0.0201131050 2.6671090000 0.9516200000 0.4304220000 0.1106590000 0.5755880000 0.5984170000 109247710 0 1787105280 3.9773490429 4.0256052017 4.2279887199 22 1305031102.8753631115 0.0411531404 0.0263777554 0.0413634107 0.0196993318 1.7690130000 0.9532470000 0.2474090000 0.0000050000 0.5607210000 0.0072380000 109249864 0 1785327616 3.9738907814 4.0273661613 4.2397880554 23 1305031102.9111850262 0.0446396582 0.0271717512 0.0446396582 0.0193029643 2.0174160000 0.9381630000 0.4224760000 0.1101740000 0.5389710000 0.0071790000 109252114 0 1786978304 3.9713754654 4.0300021172 4.2513899803 24 1305031102.9432289600 0.0453409366 0.0279288006 0.0453409366 0.0191911640 1.7834840000 0.9328930000 0.3177740000 0.0000050000 0.5251860000 0.0072340000 109254332 0 1785581568 3.9698698521 4.0335602760 4.2626900673 25 1305031102.9752030373 0.0475486554 0.0287135947 0.0475486554 0.0198999551 2.5169710000 0.9319590000 0.4197790000 0.1094840000 0.5187460000 0.5365840000 109256454 0 1787232256 3.9655344486 4.0359392166 4.2742624283 26 1305031103.0112149715 0.0510647967 0.0295732564 0.0510647967 0.0195083606 1.9124680000 0.9557530000 0.4355790000 0.0000030000 0.5133990000 0.0073170000 109258736 0 1785454592 3.9648766518 4.0386033058 4.2861351967 27 1305031103.0432269573 0.0534252599 0.0304566639 0.0534252599 0.0191430603 1.8538730000 0.9539110000 0.2829490000 0.1090210000 0.5000690000 0.0075080000 109260954 0 1787105280 3.9658603668 4.0412397385 4.2976789474 28 1305031103.0753190517 0.0555779561 0.0313538529 0.0555779561 0.0193357069 1.7182220000 0.9383290000 0.2807820000 0.0000030000 0.4914380000 0.0072110000 109263108 0 1785200640 3.9671678543 4.0437288284 4.3083133698 29 1305031103.1112399101 0.0594825521 0.0323238081 0.0594825521 0.0191790953 2.3052750000 0.9330750000 0.2792820000 0.1085440000 0.4832840000 0.5006340000 109265358 0 1786978304 3.9668984413 4.0455899239 4.3178935051 30 1305031103.1433179379 0.0581803992 0.0331856944 0.0594825521 0.0188755373 1.8462540000 0.9308480000 0.4278770000 0.0000040000 0.4798350000 0.0072620000 109267544 0 1785454592 3.9674363136 4.0516262054 4.3274383545 31 1305031103.1754519939 0.0602660216 0.0340592534 0.0602660216 0.0185753774 1.9563280000 0.9415750000 0.4230870000 0.1082460000 0.4757900000 0.0071950000 109269730 0 1787240448 3.9664056301 4.0536804199 4.3363981247 32 1305031103.2112200260 0.0610761009 0.0349035299 0.0610761009 0.0191004809 1.6641950000 0.9510530000 0.2456720000 0.0000050000 0.4597680000 0.0072420000 109271980 0 1785335808 3.9658954144 4.0586524010 4.3452425003 33 1305031103.2432160378 0.0621641092 0.0357296080 0.0621641092 0.0188225654 2.4065770000 0.9657100000 0.4290920000 0.1078640000 0.4423220000 0.4611120000 109276758 0 1786986496 3.9667818546 4.0620689392 4.3542499542 34 1305031103.2753698826 0.0650229454 0.0365911768 0.0650229454 0.0188545072 1.7217890000 0.9672460000 0.3246750000 0.0000030000 0.4220900000 0.0073210000 109284160 0 1785589760 3.9674775600 4.0629906654 4.3626856804 35 1305031103.3112099171 0.0700979903 0.0375485143 0.0700979903 0.0192341817 1.7418090000 0.9671980000 0.2513020000 0.1075360000 0.4080130000 0.0073010000 109286410 0 1787105280 3.9659316540 4.0604486465 4.3701715469 36 1305031103.3432230949 0.0758340433 0.0386120012 0.0758340433 0.0198419154 1.6560420000 0.9684960000 0.2816630000 0.0000040000 0.3981400000 0.0072730000 109288628 0 1785327616 3.9654870033 4.0556139946 4.3751053810 37 1305031103.3753271103 0.0763688982 0.0396324579 0.0763688982 0.0198019432 2.1023760000 0.9400050000 0.2431670000 0.1075830000 0.3960210000 0.4150430000 109290782 0 1787105280 3.9692285061 4.0556793213 4.3777890205 38 1305031103.4112598896 0.0775976405 0.0406315416 0.0775976405 0.0196933862 1.7882900000 0.9690820000 0.4193490000 0.0000030000 0.3921900000 0.0071940000 109293032 0 1785200640 3.9701297283 4.0531802177 4.3786306381 39 1305031103.4432799816 0.0807341412 0.0416598134 0.0807341412 0.0195207983 1.8712590000 0.9346930000 0.4237700000 0.1076400000 0.3975020000 0.0071880000 109295250 0 1786851328 3.9694590569 4.0481357574 4.3773732185 40 1305031103.4752740860 0.0811192095 0.0426462983 0.0811192095 0.0192878611 1.6319230000 0.9471450000 0.2807570000 0.0000040000 0.3962890000 0.0072390000 109297404 0 1785454592 3.9697344303 4.0450868607 4.3745651245 41 1305031103.5113329887 0.0811941326 0.0435864894 0.0811941326 0.0191526117 2.3321540000 0.9751340000 0.4257920000 0.1079850000 0.4020210000 0.4207180000 109299654 0 1787105280 3.9700365067 4.0407805443 4.3698334694 42 1305031103.5434439182 0.0811153427 0.0444800335 0.0811941326 0.0190261126 1.6657310000 0.9622750000 0.2855510000 0.0000050000 0.4101300000 0.0072490000 109301872 0 1785327616 3.9700148106 4.0357694626 4.3631515503 43 1305031103.5754740238 0.0802866817 0.0453127463 0.0811941326 0.0188469616 1.9401250000 0.9633260000 0.4350930000 0.1100870000 0.4237650000 0.0073540000 109304026 0 1786978304 3.9711318016 4.0310425758 4.3548889160 44 1305031103.6112229824 0.0770343617 0.0460336921 0.0811941326 0.0187167926 1.7042320000 0.9667930000 0.2905170000 0.0000050000 0.4390560000 0.0073420000 109306276 0 1785454592 3.9729042053 4.0282773972 4.3457350731 45 1305031103.6434450150 0.0753282011 0.0466846812 0.0811941326 0.0185085858 2.3014690000 0.9784430000 0.2871330000 0.1090040000 0.4537090000 0.4725760000 109308494 0 1787232256 3.9738574028 4.0236907005 4.3359274864 46 1305031103.6755230427 0.0724204332 0.0472441540 0.0811941326 0.0183371670 1.8108950000 0.9623350000 0.3603000000 0.0000040000 0.4804610000 0.0072690000 109310648 0 1785327616 3.9728178978 4.0198330879 4.3255658150 47 1305031103.7116100788 0.0688526630 0.0477039095 0.0811941326 0.0181542940 1.8385470000 0.9563290000 0.2529360000 0.1098400000 0.5116190000 0.0073200000 109312898 0 1787232256 3.9737257957 4.0162086487 4.3144388199 48 1305031103.7433259487 0.0657547414 0.0480799685 0.0811941326 0.0180084133 1.7332040000 0.9447230000 0.2462600000 0.0000050000 0.5343920000 0.0072930000 109315116 0 1785454592 3.9762902260 4.0123653412 4.3024816513 49 1305031103.7753419876 0.0638200045 0.0484011938 0.0811941326 0.0178209199 2.6268680000 0.9515250000 0.4291820000 0.1103440000 0.5553630000 0.5798470000 109317270 0 1787359232 3.9765288830 4.0066843033 4.2898831367 50 1305031103.8112421036 0.0589320771 0.0486118114 0.0811941326 0.0180232690 1.9548790000 0.9349140000 0.4267400000 0.0000050000 0.5854750000 0.0072100000 109319520 0 1785462784 3.9777123928 4.0048727989 4.2767734528 51 1305031103.8432509899 0.0550161973 0.0487373876 0.0811941326 0.0180115311 1.8811820000 0.9278890000 0.2450180000 0.1107520000 0.5897200000 0.0072490000 109321738 0 1787113472 3.9790956974 4.0025668144 4.2640242577 52 1305031103.8753609657 0.0524358787 0.0488085125 0.0811941326 0.0179545490 1.9887240000 0.9435040000 0.4304230000 0.0000050000 0.6069960000 0.0072410000 109323892 0 1785208832 3.9783837795 3.9991242886 4.2519931793 53 1305031103.9112210274 0.0556049198 0.0489367466 0.0811941326 0.0188718575 2.5238010000 0.9496900000 0.2089810000 0.1119930000 0.6161680000 0.6363400000 109326142 0 1787105280 3.9778008461 3.9886214733 4.2391557693 54 1305031103.9432110786 0.0558935963 0.0490655771 0.0811941326 0.0187446690 1.8324930000 0.9461510000 0.2112910000 0.0000050000 0.6671230000 0.0073590000 109328360 0 1785581568 3.9789459705 3.9813523293 4.2256379128 55 1305031103.9753730297 0.0520226732 0.0491193425 0.0811941326 0.0186829935 2.0615910000 0.9450920000 0.3144030000 0.1127980000 0.6814650000 0.0072430000 109330546 0 1787232256 3.9804711342 3.9784049988 4.2111053467 56 1305031104.0112318993 0.0503251031 0.0491408739 0.0811941326 0.0188758825 1.9633180000 0.9450270000 0.2823220000 0.0000050000 0.7281110000 0.0073180000 109332764 0 1785327616 3.9830892086 3.9732604027 4.1966261864 57 1305031104.0432488918 0.0481390208 0.0491232976 0.0811941326 0.0188147449 2.9903440000 0.9622640000 0.4264040000 0.1137690000 0.7323150000 0.7547330000 109334982 0 1787232256 3.9866814613 3.9676442146 4.1817464828 58 1305031104.0754249096 0.0415161066 0.0489921391 0.0811941326 0.0188506283 1.9881650000 0.9439330000 0.2837830000 0.0000050000 0.7525670000 0.0072540000 109337136 0 1785327616 3.9870510101 3.9672522545 4.1664109230 59 1305031104.1112349033 0.0357069932 0.0487669671 0.0811941326 0.0187794316 2.1298370000 0.9317290000 0.3157980000 0.1143780000 0.7600670000 0.0072060000 109339386 0 1786978304 3.9885196686 3.9667413235 4.1516208649 60 1305031104.1432299614 0.0334506519 0.0485116952 0.0811941326 0.0187359254 2.1407890000 0.9364550000 0.4254280000 0.0000050000 0.7710730000 0.0072150000 109341604 0 1785581568 3.9907495975 3.9611549377 4.1371169090 61 1305031104.1754240990 0.0298741609 0.0482061619 0.0811941326 0.0186805621 3.0653750000 0.9376890000 0.4224640000 0.1204910000 0.7831340000 0.8009480000 109343758 0 1787359232 3.9872703552 3.9578437805 4.1231193542 62 1305031104.2112829685 0.0269847568 0.0478638811 0.0811941326 0.0185807093 2.0017060000 0.9315230000 0.2426960000 0.0000050000 0.8195840000 0.0072690000 109346008 0 1785200640 3.9879837036 3.9558665752 4.1095018387 63 1305031104.2431960106 0.0239635687 0.0474845111 0.0811941326 0.0184578267 2.3307320000 0.9326150000 0.4285420000 0.1153680000 0.8463460000 0.0072280000 109348226 0 1786851328 3.9891364574 3.9525108337 4.0963702202 64 1305031104.2755460739 0.0196981262 0.0470503488 0.0811941326 0.0183190889 2.1329190000 0.9255200000 0.3148310000 0.0000040000 0.8846290000 0.0073260000 109350380 0 1785200640 3.9895737171 3.9513292313 4.0832099915 65 1305031104.3112189770 0.0163900405 0.0465786518 0.0811941326 0.0182212062 3.2035940000 0.9307730000 0.2789990000 0.1159920000 0.9323700000 0.9448020000 109357750 0 1786859520 3.9909279346 3.9509551525 4.0705265999 66 1305031104.3433420658 0.0120250480 0.0460551123 0.0811941326 0.0181233113 2.0945260000 0.9198800000 0.2059420000 0.0000040000 0.9607690000 0.0072900000 109370464 0 1785335808 3.9924683571 3.9502577782 4.0582599640 67 1305031104.3758370876 0.0093925251 0.0455079095 0.0811941326 0.0180499002 2.3493620000 0.9493090000 0.2778340000 0.1174980000 0.9967770000 0.0073150000 109372618 0 1786851328 3.9931683540 3.9502377510 4.0463910103 68 1305031104.4115090370 0.0065287147 0.0449346861 0.0811941326 0.0179820626 2.2684320000 0.9194410000 0.3093870000 0.0000040000 1.0317120000 0.0071660000 109374868 0 1785200640 3.9934597015 3.9497323036 4.0350289345 69 1305031104.4432880878 0.0045518423 0.0443494275 0.0811941326 0.0179075684 3.4154440000 0.9137720000 0.2394890000 0.1170430000 1.0667970000 1.0776840000 109377054 0 1786851328 3.9937138557 3.9486780167 4.0246386528 70 1305031104.4754559994 0.0045628045 0.0437810471 0.0811941326 0.0178323853 2.2299480000 0.8990350000 0.2381900000 0.0000040000 1.0848430000 0.0072180000 109379240 0 1784946688 3.9928417206 3.9481415749 4.0151948929 71 1305031104.5113289356 0.0073779025 0.0432683268 0.0811941326 0.0179126799 2.4592960000 0.9150840000 0.3171830000 0.1175780000 1.1016260000 0.0071730000 109381490 0 1786724352 3.9901728630 3.9458968639 4.0059685707 72 1305031104.5433681011 0.0059308964 0.0427497514 0.0811941326 0.0178840719 2.3265360000 0.9167530000 0.2766630000 0.0000050000 1.1251690000 0.0072820000 109383708 0 1785581568 3.9909224510 3.9422197342 3.9962759018 73 1305031104.5753428936 0.0045464244 0.0422264181 0.0811941326 0.0179908859 3.5856750000 0.9247200000 0.2399350000 0.1184530000 1.1447500000 1.1569880000 109385830 0 1787232256 3.9940617085 3.9403276443 3.9862864017 74 1305031104.6113359928 0.0067652753 0.0417472135 0.0811941326 0.0186724734 2.3686420000 0.9285240000 0.2428710000 0.0000040000 1.1892840000 0.0072980000 109388112 0 1785454592 3.9984314442 3.9357645512 3.9751830101 75 1305031104.6432430744 0.0103576584 0.0413286861 0.0811941326 0.0186699010 2.5342030000 0.9484490000 0.2427150000 0.1193930000 1.2156260000 0.0073270000 109390298 0 1786978304 4.0061759949 3.9320619106 3.9621164799 76 1305031104.6755249500 0.0169438403 0.0410078329 0.0811941326 0.0185513485 2.4984890000 0.9520940000 0.2437490000 0.0000050000 1.2946020000 0.0073660000 109392484 0 1785327616 4.0107798576 3.9379723072 3.9479608536 77 1305031104.7112770081 0.0213061925 0.0407519674 0.0811941326 0.0187354207 4.1085090000 0.9845890000 0.3409590000 0.1206370000 1.3158010000 1.3458110000 109394734 0 1786851328 4.0134258270 3.9396541119 3.9331388474 78 1305031104.7432799339 0.0287525691 0.0405981290 0.0811941326 0.0186356346 2.6262130000 0.9466090000 0.2757840000 0.0000050000 1.3958240000 0.0073030000 109396920 0 1785225216 4.0139541626 3.9449656010 3.9176712036 79 1305031104.7753269672 0.0388373770 0.0405758410 0.0811941326 0.0185394041 2.7590170000 0.9518290000 0.3016130000 0.1222800000 1.3751930000 0.0073040000 109399074 0 1786732544 4.0166726112 3.9519217014 3.9037382603 80 1305031104.8114650249 0.0465703495 0.0406507723 0.0811941326 0.0184689477 2.7698200000 0.9527940000 0.3822610000 0.0000030000 1.4267100000 0.0073290000 109401356 0 1785327616 4.0193276405 3.9573619366 3.8916387558 81 1305031104.8432579041 0.0573870875 0.0408573935 0.0811941326 0.0183794729 4.3105090000 0.9363100000 0.3352570000 0.1234700000 1.4248460000 1.4898930000 109403542 0 1786851328 4.0244417191 3.9650015831 3.8812289238 82 1305031104.8753499985 0.0630046427 0.0411274819 0.0811941326 0.0184004252 2.8325640000 0.9418010000 0.4163160000 0.0000030000 1.4664220000 0.0073070000 109405728 0 1785327616 4.0251870155 3.9698314667 3.8749327660 83 1305031104.9115340710 0.0690686256 0.0414641222 0.0811941326 0.0183347487 2.7821350000 0.9232000000 0.2701310000 0.1242120000 1.4565870000 0.0072740000 109407978 0 1786851328 4.0269064903 3.9757728577 3.8711757660 84 1305031104.9432621002 0.0730839297 0.0418405485 0.0811941326 0.0182314461 2.7732200000 0.8960460000 0.4108240000 0.0000030000 1.4584130000 0.0071950000 109410164 0 1785200640 4.0281925201 3.9795165062 3.8702700138 85 1305031104.9752020836 0.0747069940 0.0422272125 0.0811941326 0.0182087045 4.4469070000 0.9337130000 0.4132370000 0.1243970000 1.4542930000 1.5205370000 109412350 0 1786597376 4.0283055305 3.9818162918 3.8720920086 86 1305031105.0112900734 0.0784304813 0.0426481808 0.0811941326 0.0182793543 2.7893820000 0.9223010000 0.4155790000 0.0000030000 1.4434460000 0.0073030000 109414600 0 1785327616 4.0290665627 3.9877793789 3.8782486916 87 1305031105.0433731079 0.0813562050 0.0430931006 0.0813562050 0.0182332905 2.9044430000 0.9348010000 0.4186220000 0.1238200000 1.4191450000 0.0072930000 109416786 0 1786851328 4.0290980339 3.9938607216 3.8861074448 88 1305031105.0753200054 0.0782514066 0.0434926268 0.0813562050 0.0181648004 2.6130350000 0.9379950000 0.2807220000 0.0000020000 1.3862830000 0.0072910000 109418972 0 1785462784 4.0258746147 3.9942214489 3.8962523937 89 1305031105.1112990379 0.0760941952 0.0438589366 0.0813562050 0.0180779339 4.0728210000 0.9367690000 0.2821480000 0.1235590000 1.3465140000 1.3830740000 109421222 0 1786851328 4.0238981247 3.9939727783 3.9074742794 90 1305031105.1431059837 0.0710643977 0.0441612195 0.0813562050 0.0180664818 2.6648380000 0.9319300000 0.4238350000 0.0000030000 1.3010180000 0.0072790000 109423408 0 1785319424 4.0194606781 3.9925162792 3.9200346470 91 1305031105.1751589775 0.0692824647 0.0444372771 0.0813562050 0.0185150255 2.5819880000 0.9563170000 0.2472720000 0.1218500000 1.2483910000 0.0073760000 109425594 0 1786978304 4.0150990486 3.9975743294 3.9364800453 92 1305031105.2112679482 0.0653790310 0.0446649049 0.0813562050 0.0185421762 2.3975430000 0.9488370000 0.2459750000 0.0000020000 1.1946490000 0.0073070000 109427844 0 1785200640 4.0103564262 3.9986104965 3.9542918205 93 1305031105.2432699203 0.0548718944 0.0447746574 0.0813562050 0.0185383263 3.6170940000 0.9714720000 0.2434940000 0.1202240000 1.1301090000 1.1509600000 109430030 0 1786978304 4.0066847801 3.9912357330 3.9692187309 94 1305031105.2752881050 0.0486174561 0.0448155383 0.0813562050 0.0186980152 2.4607120000 0.9484010000 0.4256240000 0.0000020000 1.0784960000 0.0073860000 109432216 0 1785454592 4.0028624535 3.9906687737 3.9858410358 95 1305031105.3112900257 0.0421641618 0.0447876290 0.0813562050 0.0186871147 2.3641930000 0.9591110000 0.2462280000 0.1183720000 1.0322050000 0.0073630000 109434466 0 1787105280 3.9950418472 3.9886243343 4.0023002625 96 1305031105.3433020115 0.0337749235 0.0446729134 0.0813562050 0.0186121302 2.1924660000 0.9477150000 0.2455840000 0.0000020000 0.9910440000 0.0073110000 109436652 0 1785327616 3.9893145561 3.9846141338 4.0176591873 97 1305031105.3753380775 0.0263351221 0.0444838640 0.0813562050 0.0187479071 3.4164580000 0.9473430000 0.4250990000 0.1168190000 0.9534420000 0.9728990000 109438838 0 1787105280 3.9844572544 3.9794433117 4.0319042206 98 1305031105.4112861156 0.0249511953 0.0442845510 0.0813562050 0.0187805647 2.1212530000 0.9327190000 0.2436240000 0.0000030000 0.9367180000 0.0072810000 109441088 0 1785327616 3.9820997715 3.9786841869 4.0462808609 99 1305031105.4433159828 0.0221059937 0.0440605252 0.0813562050 0.0186979743 2.2178110000 0.9536460000 0.2475820000 0.1160650000 0.8923500000 0.0073170000 109443274 0 1786851328 3.9774780273 3.9830019474 4.0610270500 100 1305031105.4752800465 0.0181168821 0.0438010888 0.0813562050 0.0186310338 2.0337150000 0.9291200000 0.2337940000 0.0000030000 0.8626400000 0.0072770000 109445460 0 1785200640 3.9745800495 3.9801461697 4.0750970840 101 1305031105.5113320351 0.0191109963 0.0435566324 0.0813562050 0.0186127645 3.1616070000 0.9396900000 0.4213570000 0.1150930000 0.8333470000 0.8512270000 109447710 0 1786986496 3.9733746052 3.9811224937 4.0892219543 102 1305031105.5432820320 0.0173205603 0.0432994160 0.0813562050 0.0185425775 1.9562110000 0.9315560000 0.2078680000 0.0000030000 0.8087070000 0.0072430000 109449896 0 1785225216 3.9719123840 3.9825756550 4.1032233238 103 1305031105.5754489899 0.0173556991 0.0430475353 0.0813562050 0.0184573021 2.1721590000 0.9589870000 0.3124900000 0.1141980000 0.7784510000 0.0071830000 109452082 0 1787113472 3.9712038040 3.9818074703 4.1167268753 104 1305031105.6113779545 0.0208591074 0.0428341850 0.0813562050 0.0183736701 1.9200100000 0.9179720000 0.2409680000 0.0000030000 0.7529760000 0.0072470000 109454332 0 1785208832 3.9703288078 3.9835667610 4.1304054260 105 1305031105.6432731152 0.0232939683 0.0426480877 0.0813562050 0.0183505342 2.6669400000 0.9124220000 0.1742640000 0.1133010000 0.7245430000 0.7415480000 109456518 0 1786978304 3.9703412056 3.9824836254 4.1442513466 106 1305031105.6751658916 0.0235827826 0.0424682263 0.0813562050 0.0183145288 1.8568100000 0.9006330000 0.2398220000 0.0000030000 0.7083770000 0.0071220000 109458704 0 1785073664 3.9691970348 3.9850571156 4.1583395004 107 1305031105.7113089561 0.0277896319 0.0423310432 0.0813562050 0.0184037847 2.0102220000 0.9201910000 0.2759940000 0.1125740000 0.6933660000 0.0072410000 109460954 0 1786851328 3.9711818695 3.9876520634 4.1717715263 108 1305031105.7433118820 0.0305792037 0.0422222299 0.0813562050 0.0183253563 1.8555650000 0.9316350000 0.2432100000 0.0000030000 0.6726020000 0.0072380000 109463140 0 1785327616 3.9726200104 3.9884457588 4.1854801178 109 1305031105.7753388882 0.0288875774 0.0420998936 0.0813562050 0.0182488523 2.8060760000 0.9370740000 0.4239730000 0.1118650000 0.6541610000 0.6781280000 109465326 0 1786978304 3.9729056358 3.9942038059 4.1993083954 110 1305031105.8112831116 0.0342794359 0.0420287985 0.0813562050 0.0181846730 1.8957830000 0.9353540000 0.3164170000 0.0000030000 0.6358350000 0.0073000000 109467576 0 1785327616 3.9726803303 3.9959821701 4.2128448486 111 1305031105.8432710171 0.0352651216 0.0419678645 0.0813562050 0.0181051436 1.9144270000 0.9347510000 0.2414490000 0.1108390000 0.6192740000 0.0072550000 109469762 0 1786978304 3.9726569653 3.9990546703 4.2265591621 112 1305031105.8753368855 0.0358870253 0.0419135713 0.0813562050 0.0180452272 1.8209630000 0.9276340000 0.2783600000 0.0000030000 0.6068440000 0.0071640000 109471948 0 1785200640 3.9746689796 4.0031199455 4.2401099205 113 1305031105.9112620354 0.0377278142 0.0418765292 0.0813562050 0.0180698169 2.5343970000 0.9390080000 0.2833270000 0.1101410000 0.5914060000 0.6096200000 109474198 0 1786724352 3.9755861759 4.0091066360 4.2542686462 114 1305031105.9432721138 0.0392340384 0.0418533495 0.0813562050 0.0180057524 1.8124490000 0.9445580000 0.2842530000 0.0000030000 0.5755010000 0.0072390000 109476384 0 1785327616 3.9771428108 4.0124640465 4.2675619125 115 1305031105.9753289223 0.0400740765 0.0418378775 0.0813562050 0.0179876566 2.0471320000 0.9482030000 0.4271740000 0.1095030000 0.5541020000 0.0072630000 109478570 0 1786978304 3.9757316113 4.0170865059 4.2805457115 116 1305031106.0112850666 0.0446829200 0.0418624037 0.0813562050 0.0179346353 1.7153830000 0.9359540000 0.2442810000 0.0000030000 0.5268550000 0.0073870000 109480820 0 1785200640 3.9755761623 4.0206050873 4.2933063507 117 1305031106.0433549881 0.0464545526 0.0419016529 0.0813562050 0.0178575766 2.4191950000 0.9442590000 0.3514240000 0.1088280000 0.4977140000 0.5160640000 109483038 0 1786851328 3.9772975445 4.0242223740 4.3055849075 118 1305031106.0753300190 0.0491667353 0.0419632214 0.0813562050 0.0177979132 1.8428830000 0.9314450000 0.4208610000 0.0000040000 0.4824350000 0.0072000000 109485192 0 1785081856 3.9761331081 4.0270934105 4.3177471161 119 1305031106.1113269329 0.0524527878 0.0420513690 0.0813562050 0.0177854724 1.8824220000 0.9408500000 0.3511310000 0.1083080000 0.4739340000 0.0072820000 109487442 0 1786732544 3.9733505249 4.0315093994 4.3292493820 120 1305031106.1433548927 0.0534414649 0.0421462865 0.0813562050 0.0177189123 1.7128650000 0.9406610000 0.3165700000 0.0000040000 0.4474420000 0.0072850000 109489660 0 1785208832 3.9726819992 4.0356869698 4.3409709930 121 1305031106.1755340099 0.0581255034 0.0422783461 0.0813562050 0.0176513851 2.1942550000 0.9568350000 0.2410560000 0.1079800000 0.4343390000 0.4531030000 109491814 0 1786986496 3.9719121456 4.0359091759 4.3518857956 122 1305031106.2112751007 0.0621756800 0.0424414390 0.0813562050 0.0175826697 1.7506450000 0.9389620000 0.3828080000 0.0000040000 0.4205600000 0.0073440000 109494064 0 1785327616 3.9704384804 4.0378694534 4.3617472649 123 1305031106.2432670593 0.0667584911 0.0426391386 0.0813562050 0.0175144545 1.7125430000 0.9129500000 0.2735480000 0.1073760000 0.4105440000 0.0071840000 109496282 0 1786851328 3.9685225487 4.0376772881 4.3709573746 124 1305031106.2763850689 0.0686841011 0.0428491786 0.0813562050 0.0174498861 1.7371450000 0.9079900000 0.4129780000 0.0000050000 0.4080090000 0.0071170000 109498468 0 1785327616 3.9681394100 4.0408849716 4.3785276413 125 1305031106.3112380505 0.0682544634 0.0430524209 0.0813562050 0.0173927336 2.1794770000 0.9322350000 0.3107640000 0.1070780000 0.4046110000 0.4238180000 109500686 0 1787105280 3.9682967663 4.0449552536 4.3853912354 126 1305031106.3432579041 0.0698046312 0.0432647400 0.0813562050 0.0174004433 1.7457500000 0.9248220000 0.4192850000 0.0000060000 0.3934470000 0.0072230000 109502904 0 1785200640 3.9694058895 4.0468645096 4.3916649818 127 1305031106.3753879070 0.0690085664 0.0434674473 0.0813562050 0.0174253164 1.7747800000 0.9512860000 0.3215900000 0.1068520000 0.3867600000 0.0072930000 109505058 0 1786851328 3.9689197540 4.0499186516 4.3965439796 128 1305031106.4113199711 0.0734227970 0.0437014735 0.0813562050 0.0175675497 1.6771660000 0.9424540000 0.3559090000 0.0000030000 0.3704780000 0.0073430000 109507308 0 1785073664 3.9698674679 4.0465998650 4.3997011185 129 1305031106.4432780743 0.0795633495 0.0439794725 0.0813562050 0.0177043126 2.1478580000 0.9321580000 0.3513320000 0.1069060000 0.3687360000 0.3877120000 109519734 0 1786724352 3.9673941135 4.0398159027 4.4007711411 130 1305031106.4753448963 0.0819078386 0.0442712292 0.0819078386 0.0177625255 1.7076300000 0.9103780000 0.4161340000 0.0000030000 0.3730110000 0.0070900000 109542912 0 1785327616 3.9651286602 4.0355672836 4.3989410400 131 1305031106.5111289024 0.0822733268 0.0445613216 0.0822733268 0.0177704322 1.8354930000 0.9273000000 0.4164020000 0.1088120000 0.3747690000 0.0071890000 109545066 0 1786978304 3.9656438828 4.0316419601 4.3946094513 132 1305031106.5433020592 0.0827290192 0.0448504708 0.0827290192 0.0177178631 1.7099790000 0.9377500000 0.3846260000 0.0000030000 0.3793590000 0.0072370000 109547284 0 1785327616 3.9648017883 4.0269861221 4.3879346848 133 1305031106.5752820969 0.0806872696 0.0451199204 0.0827290192 0.0176730019 2.1984180000 0.9452950000 0.3531180000 0.1075670000 0.3860520000 0.4053770000 109549438 0 1786724352 3.9669959545 4.0240974426 4.3790268898 134 1305031106.6111509800 0.0772200376 0.0453594735 0.0827290192 0.0176962142 1.6108720000 0.9306250000 0.2769480000 0.0000030000 0.3950380000 0.0072490000 109551688 0 1785200640 3.9658808708 4.0217819214 4.3692750931 135 1305031106.6432070732 0.0750346333 0.0455792895 0.0827290192 0.0176655815 1.6976670000 0.9402950000 0.2448300000 0.1079440000 0.3962990000 0.0072740000 109553906 0 1786724352 3.9654152393 4.0185093880 4.3589086533 136 1305031106.6752789021 0.0760577545 0.0458033959 0.0827290192 0.0176245535 1.7059650000 0.9736110000 0.3174790000 0.0000030000 0.4066160000 0.0072090000 109556060 0 1785073664 3.9655802250 4.0117239952 4.3473644257 137 1305031106.7115080357 0.0730782822 0.0460024826 0.0827290192 0.0176533819 2.2047290000 0.9545610000 0.2827650000 0.1086280000 0.4195140000 0.4382350000 109558310 0 1786732544 3.9652843475 4.0090942383 4.3350310326 138 1305031106.7433409691 0.0729802549 0.0461979737 0.0827290192 0.0176420836 1.7231210000 0.9637230000 0.3251220000 0.0000030000 0.4259040000 0.0073410000 109560528 0 1785335808 3.9651327133 4.0032758713 4.3222355843 139 1305031106.7753899097 0.0718765110 0.0463827114 0.0827290192 0.0175836060 1.8456330000 0.9654820000 0.3203220000 0.1095470000 0.4419770000 0.0072610000 109562682 0 1786851328 3.9664473534 3.9985790253 4.3087511063 140 1305031106.8112890720 0.0690533519 0.0465446446 0.0827290192 0.0175431522 1.8480930000 0.9518980000 0.4287140000 0.0000050000 0.4590810000 0.0073240000 109564932 0 1785200640 3.9698989391 3.9956467152 4.2941951752 141 1305031106.8434159756 0.0659264624 0.0466821043 0.0827290192 0.0175082769 2.3786200000 0.9533480000 0.3168140000 0.1108100000 0.4884700000 0.5081150000 109567118 0 1786597376 3.9710731506 3.9927167892 4.2797880173 142 1305031106.8759050369 0.0670673549 0.0468256624 0.0827290192 0.0176398494 1.9267110000 0.9597400000 0.4309680000 0.0000050000 0.5276560000 0.0072740000 109569304 0 1785327616 3.9704809189 3.9839808941 4.2641253471 143 1305031106.9112429619 0.0634580776 0.0469419730 0.0827290192 0.0176940514 2.0200210000 0.9624490000 0.3967750000 0.1167470000 0.5353200000 0.0073980000 109571554 0 1786851328 3.9659943581 3.9808194637 4.2469291687 144 1305031106.9434390068 0.0559304953 0.0470043932 0.0827290192 0.0176489863 1.9273630000 0.9361650000 0.4205270000 0.0000040000 0.5623520000 0.0072460000 109573740 0 1785327616 3.9670219421 3.9809668064 4.2293024063 145 1305031106.9755470753 0.0548939519 0.0470588040 0.0827290192 0.0176599128 2.5416140000 0.9459950000 0.2876880000 0.1119700000 0.5847210000 0.6101600000 109575926 0 1786724352 3.9662857056 3.9740276337 4.2116580009 146 1305031107.0115759373 0.0524543077 0.0470957595 0.0827290192 0.0176193457 1.8965730000 0.9550210000 0.3264620000 0.0000040000 0.6066750000 0.0073410000 109578208 0 1785073664 3.9651634693 3.9688720703 4.1933951378 147 1305031107.0432810783 0.0421775244 0.0470623021 0.0827290192 0.0176449039 1.9673760000 0.9283120000 0.2837830000 0.1126570000 0.6342710000 0.0072620000 109580394 0 1786597376 3.9650077820 3.9724957943 4.1755299568 148 1305031107.0754320621 0.0413146950 0.0470234669 0.0827290192 0.0176772934 2.0586050000 0.9503490000 0.4341020000 0.0000040000 0.6657370000 0.0072790000 109582548 0 1785327616 3.9630608559 3.9659161568 4.1592988968 149 1305031107.1112289429 0.0410467423 0.0469833547 0.0827290192 0.0176232122 2.8550340000 0.9395870000 0.4259800000 0.1135050000 0.6783940000 0.6964740000 109584798 0 1786724352 3.9622545242 3.9599616528 4.1429262161 150 1305031107.1432600021 0.0347097181 0.0469015304 0.0827290192 0.0176198364 2.0614490000 0.9206490000 0.4271790000 0.0000040000 0.7052730000 0.0071720000 109587016 0 1785073664 3.9628136158 3.9609134197 4.1273264885 151 1305031107.1753990650 0.0297473520 0.0467879266 0.0827290192 0.0175715678 2.0666190000 0.9086250000 0.3068760000 0.1142340000 0.7285540000 0.0072310000 109589170 0 1786724352 3.9639136791 3.9599609375 4.1125507355 152 1305031107.2113580704 0.0316885971 0.0466885889 0.0827290192 0.0176556444 2.1124480000 0.9235730000 0.4268450000 0.0000050000 0.7535570000 0.0073510000 109591420 0 1785200640 3.9625840187 3.9531383514 4.0978174210 153 1305031107.2433779240 0.0278921444 0.0465657363 0.0827290192 0.0176054085 3.0488980000 0.9445350000 0.3925210000 0.1153070000 0.7891680000 0.8062510000 109593606 0 1787002880 3.9638028145 3.9513707161 4.0834918022 154 1305031107.2753980160 0.0235373005 0.0464162010 0.0827290192 0.0175589273 2.1935680000 0.9334460000 0.4237070000 0.0000050000 0.8280350000 0.0072640000 109595792 0 1785462784 3.9653108120 3.9513325691 4.0696172714 155 1305031107.3112258911 0.0217661802 0.0462571687 0.0827290192 0.0175587731 2.1963510000 0.9361260000 0.2811530000 0.1160670000 0.8546080000 0.0072300000 109598042 0 1787240448 3.9670305252 3.9488272667 4.0556616783 156 1305031107.3435089588 0.0224770308 0.0461047319 0.0827290192 0.0176218911 2.0946600000 0.9401720000 0.2479960000 0.0000050000 0.8979550000 0.0074130000 109600260 0 1785327616 3.9658272266 3.9449799061 4.0421986580 157 1305031107.3754129410 0.0174611658 0.0459222888 0.0827290192 0.0176485920 3.2360170000 0.9575810000 0.2485690000 0.1168730000 0.9469760000 0.9647640000 109602414 0 1786978304 3.9709265232 3.9457504749 4.0293707848 158 1305031107.4112710953 0.0140575087 0.0457206130 0.0827290192 0.0176216279 2.1546740000 0.9548370000 0.2107520000 0.0000040000 0.9806500000 0.0073030000 109604664 0 1785200640 3.9761555195 3.9494450092 4.0195560455 159 1305031107.4434189796 0.0150407432 0.0455276578 0.0827290192 0.0175716161 2.3673070000 0.9519680000 0.2843750000 0.1177820000 1.0046970000 0.0073430000 109606882 0 1786978304 3.9796946049 3.9507136345 4.0114727020 160 1305031107.4753770828 0.0170741640 0.0453498235 0.0827290192 0.0175242118 2.2868590000 0.9450370000 0.3182930000 0.0000050000 1.0151230000 0.0072560000 109609068 0 1785454592 3.9857454300 3.9541046619 4.0056762695 161 1305031107.5113520622 0.0213914607 0.0452010138 0.0827290192 0.0174952584 3.3620970000 0.9431380000 0.2434900000 0.1180850000 1.0186260000 1.0375980000 109611286 0 1787232256 3.9893598557 3.9562847614 4.0013909340 162 1305031107.5436050892 0.0259918608 0.0450824387 0.0827290192 0.0175099242 2.2808150000 0.9300060000 0.3146280000 0.0000050000 1.0278040000 0.0072250000 109613504 0 1785327616 3.9929182529 3.9616949558 3.9998013973 163 1305031107.5754539967 0.0261077229 0.0449660294 0.0827290192 0.0174895798 2.2707700000 0.9217310000 0.2078180000 0.1180490000 1.0148120000 0.0072200000 109615658 0 1787105280 3.9949052334 3.9604165554 3.9987673759 164 1305031107.6112709045 0.0259782132 0.0448502501 0.0827290192 0.0174463568 2.1876040000 0.9164430000 0.2434390000 0.0000050000 1.0192300000 0.0073150000 109617908 0 1785454592 3.9976181984 3.9587264061 3.9980869293 165 1305031107.6433229446 0.0264948085 0.0447390050 0.0827290192 0.0174353475 3.5346590000 0.9406150000 0.4256500000 0.1178770000 1.0153120000 1.0339690000 109620126 0 1787232256 4.0023608208 3.9650640488 3.9997527599 166 1305031107.6755681038 0.0257825367 0.0446248094 0.0827290192 0.0174024554 2.3584130000 0.9194920000 0.4164600000 0.0000050000 1.0140420000 0.0072410000 109622280 0 1785454592 4.0015830994 3.9650063515 4.0012478828 167 1305031107.7113070488 0.0243993215 0.0445036987 0.0827290192 0.0173582333 2.3374090000 0.9080410000 0.3049660000 0.1177920000 0.9982080000 0.0072150000 109624530 0 1787240448 4.0018110275 3.9658107758 4.0030174255 168 1305031107.7435379028 0.0248048734 0.0443864438 0.0827290192 0.0173392157 2.1708780000 0.9260220000 0.2422130000 0.0000050000 0.9941430000 0.0072980000 109626716 0 1785335808 4.0002694130 3.9693157673 4.0055599213 169 1305031107.7758018970 0.0247413460 0.0442702006 0.0827290192 0.0172959516 3.2597030000 0.9351700000 0.2438910000 0.1173630000 0.9714190000 0.9906420000 109628902 0 1786986496 3.9986317158 3.9714515209 4.0082125664 170 1305031107.8115959167 0.0226906594 0.0441432621 0.0827290192 0.0172468495 2.1352590000 0.9223440000 0.2417080000 0.0000050000 0.9628010000 0.0072050000 109631152 0 1785454592 3.9976029396 3.9703140259 4.0107827187 171 1305031107.8433320522 0.0212168563 0.0440091895 0.0827290192 0.0172054000 2.4369550000 0.9467580000 0.4190520000 0.1169780000 0.9457160000 0.0072390000 109633338 0 1787232256 3.9987556934 3.9714577198 4.0133213997 172 1305031107.8753581047 0.0209718253 0.0438752514 0.0827290192 0.0171808040 2.1474430000 0.9242950000 0.2734320000 0.0000040000 0.9412930000 0.0071990000 109635524 0 1785581568 3.9980237484 3.9706006050 4.0153527260 173 1305031107.9115409851 0.0205292795 0.0437403036 0.0827290192 0.0171632764 3.1381560000 0.9250250000 0.2093750000 0.1169260000 0.9332000000 0.9523960000 109637774 0 1787105280 3.9999804497 3.9689476490 4.0168304443 174 1305031107.9431219101 0.0224104635 0.0436177183 0.0827290192 0.0171679334 2.1358050000 0.9340610000 0.2459630000 0.0000050000 0.9472150000 0.0072060000 109639960 0 1785200640 4.0022649765 3.9692533016 4.0179772377 175 1305031107.9758069515 0.0261482485 0.0435178927 0.0827290192 0.0171543662 2.2445280000 0.9244020000 0.2424340000 0.1167140000 0.9524900000 0.0072610000 109642146 0 1786978304 4.0066227913 3.9700949192 4.0189752579 176 1305031108.0113201141 0.0291079991 0.0434360183 0.0827290192 0.0171204902 2.1508780000 0.9542880000 0.2126150000 0.0000040000 0.9754230000 0.0073170000 109644396 0 1785454592 4.0113692284 3.9703474045 4.0200943947 177 1305031108.0434179306 0.0323601402 0.0433734428 0.0827290192 0.0170816429 3.3267760000 0.9571890000 0.2492500000 0.1171210000 0.9898570000 1.0121130000 109646582 0 1787105280 4.0182576180 3.9735178947 4.0215740204 178 1305031108.0753519535 0.0351868793 0.0433274508 0.0827290192 0.0170470928 2.2462050000 0.9613950000 0.2490910000 0.0000050000 1.0271680000 0.0072870000 109648736 0 1785327616 4.0268945694 3.9772148132 4.0230402946 179 1305031108.1113779545 0.0434120148 0.0433279233 0.0827290192 0.0170067736 2.5728570000 0.9776050000 0.4321730000 0.1171350000 1.0374240000 0.0072880000 109650986 0 1787105280 4.0320982933 3.9770112038 4.0244965553 180 1305031108.1433339119 0.0477773361 0.0433526422 0.0827290192 0.0169791895 2.4632540000 0.9569760000 0.4272930000 0.0000050000 1.0703660000 0.0073470000 109653172 0 1785454592 4.0387182236 3.9781694412 4.0270814896 181 1305031108.1760580540 0.0522345454 0.0434017135 0.0827290192 0.0170101116 3.6357340000 0.9823780000 0.3870570000 0.1170990000 1.0579690000 1.0899590000 109655358 0 1787113472 4.0503687859 3.9824717045 4.0300779343 182 1305031108.2114748955 0.0538947880 0.0434593678 0.0827290192 0.0169997857 2.4247970000 0.9594890000 0.3916920000 0.0000040000 1.0649740000 0.0073530000 109657608 0 1785081856 4.0600500107 3.9871654510 4.0343961716 183 1305031108.2433469296 0.0540806837 0.0435174077 0.0827290192 0.0169943996 2.3945840000 0.9585640000 0.2787860000 0.1168910000 1.0317060000 0.0073310000 109659794 0 1786859520 4.0696754456 3.9832341671 4.0378398895 184 1305031108.2753579617 0.0548073165 0.0435787659 0.0827290192 0.0169502599 2.2946330000 0.9547830000 0.2821130000 0.0000040000 1.0491050000 0.0073060000 109661980 0 1785454592 4.0798034668 3.9796924591 4.0405659676 185 1305031108.3113319874 0.0610586330 0.0436732517 0.0827290192 0.0170661617 3.4301110000 0.9633050000 0.2824130000 0.1167290000 1.0122840000 1.0540370000 109664230 0 1786978304 4.0874323845 3.9858717918 4.0441145897 186 1305031108.3432779312 0.0619699843 0.0437716212 0.0827290192 0.0170555414 2.3033850000 0.9624890000 0.3188700000 0.0000040000 1.0133790000 0.0073680000 109666448 0 1785200640 4.0963249207 3.9884161949 4.0483188629 187 1305031108.3754100800 0.0614137091 0.0438659640 0.0827290192 0.0170260532 2.3135450000 0.9676940000 0.2491230000 0.1163050000 0.9717290000 0.0073290000 109668602 0 1786978304 4.1067280769 3.9881751537 4.0522737503 188 1305031108.4113609791 0.0636709109 0.0439713094 0.0827290192 0.0169854455 2.2665870000 0.9675620000 0.3280380000 0.0000040000 0.9620990000 0.0075120000 109670852 0 1785581568 4.1182875633 3.9870893955 4.0560231209 189 1305031108.4436099529 0.0611030310 0.0440619534 0.0827290192 0.0169967664 3.3495780000 0.9755380000 0.3577520000 0.1158070000 0.9305170000 0.9686410000 109673070 0 1787105280 4.1320900917 3.9853360653 4.0587940216 190 1305031108.4754710197 0.0603691898 0.0441477810 0.0827290192 0.0169975821 2.3239890000 0.9829290000 0.4062640000 0.0000040000 0.9259770000 0.0074710000 109675224 0 1785327616 4.1443066597 3.9838535786 4.0613174438 191 1305031108.5113780499 0.0649150759 0.0442565103 0.0827290192 0.0172478517 2.4706690000 0.9781450000 0.4494360000 0.1158850000 0.9185300000 0.0073380000 109677474 0 1786978304 4.1558041573 3.9809448719 4.0625252724 192 1305031108.5437369347 0.0652362779 0.0443657799 0.0827290192 0.0172914990 2.1995810000 0.9936650000 0.2541020000 0.0000050000 0.9430510000 0.0074560000 109679692 0 1785200640 4.1683773994 3.9789278507 4.0620827675 193 1305031108.5754139423 0.0673061162 0.0444846418 0.0827290192 0.0173277912 3.3018800000 0.9934710000 0.3241830000 0.1158420000 0.9147140000 0.9522230000 109681846 0 1787105280 4.1781053543 3.9800879955 4.0626220703 194 1305031108.6114070415 0.0731207281 0.0446322505 0.0827290192 0.0173251110 2.3736140000 0.9835840000 0.4391520000 0.0000050000 0.9421720000 0.0073910000 109684096 0 1785479168 4.1859936714 3.9875292778 4.0636763573 195 1305031108.6433029175 0.0747233033 0.0447865636 0.0827290192 0.0172906277 2.4423440000 0.9783920000 0.4291630000 0.1156270000 0.9104040000 0.0073370000 109686314 0 1787240448 4.1959676743 3.9880785942 4.0646648407 196 1305031108.6753749847 0.0762136504 0.0449469058 0.0827290192 0.0172897075 2.2305410000 0.9736190000 0.3240730000 0.0000050000 0.9240700000 0.0074190000 109688468 0 1785327616 4.2047333717 3.9922184944 4.0665736198 197 1305031108.7114109993 0.0802344903 0.0451260306 0.0827290192 0.0173029676 3.3702200000 0.9850760000 0.4327960000 0.1156490000 0.8998670000 0.9354490000 109690686 0 1787105280 4.2137989998 3.9949493408 4.0679330826 198 1305031108.7435019016 0.0827571526 0.0453160868 0.0827571526 0.0172760017 2.1654740000 0.9766050000 0.2532870000 0.0000040000 0.9267430000 0.0074520000 109692904 0 1785200640 4.2213559151 3.9931063652 4.0688776970 199 1305031108.7754929066 0.0835704282 0.0455083197 0.0835704282 0.0172354561 2.4156590000 0.9782940000 0.4310780000 0.1162560000 0.8812210000 0.0073340000 109695058 0 1786978304 4.2290296555 3.9930694103 4.0694293976 200 1305031108.8112440109 0.0844885111 0.0457032206 0.0844885111 0.0171940374 2.3237090000 0.9834510000 0.4402890000 0.0000030000 0.8911870000 0.0074080000 109697308 0 1785327616 4.2367906570 3.9950757027 4.0694637299 201 1305031108.8432641029 0.0834670514 0.0458911004 0.0844885111 0.0185379971 3.1042450000 0.9709650000 0.2529240000 0.1158560000 0.8603470000 0.9027670000 109699526 0 1787232256 4.2437601089 3.9941899776 4.0684080124 202 1305031108.8765149117 0.0773719996 0.0460469464 0.0844885111 0.0185675150 2.1030420000 0.9732060000 0.2576640000 0.0000040000 0.8634090000 0.0073540000 109701712 0 1785200640 4.2509293556 3.9933292866 4.0665020943 203 1305031108.9113640785 0.0733229294 0.0461813109 0.0844885111 0.0186461638 2.4042420000 0.9696660000 0.4421970000 0.1157300000 0.8679070000 0.0073700000 109703930 0 1786978304 4.2561845779 3.9929599762 4.0640950203 204 1305031108.9432430267 0.0730672628 0.0463131047 0.0844885111 0.0187147932 2.0684950000 0.9759420000 0.2213470000 0.0000040000 0.8624160000 0.0073810000 109706148 0 1785200640 4.2589049339 3.9890010357 4.0608954430 205 1305031108.9752678871 0.0701912567 0.0464295835 0.0844885111 0.0186946438 3.1622410000 0.9823250000 0.2913970000 0.1158560000 0.8680640000 0.9031600000 109708334 0 1786978304 4.2591590881 3.9896447659 4.0580992699 206 1305031109.0112690926 0.0643675774 0.0465166612 0.0844885111 0.0186649863 2.0860180000 0.9675990000 0.2526230000 0.0000040000 0.8570750000 0.0073170000 109710552 0 1785200640 4.2577357292 3.9944632053 4.0564308167 207 1305031109.0432770252 0.0611390285 0.0465873006 0.0844885111 0.0186469237 2.3104760000 0.9771290000 0.3571010000 0.1157480000 0.8517010000 0.0073350000 109712770 0 1786724352 4.2558331490 3.9924597740 4.0541977882 208 1305031109.0754098892 0.0603323504 0.0466533826 0.0844885111 0.0186427584 2.1068720000 0.9653660000 0.2901410000 0.0000040000 0.8425510000 0.0073530000 109714924 0 1785462784 4.2494540215 3.9928755760 4.0531411171 209 1305031109.1112821102 0.0553513989 0.0466949999 0.0844885111 0.0186151521 3.0272440000 0.9745390000 0.2552320000 0.1159010000 0.8229850000 0.8571460000 109717174 0 1787113472 4.2422318459 3.9960970879 4.0529561043 210 1305031109.1433339119 0.0531231351 0.0467256101 0.0844885111 0.0185951641 2.0535730000 0.9604130000 0.2796630000 0.0000040000 0.8047440000 0.0073540000 109719392 0 1785208832 4.2355427742 3.9921846390 4.0519113541 211 1305031109.1754639149 0.0512049794 0.0467468393 0.0844885111 0.0186016347 2.1297060000 0.9783630000 0.2538190000 0.1158930000 0.7727150000 0.0073730000 109721546 0 1786978304 4.2281212807 3.9907574654 4.0510635376 212 1305031109.2113790512 0.0442470387 0.0467350478 0.0844885111 0.0185989609 2.0423410000 0.9812450000 0.2921430000 0.0000040000 0.7600690000 0.0074340000 109723796 0 1785581568 4.2201309204 3.9951457977 4.0516457558 213 1305031109.2432899475 0.0397881679 0.0467024333 0.0844885111 0.0185625827 3.0377080000 0.9927640000 0.4412860000 0.1158750000 0.7332070000 0.7531070000 109726014 0 1787105280 4.2111711502 3.9992804527 4.0534000397 214 1305031109.2753078938 0.0398831293 0.0466705674 0.0844885111 0.0187013850 1.9361930000 0.9883410000 0.2093190000 0.0000040000 0.7297010000 0.0073570000 109728168 0 1785327616 4.2010664940 3.9917809963 4.0537543297 215 1305031109.3113288879 0.0383728556 0.0466319734 0.0844885111 0.0187653312 2.0892470000 0.9925940000 0.2578380000 0.1158060000 0.7140480000 0.0074250000 109730418 0 1786851328 4.1892542839 3.9851784706 4.0532937050 216 1305031109.3432478905 0.0338755921 0.0465729161 0.0844885111 0.0187977232 2.0229000000 0.9969420000 0.2985110000 0.0000050000 0.7185920000 0.0073810000 109732636 0 1785200640 4.1777167320 3.9898171425 4.0539932251 217 1305031109.3753969669 0.0314030610 0.0465030089 0.0844885111 0.0187596513 2.7755990000 0.9982290000 0.2171120000 0.1156820000 0.7120150000 0.7310600000 109734790 0 1786724352 4.1656208038 3.9903397560 4.0550880432 218 1305031109.4113290310 0.0275046993 0.0464158607 0.0844885111 0.0187196510 1.9905510000 1.0049620000 0.2568830000 0.0000060000 0.7198300000 0.0073970000 109737040 0 1785200640 4.1551237106 3.9867684841 4.0553102493 219 1305031109.4433019161 0.0231989510 0.0463098474 0.0844885111 0.0186980410 2.0922470000 0.9970040000 0.2594830000 0.1155910000 0.7112830000 0.0074140000 109739226 0 1786724352 4.1443095207 3.9893867970 4.0557699203 220 1305031109.4753630161 0.0223822165 0.0462010855 0.0844885111 0.0186829187 2.0149520000 0.9920560000 0.2955680000 0.0000050000 0.7184210000 0.0074130000 109741380 0 1785327616 4.1311502457 3.9886336327 4.0558876991 221 1305031109.5112729073 0.0212226342 0.0460880608 0.0844885111 0.0186658337 2.7955860000 0.9923800000 0.2561430000 0.1160910000 0.7052140000 0.7242420000 109743630 0 1786978304 4.1180224419 3.9850895405 4.0549173355 222 1305031109.5432939529 0.0227539930 0.0459829524 0.0844885111 0.0186431458 1.9695950000 0.9933260000 0.2592240000 0.0000050000 0.7080920000 0.0074390000 109745848 0 1785073664 4.1043772697 3.9826192856 4.0532078743 223 1305031109.5753619671 0.0196524374 0.0458648783 0.0844885111 0.0186030311 2.0408730000 0.9870720000 0.2176990000 0.1157570000 0.7114860000 0.0073380000 109748034 0 1786597376 4.0936417580 3.9846692085 4.0512981415 224 1305031109.6113100052 0.0159238633 0.0457312131 0.0844885111 0.0185854239 1.9497400000 0.9693400000 0.2531900000 0.0000040000 0.7183660000 0.0073250000 109750252 0 1785462784 4.0802578926 3.9865968227 4.0496501923 225 1305031109.6432290077 0.0156529061 0.0455975317 0.0844885111 0.0185448319 2.8491510000 0.9680850000 0.2908670000 0.1157540000 0.7300280000 0.7428720000 109752470 0 1786859520 4.0678887367 3.9873452187 4.0484972000 226 1305031109.6752629280 0.0130959721 0.0454537195 0.0844885111 0.0185062535 2.1362060000 0.9593640000 0.4358170000 0.0000050000 0.7321030000 0.0073890000 109754624 0 1785208832 4.0582451820 3.9893150330 4.0477385521 227 1305031109.7113120556 0.0110612847 0.0453022110 0.0844885111 0.0185341735 2.2834150000 0.9921510000 0.4430640000 0.1158310000 0.7234120000 0.0074190000 109756874 0 1786724352 4.0456571579 3.9905529022 4.0477404594 228 1305031109.7432739735 0.0094155651 0.0451448134 0.0844885111 0.0184943617 1.9743500000 0.9728660000 0.2517960000 0.0000050000 0.7408120000 0.0073160000 109759092 0 1785327616 4.0323796272 3.9932205677 4.0487461090 229 1305031109.7752768993 0.0103332400 0.0449927978 0.0844885111 0.0184715927 2.8405840000 0.9524820000 0.3179170000 0.1155760000 0.7197570000 0.7332410000 109761246 0 1786724352 4.0195899010 3.9923415184 4.0500020981 230 1305031109.8113710880 0.0098498398 0.0448400024 0.0844885111 0.0184398565 2.0723950000 0.9447290000 0.3906700000 0.0000050000 0.7281450000 0.0072420000 109763496 0 1785327616 4.0069017410 3.9921772480 4.0511541367 231 1305031109.8432960510 0.0087238122 0.0446836552 0.0844885111 0.0184072465 2.0371830000 0.9550800000 0.2462050000 0.1153370000 0.7117280000 0.0072880000 109765714 0 1786724352 3.9940085411 3.9941055775 4.0530476570 232 1305031109.8753058910 0.0089277197 0.0445295348 0.0844885111 0.0183754048 1.9196380000 0.9625330000 0.2108520000 0.0000040000 0.7373500000 0.0073290000 109767868 0 1785200640 3.9802317619 3.9946858883 4.0558099747 233 1305031109.9112648964 0.0116136437 0.0443882649 0.0844885111 0.0183523252 2.9281200000 0.9446320000 0.4260480000 0.1152120000 0.7107570000 0.7298110000 109770118 0 1786851328 3.9614944458 3.9932863712 4.0589671135 234 1305031109.9432990551 0.0128762275 0.0442535981 0.0844885111 0.0183414526 2.0093140000 0.9473740000 0.3225300000 0.0000040000 0.7306080000 0.0072380000 109772336 0 1785454592 3.9497811794 3.9932184219 4.0623183250 235 1305031109.9752581120 0.0105097229 0.0441100071 0.0844885111 0.0183072269 2.2272900000 0.9439350000 0.4277060000 0.1152940000 0.7315790000 0.0071880000 109774490 0 1786978304 3.9374785423 3.9972229004 4.0661234856 236 1305031110.0112559795 0.0143301487 0.0439838213 0.0844885111 0.0182722986 1.9430230000 0.9458650000 0.2192350000 0.0000040000 0.7688740000 0.0074440000 109776740 0 1785454592 3.9242146015 3.9951162338 4.0696225166 237 1305031110.0432989597 0.0154454624 0.0438634062 0.0844885111 0.0182352934 3.0062490000 0.9544050000 0.4303500000 0.1153130000 0.7417800000 0.7628090000 109778958 0 1787105280 3.9113934040 3.9954779148 4.0732307434 238 1305031110.0753190517 0.0172618814 0.0437516351 0.0844885111 0.0182119232 2.1591050000 0.9461360000 0.4382830000 0.0000050000 0.7658080000 0.0072870000 109781112 0 1785581568 3.9006464481 3.9956643581 4.0767078400 239 1305031110.1113250256 0.0186460707 0.0436465909 0.0844885111 0.0182290255 2.2281040000 0.9490250000 0.4278480000 0.1153760000 0.7268920000 0.0073530000 109783362 0 1787240448 3.8858025074 3.9962751865 4.0806832314 240 1305031110.1434319019 0.0224941578 0.0435584558 0.0844885111 0.0182567916 2.1687670000 0.9579660000 0.4289170000 0.0000040000 0.7724110000 0.0078490000 109785580 0 1785335808 3.8738210201 3.9931375980 4.0841007233 241 1305031110.1756410599 0.0256104693 0.0434839828 0.0844885111 0.0182192486 2.9551410000 0.9479780000 0.4258470000 0.1153690000 0.7217040000 0.7425750000 109787734 0 1786986496 3.8641171455 3.9915904999 4.0874028206 242 1305031110.2116370201 0.0262745079 0.0434128693 0.0844885111 0.0181900087 2.1428560000 0.9424060000 0.4262900000 0.0000040000 0.7652490000 0.0072240000 109790016 0 1785454592 3.8544063568 3.9948401451 4.0898714066 243 1305031110.2433230877 0.0307501070 0.0433607591 0.0844885111 0.0181907543 2.2301500000 0.9439500000 0.4211790000 0.1155460000 0.7405600000 0.0072750000 109792202 0 1787232256 3.8446342945 3.9907488823 4.0924882889 244 1305031110.2793209553 0.0338453688 0.0433217616 0.0844885111 0.0181666903 2.0811270000 0.9481940000 0.3537370000 0.0000050000 0.7694790000 0.0080490000 109794452 0 1785327616 3.8340587616 3.9893069267 4.0942764282 245 1305031110.3114039898 0.0346661471 0.0432864326 0.0844885111 0.0181310496 2.8936590000 0.9456810000 0.2814350000 0.1160130000 0.7698670000 0.7789540000 109796606 0 1786978304 3.8248193264 3.9893460274 4.0950121880 246 1305031110.3433549404 0.0343266949 0.0432500109 0.0844885111 0.0181042274 2.1882720000 0.9552300000 0.4278810000 0.0000040000 0.7961790000 0.0072680000 109798792 0 1785454592 3.8135545254 3.9909257889 4.0956406593 247 1305031110.3792810440 0.0362021141 0.0432214769 0.0844885111 0.0180926490 2.1891700000 0.9550980000 0.3177350000 0.1156150000 0.7918090000 0.0072760000 109801042 0 1786978304 3.8040709496 3.9926052094 4.0961074829 248 1305031110.4114689827 0.0372196883 0.0431972762 0.0844885111 0.0180715782 2.2352490000 0.9602800000 0.4319660000 0.0000050000 0.8340100000 0.0073370000 109803228 0 1785200640 3.7932317257 3.9934613705 4.0967445374 249 1305031110.4432599545 0.0369858332 0.0431723306 0.0844885111 0.0180421975 3.2089040000 0.9806290000 0.4283650000 0.1162730000 0.8292900000 0.8526810000 109805414 0 1786851328 3.7819039822 3.9982550144 4.0979762077 250 1305031110.4793310165 0.0415192246 0.0431657182 0.0844885111 0.0180700575 2.1413510000 0.9733190000 0.2911050000 0.0000050000 0.8678860000 0.0073760000 109807696 0 1785327616 3.7716388702 3.9980475903 4.0994467735 251 1305031110.5114290714 0.0468328670 0.0431803283 0.0844885111 0.0180564996 2.4072820000 0.9913410000 0.4377790000 0.1165730000 0.8524410000 0.0074050000 109809850 0 1786978304 3.7640321255 3.9948291779 4.1017413139 252 1305031110.5434079170 0.0485356674 0.0432015797 0.0844885111 0.0180311959 2.3030790000 0.9924870000 0.4062480000 0.0000060000 0.8952300000 0.0073770000 109812068 0 1785200640 3.7533216476 3.9960691929 4.1035904884 253 1305031110.5794260502 0.0514978841 0.0432343714 0.0844885111 0.0180227305 3.3642710000 1.0032430000 0.4401120000 0.1169860000 0.8862840000 0.9159350000 109814318 0 1787002880 3.7443823814 4.0001506805 4.1052384377 254 1305031110.6113069057 0.0532513633 0.0432738084 0.0844885111 0.0180358445 2.3719200000 0.9952560000 0.4436670000 0.0000050000 0.9238640000 0.0074040000 109816472 0 1785335808 3.7332279682 3.9999966621 4.1077551842 255 1305031110.6434180737 0.0585142933 0.0433335750 0.0844885111 0.0180675885 2.4589930000 1.0032880000 0.4415020000 0.1173530000 0.8877450000 0.0074230000 109818690 0 1786978304 3.7270505428 3.9937293530 4.1098465919 256 1305031110.6796059608 0.0588690601 0.0433942605 0.0844885111 0.0180824819 2.3715160000 1.0018570000 0.4514230000 0.0000060000 0.9089950000 0.0074760000 109820908 0 1785200640 3.7178568840 3.9951992035 4.1100621223 257 1305031110.7114119530 0.0579991601 0.0434510889 0.0844885111 0.0180536186 3.4256760000 1.0043770000 0.4487290000 0.1177660000 0.9092900000 0.9437570000 109843574 0 1786724352 3.7103133202 3.9992635250 4.1108345985 258 1305031110.7432489395 0.0609150156 0.0435187785 0.0844885111 0.0180672706 2.1912010000 0.9944940000 0.2551540000 0.0000050000 0.9323560000 0.0074450000 109887744 0 1784946688 3.7060792446 3.9952151775 4.1122331619 259 1305031110.7791929245 0.0625201911 0.0435921430 0.0844885111 0.0180334781 2.4839580000 0.9995550000 0.4415310000 0.1180530000 0.9156260000 0.0074070000 109889994 0 1786597376 3.7007808685 3.9933240414 4.1130671501 260 1305031110.8113861084 0.0618477687 0.0436623570 0.0844885111 0.0180001275 2.3231640000 0.9775190000 0.4028930000 0.0000040000 0.9336660000 0.0073500000 109892180 0 1785454592 3.6982593536 3.9954822063 4.1130099297 261 1305031110.8432180882 0.0606719814 0.0437275280 0.0844885111 0.0179775800 3.4043080000 0.9880700000 0.4093260000 0.1175650000 0.9248880000 0.9627110000 109894366 0 1787105280 3.6947197914 3.9964046478 4.1129984856 262 1305031110.8793129921 0.0632586032 0.0438020740 0.0844885111 0.0179451038 2.3861710000 0.9972360000 0.4421300000 0.0000050000 0.9376060000 0.0074530000 109896616 0 1785327616 3.6931045055 3.9921219349 4.1148443222 263 1305031110.9113330841 0.0632494241 0.0438760183 0.0844885111 0.0179219387 2.2867000000 0.9711720000 0.2593100000 0.1176590000 0.9293630000 0.0074280000 109898802 0 1786724352 3.6949751377 3.9934260845 4.1151318550 264 1305031110.9438619614 0.0636168644 0.0439507943 0.0844885111 0.0179111790 2.2990530000 0.9765570000 0.3763760000 0.0000040000 0.9370140000 0.0073590000 109901020 0 1785454592 3.6962208748 3.9923987389 4.1160044670 265 1305031110.9793450832 0.0621777773 0.0440195753 0.0844885111 0.0179363635 3.2229800000 0.9910490000 0.2211330000 0.1178810000 0.9255690000 0.9655430000 109903206 0 1787105280 3.7004511356 3.9939308167 4.1160335541 266 1305031111.0114309788 0.0604872182 0.0440814838 0.0844885111 0.0179253493 2.1958850000 1.0106670000 0.2601760000 0.0000040000 0.9157260000 0.0074780000 109905424 0 1785327616 3.7067561150 3.9972357750 4.1161069870 267 1305031111.0433270931 0.0620696694 0.0441488553 0.0844885111 0.0178922410 2.4242510000 1.0060240000 0.4141840000 0.1177830000 0.8769660000 0.0074970000 109907610 0 1786986496 3.7122795582 3.9944033623 4.1173443794 268 1305031111.0792829990 0.0573571660 0.0441981400 0.0844885111 0.0178890058 2.1303920000 1.0046790000 0.2620630000 0.0000040000 0.8544150000 0.0074330000 109909828 0 1785208832 3.7166256905 3.9975111485 4.1159482002 269 1305031111.1115078926 0.0567076206 0.0442446436 0.0844885111 0.0178704616 3.1332150000 1.0080660000 0.2993610000 0.1176320000 0.8407270000 0.8656330000 109912046 0 1786724352 3.7247462273 3.9971165657 4.1154389381 270 1305031111.1432569027 0.0579525903 0.0442954138 0.0844885111 0.0178549140 2.2986450000 1.0015860000 0.4538020000 0.0000040000 0.8339300000 0.0074990000 109914232 0 1785454592 3.7345418930 3.9945974350 4.1153783798 271 1305031111.1793260574 0.0548829995 0.0443344824 0.0844885111 0.0178996160 2.3184740000 1.0359010000 0.3349330000 0.1173420000 0.8210200000 0.0074650000 109916482 0 1787232256 3.7427196503 3.9952542782 4.1141729355 272 1305031111.2114329338 0.0531957597 0.0443670606 0.0844885111 0.0178832811 2.2447860000 1.0095170000 0.4229660000 0.0000040000 0.8029850000 0.0074780000 109918636 0 1785200640 3.7553250790 3.9967958927 4.1127929688 273 1305031111.2432360649 0.0494992286 0.0443858598 0.0844885111 0.0179263055 3.1432120000 0.9918630000 0.4497730000 0.1167870000 0.7810640000 0.8019000000 109920822 0 1786851328 3.7615292072 3.9982068539 4.1109848022 274 1305031111.2793080807 0.0494587459 0.0444043740 0.0844885111 0.0179849989 1.9824530000 0.9798700000 0.2180950000 0.0000040000 0.7752850000 0.0073770000 109923072 0 1785200640 3.7720243931 3.9934227467 4.1099557877 275 1305031111.3115470409 0.0473767892 0.0444151827 0.0844885111 0.0179950769 2.3134270000 0.9797490000 0.4426500000 0.1166490000 0.7651280000 0.0074270000 109925258 0 1786851328 3.7850008011 3.9946928024 4.1089591980 276 1305031111.3433969021 0.0405248962 0.0444010875 0.0844885111 0.0181399491 2.1418780000 0.9609750000 0.4083470000 0.0000050000 0.7633440000 0.0073580000 109927444 0 1785327616 3.7895834446 4.0014944077 4.1070256233 277 1305031111.3791339397 0.0446318351 0.0444019205 0.0844885111 0.0182809039 2.9698480000 0.9550890000 0.3590980000 0.1164430000 0.7592060000 0.7781560000 109929694 0 1786978304 3.8028042316 3.9949958324 4.1091237068 278 1305031111.4112958908 0.0454281941 0.0444056122 0.0844885111 0.0182579686 2.1698640000 0.9585270000 0.4438330000 0.0000040000 0.7582920000 0.0073710000 109931848 0 1785454592 3.8151626587 3.9919168949 4.1087460518 279 1305031111.4433860779 0.0404550284 0.0443914524 0.0844885111 0.0182494788 2.1269460000 0.9884080000 0.2496230000 0.1169540000 0.7625920000 0.0073680000 109934066 0 1786978304 3.8229849339 3.9968142509 4.1074352264 280 1305031111.4792590141 0.0393979885 0.0443736186 0.0844885111 0.0187038834 2.1237560000 0.9724720000 0.3705230000 0.0000040000 0.7715260000 0.0073970000 109936316 0 1785454592 3.8424532413 3.9954378605 4.1068353653 281 1305031111.5112640858 0.0368273593 0.0443467635 0.0844885111 0.0187018160 3.0591910000 0.9814430000 0.4441050000 0.1163800000 0.7482500000 0.7671570000 109938470 0 1787240448 3.8571629524 3.9954545498 4.1045575142 282 1305031111.5432500839 0.0360033400 0.0443171769 0.0844885111 0.0186842907 2.1507310000 0.9672060000 0.4414140000 0.0000040000 0.7328490000 0.0073760000 109940688 0 1785335808 3.8644402027 3.9940690994 4.1026530266 283 1305031111.5792369843 0.0352202021 0.0442850321 0.0844885111 0.0187066940 2.0177290000 0.9575710000 0.2161240000 0.1158340000 0.7190420000 0.0072810000 109942938 0 1786986496 3.8786115646 3.9931354523 4.1007285118 284 1305031111.6112709045 0.0322417095 0.0442426261 0.0844885111 0.0187905699 1.9714590000 1.0010290000 0.2576370000 0.0000040000 0.7035200000 0.0073700000 109945060 0 1785327616 3.8892116547 3.9962608814 4.0993695259 285 1305031111.6433949471 0.0375214331 0.0442190429 0.0844885111 0.0188162869 2.6883410000 0.9458740000 0.2178620000 0.1155310000 0.6940450000 0.7130820000 109947278 0 1786978304 3.8995118141 3.9902057648 4.0995454788 286 1305031111.6793200970 0.0370610766 0.0441940151 0.0844885111 0.0190175665 1.9418480000 0.9699040000 0.2608100000 0.0000040000 0.7017930000 0.0074480000 109949496 0 1785454592 3.9181497097 3.9887337685 4.0982336998 287 1305031111.7117600441 0.0295097157 0.0441428503 0.0844885111 0.0190382925 2.0539600000 0.9791030000 0.2577150000 0.1150780000 0.6927660000 0.0073640000 109951714 0 1787105280 3.9327604771 3.9960477352 4.0961680412 288 1305031111.7433860302 0.0315742306 0.0440992092 0.0844885111 0.0191282160 2.0829350000 0.9598520000 0.4398440000 0.0000040000 0.6739360000 0.0073880000 109953900 0 1785327616 3.9459347725 3.9929964542 4.0948715210 289 1305031111.7794229984 0.0312696882 0.0440548164 0.0844885111 0.0192171500 2.7607470000 0.9710450000 0.3314290000 0.1146520000 0.6638250000 0.6778740000 109956150 0 1786978304 3.9610204697 3.9945557117 4.0932040215 290 1305031111.8114058971 0.0310075618 0.0440098259 0.0844885111 0.0192394531 2.0177010000 0.9642470000 0.4049560000 0.0000040000 0.6392930000 0.0072760000 109958304 0 1785454592 3.9711670876 3.9972136021 4.0914359093 291 1305031111.8432989120 0.0351040959 0.0439792220 0.0844885111 0.0192181263 2.0089700000 0.9554970000 0.2887530000 0.1142010000 0.6413180000 0.0072750000 109960490 0 1787232256 3.9798731804 3.9963505268 4.0900273323 292 1305031111.8794419765 0.0370038860 0.0439553339 0.0844885111 0.0192196678 2.0393100000 0.9649210000 0.4302980000 0.0000040000 0.6347130000 0.0074770000 109962708 0 1785327616 3.9914569855 4.0004000664 4.0898752213 293 1305031111.9113540649 0.0385610126 0.0439369232 0.0844885111 0.0192451094 2.7971120000 0.9553220000 0.4362760000 0.1143230000 0.6324840000 0.6567260000 109964926 0 1787105280 4.0034537315 3.9984650612 4.0901999474 294 1305031111.9433000088 0.0404022336 0.0439249005 0.0844885111 0.0192131805 1.8433860000 0.9473000000 0.2537150000 0.0000050000 0.6329620000 0.0072910000 109967112 0 1785327616 4.0166306496 3.9948866367 4.0905985832 295 1305031111.9794490337 0.0397290252 0.0439106772 0.0844885111 0.0193594987 1.9905590000 0.9641660000 0.2623880000 0.1144340000 0.6402620000 0.0073480000 109969330 0 1786978304 4.0330080986 3.9964852333 4.0908460617 296 1305031112.0114328861 0.0370853208 0.0438876185 0.0844885111 0.0193838745 1.8526550000 0.9749690000 0.2244560000 0.0000050000 0.6439190000 0.0073670000 109971548 0 1785581568 4.0461726189 3.9995033741 4.0893330574 297 1305031112.0432701111 0.0420647413 0.0438814809 0.0844885111 0.0193519933 2.6947680000 0.9814630000 0.2929970000 0.1145750000 0.6419040000 0.6618340000 109973734 0 1787367424 4.0534839630 3.9982440472 4.0880718231 298 1305031112.0793390274 0.0464406051 0.0438900686 0.0844885111 0.0193931770 2.0858500000 0.9816400000 0.4455530000 0.0000040000 0.6493120000 0.0073440000 109975984 0 1785081856 4.0643053055 3.9997076988 4.0865449905 299 1305031112.1114230156 0.0517568327 0.0439163788 0.0844885111 0.0194600950 2.0540290000 0.9916650000 0.2959950000 0.1149990000 0.6419640000 0.0074320000 109978138 0 1786859520 4.0703015327 4.0003528595 4.0853371620 300 1305031112.1443419456 0.0551390834 0.0439537878 0.0844885111 0.0194375944 1.9372400000 0.9853940000 0.2974820000 0.0000050000 0.6449700000 0.0074050000 109980324 0 1785335808 4.0792598724 4.0007696152 4.0849947929 301 1305031112.1793899536 0.0608345382 0.0440098701 0.0844885111 0.0195180522 2.8918400000 1.0059790000 0.4560090000 0.1157560000 0.6450320000 0.6669580000 109982510 0 1787105280 4.0899763107 4.0028200150 4.0845026970 302 1305031112.2112538815 0.0664865524 0.0440842962 0.0844885111 0.0195097512 1.8663090000 0.9955240000 0.2211570000 0.0000040000 0.6402170000 0.0074070000 109984696 0 1785200640 4.0983691216 3.9994750023 4.0841393471 303 1305031112.2433691025 0.0709630325 0.0441730049 0.0844885111 0.0195338247 2.0270470000 0.9952240000 0.2636000000 0.1154690000 0.6433400000 0.0074250000 109986914 0 1786851328 4.1092920303 3.9928112030 4.0823206902 304 1305031112.2793529034 0.0766152292 0.0442797227 0.0844885111 0.0195212105 1.9241180000 0.9870390000 0.2578740000 0.0000040000 0.6698310000 0.0073520000 109989132 0 1785454592 4.1201167107 3.9936959743 4.0811524391 305 1305031112.3113119602 0.0784096494 0.0443916241 0.0844885111 0.0195135996 2.9214190000 0.9805740000 0.3944640000 0.1157520000 0.7048810000 0.7237190000 109991350 0 1787105280 4.1307597160 3.9929568768 4.0801296234 306 1305031112.3433229923 0.0781971291 0.0445020996 0.0844885111 0.0194914465 1.9658210000 0.9758650000 0.2437870000 0.0000050000 0.7366500000 0.0074620000 109993536 0 1785327616 4.1435990334 3.9921321869 4.0785918236 307 1305031112.3793599606 0.0806699991 0.0446199104 0.0844885111 0.0194668035 2.0754500000 0.9745960000 0.2076470000 0.1171360000 0.7666640000 0.0073950000 109995818 0 1787105280 4.1556501389 3.9956939220 4.0777306557 308 1305031112.4114420414 0.0785484836 0.0447300681 0.0844885111 0.0194460573 1.9829260000 0.9522880000 0.2513810000 0.0000040000 0.7698500000 0.0073780000 109997972 0 1785200640 4.1688323021 3.9975633621 4.0771417618 309 1305031112.4433910847 0.0767545626 0.0448337072 0.0844885111 0.0194318363 2.8308610000 0.9540020000 0.1791540000 0.1155560000 0.7744840000 0.8055710000 110000190 0 1786978304 4.1817002296 3.9974067211 4.0764107704 310 1305031112.4794180393 0.0777342021 0.0449398378 0.0844885111 0.0194131845 2.0200310000 0.9664640000 0.2586010000 0.0000050000 0.7855270000 0.0073770000 110002440 0 1785454592 4.1945934296 3.9963049889 4.0753312111 311 1305031112.5115039349 0.0748078749 0.0450358765 0.0844885111 0.0193987680 2.0997120000 0.9592660000 0.2254660000 0.1155540000 0.7899820000 0.0073320000 110004594 0 1787105280 4.2068867683 3.9982070923 4.0741567612 312 1305031112.5432119370 0.0733775496 0.0451267152 0.0844885111 0.0193792653 2.1920890000 0.9595800000 0.4356310000 0.0000040000 0.7875570000 0.0072610000 110006780 0 1785327616 4.2177815437 3.9972734451 4.0735025406 313 1305031112.5792520046 0.0747522861 0.0452213656 0.0844885111 0.0193502939 2.9157320000 0.9457390000 0.2495510000 0.1152850000 0.7896290000 0.8134480000 110008998 0 1787113472 4.2274432182 3.9983096123 4.0732250214 314 1305031112.6112608910 0.0726446658 0.0453087010 0.0844885111 0.0193926584 1.9984790000 0.9479570000 0.2518990000 0.0000040000 0.7892930000 0.0072890000 110011184 0 1785208832 4.2379531860 3.9999332428 4.0729656219 315 1305031112.6432459354 0.0717766359 0.0453927262 0.0844885111 0.0194173636 2.3313510000 0.9714340000 0.4339950000 0.1152570000 0.8010650000 0.0073970000 110013402 0 1786859520 4.2457919121 4.0034270287 4.0732588768 316 1305031112.6799519062 0.0753902271 0.0454876550 0.0844885111 0.0194106306 2.1085100000 0.9683780000 0.3013060000 0.0000040000 0.8293280000 0.0074360000 110015652 0 1785335808 4.2497878075 4.0029778481 4.0737810135 317 1305031112.7112510204 0.0765284598 0.0455855755 0.0844885111 0.0194097178 3.0590770000 0.9712000000 0.2540620000 0.1152740000 0.8409290000 0.8755430000 110017806 0 1787105280 4.2527484894 4.0035619736 4.0747404099 318 1305031112.7432448864 0.0764495581 0.0456826320 0.0844885111 0.0194064901 2.0846490000 0.9701450000 0.2605780000 0.0000040000 0.8445670000 0.0073160000 110020024 0 1785327616 4.2549505234 4.0078315735 4.0763435364 319 1305031112.7793099880 0.0756219849 0.0457764858 0.0844885111 0.0194088289 2.2649560000 1.0144660000 0.2941160000 0.1153560000 0.8313980000 0.0074700000 110022274 0 1787232256 4.2554292679 4.0124664307 4.0786504745 320 1305031112.8113100529 0.0746008158 0.0458665618 0.0844885111 0.0194243431 2.0631310000 0.9780690000 0.2529650000 0.0000050000 0.8226580000 0.0073770000 110024428 0 1785327616 4.2559704781 4.0073885918 4.0795645714 321 1305031112.8432860374 0.0723562762 0.0459490843 0.0844885111 0.0194381932 3.1946940000 0.9780730000 0.4431790000 0.1151680000 0.8078340000 0.8483440000 110026614 0 1786978304 4.2550334930 4.0085754395 4.0811719894 322 1305031112.8794209957 0.0672937185 0.0460153720 0.0844885111 0.0194452855 2.2244410000 0.9797360000 0.4504690000 0.0000050000 0.7848120000 0.0073300000 110028864 0 1785454592 4.2551350594 4.0114660263 4.0825314522 323 1305031112.9114110470 0.0637990162 0.0460704297 0.0844885111 0.0194174881 2.1164540000 0.9799670000 0.2538800000 0.1148430000 0.7581820000 0.0073720000 110031082 0 1786851328 4.2543435097 4.0107631683 4.0835032463 324 1305031112.9433209896 0.0610126108 0.0461165476 0.0844885111 0.0193908414 1.9403450000 0.9753240000 0.2191760000 0.0000050000 0.7363360000 0.0073770000 110033268 0 1785200640 4.2515544891 4.0092124939 4.0840148926 325 1305031112.9792780876 0.0570573211 0.0461502115 0.0844885111 0.0194110912 2.8483990000 0.9816180000 0.3295150000 0.1147330000 0.6977200000 0.7226570000 110035518 0 1786851328 4.2476167679 4.0065803528 4.0840835571 326 1305031113.0113530159 0.0541836992 0.0461748541 0.0844885111 0.0193869612 1.8689390000 0.9791330000 0.2216500000 0.0000050000 0.6583680000 0.0076500000 110037672 0 1785327616 4.2430734634 4.0059661865 4.0838470459 327 1305031113.0432310104 0.0516927615 0.0461917284 0.0844885111 0.0193657382 2.0065140000 0.9844250000 0.2538920000 0.1147530000 0.6439880000 0.0073280000 110039890 0 1786978304 4.2358536720 4.0062437057 4.0838599205 328 1305031113.0792510509 0.0494683199 0.0462017180 0.0844885111 0.0193774442 1.8692720000 0.9681890000 0.2542130000 0.0000050000 0.6374340000 0.0073040000 110042140 0 1785335808 4.2270512581 4.0002956390 4.0826845169 329 1305031113.1113159657 0.0490556844 0.0462103927 0.0844885111 0.0193701647 2.7066750000 0.9908220000 0.2979150000 0.1150320000 0.6439020000 0.6568480000 110044294 0 1786859520 4.2190265656 3.9959897995 4.0807256699 330 1305031113.1433060169 0.0458341725 0.0462092526 0.0844885111 0.0193519671 2.0740350000 0.9799500000 0.4441810000 0.0000050000 0.6403150000 0.0074270000 110046512 0 1785073664 4.2086653709 3.9993829727 4.0799221992 331 1305031113.1793429852 0.0413547605 0.0461945865 0.0844885111 0.0193659733 2.1924240000 0.9872690000 0.4404790000 0.1149540000 0.6394650000 0.0080880000 110048762 0 1786597376 4.1977739334 3.9979000092 4.0792155266 332 1305031113.2112588882 0.0436171666 0.0461868232 0.0844885111 0.0193536791 1.9588120000 0.9893200000 0.3224090000 0.0000040000 0.6375230000 0.0073960000 110050916 0 1785200640 4.1867809296 3.9912962914 4.0774979591 333 1305031113.2432270050 0.0399988443 0.0461682407 0.0844885111 0.0193512816 2.6767900000 0.9956990000 0.2569500000 0.1150450000 0.6411550000 0.6656880000 110053134 0 1786978304 4.1756176949 3.9932839870 4.0770483017 334 1305031113.2793118954 0.0343794450 0.0461329449 0.0844885111 0.0193677641 1.9857710000 1.0005150000 0.3318090000 0.0000050000 0.6437900000 0.0074760000 110055352 0 1785200640 4.1640915871 3.9914424419 4.0769848824 335 1305031113.3114519119 0.0372563526 0.0461064476 0.0844885111 0.0194337327 2.0638740000 0.9979290000 0.2968080000 0.1150730000 0.6443580000 0.0074600000 110057538 0 1786851328 4.1523275375 3.9829368591 4.0758442879 336 1305031113.3432519436 0.0342840403 0.0460712618 0.0844885111 0.0194434959 1.9822160000 1.0073380000 0.2974280000 0.0000050000 0.6677730000 0.0074760000 110059724 0 1785454592 4.1396646500 3.9833514690 4.0746445656 337 1305031113.3793120384 0.0219695456 0.0459997434 0.0844885111 0.0194741033 2.7209880000 1.0016650000 0.2219620000 0.1150770000 0.6809310000 0.6991190000 110061942 0 1787105280 4.1278853416 3.9910120964 4.0762915611 338 1305031113.4116249084 0.0228465125 0.0459312427 0.0844885111 0.0194965874 1.9396160000 0.9992930000 0.2561500000 0.0000040000 0.6741310000 0.0078250000 110064160 0 1785200640 4.1126942635 3.9855608940 4.0778503418 339 1305031113.4432659149 0.0220497549 0.0458607958 0.0844885111 0.0194786858 2.0153550000 0.9966330000 0.2102030000 0.1152400000 0.6836110000 0.0073970000 110066346 0 1786851328 4.0977773666 3.9834566116 4.0786933899 340 1305031113.4793109894 0.0155167710 0.0457715487 0.0844885111 0.0195016925 1.9719410000 0.9862200000 0.2877590000 0.0000040000 0.6882720000 0.0073660000 110068564 0 1785200640 4.0783510208 3.9874062538 4.0809698105 341 1305031113.5115230083 0.0151971886 0.0456818878 0.0844885111 0.0194787383 2.7353750000 0.9807450000 0.2557800000 0.1151020000 0.6815140000 0.7000040000 110070782 0 1786724352 4.0602569580 3.9856977463 4.0831675529 342 1305031113.5432419777 0.0164591447 0.0455964412 0.0844885111 0.0194715597 1.9056650000 0.9639590000 0.2519740000 0.0000040000 0.6800250000 0.0073770000 110072968 0 1785073664 4.0450339317 3.9817192554 4.0843734741 343 1305031113.5793011189 0.0157495756 0.0455094241 0.0844885111 0.0194466893 2.0304250000 0.9673490000 0.2517670000 0.1148490000 0.6868560000 0.0072580000 110075186 0 1786597376 4.0279283524 3.9796760082 4.0851306915 344 1305031113.6112680435 0.0128133781 0.0454143775 0.0844885111 0.0194221254 1.9194370000 0.9589240000 0.2530970000 0.0000040000 0.6977980000 0.0074030000 110077404 0 1785716736 4.0123248100 3.9820344448 4.0866398811 345 1305031113.6432220936 0.0126552191 0.0453194234 0.0844885111 0.0193987872 2.9116200000 0.9429160000 0.4322550000 0.1205450000 0.6980380000 0.7155990000 110079590 0 1787494400 3.9987316132 3.9817376137 4.0874905586 346 1305031113.6792879105 0.0131007852 0.0452263059 0.0844885111 0.0193783636 2.0286580000 0.9310810000 0.3920860000 0.0000050000 0.6960460000 0.0072060000 110081872 0 1784193024 3.9836845398 3.9802825451 4.0879759789 347 1305031113.7119309902 0.0134534249 0.0451347414 0.0844885111 0.0193532095 2.0429840000 0.9301550000 0.2839050000 0.1147420000 0.7046820000 0.0072330000 110084026 0 1785708544 3.9697442055 3.9799916744 4.0882201195 348 1305031113.7435901165 0.0133860018 0.0450435094 0.0844885111 0.0193261879 1.8728200000 0.9186490000 0.2444240000 0.0000040000 0.7002910000 0.0071820000 110086244 0 1787613184 3.9549829960 3.9801933765 4.0886273384 349 1305031113.7793200016 0.0121736312 0.0449493264 0.0844885111 0.0193149453 2.7790910000 0.9183300000 0.3190930000 0.1145830000 0.7010580000 0.7237130000 110088462 0 1784946688 3.9425306320 3.9807047844 4.0890059471 350 1305031113.8112370968 0.0134360343 0.0448592884 0.0844885111 0.0192891251 2.0715680000 0.9344620000 0.4228260000 0.0000050000 0.7047560000 0.0072360000 110090616 0 1786335232 3.9274966717 3.9803202152 4.0901732445 351 1305031113.8432950974 0.0101755830 0.0447604744 0.0844885111 0.0192725024 2.1170630000 0.9035940000 0.3805350000 0.1145190000 0.7088840000 0.0071280000 110092834 0 1785192448 3.9151148796 3.9840197563 4.0910134315 352 1305031113.8792810440 0.0118590025 0.0446670043 0.0844885111 0.0193114145 2.0015690000 0.9327460000 0.3524710000 0.0000050000 0.7067840000 0.0072630000 110095084 0 1786851328 3.9000470638 3.9824612141 4.0923595428 353 1305031113.9112899303 0.0147810224 0.0445823415 0.0844885111 0.0192842704 2.9452600000 0.9415070000 0.4314470000 0.1146950000 0.7181690000 0.7370830000 110097270 0 1785327616 3.8875465393 3.9802789688 4.0936379433 354 1305031113.9432909489 0.0117774121 0.0444896722 0.0844885111 0.0192695760 1.9119460000 0.9239210000 0.2428960000 0.0000040000 0.7356550000 0.0071560000 110099456 0 1786724352 3.8767230511 3.9845042229 4.0943288803 355 1305031113.9792931080 0.0122284358 0.0443987955 0.0844885111 0.0192452423 2.0011370000 0.9191800000 0.2083840000 0.1154460000 0.7485860000 0.0072130000 110101706 0 1785200640 3.8625409603 3.9857263565 4.0950536728 356 1305031114.0112569332 0.0110281743 0.0443050578 0.0844885111 0.0192335551 1.9584390000 0.9309070000 0.2463890000 0.0000040000 0.7714270000 0.0072920000 110103892 0 1786724352 3.8476917744 3.9875280857 4.0959286690 357 1305031114.0433011055 0.0119459117 0.0442144159 0.0844885111 0.0192368163 2.8852210000 0.9409200000 0.2484200000 0.1149370000 0.7805920000 0.7979980000 110106078 0 1785327616 3.8307175636 3.9889721870 4.0980381966 358 1305031114.0792849064 0.0139778433 0.0441299562 0.0844885111 0.0192314713 1.9765200000 0.9481500000 0.2116100000 0.0000040000 0.8070710000 0.0072710000 110108328 0 1786724352 3.8166539669 3.9876277447 4.0999641418 359 1305031114.1112630367 0.0145031624 0.0440474303 0.0844885111 0.0192081837 2.2586160000 0.9545310000 0.3583600000 0.1151320000 0.8208960000 0.0073640000 110110514 0 1785454592 3.8029344082 3.9903125763 4.1020112038 360 1305031114.1432840824 0.0165099651 0.0439709374 0.0844885111 0.0191844895 2.2270630000 0.9436430000 0.4308650000 0.0000030000 0.8428200000 0.0073760000 110112732 0 1786859520 3.7876834869 3.9938817024 4.1050553322 361 1305031114.1793370247 0.0185379051 0.0439004858 0.0844885111 0.0191968612 3.0855970000 0.9503490000 0.2831290000 0.1154210000 0.8599660000 0.8743000000 110114982 0 1785208832 3.7773840427 3.9927055836 4.1072387695 362 1305031114.2113029957 0.0198078398 0.0438339315 0.0844885111 0.0191939273 2.1379870000 0.9363560000 0.3085620000 0.0000030000 0.8826770000 0.0080020000 110117136 0 1786605568 3.7650232315 3.9952416420 4.1096544266 363 1305031114.2433369160 0.0228277724 0.0437760633 0.0844885111 0.0192059586 2.2884000000 0.9639750000 0.3174810000 0.1152090000 0.8820750000 0.0072510000 110119322 0 1785327616 3.7463512421 4.0012698174 4.1133522987 364 1305031114.2793900967 0.0240124743 0.0437217677 0.0844885111 0.0192525023 2.1828140000 0.9568620000 0.3241010000 0.0000040000 0.8920930000 0.0073760000 110121572 0 1786851328 3.7347326279 3.9980151653 4.1168012619 365 1305031114.3114290237 0.0276808161 0.0436778199 0.0844885111 0.0192354102 3.1731080000 0.9703760000 0.2520130000 0.1154950000 0.9072030000 0.9255010000 110123758 0 1785200640 3.7224593163 3.9992828369 4.1211194992 366 1305031114.3433310986 0.0306023806 0.0436420947 0.0844885111 0.0192214426 2.3500040000 0.9686830000 0.4385780000 0.0000040000 0.9326510000 0.0073270000 110125976 0 1786724352 3.7139456272 4.0013022423 4.1244006157 367 1305031114.3793199062 0.0335680656 0.0436146450 0.0844885111 0.0192039316 2.4632040000 0.9677460000 0.4366960000 0.1157170000 0.9331660000 0.0073400000 110128226 0 1785200640 3.7076833248 4.0013499260 4.1268157959 368 1305031114.4113969803 0.0348518826 0.0435908331 0.0844885111 0.0191859579 2.1761170000 0.9650330000 0.2537580000 0.0000040000 0.9473680000 0.0074540000 110130412 0 1786597376 3.6949617863 4.0005221367 4.1293563843 369 1305031114.4433450699 0.0371830985 0.0435734680 0.0844885111 0.0191778042 3.4071220000 0.9890470000 0.3649000000 0.1156680000 0.9590720000 0.9760190000 110132598 0 1785454592 3.6800503731 3.9996824265 4.1329245567 370 1305031114.4793319702 0.0401106998 0.0435641092 0.0844885111 0.0191830288 2.3619100000 0.9959040000 0.3692900000 0.0000030000 0.9868330000 0.0074790000 110134848 0 1787105280 3.6714053154 3.9970762730 4.1365146637 371 1305031114.5112659931 0.0424941853 0.0435612253 0.0844885111 0.0191611626 2.5861150000 1.0112780000 0.4502260000 0.1160050000 0.9987220000 0.0074620000 110137002 0 1785335808 3.6638951302 3.9950580597 4.1402726173 372 1305031114.5432360172 0.0459464379 0.0435676371 0.0844885111 0.0191465314 2.3708560000 1.0023440000 0.3345840000 0.0000050000 1.0239690000 0.0074590000 110139220 0 1786859520 3.6582169533 3.9956338406 4.1447286606 373 1305031114.5792369843 0.0470507257 0.0435769752 0.0844885111 0.0191270764 3.5493210000 0.9810590000 0.4028150000 0.1161500000 1.0145320000 1.0323320000 110141470 0 1785200640 3.6546287537 3.9919452667 4.1464238167 374 1305031114.6113910675 0.0480836444 0.0435890251 0.0844885111 0.0191106234 2.4153980000 0.9824390000 0.4031710000 0.0000050000 1.0198880000 0.0075000000 110143624 0 1786597376 3.6488618851 3.9920454025 4.1487207413 375 1305031114.6441500187 0.0486591309 0.0436025454 0.0844885111 0.0190946703 2.3871270000 0.9929240000 0.2559840000 0.1160990000 1.0121290000 0.0075540000 110145842 0 1785454592 3.6431584358 3.9935889244 4.1501569748 376 1305031114.6792509556 0.0509024523 0.0436219600 0.0844885111 0.0190877509 2.2993780000 1.0074060000 0.2674490000 0.0000040000 1.0145150000 0.0075590000 110148028 0 1787105280 3.6406166553 3.9874036312 4.1520843506 377 1305031114.7113060951 0.0537121519 0.0436487245 0.0844885111 0.0190841203 3.4707780000 0.9993930000 0.2973090000 0.1162560000 1.0176000000 1.0377820000 110150182 0 1785327616 3.6393446922 3.9826068878 4.1538243294 378 1305031114.7432758808 0.0555354841 0.0436801709 0.0844885111 0.0190619264 2.4779670000 0.9990810000 0.4411200000 0.0000040000 1.0277010000 0.0074910000 110152400 0 1786724352 3.6394143105 3.9813451767 4.1544642448 379 1305031114.7792890072 0.0593656935 0.0437215575 0.0844885111 0.0190438671 2.4766260000 0.9795890000 0.3332690000 0.1163390000 1.0373800000 0.0074980000 110154650 0 1785454592 3.6391124725 3.9781422615 4.1570935249 380 1305031114.8113029003 0.0592296645 0.0437623683 0.0844885111 0.0190312591 2.3491580000 0.9696250000 0.3249140000 0.0000050000 1.0447640000 0.0073990000 110156804 0 1787105280 3.6379804611 3.9803869724 4.1571831703 381 1305031114.8432080746 0.0589774400 0.0438023029 0.0844885111 0.0190073265 3.6334720000 0.9668230000 0.4339970000 0.1164080000 1.0436600000 1.0700340000 110159022 0 1785073664 3.6379482746 3.9810974598 4.1566662788 382 1305031114.8792810440 0.0577878505 0.0438389143 0.0844885111 0.0189824447 2.4533210000 0.9630120000 0.4384830000 0.0000040000 1.0419290000 0.0073890000 110161240 0 1786470400 3.6392817497 3.9821677208 4.1556363106 383 1305031114.9128789902 0.0573089607 0.0438740841 0.0844885111 0.0189612543 2.5801170000 0.9751600000 0.4380740000 0.1164210000 1.0405580000 0.0073810000 110163490 0 1785581568 3.6431922913 3.9843940735 4.1550745964 384 1305031114.9432640076 0.0573741123 0.0439092404 0.0844885111 0.0189379778 2.4949320000 1.0203610000 0.4383340000 0.0000050000 1.0260070000 0.0076020000 110165612 0 1787113472 3.6468193531 3.9872572422 4.1562247276 385 1305031114.9792799950 0.0548346862 0.0439376182 0.0844885111 0.0189177333 3.6055780000 0.9905320000 0.4445280000 0.1163600000 1.0127650000 1.0387060000 110167862 0 1784320000 3.6549439430 3.9902155399 4.1548280716 386 1305031115.0113000870 0.0509389378 0.0439557563 0.0844885111 0.0189012764 2.3283290000 1.0017790000 0.3305250000 0.0000040000 0.9860270000 0.0074720000 110170048 0 1785835520 3.6591932774 3.9952132702 4.1528358459 387 1305031115.0435299873 0.0493954308 0.0439698123 0.0844885111 0.0188986279 2.5029070000 1.0097680000 0.4091060000 0.1162190000 0.9578080000 0.0074650000 110172266 0 1787740160 3.6703550816 3.9966223240 4.1526970863 388 1305031115.0792379379 0.0465325825 0.0439764174 0.0844885111 0.0188764089 2.2769010000 1.0010400000 0.3345410000 0.0000030000 0.9312340000 0.0074630000 110174516 0 1784692736 3.6817262173 3.9966797829 4.1520848274 389 1305031115.1112298965 0.0450197496 0.0439790995 0.0844885111 0.0188685084 3.2712980000 1.0137450000 0.3056830000 0.1160410000 0.9074060000 0.9258900000 110176670 0 1786216448 3.6930868626 3.9981341362 4.1527171135 390 1305031115.1432940960 0.0413012840 0.0439722333 0.0844885111 0.0188622384 2.2498800000 1.0221850000 0.3399540000 0.0000040000 0.8776600000 0.0075790000 110178888 0 1788121088 3.7107048035 3.9999442101 4.1509237289 391 1305031115.1794400215 0.0378881693 0.0439566731 0.0844885111 0.0188666423 2.4129800000 0.9957210000 0.4505140000 0.1153850000 0.8413640000 0.0074640000 110181138 0 1785454592 3.7190482616 3.9997570515 4.1517138481 392 1305031115.2113740444 0.0374727622 0.0439401325 0.0844885111 0.0188731801 2.2602520000 0.9803670000 0.4446160000 0.0000030000 0.8253690000 0.0073670000 110183292 0 1787105280 3.7322037220 3.9975957870 4.1533179283 393 1305031115.2432971001 0.0382188745 0.0439255746 0.0844885111 0.0188690335 3.1185190000 0.9866710000 0.3721240000 0.1150330000 0.8119010000 0.8302440000 110185510 0 1785454592 3.7494194508 3.9933626652 4.1551523209 394 1305031115.2799661160 0.0349932648 0.0439029037 0.0844885111 0.0188968681 2.2308030000 0.9759020000 0.4409460000 0.0000040000 0.8040500000 0.0073550000 110187728 0 1786978304 3.7592601776 3.9963319302 4.1575341225 395 1305031115.3117039204 0.0324252211 0.0438738463 0.0844885111 0.0189183153 2.1416380000 0.9697400000 0.2575370000 0.1147160000 0.7897330000 0.0073250000 110189946 0 1785454592 3.7755639553 3.9983150959 4.1590557098 396 1305031115.3434259892 0.0319425911 0.0438437169 0.0844885111 0.0189033908 1.9793620000 0.9772540000 0.2198680000 0.0000040000 0.7721620000 0.0075120000 110192132 0 1786978304 3.7923123837 3.9960260391 4.1596713066 397 1305031115.3791658878 0.0303647034 0.0438097647 0.0844885111 0.0191677691 2.8440120000 0.9495960000 0.2521680000 0.1195870000 0.7508780000 0.7691470000 110194318 0 1785344000 3.7991573811 4.0046100616 4.1620087624 398 1305031115.4112370014 0.0338635221 0.0437847741 0.0844885111 0.0191545811 1.9275860000 0.9407000000 0.2481190000 0.0000040000 0.7288610000 0.0073350000 110196504 0 1787240448 3.8104970455 4.0033054352 4.1648845673 399 1305031115.4431591034 0.0346811786 0.0437619581 0.0844885111 0.0191912467 2.0838680000 0.9480790000 0.2870000000 0.1140430000 0.7247710000 0.0072810000 110198690 0 1785208832 3.8316917419 4.0001935959 4.1685285568 400 1305031115.4792408943 0.0361917019 0.0437430325 0.0844885111 0.0191732548 1.9504150000 0.9460550000 0.2907290000 0.0000030000 0.7037570000 0.0073030000 110200940 0 1786859520 3.8500976562 4.0013632774 4.1709275246 401 1305031115.5112531185 0.0390873440 0.0437314223 0.0844885111 0.0192399387 2.7852140000 0.9506060000 0.3272350000 0.1136510000 0.6834800000 0.7075980000 110203094 0 1785454592 3.8666005135 3.9992020130 4.1728506088 402 1305031115.5436201096 0.0384116694 0.0437181890 0.0844885111 0.0192794919 1.8856360000 0.9631660000 0.2548560000 0.0000040000 0.6577400000 0.0072660000 110205312 0 1786978304 3.8896982670 3.9974348545 4.1730127335 403 1305031115.5793149471 0.0400722139 0.0437091420 0.0844885111 0.0192564497 2.1611190000 0.9643640000 0.4453740000 0.1132240000 0.6282440000 0.0072910000 110207562 0 1785327616 3.9062380791 3.9975898266 4.1716442108 404 1305031115.6114239693 0.0423382372 0.0437057486 0.0844885111 0.0192366486 1.8548000000 0.9737690000 0.2611900000 0.0000040000 0.6099000000 0.0073110000 110209716 0 1786978304 3.9198002815 3.9965453148 4.1705107689 405 1305031115.6432540417 0.0419543460 0.0437014242 0.0844885111 0.0192149618 2.5935680000 0.9711590000 0.2964540000 0.1129730000 0.5961770000 0.6141680000 110211902 0 1785454592 3.9368019104 3.9959473610 4.1690192223 406 1305031115.6792409420 0.0459084846 0.0437068603 0.0844885111 0.0191984315 1.7922410000 0.9643990000 0.2317570000 0.0000030000 0.5861140000 0.0072580000 110214152 0 1787232256 3.9525051117 3.9947755337 4.1674814224 407 1305031115.7113199234 0.0463291518 0.0437133033 0.0844885111 0.0192188021 1.9297150000 0.9630210000 0.2655750000 0.1126540000 0.5785940000 0.0072470000 110216338 0 1785327616 3.9674291611 3.9950580597 4.1660294533 408 1305031115.7432498932 0.0421044268 0.0437093599 0.0844885111 0.0192575007 1.8538630000 0.9734430000 0.2982150000 0.0000040000 0.5722610000 0.0073070000 110218556 0 1787105280 3.9872603416 3.9971792698 4.1640768051 409 1305031115.7794249058 0.0430291779 0.0437076969 0.0844885111 0.0192636716 2.4991000000 0.9729520000 0.2577400000 0.1126230000 0.5671860000 0.5859380000 110220806 0 1785327616 4.0083742142 3.9960837364 4.1615858078 410 1305031115.8112769127 0.0433757044 0.0437068872 0.0844885111 0.0192591883 1.8866950000 0.9716720000 0.3368110000 0.0000030000 0.5681830000 0.0073290000 110222960 0 1786978304 4.0206942558 3.9979722500 4.1597728729 411 1305031115.8432240486 0.0403689817 0.0436987657 0.0844885111 0.0192472196 1.8936160000 0.9776280000 0.2285890000 0.1127070000 0.5646980000 0.0073460000 110225178 0 1785454592 4.0370278358 4.0014247894 4.1581830978 412 1305031115.8791980743 0.0479401685 0.0437090604 0.0844885111 0.0192373660 1.8929510000 0.9808370000 0.3395650000 0.0000040000 0.5625100000 0.0073630000 110227364 0 1787232256 4.0491237640 3.9981811047 4.1574044228 413 1305031115.9111180305 0.0494063422 0.0437228553 0.0844885111 0.0192227521 2.6870440000 0.9756380000 0.4509580000 0.1129550000 0.5599840000 0.5848160000 110229550 0 1785454592 4.0620322227 3.9983284473 4.1565551758 414 1305031115.9433109760 0.0467000715 0.0437300466 0.0844885111 0.0192196816 1.8287170000 0.9972510000 0.2624690000 0.0000040000 0.5587460000 0.0074180000 110231704 0 1786978304 4.0761203766 4.0029473305 4.1565146446 415 1305031115.9807400703 0.0528653078 0.0437520593 0.0844885111 0.0192108373 1.9315520000 0.9983510000 0.2647880000 0.1131410000 0.5451880000 0.0074130000 110233954 0 1785462784 4.0851960182 4.0047540665 4.1574854851 416 1305031116.0113790035 0.0530424714 0.0437743920 0.0844885111 0.0192525210 1.7958380000 1.0121940000 0.2275690000 0.0000040000 0.5459110000 0.0074800000 110236108 0 1786986496 4.0966119766 4.0078816414 4.1578726768 417 1305031116.0431640148 0.0555408001 0.0438026088 0.0844885111 0.0192367242 2.5155100000 1.0083190000 0.3033620000 0.1134060000 0.5334290000 0.5542580000 110238326 0 1785081856 4.1047754288 4.0111141205 4.1587700844 418 1305031116.0800299644 0.0631277636 0.0438488413 0.0844885111 0.0192387979 1.8605750000 1.0082250000 0.3028180000 0.0000050000 0.5393830000 0.0073790000 110240576 0 1786732544 4.1126356125 4.0126338005 4.1609501839 419 1305031116.1112999916 0.0646785498 0.0438985542 0.0844885111 0.0192222527 1.9025870000 1.0034620000 0.2618890000 0.1134660000 0.5135800000 0.0074620000 110242730 0 1785327616 4.1221141815 4.0150713921 4.1633272171 420 1305031116.1434469223 0.0675997213 0.0439549855 0.0844885111 0.0192023462 1.8468840000 1.0100860000 0.3028330000 0.0000050000 0.5237600000 0.0074780000 110244916 0 1786978304 4.1318478584 4.0143795013 4.1652870178 421 1305031116.1795721054 0.0731015205 0.0440242172 0.0844885111 0.0191827009 2.4638230000 0.9984530000 0.2981490000 0.1143880000 0.5109950000 0.5390740000 110247166 0 1785327616 4.1416311264 4.0140066147 4.1670274734 422 1305031116.2113199234 0.0734510422 0.0440939490 0.0844885111 0.0191628860 1.8184320000 0.9966990000 0.2973420000 0.0000050000 0.5141490000 0.0073530000 110249352 0 1786724352 4.1512446404 4.0165214539 4.1689720154 423 1305031116.2433199883 0.0748309195 0.0441666132 0.0844885111 0.0191484400 2.0672540000 0.9963090000 0.4530420000 0.1198000000 0.4872210000 0.0074500000 110251538 0 1785327616 4.1612863541 4.0159387589 4.1700229645 424 1305031116.2793850899 0.0791450366 0.0442491095 0.0844885111 0.0191614374 1.7795850000 1.0099900000 0.2631820000 0.0000050000 0.4962380000 0.0074090000 110253820 0 1787105280 4.1697044373 4.0165290833 4.1695899963 425 1305031116.3113360405 0.0793784410 0.0443317668 0.0844885111 0.0191596000 2.5253600000 1.0075170000 0.3407120000 0.1143510000 0.5125410000 0.5475000000 110255974 0 1784946688 4.1780338287 4.0173764229 4.1696543694 426 1305031116.3432919979 0.0794822797 0.0444142797 0.0844885111 0.0191453568 1.8986310000 1.0154790000 0.3018890000 0.0000040000 0.5710820000 0.0073710000 110258160 0 1786724352 4.1861710548 4.0162491798 4.1682457924 427 1305031116.3793840408 0.0817153752 0.0445016359 0.0844885111 0.0191348015 1.9784030000 1.0069380000 0.2624980000 0.1149270000 0.5838510000 0.0074280000 110260378 0 1785200640 4.1918177605 4.0143218040 4.1652774811 428 1305031116.4113330841 0.0792354718 0.0445827897 0.0844885111 0.0191163950 1.9539780000 1.0075270000 0.3458760000 0.0000040000 0.5903870000 0.0073860000 110262596 0 1786978304 4.1971683502 4.0169305801 4.1627216339 429 1305031116.4433689117 0.0751573965 0.0446540592 0.0844885111 0.0191045794 2.7015400000 0.9962490000 0.3457610000 0.1148720000 0.5953050000 0.6465930000 110264814 0 1785200640 4.2027196884 4.0187678337 4.1613926888 430 1305031116.4798500538 0.0723919868 0.0447185660 0.0844885111 0.0190862005 1.9244140000 0.9937210000 0.3059280000 0.0000050000 0.6145770000 0.0073530000 110267064 0 1786724352 4.2053155899 4.0173988342 4.1593818665 431 1305031116.5112049580 0.0713827908 0.0447804320 0.0844885111 0.0190699072 2.0229160000 0.9977580000 0.2977450000 0.1151900000 0.6020230000 0.0074190000 110269218 0 1785454592 4.2026224136 4.0172414780 4.1568965912 432 1305031116.5432620049 0.0697494298 0.0448382306 0.0844885111 0.0190481447 1.9474530000 1.0008260000 0.3433430000 0.0000050000 0.5930140000 0.0074890000 110271404 0 1787240448 4.1985478401 4.0167431831 4.1548247337 433 1305031116.5793130398 0.0640992671 0.0448827133 0.0844885111 0.0190592146 2.8156420000 1.0049250000 0.4609190000 0.1152680000 0.5898260000 0.6419160000 110273654 0 1785208832 4.1930489540 4.0176897049 4.1534924507 434 1305031116.6112608910 0.0609394573 0.0449197104 0.0844885111 0.0190567736 1.8953300000 1.0093280000 0.3020960000 0.0000040000 0.5737400000 0.0073680000 110275808 0 1786978304 4.1865630150 4.0166578293 4.1519165039 435 1305031116.6433548927 0.0596907735 0.0449536669 0.0844885111 0.0190524821 2.0194650000 1.0142420000 0.3453020000 0.1156860000 0.5339950000 0.0073820000 110277994 0 1785454592 4.1764917374 4.0153169632 4.1507372856 436 1305031116.6792809963 0.0537337735 0.0449738048 0.0844885111 0.0190427255 1.7837150000 1.0136880000 0.2691640000 0.0000040000 0.4905670000 0.0074420000 110280308 0 1787232256 4.1661472321 4.0147676468 4.1501779556 437 1305031116.7116339207 0.0531427823 0.0449924981 0.0844885111 0.0190238975 2.3293240000 0.9987620000 0.2314170000 0.1144740000 0.4764650000 0.5053370000 110282462 0 1785327616 4.1533670425 4.0129895210 4.1493968964 438 1305031116.7432909012 0.0527481586 0.0450102051 0.0844885111 0.0190182113 1.7634980000 1.0047430000 0.2704360000 0.0000040000 0.4781440000 0.0073850000 110284648 0 1786978304 4.1388573647 4.0121359825 4.1492414474 439 1305031116.7792980671 0.0496291667 0.0450207266 0.0844885111 0.0190163114 1.8989850000 1.0224110000 0.2718840000 0.1143730000 0.4800690000 0.0074250000 110286898 0 1785200640 4.1240787506 4.0106663704 4.1488537788 440 1305031116.8113429546 0.0506008975 0.0450334088 0.0844885111 0.0190563875 1.8462890000 1.0007220000 0.3492600000 0.0000040000 0.4859220000 0.0074440000 110289084 0 1786724352 4.1094250679 4.0079092979 4.1476011276 441 1305031116.8460888863 0.0485148504 0.0450413033 0.0844885111 0.0191558260 2.3467210000 1.0016570000 0.2275050000 0.1147740000 0.4894980000 0.5104280000 110291302 0 1785200640 4.0941143036 4.0057730675 4.1464748383 442 1305031116.8801651001 0.0459733196 0.0450434119 0.0844885111 0.0191345033 1.9779120000 1.0114850000 0.4533740000 0.0000040000 0.5026650000 0.0075090000 110293520 0 1786851328 4.0796246529 4.0074772835 4.1458339691 443 1305031116.9120440483 0.0469385646 0.0450476899 0.0844885111 0.0191256498 2.0755760000 1.0045850000 0.4490170000 0.1139050000 0.4976900000 0.0074650000 110295706 0 1785327616 4.0650405884 4.0055885315 4.1458230019 444 1305031116.9432959557 0.0436676703 0.0450445817 0.0844885111 0.0191176717 1.7826170000 1.0096130000 0.2577060000 0.0000040000 0.5049810000 0.0074520000 110297892 0 1786978304 4.0513672829 4.0078496933 4.1454243660 445 1305031116.9793510437 0.0422510542 0.0450383041 0.0844885111 0.0191225449 2.6095090000 1.0390650000 0.4132230000 0.1141050000 0.5104730000 0.5296580000 110300110 0 1785200640 4.0344343185 4.0087642670 4.1455659866 446 1305031117.0113821030 0.0420274213 0.0450315533 0.0844885111 0.0191198950 1.8241850000 0.9979270000 0.3028780000 0.0000040000 0.5130860000 0.0074550000 110302328 0 1786978304 4.0185279846 4.0101099014 4.1448521614 447 1305031117.0432610512 0.0414199159 0.0450234736 0.0844885111 0.0191004780 1.8815480000 0.9834820000 0.2552190000 0.1133080000 0.5192980000 0.0074080000 110304514 0 1785454592 4.0000696182 4.0135674477 4.1451869011 448 1305031117.0795199871 0.0402091034 0.0450127272 0.0844885111 0.0190960365 1.9529680000 0.9851960000 0.4412120000 0.0000040000 0.5161680000 0.0074250000 110306764 0 1787105280 3.9858527184 4.0165815353 4.1457290649 449 1305031117.1112380028 0.0426638983 0.0450074960 0.0844885111 0.0190926084 2.4743040000 0.9792340000 0.3302570000 0.1130070000 0.5151720000 0.5337030000 110308918 0 1785352192 3.9744999409 4.0165557861 4.1471376419 450 1305031117.1432180405 0.0444307812 0.0450062144 0.0844885111 0.0190752686 1.9605900000 0.9888090000 0.4393930000 0.0000040000 0.5220930000 0.0073920000 110311136 0 1787367424 3.9628028870 4.0178022385 4.1491346359 451 1305031117.1792640686 0.0430295728 0.0450018316 0.0844885111 0.0190567903 2.0415730000 0.9815730000 0.4009970000 0.1131090000 0.5356990000 0.0072930000 110313386 0 1785335808 3.9545567036 4.0211730003 4.1501350403 452 1305031117.2113609314 0.0450018905 0.0450018317 0.0844885111 0.0190585004 1.8811320000 0.9749800000 0.3368040000 0.0000040000 0.5591530000 0.0072930000 110315572 0 1787105280 3.9458835125 4.0208950043 4.1518821716 453 1305031117.2432770729 0.0435105599 0.0449985397 0.0844885111 0.0190558883 2.6548630000 0.9681040000 0.4388680000 0.1135250000 0.5562170000 0.5752150000 110317758 0 1785200640 3.9435920715 4.0233783722 4.1535949707 454 1305031117.2792990208 0.0429958552 0.0449941285 0.0844885111 0.0190410376 1.7970000000 0.9574660000 0.2542990000 0.0000040000 0.5750210000 0.0072770000 110320008 0 1786978304 3.9391191006 4.0243372917 4.1552219391 455 1305031117.3111999035 0.0460472479 0.0449964431 0.0844885111 0.0190298314 1.9479130000 0.9520050000 0.3226980000 0.1132820000 0.5497570000 0.0072640000 110322162 0 1785073664 3.9350149632 4.0211167336 4.1570196152 456 1305031117.3432428837 0.0498502627 0.0450070874 0.0844885111 0.0190196387 1.8588120000 0.9382650000 0.3510760000 0.0000050000 0.5589310000 0.0072950000 110324380 0 1786851328 3.9301278591 4.0166234970 4.1580886841 457 1305031117.3794538975 0.0503985770 0.0450188850 0.0844885111 0.0190096868 2.4497340000 0.9618750000 0.2529080000 0.1133290000 0.5495520000 0.5690830000 110326630 0 1785327616 3.9285628796 4.0129227638 4.1580448151 458 1305031117.4112210274 0.0506291240 0.0450311344 0.0844885111 0.0189900202 1.9413420000 0.9537640000 0.4337910000 0.0000050000 0.5435590000 0.0072790000 110328816 0 1786978304 3.9270174503 4.0092110634 4.1573944092 459 1305031117.4432740211 0.0495869741 0.0450410600 0.0844885111 0.0189710945 1.9326320000 0.9700410000 0.2910510000 0.1136350000 0.5475810000 0.0073800000 110331002 0 1785454592 3.9276025295 4.0054845810 4.1564936638 460 1305031117.4794030190 0.0454128273 0.0450418682 0.0844885111 0.0189556015 1.8003440000 0.9560810000 0.2875670000 0.0000040000 0.5463650000 0.0072470000 110333252 0 1787232256 3.9285051823 4.0024552345 4.1553950310 461 1305031117.5113248825 0.0453749187 0.0450425906 0.0844885111 0.0189373505 2.6477140000 0.9625270000 0.4386120000 0.1136530000 0.5554970000 0.5743950000 110335438 0 1785454592 3.9280924797 3.9960560799 4.1546349525 462 1305031117.5442850590 0.0429394506 0.0450380384 0.0844885111 0.0189195672 2.0063300000 0.9777580000 0.4494720000 0.0000040000 0.5688140000 0.0073070000 110337592 0 1787105280 3.9272806644 3.9919114113 4.1535921097 463 1305031117.5791549683 0.0367562436 0.0450201511 0.0844885111 0.0189007537 2.0174540000 0.9439380000 0.3673830000 0.1135860000 0.5822360000 0.0073230000 110339874 0 1785327616 3.9272069931 3.9889333248 4.1531901360 464 1305031117.6111590862 0.0347175077 0.0449979471 0.0844885111 0.0188816201 1.7696890000 0.9443770000 0.2193350000 0.0000050000 0.5956220000 0.0073710000 110342028 0 1786978304 3.9263670444 3.9841699600 4.1544713974 465 1305031117.6432840824 0.0346982479 0.0449757973 0.0844885111 0.0188634724 2.7294010000 0.9498940000 0.4361200000 0.1137870000 0.6034940000 0.6230550000 110344246 0 1784954880 3.9263465405 3.9770004749 4.1565823555 466 1305031117.6792619228 0.0307946913 0.0449453657 0.0844885111 0.0188489408 1.7812140000 0.9358590000 0.2121050000 0.0000050000 0.6229880000 0.0072250000 110346496 0 1786605568 3.9254319668 3.9717218876 4.1592273712 467 1305031117.7112150192 0.0310719702 0.0449156582 0.0844885111 0.0188303442 1.9687800000 0.9374280000 0.2828550000 0.1140580000 0.6241550000 0.0072870000 110348650 0 1785716736 3.9264829159 3.9639523029 4.1628761292 468 1305031117.7431840897 0.0321240723 0.0448883258 0.0844885111 0.0188126929 1.8259840000 0.9340850000 0.2483760000 0.0000040000 0.6331050000 0.0074280000 110350836 0 1787367424 3.9270710945 3.9549374580 4.1668281555 469 1305031117.7794671059 0.0296906196 0.0448559213 0.0844885111 0.0187928104 2.7866070000 0.9335010000 0.4282220000 0.1142400000 0.6445830000 0.6629920000 110353086 0 1785454592 3.9259216785 3.9477818012 4.1704673767 470 1305031117.8113200665 0.0284456927 0.0448210059 0.0844885111 0.0187764010 2.0117770000 0.9242930000 0.4241040000 0.0000050000 0.6530510000 0.0072560000 110355272 0 1786978304 3.9277713299 3.9402337074 4.1743783951 471 1305031117.8433070183 0.0303810202 0.0447903477 0.0844885111 0.0187684929 1.9700830000 0.9304320000 0.2539100000 0.1137550000 0.6617650000 0.0072460000 110357394 0 1784438784 3.9296996593 3.9294629097 4.1786217690 472 1305031117.8794670105 0.0267976131 0.0447522275 0.0844885111 0.0187518606 1.9923410000 0.9246540000 0.3899340000 0.0000040000 0.6674140000 0.0073220000 110359644 0 1785962496 3.9303462505 3.9231145382 4.1819138527 473 1305031117.9114069939 0.0281302705 0.0447170860 0.0844885111 0.0187331702 2.7907100000 0.8985550000 0.4151670000 0.1133240000 0.6679050000 0.6926980000 110361798 0 1785327616 3.9288477898 3.9144623280 4.1860547066 474 1305031117.9432721138 0.0297355223 0.0446854793 0.0844885111 0.0187141629 2.0225610000 0.9132170000 0.4243370000 0.0000040000 0.6747790000 0.0071830000 110363984 0 1786851328 3.9281218052 3.9054746628 4.1907815933 475 1305031117.9792630672 0.0285796970 0.0446515724 0.0844885111 0.0187069741 2.0231200000 0.8873470000 0.3406470000 0.1129790000 0.6720390000 0.0071390000 110366234 0 1784565760 3.9260270596 3.8996367455 4.1953029633 476 1305031118.0112280846 0.0316126682 0.0446241797 0.0844885111 0.0186910979 1.8764060000 0.8929000000 0.3034470000 0.0000040000 0.6698720000 0.0070820000 110368388 0 1786216448 3.9235434532 3.8894166946 4.2009849548 477 1305031118.0435490608 0.0338302292 0.0446015509 0.0844885111 0.0186753317 2.5703350000 0.8915390000 0.1949280000 0.1127240000 0.6752610000 0.6927350000 110370606 0 1787994112 3.9253427982 3.8782393932 4.2064037323 478 1305031118.0793690681 0.0342091881 0.0445798096 0.0844885111 0.0186592872 1.8099250000 0.8849530000 0.2351750000 0.0000050000 0.6796330000 0.0070670000 110372856 0 1785073664 3.9230346680 3.8706514835 4.2115578651 479 1305031118.1112170219 0.0354296118 0.0445607069 0.0844885111 0.0186467864 1.9250360000 0.8853340000 0.2384220000 0.1124960000 0.6784610000 0.0071640000 110375010 0 1786597376 3.9241082668 3.8617885113 4.2163190842 480 1305031118.1432559490 0.0377022587 0.0445464184 0.0844885111 0.0186298007 1.9847140000 0.8887850000 0.4076990000 0.0000040000 0.6779540000 0.0071130000 110377228 0 1785200640 3.9223940372 3.8523893356 4.2209072113 481 1305031118.1793229580 0.0388153456 0.0445345035 0.0844885111 0.0186124047 2.6762190000 0.9193670000 0.2699390000 0.1119820000 0.6768610000 0.6948530000 110379478 0 1786851328 3.9210793972 3.8437018394 4.2253870964 482 1305031118.2112019062 0.0418209955 0.0445288738 0.0844885111 0.0186039649 1.8450080000 0.8776990000 0.2687900000 0.0000040000 0.6882840000 0.0070360000 110381632 0 1784872960 3.9209232330 3.8320183754 4.2297234535 483 1305031118.2431728840 0.0441333689 0.0445280550 0.0844885111 0.0185963546 2.1149880000 0.8813720000 0.4049970000 0.1117830000 0.7065750000 0.0070150000 110383818 0 1786605568 3.9176521301 3.8231704235 4.2337584496 484 1305031118.2791941166 0.0449181087 0.0445288609 0.0844885111 0.0185985835 1.9311440000 0.8834360000 0.3037090000 0.0000050000 0.7336580000 0.0070880000 110386068 0 1785208832 3.9169282913 3.8152716160 4.2371110916 485 1305031118.3112990856 0.0473840721 0.0445347479 0.0844885111 0.0185798188 2.9291350000 0.8744390000 0.3987480000 0.1118460000 0.7652120000 0.7757430000 110388254 0 1787105280 3.9154245853 3.8062813282 4.2408714294 486 1305031118.3433239460 0.0468116887 0.0445394330 0.0844885111 0.0185724788 1.9340680000 0.8746700000 0.2660110000 0.0000040000 0.7831590000 0.0070650000 110390440 0 1785327616 3.9144139290 3.8038237095 4.2435836792 487 1305031118.3792080879 0.0479545593 0.0445464456 0.0844885111 0.0185539590 2.0257500000 0.8747600000 0.2326590000 0.1115040000 0.7965840000 0.0071070000 110392690 0 1786851328 3.9123404026 3.7989447117 4.2473678589 488 1305031118.4112958908 0.0501887910 0.0445580077 0.0844885111 0.0185469289 1.9605580000 0.8740150000 0.2654450000 0.0000040000 0.8108120000 0.0070380000 110394876 0 1785200640 3.9089803696 3.7944328785 4.2516431808 489 1305031118.4457030296 0.0484148785 0.0445658950 0.0844885111 0.0185308003 2.9042210000 0.8540340000 0.2902230000 0.1113960000 0.8113810000 0.8339870000 110397094 0 1786597376 3.9121108055 3.7938830853 4.2553253174 490 1305031118.4792850018 0.0488499254 0.0445746379 0.0844885111 0.0185119608 2.0732340000 0.8558680000 0.3916600000 0.0000050000 0.8155080000 0.0070090000 110399280 0 1784946688 3.9123158455 3.7913355827 4.2582259178 491 1305031118.5112550259 0.0497277118 0.0445851330 0.0844885111 0.0184974414 2.0882780000 0.8583150000 0.2910020000 0.1114950000 0.8172060000 0.0070590000 110401466 0 1786249216 3.9122893810 3.7893402576 4.2609272003 492 1305031118.5451989174 0.0472303554 0.0445905095 0.0844885111 0.0184941355 1.9802770000 0.8628170000 0.2971410000 0.0000040000 0.8099850000 0.0071110000 110403684 0 1785454592 3.9138493538 3.7940373421 4.2627253532 493 1305031118.5792849064 0.0472574756 0.0445959191 0.0844885111 0.0184763867 2.8492610000 0.8609350000 0.2615170000 0.1113660000 0.7974490000 0.8147490000 110405934 0 1787232256 3.9150207043 3.7955675125 4.2639141083 494 1305031118.6161420345 0.0475340784 0.0446018668 0.0844885111 0.0184601953 2.0688670000 0.8772580000 0.3966970000 0.0000040000 0.7847310000 0.0070330000 110408184 0 1785454592 3.9158067703 3.7984280586 4.2639508247 495 1305031118.6453309059 0.0452057458 0.0446030868 0.0844885111 0.0184456138 2.0657990000 0.8751170000 0.2979130000 0.1110200000 0.7715070000 0.0070860000 110410338 0 1786978304 3.9178442955 3.8038034439 4.2628006935 496 1305031118.6792950630 0.0444057919 0.0446026890 0.0844885111 0.0184324441 1.8732030000 0.8734800000 0.2312420000 0.0000040000 0.7581400000 0.0070400000 110412588 0 1785327616 3.9189772606 3.8099122047 4.2614259720 497 1305031118.7114210129 0.0457798950 0.0446050576 0.0844885111 0.0184243353 2.7411430000 0.8716470000 0.2633990000 0.1109880000 0.7373450000 0.7546220000 110414742 0 1786986496 3.9181723595 3.8140408993 4.2588882446 498 1305031118.7468008995 0.0496433266 0.0446151746 0.0844885111 0.0184231628 1.8610260000 0.8788220000 0.2323350000 0.0000040000 0.7395600000 0.0070820000 110416992 0 1784573952 3.9172866344 3.8175892830 4.2559895515 499 1305031118.7792770863 0.0450780578 0.0446161022 0.0844885111 0.0184535949 2.0165260000 0.8883800000 0.2720940000 0.1112960000 0.7343610000 0.0071270000 110419210 0 1786097664 3.9191825390 3.8295612335 4.2532401085 500 1305031118.8112208843 0.0424595438 0.0446117891 0.0844885111 0.0184535742 2.0076150000 0.8806120000 0.3992680000 0.0000040000 0.7174010000 0.0071210000 110421364 0 1785073664 3.9221036434 3.8387601376 4.2496404648 501 1305031118.8467741013 0.0478268564 0.0446182064 0.0844885111 0.0184763349 2.6560140000 0.8714220000 0.2269390000 0.1115150000 0.7126340000 0.7302580000 110423614 0 1786597376 3.9249446392 3.8413810730 4.2438511848 502 1305031118.8792080879 0.0420182571 0.0446130272 0.0844885111 0.0185296390 1.8835730000 0.8824540000 0.2738780000 0.0000050000 0.7167330000 0.0070730000 110425832 0 1785454592 3.9253237247 3.8571479321 4.2375211716 503 1305031118.9111769199 0.0401338674 0.0446041224 0.0844885111 0.0185303756 1.9824710000 0.8844760000 0.2681760000 0.1116030000 0.7078130000 0.0070780000 110427986 0 1787105280 3.9243693352 3.8686366081 4.2315783501 504 1305031118.9470090866 0.0432709418 0.0446014772 0.0844885111 0.0185124869 1.8304400000 0.8930230000 0.2349530000 0.0000050000 0.6921550000 0.0070800000 110430236 0 1784565760 3.9256300926 3.8763360977 4.2241024971 505 1305031118.9793939590 0.0395570323 0.0445914882 0.0844885111 0.0185069394 2.6333160000 0.8946080000 0.2394540000 0.1119860000 0.6804540000 0.7035450000 110432454 0 1785962496 3.9248700142 3.8897955418 4.2171082497 506 1305031119.0113630295 0.0383139700 0.0445790820 0.0844885111 0.0184952117 1.8794850000 0.9027280000 0.3075230000 0.0000040000 0.6585870000 0.0071730000 110434608 0 1785327616 3.9229602814 3.9011518955 4.2108817101 507 1305031119.0471799374 0.0419302732 0.0445738575 0.0844885111 0.0184831210 1.8816520000 0.9071860000 0.2027290000 0.1121970000 0.6490350000 0.0072430000 110436858 0 1786724352 3.9222409725 3.9093101025 4.2038750648 508 1305031119.0792229176 0.0422477163 0.0445692785 0.0844885111 0.0184688703 1.8240700000 0.9179020000 0.2475990000 0.0000050000 0.6479350000 0.0073770000 110439012 0 1785327616 3.9210715294 3.9181904793 4.1971483231 509 1305031119.1113278866 0.0420218185 0.0445642737 0.0844885111 0.0184543437 2.7677090000 0.9212190000 0.4155510000 0.1127530000 0.6483510000 0.6665260000 110441230 0 1786978304 3.9197363853 3.9274759293 4.1903152466 510 1305031119.1476290226 0.0425658673 0.0445603552 0.0844885111 0.0184422522 1.8358590000 0.9231230000 0.2430610000 0.0000050000 0.6590290000 0.0071860000 110443480 0 1784946688 3.9204051495 3.9380805492 4.1837711334 511 1305031119.1792619228 0.0422649086 0.0445558632 0.0844885111 0.0184364496 1.9480490000 0.9253570000 0.2409230000 0.1131620000 0.6580910000 0.0072450000 110445666 0 1786343424 3.9195597172 3.9469778538 4.1773495674 512 1305031119.2113640308 0.0422740653 0.0445514065 0.0844885111 0.0184243129 1.9342410000 0.9123080000 0.3457580000 0.0000050000 0.6656200000 0.0071710000 110447852 0 1785073664 3.9201979637 3.9551048279 4.1711907387 513 1305031119.2476599216 0.0421294384 0.0445466853 0.0844885111 0.0184129257 2.6483120000 0.9218900000 0.2427720000 0.1139810000 0.6754570000 0.6907710000 110491062 0 1786724352 3.9203989506 3.9666442871 4.1651353836 514 1305031119.2792439461 0.0409783088 0.0445397430 0.0844885111 0.0183982330 1.8894530000 0.9262860000 0.2815260000 0.0000050000 0.6710100000 0.0072550000 110577216 0 1784819712 3.9194529057 3.9768071175 4.1599731445 515 1305031119.3112120628 0.0407998301 0.0445324810 0.0844885111 0.0183814799 2.0495650000 0.9313520000 0.3237610000 0.1137610000 0.6699050000 0.0072540000 110579402 0 1786605568 3.9199645519 3.9855408669 4.1553874016 516 1305031119.3477499485 0.0447233096 0.0445328508 0.0844885111 0.0183651017 1.8771130000 0.9465280000 0.2496590000 0.0000060000 0.6701870000 0.0072490000 110581652 0 1785716736 3.9210872650 3.9927132130 4.1510038376 517 1305031119.3792390823 0.0435794517 0.0445310067 0.0844885111 0.0183555619 2.6875070000 0.9476510000 0.2512460000 0.1139420000 0.6736270000 0.6976440000 110583838 0 1787359232 3.9204478264 4.0030584335 4.1470055580 518 1305031119.4114921093 0.0427882150 0.0445276423 0.0844885111 0.0183454255 1.8410230000 0.9457210000 0.2131790000 0.0000050000 0.6713170000 0.0073330000 110586024 0 1784946688 3.9211151600 4.0133042336 4.1431307793 519 1305031119.4477260113 0.0465509929 0.0445315408 0.0844885111 0.0183282987 1.9925290000 0.9531400000 0.2528830000 0.1148500000 0.6609070000 0.0073500000 110588306 0 1786470400 3.9220459461 4.0223760605 4.1394424438 520 1305031119.4792668819 0.0478569567 0.0445379358 0.0844885111 0.0183126470 2.0376930000 0.9453490000 0.4297830000 0.0000060000 0.6518310000 0.0072400000 110590428 0 1785090048 3.9208774567 4.0305585861 4.1352324486 521 1305031119.5112578869 0.0476215258 0.0445438544 0.0844885111 0.0183008827 2.8127130000 0.9550470000 0.4346880000 0.1140420000 0.6439150000 0.6616170000 110592614 0 1786724352 3.9188230038 4.0419034958 4.1318826675 522 1305031119.5474140644 0.0518873744 0.0445579225 0.0844885111 0.0182836750 1.8213760000 0.9601680000 0.2138480000 0.0000060000 0.6366560000 0.0072910000 110594896 0 1784819712 3.9184823036 4.0511760712 4.1285157204 523 1305031119.5795691013 0.0515064821 0.0445712085 0.0844885111 0.0182788446 2.0417640000 0.9613050000 0.3266450000 0.1140700000 0.6289250000 0.0073770000 110597082 0 1786343424 3.9200978279 4.0622305870 4.1256375313 524 1305031119.6150240898 0.0528845936 0.0445870737 0.0844885111 0.0182672833 2.0405860000 0.9641660000 0.4360140000 0.0000060000 0.6297490000 0.0072720000 110599332 0 1785581568 3.9185383320 4.0719566345 4.1230897903 525 1305031119.6488890648 0.0587414429 0.0446140344 0.0844885111 0.0182649480 2.6892650000 0.9634220000 0.2885280000 0.1140270000 0.6505080000 0.6693890000 110601550 0 1786978304 3.9172139168 4.0807156563 4.1215963364 526 1305031119.6792080402 0.0591903701 0.0446417461 0.0844885111 0.0182556689 1.9577990000 0.9650880000 0.2882130000 0.0000040000 0.6936450000 0.0074260000 110603672 0 1785327616 3.9157857895 4.0920219421 4.1200699806 527 1305031119.7152490616 0.0614813715 0.0446736998 0.0844885111 0.0182405140 2.0997400000 0.9731010000 0.3568300000 0.1140120000 0.6451010000 0.0073360000 110605922 0 1786978304 3.9133319855 4.1016912460 4.1193008423 528 1305031119.7471930981 0.0696175247 0.0447209419 0.0844885111 0.0182320978 2.0396740000 0.9569690000 0.3983000000 0.0000030000 0.6735860000 0.0072770000 110608140 0 1785200640 3.9113457203 4.1061086655 4.1189885139 529 1305031119.7791690826 0.0716968179 0.0447719360 0.0844885111 0.0182159132 2.7675800000 0.9475530000 0.3656300000 0.1137650000 0.6572190000 0.6800200000 110610326 0 1787105280 3.9101133347 4.1149249077 4.1181530952 530 1305031119.8145709038 0.0747246593 0.0448284506 0.0844885111 0.0182035435 2.0860240000 0.9510410000 0.4354250000 0.0000040000 0.6887380000 0.0073850000 110612512 0 1784946688 3.9109396935 4.1217336655 4.1174502373 531 1305031119.8474450111 0.0785266608 0.0448919124 0.0844885111 0.0181920678 2.1614620000 0.9652810000 0.4025930000 0.1140540000 0.6687330000 0.0073580000 110614762 0 1786605568 3.9125475883 4.1307134628 4.1164832115 532 1305031119.8792319298 0.0805675313 0.0449589718 0.0844885111 0.0181805916 2.0811600000 0.9490840000 0.4299980000 0.0000040000 0.6913420000 0.0072650000 110616916 0 1784446976 3.9105267525 4.1374197006 4.1149945259 533 1305031119.9114239216 0.0810366645 0.0450266598 0.0844885111 0.0181812707 2.8805610000 0.9388650000 0.4238800000 0.1139900000 0.6901430000 0.7101810000 110619102 0 1785962496 3.9088151455 4.1459012032 4.1130104065 534 1305031119.9474620819 0.0828215331 0.0450974367 0.0844885111 0.0181695991 2.0504710000 0.9555020000 0.3631740000 0.0000040000 0.7210370000 0.0072890000 110621384 0 1787740160 3.9089908600 4.1550521851 4.1114678383 535 1305031119.9795460701 0.0854819566 0.0451729218 0.0854819566 0.0181562643 2.1817530000 0.9461290000 0.4242850000 0.1143460000 0.6862880000 0.0072110000 110623570 0 1784692736 3.9083104134 4.1589026451 4.1104159355 536 1305031120.0152831078 0.0851813778 0.0452475644 0.0854819566 0.0181661636 2.0358170000 0.9566120000 0.3597760000 0.0000030000 0.7084640000 0.0072740000 110625788 0 1786216448 3.9063799381 4.1666307449 4.1093525887 537 1305031120.0473101139 0.0883211121 0.0453277759 0.0883211121 0.0181607381 2.7506450000 0.9656660000 0.2821200000 0.1139400000 0.6760960000 0.7093250000 110628006 0 1788121088 3.9076251984 4.1704540253 4.1095142365 538 1305031120.0794179440 0.0941268876 0.0454184805 0.0941268876 0.0181671317 2.0895870000 0.9483060000 0.4270530000 0.0000040000 0.7034020000 0.0073160000 110630192 0 1784946688 3.9087016582 4.1661815643 4.1104898453 539 1305031120.1152489185 0.0925396085 0.0455059038 0.0941268876 0.0181605262 2.0465460000 0.9552120000 0.2852690000 0.1139890000 0.6813160000 0.0072820000 110632410 0 1786470400 3.9076821804 4.1695761681 4.1097426414 540 1305031120.1481750011 0.0908135325 0.0455898068 0.0941268876 0.0181614160 2.0008210000 0.9581540000 0.3204300000 0.0000040000 0.7108580000 0.0077270000 110634628 0 1784565760 3.9082281590 4.1700649261 4.1094341278 541 1305031120.1792609692 0.0933578014 0.0456781025 0.0941268876 0.0181525391 2.7854150000 0.9558360000 0.3229740000 0.1140920000 0.6792320000 0.7096460000 110636782 0 1786089472 3.9078750610 4.1638164520 4.1107015610 542 1305031120.2152600288 0.0932464823 0.0457658671 0.0941268876 0.0181380640 1.9689710000 0.9745690000 0.3237650000 0.0000040000 0.6598270000 0.0072990000 110639032 0 1788121088 3.9084906578 4.1581397057 4.1106700897 543 1305031120.2480180264 0.0854214728 0.0458388977 0.0941268876 0.0181236806 2.1639410000 0.9547910000 0.4309480000 0.1141090000 0.6531790000 0.0072390000 110641250 0 1784565760 3.9047629833 4.1581211090 4.1087026596 544 1305031120.2794411182 0.0818803832 0.0459051504 0.0941268876 0.0181080768 2.0579630000 0.9575250000 0.4332960000 0.0000040000 0.6562820000 0.0072340000 110643436 0 1785962496 3.9009830952 4.1535181999 4.1081337929 545 1305031120.3152129650 0.0777276531 0.0459635403 0.0941268876 0.0180919342 2.8168910000 0.9507180000 0.4305760000 0.1141190000 0.6467430000 0.6711040000 110645654 0 1787994112 3.8965501785 4.1488175392 4.1074686050 546 1305031120.3477969170 0.0706352964 0.0460087267 0.0941268876 0.0180759909 2.0568740000 0.9633400000 0.4319620000 0.0000040000 0.6505140000 0.0073120000 110647872 0 1784827904 3.8937470913 4.1433835030 4.1068606377 547 1305031120.3794460297 0.0678084940 0.0460485800 0.0941268876 0.0180604740 2.0135880000 0.9622730000 0.2882150000 0.1138760000 0.6383960000 0.0072490000 110650058 0 1786097664 3.8941826820 4.1364970207 4.1092705727 548 1305031120.4154899120 0.0654648021 0.0460840110 0.0941268876 0.0181133062 1.9346600000 0.9650510000 0.3290320000 0.0000030000 0.6295270000 0.0072760000 110652276 0 1788002304 3.9037799835 4.1233625412 4.1106772423 549 1305031120.4474329948 0.0589466766 0.0461074403 0.0941268876 0.0181071039 2.6432520000 0.9772210000 0.2893740000 0.1143110000 0.6190330000 0.6396710000 110654494 0 1784565760 3.9006912708 4.1178646088 4.1141343117 550 1305031120.4794321060 0.0531920828 0.0461203215 0.0941268876 0.0180926051 1.8390260000 0.9651940000 0.2528480000 0.0000030000 0.6100450000 0.0073580000 110656680 0 1786216448 3.9067270756 4.1130905151 4.1170840263 551 1305031120.5148770809 0.0539277829 0.0461344911 0.0941268876 0.0180828600 2.0035540000 0.9786850000 0.2918740000 0.1191130000 0.6027630000 0.0075100000 110658898 0 1788121088 3.9086723328 4.1011204720 4.1215958595 552 1305031120.5478069782 0.0477432460 0.0461374055 0.0941268876 0.0180694038 2.0265110000 0.9716120000 0.4395540000 0.0000030000 0.6043680000 0.0073810000 110661116 0 1784565760 3.9115381241 4.0940437317 4.1252727509 553 1305031120.5795590878 0.0434117094 0.0461324766 0.0941268876 0.0180588242 2.6671660000 0.9753640000 0.3253700000 0.1138210000 0.6121340000 0.6368110000 110663302 0 1786089472 3.9151775837 4.0897870064 4.1294097900 554 1305031120.6152710915 0.0429151803 0.0461266692 0.0941268876 0.0180475867 2.0308010000 0.9679500000 0.4359180000 0.0000040000 0.6160690000 0.0072950000 110665488 0 1788121088 3.9181611538 4.0811843872 4.1342720985 555 1305031120.6473538876 0.0380246080 0.0461120709 0.0941268876 0.0180354399 2.1432160000 0.9569430000 0.4340840000 0.1135750000 0.6276410000 0.0072760000 110667706 0 1785200640 3.9196643829 4.0736999512 4.1383914948 556 1305031120.6793179512 0.0348508656 0.0460918169 0.0941268876 0.0180431287 1.8280410000 0.9592290000 0.2152400000 0.0000030000 0.6426570000 0.0073350000 110669860 0 1786851328 3.9217576981 4.0689940453 4.1425905228 557 1305031120.7145531178 0.0334607400 0.0460691399 0.0941268876 0.0180275888 2.7169480000 0.9545510000 0.3269130000 0.1136950000 0.6496020000 0.6684840000 110672110 0 1784438784 3.9226608276 4.0613188744 4.1468882561 558 1305031120.7473959923 0.0296525452 0.0460397195 0.0941268876 0.0180146562 2.0552410000 0.9514800000 0.4357820000 0.0000040000 0.6567770000 0.0072950000 110674328 0 1785978880 3.9221301079 4.0533466339 4.1512904167 559 1305031120.7799079418 0.0305322222 0.0460119780 0.0941268876 0.0180034494 2.0356980000 0.9519730000 0.2901490000 0.1135750000 0.6690820000 0.0072710000 110676546 0 1787740160 3.9227890968 4.0433545113 4.1556057930 560 1305031120.8149440289 0.0291359350 0.0459818422 0.0941268876 0.0179952938 1.9299810000 0.9427620000 0.2887660000 0.0000040000 0.6874100000 0.0073200000 110678764 0 1785073664 3.9233071804 4.0362501144 4.1591486931 561 1305031120.8479421139 0.0241060965 0.0459428480 0.0941268876 0.0179795311 2.8823970000 0.9400120000 0.4283340000 0.1136250000 0.6889120000 0.7078250000 110680982 0 1786724352 3.9222054482 4.0304288864 4.1626963615 562 1305031120.8834540844 0.0254152417 0.0459063220 0.0941268876 0.0179723006 2.0842130000 0.9382660000 0.4330010000 0.0000040000 0.7020190000 0.0072650000 110683200 0 1784827904 3.9244172573 4.0192918777 4.1658539772 563 1305031120.9154539108 0.0237842724 0.0458670289 0.0941268876 0.0179654776 2.0220310000 0.9417310000 0.2505680000 0.1135660000 0.7052340000 0.0073300000 110685386 0 1786224640 3.9234795570 4.0130453110 4.1689963341 564 1305031120.9475090504 0.0210985783 0.0458231132 0.0941268876 0.0179502935 2.0723270000 0.9293580000 0.4257330000 0.0000030000 0.7062850000 0.0072150000 110687572 0 1788129280 3.9221465588 4.0051302910 4.1718907356 565 1305031120.9833900928 0.0215968378 0.0457802348 0.0941268876 0.0179378494 2.8123310000 0.9382650000 0.3175620000 0.1134630000 0.7109870000 0.7283380000 110689822 0 1784819712 3.9218752384 3.9961786270 4.1748862267 566 1305031121.0150289536 0.0236599296 0.0457411530 0.0941268876 0.0179287585 2.0912760000 0.9344630000 0.4287870000 0.0000040000 0.7169760000 0.0073250000 110691976 0 1786089472 3.9203345776 3.9865810871 4.1777262688 567 1305031121.0477550030 0.0191841777 0.0456943153 0.0941268876 0.0179130579 2.0478970000 0.9288590000 0.2698510000 0.1139180000 0.7243210000 0.0072860000 110694226 0 1788121088 3.9204244614 3.9808089733 4.1799139977 568 1305031121.0831170082 0.0222223271 0.0456529914 0.0941268876 0.0179018431 2.0862240000 0.9255750000 0.4211850000 0.0000030000 0.7285130000 0.0072660000 110696444 0 1784692736 3.9178256989 3.9704649448 4.1825089455 569 1305031121.1148779392 0.0221073404 0.0456116106 0.0941268876 0.0178885344 2.9813370000 0.9307510000 0.4270380000 0.1133550000 0.7470050000 0.7595110000 110698598 0 1786089472 3.9192659855 3.9615433216 4.1847548485 570 1305031121.1473550797 0.0199708901 0.0455666269 0.0941268876 0.0178736586 1.9701950000 0.9661570000 0.2369560000 0.0000040000 0.7561090000 0.0072280000 110700816 0 1788121088 3.9175081253 3.9547564983 4.1868491173 571 1305031121.1832809448 0.0219992604 0.0455253531 0.0941268876 0.0178580459 2.2580040000 0.9272020000 0.4269700000 0.1134670000 0.7794110000 0.0072840000 110703066 0 1784692736 3.9151976109 3.9461622238 4.1892223358 572 1305031121.2114310265 0.0216566268 0.0454836245 0.0941268876 0.0178467686 1.9328130000 0.9213950000 0.2092470000 0.0000030000 0.7911230000 0.0073240000 110705156 0 1786089472 3.9157991409 3.9380240440 4.1914567947 573 1305031121.2472009659 0.0215481985 0.0454418524 0.0941268876 0.0178323340 2.9502380000 0.9228800000 0.2778190000 0.1132830000 0.8042110000 0.8283010000 110707406 0 1788121088 3.9140524864 3.9318547249 4.1941385269 574 1305031121.2828760147 0.0243497845 0.0454051066 0.0941268876 0.0178171046 2.0085160000 0.9099080000 0.2745470000 0.0000040000 0.8131680000 0.0072080000 110709656 0 1784692736 3.9119534492 3.9227311611 4.1975646019 575 1305031121.3135879040 0.0253581591 0.0453702424 0.0941268876 0.0178105726 2.1520440000 0.9231180000 0.2795240000 0.1132780000 0.8249890000 0.0072810000 110711810 0 1786216448 3.9130942822 3.9123513699 4.2005510330 576 1305031121.3475399017 0.0273252297 0.0453389142 0.0941268876 0.0177991945 2.0151120000 0.9228030000 0.2399460000 0.0000060000 0.8412760000 0.0072520000 110714028 0 1788121088 3.9103274345 3.9054005146 4.2041163445 577 1305031121.3832480907 0.0268803313 0.0453069236 0.0941268876 0.0177948392 3.0328810000 0.9116680000 0.2751020000 0.1132250000 0.8556380000 0.8733430000 110716278 0 1784586240 3.9115474224 3.8965191841 4.2076086998 578 1305031121.4143280983 0.0290794205 0.0452788484 0.0941268876 0.0177806864 2.1762210000 0.9456390000 0.3445330000 0.0000040000 0.8749660000 0.0072340000 110718432 0 1786097664 3.9099564552 3.8880743980 4.2102074623 579 1305031121.4473190308 0.0318785571 0.0452557045 0.0941268876 0.0177735735 2.2065020000 0.8879000000 0.3035670000 0.1131680000 0.8908810000 0.0071510000 110720650 0 1785200640 3.9066336155 3.8835015297 4.2138662338 580 1305031121.4830150604 0.0313570499 0.0452317413 0.0941268876 0.0177763666 2.1321920000 0.9158420000 0.3072740000 0.0000050000 0.8979940000 0.0073040000 110722868 0 1786597376 3.9089090824 3.8738408089 4.2167477608 581 1305031121.5141639709 0.0339902677 0.0452123928 0.0941268876 0.0177656685 3.1670820000 0.9033020000 0.3070110000 0.1138400000 0.9108520000 0.9281250000 110725022 0 1784565760 3.9067893028 3.8634488583 4.2195944786 582 1305031121.5472700596 0.0344956256 0.0451939791 0.0941268876 0.0177602080 2.2019360000 0.8788950000 0.3950740000 0.0000050000 0.9169690000 0.0071280000 110727272 0 1786105856 3.9063684940 3.8562881947 4.2236790657 583 1305031121.5832130909 0.0348136425 0.0451761741 0.0941268876 0.0177479081 2.2447690000 0.9324680000 0.2712030000 0.1132380000 0.9168160000 0.0071370000 110729522 0 1787740160 3.9063496590 3.8477458954 4.2266025543 584 1305031121.6147189140 0.0358118787 0.0451601393 0.0941268876 0.0177349518 2.0160000000 0.8812880000 0.2046270000 0.0000050000 0.9190210000 0.0072360000 110731676 0 1784438784 3.9062912464 3.8362686634 4.2293663025 585 1305031121.6471829414 0.0354986303 0.0451436239 0.0941268876 0.0177281975 3.1678370000 0.8873730000 0.3044040000 0.1126180000 0.9205760000 0.9389970000 110733862 0 1785962496 3.9086222649 3.8294453621 4.2316412926 586 1305031121.6832110882 0.0374916978 0.0451305660 0.0941268876 0.0177184158 2.0842730000 0.8899440000 0.2674800000 0.0000040000 0.9158280000 0.0072290000 110736144 0 1787740160 3.9067313671 3.8221452236 4.2348241806 587 1305031121.7145280838 0.0413774475 0.0451241723 0.0941268876 0.0177045933 2.1424940000 0.8734620000 0.2304040000 0.1122600000 0.9154520000 0.0071390000 110738298 0 1784438784 3.9035809040 3.8117733002 4.2373270988 588 1305031121.7471449375 0.0429058559 0.0451203997 0.0941268876 0.0176916561 2.1055330000 0.8463300000 0.3209670000 0.0000050000 0.9274370000 0.0069960000 110740484 0 1785962496 3.9034590721 3.8076918125 4.2404198647 589 1305031121.7828710079 0.0435331725 0.0451177049 0.0941268876 0.0176775405 3.1642610000 0.8637990000 0.3303440000 0.1121490000 0.9191820000 0.9349900000 110742734 0 1787867136 3.9048933983 3.8004899025 4.2435622215 590 1305031121.8115448952 0.0449118540 0.0451173560 0.0941268876 0.0176672660 2.1889730000 0.8578950000 0.4000550000 0.0000050000 0.9200720000 0.0071120000 110744856 0 1784819712 3.9047391415 3.7953035831 4.2465987206 591 1305031121.8473351002 0.0454292372 0.0451178837 0.0941268876 0.0176545660 2.3077670000 0.8769080000 0.3937160000 0.1120480000 0.9141790000 0.0070860000 110747106 0 1786343424 3.9071395397 3.7919812202 4.2493200302 592 1305031121.8821229935 0.0462932810 0.0451198692 0.0941268876 0.0176396512 2.0494440000 0.8607080000 0.2627610000 0.0000040000 0.9151040000 0.0070210000 110749324 0 1788256256 3.9063718319 3.7891399860 4.2516832352 593 1305031121.9149429798 0.0456147082 0.0451207036 0.0941268876 0.0176254920 3.0643820000 0.8576450000 0.2628890000 0.1118100000 0.9052350000 0.9229260000 110751542 0 1784193024 3.9077188969 3.7875049114 4.2531213760 594 1305031121.9473180771 0.0462856963 0.0451226649 0.0941268876 0.0176136938 1.9908710000 0.8467930000 0.2244350000 0.0000040000 0.9087940000 0.0069820000 110753728 0 1785581568 3.9069349766 3.7861900330 4.2541956902 595 1305031121.9829349518 0.0434178896 0.0451197997 0.0941268876 0.0175995732 2.1758170000 0.8548000000 0.2965760000 0.1118970000 0.9015570000 0.0070670000 110755978 0 1787359232 3.9091196060 3.7900333405 4.2546453476 596 1305031122.0144240856 0.0432416238 0.0451166484 0.0941268876 0.0175857486 1.9828590000 0.8527450000 0.2252310000 0.0000050000 0.8939750000 0.0070530000 110758164 0 1784311808 3.9079802036 3.7923679352 4.2543401718 597 1305031122.0473060608 0.0432836600 0.0451135781 0.0941268876 0.0175717317 3.1721820000 0.8629770000 0.3941240000 0.1120420000 0.8907560000 0.9084080000 110760350 0 1785835520 3.9076743126 3.7949879169 4.2531819344 598 1305031122.0829689503 0.0419232771 0.0451082431 0.0941268876 0.0175576673 2.0377020000 0.8695180000 0.2681950000 0.0000050000 0.8889050000 0.0070480000 110762600 0 1787867136 3.9072957039 3.8017420769 4.2514138222 599 1305031122.1146879196 0.0411168858 0.0451015798 0.0941268876 0.0175440412 2.2106400000 0.9059510000 0.2965240000 0.1123570000 0.8847810000 0.0071310000 110764754 0 1784819712 3.9072594643 3.8090624809 4.2483339310 600 1305031122.1507480145 0.0398408808 0.0450928120 0.0941268876 0.0175349249 2.0395090000 0.8828070000 0.2688260000 0.0000050000 0.8768330000 0.0071430000 110767004 0 1786089472 3.9070477486 3.8186624050 4.2455167770 601 1305031122.1830520630 0.0383886397 0.0450816569 0.0941268876 0.0175323667 3.0689950000 0.8917380000 0.3019660000 0.1121010000 0.8710270000 0.8881960000 110769222 0 1787994112 3.9088160992 3.8270680904 4.2412996292 602 1305031122.2149689198 0.0358862169 0.0450663821 0.0941268876 0.0175589997 2.0700660000 0.8948520000 0.3066630000 0.0000050000 0.8574420000 0.0071210000 110771376 0 1784692736 3.9076974392 3.8405079842 4.2383918762 603 1305031122.2513549328 0.0368448608 0.0450527477 0.0941268876 0.0175508260 2.2014050000 0.9061370000 0.3383640000 0.1128030000 0.8330370000 0.0071870000 110773658 0 1786089472 3.9054765701 3.8518850803 4.2346487045 604 1305031122.2838659286 0.0380863883 0.0450412140 0.0941268876 0.0175413710 2.1348960000 0.9029510000 0.4033520000 0.0000050000 0.8173640000 0.0072010000 110775876 0 1787994112 3.9046835899 3.8598759174 4.2285284996 605 1305031122.3143088818 0.0335578844 0.0450222333 0.0941268876 0.0175617764 2.8820890000 0.8982500000 0.2398340000 0.1121130000 0.8082870000 0.8196650000 110777998 0 1784692736 3.9041361809 3.8762657642 4.2240872383 606 1305031122.3513510227 0.0353833586 0.0450063276 0.0941268876 0.0175536862 1.9298060000 0.9090090000 0.2344270000 0.0000050000 0.7752220000 0.0072040000 110780248 0 1786343424 3.9050118923 3.8836123943 4.2199411392 607 1305031122.3826780319 0.0348077677 0.0449895260 0.0941268876 0.0175423769 2.0280530000 0.9082980000 0.2354850000 0.1125190000 0.7606030000 0.0071960000 110782466 0 1788002304 3.9066905975 3.8916456699 4.2147030830 608 1305031122.4150080681 0.0367633738 0.0449759962 0.0941268876 0.0175399855 2.0093830000 0.9164650000 0.3416140000 0.0000050000 0.7401170000 0.0072630000 110784588 0 1785335808 3.9061150551 3.8982322216 4.2089996338 609 1305031122.4512720108 0.0382986590 0.0449650317 0.0941268876 0.0175281782 2.8724990000 0.9230580000 0.3456750000 0.1130730000 0.7312240000 0.7554490000 110786870 0 1786859520 3.9070889950 3.9074287415 4.2032747269 610 1305031122.4833879471 0.0368407704 0.0449517133 0.0941268876 0.0175149361 2.0679420000 0.9208620000 0.4131720000 0.0000050000 0.7227640000 0.0071930000 110789056 0 1784819712 3.9064676762 3.9177198410 4.1975831985 611 1305031122.5151350498 0.0367475748 0.0449382859 0.0941268876 0.0175044222 2.1852420000 0.9223010000 0.4132600000 0.1135380000 0.7248450000 0.0072440000 110791242 0 1786343424 3.9067275524 3.9261291027 4.1922073364 612 1305031122.5515100956 0.0380247869 0.0449269893 0.0941268876 0.0174972092 1.9797180000 0.9305230000 0.3125790000 0.0000050000 0.7253750000 0.0072970000 110793492 0 1785835520 3.9069514275 3.9366755486 4.1868076324 613 1305031122.5832169056 0.0377767496 0.0449153250 0.0941268876 0.0174839239 2.7385980000 0.9270660000 0.2430700000 0.1137150000 0.7163930000 0.7343210000 110795678 0 1787232256 3.9068570137 3.9460494518 4.1813974380 614 1305031122.6150169373 0.0394086652 0.0449063565 0.0941268876 0.0174775975 1.8600890000 0.9308660000 0.2079800000 0.0000050000 0.7098190000 0.0072100000 110797832 0 1784946688 3.9060895443 3.9532296658 4.1758656502 615 1305031122.6488099098 0.0432917140 0.0449037310 0.0941268876 0.0174635947 2.0176770000 0.9341580000 0.2450440000 0.1139410000 0.7132120000 0.0072410000 110800082 0 1786470400 3.9059948921 3.9615292549 4.1703538895 616 1305031122.6834199429 0.0420158282 0.0448990429 0.0941268876 0.0174497375 1.8990450000 0.9226380000 0.2441740000 0.0000060000 0.7208720000 0.0072080000 110802300 0 1784692736 3.9056999683 3.9727728367 4.1653738022 617 1305031122.7152190208 0.0424976312 0.0448951508 0.0941268876 0.0174378710 2.9391260000 0.9407220000 0.4275180000 0.1141440000 0.7172220000 0.7354790000 110804454 0 1786089472 3.9057192802 3.9818775654 4.1612696648 618 1305031122.7513089180 0.0441430695 0.0448939338 0.0941268876 0.0174317391 2.1116090000 0.9449720000 0.4277680000 0.0000040000 0.7274720000 0.0073270000 110806736 0 1787867136 3.9074273109 3.9935224056 4.1571950912 619 1305031122.7834379673 0.0416138545 0.0448886348 0.0941268876 0.0174241020 2.0648030000 0.9749420000 0.2499990000 0.1143150000 0.7142460000 0.0072780000 110808922 0 1785446400 3.9075388908 4.0067076683 4.1541800499 620 1305031122.8125650883 0.0425903350 0.0448849279 0.0941268876 0.0174119482 1.9837760000 0.9572810000 0.3190540000 0.0000050000 0.6959960000 0.0072760000 110811076 0 1787105280 3.9083511829 4.0157532692 4.1515073776 621 1305031122.8514859676 0.0476325378 0.0448893524 0.0941268876 0.0174106024 2.8673960000 0.9511180000 0.4297890000 0.1143620000 0.6749840000 0.6929930000 110813358 0 1784700928 3.9079625607 4.0226659775 4.1490044594 622 1305031122.8837749958 0.0478901938 0.0448941769 0.0941268876 0.0173992213 1.9798350000 0.9581260000 0.3583580000 0.0000050000 0.6519010000 0.0072820000 110815576 0 1786216448 3.9096193314 4.0317559242 4.1464638710 623 1305031122.9145851135 0.0502008162 0.0449026948 0.0941268876 0.0173923383 1.9667590000 0.9607010000 0.2493310000 0.1146990000 0.6307090000 0.0072590000 110817698 0 1787994112 3.9072446823 4.0380291939 4.1437859535 624 1305031122.9514129162 0.0551537909 0.0449191228 0.0941268876 0.0173802108 1.7998810000 0.9529360000 0.2133040000 0.0000040000 0.6222740000 0.0073100000 110819980 0 1785327616 3.9059119225 4.0437493324 4.1412801743 625 1305031122.9830000401 0.0557932407 0.0449365214 0.0941268876 0.0173686458 2.6095020000 0.9792930000 0.2511690000 0.1143650000 0.6237740000 0.6368400000 110822166 0 1786724352 3.9070806503 4.0513067245 4.1390724182 626 1305031123.0154619217 0.0575579852 0.0449566835 0.0941268876 0.0173551206 1.8676660000 0.9500130000 0.2884840000 0.0000050000 0.6178360000 0.0073200000 110824320 0 1784565760 3.9056036472 4.0579652786 4.1370210648 627 1305031123.0518379211 0.0623055659 0.0449843532 0.0941268876 0.0173449732 1.9819820000 0.9473900000 0.2843400000 0.1142230000 0.6246890000 0.0072980000 110826602 0 1786089472 3.9055085182 4.0635113716 4.1347222328 628 1305031123.0829920769 0.0625543967 0.0450123309 0.0941268876 0.0173350997 1.8856890000 0.9583670000 0.2857390000 0.0000210000 0.6301560000 0.0073080000 110828788 0 1787867136 3.9049110413 4.0721645355 4.1322345734 629 1305031123.1139390469 0.0614643022 0.0450384867 0.0941268876 0.0173280735 2.8129950000 0.9657090000 0.4415030000 0.1145390000 0.6340590000 0.6531580000 110830910 0 1785454592 3.9065518379 4.0827221870 4.1300978661 630 1305031123.1508400440 0.0666075125 0.0450727232 0.0941268876 0.0173146283 1.9034380000 0.9679870000 0.2901790000 0.0000050000 0.6337210000 0.0073980000 110833192 0 1786851328 3.9044725895 4.0894303322 4.1289801598 631 1305031123.1821761131 0.0678529665 0.0451088251 0.0941268876 0.0173122148 2.0150100000 0.9605470000 0.2925150000 0.1141970000 0.6363820000 0.0073420000 110835378 0 1784692736 3.9040427208 4.0986442566 4.1274785995 632 1305031123.2147240639 0.0679493994 0.0451449652 0.0941268876 0.0173012772 1.8345420000 0.9655650000 0.2133730000 0.0000050000 0.6441720000 0.0072390000 110837564 0 1786343424 3.9065537453 4.1096262932 4.1265134811 633 1305031123.2506411076 0.0729761049 0.0451889322 0.0941268876 0.0173118940 2.6504960000 0.9563570000 0.2846570000 0.1139440000 0.6346900000 0.6566660000 110839814 0 1785581568 3.9033892155 4.1186599731 4.1259164810 634 1305031123.2823629379 0.0770811886 0.0452392355 0.0941268876 0.0173047972 2.0420550000 0.9648310000 0.4303790000 0.0000050000 0.6351910000 0.0073880000 110842000 0 1787105280 3.9066841602 4.1257848740 4.1266465187 635 1305031123.3209919930 0.0837863684 0.0452999396 0.0941268876 0.0172964233 2.0156520000 0.9703970000 0.2873250000 0.1141520000 0.6323150000 0.0073270000 110844282 0 1785335808 3.9052402973 4.1325531006 4.1272010803 636 1305031123.3504929543 0.0860189199 0.0453639632 0.0941268876 0.0172838355 1.8969970000 0.9657500000 0.2858860000 0.0000050000 0.6336620000 0.0073950000 110846436 0 1786732544 3.9048073292 4.1407594681 4.1271090508 637 1305031123.3822629452 0.0892587900 0.0454328719 0.0941268876 0.0172717966 2.8278490000 0.9659770000 0.4416000000 0.1139450000 0.6379250000 0.6642560000 110848622 0 1784819712 3.9069278240 4.1475934982 4.1271452904 638 1305031123.4213430882 0.0952416137 0.0455109420 0.0952416137 0.0172587013 1.9248890000 0.9689210000 0.2896220000 0.0000050000 0.6548600000 0.0073290000 110850904 0 1786216448 3.9069304466 4.1536812782 4.1270956993 639 1305031123.4512660503 0.0984898657 0.0455938511 0.0984898657 0.0172535364 2.0019270000 0.9677130000 0.2517210000 0.1138770000 0.6571080000 0.0073700000 110853026 0 1787994112 3.9057807922 4.1593375206 4.1266236305 640 1305031123.4836049080 0.0992172807 0.0456776377 0.0992172807 0.0172426060 2.1093580000 0.9694470000 0.4418990000 0.0000050000 0.6864740000 0.0073960000 110855244 0 1785327616 3.9074485302 4.1679773331 4.1254849434 641 1305031123.5197250843 0.1026541814 0.0457665247 0.1026541814 0.0172305736 2.7956190000 0.9776110000 0.3295220000 0.1138380000 0.6671340000 0.7034570000 110857462 0 1786851328 3.9070770741 4.1754159927 4.1243696213 642 1305031123.5515730381 0.1045611575 0.0458581051 0.1045611575 0.0172175900 1.9700790000 0.9791540000 0.2918900000 0.0000040000 0.6874270000 0.0072940000 110859680 0 1784692736 3.9088089466 4.1815276146 4.1236057281 643 1305031123.5796160698 0.1058378965 0.0459513863 0.1058378965 0.0172063751 2.0852450000 0.9827940000 0.2923670000 0.1141040000 0.6843870000 0.0073360000 110861770 0 1786089472 3.9091768265 4.1884374619 4.1226367950 644 1305031123.6203870773 0.1085168123 0.0460485376 0.1085168123 0.0172016594 2.1254560000 0.9954190000 0.4085750000 0.0000040000 0.7098620000 0.0073490000 110864084 0 1787994112 3.9111199379 4.1956467628 4.1217913628 645 1305031123.6524300575 0.1087969244 0.0461458219 0.1087969244 0.0171896211 2.9431500000 0.9905560000 0.4442290000 0.1144340000 0.6781130000 0.7115730000 110866270 0 1785327616 3.9138324261 4.2034163475 4.1212615967 646 1305031123.6837849617 0.1093299091 0.0462436301 0.1093299091 0.0171783170 2.1821160000 1.0045390000 0.4479690000 0.0000050000 0.7178740000 0.0073650000 110868456 0 1786978304 3.9129784107 4.2103772163 4.1207909584 647 1305031123.7199749947 0.1121686623 0.0463455235 0.1121686623 0.0171659122 2.1528470000 0.9977150000 0.3291110000 0.1142450000 0.7000490000 0.0074240000 110870706 0 1784455168 3.9128301144 4.2155714035 4.1202826500 648 1305031123.7519800663 0.1129689217 0.0464483374 0.1129689217 0.0171586069 2.1890710000 0.9903210000 0.4511370000 0.0000050000 0.7358740000 0.0073250000 110872892 0 1785962496 3.9125673771 4.2189941406 4.1195373535 649 1305031123.7841379642 0.1139895469 0.0465524070 0.1139895469 0.0171498759 2.8044570000 0.9871500000 0.2906210000 0.1143470000 0.6851250000 0.7229870000 110875046 0 1787994112 3.9137682915 4.2205362320 4.1191964149 650 1305031123.8196959496 0.1137442589 0.0466557791 0.1139895469 0.0171380670 2.1356420000 0.9826470000 0.4427320000 0.0000040000 0.6986610000 0.0073460000 110877328 0 1785462784 3.9153015614 4.2227921486 4.1182765961 651 1305031123.8515510559 0.1135679260 0.0467585627 0.1139895469 0.0171251765 2.2165640000 0.9708330000 0.4337340000 0.1143920000 0.6860330000 0.0073930000 110879514 0 1786986496 3.9159102440 4.2224936485 4.1176238060 652 1305031123.8838191032 0.1137512699 0.0468613123 0.1139895469 0.0171151078 2.1474610000 0.9897540000 0.4538680000 0.0000040000 0.6922730000 0.0073510000 110881700 0 1784700928 3.9156978130 4.2208776474 4.1174726486 653 1305031123.9157938957 0.1122639775 0.0469614695 0.1139895469 0.0171036705 2.7875660000 0.9890300000 0.2959340000 0.1144680000 0.6738470000 0.7100240000 110883854 0 1786089472 3.9158051014 4.2182531357 4.1168317795 654 1305031123.9515299797 0.1084120348 0.0470554306 0.1139895469 0.0171023985 1.9732910000 0.9882170000 0.2933480000 0.0000050000 0.6800810000 0.0073000000 110886136 0 1787867136 3.9163773060 4.2187471390 4.1162104607 655 1305031123.9834210873 0.1096879020 0.0471510527 0.1139895469 0.0171012493 2.2317610000 0.9876780000 0.4525010000 0.1145970000 0.6653590000 0.0073750000 110888322 0 1785200640 3.9154007435 4.2128710747 4.1179904938 656 1305031124.0197370052 0.1105117351 0.0472476391 0.1139895469 0.0171145539 2.1254410000 1.0052450000 0.4497310000 0.0000050000 0.6587680000 0.0074590000 110890572 0 1786597376 3.9146134853 4.2036857605 4.1206498146 657 1305031124.0515310764 0.1062661037 0.0473374693 0.1139895469 0.0171133929 2.7099740000 1.0063960000 0.2589690000 0.1144140000 0.6476790000 0.6782120000 110892726 0 1784819712 3.9155597687 4.2014327049 4.1207442284 658 1305031124.0839018822 0.1054310948 0.0474257575 0.1139895469 0.0171052587 2.0633850000 0.9960490000 0.4117190000 0.0000050000 0.6440150000 0.0073240000 110894912 0 1786343424 3.9162919521 4.1959509850 4.1233520508 659 1305031124.1196689606 0.1043297648 0.0475121066 0.1139895469 0.0171094231 2.2152840000 1.0011730000 0.4585670000 0.1142740000 0.6295040000 0.0073950000 110897162 0 1787994112 3.9099082947 4.1855521202 4.1255364418 660 1305031124.1474580765 0.1008357853 0.0475929000 0.1139895469 0.0171089718 1.9744640000 0.9954000000 0.3395770000 0.0000040000 0.6277880000 0.0074350000 110899316 0 1785327616 3.9188170433 4.1821279526 4.1279387474 661 1305031124.1827070713 0.0995774344 0.0476715453 0.1139895469 0.0170997941 2.8185380000 0.9784620000 0.4519990000 0.1139290000 0.6217260000 0.6481550000 110901534 0 1786724352 3.9172019958 4.1753683090 4.1306977272 662 1305031124.2171790600 0.0935833082 0.0477408984 0.1139895469 0.0171038092 1.9866750000 0.9809540000 0.3752960000 0.0000060000 0.6188040000 0.0073020000 110903752 0 1784819712 3.9048039913 4.1682586670 4.1286301613 663 1305031124.2493400574 0.0939534679 0.0478106006 0.1139895469 0.0170983138 2.1355980000 0.9771980000 0.4139730000 0.1136670000 0.6189860000 0.0074040000 110905906 0 1786343424 3.9213724136 4.1601948738 4.1346964836 664 1305031124.2825551033 0.0886362046 0.0478720850 0.1139895469 0.0170862486 1.9981980000 0.9690110000 0.4047260000 0.0000040000 0.6128680000 0.0073340000 110908124 0 1785708544 3.9200689793 4.1570067406 4.1355762482 665 1305031124.3167819977 0.0828951225 0.0479247512 0.1139895469 0.0170922296 2.7066430000 0.9720240000 0.3656810000 0.1140610000 0.6118910000 0.6386440000 110910342 0 1787240448 3.9131729603 4.1484932899 4.1342296600 666 1305031124.3503708839 0.0802833289 0.0479733376 0.1139895469 0.0170847315 1.8411990000 0.9604860000 0.2526360000 0.0000050000 0.6164850000 0.0073140000 110912528 0 1784573952 3.9156596661 4.1418771744 4.1360397339 667 1305031124.3824319839 0.0760309100 0.0480154030 0.1139895469 0.0170759226 2.1476740000 0.9632650000 0.4392940000 0.1137570000 0.6197560000 0.0073150000 110914746 0 1786097664 3.9173102379 4.1356639862 4.1363563538 668 1305031124.4185550213 0.0709513128 0.0480497382 0.1139895469 0.0170786053 1.9429680000 0.9758880000 0.3312550000 0.0000040000 0.6241420000 0.0073520000 110917028 0 1788002304 3.9212145805 4.1257944107 4.1367211342 669 1305031124.4502561092 0.0683669597 0.0480801077 0.1139895469 0.0170660033 2.7878300000 0.9671640000 0.4411670000 0.1137160000 0.6205270000 0.6409940000 110919150 0 1784946688 3.9200294018 4.1166157722 4.1373200417 670 1305031124.4801259041 0.0639269501 0.0481037597 0.1139895469 0.0170540664 2.0475800000 0.9783790000 0.4396250000 0.0000040000 0.6178910000 0.0073870000 110921336 0 1786343424 3.9212121964 4.1090426445 4.1371269226 671 1305031124.5167369843 0.0567174293 0.0481165968 0.1139895469 0.0170419620 2.0420470000 0.9717810000 0.3283780000 0.1137380000 0.6163200000 0.0074510000 110923586 0 1785581568 3.9231359959 4.1011915207 4.1377277374 672 1305031124.5505030155 0.0526660085 0.0481233667 0.1139895469 0.0170294475 1.8201900000 0.9671040000 0.2172930000 0.0000030000 0.6239940000 0.0073110000 110925804 0 1786978304 3.9217696190 4.0940093994 4.1391754150 673 1305031124.5846059322 0.0507958010 0.0481273377 0.1139895469 0.0170173179 2.8112460000 0.9926080000 0.4409430000 0.1137500000 0.6203670000 0.6391780000 110928022 0 1784438784 3.9226021767 4.0840597153 4.1412997246 674 1305031124.6176528931 0.0452044532 0.0481230010 0.1139895469 0.0170191955 2.0401830000 0.9635890000 0.4409140000 0.0000040000 0.6239040000 0.0073470000 110930240 0 1785962496 3.9231564999 4.0732951164 4.1437778473 675 1305031124.6513130665 0.0420530029 0.0481140084 0.1139895469 0.0170124375 1.9437550000 0.9635680000 0.2178780000 0.1137740000 0.6368360000 0.0072790000 110932426 0 1787867136 3.9233064651 4.0648341179 4.1465191841 676 1305031124.6854729652 0.0408569239 0.0481032731 0.1139895469 0.0170043138 2.0571350000 0.9534640000 0.4389570000 0.0000030000 0.6529580000 0.0073080000 110934644 0 1784233984 3.9246325493 4.0536394119 4.1495866776 677 1305031124.7157909870 0.0339103974 0.0480823087 0.1139895469 0.0169928949 2.6515840000 0.9552880000 0.2211740000 0.1138890000 0.6693800000 0.6874350000 110936830 0 1785835520 3.9255359173 4.0447931290 4.1525349617 678 1305031124.7499411106 0.0318225957 0.0480583269 0.1139895469 0.0169811143 2.0670270000 0.9431970000 0.4302810000 0.0000040000 0.6819500000 0.0072820000 110939048 0 1787613184 3.9245691299 4.0352878571 4.1562318802 679 1305031124.7851779461 0.0316091888 0.0480341013 0.1139895469 0.0169692190 2.2101470000 0.9465950000 0.4410870000 0.1142550000 0.6965180000 0.0073170000 110941266 0 1784819712 3.9242160320 4.0237770081 4.1604752541 680 1305031124.8166410923 0.0256292205 0.0480011530 0.1139895469 0.0169578911 1.8732660000 0.9379880000 0.2125910000 0.0000030000 0.7110440000 0.0072520000 110943452 0 1786216448 3.9227838516 4.0149297714 4.1651549339 681 1305031124.8505589962 0.0250943955 0.0479675160 0.1139895469 0.0169457174 2.7764630000 0.9440380000 0.2509800000 0.1142650000 0.7193450000 0.7433910000 110945670 0 1788129280 3.9225485325 4.0045800209 4.1706867218 682 1305031124.8835940361 0.0251069609 0.0479339962 0.1139895469 0.0169440595 1.9361670000 0.9453320000 0.2500980000 0.0000060000 0.7290080000 0.0073820000 110947856 0 1784700928 3.9246010780 3.9930145741 4.1762828827 683 1305031124.9187700748 0.0203041676 0.0478935425 0.1139895469 0.0169430312 2.0374570000 0.9353880000 0.2459180000 0.1138670000 0.7306680000 0.0072540000 110950106 0 1786224640 3.9243171215 3.9854247570 4.1822099686 684 1305031124.9507479668 0.0212472882 0.0478545860 0.1139895469 0.0169322311 2.1200870000 0.9597260000 0.4210560000 0.0000050000 0.7276370000 0.0073210000 110952260 0 1787994112 3.9220056534 3.9770858288 4.1884016991 685 1305031124.9864599705 0.0242814273 0.0478201726 0.1139895469 0.0169662099 2.7670660000 0.9315900000 0.2484620000 0.1132970000 0.7245880000 0.7447330000 110954510 0 1784692736 3.9232757092 3.9608623981 4.1943278313 686 1305031125.0194671154 0.0274418052 0.0477904666 0.1139895469 0.0169567288 2.1066820000 0.9310760000 0.4242240000 0.0000050000 0.7396130000 0.0072230000 110956728 0 1786089472 3.9215219021 3.9495756626 4.2002086639 687 1305031125.0507979393 0.0243980847 0.0477564165 0.1139895469 0.0169563223 2.1182030000 0.9208730000 0.3118210000 0.1136190000 0.7600760000 0.0072870000 110958882 0 1787867136 3.9213619232 3.9458463192 4.2053675652 688 1305031125.0834798813 0.0238317642 0.0477216423 0.1139895469 0.0169456874 1.9425180000 0.9191980000 0.2382370000 0.0000050000 0.7731720000 0.0072540000 110961100 0 1785073664 3.9217684269 3.9383511543 4.2106428146 689 1305031125.1190290451 0.0254901126 0.0476893759 0.1139895469 0.0169387358 2.8960220000 0.9336300000 0.2788250000 0.1132760000 0.7744450000 0.7912840000 110963350 0 1786597376 3.9193992615 3.9270281792 4.2155461311 690 1305031125.1510369778 0.0252574291 0.0476568659 0.1139895469 0.0169304457 1.9686170000 0.9116240000 0.2435150000 0.0000050000 0.8017230000 0.0071900000 110965504 0 1784692736 3.9199411869 3.9187657833 4.2194766998 691 1305031125.1870639324 0.0233798660 0.0476217327 0.1139895469 0.0169314088 2.0790770000 0.9121760000 0.2387710000 0.1132560000 0.8032180000 0.0071870000 110967786 0 1786089472 3.9169893265 3.9156501293 4.2235746384 692 1305031125.2190179825 0.0253584776 0.0475895604 0.1139895469 0.0169231776 1.9506830000 0.9029550000 0.2385290000 0.0000050000 0.7974700000 0.0071640000 110969972 0 1787994112 3.9146635532 3.9063699245 4.2271161079 693 1305031125.2506420612 0.0289471224 0.0475626593 0.1139895469 0.0169152479 2.8971150000 0.9176270000 0.2409270000 0.1125610000 0.8018520000 0.8196590000 110972126 0 1784819712 3.9133923054 3.8935177326 4.2303028107 694 1305031125.2863960266 0.0294767749 0.0475365990 0.1139895469 0.0169052872 1.9777870000 0.9066870000 0.2399680000 0.0000040000 0.8193870000 0.0071610000 110974376 0 1786089472 3.9101645947 3.8875608444 4.2334775925 695 1305031125.3191399574 0.0291304030 0.0475101153 0.1139895469 0.0168968528 2.1749610000 0.9189620000 0.3071120000 0.1125410000 0.8246570000 0.0071980000 110976594 0 1787994112 3.9100809097 3.8814582825 4.2364950180 696 1305031125.3488988876 0.0332978927 0.0474896954 0.1139895469 0.0168864690 2.0153690000 0.8938440000 0.2740020000 0.0000050000 0.8356680000 0.0071620000 110978716 0 1784565760 3.9055240154 3.8728065491 4.2390975952 697 1305031125.3867919445 0.0321115777 0.0474676321 0.1139895469 0.0168862076 2.9915830000 0.8956760000 0.2727010000 0.1179000000 0.8418190000 0.8589880000 110981030 0 1786224640 3.9050295353 3.8709149361 4.2425498962 698 1305031125.4195740223 0.0333490074 0.0474474048 0.1139895469 0.0168756760 2.1964670000 0.9392490000 0.4127730000 0.0000040000 0.8326100000 0.0072500000 110983216 0 1788129280 3.9052197933 3.8639671803 4.2456741333 699 1305031125.4512319565 0.0354375467 0.0474302234 0.1139895469 0.0168736985 2.2583740000 0.9013510000 0.4133840000 0.1123360000 0.8195710000 0.0072040000 110985402 0 1784565760 3.9024856091 3.8596360683 4.2486343384 700 1305031125.4869990349 0.0378088616 0.0474164786 0.1139895469 0.0168738993 1.9750080000 0.8846190000 0.2680850000 0.0000040000 0.8104780000 0.0071530000 110987652 0 1786089472 3.9041178226 3.8488402367 4.2506599426 701 1305031125.5193541050 0.0387398936 0.0474041011 0.1139895469 0.0168685503 3.0588030000 0.8936410000 0.4038710000 0.1118250000 0.8163150000 0.8285720000 110989870 0 1787994112 3.9027543068 3.8458671570 4.2531747818 702 1305031125.5510499477 0.0382020287 0.0473909927 0.1139895469 0.0168587363 2.0013720000 0.8849420000 0.3000440000 0.0000040000 0.8047160000 0.0070810000 110992024 0 1784692736 3.9041004181 3.8427841663 4.2546234131 703 1305031125.5853030682 0.0378967859 0.0473774875 0.1139895469 0.0168468443 2.1030320000 0.9090500000 0.2683050000 0.1113490000 0.8026210000 0.0072190000 110994242 0 1786089472 3.9055535793 3.8400230408 4.2555432320 704 1305031125.6178700924 0.0414180681 0.0473690224 0.1139895469 0.0168559857 1.9920800000 0.8847180000 0.3010320000 0.0000040000 0.7946360000 0.0071230000 110996460 0 1787867136 3.9042832851 3.8342285156 4.2551236153 705 1305031125.6505749226 0.0449647158 0.0473656120 0.1139895469 0.0168490424 2.8988830000 0.8815630000 0.2676940000 0.1112760000 0.8051320000 0.8286520000 110998646 0 1784692736 3.9028854370 3.8303623199 4.2533292770 706 1305031125.6846020222 0.0433547571 0.0473599309 0.1139895469 0.0168480680 2.0023270000 0.8954660000 0.2715630000 0.0000050000 0.8236230000 0.0071210000 111000832 0 1785962496 3.9026696682 3.8345897198 4.2512512207 707 1305031125.7156689167 0.0418810099 0.0473521814 0.1139895469 0.0168655285 2.1223040000 0.8924750000 0.2693180000 0.1117850000 0.8369540000 0.0072290000 111003018 0 1787867136 3.9041678905 3.8375082016 4.2491831779 708 1305031125.7512919903 0.0390641354 0.0473404751 0.1139895469 0.0168647225 2.0957130000 0.8922430000 0.3386850000 0.0000040000 0.8530500000 0.0071750000 111005268 0 1784565760 3.9067440033 3.8431265354 4.2460017204 709 1305031125.7868049145 0.0358934477 0.0473243298 0.1139895469 0.0168589066 2.9657930000 0.8868040000 0.2352800000 0.1121200000 0.8548820000 0.8720050000 111007518 0 1785962496 3.9068496227 3.8526768684 4.2436590195 710 1305031125.8194499016 0.0343490094 0.0473060547 0.1139895469 0.0168504532 2.1597430000 0.8948660000 0.4021500000 0.0000040000 0.8509340000 0.0072070000 111009736 0 1788121088 3.9087407589 3.8590517044 4.2402172089 711 1305031125.8547739983 0.0322100408 0.0472848226 0.1139895469 0.0168432811 2.2513940000 0.9159190000 0.3729660000 0.1122880000 0.8383350000 0.0072330000 111011922 0 1784320000 3.9091243744 3.8681919575 4.2366971970 712 1305031125.8866450787 0.0368853584 0.0472702166 0.1139895469 0.0168462446 2.1391580000 0.8884630000 0.4069370000 0.0000040000 0.8319060000 0.0071090000 111014140 0 1785843712 3.9043445587 3.8759675026 4.2317366600 713 1305031125.9193339348 0.0350924395 0.0472531370 0.1139895469 0.0168446941 2.9285400000 0.9111530000 0.2405760000 0.1122030000 0.8208630000 0.8387810000 111016358 0 1787740160 3.9052014351 3.8853139877 4.2294049263 714 1305031125.9552519321 0.0384550728 0.0472408148 0.1139895469 0.0168434840 1.9556280000 0.9263590000 0.2057210000 0.0000040000 0.8116040000 0.0073350000 111018576 0 1784819712 3.9043290615 3.8898658752 4.2255659103 715 1305031125.9870939255 0.0391777083 0.0472295377 0.1139895469 0.0168361240 2.0868010000 0.9359320000 0.2105530000 0.1128300000 0.8156220000 0.0072340000 111020762 0 1786089472 3.9062595367 3.8991074562 4.2224392891 716 1305031126.0195720196 0.0365618691 0.0472146387 0.1139895469 0.0168285392 2.0840600000 0.9351200000 0.3152000000 0.0000060000 0.8217880000 0.0073270000 111022980 0 1787994112 3.9071114063 3.9120874405 4.2201261520 717 1305031126.0550379753 0.0325768143 0.0471942234 0.1139895469 0.0168229169 2.9455520000 0.9246590000 0.2771500000 0.1130910000 0.8036730000 0.8222630000 111025198 0 1784692736 3.9122412205 3.9241027832 4.2180700302 718 1305031126.0870759487 0.0343925431 0.0471763937 0.1139895469 0.0168133331 2.1383000000 0.9266290000 0.4171940000 0.0000050000 0.7825770000 0.0072740000 111027384 0 1786089472 3.9155464172 3.9354670048 4.2155961990 719 1305031126.1194519997 0.0369409211 0.0471621580 0.1139895469 0.0168033146 2.0604310000 0.9475710000 0.2419220000 0.1128990000 0.7459170000 0.0072440000 111029602 0 1787994112 3.9149451256 3.9446461201 4.2130346298 720 1305031126.1549999714 0.0357925929 0.0471463669 0.1139895469 0.0167954810 2.0170380000 0.9282760000 0.3494750000 0.0000050000 0.7273130000 0.0072240000 111031788 0 1784692736 3.9184904099 3.9561221600 4.2107000351 721 1305031126.1871740818 0.0396176204 0.0471359249 0.1139895469 0.0167927356 2.7366690000 0.9396710000 0.2455550000 0.1129580000 0.7078320000 0.7258690000 111034006 0 1786089472 3.9185538292 3.9687271118 4.2090706825 722 1305031126.2194728851 0.0432077721 0.0471304842 0.1139895469 0.0167962261 1.9844320000 0.9328450000 0.3479010000 0.0000050000 0.6916670000 0.0072330000 111036224 0 1787994112 3.9204115868 3.9767985344 4.2066855431 723 1305031126.2552359104 0.0434659533 0.0471254157 0.1139895469 0.0167957631 1.9860970000 0.9375020000 0.2459280000 0.1127360000 0.6778500000 0.0073080000 111038474 0 1784819712 3.9224796295 3.9884161949 4.2041220665 724 1305031126.2871050835 0.0478894971 0.0471264711 0.1139895469 0.0167869050 1.9402820000 0.9457040000 0.3226120000 0.0000040000 0.6599430000 0.0073190000 111040628 0 1786089472 3.9230718613 3.9996216297 4.2013411522 725 1305031126.3197870255 0.0483202450 0.0471281176 0.1139895469 0.0167796332 2.7491740000 0.9548200000 0.3843140000 0.1127050000 0.6394240000 0.6531230000 111042846 0 1788129280 3.9236185551 4.0115857124 4.1991829872 726 1305031126.3554151058 0.0509456582 0.0471333760 0.1139895469 0.0167708349 2.0042300000 0.9540750000 0.4314170000 0.0000050000 0.6067350000 0.0072900000 111045064 0 1784446976 3.9234292507 4.0201301575 4.1967101097 727 1305031126.3874828815 0.0554482639 0.0471448132 0.1139895469 0.0167634919 1.8906770000 0.9660080000 0.2140060000 0.1126650000 0.5858770000 0.0072910000 111047282 0 1785843712 3.9224786758 4.0298099518 4.1938543320 728 1305031126.4197928905 0.0568285398 0.0471581150 0.1139895469 0.0167532386 1.7996710000 0.9680230000 0.2517690000 0.0000060000 0.5677430000 0.0073840000 111049436 0 1787867136 3.9204897881 4.0394458771 4.1914753914 729 1305031126.4553799629 0.0604527518 0.0471763519 0.1139895469 0.0167549453 2.4419070000 0.9592170000 0.2492250000 0.1127350000 0.5485570000 0.5672690000 111051654 0 1784438784 3.9217562675 4.0457763672 4.1891698837 730 1305031126.4903860092 0.0664908513 0.0472028101 0.1139895469 0.0167523630 1.9566160000 0.9663830000 0.4371950000 0.0000050000 0.5408540000 0.0073310000 111053904 0 1785835520 3.9213321209 4.0532364845 4.1862592697 731 1305031126.5223209858 0.0660518259 0.0472285953 0.1139895469 0.0167507487 1.9678370000 0.9680030000 0.3315230000 0.1140750000 0.5421990000 0.0073810000 111056090 0 1787740160 3.9223966599 4.0638685226 4.1837143898 732 1305031126.5582089424 0.0695701838 0.0472591166 0.1139895469 0.0167477158 1.7794920000 0.9671710000 0.2519150000 0.0000050000 0.5482520000 0.0072990000 111058340 0 1784692736 3.9238159657 4.0731587410 4.1819572449 733 1305031126.5901761055 0.0726061463 0.0472936965 0.1139895469 0.0167368651 2.6452150000 0.9719490000 0.4386910000 0.1126470000 0.5488870000 0.5681920000 111060526 0 1786089472 3.9224104881 4.0792069435 4.1810851097 734 1305031126.6186869144 0.0737772062 0.0473297775 0.1139895469 0.0167260267 1.9618400000 0.9637500000 0.4369630000 0.0000040000 0.5491120000 0.0073020000 111062648 0 1787994112 3.9223015308 4.0864920616 4.1795644760 735 1305031126.6544740200 0.0778878182 0.0473713531 0.1139895469 0.0167278939 1.8930030000 0.9633160000 0.2537410000 0.1130200000 0.5506770000 0.0073310000 111064930 0 1784692736 3.9235353470 4.0893921852 4.1790752411 736 1305031126.6900219917 0.0824416280 0.0474190029 0.1139895469 0.0167177839 1.8459360000 0.9536610000 0.3270890000 0.0000040000 0.5531550000 0.0072720000 111067180 0 1786089472 3.9235386848 4.0933842659 4.1773304939 737 1305031126.7157700062 0.0819762275 0.0474658920 0.1139895469 0.0167073758 2.5033210000 0.9551710000 0.2913590000 0.1130640000 0.5606570000 0.5782070000 111069238 0 1788121088 3.9251775742 4.0997262001 4.1751518250 738 1305031126.7553739548 0.0846277997 0.0475162469 0.1139895469 0.0166975683 1.8746630000 0.9457540000 0.3585330000 0.0000050000 0.5582130000 0.0072670000 111071552 0 1784438784 3.9239439964 4.1014337540 4.1729745865 739 1305031126.7875649929 0.0845153555 0.0475663133 0.1139895469 0.0166887230 2.0303020000 0.9453840000 0.3971660000 0.1130160000 0.5626360000 0.0072650000 111073738 0 1785835520 3.9252963066 4.1067929268 4.1697940826 740 1305031126.8199288845 0.0841609836 0.0476157656 0.1139895469 0.0166804593 1.8559920000 0.9547130000 0.3234820000 0.0000040000 0.5657860000 0.0072660000 111075924 0 1787740160 3.9265868664 4.1109547615 4.1674160957 741 1305031126.8583779335 0.0861130580 0.0476677187 0.1139895469 0.0166694618 2.6620780000 0.9592810000 0.4331190000 0.1128420000 0.5643390000 0.5876460000 111078238 0 1784819712 3.9279434681 4.1132392883 4.1661825180 742 1305031126.8881540298 0.0867727697 0.0477204210 0.1139895469 0.0166587300 1.9687830000 0.9577030000 0.4324980000 0.0000040000 0.5663040000 0.0072550000 111080392 0 1786097664 3.9279637337 4.1146345139 4.1643762589 743 1305031126.9194090366 0.0865992680 0.0477727478 0.1139895469 0.0166482805 1.9302240000 0.9514080000 0.2860890000 0.1127700000 0.5679050000 0.0072160000 111082546 0 1788002304 3.9296448231 4.1156902313 4.1628251076 744 1305031126.9555010796 0.0859439820 0.0478240532 0.1139895469 0.0166402973 1.9623330000 0.9436760000 0.4336380000 0.0000050000 0.5728650000 0.0072330000 111084796 0 1784598528 3.9296472073 4.1172809601 4.1612577438 745 1305031126.9873158932 0.0872419178 0.0478769631 0.1139895469 0.0166302416 2.6557610000 0.9466260000 0.4315240000 0.1129600000 0.5682180000 0.5915050000 111087014 0 1785978880 3.9294004440 4.1160683632 4.1603503227 746 1305031127.0195240974 0.0870492980 0.0479294730 0.1139895469 0.0166197947 1.9618850000 0.9474790000 0.4329560000 0.0000050000 0.5692040000 0.0072050000 111089168 0 1787740160 3.9295191765 4.1158108711 4.1594514847 747 1305031127.0533180237 0.0853140652 0.0479795193 0.1139895469 0.0166120245 1.9272430000 0.9492170000 0.2816130000 0.1131460000 0.5711040000 0.0072380000 111091386 0 1784217600 3.9319574833 4.1170687675 4.1589775085 748 1305031127.0886490345 0.0835725516 0.0480271035 0.1139895469 0.0166041806 1.9629230000 0.9413900000 0.4375290000 0.0000060000 0.5718940000 0.0072450000 111093636 0 1785708544 3.9321048260 4.1172933578 4.1590008736 749 1305031127.1209630966 0.0842146650 0.0480754180 0.1139895469 0.0166005936 2.6454770000 0.9535730000 0.4090080000 0.1132180000 0.5713120000 0.5934680000 111095790 0 1787740160 3.9310123920 4.1147036552 4.1590805054 750 1305031127.1576919556 0.0824033618 0.0481211886 0.1139895469 0.0165900813 1.9753590000 0.9568370000 0.4335590000 0.0000060000 0.5728080000 0.0073140000 111098072 0 1784692736 3.9285693169 4.1137146950 4.1582045555 751 1305031127.1875000000 0.0801239386 0.0481638021 0.1139895469 0.0165827103 2.0942500000 0.9586110000 0.4308630000 0.1129990000 0.5796060000 0.0073030000 111100226 0 1786216448 3.9293613434 4.1141858101 4.1585454941 752 1305031127.2218310833 0.0774564669 0.0482027551 0.1139895469 0.0165743914 1.9556670000 0.9400970000 0.4273600000 0.0000050000 0.5760900000 0.0072450000 111102444 0 1788121088 3.9280641079 4.1147713661 4.1581902504 753 1305031127.2597610950 0.0768025964 0.0482407363 0.1139895469 0.0165683587 2.6667820000 0.9484800000 0.4265190000 0.1134270000 0.5731150000 0.6001710000 111104726 0 1784487936 3.9262840748 4.1114406586 4.1591787338 754 1305031127.2870380878 0.0745913833 0.0482756842 0.1139895469 0.0165654902 1.9611540000 0.9530820000 0.4245410000 0.0000040000 0.5713050000 0.0072200000 111106816 0 1785995264 3.9260625839 4.1112084389 4.1596975327 755 1305031127.3204679489 0.0732171014 0.0483087191 0.1139895469 0.0165557853 2.0599130000 0.9397600000 0.4248690000 0.1128920000 0.5700990000 0.0072810000 111109034 0 1787883520 3.9251759052 4.1101565361 4.1608576775 756 1305031127.3534069061 0.0753751770 0.0483445213 0.1139895469 0.0165510382 1.9731110000 0.9585190000 0.4328350000 0.0000040000 0.5693120000 0.0072090000 111111220 0 1784573952 3.9259197712 4.1043162346 4.1628489494 757 1305031127.3837130070 0.0729849860 0.0483770715 0.1139895469 0.0165430239 2.6629050000 0.9557310000 0.4326930000 0.1129710000 0.5680690000 0.5885180000 111113406 0 1786224640 3.9258949757 4.1044096947 4.1638760567 758 1305031127.4196500778 0.0704585388 0.0484062027 0.1139895469 0.0165336488 1.7703780000 0.9399720000 0.2454710000 0.0000040000 0.5725660000 0.0072080000 111115624 0 1787908096 3.9264419079 4.1040806770 4.1654086113 759 1305031127.4542460442 0.0714576915 0.0484365736 0.1139895469 0.0165340280 2.0762390000 0.9559860000 0.4288920000 0.1129070000 0.5660680000 0.0072300000 111117874 0 1784844288 3.9261927605 4.1001791954 4.1671185493 760 1305031127.4872000217 0.0692555979 0.0484639670 0.1139895469 0.0165359972 1.8395200000 0.9434850000 0.3188150000 0.0000040000 0.5648310000 0.0072550000 111120060 0 1786232832 3.9269323349 4.1003184319 4.1685409546 761 1305031127.5218999386 0.0690537542 0.0484910233 0.1139895469 0.0165256486 2.6576570000 0.9589730000 0.4348420000 0.1127910000 0.5631560000 0.5827500000 111122310 0 1788137472 3.9268603325 4.0999345779 4.1706042290 762 1305031127.5537250042 0.0713732466 0.0485210524 0.1139895469 0.0165245559 1.8126700000 0.9518710000 0.2869190000 0.0000040000 0.5614380000 0.0073590000 111124464 0 1785233408 3.9258100986 4.0956726074 4.1724967957 763 1305031127.5866320133 0.0705177486 0.0485498816 0.1139895469 0.0165160648 2.0688950000 0.9488810000 0.4340470000 0.1127580000 0.5609150000 0.0072320000 111126682 0 1786724352 3.9249291420 4.0953383446 4.1734247208 764 1305031127.6206569672 0.0695327520 0.0485773461 0.1139895469 0.0165059541 1.8338280000 0.9405810000 0.3202650000 0.0000040000 0.5606600000 0.0072040000 111128900 0 1784725504 3.9269919395 4.0958733559 4.1750626564 765 1305031127.6546559334 0.0710249245 0.0486066894 0.1139895469 0.0164967206 2.4476130000 0.9369350000 0.2500090000 0.1126850000 0.5588100000 0.5840500000 111131086 0 1786216448 3.9268553257 4.0934691429 4.1762976646 766 1305031127.6871099472 0.0710219592 0.0486359521 0.1139895469 0.0164860466 1.8417460000 0.9536290000 0.3158520000 0.0000050000 0.5597750000 0.0072810000 111133304 0 1788121088 3.9282777309 4.0915675163 4.1767096519 767 1305031127.7232100964 0.0694914460 0.0486631431 0.1139895469 0.0164775963 1.9093820000 0.9413880000 0.2823390000 0.1127730000 0.5603380000 0.0072950000 111135554 0 1785090048 3.9279623032 4.0929417610 4.1773214340 768 1305031127.7546939850 0.0705989972 0.0486917054 0.1139895469 0.0164678571 1.9528470000 0.9436590000 0.4362740000 0.0000040000 0.5603850000 0.0073760000 111137708 0 1786724352 3.9272325039 4.0910248756 4.1783232689 769 1305031127.7876410484 0.0706660524 0.0487202807 0.1139895469 0.0164621140 2.6324480000 0.9500200000 0.4251100000 0.1129370000 0.5592860000 0.5799890000 111139958 0 1784565760 3.9263095856 4.0890893936 4.1780691147 770 1305031127.8201279640 0.0691548660 0.0487468191 0.1139895469 0.0164531703 1.9459840000 0.9432350000 0.4293470000 0.0000040000 0.5609190000 0.0072830000 111142112 0 1786216448 3.9259192944 4.0898299217 4.1778526306 771 1305031127.8551321030 0.0690916404 0.0487732067 0.1139895469 0.0164425153 2.0455700000 0.9355400000 0.4253020000 0.1126570000 0.5596330000 0.0071800000 111144330 0 1787899904 3.9260132313 4.0892696381 4.1781573296 772 1305031127.8871219158 0.0694473162 0.0487999866 0.1139895469 0.0164331264 1.9503960000 0.9402660000 0.4381390000 0.0000040000 0.5593730000 0.0072120000 111146548 0 1785098240 3.9253556728 4.0877680779 4.1782484055 773 1305031127.9225599766 0.0691172257 0.0488262702 0.1139895469 0.0164248853 2.4048970000 0.9405610000 0.2091030000 0.1126380000 0.5588440000 0.5785880000 111148798 0 1786605568 3.9236083031 4.0880460739 4.1785807610 774 1305031127.9550879002 0.0684893578 0.0488516747 0.1139895469 0.0164155248 1.9438920000 0.9329510000 0.4364060000 0.0000040000 0.5617060000 0.0071930000 111150984 0 1785462784 3.9251484871 4.0884294510 4.1797609329 775 1305031127.9870929718 0.0680964887 0.0488765067 0.1139895469 0.0164050899 1.9873990000 0.9488480000 0.3537510000 0.1128270000 0.5594490000 0.0073230000 111153170 0 1786757120 3.9252777100 4.0878071785 4.1812324524 776 1305031128.0217759609 0.0678564683 0.0489009654 0.1139895469 0.0163976041 1.9283330000 0.9331870000 0.4255580000 0.0000050000 0.5569820000 0.0072780000 111155420 0 1784614912 3.9249880314 4.0877213478 4.1830816269 777 1305031128.0557179451 0.0681155547 0.0489256946 0.1139895469 0.0163900729 2.5989040000 0.9554130000 0.3935830000 0.1127980000 0.5585770000 0.5733380000 111157606 0 1786122240 3.9247238636 4.0864048004 4.1853575706 778 1305031128.0872058868 0.0700852573 0.0489528920 0.1139895469 0.0163814908 1.7914710000 0.9445250000 0.2852630000 0.0000050000 0.5491030000 0.0072540000 111159792 0 1788010496 3.9247541428 4.0831990242 4.1872415543 779 1305031128.1247460842 0.0699366480 0.0489798288 0.1139895469 0.0163721193 2.0264740000 0.9371480000 0.4164190000 0.1124720000 0.5479790000 0.0072590000 111162074 0 1784614912 3.9255073071 4.0824842453 4.1886229515 780 1305031128.1577820778 0.0699261054 0.0490066830 0.1139895469 0.0163630751 1.7462980000 0.9385820000 0.2492380000 0.0000040000 0.5459480000 0.0072800000 111164292 0 1786105856 3.9272449017 4.0815944672 4.1905245781 781 1305031128.1872210503 0.0712969899 0.0490352237 0.1139895469 0.0163560895 2.5337810000 0.9496670000 0.3582870000 0.1126210000 0.5442030000 0.5637580000 111166414 0 1788010496 3.9270448685 4.0788364410 4.1912546158 782 1305031128.2254419327 0.0701117069 0.0490621758 0.1139895469 0.0163507589 1.9343710000 0.9496200000 0.4271890000 0.0000040000 0.5447500000 0.0072150000 111168696 0 1785090048 3.9269886017 4.0794024467 4.1914443970 783 1305031128.2560069561 0.0694125071 0.0490881660 0.1139895469 0.0163405743 1.8471140000 0.9406110000 0.2385340000 0.1125150000 0.5430170000 0.0072610000 111170850 0 1786470400 3.9268276691 4.0797019005 4.1922039986 784 1305031128.2912750244 0.0704053193 0.0491153562 0.1139895469 0.0163336318 1.8988210000 0.9397530000 0.4032100000 0.0000040000 0.5432540000 0.0072750000 111173100 0 1785073664 3.9266152382 4.0779962540 4.1925711632 785 1305031128.3241701126 0.0696233511 0.0491414811 0.1139895469 0.0163239636 2.5907740000 0.9432920000 0.4232070000 0.1124270000 0.5437310000 0.5628970000 111175286 0 1786597376 3.9282755852 4.0780858994 4.1925144196 786 1305031128.3552060127 0.0691807941 0.0491669764 0.1139895469 0.0163144629 1.8113160000 0.9364090000 0.3192210000 0.0000040000 0.5431980000 0.0072310000 111177472 0 1785835520 3.9272458553 4.0781965256 4.1924953461 787 1305031128.3913969994 0.0694033355 0.0491926897 0.1139895469 0.0163042602 2.0398770000 0.9319570000 0.4392460000 0.1124670000 0.5436010000 0.0071880000 111179722 0 1787232256 3.9255874157 4.0772080421 4.1924114227 788 1305031128.4236090183 0.0697845146 0.0492188214 0.1139895469 0.0162940361 1.8499650000 0.9410680000 0.3534030000 0.0000040000 0.5430480000 0.0072180000 111181908 0 1785327616 3.9250845909 4.0760235786 4.1922984123 789 1305031128.4554989338 0.0686077923 0.0492433955 0.1139895469 0.0162856784 2.4829980000 0.9359970000 0.3165680000 0.1125060000 0.5443890000 0.5681910000 111184094 0 1787256832 3.9242944717 4.0766081810 4.1919021606 790 1305031128.4895229340 0.0691320524 0.0492685710 0.1139895469 0.0162759144 1.9239530000 0.9401550000 0.4281180000 0.0000040000 0.5430320000 0.0072810000 111186344 0 1784717312 3.9240624905 4.0753440857 4.1921563148 791 1305031128.5236039162 0.0686714947 0.0492931006 0.1139895469 0.0162658373 1.8873230000 0.9367790000 0.2820080000 0.1124990000 0.5433580000 0.0072690000 111188530 0 1786478592 3.9241783619 4.0747542381 4.1919851303 792 1305031128.5556390285 0.0683803037 0.0493172006 0.1139895469 0.0162572825 1.7450030000 0.9388870000 0.2499840000 0.0000050000 0.5435170000 0.0072600000 111190716 0 1785843712 3.9255599976 4.0740733147 4.1919507980 793 1305031128.5914599895 0.0691784322 0.0493422463 0.1139895469 0.0162479101 2.5936770000 0.9454600000 0.4286740000 0.1124370000 0.5412360000 0.5605320000 111192966 0 1787232256 3.9234814644 4.0724158287 4.1916527748 794 1305031128.6233680248 0.0690041557 0.0493670094 0.1139895469 0.0162383852 1.9199230000 0.9387520000 0.4206810000 0.0000040000 0.5479110000 0.0072140000 111195152 0 1785344000 3.9246432781 4.0714678764 4.1913676262 795 1305031128.6555540562 0.0680021346 0.0493904499 0.1139895469 0.0162301940 2.0428990000 0.9460060000 0.4279860000 0.1125150000 0.5437230000 0.0073360000 111197338 0 1786978304 3.9248709679 4.0718173981 4.1909255981 796 1305031128.6904489994 0.0677562132 0.0494135224 0.1139895469 0.0162209131 1.9178830000 0.9310960000 0.4272310000 0.0000040000 0.5468130000 0.0072760000 111199588 0 1784819712 3.9246177673 4.0715751648 4.1906228065 797 1305031128.7229759693 0.0676223859 0.0494363692 0.1139895469 0.0162116210 2.5975450000 0.9471830000 0.4191490000 0.1126140000 0.5473460000 0.5659700000 111201774 0 1786343424 3.9241869450 4.0710287094 4.1901893616 798 1305031128.7546460629 0.0666758865 0.0494579726 0.1139895469 0.0162029520 1.9224700000 0.9355460000 0.4282420000 0.0000040000 0.5460980000 0.0072130000 111203960 0 1788121088 3.9236290455 4.0715579987 4.1895370483 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 11:46:54 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019025257 0.0019025257 0.0019025257 nan 2.5490190000 0.9149040000 0.0550070000 0.1187900000 0.0000090000 1.4408370000 113712199 0 1769353216 4.0000000000 4.0000000000 4.0000000000 2 1311867718.6768438816 0.0021839470 0.0020432363 0.0021839470 0.0015734782 1.1309110000 0.9599210000 0.0416930000 0.1183630000 0.0000020000 0.0069520000 126291456 0 1769340928 4.0000000000 4.0000000000 4.0000000000 3 1311867718.7114279270 0.0026191149 0.0022351959 0.0026191149 0.0052681777 1.0922440000 0.9159080000 0.0415300000 0.1238920000 0.0000030000 0.0069920000 126293998 0 1771102208 4.0000000000 4.0000000000 4.0000000000 4 1311867718.7410299778 0.0032201277 0.0024814288 0.0032201277 0.0047920722 2.4863750000 0.9587450000 0.0417610000 0.1184240000 1.3564480000 0.0070260000 126296448 0 1780207616 4.0000000000 4.0000000000 4.0000000000 5 1311867718.7767970562 0.0102790073 0.0040409445 0.0102790073 0.0093991090 3.9766110000 0.9036970000 0.2698750000 0.1184600000 1.3363610000 1.3443960000 126299018 0 1781850112 3.9891881943 3.9964041710 4.0032477379 6 1311867718.8094089031 0.0111378012 0.0052237540 0.0111378012 0.0088732140 2.6582810000 0.9139600000 0.4072900000 0.0000020000 1.3262170000 0.0070040000 126301860 0 1783640064 3.9877426624 3.9977478981 4.0040683746 7 1311867718.8408079147 0.0115118017 0.0061220465 0.0115118017 0.0081134332 2.7801820000 0.9222130000 0.4106400000 0.1187280000 1.3177670000 0.0070310000 126304014 0 1785278464 3.9869349003 3.9982521534 4.0042514801 8 1311867718.8767778873 0.0151338438 0.0072485212 0.0151338438 0.0077122156 2.5247590000 0.9227890000 0.2730280000 0.0000040000 1.3171390000 0.0070330000 126306264 0 1784442880 3.9833164215 3.9974730015 4.0047249794 9 1311867718.9088680744 0.0145786814 0.0080629834 0.0151338438 0.0072450385 4.0785260000 0.9277920000 0.4108650000 0.1190570000 1.3010750000 1.3156760000 126309058 0 1784291328 3.9835577011 3.9977281094 4.0048475266 10 1311867718.9438331127 0.0158578660 0.0088424717 0.0158578660 0.0068873684 2.6482820000 0.9222700000 0.4148560000 0.0000030000 1.3001860000 0.0070970000 126312620 0 1785921536 3.9821507931 3.9979395866 4.0057187080 11 1311867718.9784109592 0.0144037968 0.0093480467 0.0158578660 0.0067751901 2.7302690000 0.9143820000 0.4064120000 0.1183610000 1.2791750000 0.0070980000 126314870 0 1785032704 3.9839460850 3.9964599609 4.0056343079 12 1311867719.0091300011 0.0181386732 0.0100805989 0.0181386732 0.0067915979 2.5655580000 0.9271680000 0.3501980000 0.0000050000 1.2769900000 0.0070850000 126316992 0 1784934400 3.9798710346 3.9964549541 4.0066061020 13 1311867719.0441620350 0.0168107618 0.0105983037 0.0181386732 0.0065182474 3.9898770000 0.9230990000 0.3836820000 0.1188490000 1.2684480000 1.2909340000 126319242 0 1784188928 3.9809930325 3.9964718819 4.0068135262 14 1311867719.0776190758 0.0181683172 0.0111390190 0.0181683172 0.0063253112 2.6292440000 0.9270450000 0.4236380000 0.0000050000 1.2672710000 0.0071140000 126321460 0 1783926784 3.9796946049 3.9957447052 4.0073690414 15 1311867719.1086950302 0.0169197079 0.0115243982 0.0181683172 0.0061302204 2.7423800000 0.9299290000 0.4210700000 0.1187430000 1.2616220000 0.0070730000 126323646 0 1785667584 3.9810242653 3.9951002598 4.0075087547 16 1311867719.1437010765 0.0179919880 0.0119286226 0.0181683172 0.0059853928 2.4347690000 0.9309770000 0.2411490000 0.0000040000 1.2505790000 0.0071540000 126325864 0 1784778752 3.9795155525 3.9950368404 4.0081710815 17 1311867719.1810290813 0.0160176866 0.0121691558 0.0181683172 0.0059246600 3.9664590000 0.9214170000 0.4143690000 0.1240620000 1.2424930000 1.2599610000 126329394 0 1784561664 3.9816949368 3.9940876961 4.0082030296 18 1311867719.2127099037 0.0172360651 0.0124506507 0.0181683172 0.0057776795 2.6090440000 0.9208700000 0.4234540000 0.0000040000 1.2528520000 0.0070700000 126334204 0 1783910400 3.9803044796 3.9934408665 4.0087127686 19 1311867719.2412090302 0.0176635832 0.0127250156 0.0181683172 0.0057002891 2.5299140000 0.9301900000 0.2426690000 0.1182470000 1.2275210000 0.0071040000 126336326 0 1783672832 3.9793572426 3.9936642647 4.0092020035 20 1311867719.2779469490 0.0180318914 0.0129903594 0.0181683172 0.0058512817 2.6254900000 0.9574810000 0.4223890000 0.0000040000 1.2345070000 0.0071030000 126338544 0 1785307136 3.9785938263 3.9924757481 4.0094294548 21 1311867719.3104898930 0.0165055394 0.0131577489 0.0181683172 0.0057604161 3.9496090000 0.9316850000 0.4201450000 0.1187080000 1.2278150000 1.2463490000 126340762 0 1784561664 3.9797348976 3.9931559563 4.0097107887 22 1311867719.3413150311 0.0174339171 0.0133521202 0.0181683172 0.0056744516 2.5971360000 0.9365620000 0.4188040000 0.0000040000 1.2304490000 0.0071230000 126342948 0 1784307712 3.9786779881 3.9920084476 4.0100603104 23 1311867719.3772718906 0.0166113824 0.0134938272 0.0181683172 0.0055604622 2.5898200000 0.9293520000 0.3133350000 0.1183300000 1.2167810000 0.0072080000 126345166 0 1783537664 3.9793190956 3.9914262295 4.0097784996 24 1311867719.4105761051 0.0179838091 0.0136809098 0.0181683172 0.0055103060 2.4036250000 0.9342960000 0.2407880000 0.0000040000 1.2172660000 0.0071490000 126347384 0 1783427072 3.9776186943 3.9909486771 4.0101861954 25 1311867719.4427709579 0.0167042017 0.0138018415 0.0181683172 0.0055100745 3.9081500000 0.9174440000 0.4161210000 0.1180690000 1.2105790000 1.2417770000 126349602 0 1784905728 3.9792501926 3.9902482033 4.0101470947 26 1311867719.4787840843 0.0192787778 0.0140124929 0.0192787778 0.0054440461 2.5601870000 0.9277970000 0.4095350000 0.0000040000 1.2108400000 0.0071370000 126351820 0 1784160256 3.9768915176 3.9880101681 4.0103001595 27 1311867719.5104370117 0.0194411296 0.0142135535 0.0194411296 0.0054990990 2.6812370000 0.9300190000 0.4117080000 0.1232850000 1.2049030000 0.0071710000 126354006 0 1784053760 3.9764797688 3.9878709316 4.0101985931 28 1311867719.5449650288 0.0180841591 0.0143517894 0.0194411296 0.0054839059 2.5508580000 0.9246050000 0.4061820000 0.0000050000 1.2087710000 0.0071150000 126356224 0 1785667584 3.9764449596 3.9887762070 4.0108075142 29 1311867719.5771939754 0.0191128459 0.0145159638 0.0194411296 0.0054496093 3.8070400000 0.9209000000 0.3423170000 0.1183830000 1.1967810000 1.2235900000 126358442 0 1784926208 3.9757437706 3.9869673252 4.0107450485 30 1311867719.6112511158 0.0196607690 0.0146874573 0.0196607690 0.0054158048 2.3668440000 0.9175780000 0.2374680000 0.0000050000 1.2004580000 0.0071650000 126360660 0 1784688640 3.9747128487 3.9866485596 4.0111865997 31 1311867719.6421909332 0.0168388542 0.0147568572 0.0196607690 0.0053401309 2.6489320000 0.9088810000 0.4124060000 0.1182290000 1.1973920000 0.0071280000 126362814 0 1783926784 3.9771244526 3.9875679016 4.0113749504 32 1311867719.6770479679 0.0178507920 0.0148535427 0.0196607690 0.0052703529 2.4926790000 0.9359540000 0.3392840000 0.0000050000 1.2061720000 0.0070550000 126365064 0 1783783424 3.9763216972 3.9863836765 4.0119290352 33 1311867719.7107939720 0.0180364903 0.0149499956 0.0196607690 0.0052018500 3.8622460000 0.9062130000 0.4084550000 0.1182950000 1.1968410000 1.2283430000 126369810 0 1785413632 3.9755866528 3.9866964817 4.0126104355 34 1311867719.7442650795 0.0174866896 0.0150246043 0.0196607690 0.0051528119 2.4484780000 0.9145230000 0.3112480000 0.0000040000 1.2105490000 0.0071640000 126377244 0 1784688640 3.9754452705 3.9876160622 4.0135178566 35 1311867719.7861878872 0.0186792649 0.0151290231 0.0196607690 0.0050840126 2.5528810000 0.9215700000 0.3052790000 0.1184330000 1.1962370000 0.0071490000 126379622 0 1784434688 3.9743959904 3.9866409302 4.0141439438 36 1311867719.8099169731 0.0185912792 0.0152251969 0.0196607690 0.0050272926 2.5777140000 0.9533190000 0.4126160000 0.0000030000 1.1996360000 0.0071110000 126381648 0 1783517184 3.9745750427 3.9862301350 4.0144400597 37 1311867719.8454990387 0.0191425029 0.0153310701 0.0196607690 0.0050010082 3.8553350000 0.9163680000 0.4148810000 0.1185340000 1.1819910000 1.2192530000 126383898 0 1783418880 3.9745960236 3.9849770069 4.0145130157 38 1311867719.8771090508 0.0189240780 0.0154256229 0.0196607690 0.0049357317 2.5357500000 0.9184420000 0.4214620000 0.0000030000 1.1844710000 0.0071740000 126386084 0 1785180160 3.9744987488 3.9848001003 4.0147175789 39 1311867719.9114089012 0.0185734667 0.0155063368 0.0196607690 0.0049457966 2.6258630000 0.9215790000 0.3846430000 0.1183590000 1.1890890000 0.0071610000 126388334 0 1784291328 3.9736614227 3.9852950573 4.0152645111 40 1311867719.9461970329 0.0213733148 0.0156530113 0.0213733148 0.0049337965 2.5768430000 0.9611670000 0.4149700000 0.0000030000 1.1892250000 0.0071360000 126390552 0 1784164352 3.9713058472 3.9833247662 4.0159101486 41 1311867719.9807810783 0.0208442695 0.0157796273 0.0213733148 0.0048894762 3.7576220000 0.9196410000 0.3088820000 0.1189400000 1.1878330000 1.2182050000 126392770 0 1785815040 3.9724845886 3.9823627472 4.0158843994 42 1311867720.0117020607 0.0209155008 0.0159019100 0.0213733148 0.0049142354 2.5469530000 0.9311940000 0.4124660000 0.0000040000 1.1909390000 0.0072690000 126394956 0 1784942592 3.9702699184 3.9838802814 4.0166473389 43 1311867720.0452380180 0.0216199812 0.0160348884 0.0216199812 0.0048910700 2.6720270000 0.9415550000 0.4131950000 0.1187900000 1.1870490000 0.0071950000 126397142 0 1784799232 3.9692015648 3.9832832813 4.0169425011 44 1311867720.0772819519 0.0181528777 0.0160830246 0.0216199812 0.0048803724 2.5820400000 0.9623580000 0.4130640000 0.0000050000 1.1943200000 0.0072240000 126399360 0 1784057856 3.9733016491 3.9841411114 4.0174274445 45 1311867720.1172130108 0.0164391696 0.0160909389 0.0216199812 0.0048599757 3.8569960000 0.9014540000 0.4085570000 0.1187610000 1.1898520000 1.2339690000 126401674 0 1783398400 3.9764816761 3.9841244221 4.0178666115 46 1311867720.1451559067 0.0172737669 0.0161166525 0.0216199812 0.0048088107 2.4228220000 0.9040770000 0.3156990000 0.0000040000 1.1917210000 0.0071590000 126403764 0 1785180160 3.9755601883 3.9837658405 4.0184154510 47 1311867720.1781630516 0.0152199073 0.0160975729 0.0216199812 0.0047665350 2.6316770000 0.8959350000 0.4174430000 0.1190980000 1.1870290000 0.0071450000 126405950 0 1784422400 3.9777271748 3.9851949215 4.0188760757 48 1311867720.2094950676 0.0165804606 0.0161076330 0.0216199812 0.0047656805 2.5651270000 0.9377680000 0.4241770000 0.0000040000 1.1914870000 0.0073730000 126408136 0 1783689216 3.9740736485 3.9858856201 4.0197796822 49 1311867720.2421469688 0.0135671124 0.0160557857 0.0216199812 0.0047680545 3.8508850000 0.9061870000 0.4055000000 0.1189130000 1.1817650000 1.2342670000 126410354 0 1785278464 3.9786221981 3.9870495796 4.0199761391 50 1311867720.2770779133 0.0156953726 0.0160485774 0.0216199812 0.0047638424 2.5180700000 0.9087770000 0.4126000000 0.0000040000 1.1845230000 0.0071310000 126412572 0 1784422400 3.9761381149 3.9860982895 4.0211930275 51 1311867720.3094570637 0.0125912968 0.0159807876 0.0216199812 0.0047374240 2.5736180000 0.9205170000 0.3418120000 0.1190080000 1.1808730000 0.0071130000 126414758 0 1783681024 3.9797532558 3.9882721901 4.0219068527 52 1311867720.3430728912 0.0129760262 0.0159230037 0.0216199812 0.0047626862 2.5481010000 0.9460860000 0.4128330000 0.0000040000 1.1779170000 0.0071390000 126416976 0 1785397248 3.9796385765 3.9887793064 4.0231599808 53 1311867720.3779859543 0.0137907956 0.0158827734 0.0216199812 0.0048080572 3.8695210000 0.9311740000 0.4171040000 0.1195120000 1.1757220000 1.2209470000 126419162 0 1784549376 3.9820392132 3.9869890213 4.0234212875 54 1311867720.4096798897 0.0142978169 0.0158534223 0.0216199812 0.0048775396 2.5462100000 0.9427620000 0.4166900000 0.0000050000 1.1752210000 0.0071990000 126421348 0 1783808000 3.9816231728 3.9865357876 4.0240859985 55 1311867720.4461109638 0.0136140566 0.0158127066 0.0216199812 0.0048409133 2.5351750000 0.9238540000 0.3077150000 0.1195890000 1.1726950000 0.0071370000 126423630 0 1785438208 3.9826936722 3.9873690605 4.0244455338 56 1311867720.4799289703 0.0139096249 0.0157787230 0.0216199812 0.0048648292 2.4480890000 0.9137790000 0.3474920000 0.0000030000 1.1744860000 0.0070890000 126425848 0 1784168448 3.9845161438 3.9872117043 4.0243806839 57 1311867720.5104389191 0.0136508904 0.0157413926 0.0216199812 0.0049205475 3.6126540000 0.9199620000 0.1680640000 0.1200370000 1.1715060000 1.2286990000 126428002 0 1783406592 3.9830124378 3.9867835045 4.0242376328 58 1311867720.5467319489 0.0144285727 0.0157187578 0.0216199812 0.0050311283 2.4551850000 0.9151690000 0.3496760000 0.0000040000 1.1790370000 0.0071780000 126430284 0 1785143296 3.9862763882 3.9875509739 4.0245561600 59 1311867720.5793280602 0.0141859930 0.0156927787 0.0216199812 0.0050789639 2.4574960000 0.9166740000 0.2362480000 0.1202090000 1.1721640000 0.0071400000 126432470 0 1784295424 3.9842147827 3.9867339134 4.0250782967 60 1311867720.6121249199 0.0151693467 0.0156840548 0.0216199812 0.0050581097 2.3882260000 0.9231390000 0.2729730000 0.0000040000 1.1805450000 0.0070950000 126434656 0 1783291904 3.9852352142 3.9862277508 4.0250916481 61 1311867720.6463210583 0.0152821736 0.0156774666 0.0216199812 0.0050446271 3.8901600000 0.9178690000 0.4332440000 0.1208650000 1.1788520000 1.2351600000 126436906 0 1784918016 3.9849843979 3.9864122868 4.0255994797 62 1311867720.6798269749 0.0171530992 0.0157012671 0.0216199812 0.0050440192 2.4593320000 0.9269130000 0.3444860000 0.0000040000 1.1755970000 0.0071020000 126439060 0 1783762944 3.9879589081 3.9862368107 4.0255599022 63 1311867720.7102439404 0.0172563102 0.0157259504 0.0216199812 0.0050093858 2.6421090000 0.9222370000 0.4116830000 0.1209520000 1.1757290000 0.0071280000 126441246 0 1782665216 3.9863104820 3.9851508141 4.0256237984 64 1311867720.7451629639 0.0168452598 0.0157434396 0.0216199812 0.0050168558 2.5179930000 0.9145940000 0.4083420000 0.0000050000 1.1836720000 0.0071290000 126443464 0 1784295424 3.9857523441 3.9857149124 4.0256137848 65 1311867720.7790179253 0.0583425798 0.0163988110 0.0583425798 0.0062018495 3.8090190000 0.8975590000 0.3377390000 0.1215820000 1.1818060000 1.2660870000 126450834 0 1785925632 4.0316996574 3.9881739616 4.0336151123 66 1311867720.8115909100 0.0589457639 0.0170434618 0.0589457639 0.0061552118 2.4504380000 0.9126720000 0.3384330000 0.0000040000 1.1868870000 0.0070500000 126463516 0 1784545280 4.0314841270 3.9873993397 4.0339946747 67 1311867720.8467299938 0.0622125380 0.0177176271 0.0622125380 0.0061221168 2.6054010000 0.9084270000 0.3732450000 0.1224520000 1.1897500000 0.0070030000 126465766 0 1783808000 4.0344843864 3.9881641865 4.0344061852 68 1311867720.8813319206 0.0592153557 0.0183278878 0.0622125380 0.0061652395 2.4948790000 0.8931190000 0.4002430000 0.0000040000 1.1902220000 0.0069810000 126467984 0 1785417728 4.0310091972 3.9887137413 4.0349779129 69 1311867720.9149661064 0.0605382398 0.0189396320 0.0622125380 0.0061296917 3.9353430000 0.9305990000 0.4018080000 0.1281250000 1.1914630000 1.2779690000 126470170 0 1784041472 4.0315842628 3.9872763157 4.0353093147 70 1311867720.9500010014 0.0604909956 0.0195332229 0.0622125380 0.0060855191 2.4960470000 0.9075120000 0.3722140000 0.0000040000 1.2048340000 0.0070300000 126472388 0 1783283712 4.0312075615 3.9876277447 4.0358014107 71 1311867720.9797990322 0.0632178336 0.0201484991 0.0632178336 0.0060578051 2.6357190000 0.9018660000 0.4042880000 0.1227540000 1.1955170000 0.0070200000 126474510 0 1784889344 4.0339717865 3.9880847931 4.0356922150 72 1311867721.0093889236 0.0640607178 0.0207583911 0.0640607178 0.0060160462 2.3153200000 0.8968680000 0.2014010000 0.0000040000 1.2049180000 0.0069990000 126476664 0 1784045568 4.0346107483 3.9879126549 4.0359840393 73 1311867721.0478379726 0.0628220066 0.0213346050 0.0640607178 0.0059804993 3.9316900000 0.9030640000 0.4096040000 0.1232080000 1.2000780000 1.2912160000 126478978 0 1783308288 4.0329751968 3.9879059792 4.0359635353 74 1311867721.0794439316 0.0642507896 0.0219145534 0.0642507896 0.0059474207 2.5333770000 0.9047190000 0.4083240000 0.0000040000 1.2090190000 0.0069810000 126481132 0 1784909824 4.0340943336 3.9873261452 4.0362010002 75 1311867721.1103579998 0.0598834753 0.0224208057 0.0642507896 0.0059396331 2.6567780000 0.9060550000 0.4075180000 0.1236390000 1.2072340000 0.0070550000 126483318 0 1783525376 4.0289812088 3.9868626595 4.0363736153 76 1311867721.1467890739 0.0626448989 0.0229500701 0.0642507896 0.0059398754 2.5395460000 0.9063440000 0.4072610000 0.0000040000 1.2144280000 0.0070490000 126485568 0 1782636544 4.0311188698 3.9865548611 4.0363392830 77 1311867721.1774179935 0.0626087338 0.0234651177 0.0642507896 0.0059820068 3.9742470000 0.9081570000 0.4105770000 0.1237370000 1.2120620000 1.3153450000 126487754 0 1784545280 4.0309996605 3.9862031937 4.0365490913 78 1311867721.2112360001 0.0614290871 0.0239518352 0.0642507896 0.0059478457 2.5455150000 0.9090970000 0.4048360000 0.0000040000 1.2194140000 0.0069850000 126489940 0 1783660544 4.0293345451 3.9861586094 4.0367455482 79 1311867721.2469010353 0.0645032823 0.0244651447 0.0645032823 0.0059290614 2.6826140000 0.9156330000 0.4021770000 0.1243110000 1.2289700000 0.0069660000 126492190 0 1782902784 4.0323596001 3.9859361649 4.0366711617 80 1311867721.2800450325 0.0633779317 0.0249515545 0.0645032823 0.0058914759 2.5789950000 0.9341050000 0.4043560000 0.0000030000 1.2292360000 0.0069690000 126494376 0 1784549376 4.0303039551 3.9848754406 4.0368833542 81 1311867721.3099579811 0.0684754178 0.0254888862 0.0684754178 0.0059024305 4.0179110000 0.9095790000 0.4022810000 0.1304590000 1.2316270000 1.3388160000 126496530 0 1783771136 4.0354700089 3.9850409031 4.0370702744 82 1311867721.3483059406 0.0673959404 0.0259999478 0.0684754178 0.0058910894 2.3591780000 0.9059810000 0.2005410000 0.0000040000 1.2412020000 0.0069790000 126498812 0 1782898688 4.0339212418 3.9851934910 4.0369920731 83 1311867721.3790040016 0.0672444403 0.0264968694 0.0684754178 0.0058612006 2.6916410000 0.9133440000 0.4036530000 0.1250380000 1.2382000000 0.0069620000 126500934 0 1784528896 4.0331826210 3.9850866795 4.0371961594 84 1311867721.4092550278 0.0668599531 0.0269773823 0.0684754178 0.0058345230 2.5289480000 0.9341440000 0.3312770000 0.0000040000 1.2511620000 0.0070210000 126503088 0 1783140352 4.0319895744 3.9846005440 4.0377235413 85 1311867721.4478130341 0.0693931803 0.0274763917 0.0693931803 0.0058050366 3.8968290000 0.9049840000 0.2634490000 0.1251120000 1.2449350000 1.3537200000 126505434 0 1782673408 4.0339555740 3.9842364788 4.0381212234 86 1311867721.4768960476 0.0711713061 0.0279844721 0.0711713061 0.0057731451 2.4470510000 0.9199070000 0.2643510000 0.0000040000 1.2513960000 0.0070500000 126507556 0 1784381440 4.0354280472 3.9845135212 4.0384988785 87 1311867721.5093359947 0.0710743144 0.0284797576 0.0711713061 0.0057482566 2.7031360000 0.9168890000 0.3992470000 0.1267570000 1.2488600000 0.0070060000 126509710 0 1786032128 4.0348782539 3.9841873646 4.0383872986 88 1311867721.5451331139 0.0679051951 0.0289277740 0.0711713061 0.0057473033 2.5079860000 0.9406860000 0.2989870000 0.0000040000 1.2559390000 0.0069960000 126511928 0 1785184256 4.0306162834 3.9832425117 4.0386986732 89 1311867721.5769670010 0.0681435317 0.0293684005 0.0711713061 0.0057235835 4.0664580000 0.9020390000 0.3984530000 0.1264930000 1.2578640000 1.3770460000 126514050 0 1784422400 4.0307049751 3.9835448265 4.0385890007 90 1311867721.6129651070 0.0694020987 0.0298132193 0.0711713061 0.0057218790 2.5663960000 0.8972640000 0.3944540000 0.0000040000 1.2633110000 0.0069700000 126516268 0 1786052608 4.0314331055 3.9832563400 4.0386734009 91 1311867721.6496050358 0.0679904819 0.0302327497 0.0711713061 0.0057480898 2.5503310000 0.9068580000 0.2329370000 0.1262510000 1.2718850000 0.0069050000 126518550 0 1784946688 4.0290846825 3.9819204807 4.0384483337 92 1311867721.6800351143 0.0684563220 0.0306482233 0.0711713061 0.0057492101 2.5846720000 0.9061470000 0.3978810000 0.0000040000 1.2690520000 0.0069180000 126520704 0 1784184832 4.0296626091 3.9835960865 4.0386409760 93 1311867721.7162289619 0.0682300702 0.0310523292 0.0711713061 0.0057444477 4.0151610000 0.9112680000 0.3348430000 0.1270120000 1.2634130000 1.3741070000 126522986 0 1785905152 4.0292248726 3.9834175110 4.0388126373 94 1311867721.7467949390 0.0700440183 0.0314671344 0.0711713061 0.0057722991 2.6166690000 0.9240600000 0.4031260000 0.0000040000 1.2771510000 0.0069270000 126525140 0 1785057280 4.0297117233 3.9809396267 4.0387654305 95 1311867721.7787001133 0.0729578286 0.0319038785 0.0729578286 0.0057560428 2.7160780000 0.9075540000 0.3995640000 0.1275970000 1.2698180000 0.0069380000 126527326 0 1784295424 4.0329470634 3.9822268486 4.0392360687 96 1311867721.8154830933 0.0716688931 0.0323180974 0.0729578286 0.0057296139 2.5950220000 0.9056910000 0.3968960000 0.0000040000 1.2809600000 0.0069940000 126529576 0 1785933824 4.0308985710 3.9818875790 4.0392398834 97 1311867721.8485159874 0.0722035021 0.0327292872 0.0729578286 0.0057052295 4.0960420000 0.9029570000 0.4044810000 0.1275590000 1.2718870000 1.3835480000 126531794 0 1784811520 4.0305871964 3.9806551933 4.0391416550 98 1311867721.8778810501 0.0701995492 0.0331116368 0.0729578286 0.0056902759 2.6210590000 0.9234560000 0.4083630000 0.0000040000 1.2776500000 0.0069850000 126533948 0 1784061952 4.0283393860 3.9816775322 4.0390577316 99 1311867721.9146931171 0.0701675564 0.0334859390 0.0729578286 0.0056647174 2.6158620000 0.9018230000 0.2937730000 0.1278490000 1.2809750000 0.0068820000 126536070 0 1785671680 4.0276856422 3.9808461666 4.0387978554 100 1311867721.9467151165 0.0707538873 0.0338586185 0.0729578286 0.0056382418 2.6200750000 0.9209280000 0.4072670000 0.0000030000 1.2794460000 0.0068870000 126538256 0 1784565760 4.0276455879 3.9800882339 4.0387082100 101 1311867721.9773728848 0.0694729239 0.0342112354 0.0729578286 0.0056402700 4.0205030000 0.9077410000 0.3015260000 0.1283680000 1.2853200000 1.3928870000 126540442 0 1783787520 4.0261631012 3.9803926945 4.0385708809 102 1311867722.0166850090 0.0723015741 0.0345846701 0.0729578286 0.0056804578 2.5755980000 0.9099920000 0.3651360000 0.0000040000 1.2890400000 0.0069320000 126542660 0 1785417728 4.0287165642 3.9799263477 4.0384469032 103 1311867722.0475180149 0.0718037114 0.0349460200 0.0729578286 0.0056922742 2.7448520000 0.9068500000 0.4114500000 0.1281570000 1.2856010000 0.0073510000 126544750 0 1784291328 4.0280451775 3.9794890881 4.0381212234 104 1311867722.0800709724 0.0739552155 0.0353211084 0.0739552155 0.0056846537 2.5336020000 0.8971530000 0.3345350000 0.0000040000 1.2903120000 0.0068840000 126546968 0 1783533568 4.0299253464 3.9790413380 4.0382008553 105 1311867722.1161251068 0.0747775510 0.0356968840 0.0747775510 0.0056646388 4.0156580000 0.9166770000 0.2693190000 0.1286440000 1.2906290000 1.4058430000 126549218 0 1785311232 4.0298342705 3.9777030945 4.0381584167 106 1311867722.1479530334 0.0738418251 0.0360567420 0.0747775510 0.0056587600 2.6221040000 0.9101390000 0.4018280000 0.0000040000 1.2977120000 0.0068970000 126551372 0 1784188928 4.0280284882 3.9772036076 4.0381898880 107 1311867722.1798410416 0.0717860237 0.0363906605 0.0747775510 0.0056506319 2.7431970000 0.9075000000 0.3948390000 0.1293180000 1.3000210000 0.0068610000 126553558 0 1783283712 4.0258722305 3.9785153866 4.0379695892 108 1311867722.2146399021 0.0726177171 0.0367260962 0.0747775510 0.0056481184 2.5837720000 0.9047800000 0.3623130000 0.0000050000 1.3052510000 0.0069070000 126555808 0 1785024512 4.0259094238 3.9768297672 4.0381240845 109 1311867722.2469589710 0.0739942119 0.0370680055 0.0747775510 0.0056243128 4.1526830000 0.8923440000 0.3949240000 0.1294880000 1.3037430000 1.4267830000 126557994 0 1784197120 4.0271744728 3.9765830040 4.0381031036 110 1311867722.2780389786 0.0718176216 0.0373839111 0.0747775510 0.0056069516 2.6123680000 0.8917760000 0.4025530000 0.0000040000 1.3064180000 0.0069260000 126560180 0 1783025664 4.0249795914 3.9778342247 4.0381131172 111 1311867722.3154170513 0.0747861564 0.0377208683 0.0747861564 0.0055992000 2.7420320000 0.8940140000 0.3918270000 0.1294890000 1.3152160000 0.0068350000 126562430 0 1784762368 4.0274615288 3.9761385918 4.0384588242 112 1311867722.3488469124 0.0742633641 0.0380471406 0.0747861564 0.0055772618 2.5900930000 0.9030390000 0.3632430000 0.0000040000 1.3115000000 0.0068510000 126564616 0 1783934976 4.0263366699 3.9754860401 4.0384840965 113 1311867722.3777940273 0.0728413314 0.0383550538 0.0747861564 0.0055654911 4.1970140000 0.9048070000 0.4088050000 0.1297490000 1.3143370000 1.4345750000 126566770 0 1782755328 4.0253653526 3.9767813683 4.0381150246 114 1311867722.4150679111 0.0769216940 0.0386933576 0.0769216940 0.0055744304 2.6373170000 0.9062520000 0.3942390000 0.0000050000 1.3253360000 0.0068810000 126568924 0 1784381440 4.0286870003 3.9747376442 4.0389103889 115 1311867722.4467909336 0.0746407434 0.0390059436 0.0769216940 0.0056357840 2.7587120000 0.9015600000 0.3933740000 0.1296360000 1.3226580000 0.0069790000 126571110 0 1786179584 4.0255041122 3.9741165638 4.0388908386 116 1311867722.4777851105 0.0744935200 0.0393118710 0.0769216940 0.0056474858 2.6267900000 0.9512060000 0.3303560000 0.0000050000 1.3327060000 0.0068960000 126573264 0 1784909824 4.0253934860 3.9750494957 4.0391378403 117 1311867722.5147399902 0.0764756575 0.0396295102 0.0769216940 0.0056251204 4.2202100000 0.9052730000 0.3958720000 0.1304480000 1.3282840000 1.4555710000 126575482 0 1783787520 4.0270829201 3.9743754864 4.0395603180 118 1311867722.5469911098 0.0717271492 0.0399015241 0.0769216940 0.0056484622 2.6343880000 0.8991310000 0.3903140000 0.0000050000 1.3335080000 0.0068440000 126577668 0 1785524224 4.0213427544 3.9741027355 4.0391411781 119 1311867722.5802359581 0.0739122555 0.0401873285 0.0769216940 0.0056362793 2.7731950000 0.8979550000 0.3895980000 0.1303150000 1.3428570000 0.0068160000 126579854 0 1784578048 4.0236353874 3.9735360146 4.0392346382 120 1311867722.6146309376 0.0742752478 0.0404713945 0.0769216940 0.0056134499 2.6579440000 0.9084430000 0.3981780000 0.0000050000 1.3397380000 0.0067760000 126582072 0 1783418880 4.0237832069 3.9730246067 4.0392441750 121 1311867722.6560258865 0.0749400035 0.0407562591 0.0769216940 0.0055941905 4.2273130000 0.8940210000 0.3864230000 0.1357940000 1.3419250000 1.4645350000 126584418 0 1784889344 4.0239944458 3.9722707272 4.0394906998 122 1311867722.6778230667 0.0760740563 0.0410457492 0.0769216940 0.0055794539 2.6558330000 0.9032050000 0.3880090000 0.0000050000 1.3523020000 0.0067810000 126586476 0 1783918592 4.0248165131 3.9716792107 4.0398721695 123 1311867722.7252709866 0.0738319233 0.0413123035 0.0769216940 0.0055834690 2.7676690000 0.8834410000 0.3895660000 0.1306720000 1.3523250000 0.0068220000 126588886 0 1782775808 4.0219397545 3.9713232517 4.0394334793 124 1311867722.7449109554 0.0755100101 0.0415880914 0.0769216940 0.0055759638 2.6608810000 0.8932310000 0.3935280000 0.0000050000 1.3627170000 0.0067560000 126590848 0 1784254464 4.0239496231 3.9710614681 4.0390667915 125 1311867722.7770080566 0.0715001971 0.0418273883 0.0769216940 0.0056566612 4.2745450000 0.9049260000 0.3848350000 0.1313220000 1.3565620000 1.4923020000 126593066 0 1786032128 4.0190129280 3.9713928699 4.0385532379 126 1311867722.8162860870 0.0730099678 0.0420748691 0.0769216940 0.0056370662 2.6774420000 0.9134950000 0.3858240000 0.0000050000 1.3655970000 0.0067910000 126595316 0 1785188352 4.0204510689 3.9713764191 4.0390295982 127 1311867722.8466939926 0.0787032098 0.0423632812 0.0787032098 0.0056761796 2.7134360000 0.9048890000 0.2879070000 0.1321320000 1.3768660000 0.0067530000 126597470 0 1783918592 4.0250701904 3.9688374996 4.0405497551 128 1311867722.8819770813 0.0779429674 0.0426412475 0.0787032098 0.0056544524 2.5899270000 0.9157700000 0.2840910000 0.0000050000 1.3786670000 0.0067810000 126599720 0 1785413632 4.0231585503 3.9681959152 4.0409741402 129 1311867722.9150629044 0.0779802427 0.0429151932 0.0787032098 0.0056563218 4.2897940000 0.8847460000 0.3795720000 0.1319130000 1.3818090000 1.5060650000 126612050 0 1784532992 4.0236840248 3.9707527161 4.0413203239 130 1311867722.9485991001 0.0798601359 0.0431993851 0.0798601359 0.0056747043 2.6612460000 0.8832010000 0.3790140000 0.0000050000 1.3874450000 0.0066750000 126635292 0 1783418880 4.0240483284 3.9677441120 4.0420002937 131 1311867722.9821140766 0.0830142647 0.0435033154 0.0830142647 0.0056555074 2.8059120000 0.8973980000 0.3846710000 0.1326670000 1.3797090000 0.0066950000 126637478 0 1785024512 4.0259079933 3.9665710926 4.0442705154 132 1311867723.0147259235 0.0824502781 0.0437983682 0.0830142647 0.0056371037 2.6883680000 0.8995250000 0.3831800000 0.0000040000 1.3933660000 0.0067020000 126639664 0 1784057856 4.0262603760 3.9689075947 4.0440373421 133 1311867723.0460629463 0.0862044245 0.0441172107 0.0862044245 0.0056544635 4.1821760000 0.8951360000 0.2524650000 0.1328590000 1.3802810000 1.5109330000 126641818 0 1783545856 4.0282883644 3.9664220810 4.0457949638 134 1311867723.0845439434 0.0891092122 0.0444529719 0.0891092122 0.0056490334 2.6652430000 0.8838000000 0.3865140000 0.0000050000 1.3833850000 0.0067710000 126644100 0 1785159680 4.0307831764 3.9655163288 4.0461182594 135 1311867723.1140980721 0.0902188271 0.0447919783 0.0902188271 0.0056300677 2.8220750000 0.9012770000 0.3875940000 0.1328350000 1.3879820000 0.0067870000 126646254 0 1784434688 4.0312991142 3.9654922485 4.0468873978 136 1311867723.1505160332 0.0927885920 0.0451448945 0.0927885920 0.0056178080 2.4904510000 0.9031710000 0.1898650000 0.0000040000 1.3858480000 0.0067140000 126648504 0 1784180736 4.0326137543 3.9637856483 4.0477147102 137 1311867723.1811029911 0.0941971987 0.0455029405 0.0941971987 0.0055989838 4.1762270000 0.9041070000 0.2257260000 0.1334500000 1.3919150000 1.5162950000 126650658 0 1785794560 4.0329132080 3.9623930454 4.0481410027 138 1311867723.2201359272 0.0948703960 0.0458606757 0.0948703960 0.0055791849 2.5533310000 0.8933690000 0.2577410000 0.0000050000 1.3898140000 0.0067500000 126652940 0 1785069568 4.0332245827 3.9623594284 4.0483093262 139 1311867723.2486810684 0.0989017859 0.0462422664 0.0989017859 0.0055767280 2.6555380000 0.8983860000 0.2222150000 0.1333320000 1.3900410000 0.0066690000 126655062 0 1784942592 4.0369429588 3.9614045620 4.0489978790 140 1311867723.2846419811 0.0875978097 0.0465376632 0.0989017859 0.0055977835 2.5573790000 0.9237780000 0.2213930000 0.0000050000 1.3997620000 0.0066560000 126657312 0 1784016896 4.0245766640 3.9617948532 4.0454130173 141 1311867723.3132460117 0.0894287080 0.0468418550 0.0989017859 0.0055820681 4.3415320000 0.8952670000 0.3847610000 0.1335430000 1.3958480000 1.5271810000 126659434 0 1783926784 4.0258507729 3.9608016014 4.0459775925 142 1311867723.3499810696 0.0897609368 0.0471441020 0.0989017859 0.0055702580 2.7093420000 0.9076850000 0.3865720000 0.0000050000 1.4034720000 0.0067460000 126661716 0 1785548800 4.0255527496 3.9608528614 4.0464987755 143 1311867723.3822429180 0.0912476331 0.0474525183 0.0989017859 0.0055568541 2.6224620000 0.8847130000 0.1894880000 0.1335870000 1.4022210000 0.0066670000 126663934 0 1784823808 4.0269918442 3.9606235027 4.0466475487 144 1311867723.4193739891 0.0924079865 0.0477647091 0.0989017859 0.0055680284 2.7276950000 0.9318000000 0.3809850000 0.0000050000 1.4032380000 0.0066520000 126666184 0 1784561664 4.0276560783 3.9598383904 4.0479645729 145 1311867723.4455900192 0.0907872021 0.0480614159 0.0989017859 0.0055554776 4.2224530000 0.8809690000 0.2559140000 0.1343280000 1.4099580000 1.5354240000 126668274 0 1783635968 4.0262632370 3.9608762264 4.0470404625 146 1311867723.4825348854 0.0936103240 0.0483733948 0.0989017859 0.0055479982 2.5264050000 0.8893740000 0.2193640000 0.0000050000 1.4059420000 0.0066720000 126670556 0 1783656448 4.0277514458 3.9599905014 4.0484352112 147 1311867723.5147960186 0.0956088826 0.0486947246 0.0989017859 0.0055310530 2.6773510000 0.8933280000 0.2178000000 0.1346560000 1.4200320000 0.0067050000 126672710 0 1785286656 4.0292038918 3.9596354961 4.0492572784 148 1311867723.5451340675 0.0957957506 0.0490129748 0.0989017859 0.0055140044 2.7003060000 0.9920180000 0.2835530000 0.0000050000 1.4122350000 0.0066890000 126674896 0 1784397824 4.0286908150 3.9595520496 4.0496177673 149 1311867723.5809938908 0.0984888598 0.0493450277 0.0989017859 0.0055038361 4.2374350000 0.8981020000 0.2498930000 0.1343760000 1.4083250000 1.5417250000 126677146 0 1784291328 4.0305242538 3.9585630894 4.0505428314 150 1311867723.6132669449 0.1003287882 0.0496849195 0.1003287882 0.0054898186 2.6986430000 0.9871880000 0.2865200000 0.0000030000 1.4131980000 0.0066750000 126679364 0 1785921536 4.0325303078 3.9589948654 4.0508613586 151 1311867723.6453940868 0.0993667245 0.0500139380 0.1003287882 0.0054724273 2.6924380000 0.8806180000 0.2455450000 0.1343350000 1.4193750000 0.0066980000 126681518 0 1785196544 4.0320253372 3.9601347446 4.0500702858 152 1311867723.6809489727 0.1012178287 0.0503508057 0.1012178287 0.0054579124 2.7157940000 0.9023770000 0.3874020000 0.0000040000 1.4142470000 0.0067770000 126683768 0 1784922112 4.0329904556 3.9586498737 4.0507373810 153 1311867723.7130429745 0.1037466601 0.0506997982 0.1037466601 0.0054416970 4.3693770000 0.8811280000 0.3829640000 0.1342590000 1.4173920000 1.5478420000 126685954 0 1784152064 4.0349326134 3.9580075741 4.0518879890 154 1311867723.7471990585 0.1044017300 0.0510485121 0.1044017300 0.0054258233 2.6975520000 0.8849280000 0.3840600000 0.0000040000 1.4168070000 0.0067440000 126688172 0 1784045568 4.0357246399 3.9584114552 4.0514621735 155 1311867723.7809250355 0.1055940911 0.0514004190 0.1055940911 0.0054123584 2.8551180000 0.9026020000 0.3891770000 0.1354880000 1.4162370000 0.0066500000 126690390 0 1785540608 4.0361356735 3.9570469856 4.0511360168 156 1311867723.8157649040 0.1077487618 0.0517616264 0.1077487618 0.0054011018 2.6452640000 0.8975680000 0.3147360000 0.0000040000 1.4204440000 0.0066820000 126692608 0 1784815616 4.0378379822 3.9564082623 4.0510039330 157 1311867723.8468959332 0.1083770990 0.0521222345 0.1083770990 0.0053855952 4.2716480000 0.9081490000 0.2493570000 0.1358750000 1.4186710000 1.5545780000 126694794 0 1784274944 4.0393867493 3.9582550526 4.0503864288 158 1311867723.8826351166 0.1072908714 0.0524714031 0.1083770990 0.0053789536 2.7110840000 0.8928760000 0.3790580000 0.0000040000 1.4276190000 0.0066760000 126697012 0 1786068992 4.0374641418 3.9570460320 4.0495381355 159 1311867723.9172909260 0.1083371639 0.0528227601 0.1083770990 0.0053720165 2.7866770000 0.9037270000 0.3119040000 0.1357540000 1.4226470000 0.0066420000 126699166 0 1784926208 4.0386257172 3.9577357769 4.0497426987 160 1311867723.9490020275 0.1111738607 0.0531874544 0.1111738607 0.0053601593 2.6343720000 0.9181280000 0.2788750000 0.0000030000 1.4256740000 0.0066740000 126701320 0 1784668160 4.0418243408 3.9586939812 4.0502967834 161 1311867723.9839010239 0.1128498986 0.0535580286 0.1128498986 0.0053569050 4.2468120000 0.8957120000 0.2166620000 0.1358780000 1.4248260000 1.5679390000 126703570 0 1783906304 4.0425767899 3.9567887783 4.0504407883 162 1311867724.0132899284 0.1134592891 0.0539277895 0.1134592891 0.0053439852 2.7035530000 0.8817080000 0.3793820000 0.0000040000 1.4307210000 0.0066130000 126705692 0 1783799808 4.0432538986 3.9571349621 4.0505743027 163 1311867724.0475380421 0.1160633117 0.0543089890 0.1160633117 0.0053327043 2.6880110000 0.8963770000 0.2160710000 0.1369230000 1.4269910000 0.0066870000 126707942 0 1785434112 4.0459585190 3.9578611851 4.0516080856 164 1311867724.0824530125 0.1174713746 0.0546941255 0.1174713746 0.0053213121 2.5924300000 0.9022400000 0.2477210000 0.0000040000 1.4299420000 0.0066220000 126710160 0 1784688640 4.0465664864 3.9566996098 4.0522909164 165 1311867724.1132431030 0.1157468930 0.0550641423 0.1174713746 0.0053066811 4.2150410000 0.8879870000 0.1880280000 0.1359860000 1.4308230000 1.5671520000 126712346 0 1784442880 4.0452694893 3.9577369690 4.0509972572 166 1311867724.1547191143 0.1192401499 0.0554507447 0.1192401499 0.0053063757 2.5144780000 0.8790980000 0.1850610000 0.0000050000 1.4378960000 0.0065950000 126714692 0 1783517184 4.0481028557 3.9572384357 4.0527405739 167 1311867724.1810541153 0.1208110601 0.0558421239 0.1208110601 0.0052956294 2.7643210000 0.8789310000 0.3070230000 0.1360680000 1.4305200000 0.0066050000 126716782 0 1783545856 4.0490770340 3.9565305710 4.0537276268 168 1311867724.2139430046 0.1218371242 0.0562349513 0.1218371242 0.0052828580 2.6436360000 0.8878740000 0.3103950000 0.0000040000 1.4337840000 0.0066500000 126719000 0 1785159680 4.0497264862 3.9560444355 4.0540575981 169 1311867724.2507870197 0.1210946664 0.0566187365 0.1218371242 0.0052721417 4.4078000000 0.8918310000 0.3702750000 0.1356400000 1.4310590000 1.5731120000 126721250 0 1784270848 4.0492711067 3.9574441910 4.0534658432 170 1311867724.2855930328 0.1247202158 0.0570193335 0.1247202158 0.0052658886 2.6080450000 0.8846630000 0.2779690000 0.0000050000 1.4335660000 0.0066940000 126723468 0 1784033280 4.0521631241 3.9563608170 4.0549340248 171 1311867724.3144888878 0.1279559582 0.0574341675 0.1279559582 0.0052560265 2.6491150000 0.8757870000 0.1875040000 0.1420940000 1.4321000000 0.0066790000 126725590 0 1785794560 4.0545682907 3.9545974731 4.0557727814 172 1311867724.3517999649 0.1281298250 0.0578451888 0.1281298250 0.0052574743 2.5475890000 0.9135200000 0.1893110000 0.0000040000 1.4320550000 0.0066940000 126727904 0 1785069568 4.0542745590 3.9547655582 4.0565147400 173 1311867724.3888330460 0.1279934943 0.0582506703 0.1281298250 0.0052487649 4.4001330000 0.8836590000 0.3723460000 0.1361360000 1.4332960000 1.5695440000 126730122 0 1784926208 4.0545644760 3.9555153847 4.0555944443 174 1311867724.4160330296 0.1323919445 0.0586767696 0.1323919445 0.0052434111 2.6964080000 0.8690370000 0.3749040000 0.0000050000 1.4398860000 0.0066750000 126732244 0 1784045568 4.0577907562 3.9534342289 4.0580797195 175 1311867724.4509639740 0.1335439980 0.0591045824 0.1335439980 0.0052302847 2.7514420000 0.8836320000 0.2842400000 0.1370200000 1.4347890000 0.0066130000 126734462 0 1783918592 4.0587105751 3.9526937008 4.0576291084 176 1311867724.4830689430 0.1337563097 0.0595287399 0.1337563097 0.0052162140 2.6353370000 0.9267290000 0.2591510000 0.0000050000 1.4377870000 0.0066330000 126736648 0 1785430016 4.0589394569 3.9526789188 4.0569300652 177 1311867724.5208630562 0.1342641413 0.0599509738 0.1342641413 0.0052028532 4.4201120000 0.8823850000 0.3788310000 0.1368790000 1.4363500000 1.5796520000 126738866 0 1784827904 4.0586099625 3.9519588947 4.0574126244 178 1311867724.5523910522 0.1395850629 0.0603983563 0.1395850629 0.0052058035 2.5696680000 0.8950040000 0.2207990000 0.0000040000 1.4419270000 0.0066790000 126741084 0 1784193024 4.0630741119 3.9500229359 4.0593495369 179 1311867724.5861799717 0.1400822252 0.0608435176 0.1400822252 0.0052001427 2.7506150000 0.8829710000 0.2774050000 0.1420030000 1.4365570000 0.0066080000 126743270 0 1785942016 4.0623688698 3.9481494427 4.0599374771 180 1311867724.6193559170 0.1416898221 0.0612926637 0.1416898221 0.0052161722 2.6078990000 0.9085560000 0.2483950000 0.0000050000 1.4382050000 0.0066640000 126745456 0 1784799232 4.0636525154 3.9478542805 4.0600752831 181 1311867724.6529819965 0.1435690969 0.0617472297 0.1435690969 0.0052050605 4.2834870000 0.8789350000 0.2482380000 0.1364940000 1.4390080000 1.5755720000 126747674 0 1784672256 4.0654616356 3.9484171867 4.0603156090 182 1311867724.6818330288 0.1440624744 0.0621995112 0.1440624744 0.0052014183 2.5461230000 0.8965240000 0.1889090000 0.0000050000 1.4481430000 0.0066630000 126749796 0 1783767040 4.0652647018 3.9470062256 4.0597763062 183 1311867724.7153129578 0.1446227282 0.0626499113 0.1446227282 0.0051993872 2.6980740000 0.8914900000 0.2169680000 0.1378220000 1.4398950000 0.0066910000 126752014 0 1783259136 4.0652537346 3.9476251602 4.0606245995 184 1311867724.7518899441 0.1470024437 0.0631083490 0.1470024437 0.0051907525 2.7198800000 0.9467620000 0.3123380000 0.0000050000 1.4489750000 0.0066600000 126754264 0 1785053184 4.0673747063 3.9486446381 4.0615863800 185 1311867724.7853860855 0.1496366709 0.0635760697 0.1496366709 0.0051813934 4.3978060000 0.8871530000 0.3400920000 0.1373540000 1.4410710000 1.5861660000 126756482 0 1784180736 4.0684418678 3.9465930462 4.0633893013 186 1311867724.8179960251 0.1511782110 0.0640470489 0.1511782110 0.0051785168 2.6178620000 0.8843790000 0.2763760000 0.0000040000 1.4452250000 0.0066290000 126758668 0 1783930880 4.0695719719 3.9462532997 4.0637907982 187 1311867724.8547580242 0.1508246362 0.0645111002 0.1511782110 0.0051823694 2.6786260000 0.8933940000 0.1872090000 0.1381120000 1.4481490000 0.0067420000 126760886 0 1785671680 4.0693273544 3.9471559525 4.0630669594 188 1311867724.8830249310 0.1535219699 0.0649845623 0.1535219699 0.0051702880 2.6548010000 0.8880200000 0.3107980000 0.0000050000 1.4431670000 0.0067180000 126763008 0 1784528896 4.0707788467 3.9458367825 4.0648517609 189 1311867724.9137279987 0.1570055187 0.0654714456 0.1570055187 0.0051841098 4.2935630000 0.9009520000 0.2202100000 0.1451300000 1.4433860000 1.5785900000 126765194 0 1783664640 4.0728020668 3.9436790943 4.0666227341 190 1311867724.9535229206 0.1568588763 0.0659524321 0.1570055187 0.0051722151 2.5750570000 0.8898690000 0.2224110000 0.0000040000 1.4509760000 0.0066300000 126767476 0 1785434112 4.0729436874 3.9446070194 4.0660567284 191 1311867724.9843940735 0.1578759104 0.0664337069 0.1578759104 0.0051590950 2.7281420000 0.8803710000 0.2522860000 0.1378330000 1.4449490000 0.0066300000 126769662 0 1784311808 4.0735154152 3.9442088604 4.0667376518 192 1311867725.0159099102 0.1610437483 0.0669264675 0.1610437483 0.0051593146 2.7582660000 0.9168500000 0.3789980000 0.0000050000 1.4505540000 0.0065890000 126771816 0 1783787520 4.0748925209 3.9414029121 4.0692210197 193 1311867725.0518310070 0.1587159932 0.0674020609 0.1610437483 0.0051470592 4.3143610000 0.8822660000 0.2530280000 0.1379790000 1.4463970000 1.5894610000 126774066 0 1785417728 4.0732741356 3.9425995350 4.0672268867 194 1311867725.0813930035 0.1600035876 0.0678793883 0.1610437483 0.0051340629 2.7313570000 0.8927730000 0.3775740000 0.0000050000 1.4481440000 0.0066210000 126776220 0 1784020992 4.0739293098 3.9423398972 4.0681786537 195 1311867725.1151220798 0.1618565321 0.0683613224 0.1618565321 0.0051246486 2.7552110000 0.8977540000 0.2524460000 0.1383030000 1.4547720000 0.0066410000 126778438 0 1783300096 4.0750169754 3.9405939579 4.0685729980 196 1311867725.1557130814 0.1611903310 0.0688349398 0.1618565321 0.0051136569 2.5537160000 0.8996820000 0.1886080000 0.0000050000 1.4537170000 0.0065920000 126780752 0 1784930304 4.0744848251 3.9414272308 4.0678586960 197 1311867725.1843969822 0.1661991030 0.0693291741 0.1661991030 0.0051131842 4.4651980000 0.9027410000 0.3772900000 0.1443620000 1.4488040000 1.5858150000 126782874 0 1783386112 4.0770483017 3.9386777878 4.0720100403 198 1311867725.2150099277 0.1683858633 0.0698294604 0.1683858633 0.0051033233 2.6264570000 0.9044710000 0.2535510000 0.0000050000 1.4565490000 0.0065890000 126785060 0 1782648832 4.0774326324 3.9359467030 4.0735564232 199 1311867725.2516539097 0.1651346236 0.0703083809 0.1683858633 0.0050917051 2.7858610000 0.8966060000 0.2850250000 0.1385220000 1.4536980000 0.0066450000 126787342 0 1784381440 4.0761671066 3.9390773773 4.0700359344 200 1311867725.2816410065 0.1651758850 0.0707827184 0.1683858633 0.0050825400 2.7715890000 0.9231140000 0.3709660000 0.0000050000 1.4650160000 0.0065840000 126789496 0 1783562240 4.0761265755 3.9389967918 4.0697374344 201 1311867725.3196239471 0.1704143137 0.0712783980 0.1704143137 0.0050796360 4.4940470000 0.9122260000 0.3815700000 0.1392430000 1.4560760000 1.5995870000 126791746 0 1782525952 4.0787920952 3.9358637333 4.0735955238 202 1311867725.3517010212 0.1703180075 0.0717686931 0.1704143137 0.0050700583 2.7577970000 0.9034770000 0.3841810000 0.0000050000 1.4583020000 0.0065800000 126793900 0 1784127488 4.0784564018 3.9363183975 4.0740432739 203 1311867725.3837459087 0.1780184358 0.0722920908 0.1780184358 0.0051064571 2.8919860000 0.9053050000 0.3774920000 0.1446160000 1.4527980000 0.0065860000 126796022 0 1785778176 4.0822033882 3.9324841499 4.0817055702 204 1311867725.4178969860 0.1741071790 0.0727911844 0.1780184358 0.0050958928 2.6680980000 0.9091150000 0.2854630000 0.0000050000 1.4608050000 0.0065710000 126798272 0 1784930304 4.0808935165 3.9351496696 4.0765786171 205 1311867725.4492449760 0.1719922125 0.0732750918 0.1780184358 0.0050902649 4.3890420000 0.9335000000 0.2510690000 0.1395160000 1.4616080000 1.5980060000 126800426 0 1783934976 4.0791802406 3.9364185333 4.0748863220 206 1311867725.4836509228 0.1859792322 0.0738221993 0.1859792322 0.0051706841 2.7915990000 0.9348150000 0.3853590000 0.0000050000 1.4594520000 0.0066220000 126802644 0 1785524224 4.0859522820 3.9293901920 4.0877766609 207 1311867725.5178139210 0.1954273731 0.0744096639 0.1954273731 0.0051828393 2.8081010000 0.9226780000 0.2855270000 0.1391260000 1.4478800000 0.0067390000 126804926 0 1784401920 4.0897912979 3.9242954254 4.0968594551 208 1311867725.5497610569 0.1994982213 0.0750110512 0.1994982213 0.0051774085 2.7671930000 0.9215990000 0.3841320000 0.0000050000 1.4494340000 0.0066360000 126807080 0 1783664640 4.0913891792 3.9221303463 4.1001133919 209 1311867725.5815479755 0.1921291649 0.0755714250 0.1994982213 0.0052088715 4.5191240000 0.9329650000 0.3846140000 0.1399330000 1.4634510000 1.5929390000 126809266 0 1785278464 4.0891218185 3.9274785519 4.0910911560 210 1311867725.6194949150 0.2011373043 0.0761693577 0.2011373043 0.0052098786 2.7914770000 0.9388280000 0.3836740000 0.0000040000 1.4561790000 0.0066450000 126811548 0 1784307712 4.0933856964 3.9226443768 4.0985221863 211 1311867725.6515610218 0.2160202861 0.0768321583 0.2160202861 0.0053690230 2.8750860000 0.9324910000 0.3485980000 0.1392590000 1.4426940000 0.0066790000 126813734 0 1783164928 4.0977039337 3.9134385586 4.1140336990 212 1311867725.6834650040 0.2107501030 0.0774638467 0.2160202861 0.0053689176 2.7214860000 0.9346820000 0.3176250000 0.0000040000 1.4572630000 0.0066410000 126815920 0 1784762368 4.0964660645 3.9181342125 4.1078267097 213 1311867725.7201809883 0.2145882249 0.0781076232 0.2160202861 0.0053615000 4.4935650000 0.9383840000 0.3806880000 0.1398440000 1.4492130000 1.5792690000 126818170 0 1783803904 4.0980925560 3.9158878326 4.1102886200 214 1311867725.7515070438 0.2211871743 0.0787762192 0.2211871743 0.0053578820 2.7576640000 0.9480710000 0.3517700000 0.0000050000 1.4456540000 0.0067720000 126820356 0 1783545856 4.1003599167 3.9117796421 4.1159696579 215 1311867725.7835409641 0.1816293001 0.0792546056 0.2211871743 0.0056088169 2.8332490000 0.9284510000 0.2911280000 0.1395540000 1.4621620000 0.0067120000 126822510 0 1785159680 4.0727062225 3.9266967773 4.0890436172 216 1311867725.8211829662 0.1920296103 0.0797767121 0.2211871743 0.0056312243 2.7909760000 0.9356330000 0.3908020000 0.0000050000 1.4515910000 0.0067370000 126824824 0 1784270848 4.0763306618 3.9201655388 4.0986700058 217 1311867725.8517971039 0.1905281097 0.0802870872 0.2211871743 0.0056270632 4.5211410000 0.9393910000 0.3937320000 0.1395960000 1.4594450000 1.5835360000 126827010 0 1784291328 4.0753998756 3.9208250046 4.0966253281 218 1311867725.8837900162 0.1945903748 0.0808114142 0.2211871743 0.0056379999 2.7992180000 0.9417450000 0.3873730000 0.0000050000 1.4581480000 0.0066830000 126829132 0 1785921536 4.0772767067 3.9202721119 4.1003918648 219 1311867725.9192690849 0.1980188340 0.0813466079 0.2211871743 0.0056335003 2.8710370000 0.9459370000 0.3188720000 0.1396200000 1.4536650000 0.0067240000 126831382 0 1785032704 4.0792622566 3.9188675880 4.1018867493 220 1311867725.9511859417 0.2053075135 0.0819100666 0.2211871743 0.0056288315 2.7581730000 0.9337270000 0.3569200000 0.0000040000 1.4553640000 0.0066420000 126833568 0 1784815616 4.0814809799 3.9140985012 4.1084461212 221 1311867725.9829630852 0.2073135525 0.0824775032 0.2211871743 0.0056195998 4.5092280000 0.9393850000 0.3890850000 0.1398690000 1.4491030000 1.5855200000 126835722 0 1784045568 4.0827608109 3.9146232605 4.1099767685 222 1311867726.0219368935 0.2124560773 0.0830629923 0.2211871743 0.0056130993 2.7925420000 0.9462070000 0.3844080000 0.0000040000 1.4496180000 0.0068230000 126838036 0 1783517184 4.0847887993 3.9118590355 4.1134676933 223 1311867726.0504179001 0.2075613737 0.0836212810 0.2211871743 0.0056150387 2.9510350000 0.9456780000 0.3943180000 0.1396960000 1.4593110000 0.0067130000 126840126 0 1785159680 4.0824990273 3.9139330387 4.1079335213 224 1311867726.0845088959 0.2154436260 0.0842097736 0.2211871743 0.0056258640 2.7888110000 0.9407940000 0.3879000000 0.0000040000 1.4471170000 0.0067000000 126842376 0 1784418304 4.0850701332 3.9099886417 4.1158394814 225 1311867726.1199669838 0.2155897468 0.0847936846 0.2211871743 0.0056150826 4.5190480000 0.9520870000 0.3976250000 0.1406850000 1.4478540000 1.5752380000 126844594 0 1783894016 4.0850152969 3.9097261429 4.1151766777 226 1311867726.1506989002 0.2186357677 0.0853859062 0.2211871743 0.0056085076 2.7042960000 0.9523060000 0.2882070000 0.0000040000 1.4517290000 0.0067350000 126846780 0 1785692160 4.0853042603 3.9071846008 4.1178660393 227 1311867726.1824700832 0.2137962878 0.0859515907 0.2211871743 0.0055978971 2.8093480000 0.9476700000 0.2585360000 0.1398790000 1.4502290000 0.0066540000 126848966 0 1784549376 4.0832533836 3.9104185104 4.1132483482 228 1311867726.2198660374 0.2180940509 0.0865311629 0.2211871743 0.0055936992 2.6637150000 0.9450820000 0.2550930000 0.0000040000 1.4513680000 0.0066990000 126851216 0 1783787520 4.0853590965 3.9085543156 4.1161799431 229 1311867726.2506690025 0.2253050804 0.0871371625 0.2253050804 0.0055927590 4.5010470000 0.9404440000 0.3909670000 0.1396390000 1.4468180000 1.5777740000 126853402 0 1785417728 4.0873489380 3.9035980701 4.1226086617 230 1311867726.2845950127 0.2231656015 0.0877285905 0.2253050804 0.0055812894 2.8038530000 0.9367850000 0.3939150000 0.0000040000 1.4596140000 0.0071980000 126855588 0 1784295424 4.0866312981 3.9049293995 4.1199364662 231 1311867726.3187239170 0.2289908528 0.0883401155 0.2289908528 0.0055760347 2.9478060000 0.9581340000 0.3867480000 0.1400420000 1.4507260000 0.0066500000 126857838 0 1783545856 4.0891313553 3.9026873112 4.1249647141 232 1311867726.3524029255 0.2275320441 0.0889400807 0.2289908528 0.0055683402 2.8026920000 0.9449030000 0.3839440000 0.0000040000 1.4617700000 0.0067060000 126860056 0 1785151488 4.0894508362 3.9044764042 4.1224431992 233 1311867726.3835608959 0.2306391746 0.0895482313 0.2306391746 0.0055580547 4.3801590000 0.9429600000 0.2603300000 0.1398320000 1.4532370000 1.5775110000 126862210 0 1784311808 4.0899271965 3.9022672176 4.1249713898 234 1311867726.4218099117 0.2276593447 0.0901384497 0.2306391746 0.0055506513 2.8176230000 0.9612120000 0.3857820000 0.0000040000 1.4582610000 0.0066360000 126864524 0 1783152640 4.0899429321 3.9055957794 4.1209936142 235 1311867726.4504199028 0.2285399586 0.0907273923 0.2306391746 0.0055389083 2.7683840000 0.9403030000 0.2123550000 0.1398590000 1.4634990000 0.0067010000 126866646 0 1784930304 4.0898895264 3.9052884579 4.1218156815 236 1311867726.4843189716 0.2313852310 0.0913234001 0.2313852310 0.0055303336 2.8130020000 0.9600190000 0.3798250000 0.0000040000 1.4600580000 0.0066970000 126868864 0 1783406592 4.0904321671 3.9035227299 4.1244163513 237 1311867726.5207901001 0.2360561937 0.0919340870 0.2360561937 0.0055239418 4.3661040000 0.9536470000 0.2268190000 0.1399350000 1.4613950000 1.5787560000 126871114 0 1782665216 4.0914893150 3.9003448486 4.1288022995 238 1311867726.5524380207 0.2355842590 0.0925376591 0.2360561937 0.0055180063 2.6288570000 0.9324870000 0.2262340000 0.0000040000 1.4579680000 0.0066530000 126873300 0 1784381440 4.0913786888 3.9012558460 4.1281900406 239 1311867726.5874860287 0.2321287841 0.0931217224 0.2360561937 0.0055142518 2.7931570000 0.9573220000 0.2247740000 0.1402120000 1.4587140000 0.0066860000 126875550 0 1786179584 4.0903291702 3.9039750099 4.1245422363 240 1311867726.6204600334 0.2341166139 0.0937092011 0.2360561937 0.0055167541 2.8206630000 0.9912860000 0.3534670000 0.0000040000 1.4628120000 0.0067400000 126877736 0 1785315328 4.0916886330 3.9032790661 4.1261320114 241 1311867726.6509370804 0.2304998487 0.0942767972 0.2360561937 0.0055207061 4.5275930000 0.9481860000 0.3979900000 0.1399820000 1.4546060000 1.5811590000 126879890 0 1784172544 4.0906958580 3.9048271179 4.1214346886 242 1311867726.6916151047 0.2338384092 0.0948534981 0.2360561937 0.0055158008 2.6288150000 0.9389800000 0.2285300000 0.0000040000 1.4491850000 0.0066550000 126882236 0 1785786368 4.0915660858 3.9028422832 4.1250190735 243 1311867726.7201170921 0.2340801507 0.0954264473 0.2360561937 0.0055057966 2.8564460000 0.9541150000 0.2963990000 0.1397200000 1.4531170000 0.0067570000 126884326 0 1784954880 4.0925202370 3.9035325050 4.1248559952 244 1311867726.7513859272 0.2310805321 0.0959824066 0.2360561937 0.0054965662 2.8387540000 0.9760390000 0.4039820000 0.0000040000 1.4463370000 0.0067980000 126886512 0 1783918592 4.0908269882 3.9040274620 4.1220936775 245 1311867726.7880010605 0.2260471731 0.0965132832 0.2360561937 0.0054922100 4.5137550000 0.9519500000 0.3965390000 0.1454440000 1.4468510000 1.5675490000 126888794 0 1785544704 4.0888748169 3.9062445164 4.1173644066 246 1311867726.8198299408 0.2285765558 0.0970501258 0.2360561937 0.0054845766 2.6020200000 0.9432020000 0.1968920000 0.0000030000 1.4487570000 0.0067010000 126890948 0 1784442880 4.0902109146 3.9051027298 4.1197586060 247 1311867726.8500390053 0.2301150709 0.0975888503 0.2360561937 0.0054745765 2.9451680000 0.9453110000 0.4028400000 0.1399410000 1.4446710000 0.0067980000 126893102 0 1783283712 4.0906944275 3.9038124084 4.1212911606 248 1311867726.8927390575 0.2253995240 0.0981042159 0.2360561937 0.0054672538 2.8197240000 0.9417670000 0.4183960000 0.0000200000 1.4474190000 0.0066870000 126895480 0 1784762368 4.0894627571 3.9064664841 4.1163926125 249 1311867726.9216780663 0.2272553593 0.0986228952 0.2360561937 0.0054583448 4.4977650000 0.9439040000 0.3970850000 0.1399640000 1.4421560000 1.5682570000 126897602 0 1783791616 4.0897855759 3.9055664539 4.1191411018 250 1311867726.9543499947 0.2213328034 0.0991137348 0.2360561937 0.0054840519 2.7073840000 0.9570810000 0.2926510000 0.0000040000 1.4452360000 0.0067390000 126899788 0 1782648832 4.0886359215 3.9092903137 4.1127700806 251 1311867726.9902989864 0.2220121324 0.0996033699 0.2360561937 0.0054786270 2.8589240000 0.9559580000 0.3003350000 0.1451530000 1.4452040000 0.0066900000 126902006 0 1784254464 4.0882883072 3.9083676338 4.1142225266 252 1311867727.0208179951 0.2232019156 0.1000938403 0.2360561937 0.0054682708 2.7944590000 0.9345090000 0.4055360000 0.0000040000 1.4421670000 0.0067300000 126904192 0 1786052608 4.0888390541 3.9074110985 4.1152939796 253 1311867727.0536949635 0.2199508250 0.1005675833 0.2360561937 0.0054638690 4.5283760000 0.9515710000 0.4169770000 0.1396540000 1.4462770000 1.5673870000 126906378 0 1785085952 4.0881190300 3.9091751575 4.1120724678 254 1311867727.0911629200 0.2204600722 0.1010396010 0.2360561937 0.0054543441 2.6731380000 0.9504350000 0.2709870000 0.0000040000 1.4392160000 0.0067640000 126908660 0 1783934976 4.0879101753 3.9085118771 4.1135225296 255 1311867727.1196689606 0.2166850269 0.1014931124 0.2360561937 0.0054461025 2.7839840000 0.9527760000 0.2348550000 0.1407730000 1.4432140000 0.0068220000 126910718 0 1785561088 4.0864310265 3.9100606441 4.1099352837 256 1311867727.1514298916 0.2129744589 0.1019285865 0.2360561937 0.0054407903 2.8293770000 0.9680990000 0.4085190000 0.0000030000 1.4394280000 0.0068610000 126912936 0 1784815616 4.0847301483 3.9118111134 4.1072735786 257 1311867727.1904149055 0.2137176543 0.1023635634 0.2360561937 0.0054490136 4.4046070000 0.9629830000 0.2975930000 0.1399120000 1.4405060000 1.5578520000 126935666 0 1784688640 4.0850749016 3.9111599922 4.1087040901 258 1311867727.2208960056 0.2110006660 0.1027846374 0.2360561937 0.0054464519 2.7996150000 0.9534250000 0.4006830000 0.0000030000 1.4322920000 0.0067410000 126979836 0 1783762944 4.0837163925 3.9129853249 4.1075601578 259 1311867727.2544560432 0.2060038447 0.1031831672 0.2360561937 0.0054497795 2.9014970000 0.9585880000 0.3595610000 0.1395680000 1.4312750000 0.0067850000 126982022 0 1783672832 4.0818376541 3.9150226116 4.1024270058 260 1311867727.2870850563 0.2071049809 0.1035828665 0.2360561937 0.0054406314 2.7557930000 0.9372660000 0.3711010000 0.0000030000 1.4350620000 0.0066930000 126984240 0 1785286656 4.0821266174 3.9139850140 4.1041393280 261 1311867727.3192501068 0.2069724798 0.1039789952 0.2360561937 0.0054306455 4.3244580000 0.9658830000 0.2355970000 0.1398290000 1.4273220000 1.5492170000 126986426 0 1784561664 4.0825138092 3.9135410786 4.1039633751 262 1311867727.3502039909 0.2027501017 0.1043559842 0.2360561937 0.0054294289 2.7957480000 0.9599730000 0.3974050000 0.0000040000 1.4259180000 0.0067390000 126988580 0 1784307712 4.0804843903 3.9144952297 4.1001906395 263 1311867727.3894629478 0.2017349154 0.1047262463 0.2360561937 0.0054205189 2.7385500000 0.9526940000 0.1954560000 0.1394580000 1.4377210000 0.0067740000 126990830 0 1783529472 4.0799112320 3.9154701233 4.1011157036 264 1311867727.4182970524 0.1996980160 0.1050859878 0.2360561937 0.0054110602 2.6306800000 0.9575130000 0.2356460000 0.0000030000 1.4249760000 0.0067130000 126992984 0 1783427072 4.0792255402 3.9161422253 4.1003432274 265 1311867727.4495580196 0.1958875656 0.1054286353 0.2360561937 0.0054057783 4.3049930000 0.9494630000 0.2321600000 0.1390850000 1.4310110000 1.5475460000 126995106 0 1784913920 4.0775098801 3.9174461365 4.0973482132 266 1311867727.4858360291 0.1963202953 0.1057703333 0.2360561937 0.0054175046 2.7719120000 0.9331020000 0.4029020000 0.0000030000 1.4226610000 0.0067520000 126997388 0 1784180736 4.0767984390 3.9174926281 4.1002130508 267 1311867727.5198891163 0.1929801553 0.1060969618 0.2360561937 0.0054204141 2.9295450000 0.9622400000 0.3896240000 0.1394510000 1.4257290000 0.0067200000 126999574 0 1784053760 4.0762109756 3.9191644192 4.0963301659 268 1311867727.5494980812 0.1919651479 0.1064173655 0.2360561937 0.0054163042 2.8375950000 0.9851850000 0.4088860000 0.0000040000 1.4310990000 0.0067880000 127001728 0 1785815040 4.0751433372 3.9182662964 4.0959115028 269 1311867727.5905909538 0.1894464940 0.1067260240 0.2360561937 0.0054137402 4.4803060000 0.9587000000 0.3940900000 0.1396910000 1.4266120000 1.5545420000 127004074 0 1784926208 4.0745182037 3.9192464352 4.0937552452 270 1311867727.6176431179 0.1880774200 0.1070273254 0.2360561937 0.0054133623 2.6240360000 0.9593440000 0.2274330000 0.0000040000 1.4247580000 0.0067110000 127006164 0 1784680448 4.0726604462 3.9187541008 4.0937676430 271 1311867727.6497650146 0.1860184222 0.1073188055 0.2360561937 0.0054085171 2.9153510000 0.9402350000 0.3913010000 0.1390490000 1.4314670000 0.0067010000 127008350 0 1783926784 4.0716481209 3.9192616940 4.0920166969 272 1311867727.6884338856 0.1812899262 0.1075907582 0.2360561937 0.0054064504 2.6046960000 0.9715170000 0.1946240000 0.0000040000 1.4259630000 0.0067870000 127010536 0 1783783424 4.0700850487 3.9220535755 4.0874443054 273 1311867727.7184689045 0.1791374981 0.1078528341 0.2360561937 0.0053977210 4.2944260000 0.9499790000 0.2217980000 0.1392050000 1.4309420000 1.5467570000 127012722 0 1785434112 4.0687937737 3.9224967957 4.0851101875 274 1311867727.7523269653 0.1746491343 0.1080966162 0.2360561937 0.0053919882 2.7702610000 0.9365050000 0.3896260000 0.0000050000 1.4306610000 0.0067670000 127014940 0 1784545280 4.0651903152 3.9228775501 4.0814957619 275 1311867727.7856590748 0.1734922379 0.1083344185 0.2360561937 0.0053858993 2.8870190000 0.9266950000 0.3876630000 0.1387200000 1.4213220000 0.0066790000 127017126 0 1784188928 4.0639958382 3.9236223698 4.0814495087 276 1311867727.8181309700 0.1731333584 0.1085691973 0.2360561937 0.0053827713 2.7592780000 0.9195210000 0.4002380000 0.0000050000 1.4271840000 0.0066820000 127019344 0 1785683968 4.0632839203 3.9239079952 4.0817136765 277 1311867727.8548729420 0.1724901050 0.1087999587 0.2360561937 0.0053747560 4.2567480000 0.9136880000 0.2278720000 0.1381110000 1.4217160000 1.5486970000 127021594 0 1785073664 4.0630173683 3.9240174294 4.0808682442 278 1311867727.8882629871 0.1699799448 0.1090200306 0.2360561937 0.0053658967 2.5849400000 0.9209320000 0.2297380000 0.0000050000 1.4216720000 0.0067180000 127023812 0 1784545280 4.0619411469 3.9254283905 4.0788908005 279 1311867727.9193139076 0.1692522317 0.1092359166 0.2360561937 0.0053588228 2.7013300000 0.9261410000 0.1960670000 0.1386760000 1.4271320000 0.0067260000 127025966 0 1783672832 4.0610389709 3.9256894588 4.0793461800 280 1311867727.9556980133 0.1690438092 0.1094495162 0.2360561937 0.0053502560 2.6716240000 0.9725450000 0.2638710000 0.0000050000 1.4225460000 0.0066870000 127028216 0 1783529472 4.0615286827 3.9256038666 4.0784978867 281 1311867727.9869389534 0.1686072946 0.1096600421 0.2360561937 0.0053412594 4.2298280000 0.9198430000 0.1966850000 0.1384610000 1.4271410000 1.5418840000 127030434 0 1785159680 4.0613665581 3.9258375168 4.0783004761 282 1311867728.0179219246 0.1671759039 0.1098639991 0.2360561937 0.0053400335 2.7538710000 0.9167460000 0.3970050000 0.0000050000 1.4268400000 0.0066480000 127032556 0 1784270848 4.0610446930 3.9267351627 4.0772247314 283 1311867728.0555219650 0.1641387492 0.1100557826 0.2360561937 0.0053339972 2.7265060000 0.9250570000 0.2284260000 0.1398550000 1.4206040000 0.0067310000 127034838 0 1784164352 4.0590429306 3.9278094769 4.0756969452 284 1311867728.0892169476 0.1631280631 0.1102426569 0.2360561937 0.0053254653 2.7554240000 0.9192930000 0.3989260000 0.0000050000 1.4246910000 0.0066610000 127037056 0 1785794560 4.0590467453 3.9287848473 4.0749931335 285 1311867728.1177880764 0.1604584903 0.1104188528 0.2360561937 0.0053232682 4.2172660000 0.9173000000 0.1875970000 0.1384360000 1.4205560000 1.5466090000 127039210 0 1785053184 4.0575985909 3.9297828674 4.0730090141 286 1311867728.1556169987 0.1603227258 0.1105933418 0.2360561937 0.0053168338 2.7529630000 0.9236740000 0.3980360000 0.0000040000 1.4186070000 0.0066810000 127041460 0 1784537088 4.0576181412 3.9296278954 4.0730795860 287 1311867728.1882989407 0.1587897390 0.1107612735 0.2360561937 0.0053078770 2.7889940000 0.9212630000 0.2896290000 0.1385930000 1.4269630000 0.0067520000 127043710 0 1786224640 4.0572910309 3.9301607609 4.0711951256 288 1311867728.2182519436 0.1580016762 0.1109253027 0.2360561937 0.0053013188 2.5639860000 0.9346260000 0.1961620000 0.0000050000 1.4196120000 0.0066730000 127045864 0 1785200640 4.0563888550 3.9300949574 4.0710167885 289 1311867728.2558999062 0.1560921967 0.1110815895 0.2360561937 0.0052928434 4.4224980000 0.9119800000 0.3929670000 0.1387060000 1.4290770000 1.5437790000 127048114 0 1784688640 4.0555472374 3.9308433533 4.0693783760 290 1311867728.2875900269 0.1373283714 0.1111720957 0.2360561937 0.0053772152 2.6188590000 0.9247580000 0.2547430000 0.0000050000 1.4259400000 0.0066840000 127050300 0 1783803904 4.0354862213 3.9328296185 4.0637121201 291 1311867728.3226509094 0.1368709952 0.1112604080 0.2360561937 0.0053827784 2.6954070000 0.9273570000 0.1954110000 0.1382700000 1.4216570000 0.0066640000 127052550 0 1783275520 4.0361027718 3.9338951111 4.0633616447 292 1311867728.3597300053 0.1358681321 0.1113446811 0.2360561937 0.0053827478 2.5461500000 0.9136670000 0.1922930000 0.0000050000 1.4276000000 0.0067150000 127054768 0 1785036800 4.0349984169 3.9331665039 4.0628051758 293 1311867728.3861401081 0.1363536566 0.1114300359 0.2360561937 0.0053737723 4.2988930000 0.9231150000 0.2617120000 0.1382770000 1.4217490000 1.5471320000 127056890 0 1783783424 4.0357160568 3.9332082272 4.0629692078 294 1311867728.4175701141 0.1361754388 0.1115142040 0.2360561937 0.0054041630 2.5415850000 0.9140930000 0.1916860000 0.0000050000 1.4230860000 0.0066690000 127059076 0 1783418880 4.0350623131 3.9326636791 4.0626440048 295 1311867728.4568250179 0.1342363060 0.1115912281 0.2360561937 0.0053966521 2.7206530000 0.9159220000 0.2249050000 0.1382210000 1.4290420000 0.0067240000 127061358 0 1785053184 4.0339784622 3.9335188866 4.0610599518 296 1311867728.4875330925 0.1323365122 0.1116613135 0.2360561937 0.0053911202 2.6794210000 0.9471450000 0.2937650000 0.0000050000 1.4250850000 0.0067120000 127063512 0 1784295424 4.0335617065 3.9351191521 4.0594873428 297 1311867728.5187420845 0.1320787817 0.1117300592 0.2360561937 0.0053850357 4.2231890000 0.9038750000 0.1942210000 0.1376600000 1.4339230000 1.5473920000 127065666 0 1783664640 4.0334405899 3.9346275330 4.0586905479 298 1311867728.5550920963 0.1307024658 0.1117937250 0.2360561937 0.0053783697 2.5745700000 0.9085960000 0.2284700000 0.0000040000 1.4249820000 0.0067180000 127067948 0 1785442304 4.0324907303 3.9353692532 4.0582489967 299 1311867728.5878560543 0.1312714517 0.1118588678 0.2360561937 0.0053718217 2.7460110000 0.9151540000 0.2543600000 0.1376710000 1.4252090000 0.0067730000 127070166 0 1784446976 4.0336999893 3.9352838993 4.0576109886 300 1311867728.6187679768 0.1299001575 0.1119190055 0.2360561937 0.0053640734 2.6161480000 0.9077800000 0.2634980000 0.0000040000 1.4321300000 0.0066720000 127072288 0 1783803904 4.0328664780 3.9358761311 4.0565557480 301 1311867728.6580820084 0.1306810230 0.1119813378 0.2360561937 0.0053561619 4.1975560000 0.8964980000 0.1929640000 0.1370730000 1.4227340000 1.5424190000 127074602 0 1785544704 4.0332632065 3.9354193211 4.0571508408 302 1311867728.6893489361 0.1302850842 0.1120419462 0.2360561937 0.0053484280 2.7327300000 0.9058560000 0.3901270000 0.0000040000 1.4231430000 0.0067190000 127076788 0 1784438784 4.0324230194 3.9348564148 4.0570158958 303 1311867728.7210168839 0.1296202987 0.1120999606 0.2360561937 0.0053448857 2.8864580000 0.9101660000 0.3984090000 0.1374410000 1.4276430000 0.0066500000 127078974 0 1783930880 4.0323987007 3.9352002144 4.0564031601 304 1311867728.7584259510 0.1287386268 0.1121546930 0.2360561937 0.0053362089 2.5962370000 0.9012160000 0.2598710000 0.0000040000 1.4225690000 0.0066570000 127081224 0 1785561088 4.0320129395 3.9353051186 4.0554695129 305 1311867728.7858450413 0.1278453469 0.1122061378 0.2360561937 0.0053283507 4.2362070000 0.8971910000 0.2246430000 0.1373390000 1.4274830000 1.5425900000 127083378 0 1784565760 4.0307998657 3.9349670410 4.0549688339 306 1311867728.8203740120 0.1268688589 0.1122540552 0.2360561937 0.0053207351 2.6699000000 0.9107380000 0.3237220000 0.0000050000 1.4226220000 0.0067100000 127085564 0 1784041472 4.0307092667 3.9353711605 4.0532159805 307 1311867728.8545160294 0.1229026467 0.1122887411 0.2360561937 0.0053143804 2.6807250000 0.9120600000 0.1925920000 0.1375180000 1.4258780000 0.0067900000 127087782 0 1785798656 4.0287795067 3.9370949268 4.0497059822 308 1311867728.8860759735 0.1263941228 0.1123345378 0.2360561937 0.0053080260 2.7295140000 0.9024700000 0.3865780000 0.0000050000 1.4267390000 0.0066270000 127090000 0 1784692736 4.0307202339 3.9355618954 4.0524191856 309 1311867728.9193949699 0.1261330098 0.1123791931 0.2360561937 0.0052999058 4.2285500000 0.9031910000 0.2228050000 0.1375960000 1.4191850000 1.5396490000 127092154 0 1783775232 4.0301842690 3.9353954792 4.0528779030 310 1311867728.9585559368 0.1229580939 0.1124133186 0.2360561937 0.0053112396 2.7389490000 0.9101400000 0.3954000000 0.0000050000 1.4207690000 0.0067030000 127094532 0 1785552896 4.0288538933 3.9373309612 4.0503463745 311 1311867728.9886839390 0.1244393289 0.1124519874 0.2360561937 0.0053071879 2.8814740000 0.9172070000 0.3880220000 0.1384930000 1.4240710000 0.0066850000 127096622 0 1784422400 4.0292468071 3.9354882240 4.0516219139 312 1311867729.0231020451 0.1219966561 0.1124825793 0.2360561937 0.0053012186 2.7281410000 0.9111330000 0.3853080000 0.0000050000 1.4188570000 0.0066740000 127098872 0 1783681024 4.0281896591 3.9370286465 4.0502858162 313 1311867729.0583839417 0.1197180375 0.1125056958 0.2360561937 0.0053001393 4.3505490000 0.9151530000 0.3265570000 0.1378650000 1.4246800000 1.5403180000 127101122 0 1785290752 4.0262675285 3.9378130436 4.0498628616 314 1311867729.0882170200 0.1166140586 0.1125187797 0.2360561937 0.0052930442 2.7308350000 0.9043700000 0.3925190000 0.0000050000 1.4202520000 0.0067270000 127103276 0 1784168448 4.0239367485 3.9388608932 4.0476794243 315 1311867729.1263229847 0.1173053831 0.1125339753 0.2360561937 0.0053061497 2.6937020000 0.9015220000 0.2250230000 0.1371170000 1.4171800000 0.0066520000 127105558 0 1783554048 4.0240974426 3.9398293495 4.0495433807 316 1311867729.1556320190 0.1157138720 0.1125440383 0.2360561937 0.0053015175 2.6679090000 0.9460560000 0.2848480000 0.0000050000 1.4243040000 0.0067480000 127107680 0 1785270272 4.0232348442 3.9411952496 4.0478944778 317 1311867729.1888830662 0.1160848066 0.1125552079 0.2360561937 0.0053282879 4.4112920000 0.9287780000 0.3821260000 0.1379860000 1.4182920000 1.5371800000 127109898 0 1784418304 4.0227847099 3.9406857491 4.0481281281 318 1311867729.2240469456 0.1105632931 0.1125489440 0.2360561937 0.0053333942 2.7393020000 0.9193050000 0.3866400000 0.0000050000 1.4204330000 0.0067590000 127112116 0 1783263232 4.0189132690 3.9427192211 4.0449109077 319 1311867729.2579979897 0.1116490513 0.1125461230 0.2360561937 0.0053251860 2.6741940000 0.9094630000 0.1920070000 0.1369870000 1.4230500000 0.0067060000 127114366 0 1785016320 4.0179314613 3.9405353069 4.0468311310 320 1311867729.2880148888 0.1147912294 0.1125531390 0.2360561937 0.0053239420 2.7278080000 0.9198520000 0.3824250000 0.0000040000 1.4118690000 0.0068110000 127116520 0 1784197120 4.0174450874 3.9375798702 4.0515298843 321 1311867729.3236539364 0.1091207936 0.1125424463 0.2360561937 0.0053244637 4.4147920000 0.9276790000 0.3894190000 0.1369750000 1.4209490000 1.5335550000 127118738 0 1783046144 4.0132679939 3.9395532608 4.0495457649 322 1311867729.3580930233 0.1049194708 0.1125187725 0.2360561937 0.0053288762 2.6296950000 0.9390480000 0.2561440000 0.0000050000 1.4218220000 0.0066900000 127120988 0 1784782848 4.0106287003 3.9398849010 4.0475907326 323 1311867729.3882780075 0.1064861268 0.1125000956 0.2360561937 0.0053301799 2.8575510000 0.9218490000 0.3722810000 0.1370790000 1.4126590000 0.0067720000 127123110 0 1783533568 4.0101327896 3.9388747215 4.0506210327 324 1311867729.4253289700 0.1033744141 0.1124719299 0.2360561937 0.0053253958 2.7663620000 0.9423060000 0.3896060000 0.0000040000 1.4209580000 0.0070230000 127125392 0 1782775808 4.0083956718 3.9403634071 4.0497632027 325 1311867729.4572670460 0.1036045775 0.1124446457 0.2360561937 0.0053191574 4.2115220000 0.8989150000 0.2245960000 0.1358710000 1.4133860000 1.5326430000 127127578 0 1784508416 4.0084681511 3.9393684864 4.0503144264 326 1311867729.4887750149 0.1008278057 0.1124090112 0.2360561937 0.0053291990 2.7220910000 0.9077090000 0.3862930000 0.0000040000 1.4144970000 0.0067290000 127129796 0 1783791616 4.0078344345 3.9400374889 4.0479421616 327 1311867729.5223650932 0.1015720516 0.1123758707 0.2360561937 0.0053225806 2.8533910000 0.9085620000 0.3746470000 0.1364870000 1.4205210000 0.0068050000 127131982 0 1782538240 4.0074257851 3.9389729500 4.0497555733 328 1311867729.5603790283 0.0996175632 0.1123369734 0.2360561937 0.0053173238 2.7128110000 0.8946450000 0.3928550000 0.0000040000 1.4124920000 0.0066740000 127134264 0 1784127488 4.0067825317 3.9393565655 4.0486531258 329 1311867729.5890150070 0.0988046750 0.1122958418 0.2360561937 0.0053095377 4.3805800000 0.9009730000 0.3874830000 0.1360730000 1.4177140000 1.5322920000 127136386 0 1785778176 4.0071711540 3.9392805099 4.0476260185 330 1311867729.6254830360 0.0983528271 0.1122535902 0.2360561937 0.0053049349 2.7060030000 0.8987490000 0.3782380000 0.0000040000 1.4150770000 0.0067060000 127138636 0 1784807424 4.0064620972 3.9391217232 4.0487656593 331 1311867729.6614611149 0.0957967713 0.1122038718 0.2360561937 0.0053007041 2.7617110000 0.9121710000 0.2902800000 0.1361840000 1.4100380000 0.0066990000 127140886 0 1783398400 4.0060935020 3.9400043488 4.0468540192 332 1311867729.6888220310 0.0939256474 0.1121488169 0.2360561937 0.0052940614 2.5782850000 0.8916350000 0.2571230000 0.0000050000 1.4167070000 0.0067160000 127142944 0 1785024512 4.0045642853 3.9399859905 4.0459017754 333 1311867729.7230739594 0.0922603384 0.1120890917 0.2360561937 0.0052874099 4.2764080000 0.8961390000 0.2903360000 0.1359810000 1.4093510000 1.5375460000 127145194 0 1784029184 4.0031628609 3.9404661655 4.0458498001 334 1311867729.7570610046 0.0888888240 0.1120196298 0.2360561937 0.0052828218 2.6092940000 0.9286790000 0.2570660000 0.0000050000 1.4105190000 0.0066930000 127147316 0 1782902784 4.0025119781 3.9422552586 4.0434751511 335 1311867729.7899730206 0.0817666948 0.1119293226 0.2360561937 0.0052832204 2.8759800000 0.9137650000 0.3887590000 0.1366010000 1.4239540000 0.0067020000 127149534 0 1784381440 3.9987318516 3.9445660114 4.0377764702 336 1311867729.8264250755 0.0861043930 0.1118524626 0.2360561937 0.0052965782 2.7461430000 0.9455530000 0.3780090000 0.0000040000 1.4097470000 0.0066770000 127151752 0 1786179584 3.9987807274 3.9417777061 4.0435843468 337 1311867729.8550031185 0.0792955980 0.1117558547 0.2360561937 0.0052938688 4.4015090000 0.9213300000 0.3847670000 0.1361450000 1.4184930000 1.5335090000 127153874 0 1785077760 3.9953155518 3.9450960159 4.0392541885 338 1311867729.8881840706 0.0778796673 0.1116556293 0.2360561937 0.0052940474 2.7350330000 0.9210080000 0.3845610000 0.0000040000 1.4163860000 0.0066800000 127156124 0 1783934976 3.9957761765 3.9452345371 4.0369081497 339 1311867729.9233629704 0.0696572810 0.1115317404 0.2360561937 0.0052965690 2.7506960000 0.9011440000 0.2856220000 0.1345360000 1.4164500000 0.0067990000 127158342 0 1785524224 3.9897429943 3.9486331940 4.0322766304 340 1311867729.9569330215 0.0722553059 0.1114162215 0.2360561937 0.0052922104 2.6623250000 0.9155560000 0.3163140000 0.0000040000 1.4165700000 0.0067110000 127160560 0 1784553472 3.9916408062 3.9478542805 4.0347971916 341 1311867729.9865698814 0.0679179281 0.1112886605 0.2360561937 0.0052923179 4.3914820000 0.9079320000 0.3851590000 0.1353070000 1.4137850000 1.5429950000 127162682 0 1783410688 3.9885668755 3.9490344524 4.0314707756 342 1311867730.0230469704 0.0652562156 0.1111540627 0.2360561937 0.0052857211 2.7173410000 0.9084190000 0.3807050000 0.0000040000 1.4152700000 0.0067850000 127164932 0 1784897536 3.9865701199 3.9499325752 4.0298838615 343 1311867730.0557899475 0.0633787885 0.1110147762 0.2360561937 0.0052805798 2.7556130000 0.8994880000 0.2868410000 0.1347540000 1.4205990000 0.0067610000 127167150 0 1783635968 3.9849746227 3.9509696960 4.0293769836 344 1311867730.0871100426 0.0637795329 0.1108774644 0.2360561937 0.0052730954 2.5581980000 0.9427470000 0.1887710000 0.0000040000 1.4135820000 0.0067970000 127169336 0 1782648832 3.9853444099 3.9507167339 4.0295009613 345 1311867730.1231229305 0.0629292578 0.1107384841 0.2360561937 0.0052661519 4.3876410000 0.9057770000 0.3856800000 0.1347580000 1.4196750000 1.5355640000 127171586 0 1784127488 3.9846377373 3.9511063099 4.0290017128 346 1311867730.1568520069 0.0615907051 0.1105964385 0.2360561937 0.0052595338 2.7124530000 0.8949790000 0.3831080000 0.0000040000 1.4214180000 0.0066710000 127173804 0 1785778176 3.9854972363 3.9527359009 4.0277338028 347 1311867730.1882419586 0.0593630448 0.1104487919 0.2360561937 0.0052550561 2.8699650000 0.9201580000 0.3842830000 0.1345830000 1.4169480000 0.0067810000 127175958 0 1784807424 3.9855504036 3.9543342590 4.0256237984 348 1311867730.2224810123 0.0585939437 0.1102997837 0.2360561937 0.0052480203 2.7303250000 0.9147780000 0.3806630000 0.0000050000 1.4217870000 0.0067380000 127178208 0 1783664640 3.9847304821 3.9547643661 4.0258264542 349 1311867730.2575879097 0.0592126660 0.1101534022 0.2360561937 0.0052436369 4.3945930000 0.9194180000 0.3836700000 0.1346030000 1.4114120000 1.5392020000 127180426 0 1785270272 3.9878096581 3.9560899734 4.0253486633 350 1311867730.2914879322 0.0591649227 0.1100077209 0.2360561937 0.0052379107 2.7374790000 0.9241280000 0.3892390000 0.0000040000 1.4100660000 0.0068450000 127182644 0 1784299520 3.9880135059 3.9568753242 4.0260362625 351 1311867730.3230810165 0.0598716624 0.1098648831 0.2360561937 0.0052355742 2.8717770000 0.9294030000 0.3849510000 0.1346060000 1.4095130000 0.0068190000 127184830 0 1782882304 3.9901211262 3.9574496746 4.0255393982 352 1311867730.3554260731 0.0577715039 0.1097168905 0.2360561937 0.0052339769 2.6639650000 0.9194470000 0.3230980000 0.0000040000 1.4082610000 0.0068090000 127187016 0 1784508416 3.9870355129 3.9572975636 4.0252327919 353 1311867730.3982920647 0.0595128164 0.1095746694 0.2360561937 0.0052279262 4.3781670000 0.9354100000 0.3927270000 0.1341350000 1.3963820000 1.5123630000 127189362 0 1783562240 3.9903256893 3.9579856396 4.0256972313 354 1311867730.4225230217 0.0605244450 0.1094361094 0.2360561937 0.0052336883 2.7356790000 0.9332440000 0.3899690000 0.0000050000 1.3992220000 0.0068470000 127191452 0 1782403072 3.9924545288 3.9592862129 4.0262837410 355 1311867730.4600110054 0.0615485795 0.1093012150 0.2360561937 0.0052267109 2.8074190000 0.9156390000 0.3550230000 0.1335910000 1.3900460000 0.0068820000 127193702 0 1783881728 3.9930012226 3.9586486816 4.0259823799 356 1311867730.4948410988 0.0637297481 0.1091732052 0.2360561937 0.0052213121 2.7132910000 0.9181960000 0.3940890000 0.0000050000 1.3879250000 0.0068770000 127195920 0 1785540608 3.9957087040 3.9585053921 4.0265078545 357 1311867730.5300729275 0.0618921518 0.1090407653 0.2360561937 0.0052156547 4.2314060000 0.9342790000 0.2630190000 0.1337550000 1.3860250000 1.5069630000 127198138 0 1784291328 3.9937226772 3.9591507912 4.0261640549 358 1311867730.5597670078 0.0634391308 0.1089133864 0.2360561937 0.0052102416 2.7266830000 0.9290270000 0.4019510000 0.0000050000 1.3823990000 0.0068800000 127200292 0 1783283712 3.9950604439 3.9587175846 4.0270571709 359 1311867730.5940020084 0.0615210421 0.1087813743 0.2360561937 0.0052071484 2.6969570000 0.9195140000 0.2308150000 0.1332160000 1.4002450000 0.0068020000 127202542 0 1784762368 3.9922430515 3.9587328434 4.0266747475 360 1311867730.6230149269 0.0621482506 0.1086518379 0.2360561937 0.0052095427 2.5466760000 0.9218920000 0.2298220000 0.0000050000 1.3809360000 0.0068650000 127204632 0 1783775232 3.9956140518 3.9605827332 4.0265884399 361 1311867730.6614060402 0.0607092641 0.1085190330 0.2360561937 0.0052032943 4.3410170000 0.9311780000 0.4017010000 0.1329940000 1.3778940000 1.4907980000 127206914 0 1782538240 3.9942100048 3.9606878757 4.0260090828 362 1311867730.6922950745 0.0604026131 0.1083861147 0.2360561937 0.0051972305 2.7232980000 0.9309410000 0.3985590000 0.0000050000 1.3805780000 0.0069050000 127209100 0 1784127488 3.9954111576 3.9616675377 4.0254864693 363 1311867730.7275629044 0.0605553202 0.1082543494 0.2360561937 0.0051994008 2.8560370000 0.9325190000 0.4011690000 0.1335570000 1.3755380000 0.0068410000 127211318 0 1785778176 3.9975440502 3.9626097679 4.0243782997 364 1311867730.7572948933 0.0618543848 0.1081268770 0.2360561937 0.0051957409 2.6043480000 0.9536890000 0.2694960000 0.0000050000 1.3668740000 0.0068270000 127213472 0 1784532992 3.9999387264 3.9630315304 4.0246973038 365 1311867730.7932779789 0.0586795285 0.1079914048 0.2360561937 0.0051902594 4.2144680000 0.9302800000 0.2959780000 0.1330850000 1.3660710000 1.4825620000 127215754 0 1783562240 3.9973328114 3.9640114307 4.0230140686 366 1311867730.8240480423 0.0615621060 0.1078645488 0.2360561937 0.0051872386 2.6279700000 0.9200140000 0.3325010000 0.0000040000 1.3622150000 0.0068130000 127217876 0 1785024512 4.0005331039 3.9625771046 4.0231456757 367 1311867730.8591129780 0.0590134077 0.1077314394 0.2360561937 0.0051836824 2.6878180000 0.9079150000 0.2627900000 0.1322110000 1.3707550000 0.0068810000 127220126 0 1784053760 3.9991121292 3.9642035961 4.0223236084 368 1311867730.8922739029 0.0588772222 0.1075986834 0.2360561937 0.0051782637 2.6966810000 0.9259230000 0.3972120000 0.0000040000 1.3601260000 0.0068270000 127222248 0 1782755328 3.9995470047 3.9647912979 4.0231614113 369 1311867730.9270720482 0.0600345433 0.1074697833 0.2360561937 0.0051737758 4.2919610000 0.9183700000 0.4084050000 0.1323130000 1.3587790000 1.4676240000 127224498 0 1784545280 4.0027327538 3.9659621716 4.0236067772 370 1311867730.9611239433 0.0594076812 0.1073398857 0.2360561937 0.0051725166 2.5841830000 0.9437040000 0.2660280000 0.0000050000 1.3603080000 0.0068770000 127226684 0 1783799808 4.0026021004 3.9667832851 4.0244660378 371 1311867730.9928169250 0.0610039420 0.1072149910 0.2360561937 0.0051717137 2.8307370000 0.9381690000 0.3992680000 0.1335290000 1.3462380000 0.0069390000 127228870 0 1783545856 4.0057539940 3.9666719437 4.0241208076 372 1311867731.0221049786 0.0614561401 0.1070919833 0.2360561937 0.0051654933 2.6070670000 0.9709960000 0.2699860000 0.0000050000 1.3527750000 0.0069730000 127231024 0 1785307136 4.0067396164 3.9664189816 4.0242447853 373 1311867731.0609729290 0.0592927597 0.1069638353 0.2360561937 0.0051613445 4.2838250000 0.9445360000 0.4065390000 0.1327720000 1.3396930000 1.4529550000 127233306 0 1784397824 4.0057077408 3.9676980972 4.0241885185 374 1311867731.0900061131 0.0610514283 0.1068410748 0.2360561937 0.0051583897 2.6818770000 0.9284440000 0.4042520000 0.0000050000 1.3356500000 0.0068760000 127235428 0 1784180736 4.0079894066 3.9667210579 4.0244522095 375 1311867731.1276559830 0.0627892241 0.1067236032 0.2360561937 0.0051542182 2.8277430000 0.9345510000 0.4084330000 0.1319780000 1.3391590000 0.0068700000 127237710 0 1785942016 4.0112056732 3.9663400650 4.0240674019 376 1311867731.1551880836 0.0614388771 0.1066031651 0.2360561937 0.0051480484 2.6779620000 0.9201910000 0.4101070000 0.0000050000 1.3333840000 0.0069080000 127239832 0 1785200640 4.0107626915 3.9678747654 4.0251355171 377 1311867731.1935870647 0.0610972568 0.1064824598 0.2360561937 0.0051427027 4.2468120000 0.9311160000 0.4086470000 0.1317190000 1.3299000000 1.4387490000 127242082 0 1784532992 4.0114340782 3.9681851864 4.0251078606 378 1311867731.2235820293 0.0618565902 0.1063644019 0.2360561937 0.0051359058 2.4742600000 0.9270800000 0.2006760000 0.0000040000 1.3317930000 0.0070100000 127244268 0 1783808000 4.0126495361 3.9679293633 4.0260424614 379 1311867731.2602028847 0.0604952537 0.1062433751 0.2360561937 0.0051298494 2.8272170000 0.9496250000 0.4111610000 0.1321920000 1.3206470000 0.0069230000 127246486 0 1783672832 4.0129070282 3.9689011574 4.0253977776 380 1311867731.2900059223 0.0604774505 0.1061229385 0.2360561937 0.0051523603 2.6962810000 0.9458910000 0.4130770000 0.0000050000 1.3237980000 0.0069530000 127248640 0 1785176064 4.0141158104 3.9691226482 4.0255675316 381 1311867731.3230779171 0.0604355037 0.1060030240 0.2360561937 0.0051771993 4.2318390000 0.9486160000 0.4078970000 0.1318330000 1.3128180000 1.4232640000 127250858 0 1784545280 4.0153193474 3.9691736698 4.0248994827 382 1311867731.3570859432 0.0683828145 0.1059045417 0.2360561937 0.0052061708 2.6096620000 0.9508870000 0.3379960000 0.0000040000 1.3071850000 0.0070300000 127253108 0 1784291328 4.0258259773 3.9686148167 4.0252747536 383 1311867731.3915760517 0.0632695705 0.1057932233 0.2360561937 0.0052046720 2.8088740000 0.9489770000 0.4069840000 0.1316440000 1.3078100000 0.0070450000 127255294 0 1785921536 4.0209803581 3.9687898159 4.0240230560 384 1311867731.4279849529 0.0639861524 0.1056843507 0.2360561937 0.0052002403 2.6964040000 0.9783810000 0.4055530000 0.0000050000 1.2980340000 0.0070320000 127257576 0 1785200640 4.0227193832 3.9682781696 4.0229969025 385 1311867731.4602010250 0.0586528704 0.1055621910 0.2360561937 0.0052087860 4.1507010000 0.9449410000 0.3691840000 0.1314720000 1.3026430000 1.3958310000 127259762 0 1784672256 4.0171532631 3.9685506821 4.0219082832 386 1311867731.4926180840 0.0552000664 0.1054317192 0.2360561937 0.0052070653 2.6622340000 0.9413110000 0.4073930000 0.0000050000 1.2990530000 0.0070930000 127261948 0 1783926784 4.0148873329 3.9701716900 4.0206050873 387 1311867731.5259540081 0.0571578220 0.1053069804 0.2360561937 0.0052029651 2.7956220000 0.9521200000 0.4117290000 0.1310670000 1.2869760000 0.0070860000 127264134 0 1783783424 4.0190567970 3.9707896709 4.0203595161 388 1311867731.5589148998 0.0552238151 0.1051779001 0.2360561937 0.0052021686 2.4797870000 0.9451330000 0.2328220000 0.0000040000 1.2883360000 0.0069800000 127266320 0 1785442304 4.0186986923 3.9719855785 4.0193872452 389 1311867731.5967359543 0.0518169478 0.1050407254 0.2360561937 0.0052106720 4.1403290000 0.9377520000 0.4094450000 0.1301990000 1.2807310000 1.3747300000 127268634 0 1784700928 4.0152640343 3.9726126194 4.0190415382 390 1311867731.6247410774 0.0522913709 0.1049054707 0.2360561937 0.0052131125 2.4677000000 0.9415120000 0.2375240000 0.0000050000 1.2749600000 0.0069570000 127270724 0 1784291328 4.0154461861 3.9721577168 4.0194973946 391 1311867731.6616659164 0.0511708073 0.1047680419 0.2360561937 0.0052184565 2.5955140000 0.9396830000 0.2383210000 0.1301350000 1.2738930000 0.0070060000 127273006 0 1785921536 4.0146632195 3.9726264477 4.0196022987 392 1311867731.6925039291 0.0504489504 0.1046294728 0.2360561937 0.0052199234 2.4438290000 0.9568990000 0.1987600000 0.0000040000 1.2736200000 0.0069900000 127275160 0 1785032704 4.0148024559 3.9730927944 4.0194416046 393 1311867731.7299311161 0.0487560183 0.1044873011 0.2360561937 0.0052148773 4.0883380000 0.9351240000 0.3789820000 0.1292720000 1.2754380000 1.3628230000 127277442 0 1784926208 4.0127739906 3.9726543427 4.0198197365 394 1311867731.7615330219 0.0466335043 0.1043404641 0.2360561937 0.0052111520 2.6416190000 0.9493230000 0.4100480000 0.0000050000 1.2676550000 0.0070410000 127279628 0 1784164352 4.0105566978 3.9726171494 4.0196061134 395 1311867731.7939310074 0.0446803384 0.1041894258 0.2360561937 0.0052062188 2.7693860000 0.9406780000 0.4212790000 0.1300090000 1.2636900000 0.0069690000 127281814 0 1783926784 4.0089278221 3.9731144905 4.0195550919 396 1311867731.8252151012 0.0470610559 0.1040451622 0.2360561937 0.0052152145 2.6641740000 0.9713710000 0.4172450000 0.0000050000 1.2618820000 0.0070460000 127283968 0 1785561088 4.0116834641 3.9715723991 4.0192875862 397 1311867731.8593230247 0.0445543677 0.1038953113 0.2360561937 0.0052291340 3.9622770000 0.9470940000 0.2691930000 0.1293520000 1.2595960000 1.3495380000 127286186 0 1784819712 4.0093512535 3.9718899727 4.0186743736 398 1311867731.8910930157 0.0447210930 0.1037466324 0.2360561937 0.0052352143 2.4866800000 0.9396760000 0.2699610000 0.0000050000 1.2632560000 0.0070210000 127288404 0 1784291328 4.0106840134 3.9720962048 4.0182356834 399 1311867731.9224479198 0.0456041619 0.1036009119 0.2360561937 0.0052296364 2.5965560000 0.9309730000 0.2683250000 0.1288570000 1.2547590000 0.0069680000 127290590 0 1786068992 4.0125956535 3.9720044136 4.0177054405 400 1311867731.9598410130 0.0450581349 0.1034545550 0.2360561937 0.0052234234 2.6512030000 0.9730070000 0.4121620000 0.0000040000 1.2514280000 0.0069810000 127292808 0 1785208832 4.0128145218 3.9721508026 4.0172514915 401 1311867731.9915709496 0.0411754809 0.1032992456 0.2360561937 0.0052224415 4.0742840000 0.9361500000 0.4060950000 0.1288500000 1.2501840000 1.3462250000 127294994 0 1784676352 4.0094118118 3.9734747410 4.0165386200 402 1311867732.0239229202 0.0400072671 0.1031418028 0.2360561937 0.0052241544 2.6030730000 0.9334880000 0.4075730000 0.0000050000 1.2473610000 0.0069860000 127297180 0 1783533568 4.0082507133 3.9721958637 4.0158629417 403 1311867732.0619950294 0.0404768959 0.1029863068 0.2360561937 0.0052191501 2.7338940000 0.9325720000 0.4056310000 0.1282880000 1.2535290000 0.0070430000 127299462 0 1783025664 4.0091061592 3.9721586704 4.0149750710 404 1311867732.0918290615 0.0368015207 0.1028224831 0.2360561937 0.0052253196 2.6272010000 0.9600430000 0.4028950000 0.0000050000 1.2505540000 0.0069690000 127301616 0 1784655872 4.0053634644 3.9732396603 4.0141091347 405 1311867732.1221950054 0.0384965986 0.1026636537 0.2360561937 0.0052315472 4.0150650000 0.9201620000 0.3674750000 0.1277200000 1.2542970000 1.3379140000 127303802 0 1783554048 4.0078234673 3.9719588757 4.0131392479 406 1311867732.1605980396 0.0360945128 0.1024996903 0.2360561937 0.0052300666 2.5992480000 0.9224450000 0.4038170000 0.0000050000 1.2591390000 0.0069930000 127306052 0 1782521856 4.0058469772 3.9728128910 4.0123386383 407 1311867732.1931400299 0.0349144787 0.1023336333 0.2360561937 0.0052413845 2.5440130000 0.9171420000 0.2316510000 0.1276330000 1.2538960000 0.0069340000 127308270 0 1784020992 4.0062527657 3.9739677906 4.0116672516 408 1311867732.2232089043 0.0349072441 0.1021683725 0.2360561937 0.0052675385 2.6487390000 0.9706020000 0.4017360000 0.0000040000 1.2628130000 0.0069510000 127310392 0 1785651200 4.0059437752 3.9730806351 4.0108079910 409 1311867732.2590498924 0.0336005352 0.1020007250 0.2360561937 0.0053342948 3.9799060000 0.9108520000 0.3312490000 0.1274640000 1.2558900000 1.3467900000 127312642 0 1784676352 4.0059852600 3.9751644135 4.0102434158 410 1311867732.2903969288 0.0316501148 0.1018291382 0.2360561937 0.0053504804 2.4221190000 0.9122020000 0.2367940000 0.0000040000 1.2591770000 0.0070260000 127314828 0 1783795712 4.0031886101 3.9746379852 4.0103092194 411 1311867732.3218240738 0.0315741263 0.1016582014 0.2360561937 0.0053472773 2.5424400000 0.9157350000 0.2311520000 0.1275920000 1.2542940000 0.0070050000 127317014 0 1785552896 4.0030236244 3.9738354683 4.0095648766 412 1311867732.3607840538 0.0317697600 0.1014885692 0.2360561937 0.0053408210 2.6126360000 0.9408190000 0.4017530000 0.0000050000 1.2554190000 0.0069380000 127319296 0 1784422400 4.0058078766 3.9749596119 4.0089244843 413 1311867732.3899528980 0.0299842022 0.1013154352 0.2360561937 0.0053360778 4.0423880000 0.9040390000 0.4052840000 0.1264660000 1.2525330000 1.3471280000 127321418 0 1783681024 4.0040659904 3.9752066135 4.0084195137 414 1311867732.4218940735 0.0306879506 0.1011448374 0.2360561937 0.0053317474 2.5779800000 0.9128610000 0.4005250000 0.0000050000 1.2508360000 0.0069610000 127323636 0 1785180160 4.0054674149 3.9740798473 4.0074663162 415 1311867732.4593050480 0.0288684890 0.1009706775 0.2360561937 0.0053297513 2.7099100000 0.9110280000 0.4033250000 0.1267200000 1.2541360000 0.0069310000 127325886 0 1783787520 4.0051741600 3.9755964279 4.0069060326 416 1311867732.4918489456 0.0273304489 0.1007936577 0.2360561937 0.0053270210 2.6113630000 0.9440200000 0.4002940000 0.0000040000 1.2531640000 0.0070140000 127328104 0 1782898688 4.0030937195 3.9753422737 4.0063529015 417 1311867732.5229809284 0.0287573580 0.1006209088 0.2360561937 0.0053295558 4.0602360000 0.9374340000 0.4035200000 0.1268440000 1.2496310000 1.3360600000 127330258 0 1784676352 4.0079030991 3.9761371613 4.0053005219 418 1311867732.5698928833 0.0256391875 0.1004415267 0.2360561937 0.0053279084 2.4862310000 0.9149550000 0.3015680000 0.0000050000 1.2548760000 0.0070160000 127332668 0 1783279616 4.0056266785 3.9779517651 4.0051784515 419 1311867732.5926280022 0.0237640962 0.1002585257 0.2360561937 0.0053252452 2.6937470000 0.9038740000 0.4051680000 0.1255530000 1.2452670000 0.0069980000 127334726 0 1782386688 4.0024595261 3.9779148102 4.0048437119 420 1311867732.6242370605 0.0243703425 0.1000778395 0.2360561937 0.0053275610 2.5753260000 0.9384400000 0.3733880000 0.0000040000 1.2497630000 0.0070120000 127336912 0 1784164352 4.0047106743 3.9777555466 4.0040216446 421 1311867732.6630299091 0.0222788248 0.0998930438 0.2360561937 0.0053243328 4.0114700000 0.9118960000 0.4031390000 0.1257880000 1.2414040000 1.3224950000 127339194 0 1785778176 4.0024743080 3.9786248207 4.0041666031 422 1311867732.6922440529 0.0216085296 0.0997075354 0.2360561937 0.0053207439 2.5162800000 0.9289170000 0.3376620000 0.0000040000 1.2348940000 0.0071090000 127341348 0 1784950784 4.0035314560 3.9801163673 4.0040507317 423 1311867732.7260940075 0.0220300443 0.0995239007 0.2360561937 0.0053151038 2.7029130000 0.9146360000 0.4107890000 0.1262000000 1.2372880000 0.0070960000 127343566 0 1784422400 4.0032935143 3.9790654182 4.0034432411 424 1311867732.7601239681 0.0201062970 0.0993365950 0.2360561937 0.0053186047 2.4549580000 0.9053270000 0.3041690000 0.0000050000 1.2307880000 0.0070860000 127345752 0 1783635968 3.9990983009 3.9794929028 4.0031514168 425 1311867732.7919039726 0.0200245623 0.0991499785 0.2360561937 0.0053150227 3.9202870000 0.9167530000 0.3379430000 0.1249740000 1.2305300000 1.3030780000 127347970 0 1783545856 4.0020027161 3.9811868668 4.0030102730 426 1311867732.8280360699 0.0196312461 0.0989633148 0.2360561937 0.0053151736 2.5563750000 0.9134130000 0.4081180000 0.0000050000 1.2210710000 0.0069960000 127350188 0 1785180160 3.9983229637 3.9800732136 4.0024805069 427 1311867732.8589270115 0.0188154150 0.0987756148 0.2360561937 0.0053111018 2.4795220000 0.9206750000 0.2013520000 0.1244980000 1.2182080000 0.0069860000 127352374 0 1784418304 3.9985458851 3.9813289642 4.0023550987 428 1311867732.8912909031 0.0179382712 0.0985867425 0.2360561937 0.0053085039 2.6041130000 0.9595760000 0.4153270000 0.0000050000 1.2151450000 0.0071120000 127354560 0 1784184832 3.9963130951 3.9820499420 4.0023145676 429 1311867732.9262781143 0.0174430534 0.0983975964 0.2360561937 0.0053025155 3.9234190000 0.9374980000 0.3757230000 0.1241140000 1.2050490000 1.2741790000 127356810 0 1785942016 3.9971292019 3.9831531048 4.0026865005 430 1311867732.9602870941 0.0183698889 0.0982114854 0.2360561937 0.0053025494 2.5557970000 0.9262480000 0.4095020000 0.0000050000 1.2052050000 0.0071040000 127358996 0 1785069568 3.9958143234 3.9813985825 4.0026364326 431 1311867732.9987640381 0.0179505777 0.0980252652 0.2360561937 0.0052984721 2.4980910000 0.9266200000 0.2390300000 0.1240240000 1.1943650000 0.0070560000 127361310 0 1784926208 3.9978775978 3.9820196629 4.0025749207 432 1311867733.0276939869 0.0175995100 0.0978390945 0.2360561937 0.0052976730 2.5776030000 0.9518710000 0.4153910000 0.0000050000 1.1955270000 0.0071000000 127363464 0 1784016896 3.9936287403 3.9824004173 4.0032863617 433 1311867733.0607628822 0.0189891979 0.0976569931 0.2360561937 0.0053154513 3.9096590000 0.9279490000 0.4219940000 0.1234360000 1.1834260000 1.2457880000 127365650 0 1783926784 3.9949328899 3.9803333282 4.0032043457 434 1311867733.0977020264 0.0178258866 0.0974730505 0.2360561937 0.0053125568 2.5482470000 0.9360700000 0.4118660000 0.0000050000 1.1863320000 0.0071170000 127367900 0 1785696256 3.9942288399 3.9816143513 4.0032653809 435 1311867733.1263020039 0.0174004715 0.0972889756 0.2360561937 0.0053105523 2.6823760000 0.9357460000 0.4199890000 0.1231260000 1.1885280000 0.0071160000 127370022 0 1784807424 3.9907586575 3.9830217361 4.0037727356 436 1311867733.1625030041 0.0199105665 0.0971115022 0.2360561937 0.0053121048 2.4404380000 0.9340190000 0.3120230000 0.0000050000 1.1802830000 0.0071460000 127372272 0 1784553472 3.9899661541 3.9798555374 4.0034976006 437 1311867733.1926651001 0.0196752846 0.0969343026 0.2360561937 0.0053109668 3.8397100000 0.9398710000 0.3419880000 0.1231500000 1.1865560000 1.2404450000 127374426 0 1783799808 3.9882516861 3.9807841778 4.0035910606 438 1311867733.2259631157 0.0185478590 0.0967553381 0.2360561937 0.0053081720 2.4318890000 0.9256970000 0.3132370000 0.0000050000 1.1787830000 0.0070720000 127376644 0 1783549952 3.9891154766 3.9824669361 4.0039057732 439 1311867733.2618060112 0.0201226845 0.0965807763 0.2360561937 0.0053062039 2.6558550000 0.9246820000 0.4215210000 0.1220960000 1.1735610000 0.0070980000 127378894 0 1785290752 3.9865169525 3.9819092751 4.0039582253 440 1311867733.2919199467 0.0211697854 0.0964093876 0.2360561937 0.0053016140 2.3887140000 0.9632230000 0.2392550000 0.0000050000 1.1711940000 0.0071020000 127381016 0 1784164352 3.9847276211 3.9814114571 4.0036292076 441 1311867733.3300418854 0.0200804286 0.0962363061 0.2360561937 0.0053086249 3.8763310000 0.9325140000 0.4237170000 0.1219370000 1.1684840000 1.2226360000 127383298 0 1783926784 3.9864194393 3.9817154408 4.0035529137 442 1311867733.3602790833 0.0200256761 0.0960638839 0.2360561937 0.0053068288 2.5519960000 0.9438690000 0.4179710000 0.0000050000 1.1759520000 0.0071510000 127385484 0 1785688064 3.9882011414 3.9804780483 4.0029320717 443 1311867733.3923840523 0.0224036444 0.0958976079 0.2360561937 0.0053098115 2.5045480000 0.9250490000 0.2733210000 0.1224680000 1.1685740000 0.0071190000 127387670 0 1784545280 3.9840593338 3.9804878235 4.0029058456 444 1311867733.4289550781 0.0223543644 0.0957319700 0.2360561937 0.0053072885 2.3958020000 0.9683670000 0.2368680000 0.0000050000 1.1762350000 0.0071050000 127389920 0 1784295424 3.9830272198 3.9822096825 4.0029015541 445 1311867733.4588150978 0.0218509808 0.0955659453 0.2360561937 0.0053049656 3.8531940000 0.9198550000 0.4154650000 0.1213220000 1.1709050000 1.2186550000 127392010 0 1786052608 3.9841463566 3.9817094803 4.0024046898 446 1311867733.4956119061 0.0220564548 0.0954011258 0.2360561937 0.0053000645 2.5262430000 0.9270680000 0.4126020000 0.0000050000 1.1714530000 0.0071610000 127394196 0 1784954880 3.9837970734 3.9819061756 4.0021800995 447 1311867733.5290400982 0.0226350594 0.0952383382 0.2360561937 0.0052967395 2.5394910000 0.9218540000 0.3118210000 0.1211670000 1.1704200000 0.0072180000 127396414 0 1784426496 3.9821639061 3.9828860760 4.0023269653 448 1311867733.5630290508 0.0219813492 0.0950748181 0.2360561937 0.0052913903 2.4293690000 0.9770180000 0.2738230000 0.0000050000 1.1643450000 0.0071870000 127398632 0 1783558144 3.9832975864 3.9828395844 4.0021319389 449 1311867733.5922229290 0.0248165838 0.0949183410 0.2360561937 0.0052896356 3.8494740000 0.9268120000 0.4157810000 0.1210870000 1.1635950000 1.2151020000 127400754 0 1783173120 3.9806563854 3.9813292027 4.0017228127 450 1311867733.6283020973 0.0265887659 0.0947664975 0.2360561937 0.0052872123 2.5128170000 0.9207350000 0.4134560000 0.0000050000 1.1644390000 0.0071580000 127403004 0 1784782848 3.9786829948 3.9814283848 4.0020394325 451 1311867733.6601879597 0.0259424709 0.0946138943 0.2360561937 0.0052818656 2.6196020000 0.9325410000 0.3833040000 0.1208540000 1.1678690000 0.0071330000 127405190 0 1783676928 3.9791867733 3.9818468094 4.0017533302 452 1311867733.6917510033 0.0263925064 0.0944629620 0.2360561937 0.0052777059 2.3323710000 0.9521010000 0.2060650000 0.0000040000 1.1598400000 0.0072770000 127407376 0 1783169024 3.9790749550 3.9812977314 4.0014729500 453 1311867733.7288239002 0.0280234851 0.0943162965 0.2360561937 0.0052745777 3.8311750000 0.9279810000 0.4145620000 0.1201750000 1.1633210000 1.1982090000 127409626 0 1784799232 3.9781999588 3.9800884724 4.0014495850 454 1311867733.7597820759 0.0310060699 0.0941768467 0.2360561937 0.0052705587 2.4726000000 0.9197600000 0.3769260000 0.0000050000 1.1608090000 0.0072370000 127411748 0 1784037376 3.9751911163 3.9795804024 4.0017805099 455 1311867733.7924160957 0.0300154015 0.0940358325 0.2360561937 0.0052943761 2.6307610000 0.9233800000 0.4135150000 0.1199770000 1.1596090000 0.0071580000 127413934 0 1783533568 3.9762837887 3.9797916412 4.0018444061 456 1311867733.8282589912 0.0343489386 0.0939049402 0.2360561937 0.0052986816 2.5503290000 0.9585700000 0.4137420000 0.0000050000 1.1636560000 0.0072040000 127416184 0 1785290752 3.9731056690 3.9777929783 4.0014510155 457 1311867733.8608579636 0.0315181166 0.0937684264 0.2360561937 0.0052955261 3.8419460000 0.9421690000 0.4092940000 0.1199050000 1.1623670000 1.2002510000 127418306 0 1784168448 3.9760017395 3.9790084362 4.0008993149 458 1311867733.8918149471 0.0332653336 0.0936363236 0.2360561937 0.0052913269 2.5266680000 0.9278150000 0.4171480000 0.0000050000 1.1673680000 0.0071660000 127420428 0 1783406592 3.9743678570 3.9792077541 4.0008287430 459 1311867733.9289460182 0.0346578509 0.0935078302 0.2360561937 0.0052862869 2.4689930000 0.9326330000 0.2375250000 0.1196990000 1.1648150000 0.0072530000 127422678 0 1785044992 3.9738948345 3.9777855873 4.0002870560 460 1311867733.9595899582 0.0381930359 0.0933875806 0.2360561937 0.0052911921 2.4730670000 0.9437130000 0.3412980000 0.0000050000 1.1729460000 0.0071770000 127424864 0 1783930880 3.9709229469 3.9760785103 4.0001864433 461 1311867733.9941790104 0.0384781174 0.0932684711 0.2360561937 0.0052888937 3.8011220000 0.9066260000 0.4050600000 0.1192240000 1.1655590000 1.1974120000 127427082 0 1783422976 3.9712879658 3.9762737751 4.0004539490 462 1311867734.0275731087 0.0436355732 0.0931610406 0.2360561937 0.0053046835 2.4918940000 0.9010330000 0.4099190000 0.0000050000 1.1667750000 0.0070990000 127429332 0 1785180160 3.9668121338 3.9734227657 4.0005602837 463 1311867734.0599920750 0.0417438559 0.0930499884 0.2360561937 0.0053003636 2.6291760000 0.9141870000 0.4096990000 0.1189410000 1.1712210000 0.0071640000 127431486 0 1784422400 3.9688658714 3.9740436077 4.0002508163 464 1311867734.0956780910 0.0410394371 0.0929378967 0.2360561937 0.0052955339 2.4697750000 0.9219340000 0.3731230000 0.0000040000 1.1602680000 0.0071900000 127433736 0 1783533568 3.9698543549 3.9742181301 4.0002312660 465 1311867734.1274170876 0.0443525873 0.0928334121 0.2360561937 0.0052935414 3.7988010000 0.9067550000 0.4103360000 0.1188860000 1.1663990000 1.1893670000 127435954 0 1785180160 3.9677109718 3.9714052677 3.9997975826 466 1311867734.1618878841 0.0434162803 0.0927273668 0.2360561937 0.0052938003 2.4956480000 0.9127440000 0.4071740000 0.0000040000 1.1605800000 0.0071510000 127438140 0 1784188928 3.9685492516 3.9726734161 3.9994328022 467 1311867734.1942350864 0.0428714231 0.0926206089 0.2360561937 0.0052896113 2.6254490000 0.9152750000 0.4165940000 0.1188610000 1.1601610000 0.0071220000 127440358 0 1783279616 3.9690182209 3.9740273952 3.9994454384 468 1311867734.2291829586 0.0465277992 0.0925221200 0.2360561937 0.0052927008 2.4383280000 0.9558980000 0.3109180000 0.0000050000 1.1571500000 0.0071670000 127442544 0 1784909824 3.9663541317 3.9712707996 3.9992806911 469 1311867734.2607750893 0.0450624190 0.0924209266 0.2360561937 0.0052891779 3.6899690000 0.9259350000 0.3037700000 0.1189490000 1.1546040000 1.1787220000 127444730 0 1783914496 3.9676458836 3.9725682735 3.9991419315 470 1311867734.2941219807 0.0444957241 0.0923189581 0.2360561937 0.0052864264 2.4942920000 0.9096570000 0.4129280000 0.0000050000 1.1573440000 0.0070700000 127446916 0 1783291904 3.9680750370 3.9737417698 3.9995281696 471 1311867734.3263280392 0.0434226431 0.0922151442 0.2360561937 0.0052842491 2.5047860000 0.9216140000 0.3055910000 0.1188030000 1.1445270000 0.0071250000 127449102 0 1785024512 3.9695625305 3.9734945297 3.9994106293 472 1311867734.3610401154 0.0443620645 0.0921137606 0.2360561937 0.0052810952 2.5195680000 0.9418930000 0.4163410000 0.0000040000 1.1462280000 0.0071110000 127451320 0 1784176640 3.9691033363 3.9727754593 3.9997489452 473 1311867734.3941841125 0.0455690809 0.0920153575 0.2360561937 0.0052852074 3.7065580000 0.9358410000 0.3440380000 0.1202600000 1.1399450000 1.1587730000 127453538 0 1783406592 3.9676373005 3.9740087986 4.0004849434 474 1311867734.4276480675 0.0462170728 0.0919187366 0.2360561937 0.0052796812 2.3818430000 0.9282400000 0.3060530000 0.0000040000 1.1332900000 0.0071070000 127455756 0 1785057280 3.9672329426 3.9736723900 4.0006580353 475 1311867734.4586091042 0.0462276936 0.0918225449 0.2360561937 0.0052758849 2.6120260000 0.9269870000 0.4242060000 0.1186770000 1.1269070000 0.0071730000 127457910 0 1783660544 3.9675760269 3.9728844166 4.0010190010 476 1311867734.4938759804 0.0466786847 0.0917277049 0.2360561937 0.0052712439 2.5238240000 0.9646080000 0.4188130000 0.0000060000 1.1259630000 0.0071110000 127460160 0 1783042048 3.9670791626 3.9740574360 4.0014538765 477 1311867734.5300569534 0.0476863310 0.0916353750 0.2360561937 0.0052666628 3.7285160000 0.9413970000 0.4188960000 0.1189930000 1.1089190000 1.1331170000 127462410 0 1784782848 3.9663977623 3.9737849236 4.0020437241 478 1311867734.5595300198 0.0474167615 0.0915428674 0.2360561937 0.0052650619 2.4642250000 0.9208560000 0.4212970000 0.0000050000 1.1068620000 0.0071150000 127464532 0 1783681024 3.9672727585 3.9734003544 4.0024075508 479 1311867734.5953910351 0.0492146239 0.0914544995 0.2360561937 0.0052624794 2.5996040000 0.9336330000 0.4268630000 0.1187710000 1.1057700000 0.0071430000 127466750 0 1782919168 3.9650747776 3.9741160870 4.0034270287 480 1311867734.6285231113 0.0469583236 0.0913617991 0.2360561937 0.0052581960 2.4767800000 0.9502070000 0.4150730000 0.0000050000 1.0971290000 0.0072040000 127468968 0 1784524800 3.9678866863 3.9742455482 4.0030040741 481 1311867734.6593229771 0.0484777242 0.0912726430 0.2360561937 0.0052533363 3.6867370000 0.9275900000 0.4199060000 0.1184760000 1.1005090000 1.1122920000 127471122 0 1783787520 3.9664423466 3.9736182690 4.0029811859 482 1311867734.6947479248 0.0482968837 0.0911834817 0.2360561937 0.0052495844 2.2386390000 0.9247310000 0.2052350000 0.0000060000 1.0941550000 0.0071280000 127473340 0 1782894592 3.9665737152 3.9734020233 4.0032200813 483 1311867734.7310240269 0.0481990688 0.0910944871 0.2360561937 0.0052484364 2.3769820000 0.9354550000 0.2169800000 0.1186700000 1.0913870000 0.0072150000 127475622 0 1784672256 3.9671552181 3.9732131958 4.0032129288 484 1311867734.7607629299 0.0478250980 0.0910050875 0.2360561937 0.0052432765 2.4891390000 0.9571890000 0.4275750000 0.0000040000 1.0890060000 0.0071990000 127477744 0 1783918592 3.9680511951 3.9731202126 4.0030984879 485 1311867734.7976419926 0.0490989052 0.0909186830 0.2360561937 0.0052402963 3.7122920000 0.9566270000 0.4343440000 0.1189350000 1.0897820000 1.1051080000 127480026 0 1783681024 3.9667637348 3.9736723900 4.0035204887 486 1311867734.8298120499 0.0497519448 0.0908339778 0.2360561937 0.0052366365 2.4820260000 0.9473230000 0.4262810000 0.0000060000 1.0940080000 0.0072090000 127482212 0 1785413632 3.9662482738 3.9742088318 4.0038223267 487 1311867734.8645250797 0.0513109230 0.0907528216 0.2360561937 0.0052333039 2.5925570000 0.9554930000 0.4228890000 0.1187390000 1.0800020000 0.0072190000 127484430 0 1784524800 3.9646077156 3.9756495953 4.0046224594 488 1311867734.8943901062 0.0493609384 0.0906680022 0.2360561937 0.0052343361 2.3658180000 0.9515470000 0.3148920000 0.0000060000 1.0847220000 0.0071680000 127486616 0 1784561664 3.9670884609 3.9747231007 4.0042629242 489 1311867734.9263660908 0.0491591468 0.0905831170 0.2360561937 0.0052291218 3.6763710000 0.9517260000 0.4312470000 0.1188880000 1.0759440000 1.0904830000 127488770 0 1784016896 3.9677553177 3.9743530750 4.0045580864 490 1311867734.9631719589 0.0514496043 0.0905032527 0.2360561937 0.0052279959 2.4757900000 0.9510870000 0.4361810000 0.0000050000 1.0738530000 0.0071880000 127490892 0 1783926784 3.9659864902 3.9742066860 4.0045437813 491 1311867734.9948470592 0.0502729453 0.0904213172 0.2360561937 0.0052309309 2.5845880000 0.9451700000 0.4381710000 0.1187930000 1.0679600000 0.0071760000 127493078 0 1785688064 3.9667685032 3.9743385315 4.0042042732 492 1311867735.0292239189 0.0504956916 0.0903401676 0.2360561937 0.0052309798 2.5198340000 0.9886730000 0.4471230000 0.0000060000 1.0685400000 0.0071920000 127495360 0 1784778752 3.9668142796 3.9747335911 4.0040640831 493 1311867735.0596508980 0.0529129989 0.0902642504 0.2360561937 0.0052277268 3.5546650000 0.9589120000 0.3192630000 0.1186670000 1.0672840000 1.0830910000 127497450 0 1784270848 3.9641449451 3.9751591682 4.0045185089 494 1311867735.0952830315 0.0503933132 0.0901835400 0.2360561937 0.0052323333 2.4599760000 0.9482720000 0.4319680000 0.0000060000 1.0653310000 0.0071910000 127499700 0 1785921536 3.9668531418 3.9747397900 4.0042724609 495 1311867735.1313030720 0.0506392233 0.0901036525 0.2360561937 0.0052301308 2.3647010000 0.9510850000 0.2137030000 0.1188630000 1.0656240000 0.0071640000 127501950 0 1785196544 3.9665126801 3.9754645824 4.0045151711 496 1311867735.1603751183 0.0509930588 0.0900248005 0.2360561937 0.0052249429 2.4688150000 0.9623960000 0.4265610000 0.0000050000 1.0652430000 0.0072100000 127504072 0 1785077760 3.9663319588 3.9752576351 4.0047101974 497 1311867735.1994349957 0.0523455329 0.0899489871 0.2360561937 0.0052230205 3.5390520000 0.9629010000 0.2902630000 0.1187630000 1.0685430000 1.0902860000 127506354 0 1784152064 3.9654233456 3.9739019871 4.0050258636 498 1311867735.2263538837 0.0514997840 0.0898717798 0.2360561937 0.0052211450 2.4719540000 0.9512130000 0.4314570000 0.0000060000 1.0745640000 0.0072120000 127508508 0 1783898112 3.9660787582 3.9753062725 4.0052924156 499 1311867735.2655019760 0.0510077439 0.0897938960 0.2360561937 0.0052165908 2.6059960000 0.9600960000 0.4277370000 0.1187530000 1.0848360000 0.0071980000 127510758 0 1785667584 3.9665651321 3.9761250019 4.0055723190 500 1311867735.2961549759 0.0524555221 0.0897192193 0.2360561937 0.0052189756 2.4950560000 0.9592000000 0.4393890000 0.0000050000 1.0809450000 0.0072890000 127512944 0 1784782848 3.9654211998 3.9749135971 4.0063524246 501 1311867735.3321089745 0.0514527149 0.0896428390 0.2360561937 0.0052169891 3.6025380000 1.0018220000 0.2860100000 0.1187880000 1.0896300000 1.0988480000 127515194 0 1784311808 3.9663207531 3.9761836529 4.0066351891 502 1311867735.3666970730 0.0523629747 0.0895685763 0.2360561937 0.0052194892 2.3136980000 0.9670060000 0.2476600000 0.0000050000 1.0843200000 0.0073020000 127517348 0 1786068992 3.9657714367 3.9754462242 4.0070357323 503 1311867735.3943350315 0.0529557616 0.0894957874 0.2360561937 0.0052322097 2.6460640000 0.9900090000 0.4348110000 0.1189210000 1.0867250000 0.0073510000 127519438 0 1785180160 3.9654154778 3.9756813049 4.0073261261 504 1311867735.4322299957 0.0552904345 0.0894279197 0.2360561937 0.0052341583 2.3788160000 0.9836270000 0.2870970000 0.0000050000 1.0931000000 0.0073770000 127521752 0 1784676352 3.9630203247 3.9766032696 4.0077395439 505 1311867735.4628560543 0.0534850582 0.0893567457 0.2360561937 0.0052308944 3.7154950000 0.9975360000 0.3917390000 0.1189530000 1.0905570000 1.1083170000 127523906 0 1783549952 3.9655833244 3.9767026901 4.0076923370 506 1311867735.4973869324 0.0556300916 0.0892900922 0.2360561937 0.0052293597 2.5088780000 0.9658470000 0.4305970000 0.0000050000 1.0976280000 0.0072220000 127526156 0 1783042048 3.9630169868 3.9769690037 4.0083785057 507 1311867735.5293200016 0.0552108586 0.0892228748 0.2360561937 0.0052250410 2.4124250000 0.9722260000 0.2124510000 0.1189480000 1.0941720000 0.0073100000 127528310 0 1784782848 3.9636893272 3.9769213200 4.0087018013 508 1311867735.5632629395 0.0547615886 0.0891550376 0.2360561937 0.0052205225 2.5337570000 0.9868380000 0.4344280000 0.0000050000 1.0969500000 0.0072540000 127530560 0 1783660544 3.9644799232 3.9763855934 4.0089507103 509 1311867735.5976569653 0.0557032488 0.0890893170 0.2360561937 0.0052158657 3.4769450000 0.9736570000 0.1781930000 0.1189550000 1.0900590000 1.1084450000 127532778 0 1782779904 3.9637260437 3.9765264988 4.0091609955 510 1311867735.6363260746 0.0578134060 0.0890279917 0.2360561937 0.0052154983 2.5412750000 0.9859630000 0.4474510000 0.0000050000 1.0932070000 0.0073120000 127535028 0 1784528896 3.9619476795 3.9757964611 4.0093717575 511 1311867735.6626520157 0.0572562814 0.0889658161 0.2360561937 0.0052145481 2.5993540000 1.0008050000 0.3648560000 0.1189960000 1.0990890000 0.0073490000 127537150 0 1783427072 3.9628515244 3.9749274254 4.0091629028 512 1311867735.6952130795 0.0552302897 0.0888999264 0.2360561937 0.0052137661 2.3193050000 0.9866220000 0.2148070000 0.0000050000 1.1029750000 0.0073150000 127539336 0 1782513664 3.9649467468 3.9749429226 4.0086083412 513 1311867735.7291250229 0.0553390384 0.0888345056 0.2360561937 0.0052126241 3.7694540000 0.9866260000 0.4314990000 0.1189890000 1.0993800000 1.1253660000 127582514 0 1784307712 3.9649651051 3.9754638672 4.0083794594 514 1311867735.7631659508 0.0559154898 0.0887704608 0.2360561937 0.0052119414 2.3484330000 0.9751690000 0.2532440000 0.0000050000 1.1054150000 0.0072580000 127668732 0 1786068992 3.9643213749 3.9769032001 4.0084776878 515 1311867735.7963778973 0.0555766001 0.0887060067 0.2360561937 0.0052132996 2.6389320000 0.9682080000 0.4268870000 0.1189140000 1.1091880000 0.0071870000 127670918 0 1785311232 3.9649176598 3.9768431187 4.0084109306 516 1311867735.8277759552 0.0567534342 0.0886440831 0.2360561937 0.0052189350 2.5580700000 0.9898780000 0.4465790000 0.0000050000 1.1067300000 0.0071950000 127673072 0 1784406016 3.9638655186 3.9777858257 4.0085096359 517 1311867735.8638889790 0.0575127155 0.0885838677 0.2360561937 0.0052151290 3.7738200000 0.9811160000 0.4326400000 0.1189950000 1.1087590000 1.1238960000 127675226 0 1783681024 3.9632477760 3.9780597687 4.0088682175 518 1311867735.8951849937 0.0574771576 0.0885238162 0.2360561937 0.0052111204 2.5363440000 0.9793460000 0.4337230000 0.0000040000 1.1083310000 0.0072380000 127677412 0 1782919168 3.9633126259 3.9785752296 4.0093836784 519 1311867735.9322230816 0.0581161715 0.0884652272 0.2360561937 0.0052079469 2.5240950000 1.0013890000 0.2857700000 0.1190680000 1.1026110000 0.0074210000 127679694 0 1784528896 3.9626471996 3.9796175957 4.0101199150 520 1311867735.9623689651 0.0585904904 0.0884077758 0.2360561937 0.0052054147 2.5315670000 0.9786590000 0.4334510000 0.0000050000 1.1047290000 0.0072480000 127681848 0 1786032128 3.9619410038 3.9799449444 4.0104718208 521 1311867735.9945859909 0.0578804836 0.0883491822 0.2360561937 0.0052020985 3.5663400000 0.9958200000 0.2138840000 0.1190710000 1.1013690000 1.1274650000 127684002 0 1785065472 3.9625220299 3.9803543091 4.0107426643 522 1311867736.0290079117 0.0561816059 0.0882875585 0.2360561937 0.0052000764 2.5633640000 1.0008690000 0.4360160000 0.0000050000 1.1114230000 0.0073310000 127686252 0 1784303616 3.9641120434 3.9809675217 4.0109171867 523 1311867736.0642199516 0.0561767705 0.0882261612 0.2360561937 0.0051972920 2.6692250000 0.9958360000 0.4375170000 0.1192200000 1.1018360000 0.0073710000 127688502 0 1785925632 3.9641604424 3.9803342819 4.0110230446 524 1311867736.0946779251 0.0552278049 0.0881631872 0.2360561937 0.0051951010 2.6010560000 1.0268320000 0.4433130000 0.0000050000 1.1150380000 0.0072840000 127690624 0 1784782848 3.9650371075 3.9809324741 4.0113916397 525 1311867736.1299190521 0.0565102175 0.0881028958 0.2360561937 0.0051978794 3.7755840000 0.9988400000 0.4378710000 0.1192380000 1.0928180000 1.1191620000 127692874 0 1784061952 3.9636013508 3.9807898998 4.0115480423 526 1311867736.1631360054 0.0576992407 0.0880450942 0.2360561937 0.0051942686 2.4981010000 1.0091760000 0.3694260000 0.0000050000 1.1046610000 0.0073060000 127695124 0 1785651200 3.9620611668 3.9807274342 4.0119628906 527 1311867736.1942429543 0.0587480366 0.0879895021 0.2360561937 0.0051958214 2.5485540000 0.9885850000 0.3254380000 0.1195030000 1.0993070000 0.0073170000 127697246 0 1784799232 3.9608514309 3.9810686111 4.0117983818 528 1311867736.2298679352 0.0582875721 0.0879332484 0.2360561937 0.0051983522 2.5548100000 1.0004010000 0.4375080000 0.0000060000 1.1019130000 0.0072620000 127699496 0 1784041472 3.9607207775 3.9813797474 4.0121126175 529 1311867736.2633900642 0.0560640506 0.0878730042 0.2360561937 0.0052028900 3.7895300000 0.9959210000 0.4370710000 0.1196650000 1.1035190000 1.1258390000 127701714 0 1785671680 3.9628012180 3.9815571308 4.0120530128 530 1311867736.2995250225 0.0576066785 0.0878158979 0.2360561937 0.0051997061 2.5624980000 0.9995530000 0.4446380000 0.0000050000 1.1024480000 0.0072930000 127703964 0 1784565760 3.9613001347 3.9793992043 4.0122838020 531 1311867736.3304500580 0.0575294681 0.0877588613 0.2360561937 0.0052002930 2.5600510000 0.9923110000 0.3361900000 0.1194270000 1.0970800000 0.0073850000 127706086 0 1783808000 3.9611368179 3.9811022282 4.0126605034 532 1311867736.3637149334 0.0596019588 0.0877059348 0.2360561937 0.0051980718 2.4744960000 1.0259080000 0.3284950000 0.0000050000 1.1051670000 0.0073040000 127708304 0 1785417728 3.9591052532 3.9802598953 4.0129933357 533 1311867736.3943159580 0.0621484891 0.0876579846 0.2360561937 0.0051941186 3.8143210000 1.0148290000 0.4386830000 0.1203530000 1.0998460000 1.1320140000 127710426 0 1784320000 3.9567036629 3.9786825180 4.0130867958 534 1311867736.4313519001 0.0637289956 0.0876131738 0.2360561937 0.0052131645 2.4126710000 0.9961670000 0.2918290000 0.0000050000 1.1096540000 0.0073200000 127712740 0 1783541760 3.9553523064 3.9799101353 4.0137591362 535 1311867736.4625089169 0.0659307018 0.0875726458 0.2360561937 0.0052096108 2.5645760000 0.9970290000 0.3303430000 0.1197940000 1.1024620000 0.0072940000 127714926 0 1785171968 3.9529712200 3.9798195362 4.0139431953 536 1311867736.4987530708 0.0673924759 0.0875349962 0.2360561937 0.0052055716 2.5375790000 1.0420720000 0.3646700000 0.0000060000 1.1149180000 0.0074060000 127717144 0 1784057856 3.9517378807 3.9784495831 4.0140962601 537 1311867736.5321619511 0.0707171112 0.0875036780 0.2360561937 0.0052207033 3.6350570000 1.0007430000 0.2554290000 0.1201160000 1.1076040000 1.1434130000 127719362 0 1783660544 3.9483795166 3.9798398018 4.0145187378 538 1311867736.5634689331 0.0706243739 0.0874723038 0.2360561937 0.0052161881 2.5483940000 1.0140720000 0.4023960000 0.0000060000 1.1168860000 0.0073530000 127721548 0 1785290752 3.9484996796 3.9791493416 4.0148019791 539 1311867736.5958600044 0.0726801679 0.0874448602 0.2360561937 0.0052123448 2.5723580000 0.9982000000 0.3296960000 0.1202190000 1.1082890000 0.0072630000 127723734 0 1784184832 3.9464101791 3.9771883488 4.0148301125 540 1311867736.6320459843 0.0749224126 0.0874216705 0.2360561937 0.0052238651 2.4072730000 1.0267940000 0.2511590000 0.0000050000 1.1142660000 0.0073250000 127725984 0 1783660544 3.9443585873 3.9785504341 4.0151882172 541 1311867736.6635379791 0.0737801939 0.0873964552 0.2360561937 0.0052399273 3.7990850000 0.9928030000 0.4125840000 0.1200880000 1.1136900000 1.1522730000 127728170 0 1785290752 3.9450802803 3.9779689312 4.0148825645 542 1311867736.6945500374 0.0785358697 0.0873801072 0.2360561937 0.0052415595 2.4007300000 1.0068870000 0.2536400000 0.0000050000 1.1242340000 0.0073260000 127730292 0 1784295424 3.9404408932 3.9756817818 4.0150403976 543 1311867736.7332150936 0.0796289071 0.0873658324 0.2360561937 0.0052391633 2.6909470000 0.9937290000 0.4333460000 0.1203450000 1.1285150000 0.0072380000 127732574 0 1783676928 3.9392821789 3.9763324261 4.0150308609 544 1311867736.7636179924 0.0812514201 0.0873545927 0.2360561937 0.0052395508 2.4529940000 1.0193920000 0.2875610000 0.0000050000 1.1311090000 0.0072550000 127734760 0 1785417728 3.9382743835 3.9767704010 4.0151824951 545 1311867736.7952749729 0.0841629878 0.0873487366 0.2360561937 0.0052382794 3.7613860000 0.9913670000 0.3252160000 0.1207600000 1.1392700000 1.1760960000 127736914 0 1784311808 3.9352524281 3.9759674072 4.0152840614 546 1311867736.8325269222 0.0888223127 0.0873514354 0.2360561937 0.0052561442 2.5752160000 0.9821450000 0.4326660000 0.0000050000 1.1452390000 0.0072530000 127739164 0 1783558144 3.9309852123 3.9766123295 4.0161008835 547 1311867736.8640279770 0.0912437215 0.0873585511 0.2360561937 0.0052625673 2.5571670000 0.9997970000 0.2879310000 0.1210340000 1.1334480000 0.0072540000 127741382 0 1785188352 3.9287478924 3.9785552025 4.0164690018 548 1311867736.8945000172 0.0924166217 0.0873677812 0.2360561937 0.0052606638 2.5063320000 1.0202240000 0.3267560000 0.0000050000 1.1433800000 0.0073440000 127743504 0 1784041472 3.9278538227 3.9769828320 4.0166091919 549 1311867736.9362800121 0.0960575789 0.0873836096 0.2360561937 0.0052639431 3.9176830000 1.0077570000 0.4430100000 0.1212370000 1.1433050000 1.1946020000 127745850 0 1783283712 3.9245049953 3.9778077602 4.0167813301 550 1311867736.9632000923 0.0986299217 0.0874040574 0.2360561937 0.0052676729 2.6244810000 1.0099770000 0.4378940000 0.0000050000 1.1615390000 0.0073630000 127747972 0 1785016320 3.9220838547 3.9795904160 4.0180654526 551 1311867736.9954400063 0.0996661782 0.0874263117 0.2360561937 0.0052680524 2.5364390000 1.0069050000 0.2522910000 0.1215250000 1.1397810000 0.0074280000 127750158 0 1784168448 3.9212601185 3.9779009819 4.0180535316 552 1311867737.0307478905 0.1009659693 0.0874508401 0.2360561937 0.0052641129 2.5781910000 1.0367520000 0.3810050000 0.0000060000 1.1451890000 0.0072880000 127752376 0 1783025664 3.9200229645 3.9774854183 4.0183939934 553 1311867737.0629029274 0.1017091572 0.0874766237 0.2360561937 0.0052614973 3.9198570000 1.0070650000 0.4437570000 0.1217740000 1.1397650000 1.1997800000 127754594 0 1784635392 3.9194900990 3.9786961079 4.0190153122 554 1311867737.0977239609 0.1030520722 0.0875047382 0.2360561937 0.0052575458 2.5714440000 1.0076260000 0.4043500000 0.0000050000 1.1434980000 0.0072950000 127756812 0 1783517184 3.9181497097 3.9779801369 4.0189781189 555 1311867737.1300530434 0.1046945825 0.0875357109 0.2360561937 0.0052537130 2.6990490000 1.0007200000 0.4190040000 0.1218390000 1.1422630000 0.0073150000 127758966 0 1782521856 3.9165101051 3.9772441387 4.0189633369 556 1311867737.1655049324 0.1042415798 0.0875657574 0.2360561937 0.0052507404 2.4533440000 1.0400390000 0.2573460000 0.0000060000 1.1408220000 0.0073610000 127761216 0 1784000512 3.9171135426 3.9788215160 4.0192079544 557 1311867737.1952710152 0.1061143428 0.0875990583 0.2360561937 0.0052470030 3.9224370000 1.0125550000 0.4437090000 0.1221410000 1.1426860000 1.1934930000 127763370 0 1785667584 3.9153721333 3.9782450199 4.0190701485 558 1311867737.2333149910 0.1063992381 0.0876327504 0.2360561937 0.0052425411 2.6232300000 1.0132140000 0.4547600000 0.0000050000 1.1391110000 0.0073250000 127765684 0 1784705024 3.9153091908 3.9775817394 4.0192294121 559 1311867737.2693018913 0.1072584912 0.0876678590 0.2360561937 0.0052434396 2.6285050000 1.0232400000 0.3342290000 0.1225410000 1.1332000000 0.0073220000 127767902 0 1783545856 3.9149646759 3.9785585403 4.0191488266 560 1311867737.2957379818 0.1083268374 0.0877047501 0.2360561937 0.0052405538 2.6209870000 1.0229330000 0.4468980000 0.0000050000 1.1360210000 0.0073460000 127769992 0 1785151488 3.9141757488 3.9789171219 4.0196304321 561 1311867737.3316531181 0.1087443903 0.0877422539 0.2360561937 0.0052364634 3.9273080000 1.0360260000 0.4470520000 0.1225210000 1.1276300000 1.1852190000 127772274 0 1784025088 3.9140067101 3.9780471325 4.0198397636 562 1311867737.3659460545 0.1086611375 0.0877794761 0.2360561937 0.0052320275 2.6226880000 1.0246810000 0.4529210000 0.0000050000 1.1298560000 0.0073470000 127774460 0 1783029760 3.9139916897 3.9783141613 4.0200738907 563 1311867737.3967239857 0.1097655594 0.0878185277 0.2360561937 0.0052284589 2.5787400000 1.0265590000 0.2961690000 0.1227200000 1.1181140000 0.0074590000 127776646 0 1784508416 3.9130659103 3.9784705639 4.0203900337 564 1311867737.4355359077 0.1113885045 0.0878603185 0.2360561937 0.0052252762 2.5852370000 1.0715010000 0.3731850000 0.0000060000 1.1244210000 0.0074670000 127778928 0 1783554048 3.9115731716 3.9786553383 4.0210566521 565 1311867737.4691100121 0.1123777330 0.0879037121 0.2360561937 0.0052210100 3.7135090000 1.0370620000 0.2591040000 0.1243280000 1.1109820000 1.1740750000 127781146 0 1782374400 3.9107494354 3.9784667492 4.0216994286 566 1311867737.4959459305 0.1132240668 0.0879484477 0.2360561937 0.0052168057 2.4553090000 1.0320610000 0.2997300000 0.0000060000 1.1082280000 0.0075050000 127783236 0 1784000512 3.9098012447 3.9785358906 4.0220894814 567 1311867737.5353999138 0.1155919433 0.0879972017 0.2360561937 0.0052148187 2.6492230000 1.0359950000 0.3758640000 0.1233110000 1.0987820000 0.0075490000 127785550 0 1785778176 3.9077653885 3.9778728485 4.0230574608 568 1311867737.5654399395 0.1153476015 0.0880453538 0.2360561937 0.0052109300 2.4541880000 1.0435160000 0.3010380000 0.0000050000 1.0932900000 0.0074210000 127787672 0 1784823808 3.9085445404 3.9780957699 4.0232205391 569 1311867737.5958089828 0.1161824837 0.0880948040 0.2360561937 0.0052067513 3.7162410000 1.0401220000 0.2986340000 0.1233010000 1.0950660000 1.1511650000 127789858 0 1783664640 3.9080874920 3.9777369499 4.0238094330 570 1311867737.6330978870 0.1176110208 0.0881465868 0.2360561937 0.0052025982 2.5996440000 1.0371950000 0.4551220000 0.0000050000 1.0920030000 0.0075270000 127792140 0 1785151488 3.9069597721 3.9777565002 4.0242314339 571 1311867737.6624519825 0.1185115948 0.0881997654 0.2360561937 0.0051984531 2.6130210000 1.0507730000 0.3389040000 0.1234650000 1.0836070000 0.0074320000 127794294 0 1784180736 3.9063086510 3.9767916203 4.0245485306 572 1311867737.7032339573 0.1199806407 0.0882553264 0.2360561937 0.0051940988 2.6009870000 1.0658550000 0.4311570000 0.0000050000 1.0884730000 0.0074380000 127796576 0 1783029760 3.9051876068 3.9760479927 4.0250811577 573 1311867737.7314720154 0.1201674938 0.0883110195 0.2360561937 0.0051897385 3.5932240000 1.0387680000 0.1901710000 0.1234130000 1.0843390000 1.1485900000 127798698 0 1784508416 3.9052741528 3.9762554169 4.0253477097 574 1311867737.7658560276 0.1216967106 0.0883691828 0.2360561937 0.0051868028 2.6211630000 1.0358020000 0.4712580000 0.0000050000 1.0978680000 0.0074210000 127800916 0 1783554048 3.9041380882 3.9760508537 4.0257754326 575 1311867737.8011269569 0.1215530857 0.0884268939 0.2360561937 0.0051835271 2.5652690000 1.0401410000 0.3022140000 0.1238560000 1.0836110000 0.0074700000 127803166 0 1782411264 3.9044415951 3.9763655663 4.0258126259 576 1311867737.8323190212 0.1211423278 0.0884836915 0.2360561937 0.0051791694 2.4399800000 1.0713730000 0.2628470000 0.0000050000 1.0904250000 0.0075220000 127805352 0 1784147968 3.9050881863 3.9763324261 4.0260858536 577 1311867737.8633110523 0.1228569075 0.0885432638 0.2360561937 0.0051844339 3.8240600000 1.0431040000 0.4191840000 0.1238680000 1.0816040000 1.1485020000 127807506 0 1785769984 3.9041361809 3.9761216640 4.0271358490 578 1311867737.9004418850 0.1240959242 0.0886047736 0.2360561937 0.0051806083 2.6139910000 1.0501370000 0.4610580000 0.0000060000 1.0864080000 0.0074600000 127809724 0 1784655872 3.9033207893 3.9756064415 4.0277032852 579 1311867737.9305500984 0.1244415492 0.0886666679 0.2360561937 0.0051802076 2.5247820000 1.0434730000 0.2653300000 0.1240940000 1.0763840000 0.0075020000 127811878 0 1783910400 3.9032590389 3.9750618935 4.0283145905 580 1311867737.9630560875 0.1251977086 0.0887296524 0.2360561937 0.0051762501 2.4723860000 1.0727130000 0.3041010000 0.0000050000 1.0800950000 0.0074990000 127814096 0 1785540608 3.9029624462 3.9749839306 4.0288248062 581 1311867737.9996941090 0.1265220046 0.0887946995 0.2360561937 0.0051725753 3.6956750000 1.0444620000 0.3013950000 0.1244340000 1.0713250000 1.1451700000 127816346 0 1784651776 3.9021019936 3.9742617607 4.0296492577 582 1311867738.0315399170 0.1276813895 0.0888615151 0.2360561937 0.0051695381 2.5893690000 1.0365650000 0.4627050000 0.0000050000 1.0745390000 0.0074580000 127818532 0 1784569856 3.9012539387 3.9750220776 4.0303025246 583 1311867738.0629770756 0.1265125424 0.0889260967 0.2360561937 0.0051667046 2.7235420000 1.0473700000 0.4667050000 0.1244930000 1.0687070000 0.0075110000 127820718 0 1784061952 3.9030847549 3.9765512943 4.0314321518 584 1311867738.0998299122 0.1271587908 0.0889915636 0.2360561937 0.0051641009 2.4327390000 1.0813920000 0.2661020000 0.0000050000 1.0694970000 0.0074980000 127822936 0 1783799808 3.9030480385 3.9750273228 4.0321645737 585 1311867738.1308510303 0.1285208762 0.0890591351 0.2360561937 0.0051620358 3.7740820000 1.0549860000 0.3812650000 0.1246830000 1.0676290000 1.1375140000 127825090 0 1785540608 3.9022402763 3.9738876820 4.0328974724 586 1311867738.1635079384 0.1286653727 0.0891267225 0.2360561937 0.0051580621 2.3791950000 1.0553070000 0.2300190000 0.0000050000 1.0774370000 0.0074880000 127827308 0 1784815616 3.9025673866 3.9735066891 4.0335288048 587 1311867738.1992070675 0.1311589926 0.0891983277 0.2360561937 0.0051557367 2.5325880000 1.0560790000 0.2720160000 0.1248450000 1.0640190000 0.0075430000 127829526 0 1784561664 3.9008238316 3.9728758335 4.0346417427 588 1311867738.2306089401 0.1308726817 0.0892692025 0.2360561937 0.0051546360 2.4188010000 1.0555530000 0.2718620000 0.0000050000 1.0750980000 0.0074620000 127831712 0 1784037376 3.9015152454 3.9713532925 4.0347976685 589 1311867738.2632689476 0.1325688958 0.0893427164 0.2360561937 0.0051529606 3.8168940000 1.0548730000 0.4233890000 0.1252300000 1.0672450000 1.1379760000 127833930 0 1783799808 3.9003262520 3.9702000618 4.0350904465 590 1311867738.3008689880 0.1338331103 0.0894181239 0.2360561937 0.0051492253 2.5718000000 1.0553860000 0.4216770000 0.0000050000 1.0791800000 0.0075380000 127836180 0 1785540608 3.8996481895 3.9697804451 4.0351543427 591 1311867738.3339769840 0.1349638253 0.0894951893 0.2360561937 0.0051466808 2.7233500000 1.0561180000 0.4585750000 0.1254800000 1.0667830000 0.0075440000 127838366 0 1784815616 3.8990323544 3.9693684578 4.0352559090 592 1311867738.3651630878 0.1370348781 0.0895754929 0.2360561937 0.0051437851 2.4819470000 1.0545580000 0.3427160000 0.0000060000 1.0690130000 0.0074670000 127840552 0 1784545280 3.8971681595 3.9693875313 4.0352530479 593 1311867738.3995900154 0.1395324022 0.0896597372 0.2360561937 0.0051422701 3.8580850000 1.0678910000 0.4572170000 0.1256760000 1.0621530000 1.1361980000 127842802 0 1783799808 3.8952186108 3.9702951908 4.0355858803 594 1311867738.4334011078 0.1384680420 0.0897419061 0.2360561937 0.0051389729 2.4110270000 1.0473520000 0.2682930000 0.0000050000 1.0795430000 0.0075150000 127845020 0 1783533568 3.8964469433 3.9710550308 4.0352821350 595 1311867738.4643430710 0.1423823237 0.0898303774 0.2360561937 0.0051366151 2.5299570000 1.0473120000 0.2691390000 0.1261230000 1.0718660000 0.0074430000 127847174 0 1785294848 3.8933577538 3.9699282646 4.0355906487 596 1311867738.5000250340 0.1407688260 0.0899158446 0.2360561937 0.0051352352 2.5919340000 1.0447720000 0.4617790000 0.0000050000 1.0689210000 0.0075280000 127849424 0 1784406016 3.8956551552 3.9715368748 4.0358471870 597 1311867738.5332009792 0.1419148445 0.0900029451 0.2360561937 0.0051317248 3.6502890000 1.0440800000 0.2642040000 0.1263790000 1.0723880000 1.1350500000 127851610 0 1784180736 3.8952915668 3.9726297855 4.0361304283 598 1311867738.5634350777 0.1421958357 0.0900902242 0.2360561937 0.0051289981 2.3952510000 1.0419720000 0.2636400000 0.0000050000 1.0741600000 0.0074620000 127853796 0 1785921536 3.8957188129 3.9709522724 4.0363097191 599 1311867738.6022439003 0.1419545859 0.0901768091 0.2360561937 0.0051269407 2.4923150000 1.0503700000 0.2257500000 0.1282050000 1.0714140000 0.0075220000 127856078 0 1785180160 3.8969018459 3.9706745148 4.0362544060 600 1311867738.6328980923 0.1432393193 0.0902652466 0.2360561937 0.0051248782 2.4054360000 1.0458650000 0.2684220000 0.0000050000 1.0754350000 0.0075130000 127858232 0 1784942592 3.8965797424 3.9720480442 4.0365757942 601 1311867738.6628730297 0.1436018348 0.0903539930 0.2360561937 0.0051237067 3.6695920000 1.0498040000 0.2687930000 0.1270280000 1.0737480000 1.1411610000 127860418 0 1784180736 3.8969697952 3.9715926647 4.0362615585 602 1311867738.6996099949 0.1458725035 0.0904462164 0.2360561937 0.0051210521 2.5222100000 1.0405000000 0.3809770000 0.0000050000 1.0849410000 0.0074740000 127862668 0 1784053760 3.8957383633 3.9702682495 4.0366592407 603 1311867738.7314729691 0.1463012546 0.0905388450 0.2360561937 0.0051302514 2.5613400000 1.0566910000 0.2783950000 0.1270410000 1.0822830000 0.0077870000 127864854 0 1785061376 3.8962113857 3.9714794159 4.0368933678 604 1311867738.7626600266 0.1485830694 0.0906349447 0.2360561937 0.0051282805 2.4124650000 1.0379980000 0.2646240000 0.0000050000 1.0941790000 0.0074880000 127867008 0 1784950784 3.8949809074 3.9713246822 4.0374860764 605 1311867738.8032259941 0.1493946612 0.0907320682 0.2360561937 0.0051310571 3.7255180000 1.0403930000 0.3038390000 0.1272470000 1.0894910000 1.1555330000 127869322 0 1784025088 3.8952207565 3.9710068703 4.0375919342 606 1311867738.8306779861 0.1506196707 0.0908308927 0.2360561937 0.0051327766 2.4231310000 1.0468370000 0.2635270000 0.0000050000 1.0970170000 0.0075240000 127871444 0 1783771136 3.8946709633 3.9714541435 4.0378808975 607 1311867738.8639259338 0.1495995373 0.0909277109 0.2360561937 0.0051295305 2.5420700000 1.0344680000 0.2666150000 0.1275440000 1.0977160000 0.0075150000 127873662 0 1785548800 3.8965425491 3.9721298218 4.0380330086 608 1311867738.9000120163 0.1500889808 0.0910250156 0.2360561937 0.0051304318 2.6708180000 1.0854670000 0.4638230000 0.0000050000 1.1049530000 0.0074210000 127875912 0 1784659968 3.8968484402 3.9718785286 4.0379724503 609 1311867738.9307610989 0.1532300264 0.0911271584 0.2360561937 0.0051320631 3.7200640000 1.0391180000 0.2629080000 0.1280240000 1.1059120000 1.1758140000 127878066 0 1784545280 3.8943314552 3.9712290764 4.0385527611 610 1311867738.9664750099 0.1541131437 0.0912304142 0.2360561937 0.0051298547 2.5160930000 1.0405140000 0.3421980000 0.0000050000 1.1166160000 0.0076660000 127880316 0 1783799808 3.8940148354 3.9722902775 4.0389080048 611 1311867738.9989941120 0.1557191163 0.0913359603 0.2360561937 0.0051260456 2.6415210000 1.0318560000 0.3427840000 0.1283280000 1.1228260000 0.0074820000 127882534 0 1783545856 3.8929755688 3.9721698761 4.0390486717 612 1311867739.0329539776 0.1551060379 0.0914401598 0.2360561937 0.0051252662 2.4428750000 1.0807920000 0.2238130000 0.0000060000 1.1226390000 0.0074220000 127884752 0 1785159680 3.8940329552 3.9707143307 4.0389142036 613 1311867739.0664470196 0.1542560011 0.0915426326 0.2360561937 0.0051230592 3.7985240000 1.0374780000 0.3007600000 0.1282790000 1.1317400000 1.1911120000 127886938 0 1784434688 3.8954403400 3.9714417458 4.0391464233 614 1311867739.0997900963 0.1542759836 0.0916448042 0.2360561937 0.0051200130 2.5177290000 1.0300350000 0.3399940000 0.0000050000 1.1319580000 0.0073950000 127889060 0 1784180736 3.8959033489 3.9727506638 4.0393700600 615 1311867739.1321549416 0.1548567265 0.0917475878 0.2360561937 0.0051179798 2.6253410000 1.0436240000 0.3006030000 0.1287660000 1.1366900000 0.0074820000 127891214 0 1785921536 3.8957498074 3.9719176292 4.0398330688 616 1311867739.1687150002 0.1549858302 0.0918502473 0.2360561937 0.0051144294 2.5334060000 1.0732940000 0.2980860000 0.0000050000 1.1454160000 0.0075240000 127893464 0 1785032704 3.8958394527 3.9718618393 4.0401492119 617 1311867739.1999289989 0.1549378037 0.0919524962 0.2360561937 0.0051140941 3.8622820000 1.0296150000 0.3331250000 0.1286390000 1.1485060000 1.2139070000 127895618 0 1784815616 3.8961310387 3.9724299908 4.0409893990 618 1311867739.2313010693 0.1556158662 0.0920555113 0.2360561937 0.0051110247 2.5021340000 1.0291040000 0.3031130000 0.0000060000 1.1534010000 0.0074230000 127897772 0 1784053760 3.8955223560 3.9717974663 4.0412044525 619 1311867739.2672259808 0.1564776748 0.0921595859 0.2360561937 0.0051072518 2.6579530000 1.0269780000 0.3333140000 0.1289420000 1.1529620000 0.0073700000 127900054 0 1783934976 3.8944876194 3.9713618755 4.0412869453 620 1311867739.2996931076 0.1557893008 0.0922622145 0.2360561937 0.0051091735 2.5744740000 1.0766070000 0.2961850000 0.0000050000 1.1860040000 0.0075160000 127902240 0 1785565184 3.8951809406 3.9709045887 4.0416951180 621 1311867739.3319859505 0.1560454220 0.0923649250 0.2360561937 0.0051081513 4.0137680000 1.0277420000 0.4463910000 0.1291610000 1.1683640000 1.2328020000 127904426 0 1784799232 3.8950524330 3.9720540047 4.0422577858 622 1311867739.3670029640 0.1555458903 0.0924665021 0.2360561937 0.0051063521 2.6531840000 1.0200560000 0.4530600000 0.0000050000 1.1642400000 0.0074280000 127906644 0 1784561664 3.8953549862 3.9716398716 4.0425486565 623 1311867739.3990058899 0.1555122882 0.0925676992 0.2360561937 0.0051024471 2.6009940000 1.0230430000 0.2626550000 0.1290950000 1.1696320000 0.0074900000 127908862 0 1783799808 3.8951323032 3.9722526073 4.0427894592 624 1311867739.4311320782 0.1539001316 0.0926659883 0.2360561937 0.0050989297 2.5277750000 1.0459600000 0.3016600000 0.0000050000 1.1643810000 0.0073440000 127911016 0 1783656448 3.8968148232 3.9725935459 4.0430960655 625 1311867739.4668490887 0.1558060944 0.0927670125 0.2360561937 0.0050959201 3.7809940000 1.0269570000 0.2217660000 0.1291530000 1.1683160000 1.2265160000 127913266 0 1785176064 3.8949310780 3.9717030525 4.0437860489 626 1311867739.4988598824 0.1566359103 0.0928690395 0.2360561937 0.0050994067 2.6549140000 1.0210780000 0.4515510000 0.0000060000 1.1657180000 0.0073910000 127915452 0 1784414208 3.8941185474 3.9709327221 4.0445222855 627 1311867739.5316400528 0.1565331072 0.0929705771 0.2360561937 0.0050956647 2.7694910000 1.0331570000 0.4199900000 0.1291600000 1.1714050000 0.0073560000 127917606 0 1784291328 3.8943469524 3.9717981815 4.0445885658 628 1311867739.5670249462 0.1593789160 0.0930763228 0.2360561937 0.0050955743 2.6915380000 1.0520440000 0.4477190000 0.0000050000 1.1761360000 0.0073950000 127919856 0 1786068992 3.8916895390 3.9721434116 4.0457687378 629 1311867739.5990490913 0.1615386605 0.0931851660 0.2360561937 0.0050921725 3.9452260000 1.0243240000 0.3765210000 0.1293760000 1.1703580000 1.2353560000 127922042 0 1785196544 3.8894641399 3.9707391262 4.0465168953 630 1311867739.6325490475 0.1625288129 0.0932952353 0.2360561937 0.0050884796 2.4352040000 1.0203590000 0.2257510000 0.0000060000 1.1732610000 0.0073480000 127924260 0 1784942592 3.8883149624 3.9717035294 4.0472016335 631 1311867739.6706740856 0.1638700813 0.0934070813 0.2360561937 0.0050856894 2.6790790000 1.0233810000 0.3384750000 0.1298550000 1.1707140000 0.0074270000 127926542 0 1784188928 3.8866708279 3.9711928368 4.0478496552 632 1311867739.7001221180 0.1651354879 0.0935205756 0.2360561937 0.0050820431 2.5518520000 1.0566550000 0.3049800000 0.0000060000 1.1743860000 0.0073490000 127928696 0 1784045568 3.8853902817 3.9711933136 4.0487222672 633 1311867739.7323939800 0.1657073647 0.0936346148 0.2360561937 0.0050794080 3.8474510000 1.0352390000 0.2583560000 0.1308920000 1.1711550000 1.2428470000 127930882 0 1785815040 3.8846981525 3.9720640182 4.0494565964 634 1311867739.7662999630 0.1677273363 0.0937514803 0.2360561937 0.0050773984 2.5180560000 1.0294980000 0.2969270000 0.0000060000 1.1749740000 0.0073560000 127933100 0 1784942592 3.8825209141 3.9709668159 4.0502214432 635 1311867739.8016180992 0.1682568341 0.0938688115 0.2360561937 0.0050754083 2.8050790000 1.0294610000 0.4553750000 0.1317690000 1.1726440000 0.0074280000 127935350 0 1784799232 3.8817033768 3.9693484306 4.0506963730 636 1311867739.8325679302 0.1695445925 0.0939877986 0.2360561937 0.0050832342 2.5564870000 1.0214260000 0.3385770000 0.0000050000 1.1798170000 0.0073850000 127937504 0 1783910400 3.8803274632 3.9715244770 4.0515694618 637 1311867739.8701560497 0.1696978360 0.0941066527 0.2360561937 0.0050799028 3.9592650000 1.0295600000 0.3750470000 0.1302820000 1.1752980000 1.2405230000 127939754 0 1783803904 3.8797414303 3.9704985619 4.0522007942 638 1311867739.9036860466 0.1703723520 0.0942261914 0.2360561937 0.0050780394 2.5588570000 1.0220780000 0.3348270000 0.0000060000 1.1861310000 0.0074460000 127942004 0 1785323520 3.8782706261 3.9689328671 4.0521988869 639 1311867739.9317240715 0.1715877801 0.0943472580 0.2360561937 0.0050757319 2.6078020000 1.0221090000 0.2551170000 0.1304430000 1.1831130000 0.0073770000 127944126 0 1784311808 3.8766965866 3.9697399139 4.0527415276 640 1311867739.9668979645 0.1719474941 0.0944685084 0.2360561937 0.0050723972 2.6469600000 1.0285880000 0.4100220000 0.0000050000 1.1914560000 0.0073830000 127946344 0 1783783424 3.8760018349 3.9705283642 4.0530905724 641 1311867739.9987080097 0.1745824367 0.0945934911 0.2360561937 0.0050702717 3.9828300000 1.0304970000 0.3712870000 0.1308800000 1.1868790000 1.2549120000 127948562 0 1785581568 3.8726832867 3.9691743851 4.0537009239 642 1311867740.0328791142 0.1743095815 0.0947176595 0.2360561937 0.0050667697 2.4628920000 1.0359750000 0.2194220000 0.0000060000 1.1907000000 0.0074120000 127950780 0 1784672256 3.8723957539 3.9692211151 4.0538396835 643 1311867740.0671849251 0.1740085930 0.0948409735 0.2360561937 0.0050669824 2.8130610000 1.0157260000 0.4561690000 0.1306430000 1.1945520000 0.0073710000 127952966 0 1784197120 3.8724985123 3.9712319374 4.0542979240 644 1311867740.0992529392 0.1755366474 0.0949662774 0.2360561937 0.0050689416 2.7003470000 1.0501240000 0.4464240000 0.0000050000 1.1879170000 0.0073260000 127955184 0 1785806848 3.8706133366 3.9690797329 4.0544557571 645 1311867740.1347720623 0.1779049039 0.0950948644 0.2360561937 0.0050677866 3.9581460000 1.0288360000 0.3323800000 0.1311400000 1.1964280000 1.2598680000 127957370 0 1784692736 3.8674366474 3.9674477577 4.0546035767 646 1311867740.1666491032 0.1775529534 0.0952225085 0.2360561937 0.0050678065 2.6834850000 1.0250220000 0.4465840000 0.0000050000 1.1959020000 0.0073540000 127959588 0 1783894016 3.8677694798 3.9695031643 4.0547909737 647 1311867740.1993310452 0.1788732708 0.0953517987 0.2360561937 0.0050642117 2.6644260000 1.0279560000 0.2933470000 0.1315210000 1.1957130000 0.0074430000 127961806 0 1785561088 3.8661651611 3.9697690010 4.0552506447 648 1311867740.2383539677 0.1783320606 0.0954798547 0.2360561937 0.0050623128 2.5802590000 1.0257790000 0.3382710000 0.0000050000 1.1994650000 0.0073000000 127964120 0 1784549376 3.8661758900 3.9684100151 4.0550379753 649 1311867740.2664349079 0.1789748073 0.0956085064 0.2360561937 0.0050621870 4.0855330000 1.0408900000 0.4360440000 0.1319260000 1.1998180000 1.2682660000 127966210 0 1783930880 3.8653099537 3.9694881439 4.0553030968 650 1311867740.2981588840 0.1794265360 0.0957374572 0.2360561937 0.0050602060 2.4955690000 1.0198910000 0.2611160000 0.0000050000 1.1989020000 0.0073440000 127968396 0 1785671680 3.8646175861 3.9700822830 4.0555653572 651 1311867740.3347120285 0.1789368689 0.0958652596 0.2360561937 0.0050577313 2.8142170000 1.0145800000 0.4531160000 0.1313530000 1.1982480000 0.0073390000 127970678 0 1784418304 3.8645761013 3.9688508511 4.0551695824 652 1311867740.3665161133 0.1765992790 0.0959890848 0.2360561937 0.0050595640 2.7028980000 1.0271840000 0.4574110000 0.0000050000 1.2017190000 0.0074280000 127972832 0 1784041472 3.8668074608 3.9704871178 4.0546956062 653 1311867740.3993780613 0.1775608957 0.0961140034 0.2360561937 0.0050577062 3.9212630000 1.0172080000 0.2936060000 0.1315690000 1.1978520000 1.2725880000 127975018 0 1785671680 3.8657169342 3.9692320824 4.0546526909 654 1311867740.4346680641 0.1773246676 0.0962381787 0.2360561937 0.0050549970 2.6961490000 1.0239070000 0.4550440000 0.0000060000 1.2002040000 0.0073960000 127977268 0 1784684544 3.8660545349 3.9696848392 4.0541820526 655 1311867740.4664289951 0.1786109656 0.0963639387 0.2360561937 0.0050517426 2.8181970000 1.0188230000 0.4503110000 0.1318840000 1.2012330000 0.0073640000 127979454 0 1783795712 3.8646199703 3.9698038101 4.0537838936 656 1311867740.4993040562 0.1792218983 0.0964902465 0.2360561937 0.0050501470 2.5797870000 1.0201440000 0.3423730000 0.0000050000 1.2014460000 0.0072990000 127981640 0 1785442304 3.8645520210 3.9697778225 4.0538072586 657 1311867740.5354259014 0.1803937703 0.0966179536 0.2360561937 0.0050514030 3.8602320000 1.0284320000 0.2189960000 0.1325700000 1.2005680000 1.2701750000 127983890 0 1784422400 3.8637342453 3.9694652557 4.0535426140 658 1311867740.5666589737 0.1807736158 0.0967458497 0.2360561937 0.0050476387 2.5898100000 1.0307610000 0.3345890000 0.0000050000 1.2085000000 0.0073710000 127986076 0 1783513088 3.8635096550 3.9701476097 4.0532445908 659 1311867740.6008880138 0.1833816618 0.0968773153 0.2360561937 0.0050469349 2.6659330000 1.0195870000 0.2932540000 0.1325330000 1.2047520000 0.0074000000 127988294 0 1785180160 3.8611018658 3.9706997871 4.0534667969 660 1311867740.6346809864 0.1827588528 0.0970074388 0.2360561937 0.0050456694 2.5077900000 1.0199010000 0.2555700000 0.0000050000 1.2156150000 0.0073450000 127990512 0 1784422400 3.8617055416 3.9706981182 4.0532140732 661 1311867740.6665890217 0.1832101792 0.0971378515 0.2360561937 0.0050421322 3.8974440000 1.0249350000 0.2537540000 0.1330010000 1.2022780000 1.2747390000 127992698 0 1783660544 3.8610665798 3.9705960751 4.0528697968 662 1311867740.6994900703 0.1838581413 0.0972688489 0.2360561937 0.0050391499 2.4758370000 1.0282880000 0.2259220000 0.0000050000 1.2057010000 0.0074300000 127994884 0 1785307136 3.8603184223 3.9701745510 4.0525135994 663 1311867740.7368240356 0.1840982139 0.0973998132 0.2360561937 0.0050376442 2.8234050000 1.0218160000 0.4444470000 0.1327760000 1.2075430000 0.0072910000 127997070 0 1784295424 3.8599772453 3.9697296619 4.0522494316 664 1311867740.7668819427 0.1849865913 0.0975317210 0.2360561937 0.0050350471 2.5369260000 1.0493250000 0.2606920000 0.0000050000 1.2108370000 0.0072800000 127999224 0 1783152640 3.8588817120 3.9698836803 4.0520815849 665 1311867740.7996399403 0.1879374385 0.0976676695 0.2360561937 0.0050325217 3.9699600000 1.0248780000 0.3014070000 0.1332040000 1.2170920000 1.2848520000 128001442 0 1784889344 3.8557562828 3.9689619541 4.0526313782 666 1311867740.8349099159 0.1880190969 0.0978033323 0.2360561937 0.0050288015 2.5461710000 1.0214040000 0.2954650000 0.0000050000 1.2126170000 0.0073050000 128003628 0 1784066048 3.8554477692 3.9693984985 4.0523562431 667 1311867740.8668210506 0.1894530505 0.0979407382 0.2360561937 0.0050259293 2.6810690000 1.0224330000 0.2954100000 0.1335980000 1.2135820000 0.0073010000 128005846 0 1783054336 3.8537118435 3.9694275856 4.0525016785 668 1311867740.8993830681 0.1903488785 0.0980790737 0.2360561937 0.0050224479 2.5343360000 1.0450770000 0.2556070000 0.0000060000 1.2178370000 0.0072940000 128008032 0 1784762368 3.8521606922 3.9684491158 4.0523152351 669 1311867740.9399120808 0.1889386475 0.0982148877 0.2360561937 0.0050258713 3.9232990000 1.0153340000 0.2530960000 0.1331140000 1.2175070000 1.2948040000 128010378 0 1784025088 3.8532266617 3.9700300694 4.0522980690 670 1311867740.9665501118 0.1892486960 0.0983507591 0.2360561937 0.0050228356 2.5772390000 1.0080650000 0.3269610000 0.0000050000 1.2259560000 0.0074170000 128012468 0 1783029760 3.8524627686 3.9697747231 4.0518236160 671 1311867741.0021579266 0.1898737848 0.0984871570 0.2360561937 0.0050199881 2.6858840000 1.0232760000 0.2937640000 0.1338490000 1.2190910000 0.0073560000 128014718 0 1784762368 3.8513965607 3.9684767723 4.0516448021 672 1311867741.0367169380 0.1888072640 0.0986215619 0.2360561937 0.0050171784 2.5325220000 1.0325460000 0.2538170000 0.0000050000 1.2294100000 0.0072320000 128016936 0 1783918592 3.8522288799 3.9694538116 4.0513057709 673 1311867741.0666699409 0.1889247298 0.0987557420 0.2360561937 0.0050155403 3.8980890000 1.0160340000 0.2122780000 0.1335060000 1.2227130000 1.3048040000 128019090 0 1782792192 3.8519248962 3.9705882072 4.0511879921 674 1311867741.1009640694 0.1890121847 0.0988896536 0.2360561937 0.0050193380 2.7001490000 1.0100690000 0.4498460000 0.0000050000 1.2242540000 0.0073630000 128021308 0 1784381440 3.8512575626 3.9684724808 4.0506963730 675 1311867741.1357901096 0.1887515187 0.0990227823 0.2360561937 0.0050165323 2.8202540000 1.0109880000 0.4285030000 0.1335600000 1.2313840000 0.0072980000 128023526 0 1786179584 3.8509895802 3.9688444138 4.0500583649 676 1311867741.1675300598 0.1881077737 0.0991545648 0.2360561937 0.0050137179 2.5845440000 1.0077490000 0.3327900000 0.0000050000 1.2268550000 0.0073800000 128025744 0 1785188352 3.8517498970 3.9688181877 4.0499625206 677 1311867741.2014830112 0.1891007870 0.0992874248 0.2360561937 0.0050151388 3.9078830000 1.0054820000 0.2202040000 0.1346470000 1.2348390000 1.3039250000 128027930 0 1783918592 3.8508670330 3.9680449963 4.0494947433 678 1311867741.2411060333 0.1908894926 0.0994225311 0.2360561937 0.0050171186 2.5180920000 1.0155020000 0.2520070000 0.0000050000 1.2346470000 0.0072110000 128030244 0 1785421824 3.8487727642 3.9667463303 4.0492115021 679 1311867741.2668209076 0.1926662028 0.0995598561 0.2360561937 0.0050188844 2.7279120000 1.0160390000 0.3231620000 0.1341020000 1.2377350000 0.0072080000 128032334 0 1784451072 3.8472483158 3.9671723843 4.0492734909 680 1311867741.2997009754 0.1932048798 0.0996975694 0.2360561937 0.0050154669 2.6135140000 1.0231430000 0.3245840000 0.0000060000 1.2497600000 0.0071640000 128034520 0 1783283712 3.8470346928 3.9676966667 4.0490870476 681 1311867741.3348419666 0.1937544793 0.0998356853 0.2360561937 0.0050119011 3.9690880000 0.9998430000 0.2532270000 0.1341510000 1.2474680000 1.3257200000 128036770 0 1784889344 3.8466942310 3.9682147503 4.0489673615 682 1311867741.3701419830 0.1941355616 0.0999739549 0.2360561937 0.0050091443 2.5678250000 1.0049480000 0.2952450000 0.0000050000 1.2508370000 0.0071990000 128038988 0 1783918592 3.8467404842 3.9698150158 4.0488719940 683 1311867741.4066278934 0.1947057098 0.1001126544 0.2360561937 0.0050071586 2.6841710000 0.9981730000 0.2849900000 0.1342010000 1.2507250000 0.0071710000 128041270 0 1782775808 3.8465278149 3.9695937634 4.0486636162 684 1311867741.4393060207 0.1935464591 0.1002492535 0.2360561937 0.0050047600 2.5970780000 1.0044960000 0.3233740000 0.0000060000 1.2533700000 0.0072220000 128043488 0 1784254464 3.8480224609 3.9703793526 4.0485434532 685 1311867741.4667329788 0.1943008006 0.1003865550 0.2360561937 0.0050011501 3.9594850000 1.0071820000 0.2148200000 0.1345970000 1.2552170000 1.3389610000 128045578 0 1785921536 3.8478016853 3.9704408646 4.0487089157 686 1311867741.5025069714 0.1959667653 0.1005258848 0.2360561937 0.0049994455 2.5876150000 1.0002660000 0.3126820000 0.0000050000 1.2576130000 0.0071880000 128047828 0 1784659968 3.8467376232 3.9710032940 4.0490121841 687 1311867741.5368049145 0.1956543177 0.1006643541 0.2360561937 0.0049972204 2.6954000000 0.9942270000 0.2869780000 0.1344830000 1.2636170000 0.0072470000 128050046 0 1783664640 3.8475418091 3.9705054760 4.0489797592 688 1311867741.5688209534 0.1948249936 0.1008012155 0.2360561937 0.0049937862 2.5365020000 1.0026510000 0.2572990000 0.0000050000 1.2606280000 0.0072770000 128052232 0 1785143296 3.8490145206 3.9710645676 4.0490207672 689 1311867741.6046030521 0.1954616755 0.1009386037 0.2360561937 0.0050002674 3.9659750000 1.0023160000 0.2182470000 0.1349410000 1.2604930000 1.3402900000 128054450 0 1784180736 3.8489847183 3.9718532562 4.0491943359 690 1311867741.6355440617 0.1973337233 0.1010783068 0.2360561937 0.0049975675 2.5727270000 1.0015420000 0.2883690000 0.0000060000 1.2667540000 0.0072020000 128056636 0 1782910976 3.8475534916 3.9712870121 4.0492339134 691 1311867741.6679561138 0.1968150884 0.1012168549 0.2360561937 0.0049941604 2.8579580000 1.0030630000 0.4430670000 0.1350520000 1.2608850000 0.0072100000 128058854 0 1784532992 3.8487784863 3.9718954563 4.0491833687 692 1311867741.7048020363 0.1981165409 0.1013568834 0.2360561937 0.0049952280 2.5346150000 1.0016810000 0.2476210000 0.0000050000 1.2684140000 0.0072080000 128061104 0 1783533568 3.8482780457 3.9721090794 4.0491099358 693 1311867741.7345991135 0.1977759600 0.1014960163 0.2360561937 0.0049930944 4.0406090000 1.0004700000 0.2914780000 0.1353080000 1.2621300000 1.3421840000 128063226 0 1782394880 3.8491973877 3.9714913368 4.0488095284 694 1311867741.7702169418 0.1981231421 0.1016352484 0.2360561937 0.0049896756 2.7218500000 1.0006040000 0.4402650000 0.0000050000 1.2650930000 0.0071490000 128065476 0 1784000512 3.8497171402 3.9716486931 4.0487661362 695 1311867741.8058650494 0.1987054497 0.1017749178 0.2360561937 0.0049861284 2.6412840000 1.0013300000 0.2181170000 0.1352690000 1.2706650000 0.0072270000 128067726 0 1785798656 3.8500437737 3.9717857838 4.0485339165 696 1311867741.8388509750 0.1983038187 0.1019136087 0.2360561937 0.0049836547 2.5327440000 1.0000920000 0.2496950000 0.0000050000 1.2659050000 0.0071990000 128069976 0 1784696832 3.8511869907 3.9719274044 4.0483689308 697 1311867741.8683021069 0.2006217837 0.1020552273 0.2360561937 0.0049804405 3.9778450000 1.0050430000 0.2112270000 0.1355080000 1.2704940000 1.3466480000 128072098 0 1783537664 3.8494620323 3.9721076488 4.0484533310 698 1311867741.9065721035 0.1990013570 0.1021941186 0.2360561937 0.0049777378 2.6942230000 1.0003170000 0.4101320000 0.0000060000 1.2679080000 0.0072020000 128074380 0 1785016320 3.8516786098 3.9718346596 4.0475196838 699 1311867741.9387769699 0.2009589076 0.1023354131 0.2360561937 0.0049752241 2.8725440000 1.0139470000 0.4365330000 0.1355510000 1.2695200000 0.0071840000 128076598 0 1784045568 3.8507483006 3.9724197388 4.0478358269 700 1311867741.9665379524 0.2010975331 0.1024765018 0.2360561937 0.0049728276 2.7349510000 1.0116590000 0.4297060000 0.0000060000 1.2774680000 0.0071780000 128078688 0 1782910976 3.8511781693 3.9719383717 4.0471754074 701 1311867742.0029959679 0.2022070736 0.1026187708 0.2360561937 0.0049694807 4.0955500000 1.0012790000 0.3241560000 0.1355910000 1.2726500000 1.3531390000 128080938 0 1784508416 3.8511323929 3.9714779854 4.0473923683 702 1311867742.0344839096 0.2022951096 0.1027607599 0.2360561937 0.0049664389 2.7414910000 1.0032520000 0.4444800000 0.0000060000 1.2768370000 0.0071870000 128083092 0 1783537664 3.8519263268 3.9726364613 4.0470843315 703 1311867742.0674400330 0.2032293975 0.1029036740 0.2360561937 0.0049643363 2.8756370000 1.0102650000 0.4346560000 0.1358400000 1.2786710000 0.0071330000 128085278 0 1782394880 3.8519198895 3.9726891518 4.0472917557 704 1311867742.1030650139 0.2036194354 0.1030467362 0.2360561937 0.0049609356 2.7906220000 1.0594330000 0.4306350000 0.0000050000 1.2845720000 0.0071740000 128087496 0 1783873536 3.8528969288 3.9732308388 4.0472445488 705 1311867742.1348879337 0.2057845592 0.1031924636 0.2360561937 0.0049594661 4.1388280000 1.0093640000 0.3313190000 0.1364230000 1.2893610000 1.3636240000 128089650 0 1785671680 3.8517546654 3.9728877544 4.0472598076 706 1311867742.1672229767 0.2050222605 0.1033366984 0.2360561937 0.0049571849 2.5601380000 1.0027170000 0.2520290000 0.0000050000 1.2882620000 0.0071590000 128091868 0 1784279040 3.8531963825 3.9738562107 4.0473189354 707 1311867742.2028279305 0.2053544819 0.1034809952 0.2360561937 0.0049540733 2.8464110000 1.0071530000 0.3962900000 0.1361990000 1.2906260000 0.0071000000 128094150 0 1783283712 3.8538784981 3.9739902020 4.0472793579 708 1311867742.2362670898 0.2052812427 0.1036247808 0.2360561937 0.0049514602 2.6220200000 0.9988430000 0.3134530000 0.0000060000 1.2936350000 0.0071700000 128096336 0 1784762368 3.8548479080 3.9744114876 4.0471234322 709 1311867742.2674059868 0.2068462372 0.1037703682 0.2360561937 0.0049484683 4.2636000000 1.0118280000 0.4312830000 0.1366820000 1.2952750000 1.3788050000 128098522 0 1783791616 3.8540823460 3.9730253220 4.0477595329 710 1311867742.3028159142 0.2075316608 0.1039165109 0.2360561937 0.0049465408 2.6122650000 1.0129130000 0.2828120000 0.0000050000 1.3003180000 0.0071520000 128100772 0 1782657024 3.8539798260 3.9736220837 4.0476312637 711 1311867742.3350739479 0.2075488418 0.1040622666 0.2360561937 0.0049432633 2.7403850000 0.9969780000 0.2879640000 0.1365110000 1.3029630000 0.0071160000 128102926 0 1784135680 3.8543064594 3.9738640785 4.0471363068 712 1311867742.3694241047 0.2087737620 0.1042093333 0.2360561937 0.0049403884 2.5631420000 1.0305650000 0.2111460000 0.0000050000 1.3054540000 0.0071450000 128105176 0 1785913344 3.8533182144 3.9732389450 4.0471606255 713 1311867742.4062991142 0.2098773122 0.1043575352 0.2360561937 0.0049370502 4.0929850000 1.0020660000 0.2410460000 0.1368930000 1.3069840000 1.3959820000 128107426 0 1784934400 3.8524830341 3.9734625816 4.0467166901 714 1311867742.4346439838 0.2107755840 0.1045065801 0.2360561937 0.0049336609 2.6261390000 0.9908680000 0.3110970000 0.0000050000 1.3080360000 0.0071180000 128109548 0 1783791616 3.8519208431 3.9728696346 4.0467276573 715 1311867742.4666969776 0.2102937996 0.1046545343 0.2360561937 0.0049304378 2.7513350000 0.9929050000 0.2936970000 0.1368460000 1.3118940000 0.0070540000 128111734 0 1785270272 3.8526988029 3.9737298489 4.0460667610 716 1311867742.5047059059 0.2105777413 0.1048024717 0.2360561937 0.0049272013 2.6884580000 1.0312150000 0.3248330000 0.0000050000 1.3154280000 0.0071430000 128113984 0 1784299520 3.8529238701 3.9740650654 4.0459671021 717 1311867742.5359389782 0.2100277692 0.1049492295 0.2360561937 0.0049251646 4.1079270000 0.9983000000 0.2512880000 0.1368060000 1.3148000000 1.3975990000 128116170 0 1783156736 3.8539595604 3.9752459526 4.0459961891 718 1311867742.5678529739 0.2099774331 0.1050955083 0.2360561937 0.0049226388 2.5652390000 0.9896890000 0.2391630000 0.0000060000 1.3203310000 0.0070560000 128118388 0 1784889344 3.8544268608 3.9753968716 4.0459570885 719 1311867742.6054639816 0.2112375051 0.1052431328 0.2360561937 0.0049198975 2.8857650000 0.9914890000 0.4264880000 0.1370800000 1.3138370000 0.0071370000 128120638 0 1784045568 3.8535501957 3.9742815495 4.0460863113 720 1311867742.6347279549 0.2106960267 0.1053895951 0.2360561937 0.0049166895 2.6993640000 1.0437610000 0.3231890000 0.0000060000 1.3162160000 0.0071090000 128122760 0 1782919168 3.8544235229 3.9750578403 4.0460734367 721 1311867742.6724960804 0.2109761536 0.1055360397 0.2360561937 0.0049138516 4.2984520000 0.9990090000 0.4270090000 0.1372520000 1.3186140000 1.4075570000 128125074 0 1784643584 3.8544261456 3.9745237827 4.0462503433 722 1311867742.7046229839 0.2109738290 0.1056820754 0.2360561937 0.0049104600 2.6204480000 0.9952850000 0.2883510000 0.0000050000 1.3198730000 0.0070540000 128127228 0 1783812096 3.8547399044 3.9740273952 4.0462331772 723 1311867742.7356119156 0.2108388692 0.1058275205 0.2360561937 0.0049070766 2.7314440000 0.9978630000 0.2572100000 0.1372990000 1.3228320000 0.0070360000 128129414 0 1783296000 3.8552920818 3.9743452072 4.0461459160 724 1311867742.7726070881 0.2110461146 0.1059728501 0.2360561937 0.0049041319 2.6188120000 0.9951350000 0.2823320000 0.0000050000 1.3252080000 0.0071120000 128131696 0 1785036800 3.8556435108 3.9736385345 4.0461573601 725 1311867742.8034689426 0.2118033618 0.1061188232 0.2360561937 0.0049038478 4.0971480000 0.9986740000 0.2132950000 0.1372530000 1.3270540000 1.4108940000 128133882 0 1783930880 3.8548822403 3.9737253189 4.0460724831 726 1311867742.8352251053 0.2125635594 0.1062654413 0.2360561937 0.0049035355 2.6280600000 0.9908730000 0.2847720000 0.0000050000 1.3362020000 0.0070200000 128136036 0 1783422976 3.8549292088 3.9738082886 4.0462508202 727 1311867742.8705639839 0.2128731757 0.1064120819 0.2360561937 0.0049004029 2.6478530000 0.9882960000 0.1752550000 0.1374990000 1.3307410000 0.0070260000 128138254 0 1785036800 3.8548612595 3.9743855000 4.0461201668 728 1311867742.9046700001 0.2123773992 0.1065576387 0.2360561937 0.0048973951 2.8090600000 1.0213270000 0.4362100000 0.0000050000 1.3345240000 0.0070460000 128140472 0 1783910400 3.8559844494 3.9739706516 4.0463595390 729 1311867742.9382069111 0.2128584385 0.1067034560 0.2360561937 0.0049128053 4.2164320000 0.9919070000 0.3142670000 0.1375570000 1.3363330000 1.4270290000 128142722 0 1783422976 3.8553404808 3.9743418694 4.0461850166 730 1311867742.9707310200 0.2130738199 0.1068491688 0.2360561937 0.0049142234 2.5605800000 0.9950280000 0.2112540000 0.0000050000 1.3382570000 0.0070480000 128144908 0 1785036800 3.8556282520 3.9742825031 4.0462422371 731 1311867743.0024189949 0.2137768865 0.1069954447 0.2360561937 0.0049153881 2.7273270000 0.9815380000 0.2477370000 0.1375350000 1.3434750000 0.0070370000 128147062 0 1783910400 3.8551402092 3.9742839336 4.0463829041 732 1311867743.0345149040 0.2130800188 0.1071403690 0.2360561937 0.0049163540 2.7943210000 1.0198130000 0.4190670000 0.0000050000 1.3391540000 0.0071210000 128149248 0 1783422976 3.8563313484 3.9748482704 4.0462455750 733 1311867743.0722420216 0.2136824131 0.1072857197 0.2360561937 0.0049151959 4.2559130000 0.9901410000 0.3559110000 0.1377190000 1.3398440000 1.4232340000 128151530 0 1785171968 3.8561425209 3.9739754200 4.0459613800 734 1311867743.1045989990 0.2135285288 0.1074304647 0.2360561937 0.0049131673 2.7832260000 0.9941770000 0.4240950000 0.0000050000 1.3479400000 0.0070600000 128153716 0 1784045568 3.8567521572 3.9746234417 4.0460863113 735 1311867743.1350400448 0.2138563544 0.1075752618 0.2360561937 0.0049110895 2.7098740000 0.9965200000 0.2128350000 0.1403750000 1.3438630000 0.0070100000 128155870 0 1783549952 3.8571615219 3.9743585587 4.0461487770 736 1311867743.1704380512 0.2143695503 0.1077203627 0.2360561937 0.0049132788 2.6425420000 0.9900490000 0.2863250000 0.0000050000 1.3501220000 0.0070030000 128158088 0 1785290752 3.8566782475 3.9738245010 4.0457806587 737 1311867743.2037980556 0.2138685137 0.1078643901 0.2360561937 0.0049111481 4.1404350000 0.9967240000 0.2108040000 0.1386590000 1.3470450000 1.4371900000 128160306 0 1784184832 3.8575491905 3.9748494625 4.0452480316 738 1311867743.2358140945 0.2152063847 0.1080098399 0.2360561937 0.0049093635 2.7896710000 0.9962300000 0.4278410000 0.0000050000 1.3491410000 0.0070060000 128162460 0 1783799808 3.8569176197 3.9741733074 4.0459084511 739 1311867743.2708129883 0.2150664926 0.1081547068 0.2360561937 0.0049099606 2.7194220000 1.0001240000 0.2096520000 0.1383840000 1.3551630000 0.0070660000 128164710 0 1785540608 3.8572163582 3.9749629498 4.0460467339 740 1311867743.3032529354 0.2143882662 0.1082982657 0.2360561937 0.0049179894 2.5979810000 1.0261650000 0.2044220000 0.0000050000 1.3503260000 0.0070730000 128166896 0 1784819712 3.8580012321 3.9755671024 4.0458559990 741 1311867743.3363931179 0.2134938091 0.1084402300 0.2360561937 0.0049147606 4.3472280000 0.9916330000 0.4212400000 0.1435330000 1.3494930000 1.4319450000 128169082 0 1784307712 3.8591318130 3.9754967690 4.0461068153 742 1311867743.3707330227 0.2139510512 0.1085824279 0.2360561937 0.0049120469 2.6063120000 0.9951200000 0.2394380000 0.0000050000 1.3555030000 0.0069980000 128171300 0 1785942016 3.8586962223 3.9765143394 4.0458898544 743 1311867743.4043838978 0.2144688070 0.1087249398 0.2360561937 0.0049088446 2.8075530000 0.9944210000 0.3107440000 0.1382630000 1.3470260000 0.0069910000 128173518 0 1785180160 3.8584868908 3.9756314754 4.0466027260 744 1311867743.4352641106 0.2152636349 0.1088681370 0.2360561937 0.0049097040 2.6343040000 1.0176240000 0.2408500000 0.0000050000 1.3595000000 0.0069900000 128175704 0 1784954880 3.8577232361 3.9749295712 4.0467643738 745 1311867743.4768960476 0.2156155556 0.1090114221 0.2360561937 0.0049088765 4.1812390000 0.9967570000 0.2471020000 0.1386920000 1.3505980000 1.4380080000 128178018 0 1784156160 3.8577291965 3.9748709202 4.0471978188 746 1311867743.5035250187 0.2163444161 0.1091553001 0.2360561937 0.0049064199 2.5781570000 1.0045340000 0.2052040000 0.0000050000 1.3520340000 0.0070860000 128180140 0 1783656448 3.8571250439 3.9758803844 4.0470056534 747 1311867743.5389750004 0.2162577808 0.1092986769 0.2360561937 0.0049058429 2.7192930000 1.0015540000 0.2050280000 0.1389540000 1.3574750000 0.0069980000 128182358 0 1785307136 3.8570039272 3.9754960537 4.0468673706 748 1311867743.5749680996 0.2167386562 0.1094423133 0.2360561937 0.0049062641 2.7099850000 1.0216780000 0.3191030000 0.0000050000 1.3518100000 0.0072380000 128184608 0 1784545280 3.8572006226 3.9756367207 4.0467348099 749 1311867743.6036109924 0.2167397887 0.1095855676 0.2360561937 0.0049106551 4.1426400000 1.0009620000 0.2049870000 0.1389010000 1.3567480000 1.4317700000 128186730 0 1784307712 3.8566999435 3.9762835503 4.0467700958 750 1311867743.6354589462 0.2169745564 0.1097287529 0.2360561937 0.0049108271 2.8043510000 1.0039480000 0.4266130000 0.0000060000 1.3575440000 0.0069800000 128188916 0 1785921536 3.8563747406 3.9753630161 4.0467243195 751 1311867743.6759150028 0.2168388516 0.1098713762 0.2360561937 0.0049076508 2.9465100000 1.0030540000 0.4356640000 0.1388310000 1.3518600000 0.0070350000 128191230 0 1785196544 3.8563582897 3.9750599861 4.0464200974 752 1311867743.7034959793 0.2156729251 0.1100120698 0.2360561937 0.0049049264 2.8062090000 1.0005050000 0.4300920000 0.0000060000 1.3592490000 0.0070770000 128193352 0 1784942592 3.8573374748 3.9758465290 4.0459876060 753 1311867743.7388861179 0.2162261754 0.1101531243 0.2360561937 0.0049029299 4.1413030000 0.9911640000 0.2085280000 0.1385270000 1.3526050000 1.4403230000 128195602 0 1784180736 3.8566079140 3.9752895832 4.0457391739 754 1311867743.7733619213 0.2167639434 0.1102945180 0.2360561937 0.0048998981 2.6506780000 0.9998630000 0.2801240000 0.0000050000 1.3543300000 0.0069830000 128197852 0 1784053760 3.8559079170 3.9740831852 4.0458507538 755 1311867743.8064749241 0.2173854262 0.1104363603 0.2360561937 0.0048976324 2.6893800000 0.9963450000 0.1750350000 0.1389850000 1.3627620000 0.0070490000 128200006 0 1785675776 3.8551173210 3.9747452736 4.0455684662 756 1311867743.8391659260 0.2180123478 0.1105786565 0.2360561937 0.0048950040 2.5839870000 0.9981910000 0.2112850000 0.0000060000 1.3573050000 0.0069770000 128202192 0 1784786944 3.8540220261 3.9739148617 4.0449805260 757 1311867743.8726658821 0.2168721557 0.1107190707 0.2360561937 0.0048925104 4.1855130000 1.0001470000 0.2370710000 0.1389580000 1.3628010000 1.4371100000 128204442 0 1784680448 3.8551418781 3.9737474918 4.0449643135 758 1311867743.9031310081 0.2172224820 0.1108595765 0.2360561937 0.0048894749 2.5978560000 1.0048120000 0.2107350000 0.0000060000 1.3593190000 0.0119890000 128206596 0 1783930880 3.8548972607 3.9742379189 4.0446243286 759 1311867743.9453630447 0.2191327214 0.1110022289 0.2360561937 0.0048868662 2.7327770000 1.0034390000 0.2095260000 0.1394450000 1.3639120000 0.0070240000 128208942 0 1783525376 3.8528435230 3.9731206894 4.0448274612 760 1311867743.9741249084 0.2180308998 0.1111430561 0.2360561937 0.0048852583 2.6538460000 1.0300050000 0.2397120000 0.0000060000 1.3678310000 0.0069520000 128211064 0 1785286656 3.8536181450 3.9747245312 4.0435867310 761 1311867744.0042529106 0.2176350057 0.1112829929 0.2360561937 0.0048866631 4.3644070000 1.0006890000 0.4090020000 0.1392050000 1.3626550000 1.4426650000 128213186 0 1784561664 3.8542442322 3.9768373966 4.0435104370 762 1311867744.0407259464 0.2174437493 0.1114223115 0.2360561937 0.0048858806 2.5892550000 1.0091620000 0.2019380000 0.0000050000 1.3616960000 0.0069780000 128215468 0 1783906304 3.8545570374 3.9749546051 4.0438308716 763 1311867744.0716118813 0.2165779620 0.1115601302 0.2360561937 0.0048838428 2.7812570000 0.9894850000 0.2712580000 0.1389310000 1.3652770000 0.0069580000 128217622 0 1785667584 3.8554019928 3.9762191772 4.0436816216 764 1311867744.1111290455 0.2174663246 0.1116987508 0.2360561937 0.0048812609 2.7861110000 1.0077210000 0.4027190000 0.0000050000 1.3584260000 0.0070560000 128219840 0 1784942592 3.8544480801 3.9753265381 4.0437555313 765 1311867744.1412119865 0.2172515541 0.1118367284 0.2360561937 0.0048785538 4.1953550000 1.0091210000 0.2383750000 0.1392750000 1.3623660000 1.4368820000 128221994 0 1784688640 3.8545749187 3.9769210815 4.0431141853 766 1311867744.1734991074 0.2173905671 0.1119745271 0.2360561937 0.0048768767 2.6226670000 1.0080330000 0.2411550000 0.0000050000 1.3563350000 0.0069930000 128224212 0 1784164352 3.8549194336 3.9782435894 4.0434312820 767 1311867744.2046771049 0.2183810025 0.1121132578 0.2360561937 0.0048806991 2.7622030000 1.0145940000 0.2418680000 0.1393350000 1.3498400000 0.0070170000 128226366 0 1783922688 3.8537776470 3.9760584831 4.0435066223 768 1311867744.2400228977 0.2175762951 0.1122505795 0.2360561937 0.0048779594 2.7970310000 1.0357080000 0.3881410000 0.0000050000 1.3568190000 0.0070210000 128228648 0 1785692160 3.8542485237 3.9755904675 4.0427837372 769 1311867744.2773048878 0.2179860473 0.1123880769 0.2360561937 0.0048767104 4.2447730000 1.0154900000 0.3084470000 0.1390200000 1.3485950000 1.4227360000 128230898 0 1784168448 3.8540701866 3.9783356190 4.0429234505 770 1311867744.3032519817 0.2178971767 0.1125251017 0.2360561937 0.0048756761 2.8087080000 1.0256960000 0.4179720000 0.0000050000 1.3484950000 0.0070370000 128232988 0 1783009280 3.8539302349 3.9764270782 4.0430345535 771 1311867744.3391230106 0.2171456516 0.1126607963 0.2360561937 0.0048788371 2.8150390000 1.0213530000 0.2865390000 0.1398970000 1.3508600000 0.0070390000 128235238 0 1784651776 3.8545565605 3.9759061337 4.0424289703 772 1311867744.3707659245 0.2171469331 0.1127961410 0.2360561937 0.0048771503 2.8119860000 1.0154490000 0.4311610000 0.0000050000 1.3479940000 0.0070710000 128237392 0 1783656448 3.8549189568 3.9775929451 4.0425434113 773 1311867744.4027431011 0.2178426832 0.1129320356 0.2360561937 0.0048747786 4.1763910000 1.0122190000 0.2435080000 0.1389930000 1.3515110000 1.4206360000 128239610 0 1783398400 3.8544995785 3.9766852856 4.0430765152 774 1311867744.4383800030 0.2185275406 0.1130684639 0.2360561937 0.0048721701 2.5878180000 1.0075060000 0.2117990000 0.0000050000 1.3520540000 0.0070020000 128241828 0 1785159680 3.8537752628 3.9762549400 4.0429382324 775 1311867744.4717690945 0.2191670835 0.1132053654 0.2360561937 0.0048692433 2.9138210000 1.0165510000 0.3930070000 0.1393870000 1.3472830000 0.0071080000 128244046 0 1784270848 3.8530995846 3.9762430191 4.0426616669 776 1311867744.5026860237 0.2181585282 0.1133406143 0.2360561937 0.0048664568 2.6302660000 1.0484950000 0.2121360000 0.0000050000 1.3530370000 0.0070780000 128246232 0 1784180736 3.8544900417 3.9773910046 4.0426735878 777 1311867744.5383169651 0.2184158266 0.1134758462 0.2360561937 0.0048665872 4.2738920000 1.0057750000 0.3512140000 0.1390960000 1.3471030000 1.4213280000 128248482 0 1785942016 3.8542075157 3.9764702320 4.0422725677 778 1311867744.5726189613 0.2176362425 0.1136097285 0.2360561937 0.0048643133 2.7877860000 1.0119590000 0.4098260000 0.0000050000 1.3485380000 0.0070960000 128250700 0 1785032704 3.8548367023 3.9762780666 4.0416331291 779 1311867744.6028740406 0.2192488462 0.1137453371 0.2360561937 0.0048669118 2.7886770000 0.9984890000 0.2805470000 0.1391640000 1.3538390000 0.0070630000 128252854 0 1784823808 3.8540303707 3.9760251045 4.0425443649 780 1311867744.6386809349 0.2178756893 0.1138788376 0.2360561937 0.0048680777 2.6162870000 1.0023470000 0.2483880000 0.0000040000 1.3482310000 0.0070780000 128255104 0 1784053760 3.8549025059 3.9767432213 4.0417709351 781 1311867744.6707758904 0.2172911763 0.1140112477 0.2360561937 0.0048651242 4.1063150000 1.0043720000 0.1751020000 0.1390290000 1.3549700000 1.4232360000 128257290 0 1783926784 3.8554525375 3.9766345024 4.0415616035 782 1311867744.7029349804 0.2188765109 0.1141453465 0.2360561937 0.0048677094 2.6963880000 1.0038750000 0.3223580000 0.0000050000 1.3481090000 0.0070230000 128259476 0 1785430016 3.8546600342 3.9764723778 4.0421700478 783 1311867744.7396171093 0.2172430158 0.1142770166 0.2360561937 0.0048707967 2.9439000000 1.0084800000 0.4313990000 0.1390900000 1.3475060000 0.0070360000 128261726 0 1784799232 3.8557651043 3.9780964851 4.0415744781 784 1311867744.7705199718 0.2187134475 0.1144102264 0.2360561937 0.0048685296 2.6928210000 1.0442480000 0.2788330000 0.0000050000 1.3531100000 0.0070070000 128263880 0 1784561664 3.8542859554 3.9765720367 4.0421872139 785 1311867744.8035891056 0.2189363241 0.1145433806 0.2360561937 0.0048688756 4.1450600000 1.0212920000 0.2065450000 0.1397850000 1.3468020000 1.4202630000 128266098 0 1783635968 3.8542816639 3.9756746292 4.0418653488 786 1311867744.8424170017 0.2187928557 0.1146760135 0.2360561937 0.0048663683 2.5871390000 1.0188270000 0.2055010000 0.0000060000 1.3461360000 0.0070260000 128268380 0 1783525376 3.8545904160 3.9764406681 4.0416159630 787 1311867744.8727390766 0.2180586457 0.1148073765 0.2360561937 0.0048670710 2.9844920000 1.0113650000 0.4575880000 0.1394470000 1.3594920000 0.0070030000 128270566 0 1785159680 3.8549497128 3.9756712914 4.0419058800 788 1311867744.9029939175 0.2189452946 0.1149395312 0.2360561937 0.0048643480 2.5898770000 1.0148120000 0.2068240000 0.0000050000 1.3507790000 0.0070050000 128272720 0 1784434688 3.8538765907 3.9748036861 4.0416173935 789 1311867744.9392940998 0.2180210203 0.1150701795 0.2360561937 0.0048634723 4.1464190000 1.0134530000 0.2066190000 0.1398690000 1.3568550000 1.4200200000 128275002 0 1784315904 3.8554077148 3.9761016369 4.0409574509 790 1311867744.9708900452 0.2174749076 0.1151998057 0.2360561937 0.0048632980 2.5892500000 1.0106710000 0.2130480000 0.0000060000 1.3489450000 0.0070550000 128277124 0 1785929728 3.8557686806 3.9762015343 4.0410385132 791 1311867745.0027489662 0.2183966041 0.1153302694 0.2360561937 0.0048689818 2.8125220000 1.0168380000 0.2871270000 0.1393540000 1.3517510000 0.0070450000 128279310 0 1785032704 3.8551249504 3.9757680893 4.0401067734 792 1311867745.0384869576 0.2182689756 0.1154602425 0.2360561937 0.0048692026 2.5862620000 1.0340220000 0.1746010000 0.0000050000 1.3609630000 0.0069890000 128281560 0 1784926208 3.8549373150 3.9755463600 4.0398507118 793 1311867745.0729780197 0.2187266946 0.1155904651 0.2360561937 0.0048689108 4.1914630000 1.0075880000 0.2431590000 0.1395280000 1.3584210000 1.4321710000 128283778 0 1784180736 3.8546252251 3.9752457142 4.0397787094 794 1311867745.1118760109 0.2184268534 0.1157199819 0.2360561937 0.0048706274 2.8137070000 1.0148990000 0.4221170000 0.0000050000 1.3599880000 0.0069800000 128286060 0 1783926784 3.8549137115 3.9759795666 4.0397706032 795 1311867745.1405589581 0.2184016407 0.1158491412 0.2360561937 0.0048677470 2.7389300000 1.0042120000 0.2121060000 0.1397620000 1.3659530000 0.0071130000 128288182 0 1785688064 3.8551845551 3.9764184952 4.0398712158 796 1311867745.1729030609 0.2196324170 0.1159795222 0.2360561937 0.0048651608 2.6726900000 1.0088890000 0.2818240000 0.0000060000 1.3643520000 0.0070580000 128290368 0 1784778752 3.8539872169 3.9749410152 4.0399475098 797 1311867745.2068369389 0.2205338925 0.1161107071 0.2360561937 0.0048622013 4.2730960000 1.0059400000 0.3093260000 0.1398060000 1.3707610000 1.4374590000 128292586 0 1784541184 3.8531200886 3.9751667976 4.0400991440 798 1311867745.2430789471 0.2196547836 0.1162404616 0.2360561937 0.0048621778 2.8214400000 1.0100350000 0.4246580000 0.0000050000 1.3691550000 0.0070960000 128294836 0 1783910400 3.8546638489 3.9767205715 4.0405449867 799 1311867745.2729060650 0.2202449143 0.1163706299 0.2360561937 0.0048591700 2.7320970000 1.0021300000 0.2024080000 0.1398490000 1.3708240000 0.0070120000 128296990 0 1783799808 3.8541460037 3.9766066074 4.0404014587 800 1311867745.3112850189 0.2209843397 0.1165013970 0.2360561937 0.0048565473 2.6561270000 1.0290880000 0.2328620000 0.0000050000 1.3775920000 0.0069310000 128299240 0 1785286656 3.8537869453 3.9754335880 4.0411605835 801 1311867745.3395059109 0.2206334174 0.1166313996 0.2360561937 0.0048535443 4.2421150000 0.9978930000 0.2760000000 0.1401960000 1.3726480000 1.4447770000 128301394 0 1784549376 3.8543021679 3.9753136635 4.0408411026 802 1311867745.3733940125 0.2208164036 0.1167613060 0.2360561937 0.0048511980 2.7198420000 1.0107090000 0.3188360000 0.0000050000 1.3735880000 0.0070140000 128303612 0 1784307712 3.8544437885 3.9747080803 4.0410766602 803 1311867745.4102098942 0.2215573639 0.1168918117 0.2360561937 0.0048487197 2.9593810000 0.9983170000 0.4211470000 0.1403380000 1.3822230000 0.0069690000 128305862 0 1783545856 3.8544306755 3.9744472504 4.0419554710 804 1311867745.4433169365 0.2225740701 0.1170232573 0.2360561937 0.0048459640 2.6023150000 0.9962190000 0.2089470000 0.0000050000 1.3804610000 0.0070010000 128308080 0 1783271424 3.8532736301 3.9749526978 4.0413432121 805 1311867745.4708619118 0.2209872454 0.1171524051 0.2360561937 0.0048433131 4.1628140000 1.0005520000 0.1733180000 0.1403940000 1.3860700000 1.4527430000 128310170 0 1785180160 3.8549094200 3.9754521847 4.0408072472 806 1311867745.5099780560 0.2224585414 0.1172830579 0.2360561937 0.0048411662 2.8294870000 1.0012950000 0.4272860000 0.0000060000 1.3834000000 0.0069600000 128312484 0 1784307712 3.8539717197 3.9753918648 4.0413746834 807 1311867745.5417380333 0.2227534652 0.1174137523 0.2360561937 0.0048403207 2.8584010000 1.0035840000 0.3141980000 0.1402150000 1.3837120000 0.0069680000 128314670 0 1784053760 3.8541150093 3.9737191200 4.0415749550 808 1311867745.5704059601 0.2213775814 0.1175424204 0.2360561937 0.0048378298 2.8425810000 1.0233810000 0.4083450000 0.0000060000 1.3943360000 0.0069330000 128316792 0 1785815040 3.8554756641 3.9730017185 4.0410490036 809 1311867745.6133821011 0.2219270915 0.1176714497 0.2360561937 0.0048352123 4.4089810000 0.9924930000 0.4051790000 0.1404620000 1.3909480000 1.4692490000 128319170 0 1784926208 3.8551836014 3.9732463360 4.0409631729 810 1311867745.6438291073 0.2226187885 0.1178010143 0.2360561937 0.0048337146 2.8037910000 0.9885170000 0.4048320000 0.0000050000 1.3937440000 0.0069170000 128321356 0 1784815616 3.8548526764 3.9732291698 4.0414328575 811 1311867745.6709001064 0.2233513296 0.1179311627 0.2360561937 0.0048389133 2.8987630000 0.9867680000 0.3459280000 0.1406110000 1.4079560000 0.0068520000 128323414 0 1783914496 3.8544676304 3.9741432667 4.0415821075 812 1311867745.7088780403 0.2229333371 0.1180604757 0.2360561937 0.0048367982 2.8189320000 0.9936940000 0.4057190000 0.0000050000 1.4027430000 0.0069540000 128325728 0 1783939072 3.8551750183 3.9742717743 4.0408086777 813 1311867745.7423269749 0.2237468362 0.1181904712 0.2360561937 0.0048346082 4.4093410000 0.9876790000 0.3895390000 0.1407320000 1.4048590000 1.4767670000 128327914 0 1785561088 3.8543708324 3.9739658833 4.0413041115 814 1311867745.7760419846 0.2244660109 0.1183210308 0.2360561937 0.0048394668 2.5883080000 0.9891000000 0.1697770000 0.0000050000 1.4118760000 0.0068500000 128330132 0 1784688640 3.8540222645 3.9728856087 4.0414485931 815 1311867745.8116889000 0.2244877964 0.1184512968 0.2360561937 0.0048441709 2.8229840000 0.9819120000 0.2773830000 0.1410510000 1.4059660000 0.0068400000 128332382 0 1784438784 3.8544335365 3.9736192226 4.0419197083 816 1311867745.8389890194 0.2242828608 0.1185809924 0.2360561937 0.0048442513 2.7993230000 1.0228630000 0.3487180000 0.0000050000 1.4111390000 0.0069560000 128334504 0 1786195968 3.8548617363 3.9728496075 4.0426492691 817 1311867745.8709759712 0.2263144702 0.1187128571 0.2360561937 0.0048423854 4.3134350000 0.9922460000 0.2699730000 0.1411200000 1.4081950000 1.4910680000 128336658 0 1785036800 3.8528363705 3.9731700420 4.0430450439 818 1311867745.9108459949 0.2251839638 0.1188430174 0.2360561937 0.0048413360 2.6800190000 0.9790270000 0.2735710000 0.0000050000 1.4105610000 0.0069160000 128338972 0 1784549376 3.8542490005 3.9747245312 4.0424914360 819 1311867745.9435789585 0.2259591669 0.1189738063 0.2360561937 0.0048421491 2.9751880000 0.9889870000 0.4095520000 0.1409770000 1.4182790000 0.0068290000 128341190 0 1783676928 3.8535280228 3.9730284214 4.0423974991 820 1311867745.9732220173 0.2278096080 0.1191065329 0.2360561937 0.0048399855 2.7998590000 0.9935980000 0.3743250000 0.0000050000 1.4151520000 0.0068670000 128343312 0 1782898688 3.8526391983 3.9703850746 4.0445365906 821 1311867746.0083909035 0.2284077555 0.1192396647 0.2360561937 0.0048376002 4.4564490000 0.9913850000 0.4017820000 0.1410870000 1.4190070000 1.4933820000 128345530 0 1784655872 3.8524963856 3.9706964493 4.0448122025 822 1311867746.0391409397 0.2280189097 0.1193719996 0.2360561937 0.0048348383 2.7575770000 0.9787110000 0.3377400000 0.0000050000 1.4235980000 0.0068010000 128347748 0 1783541760 3.8534216881 3.9704821110 4.0450854301 823 1311867746.0728518963 0.2277980894 0.1195037445 0.2360561937 0.0048322320 2.9717110000 0.9862720000 0.4007300000 0.1412690000 1.4267680000 0.0068840000 128349934 0 1782906880 3.8538203239 3.9711728096 4.0444393158 824 1311867746.1113359928 0.2278584838 0.1196352430 0.2360561937 0.0048306975 2.8407220000 0.9845520000 0.4094880000 0.0000060000 1.4301020000 0.0067810000 128352184 0 1784553472 3.8541505337 3.9708390236 4.0441532135 825 1311867746.1412689686 0.2306877226 0.1197698520 0.2360561937 0.0048295392 4.4805860000 0.9710120000 0.4028360000 0.1411370000 1.4422800000 1.5125530000 128354370 0 1783533568 3.8521208763 3.9689841270 4.0458297729 826 1311867746.1721889973 0.2302865237 0.1199036495 0.2360561937 0.0048269396 2.8282540000 0.9779440000 0.3961440000 0.0000050000 1.4374730000 0.0067540000 128356524 0 1782792192 3.8521530628 3.9701859951 4.0444221497 827 1311867746.2066209316 0.2285517156 0.1200350256 0.2360561937 0.0048249834 2.9142990000 0.9701720000 0.3418110000 0.1425630000 1.4431920000 0.0068480000 128358742 0 1784422400 3.8538804054 3.9720442295 4.0430231094 828 1311867746.2386920452 0.2312317342 0.1201693211 0.2360561937 0.0048238244 2.6986370000 0.9671110000 0.2669000000 0.0000050000 1.4480450000 0.0067870000 128360960 0 1785905152 3.8515603542 3.9685938358 4.0449185371 829 1311867746.2704648972 0.2317921966 0.1203039688 0.2360561937 0.0048209481 4.3605360000 0.9780180000 0.2599420000 0.1415930000 1.4461020000 1.5239820000 128363146 0 1784930304 3.8512709141 3.9671328068 4.0457777977 830 1311867746.3068819046 0.2290824056 0.1204350271 0.2360561937 0.0048207876 2.8224270000 0.9657340000 0.3891720000 0.0000050000 1.4507040000 0.0067850000 128365364 0 1783918592 3.8538653851 3.9689483643 4.0448741913 831 1311867746.3393440247 0.2304461449 0.1205674111 0.2360561937 0.0048228014 2.9810230000 0.9674240000 0.3937390000 0.1417680000 1.4615330000 0.0067030000 128367582 0 1785524224 3.8527672291 3.9690675735 4.0448956490 832 1311867746.3797800541 0.2316461056 0.1207009192 0.2360561937 0.0048206014 2.8342830000 0.9629460000 0.3970410000 0.0000050000 1.4568970000 0.0066860000 128369896 0 1784692736 3.8515899181 3.9672684669 4.0459198952 833 1311867746.4078478813 0.2308427840 0.1208331423 0.2360561937 0.0048198298 4.3370400000 0.9571100000 0.2228360000 0.1414730000 1.4655080000 1.5401000000 128372018 0 1783525376 3.8526620865 3.9676821232 4.0459423065 834 1311867746.4389901161 0.2304767370 0.1209646095 0.2360561937 0.0048171211 2.6083140000 0.9617070000 0.1644480000 0.0000050000 1.4657040000 0.0067330000 128374172 0 1785159680 3.8527779579 3.9689233303 4.0457596779 835 1311867746.4774639606 0.2296362817 0.1210947552 0.2360561937 0.0048165719 2.8445080000 0.9617140000 0.2612660000 0.1415980000 1.4624580000 0.0067150000 128376486 0 1784168448 3.8531370163 3.9688212872 4.0449142456 836 1311867746.5066781044 0.2294903100 0.1212244149 0.2360561937 0.0048139725 2.6991160000 0.9495970000 0.2613370000 0.0000050000 1.4714500000 0.0067040000 128378608 0 1783025664 3.8535528183 3.9684195518 4.0450096130 837 1311867746.5406761169 0.2299920321 0.1213543643 0.2360561937 0.0048141493 4.4607610000 0.9538250000 0.3351020000 0.1414590000 1.4662160000 1.5542220000 128380826 0 1784762368 3.8530333042 3.9694766998 4.0454230309 838 1311867746.5748629570 0.2306782156 0.1214848223 0.2360561937 0.0048119461 2.8171790000 0.9439630000 0.3888920000 0.0000050000 1.4668480000 0.0067260000 128383076 0 1783787520 3.8522474766 3.9688189030 4.0456280708 839 1311867746.6067559719 0.2284973115 0.1216123700 0.2360561937 0.0048118582 2.9826340000 0.9523410000 0.3971960000 0.1415540000 1.4747460000 0.0066600000 128385230 0 1782775808 3.8537018299 3.9705383778 4.0437407494 840 1311867746.6396849155 0.2298088223 0.1217411753 0.2360561937 0.0048142193 2.7028570000 0.9537250000 0.2632290000 0.0000050000 1.4692250000 0.0067390000 128387480 0 1784381440 3.8528509140 3.9695405960 4.0449566841 841 1311867746.6749529839 0.2296469808 0.1218694819 0.2360561937 0.0048156671 4.3968200000 0.9487420000 0.2712330000 0.1415590000 1.4709770000 1.5534630000 128389698 0 1783406592 3.8528192043 3.9697217941 4.0441808701 842 1311867746.7095060349 0.2301625907 0.1219980960 0.2360561937 0.0048129607 2.8564120000 0.9692860000 0.3904830000 0.0000050000 1.4797700000 0.0066680000 128391916 0 1782665216 3.8527626991 3.9684293270 4.0449771881 843 1311867746.7391049862 0.2305096537 0.1221268167 0.2360561937 0.0048106870 2.9768940000 0.9534160000 0.3870600000 0.1419490000 1.4778200000 0.0066810000 128394038 0 1784528896 3.8525924683 3.9679400921 4.0451941490 844 1311867746.7751340866 0.2310893834 0.1222559193 0.2360561937 0.0048081043 2.8541960000 0.9546040000 0.3997980000 0.0000050000 1.4822040000 0.0067110000 128396320 0 1783779328 3.8522610664 3.9675920010 4.0455226898 845 1311867746.8070099354 0.2307339907 0.1223842957 0.2360561937 0.0048061604 4.4364870000 0.9581510000 0.2676350000 0.1419130000 1.4922200000 1.5663250000 128398506 0 1782915072 3.8525266647 3.9676663876 4.0448541641 846 1311867746.8401610851 0.2306566834 0.1225122772 0.2360561937 0.0048034955 2.8378960000 0.9500800000 0.3865010000 0.0000050000 1.4847490000 0.0067110000 128400692 0 1784655872 3.8526961803 3.9668486118 4.0448870659 847 1311867746.8748359680 0.2277926356 0.1226365752 0.2360561937 0.0048015838 2.8337690000 0.9589780000 0.2247340000 0.1420730000 1.4904720000 0.0066120000 128402942 0 1783787520 3.8548176289 3.9688446522 4.0421009064 848 1311867746.9086029530 0.2293862551 0.1227624592 0.2360561937 0.0047997332 2.7467520000 0.9448880000 0.2913450000 0.0000050000 1.4937360000 0.0065970000 128405128 0 1783279616 3.8542227745 3.9695377350 4.0435581207 849 1311867746.9389610291 0.2293673307 0.1228880245 0.2360561937 0.0047973780 4.5306970000 0.9365360000 0.3842120000 0.1415720000 1.4875290000 1.5708880000 128407314 0 1784909824 3.8546068668 3.9676277637 4.0440053940 850 1311867746.9748229980 0.2290589958 0.1230129315 0.2360561937 0.0047981243 2.7527310000 0.9514940000 0.2947520000 0.0000050000 1.4888880000 0.0066120000 128409564 0 1783803904 3.8555991650 3.9679567814 4.0435848236 851 1311867747.0066559315 0.2284765095 0.1231368605 0.2360561937 0.0048005936 2.9846630000 0.9370250000 0.3947530000 0.1416590000 1.4944730000 0.0066120000 128411718 0 1782878208 3.8551862240 3.9689717293 4.0425777435 852 1311867747.0389339924 0.2293559164 0.1232615307 0.2360561937 0.0047987024 2.8325260000 0.9332250000 0.3926000000 0.0000060000 1.4900980000 0.0065910000 128413904 0 1784651776 3.8550097942 3.9667553902 4.0441370010 853 1311867747.0749640465 0.2294392884 0.1233860064 0.2360561937 0.0047972833 4.5664310000 0.9431400000 0.3963210000 0.1418240000 1.4979350000 1.5763920000 128416186 0 1783513088 3.8554892540 3.9679205418 4.0440826416 854 1311867747.1066820621 0.2285043299 0.1235090958 0.2360561937 0.0048011763 2.7228980000 0.9473300000 0.2611260000 0.0000050000 1.4976290000 0.0066680000 128418340 0 1783025664 3.8561356068 3.9679088593 4.0440387726 855 1311867747.1389479637 0.2283263057 0.1236316890 0.2360561937 0.0047989261 2.7954540000 0.9544360000 0.1899880000 0.1420850000 1.4922310000 0.0066800000 128420526 0 1784680448 3.8567163944 3.9694709778 4.0441632271 856 1311867747.1744880676 0.2285129875 0.1237542139 0.2360561937 0.0047969388 2.8579240000 0.9468010000 0.3928890000 0.0000050000 1.5006070000 0.0066590000 128422776 0 1783668736 3.8566513062 3.9687650204 4.0441284180 857 1311867747.2066030502 0.2283565849 0.1238762703 0.2360561937 0.0047952838 4.5612260000 0.9426170000 0.3940000000 0.1413700000 1.4928350000 1.5801880000 128424962 0 1782771712 3.8568084240 3.9682006836 4.0439743996 858 1311867747.2385439873 0.2267806232 0.1239962055 0.2360561937 0.0047931295 2.8433280000 0.9423680000 0.3905550000 0.0000060000 1.4937000000 0.0066000000 128427180 0 1784401920 3.8582220078 3.9693915844 4.0423598289 859 1311867747.2745490074 0.2288653255 0.1241182883 0.2360561937 0.0048016316 3.0000960000 0.9474200000 0.4002940000 0.1420320000 1.4938660000 0.0066530000 128429430 0 1785921536 3.8571591377 3.9676196575 4.0443425179 860 1311867747.3064720631 0.2297390103 0.1242411031 0.2360561937 0.0048099811 2.8410540000 0.9400400000 0.3905840000 0.0000050000 1.4927330000 0.0066760000 128431552 0 1784946688 3.8567159176 3.9665544033 4.0452518463 861 1311867747.3388469219 0.2264292389 0.1243597885 0.2360561937 0.0048364621 4.4896660000 0.9410650000 0.3192880000 0.1414490000 1.4975280000 1.5800530000 128433802 0 1784315904 3.8590879440 3.9678828716 4.0427107811 862 1311867747.3758800030 0.2284440100 0.1244805358 0.2360561937 0.0048449507 2.8528290000 0.9504470000 0.3868510000 0.0000050000 1.4987970000 0.0067740000 128436020 0 1785925632 3.8581299782 3.9669046402 4.0444173813 863 1311867747.4068729877 0.2273483723 0.1245997338 0.2360561937 0.0048449267 2.9946150000 0.9406570000 0.3944650000 0.1418770000 1.4999670000 0.0065680000 128438206 0 1784803328 3.8590476513 3.9681334496 4.0437550545 864 1311867747.4396450520 0.2256646603 0.1247167071 0.2360561937 0.0048447978 2.7717210000 0.9638770000 0.2893930000 0.0000050000 1.5016010000 0.0065680000 128440360 0 1783914496 3.8603346348 3.9695374966 4.0421929359 865 1311867747.4756069183 0.2268160433 0.1248347410 0.2360561937 0.0048460043 4.5832440000 0.9439010000 0.3906440000 0.1421370000 1.5091230000 1.5873540000 128442610 0 1785679872 3.8594429493 3.9681701660 4.0431118011 866 1311867747.5095520020 0.2258819044 0.1249514236 0.2360561937 0.0048454441 2.7608530000 0.9197110000 0.3118080000 0.0000050000 1.5116670000 0.0065390000 128444860 0 1784573952 3.8606002331 3.9695708752 4.0430674553 867 1311867747.5405330658 0.2245923728 0.1250663498 0.2360561937 0.0048513262 2.9846520000 0.9387000000 0.3840980000 0.1416510000 1.5033680000 0.0065610000 128447014 0 1783808000 3.8612396717 3.9699823856 4.0411224365 868 1311867747.5766739845 0.2272752672 0.1251841020 0.2360561937 0.0048519891 2.7897600000 0.9388170000 0.3222120000 0.0000050000 1.5119690000 0.0066100000 128449264 0 1785397248 3.8593482971 3.9679861069 4.0431084633 869 1311867747.6086390018 0.2196042687 0.1252927558 0.2360561937 0.0048794578 4.5880040000 0.9429070000 0.3809330000 0.1426040000 1.5091950000 1.6014230000 128451450 0 1784549376 3.8640596867 3.9741790295 4.0353889465 870 1311867747.6432039738 0.2259640396 0.1254084699 0.2360561937 0.0048981593 2.8299400000 0.9243450000 0.3809820000 0.0000050000 1.5078430000 0.0065760000 128453700 0 1783406592 3.8604409695 3.9699013233 4.0422611237 871 1311867747.6760280132 0.2252814770 0.1255231347 0.2360561937 0.0049019654 2.9909350000 0.9300090000 0.3872630000 0.1419550000 1.5149970000 0.0065850000 128455886 0 1785163776 3.8609173298 3.9697396755 4.0419015884 872 1311867747.7068400383 0.2232924402 0.1256352554 0.2360561937 0.0049052963 2.8455100000 0.9350110000 0.3815380000 0.0000050000 1.5112730000 0.0065700000 128458040 0 1783894016 3.8606894016 3.9733195305 4.0373592377 873 1311867747.7480750084 0.2278175503 0.1257523027 0.2360561937 0.0049374759 4.6297030000 0.9893020000 0.3800730000 0.1426980000 1.5100980000 1.5972860000 128460450 0 1783898112 3.8582246304 3.9697685242 4.0429992676 874 1311867747.7826869488 0.2270371020 0.1258681892 0.2360561937 0.0049351946 2.6859920000 0.9285190000 0.2301800000 0.0000050000 1.5106530000 0.0065890000 128462668 0 1785544704 3.8590114117 3.9690914154 4.0429840088 875 1311867747.8149020672 0.2253387421 0.1259818699 0.2360561937 0.0049342342 2.9857120000 0.9366200000 0.3791470000 0.1421900000 1.5100650000 0.0065450000 128464854 0 1784438784 3.8596105576 3.9692811966 4.0413184166 876 1311867747.8466539383 0.2255903035 0.1260955781 0.2360561937 0.0049317358 2.8451760000 0.9419050000 0.3745180000 0.0000050000 1.5118000000 0.0066670000 128467008 0 1783689216 3.8590533733 3.9712238312 4.0408043861 877 1311867747.8827810287 0.2286548913 0.1262125215 0.2360561937 0.0049418664 4.4192270000 0.9360680000 0.2188870000 0.1424770000 1.5146620000 1.5969810000 128469290 0 1785417728 3.8569955826 3.9696474075 4.0438537598 878 1311867747.9150440693 0.2283249497 0.1263288226 0.2360561937 0.0049390665 2.8504520000 0.9415040000 0.3822340000 0.0000050000 1.5090520000 0.0065190000 128471508 0 1784569856 3.8560190201 3.9700214863 4.0422739983 879 1311867747.9477820396 0.2299626321 0.1264467223 0.2360561937 0.0049370758 2.8839060000 0.9353880000 0.2828280000 0.1419830000 1.5068470000 0.0065910000 128473694 0 1783681024 3.8549983501 3.9687693119 4.0445513725 880 1311867747.9826579094 0.2299705893 0.1265643631 0.2360561937 0.0049347499 2.8553180000 0.9422320000 0.3850750000 0.0000060000 1.5112010000 0.0065220000 128475912 0 1785397248 3.8547627926 3.9685008526 4.0450153351 881 1311867748.0146598816 0.2317852974 0.1266837966 0.2360561937 0.0049361203 4.4539410000 0.9440390000 0.2573820000 0.1423650000 1.5032650000 1.5958000000 128478098 0 1784549376 3.8529891968 3.9681031704 4.0466890335 882 1311867748.0469269753 0.2317657918 0.1268029372 0.2360561937 0.0049336548 2.8489840000 0.9444790000 0.3849880000 0.0000050000 1.5025440000 0.0065320000 128480284 0 1783406592 3.8519871235 3.9689254761 4.0461263657 883 1311867748.0828750134 0.2330931723 0.1269233112 0.2360561937 0.0049316938 2.8104560000 0.9247870000 0.2222570000 0.1419580000 1.5045770000 0.0065930000 128482566 0 1785167872 3.8504564762 3.9682466984 4.0473499298 884 1311867748.1150569916 0.2336846143 0.1270440819 0.2360561937 0.0049311559 2.8839520000 0.9887710000 0.3824290000 0.0000050000 1.4949840000 0.0066330000 128484720 0 1784061952 3.8500711918 3.9676299095 4.0487957001 885 1311867748.1486010551 0.2347512692 0.1271657849 0.2360561937 0.0049301350 4.4217740000 0.9593180000 0.2234950000 0.1478330000 1.4996030000 1.5809980000 128486938 0 1783300096 3.8480865955 3.9685819149 4.0481190681 886 1311867748.1831040382 0.2338106483 0.1272861516 0.2360561937 0.0049277161 2.7373640000 0.9313030000 0.2895600000 0.0000050000 1.4994530000 0.0065670000 128489124 0 1784913920 3.8488144875 3.9681272507 4.0480203629 887 1311867748.2148320675 0.2365316600 0.1274093145 0.2365316600 0.0049285904 2.8198470000 0.9484940000 0.2205420000 0.1423380000 1.4906200000 0.0066530000 128491342 0 1783816192 3.8466649055 3.9672033787 4.0503563881 888 1311867748.2466599941 0.2357892245 0.1275313639 0.2365316600 0.0049272317 2.8755120000 0.9727890000 0.3957870000 0.0000050000 1.4898850000 0.0065590000 128493496 0 1782919168 3.8469381332 3.9679231644 4.0494208336 889 1311867748.2827599049 0.2348359376 0.1276520665 0.2365316600 0.0049249004 4.3625120000 0.9465870000 0.1943840000 0.1419070000 1.4888440000 1.5804180000 128495746 0 1784659968 3.8475155830 3.9679100513 4.0488109589 890 1311867748.3148829937 0.2346297354 0.1277722661 0.2365316600 0.0049308265 2.7865100000 0.9515220000 0.3297580000 0.0000050000 1.4874390000 0.0066140000 128497932 0 1783427072 3.8478202820 3.9673874378 4.0493316650 891 1311867748.3470869064 0.2351190299 0.1278927451 0.2365316600 0.0049341422 2.8235060000 0.9434680000 0.2273960000 0.1472170000 1.4884200000 0.0066350000 128500118 0 1782648832 3.8469216824 3.9667744637 4.0488901138 892 1311867748.3826999664 0.2354200333 0.1280132914 0.2365316600 0.0049348361 2.8460580000 0.9565740000 0.3838590000 0.0000050000 1.4887380000 0.0065840000 128502368 0 1784270848 3.8467156887 3.9673023224 4.0492768288 893 1311867748.4148259163 0.2351451814 0.1281332599 0.2365316600 0.0049324473 4.5392740000 0.9470910000 0.3873980000 0.1416810000 1.4842350000 1.5685310000 128504522 0 1786032128 3.8463058472 3.9686129093 4.0481967926 894 1311867748.4520189762 0.2362253219 0.1282541682 0.2365316600 0.0049366627 2.8530230000 0.9607220000 0.3943210000 0.0000050000 1.4799490000 0.0066500000 128506804 0 1785204736 3.8450963497 3.9671616554 4.0493440628 895 1311867748.4831318855 0.2357259393 0.1283742484 0.2365316600 0.0049341232 2.9805420000 0.9516380000 0.3947000000 0.1415910000 1.4753630000 0.0066160000 128508990 0 1784025088 3.8450372219 3.9678568840 4.0484814644 896 1311867748.5149960518 0.2341752797 0.1284923299 0.2365316600 0.0049317586 2.7909510000 0.9758060000 0.3251520000 0.0000040000 1.4729650000 0.0066230000 128511176 0 1785778176 3.8462233543 3.9685606956 4.0476098061 897 1311867748.5467929840 0.2359685898 0.1286121474 0.2365316600 0.0049298626 4.3662780000 0.9568170000 0.2287900000 0.1418710000 1.4746670000 1.5528240000 128513330 0 1784958976 3.8446369171 3.9675745964 4.0492763519 898 1311867748.5827159882 0.2367086709 0.1287325221 0.2367086709 0.0049271865 2.7387850000 0.9612960000 0.2956530000 0.0000040000 1.4646990000 0.0067050000 128515580 0 1783771136 3.8434579372 3.9678666592 4.0492014885 899 1311867748.6147999763 0.2349919081 0.1288507195 0.2367086709 0.0049254725 2.9843370000 0.9634280000 0.3977720000 0.1419150000 1.4642120000 0.0066330000 128517798 0 1785524224 3.8448791504 3.9685964584 4.0488915443 900 1311867748.6470849514 0.2355494350 0.1289692736 0.2367086709 0.0049344307 2.7114450000 1.0083220000 0.2208750000 0.0000050000 1.4643600000 0.0066420000 128519952 0 1784692736 3.8443663120 3.9684162140 4.0499787331 901 1311867748.6827559471 0.2345410585 0.1290864454 0.2367086709 0.0049321894 4.3487650000 0.9431600000 0.2615610000 0.1413030000 1.4542720000 1.5378830000 128522202 0 1783926784 3.8451812267 3.9682309628 4.0498156548 902 1311867748.7147359848 0.2340147942 0.1292027739 0.2367086709 0.0049496524 2.6854190000 0.9503560000 0.2650110000 0.0000050000 1.4529830000 0.0066580000 128524388 0 1785540608 3.8459599018 3.9669272900 4.0504274368 903 1311867748.7499361038 0.2354280353 0.1293204099 0.2367086709 0.0049475210 2.8061660000 0.9622550000 0.2255340000 0.1418850000 1.4580940000 0.0066570000 128526606 0 1784815616 3.8443315029 3.9665169716 4.0510196686 904 1311867748.7828259468 0.2348924279 0.1294371931 0.2367086709 0.0049453606 2.8192020000 0.9591340000 0.3917860000 0.0000050000 1.4510840000 0.0067420000 128528856 0 1784561664 3.8443384171 3.9669427872 4.0504541397 905 1311867748.8151619434 0.2346195877 0.1295534167 0.2367086709 0.0049428462 4.3593770000 0.9558920000 0.2641540000 0.1416130000 1.4539540000 1.5323730000 128531042 0 1783652352 3.8443684578 3.9672117233 4.0506362915 906 1311867748.8466329575 0.2341339141 0.1296688477 0.2367086709 0.0049402588 2.8150530000 0.9461330000 0.4003050000 0.0000040000 1.4507780000 0.0072630000 128533164 0 1783508992 3.8443245888 3.9673988819 4.0504183769 907 1311867748.8829579353 0.2337796539 0.1297836336 0.2367086709 0.0049382411 2.9620890000 0.9607680000 0.3995010000 0.1416090000 1.4430210000 0.0068040000 128535414 0 1785159680 3.8438212872 3.9675178528 4.0500049591 908 1311867748.9149119854 0.2329342961 0.1298972357 0.2367086709 0.0049367048 2.7487550000 0.9603270000 0.3238230000 0.0000040000 1.4465140000 0.0068000000 128537632 0 1784442880 3.8438796997 3.9685759544 4.0497536659 909 1311867748.9472498894 0.2344079316 0.1300122089 0.2367086709 0.0049341454 4.4763270000 0.9598660000 0.4002310000 0.1412970000 1.4361660000 1.5280980000 128539818 0 1784299520 3.8419990540 3.9675395489 4.0504946709 910 1311867748.9829359055 0.2319007218 0.1301241743 0.2367086709 0.0049328190 2.6748370000 0.9601970000 0.2635680000 0.0000050000 1.4338680000 0.0068210000 128542068 0 1785921536 3.8432796001 3.9684102535 4.0487947464 911 1311867749.0159859657 0.2310992479 0.1302350142 0.2367086709 0.0049301171 2.7479970000 0.9575060000 0.1944940000 0.1408990000 1.4369540000 0.0067600000 128544254 0 1785196544 3.8434443474 3.9695458412 4.0481348038 912 1311867749.0467190742 0.2305258363 0.1303449822 0.2367086709 0.0049278067 2.6577340000 0.9504940000 0.2625630000 0.0000050000 1.4273090000 0.0067240000 128546408 0 1784942592 3.8436119556 3.9694070816 4.0481367111 913 1311867749.0828969479 0.2302290946 0.1304543843 0.2367086709 0.0049252437 4.3515800000 0.9567020000 0.3071490000 0.1407160000 1.4253140000 1.5103010000 128548658 0 1784180736 3.8434443474 3.9695856571 4.0479922295 914 1311867749.1158421040 0.2287379503 0.1305619155 0.2367086709 0.0049235392 2.6712710000 0.9627410000 0.2585810000 0.0000060000 1.4326040000 0.0067240000 128550876 0 1784180736 3.8445513248 3.9705910683 4.0472917557 915 1311867749.1485249996 0.2287779748 0.1306692555 0.2367086709 0.0049208665 2.7382540000 0.9643550000 0.1948400000 0.1412760000 1.4205140000 0.0067710000 128553094 0 1785958400 3.8442187309 3.9710450172 4.0473728180 916 1311867749.1829619408 0.2286213636 0.1307761901 0.2367086709 0.0049187012 2.8270260000 0.9866450000 0.4052210000 0.0000050000 1.4168890000 0.0067440000 128555312 0 1785032704 3.8436028957 3.9711809158 4.0471262932 917 1311867749.2156000137 0.2275833488 0.1308817595 0.2367086709 0.0049164431 4.2932260000 0.9648490000 0.2576080000 0.1402720000 1.4157020000 1.5040200000 128557466 0 1784926208 3.8444097042 3.9712772369 4.0466747284 918 1311867749.2468719482 0.2273276895 0.1309868204 0.2367086709 0.0049173257 2.6811860000 0.9601920000 0.2895520000 0.0000050000 1.4132200000 0.0067530000 128559620 0 1784033280 3.8444497585 3.9706420898 4.0460562706 919 1311867749.2828478813 0.2279310971 0.1310923093 0.2367086709 0.0049188021 2.8721930000 0.9607730000 0.3340640000 0.1461130000 1.4137820000 0.0067690000 128561870 0 1783918592 3.8440401554 3.9699630737 4.0472593307 920 1311867749.3148140907 0.2273646295 0.1311969531 0.2367086709 0.0049177590 2.8082270000 0.9697680000 0.4082770000 0.0000050000 1.4129440000 0.0068280000 128564088 0 1785548800 3.8438854218 3.9717633724 4.0457181931 921 1311867749.3468968868 0.2266988456 0.1313006468 0.2367086709 0.0049156469 4.3702380000 0.9777150000 0.3390670000 0.1408430000 1.4091550000 1.4919200000 128566242 0 1784815616 3.8438937664 3.9724647999 4.0452318192 922 1311867749.3828470707 0.2260980606 0.1314034640 0.2367086709 0.0049130291 2.6731990000 0.9770150000 0.2683390000 0.0000050000 1.4104070000 0.0067870000 128568492 0 1784561664 3.8435182571 3.9731402397 4.0439577103 923 1311867749.4147930145 0.2237568349 0.1315035218 0.2367086709 0.0049113213 2.7400880000 0.9788950000 0.2015100000 0.1405820000 1.4008420000 0.0068350000 128570710 0 1783783424 3.8450760841 3.9753146172 4.0425882339 924 1311867749.4467489719 0.2242043167 0.1316038473 0.2367086709 0.0049089453 2.6081430000 1.0043580000 0.1918230000 0.0000050000 1.3944090000 0.0068110000 128572864 0 1783529472 3.8440971375 3.9761042595 4.0425019264 925 1311867749.4829080105 0.2225484401 0.1317021658 0.2367086709 0.0049088249 4.3739420000 0.9911220000 0.3708870000 0.1404160000 1.3869320000 1.4740210000 128575114 0 1785307136 3.8445394039 3.9758610725 4.0417227745 926 1311867749.5159850121 0.2232825458 0.1318010647 0.2367086709 0.0049066367 2.6224260000 0.9839710000 0.2368300000 0.0000060000 1.3831570000 0.0069450000 128577300 0 1784016896 3.8434004784 3.9743354321 4.0425996780 927 1311867749.5468530655 0.2240795642 0.1319006100 0.2367086709 0.0049040718 2.9432590000 0.9901620000 0.4151130000 0.1402520000 1.3801270000 0.0069040000 128579486 0 1783508992 3.8414664268 3.9748268127 4.0418367386 928 1311867749.5830268860 0.2232436091 0.1319990400 0.2367086709 0.0049016250 2.7749380000 1.0060660000 0.3740780000 0.0000060000 1.3772970000 0.0068650000 128581736 0 1785176064 3.8414435387 3.9746918678 4.0415415764 929 1311867749.6148250103 0.2223931551 0.1320963426 0.2367086709 0.0048992117 4.2168050000 0.9940580000 0.2374880000 0.1402050000 1.3754360000 1.4580300000 128583890 0 1784434688 3.8413860798 3.9748933315 4.0409646034 930 1311867749.6469049454 0.2220392823 0.1321930554 0.2367086709 0.0048981456 2.7952950000 0.9839990000 0.4190950000 0.0000060000 1.3744030000 0.0069420000 128586108 0 1783898112 3.8416576385 3.9743552208 4.0414857864 931 1311867749.6829149723 0.2220212072 0.1322895411 0.2367086709 0.0048960373 2.8300650000 0.9886300000 0.3120550000 0.1403630000 1.3715690000 0.0069390000 128588358 0 1785675776 3.8403756618 3.9739909172 4.0407671928 932 1311867749.7160799503 0.2220539302 0.1323858548 0.2367086709 0.0048938491 2.6215050000 0.9951700000 0.2370040000 0.0000060000 1.3707700000 0.0069870000 128590544 0 1784942592 3.8397226334 3.9739930630 4.0401272774 933 1311867749.7468609810 0.2216284722 0.1324815061 0.2367086709 0.0048953387 4.1613150000 0.9794210000 0.2009430000 0.1394020000 1.3698200000 1.4608820000 128592730 0 1784688640 3.8400907516 3.9736359119 4.0401477814 934 1311867749.7828791142 0.2192117423 0.1325743650 0.2367086709 0.0048942592 2.6358750000 0.9832640000 0.2638980000 0.0000060000 1.3702530000 0.0069240000 128594980 0 1783926784 3.8414185047 3.9732689857 4.0390729904 935 1311867749.8148949146 0.2181367576 0.1326658756 0.2367086709 0.0048955689 2.7126250000 0.9774180000 0.2076090000 0.1397000000 1.3701050000 0.0069180000 128597134 0 1783926784 3.8418042660 3.9736983776 4.0386548042 936 1311867749.8469030857 0.2183256447 0.1327573924 0.2367086709 0.0048933369 2.6260800000 0.9989750000 0.2418240000 0.0000060000 1.3676360000 0.0069870000 128599352 0 1785540608 3.8414180279 3.9742994308 4.0389432907 937 1311867749.8829030991 0.2191604823 0.1328496049 0.2367086709 0.0049087531 4.3801070000 0.9916060000 0.4221380000 0.1398250000 1.3647650000 1.4500840000 128601602 0 1784795136 3.8403871059 3.9734876156 4.0388040543 938 1311867749.9149639606 0.2176119685 0.1329399699 0.2367086709 0.0049238632 2.6318660000 0.9745280000 0.2765110000 0.0000070000 1.3629820000 0.0069140000 128603756 0 1784672256 3.8408169746 3.9738869667 4.0380921364 939 1311867749.9508709908 0.2168836296 0.1330293667 0.2367086709 0.0049220634 2.9206540000 0.9853490000 0.4172020000 0.1392880000 1.3602750000 0.0069360000 128606006 0 1783910400 3.8412473202 3.9737215042 4.0382237434 940 1311867749.9827940464 0.2165496498 0.1331182181 0.2367086709 0.0049217535 2.6388880000 0.9860230000 0.2776710000 0.0000060000 1.3574400000 0.0069100000 128608224 0 1783672832 3.8410267830 3.9741394520 4.0378150940 941 1311867750.0147750378 0.2149828821 0.1332052156 0.2367086709 0.0049196382 4.3491200000 0.9782580000 0.4215340000 0.1388320000 1.3538690000 1.4458590000 128610410 0 1785294848 3.8420696259 3.9737701416 4.0374054909 942 1311867750.0470709801 0.2137951106 0.1332907675 0.2367086709 0.0049171878 2.5491010000 0.9724080000 0.2069110000 0.0000050000 1.3512450000 0.0069800000 128612596 0 1784406016 3.8428204060 3.9735565186 4.0369901657 943 1311867750.0829339027 0.2141250372 0.1333764879 0.2367086709 0.0049153927 2.6976900000 0.9778270000 0.2135740000 0.1385990000 1.3499270000 0.0069140000 128614846 0 1784315904 3.8420155048 3.9738035202 4.0368514061 944 1311867750.1156458855 0.2138555199 0.1334617411 0.2367086709 0.0049132956 2.8162250000 1.0247730000 0.4252740000 0.0000060000 1.3476610000 0.0069380000 128617032 0 1783398400 3.8418140411 3.9737994671 4.0366082191 945 1311867750.1474790573 0.2136725038 0.1335466202 0.2367086709 0.0049113150 4.3373850000 0.9885710000 0.4247250000 0.1386180000 1.3428910000 1.4316690000 128619218 0 1783402496 3.8416969776 3.9739146233 4.0366663933 946 1311867750.1828711033 0.2128174007 0.1336304159 0.2367086709 0.0049100881 2.5431740000 0.9754100000 0.2110810000 0.0000060000 1.3389810000 0.0069490000 128621468 0 1784905728 3.8420648575 3.9739351273 4.0361394882 947 1311867750.2156589031 0.2125683278 0.1337137717 0.2367086709 0.0049079229 2.6811810000 0.9829770000 0.2070690000 0.1380000000 1.3345070000 0.0069430000 128623654 0 1784184832 3.8419022560 3.9746403694 4.0359992981 948 1311867750.2469079494 0.2123134285 0.1337966827 0.2367086709 0.0049054052 2.6487040000 0.9856430000 0.3138230000 0.0000060000 1.3314380000 0.0070390000 128625808 0 1783672832 3.8417227268 3.9746577740 4.0358448029 949 1311867750.2829968929 0.2116508186 0.1338787208 0.2367086709 0.0049048053 4.2154480000 0.9800800000 0.3483110000 0.1379160000 1.3248180000 1.4135200000 128628058 0 1785303040 3.8420391083 3.9754507542 4.0361261368 950 1311867750.3150129318 0.2117626667 0.1339607039 0.2367086709 0.0049024950 2.5884610000 0.9804450000 0.2681430000 0.0000060000 1.3210460000 0.0069880000 128630276 0 1784545280 3.8413832188 3.9758930206 4.0357341766 951 1311867750.3469090462 0.2099101841 0.1340405667 0.2367086709 0.0049019378 2.8153500000 0.9899800000 0.3462540000 0.1435150000 1.3176600000 0.0069840000 128632430 0 1784307712 3.8430438042 3.9745624065 4.0356221199 952 1311867750.3828659058 0.2103513032 0.1341207250 0.2367086709 0.0048994345 2.5564710000 0.9840340000 0.2392210000 0.0000050000 1.3152920000 0.0070480000 128634680 0 1786068992 3.8424456120 3.9755451679 4.0356163979 953 1311867750.4148640633 0.2102659941 0.1342006256 0.2367086709 0.0048969788 4.0846760000 0.9885070000 0.2391060000 0.1375650000 1.3133700000 1.3943010000 128636898 0 1785188352 3.8421587944 3.9752678871 4.0356025696 954 1311867750.4469859600 0.2094848603 0.1342795399 0.2367086709 0.0048944678 2.5861750000 0.9877500000 0.2627770000 0.0000060000 1.3176660000 0.0070060000 128639052 0 1784827904 3.8424460888 3.9749202728 4.0353655815 955 1311867750.4829618931 0.2090795636 0.1343578645 0.2367086709 0.0048924670 2.6615670000 0.9859880000 0.2051550000 0.1382100000 1.3134970000 0.0070760000 128641270 0 1783930880 3.8423438072 3.9753065109 4.0344414711 956 1311867750.5148859024 0.2090227604 0.1344359659 0.2367086709 0.0048900968 2.5811400000 1.0115700000 0.2367800000 0.0000060000 1.3148110000 0.0070890000 128643424 0 1783656448 3.8420205116 3.9754316807 4.0341114998 957 1311867750.5476069450 0.2079015225 0.1345127324 0.2367086709 0.0048882261 4.0479970000 0.9898150000 0.2081000000 0.1370800000 1.3067890000 1.3953370000 128645642 0 1785450496 3.8429083824 3.9746940136 4.0337848663 958 1311867750.5827779770 0.2075592726 0.1345889814 0.2367086709 0.0048879183 2.5180500000 0.9814390000 0.2116560000 0.0000060000 1.3061600000 0.0070190000 128647892 0 1784692736 3.8429360390 3.9757735729 4.0335550308 959 1311867750.6148829460 0.2068928927 0.1346643765 0.2367086709 0.0048863426 2.7022340000 0.9908700000 0.2487720000 0.1370630000 1.3074740000 0.0071010000 128650046 0 1784168448 3.8431382179 3.9763345718 4.0330615044 960 1311867750.6469810009 0.2065983415 0.1347393077 0.2367086709 0.0048840570 2.6414010000 1.0016270000 0.3231140000 0.0000060000 1.2986260000 0.0071050000 128652264 0 1785798656 3.8427822590 3.9760818481 4.0327277184 961 1311867750.6829319000 0.2063729316 0.1348138484 0.2367086709 0.0048840328 4.2617160000 0.9862880000 0.4468430000 0.1365540000 1.3038940000 1.3763150000 128654514 0 1784692736 3.8425490856 3.9769515991 4.0329074860 962 1311867750.7149219513 0.2046669722 0.1348864608 0.2367086709 0.0048835298 2.5393150000 0.9932970000 0.2386750000 0.0000060000 1.2891640000 0.0071510000 128656732 0 1784184832 3.8439426422 3.9768047333 4.0326857567 963 1311867750.7469151020 0.2045031935 0.1349587524 0.2367086709 0.0048813179 2.7592510000 0.9962730000 0.3202960000 0.1368080000 1.2880100000 0.0070690000 128658886 0 1785815040 3.8438162804 3.9760806561 4.0327758789 964 1311867750.7832129002 0.2037394941 0.1350301017 0.2367086709 0.0048814232 2.5219570000 1.0098110000 0.2022450000 0.0000050000 1.2909300000 0.0071490000 128661104 0 1784926208 3.8442120552 3.9765338898 4.0329651833 965 1311867750.8149549961 0.2025157511 0.1351000350 0.2367086709 0.0048789747 4.1428290000 0.9925560000 0.3596770000 0.1362290000 1.2815120000 1.3617400000 128663226 0 1784573952 3.8453242779 3.9777531624 4.0331683159 966 1311867750.8468461037 0.2021095008 0.1351694030 0.2367086709 0.0048810257 2.5220780000 0.9817750000 0.2456970000 0.0000060000 1.2758060000 0.0071480000 128665412 0 1783664640 3.8453178406 3.9775540829 4.0329446793 967 1311867750.8828840256 0.2014689296 0.1352379650 0.2367086709 0.0048786623 2.6376620000 0.9948370000 0.2148990000 0.1361000000 1.2736460000 0.0071770000 128667694 0 1783169024 3.8456649780 3.9776649475 4.0327901840 968 1311867750.9147970676 0.2005848587 0.1353054722 0.2367086709 0.0048771210 2.4716260000 1.0106280000 0.1699680000 0.0000050000 1.2729870000 0.0071290000 128669848 0 1784918016 3.8465051651 3.9778876305 4.0329151154 969 1311867750.9468770027 0.2006541938 0.1353729115 0.2367086709 0.0048755524 3.9850070000 0.9961130000 0.2161570000 0.1361370000 1.2701930000 1.3546210000 128672034 0 1784061952 3.8461849689 3.9783263206 4.0329303741 970 1311867750.9830369949 0.2001038939 0.1354396445 0.2367086709 0.0048746907 2.5922770000 0.9873570000 0.3166750000 0.0000060000 1.2700200000 0.0071420000 128674316 0 1783283712 3.8465130329 3.9773294926 4.0328087807 971 1311867751.0168409348 0.1986093670 0.1355047008 0.2367086709 0.0048739154 2.8567680000 0.9976870000 0.4340720000 0.1362010000 1.2707430000 0.0071120000 128676534 0 1784930304 3.8476393223 3.9769308567 4.0323972702 972 1311867751.0470340252 0.1978406906 0.1355688325 0.2367086709 0.0048727614 2.7172880000 1.0003460000 0.4264340000 0.0000060000 1.2715610000 0.0071200000 128678688 0 1783808000 3.8477401733 3.9779295921 4.0318870544 973 1311867751.0828599930 0.1968101114 0.1356317732 0.2367086709 0.0048703902 4.1946020000 1.0042090000 0.4286920000 0.1354880000 1.2679200000 1.3471020000 128680906 0 1783046144 3.8483040333 3.9781048298 4.0311598778 974 1311867751.1174809933 0.1969097704 0.1356946869 0.2367086709 0.0048681271 2.6968190000 0.9875980000 0.4207350000 0.0000050000 1.2703360000 0.0071090000 128683156 0 1784676352 3.8476843834 3.9768903255 4.0307617188 975 1311867751.1468789577 0.1961812675 0.1357567245 0.2367086709 0.0048682215 2.6536580000 0.9869790000 0.2467480000 0.1347910000 1.2661100000 0.0071170000 128685278 0 1783554048 3.8483390808 3.9773387909 4.0303983688 976 1311867751.1835930347 0.1946559697 0.1358170720 0.2367086709 0.0048673510 2.5554400000 1.0119670000 0.2571640000 0.0000050000 1.2676330000 0.0076510000 128687560 0 1782792192 3.8491859436 3.9780712128 4.0299391747 977 1311867751.2161049843 0.1954454780 0.1358781042 0.2367086709 0.0048651661 3.9578770000 0.9894810000 0.2145870000 0.1350450000 1.2606620000 1.3470590000 128689746 0 1784389632 3.8480124474 3.9780488014 4.0297021866 978 1311867751.2468481064 0.1955492944 0.1359391177 0.2367086709 0.0048638634 2.5079180000 0.9832930000 0.2455830000 0.0000060000 1.2610190000 0.0071200000 128691900 0 1786040320 3.8478701115 3.9775707722 4.0294303894 979 1311867751.2831909657 0.1954669505 0.1359999224 0.2367086709 0.0048659516 2.8253490000 0.9822960000 0.4240630000 0.1344070000 1.2654470000 0.0070940000 128694182 0 1784930304 3.8476576805 3.9799151421 4.0294141769 980 1311867751.3149859905 0.1950245798 0.1360601516 0.2367086709 0.0048636540 2.5584260000 1.0142740000 0.2719450000 0.0000060000 1.2539660000 0.0071920000 128696336 0 1784172544 3.8478941917 3.9801645279 4.0291891098 981 1311867751.3498640060 0.1957537532 0.1361210014 0.2367086709 0.0048625671 3.9827820000 0.9921060000 0.2549530000 0.1344950000 1.2584610000 1.3318820000 128698586 0 1785778176 3.8466329575 3.9783580303 4.0288600922 982 1311867751.3834669590 0.1944141686 0.1361803631 0.2367086709 0.0048611352 2.5080010000 0.9882940000 0.2486800000 0.0000050000 1.2517710000 0.0071990000 128700804 0 1784651776 3.8475091457 3.9799549580 4.0281257629 983 1311867751.4151160717 0.1929957867 0.1362381611 0.2367086709 0.0048606900 2.6415310000 0.9886800000 0.2519620000 0.1341820000 1.2481500000 0.0074390000 128702990 0 1784143872 3.8490736485 3.9803440571 4.0273995399 984 1311867751.4513890743 0.1925942451 0.1362954335 0.2367086709 0.0048594715 2.5767390000 1.0121600000 0.2948820000 0.0000050000 1.2514880000 0.0072150000 128705208 0 1785794560 3.8490462303 3.9782772064 4.0271706581 985 1311867751.4838130474 0.1929527521 0.1363529536 0.2367086709 0.0048570602 4.0390100000 0.9914400000 0.3210990000 0.1348550000 1.2503640000 1.3292540000 128707426 0 1785069568 3.8486766815 3.9787774086 4.0266542435 986 1311867751.5149779320 0.1924505979 0.1364098478 0.2367086709 0.0048561440 2.6941150000 0.9926870000 0.4372650000 0.0000060000 1.2458670000 0.0072110000 128709612 0 1784926208 3.8486919403 3.9801230431 4.0264596939 987 1311867751.5495769978 0.1922270805 0.1364664002 0.2367086709 0.0048539128 2.6404890000 0.9920940000 0.2515420000 0.1339650000 1.2437950000 0.0071660000 128711830 0 1784164352 3.8486175537 3.9796597958 4.0263657570 988 1311867751.5829720497 0.1907077283 0.1365213003 0.2367086709 0.0048517403 2.5286080000 1.0123050000 0.2543230000 0.0000050000 1.2435670000 0.0072340000 128714016 0 1783762944 3.8503963947 3.9798064232 4.0261836052 989 1311867751.6149520874 0.1905298382 0.1365759096 0.2367086709 0.0048502244 3.9095830000 0.9903570000 0.2115940000 0.1335110000 1.2402660000 1.3226930000 128716202 0 1785548800 3.8503742218 3.9804000854 4.0260157585 990 1311867751.6501350403 0.1892862022 0.1366291523 0.2367086709 0.0048484142 2.5400490000 0.9920630000 0.2914620000 0.0000050000 1.2373470000 0.0071830000 128718420 0 1784823808 3.8509974480 3.9799389839 4.0256609917 991 1311867751.6839730740 0.1888967007 0.1366818945 0.2367086709 0.0048460254 2.6958060000 1.0056060000 0.2959970000 0.1391120000 1.2366260000 0.0072220000 128720670 0 1784561664 3.8511843681 3.9799134731 4.0254459381 992 1311867751.7150709629 0.1882562041 0.1367338848 0.2367086709 0.0048448095 2.6953820000 0.9972980000 0.4455250000 0.0000050000 1.2333540000 0.0072930000 128722792 0 1783635968 3.8516328335 3.9793834686 4.0252580643 993 1311867751.7507519722 0.1871898174 0.1367846964 0.2367086709 0.0048426300 3.9782910000 0.9964650000 0.2957840000 0.1331250000 1.2352850000 1.3063770000 128725042 0 1783549952 3.8522915840 3.9793555737 4.0249371529 994 1311867751.7830109596 0.1871163249 0.1368353318 0.2367086709 0.0048412950 2.5557030000 1.0032810000 0.2963890000 0.0000050000 1.2377320000 0.0072150000 128727228 0 1785196544 3.8520166874 3.9790804386 4.0248260498 995 1311867751.8149600029 0.1863346249 0.1368850798 0.2367086709 0.0048400912 2.6501690000 1.0082680000 0.2589100000 0.1335820000 1.2301130000 0.0072700000 128729414 0 1784438784 3.8525607586 3.9799995422 4.0247139931 996 1311867751.8509531021 0.1854453534 0.1369338351 0.2367086709 0.0048391186 2.5802920000 0.9978090000 0.3320630000 0.0000060000 1.2319970000 0.0072240000 128731664 0 1783910400 3.8531188965 3.9796094894 4.0244035721 997 1311867751.8832330704 0.1853295565 0.1369823765 0.2367086709 0.0048369729 4.0468260000 1.0114800000 0.3721730000 0.1328920000 1.2237730000 1.2953330000 128733850 0 1785561088 3.8527526855 3.9793162346 4.0243139267 998 1311867751.9149179459 0.1849072576 0.1370303974 0.2367086709 0.0048366074 2.6892450000 1.0134210000 0.4359690000 0.0000060000 1.2203900000 0.0072940000 128736004 0 1784401920 3.8525807858 3.9801080227 4.0242829323 999 1311867751.9530611038 0.1823665351 0.1370757789 0.2367086709 0.0048351424 2.8034330000 1.0019460000 0.4300450000 0.1323320000 1.2206560000 0.0072880000 128738318 0 1783914496 3.8547832966 3.9805178642 4.0240373611 1000 1311867751.9829521179 0.1815131754 0.1371202163 0.2367086709 0.0048334367 2.4461860000 1.0007510000 0.2164020000 0.0000050000 1.2106930000 0.0072400000 128740472 0 1785671680 3.8552331924 3.9800496101 4.0239019394 1001 1311867752.0153670311 0.1813394874 0.1371643914 0.2367086709 0.0048335482 4.0827520000 1.0145100000 0.4364470000 0.1319930000 1.2122790000 1.2751670000 128742626 0 1784827904 3.8549280167 3.9810402393 4.0239319801 1002 1311867752.0510330200 0.1792283058 0.1372063714 0.2367086709 0.0048317199 2.5514720000 1.0073840000 0.3278080000 0.0000050000 1.1976810000 0.0072770000 128744876 0 1784049664 3.8569078445 3.9816567898 4.0234155655 1003 1311867752.0828928947 0.1783639193 0.1372474058 0.2367086709 0.0048298156 2.6836470000 1.0164040000 0.3280740000 0.1315640000 1.1891380000 0.0072940000 128747094 0 1785798656 3.8572161198 3.9810314178 4.0231180191 1004 1311867752.1150529385 0.1751397401 0.1372851472 0.2367086709 0.0048281035 2.4749610000 1.0185610000 0.2529990000 0.0000060000 1.1837500000 0.0073280000 128749248 0 1784528896 3.8602962494 3.9807140827 4.0225553513 1005 1311867752.1509859562 0.1726459712 0.1373203321 0.2367086709 0.0048270920 3.8238850000 1.0208440000 0.2440040000 0.1323800000 1.1784570000 1.2369070000 128751498 0 1784057856 3.8618700504 3.9812293053 4.0220913887 1006 1311867752.1829679012 0.1726768464 0.1373554777 0.2367086709 0.0048260321 2.4838350000 1.0331430000 0.2572650000 0.0000060000 1.1748300000 0.0073900000 128753716 0 1785798656 3.8612444401 3.9809429646 4.0219259262 1007 1311867752.2150039673 0.1722113192 0.1373900913 0.2367086709 0.0048237059 2.5915050000 1.0250030000 0.2550130000 0.1307750000 1.1611180000 0.0074230000 128755902 0 1784676352 3.8610141277 3.9813895226 4.0215210915 1008 1311867752.2512340546 0.1707395017 0.1374231760 0.2367086709 0.0048234290 2.5059680000 1.0338050000 0.2987690000 0.0000050000 1.1546520000 0.0073160000 128758120 0 1783934976 3.8621532917 3.9823133945 4.0211238861 1009 1311867752.2833271027 0.1713265479 0.1374567770 0.2367086709 0.0048219400 3.9718880000 1.0289000000 0.4496400000 0.1305240000 1.1479750000 1.2037030000 128760306 0 1785548800 3.8613667488 3.9822466373 4.0213360786 1010 1311867752.3150799274 0.1685107648 0.1374875235 0.2367086709 0.0048242340 2.4386920000 1.0180560000 0.2593940000 0.0000060000 1.1415020000 0.0073480000 128762460 0 1784422400 3.8637578487 3.9813456535 4.0207824707 1011 1311867752.3509979248 0.1683262885 0.1375180267 0.2367086709 0.0048245483 2.5449260000 1.0283160000 0.2222160000 0.1305770000 1.1449870000 0.0073960000 128764710 0 1783554048 3.8641023636 3.9814860821 4.0208864212 1012 1311867752.3829851151 0.1690028906 0.1375491382 0.2367086709 0.0048223299 2.4310470000 1.0489450000 0.2257270000 0.0000050000 1.1377550000 0.0073740000 128766928 0 1785180160 3.8632998466 3.9807472229 4.0207662582 1013 1311867752.4160280228 0.1672154367 0.1375784238 0.2367086709 0.0048204291 3.9490730000 1.0253780000 0.4512620000 0.1298880000 1.1418750000 1.1884010000 128769114 0 1784197120 3.8649153709 3.9811131954 4.0202145576 1014 1311867752.4510710239 0.1679914445 0.1376084169 0.2367086709 0.0048238093 2.4332560000 1.0116060000 0.2651090000 0.0000060000 1.1377320000 0.0074010000 128771364 0 1783271424 3.8637402058 3.9814186096 4.0201916695 1015 1311867752.4829080105 0.1669224650 0.1376372978 0.2367086709 0.0048223455 2.7273280000 1.0239710000 0.4175860000 0.1302050000 1.1369180000 0.0074710000 128773550 0 1785049088 3.8649549484 3.9802634716 4.0196723938 1016 1311867752.5181159973 0.1669065803 0.1376661061 0.2367086709 0.0048227107 2.4437120000 1.0636800000 0.2217540000 0.0000050000 1.1386230000 0.0074210000 128775768 0 1783918592 3.8646044731 3.9799613953 4.0192532539 1017 1311867752.5511059761 0.1659405529 0.1376939079 0.2367086709 0.0048220328 3.7863300000 1.0215900000 0.2984160000 0.1296900000 1.1373210000 1.1879420000 128777954 0 1783029760 3.8656609058 3.9807167053 4.0186991692 1018 1311867752.5830090046 0.1653914005 0.1377211157 0.2367086709 0.0048198777 2.3996600000 1.0161390000 0.2214370000 0.0000050000 1.1434280000 0.0073480000 128780172 0 1784676352 3.8659942150 3.9809105396 4.0184931755 1019 1311867752.6167891026 0.1655949801 0.1377484698 0.2367086709 0.0048176520 2.7494170000 1.0201140000 0.4414540000 0.1296160000 1.1384430000 0.0073560000 128782358 0 1783152640 3.8658246994 3.9803252220 4.0180325508 1020 1311867752.6514921188 0.1661335230 0.1377762983 0.2367086709 0.0048167634 2.5518060000 1.0452430000 0.3440050000 0.0000060000 1.1437540000 0.0073640000 128784576 0 1782411264 3.8653447628 3.9808683395 4.0179619789 1021 1311867752.6830079556 0.1648000330 0.1378027662 0.2367086709 0.0048171750 3.7046960000 1.0168140000 0.2226410000 0.1296090000 1.1369310000 1.1872290000 128786762 0 1784020992 3.8667266369 3.9803423882 4.0174221992 1022 1311867752.7152869701 0.1639832258 0.1378283831 0.2367086709 0.0048183463 2.4409050000 1.0253980000 0.2573060000 0.0000060000 1.1395260000 0.0073930000 128788980 0 1785651200 3.8676767349 3.9796876907 4.0170454979 1023 1311867752.7510609627 0.1643788368 0.1378543366 0.2367086709 0.0048159930 2.7312430000 1.0112280000 0.4294000000 0.1293120000 1.1415850000 0.0074070000 128791166 0 1784287232 3.8671898842 3.9789884090 4.0165576935 1024 1311867752.7830440998 0.1644629985 0.1378803217 0.2367086709 0.0048250071 2.4283930000 1.0449030000 0.2196420000 0.0000060000 1.1448660000 0.0073440000 128793384 0 1784291328 3.8670947552 3.9801449776 4.0161938667 1025 1311867752.8162839413 0.1620580405 0.1379039097 0.2367086709 0.0048231230 3.9534190000 1.0096520000 0.4559930000 0.1292370000 1.1496440000 1.1965240000 128877490 0 1783898112 3.8694787025 3.9807472229 4.0153264999 1026 1311867752.8511059284 0.1611514986 0.1379265681 0.2367086709 0.0048209542 2.4402960000 1.0174830000 0.2621130000 0.0000050000 1.1416690000 0.0073380000 129047644 0 1783808000 3.8704900742 3.9808211327 4.0147819519 1027 1311867752.8833000660 0.1617961824 0.1379498102 0.2367086709 0.0048188716 2.6379710000 1.0121190000 0.3386880000 0.1290250000 1.1393530000 0.0073380000 129049862 0 1785438208 3.8697574139 3.9809224606 4.0147252083 1028 1311867752.9183809757 0.1601617038 0.1379714171 0.2367086709 0.0048166919 2.6568590000 1.0551190000 0.4464690000 0.0000050000 1.1353530000 0.0073840000 129052112 0 1784668160 3.8718178272 3.9814770222 4.0142483711 1029 1311867752.9511129856 0.1596381515 0.1379924732 0.2367086709 0.0048206646 3.9215080000 1.0199530000 0.4431480000 0.1294540000 1.1321450000 1.1852630000 129054266 0 1784561664 3.8722391129 3.9810461998 4.0139884949 1030 1311867752.9828579426 0.1600726992 0.1380139103 0.2367086709 0.0048185035 2.5109230000 1.0213570000 0.3336220000 0.0000050000 1.1361700000 0.0073460000 129056484 0 1783783424 3.8717355728 3.9808087349 4.0137028694 1031 1311867753.0168170929 0.1576430053 0.1380329492 0.2367086709 0.0048164094 2.5896270000 1.0071320000 0.3047820000 0.1285480000 1.1303090000 0.0073830000 129058670 0 1783545856 3.8744180202 3.9809975624 4.0132369995 1032 1311867753.0510199070 0.1594628394 0.1380537146 0.2367086709 0.0048143335 2.4585700000 1.0023530000 0.3026200000 0.0000050000 1.1347770000 0.0073950000 129060888 0 1785286656 3.8725275993 3.9804191589 4.0130124092 1033 1311867753.0829060078 0.1595423371 0.1380745168 0.2367086709 0.0048129403 3.7962920000 1.0159110000 0.3315330000 0.1286940000 1.1295420000 1.1782140000 129063042 0 1784397824 3.8722093105 3.9804980755 4.0124087334 1034 1311867753.1184310913 0.1581224352 0.1380939055 0.2367086709 0.0048107638 2.4328480000 1.0217140000 0.2637880000 0.0000050000 1.1284040000 0.0074200000 129065324 0 1784307712 3.8736133575 3.9818639755 4.0119662285 1035 1311867753.1510760784 0.1570709199 0.1381122408 0.2367086709 0.0048086288 2.7355580000 1.0083270000 0.4543400000 0.1282660000 1.1255710000 0.0073750000 129067478 0 1785921536 3.8746354580 3.9806208611 4.0117669106 1036 1311867753.1830070019 0.1574036032 0.1381308618 0.2367086709 0.0048066215 2.4479250000 1.0436440000 0.2563650000 0.0000050000 1.1280650000 0.0073890000 129069632 0 1785049088 3.8738911152 3.9796502590 4.0114102364 1037 1311867753.2186999321 0.1560271531 0.1381481195 0.2367086709 0.0048067293 3.8338020000 1.0103690000 0.3745410000 0.1278130000 1.1273030000 1.1821040000 129071914 0 1785053184 3.8751845360 3.9817826748 4.0112643242 1038 1311867753.2520470619 0.1555941105 0.1381649268 0.2367086709 0.0048044734 2.3635660000 1.0044500000 0.2168260000 0.0000050000 1.1224320000 0.0073510000 129074068 0 1784172544 3.8754258156 3.9819259644 4.0111460686 1039 1311867753.2829909325 0.1542374492 0.1381803961 0.2367086709 0.0048028636 2.5355170000 1.0112360000 0.2527070000 0.1276240000 1.1249080000 0.0073290000 129076254 0 1783898112 3.8762140274 3.9816482067 4.0107660294 1040 1311867753.3196740150 0.1499363929 0.1381916999 0.2367086709 0.0048049573 2.4853320000 1.0122080000 0.3363950000 0.0000050000 1.1178060000 0.0074520000 129078536 0 1785667584 3.8798687458 3.9828433990 4.0100021362 1041 1311867753.3509368896 0.1486683041 0.1382017639 0.2367086709 0.0048029262 3.8611500000 1.0048270000 0.4429060000 0.1323820000 1.1120530000 1.1564540000 129080658 0 1784799232 3.8809125423 3.9833066463 4.0098738670 1042 1311867753.3829340935 0.1500114501 0.1382130976 0.2367086709 0.0048023767 2.4068880000 1.0138110000 0.2553390000 0.0000050000 1.1183230000 0.0073810000 129082876 0 1784270848 3.8791897297 3.9813399315 4.0101332664 1043 1311867753.4182109833 0.1513000280 0.1382256449 0.2367086709 0.0048006932 2.7228970000 1.0143830000 0.4465850000 0.1280360000 1.1149930000 0.0073240000 129085126 0 1786068992 3.8773379326 3.9822142124 4.0097527504 1044 1311867753.4511721134 0.1499782950 0.1382369023 0.2367086709 0.0047986404 2.3973660000 1.0025090000 0.2626050000 0.0000060000 1.1123400000 0.0073920000 129087280 0 1785180160 3.8781094551 3.9828083515 4.0092301369 1045 1311867753.4831509590 0.1483747214 0.1382466035 0.2367086709 0.0047971443 3.7274230000 1.0583300000 0.2590640000 0.1266280000 1.1137810000 1.1578460000 129089498 0 1784926208 3.8790032864 3.9821810722 4.0084466934 1046 1311867753.5199849606 0.1475658864 0.1382555130 0.2367086709 0.0047949483 2.4411730000 1.0125050000 0.2885930000 0.0000050000 1.1200020000 0.0073940000 129091780 0 1784164352 3.8789718151 3.9829275608 4.0077037811 1047 1311867753.5532789230 0.1463000774 0.1382631964 0.2367086709 0.0047928207 2.6766320000 1.0070940000 0.4139190000 0.1260750000 1.1104710000 0.0073860000 129093966 0 1784053760 3.8795449734 3.9825229645 4.0074162483 1048 1311867753.5832290649 0.1448898166 0.1382695195 0.2367086709 0.0047908137 2.3940530000 1.0016710000 0.2664300000 0.0000050000 1.1069450000 0.0073770000 129096120 0 1785815040 3.8802623749 3.9824848175 4.0068316460 1049 1311867753.6183180809 0.1435218155 0.1382745265 0.2367086709 0.0047888463 3.7116300000 1.0384240000 0.2905360000 0.1256090000 1.1007240000 1.1437040000 129098370 0 1784795136 3.8806931973 3.9833407402 4.0063161850 1050 1311867753.6509299278 0.1438347101 0.1382798219 0.2367086709 0.0047869080 2.4291250000 1.0149330000 0.2970320000 0.0000050000 1.0979590000 0.0073020000 129100556 0 1784696832 3.8797576427 3.9825458527 4.0062065125 1051 1311867753.6830120087 0.1417603493 0.1382831335 0.2367086709 0.0047864962 2.5491410000 1.0103090000 0.2964590000 0.1251610000 1.0971510000 0.0075110000 129102710 0 1783934976 3.8813011646 3.9824001789 4.0055785179 1052 1311867753.7204821110 0.1403136104 0.1382850637 0.2367086709 0.0047844045 2.3500900000 1.0138530000 0.2228260000 0.0000050000 1.0942660000 0.0073140000 129105024 0 1783803904 3.8822300434 3.9833233356 4.0053644180 1053 1311867753.7510209084 0.1401650459 0.1382868490 0.2367086709 0.0047828563 3.7975780000 0.9949970000 0.4349840000 0.1247470000 1.0926190000 1.1386590000 129107146 0 1785434112 3.8815555573 3.9830045700 4.0053281784 1054 1311867753.7865459919 0.1383216828 0.1382868821 0.2367086709 0.0047823449 2.5626620000 1.0101760000 0.4415880000 0.0000050000 1.0910550000 0.0073040000 129109396 0 1784545280 3.8824286461 3.9822301865 4.0049271584 1055 1311867753.8151860237 0.1358623654 0.1382845839 0.2367086709 0.0047810289 2.6217330000 1.0055970000 0.3804500000 0.1245410000 1.0918940000 0.0073310000 129111518 0 1784016896 3.8848085403 3.9839088917 4.0047874451 1056 1311867753.8510670662 0.1353787929 0.1382818322 0.2367086709 0.0047802828 2.5884940000 1.0420100000 0.4403150000 0.0000050000 1.0873080000 0.0073590000 129113768 0 1785815040 3.8843154907 3.9838805199 4.0047311783 1057 1311867753.8831698895 0.1340936720 0.1382778699 0.2367086709 0.0047888151 3.8148750000 1.0082410000 0.4514910000 0.1248640000 1.0891790000 1.1284610000 129115986 0 1785073664 3.8849713802 3.9819345474 4.0045042038 1058 1311867753.9155960083 0.1324797422 0.1382723897 0.2367086709 0.0047872695 2.5674210000 1.0066160000 0.4396150000 0.0000050000 1.1020630000 0.0073030000 129118140 0 1784565760 3.8858838081 3.9826633930 4.0042328835 1059 1311867753.9511620998 0.1312418878 0.1382657509 0.2367086709 0.0047881105 2.4556740000 0.9978730000 0.2181620000 0.1240480000 1.0956880000 0.0073260000 129120390 0 1783676928 3.8864650726 3.9842431545 4.0044493675 1060 1311867753.9859020710 0.1311618388 0.1382590490 0.2367086709 0.0047879261 2.5923470000 1.0282310000 0.4453630000 0.0000060000 1.0996340000 0.0073040000 129122640 0 1783132160 3.8857884407 3.9828929901 4.0045170784 1061 1311867754.0151760578 0.1309199333 0.1382521319 0.2367086709 0.0047863543 3.7077120000 1.0082400000 0.3295840000 0.1237330000 1.0973650000 1.1369690000 129124762 0 1784799232 3.8848099709 3.9816107750 4.0047044754 1062 1311867754.0510439873 0.1270999163 0.1382416307 0.2367086709 0.0047927780 2.3786250000 1.0025560000 0.2554620000 0.0000050000 1.1007310000 0.0072770000 129127044 0 1783934976 3.8879613876 3.9833230972 4.0047049522 1063 1311867754.0839149952 0.1251554191 0.1382293201 0.2367086709 0.0047914101 2.4614650000 1.0046790000 0.2139570000 0.1232430000 1.1002060000 0.0074700000 129129230 0 1783558144 3.8892290592 3.9831230640 4.0045099258 1064 1311867754.1166028976 0.1235036701 0.1382154802 0.2367086709 0.0047900035 2.5624210000 1.0009010000 0.4430380000 0.0000050000 1.0994830000 0.0072710000 129131416 0 1785188352 3.8900301456 3.9823760986 4.0047993660 1065 1311867754.1511039734 0.1213644445 0.1381996576 0.2367086709 0.0047905634 3.6500100000 0.9878020000 0.2867350000 0.1224830000 1.0993170000 1.1409690000 129133602 0 1784291328 3.8913691044 3.9829120636 4.0045399666 1066 1311867754.1832261086 0.1203383133 0.1381829021 0.2367086709 0.0047886053 2.3591160000 0.9907040000 0.2525710000 0.0000050000 1.0967260000 0.0072330000 129135820 0 1783910400 3.8917052746 3.9838759899 4.0051178932 1067 1311867754.2166349888 0.1192576364 0.1381651653 0.2367086709 0.0047882812 2.6804360000 1.0046580000 0.4372250000 0.1225640000 1.0969130000 0.0073020000 129138006 0 1785561088 3.8913621902 3.9830248356 4.0048098564 1068 1311867754.2522869110 0.1182431206 0.1381465117 0.2367086709 0.0047922989 2.4330200000 0.9997950000 0.3239310000 0.0000050000 1.0893160000 0.0072990000 129140256 0 1784819712 3.8912100792 3.9825136662 4.0049834251 1069 1311867754.2873370647 0.1140799299 0.1381239985 0.2367086709 0.0047975405 3.7977720000 1.0109380000 0.4390310000 0.1219050000 1.0921060000 1.1218970000 129142506 0 1784180736 3.8941419125 3.9832849503 4.0047984123 1070 1311867754.3188319206 0.1164740622 0.1381037649 0.2367086709 0.0047956177 2.3804000000 0.9888030000 0.2880390000 0.0000060000 1.0844760000 0.0072820000 129144692 0 1785942016 3.8905766010 3.9825823307 4.0053620338 1071 1311867754.3511719704 0.1156615168 0.1380828104 0.2367086709 0.0047974089 2.6544810000 0.9963440000 0.4315230000 0.1224750000 1.0841380000 0.0072440000 129146878 0 1785073664 3.8904426098 3.9825723171 4.0054841042 1072 1311867754.3868899345 0.1137015373 0.1380600667 0.2367086709 0.0047983635 2.3892940000 0.9726700000 0.3171300000 0.0000060000 1.0803820000 0.0072200000 129149096 0 1784565760 3.8912339211 3.9832179546 4.0051178932 1073 1311867754.4159760475 0.1133638695 0.1380370507 0.2367086709 0.0047962674 3.7656190000 1.0145080000 0.4352650000 0.1214630000 1.0746690000 1.1069840000 129151282 0 1783525376 3.8910331726 3.9831187725 4.0050964355 1074 1311867754.4545960426 0.1104591414 0.1380113729 0.2367086709 0.0048101334 2.5281600000 0.9856850000 0.4459510000 0.0000050000 1.0773330000 0.0072340000 129153532 0 1783296000 3.8929018974 3.9821164608 4.0054087639 1075 1311867754.4863700867 0.1087959707 0.1379841958 0.2367086709 0.0048172150 2.6356250000 0.9838810000 0.4425850000 0.1209900000 1.0690830000 0.0072980000 129155718 0 1784934400 3.8940911293 3.9823174477 4.0054874420 1076 1311867754.5164580345 0.1080564782 0.1379563819 0.2367086709 0.0048155712 2.5332270000 0.9866710000 0.4456410000 0.0000060000 1.0809060000 0.0072820000 129157872 0 1783775232 3.8943390846 3.9829142094 4.0057239532 1077 1311867754.5513699055 0.1073457226 0.1379279598 0.2367086709 0.0048150691 3.7355200000 1.0079230000 0.4321480000 0.1222810000 1.0654180000 1.0958450000 129160058 0 1783279616 3.8945684433 3.9832339287 4.0059990883 1078 1311867754.5835940838 0.1046146154 0.1378970569 0.2367086709 0.0048164260 2.5195130000 0.9919430000 0.4459500000 0.0000050000 1.0625390000 0.0072310000 129162276 0 1785016320 3.8968040943 3.9818513393 4.0056667328 1079 1311867754.6154909134 0.1048468053 0.1378664264 0.2367086709 0.0048155777 2.6238000000 0.9831030000 0.4378800000 0.1206240000 1.0621160000 0.0073540000 129164430 0 1784168448 3.8960821629 3.9821243286 4.0060620308 1080 1311867754.6510920525 0.1044245958 0.1378354617 0.2367086709 0.0048136305 2.3444220000 0.9739640000 0.2899150000 0.0000050000 1.0613690000 0.0072540000 129166648 0 1783406592 3.8960392475 3.9826040268 4.0062193871 1081 1311867754.6872758865 0.1026048884 0.1378028710 0.2367086709 0.0048143346 3.7285360000 0.9956790000 0.4468300000 0.1203730000 1.0591240000 1.0945210000 129168898 0 1785057280 3.8972561359 3.9815084934 4.0061335564 1082 1311867754.7162959576 0.1026395932 0.1377703726 0.2367086709 0.0048121720 2.2813020000 0.9875050000 0.2144070000 0.0000050000 1.0593650000 0.0072390000 129171020 0 1783914496 3.8967525959 3.9820940495 4.0063972473 1083 1311867754.7516000271 0.1015919819 0.1377369669 0.2367086709 0.0048114631 2.5786340000 0.9747740000 0.4008300000 0.1202560000 1.0634140000 0.0073000000 129173270 0 1783406592 3.8972992897 3.9836671352 4.0066881180 1084 1311867754.7865269184 0.1002243683 0.1377023612 0.2367086709 0.0048115583 2.4717840000 0.9707070000 0.4316110000 0.0000050000 1.0502870000 0.0072580000 129175488 0 1785053184 3.8981409073 3.9832320213 4.0067210197 1085 1311867754.8154470921 0.1009962633 0.1376685307 0.2367086709 0.0048105979 3.6088470000 0.9827630000 0.3715750000 0.1201410000 1.0505420000 1.0709800000 129177610 0 1784057856 3.8968567848 3.9812231064 4.0069241524 1086 1311867754.8510210514 0.1003791839 0.1376341943 0.2367086709 0.0048243091 2.4933620000 0.9831450000 0.4467900000 0.0000040000 1.0441090000 0.0072450000 129179860 0 1783549952 3.8966524601 3.9820144176 4.0073342323 1087 1311867754.8877389431 0.0976081565 0.1375973718 0.2367086709 0.0048239776 2.4499480000 0.9866480000 0.2880900000 0.1212000000 1.0348340000 0.0072540000 129182142 0 1785188352 3.8986175060 3.9817669392 4.0069823265 1088 1311867754.9201259613 0.0956088826 0.1375587794 0.2367086709 0.0048227913 2.4820080000 0.9981400000 0.4340590000 0.0000050000 1.0292900000 0.0072990000 129184328 0 1784049664 3.8998587132 3.9802675247 4.0068521500 1089 1311867754.9510319233 0.0951038823 0.1375197942 0.2367086709 0.0048221714 3.6000210000 0.9976360000 0.3970500000 0.1199940000 1.0253260000 1.0479570000 129186482 0 1783533568 3.8995487690 3.9805026054 4.0067939758 1090 1311867754.9837870598 0.0936707109 0.1374795657 0.2367086709 0.0048214006 2.2867170000 0.9920150000 0.2513700000 0.0000040000 1.0241320000 0.0072790000 129188700 0 1785180160 3.8997855186 3.9816558361 4.0073542595 1091 1311867755.0183880329 0.0928093120 0.1374386214 0.2367086709 0.0048231485 2.5672370000 0.9821200000 0.4370040000 0.1197260000 1.0081010000 0.0073610000 129190918 0 1784168448 3.9001135826 3.9797508717 4.0076498985 1092 1311867755.0540831089 0.0933797210 0.1373982744 0.2367086709 0.0048237028 2.4508510000 0.9907760000 0.4310280000 0.0000050000 1.0096680000 0.0072870000 129193168 0 1783263232 3.8991110325 3.9788086414 4.0082716942 1093 1311867755.0850980282 0.0939034596 0.1373584804 0.2367086709 0.0048237819 3.5612510000 0.9874730000 0.4150230000 0.1195700000 1.0032120000 1.0239360000 129195354 0 1785057280 3.8981435299 3.9791326523 4.0087432861 1094 1311867755.1156959534 0.0938526839 0.1373187128 0.2367086709 0.0048258037 2.4700940000 0.9938760000 0.4547780000 0.0000060000 1.0012210000 0.0073340000 129197476 0 1783934976 3.8976683617 3.9789383411 4.0089893341 1095 1311867755.1556220055 0.0927655548 0.1372780250 0.2367086709 0.0048241137 2.5764560000 0.9908200000 0.4482850000 0.1195670000 0.9984250000 0.0072840000 129199790 0 1783152640 3.8981294632 3.9787163734 4.0091567039 1096 1311867755.1847031116 0.0933294222 0.1372379259 0.2367086709 0.0048225023 2.4650040000 0.9931570000 0.4539080000 0.0000060000 0.9985390000 0.0073790000 129201976 0 1784803328 3.8970937729 3.9775340557 4.0094022751 1097 1311867755.2151238918 0.0917939097 0.1371965001 0.2367086709 0.0048203282 3.4668620000 1.0213810000 0.2950330000 0.1193090000 0.9984900000 1.0196150000 129204098 0 1783279616 3.8980758190 3.9792838097 4.0094218254 1098 1311867755.2512340546 0.0919170305 0.1371552620 0.2367086709 0.0048195314 2.4501030000 0.9899720000 0.4434570000 0.0000060000 0.9972660000 0.0073440000 129206348 0 1782120448 3.8974435329 3.9778704643 4.0097813606 1099 1311867755.2832889557 0.0914573967 0.1371136807 0.2367086709 0.0048197250 2.5739230000 0.9968630000 0.4387170000 0.1195070000 0.9994720000 0.0074220000 129208534 0 1783746560 3.8973741531 3.9769530296 4.0093903542 1100 1311867755.3192110062 0.0903735310 0.1370711897 0.2367086709 0.0048182056 2.4457430000 0.9861830000 0.4354730000 0.0000060000 1.0048910000 0.0072890000 129210784 0 1785532416 3.8980565071 3.9783778191 4.0091009140 1101 1311867755.3553090096 0.0913484618 0.1370296613 0.2367086709 0.0048160348 3.5374080000 1.0065280000 0.3691190000 0.1194030000 1.0023540000 1.0270900000 129213066 0 1784561664 3.8967688084 3.9765260220 4.0090198517 1102 1311867755.3900220394 0.0927929878 0.1369895191 0.2367086709 0.0048141415 2.4478900000 0.9842660000 0.4353510000 0.0000050000 1.0087700000 0.0073450000 129215252 0 1783283712 3.8949098587 3.9745378494 4.0087451935 1103 1311867755.4156589508 0.0923121050 0.1369490138 0.2367086709 0.0048148695 2.3831400000 0.9725050000 0.2481810000 0.1192810000 1.0239600000 0.0072250000 129217374 0 1784778752 3.8948309422 3.9770936966 4.0084347725 1104 1311867755.4549160004 0.0919833779 0.1369082840 0.2367086709 0.0048134488 2.3388530000 0.9732750000 0.3255760000 0.0000070000 1.0197740000 0.0072970000 129219656 0 1783517184 3.8945093155 3.9781606197 4.0086116791 1105 1311867755.4860870838 0.0921438560 0.1368677732 0.2367086709 0.0048123069 3.6077990000 0.9777050000 0.4355050000 0.1193450000 1.0249080000 1.0382120000 129221810 0 1782521856 3.8940100670 3.9753878117 4.0085010529 1106 1311867755.5161950588 0.0940284356 0.1368290396 0.2367086709 0.0048141916 2.4618550000 0.9842160000 0.4342810000 0.0000050000 1.0240580000 0.0073900000 129223932 0 1784000512 3.8918569088 3.9767704010 4.0090069771 1107 1311867755.5550999641 0.0923729464 0.1367888806 0.2367086709 0.0048120770 2.4256950000 0.9698340000 0.2927910000 0.1195900000 1.0243660000 0.0072930000 129226246 0 1785651200 3.8931424618 3.9779911041 4.0089006424 1108 1311867755.5854589939 0.0931583792 0.1367495029 0.2367086709 0.0048099658 2.3347890000 0.9596350000 0.3302450000 0.0000060000 1.0246270000 0.0072460000 129228432 0 1784680448 3.8921406269 3.9779038429 4.0088086128 1109 1311867755.6171119213 0.0920359343 0.1367091840 0.2367086709 0.0048082418 3.4350540000 0.9771560000 0.2548610000 0.1191120000 1.0258130000 1.0458910000 129230586 0 1783537664 3.8930246830 3.9782376289 4.0086421967 1110 1311867755.6542940140 0.0914792046 0.1366684363 0.2367086709 0.0048061488 2.4503610000 0.9713300000 0.4360240000 0.0000050000 1.0237490000 0.0072370000 129232868 0 1785016320 3.8934776783 3.9783220291 4.0086708069 1111 1311867755.6831719875 0.0930976942 0.1366292187 0.2367086709 0.0048046262 2.6043470000 0.9944590000 0.4440000000 0.1193690000 1.0263400000 0.0072450000 129234990 0 1784045568 3.8917093277 3.9766705036 4.0085091591 1112 1311867755.7182741165 0.0921050012 0.1365891790 0.2367086709 0.0048027778 2.2589840000 0.9657010000 0.2428020000 0.0000040000 1.0310060000 0.0072980000 129237240 0 1782902784 3.8922526836 3.9763963223 4.0078897476 1113 1311867755.7511448860 0.0927802101 0.1365498178 0.2367086709 0.0048023679 3.6088960000 0.9653150000 0.4251640000 0.1190060000 1.0339240000 1.0533570000 129239426 0 1784516608 3.8911848068 3.9769997597 4.0076012611 1114 1311867755.7863750458 0.0940579325 0.1365116743 0.2367086709 0.0048005736 2.4536220000 0.9677110000 0.4209550000 0.0000050000 1.0445670000 0.0071920000 129241644 0 1783267328 3.8896961212 3.9773647785 4.0077047348 1115 1311867755.8156878948 0.0903835446 0.1364703038 0.2367086709 0.0048028772 2.5821980000 0.9757100000 0.4275530000 0.1193370000 1.0399780000 0.0073520000 129243830 0 1782140928 3.8931772709 3.9760391712 4.0065793991 1116 1311867755.8554079533 0.0888377950 0.1364276223 0.2367086709 0.0048019054 2.3116150000 0.9576550000 0.2839060000 0.0000050000 1.0506380000 0.0072390000 129246080 0 1783619584 3.8943789005 3.9784996510 4.0065736771 1117 1311867755.8848359585 0.0900416151 0.1363860950 0.2367086709 0.0047999554 3.4741650000 0.9625220000 0.2798480000 0.1190440000 1.0400200000 1.0606670000 129248266 0 1785417728 3.8928942680 3.9783997536 4.0068316460 1118 1311867755.9156229496 0.0889517143 0.1363436671 0.2367086709 0.0048015028 2.3705660000 0.9782750000 0.3336450000 0.0000050000 1.0383870000 0.0072800000 129250452 0 1784299520 3.8938071728 3.9759054184 4.0063714981 1119 1311867755.9550359249 0.0884658396 0.1363008808 0.2367086709 0.0048016882 2.5752730000 0.9578020000 0.4383960000 0.1189940000 1.0404620000 0.0073030000 129252702 0 1782882304 3.8938646317 3.9780166149 4.0065445900 1120 1311867755.9855198860 0.0894652456 0.1362590633 0.2367086709 0.0048000055 2.4458750000 0.9675980000 0.4205510000 0.0000050000 1.0384670000 0.0072060000 129254856 0 1784508416 3.8927810192 3.9779937267 4.0068283081 1121 1311867756.0173881054 0.0895309597 0.1362173790 0.2367086709 0.0047982797 3.6296440000 0.9623640000 0.4410440000 0.1194430000 1.0347290000 1.0589430000 129257010 0 1783533568 3.8925848007 3.9770295620 4.0067749023 1122 1311867756.0554430485 0.0869145021 0.1361734370 0.2367086709 0.0047966936 2.4672360000 0.9665170000 0.4448240000 0.0000060000 1.0362780000 0.0072990000 129259260 0 1782394880 3.8949658871 3.9787700176 4.0066266060 1123 1311867756.0835959911 0.0879866630 0.1361305281 0.2367086709 0.0047952208 2.5664300000 0.9671850000 0.4242360000 0.1193270000 1.0363290000 0.0072850000 129261414 0 1783894016 3.8938283920 3.9781556129 4.0067529678 1124 1311867756.1196908951 0.0903702751 0.1360898161 0.2367086709 0.0047956137 2.3045140000 0.9666560000 0.2900500000 0.0000050000 1.0285060000 0.0072200000 129263664 0 1785524224 3.8917117119 3.9752888680 4.0069499016 1125 1311867756.1519339085 0.0877156630 0.1360468169 0.2367086709 0.0047945174 3.5464610000 0.9676920000 0.3561700000 0.1190710000 1.0386020000 1.0516510000 129265754 0 1784553472 3.8941133022 3.9772262573 4.0064911842 1126 1311867756.1836869717 0.0896059722 0.1360055728 0.2367086709 0.0047950559 2.2675930000 0.9687250000 0.2481490000 0.0000050000 1.0310860000 0.0072220000 129267876 0 1783799808 3.8922352791 3.9780571461 4.0071854591 1127 1311867756.2230648994 0.0901733041 0.1359649053 0.2367086709 0.0047995770 2.4566870000 0.9603020000 0.3298020000 0.1191430000 1.0280860000 0.0072530000 129270062 0 1785405440 3.8919510841 3.9757239819 4.0071697235 1128 1311867756.2552509308 0.0894575492 0.1359236753 0.2367086709 0.0048001127 2.2339690000 0.9722070000 0.2115560000 0.0000050000 1.0297820000 0.0072610000 129272248 0 1784434688 3.8926374912 3.9760525227 4.0072145462 1129 1311867756.2851591110 0.0894793123 0.1358825377 0.2367086709 0.0047987130 3.4282220000 0.9722560000 0.2443570000 0.1190370000 1.0338300000 1.0463470000 129274434 0 1783283712 3.8926906586 3.9777634144 4.0074496269 1130 1311867756.3200058937 0.0903351903 0.1358422303 0.2367086709 0.0047968611 2.2593900000 0.9688600000 0.2470680000 0.0000050000 1.0240150000 0.0072300000 129276652 0 1784889344 3.8920392990 3.9765167236 4.0076012611 1131 1311867756.3546419144 0.0889223963 0.1358007451 0.2367086709 0.0047957783 2.5788750000 0.9739490000 0.4406420000 0.1190930000 1.0248210000 0.0073070000 129278902 0 1783918592 3.8935675621 3.9762210846 4.0072994232 1132 1311867756.3843090534 0.0898955315 0.1357601928 0.2367086709 0.0047954027 2.2602760000 0.9612980000 0.2535070000 0.0000050000 1.0256780000 0.0072600000 129281024 0 1782374400 3.8925254345 3.9773101807 4.0077171326 1133 1311867756.4231688976 0.0894015059 0.1357192760 0.2367086709 0.0047938031 3.4827940000 0.9736050000 0.3156300000 0.1189340000 1.0223050000 1.0400830000 129283274 0 1784147968 3.8932061195 3.9772229195 4.0078072548 1134 1311867756.4510979652 0.0908097699 0.1356796733 0.2367086709 0.0047921347 2.4512610000 0.9680240000 0.4390840000 0.0000060000 1.0248040000 0.0072580000 129285364 0 1785778176 3.8919627666 3.9752960205 4.0079646111 1135 1311867756.4865350723 0.0900254771 0.1356394493 0.2367086709 0.0047963169 2.5653420000 0.9642300000 0.4428450000 0.1189050000 1.0187560000 0.0072980000 129287646 0 1784807424 3.8927426338 3.9767997265 4.0083537102 1136 1311867756.5264549255 0.0896971673 0.1355990072 0.2367086709 0.0047946769 2.4728890000 1.0060210000 0.4292470000 0.0000050000 1.0179330000 0.0073810000 129289928 0 1783681024 3.8932919502 3.9762251377 4.0083565712 1137 1311867756.5525779724 0.0903720632 0.1355592297 0.2367086709 0.0047931379 3.5812760000 0.9841380000 0.4274700000 0.1191330000 1.0097160000 1.0285280000 129292050 0 1785311232 3.8927929401 3.9756062031 4.0086169243 1138 1311867756.5897810459 0.0889312923 0.1355182561 0.2367086709 0.0047915786 2.2332460000 0.9890480000 0.2123300000 0.0000050000 1.0112860000 0.0073590000 129294332 0 1784164352 3.8942799568 3.9762818813 4.0084695816 1139 1311867756.6202929020 0.0910047069 0.1354791749 0.2367086709 0.0047902370 2.5558630000 0.9787730000 0.4377030000 0.1190330000 1.0006440000 0.0073940000 129296454 0 1783934976 3.8925313950 3.9744162560 4.0090346336 1140 1311867756.6518390179 0.0912206843 0.1354403517 0.2367086709 0.0047881778 2.1880170000 0.9844670000 0.1778500000 0.0000050000 1.0060710000 0.0073150000 129298640 0 1785696256 3.8924345970 3.9737145901 4.0093832016 1141 1311867756.6839349270 0.0898023471 0.1354003534 0.2367086709 0.0047872453 3.3822070000 0.9833010000 0.2507460000 0.1192250000 0.9991480000 1.0165410000 129300794 0 1784926208 3.8935811520 3.9746162891 4.0092687607 1142 1311867756.7217059135 0.0901969075 0.1353607707 0.2367086709 0.0047877995 2.4355950000 0.9912570000 0.4298630000 0.0000050000 0.9946770000 0.0073540000 129303044 0 1784688640 3.8932023048 3.9739313126 4.0096344948 1143 1311867756.7516939640 0.0905568227 0.1353215721 0.2367086709 0.0047860187 2.5654530000 0.9846640000 0.4486710000 0.1191590000 0.9923930000 0.0072840000 129305198 0 1783762944 3.8927764893 3.9734907150 4.0097575188 1144 1311867756.7872660160 0.0914137512 0.1352831912 0.2367086709 0.0047842955 2.4150170000 0.9884040000 0.4151240000 0.0000060000 0.9917240000 0.0072990000 129307448 0 1783656448 3.8919398785 3.9735832214 4.0100288391 1145 1311867756.8227219582 0.0901974663 0.1352438150 0.2367086709 0.0047823698 3.5888440000 1.0158510000 0.4388400000 0.1192670000 0.9897960000 1.0126750000 129309698 0 1785434112 3.8930773735 3.9734823704 4.0100669861 1146 1311867756.8542120457 0.0907090008 0.1352049539 0.2367086709 0.0047888122 2.2225320000 0.9901070000 0.2170980000 0.0000070000 0.9938760000 0.0075390000 129311852 0 1784561664 3.8926165104 3.9723877907 4.0103139877 1147 1311867756.8841960430 0.0919619128 0.1351672529 0.2367086709 0.0048001640 2.3714420000 0.9846550000 0.2588620000 0.1190700000 0.9889440000 0.0073400000 129314038 0 1784434688 3.8911716938 3.9731941223 4.0109300613 1148 1311867756.9223539829 0.0913057253 0.1351290460 0.2367086709 0.0047990491 2.2486720000 0.9922900000 0.2497090000 0.0000070000 0.9860690000 0.0073640000 129316288 0 1783508992 3.8916478157 3.9726657867 4.0109424591 1149 1311867756.9552440643 0.0899139866 0.1350896944 0.2367086709 0.0047986603 3.4246150000 0.9999340000 0.2997350000 0.1190530000 0.9849650000 1.0083720000 129318506 0 1783418880 3.8930230141 3.9713585377 4.0104331970 1150 1311867756.9841780663 0.0905609503 0.1350509737 0.2367086709 0.0047981643 2.2518510000 0.9842910000 0.2573180000 0.0000060000 0.9901400000 0.0074290000 129320628 0 1785180160 3.8921682835 3.9726567268 4.0108332634 1151 1311867757.0282740593 0.0896358117 0.1350115166 0.2367086709 0.0048016565 2.5532610000 0.9880910000 0.4373690000 0.1190170000 0.9881370000 0.0073270000 129323006 0 1784274944 3.8929300308 3.9711320400 4.0107707977 1152 1311867757.0552940369 0.0893514082 0.1349718811 0.2367086709 0.0048001407 2.4361770000 0.9976780000 0.4350170000 0.0000060000 0.9835140000 0.0073700000 129325128 0 1783812096 3.8933629990 3.9698426723 4.0105299950 1153 1311867757.0858569145 0.0885345712 0.1349316059 0.2367086709 0.0047996246 3.3758800000 0.9895070000 0.2562660000 0.1191140000 0.9922360000 1.0063850000 129327282 0 1785425920 3.8938667774 3.9723176956 4.0106940269 1154 1311867757.1283040047 0.0880844742 0.1348910104 0.2367086709 0.0048094639 2.3706990000 0.9833940000 0.3673650000 0.0000060000 0.9992660000 0.0073130000 129329596 0 1784307712 3.8946824074 3.9691944122 4.0105428696 1155 1311867757.1522068977 0.0861994028 0.1348488532 0.2367086709 0.0048086385 2.5421030000 1.0009810000 0.4069250000 0.1190540000 0.9951160000 0.0073280000 129331622 0 1783762944 3.8966071606 3.9683120251 4.0096812248 1156 1311867757.1851921082 0.0903128460 0.1348103272 0.2367086709 0.0048122124 2.3307050000 0.9806680000 0.3239490000 0.0000060000 1.0064020000 0.0072630000 129333840 0 1785561088 3.8924310207 3.9702479839 4.0105686188 1157 1311867757.2192370892 0.0890049860 0.1347707375 0.2367086709 0.0048111846 3.4439550000 0.9806370000 0.2851750000 0.1190640000 1.0172620000 1.0284710000 129336090 0 1784651776 3.8941214085 3.9686739445 4.0098562241 1158 1311867757.2523930073 0.0877162740 0.1347301032 0.2367086709 0.0048319203 2.3178530000 0.9862560000 0.2879850000 0.0000070000 1.0238220000 0.0072860000 129338276 0 1784438784 3.8956067562 3.9682273865 4.0090146065 1159 1311867757.2835690975 0.0879327580 0.1346897259 0.2367086709 0.0048353008 2.5715050000 0.9710790000 0.4278060000 0.1188730000 1.0331250000 0.0072700000 129340430 0 1783672832 3.8952283859 3.9705553055 4.0088019371 1160 1311867757.3233768940 0.0903718770 0.1346515208 0.2367086709 0.0048449059 2.3358800000 0.9587660000 0.3191930000 0.0000060000 1.0380860000 0.0071960000 129342744 0 1783402496 3.8935089111 3.9701023102 4.0088753700 1161 1311867757.3555359840 0.0896562114 0.1346127652 0.2367086709 0.0048431722 3.5744020000 0.9783080000 0.3547150000 0.1193860000 1.0449670000 1.0645030000 129344962 0 1785180160 3.8942079544 3.9702465534 4.0086207390 1162 1311867757.3833439350 0.0893406644 0.1345738047 0.2367086709 0.0048427750 2.2356350000 0.9506030000 0.2094490000 0.0000060000 1.0549470000 0.0072170000 129347052 0 1784016896 3.8945770264 3.9714484215 4.0089454651 1163 1311867757.4264349937 0.0881621614 0.1345338979 0.2367086709 0.0048476785 1.9882860000 0.5293980000 0.2739530000 0.1151870000 1.0514030000 0.0057370000 129349366 0 1783529472 3.8952662945 3.9726047516 4.0066776276 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 12:45:07 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libkfusion-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520030 0.0582520030 0.0582520030 nan 2.4455840000 0.9180360000 0.0550560000 0.1180430000 0.0000080000 1.3338310000 114019895 0 1771241472 4.0000000000 4.0000000000 4.0000000000 2 1311867170.4941389561 0.0599970818 0.0591245424 0.0599970818 0.0035990404 1.1499810000 0.9786060000 0.0417990000 0.1181400000 0.0000020000 0.0069650000 126599252 0 1770160128 4.0000000000 4.0000000000 4.0000000000 3 1311867170.5264289379 0.0615839623 0.0599443490 0.0615839623 0.0081929966 1.0965890000 0.9248370000 0.0422980000 0.1181430000 0.0000020000 0.0070310000 126601794 0 1771765760 4.0000000000 4.0000000000 4.0000000000 4 1311867170.5623490810 0.0628964603 0.0606823768 0.0628964603 0.0105671055 2.3778700000 0.9256300000 0.0422150000 0.1184490000 1.2801940000 0.0070990000 126604372 0 1780908032 4.0000000000 4.0000000000 4.0000000000 5 1311867170.5942170620 0.0609258004 0.0607310615 0.0628964603 0.0111249439 3.8348060000 0.9316270000 0.2379590000 0.1182040000 1.2620660000 1.2806180000 126606846 0 1782542336 4.0031242371 3.9974739552 3.9970715046 6 1311867170.6260869503 0.0606062971 0.0607102675 0.0628964603 0.0110248414 2.6353080000 0.9438330000 0.4147810000 0.0000040000 1.2652870000 0.0070770000 126609688 0 1784217600 4.0016174316 3.9956717491 3.9953827858 7 1311867170.6621398926 0.0602243580 0.0606408518 0.0628964603 0.0105573441 2.5385990000 0.9278970000 0.2391790000 0.1184520000 1.2407320000 0.0070910000 126611970 0 1783066624 4.0018320084 3.9940991402 3.9936189651 8 1311867170.6942050457 0.0600399859 0.0605657436 0.0628964603 0.0100564805 2.6427530000 0.9655810000 0.4207740000 0.0000050000 1.2447970000 0.0071170000 126614124 0 1782325248 4.0011572838 3.9931411743 3.9919660091 9 1311867170.7263879776 0.0608425252 0.0605964971 0.0628964603 0.0100315659 3.9665910000 0.9290950000 0.4171900000 0.1186060000 1.2414500000 1.2558310000 126616950 0 1783963648 4.0015869141 3.9936790466 3.9908607006 10 1311867170.7620189190 0.0603579953 0.0605726469 0.0628964603 0.0098614389 2.5977840000 0.9291920000 0.4132430000 0.0000030000 1.2437920000 0.0072760000 126620544 0 1785708544 3.9995050430 3.9909121990 3.9892861843 11 1311867170.7941920757 0.0607265905 0.0605866418 0.0628964603 0.0096796996 2.6817700000 0.9330580000 0.3808830000 0.1184130000 1.2368550000 0.0071000000 126622666 0 1784610816 4.0003924370 3.9889500141 3.9876811504 12 1311867170.8262820244 0.0612731390 0.0606438499 0.0628964603 0.0096061179 2.6137360000 0.9563900000 0.4140740000 0.0000020000 1.2316130000 0.0070810000 126624884 0 1783738368 4.0014548302 3.9856190681 3.9859545231 13 1311867170.8622210026 0.0614284761 0.0607042058 0.0628964603 0.0096859467 3.8424840000 0.9165670000 0.3417230000 0.1185320000 1.2183270000 1.2429260000 126627134 0 1785462784 4.0042290688 3.9817683697 3.9834074974 14 1311867170.8943779469 0.0618332960 0.0607848551 0.0628964603 0.0094039292 2.4156020000 0.9089010000 0.2687610000 0.0000030000 1.2254220000 0.0070560000 126629288 0 1784360960 4.0020575523 3.9801092148 3.9812393188 15 1311867170.9263520241 0.0620482937 0.0608690843 0.0628964603 0.0093862685 2.4761490000 0.8995100000 0.2317900000 0.1185710000 1.2146950000 0.0069780000 126631506 0 1783595008 4.0028309822 3.9772646427 3.9783926010 16 1311867170.9621469975 0.0615710244 0.0609129556 0.0628964603 0.0091725699 2.4112100000 0.8937740000 0.2692360000 0.0000030000 1.2367780000 0.0069580000 126633756 0 1785327616 4.0006346703 3.9752943516 3.9754130840 17 1311867170.9942629337 0.0615527928 0.0609505930 0.0628964603 0.0090176158 3.7969810000 0.8895930000 0.2646450000 0.1190540000 1.2460830000 1.2721730000 126637190 0 1784479744 3.9983484745 3.9747169018 3.9725239277 18 1311867171.0262739658 0.0615949519 0.0609863908 0.0628964603 0.0087661695 2.5487800000 0.8848690000 0.3969550000 0.0000040000 1.2554040000 0.0069030000 126642032 0 1783607296 3.9982666969 3.9730911255 3.9697606564 19 1311867171.0623519421 0.0607731752 0.0609751689 0.0628964603 0.0091366908 2.5651400000 0.8731100000 0.2945550000 0.1190670000 1.2670960000 0.0068890000 126644282 0 1785237504 3.9973049164 3.9699714184 3.9667077065 20 1311867171.0942349434 0.0605317093 0.0609529959 0.0628964603 0.0090687818 2.5704950000 0.8813250000 0.3954560000 0.0000030000 1.2814050000 0.0068890000 126646436 0 1784242176 3.9973285198 3.9690551758 3.9645607471 21 1311867171.1262509823 0.0605473183 0.0609336779 0.0628964603 0.0089234842 3.9461950000 0.8598540000 0.3533950000 0.1190620000 1.2853950000 1.3239010000 126648654 0 1783476224 3.9978284836 3.9692461491 3.9624114037 22 1311867171.1622469425 0.0602623783 0.0609031643 0.0628964603 0.0088200311 2.4288930000 0.8608590000 0.2594710000 0.0000030000 1.2972980000 0.0068300000 126650904 0 1785085952 3.9997384548 3.9667115211 3.9609074593 23 1311867171.1942689419 0.0591815673 0.0608283123 0.0628964603 0.0090485924 2.6852380000 0.8561120000 0.3904050000 0.1188430000 1.3076350000 0.0068210000 126653058 0 1783951360 4.0015416145 3.9671595097 3.9596407413 24 1311867171.2262530327 0.0610567480 0.0608378304 0.0628964603 0.0090296789 2.5473520000 0.8422880000 0.3905670000 0.0000040000 1.3029720000 0.0069190000 126655276 0 1783078912 4.0051937103 3.9670538902 3.9591417313 25 1311867171.2622439861 0.0604284592 0.0608214556 0.0628964603 0.0090261675 3.9990860000 0.8727040000 0.3651030000 0.1188090000 1.3009030000 1.3370490000 126657526 0 1784864768 4.0063095093 3.9663772583 3.9580330849 26 1311867171.2943410873 0.0607820675 0.0608199406 0.0628964603 0.0090299742 2.4360010000 0.8609200000 0.2597400000 0.0000030000 1.3029820000 0.0068050000 126659648 0 1783721984 4.0050621033 3.9689929485 3.9576427937 27 1311867171.3263869286 0.0610857643 0.0608297860 0.0628964603 0.0092641262 2.5581180000 0.8779490000 0.2617200000 0.1190240000 1.2878570000 0.0069400000 126661866 0 1783222272 4.0014643669 3.9706966877 3.9562244415 28 1311867171.3622460365 0.0606488399 0.0608233236 0.0628964603 0.0091314672 2.4711510000 0.8776700000 0.2986510000 0.0000040000 1.2833680000 0.0069480000 126664116 0 1784836096 3.9983370304 3.9719791412 3.9549152851 29 1311867171.3941431046 0.0616900735 0.0608532115 0.0628964603 0.0093289033 3.8212530000 0.9142030000 0.2302920000 0.1195770000 1.2616530000 1.2901180000 126666270 0 1784111104 3.9963955879 3.9747583866 3.9538307190 30 1311867171.4262878895 0.0624653660 0.0609069500 0.0628964603 0.0092852491 2.4198850000 0.8885260000 0.2656230000 0.0000040000 1.2541170000 0.0069110000 126668488 0 1783566336 3.9952642918 3.9750247002 3.9522948265 31 1311867171.4622440338 0.0615501553 0.0609276986 0.0628964603 0.0092222066 2.4950850000 0.8771050000 0.2343880000 0.1193800000 1.2527120000 0.0069880000 126670738 0 1785217024 3.9949514866 3.9722206593 3.9500756264 32 1311867171.4944040775 0.0617272779 0.0609526854 0.0628964603 0.0091409890 2.3432770000 0.8767810000 0.1979880000 0.0000040000 1.2560440000 0.0069530000 126672892 0 1784094720 3.9956698418 3.9733400345 3.9481360912 33 1311867171.5261778831 0.0612954050 0.0609630709 0.0628964603 0.0089998210 3.9456780000 0.8664300000 0.4056330000 0.1195720000 1.2581690000 1.2911710000 126677670 0 1783582720 3.9946606159 3.9734146595 3.9461271763 34 1311867171.5622971058 0.0606514551 0.0609539057 0.0628964603 0.0088653794 2.3526270000 0.8802410000 0.1965380000 0.0000040000 1.2644090000 0.0069460000 126685168 0 1785360384 3.9948449135 3.9731514454 3.9447569847 35 1311867171.5942931175 0.0608577579 0.0609511586 0.0628964603 0.0088003240 2.6732740000 0.8753170000 0.3875040000 0.1197890000 1.2782690000 0.0069260000 126687322 0 1784475648 3.9960885048 3.9744899273 3.9438252449 36 1311867171.6263399124 0.0606757924 0.0609435096 0.0628964603 0.0087035684 2.4566980000 0.9076380000 0.2689960000 0.0000040000 1.2683250000 0.0068920000 126689540 0 1783988224 3.9952523708 3.9733195305 3.9432413578 37 1311867171.6622560024 0.0606149398 0.0609346293 0.0628964603 0.0086029238 3.8442670000 0.8790220000 0.2661300000 0.1197130000 1.2738710000 1.3001040000 126691790 0 1783226368 3.9915852547 3.9727795124 3.9424724579 38 1311867171.6943440437 0.0612207577 0.0609421590 0.0628964603 0.0087803085 2.4271910000 0.8756860000 0.2664510000 0.0000040000 1.2733000000 0.0069910000 126693944 0 1782927360 3.9924182892 3.9735183716 3.9422662258 39 1311867171.7262439728 0.0611905158 0.0609485271 0.0628964603 0.0086917538 2.5937290000 0.8788910000 0.3051850000 0.1196750000 1.2785760000 0.0068920000 126696162 0 1784709120 3.9923064709 3.9728801250 3.9418802261 40 1311867171.7621190548 0.0614578761 0.0609612608 0.0628964603 0.0086043844 2.4591220000 0.9039310000 0.2624810000 0.0000040000 1.2803450000 0.0068820000 126698412 0 1783836672 3.9938220978 3.9712495804 3.9414992332 41 1311867171.7941710949 0.0610175952 0.0609626348 0.0628964603 0.0085982729 4.0071530000 0.8741900000 0.3967900000 0.1196720000 1.2891050000 1.3226620000 126700566 0 1783476224 3.9932203293 3.9692792892 3.9404668808 42 1311867171.8262550831 0.0614137873 0.0609733766 0.0628964603 0.0085180643 2.4158230000 0.8462850000 0.2580250000 0.0000040000 1.3000950000 0.0068690000 126702784 0 1785090048 3.9929487705 3.9690303802 3.9393370152 43 1311867171.8623590469 0.0609408580 0.0609726203 0.0628964603 0.0084217272 2.5340940000 0.8457050000 0.2594750000 0.1196880000 1.2968890000 0.0068570000 126705034 0 1784348672 3.9888932705 3.9687395096 3.9379785061 44 1311867171.8944430351 0.0605924912 0.0609639810 0.0628964603 0.0085313518 2.4639330000 0.8536030000 0.2918010000 0.0000040000 1.3068960000 0.0068350000 126707220 0 1783857152 3.9859056473 3.9683127403 3.9371607304 45 1311867171.9262220860 0.0615227968 0.0609763992 0.0628964603 0.0084662163 3.8283530000 0.8473330000 0.2253020000 0.1196660000 1.2970150000 1.3344480000 126709406 0 1785618432 3.9849748611 3.9696776867 3.9369156361 46 1311867171.9624669552 0.0616690032 0.0609914558 0.0628964603 0.0084073715 2.5527110000 0.8561400000 0.3889740000 0.0000040000 1.2951800000 0.0068070000 126711656 0 1784729600 3.9829330444 3.9694101810 3.9368805885 47 1311867171.9946711063 0.0620148890 0.0610132309 0.0628964603 0.0084678989 2.5539450000 0.8518540000 0.2900140000 0.1195810000 1.2808130000 0.0068460000 126713842 0 1784238080 3.9826724529 3.9692554474 3.9370698929 48 1311867172.0262680054 0.0627077743 0.0610485339 0.0628964603 0.0085274776 2.4380090000 0.8595350000 0.2915940000 0.0000040000 1.2744600000 0.0068750000 126716028 0 1783332864 3.9832532406 3.9691319466 3.9375188351 49 1311867172.0622880459 0.0630894452 0.0610901852 0.0630894452 0.0084686149 3.9629060000 0.8788260000 0.3901520000 0.1196890000 1.2679810000 1.3014580000 126718278 0 1783103488 3.9815793037 3.9699413776 3.9382522106 50 1311867172.0941960812 0.0632714927 0.0611338113 0.0632714927 0.0084497607 2.4269370000 0.8619760000 0.2930110000 0.0000040000 1.2604790000 0.0068910000 126720464 0 1784975360 3.9807560444 3.9696650505 3.9388027191 51 1311867172.1263689995 0.0637496114 0.0611851015 0.0637496114 0.0084528905 2.5470130000 0.8689940000 0.2986230000 0.1198900000 1.2469560000 0.0070150000 126722650 0 1783844864 3.9779634476 3.9700398445 3.9398198128 52 1311867172.1623349190 0.0626469329 0.0612132137 0.0637496114 0.0084112824 2.5235780000 0.8696120000 0.3925100000 0.0000040000 1.2496740000 0.0069690000 126724900 0 1782804480 3.9731307030 3.9699614048 3.9402139187 53 1311867172.1944270134 0.0616478957 0.0612214152 0.0637496114 0.0083605743 3.9319030000 0.8978320000 0.3990640000 0.1193180000 1.2379560000 1.2730420000 126727086 0 1784619008 3.9676752090 3.9710168839 3.9405872822 54 1311867172.2264409065 0.0615772717 0.0612280051 0.0637496114 0.0085131634 2.5257770000 0.8708900000 0.3946450000 0.0000050000 1.2478040000 0.0069490000 126729272 0 1783730176 3.9636077881 3.9709095955 3.9409742355 55 1311867172.2622280121 0.0611668937 0.0612268940 0.0637496114 0.0084447297 2.5482410000 0.8672470000 0.3272220000 0.1196370000 1.2223740000 0.0069920000 126731522 0 1783222272 3.9610104561 3.9717431068 3.9413545132 56 1311867172.2944829464 0.0612286180 0.0612269248 0.0637496114 0.0083845751 2.5171530000 0.8724540000 0.3941740000 0.0000040000 1.2389490000 0.0069090000 126733708 0 1785094144 3.9579191208 3.9725930691 3.9417684078 57 1311867172.3263380527 0.0607894175 0.0612192492 0.0637496114 0.0083564217 3.8974850000 0.9082130000 0.3903100000 0.1195520000 1.2197800000 1.2539710000 126735894 0 1783971840 3.9548065662 3.9724235535 3.9422311783 58 1311867172.3624010086 0.0610189959 0.0612157966 0.0637496114 0.0083050232 2.4921660000 0.8870120000 0.3646160000 0.0000040000 1.2286350000 0.0069780000 126738144 0 1783099392 3.9513802528 3.9734568596 3.9424188137 59 1311867172.3942890167 0.0598677658 0.0611929486 0.0637496114 0.0082470796 2.6269450000 0.8772350000 0.3974450000 0.1193420000 1.2211730000 0.0069760000 126740330 0 1784860672 3.9468848705 3.9733138084 3.9423272610 60 1311867172.4265220165 0.0597072542 0.0611681870 0.0637496114 0.0082933846 2.5262120000 0.8824520000 0.3980700000 0.0000040000 1.2330220000 0.0069910000 126742516 0 1783570432 3.9419817924 3.9735395908 3.9418301582 61 1311867172.4623498917 0.0591784380 0.0611355682 0.0637496114 0.0082666658 3.8857880000 0.8850890000 0.4008550000 0.1193900000 1.2173810000 1.2582150000 126744766 0 1783091200 3.9387464523 3.9727680683 3.9413881302 62 1311867172.4952669144 0.0596388690 0.0611114279 0.0637496114 0.0083043612 2.3153460000 0.8829340000 0.1964430000 0.0000040000 1.2242350000 0.0069420000 126746920 0 1784836096 3.9377090931 3.9732990265 3.9412698746 63 1311867172.5263059139 0.0592816360 0.0610823836 0.0637496114 0.0082516104 2.5407030000 0.8830670000 0.3022880000 0.1197340000 1.2224730000 0.0071490000 126749106 0 1783713792 3.9352130890 3.9716930389 3.9406447411 64 1311867172.5624930859 0.0588607229 0.0610476701 0.0637496114 0.0082020423 2.3864290000 0.8910970000 0.2663350000 0.0000040000 1.2171440000 0.0069880000 126751356 0 1782808576 3.9307608604 3.9709055424 3.9400739670 65 1311867172.5945439339 0.0597370453 0.0610275067 0.0637496114 0.0082110238 3.8806350000 0.8731680000 0.4038270000 0.1197060000 1.2248130000 1.2543260000 126758630 0 1784602624 3.9337491989 3.9710721970 3.9393627644 66 1311867172.6263699532 0.0594324842 0.0610033397 0.0637496114 0.0081873825 2.5229320000 0.8874230000 0.3997100000 0.0000040000 1.2231500000 0.0070240000 126771344 0 1783844864 3.9305911064 3.9711110592 3.9385814667 67 1311867172.6624419689 0.0592603050 0.0609773242 0.0637496114 0.0081291652 2.4827590000 0.8953420000 0.2293200000 0.1198020000 1.2264610000 0.0069570000 126773594 0 1782935552 3.9276862144 3.9713079929 3.9379968643 68 1311867172.6945450306 0.0591153800 0.0609499427 0.0637496114 0.0081954100 2.4635050000 0.9187650000 0.2989110000 0.0000040000 1.2340710000 0.0070250000 126775780 0 1784729600 3.9259471893 3.9711263180 3.9375538826 69 1311867172.7263929844 0.0594672821 0.0609284549 0.0637496114 0.0081683087 3.8950840000 0.8939270000 0.4015630000 0.1200940000 1.2199670000 1.2537000000 126777966 0 1783590912 3.9235196114 3.9711935520 3.9371969700 70 1311867172.7623739243 0.0597234517 0.0609112405 0.0637496114 0.0081248930 2.5368610000 0.8914880000 0.4091890000 0.0000040000 1.2243130000 0.0069880000 126780216 0 1782849536 3.9206523895 3.9725153446 3.9369499683 71 1311867172.7944509983 0.0589992851 0.0608843116 0.0637496114 0.0080728478 2.4795890000 0.8979700000 0.2341710000 0.1197950000 1.2157920000 0.0070330000 126782370 0 1784459264 3.9160811901 3.9716703892 3.9364151955 72 1311867172.8263089657 0.0594655126 0.0608646060 0.0637496114 0.0080360017 2.5876410000 0.9293620000 0.4174490000 0.0000040000 1.2280340000 0.0071420000 126784588 0 1783205888 3.9133558273 3.9718277454 3.9355115891 73 1311867172.8632309437 0.0593487546 0.0608438410 0.0637496114 0.0079998922 3.8809110000 0.9024950000 0.4127260000 0.1200830000 1.2011940000 1.2394060000 126786870 0 1782456320 3.9105503559 3.9712541103 3.9347085953 74 1311867172.8944649696 0.0586554557 0.0608142682 0.0637496114 0.0079459274 2.3939190000 0.8980920000 0.2768230000 0.0000040000 1.2070200000 0.0071240000 126788992 0 1784213504 3.9073219299 3.9710118771 3.9340429306 75 1311867172.9263219833 0.0583075285 0.0607808450 0.0637496114 0.0078932287 2.5863400000 0.9006980000 0.3476560000 0.1199010000 1.2053580000 0.0070390000 126791210 0 1783083008 3.9043202400 3.9701919556 3.9334456921 76 1311867172.9623310566 0.0581156686 0.0607457769 0.0637496114 0.0078418372 2.3484990000 0.9260970000 0.2034200000 0.0000040000 1.2069220000 0.0071240000 126793460 0 1782575104 3.9027221203 3.9698839188 3.9327640533 77 1311867172.9945271015 0.0584858507 0.0607164272 0.0637496114 0.0078181118 3.7458080000 0.8934890000 0.2759930000 0.1197890000 1.2096210000 1.2420420000 126795614 0 1784205312 3.9040701389 3.9697387218 3.9322407246 78 1311867173.0262629986 0.0575245768 0.0606755060 0.0637496114 0.0077804391 2.4143940000 0.8881890000 0.3068850000 0.0000050000 1.2066690000 0.0069880000 126797800 0 1783230464 3.8992884159 3.9692807198 3.9320504665 79 1311867173.0624630451 0.0575915463 0.0606364686 0.0637496114 0.0077350948 2.6420760000 0.8938610000 0.4150240000 0.1200080000 1.2011280000 0.0070900000 126800050 0 1782337536 3.8990850449 3.9687831402 3.9317266941 80 1311867173.0945179462 0.0580323823 0.0606039175 0.0637496114 0.0077171538 2.3958250000 0.9123980000 0.2702290000 0.0000050000 1.2014030000 0.0069880000 126802236 0 1784078336 3.8985679150 3.9687318802 3.9317743778 81 1311867173.1267819405 0.0578094795 0.0605694182 0.0637496114 0.0076891803 3.8666870000 0.8981020000 0.4197510000 0.1199830000 1.1949060000 1.2291440000 126804454 0 1785724928 3.8968219757 3.9687676430 3.9315352440 82 1311867173.1622309685 0.0582322627 0.0605409164 0.0637496114 0.0076768672 2.4235210000 0.9016740000 0.3034880000 0.0000050000 1.2054970000 0.0070000000 126806704 0 1784877056 3.8969404697 3.9697890282 3.9316227436 83 1311867173.1943008900 0.0586197004 0.0605177692 0.0637496114 0.0076308772 2.6197550000 0.8969080000 0.4005850000 0.1200410000 1.1901540000 0.0070830000 126808858 0 1784098816 3.8961894512 3.9703309536 3.9317052364 84 1311867173.2264449596 0.0576208718 0.0604832823 0.0637496114 0.0075910870 2.4469230000 0.9305320000 0.3040520000 0.0000040000 1.2004310000 0.0070870000 126811044 0 1785745408 3.8911306858 3.9698157310 3.9317469597 85 1311867173.2622020245 0.0589494854 0.0604652376 0.0637496114 0.0075505420 3.8490060000 0.9089300000 0.4079900000 0.1200350000 1.1846430000 1.2215270000 126813294 0 1784741888 3.8933265209 3.9705512524 3.9319810867 86 1311867173.2942678928 0.0590117015 0.0604483360 0.0637496114 0.0075067712 2.5215810000 0.9085820000 0.4099440000 0.0000050000 1.1908850000 0.0071680000 126815448 0 1783853056 3.8910365105 3.9703803062 3.9320042133 87 1311867173.3262879848 0.0586119592 0.0604272283 0.0637496114 0.0075116378 2.6289940000 0.9129520000 0.4087990000 0.1203620000 1.1748880000 0.0070870000 126817634 0 1785491456 3.8879289627 3.9690902233 3.9320244789 88 1311867173.3623280525 0.0586561747 0.0604071027 0.0637496114 0.0074692500 2.3596710000 0.9282060000 0.2422140000 0.0000050000 1.1761660000 0.0070750000 126819916 0 1784348672 3.8858942986 3.9691052437 3.9318885803 89 1311867173.3942871094 0.0581369177 0.0603815950 0.0637496114 0.0074363104 3.8408130000 0.9122520000 0.4214010000 0.1212820000 1.1699020000 1.2108740000 126822070 0 1783820288 3.8823382854 3.9692533016 3.9317722321 90 1311867173.4262790680 0.0578197874 0.0603531304 0.0637496114 0.0074177299 2.3432070000 0.9149700000 0.2443720000 0.0000050000 1.1710440000 0.0071170000 126824256 0 1783439360 3.8798844814 3.9691269398 3.9314949512 91 1311867173.4622900486 0.0572123192 0.0603186160 0.0637496114 0.0074043676 2.6426160000 0.9132970000 0.4198960000 0.1203320000 1.1768790000 0.0071820000 126826506 0 1783201792 3.8769445419 3.9686417580 3.9310617447 92 1311867173.4943389893 0.0579658113 0.0602930421 0.0637496114 0.0074626450 2.5343430000 0.9261470000 0.4206670000 0.0000050000 1.1755380000 0.0071050000 126828692 0 1784963072 3.8759386539 3.9682211876 3.9305732250 93 1311867173.5263900757 0.0576516502 0.0602646400 0.0637496114 0.0074251564 3.7106740000 0.9037900000 0.3130090000 0.1199430000 1.1692400000 1.1988640000 126830910 0 1784238080 3.8735136986 3.9677772522 3.9301335812 94 1311867173.5624370575 0.0574380420 0.0602345698 0.0637496114 0.0074049698 2.5068310000 0.9080840000 0.4216960000 0.0000040000 1.1649080000 0.0071070000 126833160 0 1783984128 3.8715929985 3.9680111408 3.9299697876 95 1311867173.5943109989 0.0576159619 0.0602070055 0.0637496114 0.0073902473 2.5183820000 0.9167200000 0.3045500000 0.1203420000 1.1638490000 0.0071540000 126835314 0 1783222272 3.8695008755 3.9681713581 3.9296848774 96 1311867173.6263959408 0.0565308407 0.0601687121 0.0637496114 0.0073630738 2.4040730000 0.9463700000 0.2810310000 0.0000050000 1.1644740000 0.0071490000 126837500 0 1783222272 3.8652555943 3.9674794674 3.9291381836 97 1311867173.6623299122 0.0573516712 0.0601396705 0.0637496114 0.0073304206 3.8327960000 0.9204690000 0.4154490000 0.1200220000 1.1673430000 1.2044230000 126839750 0 1784840192 3.8656215668 3.9680938721 3.9287607670 98 1311867173.6943540573 0.0579001978 0.0601168187 0.0637496114 0.0072961632 2.2840050000 0.9012310000 0.1958860000 0.0000050000 1.1738460000 0.0070950000 126841936 0 1784115200 3.8650488853 3.9680771828 3.9283525944 99 1311867173.7267971039 0.0568769760 0.0600840930 0.0637496114 0.0072970149 2.4302690000 0.8985280000 0.2357640000 0.1198680000 1.1639400000 0.0071050000 126844154 0 1783992320 3.8597199917 3.9674088955 3.9274072647 100 1311867173.7623970509 0.0573954992 0.0600572071 0.0637496114 0.0072733894 2.4943470000 0.9014280000 0.4103830000 0.0000050000 1.1705660000 0.0070350000 126846404 0 1785597952 3.8597583771 3.9679696560 3.9268791676 101 1311867173.7943561077 0.0578768365 0.0600356193 0.0637496114 0.0072408056 3.7512680000 0.9017360000 0.3686970000 0.1200540000 1.1592570000 1.1956010000 126848526 0 1784872960 3.8592383862 3.9682478905 3.9263858795 102 1311867173.8265669346 0.0571335480 0.0600071676 0.0637496114 0.0072073691 2.5003370000 0.9082510000 0.4176700000 0.0000050000 1.1621260000 0.0070890000 126850744 0 1784619008 3.8560931683 3.9667327404 3.9253747463 103 1311867173.8635799885 0.0577090383 0.0599848556 0.0637496114 0.0072061464 2.5306230000 0.8975440000 0.3429540000 0.1200610000 1.1571050000 0.0070910000 126852962 0 1783857152 3.8542997837 3.9677596092 3.9248950481 104 1311867173.8946080208 0.0579195619 0.0599649970 0.0637496114 0.0071748667 2.4834160000 0.9004820000 0.4095840000 0.0000050000 1.1610260000 0.0070950000 126855148 0 1783566336 3.8541486263 3.9673557281 3.9240989685 105 1311867173.9266970158 0.0568466634 0.0599352986 0.0637496114 0.0071484304 3.8259220000 0.9304580000 0.4137510000 0.1200070000 1.1573060000 1.1993890000 126857366 0 1785344000 3.8501749039 3.9668912888 3.9229762554 106 1311867173.9625461102 0.0570156127 0.0599077544 0.0637496114 0.0071517298 2.3597700000 0.9111820000 0.2716170000 0.0000050000 1.1638120000 0.0072140000 126859616 0 1784475648 3.8476972580 3.9681074619 3.9225909710 107 1311867173.9944310188 0.0575832240 0.0598860298 0.0637496114 0.0071368583 2.5048370000 0.8991620000 0.3043190000 0.1200530000 1.1690450000 0.0071290000 126861770 0 1784115200 3.8488373756 3.9683136940 3.9220428467 108 1311867174.0264260769 0.0566639975 0.0598561962 0.0637496114 0.0072188658 2.5071770000 0.9099250000 0.4126660000 0.0000050000 1.1724380000 0.0071560000 126863956 0 1785745408 3.8441989422 3.9667589664 3.9209568501 109 1311867174.0624630451 0.0573807918 0.0598334861 0.0637496114 0.0071924818 3.8365400000 0.9182450000 0.4123160000 0.1201510000 1.1727800000 1.2070480000 126866206 0 1784877056 3.8459565639 3.9672682285 3.9204864502 110 1311867174.0945188999 0.0590443909 0.0598263125 0.0637496114 0.0071696752 2.4603080000 0.9047670000 0.3764270000 0.0000050000 1.1667340000 0.0072060000 126868392 0 1784356864 3.8468382359 3.9684243202 3.9209518433 111 1311867174.1264541149 0.0584468544 0.0598138849 0.0637496114 0.0071550721 2.6071970000 0.9039770000 0.4056060000 0.1204420000 1.1640110000 0.0071250000 126870578 0 1783341056 3.8439760208 3.9667341709 3.9200520515 112 1311867174.1624329090 0.0586390942 0.0598033957 0.0637496114 0.0071549320 2.3627270000 0.9086830000 0.2739870000 0.0000050000 1.1677000000 0.0071720000 126872828 0 1783103488 3.8410651684 3.9674248695 3.9199662209 113 1311867174.1943979263 0.0595742986 0.0598013683 0.0637496114 0.0071431153 3.8238880000 0.9552360000 0.4076850000 0.1206010000 1.1482450000 1.1870640000 126875014 0 1784856576 3.8418729305 3.9687688351 3.9202806950 114 1311867174.2267580032 0.0586956479 0.0597916690 0.0637496114 0.0071215515 2.5167990000 0.9306920000 0.4115410000 0.0000050000 1.1614150000 0.0071840000 126877232 0 1783988224 3.8373532295 3.9668653011 3.9199481010 115 1311867174.2626769543 0.0587286614 0.0597824255 0.0637496114 0.0070906115 2.4147270000 0.9290440000 0.2080870000 0.1205700000 1.1446280000 0.0072000000 126879450 0 1783480320 3.8347368240 3.9667689800 3.9197309017 116 1311867174.2945280075 0.0598699339 0.0597831799 0.0637496114 0.0070735493 2.4731520000 0.9253200000 0.3795050000 0.0000040000 1.1561090000 0.0071940000 126881636 0 1785237504 3.8350160122 3.9675312042 3.9196445942 117 1311867174.3265740871 0.0585909560 0.0597729899 0.0637496114 0.0070453267 3.7689540000 0.9142290000 0.4188450000 0.1203400000 1.1364190000 1.1729470000 126883822 0 1783947264 3.8305931091 3.9666604996 3.9187405109 118 1311867174.3624329567 0.0584441125 0.0597617282 0.0637496114 0.0070233379 2.4317250000 0.9253080000 0.3575700000 0.0000050000 1.1364330000 0.0071910000 126886104 0 1783607296 3.8275561333 3.9675896168 3.9188973904 119 1311867174.3946359158 0.0591084734 0.0597562387 0.0637496114 0.0070234812 2.6162030000 0.9320450000 0.4126700000 0.1206280000 1.1385700000 0.0072030000 126888258 0 1785253888 3.8267400265 3.9688634872 3.9190390110 120 1311867174.4266788960 0.0587445237 0.0597478077 0.0637496114 0.0070002906 2.3499850000 0.9482080000 0.2424160000 0.0000040000 1.1460470000 0.0072920000 126890476 0 1784365056 3.8231389523 3.9683165550 3.9190061092 121 1311867174.4630160332 0.0581501722 0.0597346041 0.0637496114 0.0069866917 3.8078910000 0.9439440000 0.4302800000 0.1206850000 1.1322640000 1.1754410000 126892694 0 1783840768 3.8198907375 3.9676814079 3.9188239574 122 1311867174.4945669174 0.0592773780 0.0597308564 0.0637496114 0.0069587879 2.3876140000 0.9223310000 0.3190930000 0.0000040000 1.1339000000 0.0071940000 126894880 0 1785618432 3.8215534687 3.9686501026 3.9189665318 123 1311867174.5267519951 0.0586785600 0.0597223011 0.0637496114 0.0069437996 2.6250210000 0.9229790000 0.4304800000 0.1205560000 1.1376060000 0.0071820000 126897098 0 1784614912 3.8182566166 3.9680421352 3.9187588692 124 1311867174.5623500347 0.0582589284 0.0597104997 0.0637496114 0.0069574573 2.5276000000 0.9557620000 0.4244040000 0.0000040000 1.1348090000 0.0072340000 126899348 0 1783586816 3.8148713112 3.9675412178 3.9187698364 125 1311867174.5944879055 0.0587418824 0.0597027508 0.0637496114 0.0069524372 3.5971280000 0.9198900000 0.2389960000 0.1205220000 1.1396670000 1.1729450000 126901502 0 1785364480 3.8148317337 3.9690580368 3.9190649986 126 1311867174.6265459061 0.0587840080 0.0596954592 0.0637496114 0.0069306490 2.3058000000 0.9193960000 0.2399510000 0.0000050000 1.1331830000 0.0071440000 126903688 0 1784492032 3.8112585545 3.9694936275 3.9196410179 127 1311867174.6624910831 0.0581535660 0.0596833183 0.0637496114 0.0069090978 2.6425030000 0.9458580000 0.4320740000 0.1204850000 1.1315470000 0.0072690000 126905938 0 1783844864 3.8075289726 3.9683976173 3.9196798801 128 1311867174.6945910454 0.0588014089 0.0596764284 0.0637496114 0.0069066193 2.4950270000 0.9209990000 0.4295790000 0.0000040000 1.1321070000 0.0071720000 126908124 0 1785475072 3.8070626259 3.9702501297 3.9203579426 129 1311867174.7265629768 0.0591250360 0.0596721540 0.0637496114 0.0069117358 3.6215180000 0.9371880000 0.2760920000 0.1203340000 1.1210280000 1.1606510000 126920518 0 1784324096 3.8038773537 3.9701764584 3.9207565784 130 1311867174.7623760700 0.0586149134 0.0596640214 0.0637496114 0.0069122982 2.4841620000 0.9464080000 0.3944370000 0.0000040000 1.1307520000 0.0072380000 126943792 0 1783611392 3.7997982502 3.9673120975 3.9206774235 131 1311867174.7944738865 0.0588391833 0.0596577249 0.0637496114 0.0068883398 2.5919610000 0.9221720000 0.4206910000 0.1206830000 1.1160260000 0.0072580000 126945914 0 1785221120 3.8010241985 3.9683306217 3.9202110767 132 1311867174.8273398876 0.0587935038 0.0596511778 0.0637496114 0.0068632300 2.4759070000 0.9123440000 0.4269990000 0.0000040000 1.1231020000 0.0072440000 126948132 0 1783713792 3.7980921268 3.9676325321 3.9202332497 133 1311867174.8624229431 0.0576239713 0.0596359356 0.0637496114 0.0068416568 3.6256590000 0.9510900000 0.2766020000 0.1205600000 1.1166390000 1.1554060000 126950382 0 1782951936 3.7949335575 3.9673206806 3.9190900326 134 1311867174.8944199085 0.0568569228 0.0596151967 0.0637496114 0.0068345236 2.5014120000 0.9192500000 0.4413670000 0.0000050000 1.1284150000 0.0071470000 126952536 0 1784713216 3.7915284634 3.9691476822 3.9182255268 135 1311867174.9270179272 0.0568659529 0.0595948320 0.0637496114 0.0068274679 2.5207870000 0.9179210000 0.3510960000 0.1205780000 1.1179040000 0.0071220000 126954754 0 1783599104 3.7907671928 3.9684200287 3.9177138805 136 1311867174.9626429081 0.0571434349 0.0595768070 0.0637496114 0.0068098574 2.4723890000 0.9184250000 0.4243590000 0.0000040000 1.1168940000 0.0071590000 126957004 0 1782710272 3.7909016609 3.9681434631 3.9169032574 137 1311867174.9943349361 0.0565315746 0.0595545790 0.0637496114 0.0068195548 3.7225580000 0.9225550000 0.4172330000 0.1204350000 1.1061590000 1.1509910000 126959158 0 1784459264 3.7862606049 3.9690127373 3.9163610935 138 1311867175.0265510082 0.0574030131 0.0595389880 0.0637496114 0.0068517430 2.4787990000 0.9284460000 0.4254560000 0.0000050000 1.1116340000 0.0071740000 126961376 0 1783590912 3.7856111526 3.9726138115 3.9166347980 139 1311867175.0633120537 0.0569432974 0.0595203139 0.0637496114 0.0068285413 2.4610360000 0.9307330000 0.2769170000 0.1205340000 1.1202140000 0.0071850000 126963626 0 1782845440 3.7811677456 3.9713394642 3.9167120457 140 1311867175.0947189331 0.0556159206 0.0594924254 0.0637496114 0.0068236047 2.4781430000 0.9248550000 0.4171740000 0.0000040000 1.1236160000 0.0072560000 126965812 0 1784459264 3.7697362900 3.9731354713 3.9162223339 141 1311867175.1265308857 0.0559702441 0.0594674454 0.0637496114 0.0068114548 3.7363140000 0.9293780000 0.4140420000 0.1204140000 1.1157530000 1.1504870000 126967998 0 1783336960 3.7719447613 3.9735140800 3.9168779850 142 1311867175.1625180244 0.0562498830 0.0594447865 0.0637496114 0.0068222253 2.3928530000 0.9219440000 0.3429590000 0.0000040000 1.1153110000 0.0071680000 126970248 0 1782829056 3.7708587646 3.9732387066 3.9173259735 143 1311867175.1946399212 0.0561586022 0.0594218062 0.0637496114 0.0068020238 2.3788980000 0.9324610000 0.2029090000 0.1205240000 1.1105490000 0.0071830000 126972402 0 1784602624 3.7687737942 3.9729549885 3.9174726009 144 1311867175.2270050049 0.0558356233 0.0593969022 0.0637496114 0.0068538557 2.4237990000 0.9207000000 0.3792200000 0.0000040000 1.1105090000 0.0071630000 126974620 0 1783463936 3.7661721706 3.9744918346 3.9180867672 145 1311867175.2624669075 0.0559922047 0.0593734215 0.0637496114 0.0068617975 3.5891700000 0.9410620000 0.2758300000 0.1212170000 1.1029180000 1.1427150000 126976838 0 1782824960 3.7666895390 3.9758155346 3.9181597233 146 1311867175.2944509983 0.0558784604 0.0593494834 0.0637496114 0.0068647467 2.4910230000 0.9385260000 0.4262680000 0.0000040000 1.1137470000 0.0072700000 126979024 0 1784582144 3.7595636845 3.9758026600 3.9188203812 147 1311867175.3267059326 0.0557339899 0.0593248882 0.0637496114 0.0068430712 2.5907900000 0.9445080000 0.4217650000 0.1205910000 1.0904780000 0.0072530000 126981242 0 1783443456 3.7617893219 3.9775149822 3.9195814133 148 1311867175.3625650406 0.0566750988 0.0593069842 0.0637496114 0.0068661249 2.4988370000 0.9607270000 0.4240100000 0.0000040000 1.1008820000 0.0078210000 126983460 0 1782960128 3.7567965984 3.9765629768 3.9204156399 149 1311867175.3945989609 0.0564500540 0.0592878102 0.0637496114 0.0068578364 3.4873880000 0.9596880000 0.2033750000 0.1205670000 1.0796950000 1.1188070000 126985646 0 1784627200 3.7569773197 3.9759016037 3.9204154015 150 1311867175.4266059399 0.0568232425 0.0592713797 0.0637496114 0.0068456219 2.4740470000 0.9443480000 0.4352150000 0.0000050000 1.0809640000 0.0073050000 126987832 0 1783586816 3.7503011227 3.9771943092 3.9211153984 151 1311867175.4625999928 0.0565722771 0.0592535049 0.0637496114 0.0068400051 2.5609850000 0.9408560000 0.4154640000 0.1202140000 1.0715870000 0.0072390000 126990114 0 1782702080 3.7488856316 3.9770271778 3.9212825298 152 1311867175.4945731163 0.0569796339 0.0592385452 0.0637496114 0.0068256764 2.5009930000 0.9694250000 0.4419000000 0.0000050000 1.0770890000 0.0073060000 126992300 0 1784479744 3.7433903217 3.9771893024 3.9217329025 153 1311867175.5264270306 0.0577829778 0.0592290317 0.0637496114 0.0068294911 3.7298240000 0.9833750000 0.4316440000 0.1212150000 1.0727830000 1.1145440000 126994454 0 1783357440 3.7386469841 3.9779260159 3.9220459461 154 1311867175.5625700951 0.0572606586 0.0592162500 0.0637496114 0.0068527571 2.3158140000 0.9442290000 0.2838080000 0.0000040000 1.0748230000 0.0075000000 126996736 0 1782427648 3.7368938923 3.9784686565 3.9221830368 155 1311867175.5946640968 0.0581523106 0.0592093859 0.0637496114 0.0068853681 2.5905580000 0.9536960000 0.4345900000 0.1204500000 1.0691850000 0.0072860000 126998890 0 1784205312 3.7348206043 3.9798421860 3.9225444794 156 1311867175.6264801025 0.0577042811 0.0591997378 0.0637496114 0.0068930601 2.4734210000 0.9550030000 0.4388990000 0.0000050000 1.0660820000 0.0073140000 127001076 0 1783336960 3.7309091091 3.9798426628 3.9226858616 157 1311867175.6624929905 0.0585416444 0.0591955461 0.0637496114 0.0069499755 3.6634300000 0.9796640000 0.3923720000 0.1204020000 1.0663110000 1.0991790000 127003326 0 1782575104 3.7306337357 3.9813606739 3.9231817722 158 1311867175.6947000027 0.0583335720 0.0591900906 0.0637496114 0.0069541814 2.4696260000 0.9621270000 0.4308840000 0.0000040000 1.0639840000 0.0073130000 127005512 0 1784221696 3.7278964520 3.9804387093 3.9232385159 159 1311867175.7273120880 0.0588334091 0.0591878473 0.0637496114 0.0069438815 2.4087570000 0.9655930000 0.2519760000 0.1205550000 1.0570230000 0.0073740000 127007730 0 1783083008 3.7252597809 3.9800019264 3.9235539436 160 1311867175.7624969482 0.0590400398 0.0591869235 0.0637496114 0.0069459277 2.4437620000 0.9460900000 0.4251510000 0.0000050000 1.0597460000 0.0072860000 127009980 0 1782333440 3.7210502625 3.9807469845 3.9235391617 161 1311867175.7948620319 0.0592172816 0.0591871121 0.0637496114 0.0069540273 3.4573100000 0.9429690000 0.2466080000 0.1204210000 1.0513880000 1.0904970000 127012134 0 1783971840 3.7184464931 3.9798192978 3.9235708714 162 1311867175.8287971020 0.0594117232 0.0591884986 0.0637496114 0.0069426655 2.4584200000 0.9566120000 0.4343890000 0.0000050000 1.0547630000 0.0073060000 127014384 0 1785716736 3.7144296169 3.9787187576 3.9233922958 163 1311867175.8625519276 0.0595719330 0.0591908509 0.0637496114 0.0069618693 2.5959830000 0.9646420000 0.4391700000 0.1205750000 1.0578300000 0.0073370000 127016602 0 1784590336 3.7129812241 3.9804167747 3.9233610630 164 1311867175.8946080208 0.0598301999 0.0591947494 0.0637496114 0.0069461912 2.4184070000 0.9852720000 0.3571350000 0.0000040000 1.0630840000 0.0073540000 127018756 0 1783717888 3.7109079361 3.9806263447 3.9228589535 165 1311867175.9282429218 0.0597392768 0.0591980496 0.0637496114 0.0069503239 3.6807440000 0.9699600000 0.4314100000 0.1206680000 1.0561830000 1.0970900000 127020974 0 1785487360 3.7049741745 3.9796335697 3.9224581718 166 1311867175.9629371166 0.0601840764 0.0592039895 0.0637496114 0.0069299119 2.3602600000 0.9579260000 0.3194550000 0.0000050000 1.0691940000 0.0073670000 127023192 0 1784623104 3.7026989460 3.9799046516 3.9225471020 167 1311867175.9983000755 0.0602572560 0.0592102965 0.0637496114 0.0069430613 2.4142430000 0.9398170000 0.2831760000 0.1203930000 1.0580300000 0.0072620000 127025410 0 1783447552 3.7022697926 3.9811801910 3.9223616123 168 1311867176.0268509388 0.0608884469 0.0592202855 0.0637496114 0.0069288244 2.4617550000 0.9493360000 0.4317440000 0.0000050000 1.0679780000 0.0072760000 127027532 0 1785200640 3.6976859570 3.9791584015 3.9221291542 169 1311867176.0627059937 0.0605483465 0.0592281438 0.0637496114 0.0069466469 3.5368340000 0.9657720000 0.2855990000 0.1211550000 1.0589940000 1.0990480000 127029782 0 1784352768 3.6931841373 3.9796481133 3.9216091633 170 1311867176.0946600437 0.0614970289 0.0592414902 0.0637496114 0.0069926013 2.4037400000 0.9422110000 0.3883310000 0.0000060000 1.0602900000 0.0072730000 127031936 0 1783214080 3.6905729771 3.9805972576 3.9213323593 171 1311867176.1268119812 0.0615149066 0.0592547850 0.0637496114 0.0069748564 2.5244590000 0.9419580000 0.3934100000 0.1205600000 1.0557580000 0.0072640000 127034154 0 1784987648 3.6917467117 3.9804008007 3.9205183983 172 1311867176.1625900269 0.0611800626 0.0592659785 0.0637496114 0.0070378707 2.2709470000 0.9500130000 0.2447990000 0.0000050000 1.0625170000 0.0073390000 127036404 0 1784123392 3.6884796619 3.9809131622 3.9199237823 173 1311867176.1946918964 0.0616373979 0.0592796861 0.0637496114 0.0070765816 3.5371450000 0.9355290000 0.3083830000 0.1203780000 1.0624210000 1.1047780000 127038590 0 1782939648 3.6875524521 3.9812724590 3.9191911221 174 1311867176.2265360355 0.0617797226 0.0592940542 0.0637496114 0.0070575757 2.3340840000 0.9432230000 0.3185050000 0.0000050000 1.0595520000 0.0072870000 127040776 0 1784725504 3.6846528053 3.9816453457 3.9188170433 175 1311867176.2625019550 0.0618104860 0.0593084338 0.0637496114 0.0070452684 2.5448470000 0.9262770000 0.4180000000 0.1202980000 1.0666740000 0.0073420000 127043026 0 1783865344 3.6813559532 3.9821493626 3.9179294109 176 1311867176.2946109772 0.0622784160 0.0593253087 0.0637496114 0.0070404266 2.4274800000 0.9299620000 0.4168050000 0.0000050000 1.0678240000 0.0072580000 127045180 0 1783087104 3.6783118248 3.9841864109 3.9175431728 177 1311867176.3266019821 0.0629915968 0.0593460222 0.0637496114 0.0070305073 3.6407580000 0.9308470000 0.4184930000 0.1205530000 1.0683430000 1.0969950000 127047366 0 1784725504 3.6757502556 3.9866182804 3.9172277451 178 1311867176.3624560833 0.0631447509 0.0593673633 0.0637496114 0.0070127922 2.3029730000 0.9390300000 0.2855560000 0.0000050000 1.0646090000 0.0072900000 127049648 0 1783590912 3.6749634743 3.9853081703 3.9163978100 179 1311867176.3952438831 0.0633786395 0.0593897727 0.0637496114 0.0069943381 2.5564530000 0.9183820000 0.4290080000 0.1257980000 1.0703720000 0.0072920000 127051802 0 1782833152 3.6735801697 3.9867644310 3.9159812927 180 1311867176.4268360138 0.0630562156 0.0594101418 0.0637496114 0.0069805539 2.2728060000 0.9147970000 0.2748570000 0.0000050000 1.0704210000 0.0072660000 127053988 0 1784463360 3.6730272770 3.9876997471 3.9152426720 181 1311867176.4629659653 0.0627078488 0.0594283612 0.0637496114 0.0070490589 3.5301700000 0.9151990000 0.3091280000 0.1203790000 1.0740350000 1.1048840000 127056238 0 1783083008 3.6708950996 3.9875009060 3.9144408703 182 1311867176.4945809841 0.0636209399 0.0594513973 0.0637496114 0.0070457183 2.3350950000 0.9088590000 0.3416650000 0.0000040000 1.0716640000 0.0072460000 127058392 0 1782169600 3.6685369015 3.9874539375 3.9135954380 183 1311867176.5266211033 0.0639921129 0.0594762100 0.0639921129 0.0071032366 2.5072450000 0.9117330000 0.3898750000 0.1202970000 1.0725930000 0.0072340000 127060610 0 1783963648 3.6664264202 3.9898025990 3.9128546715 184 1311867176.5636389256 0.0641079023 0.0595013822 0.0641079023 0.0070971456 2.3972160000 0.9215570000 0.3858340000 0.0000050000 1.0762450000 0.0072330000 127062892 0 1783066624 3.6643879414 3.9891302586 3.9121134281 185 1311867176.5946090221 0.0642133057 0.0595268521 0.0642133057 0.0070871576 3.5081390000 0.9356380000 0.2430120000 0.1211190000 1.0823960000 1.1202400000 127065046 0 1782972416 3.6602222919 3.9890646935 3.9111826420 186 1311867176.6283841133 0.0638242662 0.0595499565 0.0642133057 0.0070771306 2.4405720000 0.9160110000 0.4165300000 0.0000040000 1.0952130000 0.0072420000 127067264 0 1784709120 3.6594204903 3.9895994663 3.9104261398 187 1311867176.6625781059 0.0638562292 0.0595729847 0.0642133057 0.0070625183 2.5141580000 0.9098410000 0.3810420000 0.1205330000 1.0891210000 0.0072200000 127069482 0 1783820288 3.6565654278 3.9905514717 3.9097523689 188 1311867176.6945180893 0.0633186176 0.0595929082 0.0642133057 0.0070459102 2.4371380000 0.9089740000 0.4174690000 0.0000050000 1.0977980000 0.0072390000 127071636 0 1783730176 3.6556811333 3.9907588959 3.9087240696 189 1311867176.7265889645 0.0638480633 0.0596154223 0.0642133057 0.0070289030 3.5809060000 0.9119020000 0.3129120000 0.1204740000 1.0940620000 1.1359230000 127073854 0 1785339904 3.6514461040 3.9915652275 3.9084146023 190 1311867176.7632329464 0.0636634827 0.0596367279 0.0642133057 0.0070240661 2.4605450000 0.9155010000 0.4295350000 0.0000050000 1.1017610000 0.0072580000 127076104 0 1784582144 3.6506538391 3.9923002720 3.9080705643 191 1311867176.7947680950 0.0637065098 0.0596580356 0.0642133057 0.0070255347 2.5009200000 0.9173070000 0.3517350000 0.1206470000 1.0982720000 0.0071760000 127078258 0 1784365056 3.6478021145 3.9921715260 3.9076189995 192 1311867176.8266770840 0.0639163256 0.0596802142 0.0642133057 0.0070087701 2.4046800000 0.9340730000 0.3512120000 0.0000050000 1.1058210000 0.0071580000 127080476 0 1783820288 3.6453547478 3.9919314384 3.9072356224 193 1311867176.8627309799 0.0637285858 0.0597011902 0.0642133057 0.0069940718 3.6599710000 0.9042600000 0.3813720000 0.1203270000 1.1032440000 1.1450310000 127082726 0 1783730176 3.6436414719 3.9931447506 3.9066770077 194 1311867176.8949549198 0.0642284974 0.0597245269 0.0642284974 0.0069770734 2.4264490000 0.8884250000 0.4205380000 0.0000050000 1.1047340000 0.0071390000 127084912 0 1785507840 3.6384825706 3.9932672977 3.9065275192 195 1311867176.9268178940 0.0636315644 0.0597445630 0.0642284974 0.0069789961 2.5074850000 0.9205150000 0.3440390000 0.1205320000 1.1085440000 0.0071950000 127087098 0 1784582144 3.6373724937 3.9932498932 3.9061431885 196 1311867176.9650609493 0.0638996065 0.0597657622 0.0642284974 0.0069906419 2.3460540000 0.9056170000 0.3126660000 0.0000050000 1.1148340000 0.0072060000 127089348 0 1784344576 3.6355366707 3.9945302010 3.9061203003 197 1311867176.9947481155 0.0637772754 0.0597861252 0.0642284974 0.0069767912 3.7121500000 0.9094390000 0.4081220000 0.1210380000 1.1100230000 1.1570200000 127091502 0 1783611392 3.6343052387 3.9948251247 3.9057068825 198 1311867177.0267279148 0.0642937869 0.0598088912 0.0642937869 0.0069618343 2.4441930000 0.9066740000 0.4101490000 0.0000050000 1.1144810000 0.0071610000 127093688 0 1783738368 3.6300809383 3.9935047626 3.9055647850 199 1311867177.0626339912 0.0642254800 0.0598310851 0.0642937869 0.0069488992 2.3848530000 0.8940430000 0.2374460000 0.1205350000 1.1199410000 0.0073210000 127095938 0 1785516032 3.6296336651 3.9947981834 3.9053254128 200 1311867177.0946850777 0.0639805347 0.0598518323 0.0642937869 0.0069347684 2.3201050000 0.8924890000 0.3005880000 0.0000050000 1.1132220000 0.0071850000 127098124 0 1784582144 3.6277296543 3.9949836731 3.9047226906 201 1311867177.1266150475 0.0640667900 0.0598728023 0.0642937869 0.0069206277 3.7003350000 0.8948130000 0.4032120000 0.1206590000 1.1201890000 1.1555400000 127100310 0 1784365056 3.6268322468 3.9944314957 3.9045748711 202 1311867177.1627299786 0.0644219071 0.0598953226 0.0644219071 0.0069063815 2.4470170000 0.9022270000 0.4121550000 0.0000040000 1.1189160000 0.0072140000 127102560 0 1783603200 3.6232953072 3.9950509071 3.9046621323 203 1311867177.1946458817 0.0645404458 0.0599182050 0.0645404458 0.0068916315 2.4249280000 0.9003010000 0.2754660000 0.1209870000 1.1152120000 0.0071940000 127104746 0 1783582720 3.6198594570 3.9958477020 3.9044196606 204 1311867177.2264730930 0.0648187622 0.0599422273 0.0648187622 0.0068757548 2.4414640000 0.8926180000 0.4176240000 0.0000050000 1.1184140000 0.0071870000 127106932 0 1785491456 3.6180214882 3.9950561523 3.9040412903 205 1311867177.2638640404 0.0654751137 0.0599692170 0.0654751137 0.0068597147 3.6803730000 0.8970350000 0.3764680000 0.1206960000 1.1184780000 1.1610310000 127109214 0 1784619008 3.6148958206 3.9954650402 3.9039430618 206 1311867177.2946178913 0.0648667812 0.0599929916 0.0654751137 0.0068607455 2.2999740000 0.8897120000 0.2727550000 0.0000040000 1.1244660000 0.0071040000 127111368 0 1784365056 3.6133577824 3.9953246117 3.9033982754 207 1311867177.3276090622 0.0649536178 0.0600169559 0.0654751137 0.0068446623 2.5549020000 0.8975940000 0.4054380000 0.1206590000 1.1176080000 0.0071570000 127113586 0 1783820288 3.6097223759 3.9960172176 3.9030108452 208 1311867177.3627710342 0.0651793703 0.0600417752 0.0654751137 0.0068320858 2.2947460000 0.8839510000 0.2720630000 0.0000040000 1.1257390000 0.0071700000 127115804 0 1783726080 3.6089613438 3.9967184067 3.9027230740 209 1311867177.3946089745 0.0656658038 0.0600686845 0.0656658038 0.0068375857 3.5955690000 0.8865710000 0.3091240000 0.1204400000 1.1159740000 1.1576860000 127117990 0 1785470976 3.6055119038 3.9963331223 3.9024293423 210 1311867177.4312860966 0.0657110438 0.0600955529 0.0657110438 0.0068244514 2.2378310000 0.8938740000 0.2033490000 0.0000040000 1.1266570000 0.0071300000 127120272 0 1784590336 3.6044569016 3.9973957539 3.9021842480 211 1311867177.4626040459 0.0660511404 0.0601237784 0.0660511404 0.0068106608 2.5495380000 0.8902700000 0.4075320000 0.1207700000 1.1178380000 0.0072350000 127122458 0 1784500224 3.6010603905 3.9977838993 3.9019231796 212 1311867177.4946429729 0.0658056810 0.0601505798 0.0660511404 0.0067968412 2.3697840000 0.8926760000 0.3370370000 0.0000050000 1.1262390000 0.0070930000 127124644 0 1783574528 3.6004328728 3.9982182980 3.9014213085 213 1311867177.5276319981 0.0657516420 0.0601768759 0.0660511404 0.0067835966 3.5636730000 0.8909710000 0.2705100000 0.1207320000 1.1145990000 1.1608820000 127126830 0 1783476224 3.5993185043 3.9990191460 3.9009921551 214 1311867177.5626399517 0.0666280463 0.0602070215 0.0666280463 0.0067775659 2.2256400000 0.8955280000 0.1983480000 0.0000040000 1.1189570000 0.0071590000 127129048 0 1785090048 3.5974872112 3.9995238781 3.9010159969 215 1311867177.5947310925 0.0663441792 0.0602355665 0.0666280463 0.0067698290 2.5524790000 0.9267100000 0.3747580000 0.1209570000 1.1161830000 0.0071690000 127131234 0 1784197120 3.5906829834 3.9986875057 3.8997228146 216 1311867177.6311450005 0.0661702529 0.0602630419 0.0666280463 0.0067548860 2.1949470000 0.8948580000 0.1685400000 0.0000050000 1.1185400000 0.0071620000 127133516 0 1784111104 3.5892031193 3.9998958111 3.8990886211 217 1311867177.6624829769 0.0658144131 0.0602886242 0.0666280463 0.0067435741 3.5412950000 0.8936170000 0.2390430000 0.1210340000 1.1165250000 1.1643450000 127135702 0 1783349248 3.5889141560 4.0009326935 3.8984889984 218 1311867177.6945610046 0.0664679259 0.0603169696 0.0666280463 0.0067535879 2.4310900000 0.8889290000 0.4093030000 0.0000040000 1.1197270000 0.0071580000 127137888 0 1783058432 3.5840294361 4.0008292198 3.8983261585 219 1311867177.7305839062 0.0660822019 0.0603432949 0.0666280463 0.0067439516 2.4517230000 0.8912110000 0.3036670000 0.1210070000 1.1229240000 0.0071280000 127140106 0 1784709120 3.5845024586 4.0025644302 3.8975970745 220 1311867177.7625379562 0.0662275255 0.0603700414 0.0666280463 0.0067351668 2.2236630000 0.8979050000 0.1953760000 0.0000050000 1.1165450000 0.0072000000 127142292 0 1783984128 3.5850541592 4.0026006699 3.8971946239 221 1311867177.7945590019 0.0664286241 0.0603974558 0.0666280463 0.0067216992 3.5852130000 0.8819000000 0.3070260000 0.1211600000 1.1104790000 1.1587310000 127144478 0 1783726080 3.5821840763 4.0026431084 3.8963801861 222 1311867177.8309149742 0.0669117719 0.0604267996 0.0669117719 0.0067124932 2.2914950000 0.8892300000 0.2753120000 0.0000040000 1.1140040000 0.0071880000 127146728 0 1785470976 3.5795781612 4.0026960373 3.8956398964 223 1311867177.8625319004 0.0665057302 0.0604540593 0.0669117719 0.0067011592 2.5616290000 0.8899800000 0.4162610000 0.1211160000 1.1203660000 0.0071650000 127148914 0 1784754176 3.5809133053 4.0029311180 3.8948771954 224 1311867177.8946919441 0.0671600848 0.0604839970 0.0671600848 0.0066871514 2.4302430000 0.8889590000 0.4112860000 0.0000040000 1.1169040000 0.0070830000 127151068 0 1784496128 3.5776793957 4.0037803650 3.8946371078 225 1311867177.9317860603 0.0674245879 0.0605148440 0.0674245879 0.0066733930 3.7252490000 0.9119280000 0.4063340000 0.1212210000 1.1226390000 1.1563340000 127153382 0 1783726080 3.5757529736 4.0039215088 3.8939437866 226 1311867177.9627909660 0.0672595724 0.0605446880 0.0674245879 0.0066636182 2.4264280000 0.8869060000 0.4110080000 0.0000050000 1.1154120000 0.0071090000 127155536 0 1783857152 3.5760354996 4.0040521622 3.8928616047 227 1311867177.9947769642 0.0672316030 0.0605741457 0.0674245879 0.0066554343 2.5522370000 0.8866760000 0.4124870000 0.1210230000 1.1189980000 0.0071790000 127157658 0 1785470976 3.5747642517 4.0059514046 3.8920507431 228 1311867178.0306100845 0.0676225498 0.0606050598 0.0676225498 0.0066413972 2.2695250000 0.8993250000 0.2372960000 0.0000040000 1.1189110000 0.0071860000 127159908 0 1784709120 3.5718371868 4.0055060387 3.8914372921 229 1311867178.0634479523 0.0675423965 0.0606353538 0.0676225498 0.0066283662 3.5606640000 0.9056210000 0.2375970000 0.1210880000 1.1221090000 1.1681920000 127162094 0 1784492032 3.5722908974 4.0046944618 3.8907358646 230 1311867178.0951139927 0.0672972351 0.0606643185 0.0676225498 0.0066149134 2.4525060000 0.8905430000 0.4138280000 0.0000040000 1.1342750000 0.0071550000 127164280 0 1783730176 3.5702455044 4.0065593719 3.8900988102 231 1311867178.1307909489 0.0683877766 0.0606977534 0.0683877766 0.0066091181 2.5627810000 0.8903050000 0.4132730000 0.1211520000 1.1249330000 0.0071800000 127166530 0 1783439360 3.5648093224 4.0054087639 3.8899784088 232 1311867178.1627469063 0.0686256364 0.0607319253 0.0686256364 0.0066210406 2.4554440000 0.9018660000 0.4016330000 0.0000040000 1.1389330000 0.0071670000 127168716 0 1785085952 3.5632002354 4.0051288605 3.8894772530 233 1311867178.1950459480 0.0681252107 0.0607636562 0.0686256364 0.0066218045 3.6435470000 0.8940740000 0.3066330000 0.1214020000 1.1345420000 1.1800820000 127170870 0 1784360960 3.5643591881 4.0070919991 3.8890254498 234 1311867178.2307190895 0.0686012879 0.0607971503 0.0686256364 0.0066098367 2.4714570000 0.9052360000 0.4132800000 0.0000050000 1.1397080000 0.0071100000 127173120 0 1784238080 3.5601785183 4.0057616234 3.8884780407 235 1311867178.2628939152 0.0681490824 0.0608284351 0.0686256364 0.0065974296 2.4549010000 0.9080600000 0.2674320000 0.1213880000 1.1440180000 0.0071410000 127175338 0 1783345152 3.5594158173 4.0057325363 3.8879368305 236 1311867178.2954900265 0.0680629760 0.0608590900 0.0686256364 0.0065863793 2.4687060000 0.8929770000 0.4111260000 0.0000050000 1.1514650000 0.0071250000 127177524 0 1783484416 3.5568747520 4.0072350502 3.8877172470 237 1311867178.3306670189 0.0683683977 0.0608907748 0.0686256364 0.0065792573 3.6752900000 0.8892440000 0.3070800000 0.1213840000 1.1495730000 1.2021190000 127179742 0 1785253888 3.5542204380 4.0054478645 3.8875837326 238 1311867178.3627231121 0.0674531460 0.0609183478 0.0686256364 0.0065681879 2.3086810000 0.8987770000 0.2368590000 0.0000050000 1.1590600000 0.0071190000 127181960 0 1784328192 3.5551698208 4.0064592361 3.8870937824 239 1311867178.3949439526 0.0675789416 0.0609462164 0.0686256364 0.0065565082 2.4580120000 0.8871110000 0.2693570000 0.1213560000 1.1669010000 0.0071470000 127184114 0 1784102912 3.5518560410 4.0069127083 3.8869042397 240 1311867178.4306581020 0.0680940226 0.0609759989 0.0686256364 0.0065587971 2.3693640000 0.8877880000 0.3065110000 0.0000050000 1.1612440000 0.0071200000 127186364 0 1783562240 3.5486450195 4.0072035789 3.8872239590 241 1311867178.4628739357 0.0684693232 0.0610070916 0.0686256364 0.0065457580 3.7909560000 0.8798320000 0.4036750000 0.1216530000 1.1692270000 1.2105250000 127188550 0 1783476224 3.5461893082 4.0077371597 3.8874359131 242 1311867178.4946439266 0.0685909390 0.0610384298 0.0686256364 0.0065339195 2.2998080000 0.8865700000 0.2365840000 0.0000040000 1.1635700000 0.0071290000 127190736 0 1785090048 3.5439732075 4.0067620277 3.8874495029 243 1311867178.5306270123 0.0680946112 0.0610674675 0.0686256364 0.0065361325 2.5994410000 0.8829680000 0.4138420000 0.1269970000 1.1616980000 0.0070670000 127192986 0 1784348672 3.5441784859 4.0083322525 3.8871891499 244 1311867178.5626420975 0.0689167529 0.0610996368 0.0689167529 0.0065239755 2.4061750000 0.8947590000 0.3354230000 0.0000050000 1.1628760000 0.0071030000 127195204 0 1783836672 3.5404541492 4.0082941055 3.8876893520 245 1311867178.5947000980 0.0688062757 0.0611310924 0.0689167529 0.0065222538 3.8184610000 0.9049170000 0.4140090000 0.1218430000 1.1613760000 1.2103700000 127197390 0 1785597952 3.5399239063 4.0073523521 3.8874621391 246 1311867178.6306900978 0.0690987855 0.0611634814 0.0690987855 0.0065197694 2.4782550000 0.8833410000 0.4090230000 0.0000050000 1.1719330000 0.0071140000 127199608 0 1784856576 3.5374474525 4.0081644058 3.8873436451 247 1311867178.6626410484 0.0686808825 0.0611939162 0.0690987855 0.0065294115 2.6000210000 0.8938800000 0.4075700000 0.1220810000 1.1632780000 0.0071270000 127201826 0 1784201216 3.5373356342 4.0093269348 3.8871557713 248 1311867178.6946120262 0.0695199445 0.0612274889 0.0695199445 0.0065197296 2.4742700000 0.8892930000 0.4030640000 0.0000050000 1.1679820000 0.0070600000 127203980 0 1783468032 3.5338237286 4.0074315071 3.8872370720 249 1311867178.7307450771 0.0692875385 0.0612598586 0.0695199445 0.0065166971 3.6848820000 0.8806520000 0.2986370000 0.1216120000 1.1661110000 1.2116470000 127206230 0 1782943744 3.5332224369 4.0090279579 3.8868076801 250 1311867178.7632350922 0.0691252202 0.0612913201 0.0695199445 0.0065092854 2.4602110000 0.8839290000 0.4024690000 0.0000050000 1.1606540000 0.0071810000 127208448 0 1784729600 3.5326392651 4.0094399452 3.8865149021 251 1311867178.8006799221 0.0695301071 0.0613241439 0.0695301071 0.0065046537 2.4546760000 0.8878550000 0.2700280000 0.1216520000 1.1611240000 0.0070780000 127210698 0 1783840768 3.5301098824 4.0075902939 3.8863160610 252 1311867178.8309500217 0.0694766045 0.0613564949 0.0695301071 0.0065008432 2.4697640000 0.8793700000 0.4115640000 0.0000040000 1.1654530000 0.0071640000 127212852 0 1783332864 3.5291018486 4.0098938942 3.8861777782 253 1311867178.8627939224 0.0693085715 0.0613879261 0.0695301071 0.0064994676 3.6449500000 0.8882640000 0.2658050000 0.1217400000 1.1576450000 1.2054210000 127215070 0 1784999936 3.5290315151 4.0097517967 3.8858816624 254 1311867178.8952279091 0.0701256692 0.0614223266 0.0701256692 0.0065004504 2.4347440000 0.8947910000 0.3692920000 0.0000050000 1.1566500000 0.0071540000 127217256 0 1784242176 3.5271840096 4.0066146851 3.8856759071 255 1311867178.9306209087 0.0695406795 0.0614541633 0.0701256692 0.0064974543 2.4311940000 0.9055780000 0.2378140000 0.1217050000 1.1527740000 0.0071980000 127219474 0 1783734272 3.5291485786 4.0092210770 3.8845882416 256 1311867178.9627609253 0.0692917407 0.0614847789 0.0701256692 0.0064950715 2.4827130000 0.9194870000 0.4113390000 0.0000040000 1.1386550000 0.0072850000 127221692 0 1785344000 3.5293607712 4.0094771385 3.8837640285 257 1311867178.9946830273 0.0698977858 0.0615175143 0.0701256692 0.0064934517 3.7195790000 0.8890480000 0.3999320000 0.1213480000 1.1304120000 1.1717530000 127244358 0 1784623104 3.5234777927 4.0086107254 3.8832075596 258 1311867179.0309159756 0.0700018182 0.0615503992 0.0701256692 0.0065307436 2.2619440000 0.8802970000 0.2335900000 0.0000050000 1.1347490000 0.0070420000 127288592 0 1784094720 3.5216555595 4.0100846291 3.8826816082 259 1311867179.0628120899 0.0696840957 0.0615818034 0.0701256692 0.0065250284 2.5158810000 0.8980970000 0.3381180000 0.1218000000 1.1436900000 0.0072060000 127290810 0 1783099392 3.5222270489 4.0088987350 3.8818325996 260 1311867179.0968201160 0.0711863786 0.0616187441 0.0711863786 0.0066245134 2.4005060000 0.8995220000 0.3378830000 0.0000050000 1.1497120000 0.0071300000 127292996 0 1782595584 3.5171494484 4.0057635307 3.8813812733 261 1311867179.1310369968 0.0698857456 0.0616504184 0.0711863786 0.0066134162 3.7365360000 0.8853640000 0.3705650000 0.1217190000 1.1592940000 1.1935870000 127295182 0 1784213504 3.5212075710 4.0081958771 3.8799796104 262 1311867179.1627540588 0.0705820546 0.0616845086 0.0711863786 0.0066186496 2.3256090000 0.8902300000 0.2683090000 0.0000050000 1.1529170000 0.0072360000 127297368 0 1783087104 3.5194079876 4.0069046021 3.8787820339 263 1311867179.1957008839 0.0707957149 0.0617191520 0.0711863786 0.0066116128 2.4668380000 0.9167050000 0.2635880000 0.1214300000 1.1517480000 0.0070810000 127299554 0 1782341632 3.5144553185 4.0059018135 3.8772785664 264 1311867179.2307469845 0.0709307641 0.0617540445 0.0711863786 0.0066729642 2.2841500000 0.8557360000 0.2588690000 0.0000050000 1.1564540000 0.0070610000 127301772 0 1783963648 3.5122570992 4.0098290443 3.8764650822 265 1311867179.2634611130 0.0708321109 0.0617883013 0.0711863786 0.0066721870 3.7720600000 0.8848090000 0.3987810000 0.1220740000 1.1611020000 1.1983530000 127304022 0 1783078912 3.5104572773 4.0080809593 3.8755557537 266 1311867179.2959330082 0.0706309751 0.0618215445 0.0711863786 0.0066639364 2.4365950000 0.9020130000 0.3355450000 0.0000050000 1.1857020000 0.0071030000 127306176 0 1782554624 3.5090558529 4.0076584816 3.8747255802 267 1311867179.3307149410 0.0699031204 0.0618518125 0.0711863786 0.0066535393 2.5842180000 0.8678290000 0.3921830000 0.1220040000 1.1890590000 0.0070590000 127308394 0 1784348672 3.5114099979 4.0090975761 3.8739917278 268 1311867179.3629300594 0.0701189786 0.0618826602 0.0711863786 0.0066439042 2.4645800000 0.8551070000 0.3996550000 0.0000050000 1.1956450000 0.0069840000 127310644 0 1783463936 3.5090749264 4.0090870857 3.8736889362 269 1311867179.3948490620 0.0701049119 0.0619132262 0.0711863786 0.0066368348 3.7976530000 0.8695260000 0.3739160000 0.1217750000 1.1907660000 1.2354130000 127312766 0 1782702080 3.5076456070 4.0077948570 3.8732280731 270 1311867179.4308040142 0.0698910132 0.0619427735 0.0711863786 0.0066505083 2.3928440000 0.8836190000 0.2942870000 0.0000040000 1.2017370000 0.0071210000 127315048 0 1784459264 3.5057773590 4.0100641251 3.8731417656 271 1311867179.4637460709 0.0703117847 0.0619736555 0.0711863786 0.0066454979 2.4445500000 0.8752840000 0.2293140000 0.1217550000 1.2042940000 0.0070390000 127317266 0 1783590912 3.5040364265 4.0106835365 3.8736026287 272 1311867179.4949469566 0.0701247603 0.0620036228 0.0711863786 0.0066553359 2.3753770000 0.8881190000 0.2628840000 0.0000040000 1.2110630000 0.0070480000 127319420 0 1782829056 3.5040259361 4.0098180771 3.8732244968 273 1311867179.5307800770 0.0697057173 0.0620318356 0.0711863786 0.0066525942 3.8670510000 0.8655160000 0.3980300000 0.1221270000 1.2088020000 1.2664570000 127321670 0 1784467456 3.5044004917 4.0127272606 3.8731875420 274 1311867179.5627610683 0.0698849335 0.0620604965 0.0711863786 0.0066650240 2.4815070000 0.8729490000 0.3883390000 0.0000050000 1.2060470000 0.0070350000 127323856 0 1783345152 3.5029113293 4.0125675201 3.8733246326 275 1311867179.5946741104 0.0702680573 0.0620903422 0.0711863786 0.0066571164 2.4849940000 0.8676500000 0.2675920000 0.1220950000 1.2142830000 0.0071010000 127326042 0 1782448128 3.5008766651 4.0130333900 3.8735287189 276 1311867179.6306900978 0.0700639263 0.0621192320 0.0711863786 0.0066705427 2.5077390000 0.8794600000 0.3968230000 0.0000040000 1.2183270000 0.0070530000 127328260 0 1784111104 3.5012161732 4.0146770477 3.8734896183 277 1311867179.6625750065 0.0704395398 0.0621492692 0.0711863786 0.0066666131 3.7731150000 0.9083640000 0.2625140000 0.1221470000 1.2126670000 1.2603170000 127330478 0 1783083008 3.5008740425 4.0135555267 3.8736860752 278 1311867179.6946051121 0.0706238672 0.0621797534 0.0711863786 0.0066692109 2.3044190000 0.8795420000 0.1998100000 0.0000040000 1.2116280000 0.0071620000 127332632 0 1782177792 3.4992988110 4.0149316788 3.8739058971 279 1311867179.7309470177 0.0709346607 0.0622111330 0.0711863786 0.0066595103 2.6148730000 0.8806940000 0.3892910000 0.1229280000 1.2086530000 0.0070180000 127334914 0 1783967744 3.4992241859 4.0147366524 3.8741555214 280 1311867179.7627270222 0.0707417205 0.0622415994 0.0711863786 0.0066763060 2.3298730000 0.8763430000 0.2329010000 0.0000040000 1.2073830000 0.0070290000 127337100 0 1782812672 3.4982101917 4.0136308670 3.8739726543 281 1311867179.7948911190 0.0701245964 0.0622696527 0.0711863786 0.0066911951 3.7585710000 0.8790520000 0.2677290000 0.1221710000 1.2156800000 1.2674710000 127339254 0 1782071296 3.4985601902 4.0156521797 3.8737442493 282 1311867179.8307530880 0.0700729415 0.0622973240 0.0711863786 0.0066818755 2.4995980000 0.9011280000 0.3680190000 0.0000040000 1.2173180000 0.0070470000 127341536 0 1783803904 3.4989550114 4.0164289474 3.8739786148 283 1311867179.8627979755 0.0707459748 0.0623271779 0.0711863786 0.0066756825 2.6314020000 0.8802200000 0.4072260000 0.1222160000 1.2085710000 0.0070790000 127343722 0 1785454592 3.4962270260 4.0143051147 3.8743908405 284 1311867179.8948040009 0.0705882162 0.0623562660 0.0711863786 0.0066659780 2.4068600000 0.8733430000 0.2967380000 0.0000040000 1.2225720000 0.0070970000 127345908 0 1784627200 3.4971122742 4.0143866539 3.8745107651 285 1311867179.9309051037 0.0707476139 0.0623857093 0.0711863786 0.0066905940 3.8931770000 0.8771780000 0.4022330000 0.1225760000 1.2146220000 1.2702080000 127348158 0 1783721984 3.4960525036 4.0176906586 3.8750815392 286 1311867179.9635379314 0.0708090514 0.0624151616 0.0711863786 0.0066915643 2.4773560000 0.8867600000 0.3698380000 0.0000040000 1.2075140000 0.0070300000 127350376 0 1785352192 3.4951179028 4.0160098076 3.8751764297 287 1311867179.9958879948 0.0709253699 0.0624448139 0.0711863786 0.0066848912 2.5066880000 0.8660750000 0.2905330000 0.1222390000 1.2135750000 0.0070130000 127352530 0 1784360960 3.4932234287 4.0160760880 3.8754651546 288 1311867180.0309770107 0.0708275437 0.0624739206 0.0711863786 0.0066822418 2.4260740000 0.9087140000 0.2951430000 0.0000050000 1.2086630000 0.0071180000 127354780 0 1783603200 3.4938290119 4.0186562538 3.8760106564 289 1311867180.0626471043 0.0712405294 0.0625042549 0.0712405294 0.0066721609 3.8848590000 0.8850530000 0.3980360000 0.1227250000 1.2055710000 1.2672300000 127356966 0 1785327616 3.4927504063 4.0174455643 3.8762054443 290 1311867180.0947730541 0.0712796375 0.0625345148 0.0712796375 0.0066616252 2.5021350000 0.8816980000 0.3977150000 0.0000040000 1.2085590000 0.0070360000 127359120 0 1784500224 3.4898006916 4.0181822777 3.8759860992 291 1311867180.1307730675 0.0714791641 0.0625652524 0.0714791641 0.0066583250 2.4895090000 0.8823000000 0.2593010000 0.1226200000 1.2117990000 0.0070450000 127361370 0 1783595008 3.4921851158 4.0176863670 3.8759746552 292 1311867180.1636900902 0.0712374672 0.0625949518 0.0714791641 0.0066743604 2.5463400000 0.9214700000 0.4095640000 0.0000030000 1.2019600000 0.0071680000 127363620 0 1785200640 3.4945781231 4.0178666115 3.8757600784 293 1311867180.1949090958 0.0708652064 0.0626231779 0.0714791641 0.0066644727 3.8534760000 0.8954460000 0.3749340000 0.1227150000 1.2026470000 1.2505100000 127365742 0 1784246272 3.4949285984 4.0175843239 3.8749845028 294 1311867180.2308139801 0.0702605918 0.0626491555 0.0714791641 0.0066609303 2.3405530000 0.8994800000 0.2339830000 0.0000040000 1.1934290000 0.0071590000 127367960 0 1783341056 3.4963006973 4.0178918839 3.8739280701 295 1311867180.2637619972 0.0697905049 0.0626733635 0.0714791641 0.0066806784 2.6118100000 0.8862660000 0.4038410000 0.1222790000 1.1861090000 0.0070850000 127370178 0 1784979456 3.4967005253 4.0184087753 3.8731157780 296 1311867180.2947549820 0.0702841878 0.0626990757 0.0714791641 0.0066695860 2.4792540000 0.8731920000 0.4046780000 0.0000040000 1.1870920000 0.0070190000 127372332 0 1783844864 3.4951496124 4.0175504684 3.8730282784 297 1311867180.3308670521 0.0701545179 0.0627241782 0.0714791641 0.0066605120 3.8339830000 0.8754040000 0.4048960000 0.1233360000 1.1882020000 1.2356900000 127374582 0 1783103488 3.4951264858 4.0186462402 3.8725404739 298 1311867180.3658289909 0.0701373219 0.0627490546 0.0714791641 0.0066590369 2.3469060000 0.8721410000 0.2676460000 0.0000040000 1.1937060000 0.0070740000 127376800 0 1784700928 3.4949672222 4.0189867020 3.8720471859 299 1311867180.3964109421 0.0704332516 0.0627747542 0.0714791641 0.0066486877 2.5002180000 0.8826430000 0.3015250000 0.1226720000 1.1791080000 0.0070980000 127378986 0 1783730176 3.4965584278 4.0193867683 3.8720474243 300 1311867180.4309151173 0.0711931810 0.0628028156 0.0714791641 0.0066383873 2.4693380000 0.8724560000 0.4016080000 0.0000040000 1.1817600000 0.0071160000 127381204 0 1782579200 3.4935162067 4.0180454254 3.8717544079 301 1311867180.4670670033 0.0709882230 0.0628300097 0.0714791641 0.0066334471 3.8228150000 0.8940620000 0.4102650000 0.1223620000 1.1742080000 1.2156410000 127383454 0 1784311808 3.4944694042 4.0195255280 3.8714315891 302 1311867180.4947559834 0.0711935610 0.0628577036 0.0714791641 0.0066324796 2.4557690000 0.8775900000 0.3928020000 0.0000040000 1.1711380000 0.0071520000 127385544 0 1783484416 3.4958059788 4.0189471245 3.8713049889 303 1311867180.5308880806 0.0704903305 0.0628828937 0.0714791641 0.0066217816 2.3743720000 0.8722290000 0.1987990000 0.1219670000 1.1678040000 0.0070380000 127387826 0 1782579200 3.4983327389 4.0193724632 3.8709390163 304 1311867180.5629510880 0.0711098239 0.0629099560 0.0714791641 0.0066113939 2.3316030000 0.8822610000 0.2702600000 0.0000040000 1.1657370000 0.0071090000 127390012 0 1784311808 3.4972641468 4.0197186470 3.8713791370 305 1311867180.5946910381 0.0712663606 0.0629373541 0.0714791641 0.0066028915 3.7274250000 0.8773610000 0.3426060000 0.1221390000 1.1671480000 1.2110140000 127392198 0 1783484416 3.4970052242 4.0201096535 3.8715960979 306 1311867180.6308128834 0.0711064190 0.0629640504 0.0714791641 0.0065934507 2.4636110000 0.8732010000 0.4128160000 0.0000040000 1.1640240000 0.0070630000 127394448 0 1782321152 3.4983248711 4.0193262100 3.8717751503 307 1311867180.6640911102 0.0707783848 0.0629895042 0.0714791641 0.0065982712 2.3777780000 0.8755300000 0.1999650000 0.1222030000 1.1667770000 0.0070200000 127396634 0 1784184832 3.4989440441 4.0203289986 3.8719351292 308 1311867180.6957859993 0.0709815845 0.0630154525 0.0714791641 0.0065880886 2.3641960000 0.8904090000 0.3032140000 0.0000040000 1.1563290000 0.0070610000 127398820 0 1783341056 3.4998052120 4.0190720558 3.8722996712 309 1311867180.7309739590 0.0706700385 0.0630402246 0.0714791641 0.0065827493 3.7729860000 0.8755000000 0.4066450000 0.1223200000 1.1640120000 1.1979960000 127401070 0 1782452224 3.5007367134 4.0202670097 3.8722691536 310 1311867180.7650830746 0.0708261728 0.0630653406 0.0714791641 0.0065824873 2.4458370000 0.8809870000 0.3934800000 0.0000040000 1.1579020000 0.0070520000 127403288 0 1784057856 3.5024714470 4.0198459625 3.8723201752 311 1311867180.7949280739 0.0710616857 0.0630910523 0.0714791641 0.0065721606 2.3829610000 0.8820520000 0.2019560000 0.1224470000 1.1619260000 0.0071290000 127405410 0 1783095296 3.5027391911 4.0197758675 3.8726782799 312 1311867180.8309240341 0.0714126229 0.0631177240 0.0714791641 0.0065624800 2.2845910000 0.8814750000 0.2299110000 0.0000040000 1.1596410000 0.0070800000 127407692 0 1782206464 3.5029609203 4.0210223198 3.8731720448 313 1311867180.8652698994 0.0713148043 0.0631439128 0.0714791641 0.0065604989 3.7892790000 0.8835510000 0.4157050000 0.1222350000 1.1597840000 1.2016770000 127409910 0 1783709696 3.5035042763 4.0196413994 3.8732626438 314 1311867180.8966469765 0.0708898306 0.0631685813 0.0714791641 0.0065506291 2.4675730000 0.8755540000 0.4136640000 0.0000040000 1.1649530000 0.0070330000 127412096 0 1785454592 3.5057880878 4.0206503868 3.8730673790 315 1311867180.9306049347 0.0713415444 0.0631945272 0.0714791641 0.0065592388 2.3753940000 0.8807650000 0.1999390000 0.1221190000 1.1579980000 0.0070360000 127414314 0 1784078336 3.5050687790 4.0202732086 3.8733706474 316 1311867180.9631829262 0.0714593679 0.0632206818 0.0714791641 0.0065588878 2.3103860000 0.8866100000 0.2377770000 0.0000040000 1.1723790000 0.0070110000 127416500 0 1783357440 3.5056002140 4.0205998421 3.8732924461 317 1311867180.9948179722 0.0709480867 0.0632450585 0.0714791641 0.0065529513 3.6717310000 0.8821850000 0.2973320000 0.1222860000 1.1607890000 1.2027750000 127418654 0 1784979456 3.5097565651 4.0210680962 3.8736131191 318 1311867181.0308310986 0.0712566748 0.0632702522 0.0714791641 0.0065436797 2.3041380000 0.8932560000 0.2312340000 0.0000050000 1.1648990000 0.0071290000 127420904 0 1783844864 3.5109517574 4.0195341110 3.8738083839 319 1311867181.0627830029 0.0718868896 0.0632972636 0.0718868896 0.0065414974 2.4536020000 0.8864580000 0.2727620000 0.1223070000 1.1584770000 0.0070520000 127423122 0 1783087104 3.5126228333 4.0191888809 3.8741047382 320 1311867181.0948719978 0.0710262135 0.0633214166 0.0718868896 0.0065392980 2.4850040000 0.8937540000 0.4128510000 0.0000050000 1.1648710000 0.0071320000 127425308 0 1784713216 3.5154731274 4.0196313858 3.8740592003 321 1311867181.1311910152 0.0695164204 0.0633407157 0.0718868896 0.0065357192 3.6889000000 0.8987720000 0.3041930000 0.1227540000 1.1553010000 1.2003740000 127427558 0 1783320576 3.5210745335 4.0206923485 3.8734009266 322 1311867181.1629528999 0.0706486255 0.0633634110 0.0718868896 0.0065428760 2.4882770000 0.9073200000 0.4163780000 0.0000050000 1.1508950000 0.0071320000 127429744 0 1782325248 3.5206580162 4.0192360878 3.8737750053 323 1311867181.1972830296 0.0704919770 0.0633854809 0.0718868896 0.0065336805 2.5278650000 0.8959440000 0.3463260000 0.1228800000 1.1491080000 0.0071290000 127431962 0 1783812096 3.5217275620 4.0195884705 3.8735711575 324 1311867181.2342460155 0.0705028176 0.0634074480 0.0718868896 0.0065250565 2.5048560000 0.9262740000 0.4159570000 0.0000050000 1.1491490000 0.0070490000 127434244 0 1785589760 3.5244281292 4.0185875893 3.8733527660 325 1311867181.2629361153 0.0710874721 0.0634310788 0.0718868896 0.0065162321 3.7818710000 0.8867180000 0.4000970000 0.1227240000 1.1640650000 1.2008070000 127436366 0 1784479744 3.5248305798 4.0185236931 3.8736834526 326 1311867181.2948091030 0.0702549890 0.0634520111 0.0718868896 0.0065069558 2.2840600000 0.8850960000 0.2341020000 0.0000040000 1.1511810000 0.0070560000 127438520 0 1783590912 3.5283758640 4.0198593140 3.8734414577 327 1311867181.3317139149 0.0706134588 0.0634739115 0.0718868896 0.0065031392 2.3390100000 0.8803370000 0.1683230000 0.1222440000 1.1545620000 0.0071410000 127440802 0 1785327616 3.5280592442 4.0193576813 3.8734164238 328 1311867181.3626708984 0.0699939355 0.0634937897 0.0718868896 0.0065051256 2.4320970000 0.8905850000 0.3738880000 0.0000050000 1.1522920000 0.0070760000 127442956 0 1784352768 3.5316147804 4.0218920708 3.8737370968 329 1311867181.3948218822 0.0701221973 0.0635139368 0.0718868896 0.0064967964 3.6599820000 0.8967050000 0.3015030000 0.1224550000 1.1483650000 1.1842640000 127445142 0 1783484416 3.5316841602 4.0200629234 3.8735978603 330 1311867181.4308950901 0.0702664480 0.0635343989 0.0718868896 0.0064879633 2.3869470000 0.8880710000 0.3422020000 0.0000050000 1.1429880000 0.0071910000 127447328 0 1785094144 3.5328974724 4.0197558403 3.8737313747 331 1311867181.4628310204 0.0702592582 0.0635547157 0.0718868896 0.0064819753 2.4801480000 0.8968310000 0.3044590000 0.1229010000 1.1413400000 0.0071080000 127449514 0 1783967744 3.5357103348 4.0197248459 3.8742768764 332 1311867181.4963610172 0.0693966150 0.0635723118 0.0718868896 0.0064902392 2.3978810000 0.9022580000 0.3439460000 0.0000060000 1.1377860000 0.0071370000 127451732 0 1783209984 3.5391325951 4.0199351311 3.8742225170 333 1311867181.5359110832 0.0697183385 0.0635907684 0.0718868896 0.0064842663 3.5680570000 0.8934840000 0.2380240000 0.1222930000 1.1337480000 1.1739210000 127454014 0 1784856576 3.5403337479 4.0190968513 3.8742144108 334 1311867181.5671720505 0.0696615577 0.0636089444 0.0718868896 0.0064792633 2.4522100000 0.8906400000 0.4092830000 0.0000050000 1.1375720000 0.0071240000 127456168 0 1783861248 3.5411629677 4.0182433128 3.8736436367 335 1311867181.5948610306 0.0697783232 0.0636273604 0.0718868896 0.0064756678 2.5757750000 0.8945030000 0.4151480000 0.1223900000 1.1298970000 0.0070910000 127458258 0 1783205888 3.5423529148 4.0196623802 3.8738429546 336 1311867181.6313591003 0.0696374923 0.0636452477 0.0718868896 0.0064753982 2.2768410000 0.9319620000 0.1997690000 0.0000050000 1.1314300000 0.0071790000 127460540 0 1784971264 3.5449371338 4.0186576843 3.8736011982 337 1311867181.6628570557 0.0705503076 0.0636657375 0.0718868896 0.0064734422 3.5577970000 0.8965580000 0.2365520000 0.1221720000 1.1267990000 1.1682590000 127462726 0 1784119296 3.5444705486 4.0164065361 3.8733413219 338 1311867181.6949229240 0.0694634318 0.0636828905 0.0718868896 0.0064704176 2.3294260000 0.9006430000 0.2758390000 0.0000040000 1.1386940000 0.0072700000 127464880 0 1783611392 3.5478317738 4.0184378624 3.8728251457 339 1311867181.7310829163 0.0702183545 0.0637021691 0.0718868896 0.0064734518 2.5798330000 0.8999150000 0.4172870000 0.1222370000 1.1267350000 0.0071530000 127467130 0 1785249792 3.5501956940 4.0167517662 3.8726079464 340 1311867181.7634840012 0.0708466768 0.0637231824 0.0718868896 0.0064642494 2.3758510000 0.8934600000 0.3355470000 0.0000050000 1.1321380000 0.0071650000 127469348 0 1784602624 3.5485317707 4.0149950981 3.8722090721 341 1311867181.7948980331 0.0696458668 0.0637405509 0.0718868896 0.0064611570 3.5853360000 0.8848780000 0.2740480000 0.1224460000 1.1288300000 1.1684240000 127471470 0 1784094720 3.5532674789 4.0163588524 3.8714704514 342 1311867181.8308010101 0.0698034763 0.0637582788 0.0718868896 0.0064562392 2.4412870000 0.8931890000 0.4077620000 0.0000050000 1.1266210000 0.0071740000 127473720 0 1783222272 3.5544571877 4.0148940086 3.8714258671 343 1311867181.8627979755 0.0688616261 0.0637731574 0.0718868896 0.0064495939 2.3920220000 0.8935270000 0.2312140000 0.1223190000 1.1310960000 0.0071450000 127475938 0 1783095296 3.5571928024 4.0145840645 3.8711376190 344 1311867181.8949289322 0.0687644184 0.0637876668 0.0718868896 0.0064425941 2.4621590000 0.8997250000 0.4150040000 0.0000040000 1.1336730000 0.0071090000 127478092 0 1784709120 3.5596334934 4.0155181885 3.8713326454 345 1311867181.9307990074 0.0686639845 0.0638018011 0.0718868896 0.0064377426 3.6324960000 0.8954500000 0.3080400000 0.1224560000 1.1262870000 1.1727350000 127480374 0 1783967744 3.5607759953 4.0141935349 3.8708987236 346 1311867181.9629189968 0.0695439279 0.0638183968 0.0718868896 0.0064367075 2.3261650000 0.8846700000 0.3011330000 0.0000050000 1.1264260000 0.0071030000 127482560 0 1783476224 3.5599591732 4.0141634941 3.8714754581 347 1311867181.9955599308 0.0695094466 0.0638347976 0.0718868896 0.0064535547 2.4241240000 0.8875220000 0.2699830000 0.1222180000 1.1307270000 0.0070660000 127484746 0 1784979456 3.5618646145 4.0132145882 3.8722400665 348 1311867182.0320639610 0.0688997507 0.0638493520 0.0718868896 0.0064459227 2.4326780000 0.8839960000 0.4069310000 0.0000050000 1.1270940000 0.0070780000 127486996 0 1784229888 3.5643301010 4.0124568939 3.8722279072 349 1311867182.0629000664 0.0684057176 0.0638624075 0.0718868896 0.0064405707 3.7111960000 0.8736660000 0.4066480000 0.1219260000 1.1335260000 1.1685470000 127489182 0 1783738368 3.5668580532 4.0128588676 3.8723788261 350 1311867182.0948839188 0.0684908479 0.0638756316 0.0718868896 0.0064422254 2.2960990000 0.8797000000 0.2702160000 0.0000050000 1.1324150000 0.0070590000 127491336 0 1785499648 3.5687561035 4.0124826431 3.8725409508 351 1311867182.1314840317 0.0686116144 0.0638891245 0.0718868896 0.0064335023 2.4960350000 0.8782850000 0.3458090000 0.1220230000 1.1352330000 0.0071160000 127493618 0 1784619008 3.5710141659 4.0123615265 3.8730738163 352 1311867182.1629920006 0.0683908761 0.0639019135 0.0718868896 0.0064256912 2.4337910000 0.8759590000 0.4099580000 0.0000040000 1.1339500000 0.0070260000 127495804 0 1784090624 3.5722317696 4.0127096176 3.8731844425 353 1311867182.1994500160 0.0690448284 0.0639164827 0.0718868896 0.0064201127 3.6609030000 0.8754510000 0.3509900000 0.1219310000 1.1316150000 1.1732510000 127498022 0 1782968320 3.5726060867 4.0119662285 3.8736810684 354 1311867182.2307739258 0.0690866858 0.0639310878 0.0718868896 0.0064148096 2.4236800000 0.8698070000 0.4043150000 0.0000040000 1.1356550000 0.0070610000 127500176 0 1783091200 3.5743556023 4.0111670494 3.8741462231 355 1311867182.2629120350 0.0687745586 0.0639447314 0.0718868896 0.0064156458 2.5558340000 0.8851430000 0.4078920000 0.1221090000 1.1268580000 0.0070600000 127502394 0 1784836096 3.5773739815 4.0113167763 3.8744401932 356 1311867182.2973539829 0.0694988891 0.0639603329 0.0718868896 0.0064107769 2.2815880000 0.9146860000 0.2280440000 0.0000050000 1.1241280000 0.0070530000 127504612 0 1784111104 3.5772302151 4.0097756386 3.8747963905 357 1311867182.3308460712 0.0701914877 0.0639777871 0.0718868896 0.0064276954 3.5986420000 0.8832060000 0.2997750000 0.1217510000 1.1238280000 1.1631840000 127506798 0 1783857152 3.5772049427 4.0097441673 3.8754096031 358 1311867182.3629670143 0.0703897104 0.0639956975 0.0718868896 0.0064465520 2.2904740000 0.8766680000 0.2714020000 0.0000040000 1.1285630000 0.0070980000 127509016 0 1785634816 3.5781087875 4.0091614723 3.8758871555 359 1311867182.3990368843 0.0702203736 0.0640130365 0.0718868896 0.0064424454 2.4146010000 0.8847430000 0.2726720000 0.1221580000 1.1202400000 0.0070750000 127511234 0 1784709120 3.5800025463 4.0081896782 3.8760554790 360 1311867182.4308118820 0.0714920312 0.0640338115 0.0718868896 0.0064395932 2.2501330000 0.8732510000 0.2317700000 0.0000050000 1.1310900000 0.0071820000 127513420 0 1784487936 3.5790832043 4.0059204102 3.8763811588 361 1311867182.4629440308 0.0716144890 0.0640548106 0.0718868896 0.0064357631 3.6864850000 0.8769480000 0.3985340000 0.1220640000 1.1219300000 1.1593300000 127515638 0 1783726080 3.5797498226 4.0065774918 3.8761398792 362 1311867182.4969599247 0.0718756989 0.0640764152 0.0718868896 0.0064320269 2.2563390000 0.8862870000 0.2331290000 0.0000040000 1.1228660000 0.0071220000 127517824 0 1783590912 3.5826911926 4.0048513412 3.8761906624 363 1311867182.5309500694 0.0725732297 0.0640998224 0.0725732297 0.0064235482 2.3781920000 0.8867080000 0.2337690000 0.1215840000 1.1222750000 0.0071260000 127520042 0 1785225216 3.5826482773 4.0030469894 3.8756520748 364 1311867182.5629699230 0.0736134425 0.0641259587 0.0736134425 0.0064186014 2.2932730000 0.8837550000 0.2688380000 0.0000050000 1.1253040000 0.0073980000 127522228 0 1784360960 3.5822379589 4.0031943321 3.8752589226 365 1311867182.6036369801 0.0740990117 0.0641532822 0.0740990117 0.0064162272 3.5473230000 0.8702690000 0.2667300000 0.1214430000 1.1228780000 1.1591250000 127524542 0 1783816192 3.5811886787 4.0028376579 3.8738634586 366 1311867182.6308450699 0.0745337009 0.0641816440 0.0745337009 0.0064265733 2.4084460000 0.8750470000 0.3949740000 0.0000050000 1.1246040000 0.0070880000 127526632 0 1785597952 3.5818037987 4.0017862320 3.8733232021 367 1311867182.6635921001 0.0744841620 0.0642097162 0.0745337009 0.0064199259 2.3437310000 0.8499480000 0.2316760000 0.1217790000 1.1256230000 0.0070550000 127528850 0 1784872960 3.5831348896 4.0023365021 3.8732964993 368 1311867182.6970019341 0.0740894452 0.0642365633 0.0745337009 0.0064147989 2.3113780000 0.8665280000 0.3048830000 0.0000050000 1.1259240000 0.0070710000 127531036 0 1784745984 3.5866634846 4.0017275810 3.8726449013 369 1311867182.7330639362 0.0747203305 0.0642649746 0.0747203305 0.0064111560 3.5514180000 0.8647020000 0.2621930000 0.1213620000 1.1276830000 1.1678280000 127533286 0 1784201216 3.5872564316 4.0003352165 3.8719446659 370 1311867182.7631130219 0.0748182684 0.0642934970 0.0748182684 0.0064052664 2.2677640000 0.8616400000 0.2637280000 0.0000050000 1.1284390000 0.0070290000 127535376 0 1783980032 3.5900275707 4.0007472038 3.8720726967 371 1311867182.7970550060 0.0755834281 0.0643239281 0.0755834281 0.0063973906 2.3728600000 0.8703470000 0.2329470000 0.1213600000 1.1334520000 0.0070860000 127537626 0 1783185408 3.5905227661 3.9993250370 3.8717157841 372 1311867182.8306989670 0.0765390992 0.0643567646 0.0765390992 0.0063912295 2.2185770000 0.8477320000 0.2265100000 0.0000050000 1.1302810000 0.0070880000 127539812 0 1783078912 3.5907175541 3.9990806580 3.8714706898 373 1311867182.8641169071 0.0766246766 0.0643896544 0.0766246766 0.0063881438 3.4747370000 0.8469770000 0.1979790000 0.1211270000 1.1307070000 1.1710130000 127541998 0 1784856576 3.5917949677 3.9992833138 3.8713359833 374 1311867182.8969969749 0.0753926188 0.0644190741 0.0766246766 0.0063809637 2.3835830000 0.8469990000 0.3930740000 0.0000060000 1.1287980000 0.0069560000 127544216 0 1783988224 3.5957591534 3.9987547398 3.8712632656 375 1311867182.9318990707 0.0760120228 0.0644499887 0.0766246766 0.0063726324 2.4479300000 0.8577040000 0.3229080000 0.1213040000 1.1321190000 0.0069760000 127546434 0 1783230464 3.5970144272 3.9997971058 3.8715891838 376 1311867182.9630720615 0.0741845816 0.0644758785 0.0766246766 0.0063660130 2.3881820000 0.8599440000 0.3934690000 0.0000050000 1.1209450000 0.0070520000 127548620 0 1784868864 3.6022524834 3.9997179508 3.8716113567 377 1311867182.9983949661 0.0759164616 0.0645062249 0.0766246766 0.0063803646 3.4613600000 0.8639060000 0.1946220000 0.1213570000 1.1220710000 1.1513260000 127550838 0 1783308288 3.6012620926 3.9989545345 3.8720149994 378 1311867183.0308830738 0.0759839043 0.0645365891 0.0766246766 0.0063722768 2.2105140000 0.8802430000 0.2004970000 0.0000060000 1.1157360000 0.0070000000 127553024 0 1783222272 3.6030571461 3.9984862804 3.8723909855 379 1311867183.0628600121 0.0758047700 0.0645663205 0.0766246766 0.0063646677 2.5211290000 0.8644540000 0.4080480000 0.1211360000 1.1135660000 0.0070620000 127555242 0 1784999936 3.6057853699 3.9996001720 3.8728923798 380 1311867183.1000499725 0.0763577148 0.0645973505 0.0766246766 0.0063844005 2.2631040000 0.8659560000 0.2706180000 0.0000050000 1.1117360000 0.0070620000 127557460 0 1784074240 3.6063113213 3.9978222847 3.8732073307 381 1311867183.1344780922 0.0762659907 0.0646279768 0.0766246766 0.0063784533 3.6244390000 0.8628900000 0.3765530000 0.1219290000 1.1114160000 1.1445970000 127559710 0 1783857152 3.6080448627 3.9983744621 3.8735694885 382 1311867183.1673240662 0.0761307105 0.0646580887 0.0766246766 0.0063721031 2.3090500000 0.8589920000 0.3282260000 0.0000040000 1.1077690000 0.0070140000 127561928 0 1783095296 3.6098380089 3.9993977547 3.8739125729 383 1311867183.2004919052 0.0772518143 0.0646909705 0.0772518143 0.0063673138 2.4050370000 0.8694020000 0.2958310000 0.1212840000 1.1044260000 0.0070850000 127564114 0 1782968320 3.6099317074 3.9974646568 3.8746414185 384 1311867183.2311279774 0.0766025037 0.0647219901 0.0772518143 0.0063595975 2.2575850000 0.8699730000 0.2679210000 0.0000050000 1.1057440000 0.0071130000 127566268 0 1784582144 3.6127002239 3.9972147942 3.8748645782 385 1311867183.2633349895 0.0758345872 0.0647508540 0.0772518143 0.0063531155 3.6450720000 0.8759800000 0.4018000000 0.1211540000 1.1033790000 1.1348630000 127568486 0 1783693312 3.6152548790 3.9976632595 3.8749022484 386 1311867183.2991099358 0.0760403648 0.0647801014 0.0772518143 0.0063484155 2.2540810000 0.8668960000 0.2629980000 0.0000050000 1.1100500000 0.0070670000 127570704 0 1783603200 3.6160039902 3.9954478741 3.8748750687 387 1311867183.3320920467 0.0757629573 0.0648084809 0.0772518143 0.0063484228 2.5031100000 0.8603370000 0.3994050000 0.1225010000 1.1068790000 0.0071240000 127572922 0 1785233408 3.6178107262 3.9963264465 3.8748769760 388 1311867183.3695240021 0.0765669271 0.0648387862 0.0772518143 0.0063404196 2.3951520000 0.8616250000 0.4085140000 0.0000050000 1.1101410000 0.0070610000 127575204 0 1784324096 3.6182229519 3.9959425926 3.8751499653 389 1311867183.3986210823 0.0767118111 0.0648693081 0.0772518143 0.0063341565 3.4958330000 0.8611530000 0.2601190000 0.1209810000 1.1068150000 1.1397030000 127577326 0 1784373248 3.6187114716 3.9944155216 3.8748147488 390 1311867183.4311549664 0.0764073953 0.0648988929 0.0772518143 0.0063398086 2.3867720000 0.8588650000 0.4023680000 0.0000040000 1.1107470000 0.0070170000 127579512 0 1783316480 3.6207680702 3.9950914383 3.8748047352 391 1311867183.4667448997 0.0769762993 0.0649297814 0.0772518143 0.0063377306 2.3764440000 0.8702510000 0.2640190000 0.1213330000 1.1067060000 0.0070220000 127581762 0 1783349248 3.6222753525 3.9956903458 3.8751718998 392 1311867183.4988338947 0.0765514299 0.0649594285 0.0772518143 0.0063643341 2.3877100000 0.8617590000 0.4018490000 0.0000050000 1.1101390000 0.0070500000 127583980 0 1784836096 3.6241934299 3.9937286377 3.8751115799 393 1311867183.5321829319 0.0760363415 0.0649876140 0.0772518143 0.0063572301 3.4999520000 0.8647910000 0.2629280000 0.1210610000 1.1057730000 1.1375540000 127586166 0 1784107008 3.6261606216 3.9933400154 3.8752682209 394 1311867183.5661609173 0.0761358067 0.0650159089 0.0772518143 0.0063499382 2.2343520000 0.8834650000 0.2334950000 0.0000050000 1.1031870000 0.0071070000 127588384 0 1783984128 3.6281337738 3.9944496155 3.8756260872 395 1311867183.5985479355 0.0768218264 0.0650457973 0.0772518143 0.0063465857 2.3655610000 0.8672270000 0.2633890000 0.1210300000 1.0998240000 0.0070320000 127590570 0 1785597952 3.6286327839 3.9926629066 3.8755724430 396 1311867183.6310880184 0.0766985714 0.0650752235 0.0772518143 0.0063590002 2.3831840000 0.8590270000 0.4038310000 0.0000050000 1.1053150000 0.0070100000 127592756 0 1784709120 3.6306819916 3.9924676418 3.8759486675 397 1311867183.6649260521 0.0768172592 0.0651048004 0.0772518143 0.0063525486 3.6292000000 0.8715270000 0.3965310000 0.1208880000 1.0981890000 1.1348730000 127594974 0 1784598528 3.6330735683 3.9929697514 3.8766565323 398 1311867183.6993949413 0.0763110816 0.0651329569 0.0772518143 0.0063457282 2.2248790000 0.8773890000 0.2361150000 0.0000050000 1.0964090000 0.0070970000 127597224 0 1784111104 3.6360099316 3.9911544323 3.8770227432 399 1311867183.7308928967 0.0785394385 0.0651665571 0.0785394385 0.0063491962 2.4374140000 0.8695610000 0.3351010000 0.1218110000 1.0967280000 0.0070960000 127599346 0 1783984128 3.6346755028 3.9912374020 3.8776507378 400 1311867183.7676479816 0.0764560774 0.0651947809 0.0785394385 0.0063596206 2.3315930000 0.8833610000 0.3380920000 0.0000050000 1.0960150000 0.0071050000 127601628 0 1785597952 3.6399924755 3.9905805588 3.8779459000 401 1311867183.7971870899 0.0763771459 0.0652226671 0.0785394385 0.0063521305 3.6326760000 0.8707030000 0.4091000000 0.1210200000 1.0931480000 1.1306990000 127603750 0 1784725504 3.6416962147 3.9895694256 3.8782744408 402 1311867183.8309071064 0.0786506906 0.0652560702 0.0786506906 0.0063466568 2.2702760000 0.8589180000 0.3051460000 0.0000060000 1.0918650000 0.0070150000 127605936 0 1784627200 3.6402542591 3.9889824390 3.8791668415 403 1311867183.8655049801 0.0764341801 0.0652838074 0.0786506906 0.0063450861 2.5158110000 0.8760700000 0.4068480000 0.1209600000 1.0969750000 0.0070260000 127608154 0 1783865344 3.6452138424 3.9870166779 3.8789663315 404 1311867183.8970971107 0.0769754350 0.0653127471 0.0786506906 0.0063374815 2.3657480000 0.8649820000 0.3939910000 0.0000050000 1.0924750000 0.0070170000 127610308 0 1783582720 3.6457114220 3.9868936539 3.8793048859 405 1311867183.9314939976 0.0787972882 0.0653460423 0.0787972882 0.0063320604 3.4853610000 0.8665390000 0.2719230000 0.1209250000 1.0969310000 1.1219060000 127612558 0 1785217024 3.6445441246 3.9871571064 3.8799598217 406 1311867183.9658319950 0.0772074908 0.0653752577 0.0787972882 0.0063350210 2.3798810000 0.8649800000 0.4088060000 0.0000050000 1.0910020000 0.0070280000 127614744 0 1784492032 3.6479444504 3.9856169224 3.8799617290 407 1311867183.9966781139 0.0769214258 0.0654036266 0.0787972882 0.0063282533 2.5307580000 0.8947970000 0.4080930000 0.1209990000 1.0925550000 0.0070050000 127616930 0 1784217600 3.6497900486 3.9851651192 3.8801801205 408 1311867184.0309689045 0.0780088082 0.0654345217 0.0787972882 0.0063526607 2.1599410000 0.8532320000 0.2003450000 0.0000050000 1.0913010000 0.0071360000 127619148 0 1783476224 3.6501624584 3.9848527908 3.8808319569 409 1311867184.0647850037 0.0767021030 0.0654620708 0.0787972882 0.0063506667 3.5070130000 0.8579820000 0.3043870000 0.1262270000 1.0912420000 1.1198970000 127621366 0 1783205888 3.6530444622 3.9843947887 3.8810245991 410 1311867184.0968890190 0.0767647475 0.0654896383 0.0787972882 0.0063430769 2.3328430000 0.8584070000 0.3689840000 0.0000050000 1.0913100000 0.0070120000 127623520 0 1784852480 3.6542124748 3.9841487408 3.8814504147 411 1311867184.1312260628 0.0776467174 0.0655192175 0.0787972882 0.0063372498 2.5083610000 0.8677320000 0.4075060000 0.1219460000 1.0960550000 0.0070260000 127625738 0 1784111104 3.6545817852 3.9836604595 3.8820636272 412 1311867184.1650640965 0.0781270266 0.0655498190 0.0787972882 0.0063297225 2.1694410000 0.8608680000 0.2038360000 0.0000040000 1.0903900000 0.0070320000 127627924 0 1783836672 3.6553902626 3.9829823971 3.8824272156 413 1311867184.1969559193 0.0777743906 0.0655794185 0.0787972882 0.0063239009 3.6236270000 0.8702030000 0.4143800000 0.1209050000 1.0901910000 1.1199780000 127630142 0 1783095296 3.6578183174 3.9841716290 3.8827586174 414 1311867184.2309360504 0.0759311914 0.0656044227 0.0787972882 0.0063187902 2.3441500000 0.8698200000 0.3657440000 0.0000050000 1.0941890000 0.0070950000 127632360 0 1782800384 3.6630771160 3.9841327667 3.8832426071 415 1311867184.2681369781 0.0770068169 0.0656318984 0.0787972882 0.0063190046 2.5053260000 0.8721830000 0.4140920000 0.1210300000 1.0838810000 0.0070470000 127634642 0 1784606720 3.6628849506 3.9817605019 3.8831462860 416 1311867184.2983899117 0.0778736025 0.0656613256 0.0787972882 0.0063128127 2.3782600000 0.8721730000 0.4007080000 0.0000050000 1.0902080000 0.0070800000 127636796 0 1783697408 3.6638264656 3.9828195572 3.8839023113 417 1311867184.3314700127 0.0772423148 0.0656890977 0.0787972882 0.0063052640 3.5254100000 0.8738770000 0.3335040000 0.1210190000 1.0808680000 1.1088760000 127638982 0 1783611392 3.6668422222 3.9834134579 3.8842289448 418 1311867184.3697841167 0.0775325894 0.0657174314 0.0787972882 0.0063078985 2.2514920000 0.8776110000 0.2746730000 0.0000050000 1.0849730000 0.0070890000 127641264 0 1785380864 3.6683609486 3.9818644524 3.8840975761 419 1311867184.4000220299 0.0774135590 0.0657453458 0.0787972882 0.0063414380 2.2863090000 0.8699800000 0.1998110000 0.1208810000 1.0804010000 0.0070750000 127643418 0 1784471552 3.6720609665 3.9827346802 3.8846902847 420 1311867184.4310610294 0.0771699250 0.0657725472 0.0787972882 0.0063364215 2.2792100000 0.8837530000 0.2987790000 0.0000050000 1.0820690000 0.0071280000 127645604 0 1784348672 3.6751024723 3.9832291603 3.8853378296 421 1311867184.4655809402 0.0787721202 0.0658034250 0.0787972882 0.0063341797 3.5818300000 0.8750590000 0.4054210000 0.1211620000 1.0724830000 1.0995280000 127647822 0 1783586816 3.6746788025 3.9807889462 3.8851213455 422 1311867184.5037670135 0.0783353224 0.0658331215 0.0787972882 0.0063746247 2.2680390000 0.8767920000 0.2982900000 0.0000040000 1.0785240000 0.0070490000 127650104 0 1783332864 3.6774463654 3.9799141884 3.8842909336 423 1311867184.5310881138 0.0779361501 0.0658617338 0.0787972882 0.0063941238 2.4110700000 0.8896120000 0.3076770000 0.1220940000 1.0773620000 0.0072150000 127652226 0 1785110528 3.6805703640 3.9803535938 3.8837733269 424 1311867184.5682930946 0.0773016885 0.0658887149 0.0787972882 0.0063879563 2.3924420000 0.8917270000 0.4111410000 0.0000050000 1.0743750000 0.0070610000 127654508 0 1784242176 3.6841592789 3.9805340767 3.8832044601 425 1311867184.6018071175 0.0773956254 0.0659157900 0.0787972882 0.0063809953 3.5936160000 0.8772540000 0.4057610000 0.1209570000 1.0745250000 1.1077480000 127656694 0 1783316480 3.6851837635 3.9791178703 3.8824949265 426 1311867184.6367399693 0.0798783973 0.0659485660 0.0798783973 0.0063777915 2.1601360000 0.8734010000 0.1967300000 0.0000050000 1.0757040000 0.0071110000 127658944 0 1785110528 3.6847226620 3.9797551632 3.8833558559 427 1311867184.6662440300 0.0769907087 0.0659744258 0.0798783973 0.0063955811 2.4825640000 0.8651250000 0.4074640000 0.1209050000 1.0737520000 0.0070660000 127661066 0 1784242176 3.6906738281 3.9786775112 3.8831133842 428 1311867184.6994929314 0.0777799562 0.0660020089 0.0798783973 0.0063905705 2.2786180000 0.8866640000 0.3000340000 0.0000050000 1.0772700000 0.0072260000 127663316 0 1783742464 3.6915121078 3.9772150517 3.8833057880 429 1311867184.7359158993 0.0774554238 0.0660287068 0.0798783973 0.0063901487 3.5286300000 0.8714760000 0.3340860000 0.1210330000 1.0822030000 1.1119020000 127665502 0 1785483264 3.6951096058 3.9782063961 3.8837428093 430 1311867184.7690689564 0.0792948604 0.0660595583 0.0798783973 0.0063940283 2.3719280000 0.8708110000 0.4110160000 0.0000050000 1.0747580000 0.0070210000 127667752 0 1784369152 3.6950600147 3.9759757519 3.8847045898 431 1311867184.8001279831 0.0784182325 0.0660882327 0.0798783973 0.0063947735 2.4214030000 0.8700300000 0.3323950000 0.1210050000 1.0833920000 0.0070680000 127669906 0 1783443456 3.6986711025 3.9758036137 3.8851222992 432 1311867184.8348441124 0.0787127167 0.0661174561 0.0798783973 0.0063880194 2.3641620000 0.8663120000 0.4072580000 0.0000050000 1.0762580000 0.0070120000 127672092 0 1785221120 3.7012991905 3.9759602547 3.8862059116 433 1311867184.8690660000 0.0763235167 0.0661410267 0.0798783973 0.0063827287 3.5866460000 0.8751700000 0.4056470000 0.1208390000 1.0765000000 1.1001980000 127674310 0 1784115200 3.7067830563 3.9748194218 3.8866474628 434 1311867184.9055209160 0.0756338388 0.0661628995 0.0798783973 0.0063770826 2.3717950000 0.8762420000 0.4087920000 0.0000050000 1.0721540000 0.0071020000 127676496 0 1783357440 3.7106904984 3.9745442867 3.8875875473 435 1311867184.9332280159 0.0762152448 0.0661860083 0.0798783973 0.0063712647 2.5050220000 0.8832080000 0.4180640000 0.1209710000 1.0683790000 0.0071360000 127678586 0 1784979456 3.7132871151 3.9752781391 3.8893496990 436 1311867184.9656410217 0.0762460381 0.0662090818 0.0798783973 0.0063698126 2.3237490000 0.8748430000 0.3717250000 0.0000050000 1.0619190000 0.0071020000 127680772 0 1784094720 3.7153027058 3.9737632275 3.8905284405 437 1311867184.9983251095 0.0755984262 0.0662305677 0.0798783973 0.0063664774 3.5705540000 0.8768680000 0.4091560000 0.1262320000 1.0628710000 1.0878350000 127682990 0 1783353344 3.7187004089 3.9727323055 3.8914811611 438 1311867185.0360550880 0.0741068199 0.0662485500 0.0798783973 0.0063594035 2.3606050000 0.8722060000 0.4133030000 0.0000050000 1.0607270000 0.0070190000 127685240 0 1785106432 3.7243063450 3.9727237225 3.8928964138 439 1311867185.0652348995 0.0721166134 0.0662619169 0.0798783973 0.0063574602 2.4329710000 0.8964120000 0.3416060000 0.1207890000 1.0588370000 0.0071150000 127687394 0 1784221696 3.7295477390 3.9707834721 3.8939261436 440 1311867185.0991280079 0.0736696869 0.0662787528 0.0798783973 0.0063542610 2.3288030000 0.8852000000 0.3694250000 0.0000050000 1.0595640000 0.0071320000 127689612 0 1783083008 3.7302815914 3.9720463753 3.8955464363 441 1311867185.1360778809 0.0740590915 0.0662963952 0.0798783973 0.0063505268 3.4198660000 0.8841660000 0.2686670000 0.1212940000 1.0554000000 1.0830670000 127691862 0 1784844288 3.7328426838 3.9717035294 3.8973250389 442 1311867185.1648709774 0.0737437829 0.0663132445 0.0798783973 0.0063446529 2.3626340000 0.8739310000 0.4144880000 0.0000050000 1.0588970000 0.0071240000 127694016 0 1783975936 3.7361648083 3.9709029198 3.8989801407 443 1311867185.2000720501 0.0727368444 0.0663277448 0.0798783973 0.0063378250 2.3075700000 0.8802780000 0.2391680000 0.1205920000 1.0529380000 0.0071040000 127696202 0 1782960128 3.7412488461 3.9708290100 3.9004666805 444 1311867185.2342920303 0.0731747672 0.0663431660 0.0798783973 0.0063377147 2.1502420000 0.8886720000 0.2002770000 0.0000050000 1.0468200000 0.0071980000 127698452 0 1784565760 3.7446076870 3.9708447456 3.9025239944 445 1311867185.2663950920 0.0716266707 0.0663550390 0.0798783973 0.0063321298 3.4068520000 0.8942120000 0.2716700000 0.1208650000 1.0433690000 1.0684000000 127700670 0 1783463936 3.7491385937 3.9679386616 3.9035677910 446 1311867185.2970550060 0.0717554018 0.0663671475 0.0798783973 0.0063434664 2.1466830000 0.8813090000 0.1992470000 0.0000040000 1.0514830000 0.0070230000 127702824 0 1782304768 3.7519295216 3.9690377712 3.9051954746 447 1311867185.3360140324 0.0718309432 0.0663793707 0.0798783973 0.0063363658 2.4779120000 0.8918600000 0.4109230000 0.1206610000 1.0399370000 0.0071820000 127705106 0 1784078336 3.7552437782 3.9683182240 3.9069006443 448 1311867185.3681778908 0.0713962615 0.0663905691 0.0798783973 0.0063296873 2.2868950000 0.8837830000 0.3451850000 0.0000050000 1.0435680000 0.0070540000 127707324 0 1785581568 3.7584586143 3.9668521881 3.9079613686 449 1311867185.4036509991 0.0711481869 0.0664011652 0.0798783973 0.0063252539 3.4221920000 0.8843920000 0.3033760000 0.1208300000 1.0399720000 1.0649980000 127709542 0 1784623104 3.7616147995 3.9668722153 3.9090118408 450 1311867185.4386389256 0.0726945847 0.0664151505 0.0798783973 0.0063213778 2.3539480000 0.8849590000 0.4114010000 0.0000040000 1.0430070000 0.0071040000 127711760 0 1783865344 3.7627067566 3.9676105976 3.9105901718 451 1311867185.4655449390 0.0712022781 0.0664257650 0.0798783973 0.0063159261 2.5020350000 0.9279220000 0.4094860000 0.1205930000 1.0295830000 0.0071500000 127713850 0 1785581568 3.7674479485 3.9655978680 3.9113924503 452 1311867185.5013909340 0.0694491267 0.0664324539 0.0798783973 0.0063341703 2.2092460000 0.8874900000 0.2687440000 0.0000050000 1.0375510000 0.0070610000 127716100 0 1784733696 3.7722086906 3.9645466805 3.9115722179 453 1311867185.5336329937 0.0708509758 0.0664422078 0.0798783973 0.0063571684 3.5241920000 0.8856860000 0.4222190000 0.1204360000 1.0312150000 1.0570590000 127718286 0 1783857152 3.7735726833 3.9659476280 3.9126882553 454 1311867185.5666799545 0.0708741397 0.0664519697 0.0798783973 0.0063504071 2.3509580000 0.8961890000 0.4119800000 0.0000050000 1.0273490000 0.0071100000 127720504 0 1782689792 3.7767329216 3.9646339417 3.9135217667 455 1311867185.5970540047 0.0698647574 0.0664594704 0.0798783973 0.0063488505 2.4633100000 0.8914540000 0.4069930000 0.1205130000 1.0294160000 0.0071070000 127722658 0 1782218752 3.7802033424 3.9632306099 3.9137408733 456 1311867185.6329469681 0.0715228990 0.0664705744 0.0798783973 0.0063726564 2.2396150000 0.8836240000 0.3099190000 0.0000040000 1.0315920000 0.0071070000 127724908 0 1783959552 3.7821779251 3.9651839733 3.9146540165 457 1311867185.6664180756 0.0696999952 0.0664776410 0.0798783973 0.0063798636 3.5027400000 0.8912700000 0.4087370000 0.1202230000 1.0253810000 1.0497520000 127727094 0 1785487360 3.7879180908 3.9635462761 3.9153833389 458 1311867185.6973390579 0.0694918782 0.0664842223 0.0798783973 0.0063730669 2.1438620000 0.9028020000 0.2017180000 0.0000050000 1.0237700000 0.0070550000 127729280 0 1784496128 3.7904682159 3.9625279903 3.9160521030 459 1311867185.7351899147 0.0696756244 0.0664911752 0.0798783973 0.0063717791 2.3134130000 0.9184110000 0.2375260000 0.1204060000 1.0223580000 0.0071440000 127731530 0 1783586816 3.7945432663 3.9645483494 3.9176692963 460 1311867185.7649769783 0.0701315627 0.0664990891 0.0798783973 0.0063686664 2.3350400000 0.8980680000 0.4090950000 0.0000050000 1.0132140000 0.0071190000 127733716 0 1785348096 3.7964370251 3.9620554447 3.9188969135 461 1311867185.7989649773 0.0701654777 0.0665070422 0.0798783973 0.0063742538 3.4894460000 0.8936700000 0.4118460000 0.1204290000 1.0130450000 1.0418700000 127735902 0 1784221696 3.7994267941 3.9610493183 3.9196717739 462 1311867185.8327999115 0.0696488172 0.0665138426 0.0798783973 0.0063684277 2.3355390000 0.8977510000 0.4128250000 0.0000050000 1.0102340000 0.0071510000 127738152 0 1783730176 3.8031439781 3.9614434242 3.9206578732 463 1311867185.8649098873 0.0694471896 0.0665201781 0.0798783973 0.0063624840 2.3787930000 0.8966080000 0.3410040000 0.1203280000 1.0062320000 0.0071830000 127740338 0 1785475072 3.8057367802 3.9599831104 3.9216580391 464 1311867185.9030420780 0.0689892471 0.0665254994 0.0798783973 0.0063576972 2.3508090000 0.9030020000 0.4261250000 0.0000050000 1.0059950000 0.0070790000 127742588 0 1784369152 3.8085401058 3.9596157074 3.9223368168 465 1311867185.9396789074 0.0704178959 0.0665338701 0.0798783973 0.0063556204 3.3097490000 0.9037350000 0.2397840000 0.1202540000 1.0032320000 1.0348530000 127744870 0 1783480320 3.8090829849 3.9595131874 3.9241411686 466 1311867185.9650609493 0.0694232285 0.0665400705 0.0798783973 0.0063670195 2.3323530000 0.9070450000 0.4113280000 0.0000040000 0.9992950000 0.0071760000 127746896 0 1785229312 3.8117842674 3.9570970535 3.9249858856 467 1311867186.0039470196 0.0686742440 0.0665446404 0.0798783973 0.0063621755 2.3807720000 0.9284000000 0.3126220000 0.1202890000 1.0037950000 0.0071360000 127749210 0 1784123392 3.8148813248 3.9551174641 3.9259517193 468 1311867186.0396919250 0.0703537166 0.0665527795 0.0798783973 0.0063751141 2.1592370000 0.9079570000 0.2401170000 0.0000050000 0.9963710000 0.0071900000 127751460 0 1783336960 3.8150017262 3.9570138454 3.9273815155 469 1311867186.0653240681 0.0693512410 0.0665587464 0.0798783973 0.0063791865 3.2847650000 0.9120920000 0.2371000000 0.1209410000 0.9892100000 1.0179140000 127753582 0 1784963072 3.8168644905 3.9541966915 3.9280545712 470 1311867186.1047339439 0.0697185695 0.0665654694 0.0798783973 0.0063725208 2.1555260000 0.9094900000 0.2416740000 0.0000050000 0.9887220000 0.0071470000 127755864 0 1783971840 3.8172519207 3.9527499676 3.9286165237 471 1311867186.1361179352 0.0691479892 0.0665709524 0.0798783973 0.0063678825 2.4537740000 0.9046090000 0.4183760000 0.1203150000 0.9956110000 0.0071350000 127758018 0 1782931456 3.8198335171 3.9523932934 3.9291849136 472 1311867186.1649448872 0.0696698800 0.0665775180 0.0798783973 0.0063616498 2.1079090000 0.9033770000 0.2033840000 0.0000050000 0.9864710000 0.0070860000 127760172 0 1784840192 3.8204617500 3.9512650967 3.9297094345 473 1311867186.2044749260 0.0684438348 0.0665814637 0.0798783973 0.0063560287 3.4700820000 0.9123600000 0.4234230000 0.1207890000 0.9934270000 1.0115370000 127762486 0 1783586816 3.8237180710 3.9500615597 3.9297742844 474 1311867186.2359659672 0.0690072104 0.0665865813 0.0798783973 0.0063527008 2.3403340000 0.9076470000 0.4252960000 0.0000050000 0.9926120000 0.0071100000 127764640 0 1782681600 3.8246331215 3.9501059055 3.9305355549 475 1311867186.2674899101 0.0697826818 0.0665933099 0.0798783973 0.0063467481 2.4494880000 0.9049530000 0.4229850000 0.1203810000 0.9864260000 0.0071890000 127766826 0 1784606720 3.8256688118 3.9482870102 3.9312441349 476 1311867186.3030838966 0.0690515563 0.0665984743 0.0798783973 0.0063412028 2.1190670000 0.9143670000 0.2089540000 0.0000060000 0.9800430000 0.0071200000 127769076 0 1783332864 3.8287842274 3.9482178688 3.9318556786 477 1311867186.3349270821 0.0694672987 0.0666044886 0.0798783973 0.0063356341 3.4499610000 0.9272830000 0.4179360000 0.1203890000 0.9802460000 0.9962960000 127771230 0 1782579200 3.8305900097 3.9486677647 3.9329998493 478 1311867186.3670160770 0.0681793392 0.0666077833 0.0798783973 0.0063405507 2.1781870000 0.9176540000 0.2769760000 0.0000050000 0.9682970000 0.0075220000 127773384 0 1784205312 3.8337850571 3.9458143711 3.9334731102 479 1311867186.4019849300 0.0688429698 0.0666124496 0.0798783973 0.0063447746 2.2457690000 0.9274870000 0.2059450000 0.1260450000 0.9706840000 0.0071840000 127775602 0 1783083008 3.8348000050 3.9464833736 3.9345428944 480 1311867186.4360210896 0.0688332245 0.0666170762 0.0798783973 0.0063436971 2.2900230000 0.9313220000 0.3813860000 0.0000050000 0.9623870000 0.0071610000 127777820 0 1782349824 3.8377661705 3.9470336437 3.9362955093 481 1311867186.4659481049 0.0681462660 0.0666202554 0.0798783973 0.0063414502 3.2970130000 0.9228460000 0.3125780000 0.1205880000 0.9587900000 0.9746030000 127779974 0 1783959552 3.8400151730 3.9445641041 3.9371855259 482 1311867186.5031139851 0.0683846623 0.0666239160 0.0798783973 0.0063365902 2.1396320000 0.9243060000 0.2480670000 0.0000050000 0.9526270000 0.0071450000 127782256 0 1785454592 3.8410890102 3.9430613518 3.9380099773 483 1311867186.5363171101 0.0686288178 0.0666280670 0.0798783973 0.0063337143 2.4336010000 0.9582320000 0.3899560000 0.1204600000 0.9490090000 0.0072500000 127784442 0 1784205312 3.8436167240 3.9448480606 3.9395940304 484 1311867186.5651130676 0.0689429566 0.0666328498 0.0798783973 0.0063332015 2.3126470000 0.9346660000 0.4232300000 0.0000040000 0.9397400000 0.0072690000 127786596 0 1783468032 3.8445916176 3.9424984455 3.9402902126 485 1311867186.6014220715 0.0697119534 0.0666391985 0.0798783973 0.0063282181 3.4040410000 0.9336760000 0.4412040000 0.1204190000 0.9404870000 0.9606340000 127788846 0 1785114624 3.8456218243 3.9417378902 3.9405612946 486 1311867186.6362628937 0.0699535608 0.0666460181 0.0798783973 0.0063217237 2.1706060000 0.9273680000 0.2870170000 0.0000050000 0.9402560000 0.0073030000 127791064 0 1783570432 3.8473806381 3.9416921139 3.9407284260 487 1311867186.6650478840 0.0700063333 0.0666529182 0.0798783973 0.0063174055 2.4394070000 0.9428110000 0.4229670000 0.1203630000 0.9382540000 0.0072490000 127793186 0 1782833152 3.8493752480 3.9421091080 3.9408655167 488 1311867186.7043809891 0.0694965571 0.0666587453 0.0798783973 0.0063355454 2.2258600000 0.9255960000 0.3478330000 0.0000050000 0.9376040000 0.0071540000 127795532 0 1784471552 3.8519034386 3.9417984486 3.9404654503 489 1311867186.7337749004 0.0701132938 0.0666658098 0.0798783973 0.0063423111 3.3964980000 0.9325380000 0.4390460000 0.1204370000 0.9375000000 0.9584780000 127797654 0 1783607296 3.8528392315 3.9432358742 3.9404227734 490 1311867186.7673180103 0.0706481338 0.0666739370 0.0798783973 0.0063373642 2.1445940000 0.9500010000 0.2472090000 0.0000050000 0.9322440000 0.0072280000 127799872 0 1782579200 3.8542892933 3.9442634583 3.9406535625 491 1311867186.8047299385 0.0695569292 0.0666798087 0.0798783973 0.0063408727 2.2596370000 0.9432410000 0.2488690000 0.1204690000 0.9321040000 0.0073250000 127802154 0 1784311808 3.8569064140 3.9425826073 3.9397366047 492 1311867186.8340749741 0.0709157512 0.0666884183 0.0798783973 0.0063426019 2.1051100000 0.9428570000 0.2134780000 0.0000050000 0.9330630000 0.0072630000 127804276 0 1783484416 3.8571410179 3.9453682899 3.9397208691 493 1311867186.8775999546 0.0710924938 0.0666973515 0.0798783973 0.0063364911 3.3298230000 0.9564470000 0.3648150000 0.1207820000 0.9300720000 0.9497680000 127806654 0 1782333440 3.8600029945 3.9455621243 3.9398310184 494 1311867186.9052100182 0.0706351697 0.0667053228 0.0798783973 0.0063342371 2.2511570000 0.9492690000 0.3589780000 0.0000050000 0.9278880000 0.0072490000 127808744 0 1783828480 3.8627743721 3.9465005398 3.9398107529 495 1311867186.9334239960 0.0711075142 0.0667142161 0.0798783973 0.0063282598 2.4691820000 0.9665500000 0.4397800000 0.1208490000 0.9269730000 0.0073070000 127810930 0 1785589760 3.8643059731 3.9474153519 3.9396359921 496 1311867186.9663379192 0.0714965537 0.0667238579 0.0798783973 0.0063281586 2.2258260000 0.9926280000 0.2922440000 0.0000050000 0.9248980000 0.0073550000 127813084 0 1784627200 3.8670995235 3.9493794441 3.9399321079 497 1311867187.0017139912 0.0722778738 0.0667350330 0.0798783973 0.0063312434 3.3465540000 0.9829700000 0.3683600000 0.1209040000 0.9220240000 0.9443390000 127815238 0 1783468032 3.8685724735 3.9490065575 3.9396138191 498 1311867187.0336461067 0.0712211952 0.0667440414 0.0798783973 0.0063274325 2.2057390000 0.9742520000 0.2907280000 0.0000050000 0.9256910000 0.0073680000 127817424 0 1784946688 3.8728315830 3.9495553970 3.9391076565 499 1311867187.0749349594 0.0734530240 0.0667574862 0.0798783973 0.0063310927 2.4859280000 0.9856090000 0.4412390000 0.1207720000 0.9222440000 0.0073240000 127819770 0 1783992320 3.8738496304 3.9526357651 3.9396173954 500 1311867187.1016030312 0.0731708258 0.0667703129 0.0798783973 0.0063264630 2.3079050000 0.9976400000 0.3701180000 0.0000040000 0.9248270000 0.0073540000 127821892 0 1782849536 3.8767173290 3.9529581070 3.9397518635 501 1311867187.1342070103 0.0737986714 0.0667843416 0.0798783973 0.0063274382 3.2163730000 0.9945060000 0.2177220000 0.1208710000 0.9280680000 0.9473320000 127824078 0 1784344576 3.8779258728 3.9501214027 3.9393067360 502 1311867187.1710209846 0.0740938783 0.0667989024 0.0798783973 0.0063329826 2.3739650000 0.9806350000 0.4428640000 0.0000050000 0.9343820000 0.0073820000 127826328 0 1783336960 3.8812949657 3.9522147179 3.9395003319 503 1311867187.2041370869 0.0741549805 0.0668135268 0.0798783973 0.0063314297 2.3099190000 0.9850940000 0.2540760000 0.1210550000 0.9342970000 0.0073790000 127828546 0 1782325248 3.8853068352 3.9539952278 3.9393613338 504 1311867187.2331659794 0.0736890733 0.0668271688 0.0798783973 0.0063303364 2.2027290000 0.9894190000 0.2554160000 0.0000040000 0.9426520000 0.0073470000 127830700 0 1783930880 3.8867270947 3.9511089325 3.9385015965 505 1311867187.2707629204 0.0729447380 0.0668392828 0.0798783973 0.0063366191 3.3923390000 0.9912560000 0.3673380000 0.1207340000 0.9420450000 0.9632910000 127832950 0 1782976512 3.8904223442 3.9541156292 3.9381120205 506 1311867187.3015060425 0.0720693246 0.0668496188 0.0798783973 0.0063392573 2.3539340000 0.9869630000 0.3991920000 0.0000040000 0.9524740000 0.0073320000 127835136 0 1782075392 3.8925397396 3.9534761906 3.9376721382 507 1311867187.3336570263 0.0724925324 0.0668607488 0.0798783973 0.0063344304 2.3186330000 0.9877800000 0.2532590000 0.1210260000 0.9413430000 0.0074140000 127837290 0 1783828480 3.8921937943 3.9513881207 3.9369277954 508 1311867187.3707590103 0.0716702342 0.0668702163 0.0798783973 0.0063291178 2.3891190000 0.9814530000 0.4440220000 0.0000050000 0.9484640000 0.0073550000 127839572 0 1785495552 3.8948090076 3.9517526627 3.9364607334 509 1311867187.4033529758 0.0718232319 0.0668799472 0.0798783973 0.0063271440 3.4699330000 0.9948260000 0.4452980000 0.1211460000 0.9379410000 0.9617950000 127841790 0 1784754176 3.8956544399 3.9522542953 3.9357683659 510 1311867187.4335899353 0.0702410713 0.0668865376 0.0798783973 0.0063284370 2.2910260000 0.9982110000 0.3379460000 0.0000060000 0.9395150000 0.0074130000 127843944 0 1784492032 3.8990733624 3.9512426853 3.9350547791 511 1311867187.4763159752 0.0723622218 0.0668972533 0.0798783973 0.0063318177 2.3121840000 0.9903220000 0.2528810000 0.1211710000 0.9315910000 0.0074560000 127846290 0 1783730176 3.8992681503 3.9518346786 3.9345543385 512 1311867187.5056400299 0.0726913214 0.0669085698 0.0798783973 0.0063288291 2.3978060000 0.9962560000 0.4502270000 0.0000060000 0.9358630000 0.0073910000 127848412 0 1783603200 3.9012587070 3.9503538609 3.9336600304 513 1311867187.5342190266 0.0719836950 0.0669184628 0.0798783973 0.0063245815 3.4505020000 0.9875340000 0.4499570000 0.1209370000 0.9305270000 0.9534280000 127891526 0 1785212928 3.9054887295 3.9503571987 3.9328064919 514 1311867187.5709679127 0.0722299814 0.0669287965 0.0798783973 0.0063188606 2.1995100000 0.9909750000 0.2591740000 0.0000040000 0.9330530000 0.0073430000 127977744 0 1784619008 3.9089033604 3.9506688118 3.9318206310 515 1311867187.6045789719 0.0733290538 0.0669412242 0.0798783973 0.0063391653 2.3898750000 0.9821350000 0.3384870000 0.1210540000 0.9327300000 0.0074110000 127979994 0 1784492032 3.9097518921 3.9514000416 3.9304516315 516 1311867187.6353919506 0.0729525685 0.0669528741 0.0798783973 0.0063345397 2.4007900000 0.9881630000 0.4586980000 0.0000050000 0.9376300000 0.0073400000 127982148 0 1783730176 3.9124829769 3.9497997761 3.9289903641 517 1311867187.6707689762 0.0727529749 0.0669640929 0.0798783973 0.0063397900 3.4574270000 0.9824880000 0.4475740000 0.1210850000 0.9373060000 0.9608060000 127984366 0 1783476224 3.9161260128 3.9516010284 3.9280166626 518 1311867187.7035770416 0.0716300458 0.0669731005 0.0798783973 0.0063366641 2.3922690000 0.9953080000 0.4410580000 0.0000050000 0.9405490000 0.0074240000 127986584 0 1785090048 3.9209311008 3.9520161152 3.9272589684 519 1311867187.7345480919 0.0722061545 0.0669831835 0.0798783973 0.0063429872 2.5195600000 0.9969810000 0.4434770000 0.1214550000 0.9413510000 0.0073780000 127988610 0 1784365056 3.9205129147 3.9493129253 3.9257698059 520 1311867187.7707819939 0.0720249414 0.0669928791 0.0798783973 0.0063465047 2.2062680000 0.9957790000 0.2524380000 0.0000040000 0.9425600000 0.0073930000 127990860 0 1784115200 3.9231510162 3.9524331093 3.9250223637 521 1311867187.8017508984 0.0714677200 0.0670014681 0.0798783973 0.0063439246 3.4838890000 0.9917300000 0.4385290000 0.1215330000 0.9459780000 0.9772500000 127993046 0 1783320576 3.9265396595 3.9524929523 3.9240822792 522 1311867187.8339610100 0.0720615014 0.0670111616 0.0798783973 0.0063396732 2.3976490000 0.9838250000 0.4500340000 0.0000050000 0.9482490000 0.0073990000 127995232 0 1783222272 3.9273443222 3.9522459507 3.9231462479 523 1311867187.8708090782 0.0717755780 0.0670202714 0.0798783973 0.0063395653 2.3367080000 0.9896070000 0.2558740000 0.1215080000 0.9543400000 0.0074210000 127997482 0 1784709120 3.9302353859 3.9538650513 3.9225342274 524 1311867187.9038810730 0.0725520924 0.0670308283 0.0798783973 0.0063402862 2.3864030000 0.9809210000 0.4396050000 0.0000040000 0.9495980000 0.0073620000 127999732 0 1783980032 3.9313266277 3.9541416168 3.9218611717 525 1311867187.9363000393 0.0702938437 0.0670370436 0.0798783973 0.0063360918 3.4708450000 0.9808210000 0.4372180000 0.1218100000 0.9507330000 0.9720770000 128001886 0 1783857152 3.9370744228 3.9543814659 3.9209783077 526 1311867187.9713420868 0.0705452636 0.0670437132 0.0798783973 0.0063363172 2.4210560000 0.9871970000 0.4670280000 0.0000050000 0.9514340000 0.0073860000 128004136 0 1785487360 3.9392528534 3.9530405998 3.9196057320 527 1311867188.0047569275 0.0710536614 0.0670513222 0.0798783973 0.0063543119 2.5239560000 0.9846120000 0.4508000000 0.1216250000 0.9504930000 0.0073870000 128006354 0 1784578048 3.9422051907 3.9543457031 3.9185595512 528 1311867188.0333108902 0.0713772923 0.0670595154 0.0798783973 0.0063599034 2.3649110000 0.9880590000 0.4102390000 0.0000040000 0.9510130000 0.0073290000 128008476 0 1784090624 3.9450018406 3.9553115368 3.9177739620 529 1311867188.0698699951 0.0697091967 0.0670645242 0.0798783973 0.0063558837 3.4359030000 0.9932260000 0.3743320000 0.1219800000 0.9564860000 0.9809150000 128010694 0 1783312384 3.9504175186 3.9529230595 3.9164073467 530 1311867188.1088800430 0.0710365921 0.0670720187 0.0798783973 0.0063543421 2.2836270000 0.9868550000 0.3285070000 0.0000050000 0.9526860000 0.0073400000 128013040 0 1783205888 3.9516503811 3.9532873631 3.9147913456 531 1311867188.1359970570 0.0694757923 0.0670765456 0.0798783973 0.0063599246 2.5087820000 0.9795340000 0.4418570000 0.1217770000 0.9502390000 0.0074100000 128015130 0 1784852480 3.9551560879 3.9556455612 3.9136726856 532 1311867188.1703350544 0.0707148761 0.0670833845 0.0798783973 0.0063577242 2.3891030000 0.9806590000 0.4402280000 0.0000050000 0.9519210000 0.0073140000 128017348 0 1784111104 3.9578368664 3.9539854527 3.9123556614 533 1311867188.2026720047 0.0709364861 0.0670906136 0.0798783973 0.0063581350 3.4877430000 0.9963390000 0.4417550000 0.1220400000 0.9500820000 0.9692910000 128019566 0 1783865344 3.9597206116 3.9534533024 3.9108157158 534 1311867188.2352449894 0.0689718649 0.0670941365 0.0798783973 0.0063663486 2.3920220000 0.9788440000 0.4369540000 0.0000050000 0.9608210000 0.0073000000 128021720 0 1782964224 3.9655005932 3.9550192356 3.9098825455 535 1311867188.2706460953 0.0703957602 0.0671003078 0.0798783973 0.0063646282 2.5080870000 0.9751110000 0.4346910000 0.1223380000 0.9603870000 0.0073380000 128023970 0 1782820864 3.9676365852 3.9549806118 3.9088025093 536 1311867188.3047339916 0.0708165094 0.0671072410 0.0798783973 0.0063590753 2.2819080000 0.9670710000 0.3243150000 0.0000050000 0.9751580000 0.0073480000 128026220 0 1784582144 3.9706652164 3.9553585052 3.9076023102 537 1311867188.3398799896 0.0720287934 0.0671164059 0.0798783973 0.0063539889 3.5040330000 0.9588180000 0.4330820000 0.1231540000 0.9788720000 1.0005590000 128028470 0 1783693312 3.9723751545 3.9561309814 3.9065055847 538 1311867188.3718800545 0.0730967969 0.0671275219 0.0798783973 0.0063590772 2.3864700000 0.9523700000 0.4353860000 0.0000050000 0.9832380000 0.0072800000 128030624 0 1783476224 3.9741115570 3.9589464664 3.9061005116 539 1311867188.4054470062 0.0717781410 0.0671361501 0.0798783973 0.0063636864 2.5061880000 0.9439000000 0.4396720000 0.1219780000 0.9853030000 0.0072470000 128032810 0 1785085952 3.9787364006 3.9587907791 3.9055202007 540 1311867188.4398789406 0.0715174675 0.0671442637 0.0798783973 0.0063620788 2.2842770000 0.9531850000 0.3205250000 0.0000050000 0.9942290000 0.0072270000 128035060 0 1784492032 3.9818050861 3.9582295418 3.9047026634 541 1311867188.4724500179 0.0727686137 0.0671546599 0.0798783973 0.0063676167 3.3455470000 0.9579360000 0.2478560000 0.1222080000 0.9930740000 1.0161770000 128037246 0 1784238080 3.9837126732 3.9615981579 3.9043509960 542 1311867188.5049159527 0.0722097084 0.0671639865 0.0798783973 0.0063693755 2.2809010000 0.9548860000 0.3196620000 0.0000040000 0.9900670000 0.0072570000 128039432 0 1783328768 3.9874887466 3.9618952274 3.9040577412 543 1311867188.5389990807 0.0718396157 0.0671725973 0.0798783973 0.0063702202 2.3684080000 0.9484950000 0.2888680000 0.1220580000 0.9934640000 0.0072610000 128041682 0 1783058432 3.9900066853 3.9610071182 3.9032783508 544 1311867188.5723888874 0.0737870559 0.0671847562 0.0798783973 0.0063911934 2.2226370000 0.9519750000 0.2568910000 0.0000050000 0.9983410000 0.0072130000 128043868 0 1784856576 3.9912922382 3.9655420780 3.9031503201 545 1311867188.6045958996 0.0729087442 0.0671952589 0.0798783973 0.0063861873 3.5268940000 0.9655470000 0.4295560000 0.1222030000 0.9880200000 1.0124800000 128046054 0 1783840768 3.9954609871 3.9653053284 3.9031338692 546 1311867188.6398339272 0.0726706833 0.0672052872 0.0798783973 0.0063847073 2.2310930000 0.9732940000 0.2511870000 0.0000050000 0.9910550000 0.0073210000 128048240 0 1783603200 3.9981486797 3.9635562897 3.9028069973 547 1311867188.6715080738 0.0744014233 0.0672184428 0.0798783973 0.0063899990 2.3341510000 0.9506750000 0.2489910000 0.1222240000 0.9967670000 0.0072610000 128050458 0 1785225216 3.9987714291 3.9658219814 3.9021391869 548 1311867188.7038300037 0.0745513067 0.0672318240 0.0798783973 0.0063922234 2.2001000000 0.9693690000 0.2136360000 0.0000050000 1.0006640000 0.0072530000 128052644 0 1784352768 4.0008835793 3.9643201828 3.9013485909 549 1311867188.7393829823 0.0743345097 0.0672447615 0.0798783973 0.0064039149 3.5860400000 0.9698200000 0.4305460000 0.1220480000 1.0132560000 1.0419840000 128054862 0 1783816192 4.0040192604 3.9636824131 3.9003043175 550 1311867188.7721049786 0.0774077848 0.0672632397 0.0798783973 0.0064010653 2.2909450000 0.9613630000 0.2821680000 0.0000050000 1.0319530000 0.0072270000 128057080 0 1785618432 4.0039544106 3.9660618305 3.8991551399 551 1311867188.8045220375 0.0771788731 0.0672812354 0.0798783973 0.0063957279 2.5209770000 0.9558690000 0.3889110000 0.1219220000 1.0379060000 0.0072740000 128059298 0 1784856576 4.0088920593 3.9674673080 3.8983128071 552 1311867188.8402431011 0.0780570284 0.0673007568 0.0798783973 0.0063908257 2.4515510000 0.9655870000 0.4231530000 0.0000040000 1.0472270000 0.0072870000 128061516 0 1784602624 4.0121307373 3.9661548138 3.8974134922 553 1311867188.8705990314 0.0809970424 0.0673255240 0.0809970424 0.0063931039 3.5262100000 0.9826350000 0.2458250000 0.1220650000 1.0678850000 1.0986070000 128063670 0 1783730176 4.0119099617 3.9675016403 3.8963253498 554 1311867188.9016311169 0.0818194300 0.0673516863 0.0818194300 0.0063906140 2.4326860000 0.9453080000 0.3852920000 0.0000050000 1.0865830000 0.0071730000 128065856 0 1783586816 4.0150938034 3.9701571465 3.8952136040 555 1311867188.9401769638 0.0823198780 0.0673786560 0.0823198780 0.0063895498 2.5309850000 0.9397190000 0.3512650000 0.1218880000 1.1026980000 0.0072760000 128068170 0 1785253888 4.0188751221 3.9689199924 3.8941147327 556 1311867188.9709990025 0.0831128433 0.0674069549 0.0831128433 0.0063896489 2.4734210000 0.9267480000 0.4184180000 0.0000050000 1.1119370000 0.0070940000 128070292 0 1784360960 4.0208454132 3.9684612751 3.8933110237 557 1311867189.0052258968 0.0832080022 0.0674353230 0.0832080022 0.0063852796 3.6379320000 0.9574310000 0.2747670000 0.1217090000 1.1279570000 1.1476390000 128072542 0 1784238080 4.0249638557 3.9698343277 3.8927347660 558 1311867189.0400099754 0.0825484321 0.0674624075 0.0832080022 0.0063856293 2.3828740000 0.9227160000 0.3124910000 0.0000050000 1.1314240000 0.0071480000 128074728 0 1783459840 4.0303015709 3.9689815044 3.8927035332 559 1311867189.0724329948 0.0813495219 0.0674872502 0.0832080022 0.0063830196 2.5271950000 0.9374030000 0.3088520000 0.1218180000 1.1434760000 0.0071290000 128076978 0 1783107584 4.0346102715 3.9680583477 3.8928277493 560 1311867189.1026360989 0.0803164542 0.0675101595 0.0832080022 0.0063788007 2.4828670000 0.9073230000 0.4099090000 0.0000050000 1.1503790000 0.0071060000 128079132 0 1784606720 4.0392622948 3.9688918591 3.8934764862 561 1311867189.1417639256 0.0794246122 0.0675313974 0.0832080022 0.0063732169 3.6257280000 0.9590580000 0.2040570000 0.1217050000 1.1523870000 1.1793410000 128081446 0 1783848960 4.0439887047 3.9691259861 3.8942797184 562 1311867189.1717920303 0.0803463683 0.0675541998 0.0832080022 0.0063695348 2.4026510000 0.9133320000 0.3108310000 0.0000050000 1.1630180000 0.0070090000 128083600 0 1783332864 4.0440163612 3.9686462879 3.8949530125 563 1311867189.2019069195 0.0794098377 0.0675752578 0.0832080022 0.0063661572 2.6186840000 0.9059090000 0.4183350000 0.1216180000 1.1575150000 0.0070210000 128085754 0 1784999936 4.0480093956 3.9689774513 3.8961770535 564 1311867189.2390630245 0.0794836730 0.0675963720 0.0832080022 0.0063612517 2.5223830000 0.9168700000 0.4210240000 0.0000050000 1.1682580000 0.0070200000 128088004 0 1784221696 4.0502505302 3.9686520100 3.8971080780 565 1311867189.2722640038 0.0790409297 0.0676166279 0.0832080022 0.0063573981 3.6517580000 0.9384840000 0.2384850000 0.1219330000 1.1588730000 1.1855660000 128090190 0 1783717888 4.0526952744 3.9676306248 3.8979108334 566 1311867189.3046789169 0.0796621367 0.0676379097 0.0832080022 0.0063522311 2.3556790000 0.9103700000 0.2704800000 0.0000050000 1.1594790000 0.0070130000 128092408 0 1785364480 4.0542740822 3.9668202400 3.8988211155 567 1311867189.3397970200 0.0778762624 0.0676559668 0.0832080022 0.0063615792 2.4461600000 0.9125430000 0.2366620000 0.1216140000 1.1589760000 0.0070760000 128094626 0 1784238080 4.0583887100 3.9652626514 3.8994626999 568 1311867189.3720359802 0.0781750903 0.0676744863 0.0832080022 0.0063901984 2.4956690000 0.9121610000 0.4052740000 0.0000050000 1.1626150000 0.0070060000 128096812 0 1783861248 4.0613832474 3.9647831917 3.8999037743 569 1311867189.4056949615 0.0785431191 0.0676935876 0.0832080022 0.0063881368 3.7445720000 0.9018060000 0.3539280000 0.1216740000 1.1631440000 1.1956620000 128099030 0 1785360384 4.0641565323 3.9653298855 3.9012105465 570 1311867189.4405019283 0.0778698698 0.0677114408 0.0832080022 0.0063923357 2.3347860000 0.9119590000 0.2425650000 0.0000050000 1.1638380000 0.0070930000 128101248 0 1784332288 4.0681147575 3.9631381035 3.9018251896 571 1311867189.4729130268 0.0775718018 0.0677287093 0.0832080022 0.0063873839 2.5172740000 0.9102070000 0.3036390000 0.1217490000 1.1662210000 0.0070950000 128103466 0 1783861248 4.0722880363 3.9611208439 3.9021189213 572 1311867189.5060400963 0.0782850981 0.0677471646 0.0832080022 0.0063852554 2.4945200000 0.9037570000 0.4086290000 0.0000060000 1.1668180000 0.0070320000 128105652 0 1785483264 4.0750784874 3.9616982937 3.9024646282 573 1311867189.5394289494 0.0769362003 0.0677632013 0.0832080022 0.0063800143 3.7157200000 0.9040720000 0.3114860000 0.1213750000 1.1736110000 1.1956510000 128107838 0 1784086528 4.0800747871 3.9592065811 3.9022550583 574 1311867189.5720269680 0.0774781182 0.0677801262 0.0832080022 0.0063766997 2.4906930000 0.8953210000 0.4069550000 0.0000050000 1.1728690000 0.0070030000 128110056 0 1783345152 4.0821518898 3.9567172527 3.9013309479 575 1311867189.6112909317 0.0781697556 0.0677981951 0.0832080022 0.0063732641 2.6294470000 0.9046100000 0.4053580000 0.1214110000 1.1826930000 0.0069810000 128112338 0 1784958976 4.0869221687 3.9568798542 3.9011459351 576 1311867189.6424219608 0.0789817348 0.0678176110 0.0832080022 0.0063695863 2.5202040000 0.9081940000 0.4107360000 0.0000050000 1.1849670000 0.0069820000 128114524 0 1783836672 4.0897183418 3.9564130306 3.9010407925 577 1311867189.6728401184 0.0784941465 0.0678361145 0.0832080022 0.0063643575 3.6935230000 0.9379840000 0.2372450000 0.1221500000 1.1790400000 1.2085260000 128116710 0 1783103488 4.0935983658 3.9545741081 3.9007275105 578 1311867189.7065870762 0.0803975686 0.0678578472 0.0832080022 0.0063635674 2.4277110000 0.9126550000 0.3095460000 0.0000060000 1.1901510000 0.0069920000 128118896 0 1784819712 4.0958533287 3.9542169571 3.9009313583 579 1311867189.7401719093 0.0802807137 0.0678793029 0.0832080022 0.0063590602 2.4618640000 0.9176900000 0.2363640000 0.1216530000 1.1695040000 0.0070410000 128121114 0 1783971840 4.1009345055 3.9546210766 3.9020333290 580 1311867189.7729759216 0.0822950676 0.0679041577 0.0832080022 0.0063553799 2.3519530000 0.9234260000 0.2410390000 0.0000050000 1.1717880000 0.0070610000 128123300 0 1782849536 4.1019902229 3.9543907642 3.9027404785 581 1311867189.8073968887 0.0808274001 0.0679264008 0.0832080022 0.0063533302 3.8348230000 0.9344480000 0.4177980000 0.1224310000 1.1639220000 1.1878150000 128125518 0 1784471552 4.1067533493 3.9525682926 3.9034564495 582 1311867189.8405311108 0.0823121145 0.0679511185 0.0832080022 0.0063512101 2.4967300000 0.9378200000 0.3832630000 0.0000050000 1.1592690000 0.0070650000 128127704 0 1783607296 4.1087241173 3.9528787136 3.9043052197 583 1311867189.8713529110 0.0813989416 0.0679741851 0.0832080022 0.0063474144 2.4264770000 0.9288620000 0.2047360000 0.1216630000 1.1556020000 0.0071480000 128129890 0 1782579200 4.1131777763 3.9519538879 3.9051415920 584 1311867189.9102680683 0.0817744583 0.0679978157 0.0832080022 0.0063474800 2.4169700000 0.9319890000 0.3113210000 0.0000040000 1.1580730000 0.0071120000 128132172 0 1784311808 4.1155943871 3.9501087666 3.9050538540 585 1311867189.9402260780 0.0817155689 0.0680212648 0.0832080022 0.0063432017 3.7137700000 0.9260220000 0.3214870000 0.1219960000 1.1520390000 1.1828920000 128134358 0 1783472128 4.1188006401 3.9503738880 3.9052119255 586 1311867189.9727621078 0.0809749067 0.0680433700 0.0832080022 0.0063378459 2.3684930000 0.9263920000 0.2751170000 0.0000050000 1.1513730000 0.0071090000 128136544 0 1782575104 4.1235499382 3.9507849216 3.9056267738 587 1311867190.0107009411 0.0811552256 0.0680657071 0.0832080022 0.0063358373 2.6570170000 0.9388810000 0.4288190000 0.1218780000 1.1519380000 0.0070700000 128138794 0 1784311808 4.1269659996 3.9494400024 3.9055862427 588 1311867190.0402929783 0.0813070163 0.0680882263 0.0832080022 0.0063314228 2.5241440000 0.9297390000 0.4272540000 0.0000040000 1.1507760000 0.0070900000 128140948 0 1783476224 4.1300458908 3.9491949081 3.9056506157 589 1311867190.0719039440 0.0812793821 0.0681106222 0.0832080022 0.0063265779 3.8486890000 0.9647730000 0.4268740000 0.1222160000 1.1540770000 1.1721410000 128143134 0 1783349248 4.1331415176 3.9485046864 3.9055242538 590 1311867190.1096539497 0.0890262127 0.0681460723 0.0890262127 0.0063400663 2.4545150000 0.9339470000 0.3480740000 0.0000050000 1.1568820000 0.0071440000 128145416 0 1784963072 4.1254973412 3.9478247166 3.9038331509 591 1311867190.1396369934 0.0896881893 0.0681825226 0.0896881893 0.0063370639 2.4844280000 0.9424580000 0.2416680000 0.1220100000 1.1617890000 0.0071690000 128147602 0 1784238080 4.1277890205 3.9484467506 3.9032762051 592 1311867190.1706380844 0.0896793827 0.0682188349 0.0896881893 0.0063444914 2.3912830000 0.9308170000 0.2781070000 0.0000040000 1.1666370000 0.0071880000 128149724 0 1784111104 4.1305298805 3.9473176003 3.9030845165 593 1311867190.2096021175 0.0900652707 0.0682556754 0.0900652707 0.0063393311 3.8610950000 0.9400530000 0.4106200000 0.1221510000 1.1767200000 1.2021980000 128152038 0 1783185408 4.1322989464 3.9457476139 3.9016129971 594 1311867190.2394330502 0.0898011029 0.0682919472 0.0900652707 0.0063415619 2.3679120000 0.9199540000 0.2389570000 0.0000050000 1.1932440000 0.0071060000 128154160 0 1782931456 4.1359453201 3.9472301006 3.9009845257 595 1311867190.2714810371 0.0892402828 0.0683271544 0.0900652707 0.0063441929 2.6497250000 0.9143270000 0.4070420000 0.1218020000 1.1910440000 0.0070840000 128156378 0 1784729600 4.1394858360 3.9467713833 3.9005622864 596 1311867190.3072700500 0.0902382880 0.0683639181 0.0902382880 0.0063398091 2.4096000000 0.9451660000 0.2394700000 0.0000050000 1.2085350000 0.0070700000 128158628 0 1783967744 4.1410393715 3.9463374615 3.8999905586 597 1311867190.3414731026 0.0902629867 0.0684005999 0.0902629867 0.0063375634 3.8039450000 0.9126490000 0.3407100000 0.1221710000 1.1957240000 1.2240540000 128160846 0 1783590912 4.1444067955 3.9469401836 3.9002070427 598 1311867190.3716828823 0.0893852040 0.0684356913 0.0902629867 0.0063378251 2.3745620000 0.9193710000 0.2432320000 0.0000060000 1.1963530000 0.0071330000 128163000 0 1785352192 4.1487016678 3.9481215477 3.9006323814 599 1311867190.4101090431 0.0909069553 0.0684732059 0.0909069553 0.0063373277 2.4570340000 0.9195130000 0.2056110000 0.1225160000 1.1929050000 0.0070630000 128165250 0 1784602624 4.1494097710 3.9470906258 3.9004096985 600 1311867190.4394960403 0.0913444087 0.0685113246 0.0913444087 0.0063347463 2.3385540000 0.9234990000 0.2036630000 0.0000050000 1.1955930000 0.0070610000 128167468 0 1784094720 4.1522521973 3.9487359524 3.9013371468 601 1311867190.4708199501 0.0915504321 0.0685496592 0.0915504321 0.0063307974 3.8739430000 0.9198990000 0.4128060000 0.1218900000 1.1889240000 1.2218330000 128169590 0 1785745408 4.1547589302 3.9480922222 3.9020743370 602 1311867190.5097529888 0.0915550813 0.0685878742 0.0915550813 0.0063262194 2.5276570000 0.9245660000 0.3912070000 0.0000050000 1.1952450000 0.0070880000 128171936 0 1784602624 4.1568617821 3.9467277527 3.9021921158 603 1311867190.5405189991 0.0926280767 0.0686277418 0.0926280767 0.0063288032 2.6743410000 0.9213790000 0.4184230000 0.1218270000 1.1967980000 0.0070420000 128174058 0 1784242176 4.1589512825 3.9478757381 3.9027571678 604 1311867190.5708439350 0.0928226188 0.0686677996 0.0928226188 0.0063246772 2.3771560000 0.9310960000 0.2406610000 0.0000050000 1.1889150000 0.0070730000 128176212 0 1783463936 4.1611962318 3.9471616745 3.9034802914 605 1311867190.6067750454 0.0928489044 0.0687077683 0.0928489044 0.0063198257 3.7775720000 0.9502720000 0.2806110000 0.1218080000 1.1974670000 1.2186840000 128178462 0 1782956032 4.1635146141 3.9460177422 3.9035854340 606 1311867190.6389939785 0.0929670706 0.0687478002 0.0929670706 0.0063158515 2.3897140000 0.9312420000 0.2484000000 0.0000050000 1.1944360000 0.0071210000 128180680 0 1784602624 4.1663455963 3.9467895031 3.9043142796 607 1311867190.6723659039 0.0922827870 0.0687865728 0.0929670706 0.0063118057 2.5119380000 0.9332790000 0.2437060000 0.1220250000 1.1962890000 0.0070850000 128182866 0 1783332864 4.1699652672 3.9451298714 3.9050781727 608 1311867190.7114980221 0.0926766172 0.0688258657 0.0929670706 0.0063089481 2.4425750000 0.9415400000 0.2858030000 0.0000050000 1.1993540000 0.0070860000 128185148 0 1782841344 4.1725263596 3.9452490807 3.9057893753 609 1311867190.7392649651 0.0923706368 0.0688645270 0.0929670706 0.0063040789 3.7565650000 0.9356950000 0.2765080000 0.1220980000 1.1936510000 1.2200330000 128187238 0 1784590336 4.1748437881 3.9449815750 3.9062566757 610 1311867190.7751801014 0.0925798416 0.0689034046 0.0929670706 0.0062996443 2.3908590000 0.9619920000 0.2083910000 0.0000040000 1.2038790000 0.0071380000 128189488 0 1783599104 4.1771264076 3.9452285767 3.9068019390 611 1311867190.8070900440 0.0931174606 0.0689430348 0.0931174606 0.0062957995 2.6864560000 0.9370170000 0.4208070000 0.1224510000 1.1902560000 0.0070900000 128191706 0 1782579200 4.1789450645 3.9447066784 3.9075663090 612 1311867190.8414280415 0.0917943344 0.0689803735 0.0931174606 0.0062980395 2.4409260000 0.9420850000 0.2865080000 0.0000050000 1.1966010000 0.0070980000 128193924 0 1784328192 4.1826076508 3.9431695938 3.9083268642 613 1311867190.8739249706 0.0935303196 0.0690204224 0.0935303196 0.0062944396 3.7172480000 0.9458720000 0.2455190000 0.1222990000 1.1841940000 1.2097830000 128196110 0 1783226368 4.1829037666 3.9424500465 3.9088726044 614 1311867190.9076139927 0.0937383696 0.0690606796 0.0937383696 0.0062896961 2.5674630000 0.9597710000 0.4040440000 0.0000050000 1.1877080000 0.0071020000 128198328 0 1782448128 4.1852164268 3.9425616264 3.9096496105 615 1311867190.9393599033 0.0923069715 0.0690984785 0.0937383696 0.0062866261 2.4785550000 0.9453270000 0.2129510000 0.1223710000 1.1821330000 0.0071960000 128200482 0 1784078336 4.1887993813 3.9404399395 3.9103987217 616 1311867190.9741609097 0.0919505283 0.0691355760 0.0937383696 0.0062823538 2.5256670000 0.9713760000 0.3492370000 0.0000050000 1.1884080000 0.0070960000 128202732 0 1782956032 4.1915130615 3.9395160675 3.9105219841 617 1311867191.0085949898 0.0929877982 0.0691742343 0.0937383696 0.0062869676 3.7894990000 0.9346350000 0.3243610000 0.1218710000 1.1843980000 1.2153800000 128204950 0 1782448128 4.1938714981 3.9414677620 3.9115679264 618 1311867191.0396919250 0.0929645747 0.0692127300 0.0937383696 0.0062829942 2.3860990000 0.9436160000 0.2429250000 0.0000050000 1.1837380000 0.0072290000 128207136 0 1784184832 4.1962547302 3.9412813187 3.9125056267 619 1311867191.0764329433 0.0925800502 0.0692504801 0.0937383696 0.0062804311 2.5240390000 0.9434070000 0.2491160000 0.1217520000 1.1931590000 0.0071890000 128209386 0 1783336960 4.1980757713 3.9376435280 3.9126524925 620 1311867191.1103041172 0.0936739966 0.0692898729 0.0937383696 0.0062864343 2.4354650000 0.9479590000 0.2822100000 0.0000060000 1.1892450000 0.0071100000 128211604 0 1782177792 4.2008309364 3.9387423992 3.9138576984 621 1311867191.1388139725 0.0927613601 0.0693276692 0.0937383696 0.0062945268 3.7715200000 0.9482330000 0.2803720000 0.1221120000 1.1963290000 1.2157310000 128213758 0 1783947264 4.2044272423 3.9383778572 3.9148883820 622 1311867191.1742820740 0.0935871303 0.0693666715 0.0937383696 0.0062906397 2.4495730000 0.9499860000 0.2886300000 0.0000050000 1.1942440000 0.0072230000 128215976 0 1783107584 4.2058100700 3.9370098114 3.9152283669 623 1311867191.2077920437 0.0934992731 0.0694054077 0.0937383696 0.0062857976 2.5409000000 0.9581720000 0.2509010000 0.1222890000 1.1936000000 0.0071400000 128218194 0 1781948416 4.2095284462 3.9377994537 3.9163002968 624 1311867191.2408421040 0.0943972170 0.0694454586 0.0943972170 0.0062817080 2.4137990000 0.9595380000 0.2469560000 0.0000050000 1.1914580000 0.0071670000 128220412 0 1783590912 4.2113823891 3.9376502037 3.9170157909 625 1311867191.2769579887 0.0951140821 0.0694865284 0.0951140821 0.0062784540 3.7387800000 0.9621450000 0.2491880000 0.1220220000 1.1870840000 1.2096080000 128222630 0 1785327616 4.2134742737 3.9369065762 3.9175543785 626 1311867191.3085029125 0.0952425674 0.0695276723 0.0952425674 0.0062786924 2.3747050000 0.9498930000 0.2112190000 0.0000050000 1.1967620000 0.0072020000 128224720 0 1784352768 4.2165732384 3.9381284714 3.9184145927 627 1311867191.3404779434 0.0955408961 0.0695691607 0.0955408961 0.0062745960 2.5669130000 0.9606360000 0.2814870000 0.1218250000 1.1868910000 0.0072280000 128226906 0 1783328768 4.2188572884 3.9378223419 3.9191672802 628 1311867191.3794629574 0.0956405103 0.0696106755 0.0956405103 0.0062708916 2.5000640000 0.9656890000 0.3267250000 0.0000050000 1.1915970000 0.0072480000 128229220 0 1785126912 4.2204022408 3.9353380203 3.9195554256 629 1311867191.4091579914 0.0952310413 0.0696514074 0.0956405103 0.0062673250 3.7663910000 0.9588240000 0.2791460000 0.1219850000 1.1869190000 1.2097940000 128231342 0 1783947264 4.2232670784 3.9349822998 3.9202265739 630 1311867191.4415969849 0.0945552588 0.0696909374 0.0956405103 0.0062630218 2.4158040000 0.9586770000 0.2512730000 0.0000040000 1.1897380000 0.0071560000 128233528 0 1783726080 4.2273945808 3.9361088276 3.9213542938 631 1311867191.4775309563 0.0952529162 0.0697314476 0.0956405103 0.0062634438 2.5714750000 0.9565120000 0.2849790000 0.1219680000 1.1919910000 0.0072340000 128235746 0 1785470976 4.2279944420 3.9342164993 3.9214973450 632 1311867191.5075590611 0.0952567235 0.0697718357 0.0956405103 0.0062593712 2.5090720000 0.9716340000 0.3279790000 0.0000040000 1.1925350000 0.0071890000 128237868 0 1784745984 4.2302913666 3.9353077412 3.9222548008 633 1311867191.5390620232 0.0950404480 0.0698117546 0.0956405103 0.0062544560 3.8004400000 0.9842740000 0.2781140000 0.1237900000 1.1890720000 1.2161190000 128240054 0 1784487936 4.2322182655 3.9344072342 3.9227814674 634 1311867191.5764698982 0.0950355679 0.0698515397 0.0956405103 0.0062507077 2.4983940000 0.9592880000 0.3315270000 0.0000040000 1.1905210000 0.0072720000 128242304 0 1783992320 4.2347159386 3.9339306355 3.9237546921 635 1311867191.6118669510 0.0959446579 0.0698926313 0.0959446579 0.0062779124 2.7240770000 0.9634720000 0.4343770000 0.1227380000 1.1873700000 0.0072560000 128244554 0 1783734272 4.2367730141 3.9359967709 3.9246418476 636 1311867191.6451880932 0.0954402089 0.0699328004 0.0959446579 0.0062740892 2.4115470000 0.9609340000 0.2472580000 0.0000040000 1.1870920000 0.0073040000 128246740 0 1785470976 4.2389688492 3.9353299141 3.9256453514 637 1311867191.6827919483 0.0937357470 0.0699701677 0.0959446579 0.0062773934 3.9460870000 0.9888980000 0.4504550000 0.1220460000 1.1771030000 1.1977650000 128249054 0 1784745984 4.2422924042 3.9339423180 3.9267146587 638 1311867191.7119400501 0.0941371694 0.0700080470 0.0959446579 0.0062760184 2.4259820000 0.9793470000 0.2481720000 0.0000040000 1.1822690000 0.0072940000 128251176 0 1784487936 4.2439994812 3.9353744984 3.9276175499 639 1311867191.7457199097 0.0939002931 0.0700454371 0.0959446579 0.0062946460 2.5665670000 0.9677760000 0.2868930000 0.1218350000 1.1730390000 0.0072870000 128253330 0 1783984128 4.2447495461 3.9340109825 3.9281182289 640 1311867191.7763800621 0.0947651416 0.0700840616 0.0959446579 0.0062999245 2.5791230000 0.9740750000 0.4078470000 0.0000060000 1.1807930000 0.0072710000 128255484 0 1783857152 4.2456016541 3.9347050190 3.9290173054 641 1311867191.8097250462 0.0933311284 0.0701203285 0.0959446579 0.0062968688 3.7902450000 1.0111960000 0.2842760000 0.1218930000 1.1722050000 1.1917820000 128257702 0 1785470976 4.2490854263 3.9348413944 3.9306471348 642 1311867191.8395779133 0.0922042280 0.0701547271 0.0959446579 0.0063015698 2.3442290000 0.9816060000 0.1741400000 0.0000050000 1.1713660000 0.0072950000 128259856 0 1784872960 4.2508540154 3.9337439537 3.9310462475 643 1311867191.8745219707 0.0927701369 0.0701898988 0.0959446579 0.0063039556 2.5763550000 0.9792400000 0.2928340000 0.1221640000 1.1657720000 0.0073140000 128262074 0 1784201216 4.2520422935 3.9344172478 3.9323081970 644 1311867191.9077119827 0.0915218145 0.0702230229 0.0959446579 0.0063002522 2.5830520000 0.9808000000 0.4244230000 0.0000050000 1.1607320000 0.0072890000 128264292 0 1783476224 4.2548737526 3.9344906807 3.9336788654 645 1311867191.9391601086 0.0921083912 0.0702569537 0.0959446579 0.0062977464 3.7221470000 1.0091840000 0.2424830000 0.1220360000 1.1566680000 1.1827290000 128266478 0 1783332864 4.2545781136 3.9323604107 3.9340984821 646 1311867191.9755239487 0.0913886353 0.0702896653 0.0959446579 0.0062971515 2.5105670000 0.9890040000 0.3348190000 0.0000060000 1.1705820000 0.0072980000 128268696 0 1784987648 4.2572102547 3.9331738949 3.9354543686 647 1311867192.0076289177 0.0916275010 0.0703226449 0.0959446579 0.0062927523 2.7213430000 0.9918050000 0.4327360000 0.1220580000 1.1576390000 0.0072880000 128270882 0 1784115200 4.2583379745 3.9332528114 3.9361894131 648 1311867192.0447950363 0.0912551880 0.0703549482 0.0959446579 0.0063024306 2.4232720000 0.9909130000 0.2620190000 0.0000060000 1.1539130000 0.0073320000 128273164 0 1783984128 4.2588901520 3.9308383465 3.9364283085 649 1311867192.0751929283 0.0931712091 0.0703901042 0.0959446579 0.0063038529 3.8162460000 0.9855370000 0.3595020000 0.1219680000 1.1631430000 1.1763480000 128275286 0 1783058432 4.2581152916 3.9318611622 3.9368972778 650 1311867192.1073920727 0.0919324979 0.0704232464 0.0959446579 0.0063008508 2.4137630000 0.9899220000 0.2548110000 0.0000050000 1.1524530000 0.0072720000 128277504 0 1782968320 4.2622461319 3.9331789017 3.9385745525 651 1311867192.1433029175 0.0929298773 0.0704578188 0.0959446579 0.0063049961 2.5508020000 1.0011300000 0.2580590000 0.1217730000 1.1536280000 0.0073320000 128279754 0 1784578048 4.2611551285 3.9305748940 3.9383981228 652 1311867192.1754670143 0.0935768560 0.0704932774 0.0959446579 0.0063102302 2.3737630000 0.9822610000 0.2164160000 0.0000060000 1.1579180000 0.0074050000 128281940 0 1783836672 4.2624602318 3.9317011833 3.9392578602 653 1311867192.2077538967 0.0937449709 0.0705288849 0.0959446579 0.0063068301 3.7447190000 0.9969030000 0.2905850000 0.1218090000 1.1534830000 1.1728720000 128284158 0 1783730176 4.2645854950 3.9325318336 3.9405372143 654 1311867192.2451250553 0.0930304825 0.0705632910 0.0959446579 0.0063163495 2.4287400000 0.9931190000 0.2583580000 0.0000050000 1.1609580000 0.0073260000 128286440 0 1785344000 4.2658758163 3.9295797348 3.9412891865 655 1311867192.2744629383 0.0934551284 0.0705982404 0.0959446579 0.0063144717 2.5358760000 0.9846780000 0.2561280000 0.1218870000 1.1560210000 0.0073200000 128288562 0 1784455168 4.2678480148 3.9317169189 3.9419958591 656 1311867192.3067719936 0.0936112627 0.0706333212 0.0959446579 0.0063123027 2.6331540000 1.0145270000 0.4402240000 0.0000050000 1.1619260000 0.0072870000 128290748 0 1784233984 4.2695894241 3.9307284355 3.9431889057 657 1311867192.3427391052 0.0935709476 0.0706682339 0.0959446579 0.0063093147 3.7484010000 0.9926540000 0.2864280000 0.1221770000 1.1596480000 1.1775520000 128292998 0 1783607296 4.2709512711 3.9289555550 3.9436058998 658 1311867192.3755910397 0.0943705440 0.0707042556 0.0959446579 0.0063110294 2.5012860000 0.9951100000 0.3283420000 0.0000050000 1.1614070000 0.0072770000 128295216 0 1783222272 4.2725930214 3.9295594692 3.9441640377 659 1311867192.4059340954 0.0934477821 0.0707387678 0.0959446579 0.0063068197 2.7339920000 0.9922730000 0.4466560000 0.1218550000 1.1568740000 0.0072950000 128297338 0 1785008128 4.2757902145 3.9290711880 3.9448752403 660 1311867192.4447100163 0.0953033119 0.0707759868 0.0959446579 0.0063032852 2.4892850000 1.0180850000 0.2914360000 0.0000050000 1.1626000000 0.0073470000 128299652 0 1784229888 4.2758197784 3.9274773598 3.9449098110 661 1311867192.4748210907 0.0962774605 0.0708145670 0.0962774605 0.0063007136 3.6827820000 0.9883640000 0.2160570000 0.1219870000 1.1608850000 1.1863340000 128301806 0 1783713792 4.2772684097 3.9279503822 3.9454574585 662 1311867192.5077190399 0.0971587896 0.0708543619 0.0971587896 0.0062967152 2.4561780000 0.9835420000 0.2934330000 0.0000050000 1.1629350000 0.0073010000 128303992 0 1785364480 4.2783155441 3.9272434711 3.9459764957 663 1311867192.5427820683 0.0962294415 0.0708926350 0.0971587896 0.0062976456 2.7369890000 0.9895470000 0.4460190000 0.1218590000 1.1622290000 0.0072930000 128306242 0 1784221696 4.2803101540 3.9251034260 3.9457063675 664 1311867192.5787169933 0.0978344083 0.0709332100 0.0978344083 0.0062989847 2.5336490000 1.0194140000 0.3294860000 0.0000050000 1.1683160000 0.0072690000 128308460 0 1783713792 4.2813677788 3.9265229702 3.9457695484 665 1311867192.6109929085 0.1018649340 0.0709797238 0.1018649340 0.0062963966 3.7224830000 0.9857880000 0.2588630000 0.1215530000 1.1645470000 1.1826420000 128310646 0 1785380864 4.2784171104 3.9269187450 3.9456152916 666 1311867192.6435210705 0.1032805815 0.0710282236 0.1032805815 0.0062969131 2.5182330000 0.9912480000 0.3341060000 0.0000060000 1.1753510000 0.0075190000 128312864 0 1784221696 4.2779126167 3.9254639149 3.9451639652 667 1311867192.6790139675 0.1035206988 0.0710769380 0.1035206988 0.0062944668 2.5018100000 0.9829770000 0.2158910000 0.1216950000 1.1647560000 0.0073190000 128315114 0 1783857152 4.2800288200 3.9264183044 3.9457340240 668 1311867192.7113289833 0.1042638943 0.0711266190 0.1042638943 0.0062915410 2.4961990000 1.0163070000 0.2912550000 0.0000060000 1.1723200000 0.0072640000 128317268 0 1785470976 4.2806081772 3.9261219501 3.9459605217 669 1311867192.7439620495 0.1051646695 0.0711774980 0.1051646695 0.0062904811 3.7309510000 0.9899170000 0.2605460000 0.1216990000 1.1652970000 1.1834980000 128319486 0 1784729600 4.2804322243 3.9248311520 3.9458088875 670 1311867192.7760629654 0.1046130508 0.0712274019 0.1051646695 0.0062877435 2.5177660000 0.9891260000 0.3436610000 0.0000050000 1.1684220000 0.0072690000 128321672 0 1784221696 4.2830715179 3.9260442257 3.9464809895 671 1311867192.8091869354 0.1049567387 0.0712776691 0.1051646695 0.0062831862 2.7334830000 0.9932650000 0.4392160000 0.1219070000 1.1618480000 0.0073470000 128323890 0 1783468032 4.2840566635 3.9255435467 3.9468910694 672 1311867192.8422288895 0.1033360437 0.0713253750 0.1051646695 0.0062798142 2.4740870000 0.9938030000 0.2979170000 0.0000050000 1.1657880000 0.0073480000 128326076 0 1782960128 4.2866706848 3.9240207672 3.9472460747 673 1311867192.8792889118 0.1054630131 0.0713760996 0.1054630131 0.0062825151 3.7479710000 0.9812680000 0.2954890000 0.1216920000 1.1584020000 1.1819610000 128328358 0 1784598528 4.2861924171 3.9257330894 3.9478209019 674 1311867192.9092190266 0.1049086004 0.0714258511 0.1054630131 0.0062780081 2.5973360000 0.9873360000 0.4360860000 0.0000050000 1.1566490000 0.0073570000 128330480 0 1783840768 4.2878961563 3.9249920845 3.9488008022 675 1311867192.9434111118 0.1045762897 0.0714749629 0.1054630131 0.0062757396 2.7032490000 0.9949860000 0.4092880000 0.1217350000 1.1606350000 0.0073000000 128332730 0 1783353344 4.2887902260 3.9229943752 3.9487245083 676 1311867192.9776289463 0.1042825729 0.0715234948 0.1054630131 0.0062762295 2.4441660000 1.0125080000 0.2607360000 0.0000050000 1.1544480000 0.0073410000 128334916 0 1784983552 4.2913155556 3.9243457317 3.9495124817 677 1311867193.0086810589 0.1052484363 0.0715733101 0.1054630131 0.0062734028 3.8982920000 0.9982360000 0.4396790000 0.1216790000 1.1579560000 1.1705040000 128337102 0 1783840768 4.2911076546 3.9240887165 3.9498209953 678 1311867193.0430600643 0.1043086722 0.0716215923 0.1054630131 0.0062718990 2.5133440000 1.0031780000 0.3402540000 0.0000050000 1.1533030000 0.0074160000 128339320 0 1783353344 4.2926120758 3.9214515686 3.9498815536 679 1311867193.0767369270 0.1051287279 0.0716709401 0.1054630131 0.0062783139 2.5745930000 0.9911200000 0.2923240000 0.1216870000 1.1530250000 0.0072860000 128341506 0 1785110528 4.2940807343 3.9236052036 3.9501540661 680 1311867193.1105849743 0.1044184566 0.0717190982 0.1054630131 0.0062748816 2.4959000000 1.0258600000 0.2980800000 0.0000050000 1.1544650000 0.0074290000 128343724 0 1783820288 4.2965626717 3.9237611294 3.9507720470 681 1311867193.1429219246 0.1027727351 0.0717646983 0.1054630131 0.0062757940 3.7282970000 1.0102150000 0.2610230000 0.1217920000 1.1534790000 1.1724790000 128345942 0 1783463936 4.2982401848 3.9211442471 3.9507031441 682 1311867193.1767370701 0.1045987830 0.0718128421 0.1054630131 0.0062920764 2.6231840000 0.9972000000 0.4549780000 0.0000050000 1.1544090000 0.0073270000 128348128 0 1785110528 4.2995152473 3.9247260094 3.9508895874 683 1311867193.2122681141 0.1048282459 0.0718611809 0.1054630131 0.0062923675 2.5419420000 1.0014580000 0.2526990000 0.1224250000 1.1478740000 0.0073320000 128350378 0 1783975936 4.3003191948 3.9233081341 3.9512789249 684 1311867193.2432429790 0.1036901027 0.0719077144 0.1054630131 0.0062916555 2.6479520000 1.0256530000 0.4553380000 0.0000060000 1.1500820000 0.0073860000 128352564 0 1783214080 4.3024711609 3.9219892025 3.9513275623 685 1311867193.2773900032 0.1048241258 0.0719557676 0.1054630131 0.0062904909 3.6844550000 1.0080150000 0.2236970000 0.1218780000 1.1489770000 1.1727490000 128354782 0 1784967168 4.3034234047 3.9243395329 3.9514210224 686 1311867193.3139379025 0.1054311097 0.0720045654 0.1054630131 0.0062920080 2.5169640000 1.0136760000 0.3380550000 0.0000060000 1.1476680000 0.0073350000 128357032 0 1783861248 4.3036255836 3.9222302437 3.9510829449 687 1311867193.3426671028 0.1053938046 0.0720531670 0.1054630131 0.0062913413 2.7428830000 1.0084290000 0.4418630000 0.1218680000 1.1539880000 0.0073440000 128359154 0 1782956032 4.3050894737 3.9228672981 3.9513306618 688 1311867193.3788230419 0.1046151593 0.0721004954 0.1054630131 0.0062877143 2.4977190000 1.0358800000 0.2958830000 0.0000050000 1.1493950000 0.0073380000 128361404 0 1784713216 4.3082289696 3.9242048264 3.9516546726 689 1311867193.4126739502 0.1052133739 0.0721485548 0.1054630131 0.0062963868 3.9111390000 1.0078680000 0.4570920000 0.1218460000 1.1511890000 1.1629710000 128363590 0 1783590912 4.3082985878 3.9221115112 3.9514539242 690 1311867193.4440810680 0.1054320037 0.0721967916 0.1054630131 0.0062957166 2.4582880000 0.9977870000 0.2938260000 0.0000050000 1.1499710000 0.0074050000 128365808 0 1782702080 4.3096809387 3.9223990440 3.9513123035 691 1311867193.4782969952 0.1051433459 0.0722444712 0.1054630131 0.0062918364 2.6709050000 1.0107890000 0.3734240000 0.1219210000 1.1481820000 0.0074200000 128368026 0 1784328192 4.3122005463 3.9234948158 3.9516279697 692 1311867193.5199069977 0.1059382930 0.0722931617 0.1059382930 0.0062888385 2.4432700000 1.0117460000 0.2638130000 0.0000050000 1.1500970000 0.0073870000 128370308 0 1783205888 4.3128585815 3.9218444824 3.9515178204 693 1311867193.5431120396 0.1061897874 0.0723420745 0.1061897874 0.0062854622 3.9042800000 1.0118150000 0.4435670000 0.1220290000 1.1497750000 1.1676290000 128372398 0 1782464512 4.3138380051 3.9224138260 3.9515519142 694 1311867193.5765709877 0.1061647013 0.0723908103 0.1061897874 0.0062813567 2.4699500000 0.9992950000 0.2962590000 0.0000050000 1.1577190000 0.0074330000 128374584 0 1784205312 4.3160300255 3.9234893322 3.9516894817 695 1311867193.6127800941 0.1074931026 0.0724413172 0.1074931026 0.0062773670 2.6686170000 1.0411320000 0.3384160000 0.1221020000 1.1492720000 0.0073600000 128376866 0 1784856576 4.3152852058 3.9216685295 3.9510340691 696 1311867193.6461451054 0.1072493047 0.0724913287 0.1074931026 0.0062733891 2.5442570000 1.0405860000 0.3341290000 0.0000060000 1.1527330000 0.0074280000 128379052 0 1784131584 4.3171653748 3.9217536449 3.9510145187 697 1311867193.6757860184 0.1074975207 0.0725415528 0.1074975207 0.0062701233 3.8077230000 1.0148160000 0.3354180000 0.1223950000 1.1529020000 1.1729840000 128381206 0 1785737216 4.3193445206 3.9237499237 3.9514489174 698 1311867193.7122890949 0.1085288897 0.0725931106 0.1085288897 0.0062663310 2.5154130000 1.0095080000 0.3376890000 0.0000050000 1.1503760000 0.0074090000 128383456 0 1784332288 4.3188099861 3.9218301773 3.9511225224 699 1311867193.7430191040 0.1097033024 0.0726462010 0.1097033024 0.0062631982 2.5511150000 1.0020810000 0.2545910000 0.1219070000 1.1557660000 0.0073520000 128385610 0 1783595008 4.3192429543 3.9227526188 3.9510657787 700 1311867193.7760169506 0.1113338768 0.0727014691 0.1113338768 0.0062610181 2.5061810000 1.0453390000 0.2938670000 0.0000050000 1.1502690000 0.0073910000 128387796 0 1785200640 4.3193707466 3.9242982864 3.9506108761 701 1311867193.8139710426 0.1116919070 0.0727570903 0.1116919070 0.0062591701 3.8364910000 1.0046160000 0.3810980000 0.1218090000 1.1529110000 1.1657350000 128390110 0 1784348672 4.3202838898 3.9225187302 3.9508619308 702 1311867193.8436760902 0.1121395454 0.0728131906 0.1121395454 0.0062561665 2.4377090000 1.0116510000 0.2568350000 0.0000050000 1.1523020000 0.0073810000 128392232 0 1783341056 4.3211507797 3.9226374626 3.9507768154 703 1311867193.8771181107 0.1122563332 0.0728692975 0.1122563332 0.0062525866 2.6048930000 1.0143690000 0.3002990000 0.1219800000 1.1516190000 0.0073380000 128394450 0 1784946688 4.3229150772 3.9235217571 3.9505434036 704 1311867193.9151229858 0.1130464673 0.0729263673 0.1130464673 0.0062490313 2.5866780000 1.0368110000 0.3794930000 0.0000040000 1.1527830000 0.0074030000 128396700 0 1784119296 4.3232908249 3.9222795963 3.9504699707 705 1311867193.9425311089 0.1140403375 0.0729846850 0.1140403375 0.0062466275 3.7641590000 1.0110770000 0.3034030000 0.1222140000 1.1502770000 1.1677710000 128398854 0 1783107584 4.3236513138 3.9235265255 3.9502608776 706 1311867193.9781770706 0.1149506569 0.0730441269 0.1149506569 0.0062433535 2.5390630000 1.0009830000 0.3645130000 0.0000050000 1.1569070000 0.0074340000 128401104 0 1784598528 4.3243680000 3.9237139225 3.9502508640 707 1311867194.0148570538 0.1171816364 0.0731065562 0.1171816364 0.0062413776 2.6173290000 1.0226120000 0.3056180000 0.1221880000 1.1492430000 0.0073680000 128403322 0 1783472128 4.3230648041 3.9228057861 3.9495050907 708 1311867194.0433440208 0.1186212450 0.0731708425 0.1186212450 0.0062401849 2.6357650000 1.0113980000 0.4486740000 0.0000050000 1.1588240000 0.0074750000 128405476 0 1782460416 4.3231167793 3.9236059189 3.9495561123 709 1311867194.0746119022 0.1166579127 0.0732321783 0.1186212450 0.0062367709 3.9136920000 1.0113830000 0.4480220000 0.1222910000 1.1530420000 1.1696010000 128407630 0 1783930880 4.3268442154 3.9243397713 3.9500827789 710 1311867194.1131060123 0.1173844114 0.0732943645 0.1186212450 0.0062333333 2.6569210000 1.0239840000 0.4612200000 0.0000050000 1.1540930000 0.0074720000 128409944 0 1782960128 4.3266100883 3.9229910374 3.9497306347 711 1311867194.1428558826 0.1202723309 0.0733604376 0.1202723309 0.0062336400 2.7678310000 1.0159140000 0.4538610000 0.1222490000 1.1587800000 0.0073530000 128412098 0 1781833728 4.3246111870 3.9244289398 3.9495329857 712 1311867194.1758549213 0.1187896654 0.0734242427 0.1202723309 0.0062351458 2.4349380000 1.0077590000 0.2566940000 0.0000050000 1.1537190000 0.0075150000 128414284 0 1783422976 4.3274216652 3.9255802631 3.9500381947 713 1311867194.2138450146 0.1206295192 0.0734904493 0.1206295192 0.0062326937 3.8470910000 1.0100460000 0.3770600000 0.1217820000 1.1608270000 1.1678520000 128416566 0 1785200640 4.3255462646 3.9238414764 3.9496352673 714 1311867194.2451140881 0.1198315546 0.0735553528 0.1206295192 0.0062312361 2.6351000000 1.0113390000 0.4530780000 0.0000050000 1.1529120000 0.0073680000 128418688 0 1784246272 4.3277206421 3.9255626202 3.9499354362 715 1311867194.2760241032 0.1203400716 0.0736207859 0.1206295192 0.0062278601 2.7461370000 1.0209380000 0.4392710000 0.1220580000 1.1469200000 0.0073790000 128420842 0 1783087104 4.3277220726 3.9253106117 3.9504618645 716 1311867194.3139200211 0.1208752468 0.0736867838 0.1208752468 0.0062243905 2.5028790000 1.0354630000 0.3024970000 0.0000050000 1.1481930000 0.0074380000 128423124 0 1784565760 4.3274016380 3.9239993095 3.9500548840 717 1311867194.3447821140 0.1193852872 0.0737505195 0.1208752468 0.0062282161 3.8122580000 1.0235370000 0.3418120000 0.1220070000 1.1492360000 1.1651530000 128425310 0 1783341056 4.3301019669 3.9256770611 3.9507148266 718 1311867194.3802230358 0.1187868342 0.0738132442 0.1208752468 0.0062249354 2.6281850000 1.0168020000 0.4390160000 0.0000050000 1.1554080000 0.0074470000 128427528 0 1782214656 4.3311719894 3.9253122807 3.9511957169 719 1311867194.4124519825 0.1186364368 0.0738755852 0.1208752468 0.0062233665 2.6080940000 1.0172880000 0.3020460000 0.1247510000 1.1470650000 0.0074770000 128429682 0 1783717888 4.3312287331 3.9231746197 3.9516642094 720 1311867194.4447510242 0.1199330613 0.0739395539 0.1208752468 0.0062199107 2.4212650000 1.0343400000 0.2172290000 0.0000050000 1.1526770000 0.0075840000 128431900 0 1785462784 4.3307576180 3.9238278866 3.9516463280 721 1311867194.4805839062 0.1191576496 0.0740022697 0.1208752468 0.0062164423 3.9170070000 1.0119040000 0.4594780000 0.1221830000 1.1450300000 1.1677480000 128434086 0 1784492032 4.3325262070 3.9246151447 3.9519269466 722 1311867194.5174930096 0.1201877072 0.0740662385 0.1208752468 0.0062142949 2.6314800000 1.0082950000 0.4605440000 0.0000050000 1.1455770000 0.0074330000 128436400 0 1782939648 4.3313913345 3.9231421947 3.9517047405 723 1311867194.5439500809 0.1191264316 0.0741285624 0.1208752468 0.0062130607 2.6482630000 1.0112750000 0.3425350000 0.1222500000 1.1553250000 0.0074350000 128438458 0 1784598528 4.3331537247 3.9239799976 3.9517226219 724 1311867194.5795979500 0.1197771430 0.0741916129 0.1208752468 0.0062088020 2.4795480000 1.0150360000 0.3017380000 0.0000060000 1.1450440000 0.0073620000 128440676 0 1783611392 4.3328981400 3.9239339828 3.9522664547 725 1311867194.6129479408 0.1181123108 0.0742521932 0.1208752468 0.0062051431 3.7575200000 1.0097580000 0.3047270000 0.1220920000 1.1504220000 1.1609390000 128442894 0 1782452224 4.3348755836 3.9226984978 3.9528198242 726 1311867194.6493880749 0.1175867841 0.0743118827 0.1208752468 0.0062160541 2.5071310000 1.0085400000 0.3390910000 0.0000040000 1.1426580000 0.0073820000 128445176 0 1783930880 4.3360037804 3.9238514900 3.9535791874 727 1311867194.6784319878 0.1166017503 0.0743700531 0.1208752468 0.0062158515 2.7006660000 1.0191090000 0.4022970000 0.1218280000 1.1396590000 0.0074110000 128447298 0 1782960128 4.3372173309 3.9233067036 3.9538586140 728 1311867194.7133309841 0.1172514111 0.0744289561 0.1208752468 0.0062130061 2.4956890000 1.0371660000 0.3012800000 0.0000050000 1.1401680000 0.0074410000 128449516 0 1781817344 4.3368029594 3.9233582020 3.9538371563 729 1311867194.7475099564 0.1170304045 0.0744873943 0.1208752468 0.0062089946 3.6663900000 1.0122600000 0.2249790000 0.1218050000 1.1398670000 1.1579570000 128451734 0 1783422976 4.3378949165 3.9240243435 3.9543478489 730 1311867194.7784450054 0.1172024906 0.0745459081 0.1208752468 0.0062051026 2.5791030000 1.0127520000 0.4035750000 0.0000050000 1.1460010000 0.0074480000 128453920 0 1785081856 4.3380827904 3.9238674641 3.9547498226 731 1311867194.8130390644 0.1183831617 0.0746058770 0.1208752468 0.0062011524 2.7512240000 1.0182460000 0.4562570000 0.1220340000 1.1367800000 0.0074390000 128456138 0 1784102912 4.3368186951 3.9237115383 3.9548871517 732 1311867194.8476719856 0.1190741882 0.0746666260 0.1208752468 0.0061973371 2.4618750000 1.0387980000 0.2606910000 0.0000050000 1.1453300000 0.0073850000 128458356 0 1782960128 4.3362975121 3.9245476723 3.9546349049 733 1311867194.8814148903 0.1195379347 0.0747278420 0.1208752468 0.0061934966 3.6547920000 1.0182830000 0.2144400000 0.1218860000 1.1369500000 1.1537140000 128460574 0 1784471552 4.3356237411 3.9250164032 3.9548335075 734 1311867194.9104089737 0.1198780015 0.0747893545 0.1208752468 0.0061997193 2.3938210000 1.0226960000 0.2173300000 0.0000060000 1.1358850000 0.0074300000 128462696 0 1783214080 4.3352499008 3.9257724285 3.9549930096 735 1311867194.9451448917 0.1188180596 0.0748492575 0.1208752468 0.0061970175 2.5585580000 1.0247880000 0.2618320000 0.1218550000 1.1330150000 0.0073820000 128464946 0 1782218752 4.3353657722 3.9245417118 3.9554879665 736 1311867194.9787399769 0.1158162877 0.0749049192 0.1208752468 0.0061962600 2.4270410000 1.0193070000 0.2585860000 0.0000050000 1.1321460000 0.0073920000 128467164 0 1783709696 4.3378529549 3.9233396053 3.9560558796 737 1311867195.0132799149 0.1155345887 0.0749600477 0.1208752468 0.0061940676 3.7839520000 1.0225600000 0.3439650000 0.1220160000 1.1316020000 1.1543630000 128469382 0 1785454592 4.3374905586 3.9245071411 3.9564185143 738 1311867195.0464940071 0.1150740534 0.0750144027 0.1208752468 0.0061913440 2.4333340000 1.0220360000 0.2635670000 0.0000050000 1.1297510000 0.0073850000 128471568 0 1784483840 4.3368434906 3.9225797653 3.9566719532 739 1311867195.0781710148 0.1139152274 0.0750670425 0.1208752468 0.0061883966 2.6273900000 1.0202570000 0.3343940000 0.1219590000 1.1336390000 0.0073690000 128473754 0 1783341056 4.3376321793 3.9232842922 3.9569768906 740 1311867195.1115310192 0.1138719916 0.0751194816 0.1208752468 0.0061845701 2.5349690000 1.0149170000 0.3785290000 0.0000050000 1.1245420000 0.0074360000 128475940 0 1784819712 4.3372111320 3.9241147041 3.9573533535 741 1311867195.1458311081 0.1142697334 0.0751723160 0.1208752468 0.0061804083 3.7154580000 1.0412870000 0.2642190000 0.1218310000 1.1327120000 1.1448090000 128478190 0 1783869440 4.3354749680 3.9232971668 3.9569945335 742 1311867195.1780319214 0.1140037477 0.0752246494 0.1208752468 0.0061785105 2.6217140000 1.0179620000 0.4618080000 0.0000050000 1.1247820000 0.0074330000 128480376 0 1783087104 4.3354034424 3.9248936176 3.9572350979 743 1311867195.2114748955 0.1123327315 0.0752745930 0.1208752468 0.0061747464 2.4678700000 1.0243850000 0.1827000000 0.1221010000 1.1216840000 0.0073890000 128482562 0 1784725504 4.3355841637 3.9245457649 3.9573013783 744 1311867195.2436800003 0.1117911339 0.0753236744 0.1208752468 0.0061731858 2.3757300000 1.0117350000 0.2272410000 0.0000040000 1.1188230000 0.0074090000 128484780 0 1783967744 4.3352270126 3.9232811928 3.9576013088 745 1311867195.2780399323 0.1116812453 0.0753724765 0.1208752468 0.0061695934 3.7251660000 1.0062540000 0.3295530000 0.1216680000 1.1222350000 1.1356550000 128486998 0 1783439360 4.3343839645 3.9238038063 3.9576261044 746 1311867195.3123180866 0.1116023138 0.0754210420 0.1208752468 0.0061656112 2.6054110000 1.0160120000 0.4462920000 0.0000050000 1.1259460000 0.0074390000 128489216 0 1785217024 4.3334064484 3.9234869480 3.9577383995 747 1311867195.3425979614 0.1126332134 0.0754708575 0.1208752468 0.0061659683 2.5266340000 1.0186270000 0.2500310000 0.1218990000 1.1181080000 0.0074560000 128491370 0 1784328192 4.3303451538 3.9217331409 3.9569139481 748 1311867195.3782711029 0.1107909232 0.0755180768 0.1208752468 0.0061634266 2.5547630000 1.0465320000 0.3698920000 0.0000040000 1.1209820000 0.0074910000 128493620 0 1784111104 4.3314166069 3.9225959778 3.9568190575 749 1311867195.4119830132 0.1103075892 0.0755645247 0.1208752468 0.0061616634 3.5690570000 1.0099730000 0.1736150000 0.1217660000 1.1176560000 1.1355260000 128495806 0 1783349248 4.3306064606 3.9227163792 3.9567074776 750 1311867195.4435520172 0.1110685617 0.0756118635 0.1208752468 0.0061597018 2.4181380000 1.0211060000 0.2613150000 0.0000050000 1.1184860000 0.0074580000 128498024 0 1783091200 4.3274970055 3.9217047691 3.9558849335 751 1311867195.4788239002 0.1100028455 0.0756576570 0.1208752468 0.0061558325 2.7414690000 1.0163600000 0.4636330000 0.1219460000 1.1167800000 0.0073740000 128500242 0 1784709120 4.3277678490 3.9235923290 3.9556994438 752 1311867195.5113179684 0.1098215431 0.0757030877 0.1208752468 0.0061517757 2.6386620000 1.0634080000 0.4409680000 0.0000050000 1.1162380000 0.0074180000 128502428 0 1783963648 4.3265666962 3.9235882759 3.9557764530 753 1311867195.5439620018 0.1097830161 0.0757483466 0.1208752468 0.0061477106 3.7456250000 1.0169700000 0.3452450000 0.1220020000 1.1198710000 1.1315430000 128504646 0 1783865344 4.3239173889 3.9220237732 3.9554927349 754 1311867195.5782160759 0.1078305393 0.0757908959 0.1208752468 0.0061453334 2.5843340000 1.0066530000 0.4487350000 0.0000050000 1.1118260000 0.0073660000 128506864 0 1785479168 4.3248972893 3.9226489067 3.9559428692 755 1311867195.6119859219 0.1082114503 0.0758338371 0.1208752468 0.0061426913 2.7157220000 1.0154530000 0.4487570000 0.1224140000 1.1109180000 0.0074190000 128509082 0 1784582144 4.3227119446 3.9227004051 3.9558320045 756 1311867195.6430909634 0.1091967821 0.0758779679 0.1208752468 0.0061390796 2.4805120000 1.0140910000 0.3385070000 0.0000040000 1.1106560000 0.0074750000 128511236 0 1784492032 4.3192253113 3.9220919609 3.9551661015 757 1311867195.6779129505 0.1083584055 0.0759208747 0.1208752468 0.0061356761 3.8425810000 1.0212210000 0.4546220000 0.1219640000 1.1087650000 1.1253310000 128513486 0 1783582720 4.3184633255 3.9226229191 3.9551942348 758 1311867195.7107300758 0.1088199764 0.0759642772 0.1208752468 0.0061353610 2.4434210000 1.0111680000 0.3028330000 0.0000060000 1.1120450000 0.0073960000 128515640 0 1783455744 4.3157401085 3.9226102829 3.9552285671 759 1311867195.7458300591 0.1079443246 0.0760064117 0.1208752468 0.0061322575 2.5833890000 1.0117220000 0.3267180000 0.1217930000 1.1059660000 0.0074230000 128517890 0 1785217024 4.3144078255 3.9215993881 3.9551491737 760 1311867195.7821879387 0.1068387926 0.0760469806 0.1208752468 0.0061287362 2.4247490000 1.0445230000 0.2534070000 0.0000050000 1.1085890000 0.0074060000 128520108 0 1784324096 4.3139810562 3.9218146801 3.9556081295 761 1311867195.8100500107 0.1074616164 0.0760882613 0.1208752468 0.0061251926 3.6205060000 1.0111360000 0.2546450000 0.1217190000 1.1029200000 1.1200860000 128522230 0 1784238080 4.3114190102 3.9216644764 3.9554424286 762 1311867195.8458549976 0.1068133116 0.0761285829 0.1208752468 0.0061213677 2.4279960000 1.0100570000 0.2989100000 0.0000050000 1.1009940000 0.0074250000 128524480 0 1783476224 4.3097710609 3.9210612774 3.9553675652 763 1311867195.8778660297 0.1063338146 0.0761681704 0.1208752468 0.0061197695 2.7337590000 1.0316700000 0.4650620000 0.1218960000 1.0978300000 0.0074560000 128526698 0 1783332864 4.3089747429 3.9229338169 3.9554512501 764 1311867195.9098269939 0.1063824072 0.0762077178 0.1208752468 0.0061171992 2.4806390000 1.0381820000 0.3291250000 0.0000050000 1.0962630000 0.0074270000 128528884 0 1784999936 4.3070826530 3.9223797321 3.9556152821 765 1311867195.9458460808 0.1063584760 0.0762471306 0.1208752468 0.0061134527 3.5918630000 1.0165370000 0.2250860000 0.1220280000 1.0965020000 1.1209570000 128531102 0 1784221696 4.3047823906 3.9216849804 3.9554169178 766 1311867195.9778430462 0.1067801490 0.0762869909 0.1208752468 0.0061123140 2.3798920000 1.0133330000 0.2536400000 0.0000050000 1.0954520000 0.0074800000 128533320 0 1783996416 4.3035011292 3.9236774445 3.9556319714 767 1311867196.0100569725 0.1057698131 0.0763254301 0.1208752468 0.0061101276 2.4610570000 1.0060690000 0.2189120000 0.1217970000 1.0971890000 0.0074720000 128535506 0 1785610240 4.3027896881 3.9227280617 3.9558932781 768 1311867196.0498790741 0.1049150005 0.0763626561 0.1208752468 0.0061067195 2.4188030000 1.0086470000 0.2977140000 0.0000040000 1.0930310000 0.0085740000 128537820 0 1784479744 4.3017759323 3.9220097065 3.9556102753 769 1311867196.0793108940 0.1060231104 0.0764012262 0.1208752468 0.0061092152 3.5748980000 1.0119410000 0.2243950000 0.1216930000 1.0975150000 1.1093700000 128540006 0 1783320576 4.2998552322 3.9241909981 3.9558792114 770 1311867196.1113979816 0.1057784781 0.0764393785 0.1208752468 0.0061063362 2.4413830000 1.0010230000 0.3303550000 0.0000050000 1.0927700000 0.0073730000 128542128 0 1784946688 4.2978987694 3.9228470325 3.9558787346 771 1311867196.1473290920 0.1044151932 0.0764756636 0.1208752468 0.0061029808 2.4395970000 1.0262740000 0.1850170000 0.1218520000 1.0883330000 0.0074270000 128544410 0 1783975936 4.2973842621 3.9219660759 3.9560694695 772 1311867196.1811769009 0.1045411825 0.0765120179 0.1208752468 0.0061045529 2.3726360000 1.0077050000 0.2615450000 0.0000040000 1.0860310000 0.0074470000 128546628 0 1782710272 4.2960367203 3.9236898422 3.9559862614 773 1311867196.2114949226 0.1056821868 0.0765497542 0.1208752468 0.0061025151 3.8021850000 1.0157070000 0.4635170000 0.1216790000 1.0874120000 1.1038770000 128548750 0 1784455168 4.2928638458 3.9225182533 3.9557735920 774 1311867196.2462599277 0.1053091735 0.0765869111 0.1208752468 0.0060996265 2.5554470000 1.0062040000 0.4393030000 0.0000040000 1.0918230000 0.0073510000 128551000 0 1783582720 4.2914962769 3.9222877026 3.9558699131 775 1311867196.2800569534 0.1054594666 0.0766241660 0.1208752468 0.0060958955 2.6893730000 1.0032860000 0.4604200000 0.1214240000 1.0868440000 0.0074270000 128553218 0 1783083008 4.2898058891 3.9232106209 3.9557316303 776 1311867196.3111600876 0.1051508710 0.0766609272 0.1208752468 0.0060924942 2.5280190000 1.0363850000 0.3850430000 0.0000050000 1.0893380000 0.0073690000 128555372 0 1784840192 4.2880926132 3.9222290516 3.9557926655 777 1311867196.3484730721 0.1052757576 0.0766977545 0.1208752468 0.0060891604 3.7921330000 1.0185160000 0.4555260000 0.1217720000 1.0845860000 1.1008490000 128557654 0 1783738368 4.2862725258 3.9225969315 3.9556035995 778 1311867196.3842670918 0.1048408449 0.0767339282 0.1208752468 0.0060860434 2.5615850000 1.0186250000 0.4413510000 0.0000040000 1.0841560000 0.0074530000 128559872 0 1782587392 4.2852721214 3.9238169193 3.9558677673 779 1311867196.4107549191 0.1051102728 0.0767703548 0.1208752468 0.0060838107 2.4815450000 1.0053880000 0.2531850000 0.1224270000 1.0834150000 0.0074380000 128561962 0 1784193024 4.2829279900 3.9221947193 3.9560277462 780 1311867196.4463150501 0.1047390103 0.0768062121 0.1208752468 0.0060832676 2.5600900000 1.0431260000 0.4195040000 0.0000050000 1.0792660000 0.0074120000 128564212 0 1783242752 4.2819924355 3.9231908321 3.9561734200 781 1311867196.4798319340 0.1039715260 0.0768409948 0.1208752468 0.0060794399 3.5694040000 1.0101620000 0.2533940000 0.1217140000 1.0762100000 1.0977190000 128566430 0 1781960704 4.2814555168 3.9236631393 3.9567127228 782 1311867196.5113470554 0.1044202447 0.0768762624 0.1208752468 0.0060758620 2.3215710000 1.0051780000 0.2236100000 0.0000040000 1.0755200000 0.0073700000 128568584 0 1783455744 4.2787618637 3.9230198860 3.9565923214 783 1311867196.5468420982 0.1040383428 0.0769109521 0.1208752468 0.0060729742 2.4943180000 1.0115740000 0.2663220000 0.1216270000 1.0775680000 0.0073580000 128570834 0 1785200640 4.2768855095 3.9237301350 3.9568204880 784 1311867196.5795550346 0.1037958562 0.0769452441 0.1208752468 0.0060708625 2.3595780000 1.0167320000 0.2540930000 0.0000040000 1.0702540000 0.0073930000 128573052 0 1783971840 4.2763981819 3.9248964787 3.9573628902 785 1311867196.6108930111 0.1028189436 0.0769782042 0.1208752468 0.0060702104 3.5127050000 1.0101850000 0.2144410000 0.1216370000 1.0725070000 1.0838630000 128575206 0 1782976512 4.2750921249 3.9235460758 3.9577162266 786 1311867196.6521809101 0.1031233743 0.0770114678 0.1208752468 0.0060732309 2.2775810000 1.0067030000 0.1861070000 0.0000050000 1.0673870000 0.0074190000 128577552 0 1784471552 4.2723455429 3.9247684479 3.9575808048 787 1311867196.6805100441 0.1019650623 0.0770431750 0.1208752468 0.0060807465 2.5944420000 1.0136310000 0.3773170000 0.1214290000 1.0636060000 0.0075750000 128579674 0 1783463936 4.2717165947 3.9256644249 3.9582018852 788 1311867196.7112100124 0.1011758968 0.0770738003 0.1208752468 0.0060777778 2.3119530000 1.0140250000 0.2219340000 0.0000040000 1.0584930000 0.0073960000 128581828 0 1782296576 4.2706236839 3.9243915081 3.9589025974 789 1311867196.7464900017 0.1023500785 0.0771058362 0.1208752468 0.0060744230 3.5429160000 1.0088120000 0.2648530000 0.1214520000 1.0635220000 1.0744030000 128584078 0 1784057856 4.2673902512 3.9258091450 3.9590995312 790 1311867196.7783749104 0.1008323431 0.0771358697 0.1208752468 0.0060709462 2.2687920000 1.0145210000 0.1827550000 0.0000050000 1.0540810000 0.0074820000 128586296 0 1785708544 4.2666935921 3.9255032539 3.9594893456 791 1311867196.8109180927 0.1009058505 0.0771659203 0.1208752468 0.0060687439 2.4856710000 1.0260880000 0.2667170000 0.1216560000 1.0527650000 0.0074730000 128588418 0 1784614912 4.2641282082 3.9250612259 3.9597098827 792 1311867196.8488750458 0.1007028967 0.0771956387 0.1208752468 0.0060663274 2.3102650000 1.0128440000 0.2280620000 0.0000040000 1.0518370000 0.0074480000 128590732 0 1783726080 4.2619338036 3.9251861572 3.9599287510 793 1311867196.8821749687 0.1003503948 0.0772248376 0.1208752468 0.0060627547 3.5365490000 1.0222440000 0.2660210000 0.1220030000 1.0488670000 1.0674870000 128592918 0 1785454592 4.2604093552 3.9259262085 3.9602932930 794 1311867196.9115700722 0.0996427983 0.0772530718 0.1208752468 0.0060604624 2.3959980000 1.0165650000 0.3078530000 0.0000040000 1.0531730000 0.0074170000 128595040 0 1784602624 4.2585930824 3.9241757393 3.9604148865 795 1311867196.9482440948 0.0993708521 0.0772808929 0.1208752468 0.0060571582 2.4183940000 1.0119300000 0.2197630000 0.1213160000 1.0478320000 0.0074590000 128597322 0 1783844864 4.2565469742 3.9247913361 3.9604871273 796 1311867196.9809880257 0.0987384021 0.0773078496 0.1208752468 0.0060545770 2.3086480000 1.0165050000 0.2274040000 0.0000040000 1.0472410000 0.0073840000 128599540 0 1783099392 4.2550883293 3.9245131016 3.9606375694 797 1311867197.0154891014 0.0985818207 0.0773345421 0.1208752468 0.0060512877 3.5623880000 1.0110190000 0.3060820000 0.1213560000 1.0471860000 1.0665180000 128601726 0 1782571008 4.2531828880 3.9240441322 3.9606518745 798 1311867197.0490679741 0.0986967236 0.0773613118 0.1208752468 0.0060481212 2.4275400000 1.0238400000 0.3320740000 0.0000040000 1.0541270000 0.0074170000 128603944 0 1784348672 4.2507481575 3.9240250587 3.9604880810 799 1311867197.0806479454 0.0970277190 0.0773859256 0.1208752468 0.0060453105 2.3881960000 1.0142290000 0.1886250000 0.1213660000 1.0455920000 0.0073650000 128606066 0 1783476224 4.2505154610 3.9234852791 3.9604823589 800 1311867197.1148109436 0.0975865275 0.0774111763 0.1208752468 0.0060416216 2.5459270000 1.0092010000 0.4667990000 0.0000040000 1.0523320000 0.0074590000 128608316 0 1783201792 4.2473220825 3.9233610630 3.9599511623 801 1311867197.1468429565 0.0979172289 0.0774367769 0.1208752468 0.0060391489 3.4712200000 1.0067520000 0.2259050000 0.1212890000 1.0450350000 1.0622330000 128610502 0 1784852480 4.2451214790 3.9243805408 3.9598610401 802 1311867197.1792430878 0.0979637951 0.0774623717 0.1208752468 0.0060364041 2.3396610000 1.0132160000 0.2643890000 0.0000040000 1.0436290000 0.0073650000 128612720 0 1784090624 4.2426328659 3.9238197803 3.9597215652 803 1311867197.2143619061 0.0980533287 0.0774880142 0.1208752468 0.0060355281 2.4640930000 1.0142740000 0.2677420000 0.1213610000 1.0431300000 0.0073790000 128614938 0 1783857152 4.2402200699 3.9243004322 3.9596452713 804 1311867197.2459290028 0.0975781381 0.0775130019 0.1208752468 0.0060320685 2.3697790000 1.0103980000 0.2996270000 0.0000040000 1.0412400000 0.0073500000 128617124 0 1783214080 4.2390389442 3.9248092175 3.9598541260 805 1311867197.2799959183 0.0971952602 0.0775374519 0.1208752468 0.0060291637 3.5100330000 1.0156370000 0.2604040000 0.1213360000 1.0390040000 1.0633680000 128619374 0 1782558720 4.2370247841 3.9243502617 3.9600269794 806 1311867197.3157260418 0.0970740542 0.0775616909 0.1208752468 0.0060261130 2.4529620000 1.0155620000 0.3805020000 0.0000040000 1.0392670000 0.0074360000 128621560 0 1784201216 4.2346496582 3.9246387482 3.9598712921 807 1311867197.3468708992 0.0964184031 0.0775850573 0.1208752468 0.0060229319 2.5142040000 1.0231040000 0.2928050000 0.1230840000 1.0565100000 0.0076800000 128623746 0 1783476224 4.2332439423 3.9247453213 3.9600753784 808 1311867197.3784019947 0.0967156962 0.0776087339 0.1208752468 0.0060204425 2.4268440000 1.0589280000 0.3109930000 0.0000040000 1.0391490000 0.0074450000 128625900 0 1783349248 4.2305650711 3.9241027832 3.9598588943 809 1311867197.4155099392 0.0969023705 0.0776325826 0.1208752468 0.0060171408 3.4523550000 1.0127290000 0.2106760000 0.1212240000 1.0425760000 1.0550870000 128628150 0 1784979456 4.2279057503 3.9239964485 3.9594843388 810 1311867197.4478878975 0.0958662033 0.0776550933 0.1208752468 0.0060137267 2.2517540000 1.0175030000 0.1786430000 0.0000040000 1.0370340000 0.0074100000 128630336 0 1784238080 4.2275218964 3.9240953922 3.9594984055 811 1311867197.4793179035 0.0968154222 0.0776787188 0.1208752468 0.0060102369 2.6630830000 1.0115940000 0.4662010000 0.1267820000 1.0408680000 0.0074270000 128632458 0 1783963648 4.2240386009 3.9237976074 3.9584798813 812 1311867197.5150759220 0.0973357931 0.0777029270 0.1208752468 0.0060082826 2.3299290000 1.0114350000 0.2599370000 0.0000040000 1.0401430000 0.0074140000 128634708 0 1783222272 4.2214927673 3.9247100353 3.9577293396 813 1311867197.5469260216 0.0969982967 0.0777266606 0.1208752468 0.0060050538 3.5025290000 1.0128970000 0.2547680000 0.1213790000 1.0461940000 1.0569800000 128636862 0 1782947840 4.2203068733 3.9253840446 3.9574263096 814 1311867197.5802750587 0.0970142335 0.0777503554 0.1208752468 0.0060039822 2.4195790000 1.0163140000 0.3432910000 0.0000040000 1.0423800000 0.0074660000 128639080 0 1784598528 4.2177476883 3.9239547253 3.9566297531 815 1311867197.6152749062 0.0990451202 0.0777764839 0.1208752468 0.0060047139 2.4221870000 1.0170650000 0.2214420000 0.1216170000 1.0436660000 0.0073620000 128641298 0 1783836672 4.2135286331 3.9255340099 3.9552514553 816 1311867197.6470439434 0.0982500538 0.0778015741 0.1208752468 0.0060022158 2.3587470000 1.0147100000 0.2834580000 0.0000050000 1.0428860000 0.0073730000 128643484 0 1783603200 4.2132248878 3.9273407459 3.9550104141 817 1311867197.6800849438 0.0981533304 0.0778264844 0.1208752468 0.0060016580 3.5507140000 1.0173120000 0.3008570000 0.1212630000 1.0425870000 1.0585690000 128645702 0 1785372672 4.2104372978 3.9254286289 3.9542515278 818 1311867197.7143290043 0.0985583290 0.0778518290 0.1208752468 0.0060021853 2.5397550000 1.0117530000 0.4604070000 0.0000040000 1.0489610000 0.0075040000 128647920 0 1784209408 4.2087578773 3.9277825356 3.9535963535 819 1311867197.7463419437 0.0984812006 0.0778770175 0.1208752468 0.0060002021 2.4056590000 1.0087160000 0.2179320000 0.1213190000 1.0399460000 0.0074780000 128650106 0 1783963648 4.2068767548 3.9277553558 3.9529862404 820 1311867197.7793009281 0.0992384776 0.0779030680 0.1208752468 0.0059975575 2.3797930000 1.0106990000 0.3037320000 0.0000050000 1.0468120000 0.0074340000 128652324 0 1783222272 4.2032651901 3.9263875484 3.9517965317 821 1311867197.8146750927 0.0990421399 0.0779288160 0.1208752468 0.0059994075 3.4741860000 1.0131930000 0.2259440000 0.1215110000 1.0428470000 1.0602880000 128654574 0 1782681600 4.2025675774 3.9288232327 3.9511981010 822 1311867197.8467919827 0.0984805077 0.0779538181 0.1208752468 0.0059983711 2.3359820000 1.0112450000 0.2602050000 0.0000050000 1.0468420000 0.0075000000 128656728 0 1784459264 4.2012128830 3.9274125099 3.9505975246 823 1311867197.8802978992 0.0995512158 0.0779800603 0.1208752468 0.0059968930 2.4078980000 1.0049990000 0.2201740000 0.1214310000 1.0427790000 0.0074250000 128658914 0 1783336960 4.1975741386 3.9281737804 3.9492754936 824 1311867197.9148609638 0.0990874916 0.0780056761 0.1208752468 0.0059979668 2.2930180000 1.0117760000 0.2148380000 0.0000040000 1.0485770000 0.0074000000 128661164 0 1782444032 4.1970615387 3.9297378063 3.9488518238 825 1311867197.9470140934 0.0982088149 0.0780301648 0.1208752468 0.0060012648 3.4609090000 1.0094360000 0.2192410000 0.1215640000 1.0415900000 1.0589540000 128663350 0 1784221696 4.1954908371 3.9290125370 3.9482016563 826 1311867197.9812700748 0.0983201787 0.0780547290 0.1208752468 0.0059976617 2.3406040000 1.0151740000 0.2641830000 0.0000040000 1.0427400000 0.0073690000 128665568 0 1783332864 4.1933474541 3.9292447567 3.9474763870 827 1311867198.0145471096 0.0982596353 0.0780791606 0.1208752468 0.0059953419 2.4049260000 1.0136230000 0.2123540000 0.1214910000 1.0396370000 0.0074070000 128667818 0 1782824960 4.1920413971 3.9305484295 3.9473292828 828 1311867198.0463368893 0.0975323021 0.0781026547 0.1208752468 0.0059930256 2.2565750000 1.0181750000 0.1813230000 0.0000050000 1.0393850000 0.0074220000 128669972 0 1784586240 4.1905851364 3.9297392368 3.9467198849 829 1311867198.0787069798 0.0978969932 0.0781265321 0.1208752468 0.0059926949 3.5485970000 1.0142930000 0.3070610000 0.1215060000 1.0386780000 1.0558450000 128672190 0 1783484416 4.1884188652 3.9305205345 3.9461765289 830 1311867198.1143770218 0.0956694633 0.0781476681 0.1208752468 0.0059902396 2.5235830000 1.0137930000 0.4553580000 0.0000040000 1.0366240000 0.0073610000 128674408 0 1782599680 4.1890826225 3.9309699535 3.9460034370 831 1311867198.1463611126 0.0971668884 0.0781705553 0.1208752468 0.0059867573 2.4407340000 1.0142730000 0.2521400000 0.1217510000 1.0348890000 0.0074120000 128676594 0 1784209408 4.1852235794 3.9313743114 3.9452044964 832 1311867198.1822519302 0.0962258130 0.0781922563 0.1208752468 0.0059834424 2.3735810000 1.0508980000 0.2682010000 0.0000040000 1.0358710000 0.0074160000 128678844 0 1783107584 4.1840243340 3.9318902493 3.9444746971 833 1311867198.2144989967 0.0963143930 0.0782140116 0.1208752468 0.0059866019 3.4947070000 1.0134350000 0.2558000000 0.1215990000 1.0348000000 1.0585850000 128681030 0 1782464512 4.1819810867 3.9320778847 3.9439501762 834 1311867198.2464120388 0.0957555324 0.0782350446 0.1208752468 0.0059844363 2.4178190000 1.0129740000 0.3495460000 0.0000040000 1.0376280000 0.0073720000 128683216 0 1784074240 4.1804070473 3.9317109585 3.9431047440 835 1311867198.2821578979 0.0954289138 0.0782556360 0.1208752468 0.0059815280 2.5277630000 1.0105670000 0.3351900000 0.1217100000 1.0417010000 0.0073570000 128685466 0 1782972416 4.1785178185 3.9326024055 3.9425127506 836 1311867198.3159120083 0.0947459266 0.0782753612 0.1208752468 0.0059809404 2.2907630000 1.0063990000 0.2255650000 0.0000040000 1.0407570000 0.0073930000 128687652 0 1782210560 4.1770625114 3.9333872795 3.9415819645 837 1311867198.3481218815 0.0934627950 0.0782935063 0.1208752468 0.0059784877 3.6803540000 1.0022320000 0.4495310000 0.1215470000 1.0422400000 1.0531020000 128689838 0 1783820288 4.1759824753 3.9326536655 3.9409961700 838 1311867198.3828320503 0.0938486829 0.0783120686 0.1208752468 0.0059800228 2.3590010000 1.0045500000 0.2990130000 0.0000050000 1.0377800000 0.0073440000 128692088 0 1785470976 4.1732077599 3.9343194962 3.9399900436 839 1311867198.4242680073 0.0927204713 0.0783292419 0.1208752468 0.0059825661 2.4491930000 1.0102330000 0.2609110000 0.1222000000 1.0370870000 0.0074310000 128694306 0 1784496128 4.1712841988 3.9348223209 3.9389402866 840 1311867198.4497859478 0.0921353996 0.0783456778 0.1208752468 0.0059795015 2.2825600000 1.0055960000 0.2195190000 0.0000040000 1.0395960000 0.0073800000 128696332 0 1783988224 4.1694569588 3.9328732491 3.9380195141 841 1311867198.4856219292 0.0938281640 0.0783640874 0.1208752468 0.0059856580 3.5410300000 1.0026380000 0.3000770000 0.1217900000 1.0451710000 1.0610290000 128698518 0 1785602048 4.1649513245 3.9345219135 3.9368810654 842 1311867198.5190339088 0.0935285166 0.0783820974 0.1208752468 0.0059833456 2.2789510000 0.9931940000 0.2233060000 0.0000040000 1.0437160000 0.0073050000 128700736 0 1784496128 4.1628313065 3.9358546734 3.9360537529 843 1311867198.5499279499 0.0920621380 0.0783983252 0.1208752468 0.0059839389 2.6327790000 1.0104830000 0.4376330000 0.1221730000 1.0446460000 0.0072950000 128702922 0 1783726080 4.1614470482 3.9346158504 3.9350178242 844 1311867198.5824239254 0.0909883976 0.0784132424 0.1208752468 0.0059814239 2.3025730000 0.9847220000 0.2552320000 0.0000040000 1.0449030000 0.0072800000 128705108 0 1785356288 4.1604123116 3.9366500378 3.9341995716 845 1311867198.6147489548 0.0899347067 0.0784268772 0.1208752468 0.0059831533 3.5395540000 1.0022650000 0.2989820000 0.1218780000 1.0432110000 1.0618520000 128707294 0 1784250368 4.1589770317 3.9363398552 3.9334607124 846 1311867198.6482009888 0.0900367126 0.0784406005 0.1208752468 0.0059807023 2.3542570000 0.9931020000 0.2919090000 0.0000050000 1.0512370000 0.0073540000 128709480 0 1783484416 4.1563763618 3.9373202324 3.9325518608 847 1311867198.6827540398 0.0905921832 0.0784549471 0.1208752468 0.0059784783 2.3994150000 0.9923320000 0.2222730000 0.1219600000 1.0450970000 0.0072740000 128711698 0 1785090048 4.1531119347 3.9382848740 3.9315717220 848 1311867198.7146520615 0.0902976468 0.0784689125 0.1208752468 0.0059749675 2.2792580000 0.9941250000 0.2164180000 0.0000040000 1.0501510000 0.0073380000 128713852 0 1784242176 4.1515264511 3.9389567375 3.9311108589 849 1311867198.7467699051 0.0905508995 0.0784831434 0.1208752468 0.0059725285 3.6822240000 0.9954050000 0.4503060000 0.1218520000 1.0423920000 1.0616830000 128716006 0 1783230464 4.1490030289 3.9386024475 3.9303104877 850 1311867198.7842700481 0.0895780474 0.0784961962 0.1208752468 0.0059693268 2.3050840000 0.9911650000 0.2517530000 0.0000050000 1.0443450000 0.0073730000 128718256 0 1784840192 4.1481342316 3.9400360584 3.9298563004 851 1311867198.8149418831 0.0920255482 0.0785120944 0.1208752468 0.0059666006 2.4365890000 0.9946430000 0.2545060000 0.1221430000 1.0466220000 0.0072970000 128720410 0 1783697408 4.1425304413 3.9405372143 3.9284901619 852 1311867198.8464009762 0.0925100893 0.0785285239 0.1208752468 0.0059638719 2.4082390000 0.9949780000 0.3464180000 0.0000050000 1.0488820000 0.0072890000 128722596 0 1782956032 4.1400756836 3.9413135052 3.9277377129 853 1311867198.8845369816 0.0920952782 0.0785444287 0.1208752468 0.0059612768 3.4833520000 0.9847670000 0.2540730000 0.1218280000 1.0468400000 1.0652450000 128724814 0 1784602624 4.1390261650 3.9422426224 3.9271783829 854 1311867198.9147930145 0.0928629115 0.0785611951 0.1208752468 0.0059578504 2.3265030000 1.0018340000 0.2578380000 0.0000040000 1.0481370000 0.0072980000 128726968 0 1783443456 4.1365919113 3.9431025982 3.9263565540 855 1311867198.9465179443 0.0937010944 0.0785789026 0.1208752468 0.0059545339 2.4805100000 0.9932220000 0.2976220000 0.1219080000 1.0498310000 0.0073900000 128729154 0 1782972416 4.1339945793 3.9443335533 3.9253065586 856 1311867198.9839329720 0.0940730199 0.0785970032 0.1208752468 0.0059513551 2.4089150000 1.0026870000 0.3364450000 0.0000050000 1.0520270000 0.0073980000 128731468 0 1784627200 4.1316761971 3.9450407028 3.9244725704 857 1311867199.0148730278 0.0952189118 0.0786163986 0.1208752468 0.0059524633 3.5264100000 0.9989130000 0.2600940000 0.1219720000 1.0549520000 1.0790780000 128733622 0 1783865344 4.1286296844 3.9461903572 3.9234097004 858 1311867199.0468010902 0.0968928784 0.0786376999 0.1208752468 0.0059538021 2.3245660000 0.9886360000 0.2598190000 0.0000040000 1.0581380000 0.0073120000 128735808 0 1783603200 4.1262736320 3.9473433495 3.9225463867 859 1311867199.0849320889 0.0964852870 0.0786584770 0.1208752468 0.0059540847 2.4650770000 0.9991540000 0.2611340000 0.1219520000 1.0648880000 0.0073940000 128738122 0 1785344000 4.1255788803 3.9485559464 3.9217295647 860 1311867199.1149818897 0.0977589786 0.0786806869 0.1208752468 0.0059514370 2.3455920000 1.0051890000 0.2601020000 0.0000050000 1.0614500000 0.0073980000 128740244 0 1784619008 4.1228523254 3.9490263462 3.9205803871 861 1311867199.1465420723 0.0991176292 0.0787044232 0.1208752468 0.0059488699 3.5038120000 0.9964830000 0.2205120000 0.1222840000 1.0702880000 1.0836160000 128742430 0 1784365056 4.1205320358 3.9504902363 3.9193143845 862 1311867199.1823658943 0.1004752144 0.0787296794 0.1208752468 0.0059475042 2.3680540000 0.9816890000 0.2985360000 0.0000050000 1.0690640000 0.0072850000 128744680 0 1783599104 4.1183176041 3.9527571201 3.9181077480 863 1311867199.2146680355 0.1015730575 0.0787561491 0.1208752468 0.0059442610 2.5086950000 0.9943390000 0.3040840000 0.1219800000 1.0702630000 0.0074310000 128746898 0 1783476224 4.1155896187 3.9528613091 3.9168469906 864 1311867199.2467749119 0.1017129123 0.0787827194 0.1208752468 0.0059410111 2.2976000000 0.9879700000 0.2181130000 0.0000050000 1.0736720000 0.0073870000 128749052 0 1785106432 4.1144905090 3.9542510509 3.9159495831 865 1311867199.2833590508 0.1018062755 0.0788093362 0.1208752468 0.0059375895 3.5041720000 0.9860920000 0.2108950000 0.1217100000 1.0807990000 1.0930490000 128751334 0 1784197120 4.1129412651 3.9550929070 3.9148459435 866 1311867199.3159129620 0.1024150699 0.0788365946 0.1208752468 0.0059376345 2.5272730000 0.9840280000 0.4487470000 0.0000050000 1.0764460000 0.0072660000 128753456 0 1784111104 4.1109423637 3.9555084705 3.9135770798 867 1311867199.3465209007 0.1030907258 0.0788645694 0.1208752468 0.0059344531 2.5850080000 0.9954340000 0.3676230000 0.1220230000 1.0810940000 0.0073620000 128755610 0 1783349248 4.1088309288 3.9561460018 3.9123408794 868 1311867199.3829050064 0.1031697169 0.0788925707 0.1208752468 0.0059314046 2.4009630000 1.0064760000 0.2925560000 0.0000040000 1.0837890000 0.0073650000 128757892 0 1783091200 4.1069021225 3.9567792416 3.9112167358 869 1311867199.4147589207 0.1029909998 0.0789203019 0.1208752468 0.0059280310 3.5775750000 1.0000110000 0.2542060000 0.1220110000 1.0857670000 1.1049620000 128760046 0 1784844288 4.1050658226 3.9564580917 3.9100301266 870 1311867199.4512910843 0.1032719389 0.0789482923 0.1208752468 0.0059252293 2.3121270000 0.9808640000 0.2171060000 0.0000050000 1.0954000000 0.0073310000 128762328 0 1783955456 4.1026415825 3.9576449394 3.9086480141 871 1311867199.4837360382 0.1020537540 0.0789748198 0.1208752468 0.0059227838 2.6535990000 0.9776330000 0.4442640000 0.1221770000 1.0911220000 0.0074760000 128764514 0 1783730176 4.1021761894 3.9578564167 3.9079227448 872 1311867199.5150198936 0.1018505543 0.0790010535 0.1208752468 0.0059195533 2.4421260000 1.0155090000 0.2926650000 0.0000050000 1.1160160000 0.0072380000 128766700 0 1785470976 4.1004137993 3.9578928947 3.9070897102 873 1311867199.5544059277 0.1019942835 0.0790273916 0.1208752468 0.0059182742 3.5762960000 0.9816480000 0.2490010000 0.1219090000 1.0930480000 1.1190350000 128769014 0 1784745984 4.0976772308 3.9589364529 3.9061372280 874 1311867199.5835030079 0.1023049802 0.0790540250 0.1208752468 0.0059149711 2.3248340000 0.9931890000 0.2205270000 0.0000040000 1.0931410000 0.0072860000 128771168 0 1784602624 4.0951118469 3.9595243931 3.9054191113 875 1311867199.6158308983 0.1019374356 0.0790801775 0.1208752468 0.0059125011 2.6646020000 0.9823240000 0.4511370000 0.1224960000 1.0898030000 0.0073150000 128773290 0 1783713792 4.0926609039 3.9594142437 3.9047772884 876 1311867199.6538460255 0.1003165096 0.0791044199 0.1208752468 0.0059102636 2.3704730000 1.0141430000 0.2502850000 0.0000050000 1.0879480000 0.0073580000 128775604 0 1783476224 4.0917129517 3.9596321583 3.9044532776 877 1311867199.6824479103 0.1005547717 0.0791288787 0.1208752468 0.0059071037 3.5646650000 0.9840810000 0.2515100000 0.1224920000 1.0852250000 1.1106680000 128777726 0 1785253888 4.0890603065 3.9593672752 3.9038987160 878 1311867199.7146759033 0.0995540395 0.0791521419 0.1208752468 0.0059046371 2.3012990000 0.9779250000 0.2193150000 0.0000050000 1.0850260000 0.0073350000 128779944 0 1784365056 4.0876312256 3.9596269131 3.9034249783 879 1311867199.7511539459 0.0993806198 0.0791751550 0.1208752468 0.0059022206 2.4627640000 0.9759110000 0.2588240000 0.1225240000 1.0874260000 0.0072290000 128782162 0 1783861248 4.0852928162 3.9605631828 3.9031515121 880 1311867199.7826020718 0.0997390598 0.0791985231 0.1208752468 0.0059001978 2.3227950000 0.9678340000 0.2572920000 0.0000050000 1.0796900000 0.0072700000 128784348 0 1785618432 4.0821681023 3.9598398209 3.9026131630 881 1311867199.8150150776 0.0985751823 0.0792205170 0.1208752468 0.0059025533 3.7441370000 0.9867980000 0.4379230000 0.1228630000 1.0853080000 1.0994700000 128786534 0 1784492032 4.0804443359 3.9593868256 3.9020669460 882 1311867199.8519051075 0.0982895643 0.0792421373 0.1208752468 0.0058995838 2.3705030000 0.9787200000 0.2965240000 0.0000050000 1.0771620000 0.0073060000 128788784 0 1784225792 4.0785541534 3.9605815411 3.9018027782 883 1311867199.8839609623 0.0979576930 0.0792633327 0.1208752468 0.0058999633 2.5338930000 0.9751800000 0.3365870000 0.1275630000 1.0756910000 0.0072190000 128791002 0 1783468032 4.0760612488 3.9595153332 3.9014275074 884 1311867199.9148159027 0.0977400169 0.0792842339 0.1208752468 0.0058979443 2.2361280000 0.9662980000 0.1767660000 0.0000050000 1.0749260000 0.0073420000 128793188 0 1782935552 4.0737495422 3.9593224525 3.9011130333 885 1311867199.9520709515 0.0969754010 0.0793042239 0.1208752468 0.0058948555 3.4812290000 0.9603780000 0.2181230000 0.1219380000 1.0785700000 1.0914600000 128795438 0 1784602624 4.0727910995 3.9601864815 3.9009249210 886 1311867199.9828410149 0.0957470015 0.0793227824 0.1208752468 0.0058932475 2.3673770000 0.9778220000 0.2990800000 0.0000050000 1.0716110000 0.0072740000 128797592 0 1783443456 4.0714631081 3.9589848518 3.9005208015 887 1311867200.0144031048 0.0950082913 0.0793404661 0.1208752468 0.0058910126 2.4633450000 0.9692080000 0.2814730000 0.1224080000 1.0721220000 0.0072700000 128799778 0 1782951936 4.0700073242 3.9593851566 3.9002122879 888 1311867200.0539638996 0.0946414918 0.0793576970 0.1208752468 0.0058899490 2.4182140000 0.9672430000 0.3613950000 0.0000050000 1.0710250000 0.0072600000 128802092 0 1784745984 4.0682892799 3.9612417221 3.9001607895 889 1311867200.0830330849 0.0943947285 0.0793746116 0.1208752468 0.0058873811 3.4612950000 0.9731030000 0.2001530000 0.1226200000 1.0681780000 1.0854970000 128804214 0 1783840768 4.0660972595 3.9598150253 3.9001908302 890 1311867200.1174468994 0.0947218165 0.0793918556 0.1208752468 0.0058863138 2.3124520000 0.9688450000 0.2526400000 0.0000050000 1.0725570000 0.0071790000 128806432 0 1782951936 4.0629343987 3.9609367847 3.9000282288 891 1311867200.1517000198 0.0927497596 0.0794068476 0.1208752468 0.0058863772 2.6125030000 0.9736060000 0.4344690000 0.1222100000 1.0641680000 0.0072290000 128808650 0 1784709120 4.0632762909 3.9612236023 3.9003374577 892 1311867200.1853220463 0.0932736695 0.0794223934 0.1208752468 0.0058865284 2.2967630000 0.9560030000 0.2532510000 0.0000050000 1.0631790000 0.0126080000 128810900 0 1783590912 4.0600590706 3.9600076675 3.9003236294 893 1311867200.2179059982 0.0919660181 0.0794364400 0.1208752468 0.0058859126 3.5415950000 0.9641500000 0.2967930000 0.1225490000 1.0640330000 1.0830870000 128813086 0 1782681600 4.0599136353 3.9617960453 3.9005005360 894 1311867200.2522649765 0.0916467085 0.0794500980 0.1208752468 0.0058826790 2.4750430000 0.9585140000 0.4334530000 0.0000050000 1.0648780000 0.0072710000 128815304 0 1784459264 4.0578584671 3.9616968632 3.9010183811 895 1311867200.2825429440 0.0902317390 0.0794621446 0.1208752468 0.0058816563 2.4622540000 0.9686120000 0.2936530000 0.1222410000 1.0587040000 0.0072490000 128817458 0 1783361536 4.0567426682 3.9606885910 3.9013552666 896 1311867200.3148880005 0.0900954455 0.0794740121 0.1208752468 0.0058785676 2.2903490000 0.9667080000 0.2432520000 0.0000050000 1.0621780000 0.0072860000 128819676 0 1782853632 4.0549354553 3.9621229172 3.9018292427 897 1311867200.3514990807 0.0883453712 0.0794839021 0.1208752468 0.0058785671 3.5963440000 0.9650830000 0.3697870000 0.1220180000 1.0550040000 1.0737310000 128821894 0 1784455168 4.0539994240 3.9602711201 3.9024722576 898 1311867200.3837759495 0.0877752081 0.0794931352 0.1208752468 0.0058846747 2.4078780000 0.9711490000 0.3622890000 0.0000040000 1.0554070000 0.0072380000 128824112 0 1783463936 4.0522966385 3.9611787796 3.9028840065 899 1311867200.4162800312 0.0875976607 0.0795021503 0.1208752468 0.0058821485 2.5962150000 0.9681640000 0.4371210000 0.1222970000 1.0504870000 0.0072130000 128826266 0 1782722560 4.0499744415 3.9610114098 3.9032170773 900 1311867200.4522490501 0.0871786326 0.0795106797 0.1208752468 0.0058799419 2.4756290000 0.9683310000 0.4389160000 0.0000050000 1.0502980000 0.0071880000 128828516 0 1784193024 4.0470929146 3.9601697922 3.9033465385 901 1311867200.4850699902 0.0869842768 0.0795189745 0.1208752468 0.0058805888 3.4668120000 0.9934090000 0.2159560000 0.1220510000 1.0492220000 1.0743740000 128830702 0 1783078912 4.0445775986 3.9606773853 3.9037077427 902 1311867200.5143918991 0.0865111575 0.0795267263 0.1208752468 0.0058784974 2.3513090000 0.9571760000 0.3289520000 0.0000040000 1.0468240000 0.0072420000 128832888 0 1782300672 4.0423974991 3.9596624374 3.9043743610 903 1311867200.5505030155 0.0864775702 0.0795344238 0.1208752468 0.0058818984 2.5941650000 0.9632910000 0.4392200000 0.1220680000 1.0515750000 0.0071870000 128835138 0 1784078336 4.0393052101 3.9601931572 3.9047775269 904 1311867200.5832219124 0.0875121132 0.0795432487 0.1208752468 0.0058867083 2.3402310000 0.9538840000 0.3244910000 0.0000050000 1.0428760000 0.0072670000 128837324 0 1782956032 4.0359315872 3.9609057903 3.9053258896 905 1311867200.6145610809 0.0875084177 0.0795520500 0.1208752468 0.0058855564 3.6458250000 0.9657040000 0.4432830000 0.1218680000 1.0447020000 1.0591250000 128839478 0 1782194176 4.0327062607 3.9600012302 3.9059083462 906 1311867200.6504778862 0.0862139761 0.0795594031 0.1208752468 0.0058849053 2.4621670000 0.9629400000 0.4440600000 0.0000040000 1.0370800000 0.0073240000 128841728 0 1783840768 4.0312752724 3.9602620602 3.9064581394 907 1311867200.6851279736 0.0860352218 0.0795665429 0.1208752468 0.0058821225 2.3600260000 0.9633910000 0.2222770000 0.1222130000 1.0339810000 0.0071920000 128843978 0 1785454592 4.0284337997 3.9600913525 3.9067876339 908 1311867200.7189719677 0.0867719799 0.0795744784 0.1208752468 0.0058802216 2.4152180000 0.9590710000 0.4059570000 0.0000040000 1.0310660000 0.0072560000 128846196 0 1784340480 4.0244007111 3.9599037170 3.9071228504 909 1311867200.7503669262 0.0878049135 0.0795835328 0.1208752468 0.0058777371 3.6095140000 0.9506950000 0.4482440000 0.1217990000 1.0295470000 1.0482200000 128848350 0 1783590912 4.0206146240 3.9607470036 3.9075262547 910 1311867200.7832930088 0.0872369260 0.0795919431 0.1208752468 0.0058820316 2.3637710000 0.9653350000 0.3557360000 0.0000040000 1.0245190000 0.0072560000 128850568 0 1785217024 4.0187287331 3.9607887268 3.9080855846 911 1311867200.8181068897 0.0871670097 0.0796002583 0.1208752468 0.0058798183 2.5837560000 0.9741590000 0.4461860000 0.1218730000 1.0224320000 0.0072910000 128852786 0 1784078336 4.0152401924 3.9605619907 3.9084234238 912 1311867200.8501501083 0.0876855031 0.0796091237 0.1208752468 0.0058769957 2.2154130000 0.9603410000 0.2163370000 0.0000050000 1.0204980000 0.0072660000 128854940 0 1783209984 4.0123710632 3.9612100124 3.9089343548 913 1311867200.8845369816 0.0875968114 0.0796178725 0.1208752468 0.0058764498 3.5438270000 0.9669960000 0.3934360000 0.1218360000 1.0151060000 1.0354620000 128857222 0 1784979456 4.0096373558 3.9608905315 3.9096119404 914 1311867200.9194929600 0.0889450610 0.0796280773 0.1208752468 0.0058758680 2.4532970000 0.9650670000 0.4463090000 0.0000050000 1.0228450000 0.0072050000 128859440 0 1784111104 4.0054125786 3.9600579739 3.9101097584 915 1311867200.9512679577 0.0884795561 0.0796377510 0.1208752468 0.0058747819 2.5433840000 0.9552430000 0.4310220000 0.1225710000 1.0162340000 0.0072860000 128861594 0 1783353344 4.0033574104 3.9601228237 3.9105868340 916 1311867200.9856009483 0.0888376161 0.0796477946 0.1208752468 0.0058761925 2.4631410000 0.9874100000 0.4334190000 0.0000040000 1.0235330000 0.0078530000 128863844 0 1785200640 4.0017313957 3.9594068527 3.9107902050 917 1311867201.0184400082 0.0891684070 0.0796581769 0.1208752468 0.0058729989 3.4760500000 0.9636220000 0.3153410000 0.1217540000 1.0216000000 1.0417550000 128866030 0 1784348672 3.9998505116 3.9594931602 3.9108376503 918 1311867201.0555179119 0.0892580450 0.0796686343 0.1208752468 0.0058715272 2.4252940000 0.9586870000 0.4242320000 0.0000040000 1.0239990000 0.0071670000 128868312 0 1783611392 3.9982259274 3.9597740173 3.9107177258 919 1311867201.0825428963 0.0900732949 0.0796799560 0.1208752468 0.0058714348 2.5475620000 0.9553130000 0.4248170000 0.1216540000 1.0276190000 0.0071860000 128870402 0 1785221120 3.9958848953 3.9591391087 3.9107728004 920 1311867201.1193449497 0.0906166881 0.0796918438 0.1208752468 0.0058691702 2.4577320000 0.9832160000 0.4259200000 0.0000040000 1.0292640000 0.0072850000 128872684 0 1784123392 3.9939389229 3.9590878487 3.9108383656 921 1311867201.1506710052 0.0906166062 0.0797037056 0.1208752468 0.0058660993 3.3871420000 0.9488210000 0.2135560000 0.1215740000 1.0345410000 1.0572300000 128874806 0 1783218176 3.9929091930 3.9593181610 3.9107732773 922 1311867201.1830160618 0.0904733092 0.0797153863 0.1208752468 0.0058641614 2.2454810000 0.9467870000 0.2466320000 0.0000040000 1.0339460000 0.0071760000 128876992 0 1784963072 3.9918019772 3.9587976933 3.9108603001 923 1311867201.2196528912 0.0916200504 0.0797282841 0.1208752468 0.0058625014 2.5492120000 0.9495150000 0.4209730000 0.1214730000 1.0380700000 0.0072650000 128879210 0 1784094720 3.9888026714 3.9597630501 3.9106700420 924 1311867201.2503149509 0.0912429467 0.0797407459 0.1208752468 0.0058593337 2.4299960000 0.9512880000 0.4197250000 0.0000050000 1.0406180000 0.0071920000 128881396 0 1783336960 3.9880225658 3.9599678516 3.9108912945 925 1311867201.2824099064 0.0905357003 0.0797524161 0.1208752468 0.0058568403 3.6065860000 0.9325370000 0.4351340000 0.1213770000 1.0403490000 1.0662370000 128883582 0 1785073664 3.9873163700 3.9604694843 3.9106371403 926 1311867201.3180539608 0.0904457569 0.0797639640 0.1208752468 0.0058548973 2.2451340000 0.9397650000 0.2420990000 0.0000040000 1.0440210000 0.0071800000 128885832 0 1784242176 3.9850897789 3.9590389729 3.9106056690 927 1311867201.3522200584 0.0913658515 0.0797764795 0.1208752468 0.0058544080 2.5589870000 0.9438630000 0.4224280000 0.1218340000 1.0525330000 0.0072070000 128888050 0 1783353344 3.9821522236 3.9605991840 3.9103672504 928 1311867201.3842790127 0.0908162221 0.0797883758 0.1208752468 0.0058543857 2.2915950000 0.9453980000 0.2815880000 0.0000050000 1.0463930000 0.0072410000 128890236 0 1785094144 3.9806761742 3.9621868134 3.9103596210 929 1311867201.4198760986 0.0903789103 0.0797997757 0.1208752468 0.0058730822 3.4092640000 0.9527780000 0.2138520000 0.1216860000 1.0470290000 1.0618010000 128892422 0 1784098816 3.9772322178 3.9605302811 3.9099326134 930 1311867201.4558579922 0.0907597989 0.0798115607 0.1208752468 0.0058751933 2.4426730000 0.9504540000 0.4281180000 0.0000050000 1.0455070000 0.0071620000 128894608 0 1783230464 3.9738066196 3.9617512226 3.9097485542 931 1311867201.4853110313 0.0911447182 0.0798237338 0.1208752468 0.0058745150 2.3836690000 0.9574030000 0.2450720000 0.1216930000 1.0412330000 0.0072890000 128896762 0 1784860672 3.9713759422 3.9643654823 3.9097013474 932 1311867201.5198690891 0.0906530172 0.0798353532 0.1208752468 0.0058730849 2.3955320000 0.9519890000 0.3908480000 0.0000050000 1.0334000000 0.0072560000 128899012 0 1783316480 3.9685504436 3.9633369446 3.9098086357 933 1311867201.5527739525 0.0916609839 0.0798480280 0.1208752468 0.0058717405 3.5894930000 0.9481610000 0.4270380000 0.1216190000 1.0311700000 1.0501190000 128901166 0 1782587392 3.9641554356 3.9638059139 3.9094679356 934 1311867201.5840220451 0.0909589529 0.0798599241 0.1208752468 0.0058686922 2.4242670000 0.9536320000 0.4246580000 0.0000050000 1.0277150000 0.0071790000 128903352 0 1784193024 3.9627459049 3.9640507698 3.9093868732 935 1311867201.6197049618 0.0905836150 0.0798713933 0.1208752468 0.0058659299 2.4002160000 0.9512450000 0.2850130000 0.1214640000 1.0233060000 0.0072510000 128905602 0 1783238656 3.9608845711 3.9642653465 3.9090077877 936 1311867201.6515579224 0.0892971382 0.0798814635 0.1208752468 0.0058651072 2.4272710000 0.9519700000 0.4366410000 0.0000050000 1.0201410000 0.0072190000 128907756 0 1781940224 3.9599928856 3.9638857841 3.9088070393 937 1311867201.6839449406 0.0899688378 0.0798922291 0.1208752468 0.0058620316 3.5755840000 0.9489100000 0.4363220000 0.1216160000 1.0193630000 1.0382840000 128909974 0 1783676928 3.9569025040 3.9648299217 3.9083354473 938 1311867201.7189009190 0.0905050188 0.0799035434 0.1208752468 0.0058617267 2.3424290000 0.9476100000 0.3534860000 0.0000050000 1.0230230000 0.0072100000 128912224 0 1785344000 3.9548335075 3.9663255215 3.9083266258 939 1311867201.7507290840 0.0897078440 0.0799139846 0.1208752468 0.0058601097 2.5299470000 0.9503480000 0.4259080000 0.1216030000 1.0127130000 0.0072270000 128914410 0 1784225792 3.9532670975 3.9655134678 3.9079835415 940 1311867201.7858049870 0.0898161307 0.0799245188 0.1208752468 0.0058633022 2.4198090000 0.9430180000 0.4396060000 0.0000040000 1.0186400000 0.0073140000 128916596 0 1783066624 3.9505789280 3.9659540653 3.9077270031 941 1311867201.8190178871 0.0897119790 0.0799349199 0.1208752468 0.0058697933 3.4802620000 0.9486760000 0.3556920000 0.1218830000 1.0115860000 1.0313260000 128918846 0 1784692736 3.9501311779 3.9689052105 3.9079136848 942 1311867201.8505740166 0.0893018693 0.0799448636 0.1208752468 0.0058723270 2.3672390000 0.9526360000 0.3888100000 0.0000050000 1.0064690000 0.0072310000 128921000 0 1783738368 3.9486677647 3.9678287506 3.9076280594 943 1311867201.8862850666 0.0891121477 0.0799545850 0.1208752468 0.0058695273 2.5077470000 0.9452410000 0.4157780000 0.1215780000 1.0065900000 0.0072290000 128923218 0 1782579200 3.9476432800 3.9677953720 3.9075305462 944 1311867201.9195730686 0.0898374766 0.0799650542 0.1208752468 0.0058693153 2.4018250000 0.9465220000 0.4299630000 0.0000050000 1.0069620000 0.0071540000 128925468 0 1784184832 3.9459624290 3.9690806866 3.9073824883 945 1311867201.9516520500 0.0896882564 0.0799753433 0.1208752468 0.0058672940 3.5422660000 0.9456470000 0.4284450000 0.1214460000 1.0048610000 1.0298180000 128927590 0 1783214080 3.9446730614 3.9685907364 3.9068589211 946 1311867201.9894599915 0.0886073038 0.0799844680 0.1208752468 0.0058647350 2.3210250000 0.9393050000 0.3563030000 0.0000050000 1.0069630000 0.0072540000 128929904 0 1781968896 3.9449355602 3.9686746597 3.9062702656 947 1311867202.0184879303 0.0891793296 0.0799941774 0.1208752468 0.0058621602 2.4918880000 0.9383630000 0.3989640000 0.1221760000 1.0085600000 0.0126980000 128932026 0 1783463936 3.9432346821 3.9692151546 3.9057703018 948 1311867202.0507359505 0.0883415714 0.0800029827 0.1208752468 0.0058599139 2.3959260000 0.9385460000 0.4314560000 0.0000050000 1.0075860000 0.0071790000 128934212 0 1785208832 3.9436359406 3.9698710442 3.9052696228 949 1311867202.0866351128 0.0888658687 0.0800123219 0.1208752468 0.0058571299 3.5460700000 0.9364800000 0.4327780000 0.1213290000 1.0085130000 1.0345350000 128936462 0 1784246272 3.9420509338 3.9702043533 3.9048826694 950 1311867202.1185920238 0.0897379443 0.0800225594 0.1208752468 0.0058552729 2.2146570000 0.9367200000 0.2503900000 0.0000050000 1.0090440000 0.0072080000 128938648 0 1783087104 3.9394421577 3.9706122875 3.9046084881 951 1311867202.1516621113 0.0896109045 0.0800326418 0.1208752468 0.0058533408 2.5215850000 0.9438810000 0.4257640000 0.1216510000 1.0118850000 0.0073450000 128940866 0 1784725504 3.9386525154 3.9718084335 3.9046695232 952 1311867202.1866259575 0.0879628882 0.0800409719 0.1208752468 0.0058511721 2.3851340000 0.9418530000 0.4200730000 0.0000040000 1.0038660000 0.0071730000 128943084 0 1783582720 3.9394683838 3.9718186855 3.9046401978 953 1311867202.2191269398 0.0891569704 0.0800505374 0.1208752468 0.0058489819 3.5560400000 0.9516500000 0.4399940000 0.1214270000 1.0086810000 1.0228710000 128945270 0 1783476224 3.9365558624 3.9721879959 3.9044759274 954 1311867202.2513220310 0.0887368768 0.0800596426 0.1208752468 0.0058462131 2.3252290000 0.9398080000 0.3645420000 0.0000050000 1.0024300000 0.0071830000 128947424 0 1785090048 3.9358582497 3.9729607105 3.9046242237 955 1311867202.2868280411 0.0880465284 0.0800680058 0.1208752468 0.0058442993 2.3428190000 0.9610880000 0.2417620000 0.1217210000 0.9987690000 0.0071980000 128949674 0 1784365056 3.9353959560 3.9738941193 3.9046127796 956 1311867202.3199880123 0.0886782035 0.0800770123 0.1208752468 0.0058428295 2.2363780000 0.9440080000 0.2779130000 0.0000040000 0.9958580000 0.0071570000 128951860 0 1784238080 3.9328620434 3.9723446369 3.9045815468 957 1311867202.3523900509 0.0882196277 0.0800855208 0.1208752468 0.0058402927 3.5301190000 0.9430420000 0.4341690000 0.1218700000 1.0005520000 1.0182460000 128954046 0 1783476224 3.9318223000 3.9727230072 3.9044141769 958 1311867202.3883628845 0.0880176574 0.0800938007 0.1208752468 0.0058374301 2.4168500000 0.9588260000 0.4415060000 0.0000050000 0.9976920000 0.0072580000 128956296 0 1783349248 3.9306757450 3.9742193222 3.9044294357 959 1311867202.4196391106 0.0881847739 0.0801022376 0.1208752468 0.0058358733 2.5104810000 0.9453830000 0.4295720000 0.1214100000 0.9956170000 0.0072350000 128958482 0 1784971264 3.9294672012 3.9738829136 3.9043841362 960 1311867202.4529430866 0.0881487876 0.0801106194 0.1208752468 0.0058332331 2.3986790000 0.9603980000 0.4198340000 0.0000050000 0.9988530000 0.0072540000 128960668 0 1784246272 3.9285204411 3.9728941917 3.9044508934 961 1311867202.4875710011 0.0887586847 0.0801196184 0.1208752468 0.0058328673 3.5178540000 0.9433370000 0.4183350000 0.1217330000 1.0016540000 1.0212410000 128962886 0 1784111104 3.9275088310 3.9739537239 3.9048268795 962 1311867202.5206449032 0.0890741646 0.0801289267 0.1208752468 0.0058475971 2.3972980000 0.9375320000 0.4295430000 0.0000050000 1.0107740000 0.0071890000 128965072 0 1783349248 3.9260511398 3.9747414589 3.9046280384 963 1311867202.5508940220 0.0895984322 0.0801387600 0.1208752468 0.0058446695 2.2996740000 0.9439520000 0.2093030000 0.1215170000 1.0062120000 0.0071600000 128967226 0 1783222272 3.9246065617 3.9743225574 3.9047858715 964 1311867202.5864949226 0.0902990699 0.0801492998 0.1208752468 0.0058539973 2.1799300000 0.9381090000 0.2082930000 0.0000050000 1.0149320000 0.0071900000 128969508 0 1784963072 3.9230971336 3.9735543728 3.9047687054 965 1311867202.6185030937 0.0904121995 0.0801599349 0.1208752468 0.0058551783 3.5642620000 0.9523950000 0.4255640000 0.1215720000 1.0157410000 1.0366000000 128971694 0 1784217600 3.9215993881 3.9735243320 3.9041659832 966 1311867202.6514449120 0.0914793387 0.0801716527 0.1208752468 0.0058599741 2.2364640000 0.9445550000 0.2423420000 0.0000060000 1.0308340000 0.0071540000 128973880 0 1784107008 3.9185950756 3.9745452404 3.9034304619 967 1311867202.6866559982 0.0910606459 0.0801829133 0.1208752468 0.0058575471 2.5610030000 0.9692400000 0.4233180000 0.1215150000 1.0273990000 0.0072550000 128976130 0 1783476224 3.9178552628 3.9752752781 3.9027669430 968 1311867202.7185359001 0.0913127512 0.0801944111 0.1208752468 0.0058550267 2.2424120000 0.9443000000 0.2428210000 0.0000050000 1.0366010000 0.0072060000 128978316 0 1783349248 3.9154670238 3.9738910198 3.9016184807 969 1311867202.7507350445 0.0909549892 0.0802055159 0.1208752468 0.0058530716 3.4054320000 0.9305350000 0.2391020000 0.1215440000 1.0404840000 1.0623140000 128980502 0 1785090048 3.9138360023 3.9728388786 3.9003045559 970 1311867202.7897169590 0.0915786996 0.0802172408 0.1208752468 0.0058504883 2.2259600000 0.9211600000 0.2349300000 0.0000050000 1.0502700000 0.0071570000 128982816 0 1784348672 3.9119753838 3.9738647938 3.8994386196 971 1311867202.8190000057 0.0918179974 0.0802291881 0.1208752468 0.0058491737 2.3196980000 0.9217070000 0.2010050000 0.1217580000 1.0566090000 0.0070770000 128984970 0 1783947264 3.9101760387 3.9740784168 3.8984038830 972 1311867202.8527579308 0.0909596086 0.0802402276 0.1208752468 0.0058462443 2.4302840000 0.9232120000 0.4223890000 0.0000050000 1.0653330000 0.0071070000 128987156 0 1783566336 3.9092016220 3.9738385677 3.8973979950 973 1311867202.8873219490 0.0905419439 0.0802508152 0.1208752468 0.0058455605 3.6287080000 0.9164040000 0.4125210000 0.1215310000 1.0711090000 1.0954560000 128989374 0 1783357440 3.9087481499 3.9755384922 3.8969774246 974 1311867202.9199879169 0.0901903883 0.0802610201 0.1208752468 0.0058431848 2.4146010000 0.9110400000 0.4156580000 0.0000050000 1.0694320000 0.0071240000 128991560 0 1784958976 3.9089245796 3.9760558605 3.8972415924 975 1311867202.9525690079 0.0908596590 0.0802718905 0.1208752468 0.0058467958 2.3800560000 0.9028550000 0.2706580000 0.1213620000 1.0656730000 0.0070980000 128993778 0 1784233984 3.9078676701 3.9751958847 3.8972828388 976 1311867202.9868710041 0.0889845714 0.0802808174 0.1208752468 0.0058521928 2.2691240000 0.9175020000 0.2720330000 0.0000050000 1.0609670000 0.0070600000 128995996 0 1784111104 3.9099099636 3.9756293297 3.8978264332 977 1311867203.0202019215 0.0894886479 0.0802902420 0.1208752468 0.0058492367 3.6041400000 0.9217430000 0.4135410000 0.1216610000 1.0524080000 1.0826190000 128998182 0 1783455744 3.9094579220 3.9759924412 3.8982067108 978 1311867203.0560851097 0.0900364667 0.0803002074 0.1208752468 0.0058525994 2.2579690000 0.9223630000 0.2743580000 0.0000050000 1.0425130000 0.0071180000 129000432 0 1783349248 3.9091744423 3.9732460976 3.8986840248 979 1311867203.0865778923 0.0904791504 0.0803106047 0.1208752468 0.0058510769 2.3170840000 0.9259850000 0.2060130000 0.1215230000 1.0450330000 0.0071940000 129002586 0 1784979456 3.9100430012 3.9734861851 3.8992044926 980 1311867203.1189930439 0.0900484771 0.0803205413 0.1208752468 0.0058575843 2.3428240000 0.9394680000 0.3510900000 0.0000050000 1.0326470000 0.0071470000 129004772 0 1784233984 3.9111342430 3.9715628624 3.8995175362 981 1311867203.1549820900 0.0907976925 0.0803312214 0.1208752468 0.0058627331 3.5895720000 0.9432020000 0.4256290000 0.1217730000 1.0347280000 1.0526080000 129007022 0 1783984128 3.9105618000 3.9696633816 3.8996155262 982 1311867203.1877939701 0.0925748572 0.0803436895 0.1208752468 0.0058953304 2.3415450000 0.9385810000 0.3489990000 0.0000060000 1.0343740000 0.0071390000 129009208 0 1783222272 3.9089283943 3.9679632187 3.8993945122 983 1311867203.2185909748 0.0929385498 0.0803565021 0.1208752468 0.0058953153 2.5366320000 0.9237680000 0.4275720000 0.1268140000 1.0397500000 0.0070780000 129011394 0 1783095296 3.9101240635 3.9696054459 3.8993434906 984 1311867203.2552030087 0.0932305530 0.0803695855 0.1208752468 0.0058936017 2.2903760000 0.9306760000 0.3059730000 0.0000050000 1.0350970000 0.0071090000 129013644 0 1784709120 3.9099712372 3.9674918652 3.8991365433 985 1311867203.2864799500 0.0936459601 0.0803830641 0.1208752468 0.0058930756 3.5807700000 0.9303180000 0.4144950000 0.1216850000 1.0434920000 1.0581950000 129015798 0 1783824384 3.9092843533 3.9662759304 3.8984699249 986 1311867203.3194670677 0.0928964615 0.0803957552 0.1208752468 0.0058905217 2.4015000000 0.9234350000 0.4206250000 0.0000050000 1.0385910000 0.0071750000 129018048 0 1783738368 3.9106812477 3.9661817551 3.8980600834 987 1311867203.3547461033 0.0925561413 0.0804080757 0.1208752468 0.0058886820 2.3126990000 0.9299460000 0.2064230000 0.1217780000 1.0357340000 0.0071650000 129020234 0 1785352192 3.9116704464 3.9663410187 3.8978402615 988 1311867203.3865599632 0.0917964578 0.0804196024 0.1208752468 0.0058915876 2.2512070000 0.9592450000 0.2415940000 0.0000050000 1.0306310000 0.0071420000 129022420 0 1784619008 3.9123568535 3.9646573067 3.8975963593 989 1311867203.4183609486 0.0914907306 0.0804307967 0.1208752468 0.0058977070 3.5729310000 0.9351590000 0.4244810000 0.1222460000 1.0291910000 1.0501800000 129024638 0 1784365056 3.9117684364 3.9606823921 3.8968040943 990 1311867203.4545118809 0.0922122747 0.0804426972 0.1208752468 0.0058958288 2.4008960000 0.9242160000 0.4152210000 0.0000050000 1.0418650000 0.0071140000 129026888 0 1783435264 3.9112684727 3.9604372978 3.8966209888 991 1311867203.4864439964 0.0912023708 0.0804535546 0.1208752468 0.0058942996 2.3121290000 0.9329560000 0.2073130000 0.1216990000 1.0312840000 0.0071680000 129029042 0 1783476224 3.9121649265 3.9584796429 3.8965001106 992 1311867203.5185539722 0.0916721821 0.0804648637 0.1208752468 0.0058958740 2.4076210000 0.9352040000 0.4213460000 0.0000050000 1.0323070000 0.0071270000 129031260 0 1784963072 3.9112277031 3.9553153515 3.8957600594 993 1311867203.5560259819 0.0922541842 0.0804767361 0.1208752468 0.0058933299 3.4127470000 0.9360100000 0.2407340000 0.1236570000 1.0421130000 1.0576210000 129033510 0 1784238080 3.9105911255 3.9531004429 3.8951263428 994 1311867203.5876550674 0.0923652574 0.0804886964 0.1208752468 0.0058909832 2.3136880000 0.9332700000 0.3178180000 0.0000050000 1.0437370000 0.0071240000 129035696 0 1784111104 3.9106993675 3.9522490501 3.8947944641 995 1311867203.6191980839 0.0922276676 0.0805004943 0.1208752468 0.0058892978 2.5163390000 0.9203170000 0.4201050000 0.1217690000 1.0345870000 0.0071670000 129037882 0 1783185408 3.9106109142 3.9496333599 3.8944892883 996 1311867203.6557719707 0.0909959599 0.0805110319 0.1208752468 0.0058867055 2.4089910000 0.9288560000 0.4186260000 0.0000050000 1.0425410000 0.0071650000 129040100 0 1783095296 3.9119498730 3.9469673634 3.8938214779 997 1311867203.6866750717 0.0924038589 0.0805229606 0.1208752468 0.0058850756 3.3942800000 0.9236470000 0.2396660000 0.1219420000 1.0383960000 1.0589470000 129042286 0 1784598528 3.9098212719 3.9455540180 3.8933224678 998 1311867203.7195260525 0.0913536996 0.0805338130 0.1208752468 0.0058832092 2.2639770000 0.9207460000 0.2818980000 0.0000050000 1.0417630000 0.0070840000 129044472 0 1783853056 3.9115202427 3.9437639713 3.8930883408 999 1311867203.7566421032 0.0917746052 0.0805450650 0.1208752468 0.0058806162 2.5406070000 0.9220290000 0.4367690000 0.1220380000 1.0408770000 0.0071420000 129046754 0 1783738368 3.9116652012 3.9425349236 3.8930456638 1000 1311867203.7867228985 0.0920190737 0.0805565391 0.1208752468 0.0058776977 2.3814660000 0.9253690000 0.3962370000 0.0000050000 1.0410540000 0.0071520000 129048908 0 1785479168 3.9112689495 3.9405157566 3.8927204609 1001 1311867203.8193860054 0.0915557891 0.0805675273 0.1208752468 0.0058749601 3.4437540000 0.9256530000 0.2792080000 0.1220310000 1.0415400000 1.0626410000 129051094 0 1784582144 3.9120748043 3.9391441345 3.8921890259 1002 1311867203.8572859764 0.0921771675 0.0805791138 0.1208752468 0.0058735156 2.2407450000 0.9299880000 0.2484140000 0.0000050000 1.0432520000 0.0071710000 129053376 0 1784074240 3.9114596844 3.9379565716 3.8914980888 1003 1311867203.8891890049 0.0922658965 0.0805907656 0.1208752468 0.0058712409 2.3743670000 0.9437380000 0.2426060000 0.1218590000 1.0474150000 0.0071110000 129055562 0 1785745408 3.9109609127 3.9360830784 3.8905489445 1004 1311867203.9188020229 0.0922078714 0.0806023364 0.1208752468 0.0058687997 2.3798320000 0.9305050000 0.3744810000 0.0000050000 1.0550800000 0.0071480000 129057716 0 1784999936 3.9107506275 3.9346113205 3.8897159100 1005 1311867203.9553489685 0.0928869769 0.0806145600 0.1208752468 0.0058662507 3.5999150000 0.9125200000 0.4066330000 0.1220710000 1.0600910000 1.0868120000 129059966 0 1784725504 3.9102933407 3.9357213974 3.8887035847 1006 1311867203.9866371155 0.0920490921 0.0806259263 0.1208752468 0.0058669056 2.3978650000 0.9083520000 0.4055250000 0.0000050000 1.0642930000 0.0071240000 129062152 0 1783984128 3.9107196331 3.9325120449 3.8877124786 1007 1311867204.0199849606 0.0918174833 0.0806370400 0.1208752468 0.0058653641 2.5053790000 0.9163530000 0.3704320000 0.1223830000 1.0773570000 0.0071370000 129064338 0 1783709696 3.9111249447 3.9324028492 3.8864717484 1008 1311867204.0551509857 0.0931819901 0.0806494854 0.1208752468 0.0058628087 2.3090280000 0.9108280000 0.3035720000 0.0000050000 1.0758410000 0.0070640000 129066588 0 1785470976 3.9092302322 3.9311130047 3.8853847980 1009 1311867204.0867509842 0.0917790160 0.0806605157 0.1208752468 0.0058629627 3.5034410000 0.9053620000 0.2687690000 0.1221750000 1.0888660000 1.1055730000 129068774 0 1784582144 3.9104158878 3.9291274548 3.8841965199 1010 1311867204.1191530228 0.0923350155 0.0806720746 0.1208752468 0.0058602125 2.4455120000 0.9093940000 0.4170910000 0.0000050000 1.1000210000 0.0070610000 129070960 0 1784344576 3.9099190235 3.9280619621 3.8831813335 1011 1311867204.1555769444 0.0921882614 0.0806834655 0.1208752468 0.0058576578 2.3939210000 0.9081630000 0.2372700000 0.1223210000 1.1063170000 0.0071250000 129073178 0 1783595008 3.9101028442 3.9263596535 3.8824079037 1012 1311867204.1876530647 0.0915212482 0.0806941748 0.1208752468 0.0058566419 2.3591730000 0.8911000000 0.3382260000 0.0000060000 1.1109900000 0.0070050000 129075364 0 1783357440 3.9107301235 3.9246981144 3.8817110062 1013 1311867204.2187769413 0.0926030874 0.0807059308 0.1208752468 0.0058550567 3.6909680000 0.8844390000 0.3966810000 0.1220300000 1.1291940000 1.1467750000 129077550 0 1785118720 3.9095871449 3.9241197109 3.8812704086 1014 1311867204.2566440105 0.0919416025 0.0807170114 0.1208752468 0.0058526500 2.4354910000 0.8884250000 0.3986260000 0.0000060000 1.1287690000 0.0070800000 129079832 0 1784229888 3.9107089043 3.9224176407 3.8808472157 1015 1311867204.2867140770 0.0918600410 0.0807279897 0.1208752468 0.0058501164 2.3992590000 0.8870100000 0.2319780000 0.1225700000 1.1388610000 0.0069370000 129081986 0 1783861248 3.9103403091 3.9200451374 3.8800868988 1016 1311867204.3204538822 0.0925265327 0.0807396025 0.1208752468 0.0058475123 2.2729070000 0.8725600000 0.2297680000 0.0000050000 1.1519720000 0.0069770000 129084172 0 1785491456 3.9099290371 3.9195265770 3.8797452450 1017 1311867204.3625741005 0.0932042375 0.0807518588 0.1208752468 0.0058447329 3.7179010000 0.8730930000 0.3632120000 0.1220910000 1.1589640000 1.1877650000 129086550 0 1784602624 3.9092497826 3.9179792404 3.8796672821 1018 1311867204.3869600296 0.0940977335 0.0807649687 0.1208752468 0.0058421919 2.3493840000 0.8625240000 0.2930520000 0.0000060000 1.1749690000 0.0068790000 129088608 0 1784221696 3.9077825546 3.9167032242 3.8792095184 1019 1311867204.4240970612 0.0943979099 0.0807783474 0.1208752468 0.0058394996 2.5799580000 0.8630380000 0.3953020000 0.1223820000 1.1797010000 0.0069010000 129090890 0 1783332864 3.9076192379 3.9152979851 3.8789441586 1020 1311867204.4549949169 0.0947801694 0.0807920747 0.1208752468 0.0058377187 2.2515640000 0.8499390000 0.1912260000 0.0000050000 1.1915060000 0.0068830000 129093044 0 1782677504 3.9074923992 3.9147763252 3.8788146973 1021 1311867204.4872748852 0.0945060849 0.0808055066 0.1208752468 0.0058362303 3.7970980000 0.8551610000 0.3888520000 0.1219460000 1.1932430000 1.2260110000 129095230 0 1784475648 3.9074785709 3.9126133919 3.8783659935 1022 1311867204.5237219334 0.0960530937 0.0808204260 0.1208752468 0.0058337930 2.4124880000 0.8657540000 0.3229560000 0.0000060000 1.2041010000 0.0068560000 129097512 0 1783463936 3.9055290222 3.9112191200 3.8781213760 1023 1311867204.5581860542 0.0963623822 0.0808356185 0.1208752468 0.0058329709 2.3492790000 0.8373460000 0.1577010000 0.1220480000 1.2133490000 0.0067830000 129099730 0 1782824960 3.9055166245 3.9112088680 3.8779513836 1024 1311867204.5878469944 0.0961072668 0.0808505322 0.1208752468 0.0058308748 2.4501670000 0.8310490000 0.3809570000 0.0000040000 1.2195180000 0.0067550000 129101884 0 1784627200 3.9050672054 3.9086141586 3.8778872490 1025 1311867204.6241528988 0.0965793431 0.0808658774 0.1208752468 0.0058282193 3.8039570000 0.8278390000 0.3454850000 0.1218470000 1.2278370000 1.2680770000 129186054 0 1783840768 3.9038279057 3.9081156254 3.8779113293 1026 1311867204.6541819572 0.0965075865 0.0808811227 0.1208752468 0.0058257580 2.4553700000 0.8262220000 0.3767270000 0.0000060000 1.2335410000 0.0067890000 129356144 0 1783480320 3.9037718773 3.9060535431 3.8781356812 1027 1311867204.6871540546 0.0964982882 0.0808963293 0.1208752468 0.0058232684 2.5954320000 0.8300910000 0.3776560000 0.1220250000 1.2469290000 0.0067380000 129358330 0 1785110528 3.9036233425 3.9050400257 3.8781673908 1028 1311867204.7225689888 0.0977304578 0.0809127049 0.1208752468 0.0058228884 2.4083810000 0.8309860000 0.3120660000 0.0000040000 1.2456390000 0.0067690000 129360580 0 1784348672 3.9024786949 3.9052214622 3.8785288334 1029 1311867204.7539510727 0.0984838307 0.0809297809 0.1208752468 0.0058203393 3.9072990000 0.8529130000 0.3810740000 0.1218150000 1.2530900000 1.2862680000 129362766 0 1783988224 3.9005088806 3.9034345150 3.8788797855 1030 1311867204.7878720760 0.0981191918 0.0809464696 0.1208752468 0.0058185938 2.4630450000 0.8199820000 0.3714650000 0.0000050000 1.2530280000 0.0066950000 129364984 0 1785618432 3.8998599052 3.9016325474 3.8796372414 1031 1311867204.8227200508 0.0980022848 0.0809630126 0.1208752468 0.0058164567 2.4875690000 0.8053530000 0.2871680000 0.1215440000 1.2538480000 0.0066810000 129367202 0 1784475648 3.8999609947 3.9015729427 3.8811118603 1032 1311867204.8542668819 0.0968832970 0.0809784392 0.1208752468 0.0058161693 2.4565360000 0.8133500000 0.3736770000 0.0000050000 1.2507760000 0.0066810000 129369388 0 1783967744 3.9002761841 3.8993241787 3.8821215630 1033 1311867204.8864960670 0.0970010012 0.0809939499 0.1208752468 0.0058139815 3.8782150000 0.8167740000 0.3863970000 0.1216760000 1.2522270000 1.2892830000 129371574 0 1785745408 3.8993299007 3.8963270187 3.8832101822 1034 1311867204.9220221043 0.0983453915 0.0810107308 0.1208752468 0.0058114125 2.5190050000 0.8648230000 0.3733420000 0.0000050000 1.2612500000 0.0067600000 129373824 0 1783046144 3.8973937035 3.8949854374 3.8844437599 1035 1311867204.9542920589 0.0990041792 0.0810281158 0.1208752468 0.0058087591 2.5266250000 0.8141500000 0.3141880000 0.1217370000 1.2576060000 0.0067930000 129376010 0 1784664064 3.8962144852 3.8937337399 3.8854405880 1036 1311867204.9865999222 0.0973397121 0.0810438606 0.1208752468 0.0058076955 2.4065150000 0.8095830000 0.3122490000 0.0000050000 1.2649200000 0.0067500000 129378196 0 1783504896 3.8977837563 3.8903522491 3.8861596584 1037 1311867205.0227239132 0.0973741785 0.0810596082 0.1208752468 0.0058088618 3.8936590000 0.8135200000 0.3731930000 0.1215660000 1.2657090000 1.3074760000 129380446 0 1782734848 3.8977622986 3.8886079788 3.8869175911 1038 1311867205.0550808907 0.0968954489 0.0810748643 0.1208752468 0.0058223917 2.2751840000 0.8049710000 0.1819450000 0.0000050000 1.2694470000 0.0067150000 129382664 0 1784475648 3.8980789185 3.8884377480 3.8877544403 1039 1311867205.0880999565 0.0971796140 0.0810903646 0.1208752468 0.0058199076 2.5892470000 0.8079900000 0.3693030000 0.1212490000 1.2712130000 0.0066670000 129384786 0 1783365632 3.8972325325 3.8856186867 3.8885886669 1040 1311867205.1232450008 0.0993341953 0.0811079067 0.1208752468 0.0058201191 2.3777780000 0.8063750000 0.2761080000 0.0000050000 1.2764860000 0.0066430000 129387036 0 1782456320 3.8952298164 3.8845522404 3.8892974854 1041 1311867205.1545319557 0.0982579365 0.0811243813 0.1208752468 0.0058258603 3.8104590000 0.8024890000 0.2743680000 0.1212260000 1.2779900000 1.3224040000 129389190 0 1784184832 3.8978714943 3.8835890293 3.8900384903 1042 1311867205.1863510609 0.0979744941 0.0811405522 0.1208752468 0.0058327995 2.4524810000 0.8137190000 0.3392080000 0.0000040000 1.2801010000 0.0066380000 129391376 0 1783357440 3.8978955746 3.8808383942 3.8907620907 1043 1311867205.2223129272 0.0987224206 0.0811574093 0.1208752468 0.0058319177 2.4185040000 0.8066010000 0.1807740000 0.1213300000 1.2907780000 0.0066910000 129393626 0 1782194176 3.8967621326 3.8789811134 3.8913087845 1044 1311867205.2541849613 0.0975002050 0.0811730633 0.1208752468 0.0058302916 2.4675480000 0.7949480000 0.3625030000 0.0000050000 1.2914260000 0.0066860000 129395812 0 1783803904 3.8980815411 3.8773567677 3.8919801712 1045 1311867205.2880499363 0.0978537872 0.0811890257 0.1208752468 0.0058277831 3.7798600000 0.7984120000 0.2107840000 0.1219940000 1.3008300000 1.3358390000 129398030 0 1785487360 3.8977124691 3.8754436970 3.8928945065 1046 1311867205.3218879700 0.0980494469 0.0812051446 0.1208752468 0.0058263438 2.4750930000 0.7942330000 0.3615730000 0.0000050000 1.2994790000 0.0066640000 129400216 0 1784479744 3.8971309662 3.8730425835 3.8935945034 1047 1311867205.3542900085 0.0979834870 0.0812211698 0.1208752468 0.0058311525 2.5928090000 0.7905990000 0.3562360000 0.1215040000 1.3054520000 0.0065580000 129402434 0 1783209984 3.8971252441 3.8714394569 3.8945469856 1048 1311867205.3862779140 0.0987035483 0.0812378515 0.1208752468 0.0058382986 2.4997360000 0.8129530000 0.3619480000 0.0000050000 1.3062380000 0.0066270000 129404620 0 1784954880 3.8958399296 3.8702013493 3.8955843449 1049 1311867205.4225649834 0.0985105410 0.0812543173 0.1208752468 0.0058415990 3.7965980000 0.7929680000 0.2053780000 0.1214260000 1.3113500000 1.3524910000 129406870 0 1783853056 3.8950741291 3.8681514263 3.8960978985 1050 1311867205.4540419579 0.0981628224 0.0812704207 0.1208752468 0.0058434867 2.3483470000 0.7759210000 0.2329850000 0.0000050000 1.3205500000 0.0065860000 129409056 0 1782853632 3.8954825401 3.8674907684 3.8970160484 1051 1311867205.4865119457 0.0978851318 0.0812862291 0.1208752468 0.0058443237 2.6046610000 0.7784560000 0.3734880000 0.1209130000 1.3132820000 0.0065460000 129411242 0 1784311808 3.8941736221 3.8655242920 3.8981494904 1052 1311867205.5230340958 0.0972646326 0.0813014177 0.1208752468 0.0058547401 2.4837550000 0.7844400000 0.3567520000 0.0000050000 1.3229170000 0.0066240000 129413492 0 1783361536 3.8938715458 3.8634078503 3.8989076614 1053 1311867205.5542900562 0.0983831882 0.0813176397 0.1208752468 0.0058764356 3.8998260000 0.7862950000 0.2965790000 0.1210570000 1.3225510000 1.3611620000 129415678 0 1781817344 3.8920464516 3.8639841080 3.8998973370 1054 1311867205.5866839886 0.0979561508 0.0813334258 0.1208752468 0.0058736895 2.4990530000 0.7882010000 0.3717860000 0.0000040000 1.3204710000 0.0065530000 129417864 0 1783422976 3.8915886879 3.8627710342 3.9011442661 1055 1311867205.6226179600 0.0981949121 0.0813494083 0.1208752468 0.0058759577 2.4581890000 0.7839260000 0.2123790000 0.1209580000 1.3221790000 0.0066180000 129420114 0 1785106432 3.8890986443 3.8592708111 3.9020371437 1056 1311867205.6555979252 0.0994953364 0.0813665919 0.1208752468 0.0058742853 2.3359710000 0.7835650000 0.2067260000 0.0000050000 1.3259910000 0.0065940000 129422300 0 1784098816 3.8863537312 3.8576893806 3.9028837681 1057 1311867205.6902959347 0.0984690115 0.0813827720 0.1208752468 0.0058717755 3.7934710000 0.7795680000 0.1739010000 0.1210220000 1.3300350000 1.3766230000 129424550 0 1782960128 3.8870158195 3.8559615612 3.9036376476 1058 1311867205.7222061157 0.0981135815 0.0813985857 0.1208752468 0.0058690259 2.4881380000 0.7820750000 0.3524940000 0.0000060000 1.3349230000 0.0065270000 129426736 0 1784438784 3.8861603737 3.8529567719 3.9041523933 1059 1311867205.7548348904 0.0978351161 0.0814141065 0.1208752468 0.0058665831 2.5627120000 0.7824990000 0.2914450000 0.1213220000 1.3479350000 0.0065120000 129428954 0 1783484416 3.8854322433 3.8508000374 3.9043977261 1060 1311867205.7906379700 0.0987497196 0.0814304608 0.1208752468 0.0058647232 2.4704600000 0.7889550000 0.3161460000 0.0000050000 1.3465810000 0.0065710000 129431172 0 1782472704 3.8838107586 3.8494081497 3.9053051472 1061 1311867205.8232109547 0.0976617634 0.0814457589 0.1208752468 0.0058756612 4.0036560000 0.7711450000 0.3532260000 0.1207810000 1.3554500000 1.3908690000 129433390 0 1783939072 3.8839600086 3.8461163044 3.9056572914 1062 1311867205.8554759026 0.0983262733 0.0814616540 0.1208752468 0.0058780985 2.4928990000 0.7739040000 0.3453780000 0.0000050000 1.3549780000 0.0064710000 129435608 0 1785716736 3.8824656010 3.8451993465 3.9062530994 1063 1311867205.8905880451 0.0993339643 0.0814784670 0.1208752468 0.0058779397 2.6005220000 0.7570490000 0.3456930000 0.1209080000 1.3567650000 0.0064610000 129437794 0 1784737792 3.8806560040 3.8445138931 3.9065668583 1064 1311867205.9223020077 0.0981362984 0.0814941229 0.1208752468 0.0058864109 2.5343660000 0.7999550000 0.3520470000 0.0000050000 1.3634820000 0.0065990000 129439980 0 1783595008 3.8813860416 3.8427231312 3.9069228172 1065 1311867205.9544939995 0.0980944037 0.0815097100 0.1208752468 0.0058840709 3.8782710000 0.7511480000 0.2335150000 0.1206970000 1.3603360000 1.4004700000 129442166 0 1785073664 3.8805923462 3.8406417370 3.9072513580 1066 1311867205.9905850887 0.1001387239 0.0815271856 0.1208752468 0.0058931829 2.4784560000 0.7480990000 0.3483810000 0.0000060000 1.3621260000 0.0065480000 129444448 0 1784119296 3.8781335354 3.8406939507 3.9078185558 1067 1311867206.0259850025 0.0995816514 0.0815441064 0.1208752468 0.0058938519 2.4962240000 0.7680060000 0.2314730000 0.1206490000 1.3572230000 0.0064790000 129446666 0 1783107584 3.8787295818 3.8406984806 3.9078774452 1068 1311867206.0604250431 0.0997705013 0.0815611723 0.1208752468 0.0059005500 2.4652610000 0.7898430000 0.3022810000 0.0000060000 1.3545070000 0.0064910000 129448852 0 1784565760 3.8769471645 3.8365616798 3.9080331326 1069 1311867206.0903289318 0.0992304161 0.0815777011 0.1208752468 0.0058980552 4.0150700000 0.7698580000 0.3499940000 0.1209730000 1.3583540000 1.4025420000 129451006 0 1783595008 3.8769588470 3.8339788914 3.9080381393 1070 1311867206.1227540970 0.0982520580 0.0815932846 0.1208752468 0.0058955845 2.4935480000 0.7563080000 0.3605950000 0.0000050000 1.3577080000 0.0064520000 129453192 0 1782452224 3.8784942627 3.8327023983 3.9084343910 1071 1311867206.1546130180 0.0987842828 0.0816093360 0.1208752468 0.0058930215 2.6259430000 0.7603940000 0.3607480000 0.1211580000 1.3648990000 0.0065640000 129455378 0 1783930880 3.8774027824 3.8298695087 3.9080667496 1072 1311867206.1903800964 0.0992205292 0.0816257643 0.1208752468 0.0058942389 2.3743840000 0.7908530000 0.2003200000 0.0000050000 1.3644230000 0.0065390000 129457660 0 1782960128 3.8762993813 3.8275465965 3.9081530571 1073 1311867206.2239561081 0.0995300561 0.0816424505 0.1208752468 0.0058922402 3.9619690000 0.7623470000 0.2851500000 0.1212640000 1.3732870000 1.4075530000 129459878 0 1781841920 3.8759646416 3.8268158436 3.9079751968 1074 1311867206.2553579807 0.0994590819 0.0816590395 0.1208752468 0.0058909543 2.5069020000 0.7718090000 0.3498940000 0.0000050000 1.3663930000 0.0065510000 129462032 0 1783336960 3.8753128052 3.8245584965 3.9075605869 1075 1311867206.2904770374 0.0998867899 0.0816759956 0.1208752468 0.0058882450 2.6254950000 0.7825260000 0.3335350000 0.1211730000 1.3696180000 0.0064820000 129464250 0 1785073664 3.8739187717 3.8219757080 3.9072566032 1076 1311867206.3222041130 0.1007928923 0.0816937622 0.1208752468 0.0058857419 2.5479100000 0.7950520000 0.3649150000 0.0000040000 1.3682220000 0.0064740000 129466404 0 1784102912 3.8726055622 3.8216068745 3.9067504406 1077 1311867206.3542530537 0.1013692766 0.0817120310 0.1208752468 0.0058842012 3.9165690000 0.7719480000 0.2379790000 0.1210420000 1.3677960000 1.4052810000 129468622 0 1782960128 3.8710484505 3.8197681904 3.9063918591 1078 1311867206.3900070190 0.1001102179 0.0817290980 0.1208752468 0.0058837325 2.4405000000 0.7731340000 0.2728990000 0.0000050000 1.3757160000 0.0065470000 129470840 0 1784438784 3.8721013069 3.8171608448 3.9063580036 1079 1311867206.4220259190 0.1004828215 0.0817464787 0.1208752468 0.0058828961 2.6369220000 0.7674950000 0.3607690000 0.1211740000 1.3677360000 0.0064800000 129473026 0 1783193600 3.8716733456 3.8164079189 3.9062135220 1080 1311867206.4542310238 0.0993742868 0.0817628007 0.1208752468 0.0058803463 2.5644320000 0.8141810000 0.3638520000 0.0000050000 1.3673640000 0.0065200000 129475244 0 1782218752 3.8725860119 3.8146033287 3.9062054157 1081 1311867206.4905378819 0.0999692976 0.0817796430 0.1208752468 0.0058857101 3.9843490000 0.7735240000 0.2944230000 0.1211680000 1.3720130000 1.4108500000 129477462 0 1783676928 3.8709790707 3.8117759228 3.9061393738 1082 1311867206.5250329971 0.1007409692 0.0817971673 0.1208752468 0.0058872138 2.3388730000 0.7748090000 0.1749320000 0.0000040000 1.3703210000 0.0065850000 129479712 0 1785327616 3.8696517944 3.8093154430 3.9060549736 1083 1311867206.5539300442 0.0991971567 0.0818132338 0.1208752468 0.0058918813 2.5546930000 0.7706710000 0.2626640000 0.1213880000 1.3800680000 0.0065540000 129481866 0 1784356864 3.8715209961 3.8068544865 3.9059693813 1084 1311867206.5921130180 0.0987980515 0.0818289024 0.1208752468 0.0058910599 2.3320180000 0.7629710000 0.1709900000 0.0000040000 1.3790420000 0.0065760000 129484116 0 1783214080 3.8721861839 3.8055596352 3.9055764675 1085 1311867206.6226360798 0.1014776826 0.0818470119 0.1208752468 0.0059045591 3.9357100000 0.7630310000 0.2313920000 0.1210840000 1.3874300000 1.4204130000 129486270 0 1784860672 3.8692443371 3.8035185337 3.9054765701 1086 1311867206.6566751003 0.1001344174 0.0818638511 0.1208752468 0.0059028785 2.5258520000 0.7655450000 0.3493330000 0.0000040000 1.3912860000 0.0064780000 129488488 0 1783988224 3.8701987267 3.8014855385 3.9053156376 1087 1311867206.6945209503 0.1003149077 0.0818808254 0.1208752468 0.0059007270 2.6315010000 0.7488390000 0.3504820000 0.1210040000 1.3921850000 0.0064430000 129490770 0 1782960128 3.8702390194 3.8011188507 3.9048843384 1088 1311867206.7248480320 0.0990661979 0.0818966208 0.1208752468 0.0059086281 2.4302410000 0.7601530000 0.2572930000 0.0000050000 1.3940750000 0.0064980000 129492924 0 1784565760 3.8705942631 3.7979264259 3.9046123028 1089 1311867206.7587969303 0.1017148644 0.0819148194 0.1208752468 0.0059537338 3.8985210000 0.7835260000 0.1387340000 0.1209470000 1.4002230000 1.4417590000 129495174 0 1783463936 3.8688175678 3.7973780632 3.9042098522 1090 1311867206.7902839184 0.1001793891 0.0819315759 0.1208752468 0.0059722641 2.3515450000 0.7520230000 0.1721310000 0.0000040000 1.4083270000 0.0064660000 129497360 0 1782452224 3.8691546917 3.7957870960 3.9034888744 1091 1311867206.8229770660 0.1006177589 0.0819487034 0.1208752468 0.0059701572 2.6475060000 0.7534630000 0.3436800000 0.1211170000 1.4103590000 0.0064570000 129499546 0 1783930880 3.8681485653 3.7940361500 3.9028990269 1092 1311867206.8605449200 0.0998748764 0.0819651193 0.1208752468 0.0059675606 2.4131920000 0.7493080000 0.2263450000 0.0000040000 1.4186730000 0.0064320000 129501796 0 1782960128 3.8681550026 3.7909905910 3.9022359848 1093 1311867206.8907771111 0.0989382863 0.0819806483 0.1208752468 0.0059660429 4.1170360000 0.7723670000 0.3364220000 0.1210850000 1.4150170000 1.4596290000 129503950 0 1782083584 3.8694131374 3.7906677723 3.9015579224 1094 1311867206.9225020409 0.1005818918 0.0819976513 0.1208752468 0.0059634539 2.5277440000 0.7485550000 0.3412530000 0.0000050000 1.4190640000 0.0064430000 129506136 0 1783824384 3.8670506477 3.7884259224 3.9010717869 1095 1311867206.9592480659 0.1011457443 0.0820151381 0.1208752468 0.0059616178 2.5671530000 0.7504300000 0.2518050000 0.1212770000 1.4247850000 0.0064480000 129508418 0 1785327616 3.8662991524 3.7852609158 3.9005711079 1096 1311867206.9948680401 0.1010199711 0.0820324783 0.1208752468 0.0059723126 2.5282450000 0.7384200000 0.3342500000 0.0000050000 1.4357210000 0.0064640000 129510636 0 1784369152 3.8665382862 3.7834334373 3.9001643658 1097 1311867207.0247550011 0.1016308516 0.0820503437 0.1208752468 0.0059747752 4.0159250000 0.7576990000 0.1904570000 0.1208500000 1.4464410000 1.4878230000 129512822 0 1783599104 3.8668169975 3.7823960781 3.8999948502 1098 1311867207.0597259998 0.1019030511 0.0820684245 0.1208752468 0.0059722679 2.4776480000 0.7332900000 0.2789990000 0.0000040000 1.4463650000 0.0063610000 129515072 0 1785245696 3.8659801483 3.7799220085 3.8997514248 1099 1311867207.0942800045 0.1009762213 0.0820856291 0.1208752468 0.0059772363 2.5392450000 0.7426470000 0.2020720000 0.1215820000 1.4530340000 0.0063720000 129517258 0 1784094720 3.8669629097 3.7771103382 3.8995690346 1100 1311867207.1229140759 0.0999330580 0.0821018540 0.1208752468 0.0059797184 2.4415640000 0.7160620000 0.2499500000 0.0000050000 1.4565200000 0.0064100000 129519380 0 1783607296 3.8688559532 3.7766785622 3.8992843628 1101 1311867207.1583549976 0.1024419591 0.0821203282 0.1208752468 0.0059857896 4.1397300000 0.7559580000 0.2878400000 0.1210150000 1.4561020000 1.5063370000 129521630 0 1785348096 3.8662192822 3.7740209103 3.8993556499 1102 1311867207.1904919147 0.1008128822 0.0821372906 0.1208752468 0.0059854908 2.5135900000 0.7256380000 0.3033230000 0.0000050000 1.4647160000 0.0063850000 129523784 0 1784094720 3.8676304817 3.7724761963 3.8990237713 1103 1311867207.2226181030 0.1016220078 0.0821549558 0.1208752468 0.0059841000 2.6616310000 0.7269390000 0.3349080000 0.1212150000 1.4596510000 0.0063830000 129526002 0 1783586816 3.8667335510 3.7714071274 3.8991947174 1104 1311867207.2604830265 0.1008919552 0.0821719277 0.1208752468 0.0059828240 2.3673880000 0.7178180000 0.1661250000 0.0000050000 1.4645750000 0.0063180000 129528284 0 1785344000 3.8672227859 3.7697167397 3.8992757797 1105 1311867207.2926900387 0.0999234840 0.0821879925 0.1208752468 0.0059832080 4.2155670000 0.7731920000 0.3379740000 0.1214430000 1.4582450000 1.5111540000 129530470 0 1784074240 3.8676245213 3.7667329311 3.8996407986 1106 1311867207.3235239983 0.1007085741 0.0822047380 0.1208752468 0.0059872323 2.3987950000 0.7262600000 0.1911020000 0.0000050000 1.4623640000 0.0063350000 129532624 0 1783603200 3.8665556908 3.7651679516 3.9001727104 1107 1311867207.3597478867 0.1006482765 0.0822213989 0.1208752468 0.0059849642 2.5026380000 0.7297590000 0.1660170000 0.1212570000 1.4666250000 0.0064860000 129534906 0 1785475072 3.8661906719 3.7647967339 3.9006502628 1108 1311867207.3901309967 0.1002152786 0.0822376388 0.1208752468 0.0059858704 2.4018660000 0.7280690000 0.1945320000 0.0000050000 1.4593040000 0.0064100000 129537060 0 1784365056 3.8657255173 3.7620594501 3.9011211395 1109 1311867207.4227840900 0.1001830772 0.0822538205 0.1208752468 0.0059832790 4.1627490000 0.7260550000 0.3201290000 0.1210970000 1.4730950000 1.5096120000 129539246 0 1784102912 3.8643717766 3.7608637810 3.9011139870 1110 1311867207.4586789608 0.1001991481 0.0822699874 0.1208752468 0.0059827804 2.3966700000 0.7226380000 0.1928690000 0.0000040000 1.4622760000 0.0063210000 129541496 0 1782960128 3.8640692234 3.7602908611 3.9017927647 1111 1311867207.4927639961 0.1003727391 0.0822862815 0.1208752468 0.0059808604 2.5964870000 0.7309630000 0.2583920000 0.1214570000 1.4665550000 0.0063960000 129543714 0 1782677504 3.8623461723 3.7571060658 3.9019675255 1112 1311867207.5237300396 0.1010605916 0.0823031649 0.1208752468 0.0059827700 2.3963650000 0.7205440000 0.1898400000 0.0000050000 1.4670910000 0.0063760000 129545900 0 1784344576 3.8604555130 3.7542977333 3.9023973942 1113 1311867207.5598409176 0.0997320116 0.0823188242 0.1208752468 0.0059804440 4.0207660000 0.7262520000 0.1704510000 0.1213850000 1.4727950000 1.5164200000 129548118 0 1783582720 3.8615007401 3.7535550594 3.9027497768 1114 1311867207.5944800377 0.1008238867 0.0823354356 0.1208752468 0.0059798823 2.4121670000 0.7193890000 0.1941220000 0.0000050000 1.4788880000 0.0064060000 129550368 0 1783349248 3.8591802120 3.7517004013 3.9029071331 1115 1311867207.6259219646 0.0982584357 0.0823497163 0.1208752468 0.0059780612 2.6863020000 0.7367320000 0.3301970000 0.1215040000 1.4788660000 0.0063750000 129552522 0 1785110528 3.8605098724 3.7477338314 3.9034192562 1116 1311867207.6592938900 0.0982091129 0.0823639273 0.1208752468 0.0059763373 2.6219240000 0.7820060000 0.3294650000 0.0000040000 1.4905830000 0.0063230000 129554772 0 1784348672 3.8599550724 3.7470777035 3.9033484459 1117 1311867207.6923089027 0.0985101312 0.0823783822 0.1208752468 0.0059747944 4.2066750000 0.7157740000 0.3262600000 0.1214930000 1.4885310000 1.5418670000 129556958 0 1783689216 3.8591997623 3.7451572418 3.9035069942 1118 1311867207.7238640785 0.0983751714 0.0823926906 0.1208752468 0.0059738778 2.4564950000 0.7259400000 0.2187510000 0.0000050000 1.4927220000 0.0062980000 129559144 0 1785470976 3.8582484722 3.7416379452 3.9038450718 1119 1311867207.7588050365 0.0987046212 0.0824072679 0.1208752468 0.0059723660 2.6190620000 0.7108870000 0.2620150000 0.1210440000 1.5051980000 0.0062770000 129561298 0 1784745984 3.8569872379 3.7396061420 3.9036586285 1120 1311867207.7921919823 0.1005295143 0.0824234484 0.1208752468 0.0059702643 2.4772520000 0.7646630000 0.1890040000 0.0000050000 1.5044780000 0.0062820000 129563516 0 1784483840 3.8542883396 3.7382130623 3.9039118290 1121 1311867207.8237760067 0.0988613516 0.0824381121 0.1208752468 0.0059692402 4.1310610000 0.7075710000 0.2161930000 0.1211710000 1.5139300000 1.5585000000 129565702 0 1783734272 3.8555760384 3.7353742123 3.9039371014 1122 1311867207.8608479500 0.0983096883 0.0824522578 0.1208752468 0.0059677104 2.5520210000 0.7007160000 0.3181960000 0.0000050000 1.5140010000 0.0062930000 129567952 0 1783611392 3.8564779758 3.7341706753 3.9042527676 1123 1311867207.8937089443 0.0979926735 0.0824660962 0.1208752468 0.0059651501 2.6801050000 0.7077310000 0.3146630000 0.1218270000 1.5169580000 0.0062320000 129570170 0 1785212928 3.8569157124 3.7330334187 3.9041709900 1124 1311867207.9244139194 0.0997376665 0.0824814623 0.1208752468 0.0059633134 2.4680860000 0.7127130000 0.2157860000 0.0000040000 1.5194870000 0.0063060000 129572324 0 1784455168 3.8541514874 3.7305581570 3.9046111107 1125 1311867207.9614970684 0.0970499963 0.0824944121 0.1208752468 0.0059657106 4.1188730000 0.7009130000 0.1850730000 0.1209000000 1.5233430000 1.5756950000 129574510 0 1784238080 3.8569097519 3.7295618057 3.9046392441 1126 1311867207.9914131165 0.0970929787 0.0825073771 0.1208752468 0.0059801489 2.5014490000 0.7045780000 0.2480810000 0.0000050000 1.5288720000 0.0062890000 129576664 0 1783476224 3.8572990894 3.7283742428 3.9050152302 1127 1311867208.0248498917 0.0966911912 0.0825199626 0.1208752468 0.0059951681 2.5457420000 0.7066070000 0.1592820000 0.1244480000 1.5361210000 0.0063580000 129578914 0 1783349248 3.8566062450 3.7246186733 3.9053101540 1128 1311867208.0618500710 0.0979385450 0.0825336315 0.1208752468 0.0059949519 2.5371090000 0.7435160000 0.2366380000 0.0000040000 1.5379290000 0.0062150000 129581068 0 1784836096 3.8553240299 3.7232491970 3.9055817127 1129 1311867208.0924620628 0.0971696302 0.0825465952 0.1208752468 0.0059925794 4.2525450000 0.6956460000 0.2992970000 0.1209670000 1.5318970000 1.5910760000 129583222 0 1784111104 3.8565580845 3.7229349613 3.9055230618 1130 1311867208.1276559830 0.0973464325 0.0825596924 0.1208752468 0.0059910345 2.4868900000 0.6972740000 0.2360180000 0.0000050000 1.5345340000 0.0062670000 129585440 0 1783984128 3.8556442261 3.7205650806 3.9054479599 1131 1311867208.1596069336 0.0958725065 0.0825714632 0.1208752468 0.0059885171 2.6840040000 0.6956390000 0.3029760000 0.1210490000 1.5453890000 0.0062160000 129587626 0 1785597952 3.8574173450 3.7198421955 3.9052214622 1132 1311867208.1905009747 0.0980381742 0.0825851264 0.1208752468 0.0059865997 2.5983660000 0.7220570000 0.3134660000 0.0000050000 1.5430050000 0.0061890000 129589748 0 1784725504 3.8545975685 3.7185153961 3.9049255848 1133 1311867208.2280850410 0.0983539671 0.0825990442 0.1208752468 0.0059845325 4.1373950000 0.6913230000 0.1548900000 0.1214040000 1.5539340000 1.6029290000 129592062 0 1784627200 3.8542938232 3.7171850204 3.9047451019 1134 1311867208.2581789494 0.0976487473 0.0826123155 0.1208752468 0.0059825164 2.5832980000 0.6875760000 0.3150960000 0.0000050000 1.5607670000 0.0062690000 129594216 0 1783857152 3.8544905186 3.7150387764 3.9045150280 1135 1311867208.2901990414 0.0973926336 0.0826253378 0.1208752468 0.0059800758 2.6751480000 0.6704520000 0.3074410000 0.1206310000 1.5575790000 0.0061500000 129596370 0 1783603200 3.8547594547 3.7141892910 3.9040725231 1136 1311867208.3270208836 0.0980998948 0.0826389598 0.1208752468 0.0059824606 2.5990690000 0.7044030000 0.3078630000 0.0000050000 1.5679010000 0.0061580000 129598652 0 1785364480 3.8542797565 3.7130582333 3.9039807320 1137 1311867208.3580970764 0.0984742865 0.0826528871 0.1208752468 0.0059838584 4.3013020000 0.6695040000 0.3080280000 0.1209060000 1.5653790000 1.6237470000 129600838 0 1784475648 3.8534753323 3.7114641666 3.9040033817 1138 1311867208.3910560608 0.0972172543 0.0826656853 0.1208752468 0.0059821225 2.5837820000 0.6741380000 0.3203510000 0.0000040000 1.5702360000 0.0061290000 129602992 0 1783967744 3.8549778461 3.7105543613 3.9038665295 1139 1311867208.4260230064 0.0982573330 0.0826793742 0.1208752468 0.0059800340 2.7086700000 0.6771050000 0.3153640000 0.1209460000 1.5761640000 0.0061930000 129605242 0 1785618432 3.8529648781 3.7079703808 3.9036660194 1140 1311867208.4577419758 0.0982818604 0.0826930606 0.1208752468 0.0059808216 2.4797690000 0.6816150000 0.2038350000 0.0000040000 1.5742730000 0.0061480000 129607428 0 1784745984 3.8535158634 3.7068626881 3.9038038254 1141 1311867208.4907650948 0.0967174843 0.0827053519 0.1208752468 0.0059797326 4.3463380000 0.6774010000 0.3187610000 0.1210040000 1.5803090000 1.6358530000 129609646 0 1784365056 3.8552911282 3.7055912018 3.9038269520 1142 1311867208.5257411003 0.0968656838 0.0827177515 0.1208752468 0.0059780543 2.4061080000 0.6622940000 0.1476500000 0.0000040000 1.5763430000 0.0062010000 129611896 0 1783472128 3.8544218540 3.7043004036 3.9038863182 1143 1311867208.5583798885 0.0988465920 0.0827318625 0.1208752468 0.0059761284 2.7047440000 0.6729300000 0.3146190000 0.1208160000 1.5773060000 0.0061340000 129614082 0 1783349248 3.8517339230 3.7030873299 3.9045698643 1144 1311867208.5904500484 0.0997377932 0.0827467278 0.1208752468 0.0059747502 2.4588970000 0.7065760000 0.1564030000 0.0000050000 1.5768420000 0.0061950000 129616300 0 1784967168 3.8509531021 3.7028625011 3.9051036835 1145 1311867208.6259779930 0.0965613127 0.0827587930 0.1208752468 0.0059744257 4.3490610000 0.6810120000 0.3177330000 0.1211400000 1.5776340000 1.6375880000 129618486 0 1784209408 3.8538670540 3.7012999058 3.9053733349 1146 1311867208.6582078934 0.0971366167 0.0827713391 0.1208752468 0.0059719118 2.6027090000 0.6816570000 0.3242980000 0.0000050000 1.5776930000 0.0062090000 129620704 0 1783984128 3.8525319099 3.6997148991 3.9060668945 1147 1311867208.6910300255 0.0951484144 0.0827821299 0.1208752468 0.0059757503 2.7139450000 0.6822790000 0.3152770000 0.1208950000 1.5763110000 0.0062220000 129622890 0 1785597952 3.8536036015 3.6991195679 3.9066047668 1148 1311867208.7262260914 0.0963867903 0.0827939806 0.1208752468 0.0059780200 2.4896630000 0.7094700000 0.1839160000 0.0000050000 1.5762130000 0.0061590000 129625140 0 1784868864 3.8522160053 3.6979026794 3.9069833755 1149 1311867208.7591009140 0.0981243700 0.0828073230 0.1208752468 0.0059759977 4.2353930000 0.6776590000 0.2074560000 0.1210790000 1.5768450000 1.6394010000 129627326 0 1784745984 3.8497645855 3.6980178356 3.9074356556 1150 1311867208.7909750938 0.0958040357 0.0828186245 0.1208752468 0.0059755013 2.5182100000 0.6808330000 0.2401260000 0.0000040000 1.5773450000 0.0061570000 129629480 0 1784111104 3.8515601158 3.6961874962 3.9079020023 1151 1311867208.8259930611 0.0965078473 0.0828305178 0.1208752468 0.0059744345 2.7281730000 0.6906740000 0.3105910000 0.1211260000 1.5865510000 0.0061470000 129631730 0 1783984128 3.8499732018 3.6935749054 3.9084370136 1152 1311867208.8588190079 0.0977348983 0.0828434557 0.1208752468 0.0059789888 2.5171210000 0.7096220000 0.2037850000 0.0000040000 1.5838230000 0.0062010000 129633948 0 1783222272 3.8487117290 3.6941046715 3.9087047577 1153 1311867208.8916258812 0.0970382020 0.0828557668 0.1208752468 0.0059904283 4.3482520000 0.6711480000 0.3210340000 0.1208330000 1.5829510000 1.6391800000 129636102 0 1782964224 3.8478977680 3.6938397884 3.9092059135 1154 1311867208.9275119305 0.0978042930 0.0828687205 0.1208752468 0.0059926547 2.6364350000 0.6839460000 0.3172340000 0.0000050000 1.6161810000 0.0061390000 129638320 0 1784582144 3.8467502594 3.6909091473 3.9094860554 1155 1311867208.9577760696 0.0981009603 0.0828819085 0.1208752468 0.0059904161 2.7205640000 0.6761340000 0.3073440000 0.1216030000 1.5952850000 0.0061970000 129640474 0 1783857152 3.8456318378 3.6882147789 3.9094769955 1156 1311867208.9911639690 0.0963101760 0.0828935247 0.1208752468 0.0059878644 2.5565350000 0.7024450000 0.2293200000 0.0000050000 1.6056720000 0.0061230000 129642692 0 1783738368 3.8480815887 3.6884858608 3.9090423584 1157 1311867209.0270779133 0.0960714892 0.0829049145 0.1208752468 0.0059871103 4.3858150000 0.6737010000 0.3112290000 0.1212000000 1.6013380000 1.6653420000 129644942 0 1785352192 3.8479571342 3.6857361794 3.9091331959 1158 1311867209.0579569340 0.0979266018 0.0829178866 0.1208752468 0.0059851234 2.4997110000 0.6678230000 0.2021710000 0.0000040000 1.6097550000 0.0061050000 129647096 0 1784455168 3.8455286026 3.6850392818 3.9083216190 1159 1311867209.0906980038 0.0986221433 0.0829314364 0.1208752468 0.0059834561 2.7113640000 0.6558640000 0.2990910000 0.1203990000 1.6167100000 0.0061670000 129649314 0 1784233984 3.8447563648 3.6854650974 3.9078447819 1160 1311867209.1260778904 0.0982181281 0.0829446146 0.1208752468 0.0059812222 2.4749480000 0.6653360000 0.1766260000 0.0000050000 1.6128860000 0.0062340000 129651500 0 1783603200 3.8448214531 3.6845202446 3.9071929455 1161 1311867209.1600620747 0.0991974771 0.0829586136 0.1208752468 0.0059795836 4.3154180000 0.6562740000 0.2225910000 0.1207270000 1.6233930000 1.6792080000 129653750 0 1783328768 3.8432583809 3.6820583344 3.9069828987 1162 1311867209.1917839050 0.0998546034 0.0829731540 0.1208752468 0.0059778467 2.4984250000 0.6546890000 0.1995550000 0.0000050000 1.6250810000 0.0060480000 129655936 0 1785090048 3.8429143429 3.6828088760 3.9065155983 1163 1311867209.2259531021 0.0996889174 0.0829875270 0.1208752468 0.0059753303 2.5623340000 0.6502800000 0.1494500000 0.1206600000 1.6219310000 0.0061050000 129658122 0 1784201216 3.8425393105 3.6813225746 3.9059369564 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:18:19 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000001192 0.0000001192 0.0000001192 nan 0.2304760000 0.0758630000 0.0260140000 0.0004930000 0.0000470000 0.1265850000 7890518 96830484 1026588672 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0071111759 0.0035556476 0.0071111759 0.0073250318 0.0374000000 0.0108830000 0.0109820000 0.0000760000 0.0000060000 0.0151380000 8220144 96830484 1027256320 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0160688832 0.0077267261 0.0160688832 0.0105654109 0.0300170000 0.0092550000 0.0081120000 0.0001370000 0.0000080000 0.0120320000 8222142 96830484 1027891200 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0069097765 0.0075224887 0.0160688832 0.0105835684 0.1152620000 0.0136600000 0.0172610000 0.0002150000 0.0002810000 0.0826600000 8224164 96830484 1028526080 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0087672304 0.0077714371 0.0160688832 0.0110947667 0.1567160000 0.0096570000 0.0622380000 0.0002980000 0.0003080000 0.0837820000 8226158 96830484 1029160960 4.0003604889 4.0041589737 3.9997618198 6 0.2000000000 0.0087729022 0.0079383479 0.0160688832 0.0099842521 0.0910700000 0.0084450000 0.0435070000 0.0000220000 0.0004050000 0.0374510000 8228488 96830484 1029795840 4.0005397797 3.9986739159 4.0006165504 7 0.2400000000 0.0089614438 0.0080845045 0.0160688832 0.0091709170 0.1212740000 0.0081960000 0.0536250000 0.0004810000 0.0003050000 0.0573240000 8230162 96830484 1030369280 4.0003643036 3.9985847473 4.0004940033 8 0.2800000000 0.0086605372 0.0081565086 0.0160688832 0.0085533177 0.0926600000 0.0081360000 0.0395710000 0.0000230000 0.0003680000 0.0442000000 8231836 96830484 1031147520 4.0010013580 4.0011544228 4.0005350113 9 0.3200000000 0.0086929584 0.0082161141 0.0160688832 0.0080191187 0.1375200000 0.0085340000 0.0431890000 0.0003070000 0.0002760000 0.0837500000 8234150 96830484 1031798784 4.0009446144 4.0011124611 4.0001001358 10 0.3600000000 0.0088473009 0.0082792328 0.0160688832 0.0075715586 0.0917150000 0.0087570000 0.0461860000 0.0000230000 0.0003720000 0.0359980000 8237136 96830484 1032433664 4.0023875237 3.9998784065 4.0002794266 11 0.4000000000 0.0089137303 0.0083369144 0.0160688832 0.0072054639 0.1055710000 0.0088660000 0.0516440000 0.0004280000 0.0002690000 0.0428550000 8238810 96830484 1033068544 4.0022621155 3.9993741512 4.0004625320 12 0.4400000000 0.0089347186 0.0083867314 0.0160688832 0.0068919919 0.0974020000 0.0092110000 0.0503860000 0.0000950000 0.0003020000 0.0358790000 8240484 96830484 1033703424 4.0025334358 3.9998526573 3.9999463558 13 0.4800000000 0.0089757601 0.0084320413 0.0160688832 0.0067033457 0.1244690000 0.0087500000 0.0465300000 0.0003720000 0.0002760000 0.0681270000 8242158 96830484 1034338304 4.0026526451 4.0015048981 3.9993927479 14 0.5200000000 0.0089717600 0.0084705926 0.0160688832 0.0065182433 0.0940190000 0.0094470000 0.0477510000 0.0000240000 0.0003000000 0.0360250000 8243832 96830484 1034973184 4.0027189255 4.0024604797 3.9992067814 15 0.5600000000 0.0089664999 0.0085036531 0.0160688832 0.0062908370 0.1009160000 0.0085960000 0.0475030000 0.0003020000 0.0003400000 0.0423200000 8245506 96830484 1035608064 4.0029129982 4.0031342506 3.9986877441 16 0.6000000000 0.0090225749 0.0085360857 0.0160688832 0.0060791835 0.0906920000 0.0088450000 0.0439710000 0.0000270000 0.0003770000 0.0359890000 8247180 96830484 1036242944 4.0029549599 4.0030102730 3.9984180927 17 0.6400000000 0.0090523968 0.0085664570 0.0160688832 0.0058997607 0.1224610000 0.0086960000 0.0452390000 0.0003120000 0.0002690000 0.0674830000 8250134 96830484 1036877824 4.0021615028 4.0036854744 3.9978315830 18 0.6800000000 0.0092077553 0.0086020846 0.0160688832 0.0057495889 0.0855210000 0.0085500000 0.0364830000 0.0000230000 0.0003660000 0.0382250000 8254432 96830484 1037623296 4.0025982857 4.0049695969 3.9975538254 19 0.7200000000 0.0092679001 0.0086371276 0.0160688832 0.0057176365 0.1125500000 0.0083580000 0.0516170000 0.0003430000 0.0002690000 0.0514940000 8256106 96830484 1038274560 4.0038008690 4.0054721832 3.9974596500 20 0.7600000000 0.0093646012 0.0086735012 0.0160688832 0.0055669590 0.0806750000 0.0084050000 0.0342820000 0.0000170000 0.0002050000 0.0358520000 8257780 96830484 1038909440 4.0043578148 4.0055813789 3.9969880581 21 0.8000000000 0.0094007514 0.0087081322 0.0160688832 0.0054260382 0.1262140000 0.0090030000 0.0508820000 0.0003740000 0.0003090000 0.0636950000 8259454 96830484 1039544320 4.0034461021 4.0064182281 3.9972100258 22 0.8400000000 0.0096053071 0.0087489129 0.0160688832 0.0052954562 0.0863860000 0.0088820000 0.0363740000 0.0000250000 0.0003760000 0.0386930000 8261128 96830484 1040179200 4.0031504631 4.0063815117 3.9969263077 23 0.8800000000 0.0094859675 0.0087809587 0.0160688832 0.0051737677 0.1057600000 0.0083860000 0.0463090000 0.0003210000 0.0002690000 0.0483470000 8262802 96830484 1040814080 4.0037240982 4.0054359436 3.9970669746 24 0.9200000000 0.0096065747 0.0088153594 0.0160688832 0.0050636770 0.0933180000 0.0081550000 0.0419810000 0.0000330000 0.0003420000 0.0421660000 8264476 96830484 1041416192 4.0044240952 4.0051817894 3.9973945618 25 0.9600000000 0.0096701365 0.0088495505 0.0160688832 0.0049637006 0.1122980000 0.0084820000 0.0358750000 0.0000830000 0.0000820000 0.0672620000 8266150 96830484 1042083840 4.0056781769 4.0050964355 3.9977092743 26 1.0000000000 0.0096045919 0.0088785905 0.0160688832 0.0048655354 0.0843940000 0.0083120000 0.0397310000 0.0000280000 0.0006810000 0.0351040000 8267824 96830484 1042718720 4.0052924156 4.0045461655 3.9974346161 27 1.0400000000 0.0095490040 0.0089034207 0.0160688832 0.0047759215 0.0977050000 0.0083360000 0.0430280000 0.0003850000 0.0002770000 0.0431180000 8269498 96830484 1043353600 4.0054473877 4.0051455498 3.9975295067 28 1.0800000000 0.0094877062 0.0089242880 0.0160688832 0.0047054671 0.0951920000 0.0088860000 0.0465940000 0.0000270000 0.0003700000 0.0370610000 8271172 96830484 1044099072 4.0072197914 4.0039138794 3.9976327419 29 1.1200000000 0.0094594797 0.0089427429 0.0160688832 0.0047737912 0.1304100000 0.0091920000 0.0513710000 0.0004060000 0.0002730000 0.0685220000 8272846 96830484 1044750336 4.0084528923 4.0044531822 3.9976911545 30 1.1600000000 0.0095187202 0.0089619421 0.0160688832 0.0049254594 0.0925160000 0.0082220000 0.0442200000 0.0000280000 0.0007070000 0.0387790000 8274520 96830484 1045385216 4.0077743530 4.0029916763 3.9979414940 31 1.2000000000 0.0095992675 0.0089825010 0.0160688832 0.0050156954 0.1094620000 0.0083740000 0.0470250000 0.0003780000 0.0002760000 0.0528260000 8276194 96830484 1046020096 4.0100097656 4.0033450127 3.9981105328 32 1.2400000000 0.0096527329 0.0090034458 0.0160688832 0.0052974317 0.0997040000 0.0083280000 0.0465840000 0.0000180000 0.0002810000 0.0417940000 8277868 96830484 1046749184 4.0117545128 4.0045742989 3.9984753132 33 1.2800000000 0.0096740825 0.0090237681 0.0160688832 0.0055436688 0.1631170000 0.0083150000 0.0744240000 0.0005580000 0.0002640000 0.0766070000 8282102 96830484 1047384064 4.0115585327 4.0040273666 3.9992868900 34 1.3200000000 0.0097341947 0.0090446630 0.0160688832 0.0056845197 0.0909720000 0.0088520000 0.0444720000 0.0000240000 0.0003070000 0.0366900000 8289024 96830484 1048018944 4.0111398697 4.0038499832 4.0000424385 35 1.3600000000 0.0097994963 0.0090662297 0.0160688832 0.0060332464 0.1035470000 0.0085310000 0.0454320000 0.0005230000 0.0002860000 0.0452380000 8290698 96830484 1048653824 4.0113830566 4.0045228004 4.0006899834 36 1.4000000000 0.0098696025 0.0090885456 0.0160688832 0.0063440764 0.1134100000 0.0083240000 0.0584970000 0.0000260000 0.0004390000 0.0453920000 8292372 96830484 1049321472 4.0127730370 4.0029487610 4.0015988350 37 1.4400000000 0.0099604372 0.0091121102 0.0160688832 0.0067326811 0.1209760000 0.0083020000 0.0411830000 0.0003860000 0.0002960000 0.0698460000 8294046 96830484 1049956352 4.0137982368 4.0030946732 4.0021119118 38 1.4800000000 0.0099616181 0.0091344657 0.0160688832 0.0085641649 0.0947810000 0.0082710000 0.0445610000 0.0000280000 0.0003780000 0.0395840000 8295720 96830484 1050685440 4.0152726173 4.0021977425 4.0038652420 39 1.5200000000 0.0100118108 0.0091569617 0.0160688832 0.0088498033 0.1095440000 0.0081430000 0.0465730000 0.0003090000 0.0003400000 0.0534400000 8297394 96830484 1051320320 4.0168070793 4.0024704933 4.0048856735 40 1.5600000000 0.0100022415 0.0091780937 0.0160688832 0.0089654052 0.1078840000 0.0081560000 0.0486530000 0.0000250000 0.0003830000 0.0476540000 8299068 96830484 1051860992 4.0181431770 4.0022873878 4.0052509308 41 1.6000000000 0.0099784276 0.0091976140 0.0160688832 0.0091048932 0.1271430000 0.0081970000 0.0441900000 0.0003150000 0.0003760000 0.0733330000 8300742 96830484 1052598272 4.0197405815 3.9987430573 4.0067362785 42 1.6400000000 0.0101140821 0.0092194347 0.0160688832 0.0092250856 0.0925710000 0.0079510000 0.0445080000 0.0000270000 0.0003220000 0.0390580000 8302416 96830484 1053138944 4.0215530396 3.9990427494 4.0070905685 43 1.6800000000 0.0100304652 0.0092382959 0.0160688832 0.0094689640 0.1015800000 0.0079410000 0.0429050000 0.0003780000 0.0003070000 0.0467990000 8304090 96830484 1053868032 4.0233945847 4.0012512207 4.0076274872 44 1.7200000000 0.0100632990 0.0092570460 0.0160688832 0.0097023953 0.1084100000 0.0078220000 0.0507100000 0.0000280000 0.0003090000 0.0461880000 8305764 96830484 1054519296 4.0247111320 4.0028095245 4.0085988045 45 1.7600000000 0.0100781405 0.0092752925 0.0160688832 0.0100015509 0.1508260000 0.0078810000 0.0546120000 0.0003130000 0.0003600000 0.0868770000 8307438 96830484 1055264768 4.0267496109 4.0007348061 4.0096950531 46 1.8000000000 0.0101584280 0.0092944911 0.0160688832 0.0112160833 0.0913010000 0.0079900000 0.0446060000 0.0000280000 0.0003030000 0.0376740000 8309112 96830484 1055805440 4.0545845032 4.0003557205 4.0058860779 47 1.8400000000 0.0102256676 0.0093143034 0.0160688832 0.0111219055 0.1062080000 0.0080120000 0.0437300000 0.0003230000 0.0004770000 0.0512920000 8310786 96830484 1056423936 4.1148509979 3.9970896244 3.9948425293 48 1.8800000000 0.0101773646 0.0093322838 0.0160688832 0.0112458792 0.0991520000 0.0078570000 0.0517290000 0.0000270000 0.0003400000 0.0384110000 8312460 96830484 1057169408 4.1175284386 3.9967877865 3.9951961040 49 1.9200000000 0.0102173164 0.0093503457 0.0160688832 0.0113779196 0.1324790000 0.0077730000 0.0444200000 0.0003760000 0.0002760000 0.0761880000 8314134 96830484 1057677312 4.1197614670 3.9957680702 3.9954757690 50 1.9600000000 0.0102211619 0.0093677620 0.0160688832 0.0114547442 0.0920390000 0.0083350000 0.0469280000 0.0000280000 0.0003000000 0.0356410000 8315808 96830484 1058439168 4.1222996712 3.9955277443 3.9957160950 51 2.0000000000 0.0102299955 0.0093846686 0.0160688832 0.0115132263 0.1082820000 0.0083660000 0.0523960000 0.0003680000 0.0003540000 0.0453180000 8317482 96830484 1058959360 4.1251668930 3.9945275784 3.9955182076 52 2.0400000000 0.0102266045 0.0094008596 0.0160688832 0.0115618081 0.0901440000 0.0081560000 0.0443980000 0.0000260000 0.0003410000 0.0363320000 8319156 96830484 1059835904 4.1282296181 3.9936106205 3.9955542088 53 2.0800000000 0.0102715930 0.0094172886 0.0160688832 0.0115838867 0.1286360000 0.0081360000 0.0455960000 0.0003200000 0.0002750000 0.0733750000 8320830 96830484 1060470784 4.1295466423 3.9927649498 3.9956350327 54 2.1200000000 0.0102795241 0.0094332559 0.0160688832 0.0116050819 0.0963990000 0.0079150000 0.0430580000 0.0000270000 0.0005240000 0.0410230000 8322504 96830484 1060995072 4.1327819824 3.9931232929 3.9951810837 55 2.1600000000 0.0103163803 0.0094493127 0.0160688832 0.0116347844 0.1427510000 0.0075150000 0.0735770000 0.0003990000 0.0002790000 0.0570650000 8324178 96830484 1061740544 4.1360116005 3.9953260422 3.9942359924 56 2.2000000000 0.0103946207 0.0094661932 0.0160688832 0.0116978921 0.1069270000 0.0074150000 0.0490000000 0.0000260000 0.0003060000 0.0459370000 8325852 96830484 1062375424 4.1373162270 3.9938941002 3.9940731525 57 2.2400000000 0.0104805371 0.0094839887 0.0160688832 0.0118348726 0.1519180000 0.0077690000 0.0529940000 0.0003170000 0.0002760000 0.0896570000 8327526 96830484 1063010304 4.1365695000 3.9913032055 3.9946730137 58 2.2800000000 0.0104900710 0.0095013350 0.0160688832 0.0119862448 0.1087990000 0.0076940000 0.0443240000 0.0000250000 0.0003680000 0.0554270000 8329200 96830484 1063645184 4.1383852959 3.9901564121 3.9942927361 59 2.3200000000 0.0108217485 0.0095237148 0.0160688832 0.0122081307 0.1460910000 0.0073980000 0.0560840000 0.0003010000 0.0003580000 0.0680270000 8330874 96830484 1064407040 4.1397399902 3.9898941517 3.9937949181 60 2.3600000000 0.0107696131 0.0095444798 0.0160688832 0.0123711615 0.1086100000 0.0084330000 0.0578300000 0.0000190000 0.0002500000 0.0378750000 8332548 96830484 1064931328 4.1426682472 3.9890098572 3.9926300049 61 2.4000000000 0.0104965102 0.0095600869 0.0160688832 0.0126430515 0.1310300000 0.0080120000 0.0411550000 0.0002010000 0.0001810000 0.0775970000 8334222 96830484 1065676800 4.1450257301 3.9885711670 3.9923589230 62 2.4400000000 0.0103447735 0.0095727431 0.0160688832 0.0128742462 0.0946920000 0.0079320000 0.0433220000 0.0000240000 0.0008670000 0.0406120000 8335896 96830484 1066201088 4.1489267349 3.9883503914 3.9910597801 63 2.4800000000 0.0102483397 0.0095834669 0.0160688832 0.0130853008 0.1108910000 0.0076710000 0.0498050000 0.0009580000 0.0002890000 0.0512210000 8337570 96830484 1066835968 4.1525845528 3.9888386726 3.9899265766 64 2.5200000000 0.0101946210 0.0095930161 0.0160688832 0.0132261323 0.0901980000 0.0077060000 0.0409570000 0.0000270000 0.0002950000 0.0401810000 8339244 96830484 1067573248 4.1565704346 3.9868667126 3.9882476330 65 2.5600000000 0.0100956382 0.0096007488 0.0160688832 0.0133257908 0.1408550000 0.0071970000 0.0485100000 0.0003710000 0.0003150000 0.0799650000 8346038 96830484 1068097536 4.1606850624 3.9870462418 3.9863679409 66 2.6000000000 0.0101253837 0.0096086978 0.0160688832 0.0134093144 0.0914570000 0.0074590000 0.0406970000 0.0000280000 0.0003960000 0.0419260000 8358208 96830484 1068969984 4.1652445793 3.9861567020 3.9840836525 67 2.6400000000 0.0101791359 0.0096172118 0.0160688832 0.0135126614 0.1060970000 0.0076120000 0.0390720000 0.0001960000 0.0002070000 0.0536300000 8359882 96830484 1069494272 4.1685161591 3.9857208729 3.9820842743 68 2.6800000000 0.0101869255 0.0096255900 0.0160688832 0.0136252746 0.1070470000 0.0069910000 0.0426830000 0.0000260000 0.0003570000 0.0523680000 8361556 96830484 1070129152 4.1731781960 3.9860131741 3.9792995453 69 2.7200000000 0.0101875020 0.0096337336 0.0160688832 0.0137351532 0.1474510000 0.0069580000 0.0470150000 0.0003510000 0.0002640000 0.0918080000 8363230 96830484 1070764032 4.1765737534 3.9839973450 3.9774465561 70 2.7600000000 0.0102176145 0.0096420748 0.0160688832 0.0139070540 0.0931600000 0.0072680000 0.0410720000 0.0000260000 0.0003160000 0.0434320000 8364904 96830484 1071398912 4.1788344383 3.9826326370 3.9764947891 71 2.8000000000 0.0102633368 0.0096508249 0.0160688832 0.0140159622 0.1090920000 0.0070900000 0.0401900000 0.0001920000 0.0001940000 0.0590690000 8366578 96830484 1072033792 4.1828689575 3.9832227230 3.9742212296 72 2.8400000000 0.0103054969 0.0096599176 0.0160688832 0.0141741926 0.1035810000 0.0068820000 0.0402560000 0.0000180000 0.0002040000 0.0510870000 8368252 96830484 1072668672 4.1856265068 3.9831962585 3.9727435112 73 2.8800000000 0.0103268595 0.0096690538 0.0160688832 0.0142979302 0.1488800000 0.0072420000 0.0432340000 0.0003580000 0.0002720000 0.0929760000 8369926 96830484 1073414144 4.1879143715 3.9826557636 3.9714829922 74 2.9200000000 0.0103388764 0.0096781054 0.0160688832 0.0143766092 0.0996900000 0.0075390000 0.0398980000 0.0000250000 0.0003040000 0.0466630000 8371600 96830484 1074065408 4.1923332214 3.9823169708 3.9687235355 75 2.9600000000 0.0103649581 0.0096872635 0.0160688832 0.0145132152 0.1094470000 0.0074730000 0.0396630000 0.0002360000 0.0001770000 0.0566940000 8373274 96830484 1074810880 4.1938962936 3.9824354649 3.9678480625 76 3.0000000000 0.0103874020 0.0096964758 0.0160688832 0.0145455296 0.1098130000 0.0071500000 0.0431790000 0.0000250000 0.0003130000 0.0556370000 8374948 96830484 1075335168 4.1988954544 3.9799420834 3.9647459984 77 3.0400000000 0.0103729162 0.0097052608 0.0160688832 0.0146121999 0.1511880000 0.0070700000 0.0425970000 0.0003230000 0.0002680000 0.0998260000 8376622 96830484 1075970048 4.2018432617 3.9786612988 3.9626824856 78 3.0800000000 0.0103810765 0.0097139251 0.0160688832 0.0146268462 0.1010170000 0.0070110000 0.0387960000 0.0000070000 0.0000830000 0.0501800000 8378296 96830484 1076604928 4.2063856125 3.9777352810 3.9592578411 79 3.1200000000 0.0103476308 0.0097219467 0.0160688832 0.0146751327 0.1136760000 0.0072460000 0.0432170000 0.0003860000 0.0002750000 0.0614290000 8379970 96830484 1077239808 4.2104434967 3.9773402214 3.9567110538 80 3.1600000000 0.0104052220 0.0097304876 0.0160688832 0.0150959289 0.1058520000 0.0070130000 0.0332860000 0.0000080000 0.0000820000 0.0619090000 8381644 96830484 1077874688 4.2190318108 3.9762656689 3.9505634308 81 3.2000000000 0.0103524309 0.0097381659 0.0160688832 0.0151197854 0.1712260000 0.0069690000 0.0470140000 0.0002900000 0.0003470000 0.1154490000 8383318 96830484 1078636544 4.2230148315 3.9758691788 3.9480741024 82 3.2400000000 0.0103167826 0.0097452222 0.0160688832 0.0151229048 0.0924450000 0.0071070000 0.0334870000 0.0000070000 0.0000760000 0.0492890000 8384992 96830484 1079271424 4.2263460159 3.9729228020 3.9457473755 83 3.2800000000 0.0103241010 0.0097521967 0.0160688832 0.0151688890 0.1312390000 0.0187040000 0.0530740000 0.0000800000 0.0000470000 0.0580100000 8386666 96830484 1295368192 4.2295274734 3.9726026058 3.9436554909 84 3.3200000000 0.0103217401 0.0097589769 0.0160688832 0.0151588758 0.1116690000 0.0071350000 0.0464410000 0.0000160000 0.0002070000 0.0526580000 8388340 96830484 1296527360 4.2317872047 3.9696841240 3.9422729015 85 3.3600000000 0.0103230877 0.0097656135 0.0160688832 0.0151688125 0.1713940000 0.0070700000 0.0480150000 0.0003150000 0.0003080000 0.1097140000 8390014 96830484 1297162240 4.2351279259 3.9683175087 3.9400277138 86 3.4000000000 0.0103287390 0.0097721615 0.0160688832 0.0152082543 0.1113060000 0.0073570000 0.0396210000 0.0000230000 0.0002760000 0.0628560000 8391688 96830484 1297797120 4.2371840477 3.9671514034 3.9388163090 87 3.4400000000 0.0103208339 0.0097784681 0.0160688832 0.0152310247 0.1466380000 0.0072150000 0.0543260000 0.0003280000 0.0003370000 0.0790920000 8393362 96830484 1298542592 4.2408509254 3.9666495323 3.9364771843 88 3.4800000000 0.0102681182 0.0097840323 0.0160688832 0.0152504954 0.1220710000 0.0069090000 0.0434100000 0.0000270000 0.0003880000 0.0648380000 8395036 96830484 1299177472 4.2444772720 3.9674115181 3.9339132309 89 3.5200000000 0.0102995709 0.0097898249 0.0160688832 0.0152535276 0.1722580000 0.0070530000 0.0479070000 0.0002970000 0.0003860000 0.1108950000 8396710 96830484 1299701760 4.2472844124 3.9669210911 3.9318666458 90 3.5600000000 0.0103567569 0.0097961241 0.0160688832 0.0152602331 0.1048330000 0.0071780000 0.0396930000 0.0000280000 0.0004140000 0.0515620000 8398384 96830484 1300463616 4.2495231628 3.9648990631 3.9302983284 91 3.6000000000 0.0103160087 0.0098018371 0.0160688832 0.0152758060 0.1124300000 0.0077120000 0.0414260000 0.0003790000 0.0002730000 0.0614000000 8400058 96830484 1301098496 4.2519841194 3.9640855789 3.9287343025 92 3.6400000000 0.0103381528 0.0098076666 0.0160688832 0.0152703181 0.1041030000 0.0069100000 0.0355530000 0.0000180000 0.0001950000 0.0581730000 8401732 96830484 1301733376 4.2550363541 3.9649424553 3.9266722202 93 3.6800000000 0.0103364950 0.0098133530 0.0160688832 0.0152333947 0.1686980000 0.0071950000 0.0439230000 0.0003950000 0.0002850000 0.1116000000 8403406 96830484 1302368256 4.2571849823 3.9636113644 3.9248032570 94 3.7200000000 0.0103842421 0.0098194263 0.0160688832 0.0151954408 0.1262840000 0.0072760000 0.0600550000 0.0000230000 0.0003590000 0.0523060000 8405080 96830484 1303003136 4.2597084045 3.9631004333 3.9234523773 95 3.7600000000 0.0104021374 0.0098255601 0.0160688832 0.0151533558 0.1112010000 0.0076050000 0.0390870000 0.0002880000 0.0006750000 0.0622830000 8406754 96830484 1303638016 4.2629003525 3.9634335041 3.9213182926 96 3.8000000000 0.0102999900 0.0098305020 0.0160688832 0.0151081820 0.1063500000 0.0072350000 0.0330170000 0.0000170000 0.0002240000 0.0592820000 8408428 96830484 1304272896 4.2654843330 3.9629988670 3.9189617634 97 3.8400000000 0.0103436559 0.0098357923 0.0160688832 0.0150714057 0.1721970000 0.0068370000 0.0565210000 0.0002880000 0.0003420000 0.1069370000 8410102 96830484 1304924160 4.2678208351 3.9627630711 3.9169416428 98 3.8800000000 0.0103036193 0.0098405660 0.0160688832 0.0150278085 0.1070650000 0.0071480000 0.0403690000 0.0000260000 0.0006710000 0.0563650000 8411776 96830484 1305669632 4.2687768936 3.9616146088 3.9162800312 99 3.9200000000 0.0103867864 0.0098460834 0.0160688832 0.0149738550 0.1294390000 0.0069910000 0.0458520000 0.0002950000 0.0002660000 0.0747770000 8413450 96830484 1306415104 4.2715058327 3.9610722065 3.9140627384 100 3.9600000000 0.0104499692 0.0098521223 0.0160688832 0.0149210132 0.1093680000 0.0070420000 0.0425330000 0.0000270000 0.0003160000 0.0581610000 8415124 96830484 1307049984 4.2730374336 3.9597287178 3.9127891064 101 4.0000000000 0.0105001945 0.0098585388 0.0160688832 0.0148718631 0.1429820000 0.0071000000 0.0397020000 0.0005430000 0.0002560000 0.0940680000 8416798 96830484 1307684864 4.2755141258 3.9615800381 3.9112975597 102 4.0400000000 0.0103933783 0.0098637823 0.0160688832 0.0148261492 0.1092880000 0.0085440000 0.0395030000 0.0000110000 0.0001090000 0.0568720000 8418472 96830484 1308209152 4.2776446342 3.9620947838 3.9096734524 103 4.0800000000 0.0104692886 0.0098696610 0.0160688832 0.0147805472 0.1304590000 0.0069520000 0.0431570000 0.0003650000 0.0002680000 0.0783510000 8420146 96830484 1308844032 4.2799487114 3.9626636505 3.9083991051 104 4.1200000000 0.0104708336 0.0098754416 0.0160688832 0.0147270239 0.1090500000 0.0070150000 0.0419640000 0.0000260000 0.0002820000 0.0584080000 8421820 96830484 1309478912 4.2816195488 3.9636330605 3.9070777893 105 4.1600000000 0.0105650183 0.0098820089 0.0160688832 0.0146802121 0.1519080000 0.0070470000 0.0392480000 0.0004780000 0.0002730000 0.1033840000 8423494 96830484 1310240768 4.2843341827 3.9649906158 3.9051678181 106 4.2000000000 0.0105156563 0.0098879868 0.0160688832 0.0146234224 0.1057520000 0.0075100000 0.0397110000 0.0000230000 0.0002810000 0.0568360000 8425168 96830484 1310875648 4.2858891487 3.9654176235 3.9039437771 107 4.2400000000 0.0105372919 0.0098940550 0.0160688832 0.0145603895 0.1087210000 0.0069640000 0.0366070000 0.0001900000 0.0001700000 0.0628190000 8426842 96830484 1311510528 4.2867360115 3.9654285908 3.9032173157 108 4.2800000000 0.0105649047 0.0099002666 0.0160688832 0.0144965138 0.1082040000 0.0072570000 0.0389980000 0.0000180000 0.0001940000 0.0582130000 8428516 96830484 1312145408 4.2903718948 3.9677782059 3.9002728462 109 4.3200000000 0.0106210206 0.0099068790 0.0160688832 0.0144297305 0.1723720000 0.0070750000 0.0431390000 0.0003190000 0.0002720000 0.1141650000 8430190 96830484 1312763904 4.2919774055 3.9684860706 3.8990099430 110 4.3600000000 0.0107103270 0.0099141831 0.0160688832 0.0143656656 0.1117670000 0.0074400000 0.0394430000 0.0000250000 0.0002880000 0.0580570000 8431864 96830484 1313398784 4.2928061485 3.9696662426 3.8979542255 111 4.4000000000 0.0107203554 0.0099214459 0.0160688832 0.0143024196 0.1446250000 0.0068220000 0.0443780000 0.0004030000 0.0002870000 0.0855250000 8433538 96830484 1314033664 4.2940211296 3.9718077183 3.8966026306 112 4.4400000000 0.0107960468 0.0099292548 0.0160688832 0.0142454633 0.1119250000 0.0072340000 0.0380310000 0.0000190000 0.0002590000 0.0649770000 8435212 96830484 1314668544 4.2964768410 3.9745378494 3.8943321705 113 4.4800000000 0.0108693969 0.0099375747 0.0160688832 0.0141827590 0.1639020000 0.0067940000 0.0356020000 0.0002440000 0.0002050000 0.1144080000 8436886 96830484 1315430400 4.2977981567 3.9770436287 3.8932936192 114 4.5200000000 0.0108514121 0.0099455908 0.0160688832 0.0141199915 0.1107230000 0.0073120000 0.0416950000 0.0000270000 0.0005380000 0.0584110000 8438560 96830484 1316065280 4.2986621857 3.9785618782 3.8922672272 115 4.5600000000 0.0109217837 0.0099540794 0.0160688832 0.0140599227 0.1103690000 0.0068140000 0.0330870000 0.0003380000 0.0002780000 0.0684800000 8440234 96830484 1316810752 4.2999701500 3.9811172485 3.8907353878 116 4.6000000000 0.0108626150 0.0099619116 0.0160688832 0.0140034291 0.1089220000 0.0070760000 0.0407810000 0.0000260000 0.0003690000 0.0591260000 8441908 96830484 1317445632 4.3004093170 3.9825234413 3.8896949291 117 4.6400000000 0.0110326828 0.0099710635 0.0160688832 0.0139603488 0.1514370000 0.0069530000 0.0448760000 0.0003350000 0.0003590000 0.0973430000 8443582 96830484 1318080512 4.3012814522 3.9852552414 3.8883314133 118 4.6800000000 0.0109935636 0.0099797288 0.0160688832 0.0139268932 0.1060410000 0.0070230000 0.0390670000 0.0000280000 0.0003060000 0.0580630000 8445256 96830484 1318604800 4.3018145561 3.9857378006 3.8877661228 119 4.7200000000 0.0109769925 0.0099881092 0.0160688832 0.0138870063 0.1286210000 0.0074940000 0.0430180000 0.0002990000 0.0003450000 0.0751120000 8446930 96830484 1319239680 4.3020415306 3.9884240627 3.8873972893 120 4.7600000000 0.0110459616 0.0099969246 0.0160688832 0.0138408862 0.1080150000 0.0070630000 0.0378730000 0.0000290000 0.0002940000 0.0555050000 8448604 96830484 1320001536 4.3019576073 3.9894912243 3.8864250183 121 4.8000000000 0.0110507077 0.0100056335 0.0160688832 0.0137973143 0.1551590000 0.0073200000 0.0388040000 0.0002970000 0.0003540000 0.1010330000 8450278 96830484 1320636416 4.3011765480 3.9908180237 3.8868768215 122 4.8400000000 0.0110885818 0.0100145102 0.0160688832 0.0137687597 0.1062830000 0.0076920000 0.0479730000 0.0000260000 0.0003050000 0.0486530000 8451952 96830484 1321271296 4.3003282547 3.9955956936 3.8862004280 123 4.8800000000 0.0111483596 0.0100237285 0.0160688832 0.0137227035 0.1157970000 0.0071800000 0.0387940000 0.0005760000 0.0002750000 0.0663750000 8453626 96830484 1321906176 4.2994222641 3.9979124069 3.8865044117 124 4.9200000000 0.0112627838 0.0100337208 0.0160688832 0.0136821832 0.1258650000 0.0068420000 0.0438990000 0.0000280000 0.0003080000 0.0674550000 8455300 96830484 1322541056 4.2986903191 3.9990355968 3.8864142895 125 4.9600000000 0.0112367161 0.0100433448 0.0160688832 0.0136407029 0.1850670000 0.0067210000 0.0500740000 0.0003790000 0.0002850000 0.1260350000 8456974 96830484 1323175936 4.2980127335 4.0019397736 3.8870081902 126 5.0000000000 0.0113278022 0.0100535389 0.0160688832 0.0136014382 0.1103810000 0.0096020000 0.0413860000 0.0000270000 0.0003730000 0.0573870000 8458648 96830484 1323810816 4.2978658676 4.0039119720 3.8868775368 127 5.0400000000 0.0113310935 0.0100635984 0.0160688832 0.0135729462 0.1088330000 0.0068280000 0.0368230000 0.0002010000 0.0002240000 0.0624570000 8460322 96830484 1324445696 4.2966051102 4.0054578781 3.8875687122 128 5.0800000000 0.0113838827 0.0100739131 0.0160688832 0.0135442718 0.1226070000 0.0074840000 0.0518800000 0.0000290000 0.0002980000 0.0546190000 8461996 96830484 1325207552 4.2956080437 4.0070581436 3.8879857063 129 5.1200000000 0.0113799525 0.0100840374 0.0160688832 0.0135157794 0.1485890000 0.0076330000 0.0390260000 0.0003100000 0.0003440000 0.0995810000 8473910 96830484 1325842432 4.2956304550 4.0097746849 3.8878090382 130 5.1600000000 0.0113449655 0.0100937369 0.0160688832 0.0134965036 0.1077060000 0.0070800000 0.0377160000 0.0000160000 0.0001950000 0.0575970000 8496576 96830484 1326477312 4.2937564850 4.0105371475 3.8891985416 131 5.2000000000 0.0113617256 0.0101034162 0.0160688832 0.0134766579 0.1290070000 0.0068160000 0.0408580000 0.0002120000 0.0005360000 0.0756250000 8498250 96830484 1327112192 4.2918047905 4.0106754303 3.8904232979 132 5.2400000000 0.0114310123 0.0101134737 0.0160688832 0.0134568893 0.1236260000 0.0068750000 0.0442780000 0.0000270000 0.0003010000 0.0636610000 8499924 96830484 1327874048 4.2898807526 4.0110359192 3.8916051388 133 5.2800000000 0.0114603983 0.0101236010 0.0160688832 0.0134255796 0.1938310000 0.0068290000 0.0564910000 0.0007030000 0.0002750000 0.1278430000 8501598 96830484 1328508928 4.2885565758 4.0118861198 3.8933205605 134 5.3200000000 0.0114360582 0.0101333955 0.0160688832 0.0133890437 0.1085390000 0.0070650000 0.0470260000 0.0000990000 0.0003040000 0.0523830000 8503272 96830484 1329143808 4.2866930962 4.0135512352 3.8948113918 135 5.3600000000 0.0114026340 0.0101427972 0.0160688832 0.0133531311 0.1260030000 0.0070140000 0.0416400000 0.0003600000 0.0002720000 0.0723140000 8504946 96830484 1329889280 4.2841329575 4.0137987137 3.8970122337 136 5.4000000000 0.0114903795 0.0101527059 0.0160688832 0.0133196491 0.1122030000 0.0070290000 0.0445330000 0.0000260000 0.0003650000 0.0584990000 8506620 96830484 1330524160 4.2826952934 4.0154962540 3.8983576298 137 5.4400000000 0.0114553794 0.0101622145 0.0160688832 0.0132876137 0.1463770000 0.0069320000 0.0404410000 0.0004460000 0.0002780000 0.0965890000 8508294 96830484 1331048448 4.2817316055 4.0180644989 3.8996050358 138 5.4800000000 0.0114679104 0.0101716760 0.0160688832 0.0133454579 0.1079320000 0.0068000000 0.0406390000 0.0000260000 0.0002900000 0.0550380000 8509968 96830484 1331683328 4.2781672478 4.0180053711 3.9027519226 139 5.5200000000 0.0114683248 0.0101810044 0.0160688832 0.0133143794 0.1270440000 0.0070450000 0.0437060000 0.0002990000 0.0002750000 0.0669680000 8511642 96830484 1332318208 4.2758464813 4.0187849998 3.9046504498 140 5.5600000000 0.0115279611 0.0101906256 0.0160688832 0.0132947789 0.1118690000 0.0068560000 0.0453540000 0.0000280000 0.0002960000 0.0575190000 8513316 96830484 1332969472 4.2747755051 4.0207147598 3.9059722424 141 5.6000000000 0.0116433930 0.0102009289 0.0160688832 0.0132714693 0.1500800000 0.0071590000 0.0422810000 0.0003060000 0.0003400000 0.0982690000 8514990 96830484 1333714944 4.2729363441 4.0225696564 3.9076199532 142 5.6400000000 0.0116384150 0.0102110520 0.0160688832 0.0132452625 0.1058490000 0.0074740000 0.0390360000 0.0000260000 0.0003690000 0.0534030000 8516664 96830484 1334349824 4.2715783119 4.0250854492 3.9090197086 143 5.6800000000 0.0115826782 0.0102206438 0.0160688832 0.0132274155 0.1295600000 0.0069670000 0.0485170000 0.0002940000 0.0003470000 0.0699710000 8518338 96830484 1334984704 4.2691965103 4.0254769325 3.9106385708 144 5.7200000000 0.0116712172 0.0102307172 0.0160688832 0.0131976542 0.1279260000 0.0069810000 0.0476560000 0.0000270000 0.0002890000 0.0640930000 8520012 96830484 1335619584 4.2666106224 4.0258173943 3.9120497704 145 5.7600000000 0.0116763068 0.0102406868 0.0160688832 0.0131673142 0.1585470000 0.0069850000 0.0394420000 0.0003500000 0.0002680000 0.1097240000 8521686 96830484 1336254464 4.2646765709 4.0293097496 3.9138391018 146 5.8000000000 0.0116876094 0.0102505973 0.0160688832 0.0131391179 0.1010570000 0.0083850000 0.0397750000 0.0000250000 0.0002840000 0.0507920000 8523360 96830484 1336889344 4.2625465393 4.0300021172 3.9152028561 147 5.8400000000 0.0117289247 0.0102606539 0.0160688832 0.0131166345 0.1255530000 0.0069740000 0.0444280000 0.0001960000 0.0001730000 0.0645790000 8525034 96830484 1337524224 4.2595829964 4.0310149193 3.9175240993 148 5.8800000000 0.0117274253 0.0102705645 0.0160688832 0.0130963479 0.1297400000 0.0071660000 0.0484920000 0.0000280000 0.0003960000 0.0655430000 8526708 96830484 1338269696 4.2579460144 4.0322299004 3.9182693958 149 5.9200000000 0.0117631005 0.0102805815 0.0160688832 0.0130754419 0.1491680000 0.0070010000 0.0391120000 0.0003250000 0.0001890000 0.0961890000 8528382 96830484 1338920960 4.2547078133 4.0322666168 3.9203569889 150 5.9600000000 0.0116612921 0.0102897863 0.0160688832 0.0130564705 0.1078540000 0.0077710000 0.0392320000 0.0000170000 0.0001870000 0.0512000000 8530056 96830484 1339555840 4.2509393692 4.0308976173 3.9226186275 151 6.0000000000 0.0118112555 0.0102998622 0.0160688832 0.0130335905 0.1257420000 0.0071120000 0.0425940000 0.0003560000 0.0002760000 0.0668800000 8531730 96830484 1340190720 4.2472825050 4.0313320160 3.9248015881 152 6.0400000000 0.0116222585 0.0103085622 0.0160688832 0.0130164075 0.1302430000 0.0071960000 0.0513000000 0.0000280000 0.0003040000 0.0639160000 8533404 96830484 1340825600 4.2438769341 4.0298242569 3.9271061420 153 6.0800000000 0.0118302358 0.0103185078 0.0160688832 0.0130000289 0.1526500000 0.0070300000 0.0413480000 0.0002920000 0.0003260000 0.0944330000 8535078 96830484 1341460480 4.2396488190 4.0321898460 3.9297087193 154 6.1200000000 0.0117342807 0.0103277011 0.0160688832 0.0129928915 0.0962240000 0.0075890000 0.0401600000 0.0000280000 0.0002820000 0.0462900000 8536752 96830484 1342095360 4.2366466522 4.0337581635 3.9314088821 155 6.1600000000 0.0118555008 0.0103375579 0.0160688832 0.0129868906 0.1065610000 0.0070780000 0.0395430000 0.0002930000 0.0002670000 0.0575240000 8538426 96830484 1342730240 4.2323813438 4.0331606865 3.9339160919 156 6.2000000000 0.0118788853 0.0103474382 0.0160688832 0.0129841752 0.1073140000 0.0071000000 0.0442470000 0.0000250000 0.0002840000 0.0468690000 8540100 96830484 1343365120 4.2278046608 4.0340232849 3.9366228580 157 6.2400000000 0.0116838142 0.0103559501 0.0160688832 0.0129858830 0.1482280000 0.0079630000 0.0428800000 0.0002850000 0.0002650000 0.0877070000 8541774 96830484 1344000000 4.2235040665 4.0357966423 3.9383356571 158 6.2800000000 0.0117797442 0.0103649615 0.0160688832 0.0130008251 0.0952960000 0.0072810000 0.0428940000 0.0000250000 0.0002820000 0.0429060000 8543448 96830484 1344761856 4.2207098007 4.0370764732 3.9399261475 159 6.3200000000 0.0116844848 0.0103732604 0.0160688832 0.0130075025 0.1041830000 0.0071170000 0.0388280000 0.0003070000 0.0008090000 0.0531170000 8545122 96830484 1345396736 4.2167997360 4.0371131897 3.9417018890 160 6.3600000000 0.0117274290 0.0103817239 0.0160688832 0.0130075748 0.1050670000 0.0077140000 0.0395110000 0.0000420000 0.0002860000 0.0475420000 8546796 96830484 1346031616 4.2136745453 4.0383620262 3.9433155060 161 6.4000000000 0.0116891535 0.0103898446 0.0160688832 0.0130087088 0.1683540000 0.0071550000 0.0593750000 0.0003720000 0.0002810000 0.0917490000 8548470 96830484 1346666496 4.2107400894 4.0394763947 3.9446489811 162 6.4400000000 0.0116699478 0.0103977465 0.0160688832 0.0130211848 0.1066230000 0.0076170000 0.0408260000 0.0002410000 0.0003000000 0.0480350000 8550144 96830484 1347301376 4.2062578201 4.0388116837 3.9462721348 163 6.4800000000 0.0116918040 0.0104056855 0.0160688832 0.0130192795 0.1320520000 0.0071790000 0.0533070000 0.0003010000 0.0003470000 0.0689760000 8551818 96830484 1347952640 4.2021579742 4.0381903648 3.9482078552 164 6.5200000000 0.0116668222 0.0104133754 0.0160688832 0.0130124032 0.0907650000 0.0072440000 0.0355810000 0.0000080000 0.0000820000 0.0458300000 8553492 96830484 1348698112 4.1990218163 4.0369687080 3.9498789310 165 6.5600000000 0.0115732607 0.0104204050 0.0160688832 0.0130009657 0.1482760000 0.0071900000 0.0420600000 0.0002920000 0.0002670000 0.0886360000 8555166 96830484 1349332992 4.1947069168 4.0400862694 3.9517047405 166 6.6000000000 0.0115166008 0.0104270086 0.0160688832 0.0130112373 0.0945810000 0.0078250000 0.0433480000 0.0000260000 0.0005460000 0.0407740000 8556840 96830484 1349967872 4.1891398430 4.0387005806 3.9543192387 167 6.6400000000 0.0115298992 0.0104336127 0.0160688832 0.0130287058 0.1073900000 0.0075210000 0.0413920000 0.0002790000 0.0002540000 0.0535330000 8558514 96830484 1350602752 4.1849708557 4.0384707451 3.9564499855 168 6.6800000000 0.0115779880 0.0104404244 0.0160688832 0.0130288788 0.1088900000 0.0071900000 0.0455840000 0.0000240000 0.0003600000 0.0515250000 8560188 96830484 1351237632 4.1812186241 4.0408911705 3.9582777023 169 6.7200000000 0.0116317123 0.0104474735 0.0160688832 0.0130725006 0.1476570000 0.0072980000 0.0433510000 0.0002830000 0.0003440000 0.0873780000 8561862 96830484 1351872512 4.1770572662 4.0396995544 3.9599988461 170 6.7600000000 0.0116111105 0.0104543184 0.0160688832 0.0130888952 0.0915790000 0.0079860000 0.0425010000 0.0000270000 0.0010090000 0.0380480000 8563536 96830484 1352507392 4.1733508110 4.0386385918 3.9614419937 171 6.8000000000 0.0117455628 0.0104618695 0.0160688832 0.0131028762 0.1080920000 0.0076140000 0.0479240000 0.0002820000 0.0003420000 0.0496040000 8565210 96830484 1353142272 4.1702313423 4.0412788391 3.9623868465 172 6.8400000000 0.0118740229 0.0104700797 0.0160688832 0.0131235642 0.1069840000 0.0073770000 0.0463160000 0.0000300000 0.0003820000 0.0478210000 8566884 96830484 1353904128 4.1676292419 4.0422730446 3.9634246826 173 6.8800000000 0.0121291373 0.0104796697 0.0160688832 0.0131499375 0.1288690000 0.0076380000 0.0370320000 0.0001940000 0.0001700000 0.0817660000 8568558 96830484 1354539008 4.1663899422 4.0419526100 3.9638161659 174 6.9200000000 0.0121169472 0.0104890793 0.0160688832 0.0131792667 0.1050940000 0.0079900000 0.0443040000 0.0000290000 0.0002850000 0.0427710000 8570232 96830484 1355173888 4.1649451256 4.0400447845 3.9652476311 175 6.9600000000 0.0121503351 0.0104985722 0.0160688832 0.0132192490 0.1121530000 0.0072800000 0.0474270000 0.0003610000 0.0002730000 0.0547410000 8571906 96830484 1355808768 4.1648960114 4.0410470963 3.9655835629 176 7.0000000000 0.0118927239 0.0105064935 0.0160688832 0.0132258630 0.1060910000 0.0076160000 0.0441810000 0.0000270000 0.0002940000 0.0442150000 8573580 96830484 1356460032 4.1653237343 4.0422935486 3.9654874802 177 7.0400000000 0.0117918076 0.0105137552 0.0160688832 0.0132657882 0.1715950000 0.0076940000 0.0572380000 0.0002960000 0.0004020000 0.0956940000 8575254 96830484 1357078528 4.1632113457 4.0442285538 3.9663431644 178 7.0800000000 0.0116490507 0.0105201332 0.0160688832 0.0133047122 0.0944730000 0.0084530000 0.0426120000 0.0000240000 0.0009600000 0.0393760000 8576928 96830484 1357713408 4.1613192558 4.0444965363 3.9668288231 179 7.1200000000 0.0115900980 0.0105261107 0.0160688832 0.0133609481 0.1085290000 0.0080200000 0.0439560000 0.0003540000 0.0005800000 0.0501730000 8578602 96830484 1358475264 4.1599874496 4.0428586006 3.9675276279 180 7.1600000000 0.0115908040 0.0105320257 0.0160688832 0.0133911064 0.1079500000 0.0076010000 0.0463850000 0.0000260000 0.0002880000 0.0438310000 8580276 96830484 1359126528 4.1590342522 4.0444536209 3.9677786827 181 7.2000000000 0.0115358932 0.0105375719 0.0160688832 0.0133803839 0.1581200000 0.0079880000 0.0698640000 0.0002900000 0.0003410000 0.0688720000 8581950 96830484 1359728640 4.1564488411 4.0446562767 3.9684493542 182 7.2400000000 0.0115800658 0.0105432999 0.0160688832 0.0133738089 0.1040460000 0.0083540000 0.0464250000 0.0000260000 0.0003120000 0.0387690000 8583624 96830484 1360363520 4.1561017036 4.0459227562 3.9684019089 183 7.2800000000 0.0116024697 0.0105490877 0.0160688832 0.0133593548 0.1107460000 0.0085690000 0.0467200000 0.0003180000 0.0002760000 0.0456060000 8585298 96830484 1361018880 4.1517076492 4.0466718674 3.9696056843 184 7.3200000000 0.0115742749 0.0105546594 0.0160688832 0.0133611318 0.0917320000 0.0088280000 0.0456130000 0.0000270000 0.0003120000 0.0348370000 8586972 96830484 1361653760 4.1499624252 4.0453777313 3.9699053764 185 7.3600000000 0.0116364853 0.0105605071 0.0160688832 0.0133488101 0.1410990000 0.0084570000 0.0456790000 0.0003100000 0.0006820000 0.0747920000 8588646 96830484 1362288640 4.1450195312 4.0458950996 3.9703154564 186 7.4000000000 0.0116535900 0.0105663839 0.0160688832 0.0133614637 0.0910450000 0.0084350000 0.0366200000 0.0000260000 0.0002790000 0.0399110000 8590320 96830484 1362903040 4.1449046135 4.0455927849 3.9707882404 187 7.4400000000 0.0116579123 0.0105722209 0.0160688832 0.0133787679 0.1081100000 0.0080150000 0.0427830000 0.0002890000 0.0002630000 0.0471700000 8591994 96830484 1363685376 4.1424927711 4.0439248085 3.9710206985 188 7.4800000000 0.0117064435 0.0105782540 0.0160688832 0.0133939730 0.1093980000 0.0078010000 0.0482870000 0.0000280000 0.0003660000 0.0447330000 8593668 96830484 1364320256 4.1395893097 4.0431394577 3.9719662666 189 7.5200000000 0.0116084237 0.0105837046 0.0160688832 0.0134276957 0.1312070000 0.0080520000 0.0445450000 0.0002940000 0.0003460000 0.0756390000 8595342 96830484 1364955136 4.1372256279 4.0444140434 3.9727127552 190 7.5600000000 0.0116173550 0.0105891449 0.0160688832 0.0134802601 0.1059350000 0.0080400000 0.0412190000 0.0000320000 0.0003350000 0.0410100000 8597016 96830484 1365569536 4.1345343590 4.0428066254 3.9734525681 191 7.6000000000 0.0117216762 0.0105950744 0.0160688832 0.0135193814 0.1244060000 0.0079030000 0.0644120000 0.0003010000 0.0000550000 0.0403520000 8598690 96830484 1366224896 4.1330032349 4.0449972153 3.9736485481 192 7.6400000000 0.0117034623 0.0106008472 0.0160688832 0.0135408274 0.1037790000 0.0086210000 0.0467000000 0.0000270000 0.0003060000 0.0366950000 8600364 96830484 1366839296 4.1303210258 4.0446224213 3.9739420414 193 7.6800000000 0.0115789250 0.0106059150 0.0160688832 0.0135750117 0.1257790000 0.0088440000 0.0446300000 0.0003930000 0.0002690000 0.0694160000 8602038 96830484 1367621632 4.1289186478 4.0451693535 3.9744098186 194 7.7200000000 0.0116329975 0.0106112092 0.0160688832 0.0135792179 0.0953610000 0.0082570000 0.0445100000 0.0000250000 0.0005360000 0.0385330000 8603712 96830484 1368256512 4.1264696121 4.0436506271 3.9741537571 195 7.7600000000 0.0117179183 0.0106168847 0.0160688832 0.0135758905 0.1074450000 0.0083770000 0.0440620000 0.0003650000 0.0002740000 0.0453420000 8605386 96830484 1368891392 4.1270236969 4.0458083153 3.9741954803 196 7.8000000000 0.0116291204 0.0106220491 0.0160688832 0.0135626179 0.1027890000 0.0082920000 0.0536990000 0.0000260000 0.0003070000 0.0381360000 8607060 96830484 1369526272 4.1233139038 4.0450701714 3.9740960598 197 7.8400000000 0.0116244545 0.0106271375 0.0160688832 0.0135739694 0.1360250000 0.0087630000 0.0422350000 0.0003710000 0.0002830000 0.0820740000 8608734 96830484 1370161152 4.1271924973 4.0456609726 3.9743714333 198 7.8800000000 0.0116698844 0.0106324039 0.0160688832 0.0135796473 0.1026550000 0.0088460000 0.0458750000 0.0000310000 0.0003090000 0.0361720000 8610408 96830484 1370775552 4.1250057220 4.0462226868 3.9743957520 199 7.9200000000 0.0116106393 0.0106373197 0.0160688832 0.0136032284 0.1073530000 0.0087860000 0.0442400000 0.0003110000 0.0002780000 0.0422560000 8612082 96830484 1371430912 4.1297459602 4.0473923683 3.9747793674 200 7.9600000000 0.0116057666 0.0106421619 0.0160688832 0.0136177550 0.0917270000 0.0089020000 0.0444400000 0.0000280000 0.0003070000 0.0357460000 8613756 96830484 1372065792 4.1285181046 4.0486536026 3.9746446609 201 8.0000000000 0.0116106719 0.0106469803 0.0160688832 0.0136319022 0.1298840000 0.0092550000 0.0500010000 0.0003670000 0.0002800000 0.0675050000 8615430 96830484 1372700672 4.1307358742 4.0491256714 3.9749488831 202 8.0400000000 0.0116131874 0.0106517635 0.0160688832 0.0136289954 0.1061840000 0.0082750000 0.0518250000 0.0000310000 0.0003830000 0.0359680000 8617104 96830484 1373315072 4.1294398308 4.0488491058 3.9750192165 203 8.0800000000 0.0116105312 0.0106564865 0.0160688832 0.0136117187 0.1087700000 0.0090680000 0.0456100000 0.0003210000 0.0003510000 0.0426290000 8618778 96830484 1374097408 4.1265048981 4.0501441956 3.9753460884 204 8.1200000000 0.0116560897 0.0106613866 0.0160688832 0.0135829113 0.0916630000 0.0088810000 0.0457310000 0.0000290000 0.0003100000 0.0343830000 8620452 96830484 1374732288 4.1254281998 4.0523848534 3.9759604931 205 8.1600000000 0.0116836950 0.0106663734 0.0160688832 0.0135581989 0.1222510000 0.0089290000 0.0423850000 0.0003010000 0.0011520000 0.0670850000 8622126 96830484 1375367168 4.1232099533 4.0507121086 3.9765834808 206 8.1999999990 0.0117137926 0.0106714580 0.0160688832 0.0135417687 0.0921760000 0.0088900000 0.0458500000 0.0000270000 0.0003070000 0.0346230000 8623800 96830484 1375981568 4.1206393242 4.0482845306 3.9780797958 207 8.2400000000 0.0115740765 0.0106758185 0.0160688832 0.0135365098 0.1087880000 0.0088780000 0.0570970000 0.0003780000 0.0002780000 0.0398270000 8625474 96830484 1376636928 4.1189093590 4.0497226715 3.9789142609 208 8.2799999990 0.0117162131 0.0106808204 0.0160688832 0.0135544478 0.0892770000 0.0082780000 0.0423850000 0.0000240000 0.0002940000 0.0356490000 8627148 96830484 1377271808 4.1192107201 4.0470914841 3.9807753563 209 8.3200000000 0.0117718149 0.0106860404 0.0160688832 0.0135663662 0.1282700000 0.0082290000 0.0434960000 0.0003750000 0.0006120000 0.0731820000 8628822 96830484 1378033664 4.1173605919 4.0491051674 3.9813451767 210 8.3599999990 0.0117093315 0.0106909132 0.0160688832 0.0135809645 0.0895560000 0.0079330000 0.0427940000 0.0000270000 0.0003020000 0.0361380000 8630496 96830484 1378668544 4.1144661903 4.0526242256 3.9819579124 211 8.4000000000 0.0118187051 0.0106962582 0.0160688832 0.0136140574 0.1034610000 0.0080050000 0.0400250000 0.0003140000 0.0002600000 0.0430060000 8632170 96830484 1379303424 4.1122684479 4.0532150269 3.9828631878 212 8.4399999990 0.0117824664 0.0107013819 0.0160688832 0.0136392722 0.0919070000 0.0085600000 0.0435620000 0.0000270000 0.0010200000 0.0363360000 8633844 96830484 1379938304 4.1128077507 4.0502657890 3.9848432541 213 8.4800000000 0.0118173612 0.0107066212 0.0160688832 0.0136510305 0.1223790000 0.0084870000 0.0424900000 0.0002940000 0.0012050000 0.0674840000 8635518 96830484 1380573184 4.1087675095 4.0516600609 3.9856457710 214 8.5200000000 0.0117540453 0.0107115157 0.0160688832 0.0136666927 0.0952260000 0.0080280000 0.0451220000 0.0000270000 0.0005180000 0.0391170000 8637192 96830484 1381208064 4.1077079773 4.0515499115 3.9871053696 215 8.5600000000 0.0118556470 0.0107168372 0.0160688832 0.0137002542 0.1085810000 0.0080530000 0.0445250000 0.0002900000 0.0002650000 0.0510510000 8638866 96830484 1381949440 4.1060810089 4.0499134064 3.9883561134 216 8.6000000000 0.0118700620 0.0107221762 0.0160688832 0.0137168012 0.1085250000 0.0078600000 0.0470530000 0.0000310000 0.0003230000 0.0481020000 8640540 96830484 1382604800 4.1088390350 4.0540013313 3.9906768799 217 8.6400000000 0.0119278869 0.0107277325 0.0160688832 0.0137191037 0.1476440000 0.0076730000 0.0469570000 0.0003630000 0.0002730000 0.0808940000 8642214 96830484 1383239680 4.1085953712 4.0555882454 3.9921019077 218 8.6800000000 0.0119619071 0.0107333939 0.0160688832 0.0137276920 0.0912710000 0.0082630000 0.0427800000 0.0000840000 0.0012680000 0.0363420000 8643888 96830484 1383874560 4.1110982895 4.0548624992 3.9943926334 219 8.7200000000 0.0119771613 0.0107390732 0.0160688832 0.0137533696 0.1064780000 0.0083770000 0.0419760000 0.0002890000 0.0003370000 0.0442290000 8645562 96830484 1384488960 4.1132078171 4.0541248322 3.9978816509 220 8.7600000000 0.0120604616 0.0107450795 0.0160688832 0.0137669402 0.0918140000 0.0081610000 0.0442770000 0.0000300000 0.0003160000 0.0364710000 8647236 96830484 1385123840 4.1134276390 4.0522031784 4.0012841225 221 8.8000000000 0.0119100614 0.0107503509 0.0160688832 0.0137922380 0.1275610000 0.0079450000 0.0439530000 0.0002880000 0.0003450000 0.0724260000 8648910 96830484 1385906176 4.1150217056 4.0525088310 4.0035700798 222 8.8400000000 0.0119636068 0.0107558160 0.0160688832 0.0138204260 0.0919460000 0.0077700000 0.0427720000 0.0000270000 0.0003590000 0.0385060000 8650584 96830484 1386541056 4.1137385368 4.0546460152 4.0052299500 223 8.8800000000 0.0119565716 0.0107612006 0.0160688832 0.0138591089 0.1049040000 0.0076470000 0.0410760000 0.0003760000 0.0002790000 0.0450420000 8652258 96830484 1387155456 4.1125340462 4.0534796715 4.0072183609 224 8.9200000000 0.0119376751 0.0107664527 0.0160688832 0.0138783408 0.0916220000 0.0079330000 0.0438670000 0.0000250000 0.0010530000 0.0361920000 8653932 96830484 1387810816 4.1087255478 4.0531806946 4.0082864761 225 8.9600000000 0.0119382022 0.0107716605 0.0160688832 0.0140224393 0.1255510000 0.0079330000 0.0438970000 0.0008320000 0.0002830000 0.0699750000 8655606 96830484 1388445696 4.0668630600 4.0475239754 3.9936082363 226 9.0000000000 0.0119296024 0.0107767841 0.0160688832 0.0140292257 0.1074370000 0.0074790000 0.0448660000 0.0000260000 0.0002840000 0.0418550000 8657280 96830484 1389080576 4.0616507530 4.0507497787 3.9927334785 227 9.0400000000 0.0119606266 0.0107819993 0.0160688832 0.0140363306 0.1495880000 0.0076720000 0.0844160000 0.0000590000 0.0000520000 0.0456880000 8658954 96830484 1389715456 4.0582652092 4.0495438576 3.9932756424 228 9.0800000000 0.0118816802 0.0107868224 0.0160688832 0.0140441232 0.0935330000 0.0078820000 0.0463610000 0.0000300000 0.0003850000 0.0363040000 8660628 96830484 1390329856 4.0544943810 4.0495352745 3.9934167862 229 9.1200000000 0.0119941933 0.0107920948 0.0160688832 0.0140502648 0.1264730000 0.0079280000 0.0455960000 0.0003210000 0.0002740000 0.0697180000 8662302 96830484 1390964736 4.0500655174 4.0491690636 3.9931211472 230 9.1600000000 0.0119068362 0.0107969415 0.0160688832 0.0140598146 0.1071010000 0.0073430000 0.0449260000 0.0000260000 0.0003560000 0.0418900000 8663976 96830484 1391599616 4.0452556610 4.0494251251 3.9931840897 231 9.2000000000 0.0119470153 0.0108019202 0.0160688832 0.0140644650 0.1501260000 0.0074810000 0.0832660000 0.0002990000 0.0002770000 0.0516100000 8665650 96830484 1392361472 4.0414280891 4.0490531921 3.9926543236 232 9.2400000000 0.0120501509 0.0108073005 0.0160688832 0.0140708250 0.1285970000 0.0074070000 0.0614460000 0.0000270000 0.0002990000 0.0497110000 8667324 96830484 1393016832 4.0377044678 4.0484910011 3.9929575920 233 9.2800000000 0.0120224869 0.0108125159 0.0160688832 0.0140828409 0.1562700000 0.0075390000 0.0709500000 0.0003920000 0.0002720000 0.0745180000 8668998 96830484 1393651712 4.0350041389 4.0494141579 3.9921438694 234 9.3200000000 0.0120205171 0.0108176783 0.0160688832 0.0140861686 0.1219840000 0.0077540000 0.0670300000 0.0000270000 0.0002950000 0.0400140000 8670672 96830484 1394286592 4.0307021141 4.0494570732 3.9914429188 235 9.3600000000 0.0121155167 0.0108232010 0.0160688832 0.0141059905 0.1085080000 0.0081350000 0.0448590000 0.0003840000 0.0002640000 0.0458450000 8672346 96830484 1394921472 4.0281777382 4.0488553047 3.9913506508 236 9.4000000000 0.0120334392 0.0108283291 0.0160688832 0.0141431089 0.1074900000 0.0078460000 0.0456570000 0.0000260000 0.0003150000 0.0401250000 8674020 96830484 1395556352 4.0254244804 4.0476412773 3.9910633564 237 9.4400000000 0.0119889863 0.0108332264 0.0160688832 0.0141720857 0.1256840000 0.0077940000 0.0440180000 0.0003120000 0.0002750000 0.0706250000 8675694 96830484 1396191232 4.0225977898 4.0447998047 3.9906232357 238 9.4800000000 0.0120079089 0.0108381620 0.0160688832 0.0141971217 0.1063540000 0.0073190000 0.0436220000 0.0000270000 0.0003040000 0.0418230000 8677368 96830484 1396826112 4.0189905167 4.0408120155 3.9903335571 239 9.5200000000 0.0119541977 0.0108428316 0.0160688832 0.0142100034 0.1122060000 0.0078620000 0.0537120000 0.0003030000 0.0002770000 0.0467640000 8679042 96830484 1397440512 4.0166883469 4.0411190987 3.9899003506 240 9.5600000000 0.0121024558 0.0108480801 0.0160688832 0.0143569899 0.1066540000 0.0077630000 0.0424250000 0.0000280000 0.0003070000 0.0436470000 8680716 96830484 1398075392 4.0138998032 4.0350608826 3.9909913540 241 9.6000000000 0.0120616220 0.0108531155 0.0160688832 0.0143556161 0.1678340000 0.0072270000 0.0563650000 0.0003100000 0.0003350000 0.0898770000 8682390 96830484 1398857728 4.0113334656 4.0350675583 3.9900867939 242 9.6400000000 0.0121494606 0.0108584723 0.0160688832 0.0143684262 0.0926730000 0.0080240000 0.0433330000 0.0000270000 0.0010670000 0.0375140000 8684064 96830484 1399492608 4.0102124214 4.0327782631 3.9905955791 243 9.6800000000 0.0121773807 0.0108638999 0.0160688832 0.0143833103 0.1068670000 0.0079510000 0.0421380000 0.0001950000 0.0001730000 0.0499030000 8685738 96830484 1400127488 4.0083203316 4.0301547050 3.9902875423 244 9.7200000000 0.0121323066 0.0108690983 0.0160688832 0.0143926316 0.1081750000 0.0070000000 0.0465380000 0.0000240000 0.0006110000 0.0460230000 8687412 96830484 1400762368 4.0066981316 4.0294275284 3.9906592369 245 9.7600000000 0.0121190408 0.0108742001 0.0160688832 0.0143908612 0.1429680000 0.0072330000 0.0494490000 0.0002840000 0.0003380000 0.0829180000 8689086 96830484 1401397248 4.0048408508 4.0302281380 3.9904325008 246 9.8000000000 0.0122210858 0.0108796753 0.0160688832 0.0143943404 0.0967870000 0.0070760000 0.0456220000 0.0000240000 0.0004980000 0.0408320000 8690760 96830484 1402011648 4.0029053688 4.0289654732 3.9904191494 247 9.8400000000 0.0122923814 0.0108853947 0.0160688832 0.0144014845 0.1231030000 0.0070940000 0.0539290000 0.0005410000 0.0002700000 0.0533270000 8692434 96830484 1402667008 3.9997181892 4.0285401344 3.9895770550 248 9.8800000000 0.0124170287 0.0108915707 0.0160688832 0.0143984754 0.1288120000 0.0069550000 0.0584780000 0.0000220000 0.0003700000 0.0497990000 8694108 96830484 1403428864 3.9964382648 4.0253014565 3.9891433716 249 9.9200000000 0.0124373613 0.0108977786 0.0160688832 0.0143999031 0.1549820000 0.0079080000 0.0586040000 0.0002870000 0.0003310000 0.0740940000 8695782 96830484 1404063744 3.9924438000 4.0222172737 3.9873404503 250 9.9600000000 0.0123988912 0.0109037831 0.0160688832 0.0143933008 0.1089090000 0.0074810000 0.0461480000 0.0000260000 0.0003180000 0.0410180000 8697456 96830484 1404698624 3.9895977974 4.0222492218 3.9865686893 251 10.0000000000 0.0124279056 0.0109098553 0.0160688832 0.0143939247 0.1097670000 0.0077840000 0.0440920000 0.0003220000 0.0002760000 0.0474210000 8699130 96830484 1405333504 3.9863152504 4.0198888779 3.9855332375 252 10.0400000000 0.0125574544 0.0109163934 0.0160688832 0.0144000748 0.1080260000 0.0078310000 0.0449110000 0.0000260000 0.0003150000 0.0416520000 8700804 96830484 1405968384 3.9826886654 4.0179209709 3.9842207432 253 10.0800000000 0.0125354277 0.0109227927 0.0160688832 0.0143968552 0.1526610000 0.0074140000 0.0601250000 0.0003060000 0.0002720000 0.0696840000 8702478 96830484 1406582784 3.9799017906 4.0172963142 3.9833657742 254 10.1200000000 0.0124255959 0.0109287093 0.0160688832 0.0143937698 0.1126500000 0.0075840000 0.0523050000 0.0000270000 0.0003000000 0.0411010000 8704152 96830484 1407365120 3.9772431850 4.0153059959 3.9828782082 255 10.1600000000 0.0124032628 0.0109344918 0.0160688832 0.0143874060 0.1090560000 0.0078750000 0.0424450000 0.0003090000 0.0003460000 0.0479880000 8705826 96830484 1408000000 3.9745347500 4.0142412186 3.9816944599 256 10.2000000000 0.0122624105 0.0109396790 0.0160688832 0.0143861645 0.1092010000 0.0074520000 0.0508680000 0.0000300000 0.0003740000 0.0420930000 8707500 96830484 1408634880 3.9720880985 4.0129384995 3.9812843800 257 10.2400000000 0.0122007923 0.0109445861 0.0160688832 0.0144946433 0.1275070000 0.0075920000 0.0448370000 0.0004550000 0.0003500000 0.0712830000 8729654 96830484 1409249280 3.9675195217 4.0092396736 3.9801411629 258 10.2800000000 0.0121745849 0.0109493535 0.0160688832 0.0144971719 0.1089750000 0.0071020000 0.0445210000 0.0000260000 0.0003000000 0.0433410000 8773312 96830484 1410027520 3.9649591446 4.0083513260 3.9787030220 259 10.3200000000 0.0120424973 0.0109535742 0.0160688832 0.0144883812 0.1485180000 0.0070090000 0.0764210000 0.0003010000 0.0002740000 0.0502800000 8774986 96830484 1410789376 3.9630780220 4.0071287155 3.9777896404 260 10.3600000000 0.0120164035 0.0109576620 0.0160688832 0.0144772636 0.1302660000 0.0072550000 0.0671320000 0.0000290000 0.0003110000 0.0455440000 8776660 96830484 1411440640 3.9611401558 4.0053029060 3.9770221710 261 10.4000000000 0.0120113632 0.0109616991 0.0160688832 0.0144590568 0.1245510000 0.0072000000 0.0430940000 0.0003020000 0.0002770000 0.0706590000 8778334 96830484 1412042752 3.9593026638 4.0040354729 3.9760303497 262 10.4400000000 0.0120041566 0.0109656780 0.0160688832 0.0144412847 0.1121790000 0.0072690000 0.0517740000 0.0000990000 0.0003050000 0.0412150000 8780008 96830484 1412710400 3.9570851326 4.0022792816 3.9750564098 263 10.4800000000 0.0120560015 0.0109698237 0.0160688832 0.0144237745 0.1235540000 0.0078040000 0.0526180000 0.0003790000 0.0002820000 0.0473660000 8781682 96830484 1413345280 3.9549744129 4.0011572838 3.9739358425 264 10.5200000000 0.0120278634 0.0109738314 0.0160688832 0.0144075775 0.1107420000 0.0076140000 0.0535500000 0.0000260000 0.0002920000 0.0412460000 8783356 96830484 1413980160 3.9533212185 3.9998416901 3.9734790325 265 10.5600000000 0.0120290685 0.0109778134 0.0160688832 0.0143928967 0.1474460000 0.0078220000 0.0517400000 0.0003620000 0.0002840000 0.0729470000 8785030 96830484 1414594560 3.9502966404 3.9978003502 3.9711661339 266 10.6000000000 0.0120834084 0.0109819698 0.0160688832 0.0143841031 0.0921280000 0.0073750000 0.0430560000 0.0000250000 0.0002940000 0.0383930000 8786704 96830484 1415376896 3.9474804401 3.9957497120 3.9695227146 267 10.6400000000 0.0119267600 0.0109855084 0.0160688832 0.0143861149 0.1071320000 0.0078740000 0.0442440000 0.0010510000 0.0002860000 0.0468610000 8788378 96830484 1415864320 3.9451510906 3.9948265553 3.9680545330 268 10.6800000000 0.0119194370 0.0109889932 0.0160688832 0.0143919726 0.1071330000 0.0077140000 0.0422540000 0.0000270000 0.0003050000 0.0432400000 8790052 96830484 1416646656 3.9425897598 3.9930429459 3.9663667679 269 10.7200000000 0.0119351018 0.0109925103 0.0160688832 0.0144031232 0.1688950000 0.0071200000 0.0711830000 0.0003080000 0.0002790000 0.0761610000 8791726 96830484 1417256960 3.9402735233 3.9911684990 3.9647533894 270 10.7600000000 0.0119677726 0.0109961224 0.0160688832 0.0144095322 0.0923190000 0.0075730000 0.0435790000 0.0000290000 0.0002970000 0.0376380000 8793400 96830484 1417924608 3.9375247955 3.9894022942 3.9622755051 271 10.8000000000 0.0120153902 0.0109998835 0.0160688832 0.0144144936 0.1060980000 0.0075780000 0.0424970000 0.0003650000 0.0002790000 0.0461210000 8795074 96830484 1418559488 3.9352231026 3.9876320362 3.9605166912 272 10.8400000000 0.0117344400 0.0110025841 0.0160688832 0.0144318768 0.1075180000 0.0081600000 0.0447710000 0.0000280000 0.0003090000 0.0402100000 8796748 96830484 1419194368 3.9327671528 3.9856245518 3.9584596157 273 10.8800000000 0.0117268525 0.0110052371 0.0160688832 0.0144477677 0.1259520000 0.0080040000 0.0452050000 0.0003130000 0.0002780000 0.0690520000 8798422 96830484 1419808768 3.9301693439 3.9837737083 3.9561846256 274 10.9200000000 0.0116446558 0.0110075707 0.0160688832 0.0144580884 0.0952110000 0.0073450000 0.0440380000 0.0000280000 0.0003020000 0.0404120000 8800096 96830484 1420464128 3.9282889366 3.9821758270 3.9547700882 275 10.9600000000 0.0116973799 0.0110100791 0.0160688832 0.0144668391 0.1074070000 0.0071830000 0.0415320000 0.0003700000 0.0002820000 0.0520550000 8801770 96830484 1421078528 3.9261541367 3.9801609516 3.9530732632 276 11.0000000000 0.0116366809 0.0110123494 0.0160688832 0.0144665273 0.1111100000 0.0071630000 0.0466450000 0.0000270000 0.0003660000 0.0536150000 8803444 96830484 1421860864 3.9242253304 3.9795732498 3.9512901306 277 11.0400000000 0.0117722601 0.0110150928 0.0160688832 0.0147823457 0.1415590000 0.0073020000 0.0506620000 0.0003060000 0.0002870000 0.0798700000 8805118 96830484 1422462976 3.9162678719 3.9722752571 3.9443612099 278 11.0800000000 0.0115850689 0.0110171431 0.0160688832 0.0147756730 0.1115330000 0.0071880000 0.0475060000 0.0000270000 0.0003510000 0.0417030000 8806792 96830484 1423130624 3.9143683910 3.9699678421 3.9426445961 279 11.1200000000 0.0115759857 0.0110191461 0.0160688832 0.0147625493 0.1507050000 0.0072200000 0.0800320000 0.0006190000 0.0005090000 0.0558670000 8808466 96830484 1423765504 3.9129443169 3.9675641060 3.9417958260 280 11.1600000000 0.0113194473 0.0110202186 0.0160688832 0.0147537291 0.1151860000 0.0073550000 0.0720250000 0.0000260000 0.0003200000 0.0321980000 8810140 96830484 1424621568 3.9118933678 3.9663672447 3.9412047863 281 11.2000000000 0.0112663954 0.0110210947 0.0160688832 0.0147523325 0.1310210000 0.0079510000 0.0522550000 0.0002980000 0.0003560000 0.0668270000 8811814 96830484 1425276928 3.9106392860 3.9640538692 3.9402267933 282 11.2400000000 0.0110991793 0.0110213716 0.0160688832 0.0147508859 0.1015980000 0.0072120000 0.0532000000 0.0000280000 0.0003830000 0.0374980000 8813488 96830484 1425895424 3.9093236923 3.9630544186 3.9388737679 283 11.2800000000 0.0108601814 0.0110208020 0.0160688832 0.0147426892 0.1081670000 0.0078160000 0.0501480000 0.0003870000 0.0002740000 0.0452220000 8815162 96830484 1426677760 3.9084010124 3.9605276585 3.9379985332 284 11.3200000000 0.0105249397 0.0110190560 0.0160688832 0.0147487948 0.1061480000 0.0080010000 0.0422730000 0.0000230000 0.0002950000 0.0387510000 8816836 96830484 1427288064 3.9071986675 3.9588212967 3.9368791580 285 11.3600000000 0.0104483115 0.0110170534 0.0160688832 0.0147455007 0.1244370000 0.0077320000 0.0458050000 0.0003210000 0.0002790000 0.0670470000 8818510 96830484 1427955712 3.9061255455 3.9568357468 3.9356656075 286 11.4000000000 0.0102035999 0.0110142091 0.0160688832 0.0147332964 0.1107420000 0.0077440000 0.0528000000 0.0000290000 0.0002980000 0.0386520000 8820184 96830484 1428455424 3.9053106308 3.9542319775 3.9347171783 287 11.4400000000 0.0101228124 0.0110111032 0.0160688832 0.0147172766 0.1088700000 0.0077570000 0.0426260000 0.0003770000 0.0002830000 0.0447530000 8821858 96830484 1429090304 3.9046244621 3.9526839256 3.9339852333 288 11.4800000000 0.0100090047 0.0110076237 0.0160688832 0.0146968300 0.1103170000 0.0077960000 0.0578530000 0.0000280000 0.0003100000 0.0374920000 8823532 96830484 1429725184 3.9035062790 3.9503023624 3.9326517582 289 11.5200000000 0.0097732656 0.0110033526 0.0160688832 0.0146815137 0.1594680000 0.0207090000 0.0688900000 0.0000620000 0.0000520000 0.0665370000 8825206 96830484 1646592000 3.9031875134 3.9477162361 3.9321153164 290 11.5600000000 0.0095609492 0.0109983788 0.0160688832 0.0146673172 0.0986920000 0.0074480000 0.0443470000 0.0000110000 0.0001100000 0.0395700000 8826880 96830484 1647214592 3.9025616646 3.9465410709 3.9315133095 291 11.6000000000 0.0096682236 0.0109938078 0.0160688832 0.0146453044 0.1293940000 0.0072710000 0.0634920000 0.0002940000 0.0054130000 0.0453750000 8828554 96830484 1647742976 3.9022524357 3.9449241161 3.9312186241 292 11.6400000000 0.0094526457 0.0109885298 0.0160688832 0.0146208762 0.0896650000 0.0074610000 0.0427190000 0.0000250000 0.0002910000 0.0359300000 8830228 96830484 1648226304 3.9014780521 3.9425356388 3.9298715591 293 11.6800000000 0.0092968615 0.0109827562 0.0160688832 0.0145958532 0.1619300000 0.0079370000 0.0858770000 0.0002870000 0.0003290000 0.0641590000 8831902 96830484 1649131520 3.9012429714 3.9405138493 3.9294910431 294 11.7200000000 0.0092301387 0.0109767949 0.0160688832 0.0145722416 0.1363500000 0.0078590000 0.0894790000 0.0000260000 0.0002830000 0.0354350000 8833576 96830484 1649537024 3.9010720253 3.9394512177 3.9287760258 295 11.7600000000 0.0087785637 0.0109693433 0.0160688832 0.0145545407 0.1080500000 0.0078780000 0.0508890000 0.0003770000 0.0002760000 0.0438160000 8835250 96830484 1650409472 3.9009706974 3.9340012074 3.9283301830 296 11.8000000000 0.0085733365 0.0109612487 0.0160688832 0.0145347504 0.1107980000 0.0080900000 0.0656430000 0.0000280000 0.0002790000 0.0333990000 8836924 96830484 1650917376 3.9009990692 3.9316582680 3.9281179905 297 11.8400000000 0.0083526038 0.0109524654 0.0160688832 0.0145215020 0.1261070000 0.0076290000 0.0500240000 0.0013190000 0.0002940000 0.0633330000 8838598 96830484 1651798016 3.9005892277 3.9304537773 3.9271943569 298 11.8800000000 0.0082100257 0.0109432626 0.0160688832 0.0145564076 0.1084250000 0.0072870000 0.0534310000 0.0000240000 0.0003060000 0.0372270000 8840272 96830484 1652051968 3.8993861675 3.9264724255 3.9250686169 299 11.9200000000 0.0081015443 0.0109337585 0.0160688832 0.0145595171 0.1087060000 0.0080840000 0.0448520000 0.0003890000 0.0002820000 0.0434020000 8841946 96830484 1652813824 3.8986682892 3.9247786999 3.9237346649 300 11.9600000000 0.0077579608 0.0109231725 0.0160688832 0.0145718184 0.1088110000 0.0082970000 0.0527730000 0.0000260000 0.0003520000 0.0362600000 8843620 96830484 1653440512 3.8983702660 3.9225399494 3.9230682850 301 12.0000000000 0.0076761255 0.0109123850 0.0160688832 0.0145784575 0.1268300000 0.0081030000 0.0524410000 0.0002830000 0.0002590000 0.0623760000 8845294 96830484 1654075392 3.8976256847 3.9205031395 3.9218518734 302 12.0400000000 0.0073514837 0.0109005939 0.0160688832 0.0146170015 0.0943480000 0.0071290000 0.0466470000 0.0000260000 0.0004870000 0.0366800000 8846968 96830484 1654710272 3.8954515457 3.9167993069 3.9182689190 303 12.0800000000 0.0073272106 0.0108888006 0.0160688832 0.0146022403 0.1457180000 0.0071820000 0.0817950000 0.0002910000 0.0005540000 0.0429900000 8848642 96830484 1655345152 3.8941357136 3.9151041508 3.9161937237 304 12.1200000000 0.0071587651 0.0108765307 0.0160688832 0.0145898779 0.0917980000 0.0075200000 0.0456290000 0.0000270000 0.0003190000 0.0348430000 8850316 96830484 1655980032 3.8926622868 3.9130573273 3.9136779308 305 12.1600000000 0.0071578561 0.0108643383 0.0160688832 0.0145832295 0.1180490000 0.0076100000 0.0442170000 0.0012530000 0.0002770000 0.0612740000 8851990 96830484 1656631296 3.8913781643 3.9119362831 3.9116961956 306 12.2000000000 0.0068354425 0.0108511720 0.0160688832 0.0145826784 0.0987130000 0.0072630000 0.0461730000 0.0000270000 0.0002920000 0.0378640000 8853664 96830484 1657249792 3.8906395435 3.9093365669 3.9099478722 307 12.2400000000 0.0068711718 0.0108382078 0.0160688832 0.0145967629 0.1190510000 0.0072890000 0.0724600000 0.0003200000 0.0003490000 0.0351450000 8855338 96830484 1657884672 3.8892190456 3.9076449871 3.9077801704 308 12.2800000000 0.0067665461 0.0108249881 0.0160688832 0.0146138058 0.1002020000 0.0075380000 0.0524960000 0.0000260000 0.0003100000 0.0352680000 8857012 96830484 1658519552 3.8875830173 3.9058303833 3.9050288200 309 12.3200000000 0.0067382017 0.0108117623 0.0160688832 0.0146126167 0.1175650000 0.0079290000 0.0447190000 0.0005360000 0.0002850000 0.0606050000 8858686 96830484 1659281408 3.8859119415 3.9040083885 3.9019465446 310 12.3600000000 0.0066795186 0.0107984325 0.0160688832 0.0146126367 0.1004810000 0.0076730000 0.0536110000 0.0000270000 0.0002870000 0.0348060000 8860360 96830484 1659916288 3.8842630386 3.9022331238 3.8986291885 311 12.4000000000 0.0066118939 0.0107849709 0.0160688832 0.0146122355 0.1080110000 0.0077680000 0.0503430000 0.0005090000 0.0005040000 0.0409050000 8862034 96830484 1660551168 3.8830120564 3.9010272026 3.8957970142 312 12.4400000000 0.0065269493 0.0107713234 0.0160688832 0.0146050980 0.0906750000 0.0078110000 0.0454720000 0.0000330000 0.0003750000 0.0334360000 8863708 96830484 1661186048 3.8817520142 3.8995940685 3.8927762508 313 12.4800000000 0.0065405937 0.0107578067 0.0160688832 0.0145970303 0.1164060000 0.0082350000 0.0457220000 0.0003880000 0.0002750000 0.0583510000 8865382 96830484 1661820928 3.8804783821 3.8982000351 3.8902058601 314 12.5200000000 0.0065433909 0.0107443850 0.0160688832 0.0145956148 0.0996700000 0.0074360000 0.0459770000 0.0000260000 0.0003610000 0.0349860000 8867056 96830484 1662455808 3.8794524670 3.8969039917 3.8880467415 315 12.5600000000 0.0066160443 0.0107312792 0.0160688832 0.0145984786 0.1135450000 0.0075530000 0.0584120000 0.0003840000 0.0002780000 0.0434740000 8868730 96830484 1663217664 3.8780863285 3.8959357738 3.8853025436 316 12.6000000000 0.0066019287 0.0107182116 0.0160688832 0.0145962087 0.1066820000 0.0072530000 0.0576050000 0.0000170000 0.0001960000 0.0365980000 8870404 96830484 1663852544 3.8768477440 3.8946576118 3.8826260567 317 12.6400000000 0.0066020149 0.0107052268 0.0160688832 0.0145859733 0.1399490000 0.0075150000 0.0611250000 0.0003050000 0.0003480000 0.0671680000 8872078 96830484 1664503808 3.8756103516 3.8938281536 3.8799362183 318 12.6800000000 0.0066174893 0.0106923722 0.0160688832 0.0145716799 0.1157140000 0.0073470000 0.0619850000 0.0000270000 0.0002910000 0.0337520000 8873752 96830484 1665122304 3.8743164539 3.8929295540 3.8772993088 319 12.7200000000 0.0068288539 0.0106802609 0.0160688832 0.0145888994 0.1120100000 0.0072710000 0.0635320000 0.0002940000 0.0002700000 0.0371310000 8875426 96830484 1665757184 3.8720400333 3.8914704323 3.8721125126 320 12.7600000000 0.0068960199 0.0106684351 0.0160688832 0.0145769633 0.1055650000 0.0077950000 0.0527030000 0.0000280000 0.0003110000 0.0317710000 8877100 96830484 1666392064 3.8711788654 3.8905804157 3.8698902130 321 12.8000000000 0.0070165135 0.0106570584 0.0160688832 0.0145654427 0.1264890000 0.0080410000 0.0593480000 0.0002890000 0.0005210000 0.0547170000 8878774 96830484 1667043328 3.8698887825 3.8904023170 3.8673191071 322 12.8400000000 0.0073310155 0.0106467291 0.0160688832 0.0145513205 0.1137520000 0.0079980000 0.0688220000 0.0000260000 0.0002920000 0.0309260000 8880448 96830484 1667788800 3.8685359955 3.8896040916 3.8645811081 323 12.8800000000 0.0072821449 0.0106363125 0.0160688832 0.0145377294 0.0898900000 0.0080530000 0.0373720000 0.0001980000 0.0001760000 0.0405560000 8882122 96830484 1668423680 3.8675150871 3.8892729282 3.8628313541 324 12.9200000000 0.0074460446 0.0106264659 0.0160688832 0.0145248743 0.1101120000 0.0075770000 0.0652030000 0.0000300000 0.0005370000 0.0332820000 8883796 96830484 1669058560 3.8661851883 3.8893220425 3.8603057861 325 12.9600000000 0.0074407714 0.0106166638 0.0160688832 0.0145054601 0.1685350000 0.0074670000 0.0926850000 0.0002850000 0.0002640000 0.0499110000 8885470 96830484 1669693440 3.8650126457 3.8896744251 3.8583498001 326 13.0000000000 0.0077046985 0.0106077314 0.0160688832 0.0144857079 0.1022450000 0.0080790000 0.0665870000 0.0000060000 0.0000600000 0.0238670000 8887144 96830484 1670328320 3.8635973930 3.8896851540 3.8557679653 327 13.0400000000 0.0082758479 0.0106006003 0.0160688832 0.0144656901 0.1234300000 0.0084910000 0.0756650000 0.0002880000 0.0003330000 0.0349610000 8888818 96830484 1670963200 3.8623576164 3.8906824589 3.8530199528 328 13.0800000000 0.0080104517 0.0105927035 0.0160688832 0.0144460604 0.1054780000 0.0079960000 0.0522500000 0.0000930000 0.0002840000 0.0300250000 8890492 96830484 1671614464 3.8609802723 3.8916945457 3.8511769772 329 13.1200000000 0.0081101423 0.0105851577 0.0160688832 0.0144284840 0.1482250000 0.0083500000 0.0870390000 0.0002890000 0.0003420000 0.0484530000 8892166 96830484 1672359936 3.8597917557 3.8930594921 3.8490686417 330 13.1600000000 0.0090658860 0.0105805538 0.0160688832 0.0144104102 0.1319000000 0.0074790000 0.0880610000 0.0000260000 0.0003590000 0.0293190000 8893840 96830484 1672994816 3.8585038185 3.8944439888 3.8461825848 331 13.2000000000 0.0086672725 0.0105747735 0.0160688832 0.0143957146 0.1097700000 0.0082970000 0.0591810000 0.0002940000 0.0003400000 0.0366140000 8895514 96830484 1673629696 3.8573746681 3.8961215019 3.8448672295 332 13.2400000000 0.0087494450 0.0105692755 0.0160688832 0.0143788388 0.1299280000 0.0082110000 0.0844200000 0.0000060000 0.0000580000 0.0336240000 8897188 96830484 1674264576 3.8561534882 3.8981883526 3.8435008526 333 13.2800000000 0.0081958454 0.0105621481 0.0160688832 0.0143674765 0.1159780000 0.0079760000 0.0520930000 0.0002900000 0.0003350000 0.0516530000 8898862 96830484 1674899456 3.8548581600 3.9004526138 3.8425958157 334 13.3200000000 0.0085671311 0.0105561750 0.0160688832 0.0143913255 0.1207290000 0.0075520000 0.0761050000 0.0000260000 0.0003540000 0.0291800000 8900536 96830484 1675534336 3.8526124954 3.9052004814 3.8398835659 335 13.3600000000 0.0080411006 0.0105486673 0.0160688832 0.0143805261 0.1099420000 0.0083010000 0.0591670000 0.0002960000 0.0002690000 0.0359560000 8902210 96830484 1676279808 3.8516962528 3.9076757431 3.8396639824 336 13.4000000000 0.0087783048 0.0105433984 0.0160688832 0.0143686634 0.1081430000 0.0083170000 0.0588320000 0.0000270000 0.0003100000 0.0284620000 8903884 96830484 1676931072 3.8507070541 3.9101014137 3.8382635117 337 13.4400000000 0.0087060742 0.0105379464 0.0160688832 0.0143586465 0.1227230000 0.0083900000 0.0593420000 0.0003810000 0.0002700000 0.0506060000 8905558 96830484 1677565952 3.8498070240 3.9123427868 3.8378949165 338 13.4800000000 0.0087249698 0.0105325826 0.0160688832 0.0143609472 0.0956830000 0.0076440000 0.0466200000 0.0000950000 0.0003120000 0.0299270000 8907232 96830484 1678200832 3.8489840031 3.9138476849 3.8375179768 339 13.5200000000 0.0088111274 0.0105275045 0.0160688832 0.0143724286 0.1068160000 0.0074310000 0.0625720000 0.0021990000 0.0003010000 0.0305780000 8908906 96830484 1678835712 3.8479323387 3.9164562225 3.8370041847 340 13.5600000000 0.0090671834 0.0105232095 0.0160688832 0.0143747367 0.1133450000 0.0084890000 0.0717400000 0.0000280000 0.0003890000 0.0279110000 8910580 96830484 1679470592 3.8471460342 3.9185321331 3.8368740082 341 13.6000000000 0.0090874191 0.0105189989 0.0160688832 0.0143711184 0.1220090000 0.0082860000 0.0596930000 0.0000610000 0.0000520000 0.0502710000 8912254 96830484 1680105472 3.8463134766 3.9211778641 3.8368570805 342 13.6400000000 0.0093692644 0.0105156371 0.0160688832 0.0143654422 0.1070420000 0.0075600000 0.0743390000 0.0000060000 0.0000580000 0.0213440000 8913928 96830484 1680756736 3.8450901508 3.9241080284 3.8360409737 343 13.6800000000 0.0094099427 0.0105124135 0.0160688832 0.0143745503 0.0974410000 0.0081990000 0.0474930000 0.0002940000 0.0003430000 0.0373030000 8915602 96830484 1681375232 3.8442211151 3.9265637398 3.8358623981 344 13.7200000000 0.0092782909 0.0105088260 0.0160688832 0.0143882416 0.1281140000 0.0076470000 0.0848230000 0.0000280000 0.0002850000 0.0282590000 8917276 96830484 1682137088 3.8434727192 3.9290034771 3.8359050751 345 13.7600000000 0.0094385603 0.0105057238 0.0160688832 0.0145382261 0.1145680000 0.0083500000 0.0520590000 0.0002920000 0.0002650000 0.0498050000 8918950 96830484 1682771968 3.8418703079 3.9344699383 3.8357424736 346 13.8000000000 0.0099564660 0.0105041363 0.0160688832 0.0145470141 0.1028170000 0.0081790000 0.0537020000 0.0001130000 0.0003040000 0.0279670000 8920624 96830484 1683406848 3.8412358761 3.9367160797 3.8351459503 347 13.8400000000 0.0101616466 0.0105031493 0.0160688832 0.0145457230 0.1146410000 0.0082990000 0.0734860000 0.0002900000 0.0003370000 0.0283240000 8922298 96830484 1684041728 3.8403403759 3.9393875599 3.8347826004 348 13.8800000000 0.0099132275 0.0105014541 0.0160688832 0.0145324404 0.1036680000 0.0079500000 0.0542310000 0.0000290000 0.0003120000 0.0282020000 8923972 96830484 1684660224 3.8395142555 3.9422910213 3.8349289894 349 13.9200000000 0.0094730752 0.0104985075 0.0160688832 0.0145128005 0.1468700000 0.0084710000 0.0879820000 0.0002890000 0.0004840000 0.0457050000 8925646 96830484 1685311488 3.8386769295 3.9460284710 3.8352439404 350 13.9600000000 0.0100380089 0.0104971918 0.0160688832 0.0144963751 0.1325630000 0.0075930000 0.0881630000 0.0000270000 0.0002840000 0.0287000000 8927320 96830484 1685946368 3.8379004002 3.9481329918 3.8346943855 351 14.0000000000 0.0100214910 0.0104958365 0.0160688832 0.0144941329 0.1283520000 0.0081690000 0.0862070000 0.0000610000 0.0000520000 0.0287800000 8928994 96830484 1686708224 3.8372004032 3.9515914917 3.8347690105 352 14.0400000000 0.0099562733 0.0104943036 0.0160688832 0.0144922607 0.1234930000 0.0094270000 0.0709800000 0.0000270000 0.0002850000 0.0291160000 8930668 96830484 1687597056 3.8364589214 3.9544219971 3.8350560665 353 14.0800000000 0.0098842774 0.0104925755 0.0160688832 0.0145020009 0.1235500000 0.0086540000 0.0672710000 0.0002930000 0.0003330000 0.0430860000 8932342 96830484 1688358912 3.8357977867 3.9581220150 3.8354258537 354 14.1200000000 0.0103576966 0.0104921945 0.0160688832 0.0145256870 0.1373510000 0.0091040000 0.0885820000 0.0000260000 0.0002880000 0.0354430000 8934016 96830484 1688993792 3.8353123665 3.9608719349 3.8354399204 355 14.1600000000 0.0101577397 0.0104912524 0.0160688832 0.0145486776 0.1042310000 0.0077790000 0.0530200000 0.0007390000 0.0002870000 0.0350310000 8935690 96830484 1689755648 3.8347859383 3.9638409615 3.8360738754 356 14.2000000000 0.0098947808 0.0104895769 0.0160688832 0.0145585011 0.1299780000 0.0081220000 0.0888700000 0.0000270000 0.0002840000 0.0286900000 8937364 96830484 1690390528 3.8342363834 3.9673194885 3.8365356922 357 14.2400000000 0.0099514807 0.0104880696 0.0160688832 0.0145606826 0.1661890000 0.0080870000 0.0871850000 0.0003120000 0.0006940000 0.0533440000 8939038 96830484 1691041792 3.8337774277 3.9700772762 3.8371484280 358 14.2800000000 0.0100140804 0.0104867456 0.0160688832 0.0145651823 0.1102950000 0.0081310000 0.0626970000 0.0000310000 0.0003000000 0.0291070000 8940712 96830484 1691660288 3.8333756924 3.9724249840 3.8378679752 359 14.3200000000 0.0094743129 0.0104839255 0.0160688832 0.0145709077 0.1103740000 0.0082650000 0.0591870000 0.0003600000 0.0002810000 0.0354470000 8942386 96830484 1692311552 3.8330492973 3.9757022858 3.8390679359 360 14.3600000000 0.0100397980 0.0104826918 0.0160688832 0.0145688001 0.0892120000 0.0085750000 0.0455100000 0.0000300000 0.0003800000 0.0289790000 8944060 96830484 1693057024 3.8328754902 3.9780781269 3.8392143250 361 14.4000000000 0.0100623425 0.0104815274 0.0160688832 0.0145647421 0.1267590000 0.0080840000 0.0476700000 0.0002970000 0.0002710000 0.0545780000 8945734 96830484 1693691904 3.8327305317 3.9811513424 3.8400857449 362 14.4400000000 0.0096340999 0.0104791864 0.0160688832 0.0145693903 0.1312900000 0.0081310000 0.0871690000 0.0000070000 0.0000580000 0.0296380000 8947408 96830484 1694326784 3.8326828480 3.9838011265 3.8413665295 363 14.4800000000 0.0097017642 0.0104770448 0.0160688832 0.0145710533 0.0957060000 0.0080250000 0.0531680000 0.0003630000 0.0002760000 0.0297880000 8949082 96830484 1694961664 3.8327174187 3.9856483936 3.8421907425 364 14.5200000000 0.0100787915 0.0104759507 0.0160688832 0.0145727320 0.1014380000 0.0078180000 0.0541310000 0.0000280000 0.0003120000 0.0298970000 8950756 96830484 1695596544 3.8326404095 3.9879393578 3.8426327705 365 14.5600000000 0.0098237023 0.0104741637 0.0160688832 0.0145783236 0.1310030000 0.0078360000 0.0663450000 0.0002850000 0.0003340000 0.0521010000 8952430 96830484 1696231424 3.8327162266 3.9896709919 3.8438422680 366 14.6000000000 0.0093345838 0.0104710501 0.0160688832 0.0146702712 0.1040040000 0.0077260000 0.0674980000 0.0000270000 0.0002840000 0.0241870000 8954104 96830484 1696866304 3.8334357738 3.9960281849 3.8463513851 367 14.6400000000 0.0088227270 0.0104665588 0.0160688832 0.0146855814 0.0963420000 0.0079580000 0.0530360000 0.0002850000 0.0002640000 0.0307640000 8955778 96830484 1697517568 3.8338699341 3.9991021156 3.8477978706 368 14.6800000000 0.0084806820 0.0104611623 0.0160688832 0.0146967593 0.1029030000 0.0077110000 0.0611990000 0.0000280000 0.0002810000 0.0296700000 8957452 96830484 1698263040 3.8347175121 4.0024986267 3.8497834206 369 14.7200000000 0.0080268020 0.0104545652 0.0160688832 0.0147184866 0.1192000000 0.0080100000 0.0514780000 0.0003590000 0.0002740000 0.0550030000 8959126 96830484 1698787328 3.8362877369 4.0099468231 3.8531732559 370 14.7600000000 0.0073392140 0.0104461453 0.0160688832 0.0147254226 0.1172200000 0.0081580000 0.0669680000 0.0000280000 0.0003060000 0.0313330000 8960800 96830484 1699532800 3.8377187252 4.0134749413 3.8562715054 371 14.8000000000 0.0061512720 0.0104345688 0.0160688832 0.0147292843 0.1294170000 0.0079890000 0.0723760000 0.0003550000 0.0002680000 0.0384350000 8962474 96830484 1700167680 3.8389229774 4.0172219276 3.8596930504 372 14.8400000000 0.0054237400 0.0104210988 0.0160688832 0.0147297169 0.0903390000 0.0080790000 0.0438320000 0.0000270000 0.0012260000 0.0316600000 8964148 96830484 1700802560 3.8399794102 4.0207080841 3.8631525040 373 14.8800000000 0.0052522644 0.0104072414 0.0160688832 0.0147267964 0.1271320000 0.0078900000 0.0592810000 0.0002900000 0.0002600000 0.0551680000 8965822 96830484 1701437440 3.8414478302 4.0250773430 3.8667268753 374 14.9200000000 0.0054771490 0.0103940593 0.0160688832 0.0147194394 0.0913080000 0.0075370000 0.0456810000 0.0000270000 0.0002980000 0.0336750000 8967496 96830484 1702072320 3.8428993225 4.0294289589 3.8698046207 375 14.9600000000 0.0062323730 0.0103829615 0.0160688832 0.0147145879 0.1078410000 0.0074140000 0.0459850000 0.0003530000 0.0002680000 0.0453930000 8969170 96830484 1702707200 3.8444526196 4.0337567329 3.8733763695 376 15.0000000000 0.0067905919 0.0103734073 0.0160688832 0.0147238981 0.1112160000 0.0073700000 0.0658450000 0.0000290000 0.0003140000 0.0333490000 8970844 96830484 1703342080 3.8460502625 4.0369124413 3.8764569759 377 15.0400000000 0.0072415955 0.0103651001 0.0160688832 0.0147450193 0.1451320000 0.0081160000 0.0570730000 0.0002900000 0.0003500000 0.0628720000 8972518 96830484 1703993344 3.8479766846 4.0398349762 3.8795151711 378 15.0800000000 0.0078635858 0.0103584824 0.0160688832 0.0147566857 0.0919630000 0.0076160000 0.0452170000 0.0000280000 0.0003000000 0.0336340000 8974192 96830484 1704738816 3.8498733044 4.0434532166 3.8820526600 379 15.1200000000 0.0082301358 0.0103528667 0.0160688832 0.0147534055 0.1103180000 0.0079460000 0.0588420000 0.0003800000 0.0002760000 0.0386980000 8975866 96830484 1705263104 3.8520822525 4.0463752747 3.8847029209 380 15.1600000000 0.0087194610 0.0103485682 0.0160688832 0.0147586144 0.0894070000 0.0077090000 0.0458550000 0.0000250000 0.0003920000 0.0311950000 8977540 96830484 1706008576 3.8542547226 4.0488657951 3.8872783184 381 15.2000000000 0.0091242502 0.0103453548 0.0160688832 0.0147638180 0.1263250000 0.0079390000 0.0522750000 0.0003900000 0.0002670000 0.0611280000 8979214 96830484 1706643456 3.8563146591 4.0509843826 3.8893675804 382 15.2400000000 0.0091845216 0.0103423160 0.0160688832 0.0147601695 0.1085280000 0.0076240000 0.0525000000 0.0000280000 0.0003680000 0.0351930000 8980888 96830484 1707278336 3.8585894108 4.0526680946 3.8913755417 383 15.2800000000 0.0092850849 0.0103395556 0.0160688832 0.0147566688 0.1085450000 0.0080750000 0.0424180000 0.0002980000 0.0010700000 0.0416620000 8982562 96830484 1707913216 3.8606505394 4.0543909073 3.8933684826 384 15.3200000000 0.0092750462 0.0103367834 0.0160688832 0.0147749083 0.1094540000 0.0077290000 0.0522000000 0.0000280000 0.0002830000 0.0355790000 8984236 96830484 1708548096 3.8627958298 4.0556445122 3.8953206539 385 15.3600000000 0.0093237692 0.0103341522 0.0160688832 0.0147786777 0.1219990000 0.0080760000 0.0462000000 0.0003100000 0.0002680000 0.0629300000 8985910 96830484 1709182976 3.8653204441 4.0562510490 3.8974604607 386 15.4000000000 0.0094315512 0.0103318139 0.0160688832 0.0147785762 0.0988200000 0.0071640000 0.0512020000 0.0000290000 0.0003110000 0.0357330000 8987584 96830484 1709817856 3.8675830364 4.0584754944 3.8993401527 387 15.4400000000 0.0096575879 0.0103300717 0.0160688832 0.0147793700 0.0942940000 0.0079070000 0.0450440000 0.0003190000 0.0003350000 0.0363860000 8989258 96830484 1710469120 3.8703324795 4.0595111847 3.9019896984 388 15.4800000000 0.0095770517 0.0103281309 0.0160688832 0.0147888259 0.1018800000 0.0073510000 0.0440070000 0.0000250000 0.0002760000 0.0374180000 8990932 96830484 1711214592 3.8732700348 4.0601444244 3.9044024944 389 15.5200000000 0.0095459428 0.0103261201 0.0160688832 0.0147933279 0.1411770000 0.0071200000 0.0534630000 0.0002880000 0.0002630000 0.0757070000 8992606 96830484 1711738880 3.8754806519 4.0617108345 3.9061436653 390 15.5600000000 0.0097958725 0.0103247605 0.0160688832 0.0147862837 0.0978290000 0.0073820000 0.0440700000 0.0000290000 0.0002820000 0.0373690000 8994280 96830484 1712484352 3.8786118031 4.0622391701 3.9092888832 391 15.6000000000 0.0098330835 0.0103235030 0.0160688832 0.0147847313 0.1107320000 0.0072800000 0.0487730000 0.0002770000 0.0007600000 0.0493350000 8995954 96830484 1713119232 3.8809719086 4.0629768372 3.9114632607 392 15.6400000000 0.0098617924 0.0103223252 0.0160688832 0.0147849808 0.1063830000 0.0073050000 0.0460990000 0.0000280000 0.0002910000 0.0402490000 8997628 96830484 1713754112 3.8841147423 4.0627689362 3.9141769409 393 15.6800000000 0.0098721413 0.0103211797 0.0160688832 0.0147842940 0.1415110000 0.0070660000 0.0533150000 0.0003590000 0.0002750000 0.0762160000 8999302 96830484 1714388992 3.8866322041 4.0632090569 3.9161999226 394 15.7200000000 0.0099386992 0.0103202089 0.0160688832 0.0147884115 0.0960350000 0.0074660000 0.0363830000 0.0000290000 0.0002860000 0.0379420000 9000976 96830484 1715023872 3.8894832134 4.0646944046 3.9180629253 395 15.7600000000 0.0101183327 0.0103196979 0.0160688832 0.0147934490 0.1497240000 0.0072530000 0.0774330000 0.0003640000 0.0002730000 0.0532160000 9002650 96830484 1715658752 3.8922505379 4.0648736954 3.9199862480 396 15.8000000000 0.0101206144 0.0103191951 0.0160688832 0.0147878107 0.1134640000 0.0073350000 0.0572700000 0.0000260000 0.0003040000 0.0440210000 9004324 96830484 1716293632 3.8953008652 4.0656924248 3.9217350483 397 15.8400000000 0.0101552736 0.0103187822 0.0160688832 0.0147788944 0.1435610000 0.0070560000 0.0467020000 0.0003770000 0.0002720000 0.0729140000 9005998 96830484 1716944896 3.8986914158 4.0672197342 3.9240405560 398 15.8800000000 0.0102238227 0.0103185436 0.0160688832 0.0147733945 0.0925540000 0.0077420000 0.0453960000 0.0000280000 0.0003810000 0.0346770000 9007672 96830484 1717690368 3.9000027180 4.0679736137 3.9238965511 399 15.9200000000 0.0101870717 0.0103182141 0.0160688832 0.0147689891 0.1085300000 0.0075400000 0.0511360000 0.0003850000 0.0002840000 0.0442310000 9009346 96830484 1718214656 3.9035246372 4.0688543320 3.9259681702 400 15.9600000000 0.0102424463 0.0103180247 0.0160688832 0.0147644808 0.0904940000 0.0077780000 0.0431900000 0.0000270000 0.0010760000 0.0340710000 9011020 96830484 1718960128 3.9051790237 4.0681309700 3.9266710281 401 16.0000000000 0.0102701439 0.0103179053 0.0160688832 0.0147529043 0.1276340000 0.0075760000 0.0461500000 0.0002890000 0.0003490000 0.0688190000 9012694 96830484 1719595008 3.9071421623 4.0675106049 3.9280085564 402 16.0400000000 0.0103328619 0.0103179425 0.0160688832 0.0147447695 0.1071640000 0.0076680000 0.0489580000 0.0000250000 0.0019210000 0.0371530000 9014368 96830484 1720229888 3.9092545509 4.0678057671 3.9291486740 403 16.0800000000 0.0104188276 0.0103181928 0.0160688832 0.0147447198 0.1089960000 0.0080400000 0.0446160000 0.0003160000 0.0003560000 0.0444770000 9016042 96830484 1720864768 3.9108099937 4.0661554337 3.9299068451 404 16.1200000000 0.0104652978 0.0103185570 0.0160688832 0.0147515903 0.1088300000 0.0077640000 0.0522430000 0.0000280000 0.0002920000 0.0370380000 9017716 96830484 1721499648 3.9126708508 4.0662474632 3.9305469990 405 16.1600000000 0.0105490834 0.0103191262 0.0160688832 0.0147536960 0.1221700000 0.0077400000 0.0429300000 0.0002890000 0.0009310000 0.0658730000 9019390 96830484 1722134528 3.9151687622 4.0677318573 3.9314334393 406 16.2000000000 0.0107014980 0.0103200680 0.0160688832 0.0147505861 0.0948460000 0.0074840000 0.0442590000 0.0000300000 0.0003800000 0.0381790000 9021064 96830484 1722769408 3.9175353050 4.0681295395 3.9327940941 407 16.2400000000 0.0107800048 0.0103211980 0.0160688832 0.0147571393 0.1096900000 0.0071980000 0.0461540000 0.0006670000 0.0003010000 0.0507910000 9022738 96830484 1723420672 3.9205269814 4.0682806969 3.9341421127 408 16.2800000000 0.0109064830 0.0103226326 0.0160688832 0.0147615753 0.0892540000 0.0073010000 0.0427410000 0.0000280000 0.0002920000 0.0344790000 9024412 96830484 1724166144 3.9232325554 4.0687789917 3.9351296425 409 16.3200000000 0.0108749513 0.0103239830 0.0160688832 0.0147535921 0.1261300000 0.0076460000 0.0462230000 0.0003090000 0.0003520000 0.0670080000 9026086 96830484 1724690432 3.9264600277 4.0689349174 3.9368755817 410 16.3600000000 0.0109036705 0.0103253968 0.0160688832 0.0147562030 0.0932590000 0.0073060000 0.0448590000 0.0000270000 0.0004550000 0.0360700000 9027760 96830484 1725435904 3.9295997620 4.0683608055 3.9386637211 411 16.3999999990 0.0109612411 0.0103269439 0.0160688832 0.0147663398 0.1248010000 0.0070580000 0.0496100000 0.0003540000 0.0002700000 0.0565210000 9029434 96830484 1726070784 3.9327666759 4.0667800903 3.9404459000 412 16.4400000000 0.0109358123 0.0103284217 0.0160688832 0.0147699458 0.1255370000 0.0072600000 0.0761850000 0.0000240000 0.0002830000 0.0371350000 9031108 96830484 1726705664 3.9346430302 4.0666460991 3.9415132999 413 16.4800000000 0.0110280095 0.0103301157 0.0160688832 0.0147753047 0.1317900000 0.0082760000 0.0464270000 0.0002840000 0.0003840000 0.0718730000 9032782 96830484 1727356928 3.9376289845 4.0651845932 3.9435129166 414 16.5200000000 0.0110557023 0.0103318683 0.0160688832 0.0147691087 0.1050600000 0.0073680000 0.0458240000 0.0000270000 0.0003500000 0.0388110000 9034456 96830484 1727975424 3.9396579266 4.0653400421 3.9444210529 415 16.5599999990 0.0111185191 0.0103337638 0.0160688832 0.0147597070 0.1469650000 0.0073330000 0.0716580000 0.0002990000 0.0003500000 0.0463150000 9036130 96830484 1728626688 3.9417967796 4.0659794807 3.9452712536 416 16.6000000000 0.0110944342 0.0103355924 0.0160688832 0.0147475425 0.1133530000 0.0071380000 0.0645140000 0.0000300000 0.0003120000 0.0367280000 9037804 96830484 1729245184 3.9431273937 4.0661582947 3.9458494186 417 16.6400000000 0.0111224260 0.0103374793 0.0160688832 0.0147391313 0.1461070000 0.0080320000 0.0534070000 0.0002910000 0.0003340000 0.0684270000 9039478 96830484 1730007040 3.9455468655 4.0667572021 3.9469015598 418 16.6800000000 0.0111390920 0.0103393970 0.0160688832 0.0147298720 0.0926140000 0.0086930000 0.0456470000 0.0000250000 0.0003170000 0.0334140000 9041152 96830484 1730641920 3.9461157322 4.0656847954 3.9471132755 419 16.7199999990 0.0111937914 0.0103414361 0.0160688832 0.0147236920 0.1078470000 0.0076990000 0.0506110000 0.0002950000 0.0002690000 0.0433400000 9042826 96830484 1731276800 3.9487164021 4.0650701523 3.9481923580 420 16.7600000000 0.0112506626 0.0103436009 0.0160688832 0.0147215840 0.1074680000 0.0075810000 0.0511080000 0.0000260000 0.0003100000 0.0361690000 9044500 96830484 1731911680 3.9504294395 4.0635581017 3.9496772289 421 16.8000000000 0.0112484833 0.0103457503 0.0160688832 0.0147214256 0.1248200000 0.0077580000 0.0454920000 0.0003160000 0.0002750000 0.0663840000 9046174 96830484 1732657152 3.9526357651 4.0618572235 3.9513218403 422 16.8400000000 0.0112969736 0.0103480044 0.0160688832 0.0147160030 0.0950590000 0.0072740000 0.0444080000 0.0000260000 0.0003020000 0.0383310000 9047848 96830484 1733308416 3.9542210102 4.0625076294 3.9520432949 423 16.8799999990 0.0114101004 0.0103505153 0.0160688832 0.0147121075 0.1111980000 0.0073930000 0.0527430000 0.0002910000 0.0002670000 0.0459250000 9049522 96830484 1733943296 3.9563627243 4.0616044998 3.9531331062 424 16.9200000000 0.0114244353 0.0103530481 0.0160688832 0.0147031496 0.1091820000 0.0071120000 0.0564230000 0.0000250000 0.0003600000 0.0405380000 9051196 96830484 1734594560 3.9591257572 4.0604062080 3.9543266296 425 16.9600000000 0.0114951376 0.0103557354 0.0160688832 0.0147092441 0.1444670000 0.0071140000 0.0507810000 0.0004970000 0.0003590000 0.0810400000 9052870 96830484 1735213056 3.9615690708 4.0603728294 3.9564833641 426 17.0000000000 0.0115245897 0.0103584791 0.0160688832 0.0147045551 0.0919750000 0.0079640000 0.0454580000 0.0000290000 0.0003150000 0.0334640000 9054544 96830484 1735974912 3.9639654160 4.0564527512 3.9580566883 427 17.0400000000 0.0114792073 0.0103611038 0.0160688832 0.0147000819 0.1138040000 0.0078670000 0.0465710000 0.0003200000 0.0002640000 0.0486600000 9056218 96830484 1736499200 3.9670269489 4.0554242134 3.9589467049 428 17.0800000000 0.0115653351 0.0103639174 0.0160688832 0.0146945715 0.1073560000 0.0082020000 0.0456380000 0.0000290000 0.0003100000 0.0357880000 9057892 96830484 1737244672 3.9698822498 4.0553436279 3.9603011608 429 17.1200000000 0.0115458732 0.0103666726 0.0160688832 0.0146885584 0.1406860000 0.0082140000 0.0459180000 0.0003160000 0.0002770000 0.0621950000 9059566 96830484 1737879552 3.9722917080 4.0547237396 3.9614245892 430 17.1600000000 0.0116541917 0.0103696668 0.0160688832 0.0146801186 0.0946990000 0.0079230000 0.0469880000 0.0000280000 0.0003070000 0.0347920000 9061240 96830484 1738514432 3.9747481346 4.0572600365 3.9619715214 431 17.2000000000 0.0116198994 0.0103725676 0.0160688832 0.0146740548 0.1091880000 0.0078400000 0.0541270000 0.0002910000 0.0002700000 0.0418960000 9062914 96830484 1739149312 3.9772443771 4.0570273399 3.9623460770 432 17.2400000000 0.0115832826 0.0103753702 0.0160688832 0.0146748678 0.0909600000 0.0076790000 0.0436410000 0.0000280000 0.0003610000 0.0344820000 9064588 96830484 1739784192 3.9798200130 4.0522122383 3.9636905193 433 17.2800000000 0.0116265304 0.0103782597 0.0160688832 0.0146871193 0.1267460000 0.0073470000 0.0455300000 0.0002890000 0.0003440000 0.0683750000 9066262 96830484 1740419072 3.9810459614 4.0481858253 3.9655182362 434 17.3200000000 0.0116422251 0.0103811720 0.0160688832 0.0146913474 0.1075080000 0.0079260000 0.0542110000 0.0000270000 0.0002920000 0.0354550000 9067936 96830484 1741070336 3.9837281704 4.0460038185 3.9671282768 435 17.3600000000 0.0117083574 0.0103842230 0.0160688832 0.0146958957 0.1082560000 0.0082960000 0.0437990000 0.0005640000 0.0002740000 0.0423640000 9069610 96830484 1741688832 3.9860298634 4.0426440239 3.9681458473 436 17.4000000000 0.0117071345 0.0103872572 0.0160688832 0.0146946802 0.0908800000 0.0081230000 0.0427280000 0.0000290000 0.0002980000 0.0349750000 9071284 96830484 1742450688 3.9872519970 4.0409140587 3.9692878723 437 17.4400000000 0.0117021361 0.0103902661 0.0160688832 0.0146902607 0.1447920000 0.0080300000 0.0517610000 0.0003040000 0.0002770000 0.0625470000 9072958 96830484 1742974976 3.9878215790 4.0401859283 3.9696693420 438 17.4800000000 0.0117608886 0.0103933954 0.0160688832 0.0147053016 0.0933110000 0.0081750000 0.0458930000 0.0000300000 0.0003120000 0.0341160000 9074632 96830484 1743720448 3.9879705906 4.0398683548 3.9709267616 439 17.5200000000 0.0117793567 0.0103965525 0.0160688832 0.0147142508 0.0936230000 0.0081350000 0.0436840000 0.0010400000 0.0002820000 0.0356320000 9076306 96830484 1744355328 3.9875965118 4.0388288498 3.9716782570 440 17.5600000000 0.0118173445 0.0103997815 0.0160688832 0.0147178572 0.1022120000 0.0079700000 0.0466510000 0.0000280000 0.0002970000 0.0372240000 9077980 96830484 1745006592 3.9860210419 4.0383787155 3.9720492363 441 17.6000000000 0.0118371388 0.0104030409 0.0160688832 0.0147302010 0.1476380000 0.0078740000 0.0468830000 0.0003010000 0.0003470000 0.0770370000 9079654 96830484 1745625088 3.9846651554 4.0377311707 3.9731616974 442 17.6400000000 0.0118477503 0.0104063094 0.0160688832 0.0148208221 0.0918350000 0.0085680000 0.0433180000 0.0000270000 0.0003120000 0.0347740000 9081328 96830484 1746276352 3.9752962589 4.0345010757 3.9733433723 443 17.6800000000 0.0118095810 0.0104094771 0.0160688832 0.0148297663 0.1069100000 0.0081810000 0.0445540000 0.0002020000 0.0001830000 0.0420560000 9083002 96830484 1747021824 3.9712588787 4.0349521637 3.9731667042 444 17.7200000000 0.0118313599 0.0104126795 0.0160688832 0.0148351149 0.0922970000 0.0087820000 0.0461800000 0.0000260000 0.0005960000 0.0316570000 9084676 96830484 1747656704 3.9688379765 4.0348181725 3.9738614559 445 17.7600000000 0.0118555315 0.0104159219 0.0160688832 0.0148412933 0.1259580000 0.0085160000 0.0465450000 0.0003870000 0.0002760000 0.0653430000 9086350 96830484 1748291584 3.9670934677 4.0306935310 3.9746332169 446 17.8000000000 0.0116844326 0.0104187661 0.0160688832 0.0148499882 0.0928090000 0.0084440000 0.0456620000 0.0000270000 0.0003520000 0.0334870000 9088024 96830484 1748926464 3.9653995037 4.0284957886 3.9754698277 447 17.8400000000 0.0118187116 0.0104218980 0.0160688832 0.0148492362 0.1034080000 0.0080090000 0.0443320000 0.0002920000 0.0003400000 0.0454400000 9089698 96830484 1749561344 3.9664735794 4.0242366791 3.9771351814 448 17.8800000000 0.0117285103 0.0104248145 0.0160688832 0.0148408592 0.1072260000 0.0080760000 0.0471280000 0.0000270000 0.0003590000 0.0417720000 9091372 96830484 1750212608 3.9673504829 4.0213274956 3.9783234596 449 17.9200000000 0.0117548723 0.0104277768 0.0160688832 0.0148317448 0.1677570000 0.0084280000 0.0681040000 0.0003180000 0.0003470000 0.0763210000 9093046 96830484 1750831104 3.9654583931 4.0184745789 3.9805090427 450 17.9600000000 0.0117205661 0.0104306496 0.0160688832 0.0148193290 0.1131560000 0.0084500000 0.0563810000 0.0000300000 0.0002910000 0.0429920000 9094720 96830484 1751482368 3.9663131237 4.0151729584 3.9821188450 451 18.0000000000 0.0117825009 0.0104336471 0.0160688832 0.0148117691 0.1070730000 0.0083350000 0.0453780000 0.0002950000 0.0003420000 0.0465220000 9096394 96830484 1752100864 3.9665637016 4.0145130157 3.9851551056 452 18.0400000000 0.0116010811 0.0104362299 0.0160688832 0.0148063945 0.1077940000 0.0082240000 0.0458350000 0.0000270000 0.0003540000 0.0421420000 9098068 96830484 1752862720 3.9669182301 4.0120358467 3.9882185459 453 18.0800000000 0.0115839001 0.0104387634 0.0160688832 0.0147963058 0.1530930000 0.0084600000 0.0660120000 0.0003230000 0.0002760000 0.0730650000 9099742 96830484 1753497600 3.9679000378 4.0105390549 3.9914410114 454 18.1200000000 0.0115854274 0.0104412891 0.0160688832 0.0147843104 0.1079610000 0.0083710000 0.0625680000 0.0000270000 0.0003670000 0.0314810000 9101416 96830484 1754132480 3.9683570862 4.0099596977 3.9954257011 455 18.1600000000 0.0116358167 0.0104439144 0.0160688832 0.0147695168 0.1059100000 0.0090350000 0.0440810000 0.0003230000 0.0002770000 0.0415070000 9103090 96830484 1754767360 3.9699370861 4.0083937645 3.9993236065 456 18.2000000000 0.0115477834 0.0104463352 0.0160688832 0.0147607013 0.0911450000 0.0090240000 0.0435160000 0.0000290000 0.0003200000 0.0333060000 9104764 96830484 1755402240 3.9710679054 4.0071816444 4.0043058395 457 18.2400000000 0.0115130395 0.0104486693 0.0160688832 0.0147536849 0.1271150000 0.0088720000 0.0471160000 0.0003930000 0.0002650000 0.0653980000 9106438 96830484 1756037120 3.9711554050 4.0101299286 4.0089998245 458 18.2800000000 0.0114541762 0.0104508648 0.0160688832 0.0147427932 0.0911330000 0.0088370000 0.0426010000 0.0000250000 0.0002890000 0.0343040000 9108112 96830484 1756688384 3.9722733498 4.0108098984 4.0152225494 459 18.3200000000 0.0114571750 0.0104530572 0.0160688832 0.0147280760 0.1249780000 0.0083890000 0.0477880000 0.0003030000 0.0003530000 0.0499680000 9109786 96830484 1757306880 3.9746315479 4.0109758377 4.0213170052 460 18.3600000000 0.0113417786 0.0104549892 0.0160688832 0.0147138220 0.1122560000 0.0084290000 0.0647660000 0.0000290000 0.0003830000 0.0336360000 9111460 96830484 1757958144 3.9760701656 4.0145502090 4.0278286934 461 18.4000000000 0.0114449961 0.0104571367 0.0160688832 0.0146991109 0.1250610000 0.0089030000 0.0449950000 0.0003810000 0.0002760000 0.0654700000 9113134 96830484 1758576640 3.9768538475 4.0144443512 4.0350728035 462 18.4400000000 0.0113357576 0.0104590385 0.0160688832 0.0146837588 0.0913810000 0.0090210000 0.0367510000 0.0000190000 0.0002310000 0.0366130000 9114808 96830484 1759338496 3.9802114964 4.0148992538 4.0427751541 463 18.4800000000 0.0113522848 0.0104609677 0.0160688832 0.0146710707 0.1272660000 0.0083450000 0.0513700000 0.0002880000 0.0002690000 0.0519970000 9116482 96830484 1759973376 3.9808101654 4.0171952248 4.0508389473 464 18.5200000000 0.0113464138 0.0104628760 0.0160688832 0.0146581068 0.1154270000 0.0083190000 0.0700370000 0.0000270000 0.0002920000 0.0312920000 9118156 96830484 1760608256 3.9814918041 4.0192279816 4.0599565506 465 18.5600000000 0.0112679154 0.0104646073 0.0160688832 0.0146467172 0.1233860000 0.0093340000 0.0424130000 0.0002840000 0.0017140000 0.0644150000 9119830 96830484 1761243136 3.9854903221 4.0256843567 4.0794916153 466 18.6000000000 0.0112435287 0.0104662788 0.0160688832 0.0146320992 0.1074080000 0.0091010000 0.0454740000 0.0000260000 0.0003470000 0.0364740000 9121504 96830484 1761988608 3.9882032871 4.0295815468 4.0898642540 467 18.6400000000 0.0113525400 0.0104681766 0.0160688832 0.0146172435 0.1120650000 0.0083610000 0.0583010000 0.0003070000 0.0008280000 0.0391820000 9123178 96830484 1762639872 3.9909522533 4.0306673050 4.1008563042 468 18.6800000000 0.0113220885 0.0104700011 0.0160688832 0.0146040949 0.0897670000 0.0088500000 0.0445740000 0.0000250000 0.0003140000 0.0309300000 9124852 96830484 1763274752 3.9929640293 4.0354452133 4.1119513512 469 18.7200000000 0.0112892529 0.0104717480 0.0160688832 0.0145931930 0.1319750000 0.0089850000 0.0558820000 0.0003860000 0.0002830000 0.0613010000 9126526 96830484 1763926016 3.9944503307 4.0387120247 4.1235108376 470 18.7600000000 0.0113861011 0.0104736934 0.0160688832 0.0145867138 0.1023660000 0.0088580000 0.0437260000 0.0000250000 0.0002850000 0.0365360000 9128200 96830484 1764544512 3.9964919090 4.0439586639 4.1353120804 471 18.8000000000 0.0113452962 0.0104755439 0.0160688832 0.0145798970 0.1293210000 0.0085460000 0.0550310000 0.0002950000 0.0002690000 0.0541550000 9129874 96830484 1765306368 3.9978768826 4.0497260094 4.1477222443 472 18.8400000000 0.0112539819 0.0104771932 0.0160688832 0.0145652874 0.1282110000 0.0086260000 0.0685960000 0.0000270000 0.0003210000 0.0378040000 9131548 96830484 1765830656 4.0011067390 4.0558681488 4.1595654488 473 18.8800000000 0.0113356775 0.0104790081 0.0160688832 0.0145500571 0.1211360000 0.0085120000 0.0430930000 0.0002890000 0.0003430000 0.0636630000 9133222 96830484 1766576128 4.0037703514 4.0634779930 4.1714725494 474 18.9200000000 0.0113889612 0.0104809279 0.0160688832 0.0145385846 0.0966420000 0.0086270000 0.0400020000 0.0000240000 0.0003450000 0.0352810000 9134896 96830484 1767211008 4.0070776939 4.0697979927 4.1826992035 475 18.9600000000 0.0113049168 0.0104826626 0.0160688832 0.0145305249 0.1064210000 0.0084240000 0.0549240000 0.0002910000 0.0002710000 0.0373400000 9136570 96830484 1767845888 4.0107364655 4.0745744705 4.1953854561 476 19.0000000000 0.0114067327 0.0104846039 0.0160688832 0.0145208719 0.0919020000 0.0086640000 0.0383160000 0.0000170000 0.0001900000 0.0357510000 9138244 96830484 1768480768 4.0141143799 4.0774550438 4.2073850632 477 19.0400000000 0.0115353251 0.0104868067 0.0160688832 0.0145080226 0.1658640000 0.0086210000 0.0676300000 0.0003940000 0.0002790000 0.0673460000 9139918 96830484 1769132032 4.0156078339 4.0843043327 4.2192158699 478 19.0800000000 0.0114158904 0.0104887504 0.0160688832 0.0144952293 0.1123610000 0.0085280000 0.0623960000 0.0000270000 0.0003160000 0.0339170000 9141592 96830484 1769750528 4.0193328857 4.0915713310 4.2303614616 479 19.1200000000 0.0116351936 0.0104911438 0.0160688832 0.0144850380 0.0925100000 0.0088210000 0.0444720000 0.0003100000 0.0002770000 0.0333110000 9143266 96830484 1770401792 4.0228176117 4.0950903893 4.2422652245 480 19.1600000000 0.0116115678 0.0104934780 0.0160688832 0.0144761193 0.1030040000 0.0090220000 0.0436810000 0.0000260000 0.0003230000 0.0337210000 9144940 96830484 1771020288 4.0265946388 4.0998888016 4.2534060478 481 19.2000000000 0.0115217585 0.0104956158 0.0160688832 0.0144625638 0.1215210000 0.0091770000 0.0441370000 0.0003160000 0.0002740000 0.0623850000 9146614 96830484 1771782144 4.0277719498 4.1099119186 4.2636799812 482 19.2400000000 0.0115523562 0.0104978082 0.0160688832 0.0144607108 0.0980350000 0.0081950000 0.0447460000 0.0000260000 0.0002840000 0.0355020000 9148288 96830484 1772306432 4.0316448212 4.1142926216 4.2752709389 483 19.2800000000 0.0115761515 0.0105000408 0.0160688832 0.0144623352 0.1088310000 0.0083450000 0.0423980000 0.0003060000 0.0003470000 0.0473910000 9149962 96830484 1773051904 4.0341773033 4.1149830818 4.2867822647 484 19.3200000000 0.0115893660 0.0105022915 0.0160688832 0.0144603437 0.1106870000 0.0084710000 0.0542240000 0.0000300000 0.0002940000 0.0422770000 9151636 96830484 1773686784 4.0377469063 4.1162996292 4.2979540825 485 19.3600000000 0.0114974743 0.0105043434 0.0160688832 0.0144479971 0.1456420000 0.0085400000 0.0530310000 0.0003480000 0.0002690000 0.0671680000 9153310 96830484 1774321664 4.0397763252 4.1198101044 4.3091187477 486 19.4000000000 0.0115496861 0.0105064943 0.0160688832 0.0144330959 0.1096170000 0.0092730000 0.0535630000 0.0000230000 0.0003550000 0.0332290000 9154984 96830484 1774956544 4.0427598953 4.1267423630 4.3192477226 487 19.4400000000 0.0115138423 0.0105085628 0.0160688832 0.0144184357 0.1054660000 0.0089230000 0.0446170000 0.0003880000 0.0002780000 0.0388840000 9156658 96830484 1775718400 4.0431213379 4.1307654381 4.3309912682 488 19.4800000000 0.0115364054 0.0105106690 0.0160688832 0.0144039517 0.0906340000 0.0093010000 0.0421430000 0.0000290000 0.0003110000 0.0328530000 9158332 96830484 1776353280 4.0452318192 4.1335091591 4.3420305252 489 19.5200000000 0.0116027575 0.0105129023 0.0160688832 0.0143898032 0.1211870000 0.0088310000 0.0449160000 0.0003170000 0.0004790000 0.0613010000 9160006 96830484 1776988160 4.0458960533 4.1412587166 4.3526411057 490 19.5600000000 0.0116997464 0.0105153244 0.0160688832 0.0143757476 0.0978580000 0.0084240000 0.0518260000 0.0000280000 0.0003160000 0.0319390000 9161680 96830484 1777750016 4.0462470055 4.1467127800 4.3634047508 491 19.6000000000 0.0115213031 0.0105173733 0.0160688832 0.0143614159 0.1064880000 0.0090430000 0.0446440000 0.0003830000 0.0002800000 0.0387140000 9163354 96830484 1778384896 4.0491342545 4.1527132988 4.3736872673 492 19.6400000000 0.0117682116 0.0105199156 0.0160688832 0.0143468445 0.0911090000 0.0094120000 0.0438050000 0.0000310000 0.0003080000 0.0320080000 9165028 96830484 1779146752 4.0492892265 4.1573224068 4.3839845657 493 19.6800000000 0.0116569055 0.0105222219 0.0160688832 0.0143326318 0.1225480000 0.0089230000 0.0470500000 0.0003890000 0.0002750000 0.0604670000 9166702 96830484 1779781632 4.0498723984 4.1597957611 4.3948802948 494 19.7200000000 0.0115851117 0.0105243735 0.0160688832 0.0143181051 0.0952100000 0.0088000000 0.0474600000 0.0000260000 0.0002850000 0.0332660000 9168376 96830484 1780543488 4.0500421524 4.1608400345 4.4061074257 495 19.7600000000 0.0116552720 0.0105266581 0.0160688832 0.0143047720 0.1065110000 0.0084620000 0.0435760000 0.0002830000 0.0002560000 0.0404510000 9170050 96830484 1781178368 4.0507330894 4.1657371521 4.4172549248 496 19.8000000000 0.0116603430 0.0105289438 0.0160688832 0.0142921174 0.1304610000 0.0086050000 0.0733270000 0.0000280000 0.0003540000 0.0381950000 9171724 96830484 1781829632 4.0507826805 4.1724724770 4.4277591705 497 19.8400000000 0.0116244899 0.0105311481 0.0160688832 0.0142800316 0.1276450000 0.0084720000 0.0469250000 0.0003480000 0.0002610000 0.0661890000 9173398 96830484 1782448128 4.0506653786 4.1786184311 4.4387550354 498 19.8800000000 0.0117052551 0.0105335058 0.0160688832 0.0142711430 0.0890600000 0.0089220000 0.0353780000 0.0000070000 0.0000670000 0.0339520000 9175072 96830484 1783099392 4.0493454933 4.1855602264 4.4495143890 499 19.9200000000 0.0117276525 0.0105358988 0.0160688832 0.0142630589 0.1294100000 0.0087120000 0.0538760000 0.0003660000 0.0002740000 0.0563450000 9176746 96830484 1783844864 4.0484189987 4.1918463707 4.4611778259 500 19.9600000000 0.0116441641 0.0105381154 0.0160688832 0.0142531500 0.1079510000 0.0084270000 0.0491690000 0.0000270000 0.0003550000 0.0381990000 9178420 96830484 1784369152 4.0473527908 4.1936402321 4.4723339081 501 20.0000000000 0.0115444530 0.0105401240 0.0160688832 0.0142442125 0.1408110000 0.0086660000 0.0554770000 0.0003140000 0.0002740000 0.0704140000 9180094 96830484 1785114624 4.0458536148 4.1964988708 4.4831652641 502 20.0400000000 0.0116109122 0.0105422571 0.0160688832 0.0142348281 0.0973170000 0.0090970000 0.0454370000 0.0000290000 0.0003890000 0.0320310000 9181768 96830484 1785749504 4.0444250107 4.2013077736 4.4942336082 503 20.0800000000 0.0116968332 0.0105445525 0.0160688832 0.0142229267 0.1079040000 0.0109870000 0.0443880000 0.0003130000 0.0002770000 0.0378150000 9183442 96830484 1784115200 4.0422153473 4.2079029083 4.5050363541 504 20.1200000000 0.0115976352 0.0105466419 0.0160688832 0.0142088224 0.0913920000 0.0114020000 0.0446590000 0.0000280000 0.0007040000 0.0289460000 9185116 96830484 1782861824 4.0395669937 4.2128443718 4.5159192085 505 20.1600000000 0.0117031699 0.0105489321 0.0160688832 0.0141949749 0.1199930000 0.0102630000 0.0443520000 0.0003240000 0.0002830000 0.0590230000 9186790 96830484 1781850112 4.0380215645 4.2193408012 4.5265440941 506 20.2000000000 0.0116224959 0.0105510537 0.0160688832 0.0141841882 0.0951170000 0.0118300000 0.0462030000 0.0000270000 0.0003100000 0.0310590000 9188464 96830484 1780051968 4.0360379219 4.2284111977 4.5365138054 507 20.2400000000 0.0115596624 0.0105530431 0.0160688832 0.0141808550 0.1054400000 0.0101000000 0.0453920000 0.0003870000 0.0002810000 0.0375220000 9190138 96830484 1779552256 4.0331716537 4.2334403992 4.5469946861 508 20.2800000000 0.0115690846 0.0105550432 0.0160688832 0.0141794323 0.1065450000 0.0120280000 0.0452350000 0.0000280000 0.0003840000 0.0323820000 9191812 96830484 1777504256 4.0309510231 4.2380833626 4.5571103096 509 20.3200000000 0.0115840537 0.0105570648 0.0160688832 0.0141908714 0.1250440000 0.0119350000 0.0471150000 0.0003850000 0.0002750000 0.0596920000 9193486 96830484 1775996928 4.0283265114 4.2447280884 4.5666604042 510 20.3600000000 0.0116568990 0.0105592213 0.0160688832 0.0141922098 0.0947620000 0.0119240000 0.0448780000 0.0000280000 0.0003160000 0.0319940000 9195160 96830484 1774219264 4.0243959427 4.2493920326 4.5761098862 511 20.4000000000 0.0116405534 0.0105613375 0.0160688832 0.0141905381 0.1055590000 0.0104060000 0.0447950000 0.0003810000 0.0002710000 0.0381200000 9196834 96830484 1774333952 4.0223431587 4.2542047501 4.5848355293 512 20.4400000000 0.0116521586 0.0105634680 0.0160688832 0.0141960497 0.0918510000 0.0121890000 0.0451660000 0.0000300000 0.0003140000 0.0285720000 9198508 96830484 1772298240 4.0219945908 4.2607707977 4.5928282738 513 20.4800000000 0.0116533497 0.0105655925 0.0160688832 0.0141968401 0.1228440000 0.0100900000 0.0469250000 0.0003210000 0.0002750000 0.0592880000 9241142 96830484 1772171264 4.0203447342 4.2650027275 4.6011042595 514 20.5200000000 0.0116831949 0.0105677668 0.0160688832 0.0142002651 0.1084560000 0.0120770000 0.0472910000 0.0000280000 0.0003070000 0.0321720000 9326784 96830484 1770266624 4.0189733505 4.2672095299 4.6095933914 515 20.5600000000 0.0116043892 0.0105697797 0.0160688832 0.0142063005 0.1095520000 0.0119180000 0.0470860000 0.0003940000 0.0002780000 0.0379310000 9328458 96830484 1768378368 4.0186061859 4.2690076828 4.6166710854 516 20.6000000000 0.0116262604 0.0105718271 0.0160688832 0.0142212729 0.0930000000 0.0101870000 0.0443400000 0.0000290000 0.0003870000 0.0297920000 9330132 96830484 1769918464 4.0186409950 4.2746281624 4.6238722801 517 20.6400000000 0.0116966031 0.0105740027 0.0160688832 0.0142354185 0.1240670000 0.0117440000 0.0463130000 0.0003870000 0.0002760000 0.0595490000 9331806 96830484 1767964672 4.0188555717 4.2783026695 4.6304397583 518 20.6800000000 0.0116905598 0.0105761582 0.0160688832 0.0142538573 0.0908230000 0.0095850000 0.0446400000 0.0000250000 0.0003640000 0.0304240000 9333480 96830484 1769631744 4.0189628601 4.2813735008 4.6369152069 519 20.7200000000 0.0117115034 0.0105783458 0.0160688832 0.0142728975 0.1057290000 0.0108260000 0.0427380000 0.0002910000 0.0003400000 0.0398050000 9335154 96830484 1768525824 4.0208888054 4.2851371765 4.6426157951 520 20.7600000000 0.0116806701 0.0105804656 0.0160688832 0.0143011488 0.1101650000 0.0090170000 0.0581830000 0.0000290000 0.0019240000 0.0351150000 9336828 96830484 1770172416 4.0221014023 4.2880735397 4.6481432915 521 20.8000000000 0.0116343936 0.0105824885 0.0160688832 0.0143260846 0.1254880000 0.0111550000 0.0479220000 0.0002900000 0.0002620000 0.0599730000 9338502 96830484 1769009152 4.0240001678 4.2886986732 4.6534800529 522 20.8400000000 0.0116969440 0.0105846235 0.0160688832 0.0143538594 0.1075080000 0.0099250000 0.0450130000 0.0000270000 0.0003160000 0.0327360000 9340176 96830484 1770790912 4.0253849030 4.2889876366 4.6586790085 523 20.8800000000 0.0116610071 0.0105866816 0.0160688832 0.0143831857 0.1095860000 0.0113780000 0.0448940000 0.0003790000 0.0002850000 0.0387440000 9341850 96830484 1769775104 4.0274853706 4.2887372971 4.6632061005 524 20.9200000000 0.0116678681 0.0105887449 0.0160688832 0.0144174352 0.0910940000 0.0096610000 0.0442500000 0.0000270000 0.0003140000 0.0310650000 9343524 96830484 1771425792 4.0299305916 4.2922201157 4.6673679352 525 20.9600000000 0.0117239906 0.0105909073 0.0160688832 0.0144346236 0.1174370000 0.0112390000 0.0363680000 0.0003700000 0.0002820000 0.0631970000 9345198 96830484 1770266624 4.0326085091 4.2938580513 4.6712741852 526 21.0000000000 0.0117463293 0.0105931039 0.0160688832 0.0144460959 0.0989600000 0.0113150000 0.0454790000 0.0000270000 0.0003060000 0.0344030000 9346872 96830484 1768615936 4.0355591774 4.2933068275 4.6749892235 527 21.0400000000 0.0117905363 0.0105953761 0.0160688832 0.0144630483 0.1108740000 0.0086680000 0.0523320000 0.0002900000 0.0003520000 0.0434590000 9348546 96830484 1770299392 4.0383038521 4.2948670387 4.6784877777 528 21.0800000000 0.0118694026 0.0105977890 0.0160688832 0.0144734055 0.1070830000 0.0103480000 0.0549850000 0.0000260000 0.0002970000 0.0355120000 9350220 96830484 1769156608 4.0417923927 4.2965326309 4.6814851761 529 21.1200000000 0.0118748900 0.0106002032 0.0160688832 0.0144756782 0.1409410000 0.0085920000 0.0545970000 0.0003630000 0.0002760000 0.0712500000 9351894 96830484 1770790912 4.0443677902 4.2965869904 4.6844520569 530 21.1600000000 0.0119122155 0.0106026787 0.0160688832 0.0144810547 0.0909120000 0.0106920000 0.0371430000 0.0000280000 0.0002940000 0.0351230000 9353568 96830484 1770029056 4.0476889610 4.2977828979 4.6871786118 531 21.2000000000 0.0119650364 0.0106052443 0.0160688832 0.0144912985 0.1265760000 0.0089220000 0.0542170000 0.0003790000 0.0002890000 0.0529620000 9355242 96830484 1769013248 4.0513839722 4.2980327606 4.6897726059 532 21.2400000000 0.0119334105 0.0106077409 0.0160688832 0.0145067985 0.1498350000 0.0085070000 0.1031510000 0.0000260000 0.0002840000 0.0319130000 9356916 96830484 1770663936 4.0550255775 4.2973566055 4.6920576096 533 21.2800000000 0.0119438386 0.0106102476 0.0160688832 0.0145253304 0.1449520000 0.0106500000 0.0511290000 0.0005130000 0.0002730000 0.0647590000 9358590 96830484 1769869312 4.0591387749 4.2976660728 4.6942725182 534 21.3200000000 0.0119648948 0.0106127844 0.0160688832 0.0145423101 0.1097260000 0.0106470000 0.0523980000 0.0000270000 0.0003660000 0.0334940000 9360264 96830484 1768251392 4.0631852150 4.2976694107 4.6964898109 535 21.3600000000 0.0119674345 0.0106153165 0.0160688832 0.0145597025 0.1086140000 0.0095020000 0.0466400000 0.0003140000 0.0002760000 0.0404210000 9361938 96830484 1769934848 4.0669856071 4.2981467247 4.6988139153 536 21.4000000000 0.0119854575 0.0106178727 0.0160688832 0.0145772244 0.1068080000 0.0102390000 0.0443540000 0.0000270000 0.0003100000 0.0342890000 9363612 96830484 1768783872 4.0708494186 4.2987155914 4.7009525299 537 21.4400000000 0.0120353559 0.0106205124 0.0160688832 0.0145964403 0.1158160000 0.0086210000 0.0387090000 0.0003010000 0.0002720000 0.0619970000 9365286 96830484 1770405888 4.0753259659 4.2993531227 4.7032017708 538 21.4800000000 0.0120200235 0.0106231137 0.0160688832 0.0146055564 0.1042750000 0.0114450000 0.0521270000 0.0000300000 0.0003720000 0.0343520000 9366960 96830484 1769377792 4.0800843239 4.3002853394 4.7051382065 539 21.5200000000 0.0121024903 0.0106258583 0.0160688832 0.0146158551 0.1076620000 0.0084320000 0.0473990000 0.0006800000 0.0002940000 0.0414130000 9368634 96830484 1771061248 4.0850701332 4.3015570641 4.7067751884 540 21.5600000000 0.0119877681 0.0106283804 0.0160688832 0.0146177652 0.1069550000 0.0105660000 0.0454520000 0.0000280000 0.0003060000 0.0358590000 9370308 96830484 1770012672 4.0889334679 4.3018021584 4.7090082169 541 21.6000000000 0.0121151386 0.0106311286 0.0160688832 0.0146214616 0.1232220000 0.0102490000 0.0393470000 0.0003090000 0.0002790000 0.0671010000 9371982 96830484 1768218624 4.0933828354 4.3020091057 4.7108378410 542 21.6400000000 0.0121535398 0.0106339374 0.0160688832 0.0146291457 0.0955460000 0.0087230000 0.0413430000 0.0000260000 0.0003760000 0.0379240000 9373656 96830484 1769902080 4.0971231461 4.3034329414 4.7127761841 543 21.6800000000 0.0120752761 0.0106365918 0.0160688832 0.0146456845 0.1479030000 0.0092950000 0.0553420000 0.0003050000 0.0002880000 0.0734980000 9375330 96830484 1768873984 4.1010899544 4.3041167259 4.7148785591 544 21.7200000000 0.0120981252 0.0106392785 0.0160688832 0.0146602723 0.1260770000 0.0084440000 0.0543520000 0.0000270000 0.0003100000 0.0473110000 9377004 96830484 1770553344 4.1041455269 4.3047032356 4.7170534134 545 21.7600000000 0.0121370684 0.0106420267 0.0160688832 0.0146746870 0.1678980000 0.0094670000 0.0675550000 0.0003040000 0.0003520000 0.0719710000 9378678 96830484 1769406464 4.1083893776 4.3065557480 4.7192153931 546 21.8000000000 0.0122148590 0.0106449074 0.0160688832 0.0147506982 0.0931660000 0.0083490000 0.0414150000 0.0000290000 0.0003620000 0.0369020000 9380352 96830484 1771061248 4.1140718460 4.3078327179 4.7236490250 547 21.8400000000 0.0122096464 0.0106477680 0.0160688832 0.0147588082 0.1291790000 0.0095100000 0.0554490000 0.0002920000 0.0005770000 0.0572940000 9382026 96830484 1770139648 4.1176891327 4.3086657524 4.7259025574 548 21.8800000000 0.0121702114 0.0106505461 0.0160688832 0.0147718510 0.1235030000 0.0096620000 0.0523200000 0.0000260000 0.0003580000 0.0478940000 9383700 96830484 1768108032 4.1218352318 4.3104910851 4.7277145386 549 21.9200000000 0.0121920556 0.0106533540 0.0160688832 0.0147926752 0.1663590000 0.0079410000 0.0707930000 0.0003900000 0.0002820000 0.0809320000 9385374 96830484 1769914368 4.1253275871 4.3122415543 4.7299380302 550 21.9600000000 0.0121534644 0.0106560815 0.0160688832 0.0148097170 0.0945590000 0.0101070000 0.0391760000 0.0000260000 0.0002840000 0.0389230000 9387048 96830484 1768910848 4.1306748390 4.3132162094 4.7314720154 551 22.0000000000 0.0120386072 0.0106585906 0.0160688832 0.0148367670 0.1238320000 0.0080310000 0.0457810000 0.0002840000 0.0003350000 0.0558870000 9388722 96830484 1767735296 4.1338753700 4.3155546188 4.7331228256 552 22.0400000000 0.0120769665 0.0106611601 0.0160688832 0.0148478816 0.1279830000 0.0077000000 0.0527590000 0.0000290000 0.0002900000 0.0527100000 9390396 96830484 1766862848 4.1385684013 4.3180551529 4.7345294952 553 22.0800000000 0.0120506072 0.0106636727 0.0160688832 0.0148446069 0.1582290000 0.0078070000 0.0512030000 0.0003680000 0.0002810000 0.0924650000 9392070 96830484 1766084608 4.1431608200 4.3179240227 4.7360243797 554 22.1200000000 0.0120735979 0.0106662177 0.0160688832 0.0148380699 0.0988750000 0.0087570000 0.0367990000 0.0000260000 0.0002930000 0.0441800000 9393744 96830484 1767886848 4.1464219093 4.3171186447 4.7381052971 555 22.1600000000 0.0120204436 0.0106686577 0.0160688832 0.0148305347 0.1083380000 0.0073950000 0.0327380000 0.0002380000 0.0001730000 0.0562560000 9395418 96830484 1769521152 4.1525597572 4.3189582825 4.7391710281 556 22.2000000000 0.0119124698 0.0106708948 0.0160688832 0.0148293677 0.0919030000 0.0094500000 0.0345160000 0.0000250000 0.0003570000 0.0414070000 9397092 96830484 1768378368 4.1577291489 4.3218340874 4.7405238152 557 22.2400000000 0.0119678266 0.0106732232 0.0160688832 0.0148256391 0.1328650000 0.0080410000 0.0359080000 0.0002930000 0.0003420000 0.0819720000 9398766 96830484 1767010304 4.1623172760 4.3236289024 4.7420625687 558 22.2800000000 0.0118775629 0.0106753815 0.0160688832 0.0148251687 0.0984990000 0.0084780000 0.0356290000 0.0000240000 0.0003490000 0.0459500000 9400440 96830484 1768632320 4.1676216125 4.3264393806 4.7435956001 559 22.3200000000 0.0118844174 0.0106775444 0.0160688832 0.0148221906 0.1098640000 0.0073240000 0.0388650000 0.0002890000 0.0003450000 0.0569180000 9402114 96830484 1770409984 4.1731233597 4.3290686607 4.7450351715 560 22.3600000000 0.0118583841 0.0106796530 0.0160688832 0.0148181018 0.1275110000 0.0094050000 0.0519730000 0.0000280000 0.0003110000 0.0584420000 9403788 96830484 1769377792 4.1770343781 4.3298878670 4.7475967407 561 22.4000000000 0.0118813328 0.0106817950 0.0160688832 0.0148149216 0.1480110000 0.0077870000 0.0416620000 0.0002890000 0.0003370000 0.0917620000 9405462 96830484 1770934272 4.1813197136 4.3322439194 4.7492933273 562 22.4400000000 0.0118439738 0.0106838630 0.0160688832 0.0148129908 0.1062240000 0.0095850000 0.0325970000 0.0000060000 0.0000640000 0.0474930000 9407136 96830484 1770156032 4.1866855621 4.3355236053 4.7504720688 563 22.4800000000 0.0118390182 0.0106859148 0.0160688832 0.0148062298 0.1292340000 0.0099210000 0.0533250000 0.0002960000 0.0003550000 0.0518040000 9408810 96830484 1768488960 4.1928815842 4.3390789032 4.7510776520 564 22.5200000000 0.0118296659 0.0106879427 0.0160688832 0.0147967303 0.0928740000 0.0084430000 0.0340130000 0.0000170000 0.0001930000 0.0438530000 9410484 96830484 1770156032 4.1971182823 4.3407721519 4.7527747154 565 22.5600000000 0.0118575878 0.0106900129 0.0160688832 0.0147870483 0.1463250000 0.0093450000 0.0370050000 0.0003640000 0.0002760000 0.0930900000 9412158 96830484 1769246720 4.2007350922 4.3417973518 4.7543959618 566 22.6000000000 0.0118587706 0.0106920778 0.0160688832 0.0147781216 0.1055210000 0.0082110000 0.0323460000 0.0000060000 0.0001250000 0.0476390000 9413832 96830484 1770790912 4.2058572769 4.3449907303 4.7557134628 567 22.6400000000 0.0118634021 0.0106941436 0.0160688832 0.0147670293 0.1257820000 0.0099380000 0.0483120000 0.0003620000 0.0018900000 0.0508230000 9415506 96830484 1770029056 4.2105374336 4.3471117020 4.7567801476 568 22.6800000000 0.0119272424 0.0106963146 0.0160688832 0.0147574449 0.1086470000 0.0103240000 0.0358040000 0.0000270000 0.0003110000 0.0481860000 9417180 96830484 1767849984 4.2147784233 4.3489818573 4.7582635880 569 22.7200000000 0.0119394707 0.0106984994 0.0160688832 0.0147464581 0.1646830000 0.0077970000 0.0516340000 0.0003580000 0.0002760000 0.0982650000 9418854 96830484 1769644032 4.2202959061 4.3504929543 4.7585477829 570 22.7600000000 0.0119343987 0.0107006676 0.0160688832 0.0147358188 0.1118870000 0.0084120000 0.0424690000 0.0000270000 0.0010590000 0.0460030000 9420528 96830484 1771294720 4.2244129181 4.3532791138 4.7594637871 571 22.8000000000 0.0120029971 0.0107029484 0.0160688832 0.0147238897 0.1113560000 0.0097610000 0.0412100000 0.0003610000 0.0002730000 0.0534860000 9422202 96830484 1770520576 4.2295117378 4.3560423851 4.7602372169 572 22.8400000000 0.0119402083 0.0107051115 0.0160688832 0.0147115499 0.1263600000 0.0097270000 0.0441610000 0.0000290000 0.0003100000 0.0618490000 9423876 96830484 1768497152 4.2353725433 4.3589243889 4.7598538399 573 22.8800000000 0.0119825508 0.0107073408 0.0160688832 0.0147001050 0.1872120000 0.0077440000 0.0577120000 0.0002990000 0.0002790000 0.1081110000 9425550 96830484 1770147840 4.2395248413 4.3611550331 4.7606091499 574 22.9200000000 0.0120024914 0.0107095972 0.0160688832 0.0146890675 0.1085930000 0.0101210000 0.0362190000 0.0000260000 0.0003700000 0.0496500000 9427224 96830484 1769132032 4.2439126968 4.3643050194 4.7608065605 575 22.9600000000 0.0119909812 0.0107118257 0.0160688832 0.0146764505 0.1477770000 0.0076680000 0.0517330000 0.0003070000 0.0002790000 0.0726850000 9428898 96830484 1770815488 4.2479119301 4.3671135902 4.7614507675 576 23.0000000000 0.0120123085 0.0107140835 0.0160688832 0.0146637763 0.1311600000 0.0093410000 0.0640170000 0.0000280000 0.0003850000 0.0510490000 9430572 96830484 1769750528 4.2516689301 4.3705306053 4.7619810104 577 23.0400000000 0.0120693566 0.0107164323 0.0160688832 0.0146510645 0.1504040000 0.0076780000 0.0433530000 0.0002980000 0.0002750000 0.0924080000 9432246 96830484 1771274240 4.2554821968 4.3741393089 4.7623939514 578 23.0800000000 0.0120945619 0.0107188166 0.0160688832 0.0146385404 0.1046430000 0.0108210000 0.0334270000 0.0000280000 0.0003600000 0.0503220000 9433920 96830484 1770254336 4.2584109306 4.3759479523 4.7627825737 579 23.1200000000 0.0120345950 0.0107210891 0.0160688832 0.0146264076 0.1477640000 0.0095720000 0.0456830000 0.0002930000 0.0002700000 0.0816700000 9435594 96830484 1768513536 4.2622876167 4.3794817924 4.7623949051 580 23.1600000000 0.0121392962 0.0107235343 0.0160688832 0.0146143603 0.1467640000 0.0078380000 0.0501720000 0.0000300000 0.0006990000 0.0711780000 9437268 96830484 1770258432 4.2666721344 4.3853607178 4.7623219490 581 23.2000000000 0.0121114021 0.0107259231 0.0160688832 0.0146018513 0.1896260000 0.0093440000 0.0831450000 0.0002930000 0.0002700000 0.0900460000 9438942 96830484 1769127936 4.2703127861 4.3899369240 4.7621145248 582 23.2400000000 0.0121604279 0.0107283878 0.0160688832 0.0145893579 0.1089390000 0.0083830000 0.0401290000 0.0000260000 0.0003670000 0.0504580000 9440616 96830484 1770799104 4.2728290558 4.3934316635 4.7621459961 583 23.2800000000 0.0121904686 0.0107308957 0.0160688832 0.0145769469 0.1485780000 0.0095540000 0.0455170000 0.0003000000 0.0002860000 0.0826050000 9442290 96830484 1770131456 4.2759299278 4.3984942436 4.7622585297 584 23.3200000000 0.0121618081 0.0107333459 0.0160688832 0.0145656083 0.1489860000 0.0097330000 0.0509290000 0.0000310000 0.0003320000 0.0810000000 9443964 96830484 1767972864 4.2784323692 4.4013662338 4.7615747452 585 23.3600000000 0.0121940160 0.0107358428 0.0160688832 0.0145537774 0.2069570000 0.0087260000 0.0552620000 0.0003060000 0.0002810000 0.1295660000 9445638 96830484 1769734144 4.2810482979 4.4034867287 4.7611641884 586 23.4000000000 0.0122114606 0.0107383609 0.0160688832 0.0145418038 0.1086380000 0.0091760000 0.0359980000 0.0000260000 0.0004710000 0.0542170000 9447312 96830484 1769017344 4.2833175659 4.4064311981 4.7611942291 587 23.4400000000 0.0122115798 0.0107408706 0.0160688832 0.0145294329 0.1469320000 0.0075710000 0.0431020000 0.0003650000 0.0002790000 0.0823450000 9448986 96830484 1770639360 4.2855997086 4.4096841812 4.7609405518 588 23.4800000000 0.0122095225 0.0107433683 0.0160688832 0.0145171597 0.1278830000 0.0097340000 0.0541310000 0.0000310000 0.0003120000 0.0485640000 9450660 96830484 1769512960 4.2877945900 4.4124512672 4.7609281540 589 23.5200000000 0.0121814338 0.0107458099 0.0160688832 0.0145049045 0.1489620000 0.0084080000 0.0436030000 0.0003070000 0.0003450000 0.0844630000 9452334 96830484 1771163648 4.2906374931 4.4152178764 4.7607808113 590 23.5600000000 0.0122214919 0.0107483110 0.0160688832 0.0144926187 0.1103700000 0.0099550000 0.0459080000 0.0000300000 0.0003890000 0.0474500000 9454008 96830484 1770131456 4.2923445702 4.4170279503 4.7612104416 591 23.6000000000 0.0122050140 0.0107507758 0.0160688832 0.0144804299 0.1252290000 0.0102340000 0.0425550000 0.0003610000 0.0002830000 0.0551000000 9455682 96830484 1768370176 4.2943358421 4.4197645187 4.7616887093 592 23.6400000000 0.0121584972 0.0107531537 0.0160688832 0.0144689991 0.1115320000 0.0081860000 0.0497640000 0.0000270000 0.0003130000 0.0466730000 9457356 96830484 1769922560 4.2972202301 4.4224524498 4.7611260414 593 23.6800000000 0.0120464331 0.0107553347 0.0160688832 0.0144603671 0.1448120000 0.0099170000 0.0405640000 0.0003710000 0.0002830000 0.0869710000 9459030 96830484 1769127936 4.3010764122 4.4257235527 4.7615780830 594 23.7200000000 0.0119596142 0.0107573621 0.0160688832 0.0144481884 0.1100140000 0.0083020000 0.0395320000 0.0000270000 0.0002840000 0.0506900000 9460704 96830484 1770688512 4.3021874428 4.4262385368 4.7623476982 595 23.7600000000 0.0119283330 0.0107593301 0.0160688832 0.0144362689 0.1467400000 0.0092870000 0.0470090000 0.0002930000 0.0002690000 0.0742890000 9462378 96830484 1769639936 4.3036971092 4.4281611443 4.7626190186 596 23.8000000000 0.0118806725 0.0107612115 0.0160688832 0.0144242076 0.1297590000 0.0078660000 0.0464020000 0.0000250000 0.0002850000 0.0644350000 9464052 96830484 1771290624 4.3049235344 4.4304800034 4.7634453773 597 23.8400000000 0.0119718630 0.0107632394 0.0160688832 0.0144123879 0.1877130000 0.0091320000 0.0497450000 0.0003660000 0.0002840000 0.1154070000 9465726 96830484 1770496000 4.3061337471 4.4326672554 4.7639555931 598 23.8800000000 0.0119486926 0.0107652218 0.0160688832 0.0144012652 0.1096850000 0.0102150000 0.0418800000 0.0000110000 0.0001090000 0.0508780000 9467400 96830484 1768751104 4.3067502975 4.4336915016 4.7648339272 599 23.9200000000 0.0118536344 0.0107670388 0.0160688832 0.0143912663 0.1277800000 0.0078870000 0.0415960000 0.0002950000 0.0003420000 0.0701560000 9469074 96830484 1770528768 4.3076801300 4.4354748726 4.7656860352 600 23.9600000000 0.0118646249 0.0107688681 0.0160688832 0.0143816252 0.1476550000 0.0097900000 0.0728570000 0.0000310000 0.0003050000 0.0547910000 9470748 96830484 1768386560 4.3077797890 4.4372258186 4.7665805817 601 24.0000000000 0.0117758950 0.0107705437 0.0160688832 0.0143729165 0.1618410000 0.0078050000 0.0436020000 0.0002970000 0.0002670000 0.1032250000 9472422 96830484 1770147840 4.3087158203 4.4407606125 4.7682118416 602 24.0400000000 0.0117431385 0.0107721593 0.0160688832 0.0143623897 0.1102550000 0.0097230000 0.0359490000 0.0000260000 0.0003650000 0.0511760000 9474096 96830484 1769275392 4.3093419075 4.4411268234 4.7688283920 603 24.0800000000 0.0116831418 0.0107736701 0.0160688832 0.0143521139 0.1478330000 0.0075740000 0.0508650000 0.0003620000 0.0002790000 0.0752230000 9475770 96830484 1771020288 4.3099532127 4.4422488213 4.7696304321 604 24.1200000000 0.0117323156 0.0107752572 0.0160688832 0.0143404259 0.1491660000 0.0095450000 0.0732730000 0.0000280000 0.0002850000 0.0548160000 9477444 96830484 1770131456 4.3107843399 4.4435849190 4.7703776360 605 24.1600000000 0.0117073925 0.0107767980 0.0160688832 0.0143286890 0.1657710000 0.0094830000 0.0453540000 0.0002940000 0.0003420000 0.1035070000 9479118 96830484 1768366080 4.3120574951 4.4479808807 4.7715840340 606 24.2000000000 0.0116634527 0.0107782611 0.0160688832 0.0143168443 0.1103010000 0.0083080000 0.0423880000 0.0000260000 0.0002860000 0.0484430000 9480792 96830484 1770131456 4.3126788139 4.4495725632 4.7725281715 607 24.2400000000 0.0116151376 0.0107796398 0.0160688832 0.0143053194 0.1110690000 0.0096780000 0.0419970000 0.0004280000 0.0003650000 0.0518220000 9482466 96830484 1769238528 4.3137698174 4.4511990547 4.7727437019 608 24.2800000000 0.0116916848 0.0107811399 0.0160688832 0.0142937027 0.1069910000 0.0082540000 0.0419450000 0.0000240000 0.0002790000 0.0495490000 9484140 96830484 1770782720 4.3142890930 4.4522838593 4.7736353874 609 24.3200000000 0.0116454381 0.0107825591 0.0160688832 0.0142821848 0.1827980000 0.0092240000 0.0502050000 0.0003490000 0.0002670000 0.0957090000 9485814 96830484 1770020864 4.3148298264 4.4535403252 4.7741084099 610 24.3600000000 0.0116084274 0.0107839130 0.0160688832 0.0142705318 0.1130030000 0.0102420000 0.0451460000 0.0000290000 0.0003170000 0.0494110000 9487488 96830484 1768226816 4.3153676987 4.4562654495 4.7744960785 611 24.4000000000 0.0115929190 0.0107852370 0.0160688832 0.0142588495 0.1255960000 0.0083370000 0.0427550000 0.0002870000 0.0011420000 0.0543170000 9489162 96830484 1769988096 4.3163347244 4.4586682320 4.7746906281 612 24.4400000000 0.0115979966 0.0107865651 0.0160688832 0.0142471966 0.1102350000 0.0098180000 0.0376620000 0.0000270000 0.0002840000 0.0510820000 9490836 96830484 1768890368 4.3159327507 4.4604687691 4.7758231163 613 24.4800000000 0.0116254520 0.0107879336 0.0160688832 0.0142357771 0.1678070000 0.0077910000 0.0440450000 0.0003630000 0.0002800000 0.1030580000 9492510 96830484 1770622976 4.3167695999 4.4630284309 4.7761507034 614 24.5200000000 0.0116320243 0.0107893083 0.0160688832 0.0142247793 0.1097980000 0.0099080000 0.0430250000 0.0000270000 0.0010130000 0.0488790000 9494184 96830484 1769766912 4.3164319992 4.4648203850 4.7771196365 615 24.5600000000 0.0115811257 0.0107905958 0.0160688832 0.0142140782 0.1084850000 0.0082450000 0.0355540000 0.0005600000 0.0002860000 0.0570610000 9495858 96830484 1771511808 4.3155646324 4.4674983025 4.7782735825 616 24.6000000000 0.0116285449 0.0107919561 0.0160688832 0.0142031720 0.1268140000 0.0093000000 0.0470680000 0.0000260000 0.0002910000 0.0589780000 9497532 96830484 1770401792 4.3147687912 4.4694528580 4.7796039581 617 24.6400000000 0.0115872547 0.0107932451 0.0160688832 0.0141918630 0.1678900000 0.0097400000 0.0517400000 0.0002940000 0.0002700000 0.0990370000 9499206 96830484 1768640512 4.3138771057 4.4713950157 4.7808027267 618 24.6800000000 0.0115898699 0.0107945341 0.0160688832 0.0141825062 0.1089370000 0.0083950000 0.0423310000 0.0000260000 0.0002840000 0.0484660000 9500880 96830484 1770147840 4.3130326271 4.4732818604 4.7822132111 619 24.7200000000 0.0115453061 0.0107957470 0.0160688832 0.0141733611 0.1264330000 0.0100360000 0.0454770000 0.0003770000 0.0002780000 0.0542740000 9502554 96830484 1769238528 4.3114185333 4.4760627747 4.7837276459 620 24.7600000000 0.0115752276 0.0107970042 0.0160688832 0.0141648241 0.1097770000 0.0083210000 0.0427350000 0.0000260000 0.0009840000 0.0474700000 9504228 96830484 1770926080 4.3100194931 4.4776725769 4.7850098610 621 24.8000000000 0.0115697645 0.0107982486 0.0160688832 0.0141569730 0.1479420000 0.0101810000 0.0424840000 0.0003610000 0.0002730000 0.0822030000 9505902 96830484 1769877504 4.3079705238 4.4794783592 4.7869267464 622 24.8400000000 0.0115609681 0.0107994749 0.0160688832 0.0141498715 0.1087400000 0.0098040000 0.0421950000 0.0000270000 0.0003550000 0.0466670000 9507576 96830484 1768353792 4.3060827255 4.4814505577 4.7891383171 623 24.8800000000 0.0116129387 0.0108007806 0.0160688832 0.0141455296 0.1095360000 0.0083270000 0.0425310000 0.0002880000 0.0002620000 0.0511220000 9509250 96830484 1770037248 4.3044829369 4.4848513603 4.7910475731 624 24.9200000000 0.0115423910 0.0108019691 0.0160688832 0.0141391144 0.1077120000 0.0096180000 0.0424910000 0.0000250000 0.0003500000 0.0481740000 9510924 96830484 1768898560 4.3033385277 4.4857993126 4.7927794456 625 24.9600000000 0.0115176225 0.0108031141 0.0160688832 0.0141323219 0.1452310000 0.0075440000 0.0376020000 0.0002940000 0.0003380000 0.0811010000 9512598 96830484 1770622976 4.3010482788 4.4882593155 4.7949824333 626 25.0000000000 0.0115791038 0.0108043537 0.0160688832 0.0141257287 0.1097710000 0.0098380000 0.0431250000 0.0000260000 0.0002810000 0.0452330000 9514272 96830484 1769529344 4.2988190651 4.4918112755 4.7970528603 627 25.0400000000 0.0115889898 0.0108056051 0.0160688832 0.0141232184 0.1257980000 0.0083500000 0.0426970000 0.0011360000 0.0002810000 0.0519680000 9515946 96830484 1771274240 4.2976512909 4.4952707291 4.7981467247 628 25.0800000000 0.0116152801 0.0108068944 0.0160688832 0.0141218981 0.1108690000 0.0097830000 0.0442910000 0.0000300000 0.0003110000 0.0446630000 9517620 96830484 1770401792 4.2957315445 4.4977731705 4.7997937202 629 25.1200000000 0.0115385829 0.0108080577 0.0160688832 0.0141240721 0.1476840000 0.0101290000 0.0354510000 0.0002920000 0.0002690000 0.0878520000 9519294 96830484 1768734720 4.2942924500 4.4998497963 4.8009681702 630 25.1600000000 0.0115555609 0.0108092442 0.0160688832 0.0141187911 0.1086930000 0.0084160000 0.0438980000 0.0000280000 0.0003880000 0.0439630000 9520968 96830484 1770307584 4.2905411720 4.5014061928 4.8035202026 631 25.2000000000 0.0116357664 0.0108105540 0.0160688832 0.0141132233 0.1099430000 0.0099450000 0.0426640000 0.0011660000 0.0002820000 0.0489630000 9522642 96830484 1769369600 4.2881770134 4.5038208961 4.8051319122 632 25.2400000000 0.0115838945 0.0108117777 0.0160688832 0.0141067967 0.1053200000 0.0083080000 0.0353270000 0.0000290000 0.0002980000 0.0463450000 9524316 96830484 1770938368 4.2848048210 4.5038800240 4.8078565598 633 25.2800000000 0.0115291951 0.0108129110 0.0160688832 0.0140983875 0.1656990000 0.0095940000 0.0541980000 0.0019640000 0.0002860000 0.0717340000 9525990 96830484 1769861120 4.2809948921 4.5053892136 4.8100600243 634 25.3200000000 0.0115811694 0.0108141228 0.0160688832 0.0140900826 0.1117910000 0.0101170000 0.0461390000 0.0000300000 0.0003240000 0.0426140000 9527664 96830484 1768263680 4.2773571014 4.5081925392 4.8126645088 635 25.3600000000 0.0115960287 0.0108153542 0.0160688832 0.0140826322 0.1095520000 0.0080910000 0.0432310000 0.0003680000 0.0012470000 0.0479510000 9529338 96830484 1769910272 4.2735300064 4.5104489326 4.8155031204 636 25.4000000000 0.0115859536 0.0108165658 0.0160688832 0.0140762429 0.1079290000 0.0099290000 0.0430170000 0.0000260000 0.0010470000 0.0419600000 9531012 96830484 1769156608 4.2699546814 4.5116209984 4.8178176880 637 25.4400000000 0.0114943413 0.0108176298 0.0160688832 0.0140696780 0.1287610000 0.0081860000 0.0362580000 0.0003820000 0.0006180000 0.0760200000 9532686 96830484 1770651648 4.2656726837 4.5126519203 4.8207316399 638 25.4800000000 0.0114927888 0.0108186880 0.0160688832 0.0140625027 0.1040180000 0.0108650000 0.0366590000 0.0000240000 0.0003880000 0.0437990000 9534360 96830484 1769639936 4.2605280876 4.5137438774 4.8242211342 639 25.5200000000 0.0114639616 0.0108196979 0.0160688832 0.0140553624 0.1300310000 0.0075830000 0.0489390000 0.0002990000 0.0003610000 0.0638710000 9536034 96830484 1771433984 4.2559423447 4.5140318871 4.8274774551 640 25.5600000000 0.0114620375 0.0108207015 0.0160688832 0.0140470791 0.1282790000 0.0096210000 0.0494090000 0.0000320000 0.0003780000 0.0600210000 9537708 96830484 1770164224 4.2510318756 4.5132980347 4.8310718536 641 25.6000000000 0.0114785088 0.0108217277 0.0160688832 0.0140390979 0.1649450000 0.0095370000 0.0652280000 0.0003290000 0.0003430000 0.0672950000 9539382 96830484 1768767488 4.2461061478 4.5134477615 4.8343033791 642 25.6400000000 0.0115634445 0.0108228831 0.0160688832 0.0140351668 0.1093310000 0.0085430000 0.0416910000 0.0000270000 0.0003550000 0.0419880000 9541056 96830484 1770557440 4.2419342995 4.5160059929 4.8372201920 643 25.6800000000 0.0115261152 0.0108239767 0.0160688832 0.0140326545 0.1504760000 0.0097280000 0.0687500000 0.0003900000 0.0002780000 0.0610710000 9542730 96830484 1769508864 4.2371897697 4.5171103477 4.8403224945 644 25.7200000000 0.0115053328 0.0108250347 0.0160688832 0.0140291779 0.1462600000 0.0078130000 0.0742290000 0.0000250000 0.0004860000 0.0473220000 9544404 96830484 1771180032 4.2327990532 4.5170245171 4.8431720734 645 25.7600000000 0.0115233697 0.0108261174 0.0160688832 0.0140233199 0.1843150000 0.0097810000 0.0608640000 0.0003850000 0.0002890000 0.0797710000 9546078 96830484 1769750528 4.2286481857 4.5189003944 4.8456969261 646 25.8000000000 0.0115037346 0.0108271664 0.0160688832 0.0140176939 0.0953140000 0.0084410000 0.0434890000 0.0000270000 0.0003840000 0.0356170000 9547752 96830484 1771450368 4.2243371010 4.5204591751 4.8485641479 647 25.8400000000 0.0115272049 0.0108282483 0.0160688832 0.0140116281 0.1073020000 0.0105780000 0.0429000000 0.0010490000 0.0002700000 0.0432060000 9549426 96830484 1770242048 4.2194828987 4.5207118988 4.8517127037 648 25.8800000000 0.0114849247 0.0108292617 0.0160688832 0.0140040946 0.0899990000 0.0105320000 0.0362530000 0.0000260000 0.0003650000 0.0357270000 9551100 96830484 1768894464 4.2150840759 4.5226364136 4.8543758392 649 25.9200000000 0.0114542618 0.0108302248 0.0160688832 0.0139963062 0.1391830000 0.0083020000 0.0489540000 0.0005490000 0.0002850000 0.0737740000 9552774 96830484 1767591936 4.2106900215 4.5244235992 4.8570914268 650 25.9600000000 0.0115303490 0.0108313019 0.0160688832 0.0139896331 0.0942680000 0.0084440000 0.0433260000 0.0000310000 0.0010350000 0.0342910000 9554448 96830484 1769123840 4.2064156532 4.5279941559 4.8595676422 651 26.0000000000 0.0115000522 0.0108323291 0.0160688832 0.0139885181 0.1063050000 0.0085340000 0.0424140000 0.0010350000 0.0002780000 0.0413480000 9556122 96830484 1770749952 4.2032089233 4.5298929214 4.8618159294 652 26.0400000000 0.0114816446 0.0108333250 0.0160688832 0.0139853591 0.1076710000 0.0109600000 0.0438210000 0.0000260000 0.0003090000 0.0346230000 9557796 96830484 1769402368 4.1994156837 4.5320367813 4.8637247086 653 26.0800000000 0.0115024606 0.0108343497 0.0160688832 0.0139840322 0.1440830000 0.0084280000 0.0442100000 0.0003810000 0.0002790000 0.0572250000 9559470 96830484 1771036672 4.1946578026 4.5336093903 4.8660392761 654 26.1200000000 0.0114990762 0.0108353661 0.0160688832 0.0139840056 0.0954040000 0.0111780000 0.0444490000 0.0000270000 0.0003170000 0.0320330000 9561144 96830484 1770020864 4.1902060509 4.5347971916 4.8684077263 655 26.1600000000 0.0114678312 0.0108363317 0.0160688832 0.0139797260 0.1097320000 0.0089060000 0.0580050000 0.0002870000 0.0003350000 0.0348360000 9562818 96830484 1768861696 4.1875505447 4.5381989479 4.8700957298 656 26.2000000000 0.0115285562 0.0108373869 0.0160688832 0.0139757117 0.1031160000 0.0085340000 0.0469230000 0.0000300000 0.0003810000 0.0352420000 9564492 96830484 1768271872 4.1776285172 4.5415139198 4.8739166260 657 26.2400000000 0.0114870481 0.0108383758 0.0160688832 0.0139733694 0.1454040000 0.0082340000 0.0468520000 0.0003170000 0.0002770000 0.0613790000 9566166 96830484 1767120896 4.1749038696 4.5418276787 4.8756251335 658 26.2800000000 0.0113951089 0.0108392219 0.0160688832 0.0139663492 0.1336010000 0.0084940000 0.0874640000 0.0000250000 0.0002910000 0.0301480000 9567840 96830484 1766088704 4.1714072227 4.5437116623 4.8772249222 659 26.3200000000 0.0114782983 0.0108401916 0.0160688832 0.0139620315 0.1063980000 0.0085030000 0.0471540000 0.0003090000 0.0002730000 0.0368580000 9569514 96830484 1767718912 4.1680507660 4.5475311279 4.8786063194 660 26.3600000000 0.0115323216 0.0108412403 0.0160688832 0.0139596731 0.1093160000 0.0083280000 0.0585630000 0.0000250000 0.0002850000 0.0311500000 9571188 96830484 1769369600 4.1640768051 4.5485062599 4.8801259995 661 26.4000000000 0.0114388717 0.0108421445 0.0160688832 0.0139580602 0.1260400000 0.0100960000 0.0528750000 0.0002860000 0.0002710000 0.0551900000 9572862 96830484 1768353792 4.1615495682 4.5522885323 4.8808884621 662 26.4400000000 0.0114637520 0.0108430834 0.0160688832 0.0139524227 0.1108530000 0.0084260000 0.0507690000 0.0000270000 0.0002870000 0.0300030000 9574536 96830484 1769877504 4.1589999199 4.5551953316 4.8817024231 663 26.4800000000 0.0112410346 0.0108436837 0.0160688832 0.0139491562 0.1086510000 0.0100900000 0.0480790000 0.0002910000 0.0003530000 0.0400290000 9576210 96830484 1768845312 4.1552448273 4.5547585487 4.8831934929 664 26.5200000000 0.0113055231 0.0108443792 0.0160688832 0.0139479584 0.1464010000 0.0080420000 0.0880520000 0.0000280000 0.0002880000 0.0334420000 9577884 96830484 1770545152 4.1528639793 4.5563516617 4.8841705322 665 26.5600000000 0.0113047520 0.0108450715 0.0160688832 0.0139462095 0.1601040000 0.0102560000 0.0784380000 0.0002920000 0.0003350000 0.0633170000 9579558 96830484 1769250816 4.1495685577 4.5585837364 4.8853096962 666 26.6000000000 0.0112306383 0.0108456504 0.0160688832 0.0139414546 0.0994210000 0.0090000000 0.0544470000 0.0000260000 0.0002900000 0.0281160000 9581232 96830484 1771032576 4.1468491554 4.5597271919 4.8863086700 667 26.6400000000 0.0113337925 0.0108463823 0.0160688832 0.0139364147 0.1060260000 0.0105930000 0.0459770000 0.0000920000 0.0000810000 0.0347460000 9582906 96830484 1769893888 4.1425352097 4.5616612434 4.8873052597 668 26.6800000000 0.0113676824 0.0108471627 0.0160688832 0.0139312035 0.1079150000 0.0101840000 0.0546820000 0.0000290000 0.0003760000 0.0287280000 9584580 96830484 1768755200 4.1384129524 4.5636272430 4.8883628845 669 26.7200000000 0.0112677161 0.0108477913 0.0160688832 0.0139273755 0.1467010000 0.0087580000 0.0681150000 0.0003580000 0.0002780000 0.0488400000 9586254 96830484 1770397696 4.1345705986 4.5653715134 4.8893351555 670 26.7600000000 0.0113633759 0.0108485608 0.0160688832 0.0139208356 0.1110940000 0.0106760000 0.0613080000 0.0000290000 0.0002880000 0.0290610000 9587928 96830484 1769353216 4.1300554276 4.5645532608 4.8905467987 671 26.8000000000 0.0113628227 0.0108493272 0.0160688832 0.0139159087 0.1058840000 0.0093580000 0.0444130000 0.0003120000 0.0002770000 0.0342900000 9589602 96830484 1771036672 4.1267590523 4.5638175011 4.8921136856 672 26.8400000000 0.0112591367 0.0108499371 0.0160688832 0.0139082929 0.1089500000 0.0106690000 0.0541280000 0.0000310000 0.0003120000 0.0284800000 9591276 96830484 1770274816 4.1227087975 4.5637102127 4.8935317993 673 26.8800000000 0.0113228699 0.0108506398 0.0160688832 0.0138991515 0.1190040000 0.0109700000 0.0475260000 0.0003800000 0.0002760000 0.0524980000 9592950 96830484 1768624128 4.1190085411 4.5637822151 4.8948554993 674 26.9200000000 0.0114418054 0.0108515169 0.0160688832 0.0138954780 0.0981400000 0.0090110000 0.0481360000 0.0000260000 0.0003120000 0.0280890000 9594624 96830484 1770164224 4.1147775650 4.5632581711 4.8963971138 675 26.9600000000 0.0113536213 0.0108522608 0.0160688832 0.0138915942 0.1088570000 0.0109400000 0.0533280000 0.0002920000 0.0003380000 0.0333310000 9596298 96830484 1769127936 4.1107492447 4.5631680489 4.8974714279 676 27.0000000000 0.0112358052 0.0108528281 0.0160688832 0.0138839385 0.1424630000 0.0092860000 0.0876350000 0.0000280000 0.0005010000 0.0277180000 9597972 96830484 1770782720 4.1064934731 4.5633478165 4.8983097076 677 27.0400000000 0.0113481898 0.0108535598 0.0160688832 0.0138770937 0.1244410000 0.0106290000 0.0544120000 0.0002890000 0.0002670000 0.0512100000 9599646 96830484 1770020864 4.1015563011 4.5635185242 4.8990755081 678 27.0800000000 0.0113228252 0.0108542520 0.0160688832 0.0138696617 0.0920570000 0.0112680000 0.0511510000 0.0000270000 0.0003490000 0.0215920000 9601320 96830484 1767972864 4.0969796181 4.5631804466 4.9000754356 679 27.1200000000 0.0120716300 0.0108560449 0.0160688832 0.0138617328 0.1071950000 0.0096260000 0.0451480000 0.0003200000 0.0003460000 0.0333950000 9602994 96830484 1767739392 4.0897154808 4.5619835854 4.9011893272 680 27.1600000000 0.0128747467 0.0108590135 0.0160688832 0.0138572239 0.1096230000 0.0092540000 0.0589070000 0.0000280000 0.0002950000 0.0278870000 9604668 96830484 1769242624 4.0835027695 4.5614447594 4.9026803970 681 27.2000000000 0.0129361358 0.0108620636 0.0160688832 0.0138524369 0.1226570000 0.0094120000 0.0542000000 0.0003560000 0.0002660000 0.0508810000 9606342 96830484 1771286528 4.0807771683 4.5611310005 4.9033865929 682 27.2400000000 0.0130469399 0.0108652673 0.0160688832 0.0138475080 0.1152530000 0.0106290000 0.0680270000 0.0000270000 0.0002860000 0.0278070000 9608016 96830484 1770418176 4.0769891739 4.5605640411 4.9041414261 683 27.2800000000 0.0131083969 0.0108685515 0.0160688832 0.0138423161 0.1079300000 0.0114940000 0.0534000000 0.0002880000 0.0002610000 0.0327810000 9609690 96830484 1768480768 4.0742726326 4.5594463348 4.9050745964 684 27.3200000000 0.0131702516 0.0108719166 0.0160688832 0.0138331297 0.1449460000 0.0097830000 0.0856600000 0.0000070000 0.0000600000 0.0273050000 9611364 96830484 1770258432 4.0684137344 4.5599956512 4.9061579704 685 27.3600000000 0.0119131850 0.0108734367 0.0160688832 0.0138259056 0.1244120000 0.0115920000 0.0541210000 0.0003040000 0.0003530000 0.0503260000 9613038 96830484 1768124416 4.0679774284 4.5609645844 4.9070453644 686 27.4000000000 0.0116051501 0.0108745033 0.0160688832 0.0138207193 0.1123790000 0.0098170000 0.0525950000 0.0000300000 0.0013390000 0.0276740000 9614712 96830484 1769861120 4.0646228790 4.5600943565 4.9081864357 687 27.4400000000 0.0114545608 0.0108753476 0.0160688832 0.0138169552 0.1106790000 0.0115270000 0.0544300000 0.0003020000 0.0002750000 0.0324810000 9616386 96830484 1767718912 4.0611634254 4.5607509613 4.9095439911 688 27.4800000000 0.0114142932 0.0108761310 0.0160688832 0.0138140067 0.1067520000 0.0099810000 0.0526540000 0.0000350000 0.0003060000 0.0277340000 9618060 96830484 1769492480 4.0593008995 4.5612549782 4.9106321335 689 27.5200000000 0.0113269128 0.0108767852 0.0160688832 0.0138099080 0.1255000000 0.0106990000 0.0553620000 0.0003050000 0.0003490000 0.0508520000 9619734 96830484 1768628224 4.0555777550 4.5619883537 4.9114122391 690 27.5600000000 0.0113992020 0.0108775424 0.0160688832 0.0138037098 0.0903830000 0.0095620000 0.0517690000 0.0000280000 0.0002920000 0.0208800000 9621408 96830484 1770401792 4.0520839691 4.5629758835 4.9124917984 691 27.6000000000 0.0113097606 0.0108781679 0.0160688832 0.0137980907 0.1113220000 0.0111460000 0.0594330000 0.0003050000 0.0003420000 0.0323900000 9623082 96830484 1769639936 4.0490636826 4.5631160736 4.9134912491 692 27.6400000000 0.0112375496 0.0108786872 0.0160688832 0.0137922803 0.1047330000 0.0095230000 0.0464040000 0.0000300000 0.0003800000 0.0278560000 9624756 96830484 1771274240 4.0457739830 4.5641078949 4.9147191048 693 27.6800000000 0.0112329144 0.0108791983 0.0160688832 0.0137865231 0.1246630000 0.0113220000 0.0544990000 0.0003030000 0.0002810000 0.0502100000 9626430 96830484 1770147840 4.0413622856 4.5634574890 4.9157381058 694 27.7200000000 0.0112125436 0.0108796787 0.0160688832 0.0137791450 0.0950620000 0.0115380000 0.0463690000 0.0001060000 0.0003090000 0.0277430000 9628104 96830484 1768464384 4.0389671326 4.5637254715 4.9169840813 695 27.7600000000 0.0112659745 0.0108802345 0.0160688832 0.0137735331 0.1041770000 0.0098840000 0.0443300000 0.0003910000 0.0002750000 0.0329960000 9629778 96830484 1767624704 4.0361404419 4.5639915466 4.9180526733 696 27.8000000000 0.0113109229 0.0108808533 0.0160688832 0.0137681909 0.1067530000 0.0099600000 0.0466770000 0.0000310000 0.0003110000 0.0278000000 9631452 96830484 1769226240 4.0322809219 4.5625467300 4.9193415642 697 27.8400000000 0.0113927405 0.0108815877 0.0160688832 0.0137648672 0.1160490000 0.0097210000 0.0467810000 0.0003970000 0.0002880000 0.0511090000 9633126 96830484 1771048960 4.0286078453 4.5632448196 4.9203386307 698 27.8800000000 0.0113568678 0.0108822686 0.0160688832 0.0137609379 0.1018390000 0.0113360000 0.0473200000 0.0000290000 0.0003100000 0.0272050000 9634800 96830484 1770004480 4.0259652138 4.5633010864 4.9214134216 699 27.9200000000 0.0113393934 0.0108829226 0.0160688832 0.0137559226 0.1296340000 0.0117570000 0.0751390000 0.0003600000 0.0002730000 0.0322870000 9636474 96830484 1767854080 4.0221786499 4.5640459061 4.9224553108 700 27.9600000000 0.0114988135 0.0108838024 0.0160688832 0.0137537888 0.0886290000 0.0100530000 0.0434950000 0.0000320000 0.0003080000 0.0268110000 9638148 96830484 1769631744 4.0180864334 4.5642242432 4.9235720634 701 28.0000000000 0.0115623074 0.0108847704 0.0160688832 0.0137505030 0.1194520000 0.0105560000 0.0499170000 0.0003930000 0.0002790000 0.0505360000 9639822 96830484 1771286528 4.0149660110 4.5650691986 4.9245123863 702 28.0400000000 0.0115063097 0.0108856557 0.0160688832 0.0137465500 0.0941240000 0.0115390000 0.0527920000 0.0000280000 0.0004190000 0.0211920000 9641496 96830484 1770131456 4.0103697777 4.5671329498 4.9250669479 703 28.0800000000 0.0115230484 0.0108865624 0.0160688832 0.0137421267 0.1072060000 0.0110860000 0.0471890000 0.0002920000 0.0002670000 0.0324070000 9643170 96830484 1769005056 4.0076832771 4.5676403046 4.9262967110 704 28.1200000000 0.0116549954 0.0108876539 0.0160688832 0.0137373160 0.0899330000 0.0095520000 0.0438520000 0.0000290000 0.0003130000 0.0276750000 9644844 96830484 1770799104 4.0046377182 4.5676522255 4.9273872375 705 28.1600000000 0.0116849057 0.0108887848 0.0160688832 0.0137326217 0.1261720000 0.0114380000 0.0432100000 0.0003160000 0.0006650000 0.0541050000 9646518 96830484 1769639936 4.0017113686 4.5674757957 4.9288549423 706 28.2000000000 0.0118231028 0.0108901082 0.0160688832 0.0137274738 0.1087700000 0.0095430000 0.0584840000 0.0000260000 0.0002870000 0.0276260000 9648192 96830484 1771290624 4.0000033379 4.5666990280 4.9300179482 707 28.2400000000 0.0117893396 0.0108913801 0.0160688832 0.0137227905 0.1071770000 0.0114300000 0.0462240000 0.0003120000 0.0003490000 0.0333650000 9649866 96830484 1770291200 3.9957914352 4.5662460327 4.9311704636 708 28.2800000000 0.0118147274 0.0108926843 0.0160688832 0.0137170599 0.1066190000 0.0115300000 0.0434400000 0.0000310000 0.0003200000 0.0278450000 9651540 96830484 1768878080 3.9934492111 4.5657744408 4.9323401451 709 28.3200000000 0.0117753651 0.0108939292 0.0160688832 0.0137099784 0.1281660000 0.0094330000 0.0435980000 0.0003860000 0.0002880000 0.0538370000 9653214 96830484 1770557440 3.9900906086 4.5670976639 4.9333610535 710 28.3600000000 0.0118254917 0.0108952413 0.0160688832 0.0137037009 0.1099640000 0.0112370000 0.0537390000 0.0000270000 0.0003090000 0.0281310000 9654888 96830484 1769750528 3.9860222340 4.5672650337 4.9343376160 711 28.4000000000 0.0117865531 0.0108964949 0.0160688832 0.0136987435 0.1077470000 0.0115130000 0.0459860000 0.0003840000 0.0002800000 0.0329270000 9656562 96830484 1768353792 3.9822893143 4.5669398308 4.9356002808 712 28.4400000000 0.0118161775 0.0108977866 0.0160688832 0.0136923843 0.1064550000 0.0093440000 0.0465910000 0.0000290000 0.0003200000 0.0281800000 9658236 96830484 1770016768 3.9772770405 4.5669898987 4.9365053177 713 28.4800000000 0.0117968181 0.0108990475 0.0160688832 0.0136858540 0.1289680000 0.0109800000 0.0441210000 0.0003190000 0.0005700000 0.0537490000 9659910 96830484 1768628224 3.9731721878 4.5677747726 4.9374847412 714 28.5200000000 0.0118544754 0.0109003856 0.0160688832 0.0136796544 0.1068800000 0.0091510000 0.0462280000 0.0000350000 0.0003780000 0.0283000000 9661584 96830484 1770369024 3.9693453312 4.5670981407 4.9389109612 715 28.5600000000 0.0118270852 0.0109016817 0.0160688832 0.0136719507 0.1091430000 0.0112390000 0.0441220000 0.0003220000 0.0002790000 0.0333110000 9663258 96830484 1769148416 3.9647359848 4.5674276352 4.9401903152 716 28.6000000000 0.0118666030 0.0109030294 0.0160688832 0.0136665876 0.1088220000 0.0094530000 0.0531960000 0.0000290000 0.0002960000 0.0278950000 9664932 96830484 1770905600 3.9602553844 4.5663552284 4.9413433075 717 28.6400000000 0.0119431503 0.0109044800 0.0160688832 0.0136598268 0.1240800000 0.0112010000 0.0534010000 0.0002870000 0.0002620000 0.0508590000 9666606 96830484 1769783296 3.9559392929 4.5667552948 4.9421596527 718 28.6800000000 0.0120346481 0.0109060541 0.0160688832 0.0136535017 0.1078880000 0.0092870000 0.0461240000 0.0000270000 0.0003830000 0.0287990000 9668280 96830484 1771450368 3.9511535168 4.5675897598 4.9429931641 719 28.7200000000 0.0120511139 0.0109076466 0.0160688832 0.0136503427 0.1112720000 0.0110740000 0.0533410000 0.0002930000 0.0003500000 0.0332110000 9669954 96830484 1770401792 3.9469103813 4.5661873817 4.9438695908 720 28.7600000000 0.0120293237 0.0109092045 0.0160688832 0.0136516232 0.1056790000 0.0112340000 0.0458760000 0.0000270000 0.0003810000 0.0284230000 9671628 96830484 1768988672 3.9434835911 4.5664763451 4.9447064400 721 28.8000000000 0.0120722335 0.0109108176 0.0160688832 0.0136480800 0.1274740000 0.0092060000 0.0410690000 0.0002880000 0.0003450000 0.0550350000 9673302 96830484 1770684416 3.9399085045 4.5654449463 4.9459471703 722 28.8400000000 0.0121099884 0.0109124785 0.0160688832 0.0136434028 0.0926590000 0.0110820000 0.0464530000 0.0000280000 0.0003110000 0.0265780000 9674976 96830484 1769877504 3.9341948032 4.5643262863 4.9468569756 723 28.8800000000 0.0122094238 0.0109142723 0.0160688832 0.0136373043 0.0867270000 0.0097860000 0.0350910000 0.0003180000 0.0002820000 0.0330980000 9676650 96830484 1769385984 3.9304323196 4.5646891594 4.9477343559 724 28.9200000000 0.0122450376 0.0109161104 0.0160688832 0.0136304596 0.1086450000 0.0090850000 0.0658940000 0.0000270000 0.0003140000 0.0248440000 9678324 96830484 1768353792 3.9248771667 4.5641026497 4.9484457970 725 28.9600000000 0.0122355707 0.0109179304 0.0160688832 0.0136231956 0.1216040000 0.0094970000 0.0515880000 0.0003220000 0.0002700000 0.0517900000 9679998 96830484 1770131456 3.9212596416 4.5632939339 4.9496884346 726 29.0000000000 0.0122716464 0.0109197950 0.0160688832 0.0136168214 0.1093110000 0.0114520000 0.0496200000 0.0000260000 0.0002870000 0.0290770000 9681672 96830484 1769279488 3.9176628590 4.5634055138 4.9504203796 727 29.0400000000 0.0122434460 0.0109216157 0.0160688832 0.0136127633 0.1081150000 0.0091140000 0.0459730000 0.0003180000 0.0003570000 0.0334700000 9683346 96830484 1771003904 3.9142243862 4.5633397102 4.9512410164 728 29.0800000000 0.0123328753 0.0109235542 0.0160688832 0.0136093366 0.1079730000 0.0110160000 0.0469300000 0.0000290000 0.0003140000 0.0294280000 9685020 96830484 1769910272 3.9117105007 4.5624389648 4.9519948959 729 29.1200000000 0.0122654419 0.0109253949 0.0160688832 0.0136089951 0.1164840000 0.0106770000 0.0440920000 0.0003190000 0.0002730000 0.0528540000 9686694 96830484 1768865792 3.9087831974 4.5623116493 4.9526376724 730 29.1600000000 0.0123030692 0.0109272822 0.0160688832 0.0136067723 0.0999060000 0.0089580000 0.0443310000 0.0000310000 0.0003170000 0.0289220000 9688368 96830484 1770639360 3.9064950943 4.5612630844 4.9535665512 731 29.2000000000 0.0123045091 0.0109291662 0.0160688832 0.0136044261 0.1087100000 0.0109040000 0.0461130000 0.0003920000 0.0002750000 0.0343570000 9690042 96830484 1769762816 3.9015495777 4.5601520538 4.9538340569 732 29.2400000000 0.0122652296 0.0109309914 0.0160688832 0.0136010425 0.1063500000 0.0109310000 0.0435660000 0.0000280000 0.0003710000 0.0290100000 9691716 96830484 1768390656 3.8983168602 4.5603218079 4.9542155266 733 29.2800000000 0.0122507988 0.0109327920 0.0160688832 0.0135965975 0.1288900000 0.0091200000 0.0433290000 0.0003240000 0.0002670000 0.0555000000 9693390 96830484 1770033152 3.8958303928 4.5587067604 4.9549093246 734 29.3200000000 0.0122513408 0.0109345884 0.0160688832 0.0135899815 0.1092510000 0.0107940000 0.0533410000 0.0000280000 0.0002990000 0.0295940000 9695064 96830484 1768882176 3.8932003975 4.5581502914 4.9552850723 735 29.3600000000 0.0122637516 0.0109363968 0.0160688832 0.0135827746 0.1091990000 0.0091530000 0.0538420000 0.0003950000 0.0002760000 0.0352400000 9696738 96830484 1770536960 3.8896389008 4.5579485893 4.9554224014 736 29.4000000000 0.0123324832 0.0109382936 0.0160688832 0.0135773645 0.1055260000 0.0109330000 0.0427420000 0.0000300000 0.0009570000 0.0295480000 9698412 96830484 1769533440 3.8867099285 4.5565271378 4.9555644989 737 29.4400000000 0.0122110406 0.0109400205 0.0160688832 0.0135721179 0.1174070000 0.0090730000 0.0463650000 0.0003300000 0.0003490000 0.0531860000 9700086 96830484 1771204608 3.8839514256 4.5546088219 4.9557037354 738 29.4800000000 0.0123690302 0.0109419569 0.0160688832 0.0135651331 0.1018050000 0.0106810000 0.0514430000 0.0000270000 0.0002940000 0.0297110000 9701760 96830484 1770409984 3.8826889992 4.5532174110 4.9563260078 739 29.5200000000 0.0123672998 0.0109438856 0.0160688832 0.0135593082 0.1094740000 0.0108090000 0.0577900000 0.0003780000 0.0002960000 0.0313910000 9703434 96830484 1769283584 3.8813364506 4.5511703491 4.9567413330 740 29.5600000000 0.0123291034 0.0109457575 0.0160688832 0.0135565419 0.1054150000 0.0091140000 0.0535540000 0.0000270000 0.0003680000 0.0294840000 9705108 96830484 1771040768 3.8800041676 4.5494670868 4.9568719864 741 29.6000000000 0.0123160100 0.0109476067 0.0160688832 0.0135546950 0.1238150000 0.0110400000 0.0506200000 0.0004710000 0.0002790000 0.0530570000 9706782 96830484 1769902080 3.8778247833 4.5481472015 4.9573125839 742 29.6400000000 0.0123709776 0.0109495250 0.0160688832 0.0135508756 0.0919040000 0.0106050000 0.0349970000 0.0000270000 0.0003650000 0.0316830000 9708456 96830484 1768779776 3.8762655258 4.5469293594 4.9577760696 743 29.6800000000 0.0122834593 0.0109513204 0.0160688832 0.0135483357 0.1279870000 0.0090270000 0.0673940000 0.0004760000 0.0002810000 0.0385230000 9710130 96830484 1767583744 3.8749101162 4.5453510284 4.9578690529 744 29.7200000000 0.0122835757 0.0109531110 0.0160688832 0.0135493027 0.0901130000 0.0086590000 0.0444820000 0.0000250000 0.0002850000 0.0279030000 9711804 96830484 1769406464 3.8717823029 4.5415768623 4.9586114883 745 29.7600000000 0.0122528356 0.0109548556 0.0160688832 0.0135422529 0.1214250000 0.0085100000 0.0497760000 0.0002930000 0.0003590000 0.0538010000 9713478 96830484 1771139072 3.8713350296 4.5392484665 4.9591612816 746 29.8000000000 0.0123649556 0.0109567458 0.0160688832 0.0135347118 0.1340430000 0.0108690000 0.0854920000 0.0000280000 0.0007000000 0.0282520000 9715152 96830484 1770029056 3.8697254658 4.5387353897 4.9595041275 747 29.8400000000 0.0123852678 0.0109586582 0.0160688832 0.0135270047 0.1242540000 0.0109910000 0.0580370000 0.0002900000 0.0003320000 0.0355240000 9716826 96830484 1768505344 3.8685398102 4.5371012688 4.9600501060 748 29.8800000000 0.0123592755 0.0109605307 0.0160688832 0.0135180097 0.1068440000 0.0089110000 0.0439340000 0.0000280000 0.0003860000 0.0301070000 9718500 96830484 1770311680 3.8677797318 4.5356259346 4.9604029655 749 29.9200000000 0.0124484776 0.0109625172 0.0160688832 0.0135091418 0.1247400000 0.0106060000 0.0509300000 0.0002960000 0.0002670000 0.0539260000 9720174 96830484 1769144320 3.8660869598 4.5344500542 4.9607834816 750 29.9600000000 0.0124503830 0.0109645011 0.0160688832 0.0135001991 0.1117600000 0.0089950000 0.0496030000 0.0000280000 0.0003110000 0.0307880000 9721848 96830484 1770901504 3.8648588657 4.5339903831 4.9611086845 751 30.0000000000 0.0124700693 0.0109665058 0.0160688832 0.0134914738 0.1101390000 0.0106500000 0.0467360000 0.0003160000 0.0002800000 0.0359650000 9723522 96830484 1770029056 3.8650138378 4.5306215286 4.9618606567 752 30.0400000000 0.0124667129 0.0109685008 0.0160688832 0.0134828537 0.1074370000 0.0108070000 0.0439470000 0.0000250000 0.0003950000 0.0309990000 9725196 96830484 1768763392 3.8646850586 4.5288929939 4.9626598358 753 30.0800000000 0.0125287492 0.0109705728 0.0160688832 0.0134762912 0.1185620000 0.0088770000 0.0464030000 0.0003140000 0.0003550000 0.0541250000 9726870 96830484 1770311680 3.8635659218 4.5278310776 4.9634461403 754 30.1200000000 0.0125440005 0.0109726596 0.0160688832 0.0134699136 0.0998420000 0.0106010000 0.0451070000 0.0000260000 0.0003170000 0.0307780000 9728544 96830484 1769263104 3.8643782139 4.5260462761 4.9644103050 755 30.1600000000 0.0125425961 0.0109747390 0.0160688832 0.0134636027 0.1067550000 0.0091860000 0.0441040000 0.0003190000 0.0002810000 0.0359500000 9730218 96830484 1771040768 3.8644754887 4.5246796608 4.9655756950 756 30.2000000000 0.0125447260 0.0109768157 0.0160688832 0.0134555045 0.1305250000 0.0108700000 0.0801070000 0.0000280000 0.0002810000 0.0305710000 9731892 96830484 1769902080 3.8640472889 4.5236849785 4.9664120674 757 30.2400000000 0.0125191929 0.0109788532 0.0160688832 0.0134484580 0.1254620000 0.0109080000 0.0511940000 0.0002910000 0.0002700000 0.0541710000 9733566 96830484 1768505344 3.8643417358 4.5219335556 4.9675331116 758 30.2800000000 0.0125112524 0.0109808748 0.0160688832 0.0134434950 0.1032970000 0.0091440000 0.0431670000 0.0000270000 0.0010520000 0.0307920000 9735240 96830484 1770405888 3.8640875816 4.5231785774 4.9686412811 759 30.3200000000 0.0124967098 0.0109828719 0.0160688832 0.0134390962 0.1088450000 0.0107070000 0.0455010000 0.0003140000 0.0003490000 0.0362130000 9736914 96830484 1768853504 3.8646829128 4.5220465660 4.9698381424 760 30.3600000000 0.0125968009 0.0109849955 0.0160688832 0.0134381735 0.1074160000 0.0090910000 0.0496870000 0.0000280000 0.0002830000 0.0308080000 9738588 96830484 1770659840 3.8661518097 4.5198326111 4.9710640907 761 30.4000000000 0.0127398819 0.0109873016 0.0160688832 0.0134328916 0.1190860000 0.0108440000 0.0437440000 0.0003190000 0.0002800000 0.0552110000 9740262 96830484 1769648128 3.8665735722 4.5197119713 4.9726281166 762 30.4400000000 0.0126965903 0.0109895447 0.0160688832 0.0134242701 0.1390530000 0.0104930000 0.0883980000 0.0000260000 0.0003810000 0.0303470000 9741936 96830484 1768382464 3.8673131466 4.5190472603 4.9740500450 763 30.4800000000 0.0127740214 0.0109918835 0.0160688832 0.0134155639 0.0892020000 0.0088250000 0.0356660000 0.0003040000 0.0003490000 0.0353180000 9743610 96830484 1770024960 3.8691506386 4.5165829659 4.9757485390 764 30.5200000000 0.0127937142 0.0109942419 0.0160688832 0.0134079537 0.1057380000 0.0099590000 0.0484210000 0.0000330000 0.0003130000 0.0348510000 9745284 96830484 1768742912 3.8717272282 4.5147871971 4.9773259163 765 30.5600000000 0.0128180394 0.0109966259 0.0160688832 0.0134007503 0.1379960000 0.0081400000 0.0593730000 0.0003910000 0.0002870000 0.0610370000 9746958 96830484 1770520576 3.8740012646 4.5133762360 4.9791674614 766 30.6000000000 0.0128356619 0.0109990268 0.0160688832 0.0133979114 0.1151320000 0.0100480000 0.0459890000 0.0000270000 0.0002880000 0.0355610000 9748632 96830484 1769758720 3.8760938644 4.5117254257 4.9807553291 767 30.6400000000 0.0130201727 0.0110016619 0.0160688832 0.0134022915 0.1287220000 0.0107760000 0.0604900000 0.0003000000 0.0004690000 0.0363030000 9750306 96830484 1768345600 3.8790676594 4.5088553429 4.9825716019 768 30.6800000000 0.0130980471 0.0110043916 0.0160688832 0.0134094500 0.0921520000 0.0087710000 0.0443370000 0.0000290000 0.0003150000 0.0292970000 9751980 96830484 1770151936 3.8822808266 4.5080695152 4.9844150543 769 30.7200000000 0.0131314294 0.0110071576 0.0160688832 0.0134630540 0.1212430000 0.0107270000 0.0442260000 0.0009330000 0.0003010000 0.0562500000 9753654 96830484 1768890368 3.8890044689 4.5058650970 4.9881529808 770 30.7600000000 0.0132118808 0.0110100208 0.0160688832 0.0134918400 0.0921710000 0.0087930000 0.0363170000 0.0000280000 0.0003610000 0.0332480000 9755328 96830484 1770409984 3.8932723999 4.5012326241 4.9896831512 771 30.8000000000 0.0133119561 0.0110130065 0.0160688832 0.0135129588 0.1245630000 0.0100660000 0.0689130000 0.0002850000 0.0003390000 0.0338130000 9757002 96830484 1769140224 3.8968596458 4.4990081787 4.9910292625 772 30.8400000000 0.0133692902 0.0110160587 0.0160688832 0.0135342479 0.1083890000 0.0091470000 0.0511360000 0.0000290000 0.0003050000 0.0371940000 9758676 96830484 1770823680 3.8990910053 4.4979434013 4.9919772148 773 30.8800000000 0.0134190666 0.0110191673 0.0160688832 0.0135576920 0.1449900000 0.0098980000 0.0604790000 0.0003230000 0.0002700000 0.0652490000 9760350 96830484 1769648128 3.9029865265 4.4947409630 4.9936461449 774 30.9200000000 0.0134178465 0.0110222664 0.0160688832 0.0135778734 0.1091830000 0.0082820000 0.0467790000 0.0000280000 0.0003440000 0.0360060000 9762024 96830484 1771311104 3.9066965580 4.4909014702 4.9948372841 775 30.9600000000 0.0134787820 0.0110254361 0.0160688832 0.0135967419 0.1288370000 0.0097860000 0.0626590000 0.0003290000 0.0002820000 0.0405150000 9763698 96830484 1770266624 3.9098629951 4.4889693260 4.9958510399 776 31.0000000000 0.0135807432 0.0110287290 0.0160688832 0.0136187836 0.0897470000 0.0097270000 0.0410170000 0.0000110000 0.0001110000 0.0300090000 9765372 96830484 1769267200 3.9139916897 4.4862833023 4.9975275993 777 31.0400000000 0.0134836277 0.0110318885 0.0160688832 0.0136297015 0.1220220000 0.0090230000 0.0473530000 0.0005520000 0.0002850000 0.0557090000 9767046 96830484 1767870464 3.9174468517 4.4841380119 4.9991044998 778 31.0800000000 0.0137185138 0.0110353417 0.0160688832 0.0136353012 0.1080890000 0.0080400000 0.0454950000 0.0000290000 0.0003190000 0.0321160000 9768720 96830484 1769402368 3.9203650951 4.4807662964 5.0006804466 779 31.1200000000 0.0134724844 0.0110384703 0.0160688832 0.0136343499 0.1096120000 0.0096460000 0.0445910000 0.0003140000 0.0003520000 0.0375160000 9770394 96830484 1768361984 3.9237196445 4.4771347046 5.0027613640 780 31.1600000000 0.0136739425 0.0110418491 0.0160688832 0.0136309432 0.1068470000 0.0082900000 0.0444350000 0.0000250000 0.0003870000 0.0319430000 9772068 96830484 1770012672 3.9265503883 4.4744381905 5.0046839714 781 31.2000000000 0.0137255583 0.0110452853 0.0160688832 0.0136262762 0.1227620000 0.0098910000 0.0471020000 0.0003160000 0.0003500000 0.0560910000 9773742 96830484 1769033728 3.9286172390 4.4707803726 5.0063662529 782 31.2400000000 0.0136540681 0.0110486214 0.0160688832 0.0136230462 0.0971220000 0.0083570000 0.0429650000 0.0000260000 0.0046520000 0.0322150000 9775416 96830484 1770659840 3.9317319393 4.4666452408 5.0086836815 783 31.2800000000 0.0136445481 0.0110519367 0.0160688832 0.0136180543 0.1056190000 0.0100290000 0.0441900000 0.0003900000 0.0002790000 0.0376570000 9777090 96830484 1769631744 3.9342803955 4.4625735283 5.0107307434 784 31.3200000000 0.0135149024 0.0110550783 0.0160688832 0.0136134056 0.1056560000 0.0082230000 0.0434880000 0.0000280000 0.0010570000 0.0319790000 9778764 96830484 1771184128 3.9366533756 4.4574356079 5.0126924515 785 31.3600000000 0.0135817556 0.0110582970 0.0160688832 0.0136081933 0.1271060000 0.0100860000 0.0512180000 0.0002950000 0.0005040000 0.0559190000 9780438 96830484 1770168320 3.9385726452 4.4530115128 5.0144596100 786 31.4000000000 0.0136602931 0.0110616074 0.0160688832 0.0136013762 0.1100500000 0.0100330000 0.0520470000 0.0000250000 0.0002880000 0.0319640000 9782112 96830484 1768632320 3.9401750565 4.4495782852 5.0159187317 787 31.4400000000 0.0137402890 0.0110650111 0.0160688832 0.0135940466 0.1085670000 0.0085450000 0.0479530000 0.0003830000 0.0006940000 0.0371120000 9783786 96830484 1770422272 3.9416482449 4.4433026314 5.0173816681 788 31.4800000000 0.0137139941 0.0110683727 0.0160688832 0.0135907719 0.1067320000 0.0101470000 0.0443590000 0.0000260000 0.0003170000 0.0324400000 9785460 96830484 1769377792 3.9437732697 4.4384322166 5.0193691254 789 31.5200000000 0.0135706058 0.0110715441 0.0160688832 0.0135894281 0.1213570000 0.0084050000 0.0468640000 0.0003820000 0.0002820000 0.0564540000 9787134 96830484 1770930176 3.9452221394 4.4336709976 5.0210061073 790 31.5600000000 0.0136035681 0.0110747492 0.0160688832 0.0135883714 0.0979090000 0.0106170000 0.0466440000 0.0000310000 0.0003120000 0.0311210000 9788808 96830484 1769521152 3.9466328621 4.4269523621 5.0227160454 791 31.6000000000 0.0135588124 0.0110778896 0.0160688832 0.0136131141 0.1076500000 0.0082740000 0.0461470000 0.0003880000 0.0002820000 0.0436190000 9790482 96830484 1768493056 3.9478380680 4.4181799889 5.0254931450 792 31.6400000000 0.0136950035 0.0110811941 0.0160688832 0.0136105067 0.1074500000 0.0083980000 0.0530170000 0.0000290000 0.0002900000 0.0366420000 9792156 96830484 1766961152 3.9483702183 4.4141292572 5.0274825096 793 31.6800000000 0.0134220244 0.0110841459 0.0160688832 0.0136067039 0.1221580000 0.0082010000 0.0467710000 0.0003900000 0.0002850000 0.0572890000 9793830 96830484 1765969920 3.9492461681 4.4072179794 5.0293836594 794 31.7200000000 0.0135388756 0.0110872375 0.0160688832 0.0136017061 0.0916030000 0.0079000000 0.0485620000 0.0000300000 0.0003260000 0.0256700000 9795504 96830484 1765343232 3.9494588375 4.4059576988 5.0309896469 795 31.7600000000 0.0134024872 0.0110901498 0.0160688832 0.0135966620 0.1000770000 0.0082290000 0.0505730000 0.0003230000 0.0002930000 0.0313110000 9797178 96830484 1765482496 3.9492318630 4.4043731689 5.0325703621 796 31.8000000000 0.0133414231 0.0110929780 0.0160688832 0.0135936496 0.1116280000 0.0085310000 0.0491870000 0.0000270000 0.0003120000 0.0320810000 9798852 96830484 1765335040 3.9496510029 4.3990421295 5.0347719193 797 31.8400000000 0.0131465038 0.0110955546 0.0160688832 0.0135942859 0.1246910000 0.0080810000 0.0495410000 0.0011220000 0.0002840000 0.0564700000 9800526 96830484 1765466112 3.9497411251 4.3930773735 5.0373363495 798 31.8800000000 0.0130531406 0.0110980077 0.0160688832 0.0136617093 0.0935360000 0.0083640000 0.0381650000 0.0000280000 0.0002890000 0.0344020000 9802200 96830484 1767075840 3.9510548115 4.3748669624 5.0435605049 799 31.9200000000 0.0130413091 0.0111004399 0.0160688832 0.0136767053 0.1246690000 0.0076360000 0.0645360000 0.0003570000 0.0002780000 0.0387980000 9803874 96830484 1768726528 3.9512732029 4.3665370941 5.0462298393 800 31.9600000000 0.0129075022 0.0111026987 0.0160688832 0.0136829503 0.1097460000 0.0083600000 0.0602990000 0.0000260000 0.0002850000 0.0317400000 9805548 96830484 1770504192 3.9507412910 4.3620834351 5.0484719276 801 32.0000000000 0.0128262145 0.0111048504 0.0160688832 0.0136776405 0.1451010000 0.0100450000 0.0544310000 0.0002980000 0.0002670000 0.0604060000 9807222 96830484 1769521152 3.9503674507 4.3580698967 5.0514521599 802 32.0400000000 0.0128492527 0.0111070255 0.0160688832 0.0136691903 0.1093190000 0.0083820000 0.0543690000 0.0000300000 0.0002910000 0.0320990000 9808896 96830484 1771167744 3.9493126869 4.3501243591 5.0540280342 803 32.0800000000 0.0129326303 0.0111092989 0.0160688832 0.0136608693 0.1095870000 0.0101550000 0.0468540000 0.0003930000 0.0002810000 0.0402260000 9810570 96830484 1770029056 3.9486422539 4.3408703804 5.0571389198 804 32.1199999990 0.0129997348 0.0111116502 0.0160688832 0.0136549986 0.1275520000 0.0101800000 0.0708700000 0.0000300000 0.0003570000 0.0336020000 9812244 96830484 1769017344 3.9470112324 4.3258004189 5.0639104843 805 32.1600000000 0.0139369322 0.0111151599 0.0160688832 0.0136475933 0.1447370000 0.0084520000 0.0513630000 0.0003350000 0.0003550000 0.0611360000 9813918 96830484 1770786816 3.9460978508 4.3226604462 5.0670170784 806 32.2000000000 0.0139642591 0.0111186948 0.0160688832 0.0136391242 0.1094960000 0.0102260000 0.0545390000 0.0000260000 0.0003200000 0.0324330000 9815592 96830484 1769631744 3.9445466995 4.3174571991 5.0703191757 807 32.2400000000 0.0135221826 0.0111216731 0.0160688832 0.0136311293 0.1268610000 0.0085550000 0.0620060000 0.0002950000 0.0003510000 0.0396200000 9817266 96830484 1771266048 3.9431886673 4.3085799217 5.0738329887 808 32.2800000000 0.0140198907 0.0111252600 0.0160688832 0.0136233781 0.1267010000 0.0103580000 0.0619020000 0.0000270000 0.0003480000 0.0323630000 9818940 96830484 1770168320 3.9413788319 4.3030366898 5.0774698257 809 32.3200000000 0.0140493782 0.0111288745 0.0160688832 0.0136153609 0.1488340000 0.0105070000 0.0598830000 0.0003460000 0.0002700000 0.0598170000 9820614 96830484 1768763392 3.9403283596 4.2892775536 5.0822243690 810 32.3600000000 0.0154465269 0.0111342049 0.0160688832 0.0136071350 0.1268500000 0.0083130000 0.0619130000 0.0000290000 0.0005860000 0.0338290000 9822288 96830484 1770422272 3.9393055439 4.2789373398 5.0864386559 811 32.4000000000 0.0158871263 0.0111400655 0.0160688832 0.0135995698 0.1117620000 0.0103460000 0.0539110000 0.0003080000 0.0003410000 0.0374640000 9823962 96830484 1769267200 3.9372720718 4.2759294510 5.0902276039 812 32.4399999990 0.0163439885 0.0111464742 0.0163439885 0.0135932827 0.0886230000 0.0083960000 0.0385460000 0.0000270000 0.0003520000 0.0319000000 9825636 96830484 1770946560 3.9354379177 4.2699699402 5.0945496559 813 32.4800000000 0.0164670497 0.0111530186 0.0164670497 0.0135861090 0.1777420000 0.0099180000 0.1019540000 0.0002960000 0.0003500000 0.0556670000 9827310 96830484 1770029056 3.9340138435 4.2605457306 5.0993723869 814 32.5200000000 0.0163459070 0.0111593981 0.0164670497 0.0135782542 0.1376200000 0.0100580000 0.0873340000 0.0000310000 0.0002830000 0.0303010000 9828984 96830484 1768472576 3.9329285622 4.2492752075 5.1043634415 815 32.5600000000 0.0170129891 0.0111665804 0.0170129891 0.0135711181 0.1060740000 0.0084860000 0.0468950000 0.0003210000 0.0002770000 0.0370250000 9830658 96830484 1770160128 3.9317350388 4.2401194572 5.1092081070 816 32.6000000000 0.0168655068 0.0111735644 0.0170129891 0.0135630983 0.1086090000 0.0099040000 0.0559070000 0.0000270000 0.0002890000 0.0316060000 9832332 96830484 1768988672 3.9305059910 4.2329258919 5.1143050194 817 32.6400000000 0.0159709454 0.0111794363 0.0170129891 0.0135574226 0.1261540000 0.0084580000 0.0543130000 0.0002890000 0.0002650000 0.0533830000 9834006 96830484 1770795008 3.9296407700 4.2191047668 5.1211762428 818 32.6800000000 0.0165133104 0.0111859569 0.0170129891 0.0135491403 0.1481080000 0.0104740000 0.0889510000 0.0000260000 0.0003570000 0.0306300000 9835680 96830484 1769639936 3.9286811352 4.2032346725 5.1277718544 819 32.7200000000 0.0172618069 0.0111933756 0.0172618069 0.0135421446 0.1096910000 0.0084580000 0.0536470000 0.0003530000 0.0002620000 0.0367420000 9837354 96830484 1771413504 3.9271280766 4.1936841011 5.1327347755 820 32.7599999990 0.0167269371 0.0112001238 0.0172618069 0.0135339510 0.1467180000 0.0100370000 0.0895190000 0.0000280000 0.0003500000 0.0311500000 9839028 96830484 1770274816 3.9254331589 4.1869869232 5.1369471550 821 32.7999999990 0.0166794378 0.0112067978 0.0172618069 0.0135258928 0.1629880000 0.0105380000 0.0651190000 0.0003560000 0.0002720000 0.0505150000 9840702 96830484 1768861696 3.9245731831 4.1783471107 5.1417150497 822 32.8400000000 0.0166974328 0.0112134774 0.0172618069 0.0135188085 0.0948940000 0.0090700000 0.0514730000 0.0000260000 0.0003490000 0.0244020000 9842376 96830484 1770541056 3.9246060848 4.1666717529 5.1471614838 823 32.8800000000 0.0165950879 0.0112200164 0.0172618069 0.0135124482 0.1071350000 0.0102540000 0.0474190000 0.0004420000 0.0002760000 0.0362970000 9844050 96830484 1769766912 3.9246792793 4.1545982361 5.1527380943 824 32.9200000000 0.0163663942 0.0112262620 0.0172618069 0.0135050768 0.1067860000 0.0083740000 0.0516090000 0.0000360000 0.0003830000 0.0307640000 9845724 96830484 1771450368 3.9248669147 4.1434826851 5.1582913399 825 32.9600000000 0.0156677384 0.0112316456 0.0172618069 0.0134973828 0.1365330000 0.0101280000 0.0613710000 0.0003820000 0.0002780000 0.0548630000 9847398 96830484 1770274816 3.9245367050 4.1331338882 5.1629452705 826 33.0000000000 0.0151905436 0.0112364385 0.0172618069 0.0134909542 0.1405940000 0.0100180000 0.0887850000 0.0000240000 0.0003490000 0.0305300000 9849072 96830484 1769259008 3.9244017601 4.1239066124 5.1677932739 827 33.0400000000 0.0153158950 0.0112413713 0.0172618069 0.0134837859 0.1062870000 0.0085500000 0.0443880000 0.0003860000 0.0002780000 0.0375320000 9850746 96830484 1770921984 3.9244086742 4.1139597893 5.1722984314 828 33.0800000000 0.0151920933 0.0112461427 0.0172618069 0.0134774138 0.1068190000 0.0106200000 0.0441880000 0.0000260000 0.0003830000 0.0308220000 9852420 96830484 1769766912 3.9243295193 4.1061463356 5.1758933067 829 33.1199999990 0.0150047839 0.0112506766 0.0172618069 0.0134744567 0.1255290000 0.0099600000 0.0515790000 0.0003940000 0.0002800000 0.0537210000 9854094 96830484 1768464384 3.9244999886 4.0950293541 5.1800951958 830 33.1600000000 0.0149624739 0.0112551487 0.0172618069 0.0134706743 0.0928020000 0.0082610000 0.0433380000 0.0000260000 0.0010530000 0.0306260000 9855768 96830484 1770160128 3.9249663353 4.0817942619 5.1850738525 831 33.2000000000 0.0138879977 0.0112583170 0.0172618069 0.0134646161 0.1069990000 0.0099880000 0.0469650000 0.0003150000 0.0003630000 0.0360820000 9857442 96830484 1768644608 3.9255044460 4.0691266060 5.1892971992 832 33.2400000000 0.0147587787 0.0112625243 0.0172618069 0.0134607460 0.1078850000 0.0084040000 0.0549470000 0.0000260000 0.0002820000 0.0306750000 9859116 96830484 1770385408 3.9253723621 4.0615320206 5.1922249794 833 33.2800000000 0.0148262829 0.0112668025 0.0172618069 0.0134559261 0.1263470000 0.0101950000 0.0543600000 0.0002870000 0.0002620000 0.0516690000 9860790 96830484 1769512960 3.9257624149 4.0516953468 5.1957206726 834 33.3200000000 0.0146563239 0.0112708667 0.0172618069 0.0134484765 0.1074460000 0.0082740000 0.0464580000 0.0000270000 0.0003160000 0.0300200000 9862464 96830484 1771286528 3.9260818958 4.0424637794 5.1985931396 835 33.3600000000 0.0145551758 0.0112748000 0.0172618069 0.0134408867 0.1094840000 0.0100780000 0.0470680000 0.0003850000 0.0002770000 0.0356500000 9864138 96830484 1770274816 3.9270355701 4.0351486206 5.2009711266 836 33.4000000000 0.0144671518 0.0112786186 0.0172618069 0.0134372600 0.1084200000 0.0101740000 0.0544720000 0.0000290000 0.0003040000 0.0298020000 9865812 96830484 1768767488 3.9286670685 4.0267348289 5.2040605545 837 33.4399999990 0.0148589555 0.0112828961 0.0172618069 0.0134359826 0.1420170000 0.0085580000 0.0626100000 0.0003040000 0.0002720000 0.0489240000 9867486 96830484 1770496000 3.9296610355 4.0163540840 5.2073917389 838 33.4800000000 0.0148532810 0.0112871567 0.0172618069 0.0134312851 0.1094460000 0.0099360000 0.0537570000 0.0000340000 0.0003110000 0.0297020000 9869160 96830484 1769639936 3.9305775166 4.0062565804 5.2101202011 839 33.5200000000 0.0146070486 0.0112911137 0.0172618069 0.0134235462 0.1083370000 0.0097860000 0.0476890000 0.0005130000 0.0002780000 0.0354700000 9870834 96830484 1768226816 3.9313368797 3.9974851608 5.2121224403 840 33.5600000000 0.0148220202 0.0112953172 0.0172618069 0.0134159322 0.0884650000 0.0082700000 0.0363890000 0.0000270000 0.0002900000 0.0316630000 9872508 96830484 1769906176 3.9325942993 3.9913909435 5.2135601044 841 33.6000000000 0.0144760441 0.0112990992 0.0172618069 0.0134129209 0.1727410000 0.0095240000 0.0936070000 0.0002900000 0.0003410000 0.0591500000 9874182 96830484 1768501248 3.9338755608 3.9785103798 5.2169303894 842 33.6400000000 0.0144068114 0.0113027901 0.0172618069 0.0134054692 0.1229090000 0.0080720000 0.0732780000 0.0000260000 0.0003520000 0.0301230000 9875856 96830484 1770242048 3.9354987144 3.9652910233 5.2209134102 843 33.6800000000 0.0143602239 0.0113064170 0.0172618069 0.0133987832 0.1072300000 0.0102030000 0.0449880000 0.0003150000 0.0003470000 0.0357170000 9877530 96830484 1769148416 3.9360682964 3.9593298435 5.2213144302 844 33.7200000000 0.0138696423 0.0113094540 0.0172618069 0.0133974837 0.1082590000 0.0084700000 0.0521450000 0.0000270000 0.0023050000 0.0303300000 9879204 96830484 1770749952 3.9374341965 3.9519581795 5.2222666740 845 33.7599999990 0.0137566216 0.0113123500 0.0172618069 0.0134010799 0.1201850000 0.0102570000 0.0474910000 0.0003850000 0.0002810000 0.0517720000 9880878 96830484 1769783296 3.9380388260 3.9410862923 5.2239823341 846 33.7999999990 0.0135268988 0.0113149677 0.0172618069 0.0133987636 0.1133680000 0.0086660000 0.0514200000 0.0000290000 0.0002860000 0.0300990000 9882552 96830484 1771450368 3.9392819405 3.9356465340 5.2245392799 847 33.8400000000 0.0135018416 0.0113175496 0.0172618069 0.0133990172 0.1092940000 0.0100710000 0.0464210000 0.0003190000 0.0002750000 0.0350550000 9884226 96830484 1770274816 3.9398107529 3.9304451942 5.2246088982 848 33.8800000000 0.0134120630 0.0113200195 0.0172618069 0.0133960835 0.1068360000 0.0103020000 0.0452680000 0.0000280000 0.0003780000 0.0299390000 9885900 96830484 1768878080 3.9407944679 3.9187157154 5.2275199890 849 33.9200000000 0.0134349708 0.0113225107 0.0172618069 0.0133890492 0.1160070000 0.0083620000 0.0453710000 0.0003220000 0.0002790000 0.0517640000 9887574 96830484 1770557440 3.9401683807 3.9114167690 5.2282633781 850 33.9600000000 0.0131110242 0.0113246148 0.0172618069 0.0133831505 0.1019300000 0.0102430000 0.0463210000 0.0000310000 0.0003750000 0.0297910000 9889248 96830484 1769385984 3.9390294552 3.9072885513 5.2272486687 851 34.0000000000 0.0129520465 0.0113265272 0.0172618069 0.0133768746 0.1067030000 0.0083480000 0.0448520000 0.0003170000 0.0002840000 0.0353800000 9890922 96830484 1771175936 3.9382131100 3.9000949860 5.2277207375 852 34.0400000000 0.0128104622 0.0113282689 0.0172618069 0.0133698536 0.1075660000 0.0101480000 0.0472940000 0.0000280000 0.0003160000 0.0295000000 9892596 96830484 1770020864 3.9376258850 3.8954033852 5.2272658348 853 34.0800000000 0.0127178412 0.0113298979 0.0172618069 0.0133673242 0.1193530000 0.0100090000 0.0473440000 0.0003950000 0.0002670000 0.0515290000 9894270 96830484 1768718336 3.9374089241 3.8909609318 5.2268018723 854 34.1199999990 0.0126805929 0.0113314795 0.0172618069 0.0133671303 0.0975120000 0.0082360000 0.0440200000 0.0000260000 0.0009380000 0.0290780000 9895944 96830484 1770303488 3.9371242523 3.8834121227 5.2271418571 855 34.1600000000 0.0127537092 0.0113331429 0.0172618069 0.0133608011 0.1076160000 0.0100210000 0.0451560000 0.0003810000 0.0002780000 0.0343080000 9897618 96830484 1769275392 3.9375517368 3.8783221245 5.2275600433 856 34.2000000000 0.0126240579 0.0113346510 0.0172618069 0.0133545975 0.1060180000 0.0083820000 0.0444350000 0.0000270000 0.0003160000 0.0298770000 9899292 96830484 1770921984 3.9379067421 3.8764052391 5.2263493538 857 34.2400000000 0.0125110960 0.0113360238 0.0172618069 0.0133522899 0.1193520000 0.0102400000 0.0476200000 0.0002930000 0.0002670000 0.0511470000 9900966 96830484 1769783296 3.9389214516 3.8740310669 5.2252550125 858 34.2800000000 0.0124100074 0.0113372755 0.0172618069 0.0133533680 0.0986150000 0.0098900000 0.0436990000 0.0000270000 0.0010950000 0.0292250000 9902640 96830484 1768353792 3.9401249886 3.8707432747 5.2245793343 859 34.3200000000 0.0124451704 0.0113385653 0.0172618069 0.0133563438 0.1067260000 0.0083580000 0.0442540000 0.0003150000 0.0003500000 0.0347830000 9904314 96830484 1770160128 3.9402117729 3.8687484264 5.2227616310 860 34.3600000000 0.0124134878 0.0113398152 0.0172618069 0.0133548716 0.1102330000 0.0101030000 0.0449910000 0.0000300000 0.0003870000 0.0291520000 9905988 96830484 1768644608 3.9411642551 3.8663439751 5.2214875221 861 34.4000000000 0.0125537524 0.0113412251 0.0172618069 0.0133516993 0.1440610000 0.0128830000 0.0648490000 0.0002960000 0.0006960000 0.0553440000 9907662 96830484 1770401792 3.9431984425 3.8653059006 5.2208271027 862 34.4400000000 0.0125338035 0.0113426086 0.0172618069 0.0133613022 0.0914210000 0.0103170000 0.0380900000 0.0000290000 0.0002880000 0.0310700000 9909336 96830484 1769369600 3.9447500706 3.8621220589 5.2202615738 863 34.4800000000 0.0126145957 0.0113440825 0.0172618069 0.0133709837 0.1256570000 0.0082920000 0.0606720000 0.0003240000 0.0002840000 0.0399470000 9911010 96830484 1768259584 3.9461693764 3.8584051132 5.2199153900 864 34.5200000000 0.0126538659 0.0113455984 0.0172618069 0.0133761593 0.0876250000 0.0081910000 0.0367030000 0.0000280000 0.0003180000 0.0288480000 9912684 96830484 1769926656 3.9463026524 3.8587889671 5.2175226212 865 34.5600000000 0.0126336217 0.0113470875 0.0172618069 0.0133813542 0.1196970000 0.0097090000 0.0475550000 0.0003940000 0.0002890000 0.0517490000 9914358 96830484 1768734720 3.9476714134 3.8575696945 5.2161388397 866 34.6000000000 0.0126618724 0.0113486057 0.0172618069 0.0133813672 0.0958510000 0.0083590000 0.0416540000 0.0000260000 0.0002880000 0.0307520000 9916032 96830484 1770496000 3.9487693310 3.8534150124 5.2156100273 867 34.6400000000 0.0129282316 0.0113504277 0.0172618069 0.0133759859 0.1289870000 0.0095510000 0.0698310000 0.0000620000 0.0000540000 0.0391980000 9917706 96830484 1769402368 3.9494228363 3.8519032001 5.2146029472 868 34.6800000000 0.0129052149 0.0113522189 0.0172618069 0.0133700637 0.1087080000 0.0079580000 0.0552290000 0.0000310000 0.0003630000 0.0350770000 9919380 96830484 1771048960 3.9504675865 3.8509569168 5.2130231857 869 34.7200000000 0.0129172057 0.0113540198 0.0172618069 0.0133643250 0.1784250000 0.0095430000 0.0795990000 0.0003010000 0.0002810000 0.0537110000 9921054 96830484 1770020864 3.9514119625 3.8484737873 5.2123179436 870 34.7600000000 0.0128660584 0.0113557578 0.0172618069 0.0133579721 0.1540510000 0.0116380000 0.0949450000 0.0000280000 0.0007700000 0.0291520000 9922728 96830484 1768497152 3.9526600838 3.8458592892 5.2117023468 871 34.8000000000 0.0128550781 0.0113574791 0.0172618069 0.0133534560 0.1074370000 0.0085130000 0.0448640000 0.0003870000 0.0002710000 0.0347130000 9924402 96830484 1770160128 3.9533197880 3.8424232006 5.2109260559 872 34.8400000000 0.0128118917 0.0113591471 0.0172618069 0.0133483561 0.1067990000 0.0098800000 0.0448400000 0.0000270000 0.0003800000 0.0289990000 9926076 96830484 1769005056 3.9535424709 3.8384106159 5.2108922005 873 34.8800000000 0.0127674574 0.0113607602 0.0172618069 0.0133411721 0.1158440000 0.0082450000 0.0457160000 0.0003070000 0.0002840000 0.0511830000 9927750 96830484 1770795008 3.9542040825 3.8358325958 5.2104401588 874 34.9200000000 0.0126458053 0.0113622305 0.0172618069 0.0133344153 0.1002730000 0.0103580000 0.0380240000 0.0000250000 0.0002890000 0.0300370000 9929424 96830484 1769750528 3.9544479847 3.8338863850 5.2092900276 875 34.9600000000 0.0125451135 0.0113635824 0.0172618069 0.0133281421 0.1298260000 0.0099200000 0.0718790000 0.0002890000 0.0003410000 0.0341840000 9931098 96830484 1768607744 3.9541883469 3.8305528164 5.2086462975 876 35.0000000000 0.0125179645 0.0113649002 0.0172618069 0.0133206984 0.0887190000 0.0084290000 0.0360980000 0.0000270000 0.0002850000 0.0314180000 9932772 96830484 1770258432 3.9552161694 3.8278760910 5.2085957527 877 35.0400000000 0.0123696644 0.0113660459 0.0172618069 0.0133132174 0.1793850000 0.0096270000 0.1022540000 0.0000600000 0.0000550000 0.0572410000 9934446 96830484 1769009152 3.9548673630 3.8254473209 5.2073187828 878 35.0800000000 0.0123345153 0.0113671489 0.0172618069 0.0133059716 0.0954930000 0.0083550000 0.0434940000 0.0003500000 0.0010560000 0.0283970000 9936120 96830484 1770541056 3.9547109604 3.8217165470 5.2064156532 879 35.1200000000 0.0124004548 0.0113683245 0.0172618069 0.0132984413 0.1062920000 0.0100550000 0.0392300000 0.0003000000 0.0002720000 0.0364230000 9937794 96830484 1769275392 3.9552261829 3.8187057972 5.2059130669 880 35.1600000000 0.0123497089 0.0113694397 0.0172618069 0.0132919207 0.1101590000 0.0083050000 0.0466370000 0.0000290000 0.0002950000 0.0442430000 9939468 96830484 1768378368 3.9549641609 3.8139955997 5.2034697533 881 35.2000000000 0.0121046640 0.0113702742 0.0172618069 0.0132849457 0.1388270000 0.0075770000 0.0699270000 0.0000660000 0.0000570000 0.0509270000 9941142 96830484 1767247872 3.9548556805 3.8124151230 5.2017817497 882 35.2400000000 0.0120901885 0.0113710904 0.0172618069 0.0132792886 0.1118500000 0.0082890000 0.0426200000 0.0000280000 0.0003620000 0.0316690000 9942816 96830484 1765830656 3.9548110962 3.8096463680 5.2005639076 883 35.2800000000 0.0121883713 0.0113720160 0.0172618069 0.0132755698 0.1091870000 0.0087740000 0.0443510000 0.0002940000 0.0003440000 0.0338030000 9944490 96830484 1765482496 3.9542841911 3.8070275784 5.1991038322 884 35.3200000000 0.0120768351 0.0113728133 0.0172618069 0.0132749888 0.1073280000 0.0090300000 0.0456730000 0.0000310000 0.0003150000 0.0294080000 9946164 96830484 1765302272 3.9538023472 3.8048317432 5.1971836090 885 35.3600000000 0.0119961835 0.0113735177 0.0172618069 0.0132763430 0.1273120000 0.0078520000 0.0363540000 0.0003830000 0.0002760000 0.0620050000 9947838 96830484 1765474304 3.9534983635 3.8026909828 5.1956872940 886 35.4000000000 0.0119346110 0.0113741510 0.0172618069 0.0132789149 0.0891650000 0.0081590000 0.0365810000 0.0000280000 0.0011990000 0.0288280000 9949512 96830484 1765347328 3.9524664879 3.8008935452 5.1940612793 887 35.4400000000 0.0119098052 0.0113747549 0.0172618069 0.0132820587 0.1005910000 0.0081370000 0.0534030000 0.0000600000 0.0000530000 0.0278990000 9951186 96830484 1765310464 3.9520297050 3.7999815941 5.1924419403 888 35.4800000000 0.0118539380 0.0113752945 0.0172618069 0.0132840891 0.0934150000 0.0084040000 0.0449680000 0.0000280000 0.0003800000 0.0293740000 9952860 96830484 1765347328 3.9505317211 3.7976768017 5.1906294823 889 35.5200000000 0.0117936321 0.0113757651 0.0172618069 0.0132925144 0.1244380000 0.0080590000 0.0373950000 0.0003660000 0.0002830000 0.0567810000 9954534 96830484 1765199872 3.9500393867 3.7961876392 5.1890935898 890 35.5600000000 0.0117351515 0.0113761689 0.0172618069 0.0132987559 0.0889240000 0.0080800000 0.0345240000 0.0000270000 0.0003720000 0.0302890000 9956208 96830484 1766957056 3.9491181374 3.7958028316 5.1874208450 891 35.6000000000 0.0116424877 0.0113764678 0.0172618069 0.0133030343 0.1311130000 0.0076860000 0.0754980000 0.0003060000 0.0002790000 0.0361980000 9957882 96830484 1768624128 3.9473865032 3.7925081253 5.1860795021 892 35.6400000000 0.0116647445 0.0113767909 0.0172618069 0.0133143543 0.0855190000 0.0075020000 0.0346610000 0.0000270000 0.0003050000 0.0306470000 9959556 96830484 1770369024 3.9461157322 3.7914917469 5.1842470169 893 35.6800000000 0.0116218552 0.0113770654 0.0172618069 0.0133253371 0.1066890000 0.0094240000 0.0334800000 0.0003920000 0.0002810000 0.0525150000 9961230 96830484 1769402368 3.9444587231 3.7909209728 5.1824545860 894 35.7200000000 0.0114894155 0.0113771910 0.0172618069 0.0133362446 0.1091630000 0.0078740000 0.0504880000 0.0000280000 0.0002900000 0.0378190000 9962904 96830484 1770921984 3.9429123402 3.7884101868 5.1812663078 895 35.7600000000 0.0114795323 0.0113773054 0.0172618069 0.0133525373 0.1276120000 0.0097710000 0.0618760000 0.0003930000 0.0002790000 0.0384410000 9964578 96830484 1769910272 3.9413318634 3.7861747742 5.1801724434 896 35.8000000000 0.0114239743 0.0113773575 0.0172618069 0.0133755476 0.1050920000 0.0095990000 0.0385770000 0.0000270000 0.0002860000 0.0319270000 9966252 96830484 1768624128 3.9404242039 3.7860887051 5.1786961555 897 35.8400000000 0.0113998568 0.0113773826 0.0172618069 0.0133906272 0.1117130000 0.0076520000 0.0390700000 0.0002930000 0.0002670000 0.0532990000 9967926 96830484 1770414080 3.9399878979 3.7862961292 5.1779899597 898 35.8800000000 0.0114323832 0.0113774438 0.0172618069 0.0133996622 0.1066280000 0.0103720000 0.0512480000 0.0000280000 0.0003150000 0.0304010000 9969600 96830484 1768763392 3.9386649132 3.7855763435 5.1767663956 899 35.9200000000 0.0114104999 0.0113774806 0.0172618069 0.0134077188 0.1085220000 0.0089830000 0.0506950000 0.0002910000 0.0003400000 0.0377460000 9971274 96830484 1768255488 3.9386553764 3.7851903439 5.1769027710 900 35.9600000000 0.0114164343 0.0113775239 0.0172618069 0.0134117793 0.1080720000 0.0082560000 0.0407400000 0.0000270000 0.0006790000 0.0408350000 9972948 96830484 1766813696 3.9378190041 3.7847466469 5.1761994362 901 36.0000000000 0.0113818944 0.0113775287 0.0172618069 0.0134180587 0.1404910000 0.0080690000 0.0503170000 0.0003120000 0.0003520000 0.0475280000 9974622 96830484 1765724160 3.9369740486 3.7840449810 5.1752877235 902 36.0400000000 0.0113845468 0.0113775365 0.0172618069 0.0134276942 0.0921620000 0.0084850000 0.0372690000 0.0000250000 0.0003540000 0.0303580000 9976296 96830484 1765302272 3.9359145164 3.7837071419 5.1746344566 903 36.0800000000 0.0114050433 0.0113775670 0.0172618069 0.0134379024 0.1275600000 0.0075980000 0.0587680000 0.0003220000 0.0002780000 0.0435150000 9977970 96830484 1765474304 3.9341495037 3.7834024429 5.1731128693 904 36.1200000000 0.0114241978 0.0113776185 0.0172618069 0.0134542742 0.0880770000 0.0081580000 0.0384170000 0.0000290000 0.0003880000 0.0288990000 9979644 96830484 1766957056 3.9332363605 3.7823314667 5.1726255417 905 36.1600000000 0.0114605306 0.0113777102 0.0172618069 0.0134770889 0.1060090000 0.0082620000 0.0368920000 0.0002940000 0.0003410000 0.0497420000 9981318 96830484 1768751104 3.9318544865 3.7820248604 5.1714854240 906 36.2000000000 0.0114291236 0.0113777669 0.0172618069 0.0135002808 0.1093000000 0.0081640000 0.0475620000 0.0000250000 0.0003230000 0.0384300000 9982992 96830484 1770385408 3.9307432175 3.7820501328 5.1707162857 907 36.2400000000 0.0114229731 0.0113778167 0.0172618069 0.0135209339 0.1116430000 0.0094940000 0.0479070000 0.0002870000 0.0004930000 0.0425860000 9984666 96830484 1769402368 3.9295980930 3.7806131840 5.1702852249 908 36.2800000000 0.0114643034 0.0113779120 0.0172618069 0.0135379555 0.1040410000 0.0078610000 0.0440700000 0.0000260000 0.0003840000 0.0382390000 9986340 96830484 1770938368 3.9281463623 3.7809872627 5.1696243286 909 36.3200000000 0.0113917589 0.0113779272 0.0172618069 0.0135470563 0.1471400000 0.0096160000 0.0700070000 0.0003780000 0.0002850000 0.0563200000 9988014 96830484 1770020864 3.9266455173 3.7806408405 5.1689701080 910 36.3600000000 0.0113882422 0.0113779386 0.0172618069 0.0135543996 0.1071230000 0.0094130000 0.0409270000 0.0000260000 0.0002930000 0.0395010000 9989688 96830484 1768497152 3.9249501228 3.7801082134 5.1683855057 911 36.4000000000 0.0113969194 0.0113779594 0.0172618069 0.0135610292 0.1264450000 0.0079040000 0.0618330000 0.0003160000 0.0002810000 0.0354380000 9991362 96830484 1770307584 3.9238796234 3.7790019512 5.1681447029 912 36.4400000000 0.0114475414 0.0113780357 0.0172618069 0.0135672702 0.1075310000 0.0098630000 0.0447760000 0.0000280000 0.0003150000 0.0292310000 9993036 96830484 1769115648 3.9221954346 3.7777256966 5.1679697037 913 36.4800000000 0.0115397451 0.0113782128 0.0172618069 0.0136444805 0.1070760000 0.0080650000 0.0364690000 0.0003630000 0.0002700000 0.0512080000 9994710 96830484 1770795008 3.9188563824 3.7776618004 5.1666159630 914 36.5200000000 0.0113864467 0.0113782218 0.0172618069 0.0136630977 0.1084910000 0.0112070000 0.0456970000 0.0000270000 0.0003180000 0.0294960000 9996384 96830484 1769750528 3.9178159237 3.7770199776 5.1665463448 915 36.5600000000 0.0114035616 0.0113782495 0.0172618069 0.0136804409 0.1079530000 0.0097490000 0.0396030000 0.0002870000 0.0003360000 0.0373230000 9998058 96830484 1768607744 3.9160501957 3.7768087387 5.1664400101 916 36.6000000000 0.0113938479 0.0113782665 0.0172618069 0.0136966949 0.1094080000 0.0083790000 0.0578840000 0.0000290000 0.0003900000 0.0295420000 9999732 96830484 1770242048 3.9143266678 3.7767121792 5.1660871506 917 36.6400000000 0.0113877300 0.0113782769 0.0172618069 0.0137083493 0.1179710000 0.0102420000 0.0456640000 0.0003200000 0.0002760000 0.0507930000 10001406 96830484 1769009152 3.9124882221 3.7763364315 5.1658248901 918 36.6800000000 0.0114202285 0.0113783226 0.0172618069 0.0137206708 0.0933320000 0.0086280000 0.0382800000 0.0000260000 0.0002950000 0.0305700000 10003080 96830484 1770541056 3.9109756947 3.7758495808 5.1657223701 919 36.7200000000 0.0113891000 0.0113783343 0.0172618069 0.0137372734 0.1116740000 0.0095090000 0.0476090000 0.0006700000 0.0002860000 0.0426470000 10004754 96830484 1769529344 3.9094362259 3.7753012180 5.1657028198 920 36.7600000000 0.0114187934 0.0113783783 0.0172618069 0.0137550060 0.1064920000 0.0078470000 0.0527330000 0.0000270000 0.0002870000 0.0349030000 10006428 96830484 1771175936 3.9078021049 3.7755818367 5.1652736664 921 36.8000000000 0.0113668693 0.0113783658 0.0172618069 0.0137642220 0.1345620000 0.0096920000 0.0626930000 0.0003180000 0.0002690000 0.0509720000 10008102 96830484 1770037248 3.9062182903 3.7748658657 5.1654891968 922 36.8400000000 0.0114374002 0.0113784298 0.0172618069 0.0137717129 0.0982670000 0.0100380000 0.0433760000 0.0000270000 0.0010520000 0.0291900000 10009776 96830484 1768747008 3.9045112133 3.7741854191 5.1659727097 923 36.8800000000 0.0114660710 0.0113785248 0.0172618069 0.0137774548 0.1062060000 0.0084140000 0.0439120000 0.0003840000 0.0002770000 0.0348190000 10011450 96830484 1770414080 3.9026896954 3.7738289833 5.1666998863 924 36.9200000000 0.0114949476 0.0113786508 0.0172618069 0.0137802150 0.1072630000 0.0101590000 0.0452710000 0.0000280000 0.0003190000 0.0288830000 10013124 96830484 1769369600 3.9008812904 3.7733385563 5.1668653488 925 36.9600000000 0.0114799133 0.0113787602 0.0172618069 0.0137835346 0.1064680000 0.0086090000 0.0364770000 0.0002880000 0.0006420000 0.0496570000 10014798 96830484 1771016192 3.8991425037 3.7732803822 5.1670517921 926 37.0000000000 0.0114333825 0.0113788192 0.0172618069 0.0137876471 0.1084160000 0.0103750000 0.0437400000 0.0000290000 0.0010460000 0.0292950000 10016472 96830484 1769893888 3.8975703716 3.7730991840 5.1670355797 927 37.0400000000 0.0112952748 0.0113787291 0.0172618069 0.0137936771 0.0920840000 0.0098490000 0.0368600000 0.0002880000 0.0003380000 0.0339130000 10018146 96830484 1768771584 3.8963017464 3.7722332478 5.1674308777 928 37.0800000000 0.0111140320 0.0113784439 0.0172618069 0.0138051378 0.1086410000 0.0082680000 0.0563820000 0.0000270000 0.0003590000 0.0329500000 10019820 96830484 1767616512 3.8945999146 3.7725241184 5.1674542427 929 37.1200000000 0.0109435646 0.0113779757 0.0172618069 0.0138161387 0.1409530000 0.0078910000 0.0604320000 0.0003590000 0.0002700000 0.0575620000 10021494 96830484 1766576128 3.8929858208 3.7731120586 5.1668629646 930 37.1600000000 0.0108158719 0.0113773713 0.0172618069 0.0138244656 0.1026090000 0.0084180000 0.0436990000 0.0000190000 0.0001960000 0.0289060000 10023168 96830484 1765322752 3.8912093639 3.7734003067 5.1662092209 931 37.2000000000 0.0106825689 0.0113766250 0.0172618069 0.0138316541 0.1082250000 0.0085660000 0.0446170000 0.0003150000 0.0003500000 0.0343890000 10024842 96830484 1765306368 3.8895573616 3.7729036808 5.1659555435 932 37.2400000000 0.0105685778 0.0113757580 0.0172618069 0.0138483545 0.1063670000 0.0081830000 0.0448790000 0.0000280000 0.0003180000 0.0281890000 10026516 96830484 1767067648 3.8877077103 3.7725431919 5.1651134491 933 37.2800000000 0.0103489561 0.0113746575 0.0172618069 0.0138748029 0.1284710000 0.0080190000 0.0458440000 0.0003230000 0.0003300000 0.0517660000 10028190 96830484 1768751104 3.8858864307 3.7729132175 5.1636195183 934 37.3200000000 0.0102351885 0.0113734375 0.0172618069 0.0139003992 0.1072940000 0.0084520000 0.0450440000 0.0000320000 0.0003190000 0.0278490000 10029864 96830484 1770385408 3.8838820457 3.7741339207 5.1628203392 935 37.3600000000 0.0101398295 0.0113721181 0.0172618069 0.0139153214 0.1092610000 0.0101510000 0.0449410000 0.0003120000 0.0003540000 0.0338330000 10031538 96830484 1769402368 3.8820734024 3.7745487690 5.1612806320 936 37.4000000000 0.0101527832 0.0113708154 0.0172618069 0.0139266827 0.1069950000 0.0088150000 0.0478680000 0.0000290000 0.0003770000 0.0276470000 10033212 96830484 1770921984 3.8805291653 3.7748088837 5.1606578827 937 37.4400000000 0.0101384446 0.0113695002 0.0172618069 0.0139344670 0.1147010000 0.0099880000 0.0447780000 0.0003180000 0.0002790000 0.0482700000 10034886 96830484 1770291200 3.8789761066 3.7763574123 5.1599993706 938 37.4800000000 0.0101694437 0.0113682208 0.0172618069 0.0139379309 0.1022990000 0.0106210000 0.0462230000 0.0000290000 0.0003180000 0.0275710000 10036560 96830484 1768857600 3.8776311874 3.7765152454 5.1595916748 939 37.5200000000 0.0102242753 0.0113670026 0.0172618069 0.0139422145 0.1069260000 0.0085150000 0.0452620000 0.0003880000 0.0002750000 0.0334380000 10038234 96830484 1770541056 3.8762648106 3.7766463757 5.1591310501 940 37.5600000000 0.0102254739 0.0113657882 0.0172618069 0.0139441870 0.0894650000 0.0103580000 0.0374640000 0.0000980000 0.0003060000 0.0286720000 10039908 96830484 1769385984 3.8748769760 3.7768807411 5.1586761475 941 37.6000000000 0.0102298791 0.0113645810 0.0172618069 0.0139455791 0.1404080000 0.0083110000 0.0681530000 0.0000630000 0.0000540000 0.0525490000 10041582 96830484 1768378368 3.8734920025 3.7774021626 5.1573281288 942 37.6400000000 0.0102826459 0.0113634325 0.0172618069 0.0139470740 0.1124570000 0.0082620000 0.0605770000 0.0000270000 0.0003870000 0.0324420000 10043256 96830484 1767489536 3.8721449375 3.7776768208 5.1560149193 943 37.6800000000 0.0102957813 0.0113623003 0.0172618069 0.0139482144 0.1281070000 0.0078560000 0.0718400000 0.0003120000 0.0003590000 0.0360480000 10044930 96830484 1766342656 3.8710269928 3.7772815228 5.1551885605 944 37.7200000000 0.0103095705 0.0113611851 0.0172618069 0.0139504956 0.1043760000 0.0086450000 0.0486600000 0.0000310000 0.0003160000 0.0314090000 10046604 96830484 1765179392 3.8698418140 3.7769238949 5.1548810005 945 37.7600000000 0.0103123449 0.0113600752 0.0172618069 0.0139535864 0.1454070000 0.0087270000 0.0611350000 0.0003850000 0.0002850000 0.0489950000 10048278 96830484 1766748160 3.8683826923 3.7772274017 5.1561436653 946 37.8000000000 0.0103703337 0.0113590290 0.0172618069 0.0139567035 0.1083790000 0.0084430000 0.0471280000 0.0000280000 0.0003870000 0.0264560000 10049952 96830484 1768370176 3.8671245575 3.7768423557 5.1556010246 947 37.8400000000 0.0103292707 0.0113579416 0.0172618069 0.0139585261 0.1083500000 0.0083560000 0.0448300000 0.0003160000 0.0002720000 0.0320650000 10051626 96830484 1770147840 3.8655843735 3.7771658897 5.1551923752 948 37.8800000000 0.0104335612 0.0113569665 0.0172618069 0.0139582360 0.1071790000 0.0102950000 0.0461220000 0.0000290000 0.0003870000 0.0254650000 10053300 96830484 1769152512 3.8642375469 3.7772555351 5.1567826271 949 37.9200000000 0.0105371410 0.0113561026 0.0172618069 0.0139594433 0.1278470000 0.0083710000 0.0460520000 0.0003150000 0.0002740000 0.0478900000 10054974 96830484 1770749952 3.8628768921 3.7831618786 5.1656641960 950 37.9600000000 0.0107739987 0.0113554899 0.0172618069 0.0139600947 0.1076240000 0.0111400000 0.0454400000 0.0000310000 0.0003190000 0.0254260000 10056648 96830484 1769750528 3.8610663414 3.7878060341 5.1751918793 951 38.0000000000 0.0107982354 0.0113549039 0.0172618069 0.0139625169 0.1105690000 0.0084590000 0.0556780000 0.0003800000 0.0002750000 0.0316860000 10058322 96830484 1771302912 3.8597569466 3.7896075249 5.1785011292 952 38.0400000000 0.0108811846 0.0113544063 0.0172618069 0.0139634899 0.1070880000 0.0105630000 0.0529930000 0.0000290000 0.0003800000 0.0248050000 10059996 96830484 1770655744 3.8586866856 3.7905542850 5.1786184311 953 38.0800000000 0.0109248636 0.0113539556 0.0172618069 0.0139604588 0.1213780000 0.0105460000 0.0553630000 0.0003840000 0.0002770000 0.0437030000 10061670 96830484 1769529344 3.8575417995 3.7906303406 5.1784224510 954 38.1200000000 0.0108116409 0.0113533871 0.0172618069 0.0139591460 0.1151160000 0.0090550000 0.0657150000 0.0000280000 0.0006980000 0.0259660000 10063344 96830484 1771192320 3.8564832211 3.7909023762 5.1797699928 955 38.1600000000 0.0107680075 0.0113527742 0.0172618069 0.0139608303 0.1012560000 0.0111100000 0.0541580000 0.0003110000 0.0003480000 0.0240770000 10065018 96830484 1770164224 3.8556818962 3.7902882099 5.1777830124 956 38.2000000000 0.0106543172 0.0113520436 0.0172618069 0.0139621068 0.1511230000 0.0107230000 0.0905250000 0.0000290000 0.0003110000 0.0241010000 10066692 96830484 1768591360 3.8543896675 3.7908368111 5.1777024269 957 38.2400000000 0.0104781957 0.0113511305 0.0172618069 0.0139604845 0.1187330000 0.0090320000 0.0551390000 0.0003130000 0.0002860000 0.0426740000 10068366 96830484 1770303488 3.8530712128 3.7911500931 5.1762809753 958 38.2800000000 0.0103471018 0.0113500824 0.0172618069 0.0139578204 0.1340460000 0.0109200000 0.0776320000 0.0000270000 0.0003130000 0.0243130000 10070040 96830484 1769242624 3.8522350788 3.7892484665 5.1723093987 959 38.3200000000 0.0101224193 0.0113488023 0.0172618069 0.0139569676 0.1351900000 0.0092710000 0.0910340000 0.0000600000 0.0000530000 0.0237840000 10071714 96830484 1771032576 3.8510286808 3.7889192104 5.1721215248 960 38.3600000000 0.0093389992 0.0113467087 0.0172618069 0.0139565020 0.1202010000 0.0113510000 0.0643590000 0.0000290000 0.0007360000 0.0235690000 10073388 96830484 1769893888 3.8495621681 3.7903263569 5.1759786606 961 38.4000000000 0.0096665537 0.0113449604 0.0172618069 0.0139552525 0.1569220000 0.0108600000 0.0922680000 0.0003850000 0.0002800000 0.0417810000 10075062 96830484 1768771584 3.8484511375 3.7898609638 5.1785945892 962 38.4400000000 0.0162665695 0.0113500764 0.0172618069 0.0139577186 0.1391660000 0.0086410000 0.0917080000 0.0000310000 0.0002980000 0.0229650000 10076736 96830484 1770401792 3.8469810486 3.7897498608 5.1883320808 963 38.4800000000 0.0410540961 0.0113809217 0.0410540961 0.0139860654 0.1472730000 0.0108010000 0.0900910000 0.0000590000 0.0000520000 0.0297820000 10078410 96830484 1769099264 3.8453917503 3.7886614799 5.2120208740 964 38.5200000000 0.0719826147 0.0114437865 0.0719826147 0.0140370767 0.1277070000 0.0092630000 0.0907910000 0.0000060000 0.0000600000 0.0161750000 10080084 96830484 1770668032 3.8433926105 3.7903368473 5.2442922592 965 38.5600000000 0.1036058292 0.0115392912 0.1036058292 0.0140832567 0.1641120000 0.0113680000 0.0828780000 0.0000610000 0.0000520000 0.0371000000 10081758 96830484 1769656320 3.8416872025 3.7906706333 5.2744083405 966 38.6000000000 0.1252321750 0.0116569857 0.1252321750 0.0141067339 0.1500310000 0.0092490000 0.0941830000 0.0000300000 0.0003110000 0.0224940000 10083432 96830484 1771323392 3.8402101994 3.7910573483 5.2954468727 967 38.6400000000 0.1321420074 0.0117815824 0.1321420074 0.0141074453 0.1087520000 0.0108770000 0.0480500000 0.0003160000 0.0002750000 0.0293020000 10085106 96830484 1770545152 3.8387706280 3.7920792103 5.3046565056 968 38.6800000000 0.1539109349 0.0119284103 0.1539109349 0.0141313440 0.1062700000 0.0113270000 0.0457650000 0.0000290000 0.0003100000 0.0228230000 10086780 96830484 1769115648 3.8371820450 3.7909073830 5.3240265846 969 38.7200000000 0.2014205307 0.0121239646 0.2014205307 0.0142434156 0.1108220000 0.0090900000 0.0457660000 0.0003200000 0.0002750000 0.0427580000 10088454 96830484 1770811392 3.8348128796 3.7924451828 5.3719654083 970 38.7600000000 0.2527766526 0.0123720601 0.2527766526 0.0143669131 0.1049100000 0.0111270000 0.0458620000 0.0000280000 0.0003170000 0.0227520000 10090128 96830484 1769607168 3.8327383995 3.7929410934 5.4218354225 971 38.8000000000 0.3061119616 0.0126745729 0.3061119616 0.0145009401 0.1078870000 0.0107030000 0.0447040000 0.0003950000 0.0002760000 0.0283870000 10091802 96830484 1768620032 3.8303611279 3.7925231457 5.4730086327 972 38.8400000000 0.3585553467 0.0130304173 0.3585553467 0.0146202733 0.0903670000 0.0095460000 0.0448180000 0.0000940000 0.0003170000 0.0221910000 10093476 96830484 1770283008 3.8279116154 3.7935693264 5.5249805450 973 38.8800000000 0.4109050035 0.0134393326 0.4109050035 0.0147412448 0.1090160000 0.0109580000 0.0448030000 0.0003850000 0.0002750000 0.0412890000 10095150 96830484 1768869888 3.8259415627 3.7936003208 5.5761156082 974 38.9200000000 0.4600120485 0.0138978262 0.4600120485 0.0148419154 0.1030240000 0.0092590000 0.0451880000 0.0000320000 0.0006570000 0.0224350000 10096824 96830484 1770536960 3.8238229752 3.7945566177 5.6253962517 975 38.9600000000 0.5115529299 0.0144082417 0.5115529299 0.0149539018 0.1080130000 0.0111610000 0.0431940000 0.0003240000 0.0002790000 0.0281350000 10098498 96830484 1769283584 3.8216838837 3.7954912186 5.6763772964 976 39.0000000000 0.5590664744 0.0149662931 0.5590664744 0.0150490173 0.0905920000 0.0091460000 0.0455490000 0.0000320000 0.0003110000 0.0217520000 10100172 96830484 1770950656 3.8196372986 3.7947881222 5.7222394943 977 39.0400000000 0.6054406762 0.0155706681 0.6054406762 0.0151295385 0.1092180000 0.0116920000 0.0462610000 0.0003170000 0.0003480000 0.0389810000 10101846 96830484 1769791488 3.8176670074 3.7957503796 5.7680916786 978 39.0800000000 0.6526108384 0.0162220385 0.6526108384 0.0152211476 0.0858450000 0.0111880000 0.0367980000 0.0000280000 0.0003860000 0.0226620000 10103520 96830484 1768230912 3.8158614635 3.7958805561 5.8132967949 979 39.1200000000 0.7033661604 0.0169239221 0.7033661604 0.0153277235 0.1064610000 0.0098870000 0.0605920000 0.0003900000 0.0002830000 0.0233710000 10105194 96830484 1767583744 3.8140401840 3.7948985100 5.8612370491 980 39.1600000000 0.7505047321 0.0176724740 0.7505047321 0.0154153434 0.0989610000 0.0087330000 0.0351430000 0.0000280000 0.0003110000 0.0213890000 10106868 96830484 1769123840 3.8120858669 3.7954385281 5.9066290855 981 39.2000000000 0.7958915830 0.0184657656 0.7958915830 0.0154998602 0.1054170000 0.0100390000 0.0453340000 0.0003110000 0.0002720000 0.0381440000 10108542 96830484 1770917888 3.8103845119 3.7954063416 5.9513988495 982 39.2400000000 0.8421525955 0.0193045506 0.8421525955 0.0155787247 0.0967310000 0.0115520000 0.0456960000 0.0000290000 0.0003880000 0.0214500000 10110216 96830484 1769902080 3.8085861206 3.7956957817 5.9959030151 983 39.2800000000 0.8907282352 0.0201910447 0.8907282352 0.0156693310 0.1066930000 0.0097330000 0.0446280000 0.0003900000 0.0002750000 0.0279040000 10111890 96830484 1768132608 3.8068907261 3.7963786125 6.0429511070 984 39.3200000000 0.8971360922 0.0210822490 0.8971360922 0.0156642748 0.0890220000 0.0094660000 0.0371140000 0.0000300000 0.0003140000 0.0220430000 10113564 96830484 1766727680 3.8062627316 3.7967436314 6.0484266281 985 39.3600000000 0.9474811554 0.0220227555 0.9474811554 0.0157659943 0.1150580000 0.0095760000 0.0590050000 0.0006390000 0.0003540000 0.0337540000 10115238 96830484 1765605376 3.8046283722 3.7972397804 6.0961170197 986 39.4000000000 0.9506389499 0.0229645569 0.9506389499 0.0157598633 0.1095130000 0.0093300000 0.0454190000 0.0001150000 0.0003270000 0.0212510000 10116912 96830484 1765330944 3.8045678139 3.7976572514 6.0976667404 987 39.4400000000 0.9971652627 0.0239515890 0.9971652627 0.0158559754 0.0951930000 0.0099240000 0.0427460000 0.0003110000 0.0003520000 0.0303420000 10118586 96830484 1765466112 3.8032553196 3.7977623940 6.1424932480 988 39.4800000000 1.0454932451 0.0249855381 1.0454932451 0.0159530694 0.1053600000 0.0093230000 0.0508910000 0.0000290000 0.0003170000 0.0255900000 10120260 96830484 1765326848 3.8020496368 3.7978947163 6.1893286705 989 39.5200000000 1.0423430204 0.0260142110 1.0454932451 0.0159462390 0.1108650000 0.0107610000 0.0467230000 0.0005460000 0.0002840000 0.0406920000 10121934 96830484 1764470784 3.8021092415 3.7979471684 6.1835823059 990 39.5600000000 1.0941153765 0.0270931010 1.0941153765 0.0160533689 0.0868330000 0.0090080000 0.0432010000 0.0000280000 0.0039660000 0.0189270000 10123608 96830484 1765949440 3.8005032539 3.7988891602 6.2341027260 991 39.6000000000 1.0953954458 0.0281711054 1.0953954458 0.0160466005 0.1036330000 0.0097190000 0.0439580000 0.0003240000 0.0002830000 0.0280630000 10125282 96830484 1767743488 3.8004753590 3.7989408970 6.2327070236 992 39.6400000000 1.1401052475 0.0292920068 1.1401052475 0.0161267998 0.0887240000 0.0097760000 0.0373170000 0.0000270000 0.0003140000 0.0221290000 10126956 96830484 1769377792 3.7988286018 3.7997934818 6.2753667831 993 39.6800000000 1.1380872726 0.0304086183 1.1401052475 0.0161193615 0.1298830000 0.0112580000 0.0597780000 0.0003020000 0.0002790000 0.0466130000 10128630 96830484 1768361984 3.7987301350 3.7997488976 6.2714734077 994 39.7200000000 1.1801959276 0.0315653460 1.1801959276 0.0161848742 0.1064630000 0.0096480000 0.0551340000 0.0000280000 0.0003070000 0.0260300000 10130304 96830484 1769885696 3.7973139286 3.7996408939 6.3100242615 995 39.7600000000 1.1694179773 0.0327089165 1.1801959276 0.0161831674 0.1031150000 0.0109640000 0.0593180000 0.0003080000 0.0002800000 0.0206080000 10131978 96830484 1768615936 3.7971448898 3.8012163639 6.2961211205 996 39.8000000000 1.2082493305 0.0338891779 1.2082493305 0.0162487983 0.1116210000 0.0098820000 0.0586590000 0.0000280000 0.0003200000 0.0239000000 10133652 96830484 1770283008 3.7953698635 3.8032207489 6.3324813843 997 39.8400000000 1.1812582016 0.0350399994 1.2082493305 0.0162703241 0.1090530000 0.0121070000 0.0408130000 0.0003030000 0.0003700000 0.0421240000 10135326 96830484 1769033728 3.7960765362 3.8044836521 6.3039321899 998 39.8800000000 1.2131363153 0.0362204566 1.2131363153 0.0163118701 0.1046690000 0.0096020000 0.0454800000 0.0000310000 0.0003140000 0.0227930000 10137000 96830484 1770565632 3.7942783833 3.8071153164 6.3336830139 999 39.9200000000 1.2758978605 0.0374613750 1.2758978605 0.0165038971 0.1102970000 0.0112830000 0.0604100000 0.0003920000 0.0002780000 0.0252200000 10138674 96830484 1769631744 3.7918138504 3.8102986813 6.3917379379 1000 39.9600000000 1.3053488731 0.0387292625 1.3053488731 0.0165378672 0.0846460000 0.0107500000 0.0387550000 0.0000100000 0.0000960000 0.0234790000 10140348 96830484 1771184128 3.7905960083 3.8120386600 6.4193201065 1001 40.0000000000 1.2820266485 0.0399713178 1.3053488731 0.0165500050 0.1271590000 0.0111730000 0.0514610000 0.0003060000 0.0003660000 0.0516630000 10142022 96830484 1770139648 3.7911701202 3.8134405613 6.3936061859 1002 40.0400000000 1.3083431721 0.0412371580 1.3083431721 0.0165813030 0.0864910000 0.0119240000 0.0349600000 0.0000270000 0.0003080000 0.0221410000 10143696 96830484 1768792064 3.7893321514 3.8165788651 6.4176878929 1003 40.0800000000 1.3359185457 0.0425279669 1.3359185457 0.0166175231 0.1086110000 0.0098000000 0.0585230000 0.0003910000 0.0002890000 0.0273050000 10145370 96830484 1767489536 3.7882485390 3.8187897205 6.4435501099 1004 40.1200000000 1.3648509979 0.0438450217 1.3648509979 0.0166530988 0.0875180000 0.0098780000 0.0442150000 0.0000290000 0.0003130000 0.0209480000 10147044 96830484 1769267200 3.7872476578 3.8203058243 6.4690289497 1005 40.1600000000 1.3109589815 0.0451058317 1.3648509979 0.0167625233 0.1126010000 0.0101310000 0.0447260000 0.0003160000 0.0002770000 0.0454010000 10148718 96830484 1770758144 3.7892944813 3.8205771446 6.4143781662 1006 40.2000000000 1.3447288275 0.0463977034 1.3648509979 0.0168122391 0.1034230000 0.0122220000 0.0574360000 0.0000300000 0.0003770000 0.0208560000 10150392 96830484 1769279488 3.7869164944 3.8250591755 6.4453883171 1007 40.2400000000 1.3802361488 0.0477222699 1.3802361488 0.0168648141 0.1079420000 0.0099530000 0.0463830000 0.0003000000 0.0003580000 0.0389170000 10152066 96830484 1768386560 3.7858879566 3.8266627789 6.4773840904 1008 40.2800000000 1.4172966480 0.0490809746 1.4172966480 0.0169159937 0.1090380000 0.0093080000 0.0641390000 0.0000290000 0.0003100000 0.0221580000 10153740 96830484 1767108608 3.7847480774 3.8282434940 6.5121288300 1009 40.3200000000 1.4610720873 0.0504803712 1.4610720873 0.0169863905 0.0989450000 0.0108500000 0.0404290000 0.0000950000 0.0000850000 0.0348150000 10155414 96830484 1765986304 3.7830879688 3.8308672905 6.5528817177 1010 40.3600000000 1.4277722836 0.0518440265 1.4610720873 0.0170183974 0.0919790000 0.0095990000 0.0347770000 0.0000280000 0.0003140000 0.0300870000 10157088 96830484 1765363712 3.7847135067 3.8312270641 6.5160703659 1011 40.4000000000 1.4589961767 0.0532358684 1.4610720873 0.0170633203 0.1067460000 0.0118030000 0.0427980000 0.0003170000 0.0003410000 0.0306580000 10158762 96830484 1765453824 3.7826068401 3.8363883495 6.5433273315 1012 40.4400000000 1.4855914116 0.0546512395 1.4855914116 0.0170967489 0.1055880000 0.0112940000 0.0483680000 0.0000280000 0.0004230000 0.0210460000 10160436 96830484 1765322752 3.7814645767 3.8396692276 6.5669364929 1013 40.4800000000 1.5142579079 0.0560921148 1.5142579079 0.0171320681 0.1191330000 0.0105890000 0.0523510000 0.0003800000 0.0002840000 0.0433310000 10162110 96830484 1765552128 3.7802276611 3.8427603245 6.5929503441 1014 40.5200000000 1.3970773220 0.0574145854 1.5142579079 0.0176452149 0.1199470000 0.0101230000 0.0762130000 0.0000300000 0.0005450000 0.0206110000 10163784 96830484 1765318656 3.7855501175 3.8401901722 6.4737038612 1015 40.5600000000 1.4274317026 0.0587643560 1.5142579079 0.0176904404 0.1047620000 0.0114990000 0.0427850000 0.0011130000 0.0003710000 0.0302030000 10165458 96830484 1766948864 3.7815678120 3.8514902592 6.5014610291 1016 40.6000000000 1.4471995831 0.0601309261 1.5142579079 0.0177071410 0.1048490000 0.0117290000 0.0431870000 0.0000270000 0.0003130000 0.0235550000 10167132 96830484 1768644608 3.7805552483 3.8552892208 6.5194506645 1017 40.6400000000 1.4670208693 0.0615142987 1.5142579079 0.0177201667 0.1142900000 0.0115060000 0.0526560000 0.0003000000 0.0002760000 0.0374180000 10168806 96830484 1770516480 3.7794082165 3.8592565060 6.5364913940 1018 40.6800000000 1.4867401123 0.0629143241 1.5142579079 0.0177377838 0.1017970000 0.0116740000 0.0460940000 0.0000240000 0.0002980000 0.0211980000 10170480 96830484 1769410560 3.7782313824 3.8634111881 6.5540390015 1019 40.7200000000 1.5000239611 0.0643246377 1.5142579079 0.0177471243 0.1096570000 0.0102500000 0.0509480000 0.0003030000 0.0003570000 0.0339410000 10172154 96830484 1769123840 3.7771642208 3.8676967621 6.5651760101 1020 40.7600000000 1.5095945597 0.0657415690 1.5142579079 0.0177494776 0.1060030000 0.0106200000 0.0510340000 0.0000260000 0.0003050000 0.0252810000 10173828 96830484 1768775680 3.7762265205 3.8713533878 6.5732307434 1021 40.8000000000 1.5193957090 0.0671653243 1.5193957090 0.0177513935 0.1342230000 0.0100510000 0.0731710000 0.0000640000 0.0000550000 0.0305810000 10175502 96830484 1768218624 3.7752201557 3.8753442764 6.5808267593 1022 40.8400000000 1.5274497271 0.0685941740 1.5274497271 0.0177507494 0.0989110000 0.0104350000 0.0485780000 0.0000120000 0.0001160000 0.0212100000 10177176 96830484 1767645184 3.7741341591 3.8792486191 6.5876560211 1023 40.8800000000 1.5357931852 0.0700283862 1.5357931852 0.0177508271 0.1057410000 0.0100980000 0.0390500000 0.0003930000 0.0002760000 0.0297000000 10178850 96830484 1766604800 3.7730205059 3.8836619854 6.5947947502 1024 40.9200000000 1.5417033434 0.0714655687 1.5417033434 0.0177539686 0.0885080000 0.0107340000 0.0384120000 0.0000280000 0.0003560000 0.0220210000 10180524 96830484 1765060608 3.7721343040 3.8877806664 6.5989952087 1025 40.9600000000 1.5469890833 0.0729051039 1.5469890833 0.0177596588 0.1118360000 0.0109830000 0.0574320000 0.0003760000 0.0002820000 0.0303030000 10264118 96830484 1765568512 3.7714042664 3.8922712803 6.6028819084 1026 41.0000000000 1.5580185652 0.0743525829 1.5580185652 0.0177668051 0.1011500000 0.0106120000 0.0429260000 0.0000270000 0.0003860000 0.0278610000 10433728 96830484 1765457920 3.7700595856 3.8986775875 6.6111702919 1027 41.0400000000 1.5696705580 0.0758085887 1.5696705580 0.0177781881 0.1044030000 0.0103100000 0.0601020000 0.0003210000 0.0007030000 0.0207090000 10435402 96830484 1765478400 3.7688612938 3.9034912586 6.6206107140 1028 41.0800000000 1.5782730579 0.0772701300 1.5782730579 0.0177846451 0.1240660000 0.0102330000 0.0558690000 0.0000250000 0.0002930000 0.0211630000 10437076 96830484 1765314560 3.7679138184 3.9090938568 6.6277575493 1029 41.1200000000 1.5882551670 0.0787385314 1.5882551670 0.0177879976 0.1172330000 0.0107050000 0.0521140000 0.0003620000 0.0002830000 0.0417490000 10438750 96830484 1765470208 3.7668421268 3.9139049053 6.6355972290 1030 41.1600000000 1.5948764086 0.0802105099 1.5948764086 0.0177887144 0.1121700000 0.0108740000 0.0726680000 0.0000270000 0.0003470000 0.0156350000 10440424 96830484 1765302272 3.7660708427 3.9167635441 6.6402311325 1031 41.2000000000 1.6027123928 0.0816872334 1.6027123928 0.0177918764 0.0999630000 0.0098890000 0.0415800000 0.0003730000 0.0002730000 0.0321280000 10442098 96830484 1765470208 3.7650892735 3.9218568802 6.6457581520 1032 41.2400000000 1.6125736237 0.0831706504 1.6125736237 0.0177934307 0.1004380000 0.0103320000 0.0637670000 0.0000270000 0.0005010000 0.0135700000 10443772 96830484 1765314560 3.7642624378 3.9257018566 6.6537404060 1033 41.2800000000 1.6196149588 0.0846580118 1.6196149588 0.0177910692 0.1161890000 0.0103680000 0.0555810000 0.0003920000 0.0002830000 0.0375210000 10445446 96830484 1765355520 3.7634704113 3.9282677174 6.6594033241 1034 41.3200000000 1.6273493767 0.0861499764 1.6273493767 0.0178093637 0.1267260000 0.0105630000 0.0830080000 0.0000270000 0.0002820000 0.0201200000 10447120 96830484 1765318656 3.7625367641 3.9339323044 6.6638722420 1035 41.3600000000 1.6238282919 0.0876356559 1.6273493767 0.0178018597 0.1437070000 0.0106580000 0.0772930000 0.0000590000 0.0000530000 0.0281190000 10448794 96830484 1767075840 3.7624795437 3.9347720146 6.6593570709 1036 41.4000000000 1.6177012920 0.0891125532 1.6273493767 0.0177954349 0.1312310000 0.0103840000 0.0853340000 0.0000310000 0.0006910000 0.0205290000 10450468 96830484 1768632320 3.7620224953 3.9403674603 6.6512718201 1037 41.4400000000 1.5965678692 0.0905662228 1.6273493767 0.0178087701 0.1481090000 0.0105630000 0.0831100000 0.0003600000 0.0002690000 0.0414030000 10452142 96830484 1770496000 3.7617375851 3.9741404057 6.6268510818 1038 41.4800000000 2.0269024372 0.0924316719 2.0269024372 0.0280082646 0.1258860000 0.0126210000 0.0735540000 0.0000270000 0.0003540000 0.0192770000 10453816 96830484 1769275392 3.7536542416 3.3762648106 7.0033612251 1039 41.5200000000 1.9920375347 0.0942599740 2.0269024372 0.0286459933 0.1273770000 0.0105400000 0.0702890000 0.0003740000 0.0002880000 0.0252000000 10455490 96830484 1770942464 3.7583873272 3.1813859940 6.9064373970 1040 41.5600000000 1.9857610464 0.0960787250 2.0269024372 0.0286416099 0.1034280000 0.0122150000 0.0492480000 0.0000280000 0.0002970000 0.0187580000 10457164 96830484 1770147840 3.7583460808 3.1874244213 6.8997664452 1041 41.6000000000 1.9844172001 0.0978926909 2.0269024372 0.0286341524 0.1290220000 0.0121960000 0.0611760000 0.0002860000 0.0003350000 0.0373140000 10458838 96830484 1769127936 3.7580540180 3.1907639503 6.8974990845 1042 41.6400000000 1.9833139181 0.0997021163 2.0269024372 0.0286281816 0.1088990000 0.0106370000 0.0686190000 0.0000240000 0.0002840000 0.0168620000 10460512 96830484 1770905600 3.7578067780 3.1951553822 6.8955450058 1043 41.6800000000 1.9807993174 0.1015056611 2.0269024372 0.0286261106 0.1287000000 0.0123420000 0.0716010000 0.0002830000 0.0006300000 0.0248130000 10462186 96830484 1769766912 3.7578973770 3.1987905502 6.8919558525 1044 41.7200000000 1.9791527987 0.1033041736 2.0269024372 0.0286205758 0.1241210000 0.0123030000 0.0731330000 0.0000240000 0.0002840000 0.0199810000 10463860 96830484 1768370176 3.7578930855 3.2023272514 6.8899412155 1045 41.7600000000 1.9779000282 0.1050980453 2.0269024372 0.0286133688 0.1298210000 0.0105490000 0.0724830000 0.0003530000 0.0002660000 0.0338110000 10465534 96830484 1770115072 3.7577805519 3.2056336403 6.8889384270 1046 41.8000000000 1.9704083204 0.1068813247 2.0269024372 0.0286064841 0.1244860000 0.0120970000 0.0723860000 0.0000260000 0.0002830000 0.0186400000 10467208 96830484 1769009152 3.7579188347 3.2106244564 6.8811221123 1047 41.8400000000 1.9652695656 0.1086562896 2.0269024372 0.0285969804 0.1290570000 0.0104730000 0.0739240000 0.0003060000 0.0002750000 0.0269620000 10468882 96830484 1770639360 3.7580659389 3.2139556408 6.8763179779 1048 41.8800000000 1.9632413387 0.1104259318 2.0269024372 0.0285857583 0.1269930000 0.0124280000 0.0746850000 0.0000260000 0.0002800000 0.0186080000 10470556 96830484 1769623552 3.7579927444 3.2166559696 6.8733134270 1049 41.9200000000 1.9623460770 0.1121913466 2.0269024372 0.0285771747 0.1326250000 0.0109570000 0.0750820000 0.0003140000 0.0002780000 0.0334660000 10472230 96830484 1771175936 3.7579455376 3.2182481289 6.8710846901 1050 41.9600000000 1.9608408213 0.1139519652 2.0269024372 0.0285681556 0.1223930000 0.0122740000 0.0691830000 0.0000270000 0.0003020000 0.0188020000 10473904 96830484 1770401792 3.7579693794 3.2206814289 6.8686876297 1051 42.0000000000 1.9618709087 0.1157102135 2.0269024372 0.0285592669 0.1294330000 0.0123730000 0.0754540000 0.0002890000 0.0002630000 0.0255660000 10475578 96830484 1769385984 3.7580952644 3.2214426994 6.8687467575 1052 42.0400000000 1.9600867033 0.1174634230 2.0269024372 0.0285489223 0.1262530000 0.0108810000 0.0758210000 0.0000260000 0.0002860000 0.0186630000 10477252 96830484 1771020288 3.7581009865 3.2227072716 6.8664107323 1053 42.0800000000 1.9599342346 0.1192131579 2.0269024372 0.0285388862 0.1305770000 0.0123850000 0.0699970000 0.0002890000 0.0002630000 0.0351100000 10478926 96830484 1770020864 3.7579879761 3.2244625092 6.8651676178 1054 42.1200000000 1.9586241245 0.1209583296 2.0269024372 0.0285289775 0.1247350000 0.0123100000 0.0750940000 0.0000070000 0.0000590000 0.0185610000 10480600 96830484 1768480768 3.7580301762 3.2258429527 6.8632831573 1055 42.1600000000 1.9557325840 0.1226974521 2.0269024372 0.0285178516 0.1286910000 0.0107860000 0.0778880000 0.0002930000 0.0002720000 0.0251290000 10482274 96830484 1770176512 3.7578530312 3.2285044193 6.8601093292 1056 42.2000000000 1.9539164305 0.1244315610 2.0269024372 0.0285102902 0.1266820000 0.0124480000 0.0765070000 0.0000250000 0.0002800000 0.0190150000 10483948 96830484 1769152512 3.7577176094 3.2308456898 6.8581357002 1057 42.2400000000 1.9518569708 0.1261604403 2.0269024372 0.0285017735 0.1344030000 0.0109030000 0.0759690000 0.0002900000 0.0003440000 0.0343130000 10485622 96830484 1770795008 3.7577326298 3.2323341370 6.8557014465 1058 42.2800000000 1.9478529692 0.1278822669 2.0269024372 0.0284908533 0.1250400000 0.0127360000 0.0766030000 0.0000280000 0.0005430000 0.0225190000 10487296 96830484 1769656320 3.7577376366 3.2343184948 6.8518886566 1059 42.3200000000 1.9459106922 0.1295990076 2.0269024372 0.0284799127 0.1241010000 0.0117730000 0.0715800000 0.0002890000 0.0003400000 0.0255260000 10488970 96830484 1768591360 3.7576067448 3.2349007130 6.8501100540 1060 42.3600000000 1.9429193735 0.1313096872 2.0269024372 0.0284688632 0.1264170000 0.0109140000 0.0781310000 0.0000280000 0.0003460000 0.0188410000 10490644 96830484 1770274816 3.7574782372 3.2358536720 6.8471727371 1061 42.4000000000 1.9397737980 0.1330141774 2.0269024372 0.0284573059 0.1476110000 0.0123350000 0.0793120000 0.0002920000 0.0002660000 0.0371720000 10492318 96830484 1768861696 3.7573313713 3.2378008366 6.8444929123 1062 42.4400000000 1.9368618727 0.1347127157 2.0269024372 0.0284530080 0.1270220000 0.0108280000 0.0770690000 0.0000270000 0.0003460000 0.0185800000 10493992 96830484 1770528768 3.7569851875 3.2399065495 6.8437647820 1063 42.4800000000 1.9310820103 0.1364026210 2.0269024372 0.0284440890 0.1091250000 0.0130020000 0.0541250000 0.0003170000 0.0002760000 0.0256390000 10495666 96830484 1769132032 3.7572860718 3.2421586514 6.8390021324 1064 42.5200000000 1.9285467863 0.1380869670 2.0269024372 0.0284328657 0.1069760000 0.0106630000 0.0601200000 0.0000280000 0.0002810000 0.0187050000 10497340 96830484 1770811392 3.7574346066 3.2427444458 6.8370742798 1065 42.5600000000 1.9265587330 0.1397662832 2.0269024372 0.0284214770 0.1323660000 0.0124070000 0.0793760000 0.0003590000 0.0002760000 0.0273890000 10499014 96830484 1769766912 3.7576766014 3.2429082394 6.8358950615 1066 42.6000000000 1.9236319065 0.1414397031 2.0269024372 0.0284093823 0.1209550000 0.0106260000 0.0677770000 0.0000270000 0.0002890000 0.0192100000 10500688 96830484 1771384832 3.7578957081 3.2454700470 6.8336753845 1067 42.6400000000 1.9228907824 0.1431092918 2.0269024372 0.0283987010 0.1466290000 0.0127350000 0.0805740000 0.0003600000 0.0002740000 0.0260180000 10502362 96830484 1770274816 3.7580716610 3.2466247082 6.8337993622 1068 42.6800000000 1.9204328060 0.1447734524 2.0269024372 0.0283884230 0.1297430000 0.0123620000 0.0796990000 0.0000260000 0.0003530000 0.0194160000 10504036 96830484 1768894464 3.7584633827 3.2491347790 6.8329157829 1069 42.7200000000 1.9193935394 0.1464335273 2.0269024372 0.0283795110 0.1286690000 0.0106180000 0.0669700000 0.0003610000 0.0002780000 0.0377920000 10505710 96830484 1770684416 3.7588696480 3.2511053085 6.8328495026 1070 42.7600000000 1.9171487093 0.1480884013 2.0269024372 0.0283686242 0.1243890000 0.0126490000 0.0678650000 0.0000280000 0.0003790000 0.0193110000 10507384 96830484 1769512960 3.7591326237 3.2549180984 6.8316769600 1071 42.8000000000 1.9165853262 0.1497396589 2.0269024372 0.0283576506 0.1290510000 0.0105660000 0.0735980000 0.0002920000 0.0003570000 0.0261400000 10509058 96830484 1771286528 3.7591218948 3.2575304508 6.8333988190 1072 42.8400000000 1.9141644239 0.1513855775 2.0269024372 0.0283467018 0.1284220000 0.0125170000 0.0808330000 0.0000260000 0.0008130000 0.0196580000 10510732 96830484 1770147840 3.7590858936 3.2591812611 6.8328485489 1073 42.8800000000 1.9120281935 0.1530264374 2.0269024372 0.0283346810 0.1292350000 0.0123640000 0.0685220000 0.0004600000 0.0002800000 0.0348640000 10512406 96830484 1768718336 3.7590427399 3.2624597549 6.8315801620 1074 42.9200000000 1.9084490538 0.1546609091 2.0269024372 0.0283233182 0.1058720000 0.0107660000 0.0609420000 0.0000280000 0.0002970000 0.0193990000 10514080 96830484 1770414080 3.7588775158 3.2637255192 6.8284645081 1075 42.9600000000 1.9027410746 0.1562870302 2.0269024372 0.0283130301 0.1252430000 0.0124710000 0.0623420000 0.0005130000 0.0002840000 0.0261540000 10515754 96830484 1769259008 3.7589135170 3.2645847797 6.8225517273 1076 43.0000000000 1.8969272375 0.1579047255 2.0269024372 0.0283019366 0.1290960000 0.0106020000 0.0811390000 0.0000280000 0.0005810000 0.0195290000 10517428 96830484 1770938368 3.7590048313 3.2655870914 6.8184170723 1077 43.0400000000 1.8910889626 0.1595139959 2.0269024372 0.0282918851 0.1456680000 0.0124330000 0.0833270000 0.0002910000 0.0003390000 0.0364710000 10519102 96830484 1769893888 3.7591371536 3.2641451359 6.8143172264 1078 43.0800000000 1.8884329796 0.1611178169 2.0269024372 0.0282798490 0.1189940000 0.0120960000 0.0798750000 0.0000060000 0.0000700000 0.0128050000 10520776 96830484 1768501248 3.7593231201 3.2667274475 6.8141512871 1079 43.1200000000 1.8807992935 0.1627115903 2.0269024372 0.0282704212 0.1312080000 0.0115730000 0.0750460000 0.0003520000 0.0002680000 0.0259870000 10522450 96830484 1770176512 3.7596137524 3.2683227062 6.8091640472 1080 43.1600000000 1.8734092712 0.1642955696 2.0269024372 0.0282605610 0.1287860000 0.0121830000 0.0818430000 0.0000250000 0.0003440000 0.0202850000 10524124 96830484 1768988672 3.7599103451 3.2686905861 6.8032479286 1081 43.2000000000 1.8751950264 0.1658782703 2.0269024372 0.0282489593 0.1469550000 0.0103530000 0.0814440000 0.0002870000 0.0002660000 0.0377540000 10525798 96830484 1770782720 3.7599470615 3.2710704803 6.8087677956 1082 43.2400000000 1.8730109930 0.1674560270 2.0269024372 0.0282378583 0.1262430000 0.0125080000 0.0700260000 0.0000270000 0.0002830000 0.0218390000 10527472 96830484 1769385984 3.7600860596 3.2728734016 6.8088340759 1083 43.2800000000 1.8767226934 0.1690342972 2.0269024372 0.0282288286 0.1457420000 0.0106390000 0.0828010000 0.0006140000 0.0003620000 0.0255060000 10529146 96830484 1771065344 3.7602441311 3.2732262611 6.8150439262 1084 43.3200000000 1.8757028580 0.1706087147 2.0269024372 0.0282165406 0.1312440000 0.0124800000 0.0840980000 0.0000260000 0.0002810000 0.0206040000 10530820 96830484 1770020864 3.7606399059 3.2748181820 6.8156247139 1085 43.3600000000 1.8764013052 0.1721808738 2.0269024372 0.0282039777 0.1476920000 0.0123670000 0.0834940000 0.0002910000 0.0003420000 0.0384490000 10532494 96830484 1768480768 3.7609093189 3.2753918171 6.8175172806 1086 43.4000000000 1.8741022348 0.1737480205 2.0269024372 0.0281916007 0.1084210000 0.0104480000 0.0644720000 0.0002590000 0.0003200000 0.0199660000 10534168 96830484 1770266624 3.7613358498 3.2781233788 6.8170619011 1087 43.4400000000 1.8747911453 0.1753129176 2.0269024372 0.0281793433 0.1448560000 0.0123590000 0.0829170000 0.0002980000 0.0002750000 0.0263790000 10535842 96830484 1768988672 3.7616751194 3.2791635990 6.8198127747 1088 43.4800000000 1.8698568344 0.1768704028 2.0269024372 0.0281678968 0.1191420000 0.0107130000 0.0824130000 0.0000250000 0.0003000000 0.0128900000 10537516 96830484 1770684416 3.7621345520 3.2814731598 6.8162226677 1089 43.5200000000 1.8629201651 0.1784186579 2.0269024372 0.0281576025 0.1433890000 0.0122470000 0.0822970000 0.0002880000 0.0003380000 0.0350920000 10539190 96830484 1769750528 3.7628664970 3.2825460434 6.8109416962 1090 43.5600000000 1.8624745607 0.1799636633 2.0269024372 0.0281453269 0.1386680000 0.0124590000 0.0813470000 0.0000930000 0.0003010000 0.0194980000 10540864 96830484 1768390656 3.7636246681 3.2847673893 6.8125233650 1091 43.6000000000 1.8684533834 0.1815113166 2.0269024372 0.0281357808 0.1466210000 0.0106790000 0.0818340000 0.0002950000 0.0002680000 0.0256580000 10542538 96830484 1770033152 3.7643585205 3.2785859108 6.8181257248 1092 43.6400000000 1.8760896921 0.1830631283 2.0269024372 0.0281249357 0.1308480000 0.0121850000 0.0825680000 0.0000260000 0.0002830000 0.0196530000 10544212 96830484 1768624128 3.7649741173 3.2875025272 6.8319797516 1093 43.6800000000 1.8796006441 0.1846153126 2.0269024372 0.0281144040 0.1573510000 0.0105500000 0.0814640000 0.0002890000 0.0002650000 0.0517710000 10545886 96830484 1770258432 3.7656805515 3.2874717712 6.8382215500 1094 43.7200000000 1.8799607754 0.1861649886 2.0269024372 0.0281019698 0.1543890000 0.0122270000 0.1001830000 0.0000070000 0.0000590000 0.0136450000 10547560 96830484 1769226240 3.7663190365 3.2916073799 6.8420619965 1095 43.7600000000 1.8778575659 0.1877099133 2.0269024372 0.0280903088 0.1316760000 0.0105940000 0.0822700000 0.0002890000 0.0003410000 0.0253340000 10549234 96830484 1770942464 3.7668490410 3.2931358814 6.8430342674 1096 43.8000000000 1.8733073473 0.1892478672 2.0269024372 0.0280786024 0.1280150000 0.0129000000 0.0831680000 0.0000360000 0.0003580000 0.0183600000 10550908 96830484 1769496576 3.7674953938 3.2953238487 6.8413028717 1097 43.8400000000 1.8696478605 0.1907796812 2.0269024372 0.0280668137 0.1460370000 0.0107720000 0.0811390000 0.0002910000 0.0003420000 0.0373170000 10552582 96830484 1771175936 3.7681264877 3.2965333462 6.8400673866 1098 43.8800000000 1.8647243977 0.1923042210 2.0269024372 0.0280553278 0.1283270000 0.0123170000 0.0820550000 0.0000270000 0.0003020000 0.0200380000 10554256 96830484 1770385408 3.7687864304 3.2990136147 6.8375468254 1099 43.9200000000 1.8596787453 0.1938213953 2.0269024372 0.0280440882 0.1447080000 0.0126030000 0.0819580000 0.0002930000 0.0002760000 0.0259500000 10555930 96830484 1769005056 3.7694170475 3.3013234138 6.8341236115 1100 43.9600000000 1.8554501534 0.1953319669 2.0269024372 0.0280324884 0.1277280000 0.0107330000 0.0749620000 0.0000280000 0.0003490000 0.0202930000 10557604 96830484 1770496000 3.7701427937 3.3047084808 6.8328628540 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:20:41 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002853 0.0000002853 0.0000002853 nan 0.1747810000 0.0762780000 0.0219870000 0.0000880000 0.0000100000 0.0755580000 7764882 96830484 1772503040 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0004263568 0.0002133210 0.0004263568 0.0040680924 0.0391100000 0.0130760000 0.0093190000 0.0000750000 0.0000060000 0.0162270000 7930668 96830484 1772032000 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0024013643 0.0009426688 0.0024013643 0.0044545736 0.0491100000 0.0220170000 0.0133120000 0.0001460000 0.0000070000 0.0132040000 7932666 96830484 1770487808 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0017003767 0.0011320958 0.0024013643 0.0049657424 0.0811460000 0.0258180000 0.0125340000 0.0002030000 0.0002660000 0.0420010000 7934688 96830484 1768964096 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0008904631 0.0010837692 0.0024013643 0.0044341990 0.1452690000 0.0098950000 0.0703630000 0.0004080000 0.0002720000 0.0640340000 7936682 96830484 1768566784 4.0000128746 3.9995694160 4.0000009537 6 0.2000000000 0.0008924180 0.0010518774 0.0024013643 0.0040874931 0.0945690000 0.0092570000 0.0627790000 0.0000050000 0.0000640000 0.0221640000 7939012 96830484 1770221568 4.0000438690 3.9984669685 3.9996929169 7 0.2400000000 0.0009205028 0.0010331096 0.0024013643 0.0037768928 0.1102520000 0.0122930000 0.0640200000 0.0002950000 0.0003820000 0.0329550000 7940686 96830484 1769107456 4.0000243187 3.9983050823 3.9996020794 8 0.2800000000 0.0010174970 0.0010311580 0.0024013643 0.0035595045 0.0853440000 0.0102520000 0.0455120000 0.0000220000 0.0003700000 0.0277070000 7942360 96830484 1770881024 4.0002613068 3.9996204376 4.0000276566 9 0.3200000000 0.0010310443 0.0010311454 0.0024013643 0.0033327653 0.1220660000 0.0123180000 0.0575900000 0.0003050000 0.0002710000 0.0512430000 7944674 96830484 1769598976 4.0004606247 3.9996557236 4.0000720024 10 0.3600000000 0.0011193384 0.0010399647 0.0024013643 0.0031528054 0.0865270000 0.0101920000 0.0473590000 0.0000230000 0.0003400000 0.0273740000 7947660 96830484 1771409408 4.0005087852 3.9990282059 3.9999020100 11 0.4000000000 0.0010719971 0.0010428767 0.0024013643 0.0029940128 0.1046140000 0.0117090000 0.0513080000 0.0003420000 0.0002730000 0.0396850000 7949334 96830484 1770233856 4.0003881454 3.9995760918 4.0000905991 12 0.4400000000 0.0010253791 0.0010414186 0.0024013643 0.0028624087 0.0933390000 0.0124790000 0.0600510000 0.0000050000 0.0000580000 0.0204440000 7951008 96830484 1768710144 4.0004520416 4.0003004074 4.0003967285 13 0.4800000000 0.0011115796 0.0010468156 0.0024013643 0.0027523682 0.1501920000 0.0098230000 0.0881650000 0.0002920000 0.0002630000 0.0512840000 7952682 96830484 1768202240 4.0002913475 4.0009531975 4.0007076263 14 0.5200000000 0.0010815189 0.0010492944 0.0024013643 0.0027276089 0.0927720000 0.0099040000 0.0530420000 0.0000220000 0.0003630000 0.0280310000 7954356 96830484 1769836544 4.0004343987 4.0009865761 4.0007877350 15 0.5600000000 0.0010699802 0.0010506734 0.0024013643 0.0027169424 0.1010590000 0.0114090000 0.0532040000 0.0002910000 0.0002620000 0.0339350000 7956030 96830484 1768857600 4.0004868507 4.0010123253 4.0008835793 16 0.6000000000 0.0011194879 0.0010549744 0.0024013643 0.0026457905 0.0789770000 0.0098470000 0.0384020000 0.0000230000 0.0003510000 0.0287960000 7957704 96830484 1770479616 4.0009770393 4.0009307861 4.0008077621 17 0.6400000000 0.0012315910 0.0010653636 0.0024013643 0.0025688153 0.1231770000 0.0110580000 0.0454840000 0.0004260000 0.0002750000 0.0636770000 7960658 96830484 1769345024 4.0008697510 4.0009241104 4.0008525848 18 0.6800000000 0.0012707551 0.0010767742 0.0024013643 0.0025021948 0.0854790000 0.0100570000 0.0454300000 0.0000240000 0.0003080000 0.0277520000 7964956 96830484 1771171840 4.0009837151 4.0001974106 4.0006079674 19 0.7200000000 0.0011860826 0.0010825273 0.0024013643 0.0025409658 0.0997370000 0.0117730000 0.0602360000 0.0000600000 0.0000520000 0.0272530000 7966630 96830484 1769979904 4.0008993149 4.0001869202 4.0005216599 20 0.7600000000 0.0011695086 0.0010868763 0.0024013643 0.0026358235 0.0871630000 0.0103370000 0.0455210000 0.0000260000 0.0003550000 0.0292290000 7968304 96830484 1770782720 4.0006675720 3.9999303818 4.0004429817 21 0.8000000000 0.0012403087 0.0010941826 0.0024013643 0.0027462599 0.1576910000 0.0096510000 0.0809550000 0.0065030000 0.0002840000 0.0585590000 7969978 96830484 1767104512 4.0006680489 3.9998667240 4.0002846718 22 0.8400000000 0.0012322606 0.0011004589 0.0024013643 0.0027265617 0.0864560000 0.0098310000 0.0465100000 0.0000230000 0.0003150000 0.0279360000 7971652 96830484 1765900288 4.0007176399 4.0000534058 4.0004005432 23 0.8800000000 0.0012373297 0.0011064098 0.0024013643 0.0027026273 0.1176640000 0.0179850000 0.0598380000 0.0003080000 0.0003470000 0.0364820000 7973326 96830484 1764823040 4.0004849434 3.9998307228 4.0003304482 24 0.9200000000 0.0013181235 0.0011152312 0.0024013643 0.0026499258 0.1011820000 0.0099680000 0.0582780000 0.0000210000 0.0002770000 0.0306600000 7975000 96830484 1766309888 4.0005640984 4.0000424385 4.0003299713 25 0.9600000000 0.0013123177 0.0011231147 0.0024013643 0.0025964770 0.0995680000 0.0099370000 0.0357150000 0.0002780000 0.0003440000 0.0528230000 7976674 96830484 1767936000 4.0003499985 3.9999787807 4.0003352165 26 1.0000000000 0.0013829001 0.0011331064 0.0024013643 0.0025456390 0.1439940000 0.0092340000 0.1104800000 0.0000270000 0.0030680000 0.0207210000 7978348 96830484 1769713664 4.0005507469 4.0002999306 4.0003790855 27 1.0400000000 0.0014670226 0.0011454737 0.0024013643 0.0025022724 0.0819000000 0.0109350000 0.0397670000 0.0002890000 0.0003450000 0.0300680000 7980022 96830484 1768747008 4.0003237724 4.0003519058 4.0003657341 28 1.0800000000 0.0014611657 0.0011567484 0.0024013643 0.0024759814 0.0878750000 0.0107460000 0.0420560000 0.0000250000 0.0002980000 0.0326730000 7981696 96830484 1767608320 4.0002403259 4.0002017021 4.0003986359 29 1.1200000000 0.0013485512 0.0011633623 0.0024013643 0.0024415039 0.1031010000 0.0093410000 0.0341370000 0.0006980000 0.0002950000 0.0581110000 7983370 96830484 1766440960 3.9998297691 4.0003528595 4.0005002022 30 1.1600000000 0.0014573594 0.0011731622 0.0024013643 0.0024130366 0.1135340000 0.0095570000 0.0706680000 0.0000220000 0.0002930000 0.0307830000 7985044 96830484 1765392384 4.0000948906 4.0008740425 4.0004773140 31 1.2000000000 0.0013882328 0.0011801000 0.0024013643 0.0023909813 0.0961160000 0.0097770000 0.0497520000 0.0002890000 0.0002660000 0.0334480000 7986718 96830484 1765560320 3.9998567104 4.0005626678 4.0004510880 32 1.2400000000 0.0013819920 0.0011864091 0.0024013643 0.0023575941 0.0748900000 0.0099520000 0.0383470000 0.0000270000 0.0002900000 0.0257180000 7988392 96830484 1765560320 3.9996068478 4.0001568794 4.0004105568 33 1.2800000000 0.0013964027 0.0011927725 0.0024013643 0.0023527156 0.1037130000 0.0092690000 0.0360100000 0.0002130000 0.0001720000 0.0574850000 7992626 96830484 1765449728 3.9994215965 4.0002517700 4.0005779266 34 1.3200000000 0.0015335578 0.0012027956 0.0024013643 0.0023416842 0.0847020000 0.0093880000 0.0437320000 0.0000260000 0.0003010000 0.0287360000 7999548 96830484 1765560320 3.9990336895 4.0000863075 4.0006408691 35 1.3600000000 0.0013553273 0.0012071537 0.0024013643 0.0023247530 0.1037500000 0.0094200000 0.0623510000 0.0005690000 0.0000570000 0.0307880000 8001222 96830484 1765560320 3.9986040592 3.9990754128 4.0003924370 36 1.4000000000 0.0014277544 0.0012132815 0.0024013643 0.0022981342 0.1345130000 0.0119290000 0.0919870000 0.0000230000 0.0002780000 0.0278350000 8002896 96830484 1765429248 3.9982192516 3.9990477562 4.0003800392 37 1.4400000000 0.0012861796 0.0012152517 0.0024013643 0.0022667143 0.1092730000 0.0106770000 0.0460250000 0.0003140000 0.0002760000 0.0513890000 8004570 96830484 1765269504 3.9978499413 3.9995603561 4.0005798340 38 1.4800000000 0.0011958727 0.0012147417 0.0024013643 0.0022359189 0.0983770000 0.0137520000 0.0542850000 0.0000240000 0.0002810000 0.0269700000 8006244 96830484 1767092224 3.9974386692 3.9990320206 4.0006051064 39 1.5200000000 0.0011726121 0.0012136615 0.0024013643 0.0022165721 0.0898400000 0.0095850000 0.0453940000 0.0003250000 0.0002780000 0.0334940000 8007918 96830484 1768812544 3.9967052937 3.9975490570 4.0002336502 40 1.5600000000 0.0010570704 0.0012097467 0.0024013643 0.0022941811 0.0887240000 0.0094470000 0.0495310000 0.0000250000 0.0002840000 0.0278880000 8009592 96830484 1770340352 3.9962735176 3.9979026318 4.0006465912 41 1.6000000000 0.0010635647 0.0012061813 0.0024013643 0.0024324360 0.1275140000 0.0117260000 0.0649330000 0.0003140000 0.0002620000 0.0496060000 8011266 96830484 1769463808 3.9959044456 3.9991254807 4.0013785362 42 1.6400000000 0.0011623406 0.0012051375 0.0024013643 0.0025074717 0.1025990000 0.0098180000 0.0618250000 0.0000250000 0.0002850000 0.0273750000 8012940 96830484 1771036672 3.9952692986 3.9989507198 4.0017290115 43 1.6800000000 0.0012297792 0.0012057105 0.0024013643 0.0025127899 0.1036930000 0.0119860000 0.0547120000 0.0003230000 0.0003430000 0.0333490000 8014614 96830484 1769992192 3.9949560165 3.9988994598 4.0022759438 44 1.7200000000 0.0012580901 0.0012069010 0.0024013643 0.0024945604 0.1078410000 0.0119320000 0.0647370000 0.0000240000 0.0002940000 0.0272810000 8016288 96830484 1768448000 3.9945409298 3.9993011951 4.0029430389 45 1.7600000000 0.0012211995 0.0012072187 0.0024013643 0.0024892343 0.1426390000 0.0107150000 0.0795270000 0.0002850000 0.0002790000 0.0510500000 8017962 96830484 1770143744 3.9943313599 3.9987676144 4.0034589767 46 1.8000000000 0.0012830474 0.0012088672 0.0024013643 0.0026051945 0.0970320000 0.0117440000 0.0544340000 0.0000240000 0.0002770000 0.0274010000 8019636 96830484 1768976384 3.9941344261 3.9977028370 4.0039982796 47 1.8400000000 0.0012388101 0.0012095042 0.0024013643 0.0027733762 0.0888550000 0.0106090000 0.0438050000 0.0003850000 0.0002730000 0.0330520000 8021310 96830484 1768050688 3.9941861629 3.9972200394 4.0049424171 48 1.8800000000 0.0011569478 0.0012084093 0.0024013643 0.0029400860 0.0906310000 0.0101060000 0.0491040000 0.0000280000 0.0009830000 0.0273940000 8022984 96830484 1767067648 3.9939656258 3.9970407486 4.0063562393 49 1.9200000000 0.0011786200 0.0012078014 0.0024013643 0.0032211395 0.1128110000 0.0102020000 0.0535530000 0.0002960000 0.0003390000 0.0477000000 8024658 96830484 1766195200 3.9939444065 3.9956638813 4.0073828697 50 1.9600000000 0.0011949798 0.0012075449 0.0024013643 0.0035129401 0.0837000000 0.0094670000 0.0518810000 0.0000260000 0.0003400000 0.0211480000 8026332 96830484 1765556224 3.9939002991 3.9951593876 4.0089011192 51 2.0000000000 0.0012242892 0.0012078733 0.0024013643 0.0036898125 0.0957750000 0.0094260000 0.0466240000 0.0003040000 0.0003020000 0.0384160000 8028006 96830484 1765548032 3.9940006733 3.9953744411 4.0108098984 52 2.0400000000 0.0012690393 0.0012090495 0.0024013643 0.0038263259 0.0891960000 0.0093260000 0.0435910000 0.0000250000 0.0003000000 0.0342370000 8029680 96830484 1765552128 3.9946217537 3.9952757359 4.0127325058 53 2.0800000000 0.0013042438 0.0012108457 0.0024013643 0.0038931909 0.1059880000 0.0095570000 0.0425480000 0.0002900000 0.0002640000 0.0525580000 8031354 96830484 1765421056 3.9949836731 3.9940834045 4.0143833160 54 2.1200000000 0.0013371716 0.0012131850 0.0024013643 0.0039584605 0.0940590000 0.0095300000 0.0483630000 0.0000270000 0.0002830000 0.0320060000 8033028 96830484 1765568512 3.9960272312 3.9933788776 4.0161623955 55 2.1600000000 0.0013001428 0.0012147661 0.0024013643 0.0039625648 0.1295350000 0.0095060000 0.0789030000 0.0003930000 0.0002710000 0.0371550000 8034702 96830484 1765552128 3.9962956905 3.9936251640 4.0186734200 56 2.2000000000 0.0012267811 0.0012149806 0.0024013643 0.0039411824 0.1348630000 0.0093200000 0.0950500000 0.0000260000 0.0003850000 0.0263780000 8036376 96830484 1765511168 3.9967105389 3.9938147068 4.0211811066 57 2.2400000000 0.0012754892 0.0012160422 0.0024013643 0.0039562350 0.1081680000 0.0101080000 0.0439370000 0.0003760000 0.0003130000 0.0526040000 8038050 96830484 1767178240 3.9978790283 3.9937641621 4.0235881805 58 2.2800000000 0.0013237124 0.0012178986 0.0024013643 0.0040153706 0.0942990000 0.0101390000 0.0545270000 0.0000230000 0.0003580000 0.0257990000 8039724 96830484 1768939520 3.9985756874 3.9948427677 4.0264348984 59 2.3200000000 0.0013910081 0.0012208326 0.0024013643 0.0041142095 0.1097120000 0.0101120000 0.0623070000 0.0003000000 0.0002730000 0.0334610000 8041398 96830484 1770717184 3.9998767376 3.9946329594 4.0290808678 60 2.3600000000 0.0013994109 0.0012238089 0.0024013643 0.0044158742 0.0851320000 0.0117500000 0.0433920000 0.0000280000 0.0002830000 0.0259960000 8043072 96830484 1769717760 4.0008139610 3.9933297634 4.0314803123 61 2.4000000000 0.0014367197 0.0012272993 0.0024013643 0.0046786380 0.1097840000 0.0121570000 0.0533090000 0.0002880000 0.0003400000 0.0425510000 8044746 96830484 1768210432 4.0022435188 3.9933090210 4.0344052315 62 2.4400000000 0.0014479064 0.0012308574 0.0024013643 0.0049280888 0.0948380000 0.0148040000 0.0492850000 0.0000260000 0.0003080000 0.0266580000 8046420 96830484 1769873408 4.0035200119 3.9932498932 4.0373091698 63 2.4800000000 0.0015667058 0.0012361884 0.0024013643 0.0051107482 0.1078570000 0.0116770000 0.0540090000 0.0052850000 0.0003960000 0.0327640000 8048094 96830484 1768738816 4.0050268173 3.9926965237 4.0400228500 64 2.5200000000 0.0015472904 0.0012410493 0.0024013643 0.0052491835 0.0872530000 0.0100820000 0.0460910000 0.0000270000 0.0003440000 0.0269810000 8049768 96830484 1770209280 4.0066490173 3.9929873943 4.0431866646 65 2.5600000000 0.0015366236 0.0012455966 0.0024013643 0.0054903956 0.1258270000 0.0118870000 0.0562510000 0.0003080000 0.0006620000 0.0557910000 8056562 96830484 1769209856 4.0079746246 3.9925370216 4.0460400581 66 2.6000000000 0.0013394416 0.0012470185 0.0024013643 0.0058370429 0.0940200000 0.0096620000 0.0539200000 0.0000240000 0.0003180000 0.0281990000 8068732 96830484 1771016192 4.0095305443 3.9914574623 4.0485444069 67 2.6400000000 0.0012955776 0.0012477433 0.0024013643 0.0061143238 0.0892960000 0.0112720000 0.0408340000 0.0002910000 0.0003800000 0.0330800000 8070406 96830484 1770225664 4.0115537643 3.9929044247 4.0518612862 68 2.6800000000 0.0013073327 0.0012486196 0.0024013643 0.0065270744 0.0940410000 0.0120410000 0.0500380000 0.0000260000 0.0002780000 0.0277130000 8072080 96830484 1768468480 4.0118260384 3.9931588173 4.0547127724 69 2.7200000000 0.0013390359 0.0012499300 0.0024013643 0.0067401505 0.1071540000 0.0104090000 0.0443190000 0.0004240000 0.0002790000 0.0507630000 8073754 96830484 1770127360 4.0137872696 3.9922811985 4.0573821068 70 2.7600000000 0.0013638253 0.0012515571 0.0024013643 0.0068657155 0.0897640000 0.0120490000 0.0454120000 0.0000240000 0.0003120000 0.0276880000 8075428 96830484 1768189952 4.0153470039 3.9915506840 4.0598607063 71 2.8000000000 0.0013766864 0.0012533195 0.0024013643 0.0068893128 0.0927310000 0.0105010000 0.0534010000 0.0003140000 0.0003420000 0.0270580000 8077102 96830484 1767206912 4.0166683197 3.9922487736 4.0628995895 72 2.8400000000 0.0013541374 0.0012547197 0.0024013643 0.0068806046 0.0943200000 0.0104120000 0.0493540000 0.0000230000 0.0010470000 0.0283140000 8078776 96830484 1766440960 4.0180339813 3.9920051098 4.0655674934 73 2.8800000000 0.0012587614 0.0012547751 0.0024013643 0.0068674255 0.1204790000 0.0106150000 0.0507650000 0.0003640000 0.0002770000 0.0542010000 8080450 96830484 1768177664 4.0192093849 3.9914391041 4.0680284500 74 2.9200000000 0.0012515987 0.0012547321 0.0024013643 0.0068798873 0.0893540000 0.0105290000 0.0467190000 0.0000260000 0.0007130000 0.0271030000 8082124 96830484 1769967616 4.0207333565 3.9922778606 4.0709123611 75 2.9600000000 0.0013581816 0.0012561115 0.0024013643 0.0069512893 0.1206380000 0.0118850000 0.0663730000 0.0003220000 0.0003420000 0.0369350000 8083798 96830484 1768980480 4.0221443176 3.9927165508 4.0736103058 76 3.0000000000 0.0013362435 0.0012571658 0.0024013643 0.0071194331 0.0860150000 0.0097680000 0.0442430000 0.0000250000 0.0002870000 0.0272900000 8085472 96830484 1770618880 4.0236077309 3.9914739132 4.0757899284 77 3.0400000000 0.0013311761 0.0012581270 0.0024013643 0.0072809941 0.1180800000 0.0122290000 0.0458320000 0.0003870000 0.0037070000 0.0514860000 8087146 96830484 1768701952 4.0247716904 3.9902968407 4.0779018402 78 3.0800000000 0.0012353440 0.0012578349 0.0024013643 0.0075056549 0.0979320000 0.0107760000 0.0538900000 0.0000240000 0.0003000000 0.0277540000 8088820 96830484 1770110976 4.0259861946 3.9909839630 4.0807232857 79 3.1200000000 0.0012282730 0.0012574607 0.0024013643 0.0077088095 0.0943960000 0.0129000000 0.0448810000 0.0003160000 0.0005140000 0.0345960000 8090494 96830484 1768321024 4.0267004967 3.9912035465 4.0834503174 80 3.1600000000 0.0012710938 0.0012576311 0.0024013643 0.0078497568 0.0880910000 0.0099050000 0.0454500000 0.0000260000 0.0003210000 0.0293960000 8092168 96830484 1769111552 4.0278968811 3.9901616573 4.0856742859 81 3.2000000000 0.0013442001 0.0012586999 0.0024013643 0.0079963056 0.1150430000 0.0098370000 0.0470820000 0.0002900000 0.0002780000 0.0564690000 8093842 96830484 1767849984 4.0293869972 3.9899580479 4.0881948471 82 3.2400000000 0.0013728106 0.0012600915 0.0024013643 0.0081719659 0.0884970000 0.0096890000 0.0556000000 0.0000230000 0.0003770000 0.0217690000 8095516 96830484 1767321600 4.0297856331 3.9897851944 4.0907039642 83 3.2800000000 0.0013288729 0.0012609202 0.0024013643 0.0083565636 0.0943000000 0.0096640000 0.0546580000 0.0003580000 0.0002640000 0.0283270000 8097190 96830484 1766793216 4.0308146477 3.9888329506 4.0930981636 84 3.3200000000 0.0013389493 0.0012618491 0.0024013643 0.0084583802 0.0994570000 0.0096620000 0.0497220000 0.0000260000 0.0002840000 0.0386980000 8098864 96830484 1766563840 4.0314378738 3.9886620045 4.0956315994 85 3.3600000000 0.0013309265 0.0012626618 0.0024013643 0.0085292937 0.1247680000 0.0097120000 0.0587530000 0.0003050000 0.0005070000 0.0508480000 8100538 96830484 1766178816 4.0319433212 3.9890480042 4.0983991623 86 3.4000000000 0.0014413312 0.0012647393 0.0024013643 0.0085879649 0.0956150000 0.0103430000 0.0544100000 0.0000270000 0.0002840000 0.0290140000 8102212 96830484 1765670912 4.0329508781 3.9889979362 4.1009740829 87 3.4400000000 0.0013955272 0.0012662426 0.0024013643 0.0086606218 0.0889710000 0.0099030000 0.0377790000 0.0001920000 0.0001700000 0.0373580000 8103886 96830484 1765552128 4.0337600708 3.9890086651 4.1038231850 88 3.4800000000 0.0014646816 0.0012684976 0.0024013643 0.0087458397 0.1042500000 0.0096980000 0.0549240000 0.0000260000 0.0003900000 0.0340100000 8105560 96830484 1765441536 4.0344743729 3.9887464046 4.1065802574 89 3.5200000000 0.0014265880 0.0012702739 0.0024013643 0.0088275947 0.1400790000 0.0095060000 0.0711340000 0.0003930000 0.0002660000 0.0576250000 8107234 96830484 1765662720 4.0353183746 3.9887371063 4.1094856262 90 3.5600000000 0.0014380789 0.0012721384 0.0024013643 0.0089453926 0.0906690000 0.0105220000 0.0446830000 0.0000240000 0.0003540000 0.0300260000 8108908 96830484 1767161856 4.0356011391 3.9887697697 4.1124491692 91 3.6000000000 0.0014345699 0.0012739234 0.0024013643 0.0090832542 0.0925870000 0.0099010000 0.0464650000 0.0003480000 0.0003520000 0.0344370000 8110582 96830484 1768841216 4.0369496346 3.9882011414 4.1154465675 92 3.6400000000 0.0014698324 0.0012760528 0.0024013643 0.0091712853 0.0896690000 0.0095930000 0.0468570000 0.0000250000 0.0003150000 0.0317600000 8112256 96830484 1770717184 4.0373930931 3.9879958630 4.1186227798 93 3.6800000000 0.0014295292 0.0012777031 0.0024013643 0.0091733737 0.1240660000 0.0105750000 0.0536380000 0.0002880000 0.0003750000 0.0580750000 8113930 96830484 1769725952 4.0377421379 3.9874362946 4.1215591431 94 3.7200000000 0.0015629446 0.0012807376 0.0024013643 0.0091513579 0.1333790000 0.0090380000 0.0910170000 0.0000240000 0.0003120000 0.0290310000 8115604 96830484 1771417600 4.0387754440 3.9877820015 4.1247434616 95 3.7600000000 0.0014664904 0.0012826929 0.0024013643 0.0091397680 0.1387040000 0.0110400000 0.0858040000 0.0000570000 0.0000690000 0.0361600000 8117278 96830484 1770733568 4.0395660400 3.9874782562 4.1277995110 96 3.8000000000 0.0015266920 0.0012852345 0.0024013643 0.0091595697 0.1320930000 0.0114040000 0.0881160000 0.0000260000 0.0003550000 0.0300100000 8118952 96830484 1768464384 4.0404410362 3.9876890182 4.1310448647 97 3.8400000000 0.0014426031 0.0012868569 0.0024013643 0.0092730314 0.1082590000 0.0094030000 0.0450430000 0.0004180000 0.0002770000 0.0518610000 8120626 96830484 1770352640 4.0409975052 3.9890539646 4.1346793175 98 3.8800000000 0.0015764389 0.0012898118 0.0024013643 0.0093988403 0.0891770000 0.0109790000 0.0533850000 0.0001050000 0.0003470000 0.0231230000 8122300 96830484 1768304640 4.0415439606 3.9890565872 4.1378221512 99 3.9200000000 0.0015620911 0.0012925621 0.0024013643 0.0095290996 0.1076980000 0.0105290000 0.0493160000 0.0002860000 0.0002690000 0.0412240000 8123974 96830484 1766539264 4.0424971581 3.9890418053 4.1410441399 100 3.9600000000 0.0015781928 0.0012954184 0.0024013643 0.0096405830 0.1069560000 0.0090340000 0.0542660000 0.0000250000 0.0002830000 0.0372990000 8125648 96830484 1768321024 4.0426778793 3.9906759262 4.1446580887 101 4.0000000000 0.0016550687 0.0012989793 0.0024013643 0.0096923369 0.1426460000 0.0089380000 0.0594420000 0.0002480000 0.0001840000 0.0725560000 8127322 96830484 1769857024 4.0432066917 3.9913110733 4.1480350494 102 4.0400000000 0.0016607278 0.0013025259 0.0024013643 0.0097058081 0.1015000000 0.0085600000 0.0631330000 0.0000240000 0.0002920000 0.0282410000 8128996 96830484 1771618304 4.0438342094 3.9909965992 4.1509776115 103 4.0800000000 0.0016057324 0.0013054696 0.0024013643 0.0097175362 0.0980060000 0.0107870000 0.0431440000 0.0003120000 0.0002680000 0.0374640000 8130670 96830484 1770741760 4.0442304611 3.9921641350 4.1543788910 104 4.1200000000 0.0016009047 0.0013083103 0.0024013643 0.0097229660 0.1079640000 0.0109440000 0.0600570000 0.0000240000 0.0002890000 0.0308170000 8132344 96830484 1768955904 4.0450763702 3.9921970367 4.1575145721 105 4.1600000000 0.0016837718 0.0013118862 0.0024013643 0.0097316074 0.1192470000 0.0090030000 0.0519870000 0.0003210000 0.0003530000 0.0563550000 8134018 96830484 1770491904 4.0454797745 3.9924025536 4.1602501869 106 4.2000000000 0.0017371137 0.0013158977 0.0024013643 0.0097231318 0.0944730000 0.0106440000 0.0443560000 0.0000260000 0.0003150000 0.0333360000 8135692 96830484 1768558592 4.0450906754 3.9930028915 4.1630754471 107 4.2400000000 0.0016481511 0.0013190029 0.0024013643 0.0096982451 0.1135070000 0.0085230000 0.0564740000 0.0003030000 0.0003640000 0.0465810000 8137366 96830484 1768329216 4.0459651947 3.9923737049 4.1655440331 108 4.2800000000 0.0018961935 0.0013243473 0.0024013643 0.0096909128 0.1012770000 0.0084070000 0.0488380000 0.0000270000 0.0002990000 0.0377180000 8139040 96830484 1767972864 4.0455574989 3.9932904243 4.1682977676 109 4.3200000000 0.0019822565 0.0013303831 0.0024013643 0.0096752097 0.1303370000 0.0151880000 0.0525830000 0.0003570000 0.0002680000 0.0605410000 8140714 96830484 1767321600 4.0455923080 3.9941506386 4.1709680557 110 4.3600000000 0.0022053255 0.0013383372 0.0024013643 0.0096392675 0.1141260000 0.0083160000 0.0682440000 0.0000250000 0.0003790000 0.0358390000 8142388 96830484 1766572032 4.0455455780 3.9943721294 4.1735172272 111 4.4000000000 0.0022988003 0.0013469900 0.0024013643 0.0096070853 0.1014190000 0.0093480000 0.0455230000 0.0003830000 0.0002710000 0.0397480000 8144062 96830484 1768304640 4.0458831787 3.9945197105 4.1760668755 112 4.4400000000 0.0026349439 0.0013584896 0.0026349439 0.0095758182 0.0914070000 0.0087000000 0.0463190000 0.0000240000 0.0004160000 0.0329360000 8145736 96830484 1769959424 4.0459933281 3.9948046207 4.1784667969 113 4.4800000000 0.0022356219 0.0013662518 0.0026349439 0.0095420756 0.1297820000 0.0101850000 0.0605920000 0.0003190000 0.0003500000 0.0569180000 8147410 96830484 1768865792 4.0459771156 3.9952754974 4.1809144020 114 4.5200000000 0.0025524187 0.0013766568 0.0026349439 0.0095111189 0.0910210000 0.0081610000 0.0505250000 0.0000280000 0.0003120000 0.0305530000 8149084 96830484 1770590208 4.0460453033 3.9952294827 4.1833209991 115 4.5600000000 0.0022748113 0.0013844668 0.0026349439 0.0094809264 0.1076550000 0.0106180000 0.0556390000 0.0003360000 0.0003620000 0.0393130000 8150758 96830484 1769463808 4.0466914177 3.9950575829 4.1856937408 116 4.6000000000 0.0025496732 0.0013945117 0.0026349439 0.0094621783 0.0997540000 0.0088000000 0.0500450000 0.0000260000 0.0003060000 0.0342320000 8152432 96830484 1771163648 4.0462737083 3.9958226681 4.1882610321 117 4.6400000000 0.0024480575 0.0014035164 0.0026349439 0.0094308476 0.1131710000 0.0103600000 0.0438510000 0.0003120000 0.0002730000 0.0570070000 8154106 96830484 1769865216 4.0465641022 3.9954583645 4.1907124519 118 4.6800000000 0.0023190347 0.0014112750 0.0026349439 0.0094032024 0.1017360000 0.0082110000 0.0523300000 0.0000260000 0.0003050000 0.0337370000 8155780 96830484 1771671552 4.0467944145 3.9956858158 4.1934103966 119 4.7200000000 0.0026350615 0.0014215589 0.0026350615 0.0093784268 0.1042170000 0.0104170000 0.0447930000 0.0003150000 0.0002790000 0.0414860000 8157454 96830484 1770479616 4.0469322205 3.9958076477 4.1963582039 120 4.7600000000 0.0024013666 0.0014297240 0.0026350615 0.0093522262 0.0919030000 0.0106780000 0.0428410000 0.0000260000 0.0010730000 0.0350190000 8159128 96830484 1768955904 4.0472464561 3.9953985214 4.1991333961 121 4.8000000000 0.0026273816 0.0014396220 0.0026350615 0.0093408900 0.1170610000 0.0089400000 0.0415130000 0.0002890000 0.0002700000 0.0646480000 8160802 96830484 1768067072 4.0473222733 3.9957587719 4.2021789551 122 4.8400000000 0.0027005586 0.0014499575 0.0027005586 0.0093460686 0.0981660000 0.0083220000 0.0452690000 0.0000280000 0.0002900000 0.0374830000 8162476 96830484 1769639936 4.0472588539 3.9957723618 4.2052578926 123 4.8800000000 0.0025119300 0.0014585914 0.0027005586 0.0093302579 0.1249190000 0.0092090000 0.0575810000 0.0003550000 0.0002700000 0.0501240000 8164150 96830484 1768431616 4.0475778580 3.9959456921 4.2084355354 124 4.9200000000 0.0025871738 0.0014676929 0.0027005586 0.0093076143 0.1116350000 0.0078470000 0.0558790000 0.0000240000 0.0003000000 0.0461580000 8165824 96830484 1770074112 4.0475702286 3.9963126183 4.2114996910 125 4.9600000000 0.0025633324 0.0014764580 0.0027005586 0.0092862602 0.1411620000 0.0093690000 0.0533450000 0.0002820000 0.0002630000 0.0702010000 8167498 96830484 1768984576 4.0478949547 3.9966378212 4.2147974968 126 5.0000000000 0.0025024523 0.0014846008 0.0027005586 0.0092723526 0.0921480000 0.0082670000 0.0401270000 0.0000280000 0.0002860000 0.0366750000 8169172 96830484 1770717184 4.0482387543 3.9965846539 4.2179398537 127 5.0400000000 0.0025049387 0.0014926350 0.0027005586 0.0092729152 0.1101580000 0.0101420000 0.0496560000 0.0003130000 0.0002810000 0.0427710000 8170846 96830484 1769963520 4.0486574173 3.9965469837 4.2212061882 128 5.0800000000 0.0025768946 0.0015011058 0.0027005586 0.0092891114 0.0907440000 0.0083740000 0.0433320000 0.0000290000 0.0003720000 0.0370960000 8172520 96830484 1771536384 4.0490622520 3.9970891476 4.2243766785 129 5.1200000000 0.0025956230 0.0015095904 0.0027005586 0.0092737978 0.1221740000 0.0102890000 0.0438750000 0.0010530000 0.0003470000 0.0650830000 8184434 96830484 1770598400 4.0496373177 3.9972116947 4.2274990082 130 5.1600000000 0.0026314589 0.0015182202 0.0027005586 0.0092616413 0.0953130000 0.0100620000 0.0434940000 0.0000260000 0.0002830000 0.0369030000 8207100 96830484 1769074688 4.0502395630 3.9965333939 4.2301149368 131 5.2000000000 0.0025434366 0.0015260462 0.0027005586 0.0092510251 0.1039520000 0.0090540000 0.0422210000 0.0002890000 0.0004520000 0.0438760000 8208774 96830484 1768169472 4.0508980751 3.9966843128 4.2329154015 132 5.2400000000 0.0026016450 0.0015341947 0.0027005586 0.0092305507 0.0907080000 0.0084000000 0.0383420000 0.0000290000 0.0003070000 0.0399590000 8210448 96830484 1769996288 4.0511703491 3.9972362518 4.2358617783 133 5.2800000000 0.0026717728 0.0015427479 0.0027005586 0.0092243234 0.1276830000 0.0092270000 0.0380640000 0.0000810000 0.0000700000 0.0786690000 8212122 96830484 1768841216 4.0518441200 3.9967846870 4.2383956909 134 5.3200000000 0.0027758901 0.0015519505 0.0027758901 0.0092514404 0.0921520000 0.0074190000 0.0441950000 0.0000260000 0.0002890000 0.0385980000 8213796 96830484 1770582016 4.0523681641 3.9975247383 4.2414250374 135 5.3600000000 0.0027001395 0.0015604556 0.0027758901 0.0092517736 0.1075330000 0.0095610000 0.0427870000 0.0002920000 0.0002620000 0.0477020000 8215470 96830484 1769328640 4.0528984070 3.9970822334 4.2437057495 136 5.4000000000 0.0026215245 0.0015682576 0.0027758901 0.0092567138 0.0930150000 0.0077180000 0.0427790000 0.0000260000 0.0003590000 0.0405550000 8217144 96830484 1771155456 4.0536756516 3.9962749481 4.2459983826 137 5.4400000000 0.0026483235 0.0015761413 0.0027758901 0.0092552502 0.1209900000 0.0094790000 0.0355060000 0.0004650000 0.0002750000 0.0736260000 8218818 96830484 1769984000 4.0544657707 3.9961190224 4.2485060692 138 5.4800000000 0.0026965665 0.0015842603 0.0027758901 0.0092368075 0.0929140000 0.0103750000 0.0445130000 0.0000270000 0.0003160000 0.0360880000 8220492 96830484 1768439808 4.0548753738 3.9962399006 4.2508177757 139 5.5200000000 0.0026052739 0.0015916057 0.0027758901 0.0092264308 0.1058320000 0.0082200000 0.0423880000 0.0002860000 0.0003370000 0.0490640000 8222166 96830484 1767964672 4.0552797318 3.9959280491 4.2530798912 140 5.5600000000 0.0026142835 0.0015989105 0.0027758901 0.0092196837 0.1043620000 0.0078290000 0.0381970000 0.0000190000 0.0002030000 0.0506680000 8223840 96830484 1769693184 4.0555324554 3.9954445362 4.2553372383 141 5.6000000000 0.0027038488 0.0016067470 0.0027758901 0.0092729866 0.1508300000 0.0088070000 0.0469400000 0.0003230000 0.0002710000 0.0927780000 8225514 96830484 1768841216 4.0556139946 3.9952225685 4.2596135139 142 5.6400000000 0.0026833189 0.0016143285 0.0027758901 0.0092805205 0.1031980000 0.0077880000 0.0441600000 0.0000230000 0.0003040000 0.0431640000 8227188 96830484 1770647552 4.0555038452 3.9946830273 4.2616534233 143 5.6800000000 0.0026453545 0.0016215385 0.0027758901 0.0092843483 0.1260780000 0.0098560000 0.0442140000 0.0003030000 0.0002790000 0.0634370000 8228862 96830484 1768587264 4.0553526878 3.9941895008 4.2635569572 144 5.7200000000 0.0026856114 0.0016289278 0.0027758901 0.0092820904 0.1320880000 0.0079390000 0.0728380000 0.0000230000 0.0002850000 0.0492890000 8230536 96830484 1770360832 4.0548710823 3.9943263531 4.2655372620 145 5.7600000000 0.0026787941 0.0016361683 0.0027758901 0.0092722383 0.1451050000 0.0091770000 0.0491550000 0.0002870000 0.0003400000 0.0844440000 8232210 96830484 1769472000 4.0542469025 3.9943141937 4.2673048973 146 5.8000000000 0.0027291819 0.0016436547 0.0027758901 0.0092748619 0.0924040000 0.0077010000 0.0346910000 0.0000230000 0.0002860000 0.0437620000 8233884 96830484 1771122688 4.0536336899 3.9946136475 4.2692475319 147 5.8400000000 0.0027242089 0.0016510054 0.0027758901 0.0092669666 0.1100210000 0.0099970000 0.0385340000 0.0002860000 0.0003180000 0.0592390000 8235558 96830484 1768931328 4.0529651642 3.9937062263 4.2707901001 148 5.8800000000 0.0028221644 0.0016589186 0.0028221644 0.0092493951 0.1079950000 0.0079460000 0.0449370000 0.0000980000 0.0003110000 0.0497570000 8237232 96830484 1770610688 4.0520563126 3.9931044579 4.2721824646 149 5.9200000000 0.0028339420 0.0016668047 0.0028339420 0.0092330537 0.1464240000 0.0092820000 0.0449560000 0.0002960000 0.0002690000 0.0829390000 8238906 96830484 1769971712 4.0511012077 3.9930169582 4.2739372253 150 5.9600000000 0.0029182083 0.0016751474 0.0029182083 0.0092172710 0.0965250000 0.0084390000 0.0436800000 0.0000230000 0.0003830000 0.0422180000 8240580 96830484 1771544576 4.0501766205 3.9928839207 4.2759718895 151 6.0000000000 0.0028711273 0.0016830678 0.0029182083 0.0091987174 0.1081210000 0.0097740000 0.0417560000 0.0002890000 0.0003510000 0.0497560000 8242254 96830484 1770737664 4.0490541458 3.9926354885 4.2777309418 152 6.0400000000 0.0029137337 0.0016911643 0.0029182083 0.0091844494 0.0909280000 0.0102840000 0.0353520000 0.0000080000 0.0000750000 0.0435810000 8243928 96830484 1768960000 4.0479383469 3.9924621582 4.2796244621 153 6.0800000000 0.0029418555 0.0016993387 0.0029418555 0.0091728577 0.1464450000 0.0079060000 0.0480370000 0.0002900000 0.0006880000 0.0877810000 8245602 96830484 1767944192 4.0468635559 3.9922504425 4.2819447517 154 6.1200000000 0.0029907522 0.0017077245 0.0029907522 0.0091576775 0.1101030000 0.0080240000 0.0431540000 0.0000240000 0.0003650000 0.0463270000 8247276 96830484 1769717760 4.0456180573 3.9918870926 4.2839322090 155 6.1600000000 0.0029408217 0.0017156800 0.0029907522 0.0091388538 0.1283420000 0.0088350000 0.0476340000 0.0003980000 0.0038450000 0.0646060000 8248950 96830484 1768685568 4.0441985130 3.9916093349 4.2859573364 156 6.2000000000 0.0030319833 0.0017241178 0.0030319833 0.0091497873 0.1109010000 0.0074890000 0.0476740000 0.0000270000 0.0007690000 0.0531830000 8250624 96830484 1770369024 4.0413036346 3.9907805920 4.2901320457 157 6.2400000000 0.0031014769 0.0017328908 0.0031014769 0.0091330869 0.1442320000 0.0097360000 0.0432110000 0.0002870000 0.0003350000 0.0818650000 8252298 96830484 1769340928 4.0398936272 3.9907536507 4.2924480438 158 6.2800000000 0.0032223847 0.0017423180 0.0032223847 0.0091163764 0.1054820000 0.0083500000 0.0413420000 0.0000250000 0.0002880000 0.0470990000 8253972 96830484 1771020288 4.0383877754 3.9904356003 4.2944221497 159 6.3200000000 0.0033036214 0.0017521375 0.0033036214 0.0091034375 0.1327550000 0.0092490000 0.0543230000 0.0002910000 0.0003460000 0.0666950000 8255646 96830484 1770352640 4.0367465019 3.9903185368 4.2964587212 160 6.3600000000 0.0033698129 0.0017622480 0.0033698129 0.0090875694 0.1089880000 0.0098670000 0.0449110000 0.0000250000 0.0002860000 0.0520830000 8257320 96830484 1768468480 4.0351877213 3.9904718399 4.2985935211 161 6.4000000000 0.0033849219 0.0017723267 0.0033849219 0.0090780417 0.1421350000 0.0078240000 0.0460400000 0.0002850000 0.0006780000 0.0854740000 8258994 96830484 1770242048 4.0335125923 3.9904136658 4.3004894257 162 6.4400000000 0.0035173770 0.0017830986 0.0035173770 0.0090857619 0.1104400000 0.0097740000 0.0438320000 0.0000280000 0.0002870000 0.0478800000 8260668 96830484 1769320448 4.0317220688 3.9903278351 4.3023085594 163 6.4800000000 0.0035997031 0.0017942434 0.0035997031 0.0090781296 0.1524960000 0.0080850000 0.0562670000 0.0003950000 0.0002800000 0.0856330000 8262342 96830484 1771020288 4.0301604271 3.9904031754 4.3040108681 164 6.5200000000 0.0037345358 0.0018060745 0.0037345358 0.0090641848 0.1093390000 0.0103980000 0.0416120000 0.0000260000 0.0002880000 0.0552170000 8264016 96830484 1770123264 4.0286412239 3.9905653000 4.3060503006 165 6.5600000000 0.0038047947 0.0018181880 0.0038047947 0.0090561497 0.1638210000 0.0096690000 0.0532460000 0.0002890000 0.0003420000 0.0916280000 8265690 96830484 1768738816 4.0270605087 3.9904208183 4.3081288338 166 6.6000000000 0.0040374617 0.0018315571 0.0040374617 0.0090423206 0.1050910000 0.0084550000 0.0385540000 0.0000250000 0.0003460000 0.0480280000 8267364 96830484 1770496000 4.0255994797 3.9905817509 4.3100247383 167 6.6400000000 0.0040442823 0.0018448069 0.0040442823 0.0090326441 0.1481140000 0.0100210000 0.0501550000 0.0001960000 0.0001760000 0.0783660000 8269038 96830484 1768574976 4.0241127014 3.9909284115 4.3123121262 168 6.6800000000 0.0041584224 0.0018585784 0.0041584224 0.0090171208 0.1284190000 0.0083610000 0.0521810000 0.0000260000 0.0002810000 0.0582920000 8270712 96830484 1770000384 4.0226302147 3.9904491901 4.3138318062 169 6.7200000000 0.0042945938 0.0018729927 0.0042945938 0.0090030722 0.1693290000 0.0095050000 0.0472500000 0.0003680000 0.0002900000 0.1026990000 8272386 96830484 1769320448 4.0211429596 3.9903879166 4.3153066635 170 6.7600000000 0.0043234401 0.0018874071 0.0043234401 0.0089888776 0.0961750000 0.0084830000 0.0378110000 0.0000240000 0.0002910000 0.0476110000 8274060 96830484 1771114496 4.0200133324 3.9902353287 4.3170781136 171 6.8000000000 0.0043365904 0.0019017298 0.0043365904 0.0089762569 0.1283410000 0.0097020000 0.0488800000 0.0002850000 0.0003390000 0.0641590000 8275734 96830484 1770102784 4.0189852715 3.9894764423 4.3185844421 172 6.8400000000 0.0044666808 0.0019166423 0.0044666808 0.0089602376 0.1127630000 0.0100550000 0.0479030000 0.0000230000 0.0003110000 0.0525060000 8277408 96830484 1768468480 4.0178108215 3.9890506268 4.3197150230 173 6.8800000000 0.0044137668 0.0019310766 0.0044666808 0.0089458006 0.1525520000 0.0083750000 0.0499690000 0.0002860000 0.0002660000 0.0917680000 8279082 96830484 1770110976 4.0168619156 3.9884915352 4.3206958771 174 6.9200000000 0.0044525922 0.0019455681 0.0044666808 0.0089553433 0.1039820000 0.0108850000 0.0436730000 0.0000250000 0.0002830000 0.0472440000 8280756 96830484 1769250816 4.0160193443 3.9880197048 4.3217554092 175 6.9600000000 0.0044329097 0.0019597814 0.0044666808 0.0089736755 0.1276710000 0.0081360000 0.0545590000 0.0008470000 0.0002980000 0.0591350000 8282430 96830484 1770999808 4.0151820183 3.9874148369 4.3228988647 176 7.0000000000 0.0044302964 0.0019738185 0.0044666808 0.0089827019 0.1459320000 0.0097600000 0.0607240000 0.0000300000 0.0003650000 0.0698510000 8284104 96830484 1770209280 4.0143356323 3.9869196415 4.3235540390 177 7.0400000000 0.0044811126 0.0019879840 0.0044811126 0.0090091360 0.1530540000 0.0101610000 0.0498100000 0.0003140000 0.0002660000 0.0904940000 8285778 96830484 1768341504 4.0137400627 3.9863545895 4.3244633675 178 7.0800000000 0.0045000897 0.0020020969 0.0045000897 0.0090157891 0.1057920000 0.0086150000 0.0438320000 0.0000250000 0.0002790000 0.0495050000 8287452 96830484 1770094592 4.0131587982 3.9857864380 4.3252067566 179 7.1200000000 0.0044611269 0.0020158345 0.0045000897 0.0090231452 0.1124900000 0.0103710000 0.0444410000 0.0002870000 0.0002600000 0.0551840000 8289126 96830484 1768087552 4.0126752853 3.9853568077 4.3259844780 180 7.1600000000 0.0044634305 0.0020294323 0.0045000897 0.0090516504 0.1058480000 0.0085030000 0.0424200000 0.0000250000 0.0003550000 0.0498050000 8290800 96830484 1769746432 4.0122675896 3.9848368168 4.3269433975 181 7.2000000000 0.0044846176 0.0020429968 0.0045000897 0.0090711723 0.1382220000 0.0095860000 0.0441540000 0.0002910000 0.0002740000 0.0819500000 8292474 96830484 1768833024 4.0117473602 3.9844958782 4.3274617195 182 7.2400000000 0.0045893029 0.0020569875 0.0045893029 0.0090904890 0.1017810000 0.0096800000 0.0392840000 0.0000240000 0.0002890000 0.0505220000 8294148 96830484 1770512384 4.0112643242 3.9843688011 4.3279933929 183 7.2800000000 0.0046304199 0.0020710500 0.0046304199 0.0091172941 0.1471520000 0.0103470000 0.0790340000 0.0002870000 0.0002620000 0.0534590000 8295822 96830484 1769590784 4.0108766556 3.9840416908 4.3283438683 184 7.3200000000 0.0048590982 0.0020862024 0.0048590982 0.0092614879 0.1081580000 0.0093520000 0.0418660000 0.0000260000 0.0003680000 0.0485370000 8297496 96830484 1771098112 4.0101399422 3.9836523533 4.3291707039 185 7.3600000000 0.0050587025 0.0021022700 0.0050587025 0.0092860836 0.1471010000 0.0114070000 0.0418300000 0.0010510000 0.0003420000 0.0820270000 8299170 96830484 1769996288 4.0098271370 3.9834718704 4.3297176361 186 7.4000000000 0.0052377130 0.0021191272 0.0052377130 0.0092886163 0.1096780000 0.0093150000 0.0430580000 0.0000270000 0.0010480000 0.0471730000 8300844 96830484 1771765760 4.0093026161 3.9831676483 4.3310427666 187 7.4400000000 0.0052731331 0.0021359936 0.0052731331 0.0092758150 0.1112250000 0.0110450000 0.0446010000 0.0005190000 0.0006940000 0.0523260000 8302518 96830484 1770868736 4.0089797974 3.9828939438 4.3325901031 188 7.4800000000 0.0053404714 0.0021530387 0.0053404714 0.0092624053 0.1083460000 0.0109460000 0.0422840000 0.0000270000 0.0002940000 0.0502260000 8304192 96830484 1769209856 4.0087695122 3.9826452732 4.3340630531 189 7.5200000000 0.0053909868 0.0021701707 0.0053909868 0.0092565858 0.1677930000 0.0096830000 0.0524350000 0.0003770000 0.0002860000 0.0949020000 8305866 96830484 1770856448 4.0086107254 3.9823527336 4.3355693817 190 7.5600000000 0.0054450720 0.0021874070 0.0054450720 0.0092661701 0.1098090000 0.0115630000 0.0432130000 0.0000260000 0.0003810000 0.0473070000 8307540 96830484 1768849408 4.0086159706 3.9824633598 4.3372306824 191 7.6000000000 0.0055738045 0.0022051368 0.0055738045 0.0092556079 0.1103840000 0.0115000000 0.0427340000 0.0003110000 0.0002630000 0.0529420000 8309214 96830484 1770336256 4.0089097023 3.9823331833 4.3388428688 192 7.6400000000 0.0059116916 0.0022244418 0.0059116916 0.0092447531 0.1083170000 0.0109860000 0.0431630000 0.0000250000 0.0003140000 0.0471010000 8310888 96830484 1769742336 4.0089697838 3.9821057320 4.3410820961 193 7.6800000000 0.0064984267 0.0022465868 0.0064984267 0.0092343247 0.1470860000 0.0094970000 0.0450000000 0.0003180000 0.0003390000 0.0813650000 8312562 96830484 1771384832 4.0089631081 3.9820392132 4.3434357643 194 7.7200000000 0.0070853769 0.0022715290 0.0070853769 0.0092221643 0.1307510000 0.0115560000 0.0660810000 0.0000050000 0.0000590000 0.0474170000 8314236 96830484 1769463808 4.0090947151 3.9820349216 4.3455562592 195 7.7600000000 0.0076928623 0.0022993307 0.0076928623 0.0092098955 0.1260020000 0.0094380000 0.0525060000 0.0002980000 0.0003590000 0.0525480000 8315910 96830484 1771130880 4.0092821121 3.9818844795 4.3474855423 196 7.8000000000 0.0083500966 0.0023302020 0.0083500966 0.0091985650 0.1311470000 0.0110140000 0.0672300000 0.0000260000 0.0003000000 0.0467500000 8317584 96830484 1770352640 4.0094122887 3.9816493988 4.3492774963 197 7.8400000000 0.0099447481 0.0023688545 0.0099447481 0.0091914732 0.1829490000 0.0110860000 0.0897150000 0.0002980000 0.0002690000 0.0793280000 8319258 96830484 1768468480 4.0095639229 3.9813954830 4.3520007133 198 7.8800000000 0.0100619551 0.0024077085 0.0100619551 0.0091769481 0.1116770000 0.0111740000 0.0469630000 0.0000250000 0.0006430000 0.0496970000 8320932 96830484 1770082304 4.0097880363 3.9812784195 4.3531441689 199 7.9200000000 0.0103213284 0.0024474755 0.0103213284 0.0091666462 0.1278400000 0.0101470000 0.0524110000 0.0003040000 0.0003510000 0.0558800000 8322606 96830484 1769459712 4.0100560188 3.9810500145 4.3538880348 200 7.9600000000 0.0096793957 0.0024836351 0.0103213284 0.0091582743 0.1283660000 0.0084880000 0.0719520000 0.0000280000 0.0002950000 0.0454050000 8324280 96830484 1771020288 4.0102887154 3.9807436466 4.3539958000 201 8.0000000000 0.0093265614 0.0025176795 0.0103213284 0.0091451223 0.1927180000 0.0138200000 0.0969960000 0.0000570000 0.0000650000 0.0794980000 8325954 96830484 1770229760 4.0104174614 3.9805610180 4.3544325829 202 8.0400000000 0.0100942245 0.0025551871 0.0103213284 0.0091389273 0.1064890000 0.0114310000 0.0469760000 0.0000260000 0.0003480000 0.0455580000 8327628 96830484 1768452096 4.0106558800 3.9804940224 4.3556671143 203 8.0800000000 0.0094279582 0.0025890431 0.0103213284 0.0091291878 0.1467880000 0.0085020000 0.0830140000 0.0002840000 0.0003390000 0.0524080000 8329302 96830484 1770094592 4.0107693672 3.9805500507 4.3552846909 204 8.1200000000 0.0096305348 0.0026235602 0.0103213284 0.0091293631 0.1114300000 0.0107900000 0.0541190000 0.0000270000 0.0007140000 0.0435470000 8330976 96830484 1768210432 4.0108718872 3.9806091785 4.3560690880 205 8.1600000000 0.0103800977 0.0026613970 0.0103800977 0.0091345541 0.1615120000 0.0089080000 0.0582350000 0.0000600000 0.0000530000 0.0832220000 8332650 96830484 1769574400 4.0109252930 3.9807109833 4.3574829102 206 8.1999999990 0.0097859818 0.0026959824 0.0103800977 0.0091328709 0.1507090000 0.0111630000 0.0858090000 0.0000240000 0.0002840000 0.0464370000 8334324 96830484 1767686144 4.0109224319 3.9810318947 4.3569550514 207 8.2400000000 0.0096908463 0.0027297740 0.0103800977 0.0091613036 0.1100470000 0.0088430000 0.0452920000 0.0003180000 0.0003520000 0.0530220000 8335998 96830484 1769340928 4.0110268593 3.9811089039 4.3572120667 208 8.2799999990 0.0098121474 0.0027638239 0.0103800977 0.0091958320 0.1085630000 0.0099810000 0.0465440000 0.0000250000 0.0003810000 0.0465280000 8337672 96830484 1768611840 4.0110182762 3.9812197685 4.3574471474 209 8.3200000000 0.0094344122 0.0027957406 0.0103800977 0.0092211254 0.1481230000 0.0086300000 0.0502510000 0.0002870000 0.0003430000 0.0795290000 8339346 96830484 1770385408 4.0109953880 3.9810795784 4.3570117950 210 8.3599999990 0.0092824874 0.0028266298 0.0103800977 0.0092186345 0.1109370000 0.0102520000 0.0508920000 0.0000240000 0.0003560000 0.0466800000 8341020 96830484 1769488384 4.0108666420 3.9811737537 4.3570122719 211 8.4000000000 0.0089558456 0.0028556782 0.0103800977 0.0092087654 0.1095540000 0.0088200000 0.0451820000 0.0003140000 0.0002790000 0.0527290000 8342694 96830484 1771147264 4.0108695030 3.9813137054 4.3564963341 212 8.4399999990 0.0093222400 0.0028861809 0.0103800977 0.0092076441 0.1159570000 0.0102130000 0.0470830000 0.0000960000 0.0003160000 0.0472290000 8344368 96830484 1770463232 4.0108504295 3.9816110134 4.3564028740 213 8.4800000000 0.0090966979 0.0029153382 0.0103800977 0.0092170057 0.1595300000 0.0109030000 0.0650860000 0.0003690000 0.0002770000 0.0805830000 8346042 96830484 1768693760 4.0108704567 3.9815921783 4.3558502197 214 8.5200000000 0.0087375212 0.0029425447 0.0103800977 0.0092120444 0.1202250000 0.0089840000 0.0545050000 0.0000270000 0.0003180000 0.0475090000 8347716 96830484 1770455040 4.0109128952 3.9816637039 4.3549203873 215 8.5600000000 0.0091889780 0.0029715979 0.0103800977 0.0092048809 0.1118390000 0.0110910000 0.0459490000 0.0003780000 0.0002760000 0.0516740000 8349390 96830484 1768439808 4.0108103752 3.9820888042 4.3550090790 216 8.6000000000 0.0090587605 0.0029997792 0.0103800977 0.0092091487 0.1068000000 0.0087040000 0.0430050000 0.0000270000 0.0006260000 0.0469050000 8351064 96830484 1769992192 4.0107421875 3.9823927879 4.3543353081 217 8.6400000000 0.0085190963 0.0030252138 0.0103800977 0.0092160175 0.1727760000 0.0106990000 0.0679660000 0.0003620000 0.0002740000 0.0813740000 8352738 96830484 1768075264 4.0106029510 3.9826502800 4.3532962799 218 8.6800000000 0.0085034454 0.0030503433 0.0103800977 0.0092304579 0.1298100000 0.0087900000 0.0620060000 0.0000270000 0.0002970000 0.0471470000 8354412 96830484 1769598976 4.0104928017 3.9830348492 4.3527493477 219 8.7200000000 0.0087306257 0.0030762807 0.0103800977 0.0092452383 0.1120740000 0.0088870000 0.0458170000 0.0003120000 0.0003460000 0.0543010000 8356086 96830484 1771343872 4.0103588104 3.9834320545 4.3526082039 220 8.7600000000 0.0081159230 0.0030991882 0.0103800977 0.0092520414 0.1082400000 0.0101710000 0.0428390000 0.0000260000 0.0003000000 0.0477670000 8357760 96830484 1770598400 4.0103011131 3.9837419987 4.3513412476 221 8.8000000000 0.0083118733 0.0031227750 0.0103800977 0.0092685813 0.1490360000 0.0104050000 0.0533170000 0.0002970000 0.0003570000 0.0822190000 8359434 96830484 1768947712 4.0102095604 3.9838941097 4.3512001038 222 8.8400000000 0.0079008313 0.0031442978 0.0103800977 0.0092709842 0.1289770000 0.0083200000 0.0661110000 0.0000240000 0.0003080000 0.0482600000 8361108 96830484 1770500096 4.0100889206 3.9841854572 4.3502287865 223 8.8800000000 0.0077763665 0.0031650694 0.0103800977 0.0092823070 0.1105730000 0.0108070000 0.0427300000 0.0003030000 0.0002760000 0.0539910000 8362782 96830484 1768460288 4.0097823143 3.9846408367 4.3494334221 224 8.9200000000 0.0077144620 0.0031853792 0.0103800977 0.0093075997 0.1072530000 0.0091240000 0.0424140000 0.0000260000 0.0003650000 0.0489020000 8364456 96830484 1769992192 4.0094900131 3.9849786758 4.3486490250 225 8.9600000000 0.0076368600 0.0032051635 0.0103800977 0.0093266940 0.1476740000 0.0107550000 0.0498270000 0.0003190000 0.0002820000 0.0839100000 8366130 96830484 1768185856 4.0091505051 3.9855520725 4.3477320671 226 9.0000000000 0.0071138460 0.0032224586 0.0103800977 0.0093517624 0.1237720000 0.0083660000 0.0530240000 0.0000290000 0.0011110000 0.0488540000 8367804 96830484 1769820160 4.0089063644 3.9858505726 4.3463315964 227 9.0400000000 0.0072962889 0.0032404050 0.0103800977 0.0093711619 0.1130870000 0.0106830000 0.0453120000 0.0003190000 0.0002740000 0.0538970000 8369478 96830484 1767698432 4.0085124969 3.9863383770 4.3457064629 228 9.0800000000 0.0077140811 0.0032600263 0.0103800977 0.0094024090 0.1252640000 0.0084580000 0.0719160000 0.0000260000 0.0003770000 0.0420230000 8371152 96830484 1769336832 4.0081100464 3.9868297577 4.3453707695 229 9.1200000000 0.0076325601 0.0032791204 0.0103800977 0.0094321642 0.1392100000 0.0104880000 0.0443190000 0.0003130000 0.0002750000 0.0812610000 8372826 96830484 1771102208 4.0077023506 3.9869232178 4.3443112373 230 9.1600000000 0.0073388955 0.0032967716 0.0103800977 0.0094385607 0.1150970000 0.0136930000 0.0392350000 0.0000110000 0.0001160000 0.0519570000 8374500 96830484 1770221568 4.0072431564 3.9876704216 4.3426671028 231 9.2000000000 0.0071380404 0.0033134004 0.0103800977 0.0094542411 0.1889390000 0.0102620000 0.1116530000 0.0002980000 0.0000550000 0.0558160000 8376174 96830484 1768693760 4.0066933632 3.9880733490 4.3414692879 232 9.2400000000 0.0072832755 0.0033305120 0.0103800977 0.0094737146 0.1099730000 0.0087110000 0.0447100000 0.0000260000 0.0003070000 0.0491230000 8377848 96830484 1770246144 4.0061798096 3.9887597561 4.3405656815 233 9.2800000000 0.0076443944 0.0033490265 0.0103800977 0.0095034139 0.1482660000 0.0106930000 0.0493340000 0.0003200000 0.0003530000 0.0850000000 8379522 96830484 1768296448 4.0055751801 3.9893779755 4.3401722908 234 9.3200000000 0.0074412059 0.0033665144 0.0103800977 0.0095293642 0.1106720000 0.0083290000 0.0471300000 0.0000250000 0.0003050000 0.0513240000 8381196 96830484 1769721856 4.0049471855 3.9900395870 4.3384437561 235 9.3600000000 0.0074405619 0.0033838508 0.0103800977 0.0095415465 0.1474850000 0.0097500000 0.0706960000 0.0003770000 0.0002760000 0.0566920000 8382870 96830484 1769201664 4.0043220520 3.9903001785 4.3375177383 236 9.4000000000 0.0074536484 0.0034010957 0.0103800977 0.0095450487 0.1094200000 0.0084500000 0.0431050000 0.0000290000 0.0003020000 0.0492930000 8384544 96830484 1770741760 4.0035977364 3.9909021854 4.3363699913 237 9.4400000000 0.0074201948 0.0034180539 0.0103800977 0.0095542875 0.1492270000 0.0109700000 0.0422570000 0.0003120000 0.0004720000 0.0866730000 8386218 96830484 1768820736 4.0028314590 3.9913220406 4.3352947235 238 9.4800000000 0.0075482531 0.0034354077 0.0103800977 0.0096266643 0.1090120000 0.0086930000 0.0425050000 0.0000260000 0.0003830000 0.0492600000 8387892 96830484 1770356736 4.0010209084 3.9935472012 4.3327522278 239 9.5200000000 0.0074588666 0.0034522423 0.0103800977 0.0096551396 0.1111000000 0.0109130000 0.0416390000 0.0003780000 0.0002750000 0.0552560000 8389566 96830484 1768439808 4.0000629425 3.9942600727 4.3315391541 240 9.5600000000 0.0075993561 0.0034695219 0.0103800977 0.0096809866 0.1079330000 0.0086300000 0.0420760000 0.0000270000 0.0003020000 0.0523280000 8391240 96830484 1769865216 3.9989869595 3.9958896637 4.3301043510 241 9.6000000000 0.0076067541 0.0034866888 0.0103800977 0.0097481356 0.1490840000 0.0096400000 0.0425170000 0.0003100000 0.0003440000 0.0935850000 8392914 96830484 1769185280 3.9979314804 3.9967291355 4.3290905952 242 9.6400000000 0.0078405002 0.0035046798 0.0103800977 0.0098191321 0.1090670000 0.0082060000 0.0422220000 0.0000280000 0.0003110000 0.0524180000 8394588 96830484 1770868736 3.9969134331 3.9977822304 4.3280434608 243 9.6800000000 0.0079351328 0.0035229121 0.0103800977 0.0098748573 0.1679100000 0.0095950000 0.0586630000 0.0003080000 0.0002730000 0.0865770000 8396262 96830484 1770090496 3.9958379269 3.9987733364 4.3264627457 244 9.7200000000 0.0080717420 0.0035415549 0.0103800977 0.0099288388 0.1292220000 0.0102330000 0.0556310000 0.0000270000 0.0018080000 0.0500050000 8397936 96830484 1768333312 3.9947216511 3.9998443127 4.3252792358 245 9.7600000000 0.0079220962 0.0035594346 0.0103800977 0.0099723370 0.1497750000 0.0088150000 0.0445170000 0.0003200000 0.0002700000 0.0881170000 8399610 96830484 1770106880 3.9937517643 4.0003514290 4.3237266541 246 9.8000000000 0.0080907689 0.0035778547 0.0103800977 0.0099987780 0.1284990000 0.0108650000 0.0573550000 0.0000290000 0.0003840000 0.0499520000 8401284 96830484 1767931904 3.9925611019 4.0014238358 4.3222775459 247 9.8400000000 0.0080792280 0.0035960789 0.0103800977 0.0100368090 0.1286620000 0.0086940000 0.0499870000 0.0003830000 0.0002730000 0.0573480000 8402958 96830484 1769725952 3.9915511608 4.0026016235 4.3207974434 248 9.8800000000 0.0080833174 0.0036141726 0.0103800977 0.0100865698 0.1254280000 0.0108880000 0.0507900000 0.0000270000 0.0004130000 0.0500680000 8404632 96830484 1767567360 3.9904599190 4.0036587715 4.3190231323 249 9.9200000000 0.0081977705 0.0036325806 0.0103800977 0.0101391231 0.1500990000 0.0085190000 0.0419650000 0.0003100000 0.0002670000 0.0911980000 8406306 96830484 1769230336 3.9894566536 4.0044755936 4.3174567223 250 9.9600000000 0.0081759524 0.0036507541 0.0103800977 0.0101828139 0.1084460000 0.0098360000 0.0349700000 0.0000080000 0.0000830000 0.0524590000 8407980 96830484 1768443904 3.9884476662 4.0053515434 4.3159904480 251 10.0000000000 0.0081781596 0.0036687916 0.0103800977 0.0102256064 0.1305310000 0.0079240000 0.0475910000 0.0003120000 0.0003510000 0.0699080000 8409654 96830484 1770123264 3.9873590469 4.0067420006 4.3143453598 252 10.0400000000 0.0083618825 0.0036874149 0.0103800977 0.0102861444 0.1279390000 0.0097870000 0.0462720000 0.0000250000 0.0003070000 0.0609960000 8411328 96830484 1769201664 3.9863743782 4.0078992844 4.3128299713 253 10.0800000000 0.0083744247 0.0037059407 0.0103800977 0.0103217911 0.1891040000 0.0078970000 0.0509330000 0.0003880000 0.0002780000 0.1191140000 8413002 96830484 1770774528 3.9855027199 4.0089402199 4.3110837936 254 10.1200000000 0.0084733889 0.0037247101 0.0103800977 0.0103572838 0.1095430000 0.0102910000 0.0364280000 0.0000090000 0.0000820000 0.0532150000 8414676 96830484 1769693184 3.9845499992 4.0101923943 4.3095064163 255 10.1600000000 0.0085389968 0.0037435897 0.0103800977 0.0104056655 0.1496960000 0.0099440000 0.0516840000 0.0003730000 0.0002790000 0.0796140000 8416350 96830484 1767940096 3.9835178852 4.0113072395 4.3078432083 256 10.2000000000 0.0083888173 0.0037617351 0.0103800977 0.0104470303 0.1492950000 0.0082120000 0.0601810000 0.0000260000 0.0003110000 0.0750130000 8418024 96830484 1769603072 3.9826908112 4.0122117996 4.3060088158 257 10.2400000000 0.0084539624 0.0037799928 0.0103800977 0.0104901489 0.1967300000 0.0095350000 0.0565760000 0.0003130000 0.0002780000 0.1154970000 8440178 96830484 1768452096 3.9817123413 4.0132312775 4.3046422005 258 10.2800000000 0.0082996339 0.0037975108 0.0103800977 0.0105016333 0.1118240000 0.0085480000 0.0419950000 0.0000180000 0.0013640000 0.0499410000 8483836 96830484 1770258432 3.9809429646 4.0141210556 4.3027291298 259 10.3200000000 0.0082777515 0.0038148090 0.0103800977 0.0105033028 0.1116060000 0.0103280000 0.0417010000 0.0003110000 0.0002770000 0.0560480000 8485510 96830484 1769226240 3.9800369740 4.0149717331 4.3011016846 260 10.3600000000 0.0083443020 0.0038322302 0.0103800977 0.0105209054 0.1080210000 0.0083530000 0.0418330000 0.0000260000 0.0003730000 0.0527740000 8487184 96830484 1770893312 3.9790208340 4.0162954330 4.2994375229 261 10.4000000000 0.0083645498 0.0038495954 0.0103800977 0.0105541233 0.1706680000 0.0096990000 0.0502220000 0.0003060000 0.0002710000 0.1071830000 8488858 96830484 1770082304 3.9782392979 4.0169839859 4.2979350090 262 10.4400000000 0.0082038818 0.0038662148 0.0103800977 0.0105655139 0.1238440000 0.0104930000 0.0478330000 0.0000250000 0.0002840000 0.0530660000 8490532 96830484 1768337408 3.9773926735 4.0175862312 4.2961139679 263 10.4800000000 0.0082257502 0.0038827910 0.0103800977 0.0105653540 0.1490930000 0.0082200000 0.0512610000 0.0002860000 0.0002700000 0.0774950000 8492206 96830484 1770004480 3.9765338898 4.0184960365 4.2945852280 264 10.5200000000 0.0081846099 0.0038990857 0.0103800977 0.0105686084 0.1496660000 0.0098680000 0.0659130000 0.0000250000 0.0003100000 0.0639410000 8493880 96830484 1768972288 3.9756023884 4.0193610191 4.2928423882 265 10.5600000000 0.0082766991 0.0039156050 0.0103800977 0.0105940708 0.1897930000 0.0079690000 0.0562820000 0.0002900000 0.0003360000 0.1174150000 8495554 96830484 1770639360 3.9747138023 4.0196185112 4.2916173935 266 10.6000000000 0.0082980627 0.0039320804 0.0103800977 0.0105923132 0.1098690000 0.0108450000 0.0407460000 0.0000260000 0.0003080000 0.0528580000 8497228 96830484 1768591360 3.9739720821 4.0201368332 4.2898612022 267 10.6400000000 0.0083310632 0.0039485560 0.0103800977 0.0105761137 0.1302470000 0.0082120000 0.0438250000 0.0003610000 0.0002660000 0.0745640000 8498902 96830484 1770225664 3.9731135368 4.0208635330 4.2882866859 268 10.6800000000 0.0082568945 0.0039646319 0.0103800977 0.0105665307 0.1299020000 0.0097210000 0.0531680000 0.0000290000 0.0004980000 0.0635600000 8500576 96830484 1769099264 3.9722900391 4.0213017464 4.2863941193 269 10.7200000000 0.0083310157 0.0039808638 0.0103800977 0.0105649046 0.1658900000 0.0079820000 0.0490160000 0.0002850000 0.0003370000 0.0980840000 8502250 96830484 1770766336 3.9714219570 4.0216240883 4.2850332260 270 10.7600000000 0.0084544690 0.0039974327 0.0103800977 0.0105697311 0.1101390000 0.0103450000 0.0425170000 0.0000240000 0.0010680000 0.0507110000 8503924 96830484 1769988096 3.9706113338 4.0220880508 4.2833924294 271 10.8000000000 0.0084369797 0.0040138148 0.0103800977 0.0105636648 0.1279260000 0.0103640000 0.0497320000 0.0003090000 0.0002890000 0.0573650000 8505598 96830484 1768574976 3.9699003696 4.0227055550 4.2811927795 272 10.8400000000 0.0084359953 0.0040300728 0.0103800977 0.0105499435 0.1108170000 0.0084980000 0.0499220000 0.0000300000 0.0003120000 0.0490580000 8507272 96830484 1770274816 3.9689900875 4.0233139992 4.2795076370 273 10.8800000000 0.0083829658 0.0040460175 0.0103800977 0.0105546993 0.1461720000 0.0105660000 0.0436000000 0.0010420000 0.0002720000 0.0876410000 8508946 96830484 1769099264 3.9682257175 4.0237822533 4.2775611877 274 10.9200000000 0.0084443651 0.0040620699 0.0103800977 0.0105535677 0.1120510000 0.0079850000 0.0500940000 0.0000270000 0.0010310000 0.0499380000 8510620 96830484 1770717184 3.9673314095 4.0240340233 4.2759518623 275 10.9600000000 0.0085521219 0.0040783973 0.0103800977 0.0105402637 0.1299650000 0.0104200000 0.0614090000 0.0003700000 0.0002800000 0.0544790000 8512294 96830484 1769607168 3.9667491913 4.0241298676 4.2740583420 276 11.0000000000 0.0085617341 0.0040946413 0.0103800977 0.0105252559 0.1267700000 0.0095290000 0.0579670000 0.0000250000 0.0003040000 0.0496890000 8513968 96830484 1768194048 3.9661202431 4.0243349075 4.2722592354 277 11.0400000000 0.0084425332 0.0041103377 0.0103800977 0.0105161268 0.1471890000 0.0082170000 0.0476710000 0.0003190000 0.0002880000 0.0875920000 8515642 96830484 1769984000 3.9651892185 4.0243568420 4.2706141472 278 11.0800000000 0.0084713548 0.0041260248 0.0103800977 0.0105091167 0.1115560000 0.0091890000 0.0430350000 0.0000270000 0.0002970000 0.0520470000 8517316 96830484 1769103360 3.9644606113 4.0244884491 4.2689771652 279 11.1200000000 0.0084572565 0.0041415489 0.0103800977 0.0104942973 0.1319150000 0.0081030000 0.0461490000 0.0002950000 0.0003380000 0.0737870000 8518990 96830484 1770872832 3.9638571739 4.0244650841 4.2672600746 280 11.1600000000 0.0084313769 0.0041568697 0.0103800977 0.0104763342 0.1256020000 0.0096120000 0.0497450000 0.0000250000 0.0002870000 0.0550370000 8520664 96830484 1769607168 3.9631142616 4.0249314308 4.2654690742 281 11.2000000000 0.0085126748 0.0041723708 0.0103800977 0.0104604122 0.1696750000 0.0093930000 0.0615210000 0.0003140000 0.0002680000 0.0901560000 8522338 96830484 1768558592 3.9622843266 4.0251984596 4.2640075684 282 11.2400000000 0.0084861731 0.0041876680 0.0103800977 0.0104441372 0.1061230000 0.0082470000 0.0429030000 0.0000250000 0.0003470000 0.0485700000 8524012 96830484 1770237952 3.9615674019 4.0255789757 4.2622537613 283 11.2800000000 0.0083655845 0.0042024309 0.0103800977 0.0104267482 0.1279390000 0.0101250000 0.0491800000 0.0006920000 0.0006590000 0.0565780000 8525686 96830484 1769226240 3.9602947235 4.0256524086 4.2606897354 284 11.3200000000 0.0084535610 0.0042173997 0.0103800977 0.0104087667 0.1096190000 0.0084090000 0.0427010000 0.0000250000 0.0003840000 0.0489950000 8527360 96830484 1770909696 3.9596250057 4.0259442329 4.2591676712 285 11.3600000000 0.0085671758 0.0042326621 0.0103800977 0.0103907952 0.1409660000 0.0101980000 0.0398930000 0.0002970000 0.0002650000 0.0871770000 8529034 96830484 1769734144 3.9585883617 4.0262298584 4.2574687004 286 11.4000000000 0.0085378364 0.0042477151 0.0103800977 0.0103731058 0.1151930000 0.0128470000 0.0419680000 0.0000260000 0.0002870000 0.0516860000 8530708 96830484 1768341504 3.9577987194 4.0263495445 4.2553577423 287 11.4400000000 0.0085959956 0.0042628659 0.0103800977 0.0103553045 0.1487260000 0.0079270000 0.0665920000 0.0007200000 0.0002860000 0.0634820000 8532382 96830484 1770016768 3.9567708969 4.0262818336 4.2537989616 288 11.4800000000 0.0085161375 0.0042776342 0.0103800977 0.0103377713 0.1303940000 0.0097560000 0.0499180000 0.0000250000 0.0002900000 0.0651310000 8534056 96830484 1768849408 3.9558529854 4.0262889862 4.2514076233 289 11.5200000000 0.0085976608 0.0042925824 0.0103800977 0.0103206915 0.1687800000 0.0080670000 0.0498250000 0.0003020000 0.0002860000 0.1070620000 8535730 96830484 1770590208 3.9540865421 4.0260529518 4.2501897812 290 11.5600000000 0.0085256239 0.0043071791 0.0103800977 0.0103035381 0.1092610000 0.0095790000 0.0420330000 0.0000230000 0.0002830000 0.0512320000 8537404 96830484 1769734144 3.9529213905 4.0259723663 4.2478556633 291 11.6000000000 0.0085140001 0.0043216355 0.0103800977 0.0102902435 0.1492390000 0.0096740000 0.0696800000 0.0003180000 0.0002650000 0.0633570000 8539078 96830484 1768357888 3.9514479637 4.0256795883 4.2461657524 292 11.6400000000 0.0084684966 0.0043358371 0.0103800977 0.0102729932 0.1092840000 0.0078240000 0.0375600000 0.0000200000 0.0001920000 0.0593340000 8540752 96830484 1770020864 3.9499089718 4.0250363350 4.2444334030 293 11.6800000000 0.0084591424 0.0043499098 0.0103800977 0.0102618716 0.1819640000 0.0095900000 0.0568190000 0.0005720000 0.0002870000 0.1113350000 8542426 96830484 1768833024 3.9481766224 4.0244669914 4.2428150177 294 11.7200000000 0.0084345117 0.0043638030 0.0103800977 0.0102450723 0.1115340000 0.0103430000 0.0414450000 0.0000100000 0.0001090000 0.0510270000 8544100 96830484 1770528768 3.9463136196 4.0244374275 4.2407531738 295 11.7600000000 0.0083949566 0.0043774680 0.0103800977 0.0102296463 0.1492350000 0.0095680000 0.0674640000 0.0003160000 0.0002740000 0.0630560000 8545774 96830484 1769463808 3.9442148209 4.0243182182 4.2391829491 296 11.8000000000 0.0083529605 0.0043908987 0.0103800977 0.0102130303 0.1120770000 0.0078270000 0.0452500000 0.0000250000 0.0002860000 0.0554050000 8547448 96830484 1771147264 3.9421646595 4.0241131783 4.2375607491 297 11.8400000000 0.0085290624 0.0044048319 0.0103800977 0.0101960263 0.1654480000 0.0096840000 0.0461350000 0.0003000000 0.0002770000 0.1057670000 8549122 96830484 1770115072 3.9399735928 4.0240893364 4.2362084389 298 11.8800000000 0.0084576001 0.0044184318 0.0103800977 0.0101838472 0.1095460000 0.0098730000 0.0404150000 0.0000260000 0.0002900000 0.0511450000 8550796 96830484 1768607744 3.9379482269 4.0238976479 4.2344532013 299 11.9200000000 0.0084673464 0.0044319733 0.0103800977 0.0101743539 0.1316760000 0.0081950000 0.0472910000 0.0003510000 0.0002640000 0.0722270000 8552470 96830484 1770270720 3.9354741573 4.0240416527 4.2330813408 300 11.9600000000 0.0084319962 0.0044453067 0.0103800977 0.0101602546 0.1074070000 0.0095900000 0.0403890000 0.0000260000 0.0002900000 0.0538330000 8554144 96830484 1769226240 3.9331312180 4.0237903595 4.2314577103 301 12.0000000000 0.0085189315 0.0044588404 0.0103800977 0.0101497835 0.1576300000 0.0082010000 0.0406190000 0.0002900000 0.0002650000 0.0918060000 8555818 96830484 1770909696 3.9307069778 4.0240230560 4.2299427986 302 12.0400000000 0.0083942302 0.0044718715 0.0103800977 0.0101377862 0.1115890000 0.0102120000 0.0384860000 0.0000170000 0.0001930000 0.0508490000 8557492 96830484 1769717760 3.9282140732 4.0242881775 4.2282261848 303 12.0800000000 0.0084181419 0.0044848954 0.0103800977 0.0101238861 0.1534550000 0.0097870000 0.0687240000 0.0003220000 0.0002750000 0.0709700000 8559166 96830484 1768341504 3.9257934093 4.0242671967 4.2267150879 304 12.1200000000 0.0084781107 0.0044980310 0.0103800977 0.0101130443 0.1055640000 0.0078100000 0.0397520000 0.0000270000 0.0002860000 0.0497570000 8560840 96830484 1770115072 3.9233670235 4.0241503716 4.2253003120 305 12.1600000000 0.0084750745 0.0045110705 0.0103800977 0.0101049167 0.1686690000 0.0095980000 0.0445880000 0.0002920000 0.0003370000 0.1040060000 8562514 96830484 1769099264 3.9208269119 4.0245242119 4.2237272263 306 12.2000000000 0.0084867608 0.0045240630 0.0103800977 0.0100913421 0.1096250000 0.0091240000 0.0381930000 0.0000080000 0.0000770000 0.0506330000 8564188 96830484 1770987520 3.9182569981 4.0249171257 4.2221441269 307 12.2400000000 0.0085026529 0.0045370225 0.0103800977 0.0100751289 0.1738700000 0.0094810000 0.0812790000 0.0002980000 0.0002750000 0.0791350000 8565862 96830484 1770225664 3.9157683849 4.0250358582 4.2204833031 308 12.2800000000 0.0084416121 0.0045496998 0.0103800977 0.0100593166 0.1075860000 0.0101040000 0.0427140000 0.0000260000 0.0003420000 0.0509740000 8567536 96830484 1768194048 3.9134416580 4.0244107246 4.2192716599 309 12.3200000000 0.0084625576 0.0045623627 0.0103800977 0.0100495466 0.1460850000 0.0080460000 0.0416690000 0.0002880000 0.0003370000 0.0922880000 8569210 96830484 1769717760 3.9109435081 4.0241289139 4.2179622650 310 12.3600000000 0.0084510790 0.0045749070 0.0103800977 0.0100408064 0.1095290000 0.0102060000 0.0399650000 0.0000240000 0.0003620000 0.0501920000 8570884 96830484 1768587264 3.9084155560 4.0243206024 4.2165122032 311 12.4000000000 0.0084052170 0.0045872231 0.0103800977 0.0100250385 0.1505440000 0.0080390000 0.0563440000 0.0003600000 0.0002710000 0.0821200000 8572558 96830484 1770369024 3.9056949615 4.0243248940 4.2154278755 312 12.4400000000 0.0084516630 0.0045996091 0.0103800977 0.0100092609 0.1269080000 0.0094410000 0.0461710000 0.0000280000 0.0002810000 0.0602530000 8574232 96830484 1769480192 3.9032862186 4.0239467621 4.2141981125 313 12.4800000000 0.0085576884 0.0046122547 0.0103800977 0.0099946155 0.1805610000 0.0081060000 0.0575140000 0.0002880000 0.0003360000 0.1109490000 8575906 96830484 1771368448 3.9008505344 4.0237736702 4.2131218910 314 12.5200000000 0.0085202726 0.0046247007 0.0103800977 0.0099790112 0.1169520000 0.0134280000 0.0459010000 0.0000260000 0.0003170000 0.0467980000 8577580 96830484 1769226240 3.8980259895 4.0233664513 4.2123661041 315 12.5600000000 0.0084441183 0.0046368258 0.0103800977 0.0099647835 0.1114090000 0.0085050000 0.0474230000 0.0003100000 0.0002730000 0.0513650000 8579254 96830484 1770872832 3.8957479000 4.0222878456 4.2114715576 316 12.6000000000 0.0085385758 0.0046491731 0.0103800977 0.0099538543 0.1070510000 0.0103340000 0.0387560000 0.0000260000 0.0002880000 0.0483940000 8580928 96830484 1769717760 3.8933460712 4.0216717720 4.2106466293 317 12.6400000000 0.0084864525 0.0046612781 0.0103800977 0.0099434922 0.1764090000 0.0099140000 0.0664750000 0.0002880000 0.0003360000 0.0817520000 8582602 96830484 1767849984 3.8913049698 4.0206780434 4.2096934319 318 12.6800000000 0.0085791890 0.0046735986 0.0103800977 0.0099456948 0.1120270000 0.0088850000 0.0488980000 0.0000240000 0.0003080000 0.0458230000 8584276 96830484 1769496576 3.8891623020 4.0200071335 4.2088952065 319 12.7200000000 0.0086072823 0.0046859299 0.0103800977 0.0099417639 0.1491770000 0.0087890000 0.0785360000 0.0003660000 0.0002700000 0.0529550000 8585950 96830484 1771126784 3.8870735168 4.0197482109 4.2077631950 320 12.7600000000 0.0086179748 0.0046982175 0.0103800977 0.0099277270 0.1287190000 0.0100020000 0.0599570000 0.0000260000 0.0002840000 0.0458120000 8587624 96830484 1770352640 3.8851845264 4.0195951462 4.2065262794 321 12.8000000000 0.0086389640 0.0047104940 0.0103800977 0.0099126229 0.1490870000 0.0106130000 0.0400030000 0.0002840000 0.0003370000 0.0879030000 8589298 96830484 1768337408 3.8835411072 4.0188975334 4.2052040100 322 12.8400000000 0.0087245917 0.0047229601 0.0103800977 0.0099001334 0.1095450000 0.0088760000 0.0478980000 0.0000940000 0.0003160000 0.0446690000 8590972 96830484 1769988096 3.8820769787 4.0177345276 4.2040762901 323 12.8800000000 0.0087641366 0.0047354715 0.0103800977 0.0098940673 0.1283710000 0.0110190000 0.0542810000 0.0002920000 0.0002650000 0.0526760000 8592646 96830484 1767940096 3.8803582191 4.0174970627 4.2028079033 324 12.9200000000 0.0088221962 0.0047480848 0.0103800977 0.0098826626 0.1093240000 0.0089280000 0.0477550000 0.0000250000 0.0003080000 0.0445810000 8594320 96830484 1769463808 3.8785128593 4.0170865059 4.2012815475 325 12.9600000000 0.0088989269 0.0047608567 0.0103800977 0.0098700958 0.1483680000 0.0099930000 0.0467740000 0.0003150000 0.0005040000 0.0815150000 8595994 96830484 1768833024 3.8770582676 4.0163254738 4.1998777390 326 13.0000000000 0.0086296797 0.0047727242 0.0103800977 0.0098603434 0.1094300000 0.0086840000 0.0476730000 0.0000280000 0.0003810000 0.0444530000 8597668 96830484 1770582016 3.8756239414 4.0151691437 4.1983413696 327 13.0400000000 0.0087219216 0.0047848013 0.0103800977 0.0098516499 0.1112280000 0.0102490000 0.0469030000 0.0003120000 0.0002840000 0.0498930000 8599342 96830484 1769836544 3.8738903999 4.0147509575 4.1967062950 328 13.0800000000 0.0088430680 0.0047971740 0.0103800977 0.0098397012 0.1079630000 0.0106440000 0.0486070000 0.0000290000 0.0003160000 0.0442590000 8601016 96830484 1767710720 3.8724291325 4.0142645836 4.1953315735 329 13.1200000000 0.0089047393 0.0048096590 0.0103800977 0.0098297702 0.1470250000 0.0090300000 0.0529800000 0.0003470000 0.0002670000 0.0807660000 8602690 96830484 1769361408 3.8709120750 4.0136303902 4.1936335564 330 13.1600000000 0.0090879267 0.0048226235 0.0103800977 0.0098197121 0.1100910000 0.0080390000 0.0476370000 0.0000250000 0.0002800000 0.0466600000 8604364 96830484 1771089920 3.8695700169 4.0130882263 4.1918110847 331 13.2000000000 0.0090255318 0.0048353211 0.0103800977 0.0098098172 0.1486750000 0.0095880000 0.0595380000 0.0000620000 0.0000550000 0.0699450000 8606038 96830484 1770233856 3.8681426048 4.0125594139 4.1898708344 332 13.2400000000 0.0090419007 0.0048479915 0.0103800977 0.0098010904 0.1194350000 0.0100220000 0.0682290000 0.0000260000 0.0003520000 0.0372620000 8607712 96830484 1768693760 3.8666648865 4.0118145943 4.1879062653 333 13.2800000000 0.0090407999 0.0048605825 0.0103800977 0.0097962836 0.1385870000 0.0096030000 0.0418520000 0.0002920000 0.0003430000 0.0827730000 8609386 96830484 1770106880 3.8654832840 4.0117001534 4.1854181290 334 13.3200000000 0.0089016911 0.0048726817 0.0103800977 0.0097862115 0.1089980000 0.0099130000 0.0483600000 0.0000250000 0.0003730000 0.0436190000 8611060 96830484 1769091072 3.8641481400 4.0112876892 4.1831049919 335 13.3600000000 0.0091411602 0.0048854234 0.0103800977 0.0097774168 0.1468540000 0.0085840000 0.0713400000 0.0002910000 0.0003520000 0.0514600000 8612734 96830484 1770741760 3.8628284931 4.0098843575 4.1811776161 336 13.4000000000 0.0092111556 0.0048982976 0.0103800977 0.0098037326 0.1119580000 0.0101730000 0.0540490000 0.0000260000 0.0002890000 0.0434720000 8614408 96830484 1769979904 3.8616938591 4.0099716187 4.1785445213 337 13.4400000000 0.0093178628 0.0049114120 0.0103800977 0.0098132853 0.1674400000 0.0102820000 0.0677150000 0.0002850000 0.0002660000 0.0796050000 8616082 96830484 1768550400 3.8602995872 4.0106115341 4.1751866341 338 13.4800000000 0.0091945892 0.0049240842 0.0103800977 0.0098103840 0.1078120000 0.0084150000 0.0403100000 0.0000270000 0.0002900000 0.0460550000 8617756 96830484 1770266624 3.8589880466 4.0102252960 4.1728005409 339 13.5200000000 0.0091825156 0.0049366459 0.0103800977 0.0098090542 0.1538030000 0.0099870000 0.0910100000 0.0000590000 0.0000530000 0.0490710000 8619430 96830484 1769218048 3.8575778008 4.0106439590 4.1701540947 340 13.5600000000 0.0093096904 0.0049495078 0.0103800977 0.0097970651 0.1239870000 0.0083070000 0.0562990000 0.0000240000 0.0003560000 0.0436030000 8621104 96830484 1770885120 3.8561279774 4.0113091469 4.1673259735 341 13.6000000000 0.0093503138 0.0049624134 0.0103800977 0.0097826651 0.1693710000 0.0105510000 0.0746670000 0.0002840000 0.0003370000 0.0798160000 8622778 96830484 1769725952 3.8548164368 4.0115275383 4.1648683548 342 13.6400000000 0.0094838664 0.0049756340 0.0103800977 0.0097683447 0.1482710000 0.0103300000 0.0791410000 0.0000270000 0.0002870000 0.0438590000 8624452 96830484 1768079360 3.8534238338 4.0113968849 4.1621775627 343 13.6800000000 0.0097614247 0.0049895867 0.0103800977 0.0097546326 0.1294660000 0.0087290000 0.0574010000 0.0002940000 0.0003320000 0.0512900000 8626126 96830484 1769885696 3.8525378704 4.0110611916 4.1595802307 344 13.7200000000 0.0097918343 0.0050035468 0.0103800977 0.0097485941 0.1329840000 0.0101100000 0.0786380000 0.0000280000 0.0003550000 0.0401360000 8627800 96830484 1768550400 3.8516712189 4.0111923218 4.1562805176 345 13.7600000000 0.0095353955 0.0050166826 0.0103800977 0.0097400387 0.1473360000 0.0082360000 0.0553110000 0.0003700000 0.0002770000 0.0793960000 8629474 96830484 1770504192 3.8506262302 4.0113010406 4.1531848907 346 13.8000000000 0.0095116179 0.0050296737 0.0103800977 0.0097263553 0.1074070000 0.0102020000 0.0412090000 0.0000160000 0.0001990000 0.0463440000 8631148 96830484 1769218048 3.8497340679 4.0113530159 4.1503973007 347 13.8400000000 0.0097528696 0.0050432852 0.0103800977 0.0097123320 0.1286820000 0.0080380000 0.0455560000 0.0003060000 0.0003540000 0.0648960000 8632822 96830484 1771012096 3.8486995697 4.0113692284 4.1475257874 348 13.8800000000 0.0097291507 0.0050567504 0.0103800977 0.0096988211 0.1504850000 0.0102310000 0.0917760000 0.0000050000 0.0000600000 0.0430400000 8634496 96830484 1769852928 3.8476247787 4.0109510422 4.1448740959 349 13.9200000000 0.0096335728 0.0050698645 0.0103800977 0.0096866305 0.1487660000 0.0103110000 0.0551540000 0.0002890000 0.0003570000 0.0789110000 8636170 96830484 1768460288 3.8467643261 4.0104737282 4.1420831680 350 13.9600000000 0.0095802285 0.0050827512 0.0103800977 0.0096765644 0.1081880000 0.0080940000 0.0470660000 0.0000290000 0.0002800000 0.0455390000 8637844 96830484 1770266624 3.8459272385 4.0100913048 4.1388549805 351 14.0000000000 0.0096687293 0.0050958167 0.0103800977 0.0096659872 0.1298380000 0.0100790000 0.0530140000 0.0002860000 0.0002650000 0.0618000000 8639518 96830484 1769074688 3.8451399803 4.0096197128 4.1360526085 352 14.0400000000 0.0098637771 0.0051093620 0.0103800977 0.0096594010 0.1442790000 0.0079970000 0.0805950000 0.0000250000 0.0003030000 0.0478940000 8641192 96830484 1770758144 3.8443443775 4.0094842911 4.1329731941 353 14.0800000000 0.0097235441 0.0051224334 0.0103800977 0.0096511514 0.1692430000 0.0096990000 0.0753420000 0.0005440000 0.0000600000 0.0798090000 8642866 96830484 1769598976 3.8436679840 4.0090746880 4.1301913261 354 14.1200000000 0.0095827738 0.0051350332 0.0103800977 0.0096399885 0.1074140000 0.0096570000 0.0414280000 0.0001610000 0.0003020000 0.0453210000 8644540 96830484 1768185856 3.8425722122 4.0092005730 4.1272349358 355 14.1600000000 0.0098129185 0.0051482103 0.0103800977 0.0096265249 0.1685870000 0.0081740000 0.0875410000 0.0003040000 0.0004930000 0.0613950000 8646214 96830484 1769992192 3.8417341709 4.0092916489 4.1248378754 356 14.2000000000 0.0097550144 0.0051611508 0.0103800977 0.0096130713 0.1313090000 0.0095560000 0.0527900000 0.0000270000 0.0003140000 0.0647280000 8647888 96830484 1768841216 3.8408761024 4.0090832710 4.1220936775 357 14.2400000000 0.0097386306 0.0051739729 0.0103800977 0.0095997748 0.1449710000 0.0080140000 0.0478600000 0.0002990000 0.0002730000 0.0846360000 8649562 96830484 1770455040 3.8401963711 4.0093336105 4.1194806099 358 14.2800000000 0.0100318436 0.0051875423 0.0103800977 0.0095903169 0.1152440000 0.0098360000 0.0617820000 0.0000260000 0.0002850000 0.0394230000 8651236 96830484 1769345024 3.8395102024 4.0097532272 4.1174640656 359 14.3200000000 0.0099995099 0.0052009461 0.0103800977 0.0095834782 0.1064490000 0.0083840000 0.0411160000 0.0003130000 0.0002700000 0.0525250000 8652910 96830484 1771028480 3.8390767574 4.0087575912 4.1148667336 360 14.3600000000 0.0099811731 0.0052142245 0.0103800977 0.0095712171 0.1258890000 0.0097600000 0.0494620000 0.0000240000 0.0002830000 0.0482850000 8654584 96830484 1769979904 3.8389017582 4.0077710152 4.1125688553 361 14.4000000000 0.0099226283 0.0052272672 0.0103800977 0.0095679875 0.1706090000 0.0097280000 0.0645150000 0.0002880000 0.0002640000 0.0856560000 8656258 96830484 1768439808 3.8382058144 4.0075812340 4.1102981567 362 14.4400000000 0.0100009777 0.0052404543 0.0103800977 0.0095570777 0.1078200000 0.0086120000 0.0401440000 0.0000250000 0.0002830000 0.0448230000 8657932 96830484 1770246144 3.8378021717 4.0076656342 4.1074891090 363 14.4800000000 0.0098614218 0.0052531842 0.0103800977 0.0095443364 0.1495440000 0.0100530000 0.0686490000 0.0002850000 0.0002640000 0.0579670000 8659606 96830484 1769091072 3.8373227119 4.0067801476 4.1054086685 364 14.5200000000 0.0099967215 0.0052662159 0.0103800977 0.0095361328 0.1496700000 0.0080520000 0.0803650000 0.0000070000 0.0000780000 0.0514730000 8661280 96830484 1770708992 3.8370041847 4.0065121651 4.1030230522 365 14.5600000000 0.0102491099 0.0052798677 0.0103800977 0.0095257031 0.1799000000 0.0099720000 0.0592440000 0.0002950000 0.0011520000 0.0892670000 8662954 96830484 1769979904 3.8363363743 4.0072741508 4.1005244255 366 14.6000000000 0.0100859841 0.0052929991 0.0103800977 0.0095165629 0.1129570000 0.0099460000 0.0541610000 0.0000250000 0.0003560000 0.0418290000 8664628 96830484 1768583168 3.8364133835 4.0072226524 4.0981850624 367 14.6400000000 0.0100407749 0.0053059358 0.0103800977 0.0095078275 0.1267140000 0.0084920000 0.0541090000 0.0003710000 0.0002770000 0.0488750000 8666302 96830484 1770373120 3.8361601830 4.0059156418 4.0957875252 368 14.6800000000 0.0100153787 0.0053187332 0.0103800977 0.0094984901 0.1288370000 0.0099700000 0.0609890000 0.0000280000 0.0003720000 0.0415810000 8667976 96830484 1769472000 3.8357653618 4.0053191185 4.0934195518 369 14.7200000000 0.0100944005 0.0053316754 0.0103800977 0.0094893275 0.1370710000 0.0101300000 0.0467460000 0.0003160000 0.0003440000 0.0755230000 8669650 96830484 1768095744 3.8350358009 4.0053515434 4.0910372734 370 14.7600000000 0.0100325849 0.0053443806 0.0103800977 0.0094772342 0.1017770000 0.0084060000 0.0416410000 0.0000260000 0.0002950000 0.0435370000 8671324 96830484 1769738240 3.8347780704 4.0056118965 4.0889120102 371 14.8000000000 0.0099585932 0.0053568178 0.0103800977 0.0094647563 0.1486190000 0.0094170000 0.0827520000 0.0000600000 0.0000540000 0.0480020000 8672998 96830484 1768550400 3.8340034485 4.0061087608 4.0862240791 372 14.8400000000 0.0102413585 0.0053699483 0.0103800977 0.0094580560 0.1078040000 0.0083620000 0.0469480000 0.0000260000 0.0003850000 0.0408030000 8674672 96830484 1770217472 3.8334388733 4.0063366890 4.0832872391 373 14.8800000000 0.0101311868 0.0053827130 0.0103800977 0.0094514571 0.1496240000 0.0103900000 0.0526790000 0.0002930000 0.0002660000 0.0757100000 8676346 96830484 1769218048 3.8332991600 4.0066523552 4.0805673599 374 14.9200000000 0.0101977261 0.0053955874 0.0103800977 0.0094559872 0.1076500000 0.0086500000 0.0407530000 0.0000250000 0.0002930000 0.0428240000 8678020 96830484 1770901504 3.8325297832 4.0070919991 4.0782446861 375 14.9600000000 0.0103268977 0.0054087376 0.0103800977 0.0094692536 0.1284290000 0.0099360000 0.0533820000 0.0002930000 0.0002740000 0.0472270000 8679694 96830484 1769725952 3.8316133022 4.0060138702 4.0762338638 376 15.0000000000 0.0102568613 0.0054216315 0.0103800977 0.0094598407 0.1099530000 0.0102220000 0.0460810000 0.0000280000 0.0003040000 0.0402160000 8681368 96830484 1768714240 3.8314671516 4.0054244995 4.0739440918 377 15.0400000000 0.0101663154 0.0054342169 0.0103800977 0.0094477687 0.1304810000 0.0086580000 0.0406060000 0.0003690000 0.0002790000 0.0765240000 8683042 96830484 1770393600 3.8301680088 4.0063753128 4.0714921951 378 15.0800000000 0.0102847684 0.0054470490 0.0103800977 0.0094575898 0.1079120000 0.0103530000 0.0456580000 0.0000250000 0.0002970000 0.0421530000 8684716 96830484 1769218048 3.8299999237 4.0060324669 4.0687336922 379 15.1200000000 0.0106709199 0.0054608323 0.0106709199 0.0094532074 0.1309050000 0.0083260000 0.0685400000 0.0003290000 0.0002680000 0.0492650000 8686390 96830484 1770835968 3.8297812939 4.0053997040 4.0663337708 380 15.1600000000 0.0104254140 0.0054738970 0.0106709199 0.0094407647 0.1255710000 0.0100300000 0.0628460000 0.0000260000 0.0003040000 0.0398070000 8688064 96830484 1769852928 3.8290290833 4.0053491592 4.0634799004 381 15.2000000000 0.0107126096 0.0054876469 0.0107126096 0.0094295368 0.1493860000 0.0107750000 0.0478770000 0.0003830000 0.0002820000 0.0777940000 8689738 96830484 1768312832 3.8280224800 4.0056276321 4.0612778664 382 15.2400000000 0.0107932212 0.0055015358 0.0107932212 0.0094183681 0.1087560000 0.0087700000 0.0487360000 0.0000290000 0.0003030000 0.0394690000 8691412 96830484 1770119168 3.8276987076 4.0053234100 4.0583496094 383 15.2800000000 0.0104985936 0.0055145830 0.0107932212 0.0094061740 0.1104800000 0.0107270000 0.0472750000 0.0003110000 0.0003450000 0.0460360000 8693086 96830484 1768964096 3.8268518448 4.0051727295 4.0562210083 384 15.3200000000 0.0106263980 0.0055278950 0.0107932212 0.0093946269 0.1076140000 0.0089950000 0.0480530000 0.0000280000 0.0003070000 0.0393000000 8694760 96830484 1770737664 3.8255217075 4.0055594444 4.0535440445 385 15.3600000000 0.0105034765 0.0055408186 0.0107932212 0.0093849691 0.1484080000 0.0106310000 0.0473800000 0.0003890000 0.0002740000 0.0758220000 8696434 96830484 1769472000 3.8243706226 4.0057897568 4.0512948036 386 15.4000000000 0.0105930166 0.0055539072 0.0107932212 0.0093743615 0.0929140000 0.0104430000 0.0397500000 0.0000250000 0.0002950000 0.0382390000 8698108 96830484 1768169472 3.8235652447 4.0059947968 4.0483541489 387 15.4400000000 0.0107295690 0.0055672810 0.0107932212 0.0093625699 0.1445440000 0.0087450000 0.0772550000 0.0003200000 0.0005200000 0.0473160000 8699782 96830484 1767292928 3.8223545551 4.0066542625 4.0456171036 388 15.4800000000 0.0106466329 0.0055803721 0.0107932212 0.0093546536 0.1439060000 0.0083610000 0.0815140000 0.0000060000 0.0000600000 0.0385960000 8701456 96830484 1766432768 3.8209609985 4.0073075294 4.0436429977 389 15.5200000000 0.0105355354 0.0055931103 0.0107932212 0.0093515177 0.1364330000 0.0092910000 0.0469690000 0.0003170000 0.0003410000 0.0753020000 8703130 96830484 1765163008 3.8200628757 4.0075931549 4.0409035683 390 15.5600000000 0.0107380832 0.0056063026 0.0107932212 0.0093450246 0.1406930000 0.0088220000 0.0821120000 0.0000260000 0.0003060000 0.0388250000 8704804 96830484 1765175296 3.8183577061 4.0080943108 4.0386352539 391 15.6000000000 0.0104421023 0.0056186703 0.0107932212 0.0093359148 0.1086690000 0.0093520000 0.0488760000 0.0003340000 0.0002750000 0.0455830000 8706478 96830484 1764532224 3.8169667721 4.0088801384 4.0361089706 392 15.6400000000 0.0105033778 0.0056311313 0.0107932212 0.0093364399 0.1071980000 0.0091370000 0.0478260000 0.0000270000 0.0003860000 0.0390690000 8708152 96830484 1766203392 3.8154666424 4.0095248222 4.0337018967 393 15.6800000000 0.0105783092 0.0056437196 0.0107932212 0.0093343011 0.1280670000 0.0089530000 0.0395900000 0.0003060000 0.0003420000 0.0746050000 8709826 96830484 1767788544 3.8147475719 4.0099182129 4.0312390327 394 15.7200000000 0.0105254110 0.0056561096 0.0107932212 0.0093296650 0.1089640000 0.0088060000 0.0452380000 0.0000260000 0.0006040000 0.0408360000 8711500 96830484 1769582592 3.8134720325 4.0103969574 4.0288963318 395 15.7600000000 0.0105411531 0.0056684768 0.0107932212 0.0093229158 0.1515000000 0.0101700000 0.0918200000 0.0000600000 0.0000530000 0.0451370000 8713174 96830484 1768714240 3.8112919331 4.0112805367 4.0262250900 396 15.8000000000 0.0105173076 0.0056807214 0.0107932212 0.0093185482 0.1453860000 0.0090350000 0.0789810000 0.0000280000 0.0005920000 0.0384850000 8714848 96830484 1770471424 3.8106141090 4.0121879578 4.0233464241 397 15.8400000000 0.0105382409 0.0056929569 0.0107932212 0.0093228836 0.1299950000 0.0112850000 0.0400590000 0.0003090000 0.0003460000 0.0737100000 8716522 96830484 1769345024 3.8090751171 4.0128641129 4.0213298798 398 15.8800000000 0.0106190611 0.0057053341 0.0107932212 0.0093322043 0.1089300000 0.0094080000 0.0471570000 0.0000250000 0.0003690000 0.0375380000 8718196 96830484 1771118592 3.8079175949 4.0124683380 4.0187115669 399 15.9200000000 0.0105368756 0.0057174432 0.0107932212 0.0093247984 0.1291570000 0.0110100000 0.0595380000 0.0003810000 0.0002760000 0.0442650000 8719870 96830484 1769852928 3.8067038059 4.0122756958 4.0165352821 400 15.9600000000 0.0105617298 0.0057295539 0.0107932212 0.0093140551 0.0951040000 0.0108830000 0.0404620000 0.0000960000 0.0003340000 0.0389610000 8721544 96830484 1768456192 3.8052248955 4.0135354996 4.0139966011 401 16.0000000000 0.0104020135 0.0057412059 0.0107932212 0.0093188707 0.1276600000 0.0088570000 0.0402390000 0.0003060000 0.0003490000 0.0735100000 8723218 96830484 1767694336 3.8045160770 4.0135550499 4.0116653442 402 16.0400000000 0.0103985984 0.0057527915 0.0107932212 0.0093151765 0.1413510000 0.0089140000 0.0804580000 0.0000260000 0.0002960000 0.0382310000 8724892 96830484 1769357312 3.8030493259 4.0139026642 4.0094532967 403 16.0800000000 0.0103239706 0.0057641344 0.0107932212 0.0093170959 0.1093630000 0.0104730000 0.0400830000 0.0003770000 0.0002840000 0.0466360000 8726566 96830484 1768202240 3.8017368317 4.0145487785 4.0071697235 404 16.1200000000 0.0104689812 0.0057757800 0.0107932212 0.0093327412 0.1286360000 0.0084880000 0.0647570000 0.0000270000 0.0003170000 0.0419370000 8728240 96830484 1769947136 3.8016421795 4.0152397156 4.0046248436 405 16.1600000000 0.0104892049 0.0057874181 0.0107932212 0.0093537079 0.1498220000 0.0102970000 0.0637180000 0.0003030000 0.0002920000 0.0707610000 8729914 96830484 1768820736 3.8002960682 4.0149149895 4.0028476715 406 16.2000000000 0.0104850959 0.0057989887 0.0107932212 0.0093487680 0.1101430000 0.0091600000 0.0588360000 0.0000270000 0.0003730000 0.0374000000 8731588 96830484 1770737664 3.7998213768 4.0164389610 4.0004367828 407 16.2400000000 0.0105651552 0.0058106992 0.0107932212 0.0093644823 0.1297250000 0.0107540000 0.0728980000 0.0002990000 0.0005180000 0.0407800000 8733262 96830484 1769852928 3.7989072800 4.0166511536 3.9986426830 408 16.2800000000 0.0105006760 0.0058221943 0.0107932212 0.0093694689 0.1303180000 0.0107680000 0.0804040000 0.0000260000 0.0003670000 0.0343880000 8734936 96830484 1768423424 3.7983779907 4.0167379379 3.9964818954 409 16.3200000000 0.0106059862 0.0058338906 0.0107932212 0.0093626565 0.1398140000 0.0089220000 0.0548020000 0.0003160000 0.0002710000 0.0709980000 8736610 96830484 1770119168 3.7973651886 4.0168709755 3.9944536686 410 16.3600000000 0.0105024250 0.0058452773 0.0107932212 0.0093531787 0.1336030000 0.0104280000 0.0738260000 0.0000270000 0.0002950000 0.0375630000 8738284 96830484 1769074688 3.7969403267 4.0179796219 3.9922401905 411 16.3999999990 0.0104870358 0.0058565711 0.0107932212 0.0093600822 0.1085990000 0.0092260000 0.0404340000 0.0003140000 0.0002750000 0.0458410000 8739958 96830484 1770774528 3.7966914177 4.0184788704 3.9902248383 412 16.4400000000 0.0103978170 0.0058675935 0.0107932212 0.0093656171 0.1885650000 0.0103250000 0.1212020000 0.0000290000 0.0003110000 0.0411840000 8741632 96830484 1769598976 3.7964968681 4.0190806389 3.9880118370 413 16.4800000000 0.0102759385 0.0058782675 0.0107932212 0.0093641906 0.1290010000 0.0100440000 0.0377060000 0.0003800000 0.0002880000 0.0688680000 8743306 96830484 1768206336 3.7957122326 4.0190873146 3.9859807491 414 16.5200000000 0.0104298219 0.0058892616 0.0107932212 0.0093563818 0.1463240000 0.0089900000 0.0799300000 0.0000290000 0.0002940000 0.0365710000 8744980 96830484 1769865216 3.7956063747 4.0194697380 3.9838194847 415 16.5599999990 0.0105750505 0.0059005526 0.0107932212 0.0093455976 0.1327450000 0.0104750000 0.0729240000 0.0002900000 0.0002640000 0.0429070000 8746654 96830484 1768697856 3.7951459885 4.0205345154 3.9813477993 416 16.6000000000 0.0104052471 0.0059113812 0.0107932212 0.0093391197 0.1083190000 0.0086200000 0.0542070000 0.0000280000 0.0002960000 0.0369420000 8748328 96830484 1770471424 3.7948312759 4.0205125809 3.9791796207 417 16.6400000000 0.0104337102 0.0059222261 0.0107932212 0.0093335479 0.1464350000 0.0108410000 0.0614090000 0.0003630000 0.0002750000 0.0690210000 8750002 96830484 1769598976 3.7939703465 4.0211758614 3.9768087864 418 16.6800000000 0.0105465818 0.0059332892 0.0107932212 0.0093328860 0.1297700000 0.0104400000 0.0663970000 0.0000270000 0.0002970000 0.0371410000 8751676 96830484 1768353792 3.7930550575 4.0223088264 3.9743752480 419 16.7199999990 0.0104884701 0.0059441607 0.0107932212 0.0093450055 0.1091060000 0.0089870000 0.0401100000 0.0002990000 0.0003470000 0.0461700000 8753350 96830484 1769992192 3.7924635410 4.0235056877 3.9716429710 420 16.7600000000 0.0107501438 0.0059556035 0.0107932212 0.0093672381 0.1689170000 0.0099470000 0.1060910000 0.0000270000 0.0019580000 0.0371720000 8755024 96830484 1768841216 3.7927839756 4.0236816406 3.9691681862 421 16.8000000000 0.0108344434 0.0059671922 0.0108344434 0.0093636559 0.1307760000 0.0089250000 0.0475070000 0.0003960000 0.0002670000 0.0690760000 8756698 96830484 1770598400 3.7919762135 4.0243940353 3.9663934708 422 16.8400000000 0.0109401979 0.0059789766 0.0109401979 0.0093586492 0.1087690000 0.0104880000 0.0531870000 0.0000280000 0.0002990000 0.0365370000 8758372 96830484 1769709568 3.7926044464 4.0252938271 3.9635565281 423 16.8799999990 0.0109685073 0.0059907722 0.0109685073 0.0093536408 0.1078960000 0.0110140000 0.0415400000 0.0006890000 0.0002710000 0.0427560000 8760046 96830484 1768333312 3.7917699814 4.0259323120 3.9609708786 424 16.9200000000 0.0108410222 0.0060022115 0.0109685073 0.0093484079 0.1070790000 0.0086750000 0.0589150000 0.0000280000 0.0003520000 0.0345730000 8761720 96830484 1769992192 3.7917196751 4.0268979073 3.9579131603 425 16.9600000000 0.0108423494 0.0060136000 0.0109685073 0.0093651770 0.1659860000 0.0109260000 0.0682390000 0.0002870000 0.0002620000 0.0714840000 8763394 96830484 1768964096 3.7916853428 4.0271406174 3.9548683167 426 17.0000000000 0.0110682305 0.0060254654 0.0110682305 0.0093639790 0.1114580000 0.0089700000 0.0602950000 0.0000280000 0.0003620000 0.0356620000 8765068 96830484 1770647552 3.7920124531 4.0274596214 3.9520001411 427 17.0400000000 0.0110591063 0.0060372537 0.0110682305 0.0093538594 0.1088450000 0.0109850000 0.0492860000 0.0003210000 0.0003450000 0.0430940000 8766742 96830484 1769598976 3.7919015884 4.0271024704 3.9491574764 428 17.0800000000 0.0113953929 0.0060497728 0.0113953929 0.0093430664 0.1085270000 0.0088600000 0.0544190000 0.0000280000 0.0005180000 0.0388980000 8768416 96830484 1771266048 3.7935323715 4.0281229019 3.9457941055 429 17.1200000000 0.0112350155 0.0060618596 0.0113953929 0.0093333570 0.1464680000 0.0106950000 0.0555800000 0.0002910000 0.0003380000 0.0703150000 8770090 96830484 1770090496 3.7939326763 4.0281000137 3.9426119328 430 17.1600000000 0.0112793213 0.0060739932 0.0113953929 0.0093227273 0.1109730000 0.0105440000 0.0632940000 0.0000290000 0.0003700000 0.0320440000 8771764 96830484 1768583168 3.7936522961 4.0284419060 3.9396374226 431 17.2000000000 0.0111993412 0.0060858850 0.0113953929 0.0093120312 0.1066350000 0.0085470000 0.0411350000 0.0003820000 0.0002700000 0.0439290000 8773438 96830484 1770369024 3.7937366962 4.0291938782 3.9361202717 432 17.2400000000 0.0112683950 0.0060978815 0.0113953929 0.0093063667 0.1732820000 0.0098750000 0.1247110000 0.0000290000 0.0003140000 0.0336890000 8775112 96830484 1769234432 3.7936003208 4.0296630859 3.9331853390 433 17.2800000000 0.0112391887 0.0061097552 0.0113953929 0.0093039892 0.1600150000 0.0084010000 0.0790820000 0.0003260000 0.0003520000 0.0668260000 8776786 96830484 1770881024 3.7933387756 4.0299363136 3.9298067093 434 17.3200000000 0.0112036439 0.0061214923 0.0113953929 0.0092970240 0.0952170000 0.0100570000 0.0434860000 0.0000290000 0.0003140000 0.0366980000 8778460 96830484 1769852928 3.7939434052 4.0303201675 3.9268214703 435 17.3600000000 0.0111767696 0.0061331136 0.0113953929 0.0092874950 0.1457340000 0.0083930000 0.0804260000 0.0000630000 0.0000540000 0.0442250000 8780134 96830484 1768710144 3.7940254211 4.0317473412 3.9233427048 436 17.4000000000 0.0112546775 0.0061448603 0.0113953929 0.0092956286 0.1476400000 0.0081420000 0.0882340000 0.0000270000 0.0003780000 0.0353140000 8781808 96830484 1768169472 3.7950208187 4.0322608948 3.9201486111 437 17.4400000000 0.0112864552 0.0061566260 0.0113953929 0.0093116825 0.1282210000 0.0084260000 0.0485400000 0.0003110000 0.0002740000 0.0657660000 8783482 96830484 1769709568 3.7956821918 4.0325255394 3.9173996449 438 17.4800000000 0.0110363225 0.0061677668 0.0113953929 0.0093092746 0.1109900000 0.0104870000 0.0557450000 0.0000290000 0.0003660000 0.0349450000 8785156 96830484 1768476672 3.7966527939 4.0325737000 3.9141075611 439 17.5200000000 0.0110033145 0.0061787817 0.0113953929 0.0093078925 0.1273550000 0.0085030000 0.0613320000 0.0003840000 0.0002730000 0.0414610000 8786830 96830484 1770229760 3.7989373207 4.0329947472 3.9110095501 440 17.5600000000 0.0110730808 0.0061899051 0.0113953929 0.0093121683 0.1314200000 0.0108700000 0.0807770000 0.0000270000 0.0003040000 0.0346000000 8788504 96830484 1769345024 3.7996513844 4.0333170891 3.9083337784 441 17.6000000000 0.0110297147 0.0062008798 0.0113953929 0.0093164481 0.1466110000 0.0085050000 0.0561500000 0.0003040000 0.0002700000 0.0694540000 8790178 96830484 1771118592 3.8001959324 4.0338139534 3.9056701660 442 17.6400000000 0.0109910350 0.0062117172 0.0113953929 0.0093275363 0.1095830000 0.0102120000 0.0546930000 0.0000260000 0.0002940000 0.0348400000 8791852 96830484 1770233856 3.8002574444 4.0334138870 3.9029335976 443 17.6800000000 0.0110259214 0.0062225845 0.0113953929 0.0093301186 0.1287930000 0.0103270000 0.0683220000 0.0003660000 0.0002800000 0.0410050000 8793526 96830484 1769201664 3.8004112244 4.0328679085 3.9005968571 444 17.7200000000 0.0111858575 0.0062337630 0.0113953929 0.0093230682 0.1295540000 0.0086080000 0.0816310000 0.0000940000 0.0003130000 0.0342140000 8795200 96830484 1770881024 3.8001732826 4.0329217911 3.8980185986 445 17.7600000000 0.0108558955 0.0062441499 0.0113953929 0.0093125840 0.1471400000 0.0104860000 0.0567650000 0.0003040000 0.0002830000 0.0685830000 8796874 96830484 1769725952 3.8010654449 4.0335383415 3.8951890469 446 17.8000000000 0.0111350305 0.0062551160 0.0113953929 0.0093030302 0.1303740000 0.0103790000 0.0812420000 0.0000280000 0.0002960000 0.0337340000 8798548 96830484 1768349696 3.8002402782 4.0338554382 3.8924310207 447 17.8400000000 0.0109443944 0.0062656065 0.0113953929 0.0092963727 0.1079720000 0.0082800000 0.0490280000 0.0003720000 0.0010610000 0.0405540000 8800222 96830484 1770119168 3.8008563519 4.0343213081 3.8899707794 448 17.8800000000 0.0112966327 0.0062768365 0.0113953929 0.0092874546 0.1296490000 0.0104090000 0.0786700000 0.0000250000 0.0002960000 0.0349750000 8801896 96830484 1769074688 3.8004159927 4.0345997810 3.8874781132 449 17.9200000000 0.0111964671 0.0062877933 0.0113953929 0.0092803789 0.1843930000 0.0085830000 0.0814250000 0.0000600000 0.0000530000 0.0693130000 8803570 96830484 1770754048 3.8014469147 4.0335350037 3.8852458000 450 17.9600000000 0.0112234335 0.0062987614 0.0113953929 0.0092703328 0.0937330000 0.0103530000 0.0420840000 0.0000250000 0.0010690000 0.0345580000 8805244 96830484 1769836544 3.8011453152 4.0346107483 3.8801205158 451 18.0000000000 0.0112501103 0.0063097400 0.0113953929 0.0092770365 0.1471470000 0.0088480000 0.0853720000 0.0000600000 0.0000530000 0.0419440000 8806918 96830484 1768865792 3.8014361858 4.0343728065 3.8776245117 452 18.0400000000 0.0111667700 0.0063204857 0.0113953929 0.0092843827 0.1301100000 0.0084220000 0.0807440000 0.0000240000 0.0003540000 0.0344970000 8808592 96830484 1767956480 3.8012208939 4.0330653191 3.8754992485 453 18.0800000000 0.0113288304 0.0063315416 0.0113953929 0.0092891944 0.1631250000 0.0101340000 0.0814960000 0.0003810000 0.0002800000 0.0660010000 8810266 96830484 1766932480 3.8005459309 4.0325193405 3.8732070923 454 18.1200000000 0.0112482114 0.0063423713 0.0113953929 0.0092839934 0.0927560000 0.0078960000 0.0350940000 0.0000080000 0.0000770000 0.0367750000 8811940 96830484 1768439808 3.8004174232 4.0330538750 3.8703505993 455 18.1600000000 0.0110815940 0.0063527872 0.0113953929 0.0092739403 0.1495420000 0.0080010000 0.0760070000 0.0002890000 0.0002650000 0.0548060000 8813614 96830484 1770090496 3.8001124859 4.0341477394 3.8673572540 456 18.2000000000 0.0114120552 0.0063638821 0.0114120552 0.0092644301 0.1707280000 0.0104400000 0.1136020000 0.0000250000 0.0003690000 0.0388370000 8815288 96830484 1768837120 3.7989552021 4.0353770256 3.8645954132 457 18.2400000000 0.0112668229 0.0063746106 0.0114120552 0.0092674774 0.1815510000 0.0080320000 0.0976540000 0.0002890000 0.0003360000 0.0702310000 8816962 96830484 1770471424 3.7989666462 4.0350074768 3.8621494770 458 18.2800000000 0.0114164567 0.0063856190 0.0114164567 0.0092640552 0.1353840000 0.0104290000 0.0803090000 0.0000270000 0.0003050000 0.0345430000 8818636 96830484 1769582592 3.7977967262 4.0358681679 3.8593246937 459 18.3200000000 0.0112317270 0.0063961770 0.0114164567 0.0092809562 0.1049970000 0.0101360000 0.0413250000 0.0002850000 0.0002640000 0.0427840000 8820310 96830484 1768095744 3.7972817421 4.0358843803 3.8567595482 460 18.3600000000 0.0112765487 0.0064067865 0.0114164567 0.0092865447 0.1116680000 0.0079880000 0.0581540000 0.0000310000 0.0003040000 0.0401930000 8821984 96830484 1769738240 3.7968585491 4.0360546112 3.8538045883 461 18.4000000000 0.0112825250 0.0064173629 0.0114164567 0.0092834981 0.1443490000 0.0094210000 0.0540700000 0.0002890000 0.0003470000 0.0752420000 8823658 96830484 1768349696 3.7960238457 4.0363540649 3.8510420322 462 18.4400000000 0.0112842256 0.0064278972 0.0114164567 0.0093055185 0.1315120000 0.0083260000 0.0808720000 0.0000230000 0.0003500000 0.0339840000 8825332 96830484 1769963520 3.7957103252 4.0355257988 3.8485488892 463 18.4800000000 0.0112782810 0.0064383732 0.0114164567 0.0093112155 0.1284130000 0.0102810000 0.0691040000 0.0002820000 0.0002620000 0.0404200000 8827006 96830484 1768837120 3.7951874733 4.0356884003 3.8455858231 464 18.5200000000 0.0113117043 0.0064488761 0.0114164567 0.0093119815 0.1070980000 0.0083660000 0.0488300000 0.0000260000 0.0003780000 0.0339350000 8828680 96830484 1770582016 3.7942659855 4.0350751877 3.8430452347 465 18.5600000000 0.0112878364 0.0064592825 0.0114164567 0.0093093318 0.1492510000 0.0102900000 0.0551150000 0.0003010000 0.0002580000 0.0674390000 8830354 96830484 1769582592 3.7936022282 4.0355038643 3.8399786949 466 18.6000000000 0.0112334443 0.0064695274 0.0114164567 0.0093002043 0.1285050000 0.0100930000 0.0690320000 0.0000280000 0.0003100000 0.0342870000 8832028 96830484 1768083456 3.7923274040 4.0367722511 3.8366892338 467 18.6400000000 0.0112605859 0.0064797867 0.0114164567 0.0092903255 0.0936420000 0.0084240000 0.0410750000 0.0002910000 0.0003480000 0.0385220000 8833702 96830484 1769852928 3.7909672260 4.0379924774 3.8335642815 468 18.6800000000 0.0113983061 0.0064902963 0.0114164567 0.0092811056 0.1283390000 0.0094730000 0.0826160000 0.0000240000 0.0003600000 0.0308700000 8835376 96830484 1768722432 3.7893400192 4.0392389297 3.8303687572 469 18.7200000000 0.0113416919 0.0065006405 0.0114164567 0.0092809437 0.1598980000 0.0081310000 0.0821860000 0.0004590000 0.0002810000 0.0636980000 8837050 96830484 1770479616 3.7888417244 4.0396275520 3.8275184631 470 18.7600000000 0.0113927396 0.0065110492 0.0114164567 0.0092714373 0.1397140000 0.0100180000 0.0830080000 0.0000270000 0.0002960000 0.0413170000 8838724 96830484 1769607168 3.7867927551 4.0423560143 3.8240904808 471 18.8000000000 0.0113732284 0.0065213723 0.0114164567 0.0093032338 0.1225280000 0.0103900000 0.0561680000 0.0003630000 0.0002730000 0.0401550000 8840398 96830484 1768177664 3.7869136333 4.0421066284 3.8214490414 472 18.8400000000 0.0113574108 0.0065316181 0.0114164567 0.0093923088 0.0936670000 0.0085770000 0.0485080000 0.0000260000 0.0002900000 0.0311150000 8842072 96830484 1770000384 3.7860763073 4.0432648659 3.8184123039 473 18.8800000000 0.0113226818 0.0065417472 0.0114164567 0.0094586736 0.1281730000 0.0100560000 0.0493770000 0.0003110000 0.0002810000 0.0630600000 8843746 96830484 1768701952 3.7850978374 4.0428605080 3.8154036999 474 18.9200000000 0.0113676591 0.0065519285 0.0114164567 0.0094585737 0.1064500000 0.0078530000 0.0561070000 0.0000250000 0.0003160000 0.0340120000 8845420 96830484 1770496000 3.7833185196 4.0434107780 3.8126356602 475 18.9600000000 0.0113505358 0.0065620308 0.0114164567 0.0094542007 0.1105880000 0.0105000000 0.0570160000 0.0002940000 0.0002740000 0.0373940000 8847094 96830484 1769099264 3.7821424007 4.0447645187 3.8098437786 476 19.0000000000 0.0114290677 0.0065722557 0.0114290677 0.0094698684 0.1070820000 0.0081770000 0.0566950000 0.0000280000 0.0003050000 0.0338510000 8848768 96830484 1770782720 3.7807838917 4.0464835167 3.8069503307 477 19.0400000000 0.0113611901 0.0065822954 0.0114290677 0.0094685626 0.1286550000 0.0101930000 0.0499950000 0.0003830000 0.0002770000 0.0626410000 8850442 96830484 1769734144 3.7800233364 4.0483937263 3.8038966656 478 19.0800000000 0.0113666710 0.0065923045 0.0114290677 0.0094599587 0.1077740000 0.0098070000 0.0503540000 0.0000320000 0.0003810000 0.0332420000 8852116 96830484 1768194048 3.7789609432 4.0505537987 3.8013541698 479 19.1200000000 0.0112958737 0.0066021241 0.0114290677 0.0094584295 0.1082870000 0.0086410000 0.0424260000 0.0011950000 0.0003420000 0.0398990000 8853790 96830484 1769955328 3.7775976658 4.0514650345 3.7987368107 480 19.1600000000 0.0114503503 0.0066122245 0.0114503503 0.0094604285 0.1316320000 0.0100240000 0.0829150000 0.0000260000 0.0003580000 0.0331690000 8855464 96830484 1768849408 3.7764794827 4.0525174141 3.7961964607 481 19.2000000000 0.0113560269 0.0066220869 0.0114503503 0.0094573356 0.1270320000 0.0082210000 0.0506990000 0.0005040000 0.0002890000 0.0621300000 8857138 96830484 1770606592 3.7755498886 4.0531840324 3.7936913967 482 19.2400000000 0.0113973860 0.0066319942 0.0114503503 0.0094548772 0.1082250000 0.0104440000 0.0502930000 0.0000290000 0.0003730000 0.0331680000 8858812 96830484 1769734144 3.7747774124 4.0543155670 3.7911369801 483 19.2800000000 0.0114301508 0.0066419283 0.0114503503 0.0094759902 0.1088190000 0.0101920000 0.0435280000 0.0003130000 0.0002740000 0.0402310000 8860486 96830484 1768341504 3.7737388611 4.0536050797 3.7891068459 484 19.3200000000 0.0114468513 0.0066518558 0.0114503503 0.0094735382 0.1304800000 0.0083000000 0.0817210000 0.0000300000 0.0003020000 0.0328170000 8862160 96830484 1769979904 3.7733080387 4.0540542603 3.7870161533 485 19.3600000000 0.0114104096 0.0066616672 0.0114503503 0.0094654111 0.1279570000 0.0100600000 0.0500160000 0.0003000000 0.0002700000 0.0620050000 8863834 96830484 1768595456 3.7730436325 4.0542621613 3.7853107452 486 19.4000000000 0.0114120552 0.0066714417 0.0114503503 0.0094567943 0.0900570000 0.0081190000 0.0417350000 0.0000290000 0.0003060000 0.0346650000 8865508 96830484 1770364928 3.7729284763 4.0549421310 3.7831926346 487 19.4400000000 0.0115086026 0.0066813743 0.0115086026 0.0094503666 0.1684090000 0.0095410000 0.1038280000 0.0003820000 0.0002800000 0.0462510000 8867182 96830484 1769336832 3.7723584175 4.0560889244 3.7812194824 488 19.4800000000 0.0115584517 0.0066913683 0.0115584517 0.0094466230 0.1086010000 0.0079480000 0.0502930000 0.0000280000 0.0003110000 0.0415750000 8868856 96830484 1771020288 3.7717576027 4.0568232536 3.7790839672 489 19.5200000000 0.0114789633 0.0067011589 0.0115584517 0.0094512241 0.1653170000 0.0095400000 0.0759000000 0.0000640000 0.0000550000 0.0572060000 8870530 96830484 1769861120 3.7720861435 4.0564465523 3.7771797180 490 19.5600000000 0.0114789885 0.0067109095 0.0115584517 0.0094461614 0.0930360000 0.0101200000 0.0424370000 0.0000250000 0.0011290000 0.0324310000 8872204 96830484 1768468480 3.7719397545 4.0571794510 3.7751789093 491 19.6000000000 0.0115901083 0.0067208468 0.0115901083 0.0094380255 0.1244960000 0.0087560000 0.0572320000 0.0003860000 0.0002700000 0.0399850000 8873878 96830484 1767972864 3.7707049847 4.0575294495 3.7732491493 492 19.6400000000 0.0116144400 0.0067307931 0.0116144400 0.0094296907 0.1111570000 0.0087340000 0.0612360000 0.0000280000 0.0003280000 0.0317770000 8875552 96830484 1767075840 3.7710466385 4.0584602356 3.7713282108 493 19.6800000000 0.0116229253 0.0067407163 0.0116229253 0.0094249619 0.1681480000 0.0079090000 0.0861810000 0.0000590000 0.0000530000 0.0631020000 8877226 96830484 1766055936 3.7707870007 4.0585975647 3.7694058418 494 19.7200000000 0.0116543937 0.0067506630 0.0116543937 0.0094172710 0.0901690000 0.0078910000 0.0425520000 0.0000930000 0.0002890000 0.0339580000 8878900 96830484 1767559168 3.7709879875 4.0595688820 3.7674255371 495 19.7600000000 0.0116736963 0.0067606085 0.0116736963 0.0094196465 0.1264950000 0.0081720000 0.0657060000 0.0003480000 0.0002740000 0.0383590000 8880574 96830484 1769324544 3.7699706554 4.0591597557 3.7652959824 496 19.8000000000 0.0116595132 0.0067704854 0.0116736963 0.0094202700 0.1097090000 0.0098060000 0.0562390000 0.0000270000 0.0002960000 0.0318990000 8882248 96830484 1767956480 3.7687144279 4.0592746735 3.7629036903 497 19.8400000000 0.0117415870 0.0067804876 0.0117415870 0.0094173075 0.1246240000 0.0081280000 0.0510900000 0.0002950000 0.0003480000 0.0593630000 8883922 96830484 1769717760 3.7684128284 4.0587716103 3.7610402107 498 19.8800000000 0.0118121821 0.0067905914 0.0118121821 0.0094126687 0.1470030000 0.0096650000 0.0843590000 0.0000260000 0.0003090000 0.0318520000 8885596 96830484 1768591360 3.7693634033 4.0569620132 3.7597591877 499 19.9200000000 0.0117829060 0.0068005960 0.0118121821 0.0094039868 0.1328740000 0.0083580000 0.0823670000 0.0003040000 0.0002750000 0.0361910000 8887270 96830484 1770352640 3.7702877522 4.0571689606 3.7576127052 500 19.9600000000 0.0117655890 0.0068105260 0.0118121821 0.0093950502 0.0893260000 0.0095400000 0.0436380000 0.0000300000 0.0003060000 0.0305090000 8888944 96830484 1769480192 3.7716128826 4.0577511787 3.7552850246 501 20.0000000000 0.0117986845 0.0068204824 0.0118121821 0.0094094384 0.1448770000 0.0094270000 0.0525670000 0.0005520000 0.0002760000 0.0647800000 8890618 96830484 1768812544 3.7703042030 4.0556788445 3.7528388500 502 20.0400000000 0.0118206292 0.0068304429 0.0118206292 0.0094264510 0.0908730000 0.0085350000 0.0421000000 0.0000290000 0.0003900000 0.0317020000 8892292 96830484 1770512384 3.7695100307 4.0549407005 3.7499833107 503 20.0800000000 0.0119557483 0.0068406323 0.0119557483 0.0094183478 0.1475480000 0.0101140000 0.0849780000 0.0003260000 0.0002730000 0.0382280000 8893966 96830484 1769353216 3.7695155144 4.0560669899 3.7472696304 504 20.1200000000 0.0119048273 0.0068506804 0.0119557483 0.0094097935 0.1076210000 0.0085690000 0.0492190000 0.0000270000 0.0003760000 0.0316980000 8895640 96830484 1771020288 3.7704229355 4.0566596985 3.7449696064 505 20.1600000000 0.0118356515 0.0068605516 0.0119557483 0.0094017227 0.1205310000 0.0100300000 0.0443800000 0.0003110000 0.0003490000 0.0598940000 8897314 96830484 1769971712 3.7710070610 4.0578241348 3.7422034740 506 20.2000000000 0.0118629392 0.0068704377 0.0119557483 0.0093934337 0.0994820000 0.0100890000 0.0498980000 0.0000310000 0.0003850000 0.0320760000 8898988 96830484 1768591360 3.7707715034 4.0588588715 3.7398140430 507 20.2400000000 0.0118662762 0.0068802915 0.0119557483 0.0093889209 0.1077640000 0.0081790000 0.0514300000 0.0003040000 0.0003460000 0.0379510000 8900662 96830484 1770254336 3.7700953484 4.0577211380 3.7372441292 508 20.2800000000 0.0119204568 0.0068902130 0.0119557483 0.0093825030 0.1079930000 0.0098350000 0.0515250000 0.0000260000 0.0003050000 0.0327410000 8902336 96830484 1769590784 3.7703962326 4.0577297211 3.7345111370 509 20.3200000000 0.0118992273 0.0069000539 0.0119557483 0.0093800169 0.1276210000 0.0100130000 0.0376330000 0.0003810000 0.0002780000 0.0621980000 8904010 96830484 1768050688 3.7716026306 4.0571703911 3.7324512005 510 20.3600000000 0.0119341537 0.0069099247 0.0119557483 0.0093812871 0.1084150000 0.0083830000 0.0497720000 0.0000320000 0.0003130000 0.0323750000 8905684 96830484 1769746432 3.7718365192 4.0582480431 3.7300784588 511 20.4000000000 0.0120110465 0.0069199073 0.0120110465 0.0093741257 0.0941180000 0.0102720000 0.0425910000 0.0003850000 0.0010830000 0.0343740000 8907358 96830484 1768357888 3.7716701031 4.0588641167 3.7274537086 512 20.4400000000 0.0119930292 0.0069298158 0.0120110465 0.0093658469 0.1038150000 0.0087050000 0.0433590000 0.0000270000 0.0003070000 0.0324110000 8909032 96830484 1766940672 3.7719562054 4.0594787598 3.7246086597 513 20.4800000000 0.0120158233 0.0069397300 0.0120158233 0.0093582725 0.1306580000 0.0083150000 0.0505240000 0.0003150000 0.0003470000 0.0654580000 8951666 96830484 1766207488 3.7747712135 4.0609221458 3.7217755318 514 20.5200000000 0.0120040718 0.0069495828 0.0120158233 0.0093529528 0.1032030000 0.0081230000 0.0641890000 0.0000050000 0.0000700000 0.0252910000 9037308 96830484 1765019648 3.7753598690 4.0609083176 3.7186112404 515 20.5600000000 0.0120977880 0.0069595793 0.0120977880 0.0093466408 0.1081710000 0.0097590000 0.0559410000 0.0010440000 0.0002840000 0.0353140000 9038982 96830484 1765056512 3.7767558098 4.0603690147 3.7159063816 516 20.6000000000 0.0120767439 0.0069694963 0.0120977880 0.0093434704 0.1062860000 0.0081790000 0.0548020000 0.0000280000 0.0003020000 0.0317460000 9040656 96830484 1764913152 3.7793281078 4.0598087311 3.7132656574 517 20.6400000000 0.0121554174 0.0069795271 0.0121554174 0.0093359718 0.1468010000 0.0082220000 0.0586920000 0.0003760000 0.0002850000 0.0618090000 9042330 96830484 1765130240 3.7814679146 4.0601992607 3.7108421326 518 20.6800000000 0.0121302921 0.0069894707 0.0121554174 0.0093305863 0.1099430000 0.0085530000 0.0561060000 0.0000280000 0.0002970000 0.0313090000 9044004 96830484 1766797312 3.7833247185 4.0609588623 3.7082989216 519 20.7200000000 0.0121450573 0.0069994044 0.0121554174 0.0093258032 0.1106550000 0.0084120000 0.0571530000 0.0003040000 0.0003460000 0.0374210000 9045678 96830484 1768435712 3.7846591473 4.0616064072 3.7056622505 520 20.7600000000 0.0122219799 0.0070094478 0.0122219799 0.0093211956 0.1296400000 0.0080320000 0.0848650000 0.0000270000 0.0002940000 0.0307400000 9047352 96830484 1770098688 3.7854793072 4.0613312721 3.7032802105 521 20.8000000000 0.0122336214 0.0070194750 0.0122336214 0.0093129101 0.1569880000 0.0103410000 0.0591030000 0.0003030000 0.0002810000 0.0588790000 9049026 96830484 1768828928 3.7863092422 4.0624465942 3.7010974884 522 20.8400000000 0.0122299567 0.0070294568 0.0122336214 0.0093047212 0.1126280000 0.0084190000 0.0573980000 0.0000270000 0.0003650000 0.0314500000 9050700 96830484 1770655744 3.7869620323 4.0645322800 3.6986999512 523 20.8800000000 0.0122477161 0.0070394343 0.0122477161 0.0092965316 0.1478750000 0.0104250000 0.0813440000 0.0000580000 0.0000520000 0.0380580000 9052374 96830484 1769463808 3.7878401279 4.0650219917 3.6964592934 524 20.9200000000 0.0123065300 0.0070494860 0.0123065300 0.0092886991 0.1110090000 0.0100090000 0.0582530000 0.0000280000 0.0003010000 0.0315700000 9054048 96830484 1768050688 3.7877819538 4.0650606155 3.6939792633 525 20.9600000000 0.0122906724 0.0070594692 0.0123065300 0.0092829910 0.1464090000 0.0083640000 0.0582340000 0.0003050000 0.0002800000 0.0610800000 9055722 96830484 1769738240 3.7884140015 4.0652537346 3.6916668415 526 21.0000000000 0.0123377722 0.0070695040 0.0123377722 0.0092791306 0.1107000000 0.0100510000 0.0578630000 0.0000950000 0.0003050000 0.0318370000 9057396 96830484 1768460288 3.7892091274 4.0659179688 3.6895096302 527 21.0400000000 0.0123762386 0.0070795737 0.0123762386 0.0092742541 0.1087840000 0.0084020000 0.0512140000 0.0003790000 0.0002750000 0.0381160000 9059070 96830484 1770090496 3.7896773815 4.0661425591 3.6876604557 528 21.0800000000 0.0123732965 0.0070895997 0.0123762386 0.0092760722 0.1067110000 0.0101550000 0.0450420000 0.0000290000 0.0003110000 0.0320700000 9060744 96830484 1769218048 3.7908451557 4.0664157867 3.6858484745 529 21.1200000000 0.0124133723 0.0070996636 0.0124133723 0.0092749105 0.1141110000 0.0084200000 0.0422340000 0.0011710000 0.0002910000 0.0560300000 9062418 96830484 1770991616 3.7915101051 4.0655651093 3.6839835644 530 21.1600000000 0.0124696214 0.0071097956 0.0124696214 0.0092761798 0.1037410000 0.0106710000 0.0433730000 0.0000280000 0.0003050000 0.0325950000 9064092 96830484 1769852928 3.7912235260 4.0655441284 3.6821317673 531 21.2000000000 0.0125403451 0.0071200226 0.0125403451 0.0092829137 0.1122080000 0.0102440000 0.0581190000 0.0003890000 0.0002740000 0.0373780000 9065766 96830484 1768853504 3.7917397022 4.0658636093 3.6803297997 532 21.2400000000 0.0125051569 0.0071301450 0.0125403451 0.0092925203 0.1091040000 0.0083320000 0.0652010000 0.0000270000 0.0003520000 0.0289890000 9067440 96830484 1770455040 3.7925708294 4.0644011497 3.6786994934 533 21.2800000000 0.0125322258 0.0071402803 0.0125403451 0.0093009983 0.1204020000 0.0103050000 0.0430230000 0.0010440000 0.0002790000 0.0597600000 9069114 96830484 1769598976 3.7931354046 4.0641102791 3.6770999432 534 21.3200000000 0.0126243643 0.0071505501 0.0126243643 0.0092950262 0.1140310000 0.0097600000 0.0585540000 0.0000920000 0.0003130000 0.0331240000 9070788 96830484 1768333312 3.7935917377 4.0633053780 3.6757152081 535 21.3600000000 0.0126083754 0.0071607516 0.0126243643 0.0092921429 0.1088590000 0.0084670000 0.0515770000 0.0003230000 0.0003370000 0.0386030000 9072462 96830484 1769992192 3.7938156128 4.0623135567 3.6743354797 536 21.4000000000 0.0127210421 0.0071711253 0.0127210421 0.0092914089 0.1068570000 0.0113930000 0.0581940000 0.0000270000 0.0002950000 0.0309660000 9074136 96830484 1768587264 3.7939641476 4.0626087189 3.6727721691 537 21.4400000000 0.0127034439 0.0071814276 0.0127210421 0.0092894896 0.1623620000 0.0085630000 0.0856520000 0.0003010000 0.0003370000 0.0616160000 9075810 96830484 1770229760 3.7940776348 4.0616278648 3.6715385914 538 21.4800000000 0.0127089992 0.0071917019 0.0127210421 0.0093004913 0.0938750000 0.0103420000 0.0431220000 0.0000280000 0.0002980000 0.0325240000 9077484 96830484 1769218048 3.7944669724 4.0614542961 3.6703841686 539 21.5200000000 0.0126763629 0.0072018775 0.0127210421 0.0093171987 0.1088140000 0.0088180000 0.0495890000 0.0003700000 0.0002830000 0.0437890000 9079158 96830484 1767944192 3.7950766087 4.0604691505 3.6690835953 540 21.5600000000 0.0128594767 0.0072123545 0.0128594767 0.0093245957 0.1073090000 0.0086680000 0.0452180000 0.0000280000 0.0003030000 0.0419780000 9080832 96830484 1767329792 3.7945353985 4.0602879524 3.6678485870 541 21.6000000000 0.0127990181 0.0072226811 0.0128594767 0.0093291009 0.1147720000 0.0079440000 0.0446450000 0.0003780000 0.0002790000 0.0555740000 9082506 96830484 1766174720 3.7945151329 4.0600171089 3.6664969921 542 21.6400000000 0.0127946585 0.0072329615 0.0128594767 0.0093298810 0.1404480000 0.0081570000 0.0808460000 0.0000280000 0.0003690000 0.0336710000 9084180 96830484 1765031936 3.7949624062 4.0586957932 3.6653335094 543 21.6800000000 0.0128599051 0.0072433242 0.0128599051 0.0093320773 0.1491280000 0.0096480000 0.0850390000 0.0003620000 0.0002830000 0.0401280000 9085854 96830484 1764028416 3.7939515114 4.0577797890 3.6641466618 544 21.7200000000 0.0127940737 0.0072535278 0.0128599051 0.0093292101 0.1080730000 0.0083450000 0.0509210000 0.0000270000 0.0002810000 0.0342870000 9087528 96830484 1765646336 3.7939045429 4.0566802025 3.6629590988 545 21.7600000000 0.0128490860 0.0072637948 0.0128599051 0.0093242439 0.1483160000 0.0083610000 0.0578270000 0.0002870000 0.0003400000 0.0644440000 9089202 96830484 1767297024 3.7935087681 4.0553607941 3.6619369984 546 21.8000000000 0.0128396153 0.0072740070 0.0128599051 0.0093304374 0.1089620000 0.0083650000 0.0509920000 0.0000260000 0.0002900000 0.0347310000 9090876 96830484 1769074688 3.7933073044 4.0544552803 3.6609790325 547 21.8400000000 0.0127850287 0.0072840820 0.0128599051 0.0093537347 0.0926130000 0.0083050000 0.0422730000 0.0003970000 0.0002730000 0.0353190000 9092550 96830484 1770725376 3.7934086323 4.0529389381 3.6599597931 548 21.8800000000 0.0127806822 0.0072941122 0.0128599051 0.0093672450 0.1062930000 0.0104180000 0.0508370000 0.0000320000 0.0003140000 0.0353710000 9094224 96830484 1769455616 3.7930622101 4.0519285202 3.6587290764 549 21.9200000000 0.0127415275 0.0073040347 0.0128599051 0.0093774732 0.1320890000 0.0082750000 0.0510060000 0.0002900000 0.0003390000 0.0660620000 9095898 96830484 1771155456 3.7924509048 4.0484089851 3.6576778889 550 21.9600000000 0.0127576170 0.0073139503 0.0128599051 0.0093863700 0.1258210000 0.0111670000 0.0722300000 0.0000250000 0.0002830000 0.0358700000 9097572 96830484 1769979904 3.7916193008 4.0476365089 3.6565685272 551 22.0000000000 0.0128140301 0.0073239323 0.0128599051 0.0093838854 0.1092770000 0.0105300000 0.0506070000 0.0002850000 0.0004790000 0.0413020000 9099246 96830484 1768599552 3.7910814285 4.0479092598 3.6554312706 552 22.0400000000 0.0126039227 0.0073334975 0.0128599051 0.0093803456 0.1060130000 0.0084830000 0.0447700000 0.0000240000 0.0003820000 0.0365170000 9100920 96830484 1770262528 3.7903831005 4.0467967987 3.6544432640 553 22.0800000000 0.0126833804 0.0073431718 0.0128599051 0.0093804671 0.1350440000 0.0101110000 0.0511800000 0.0002900000 0.0003370000 0.0670600000 9102594 96830484 1769472000 3.7894029617 4.0449013710 3.6535305977 554 22.1200000000 0.0127342166 0.0073529029 0.0128599051 0.0093884967 0.1051160000 0.0106110000 0.0516230000 0.0000240000 0.0003820000 0.0363420000 9104268 96830484 1768206336 3.7886841297 4.0447478294 3.6526856422 555 22.1600000000 0.0126610231 0.0073624671 0.0128599051 0.0093916406 0.1089770000 0.0083740000 0.0522360000 0.0004760000 0.0002740000 0.0414610000 9105942 96830484 1769865216 3.7883546352 4.0460410118 3.6515522003 556 22.2000000000 0.0127045540 0.0073720751 0.0128599051 0.0093855009 0.1074190000 0.0104790000 0.0513460000 0.0000270000 0.0003150000 0.0367850000 9107616 96830484 1768349696 3.7884981632 4.0458230972 3.6506369114 557 22.2400000000 0.0127641046 0.0073817556 0.0128599051 0.0093782443 0.1477030000 0.0084210000 0.0518090000 0.0003540000 0.0002860000 0.0727550000 9109290 96830484 1770090496 3.7882645130 4.0442404747 3.6499032974 558 22.2800000000 0.0127589935 0.0073913923 0.0128599051 0.0093766252 0.1094580000 0.0104600000 0.0527520000 0.0000260000 0.0003190000 0.0370040000 9110964 96830484 1769091072 3.7884917259 4.0437922478 3.6493408680 559 22.3200000000 0.0127762314 0.0074010252 0.0128599051 0.0093800769 0.1273320000 0.0084180000 0.0616390000 0.0000610000 0.0000520000 0.0446080000 9112638 96830484 1770758144 3.7881941795 4.0434799194 3.6483449936 560 22.3600000000 0.0127369380 0.0074105537 0.0128599051 0.0093775053 0.1072570000 0.0102790000 0.0376230000 0.0000250000 0.0003540000 0.0398380000 9114312 96830484 1769598976 3.7878501415 4.0435934067 3.6475560665 561 22.4000000000 0.0127796270 0.0074201242 0.0128599051 0.0093750502 0.1819600000 0.0102050000 0.0962310000 0.0002850000 0.0002650000 0.0686490000 9115986 96830484 1768058880 3.7879762650 4.0429906845 3.6468741894 562 22.4400000000 0.0127561409 0.0074296189 0.0128599051 0.0093717420 0.0986830000 0.0082190000 0.0458170000 0.0000280000 0.0007190000 0.0377410000 9117660 96830484 1769844736 3.7875211239 4.0423445702 3.6461315155 563 22.4800000000 0.0127660641 0.0074390975 0.0128599051 0.0093689783 0.1248100000 0.0097790000 0.0454880000 0.0002990000 0.0003480000 0.0499630000 9119334 96830484 1768677376 3.7874636650 4.0418863297 3.6455645561 564 22.5200000000 0.0128191765 0.0074486366 0.0128599051 0.0093691287 0.1290440000 0.0078070000 0.0659050000 0.0000240000 0.0002860000 0.0380180000 9121008 96830484 1770471424 3.7873182297 4.0418429375 3.6449687481 565 22.5600000000 0.0127956038 0.0074581003 0.0128599051 0.0093717504 0.1440130000 0.0102280000 0.0585390000 0.0003180000 0.0003500000 0.0683770000 9122682 96830484 1769598976 3.7866003513 4.0409650803 3.6441290379 566 22.6000000000 0.0128201293 0.0074675738 0.0128599051 0.0093713193 0.1136560000 0.0106900000 0.0490500000 0.0001020000 0.0003000000 0.0379200000 9124356 96830484 1768353792 3.7868075371 4.0407233238 3.6437196732 567 22.6400000000 0.0128429784 0.0074770543 0.0128599051 0.0093695673 0.1311360000 0.0084550000 0.0704560000 0.0000600000 0.0000530000 0.0445260000 9126030 96830484 1769992192 3.7863941193 4.0403714180 3.6428546906 568 22.6800000000 0.0128694875 0.0074865480 0.0128694875 0.0093689568 0.1113440000 0.0100330000 0.0597120000 0.0000260000 0.0002900000 0.0350030000 9127704 96830484 1768841216 3.7861425877 4.0397505760 3.6424999237 569 22.7200000000 0.0129823815 0.0074962067 0.0129823815 0.0093755489 0.1633170000 0.0082480000 0.0653690000 0.0002860000 0.0002630000 0.0721190000 9129378 96830484 1770598400 3.7858223915 4.0395631790 3.6418759823 570 22.7600000000 0.0129694594 0.0075058089 0.0129823815 0.0093783068 0.1288910000 0.0101940000 0.0634630000 0.0000050000 0.0000590000 0.0385220000 9131052 96830484 1769709568 3.7853472233 4.0391917229 3.6412608624 571 22.8000000000 0.0129746562 0.0075153866 0.0129823815 0.0093835545 0.1119540000 0.0102840000 0.0521920000 0.0003510000 0.0002640000 0.0426190000 9132726 96830484 1768333312 3.7851903439 4.0381741524 3.6405568123 572 22.8400000000 0.0129785435 0.0075249376 0.0129823815 0.0093938212 0.1246780000 0.0084190000 0.0597640000 0.0000260000 0.0002970000 0.0384410000 9134400 96830484 1769971712 3.7850837708 4.0384807587 3.6398031712 573 22.8800000000 0.0129982168 0.0075344896 0.0129982168 0.0093931471 0.1656520000 0.0102020000 0.0521960000 0.0002830000 0.0002620000 0.0712450000 9136074 96830484 1768857600 3.7847247124 4.0380187035 3.6389603615 574 22.9200000000 0.0130330082 0.0075440689 0.0130330082 0.0093950213 0.1098940000 0.0085690000 0.0526870000 0.0000250000 0.0002790000 0.0392180000 9137748 96830484 1770610688 3.7850272655 4.0372042656 3.6379561424 575 22.9600000000 0.0130568370 0.0075536563 0.0130568370 0.0093994231 0.1266860000 0.0103150000 0.0530960000 0.0002960000 0.0002660000 0.0465950000 9139422 96830484 1769598976 3.7850408554 4.0365676880 3.6371140480 576 23.0000000000 0.0130442688 0.0075631886 0.0130568370 0.0094066840 0.1103170000 0.0085930000 0.0527800000 0.0000260000 0.0002820000 0.0396300000 9141096 96830484 1771266048 3.7846772671 4.0356841087 3.6360619068 577 23.0400000000 0.0131656546 0.0075728982 0.0131656546 0.0094144527 0.1428390000 0.0104750000 0.0529900000 0.0002870000 0.0002590000 0.0722510000 9142770 96830484 1770090496 3.7850613594 4.0347547531 3.6352684498 578 23.0800000000 0.0132586248 0.0075827351 0.0132586248 0.0094230415 0.1121370000 0.0104130000 0.0444050000 0.0000280000 0.0003920000 0.0403930000 9144444 96830484 1768726528 3.7851562500 4.0337629318 3.6345062256 579 23.1200000000 0.0132562378 0.0075925339 0.0132586248 0.0094287591 0.1121800000 0.0087020000 0.0526330000 0.0003520000 0.0002660000 0.0436280000 9146118 96830484 1770373120 3.7851402760 4.0328688622 3.6336567402 580 23.1600000000 0.0132845771 0.0076023478 0.0132845771 0.0094351532 0.1267400000 0.0105030000 0.0659920000 0.0000280000 0.0002840000 0.0402750000 9147792 96830484 1769598976 3.7849762440 4.0322427750 3.6329176426 581 23.2000000000 0.0131658195 0.0076119235 0.0132845771 0.0094376166 0.1493820000 0.0098990000 0.0599010000 0.0002820000 0.0002610000 0.0727260000 9149466 96830484 1768206336 3.7848019600 4.0311560631 3.6323547363 582 23.2400000000 0.0131287863 0.0076214026 0.0132845771 0.0094390650 0.1081470000 0.0079440000 0.0522510000 0.0000260000 0.0003080000 0.0405750000 9151140 96830484 1769865216 3.7854862213 4.0306701660 3.6317803860 583 23.2800000000 0.0131756002 0.0076309296 0.0132845771 0.0094461119 0.1264190000 0.0099750000 0.0537120000 0.0002910000 0.0003490000 0.0475490000 9152814 96830484 1768714240 3.7862939835 4.0308117867 3.6311640739 584 23.3200000000 0.0132674752 0.0076405812 0.0132845771 0.0094467001 0.1274720000 0.0084860000 0.0566850000 0.0000050000 0.0000840000 0.0413080000 9154488 96830484 1770471424 3.7858436108 4.0294914246 3.6306045055 585 23.3600000000 0.0132294903 0.0076501349 0.0132845771 0.0094572064 0.1498820000 0.0101190000 0.0521720000 0.0002860000 0.0002650000 0.0734990000 9156162 96830484 1769598976 3.7864861488 4.0290026665 3.6304028034 586 23.4000000000 0.0132824108 0.0076597463 0.0132845771 0.0094732057 0.1105410000 0.0101860000 0.0519390000 0.0000240000 0.0002930000 0.0409990000 9157836 96830484 1768333312 3.7866649628 4.0292820930 3.6298873425 587 23.4400000000 0.0131811490 0.0076691524 0.0132845771 0.0094776171 0.1089910000 0.0085980000 0.0454700000 0.0003160000 0.0002720000 0.0477780000 9159510 96830484 1769992192 3.7866270542 4.0287003517 3.6293351650 588 23.4800000000 0.0132384235 0.0076786239 0.0132845771 0.0094831405 0.1092440000 0.0101090000 0.0523530000 0.0000280000 0.0003880000 0.0399060000 9161184 96830484 1768439808 3.7872426510 4.0281624794 3.6294832230 589 23.5200000000 0.0132490406 0.0076880814 0.0132845771 0.0094899718 0.1465110000 0.0083460000 0.0467640000 0.0003190000 0.0005010000 0.0791520000 9162858 96830484 1770344448 3.7872278690 4.0280122757 3.6290569305 590 23.5600000000 0.0132799931 0.0076975592 0.0132845771 0.0094942680 0.1090400000 0.0100060000 0.0460790000 0.0001030000 0.0003080000 0.0424580000 9164532 96830484 1769582592 3.7873628139 4.0277676582 3.6288456917 591 23.6000000000 0.0132432766 0.0077069428 0.0132845771 0.0094937084 0.1288960000 0.0103270000 0.0603450000 0.0003180000 0.0002660000 0.0490870000 9166206 96830484 1768185856 3.7871835232 4.0262579918 3.6287739277 592 23.6400000000 0.0132736797 0.0077163461 0.0132845771 0.0095042169 0.1097140000 0.0086710000 0.0536220000 0.0000330000 0.0003120000 0.0404080000 9167880 96830484 1769820160 3.7870917320 4.0256524086 3.6285073757 593 23.6800000000 0.0133006647 0.0077257631 0.0133006647 0.0095093739 0.1458130000 0.0100700000 0.0523970000 0.0003070000 0.0003560000 0.0761930000 9169554 96830484 1768693760 3.7870008945 4.0253300667 3.6282882690 594 23.7200000000 0.0131740803 0.0077349354 0.0133006647 0.0095078439 0.1101290000 0.0077930000 0.0497300000 0.0000280000 0.0003840000 0.0427990000 9171228 96830484 1770360832 3.7869331837 4.0248050690 3.6277346611 595 23.7600000000 0.0132397646 0.0077441872 0.0133006647 0.0095090038 0.1270700000 0.0103410000 0.0523020000 0.0003100000 0.0002750000 0.0497280000 9172902 96830484 1769074688 3.7869184017 4.0239815712 3.6276259422 596 23.8000000000 0.0133017879 0.0077535120 0.0133017879 0.0095132172 0.1093520000 0.0083980000 0.0457150000 0.0000290000 0.0003090000 0.0438330000 9174576 96830484 1770774528 3.7864029408 4.0235710144 3.6274793148 597 23.8400000000 0.0133027835 0.0077628073 0.0133027835 0.0095129677 0.1477160000 0.0104890000 0.0429130000 0.0008710000 0.0002920000 0.0795300000 9176250 96830484 1769598976 3.7865684032 4.0233950615 3.6276805401 598 23.8800000000 0.0132959774 0.0077720601 0.0133027835 0.0095100780 0.1095700000 0.0099330000 0.0461260000 0.0000280000 0.0003840000 0.0434710000 9177924 96830484 1768185856 3.7864708900 4.0228338242 3.6275103092 599 23.9200000000 0.0132346312 0.0077811796 0.0133027835 0.0095042163 0.1098150000 0.0087900000 0.0434130000 0.0011000000 0.0002950000 0.0495570000 9179598 96830484 1769947136 3.7864863873 4.0215492249 3.6275427341 600 23.9600000000 0.0133156981 0.0077904038 0.0133156981 0.0094990613 0.1245800000 0.0097540000 0.0499840000 0.0000270000 0.0003100000 0.0447060000 9181272 96830484 1768841216 3.7867171764 4.0206384659 3.6275532246 601 24.0000000000 0.0133946473 0.0077997286 0.0133946473 0.0094962759 0.1466060000 0.0083790000 0.0523790000 0.0003040000 0.0003470000 0.0785380000 9182946 96830484 1770487808 3.7865240574 4.0199823380 3.6273920536 602 24.0400000000 0.0133917751 0.0078090177 0.0133946473 0.0094962297 0.1126130000 0.0102960000 0.0445700000 0.0000280000 0.0003160000 0.0443350000 9184620 96830484 1768964096 3.7867422104 4.0188980103 3.6275525093 603 24.0800000000 0.0134437997 0.0078183623 0.0134437997 0.0095040733 0.1062940000 0.0084210000 0.0439600000 0.0003160000 0.0002750000 0.0450890000 9186294 96830484 1770864640 3.7868456841 4.0182280540 3.6277453899 604 24.1200000000 0.0133287888 0.0078274855 0.0134437997 0.0095070923 0.1085340000 0.0144310000 0.0450060000 0.0000100000 0.0001200000 0.0422880000 9187968 96830484 1769615360 3.7870433331 4.0175771713 3.6281526089 605 24.1600000000 0.0133903697 0.0078366804 0.0134437997 0.0095046890 0.1499260000 0.0098050000 0.0526850000 0.0003150000 0.0002740000 0.0802170000 9189642 96830484 1768587264 3.7866680622 4.0175461769 3.6279685497 606 24.2000000000 0.0134134274 0.0078458829 0.0134437997 0.0094983181 0.1080700000 0.0080720000 0.0508880000 0.0000290000 0.0003090000 0.0420170000 9191316 96830484 1770246144 3.7868890762 4.0169353485 3.6280348301 607 24.2400000000 0.0134389261 0.0078550972 0.0134437997 0.0094917012 0.1235830000 0.0102500000 0.0429600000 0.0003780000 0.0010590000 0.0515220000 9192990 96830484 1768931328 3.7873232365 4.0165381432 3.6282212734 608 24.2800000000 0.0134944711 0.0078643725 0.0134944711 0.0094848663 0.1101410000 0.0081660000 0.0462480000 0.0000280000 0.0003150000 0.0453830000 9194664 96830484 1770627072 3.7878170013 4.0161442757 3.6283390522 609 24.3200000000 0.0135542806 0.0078737155 0.0135542806 0.0094780418 0.1445750000 0.0100840000 0.0459100000 0.0003090000 0.0002740000 0.0810600000 9196338 96830484 1769472000 3.7870233059 4.0148949623 3.6281785965 610 24.3600000000 0.0136319231 0.0078831552 0.0136319231 0.0094777699 0.1125850000 0.0080440000 0.0444170000 0.0000280000 0.0003870000 0.0488140000 9198012 96830484 1771266048 3.7872681618 4.0148730278 3.6279618740 611 24.4000000000 0.0135824317 0.0078924830 0.0136319231 0.0094723882 0.1454350000 0.0095000000 0.0657860000 0.0003160000 0.0003530000 0.0462750000 9199686 96830484 1769979904 3.7874932289 4.0138301849 3.6281690598 612 24.4400000000 0.0136121130 0.0079018288 0.0136319231 0.0094696385 0.1250220000 0.0100920000 0.0453920000 0.0000280000 0.0003130000 0.0466970000 9201360 96830484 1768710144 3.7876093388 4.0136690140 3.6277987957 613 24.4800000000 0.0136655848 0.0079112313 0.0136655848 0.0094647191 0.1508060000 0.0083480000 0.0458770000 0.0003900000 0.0002810000 0.0833740000 9203034 96830484 1770373120 3.7886035442 4.0146965981 3.6280775070 614 24.5200000000 0.0138194561 0.0079208538 0.0138194561 0.0094570913 0.1098470000 0.0100930000 0.0445650000 0.0000300000 0.0003900000 0.0466500000 9204708 96830484 1769312256 3.7886621952 4.0147194862 3.6280148029 615 24.5600000000 0.0138582364 0.0079305081 0.0138582364 0.0094498734 0.1271300000 0.0085120000 0.0511890000 0.0003120000 0.0002690000 0.0547670000 9206382 96830484 1771008000 3.7880649567 4.0132369995 3.6277470589 616 24.6000000000 0.0138337640 0.0079400913 0.0138582364 0.0094477948 0.1283730000 0.0101020000 0.0535850000 0.0000280000 0.0037470000 0.0472740000 9208056 96830484 1770090496 3.7878310680 4.0114374161 3.6274199486 617 24.6400000000 0.0138816070 0.0079497210 0.0138816070 0.0094495593 0.1481640000 0.0100580000 0.0458770000 0.0003830000 0.0002720000 0.0846130000 9209730 96830484 1768710144 3.7882628441 4.0111517906 3.6275155544 618 24.6800000000 0.0139939319 0.0079595013 0.0139939319 0.0094499118 0.1120050000 0.0083390000 0.0519900000 0.0000280000 0.0002980000 0.0444360000 9211404 96830484 1770373120 3.7888205051 4.0105776787 3.6273632050 619 24.7200000000 0.0140034696 0.0079692654 0.0140034696 0.0094625274 0.1080640000 0.0099790000 0.0351700000 0.0003120000 0.0002740000 0.0553850000 9213078 96830484 1769709568 3.7893662453 4.0104761124 3.6271033287 620 24.7600000000 0.0141337719 0.0079792081 0.0141337719 0.0094676688 0.1253160000 0.0095050000 0.0468690000 0.0000310000 0.0003160000 0.0546190000 9214752 96830484 1768185856 3.7895407677 4.0112609863 3.6261184216 621 24.8000000000 0.0141495802 0.0079891443 0.0141495802 0.0094607748 0.1920150000 0.0075970000 0.0845020000 0.0003160000 0.0002750000 0.0923720000 9216426 96830484 1769947136 3.7902224064 4.0111885071 3.6258625984 622 24.8400000000 0.0143640023 0.0079993933 0.0143640023 0.0094531797 0.1235800000 0.0103490000 0.0458300000 0.0000270000 0.0003820000 0.0490640000 9218100 96830484 1768849408 3.7913820744 4.0107831955 3.6258916855 623 24.8800000000 0.0143246930 0.0080095462 0.0143640023 0.0094458038 0.1299080000 0.0083140000 0.0523380000 0.0003010000 0.0019300000 0.0545360000 9219774 96830484 1770737664 3.7922694683 4.0103330612 3.6259906292 624 24.9200000000 0.0143833524 0.0080197607 0.0143833524 0.0094385978 0.1268900000 0.0101200000 0.0457400000 0.0000260000 0.0003900000 0.0493980000 9221448 96830484 1769598976 3.7927656174 4.0095438957 3.6255671978 625 24.9600000000 0.0144694811 0.0080300802 0.0144694811 0.0094330644 0.1566430000 0.0098760000 0.0526870000 0.0003790000 0.0002800000 0.0862380000 9223122 96830484 1768185856 3.7941772938 4.0098261833 3.6258404255 626 25.0000000000 0.0145654483 0.0080405201 0.0145654483 0.0094257183 0.1206960000 0.0083960000 0.0458810000 0.0000250000 0.0003130000 0.0489660000 9224796 96830484 1769971712 3.7954170704 4.0102767944 3.6258499622 627 25.0400000000 0.0145622259 0.0080509216 0.0145654483 0.0094182358 0.1302370000 0.0098400000 0.0532990000 0.0005190000 0.0005300000 0.0561030000 9226470 96830484 1768857600 3.7965342999 4.0094146729 3.6257851124 628 25.0800000000 0.0146960663 0.0080615030 0.0146960663 0.0094139225 0.1266360000 0.0081920000 0.0510390000 0.0000270000 0.0003150000 0.0501310000 9228144 96830484 1770582016 3.7979617119 4.0099449158 3.6257224083 629 25.1200000000 0.0147065800 0.0080720675 0.0147065800 0.0094075551 0.1479750000 0.0101100000 0.0427040000 0.0011060000 0.0003660000 0.0866690000 9229818 96830484 1769455616 3.7996990681 4.0113916397 3.6253187656 630 25.1600000000 0.0148026664 0.0080827510 0.0148026664 0.0094043528 0.1282700000 0.0082480000 0.0495170000 0.0000190000 0.0007890000 0.0494270000 9231492 96830484 1771155456 3.8008015156 4.0110945702 3.6255211830 631 25.2000000000 0.0148594966 0.0080934907 0.0148594966 0.0093981841 0.1276600000 0.0100010000 0.0430630000 0.0010640000 0.0002940000 0.0497960000 9233166 96830484 1769979904 3.8025953770 4.0104928017 3.6259093285 632 25.2400000000 0.0148859788 0.0081042383 0.0148859788 0.0093907485 0.1301230000 0.0101190000 0.0526930000 0.0000290000 0.0003090000 0.0499000000 9234840 96830484 1768714240 3.8041441441 4.0105366707 3.6258454323 633 25.2800000000 0.0149456132 0.0081150462 0.0149456132 0.0093833417 0.1491340000 0.0082750000 0.0454470000 0.0003170000 0.0002760000 0.0878030000 9236514 96830484 1770225664 3.8057348728 4.0117015839 3.6259138584 634 25.3200000000 0.0150372991 0.0081259645 0.0150372991 0.0093777982 0.1107230000 0.0101210000 0.0446590000 0.0000330000 0.0003110000 0.0484610000 9238188 96830484 1769472000 3.8076715469 4.0116448402 3.6265368462 635 25.3600000000 0.0151006924 0.0081369484 0.0151006924 0.0093725033 0.1259320000 0.0098910000 0.0450310000 0.0003180000 0.0002880000 0.0567090000 9239862 96830484 1767931904 3.8097319603 4.0113611221 3.6272895336 636 25.4000000000 0.0151853953 0.0081480308 0.0151853953 0.0093660834 0.1098480000 0.0080670000 0.0438200000 0.0000290000 0.0003180000 0.0499840000 9241536 96830484 1769717760 3.8115079403 4.0115995407 3.6270582676 637 25.4400000000 0.0152571769 0.0081591912 0.0152571769 0.0093603311 0.1667600000 0.0099930000 0.0520420000 0.0003120000 0.0003540000 0.0899270000 9243210 96830484 1768349696 3.8137269020 4.0119132996 3.6274588108 638 25.4800000000 0.0152962748 0.0081703778 0.0152962748 0.0093565171 0.1101280000 0.0080830000 0.0430430000 0.0000280000 0.0011030000 0.0498870000 9244884 96830484 1770090496 3.8154320717 4.0108938217 3.6279935837 639 25.5200000000 0.0152437994 0.0081814473 0.0152962748 0.0093492262 0.1265470000 0.0103950000 0.0423810000 0.0003100000 0.0003450000 0.0570280000 9246558 96830484 1768947712 3.8177187443 4.0109362602 3.6280755997 640 25.5600000000 0.0153792473 0.0081926939 0.0153792473 0.0093422530 0.1278500000 0.0082660000 0.0511300000 0.0000290000 0.0003030000 0.0502890000 9248232 96830484 1770627072 3.8201587200 4.0114645958 3.6286590099 641 25.6000000000 0.0153986523 0.0082039357 0.0153986523 0.0093355152 0.1497150000 0.0101940000 0.0429530000 0.0011050000 0.0002920000 0.0877870000 9249906 96830484 1769472000 3.8229892254 4.0119509697 3.6293385029 642 25.6400000000 0.0155090950 0.0082153144 0.0155090950 0.0093302243 0.1302370000 0.0098820000 0.0644000000 0.0000280000 0.0003770000 0.0485260000 9251580 96830484 1768169472 3.8250496387 4.0115184784 3.6294755936 643 25.6800000000 0.0154685499 0.0082265947 0.0155090950 0.0093229624 0.1273020000 0.0080570000 0.0519650000 0.0003160000 0.0005170000 0.0561720000 9253254 96830484 1769865216 3.8275725842 4.0121531487 3.6296970844 644 25.7200000000 0.0155692482 0.0082379963 0.0155692482 0.0093165083 0.1267660000 0.0098150000 0.0506980000 0.0000120000 0.0001150000 0.0497050000 9254928 96830484 1768460288 3.8301291466 4.0120186806 3.6305148602 645 25.7600000000 0.0155492080 0.0082493316 0.0155692482 0.0093093749 0.1521850000 0.0080500000 0.0499150000 0.0003130000 0.0003490000 0.0863840000 9256602 96830484 1770090496 3.8326971531 4.0113263130 3.6312360764 646 25.8000000000 0.0155922156 0.0082606982 0.0155922156 0.0093040929 0.1243520000 0.0100920000 0.0445440000 0.0000290000 0.0003070000 0.0525820000 9258276 96830484 1768964096 3.8351738453 4.0118451118 3.6315813065 647 25.8400000000 0.0155564873 0.0082719746 0.0155922156 0.0092968984 0.1280070000 0.0084160000 0.0578660000 0.0003940000 0.0002770000 0.0537550000 9259950 96830484 1770627072 3.8379106522 4.0122537613 3.6325378418 648 25.8800000000 0.0155841717 0.0082832588 0.0155922156 0.0092907061 0.1254420000 0.0104080000 0.0504300000 0.0000300000 0.0003120000 0.0492910000 9261624 96830484 1769598976 3.8400866985 4.0116558075 3.6333546638 649 25.9200000000 0.0156230060 0.0082945682 0.0156230060 0.0092835451 0.1508390000 0.0099200000 0.0460890000 0.0003140000 0.0002730000 0.0869910000 9263298 96830484 1768296448 3.8426356316 4.0112948418 3.6336970329 650 25.9600000000 0.0156586841 0.0083058976 0.0156586841 0.0092769285 0.1241860000 0.0089860000 0.0444280000 0.0000280000 0.0003120000 0.0499200000 9264972 96830484 1769836544 3.8453757763 4.0118021965 3.6344673634 651 26.0000000000 0.0156171890 0.0083171284 0.0156586841 0.0092698036 0.1290900000 0.0098990000 0.0431120000 0.0009690000 0.0003670000 0.0569420000 9266646 96830484 1768706048 3.8478419781 4.0122995377 3.6349158287 652 26.0400000000 0.0156953093 0.0083284447 0.0156953093 0.0092628705 0.1286230000 0.0084870000 0.0533830000 0.0000290000 0.0003100000 0.0498410000 9268320 96830484 1770344448 3.8501989841 4.0124907494 3.6348514557 653 26.0800000000 0.0157146528 0.0083397558 0.0157146528 0.0092558953 0.1562670000 0.0105380000 0.0510980000 0.0003090000 0.0002700000 0.0865740000 9269994 96830484 1768439808 3.8524222374 4.0123081207 3.6350014210 654 26.1200000000 0.0157967471 0.0083511580 0.0157967471 0.0092493650 0.1207950000 0.0088590000 0.0507210000 0.0000290000 0.0003160000 0.0483930000 9271668 96830484 1769979904 3.8581550121 4.0131797791 3.6370100975 655 26.1600000000 0.0158526283 0.0083626106 0.0158526283 0.0092423871 0.1190840000 0.0104880000 0.0509640000 0.0003150000 0.0002730000 0.0497630000 9273342 96830484 1768075264 3.8604068756 4.0125937462 3.6374020576 656 26.2000000000 0.0157878082 0.0083739295 0.0158526283 0.0092357041 0.1167610000 0.0085770000 0.0436040000 0.0000270000 0.0012580000 0.0489670000 9275016 96830484 1769582592 3.8633277416 4.0129871368 3.6384387016 657 26.2400000000 0.0158560984 0.0083853179 0.0158560984 0.0092287006 0.1416760000 0.0108770000 0.0373070000 0.0003100000 0.0003420000 0.0855490000 9276690 96830484 1767710720 3.8659782410 4.0129694939 3.6395773888 658 26.2800000000 0.0158879906 0.0083967201 0.0158879906 0.0092217982 0.1121060000 0.0098780000 0.0388100000 0.0000290000 0.0003050000 0.0517670000 9278364 96830484 1769361408 3.8685710430 4.0127844810 3.6402194500 659 26.3200000000 0.0158987269 0.0084081040 0.0158987269 0.0092157945 0.1494870000 0.0098010000 0.0684210000 0.0003070000 0.0003510000 0.0632290000 9280038 96830484 1767329792 3.8711261749 4.0132808685 3.6403443813 660 26.3600000000 0.0159112830 0.0084194725 0.0159112830 0.0092088049 0.1259330000 0.0080120000 0.0413820000 0.0000120000 0.0001410000 0.0599920000 9281712 96830484 1769103360 3.8737070560 4.0128192902 3.6411972046 661 26.4000000000 0.0158961974 0.0084307837 0.0159112830 0.0092023126 0.1731340000 0.0090850000 0.0703470000 0.0003040000 0.0003420000 0.0856970000 9283386 96830484 1767948288 3.8766677380 4.0125179291 3.6425132751 662 26.4400000000 0.0159660988 0.0084421664 0.0159660988 0.0091967932 0.1248600000 0.0083460000 0.0571350000 0.0000280000 0.0003110000 0.0483600000 9285060 96830484 1769742336 3.8793540001 4.0127396584 3.6431508064 663 26.4800000000 0.0158852767 0.0084533928 0.0159660988 0.0091898743 0.1282880000 0.0099520000 0.0503930000 0.0003870000 0.0002860000 0.0556680000 9286734 96830484 1768587264 3.8818254471 4.0120491982 3.6436936855 664 26.5200000000 0.0160229094 0.0084647927 0.0160229094 0.0091832948 0.1098680000 0.0081740000 0.0461300000 0.0000250000 0.0003110000 0.0477240000 9288408 96830484 1770377216 3.8842046261 4.0110406876 3.6444833279 665 26.5600000000 0.0160697382 0.0084762287 0.0160697382 0.0091785879 0.1551920000 0.0100370000 0.0514820000 0.0003810000 0.0002790000 0.0854080000 9290082 96830484 1769218048 3.8862450123 4.0094618797 3.6446228027 666 26.6000000000 0.0161172803 0.0084877017 0.0161172803 0.0091786853 0.1202950000 0.0084270000 0.0530440000 0.0000280000 0.0003100000 0.0481540000 9291756 96830484 1770901504 3.8887686729 4.0089259148 3.6450684071 667 26.6400000000 0.0160367936 0.0084990197 0.0161172803 0.0091769488 0.1267030000 0.0100020000 0.0427570000 0.0003130000 0.0003460000 0.0556210000 9293430 96830484 1769852928 3.8911597729 4.0081281662 3.6452198029 668 26.6800000000 0.0161489621 0.0085104717 0.0161489621 0.0091728127 0.1115070000 0.0098510000 0.0454860000 0.0000260000 0.0003090000 0.0483480000 9295104 96830484 1768333312 3.8935835361 4.0075778961 3.6457345486 669 26.7200000000 0.0161808468 0.0085219372 0.0161808468 0.0091679031 0.1454760000 0.0083030000 0.0427920000 0.0003120000 0.0002690000 0.0861460000 9296778 96830484 1770090496 3.8958418369 4.0064778328 3.6457083225 670 26.7600000000 0.0162545703 0.0085334784 0.0162545703 0.0091672983 0.1112200000 0.0099030000 0.0442100000 0.0000260000 0.0003050000 0.0491140000 9298452 96830484 1768947712 3.8982033730 4.0061640739 3.6455330849 671 26.8000000000 0.0163121615 0.0085450711 0.0163121615 0.0091639854 0.1281410000 0.0077500000 0.0455520000 0.0003080000 0.0003520000 0.0665530000 9300126 96830484 1770614784 3.9007799625 4.0065364838 3.6451153755 672 26.8400000000 0.0162966866 0.0085566062 0.0163121615 0.0091574348 0.1284900000 0.0096080000 0.0510600000 0.0000340000 0.0003190000 0.0600050000 9301800 96830484 1769472000 3.9030070305 4.0051612854 3.6449055672 673 26.8800000000 0.0163138490 0.0085681326 0.0163138490 0.0091593057 0.1895610000 0.0078830000 0.0595980000 0.0003890000 0.0002870000 0.1138640000 9303474 96830484 1771249664 3.9055092335 4.0043983459 3.6447508335 674 26.9200000000 0.0164068714 0.0085797628 0.0164068714 0.0091667939 0.1248390000 0.0103960000 0.0526540000 0.0000290000 0.0003870000 0.0486660000 9305148 96830484 1770106880 3.9082586765 4.0052242279 3.6443850994 675 26.9600000000 0.0164940376 0.0085914876 0.0164940376 0.0091624081 0.1104350000 0.0102790000 0.0356760000 0.0003100000 0.0002700000 0.0564080000 9306822 96830484 1768185856 3.9108426571 4.0052671432 3.6433975697 676 27.0000000000 0.0164420456 0.0086031009 0.0164940376 0.0091560735 0.1091730000 0.0079350000 0.0415120000 0.0000270000 0.0003810000 0.0516050000 9308496 96830484 1769852928 3.9133169651 4.0038628578 3.6433415413 677 27.0400000000 0.0165079180 0.0086147771 0.0165079180 0.0091529608 0.1856190000 0.0092790000 0.0564190000 0.0003860000 0.0007600000 0.1057900000 9310170 96830484 1768947712 3.9160192013 4.0038638115 3.6422526836 678 27.0800000000 0.0165724382 0.0086265141 0.0165724382 0.0091483870 0.1090880000 0.0085900000 0.0387970000 0.0000280000 0.0003740000 0.0513970000 9311844 96830484 1770631168 3.9187717438 4.0035958290 3.6416709423 679 27.1200000000 0.0165614523 0.0086382003 0.0165724382 0.0091454702 0.1467500000 0.0095450000 0.0628930000 0.0003130000 0.0002730000 0.0563370000 9313518 96830484 1769598976 3.9210157394 4.0031008720 3.6404471397 680 27.1600000000 0.0166694373 0.0086500109 0.0166694373 0.0091443257 0.1110660000 0.0082920000 0.0460510000 0.0000290000 0.0003130000 0.0487040000 9315192 96830484 1771249664 3.9237797260 4.0036401749 3.6391103268 681 27.2000000000 0.0166126136 0.0086617034 0.0166694373 0.0091379843 0.1485540000 0.0099670000 0.0428700000 0.0016460000 0.0003030000 0.0861330000 9316866 96830484 1770106880 3.9264163971 4.0034456253 3.6379923820 682 27.2400000000 0.0165985506 0.0086733410 0.0166694373 0.0091319073 0.1220380000 0.0114050000 0.0442970000 0.0000280000 0.0003140000 0.0499260000 9318540 96830484 1768456192 3.9289705753 4.0031142235 3.6363778114 683 27.2800000000 0.0167428963 0.0086851559 0.0167428963 0.0091269005 0.1275920000 0.0085920000 0.0435000000 0.0003900000 0.0002830000 0.0566520000 9320214 96830484 1770115072 3.9318268299 4.0032773018 3.6351182461 684 27.3200000000 0.0168117769 0.0086970369 0.0168117769 0.0091203922 0.1277670000 0.0101900000 0.0466200000 0.0000290000 0.0003850000 0.0495700000 9321888 96830484 1769091072 3.9346518517 4.0031914711 3.6334083080 685 27.3600000000 0.0168699604 0.0087089682 0.0168699604 0.0091137959 0.1555340000 0.0082640000 0.0527380000 0.0003060000 0.0003430000 0.0858320000 9323562 96830484 1770758144 3.9372775555 4.0013809204 3.6322922707 686 27.4000000000 0.0167850088 0.0087207409 0.0168699604 0.0091127345 0.1228150000 0.0103790000 0.0460770000 0.0000310000 0.0003200000 0.0512110000 9325236 96830484 1769607168 3.9400098324 4.0004038811 3.6307873726 687 27.4400000000 0.0168456770 0.0087325675 0.0168699604 0.0091146537 0.1285310000 0.0098750000 0.0456380000 0.0003250000 0.0002790000 0.0599770000 9326910 96830484 1768230912 3.9430503845 4.0005998611 3.6288030148 688 27.4800000000 0.0168080162 0.0087443051 0.0168699604 0.0091151340 0.1085180000 0.0081020000 0.0352620000 0.0000280000 0.0003140000 0.0537350000 9328584 96830484 1770000384 3.9461073875 4.0005245209 3.6268765926 689 27.5200000000 0.0168193504 0.0087560251 0.0168699604 0.0091157376 0.2038920000 0.0092980000 0.0744490000 0.0003860000 0.0002810000 0.0919640000 9330258 96830484 1768849408 3.9488327503 4.0001606941 3.6247298717 690 27.5600000000 0.0169035438 0.0087678331 0.0169035438 0.0091199425 0.1141540000 0.0082380000 0.0517140000 0.0000290000 0.0003870000 0.0461220000 9331932 96830484 1770606592 3.9521193504 4.0010581017 3.6224677563 691 27.6000000000 0.0169005543 0.0087796026 0.0169035438 0.0091134622 0.1252520000 0.0099630000 0.0382510000 0.0003850000 0.0002880000 0.0589180000 9333606 96830484 1769734144 3.9553980827 4.0020151138 3.6200199127 692 27.6400000000 0.0169693660 0.0087914375 0.0169693660 0.0091101812 0.1484410000 0.0097090000 0.0656180000 0.0000310000 0.0003880000 0.0541360000 9335280 96830484 1768341504 3.9584708214 4.0021991730 3.6175096035 693 27.6800000000 0.0169664882 0.0088032341 0.0169693660 0.0091066103 0.1890240000 0.0076340000 0.0741660000 0.0003110000 0.0005080000 0.0929520000 9336954 96830484 1770000384 3.9614660740 4.0014047623 3.6157059669 694 27.7200000000 0.0170068089 0.0088150548 0.0170068089 0.0091000394 0.1108450000 0.0102340000 0.0442530000 0.0000300000 0.0035860000 0.0450720000 9338628 96830484 1768972288 3.9644618034 4.0011525154 3.6134109497 695 27.7600000000 0.0170162413 0.0088268551 0.0170162413 0.0090936937 0.1255110000 0.0083260000 0.0435500000 0.0003130000 0.0003420000 0.0550600000 9340302 96830484 1770508288 3.9674837589 4.0006380081 3.6115355492 696 27.8000000000 0.0169331133 0.0088385020 0.0170162413 0.0090891611 0.1105790000 0.0100770000 0.0447370000 0.0000270000 0.0003150000 0.0475980000 9341976 96830484 1769480192 3.9703330994 4.0001678467 3.6099054813 697 27.8400000000 0.0168607384 0.0088500117 0.0170162413 0.0090864303 0.1468290000 0.0097360000 0.0428700000 0.0012680000 0.0002860000 0.0847030000 9343650 96830484 1767940096 3.9760963917 4.0010375977 3.6050980091 698 27.8800000000 0.0169790294 0.0088616578 0.0170162413 0.0090799155 0.1257960000 0.0082310000 0.0502770000 0.0000290000 0.0003820000 0.0481150000 9345324 96830484 1769746432 3.9786002636 4.0000534058 3.6034724712 699 27.9200000000 0.0169447139 0.0088732216 0.0170162413 0.0090972557 0.1136760000 0.0096220000 0.0405780000 0.0003570000 0.0002660000 0.0549380000 9346998 96830484 1768611840 3.9831647873 3.9997634888 3.5994195938 700 27.9600000000 0.0168761946 0.0088846544 0.0170162413 0.0090918294 0.1063410000 0.0074500000 0.0394860000 0.0000260000 0.0002990000 0.0513500000 9348672 96830484 1770352640 3.9852516651 3.9990372658 3.5973670483 701 28.0000000000 0.0169183854 0.0088961148 0.0170162413 0.0090885456 0.1701910000 0.0097380000 0.0525240000 0.0002980000 0.0003460000 0.0995290000 9350346 96830484 1769226240 3.9874207973 3.9980566502 3.5961167812 702 28.0400000000 0.0168850627 0.0089074950 0.0170162413 0.0090936201 0.1060710000 0.0083270000 0.0420810000 0.0000290000 0.0003480000 0.0472400000 9352020 96830484 1770889216 3.9893589020 3.9971077442 3.5945618153 703 28.0800000000 0.0167083386 0.0089185915 0.0170162413 0.0091120165 0.1272630000 0.0099690000 0.0513110000 0.0002880000 0.0002660000 0.0540990000 9353694 96830484 1769861120 3.9915125370 3.9971928596 3.5925762653 704 28.1200000000 0.0166762825 0.0089296110 0.0170162413 0.0091181395 0.1325940000 0.0101930000 0.0487240000 0.0000260000 0.0003150000 0.0595120000 9355368 96830484 1768431616 3.9939067364 3.9972572327 3.5910613537 705 28.1600000000 0.0167608466 0.0089407191 0.0170162413 0.0091183860 0.1367060000 0.0080010000 0.0362550000 0.0003220000 0.0002800000 0.0840310000 9357042 96830484 1770127360 3.9958481789 3.9964625835 3.5897021294 706 28.2000000000 0.0166847166 0.0089516880 0.0170162413 0.0091240269 0.1095320000 0.0117220000 0.0482050000 0.0000250000 0.0003020000 0.0413120000 9358716 96830484 1768972288 3.9979803562 3.9959409237 3.5883655548 707 28.2400000000 0.0167244691 0.0089626820 0.0170162413 0.0091288030 0.1343830000 0.0087310000 0.0517790000 0.0004700000 0.0002930000 0.0544430000 9360390 96830484 1770651648 4.0003714561 3.9967954159 3.5867393017 708 28.2800000000 0.0167110376 0.0089736260 0.0170162413 0.0091225125 0.1132810000 0.0102710000 0.0418200000 0.0000270000 0.0002940000 0.0474250000 9362064 96830484 1769734144 4.0028953552 3.9969997406 3.5851905346 709 28.3200000000 0.0167460144 0.0089845885 0.0170162413 0.0091161883 0.1482170000 0.0100280000 0.0453830000 0.0003240000 0.0003450000 0.0841630000 9363738 96830484 1768194048 4.0050568581 3.9959976673 3.5843954086 710 28.3600000000 0.0167724621 0.0089955573 0.0170162413 0.0091139166 0.1066000000 0.0080740000 0.0426120000 0.0000240000 0.0003160000 0.0477120000 9365412 96830484 1769979904 4.0074763298 3.9956243038 3.5837357044 711 28.4000000000 0.0168199129 0.0090065620 0.0170162413 0.0091119908 0.1647450000 0.0093560000 0.0562310000 0.0003730000 0.0002840000 0.0827010000 9367086 96830484 1768812544 4.0100579262 3.9963159561 3.5823976994 712 28.4400000000 0.0167754199 0.0090174733 0.0170162413 0.0091055946 0.1486400000 0.0079040000 0.0753610000 0.0000310000 0.0003060000 0.0532710000 9368760 96830484 1770508288 4.0124444962 3.9954104424 3.5820987225 713 28.4800000000 0.0167252105 0.0090282836 0.0170162413 0.0091001615 0.2042030000 0.0097270000 0.0703770000 0.0006190000 0.0005360000 0.0939710000 9370434 96830484 1769353216 4.0147671700 3.9945318699 3.5817511082 714 28.5200000000 0.0166654624 0.0090389800 0.0170162413 0.0090984242 0.1107820000 0.0083280000 0.0352260000 0.0000070000 0.0000700000 0.0506050000 9372108 96830484 1771016192 4.0173759460 3.9949250221 3.5809488297 715 28.5600000000 0.0166818406 0.0090496693 0.0170162413 0.0090929737 0.1513460000 0.0096220000 0.0729780000 0.0005330000 0.0002760000 0.0599590000 9373782 96830484 1770242048 4.0204038620 3.9959414005 3.5803654194 716 28.6000000000 0.0166853033 0.0090603336 0.0170162413 0.0090880503 0.1266700000 0.0099570000 0.0417400000 0.0000290000 0.0002960000 0.0626460000 9375456 96830484 1768972288 4.0232939720 3.9963738918 3.5801630020 717 28.6400000000 0.0166884847 0.0090709725 0.0170162413 0.0090848364 0.1725450000 0.0077030000 0.0681060000 0.0003090000 0.0003600000 0.0880060000 9377130 96830484 1770479616 4.0261306763 3.9960784912 3.5800216198 718 28.6800000000 0.0166977253 0.0090815948 0.0170162413 0.0090788412 0.1173940000 0.0114960000 0.0379160000 0.0000250000 0.0002970000 0.0488230000 9378804 96830484 1769734144 4.0288782120 3.9959471226 3.5800971985 719 28.7200000000 0.0166331343 0.0090920976 0.0170162413 0.0090725468 0.1469750000 0.0092860000 0.0613550000 0.0003050000 0.0002750000 0.0535530000 9380478 96830484 1768341504 4.0317687988 3.9955112934 3.5805158615 720 28.7600000000 0.0165700223 0.0091024836 0.0170162413 0.0090689876 0.1095080000 0.0083920000 0.0340190000 0.0000180000 0.0002430000 0.0492900000 9382152 96830484 1770106880 4.0349831581 3.9951758385 3.5812346935 721 28.8000000000 0.0165382363 0.0091127967 0.0170162413 0.0090705206 0.1700000000 0.0092810000 0.0638480000 0.0003860000 0.0002920000 0.0880770000 9383826 96830484 1768955904 4.0382933617 3.9964082241 3.5812280178 722 28.8400000000 0.0165660400 0.0091231198 0.0170162413 0.0090643263 0.1083480000 0.0083810000 0.0428670000 0.0000260000 0.0003690000 0.0462180000 9385500 96830484 1770745856 4.0418677330 3.9967958927 3.5819270611 723 28.8800000000 0.0165374838 0.0091333748 0.0170162413 0.0090583862 0.1101290000 0.0102040000 0.0377130000 0.0002980000 0.0002750000 0.0533480000 9387174 96830484 1769480192 4.0452604294 3.9969365597 3.5826306343 724 28.9200000000 0.0165510327 0.0091436202 0.0170162413 0.0090522176 0.1455120000 0.0092740000 0.0655540000 0.0000350000 0.0037970000 0.0512320000 9388848 96830484 1768431616 4.0487022400 3.9971213341 3.5835354328 725 28.9600000000 0.0164644122 0.0091537178 0.0170162413 0.0090460736 0.1951230000 0.0075020000 0.0573150000 0.0003220000 0.0003560000 0.1210320000 9390522 96830484 1770102784 4.0523838997 3.9970238209 3.5847051144 726 29.0000000000 0.0164286364 0.0091637383 0.0170162413 0.0090410777 0.1199620000 0.0102250000 0.0422000000 0.0000270000 0.0003150000 0.0518830000 9392196 96830484 1768820736 4.0555982590 3.9968907833 3.5854864120 727 29.0400000000 0.0164366607 0.0091737424 0.0170162413 0.0090416225 0.1415430000 0.0077240000 0.0730450000 0.0003140000 0.0002740000 0.0518220000 9393870 96830484 1770393600 4.0595922470 3.9978687763 3.5866718292 728 29.0800000000 0.0163847543 0.0091836476 0.0170162413 0.0090359504 0.1162510000 0.0095560000 0.0398730000 0.0001010000 0.0003150000 0.0554140000 9395544 96830484 1769345024 4.0634417534 3.9985475540 3.5877623558 729 29.1200000000 0.0163501073 0.0091934781 0.0170162413 0.0090298296 0.1577460000 0.0077360000 0.0643000000 0.0003860000 0.0002890000 0.0767440000 9397218 96830484 1771028480 4.0669364929 3.9978840351 3.5892348289 730 29.1600000000 0.0162864532 0.0092031945 0.0170162413 0.0090329318 0.1150700000 0.0117220000 0.0340500000 0.0000100000 0.0001200000 0.0481100000 9398892 96830484 1769979904 4.0702481270 3.9977228642 3.5904130936 731 29.2000000000 0.0163761806 0.0092130071 0.0170162413 0.0090374371 0.1318910000 0.0102130000 0.0539660000 0.0003170000 0.0007040000 0.0581940000 9400566 96830484 1768423424 4.0741915703 3.9983663559 3.5919427872 732 29.2400000000 0.0163779948 0.0092227953 0.0170162413 0.0090352530 0.1262990000 0.0077580000 0.0438220000 0.0000290000 0.0003130000 0.0603220000 9402240 96830484 1770246144 4.0777463913 3.9986050129 3.5932168961 733 29.2800000000 0.0163428374 0.0092325089 0.0170162413 0.0090323086 0.1576810000 0.0094490000 0.0547670000 0.0017120000 0.0003740000 0.0830050000 9403914 96830484 1769091072 4.0811772346 3.9989430904 3.5940299034 734 29.3200000000 0.0162338093 0.0092420475 0.0170162413 0.0090275000 0.1161910000 0.0088800000 0.0444330000 0.0000270000 0.0003110000 0.0448150000 9405588 96830484 1770864640 4.0847048759 3.9990594387 3.5952699184 735 29.3600000000 0.0163012072 0.0092516518 0.0170162413 0.0090215199 0.1278140000 0.0100240000 0.0446510000 0.0003130000 0.0002750000 0.0519780000 9407262 96830484 1769598976 4.0878725052 3.9989838600 3.5963711739 736 29.4000000000 0.0162227787 0.0092611234 0.0170162413 0.0090154894 0.1094080000 0.0097280000 0.0359670000 0.0000300000 0.0003810000 0.0469490000 9408936 96830484 1768587264 4.0908770561 3.9985013008 3.5976696014 737 29.4400000000 0.0162643846 0.0092706258 0.0170162413 0.0090111823 0.1883670000 0.0074300000 0.0729640000 0.0003870000 0.0002860000 0.0922830000 9410610 96830484 1770246144 4.0937952995 3.9984960556 3.5986526012 738 29.4800000000 0.0161881708 0.0092799992 0.0170162413 0.0090066883 0.1087530000 0.0101390000 0.0378590000 0.0000290000 0.0003050000 0.0469450000 9412284 96830484 1768820736 4.0968518257 3.9987437725 3.5997445583 739 29.5200000000 0.0161620788 0.0092893118 0.0170162413 0.0090007268 0.1478080000 0.0078320000 0.0492980000 0.0003190000 0.0002820000 0.0764420000 9413958 96830484 1770500096 4.0994977951 3.9981493950 3.6009216309 740 29.5600000000 0.0160807222 0.0092984894 0.0170162413 0.0089981567 0.1315030000 0.0095540000 0.0659910000 0.0000270000 0.0003140000 0.0465900000 9415632 96830484 1769472000 4.1018695831 3.9972267151 3.6021125317 741 29.6000000000 0.0160612185 0.0093076159 0.0170162413 0.0090056705 0.1450590000 0.0076670000 0.0409560000 0.0003100000 0.0003520000 0.0806300000 9417306 96830484 1771139072 4.1041111946 3.9970591068 3.6030673981 742 29.6400000000 0.0160310809 0.0093166772 0.0170162413 0.0090079146 0.1088570000 0.0098510000 0.0429380000 0.0000270000 0.0003860000 0.0434970000 9418980 96830484 1769979904 4.1068472862 3.9973313808 3.6040565968 743 29.6800000000 0.0159634557 0.0093256231 0.0170162413 0.0090048240 0.1102670000 0.0100320000 0.0432490000 0.0010960000 0.0003690000 0.0469660000 9420654 96830484 1768693760 4.1091670990 3.9974143505 3.6048452854 744 29.7200000000 0.0159930885 0.0093345847 0.0170162413 0.0089997585 0.1052460000 0.0080800000 0.0356120000 0.0000260000 0.0003060000 0.0464270000 9422328 96830484 1770373120 4.1113500595 3.9972307682 3.6057133675 745 29.7600000000 0.0159869548 0.0093435141 0.0170162413 0.0089960060 0.1684290000 0.0094290000 0.0631720000 0.0003890000 0.0002750000 0.0798130000 9424002 96830484 1769455616 4.1136779785 3.9979939461 3.6063618660 746 29.8000000000 0.0160048474 0.0093524435 0.0170162413 0.0089919935 0.1094470000 0.0098820000 0.0437120000 0.0000280000 0.0011030000 0.0424110000 9425676 96830484 1768095744 4.1156649590 3.9986262321 3.6066346169 747 29.8400000000 0.0160173699 0.0093613657 0.0170162413 0.0089924047 0.1079080000 0.0080360000 0.0342190000 0.0003820000 0.0002710000 0.0522200000 9427350 96830484 1769738240 4.1173081398 3.9975740910 3.6076040268 748 29.8800000000 0.0158768892 0.0093700763 0.0170162413 0.0089999652 0.1487480000 0.0093990000 0.0758230000 0.0000270000 0.0003150000 0.0517430000 9429024 96830484 1768349696 4.1212105751 3.9976544380 3.6094355583 749 29.9200000000 0.0159775522 0.0093788980 0.0170162413 0.0089939872 0.1554560000 0.0074890000 0.0641530000 0.0007040000 0.0002970000 0.0743030000 9430698 96830484 1770090496 4.1233716011 3.9981839657 3.6101598740 750 29.9600000000 0.0159058217 0.0093876006 0.0170162413 0.0089884086 0.1189690000 0.0103690000 0.0447260000 0.0000300000 0.0003100000 0.0445400000 9432372 96830484 1769218048 4.1249485016 3.9981222153 3.6107115746 751 30.0000000000 0.0158918556 0.0093962614 0.0170162413 0.0089824413 0.1308170000 0.0075760000 0.0645860000 0.0003830000 0.0002730000 0.0491150000 9434046 96830484 1770991616 4.1269049644 3.9986772537 3.6112339497 752 30.0400000000 0.0159517676 0.0094049788 0.0170162413 0.0089789315 0.1044570000 0.0105120000 0.0370120000 0.0000260000 0.0004450000 0.0446150000 9435720 96830484 1769963520 4.1289372444 3.9992332458 3.6117544174 753 30.0800000000 0.0159195121 0.0094136303 0.0170162413 0.0089762102 0.1660860000 0.0095580000 0.0439430000 0.0003120000 0.0002790000 0.0914490000 9437394 96830484 1768439808 4.1307377815 3.9988005161 3.6124205589 754 30.1200000000 0.0159308035 0.0094222737 0.0170162413 0.0089703218 0.1110910000 0.0083210000 0.0521820000 0.0000270000 0.0002900000 0.0418960000 9439068 96830484 1770135552 4.1327328682 3.9991080761 3.6128590107 755 30.1600000000 0.0158466119 0.0094307828 0.0170162413 0.0089651511 0.1243780000 0.0101580000 0.0389270000 0.0002890000 0.0003390000 0.0514480000 9440742 96830484 1769074688 4.1345105171 3.9989721775 3.6133708954 756 30.2000000000 0.0158522800 0.0094392768 0.0170162413 0.0089593823 0.1127200000 0.0086620000 0.0557360000 0.0000280000 0.0002900000 0.0395930000 9442416 96830484 1770774528 4.1360583305 3.9980418682 3.6141483784 757 30.2400000000 0.0157974828 0.0094476761 0.0170162413 0.0089598984 0.1461680000 0.0100970000 0.0442200000 0.0003070000 0.0003460000 0.0775220000 9444090 96830484 1769598976 4.1379003525 3.9971635342 3.6150033474 758 30.2800000000 0.0158132315 0.0094560739 0.0170162413 0.0089775993 0.1072970000 0.0098130000 0.0360460000 0.0000270000 0.0002910000 0.0441810000 9445764 96830484 1768185856 4.1398100853 3.9973640442 3.6152038574 759 30.3200000000 0.0157555714 0.0094643736 0.0170162413 0.0089901113 0.1423480000 0.0077560000 0.0702630000 0.0002910000 0.0006860000 0.0403570000 9447438 96830484 1769836544 4.1422381401 3.9976670742 3.6156051159 760 30.3600000000 0.0157136787 0.0094725964 0.0170162413 0.0089937492 0.0967770000 0.0096960000 0.0357530000 0.0000190000 0.0001960000 0.0425350000 9449112 96830484 1768841216 4.1443195343 3.9973385334 3.6161894798 761 30.4000000000 0.0156816691 0.0094807555 0.0170162413 0.0090026723 0.1358950000 0.0080180000 0.0448350000 0.0002880000 0.0003420000 0.0738260000 9450786 96830484 1767038976 4.1463108063 3.9969692230 3.6164205074 762 30.4400000000 0.0156983491 0.0094889151 0.0170162413 0.0090184217 0.0973730000 0.0086430000 0.0340470000 0.0000090000 0.0000940000 0.0427840000 9452460 96830484 1765916672 4.1487598419 3.9970791340 3.6170880795 763 30.4800000000 0.0156249190 0.0094969570 0.0170162413 0.0090286979 0.1297800000 0.0076330000 0.0614080000 0.0000630000 0.0000550000 0.0513720000 9454134 96830484 1764888576 4.1513547897 3.9972367287 3.6173300743 764 30.5200000000 0.0156633090 0.0095050281 0.0170162413 0.0090367583 0.1060160000 0.0074050000 0.0425790000 0.0000260000 0.0003480000 0.0419340000 9455808 96830484 1765163008 4.1538248062 3.9969363213 3.6177732944 765 30.5600000000 0.0156747047 0.0095130931 0.0170162413 0.0090541142 0.1225600000 0.0076110000 0.0338680000 0.0003540000 0.0002760000 0.0717390000 9457482 96830484 1765015552 4.1561574936 3.9968025684 3.6181142330 766 30.6000000000 0.0155981742 0.0095210370 0.0170162413 0.0090691448 0.0943600000 0.0080730000 0.0353200000 0.0000070000 0.0000690000 0.0423240000 9459156 96830484 1765179392 4.1586279869 3.9974370003 3.6180472374 767 30.6400000000 0.0155474041 0.0095288941 0.0170162413 0.0090695348 0.1472320000 0.0073810000 0.0716650000 0.0000690000 0.0000560000 0.0570200000 9460830 96830484 1764995072 4.1612401009 3.9978630543 3.6179673672 768 30.6800000000 0.0156162055 0.0095368203 0.0170162413 0.0090676367 0.1274670000 0.0086060000 0.0543570000 0.0000250000 0.0002890000 0.0495460000 9462504 96830484 1764167680 4.1633276939 3.9976546764 3.6179931164 769 30.7200000000 0.0156625174 0.0095447861 0.0170162413 0.0090695831 0.1519280000 0.0077000000 0.0643350000 0.0003930000 0.0002700000 0.0704030000 9464178 96830484 1765756928 4.1656570435 3.9982166290 3.6178414822 770 30.7600000000 0.0155700948 0.0095526112 0.0170162413 0.0090655354 0.1048720000 0.0081330000 0.0456580000 0.0000260000 0.0003210000 0.0391210000 9465852 96830484 1767424000 4.1678609848 3.9986498356 3.6175889969 771 30.8000000000 0.0154451951 0.0095602539 0.0170162413 0.0090598084 0.1096080000 0.0082330000 0.0442360000 0.0003200000 0.0002750000 0.0448870000 9467526 96830484 1769074688 4.1696906090 3.9977979660 3.6174817085 772 30.8400000000 0.0154406661 0.0095678711 0.0170162413 0.0090633033 0.1078900000 0.0095200000 0.0470040000 0.0000250000 0.0003830000 0.0387160000 9469200 96830484 1768058880 4.1712837219 3.9977073669 3.6171808243 773 30.8800000000 0.0154529279 0.0095754843 0.0170162413 0.0090633273 0.1312580000 0.0083870000 0.0439880000 0.0003120000 0.0002770000 0.0696040000 9470874 96830484 1769582592 4.1734685898 3.9982826710 3.6169176102 774 30.9200000000 0.0154684782 0.0095830980 0.0170162413 0.0090578568 0.1058960000 0.0105210000 0.0470760000 0.0000260000 0.0003060000 0.0386750000 9472548 96830484 1768312832 4.1753444672 3.9983274937 3.6167318821 775 30.9600000000 0.0154850492 0.0095907134 0.0170162413 0.0090521658 0.1268250000 0.0083270000 0.0584590000 0.0002810000 0.0003450000 0.0455690000 9474222 96830484 1770119168 4.1769580841 3.9986827374 3.6163883209 776 31.0000000000 0.0156058362 0.0095984649 0.0170162413 0.0090494324 0.1082120000 0.0101220000 0.0441250000 0.0000260000 0.0003200000 0.0381740000 9475896 96830484 1768964096 4.1788139343 3.9988653660 3.6163458824 777 31.0400000000 0.0155627895 0.0096061410 0.0170162413 0.0090455158 0.1474610000 0.0084520000 0.0509280000 0.0003000000 0.0003520000 0.0687340000 9477570 96830484 1770643456 4.1803293228 3.9986727238 3.6162519455 778 31.0800000000 0.0156129906 0.0096138619 0.0170162413 0.0090401969 0.1088500000 0.0098080000 0.0452620000 0.0000280000 0.0003140000 0.0380380000 9479244 96830484 1769963520 4.1818542480 3.9998104572 3.6155374050 779 31.1200000000 0.0157155525 0.0096216946 0.0170162413 0.0090511519 0.1274450000 0.0100800000 0.0541850000 0.0002890000 0.0002810000 0.0454070000 9480918 96830484 1768583168 4.1830782890 4.0007014275 3.6148464680 780 31.1600000000 0.0158037078 0.0096296202 0.0170162413 0.0090858218 0.1083170000 0.0082360000 0.0445780000 0.0000260000 0.0003810000 0.0381880000 9482592 96830484 1770246144 4.1840710640 4.0010337830 3.6145288944 781 31.2000000000 0.0157636981 0.0096374744 0.0170162413 0.0091206628 0.1475130000 0.0098280000 0.0461680000 0.0007140000 0.0003070000 0.0716200000 9484266 96830484 1769345024 4.1848092079 4.0011119843 3.6139712334 782 31.2400000000 0.0157444943 0.0096452839 0.0170162413 0.0091527219 0.1096880000 0.0095610000 0.0471990000 0.0000260000 0.0003130000 0.0391140000 9485940 96830484 1768296448 4.1856698990 4.0014348030 3.6135900021 783 31.2800000000 0.0157686081 0.0096531042 0.0170162413 0.0091833015 0.1087040000 0.0081440000 0.0440850000 0.0003190000 0.0002730000 0.0452430000 9487614 96830484 1769979904 4.1864833832 4.0014581680 3.6132664680 784 31.3200000000 0.0156628899 0.0096607697 0.0170162413 0.0091988194 0.1091390000 0.0100380000 0.0521500000 0.0000250000 0.0002930000 0.0377570000 9489288 96830484 1768566784 4.1870865822 4.0011138916 3.6130452156 785 31.3600000000 0.0157115031 0.0096684777 0.0170162413 0.0091969067 0.1409490000 0.0078960000 0.0526280000 0.0003620000 0.0002790000 0.0707960000 9490962 96830484 1770233856 4.1878342628 4.0008902550 3.6130046844 786 31.4000000000 0.0157009307 0.0096761526 0.0170162413 0.0091912305 0.0958710000 0.0101680000 0.0370290000 0.0000270000 0.0002980000 0.0396100000 9492636 96830484 1768947712 4.1888651848 4.0016574860 3.6126427650 787 31.4400000000 0.0157363676 0.0096838530 0.0170162413 0.0091915921 0.1247720000 0.0080580000 0.0409050000 0.0003020000 0.0002740000 0.0616080000 9494310 96830484 1767469056 4.1897997856 4.0023303032 3.6124186516 788 31.4800000000 0.0156948436 0.0096914811 0.0170162413 0.0091945483 0.1284270000 0.0075620000 0.0691170000 0.0000260000 0.0003030000 0.0390060000 9495984 96830484 1766559744 4.1907167435 4.0027542114 3.6123602390 789 31.5200000000 0.0156699531 0.0096990584 0.0170162413 0.0091986576 0.1473410000 0.0082860000 0.0461780000 0.0003150000 0.0003480000 0.0734520000 9497658 96830484 1765249024 4.1917395592 4.0037989616 3.6120712757 790 31.5600000000 0.0156611819 0.0097066054 0.0170162413 0.0092285562 0.0919750000 0.0080510000 0.0364430000 0.0000260000 0.0003630000 0.0382660000 9499332 96830484 1766916096 4.1925868988 4.0045700073 3.6119852066 791 31.6000000000 0.0157651883 0.0097142648 0.0170162413 0.0092630573 0.1261700000 0.0076510000 0.0480320000 0.0003830000 0.0002850000 0.0609820000 9501006 96830484 1768677376 4.1936020851 4.0048913956 3.6119718552 792 31.6400000000 0.0157711990 0.0097219124 0.0170162413 0.0092745494 0.1260630000 0.0074130000 0.0501690000 0.0000270000 0.0003800000 0.0525150000 9502680 96830484 1770455040 4.1946988106 4.0053958893 3.6121320724 793 31.6800000000 0.0158109087 0.0097295909 0.0170162413 0.0092841003 0.1708020000 0.0094120000 0.0746870000 0.0000620000 0.0000530000 0.0775090000 9504354 96830484 1769582592 4.1954722404 4.0062122345 3.6120555401 794 31.7200000000 0.0157738328 0.0097372033 0.0170162413 0.0093061337 0.1065510000 0.0100350000 0.0445170000 0.0000260000 0.0003170000 0.0395580000 9506028 96830484 1767948288 4.1964092255 4.0071740150 3.6121206284 795 31.7600000000 0.0157218277 0.0097447311 0.0170162413 0.0093351714 0.1091200000 0.0084520000 0.0455270000 0.0003180000 0.0003410000 0.0454780000 9507702 96830484 1769738240 4.1971387863 4.0076613426 3.6124885082 796 31.8000000000 0.0157921650 0.0097523284 0.0170162413 0.0093680998 0.1090260000 0.0096880000 0.0443480000 0.0000300000 0.0003080000 0.0398550000 9509376 96830484 1768603648 4.1977925301 4.0085916519 3.6126878262 797 31.8400000000 0.0157175958 0.0097598130 0.0170162413 0.0094485577 0.1446780000 0.0080740000 0.0441880000 0.0003180000 0.0003570000 0.0741550000 9511050 96830484 1770233856 4.1985759735 4.0094375610 3.6130266190 798 31.8800000000 0.0158929769 0.0097674987 0.0170162413 0.0095482585 0.1083800000 0.0106230000 0.0377100000 0.0000290000 0.0003610000 0.0418330000 9512724 96830484 1768964096 4.1987571716 4.0098986626 3.6131384373 799 31.9200000000 0.0158767980 0.0097751449 0.0170162413 0.0096027900 0.1302510000 0.0079860000 0.0539650000 0.0020360000 0.0003630000 0.0552190000 9514398 96830484 1770631168 4.1993141174 4.0101718903 3.6134874821 800 31.9600000000 0.0157887712 0.0097826619 0.0170162413 0.0096223077 0.1274190000 0.0095650000 0.0543720000 0.0000300000 0.0003780000 0.0495740000 9516072 96830484 1769582592 4.1998515129 4.0103259087 3.6137211323 801 32.0000000000 0.0157809779 0.0097901504 0.0170162413 0.0096254511 0.1541110000 0.0093410000 0.0570430000 0.0003860000 0.0002780000 0.0781070000 9517746 96830484 1768095744 4.2006134987 4.0105443001 3.6142950058 802 32.0400000000 0.0158045404 0.0097976497 0.0170162413 0.0096277683 0.1022190000 0.0083550000 0.0426090000 0.0000290000 0.0003070000 0.0418430000 9519420 96830484 1769738240 4.2013797760 4.0107870102 3.6147060394 803 32.0800000000 0.0158133972 0.0098051413 0.0170162413 0.0096261975 0.1267030000 0.0091780000 0.0430120000 0.0006820000 0.0002790000 0.0592580000 9521094 96830484 1768603648 4.2022194862 4.0111689568 3.6151401997 804 32.1199999990 0.0159011092 0.0098127233 0.0170162413 0.0096250767 0.1285870000 0.0075710000 0.0585750000 0.0000340000 0.0003190000 0.0478030000 9522768 96830484 1770233856 4.2029347420 4.0114831924 3.6158061028 805 32.1600000000 0.0158348288 0.0098202042 0.0170162413 0.0096259381 0.1632570000 0.0099600000 0.0394840000 0.0003760000 0.0002830000 0.0800530000 9524442 96830484 1768964096 4.2035665512 4.0116539001 3.6162986755 806 32.2000000000 0.0158775430 0.0098277195 0.0170162413 0.0096251173 0.1147330000 0.0087630000 0.0505560000 0.0000290000 0.0007040000 0.0455170000 9526116 96830484 1770647552 4.2041587830 4.0116486549 3.6169464588 807 32.2400000000 0.0159031060 0.0098352479 0.0170162413 0.0096200988 0.1280680000 0.0094140000 0.0512070000 0.0003750000 0.0002840000 0.0577040000 9527790 96830484 1769598976 4.2050323486 4.0118417740 3.6175088882 808 32.2800000000 0.0159623940 0.0098428310 0.0170162413 0.0096149424 0.1277790000 0.0093300000 0.0570580000 0.0000290000 0.0003840000 0.0516960000 9529464 96830484 1768058880 4.2055764198 4.0121011734 3.6180739403 809 32.3200000000 0.0159199703 0.0098503429 0.0170162413 0.0096111162 0.1676670000 0.0076790000 0.0718960000 0.0003900000 0.0002850000 0.0782110000 9531138 96830484 1769865216 4.2063212395 4.0121970177 3.6187059879 810 32.3600000000 0.0159510169 0.0098578746 0.0170162413 0.0096077182 0.1078630000 0.0097000000 0.0467450000 0.0000280000 0.0003130000 0.0408130000 9532812 96830484 1768714240 4.2069206238 4.0120544434 3.6195306778 811 32.4000000000 0.0160124768 0.0098654635 0.0170162413 0.0096020217 0.1088970000 0.0081450000 0.0440550000 0.0009990000 0.0003030000 0.0463250000 9534486 96830484 1770471424 4.2076902390 4.0120134354 3.6203222275 812 32.4399999990 0.0160335526 0.0098730597 0.0170162413 0.0095963535 0.1076340000 0.0101570000 0.0466940000 0.0000270000 0.0003120000 0.0404790000 9536160 96830484 1769218048 4.2084608078 4.0118722916 3.6212174892 813 32.4800000000 0.0160892941 0.0098807057 0.0170162413 0.0095912691 0.1337970000 0.0082940000 0.0441200000 0.0003120000 0.0003570000 0.0713320000 9537834 96830484 1771008000 4.2093954086 4.0120720863 3.6219658852 814 32.5200000000 0.0161499884 0.0098884075 0.0170162413 0.0095883861 0.1204210000 0.0112120000 0.0511270000 0.0000270000 0.0003040000 0.0409330000 9539508 96830484 1769852928 4.2101373672 4.0119323730 3.6229696274 815 32.5600000000 0.0162314661 0.0098961904 0.0170162413 0.0095903640 0.1104100000 0.0098760000 0.0438970000 0.0003160000 0.0002810000 0.0467740000 9541182 96830484 1768730624 4.2109198570 4.0119223595 3.6239771843 816 32.6000000000 0.0162224323 0.0099039432 0.0170162413 0.0095929268 0.1064500000 0.0083180000 0.0426560000 0.0000270000 0.0014420000 0.0416220000 9542856 96830484 1770500096 4.2117004395 4.0121126175 3.6247899532 817 32.6400000000 0.0162423961 0.0099117014 0.0170162413 0.0095950818 0.1515860000 0.0102650000 0.0583470000 0.0003790000 0.0002830000 0.0731000000 9544530 96830484 1769361408 4.2123618126 4.0120143890 3.6257731915 818 32.6800000000 0.0163272023 0.0099195443 0.0170162413 0.0095986208 0.1048720000 0.0086010000 0.0390290000 0.0000280000 0.0003120000 0.0439490000 9546204 96830484 1771028480 4.2130413055 4.0120825768 3.6267156601 819 32.7200000000 0.0163077228 0.0099273443 0.0170162413 0.0096003210 0.1491010000 0.0094380000 0.0733500000 0.0003070000 0.0002730000 0.0545630000 9547878 96830484 1769963520 4.2135701180 4.0119853020 3.6278016567 820 32.7599999990 0.0163837913 0.0099352180 0.0170162413 0.0096034606 0.1472730000 0.0095370000 0.0683980000 0.0000290000 0.0003130000 0.0559210000 9549552 96830484 1768579072 4.2137441635 4.0118336678 3.6286864281 821 32.7999999990 0.0163073931 0.0099429794 0.0170162413 0.0096068109 0.1675720000 0.0078070000 0.0474600000 0.0003830000 0.0002770000 0.0939370000 9551226 96830484 1770246144 4.2139277458 4.0116734505 3.6294488907 822 32.8400000000 0.0163649675 0.0099507921 0.0170162413 0.0096101226 0.1097330000 0.0101760000 0.0439130000 0.0000320000 0.0003110000 0.0423320000 9552900 96830484 1769091072 4.2138462067 4.0111913681 3.6303687096 823 32.8800000000 0.0162951723 0.0099585009 0.0170162413 0.0096213148 0.1097750000 0.0085810000 0.0439440000 0.0003140000 0.0002740000 0.0471260000 9554574 96830484 1770774528 4.2141418457 4.0107889175 3.6316213608 824 32.9200000000 0.0162859056 0.0099661798 0.0170162413 0.0096301394 0.1075320000 0.0100980000 0.0446080000 0.0000300000 0.0005290000 0.0423010000 9556248 96830484 1769852928 4.2140331268 4.0102696419 3.6325428486 825 32.9600000000 0.0162067488 0.0099737441 0.0170162413 0.0096412951 0.1466230000 0.0099900000 0.0429470000 0.0001220000 0.0001060000 0.0786670000 9557922 96830484 1768329216 4.2140154839 4.0098562241 3.6335337162 826 33.0000000000 0.0161769856 0.0099812541 0.0170162413 0.0096522513 0.1082550000 0.0083400000 0.0438860000 0.0000300000 0.0003820000 0.0423840000 9559596 96830484 1770119168 4.2137866020 4.0097999573 3.6341335773 827 33.0400000000 0.0161770284 0.0099887460 0.0170162413 0.0096569140 0.1066460000 0.0099570000 0.0370650000 0.0003790000 0.0002770000 0.0496650000 9561270 96830484 1769091072 4.2135996819 4.0094041824 3.6350305080 828 33.0800000000 0.0161429271 0.0099961786 0.0170162413 0.0096648837 0.1249940000 0.0078290000 0.0426420000 0.0000250000 0.0003020000 0.0575980000 9562944 96830484 1770627072 4.2131142616 4.0088505745 3.6356358528 829 33.1199999990 0.0161784086 0.0100036360 0.0170162413 0.0096737227 0.2045650000 0.0095000000 0.0718310000 0.0003960000 0.0002820000 0.0908860000 9564618 96830484 1769598976 4.2126636505 4.0089836121 3.6362020969 830 33.1600000000 0.0162339974 0.0100111425 0.0170162413 0.0096737012 0.1126210000 0.0082470000 0.0470030000 0.0000270000 0.0003130000 0.0431960000 9566292 96830484 1771249664 4.2124204636 4.0089678764 3.6373996735 831 33.2000000000 0.0162607487 0.0100186631 0.0170162413 0.0096771822 0.1087000000 0.0098670000 0.0340510000 0.0003050000 0.0004870000 0.0524760000 9567966 96830484 1770487808 4.2109928131 4.0090751648 3.6385583878 832 33.2400000000 0.0163274538 0.0100262458 0.0170162413 0.0096718149 0.1241480000 0.0097830000 0.0627100000 0.0000270000 0.0003930000 0.0410720000 9569640 96830484 1768566784 4.2107429504 4.0089416504 3.6397233009 833 33.2800000000 0.0163459070 0.0100338324 0.0170162413 0.0096674335 0.1299970000 0.0082600000 0.0353920000 0.0003210000 0.0002770000 0.0762010000 9571314 96830484 1770217472 4.2098984718 4.0087194443 3.6404740810 834 33.3200000000 0.0163711403 0.0100414311 0.0170162413 0.0096633995 0.1097350000 0.0102470000 0.0412550000 0.0000290000 0.0002990000 0.0457530000 9572988 96830484 1769455616 4.2091865540 4.0089530945 3.6413702965 835 33.3600000000 0.0164463576 0.0100491016 0.0170162413 0.0096577393 0.1470610000 0.0078050000 0.0490880000 0.0003150000 0.0002690000 0.0752560000 9574662 96830484 1771122688 4.2086896896 4.0090885162 3.6424808502 836 33.4000000000 0.0164570305 0.0100567666 0.0170162413 0.0096521084 0.1242040000 0.0099320000 0.0657520000 0.0000290000 0.0003110000 0.0368540000 9576336 96830484 1769091072 4.2076859474 4.0086998940 3.6433951855 837 33.4399999990 0.0165279470 0.0100644980 0.0170162413 0.0096473265 0.1466870000 0.0099670000 0.0411050000 0.0002950000 0.0002690000 0.0773310000 9578010 96830484 1770504192 4.2066817284 4.0084714890 3.6441962719 838 33.4800000000 0.0164874606 0.0100721627 0.0170162413 0.0096424830 0.1081740000 0.0104130000 0.0352290000 0.0000260000 0.0002920000 0.0465110000 9579684 96830484 1768710144 4.2056865692 4.0084004402 3.6448957920 839 33.5200000000 0.0165407676 0.0100798726 0.0170162413 0.0096369620 0.1279290000 0.0077360000 0.0528460000 0.0003730000 0.0002830000 0.0512900000 9581358 96830484 1770123264 4.2045192719 4.0083041191 3.6453034878 840 33.5600000000 0.0165695362 0.0100875984 0.0170162413 0.0096316433 0.1093830000 0.0104810000 0.0443410000 0.0000250000 0.0003170000 0.0436850000 9583032 96830484 1768312832 4.2033605576 4.0075740814 3.6460967064 841 33.6000000000 0.0165515300 0.0100952844 0.0170162413 0.0096290604 0.1631140000 0.0083260000 0.0432860000 0.0010100000 0.0002740000 0.0811830000 9584706 96830484 1769836544 4.2020225525 4.0065765381 3.6473488808 842 33.6400000000 0.0166011062 0.0101030110 0.0170162413 0.0096346883 0.1102700000 0.0097310000 0.0366740000 0.0000260000 0.0002870000 0.0453260000 9586380 96830484 1768947712 4.2007918358 4.0061969757 3.6480376720 843 33.6800000000 0.0166537147 0.0101107817 0.0170162413 0.0096360520 0.1117030000 0.0085270000 0.0446490000 0.0003130000 0.0003470000 0.0482140000 9588054 96830484 1770598400 4.1996226311 4.0062189102 3.6487419605 844 33.7200000000 0.0167270806 0.0101186209 0.0170162413 0.0096333717 0.1090690000 0.0097870000 0.0468850000 0.0000290000 0.0005580000 0.0419430000 9589728 96830484 1769963520 4.1983232498 4.0057740211 3.6497266293 845 33.7599999990 0.0167555157 0.0101264752 0.0170162413 0.0096344246 0.1424730000 0.0102270000 0.0434040000 0.0009210000 0.0003660000 0.0780150000 9591402 96830484 1767821312 4.1969137192 4.0056414604 3.6498928070 846 33.7999999990 0.0167839658 0.0101343446 0.0170162413 0.0096343580 0.1093390000 0.0084860000 0.0370580000 0.0000270000 0.0002900000 0.0479770000 9593076 96830484 1769582592 4.1957306862 4.0059204102 3.6505315304 847 33.8400000000 0.0168581512 0.0101422830 0.0170162413 0.0096304527 0.1497980000 0.0091640000 0.0705130000 0.0005690000 0.0006940000 0.0579660000 9594750 96830484 1768693760 4.1946430206 4.0060939789 3.6515221596 848 33.8800000000 0.0169621799 0.0101503253 0.0170162413 0.0096249854 0.1474860000 0.0079730000 0.0710380000 0.0000250000 0.0003720000 0.0553790000 9596424 96830484 1770471424 4.1932868958 4.0062708855 3.6520252228 849 33.9200000000 0.0170072503 0.0101584018 0.0170162413 0.0096194945 0.1681960000 0.0098380000 0.0572550000 0.0003190000 0.0002790000 0.0907930000 9598098 96830484 1768345600 4.1921148300 4.0065245628 3.6525044441 850 33.9600000000 0.0169832800 0.0101664310 0.0170162413 0.0096146486 0.1090670000 0.0086780000 0.0433170000 0.0000280000 0.0003120000 0.0451440000 9599772 96830484 1770090496 4.1908922195 4.0064291954 3.6537425518 851 34.0000000000 0.0170027763 0.0101744644 0.0170162413 0.0096110429 0.1260160000 0.0106420000 0.0436600000 0.0003860000 0.0002820000 0.0519250000 9601446 96830484 1767964672 4.1895203590 4.0062689781 3.6538655758 852 34.0400000000 0.0169924237 0.0101824667 0.0170162413 0.0096076275 0.1080890000 0.0088210000 0.0338460000 0.0000260000 0.0002880000 0.0478860000 9603120 96830484 1769582592 4.1877737045 4.0060963631 3.6535758972 853 34.0800000000 0.0170020591 0.0101904615 0.0170162413 0.0096038288 0.1874100000 0.0099940000 0.0690850000 0.0002900000 0.0002710000 0.0884510000 9604794 96830484 1767694336 4.1863861084 4.0057168007 3.6539897919 854 34.1199999990 0.0170227624 0.0101984618 0.0170227624 0.0095994623 0.1086900000 0.0086350000 0.0360640000 0.0000270000 0.0002930000 0.0489330000 9606468 96830484 1769439232 4.1851181984 4.0051565170 3.6548984051 855 34.1600000000 0.0169940982 0.0102064100 0.0170227624 0.0095945328 0.1473900000 0.0078970000 0.0627310000 0.0003190000 0.0002780000 0.0589140000 9608142 96830484 1771008000 4.1838059425 4.0037832260 3.6562035084 856 34.2000000000 0.0171148833 0.0102144806 0.0171148833 0.0095925642 0.1505330000 0.0096480000 0.0793070000 0.0000270000 0.0003550000 0.0515020000 9609816 96830484 1769979904 4.1826901436 4.0030369759 3.6578786373 857 34.2400000000 0.0170827024 0.0102224949 0.0171148833 0.0095933963 0.1854040000 0.0100440000 0.0485200000 0.0003000000 0.0002790000 0.1090900000 9611490 96830484 1768202240 4.1816501617 4.0031042099 3.6588885784 858 34.2800000000 0.0171838552 0.0102306083 0.0171838552 0.0095890393 0.1097320000 0.0087410000 0.0434710000 0.0000270000 0.0003160000 0.0465990000 9613164 96830484 1769836544 4.1803989410 4.0025806427 3.6602668762 859 34.3200000000 0.0172293391 0.0102387559 0.0172293391 0.0095863351 0.1248700000 0.0105450000 0.0371950000 0.0003420000 0.0002660000 0.0560440000 9614838 96830484 1767837696 4.1790122986 4.0021352768 3.6619026661 860 34.3600000000 0.0172834639 0.0102469474 0.0172834639 0.0095825142 0.1296450000 0.0089270000 0.0455310000 0.0000170000 0.0002330000 0.0599540000 9616512 96830484 1769566208 4.1776309013 4.0023608208 3.6631672382 861 34.4000000000 0.0173016842 0.0102551410 0.0173016842 0.0095771183 0.1703340000 0.0101260000 0.0573480000 0.0003930000 0.0002750000 0.0923330000 9618186 96830484 1767452672 4.1761579514 4.0021624565 3.6645827293 862 34.4400000000 0.0174403228 0.0102634765 0.0174403228 0.0095716487 0.1212640000 0.0089900000 0.0510630000 0.0000260000 0.0003530000 0.0463670000 9619860 96830484 1769197568 4.1746988297 4.0021414757 3.6663315296 863 34.4800000000 0.0173874255 0.0102717314 0.0174403228 0.0095661491 0.1095390000 0.0085900000 0.0356700000 0.0002960000 0.0003380000 0.0545710000 9621534 96830484 1770901504 4.1732087135 4.0023646355 3.6679432392 864 34.5200000000 0.0173967760 0.0102799780 0.0174403228 0.0095611598 0.1540520000 0.0098240000 0.0794970000 0.0000260000 0.0002970000 0.0452490000 9623208 96830484 1770123264 4.1713228226 4.0026226044 3.6699352264 865 34.5600000000 0.0175508074 0.0102883835 0.0175508074 0.0095573791 0.1776140000 0.0103540000 0.0619630000 0.0003240000 0.0002770000 0.0875330000 9624882 96830484 1768091648 4.1694474220 4.0024070740 3.6720426083 866 34.6000000000 0.0175255351 0.0102967405 0.0175508074 0.0095519265 0.1288770000 0.0090090000 0.0438780000 0.0000240000 0.0003170000 0.0626520000 9626556 96830484 1769836544 4.1673412323 4.0020823479 3.6743774414 867 34.6400000000 0.0175156258 0.0103050668 0.0175508074 0.0095467803 0.1498100000 0.0104640000 0.0723100000 0.0003110000 0.0002780000 0.0563800000 9628230 96830484 1767694336 4.1651954651 4.0026326180 3.6760778427 868 34.6800000000 0.0175768398 0.0103134444 0.0175768398 0.0095429238 0.1260710000 0.0082570000 0.0444090000 0.0000260000 0.0002920000 0.0621430000 9629904 96830484 1769439232 4.1629223824 4.0031924248 3.6781792641 869 34.7200000000 0.0175633635 0.0103217873 0.0175768398 0.0095405526 0.2052140000 0.0095400000 0.0778480000 0.0002900000 0.0002630000 0.0949340000 9631578 96830484 1768722432 4.1606221199 4.0038986206 3.6802136898 870 34.7600000000 0.0175909866 0.0103301427 0.0175909866 0.0095433523 0.1097370000 0.0089840000 0.0366600000 0.0000240000 0.0003630000 0.0489670000 9633252 96830484 1770471424 4.1580190659 4.0043368340 3.6826531887 871 34.8000000000 0.0176068302 0.0103384971 0.0176068302 0.0095466015 0.1697900000 0.0107860000 0.0782050000 0.0003540000 0.0002720000 0.0702820000 9634926 96830484 1768218624 4.1552748680 4.0037522316 3.6851263046 872 34.8400000000 0.0176046193 0.0103468298 0.0176068302 0.0095411429 0.1456340000 0.0081300000 0.0511310000 0.0000300000 0.0003200000 0.0691190000 9636600 96830484 1770106880 4.1523780823 4.0032362938 3.6879904270 873 34.8800000000 0.0175728779 0.0103551070 0.0176068302 0.0095401104 0.1707250000 0.0097540000 0.0573520000 0.0003910000 0.0002820000 0.0929090000 9638274 96830484 1769312256 4.1496539116 4.0045247078 3.6902000904 874 34.9200000000 0.0177340191 0.0103635497 0.0177340191 0.0095353656 0.1081500000 0.0092460000 0.0437450000 0.0000300000 0.0003150000 0.0449680000 9639948 96830484 1771106304 4.1468834877 4.0059456825 3.6922419071 875 34.9600000000 0.0177464727 0.0103719874 0.0177464727 0.0095388753 0.1248300000 0.0104890000 0.0432260000 0.0003150000 0.0002780000 0.0538410000 9641622 96830484 1770344448 4.1438908577 4.0062880516 3.6945071220 876 35.0000000000 0.0178117510 0.0103804802 0.0178117510 0.0095421237 0.1104990000 0.0107990000 0.0437450000 0.0000280000 0.0003930000 0.0455510000 9643296 96830484 1768583168 4.1408987045 4.0066213608 3.6967830658 877 35.0400000000 0.0177716576 0.0103889080 0.0178117510 0.0095431102 0.1437790000 0.0088410000 0.0429060000 0.0012690000 0.0002770000 0.0802880000 9644970 96830484 1770225664 4.1378817558 4.0072093010 3.6991083622 878 35.0800000000 0.0178764500 0.0103974360 0.0178764500 0.0095479624 0.1117650000 0.0108820000 0.0425940000 0.0000110000 0.0001110000 0.0481470000 9646644 96830484 1769472000 4.1347599030 4.0070991516 3.7014656067 879 35.1200000000 0.0177369062 0.0104057858 0.0178764500 0.0095462962 0.1449190000 0.0096710000 0.0450000000 0.0002910000 0.0002700000 0.0717810000 9648318 96830484 1768075264 4.1316933632 4.0075287819 3.7034521103 880 35.1600000000 0.0178675149 0.0104142650 0.0178764500 0.0095526023 0.1480790000 0.0082300000 0.0696660000 0.0000280000 0.0002920000 0.0526840000 9649992 96830484 1769820160 4.1287655830 4.0086035728 3.7059495449 881 35.2000000000 0.0178575963 0.0104227138 0.0178764500 0.0095694539 0.1878370000 0.0095830000 0.0692390000 0.0002920000 0.0002670000 0.0909900000 9651666 96830484 1768693760 4.1256771088 4.0084571838 3.7079031467 882 35.2400000000 0.0178753119 0.0104311634 0.0178764500 0.0095705223 0.1092550000 0.0088790000 0.0377580000 0.0000240000 0.0003490000 0.0492380000 9653340 96830484 1770455040 4.1226739883 4.0084180832 3.7104039192 883 35.2800000000 0.0177819934 0.0104394882 0.0178764500 0.0095668537 0.1479560000 0.0101340000 0.0574100000 0.0003880000 0.0002790000 0.0650690000 9655014 96830484 1769598976 4.1195011139 4.0084624290 3.7127006054 884 35.3200000000 0.0178134013 0.0104478298 0.0178764500 0.0095624775 0.1474170000 0.0102080000 0.0665950000 0.0000280000 0.0002920000 0.0531410000 9656688 96830484 1768206336 4.1167325974 4.0094041824 3.7147328854 885 35.3600000000 0.0177829750 0.0104561181 0.0178764500 0.0095592260 0.1878730000 0.0081470000 0.0719210000 0.0003870000 0.0002850000 0.0893290000 9658362 96830484 1769865216 4.1137914658 4.0098366737 3.7167854309 886 35.4000000000 0.0178123880 0.0104644209 0.0178764500 0.0095548355 0.1103030000 0.0105670000 0.0361450000 0.0000290000 0.0043770000 0.0490870000 9660036 96830484 1768423424 4.1108040810 4.0097889900 3.7189471722 887 35.4400000000 0.0178150013 0.0104727079 0.0178764500 0.0095496124 0.1434360000 0.0082840000 0.0602380000 0.0018510000 0.0002980000 0.0470610000 9661710 96830484 1770119168 4.1078777313 4.0098428726 3.7208073139 888 35.4800000000 0.0179553274 0.0104811343 0.0179553274 0.0095443322 0.1122060000 0.0107890000 0.0437950000 0.0000290000 0.0003860000 0.0471140000 9663384 96830484 1769091072 4.1050872803 4.0100111961 3.7227628231 889 35.5200000000 0.0179655701 0.0104895532 0.0179655701 0.0095406966 0.1440200000 0.0090820000 0.0425680000 0.0010520000 0.0002740000 0.0807680000 9665058 96830484 1770774528 4.1024603844 4.0105481148 3.7243406773 890 35.5600000000 0.0179182123 0.0104979000 0.0179655701 0.0095359124 0.1106410000 0.0111540000 0.0356690000 0.0000260000 0.0003080000 0.0495310000 9666732 96830484 1769709568 4.0998358727 4.0111198425 3.7260286808 891 35.6000000000 0.0179018211 0.0105062097 0.0179655701 0.0095306490 0.1471140000 0.0105040000 0.0655360000 0.0003940000 0.0004880000 0.0530400000 9668406 96830484 1768075264 4.0972342491 4.0118865967 3.7278308868 892 35.6400000000 0.0179593042 0.0105145652 0.0179655701 0.0095253662 0.1098760000 0.0092240000 0.0436600000 0.0000270000 0.0003830000 0.0463840000 9670080 96830484 1769865216 4.0946917534 4.0123844147 3.7295670509 893 35.6800000000 0.0179270077 0.0105228658 0.0179655701 0.0095200928 0.1447090000 0.0109640000 0.0431360000 0.0003850000 0.0002760000 0.0796250000 9671754 96830484 1768804352 4.0921239853 4.0128297806 3.7310798168 894 35.7200000000 0.0180743616 0.0105313126 0.0180743616 0.0095149458 0.1269590000 0.0092960000 0.0450340000 0.0000270000 0.0003830000 0.0464250000 9673428 96830484 1770500096 4.0896420479 4.0134606361 3.7326650620 895 35.7600000000 0.0179989133 0.0105396563 0.0180743616 0.0095101759 0.1148350000 0.0112880000 0.0431240000 0.0003130000 0.0003430000 0.0494250000 9675102 96830484 1769455616 4.0871419907 4.0137414932 3.7339920998 896 35.8000000000 0.0181195103 0.0105481160 0.0181195103 0.0095051090 0.1211850000 0.0111660000 0.0507210000 0.0000250000 0.0002950000 0.0465330000 9676776 96830484 1767940096 4.0847172737 4.0139865875 3.7353813648 897 35.8400000000 0.0181098878 0.0105565460 0.0181195103 0.0094999341 0.1450650000 0.0096740000 0.0453540000 0.0003290000 0.0003530000 0.0786900000 9678450 96830484 1769746432 4.0823230743 4.0144667625 3.7365486622 898 35.8800000000 0.0182517674 0.0105651153 0.0182517674 0.0094949268 0.1275570000 0.0116890000 0.0455990000 0.0000300000 0.0003150000 0.0462430000 9680124 96830484 1768595456 4.0798768997 4.0152807236 3.7377152443 899 35.9200000000 0.0182120390 0.0105736214 0.0182517674 0.0094903134 0.1138510000 0.0097570000 0.0441900000 0.0003130000 0.0002750000 0.0489060000 9681798 96830484 1770242048 4.0772833824 4.0154237747 3.7384190559 900 35.9600000000 0.0182232615 0.0105821210 0.0182517674 0.0094850891 0.1265160000 0.0119960000 0.0602400000 0.0000280000 0.0002940000 0.0434570000 9683472 96830484 1768939520 4.0747380257 4.0150985718 3.7390744686 901 36.0000000000 0.0181259979 0.0105904937 0.0182517674 0.0094814986 0.1448280000 0.0102800000 0.0452020000 0.0003210000 0.0002710000 0.0785220000 9685146 96830484 1770655744 4.0723571777 4.0151782036 3.7391812801 902 36.0400000000 0.0182573516 0.0105989936 0.0182573516 0.0094763413 0.1272950000 0.0116770000 0.0464880000 0.0000270000 0.0003810000 0.0490470000 9686820 96830484 1769480192 4.0700020790 4.0156497955 3.7392706871 903 36.0800000000 0.0182719678 0.0106074908 0.0182719678 0.0094712007 0.1704180000 0.0101580000 0.0983730000 0.0003560000 0.0002690000 0.0509050000 9688494 96830484 1771274240 4.0674266815 4.0155634880 3.7397961617 904 36.1200000000 0.0183505844 0.0106160562 0.0183505844 0.0094660332 0.1078290000 0.0115580000 0.0370590000 0.0000280000 0.0002900000 0.0485680000 9690168 96830484 1770369024 4.0649919510 4.0157027245 3.7399170399 905 36.1600000000 0.0182669628 0.0106245102 0.0183505844 0.0094613101 0.1827000000 0.0113640000 0.0587340000 0.0003930000 0.0002740000 0.0817490000 9691842 96830484 1768972288 4.0625057220 4.0160531998 3.7406053543 906 36.2000000000 0.0183529742 0.0106330405 0.0183529742 0.0094577914 0.1132910000 0.0101360000 0.0455290000 0.0000270000 0.0003190000 0.0468630000 9693516 96830484 1770639360 4.0599045753 4.0161314011 3.7406275272 907 36.2400000000 0.0183846373 0.0106415869 0.0183846373 0.0094542958 0.1275680000 0.0117220000 0.0515830000 0.0006150000 0.0003690000 0.0524330000 9695190 96830484 1769607168 4.0572919846 4.0159149170 3.7401163578 908 36.2800000000 0.0183521174 0.0106500787 0.0183846373 0.0094491794 0.1078790000 0.0100870000 0.0379180000 0.0000250000 0.0003580000 0.0486530000 9696864 96830484 1771384832 4.0546274185 4.0157327652 3.7395374775 909 36.3200000000 0.0183256734 0.0106585227 0.0183846373 0.0094439918 0.2428420000 0.0111960000 0.1210490000 0.0006750000 0.0002820000 0.0794090000 9698538 96830484 1770496000 4.0519886017 4.0157308578 3.7394995689 910 36.3600000000 0.0183381289 0.0106669618 0.0183846373 0.0094388559 0.1311370000 0.0131850000 0.0537920000 0.0000280000 0.0003670000 0.0460570000 9700212 96830484 1768574976 4.0493755341 4.0159788132 3.7394447327 911 36.4000000000 0.0183987115 0.0106754489 0.0183987115 0.0094340759 0.1102580000 0.0104920000 0.0350580000 0.0003620000 0.0002750000 0.0536590000 9701886 96830484 1770258432 4.0467233658 4.0157332420 3.7391452789 912 36.4400000000 0.0183982756 0.0106839169 0.0183987115 0.0094289109 0.1294600000 0.0114310000 0.0533810000 0.0000280000 0.0003070000 0.0539250000 9703560 96830484 1769099264 4.0442252159 4.0159358978 3.7393026352 913 36.4800000000 0.0183904637 0.0106923578 0.0183987115 0.0094240525 0.1842050000 0.0094520000 0.0713840000 0.0003080000 0.0003510000 0.0922120000 9705234 96830484 1770860544 4.0417389870 4.0162220001 3.7396590710 914 36.5200000000 0.0183925647 0.0107007826 0.0183987115 0.0094205232 0.1097570000 0.0122630000 0.0393460000 0.0000290000 0.0003110000 0.0472910000 9706908 96830484 1770115072 4.0390906334 4.0160489082 3.7395176888 915 36.5600000000 0.0184327271 0.0107092328 0.0184327271 0.0094166740 0.1646830000 0.0112710000 0.0684040000 0.0003240000 0.0003430000 0.0651180000 9708582 96830484 1768337408 4.0366535187 4.0158848763 3.7390322685 916 36.6000000000 0.0183823314 0.0107176095 0.0184327271 0.0094118047 0.1232100000 0.0100930000 0.0606160000 0.0000280000 0.0002890000 0.0402330000 9710256 96830484 1770082304 4.0342497826 4.0156965256 3.7391433716 917 36.6400000000 0.0184137020 0.0107260022 0.0184327271 0.0094066762 0.1654220000 0.0143410000 0.0589200000 0.0002960000 0.0002670000 0.0811430000 9711930 96830484 1768972288 4.0318207741 4.0150370598 3.7391300201 918 36.6800000000 0.0184236467 0.0107343875 0.0184327271 0.0094018383 0.1291280000 0.0097270000 0.0455140000 0.0000270000 0.0003890000 0.0476420000 9713604 96830484 1770606592 4.0295615196 4.0149998665 3.7394146919 919 36.7200000000 0.0184308793 0.0107427623 0.0184327271 0.0093967763 0.1298470000 0.0118490000 0.0437310000 0.0003120000 0.0002750000 0.0543910000 9715278 96830484 1769607168 4.0275254250 4.0153293610 3.7390084267 920 36.7600000000 0.0184630398 0.0107511539 0.0184630398 0.0093919830 0.1119520000 0.0100540000 0.0463180000 0.0000250000 0.0003800000 0.0446540000 9716952 96830484 1771225088 4.0254788399 4.0151333809 3.7393257618 921 36.8000000000 0.0184625946 0.0107595268 0.0184630398 0.0093869145 0.1503080000 0.0113270000 0.0458970000 0.0003830000 0.0002770000 0.0818380000 9718626 96830484 1770115072 4.0236587524 4.0153212547 3.7395348549 922 36.8400000000 0.0185287613 0.0107679533 0.0185287613 0.0093823067 0.1184370000 0.0120240000 0.0526600000 0.0000290000 0.0002910000 0.0405850000 9720300 96830484 1768448000 4.0220232010 4.0158782005 3.7402765751 923 36.8800000000 0.0185543690 0.0107763893 0.0185543690 0.0093784533 0.1265240000 0.0109960000 0.0468700000 0.0003070000 0.0002790000 0.0535470000 9721974 96830484 1770110976 4.0204515457 4.0160336494 3.7403676510 924 36.9200000000 0.0185459964 0.0107847980 0.0185543690 0.0093757184 0.1261970000 0.0111610000 0.0466140000 0.0000300000 0.0003150000 0.0478400000 9723648 96830484 1768972288 4.0190143585 4.0158133507 3.7396538258 925 36.9600000000 0.0185758583 0.0107932207 0.0185758583 0.0093714584 0.1753420000 0.0099000000 0.0723280000 0.0000620000 0.0000530000 0.0824070000 9725322 96830484 1770639360 4.0174756050 4.0156078339 3.7400097847 926 37.0000000000 0.0185410455 0.0108015877 0.0185758583 0.0093664521 0.1210120000 0.0123210000 0.0462540000 0.0000280000 0.0003140000 0.0474020000 9726996 96830484 1769861120 4.0161995888 4.0158872604 3.7395751476 927 37.0400000000 0.0185513254 0.0108099477 0.0185758583 0.0093619424 0.1264410000 0.0114320000 0.0382400000 0.0003700000 0.0002820000 0.0570730000 9728670 96830484 1768194048 4.0150775909 4.0160307884 3.7396321297 928 37.0800000000 0.0185901616 0.0108183316 0.0185901616 0.0093586714 0.1307570000 0.0095100000 0.0586560000 0.0000260000 0.0003720000 0.0514960000 9730344 96830484 1769852928 4.0140647888 4.0168581009 3.7400691509 929 37.1200000000 0.0185482930 0.0108266523 0.0185901616 0.0093579141 0.1687180000 0.0103480000 0.0571990000 0.0003060000 0.0002820000 0.0898190000 9732018 96830484 1768730624 4.0130496025 4.0170016289 3.7405045033 930 37.1600000000 0.0185769740 0.0108349860 0.0185901616 0.0093569577 0.1224160000 0.0095820000 0.0533850000 0.0000270000 0.0003040000 0.0474290000 9733692 96830484 1770401792 4.0122227669 4.0172567368 3.7406246662 931 37.2000000000 0.0185802076 0.0108433053 0.0185901616 0.0093552046 0.1266090000 0.0111010000 0.0447190000 0.0003250000 0.0002850000 0.0537590000 9735366 96830484 1769480192 4.0114398003 4.0175848007 3.7409491539 932 37.2400000000 0.0185900778 0.0108516172 0.0185901616 0.0093522279 0.1094010000 0.0093660000 0.0389220000 0.0000950000 0.0002930000 0.0499290000 9737040 96830484 1771114496 4.0107994080 4.0177841187 3.7409925461 933 37.2800000000 0.0185711179 0.0108598911 0.0185901616 0.0093491500 0.1593350000 0.0105100000 0.0420140000 0.0003150000 0.0003600000 0.0811500000 9738714 96830484 1769971712 4.0101070404 4.0181956291 3.7414114475 934 37.3200000000 0.0186095685 0.0108681884 0.0186095685 0.0093466757 0.1585820000 0.0111680000 0.0896970000 0.0000280000 0.0002990000 0.0402870000 9740388 96830484 1768210432 4.0095825195 4.0189514160 3.7417445183 935 37.3600000000 0.0185077153 0.0108763590 0.0186095685 0.0093463039 0.1238660000 0.0096180000 0.0519790000 0.0003040000 0.0006650000 0.0505520000 9742062 96830484 1769877504 4.0091962814 4.0192298889 3.7418069839 936 37.4000000000 0.0185904577 0.0108846006 0.0186095685 0.0093444805 0.1234160000 0.0108410000 0.0446770000 0.0000280000 0.0003130000 0.0468460000 9743736 96830484 1768714240 4.0087771416 4.0194578171 3.7417783737 937 37.4400000000 0.0185982231 0.0108928328 0.0186095685 0.0093410234 0.1487090000 0.0094930000 0.0466370000 0.0003830000 0.0002800000 0.0811720000 9745410 96830484 1770639360 4.0085072517 4.0194530487 3.7417984009 938 37.4800000000 0.0186542105 0.0109011072 0.0186542105 0.0093376521 0.1660690000 0.0114760000 0.0828450000 0.0000060000 0.0000580000 0.0468350000 9747084 96830484 1769734144 4.0082221031 4.0194945335 3.7417271137 939 37.5200000000 0.0186090954 0.0109093159 0.0186542105 0.0093333554 0.1285970000 0.0110350000 0.0390060000 0.0003870000 0.0002790000 0.0571320000 9748758 96830484 1768321024 4.0082178116 4.0196700096 3.7414929867 940 37.5600000000 0.0185786877 0.0109174748 0.0186542105 0.0093291591 0.1294930000 0.0092540000 0.0466140000 0.0000270000 0.0003050000 0.0587170000 9750432 96830484 1769955328 4.0082197189 4.0199360847 3.7414703369 941 37.6000000000 0.0186125599 0.0109256524 0.0186542105 0.0093254804 0.1834490000 0.0105630000 0.0618950000 0.0003880000 0.0002830000 0.0796940000 9752106 96830484 1768988672 4.0081624985 4.0205016136 3.7415330410 942 37.6400000000 0.0185961276 0.0109337952 0.0186542105 0.0093222304 0.1306450000 0.0092630000 0.0546780000 0.0000280000 0.0003830000 0.0458440000 9753780 96830484 1770606592 4.0083250999 4.0209631920 3.7413580418 943 37.6800000000 0.0185294896 0.0109418500 0.0186542105 0.0093206669 0.1118520000 0.0111490000 0.0366970000 0.0003050000 0.0003540000 0.0525930000 9755454 96830484 1769480192 4.0084185600 4.0211162567 3.7411508560 944 37.7200000000 0.0185327604 0.0109498912 0.0186542105 0.0093183499 0.1245090000 0.0088580000 0.0457620000 0.0000260000 0.0003040000 0.0519790000 9757128 96830484 1771147264 4.0085339546 4.0216131210 3.7409765720 945 37.7600000000 0.0185343493 0.0109579171 0.0186542105 0.0093159365 0.1572960000 0.0115150000 0.0461290000 0.0003090000 0.0002740000 0.0881430000 9758802 96830484 1769988096 4.0086665154 4.0219082832 3.7407817841 946 37.8000000000 0.0185503997 0.0109659430 0.0186542105 0.0093134872 0.1172480000 0.0126480000 0.0371120000 0.0000310000 0.0003850000 0.0484020000 9760476 96830484 1768321024 4.0086755753 4.0220785141 3.7405614853 947 37.8400000000 0.0186268128 0.0109740326 0.0186542105 0.0093100266 0.1484780000 0.0095420000 0.0643290000 0.0003070000 0.0003500000 0.0592190000 9762150 96830484 1770004480 4.0088243484 4.0224456787 3.7405571938 948 37.8800000000 0.0185481962 0.0109820222 0.0186542105 0.0093073268 0.1681100000 0.0107140000 0.0923890000 0.0000260000 0.0003100000 0.0507130000 9763824 96830484 1768845312 4.0089287758 4.0225682259 3.7404253483 949 37.9200000000 0.0185472537 0.0109899940 0.0186542105 0.0093043669 0.1859210000 0.0088340000 0.0560340000 0.0003970000 0.0002800000 0.1007740000 9765498 96830484 1770766336 4.0091371536 4.0228576660 3.7402341366 950 37.9600000000 0.0185791980 0.0109979826 0.0186542105 0.0093004738 0.1106100000 0.0117090000 0.0422170000 0.0000310000 0.0003830000 0.0450770000 9767172 96830484 1769861120 4.0093884468 4.0233006477 3.7400207520 951 38.0000000000 0.0185388103 0.0110059120 0.0186542105 0.0092962591 0.1252640000 0.0118480000 0.0385990000 0.0003050000 0.0003490000 0.0553040000 9768846 96830484 1768079360 4.0095877647 4.0235309601 3.7399086952 952 38.0400000000 0.0185328498 0.0110138184 0.0186542105 0.0092938522 0.1466080000 0.0097940000 0.0700210000 0.0000280000 0.0003020000 0.0454050000 9770520 96830484 1769844736 4.0097379684 4.0237641335 3.7399952412 953 38.0800000000 0.0185447410 0.0110217208 0.0186542105 0.0092897576 0.1646370000 0.0112550000 0.0383730000 0.0002960000 0.0005880000 0.0804770000 9772194 96830484 1768955904 4.0100874901 4.0240368843 3.7396917343 954 38.1200000000 0.0185758024 0.0110296391 0.0186542105 0.0092849635 0.1127790000 0.0104430000 0.0429580000 0.0000270000 0.0003190000 0.0448680000 9773868 96830484 1770749952 4.0103731155 4.0244245529 3.7393677235 955 38.1600000000 0.0185526796 0.0110375166 0.0186542105 0.0092805173 0.1282590000 0.0111410000 0.0522920000 0.0002850000 0.0002640000 0.0516870000 9775542 96830484 1769861120 4.0105047226 4.0244140625 3.7395980358 956 38.2000000000 0.0186160821 0.0110454440 0.0186542105 0.0092756746 0.1084930000 0.0115530000 0.0384700000 0.0000290000 0.0002830000 0.0470520000 9777216 96830484 1768099840 4.0108461380 4.0248560905 3.7390618324 957 38.2400000000 0.0186196361 0.0110533585 0.0186542105 0.0092709449 0.1652350000 0.0092860000 0.0564260000 0.0007440000 0.0003030000 0.0798310000 9778890 96830484 1770020864 4.0109724998 4.0247197151 3.7388198376 958 38.2800000000 0.0186080001 0.0110612444 0.0186542105 0.0092662653 0.1109410000 0.0116770000 0.0449370000 0.0000310000 0.0003990000 0.0427070000 9780564 96830484 1768714240 4.0111160278 4.0249409676 3.7388584614 959 38.3200000000 0.0186277516 0.0110691344 0.0186542105 0.0092615961 0.1243670000 0.0096430000 0.0440280000 0.0003860000 0.0002850000 0.0514350000 9782238 96830484 1770496000 4.0114116669 4.0249576569 3.7384941578 960 38.3600000000 0.0186579153 0.0110770393 0.0186579153 0.0092570765 0.1309770000 0.0115990000 0.0665330000 0.0000260000 0.0002880000 0.0414630000 9783912 96830484 1769336832 4.0115814209 4.0251278877 3.7385671139 961 38.4000000000 0.0186493807 0.0110849190 0.0186579153 0.0092525906 0.1443590000 0.0098890000 0.0443240000 0.0005270000 0.0005390000 0.0779650000 9785586 96830484 1771012096 4.0118894577 4.0252466202 3.7382283211 962 38.4400000000 0.0186684970 0.0110928021 0.0186684970 0.0092479846 0.1094570000 0.0116470000 0.0364890000 0.0000280000 0.0003570000 0.0474450000 9787260 96830484 1769979904 4.0121498108 4.0253648758 3.7379837036 963 38.4800000000 0.0186754819 0.0111006761 0.0186754819 0.0092432859 0.1458940000 0.0108920000 0.0633250000 0.0002950000 0.0003410000 0.0516540000 9788934 96830484 1768198144 4.0124239922 4.0252323151 3.7378711700 964 38.5200000000 0.0186893996 0.0111085483 0.0186893996 0.0092385658 0.1233630000 0.0100540000 0.0463410000 0.0000260000 0.0003870000 0.0444180000 9790608 96830484 1769832448 4.0127549171 4.0254545212 3.7377099991 965 38.5600000000 0.0186861604 0.0111164007 0.0186893996 0.0092338397 0.1497010000 0.0113560000 0.0481790000 0.0003080000 0.0003600000 0.0781490000 9792282 96830484 1768853504 4.0130486488 4.0255298615 3.7376918793 966 38.6000000000 0.0186740421 0.0111242244 0.0186893996 0.0092292518 0.1097030000 0.0093150000 0.0365040000 0.0000300000 0.0007010000 0.0468260000 9793956 96830484 1770500096 4.0133180618 4.0254974365 3.7375433445 967 38.6400000000 0.0186438542 0.0111320006 0.0186893996 0.0092245025 0.1457970000 0.0108750000 0.0612740000 0.0003060000 0.0002760000 0.0577970000 9795630 96830484 1769693184 4.0135960579 4.0255022049 3.7375471592 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:22:55 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002980 0.0000002980 0.0000002980 nan 0.1168510000 0.0244110000 0.0202690000 0.0002760000 0.0000300000 0.0711690000 7758382 96830484 1772818432 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0010032422 0.0005017701 0.0010032422 0.0033378715 0.0530380000 0.0149230000 0.0081290000 0.0001150000 0.0000080000 0.0289740000 7924168 96830484 1771823104 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0055015511 0.0021683638 0.0055015511 0.0047728951 0.0719670000 0.0157470000 0.0170530000 0.0001160000 0.0000070000 0.0378730000 7926166 96830484 1769914368 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0036504185 0.0025388775 0.0055015511 0.0040723570 0.1664880000 0.0306330000 0.0329240000 0.0004020000 0.0004300000 0.1017570000 7928188 96830484 1768628224 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0021276867 0.0024566393 0.0055015511 0.0048987371 0.1689820000 0.0125480000 0.0737400000 0.0003020000 0.0002750000 0.0818000000 7930182 96830484 1770323968 3.9957129955 4.0020370483 4.0009112358 6 0.2000000000 0.0021193668 0.0024004272 0.0055015511 0.0043898062 0.0916550000 0.0118560000 0.0457330000 0.0000230000 0.0003060000 0.0333760000 7932512 96830484 1768284160 3.9965579510 4.0017552376 4.0000634193 7 0.2400000000 0.0020520808 0.0023506635 0.0055015511 0.0040162997 0.1077280000 0.0100580000 0.0457070000 0.0003040000 0.0002790000 0.0509940000 7934186 96830484 1767124992 3.9963893890 4.0014748573 4.0003581047 8 0.2800000000 0.0021309818 0.0023232032 0.0055015511 0.0037226413 0.0874620000 0.0094460000 0.0381990000 0.0000230000 0.0002980000 0.0391720000 7935860 96830484 1768783872 3.9949610233 4.0019330978 4.0002708435 9 0.3200000000 0.0021698186 0.0023061605 0.0055015511 0.0035285959 0.1142360000 0.0096230000 0.0352230000 0.0000940000 0.0000840000 0.0689260000 7938174 96830484 1770426368 3.9930253029 4.0012869835 4.0003128052 10 0.3600000000 0.0022089549 0.0022964399 0.0055015511 0.0033889458 0.0856940000 0.0108700000 0.0386050000 0.0000240000 0.0003120000 0.0355350000 7941160 96830484 1769541632 3.9929094315 4.0026316643 4.0009026527 11 0.4000000000 0.0022607681 0.0022931970 0.0055015511 0.0033576477 0.1044120000 0.0112780000 0.0429260000 0.0002950000 0.0002670000 0.0483750000 7942834 96830484 1767772160 3.9919469357 4.0017871857 4.0016007423 12 0.4400000000 0.0022675800 0.0022910623 0.0055015511 0.0034304054 0.0884190000 0.0092970000 0.0360190000 0.0000160000 0.0002020000 0.0415910000 7944508 96830484 1769414656 3.9918613434 4.0017371178 4.0008234978 13 0.4800000000 0.0022817205 0.0022903437 0.0055015511 0.0034359296 0.1270910000 0.0113460000 0.0373730000 0.0000990000 0.0000830000 0.0778710000 7946182 96830484 1767485440 3.9894282818 4.0015411377 4.0013957024 14 0.5200000000 0.0023265851 0.0022929324 0.0055015511 0.0033242156 0.1306030000 0.0091770000 0.0840820000 0.0000040000 0.0000620000 0.0359580000 7947856 96830484 1769148416 3.9894304276 4.0028085709 4.0008177757 15 0.5600000000 0.0023081175 0.0022939447 0.0055015511 0.0032120843 0.0986650000 0.0111430000 0.0406610000 0.0002960000 0.0003370000 0.0447170000 7949530 96830484 1768284160 3.9863359928 4.0038886070 4.0015878677 16 0.6000000000 0.0023983542 0.0023004703 0.0055015511 0.0031278541 0.1095190000 0.0089480000 0.0569750000 0.0000230000 0.0002820000 0.0417590000 7951204 96830484 1770057728 3.9871211052 4.0023255348 4.0005331039 17 0.6400000000 0.0024038421 0.0023065510 0.0055015511 0.0030498086 0.1402680000 0.0109520000 0.0458690000 0.0002980000 0.0002700000 0.0813130000 7954158 96830484 1769287680 3.9851036072 4.0008940697 3.9991033077 18 0.6800000000 0.0024459769 0.0023142969 0.0055015511 0.0029599863 0.0920080000 0.0100030000 0.0462660000 0.0000240000 0.0003140000 0.0350040000 7958456 96830484 1770962944 3.9835436344 4.0011606216 4.0000782013 19 0.7200000000 0.0024385911 0.0023208387 0.0055015511 0.0029191459 0.0977890000 0.0111290000 0.0417450000 0.0003610000 0.0010790000 0.0413020000 7960130 96830484 1770049536 3.9820597172 4.0014066696 3.9996430874 20 0.7600000000 0.0025582798 0.0023327107 0.0055015511 0.0029371889 0.0868790000 0.0116360000 0.0354730000 0.0000150000 0.0002420000 0.0378340000 7961804 96830484 1768030208 3.9790954590 4.0002269745 3.9993181229 21 0.8000000000 0.0026402324 0.0023473546 0.0055015511 0.0028722433 0.1399500000 0.0094300000 0.0486080000 0.0003880000 0.0002650000 0.0795650000 7963478 96830484 1766850560 3.9762647152 4.0010972023 3.9996490479 22 0.8400000000 0.0029144434 0.0023731314 0.0055015511 0.0028126042 0.0881710000 0.0094010000 0.0387550000 0.0000250000 0.0002880000 0.0379100000 7965152 96830484 1768529920 3.9707875252 4.0004653931 3.9992005825 23 0.8800000000 0.0029079607 0.0023963848 0.0055015511 0.0027479746 0.1016430000 0.0090020000 0.0458820000 0.0002940000 0.0002680000 0.0444500000 7966826 96830484 1770299392 3.9713721275 3.9995739460 3.9975578785 24 0.9200000000 0.0028096719 0.0024136051 0.0055015511 0.0026877533 0.1101260000 0.0113000000 0.0509640000 0.0000250000 0.0002840000 0.0456770000 7968500 96830484 1769410560 3.9628987312 4.0010185242 3.9969220161 25 0.9600000000 0.0027906045 0.0024286851 0.0055015511 0.0026594775 0.1160930000 0.0092010000 0.0354160000 0.0002130000 0.0002130000 0.0705730000 7970174 96830484 1771106304 3.9617063999 4.0022830963 3.9961562157 26 1.0000000000 0.0028318348 0.0024441909 0.0055015511 0.0026071390 0.0936140000 0.0120300000 0.0433840000 0.0000230000 0.0003780000 0.0358490000 7971848 96830484 1769938944 3.9554364681 4.0008044243 3.9970476627 27 1.0400000000 0.0026902761 0.0024533051 0.0055015511 0.0026328308 0.1062440000 0.0099410000 0.0434850000 0.0004200000 0.0002760000 0.0501000000 7973522 96830484 1768931328 3.9496479034 4.0000362396 3.9948539734 28 1.0800000000 0.0027714712 0.0024646682 0.0055015511 0.0027076172 0.0932270000 0.0100050000 0.0505470000 0.0000230000 0.0003570000 0.0318040000 7975196 96830484 1768038400 3.9448773861 4.0019016266 3.9945564270 29 1.1200000000 0.0027285318 0.0024737670 0.0055015511 0.0027861190 0.1285910000 0.0099760000 0.0482600000 0.0003200000 0.0002770000 0.0692510000 7976870 96830484 1767538688 3.9388296604 4.0020227432 3.9917793274 30 1.1600000000 0.0030032410 0.0024914161 0.0055015511 0.0027895884 0.0873420000 0.0096950000 0.0456890000 0.0000250000 0.0003120000 0.0311100000 7978544 96830484 1767010304 3.9293973446 4.0014457703 3.9938304424 31 1.2000000000 0.0029136736 0.0025050373 0.0055015511 0.0027657983 0.1100300000 0.0094880000 0.0484310000 0.0084380000 0.0003230000 0.0428270000 7980218 96830484 1766113280 3.9228038788 4.0022139549 3.9920375347 32 1.2400000000 0.0029506644 0.0025189631 0.0055015511 0.0027654780 0.0902970000 0.0103140000 0.0458610000 0.0000260000 0.0003170000 0.0332310000 7981892 96830484 1765629952 3.9160888195 4.0025353432 3.9897420406 33 1.2800000000 0.0029396042 0.0025317098 0.0055015511 0.0028074009 0.1266070000 0.0092980000 0.0450430000 0.0002950000 0.0003500000 0.0710440000 7986126 96830484 1764843520 3.9104783535 4.0022211075 3.9895060062 34 1.3200000000 0.0028935280 0.0025423516 0.0055015511 0.0027808310 0.0922050000 0.0101340000 0.0445590000 0.0000260000 0.0002880000 0.0365520000 7993048 96830484 1764114432 3.8820114136 4.0016813278 3.9892072678 35 1.3600000000 0.0030744108 0.0025575532 0.0055015511 0.0030478038 0.1010410000 0.0094580000 0.0427850000 0.0003050000 0.0002760000 0.0457280000 7994722 96830484 1764499456 3.8787240982 4.0025434494 3.9865615368 36 1.4000000000 0.0030465741 0.0025711372 0.0055015511 0.0035589818 0.0853310000 0.0088580000 0.0353870000 0.0000250000 0.0003670000 0.0383020000 7996396 96830484 1765990400 3.8730773926 4.0032992363 3.9847621918 37 1.4400000000 0.0030497839 0.0025840736 0.0055015511 0.0035973373 0.1414510000 0.0088570000 0.0496580000 0.0003000000 0.0006870000 0.0813220000 7998070 96830484 1767739392 3.8621592522 4.0013198853 3.9860253334 38 1.4800000000 0.0032345029 0.0026011901 0.0055015511 0.0035570682 0.1001060000 0.0126320000 0.0552690000 0.0000240000 0.0003540000 0.0311980000 7999744 96830484 1769517056 3.8505938053 4.0007581711 3.9867534637 39 1.5200000000 0.0032989846 0.0026190823 0.0055015511 0.0035142170 0.0878350000 0.0107030000 0.0337570000 0.0000770000 0.0000680000 0.0426760000 8001418 96830484 1768390656 3.8474638462 4.0001363754 3.9834077358 40 1.5600000000 0.0033597045 0.0026375978 0.0055015511 0.0034974239 0.0861680000 0.0089620000 0.0359030000 0.0000170000 0.0002120000 0.0384900000 8003092 96830484 1767264256 3.8375625610 3.9985222816 3.9840943813 41 1.6000000000 0.0033773324 0.0026556401 0.0055015511 0.0035179614 0.1433790000 0.0085350000 0.0524460000 0.0003590000 0.0002740000 0.0811080000 8004766 96830484 1766129664 3.8271625042 3.9974081516 3.9858469963 42 1.6400000000 0.0033806583 0.0026729025 0.0055015511 0.0034791059 0.0925090000 0.0087390000 0.0369930000 0.0000240000 0.0004260000 0.0436280000 8006440 96830484 1767768064 3.8137972355 3.9989020824 3.9880621433 43 1.6800000000 0.0033616489 0.0026889198 0.0055015511 0.0034582636 0.1102410000 0.0085420000 0.0457920000 0.0002860000 0.0003360000 0.0522250000 8008114 96830484 1769517056 3.8069863319 3.9993288517 3.9914345741 44 1.7200000000 0.0033652280 0.0027042905 0.0055015511 0.0034889558 0.0909420000 0.0105240000 0.0377150000 0.0000080000 0.0001000000 0.0418970000 8009788 96830484 1768263680 3.8006696701 3.9986765385 3.9893207550 45 1.7600000000 0.0033918147 0.0027195688 0.0055015511 0.0035075427 0.1384910000 0.0091240000 0.0475490000 0.0003730000 0.0002730000 0.0783970000 8011462 96830484 1766477824 3.7923023701 4.0006685257 3.9930346012 46 1.8000000000 0.0034418837 0.0027352713 0.0055015511 0.0035142630 0.0919630000 0.0089710000 0.0458390000 0.0000240000 0.0003240000 0.0361570000 8013136 96830484 1768247296 3.7863330841 4.0012736320 3.9931325912 47 1.8400000000 0.0034591854 0.0027506737 0.0055015511 0.0036200882 0.0883640000 0.0086240000 0.0340650000 0.0001110000 0.0000820000 0.0434940000 8014810 96830484 1770024960 3.7833192348 3.9994659424 3.9928328991 48 1.8800000000 0.0034216086 0.0027646515 0.0055015511 0.0036631902 0.0899930000 0.0110440000 0.0432350000 0.0000240000 0.0003140000 0.0346380000 8016484 96830484 1768775680 3.7787630558 3.9991860390 3.9939386845 49 1.9200000000 0.0036153251 0.0027820122 0.0055015511 0.0036249469 0.1156660000 0.0109720000 0.0355100000 0.0000770000 0.0000770000 0.0683880000 8018158 96830484 1767391232 3.7716283798 4.0004005432 3.9947481155 50 1.9600000000 0.0035999152 0.0027983703 0.0055015511 0.0036102982 0.0936690000 0.0088390000 0.0433220000 0.0000260000 0.0003690000 0.0380210000 8019832 96830484 1769074688 3.7573053837 4.0000443459 3.9996886253 51 2.0000000000 0.0035136426 0.0028123952 0.0055015511 0.0035844400 0.1089990000 0.0085430000 0.0453820000 0.0002910000 0.0003410000 0.0511550000 8021506 96830484 1770913792 3.7588639259 3.9998888969 3.9966924191 52 2.0400000000 0.0035622681 0.0028268159 0.0055015511 0.0035492689 0.1114950000 0.0103120000 0.0544880000 0.0000270000 0.0002880000 0.0456770000 8023180 96830484 1769914368 3.7549383640 4.0002870560 3.9959812164 53 2.0800000000 0.0034568321 0.0028387030 0.0055015511 0.0035930304 0.1413640000 0.0106370000 0.0510920000 0.0003160000 0.0002700000 0.0757240000 8024854 96830484 1768534016 3.7529284954 3.9978299141 3.9927301407 54 2.1200000000 0.0036012181 0.0028528236 0.0055015511 0.0036679579 0.0917120000 0.0092230000 0.0446810000 0.0000270000 0.0021560000 0.0348870000 8026528 96830484 1770196992 3.7399032116 3.9963810444 3.9985296726 55 2.1600000000 0.0035210552 0.0028649733 0.0055015511 0.0037628136 0.1023140000 0.0112940000 0.0435350000 0.0003910000 0.0002790000 0.0430560000 8028202 96830484 1769009152 3.7375395298 3.9971230030 3.9982161522 56 2.2000000000 0.0036108077 0.0028782917 0.0055015511 0.0037701873 0.0911320000 0.0092550000 0.0435300000 0.0000290000 0.0003120000 0.0365320000 8029876 96830484 1770717184 3.7177057266 3.9974868298 4.0073981285 57 2.2400000000 0.0037530900 0.0028936391 0.0055015511 0.0037490218 0.1256980000 0.0110440000 0.0409680000 0.0002900000 0.0002600000 0.0723670000 8031550 96830484 1770033152 3.7129147053 3.9949142933 4.0079951286 58 2.2800000000 0.0036983066 0.0029075127 0.0055015511 0.0037578113 0.0887950000 0.0107010000 0.0357680000 0.0000080000 0.0000900000 0.0386010000 8033224 96830484 1768525824 3.7035658360 3.9941787720 4.0107650757 59 2.3200000000 0.0038099838 0.0029228088 0.0055015511 0.0038958326 0.1095540000 0.0088560000 0.0441720000 0.0003020000 0.0003780000 0.0550500000 8034898 96830484 1767129088 3.6894240379 3.9966025352 4.0165247917 60 2.3600000000 0.0037962198 0.0029373656 0.0055015511 0.0040111455 0.0852260000 0.0086190000 0.0359040000 0.0000160000 0.0001900000 0.0368810000 8036572 96830484 1768779776 3.6862916946 3.9948871136 4.0145845413 61 2.4000000000 0.0038407429 0.0029521751 0.0055015511 0.0041276544 0.1246670000 0.0086140000 0.0446600000 0.0007180000 0.0003600000 0.0694270000 8038246 96830484 1770524672 3.6795248985 3.9934597015 4.0143733025 62 2.4400000000 0.0038516498 0.0029666828 0.0055015511 0.0042929660 0.0949570000 0.0102400000 0.0425270000 0.0000260000 0.0002890000 0.0389690000 8039920 96830484 1769652224 3.6558568478 3.9938807487 4.0246858597 63 2.4800000000 0.0038877756 0.0029813033 0.0055015511 0.0044370411 0.1105190000 0.0087020000 0.0496730000 0.0003050000 0.0003490000 0.0506900000 8041594 96830484 1768493056 3.6471881866 3.9928202629 4.0258584023 64 2.5200000000 0.0038804887 0.0029953530 0.0055015511 0.0047966692 0.1039500000 0.0084220000 0.0445130000 0.0000230000 0.0002840000 0.0462610000 8043268 96830484 1767923712 3.6346523762 3.9939303398 4.0304179192 65 2.5600000000 0.0038905402 0.0030091252 0.0055015511 0.0051044200 0.1624210000 0.0081110000 0.0714600000 0.0025140000 0.0002790000 0.0751330000 8050062 96830484 1766879232 3.6208126545 3.9938166142 4.0341472626 66 2.6000000000 0.0040779728 0.0030253198 0.0055015511 0.0051955713 0.0924630000 0.0080040000 0.0385130000 0.0000160000 0.0002380000 0.0448030000 8062232 96830484 1765621760 3.6103200912 3.9951486588 4.0361342430 67 2.6400000000 0.0040969332 0.0030413140 0.0055015511 0.0052466839 0.1054760000 0.0096090000 0.0446300000 0.0002830000 0.0006370000 0.0458330000 8063906 96830484 1764487168 3.6001145840 3.9975600243 4.0384063721 68 2.6800000000 0.0043201996 0.0030601212 0.0055015511 0.0052299538 0.1103000000 0.0081210000 0.0547800000 0.0000230000 0.0003120000 0.0460190000 8065580 96830484 1766109184 3.5891766548 3.9974367619 4.0377378464 69 2.7200000000 0.0043213847 0.0030784004 0.0055015511 0.0051933888 0.1223160000 0.0080690000 0.0414170000 0.0003810000 0.0003070000 0.0712420000 8067254 96830484 1767735296 3.5796022415 3.9977006912 4.0422320366 70 2.7600000000 0.0044693355 0.0030982709 0.0055015511 0.0051654802 0.0955190000 0.0082860000 0.0436680000 0.0000240000 0.0003150000 0.0394850000 8068928 96830484 1769508864 3.5707454681 3.9996337891 4.0418829918 71 2.8000000000 0.0045017679 0.0031180384 0.0055015511 0.0052159198 0.1106730000 0.0097190000 0.0461040000 0.0002950000 0.0003770000 0.0532650000 8070602 96830484 1768366080 3.5635986328 4.0002326965 4.0388050079 72 2.8400000000 0.0048455861 0.0031420322 0.0055015511 0.0058973271 0.1081840000 0.0080240000 0.0480350000 0.0000250000 0.0006220000 0.0467160000 8072276 96830484 1770151936 3.5478820801 4.0054097176 4.0417695045 73 2.8800000000 0.0048695048 0.0031656962 0.0055015511 0.0059700889 0.1440970000 0.0100780000 0.0496030000 0.0003140000 0.0002650000 0.0796050000 8073950 96830484 1769398272 3.5378980637 4.0068230629 4.0434441566 74 2.9200000000 0.0049511874 0.0031898244 0.0055015511 0.0060608059 0.0901580000 0.0104250000 0.0369320000 0.0000060000 0.0000750000 0.0388260000 8075624 96830484 1767890944 3.5358490944 4.0085172653 4.0402970314 75 2.9600000000 0.0050919703 0.0032151864 0.0055015511 0.0061155850 0.1106700000 0.0092870000 0.0479820000 0.0002900000 0.0003370000 0.0518110000 8077298 96830484 1767137280 3.5346438885 4.0121569633 4.0375247002 76 3.0000000000 0.0050736363 0.0032396397 0.0055015511 0.0061499715 0.0900570000 0.0080000000 0.0418440000 0.0000250000 0.0002940000 0.0388330000 8078972 96830484 1768873984 3.5366401672 4.0152049065 4.0294260979 77 3.0400000000 0.0047360552 0.0032590736 0.0055015511 0.0061733563 0.1243070000 0.0077600000 0.0336360000 0.0002570000 0.0001770000 0.0783210000 8080646 96830484 1770524672 3.5357468128 4.0155305862 4.0226578712 78 3.0800000000 0.0043565077 0.0032731433 0.0055015511 0.0061424763 0.0909840000 0.0107150000 0.0437410000 0.0000260000 0.0003230000 0.0351970000 8082320 96830484 1769398272 3.5369172096 4.0168828964 4.0154690742 79 3.1200000000 0.0042994311 0.0032861343 0.0055015511 0.0061043897 0.1097890000 0.0088460000 0.0486160000 0.0009750000 0.0003320000 0.0499420000 8083994 96830484 1768378368 3.5298633575 4.0200643539 4.0133028030 80 3.1600000000 0.0040675509 0.0032959020 0.0055015511 0.0060687379 0.1051530000 0.0124440000 0.0539610000 0.0000220000 0.0003590000 0.0373790000 8085668 96830484 1769889792 3.5259122849 4.0230669975 4.0096015930 81 3.2000000000 0.0041678529 0.0033066668 0.0055015511 0.0060408441 0.1656140000 0.0103550000 0.0817130000 0.0003290000 0.0002710000 0.0718710000 8087342 96830484 1768783872 3.5140886307 4.0221219063 4.0126109123 82 3.2400000000 0.0043998412 0.0033199982 0.0055015511 0.0060490392 0.0925020000 0.0081870000 0.0518350000 0.0000270000 0.0003130000 0.0311250000 8089016 96830484 1770463232 3.5058853626 4.0222730637 4.0121889114 83 3.2800000000 0.0043142238 0.0033319768 0.0055015511 0.0060868578 0.0921810000 0.0101390000 0.0356530000 0.0000770000 0.0000680000 0.0452640000 8090690 96830484 1769672704 3.4979877472 4.0243492126 4.0090532303 84 3.3200000000 0.0043057348 0.0033435692 0.0055015511 0.0060778952 0.1048170000 0.0081530000 0.0476300000 0.0000230000 0.0003240000 0.0469930000 8092364 96830484 1768542208 3.4852621555 4.0233669281 4.0093283653 85 3.3600000000 0.0045070788 0.0033572575 0.0055015511 0.0060685870 0.1509870000 0.0079080000 0.0532410000 0.0002940000 0.0002710000 0.0841240000 8094038 96830484 1768034304 3.4720706940 4.0242362022 4.0097379684 86 3.4000000000 0.0044985469 0.0033705283 0.0055015511 0.0061072585 0.0948960000 0.0084320000 0.0482860000 0.0000280000 0.0003820000 0.0366930000 8095712 96830484 1766895616 3.4570465088 4.0251402855 4.0137996674 87 3.4400000000 0.0041875807 0.0033799197 0.0055015511 0.0062326132 0.1057850000 0.0082580000 0.0425210000 0.0002870000 0.0002630000 0.0481390000 8097386 96830484 1765736448 3.4469785690 4.0238556862 4.0134696960 88 3.4800000000 0.0038636187 0.0033854163 0.0055015511 0.0063830350 0.0893460000 0.0089500000 0.0355920000 0.0000170000 0.0001920000 0.0413440000 8099060 96830484 1765318656 3.4335203171 4.0241293907 4.0137071609 89 3.5200000000 0.0040280754 0.0033926372 0.0055015511 0.0065297436 0.1571910000 0.0083530000 0.0634150000 0.0002950000 0.0002640000 0.0837780000 8100734 96830484 1765113856 3.4245235920 4.0243425369 4.0138111115 90 3.5600000000 0.0044007315 0.0034038383 0.0055015511 0.0066381226 0.0970940000 0.0087850000 0.0414510000 0.0000230000 0.0002850000 0.0413940000 8102408 96830484 1764827136 3.4175665379 4.0225892067 4.0125846863 91 3.6000000000 0.0041434229 0.0034119656 0.0055015511 0.0066784884 0.1059050000 0.0075460000 0.0399140000 0.0002350000 0.0001710000 0.0530330000 8104082 96830484 1765105664 3.4026882648 4.0212779045 4.0156178474 92 3.6400000000 0.0042125247 0.0034206673 0.0055015511 0.0066905032 0.1092370000 0.0080830000 0.0469450000 0.0000250000 0.0003620000 0.0507760000 8105756 96830484 1764585472 3.3876051903 4.0233893394 4.0208153725 93 3.6800000000 0.0041170446 0.0034281552 0.0055015511 0.0066699189 0.1464540000 0.0082880000 0.0447450000 0.0003910000 0.0003020000 0.0912270000 8107430 96830484 1766256640 3.3826262951 4.0225024223 4.0174160004 94 3.7200000000 0.0040446194 0.0034347134 0.0055015511 0.0066420503 0.0940100000 0.0078160000 0.0479870000 0.0000260000 0.0003160000 0.0367540000 8109104 96830484 1767735296 3.3753530979 4.0200648308 4.0169715881 95 3.7600000000 0.0041557457 0.0034423032 0.0055015511 0.0066274985 0.1066310000 0.0083020000 0.0418350000 0.0003270000 0.0003460000 0.0503430000 8110778 96830484 1769508864 3.3624577522 4.0213975906 4.0235295296 96 3.8000000000 0.0040876796 0.0034490258 0.0055015511 0.0065997821 0.1102860000 0.0089820000 0.0494860000 0.0000230000 0.0002870000 0.0488970000 8112452 96830484 1768407040 3.3521332741 4.0208735466 4.0231089592 97 3.8400000000 0.0042544981 0.0034573297 0.0055015511 0.0065660225 0.1579140000 0.0077530000 0.0573780000 0.0007060000 0.0002870000 0.0906170000 8114126 96830484 1770065920 3.3468501568 4.0181550980 4.0250072479 98 3.8800000000 0.0042286213 0.0034652000 0.0055015511 0.0065406206 0.1004770000 0.0125310000 0.0402160000 0.0000320000 0.0003010000 0.0431880000 8115800 96830484 1769017344 3.3322317600 4.0175247192 4.0290803909 99 3.9200000000 0.0043106712 0.0034737401 0.0055015511 0.0065134598 0.1097220000 0.0081050000 0.0433470000 0.0002940000 0.0003300000 0.0564650000 8117474 96830484 1767530496 3.3268041611 4.0189332962 4.0322213173 100 3.9600000000 0.0044734539 0.0034837372 0.0055015511 0.0064808071 0.0924500000 0.0079240000 0.0405800000 0.0000260000 0.0003600000 0.0423070000 8119148 96830484 1767272448 3.3189098835 4.0183291435 4.0362606049 101 4.0000000000 0.0041882480 0.0034907126 0.0055015511 0.0064511271 0.1450390000 0.0077080000 0.0505010000 0.0002860000 0.0003390000 0.0802440000 8120822 96830484 1766359040 3.3098516464 4.0166153908 4.0422801971 102 4.0400000000 0.0041925670 0.0034975935 0.0055015511 0.0064307157 0.0921130000 0.0083600000 0.0434600000 0.0000270000 0.0011410000 0.0379200000 8122496 96830484 1766002688 3.3061838150 4.0152354240 4.0438990593 103 4.0800000000 0.0041389293 0.0035038201 0.0055015511 0.0064001388 0.1077960000 0.0081810000 0.0388080000 0.0103520000 0.0009610000 0.0482840000 8124170 96830484 1765384192 3.2954325676 4.0147409439 4.0505323410 104 4.1200000000 0.0043298230 0.0035117624 0.0055015511 0.0063751894 0.0905740000 0.0083100000 0.0401900000 0.0000250000 0.0002910000 0.0404540000 8125844 96830484 1765089280 3.2831025124 4.0128850937 4.0633416176 105 4.1600000000 0.0042557004 0.0035188475 0.0055015511 0.0063732583 0.1272060000 0.0080730000 0.0371590000 0.0001350000 0.0000690000 0.0805800000 8127518 96830484 1764950016 3.2800943851 4.0127501488 4.0651073456 106 4.2000000000 0.0043538716 0.0035267251 0.0055015511 0.0063828762 0.0908920000 0.0076180000 0.0402350000 0.0000080000 0.0000750000 0.0417890000 8129192 96830484 1766756352 3.2739760876 4.0132474899 4.0701584816 107 4.2400000000 0.0044673840 0.0035355163 0.0055015511 0.0063663586 0.1078170000 0.0075330000 0.0393930000 0.0001900000 0.0002930000 0.0554180000 8130866 96830484 1768488960 3.2737646103 4.0100221634 4.0664815903 108 4.2800000000 0.0041306498 0.0035410268 0.0055015511 0.0063376871 0.1046350000 0.0075830000 0.0409140000 0.0000160000 0.0001930000 0.0500450000 8132540 96830484 1770262528 3.2635633945 4.0090322495 4.0749359131 109 4.3200000000 0.0042447792 0.0035474833 0.0055015511 0.0063186525 0.1687160000 0.0101240000 0.0621050000 0.0001560000 0.0000620000 0.0900180000 8134214 96830484 1769390080 3.2618064880 4.0092082024 4.0760221481 110 4.3600000000 0.0047176909 0.0035581215 0.0055015511 0.0063305631 0.0998280000 0.0081230000 0.0393770000 0.0000240000 0.0003050000 0.0453740000 8135888 96830484 1770897408 3.2547669411 4.0085148811 4.0843915939 111 4.4000000000 0.0043540760 0.0035652923 0.0055015511 0.0063283967 0.1338870000 0.0098690000 0.0670080000 0.0003190000 0.0005020000 0.0548680000 8137562 96830484 1768992768 3.2477731705 4.0073037148 4.0910882950 112 4.4400000000 0.0043636537 0.0035724205 0.0055015511 0.0063294602 0.1075340000 0.0080820000 0.0422720000 0.0000270000 0.0003780000 0.0530600000 8139236 96830484 1770528768 3.2398145199 4.0079445839 4.0989527702 113 4.4800000000 0.0044202693 0.0035799236 0.0055015511 0.0063361286 0.1628330000 0.0100460000 0.0447010000 0.0003250000 0.0002740000 0.1008530000 8140910 96830484 1768628224 3.2356603146 4.0078201294 4.1031579971 114 4.5200000000 0.0044310060 0.0035873892 0.0055015511 0.0063828275 0.1054170000 0.0085640000 0.0457890000 0.0000260000 0.0003790000 0.0444810000 8142584 96830484 1770262528 3.2248780727 4.0076932907 4.1154446602 115 4.5600000000 0.0044104755 0.0035945465 0.0055015511 0.0064050172 0.1095620000 0.0097940000 0.0381060000 0.0001910000 0.0001690000 0.0546840000 8144258 96830484 1769517056 3.2241613865 4.0075888634 4.1172804832 116 4.6000000000 0.0044571646 0.0036019829 0.0055015511 0.0064460610 0.1242620000 0.0079910000 0.0502420000 0.0000270000 0.0003190000 0.0594740000 8145932 96830484 1771184128 3.2138011456 4.0102252960 4.1293311119 117 4.6400000000 0.0045295958 0.0036099112 0.0055015511 0.0064535611 0.1665240000 0.0098790000 0.0476030000 0.0003630000 0.0003060000 0.1019900000 8147606 96830484 1769033728 3.2062163353 4.0131697655 4.1397809982 118 4.6800000000 0.0044899643 0.0036173693 0.0055015511 0.0064263592 0.1026880000 0.0082630000 0.0544190000 0.0000340000 0.0003460000 0.0381630000 8149280 96830484 1770672128 3.2005317211 4.0115976334 4.1439776421 119 4.7200000000 0.0043839146 0.0036238108 0.0055015511 0.0064042992 0.1152360000 0.0152840000 0.0387430000 0.0001090000 0.0000960000 0.0565450000 8150954 96830484 1768632320 3.1941034794 4.0111160278 4.1509785652 120 4.7600000000 0.0043759644 0.0036300788 0.0055015511 0.0063796073 0.1481770000 0.0078850000 0.0853680000 0.0000060000 0.0000590000 0.0478820000 8152628 96830484 1770401792 3.1872189045 4.0124731064 4.1592054367 121 4.8000000000 0.0042338832 0.0036350689 0.0055015511 0.0063623421 0.1686840000 0.0100690000 0.0657070000 0.0002890000 0.0000680000 0.0861180000 8154302 96830484 1768374272 3.1777808666 4.0119271278 4.1769375801 122 4.8400000000 0.0043840194 0.0036412078 0.0055015511 0.0063399134 0.0921460000 0.0083320000 0.0372020000 0.0000250000 0.0005560000 0.0446750000 8155976 96830484 1769799680 3.1763107777 4.0134363174 4.1777849197 123 4.8800000000 0.0044023991 0.0036473964 0.0055015511 0.0063177710 0.1169200000 0.0099360000 0.0451480000 0.0003510000 0.0002680000 0.0539480000 8157650 96830484 1767866368 3.1706545353 4.0176043510 4.1841621399 124 4.9200000000 0.0045968168 0.0036550530 0.0055015511 0.0062977817 0.1089610000 0.0084250000 0.0477370000 0.0000230000 0.0003820000 0.0457660000 8159324 96830484 1769545728 3.1615383625 4.0185518265 4.2000694275 125 4.9600000000 0.0045725657 0.0036623931 0.0055015511 0.0062876576 0.1483090000 0.0099580000 0.0405440000 0.0002920000 0.0003320000 0.0898560000 8160998 96830484 1768796160 3.1571557522 4.0183286667 4.2050676346 126 5.0000000000 0.0043846602 0.0036681254 0.0055015511 0.0062683087 0.1077010000 0.0084880000 0.0459030000 0.0000250000 0.0003120000 0.0463230000 8162672 96830484 1770389504 3.1521465778 4.0194344521 4.2123532295 127 5.0400000000 0.0045854216 0.0036753482 0.0055015511 0.0062440527 0.1105860000 0.0100250000 0.0381550000 0.0001880000 0.0002230000 0.0575210000 8164346 96830484 1769644032 3.1428544521 4.0204439163 4.2293477058 128 5.0800000000 0.0045399363 0.0036821028 0.0055015511 0.0062215252 0.1126220000 0.0096630000 0.0457110000 0.0000250000 0.0002960000 0.0554660000 8166020 96830484 1768267776 3.1373357773 4.0202531815 4.2351298332 129 5.1200000000 0.0045370036 0.0036887299 0.0055015511 0.0061985820 0.1368750000 0.0076130000 0.0398420000 0.0002940000 0.0003430000 0.0872420000 8177934 96830484 1769910272 3.1333868504 4.0206036568 4.2417931557 130 5.1600000000 0.0044152057 0.0036943182 0.0055015511 0.0061938144 0.1137320000 0.0131850000 0.0453910000 0.0000280000 0.0003140000 0.0478480000 8200600 96830484 1769029632 3.1246411800 4.0203986168 4.2597942352 131 5.2000000000 0.0045606871 0.0037009317 0.0055015511 0.0062248603 0.1106810000 0.0081440000 0.0405070000 0.0002780000 0.0002520000 0.0588160000 8202274 96830484 1770799104 3.1212036610 4.0209698677 4.2639036179 132 5.2400000000 0.0045011132 0.0037069937 0.0055015511 0.0062368719 0.1107270000 0.0094440000 0.0440220000 0.0000260000 0.0002880000 0.0554430000 8203948 96830484 1770024960 3.1207258701 4.0206942558 4.2615728378 133 5.2800000000 0.0044290908 0.0037124230 0.0055015511 0.0062367300 0.1473750000 0.0096670000 0.0390700000 0.0002960000 0.0002670000 0.0923970000 8205622 96830484 1768484864 3.1103262901 4.0208992958 4.2806978226 134 5.3200000000 0.0049535483 0.0037216851 0.0055015511 0.0062692380 0.1052200000 0.0083750000 0.0380270000 0.0000160000 0.0001860000 0.0511660000 8207296 96830484 1770328064 3.1018130779 4.0237188339 4.2973408699 135 5.3600000000 0.0050981650 0.0037318812 0.0055015511 0.0062899256 0.1330010000 0.0095390000 0.0472910000 0.0002890000 0.0003410000 0.0740170000 8208970 96830484 1769156608 3.0986688137 4.0242047310 4.3013191223 136 5.4000000000 0.0052580792 0.0037431033 0.0055015511 0.0063266964 0.1003380000 0.0078510000 0.0360870000 0.0000080000 0.0000760000 0.0487370000 8210644 96830484 1770835968 3.0919291973 4.0243339539 4.3133592606 137 5.4400000000 0.0051940610 0.0037536942 0.0055015511 0.0063796535 0.1510430000 0.0100630000 0.0398570000 0.0002110000 0.0004690000 0.0940710000 8212318 96830484 1769537536 3.0865287781 4.0247116089 4.3226008415 138 5.4800000000 0.0052057235 0.0037642162 0.0055015511 0.0064223770 0.1083420000 0.0096860000 0.0390610000 0.0000230000 0.0002920000 0.0517670000 8213992 96830484 1768120320 3.0809540749 4.0238699913 4.3272929192 139 5.5200000000 0.0050517544 0.0037734790 0.0055015511 0.0064647223 0.1266950000 0.0076500000 0.0403590000 0.0001920000 0.0001690000 0.0705800000 8215666 96830484 1769910272 3.0748353004 4.0217118263 4.3324923515 140 5.5600000000 0.0050807847 0.0037828169 0.0055015511 0.0065367369 0.1138230000 0.0092150000 0.0450810000 0.0000250000 0.0003540000 0.0575510000 8217340 96830484 1769029632 3.0655672550 4.0224595070 4.3467688560 141 5.6000000000 0.0050909431 0.0037920944 0.0055015511 0.0065706000 0.1657300000 0.0076200000 0.0404520000 0.0003570000 0.0002700000 0.1094150000 8219014 96830484 1770770432 3.0601978302 4.0236749649 4.3522362709 142 5.6400000000 0.0051241852 0.0038014753 0.0055015511 0.0066050987 0.1052810000 0.0101200000 0.0336290000 0.0000080000 0.0000770000 0.0534480000 8220688 96830484 1769537536 3.0509636402 4.0237746239 4.3669538498 143 5.6800000000 0.0051526418 0.0038109241 0.0055015511 0.0066816118 0.1474650000 0.0092240000 0.0492200000 0.0002910000 0.0002690000 0.0801120000 8222362 96830484 1768120320 3.0457272530 4.0260248184 4.3769593239 144 5.7200000000 0.0052279229 0.0038207643 0.0055015511 0.0067254803 0.1117090000 0.0076600000 0.0421590000 0.0000250000 0.0003560000 0.0598220000 8224036 96830484 1769820160 3.0395171642 4.0277700424 4.3848295212 145 5.7600000000 0.0052101971 0.0038303466 0.0055015511 0.0067254994 0.1512130000 0.0092590000 0.0394860000 0.0002950000 0.0002660000 0.1002560000 8225710 96830484 1769009152 3.0339581966 4.0268373489 4.3915781975 146 5.8000000000 0.0052463310 0.0038400451 0.0055015511 0.0067167629 0.1062570000 0.0084110000 0.0408320000 0.0000240000 0.0003600000 0.0541190000 8227384 96830484 1770688512 3.0281167030 4.0269894600 4.4010472298 147 5.8400000000 0.0052832770 0.0038498631 0.0055015511 0.0067002743 0.1262000000 0.0095090000 0.0395130000 0.0003000000 0.0002650000 0.0683250000 8229058 96830484 1769517056 3.0179305077 4.0262370110 4.4219803810 148 5.8800000000 0.0053111040 0.0038597363 0.0055015511 0.0066797053 0.1319890000 0.0094790000 0.0526320000 0.0000250000 0.0013200000 0.0668670000 8230732 96830484 1768103936 3.0165171623 4.0261402130 4.4253592491 149 5.9200000000 0.0052792788 0.0038692634 0.0055015511 0.0066630867 0.1511610000 0.0076030000 0.0391990000 0.0002900000 0.0002630000 0.1020230000 8232406 96830484 1769926656 3.0121631622 4.0268230438 4.4364194870 150 5.9600000000 0.0053305435 0.0038790053 0.0055015511 0.0066447090 0.1061690000 0.0093380000 0.0396410000 0.0000270000 0.0002850000 0.0551880000 8234080 96830484 1768792064 3.0085997581 4.0266056061 4.4451336861 151 6.0000000000 0.0053739781 0.0038889058 0.0055015511 0.0066260883 0.1236000000 0.0078380000 0.0377640000 0.0000810000 0.0000700000 0.0696140000 8235754 96830484 1770434560 3.0053029060 4.0271229744 4.4548649788 152 6.0400000000 0.0053502726 0.0038985200 0.0055015511 0.0066125780 0.1330030000 0.0098500000 0.0643700000 0.0000300000 0.0003220000 0.0567390000 8237428 96830484 1769263104 3.0021977425 4.0284290314 4.4656472206 153 6.0800000000 0.0054323329 0.0039085450 0.0055015511 0.0066018535 0.1551190000 0.0078480000 0.0378650000 0.0005400000 0.0002750000 0.1068910000 8239102 96830484 1770942464 2.9985551834 4.0274720192 4.4742350578 154 6.1200000000 0.0053986544 0.0039182210 0.0055015511 0.0066206331 0.1119060000 0.0140010000 0.0327120000 0.0000110000 0.0001130000 0.0569390000 8240776 96830484 1769897984 2.9940745831 4.0267801285 4.4865512848 155 6.1600000000 0.0053828186 0.0039276700 0.0055015511 0.0066839783 0.1491250000 0.0095920000 0.0531090000 0.0006140000 0.0002760000 0.0838000000 8242450 96830484 1768357888 2.9924225807 4.0258541107 4.4941563606 156 6.2000000000 0.0053906296 0.0039370480 0.0055015511 0.0067957141 0.1243030000 0.0077070000 0.0461090000 0.0000250000 0.0003630000 0.0614930000 8244124 96830484 1770070016 2.9877223969 4.0269780159 4.5091190338 157 6.2400000000 0.0054095751 0.0039464271 0.0055015511 0.0068865812 0.1892990000 0.0093590000 0.0485550000 0.0003080000 0.0003500000 0.1216070000 8245798 96830484 1769263104 2.9854676723 4.0275936127 4.5200443268 158 6.2800000000 0.0053982022 0.0039556156 0.0055015511 0.0069633910 0.1107060000 0.0084030000 0.0413650000 0.0000250000 0.0003860000 0.0574750000 8247472 96830484 1770942464 2.9824633598 4.0278801918 4.5365538597 159 6.3200000000 0.0054318053 0.0039648998 0.0055015511 0.0069938511 0.1305770000 0.0092340000 0.0393550000 0.0003630000 0.0002770000 0.0795820000 8249146 96830484 1770151936 2.9819014072 4.0272908211 4.5442690849 160 6.3600000000 0.0054244986 0.0039740223 0.0055015511 0.0070315159 0.1100470000 0.0095380000 0.0394000000 0.0000270000 0.0002910000 0.0588670000 8250820 96830484 1768755200 2.9807677269 4.0286664963 4.5597171783 161 6.4000000000 0.0055277729 0.0039836729 0.0055277729 0.0070167934 0.1659740000 0.0078070000 0.0401180000 0.0002900000 0.0003360000 0.1089580000 8252494 96830484 1770434560 2.9808900356 4.0291829109 4.5705785751 162 6.4400000000 0.0056116399 0.0039937221 0.0056116399 0.0069972159 0.1109260000 0.0101970000 0.0401560000 0.0000280000 0.0003070000 0.0584500000 8254168 96830484 1769283584 2.9807767868 4.0274944305 4.5817613602 163 6.4800000000 0.0055531142 0.0040032889 0.0056116399 0.0069804384 0.1104890000 0.0077500000 0.0314500000 0.0000760000 0.0000690000 0.0693940000 8255842 96830484 1770962944 2.9798049927 4.0287609100 4.5947580338 164 6.5200000000 0.0055600577 0.0040127814 0.0056116399 0.0069639819 0.1275580000 0.0093820000 0.0464180000 0.0000250000 0.0002790000 0.0685970000 8257516 96830484 1769791488 2.9796931744 4.0301356316 4.6065859795 165 6.5600000000 0.0056226337 0.0040225381 0.0056226337 0.0069544809 0.1687920000 0.0095690000 0.0398330000 0.0002870000 0.0002600000 0.1151230000 8259190 96830484 1768394752 2.9786641598 4.0314221382 4.6245770454 166 6.6000000000 0.0056311330 0.0040322284 0.0056311330 0.0069715005 0.1092200000 0.0077670000 0.0378600000 0.0000180000 0.0001870000 0.0596470000 8260864 96830484 1770070016 2.9794433117 4.0321297646 4.6358819008 167 6.6400000000 0.0055969302 0.0040415979 0.0056311330 0.0069788229 0.1304540000 0.0093940000 0.0405960000 0.0002970000 0.0002710000 0.0780310000 8262538 96830484 1769390080 2.9804966450 4.0340008736 4.6462559700 168 6.6800000000 0.0056347032 0.0040510806 0.0056347032 0.0069810639 0.1092830000 0.0076440000 0.0378610000 0.0000070000 0.0000920000 0.0618600000 8264212 96830484 1771073536 2.9810054302 4.0342464447 4.6586923599 169 6.7200000000 0.0056538559 0.0040605645 0.0056538559 0.0069675723 0.1812200000 0.0092900000 0.0461650000 0.0004430000 0.0002940000 0.1154520000 8265886 96830484 1770262528 2.9810667038 4.0320744514 4.6730980873 170 6.7600000000 0.0056862906 0.0040701276 0.0056862906 0.0069596586 0.1121250000 0.0099470000 0.0381020000 0.0000160000 0.0002360000 0.0609870000 8267560 96830484 1768755200 2.9791903496 4.0341777802 4.6901607513 171 6.8000000000 0.0056537953 0.0040793888 0.0056862906 0.0069529215 0.1482900000 0.0076820000 0.0451050000 0.0003820000 0.0002780000 0.0888830000 8269234 96830484 1770450944 2.9802505970 4.0369043350 4.6993718147 172 6.8400000000 0.0057232729 0.0040889463 0.0057232729 0.0069346813 0.1286630000 0.0094020000 0.0416670000 0.0001000000 0.0002860000 0.0682010000 8270908 96830484 1769517056 2.9807760715 4.0382065773 4.7124075890 173 6.8800000000 0.0057155616 0.0040983487 0.0057232729 0.0069154841 0.1744110000 0.0093150000 0.0599690000 0.0017970000 0.0002940000 0.1010800000 8272582 96830484 1767993344 2.9804041386 4.0398097038 4.7263331413 174 6.9200000000 0.0057898900 0.0041080702 0.0057898900 0.0068960730 0.1063510000 0.0075950000 0.0384820000 0.0000250000 0.0003600000 0.0579360000 8274256 96830484 1769799680 2.9793498516 4.0416283607 4.7389860153 175 6.9600000000 0.0057721375 0.0041175791 0.0057898900 0.0068762946 0.1294780000 0.0093030000 0.0388420000 0.0003700000 0.0002780000 0.0787860000 8275930 96830484 1768628224 2.9798245430 4.0425558090 4.7508134842 176 7.0000000000 0.0057965261 0.0041271186 0.0057965261 0.0068605514 0.1069890000 0.0076720000 0.0349790000 0.0000180000 0.0002000000 0.0621790000 8277604 96830484 1770405888 2.9785537720 4.0429134369 4.7653565407 177 7.0400000000 0.0058230069 0.0041366999 0.0058230069 0.0068711309 0.1678300000 0.0096250000 0.0388270000 0.0003650000 0.0002750000 0.1120830000 8279278 96830484 1769644032 2.9796037674 4.0405187607 4.7724456787 178 7.0800000000 0.0058713625 0.0041464452 0.0058713625 0.0068569578 0.1103110000 0.0100640000 0.0376950000 0.0000080000 0.0000840000 0.0601390000 8280952 96830484 1767993344 2.9808619022 4.0401058197 4.7797164917 179 7.1200000000 0.0057756775 0.0041555471 0.0058713625 0.0068429434 0.1098440000 0.0075200000 0.0363170000 0.0002620000 0.0001850000 0.0636330000 8282626 96830484 1769799680 2.9810593128 4.0424866676 4.7933707237 180 7.1600000000 0.0058105090 0.0041647413 0.0058713625 0.0068246482 0.1094030000 0.0095240000 0.0391880000 0.0000270000 0.0003130000 0.0583540000 8284300 96830484 1768628224 2.9818563461 4.0449447632 4.8064174652 181 7.2000000000 0.0058070384 0.0041738148 0.0058713625 0.0068099252 0.1510110000 0.0077690000 0.0316610000 0.0000870000 0.0000760000 0.1093090000 8285974 96830484 1770307584 2.9840016365 4.0455956459 4.8172302246 182 7.2400000000 0.0058292793 0.0041829107 0.0058713625 0.0067930637 0.1069620000 0.0098120000 0.0346480000 0.0000190000 0.0005200000 0.0600140000 8287648 96830484 1769263104 2.9836800098 4.0458707809 4.8312015533 183 7.2800000000 0.0058379467 0.0041919546 0.0058713625 0.0067779427 0.1295760000 0.0080370000 0.0407870000 0.0003870000 0.0002770000 0.0778130000 8289322 96830484 1770897408 2.9819910526 4.0464487076 4.8473787308 184 7.3200000000 0.0058432720 0.0042009292 0.0058713625 0.0067600124 0.1282950000 0.0092890000 0.0440360000 0.0000290000 0.0003070000 0.0698390000 8290996 96830484 1770151936 2.9841806889 4.0460124016 4.8579874039 185 7.3600000000 0.0058360742 0.0042097678 0.0058713625 0.0067443456 0.1769760000 0.0097490000 0.0424660000 0.0003140000 0.0003540000 0.1139880000 8292670 96830484 1768628224 2.9857268333 4.0463123322 4.8733577728 186 7.4000000000 0.0057869474 0.0042182473 0.0058713625 0.0067319225 0.1120090000 0.0082750000 0.0385100000 0.0000260000 0.0003010000 0.0606520000 8294344 96830484 1770459136 2.9855818748 4.0459403992 4.8914837837 187 7.4400000000 0.0057564480 0.0042264729 0.0058713625 0.0067254993 0.1482140000 0.0095150000 0.0495540000 0.0003090000 0.0002750000 0.0786430000 8296018 96830484 1769525248 2.9887070656 4.0459337234 4.8998847008 188 7.4800000000 0.0057723727 0.0042346958 0.0058713625 0.0067339833 0.1513240000 0.0098110000 0.0689120000 0.0000260000 0.0003770000 0.0701660000 8297692 96830484 1768001536 2.9910883904 4.0494847298 4.9153275490 189 7.5200000000 0.0057317023 0.0042426165 0.0058713625 0.0067178576 0.2047460000 0.0075390000 0.0503870000 0.0003800000 0.0002900000 0.1408360000 8299366 96830484 1769635840 2.9932467937 4.0521445274 4.9329366684 190 7.5600000000 0.0058005541 0.0042508161 0.0058713625 0.0067078205 0.1105470000 0.0098740000 0.0375330000 0.0000080000 0.0000810000 0.0610800000 8301040 96830484 1768636416 2.9955132008 4.0511283875 4.9477171898 191 7.6000000000 0.0058035296 0.0042589455 0.0058713625 0.0066961314 0.1280250000 0.0074820000 0.0384680000 0.0002100000 0.0001800000 0.0756790000 8302714 96830484 1770405888 2.9968194962 4.0533919334 4.9640216827 192 7.6400000000 0.0059071253 0.0042675298 0.0059071253 0.0066889306 0.1289340000 0.0095390000 0.0411000000 0.0000260000 0.0002990000 0.0701450000 8304388 96830484 1769525248 3.0004868507 4.0595726967 4.9791088104 193 7.6800000000 0.0059852800 0.0042764301 0.0059852800 0.0066903627 0.1898330000 0.0095300000 0.0675670000 0.0003910000 0.0002690000 0.1076610000 8306062 96830484 1768001536 3.0005056858 4.0601115227 4.9973998070 194 7.7200000000 0.0060913847 0.0042857855 0.0060913847 0.0066877133 0.1100030000 0.0078330000 0.0381510000 0.0000190000 0.0001960000 0.0617720000 8307736 96830484 1769697280 3.0002415180 4.0561037064 5.0137042999 195 7.7600000000 0.0060795103 0.0042949841 0.0060913847 0.0066908814 0.1278710000 0.0094830000 0.0385060000 0.0003000000 0.0002730000 0.0717820000 8309410 96830484 1768636416 3.0014679432 4.0556755066 5.0267329216 196 7.8000000000 0.0060571237 0.0043039746 0.0060913847 0.0067277218 0.1287940000 0.0075330000 0.0399020000 0.0000170000 0.0002030000 0.0712250000 8311084 96830484 1770397696 3.0033404827 4.0593228340 5.0434970856 197 7.8400000000 0.0061425329 0.0043133074 0.0061425329 0.0067533313 0.2006050000 0.0094510000 0.0475800000 0.0003140000 0.0002840000 0.1320370000 8312758 96830484 1769525248 3.0051894188 4.0627937317 5.0555682182 198 7.8800000000 0.0060075731 0.0043218643 0.0061425329 0.0067712935 0.1128430000 0.0099230000 0.0366590000 0.0000270000 0.0003090000 0.0638180000 8314432 96830484 1768001536 3.0063166618 4.0664410591 5.0721044540 199 7.9200000000 0.0060479632 0.0043305381 0.0061425329 0.0067644958 0.1287490000 0.0079250000 0.0385450000 0.0000820000 0.0000740000 0.0784590000 8316106 96830484 1769697280 3.0083861351 4.0674052238 5.0879182816 200 7.9600000000 0.0062328703 0.0043400498 0.0062328703 0.0067551367 0.1098210000 0.0092960000 0.0357910000 0.0000180000 0.0002030000 0.0612120000 8317780 96830484 1768636416 3.0085654259 4.0659980774 5.1019802094 201 8.0000000000 0.0061905170 0.0043492561 0.0062328703 0.0067704445 0.1590320000 0.0081230000 0.0370350000 0.0000810000 0.0000710000 0.1116380000 8319454 96830484 1770524672 3.0092012882 4.0664062500 5.1207022667 202 8.0400000000 0.0061700302 0.0043582698 0.0062328703 0.0067875518 0.1195420000 0.0139160000 0.0402470000 0.0000110000 0.0001160000 0.0631200000 8321128 96830484 1769525248 3.0120127201 4.0673093796 5.1309838295 203 8.0800000000 0.0062622698 0.0043676492 0.0062622698 0.0067970822 0.1469000000 0.0096600000 0.0422070000 0.0003750000 0.0002850000 0.0856820000 8322802 96830484 1767985152 3.0143148899 4.0690894127 5.1484227180 204 8.1200000000 0.0061317701 0.0043762968 0.0062622698 0.0067892741 0.1300910000 0.0079110000 0.0413640000 0.0000290000 0.0006370000 0.0754490000 8324476 96830484 1769697280 3.0162017345 4.0684967041 5.1607022285 205 8.1600000000 0.0062015634 0.0043852005 0.0062622698 0.0067814093 0.2004240000 0.0094440000 0.0441780000 0.0003650000 0.0002760000 0.1357460000 8326150 96830484 1768636416 3.0191206932 4.0674786568 5.1724720001 206 8.1999999990 0.0062135546 0.0043940761 0.0062622698 0.0067721491 0.1143720000 0.0081630000 0.0451200000 0.0000270000 0.0003210000 0.0585490000 8327824 96830484 1770295296 3.0224809647 4.0675692558 5.1860198975 207 8.2400000000 0.0061982842 0.0044027920 0.0062622698 0.0067649154 0.1272420000 0.0099950000 0.0378650000 0.0002890000 0.0003420000 0.0749410000 8329498 96830484 1769398272 3.0270125866 4.0703992844 5.1996154785 208 8.2799999990 0.0061652721 0.0044112655 0.0062622698 0.0067522144 0.1304020000 0.0081790000 0.0467570000 0.0000290000 0.0003550000 0.0727730000 8331172 96830484 1771098112 3.0312306881 4.0725245476 5.2122244835 209 8.3200000000 0.0062739123 0.0044201777 0.0062739123 0.0067495938 0.1729390000 0.0095930000 0.0336560000 0.0001940000 0.0001740000 0.1213380000 8332846 96830484 1770143744 3.0357863903 4.0744037628 5.2253375053 210 8.3599999990 0.0062792581 0.0044290304 0.0062792581 0.0067735264 0.1161230000 0.0109240000 0.0405040000 0.0000260000 0.0006150000 0.0618200000 8334520 96830484 1768636416 3.0414152145 4.0752496719 5.2363462448 211 8.4000000000 0.0063404832 0.0044380895 0.0063404832 0.0067932688 0.1263760000 0.0079070000 0.0373150000 0.0002950000 0.0003290000 0.0746910000 8336194 96830484 1770184704 3.0464706421 4.0734324455 5.2501068115 212 8.4399999990 0.0063815415 0.0044472567 0.0063815415 0.0067794063 0.1305140000 0.0101410000 0.0388220000 0.0000270000 0.0002900000 0.0789600000 8337868 96830484 1769271296 3.0537533760 4.0763864517 5.2617316246 213 8.4800000000 0.0064212461 0.0044565242 0.0064212461 0.0067810206 0.1883120000 0.0081440000 0.0419310000 0.0003010000 0.0002760000 0.1333040000 8339542 96830484 1770844160 3.0601816177 4.0803155899 5.2762241364 214 8.5200000000 0.0064659980 0.0044659143 0.0064659980 0.0068438847 0.1122380000 0.0097740000 0.0370560000 0.0000180000 0.0007520000 0.0623940000 8341216 96830484 1769652224 3.0672376156 4.0806236267 5.2883591652 215 8.5600000000 0.0064945477 0.0044753498 0.0064945477 0.0068533298 0.1265100000 0.0097370000 0.0376000000 0.0003050000 0.0002760000 0.0751760000 8342890 96830484 1768255488 3.0751185417 4.0799493790 5.2988648415 216 8.6000000000 0.0065747057 0.0044850691 0.0065747057 0.0068385490 0.1273140000 0.0079530000 0.0375350000 0.0000080000 0.0000810000 0.0710690000 8344564 96830484 1769889792 3.0844266415 4.0844678879 5.3104658127 217 8.6400000000 0.0066987830 0.0044952705 0.0066987830 0.0068624458 0.1901710000 0.0096890000 0.0574270000 0.0003000000 0.0002790000 0.1147760000 8346238 96830484 1768910848 3.0934202671 4.0874967575 5.3273324966 218 8.6800000000 0.0065565794 0.0045047260 0.0066987830 0.0069130553 0.1119060000 0.0086430000 0.0364040000 0.0000090000 0.0000770000 0.0639860000 8347912 96830484 1770553344 3.1018471718 4.0872349739 5.3364033699 219 8.7200000000 0.0067064166 0.0045147794 0.0067064166 0.0069131207 0.1275860000 0.0098320000 0.0368830000 0.0002870000 0.0002610000 0.0759190000 8349586 96830484 1769398272 3.1120157242 4.0900926590 5.3467345238 220 8.7600000000 0.0068453876 0.0045253731 0.0068453876 0.0069163438 0.1277540000 0.0081470000 0.0376800000 0.0000240000 0.0001980000 0.0720350000 8351260 96830484 1771098112 3.1226029396 4.0951023102 5.3584980965 221 8.8000000000 0.0067417342 0.0045354019 0.0068453876 0.0069537746 0.2240720000 0.0099630000 0.0520210000 0.0002960000 0.0003480000 0.1494650000 8352934 96830484 1770033152 3.1322591305 4.0962243080 5.3702726364 222 8.8400000000 0.0069097932 0.0045460973 0.0069097932 0.0069622956 0.1244120000 0.0104060000 0.0326290000 0.0000180000 0.0006440000 0.0719500000 8354608 96830484 1768620032 3.1415610313 4.0980634689 5.3848152161 223 8.8800000000 0.0069119441 0.0045567065 0.0069119441 0.0069630541 0.1490170000 0.0080030000 0.0404210000 0.0005030000 0.0003340000 0.0895590000 8356282 96830484 1770315776 3.1522185802 4.1012015343 5.3941946030 224 8.9200000000 0.0068558217 0.0045669704 0.0069119441 0.0069689221 0.1502130000 0.0101740000 0.0601990000 0.0000280000 0.0003870000 0.0725270000 8357956 96830484 1769525248 3.1629397869 4.1042351723 5.4048171043 225 8.9600000000 0.0068885642 0.0045772886 0.0069119441 0.0069662651 0.2183140000 0.0100470000 0.0543860000 0.0003590000 0.0002730000 0.1507640000 8359630 96830484 1767911424 3.1734106541 4.1069216728 5.4128561020 226 9.0000000000 0.0072183600 0.0045889748 0.0072183600 0.0069526647 0.1198570000 0.0094410000 0.0379060000 0.0000260000 0.0003560000 0.0675550000 8361304 96830484 1769680896 3.1838562489 4.1111717224 5.4244890213 227 9.0400000000 0.0070862393 0.0045999759 0.0072183600 0.0069388859 0.1305800000 0.0104430000 0.0316790000 0.0000690000 0.0000630000 0.0859450000 8362978 96830484 1768529920 3.1958312988 4.1170139313 5.4328708649 228 9.0800000000 0.0072635086 0.0046116581 0.0072635086 0.0069501916 0.1282160000 0.0083060000 0.0373260000 0.0000060000 0.0003540000 0.0791290000 8364652 96830484 1770143744 3.2073814869 4.1231055260 5.4463658333 229 9.1200000000 0.0072230431 0.0046230615 0.0072635086 0.0070095292 0.1837970000 0.0104610000 0.0392720000 0.0002970000 0.0003510000 0.1210600000 8366326 96830484 1769009152 3.2179586887 4.1271810532 5.4538083076 230 9.1600000000 0.0072514252 0.0046344892 0.0072635086 0.0071108724 0.1140990000 0.0092080000 0.0370070000 0.0000190000 0.0002060000 0.0652500000 8368000 96830484 1770819584 3.2288503647 4.1312589645 5.4606761932 231 9.2000000000 0.0071084034 0.0046451988 0.0072635086 0.0073237661 0.1268430000 0.0105270000 0.0318280000 0.0001930000 0.0001720000 0.0817030000 8369674 96830484 1769644032 3.2381000519 4.1320743561 5.4681119919 232 9.2400000000 0.0072278720 0.0046563310 0.0072635086 0.0074885108 0.1666200000 0.0104560000 0.0467350000 0.0000960000 0.0002880000 0.0967910000 8371348 96830484 1768267776 3.2476196289 4.1351494789 5.4764685631 233 9.2800000000 0.0071786158 0.0046671563 0.0072635086 0.0076322463 0.1853080000 0.0087230000 0.0360920000 0.0001960000 0.0001740000 0.1279970000 8373022 96830484 1769943040 3.2572281361 4.1379003525 5.4837727547 234 9.3200000000 0.0072247316 0.0046780861 0.0072635086 0.0077361722 0.1301890000 0.0111020000 0.0398420000 0.0000250000 0.0002880000 0.0675800000 8374696 96830484 1768738816 3.2671837807 4.1416583061 5.4906706810 235 9.3600000000 0.0071897143 0.0046887738 0.0072635086 0.0078133224 0.1721620000 0.0087070000 0.0542350000 0.0003170000 0.0003420000 0.1061040000 8376370 96830484 1770434560 3.2772872448 4.1448612213 5.4979667664 236 9.4000000000 0.0073412992 0.0047000134 0.0073412992 0.0078743775 0.1307100000 0.0108090000 0.0443650000 0.0000280000 0.0002960000 0.0727050000 8378044 96830484 1769263104 3.2867586613 4.1478252411 5.5063419342 237 9.4400000000 0.0072533204 0.0047107868 0.0073412992 0.0079027232 0.1546960000 0.0090210000 0.0312820000 0.0002030000 0.0001780000 0.1115590000 8379718 96830484 1770942464 3.2967314720 4.1517887115 5.5128068924 238 9.4800000000 0.0074419929 0.0047222625 0.0074419929 0.0079247261 0.1215480000 0.0132460000 0.0410900000 0.0000260000 0.0003030000 0.0643630000 8381392 96830484 1769897984 3.3076195717 4.1580171585 5.5205988884 239 9.5200000000 0.0073686484 0.0047333352 0.0074419929 0.0079684690 0.1286860000 0.0107450000 0.0392940000 0.0003090000 0.0003490000 0.0754560000 8383066 96830484 1768411136 3.3183436394 4.1631016731 5.5281271935 240 9.5600000000 0.0074091824 0.0047444846 0.0074419929 0.0080224962 0.1266000000 0.0088750000 0.0335980000 0.0000070000 0.0000720000 0.0713230000 8384740 96830484 1770196992 3.3285520077 4.1679220200 5.5366945267 241 9.6000000000 0.0073671583 0.0047553670 0.0074419929 0.0080772365 0.2048330000 0.0106410000 0.0659020000 0.0007350000 0.0002810000 0.1141740000 8386414 96830484 1769246720 3.3378491402 4.1686501503 5.5454206467 242 9.6400000000 0.0072513977 0.0047656812 0.0074419929 0.0080980232 0.1300840000 0.0095800000 0.0450430000 0.0000250000 0.0003140000 0.0632980000 8388088 96830484 1770962944 3.3475980759 4.1710453033 5.5539622307 243 9.6800000000 0.0072520971 0.0047759134 0.0074419929 0.0081123779 0.1331270000 0.0114320000 0.0500800000 0.0005060000 0.0002840000 0.0682770000 8389762 96830484 1769918464 3.3585801125 4.1770195961 5.5617213249 244 9.7200000000 0.0072627170 0.0047861052 0.0074419929 0.0081593651 0.1268030000 0.0111290000 0.0458660000 0.0000300000 0.0003170000 0.0634970000 8391436 96830484 1768411136 3.3698759079 4.1834473610 5.5698981285 245 9.7600000000 0.0071155876 0.0047956133 0.0074419929 0.0082226075 0.1710470000 0.0095760000 0.0442480000 0.0003830000 0.0002740000 0.1105490000 8393110 96830484 1770033152 3.3801040649 4.1858243942 5.5777435303 246 9.8000000000 0.0071129859 0.0048050335 0.0074419929 0.0082424165 0.1162820000 0.0112000000 0.0381170000 0.0000260000 0.0003780000 0.0638400000 8394784 96830484 1769009152 3.3904457092 4.1886858940 5.5867166519 247 9.8400000000 0.0071934848 0.0048147033 0.0074419929 0.0082475664 0.1308160000 0.0090350000 0.0426570000 0.0003170000 0.0002740000 0.0758060000 8396458 96830484 1770516480 3.3999631405 4.1890296936 5.5966963768 248 9.8800000000 0.0071915998 0.0048242876 0.0074419929 0.0082327684 0.1264460000 0.0107810000 0.0455300000 0.0000270000 0.0003080000 0.0657540000 8398132 96830484 1769537536 3.4092972279 4.1907863617 5.6052098274 249 9.9200000000 0.0071689170 0.0048337038 0.0074419929 0.0082173493 0.1815210000 0.0105740000 0.0423170000 0.0003100000 0.0003500000 0.1149590000 8399806 96830484 1768140800 3.4193298817 4.1930556297 5.6128511429 250 9.9600000000 0.0071839117 0.0048431046 0.0074419929 0.0082011724 0.1133740000 0.0094830000 0.0377380000 0.0000190000 0.0002560000 0.0632850000 8401480 96830484 1769799680 3.4290142059 4.1952667236 5.6217961311 251 10.0000000000 0.0072737900 0.0048527886 0.0074419929 0.0081850175 0.1478710000 0.0102760000 0.0478440000 0.0003180000 0.0003620000 0.0841040000 8403154 96830484 1768910848 3.4391326904 4.1984300613 5.6306056976 252 10.0400000000 0.0072200862 0.0048621827 0.0074419929 0.0081718363 0.1475440000 0.0087540000 0.0498840000 0.0000290000 0.0003760000 0.0764500000 8404828 96830484 1770659840 3.4476654530 4.1974697113 5.6410489082 253 10.0800000000 0.0071694297 0.0048713022 0.0074419929 0.0081565577 0.2298070000 0.0105640000 0.1010970000 0.0003760000 0.0002790000 0.1061980000 8406502 96830484 1769762816 3.4552130699 4.1943402290 5.6508669853 254 10.1200000000 0.0072454321 0.0048806492 0.0074419929 0.0081768545 0.1293000000 0.0112510000 0.0453430000 0.0000280000 0.0003180000 0.0628280000 8408176 96830484 1768255488 3.4650044441 4.1982121468 5.6597628593 255 10.1600000000 0.0072444421 0.0048899190 0.0074419929 0.0081920353 0.1298010000 0.0092310000 0.0423950000 0.0003770000 0.0010600000 0.0699100000 8409850 96830484 1770061824 3.4758853912 4.2050776482 5.6686735153 256 10.2000000000 0.0072643212 0.0048991940 0.0074419929 0.0081795043 0.1114210000 0.0112070000 0.0350550000 0.0000080000 0.0000720000 0.0623970000 8411524 96830484 1769017344 3.4870820045 4.2099967003 5.6771268845 257 10.2400000000 0.0072170347 0.0049082128 0.0074419929 0.0081652195 0.1678390000 0.0088860000 0.0427790000 0.0003020000 0.0003600000 0.1115570000 8433678 96830484 1770590208 3.4964504242 4.2096548080 5.6859345436 258 10.2800000000 0.0072307624 0.0049172149 0.0074419929 0.0081493629 0.1295210000 0.0110630000 0.0523580000 0.0000990000 0.0003160000 0.0619720000 8477336 96830484 1769799680 3.5068004131 4.2147393227 5.6947603226 259 10.3200000000 0.0072531835 0.0049262341 0.0074419929 0.0081435425 0.1293050000 0.0110430000 0.0456180000 0.0003240000 0.0003470000 0.0691920000 8479010 96830484 1768402944 3.5172820091 4.2186408043 5.7011680603 260 10.3600000000 0.0072594336 0.0049352080 0.0074419929 0.0081496000 0.1263410000 0.0092880000 0.0419860000 0.0000250000 0.0002950000 0.0617270000 8480684 96830484 1770143744 3.5272617340 4.2202429771 5.7094039917 261 10.4000000000 0.0071995272 0.0049438835 0.0074419929 0.0081493002 0.1710910000 0.0111820000 0.0426320000 0.0003200000 0.0002740000 0.1111080000 8482358 96830484 1769271296 3.5368244648 4.2197060585 5.7162361145 262 10.4400000000 0.0072190091 0.0049525672 0.0074419929 0.0081369262 0.1281520000 0.0091070000 0.0440510000 0.0000290000 0.0003050000 0.0649100000 8484032 96830484 1771061248 3.5463531017 4.2199959755 5.7234449387 263 10.4800000000 0.0071899486 0.0049610743 0.0074419929 0.0081234539 0.1700570000 0.0102170000 0.0569180000 0.0003130000 0.0002720000 0.0945420000 8485706 96830484 1770176512 3.5571446419 4.2214131355 5.7290558815 264 10.5200000000 0.0071815168 0.0049694851 0.0074419929 0.0081132052 0.2088250000 0.0101870000 0.1153450000 0.0000260000 0.0003100000 0.0745210000 8487380 96830484 1769037824 3.5674560070 4.2210521698 5.7350697517 265 10.5600000000 0.0072301202 0.0049780158 0.0074419929 0.0080980771 0.1971360000 0.0087000000 0.0526670000 0.0003720000 0.0002720000 0.1321680000 8489054 96830484 1770717184 3.5787055492 4.2229838371 5.7412343025 266 10.6000000000 0.0071409997 0.0049861473 0.0074419929 0.0080872630 0.1226070000 0.0121440000 0.0435670000 0.0000300000 0.0003150000 0.0635720000 8490728 96830484 1769652224 3.5906906128 4.2252111435 5.7455463409 267 10.6400000000 0.0071661584 0.0049943122 0.0074419929 0.0080835863 0.1675580000 0.0101240000 0.0552060000 0.0003220000 0.0005280000 0.0926040000 8492402 96830484 1768128512 3.6019568443 4.2243156433 5.7495784760 268 10.6800000000 0.0071932431 0.0050025171 0.0074419929 0.0080768128 0.1495830000 0.0084810000 0.0649970000 0.0000240000 0.0003170000 0.0676010000 8494076 96830484 1769824256 3.6132988930 4.2237806320 5.7556233406 269 10.7200000000 0.0071482142 0.0050104937 0.0074419929 0.0080658521 0.2245540000 0.0109560000 0.0788770000 0.0000600000 0.0000550000 0.1201610000 8495750 96830484 1768800256 3.6251964569 4.2235808372 5.7579751015 270 10.7600000000 0.0071400967 0.0050183811 0.0074419929 0.0080565736 0.1132930000 0.0087450000 0.0442390000 0.0000270000 0.0003790000 0.0569870000 8497424 96830484 1770442752 3.6505968571 4.2283124924 5.7682948112 271 10.8000000000 0.0071303020 0.0050261742 0.0074419929 0.0080735814 0.1278560000 0.0108340000 0.0428580000 0.0009530000 0.0016330000 0.0664020000 8499098 96830484 1769398272 3.6649234295 4.2320523262 5.7716302872 272 10.8400000000 0.0071498575 0.0050339818 0.0074419929 0.0081357162 0.1120400000 0.0090300000 0.0444950000 0.0000290000 0.0003070000 0.0552200000 8500772 96830484 1770905600 3.6768729687 4.2302017212 5.7751474380 273 10.8800000000 0.0071553937 0.0050417526 0.0074419929 0.0081441106 0.1668550000 0.0109930000 0.0460100000 0.0003140000 0.0002780000 0.1053940000 8502446 96830484 1769906176 3.6894824505 4.2309336662 5.7796964645 274 10.9200000000 0.0071847606 0.0050495738 0.0074419929 0.0081529597 0.1272610000 0.0105270000 0.0445120000 0.0000900000 0.0003000000 0.0610140000 8504120 96830484 1768382464 3.7027606964 4.2321753502 5.7833747864 275 10.9600000000 0.0071675256 0.0050572754 0.0074419929 0.0081585821 0.1523920000 0.0082930000 0.0697350000 0.0003100000 0.0002830000 0.0707020000 8505794 96830484 1770078208 3.7156510353 4.2321186066 5.7861371040 276 11.0000000000 0.0071881157 0.0050649959 0.0074419929 0.0081557804 0.1266960000 0.0099900000 0.0444420000 0.0000240000 0.0003650000 0.0642350000 8507468 96830484 1769160704 3.7291152477 4.2340230942 5.7899084091 277 11.0400000000 0.0072061722 0.0050727257 0.0074419929 0.0081613577 0.1820060000 0.0083060000 0.0508270000 0.0003120000 0.0002750000 0.1192840000 8509142 96830484 1770934272 3.7426838875 4.2355213165 5.7932553291 278 11.0800000000 0.0072293654 0.0050804834 0.0074419929 0.0081672050 0.1155800000 0.0146120000 0.0437020000 0.0000300000 0.0003860000 0.0538730000 8510816 96830484 1770033152 3.7562696934 4.2372851372 5.7966260910 279 11.1200000000 0.0072107618 0.0050881188 0.0074419929 0.0081765392 0.1274150000 0.0101360000 0.0462670000 0.0003120000 0.0004870000 0.0637840000 8512490 96830484 1769037824 3.7702217102 4.2390351295 5.8006215096 280 11.1600000000 0.0072117136 0.0050957031 0.0074419929 0.0081848066 0.1105190000 0.0087120000 0.0445880000 0.0000280000 0.0005120000 0.0536800000 8514164 96830484 1770717184 3.7842233181 4.2415375710 5.8037843704 281 11.2000000000 0.0072458065 0.0051033547 0.0074419929 0.0081911724 0.1577890000 0.0105170000 0.0464640000 0.0003790000 0.0002710000 0.0972190000 8515838 96830484 1769525248 3.7973754406 4.2424178123 5.8063907623 282 11.2400000000 0.0072158491 0.0051108458 0.0074419929 0.0081865326 0.1181810000 0.0129590000 0.0460280000 0.0000290000 0.0003210000 0.0549220000 8517512 96830484 1768148992 3.8092210293 4.2414021492 5.8110079765 283 11.2800000000 0.0072045014 0.0051182439 0.0074419929 0.0081722249 0.1277830000 0.0083810000 0.0441320000 0.0003800000 0.0002760000 0.0661570000 8519186 96830484 1769807872 3.8215155602 4.2427053452 5.8134932518 284 11.3200000000 0.0072371671 0.0051257049 0.0074419929 0.0081613399 0.1278250000 0.0096730000 0.0436630000 0.0000280000 0.0003070000 0.0614940000 8520860 96830484 1768656896 3.8341059685 4.2448267937 5.8188529015 285 11.3600000000 0.0073399986 0.0051334744 0.0074419929 0.0081585671 0.1867490000 0.0079590000 0.0657370000 0.0003220000 0.0003480000 0.0961950000 8522534 96830484 1770414080 3.8457179070 4.2460341454 5.8229842186 286 11.4000000000 0.0072419588 0.0051408467 0.0074419929 0.0081504518 0.1129590000 0.0102500000 0.0452110000 0.0000290000 0.0003090000 0.0540460000 8524208 96830484 1769541632 3.8562197685 4.2458934784 5.8269877434 287 11.4400000000 0.0072880541 0.0051483282 0.0074419929 0.0081362742 0.1240880000 0.0085100000 0.0427140000 0.0003750000 0.0002730000 0.0617820000 8525882 96830484 1771208704 3.8657524586 4.2455530167 5.8311848640 288 11.4800000000 0.0072166361 0.0051555099 0.0074419929 0.0081229825 0.1114650000 0.0103190000 0.0459760000 0.0000270000 0.0003920000 0.0517200000 8527556 96830484 1770434560 3.8745987415 4.2453618050 5.8351273537 289 11.5200000000 0.0072731958 0.0051628375 0.0074419929 0.0081102802 0.1552350000 0.0105800000 0.0463750000 0.0003810000 0.0002790000 0.0945390000 8529230 96830484 1769017344 3.8831486702 4.2452931404 5.8416900635 290 11.5600000000 0.0072817197 0.0051701440 0.0074419929 0.0081020250 0.1598360000 0.0089580000 0.0868250000 0.0000270000 0.0003070000 0.0532420000 8530904 96830484 1770549248 3.8914682865 4.2457027435 5.8474440575 291 11.6000000000 0.0073214364 0.0051775368 0.0074419929 0.0080918333 0.1688550000 0.0104940000 0.0846630000 0.0000590000 0.0000540000 0.0618120000 8532578 96830484 1769541632 3.8990240097 4.2448401451 5.8545670509 292 11.6400000000 0.0073223813 0.0051848821 0.0074419929 0.0080797221 0.1297750000 0.0086480000 0.0587030000 0.0000200000 0.0002080000 0.0533670000 8534252 96830484 1771159552 3.9070658684 4.2458314896 5.8603334427 293 11.6800000000 0.0073132911 0.0051921463 0.0074419929 0.0080659949 0.1606120000 0.0109060000 0.0336330000 0.0000830000 0.0000740000 0.0997130000 8535926 96830484 1770041344 3.9140355587 4.2460818291 5.8671889305 294 11.7200000000 0.0073506190 0.0051994880 0.0074419929 0.0080536961 0.1130820000 0.0116000000 0.0438270000 0.0000280000 0.0003100000 0.0528330000 8537600 96830484 1768517632 3.9201622009 4.2453889847 5.8745393753 295 11.7600000000 0.0073434757 0.0052067558 0.0074419929 0.0080458106 0.1271170000 0.0090550000 0.0440370000 0.0003180000 0.0002720000 0.0607870000 8539274 96830484 1770323968 3.9258491993 4.2453398705 5.8814907074 296 11.8000000000 0.0073283808 0.0052139235 0.0074419929 0.0080367550 0.1113480000 0.0105430000 0.0425940000 0.0000270000 0.0010860000 0.0534810000 8540948 96830484 1769406464 3.9317009449 4.2455120087 5.8880209923 297 11.8400000000 0.0073664878 0.0052211711 0.0074419929 0.0080282524 0.1664640000 0.0104700000 0.0433850000 0.0010810000 0.0002860000 0.0964360000 8542622 96830484 1767993344 3.9366052151 4.2450776100 5.8955769539 298 11.8800000000 0.0073884320 0.0052284438 0.0074419929 0.0080237498 0.1105690000 0.0088070000 0.0358770000 0.0000170000 0.0002030000 0.0566240000 8544296 96830484 1769799680 3.9415006638 4.2444596291 5.9035415649 299 11.9200000000 0.0073690070 0.0052356029 0.0074419929 0.0080147546 0.1510140000 0.0096410000 0.0571590000 0.0003090000 0.0002770000 0.0804180000 8545970 96830484 1768484864 3.9465432167 4.2444586754 5.9116683006 300 11.9600000000 0.0073738876 0.0052427305 0.0074419929 0.0080022171 0.1085930000 0.0081160000 0.0375220000 0.0000280000 0.0003780000 0.0593150000 8547644 96830484 1770278912 3.9515573978 4.2452802658 5.9199595451 301 12.0000000000 0.0073729921 0.0052498078 0.0074419929 0.0079891421 0.1481730000 0.0103700000 0.0393590000 0.0003000000 0.0006260000 0.0942210000 8549318 96830484 1769025536 3.9561946392 4.2455625534 5.9291901588 302 12.0400000000 0.0074241417 0.0052570076 0.0074419929 0.0079785176 0.1095780000 0.0086380000 0.0427290000 0.0000260000 0.0003010000 0.0537480000 8550992 96830484 1770835968 3.9601697922 4.2454571724 5.9390864372 303 12.0800000000 0.0073767337 0.0052640034 0.0074419929 0.0079725906 0.1274820000 0.0107340000 0.0441950000 0.0003240000 0.0002750000 0.0616220000 8552666 96830484 1770041344 3.9643566608 4.2457032204 5.9490427971 304 12.1200000000 0.0074868421 0.0052713153 0.0074868421 0.0079715906 0.1301810000 0.0107910000 0.0573000000 0.0000270000 0.0003700000 0.0546930000 8554340 96830484 1768534016 3.9682958126 4.2460737228 5.9593019485 305 12.1600000000 0.0074375300 0.0052784177 0.0074868421 0.0079686468 0.1668480000 0.0090140000 0.0425920000 0.0003050000 0.0002660000 0.0983420000 8556014 96830484 1770323968 3.9719529152 4.2458839417 5.9705891609 306 12.2000000000 0.0074679595 0.0052855731 0.0074868421 0.0079620435 0.1127300000 0.0105040000 0.0450430000 0.0001040000 0.0003160000 0.0532530000 8557688 96830484 1769390080 3.9755680561 4.2458815575 5.9821076393 307 12.2400000000 0.0075131920 0.0052928291 0.0075131920 0.0079639082 0.1269860000 0.0102780000 0.0432920000 0.0010490000 0.0002820000 0.0617880000 8559362 96830484 1768267776 3.9788534641 4.2466526031 5.9937467575 308 12.2800000000 0.0075425324 0.0053001334 0.0075425324 0.0079679500 0.1095040000 0.0087410000 0.0355060000 0.0000090000 0.0000780000 0.0575200000 8561036 96830484 1769926656 3.9814891815 4.2467846870 6.0053153038 309 12.3200000000 0.0075095445 0.0053072836 0.0075425324 0.0079793515 0.1886780000 0.0099040000 0.0492910000 0.0002950000 0.0002680000 0.1169000000 8562710 96830484 1768792064 3.9834015369 4.2463583946 6.0162491798 310 12.3600000000 0.0075569362 0.0053145405 0.0075569362 0.0079982960 0.1284900000 0.0086400000 0.0504900000 0.0000250000 0.0003830000 0.0548990000 8564384 96830484 1770545152 3.9850788116 4.2458825111 6.0282092094 311 12.4000000000 0.0075834822 0.0053218362 0.0075834822 0.0080121738 0.1312290000 0.0106890000 0.0506330000 0.0002950000 0.0002670000 0.0630820000 8566058 96830484 1769279488 3.9873003960 4.2467231750 6.0389986038 312 12.4400000000 0.0076281969 0.0053292283 0.0076281969 0.0080493406 0.1103390000 0.0102890000 0.0424820000 0.0000260000 0.0003680000 0.0538670000 8567732 96830484 1768247296 3.9896602631 4.2464780807 6.0628433228 313 12.4800000000 0.0076256399 0.0053365651 0.0076281969 0.0080431731 0.1539840000 0.0086090000 0.0436050000 0.0009960000 0.0002730000 0.0971780000 8569406 96830484 1769881600 3.9902474880 4.2462701797 6.0735983849 314 12.5200000000 0.0076742438 0.0053440099 0.0076742438 0.0080355083 0.1225760000 0.0113340000 0.0436940000 0.0000260000 0.0002840000 0.0588450000 8571080 96830484 1768521728 3.9903092384 4.2451834679 6.0861616135 315 12.5600000000 0.0077040317 0.0053515021 0.0077040317 0.0080358353 0.1482030000 0.0080320000 0.0496500000 0.0002900000 0.0002800000 0.0808390000 8572754 96830484 1770180608 3.9907627106 4.2454414368 6.0975146294 316 12.6000000000 0.0076975487 0.0053589263 0.0077040317 0.0080256219 0.1489260000 0.0100270000 0.0535130000 0.0000260000 0.0003090000 0.0743460000 8574428 96830484 1769152512 3.9909455776 4.2456779480 6.1096744537 317 12.6400000000 0.0076432684 0.0053661324 0.0077040317 0.0080130648 0.2021670000 0.0083510000 0.0544460000 0.0002930000 0.0003400000 0.1212880000 8576102 96830484 1770819584 3.9906268120 4.2449584007 6.1213231087 318 12.6800000000 0.0076455348 0.0053733003 0.0077040317 0.0080004178 0.1136640000 0.0107990000 0.0433030000 0.0000280000 0.0003100000 0.0556520000 8577776 96830484 1769660416 3.9899880886 4.2444357872 6.1326842308 319 12.7200000000 0.0076021259 0.0053802873 0.0077040317 0.0079878413 0.1285470000 0.0107880000 0.0505310000 0.0001140000 0.0001000000 0.0628570000 8579450 96830484 1768230912 3.9892587662 4.2445030212 6.1427187920 320 12.7600000000 0.0075561246 0.0053870867 0.0077040317 0.0079753180 0.1505460000 0.0088960000 0.0864320000 0.0000810000 0.0002960000 0.0514430000 8581124 96830484 1769943040 3.9880611897 4.2445869446 6.1529593468 321 12.8000000000 0.0075005945 0.0053936709 0.0077040317 0.0079652568 0.1633060000 0.0105240000 0.0538920000 0.0003590000 0.0002690000 0.0913860000 8582798 96830484 1768902656 3.9859168530 4.2434430122 6.1637663841 322 12.8400000000 0.0074224598 0.0053999715 0.0077040317 0.0079550149 0.1118700000 0.0086200000 0.0455280000 0.0000840000 0.0002850000 0.0537980000 8584472 96830484 1770545152 3.9842751026 4.2437133789 6.1732611656 323 12.8800000000 0.0073768292 0.0054060918 0.0077040317 0.0079461761 0.1265320000 0.0102860000 0.0448640000 0.0002900000 0.0003440000 0.0643880000 8586146 96830484 1769390080 3.9823191166 4.2425618172 6.1819939613 324 12.9200000000 0.0073206592 0.0054120009 0.0077040317 0.0079348571 0.1306570000 0.0086820000 0.0553690000 0.0000270000 0.0002990000 0.0625790000 8587820 96830484 1771089920 3.9803371429 4.2418608665 6.1912159920 325 12.9600000000 0.0072150687 0.0054175488 0.0077040317 0.0079228145 0.1667250000 0.0104950000 0.0443350000 0.0002910000 0.0003400000 0.1018160000 8589494 96830484 1769914368 3.9789364338 4.2425885201 6.2003254890 326 13.0000000000 0.0071793455 0.0054229531 0.0077040317 0.0079112010 0.1103170000 0.0111460000 0.0420330000 0.0002820000 0.0013490000 0.0516660000 8591168 96830484 1768374272 3.9769806862 4.2422032356 6.2075972557 327 13.0400000000 0.0072000218 0.0054283876 0.0077040317 0.0079004501 0.1264810000 0.0096680000 0.0448460000 0.0003250000 0.0003530000 0.0585490000 8592842 96830484 1770196992 3.9750475883 4.2426018715 6.2173500061 328 13.0800000000 0.0071992134 0.0054337864 0.0077040317 0.0078895588 0.1115330000 0.0113140000 0.0458010000 0.0000240000 0.0003080000 0.0505570000 8594516 96830484 1769279488 3.9745304585 4.2453002930 6.2239203453 329 13.1200000000 0.0071638525 0.0054390450 0.0077040317 0.0078781255 0.1458880000 0.0096290000 0.0456370000 0.0003130000 0.0002740000 0.0865260000 8596190 96830484 1771053056 3.9729261398 4.2460441589 6.2330021858 330 13.1600000000 0.0071280962 0.0054441633 0.0077040317 0.0078673084 0.1117830000 0.0107560000 0.0434910000 0.0000250000 0.0002890000 0.0512270000 8597864 96830484 1770168320 3.9710223675 4.2462706566 6.2410573959 331 13.2000000000 0.0071798158 0.0054494070 0.0077040317 0.0078558048 0.1152400000 0.0107080000 0.0445450000 0.0003580000 0.0002700000 0.0556500000 8599538 96830484 1768771584 3.9693257809 4.2468862534 6.2511096001 332 13.2400000000 0.0073184771 0.0054550367 0.0077040317 0.0078460846 0.1209360000 0.0088270000 0.0423830000 0.0000260000 0.0002870000 0.0583470000 8601212 96830484 1770430464 3.9675800800 4.2474908829 6.2597055435 333 13.2800000000 0.0072761509 0.0054605055 0.0077040317 0.0078353179 0.1693540000 0.0106220000 0.0659880000 0.0002990000 0.0003440000 0.0820980000 8602886 96830484 1769627648 3.9654788971 4.2476992607 6.2690320015 334 13.3200000000 0.0072991364 0.0054660104 0.0077040317 0.0078240969 0.1114360000 0.0111070000 0.0521430000 0.0000280000 0.0002990000 0.0442900000 8604560 96830484 1768120320 3.9632644653 4.2476191521 6.2770023346 335 13.3600000000 0.0072785006 0.0054714208 0.0077040317 0.0078125575 0.1075130000 0.0087590000 0.0362540000 0.0003090000 0.0002920000 0.0558390000 8606234 96830484 1769926656 3.9612171650 4.2485785484 6.2855963707 336 13.4000000000 0.0072842594 0.0054768162 0.0077040317 0.0078009635 0.1129780000 0.0101300000 0.0484880000 0.0000300000 0.0003800000 0.0498750000 8607908 96830484 1768792064 3.9597706795 4.2504644394 6.2934122086 337 13.4400000000 0.0072782435 0.0054821617 0.0077040317 0.0077996166 0.1321290000 0.0085340000 0.0374830000 0.0003190000 0.0003360000 0.0818570000 8609582 96830484 1770434560 3.9580950737 4.2528557777 6.3008394241 338 13.4800000000 0.0073059909 0.0054875576 0.0077040317 0.0078057002 0.1016590000 0.0122070000 0.0369730000 0.0000270000 0.0003590000 0.0455650000 8611256 96830484 1769279488 3.9563336372 4.2544822693 6.3070406914 339 13.5200000000 0.0073107537 0.0054929358 0.0077040317 0.0078216645 0.1273480000 0.0082230000 0.0454430000 0.0003930000 0.0002730000 0.0603550000 8612930 96830484 1771053056 3.9539306164 4.2544836998 6.3124933243 340 13.5600000000 0.0073153148 0.0054982957 0.0077040317 0.0078181083 0.1311110000 0.0101680000 0.0675580000 0.0000270000 0.0003020000 0.0475090000 8614604 96830484 1770168320 3.9515447617 4.2548317909 6.3176441193 341 13.6000000000 0.0073534627 0.0055037361 0.0077040317 0.0078114644 0.1666890000 0.0100510000 0.0490290000 0.0003680000 0.0006900000 0.0919480000 8616278 96830484 1768628224 3.9494123459 4.2552208900 6.3224954605 342 13.6400000000 0.0073215603 0.0055090514 0.0077040317 0.0078031133 0.0938330000 0.0088440000 0.0422750000 0.0000270000 0.0009670000 0.0379850000 8617952 96830484 1770450944 3.9472951889 4.2555336952 6.3280072212 343 13.6800000000 0.0073881662 0.0055145298 0.0077040317 0.0077921154 0.1068550000 0.0102430000 0.0446530000 0.0003930000 0.0002720000 0.0476320000 8619626 96830484 1769533440 3.9454083443 4.2558550835 6.3327383995 344 13.7200000000 0.0074160439 0.0055200575 0.0077040317 0.0077808971 0.0912820000 0.0101140000 0.0442660000 0.0000290000 0.0003140000 0.0329360000 8621300 96830484 1768542208 3.9443604946 4.2575035095 6.3382768631 345 13.7600000000 0.0074364417 0.0055256122 0.0077040317 0.0077729614 0.1423810000 0.0088190000 0.0440890000 0.0003710000 0.0002820000 0.0737980000 8622974 96830484 1766993920 3.9424867630 4.2573819160 6.3436956406 346 13.8000000000 0.0074265990 0.0055311064 0.0077040317 0.0077671676 0.0921860000 0.0083690000 0.0421940000 0.0000310000 0.0003250000 0.0371890000 8624648 96830484 1768656896 3.9408476353 4.2572388649 6.3486852646 347 13.8400000000 0.0073777032 0.0055364280 0.0077040317 0.0077563942 0.1069500000 0.0083930000 0.0429590000 0.0011130000 0.0003610000 0.0443430000 8626322 96830484 1770278912 3.9384753704 4.2558159828 6.3532862663 348 13.8800000000 0.0073424918 0.0055416178 0.0077040317 0.0077458555 0.0923830000 0.0104630000 0.0427760000 0.0000300000 0.0010800000 0.0342350000 8627996 96830484 1769279488 3.9379105568 4.2579884529 6.3590779305 349 13.9200000000 0.0073302202 0.0055467428 0.0077040317 0.0077429380 0.1253350000 0.0089060000 0.0440100000 0.0016610000 0.0002970000 0.0667010000 8629670 96830484 1768153088 3.9362730980 4.2576265335 6.3647866249 350 13.9600000000 0.0073110075 0.0055517835 0.0077040317 0.0077348310 0.1070750000 0.0082580000 0.0489130000 0.0000260000 0.0003610000 0.0361910000 8631344 96830484 1767641088 3.9342541695 4.2562303543 6.3736166954 351 14.0000000000 0.0071627148 0.0055563731 0.0077040317 0.0077246594 0.0985500000 0.0084480000 0.0504450000 0.0003270000 0.0004670000 0.0351180000 8633018 96830484 1766490112 3.9340023994 4.2567739487 6.3782615662 352 14.0400000000 0.0071655228 0.0055609445 0.0077040317 0.0077164205 0.1015020000 0.0088100000 0.0517340000 0.0000270000 0.0012980000 0.0356830000 8634692 96830484 1765347328 3.9334242344 4.2563672066 6.3830356598 353 14.0800000000 0.0071655605 0.0055654902 0.0077040317 0.0077054963 0.1392740000 0.0081310000 0.0644050000 0.0003590000 0.0002750000 0.0623370000 8636366 96830484 1764995072 3.9330894947 4.2553577423 6.3873291016 354 14.1200000000 0.0071829734 0.0055700593 0.0077040317 0.0076946227 0.0981110000 0.0097120000 0.0474400000 0.0000270000 0.0003830000 0.0353380000 8638040 96830484 1764073472 3.9334175587 4.2559070587 6.3921575546 355 14.1600000000 0.0071995365 0.0055746494 0.0077040317 0.0076841304 0.1063470000 0.0086970000 0.0462910000 0.0003150000 0.0002780000 0.0407960000 8639714 96830484 1763835904 3.9329116344 4.2544860840 6.3968935013 356 14.2000000000 0.0071500433 0.0055790747 0.0077040317 0.0076755479 0.1077440000 0.0088860000 0.0497230000 0.0000250000 0.0002860000 0.0347220000 8641388 96830484 1765466112 3.9331839085 4.2542700768 6.4015455246 357 14.2400000000 0.0070691272 0.0055832485 0.0077040317 0.0076652322 0.1135130000 0.0085780000 0.0438440000 0.0003930000 0.0002800000 0.0565060000 8643062 96830484 1767104512 3.9334659576 4.2547063828 6.4071583748 358 14.2800000000 0.0070911204 0.0055874604 0.0077040317 0.0076552531 0.0894780000 0.0079760000 0.0433300000 0.0002330000 0.0008060000 0.0332500000 8644736 96830484 1768755200 3.9331893921 4.2533326149 6.4125366211 359 14.3200000000 0.0070780781 0.0055916126 0.0077040317 0.0076460730 0.1060610000 0.0080200000 0.0450520000 0.0002990000 0.0002750000 0.0450690000 8646410 96830484 1770516480 3.9325616360 4.2515120506 6.4179773331 360 14.3600000000 0.0070382105 0.0055956309 0.0077040317 0.0076377052 0.1259130000 0.0098050000 0.0744690000 0.0000280000 0.0003760000 0.0347740000 8648084 96830484 1769426944 3.9323914051 4.2501811981 6.4240908623 361 14.4000000000 0.0070457025 0.0055996477 0.0077040317 0.0076342349 0.1289070000 0.0085620000 0.0458980000 0.0003840000 0.0002800000 0.0553380000 8649758 96830484 1771089920 3.9322888851 4.2499985695 6.4305772781 362 14.4400000000 0.0070510106 0.0056036570 0.0077040317 0.0076280866 0.0982560000 0.0103800000 0.0459360000 0.0000260000 0.0003120000 0.0343060000 8651432 96830484 1769914368 3.9322922230 4.2502036095 6.4370865822 363 14.4800000000 0.0070533953 0.0056076508 0.0077040317 0.0076179147 0.1084870000 0.0086730000 0.0459770000 0.0003150000 0.0003410000 0.0455160000 8653106 96830484 1768529920 3.9324440956 4.2510895729 6.4442496300 364 14.5200000000 0.0070514949 0.0056116174 0.0077040317 0.0076082821 0.0967600000 0.0085370000 0.0574170000 0.0000270000 0.0003020000 0.0266490000 8654780 96830484 1767374848 3.9320924282 4.2504234314 6.4514431953 365 14.5600000000 0.0070720995 0.0056156187 0.0077040317 0.0075981655 0.1580320000 0.0083620000 0.0771140000 0.0005070000 0.0002760000 0.0517560000 8656454 96830484 1766199296 3.9315376282 4.2495069504 6.4584455490 366 14.6000000000 0.0070825852 0.0056196268 0.0077040317 0.0075877860 0.1097510000 0.0086190000 0.0524580000 0.0000260000 0.0003710000 0.0335370000 8658128 96830484 1765093376 3.9314501286 4.2504158020 6.4662723541 367 14.6400000000 0.0071512922 0.0056238003 0.0077040317 0.0075775873 0.1093410000 0.0091470000 0.0508710000 0.0002980000 0.0002810000 0.0387590000 8659802 96830484 1764823040 3.9315326214 4.2513794899 6.4734969139 368 14.6800000000 0.0071991710 0.0056280812 0.0077040317 0.0075698810 0.0905150000 0.0088000000 0.0439810000 0.0000290000 0.0003110000 0.0328140000 8661476 96830484 1766518784 3.9313621521 4.2518963814 6.4812440872 369 14.7200000000 0.0072035594 0.0056323508 0.0077040317 0.0075696823 0.1527350000 0.0084890000 0.0704220000 0.0002980000 0.0002730000 0.0532890000 8663150 96830484 1768103936 3.9305880070 4.2516250610 6.4886684418 370 14.7600000000 0.0072354404 0.0056366835 0.0077040317 0.0075677427 0.1100390000 0.0084910000 0.0711650000 0.0000060000 0.0000610000 0.0263640000 8664824 96830484 1769771008 3.9304101467 4.2520046234 6.4965953827 371 14.8000000000 0.0072592520 0.0056410570 0.0077040317 0.0075620691 0.1115530000 0.0140950000 0.0519740000 0.0003000000 0.0002740000 0.0386830000 8666498 96830484 1768792064 3.9303910732 4.2516918182 6.5037398338 372 14.8400000000 0.0072665922 0.0056454267 0.0077040317 0.0075583883 0.1073680000 0.0086330000 0.0535510000 0.0000270000 0.0003050000 0.0337130000 8668172 96830484 1770434560 3.9301850796 4.2511596680 6.5107722282 373 14.8800000000 0.0072774515 0.0056498021 0.0077040317 0.0075590950 0.1167940000 0.0105100000 0.0409980000 0.0003020000 0.0003560000 0.0606570000 8669846 96830484 1769263104 3.9300775528 4.2509202957 6.5180325508 374 14.9200000000 0.0073239352 0.0056542784 0.0077040317 0.0075558475 0.1022030000 0.0080590000 0.0503670000 0.0000270000 0.0010800000 0.0337280000 8671520 96830484 1770942464 3.9299626350 4.2502460480 6.5252280235 375 14.9600000000 0.0073652146 0.0056588409 0.0077040317 0.0075586141 0.1093020000 0.0104660000 0.0510380000 0.0003730000 0.0002820000 0.0401380000 8673194 96830484 1769787392 3.9302515984 4.2498774529 6.5321679115 376 15.0000000000 0.0073881983 0.0056634402 0.0077040317 0.0075581449 0.1241540000 0.0102930000 0.0816920000 0.0000060000 0.0000580000 0.0281020000 8674868 96830484 1768411136 3.9312629700 4.2512402534 6.5395879745 377 15.0400000000 0.0074251681 0.0056681132 0.0077040317 0.0075510548 0.1205280000 0.0102250000 0.0411050000 0.0003150000 0.0003450000 0.0644740000 8676542 96830484 1770070016 3.9335985184 4.2523293495 6.5526790619 378 15.0800000000 0.0075383494 0.0056730609 0.0077040317 0.0075411154 0.0979210000 0.0104650000 0.0534550000 0.0000300000 0.0003160000 0.0295870000 8678216 96830484 1768898560 3.9356408119 4.2535872459 6.5589818954 379 15.1200000000 0.0075239511 0.0056779446 0.0077040317 0.0075311962 0.1079310000 0.0085630000 0.0436310000 0.0003080000 0.0005290000 0.0501610000 8679890 96830484 1767354368 3.9374895096 4.2540149689 6.5646681786 380 15.1600000000 0.0075786663 0.0056829465 0.0077040317 0.0075224188 0.1133130000 0.0082520000 0.0538000000 0.0000260000 0.0003100000 0.0469360000 8681564 96830484 1766379520 3.9402852058 4.2551121712 6.5700902939 381 15.2000000000 0.0075994153 0.0056879766 0.0077040317 0.0075126577 0.1578330000 0.0082110000 0.0788840000 0.0000600000 0.0000540000 0.0664430000 8683238 96830484 1765244928 3.9426660538 4.2560849190 6.5751690865 382 15.2400000000 0.0076246783 0.0056930465 0.0077040317 0.0075039989 0.0951000000 0.0082900000 0.0399220000 0.0000280000 0.0003690000 0.0400760000 8684912 96830484 1763962880 3.9449107647 4.2564477921 6.5799832344 383 15.2800000000 0.0076704901 0.0056982095 0.0077040317 0.0074947939 0.1301760000 0.0088750000 0.0533760000 0.0002160000 0.0002380000 0.0632510000 8686586 96830484 1763962880 3.9476051331 4.2574386597 6.5845594406 384 15.3200000000 0.0076827779 0.0057033776 0.0077040317 0.0074850964 0.1060540000 0.0082960000 0.0432220000 0.0000260000 0.0003060000 0.0435430000 8688260 96830484 1764319232 3.9504241943 4.2580885887 6.5883893967 385 15.3600000000 0.0077608521 0.0057087217 0.0077608521 0.0074763403 0.1403090000 0.0083480000 0.0491740000 0.0003120000 0.0002750000 0.0780520000 8689934 96830484 1764610048 3.9529879093 4.2577366829 6.5909290314 386 15.4000000000 0.0077581960 0.0057140313 0.0077608521 0.0074739498 0.0996880000 0.0095830000 0.0462140000 0.0000290000 0.0003090000 0.0393630000 8691608 96830484 1764610048 3.9560210705 4.2582912445 6.5931172371 387 15.4400000000 0.0077895387 0.0057193943 0.0077895387 0.0074758427 0.1262070000 0.0089700000 0.0589640000 0.0003200000 0.0003470000 0.0468410000 8693282 96830484 1764990976 3.9597289562 4.2604217529 6.5953302383 388 15.4800000000 0.0077734818 0.0057246884 0.0077895387 0.0074668649 0.1084660000 0.0090100000 0.0463340000 0.0000280000 0.0003190000 0.0411680000 8694956 96830484 1764970496 3.9627332687 4.2615780830 6.5963768959 389 15.5200000000 0.0077722073 0.0057299519 0.0077895387 0.0074580563 0.1303030000 0.0088940000 0.0431450000 0.0012790000 0.0003750000 0.0724760000 8696630 96830484 1765089280 3.9653482437 4.2616839409 6.5973796844 390 15.5600000000 0.0077562253 0.0057351475 0.0077895387 0.0074485886 0.1079940000 0.0090820000 0.0425780000 0.0000300000 0.0003850000 0.0471160000 8698304 96830484 1764941824 3.9692153931 4.2647256851 6.5986247063 391 15.6000000000 0.0077050417 0.0057401856 0.0077895387 0.0074559555 0.1185000000 0.0085180000 0.0603570000 0.0019720000 0.0002960000 0.0431940000 8699978 96830484 1765093376 3.9723536968 4.2649388313 6.5999689102 392 15.6400000000 0.0077219601 0.0057452411 0.0077895387 0.0074473827 0.1168460000 0.0091090000 0.0489640000 0.0000300000 0.0003900000 0.0437350000 8701652 96830484 1765113856 3.9752030373 4.2647438049 6.6003608704 393 15.6800000000 0.0076589691 0.0057501107 0.0077895387 0.0074381535 0.1488920000 0.0093250000 0.0421110000 0.0009500000 0.0002880000 0.0817070000 8703326 96830484 1765097472 3.9772679806 4.2631602287 6.6010169983 394 15.7200000000 0.0077032507 0.0057550679 0.0077895387 0.0074300614 0.0937550000 0.0094050000 0.0353870000 0.0000170000 0.0002390000 0.0445560000 8705000 96830484 1766723584 3.9793212414 4.2614035606 6.6020255089 395 15.7600000000 0.0077425814 0.0057600995 0.0077895387 0.0074321638 0.1255920000 0.0083760000 0.0471080000 0.0003010000 0.0002790000 0.0604840000 8706674 96830484 1768374272 3.9826586246 4.2618608475 6.6026248932 396 15.8000000000 0.0077606076 0.0057651513 0.0077895387 0.0074267176 0.1301080000 0.0084850000 0.0558860000 0.0000270000 0.0003670000 0.0605940000 8708348 96830484 1770024960 3.9864311218 4.2621350288 6.6028485298 397 15.8400000000 0.0077267257 0.0057700923 0.0077895387 0.0074296826 0.1678480000 0.0103650000 0.0472140000 0.0003620000 0.0002830000 0.0988310000 8710022 96830484 1769025536 3.9892933369 4.2613101006 6.6028103828 398 15.8800000000 0.0077104382 0.0057749676 0.0077895387 0.0074245778 0.1101380000 0.0088370000 0.0462410000 0.0000300000 0.0003090000 0.0499970000 8711696 96830484 1770815488 3.9922142029 4.2594923973 6.6021232605 399 15.9200000000 0.0076690773 0.0057797147 0.0077895387 0.0074167156 0.1239400000 0.0107230000 0.0383040000 0.0002980000 0.0003550000 0.0619810000 8713370 96830484 1770041344 3.9967300892 4.2611150742 6.6006727219 400 15.9600000000 0.0076455297 0.0057843792 0.0077895387 0.0074096782 0.1289280000 0.0100750000 0.0551820000 0.0001020000 0.0003120000 0.0518160000 8715044 96830484 1768534016 4.0010557175 4.2621231079 6.6008553505 401 16.0000000000 0.0076041436 0.0057889173 0.0077895387 0.0074042735 0.1438810000 0.0087500000 0.0431680000 0.0003200000 0.0002680000 0.0871010000 8716718 96830484 1770323968 4.0053906441 4.2624907494 6.6012415886 402 16.0400000000 0.0076168636 0.0057934644 0.0077895387 0.0073958672 0.1116140000 0.0140060000 0.0370720000 0.0000260000 0.0003090000 0.0550530000 8718392 96830484 1769406464 4.0109233856 4.2631049156 6.6009383202 403 16.0800000000 0.0076494860 0.0057980700 0.0077895387 0.0073903832 0.1471940000 0.0080450000 0.0483190000 0.0003760000 0.0002800000 0.0780190000 8720066 96830484 1771024384 4.0155453682 4.2625999451 6.6022095680 404 16.1200000000 0.0077511077 0.0058029042 0.0077895387 0.0073818933 0.1490690000 0.0098240000 0.0679430000 0.0000290000 0.0003040000 0.0594290000 8721740 96830484 1770295296 4.0205254555 4.2631039619 6.6009349823 405 16.1600000000 0.0079277018 0.0058081506 0.0079277018 0.0073732735 0.2043530000 0.0098390000 0.0700840000 0.0003960000 0.0002760000 0.1019930000 8723414 96830484 1768771584 4.0259718895 4.2636060715 6.6018424034 406 16.2000000000 0.0081254402 0.0058138582 0.0081254402 0.0073646456 0.1124320000 0.0085550000 0.0425180000 0.0000280000 0.0010490000 0.0530590000 8725088 96830484 1770577920 4.0319151878 4.2653026581 6.6040053368 407 16.2400000000 0.0081691369 0.0058196452 0.0081691369 0.0073568986 0.1105770000 0.0102030000 0.0320630000 0.0002040000 0.0001780000 0.0635590000 8726762 96830484 1769660416 4.0370960236 4.2662134171 6.6059141159 408 16.2800000000 0.0082234377 0.0058255368 0.0082234377 0.0073596987 0.1286070000 0.0095280000 0.0470070000 0.0000290000 0.0003070000 0.0672210000 8728436 96830484 1768267776 4.0423955917 4.2668251991 6.6086435318 409 16.3200000000 0.0081765018 0.0058312849 0.0082234377 0.0073627754 0.1618710000 0.0076850000 0.0447210000 0.0003780000 0.0002810000 0.1045470000 8730110 96830484 1769943040 4.0490565300 4.2703709602 6.6114754677 410 16.3600000000 0.0082723964 0.0058372388 0.0082723964 0.0073540251 0.1129140000 0.0142260000 0.0402510000 0.0000260000 0.0003700000 0.0536760000 8731784 96830484 1768767488 4.0552563667 4.2735013962 6.6156973839 411 16.3999999990 0.0083110621 0.0058432579 0.0083110621 0.0073480897 0.1283430000 0.0077200000 0.0416930000 0.0003590000 0.0002800000 0.0738110000 8733458 96830484 1770545152 4.0587868690 4.2723093033 6.6174440384 412 16.4400000000 0.0082759596 0.0058491625 0.0083110621 0.0073639624 0.1257770000 0.0095400000 0.0430450000 0.0000260000 0.0003090000 0.0603860000 8735132 96830484 1769771008 4.0639996529 4.2721552849 6.6239142418 413 16.4800000000 0.0083349580 0.0058551813 0.0083349580 0.0073783307 0.1900660000 0.0094960000 0.0516910000 0.0002960000 0.0002710000 0.1214760000 8736806 96830484 1768284160 4.0703501701 4.2736248970 6.6309952736 414 16.5200000000 0.0083702840 0.0058612565 0.0083702840 0.0073745831 0.1091690000 0.0085100000 0.0385750000 0.0000260000 0.0002920000 0.0563410000 8738480 96830484 1769926656 4.0751848221 4.2715587616 6.6345353127 415 16.5599999990 0.0084680747 0.0058675380 0.0084680747 0.0073893610 0.1494050000 0.0098060000 0.0482990000 0.0002930000 0.0003530000 0.0862190000 8740154 96830484 1768787968 4.0783929825 4.2658658028 6.6400904655 416 16.6000000000 0.0085275099 0.0058739321 0.0085275099 0.0074722271 0.1109440000 0.0076990000 0.0415320000 0.0000250000 0.0002820000 0.0570270000 8741828 96830484 1770516480 4.0847301483 4.2659149170 6.6457996368 417 16.6400000000 0.0085718222 0.0058804019 0.0085718222 0.0075056399 0.1921080000 0.0095650000 0.0476580000 0.0003080000 0.0003460000 0.1297520000 8743502 96830484 1769406464 4.0910453796 4.2675909996 6.6474189758 418 16.6800000000 0.0086434158 0.0058870120 0.0086434158 0.0075103233 0.1211100000 0.0112810000 0.0407520000 0.0000260000 0.0003440000 0.0568420000 8745176 96830484 1768013824 4.0932674408 4.2644848824 6.6467385292 419 16.7199999990 0.0087660309 0.0058938831 0.0087660309 0.0075424214 0.1516490000 0.0078550000 0.0703330000 0.0002950000 0.0002710000 0.0685020000 8746850 96830484 1769799680 4.1011204720 4.2675766945 6.6524605751 420 16.7600000000 0.0087601589 0.0059007076 0.0087660309 0.0075337999 0.1292580000 0.0091690000 0.0471810000 0.0000270000 0.0003460000 0.0680780000 8748524 96830484 1768538112 4.1084680557 4.2703003883 6.6523880959 421 16.8000000000 0.0088421116 0.0059076943 0.0088421116 0.0075450022 0.1569180000 0.0077410000 0.0405940000 0.0002920000 0.0006940000 0.1031490000 8750198 96830484 1770151936 4.1124019623 4.2658686638 6.6533045769 422 16.8400000000 0.0089558968 0.0059149175 0.0089558968 0.0075424742 0.1168570000 0.0126390000 0.0377550000 0.0000110000 0.0001090000 0.0550610000 8751872 96830484 1769136128 4.1212964058 4.2593255043 6.6553258896 423 16.8799999990 0.0089256410 0.0059220351 0.0089558968 0.0075388115 0.1502580000 0.0080120000 0.0649540000 0.0001540000 0.0000540000 0.0706910000 8753546 96830484 1770770432 4.1283464432 4.2582521439 6.6552791595 424 16.9200000000 0.0087943086 0.0059288093 0.0089558968 0.0075304338 0.1307160000 0.0097380000 0.0498880000 0.0000260000 0.0002830000 0.0663200000 8755220 96830484 1769771008 4.1336498260 4.2552485466 6.6530199051 425 16.9600000000 0.0086584957 0.0059352321 0.0089558968 0.0075300232 0.1831210000 0.0095590000 0.0475390000 0.0003040000 0.0006940000 0.1021370000 8756894 96830484 1768148992 4.1413497925 4.2557196617 6.6503591537 426 17.0000000000 0.0086677624 0.0059416465 0.0089558968 0.0075223779 0.1117180000 0.0084460000 0.0397850000 0.0000250000 0.0002930000 0.0539140000 8758568 96830484 1769771008 4.1502294540 4.2558183670 6.6496720314 427 17.0400000000 0.0086701633 0.0059480365 0.0089558968 0.0075204448 0.1518920000 0.0095590000 0.0704090000 0.0003520000 0.0002690000 0.0665830000 8760242 96830484 1769041920 4.1561102867 4.2520570755 6.6452126503 428 17.0800000000 0.0086917570 0.0059544470 0.0089558968 0.0075122547 0.1467540000 0.0079680000 0.0635960000 0.0000290000 0.0003080000 0.0685560000 8761916 96830484 1770676224 4.1658596992 4.2503190041 6.6419038773 429 17.1200000000 0.0085015399 0.0059603843 0.0089558968 0.0075054454 0.2082220000 0.0099140000 0.0754450000 0.0003040000 0.0002690000 0.1142600000 8763590 96830484 1768865792 4.1762084961 4.2491488457 6.6403393745 430 17.1600000000 0.0087890066 0.0059669625 0.0089558968 0.0075029632 0.1292290000 0.0087770000 0.0637580000 0.0000250000 0.0003420000 0.0497370000 8765264 96830484 1770389504 4.1846499443 4.2454690933 6.6335697174 431 17.2000000000 0.0089655230 0.0059739197 0.0089655230 0.0074943338 0.1293750000 0.0104790000 0.0522970000 0.0002830000 0.0002650000 0.0608650000 8766938 96830484 1768390656 4.1942348480 4.2411875725 6.6301498413 432 17.2400000000 0.0091248276 0.0059812135 0.0091248276 0.0074931000 0.1439150000 0.0085590000 0.0758000000 0.0000270000 0.0006080000 0.0497990000 8768612 96830484 1769914368 4.2063589096 4.2399072647 6.6254448891 433 17.2800000000 0.0088815326 0.0059879117 0.0091248276 0.0074859042 0.2035820000 0.0104980000 0.0754540000 0.0003570000 0.0002690000 0.0940730000 8770286 96830484 1767882752 4.2175288200 4.2383656502 6.6197690964 434 17.3200000000 0.0088177864 0.0059944321 0.0091248276 0.0074773307 0.1332200000 0.0086130000 0.0696580000 0.0000270000 0.0003460000 0.0493340000 8771960 96830484 1769533440 4.2272820473 4.2337675095 6.6112532616 435 17.3600000000 0.0087846583 0.0060008464 0.0091248276 0.0074887726 0.1482450000 0.0105670000 0.0691770000 0.0003520000 0.0002720000 0.0598520000 8773634 96830484 1767485440 4.2402067184 4.2329568863 6.6058745384 436 17.4000000000 0.0087365117 0.0060071209 0.0091248276 0.0074940143 0.1271680000 0.0085770000 0.0570450000 0.0000250000 0.0002930000 0.0489710000 8775308 96830484 1769263104 4.2560954094 4.2366814613 6.5988664627 437 17.4400000000 0.0088102780 0.0060135355 0.0091248276 0.0074915455 0.1606490000 0.0085270000 0.0556770000 0.0002900000 0.0002690000 0.0911050000 8776982 96830484 1770926080 4.2734618187 4.2422389984 6.5902500153 438 17.4800000000 0.0087588942 0.0060198034 0.0091248276 0.0075961087 0.1359170000 0.0122430000 0.0629060000 0.0000260000 0.0002860000 0.0476270000 8778656 96830484 1770041344 4.2868099213 4.2434663773 6.5822129250 439 17.5200000000 0.0086241513 0.0060257358 0.0091248276 0.0077373915 0.1494000000 0.0107220000 0.0685580000 0.0002860000 0.0002660000 0.0588560000 8780330 96830484 1768263680 4.2942619324 4.2379932404 6.5713391304 440 17.5600000000 0.0085794767 0.0060315398 0.0091248276 0.0077668337 0.1287880000 0.0086050000 0.0629680000 0.0000260000 0.0002910000 0.0470060000 8782004 96830484 1770057728 4.3002409935 4.2293682098 6.5628824234 441 17.6000000000 0.0086717615 0.0060375267 0.0091248276 0.0077632891 0.1885880000 0.0101970000 0.0747490000 0.0004990000 0.0005890000 0.0925540000 8783678 96830484 1769263104 4.3081417084 4.2225713730 6.5553269386 442 17.6400000000 0.0085224370 0.0060431487 0.0091248276 0.0078228404 0.1275840000 0.0086260000 0.0560910000 0.0000270000 0.0002890000 0.0473390000 8785352 96830484 1770930176 4.3215632439 4.2234497070 6.5462627411 443 17.6800000000 0.0083595999 0.0060483777 0.0091248276 0.0078454389 0.1303770000 0.0103550000 0.0503180000 0.0003450000 0.0002640000 0.0587040000 8787026 96830484 1770041344 4.3470096588 4.2275242805 6.5287947655 444 17.7200000000 0.0079213334 0.0060525960 0.0091248276 0.0078405457 0.1474090000 0.0105650000 0.0744330000 0.0002420000 0.0002900000 0.0465980000 8788700 96830484 1768517632 4.3558940887 4.2267489433 6.5169134140 445 17.7600000000 0.0079277093 0.0060568098 0.0091248276 0.0078367083 0.1662480000 0.0087000000 0.0439930000 0.0003140000 0.0003460000 0.0880930000 8790374 96830484 1770438656 4.3660521507 4.2239346504 6.5088052750 446 17.8000000000 0.0080003282 0.0060611675 0.0091248276 0.0078279146 0.1497980000 0.0098520000 0.0744950000 0.0000260000 0.0002890000 0.0461800000 8792048 96830484 1769406464 4.3761725426 4.2241249084 6.4996924400 447 17.8400000000 0.0077510327 0.0060649479 0.0091248276 0.0078235265 0.1501930000 0.0083740000 0.0723000000 0.0002870000 0.0003500000 0.0573310000 8793722 96830484 1771184128 4.3836603165 4.2211122513 6.4918518066 448 17.8800000000 0.0079052206 0.0060690557 0.0091248276 0.0078148444 0.1090520000 0.0102350000 0.0379380000 0.0000270000 0.0002860000 0.0487760000 8795396 96830484 1770024960 4.3914880753 4.2191715240 6.4844107628 449 17.9200000000 0.0079917358 0.0060733378 0.0091248276 0.0078063418 0.2038390000 0.0100680000 0.0978610000 0.0000590000 0.0000540000 0.0909430000 8797070 96830484 1768263680 4.3996362686 4.2173280716 6.4763917923 450 17.9600000000 0.0079415422 0.0060774894 0.0091248276 0.0077988775 0.1474520000 0.0102410000 0.0775430000 0.0000270000 0.0003000000 0.0457210000 8798744 96830484 1769930752 4.4062328339 4.2131314278 6.4705967903 451 18.0000000000 0.0077358331 0.0060811664 0.0091248276 0.0078021509 0.1496890000 0.0098950000 0.0728190000 0.0003580000 0.0002850000 0.0563230000 8800418 96830484 1769152512 4.4154262543 4.2126812935 6.4646501541 452 18.0400000000 0.0078854114 0.0060851581 0.0091248276 0.0077960959 0.1283740000 0.0084940000 0.0619490000 0.0000260000 0.0002940000 0.0455800000 8802092 96830484 1770913792 4.4255471230 4.2127799988 6.4581031799 453 18.0800000000 0.0078464905 0.0060890462 0.0091248276 0.0077874757 0.1579100000 0.0104790000 0.0557270000 0.0003770000 0.0002740000 0.0862350000 8803766 96830484 1768644608 4.4330363274 4.2094550133 6.4514980316 454 18.1200000000 0.0077444017 0.0060926924 0.0091248276 0.0077867151 0.1378840000 0.0092200000 0.0690900000 0.0000270000 0.0003070000 0.0448930000 8805440 96830484 1770405888 4.4429125786 4.2086596489 6.4458675385 455 18.1600000000 0.0077004139 0.0060962259 0.0091248276 0.0077793448 0.1498350000 0.0098090000 0.0737460000 0.0003120000 0.0003370000 0.0549220000 8807114 96830484 1769771008 4.4531512260 4.2076945305 6.4406189919 456 18.2000000000 0.0078052208 0.0060999737 0.0091248276 0.0077724133 0.1080900000 0.0100630000 0.0373010000 0.0000280000 0.0003130000 0.0466560000 8808788 96830484 1767903232 4.4618844986 4.2045626640 6.4340858459 457 18.2400000000 0.0077359462 0.0061035535 0.0091248276 0.0077735307 0.1894100000 0.0079070000 0.0841690000 0.0000590000 0.0000520000 0.0870690000 8810462 96830484 1769644032 4.4709315300 4.2017431259 6.4290981293 458 18.2800000000 0.0077353511 0.0061071163 0.0091248276 0.0077880781 0.1305190000 0.0093930000 0.0728710000 0.0000310000 0.0003110000 0.0427390000 8812136 96830484 1768804352 4.4827032089 4.2029824257 6.4261455536 459 18.3200000000 0.0079433890 0.0061111169 0.0091248276 0.0077815733 0.1468000000 0.0081360000 0.0715870000 0.0003040000 0.0003520000 0.0556470000 8813810 96830484 1770553344 4.4961209297 4.2053742409 6.4198951721 460 18.3600000000 0.0076793246 0.0061145261 0.0091248276 0.0077813654 0.1206250000 0.0101910000 0.0689020000 0.0000280000 0.0003620000 0.0361230000 8815484 96830484 1769668608 4.5040225983 4.2013864517 6.4160437584 461 18.4000000000 0.0076051545 0.0061177595 0.0091248276 0.0077738866 0.1619860000 0.0118160000 0.0608800000 0.0003750000 0.0002770000 0.0837040000 8817158 96830484 1768022016 4.5150899887 4.1995339394 6.4130654335 462 18.4400000000 0.0075787758 0.0061209219 0.0091248276 0.0077665119 0.1040520000 0.0087720000 0.0496460000 0.0000310000 0.0003030000 0.0404950000 8818832 96830484 1769680896 4.5262746811 4.2004113197 6.4073505402 463 18.4800000000 0.0075788875 0.0061240709 0.0091248276 0.0077608258 0.1269640000 0.0100710000 0.0499390000 0.0003000000 0.0002780000 0.0533410000 8820506 96830484 1768402944 4.5355582237 4.1983661652 6.4011750221 464 18.5200000000 0.0076189884 0.0061272927 0.0091248276 0.0077545571 0.1088000000 0.0083570000 0.0557920000 0.0000280000 0.0002990000 0.0392600000 8822180 96830484 1770172416 4.5433812141 4.1948552132 6.3981895447 465 18.5600000000 0.0076321596 0.0061305290 0.0091248276 0.0077504286 0.1624400000 0.0096190000 0.0421050000 0.0003150000 0.0002900000 0.0851340000 8823854 96830484 1769398272 4.5513353348 4.1907744408 6.3951110840 466 18.6000000000 0.0074416106 0.0061333424 0.0091248276 0.0077670173 0.0944530000 0.0098490000 0.0368730000 0.0000180000 0.0001940000 0.0425620000 8825528 96830484 1767890944 4.5628457069 4.1917309761 6.3919672966 467 18.6400000000 0.0073004998 0.0061358417 0.0091248276 0.0077621466 0.1283970000 0.0079270000 0.0489970000 0.0002970000 0.0003510000 0.0657060000 8827202 96830484 1767391232 4.5738077164 4.1900997162 6.3893146515 468 18.6800000000 0.0074213361 0.0061385885 0.0091248276 0.0077637681 0.1461810000 0.0076880000 0.0796760000 0.0000070000 0.0000620000 0.0455620000 8828876 96830484 1766604800 4.5838704109 4.1866259575 6.3885126114 469 18.7200000000 0.0074087474 0.0061412967 0.0091248276 0.0077859209 0.1482640000 0.0078190000 0.0382550000 0.0003650000 0.0002790000 0.0877600000 8830550 96830484 1765355520 4.5931787491 4.1850814819 6.3871822357 470 18.7600000000 0.0074180793 0.0061440133 0.0091248276 0.0078044004 0.1076720000 0.0084860000 0.0405860000 0.0000270000 0.0003100000 0.0412570000 8832224 96830484 1766985728 4.6016216278 4.1817083359 6.3867826462 471 18.8000000000 0.0073908446 0.0061466605 0.0091248276 0.0078560780 0.1112270000 0.0084440000 0.0417810000 0.0002890000 0.0010070000 0.0506600000 8833898 96830484 1768624128 4.6127433777 4.1799798012 6.3846602440 472 18.8400000000 0.0073674424 0.0061492469 0.0091248276 0.0078997879 0.1072860000 0.0084200000 0.0403450000 0.0000290000 0.0002930000 0.0428790000 8835572 96830484 1770287104 4.6233468056 4.1802644730 6.3816184998 473 18.8800000000 0.0074563385 0.0061520103 0.0091248276 0.0079086701 0.1699770000 0.0099950000 0.0576740000 0.0002950000 0.0003190000 0.0906740000 8837246 96830484 1769287680 4.6330976486 4.1803226471 6.3775629997 474 18.9200000000 0.0074147359 0.0061546743 0.0091248276 0.0079062795 0.1074310000 0.0087930000 0.0421980000 0.0000280000 0.0002780000 0.0399750000 8838920 96830484 1771061248 4.6383762360 4.1788849831 6.3700137138 475 18.9600000000 0.0074525629 0.0061574067 0.0091248276 0.0079050238 0.1105910000 0.0105210000 0.0356200000 0.0001990000 0.0004950000 0.0535690000 8840594 96830484 1770160128 4.6472101212 4.1769499779 6.3678598404 476 19.0000000000 0.0074847084 0.0061601951 0.0091248276 0.0079108247 0.1209770000 0.0105020000 0.0675840000 0.0000250000 0.0003030000 0.0372820000 8842268 96830484 1768906752 4.6564822197 4.1767754555 6.3651432991 477 19.0400000000 0.0074313045 0.0061628599 0.0091248276 0.0079089905 0.1512000000 0.0097790000 0.0404700000 0.0002830000 0.0002600000 0.0830590000 8843942 96830484 1770586112 4.6648793221 4.1767749786 6.3572082520 478 19.0800000000 0.0075026853 0.0061656629 0.0091248276 0.0079029105 0.1117870000 0.0109030000 0.0546680000 0.0000270000 0.0003000000 0.0395210000 8845616 96830484 1769414656 4.6776561737 4.1761674881 6.3603224754 479 19.1200000000 0.0075431373 0.0061685386 0.0091248276 0.0078958418 0.1089130000 0.0107880000 0.0391490000 0.0003150000 0.0003490000 0.0531600000 8847290 96830484 1768038400 4.6849503517 4.1733918190 6.3590517044 480 19.1600000000 0.0076852790 0.0061716985 0.0091248276 0.0079011628 0.1077730000 0.0083710000 0.0495390000 0.0000910000 0.0002830000 0.0413420000 8848964 96830484 1769791488 4.6955251694 4.1714816093 6.3609094620 481 19.2000000000 0.0080006942 0.0061755010 0.0091248276 0.0079167200 0.1610510000 0.0101950000 0.0536670000 0.0005180000 0.0002860000 0.0911870000 8850638 96830484 1768292352 4.7033944130 4.1736936569 6.3550267220 482 19.2400000000 0.0079561258 0.0061791952 0.0091248276 0.0079090299 0.1334980000 0.0095180000 0.0765690000 0.0000240000 0.0002820000 0.0393410000 8852312 96830484 1770033152 4.7131681442 4.1732635498 6.3562173843 483 19.2800000000 0.0078445133 0.0061826431 0.0091248276 0.0079010489 0.1262260000 0.0107550000 0.0447170000 0.0003120000 0.0002810000 0.0501870000 8853986 96830484 1769017344 4.7217383385 4.1709218025 6.3549904823 484 19.3200000000 0.0080375345 0.0061864755 0.0091248276 0.0078976901 0.1320370000 0.0091420000 0.0772550000 0.0000260000 0.0005400000 0.0395100000 8855660 96830484 1770696704 4.7269454002 4.1707930565 6.3504528999 485 19.3600000000 0.0082096308 0.0061906470 0.0091248276 0.0078947842 0.1490360000 0.0109990000 0.0517050000 0.0002900000 0.0006620000 0.0802600000 8857334 96830484 1769652224 4.7365455627 4.1739358902 6.3460388184 486 19.4000000000 0.0079777883 0.0061943242 0.0091248276 0.0078976402 0.1075730000 0.0106420000 0.0471450000 0.0000270000 0.0003840000 0.0394920000 8859008 96830484 1768128512 4.7453336716 4.1768522263 6.3436708450 487 19.4400000000 0.0081363115 0.0061983119 0.0091248276 0.0079399047 0.1261240000 0.0088160000 0.0466470000 0.0003240000 0.0002660000 0.0512620000 8860682 96830484 1769824256 4.7514042854 4.1737546921 6.3407759666 488 19.4800000000 0.0080677867 0.0062021427 0.0091248276 0.0079392897 0.1099570000 0.0105270000 0.0449150000 0.0000290000 0.0003210000 0.0397600000 8862356 96830484 1768673280 4.7512731552 4.1711130142 6.3332405090 489 19.5200000000 0.0081029525 0.0062060299 0.0091248276 0.0079313095 0.1499980000 0.0088700000 0.0474110000 0.0003220000 0.0002750000 0.0833750000 8864030 96830484 1770397696 4.7562594414 4.1705951691 6.3289117813 490 19.5600000000 0.0080789328 0.0062098521 0.0091248276 0.0079234828 0.1076080000 0.0106030000 0.0408710000 0.0000260000 0.0002870000 0.0419830000 8865704 96830484 1769271296 4.7603116035 4.1698718071 6.3206257820 491 19.6000000000 0.0080438135 0.0062135873 0.0091248276 0.0079156123 0.1487830000 0.0086080000 0.0745170000 0.0003830000 0.0002730000 0.0510440000 8867378 96830484 1770971136 4.7660741806 4.1690802574 6.3162760735 492 19.6400000000 0.0082025258 0.0062176298 0.0091248276 0.0079076381 0.1092860000 0.0106910000 0.0477580000 0.0000280000 0.0003120000 0.0392030000 8869052 96830484 1769795584 4.7663903236 4.1695938110 6.3046097755 493 19.6800000000 0.0081422776 0.0062215338 0.0091248276 0.0079049283 0.1397620000 0.0109490000 0.0448380000 0.0003230000 0.0002650000 0.0782280000 8870726 96830484 1768656896 4.7684078217 4.1687703133 6.2935991287 494 19.7200000000 0.0080071427 0.0062251484 0.0091248276 0.0079063777 0.0969650000 0.0096410000 0.0404370000 0.0000110000 0.0001330000 0.0415210000 8872400 96830484 1770315776 4.7697653770 4.1637325287 6.2863707542 495 19.7600000000 0.0080401199 0.0062288150 0.0091248276 0.0078997611 0.1275130000 0.0099020000 0.0494970000 0.0002870000 0.0006880000 0.0571650000 8874074 96830484 1769525248 4.7695794106 4.1607990265 6.2757663727 496 19.8000000000 0.0080954367 0.0062325783 0.0091248276 0.0078958759 0.1116780000 0.0097850000 0.0424780000 0.0000260000 0.0003560000 0.0471750000 8875748 96830484 1768402944 4.7682247162 4.1609854698 6.2685170174 497 19.8400000000 0.0080364430 0.0062362079 0.0091248276 0.0078883690 0.1648180000 0.0079440000 0.0511120000 0.0003720000 0.0002850000 0.0998480000 8877422 96830484 1770016768 4.7715392113 4.1578769684 6.2622261047 498 19.8800000000 0.0080840085 0.0062399183 0.0091248276 0.0078816611 0.1094270000 0.0104310000 0.0473520000 0.0000290000 0.0003820000 0.0405950000 8879096 96830484 1768906752 4.7698273659 4.1567969322 6.2512578964 499 19.9200000000 0.0081665991 0.0062437794 0.0091248276 0.0078738213 0.1266610000 0.0086310000 0.0467510000 0.0003810000 0.0002840000 0.0523010000 8880770 96830484 1770569728 4.7707967758 4.1555738449 6.2446904182 500 19.9600000000 0.0081649562 0.0062476217 0.0091248276 0.0078661778 0.1103070000 0.0103190000 0.0468750000 0.0000270000 0.0003760000 0.0405750000 8882444 96830484 1769795584 4.7706308365 4.1542019844 6.2343931198 501 20.0000000000 0.0082508260 0.0062516201 0.0091248276 0.0078590283 0.1644690000 0.0102090000 0.0538480000 0.0003730000 0.0002880000 0.0843050000 8884118 96830484 1768656896 4.7715206146 4.1525301933 6.2237458229 502 20.0400000000 0.0081566572 0.0062554150 0.0091248276 0.0078512834 0.0928730000 0.0087970000 0.0384970000 0.0000290000 0.0003700000 0.0398410000 8885792 96830484 1770442752 4.7748022079 4.1500973701 6.2177481651 503 20.0800000000 0.0081074219 0.0062590970 0.0091248276 0.0078445984 0.1268870000 0.0104070000 0.0537060000 0.0003120000 0.0003440000 0.0551280000 8887466 96830484 1769160704 4.7768740654 4.1501927376 6.2049226761 504 20.1200000000 0.0082589015 0.0062630648 0.0091248276 0.0078377278 0.1286720000 0.0078820000 0.0712290000 0.0000280000 0.0005090000 0.0403430000 8889140 96830484 1770905600 4.7755432129 4.1470942497 6.1943550110 505 20.1600000000 0.0082028415 0.0062669060 0.0091248276 0.0078334163 0.1492880000 0.0100670000 0.0522340000 0.0003140000 0.0003410000 0.0810440000 8890814 96830484 1770151936 4.7714753151 4.1451792717 6.1814327240 506 20.2000000000 0.0084551731 0.0062712306 0.0091248276 0.0078300980 0.1266440000 0.0101620000 0.0603940000 0.0000270000 0.0003020000 0.0411100000 8892488 96830484 1768644608 4.7707986832 4.1480183601 6.1724371910 507 20.2400000000 0.0084755328 0.0062755783 0.0091248276 0.0078287311 0.1112390000 0.0086100000 0.0447930000 0.0003110000 0.0002730000 0.0516990000 8894162 96830484 1770303488 4.7710099220 4.1490449905 6.1611094475 508 20.2800000000 0.0083852448 0.0062797312 0.0091248276 0.0078340143 0.1081890000 0.0100010000 0.0486070000 0.0000280000 0.0003780000 0.0417590000 8895836 96830484 1769533440 4.7636642456 4.1464610100 6.1515374184 509 20.3200000000 0.0083901798 0.0062838775 0.0091248276 0.0078279331 0.1463920000 0.0100950000 0.0484180000 0.0003870000 0.0002790000 0.0818350000 8897510 96830484 1767993344 4.7673454285 4.1452794075 6.1419496536 510 20.3600000000 0.0084405821 0.0062881063 0.0091248276 0.0078205331 0.1099690000 0.0081900000 0.0464520000 0.0000260000 0.0003700000 0.0435940000 8899184 96830484 1769689088 4.7717442513 4.1464495659 6.1270852089 511 20.4000000000 0.0084531428 0.0062923432 0.0091248276 0.0078139889 0.1304060000 0.0093130000 0.0669240000 0.0003160000 0.0003600000 0.0452070000 8900858 96830484 1768501248 4.7746162415 4.1503448486 6.1147460938 512 20.4400000000 0.0084902244 0.0062966359 0.0091248276 0.0078253246 0.1204950000 0.0103070000 0.0607300000 0.0000940000 0.0003160000 0.0411400000 8902532 96830484 1770278912 4.7712583542 4.1509542465 6.1018142700 513 20.4800000000 0.0085965302 0.0063011192 0.0091248276 0.0078320194 0.1481600000 0.0099830000 0.0409970000 0.0003060000 0.0002700000 0.0847950000 8945166 96830484 1769517056 4.7759838104 4.1494646072 6.0905861855 514 20.5200000000 0.0086431094 0.0063056756 0.0091248276 0.0078261261 0.1091890000 0.0099590000 0.0486500000 0.0000300000 0.0003130000 0.0416290000 9030808 96830484 1768120320 4.7774472237 4.1510152817 6.0789952278 515 20.5600000000 0.0086761015 0.0063102783 0.0091248276 0.0078259353 0.1264850000 0.0081870000 0.0474480000 0.0003770000 0.0002770000 0.0524800000 9032482 96830484 1769910272 4.7827095985 4.1531977654 6.0666203499 516 20.6000000000 0.0087394258 0.0063149860 0.0091248276 0.0078358094 0.1105030000 0.0099110000 0.0477480000 0.0000250000 0.0003190000 0.0417600000 9034156 96830484 1768792064 4.7856016159 4.1524052620 6.0530424118 517 20.6400000000 0.0087875025 0.0063197684 0.0091248276 0.0078390318 0.1450870000 0.0083470000 0.0482640000 0.0003140000 0.0002750000 0.0824000000 9035830 96830484 1770434560 4.7813134193 4.1500859261 6.0541949272 518 20.6800000000 0.0086786440 0.0063243222 0.0091248276 0.0078317229 0.1160990000 0.0103490000 0.0602320000 0.0000310000 0.0003080000 0.0397320000 9037504 96830484 1769263104 4.7955560684 4.1502346992 6.0333909988 519 20.7200000000 0.0087778755 0.0063290497 0.0091248276 0.0078253805 0.1242140000 0.0081450000 0.0482140000 0.0003870000 0.0002890000 0.0537540000 9039178 96830484 1770942464 4.7864699364 4.1530151367 6.0374965668 520 20.7600000000 0.0088110706 0.0063338228 0.0091248276 0.0078297119 0.1299340000 0.0103040000 0.0671570000 0.0000260000 0.0003060000 0.0424260000 9040852 96830484 1769771008 4.7794098854 4.1548037529 6.0376725197 521 20.8000000000 0.0087059606 0.0063383758 0.0091248276 0.0078436613 0.1479260000 0.0100460000 0.0484690000 0.0003180000 0.0003480000 0.0832880000 9042526 96830484 1768374272 4.7771100998 4.1526098251 6.0300984383 522 20.8400000000 0.0087897535 0.0063430720 0.0091248276 0.0078406583 0.1081820000 0.0081870000 0.0404530000 0.0000320000 0.0003090000 0.0460880000 9044200 96830484 1770070016 4.7787585258 4.1489958763 6.0235314369 523 20.8800000000 0.0087277377 0.0063476316 0.0091248276 0.0078337680 0.1492930000 0.0095950000 0.0540740000 0.0002990000 0.0003520000 0.0733910000 9045874 96830484 1769136128 4.7683744431 4.1477708817 6.0292835236 524 20.9200000000 0.0087732831 0.0063522607 0.0091248276 0.0078296809 0.1488300000 0.0078750000 0.0792500000 0.0000270000 0.0003130000 0.0499570000 9047548 96830484 1770942464 4.7851705551 4.1480956078 6.0077319145 525 20.9600000000 0.0086944802 0.0063567220 0.0091248276 0.0078222297 0.1737360000 0.0094240000 0.0534890000 0.0003360000 0.0002880000 0.1044880000 9049222 96830484 1770135552 4.7849416733 4.1473665237 6.0027570724 526 21.0000000000 0.0086199492 0.0063610248 0.0091248276 0.0078152151 0.1066940000 0.0103050000 0.0466940000 0.0000260000 0.0003020000 0.0437260000 9050896 96830484 1768628224 4.7929105759 4.1438097954 5.9897661209 527 21.0400000000 0.0086334758 0.0063653368 0.0091248276 0.0078157123 0.1477790000 0.0080070000 0.0625280000 0.0003940000 0.0002730000 0.0709400000 9052570 96830484 1770450944 4.7939748764 4.1443147659 5.9806618690 528 21.0800000000 0.0087508820 0.0063698549 0.0091248276 0.0078085015 0.1273960000 0.0095340000 0.0530640000 0.0000270000 0.0005500000 0.0534180000 9054244 96830484 1769517056 4.7966613770 4.1438794136 5.9758605957 529 21.1200000000 0.0086401263 0.0063741465 0.0091248276 0.0078020439 0.1771430000 0.0097090000 0.0628450000 0.0003350000 0.0003450000 0.0981900000 9055918 96830484 1768140800 4.8098835945 4.1417546272 5.9553022385 530 21.1600000000 0.0086369449 0.0063784159 0.0091248276 0.0077973892 0.1369750000 0.0083730000 0.0610160000 0.0000280000 0.0002860000 0.0464630000 9057592 96830484 1769816064 4.8064675331 4.1419701576 5.9535174370 531 21.2000000000 0.0087306565 0.0063828458 0.0091248276 0.0077907437 0.1336720000 0.0100050000 0.0466170000 0.0003800000 0.0002820000 0.0583610000 9059266 96830484 1768628224 4.8145346642 4.1408867836 5.9383497238 532 21.2400000000 0.0087214550 0.0063872417 0.0091248276 0.0077846628 0.1249710000 0.0078500000 0.0525840000 0.0000290000 0.0002800000 0.0472730000 9060940 96830484 1770405888 4.8149757385 4.1395254135 5.9302887917 533 21.2800000000 0.0086651528 0.0063915154 0.0091248276 0.0077786148 0.1497000000 0.0100520000 0.0406810000 0.0003590000 0.0002650000 0.0927070000 9062614 96830484 1769517056 4.8135566711 4.1384706497 5.9252114296 534 21.3200000000 0.0087866308 0.0063960006 0.0091248276 0.0077738355 0.1273980000 0.0101280000 0.0491670000 0.0000260000 0.0003120000 0.0482830000 9064288 96830484 1768120320 4.8208560944 4.1369171143 5.9098534584 535 21.3600000000 0.0087555191 0.0064004110 0.0091248276 0.0077697135 0.1142970000 0.0085800000 0.0403690000 0.0003620000 0.0003020000 0.0587480000 9065962 96830484 1769816064 4.8265309334 4.1390762329 5.8949880600 536 21.4000000000 0.0087351520 0.0064047668 0.0091248276 0.0077633644 0.1225920000 0.0098420000 0.0503300000 0.0000300000 0.0002830000 0.0537630000 9067636 96830484 1768775680 4.8240971565 4.1382265091 5.8911051750 537 21.4400000000 0.0089759314 0.0064095548 0.0091248276 0.0077562261 0.1756970000 0.0080440000 0.0594430000 0.0003010000 0.0002800000 0.1020060000 9069310 96830484 1770307584 4.8318753242 4.1367530823 5.8738627434 538 21.4800000000 0.0089796279 0.0064143319 0.0091248276 0.0077492251 0.1199700000 0.0117180000 0.0421630000 0.0000270000 0.0003490000 0.0520700000 9070984 96830484 1769279488 4.8320097923 4.1367077827 5.8656244278 539 21.5200000000 0.0091936821 0.0064194884 0.0091936821 0.0077421646 0.1702530000 0.0082460000 0.0899540000 0.0000590000 0.0000530000 0.0634070000 9072658 96830484 1770897408 4.8303127289 4.1364436150 5.8576221466 540 21.5600000000 0.0093980907 0.0064250043 0.0093980907 0.0077360879 0.1296670000 0.0099230000 0.0612810000 0.0000280000 0.0017760000 0.0508190000 9074332 96830484 1769787392 4.8334670067 4.1376681328 5.8429651260 541 21.6000000000 0.0092131430 0.0064301580 0.0093980907 0.0077293434 0.1477330000 0.0097710000 0.0398560000 0.0002860000 0.0003410000 0.0915330000 9076006 96830484 1768394752 4.8340020180 4.1393089294 5.8336949348 542 21.6400000000 0.0090999780 0.0064350839 0.0093980907 0.0077270901 0.1269170000 0.0084580000 0.0543450000 0.0000280000 0.0005360000 0.0499060000 9077680 96830484 1770070016 4.8363804817 4.1373591423 5.8208937645 543 21.6800000000 0.0091091339 0.0064400085 0.0093980907 0.0077200698 0.1299060000 0.0102650000 0.0477960000 0.0003230000 0.0002770000 0.0607040000 9079354 96830484 1769152512 4.8373413086 4.1347861290 5.8156175613 544 21.7200000000 0.0092120450 0.0064451041 0.0093980907 0.0077198831 0.1102110000 0.0083710000 0.0478400000 0.0000280000 0.0003820000 0.0477920000 9081028 96830484 1770835968 4.8379249573 4.1356096268 5.8053717613 545 21.7600000000 0.0094136735 0.0064505510 0.0094136735 0.0077164969 0.1666420000 0.0105820000 0.0477830000 0.0003140000 0.0002870000 0.0965810000 9082702 96830484 1769771008 4.8407592773 4.1342177391 5.7932038307 546 21.8000000000 0.0094666556 0.0064560750 0.0094666556 0.0077209185 0.1281760000 0.0104960000 0.0553020000 0.0000280000 0.0002860000 0.0501930000 9084376 96830484 1768247296 4.8422384262 4.1348981857 5.7865400314 547 21.8400000000 0.0095789405 0.0064617841 0.0095789405 0.0077189197 0.1293350000 0.0086940000 0.0478440000 0.0003130000 0.0003460000 0.0617130000 9086050 96830484 1770053632 4.8442440033 4.1368021965 5.7747836113 548 21.8800000000 0.0095372852 0.0064673964 0.0095789405 0.0077120100 0.1270990000 0.0104570000 0.0483880000 0.0000260000 0.0003070000 0.0512570000 9087724 96830484 1768771584 4.8409271240 4.1370639801 5.7714886665 549 21.9200000000 0.0091417870 0.0064722677 0.0095789405 0.0077054234 0.1692620000 0.0086280000 0.0482100000 0.0003150000 0.0003580000 0.0977820000 9089398 96830484 1770582016 4.8420429230 4.1360564232 5.7651767731 550 21.9600000000 0.0092780814 0.0064773692 0.0095789405 0.0076990742 0.1115760000 0.0103460000 0.0417600000 0.0000260000 0.0002840000 0.0531990000 9091072 96830484 1769787392 4.8416042328 4.1383428574 5.7582731247 551 22.0000000000 0.0093954476 0.0064826652 0.0095789405 0.0076933996 0.1472290000 0.0099160000 0.0562490000 0.0003020000 0.0003520000 0.0706780000 9092746 96830484 1768263680 4.8420934677 4.1383938789 5.7502312660 552 22.0400000000 0.0097348522 0.0064885568 0.0097348522 0.0076866272 0.1498540000 0.0079720000 0.0583460000 0.0000380000 0.0003830000 0.0766800000 9094420 96830484 1769881600 4.8454060555 4.1400256157 5.7418951988 553 22.0800000000 0.0097717522 0.0064944939 0.0097717522 0.0076831523 0.1939530000 0.0098770000 0.0629430000 0.0003810000 0.0002810000 0.1143580000 9096094 96830484 1768882176 4.8439793587 4.1400651932 5.7395195961 554 22.1200000000 0.0095392745 0.0064999899 0.0097717522 0.0076772135 0.1218540000 0.0086660000 0.0481650000 0.0000290000 0.0003050000 0.0557610000 9097768 96830484 1770582016 4.8443565369 4.1382212639 5.7326464653 555 22.1600000000 0.0095150741 0.0065054225 0.0097717522 0.0076709048 0.1682050000 0.0097460000 0.0755490000 0.0002980000 0.0002730000 0.0712840000 9099442 96830484 1769406464 4.8451075554 4.1407132149 5.7244834900 556 22.2000000000 0.0100272037 0.0065117566 0.0100272037 0.0076671272 0.1471060000 0.0078740000 0.0598460000 0.0000260000 0.0016830000 0.0625130000 9101116 96830484 1771089920 4.8449268341 4.1436815262 5.7156171799 557 22.2400000000 0.0101558128 0.0065182989 0.0101558128 0.0076747445 0.2068700000 0.0097350000 0.0659140000 0.0003870000 0.0002750000 0.1062550000 9102790 96830484 1769914368 4.8444442749 4.1410717964 5.7114362717 558 22.2800000000 0.0102522764 0.0065249906 0.0102522764 0.0076680031 0.1129380000 0.0104460000 0.0395820000 0.0000290000 0.0004800000 0.0563210000 9104464 96830484 1768501248 4.8424096107 4.1385917664 5.7054080963 559 22.3200000000 0.0100625455 0.0065313190 0.0102522764 0.0076632787 0.1491120000 0.0078970000 0.0496600000 0.0003150000 0.0002870000 0.0848310000 9106138 96830484 1770323968 4.8419017792 4.1408109665 5.7001333237 560 22.3600000000 0.0102595342 0.0065379765 0.0102595342 0.0076576538 0.1276340000 0.0095540000 0.0493540000 0.0000280000 0.0002860000 0.0601950000 9107812 96830484 1769406464 4.8406715393 4.1408762932 5.6966967583 561 22.4000000000 0.0104542449 0.0065449574 0.0104542449 0.0076517816 0.2049210000 0.0099360000 0.0507070000 0.0003680000 0.0002780000 0.1209910000 9109486 96830484 1768378368 4.8440914154 4.1399617195 5.6882314682 562 22.4400000000 0.0109158065 0.0065527347 0.0109158065 0.0076451830 0.1291770000 0.0083830000 0.0458970000 0.0001070000 0.0003070000 0.0540180000 9111160 96830484 1769926656 4.8425941467 4.1417274475 5.6850028038 563 22.4800000000 0.0110149700 0.0065606605 0.0110149700 0.0076408441 0.1311230000 0.0098450000 0.0405050000 0.0003040000 0.0003540000 0.0694740000 9112834 96830484 1768775680 4.8447847366 4.1417841911 5.6756644249 564 22.5200000000 0.0108814258 0.0065683214 0.0110149700 0.0076375933 0.1323120000 0.0078340000 0.0543030000 0.0000280000 0.0003870000 0.0635510000 9114508 96830484 1770516480 4.8449993134 4.1396546364 5.6699733734 565 22.5600000000 0.0108505245 0.0065759006 0.0110149700 0.0076309201 0.1824700000 0.0095790000 0.0430270000 0.0003100000 0.0003610000 0.1065520000 9116182 96830484 1769279488 4.8483452797 4.1370759010 5.6585240364 566 22.6000000000 0.0110975625 0.0065838894 0.0110975625 0.0076257732 0.1142760000 0.0085130000 0.0480610000 0.0000270000 0.0003140000 0.0512160000 9117856 96830484 1771089920 4.8491635323 4.1363501549 5.6516737938 567 22.6400000000 0.0110822199 0.0065918229 0.0110975625 0.0076198544 0.1266320000 0.0103310000 0.0388370000 0.0003620000 0.0002780000 0.0691790000 9119530 96830484 1769914368 4.8505392075 4.1357874870 5.6452660561 568 22.6800000000 0.0113063157 0.0066001231 0.0113063157 0.0076134259 0.1485860000 0.0096440000 0.0694860000 0.0000310000 0.0003860000 0.0618710000 9121204 96830484 1768538112 4.8528070450 4.1338176727 5.6363215446 569 22.7200000000 0.0115867658 0.0066088870 0.0115867658 0.0076090206 0.2006610000 0.0079960000 0.0500320000 0.0002930000 0.0002700000 0.1180490000 9122878 96830484 1770180608 4.8549494743 4.1324548721 5.6257243156 570 22.7600000000 0.0117673203 0.0066179368 0.0117673203 0.0076053441 0.1137480000 0.0100380000 0.0406700000 0.0000900000 0.0002900000 0.0565230000 9124552 96830484 1769406464 4.8538489342 4.1351346970 5.6158084869 571 22.8000000000 0.0118031679 0.0066270178 0.0118031679 0.0076001470 0.1658220000 0.0080380000 0.0583720000 0.0003680000 0.0002750000 0.0846470000 9126226 96830484 1771024384 4.8525762558 4.1364488602 5.6073198318 572 22.8400000000 0.0120234694 0.0066364522 0.0120234694 0.0075982273 0.1493630000 0.0096520000 0.0652980000 0.0000260000 0.0003500000 0.0615490000 9127900 96830484 1770024960 4.8525247574 4.1326332092 5.5987730026 573 22.8800000000 0.0114819678 0.0066449086 0.0120234694 0.0075937198 0.2076420000 0.0097920000 0.0704320000 0.0002850000 0.0003450000 0.1104040000 9129574 96830484 1768423424 4.8516178131 4.1319522858 5.5901408195 574 22.9200000000 0.0111094201 0.0066526865 0.0120234694 0.0075871798 0.1112050000 0.0084900000 0.0388260000 0.0000270000 0.0003650000 0.0571530000 9131248 96830484 1770196992 4.8487348557 4.1332368851 5.5837264061 575 22.9600000000 0.0106472438 0.0066596335 0.0120234694 0.0075823730 0.1491920000 0.0097630000 0.0544580000 0.0003000000 0.0002670000 0.0779770000 9132922 96830484 1769279488 4.8473834991 4.1297736168 5.5744400024 576 23.0000000000 0.0106896451 0.0066666301 0.0120234694 0.0075775987 0.1453990000 0.0078460000 0.0684470000 0.0000290000 0.0003110000 0.0518660000 9134596 96830484 1771053056 4.8464598656 4.1263008118 5.5671644211 577 23.0400000000 0.0107573466 0.0066737197 0.0120234694 0.0075788200 0.1695460000 0.0102590000 0.0402010000 0.0003020000 0.0002830000 0.1044920000 9136270 96830484 1770151936 4.8451123238 4.1279835701 5.5576243401 578 23.0800000000 0.0109157283 0.0066810588 0.0120234694 0.0075722736 0.1121060000 0.0102210000 0.0425780000 0.0000290000 0.0010480000 0.0518130000 9137944 96830484 1768771584 4.8441662788 4.1274762154 5.5480494499 579 23.1200000000 0.0108747091 0.0066883017 0.0120234694 0.0075658238 0.1268020000 0.0083100000 0.0407200000 0.0003110000 0.0005980000 0.0686680000 9139618 96830484 1770430464 4.8436036110 4.1246953011 5.5389280319 580 23.1600000000 0.0111034112 0.0066959140 0.0120234694 0.0075609378 0.1689930000 0.0095190000 0.0898620000 0.0000300000 0.0002990000 0.0607950000 9141292 96830484 1769533440 4.8429918289 4.1238946915 5.5285820961 581 23.2000000000 0.0109791821 0.0067032862 0.0120234694 0.0075547483 0.1862780000 0.0093560000 0.0502690000 0.0003160000 0.0002780000 0.1176120000 9142966 96830484 1768521728 4.8414144516 4.1239824295 5.5192971230 582 23.2400000000 0.0109285833 0.0067105462 0.0120234694 0.0075487238 0.1231160000 0.0093400000 0.0485550000 0.0000290000 0.0003100000 0.0535600000 9144640 96830484 1770180608 4.8400149345 4.1217613220 5.5082345009 583 23.2800000000 0.0111092208 0.0067180911 0.0120234694 0.0075426957 0.1285750000 0.0102250000 0.0414870000 0.0003040000 0.0007870000 0.0640320000 9146314 96830484 1769009152 4.8399586678 4.1185960770 5.4986939430 584 23.3200000000 0.0113302721 0.0067259886 0.0120234694 0.0075431738 0.1107310000 0.0086620000 0.0410020000 0.0000300000 0.0003100000 0.0543230000 9147988 96830484 1770688512 4.8379058838 4.1192560196 5.4873566628 585 23.3600000000 0.0114375902 0.0067340427 0.0120234694 0.0075380971 0.2032320000 0.0096060000 0.0466940000 0.0003200000 0.0002730000 0.1210390000 9149662 96830484 1769914368 4.8366322517 4.1185698509 5.4759197235 586 23.4000000000 0.0115266116 0.0067422211 0.0120234694 0.0075339081 0.1133760000 0.0102720000 0.0409170000 0.0000260000 0.0003890000 0.0541640000 9151336 96830484 1768407040 4.8362703323 4.1153521538 5.4647641182 587 23.4400000000 0.0115992622 0.0067504955 0.0120234694 0.0075380636 0.1275630000 0.0082600000 0.0414740000 0.0003100000 0.0002780000 0.0675100000 9153010 96830484 1770196992 4.8348550797 4.1148691177 5.4551963806 588 23.4800000000 0.0118405782 0.0067591521 0.0120234694 0.0075458947 0.1294250000 0.0095810000 0.0464690000 0.0000300000 0.0003060000 0.0659590000 9154684 96830484 1769279488 4.8321790695 4.1171360016 5.4275679588 589 23.5200000000 0.0118931178 0.0067678685 0.0120234694 0.0075401401 0.2238260000 0.0078150000 0.0579840000 0.0003810000 0.0002780000 0.1314840000 9156358 96830484 1770913792 4.8303127289 4.1186265945 5.4176855087 590 23.5600000000 0.0120582636 0.0067768352 0.0120582636 0.0075376666 0.1137010000 0.0101630000 0.0407860000 0.0000300000 0.0003050000 0.0558730000 9158032 96830484 1770278912 4.8280000687 4.1204538345 5.4060840607 591 23.6000000000 0.0120657636 0.0067857844 0.0120657636 0.0075418816 0.1293760000 0.0100130000 0.0373430000 0.0003150000 0.0003540000 0.0749410000 9159706 96830484 1768660992 4.8267989159 4.1181788445 5.3948574066 592 23.6400000000 0.0121659962 0.0067948726 0.0121659962 0.0075357803 0.1467860000 0.0078270000 0.0615060000 0.0000320000 0.0003050000 0.0669550000 9161380 96830484 1770450944 4.8257064819 4.1156754494 5.3807339668 593 23.6800000000 0.0122684296 0.0068041028 0.0122684296 0.0075314720 0.1759450000 0.0097400000 0.0500160000 0.0003770000 0.0002800000 0.1090930000 9163054 96830484 1769660416 4.8238992691 4.1156573296 5.3681468964 594 23.7200000000 0.0124301882 0.0068135744 0.0124301882 0.0075272741 0.1614290000 0.0110280000 0.0842230000 0.0002560000 0.0003060000 0.0525480000 9164728 96830484 1768136704 4.8224272728 4.1156740189 5.3562045097 595 23.7600000000 0.0122766038 0.0068227559 0.0124301882 0.0075240871 0.1154030000 0.0084460000 0.0413020000 0.0003170000 0.0003570000 0.0584170000 9166402 96830484 1769799680 4.8198118210 4.1146378517 5.3472561836 596 23.8000000000 0.0122691244 0.0068318941 0.0124301882 0.0075233464 0.1237160000 0.0097670000 0.0485940000 0.0000270000 0.0003840000 0.0583830000 9168076 96830484 1768628224 4.8180265427 4.1159672737 5.3342776299 597 23.8400000000 0.0123792300 0.0068411861 0.0124301882 0.0075173072 0.1870160000 0.0079570000 0.0555920000 0.0003180000 0.0003490000 0.1163020000 9169750 96830484 1770434560 4.8152709007 4.1177415848 5.3236622810 598 23.8800000000 0.0125074890 0.0068506616 0.0125074890 0.0075118955 0.1110460000 0.0105870000 0.0436820000 0.0000270000 0.0008780000 0.0492040000 9171424 96830484 1769533440 4.8135957718 4.1176447868 5.3098974228 599 23.9200000000 0.0124597894 0.0068600257 0.0125074890 0.0075060412 0.1267070000 0.0102880000 0.0420410000 0.0003110000 0.0002700000 0.0664630000 9173098 96830484 1768542208 4.8105645180 4.1196470261 5.2997112274 600 23.9600000000 0.0127240382 0.0068697991 0.0127240382 0.0075031175 0.1292220000 0.0078750000 0.0550620000 0.0000300000 0.0003070000 0.0591900000 9174772 96830484 1770164224 4.8085494041 4.1199908257 5.2883105278 601 24.0000000000 0.0126939081 0.0068794898 0.0127240382 0.0074975172 0.1922890000 0.0098650000 0.0748200000 0.0005060000 0.0019390000 0.0985520000 9176446 96830484 1769025536 4.8055071831 4.1201095581 5.2780213356 602 24.0400000000 0.0127628166 0.0068892627 0.0127628166 0.0074913713 0.1185890000 0.0093910000 0.0467820000 0.0000300000 0.0003130000 0.0514200000 9178120 96830484 1770643456 4.8035044670 4.1201486588 5.2653918266 603 24.0800000000 0.0127111915 0.0068989177 0.0127628166 0.0074851950 0.1282410000 0.0107130000 0.0438330000 0.0003890000 0.0002780000 0.0611250000 9179794 96830484 1769533440 4.8000788689 4.1204652786 5.2564873695 604 24.1200000000 0.0126210703 0.0069083914 0.0127628166 0.0074789965 0.1099410000 0.0105110000 0.0387130000 0.0000280000 0.0003110000 0.0537060000 9181468 96830484 1768140800 4.7967057228 4.1212468147 5.2485675812 605 24.1600000000 0.0124577666 0.0069175640 0.0127628166 0.0074731794 0.1869650000 0.0079150000 0.0560760000 0.0003740000 0.0002790000 0.1108920000 9183142 96830484 1769779200 4.7938346863 4.1201572418 5.2399396896 606 24.2000000000 0.0124077890 0.0069266237 0.0127628166 0.0074672165 0.1096450000 0.0102130000 0.0381940000 0.0000290000 0.0003050000 0.0536530000 9184816 96830484 1768775680 4.7913460732 4.1177096367 5.2324104309 607 24.2400000000 0.0123958327 0.0069356340 0.0127628166 0.0074614925 0.1494000000 0.0079510000 0.0559150000 0.0003130000 0.0006790000 0.0780120000 9186490 96830484 1770418176 4.7891721725 4.1171121597 5.2196855545 608 24.2800000000 0.0124336425 0.0069446767 0.0127628166 0.0074557216 0.1282090000 0.0097700000 0.0527910000 0.0000290000 0.0003810000 0.0584670000 9188164 96830484 1769152512 4.7860875130 4.1186375618 5.2109289169 609 24.3200000000 0.0124151176 0.0069536594 0.0127628166 0.0074514587 0.2057150000 0.0080810000 0.0582800000 0.0003170000 0.0002790000 0.1233150000 9189838 96830484 1770913792 4.7844367027 4.1158537865 5.2018961906 610 24.3600000000 0.0127007607 0.0069630809 0.0127628166 0.0074456483 0.1116030000 0.0101790000 0.0461690000 0.0000290000 0.0003080000 0.0481290000 9191512 96830484 1769787392 4.7824163437 4.1120834351 5.1934227943 611 24.4000000000 0.0127362516 0.0069725296 0.0127628166 0.0074441592 0.1264340000 0.0108150000 0.0431940000 0.0010910000 0.0002900000 0.0591070000 9193186 96830484 1767772160 4.7810468674 4.1113672256 5.1798610687 612 24.4400000000 0.0127452640 0.0069819622 0.0127628166 0.0074392557 0.1096700000 0.0088170000 0.0440030000 0.0000280000 0.0003130000 0.0497970000 9194860 96830484 1769533440 4.7781620026 4.1117529869 5.1706047058 613 24.4800000000 0.0127890650 0.0069914354 0.0127890650 0.0074338981 0.1485460000 0.0106730000 0.0426400000 0.0002970000 0.0013790000 0.0868540000 9196534 96830484 1767370752 4.7759990692 4.1098341942 5.1632413864 614 24.5200000000 0.0129290847 0.0070011059 0.0129290847 0.0074279398 0.1080590000 0.0090180000 0.0425400000 0.0000260000 0.0002920000 0.0488090000 9198208 96830484 1769132032 4.7741532326 4.1075186729 5.1499814987 615 24.5600000000 0.0129481684 0.0070107759 0.0129481684 0.0074222704 0.1270220000 0.0089150000 0.0462050000 0.0003170000 0.0003540000 0.0583840000 9199882 96830484 1770672128 4.7727689743 4.1062159538 5.1416497231 616 24.6000000000 0.0130404197 0.0070205643 0.0130404197 0.0074171062 0.1265680000 0.0102950000 0.0458870000 0.0000280000 0.0003870000 0.0486750000 9201556 96830484 1769897984 4.7712531090 4.1034317017 5.1305079460 617 24.6400000000 0.0130523136 0.0070303402 0.0130523136 0.0074161152 0.1509900000 0.0105550000 0.0467610000 0.0003250000 0.0002680000 0.0863570000 9203230 96830484 1768136704 4.7693428993 4.1018643379 5.1196284294 618 24.6800000000 0.0132277505 0.0070403684 0.0132277505 0.0074163843 0.1097400000 0.0088710000 0.0432150000 0.0000280000 0.0003750000 0.0504430000 9204904 96830484 1769787392 4.7682404518 4.1001663208 5.1066875458 619 24.7200000000 0.0130799143 0.0070501253 0.0132277505 0.0074178126 0.1473920000 0.0101860000 0.0534170000 0.0003170000 0.0003440000 0.0727990000 9206578 96830484 1767772160 4.7670531273 4.0992817879 5.0915479660 620 24.7600000000 0.0132105090 0.0070600614 0.0132277505 0.0074150581 0.1313850000 0.0086210000 0.0547430000 0.0000310000 0.0003100000 0.0608650000 9208252 96830484 1769517056 4.7641448975 4.1002359390 5.0825390816 621 24.8000000000 0.0132454624 0.0070700218 0.0132454624 0.0074092121 0.1808380000 0.0100730000 0.0471990000 0.0003120000 0.0002780000 0.0944850000 9209926 96830484 1767497728 4.7624368668 4.0997161865 5.0722036362 622 24.8400000000 0.0131339347 0.0070797709 0.0132454624 0.0074034822 0.1157110000 0.0089960000 0.0526410000 0.0000250000 0.0003110000 0.0467860000 9211600 96830484 1769132032 4.7605314255 4.0975975990 5.0613856316 623 24.8800000000 0.0134852519 0.0070900525 0.0134852519 0.0074008803 0.1265100000 0.0088260000 0.0467570000 0.0003170000 0.0002750000 0.0561140000 9213274 96830484 1770799104 4.7582097054 4.0983633995 5.0503821373 624 24.9200000000 0.0136501333 0.0071005655 0.0136501333 0.0073955632 0.1105710000 0.0108820000 0.0442950000 0.0000300000 0.0003850000 0.0474740000 9214948 96830484 1768771584 4.7552542686 4.0992584229 5.0390863419 625 24.9600000000 0.0137903979 0.0071112692 0.0137903979 0.0073897757 0.1444250000 0.0089180000 0.0442340000 0.0003780000 0.0002760000 0.0835940000 9216622 96830484 1770295296 4.7524709702 4.0976781845 5.0290341377 626 25.0000000000 0.0138315009 0.0071220044 0.0138315009 0.0073847096 0.1130610000 0.0104400000 0.0488920000 0.0000320000 0.0005030000 0.0463280000 9218296 96830484 1769660416 4.7505235672 4.0956835747 5.0197148323 627 25.0400000000 0.0139297172 0.0071328620 0.0139297172 0.0073815561 0.1265210000 0.0104580000 0.0462020000 0.0003840000 0.0002820000 0.0560350000 9219970 96830484 1767878656 4.7477254868 4.0953450203 5.0092868805 628 25.0800000000 0.0138479555 0.0071435548 0.0139297172 0.0073759498 0.1259410000 0.0089500000 0.0466460000 0.0000900000 0.0003070000 0.0472590000 9221644 96830484 1769512960 4.7439031601 4.0972547531 4.9998850822 629 25.1200000000 0.0138677983 0.0071542452 0.0139297172 0.0073726137 0.1609290000 0.0107830000 0.0537720000 0.0003120000 0.0002780000 0.0885780000 9223318 96830484 1767497728 4.7413043976 4.0965652466 4.9936246872 630 25.1600000000 0.0139881615 0.0071650927 0.0139881615 0.0073675122 0.1167310000 0.0100070000 0.0465090000 0.0000300000 0.0003200000 0.0466300000 9224992 96830484 1769119744 4.7373986244 4.0966119766 4.9841599464 631 25.2000000000 0.0138956644 0.0071757592 0.0139881615 0.0073639772 0.1283500000 0.0090030000 0.0513320000 0.0003020000 0.0003530000 0.0544390000 9226666 96830484 1770926080 4.7334280014 4.0974245071 4.9755687714 632 25.2400000000 0.0140492180 0.0071866349 0.0140492180 0.0073629160 0.1101070000 0.0105250000 0.0448290000 0.0000280000 0.0006390000 0.0459110000 9228340 96830484 1770041344 4.7296404839 4.0965461731 4.9698591232 633 25.2800000000 0.0136177251 0.0071967946 0.0140492180 0.0073589147 0.1446860000 0.0111790000 0.0462940000 0.0003110000 0.0002790000 0.0795210000 9230014 96830484 1768280064 4.7255887985 4.0975255966 4.9600515366 634 25.3200000000 0.0145225320 0.0072083494 0.0145225320 0.0073556442 0.1510990000 0.0092240000 0.0849870000 0.0000270000 0.0002960000 0.0463030000 9231688 96830484 1770024960 4.7204117775 4.0992050171 4.9509472847 635 25.3600000000 0.0144198742 0.0072197062 0.0145225320 0.0073583949 0.1460790000 0.0108630000 0.0623810000 0.0003090000 0.0002720000 0.0529930000 9233362 96830484 1769152512 4.7163805962 4.0990614891 4.9455409050 636 25.4000000000 0.0144641874 0.0072310968 0.0145225320 0.0073582983 0.1084550000 0.0096460000 0.0477340000 0.0000250000 0.0003190000 0.0435840000 9235036 96830484 1770897408 4.7129130363 4.0974206924 4.9363198280 637 25.4400000000 0.0145586887 0.0072426001 0.0145586887 0.0073531870 0.1663750000 0.0117270000 0.0582700000 0.0003830000 0.0002770000 0.0795680000 9236710 96830484 1768771584 4.7084288597 4.0978798866 4.9292545319 638 25.4800000000 0.0145440083 0.0072540443 0.0145586887 0.0073488817 0.1084750000 0.0099100000 0.0387910000 0.0000270000 0.0003840000 0.0459550000 9238384 96830484 1770516480 4.7051062584 4.0962061882 4.9213223457 639 25.5200000000 0.0147055322 0.0072657055 0.0147055322 0.0073432854 0.1688940000 0.0112840000 0.0860730000 0.0003130000 0.0002760000 0.0582220000 9240058 96830484 1768390656 4.6999769211 4.0941691399 4.9153952599 640 25.5600000000 0.0148764001 0.0072775972 0.0148764001 0.0073383117 0.1467850000 0.0094740000 0.0753610000 0.0000290000 0.0003070000 0.0439430000 9241732 96830484 1770024960 4.6958661079 4.0927925110 4.9091138840 641 25.6000000000 0.0148250721 0.0072893718 0.0148764001 0.0073332560 0.1446430000 0.0123270000 0.0478620000 0.0003150000 0.0002780000 0.0768550000 9243406 96830484 1768120320 4.6907806396 4.0917224884 4.9027447701 642 25.6400000000 0.0152110932 0.0073017109 0.0152110932 0.0073286892 0.1341190000 0.0101950000 0.0696180000 0.0000290000 0.0003070000 0.0432070000 9245080 96830484 1769771008 4.6854014397 4.0906405449 4.8974304199 643 25.6800000000 0.0151236812 0.0073138757 0.0152110932 0.0073232825 0.1271770000 0.0117700000 0.0459580000 0.0003190000 0.0003550000 0.0518430000 9246754 96830484 1769119744 4.6807289124 4.0890192986 4.8910331726 644 25.7200000000 0.0154662654 0.0073265347 0.0154662654 0.0073176902 0.1103900000 0.0102750000 0.0482400000 0.0000300000 0.0003150000 0.0429310000 9248428 96830484 1770803200 4.6750235558 4.0881175995 4.8857321739 645 25.7600000000 0.0155708371 0.0073393165 0.0155708371 0.0073122532 0.1538760000 0.0119780000 0.0615760000 0.0003080000 0.0002740000 0.0725470000 9250102 96830484 1769914368 4.6700453758 4.0861401558 4.8793950081 646 25.8000000000 0.0158476885 0.0073524874 0.0158476885 0.0073066386 0.1224660000 0.0132870000 0.0571720000 0.0000290000 0.0002980000 0.0426090000 9251776 96830484 1768009728 4.6636204720 4.0845589638 4.8751535416 647 25.8400000000 0.0159077831 0.0073657104 0.0159077831 0.0073010504 0.1276950000 0.0106240000 0.0555420000 0.0003720000 0.0002760000 0.0505870000 9253450 96830484 1769660416 4.6562781334 4.0850505829 4.8694906235 648 25.8800000000 0.0161299556 0.0073792355 0.0161299556 0.0072987810 0.1111670000 0.0124520000 0.0521920000 0.0000280000 0.0003800000 0.0388500000 9255124 96830484 1767645184 4.6495547295 4.0844373703 4.8649234772 649 25.9200000000 0.0161708612 0.0073927819 0.0161708612 0.0072975532 0.1611140000 0.0107600000 0.0688450000 0.0003790000 0.0002870000 0.0735950000 9256798 96830484 1769168896 4.6424446106 4.0814595222 4.8598580360 650 25.9600000000 0.0166279692 0.0074069899 0.0166279692 0.0072934451 0.1338280000 0.0118500000 0.0682380000 0.0000290000 0.0003810000 0.0426310000 9258472 96830484 1768357888 4.6283736229 4.0748348236 4.8508095741 651 26.0000000000 0.0171577297 0.0074219680 0.0171577297 0.0072945209 0.1264460000 0.0102350000 0.0476850000 0.0003170000 0.0002720000 0.0495480000 9260146 96830484 1770151936 4.6109142303 4.0750455856 4.8401536942 652 26.0400000000 0.0175521895 0.0074375051 0.0175521895 0.0072890671 0.1297640000 0.0121840000 0.0623110000 0.0000270000 0.0002920000 0.0419090000 9261820 96830484 1769279488 4.6015219688 4.0759072304 4.8340530396 653 26.0800000000 0.0176233854 0.0074531037 0.0176233854 0.0072860479 0.1673380000 0.0105110000 0.0626400000 0.0003030000 0.0003460000 0.0755260000 9263494 96830484 1771057152 4.5913105011 4.0787215233 4.8293747902 654 26.1200000000 0.0182895996 0.0074696733 0.0182895996 0.0072925011 0.1298330000 0.0122010000 0.0625380000 0.0000270000 0.0003780000 0.0408430000 9265168 96830484 1769787392 4.5809755325 4.0787234306 4.8252620697 655 26.1600000000 0.0188709423 0.0074870798 0.0188709423 0.0072880489 0.1305460000 0.0126450000 0.0626160000 0.0003020000 0.0003580000 0.0472730000 9266842 96830484 1768153088 4.5715160370 4.0763998032 4.8187212944 656 26.2000000000 0.0182792228 0.0075035312 0.0188709423 0.0072866575 0.1259580000 0.0107740000 0.0603620000 0.0000270000 0.0003680000 0.0398280000 9268516 96830484 1769803776 4.5606975555 4.0769572258 4.8153972626 657 26.2400000000 0.0184961203 0.0075202627 0.0188709423 0.0072867057 0.1705490000 0.0125580000 0.0801370000 0.0000600000 0.0000530000 0.0705580000 9270190 96830484 1767628800 4.5500874519 4.0773620605 4.8116140366 658 26.2800000000 0.0181955379 0.0075364866 0.0188709423 0.0072881819 0.1252210000 0.0102210000 0.0559130000 0.0000290000 0.0002980000 0.0401970000 9271864 96830484 1769418752 4.5388898849 4.0786585808 4.8073992729 659 26.3200000000 0.0186544377 0.0075533575 0.0188709423 0.0072856640 0.1503490000 0.0119880000 0.0755330000 0.0003740000 0.0002820000 0.0475670000 9273538 96830484 1768521728 4.5270838737 4.0814943314 4.8037166595 660 26.3600000000 0.0182489995 0.0075695630 0.0188709423 0.0072806522 0.1092380000 0.0104660000 0.0474970000 0.0000320000 0.0003230000 0.0392770000 9275212 96830484 1770164224 4.5162558556 4.0826215744 4.8006591797 661 26.4000000000 0.0184710287 0.0075860554 0.0188709423 0.0072755347 0.1456300000 0.0122780000 0.0556150000 0.0003640000 0.0002810000 0.0695340000 9276886 96830484 1769279488 4.5041809082 4.0852212906 4.7965722084 662 26.4400000000 0.0184828807 0.0076025159 0.0188709423 0.0072744321 0.1514390000 0.0105960000 0.0897740000 0.0000300000 0.0004830000 0.0389640000 9278560 96830484 1770971136 4.4923291206 4.0885848999 4.7950773239 663 26.4800000000 0.0185929481 0.0076190927 0.0188709423 0.0072918998 0.1157830000 0.0122110000 0.0554970000 0.0003880000 0.0002810000 0.0400110000 9280234 96830484 1769779200 4.4816460609 4.0880403519 4.7914075851 664 26.5200000000 0.0188496243 0.0076360061 0.0188709423 0.0072996107 0.1204700000 0.0128240000 0.0556410000 0.0000270000 0.0002870000 0.0382640000 9281908 96830484 1768239104 4.4714689255 4.0850958824 4.7854413986 665 26.5600000000 0.0189551562 0.0076530274 0.0189551562 0.0072946899 0.1869330000 0.0104340000 0.0903940000 0.0002890000 0.0003470000 0.0671960000 9283582 96830484 1770061824 4.4609012604 4.0856337547 4.7823987007 666 26.6000000000 0.0184516180 0.0076692415 0.0189551562 0.0072908811 0.1127390000 0.0120240000 0.0552320000 0.0000280000 0.0002950000 0.0377710000 9285256 96830484 1769160704 4.4497818947 4.0878534317 4.7795467377 667 26.6400000000 0.0189688765 0.0076861825 0.0189688765 0.0072947304 0.1256520000 0.0106200000 0.0513670000 0.0002900000 0.0003380000 0.0457470000 9286930 96830484 1770827776 4.4391250610 4.0908665657 4.7774815559 668 26.6800000000 0.0186360497 0.0077025745 0.0189688765 0.0073167286 0.1114640000 0.0121310000 0.0547400000 0.0000260000 0.0002940000 0.0369000000 9288604 96830484 1770160128 4.4280743599 4.0950093269 4.7747716904 669 26.7200000000 0.0189871527 0.0077194423 0.0189871527 0.0073596444 0.1475320000 0.0128430000 0.0606570000 0.0002920000 0.0002650000 0.0660180000 9290278 96830484 1768779776 4.4171404839 4.0963954926 4.7714524269 670 26.7600000000 0.0184010472 0.0077353850 0.0189871527 0.0073964722 0.1245130000 0.0107260000 0.0684030000 0.0000060000 0.0000600000 0.0372980000 9291952 96830484 1770459136 4.4074883461 4.0959706306 4.7692160606 671 26.8000000000 0.0185734630 0.0077515372 0.0189871527 0.0074033644 0.1281390000 0.0121860000 0.0616920000 0.0002980000 0.0002700000 0.0447550000 9293626 96830484 1769287680 4.3979730606 4.0963859558 4.7653260231 672 26.8400000000 0.0186730400 0.0077677894 0.0189871527 0.0073992777 0.1480950000 0.0105500000 0.0909120000 0.0000260000 0.0003600000 0.0371680000 9295300 96830484 1770950656 4.3883886337 4.0989818573 4.7611031532 673 26.8800000000 0.0179606974 0.0077829349 0.0189871527 0.0073953143 0.1606590000 0.0123920000 0.0752640000 0.0002920000 0.0002690000 0.0649870000 9296974 96830484 1770176512 4.3793830872 4.0995182991 4.7584471703 674 26.9200000000 0.0183751434 0.0077986503 0.0189871527 0.0073899029 0.1158360000 0.0126000000 0.0537100000 0.0000260000 0.0002910000 0.0371060000 9298648 96830484 1768763392 4.3706302643 4.1005496979 4.7540612221 675 26.9600000000 0.0181164909 0.0078139360 0.0189871527 0.0073844573 0.1502240000 0.0107590000 0.0898260000 0.0003500000 0.0002700000 0.0415200000 9300322 96830484 1770442752 4.3618955612 4.1025161743 4.7516937256 676 27.0000000000 0.0184583310 0.0078296822 0.0189871527 0.0073801135 0.1070950000 0.0122730000 0.0470060000 0.0000250000 0.0003110000 0.0370940000 9301996 96830484 1769271296 4.3528389931 4.1068372726 4.7477707863 677 27.0400000000 0.0184160452 0.0078453193 0.0189871527 0.0073889287 0.1657150000 0.0102920000 0.0683690000 0.0002950000 0.0003530000 0.0672010000 9303670 96830484 1770905600 4.3441085815 4.1099610329 4.7460718155 678 27.0800000000 0.0179279689 0.0078601905 0.0189871527 0.0074021786 0.1493770000 0.0127200000 0.0827270000 0.0000240000 0.0002850000 0.0369080000 9305344 96830484 1769906176 4.3358817101 4.1119070053 4.7435550690 679 27.1200000000 0.0183698907 0.0078756687 0.0189871527 0.0074118822 0.1276880000 0.0117640000 0.0544280000 0.0002920000 0.0003410000 0.0431590000 9307018 96830484 1768382464 4.3270144463 4.1140413284 4.7391767502 680 27.1600000000 0.0175446160 0.0078898877 0.0189871527 0.0074142580 0.1151380000 0.0100760000 0.0682310000 0.0000260000 0.0002830000 0.0289960000 9308692 96830484 1770188800 4.3191761971 4.1139492989 4.7355732918 681 27.2000000000 0.0185796637 0.0079055849 0.0189871527 0.0074090558 0.1714530000 0.0119540000 0.0881150000 0.0000610000 0.0000540000 0.0638770000 9310366 96830484 1768906752 4.3112182617 4.1151866913 4.7305822372 682 27.2400000000 0.0185933579 0.0079212561 0.0189871527 0.0074038856 0.1183670000 0.0099370000 0.0551320000 0.0000250000 0.0003560000 0.0350550000 9312040 96830484 1770684416 4.3029727936 4.1188216209 4.7265176773 683 27.2800000000 0.0193574764 0.0079380002 0.0193574764 0.0074030387 0.1282450000 0.0113970000 0.0550510000 0.0002990000 0.0002750000 0.0431820000 9313714 96830484 1769541632 4.2950797081 4.1216926575 4.7212076187 684 27.3200000000 0.0189307667 0.0079540715 0.0193574764 0.0074082426 0.1109940000 0.0114120000 0.0552300000 0.0000270000 0.0002970000 0.0354000000 9315388 96830484 1767747584 4.2867355347 4.1227793694 4.7175221443 685 27.3600000000 0.0197091810 0.0079712323 0.0197091810 0.0074075240 0.1687900000 0.0098060000 0.0910830000 0.0003120000 0.0003530000 0.0594980000 9317062 96830484 1769525248 4.2790722847 4.1236004829 4.7110419273 686 27.4000000000 0.0195980482 0.0079881810 0.0197091810 0.0074042894 0.1100830000 0.0095480000 0.0607790000 0.0000260000 0.0003060000 0.0318130000 9318736 96830484 1771208704 4.2705345154 4.1271119118 4.7057271004 687 27.4400000000 0.0192694459 0.0080046020 0.0197091810 0.0074111981 0.1254370000 0.0109630000 0.0602670000 0.0003860000 0.0002680000 0.0427010000 9320410 96830484 1770303488 4.2623238564 4.1306886673 4.7006459236 688 27.4800000000 0.0196907278 0.0080215877 0.0197091810 0.0074269215 0.1091360000 0.0114610000 0.0540040000 0.0000280000 0.0003040000 0.0351740000 9322084 96830484 1768636416 4.2540426254 4.1323790550 4.6946668625 689 27.5200000000 0.0195895862 0.0080383772 0.0197091810 0.0074366654 0.1395720000 0.0092840000 0.0604150000 0.0003030000 0.0003570000 0.0615210000 9323758 96830484 1770319872 4.2456636429 4.1340270042 4.6891784668 690 27.5600000000 0.0193785634 0.0080548123 0.0197091810 0.0074378155 0.1147870000 0.0108970000 0.0540250000 0.0000320000 0.0002920000 0.0345740000 9325432 96830484 1769414656 4.2377271652 4.1354174614 4.6827244759 691 27.6000000000 0.0197376255 0.0080717194 0.0197376255 0.0074379476 0.1497000000 0.0094100000 0.0884100000 0.0003070000 0.0003610000 0.0416840000 9327106 96830484 1771175936 4.2288713455 4.1397361755 4.6760659218 692 27.6400000000 0.0202354994 0.0080892971 0.0202354994 0.0074524403 0.1069350000 0.0107400000 0.0464440000 0.0000280000 0.0003070000 0.0345030000 9328780 96830484 1770049536 4.2202033997 4.1435661316 4.6691527367 693 27.6800000000 0.0205800403 0.0081073213 0.0205800403 0.0074828607 0.1270000000 0.0112840000 0.0463400000 0.0003210000 0.0003600000 0.0609710000 9330454 96830484 1768271872 4.2123656273 4.1440181732 4.6614494324 694 27.7200000000 0.0213539954 0.0081264087 0.0213539954 0.0074974571 0.1097540000 0.0090910000 0.0528730000 0.0000290000 0.0003730000 0.0341530000 9332128 96830484 1769918464 4.2048897743 4.1433930397 4.6523942947 695 27.7600000000 0.0216783658 0.0081459079 0.0216783658 0.0074973039 0.1296570000 0.0109210000 0.0675400000 0.0002980000 0.0002900000 0.0413760000 9333802 96830484 1768906752 4.1977829933 4.1426291466 4.6447014809 696 27.8000000000 0.0223317388 0.0081662899 0.0223317388 0.0074932721 0.1082480000 0.0090000000 0.0548570000 0.0000280000 0.0003060000 0.0346230000 9335476 96830484 1770446848 4.1900348663 4.1451425552 4.6365804672 697 27.8400000000 0.0230007321 0.0081875731 0.0230007321 0.0074904076 0.1485500000 0.0108730000 0.0685100000 0.0003010000 0.0003500000 0.0607250000 9337150 96830484 1769414656 4.1819138527 4.1486091614 4.6288304329 698 27.8800000000 0.0233368780 0.0082092770 0.0233368780 0.0074926116 0.0981750000 0.0087110000 0.0527140000 0.0000290000 0.0005090000 0.0282850000 9338824 96830484 1771098112 4.1729097366 4.1531667709 4.6220345497 699 27.9200000000 0.0234041400 0.0082310150 0.0234041400 0.0075034186 0.1167840000 0.0102770000 0.0465190000 0.0004120000 0.0002870000 0.0425870000 9340498 96830484 1770287104 4.1645202637 4.1572694778 4.6158919334 700 27.9600000000 0.0232656263 0.0082524930 0.0234041400 0.0075204187 0.1104500000 0.0108690000 0.0545040000 0.0000300000 0.0003680000 0.0357370000 9342172 96830484 1768525824 4.1558227539 4.1604790688 4.6093621254 701 28.0000000000 0.0229753759 0.0082734957 0.0234041400 0.0075394607 0.1452140000 0.0090680000 0.0528590000 0.0003090000 0.0002880000 0.0622000000 9343846 96830484 1770172416 4.1475872993 4.1627759933 4.6035981178 702 28.0400000000 0.0222718362 0.0082934364 0.0234041400 0.0075546873 0.1093730000 0.0105390000 0.0467330000 0.0000340000 0.0003660000 0.0353980000 9345520 96830484 1769033728 4.1395316124 4.1639385223 4.5982379913 703 28.0800000000 0.0213125069 0.0083119557 0.0234041400 0.0075631734 0.1097210000 0.0086110000 0.0465790000 0.0003880000 0.0002840000 0.0424700000 9347194 96830484 1770811392 4.1323060989 4.1649956703 4.5947365761 704 28.1200000000 0.0201804210 0.0083288143 0.0234041400 0.0075704159 0.1074100000 0.0107930000 0.0429890000 0.0000270000 0.0009050000 0.0359730000 9348868 96830484 1769684992 4.1233873367 4.1713142395 4.5920209885 705 28.1600000000 0.0193232615 0.0083444093 0.0234041400 0.0075947643 0.1474360000 0.0105140000 0.0541650000 0.0003180000 0.0003340000 0.0631950000 9350542 96830484 1768022016 4.1149296761 4.1755628586 4.5889759064 706 28.2000000000 0.0186705031 0.0083590354 0.0234041400 0.0076159384 0.1061390000 0.0089510000 0.0458940000 0.0000310000 0.0003150000 0.0356860000 9352216 96830484 1769652224 4.1076602936 4.1756229401 4.5860204697 707 28.2400000000 0.0181915853 0.0083729429 0.0234041400 0.0076184285 0.1107560000 0.0102190000 0.0509460000 0.0003070000 0.0002830000 0.0409990000 9353890 96830484 1768538112 4.0998320580 4.1790704727 4.5827794075 708 28.2800000000 0.0175695345 0.0083859324 0.0234041400 0.0076158833 0.1092180000 0.0087840000 0.0598550000 0.0000280000 0.0003020000 0.0325170000 9355564 96830484 1770192896 4.0915536880 4.1835079193 4.5809454918 709 28.3200000000 0.0164776109 0.0083973452 0.0234041400 0.0076115676 0.1261730000 0.0101440000 0.0443160000 0.0001180000 0.0001030000 0.0635430000 9357238 96830484 1769414656 4.0851984024 4.1805315018 4.5794172287 710 28.3600000000 0.0156704504 0.0084075890 0.0234041400 0.0076079782 0.1088930000 0.0084190000 0.0540950000 0.0000260000 0.0003090000 0.0369250000 9358912 96830484 1771188224 4.0783195496 4.1814999580 4.5773091316 711 28.4000000000 0.0153071219 0.0084172930 0.0234041400 0.0076030025 0.1250340000 0.0103970000 0.0475900000 0.0003160000 0.0002730000 0.0433470000 9360586 96830484 1770303488 4.0697679520 4.1894001961 4.5763020515 712 28.4400000000 0.0149861109 0.0084265189 0.0234041400 0.0076000913 0.1094090000 0.0106970000 0.0437810000 0.0000280000 0.0003140000 0.0362400000 9362260 96830484 1768796160 4.0618805885 4.1916584969 4.5742092133 713 28.4800000000 0.0148077440 0.0084354687 0.0234041400 0.0075970405 0.1270860000 0.0088860000 0.0463080000 0.0003150000 0.0002740000 0.0634260000 9363934 96830484 1770573824 4.0568680763 4.1882057190 4.5736980438 714 28.5200000000 0.0148235969 0.0084444157 0.0234041400 0.0076158389 0.0936990000 0.0100870000 0.0427020000 0.0000280000 0.0002890000 0.0324880000 9365608 96830484 1769779200 4.0485210419 4.1957216263 4.5732097626 715 28.5600000000 0.0146974055 0.0084531611 0.0234041400 0.0076110682 0.1105010000 0.0090560000 0.0531680000 0.0003030000 0.0002810000 0.0397340000 9367282 96830484 1768521728 4.0397529602 4.2025599480 4.5731954575 716 28.6000000000 0.0146679385 0.0084618410 0.0234041400 0.0076116557 0.1043400000 0.0086260000 0.0441050000 0.0000310000 0.0003040000 0.0415720000 9368956 96830484 1767755776 4.0330042839 4.2043118477 4.5753064156 717 28.6400000000 0.0146206142 0.0084704306 0.0234041400 0.0076090184 0.1459650000 0.0086470000 0.0540250000 0.0003100000 0.0002780000 0.0652560000 9370630 96830484 1767014400 4.0265536308 4.2058911324 4.5780897141 718 28.6800000000 0.0146794636 0.0084790783 0.0234041400 0.0076042896 0.1136900000 0.0085850000 0.0596030000 0.0000280000 0.0003770000 0.0369690000 9372304 96830484 1765842944 4.0192165375 4.2106003761 4.5808091164 719 28.7200000000 0.0146636609 0.0084876799 0.0234041400 0.0076031499 0.1231080000 0.0078860000 0.0468660000 0.0003060000 0.0002900000 0.0515150000 9373978 96830484 1764732928 4.0114812851 4.2138681412 4.5830125809 720 28.7600000000 0.0146838333 0.0084962857 0.0234041400 0.0076010228 0.1117210000 0.0077270000 0.0573800000 0.0000290000 0.0003220000 0.0377470000 9375652 96830484 1766350848 4.0040273666 4.2162251472 4.5866551399 721 28.8000000000 0.0147242602 0.0085049237 0.0234041400 0.0075962213 0.1227270000 0.0082510000 0.0438990000 0.0003170000 0.0006840000 0.0615400000 9377326 96830484 1768001536 3.9971418381 4.2171368599 4.5912604332 722 28.8400000000 0.0147357145 0.0085135536 0.0234041400 0.0075909757 0.1096120000 0.0083740000 0.0449040000 0.0000280000 0.0003850000 0.0349800000 9379000 96830484 1769771008 3.9892985821 4.2196011543 4.5956435204 723 28.8800000000 0.0147332652 0.0085221562 0.0234041400 0.0075857726 0.1108190000 0.0101540000 0.0466050000 0.0003190000 0.0006360000 0.0414500000 9380674 96830484 1768775680 3.9816117287 4.2208828926 4.6011700630 724 28.9200000000 0.0146774640 0.0085306580 0.0234041400 0.0075805636 0.1069040000 0.0086350000 0.0473620000 0.0000260000 0.0003160000 0.0342600000 9382348 96830484 1770418176 3.9733407497 4.2232346535 4.6065607071 725 28.9600000000 0.0146483900 0.0085390963 0.0234041400 0.0075778954 0.1405360000 0.0106150000 0.0605360000 0.0002850000 0.0003400000 0.0607110000 9384022 96830484 1769517056 3.9646880627 4.2258806229 4.6123008728 726 29.0000000000 0.0146942381 0.0085475744 0.0234041400 0.0075829292 0.1008710000 0.0084850000 0.0521390000 0.0000280000 0.0003160000 0.0319160000 9385696 96830484 1771089920 3.9565818310 4.2273068428 4.6183695793 727 29.0400000000 0.0146342563 0.0085559467 0.0234041400 0.0075873020 0.1060330000 0.0102820000 0.0441510000 0.0003110000 0.0002750000 0.0408450000 9387370 96830484 1770295296 3.9474041462 4.2293629646 4.6242895126 728 29.0800000000 0.0147076957 0.0085643970 0.0234041400 0.0075910323 0.1063320000 0.0105390000 0.0429000000 0.0000290000 0.0010350000 0.0336810000 9389044 96830484 1768517632 3.9386363029 4.2318329811 4.6308751106 729 29.1200000000 0.0146836843 0.0085727910 0.0234041400 0.0075906491 0.1234940000 0.0088020000 0.0459290000 0.0003120000 0.0003380000 0.0599640000 9390718 96830484 1770295296 3.9298713207 4.2344408035 4.6378803253 730 29.1600000000 0.0148183806 0.0085813466 0.0234041400 0.0075871460 0.1162130000 0.0098790000 0.0657860000 0.0000280000 0.0002850000 0.0320140000 9392392 96830484 1769390080 3.9211218357 4.2357854843 4.6446886063 731 29.2000000000 0.0148470541 0.0085899181 0.0234041400 0.0075825937 0.1064830000 0.0088300000 0.0440900000 0.0003190000 0.0003540000 0.0398850000 9394066 96830484 1771167744 3.9117555618 4.2384305000 4.6511240005 732 29.2400000000 0.0150051704 0.0085986821 0.0234041400 0.0075784624 0.1073890000 0.0102460000 0.0452200000 0.0000310000 0.0003140000 0.0332440000 9395740 96830484 1770295296 3.9016520977 4.2428240776 4.6576581001 733 29.2800000000 0.0149256671 0.0086073137 0.0234041400 0.0075737670 0.1228370000 0.0104510000 0.0442860000 0.0003120000 0.0002810000 0.0592840000 9397414 96830484 1768517632 3.8919045925 4.2460803986 4.6660461426 734 29.3200000000 0.0148434648 0.0086158098 0.0234041400 0.0075693552 0.0945330000 0.0089910000 0.0363190000 0.0000190000 0.0002380000 0.0349520000 9399088 96830484 1770295296 3.8827900887 4.2497301102 4.6752996445 735 29.3600000000 0.0146998269 0.0086240874 0.0234041400 0.0075663236 0.1315870000 0.0097690000 0.0720490000 0.0003030000 0.0003500000 0.0404320000 9400762 96830484 1769152512 3.8739161491 4.2531423569 4.6840734482 736 29.4000000000 0.0145548675 0.0086321455 0.0234041400 0.0075631241 0.1040230000 0.0081550000 0.0450370000 0.0000280000 0.0003700000 0.0349960000 9402436 96830484 1770913792 3.8653137684 4.2573699951 4.6932678223 737 29.4400000000 0.0143519957 0.0086399065 0.0234041400 0.0075584236 0.1495900000 0.0101550000 0.0585020000 0.0003010000 0.0003560000 0.0718220000 9404110 96830484 1770041344 3.8570296764 4.2605137825 4.7020540237 738 29.4800000000 0.0142242173 0.0086474733 0.0234041400 0.0075570685 0.1073590000 0.0115100000 0.0470840000 0.0000270000 0.0003830000 0.0333280000 9405784 96830484 1768247296 3.8485243320 4.2639899254 4.7108230591 739 29.5200000000 0.0141146993 0.0086548715 0.0234041400 0.0075721590 0.1077440000 0.0086540000 0.0431570000 0.0004560000 0.0003540000 0.0390780000 9407458 96830484 1770024960 3.8406844139 4.2668724060 4.7196841240 740 29.5600000000 0.0141634969 0.0086623155 0.0234041400 0.0075916405 0.1078620000 0.0101280000 0.0437690000 0.0000270000 0.0010890000 0.0334460000 9409132 96830484 1769152512 3.8336074352 4.2695889473 4.7282757759 741 29.6000000000 0.0142182484 0.0086698134 0.0234041400 0.0076158549 0.1270260000 0.0083730000 0.0425420000 0.0010270000 0.0002760000 0.0515130000 9410806 96830484 1770913792 3.8263628483 4.2739658356 4.7367572784 742 29.6400000000 0.0142703103 0.0086773613 0.0234041400 0.0076342965 0.1103780000 0.0100560000 0.0506180000 0.0000280000 0.0004540000 0.0336010000 9412480 96830484 1770041344 3.8201651573 4.2776603699 4.7457337379 743 29.6800000000 0.0142130833 0.0086848118 0.0234041400 0.0076339178 0.1089320000 0.0105080000 0.0448750000 0.0003090000 0.0003520000 0.0382000000 9414154 96830484 1768280064 3.8153321743 4.2786693573 4.7539277077 744 29.7200000000 0.0142174447 0.0086922481 0.0234041400 0.0076292853 0.1065700000 0.0085110000 0.0465710000 0.0000280000 0.0003240000 0.0320410000 9415828 96830484 1770070016 3.8103616238 4.2806506157 4.7609291077 745 29.7600000000 0.0142213451 0.0086996697 0.0234041400 0.0076270749 0.1199090000 0.0100630000 0.0440130000 0.0003130000 0.0003540000 0.0567730000 9417502 96830484 1768882176 3.8051857948 4.2833600044 4.7673730850 746 29.8000000000 0.0142170060 0.0087070656 0.0234041400 0.0076231020 0.0954510000 0.0087080000 0.0447510000 0.0000280000 0.0003160000 0.0320200000 9419176 96830484 1770516480 3.8003602028 4.2852253914 4.7737121582 747 29.8400000000 0.0142135294 0.0087144370 0.0234041400 0.0076181888 0.1252310000 0.0099870000 0.0460570000 0.0003360000 0.0002820000 0.0387880000 9420850 96830484 1769787392 3.7951130867 4.2883172035 4.7794489861 748 29.8800000000 0.0141802505 0.0087217443 0.0234041400 0.0076153820 0.1113150000 0.0104520000 0.0552170000 0.0000280000 0.0003720000 0.0350340000 9422524 96830484 1768284160 3.7901213169 4.2918338776 4.7853894234 749 29.9200000000 0.0141853075 0.0087290388 0.0234041400 0.0076119248 0.1278510000 0.0079190000 0.0524240000 0.0003060000 0.0003550000 0.0584730000 9424198 96830484 1770057728 3.7858245373 4.2947320938 4.7910404205 750 29.9600000000 0.0141989570 0.0087363320 0.0234041400 0.0076088626 0.1077960000 0.0105590000 0.0523220000 0.0000290000 0.0003170000 0.0345790000 9425872 96830484 1769152512 3.7817771435 4.2975530624 4.7962698936 751 30.0000000000 0.0142370313 0.0087436565 0.0234041400 0.0076058479 0.1056710000 0.0083260000 0.0444040000 0.0003690000 0.0002740000 0.0372620000 9427546 96830484 1770930176 3.7780020237 4.2997326851 4.8008852005 752 30.0400000000 0.0142752025 0.0087510123 0.0234041400 0.0076029880 0.1077410000 0.0106380000 0.0458210000 0.0000290000 0.0003960000 0.0313720000 9429220 96830484 1769787392 3.7744352818 4.3024468422 4.8051929474 753 30.0800000000 0.0142783234 0.0087583527 0.0234041400 0.0076021922 0.1174570000 0.0102700000 0.0427030000 0.0010490000 0.0003420000 0.0545200000 9430894 96830484 1768013824 3.7707328796 4.3043985367 4.8089151382 754 30.1200000000 0.0143137751 0.0087657206 0.0234041400 0.0076077374 0.1006340000 0.0084580000 0.0497320000 0.0000250000 0.0002920000 0.0309230000 9432568 96830484 1769754624 3.7671816349 4.3065361977 4.8124823570 755 30.1600000000 0.0143734552 0.0087731480 0.0234041400 0.0076190293 0.1073730000 0.0101210000 0.0447440000 0.0003970000 0.0002710000 0.0364670000 9434242 96830484 1768751104 3.7631285191 4.3080182076 4.8157296181 756 30.2000000000 0.0143836960 0.0087805694 0.0234041400 0.0076304075 0.1076390000 0.0083800000 0.0510400000 0.0000280000 0.0002970000 0.0308820000 9435916 96830484 1770565632 3.7588603497 4.3107681274 4.8192996979 757 30.2400000000 0.0143522769 0.0087879297 0.0234041400 0.0076320813 0.1279070000 0.0101360000 0.0422700000 0.0003020000 0.0011410000 0.0559830000 9437590 96830484 1769771008 3.7540502548 4.3138208389 4.8223252296 758 30.2800000000 0.0143564139 0.0087952759 0.0234041400 0.0076351886 0.1096330000 0.0107100000 0.0524680000 0.0000380000 0.0003080000 0.0307640000 9439264 96830484 1767993344 3.7491610050 4.3155627251 4.8257799149 759 30.3200000000 0.0144019322 0.0088026628 0.0234041400 0.0076521664 0.1061000000 0.0085950000 0.0419760000 0.0003010000 0.0008480000 0.0352410000 9440938 96830484 1769787392 3.7436444759 4.3186225891 4.8292622566 760 30.3600000000 0.0144118993 0.0088100434 0.0234041400 0.0076650558 0.1086620000 0.0098360000 0.0518380000 0.0000290000 0.0005680000 0.0303750000 9442612 96830484 1769152512 3.7373392582 4.3234786987 4.8322777748 761 30.4000000000 0.0144270370 0.0088174245 0.0234041400 0.0076740923 0.1150720000 0.0086570000 0.0456230000 0.0003780000 0.0002770000 0.0515020000 9444286 96830484 1770799104 3.7310059071 4.3269586563 4.8350033760 762 30.4400000000 0.0144324051 0.0088247932 0.0234041400 0.0076753856 0.1026920000 0.0103120000 0.0508830000 0.0000280000 0.0003010000 0.0294480000 9445960 96830484 1770135552 3.7242331505 4.3305974007 4.8372020721 763 30.4800000000 0.0144912638 0.0088322198 0.0234041400 0.0076742232 0.1073150000 0.0112400000 0.0445950000 0.0003930000 0.0002900000 0.0350060000 9447634 96830484 1768120320 3.7170283794 4.3346767426 4.8394079208 764 30.5200000000 0.0145480139 0.0088397012 0.0234041400 0.0076739763 0.1083650000 0.0087060000 0.0576590000 0.0000270000 0.0002980000 0.0293440000 9449308 96830484 1769897984 3.7092885971 4.3385605812 4.8415946960 765 30.5600000000 0.0145301241 0.0088471397 0.0234041400 0.0076717255 0.1147530000 0.0103210000 0.0450320000 0.0003180000 0.0003460000 0.0501730000 9450982 96830484 1769136128 3.7016010284 4.3425726891 4.8438782692 766 30.6000000000 0.0146085331 0.0088546611 0.0234041400 0.0076707546 0.1008490000 0.0085220000 0.0461250000 0.0000270000 0.0003110000 0.0286100000 9452656 96830484 1770930176 3.6939091682 4.3462052345 4.8461594582 767 30.6400000000 0.0145908296 0.0088621398 0.0234041400 0.0076694135 0.1079210000 0.0102690000 0.0449520000 0.0003160000 0.0003600000 0.0341320000 9454330 96830484 1769897984 3.6854104996 4.3502006531 4.8479971886 768 30.6800000000 0.0146369915 0.0088696591 0.0234041400 0.0076705423 0.1072740000 0.0105740000 0.0448310000 0.0000290000 0.0006510000 0.0275180000 9456004 96830484 1768263680 3.6770977974 4.3538813591 4.8500752449 769 30.7200000000 0.0146542834 0.0088771814 0.0234041400 0.0076712017 0.1282540000 0.0084550000 0.0454150000 0.0003110000 0.0003490000 0.0526270000 9457678 96830484 1769787392 3.6687211990 4.3581404686 4.8521952629 770 30.7600000000 0.0146609889 0.0088846928 0.0234041400 0.0076683892 0.1078310000 0.0101220000 0.0461400000 0.0000300000 0.0003830000 0.0280830000 9459352 96830484 1768755200 3.6603379250 4.3624267578 4.8542914391 771 30.8000000000 0.0146680949 0.0088921940 0.0234041400 0.0076647115 0.1096070000 0.0085640000 0.0502780000 0.0003060000 0.0002780000 0.0337000000 9461026 96830484 1770422272 3.6518762112 4.3662247658 4.8559947014 772 30.8400000000 0.0147304311 0.0088997565 0.0234041400 0.0076623415 0.1066940000 0.0108830000 0.0451360000 0.0000280000 0.0003790000 0.0270780000 9462700 96830484 1768390656 3.6435749531 4.3688349724 4.8577790260 773 30.8800000000 0.0147272693 0.0089072953 0.0234041400 0.0076609558 0.1283220000 0.0085280000 0.0460490000 0.0003870000 0.0002780000 0.0512640000 9464374 96830484 1770041344 3.6350531578 4.3719048500 4.8596186638 774 30.9200000000 0.0147727616 0.0089148734 0.0234041400 0.0076643041 0.0942870000 0.0101510000 0.0532440000 0.0000270000 0.0005200000 0.0217310000 9466048 96830484 1769025536 3.6269917488 4.3743619919 4.8616433144 775 30.9600000000 0.0148143601 0.0089224857 0.0234041400 0.0076695929 0.1018300000 0.0085730000 0.0424730000 0.0003090000 0.0002750000 0.0329560000 9467722 96830484 1767886848 3.6186985970 4.3759398460 4.8631229401 776 31.0000000000 0.0148222661 0.0089300885 0.0234041400 0.0076772483 0.1075390000 0.0089740000 0.0458380000 0.0001010000 0.0003170000 0.0334300000 9469396 96830484 1767374848 3.6101284027 4.3778934479 4.8646459579 777 31.0400000000 0.0148576815 0.0089377173 0.0234041400 0.0076880161 0.1069680000 0.0084630000 0.0377920000 0.0003840000 0.0002800000 0.0508450000 9471070 96830484 1767014400 3.6016600132 4.3811264038 4.8659329414 778 31.0800000000 0.0148812365 0.0089453568 0.0234041400 0.0076890474 0.0961980000 0.0087330000 0.0574070000 0.0000290000 0.0003190000 0.0209640000 9472744 96830484 1766359040 3.5933251381 4.3844819069 4.8670859337 779 31.1200000000 0.0149004431 0.0089530013 0.0234041400 0.0076875440 0.1048810000 0.0087890000 0.0580960000 0.0003300000 0.0004540000 0.0281170000 9474418 96830484 1765965824 3.5854594707 4.3867373466 4.8686213493 780 31.1600000000 0.0149104847 0.0089606391 0.0234041400 0.0076865487 0.1033220000 0.0079380000 0.0497490000 0.0000290000 0.0003400000 0.0252770000 9476092 96830484 1765228544 3.5777521133 4.3893613815 4.8701572418 781 31.2000000000 0.0149608431 0.0089683218 0.0234041400 0.0076843368 0.1069980000 0.0086170000 0.0477750000 0.0003200000 0.0003510000 0.0386330000 9477766 96830484 1764945920 3.5700554848 4.3917856216 4.8709177971 782 31.2400000000 0.0149521809 0.0089759738 0.0234041400 0.0076802814 0.1048380000 0.0108240000 0.0668630000 0.0000050000 0.0000600000 0.0182130000 9479440 96830484 1765097472 3.5627579689 4.3931102753 4.8721847534 783 31.2800000000 0.0149450498 0.0089835971 0.0234041400 0.0076757486 0.1060120000 0.0084290000 0.0521300000 0.0003110000 0.0003550000 0.0313300000 9481114 96830484 1763790848 3.5555570126 4.3947820663 4.8735527992 784 31.3200000000 0.0149870533 0.0089912546 0.0234041400 0.0076710048 0.1057740000 0.0085080000 0.0506690000 0.0000280000 0.0002950000 0.0252610000 9482788 96830484 1765629952 3.5489282608 4.3960862160 4.8749723434 785 31.3600000000 0.0149807893 0.0089988846 0.0234041400 0.0076662732 0.1273020000 0.0081690000 0.0462740000 0.0003170000 0.0002690000 0.0483330000 9484462 96830484 1767231488 3.5425209999 4.3966846466 4.8760986328 786 31.4000000000 0.0149999484 0.0090065195 0.0234041400 0.0076630860 0.0905600000 0.0079120000 0.0431480000 0.0000310000 0.0003110000 0.0244840000 9486136 96830484 1769009152 3.5361075401 4.3976063728 4.8773374557 787 31.4400000000 0.0149907544 0.0090141234 0.0234041400 0.0076597612 0.1075700000 0.0099630000 0.0449950000 0.0003850000 0.0002790000 0.0306340000 9487810 96830484 1768120320 3.5303318501 4.3995628357 4.8785133362 788 31.4800000000 0.0150179910 0.0090217425 0.0234041400 0.0076579051 0.0900860000 0.0084880000 0.0462210000 0.0000280000 0.0003160000 0.0240460000 9489484 96830484 1769914368 3.5251133442 4.4004697800 4.8801250458 789 31.5200000000 0.0150419818 0.0090293727 0.0234041400 0.0076564257 0.1096920000 0.0105910000 0.0458430000 0.0003900000 0.0002840000 0.0437080000 9491158 96830484 1768771584 3.5198178291 4.4005422592 4.8812093735 790 31.5600000000 0.0150332088 0.0090369725 0.0234041400 0.0076527195 0.1044260000 0.0085820000 0.0518710000 0.0000290000 0.0003130000 0.0240380000 9492832 96830484 1770532864 3.5147080421 4.4007182121 4.8826723099 791 31.6000000000 0.0150221139 0.0090445391 0.0234041400 0.0076480306 0.1075570000 0.0100150000 0.0425980000 0.0011080000 0.0003690000 0.0302190000 9494506 96830484 1769660416 3.5098609924 4.4009604454 4.8838796616 792 31.6400000000 0.0150236012 0.0090520884 0.0234041400 0.0076432387 0.0935040000 0.0105110000 0.0533320000 0.0000270000 0.0003000000 0.0203990000 9496180 96830484 1767624704 3.5055963993 4.4005794525 4.8852710724 793 31.6800000000 0.0150265619 0.0090596224 0.0234041400 0.0076400783 0.1074470000 0.0091050000 0.0456420000 0.0003830000 0.0002790000 0.0430650000 9497854 96830484 1767501824 3.5017411709 4.3997955322 4.8864841461 794 31.7200000000 0.0150258644 0.0090671366 0.0234041400 0.0076427218 0.1046500000 0.0082900000 0.0449410000 0.0000250000 0.0003780000 0.0326130000 9499528 96830484 1766604800 3.4984414577 4.3987030983 4.8879008293 795 31.7600000000 0.0150219491 0.0090746269 0.0234041400 0.0076519751 0.0991410000 0.0087060000 0.0573530000 0.0002900000 0.0002620000 0.0236110000 9501202 96830484 1765580800 3.4951846600 4.3976783752 4.8891954422 796 31.8000000000 0.0150127448 0.0090820868 0.0234041400 0.0076693822 0.0977330000 0.0081740000 0.0422390000 0.0000300000 0.0004650000 0.0326720000 9502876 96830484 1765113856 3.4920165539 4.3965725899 4.8908629417 797 31.8400000000 0.0150536066 0.0090895793 0.0234041400 0.0076890770 0.1126620000 0.0082260000 0.0582950000 0.0003220000 0.0003150000 0.0309490000 9504550 96830484 1764966400 3.4896512032 4.3954977989 4.8924775124 798 31.8800000000 0.0150425956 0.0090970393 0.0234041400 0.0077072435 0.0804940000 0.0083840000 0.0447030000 0.0000340000 0.0009740000 0.0174110000 9506224 96830484 1765097472 3.4868018627 4.3940052986 4.8937835693 799 31.9200000000 0.0150640765 0.0091045074 0.0234041400 0.0077175999 0.1122370000 0.0075190000 0.0610590000 0.0004050000 0.0002800000 0.0332620000 9507898 96830484 1764950016 3.4841926098 4.3922376633 4.8951892853 800 31.9600000000 0.0150249191 0.0091119079 0.0234041400 0.0077253028 0.0858430000 0.0080330000 0.0391240000 0.0000290000 0.0003120000 0.0247650000 9509572 96830484 1765097472 3.4818174839 4.3902139664 4.8967137337 801 32.0000000000 0.0150167542 0.0091192798 0.0234041400 0.0077382952 0.0994830000 0.0080700000 0.0357840000 0.0002890000 0.0002690000 0.0460310000 9511246 96830484 1764950016 3.4798398018 4.3885188103 4.8987574577 802 32.0400000000 0.0150408773 0.0091266633 0.0234041400 0.0077441816 0.1133820000 0.0082870000 0.0559680000 0.0000250000 0.0003240000 0.0248360000 9512920 96830484 1765097472 3.4777500629 4.3864583969 4.9005646706 803 32.0800000000 0.0150237493 0.0091340071 0.0234041400 0.0077553806 0.0904820000 0.0077870000 0.0359160000 0.0002870000 0.0003370000 0.0326970000 9514594 96830484 1764950016 3.4768815041 4.3861145973 4.9031500816 804 32.1199999990 0.0150501598 0.0091413655 0.0234041400 0.0077718610 0.1079540000 0.0078110000 0.0703140000 0.0000280000 0.0002850000 0.0202600000 9516268 96830484 1765097472 3.4757683277 4.3853678703 4.9051642418 805 32.1600000000 0.0150162932 0.0091486636 0.0234041400 0.0077879407 0.1242080000 0.0093550000 0.0426670000 0.0003220000 0.0002760000 0.0478560000 9517942 96830484 1764818944 3.4747710228 4.3836479187 4.9073653221 806 32.2000000000 0.0150316413 0.0091559625 0.0234041400 0.0078046176 0.0904460000 0.0081510000 0.0435740000 0.0000280000 0.0003170000 0.0249750000 9519616 96830484 1766375424 3.4735305309 4.3820986748 4.9090895653 807 32.2400000000 0.0150391487 0.0091632527 0.0234041400 0.0078220152 0.1060640000 0.0084760000 0.0438180000 0.0003180000 0.0002750000 0.0319320000 9521290 96830484 1768136704 3.4729351997 4.3790364265 4.9110822678 808 32.2800000000 0.0150476694 0.0091705354 0.0234041400 0.0078311093 0.0904150000 0.0080620000 0.0434600000 0.0000290000 0.0003100000 0.0254100000 9522964 96830484 1769881600 3.4717354774 4.3766255379 4.9133515358 809 32.3200000000 0.0150329769 0.0091777820 0.0234041400 0.0078371428 0.1029600000 0.0100760000 0.0356230000 0.0002890000 0.0003390000 0.0474130000 9524638 96830484 1768640512 3.4715194702 4.3729205132 4.9157776833 810 32.3600000000 0.0150588304 0.0091850425 0.0234041400 0.0078439416 0.1134570000 0.0089190000 0.0564570000 0.0000240000 0.0002840000 0.0280200000 9526312 96830484 1770311680 3.4707312584 4.3705725670 4.9178886414 811 32.4000000000 0.0150542827 0.0091922795 0.0234041400 0.0078425085 0.1306350000 0.0096690000 0.0800100000 0.0003540000 0.0002780000 0.0311080000 9527986 96830484 1769279488 3.4696519375 4.3667635918 4.9199771881 812 32.4399999990 0.0150657520 0.0091995129 0.0234041400 0.0078415460 0.1039770000 0.0083680000 0.0439400000 0.0000280000 0.0010570000 0.0270080000 9529660 96830484 1770930176 3.4688868523 4.3632526398 4.9221863747 813 32.4800000000 0.0150273163 0.0092066812 0.0234041400 0.0078416952 0.1438340000 0.0141660000 0.0650830000 0.0005130000 0.0002940000 0.0545370000 9531334 96830484 1770168320 3.4686744213 4.3606710434 4.9252405167 814 32.5200000000 0.0150446845 0.0092138531 0.0234041400 0.0078422118 0.0987870000 0.0140060000 0.0562180000 0.0000250000 0.0002900000 0.0189780000 9533008 96830484 1768501248 3.4680998325 4.3578500748 4.9280781746 815 32.5600000000 0.0150083303 0.0092209629 0.0234041400 0.0078398080 0.1395070000 0.0167740000 0.0769820000 0.0003000000 0.0003420000 0.0358760000 9534682 96830484 1770160128 3.4672837257 4.3548216820 4.9308123589 816 32.6000000000 0.0150252255 0.0092280760 0.0234041400 0.0078378399 0.1020300000 0.0122570000 0.0601370000 0.0000280000 0.0002950000 0.0199060000 9536356 96830484 1768923136 3.4670374393 4.3505525589 4.9341263771 817 32.6400000000 0.0149835339 0.0092351206 0.0234041400 0.0078340978 0.2302690000 0.0294520000 0.1335510000 0.0003170000 0.0002830000 0.0570930000 9538030 96830484 1766748160 3.4662728310 4.3471016884 4.9370169640 818 32.6800000000 0.0149713913 0.0092421332 0.0234041400 0.0078295514 0.1181590000 0.0179980000 0.0551860000 0.0000270000 0.0003010000 0.0267200000 9539704 96830484 1768538112 3.4656205177 4.3434543610 4.9407253265 819 32.7200000000 0.0149873290 0.0092491481 0.0234041400 0.0078262068 0.1560920000 0.0268330000 0.0778850000 0.0004000000 0.0002680000 0.0326410000 9541378 96830484 1770160128 3.4654166698 4.3415312767 4.9449844360 820 32.7599999990 0.0149738220 0.0092561294 0.0234041400 0.0078233936 0.0910570000 0.0103030000 0.0456020000 0.0000280000 0.0003920000 0.0254020000 9543052 96830484 1769017344 3.4648218155 4.3391108513 4.9492516518 821 32.7999999990 0.0148857543 0.0092629864 0.0234041400 0.0078273846 0.1108460000 0.0090530000 0.0436090000 0.0011650000 0.0002840000 0.0473520000 9544726 96830484 1767890944 3.4653356075 4.3370370865 4.9548072815 822 32.8400000000 0.0149300871 0.0092698807 0.0234041400 0.0078510160 0.0982420000 0.0085300000 0.0461670000 0.0000280000 0.0010910000 0.0279730000 9546400 96830484 1769574400 3.4650657177 4.3345003128 4.9596967697 823 32.8800000000 0.0148633756 0.0092766772 0.0234041400 0.0078609471 0.1075070000 0.0099500000 0.0456100000 0.0003230000 0.0003390000 0.0335090000 9548074 96830484 1768529920 3.4644498825 4.3324174881 4.9647026062 824 32.9200000000 0.0149276219 0.0092835351 0.0234041400 0.0078653469 0.1071750000 0.0082280000 0.0509830000 0.0000280000 0.0002830000 0.0272210000 9549748 96830484 1770172416 3.4640951157 4.3316097260 4.9705533981 825 32.9600000000 0.0148329111 0.0092902616 0.0234041400 0.0078779998 0.1281750000 0.0102800000 0.0451770000 0.0003870000 0.0002820000 0.0510040000 9551422 96830484 1769160704 3.4637951851 4.3291549683 4.9765729904 826 33.0000000000 0.0147286514 0.0092968456 0.0234041400 0.0078859214 0.1070770000 0.0085350000 0.0460410000 0.0000330000 0.0003140000 0.0266560000 9553096 96830484 1770844160 3.4633622169 4.3277950287 4.9827528000 827 33.0400000000 0.0146513162 0.0093033202 0.0234041400 0.0079025225 0.1091270000 0.0099700000 0.0439030000 0.0003180000 0.0002730000 0.0339670000 9554770 96830484 1769668608 3.4628126621 4.3245739937 4.9886050224 828 33.0800000000 0.0146112284 0.0093097307 0.0234041400 0.0079295086 0.1072320000 0.0101060000 0.0452460000 0.0000270000 0.0003800000 0.0279220000 9556444 96830484 1768255488 3.4625041485 4.3207631111 4.9941649437 829 33.1199999990 0.0145648438 0.0093160698 0.0234041400 0.0079506272 0.1144640000 0.0084700000 0.0462770000 0.0003160000 0.0003530000 0.0496510000 9558118 96830484 1769889792 3.4617795944 4.3175425529 5.0003771782 830 33.1600000000 0.0144506451 0.0093222561 0.0234041400 0.0079663728 0.1039950000 0.0099160000 0.0502100000 0.0000310000 0.0003240000 0.0280370000 9559792 96830484 1768886272 3.4611337185 4.3140349388 5.0062394142 831 33.2000000000 0.0143014351 0.0093282479 0.0234041400 0.0079839856 0.1066170000 0.0084100000 0.0424340000 0.0013190000 0.0002810000 0.0326450000 9561466 96830484 1770590208 3.4612655640 4.3089480400 5.0130481720 832 33.2400000000 0.0141460579 0.0093340385 0.0234041400 0.0079937720 0.1073330000 0.0105090000 0.0450450000 0.0000260000 0.0003160000 0.0273710000 9563140 96830484 1769525248 3.4605548382 4.3047413826 5.0195274353 833 33.2800000000 0.0139941080 0.0093396328 0.0234041400 0.0079967386 0.1192280000 0.0102180000 0.0500120000 0.0003010000 0.0002710000 0.0488300000 9564814 96830484 1768038400 3.4596030712 4.3012576103 5.0264129639 834 33.3200000000 0.0139315808 0.0093451387 0.0234041400 0.0080008105 0.0999960000 0.0082100000 0.0519840000 0.0000260000 0.0002840000 0.0275010000 9566488 96830484 1769791488 3.4588158131 4.2961168289 5.0329313278 835 33.3600000000 0.0137639912 0.0093504308 0.0234041400 0.0080073320 0.1079900000 0.0101270000 0.0456300000 0.0003200000 0.0003480000 0.0333000000 9568162 96830484 1768525824 3.4574878216 4.2933235168 5.0391111374 836 33.4000000000 0.0136679774 0.0093555953 0.0234041400 0.0080165424 0.1145550000 0.0109940000 0.0566960000 0.0000240000 0.0003080000 0.0319810000 9569836 96830484 1770397696 3.4566037655 4.2896428108 5.0458092690 837 33.4399999990 0.0135176536 0.0093605679 0.0234041400 0.0080319252 0.1135770000 0.0102380000 0.0436620000 0.0003160000 0.0003550000 0.0494980000 9571510 96830484 1769160704 3.4554553032 4.2869520187 5.0522036552 838 33.4800000000 0.0134433797 0.0093654400 0.0234041400 0.0080611646 0.0935240000 0.0083680000 0.0354990000 0.0000190000 0.0002090000 0.0297910000 9573184 96830484 1770844160 3.4550514221 4.2820529938 5.0581874847 839 33.5200000000 0.0132945431 0.0093701231 0.0234041400 0.0080921430 0.1126390000 0.0104530000 0.0578560000 0.0003870000 0.0002750000 0.0337870000 9574858 96830484 1770176512 3.4545063972 4.2794461250 5.0646343231 840 33.5600000000 0.0130950166 0.0093745575 0.0234041400 0.0081132610 0.1045300000 0.0098800000 0.0430220000 0.0000170000 0.0001920000 0.0283150000 9576532 96830484 1768779776 3.4522798061 4.2767796516 5.0692911148 841 33.6000000000 0.0128930761 0.0093787412 0.0234041400 0.0081158271 0.1268550000 0.0085430000 0.0454350000 0.0003180000 0.0002740000 0.0532170000 9578206 96830484 1770295296 3.4508697987 4.2745780945 5.0747709274 842 33.6400000000 0.0127184391 0.0093827076 0.0234041400 0.0081142846 0.1068640000 0.0104820000 0.0427650000 0.0000280000 0.0010580000 0.0284560000 9579880 96830484 1769398272 3.4494531155 4.2722830772 5.0798406601 843 33.6800000000 0.0125327902 0.0093864443 0.0234041400 0.0081141894 0.1091150000 0.0084010000 0.0465260000 0.0003910000 0.0002800000 0.0337530000 9581554 96830484 1770950656 3.4484107494 4.2687239647 5.0850868225 844 33.7200000000 0.0123616988 0.0093899695 0.0234041400 0.0081192932 0.1077140000 0.0102120000 0.0434600000 0.0000280000 0.0011800000 0.0284920000 9583228 96830484 1770033152 3.4476885796 4.2636761665 5.0899662971 845 33.7599999990 0.0121732969 0.0093932634 0.0234041400 0.0081301969 0.1282880000 0.0101160000 0.0431060000 0.0003880000 0.0002840000 0.0536250000 9584902 96830484 1768431616 3.4476125240 4.2603440285 5.0951604843 846 33.7999999990 0.0117664142 0.0093960685 0.0234041400 0.0081372652 0.0912610000 0.0086840000 0.0463740000 0.0000240000 0.0003120000 0.0264020000 9586576 96830484 1770209280 3.4464166164 4.2576856613 5.0997395515 847 33.8400000000 0.0114463633 0.0093984892 0.0234041400 0.0081360981 0.1056700000 0.0106810000 0.0437340000 0.0003120000 0.0002850000 0.0334800000 9588250 96830484 1768034304 3.4456198215 4.2526707649 5.1033773422 848 33.8800000000 0.0111616468 0.0094005684 0.0234041400 0.0081316447 0.1055340000 0.0087030000 0.0425110000 0.0000260000 0.0009270000 0.0284580000 9589924 96830484 1769811968 3.4447584152 4.2489895821 5.1074609756 849 33.9200000000 0.0107934214 0.0094022090 0.0234041400 0.0081268836 0.1181100000 0.0100160000 0.0464150000 0.0003040000 0.0002780000 0.0514050000 9591598 96830484 1769050112 3.4439668655 4.2432546616 5.1110267639 850 33.9600000000 0.0105347205 0.0094035413 0.0234041400 0.0081224328 0.1003010000 0.0086360000 0.0464870000 0.0000980000 0.0003170000 0.0285140000 9593272 96830484 1770795008 3.4431986809 4.2393631935 5.1146960258 851 34.0000000000 0.0103179747 0.0094046159 0.0234041400 0.0081176833 0.1076360000 0.0103360000 0.0433110000 0.0003140000 0.0003510000 0.0335660000 9594946 96830484 1769922560 3.4423029423 4.2363219261 5.1186394691 852 34.0400000000 0.0101552987 0.0094054970 0.0234041400 0.0081129359 0.1069930000 0.0105360000 0.0450200000 0.0000190000 0.0002020000 0.0292770000 9596620 96830484 1768271872 3.4426252842 4.2310047150 5.1225013733 853 34.0800000000 0.0098382831 0.0094060043 0.0234041400 0.0081104890 0.1082800000 0.0087800000 0.0384260000 0.0002960000 0.0003390000 0.0507370000 9598294 96830484 1769795584 3.4416742325 4.2268700600 5.1254968643 854 34.1199999990 0.0095137870 0.0094061305 0.0234041400 0.0081088307 0.1067580000 0.0115450000 0.0486610000 0.0000280000 0.0003140000 0.0292070000 9599968 96830484 1768763392 3.4414384365 4.2240562439 5.1290454865 855 34.1600000000 0.0090836529 0.0094057534 0.0234041400 0.0081096980 0.1069870000 0.0087280000 0.0423710000 0.0010910000 0.0002790000 0.0341700000 9601642 96830484 1770430464 3.4417095184 4.2203431129 5.1325554848 856 34.2000000000 0.0087150522 0.0094049465 0.0234041400 0.0081096267 0.1320130000 0.0101080000 0.0849040000 0.0000870000 0.0006120000 0.0264170000 9603316 96830484 1769779200 3.4412145615 4.2171568871 5.1353816986 857 34.2400000000 0.0083650555 0.0094037331 0.0234041400 0.0081055255 0.1184490000 0.0108270000 0.0450310000 0.0003890000 0.0002770000 0.0512140000 9604990 96830484 1767669760 3.4401614666 4.2158069611 5.1382479668 858 34.2800000000 0.0080852835 0.0094021964 0.0234041400 0.0081009536 0.1122380000 0.0089430000 0.0497210000 0.0000260000 0.0002880000 0.0288400000 9606664 96830484 1769414656 3.4390001297 4.2133111954 5.1406335831 859 34.3200000000 0.0079318359 0.0094004847 0.0234041400 0.0080965272 0.1087410000 0.0085970000 0.0438570000 0.0003160000 0.0002650000 0.0337500000 9608338 96830484 1771077632 3.4393191338 4.2071647644 5.1425771713 860 34.3600000000 0.0075774812 0.0093983649 0.0234041400 0.0080920928 0.1077560000 0.0104830000 0.0424570000 0.0000260000 0.0010370000 0.0288360000 9610012 96830484 1770033152 3.4386868477 4.2019920349 5.1440424919 861 34.4000000000 0.0072054449 0.0093958180 0.0234041400 0.0080877769 0.1162520000 0.0106390000 0.0433370000 0.0003170000 0.0002780000 0.0518290000 9611686 96830484 1767907328 3.4383511543 4.1982941628 5.1465358734 862 34.4400000000 0.0068416530 0.0093928549 0.0234041400 0.0080831091 0.1011660000 0.0091170000 0.0438450000 0.0000250000 0.0011610000 0.0293000000 9613360 96830484 1769762816 3.4382276535 4.1939520836 5.1484861374 863 34.4800000000 0.0064997002 0.0093895025 0.0234041400 0.0080787465 0.1084160000 0.0113470000 0.0450730000 0.0003160000 0.0002790000 0.0344800000 9615034 96830484 1767542784 3.4380850792 4.1873660088 5.1496939659 864 34.5200000000 0.0060804086 0.0093856725 0.0234041400 0.0080744193 0.0856990000 0.0087350000 0.0357830000 0.0000260000 0.0003550000 0.0309590000 9616708 96830484 1769414656 3.4382736683 4.1836471558 5.1514587402 865 34.5600000000 0.0058761244 0.0093816152 0.0234041400 0.0080697500 0.1817180000 0.0080300000 0.0859410000 0.0003650000 0.0002810000 0.0513900000 9618382 96830484 1771061248 3.4373314381 4.1823906898 5.1531662941 866 34.6000000000 0.0058054565 0.0093774857 0.0234041400 0.0080672612 0.0943820000 0.0107280000 0.0435620000 0.0000250000 0.0003020000 0.0292860000 9620056 96830484 1769906176 3.4360997677 4.1808915138 5.1542882919 867 34.6400000000 0.0056636957 0.0093732022 0.0234041400 0.0080639948 0.1052980000 0.0091870000 0.0451060000 0.0003840000 0.0002810000 0.0340960000 9621730 96830484 1768783872 3.4363296032 4.1781005859 5.1559152603 868 34.6800000000 0.0056597078 0.0093689240 0.0234041400 0.0080598790 0.0899170000 0.0088320000 0.0371100000 0.0000400000 0.0003070000 0.0302350000 9623404 96830484 1768267776 3.4357051849 4.1743249893 5.1566691399 869 34.7200000000 0.0054676021 0.0093644346 0.0234041400 0.0080556353 0.1579070000 0.0081590000 0.0649130000 0.0003230000 0.0002710000 0.0530100000 9625078 96830484 1767522304 3.4363102913 4.1708297729 5.1577215195 870 34.7600000000 0.0053771418 0.0093598515 0.0234041400 0.0080512786 0.1150190000 0.0087370000 0.0590990000 0.0000270000 0.0005160000 0.0289840000 9626752 96830484 1766588416 3.4353466034 4.1681771278 5.1581935883 871 34.8000000000 0.0053591453 0.0093552582 0.0234041400 0.0080466514 0.0903080000 0.0085910000 0.0361470000 0.0003740000 0.0002790000 0.0350980000 9628426 96830484 1768382464 3.4343764782 4.1663417816 5.1589269638 872 34.8400000000 0.0052680951 0.0093505711 0.0234041400 0.0080423951 0.1082670000 0.0079480000 0.0529150000 0.0000290000 0.0003070000 0.0370970000 9630100 96830484 1770143744 3.4332933426 4.1631369591 5.1595563889 873 34.8800000000 0.0051404312 0.0093457485 0.0234041400 0.0080379411 0.1381850000 0.0097450000 0.0557490000 0.0003230000 0.0002740000 0.0621380000 9631774 96830484 1768923136 3.4328896999 4.1610379219 5.1609320641 874 34.9200000000 0.0051960330 0.0093410006 0.0234041400 0.0080340508 0.0956390000 0.0088200000 0.0429350000 0.0000300000 0.0003200000 0.0295660000 9633448 96830484 1770590208 3.4321920872 4.1598315239 5.1621184349 875 34.9600000000 0.0050678770 0.0093361170 0.0234041400 0.0080305382 0.0919450000 0.0104510000 0.0383360000 0.0003020000 0.0003610000 0.0324650000 9635122 96830484 1769558016 3.4306643009 4.1598458290 5.1635971069 876 35.0000000000 0.0051352964 0.0093313215 0.0234041400 0.0080267992 0.1024700000 0.0085350000 0.0388470000 0.0000270000 0.0003080000 0.0365930000 9636796 96830484 1768521728 3.4298913479 4.1590318680 5.1649417877 877 35.0400000000 0.0050764759 0.0093264699 0.0234041400 0.0080222343 0.1608060000 0.0080740000 0.0633970000 0.0003130000 0.0002680000 0.0538930000 9638470 96830484 1767645184 3.4290013313 4.1586966515 5.1663398743 878 35.0800000000 0.0051877159 0.0093217561 0.0234041400 0.0080178060 0.0956090000 0.0098860000 0.0417480000 0.0000290000 0.0020270000 0.0290340000 9640144 96830484 1766461440 3.4279804230 4.1590428352 5.1674957275 879 35.1200000000 0.0051598153 0.0093170212 0.0234041400 0.0080132651 0.0894450000 0.0086460000 0.0366200000 0.0003700000 0.0002840000 0.0336450000 9641818 96830484 1765478400 3.4271280766 4.1579728127 5.1685857773 880 35.1600000000 0.0051180124 0.0093122496 0.0234041400 0.0080090732 0.1057590000 0.0079890000 0.0476350000 0.0000290000 0.0003660000 0.0352550000 9643492 96830484 1764343808 3.4265038967 4.1588759422 5.1699271202 881 35.2000000000 0.0051857093 0.0093075657 0.0234041400 0.0080052118 0.1602090000 0.0077470000 0.0628760000 0.0003900000 0.0002840000 0.0541380000 9645166 96830484 1765969920 3.4254567623 4.1587615013 5.1712312698 882 35.2400000000 0.0050800606 0.0093027726 0.0234041400 0.0080018208 0.1133310000 0.0097410000 0.0499270000 0.0000260000 0.0003880000 0.0289930000 9646840 96830484 1767493632 3.4260027409 4.1547079086 5.1718630791 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-19 03:24:58 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000002920 0.0000002920 0.0000002920 nan 0.1023620000 0.0173210000 0.0169500000 0.0001000000 0.0000100000 0.0635630000 7868678 96830484 1770655744 4.0000000000 4.0000000000 4.0000000000 2 0.0400000000 0.0040127714 0.0020065317 0.0040127714 0.0032323198 0.0472550000 0.0122780000 0.0080340000 0.0009110000 0.0000050000 0.0253050000 8198304 96830484 1769148416 4.0000000000 4.0000000000 4.0000000000 3 0.0800000000 0.0039232424 0.0026454353 0.0040127714 0.0045263772 0.1068400000 0.0325750000 0.0301410000 0.0006730000 0.0000220000 0.0421890000 8200302 96830484 1767256064 4.0000000000 4.0000000000 4.0000000000 4 0.1200000000 0.0033563883 0.0028231735 0.0040127714 0.0050261360 0.0968410000 0.0222330000 0.0197960000 0.0002020000 0.0002650000 0.0533240000 8202324 96830484 1766113280 4.0000000000 4.0000000000 4.0000000000 5 0.1600000000 0.0020584480 0.0026702284 0.0040127714 0.0052620040 0.1396510000 0.0095890000 0.0622300000 0.0003810000 0.0002820000 0.0660110000 8204318 96830484 1765339136 4.0005674362 4.0062384605 4.0028867722 6 0.2000000000 0.0022279536 0.0025965160 0.0040127714 0.0049476665 0.1032490000 0.0095650000 0.0574240000 0.0000210000 0.0002950000 0.0348060000 8206648 96830484 1765081088 4.0035138130 3.9963679314 4.0019836426 7 0.2400000000 0.0023014175 0.0025543591 0.0040127714 0.0047215604 0.1032710000 0.0098340000 0.0509680000 0.0004040000 0.0002870000 0.0405070000 8208322 96830484 1764970496 4.0037331581 3.9863786697 3.9988594055 8 0.2800000000 0.0024058358 0.0025357936 0.0040127714 0.0043780790 0.0911480000 0.0099210000 0.0448780000 0.0000240000 0.0003210000 0.0349320000 8209996 96830484 1763807232 4.0014529228 3.9884290695 3.9979808331 9 0.3200000000 0.0023834214 0.0025188634 0.0040127714 0.0050587518 0.1200340000 0.0090140000 0.0450680000 0.0003030000 0.0003120000 0.0649560000 8212310 96830484 1763975168 4.0003538132 3.9923250675 4.0009708405 10 0.3600000000 0.0024723369 0.0025142107 0.0040127714 0.0047844902 0.0928560000 0.0092870000 0.0458020000 0.0000250000 0.0003610000 0.0360380000 8215296 96830484 1765613568 3.9983100891 3.9848978519 3.9990837574 11 0.4000000000 0.0026106657 0.0025229794 0.0040127714 0.0045836493 0.1453640000 0.0090940000 0.0938620000 0.0000570000 0.0000530000 0.0409610000 8216970 96830484 1767239680 3.9983108044 3.9888923168 3.9978291988 12 0.4400000000 0.0026466376 0.0025332842 0.0040127714 0.0046222946 0.0900070000 0.0097380000 0.0454020000 0.0000240000 0.0003760000 0.0333880000 8218644 96830484 1769017344 3.9992911816 3.9987828732 4.0008072853 13 0.4800000000 0.0025967760 0.0025381682 0.0040127714 0.0044295951 0.1208940000 0.0091450000 0.0454050000 0.0003040000 0.0003840000 0.0652760000 8220318 96830484 1770668032 4.0013036728 3.9965372086 4.0008158684 14 0.5200000000 0.0027372187 0.0025523861 0.0040127714 0.0043598152 0.0983920000 0.0111760000 0.0511950000 0.0000240000 0.0003120000 0.0338550000 8221992 96830484 1769410560 4.0040879250 3.9890961647 3.9980862141 15 0.5600000000 0.0027276226 0.0025640685 0.0040127714 0.0042910284 0.1113650000 0.0102990000 0.0640400000 0.0003730000 0.0002710000 0.0359780000 8223666 96830484 1767903232 4.0069079399 3.9907083511 3.9979023933 16 0.6000000000 0.0027499998 0.0025756892 0.0040127714 0.0041493365 0.0901130000 0.0095380000 0.0446410000 0.0000210000 0.0014840000 0.0338270000 8225340 96830484 1766739968 4.0079059601 3.9920754433 3.9981877804 17 0.6400000000 0.0027915987 0.0025883898 0.0040127714 0.0040347247 0.1355210000 0.0097150000 0.0526060000 0.0003170000 0.0003580000 0.0708150000 8228294 96830484 1765244928 4.0076589584 3.9883260727 3.9963281155 18 0.6800000000 0.0028616060 0.0026035685 0.0040127714 0.0039154018 0.1120990000 0.0092130000 0.0604470000 0.0000270000 0.0003400000 0.0416280000 8232592 96830484 1764978688 4.0069379807 3.9894137383 3.9949533939 19 0.7200000000 0.0028733131 0.0026177656 0.0040127714 0.0039408206 0.1081070000 0.0092000000 0.0566630000 0.0003090000 0.0002730000 0.0411460000 8234266 96830484 1764986880 4.0073790550 3.9935991764 3.9951674938 20 0.7600000000 0.0029136736 0.0026325610 0.0040127714 0.0041996213 0.0848460000 0.0091890000 0.0401970000 0.0000250000 0.0003020000 0.0329870000 8235940 96830484 1763819520 4.0069322586 3.9923043251 3.9925448895 21 0.8000000000 0.0028847996 0.0026445723 0.0040127714 0.0043455623 0.1162210000 0.0098670000 0.0454100000 0.0003900000 0.0003080000 0.0584270000 8237614 96830484 1763975168 4.0093746185 3.9954648018 3.9927828312 22 0.8400000000 0.0029365923 0.0026578460 0.0040127714 0.0042696657 0.1035310000 0.0100900000 0.0580490000 0.0000250000 0.0003330000 0.0331140000 8239288 96830484 1765613568 4.0094819069 3.9983503819 3.9931850433 23 0.8800000000 0.0030847939 0.0026764089 0.0040127714 0.0042417999 0.0927540000 0.0102280000 0.0441780000 0.0003120000 0.0003840000 0.0371820000 8240962 96830484 1767239680 4.0121822357 3.9920930862 3.9892170429 24 0.9200000000 0.0033510337 0.0027045183 0.0040127714 0.0042380637 0.0889130000 0.0090800000 0.0435710000 0.0000250000 0.0003740000 0.0353720000 8242636 96830484 1769017344 4.0144157410 3.9935758114 3.9894192219 25 0.9600000000 0.0033436674 0.0027300842 0.0040127714 0.0041504026 0.1268260000 0.0090470000 0.0460480000 0.0003060000 0.0002790000 0.0706400000 8244310 96830484 1770663936 4.0146045685 3.9905085564 3.9862887859 26 1.0000000000 0.0033614191 0.0027543664 0.0040127714 0.0040671635 0.0939830000 0.0116400000 0.0485240000 0.0000260000 0.0002900000 0.0329650000 8245984 96830484 1769537536 4.0128602982 3.9902772903 3.9853055477 27 1.0400000000 0.0033400382 0.0027760579 0.0040127714 0.0040004014 0.1093120000 0.0101370000 0.0574120000 0.0004870000 0.0002810000 0.0404700000 8247658 96830484 1768419328 4.0138974190 3.9860904217 3.9828312397 28 1.0800000000 0.0033537620 0.0027966902 0.0040127714 0.0039303283 0.0924820000 0.0101160000 0.0454080000 0.0000250000 0.0003110000 0.0361170000 8249332 96830484 1767288832 4.0126333237 3.9840540886 3.9814434052 29 1.1200000000 0.0033597255 0.0028161052 0.0040127714 0.0039414891 0.1164420000 0.0095810000 0.0437550000 0.0003180000 0.0003380000 0.0604690000 8251006 96830484 1766125568 4.0137362480 3.9820573330 3.9802517891 30 1.1600000000 0.0034485457 0.0028371866 0.0040127714 0.0039072430 0.1127270000 0.0141280000 0.0574940000 0.0000230000 0.0003870000 0.0383970000 8252680 96830484 1764855808 4.0170397758 3.9830815792 3.9798834324 31 1.2000000000 0.0036161647 0.0028623149 0.0040127714 0.0039111062 0.0879010000 0.0091050000 0.0358340000 0.0001960000 0.0002460000 0.0398430000 8254354 96830484 1764986880 4.0219879150 3.9843549728 3.9785194397 32 1.2400000000 0.0036406731 0.0028866386 0.0040127714 0.0039559013 0.0870220000 0.0097060000 0.0406240000 0.0000230000 0.0003650000 0.0339120000 8256028 96830484 1764970496 4.0223827362 3.9876074791 3.9773905277 33 1.2800000000 0.0037004391 0.0029112992 0.0040127714 0.0041795297 0.1138160000 0.0095710000 0.0431170000 0.0003190000 0.0003600000 0.0598640000 8260262 96830484 1764990976 4.0237021446 3.9915742874 3.9773099422 34 1.3200000000 0.0036784415 0.0029338622 0.0040127714 0.0043680980 0.0917830000 0.0095630000 0.0429070000 0.0000260000 0.0002770000 0.0358870000 8267184 96830484 1765588992 4.0318679810 3.9940259457 3.9749884605 35 1.3600000000 0.0036426303 0.0029541127 0.0040127714 0.0043061077 0.1015900000 0.0090830000 0.0497990000 0.0003630000 0.0002730000 0.0414650000 8268858 96830484 1764986880 4.0311307907 3.9926416874 3.9733855724 36 1.4000000000 0.0037399507 0.0029759416 0.0040127714 0.0042534671 0.0810750000 0.0092970000 0.0372180000 0.0000260000 0.0003520000 0.0335430000 8270532 96830484 1764970496 4.0315446854 3.9903743267 3.9700055122 37 1.4400000000 0.0036503619 0.0029941691 0.0040127714 0.0041952689 0.1367770000 0.0095340000 0.0502460000 0.0003180000 0.0002790000 0.0735300000 8272206 96830484 1764970496 4.0340600014 3.9892807007 3.9676885605 38 1.4800000000 0.0039302306 0.0030188023 0.0040127714 0.0041385495 0.0925130000 0.0097710000 0.0485730000 0.0000280000 0.0003140000 0.0331600000 8273880 96830484 1764990976 4.0342345238 3.9894709587 3.9674458504 39 1.5200000000 0.0038190051 0.0030393204 0.0040127714 0.0041046514 0.1034580000 0.0099850000 0.0425600000 0.0003270000 0.0003630000 0.0473420000 8275554 96830484 1764970496 4.0348224640 3.9902083874 3.9665136337 40 1.5600000000 0.0039660390 0.0030624883 0.0040127714 0.0043001556 0.0921060000 0.0091540000 0.0466490000 0.0000250000 0.0002820000 0.0352900000 8277228 96830484 1764970496 4.0379071236 3.9906201363 3.9656770229 41 1.6000000000 0.0039867833 0.0030850321 0.0040127714 0.0045462100 0.1238270000 0.0091230000 0.0440380000 0.0002990000 0.0002680000 0.0693730000 8278902 96830484 1764970496 4.0435161591 3.9923312664 3.9650828838 42 1.6400000000 0.0044846674 0.0031183568 0.0044846674 0.0045169757 0.0957330000 0.0090360000 0.0473470000 0.0000240000 0.0003530000 0.0382850000 8280576 96830484 1766473728 4.0445218086 3.9924125671 3.9638338089 43 1.6800000000 0.0042987792 0.0031458084 0.0044846674 0.0044984958 0.1012770000 0.0092320000 0.0433450000 0.0002970000 0.0002720000 0.0447880000 8282250 96830484 1768370176 4.0461382866 3.9921391010 3.9622652531 44 1.7200000000 0.0045085065 0.0031767788 0.0045085065 0.0044678944 0.1108950000 0.0087350000 0.0543350000 0.0000230000 0.0003150000 0.0441640000 8283924 96830484 1769910272 4.0483307838 3.9931688309 3.9621019363 45 1.7600000000 0.0046872688 0.0032103453 0.0046872688 0.0046640638 0.1273830000 0.0104560000 0.0467220000 0.0003850000 0.0002770000 0.0688430000 8285598 96830484 1768767488 4.0504102707 3.9947988987 3.9609925747 46 1.8000000000 0.0046753790 0.0032421938 0.0046872688 0.0047500979 0.1013610000 0.0092250000 0.0543170000 0.0000270000 0.0003160000 0.0340500000 8287272 96830484 1770557440 4.0517597198 3.9956576824 3.9602897167 47 1.8400000000 0.0043469672 0.0032656997 0.0046872688 0.0047452276 0.0960060000 0.0111040000 0.0463200000 0.0003270000 0.0003570000 0.0371680000 8288946 96830484 1769529344 4.0531120300 3.9980454445 3.9598872662 48 1.8800000000 0.0045089098 0.0032915999 0.0046872688 0.0047316124 0.0939150000 0.0095890000 0.0464250000 0.0000270000 0.0003460000 0.0342330000 8290620 96830484 1768402944 4.0551476479 3.9993133545 3.9601130486 49 1.9200000000 0.0044852593 0.0033159603 0.0046872688 0.0047578191 0.1234410000 0.0091120000 0.0460310000 0.0003250000 0.0003550000 0.0644540000 8292294 96830484 1769959424 4.0561594963 3.9968883991 3.9582459927 50 1.9600000000 0.0046155336 0.0033419517 0.0046872688 0.0047313401 0.1065730000 0.0174110000 0.0504830000 0.0000270000 0.0006650000 0.0341650000 8293968 96830484 1768370176 4.0514874458 3.9993257523 3.9562671185 51 2.0000000000 0.0044671916 0.0033640153 0.0046872688 0.0047245112 0.0994080000 0.0090240000 0.0451440000 0.0003160000 0.0002740000 0.0408810000 8295642 96830484 1770176512 4.0505285263 4.0037336349 3.9571313858 52 2.0400000000 0.0047122226 0.0033899423 0.0047122226 0.0047003531 0.0924640000 0.0109070000 0.0462540000 0.0000220000 0.0003820000 0.0341630000 8297316 96830484 1768640512 4.0510125160 4.0015044212 3.9568879604 53 2.0800000000 0.0046365256 0.0034134628 0.0047122226 0.0046648731 0.1371290000 0.0095130000 0.0566290000 0.0002840000 0.0002650000 0.0669130000 8298990 96830484 1767370752 4.0512051582 3.9970633984 3.9545476437 54 2.1200000000 0.0045997058 0.0034354302 0.0047122226 0.0046824287 0.0937810000 0.0094270000 0.0526310000 0.0000280000 0.0003260000 0.0306020000 8300664 96830484 1769050112 4.0513677597 3.9984407425 3.9549841881 55 2.1600000000 0.0045124972 0.0034550133 0.0047122226 0.0046720663 0.1024000000 0.0088420000 0.0459130000 0.0002910000 0.0003470000 0.0431090000 8302338 96830484 1770532864 4.0520801544 4.0007300377 3.9550130367 56 2.2000000000 0.0044306456 0.0034724353 0.0047122226 0.0046746646 0.1112990000 0.0102040000 0.0661310000 0.0000270000 0.0003370000 0.0337690000 8304012 96830484 1769402368 4.0534005165 3.9998857975 3.9541096687 57 2.2400000000 0.0045574410 0.0034914705 0.0047122226 0.0046953639 0.1256800000 0.0085180000 0.0509880000 0.0003260000 0.0003440000 0.0646530000 8305686 96830484 1770975232 4.0539312363 3.9971575737 3.9518043995 58 2.2800000000 0.0045830063 0.0035102900 0.0047122226 0.0048526395 0.0930740000 0.0105200000 0.0449330000 0.0000260000 0.0003800000 0.0363180000 8307360 96830484 1769529344 4.0575232506 3.9987654686 3.9523789883 59 2.3200000000 0.0047948300 0.0035320619 0.0047948300 0.0050187427 0.1039900000 0.0090010000 0.0435510000 0.0003050000 0.0002870000 0.0471190000 8309034 96830484 1768656896 4.0615334511 4.0016226768 3.9516851902 60 2.3600000000 0.0049526384 0.0035557382 0.0049526384 0.0050701593 0.0941450000 0.0081300000 0.0477800000 0.0000280000 0.0002970000 0.0370600000 8310708 96830484 1767886848 4.0651297569 3.9972324371 3.9490823746 61 2.4000000000 0.0049849260 0.0035791675 0.0049849260 0.0050606065 0.1370800000 0.0080110000 0.0452670000 0.0002940000 0.0003490000 0.0787050000 8312382 96830484 1766387712 4.0649242401 3.9946403503 3.9476425648 62 2.4400000000 0.0047018793 0.0035972757 0.0049849260 0.0050969370 0.1048260000 0.0087290000 0.0572800000 0.0000240000 0.0002980000 0.0346950000 8314056 96830484 1765228544 4.0665764809 3.9957633018 3.9481945038 63 2.4800000000 0.0050490871 0.0036203204 0.0050490871 0.0051358712 0.0953280000 0.0086390000 0.0433220000 0.0002160000 0.0001850000 0.0420770000 8315730 96830484 1764843520 4.0733814240 3.9973406792 3.9481499195 64 2.5200000000 0.0049290801 0.0036407697 0.0050490871 0.0051096783 0.0890600000 0.0083400000 0.0427750000 0.0000260000 0.0003200000 0.0354110000 8317404 96830484 1764962304 4.0755009651 3.9932105541 3.9442245960 65 2.5600000000 0.0049928990 0.0036615717 0.0050490871 0.0051006005 0.1603670000 0.0082230000 0.0780830000 0.0003140000 0.0003320000 0.0691300000 8324198 96830484 1764962304 4.0765776634 3.9943478107 3.9443871975 66 2.6000000000 0.0051058903 0.0036834553 0.0051058903 0.0050625300 0.0895890000 0.0082290000 0.0391930000 0.0000260000 0.0003400000 0.0377270000 8336368 96830484 1766719488 4.0738925934 3.9897966385 3.9425389767 67 2.6400000000 0.0051691225 0.0037056295 0.0051691225 0.0050947611 0.1067490000 0.0077760000 0.0452260000 0.0003360000 0.0003540000 0.0486480000 8338042 96830484 1768259584 4.0741314888 3.9883863926 3.9407274723 68 2.6800000000 0.0052279546 0.0037280166 0.0052279546 0.0051668601 0.1054020000 0.0077750000 0.0523550000 0.0000250000 0.0002800000 0.0408280000 8339716 96830484 1770147840 4.0792150497 3.9859166145 3.9403655529 69 2.7200000000 0.0050194524 0.0037467331 0.0052279546 0.0051837305 0.1502080000 0.0095810000 0.0562030000 0.0002890000 0.0003700000 0.0828510000 8341390 96830484 1768783872 4.0803675652 3.9865522385 3.9391827583 70 2.7600000000 0.0051316181 0.0037665172 0.0052279546 0.0052323510 0.0908910000 0.0082650000 0.0431290000 0.0000260000 0.0003850000 0.0381520000 8343064 96830484 1770704896 4.0830912590 3.9880158901 3.9385132790 71 2.8000000000 0.0052578063 0.0037875212 0.0052578063 0.0052788648 0.1077630000 0.0098850000 0.0436280000 0.0002890000 0.0002980000 0.0490230000 8344738 96830484 1769402368 4.0858616829 3.9886777401 3.9367773533 72 2.8400000000 0.0051917853 0.0038070249 0.0052578063 0.0052983795 0.1056680000 0.0079690000 0.0515680000 0.0000260000 0.0002860000 0.0410370000 8346412 96830484 1771212800 4.0874004364 3.9884264469 3.9358806610 73 2.8800000000 0.0051567452 0.0038255142 0.0052578063 0.0053400726 0.1432810000 0.0100800000 0.0430270000 0.0002950000 0.0002660000 0.0852620000 8348086 96830484 1769783296 4.0898256302 3.9910447598 3.9336352348 74 2.9200000000 0.0052077160 0.0038441926 0.0052578063 0.0054577023 0.0909370000 0.0101590000 0.0366110000 0.0000260000 0.0002830000 0.0395540000 8349760 96830484 1768046592 4.0917730331 3.9908578396 3.9306089878 75 2.9600000000 0.0052985507 0.0038635841 0.0052985507 0.0054995052 0.1085750000 0.0085340000 0.0450490000 0.0003020000 0.0002760000 0.0534170000 8351434 96830484 1766846464 4.0974693298 3.9908189774 3.9291646481 76 3.0000000000 0.0052520786 0.0038818537 0.0052985507 0.0055201034 0.0896190000 0.0078290000 0.0384830000 0.0000250000 0.0002980000 0.0419890000 8353108 96830484 1768538112 4.1008749008 3.9922838211 3.9274396896 77 3.0400000000 0.0051374701 0.0038981604 0.0052985507 0.0055426674 0.1265010000 0.0077690000 0.0393590000 0.0001970000 0.0001730000 0.0780260000 8354782 96830484 1770151936 4.1035480499 3.9928736687 3.9264070988 78 3.0800000000 0.0050570983 0.0039130186 0.0052985507 0.0055140209 0.0928060000 0.0096970000 0.0425750000 0.0000280000 0.0004250000 0.0390620000 8356456 96830484 1769148416 4.1065850258 3.9903497696 3.9228320122 79 3.1200000000 0.0049942629 0.0039267052 0.0052985507 0.0055353211 0.0894830000 0.0081720000 0.0338670000 0.0000730000 0.0000630000 0.0460710000 8358130 96830484 1769275392 4.1102395058 3.9917402267 3.9223649502 80 3.1600000000 0.0050251195 0.0039404354 0.0052985507 0.0055192700 0.0892460000 0.0084040000 0.0425400000 0.0000250000 0.0002970000 0.0369340000 8359804 96830484 1768644608 4.1140961647 3.9913799763 3.9194910526 81 3.2000000000 0.0050367448 0.0039539701 0.0052985507 0.0054981102 0.1215130000 0.0084290000 0.0348150000 0.0002090000 0.0002160000 0.0767950000 8361478 96830484 1767014400 4.1197075844 3.9899468422 3.9178786278 82 3.2400000000 0.0049995645 0.0039667213 0.0052985507 0.0054710478 0.1031230000 0.0079550000 0.0463760000 0.0000280000 0.0002910000 0.0436520000 8363152 96830484 1765994496 4.1236920357 3.9884843826 3.9155642986 83 3.2800000000 0.0050442712 0.0039797038 0.0052985507 0.0054579753 0.1315030000 0.0074670000 0.0548730000 0.0003670000 0.0004600000 0.0648060000 8364826 96830484 1764941824 4.1255984306 3.9883244038 3.9134359360 84 3.3200000000 0.0050518187 0.0039924671 0.0052985507 0.0054342086 0.1052230000 0.0074770000 0.0384350000 0.0000190000 0.0002060000 0.0540520000 8366500 96830484 1764831232 4.1318545341 3.9879934788 3.9106462002 85 3.3600000000 0.0050697178 0.0040051406 0.0052985507 0.0054046120 0.1630060000 0.0073290000 0.0474180000 0.0003060000 0.0003890000 0.1023220000 8368174 96830484 1763811328 4.1423273087 3.9913778305 3.9105865955 86 3.4000000000 0.0051006856 0.0040178795 0.0052985507 0.0054183848 0.0938650000 0.0082090000 0.0434460000 0.0000260000 0.0003840000 0.0405380000 8369848 96830484 1765466112 4.1449284554 3.9936671257 3.9082803726 87 3.4400000000 0.0051415176 0.0040307949 0.0052985507 0.0054132254 0.1063960000 0.0078100000 0.0423430000 0.0003190000 0.0003440000 0.0511380000 8371522 96830484 1767104512 4.1471118927 3.9930377007 3.9054021835 88 3.4800000000 0.0051168944 0.0040431369 0.0052985507 0.0053882674 0.1022540000 0.0074930000 0.0400400000 0.0000260000 0.0003710000 0.0486900000 8373196 96830484 1769005056 4.1524996758 3.9958410263 3.9047274590 89 3.5200000000 0.0051179053 0.0040552130 0.0052985507 0.0053711735 0.1678180000 0.0074820000 0.0698960000 0.0003230000 0.0003890000 0.0839760000 8374870 96830484 1770655744 4.1555533409 3.9961588383 3.9035234451 90 3.5600000000 0.0053618494 0.0040697311 0.0053618494 0.0053444666 0.0911580000 0.0095400000 0.0443360000 0.0000270000 0.0002890000 0.0358460000 8376544 96830484 1769402368 4.1587157249 3.9964628220 3.9019398689 91 3.6000000000 0.0054226108 0.0040845980 0.0054226108 0.0053803500 0.1267120000 0.0083700000 0.0627640000 0.0003590000 0.0002810000 0.0491530000 8378218 96830484 1768116224 4.1651806831 3.9967246056 3.9009675980 92 3.6400000000 0.0053551919 0.0040984088 0.0054226108 0.0054532924 0.0900350000 0.0082150000 0.0359060000 0.0000270000 0.0003480000 0.0443180000 8379892 96830484 1769803776 4.1743893623 3.9995653629 3.9010136127 93 3.6800000000 0.0053314115 0.0041116669 0.0054226108 0.0054674645 0.1293090000 0.0094290000 0.0352060000 0.0000800000 0.0000710000 0.0834170000 8381566 96830484 1768288256 4.1824688911 4.0035901070 3.8995640278 94 3.7200000000 0.0052972999 0.0041242800 0.0054226108 0.0054444039 0.0892820000 0.0074160000 0.0353200000 0.0000080000 0.0000760000 0.0452850000 8383240 96830484 1769902080 4.1907601357 4.0028100014 3.8969960213 95 3.7600000000 0.0052803620 0.0041364493 0.0054226108 0.0054171396 0.1264290000 0.0094060000 0.0465430000 0.0002940000 0.0002710000 0.0642650000 8384914 96830484 1768759296 4.1968235970 4.0028247833 3.8945274353 96 3.8000000000 0.0053357203 0.0041489417 0.0054226108 0.0054019906 0.1053820000 0.0076130000 0.0396910000 0.0000250000 0.0002820000 0.0518810000 8386588 96830484 1770565632 4.2043542862 4.0015506744 3.8925285339 97 3.8400000000 0.0053119445 0.0041609314 0.0054226108 0.0053760765 0.1410150000 0.0094850000 0.0412260000 0.0003690000 0.0002750000 0.0884110000 8388262 96830484 1769521152 4.2122282982 4.0030899048 3.8894290924 98 3.8800000000 0.0053398418 0.0041729611 0.0054226108 0.0053493290 0.1035800000 0.0098220000 0.0422550000 0.0000100000 0.0001080000 0.0460010000 8389936 96830484 1771094016 4.2207140923 4.0032181740 3.8886060715 99 3.9200000000 0.0053403308 0.0041847527 0.0054226108 0.0053594102 0.1330450000 0.0095670000 0.0609790000 0.0003190000 0.0003770000 0.0577210000 8391610 96830484 1769631744 4.2289257050 4.0025739670 3.8866949081 100 3.9600000000 0.0053950832 0.0041968560 0.0054226108 0.0053343263 0.0908410000 0.0077200000 0.0405730000 0.0000270000 0.0005080000 0.0407660000 8393284 96830484 1771347968 4.2365450859 4.0030832291 3.8862676620 101 4.0000000000 0.0053847381 0.0042086172 0.0054226108 0.0053237217 0.1350720000 0.0096990000 0.0420160000 0.0003560000 0.0002780000 0.0814490000 8394958 96830484 1770029056 4.2451539040 4.0052194595 3.8849558830 102 4.0400000000 0.0055169007 0.0042214435 0.0055169007 0.0053345018 0.1091910000 0.0124810000 0.0437190000 0.0000250000 0.0003200000 0.0466040000 8396632 96830484 1767997440 4.2498669624 4.0046529770 3.8828976154 103 4.0800000000 0.0055205366 0.0042340561 0.0055205366 0.0053091875 0.1495420000 0.0077600000 0.0722490000 0.0006740000 0.0003150000 0.0618910000 8398306 96830484 1769783296 4.2579045296 4.0080895424 3.8836789131 104 4.1200000000 0.0055599371 0.0042468049 0.0055599371 0.0052845169 0.1280960000 0.0096660000 0.0644070000 0.0000250000 0.0003850000 0.0478540000 8399980 96830484 1768378368 4.2683677673 4.0107350349 3.8829421997 105 4.1600000000 0.0055899820 0.0042595971 0.0055899820 0.0052767970 0.1187500000 0.0074280000 0.0338870000 0.0003180000 0.0002770000 0.0753940000 8401654 96830484 1770156032 4.2749261856 4.0120882988 3.8827199936 106 4.2000000000 0.0056612990 0.0042728207 0.0056612990 0.0052889098 0.1009630000 0.0138440000 0.0421850000 0.0000110000 0.0001120000 0.0434740000 8403328 96830484 1768996864 4.2819852829 4.0102577209 3.8801584244 107 4.2400000000 0.0055985078 0.0042852103 0.0056612990 0.0052663233 0.1099740000 0.0078450000 0.0427850000 0.0003620000 0.0002770000 0.0574180000 8405002 96830484 1767399424 4.2898216248 4.0093164444 3.8789520264 108 4.2800000000 0.0056290352 0.0042976531 0.0056612990 0.0052502990 0.0912990000 0.0076630000 0.0407220000 0.0000250000 0.0002920000 0.0413100000 8406676 96830484 1766215680 4.2985057831 4.0095143318 3.8771848679 109 4.3200000000 0.0055561294 0.0043091988 0.0056612990 0.0052303160 0.1337500000 0.0075100000 0.0417360000 0.0003220000 0.0003440000 0.0825610000 8408350 96830484 1764966400 4.3155407906 4.0091118813 3.8746392727 110 4.3600000000 0.0057229227 0.0043220508 0.0057229227 0.0052277387 0.0953590000 0.0083760000 0.0340530000 0.0000240000 0.0002920000 0.0456970000 8410024 96830484 1764950016 4.3276729584 4.0103597641 3.8738629818 111 4.4000000000 0.0057095070 0.0043345504 0.0057229227 0.0052042940 0.1304790000 0.0074520000 0.0494640000 0.0003220000 0.0004480000 0.0689400000 8411698 96830484 1764954112 4.3374929428 4.0095000267 3.8721609116 112 4.4400000000 0.0056971703 0.0043467167 0.0057229227 0.0051892231 0.1264220000 0.0073960000 0.0473550000 0.0000220000 0.0002960000 0.0642060000 8413372 96830484 1764954112 4.3432860374 4.0053067207 3.8694334030 113 4.4800000000 0.0056711435 0.0043584372 0.0057229227 0.0051660159 0.1524900000 0.0076660000 0.0499380000 0.0002890000 0.0002710000 0.0929020000 8415046 96830484 1766711296 4.3523006439 4.0045905113 3.8687887192 114 4.5200000000 0.0057465583 0.0043706137 0.0057465583 0.0051497099 0.1034700000 0.0078190000 0.0418180000 0.0000240000 0.0003060000 0.0465050000 8416720 96830484 1768235008 4.3631615639 4.0046863556 3.8679230213 115 4.5600000000 0.0056847846 0.0043820413 0.0057465583 0.0051366789 0.1321710000 0.0074890000 0.0670020000 0.0003900000 0.0003080000 0.0556160000 8418394 96830484 1770012672 4.3731217384 4.0027022362 3.8666179180 116 4.6000000000 0.0056569423 0.0043930318 0.0057465583 0.0051165759 0.1079480000 0.0095320000 0.0440220000 0.0000240000 0.0003050000 0.0497100000 8420068 96830484 1768632320 4.3810024261 3.9996685982 3.8650109768 117 4.6400000000 0.0056704823 0.0044039502 0.0057465583 0.0051207173 0.1516220000 0.0079710000 0.0439010000 0.0001960000 0.0002190000 0.0979610000 8421742 96830484 1770422272 4.3884582520 3.9971795082 3.8638668060 118 4.6800000000 0.0056924117 0.0044148694 0.0057465583 0.0051340452 0.1004240000 0.0100070000 0.0364790000 0.0000240000 0.0002870000 0.0469710000 8423416 96830484 1769267200 4.3976001740 3.9972603321 3.8635232449 119 4.7200000000 0.0056381226 0.0044251488 0.0057465583 0.0051728593 0.1320710000 0.0078930000 0.0537760000 0.0003510000 0.0002760000 0.0683040000 8425090 96830484 1770950656 4.4117245674 3.9979004860 3.8653900623 120 4.7600000000 0.0057493504 0.0044361838 0.0057493504 0.0051514485 0.1094490000 0.0098320000 0.0462250000 0.0000240000 0.0003090000 0.0516480000 8426764 96830484 1769521152 4.4229984283 3.9999001026 3.8668017387 121 4.8000000000 0.0057022399 0.0044466471 0.0057493504 0.0051472254 0.1455970000 0.0078310000 0.0428220000 0.0003920000 0.0002760000 0.0873740000 8428438 96830484 1771028480 4.4315042496 3.9984929562 3.8652753830 122 4.8400000000 0.0057766116 0.0044575485 0.0057766116 0.0051460399 0.0914930000 0.0103570000 0.0348660000 0.0000080000 0.0000790000 0.0447490000 8430112 96830484 1769766912 4.4405755997 3.9990491867 3.8647367954 123 4.8800000000 0.0057300995 0.0044678944 0.0057766116 0.0051258386 0.1273240000 0.0082280000 0.0483240000 0.0002990000 0.0002780000 0.0686570000 8431786 96830484 1768243200 4.4518442154 4.0015025139 3.8667614460 124 4.9200000000 0.0058413493 0.0044789707 0.0058413493 0.0051066310 0.1089480000 0.0077960000 0.0460630000 0.0000240000 0.0002940000 0.0532100000 8433460 96830484 1769922560 4.4582505226 4.0030841827 3.8700127602 125 4.9600000000 0.0057790214 0.0044893711 0.0058413493 0.0050986210 0.1457820000 0.0095910000 0.0441660000 0.0002960000 0.0003490000 0.0899290000 8435134 96830484 1768407040 4.4617037773 4.0026473999 3.8714387417 126 5.0000000000 0.0059276256 0.0045007858 0.0059276256 0.0050849648 0.0924370000 0.0076010000 0.0356200000 0.0000090000 0.0000920000 0.0471380000 8436808 96830484 1770160128 4.4711318016 4.0028510094 3.8731276989 127 5.0400000000 0.0059243571 0.0045119950 0.0059276256 0.0050676571 0.1264500000 0.0097510000 0.0466900000 0.0003520000 0.0002690000 0.0618320000 8438482 96830484 1768624128 4.4812998772 4.0027093887 3.8752958775 128 5.0800000000 0.0059471787 0.0045232074 0.0059471787 0.0050617316 0.1108670000 0.0076780000 0.0476730000 0.0000250000 0.0002890000 0.0537220000 8440156 96830484 1770450944 4.4930911064 4.0041337013 3.8786742687 129 5.1200000000 0.0059160148 0.0045340043 0.0059471787 0.0050540132 0.1649070000 0.0095710000 0.0483720000 0.0003010000 0.0003500000 0.0985750000 8452070 96830484 1769115648 4.5041451454 4.0054826736 3.8822391033 130 5.1600000000 0.0060295425 0.0045455085 0.0060295425 0.0050361901 0.1053600000 0.0082460000 0.0437840000 0.0000290000 0.0010480000 0.0447360000 8474736 96830484 1770688512 4.5108404160 4.0064239502 3.8846938610 131 5.2000000000 0.0060330816 0.0045568640 0.0060330816 0.0050718692 0.1104820000 0.0105850000 0.0425570000 0.0003720000 0.0009460000 0.0516280000 8476410 96830484 1769259008 4.5175075531 4.0055208206 3.8878240585 132 5.2400000000 0.0059435642 0.0045673693 0.0060330816 0.0050574778 0.1039330000 0.0084030000 0.0423610000 0.0000270000 0.0002890000 0.0448650000 8478084 96830484 1770958848 4.5282168388 4.0059967041 3.8916342258 133 5.2800000000 0.0058933799 0.0045773393 0.0060330816 0.0050384217 0.1356450000 0.0101330000 0.0428060000 0.0002910000 0.0002660000 0.0805660000 8479758 96830484 1769529344 4.5387849808 4.0069055557 3.8960564137 134 5.3200000000 0.0059458842 0.0045875523 0.0060330816 0.0050856335 0.1043130000 0.0080990000 0.0436840000 0.0000280000 0.0002840000 0.0472020000 8481432 96830484 1771212800 4.5474796295 4.0064573288 3.8986992836 135 5.3600000000 0.0059992671 0.0045980095 0.0060330816 0.0050996900 0.1099230000 0.0098590000 0.0368500000 0.0001980000 0.0001730000 0.0588500000 8483106 96830484 1769639936 4.5572023392 4.0076370239 3.9021444321 136 5.4000000000 0.0060029272 0.0046083397 0.0060330816 0.0051262641 0.1237490000 0.0095450000 0.0483520000 0.0000250000 0.0003630000 0.0573400000 8484780 96830484 1767989248 4.5713100433 4.0152645111 3.9084045887 137 5.4400000000 0.0059783030 0.0046183395 0.0060330816 0.0051225608 0.1716720000 0.0077470000 0.0495090000 0.0003660000 0.0002840000 0.1056850000 8486454 96830484 1769668608 4.5764141083 4.0192475319 3.9122540951 138 5.4800000000 0.0060735461 0.0046288845 0.0060735461 0.0051680529 0.1080760000 0.0097720000 0.0457340000 0.0000280000 0.0003140000 0.0446870000 8488128 96830484 1768263680 4.5801625252 4.0180749893 3.9150266647 139 5.5200000000 0.0060759927 0.0046392953 0.0060759927 0.0051495208 0.1106460000 0.0082850000 0.0429820000 0.0009410000 0.0002890000 0.0521910000 8489802 96830484 1769893888 4.5890235901 4.0188117027 3.9199886322 140 5.5600000000 0.0061393515 0.0046500100 0.0061393515 0.0051331505 0.1060250000 0.0102490000 0.0431280000 0.0000940000 0.0010490000 0.0446050000 8491476 96830484 1768386560 4.5973992348 4.0201997757 3.9251382351 141 5.6000000000 0.0061026849 0.0046603127 0.0061393515 0.0051150973 0.1339840000 0.0080200000 0.0436330000 0.0008740000 0.0002920000 0.0794460000 8493150 96830484 1770160128 4.6060743332 4.0210452080 3.9299621582 142 5.6400000000 0.0060700397 0.0046702403 0.0061393515 0.0051003091 0.1052700000 0.0099610000 0.0428690000 0.0000230000 0.0003510000 0.0472240000 8494824 96830484 1768640512 4.6169929504 4.0214338303 3.9351365566 143 5.6800000000 0.0060751433 0.0046800648 0.0061393515 0.0050904787 0.1265890000 0.0075600000 0.0472190000 0.0003620000 0.0002850000 0.0619230000 8496498 96830484 1770430464 4.6259346008 4.0235395432 3.9404463768 144 5.7200000000 0.0060913297 0.0046898653 0.0061393515 0.0051095486 0.1102650000 0.0093610000 0.0404200000 0.0000280000 0.0003100000 0.0538950000 8498172 96830484 1769259008 4.6319603920 4.0235042572 3.9448893070 145 5.7600000000 0.0060698520 0.0046993824 0.0061393515 0.0050967950 0.1678370000 0.0077640000 0.0528270000 0.0003060000 0.0002800000 0.0986200000 8499846 96830484 1770938368 4.6399083138 4.0239825249 3.9501924515 146 5.8000000000 0.0061010313 0.0047089827 0.0061393515 0.0050818045 0.0936140000 0.0102760000 0.0375110000 0.0000070000 0.0000800000 0.0440340000 8501520 96830484 1769529344 4.6496682167 4.0256052017 3.9563724995 147 5.8400000000 0.0060022110 0.0047177802 0.0061393515 0.0050645789 0.1082640000 0.0080690000 0.0372870000 0.0002970000 0.0003600000 0.0605400000 8503194 96830484 1768652800 4.6589918137 4.0294895172 3.9624922276 148 5.8800000000 0.0061066672 0.0047271646 0.0061393515 0.0050880558 0.0998660000 0.0077970000 0.0441940000 0.0000280000 0.0003080000 0.0458320000 8504868 96830484 1767870464 4.6632933617 4.0291781425 3.9671692848 149 5.9200000000 0.0061573549 0.0047367632 0.0061573549 0.0050731110 0.1247510000 0.0074510000 0.0362040000 0.0003110000 0.0002670000 0.0786960000 8506542 96830484 1766350848 4.6691074371 4.0286149979 3.9715292454 150 5.9600000000 0.0061066644 0.0047458959 0.0061573549 0.0050792448 0.0997110000 0.0083650000 0.0491880000 0.0000260000 0.0003330000 0.0388580000 8508216 96830484 1765212160 4.6770429611 4.0318393707 3.9775440693 151 6.0000000000 0.0060382602 0.0047544546 0.0061573549 0.0050760730 0.1362420000 0.0074310000 0.0550230000 0.0002990000 0.0003530000 0.0680940000 8509890 96830484 1764827136 4.6848592758 4.0338835716 3.9822421074 152 6.0400000000 0.0060454197 0.0047629477 0.0061573549 0.0050832827 0.1278220000 0.0081500000 0.0474130000 0.0000270000 0.0003830000 0.0643590000 8511564 96830484 1764687872 4.6980729103 4.0334734917 3.9913334846 153 6.0800000000 0.0060489392 0.0047713529 0.0061573549 0.0051023144 0.1497590000 0.0076570000 0.0510570000 0.0003050000 0.0003570000 0.0885680000 8513238 96830484 1766387712 4.7058382034 4.0345540047 3.9967093468 154 6.1200000000 0.0060302219 0.0047795274 0.0061573549 0.0050859767 0.1088410000 0.0075800000 0.0517700000 0.0000270000 0.0003190000 0.0429360000 8514912 96830484 1768116224 4.7120246887 4.0361847878 4.0017485619 155 6.1600000000 0.0060113384 0.0047874746 0.0061573549 0.0050855916 0.1126120000 0.0081010000 0.0498650000 0.0003030000 0.0015730000 0.0509290000 8516586 96830484 1769766912 4.7163062096 4.0360507965 4.0059566498 156 6.2000000000 0.0060213567 0.0047953841 0.0061573549 0.0050982118 0.1051780000 0.0092260000 0.0403100000 0.0000270000 0.0002950000 0.0458930000 8518260 96830484 1768660992 4.7250099182 4.0375318527 4.0115652084 157 6.2400000000 0.0060294685 0.0048032445 0.0061573549 0.0051086885 0.1510070000 0.0076710000 0.0546620000 0.0002940000 0.0003550000 0.0862010000 8519934 96830484 1770303488 4.7316813469 4.0387496948 4.0176062584 158 6.2800000000 0.0060438761 0.0048110966 0.0061573549 0.0051181961 0.1076660000 0.0101040000 0.0438070000 0.0000380000 0.0013330000 0.0430210000 8521608 96830484 1768894464 4.7362785339 4.0396800041 4.0233774185 159 6.3200000000 0.0060289633 0.0048187561 0.0061573549 0.0051476738 0.1095330000 0.0082500000 0.0451920000 0.0003970000 0.0002860000 0.0492640000 8523282 96830484 1770639360 4.7436208725 4.0417761803 4.0302038193 160 6.3600000000 0.0059628799 0.0048259069 0.0061573549 0.0052032482 0.1089700000 0.0101050000 0.0441350000 0.0000960000 0.0003150000 0.0424610000 8524956 96830484 1769512960 4.7569541931 4.0455675125 4.0445919037 161 6.4000000000 0.0060305437 0.0048333891 0.0061573549 0.0052264230 0.1328270000 0.0084680000 0.0462630000 0.0005130000 0.0002920000 0.0753430000 8526630 96830484 1771196416 4.7611379623 4.0478286743 4.0513195992 162 6.4400000000 0.0059307651 0.0048401630 0.0061573549 0.0052163225 0.1169360000 0.0099000000 0.0695240000 0.0000870000 0.0002880000 0.0351930000 8528304 96830484 1769766912 4.7662172318 4.0501766205 4.0590524673 163 6.4800000000 0.0058892411 0.0048465991 0.0061573549 0.0052249841 0.1004180000 0.0122620000 0.0377460000 0.0002920000 0.0002740000 0.0478620000 8529978 96830484 1768009728 4.7727494240 4.0508723259 4.0670804977 164 6.5200000000 0.0058246651 0.0048525629 0.0061573549 0.0052355014 0.1044580000 0.0078390000 0.0433860000 0.0000270000 0.0003700000 0.0435830000 8531652 96830484 1769648128 4.7805194855 4.0506706238 4.0751376152 165 6.5600000000 0.0058317548 0.0048584974 0.0061573549 0.0052418269 0.1678300000 0.0093980000 0.0603390000 0.0003770000 0.0002800000 0.0882230000 8533326 96830484 1768263680 4.7891573906 4.0535707474 4.0839738846 166 6.6000000000 0.0058087180 0.0048642216 0.0061573549 0.0052639918 0.0949270000 0.0082820000 0.0474250000 0.0000240000 0.0003820000 0.0369240000 8535000 96830484 1769906176 4.7971391678 4.0574989319 4.0930433273 167 6.6400000000 0.0057810303 0.0048697115 0.0061573549 0.0053155011 0.1069330000 0.0094150000 0.0412910000 0.0003330000 0.0002860000 0.0496410000 8536674 96830484 1768734720 4.8014888763 4.0593228340 4.1012334824 168 6.6800000000 0.0057380670 0.0048748803 0.0061573549 0.0053191543 0.0902890000 0.0076310000 0.0414950000 0.0000240000 0.0003110000 0.0388820000 8538348 96830484 1770430464 4.8085722923 4.0617160797 4.1099858284 169 6.7200000000 0.0057138004 0.0048798443 0.0061573549 0.0053130068 0.1306330000 0.0097200000 0.0440410000 0.0003680000 0.0002750000 0.0742530000 8540022 96830484 1769275392 4.8173160553 4.0663104057 4.1206240654 170 6.7600000000 0.0057245800 0.0048848133 0.0061573549 0.0053265515 0.1050570000 0.0081340000 0.0454560000 0.0000250000 0.0002910000 0.0415380000 8541696 96830484 1771065344 4.8230280876 4.0676465034 4.1288967133 171 6.8000000000 0.0056700935 0.0048894056 0.0061573549 0.0053110492 0.1302710000 0.0099230000 0.0616570000 0.0003170000 0.0002920000 0.0500130000 8543370 96830484 1769910272 4.8323879242 4.0704755783 4.1391487122 172 6.8400000000 0.0056625106 0.0048939004 0.0061573549 0.0052956067 0.0892310000 0.0097690000 0.0322820000 0.0000060000 0.0000720000 0.0402770000 8545044 96830484 1768136704 4.8404417038 4.0731782913 4.1494412422 173 6.8800000000 0.0056473603 0.0048982557 0.0061573549 0.0052807912 0.1356270000 0.0107290000 0.0477180000 0.0003880000 0.0002800000 0.0662300000 8546718 96830484 1766715392 4.8442859650 4.0731334686 4.1566591263 174 6.9200000000 0.0056726779 0.0049027064 0.0061573549 0.0052739523 0.0937360000 0.0083670000 0.0443700000 0.0000250000 0.0003120000 0.0387090000 8548392 96830484 1768398848 4.8527293205 4.0753998756 4.1664071083 175 6.9600000000 0.0056423671 0.0049069330 0.0061573549 0.0052617640 0.1075910000 0.0081280000 0.0456750000 0.0003870000 0.0002730000 0.0448450000 8550066 96830484 1770147840 4.8624186516 4.0791659355 4.1769008636 176 7.0000000000 0.0056794323 0.0049113222 0.0061573549 0.0052469016 0.0918490000 0.0101870000 0.0419710000 0.0000260000 0.0002900000 0.0373670000 8551740 96830484 1768894464 4.8692741394 4.0817041397 4.1868510246 177 7.0400000000 0.0055979765 0.0049152016 0.0061573549 0.0052877200 0.1449320000 0.0081030000 0.0477020000 0.0002920000 0.0002650000 0.0785810000 8553414 96830484 1767731200 4.8739604950 4.0814566612 4.1950302124 178 7.0800000000 0.0055368855 0.0049186942 0.0061573549 0.0053153750 0.1056120000 0.0080830000 0.0494960000 0.0000280000 0.0003830000 0.0380530000 8555088 96830484 1767002112 4.8782396317 4.0814299583 4.2028574944 179 7.1200000000 0.0055213110 0.0049220608 0.0061573549 0.0053009617 0.1072390000 0.0081540000 0.0489560000 0.0003180000 0.0002710000 0.0440920000 8556762 96830484 1765720064 4.8843045235 4.0839400291 4.2120466232 180 7.1600000000 0.0055010691 0.0049252775 0.0061573549 0.0052912981 0.1010830000 0.0083710000 0.0445090000 0.0000270000 0.0003160000 0.0376820000 8558436 96830484 1764818944 4.8906345367 4.0852141380 4.2211465836 181 7.2000000000 0.0054976288 0.0049284397 0.0061573549 0.0052768610 0.1235640000 0.0084700000 0.0451780000 0.0003170000 0.0003620000 0.0671410000 8560110 96830484 1764696064 4.8944253922 4.0859780312 4.2299895287 182 7.2400000000 0.0055210143 0.0049316956 0.0061573549 0.0052632478 0.0960950000 0.0076700000 0.0449490000 0.0000260000 0.0002940000 0.0387190000 8561784 96830484 1766514688 4.9002623558 4.0878515244 4.2386097908 183 7.2800000000 0.0054383860 0.0049344644 0.0061573549 0.0052490123 0.1099120000 0.0078770000 0.0476570000 0.0002960000 0.0002780000 0.0516540000 8563458 96830484 1768243200 4.9055213928 4.0899486542 4.2479681969 184 7.3200000000 0.0053948131 0.0049369663 0.0061573549 0.0052414273 0.1039090000 0.0077090000 0.0450510000 0.0000270000 0.0004760000 0.0402800000 8565132 96830484 1770020864 4.9109878540 4.0905728340 4.2555222511 185 7.3600000000 0.0054216827 0.0049395864 0.0061573549 0.0052319934 0.1459420000 0.0093540000 0.0682740000 0.0004710000 0.0002770000 0.0654070000 8566806 96830484 1768878080 4.9146995544 4.0901780128 4.2616591454 186 7.4000000000 0.0054227798 0.0049421842 0.0061573549 0.0052188322 0.0937050000 0.0079470000 0.0395130000 0.0000250000 0.0002880000 0.0372520000 8568480 96830484 1770541056 4.9201245308 4.0918116570 4.2710485458 187 7.4400000000 0.0053484552 0.0049443567 0.0061573549 0.0052186795 0.1303560000 0.0098770000 0.0665110000 0.0003930000 0.0002840000 0.0458580000 8570154 96830484 1769402368 4.9250731468 4.0927572250 4.2783331871 188 7.4800000000 0.0053255740 0.0049463845 0.0061573549 0.0052053957 0.1042770000 0.0078800000 0.0508940000 0.0000250000 0.0002930000 0.0349960000 8571828 96830484 1771085824 4.9292154312 4.0936365128 4.2850298882 189 7.5200000000 0.0053210258 0.0049483667 0.0061573549 0.0051923920 0.1227330000 0.0104220000 0.0450320000 0.0003230000 0.0002760000 0.0645080000 8573502 96830484 1769656320 4.9323039055 4.0935063362 4.2914481163 190 7.5600000000 0.0052824141 0.0049501249 0.0061573549 0.0051838942 0.0974350000 0.0098960000 0.0448200000 0.0000230000 0.0003540000 0.0364530000 8575176 96830484 1767735296 4.9374551773 4.0942306519 4.2994875908 191 7.6000000000 0.0052180463 0.0049515276 0.0061573549 0.0051747699 0.1117720000 0.0081140000 0.0534580000 0.0003560000 0.0002720000 0.0474060000 8576850 96830484 1767616512 4.9411678314 4.0960941315 4.3077373505 192 7.6400000000 0.0052522602 0.0049530939 0.0061573549 0.0051617834 0.0821190000 0.0079900000 0.0442450000 0.0000250000 0.0002930000 0.0274680000 8578524 96830484 1766871040 4.9439320564 4.0977220535 4.3161911964 193 7.6800000000 0.0051750736 0.0049542441 0.0061573549 0.0051496732 0.1300810000 0.0077540000 0.0480070000 0.0003590000 0.0002790000 0.0633340000 8580198 96830484 1765576704 4.9493479729 4.0995388031 4.3316097260 194 7.7200000000 0.0052066022 0.0049555449 0.0061573549 0.0051363405 0.1016470000 0.0082850000 0.0486010000 0.0000280000 0.0003930000 0.0340650000 8581872 96830484 1764839424 4.9530467987 4.1020269394 4.3403658867 195 7.7600000000 0.0050939457 0.0049562546 0.0061573549 0.0051232968 0.1062480000 0.0084680000 0.0468130000 0.0003210000 0.0002770000 0.0392730000 8583546 96830484 1764945920 4.9578199387 4.1034331322 4.3589296341 196 7.8000000000 0.0052108094 0.0049575534 0.0061573549 0.0051170010 0.0903980000 0.0085970000 0.0446010000 0.0000910000 0.0003090000 0.0331820000 8585220 96830484 1764319232 4.9581122398 4.1025886536 4.3676347733 197 7.8400000000 0.0051970184 0.0049587689 0.0061573549 0.0051051985 0.1272990000 0.0088100000 0.0437470000 0.0003250000 0.0002820000 0.0647620000 8586894 96830484 1764843520 4.9607629776 4.1033344269 4.3778390884 198 7.8800000000 0.0050696060 0.0049593287 0.0061573549 0.0050924169 0.0902000000 0.0085440000 0.0445480000 0.0000290000 0.0003200000 0.0329820000 8588568 96830484 1766498304 4.9627189636 4.1039152145 4.3887772560 199 7.9200000000 0.0051633017 0.0049603537 0.0061573549 0.0050872169 0.1082080000 0.0085380000 0.0515760000 0.0003810000 0.0002790000 0.0389350000 8590242 96830484 1768116224 4.9628825188 4.1031379700 4.3988327980 200 7.9600000000 0.0051619150 0.0049613615 0.0061573549 0.0050764614 0.1054430000 0.0079430000 0.0523710000 0.0000250000 0.0003520000 0.0335860000 8591916 96830484 1769766912 4.9650697708 4.1039562225 4.4098057747 201 8.0000000000 0.0050492701 0.0049617989 0.0061573549 0.0050645997 0.1199830000 0.0101030000 0.0464930000 0.0003840000 0.0002790000 0.0604630000 8593590 96830484 1768390656 4.9673676491 4.1037187576 4.4213175774 202 8.0400000000 0.0050634230 0.0049623020 0.0061573549 0.0050526846 0.0981850000 0.0077270000 0.0439160000 0.0000250000 0.0003600000 0.0347030000 8595264 96830484 1770147840 4.9671068192 4.1040959358 4.4316329956 203 8.0800000000 0.0050757648 0.0049628609 0.0061573549 0.0050404876 0.1300770000 0.0096200000 0.0710600000 0.0002880000 0.0003450000 0.0383960000 8596938 96830484 1769021440 4.9669985771 4.1043624878 4.4422907829 204 8.1200000000 0.0051346733 0.0049637031 0.0061573549 0.0050314803 0.0906630000 0.0083680000 0.0463600000 0.0000300000 0.0003100000 0.0325000000 8598612 96830484 1770688512 4.9671959877 4.1058201790 4.4530000687 205 8.1600000000 0.0052326056 0.0049650148 0.0061573549 0.0050436621 0.1202890000 0.0103690000 0.0471230000 0.0003850000 0.0002830000 0.0597940000 8600286 96830484 1769275392 4.9684805870 4.1076202393 4.4646992683 206 8.1999999990 0.0051842867 0.0049660793 0.0061573549 0.0050509742 0.0970830000 0.0079450000 0.0471510000 0.0000260000 0.0002870000 0.0350060000 8601960 96830484 1770942464 4.9691438675 4.1096720695 4.4768514633 207 8.2400000000 0.0051149940 0.0049667987 0.0061573549 0.0050461534 0.1135030000 0.0099980000 0.0602370000 0.0002910000 0.0003440000 0.0403080000 8603634 96830484 1769529344 4.9698987007 4.1120591164 4.4897060394 208 8.2799999990 0.0051587033 0.0049677213 0.0061573549 0.0050471786 0.0968930000 0.0077040000 0.0426630000 0.0000260000 0.0002860000 0.0346950000 8605308 96830484 1771147264 4.9695887566 4.1151714325 4.5014529228 209 8.3200000000 0.0052324608 0.0049689880 0.0061573549 0.0050412863 0.1466100000 0.0099490000 0.0537900000 0.0003000000 0.0002770000 0.0708350000 8606982 96830484 1769893888 4.9698171616 4.1167240143 4.5130977631 210 8.3599999990 0.0051037646 0.0049696298 0.0061573549 0.0050301134 0.0915980000 0.0103950000 0.0441400000 0.0000310000 0.0003150000 0.0323870000 8608656 96830484 1767862272 4.9704203606 4.1181473732 4.5251755714 211 8.4000000000 0.0051331157 0.0049704046 0.0061573549 0.0050263862 0.0881580000 0.0087150000 0.0359490000 0.0000700000 0.0000620000 0.0402310000 8610330 96830484 1767108608 4.9708409309 4.1203446388 4.5375857353 212 8.4399999990 0.0050888667 0.0049709634 0.0061573549 0.0050189567 0.1053930000 0.0081390000 0.0471980000 0.0000230000 0.0002970000 0.0379110000 8612004 96830484 1765482496 4.9698095322 4.1221051216 4.5499768257 213 8.4800000000 0.0051307655 0.0049717136 0.0061573549 0.0050111428 0.1456220000 0.0078280000 0.0546140000 0.0003570000 0.0002740000 0.0702550000 8613678 96830484 1767124992 4.9686198235 4.1240658760 4.5614829063 214 8.5200000000 0.0052493578 0.0049730110 0.0061573549 0.0050078097 0.0914670000 0.0083990000 0.0447780000 0.0000250000 0.0003600000 0.0325970000 8615352 96830484 1768624128 4.9680495262 4.1262888908 4.5727934837 215 8.5600000000 0.0052542188 0.0049743189 0.0061573549 0.0049987946 0.1252090000 0.0080980000 0.0663550000 0.0000600000 0.0000680000 0.0381150000 8617026 96830484 1770401792 4.9682364464 4.1294770241 4.5849418640 216 8.6000000000 0.0050310213 0.0049745815 0.0061573549 0.0049908670 0.1149310000 0.0219090000 0.0480440000 0.0000330000 0.0003660000 0.0321360000 8618700 96830484 1769132032 4.9686784744 4.1316208839 4.5973081589 217 8.6400000000 0.0050830012 0.0049750811 0.0061573549 0.0049840772 0.1134790000 0.0084820000 0.0471260000 0.0003920000 0.0002810000 0.0547190000 8620374 96830484 1770815488 4.9675602913 4.1332793236 4.6082110405 218 8.6800000000 0.0051134760 0.0049757159 0.0061573549 0.0049784532 0.0879070000 0.0104750000 0.0452670000 0.0000290000 0.0003120000 0.0292850000 8622048 96830484 1769291776 4.9659605026 4.1347460747 4.6188678741 219 8.7200000000 0.0051949448 0.0049767170 0.0061573549 0.0049717540 0.1066600000 0.0082710000 0.0515330000 0.0003180000 0.0002710000 0.0375510000 8623722 96830484 1767604224 4.9632682800 4.1358251572 4.6292157173 220 8.7600000000 0.0052102669 0.0049777786 0.0061573549 0.0049621501 0.0812110000 0.0086000000 0.0444360000 0.0000250000 0.0003830000 0.0252810000 8625396 96830484 1769287680 4.9599676132 4.1361312866 4.6387810707 221 8.8000000000 0.0051871389 0.0049787259 0.0061573549 0.0049514097 0.1301510000 0.0092910000 0.0595380000 0.0003070000 0.0002870000 0.0580190000 8627070 96830484 1768116224 4.9603199959 4.1384325027 4.6508631706 222 8.8400000000 0.0050667441 0.0049791224 0.0061573549 0.0049426914 0.1082990000 0.0080970000 0.0725230000 0.0000070000 0.0000570000 0.0251900000 8628744 96830484 1769766912 4.9586420059 4.1390404701 4.6615986824 223 8.8800000000 0.0050450116 0.0049794178 0.0061573549 0.0049315844 0.1101250000 0.0141740000 0.0467330000 0.0002950000 0.0002650000 0.0390480000 8630418 96830484 1768624128 4.9558792114 4.1389951706 4.6711916924 224 8.9200000000 0.0049580233 0.0049793223 0.0061573549 0.0049216061 0.1098870000 0.0074530000 0.0559940000 0.0000920000 0.0003030000 0.0414820000 8632092 96830484 1770401792 4.9541444778 4.1395349503 4.6816153526 225 8.9600000000 0.0048469235 0.0049787339 0.0061573549 0.0049138176 0.1305780000 0.0098490000 0.0540180000 0.0002940000 0.0005930000 0.0629930000 8633766 96830484 1769275392 4.9538516998 4.1410942078 4.6929492950 226 9.0000000000 0.0049810573 0.0049787442 0.0061573549 0.0049036610 0.0863380000 0.0080670000 0.0473570000 0.0000240000 0.0002860000 0.0279740000 8635440 96830484 1770942464 4.9550690651 4.1433959007 4.7148246765 227 9.0400000000 0.0048233694 0.0049780597 0.0061573549 0.0048928916 0.0916180000 0.0098200000 0.0420500000 0.0003570000 0.0002770000 0.0365570000 8637114 96830484 1769529344 4.9551706314 4.1454558372 4.7255797386 228 9.0800000000 0.0049542054 0.0049779551 0.0061573549 0.0048841654 0.0849340000 0.0081970000 0.0344790000 0.0000160000 0.0001930000 0.0316030000 8638788 96830484 1768005632 4.9529190063 4.1470088959 4.7345776558 229 9.1200000000 0.0048600221 0.0049774401 0.0061573549 0.0048952044 0.1112080000 0.0101810000 0.0446120000 0.0003240000 0.0003590000 0.0531800000 8640462 96830484 1766625280 4.9530954361 4.1487212181 4.7457399368 230 9.1600000000 0.0047450694 0.0049764298 0.0061573549 0.0048919682 0.0869320000 0.0078070000 0.0378110000 0.0000070000 0.0000720000 0.0320950000 8642136 96830484 1768271872 4.9536809921 4.1500387192 4.7559871674 231 9.2000000000 0.0046596415 0.0049750584 0.0061573549 0.0048868420 0.1117530000 0.0075980000 0.0594790000 0.0003540000 0.0003010000 0.0412490000 8643810 96830484 1769893888 4.9529786110 4.1512832642 4.7746334076 232 9.2400000000 0.0046852026 0.0049738090 0.0061573549 0.0048798851 0.0882040000 0.0094280000 0.0391170000 0.0000950000 0.0003040000 0.0347750000 8645484 96830484 1768787968 4.9537658691 4.1536693573 4.7866201401 233 9.2800000000 0.0045906957 0.0049721648 0.0061573549 0.0048813631 0.1318220000 0.0081770000 0.0596190000 0.0000610000 0.0000540000 0.0508420000 8647158 96830484 1767337984 4.9543757439 4.1562633514 4.7987079620 234 9.3200000000 0.0047225100 0.0049710979 0.0061573549 0.0048798094 0.0943180000 0.0082920000 0.0518850000 0.0000260000 0.0002880000 0.0301320000 8648832 96830484 1769033728 4.9536380768 4.1589188576 4.8094425201 235 9.3600000000 0.0045463527 0.0049692904 0.0061573549 0.0048782078 0.1085370000 0.0082870000 0.0530720000 0.0002840000 0.0003510000 0.0349430000 8650506 96830484 1770528768 4.9533519745 4.1601018906 4.8202767372 236 9.4000000000 0.0046770759 0.0049680522 0.0061573549 0.0048725517 0.1076360000 0.0103980000 0.0541750000 0.0000290000 0.0003180000 0.0290590000 8652180 96830484 1769275392 4.9549727440 4.1608600616 4.8297858238 237 9.4400000000 0.0046687135 0.0049667892 0.0061573549 0.0048806007 0.1105800000 0.0083620000 0.0472420000 0.0003240000 0.0003540000 0.0516400000 8653854 96830484 1770958848 4.9556860924 4.1634912491 4.8408384323 238 9.4800000000 0.0046149255 0.0049653108 0.0061573549 0.0048785202 0.0897260000 0.0107380000 0.0432180000 0.0000260000 0.0002990000 0.0290270000 8655528 96830484 1769512960 4.9564738274 4.1650271416 4.8516430855 239 9.5200000000 0.0046831062 0.0049641300 0.0061573549 0.0048843887 0.1095650000 0.0105270000 0.0600760000 0.0002940000 0.0003620000 0.0339330000 8657202 96830484 1767747584 4.9583854675 4.1672596931 4.8623971939 240 9.5600000000 0.0045664525 0.0049624730 0.0061573549 0.0048827609 0.0872010000 0.0087470000 0.0357340000 0.0000070000 0.0000700000 0.0303320000 8658876 96830484 1769414656 4.9580101967 4.1680603027 4.8719315529 241 9.6000000000 0.0045320825 0.0049606872 0.0061573549 0.0048726200 0.1658840000 0.0092780000 0.0907770000 0.0002950000 0.0003550000 0.0624460000 8660550 96830484 1768353792 4.9562802315 4.1695151329 4.8816847801 242 9.6400000000 0.0044488986 0.0049585723 0.0061573549 0.0048759050 0.0936650000 0.0077180000 0.0487830000 0.0000240000 0.0003740000 0.0299590000 8662224 96830484 1770020864 4.9574737549 4.1718840599 4.8938460350 243 9.6800000000 0.0044982978 0.0049566782 0.0061573549 0.0048666472 0.1091440000 0.0094950000 0.0513050000 0.0003640000 0.0004080000 0.0417080000 8663898 96830484 1768878080 4.9604787827 4.1743721962 4.9075255394 244 9.7200000000 0.0043552066 0.0049542132 0.0061573549 0.0048566400 0.0923700000 0.0079900000 0.0510640000 0.0000240000 0.0002960000 0.0302820000 8665572 96830484 1770688512 4.9617590904 4.1779818535 4.9195814133 245 9.7600000000 0.0044633448 0.0049522096 0.0061573549 0.0048484778 0.1182950000 0.0097040000 0.0480250000 0.0003540000 0.0002670000 0.0572500000 8667246 96830484 1769402368 4.9618301392 4.1787681580 4.9291963577 246 9.8000000000 0.0042476556 0.0049493456 0.0061573549 0.0048386060 0.0962480000 0.0088010000 0.0523580000 0.0000270000 0.0003850000 0.0276020000 8668920 96830484 1771065344 4.9632902145 4.1814465523 4.9409284592 247 9.8400000000 0.0042980099 0.0049467086 0.0061573549 0.0048289833 0.1080540000 0.0103700000 0.0517390000 0.0002940000 0.0002880000 0.0325160000 8670594 96830484 1769656320 4.9635901451 4.1840600967 4.9526171684 248 9.8800000000 0.0043979720 0.0049444959 0.0061573549 0.0048240150 0.0893220000 0.0105820000 0.0378550000 0.0000080000 0.0006040000 0.0288510000 8672268 96830484 1767981056 4.9636178017 4.1872301102 4.9626727104 249 9.9200000000 0.0041772276 0.0049414145 0.0061573549 0.0048144105 0.1447630000 0.0092880000 0.0640450000 0.0003250000 0.0002670000 0.0573770000 8673942 96830484 1766764544 4.9648575783 4.1882314682 4.9734330177 250 9.9600000000 0.0042660916 0.0049387132 0.0061573549 0.0048051263 0.0926520000 0.0084740000 0.0475360000 0.0000290000 0.0003670000 0.0335200000 8675616 96830484 1768361984 4.9655222893 4.1900920868 4.9843182564 251 10.0000000000 0.0041730371 0.0049356627 0.0061573549 0.0047973893 0.1074350000 0.0080250000 0.0552050000 0.0002940000 0.0003530000 0.0358350000 8677290 96830484 1770156032 4.9649596214 4.1908493042 4.9934377670 252 10.0400000000 0.0040976014 0.0049323371 0.0061573549 0.0047878406 0.1086330000 0.0100020000 0.0529610000 0.0000250000 0.0002990000 0.0348910000 8678964 96830484 1768648704 4.9653768539 4.1924948692 5.0030364990 253 10.0800000000 0.0042309975 0.0049295650 0.0061573549 0.0047788330 0.1270170000 0.0081070000 0.0672860000 0.0003910000 0.0002800000 0.0481600000 8680638 96830484 1770549248 4.9657840729 4.1942276955 5.0124511719 254 10.1200000000 0.0041667572 0.0049265618 0.0061573549 0.0047732027 0.0880160000 0.0106550000 0.0546210000 0.0000260000 0.0003500000 0.0195820000 8682312 96830484 1769283584 4.9660162926 4.1962485313 5.0217781067 255 10.1600000000 0.0041828016 0.0049236451 0.0061573549 0.0047640854 0.1331800000 0.0101080000 0.0862000000 0.0003550000 0.0002790000 0.0313000000 8683986 96830484 1767628800 4.9653997421 4.1979484558 5.0309453011 256 10.2000000000 0.0040147114 0.0049200946 0.0061573549 0.0047658325 0.0839510000 0.0088530000 0.0529160000 0.0000270000 0.0002890000 0.0190640000 8685660 96830484 1769295872 4.9641437531 4.1987204552 5.0385832787 257 10.2400000000 0.0039670351 0.0049163862 0.0061573549 0.0047764192 0.1211510000 0.0082500000 0.0632890000 0.0000610000 0.0000540000 0.0466840000 8707814 96830484 1770901504 4.9632406235 4.2003951073 5.0474090576 258 10.2800000000 0.0040460951 0.0049130130 0.0061573549 0.0047777626 0.0976650000 0.0103530000 0.0469870000 0.0000280000 0.0003960000 0.0254670000 8751472 96830484 1769648128 4.9636998177 4.2020401955 5.0570387840 259 10.3200000000 0.0041758809 0.0049101669 0.0061573549 0.0047883196 0.1104190000 0.0086810000 0.0533800000 0.0003080000 0.0003500000 0.0389510000 8753146 96830484 1768255488 4.9632592201 4.2029094696 5.0650534630 260 10.3600000000 0.0043873335 0.0049081560 0.0061573549 0.0047905688 0.0933430000 0.0085610000 0.0525320000 0.0000260000 0.0003580000 0.0290140000 8754820 96830484 1766998016 4.9611182213 4.2043576241 5.0726046562 261 10.4000000000 0.0043114759 0.0049058699 0.0061573549 0.0047825139 0.1156310000 0.0085270000 0.0468550000 0.0003180000 0.0002620000 0.0567140000 8756494 96830484 1765617664 4.9598746300 4.2061290741 5.0822253227 262 10.4400000000 0.0045512244 0.0049045163 0.0061573549 0.0047734716 0.0975130000 0.0085260000 0.0464270000 0.0000300000 0.0002860000 0.0311140000 8758168 96830484 1764974592 4.9610090256 4.2074818611 5.0913591385 263 10.4800000000 0.0043982123 0.0049025912 0.0061573549 0.0047643924 0.1052910000 0.0084970000 0.0541920000 0.0002850000 0.0003440000 0.0296040000 8759842 96830484 1764859904 4.9603972435 4.2089767456 5.1009654999 264 10.5200000000 0.0043559154 0.0049005204 0.0061573549 0.0047584509 0.1094370000 0.0087980000 0.0682440000 0.0000060000 0.0000570000 0.0247480000 8761516 96830484 1764954112 4.9586682320 4.2095127106 5.1088771820 265 10.5600000000 0.0045370013 0.0048991487 0.0061573549 0.0047506741 0.1031640000 0.0085460000 0.0466280000 0.0003110000 0.0003560000 0.0442680000 8763190 96830484 1764843520 4.9575319290 4.2096991539 5.1163525581 266 10.6000000000 0.0044634612 0.0048975107 0.0061573549 0.0047418887 0.0941190000 0.0080350000 0.0522610000 0.0000270000 0.0003860000 0.0241130000 8764864 96830484 1764974592 4.9581546783 4.2107882500 5.1249823570 267 10.6400000000 0.0044529960 0.0048958459 0.0061573549 0.0047347477 0.1288960000 0.0090450000 0.0804290000 0.0002870000 0.0002650000 0.0289970000 8766538 96830484 1764823040 4.9573054314 4.2121853828 5.1336388588 268 10.6800000000 0.0043705539 0.0048938858 0.0061573549 0.0047287090 0.0896420000 0.0086860000 0.0503690000 0.0000270000 0.0003120000 0.0240480000 8768212 96830484 1766600704 4.9561033249 4.2142138481 5.1430377960 269 10.7200000000 0.0043341508 0.0048918050 0.0061573549 0.0047244059 0.0986400000 0.0085650000 0.0429560000 0.0003590000 0.0013990000 0.0423320000 8769886 96830484 1768251392 4.9543414116 4.2150068283 5.1522483826 270 10.7600000000 0.0044243592 0.0048900738 0.0061573549 0.0047181391 0.0946860000 0.0085000000 0.0466330000 0.0000240000 0.0003820000 0.0244190000 8771560 96830484 1769902080 4.9524517059 4.2172780037 5.1613411903 271 10.8000000000 0.0043329340 0.0048880179 0.0061573549 0.0047111214 0.1119910000 0.0104610000 0.0672750000 0.0006790000 0.0002930000 0.0284040000 8773234 96830484 1768771584 4.9502635002 4.2191567421 5.1712827682 272 10.8400000000 0.0042613423 0.0048857139 0.0061573549 0.0047024258 0.0890590000 0.0090650000 0.0514710000 0.0000260000 0.0002810000 0.0237000000 8774908 96830484 1770553344 4.9473829269 4.2209887505 5.1805114746 273 10.8800000000 0.0040680864 0.0048827190 0.0061573549 0.0046940066 0.1017240000 0.0106700000 0.0434050000 0.0010500000 0.0003490000 0.0431240000 8776582 96830484 1769410560 4.9434003830 4.2213978767 5.1894860268 274 10.9200000000 0.0039144149 0.0048791850 0.0061573549 0.0046864802 0.0765490000 0.0084340000 0.0396590000 0.0000260000 0.0003510000 0.0250610000 8778256 96830484 1771044864 4.9417343140 4.2234559059 5.1999192238 275 10.9600000000 0.0039044668 0.0048756406 0.0061573549 0.0046802404 0.0902440000 0.0106280000 0.0476560000 0.0002860000 0.0002680000 0.0283830000 8779930 96830484 1769029632 4.9391245842 4.2271442413 5.2095384598 276 11.0000000000 0.0039003717 0.0048721070 0.0061573549 0.0046734500 0.0868300000 0.0098240000 0.0452830000 0.0000290000 0.0003530000 0.0243200000 8781604 96830484 1767870464 4.9354739189 4.2263617516 5.2173790932 277 11.0400000000 0.0038384835 0.0048683755 0.0061573549 0.0046691640 0.0971440000 0.0085370000 0.0429790000 0.0001890000 0.0001740000 0.0422810000 8783278 96830484 1765851136 4.9350600243 4.2285780907 5.2286362648 278 11.0800000000 0.0038848643 0.0048648377 0.0061573549 0.0046607309 0.0993830000 0.0089010000 0.0536380000 0.0000270000 0.0003160000 0.0235040000 8784952 96830484 1766227968 4.9300122261 4.2296891212 5.2375621796 279 11.1200000000 0.0038029479 0.0048610316 0.0061573549 0.0046535672 0.0906740000 0.0093270000 0.0451960000 0.0003150000 0.0003590000 0.0280860000 8786626 96830484 1765724160 4.9252004623 4.2296810150 5.2468066216 280 11.1600000000 0.0037873972 0.0048571972 0.0061573549 0.0046452472 0.0876510000 0.0089820000 0.0435700000 0.0000270000 0.0010900000 0.0232820000 8788300 96830484 1765457920 4.9227137566 4.2321877480 5.2576131821 281 11.2000000000 0.0038225590 0.0048535152 0.0061573549 0.0046372619 0.1228790000 0.0092660000 0.0686410000 0.0003630000 0.0002730000 0.0412110000 8789974 96830484 1764962304 4.9206376076 4.2360038757 5.2670769691 282 11.2400000000 0.0037625672 0.0048496466 0.0061573549 0.0046295882 0.0920930000 0.0091230000 0.0634950000 0.0000060000 0.0000630000 0.0163480000 8791648 96830484 1764958208 4.9171466827 4.2370309830 5.2757687569 283 11.2800000000 0.0036735286 0.0048454907 0.0061573549 0.0046221612 0.0928660000 0.0087620000 0.0594960000 0.0003220000 0.0000620000 0.0206880000 8793322 96830484 1764843520 4.9139361382 4.2400670052 5.2853240967 284 11.3200000000 0.0037056259 0.0048414771 0.0061573549 0.0046149834 0.1056900000 0.0087820000 0.0612410000 0.0000320000 0.0003170000 0.0233770000 8794996 96830484 1764954112 4.9089546204 4.2428030968 5.2963509560 285 11.3600000000 0.0037134127 0.0048375190 0.0061573549 0.0046073566 0.1024060000 0.0089530000 0.0561140000 0.0002920000 0.0003430000 0.0336270000 8796670 96830484 1764933632 4.9041938782 4.2434678078 5.3052058220 286 11.4000000000 0.0037394119 0.0048336795 0.0061573549 0.0046118970 0.0918970000 0.0101710000 0.0460440000 0.0000260000 0.0003100000 0.0226300000 8798344 96830484 1764859904 4.9055361748 4.2467780113 5.3157610893 287 11.4400000000 0.0037250102 0.0048298165 0.0061573549 0.0046048499 0.1075300000 0.0088310000 0.0556750000 0.0003920000 0.0002840000 0.0267620000 8800018 96830484 1764954112 4.9029726982 4.2502532005 5.3247327805 288 11.4800000000 0.0037166683 0.0048259514 0.0061573549 0.0045969540 0.0913320000 0.0089990000 0.0531480000 0.0000270000 0.0002860000 0.0220330000 8801692 96830484 1764954112 4.8959069252 4.2511954308 5.3314852715 289 11.5200000000 0.0036070349 0.0048217337 0.0061573549 0.0045895121 0.1139200000 0.0096990000 0.0607320000 0.0003060000 0.0002770000 0.0397850000 8803366 96830484 1764970496 4.8902235031 4.2497301102 5.3387613297 290 11.5600000000 0.0035162081 0.0048172319 0.0061573549 0.0045823608 0.1139740000 0.0090160000 0.0858200000 0.0000260000 0.0002900000 0.0156430000 8805040 96830484 1765101568 4.8872370720 4.2507214546 5.3476438522 291 11.6000000000 0.0034802405 0.0048126374 0.0061573549 0.0045747957 0.1321600000 0.0091260000 0.0793600000 0.0002910000 0.0002660000 0.0274000000 8806714 96830484 1766760448 4.8847813606 4.2532386780 5.3560400009 292 11.6400000000 0.0034080446 0.0048078272 0.0061573549 0.0045672254 0.1310170000 0.0090640000 0.0881090000 0.0000270000 0.0003770000 0.0223220000 8808388 96830484 1768378368 4.8816514015 4.2538027763 5.3637819290 293 11.6800000000 0.0032520820 0.0048025175 0.0061573549 0.0045594459 0.1196730000 0.0090670000 0.0743030000 0.0003530000 0.0002640000 0.0323780000 8810062 96830484 1770156032 4.8797683716 4.2559661865 5.3703002930 294 11.7200000000 0.0031284201 0.0047968233 0.0061573549 0.0045579186 0.0990000000 0.0135390000 0.0580160000 0.0000250000 0.0002890000 0.0217050000 8811736 96830484 1769029632 4.8756155968 4.2551903725 5.3768157959 295 11.7600000000 0.0030600408 0.0047909359 0.0061573549 0.0045581274 0.0880870000 0.0093480000 0.0462210000 0.0003170000 0.0003590000 0.0264110000 8813410 96830484 1769172992 4.8742184639 4.2559328079 5.3846187592 296 11.8000000000 0.0030306468 0.0047849889 0.0061573549 0.0045767578 0.0876810000 0.0095550000 0.0505590000 0.0000290000 0.0003880000 0.0232380000 8815084 96830484 1767903232 4.8717637062 4.2563080788 5.3923945427 297 11.8400000000 0.0029656861 0.0047788633 0.0061573549 0.0046043995 0.1152350000 0.0096530000 0.0563020000 0.0003830000 0.0002780000 0.0452990000 8816758 96830484 1765470208 4.8673973083 4.2562003136 5.3996624947 298 11.8800000000 0.0028165088 0.0047722783 0.0061573549 0.0046171024 0.0844670000 0.0084530000 0.0484570000 0.0000290000 0.0002940000 0.0238770000 8818432 96830484 1764962304 4.8644223213 4.2557325363 5.4084911346 299 11.9200000000 0.0027408421 0.0047654842 0.0061573549 0.0046155682 0.1047800000 0.0090140000 0.0609510000 0.0002960000 0.0002890000 0.0259830000 8820106 96830484 1764859904 4.8625001907 4.2553958893 5.4166140556 300 11.9600000000 0.0026275720 0.0047583578 0.0061573549 0.0046144477 0.0891620000 0.0088600000 0.0458460000 0.0000270000 0.0003230000 0.0270400000 8821780 96830484 1764950016 4.8606319427 4.2548079491 5.4242615700 301 12.0000000000 0.0025660635 0.0047510744 0.0061573549 0.0046098357 0.1217450000 0.0091170000 0.0649230000 0.0055420000 0.0002760000 0.0385540000 8823454 96830484 1764954112 4.8596000671 4.2555947304 5.4338459969 302 12.0400000000 0.0024709089 0.0047435242 0.0061573549 0.0046033531 0.0968600000 0.0093610000 0.0577750000 0.0000280000 0.0002850000 0.0214620000 8825128 96830484 1764806656 4.8588685989 4.2558956146 5.4424786568 303 12.0800000000 0.0024605617 0.0047359897 0.0061573549 0.0045974204 0.1044440000 0.0091500000 0.0529020000 0.0003580000 0.0002620000 0.0254470000 8826802 96830484 1764974592 4.8568801880 4.2551364899 5.4500432014 304 12.1200000000 0.0023868543 0.0047282622 0.0061573549 0.0045913322 0.0900150000 0.0095070000 0.0460100000 0.0000260000 0.0003860000 0.0211710000 8828476 96830484 1764843520 4.8556923866 4.2560238838 5.4596476555 305 12.1600000000 0.0022730597 0.0047202124 0.0061573549 0.0045838673 0.1104430000 0.0092550000 0.0536060000 0.0003210000 0.0002760000 0.0405560000 8830150 96830484 1764954112 4.8545207977 4.2570662498 5.4693064690 306 12.2000000000 0.0022945558 0.0047122854 0.0061573549 0.0045764762 0.0804360000 0.0094280000 0.0529010000 0.0000270000 0.0003140000 0.0143360000 8831824 96830484 1763708928 4.8518886566 4.2580795288 5.4781446457 307 12.2400000000 0.0021772545 0.0047040280 0.0061573549 0.0045706123 0.0964340000 0.0089110000 0.0461160000 0.0002920000 0.0002610000 0.0294160000 8833498 96830484 1763958784 4.8497443199 4.2598915100 5.4877309799 308 12.2800000000 0.0020683578 0.0046954706 0.0061573549 0.0045688963 0.1033670000 0.0085950000 0.0754390000 0.0000070000 0.0000620000 0.0158280000 8835172 96830484 1763975168 4.8486337662 4.2605671883 5.4974679947 309 12.3200000000 0.0020803399 0.0046870074 0.0061573549 0.0045670079 0.0999260000 0.0098900000 0.0498300000 0.0002900000 0.0002710000 0.0362920000 8836846 96830484 1764085760 4.8472628593 4.2612028122 5.5065946579 310 12.3600000000 0.0021224376 0.0046787346 0.0061573549 0.0045743529 0.0995510000 0.0092400000 0.0542320000 0.0000260000 0.0003220000 0.0253750000 8838520 96830484 1764212736 4.8462328911 4.2638792992 5.5165863037 311 12.4000000000 0.0021071606 0.0046704659 0.0061573549 0.0045944057 0.0925830000 0.0097340000 0.0576920000 0.0002920000 0.0003490000 0.0211280000 8840194 96830484 1764229120 4.8449764252 4.2660784721 5.5268058777 312 12.4400000000 0.0020944253 0.0046622093 0.0061573549 0.0046011930 0.0876190000 0.0094800000 0.0490370000 0.0000280000 0.0020580000 0.0236430000 8841868 96830484 1764339712 4.8439440727 4.2649812698 5.5344939232 313 12.4800000000 0.0019343861 0.0046534942 0.0061573549 0.0046023076 0.1171550000 0.0089530000 0.0762230000 0.0000650000 0.0000570000 0.0285150000 8843542 96830484 1764466688 4.8426799774 4.2660293579 5.5441303253 314 12.5200000000 0.0018096040 0.0046444373 0.0061573549 0.0046009255 0.0988640000 0.0108270000 0.0645650000 0.0000250000 0.0003110000 0.0197100000 8845216 96830484 1764593664 4.8409299850 4.2671594620 5.5533885956 315 12.5600000000 0.0017762837 0.0046353320 0.0061573549 0.0045959858 0.0782550000 0.0095870000 0.0472160000 0.0004090000 0.0002930000 0.0173500000 8846890 96830484 1764720640 4.8395195007 4.2681784630 5.5615429878 316 12.6000000000 0.0018524523 0.0046265254 0.0061573549 0.0045889467 0.1389440000 0.0093120000 0.0907320000 0.0000270000 0.0002980000 0.0214620000 8848564 96830484 1764847616 4.8401370049 4.2678279877 5.5694727898 317 12.6400000000 0.0017785075 0.0046175412 0.0061573549 0.0045820624 0.1097160000 0.0091010000 0.0656930000 0.0003200000 0.0002680000 0.0309140000 8850238 96830484 1764974592 4.8393535614 4.2689757347 5.5784187317 318 12.6800000000 0.0019376302 0.0046091138 0.0061573549 0.0045776809 0.0820340000 0.0097650000 0.0547290000 0.0000260000 0.0002950000 0.0135790000 8851912 96830484 1766600704 4.8390922546 4.2707653046 5.5874052048 319 12.7200000000 0.0020557127 0.0046011094 0.0061573549 0.0045716869 0.1041090000 0.0093880000 0.0580190000 0.0002870000 0.0003490000 0.0302700000 8853586 96830484 1768251392 4.8364682198 4.2735743523 5.5978207588 320 12.7600000000 0.0020655959 0.0045931859 0.0061573549 0.0045713887 0.1077250000 0.0092430000 0.0623250000 0.0000270000 0.0003630000 0.0243700000 8855260 96830484 1770020864 4.8343267441 4.2746353149 5.6068377495 321 12.8000000000 0.0020932248 0.0045853979 0.0061573549 0.0045825544 0.1480730000 0.0123790000 0.0895640000 0.0000600000 0.0000530000 0.0305940000 8856934 96830484 1768767488 4.8327555656 4.2766599655 5.6161513329 322 12.8400000000 0.0021227058 0.0045777497 0.0061573549 0.0045878056 0.1111610000 0.0104280000 0.0738510000 0.0000290000 0.0002820000 0.0192900000 8858608 96830484 1770541056 4.8316793442 4.2789740562 5.6251139641 323 12.8800000000 0.0021257203 0.0045701583 0.0061573549 0.0045999121 0.1079080000 0.0122320000 0.0612130000 0.0002840000 0.0002670000 0.0230310000 8860282 96830484 1769402368 4.8304591179 4.2804450989 5.6330194473 324 12.9200000000 0.0020548541 0.0045623950 0.0061573549 0.0046121441 0.1084240000 0.0103440000 0.0676200000 0.0000230000 0.0002750000 0.0184860000 8861956 96830484 1771212800 4.8292942047 4.2805895805 5.6399936676 325 12.9600000000 0.0020594383 0.0045546936 0.0061573549 0.0046243802 0.1109030000 0.0121980000 0.0562550000 0.0002940000 0.0002640000 0.0369510000 8863630 96830484 1769656320 4.8289122581 4.2810463905 5.6471590996 326 13.0000000000 0.0021830834 0.0045474187 0.0061573549 0.0046330673 0.0916200000 0.0119720000 0.0615930000 0.0000270000 0.0003590000 0.0140740000 8865304 96830484 1767882752 4.8277378082 4.2819027901 5.6553158760 327 13.0400000000 0.0021290765 0.0045400232 0.0061573549 0.0047406068 0.0869560000 0.0108290000 0.0517440000 0.0003860000 0.0002630000 0.0201250000 8866978 96830484 1766981632 4.8240561485 4.2864360809 5.6748538017 328 13.0800000000 0.0021828497 0.0045328367 0.0061573549 0.0047590940 0.1077580000 0.0120320000 0.0721170000 0.0000280000 0.0003630000 0.0193510000 8868652 96830484 1765576704 4.8221869469 4.2871522903 5.6826968193 329 13.1200000000 0.0021843717 0.0045256985 0.0061573549 0.0047644203 0.1301720000 0.0121980000 0.0634510000 0.0003730000 0.0002790000 0.0343290000 8870326 96830484 1767272448 4.8200626373 4.2881412506 5.6906599998 330 13.1600000000 0.0022639476 0.0045188447 0.0061573549 0.0047636005 0.0961260000 0.0098750000 0.0627330000 0.0000280000 0.0003020000 0.0195010000 8872000 96830484 1769005056 4.8186287880 4.2885298729 5.6978778839 331 13.2000000000 0.0022585264 0.0045120160 0.0061573549 0.0047633568 0.1070160000 0.0106410000 0.0643510000 0.0003510000 0.0002670000 0.0235450000 8873674 96830484 1770655744 4.8178811073 4.2884716988 5.7046170235 332 13.2400000000 0.0023278724 0.0045054372 0.0061573549 0.0047602837 0.1090620000 0.0116240000 0.0698010000 0.0000250000 0.0002860000 0.0190990000 8875348 96830484 1769529344 4.8168616295 4.2899856567 5.7123022079 333 13.2800000000 0.0023029621 0.0044988232 0.0061573549 0.0047554003 0.1354510000 0.0135140000 0.0712670000 0.0003600000 0.0002690000 0.0318250000 8877022 96830484 1768026112 4.8158268929 4.2914223671 5.7197942734 334 13.3200000000 0.0022565671 0.0044921098 0.0061573549 0.0047576383 0.1109340000 0.0100480000 0.0656760000 0.0000270000 0.0002950000 0.0187300000 8878696 96830484 1769795584 4.8154149055 4.2914981842 5.7258672714 335 13.3600000000 0.0022141754 0.0044853100 0.0061573549 0.0047633641 0.1094690000 0.0120950000 0.0605410000 0.0003120000 0.0002770000 0.0217710000 8880370 96830484 1768407040 4.8132724762 4.2942934036 5.7345809937 336 13.4000000000 0.0021700333 0.0044784193 0.0061573549 0.0047771643 0.0916780000 0.0105450000 0.0457890000 0.0000260000 0.0003900000 0.0182310000 8882044 96830484 1770020864 4.8112406731 4.2950568199 5.7407903671 337 13.4400000000 0.0020237195 0.0044711354 0.0061573549 0.0048018362 0.0875600000 0.0120130000 0.0389260000 0.0003160000 0.0003560000 0.0322910000 8883718 96830484 1768894464 4.8099174500 4.2940893173 5.7459917068 338 13.4800000000 0.0020011466 0.0044638277 0.0061573549 0.0048295450 0.0977150000 0.0103400000 0.0538260000 0.0000290000 0.0002910000 0.0180010000 8885392 96830484 1767112704 4.8064684868 4.2941436768 5.7514424324 339 13.5200000000 0.0020256443 0.0044566354 0.0061573549 0.0048511432 0.1055070000 0.0110740000 0.0537470000 0.0003610000 0.0002790000 0.0215090000 8887066 96830484 1766600704 4.8045206070 4.2958588600 5.7590131760 340 13.5600000000 0.0020258313 0.0044494860 0.0061573549 0.0048755394 0.0899420000 0.0106510000 0.0455470000 0.0000300000 0.0007080000 0.0180350000 8888740 96830484 1768419328 4.7999243736 4.2961187363 5.7647190094 341 13.6000000000 0.0019599549 0.0044421853 0.0061573549 0.0048849060 0.1303200000 0.0106220000 0.0759560000 0.0003750000 0.0002870000 0.0345190000 8890414 96830484 1769893888 4.7961978912 4.2970948219 5.7719802856 342 13.6400000000 0.0021204043 0.0044353965 0.0061573549 0.0048981074 0.0712530000 0.0123040000 0.0379610000 0.0000270000 0.0004900000 0.0167900000 8892088 96830484 1768624128 4.7925701141 4.2994780540 5.7800745964 343 13.6800000000 0.0022315641 0.0044289713 0.0061573549 0.0049167596 0.0875480000 0.0094490000 0.0472800000 0.0003000000 0.0002990000 0.0224580000 8893762 96830484 1767743488 4.7883558273 4.3029694557 5.7885131836 344 13.7200000000 0.0022771887 0.0044227161 0.0061573549 0.0049210191 0.0881680000 0.0097630000 0.0517440000 0.0000270000 0.0003100000 0.0178970000 8895436 96830484 1766371328 4.7844109535 4.3049488068 5.7943649292 345 13.7600000000 0.0023187336 0.0044166176 0.0061573549 0.0049232028 0.0985190000 0.0104050000 0.0534470000 0.0003820000 0.0002940000 0.0302760000 8897110 96830484 1765064704 4.7826552391 4.3040680885 5.7990117073 346 13.8000000000 0.0024093387 0.0044108162 0.0061573549 0.0049239398 0.1129680000 0.0104910000 0.0878770000 0.0000070000 0.0000590000 0.0108770000 8898784 96830484 1764798464 4.7801308632 4.3044967651 5.8029804230 347 13.8400000000 0.0024715327 0.0044052275 0.0061573549 0.0049319857 0.0917770000 0.0119000000 0.0470670000 0.0003840000 0.0007100000 0.0210940000 8900458 96830484 1764937728 4.7762856483 4.3038940430 5.8087124825 348 13.8800000000 0.0025784117 0.0043999781 0.0061573549 0.0049451650 0.1085540000 0.0102960000 0.0650610000 0.0000290000 0.0003070000 0.0231340000 8902132 96830484 1764962304 4.7717690468 4.3044428825 5.8153643608 349 13.9200000000 0.0026409295 0.0043949378 0.0061573549 0.0049537589 0.0892470000 0.0103800000 0.0517420000 0.0003730000 0.0002820000 0.0227240000 8903806 96830484 1764835328 4.7657051086 4.3049054146 5.8227128983 350 13.9600000000 0.0028400517 0.0043904953 0.0061573549 0.0049630698 0.0882100000 0.0097890000 0.0452310000 0.0000280000 0.0003050000 0.0233620000 8905480 96830484 1764966400 4.7601008415 4.3061966896 5.8303084373 351 14.0000000000 0.0028311559 0.0043860527 0.0061573549 0.0049632630 0.0935130000 0.0097840000 0.0606480000 0.0003200000 0.0002750000 0.0185030000 8907154 96830484 1764945920 4.7548232079 4.3076848984 5.8367776871 352 14.0400000000 0.0028946802 0.0043818159 0.0061573549 0.0049638618 0.1018830000 0.0110700000 0.0681550000 0.0000270000 0.0003920000 0.0182870000 8908828 96830484 1764945920 4.7492203712 4.3073811531 5.8404984474 353 14.0800000000 0.0028901980 0.0043775903 0.0061573549 0.0049621241 0.1256640000 0.0111430000 0.0684740000 0.0003010000 0.0004560000 0.0280680000 8910502 96830484 1764945920 4.7448596954 4.3063921928 5.8459000587 354 14.1200000000 0.0029582342 0.0043735808 0.0061573549 0.0049634212 0.0886530000 0.0097470000 0.0450060000 0.0000300000 0.0002990000 0.0194740000 8912176 96830484 1764945920 4.7388300896 4.3087592125 5.8549761772 355 14.1600000000 0.0031164989 0.0043700398 0.0061573549 0.0049600397 0.0904470000 0.0101020000 0.0523730000 0.0003000000 0.0003630000 0.0209250000 8913850 96830484 1764954112 4.7331070900 4.3096714020 5.8600602150 356 14.2000000000 0.0032652216 0.0043669363 0.0061573549 0.0049570058 0.1069640000 0.0103300000 0.0671330000 0.0000260000 0.0002980000 0.0168050000 8915524 96830484 1764724736 4.7271456718 4.3096723557 5.8644561768 357 14.2400000000 0.0033692855 0.0043641418 0.0061573549 0.0049538460 0.0967570000 0.0104220000 0.0523560000 0.0003790000 0.0002840000 0.0293880000 8917198 96830484 1764966400 4.7197785378 4.3109164238 5.8708009720 358 14.2800000000 0.0034578459 0.0043616102 0.0061573549 0.0049475536 0.0819000000 0.0102760000 0.0464210000 0.0000250000 0.0003080000 0.0171160000 8918872 96830484 1764945920 4.7144527435 4.3111081123 5.8763098717 359 14.3200000000 0.0034898976 0.0043591821 0.0061573549 0.0049410850 0.1194920000 0.0097840000 0.0868840000 0.0024580000 0.0002980000 0.0159800000 8920546 96830484 1764966400 4.7054882050 4.3147158623 5.8838491440 360 14.3600000000 0.0036973257 0.0043573436 0.0061573549 0.0049424364 0.0776690000 0.0098050000 0.0430870000 0.0000270000 0.0003170000 0.0169960000 8922220 96830484 1766592512 4.6897864342 4.3179478645 5.8957281113 361 14.4000000000 0.0041212002 0.0043566894 0.0061573549 0.0049356952 0.0778830000 0.0106410000 0.0359950000 0.0003040000 0.0003560000 0.0266110000 8923894 96830484 1768370176 4.6807169914 4.3224568367 5.9043183327 362 14.4400000000 0.0041875206 0.0043562221 0.0061573549 0.0049309358 0.0813550000 0.0095470000 0.0467440000 0.0000280000 0.0003100000 0.0179260000 8925568 96830484 1770020864 4.6639442444 4.3216757774 5.9105672836 363 14.4800000000 0.0041117561 0.0043555487 0.0061573549 0.0049268539 0.0871780000 0.0122670000 0.0413510000 0.0002930000 0.0003590000 0.0198410000 8927242 96830484 1768640512 4.6579742432 4.3206734657 5.9145102501 364 14.5200000000 0.0040224921 0.0043546337 0.0061573549 0.0049201082 0.1103690000 0.0103170000 0.0781170000 0.0000270000 0.0003700000 0.0158160000 8928916 96830484 1767084032 4.6502103806 4.3212604523 5.9206070900 365 14.5600000000 0.0042127008 0.0043542448 0.0061573549 0.0049133821 0.1283400000 0.0103890000 0.0809850000 0.0003010000 0.0003510000 0.0296120000 8930590 96830484 1768796160 4.6421809196 4.3213033676 5.9256916046 366 14.6000000000 0.0043948013 0.0043543556 0.0061573549 0.0049074442 0.0867820000 0.0102660000 0.0443030000 0.0000290000 0.0003070000 0.0162290000 8932264 96830484 1770401792 4.6258244514 4.3275074959 5.9402499199 367 14.6400000000 0.0048056869 0.0043555854 0.0061573549 0.0049011555 0.0932050000 0.0127470000 0.0565470000 0.0003160000 0.0003570000 0.0190800000 8933938 96830484 1769148416 4.6166200638 4.3314514160 5.9453239441 368 14.6800000000 0.0050762161 0.0043575437 0.0061573549 0.0048960892 0.0897150000 0.0112150000 0.0622730000 0.0000290000 0.0003660000 0.0119110000 8935612 96830484 1769021440 4.6079950333 4.3316946030 5.9491600990 369 14.7200000000 0.0051679220 0.0043597398 0.0061573549 0.0048914018 0.1148750000 0.0105360000 0.0766900000 0.0000600000 0.0000540000 0.0235090000 8937286 96830484 1767497728 4.5995845795 4.3293581009 5.9505691528 370 14.7600000000 0.0050973287 0.0043617333 0.0061573549 0.0048855205 0.0813590000 0.0105820000 0.0473120000 0.0000250000 0.0003730000 0.0189870000 8938960 96830484 1766617088 4.5914378166 4.3281726837 5.9522075653 371 14.8000000000 0.0049762633 0.0043633897 0.0061573549 0.0048805513 0.1131540000 0.0107500000 0.0838440000 0.0003070000 0.0002800000 0.0139850000 8940634 96830484 1765228544 4.5819640160 4.3303523064 5.9589152336 372 14.8400000000 0.0050962577 0.0043653598 0.0061573549 0.0048745440 0.0964870000 0.0104910000 0.0710930000 0.0000060000 0.0000590000 0.0109430000 8942308 96830484 1764954112 4.5733766556 4.3316521645 5.9640893936 373 14.8800000000 0.0053069554 0.0043678842 0.0061573549 0.0048703592 0.1043720000 0.0104460000 0.0569620000 0.0063650000 0.0002920000 0.0262740000 8943982 96830484 1764687872 4.5637497902 4.3326997757 5.9687404633 374 14.9200000000 0.0059119542 0.0043720127 0.0061573549 0.0048648729 0.0782620000 0.0100710000 0.0456720000 0.0000260000 0.0003000000 0.0180670000 8945656 96830484 1764966400 4.5531463623 4.3331904411 5.9720292091 375 14.9600000000 0.0060359929 0.0043764500 0.0061573549 0.0048625534 0.0896790000 0.0097600000 0.0511400000 0.0003070000 0.0003600000 0.0239760000 8947330 96830484 1764835328 4.5428318977 4.3327355385 5.9733576775 376 15.0000000000 0.0061924597 0.0043812798 0.0061924597 0.0048563726 0.0863350000 0.0093850000 0.0405070000 0.0000260000 0.0002980000 0.0199990000 8949004 96830484 1764966400 4.5338268280 4.3322739601 5.9786672592 377 15.0400000000 0.0061333077 0.0043859271 0.0061924597 0.0048536891 0.0918500000 0.0095740000 0.0443060000 0.0003810000 0.0002800000 0.0332270000 8950678 96830484 1764835328 4.5127720833 4.3335642815 5.9859275818 378 15.0800000000 0.0068221814 0.0043923722 0.0068221814 0.0048512010 0.0886260000 0.0099470000 0.0535480000 0.0000250000 0.0023380000 0.0186100000 8952352 96830484 1764945920 4.5043978691 4.3339581490 5.9899263382 379 15.1200000000 0.0073409546 0.0044001521 0.0073409546 0.0048458419 0.1256080000 0.0101670000 0.0802810000 0.0003190000 0.0004560000 0.0232960000 8954026 96830484 1764724736 4.4973764420 4.3334369659 5.9929618835 380 15.1600000000 0.0076790256 0.0044087807 0.0076790256 0.0048423680 0.0996540000 0.0104070000 0.0726850000 0.0000050000 0.0000590000 0.0125000000 8955700 96830484 1764966400 4.4902591705 4.3321413994 5.9966611862 381 15.2000000000 0.0080910586 0.0044184455 0.0080910586 0.0048480487 0.1005970000 0.0108170000 0.0526240000 0.0003010000 0.0003420000 0.0323960000 8957374 96830484 1764835328 4.4825658798 4.3332271576 6.0026950836 382 15.2400000000 0.0086815590 0.0044296055 0.0086815590 0.0048490838 0.1245060000 0.0100620000 0.0837050000 0.0000280000 0.0003750000 0.0188350000 8959048 96830484 1764925440 4.4729089737 4.3327207565 6.0035920143 383 15.2800000000 0.0088706231 0.0044412008 0.0088706231 0.0048597156 0.0898920000 0.0104570000 0.0482240000 0.0003070000 0.0003470000 0.0228150000 8960722 96830484 1763684352 4.4645590782 4.3325424194 6.0062236786 384 15.3200000000 0.0084564891 0.0044516573 0.0088706231 0.0048806197 0.0869820000 0.0101490000 0.0426100000 0.0000280000 0.0003040000 0.0193820000 8962396 96830484 1763950592 4.4555530548 4.3343544006 6.0115189552 385 15.3600000000 0.0086838203 0.0044626499 0.0088706231 0.0048802147 0.1327490000 0.0099600000 0.0857100000 0.0002980000 0.0003600000 0.0322420000 8964070 96830484 1763966976 4.4478545189 4.3342919350 6.0143046379 386 15.4000000000 0.0084649501 0.0044730186 0.0088706231 0.0048836043 0.1070750000 0.0096510000 0.0729430000 0.0000250000 0.0005460000 0.0187680000 8965744 96830484 1765576704 4.4402608871 4.3349442482 6.0173888206 387 15.4400000000 0.0084671406 0.0044833393 0.0088706231 0.0048879749 0.1256710000 0.0103910000 0.0726760000 0.0002970000 0.0006830000 0.0230250000 8967418 96830484 1767354368 4.4338703156 4.3356504440 6.0212650299 388 15.4800000000 0.0081107477 0.0044926883 0.0088706231 0.0048982433 0.0904500000 0.0102640000 0.0487220000 0.0000270000 0.0002980000 0.0195930000 8969092 96830484 1769005056 4.4270195961 4.3369770050 6.0249910355 389 15.5200000000 0.0083094696 0.0045025001 0.0088706231 0.0048983293 0.1193160000 0.0103730000 0.0716980000 0.0003000000 0.0003520000 0.0323780000 8970766 96830484 1770766336 4.4193148613 4.3380026817 6.0290398598 390 15.5600000000 0.0082602631 0.0045121354 0.0088706231 0.0049161802 0.1186710000 0.0119390000 0.0747600000 0.0000290000 0.0002910000 0.0190190000 8972440 96830484 1769529344 4.4112095833 4.3386697769 6.0321836472 391 15.6000000000 0.0078531671 0.0045206802 0.0088706231 0.0049195553 0.1089340000 0.0118370000 0.0620470000 0.0003030000 0.0003620000 0.0224710000 8974114 96830484 1767845888 4.4038681984 4.3395547867 6.0356054306 392 15.6400000000 0.0076426738 0.0045286445 0.0088706231 0.0049323578 0.1098480000 0.0103610000 0.0741050000 0.0000270000 0.0003150000 0.0187430000 8975788 96830484 1769541632 4.3967890739 4.3405847549 6.0405044556 393 15.6800000000 0.0075946129 0.0045364459 0.0088706231 0.0049297248 0.1289850000 0.0115450000 0.0746770000 0.0003000000 0.0002800000 0.0354930000 8977462 96830484 1768407040 4.3898119926 4.3405685425 6.0433921814 394 15.7200000000 0.0077051390 0.0045444883 0.0088706231 0.0049315280 0.1087510000 0.0097530000 0.0744510000 0.0000250000 0.0005500000 0.0189080000 8979136 96830484 1770147840 4.3831415176 4.3412904739 6.0466985703 395 15.7600000000 0.0078169741 0.0045527730 0.0088706231 0.0049321518 0.1268890000 0.0119170000 0.0767000000 0.0006730000 0.0002770000 0.0229900000 8980810 96830484 1768894464 4.3766999245 4.3420257568 6.0528736115 396 15.8000000000 0.0081145773 0.0045617675 0.0088706231 0.0049291544 0.1106790000 0.0101440000 0.0759210000 0.0000280000 0.0005400000 0.0185150000 8982484 96830484 1770704896 4.3697891235 4.3438186646 6.0580425262 397 15.8400000000 0.0078516360 0.0045700543 0.0088706231 0.0049284265 0.1079590000 0.0119920000 0.0589460000 0.0002940000 0.0003470000 0.0318450000 8984158 96830484 1769259008 4.3631443977 4.3434247971 6.0605797768 398 15.8800000000 0.0073592691 0.0045770624 0.0088706231 0.0049317328 0.1238660000 0.0097950000 0.0787770000 0.0000250000 0.0002940000 0.0193340000 8985832 96830484 1770811392 4.3570489883 4.3444104195 6.0677709579 399 15.9200000000 0.0073318873 0.0045839667 0.0088706231 0.0049348910 0.1290920000 0.0119720000 0.0776020000 0.0003000000 0.0002750000 0.0227520000 8987506 96830484 1769529344 4.3488416672 4.3462104797 6.0713376999 400 15.9600000000 0.0067186980 0.0045893036 0.0088706231 0.0049354623 0.0893470000 0.0101100000 0.0464810000 0.0000280000 0.0003870000 0.0191730000 8989180 96830484 1771196416 4.3424172401 4.3453497887 6.0746183395 401 16.0000000000 0.0058728731 0.0045925045 0.0088706231 0.0049397200 0.1520370000 0.0119030000 0.0996610000 0.0002920000 0.0002700000 0.0354130000 8990854 96830484 1769656320 4.3347473145 4.3447022438 6.0787987709 402 16.0400000000 0.0059330096 0.0045958391 0.0088706231 0.0049636217 0.1279040000 0.0111870000 0.0864230000 0.0000240000 0.0002830000 0.0206260000 8992528 96830484 1768132608 4.3265328407 4.3459105492 6.0855598450 403 16.0800000000 0.0059325476 0.0045991560 0.0088706231 0.0049596826 0.1270250000 0.0093580000 0.0798090000 0.0003150000 0.0003510000 0.0231250000 8994202 96830484 1769943040 4.3210625648 4.3464450836 6.0917077065 404 16.1200000000 0.0061023543 0.0046028767 0.0088706231 0.0049553213 0.1278770000 0.0117460000 0.0784290000 0.0000240000 0.0002880000 0.0187680000 8995876 96830484 1768370176 4.3140769005 4.3463010788 6.0960779190 405 16.1600000000 0.0065658325 0.0046077236 0.0088706231 0.0049627938 0.1178180000 0.0098100000 0.0720230000 0.0002930000 0.0003470000 0.0310030000 8997550 96830484 1770037248 4.3066949844 4.3460297585 6.1000933647 406 16.2000000000 0.0069922535 0.0046135968 0.0088706231 0.0049827358 0.1030380000 0.0110680000 0.0679470000 0.0000270000 0.0002970000 0.0185450000 8999224 96830484 1768607744 4.3008952141 4.3476037979 6.1086163521 407 16.2400000000 0.0075919149 0.0046209145 0.0088706231 0.0049934205 0.1266730000 0.0100500000 0.0801540000 0.0003620000 0.0002710000 0.0222660000 9000898 96830484 1770414080 4.2943458557 4.3502855301 6.1141242981 408 16.2800000000 0.0083082095 0.0046299520 0.0088706231 0.0050068994 0.1106610000 0.0116180000 0.0732080000 0.0000270000 0.0002950000 0.0180920000 9002572 96830484 1769148416 4.2893195152 4.3515248299 6.1186904907 409 16.3200000000 0.0089912228 0.0046406153 0.0089912228 0.0050224325 0.1122060000 0.0099650000 0.0668510000 0.0002940000 0.0002730000 0.0302590000 9004246 96830484 1770827776 4.2829217911 4.3530879021 6.1255211830 410 16.3600000000 0.0096067004 0.0046527277 0.0096067004 0.0050236010 0.0866970000 0.0120170000 0.0538640000 0.0000250000 0.0002850000 0.0156120000 9005920 96830484 1769783296 4.2778635025 4.3541111946 6.1294789314 411 16.3999999990 0.0103681320 0.0046666338 0.0103681320 0.0050272151 0.0986970000 0.0117880000 0.0651080000 0.0002880000 0.0003470000 0.0165610000 9007594 96830484 1768263680 4.2725090981 4.3550505638 6.1327929497 412 16.4400000000 0.0100148953 0.0046796150 0.0103681320 0.0050223088 0.0832560000 0.0102430000 0.0567160000 0.0000950000 0.0003180000 0.0114270000 9009268 96830484 1769943040 4.2679705620 4.3543467522 6.1381525993 413 16.4800000000 0.0098900357 0.0046922310 0.0103681320 0.0050239827 0.1428090000 0.0115900000 0.0856450000 0.0002840000 0.0003480000 0.0364510000 9010942 96830484 1768894464 4.2624115944 4.3553495407 6.1453433037 414 16.5200000000 0.0128385602 0.0047119081 0.0128385602 0.0050653668 0.0894130000 0.0093670000 0.0548920000 0.0000250000 0.0005070000 0.0201660000 9012616 96830484 1770545152 4.2587995529 4.3586678505 6.1508741379 415 16.5599999990 0.0129972203 0.0047318727 0.0129972203 0.0050849973 0.1112710000 0.0109870000 0.0773400000 0.0003190000 0.0003420000 0.0178270000 9014290 96830484 1769402368 4.2523946762 4.3611006737 6.1575541496 416 16.6000000000 0.0161206163 0.0047592495 0.0161206163 0.0051112242 0.1234730000 0.0093690000 0.0755550000 0.0000260000 0.0003560000 0.0209070000 9015964 96830484 1771147264 4.2494940758 4.3641366959 6.1617302895 417 16.6400000000 0.0137352329 0.0047807747 0.0161206163 0.0051209770 0.1322810000 0.0118240000 0.0828880000 0.0000580000 0.0000530000 0.0330290000 9017638 96830484 1769021440 4.2407202721 4.3643512726 6.1653900146 418 16.6800000000 0.0177259799 0.0048117441 0.0177259799 0.0052711000 0.0843160000 0.0094570000 0.0378050000 0.0000250000 0.0003540000 0.0189960000 9019312 96830484 1770655744 4.2310147285 4.3697605133 6.1745281219 419 16.7199999990 0.0220067296 0.0048527822 0.0220067296 0.0053006683 0.1287140000 0.0117250000 0.0745940000 0.0002870000 0.0002660000 0.0232700000 9020986 96830484 1768767488 4.2337198257 4.3697533607 6.1810688972 420 16.7600000000 0.0293692630 0.0049111548 0.0293692630 0.0054286142 0.0891600000 0.0098220000 0.0450220000 0.0000300000 0.0003220000 0.0196320000 9022660 96830484 1770291200 4.2338075638 4.3759765625 6.1871509552 421 16.8000000000 0.0228737425 0.0049538213 0.0293692630 0.0054303405 0.0962150000 0.0125160000 0.0433060000 0.0003170000 0.0002730000 0.0351200000 9024334 96830484 1768386560 4.2230963707 4.3732700348 6.1922855377 422 16.8400000000 0.0174224116 0.0049833677 0.0293692630 0.0054317020 0.0628770000 0.0097120000 0.0293010000 0.0000260000 0.0002980000 0.0189550000 9026008 96830484 1768243200 4.2134571075 4.3705034256 6.1969394684 423 16.8799999990 0.0171730071 0.0050121848 0.0293692630 0.0054612313 0.1253070000 0.0095700000 0.0746510000 0.0003880000 0.0002770000 0.0239690000 9027682 96830484 1767735296 4.2079539299 4.3709759712 6.2021880150 424 16.9200000000 0.0147066889 0.0050350492 0.0293692630 0.0054938961 0.1098640000 0.0100510000 0.0675100000 0.0000250000 0.0003670000 0.0210470000 9029356 96830484 1769385984 4.1943898201 4.3713307381 6.2117848396 425 16.9600000000 0.0120334802 0.0050515161 0.0293692630 0.0054884991 0.1297630000 0.0096060000 0.0735820000 0.0003000000 0.0003500000 0.0379760000 9031030 96830484 1771048960 4.1879234314 4.3703718185 6.2153072357 426 17.0000000000 0.0115213916 0.0050667036 0.0293692630 0.0055018245 0.1078190000 0.0111590000 0.0628700000 0.0000250000 0.0002990000 0.0212350000 9032704 96830484 1769910272 4.1817502975 4.3717513084 6.2203288078 427 17.0400000000 0.0110187093 0.0050806427 0.0293692630 0.0055058224 0.0899950000 0.0115470000 0.0442640000 0.0003830000 0.0002780000 0.0260760000 9034378 96830484 1767768064 4.1758589745 4.3732266426 6.2247867584 428 17.0800000000 0.0113940174 0.0050953936 0.0293692630 0.0055144959 0.1270230000 0.0119270000 0.0788630000 0.0000260000 0.0003100000 0.0225950000 9036052 96830484 1766846464 4.1709070206 4.3757052422 6.2287411690 429 17.1200000000 0.0107962545 0.0051086823 0.0293692630 0.0055134961 0.1106190000 0.0096650000 0.0538730000 0.0003120000 0.0003590000 0.0402690000 9037726 96830484 1768259584 4.1655344963 4.3754997253 6.2309837341 430 17.1600000000 0.0108288219 0.0051219850 0.0293692630 0.0055158388 0.1059570000 0.0089900000 0.0559660000 0.0000260000 0.0003800000 0.0228040000 9039400 96830484 1770033152 4.1606693268 4.3758783340 6.2345037460 431 17.2000000000 0.0103275189 0.0051340628 0.0293692630 0.0055131329 0.1289570000 0.0113170000 0.0721850000 0.0003070000 0.0002720000 0.0267060000 9041074 96830484 1769005056 4.1558489799 4.3749713898 6.2381601334 432 17.2400000000 0.0107141864 0.0051469797 0.0293692630 0.0055141827 0.0897110000 0.0098520000 0.0431690000 0.0000240000 0.0003860000 0.0224840000 9042748 96830484 1770528768 4.1505608559 4.3760142326 6.2427163124 433 17.2800000000 0.0105407238 0.0051594364 0.0293692630 0.0055121795 0.1315260000 0.0117740000 0.0741860000 0.0005500000 0.0006370000 0.0396520000 9044422 96830484 1768624128 4.1465554237 4.3773322105 6.2464489937 434 17.3200000000 0.0107741635 0.0051723736 0.0293692630 0.0055134979 0.0870590000 0.0089990000 0.0443750000 0.0000270000 0.0003040000 0.0236190000 9046096 96830484 1770164224 4.1411085129 4.3787240982 6.2488813400 435 17.3600000000 0.0105487844 0.0051847331 0.0293692630 0.0055112859 0.1541180000 0.0105800000 0.1107670000 0.0003070000 0.0006890000 0.0270800000 9047770 96830484 1769148416 4.1357908249 4.3770418167 6.2503762245 436 17.4000000000 0.0109743504 0.0051980121 0.0293692630 0.0055172099 0.0842440000 0.0089580000 0.0418720000 0.0000260000 0.0002980000 0.0250150000 9049444 96830484 1770799104 4.1308083534 4.3772239685 6.2531652451 437 17.4400000000 0.0109014483 0.0052110634 0.0293692630 0.0055154881 0.1296040000 0.0110740000 0.0677920000 0.0003830000 0.0002770000 0.0453500000 9051118 96830484 1768656896 4.1244621277 4.3784675598 6.2562112808 438 17.4800000000 0.0105683291 0.0052232946 0.0293692630 0.0055146304 0.1158080000 0.0093520000 0.0861120000 0.0000070000 0.0000610000 0.0156350000 9052792 96830484 1770291200 4.1193237305 4.3766813278 6.2585535049 439 17.5200000000 0.0100537864 0.0052342980 0.0293692630 0.0055121595 0.1332170000 0.0142650000 0.0755010000 0.0003760000 0.0002780000 0.0275030000 9054466 96830484 1768370176 4.1143794060 4.3760156631 6.2609000206 440 17.5600000000 0.0105229411 0.0052463176 0.0293692630 0.0055131504 0.0891470000 0.0094840000 0.0441550000 0.0000260000 0.0003130000 0.0225760000 9056140 96830484 1769893888 4.1091594696 4.3763036728 6.2630486488 441 17.6000000000 0.0106869759 0.0052586547 0.0293692630 0.0055119687 0.1174850000 0.0106850000 0.0627140000 0.0003810000 0.0002810000 0.0384850000 9057814 96830484 1769132032 4.1033468246 4.3762011528 6.2644801140 442 17.6400000000 0.0108965831 0.0052714102 0.0293692630 0.0055111607 0.0993210000 0.0092980000 0.0511450000 0.0000250000 0.0008740000 0.0227590000 9059488 96830484 1770528768 4.0981197357 4.3751025200 6.2655949593 443 17.6800000000 0.0108308764 0.0052839598 0.0293692630 0.0055110397 0.1081100000 0.0108390000 0.0506560000 0.0003100000 0.0002750000 0.0276470000 9061162 96830484 1769529344 4.0923771858 4.3761615753 6.2674403191 444 17.7200000000 0.0105453702 0.0052958098 0.0293692630 0.0055083660 0.0900450000 0.0096130000 0.0449360000 0.0000280000 0.0003830000 0.0230690000 9062836 96830484 1771180032 4.0868844986 4.3753957748 6.2698864937 445 17.7600000000 0.0104576172 0.0053074094 0.0293692630 0.0055055081 0.1311670000 0.0109170000 0.0737330000 0.0003830000 0.0002770000 0.0409370000 9064510 96830484 1770037248 4.0819315910 4.3750724792 6.2715301514 446 17.8000000000 0.0113886278 0.0053210444 0.0293692630 0.0055069919 0.0864400000 0.0111620000 0.0393720000 0.0000250000 0.0002980000 0.0239620000 9066184 96830484 1767895040 4.0762867928 4.3751959801 6.2730474472 447 17.8400000000 0.0113811297 0.0053346017 0.0293692630 0.0055065983 0.1088110000 0.0087890000 0.0572520000 0.0003840000 0.0019810000 0.0285620000 9067858 96830484 1766100992 4.0706124306 4.3747863770 6.2764835358 448 17.8800000000 0.0111299455 0.0053475377 0.0293692630 0.0055054410 0.1066680000 0.0098730000 0.0565210000 0.0000290000 0.0007150000 0.0226030000 9069532 96830484 1767862272 4.0639710426 4.3743891716 6.2784118652 449 17.9200000000 0.0107291965 0.0053595236 0.0293692630 0.0055026467 0.1319140000 0.0094880000 0.0743420000 0.0003080000 0.0002740000 0.0425210000 9071206 96830484 1769652224 4.0585212708 4.3729953766 6.2794156075 450 17.9600000000 0.0109195756 0.0053718792 0.0293692630 0.0054994240 0.1259850000 0.0111840000 0.0762580000 0.0000310000 0.0003760000 0.0225120000 9072880 96830484 1767510016 4.0530171394 4.3719444275 6.2807793617 451 18.0000000000 0.0102310088 0.0053826534 0.0293692630 0.0055009871 0.1286500000 0.0095870000 0.0747550000 0.0003070000 0.0002710000 0.0276760000 9074554 96830484 1769271296 4.0396914482 4.3698554039 6.2847228050 452 18.0400000000 0.0049423091 0.0053816792 0.0293692630 0.0054984245 0.1081380000 0.0094140000 0.0581390000 0.0000310000 0.0003110000 0.0222450000 9076228 96830484 1770795008 4.0338072777 4.3629517555 6.2871379852 453 18.0800000000 0.0041723335 0.0053790095 0.0293692630 0.0054934472 0.1324880000 0.0108600000 0.0756180000 0.0005420000 0.0002980000 0.0402210000 9077902 96830484 1769783296 4.0274205208 4.3586697578 6.2893233299 454 18.1200000000 0.0050910511 0.0053783752 0.0293692630 0.0054900442 0.1255540000 0.0107400000 0.0772470000 0.0000300000 0.0003060000 0.0225750000 9079576 96830484 1768009728 4.0200242996 4.3557476997 6.2927837372 455 18.1600000000 0.0058854185 0.0053794896 0.0293692630 0.0054855046 0.0905240000 0.0093720000 0.0451020000 0.0003230000 0.0003630000 0.0271050000 9081250 96830484 1769639936 4.0132899284 4.3546996117 6.2963128090 456 18.2000000000 0.0084008984 0.0053861155 0.0293692630 0.0054813211 0.1262380000 0.0106070000 0.0759160000 0.0000280000 0.0003080000 0.0227260000 9082924 96830484 1768517632 4.0077157021 4.3500952721 6.2979159355 457 18.2400000000 0.0087129585 0.0053933953 0.0293692630 0.0054783378 0.1318940000 0.0092620000 0.0756680000 0.0002970000 0.0003530000 0.0413600000 9084598 96830484 1770176512 4.0008196831 4.3494977951 6.3005862236 458 18.2800000000 0.0148667265 0.0054140794 0.0293692630 0.0054873872 0.0868160000 0.0110310000 0.0406280000 0.0000280000 0.0003120000 0.0229570000 9086272 96830484 1768767488 3.9935870171 4.3430633545 6.3023166656 459 18.3200000000 0.0154059315 0.0054358481 0.0293692630 0.0054874573 0.1302750000 0.0087140000 0.0956150000 0.0003050000 0.0005490000 0.0199110000 9087946 96830484 1766985728 3.9872498512 4.3414597511 6.3037796021 460 18.3600000000 0.0406694263 0.0055124429 0.0406694263 0.0055913982 0.1254280000 0.0089740000 0.0776090000 0.0000260000 0.0003010000 0.0213650000 9089620 96830484 1768636416 3.9814734459 4.3147926331 6.3054990768 461 18.4000000000 0.0301909521 0.0055659754 0.0406694263 0.0056131887 0.1167000000 0.0092100000 0.0646460000 0.0002860000 0.0003360000 0.0372090000 9091294 96830484 1770274816 3.9743273258 4.3240308762 6.3081622124 462 18.4400000000 0.5019711256 0.0066404455 0.5019711256 0.0225802063 0.1238640000 0.0111530000 0.0731100000 0.0000260000 0.0003720000 0.0342040000 9092968 96830484 1768910848 3.9669184685 3.8513724804 6.3089022636 463 18.4800000000 0.4059753716 0.0075029399 0.5019711256 0.0230095222 0.1263920000 0.0091400000 0.0768900000 0.0003590000 0.0002750000 0.0254650000 9094642 96830484 1770639360 3.9617350101 3.9475417137 6.3111491203 464 18.5200000000 0.4177706540 0.0083871376 0.5019711256 0.0229895278 0.1113030000 0.0111030000 0.0752960000 0.0000280000 0.0003680000 0.0195200000 9096316 96830484 1769148416 3.9550714493 3.9343168736 6.3118133545 465 18.5600000000 0.4662440121 0.0093717760 0.5019711256 0.0230606605 0.1284090000 0.0089780000 0.0754160000 0.0002910000 0.0003510000 0.0382940000 9097990 96830484 1770811392 3.9483590126 3.8846759796 6.3145627975 466 18.6000000000 0.6214333773 0.0106852129 0.6214333773 0.0241036400 0.1253670000 0.0109630000 0.0762560000 0.0000280000 0.0002860000 0.0201610000 9099664 96830484 1769783296 3.9422807693 3.7282187939 6.3170328140 467 18.6400000000 0.8282750845 0.0124359407 0.8282750845 0.0258940049 0.1287620000 0.0109450000 0.0730930000 0.0005060000 0.0002730000 0.0278210000 9101338 96830484 1768026112 3.9368269444 3.5218288898 6.3178319931 468 18.6800000000 0.7818546891 0.0140799978 0.8282750845 0.0259737162 0.1276710000 0.0094830000 0.0768710000 0.0000260000 0.0002930000 0.0217620000 9103012 96830484 1769795584 3.9315271378 3.5673236847 6.3176741600 469 18.7200000000 0.7101156712 0.0155640824 0.8282750845 0.0261697065 0.1323810000 0.0110370000 0.0764420000 0.0003670000 0.0002760000 0.0391090000 9104686 96830484 1768243200 3.9250748158 3.6390600204 6.3200268745 470 18.7600000000 0.6829617620 0.0169840775 0.8282750845 0.0261761345 0.1248810000 0.0087400000 0.0774540000 0.0000250000 0.0002860000 0.0208270000 9106360 96830484 1769877504 3.9190139771 3.6651964188 6.3207798004 471 18.8000000000 0.6846255064 0.0184015752 0.8282750845 0.0261558296 0.1292740000 0.0109720000 0.0764060000 0.0003020000 0.0002790000 0.0261820000 9108034 96830484 1768517632 3.9052522182 3.6592895985 6.3219099045 472 18.8400000000 0.6738861799 0.0197903138 0.8282750845 0.0261358713 0.1276170000 0.0091420000 0.0786440000 0.0000260000 0.0002870000 0.0208240000 9109708 96830484 1770176512 3.9002640247 3.6688630581 6.3233342171 473 18.8800000000 0.6734230518 0.0211722012 0.8282750845 0.0261092579 0.1332450000 0.0111490000 0.0780640000 0.0002930000 0.0003390000 0.0382660000 9111382 96830484 1768767488 3.8983135223 3.6672420502 6.3220782280 474 18.9200000000 0.6690549850 0.0225390425 0.8282750845 0.0260855146 0.0868090000 0.0086490000 0.0473390000 0.0001200000 0.0003130000 0.0224510000 9113056 96830484 1770414080 3.8960886002 3.6697840691 6.3223223686 475 18.9600000000 0.6595476866 0.0238801133 0.8282750845 0.0260658862 0.1087010000 0.0104540000 0.0569880000 0.0003020000 0.0003540000 0.0323660000 9114730 96830484 1769021440 3.8924751282 3.6784794331 6.3238763809 476 19.0000000000 0.6438632607 0.0251825989 0.8282750845 0.0260634861 0.0965450000 0.0085390000 0.0659600000 0.0000280000 0.0003880000 0.0163300000 9116404 96830484 1770815488 3.8873736858 3.6914789677 6.3241877556 477 19.0400000000 0.6316706538 0.0264540624 0.8282750845 0.0260513374 0.1266270000 0.0113800000 0.0723630000 0.0003160000 0.0003630000 0.0369430000 9118078 96830484 1769275392 3.8851134777 3.7013766766 6.3236360550 478 19.0800000000 0.6211659312 0.0276982295 0.8282750845 0.0260417150 0.0964480000 0.0086060000 0.0487580000 0.0000240000 0.0002830000 0.0216580000 9119752 96830484 1770893312 3.8789081573 3.7096164227 6.3296403885 479 19.1200000000 0.6067261100 0.0289070559 0.8282750845 0.0260289034 0.1298710000 0.0109050000 0.0784870000 0.0003560000 0.0002660000 0.0267230000 9121426 96830484 1769910272 3.8784310818 3.7240622044 6.3300948143 480 19.1600000000 0.6686126590 0.0302397759 0.8282750845 0.0261382499 0.1281380000 0.0108970000 0.0799130000 0.0000260000 0.0003840000 0.0230680000 9123100 96830484 1768026112 3.8783736229 3.6615614891 6.3291983604 481 19.2000000000 0.5939254761 0.0314116797 0.8282750845 0.0263723933 0.1327440000 0.0091430000 0.0788040000 0.0003510000 0.0002810000 0.0389060000 9124774 96830484 1769775104 3.8768303394 3.7354991436 6.3305830956 482 19.2400000000 0.6424643993 0.0326794239 0.8282750845 0.0264231387 0.1258320000 0.0105780000 0.0797340000 0.0000250000 0.0002860000 0.0222410000 9126448 96830484 1768280064 3.8761243820 3.6872258186 6.3309130669 483 19.2800000000 0.5773849487 0.0338071786 0.8282750845 0.0265966175 0.1282790000 0.0088860000 0.0780810000 0.0002870000 0.0002600000 0.0278140000 9128122 96830484 1770020864 3.8751721382 3.7510941029 6.3324584961 484 19.3200000000 0.5692709684 0.0349135088 0.8282750845 0.0265797993 0.1282670000 0.0109930000 0.0791290000 0.0000270000 0.0003570000 0.0222270000 9129796 96830484 1768894464 3.8755033016 3.7587373257 6.3333616257 485 19.3600000000 0.5516361594 0.0359789163 0.8282750845 0.0265835748 0.0953310000 0.0092790000 0.0409100000 0.0002880000 0.0003390000 0.0391620000 9131470 96830484 1770512384 3.8758435249 3.7763013840 6.3335375786 486 19.4000000000 0.4071510136 0.0367426449 0.8282750845 0.0274379424 0.1228660000 0.0108780000 0.0788570000 0.0000260000 0.0003460000 0.0211090000 9133144 96830484 1769132032 3.8747167587 3.9208295345 6.3368387222 487 19.4400000000 0.6939773560 0.0380922028 0.8282750845 0.0302173916 0.1281970000 0.0092740000 0.0748790000 0.0002900000 0.0005010000 0.0302790000 9134818 96830484 1770815488 3.8752453327 3.6341226101 6.3379855156 488 19.4800000000 0.4766470194 0.0389908807 0.8282750845 0.0318669086 0.1280610000 0.0110340000 0.0784460000 0.0000280000 0.0002940000 0.0222470000 9136492 96830484 1769766912 3.8754324913 3.8503932953 6.3413715363 489 19.5200000000 0.3061169684 0.0395371508 0.8282750845 0.0328443514 0.1382390000 0.0110680000 0.0834030000 0.0000620000 0.0000540000 0.0383300000 9138166 96830484 1767645184 3.8728585243 4.0213994980 6.3473052979 490 19.5600000000 0.7353366613 0.0409571498 0.8282750845 0.0379769782 0.0813570000 0.0091200000 0.0384470000 0.0000270000 0.0002830000 0.0281420000 9139840 96830484 1769414656 3.8737239838 3.5929052830 6.3465876579 491 19.6000000000 0.5868066549 0.0420688596 0.8282750845 0.0385671547 0.1453260000 0.0104870000 0.0855120000 0.0002950000 0.0002700000 0.0302730000 9141514 96830484 1768267776 3.8745987415 3.7418391705 6.3511805534 492 19.6400000000 0.5351561904 0.0430710696 0.8282750845 0.0386214488 0.1289090000 0.0090110000 0.0791470000 0.0000250000 0.0002990000 0.0241110000 9143188 96830484 1770053632 3.8748536110 3.7937157154 6.3544754982 493 19.6800000000 0.5231240392 0.0440448079 0.8282750845 0.0385927541 0.1420760000 0.0107710000 0.0818970000 0.0003600000 0.0002720000 0.0433480000 9144862 96830484 1768988672 3.8769721985 3.8073282242 6.3547039032 494 19.7200000000 0.5464247465 0.0450617714 0.8282750845 0.0385648238 0.1355670000 0.0099380000 0.0848220000 0.0000280000 0.0003180000 0.0258540000 9146536 96830484 1770782720 3.8758058548 3.7838835716 6.3596377373 495 19.7600000000 0.4864273369 0.0459534190 0.8282750845 0.0386497276 0.1303270000 0.0108370000 0.0802820000 0.0002890000 0.0003490000 0.0304080000 9148210 96830484 1769656320 3.8751628399 3.8437230587 6.3656935692 496 19.8000000000 0.6448945403 0.0471609615 0.8282750845 0.0392054373 0.1280180000 0.0090410000 0.0808090000 0.0000280000 0.0003020000 0.0270660000 9149884 96830484 1771323392 3.8747053146 3.6860067844 6.3695111275 497 19.8400000000 0.2739302814 0.0476172378 0.8282750845 0.0426987190 0.1337830000 0.0108550000 0.0771040000 0.0002900000 0.0002660000 0.0397300000 9151558 96830484 1770164224 3.8757858276 4.0582356453 6.3717904091 498 19.8800000000 0.6213555932 0.0487693229 0.8282750845 0.0453252573 0.1247090000 0.0106850000 0.0753010000 0.0000290000 0.0003650000 0.0278460000 9153232 96830484 1768497152 3.8767030239 3.7113902569 6.3730125427 499 19.9200000000 0.5157486796 0.0497051533 0.8282750845 0.0455553045 0.1306530000 0.0094270000 0.0805920000 0.0003800000 0.0006060000 0.0342520000 9154906 96830484 1770164224 3.8768863678 3.8166072369 6.3785815239 500 19.9600000000 0.6665877104 0.0509389184 0.8282750845 0.0459680267 0.1440680000 0.0108480000 0.0831450000 0.0000290000 0.0003760000 0.0285090000 9156580 96830484 1769013248 3.8772354126 3.6669313908 6.3808846474 501 20.0000000000 0.6062684059 0.0520473605 0.8282750845 0.0460222632 0.1436380000 0.0090860000 0.0803270000 0.0003900000 0.0002830000 0.0481310000 9158254 96830484 1770663936 3.8779439926 3.7277832031 6.3838081360 502 20.0400000000 0.6731163859 0.0532845498 0.8282750845 0.0460516296 0.1356580000 0.0105470000 0.0830840000 0.0000320000 0.0002960000 0.0292880000 9159928 96830484 1769537536 3.8778994083 3.6613671780 6.3868064880 503 20.0800000000 0.6564045548 0.0544835955 0.8282750845 0.0460196674 0.1305770000 0.0093240000 0.0818200000 0.0003720000 0.0002920000 0.0331660000 9161602 96830484 1771188224 3.8769161701 3.6789884567 6.3902983665 504 20.1200000000 0.6654819846 0.0556958939 0.8282750845 0.0459744326 0.1286380000 0.0111430000 0.0826820000 0.0000250000 0.0002930000 0.0289980000 9163276 96830484 1770045440 3.8765602112 3.6701309681 6.3933525085 505 20.1600000000 0.6710240841 0.0569143656 0.8282750845 0.0459295454 0.1650040000 0.0111550000 0.0825940000 0.0003070000 0.0002800000 0.0528730000 9164950 96830484 1768411136 3.8760280609 3.6654210091 6.3957557678 506 20.2000000000 0.6550804973 0.0580965121 0.8282750845 0.0458982005 0.1304800000 0.0097900000 0.0804600000 0.0000290000 0.0002980000 0.0301660000 9166624 96830484 1770029056 3.8762986660 3.6815564632 6.3978471756 507 20.2400000000 0.6564952135 0.0592767856 0.8282750845 0.0458542567 0.1468560000 0.0109530000 0.0824100000 0.0003000000 0.0003490000 0.0363060000 9168298 96830484 1768919040 3.8756709099 3.6797606945 6.4006218910 508 20.2800000000 0.6285970211 0.0603974948 0.8282750845 0.0458392292 0.1305560000 0.0093510000 0.0811290000 0.0000260000 0.0003770000 0.0310760000 9169972 96830484 1770553344 3.8736364841 3.7071454525 6.4038844109 509 20.3200000000 0.6353790164 0.0615271245 0.8282750845 0.0457946646 0.1523890000 0.0112120000 0.0826250000 0.0003080000 0.0002800000 0.0523460000 9171646 96830484 1769410560 3.8736929893 3.6998307705 6.4066944122 510 20.3600000000 0.6310787201 0.0626438923 0.8282750845 0.0457533554 0.1067460000 0.0090580000 0.0621490000 0.0000320000 0.0002990000 0.0295870000 9173320 96830484 1771155456 3.8740415573 3.7047383785 6.4061708450 511 20.4000000000 0.6673968434 0.0638273619 0.8282750845 0.0457282051 0.1455200000 0.0111070000 0.0825760000 0.0003030000 0.0002930000 0.0367010000 9174994 96830484 1769918464 3.8728375435 3.6680064201 6.4080319405 512 20.4400000000 0.6375189424 0.0649478532 0.8282750845 0.0457140655 0.1473670000 0.0112760000 0.0837310000 0.0000330000 0.0002970000 0.0311500000 9176668 96830484 1768247296 3.8706891537 3.6983244419 6.4101715088 513 20.4800000000 0.6415691972 0.0660718715 0.8282750845 0.0456701580 0.1424930000 0.0094610000 0.0706270000 0.0003780000 0.0002760000 0.0559520000 9219302 96830484 1770012672 3.8707005978 3.6944921017 6.4098920822 514 20.5200000000 0.6312078238 0.0671713577 0.8282750845 0.0456324089 0.1334650000 0.0112280000 0.0822440000 0.0000250000 0.0002910000 0.0315370000 9304944 96830484 1769029632 3.8690185547 3.7050037384 6.4119620323 515 20.5600000000 0.6063035131 0.0682182163 0.8282750845 0.0456092488 0.1462220000 0.0092680000 0.0831180000 0.0002940000 0.0002590000 0.0365840000 9306618 96830484 1770680320 3.8679516315 3.7297172546 6.4125080109 516 20.6000000000 0.6248710155 0.0692970008 0.8282750845 0.0455687314 0.1317930000 0.0112140000 0.0839100000 0.0000240000 0.0002840000 0.0305620000 9308292 96830484 1769537536 3.8664529324 3.7110514641 6.4120926857 517 20.6400000000 0.6145218611 0.0703515943 0.8282750845 0.0455308266 0.1526260000 0.0093630000 0.0842840000 0.0002940000 0.0002690000 0.0526120000 9309966 96830484 1771188224 3.8653309345 3.7209458351 6.4110279083 518 20.6800000000 0.6140749454 0.0714012533 0.8282750845 0.0454883267 0.1423940000 0.0109740000 0.0854350000 0.0000290000 0.0003670000 0.0313030000 9311640 96830484 1770045440 3.8638257980 3.7206735611 6.4110331535 519 20.7200000000 0.6153280139 0.0724492818 0.8282750845 0.0454456543 0.1483290000 0.0114360000 0.0850400000 0.0003470000 0.0002670000 0.0370710000 9313314 96830484 1768284160 3.8607518673 3.7193126678 6.4120135307 520 20.7600000000 0.6189811826 0.0735003046 0.8282750845 0.0454026485 0.1313290000 0.0098130000 0.0851340000 0.0000250000 0.0002830000 0.0302570000 9314988 96830484 1770029056 3.8589477539 3.7140314579 6.4124522209 521 20.8000000000 0.6256379485 0.0745600698 0.8282750845 0.0453591842 0.1216050000 0.0110440000 0.0503980000 0.0002870000 0.0003060000 0.0535430000 9316662 96830484 1768902656 3.8567748070 3.7067434788 6.4113178253 522 20.8400000000 0.6334594488 0.0756307583 0.8282750845 0.0453162116 0.1159970000 0.0090810000 0.0714150000 0.0000270000 0.0006190000 0.0288910000 9318336 96830484 1770553344 3.8538935184 3.6976771355 6.4114170074 523 20.8800000000 0.6387676001 0.0767075017 0.8282750845 0.0452732824 0.1457600000 0.0115260000 0.0849090000 0.0002870000 0.0002630000 0.0370050000 9320010 96830484 1769410560 3.8534233570 3.6929404736 6.4060063362 524 20.9200000000 0.6358650923 0.0777745964 0.8282750845 0.0452323398 0.1306640000 0.0094390000 0.0855760000 0.0000270000 0.0002930000 0.0295320000 9321684 96830484 1771155456 3.8518404961 3.6941833496 6.4051394463 525 20.9600000000 0.6423726082 0.0788500212 0.8282750845 0.0451893299 0.1566820000 0.0112740000 0.0851430000 0.0003670000 0.0002840000 0.0538240000 9323358 96830484 1770045440 3.8486526012 3.6853170395 6.4053983688 526 21.0000000000 0.6429905891 0.0799225317 0.8282750845 0.0451465518 0.1387520000 0.0110970000 0.0858420000 0.0000250000 0.0003720000 0.0325680000 9325032 96830484 1768108032 3.8458628654 3.6851162910 6.4020385742 527 21.0400000000 0.6477107406 0.0809999287 0.8282750845 0.0451040867 0.1466350000 0.0095910000 0.0851080000 0.0003610000 0.0002730000 0.0370720000 9326706 96830484 1769922560 3.8432114124 3.6802973747 6.3979744911 528 21.0800000000 0.6534577608 0.0820841292 0.8282750845 0.0450614214 0.1476400000 0.0112900000 0.0858380000 0.0000250000 0.0002890000 0.0320940000 9328380 96830484 1768763392 3.8388893604 3.6724107265 6.3980693817 529 21.1200000000 0.6566330194 0.0831702329 0.8282750845 0.0450191380 0.1487350000 0.0097540000 0.0647050000 0.0004740000 0.0002820000 0.0574040000 9330054 96830484 1770434560 3.8346519470 3.6681978703 6.3962168694 530 21.1600000000 0.6624059081 0.0842631304 0.8282750845 0.0449766786 0.1482720000 0.0115870000 0.0854770000 0.0000250000 0.0003540000 0.0321040000 9331728 96830484 1769275392 3.8320455551 3.6630663872 6.3917245865 531 21.2000000000 0.6543648839 0.0853367684 0.8282750845 0.0449371981 0.1291630000 0.0097800000 0.0651120000 0.0003000000 0.0003530000 0.0382650000 9333402 96830484 1771036672 3.8287086487 3.6700789928 6.3888592720 532 21.2400000000 0.6520460844 0.0864020115 0.8282750845 0.0448963220 0.1513590000 0.0116020000 0.0869410000 0.0000270000 0.0003740000 0.0464440000 9335076 96830484 1769893888 3.8242323399 3.6719102859 6.3871569633 533 21.2800000000 0.6548203826 0.0874684624 0.8282750845 0.0448543810 0.1851730000 0.0115460000 0.0999190000 0.0000640000 0.0000690000 0.0585150000 9336750 96830484 1767735296 3.8205952644 3.6685094833 6.3847413063 534 21.3200000000 0.6531295180 0.0885277528 0.8282750845 0.0448128872 0.1102440000 0.0103010000 0.0593410000 0.0000270000 0.0002970000 0.0323150000 9338424 96830484 1769529344 3.8166184425 3.6676867008 6.3830537796 535 21.3600000000 0.6549238563 0.0895864371 0.8282750845 0.0447715792 0.1274170000 0.0112900000 0.0653740000 0.0003780000 0.0002790000 0.0373610000 9340098 96830484 1768390656 3.8113329411 3.6645660400 6.3828902245 536 21.4000000000 0.6590809822 0.0906489269 0.8282750845 0.0447299372 0.1308990000 0.0098220000 0.0857980000 0.0000280000 0.0003580000 0.0289500000 9341772 96830484 1770053632 3.8073754311 3.6600759029 6.3796710968 537 21.4400000000 0.6579042077 0.0917052682 0.8282750845 0.0446885430 0.1422240000 0.0115930000 0.0639390000 0.0003610000 0.0002730000 0.0461770000 9343446 96830484 1768910848 3.8030984402 3.6617379189 6.3750228882 538 21.4800000000 0.6631788611 0.0927674868 0.8282750845 0.0446470806 0.1333040000 0.0099510000 0.0839920000 0.0000300000 0.0002900000 0.0302750000 9345120 96830484 1770545152 3.7982568741 3.6569707394 6.3713212013 539 21.5200000000 0.6597861052 0.0938194694 0.8282750845 0.0446069797 0.1109210000 0.0118230000 0.0584600000 0.0002910000 0.0002680000 0.0340430000 9346794 96830484 1769418752 3.7939283848 3.6591947079 6.3692140579 540 21.5600000000 0.6619403362 0.0948715451 0.8282750845 0.0445659007 0.1271080000 0.0100030000 0.0861970000 0.0000280000 0.0002890000 0.0245210000 9348468 96830484 1771163648 3.7888600826 3.6567478180 6.3670458794 541 21.6000000000 0.6637886763 0.0959231479 0.8282750845 0.0445261116 0.1551610000 0.0114350000 0.0841530000 0.0002990000 0.0003560000 0.0529100000 9350142 96830484 1770037248 3.7839510441 3.6539452076 6.3656225204 542 21.6400000000 0.6664276123 0.0969757392 0.8282750845 0.0444887362 0.1014010000 0.0116020000 0.0588680000 0.0000270000 0.0002900000 0.0244340000 9351816 96830484 1768259584 3.7797622681 3.6484062672 6.3643765450 543 21.6800000000 0.6740013957 0.0980384015 0.8282750845 0.0444505447 0.1458160000 0.0100510000 0.0834980000 0.0002950000 0.0002720000 0.0356890000 9353490 96830484 1769926656 3.7754867077 3.6387205124 6.3610601425 544 21.7200000000 0.6935774684 0.0991331425 0.8282750845 0.0444273525 0.1479630000 0.0116830000 0.0855980000 0.0000260000 0.0002770000 0.0313070000 9355164 96830484 1768783872 3.7678594589 3.6157441139 6.3505201340 545 21.7600000000 0.6864110827 0.1002107167 0.8282750845 0.0443894504 0.1485430000 0.0099940000 0.0855540000 0.0004870000 0.0002990000 0.0461620000 9356838 96830484 1770418176 3.7630021572 3.6251695156 6.3445572853 546 21.8000000000 0.7068233490 0.1013217288 0.8282750845 0.0443553151 0.1324920000 0.0114630000 0.0862270000 0.0000280000 0.0002920000 0.0283790000 9358512 96830484 1769259008 3.7585163116 3.6038956642 6.3399209976 547 21.8400000000 0.7095046043 0.1024335805 0.8282750845 0.0443167323 0.1456380000 0.0102370000 0.0865920000 0.0000590000 0.0000550000 0.0351390000 9360186 96830484 1770958848 3.7538564205 3.5987894535 6.3343744278 548 21.8800000000 0.7198863626 0.1035603192 0.8282750845 0.0442776407 0.1300290000 0.0120990000 0.0803670000 0.0000250000 0.0002940000 0.0284360000 9361860 96830484 1769910272 3.7480957508 3.5929453373 6.3280210495 549 21.9200000000 0.7125939727 0.1046696701 0.8282750845 0.0442400615 0.1334130000 0.0118770000 0.0663420000 0.0002950000 0.0003410000 0.0484740000 9363534 96830484 1768136704 3.7429127693 3.6029787064 6.3226490021 550 21.9600000000 0.7186527252 0.1057860029 0.8282750845 0.0442024883 0.1013370000 0.0106370000 0.0452850000 0.0000260000 0.0003120000 0.0283460000 9365208 96830484 1769795584 3.7394196987 3.5894167423 6.3189616203 551 22.0000000000 0.7279100418 0.1069150846 0.8282750845 0.0441658413 0.1112960000 0.0117140000 0.0591170000 0.0003500000 0.0002690000 0.0337960000 9366882 96830484 1768370176 3.7351481915 3.5786960125 6.3120393753 552 22.0400000000 0.7322071791 0.1080478602 0.8282750845 0.0441261341 0.1250940000 0.0101100000 0.0873370000 0.0000270000 0.0003730000 0.0212270000 9368556 96830484 1770033152 3.7296514511 3.5806384087 6.3044848442 553 22.0800000000 0.7361746430 0.1091837133 0.8282750845 0.0440863932 0.1533360000 0.0115410000 0.0870570000 0.0002960000 0.0002750000 0.0480560000 9370230 96830484 1768861696 3.7255344391 3.5777535439 6.2993893623 554 22.1200000000 0.7263910770 0.1102978060 0.8282750845 0.0440485494 0.1433570000 0.0099200000 0.0874350000 0.0000260000 0.0002910000 0.0272430000 9371904 96830484 1770577920 3.7212336063 3.5853185654 6.2945551872 555 22.1600000000 0.7397669554 0.1114319847 0.8282750845 0.0440108940 0.1306660000 0.0119930000 0.0741620000 0.0003550000 0.0002820000 0.0330310000 9373578 96830484 1769148416 3.7173328400 3.5726687908 6.2892484665 556 22.2000000000 0.7233500481 0.1125325567 0.8282750845 0.0439762441 0.1095770000 0.0101640000 0.0660860000 0.0000250000 0.0002840000 0.0269850000 9375252 96830484 1770926080 3.7138195038 3.5873823166 6.2844934464 557 22.2400000000 0.7411343455 0.1136611057 0.8282750845 0.0439398542 0.1493270000 0.0121990000 0.0873160000 0.0002850000 0.0002620000 0.0395230000 9376926 96830484 1768767488 3.7094469070 3.5717000961 6.2800579071 558 22.2800000000 0.7532724142 0.1148073625 0.8282750845 0.0439021422 0.1398670000 0.0102190000 0.0871640000 0.0000270000 0.0003610000 0.0274470000 9378600 96830484 1770528768 3.7060561180 3.5583453178 6.2753796577 559 22.3200000000 0.7377316356 0.1159217172 0.8282750845 0.0438706493 0.1479560000 0.0118370000 0.0865700000 0.0002930000 0.0002700000 0.0324920000 9380274 96830484 1769275392 3.7025845051 3.5722906590 6.2829136848 560 22.3600000000 0.7447668910 0.1170446550 0.8282750845 0.0438686026 0.1303640000 0.0100730000 0.0868050000 0.0000290000 0.0002960000 0.0248350000 9381948 96830484 1770909696 3.6989860535 3.5655615330 6.3121590614 561 22.4000000000 0.7419990301 0.1181586557 0.8282750845 0.0438385685 0.0946620000 0.0116170000 0.0312240000 0.0003050000 0.0002670000 0.0449310000 9383622 96830484 1769910272 3.6954646111 3.5695517063 6.3256850243 562 22.4400000000 0.7264005542 0.1192409367 0.8282750845 0.0438090711 0.1404520000 0.0103260000 0.0959290000 0.0000070000 0.0000580000 0.0240730000 9385296 96830484 1769005056 3.6917002201 3.5823767185 6.3373618126 563 22.4800000000 0.7303184867 0.1203263320 0.8282750845 0.0437748962 0.1463920000 0.0098270000 0.0877810000 0.0003700000 0.0002760000 0.0313390000 9386970 96830484 1770782720 3.6885738373 3.5780200958 6.3440341949 564 22.5200000000 0.7324662209 0.1214116864 0.8282750845 0.0437417355 0.1311020000 0.0122020000 0.0871260000 0.0000270000 0.0002890000 0.0239690000 9388644 96830484 1768656896 3.6851699352 3.5791180134 6.3531718254 565 22.5600000000 0.7313762903 0.1224912697 0.8282750845 0.0437314635 0.1410510000 0.0100000000 0.0877300000 0.0003740000 0.0002840000 0.0363910000 9390318 96830484 1770528768 3.6772053242 3.5890493393 6.3739428520 566 22.6000000000 0.7364639640 0.1235760272 0.8282750845 0.0436939831 0.1258050000 0.0148950000 0.0866770000 0.0000060000 0.0000610000 0.0180040000 9391992 96830484 1768259584 3.6735043526 3.5820198059 6.3750028610 567 22.6400000000 0.7379631400 0.1246596023 0.8282750845 0.0436636782 0.1114130000 0.0111390000 0.0609480000 0.0003000000 0.0002770000 0.0319880000 9393666 96830484 1770004480 3.6699073315 3.5839526653 6.3872756958 568 22.6800000000 0.7431802750 0.1257485472 0.8282750845 0.0436457374 0.1457120000 0.0118830000 0.0879230000 0.0000880000 0.0006380000 0.0244680000 9395340 96830484 1768783872 3.6660511494 3.5885925293 6.4105267525 569 22.7200000000 0.7416920066 0.1268310488 0.8282750845 0.0436178368 0.1007130000 0.0099180000 0.0381200000 0.0003770000 0.0002850000 0.0458150000 9397014 96830484 1770528768 3.6621460915 3.5964345932 6.4242191315 570 22.7600000000 0.7492341995 0.1279229842 0.8282750845 0.0436262939 0.1377820000 0.0111580000 0.0890520000 0.0000280000 0.0002950000 0.0239690000 9398688 96830484 1769402368 3.6581518650 3.6002871990 6.4630336761 571 22.8000000000 0.7484843731 0.1290097817 0.8282750845 0.0435892432 0.1465980000 0.0097700000 0.0829760000 0.0000720000 0.0000560000 0.0321380000 9400362 96830484 1771053056 3.6556859016 3.6002123356 6.4635396004 572 22.8400000000 0.7581703663 0.1301097128 0.8282750845 0.0435543271 0.1483890000 0.0114560000 0.0902720000 0.0000250000 0.0003030000 0.0244390000 9402036 96830484 1769910272 3.6523859501 3.5998151302 6.4672160149 573 22.8800000000 0.7509239912 0.1311931583 0.8282750845 0.0435208591 0.1692570000 0.0116170000 0.0895250000 0.0002970000 0.0007060000 0.0478190000 9403710 96830484 1768148992 3.6481778622 3.6084909439 6.4651398659 574 22.9200000000 0.7498619556 0.1322709785 0.8282750845 0.0434922871 0.1135350000 0.0097920000 0.0746910000 0.0000250000 0.0005470000 0.0222550000 9405384 96830484 1769877504 3.6432209015 3.6169939041 6.4769458771 575 22.9600000000 0.7493019104 0.1333440758 0.8282750845 0.0434546956 0.1453060000 0.0111140000 0.0892080000 0.0002940000 0.0004490000 0.0328950000 9407058 96830484 1768636416 3.6405522823 3.6156213284 6.4678297043 576 23.0000000000 0.7616541982 0.1344348920 0.8282750845 0.0434639890 0.1293660000 0.0094270000 0.0878530000 0.0000050000 0.0000590000 0.0250500000 9408732 96830484 1770418176 3.6363220215 3.6185727119 6.5059361458 577 23.0400000000 0.7675385475 0.1355321254 0.8282750845 0.0434337074 0.1538620000 0.0114730000 0.0908470000 0.0003080000 0.0003420000 0.0444270000 9410406 96830484 1769148416 3.6319811344 3.6180205345 6.5151772499 578 23.0800000000 0.7755789161 0.1366394728 0.8282750845 0.0434060375 0.1028540000 0.0091940000 0.0613280000 0.0000260000 0.0002900000 0.0243060000 9412080 96830484 1770926080 3.6294221878 3.6210198402 6.5278959274 579 23.1200000000 0.7820821404 0.1377542269 0.8282750845 0.0433751407 0.0886390000 0.0113460000 0.0359310000 0.0002870000 0.0002630000 0.0339520000 9413754 96830484 1769783296 3.6275928020 3.6231737137 6.5371861458 580 23.1600000000 0.7871850729 0.1388739353 0.8282750845 0.0433441131 0.1260900000 0.0111120000 0.0747120000 0.0000220000 0.0002900000 0.0252920000 9415428 96830484 1767747584 3.6260509491 3.6284112930 6.5480613708 581 23.2000000000 0.7905489206 0.1399955790 0.8282750845 0.0433345418 0.1465270000 0.0098740000 0.0885590000 0.0002850000 0.0002740000 0.0395960000 9417102 96830484 1769496576 3.6204421520 3.6459264755 6.5735888481 582 23.2400000000 0.7991366982 0.1411281239 0.8282750845 0.0433090766 0.1401970000 0.0113470000 0.0865580000 0.0000050000 0.0000590000 0.0232910000 9418776 96830484 1771175936 3.6128911972 3.6457643509 6.5887947083 583 23.2800000000 0.8086863756 0.1422731637 0.8282750845 0.0432816016 0.1106010000 0.0111160000 0.0536510000 0.0003100000 0.0005360000 0.0340460000 9420450 96830484 1770147840 3.6103885174 3.6495051384 6.6027150154 584 23.3200000000 0.8169590831 0.1434284478 0.8282750845 0.0432549504 0.1255410000 0.0116230000 0.0864630000 0.0000270000 0.0002800000 0.0205420000 9422124 96830484 1767895040 3.6066424847 3.6555831432 6.6171998978 585 23.3600000000 0.8178099394 0.1445812367 0.8282750845 0.0432199795 0.1845180000 0.0095530000 0.0904730000 0.0003000000 0.0003480000 0.0512250000 9423798 96830484 1769656320 3.6000745296 3.6577970982 6.6167788506 586 23.4000000000 0.8238054514 0.1457403224 0.8282750845 0.0431834184 0.1350540000 0.0116070000 0.0887150000 0.0000270000 0.0002950000 0.0273840000 9425472 96830484 1768390656 3.5969364643 3.6476001740 6.6097989082 587 23.4400000000 0.8240425587 0.1468958628 0.8282750845 0.0431487019 0.1459960000 0.0092850000 0.0867800000 0.0000600000 0.0000530000 0.0346090000 9427146 96830484 1770164224 3.5922832489 3.6498391628 6.6068558693 588 23.4800000000 0.8238611221 0.1480471643 0.8282750845 0.0431139699 0.1470470000 0.0109400000 0.0873910000 0.0000060000 0.0000580000 0.0278010000 9428820 96830484 1769005056 3.5854346752 3.6444914341 6.5957884789 589 23.5200000000 0.8234352469 0.1491938334 0.8282750845 0.0430780476 0.1533910000 0.0092390000 0.0892690000 0.0002930000 0.0002720000 0.0478610000 9430494 96830484 1770672128 3.5790324211 3.6424591541 6.5889616013 590 23.5600000000 0.8255050182 0.1503401235 0.8282750845 0.0430417326 0.1446850000 0.0109420000 0.0891090000 0.0000290000 0.0005020000 0.0277860000 9432168 96830484 1769545728 3.5729699135 3.6360499859 6.5796713829 591 23.6000000000 0.8238426447 0.1514797217 0.8282750845 0.0430057485 0.1282720000 0.0091240000 0.0681790000 0.0002850000 0.0002610000 0.0338140000 9433842 96830484 1771290624 3.5665497780 3.6360545158 6.5724067688 592 23.6400000000 0.8204129338 0.1526096764 0.8282750845 0.0429703264 0.1314230000 0.0110110000 0.0870660000 0.0000270000 0.0003490000 0.0264300000 9435516 96830484 1770053632 3.5602672100 3.6392860413 6.5634245872 593 23.6800000000 0.8198590279 0.1537348861 0.8282750845 0.0429348422 0.1549620000 0.0112160000 0.0892470000 0.0002840000 0.0005090000 0.0472190000 9437190 96830484 1768402944 3.5542905331 3.6396048069 6.5550928116 594 23.7200000000 0.8168990612 0.1548513242 0.8282750845 0.0428998980 0.1377090000 0.0091930000 0.0815580000 0.0000050000 0.0000590000 0.0276120000 9438864 96830484 1770020864 3.5470490456 3.6394941807 6.5465092659 595 23.7600000000 0.8126259446 0.1559568277 0.8282750845 0.0428654462 0.1334580000 0.0108130000 0.0887400000 0.0003500000 0.0002650000 0.0267800000 9440538 96830484 1768640512 3.5385429859 3.6400914192 6.5373878479 596 23.8000000000 0.8130252361 0.1570592915 0.8282750845 0.0428310547 0.1057050000 0.0089860000 0.0604010000 0.0000270000 0.0002850000 0.0267150000 9442212 96830484 1770291200 3.5311412811 3.6353449821 6.5278854370 597 23.8400000000 0.8086607456 0.1581507512 0.8282750845 0.0427958557 0.1396890000 0.0106800000 0.0750130000 0.0003010000 0.0003480000 0.0467270000 9443886 96830484 1769259008 3.5273253918 3.6404464245 6.5187320709 598 23.8800000000 0.8065528274 0.1592350356 0.8282750845 0.0427610379 0.1364580000 0.0090770000 0.0879370000 0.0000280000 0.0003120000 0.0263090000 9445560 96830484 1770799104 3.5188345909 3.6418473721 6.5099043846 599 23.9200000000 0.8026573658 0.1603091964 0.8282750845 0.0427268183 0.1090840000 0.0106190000 0.0545620000 0.0002960000 0.0002650000 0.0334360000 9447234 96830484 1769656320 3.5104429722 3.6454923153 6.4999394417 600 23.9600000000 0.7974987030 0.1613711789 0.8282750845 0.0426930553 0.1459570000 0.0109320000 0.0887600000 0.0000260000 0.0002860000 0.0270070000 9448908 96830484 1767645184 3.5045166016 3.6499967575 6.4908351898 601 24.0000000000 0.7924869061 0.1624212883 0.8282750845 0.0426600461 0.1583830000 0.0092680000 0.0945450000 0.0000600000 0.0000540000 0.0479390000 9450582 96830484 1769259008 3.4970641136 3.6540222168 6.4810609818 602 24.0400000000 0.7828968167 0.1634519786 0.8282750845 0.0426325855 0.1205680000 0.0084670000 0.0745380000 0.0000060000 0.0000590000 0.0275610000 9452256 96830484 1770921984 3.4808018208 3.6627252102 6.4615864754 603 24.0800000000 0.7823354602 0.1644783193 0.8282750845 0.0425988835 0.1079430000 0.0108560000 0.0474450000 0.0003150000 0.0003730000 0.0350780000 9453930 96830484 1769893888 3.4716567993 3.6618313789 6.4530205727 604 24.1200000000 0.7763850689 0.1654914100 0.8282750845 0.0425663274 0.1095290000 0.0108770000 0.0620270000 0.0000260000 0.0003540000 0.0273710000 9455604 96830484 1767989248 3.4598786831 3.6658046246 6.4426460266 605 24.1600000000 0.7670378685 0.1664857016 0.8282750845 0.0425344780 0.1317420000 0.0090960000 0.0675470000 0.0002950000 0.0002690000 0.0428040000 9457278 96830484 1769672704 3.4536623955 3.6752316952 6.4313268661 606 24.2000000000 0.8047037721 0.1675388668 0.8282750845 0.0425562474 0.1396260000 0.0105710000 0.0867170000 0.0000050000 0.0000590000 0.0277630000 9458952 96830484 1768390656 3.4481637478 3.6353077888 6.4343552589 607 24.2400000000 0.8036531806 0.1685868310 0.8282750845 0.0425218549 0.1105710000 0.0087130000 0.0602180000 0.0002860000 0.0003510000 0.0342190000 9460626 96830484 1770053632 3.4412860870 3.6350739002 6.4254956245 608 24.2800000000 0.8057572842 0.1696348088 0.8282750845 0.0424875431 0.1457780000 0.0107600000 0.0892860000 0.0000260000 0.0002900000 0.0272470000 9462300 96830484 1768890368 3.4331939220 3.6314167976 6.4169430733 609 24.3200000000 0.8104267716 0.1706870123 0.8282750845 0.0424544960 0.1452220000 0.0086560000 0.0817870000 0.0002920000 0.0003370000 0.0474120000 9463974 96830484 1770545152 3.4250533581 3.6256864071 6.4095549583 610 24.3600000000 0.8103892207 0.1717357045 0.8282750845 0.0424210579 0.1344250000 0.0104280000 0.0884000000 0.0000240000 0.0002890000 0.0275030000 9465648 96830484 1769418752 3.4200582504 3.6248366833 6.4010610580 611 24.4000000000 0.8106345534 0.1727813654 0.8282750845 0.0423871043 0.1468250000 0.0087980000 0.0891150000 0.0002890000 0.0003460000 0.0354940000 9467322 96830484 1771085824 3.4152860641 3.6235027313 6.3922357559 612 24.4400000000 0.8168638349 0.1738337878 0.8282750845 0.0423536325 0.1289900000 0.0104300000 0.0902330000 0.0000250000 0.0002820000 0.0209790000 9468996 96830484 1769926656 3.4086387157 3.6164166927 6.3866457939 613 24.4800000000 0.8177447915 0.1748842135 0.8282750845 0.0423202435 0.1558920000 0.0103640000 0.0881840000 0.0002940000 0.0002700000 0.0499270000 9470670 96830484 1768243200 3.4015569687 3.6147749424 6.3777651787 614 24.5200000000 0.8202608824 0.1759353156 0.8282750845 0.0422867790 0.1404060000 0.0082580000 0.0912000000 0.0000270000 0.0003120000 0.0275060000 9472344 96830484 1769926656 3.3949215412 3.6106879711 6.3700666428 615 24.5600000000 0.8184217811 0.1769800090 0.8282750845 0.0422538521 0.1123450000 0.0105550000 0.0618410000 0.0003060000 0.0003600000 0.0324630000 9474018 96830484 1768353792 3.3893375397 3.6123387814 6.3611683846 616 24.6000000000 0.8218671083 0.1780269037 0.8282750845 0.0422204939 0.1403230000 0.0086940000 0.0881430000 0.0000290000 0.0003790000 0.0275730000 9475692 96830484 1770176512 3.3818657398 3.6074910164 6.3522467613 617 24.6400000000 0.8213210702 0.1790695198 0.8282750845 0.0421875273 0.1275340000 0.0103650000 0.0616740000 0.0003160000 0.0002820000 0.0477540000 9477366 96830484 1769132032 3.3747925758 3.6082196236 6.3435916901 618 24.6800000000 0.8222383857 0.1801102462 0.8282750845 0.0421546436 0.1087900000 0.0088910000 0.0538630000 0.0000270000 0.0006540000 0.0290970000 9479040 96830484 1770815488 3.3704659939 3.6066913605 6.3344359398 619 24.7200000000 0.8233734369 0.1811494436 0.8282750845 0.0421213992 0.1498880000 0.0104270000 0.0897200000 0.0003120000 0.0002730000 0.0377740000 9480714 96830484 1769259008 3.3670918941 3.6071248055 6.3289461136 620 24.7600000000 0.8248688579 0.1821877007 0.8282750845 0.0420914388 0.1464990000 0.0083840000 0.0892360000 0.0000290000 0.0002950000 0.0304800000 9482388 96830484 1770942464 3.3548347950 3.6040530205 6.3097267151 621 24.8000000000 0.8250553608 0.1832229143 0.8282750845 0.0420584071 0.1350090000 0.0104030000 0.0609400000 0.0003080000 0.0002840000 0.0559240000 9484062 96830484 1769893888 3.3503322601 3.6022703648 6.3010163307 622 24.8400000000 0.8248524070 0.1842544730 0.8282750845 0.0420254181 0.1043460000 0.0104460000 0.0535600000 0.0000260000 0.0002990000 0.0310100000 9485736 96830484 1767989248 3.3433620930 3.6005032063 6.2912836075 623 24.8800000000 0.8253769279 0.1852835620 0.8282750845 0.0419921573 0.1275350000 0.0087040000 0.0680240000 0.0002950000 0.0003510000 0.0399830000 9487410 96830484 1769775104 3.3380548954 3.5989370346 6.2824687958 624 24.9200000000 0.8265213966 0.1863111867 0.8282750845 0.0419586369 0.1095320000 0.0102950000 0.0611770000 0.0000260000 0.0003010000 0.0308550000 9489084 96830484 1768497152 3.3324623108 3.5957822800 6.2726449966 625 24.9600000000 0.8271226287 0.1873364850 0.8282750845 0.0419253248 0.1622300000 0.0083380000 0.0897120000 0.0003040000 0.0002790000 0.0567590000 9490758 96830484 1770287104 3.3268425465 3.5948162079 6.2631382942 626 25.0000000000 0.8272225857 0.1883586673 0.8282750845 0.0418920706 0.1321500000 0.0103560000 0.0740320000 0.0000300000 0.0003030000 0.0317260000 9492432 96830484 1769148416 3.3196988106 3.5942354202 6.2528457642 627 25.0400000000 0.8284314275 0.1893795170 0.8284314275 0.0418598059 0.1289510000 0.0085580000 0.0674180000 0.0003060000 0.0002750000 0.0396970000 9494106 96830484 1770811392 3.3146908283 3.5919866562 6.2434549332 628 25.0800000000 0.8288872242 0.1903978414 0.8288872242 0.0418272161 0.1105130000 0.0105600000 0.0684220000 0.0000260000 0.0003040000 0.0241090000 9495780 96830484 1769402368 3.3093671799 3.5891139507 6.2328543663 629 25.1200000000 0.8291714191 0.1914133796 0.8291714191 0.0417943360 0.1813290000 0.0083800000 0.0873430000 0.0003010000 0.0003440000 0.0522870000 9497454 96830484 1771147264 3.3024773598 3.5885133743 6.2205152512 630 25.1600000000 0.8298645020 0.1924267941 0.8298645020 0.0417631143 0.1514030000 0.0115850000 0.0885040000 0.0000250000 0.0002990000 0.0303010000 9499128 96830484 1769656320 3.2982370853 3.5868322849 6.2105383873 631 25.2000000000 0.8301509619 0.1934374505 0.8301509619 0.0417300586 0.1502030000 0.0103250000 0.0890370000 0.0002880000 0.0006210000 0.0388400000 9500802 96830484 1768263680 3.2949323654 3.5856516361 6.2007393837 632 25.2400000000 0.8303782344 0.1944452682 0.8303782344 0.0416970751 0.1464440000 0.0087650000 0.0889560000 0.0000260000 0.0003440000 0.0304790000 9502476 96830484 1769943040 3.2881441116 3.5840280056 6.1878862381 633 25.2800000000 0.8311813474 0.1954511704 0.8311813474 0.0416651651 0.1619290000 0.0104100000 0.0892750000 0.0002850000 0.0002750000 0.0544450000 9504150 96830484 1768407040 3.2818956375 3.5814020634 6.1758332253 634 25.3200000000 0.8309869766 0.1964535928 0.8311813474 0.0416326744 0.1372200000 0.0083540000 0.0891800000 0.0000280000 0.0002840000 0.0293570000 9505824 96830484 1770147840 3.2790279388 3.5798945427 6.1652412415 635 25.3600000000 0.8318203092 0.1974541703 0.8318203092 0.0416006950 0.1495120000 0.0104910000 0.0936570000 0.0002940000 0.0003510000 0.0374730000 9507498 96830484 1769005056 3.2783424854 3.5783872604 6.1572856903 636 25.4000000000 0.8324890733 0.1984526528 0.8324890733 0.0415743472 0.1261870000 0.0084890000 0.0879950000 0.0000290000 0.0002890000 0.0224640000 9509172 96830484 1770704896 3.2689561844 3.5765826702 6.1435837746 637 25.4400000000 0.8338493705 0.1994501359 0.8338493705 0.0415418719 0.1585410000 0.0104920000 0.0874270000 0.0002960000 0.0003440000 0.0528450000 9510846 96830484 1769639936 3.2600271702 3.5754253864 6.1298007965 638 25.4800000000 0.8330145478 0.2004431836 0.8338493705 0.0415107500 0.1375040000 0.0084220000 0.0850340000 0.0000280000 0.0002870000 0.0289550000 9512520 96830484 1771212800 3.2599201202 3.5754704475 6.1188254356 639 25.5200000000 0.8336815834 0.2014341670 0.8338493705 0.0414784551 0.1109650000 0.0104740000 0.0554830000 0.0003860000 0.0006170000 0.0369340000 9514194 96830484 1770037248 3.2555589676 3.5745584965 6.1079196930 640 25.5600000000 0.8342304826 0.2024229112 0.8342304826 0.0414466072 0.1064490000 0.0106240000 0.0535410000 0.0000280000 0.0003580000 0.0294170000 9515868 96830484 1768402944 3.2515895367 3.5726072788 6.0952548981 641 25.6000000000 0.8351330161 0.2034099785 0.8351330161 0.0414147894 0.1650780000 0.0085680000 0.0808880000 0.0000600000 0.0000540000 0.0507250000 9517542 96830484 1770029056 3.2489814758 3.5711104870 6.0847821236 642 25.6400000000 0.8354862332 0.2043945209 0.8354862332 0.0413824934 0.1010950000 0.0102980000 0.0603690000 0.0000270000 0.0002910000 0.0227840000 9519216 96830484 1768861696 3.2458622456 3.5689756870 6.0727639198 643 25.6800000000 0.8355593085 0.2053761147 0.8355593085 0.0413503810 0.1408390000 0.0089790000 0.0890730000 0.0002930000 0.0002670000 0.0352050000 9520890 96830484 1770561536 3.2433090210 3.5671470165 6.0610022545 644 25.7200000000 0.8365513086 0.2063562004 0.8365513086 0.0413182937 0.1050870000 0.0103970000 0.0464830000 0.0000260000 0.0003830000 0.0299430000 9522564 96830484 1769402368 3.2398319244 3.5637605190 6.0497698784 645 25.7600000000 0.8369067311 0.2073337981 0.8369067311 0.0412863532 0.1277340000 0.0086790000 0.0600280000 0.0002910000 0.0002680000 0.0510790000 9524238 96830484 1771085824 3.2345290184 3.5621364117 6.0373191833 646 25.8000000000 0.8364692330 0.2083076920 0.8369067311 0.0412547046 0.1483380000 0.0107390000 0.0868270000 0.0000240000 0.0002850000 0.0300470000 9525912 96830484 1769783296 3.2317738533 3.5613589287 6.0249319077 647 25.8400000000 0.8369317651 0.2092792902 0.8369317651 0.0412231782 0.1503340000 0.0106100000 0.0886170000 0.0002870000 0.0002660000 0.0391030000 9527586 96830484 1768026112 3.2293446064 3.5607564449 6.0135779381 648 25.8800000000 0.8375999331 0.2102489209 0.8375999331 0.0411916697 0.1466220000 0.0089660000 0.0873650000 0.0000250000 0.0002920000 0.0308340000 9529260 96830484 1769558016 3.2289085388 3.5584361553 6.0047388077 649 25.9200000000 0.8383128643 0.2112166619 0.8383128643 0.0411607639 0.1189080000 0.0101920000 0.0461750000 0.0003080000 0.0003500000 0.0545230000 9530934 96830484 1768353792 3.2246351242 3.5557122231 5.9927372932 650 25.9600000000 0.8388349414 0.2121822285 0.8388349414 0.0411296738 0.1359370000 0.0086970000 0.0848090000 0.0000250000 0.0003630000 0.0303300000 9532608 96830484 1770196992 3.2206478119 3.5536222458 5.9815621376 651 26.0000000000 0.8395489454 0.2131459254 0.8395489454 0.0410985330 0.1481990000 0.0106770000 0.0865650000 0.0002940000 0.0002730000 0.0381380000 9534282 96830484 1768751104 3.2183425426 3.5505030155 5.9716930389 652 26.0400000000 0.8399205804 0.2141072363 0.8399205804 0.0410677960 0.1469450000 0.0085750000 0.0889620000 0.0000280000 0.0002920000 0.0303360000 9535956 96830484 1770418176 3.2163338661 3.5479264259 5.9602646828 653 26.0800000000 0.8402572870 0.2150661184 0.8402572870 0.0410369806 0.1611940000 0.0103480000 0.0875440000 0.0002870000 0.0002650000 0.0555180000 9537630 96830484 1769275392 3.2118394375 3.5445706844 5.9483928680 654 26.1200000000 0.8407667279 0.2160228472 0.8407667279 0.0410060433 0.1368660000 0.0085950000 0.0832230000 0.0000270000 0.0002880000 0.0317680000 9539304 96830484 1770926080 3.2086844444 3.5410850048 5.9377741814 655 26.1600000000 0.8411350250 0.2169772169 0.8411350250 0.0409753163 0.1486430000 0.0105480000 0.0856770000 0.0000590000 0.0000660000 0.0396890000 9540978 96830484 1769893888 3.2054357529 3.5372242928 5.9270381927 656 26.2000000000 0.8415760994 0.2179293494 0.8415760994 0.0409451697 0.1094030000 0.0106240000 0.0599010000 0.0000270000 0.0003470000 0.0311950000 9542652 96830484 1767747584 3.2012465000 3.5341653824 5.9158520699 657 26.2400000000 0.8426426053 0.2188802067 0.8426426053 0.0409142708 0.1576280000 0.0089420000 0.0855950000 0.0000620000 0.0000540000 0.0555960000 9544326 96830484 1769508864 3.1960313320 3.5301265717 5.9049153328 658 26.2800000000 0.8427335024 0.2198283120 0.8427335024 0.0408835156 0.1382810000 0.0088870000 0.0887780000 0.0000270000 0.0002850000 0.0304090000 9546000 96830484 1771175936 3.1937255859 3.5270905495 5.8950924873 659 26.3200000000 0.8435621858 0.2207747974 0.8435621858 0.0408529609 0.1482870000 0.0106720000 0.0871660000 0.0002870000 0.0002690000 0.0393000000 9547674 96830484 1770020864 3.1896040440 3.5244421959 5.8840384483 660 26.3600000000 0.8433752060 0.2217181313 0.8435621858 0.0408224998 0.1479570000 0.0108560000 0.0899410000 0.0000260000 0.0002920000 0.0304830000 9549348 96830484 1768386560 3.1867210865 3.5220289230 5.8728613853 661 26.4000000000 0.8443481922 0.2226600830 0.8443481922 0.0407922679 0.1606230000 0.0087720000 0.0880610000 0.0002910000 0.0002660000 0.0556650000 9551022 96830484 1769893888 3.1828958988 3.5190873146 5.8616490364 662 26.4400000000 0.8452661633 0.2236005756 0.8452661633 0.0407620185 0.1383730000 0.0106460000 0.0877510000 0.0000230000 0.0002860000 0.0320770000 9552696 96830484 1768878080 3.1775088310 3.5164911747 5.8498754501 663 26.4800000000 0.8457205296 0.2245389164 0.8457205296 0.0407315706 0.1466860000 0.0089730000 0.0856170000 0.0000600000 0.0000530000 0.0396320000 9554370 96830484 1770528768 3.1722273827 3.5148098469 5.8365621567 664 26.5200000000 0.8460847735 0.2254749794 0.8460847735 0.0407017935 0.1425200000 0.0105240000 0.0862080000 0.0000070000 0.0000580000 0.0240840000 9556044 96830484 1769402368 3.1681597233 3.5120027065 5.8245539665 665 26.5600000000 0.8468244672 0.2264093396 0.8468244672 0.0406760455 0.1597180000 0.0090710000 0.0866350000 0.0003520000 0.0002650000 0.0560440000 9557718 96830484 1771053056 3.1601679325 3.5090875626 5.7998685837 666 26.6000000000 0.8472566605 0.2273415428 0.8472566605 0.0406458526 0.1425100000 0.0103390000 0.0870180000 0.0000250000 0.0002910000 0.0305320000 9559392 96830484 1769910272 3.1551887989 3.5085582733 5.7860751152 667 26.6400000000 0.8477629423 0.2282717098 0.8477629423 0.0406160127 0.1488830000 0.0112240000 0.0868620000 0.0003520000 0.0002680000 0.0392120000 9561066 96830484 1767878656 3.1517460346 3.5075101852 5.7742633820 668 26.6800000000 0.8486080170 0.2292003569 0.8486080170 0.0405861129 0.1483320000 0.0087840000 0.0996310000 0.0000270000 0.0002960000 0.0306080000 9562740 96830484 1769639936 3.1464958191 3.5057659149 5.7606682777 669 26.7200000000 0.8486671448 0.2301263163 0.8486671448 0.0405572565 0.1459480000 0.0101020000 0.0573750000 0.0002930000 0.0003430000 0.0590660000 9564414 96830484 1768267776 3.1432731152 3.5055112839 5.7481446266 670 26.7600000000 0.8490120769 0.2310500263 0.8490120769 0.0405275188 0.1093420000 0.0087720000 0.0524900000 0.0000310000 0.0002860000 0.0303580000 9566088 96830484 1770164224 3.1402640343 3.5059111118 5.7353858948 671 26.8000000000 0.8497307301 0.2319720542 0.8497307301 0.0404979057 0.1391030000 0.0109030000 0.0879860000 0.0002860000 0.0003350000 0.0321940000 9567762 96830484 1768116224 3.1348879337 3.5035567284 5.7224450111 672 26.8400000000 0.8502783775 0.2328921529 0.8502783775 0.0404691191 0.1383520000 0.0090690000 0.0869130000 0.0000270000 0.0002850000 0.0309830000 9569436 96830484 1769656320 3.1298196316 3.5007221699 5.7098569870 673 26.8800000000 0.8505471349 0.2338099166 0.8505471349 0.0404400394 0.1644960000 0.0106860000 0.0864080000 0.0002870000 0.0003500000 0.0589820000 9571110 96830484 1767641088 3.1261451244 3.4981551170 5.6971035004 674 26.9200000000 0.8513335586 0.2347261238 0.8513335586 0.0404103268 0.1335350000 0.0090190000 0.0860950000 0.0000830000 0.0002910000 0.0304760000 9572784 96830484 1769418752 3.1252832413 3.4955575466 5.6857557297 675 26.9600000000 0.8517367244 0.2356402136 0.8517367244 0.0403815993 0.1472400000 0.0099180000 0.0869710000 0.0003490000 0.0004920000 0.0392290000 9574458 96830484 1768116224 3.1238911152 3.4928348064 5.6738400459 676 27.0000000000 0.8519620299 0.2365519323 0.8519620299 0.0403543916 0.1458340000 0.0088370000 0.0854400000 0.0000050000 0.0000590000 0.0310110000 9576132 96830484 1769926656 3.1204507351 3.4911220074 5.6605801582 677 27.0400000000 0.8527259827 0.2374620860 0.8527259827 0.0403255880 0.1626980000 0.0102260000 0.0874940000 0.0003730000 0.0002790000 0.0568090000 9577806 96830484 1768763392 3.1167128086 3.4891395569 5.6483788490 678 27.0800000000 0.8529717326 0.2383699173 0.8529717326 0.0402971314 0.1368950000 0.0086140000 0.0870110000 0.0000280000 0.0003020000 0.0327070000 9579480 96830484 1770418176 3.1137964725 3.4883131981 5.6377553940 679 27.1200000000 0.8535962105 0.2392759943 0.8535962105 0.0402684273 0.1369960000 0.0107160000 0.0854210000 0.0002960000 0.0003470000 0.0327120000 9581154 96830484 1769259008 3.1110031605 3.4860842228 5.6269402504 680 27.1600000000 0.8536589146 0.2401794986 0.8536589146 0.0402397999 0.1380540000 0.0092480000 0.0855880000 0.0000250000 0.0003640000 0.0316680000 9582828 96830484 1771053056 3.1082329750 3.4851677418 5.6174545288 681 27.2000000000 0.8542760015 0.2410812556 0.8542760015 0.0402113250 0.1270200000 0.0105980000 0.0512260000 0.0003130000 0.0003590000 0.0568220000 9584502 96830484 1769893888 3.1054236889 3.4837348461 5.6071090698 682 27.2400000000 0.8545939326 0.2419808343 0.8545939326 0.0401833047 0.1072040000 0.0103580000 0.0435880000 0.0000250000 0.0010050000 0.0318660000 9586176 96830484 1768136704 3.1015627384 3.4830968380 5.5954504013 683 27.2800000000 0.8551944494 0.2428786580 0.8551944494 0.0401542287 0.1463370000 0.0087550000 0.0842820000 0.0003000000 0.0003520000 0.0401010000 9587850 96830484 1769795584 3.0965507030 3.4820809364 5.5835814476 684 27.3200000000 0.8555061817 0.2437743123 0.8555061817 0.0401261952 0.1291340000 0.0103640000 0.0857000000 0.0000270000 0.0003060000 0.0249450000 9589524 96830484 1768243200 3.0957288742 3.4793736935 5.5742812157 685 27.3600000000 0.8558052778 0.2446677882 0.8558052778 0.0400989241 0.1587910000 0.0085930000 0.0839610000 0.0003460000 0.0002650000 0.0578530000 9591198 96830484 1770033152 3.0956819057 3.4783926010 5.5646791458 686 27.4000000000 0.8562361598 0.2455592872 0.8562361598 0.0400723362 0.1362360000 0.0100700000 0.0796760000 0.0000250000 0.0002860000 0.0316270000 9592872 96830484 1768890368 3.0896492004 3.4767715931 5.5513253212 687 27.4400000000 0.8568557501 0.2464490929 0.8568557501 0.0400437683 0.1488100000 0.0084950000 0.0855660000 0.0002850000 0.0002780000 0.0402810000 9594546 96830484 1770577920 3.0859301090 3.4740598202 5.5403752327 688 27.4800000000 0.8571804762 0.2473367838 0.8571804762 0.0400153373 0.1467810000 0.0106250000 0.0847150000 0.0000250000 0.0002890000 0.0323280000 9596220 96830484 1769132032 3.0838992596 3.4734082222 5.5308356285 689 27.5200000000 0.8573326468 0.2482221189 0.8573326468 0.0399869588 0.1608660000 0.0086630000 0.0854010000 0.0003690000 0.0002880000 0.0583590000 9597894 96830484 1770815488 3.0786879063 3.4722735882 5.5175504684 690 27.5600000000 0.8575899601 0.2491052607 0.8575899601 0.0399590270 0.1380440000 0.0104370000 0.0840720000 0.0000270000 0.0005170000 0.0323740000 9599568 96830484 1769656320 3.0778248310 3.4713153839 5.5069708824 691 27.6000000000 0.8578355908 0.2499862018 0.8578355908 0.0399305348 0.1473440000 0.0105430000 0.0827540000 0.0000620000 0.0000540000 0.0415900000 9601242 96830484 1768009728 3.0762407780 3.4697487354 5.4962553978 692 27.6400000000 0.8585749269 0.2508656653 0.8585749269 0.0399018466 0.1074540000 0.0089230000 0.0501370000 0.0000260000 0.0003040000 0.0322680000 9602916 96830484 1769652224 3.0732893944 3.4664762020 5.4839959145 693 27.6800000000 0.8589978814 0.2517432010 0.8589978814 0.0398731960 0.1215120000 0.0102210000 0.0434110000 0.0010980000 0.0002920000 0.0586340000 9604590 96830484 1768153088 3.0712132454 3.4650924206 5.4719514847 694 27.7200000000 0.8589939475 0.2526182021 0.8589978814 0.0398447294 0.1184440000 0.0084640000 0.0696660000 0.0000260000 0.0003030000 0.0318550000 9606264 96830484 1769893888 3.0696499348 3.4627935886 5.4597620964 695 27.7600000000 0.8597582579 0.2534917849 0.8597582579 0.0398170414 0.1632280000 0.0104130000 0.0923200000 0.0003100000 0.0003540000 0.0400530000 9607938 96830484 1768734720 3.0671415329 3.4587881565 5.4477224350 696 27.8000000000 0.8602964878 0.2543636307 0.8602964878 0.0397884973 0.1313800000 0.0083660000 0.0834890000 0.0000250000 0.0003720000 0.0314070000 9609612 96830484 1770430464 3.0652904510 3.4561953545 5.4351038933 697 27.8400000000 0.8615990877 0.2552348437 0.8615990877 0.0397628924 0.1623360000 0.0105070000 0.0840660000 0.0003010000 0.0002820000 0.0590780000 9611286 96830484 1769005056 3.0608227253 3.4472112656 5.4094986916 698 27.8800000000 0.8623490334 0.2561046348 0.8623490334 0.0397346865 0.1333120000 0.0086020000 0.0817370000 0.0000280000 0.0002940000 0.0317960000 9612960 96830484 1770704896 3.0607793331 3.4432141781 5.3994212151 699 27.9200000000 0.8632460237 0.2569732205 0.8632460237 0.0397126879 0.1482000000 0.0106050000 0.0823230000 0.0002920000 0.0003440000 0.0402350000 9614634 96830484 1769766912 3.0582714081 3.4438567162 5.3850121498 700 27.9600000000 0.8638092875 0.2578401292 0.8638092875 0.0396843532 0.1305830000 0.0104480000 0.0836190000 0.0000250000 0.0003500000 0.0281430000 9616308 96830484 1767862272 3.0574223995 3.4438221455 5.3700089455 701 28.0000000000 0.8645146489 0.2587055707 0.8645146489 0.0396578262 0.1563830000 0.0087080000 0.0813440000 0.0003000000 0.0003450000 0.0576870000 9617982 96830484 1769496576 3.0592780113 3.4418172836 5.3581075668 702 28.0400000000 0.8650240302 0.2595692722 0.8650240302 0.0396296310 0.1376270000 0.0101200000 0.0838130000 0.0000270000 0.0003550000 0.0315830000 9619656 96830484 1768243200 3.0589721203 3.4418241978 5.3452124596 703 28.0800000000 0.8658568859 0.2604317012 0.8658568859 0.0396017379 0.1465960000 0.0081760000 0.0827070000 0.0002890000 0.0002700000 0.0396560000 9621330 96830484 1769893888 3.0558485985 3.4388239384 5.3304500580 704 28.1200000000 0.8665396571 0.2612926500 0.8665396571 0.0395765472 0.1472920000 0.0102680000 0.0837040000 0.0000260000 0.0003120000 0.0318340000 9623004 96830484 1768771584 3.0564548969 3.4347503185 5.3182673454 705 28.1600000000 0.8669668436 0.2621517624 0.8669668436 0.0395489452 0.1579000000 0.0086510000 0.0827890000 0.0002930000 0.0002780000 0.0580850000 9624678 96830484 1770414080 3.0557696819 3.4297924042 5.3044133186 706 28.2000000000 0.8677285314 0.2630095198 0.8677285314 0.0395210092 0.1401990000 0.0103550000 0.0835310000 0.0000250000 0.0002970000 0.0318070000 9626352 96830484 1769005056 3.0553565025 3.4249820709 5.2913718224 707 28.2400000000 0.8688044548 0.2638663726 0.8688044548 0.0394947901 0.1473370000 0.0085770000 0.0836350000 0.0002900000 0.0002720000 0.0393750000 9628026 96830484 1770766336 3.0555436611 3.4236705303 5.2769560814 708 28.2800000000 0.8690134287 0.2647211001 0.8690134287 0.0394677000 0.1469220000 0.0105320000 0.0831780000 0.0000250000 0.0003890000 0.0316550000 9629700 96830484 1769418752 3.0521953106 3.4245052338 5.2611031532 709 28.3200000000 0.8700006008 0.2655748089 0.8700006008 0.0394426398 0.1582670000 0.0085040000 0.0826940000 0.0002900000 0.0002710000 0.0585340000 9631374 96830484 1771175936 3.0518715382 3.4204182625 5.2476615906 710 28.3600000000 0.8702621460 0.2664264812 0.8702621460 0.0394152597 0.1394610000 0.0104280000 0.0810840000 0.0000070000 0.0000610000 0.0322840000 9633048 96830484 1770037248 3.0548017025 3.4189562798 5.2376441956 711 28.4000000000 0.8707403541 0.2672764304 0.8707403541 0.0393879232 0.1483140000 0.0106030000 0.0817700000 0.0002870000 0.0003480000 0.0404200000 9634722 96830484 1768243200 3.0536077023 3.4172155857 5.2248892784 712 28.4400000000 0.8713992238 0.2681249174 0.8713992238 0.0393603860 0.1301000000 0.0085400000 0.0831030000 0.0000240000 0.0002910000 0.0301440000 9636396 96830484 1770065920 3.0535156727 3.4141693115 5.2135796547 713 28.4800000000 0.8720355034 0.2689719169 0.8720355034 0.0393328214 0.1597540000 0.0103240000 0.0818370000 0.0005670000 0.0002930000 0.0586900000 9638070 96830484 1768783872 3.0553493500 3.4103803635 5.2037329674 714 28.5200000000 0.8726665378 0.2698174275 0.8726665378 0.0393084251 0.1348430000 0.0087160000 0.0806850000 0.0000250000 0.0002860000 0.0320220000 9639744 96830484 1770512384 3.0547008514 3.4091885090 5.1925230026 715 28.5600000000 0.8730017543 0.2706610420 0.8730017543 0.0392828574 0.1483270000 0.0106260000 0.0824180000 0.0002880000 0.0003390000 0.0407690000 9641418 96830484 1769402368 3.0528798103 3.4104251862 5.1771049500 716 28.6000000000 0.8736733794 0.2715032380 0.8736733794 0.0392560523 0.1428070000 0.0091320000 0.0803430000 0.0000060000 0.0000580000 0.0324500000 9643092 96830484 1771085824 3.0526645184 3.4090740681 5.1645183563 717 28.6400000000 0.8738991022 0.2723433996 0.8738991022 0.0392306788 0.1610330000 0.0106050000 0.0819570000 0.0002880000 0.0003480000 0.0597720000 9644766 96830484 1770037248 3.0539436340 3.4046475887 5.1562323570 718 28.6800000000 0.8741904497 0.2731816267 0.8741904497 0.0392042756 0.1373110000 0.0103590000 0.0814180000 0.0000270000 0.0003880000 0.0329980000 9646440 96830484 1768144896 3.0536324978 3.4035320282 5.1475501060 719 28.7200000000 0.8749322295 0.2740185538 0.8749322295 0.0391780640 0.1472320000 0.0088070000 0.0822590000 0.0002920000 0.0002690000 0.0404240000 9648114 96830484 1769902080 3.0509099960 3.4018585682 5.1350364685 720 28.7600000000 0.8754073381 0.2748538160 0.8754073381 0.0391512269 0.0918490000 0.0103330000 0.0415720000 0.0000270000 0.0002860000 0.0315940000 9649788 96830484 1768370176 3.0485844612 3.3999791145 5.1235117912 721 28.8000000000 0.8757733703 0.2756872689 0.8757733703 0.0391252837 0.1801740000 0.0083340000 0.0982920000 0.0000600000 0.0000550000 0.0654240000 9651462 96830484 1766973440 3.0499784946 3.4009606838 5.1128401756 722 28.8400000000 0.8765204549 0.2765194478 0.8765204549 0.0390993971 0.1315750000 0.0085560000 0.0790760000 0.0000260000 0.0003630000 0.0335170000 9653136 96830484 1768673280 3.0439977646 3.4019665718 5.0998873711 723 28.8800000000 0.8770605326 0.2773500717 0.8770605326 0.0390735897 0.1471410000 0.0085410000 0.0808190000 0.0003020000 0.0002720000 0.0408940000 9654810 96830484 1770291200 3.0384557247 3.4010288715 5.0886011124 724 28.9200000000 0.8773181438 0.2781787569 0.8773181438 0.0390479518 0.1465400000 0.0105650000 0.0790740000 0.0000280000 0.0002840000 0.0332920000 9656484 96830484 1769259008 3.0353794098 3.4008977413 5.0793709755 725 28.9600000000 0.8777616620 0.2790057678 0.8777616620 0.0390216066 0.1209870000 0.0090510000 0.0406530000 0.0003560000 0.0002690000 0.0624130000 9658158 96830484 1770958848 3.0305888653 3.4008469582 5.0674600601 726 29.0000000000 0.8781412244 0.2798310233 0.8781412244 0.0389975981 0.1167870000 0.0104670000 0.0530060000 0.0000240000 0.0002920000 0.0339050000 9659832 96830484 1769545728 3.0279309750 3.3982596397 5.0541987419 727 29.0400000000 0.8795875311 0.2806559978 0.8795875311 0.0389726343 0.1483880000 0.0084150000 0.0803910000 0.0002870000 0.0003400000 0.0419450000 9661506 96830484 1771147264 3.0177583694 3.3954732418 5.0342388153 728 29.0800000000 0.8806426525 0.2814801553 0.8806426525 0.0389482288 0.1465190000 0.0103680000 0.0773310000 0.0000290000 0.0002840000 0.0353580000 9663180 96830484 1770164224 3.0069992542 3.3934950829 5.0199823380 729 29.1200000000 0.8806853294 0.2823021103 0.8806853294 0.0389344670 0.1606160000 0.0107060000 0.0774850000 0.0002960000 0.0003460000 0.0636580000 9664854 96830484 1768767488 3.0036811829 3.3877818584 5.0125694275 730 29.1600000000 0.8812249899 0.2831225526 0.8812249899 0.0389083031 0.1371820000 0.0081180000 0.0779460000 0.0000260000 0.0002880000 0.0349940000 9666528 96830484 1770430464 3.0009410381 3.3869013786 5.0035200119 731 29.2000000000 0.8818504810 0.2839416059 0.8818504810 0.0388817786 0.1481720000 0.0103250000 0.0772650000 0.0002870000 0.0003550000 0.0435500000 9668202 96830484 1769402368 2.9925875664 3.3885936737 4.9890084267 732 29.2400000000 0.8822973371 0.2847590317 0.8822973371 0.0388587063 0.1302680000 0.0087730000 0.0765980000 0.0000300000 0.0003540000 0.0363060000 9669876 96830484 1771085824 2.9868466854 3.3891816139 4.9778275490 733 29.2800000000 0.8828828335 0.2855750260 0.8828828335 0.0388333509 0.2017960000 0.0105090000 0.0879800000 0.0000780000 0.0000550000 0.0684590000 9671550 96830484 1770045440 2.9836668968 3.3911972046 4.9675874710 734 29.3200000000 0.8830666542 0.2863890473 0.8830666542 0.0388077160 0.1338250000 0.0109270000 0.0752310000 0.0000260000 0.0002860000 0.0390030000 9673224 96830484 1768759296 2.9754683971 3.3949360847 4.9546842575 735 29.3600000000 0.8836557269 0.2872016550 0.8836557269 0.0387938728 0.1460310000 0.0085230000 0.0736450000 0.0003600000 0.0002770000 0.0473520000 9674898 96830484 1770438656 2.9703042507 3.3922164440 4.9449758530 736 29.4000000000 0.8842149377 0.2880128144 0.8842149377 0.0387704815 0.1307160000 0.0104980000 0.0736070000 0.0000280000 0.0003830000 0.0379910000 9676572 96830484 1769410560 2.9677236080 3.3924927711 4.9369316101 737 29.4400000000 0.8842080235 0.2888217631 0.8842149377 0.0387444038 0.1647750000 0.0088990000 0.0737710000 0.0003610000 0.0002740000 0.0732750000 9678246 96830484 1771094016 2.9624216557 3.3968968391 4.9238662720 738 29.4800000000 0.8847869635 0.2896293040 0.8847869635 0.0387257890 0.1469040000 0.0105500000 0.0716260000 0.0000280000 0.0005360000 0.0405490000 9679920 96830484 1770045440 2.9577624798 3.3972532749 4.9132614136 739 29.5200000000 0.8848653436 0.2904347655 0.8848653436 0.0387090156 0.1498790000 0.0104280000 0.0722660000 0.0002880000 0.0004960000 0.0498150000 9681594 96830484 1768615936 2.9572246075 3.3953101635 4.9077372551 740 29.5600000000 0.8855763078 0.2912390108 0.8855763078 0.0386837864 0.1082050000 0.0088120000 0.0444030000 0.0000960000 0.0003240000 0.0406730000 9683268 96830484 1770438656 2.9548907280 3.3940081596 4.8989586830 741 29.6000000000 0.8856374621 0.2920411680 0.8856374621 0.0386581265 0.1434250000 0.0110200000 0.0498220000 0.0002900000 0.0005100000 0.0733890000 9684942 96830484 1769283584 2.9524259567 3.3941411972 4.8879542351 742 29.6400000000 0.8869400024 0.2928429184 0.8869400024 0.0386325277 0.1332910000 0.0082810000 0.0712220000 0.0000240000 0.0003780000 0.0404510000 9686616 96830484 1770967040 2.9506375790 3.3940134048 4.8783183098 743 29.6800000000 0.8871015906 0.2936427282 0.8871015906 0.0386071507 0.1478830000 0.0108210000 0.0718040000 0.0002900000 0.0003440000 0.0485450000 9688290 96830484 1769521152 2.9474642277 3.3957879543 4.8693313599 744 29.7200000000 0.8869400620 0.2944401709 0.8871015906 0.0385828166 0.1299460000 0.0087460000 0.0718510000 0.0000280000 0.0003000000 0.0406480000 9689964 96830484 1771220992 2.9409050941 3.3973090649 4.8595938683 745 29.7600000000 0.8871113062 0.2952357026 0.8871113062 0.0385623771 0.1342340000 0.0108280000 0.0421440000 0.0006960000 0.0013000000 0.0709480000 9691638 96830484 1769775104 2.9380261898 3.3977296352 4.8540477753 746 29.8000000000 0.8877432346 0.2960299486 0.8877432346 0.0385407565 0.1389550000 0.0112800000 0.0695580000 0.0000260000 0.0002950000 0.0412990000 9693312 96830484 1768235008 2.9331462383 3.3979241848 4.8458271027 747 29.8400000000 0.8873891234 0.2968215941 0.8877432346 0.0385257383 0.1478190000 0.0086310000 0.0707540000 0.0012000000 0.0002810000 0.0483460000 9694986 96830484 1769947136 2.9378142357 3.3968939781 4.8406214714 748 29.8800000000 0.8876511455 0.2976114732 0.8877432346 0.0385016902 0.1466800000 0.0105060000 0.0703330000 0.0000310000 0.0003670000 0.0414550000 9696660 96830484 1768669184 2.9398868084 3.3934388161 4.8376893997 749 29.9200000000 0.8878951669 0.2983995689 0.8878951669 0.0384772170 0.1640620000 0.0085570000 0.0710890000 0.0005340000 0.0002900000 0.0751610000 9698334 96830484 1770184704 2.9360866547 3.3932957649 4.8296618462 750 29.9600000000 0.8878538013 0.2991855079 0.8878951669 0.0384517155 0.1323930000 0.0106110000 0.0696290000 0.0000280000 0.0003120000 0.0418930000 9700008 96830484 1769029632 2.9326889515 3.3956918716 4.8190784454 751 30.0000000000 0.8888334036 0.2999706582 0.8888334036 0.0384296781 0.1462700000 0.0088230000 0.0695510000 0.0002980000 0.0003550000 0.0493280000 9701682 96830484 1770840064 2.9313511848 3.3934345245 4.8145513535 752 30.0400000000 0.8885419369 0.3007533328 0.8888334036 0.0384053436 0.1467820000 0.0106130000 0.0701850000 0.0000300000 0.0003030000 0.0428970000 9703356 96830484 1769631744 2.9291012287 3.3925788403 4.8106799126 753 30.0800000000 0.8892777562 0.3015349057 0.8892777562 0.0383798431 0.1663270000 0.0106290000 0.0710150000 0.0002980000 0.0003590000 0.0754070000 9705030 96830484 1767743488 2.9248695374 3.3951506615 4.8011336327 754 30.1200000000 0.8894123435 0.3023145840 0.8894123435 0.0383621683 0.1323900000 0.0083220000 0.0688210000 0.0000240000 0.0003090000 0.0418180000 9706704 96830484 1769549824 2.9257061481 3.3919317722 4.7963266373 755 30.1600000000 0.8894010186 0.3030921819 0.8894123435 0.0383386352 0.1310310000 0.0102810000 0.0650110000 0.0002960000 0.0003610000 0.0465060000 9708378 96830484 1768161280 2.9298639297 3.3890776634 4.7943344116 756 30.2000000000 0.8901574016 0.3038687232 0.8901574016 0.0383135434 0.1270980000 0.0085910000 0.0703580000 0.0000270000 0.0002990000 0.0390820000 9710052 96830484 1769775104 2.9279110432 3.3881022930 4.7871708870 757 30.2400000000 0.8902650476 0.3046433551 0.8902650476 0.0382888848 0.1449030000 0.0101410000 0.0363060000 0.0002910000 0.0002730000 0.0814250000 9711726 96830484 1768652800 2.9257988930 3.3870391846 4.7803034782 758 30.2800000000 0.8906463981 0.3054164462 0.8906463981 0.0382638517 0.1300080000 0.0088310000 0.0705350000 0.0000260000 0.0002950000 0.0415070000 9713400 96830484 1770422272 2.9235777855 3.3871364594 4.7739191055 759 30.3200000000 0.8908140659 0.3061877210 0.8908140659 0.0382388664 0.1467240000 0.0108370000 0.0695320000 0.0003700000 0.0002860000 0.0494710000 9715074 96830484 1769140224 2.9223506451 3.3893637657 4.7635736465 760 30.3600000000 0.8911832571 0.3069574520 0.8911832571 0.0382205501 0.1301800000 0.0086710000 0.0716370000 0.0000250000 0.0003000000 0.0408030000 9716748 96830484 1771057152 2.9258992672 3.3862581253 4.7583022118 761 30.4000000000 0.8915829062 0.3077256852 0.8915829062 0.0381964172 0.1664170000 0.0107220000 0.0701150000 0.0003550000 0.0002660000 0.0761510000 9718422 96830484 1769791488 2.9262938499 3.3845651150 4.7538452148 762 30.4400000000 0.8922157288 0.3084927325 0.8922157288 0.0381719753 0.1456830000 0.0110290000 0.0690610000 0.0000260000 0.0003020000 0.0423070000 9720096 96830484 1768034304 2.9229724407 3.3837664127 4.7462606430 763 30.4800000000 0.8920970559 0.3092576137 0.8922157288 0.0381510439 0.1341470000 0.0086160000 0.0698180000 0.0002830000 0.0003430000 0.0464600000 9721770 96830484 1769656320 2.9227216244 3.3811779022 4.7384638786 764 30.5200000000 0.8926090598 0.3100211627 0.8926090598 0.0381264359 0.1264620000 0.0102320000 0.0683710000 0.0000900000 0.0002940000 0.0388110000 9723444 96830484 1768288256 2.9240911007 3.3820896149 4.7318611145 765 30.5600000000 0.8926363587 0.3107827512 0.8926363587 0.0381025150 0.1651720000 0.0083970000 0.0705220000 0.0003830000 0.0002770000 0.0767960000 9725118 96830484 1770012672 2.9247069359 3.3808610439 4.7230486870 766 30.6000000000 0.8930877447 0.3115429405 0.8930877447 0.0380799509 0.1302190000 0.0107110000 0.0688730000 0.0000260000 0.0003800000 0.0413550000 9726792 96830484 1768906752 2.9294605255 3.3748097420 4.7194819450 767 30.6400000000 0.8933600783 0.3123015026 0.8933600783 0.0380553294 0.1459200000 0.0084980000 0.0703300000 0.0005430000 0.0002850000 0.0497170000 9728466 96830484 1770549248 2.9298572540 3.3747682571 4.7095751762 768 30.6800000000 0.8938381672 0.3130587118 0.8938381672 0.0380316000 0.1291640000 0.0104700000 0.0646120000 0.0000280000 0.0002920000 0.0418000000 9730140 96830484 1769410560 2.9300820827 3.3727672100 4.7001523972 769 30.7200000000 0.8940851092 0.3138142727 0.8940851092 0.0380097453 0.1649680000 0.0088480000 0.0697980000 0.0002890000 0.0003410000 0.0770490000 9731814 96830484 1771094016 2.9364240170 3.3665385246 4.6984028816 770 30.7600000000 0.8943939209 0.3145682723 0.8943939209 0.0379864956 0.1320530000 0.0105590000 0.0697990000 0.0000280000 0.0003000000 0.0422200000 9733488 96830484 1769664512 2.9377188683 3.3660285473 4.6910533905 771 30.8000000000 0.8948213458 0.3153208703 0.8948213458 0.0379625536 0.1457400000 0.0104150000 0.0660840000 0.0004960000 0.0003580000 0.0495400000 9735162 96830484 1767759872 2.9373805523 3.3632221222 4.6808075905 772 30.8400000000 0.8953315616 0.3160721795 0.8953315616 0.0379380011 0.1464030000 0.0087440000 0.0713990000 0.0000260000 0.0003550000 0.0430020000 9736836 96830484 1769504768 2.9440021515 3.3585381508 4.6755948067 773 30.8800000000 0.8957154751 0.3168220415 0.8957154751 0.0379154313 0.1669760000 0.0100430000 0.0710400000 0.0003570000 0.0002780000 0.0766200000 9738510 96830484 1768144896 2.9498302937 3.3563671112 4.6693892479 774 30.9200000000 0.8959422112 0.3175702587 0.8959422112 0.0378957711 0.1102680000 0.0086940000 0.0417030000 0.0000290000 0.0003570000 0.0417340000 9740184 96830484 1769775104 2.9480586052 3.3567411900 4.6595754623 775 30.9600000000 0.8964182734 0.3183171594 0.8964182734 0.0378722922 0.1484180000 0.0102960000 0.0698380000 0.0003090000 0.0006690000 0.0488130000 9741858 96830484 1768251392 2.9465329647 3.3559813499 4.6519618034 776 31.0000000000 0.8964045048 0.3190621173 0.8964182734 0.0378494781 0.1304350000 0.0086830000 0.0715990000 0.0000260000 0.0004820000 0.0409550000 9743532 96830484 1770057728 2.9450039864 3.3554964066 4.6447038651 777 31.0400000000 0.8966116309 0.3198054243 0.8966116309 0.0378254420 0.1662960000 0.0104380000 0.0724330000 0.0002930000 0.0003430000 0.0741050000 9745206 96830484 1768505344 2.9493074417 3.3544132710 4.6386251450 778 31.0800000000 0.8971500993 0.3205475126 0.8971500993 0.0378024025 0.1306520000 0.0085660000 0.0718410000 0.0000290000 0.0002920000 0.0401440000 9746880 96830484 1770266624 2.9483292103 3.3534622192 4.6307792664 779 31.1200000000 0.8977337480 0.3212884448 0.8977337480 0.0377803289 0.1483490000 0.0106020000 0.0721270000 0.0002910000 0.0002630000 0.0488050000 9748554 96830484 1768878080 2.9491741657 3.3559253216 4.6227917671 780 31.1600000000 0.8979111314 0.3220277047 0.8979111314 0.0377580222 0.1436390000 0.0087430000 0.0724990000 0.0000280000 0.0005840000 0.0400710000 9750228 96830484 1770577920 2.9494445324 3.3608806133 4.6130547523 781 31.2000000000 0.8976424336 0.3227647274 0.8979111314 0.0377341307 0.1885650000 0.0106790000 0.0802930000 0.0003460000 0.0003440000 0.0763610000 9751902 96830484 1769132032 2.9545116425 3.3614571095 4.6050419807 782 31.2400000000 0.8985362649 0.3235010081 0.8985362649 0.0377102085 0.1280980000 0.0087670000 0.0732460000 0.0000300000 0.0002870000 0.0367580000 9753576 96830484 1770684416 2.9591915607 3.3590383530 4.5990395546 783 31.2800000000 0.8982836604 0.3242350856 0.8985362649 0.0376865358 0.1459100000 0.0107480000 0.0732700000 0.0003030000 0.0002740000 0.0469720000 9755250 96830484 1769259008 2.9636149406 3.3589789867 4.5943460464 784 31.3200000000 0.8990293145 0.3249682415 0.8990293145 0.0376628801 0.1461200000 0.0088440000 0.0754800000 0.0000310000 0.0009470000 0.0391590000 9756924 96830484 1771065344 2.9644548893 3.3580336571 4.5854864120 785 31.3600000000 0.8993961811 0.3256999968 0.8993961811 0.0376395777 0.1420060000 0.0104340000 0.0502780000 0.0003080000 0.0002940000 0.0717470000 9758598 96830484 1769893888 2.9634504318 3.3559865952 4.5800299644 786 31.4000000000 0.8996276259 0.3264301846 0.8996276259 0.0376171562 0.1358630000 0.0105550000 0.0724440000 0.0000290000 0.0003010000 0.0389020000 9760272 96830484 1768153088 2.9672145844 3.3510446548 4.5763220787 787 31.4400000000 0.8998827934 0.3271588411 0.8998827934 0.0375935161 0.1496540000 0.0089530000 0.0753460000 0.0003040000 0.0002780000 0.0558380000 9761946 96830484 1769775104 2.9703903198 3.3480041027 4.5728254318 788 31.4800000000 0.9001074433 0.3278859332 0.9001074433 0.0375699992 0.1264650000 0.0101620000 0.0636330000 0.0000260000 0.0003040000 0.0394310000 9763620 96830484 1768407040 2.9728391171 3.3473548889 4.5675601959 789 31.5200000000 0.9001147747 0.3286111916 0.9001147747 0.0375465191 0.1490310000 0.0083270000 0.0590340000 0.0002950000 0.0003630000 0.0720760000 9765294 96830484 1770020864 2.9743983746 3.3471422195 4.5610957146 790 31.5600000000 0.9006195664 0.3293352528 0.9006195664 0.0375231517 0.1090000000 0.0108490000 0.0508890000 0.0000260000 0.0003810000 0.0377590000 9766968 96830484 1768894464 2.9757544994 3.3462741375 4.5578775406 791 31.6000000000 0.9008418918 0.3300577643 0.9008418918 0.0374999236 0.1463700000 0.0089170000 0.0753270000 0.0003030000 0.0002750000 0.0489600000 9768642 96830484 1770512384 2.9748897552 3.3477303982 4.5503997803 792 31.6400000000 0.9008519053 0.3307784640 0.9008519053 0.0374773962 0.1461720000 0.0104990000 0.0752230000 0.0000280000 0.0003520000 0.0407880000 9770316 96830484 1769529344 2.9740672112 3.3448517323 4.5453267097 793 31.6800000000 0.9012389183 0.3314978341 0.9012389183 0.0374540251 0.1698610000 0.0086900000 0.0784880000 0.0002930000 0.0003470000 0.0731250000 9771990 96830484 1771212800 2.9768662453 3.3413829803 4.5446138382 794 31.7200000000 0.9010797143 0.3322151916 0.9012389183 0.0374313905 0.1462680000 0.0109520000 0.0744210000 0.0000260000 0.0002840000 0.0406540000 9773664 96830484 1769783296 2.9745256901 3.3425202370 4.5362915993 795 31.7600000000 0.9015654922 0.3329313555 0.9015654922 0.0374085925 0.1501310000 0.0104920000 0.0758250000 0.0000600000 0.0000530000 0.0496770000 9775338 96830484 1767899136 2.9728987217 3.3409936428 4.5309972763 796 31.8000000000 0.9015450478 0.3336456943 0.9015654922 0.0373854426 0.1456830000 0.0090480000 0.0757660000 0.0000260000 0.0003670000 0.0399780000 9777012 96830484 1769668608 2.9756298065 3.3387422562 4.5283083916 797 31.8400000000 0.9017561078 0.3343585054 0.9017561078 0.0373620643 0.1888600000 0.0101490000 0.0896830000 0.0003090000 0.0002780000 0.0711430000 9778686 96830484 1768099840 2.9776687622 3.3382642269 4.5239686966 798 31.8800000000 0.9019471407 0.3350697693 0.9019471407 0.0373387982 0.1480870000 0.0085680000 0.0821730000 0.0000290000 0.0002870000 0.0407520000 9780360 96830484 1769766912 2.9765179157 3.3355650902 4.5208153725 799 31.9200000000 0.9019451737 0.3357792504 0.9019471407 0.0373174881 0.1493540000 0.0105770000 0.0757960000 0.0002970000 0.0002730000 0.0485540000 9782034 96830484 1768407040 2.9737629890 3.3406424522 4.5112948418 800 31.9600000000 0.9023775458 0.3364874983 0.9023775458 0.0372970436 0.1080270000 0.0085970000 0.0459160000 0.0000250000 0.0003840000 0.0403820000 9783708 96830484 1770160128 2.9715907574 3.3351490498 4.5065503120 801 32.0000000000 0.9025018811 0.3371941330 0.9025018811 0.0372774905 0.1867570000 0.0103780000 0.0754860000 0.0002950000 0.0002690000 0.0818590000 9785382 96830484 1769021440 2.9772710800 3.3244471550 4.5107331276 802 32.0400000000 0.9026885033 0.3378992382 0.9026885033 0.0372585739 0.1471090000 0.0086660000 0.0752290000 0.0000230000 0.0003750000 0.0415350000 9787056 96830484 1770704896 2.9765670300 3.3233647346 4.5060100555 803 32.0800000000 0.9031270742 0.3386031334 0.9031270742 0.0372380294 0.1295850000 0.0105110000 0.0512030000 0.0007090000 0.0002940000 0.0489460000 9788730 96830484 1769259008 2.9750049114 3.3240056038 4.4981641769 804 32.1199999990 0.9030194283 0.3393051437 0.9031270742 0.0372150499 0.1271800000 0.0085500000 0.0576910000 0.0000250000 0.0002990000 0.0408440000 9790404 96830484 1770893312 2.9747347832 3.3209280968 4.4953074455 805 32.1600000000 0.9035098553 0.3400060191 0.9035098553 0.0371925520 0.1713800000 0.0104330000 0.0750730000 0.0003530000 0.0002750000 0.0759920000 9792078 96830484 1769783296 2.9742605686 3.3165714741 4.4910774231 806 32.2000000000 0.9042528868 0.3407060773 0.9042528868 0.0371784546 0.1460620000 0.0101490000 0.0754660000 0.0000240000 0.0019240000 0.0422430000 9793752 96830484 1767989248 2.9783458710 3.3186714649 4.4733605385 807 32.2400000000 0.9041322470 0.3414042510 0.9042528868 0.0371573219 0.1483590000 0.0085120000 0.0750260000 0.0002850000 0.0002650000 0.0493870000 9795426 96830484 1769668608 2.9783749580 3.3201785088 4.4673738480 808 32.2800000000 0.9042777419 0.3421008766 0.9042777419 0.0371381885 0.1467850000 0.0098860000 0.0754430000 0.0000250000 0.0002840000 0.0424600000 9797100 96830484 1768243200 2.9762861729 3.3257219791 4.4572591782 809 32.3200000000 0.9047791958 0.3427963998 0.9047791958 0.0371159803 0.1670990000 0.0082110000 0.0704880000 0.0003780000 0.0002760000 0.0785690000 9798774 96830484 1769893888 2.9719507694 3.3242790699 4.4494833946 810 32.3600000000 0.9049804211 0.3434904542 0.9049804211 0.0370950193 0.1487710000 0.0103530000 0.0742540000 0.0000240000 0.0002840000 0.0444310000 9800448 96830484 1768751104 2.9714643955 3.3203437328 4.4465394020 811 32.4000000000 0.9053982496 0.3441833121 0.9053982496 0.0370736209 0.1500210000 0.0085660000 0.0761350000 0.0002980000 0.0002700000 0.0522900000 9802122 96830484 1770409984 2.9680681229 3.3135128021 4.4405999184 812 32.4399999990 0.9057129622 0.3448748511 0.9057129622 0.0370523010 0.1473790000 0.0105740000 0.0758610000 0.0000930000 0.0002910000 0.0450980000 9803796 96830484 1769021440 2.9710366726 3.3058261871 4.4410471916 813 32.4800000000 0.9059248567 0.3455649495 0.9059248567 0.0370446159 0.1761060000 0.0084930000 0.0763370000 0.0003750000 0.0002810000 0.0814770000 9805470 96830484 1770700800 2.9705951214 3.3156313896 4.4276218414 814 32.5200000000 0.9064582586 0.3462540076 0.9064582586 0.0370265465 0.1549240000 0.0115310000 0.0764960000 0.0002600000 0.0013300000 0.0452920000 9807144 96830484 1769275392 2.9642477036 3.3252024651 4.4094591141 815 32.5600000000 0.9066705704 0.3469416353 0.9066705704 0.0370155213 0.1505820000 0.0088580000 0.0766060000 0.0002950000 0.0002720000 0.0533110000 9808818 96830484 1770954752 2.9621784687 3.3161332607 4.4083981514 816 32.6000000000 0.9069301486 0.3476278957 0.9069301486 0.0369934492 0.1469480000 0.0105760000 0.0757200000 0.0000260000 0.0002930000 0.0453340000 9810492 96830484 1769512960 2.9612965584 3.3123686314 4.4039840698 817 32.6400000000 0.9073195457 0.3483129528 0.9073195457 0.0369715072 0.1784980000 0.0102090000 0.0759630000 0.0006620000 0.0003000000 0.0821320000 9812166 96830484 1768005632 2.9580652714 3.3121008873 4.3959250450 818 32.6800000000 0.9079514742 0.3489971075 0.9079514742 0.0369496885 0.1165230000 0.0092040000 0.0528710000 0.0000280000 0.0003520000 0.0447410000 9813840 96830484 1769795584 2.9531197548 3.3085434437 4.3878908157 819 32.7200000000 0.9083218575 0.3496800437 0.9083218575 0.0369285427 0.1483570000 0.0103180000 0.0761100000 0.0002910000 0.0002680000 0.0520860000 9815514 96830484 1768243200 2.9511630535 3.3016591072 4.3837585449 820 32.7599999990 0.9085288048 0.3503615666 0.9085288048 0.0369067435 0.1453910000 0.0084930000 0.0753930000 0.0000250000 0.0003550000 0.0463440000 9817188 96830484 1770020864 2.9516162872 3.3020999432 4.3772120476 821 32.7999999990 0.9091310501 0.3510421628 0.9091310501 0.0368848711 0.1864960000 0.0110600000 0.0640040000 0.0003550000 0.0002640000 0.0890700000 9818862 96830484 1768898560 2.9483268261 3.3023052216 4.3683710098 822 32.8400000000 0.9093497992 0.3517213692 0.9093497992 0.0368628328 0.1491920000 0.0086520000 0.0770550000 0.0000260000 0.0002850000 0.0469440000 9820536 96830484 1770639360 2.9454512596 3.3001487255 4.3616418839 823 32.8800000000 0.9096625447 0.3523993050 0.9096625447 0.0368410249 0.1507540000 0.0106570000 0.0753190000 0.0002890000 0.0002670000 0.0545680000 9822210 96830484 1769402368 2.9440853596 3.3005797863 4.3550930023 824 32.9200000000 0.9098956585 0.3530758782 0.9098956585 0.0368192056 0.1463010000 0.0087320000 0.0751030000 0.0000260000 0.0002910000 0.0481310000 9823884 96830484 1771065344 2.9399583340 3.3016490936 4.3452310562 825 32.9600000000 0.9102944136 0.3537512946 0.9102944136 0.0367995682 0.1880390000 0.0105530000 0.0760970000 0.0002940000 0.0002670000 0.0864190000 9825558 96830484 1769639936 2.9399347305 3.2954723835 4.3421430588 826 33.0000000000 0.9107744098 0.3544256568 0.9107744098 0.0367777802 0.1480320000 0.0103380000 0.0761830000 0.0000300000 0.0002900000 0.0476730000 9827232 96830484 1768153088 2.9419782162 3.2961835861 4.3366007805 827 33.0400000000 0.9112448096 0.3550989568 0.9112448096 0.0367559753 0.1495930000 0.0088140000 0.0755580000 0.0003580000 0.0002690000 0.0550450000 9828906 96830484 1769811968 2.9374058247 3.2935762405 4.3268866539 828 33.0800000000 0.9114844203 0.3557709199 0.9114844203 0.0367370362 0.1468880000 0.0103750000 0.0758880000 0.0000260000 0.0002990000 0.0479000000 9830580 96830484 1768480768 2.9382205009 3.2840898037 4.3264040947 829 33.1199999990 0.9118646383 0.3564417206 0.9118646383 0.0367193698 0.1877970000 0.0083880000 0.0757130000 0.0003540000 0.0002700000 0.0886740000 9832254 96830484 1770037248 2.9398269653 3.2852699757 4.3202190399 830 33.1600000000 0.9121624231 0.3571112636 0.9121624231 0.0367038209 0.1479850000 0.0104740000 0.0763570000 0.0000270000 0.0002980000 0.0478820000 9833928 96830484 1768636416 2.9319279194 3.2896776199 4.3068799973 831 33.2000000000 0.9125914574 0.3577797115 0.9125914574 0.0366828942 0.1492730000 0.0087420000 0.0754240000 0.0003630000 0.0002750000 0.0549760000 9835602 96830484 1770303488 2.9305768013 3.2856259346 4.3021130562 832 33.2400000000 0.9127149582 0.3584467009 0.9127149582 0.0366614779 0.1470020000 0.0103710000 0.0764610000 0.0000260000 0.0003630000 0.0471340000 9837276 96830484 1769275392 2.9344501495 3.2812542915 4.3010535240 833 33.2800000000 0.9131430984 0.3591126030 0.9131430984 0.0366416460 0.1875310000 0.0088200000 0.0756710000 0.0003120000 0.0003570000 0.0877780000 9838950 96830484 1770909696 2.9353740215 3.2803134918 4.2936706543 834 33.3200000000 0.9134850502 0.3597773181 0.9134850502 0.0366215618 0.1479070000 0.0103950000 0.0756030000 0.0000270000 0.0003520000 0.0469640000 9840624 96830484 1769783296 2.9319133759 3.2784311771 4.2861957550 835 33.3600000000 0.9139803052 0.3604410343 0.9139803052 0.0366011390 0.1496010000 0.0104880000 0.0754410000 0.0002860000 0.0003370000 0.0536700000 9842298 96830484 1768390656 2.9303891659 3.2776842117 4.2776179314 836 33.4000000000 0.9142147899 0.3611034431 0.9142147899 0.0365806906 0.1457980000 0.0086360000 0.0744460000 0.0000270000 0.0003560000 0.0473090000 9843972 96830484 1770156032 2.9302613735 3.2782654762 4.2696290016 837 33.4399999990 0.9145777225 0.3617647027 0.9145777225 0.0365593265 0.1599310000 0.0104650000 0.0582730000 0.0003720000 0.0002770000 0.0810520000 9845646 96830484 1768513536 2.9306566715 3.2762660980 4.2631974220 838 33.4800000000 0.9149242043 0.3624247976 0.9149242043 0.0365378757 0.1503420000 0.0098860000 0.0757870000 0.0000270000 0.0003640000 0.0460620000 9847320 96830484 1770303488 2.9317355156 3.2727384567 4.2572298050 839 33.5200000000 0.9153965116 0.3630838818 0.9153965116 0.0365175647 0.1670270000 0.0108100000 0.0765380000 0.0002980000 0.0003430000 0.0540670000 9848994 96830484 1768861696 2.9343140125 3.2732496262 4.2463250160 840 33.5600000000 0.9157741070 0.3637418464 0.9157741070 0.0364966235 0.1491560000 0.0087060000 0.0773330000 0.0000260000 0.0002890000 0.0448730000 9850668 96830484 1770577920 2.9410703182 3.2668330669 4.2422151566 841 33.6000000000 0.9160653949 0.3643985926 0.9160653949 0.0364755248 0.1887150000 0.0108270000 0.0765880000 0.0002910000 0.0003480000 0.0837850000 9852342 96830484 1769512960 2.9444115162 3.2634518147 4.2358174324 842 33.6400000000 0.9166019559 0.3650544161 0.9166019559 0.0364567732 0.1478250000 0.0092730000 0.0776920000 0.0000260000 0.0002800000 0.0434690000 9854016 96830484 1771065344 2.9454114437 3.2615170479 4.2270340919 843 33.6800000000 0.9174167514 0.3657096502 0.9174167514 0.0364407108 0.1499020000 0.0108360000 0.0771280000 0.0003610000 0.0002710000 0.0510700000 9855690 96830484 1769639936 2.9526708126 3.2569901943 4.2112088203 844 33.7200000000 0.9179618955 0.3663639775 0.9179618955 0.0364206297 0.1435450000 0.0102520000 0.0793290000 0.0000260000 0.0003600000 0.0422660000 9857364 96830484 1768132608 2.9546883106 3.2552950382 4.2015762329 845 33.7599999990 0.9181434512 0.3670169709 0.9181434512 0.0364023756 0.1860220000 0.0085070000 0.0783660000 0.0002940000 0.0003490000 0.0809950000 9859038 96830484 1769766912 2.9545061588 3.2570025921 4.1901669502 846 33.7999999990 0.9184374809 0.3676687682 0.9184374809 0.0363833074 0.1479090000 0.0104700000 0.0780250000 0.0000260000 0.0003120000 0.0414680000 9860712 96830484 1768517632 2.9551763535 3.2619695663 4.1785125732 847 33.8400000000 0.9187451005 0.3683193896 0.9187451005 0.0363624757 0.1495780000 0.0087510000 0.0788010000 0.0002950000 0.0003390000 0.0504450000 9862386 96830484 1770037248 2.9598052502 3.2628951073 4.1677098274 848 33.8800000000 0.9191386104 0.3689689406 0.9191386104 0.0363430345 0.1467090000 0.0105720000 0.0785240000 0.0000260000 0.0003670000 0.0413430000 9864060 96830484 1768636416 2.9684333801 3.2605719566 4.1600346565 849 33.9200000000 0.9194852710 0.3696173697 0.9194852710 0.0363220603 0.1865930000 0.0085640000 0.0784380000 0.0002930000 0.0003510000 0.0786220000 9865734 96830484 1770303488 2.9701750278 3.2561545372 4.1520142555 850 33.9600000000 0.9199637771 0.3702648361 0.9199637771 0.0363007247 0.1483990000 0.0103530000 0.0778100000 0.0000250000 0.0002890000 0.0414980000 9867408 96830484 1769275392 2.9776058197 3.2529511452 4.1430354118 851 34.0000000000 0.9201400876 0.3709109880 0.9201400876 0.0362793928 0.1500600000 0.0089310000 0.0796940000 0.0002900000 0.0002690000 0.0505560000 9869082 96830484 1770909696 2.9847922325 3.2497565746 4.1357250214 852 34.0400000000 0.9205834270 0.3715561434 0.9205834270 0.0362582456 0.1305970000 0.0104060000 0.0714980000 0.0000270000 0.0003570000 0.0385320000 9870756 96830484 1769783296 2.9882009029 3.2490458488 4.1260032654 853 34.0800000000 0.9207566381 0.3721999892 0.9207566381 0.0362370829 0.1833500000 0.0104540000 0.0785930000 0.0002870000 0.0003410000 0.0764170000 9872430 96830484 1768390656 2.9936833382 3.2505736351 4.1157541275 854 34.1199999990 0.9210212231 0.3728426370 0.9210212231 0.0362161752 0.1473620000 0.0088260000 0.0768240000 0.0000280000 0.0003620000 0.0422300000 9874104 96830484 1770065920 2.9965341091 3.2498908043 4.1073155403 855 34.1600000000 0.9213989377 0.3734842234 0.9213989377 0.0361951301 0.1504060000 0.0103920000 0.0777000000 0.0003140000 0.0003570000 0.0503260000 9875778 96830484 1768890368 3.0009503365 3.2466392517 4.0996088982 856 34.2000000000 0.9218135476 0.3741247950 0.9218135476 0.0361746078 0.1458670000 0.0085540000 0.0773410000 0.0000260000 0.0002840000 0.0417220000 9877452 96830484 1770668032 3.0077502728 3.2455768585 4.0920829773 857 34.2400000000 0.9218382239 0.3747639005 0.9218382239 0.0361536541 0.1886420000 0.0105850000 0.0900380000 0.0000600000 0.0000550000 0.0779740000 9879126 96830484 1769512960 3.0114161968 3.2438368797 4.0844888687 858 34.2800000000 0.9220933318 0.3754018136 0.9220933318 0.0361327471 0.1300310000 0.0089790000 0.0708940000 0.0000270000 0.0003770000 0.0400890000 9880800 96830484 1771212800 3.0163197517 3.2410674095 4.0787158012 859 34.3200000000 0.9223768711 0.3760385715 0.9223768711 0.0361139699 0.1638180000 0.0107490000 0.0783070000 0.0003690000 0.0002770000 0.0507480000 9882474 96830484 1769766912 3.0201430321 3.2426135540 4.0687780380 860 34.3600000000 0.9226385355 0.3766741529 0.9226385355 0.0360932360 0.1481200000 0.0103430000 0.0738760000 0.0000270000 0.0002940000 0.0430850000 9884148 96830484 1768263680 3.0242276192 3.2421951294 4.0596866608 861 34.4000000000 0.9231558442 0.3773088587 0.9231558442 0.0360725556 0.1887330000 0.0088470000 0.0786600000 0.0006250000 0.0002830000 0.0833870000 9885822 96830484 1769938944 3.0295026302 3.2386734486 4.0530419350 862 34.4400000000 0.9232083559 0.3779421528 0.9232083559 0.0360518094 0.1481460000 0.0105540000 0.0776100000 0.0000260000 0.0002950000 0.0427790000 9887496 96830484 1768497152 3.0339658260 3.2370409966 4.0457758904 863 34.4800000000 0.9234046340 0.3785742066 0.9234046340 0.0360311381 0.1493250000 0.0085130000 0.0764830000 0.0002890000 0.0002730000 0.0513810000 9889170 96830484 1770164224 3.0397131443 3.2378492355 4.0382809639 864 34.5200000000 0.9237986207 0.3792052534 0.9237986207 0.0360106444 0.1468790000 0.0104240000 0.0764350000 0.0000270000 0.0002890000 0.0436540000 9890844 96830484 1768763392 3.0433242321 3.2393686771 4.0286755562 865 34.5600000000 0.9240249991 0.3798351028 0.9240249991 0.0359923178 0.1758360000 0.0088230000 0.0768240000 0.0002890000 0.0002750000 0.0796790000 9892518 96830484 1770430464 3.0486857891 3.2334444523 4.0234665871 866 34.6000000000 0.9247226119 0.3804643032 0.9247226119 0.0359732389 0.1391680000 0.0115430000 0.0650020000 0.0000270000 0.0002880000 0.0442520000 9894192 96830484 1769275392 3.0518908501 3.2218258381 4.0221400261 867 34.6400000000 0.9252731204 0.3810926871 0.9252731204 0.0359620717 0.1483020000 0.0084620000 0.0694830000 0.0002870000 0.0002640000 0.0538330000 9895866 96830484 1770938368 3.0557646751 3.2180726528 4.0054364204 868 34.6800000000 0.9253850579 0.3817197520 0.9253850579 0.0359428617 0.1482790000 0.0107320000 0.0763090000 0.0000250000 0.0002890000 0.0455980000 9897540 96830484 1769783296 3.0624127388 3.2159521580 3.9993846416 869 34.7200000000 0.9254744053 0.3823454766 0.9254744053 0.0359246728 0.1879870000 0.0105590000 0.0756780000 0.0002920000 0.0002690000 0.0864990000 9899214 96830484 1768353792 3.0640175343 3.2157397270 3.9906651974 870 34.7600000000 0.9259241819 0.3829702797 0.9259241819 0.0359051028 0.1260960000 0.0084450000 0.0517740000 0.0000270000 0.0003610000 0.0465090000 9900888 96830484 1770065920 3.0688540936 3.2138392925 3.9819769859 871 34.8000000000 0.9260679483 0.3835938132 0.9260679483 0.0358847612 0.1313420000 0.0103850000 0.0575120000 0.0002910000 0.0003480000 0.0528900000 9902562 96830484 1768894464 3.0753257275 3.2101714611 3.9773190022 872 34.8400000000 0.9265161753 0.3842164306 0.9265161753 0.0358664990 0.1247250000 0.0085080000 0.0512430000 0.0000250000 0.0003170000 0.0466980000 9904236 96830484 1770684416 3.0768949986 3.2078104019 3.9702911377 873 34.8800000000 0.9264930487 0.3848375951 0.9265161753 0.0358497139 0.1522310000 0.0105040000 0.0456060000 0.0003210000 0.0002800000 0.0854990000 9905910 96830484 1769529344 3.0848901272 3.2119898796 3.9611999989 874 34.9200000000 0.9267579913 0.3854576413 0.9267579913 0.0358302131 0.1079410000 0.0085360000 0.0445560000 0.0000260000 0.0003940000 0.0444780000 9907584 96830484 1771212800 3.0855724812 3.2122070789 3.9519596100 875 34.9600000000 0.9267485738 0.3860762595 0.9267579913 0.0358108271 0.1226650000 0.0104020000 0.0456550000 0.0003890000 0.0002810000 0.0559240000 9909258 96830484 1769766912 3.0903987885 3.2156901360 3.9434251785 876 35.0000000000 0.9269663692 0.3866937140 0.9269663692 0.0357905901 0.1255830000 0.0100850000 0.0514040000 0.0000250000 0.0002890000 0.0479750000 9910932 96830484 1768226816 3.0953247547 3.2140161991 3.9364290237 877 35.0400000000 0.9269018769 0.3873096868 0.9269663692 0.0357702787 0.1477150000 0.0085850000 0.0384940000 0.0003650000 0.0002810000 0.0897830000 9912606 96830484 1769918464 3.1041574478 3.2102344036 3.9329237938 878 35.0800000000 0.9272672534 0.3879246726 0.9272672534 0.0357502531 0.1276680000 0.0104330000 0.0506680000 0.0000310000 0.0003740000 0.0478140000 9914280 96830484 1768660992 3.1073942184 3.2061836720 3.9272451401 879 35.1200000000 0.9271989465 0.3885381815 0.9272672534 0.0357336662 0.1275550000 0.0084920000 0.0384260000 0.0002890000 0.0002700000 0.0606460000 9915954 96830484 1770176512 3.1104388237 3.2097637653 3.9159622192 880 35.1600000000 0.9273045659 0.3891504160 0.9273045659 0.0357134512 0.1288220000 0.0104340000 0.0517130000 0.0000970000 0.0003130000 0.0491670000 9917628 96830484 1768894464 3.1189086437 3.2072196007 3.9097549915 881 35.2000000000 0.9273103476 0.3897612672 0.9273103476 0.0356933506 0.1523310000 0.0085790000 0.0443320000 0.0003190000 0.0003680000 0.0885630000 9919302 96830484 1770430464 3.1236405373 3.2044034004 3.9051866531 882 35.2400000000 0.9273352623 0.3903707615 0.9273352623 0.0356737705 0.1240820000 0.0106970000 0.0506770000 0.0000280000 0.0003510000 0.0494880000 9920976 96830484 1769021440 3.1304855347 3.2041325569 3.8966722488 883 35.2800000000 0.9277560711 0.3909793519 0.9277560711 0.0356539454 0.1272170000 0.0086430000 0.0429480000 0.0010290000 0.0003060000 0.0585560000 9922650 96830484 1770639360 3.1324412823 3.2030234337 3.8870508671 884 35.3200000000 0.9276821017 0.3915864817 0.9277560711 0.0356339656 0.1105100000 0.0106500000 0.0385260000 0.0000290000 0.0002920000 0.0508130000 9924324 96830484 1769275392 3.1407642365 3.2026376724 3.8806624413 885 35.3600000000 0.9277426600 0.3921923079 0.9277560711 0.0356154151 0.1816710000 0.0077420000 0.0447850000 0.0002920000 0.0002670000 0.0989340000 9925998 96830484 1770938368 3.1485590935 3.1950693130 3.8771550655 886 35.4000000000 0.9283033609 0.3927973994 0.9283033609 0.0355963975 0.1299880000 0.0102750000 0.0482280000 0.0000260000 0.0002880000 0.0516720000 9927672 96830484 1769529344 3.1495354176 3.1866929531 3.8715307713 887 35.4400000000 0.9286633730 0.3934015324 0.9286633730 0.0355772860 0.1291550000 0.0100530000 0.0435460000 0.0010980000 0.0003510000 0.0601470000 9929346 96830484 1767624704 3.1522626877 3.1852838993 3.8607559204 888 35.4800000000 0.9290047884 0.3940046892 0.9290047884 0.0355574285 0.1267650000 0.0084850000 0.0493730000 0.0000280000 0.0005370000 0.0512750000 9931020 96830484 1769414656 3.1575667858 3.1805288792 3.8541607857 889 35.5200000000 0.9293499589 0.3946068774 0.9293499589 0.0355385100 0.1690710000 0.0098720000 0.0502580000 0.0003130000 0.0006910000 0.0936180000 9932694 96830484 1767972864 3.1620693207 3.1770806313 3.8470838070 890 35.5600000000 0.9298777580 0.3952083053 0.9298777580 0.0355222146 0.1251910000 0.0080780000 0.0431220000 0.0000270000 0.0003000000 0.0517350000 9934368 96830484 1769639936 3.1665377617 3.1770842075 3.8377912045 891 35.6000000000 0.9302192330 0.3958087665 0.9302192330 0.0355055944 0.1301540000 0.0102850000 0.0442990000 0.0003260000 0.0003500000 0.0597780000 9936042 96830484 1768243200 3.1725761890 3.1781096458 3.8258578777 892 35.6400000000 0.9304000735 0.3964080841 0.9304000735 0.0354865725 0.1093810000 0.0082790000 0.0368970000 0.0000100000 0.0001130000 0.0537480000 9937716 96830484 1769922560 3.1764233112 3.1776514053 3.8163857460 893 35.6800000000 0.9308326840 0.3970065439 0.9308326840 0.0354670955 0.1756880000 0.0096830000 0.0631940000 0.0003230000 0.0003620000 0.0920210000 9939390 96830484 1768386560 3.1838657856 3.1745729446 3.8108043671 894 35.7200000000 0.9310763478 0.3976039375 0.9310763478 0.0354486002 0.1169260000 0.0086100000 0.0381080000 0.0000180000 0.0002340000 0.0544990000 9941064 96830484 1770274816 3.1921074390 3.1755833626 3.8041546345 895 35.7600000000 0.9313367605 0.3982002870 0.9313367605 0.0354302706 0.1499160000 0.0094430000 0.0563820000 0.0003940000 0.0002820000 0.0732250000 9942738 96830484 1769021440 3.1973466873 3.1760208607 3.7933154106 896 35.8000000000 0.9315033555 0.3987954913 0.9315033555 0.0354112952 0.1646790000 0.0076400000 0.0589240000 0.0000970000 0.0002930000 0.0788210000 9944412 96830484 1770766336 3.2028639317 3.1773862839 3.7847263813 897 35.8400000000 0.9316714406 0.3993895559 0.9316714406 0.0353929201 0.1803720000 0.0103020000 0.0579030000 0.0002930000 0.0002640000 0.1011520000 9946086 96830484 1769656320 3.2105882168 3.1838083267 3.7726988792 898 35.8800000000 0.9318589568 0.3999825062 0.9318589568 0.0353758470 0.1318730000 0.0114380000 0.0434650000 0.0000270000 0.0010720000 0.0531880000 9947760 96830484 1767899136 3.2184276581 3.1841695309 3.7659833431 899 35.9200000000 0.9321341515 0.4005744436 0.9321341515 0.0353590114 0.1297630000 0.0083260000 0.0439970000 0.0003210000 0.0002750000 0.0621690000 9949434 96830484 1769541632 3.2252001762 3.1816208363 3.7586469650 900 35.9600000000 0.9327130914 0.4011657087 0.9327130914 0.0353424216 0.1281840000 0.0099330000 0.0507360000 0.0000250000 0.0002860000 0.0537820000 9951108 96830484 1768136704 3.2340953350 3.1736807823 3.7556009293 901 36.0000000000 0.9332782626 0.4017562887 0.9332782626 0.0353238713 0.1840270000 0.0085770000 0.0503760000 0.0003800000 0.0002860000 0.0963350000 9952782 96830484 1769766912 3.2373564243 3.1668627262 3.7514615059 902 36.0400000000 0.9340388179 0.4023464024 0.9340388179 0.0353068977 0.1147080000 0.0097320000 0.0435690000 0.0000320000 0.0003220000 0.0506050000 9954456 96830484 1768607744 3.2430353165 3.1662931442 3.7382726669 903 36.0800000000 0.9345437288 0.4029357682 0.9345437288 0.0352886651 0.1257960000 0.0081440000 0.0410030000 0.0002890000 0.0002700000 0.0657290000 9956130 96830484 1770323968 3.2492964268 3.1622688770 3.7316381931 904 36.1200000000 0.9345966578 0.4035238886 0.9345966578 0.0352700624 0.1466290000 0.0095170000 0.0669770000 0.0000290000 0.0003270000 0.0539110000 9957804 96830484 1769275392 3.2620995045 3.1614325047 3.7353765965 905 36.1600000000 0.9359920025 0.4041122512 0.9359920025 0.0352621707 0.1594980000 0.0081300000 0.0405010000 0.0002880000 0.0002660000 0.0994190000 9959478 96830484 1770958848 3.2857930660 3.1590273380 3.7091565132 906 36.2000000000 0.9361653924 0.4046995063 0.9361653924 0.0352439940 0.1338810000 0.0117520000 0.0506790000 0.0000260000 0.0003810000 0.0546810000 9961152 96830484 1769529344 3.2929673195 3.1564455032 3.7008080482 907 36.2400000000 0.9368035197 0.4052861700 0.9368035197 0.0352252642 0.1292170000 0.0083290000 0.0448780000 0.0003180000 0.0003520000 0.0640630000 9962826 96830484 1771212800 3.2993183136 3.1509363651 3.6964912415 908 36.2800000000 0.9368947744 0.4058716421 0.9368947744 0.0352093692 0.1274020000 0.0101720000 0.0455390000 0.0000300000 0.0003240000 0.0582600000 9964500 96830484 1769783296 3.3034160137 3.1514229774 3.6897077560 909 36.3200000000 0.9368301630 0.4064557549 0.9368947744 0.0351913453 0.1687320000 0.0100570000 0.0497040000 0.0002920000 0.0002680000 0.0979730000 9966174 96830484 1767862272 3.3134481907 3.1546509266 3.6853420734 910 36.3600000000 0.9368940592 0.4070386541 0.9368947744 0.0351730532 0.1232810000 0.0083590000 0.0458990000 0.0000270000 0.0003260000 0.0560940000 9967848 96830484 1769648128 3.3221623898 3.1536855698 3.6840624809 911 36.4000000000 0.9370583296 0.4076204540 0.9370583296 0.0351546622 0.1280810000 0.0096980000 0.0394530000 0.0003580000 0.0002780000 0.0679190000 9969522 96830484 1768153088 3.3272478580 3.1510863304 3.6818397045 912 36.4400000000 0.9371108413 0.4082010355 0.9371108413 0.0351363602 0.1453240000 0.0074020000 0.0648030000 0.0000270000 0.0003880000 0.0557060000 9971196 96830484 1769893888 3.3345880508 3.1513333321 3.6752908230 913 36.4800000000 0.9375255704 0.4087807995 0.9375255704 0.0351178032 0.1853410000 0.0099170000 0.0460860000 0.0003880000 0.0002760000 0.1009610000 9972870 96830484 1768407040 3.3418233395 3.1497437954 3.6705005169 914 36.5200000000 0.9377323985 0.4093595212 0.9377323985 0.0350990390 0.1300190000 0.0081560000 0.0464520000 0.0000290000 0.0003150000 0.0568370000 9974544 96830484 1770160128 3.3475496769 3.1465203762 3.6667382717 915 36.5600000000 0.9375354052 0.4099367626 0.9377323985 0.0350803535 0.1482140000 0.0101670000 0.0524290000 0.0003880000 0.0002760000 0.0659240000 9976218 96830484 1769005056 3.3564002514 3.1466085911 3.6645350456 916 36.6000000000 0.9377049804 0.4105129288 0.9377323985 0.0350624311 0.1282270000 0.0082930000 0.0464310000 0.0000250000 0.0003940000 0.0563230000 9977892 96830484 1770704896 3.3651313782 3.1483013630 3.6592457294 917 36.6400000000 0.9379507899 0.4110881064 0.9379507899 0.0350435857 0.1765380000 0.0099490000 0.0564890000 0.0002900000 0.0003430000 0.0988780000 9979566 96830484 1769639936 3.3715293407 3.1435749531 3.6562378407 918 36.6800000000 0.9382349253 0.4116623404 0.9382349253 0.0350254093 0.1379470000 0.0109630000 0.0523450000 0.0000260000 0.0003000000 0.0564870000 9981240 96830484 1767772160 3.3775229454 3.1387538910 3.6522095203 919 36.7200000000 0.9382403493 0.4122353306 0.9382403493 0.0350075040 0.1301750000 0.0086550000 0.0458890000 0.0003170000 0.0003400000 0.0643570000 9982914 96830484 1769414656 3.3850762844 3.1406338215 3.6483435631 920 36.7600000000 0.9385269880 0.4128073867 0.9385269880 0.0349887728 0.1257030000 0.0095260000 0.0389470000 0.0000260000 0.0003750000 0.0601640000 9984588 96830484 1767989248 3.3909282684 3.1414361000 3.6418840885 921 36.8000000000 0.9382928014 0.4133779464 0.9385269880 0.0349703608 0.2041570000 0.0073610000 0.0617790000 0.0003870000 0.0002850000 0.1072400000 9986262 96830484 1769750528 3.4025199413 3.1443510056 3.6401019096 922 36.8400000000 0.9386069179 0.4139476090 0.9386069179 0.0349535461 0.1525320000 0.0105090000 0.0604320000 0.0000250000 0.0003670000 0.0685750000 9987936 96830484 1768644608 3.4125735760 3.1396334171 3.6388804913 923 36.8800000000 0.9383392930 0.4145157474 0.9386069179 0.0349347122 0.1663290000 0.0077200000 0.0515570000 0.0003780000 0.0002890000 0.0886510000 9989610 96830484 1770287104 3.4197874069 3.1375219822 3.6369798183 924 36.9200000000 0.9386674762 0.4150830111 0.9386674762 0.0349169174 0.1302520000 0.0101190000 0.0532490000 0.0000270000 0.0003110000 0.0560260000 9991284 96830484 1769148416 3.4308323860 3.1403853893 3.6294734478 925 36.9600000000 0.9389234185 0.4156493251 0.9389234185 0.0348994651 0.1695500000 0.0081140000 0.0474320000 0.0003070000 0.0002790000 0.0963800000 9992958 96830484 1770811392 3.4416198730 3.1398913860 3.6244840622 926 37.0000000000 0.9390605092 0.4162145639 0.9390605092 0.0348827029 0.1230010000 0.0100500000 0.0471310000 0.0000300000 0.0003190000 0.0546020000 9994632 96830484 1769656320 3.4577455521 3.1407735348 3.6165766716 927 37.0400000000 0.9392655492 0.4167788045 0.9392655492 0.0348646377 0.1440070000 0.0099000000 0.0470210000 0.0003080000 0.0002800000 0.0654900000 9996306 96830484 1768263680 3.4705519676 3.1414487362 3.6138637066 928 37.0800000000 0.9393445253 0.4173419141 0.9393445253 0.0348463219 0.1287320000 0.0081110000 0.0475760000 0.0000260000 0.0003190000 0.0572330000 9997980 96830484 1770004480 3.4782052040 3.1369576454 3.6109468937 929 37.1200000000 0.9396384358 0.4179041278 0.9396384358 0.0348279172 0.1686270000 0.0101290000 0.0390330000 0.0003620000 0.0002720000 0.1031310000 9999654 96830484 1768386560 3.4876670837 3.1335761547 3.6079068184 930 37.1600000000 0.9396564364 0.4184651518 0.9396564364 0.0348096563 0.1226500000 0.0084100000 0.0411550000 0.0004000000 0.0003190000 0.0574280000 10001328 96830484 1770147840 3.4980406761 3.1332790852 3.6045992374 931 37.2000000000 0.9398006797 0.4190251255 0.9398006797 0.0347912506 0.1309840000 0.0101140000 0.0476900000 0.0003120000 0.0005320000 0.0615880000 10003002 96830484 1769021440 3.5052354336 3.1305036545 3.6000196934 932 37.2400000000 0.9400537014 0.4195841690 0.9400537014 0.0347728451 0.1256390000 0.0082660000 0.0480850000 0.0000240000 0.0003120000 0.0575180000 10004676 96830484 1770795008 3.5163872242 3.1319277287 3.5995855331 933 37.2800000000 0.9400538802 0.4201420144 0.9400538802 0.0347548925 0.1851310000 0.0100980000 0.0486120000 0.0003160000 0.0002760000 0.1025940000 10006350 96830484 1769639936 3.5272071362 3.1333694458 3.5948171616 934 37.3200000000 0.9403130412 0.4206989427 0.9403130412 0.0347373051 0.1299810000 0.0098480000 0.0477830000 0.0000280000 0.0003880000 0.0568830000 10008024 96830484 1768226816 3.5377757549 3.1341147423 3.5902481079 935 37.3600000000 0.9405907989 0.4212549768 0.9405907989 0.0347197580 0.1283580000 0.0081680000 0.0380450000 0.0003000000 0.0002750000 0.0681810000 10009698 96830484 1769811968 3.5492293835 3.1343364716 3.5891191959 936 37.4000000000 0.9405439496 0.4218097727 0.9405907989 0.0347016085 0.1692710000 0.0099170000 0.0739680000 0.0000310000 0.0003220000 0.0742030000 10011372 96830484 1768497152 3.5601251125 3.1326932907 3.5901935101 937 37.4400000000 0.9406332970 0.4223634797 0.9406332970 0.0346835415 0.2043490000 0.0075720000 0.0513990000 0.0003060000 0.0002820000 0.1247340000 10013046 96830484 1770037248 3.5714609623 3.1309156418 3.5896153450 938 37.4800000000 0.9410461783 0.4229164464 0.9410461783 0.0346652616 0.1283300000 0.0100280000 0.0394930000 0.0000260000 0.0003050000 0.0602230000 10014720 96830484 1768644608 3.5790498257 3.1275734901 3.5866138935 939 37.5200000000 0.9409529567 0.4234681359 0.9410461783 0.0346478517 0.1677870000 0.0079770000 0.0680680000 0.0003040000 0.0002820000 0.0717310000 10016394 96830484 1770303488 3.5905807018 3.1305229664 3.5826671124 940 37.5600000000 0.9410199523 0.4240187230 0.9410461783 0.0346296092 0.1328450000 0.0107560000 0.0524080000 0.0000280000 0.0003200000 0.0586630000 10018068 96830484 1768878080 3.6023406982 3.1325421333 3.5828213692 941 37.6000000000 0.9412798285 0.4245684160 0.9412798285 0.0346114077 0.2022830000 0.0076770000 0.0502910000 0.0003200000 0.0003540000 0.1233840000 10019742 96830484 1770573824 3.6107718945 3.1299881935 3.5808563232 942 37.6400000000 0.9413968921 0.4251170662 0.9413968921 0.0345933613 0.1291680000 0.0101700000 0.0476570000 0.0000270000 0.0003110000 0.0560670000 10021416 96830484 1769402368 3.6188781261 3.1266827583 3.5778675079 943 37.6800000000 0.9414955378 0.4256646573 0.9414955378 0.0345753487 0.1292050000 0.0098180000 0.0409410000 0.0003800000 0.0002770000 0.0668720000 10023090 96830484 1768005632 3.6303398609 3.1261017323 3.5777986050 944 37.7200000000 0.9414231777 0.4262110117 0.9414955378 0.0345572375 0.1299370000 0.0076980000 0.0459510000 0.0000270000 0.0003300000 0.0650230000 10024764 96830484 1769795584 3.6385881901 3.1247661114 3.5786259174 945 37.7600000000 0.9413293004 0.4267561104 0.9414955378 0.0345393303 0.1850730000 0.0096470000 0.0609990000 0.0003220000 0.0002810000 0.1002850000 10026438 96830484 1768280064 3.6502435207 3.1234977245 3.5802624226 946 37.8000000000 0.9415696263 0.4273003107 0.9415696263 0.0345217551 0.1274990000 0.0084540000 0.0494480000 0.0000950000 0.0003130000 0.0562390000 10028112 96830484 1770037248 3.6597449780 3.1214933395 3.5793368816 947 37.8400000000 0.9417418838 0.4278435437 0.9417418838 0.0345060519 0.1287260000 0.0103350000 0.0433380000 0.0009680000 0.0006210000 0.0625840000 10029786 96830484 1768894464 3.6690847874 3.1191444397 3.5759792328 948 37.8800000000 0.9418497682 0.4283857443 0.9418497682 0.0344897445 0.1258840000 0.0083960000 0.0429200000 0.0000250000 0.0010940000 0.0549730000 10031460 96830484 1770577920 3.6789038181 3.1166746616 3.5748696327 949 37.9200000000 0.9420289397 0.4289269911 0.9420289397 0.0344739275 0.1687000000 0.0103420000 0.0441160000 0.0003950000 0.0002810000 0.0981880000 10033134 96830484 1769402368 3.6883521080 3.1162569523 3.5710046291 950 37.9600000000 0.9421494007 0.4294672252 0.9421494007 0.0344567703 0.1264420000 0.0082850000 0.0427950000 0.0000280000 0.0003090000 0.0539600000 10034808 96830484 1771085824 3.6985187531 3.1159567833 3.5693528652 951 38.0000000000 0.9423589110 0.4300065435 0.9423589110 0.0344392555 0.1313990000 0.0101740000 0.0508390000 0.0003910000 0.0002830000 0.0586390000 10036482 96830484 1770037248 3.7074420452 3.1138586998 3.5683901310 952 38.0400000000 0.9425142407 0.4305448919 0.9425142407 0.0344225113 0.1251050000 0.0100690000 0.0414550000 0.0000270000 0.0003160000 0.0563470000 10038156 96830484 1768529920 3.7170093060 3.1112251282 3.5658066273 953 38.0800000000 0.9424369931 0.4310820295 0.9425142407 0.0344058057 0.2039770000 0.0079890000 0.0725880000 0.0003790000 0.0002860000 0.0928960000 10039830 96830484 1770172416 3.7270271778 3.1107096672 3.5648708344 954 38.1200000000 0.9428568482 0.4316184811 0.9428568482 0.0343887060 0.1304000000 0.0105190000 0.0440330000 0.0000270000 0.0003830000 0.0539840000 10041504 96830484 1769140224 3.7376217842 3.1096808910 3.5636546612 955 38.1600000000 0.9428369999 0.4321537884 0.9428568482 0.0343727955 0.1307440000 0.0084850000 0.0510080000 0.0003150000 0.0002760000 0.0596020000 10043178 96830484 1770819584 3.7474107742 3.1105849743 3.5615301132 956 38.2000000000 0.9430729151 0.4326882227 0.9430729151 0.0343555564 0.1275500000 0.0104830000 0.0509820000 0.0000270000 0.0003020000 0.0536450000 10044852 96830484 1769775104 3.7583634853 3.1099071503 3.5588891506 957 38.2400000000 0.9433459640 0.4332218253 0.9433459640 0.0343378531 0.1832300000 0.0103380000 0.0493310000 0.0003880000 0.0002710000 0.0931890000 10046526 96830484 1768288256 3.7691018581 3.1092686653 3.5557086468 958 38.2800000000 0.9436194897 0.4337545995 0.9436194897 0.0343201496 0.1304080000 0.0082900000 0.0491180000 0.0000250000 0.0003150000 0.0540620000 10048200 96830484 1769930752 3.7775826454 3.1070477962 3.5523796082 959 38.3200000000 0.9438706636 0.4342865245 0.9438706636 0.0343030144 0.1296730000 0.0106630000 0.0438690000 0.0003200000 0.0003830000 0.0613650000 10049874 96830484 1768378368 3.7886908054 3.1097919941 3.5505936146 960 38.3600000000 0.9439893961 0.4348174650 0.9439893961 0.0342855864 0.1257940000 0.0082440000 0.0424360000 0.0000260000 0.0011130000 0.0548300000 10051548 96830484 1770057728 3.8022580147 3.1136214733 3.5494689941 961 38.4000000000 0.9441381693 0.4353474553 0.9441381693 0.0342730252 0.1743310000 0.0100530000 0.0560690000 0.0003040000 0.0003530000 0.0962580000 10053222 96830484 1768771584 3.8110327721 3.1075270176 3.5500910282 962 38.4400000000 0.9441190362 0.4358763239 0.9441381693 0.0342563036 0.1227030000 0.0084910000 0.0449110000 0.0000260000 0.0003890000 0.0556040000 10054896 96830484 1770422272 3.8208360672 3.1049547195 3.5492529869 963 38.4800000000 0.9442738295 0.4364042548 0.9442738295 0.0342397975 0.1291260000 0.0103190000 0.0459110000 0.0003240000 0.0002720000 0.0611250000 10056570 96830484 1768919040 3.8326778412 3.1027784348 3.5475988388 964 38.5200000000 0.9444000721 0.4369312215 0.9444000721 0.0342233347 0.1255360000 0.0086170000 0.0449520000 0.0000260000 0.0003190000 0.0553970000 10058244 96830484 1770565632 3.8428473473 3.1006376743 3.5474810600 965 38.5600000000 0.9445162416 0.4374572163 0.9445162416 0.0342060163 0.1691760000 0.0101830000 0.0434960000 0.0009400000 0.0003620000 0.1016450000 10059918 96830484 1769537536 3.8534235954 3.0980536938 3.5441267490 966 38.6000000000 0.9446420074 0.4379822523 0.9446420074 0.0341889695 0.1264830000 0.0084150000 0.0453220000 0.0000270000 0.0003150000 0.0564520000 10061592 96830484 1771155456 3.8628940582 3.0957729816 3.5426967144 967 38.6400000000 0.9446892142 0.4385062512 0.9446892142 0.0341731915 0.1293400000 0.0103060000 0.0439400000 0.0003130000 0.0003500000 0.0634130000 10063266 96830484 1769902080 3.8739786148 3.0946414471 3.5420801640 968 38.6800000000 0.9449005127 0.4390293858 0.9449005127 0.0341567326 0.1265730000 0.0104230000 0.0450480000 0.0000250000 0.0003190000 0.0569780000 10064940 96830484 1768144896 3.8836219311 3.0923399925 3.5388772488 969 38.7200000000 0.9448156357 0.4395513530 0.9449005127 0.0341394680 0.1676300000 0.0082800000 0.0446520000 0.0003200000 0.0002770000 0.1012430000 10066614 96830484 1769947136 3.8938992023 3.0922913551 3.5384776592 970 38.7600000000 0.9450725317 0.4400725089 0.9450725317 0.0341222708 0.1271090000 0.0100340000 0.0433090000 0.0000260000 0.0010430000 0.0580370000 10068288 96830484 1768771584 3.9016575813 3.0898473263 3.5346815586 971 38.8000000000 0.9451931119 0.4405927155 0.9451931119 0.0341050279 0.1285260000 0.0080880000 0.0431920000 0.0010460000 0.0002780000 0.0648640000 10069962 96830484 1770549248 3.9122140408 3.0896821022 3.5318942070 972 38.8400000000 0.9451973438 0.4411118561 0.9451973438 0.0340889588 0.1276390000 0.0103400000 0.0470220000 0.0000280000 0.0007200000 0.0582410000 10071636 96830484 1769029632 3.9220786095 3.0894908905 3.5301716328 973 38.8800000000 0.9452486634 0.4416299823 0.9452486634 0.0340761532 0.1833520000 0.0084380000 0.0434330000 0.0010380000 0.0003480000 0.1017380000 10073310 96830484 1770790912 3.9325091839 3.0892932415 3.5291068554 974 38.9200000000 0.9452406764 0.4421470364 0.9452486634 0.0340630008 0.1279540000 0.0106000000 0.0441540000 0.0000250000 0.0003220000 0.0582220000 10074984 96830484 1769775104 3.9406461716 3.0872504711 3.5303637981 975 38.9600000000 0.9451849461 0.4426629727 0.9452486634 0.0340464981 0.1294990000 0.0101320000 0.0447530000 0.0003910000 0.0002830000 0.0626600000 10076658 96830484 1767870464 3.9497470856 3.0855488777 3.5306174755 976 39.0000000000 0.9452119470 0.4431778794 0.9452486634 0.0340294999 0.1255940000 0.0083910000 0.0431540000 0.0000280000 0.0010400000 0.0584010000 10078332 96830484 1769566208 3.9592382908 3.0838062763 3.5302691460 977 39.0400000000 0.9452803135 0.4436918021 0.9452803135 0.0340124423 0.1841140000 0.0099410000 0.0443150000 0.0003240000 0.0003520000 0.1010570000 10080006 96830484 1768124416 3.9696440697 3.0835821629 3.5298051834 978 39.0800000000 0.9451869726 0.4442045783 0.9452803135 0.0339954083 0.1302750000 0.0081910000 0.0448980000 0.0000270000 0.0003910000 0.0590220000 10081680 96830484 1769775104 3.9788851738 3.0820491314 3.5319278240 979 39.1200000000 0.9453550577 0.4447164787 0.9453550577 0.0339815310 0.1303010000 0.0098450000 0.0436070000 0.0010490000 0.0002780000 0.0643990000 10083354 96830484 1768742912 3.9872052670 3.0797569752 3.5295264721 980 39.1600000000 0.9453854561 0.4452273654 0.9453854561 0.0339663551 0.1268920000 0.0082980000 0.0464300000 0.0000270000 0.0003130000 0.0593430000 10085028 96830484 1770328064 3.9985613823 3.0794715881 3.5278439522 981 39.2000000000 0.9452473521 0.4457370698 0.9453854561 0.0339494474 0.1794730000 0.0103670000 0.0435260000 0.0003180000 0.0003530000 0.0990760000 10086702 96830484 1769267200 4.0107221603 3.0808548927 3.5276620388 982 39.2400000000 0.9451600313 0.4462456471 0.9453854561 0.0339324754 0.1333410000 0.0086330000 0.0425350000 0.0000280000 0.0003690000 0.0596590000 10088376 96830484 1771057152 4.0167284012 3.0795967579 3.5287220478 983 39.2800000000 0.9451538324 0.4467531834 0.9453854561 0.0339160884 0.1481310000 0.0103260000 0.0502480000 0.0002910000 0.0003580000 0.0666990000 10090050 96830484 1769807872 4.0264649391 3.0784325600 3.5293374062 984 39.3200000000 0.9450265169 0.4472595588 0.9453854561 0.0338995392 0.1288810000 0.0101640000 0.0421470000 0.0000260000 0.0003540000 0.0609340000 10091724 96830484 1768415232 4.0378532410 3.0785052776 3.5285496712 985 39.3600000000 0.9450372458 0.4477649168 0.9453854561 0.0338826303 0.1855740000 0.0085230000 0.0456840000 0.0003130000 0.0002760000 0.1080360000 10093398 96830484 1770012672 4.0460724831 3.0761346817 3.5283091068 986 39.4000000000 0.9448444843 0.4482690543 0.9453854561 0.0338658969 0.1305490000 0.0102360000 0.0468680000 0.0000300000 0.0003180000 0.0608310000 10095072 96830484 1769013248 4.0539264679 3.0751297474 3.5312063694 987 39.4400000000 0.9448132515 0.4487721386 0.9453854561 0.0338496174 0.1457100000 0.0083960000 0.0494680000 0.0003870000 0.0002900000 0.0672110000 10096746 96830484 1770713088 4.0635323524 3.0740463734 3.5327441692 988 39.4800000000 0.9447513223 0.4492741419 0.9453854561 0.0338330187 0.1295830000 0.0104120000 0.0455240000 0.0000250000 0.0003770000 0.0599990000 10098420 96830484 1769553920 4.0740070343 3.0731930733 3.5331118107 989 39.5200000000 0.9447427988 0.4497751213 0.9453854561 0.0338164420 0.1716720000 0.0100210000 0.0443530000 0.0003790000 0.0002690000 0.1052220000 10100094 96830484 1768034304 4.0829200745 3.0724880695 3.5333807468 990 39.5600000000 0.9446517229 0.4502749966 0.9453854561 0.0337996458 0.1239880000 0.0083150000 0.0424180000 0.0000340000 0.0003160000 0.0604210000 10101768 96830484 1769803776 4.0926628113 3.0728046894 3.5340116024 991 39.6000000000 0.9443738461 0.4507735828 0.9453854561 0.0337827680 0.1450910000 0.0098900000 0.0447700000 0.0003100000 0.0002910000 0.0679620000 10103442 96830484 1768398848 4.1023492813 3.0749866962 3.5374822617 992 39.6400000000 0.9442547560 0.4512710436 0.9453854561 0.0337661106 0.1302470000 0.0083220000 0.0496570000 0.0000260000 0.0003120000 0.0605160000 10105116 96830484 1770045440 4.1120243073 3.0773684978 3.5387179852 993 39.6800000000 0.9439609051 0.4517672066 0.9453854561 0.0337508933 0.1865620000 0.0103440000 0.0497310000 0.0003150000 0.0002770000 0.1088620000 10106790 96830484 1768517632 4.1211671829 3.0797712803 3.5432956219 994 39.7200000000 0.9437645674 0.4522621738 0.9453854561 0.0337359005 0.1296090000 0.0084180000 0.0519030000 0.0000250000 0.0002910000 0.0576650000 10108464 96830484 1770311680 4.1307926178 3.0806753635 3.5455195904 995 39.7600000000 0.9436703920 0.4527560514 0.9453854561 0.0337209151 0.1461890000 0.0103180000 0.0508600000 0.0003650000 0.0002760000 0.0680230000 10110138 96830484 1768792064 4.1391539574 3.0794718266 3.5474970341 996 39.8000000000 0.9435850382 0.4532488516 0.9453854561 0.0337045213 0.1290610000 0.0084780000 0.0490390000 0.0000260000 0.0003870000 0.0595450000 10111812 96830484 1770663936 4.1486029625 3.0785553455 3.5501143932 997 39.8400000000 0.9433541894 0.4537404317 0.9453854561 0.0336881086 0.1718250000 0.0102820000 0.0441510000 0.0001180000 0.0001030000 0.1055710000 10113486 96830484 1769410560 4.1591987610 3.0788097382 3.5521950722 998 39.8800000000 0.9433414340 0.4542310138 0.9453854561 0.0336717872 0.1410400000 0.0088570000 0.0530310000 0.0000310000 0.0006450000 0.0606840000 10115160 96830484 1771028480 4.1683616638 3.0780069828 3.5538694859 999 39.9200000000 0.9430439472 0.4547203161 0.9453854561 0.0336552864 0.1464330000 0.0105870000 0.0454830000 0.0006920000 0.0003110000 0.0676190000 10116834 96830484 1768759296 4.1810112000 3.0824062824 3.5573141575 1000 39.9600000000 0.9429087639 0.4552085045 0.9453854561 0.0336394865 0.1308100000 0.0086040000 0.0506310000 0.0000970000 0.0006500000 0.0590980000 10118508 96830484 1770172416 4.1899094582 3.0818972588 3.5578258038 1001 40.0000000000 0.9429247975 0.4556957336 0.9453854561 0.0336227773 0.1847740000 0.0105040000 0.0452900000 0.0003840000 0.0002860000 0.1082610000 10120182 96830484 1768124416 4.1990523338 3.0807147026 3.5589375496 1002 40.0400000000 0.9426673651 0.4561817332 0.9453854561 0.0336062432 0.1304850000 0.0086200000 0.0520490000 0.0000290000 0.0003080000 0.0577410000 10121856 96830484 1769775104 4.2095928192 3.0820872784 3.5618855953 1003 40.0800000000 0.9423675537 0.4566664648 0.9453854561 0.0335897283 0.1458320000 0.0108260000 0.0513990000 0.0003100000 0.0002790000 0.0673600000 10123530 96830484 1767395328 4.2209162712 3.0845072269 3.5638551712 1004 40.1200000000 0.9415736198 0.4571494401 0.9453854561 0.0335744792 0.1301920000 0.0085350000 0.0510990000 0.0000260000 0.0003130000 0.0584270000 10125204 96830484 1769123840 4.2296633720 3.0837121010 3.5651154518 1005 40.1600000000 0.9411249757 0.4576310078 0.9453854561 0.0335579164 0.1831910000 0.0084750000 0.0432710000 0.0011110000 0.0003720000 0.1036350000 10126878 96830484 1770692608 4.2390804291 3.0840275288 3.5662009716 1006 40.2000000000 0.9400972128 0.4581105965 0.9453854561 0.0335413360 0.1306910000 0.0100840000 0.0519760000 0.0000270000 0.0003820000 0.0563500000 10128552 96830484 1769648128 4.2493238449 3.0865263939 3.5687325001 1007 40.2400000000 0.9395916462 0.4585887306 0.9453854561 0.0335251594 0.1652290000 0.0083580000 0.0787740000 0.0003170000 0.0003490000 0.0656390000 10130226 96830484 1771282432 4.2590661049 3.0881476402 3.5720603466 1008 40.2800000000 0.9390669465 0.4590653955 0.9453854561 0.0335092342 0.1667730000 0.0100750000 0.0827500000 0.0000070000 0.0000590000 0.0600700000 10131900 96830484 1770409984 4.2670102119 3.0878670216 3.5745828152 1009 40.3200000000 0.9386889338 0.4595407409 0.9453854561 0.0334928819 0.1847940000 0.0104750000 0.0444710000 0.0003200000 0.0002800000 0.1066920000 10133574 96830484 1768394752 4.2754821777 3.0884449482 3.5777249336 1010 40.3600000000 0.9378151298 0.4600142799 0.9453854561 0.0334765691 0.1696670000 0.0088420000 0.0873570000 0.0000270000 0.0003150000 0.0591810000 10135248 96830484 1770156032 4.2853522301 3.0892202854 3.5798277855 1011 40.4000000000 0.9382770061 0.4604873390 0.9453854561 0.0334605797 0.1463580000 0.0100460000 0.0499500000 0.0003900000 0.0002830000 0.0667560000 10136922 96830484 1769267200 4.2931585312 3.0885798931 3.5826842785 1012 40.4400000000 0.9381105900 0.4609592987 0.9453854561 0.0334443905 0.1298590000 0.0084570000 0.0511170000 0.0000280000 0.0003200000 0.0581080000 10138596 96830484 1770934272 4.3010163307 3.0870132446 3.5837285519 1013 40.4800000000 0.9378440976 0.4614300636 0.9453854561 0.0334285313 0.1897130000 0.0102830000 0.0639850000 0.0003050000 0.0005180000 0.1027460000 10140270 96830484 1769902080 4.3099880219 3.0879294872 3.5884001255 1014 40.5200000000 0.9383289218 0.4619003780 0.9453854561 0.0334123378 0.1449180000 0.0106370000 0.0648020000 0.0000280000 0.0003130000 0.0574070000 10141944 96830484 1767870464 4.3170742989 3.0882558823 3.5930290222 1015 40.5600000000 0.9381419420 0.4623695815 0.9453854561 0.0333968541 0.1449720000 0.0085930000 0.0498140000 0.0004010000 0.0002910000 0.0666220000 10143618 96830484 1769664512 4.3250193596 3.0868203640 3.5937187672 1016 40.6000000000 0.9373736382 0.4628371052 0.9453854561 0.0333812033 0.1454850000 0.0096690000 0.0564110000 0.0000260000 0.0007930000 0.0593090000 10145292 96830484 1768742912 4.3324060440 3.0845928192 3.5936925411 1017 40.6400000000 0.9367913008 0.4633031369 0.9453854561 0.0333659608 0.2089970000 0.0085060000 0.0828310000 0.0002890000 0.0002760000 0.1049500000 10146966 96830484 1770528768 4.3393969536 3.0853376389 3.5971577168 1018 40.6800000000 0.9362553358 0.4637677264 0.9453854561 0.0333498688 0.1484300000 0.0105610000 0.0691330000 0.0000240000 0.0002850000 0.0566980000 10148640 96830484 1769385984 4.3478817940 3.0855031013 3.5997831821 1019 40.7200000000 0.9353559017 0.4642305215 0.9453854561 0.0333336371 0.1680640000 0.0082410000 0.0821070000 0.0003520000 0.0002720000 0.0650120000 10150314 96830484 1771180032 4.3547053337 3.0861494541 3.6029405594 1020 40.7600000000 0.9329506755 0.4646900511 0.9453854561 0.0333178361 0.1651210000 0.0101560000 0.0758260000 0.0000370000 0.0003110000 0.0582260000 10151988 96830484 1770274816 4.3634810448 3.0863182545 3.6031153202 1021 40.8000000000 0.9322471619 0.4651479914 0.9453854561 0.0333015800 0.1825620000 0.0100430000 0.0570120000 0.0003660000 0.0002790000 0.1007700000 10153662 96830484 1768480768 4.3715586662 3.0870761871 3.6068146229 1022 40.8400000000 0.9311265945 0.4656039392 0.9453854561 0.0332854606 0.1276930000 0.0092630000 0.0434460000 0.0000300000 0.0010480000 0.0580060000 10155336 96830484 1770303488 4.3788437843 3.0881986618 3.6114518642 1023 40.8800000000 0.9321221709 0.4660599687 0.9453854561 0.0332694252 0.1692390000 0.0099520000 0.0828270000 0.0002910000 0.0002730000 0.0640840000 10157010 96830484 1769385984 4.3859305382 3.0890491009 3.6193404198 1024 40.9200000000 0.9301266074 0.4665131588 0.9453854561 0.0332543186 0.1478970000 0.0088590000 0.0692950000 0.0000060000 0.0000620000 0.0578420000 10158684 96830484 1770942464 4.3951640129 3.0898170471 3.6203351021 1025 40.9600000000 0.9302573204 0.4669655922 0.9453854561 0.0332383416 0.2028740000 0.0100900000 0.0629120000 0.0002880000 0.0005730000 0.1000850000 10245598 96830484 1770274816 4.4046735764 3.0909709930 3.6271417141 1026 41.0000000000 0.9296177030 0.4674165201 0.9453854561 0.0332226582 0.1312400000 0.0103680000 0.0500790000 0.0000300000 0.0003170000 0.0576350000 10411888 96830484 1768497152 4.4106855392 3.0909297466 3.6318755150 1027 41.0400000000 0.9293139577 0.4678662742 0.9453854561 0.0332069253 0.1483620000 0.0085100000 0.0622410000 0.0003020000 0.0003630000 0.0649320000 10413562 96830484 1770147840 4.4189434052 3.0896310806 3.6333227158 1028 41.0800000000 0.9286948442 0.4683145510 0.9453854561 0.0331911579 0.1647290000 0.0100800000 0.0761220000 0.0000280000 0.0003780000 0.0574730000 10415236 96830484 1768767488 4.4298834801 3.0920236111 3.6402819157 1029 41.1200000000 0.9288183451 0.4687620766 0.9453854561 0.0331752582 0.1854400000 0.0082140000 0.0495880000 0.0003140000 0.0005210000 0.0991980000 10416910 96830484 1770434560 4.4384217262 3.0920541286 3.6432931423 1030 41.1600000000 0.9283460379 0.4692082746 0.9453854561 0.0331596140 0.1502220000 0.0102640000 0.0625280000 0.0000300000 0.0002930000 0.0577520000 10418584 96830484 1769021440 4.4464507103 3.0918471813 3.6461248398 1031 41.2000000000 0.9280278087 0.4696532984 0.9453854561 0.0331445417 0.1489720000 0.0083120000 0.0611620000 0.0003010000 0.0002800000 0.0641080000 10420258 96830484 1770688512 4.4552688599 3.0913505554 3.6508107185 1032 41.2400000000 0.9277309179 0.4700971721 0.9453854561 0.0331294078 0.1273480000 0.0099670000 0.0414710000 0.0000110000 0.0001180000 0.0597430000 10421932 96830484 1769656320 4.4638147354 3.0916583538 3.6556639671 1033 41.2800000000 0.9276520610 0.4705401100 0.9453854561 0.0331144447 0.2066090000 0.0095320000 0.0674550000 0.0003140000 0.0003690000 0.1085730000 10423606 96830484 1767481344 4.4736738205 3.0932891369 3.6619091034 1034 41.3200000000 0.9271090627 0.4709816661 0.9453854561 0.0331003261 0.1473080000 0.0083540000 0.0607910000 0.0000280000 0.0003830000 0.0563960000 10425280 96830484 1769259008 4.4837331772 3.0938904285 3.6666679382 1035 41.3600000000 0.9269185662 0.4714221848 0.9453854561 0.0330873887 0.1438670000 0.0080910000 0.0491920000 0.0004050000 0.0002850000 0.0631790000 10426954 96830484 1770921984 4.4898142815 3.0942959785 3.6707985401 1036 41.4000000000 0.9265135527 0.4718614622 0.9453854561 0.0330718726 0.1290370000 0.0098690000 0.0411560000 0.0000230000 0.0003520000 0.0591590000 10428628 96830484 1769910272 4.4962196350 3.0919749737 3.6733515263 1037 41.4400000000 0.9265106320 0.4722998895 0.9453854561 0.0330568686 0.2045050000 0.0102150000 0.0616470000 0.0002850000 0.0002680000 0.1019350000 10430302 96830484 1768128512 4.5057497025 3.0913918018 3.6772706509 1038 41.4800000000 0.9260551333 0.4727370333 0.9453854561 0.0330415801 0.1290250000 0.0081870000 0.0417930000 0.0000270000 0.0002880000 0.0554870000 10431976 96830484 1769910272 4.5150442123 3.0934338570 3.6824653149 1039 41.5200000000 0.9258354306 0.4731731242 0.9453854561 0.0330258670 0.1314450000 0.0097290000 0.0482310000 0.0003100000 0.0005370000 0.0604440000 10433650 96830484 1768751104 4.5242547989 3.0952594280 3.6866950989 1040 41.5600000000 0.9254539609 0.4736080096 0.9453854561 0.0330100446 0.1261210000 0.0080070000 0.0480060000 0.0000270000 0.0003230000 0.0548920000 10435324 96830484 1770418176 4.5316324234 3.0982954502 3.6913185120 1041 41.6000000000 0.9254114628 0.4740420187 0.9453854561 0.0329942380 0.1837480000 0.0097630000 0.0487370000 0.0003140000 0.0003610000 0.0944720000 10436998 96830484 1769402368 4.5390009880 3.0982923508 3.6926665306 1042 41.6400000000 0.9250365496 0.4744748349 0.9453854561 0.0329788741 0.1295560000 0.0081470000 0.0408580000 0.0000240000 0.0002910000 0.0573480000 10438672 96830484 1771036672 4.5490794182 3.1005640030 3.6985394955 1043 41.6800000000 0.9246047139 0.4749064072 0.9453854561 0.0329664104 0.1680180000 0.0103060000 0.0622540000 0.0002890000 0.0003410000 0.0724710000 10440346 96830484 1769910272 4.5552330017 3.1021938324 3.7032775879 1044 41.7200000000 0.9243443012 0.4753369033 0.9453854561 0.0329629499 0.1495890000 0.0103250000 0.0629870000 0.0000260000 0.0002910000 0.0605640000 10442020 96830484 1768153088 4.5688767433 3.1028130054 3.7079348564 1045 41.7600000000 0.9240784645 0.4757663210 0.9453854561 0.0329509298 0.2258220000 0.0075330000 0.0900700000 0.0002920000 0.0002690000 0.1103130000 10443694 96830484 1769766912 4.5761194229 3.1032798290 3.7116661072 1046 41.8000000000 0.9235538840 0.4761944162 0.9453854561 0.0329368601 0.1243990000 0.0098000000 0.0405700000 0.0000270000 0.0002850000 0.0565890000 10445368 96830484 1768779776 4.5814728737 3.1050198078 3.7181482315 1047 41.8400000000 0.9234551787 0.4766215994 0.9453854561 0.0329212031 0.1514100000 0.0076510000 0.0579060000 0.0003330000 0.0002810000 0.0729840000 10447042 96830484 1770446848 4.5882587433 3.1048858166 3.7206385136 1048 41.8800000000 0.9230579138 0.4770475882 0.9453854561 0.0329056436 0.1448990000 0.0095960000 0.0506670000 0.0000250000 0.0003600000 0.0712720000 10448716 96830484 1769148416 4.5962576866 3.1059665680 3.7268395424 1049 41.9200000000 0.9227262139 0.4774724487 0.9453854561 0.0328901672 0.2265620000 0.0078370000 0.0763330000 0.0000660000 0.0000570000 0.1253060000 10450390 96830484 1770831872 4.6033720970 3.1064786911 3.7308874130 1050 41.9600000000 0.9224275947 0.4778962155 0.9453854561 0.0328745734 0.1283850000 0.0100930000 0.0517080000 0.0000230000 0.0002880000 0.0525650000 10452064 96830484 1769402368 4.6093473434 3.1071407795 3.7334737778 1051 42.0000000000 0.9222768545 0.4783190324 0.9453854561 0.0328589737 0.1267090000 0.0083100000 0.0395180000 0.0002920000 0.0003470000 0.0619320000 10453738 96830484 1771020288 4.6167879105 3.1060745716 3.7364468575 1052 42.0400000000 0.9216230512 0.4787404241 0.9453854561 0.0328433906 0.1488220000 0.0096530000 0.0682150000 0.0000070000 0.0000620000 0.0586930000 10455412 96830484 1769656320 4.6233339310 3.1078085899 3.7416701317 1053 42.0800000000 0.9210592508 0.4791604800 0.9453854561 0.0328279307 0.2027490000 0.0093370000 0.0647890000 0.0006030000 0.0005420000 0.0973210000 10457086 96830484 1767878656 4.6292853355 3.1095325947 3.7445988655 1054 42.1200000000 0.9204450250 0.4795791560 0.9453854561 0.0328123916 0.1131220000 0.0081000000 0.0396460000 0.0000260000 0.0002940000 0.0525910000 10458760 96830484 1769521152 4.6356592178 3.1101672649 3.7489876747 1055 42.1600000000 0.9197572470 0.4799963864 0.9453854561 0.0327976610 0.1662560000 0.0089660000 0.0817700000 0.0000610000 0.0000550000 0.0612910000 10460434 96830484 1768534016 4.6474413872 3.1107869148 3.7561395168 1056 42.2000000000 0.9193361402 0.4804124279 0.9453854561 0.0327825443 0.1669430000 0.0072750000 0.0829880000 0.0000260000 0.0002910000 0.0622600000 10462108 96830484 1770147840 4.6538925171 3.1110794544 3.7604732513 1057 42.2400000000 0.9189897180 0.4808273543 0.9453854561 0.0327671802 0.1719840000 0.0097770000 0.0596130000 0.0003920000 0.0002830000 0.0896010000 10463782 96830484 1768751104 4.6599111557 3.1119263172 3.7660732269 1058 42.2800000000 0.9183745384 0.4812409150 0.9453854561 0.0327517701 0.1224640000 0.0080680000 0.0473820000 0.0000270000 0.0003900000 0.0509060000 10465456 96830484 1770557440 4.6661324501 3.1137194633 3.7731332779 1059 42.3200000000 0.9179906845 0.4816533322 0.9453854561 0.0327364311 0.1295980000 0.0102130000 0.0522530000 0.0002900000 0.0003430000 0.0541830000 10467130 96830484 1769402368 4.6703343391 3.1162555218 3.7774798870 1060 42.3600000000 0.9174543023 0.4820644652 0.9453854561 0.0327212040 0.1246410000 0.0080350000 0.0461170000 0.0000330000 0.0003120000 0.0501260000 10468804 96830484 1771175936 4.6750330925 3.1176881790 3.7828071117 1061 42.4000000000 0.9171332717 0.4824745206 0.9453854561 0.0327058221 0.1846560000 0.0099150000 0.0523140000 0.0002950000 0.0002730000 0.0897160000 10470478 96830484 1769910272 4.6801214218 3.1190965176 3.7878196239 1062 42.4400000000 0.9165742397 0.4828832774 0.9453854561 0.0326906333 0.1298460000 0.0104170000 0.0461860000 0.0000240000 0.0003850000 0.0505090000 10472152 96830484 1768656896 4.6850037575 3.1208746433 3.7939436436 1063 42.4800000000 0.9161866903 0.4832909005 0.9453854561 0.0326761317 0.1278400000 0.0082800000 0.0383200000 0.0002860000 0.0002650000 0.0601280000 10473826 96830484 1770258432 4.6904783249 3.1221370697 3.7998151779 1064 42.5200000000 0.9157654047 0.4836973615 0.9453854561 0.0326619134 0.1302120000 0.0099150000 0.0583750000 0.0000280000 0.0002830000 0.0490610000 10475500 96830484 1769148416 4.6953916550 3.1229302883 3.8051106930 1065 42.5600000000 0.9154229760 0.4841027377 0.9453854561 0.0326470434 0.1650820000 0.0082390000 0.0446590000 0.0003190000 0.0002840000 0.0900310000 10477174 96830484 1770811392 4.6994695663 3.1242585182 3.8099815845 1066 42.6000000000 0.9149937034 0.4845069506 0.9453854561 0.0326319106 0.1259980000 0.0099930000 0.0526410000 0.0000270000 0.0003200000 0.0493510000 10478848 96830484 1769402368 4.7039203644 3.1261811256 3.8156964779 1067 42.6400000000 0.9062500596 0.4849022113 0.9453854561 0.0327051060 0.1488030000 0.0081430000 0.0742930000 0.0002860000 0.0003450000 0.0530260000 10480522 96830484 1771212800 4.7112612724 3.1018376350 3.7636156082 1068 42.6800000000 0.9037722945 0.4852944117 0.9453854561 0.0326901141 0.1260700000 0.0102910000 0.0525710000 0.0000230000 0.0002880000 0.0494820000 10482196 96830484 1769656320 4.7153120041 3.1039080620 3.7648339272 1069 42.7200000000 0.9032963514 0.4856854332 0.9453854561 0.0326757430 0.1676320000 0.0100850000 0.0575610000 0.0002920000 0.0003490000 0.0866670000 10483870 96830484 1768005632 4.7227878571 3.1058602333 3.7688167095 1070 42.7600000000 0.9014052749 0.4860739564 0.9453854561 0.0326642581 0.1261460000 0.0083070000 0.0508160000 0.0000250000 0.0002910000 0.0488690000 10485544 96830484 1769623552 4.7292356491 3.1091926098 3.7699570656 1071 42.8000000000 0.9018811584 0.4864621984 0.9453854561 0.0326527921 0.1291190000 0.0095700000 0.0502600000 0.0002940000 0.0003440000 0.0555240000 10487218 96830484 1768644608 4.7349858284 3.1098542213 3.7762670517 1072 42.8400000000 0.9001776576 0.4868481270 0.9453854561 0.0326379537 0.1257600000 0.0081630000 0.0508380000 0.0000270000 0.0006460000 0.0488220000 10488892 96830484 1770274816 4.7409358025 3.1116106510 3.7775902748 1073 42.8800000000 0.9000577331 0.4872332245 0.9453854561 0.0326235054 0.1721530000 0.0100690000 0.0623890000 0.0003040000 0.0002750000 0.0864130000 10490566 96830484 1768894464 4.7436923981 3.1122317314 3.7839839458 1074 42.9200000000 0.8989499807 0.4876165734 0.9453854561 0.0326087339 0.1250190000 0.0080350000 0.0569410000 0.0003460000 0.0003920000 0.0467360000 10492240 96830484 1770684416 4.7502079010 3.1143591404 3.7877352238 1075 42.9600000000 0.8988811374 0.4879991451 0.9453854561 0.0325940493 0.1288430000 0.0102570000 0.0529590000 0.0003700000 0.0002860000 0.0522930000 10493914 96830484 1769148416 4.7542505264 3.1163568497 3.7947387695 1076 43.0000000000 0.8983895183 0.4883805488 0.9453854561 0.0325799851 0.1093260000 0.0085360000 0.0456020000 0.0000300000 0.0003190000 0.0421210000 10495588 96830484 1770811392 4.7589416504 3.1186931133 3.7978017330 1077 43.0400000000 0.8986188173 0.4887614571 0.9453854561 0.0325659606 0.1678400000 0.0098630000 0.0577150000 0.0003050000 0.0002810000 0.0869620000 10497262 96830484 1769766912 4.7655539513 3.1198360920 3.8024456501 1078 43.0800000000 0.8984555602 0.4891415073 0.9453854561 0.0325520865 0.1212000000 0.0101120000 0.0373830000 0.0000080000 0.0000820000 0.0515000000 10498936 96830484 1768005632 4.7691435814 3.1207027435 3.8055088520 1079 43.1200000000 0.8980190754 0.4895204485 0.9453854561 0.0325376336 0.1483240000 0.0083400000 0.0581540000 0.0003010000 0.0003570000 0.0622850000 10500610 96830484 1769648128 4.7736048698 3.1226089001 3.8101830482 1080 43.1600000000 0.8968948126 0.4898976470 0.9453854561 0.0325227100 0.1317990000 0.0096330000 0.0586020000 0.0000270000 0.0003660000 0.0504270000 10502284 96830484 1768644608 4.7793960571 3.1252267361 3.8179941177 1081 43.2000000000 0.8966948390 0.4902739626 0.9453854561 0.0325081083 0.1796250000 0.0073910000 0.0548350000 0.0004000000 0.0007430000 0.1006350000 10503958 96830484 1770274816 4.7836384773 3.1259531975 3.8249037266 1082 43.2400000000 0.8960230350 0.4906489618 0.9453854561 0.0324933554 0.1266710000 0.0125020000 0.0387540000 0.0000100000 0.0001190000 0.0507870000 10505632 96830484 1769148416 4.7865099907 3.1285014153 3.8310158253 1083 43.2800000000 0.8955517411 0.4910228332 0.9453854561 0.0324783959 0.1503030000 0.0084250000 0.0603860000 0.0003810000 0.0002780000 0.0648120000 10507306 96830484 1770766336 4.7920103073 3.1301488876 3.8406805992 1084 43.3200000000 0.8955084682 0.4913959750 0.9453854561 0.0324635829 0.1469270000 0.0095070000 0.0649650000 0.0000310000 0.0003160000 0.0540530000 10508980 96830484 1769783296 4.7979092598 3.1312079430 3.8495330811 1085 43.3600000000 0.8957743049 0.4917686739 0.9453854561 0.0324495881 0.2064720000 0.0095480000 0.0669150000 0.0003190000 0.0004870000 0.1069490000 10510654 96830484 1768005632 4.8015289307 3.1340012550 3.8551781178 1086 43.4000000000 0.8953775167 0.4921403211 0.9453854561 0.0324347004 0.1114080000 0.0081170000 0.0447100000 0.0000280000 0.0011670000 0.0447240000 10512328 96830484 1769648128 4.8059611320 3.1358757019 3.8613281250 1087 43.4400000000 0.8950991035 0.4925110283 0.9453854561 0.0324197697 0.1256580000 0.0099840000 0.0449530000 0.0003980000 0.0002820000 0.0546380000 10514002 96830484 1768493056 4.8099021912 3.1377501488 3.8696570396 1088 43.4800000000 0.8949555159 0.4928809222 0.9453854561 0.0324051291 0.1081630000 0.0080250000 0.0377660000 0.0000330000 0.0003840000 0.0493030000 10515676 96830484 1770303488 4.8128943443 3.1387577057 3.8755979538 1089 43.5200000000 0.8946738243 0.4932498780 0.9453854561 0.0323903128 0.1861620000 0.0095180000 0.0512600000 0.0003230000 0.0003530000 0.1064670000 10517350 96830484 1768878080 4.8173694611 3.1398608685 3.8825914860 1090 43.5600000000 0.8942067623 0.4936177283 0.9453854561 0.0323754653 0.1099500000 0.0082010000 0.0440790000 0.0000270000 0.0005600000 0.0439740000 10519024 96830484 1770557440 4.8220143318 3.1420280933 3.8917703629 1091 43.6000000000 0.8941727877 0.4939848732 0.9453854561 0.0323611118 0.1438630000 0.0100470000 0.0560010000 0.0003890000 0.0002830000 0.0540820000 10520698 96830484 1769148416 4.8266758919 3.1434607506 3.9002134800 1092 43.6400000000 0.8939929605 0.4943511810 0.9453854561 0.0323466027 0.1272360000 0.0081820000 0.0493650000 0.0000280000 0.0003940000 0.0470140000 10522372 96830484 1770958848 4.8298263550 3.1461288929 3.9074957371 1093 43.6800000000 0.8940526843 0.4947168731 0.9453854561 0.0323326043 0.1684260000 0.0101120000 0.0506760000 0.0003900000 0.0002860000 0.0871130000 10524046 96830484 1769529344 4.8337130547 3.1478152275 3.9169197083 1094 43.7200000000 0.8939187527 0.4950817743 0.9453854561 0.0323183891 0.1265200000 0.0082330000 0.0486900000 0.0000300000 0.0003890000 0.0464110000 10525720 96830484 1771212800 4.8352746964 3.1506364346 3.9241898060 1095 43.7600000000 0.8938130140 0.4954459124 0.9453854561 0.0323038750 0.1284830000 0.0102040000 0.0438290000 0.0003950000 0.0002800000 0.0536080000 10527394 96830484 1769783296 4.8355512619 3.1521234512 3.9306356907 1096 43.8000000000 0.8935223818 0.4958091209 0.9453854561 0.0322892197 0.1103800000 0.0099240000 0.0428800000 0.0000330000 0.0010590000 0.0435450000 10529068 96830484 1767972864 4.8379645348 3.1545026302 3.9382872581 1097 43.8400000000 0.8931415677 0.4961713200 0.9453854561 0.0322747062 0.1681050000 0.0085260000 0.0629220000 0.0003690000 0.0002740000 0.0830530000 10530742 96830484 1769648128 4.8404374123 3.1572103500 3.9487717152 1098 43.8800000000 0.8933177590 0.4965330199 0.9453854561 0.0322628426 0.1450640000 0.0096240000 0.0730980000 0.0000300000 0.0003730000 0.0453500000 10532416 96830484 1768644608 4.8434453011 3.1585526466 3.9602680206 1099 43.9200000000 0.8937779665 0.4968944802 0.9453854561 0.0322503685 0.1454280000 0.0079690000 0.0729480000 0.0003040000 0.0003500000 0.0508140000 10534090 96830484 1770385408 4.8439121246 3.1605165005 3.9680123329 1100 43.9600000000 0.8933381438 0.4972548836 0.9453854561 0.0322359939 0.1453640000 0.0099710000 0.0712920000 0.0000320000 0.0003880000 0.0455190000 10535764 96830484 1769148416 4.8447418213 3.1637163162 3.9760007858 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 03:27:34 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188253 0.0606188253 0.0606188253 nan 0.1444140000 0.0394290000 0.0186040000 0.0004280000 0.0000480000 0.0730690000 8213518 96830484 1770606592 4.0000000000 4.0000000000 4.0000000000 2 1305031229.5644419193 0.0642096773 0.0624142513 0.0642096773 0.1658526063 0.0518190000 0.0148390000 0.0151840000 0.0003150000 0.0000220000 0.0199600000 8871336 96830484 1769353216 4.0000000000 4.0000000000 4.0000000000 3 1305031229.5966169834 0.0662607327 0.0636964117 0.0662607327 0.1252030593 0.0487240000 0.0132280000 0.0108580000 0.0000700000 0.0000040000 0.0204330000 8873846 96830484 1768226816 4.0000000000 4.0000000000 4.0000000000 4 1305031229.6287899017 0.0688454211 0.0649836641 0.0688454211 0.1129914361 0.0947770000 0.0220740000 0.0150060000 0.0002070000 0.0002850000 0.0565540000 8876348 96830484 1766682624 4.0000000000 4.0000000000 4.0000000000 5 1305031229.6646571159 0.0660073161 0.0651883945 0.0688454211 0.1146815906 0.1536550000 0.0085930000 0.0706300000 0.0003640000 0.0002690000 0.0721660000 8878886 96830484 1766576128 3.9731338024 4.0052871704 4.0138797760 6 1305031229.6968429089 0.0563749559 0.0637194881 0.0688454211 0.1026607419 0.1138000000 0.0092530000 0.0638570000 0.0000250000 0.0004110000 0.0398110000 8881760 96830484 1768091648 3.9885642529 3.9999618530 4.0209727287 7 1305031229.7290771008 0.0504670925 0.0618262887 0.0688454211 0.0944304650 0.1080220000 0.0090750000 0.0604310000 0.0003070000 0.0002650000 0.0375000000 8883914 96830484 1769844736 3.9916899204 4.0025506020 4.0272154808 8 1305031229.7648689747 0.0483920984 0.0601470149 0.0688454211 0.0875827377 0.1092240000 0.0108430000 0.0667440000 0.0000220000 0.0003720000 0.0307890000 8886164 96830484 1768882176 3.9982411861 3.9968731403 4.0331044197 9 1305031229.7969229221 0.0486251563 0.0588668084 0.0688454211 0.0820227982 0.1370010000 0.0094070000 0.0661860000 0.0004010000 0.0002700000 0.0582050000 8888990 96830484 1770508288 3.9983160496 3.9944117069 4.0363583565 10 1305031229.8256299496 0.0431816503 0.0572982926 0.0688454211 0.0773861567 0.0906670000 0.0111440000 0.0453450000 0.0000250000 0.0003740000 0.0318990000 8892424 96830484 1769353216 4.0013742447 3.9980475903 4.0419926643 11 1305031229.8630619049 0.0423634015 0.0559405752 0.0688454211 0.0737720180 0.1153300000 0.0096120000 0.0672910000 0.0003200000 0.0002710000 0.0358820000 8894738 96830484 1768210432 4.0051417351 3.9986724854 4.0450448990 12 1305031229.8969380856 0.0430381075 0.0548653696 0.0688454211 0.0708035267 0.0837500000 0.0095960000 0.0412380000 0.0000250000 0.0005250000 0.0304330000 8896924 96830484 1769910272 4.0110988617 4.0005612373 4.0481553078 13 1305031229.9262549877 0.0435138233 0.0539921737 0.0688454211 0.0678469189 0.1374950000 0.0111150000 0.0671020000 0.0003410000 0.0003560000 0.0565460000 8899078 96830484 1768738816 4.0164823532 4.0023322105 4.0533270836 14 1305031229.9662408829 0.0455033407 0.0533858285 0.0688454211 0.0652225772 0.1080790000 0.0093040000 0.0642310000 0.0000250000 0.0003070000 0.0319530000 8901392 96830484 1770508288 4.0199174881 4.0032386780 4.0584087372 15 1305031229.9979310036 0.0476685464 0.0530046764 0.0688454211 0.0632056490 0.1186070000 0.0116240000 0.0673500000 0.0002980000 0.0002700000 0.0369490000 8903546 96830484 1769336832 4.0225658417 4.0031871796 4.0627064705 16 1305031230.0300021172 0.0504597835 0.0528456206 0.0688454211 0.0611077333 0.0977560000 0.0096590000 0.0539030000 0.0000300000 0.0003900000 0.0316090000 8905732 96830484 1771053056 4.0251278877 4.0037612915 4.0669584274 17 1305031230.0656960011 0.0551199540 0.0529794049 0.0688454211 0.0592776110 0.1306490000 0.0110810000 0.0686360000 0.0003880000 0.0002730000 0.0497420000 8909262 96830484 1770135552 4.0273513794 4.0023422241 4.0701670647 18 1305031230.0982739925 0.0569276884 0.0531987540 0.0688454211 0.0575944833 0.0982150000 0.0109920000 0.0530660000 0.0000250000 0.0003340000 0.0312470000 8914072 96830484 1768718336 4.0271396637 4.0022411346 4.0725073814 19 1305031230.1299350262 0.0593218468 0.0535210220 0.0688454211 0.0559890913 0.1011570000 0.0095410000 0.0526740000 0.0002920000 0.0003480000 0.0360430000 8916258 96830484 1770377216 4.0277972221 4.0029826164 4.0755438805 20 1305031230.1657800674 0.0627599806 0.0539829699 0.0688454211 0.0545648167 0.0914060000 0.0115560000 0.0474670000 0.0000270000 0.0003060000 0.0305120000 8918508 96830484 1769627648 4.0275964737 4.0022168159 4.0777478218 21 1305031230.1977820396 0.0652241409 0.0545182638 0.0688454211 0.0532382598 0.1208580000 0.0100510000 0.0531890000 0.0003880000 0.0003050000 0.0562940000 8920694 96830484 1768751104 4.0271196365 4.0007619858 4.0796465874 22 1305031230.2298529148 0.0667081550 0.0550723498 0.0688454211 0.0520138371 0.1185340000 0.0092480000 0.0748980000 0.0000050000 0.0000630000 0.0319300000 8922880 96830484 1768259584 4.0253829956 4.0003824234 4.0810613632 23 1305031230.2655899525 0.0662120730 0.0555566855 0.0688454211 0.0508994034 0.1130230000 0.0094690000 0.0551860000 0.0003430000 0.0003550000 0.0465430000 8925130 96830484 1767116800 4.0204772949 3.9986872673 4.0808091164 24 1305031230.2979929447 0.0668463558 0.0560270885 0.0688454211 0.0497932229 0.1162780000 0.0089830000 0.0699870000 0.0000260000 0.0003250000 0.0342800000 8927316 96830484 1765945344 4.0180387497 3.9990363121 4.0823507309 25 1305031230.3351120949 0.0694327503 0.0565633149 0.0694327503 0.0487910797 0.1445780000 0.0088730000 0.0754210000 0.0003220000 0.0003790000 0.0588950000 8929598 96830484 1767559168 4.0161185265 3.9961929321 4.0838260651 26 1305031230.3656799793 0.0676493123 0.0569896995 0.0694327503 0.0478322560 0.1156100000 0.0088050000 0.0709130000 0.0000260000 0.0004020000 0.0339360000 8931752 96830484 1769336832 4.0118756294 3.9971506596 4.0843830109 27 1305031230.3973290920 0.0665875822 0.0573451766 0.0694327503 0.0469064922 0.1238600000 0.0112050000 0.0679390000 0.0003080000 0.0003100000 0.0413910000 8933970 96830484 1768210432 4.0073175430 3.9960575104 4.0856986046 28 1305031230.4368140697 0.0694544986 0.0577776524 0.0694544986 0.0465467344 0.1079060000 0.0101290000 0.0586880000 0.0000270000 0.0003350000 0.0359510000 8936252 96830484 1769844736 4.0057015419 3.9953191280 4.0883927345 29 1305031230.4653120041 0.0681370199 0.0581348720 0.0694544986 0.0458255831 0.1322860000 0.0113310000 0.0569040000 0.0005290000 0.0003270000 0.0625260000 8938374 96830484 1768718336 3.9981250763 3.9910550117 4.0865283012 30 1305031230.4972999096 0.0647407025 0.0583550663 0.0694544986 0.0450842452 0.0988340000 0.0089910000 0.0454830000 0.0000280000 0.0003060000 0.0411850000 8940592 96830484 1770479616 3.9881329536 3.9884817600 4.0833086967 31 1305031230.5301918983 0.0633595735 0.0585165020 0.0694544986 0.0443651508 0.1440070000 0.0111090000 0.0791970000 0.0003030000 0.0002740000 0.0502080000 8942746 96830484 1769099264 3.9796788692 3.9849009514 4.0810785294 32 1305031230.5661149025 0.0642074943 0.0586943455 0.0694544986 0.0440624153 0.1479550000 0.0094680000 0.0869640000 0.0000260000 0.0003790000 0.0482010000 8945028 96830484 1770782720 3.9728610516 3.9823868275 4.0816364288 33 1305031230.5988430977 0.0621162616 0.0587980400 0.0694544986 0.0434076986 0.1813850000 0.0107700000 0.0825690000 0.0003440000 0.0019290000 0.0825860000 8949774 96830484 1769734144 3.9617786407 3.9789960384 4.0784735680 34 1305031230.6319139004 0.0611318946 0.0588666827 0.0694544986 0.0428888847 0.1174320000 0.0111110000 0.0570150000 0.0000260000 0.0003020000 0.0458660000 8957240 96830484 1768210432 3.9484906197 3.9739117622 4.0775556564 35 1305031230.6660470963 0.0576737560 0.0588325991 0.0694544986 0.0423847710 0.1106230000 0.0094430000 0.0444040000 0.0003140000 0.0002710000 0.0531210000 8959458 96830484 1769906176 3.9352512360 3.9746530056 4.0740189552 36 1305031230.6979451180 0.0593868569 0.0588479952 0.0694544986 0.0418384868 0.1141880000 0.0112350000 0.0504040000 0.0000260000 0.0006160000 0.0486820000 8961612 96830484 1768755200 3.9263215065 3.9705612659 4.0751686096 37 1305031230.7336409092 0.0614226051 0.0589175792 0.0694544986 0.0414734147 0.1622210000 0.0094410000 0.0662860000 0.0003060000 0.0003090000 0.0851410000 8963830 96830484 1770479616 3.9183073044 3.9677414894 4.0729885101 38 1305031230.7659239769 0.0650500953 0.0590789612 0.0694544986 0.0409339711 0.1361290000 0.0149660000 0.0660170000 0.0000280000 0.0003360000 0.0515420000 8966048 96830484 1769480192 3.9108333588 3.9633374214 4.0710506439 39 1305031230.7973229885 0.0701379478 0.0593625250 0.0701379478 0.0404564680 0.1291830000 0.0098480000 0.0589290000 0.0003720000 0.0002800000 0.0589750000 8968234 96830484 1771053056 3.9011533260 3.9574677944 4.0676817894 40 1305031230.8317570686 0.0760506094 0.0597797271 0.0760506094 0.0399839811 0.1180530000 0.0112810000 0.0485180000 0.0000260000 0.0003010000 0.0546250000 8970452 96830484 1770242048 3.8927912712 3.9509928226 4.0674991608 41 1305031230.8655419350 0.0774406195 0.0602104806 0.0774406195 0.0397164561 0.1727340000 0.0115950000 0.0624850000 0.0007380000 0.0002800000 0.0967520000 8972638 96830484 1768845312 3.8829555511 3.9492831230 4.0663614273 42 1305031230.8973939419 0.0863252506 0.0608322608 0.0863252506 0.0393283235 0.1254260000 0.0091070000 0.0538370000 0.0000280000 0.0003030000 0.0583770000 8974856 96830484 1770377216 3.8749778271 3.9403240681 4.0741825104 43 1305031230.9373099804 0.1054669246 0.0618702762 0.1054669246 0.0394996300 0.1417650000 0.0110620000 0.0605300000 0.0003410000 0.0003470000 0.0660460000 8977138 96830484 1769717760 3.8573307991 3.9254093170 4.0874066353 44 1305031230.9650349617 0.1153497398 0.0630857186 0.1153497398 0.0397230053 0.1297180000 0.0112170000 0.0552800000 0.0000260000 0.0002940000 0.0599270000 8979260 96830484 1768230912 3.8489434719 3.9230477810 4.1092009544 45 1305031230.9971239567 0.1246746927 0.0644543625 0.1246746927 0.0395884068 0.1732080000 0.0094690000 0.0558160000 0.0003550000 0.0002770000 0.1032720000 8981478 96830484 1769889792 3.8425123692 3.9216973782 4.1255598068 46 1305031231.0367500782 0.1313072890 0.0659076869 0.1313072890 0.0392975436 0.1479460000 0.0217680000 0.0613880000 0.0000240000 0.0002840000 0.0608190000 8983760 96830484 1768738816 3.8390231133 3.9203486443 4.1358160973 47 1305031231.0644741058 0.1299242973 0.0672697425 0.1313072890 0.0388905310 0.1408080000 0.0092550000 0.0599140000 0.0003480000 0.0002690000 0.0667640000 8985850 96830484 1770606592 3.8371093273 3.9225251675 4.1356315613 48 1305031231.0967879295 0.1208286434 0.0683855529 0.1313072890 0.0384899920 0.1333390000 0.0109970000 0.0625350000 0.0000240000 0.0003110000 0.0586460000 8988068 96830484 1769734144 3.8387105465 3.9307494164 4.1317067146 49 1305031231.1347110271 0.1275153309 0.0695922831 0.1313072890 0.0380986545 0.1724710000 0.0108510000 0.0533010000 0.0003660000 0.0002750000 0.1039020000 8990318 96830484 1768194048 3.8390984535 3.9243156910 4.1367273331 50 1305031231.1652760506 0.1272833198 0.0707461038 0.1313072890 0.0377530169 0.1361150000 0.0093050000 0.0633860000 0.0000240000 0.0002890000 0.0598790000 8992504 96830484 1769889792 3.8399150372 3.9249041080 4.1379599571 51 1305031231.1977710724 0.1156106889 0.0716258016 0.1313072890 0.0374741762 0.1295400000 0.0110950000 0.0530950000 0.0002890000 0.0003420000 0.0638680000 8994722 96830484 1768738816 3.8441789150 3.9344615936 4.1326851845 52 1305031231.2344679832 0.1079543754 0.0723244280 0.1313072890 0.0376890549 0.1188750000 0.0091270000 0.0438920000 0.0000250000 0.0002850000 0.0616460000 8996972 96830484 1770606592 3.8507122993 3.9347686768 4.1207504272 53 1305031231.2656350136 0.0915284529 0.0726867681 0.1313072890 0.0374985539 0.1827520000 0.0104400000 0.0658160000 0.0000590000 0.0000530000 0.1055120000 8999126 96830484 1769734144 3.8587720394 3.9456741810 4.1044168472 54 1305031231.2978610992 0.0771234110 0.0727689281 0.1313072890 0.0374874615 0.1351690000 0.0151430000 0.0633890000 0.0000250000 0.0002770000 0.0543050000 9001344 96830484 1768230912 3.8619170189 3.9620397091 4.0759797096 55 1305031231.3351519108 0.0701122507 0.0727206249 0.1313072890 0.0374221163 0.1383330000 0.0094450000 0.0640200000 0.0002940000 0.0003420000 0.0590860000 9003594 96830484 1769889792 3.8723185062 3.9738297462 4.0632781982 56 1305031231.3650770187 0.0638575107 0.0725623550 0.1313072890 0.0371736560 0.1250240000 0.0109880000 0.0592260000 0.0000270000 0.0005330000 0.0501660000 9005748 96830484 1768738816 3.8806941509 3.9849874973 4.0581765175 57 1305031231.3973300457 0.0564119183 0.0722790140 0.1313072890 0.0368820926 0.1639010000 0.0093340000 0.0656590000 0.0003430000 0.0003010000 0.0841290000 9007966 96830484 1770479616 3.8923983574 3.9875936508 4.0652661324 58 1305031231.4368579388 0.0504382625 0.0719024493 0.1313072890 0.0366032613 0.1293700000 0.0112810000 0.0678590000 0.0000280000 0.0003470000 0.0453520000 9010248 96830484 1769607168 3.9052250385 3.9884586334 4.0753097534 59 1305031231.4649889469 0.0487137660 0.0715094208 0.1313072890 0.0363458923 0.1293620000 0.0110540000 0.0684160000 0.0003820000 0.0003110000 0.0482350000 9012370 96830484 1768083456 3.9128077030 3.9896957874 4.0784020424 60 1305031231.4992439747 0.0426294208 0.0710280875 0.1313072890 0.0361299885 0.1196910000 0.0093320000 0.0627540000 0.0000270000 0.0002800000 0.0423600000 9014556 96830484 1769869312 3.9243352413 3.9974670410 4.0792264938 61 1305031231.5331959724 0.0400107950 0.0705196073 0.1313072890 0.0358962439 0.1299410000 0.0115300000 0.0469030000 0.0003830000 0.0002760000 0.0698360000 9016838 96830484 1768357888 3.9324538708 4.0014634132 4.0819621086 62 1305031231.5650680065 0.0379846059 0.0699948492 0.1313072890 0.0356834370 0.1063890000 0.0090120000 0.0533300000 0.0000240000 0.0003810000 0.0392480000 9018992 96830484 1770225664 3.9415962696 4.0041832924 4.0882344246 63 1305031231.6013169289 0.0356057771 0.0694489909 0.1313072890 0.0354035338 0.1095970000 0.0111620000 0.0528880000 0.0003890000 0.0002800000 0.0437610000 9021242 96830484 1769353216 3.9459676743 4.0091614723 4.0892958641 64 1305031231.6331589222 0.0348553322 0.0689084650 0.1313072890 0.0351909291 0.1208930000 0.0097630000 0.0694470000 0.0000260000 0.0003290000 0.0361630000 9023460 96830484 1770926080 3.9506518841 4.0121893883 4.0907354355 65 1305031231.6650550365 0.0348749869 0.0683848730 0.1313072890 0.0349228814 0.1189500000 0.0114730000 0.0424240000 0.0010480000 0.0002760000 0.0625090000 9030734 96830484 1769861120 3.9591712952 4.0158329010 4.0943727493 66 1305031231.7035079002 0.0353966430 0.0678850513 0.1313072890 0.0348517051 0.1189210000 0.0112270000 0.0718350000 0.0000250000 0.0002850000 0.0333380000 9043544 96830484 1768464384 3.9636099339 4.0163874626 4.0977816582 67 1305031231.7339379787 0.0354861990 0.0674014864 0.1313072890 0.0346900872 0.1086050000 0.0096280000 0.0596700000 0.0002910000 0.0003790000 0.0375800000 9045666 96830484 1770160128 3.9671154022 4.0174579620 4.0992121696 68 1305031231.7655088902 0.0354005620 0.0669308846 0.1313072890 0.0344811726 0.1047920000 0.0111860000 0.0596430000 0.0000270000 0.0002950000 0.0304010000 9047852 96830484 1769099264 3.9703264236 4.0189299583 4.1003131866 69 1305031231.8011910915 0.0387956277 0.0665231272 0.1313072890 0.0342558320 0.1323950000 0.0097090000 0.0690000000 0.0002910000 0.0002850000 0.0519220000 9050102 96830484 1770672128 3.9755938053 4.0174226761 4.1010508537 70 1305031231.8332920074 0.0396801718 0.0661396564 0.1313072890 0.0342032253 0.1147960000 0.0111010000 0.0710600000 0.0000260000 0.0002810000 0.0275480000 9052288 96830484 1769844736 3.9771656990 4.0165023804 4.0981082916 71 1305031231.8649590015 0.0405335873 0.0657790076 0.1313072890 0.0340002646 0.1208680000 0.0119540000 0.0707770000 0.0002970000 0.0002690000 0.0322180000 9054474 96830484 1768329216 3.9785068035 4.0157966614 4.0941214561 72 1305031231.9012699127 0.0463057160 0.0655085452 0.1313072890 0.0340559693 0.1085670000 0.0093600000 0.0707810000 0.0000250000 0.0002820000 0.0231520000 9056724 96830484 1770135552 3.9703812599 4.0083494186 4.0844373703 73 1305031231.9330461025 0.0498520210 0.0652940722 0.1313072890 0.0338854266 0.1331830000 0.0112110000 0.0715150000 0.0002870000 0.0003300000 0.0446310000 9058910 96830484 1769091072 3.9757270813 4.0054960251 4.0831475258 74 1305031231.9650299549 0.0510324873 0.0651013481 0.1313072890 0.0336742094 0.1093510000 0.0094990000 0.0728810000 0.0000260000 0.0003540000 0.0215570000 9061096 96830484 1770774528 3.9756526947 4.0048565865 4.0796203613 75 1305031232.0007200241 0.0518577881 0.0649247673 0.1313072890 0.0335813550 0.1169840000 0.0111080000 0.0717380000 0.0002910000 0.0002710000 0.0285080000 9063346 96830484 1769873408 3.9751021862 4.0050001144 4.0765657425 76 1305031232.0332028866 0.0544179268 0.0647865194 0.1313072890 0.0334753252 0.0915210000 0.0113030000 0.0543540000 0.0000260000 0.0003700000 0.0216250000 9065564 96830484 1768329216 3.9725930691 4.0030589104 4.0721774101 77 1305031232.0651450157 0.0568121783 0.0646829565 0.1313072890 0.0332980865 0.0954610000 0.0103350000 0.0427460000 0.0003820000 0.0003100000 0.0404520000 9067718 96830484 1767694336 3.9694478512 4.0026245117 4.0675115585 78 1305031232.1007990837 0.0593014918 0.0646139634 0.1313072890 0.0331599313 0.0786790000 0.0095020000 0.0437670000 0.0000280000 0.0003730000 0.0226090000 9069968 96830484 1768947712 3.9651453495 4.0031480789 4.0626211166 79 1305031232.1328380108 0.0634541288 0.0645992820 0.1313072890 0.0330050496 0.1268330000 0.0093310000 0.0808270000 0.0002900000 0.0002640000 0.0326750000 9072186 96830484 1768349696 3.9614746571 4.0013594627 4.0583167076 80 1305031232.1650519371 0.0659174547 0.0646157591 0.1313072890 0.0328198075 0.0954200000 0.0095090000 0.0530010000 0.0000260000 0.0002900000 0.0273690000 9074340 96830484 1769844736 3.9590852261 4.0010695457 4.0545434952 81 1305031232.1992239952 0.0668481216 0.0646433191 0.1313072890 0.0326572159 0.1185950000 0.0113630000 0.0706890000 0.0003260000 0.0003470000 0.0346560000 9076558 96830484 1767849984 3.9590594769 4.0022010803 4.0513577461 82 1305031232.2364680767 0.0682099834 0.0646868150 0.1313072890 0.0324897981 0.0909000000 0.0100610000 0.0513060000 0.0000280000 0.0003030000 0.0232480000 9078840 96830484 1769496576 3.9583444595 4.0025267601 4.0481963158 83 1305031232.2626979351 0.0712094307 0.0647654008 0.1313072890 0.0324457996 0.1120790000 0.0096450000 0.0712190000 0.0003040000 0.0002730000 0.0288700000 9080930 96830484 1771163648 3.9578032494 4.0004901886 4.0453014374 84 1305031232.2980248928 0.0715446547 0.0648461062 0.1313072890 0.0324075638 0.0841020000 0.0115420000 0.0421370000 0.0000260000 0.0010520000 0.0235890000 9083180 96830484 1769119744 3.9576880932 4.0015940666 4.0424609184 85 1305031232.3321430683 0.0766664818 0.0649851694 0.1313072890 0.0322886509 0.1412330000 0.0096010000 0.0842670000 0.0004100000 0.0002790000 0.0454120000 9085398 96830484 1767448576 3.9540059566 3.9985351562 4.0386567116 86 1305031232.3647489548 0.0777979791 0.0651341556 0.1313072890 0.0321372870 0.0886770000 0.0090570000 0.0455340000 0.0000260000 0.0003090000 0.0278980000 9087552 96830484 1769099264 3.9514143467 4.0012955666 4.0351810455 87 1305031232.4008779526 0.0808016881 0.0653142422 0.1313072890 0.0319705764 0.1094880000 0.0091220000 0.0645740000 0.0000580000 0.0000530000 0.0309370000 9089834 96830484 1770749952 3.9476969242 4.0025939941 4.0314869881 88 1305031232.4331440926 0.0822420865 0.0655066040 0.1313072890 0.0317881260 0.0888040000 0.0114410000 0.0457650000 0.0000290000 0.0003080000 0.0251760000 9092052 96830484 1768845312 3.9461545944 4.0030264854 4.0289134979 89 1305031232.4647209644 0.0859740004 0.0657365748 0.1313072890 0.0316101964 0.1349370000 0.0112030000 0.0715620000 0.0003080000 0.0003520000 0.0502400000 9094174 96830484 1766686720 3.9408013821 4.0039081573 4.0259838104 90 1305031232.5015261173 0.0900173634 0.0660063613 0.1313072890 0.0314406257 0.1315790000 0.0086980000 0.0872910000 0.0000060000 0.0000590000 0.0283370000 9096456 96830484 1768337408 3.9379568100 4.0000801086 4.0233092308 91 1305031232.5324640274 0.0992609710 0.0663717966 0.1313072890 0.0312726205 0.1268830000 0.0083680000 0.0778380000 0.0003380000 0.0002770000 0.0340100000 9098642 96830484 1770004480 3.9294307232 3.9937245846 4.0196194649 92 1305031232.5647449493 0.1076990217 0.0668210056 0.1313072890 0.0311368011 0.0881800000 0.0104740000 0.0444860000 0.0000270000 0.0003020000 0.0271230000 9100828 96830484 1767849984 3.9209759235 3.9890413284 4.0161375999 93 1305031232.6003499031 0.1180415750 0.0673717644 0.1313072890 0.0309927296 0.1159320000 0.0107960000 0.0456530000 0.0003790000 0.0002720000 0.0528990000 9103046 96830484 1766436864 3.9122288227 3.9816033840 4.0124750137 94 1305031232.6294269562 0.1234458908 0.0679682976 0.1313072890 0.0308602306 0.1112890000 0.0090130000 0.0684680000 0.0000260000 0.0003730000 0.0280210000 9105168 96830484 1768194048 3.9071130753 3.9795172215 4.0087447166 95 1305031232.6647078991 0.1260998994 0.0685802092 0.1313072890 0.0306996060 0.1012570000 0.0091560000 0.0507770000 0.0003390000 0.0002790000 0.0347400000 9107450 96830484 1769877504 3.9018981457 3.9813451767 4.0058550835 96 1305031232.7005090714 0.1333602965 0.0692550018 0.1333602965 0.0305502485 0.0903420000 0.0115220000 0.0463030000 0.0000280000 0.0003050000 0.0285550000 9109668 96830484 1767845888 3.8939144611 3.9795141220 4.0022912025 97 1305031232.7327980995 0.1361145973 0.0699442760 0.1361145973 0.0304344496 0.1377130000 0.0099030000 0.0675800000 0.0003780000 0.0003110000 0.0581690000 9111854 96830484 1767305216 3.8910870552 3.9804131985 3.9986584187 98 1305031232.7684600353 0.1405884624 0.0706651350 0.1405884624 0.0303479012 0.0964120000 0.0085590000 0.0468080000 0.0000260000 0.0003360000 0.0352630000 9114104 96830484 1768828928 3.8864865303 3.9775676727 3.9963965416 99 1305031232.8045380116 0.1473805159 0.0714400379 0.1473805159 0.0302100271 0.1287150000 0.0090980000 0.0687030000 0.0003100000 0.0002770000 0.0460220000 9116354 96830484 1770745856 3.8794546127 3.9729163647 3.9933698177 100 1305031232.8346450329 0.1512351334 0.0722379888 0.1512351334 0.0300988879 0.1162440000 0.0103190000 0.0671800000 0.0000300000 0.0002980000 0.0321850000 9118508 96830484 1770123264 3.8742222786 3.9746911526 3.9896545410 101 1305031232.8685569763 0.1544296741 0.0730517679 0.1544296741 0.0299858993 0.1115990000 0.0108750000 0.0397510000 0.0005320000 0.0002880000 0.0585630000 9120758 96830484 1768464384 3.8700342178 3.9746730328 3.9867882729 102 1305031232.9041829109 0.1580199897 0.0738847897 0.1580199897 0.0298667371 0.0961220000 0.0087060000 0.0458690000 0.0000290000 0.0003820000 0.0339890000 9122976 96830484 1770098688 3.8650848866 3.9743471146 3.9844086170 103 1305031232.9330000877 0.1594968587 0.0747159748 0.1594968587 0.0297657517 0.1317650000 0.0106950000 0.0776900000 0.0003090000 0.0002710000 0.0378830000 9125098 96830484 1768103936 3.8629195690 3.9767062664 3.9821953773 104 1305031232.9683640003 0.1583745778 0.0755203844 0.1594968587 0.0296212520 0.0884030000 0.0092220000 0.0458940000 0.0000280000 0.0003120000 0.0315350000 9127380 96830484 1769734144 3.8635869026 3.9770855904 3.9805004597 105 1305031233.0011510849 0.1550122648 0.0762774500 0.1594968587 0.0295231034 0.1275980000 0.0113460000 0.0537710000 0.0003110000 0.0003460000 0.0604070000 9129566 96830484 1767571456 3.8654017448 3.9830379486 3.9794852734 106 1305031233.0330219269 0.1526469886 0.0769979173 0.1594968587 0.0296861794 0.0878670000 0.0086150000 0.0415050000 0.0000260000 0.0003030000 0.0331290000 9131752 96830484 1769349120 3.8634045124 3.9889543056 3.9823963642 107 1305031233.0688428879 0.1467102468 0.0776494344 0.1594968587 0.0298272280 0.0893410000 0.0085180000 0.0439390000 0.0003070000 0.0002750000 0.0348750000 9133938 96830484 1771036672 3.8674221039 3.9923024178 3.9837765694 108 1305031233.1004469395 0.1358748674 0.0781885588 0.1594968587 0.0297776134 0.0871960000 0.0109310000 0.0407570000 0.0000280000 0.0003140000 0.0291440000 9136092 96830484 1768865792 3.8750383854 4.0037436485 3.9880533218 109 1305031233.1328918934 0.1288069040 0.0786529473 0.1594968587 0.0301227398 0.1445440000 0.0084740000 0.0753900000 0.0003120000 0.0002770000 0.0584870000 9138278 96830484 1768210432 3.8848164082 3.9985797405 3.9897744656 110 1305031233.1684799194 0.1172577441 0.0790039000 0.1594968587 0.0301181416 0.0973050000 0.0091410000 0.0647790000 0.0000290000 0.0003090000 0.0215450000 9140528 96830484 1769844736 3.9009480476 4.0020575523 3.9902071953 111 1305031233.2006340027 0.1139211953 0.0793184702 0.1594968587 0.0300213403 0.1151600000 0.0118250000 0.0574420000 0.0005930000 0.0002800000 0.0368790000 9142714 96830484 1768067072 3.9043445587 4.0020565987 3.9933540821 112 1305031233.2330091000 0.1111635640 0.0796028014 0.1594968587 0.0299962090 0.1173210000 0.0087410000 0.0718630000 0.0000260000 0.0003740000 0.0290010000 9144900 96830484 1769844736 3.9043223858 4.0034809113 3.9971523285 113 1305031233.2684679031 0.1098065302 0.0798700910 0.1594968587 0.0306397660 0.1467530000 0.0103300000 0.0846840000 0.0000600000 0.0000550000 0.0502300000 9147150 96830484 1767993344 3.9011337757 4.0040149689 4.0019464493 114 1305031233.3003950119 0.0954040289 0.0800063537 0.1594968587 0.0308908389 0.1135350000 0.0086020000 0.0759470000 0.0000270000 0.0003030000 0.0255550000 9149336 96830484 1769590784 3.9098842144 4.0134057999 4.0097918510 115 1305031233.3325300217 0.0880237669 0.0800760703 0.1594968587 0.0307741179 0.1012500000 0.0101860000 0.0529750000 0.0003100000 0.0003440000 0.0303560000 9151522 96830484 1768079360 3.9128947258 4.0040369034 4.0230507851 116 1305031233.3686299324 0.0700233951 0.0799894093 0.1594968587 0.0307383251 0.1061810000 0.0095540000 0.0655240000 0.0000280000 0.0003100000 0.0230840000 9153708 96830484 1769504768 3.9359421730 4.0128316879 4.0282588005 117 1305031233.4008929729 0.0578505807 0.0798001885 0.1594968587 0.0307200420 0.1226560000 0.0114000000 0.0673500000 0.0003060000 0.0003430000 0.0416930000 9155926 96830484 1767866368 3.9621622562 4.0260400772 4.0355200768 118 1305031233.4330079556 0.0598621070 0.0796312217 0.1594968587 0.0307396243 0.1106360000 0.0092360000 0.0696800000 0.0000260000 0.0003070000 0.0238270000 9158144 96830484 1769463808 3.9574944973 4.0161881447 4.0406293869 119 1305031233.4687869549 0.0625616908 0.0794877803 0.1594968587 0.0307507445 0.0997270000 0.0098660000 0.0532200000 0.0003720000 0.0002790000 0.0280220000 9160330 96830484 1771245568 3.9559452534 4.0092821121 4.0448622704 120 1305031233.5007359982 0.0641293675 0.0793597935 0.1594968587 0.0306506333 0.0878100000 0.0110510000 0.0468570000 0.0000270000 0.0003040000 0.0223950000 9162548 96830484 1770364928 3.9521250725 4.0065946579 4.0464987755 121 1305031233.5341610909 0.0650447831 0.0792414877 0.1594968587 0.0306246993 0.1088500000 0.0099810000 0.0541600000 0.0003060000 0.0003560000 0.0424490000 9164766 96830484 1769725952 3.9524700642 4.0051007271 4.0492630005 122 1305031233.5697269440 0.0640599802 0.0791170491 0.1594968587 0.0305258739 0.1069560000 0.0097400000 0.0703410000 0.0000270000 0.0003060000 0.0218770000 9166984 96830484 1771282432 3.9533166885 4.0051431656 4.0529913902 123 1305031233.6012749672 0.0666429251 0.0790156334 0.1594968587 0.0304641181 0.1189380000 0.0115870000 0.0702680000 0.0003680000 0.0002820000 0.0285250000 9169170 96830484 1769598976 3.9519114494 4.0019783974 4.0539102554 124 1305031233.6330409050 0.0668111444 0.0789172101 0.1594968587 0.0303977350 0.0881780000 0.0113390000 0.0469880000 0.0000300000 0.0003080000 0.0215520000 9171356 96830484 1768095744 3.9523425102 3.9991092682 4.0581884384 125 1305031233.6717829704 0.0660161525 0.0788140017 0.1594968587 0.0302781708 0.1332630000 0.0111510000 0.0784220000 0.0003080000 0.0003480000 0.0413820000 9173670 96830484 1767964672 3.9492058754 3.9991955757 4.0595054626 126 1305031233.7022960186 0.0631752312 0.0786898845 0.1594968587 0.0303316478 0.0843730000 0.0088770000 0.0485060000 0.0000300000 0.0003700000 0.0245580000 9175856 96830484 1769648128 3.9500460625 4.0010571480 4.0629835129 127 1305031233.7312009335 0.0558723547 0.0785102189 0.1594968587 0.0305094197 0.1256670000 0.0106930000 0.0763760000 0.0003180000 0.0003510000 0.0300200000 9177978 96830484 1768439808 3.9577050209 4.0089974403 4.0700731277 128 1305031233.7691600323 0.0526266769 0.0783080037 0.1594968587 0.0305568887 0.1090510000 0.0098550000 0.0713880000 0.0000280000 0.0003010000 0.0229500000 9180228 96830484 1770139648 3.9609050751 4.0130696297 4.0726437569 129 1305031233.7997679710 0.0530228987 0.0781119951 0.1594968587 0.0304503850 0.1393560000 0.0113990000 0.0727740000 0.0003120000 0.0002760000 0.0460120000 9192622 96830484 1769091072 3.9598319530 4.0118989944 4.0718221664 130 1305031233.8338310719 0.0565979294 0.0779465023 0.1594968587 0.0304024585 0.0905540000 0.0097080000 0.0512810000 0.0000290000 0.0003050000 0.0227170000 9215832 96830484 1770790912 3.9554870129 4.0061516762 4.0683078766 131 1305031233.8655700684 0.0585149527 0.0777981699 0.1594968587 0.0303304489 0.1196570000 0.0113600000 0.0698510000 0.0003730000 0.0002820000 0.0294240000 9218018 96830484 1769979904 3.9563243389 4.0043959618 4.0677161217 132 1305031233.8986968994 0.0576547720 0.0776455684 0.1594968587 0.0302154487 0.1104820000 0.0111950000 0.0714730000 0.0000290000 0.0003060000 0.0223670000 9220268 96830484 1768493056 3.9564270973 4.0052580833 4.0676288605 133 1305031233.9320030212 0.0573145561 0.0774927036 0.1594968587 0.0301421176 0.1286020000 0.0094440000 0.0708290000 0.0003050000 0.0002730000 0.0448830000 9222454 96830484 1770135552 3.9623031616 4.0053882599 4.0703406334 134 1305031233.9681589603 0.0555655397 0.0773290681 0.1594968587 0.0300484276 0.1086230000 0.0115250000 0.0719990000 0.0000260000 0.0003700000 0.0229820000 9224704 96830484 1768439808 3.9677896500 4.0077476501 4.0722107887 135 1305031233.9989380836 0.0563533232 0.0771736922 0.1594968587 0.0299781403 0.1206860000 0.0098070000 0.0724280000 0.0003060000 0.0006960000 0.0290840000 9226890 96830484 1770135552 3.9688072205 4.0066723824 4.0709471703 136 1305031234.0370678902 0.0539855994 0.0770031915 0.1594968587 0.0298792485 0.0988230000 0.0119030000 0.0544340000 0.0000270000 0.0003790000 0.0235130000 9229172 96830484 1768456192 3.9743762016 4.0106434822 4.0725831985 137 1305031234.0687561035 0.0529507063 0.0768276259 0.1594968587 0.0297715543 0.1227340000 0.0097400000 0.0556780000 0.0003740000 0.0002740000 0.0481270000 9231326 96830484 1770008576 3.9749045372 4.0118618011 4.0712361336 138 1305031234.0997409821 0.0533432029 0.0766574489 0.1594968587 0.0296693035 0.1065730000 0.0118600000 0.0607470000 0.0000270000 0.0003800000 0.0251590000 9233512 96830484 1768456192 3.9835240841 4.0150995255 4.0741224289 139 1305031234.1350688934 0.0529111102 0.0764866120 0.1594968587 0.0295777686 0.1248170000 0.0100680000 0.0726060000 0.0003080000 0.0002860000 0.0329190000 9235730 96830484 1770008576 3.9843149185 4.0165910721 4.0726599693 140 1305031234.1659009457 0.0492469333 0.0762920428 0.1594968587 0.0295417917 0.1183110000 0.0118880000 0.0702570000 0.0000280000 0.0003740000 0.0273860000 9237916 96830484 1768329216 3.9851830006 4.0226211548 4.0733084679 141 1305031234.2010040283 0.0494681522 0.0761018025 0.1594968587 0.0294916465 0.1470480000 0.0095870000 0.0719500000 0.0003050000 0.0002790000 0.0561430000 9240134 96830484 1769861120 3.9850015640 4.0220274925 4.0724320412 142 1305031234.2385749817 0.0481995083 0.0759053074 0.1594968587 0.0293896540 0.0856290000 0.0110850000 0.0360900000 0.0000170000 0.0002020000 0.0298710000 9242448 96830484 1769074688 3.9860389233 4.0249061584 4.0726213455 143 1305031234.2655100822 0.0448391996 0.0756880619 0.1594968587 0.0293108515 0.1394700000 0.0107030000 0.0786800000 0.0000600000 0.0000540000 0.0411870000 9244506 96830484 1767583744 3.9880082607 4.0324225426 4.0754084587 144 1305031234.3024549484 0.0448098294 0.0754736298 0.1594968587 0.0292083100 0.1313230000 0.0089700000 0.0847260000 0.0000250000 0.0003100000 0.0348940000 9246820 96830484 1769373696 3.9888648987 4.0325360298 4.0758514404 145 1305031234.3384580612 0.0440557525 0.0752569548 0.1594968587 0.0291265047 0.1418450000 0.0106380000 0.0735490000 0.0003790000 0.0002780000 0.0551500000 9249070 96830484 1768222720 3.9873707294 4.0338864326 4.0747742653 146 1305031234.3661808968 0.0414898247 0.0750256730 0.1594968587 0.0290716819 0.1102670000 0.0111470000 0.0647320000 0.0000260000 0.0002950000 0.0311380000 9251160 96830484 1769865216 3.9884717464 4.0393786430 4.0773463249 147 1305031234.4000349045 0.0421798937 0.0748022324 0.1594968587 0.0289725579 0.1272390000 0.0108650000 0.0695750000 0.0002980000 0.0002750000 0.0382980000 9253378 96830484 1768873984 3.9908449650 4.0408897400 4.0787987709 148 1305031234.4367709160 0.0447303690 0.0745990441 0.1594968587 0.0289437165 0.0864580000 0.0093860000 0.0419940000 0.0000300000 0.0002960000 0.0322580000 9255660 96830484 1770520576 3.9953260422 4.0405292511 4.0793380737 149 1305031234.4676060677 0.0455776230 0.0744042695 0.1594968587 0.0288561814 0.1281810000 0.0115760000 0.0458950000 0.0003010000 0.0002720000 0.0682500000 9257814 96830484 1769455616 3.9976511002 4.0434088707 4.0795474052 150 1305031234.4977810383 0.0462631620 0.0742166621 0.1594968587 0.0287650146 0.1070390000 0.0091540000 0.0576780000 0.0000270000 0.0003580000 0.0338940000 9259968 96830484 1771036672 3.9992830753 4.0472083092 4.0798850060 151 1305031234.5376710892 0.0502059646 0.0740576508 0.1594968587 0.0288484093 0.1287870000 0.0113380000 0.0690330000 0.0002940000 0.0002730000 0.0420560000 9262282 96830484 1770225664 4.0033307076 4.0437240601 4.0765519142 152 1305031234.5690369606 0.0535500348 0.0739227323 0.1594968587 0.0288609521 0.1245160000 0.0115560000 0.0671840000 0.0000250000 0.0002800000 0.0358300000 9264436 96830484 1768828928 4.0084385872 4.0506606102 4.0793170929 153 1305031234.5982480049 0.0579603128 0.0738184028 0.1594968587 0.0287706969 0.1450010000 0.0100480000 0.0653740000 0.0003780000 0.0002690000 0.0670040000 9266622 96830484 1770496000 4.0132241249 4.0552477837 4.0807437897 154 1305031234.6336491108 0.0600856990 0.0737292294 0.1594968587 0.0287112352 0.1263110000 0.0116430000 0.0666820000 0.0000250000 0.0002820000 0.0383740000 9268808 96830484 1768828928 4.0148277283 4.0542483330 4.0771446228 155 1305031234.6658589840 0.0628216490 0.0736588579 0.1594968587 0.0286445912 0.1294220000 0.0098340000 0.0657420000 0.0002880000 0.0003310000 0.0475920000 9271026 96830484 1770463232 4.0162158012 4.0578961372 4.0753374100 156 1305031234.6987318993 0.0642019659 0.0735982368 0.1594968587 0.0285657420 0.1061720000 0.0118720000 0.0586370000 0.0000050000 0.0000750000 0.0335900000 9273244 96830484 1768448000 4.0142650604 4.0599784851 4.0702123642 157 1305031234.7344369888 0.0657853261 0.0735484730 0.1594968587 0.0284835319 0.1582060000 0.0120700000 0.0674160000 0.0003570000 0.0002750000 0.0761110000 9275430 96830484 1769840640 4.0116004944 4.0640788078 4.0656237602 158 1305031234.7689719200 0.0688763186 0.0735189024 0.1594968587 0.0283988715 0.1323350000 0.0112920000 0.0694990000 0.0000260000 0.0002750000 0.0420900000 9277680 96830484 1767940096 4.0118851662 4.0677595139 4.0631756783 159 1305031234.8015530109 0.0725581571 0.0735128600 0.1594968587 0.0284282617 0.1282290000 0.0100060000 0.0568100000 0.0002840000 0.0002620000 0.0513990000 9279898 96830484 1769746432 4.0067791939 4.0814476013 4.0642704964 160 1305031234.8378078938 0.0755512714 0.0735256001 0.1594968587 0.0283534945 0.1288860000 0.0117250000 0.0679420000 0.0000260000 0.0002960000 0.0436060000 9282180 96830484 1767833600 4.0051274300 4.0883936882 4.0670847893 161 1305031234.8693211079 0.0776892453 0.0735514612 0.1594968587 0.0282803395 0.1672080000 0.0097870000 0.0675020000 0.0003490000 0.0002720000 0.0804580000 9284302 96830484 1769590784 3.9989037514 4.0933880806 4.0622673035 162 1305031234.9019980431 0.0818303525 0.0736025655 0.1594968587 0.0282035761 0.1291930000 0.0116430000 0.0677380000 0.0000290000 0.0003850000 0.0451880000 9286520 96830484 1767833600 3.9961798191 4.1015400887 4.0667920113 163 1305031234.9381608963 0.0839068666 0.0736657821 0.1594968587 0.0282912536 0.1094110000 0.0099480000 0.0458150000 0.0007060000 0.0002870000 0.0506660000 9288770 96830484 1769447424 3.9897766113 4.1085987091 4.0726995468 164 1305031234.9730799198 0.0851857513 0.0737360258 0.1594968587 0.0282076331 0.1269650000 0.0095680000 0.0681790000 0.0000260000 0.0003510000 0.0448250000 9291020 96830484 1771126784 3.9886422157 4.1114358902 4.0789370537 165 1305031235.0050830841 0.0841543227 0.0737991670 0.1594968587 0.0282696266 0.1634980000 0.0117830000 0.0693580000 0.0002860000 0.0003370000 0.0796780000 9293174 96830484 1769590784 3.9889807701 4.1123957634 4.0881600380 166 1305031235.0399720669 0.0794951543 0.0738334801 0.1594968587 0.0281902366 0.1115970000 0.0110950000 0.0469720000 0.0000230000 0.0002790000 0.0457560000 9295424 96830484 1767976960 3.9946880341 4.1052818298 4.0938334465 167 1305031235.0729401112 0.0752391741 0.0738418975 0.1594968587 0.0281499181 0.1501040000 0.0095840000 0.0907920000 0.0000600000 0.0000530000 0.0476370000 9297610 96830484 1769717760 3.9971859455 4.1007094383 4.1018438339 168 1305031235.0995910168 0.0678160042 0.0738060291 0.1594968587 0.0280749629 0.1159790000 0.0113820000 0.0531650000 0.0000260000 0.0003110000 0.0415580000 9299732 96830484 1767960576 3.9998111725 4.0917391777 4.1046805382 169 1305031235.1362709999 0.0600337796 0.0737245365 0.1594968587 0.0280441600 0.1666110000 0.0099600000 0.0688760000 0.0003150000 0.0002630000 0.0767880000 9301982 96830484 1769701376 4.0035471916 4.0789141655 4.1043868065 170 1305031235.1663711071 0.0556303188 0.0736180999 0.1594968587 0.0280320848 0.1264080000 0.0117610000 0.0635980000 0.0000290000 0.0002970000 0.0398840000 9304136 96830484 1767796736 4.0019965172 4.0764584541 4.1082530022 171 1305031235.1998469830 0.0537645742 0.0735019974 0.1594968587 0.0279575337 0.1292440000 0.0100810000 0.0672290000 0.0003550000 0.0002700000 0.0462490000 9306290 96830484 1769574400 4.0056624413 4.0715456009 4.1150660515 172 1305031235.2375700474 0.0501593500 0.0733662843 0.1594968587 0.0279489224 0.1187950000 0.0113600000 0.0588140000 0.0000280000 0.0002900000 0.0378110000 9308572 96830484 1767833600 4.0041832924 4.0713567734 4.1187157631 173 1305031235.2690389156 0.0470708944 0.0732142879 0.1594968587 0.0278697163 0.1470500000 0.0097700000 0.0682590000 0.0003750000 0.0002750000 0.0662610000 9310758 96830484 1769476096 4.0022010803 4.0714306831 4.1236715317 174 1305031235.3064870834 0.0440463424 0.0730466560 0.1594968587 0.0278980718 0.1090960000 0.0094440000 0.0528970000 0.0000270000 0.0003800000 0.0362540000 9313040 96830484 1771126784 3.9987885952 4.0752854347 4.1285181046 175 1305031235.3380000591 0.0356706269 0.0728330787 0.1594968587 0.0278204449 0.1110570000 0.0119850000 0.0560880000 0.0005190000 0.0002830000 0.0400270000 9315194 96830484 1769209856 3.9905288219 4.0759983063 4.1288366318 176 1305031235.3698880672 0.0268602502 0.0725718694 0.1594968587 0.0277892151 0.1195250000 0.0096590000 0.0662800000 0.0000270000 0.0003500000 0.0325690000 9317380 96830484 1770868736 3.9815726280 4.0749692917 4.1244301796 177 1305031235.4060161114 0.0218277443 0.0722851794 0.1594968587 0.0278311824 0.1100610000 0.0116830000 0.0406620000 0.0002870000 0.0003370000 0.0549400000 9319630 96830484 1769066496 3.9762215614 4.0746145248 4.1228127480 178 1305031235.4381530285 0.0192042068 0.0719869717 0.1594968587 0.0277839848 0.0886230000 0.0091890000 0.0447300000 0.0000410000 0.0003600000 0.0309020000 9321816 96830484 1770762240 3.9679536819 4.0772132874 4.1229424477 179 1305031235.4700589180 0.0204898082 0.0716992781 0.1594968587 0.0277742389 0.1293120000 0.0110620000 0.0791410000 0.0000600000 0.0000540000 0.0365860000 9324002 96830484 1768976384 3.9637475014 4.0682868958 4.1163158417 180 1305031235.5059850216 0.0250936374 0.0714403579 0.1594968587 0.0277080463 0.0842900000 0.0091240000 0.0393150000 0.0000290000 0.0003790000 0.0264490000 9326252 96830484 1770635264 3.9590539932 4.0662469864 4.1158127785 181 1305031235.5385539532 0.0256614871 0.0711874359 0.1594968587 0.0276403074 0.1027140000 0.0117460000 0.0400650000 0.0002930000 0.0002700000 0.0480450000 9328438 96830484 1768828928 3.9586865902 4.0642356873 4.1178097725 182 1305031235.5703649521 0.0272601265 0.0709460771 0.1594968587 0.0275749802 0.0947290000 0.0091510000 0.0555110000 0.0000260000 0.0003200000 0.0260390000 9330624 96830484 1770749952 3.9609892368 4.0596046448 4.1205759048 183 1305031235.6060059071 0.0319991335 0.0707332523 0.1594968587 0.0275342855 0.1264430000 0.0124830000 0.0740210000 0.0003670000 0.0002820000 0.0292280000 9332906 96830484 1768722432 3.9566280842 4.0588312149 4.1226897240 184 1305031235.6389510632 0.0384666920 0.0705578905 0.1594968587 0.0274920049 0.1084890000 0.0097440000 0.0715180000 0.0000280000 0.0003100000 0.0214100000 9335092 96830484 1770475520 3.9549758434 4.0535235405 4.1243386269 185 1305031235.6705160141 0.0430581607 0.0704092433 0.1594968587 0.0274254359 0.0959910000 0.0118210000 0.0434820000 0.0003830000 0.0002860000 0.0377720000 9337246 96830484 1768574976 3.9527730942 4.0513343811 4.1270937920 186 1305031235.7057778835 0.0469286926 0.0702830038 0.1594968587 0.0273514447 0.0771730000 0.0100390000 0.0441240000 0.0000270000 0.0005440000 0.0200330000 9339496 96830484 1768812544 3.9583358765 4.0466899872 4.1345772743 187 1305031235.7387969494 0.0545980185 0.0701991269 0.1594968587 0.0273123792 0.1057240000 0.0090660000 0.0554240000 0.0020220000 0.0002920000 0.0280860000 9341714 96830484 1767063552 3.9559118748 4.0422110558 4.1380829811 188 1305031235.7696299553 0.0603478998 0.0701467267 0.1594968587 0.0272497307 0.0871630000 0.0098910000 0.0413470000 0.0000290000 0.0011670000 0.0235960000 9343868 96830484 1768955904 3.9512679577 4.0411343575 4.1404795647 189 1305031235.8072249889 0.0706014931 0.0701491329 0.1594968587 0.0271902712 0.1177500000 0.0105430000 0.0620580000 0.0003710000 0.0002810000 0.0421500000 9346214 96830484 1770602496 3.9469361305 4.0368528366 4.1421074867 190 1305031235.8388121128 0.0773200989 0.0701868748 0.1594968587 0.0271487725 0.1189180000 0.0109560000 0.0724080000 0.0000270000 0.0003010000 0.0252110000 9348400 96830484 1769717760 3.9449460506 4.0336351395 4.1463747025 191 1305031235.8700668812 0.0837147832 0.0702577016 0.1594968587 0.0271068137 0.1006110000 0.0116780000 0.0473020000 0.0003140000 0.0004720000 0.0299110000 9350618 96830484 1767960576 3.9423956871 4.0311622620 4.1502299309 192 1305031235.9061110020 0.0905665383 0.0703634768 0.1594968587 0.0270405014 0.1198430000 0.0097710000 0.0733940000 0.0000260000 0.0002940000 0.0253410000 9352900 96830484 1769730048 3.9420416355 4.0285587311 4.1547937393 193 1305031235.9382328987 0.1001132950 0.0705176209 0.1594968587 0.0269969956 0.1515670000 0.0115270000 0.0719520000 0.0003040000 0.0003500000 0.0490780000 9355150 96830484 1767849984 3.9422097206 4.0219473839 4.1598892212 194 1305031235.9700109959 0.1032710150 0.0706864528 0.1594968587 0.0269310217 0.1257640000 0.0094030000 0.0807480000 0.0000270000 0.0003170000 0.0268900000 9357336 96830484 1769574400 3.9382464886 4.0234065056 4.1619830132 195 1305031236.0068531036 0.1125963703 0.0709013755 0.1594968587 0.0268729720 0.1096670000 0.0117790000 0.0614490000 0.0003060000 0.0002830000 0.0335020000 9359650 96830484 1767579648 3.9395790100 4.0178332329 4.1695032120 196 1305031236.0380480289 0.1181512177 0.0711424461 0.1594968587 0.0268099711 0.1249010000 0.0098320000 0.0745060000 0.0000270000 0.0004750000 0.0288680000 9361836 96830484 1769234432 3.9354498386 4.0169754028 4.1711735725 197 1305031236.0698781013 0.1266095936 0.0714240052 0.1594968587 0.0268165544 0.1266550000 0.0096570000 0.0674350000 0.0002970000 0.0002710000 0.0465580000 9364054 96830484 1770872832 3.9309725761 4.0129127502 4.1741948128 198 1305031236.1058719158 0.1316066086 0.0717279578 0.1594968587 0.0267563613 0.1253430000 0.0114690000 0.0736650000 0.0000310000 0.0002940000 0.0289950000 9366336 96830484 1768722432 3.9311237335 4.0114331245 4.1789226532 199 1305031236.1383249760 0.1363562793 0.0720527232 0.1594968587 0.0266967551 0.1285190000 0.0101390000 0.0738480000 0.0003040000 0.0002740000 0.0343590000 9368586 96830484 1770622976 3.9274060726 4.0100398064 4.1800241470 200 1305031236.1709330082 0.1381127983 0.0723830236 0.1594968587 0.0266302168 0.1261390000 0.0121300000 0.0743000000 0.0000240000 0.0002810000 0.0278960000 9370804 96830484 1768722432 3.9282107353 4.0106763840 4.1839346886 201 1305031236.2071900368 0.1400526911 0.0727196886 0.1594968587 0.0265702703 0.1373190000 0.0101180000 0.0741570000 0.0003790000 0.0002810000 0.0499760000 9373118 96830484 1770463232 3.9276161194 4.0112681389 4.1859927177 202 1305031236.2383749485 0.1445886195 0.0730754754 0.1594968587 0.0265433469 0.0994930000 0.0119330000 0.0513480000 0.0001000000 0.0002950000 0.0276480000 9375336 96830484 1768321024 3.9262275696 4.0078678131 4.1896581650 203 1305031236.2699589729 0.1475620866 0.0734424045 0.1594968587 0.0264792602 0.1277060000 0.0099810000 0.0748100000 0.0002800000 0.0003410000 0.0338960000 9377522 96830484 1770098688 3.9264008999 4.0047025681 4.1918334961 204 1305031236.3069939613 0.1479854286 0.0738078115 0.1594968587 0.0264608955 0.1249220000 0.0120160000 0.0751540000 0.0000270000 0.0003130000 0.0253270000 9379836 96830484 1768321024 3.9281525612 4.0020809174 4.1936135292 205 1305031236.3392169476 0.1497729123 0.0741783730 0.1594968587 0.0264039621 0.1345200000 0.0099720000 0.0761740000 0.0002820000 0.0003350000 0.0453360000 9382054 96830484 1769984000 3.9303150177 3.9977865219 4.1944379807 206 1305031236.3700959682 0.1463026255 0.0745284907 0.1594968587 0.0263459078 0.1221410000 0.0121250000 0.0760730000 0.0000260000 0.0002820000 0.0242930000 9384240 96830484 1767960576 3.9323940277 3.9975724220 4.1903128624 207 1305031236.4058690071 0.1393303275 0.0748415430 0.1594968587 0.0263291483 0.1271520000 0.0098490000 0.0758330000 0.0002880000 0.0002640000 0.0304210000 9386522 96830484 1769619456 3.9370930195 3.9988868237 4.1861681938 208 1305031236.4387879372 0.1317581385 0.0751151805 0.1594968587 0.0262678952 0.1221820000 0.0117240000 0.0747230000 0.0000240000 0.0002910000 0.0234910000 9388740 96830484 1767813120 3.9434990883 4.0005888939 4.1816053391 209 1305031236.4751410484 0.1226527542 0.0753426330 0.1594968587 0.0262094166 0.1182170000 0.0098510000 0.0626460000 0.0003030000 0.0002820000 0.0425290000 9391054 96830484 1769590784 3.9496002197 4.0033955574 4.1757988930 210 1305031236.5077209473 0.1152639389 0.0755327345 0.1594968587 0.0261541879 0.1189150000 0.0093560000 0.0768830000 0.0000270000 0.0003040000 0.0223570000 9393304 96830484 1771237376 3.9522123337 4.0053958893 4.1690111160 211 1305031236.5386450291 0.1117538884 0.0757043987 0.1594968587 0.0261083292 0.1060280000 0.0113620000 0.0506490000 0.0002920000 0.0003500000 0.0296130000 9395490 96830484 1770147840 3.9497675896 4.0041513443 4.1588172913 212 1305031236.5740950108 0.1039376482 0.0758375744 0.1594968587 0.0260524501 0.0887080000 0.0116220000 0.0446190000 0.0000270000 0.0003120000 0.0221930000 9397772 96830484 1768611840 3.9492011070 4.0059046745 4.1499114037 213 1305031236.6057569981 0.1033270285 0.0759666329 0.1594968587 0.0259927389 0.1368380000 0.0114720000 0.0815800000 0.0006050000 0.0003530000 0.0403030000 9399958 96830484 1767194624 3.9506354332 4.0014657974 4.1449694633 214 1305031236.6384010315 0.0980639458 0.0760698914 0.1594968587 0.0259703566 0.1183690000 0.0095840000 0.0763470000 0.0000250000 0.0003130000 0.0215390000 9402176 96830484 1768857600 3.9526090622 4.0021257401 4.1382212639 215 1305031236.6751470566 0.0918191746 0.0761431438 0.1594968587 0.0259253119 0.1227200000 0.0097330000 0.0722780000 0.0003040000 0.0003530000 0.0278480000 9404426 96830484 1770491904 3.9539837837 4.0024137497 4.1317553520 216 1305031236.7033619881 0.0877485946 0.0761968728 0.1594968587 0.0258692362 0.0883480000 0.0117630000 0.0415930000 0.0000250000 0.0011040000 0.0215260000 9406548 96830484 1768939520 3.9613461494 4.0013856888 4.1292338371 217 1305031236.7339220047 0.0788511187 0.0762091043 0.1594968587 0.0258479307 0.1093610000 0.0112990000 0.0491320000 0.0003060000 0.0002730000 0.0425820000 9408702 96830484 1767813120 3.9609894753 4.0072274208 4.1180996895 218 1305031236.7740409374 0.0718057901 0.0761889056 0.1594968587 0.0258136135 0.1036530000 0.0098100000 0.0603920000 0.0000250000 0.0003740000 0.0205630000 9411016 96830484 1769365504 3.9611775875 4.0095000267 4.1098356247 219 1305031236.8025879860 0.0700388178 0.0761608230 0.1594968587 0.0258685622 0.1110390000 0.0097310000 0.0708380000 0.0003160000 0.0003420000 0.0265250000 9413202 96830484 1771126784 3.9612150192 4.0104250908 4.1007308960 220 1305031236.8364150524 0.0616886951 0.0760950406 0.1594968587 0.0258123451 0.0878760000 0.0117810000 0.0501070000 0.0000280000 0.0003040000 0.0200570000 9415388 96830484 1768976384 3.9636294842 4.0148806572 4.0938978195 221 1305031236.8743979931 0.0568728447 0.0760080624 0.1594968587 0.0257681326 0.1074870000 0.0113860000 0.0437310000 0.0003080000 0.0002740000 0.0472580000 9417670 96830484 1767591936 3.9639184475 4.0159296989 4.0859966278 222 1305031236.9060690403 0.0544466861 0.0759109391 0.1594968587 0.0257581992 0.1019540000 0.0098800000 0.0566280000 0.0000270000 0.0003030000 0.0225440000 9419856 96830484 1769349120 3.9660770893 4.0168390274 4.0787529945 223 1305031236.9344370365 0.0523134209 0.0758051206 0.1594968587 0.0257157130 0.1088100000 0.0096950000 0.0551130000 0.0003060000 0.0003490000 0.0309960000 9421978 96830484 1770999808 3.9690239429 4.0179700851 4.0730128288 224 1305031236.9744000435 0.0473414734 0.0756780507 0.1594968587 0.0256610408 0.1220520000 0.0117750000 0.0716870000 0.0000270000 0.0003810000 0.0254730000 9424260 96830484 1769230336 3.9725198746 4.0208091736 4.0680952072 225 1305031237.0074260235 0.0471179113 0.0755511168 0.1594968587 0.0256148455 0.1217080000 0.0097000000 0.0579800000 0.0003070000 0.0002740000 0.0507970000 9426510 96830484 1770971136 3.9811882973 4.0230536461 4.0657973289 226 1305031237.0370240211 0.0475564674 0.0754272467 0.1594968587 0.0255902388 0.1094930000 0.0110660000 0.0549470000 0.0000280000 0.0003150000 0.0297180000 9428664 96830484 1769209856 3.9862627983 4.0277171135 4.0621900558 227 1305031237.0734269619 0.0498758964 0.0753146856 0.1594968587 0.0255370758 0.1082890000 0.0097780000 0.0470870000 0.0003200000 0.0002730000 0.0386410000 9430882 96830484 1770987520 3.9911701679 4.0285348892 4.0584897995 228 1305031237.1059679985 0.0557595640 0.0752289176 0.1594968587 0.0254956160 0.1091690000 0.0120970000 0.0570010000 0.0000280000 0.0003740000 0.0323600000 9433100 96830484 1768828928 3.9987101555 4.0288572311 4.0563845634 229 1305031237.1378319263 0.0630619302 0.0751757866 0.1594968587 0.0254513897 0.1212690000 0.0098440000 0.0463030000 0.0003140000 0.0003520000 0.0617210000 9435286 96830484 1770381312 4.0074453354 4.0303630829 4.0540285110 230 1305031237.1712269783 0.0687457770 0.0751478301 0.1594968587 0.0254964393 0.1134270000 0.0114160000 0.0566760000 0.0000280000 0.0003810000 0.0353500000 9437504 96830484 1768472576 4.0142841339 4.0373802185 4.0548834801 231 1305031237.2042291164 0.0752913430 0.0751484513 0.1594968587 0.0254978843 0.1075580000 0.0098190000 0.0398990000 0.0003120000 0.0002770000 0.0468060000 9439658 96830484 1769984000 4.0215225220 4.0354628563 4.0518360138 232 1305031237.2375690937 0.0834612474 0.0751842823 0.1594968587 0.0254753170 0.0957300000 0.0113330000 0.0434700000 0.0000270000 0.0003860000 0.0378060000 9441908 96830484 1768071168 4.0292129517 4.0370755196 4.0498256683 233 1305031237.2746589184 0.0851160064 0.0752269078 0.1594968587 0.0254422387 0.1405560000 0.0093470000 0.0450610000 0.0003070000 0.0006840000 0.0715680000 9444158 96830484 1768304640 4.0300388336 4.0381221771 4.0430092812 234 1305031237.3058099747 0.0874846950 0.0752792915 0.1594968587 0.0253938354 0.1298330000 0.0192780000 0.0563200000 0.0000260000 0.0003030000 0.0397650000 9446344 96830484 1769963520 4.0311808586 4.0387005806 4.0349330902 235 1305031237.3371419907 0.0895174444 0.0753398794 0.1594968587 0.0253764762 0.1105260000 0.0121450000 0.0460480000 0.0003130000 0.0003510000 0.0489620000 9448530 96830484 1767694336 4.0309934616 4.0384449959 4.0264782906 236 1305031237.3741660118 0.0905398130 0.0754042859 0.1594968587 0.0253415181 0.1064100000 0.0099750000 0.0472640000 0.0000280000 0.0003080000 0.0414220000 9450748 96830484 1769500672 4.0282406807 4.0420632362 4.0166363716 237 1305031237.4057340622 0.0903303474 0.0754672650 0.1594968587 0.0253404659 0.1473390000 0.0097730000 0.0469220000 0.0003170000 0.0003480000 0.0794740000 9452966 96830484 1771134976 4.0233335495 4.0512447357 4.0123343468 238 1305031237.4377219677 0.0949950293 0.0755493144 0.1594968587 0.0253375025 0.1296720000 0.0117890000 0.0690920000 0.0000260000 0.0002910000 0.0425370000 9455152 96830484 1769472000 4.0252099037 4.0550136566 4.0087308884 239 1305031237.4741280079 0.0964115486 0.0756366041 0.1594968587 0.0253048422 0.1275570000 0.0101010000 0.0578360000 0.0003030000 0.0003450000 0.0519710000 9457370 96830484 1771118592 4.0208501816 4.0613493919 4.0020365715 240 1305031237.5060451031 0.0987767279 0.0757330213 0.1594968587 0.0252883775 0.1086830000 0.0118040000 0.0473340000 0.0000260000 0.0003040000 0.0448710000 9459588 96830484 1768947712 4.0169806480 4.0712003708 4.0020532608 241 1305031237.5376501083 0.1007246971 0.0758367212 0.1594968587 0.0252442648 0.1482740000 0.0098320000 0.0527060000 0.0007080000 0.0002790000 0.0818570000 9461774 96830484 1770483712 4.0181427002 4.0716462135 3.9972519875 242 1305031237.5739479065 0.1015971452 0.0759431692 0.1594968587 0.0252037285 0.1277090000 0.0116460000 0.0652040000 0.0000280000 0.0002950000 0.0468060000 9463992 96830484 1768583168 4.0133280754 4.0743989944 3.9911777973 243 1305031237.6068129539 0.1067785621 0.0760700639 0.1594968587 0.0251758437 0.1249830000 0.0099440000 0.0470350000 0.0003800000 0.0005770000 0.0546180000 9466242 96830484 1770389504 4.0133185387 4.0858941078 3.9965608120 244 1305031237.6378550529 0.1091916189 0.0762058079 0.1594968587 0.0251330356 0.1113620000 0.0117780000 0.0518750000 0.0000300000 0.0006340000 0.0442310000 9468396 96830484 1768710144 4.0125484467 4.0899391174 3.9960296154 245 1305031237.6752760410 0.1125145406 0.0763540069 0.1594968587 0.0250978092 0.1498120000 0.0097810000 0.0523270000 0.0003720000 0.0002930000 0.0840740000 9470646 96830484 1770233856 4.0089087486 4.0967264175 3.9972743988 246 1305031237.7071180344 0.1135225967 0.0765050987 0.1594968587 0.0250493546 0.1265530000 0.0118070000 0.0678580000 0.0000290000 0.0003710000 0.0436270000 9472864 96830484 1768583168 4.0065512657 4.0989637375 3.9963512421 247 1305031237.7416670322 0.1152506173 0.0766619631 0.1594968587 0.0250293090 0.1230710000 0.0095070000 0.0405170000 0.0003040000 0.0002800000 0.0582950000 9475082 96830484 1770090496 4.0034794807 4.1045279503 4.0005426407 248 1305031237.7743060589 0.1150824055 0.0768168843 0.1594968587 0.0250629027 0.1496000000 0.0110740000 0.0832830000 0.0000260000 0.0002890000 0.0470620000 9477236 96830484 1768476672 4.0076231956 4.1010150909 3.9997589588 249 1305031237.8064959049 0.1126299426 0.0769607118 0.1594968587 0.0250205945 0.1653320000 0.0098850000 0.0672560000 0.0003580000 0.0005020000 0.0844370000 9479454 96830484 1770106880 4.0033259392 4.0988831520 3.9940953255 250 1305031237.8430309296 0.1175841242 0.0771232055 0.1594968587 0.0251050541 0.1097740000 0.0118570000 0.0398170000 0.0000250000 0.0002890000 0.0490990000 9481736 96830484 1768095744 4.0008301735 4.1085877419 4.0040230751 251 1305031237.8754220009 0.1146405563 0.0772726770 0.1594968587 0.0252986706 0.1461650000 0.0093300000 0.0670240000 0.0003130000 0.0003530000 0.0551410000 9483890 96830484 1769754624 4.0066866875 4.1008276939 3.9999980927 252 1305031237.9077839851 0.1116112024 0.0774089410 0.1594968587 0.0252651370 0.1092810000 0.0118420000 0.0408200000 0.0000260000 0.0003520000 0.0468750000 9486108 96830484 1767968768 4.0032258034 4.0971779823 3.9936966896 253 1305031237.9441869259 0.1196486354 0.0775758963 0.1594968587 0.0254407453 0.1480350000 0.0101270000 0.0399640000 0.0003680000 0.0002720000 0.0884550000 9488358 96830484 1769594880 4.0053491592 4.1101665497 4.0105299950 254 1305031237.9738099575 0.1215625033 0.0777490719 0.1594968587 0.0254063978 0.1093440000 0.0119090000 0.0474620000 0.0000290000 0.0003150000 0.0467170000 9490448 96830484 1767587840 4.0125494003 4.1090669632 4.0184750557 255 1305031238.0069320202 0.1192038879 0.0779116398 0.1594968587 0.0253718273 0.1206320000 0.0100890000 0.0414800000 0.0002910000 0.0002710000 0.0543430000 9492698 96830484 1769472000 4.0167646408 4.1043620110 4.0252122879 256 1305031238.0431399345 0.1198518723 0.0780754688 0.1594968587 0.0255524778 0.1097720000 0.0101360000 0.0463360000 0.0000260000 0.0003060000 0.0449020000 9494948 96830484 1771028480 4.0270800591 4.0988883972 4.0375800133 257 1305031238.0740320683 0.1119421497 0.0782072458 0.1594968587 0.0255840071 0.1770880000 0.0117970000 0.0679240000 0.0003030000 0.0002790000 0.0816140000 9517582 96830484 1768964096 4.0325579643 4.0830488205 4.0400710106 258 1305031238.1065878868 0.1025304422 0.0783015218 0.1594968587 0.0256057685 0.1364560000 0.0155330000 0.0746170000 0.0000270000 0.0003020000 0.0428590000 9561752 96830484 1770868736 4.0349488258 4.0654611588 4.0412836075 259 1305031238.1433279514 0.1012126952 0.0783899819 0.1594968587 0.0256573506 0.1436230000 0.0111440000 0.0662940000 0.0003070000 0.0003570000 0.0508220000 9564002 96830484 1768984576 4.0376105309 4.0584373474 4.0484676361 260 1305031238.1723001003 0.0967321470 0.0784605287 0.1594968587 0.0256329100 0.1304130000 0.0094810000 0.0784750000 0.0000310000 0.0003790000 0.0378600000 9566188 96830484 1770725376 4.0306077003 4.0628585815 4.0600118637 261 1305031238.2054259777 0.0958009735 0.0785269672 0.1594968587 0.0264293424 0.1419130000 0.0119200000 0.0657160000 0.0000280000 0.0003670000 0.0608630000 9568342 96830484 1768964096 4.0306077003 4.0628585815 4.0600118637 262 1305031238.2401471138 0.0816053525 0.0785387167 0.1594968587 0.0268242293 0.1123080000 0.0097460000 0.0598220000 0.0000260000 0.0003010000 0.0345750000 9570592 96830484 1770741760 4.0175981522 4.0581164360 4.0627989769 263 1305031238.2725269794 0.0687897205 0.0785016483 0.1594968587 0.0267813010 0.1072020000 0.0116910000 0.0387900000 0.0022610000 0.0003580000 0.0433830000 9572810 96830484 1768603648 4.0039186478 4.0577611923 4.0588393211 264 1305031238.3060529232 0.0619126111 0.0784388110 0.1594968587 0.0269528413 0.1453260000 0.0092800000 0.1001900000 0.0000070000 0.0000620000 0.0326910000 9574996 96830484 1770360832 3.9924898148 4.0651555061 4.0586142540 265 1305031238.3425960541 0.0503809713 0.0783329324 0.1594968587 0.0270216385 0.1628290000 0.0150680000 0.0841130000 0.0003190000 0.0002840000 0.0598440000 9577246 96830484 1768456192 3.9837112427 4.0548534393 4.0521578789 266 1305031238.3741040230 0.0468258858 0.0782144849 0.1594968587 0.0269943858 0.1103440000 0.0101230000 0.0614970000 0.0000290000 0.0003660000 0.0289210000 9579432 96830484 1770262528 3.9790320396 4.0490560532 4.0487203598 267 1305031238.4060359001 0.0438932888 0.0780859410 0.1594968587 0.0269454090 0.1291340000 0.0116030000 0.0759650000 0.0003990000 0.0002870000 0.0346290000 9581618 96830484 1768312832 3.9768707752 4.0450906754 4.0512166023 268 1305031238.4434239864 0.0440629683 0.0779589897 0.1594968587 0.0269006259 0.0873800000 0.0095740000 0.0472090000 0.0000290000 0.0003000000 0.0246700000 9583868 96830484 1770127360 3.9744424820 4.0405697823 4.0510716438 269 1305031238.4740819931 0.0449209213 0.0778361716 0.1594968587 0.0268639363 0.1447970000 0.0114890000 0.0704030000 0.0002940000 0.0003480000 0.0472680000 9586054 96830484 1768448000 3.9745700359 4.0360980034 4.0538640022 270 1305031238.5058109760 0.0458917320 0.0777178588 0.1594968587 0.0268868852 0.0879990000 0.0097830000 0.0412390000 0.0000240000 0.0003580000 0.0223700000 9588240 96830484 1770000384 3.9723246098 4.0306897163 4.0555558205 271 1305031238.5432639122 0.0498520583 0.0776150330 0.1594968587 0.0268391169 0.1280100000 0.0116180000 0.0723070000 0.0002940000 0.0003500000 0.0289850000 9590522 96830484 1768341504 3.9696919918 4.0245466232 4.0560011864 272 1305031238.5741839409 0.0488887690 0.0775094217 0.1594968587 0.0267965033 0.0885700000 0.0098780000 0.0478870000 0.0000260000 0.0002910000 0.0214280000 9592644 96830484 1770000384 3.9672906399 4.0248017311 4.0590353012 273 1305031238.6058249474 0.0505625717 0.0774107153 0.1594968587 0.0267512805 0.1105660000 0.0117660000 0.0542650000 0.0005520000 0.0002960000 0.0404790000 9594862 96830484 1768214528 3.9634132385 4.0220308304 4.0606827736 274 1305031238.6427590847 0.0516855121 0.0773168277 0.1594968587 0.0267070999 0.1001900000 0.0095490000 0.0533600000 0.0000280000 0.0002940000 0.0212340000 9597144 96830484 1769873408 3.9631052017 4.0208945274 4.0648465157 275 1305031238.6738131046 0.0546254590 0.0772343136 0.1594968587 0.0266642065 0.0915560000 0.0117150000 0.0466230000 0.0003170000 0.0002710000 0.0294850000 9599266 96830484 1768067072 3.9597158432 4.0199785233 4.0661220551 276 1305031238.7051889896 0.0548898615 0.0771533555 0.1594968587 0.0266170092 0.1245860000 0.0101950000 0.0805520000 0.0000300000 0.0003620000 0.0229610000 9601452 96830484 1767161856 3.9579753876 4.0212044716 4.0687494278 277 1305031238.7413070202 0.0593622029 0.0770891275 0.1594968587 0.0266059962 0.1574830000 0.0091350000 0.0985300000 0.0000610000 0.0000540000 0.0465320000 9603734 96830484 1768988672 3.9548876286 4.0175533295 4.0700855255 278 1305031238.7717959881 0.0644673407 0.0770437254 0.1594968587 0.0265862946 0.1379080000 0.0091570000 0.1056770000 0.0000280000 0.0003000000 0.0195620000 9605920 96830484 1770618880 3.9512608051 4.0138163567 4.0704407692 279 1305031238.8070189953 0.0664310083 0.0770056870 0.1594968587 0.0265613317 0.1289390000 0.0114310000 0.0795610000 0.0002980000 0.0002830000 0.0290480000 9608170 96830484 1768955904 3.9489052296 4.0150661469 4.0714731216 280 1305031238.8429400921 0.0691854879 0.0769777577 0.1594968587 0.0265175729 0.1231780000 0.0101150000 0.0743310000 0.0000300000 0.0003750000 0.0224190000 9610452 96830484 1770635264 3.9487006664 4.0129361153 4.0756754875 281 1305031238.8737230301 0.0784466043 0.0769829849 0.1594968587 0.0265261587 0.1119300000 0.0120130000 0.0502050000 0.0003810000 0.0002830000 0.0458210000 9612670 96830484 1768448000 3.9486150742 4.0048441887 4.0789179802 282 1305031238.9061720371 0.0834825635 0.0770060331 0.1594968587 0.0264921969 0.1247420000 0.0096630000 0.0771850000 0.0000290000 0.0003700000 0.0229160000 9614856 96830484 1770233856 3.9490504265 4.0005521774 4.0824561119 283 1305031238.9427859783 0.0844765231 0.0770324305 0.1594968587 0.0264455032 0.1289570000 0.0118220000 0.0752540000 0.0005480000 0.0002890000 0.0298290000 9617170 96830484 1768304640 3.9477207661 4.0011720657 4.0825028419 284 1305031238.9723079205 0.0894680321 0.0770762179 0.1594968587 0.0264084242 0.1253270000 0.0098880000 0.0756000000 0.0000290000 0.0005420000 0.0232080000 9619356 96830484 1770254336 3.9494459629 3.9968080521 4.0873656273 285 1305031239.0104830265 0.0907655433 0.0771242506 0.1594968587 0.0263840166 0.1313330000 0.0113100000 0.0700270000 0.0003060000 0.0003490000 0.0460950000 9621670 96830484 1769357312 3.9482769966 3.9975252151 4.0866122246 286 1305031239.0408790112 0.0938120186 0.0771825994 0.1594968587 0.0263436202 0.1052920000 0.0092830000 0.0576890000 0.0000260000 0.0003030000 0.0235460000 9623856 96830484 1771036672 3.9469769001 3.9954757690 4.0882859230 287 1305031239.0746610165 0.1013748944 0.0772668931 0.1594968587 0.0263443728 0.1106230000 0.0114160000 0.0638550000 0.0003130000 0.0002760000 0.0303400000 9626106 96830484 1770225664 3.9477536678 3.9885466099 4.0930037498 288 1305031239.1109058857 0.1041306555 0.0773601701 0.1594968587 0.0262989518 0.1254720000 0.0118270000 0.0770890000 0.0000260000 0.0003070000 0.0236580000 9628420 96830484 1768468480 3.9474332333 3.9860634804 4.0937075615 289 1305031239.1417789459 0.1054512411 0.0774573710 0.1594968587 0.0262643404 0.1325960000 0.0098340000 0.0759210000 0.0003050000 0.0005250000 0.0425980000 9630606 96830484 1770106880 3.9466848373 3.9842119217 4.0937590599 290 1305031239.1757500172 0.1057325900 0.0775548718 0.1594968587 0.0262551987 0.1036320000 0.0116130000 0.0579070000 0.0000280000 0.0003770000 0.0232670000 9632856 96830484 1768431616 3.9453606606 3.9832363129 4.0896720886 291 1305031239.2096450329 0.1023962721 0.0776402374 0.1594968587 0.0262186037 0.1076500000 0.0097470000 0.0580960000 0.0003110000 0.0002690000 0.0302320000 9635106 96830484 1770127360 3.9461648464 3.9861433506 4.0873284340 292 1305031239.2417099476 0.1026089862 0.0777257468 0.1594968587 0.0261910982 0.1093240000 0.0118240000 0.0701670000 0.0000280000 0.0002990000 0.0231320000 9637324 96830484 1768321024 3.9449770451 3.9850549698 4.0845766068 293 1305031239.2738199234 0.1000436991 0.0778019173 0.1594968587 0.0261652081 0.1327390000 0.0098050000 0.0761650000 0.0003100000 0.0003540000 0.0427930000 9639542 96830484 1769979904 3.9458909035 3.9862658978 4.0823040009 294 1305031239.3101770878 0.0985106230 0.0778723551 0.1594968587 0.0261214359 0.1213190000 0.0115720000 0.0759310000 0.0001010000 0.0003020000 0.0232400000 9641856 96830484 1769230336 3.9459249973 3.9868328571 4.0794973373 295 1305031239.3419699669 0.0950562283 0.0779306055 0.1594968587 0.0260823696 0.1090210000 0.0097440000 0.0627580000 0.0003050000 0.0002820000 0.0296060000 9644074 96830484 1770909696 3.9470133781 3.9892480373 4.0769782066 296 1305031239.3750240803 0.0918634385 0.0779776759 0.1594968587 0.0260521091 0.1254240000 0.0112410000 0.0747800000 0.0000290000 0.0003080000 0.0226300000 9646260 96830484 1769975808 3.9477627277 3.9909527302 4.0742874146 297 1305031239.4106309414 0.0878356621 0.0780108678 0.1594968587 0.0260094271 0.1316000000 0.0116590000 0.0740330000 0.0003000000 0.0002700000 0.0419420000 9648510 96830484 1768341504 3.9486789703 3.9939148426 4.0718512535 298 1305031239.4415419102 0.0879998729 0.0780443879 0.1594968587 0.0259687408 0.1220620000 0.0093500000 0.0739730000 0.0000270000 0.0003830000 0.0219220000 9650696 96830484 1769955328 3.9506263733 3.9923019409 4.0707201958 299 1305031239.4733181000 0.0802072361 0.0780516215 0.1594968587 0.0259288783 0.1263820000 0.0116280000 0.0729760000 0.0005350000 0.0002800000 0.0288850000 9652882 96830484 1768194048 3.9518713951 3.9991350174 4.0678634644 300 1305031239.5097389221 0.0748851821 0.0780410667 0.1594968587 0.0258905553 0.1091740000 0.0098380000 0.0726020000 0.0000280000 0.0003670000 0.0218160000 9655132 96830484 1769852928 3.9547362328 4.0039157867 4.0656061172 301 1305031239.5438020229 0.0711847916 0.0780182884 0.1594968587 0.0258559180 0.1110430000 0.0114400000 0.0546210000 0.0005230000 0.0002880000 0.0407780000 9657382 96830484 1768214528 3.9556734562 4.0066256523 4.0622067451 302 1305031239.5761160851 0.0690397471 0.0779885581 0.1594968587 0.0258211846 0.1018050000 0.0094100000 0.0549130000 0.0000290000 0.0003190000 0.0219390000 9659568 96830484 1769873408 3.9566082954 4.0083284378 4.0593628883 303 1305031239.6111609936 0.0673312843 0.0779533856 0.1594968587 0.0257822776 0.1089970000 0.0111320000 0.0590790000 0.0002980000 0.0002760000 0.0283450000 9661818 96830484 1768960000 3.9580564499 4.0098619461 4.0565166473 304 1305031239.6414220333 0.0671804249 0.0779179482 0.1594968587 0.0257428327 0.1086500000 0.0096910000 0.0711070000 0.0000250000 0.0002890000 0.0213190000 9663972 96830484 1770635264 3.9590575695 4.0097932816 4.0530896187 305 1305031239.6710560322 0.0639652982 0.0778722019 0.1594968587 0.0257161599 0.1237280000 0.0113040000 0.0718930000 0.0002950000 0.0002780000 0.0364670000 9666094 96830484 1769971712 3.9590590000 4.0133538246 4.0495986938 306 1305031239.7075550556 0.0626433119 0.0778224342 0.1594968587 0.0257114841 0.1120670000 0.0118560000 0.0721640000 0.0000290000 0.0002940000 0.0219090000 9668344 96830484 1768050688 3.9649684429 4.0142340660 4.0490674973 307 1305031239.7417550087 0.0630539581 0.0777743285 0.1594968587 0.0256707868 0.1075350000 0.0095550000 0.0610000000 0.0003620000 0.0002770000 0.0297340000 9670594 96830484 1769861120 3.9657034874 4.0134649277 4.0448265076 308 1305031239.7712600231 0.0629211664 0.0777261039 0.1594968587 0.0256307428 0.1079600000 0.0113800000 0.0661230000 0.0000260000 0.0003660000 0.0237640000 9672716 96830484 1768087552 3.9725022316 4.0144653320 4.0446515083 309 1305031239.8060870171 0.0639277026 0.0776814489 0.1594968587 0.0256699651 0.1098710000 0.0097850000 0.0478860000 0.0003120000 0.0002730000 0.0480830000 9674934 96830484 1769844736 3.9803786278 4.0141420364 4.0443291664 310 1305031239.8392889500 0.0592720620 0.0776220638 0.1594968587 0.0256824409 0.1042720000 0.0111120000 0.0481020000 0.0000280000 0.0003050000 0.0277020000 9677152 96830484 1768747008 3.9801251888 4.0216388702 4.0415511131 311 1305031239.8744299412 0.0571992546 0.0775563956 0.1594968587 0.0256478913 0.1094460000 0.0098270000 0.0463080000 0.0003190000 0.0002750000 0.0445870000 9679338 96830484 1768210432 3.9805028439 4.0250945091 4.0401458740 312 1305031239.9090619087 0.0594606362 0.0774983963 0.1594968587 0.0256524241 0.0916640000 0.0095570000 0.0517310000 0.0000280000 0.0003010000 0.0263870000 9681588 96830484 1767325696 3.9868347645 4.0273704529 4.0410113335 313 1305031239.9403729439 0.0615079291 0.0774473086 0.1594968587 0.0256373762 0.1201520000 0.0088920000 0.0466690000 0.0003210000 0.0003570000 0.0602350000 9683742 96830484 1766326272 3.9914667606 4.0311555862 4.0416030884 314 1305031239.9710669518 0.0650782436 0.0774079167 0.1594968587 0.0256515972 0.1113930000 0.0095150000 0.0623010000 0.0000060000 0.0000620000 0.0332480000 9685928 96830484 1765130240 3.9972271919 4.0352311134 4.0442047119 315 1305031240.0088651180 0.0696256459 0.0773832110 0.1594968587 0.0256776501 0.1271290000 0.0093760000 0.0666120000 0.0003160000 0.0003530000 0.0414970000 9688242 96830484 1765036032 4.0024685860 4.0327768326 4.0425238609 316 1305031240.0396599770 0.0759457871 0.0773786622 0.1594968587 0.0256439145 0.1072880000 0.0107440000 0.0517680000 0.0000300000 0.0003780000 0.0353340000 9690364 96830484 1764044800 4.0096602440 4.0333952904 4.0422945023 317 1305031240.0711870193 0.0833507702 0.0773975017 0.1594968587 0.0256045452 0.1461300000 0.0095590000 0.0514810000 0.0003880000 0.0002770000 0.0686720000 9692550 96830484 1765670912 4.0179123878 4.0318684578 4.0434069633 318 1305031240.1093459129 0.0895469338 0.0774357074 0.1594968587 0.0256175872 0.1103100000 0.0098690000 0.0557130000 0.0000200000 0.0002050000 0.0377280000 9694832 96830484 1767165952 4.0246810913 4.0272321701 4.0398778915 319 1305031240.1435019970 0.0974625647 0.0774984876 0.1594968587 0.0256381647 0.1276240000 0.0095260000 0.0612830000 0.0003840000 0.0002700000 0.0473850000 9697082 96830484 1768943616 4.0328292847 4.0218334198 4.0332536697 320 1305031240.1775770187 0.1008005887 0.0775713066 0.1594968587 0.0256094465 0.1085670000 0.0094820000 0.0514260000 0.0000270000 0.0003050000 0.0400300000 9699268 96830484 1770717184 4.0361638069 4.0286059380 4.0333666801 321 1305031240.2093310356 0.1057027206 0.0776589434 0.1594968587 0.0256552936 0.1780220000 0.0120630000 0.0685820000 0.0003040000 0.0003450000 0.0787290000 9701486 96830484 1769574400 4.0410456657 4.0284571648 4.0268716812 322 1305031240.2410049438 0.1077677310 0.0777524490 0.1594968587 0.0256417019 0.1109700000 0.0115780000 0.0464540000 0.0000300000 0.0003150000 0.0432790000 9703640 96830484 1767829504 4.0406780243 4.0363807678 4.0181093216 323 1305031240.2774341106 0.1109146029 0.0778551182 0.1594968587 0.0256110339 0.1465270000 0.0096490000 0.0699580000 0.0004930000 0.0002760000 0.0536870000 9705890 96830484 1769472000 4.0412640572 4.0507273674 4.0222506523 324 1305031240.3089289665 0.1116497368 0.0779594226 0.1594968587 0.0255834839 0.1108470000 0.0098010000 0.0529140000 0.0000270000 0.0003030000 0.0441770000 9708044 96830484 1771257856 4.0371608734 4.0591912270 4.0137085915 325 1305031240.3422729969 0.1155306250 0.0780750263 0.1594968587 0.0255742106 0.1536260000 0.0118560000 0.0529910000 0.0003030000 0.0002700000 0.0845420000 9710262 96830484 1769086976 4.0303759575 4.0789427757 4.0169053078 326 1305031240.3774259090 0.1221898720 0.0782103479 0.1594968587 0.0255882342 0.1388880000 0.0105170000 0.0695070000 0.0000270000 0.0003050000 0.0479010000 9712512 96830484 1770635264 4.0231504440 4.0972414017 4.0199398994 327 1305031240.4091110229 0.1246653795 0.0783524122 0.1594968587 0.0255570686 0.1297870000 0.0118580000 0.0573720000 0.0003790000 0.0002760000 0.0561520000 9714666 96830484 1768833024 4.0105524063 4.1100411415 4.0151605606 328 1305031240.4417860508 0.1348626465 0.0785246995 0.1594968587 0.0255274276 0.1068880000 0.0096980000 0.0399140000 0.0000600000 0.0002060000 0.0531800000 9716884 96830484 1770336256 4.0020227432 4.1266269684 4.0201215744 329 1305031240.4776389599 0.1455959976 0.0787285636 0.1594968587 0.0254990209 0.1867720000 0.0112190000 0.0750130000 0.0003130000 0.0003480000 0.0916870000 9719134 96830484 1768452096 3.9951465130 4.1411886215 4.0254788399 330 1305031240.5084490776 0.1511046290 0.0789478850 0.1594968587 0.0254727781 0.1268990000 0.0096480000 0.0564150000 0.0000280000 0.0003860000 0.0504420000 9721256 96830484 1770000384 3.9916565418 4.1478214264 4.0255899429 331 1305031240.5412700176 0.1613798141 0.0791969241 0.1613798141 0.0254754908 0.1466260000 0.0116230000 0.0603290000 0.0003140000 0.0003590000 0.0591350000 9723474 96830484 1768345600 3.9839696884 4.1604833603 4.0324978828 332 1305031240.5759088993 0.1672170013 0.0794620448 0.1672170013 0.0254500138 0.1303690000 0.0099060000 0.0647020000 0.0000290000 0.0007040000 0.0512570000 9725724 96830484 1769967616 3.9849376678 4.1654014587 4.0380501747 333 1305031240.6101338863 0.1651384234 0.0797193312 0.1672170013 0.0254234119 0.1582920000 0.0117180000 0.0513880000 0.0003110000 0.0004980000 0.0905940000 9727942 96830484 1767944192 3.9868834019 4.1629009247 4.0388531685 334 1305031240.6398229599 0.1616585106 0.0799646581 0.1672170013 0.0254086591 0.1338010000 0.0108480000 0.0658220000 0.0000290000 0.0003020000 0.0505940000 9730064 96830484 1769590784 3.9914767742 4.1578788757 4.0414538383 335 1305031240.6747570038 0.1519788355 0.0801796258 0.1672170013 0.0253786331 0.1468230000 0.0115250000 0.0672960000 0.0003080000 0.0003510000 0.0582260000 9732314 96830484 1767854080 3.9998667240 4.1455726624 4.0408515930 336 1305031240.7079319954 0.1466173232 0.0803773571 0.1672170013 0.0253740368 0.1431130000 0.0098520000 0.0684120000 0.0000280000 0.0002960000 0.0504020000 9734532 96830484 1769492480 4.0025820732 4.1391158104 4.0432772636 337 1305031240.7439579964 0.1441326737 0.0805665420 0.1672170013 0.0253470224 0.1702770000 0.0117660000 0.0680650000 0.0003130000 0.0002800000 0.0859850000 9736718 96830484 1767813120 4.0078949928 4.1351027489 4.0489058495 338 1305031240.7768330574 0.1327160299 0.0807208304 0.1672170013 0.0253183649 0.1093550000 0.0095810000 0.0516660000 0.0000310000 0.0003150000 0.0437980000 9738968 96830484 1769361408 4.0124158859 4.1209030151 4.0441937447 339 1305031240.8096249104 0.1289497763 0.0808630987 0.1672170013 0.0253012008 0.1234460000 0.0093760000 0.0411910000 0.0003800000 0.0002780000 0.0579380000 9741154 96830484 1771274240 4.0136427879 4.1165161133 4.0469064713 340 1305031240.8425960541 0.1240579635 0.0809901424 0.1672170013 0.0252853886 0.1492420000 0.0111690000 0.0889690000 0.0000310000 0.0003780000 0.0433610000 9743340 96830484 1769357312 4.0173945427 4.1093668938 4.0513687134 341 1305031240.8794100285 0.1108925715 0.0810778328 0.1672170013 0.0252635092 0.1816640000 0.0113720000 0.0801490000 0.0000610000 0.0000540000 0.0861810000 9745622 96830484 1770844160 4.0197753906 4.0919766426 4.0444335938 342 1305031240.9084498882 0.1039667800 0.0811447595 0.1672170013 0.0252462005 0.1435460000 0.0118680000 0.0688900000 0.0000250000 0.0003030000 0.0430470000 9747776 96830484 1769209856 4.0194630623 4.0837311745 4.0456452370 343 1305031240.9423189163 0.0863049626 0.0811598039 0.1672170013 0.0252568245 0.1475170000 0.0101070000 0.0676760000 0.0003750000 0.0002730000 0.0494550000 9749962 96830484 1770762240 4.0056271553 4.0729913712 4.0387039185 344 1305031240.9779360294 0.0769790933 0.0811476506 0.1672170013 0.0252308839 0.1105560000 0.0119620000 0.0518600000 0.0000290000 0.0003670000 0.0396210000 9752212 96830484 1768722432 4.0041022301 4.0598473549 4.0368456841 345 1305031241.0083029270 0.0708565116 0.0811178213 0.1672170013 0.0253233556 0.1458120000 0.0097670000 0.0616630000 0.0003020000 0.0002690000 0.0698850000 9754366 96830484 1770381312 3.9997043610 4.0597572327 4.0425748825 346 1305031241.0401480198 0.0661816299 0.0810746531 0.1672170013 0.0253030487 0.1282290000 0.0114160000 0.0665040000 0.0000270000 0.0002990000 0.0366920000 9756488 96830484 1768701952 3.9965729713 4.0632185936 4.0543928146 347 1305031241.0759329796 0.0583968759 0.0810092992 0.1672170013 0.0252884775 0.1076610000 0.0097610000 0.0395990000 0.0003780000 0.0002800000 0.0458890000 9758770 96830484 1770397696 3.9902448654 4.0612168312 4.0528049469 348 1305031241.1065559387 0.0524816923 0.0809273234 0.1672170013 0.0252614584 0.1166270000 0.0106350000 0.0709000000 0.0000280000 0.0003950000 0.0305070000 9760924 96830484 1769574400 3.9830310345 4.0639567375 4.0565261841 349 1305031241.1400520802 0.0476901196 0.0808320878 0.1672170013 0.0252545883 0.1326600000 0.0093970000 0.0590690000 0.0003040000 0.0002800000 0.0595680000 9763110 96830484 1771147264 3.9771392345 4.0650129318 4.0568876266 350 1305031241.1781818867 0.0428526998 0.0807235753 0.1672170013 0.0252565533 0.1124180000 0.0119660000 0.0518470000 0.0000270000 0.0003010000 0.0306860000 9765392 96830484 1769230336 3.9743254185 4.0619263649 4.0567054749 351 1305031241.2106790543 0.0375849903 0.0806006733 0.1672170013 0.0252274873 0.1098800000 0.0099660000 0.0558970000 0.0003000000 0.0006000000 0.0361090000 9767610 96830484 1770868736 3.9664585590 4.0585589409 4.0535087585 352 1305031241.2393150330 0.0373542048 0.0804778140 0.1672170013 0.0252697456 0.1083000000 0.0115360000 0.0633820000 0.0000270000 0.0003030000 0.0279180000 9769700 96830484 1768955904 3.9672937393 4.0524444580 4.0528020859 353 1305031241.2768468857 0.0369333252 0.0803544586 0.1672170013 0.0252569604 0.1218960000 0.0094920000 0.0409360000 0.0002910000 0.0002690000 0.0512420000 9772014 96830484 1770762240 3.9670281410 4.0488591194 4.0531172752 354 1305031241.3063299656 0.0356568955 0.0802281943 0.1672170013 0.0252229770 0.1115090000 0.0118860000 0.0687510000 0.0000280000 0.0003660000 0.0244840000 9774168 96830484 1769082880 3.9652924538 4.0493321419 4.0548114777 355 1305031241.3424758911 0.0347810350 0.0801001741 0.1672170013 0.0252107731 0.1047120000 0.0095320000 0.0477690000 0.0007120000 0.0002980000 0.0299260000 9776418 96830484 1770749952 3.9692099094 4.0469384193 4.0607933998 356 1305031241.3795149326 0.0399889350 0.0799875021 0.1672170013 0.0252499600 0.1107460000 0.0114110000 0.0718220000 0.0000260000 0.0003600000 0.0223270000 9778668 96830484 1769066496 3.9670228958 4.0402765274 4.0604081154 357 1305031241.4096820354 0.0438691303 0.0798863302 0.1672170013 0.0252318367 0.1281080000 0.0095700000 0.0723110000 0.0003730000 0.0002840000 0.0413840000 9780822 96830484 1770749952 3.9668948650 4.0375523567 4.0629129410 358 1305031241.4455459118 0.0471187532 0.0797948006 0.1672170013 0.0252105110 0.0871980000 0.0117610000 0.0481350000 0.0000300000 0.0003140000 0.0214700000 9783072 96830484 1769082880 3.9667685032 4.0365962982 4.0677456856 359 1305031241.4775071144 0.0511392131 0.0797149800 0.1672170013 0.0253852315 0.1053860000 0.0114720000 0.0515430000 0.0003200000 0.0002670000 0.0300130000 9785258 96830484 1767428096 3.9653987885 4.0326986313 4.0701618195 360 1305031241.5098490715 0.0552937277 0.0796471432 0.1672170013 0.0253792405 0.1085400000 0.0092580000 0.0702060000 0.0000260000 0.0003030000 0.0219950000 9787444 96830484 1769254912 3.9621052742 4.0288343430 4.0694770813 361 1305031241.5477299690 0.0586390570 0.0795889491 0.1672170013 0.0253560975 0.1407990000 0.0092510000 0.0660470000 0.0003040000 0.0002820000 0.0440180000 9789758 96830484 1770868736 3.9579503536 4.0262680054 4.0654072762 362 1305031241.5783948898 0.0584828593 0.0795306450 0.1672170013 0.0253384320 0.1106300000 0.0114460000 0.0653690000 0.0000280000 0.0003050000 0.0215360000 9791880 96830484 1769844736 3.9597492218 4.0262398720 4.0668644905 363 1305031241.6092638969 0.0597788095 0.0794762322 0.1672170013 0.0253364021 0.1341510000 0.0113070000 0.0719630000 0.0003080000 0.0002720000 0.0281600000 9794034 96830484 1768304640 3.9603374004 4.0249047279 4.0643529892 364 1305031241.6475839615 0.0625221953 0.0794296552 0.1672170013 0.0253065157 0.1084690000 0.0094020000 0.0740220000 0.0000280000 0.0003010000 0.0205740000 9796348 96830484 1770016768 3.9606091976 4.0212097168 4.0617609024 365 1305031241.6783659458 0.0562106036 0.0793660413 0.1672170013 0.0253373457 0.1297800000 0.0110890000 0.0734550000 0.0003860000 0.0002810000 0.0403190000 9798534 96830484 1768865792 3.9622991085 4.0275893211 4.0613231659 366 1305031241.7098269463 0.0556603931 0.0793012718 0.1672170013 0.0253091358 0.1022780000 0.0092100000 0.0551910000 0.0000260000 0.0003800000 0.0216770000 9800656 96830484 1770618880 3.9622757435 4.0281434059 4.0590085983 367 1305031241.7471020222 0.0537566245 0.0792316679 0.1672170013 0.0252792165 0.1069400000 0.0113660000 0.0482740000 0.0003070000 0.0003470000 0.0279100000 9802970 96830484 1769484288 3.9629323483 4.0295495987 4.0579905510 368 1305031241.7782680988 0.0541352741 0.0791634711 0.1672170013 0.0252596640 0.0893140000 0.0097970000 0.0476510000 0.0000280000 0.0003840000 0.0211020000 9805156 96830484 1771163648 3.9633266926 4.0291137695 4.0564827919 369 1305031241.8098289967 0.0511708893 0.0790876105 0.1672170013 0.0252587216 0.1208630000 0.0111500000 0.0723900000 0.0003740000 0.0002810000 0.0325380000 9807278 96830484 1770229760 3.9628798962 4.0321650505 4.0561785698 370 1305031241.8464360237 0.0542175844 0.0790203942 0.1672170013 0.0252665633 0.1132300000 0.0143650000 0.0718690000 0.0000280000 0.0003110000 0.0211440000 9809560 96830484 1768828928 3.9619853497 4.0285797119 4.0532841682 371 1305031241.8787989616 0.0533349216 0.0789511611 0.1672170013 0.0253388510 0.1252130000 0.0094910000 0.0713150000 0.0003090000 0.0003520000 0.0282690000 9811778 96830484 1770463232 3.9608659744 4.0298695564 4.0521588326 372 1305031241.9114871025 0.0481145792 0.0788682671 0.1672170013 0.0253679780 0.0896130000 0.0115230000 0.0490200000 0.0000300000 0.0003800000 0.0221370000 9813964 96830484 1768955904 3.9631276131 4.0352396965 4.0550460815 373 1305031241.9477050304 0.0491210669 0.0787885159 0.1672170013 0.0253525703 0.1068600000 0.0098870000 0.0493140000 0.0003040000 0.0006960000 0.0424130000 9816214 96830484 1767596032 3.9631021023 4.0341906548 4.0542507172 374 1305031241.9783430099 0.0481590964 0.0787066190 0.1672170013 0.0254594850 0.1214290000 0.0095880000 0.0755610000 0.0000260000 0.0003850000 0.0223320000 9818400 96830484 1769463808 3.9634068012 4.0353903770 4.0546164513 375 1305031242.0105700493 0.0469318964 0.0786218864 0.1672170013 0.0255410247 0.1065430000 0.0095650000 0.0490510000 0.0003090000 0.0002710000 0.0294580000 9820554 96830484 1771110400 3.9604599476 4.0370264053 4.0532722473 376 1305031242.0463600159 0.0480139665 0.0785404824 0.1672170013 0.0255960025 0.0892320000 0.0111870000 0.0426860000 0.0000290000 0.0003130000 0.0223720000 9822804 96830484 1770242048 3.9568574429 4.0360703468 4.0509862900 377 1305031242.0795490742 0.0508973189 0.0784671583 0.1672170013 0.0256790062 0.1082950000 0.0097640000 0.0494020000 0.0003080000 0.0003510000 0.0441330000 9824990 96830484 1769226240 3.9506342411 4.0336236954 4.0465178490 378 1305031242.1105840206 0.0547248684 0.0784043481 0.1672170013 0.0257367493 0.0887430000 0.0090550000 0.0366850000 0.0000280000 0.0003080000 0.0238270000 9827176 96830484 1770909696 3.9459445477 4.0298871994 4.0428714752 379 1305031242.1466050148 0.0585380420 0.0783519304 0.1672170013 0.0258301253 0.1150130000 0.0178110000 0.0483490000 0.0003890000 0.0002790000 0.0438710000 9829426 96830484 1769717760 3.9427006245 4.0259823799 4.0400967598 380 1305031242.1797080040 0.0650587380 0.0783169483 0.1672170013 0.0259083674 0.1043480000 0.0108610000 0.0539470000 0.0000280000 0.0003080000 0.0227080000 9831644 96830484 1768304640 3.9360911846 4.0197525024 4.0355243683 381 1305031242.2087249756 0.0691445470 0.0782928737 0.1672170013 0.0259342412 0.1157090000 0.0094520000 0.0598780000 0.0003100000 0.0003540000 0.0413510000 9833766 96830484 1770000384 3.9334712029 4.0144405365 4.0336503983 382 1305031242.2478089333 0.0729423538 0.0782788671 0.1672170013 0.0259784351 0.0834620000 0.0105920000 0.0483060000 0.0000300000 0.0003030000 0.0199380000 9836080 96830484 1768828928 3.9307069778 4.0095953941 4.0314493179 383 1305031242.2794981003 0.0743682757 0.0782686567 0.1672170013 0.0260116626 0.1255810000 0.0086510000 0.0745760000 0.0000610000 0.0000530000 0.0326870000 9838266 96830484 1767337984 3.9292786121 4.0079565048 4.0297174454 384 1305031242.3097639084 0.0774869993 0.0782666211 0.1672170013 0.0260166308 0.0871970000 0.0087810000 0.0469720000 0.0000300000 0.0003070000 0.0231680000 9840388 96830484 1769095168 3.9280583858 4.0037965775 4.0276641846 385 1305031242.3471269608 0.0785570666 0.0782673755 0.1672170013 0.0260976272 0.1086440000 0.0091270000 0.0478250000 0.0002110000 0.0001840000 0.0469440000 9842702 96830484 1770606592 3.9287083149 4.0009326935 4.0264391899 386 1305031242.3784790039 0.0782582462 0.0782673519 0.1672170013 0.0261890373 0.0857970000 0.0112590000 0.0378780000 0.0000300000 0.0003020000 0.0247760000 9844888 96830484 1769590784 3.9281258583 4.0001931190 4.0256299973 387 1305031242.4109969139 0.0800371096 0.0782719249 0.1672170013 0.0262321115 0.1500180000 0.0109310000 0.0959540000 0.0003190000 0.0002780000 0.0382030000 9847074 96830484 1768214528 3.9278090000 3.9969429970 4.0239028931 388 1305031242.4470989704 0.0809373856 0.0782787947 0.1672170013 0.0263500845 0.1055820000 0.0087470000 0.0566770000 0.0000300000 0.0003080000 0.0299090000 9849356 96830484 1769828352 3.9264113903 3.9947650433 4.0212554932 389 1305031242.4776470661 0.0818126127 0.0782878790 0.1672170013 0.0264299535 0.1714000000 0.0114190000 0.1038070000 0.0003080000 0.0002710000 0.0510300000 9851542 96830484 1768701952 3.9252605438 3.9939174652 4.0181159973 390 1305031242.5097260475 0.0856478736 0.0783067508 0.1672170013 0.0266227044 0.1029140000 0.0086660000 0.0559600000 0.0000300000 0.0003090000 0.0254860000 9853728 96830484 1770381312 3.9210405350 3.9905290604 4.0127544403 391 1305031242.5485460758 0.0842051730 0.0783218363 0.1672170013 0.0270320066 0.1092460000 0.0119470000 0.0546570000 0.0003110000 0.0002760000 0.0335510000 9856042 96830484 1769209856 3.9193491936 3.9923529625 4.0103874207 392 1305031242.5748429298 0.0853603333 0.0783397916 0.1672170013 0.0271445090 0.1056390000 0.0088710000 0.0535560000 0.0000310000 0.0003690000 0.0263700000 9858100 96830484 1771020288 3.9169428349 3.9928059578 4.0072712898 393 1305031242.6061151028 0.0912822559 0.0783727241 0.1672170013 0.0271986237 0.1470790000 0.0107480000 0.0625560000 0.0003070000 0.0002750000 0.0538850000 9860318 96830484 1769844736 3.9091348648 3.9902288914 4.0008440018 394 1305031242.6438109875 0.0933152139 0.0784106492 0.1672170013 0.0273963498 0.1083470000 0.0114570000 0.0535840000 0.0000290000 0.0003060000 0.0265790000 9862600 96830484 1768468480 3.9061541557 3.9897344112 3.9974892139 395 1305031242.6752018929 0.0926379263 0.0784466676 0.1672170013 0.0276720627 0.1276320000 0.0095180000 0.0710820000 0.0003120000 0.0002780000 0.0329640000 9864818 96830484 1770143744 3.9048709869 3.9906973839 3.9963629246 396 1305031242.7139821053 0.0936306790 0.0784850111 0.1672170013 0.0279948270 0.1270350000 0.0114790000 0.0716310000 0.0000280000 0.0003010000 0.0262910000 9867164 96830484 1769103360 3.9014933109 3.9912931919 3.9946274757 397 1305031242.7452580929 0.0964082778 0.0785301579 0.1672170013 0.0280471883 0.1334540000 0.0096520000 0.0713050000 0.0003170000 0.0003480000 0.0473980000 9869350 96830484 1770766336 3.8977053165 3.9913306236 3.9914543629 398 1305031242.7775399685 0.0999698341 0.0785840264 0.1672170013 0.0281748966 0.1227640000 0.0111660000 0.0710420000 0.0000280000 0.0003130000 0.0272510000 9871568 96830484 1769971712 3.8923375607 3.9897048473 3.9885501862 399 1305031242.8140709400 0.0984968543 0.0786339332 0.1672170013 0.0283625620 0.1280860000 0.0111850000 0.0710390000 0.0003060000 0.0002740000 0.0334980000 9873850 96830484 1768321024 3.8931837082 3.9928071499 3.9895319939 400 1305031242.8443179131 0.1004469767 0.0786884658 0.1672170013 0.0283921195 0.1254830000 0.0096150000 0.0698950000 0.0000270000 0.0003130000 0.0268500000 9876036 96830484 1770127360 3.8897898197 3.9932899475 3.9884567261 401 1305031242.8740880489 0.1060662791 0.0787567397 0.1672170013 0.0284147684 0.1187850000 0.0112370000 0.0539470000 0.0003030000 0.0003530000 0.0483870000 9878254 96830484 1769082880 3.8831176758 3.9901564121 3.9867072105 402 1305031242.9137070179 0.1136513799 0.0788435423 0.1672170013 0.0284738296 0.0975060000 0.0103780000 0.0498200000 0.0000300000 0.0003060000 0.0275350000 9880632 96830484 1770782720 3.8735227585 3.9894559383 3.9823493958 403 1305031242.9444379807 0.1128014699 0.0789278051 0.1672170013 0.0286107745 0.1098530000 0.0111030000 0.0603590000 0.0003120000 0.0002740000 0.0330700000 9882818 96830484 1769955328 3.8725764751 3.9938766956 3.9827299118 404 1305031242.9760620594 0.1161148772 0.0790198523 0.1672170013 0.0286472432 0.1247290000 0.0116720000 0.0712990000 0.0000280000 0.0007080000 0.0270820000 9885004 96830484 1768448000 3.8642091751 3.9968807697 3.9804091454 405 1305031243.0141661167 0.1198409796 0.0791206452 0.1672170013 0.0286907400 0.1349170000 0.0096530000 0.0720500000 0.0003070000 0.0005680000 0.0476730000 9887318 96830484 1770254336 3.8580794334 3.9977824688 3.9797501564 406 1305031243.0469100475 0.1193919256 0.0792198356 0.1672170013 0.0286844640 0.1199810000 0.0113860000 0.0658980000 0.0000270000 0.0003100000 0.0267360000 9889632 96830484 1769463808 3.8564174175 4.0003838539 3.9806771278 407 1305031243.0780448914 0.1201213002 0.0793203306 0.1672170013 0.0286706869 0.1065600000 0.0097570000 0.0429170000 0.0003140000 0.0002720000 0.0339770000 9891850 96830484 1771036672 3.8536489010 4.0027132034 3.9801940918 408 1305031243.1136150360 0.1214902475 0.0794236882 0.1672170013 0.0286695446 0.1283600000 0.0122930000 0.0705340000 0.0000260000 0.0003030000 0.0275330000 9894100 96830484 1769992192 3.8492205143 4.0054030418 3.9787976742 409 1305031243.1458160877 0.1240759417 0.0795328624 0.1672170013 0.0286393361 0.1170790000 0.0115060000 0.0529000000 0.0003060000 0.0003620000 0.0474410000 9896350 96830484 1768595456 3.8436012268 4.0081458092 3.9758062363 410 1305031243.1780760288 0.1232485697 0.0796394861 0.1672170013 0.0286260074 0.0985770000 0.0095670000 0.0479340000 0.0000280000 0.0003170000 0.0273390000 9898568 96830484 1770254336 3.8421988487 4.0099930763 3.9749014378 411 1305031243.2136580944 0.1175008789 0.0797316063 0.1672170013 0.0286366638 0.1273430000 0.0115610000 0.0654900000 0.0003820000 0.0002760000 0.0334590000 9900850 96830484 1768431616 3.8487563133 4.0086827278 3.9789659977 412 1305031243.2455608845 0.1195393801 0.0798282271 0.1672170013 0.0288966276 0.1081590000 0.0097880000 0.0597290000 0.0000280000 0.0003040000 0.0263760000 9903068 96830484 1770106880 3.8495130539 4.0044455528 3.9784345627 413 1305031243.2781798840 0.1125099510 0.0799073596 0.1672170013 0.0289613010 0.1032230000 0.0115140000 0.0368270000 0.0003160000 0.0003490000 0.0495060000 9905318 96830484 1768448000 3.8617238998 4.0043091774 3.9814901352 414 1305031243.3142709732 0.1159089878 0.0799943201 0.1672170013 0.0290002575 0.1277560000 0.0097760000 0.0735890000 0.0000280000 0.0005860000 0.0266330000 9907568 96830484 1770127360 3.8592915535 3.9986455441 3.9832770824 415 1305031243.3460359573 0.1159441695 0.0800809462 0.1672170013 0.0293061393 0.1279530000 0.0113030000 0.0657920000 0.0003060000 0.0002720000 0.0334130000 9909818 96830484 1769230336 3.8629388809 3.9964919090 3.9844806194 416 1305031243.3789350986 0.1094140038 0.0801514584 0.1672170013 0.0293389147 0.1080310000 0.0097960000 0.0562870000 0.0000310000 0.0005310000 0.0271440000 9912068 96830484 1771036672 3.8744151592 4.0000333786 3.9885003567 417 1305031243.4139740467 0.1145409048 0.0802339271 0.1672170013 0.0294157582 0.1198280000 0.0111380000 0.0552300000 0.0006360000 0.0003560000 0.0477030000 9914318 96830484 1770119168 3.8652939796 3.9993045330 3.9878342152 418 1305031243.4470911026 0.1080593243 0.0803004950 0.1672170013 0.0296130416 0.1174220000 0.0111020000 0.0730690000 0.0000300000 0.0003110000 0.0264510000 9916568 96830484 1768685568 3.8766124249 4.0034413338 3.9922645092 419 1305031243.4780371189 0.1088214293 0.0803685641 0.1672170013 0.0296407127 0.1251540000 0.0094900000 0.0663590000 0.0003060000 0.0002770000 0.0336460000 9918754 96830484 1770496000 3.8755266666 4.0066919327 3.9923419952 420 1305031243.5154008865 0.1099044457 0.0804388876 0.1672170013 0.0297417067 0.1271040000 0.0115060000 0.0712940000 0.0000300000 0.0003690000 0.0263540000 9921068 96830484 1768828928 3.8699123859 4.0112123489 3.9922878742 421 1305031243.5459430218 0.1082092151 0.0805048504 0.1672170013 0.0297919574 0.1474220000 0.0096100000 0.0697040000 0.0003840000 0.0006240000 0.0505130000 9923286 96830484 1770381312 3.8716361523 4.0145845413 3.9934449196 422 1305031243.5779840946 0.1033238545 0.0805589238 0.1672170013 0.0297824765 0.1101320000 0.0118000000 0.0655540000 0.0000260000 0.0003680000 0.0254970000 9925440 96830484 1768828928 3.8738291264 4.0204620361 3.9966402054 423 1305031243.6140549183 0.1011793390 0.0806076718 0.1672170013 0.0300289098 0.1075820000 0.0095520000 0.0601100000 0.0003000000 0.0002760000 0.0319600000 9927690 96830484 1770360832 3.8752074242 4.0244941711 3.9981620312 424 1305031243.6461870670 0.1042701676 0.0806634796 0.1672170013 0.0302959196 0.1249950000 0.0120160000 0.0715570000 0.0000290000 0.0003740000 0.0247970000 9929940 96830484 1768574976 3.8729801178 4.0220050812 3.9956338406 425 1305031243.6782801151 0.1084876657 0.0807289483 0.1672170013 0.0303222120 0.1265910000 0.0096570000 0.0486280000 0.0002990000 0.0002730000 0.0483510000 9932126 96830484 1770233856 3.8681702614 4.0180673599 3.9936521053 426 1305031243.7142961025 0.0992093906 0.0807723296 0.1672170013 0.0306403357 0.0899590000 0.0115280000 0.0420470000 0.0000280000 0.0012230000 0.0254120000 9934344 96830484 1768558592 3.8772368431 4.0267567635 3.9980525970 427 1305031243.7473781109 0.0989792645 0.0808149688 0.1672170013 0.0308800012 0.1253720000 0.0100580000 0.0708360000 0.0003890000 0.0002700000 0.0326810000 9936562 96830484 1767321600 3.8817214966 4.0246272087 3.9981865883 428 1305031243.7790360451 0.0999342129 0.0808596399 0.1672170013 0.0310168601 0.0872770000 0.0096480000 0.0371950000 0.0000270000 0.0003800000 0.0270730000 9938716 96830484 1769238528 3.8815526962 4.0193223953 3.9997529984 429 1305031243.8141930103 0.0903997719 0.0808818780 0.1672170013 0.0314468672 0.1668580000 0.0100670000 0.0866910000 0.0009110000 0.0000760000 0.0520970000 9940934 96830484 1768194048 3.8960607052 4.0235548019 4.0057735443 430 1305031243.8462920189 0.0889644474 0.0809006747 0.1672170013 0.0317415414 0.1267460000 0.0097370000 0.0702070000 0.0000270000 0.0002870000 0.0266770000 9943120 96830484 1769836544 3.9052846432 4.0216813087 4.0078487396 431 1305031243.8788089752 0.0833919421 0.0809064549 0.1672170013 0.0318395474 0.1294720000 0.0115050000 0.0706650000 0.0002940000 0.0002830000 0.0333080000 9945338 96830484 1768865792 3.9130523205 4.0238800049 4.0125069618 432 1305031243.9140000343 0.0749311224 0.0808926231 0.1672170013 0.0320337957 0.1067900000 0.0095160000 0.0535120000 0.0000240000 0.0003450000 0.0282500000 9947524 96830484 1770528768 3.9226846695 4.0282683372 4.0194244385 433 1305031243.9470779896 0.0647137091 0.0808552584 0.1672170013 0.0321396696 0.1389150000 0.0115460000 0.0694220000 0.0003570000 0.0002790000 0.0523880000 9949774 96830484 1769574400 3.9342765808 4.0367336273 4.0289521217 434 1305031243.9816520214 0.0565639548 0.0807992877 0.1672170013 0.0322173729 0.1167810000 0.0097550000 0.0646300000 0.0000280000 0.0003750000 0.0291980000 9951992 96830484 1771163648 3.9420752525 4.0434913635 4.0378589630 435 1305031244.0112700462 0.0531674996 0.0807357663 0.1672170013 0.0322667870 0.1283560000 0.0110890000 0.0683080000 0.0003610000 0.0002760000 0.0373900000 9954146 96830484 1770479616 3.9480683804 4.0482211113 4.0424208641 436 1305031244.0438230038 0.0485527553 0.0806619521 0.1672170013 0.0322729370 0.1251160000 0.0115980000 0.0636630000 0.0000260000 0.0003670000 0.0300850000 9956332 96830484 1769082880 3.9485623837 4.0583763123 4.0450859070 437 1305031244.0818090439 0.0461534113 0.0805829851 0.1672170013 0.0323084211 0.1282280000 0.0097860000 0.0574970000 0.0003640000 0.0002730000 0.0552110000 9958614 96830484 1770614784 3.9463171959 4.0638427734 4.0449852943 438 1305031244.1127901077 0.0478617996 0.0805082792 0.1672170013 0.0323906889 0.1095910000 0.0116760000 0.0590660000 0.0000280000 0.0003560000 0.0305340000 9960800 96830484 1769971712 3.9509067535 4.0634098053 4.0463194847 439 1305031244.1484949589 0.0453431755 0.0804281765 0.1672170013 0.0323809246 0.1273860000 0.0113650000 0.0688860000 0.0002930000 0.0003450000 0.0386420000 9963050 96830484 1768464384 3.9517467022 4.0687937737 4.0493311882 440 1305031244.1824309826 0.0420057625 0.0803408528 0.1672170013 0.0324437971 0.1039560000 0.0094060000 0.0415000000 0.0000270000 0.0003120000 0.0315740000 9965236 96830484 1770270720 3.9543738365 4.0745429993 4.0541410446 441 1305031244.2124009132 0.0423598140 0.0802547280 0.1672170013 0.0325482873 0.1232790000 0.0114850000 0.0472590000 0.0002850000 0.0002680000 0.0589870000 9967422 96830484 1769066496 3.9579610825 4.0772948265 4.0561375618 442 1305031244.2473471165 0.0399795659 0.0801636077 0.1672170013 0.0326951793 0.0937890000 0.0090170000 0.0365080000 0.0000980000 0.0003020000 0.0347790000 9969640 96830484 1770909696 3.9608359337 4.0825614929 4.0588335991 443 1305031244.2831470966 0.0371686220 0.0800665536 0.1672170013 0.0328092135 0.1111150000 0.0105130000 0.0608660000 0.0002950000 0.0002620000 0.0342290000 9971890 96830484 1769975808 3.9657034874 4.0878124237 4.0625123978 444 1305031244.3137950897 0.0362549722 0.0799678789 0.1672170013 0.0329281136 0.0864190000 0.0115870000 0.0352130000 0.0000250000 0.0004150000 0.0341180000 9974012 96830484 1768595456 3.9707729816 4.0953307152 4.0656223297 445 1305031244.3459599018 0.0373714603 0.0798721566 0.1672170013 0.0330843284 0.1329480000 0.0088010000 0.0466580000 0.0002830000 0.0003400000 0.0718850000 9976230 96830484 1767047168 3.9765212536 4.1036696434 4.0685110092 446 1305031244.3808560371 0.0363839492 0.0797746494 0.1672170013 0.0332161111 0.1000080000 0.0096590000 0.0476720000 0.0000260000 0.0002860000 0.0344890000 9978448 96830484 1768873984 3.9778795242 4.1087007523 4.0671935081 447 1305031244.4130189419 0.0409591608 0.0796878138 0.1672170013 0.0333975650 0.1271830000 0.0089940000 0.0672490000 0.0002910000 0.0003420000 0.0412790000 9980634 96830484 1770340352 3.9869267941 4.1164464951 4.0705270767 448 1305031244.4451670647 0.0426908731 0.0796052314 0.1672170013 0.0334591986 0.1068150000 0.0116400000 0.0476960000 0.0000860000 0.0002870000 0.0338840000 9982820 96830484 1769336832 3.9879653454 4.1265182495 4.0695772171 449 1305031244.4806590080 0.0428836942 0.0795234462 0.1672170013 0.0335094033 0.1280520000 0.0097970000 0.0537750000 0.0008760000 0.0002900000 0.0582680000 9985070 96830484 1771098112 3.9867298603 4.1321363449 4.0673527718 450 1305031244.5142281055 0.0442421772 0.0794450434 0.1672170013 0.0336034741 0.1269590000 0.0112460000 0.0690410000 0.0000270000 0.0002830000 0.0330330000 9987288 96830484 1770246144 3.9857871532 4.1368064880 4.0654463768 451 1305031244.5462141037 0.0442956537 0.0793671068 0.1672170013 0.0335859976 0.1273800000 0.0114990000 0.0594370000 0.0000590000 0.0000530000 0.0415490000 9989474 96830484 1768828928 3.9825894833 4.1439580917 4.0660414696 452 1305031244.5808050632 0.0425982252 0.0792857598 0.1672170013 0.0336280140 0.1252600000 0.0098600000 0.0704010000 0.0000300000 0.0003570000 0.0330540000 9991692 96830484 1770487808 3.9799377918 4.1454057693 4.0661349297 453 1305031244.6132769585 0.0418602303 0.0792031427 0.1672170013 0.0337024381 0.1456820000 0.0111990000 0.0700380000 0.0002920000 0.0003430000 0.0587580000 9993910 96830484 1769717760 3.9782512188 4.1469860077 4.0659551620 454 1305031244.6428399086 0.0419576503 0.0791211042 0.1672170013 0.0336842754 0.1285510000 0.0112230000 0.0698690000 0.0000270000 0.0003710000 0.0338350000 9996032 96830484 1768230912 3.9758503437 4.1524291039 4.0675129890 455 1305031244.6806099415 0.0413724333 0.0790381401 0.1672170013 0.0337348863 0.1322120000 0.0095790000 0.0688250000 0.0002910000 0.0003460000 0.0481310000 9998282 96830484 1769979904 3.9757764339 4.1555542946 4.0705180168 456 1305031244.7152500153 0.0394615270 0.0789513492 0.1672170013 0.0337403900 0.1234690000 0.0110540000 0.0688560000 0.0000260000 0.0003650000 0.0334340000 10000532 96830484 1768812544 3.9726214409 4.1590409279 4.0714921951 457 1305031244.7458879948 0.0373115540 0.0788602337 0.1672170013 0.0339155003 0.1430540000 0.0098030000 0.0682380000 0.0003070000 0.0003500000 0.0591340000 10002686 96830484 1770618880 3.9732856750 4.1572661400 4.0726461411 458 1305031244.7818510532 0.0350898243 0.0787646651 0.1672170013 0.0340180247 0.1302280000 0.0114390000 0.0679700000 0.0000260000 0.0004920000 0.0332300000 10004968 96830484 1769463808 3.9703521729 4.1547813416 4.0690307617 459 1305031244.8140940666 0.0264358185 0.0786506589 0.1672170013 0.0348554970 0.1292050000 0.0097150000 0.0684190000 0.0002870000 0.0003460000 0.0416510000 10007154 96830484 1771163648 3.9740657806 4.1592469215 4.0707764626 460 1305031244.8418219090 0.0303417873 0.0785456396 0.1672170013 0.0348534891 0.1267230000 0.0114450000 0.0690820000 0.0000280000 0.0003410000 0.0343270000 10009244 96830484 1770229760 3.9715945721 4.1612081528 4.0653095245 461 1305031244.8818008900 0.0358506031 0.0784530257 0.1672170013 0.0348240153 0.1475860000 0.0114790000 0.0692580000 0.0002860000 0.0003480000 0.0609990000 10011558 96830484 1768828928 3.9638400078 4.1666345596 4.0593280792 462 1305031244.9149079323 0.0358506031 0.0783608126 0.1672170013 0.0347862247 0.1254490000 0.0096130000 0.0643160000 0.0000270000 0.0002850000 0.0351180000 10013744 96830484 1770487808 3.9638400078 4.1666345596 4.0593280792 463 1305031244.9458680153 0.0351819843 0.0782675538 0.1672170013 0.0347593087 0.1282530000 0.0114350000 0.0665110000 0.0000280000 0.0003500000 0.0355740000 10015898 96830484 1769701376 3.9638400078 4.1666345596 4.0593280792 464 1305031244.9818000793 0.0387907289 0.0781824745 0.1672170013 0.0348695993 0.1277570000 0.0114100000 0.0670300000 0.0000280000 0.0002900000 0.0364400000 10018148 96830484 1768357888 3.9718503952 4.1829051971 4.0704245567 465 1305031245.0140550137 0.0387907289 0.0780977610 0.1672170013 0.0348320040 0.1472680000 0.0097240000 0.0649010000 0.0000260000 0.0003500000 0.0590960000 10020334 96830484 1770016768 3.9718503952 4.1829051971 4.0704245567 466 1305031245.0464398861 0.0431770682 0.0780228239 0.1672170013 0.0348025564 0.1279050000 0.0113230000 0.0675820000 0.0000250000 0.0003490000 0.0364410000 10022520 96830484 1768865792 3.9704117775 4.1889095306 4.0708785057 467 1305031245.0817689896 0.0440321006 0.0779500387 0.1672170013 0.0347686492 0.1266070000 0.0097180000 0.0647360000 0.0000310000 0.0003610000 0.0362550000 10024770 96830484 1770618880 3.9704117775 4.1889095306 4.0708785057 468 1305031245.1143150330 0.0459597670 0.0778816834 0.1672170013 0.0347366099 0.1280200000 0.0112940000 0.0650130000 0.0000260000 0.0002960000 0.0365610000 10026924 96830484 1769463808 3.9704117775 4.1889095306 4.0708785057 469 1305031245.1457099915 0.0492712930 0.0778206804 0.1672170013 0.0347001808 0.1375250000 0.0097280000 0.0653590000 0.0000270000 0.0002970000 0.0568460000 10029142 96830484 1771163648 3.9704117775 4.1889095306 4.0708785057 470 1305031245.1818709373 0.0528520308 0.0777675556 0.1672170013 0.0346713518 0.1360990000 0.0113380000 0.0672200000 0.0000290000 0.0003010000 0.0367010000 10031360 96830484 1770209280 3.9704117775 4.1889095306 4.0708785057 471 1305031245.2140939236 0.0585418418 0.0777267367 0.1672170013 0.0346596127 0.1290620000 0.0115820000 0.0672810000 0.0000290000 0.0003000000 0.0370290000 10033546 96830484 1768828928 3.9704117775 4.1889095306 4.0708785057 472 1305031245.2487950325 0.0514116585 0.0776709844 0.1672170013 0.0360933508 0.1277020000 0.0099610000 0.0690840000 0.0000300000 0.0002980000 0.0377390000 10035796 96830484 1770487808 3.9656391144 4.1759519577 4.0691184998 473 1305031245.2807950974 0.0555960946 0.0776243145 0.1672170013 0.0360881045 0.1455510000 0.0114970000 0.0700890000 0.0000270000 0.0002890000 0.0582060000 10037950 96830484 1769717760 3.9656391144 4.1759519577 4.0691184998 474 1305031245.3143179417 0.0540247485 0.0775745263 0.1672170013 0.0363299178 0.1286920000 0.0113510000 0.0649820000 0.0000250000 0.0002810000 0.0381410000 10040136 96830484 1768357888 3.9684324265 4.1654753685 4.0698866844 475 1305031245.3491809368 0.0530552007 0.0775229067 0.1672170013 0.0365531549 0.1455200000 0.0097030000 0.0694360000 0.0002870000 0.0003390000 0.0461540000 10042418 96830484 1770106880 3.9653124809 4.1597938538 4.0666775703 476 1305031245.3806860447 0.0506767333 0.0774665072 0.1672170013 0.0367355316 0.1275120000 0.0115290000 0.0579820000 0.0000270000 0.0002890000 0.0380870000 10044540 96830484 1768558592 3.9617803097 4.1512603760 4.0603427887 477 1305031245.4133110046 0.0494121611 0.0774076930 0.1672170013 0.0368858412 0.1504900000 0.0097370000 0.0701300000 0.0003700000 0.0002800000 0.0645580000 10046726 96830484 1770364928 3.9593303204 4.1425070763 4.0560469627 478 1305031245.4489970207 0.0495494343 0.0773494122 0.1672170013 0.0368687431 0.1254740000 0.0111610000 0.0627600000 0.0000280000 0.0003480000 0.0359530000 10048944 96830484 1769209856 3.9643428326 4.1295676231 4.0513596535 479 1305031245.4846711159 0.0519428216 0.0772963713 0.1672170013 0.0370727156 0.1084560000 0.0096740000 0.0441590000 0.0003850000 0.0002840000 0.0439940000 10051194 96830484 1770909696 3.9637660980 4.1271934509 4.0479550362 480 1305031245.5124320984 0.0501013286 0.0772397149 0.1672170013 0.0371588202 0.1097410000 0.0113460000 0.0580910000 0.0000260000 0.0002890000 0.0343960000 10053316 96830484 1769992192 3.9584560394 4.1226687431 4.0425982475 481 1305031245.5481460094 0.0492806807 0.0771815880 0.1672170013 0.0372922475 0.1631310000 0.0115620000 0.0693660000 0.0002920000 0.0002770000 0.0634760000 10055534 96830484 1768611840 3.9539427757 4.1171002388 4.0377988815 482 1305031245.5786890984 0.0499933660 0.0771251809 0.1672170013 0.0373002344 0.1080310000 0.0099080000 0.0472590000 0.0000280000 0.0003160000 0.0345800000 10057720 96830484 1770381312 3.9545209408 4.1126337051 4.0359120369 483 1305031245.6104750633 0.0501165465 0.0770692624 0.1672170013 0.0373574167 0.1104490000 0.0112410000 0.0527810000 0.0005110000 0.0002860000 0.0401300000 10059874 96830484 1769463808 3.9504601955 4.1054663658 4.0295310020 484 1305031245.6494629383 0.0498776250 0.0770130814 0.1672170013 0.0375127656 0.1059450000 0.0097950000 0.0532230000 0.0000270000 0.0003600000 0.0337690000 10062156 96830484 1771098112 3.9485228062 4.1024756432 4.0277218819 485 1305031245.6802349091 0.0495054163 0.0769563645 0.1672170013 0.0375354562 0.1273560000 0.0114630000 0.0503400000 0.0003020000 0.0002740000 0.0589420000 10064342 96830484 1770119168 3.9463121891 4.1017284393 4.0274567604 486 1305031245.7110319138 0.0495764539 0.0769000273 0.1672170013 0.0375399591 0.1078060000 0.0117010000 0.0581600000 0.0000270000 0.0003750000 0.0310880000 10066528 96830484 1768828928 3.9427955151 4.0987844467 4.0240898132 487 1305031245.7497749329 0.0496778786 0.0768441296 0.1672170013 0.0376012119 0.1050740000 0.0096700000 0.0421030000 0.0010440000 0.0002830000 0.0381470000 10068810 96830484 1770250240 3.9403088093 4.0986895561 4.0229511261 488 1305031245.7818500996 0.0507325009 0.0767906222 0.1672170013 0.0376333354 0.1050660000 0.0112590000 0.0521760000 0.0000250000 0.0002950000 0.0290380000 10071028 96830484 1769590784 3.9349846840 4.0963087082 4.0180745125 489 1305031245.8135690689 0.0529038161 0.0767417739 0.1672170013 0.0377166047 0.1387140000 0.0112310000 0.0701630000 0.0003060000 0.0002850000 0.0510950000 10073182 96830484 1768067072 3.9305324554 4.0943646431 4.0141320229 490 1305031245.8491089344 0.0547637381 0.0766969208 0.1672170013 0.0377471041 0.1165080000 0.0091570000 0.0709520000 0.0000280000 0.0008700000 0.0259070000 10075432 96830484 1769873408 3.9275133610 4.0884156227 4.0103311539 491 1305031245.8820281029 0.0573788211 0.0766575764 0.1672170013 0.0377616822 0.1257480000 0.0113710000 0.0660980000 0.0000600000 0.0000530000 0.0330950000 10077650 96830484 1768304640 3.9220170975 4.0812778473 4.0061135292 492 1305031245.9126079082 0.0595378987 0.0766227803 0.1672170013 0.0377649423 0.1262470000 0.0090570000 0.0719450000 0.0000290000 0.0002990000 0.0256910000 10079804 96830484 1770209280 3.9223787785 4.0772557259 4.0042176247 493 1305031245.9458959103 0.0626489073 0.0765944357 0.1672170013 0.0377979732 0.1270410000 0.0112330000 0.0433880000 0.0003170000 0.0003570000 0.0494010000 10081990 96830484 1769345024 3.9177005291 4.0712532997 4.0003442764 494 1305031245.9808180332 0.0632177740 0.0765673575 0.1672170013 0.0378141972 0.0896710000 0.0096230000 0.0413310000 0.0000280000 0.0010550000 0.0251110000 10084240 96830484 1771028480 3.9205839634 4.0688052177 3.9999549389 495 1305031246.0110030174 0.0648921952 0.0765437713 0.1672170013 0.0378207796 0.1290630000 0.0114970000 0.0717810000 0.0005400000 0.0002880000 0.0346790000 10086394 96830484 1769979904 3.9244775772 4.0659675598 3.9989831448 496 1305031246.0483930111 0.0669635087 0.0765244562 0.1672170013 0.0378877724 0.0983020000 0.0159550000 0.0557670000 0.0000290000 0.0003240000 0.0178050000 10088708 96830484 1768456192 3.9233610630 4.0619525909 3.9963705540 497 1305031246.0805249214 0.0689760223 0.0765092682 0.1672170013 0.0379497710 0.1528350000 0.0095490000 0.0717210000 0.0003130000 0.0002700000 0.0487280000 10090830 96830484 1770151936 3.9226434231 4.0587410927 3.9944658279 498 1305031246.1123559475 0.0698990226 0.0764959947 0.1672170013 0.0380385657 0.1284310000 0.0112250000 0.0722690000 0.0000290000 0.0003100000 0.0249080000 10093048 96830484 1769218048 3.9245254993 4.0571751595 3.9944465160 499 1305031246.1484489441 0.0732429698 0.0764894756 0.1672170013 0.0381111815 0.1291840000 0.0094390000 0.0714470000 0.0003010000 0.0002800000 0.0325260000 10095266 96830484 1770852352 3.9187986851 4.0537190437 3.9891974926 500 1305031246.1805961132 0.0766780749 0.0764898528 0.1672170013 0.0381458429 0.1064560000 0.0109980000 0.0536960000 0.0000310000 0.0003030000 0.0262250000 10097420 96830484 1770000384 3.9114842415 4.0505099297 3.9837059975 501 1305031246.2111370564 0.0807843804 0.0764984247 0.1672170013 0.0382240445 0.1260420000 0.0111270000 0.0419420000 0.0011140000 0.0002930000 0.0513330000 10099606 96830484 1768603648 3.9050374031 4.0441613197 3.9791891575 502 1305031246.2469689846 0.0845174789 0.0765143989 0.1672170013 0.0383202269 0.1271230000 0.0095050000 0.0702040000 0.0000260000 0.0003490000 0.0259830000 10101856 96830484 1770262528 3.8988051414 4.0407090187 3.9745435715 503 1305031246.2796959877 0.0884241238 0.0765380763 0.1672170013 0.0383654769 0.1099790000 0.0111120000 0.0533350000 0.0003600000 0.0002760000 0.0334180000 10104042 96830484 1769472000 3.8962442875 4.0365452766 3.9709582329 504 1305031246.3124730587 0.0909367204 0.0765666450 0.1672170013 0.0384643350 0.1257300000 0.0093130000 0.0702860000 0.0000250000 0.0002850000 0.0266880000 10106260 96830484 1771171840 3.8913931847 4.0348038673 3.9684154987 505 1305031246.3482720852 0.0926933065 0.0765985790 0.1672170013 0.0385693366 0.1365470000 0.0110950000 0.0700980000 0.0002890000 0.0003350000 0.0489580000 10108510 96830484 1770106880 3.8907704353 4.0327377319 3.9678704739 506 1305031246.3782060146 0.0941898227 0.0766333443 0.1672170013 0.0387056338 0.1207390000 0.0115620000 0.0709860000 0.0000280000 0.0006310000 0.0275910000 10110664 96830484 1768566784 3.8854227066 4.0332255363 3.9661738873 507 1305031246.4156370163 0.0955208167 0.0766705977 0.1672170013 0.0388524057 0.1266260000 0.0095510000 0.0686770000 0.0003480000 0.0002620000 0.0354610000 10112978 96830484 1770242048 3.8784518242 4.0327157974 3.9659554958 508 1305031246.4452888966 0.1015320495 0.0767195376 0.1672170013 0.0389088956 0.0888660000 0.0110560000 0.0413500000 0.0000260000 0.0002820000 0.0285390000 10115132 96830484 1769472000 3.8674130440 4.0280528069 3.9621951580 509 1305031246.4774649143 0.1060615331 0.0767771839 0.1672170013 0.0389791365 0.1137560000 0.0098040000 0.0451500000 0.0001120000 0.0001250000 0.0528960000 10117382 96830484 1768452096 3.8590953350 4.0277848244 3.9589011669 510 1305031246.5163950920 0.1056029797 0.0768337051 0.1672170013 0.0390881524 0.1194380000 0.0098610000 0.0723310000 0.0000260000 0.0003500000 0.0297040000 10119696 96830484 1770008576 3.8593385220 4.0320649147 3.9596390724 511 1305031246.5491750240 0.1052094549 0.0768892349 0.1672170013 0.0391962161 0.1268700000 0.0114620000 0.0690450000 0.0002850000 0.0002650000 0.0380190000 10121946 96830484 1769238528 3.8571140766 4.0361361504 3.9598805904 512 1305031246.5795109272 0.1056435630 0.0769453957 0.1672170013 0.0392718465 0.1254020000 0.0097390000 0.0699200000 0.0000250000 0.0003570000 0.0304880000 10124132 96830484 1771028480 3.8523302078 4.0390920639 3.9595742226 513 1305031246.6164529324 0.1072683632 0.0770045048 0.1672170013 0.0393202905 0.1464650000 0.0116390000 0.0701420000 0.0002840000 0.0002660000 0.0580240000 10167406 96830484 1770106880 3.8521220684 4.0418186188 3.9583668709 514 1305031246.6477630138 0.1084811613 0.0770657435 0.1672170013 0.0393618968 0.1268300000 0.0114910000 0.0637840000 0.0000260000 0.0003450000 0.0301530000 10253592 96830484 1768693760 3.8483421803 4.0446052551 3.9574639797 515 1305031246.6807579994 0.1079888046 0.0771257882 0.1672170013 0.0394363690 0.1293490000 0.0097360000 0.0699910000 0.0002880000 0.0002650000 0.0375890000 10255842 96830484 1770278912 3.8455741405 4.0469450951 3.9578180313 516 1305031246.7169740200 0.1120509282 0.0771934726 0.1672170013 0.0395411878 0.1267630000 0.0113910000 0.0709820000 0.0000260000 0.0005040000 0.0304860000 10258156 96830484 1769725952 3.8373043537 4.0488915443 3.9541826248 517 1305031246.7491660118 0.1137876958 0.0772642545 0.1672170013 0.0396067459 0.1477330000 0.0115260000 0.0704080000 0.0003040000 0.0002750000 0.0590930000 10260374 96830484 1768222720 3.8333842754 4.0524659157 3.9514913559 518 1305031246.7808170319 0.1135883778 0.0773343783 0.1672170013 0.0396563490 0.1259660000 0.0095670000 0.0693290000 0.0000260000 0.0002930000 0.0311920000 10262624 96830484 1770008576 3.8322103024 4.0551033020 3.9509623051 519 1305031246.8168079853 0.1171789244 0.0774111500 0.1672170013 0.0396912622 0.1296410000 0.0115820000 0.0702370000 0.0002900000 0.0002700000 0.0391420000 10264938 96830484 1768456192 3.8287634850 4.0581293106 3.9470529556 520 1305031246.8488121033 0.1177073717 0.0774886428 0.1672170013 0.0397073903 0.1257950000 0.0097120000 0.0699750000 0.0000940000 0.0002930000 0.0312090000 10267188 96830484 1770246144 3.8264505863 4.0610418320 3.9455292225 521 1305031246.8806428909 0.1138719916 0.0775584765 0.1672170013 0.0397676785 0.1447780000 0.0115600000 0.0710710000 0.0002900000 0.0002670000 0.0555510000 10269438 96830484 1768820736 3.8298656940 4.0656614304 3.9463367462 522 1305031246.9166710377 0.1119862571 0.0776244301 0.1672170013 0.0398286020 0.1123090000 0.0096330000 0.0646470000 0.0000270000 0.0002850000 0.0317780000 10271752 96830484 1770647552 3.8303062916 4.0685210228 3.9451706409 523 1305031246.9495339394 0.1165193915 0.0776987990 0.1672170013 0.0398166346 0.1070350000 0.0113530000 0.0474850000 0.0003190000 0.0003440000 0.0383550000 10274002 96830484 1769746432 3.8257546425 4.0707745552 3.9396765232 524 1305031246.9775969982 0.1189410836 0.0777775057 0.1672170013 0.0397960704 0.1079800000 0.0114220000 0.0590320000 0.0000290000 0.0003660000 0.0302470000 10276156 96830484 1768239104 3.8222067356 4.0710587502 3.9367802143 525 1305031247.0167899132 0.1146752760 0.0778477871 0.1672170013 0.0398726902 0.1394650000 0.0097150000 0.0710290000 0.0002940000 0.0002690000 0.0521830000 10278502 96830484 1770008576 3.8245306015 4.0746417046 3.9375665188 526 1305031247.0479340553 0.1183521152 0.0779247916 0.1672170013 0.0398453714 0.1109110000 0.0115650000 0.0546820000 0.0000260000 0.0002860000 0.0287020000 10280752 96830484 1768873984 3.8183741570 4.0749077797 3.9324803352 527 1305031247.0778899193 0.1156755313 0.0779964248 0.1672170013 0.0398326953 0.1286950000 0.0096340000 0.0718090000 0.0003070000 0.0002730000 0.0359620000 10282970 96830484 1770516480 3.8181943893 4.0772666931 3.9319329262 528 1305031247.1162130833 0.1176878810 0.0780715980 0.1672170013 0.0397988546 0.1269320000 0.0133600000 0.0719670000 0.0000260000 0.0002880000 0.0286940000 10285316 96830484 1769455616 3.8112940788 4.0795440674 3.9278821945 529 1305031247.1473660469 0.1190277934 0.0781490200 0.1672170013 0.0397851393 0.1398900000 0.0098720000 0.0714250000 0.0003570000 0.0002790000 0.0519380000 10287566 96830484 1771171840 3.8093843460 4.0811657906 3.9247927666 530 1305031247.1796920300 0.1205891669 0.0782290957 0.1672170013 0.0397499172 0.1325990000 0.0116810000 0.0698740000 0.0000250000 0.0002880000 0.0294020000 10289816 96830484 1770000384 3.8079354763 4.0777378082 3.9234771729 531 1305031247.2169430256 0.1156455576 0.0782995599 0.1672170013 0.0397217754 0.1298250000 0.0115320000 0.0711690000 0.0002920000 0.0002680000 0.0363940000 10292162 96830484 1768710144 3.8127806187 4.0793642998 3.9250423908 532 1305031247.2487928867 0.1118855849 0.0783626915 0.1672170013 0.0396978866 0.1259140000 0.0099260000 0.0714030000 0.0000280000 0.0002900000 0.0292510000 10294380 96830484 1770369024 3.8152036667 4.0791621208 3.9272208214 533 1305031247.2794220448 0.1161612496 0.0784336081 0.1672170013 0.0396783439 0.1410520000 0.0112950000 0.0717470000 0.0005070000 0.0002790000 0.0510080000 10296598 96830484 1769619456 3.8119356632 4.0768327713 3.9238502979 534 1305031247.3166429996 0.1151489317 0.0785023634 0.1672170013 0.0396742859 0.1330480000 0.0118380000 0.0756040000 0.0000280000 0.0002950000 0.0284690000 10298944 96830484 1768075264 3.8163266182 4.0729694366 3.9249603748 535 1305031247.3477900028 0.1168258414 0.0785739961 0.1672170013 0.0397231409 0.1285660000 0.0097990000 0.0720150000 0.0002890000 0.0003480000 0.0358490000 10301194 96830484 1769836544 3.8161385059 4.0706505775 3.9252455235 536 1305031247.3786110878 0.1149984375 0.0786419521 0.1672170013 0.0397282490 0.1070730000 0.0113650000 0.0554860000 0.0000280000 0.0002830000 0.0282650000 10303412 96830484 1768345600 3.8197913170 4.0691099167 3.9272940159 537 1305031247.4168620110 0.1166641191 0.0787127569 0.1672170013 0.0397615257 0.1226880000 0.0095340000 0.0559990000 0.0002910000 0.0002710000 0.0503820000 10305790 96830484 1770135552 3.8194978237 4.0657024384 3.9285204411 538 1305031247.4487700462 0.1172728762 0.0787844300 0.1672170013 0.0398773024 0.1307110000 0.0113930000 0.0732950000 0.0000260000 0.0002880000 0.0282990000 10308040 96830484 1768710144 3.8202304840 4.0645990372 3.9303481579 539 1305031247.4802629948 0.1140719056 0.0788498984 0.1672170013 0.0399228300 0.1093220000 0.0097980000 0.0554680000 0.0004020000 0.0002700000 0.0355480000 10310226 96830484 1770409984 3.8238451481 4.0665149689 3.9343273640 540 1305031247.5178461075 0.1152102426 0.0789172324 0.1672170013 0.0399918979 0.1250260000 0.0116150000 0.0673570000 0.0000290000 0.0002970000 0.0285880000 10312604 96830484 1769365504 3.8252503872 4.0659141541 3.9362974167 541 1305031247.5459010601 0.1147760376 0.0789835148 0.1672170013 0.0400676827 0.1226320000 0.0097180000 0.0554580000 0.0003030000 0.0005700000 0.0503320000 10314758 96830484 1771044864 3.8269753456 4.0641870499 3.9389960766 542 1305031247.5779209137 0.1136197895 0.0790474194 0.1672170013 0.0401221762 0.1317810000 0.0116070000 0.0719360000 0.0000250000 0.0003030000 0.0286530000 10316976 96830484 1770090496 3.8292300701 4.0639982224 3.9413139820 543 1305031247.6152799129 0.1136083603 0.0791110675 0.1672170013 0.0402521975 0.1299260000 0.0116690000 0.0734700000 0.0003160000 0.0002680000 0.0364150000 10319258 96830484 1768710144 3.8321402073 4.0634088516 3.9430122375 544 1305031247.6484000683 0.1133688614 0.0791740414 0.1672170013 0.0403582887 0.1255710000 0.0095940000 0.0738530000 0.0000280000 0.0003010000 0.0290900000 10321508 96830484 1770532864 3.8341619968 4.0621881485 3.9440529346 545 1305031247.6835579872 0.1116558835 0.0792336411 0.1672170013 0.0404937538 0.1400110000 0.0117700000 0.0682910000 0.0003030000 0.0002750000 0.0531290000 10323758 96830484 1769345024 3.8371927738 4.0613141060 3.9457633495 546 1305031247.7159609795 0.1065366194 0.0792836466 0.1672170013 0.0406641042 0.1336960000 0.0092720000 0.0768940000 0.0000280000 0.0003030000 0.0303930000 10325976 96830484 1771155456 3.8461456299 4.0620384216 3.9513328075 547 1305031247.7469019890 0.1045409590 0.0793298208 0.1672170013 0.0408526111 0.1302790000 0.0114020000 0.0733960000 0.0006690000 0.0002810000 0.0375200000 10328194 96830484 1769873408 3.8479397297 4.0605173111 3.9531586170 548 1305031247.7822608948 0.1070977822 0.0793804923 0.1672170013 0.0409797537 0.1082460000 0.0115700000 0.0611760000 0.0000290000 0.0003770000 0.0288550000 10330444 96830484 1768603648 3.8446302414 4.0529098511 3.9518682957 549 1305031247.8139829636 0.1062417999 0.0794294200 0.1672170013 0.0412158813 0.1410660000 0.0097820000 0.0708690000 0.0003830000 0.0002810000 0.0533330000 10332566 96830484 1770217472 3.8520305157 4.0486583710 3.9526481628 550 1305031247.8484420776 0.1047863811 0.0794755235 0.1672170013 0.0413651286 0.1295680000 0.0112440000 0.0688520000 0.0000270000 0.0003660000 0.0298500000 10334880 96830484 1769357312 3.8617708683 4.0503196716 3.9511291981 551 1305031247.8820719719 0.1088085771 0.0795287596 0.1672170013 0.0413993759 0.1287400000 0.0095680000 0.0685310000 0.0003110000 0.0002740000 0.0374580000 10337066 96830484 1771163648 3.8587405682 4.0412101746 3.9481346607 552 1305031247.9173319340 0.1041785777 0.0795734150 0.1672170013 0.0413776011 0.1080830000 0.0117910000 0.0537170000 0.0000310000 0.0003760000 0.0306870000 10339316 96830484 1770119168 3.8556044102 4.0486745834 3.9436442852 553 1305031247.9496860504 0.0962626338 0.0796035945 0.1672170013 0.0414453304 0.1454830000 0.0117760000 0.0702900000 0.0003140000 0.0002820000 0.0562280000 10341470 96830484 1768611840 3.8668501377 4.0561456680 3.9466714859 554 1305031247.9861450195 0.0990545377 0.0796387045 0.1672170013 0.0416078964 0.1267680000 0.0095970000 0.0654130000 0.0000290000 0.0003200000 0.0314950000 10343752 96830484 1770254336 3.8712196350 4.0510587692 3.9414796829 555 1305031248.0181560516 0.0985246301 0.0796727332 0.1672170013 0.0415783068 0.1303220000 0.0120080000 0.0696470000 0.0003100000 0.0003580000 0.0391280000 10345906 96830484 1768574976 3.8670535088 4.0544347763 3.9349966049 556 1305031248.0499138832 0.0942246318 0.0796989056 0.1672170013 0.0415974450 0.1076310000 0.0095720000 0.0583600000 0.0000300000 0.0003120000 0.0329320000 10348092 96830484 1770233856 3.8733580112 4.0578551292 3.9354376793 557 1305031248.0857460499 0.0902880281 0.0797179166 0.1672170013 0.0417521310 0.1466790000 0.0114730000 0.0694010000 0.0003280000 0.0002780000 0.0587700000 10350310 96830484 1769320448 3.8851618767 4.0580606461 3.9365200996 558 1305031248.1175789833 0.0869029686 0.0797307931 0.1672170013 0.0417651610 0.1258480000 0.0095900000 0.0672740000 0.0000270000 0.0003050000 0.0342780000 10352496 96830484 1771163648 3.8999598026 4.0586643219 3.9413728714 559 1305031248.1493461132 0.0806188807 0.0797323818 0.1672170013 0.0417585654 0.1080340000 0.0112320000 0.0408590000 0.0003120000 0.0002750000 0.0430280000 10354682 96830484 1770119168 3.9115383625 4.0609927177 3.9494633675 560 1305031248.1848630905 0.0786916167 0.0797305233 0.1672170013 0.0418842473 0.1270630000 0.0114360000 0.0672240000 0.0000280000 0.0003070000 0.0358080000 10356900 96830484 1768722432 3.9281444550 4.0647096634 3.9575700760 561 1305031248.2167689800 0.0748197436 0.0797217697 0.1672170013 0.0419135641 0.1397520000 0.0096940000 0.0667940000 0.0000320000 0.0003830000 0.0564540000 10359086 96830484 1770360832 3.9281444550 4.0647096634 3.9575700760 562 1305031248.2488510609 0.0715525374 0.0797072337 0.1672170013 0.0419576085 0.1309910000 0.0116230000 0.0691720000 0.0000300000 0.0003080000 0.0354960000 10361240 96830484 1768574976 3.9281444550 4.0647096634 3.9575700760 563 1305031248.2847399712 0.0682041496 0.0796868019 0.1672170013 0.0419527000 0.1156200000 0.0096580000 0.0699350000 0.0000290000 0.0003060000 0.0293030000 10363522 96830484 1770233856 3.9281444550 4.0647096634 3.9575700760 564 1305031248.3161809444 0.0660260320 0.0796625807 0.1672170013 0.0419360666 0.1379810000 0.0109010000 0.0734430000 0.0000300000 0.0003070000 0.0353590000 10365708 96830484 1769447424 3.9281444550 4.0647096634 3.9575700760 565 1305031248.3488430977 0.0858085677 0.0796734585 0.1672170013 0.0427982120 0.1309300000 0.0095670000 0.0501460000 0.0003110000 0.0002760000 0.0642100000 10367862 96830484 1771163648 3.9654204845 4.0828704834 3.9694907665 566 1305031248.3881969452 0.0905481353 0.0796926717 0.1672170013 0.0427906620 0.1056730000 0.0117970000 0.0469140000 0.0000290000 0.0003130000 0.0352380000 10370176 96830484 1770119168 3.9749219418 4.0860252380 3.9773330688 567 1305031248.4155070782 0.0953409970 0.0797202702 0.1672170013 0.0428220409 0.1087550000 0.0114860000 0.0470040000 0.0003950000 0.0002880000 0.0425200000 10372298 96830484 1768701952 3.9815216064 4.0902895927 3.9793872833 568 1305031248.4482519627 0.0988694429 0.0797539835 0.1672170013 0.0428321324 0.1254310000 0.0097190000 0.0687000000 0.0000290000 0.0003070000 0.0350510000 10374484 96830484 1770360832 3.9860053062 4.0926523209 3.9790260792 569 1305031248.4852969646 0.1023351178 0.0797936692 0.1672170013 0.0428869007 0.1437490000 0.0116090000 0.0574160000 0.0003080000 0.0002810000 0.0674470000 10376734 96830484 1768574976 3.9894645214 4.0941352844 3.9748332500 570 1305031248.5154309273 0.1020495966 0.0798327147 0.1672170013 0.0428574890 0.1102260000 0.0096320000 0.0488200000 0.0000300000 0.0003180000 0.0382640000 10378920 96830484 1770233856 3.9889056683 4.1035132408 3.9753234386 571 1305031248.5470030308 0.1049439535 0.0798766923 0.1672170013 0.0428752045 0.1097400000 0.0112610000 0.0461790000 0.0003140000 0.0002750000 0.0449730000 10381106 96830484 1769447424 3.9923512936 4.1112651825 3.9771807194 572 1305031248.5860579014 0.1026671305 0.0799165357 0.1672170013 0.0429173160 0.1257040000 0.0096760000 0.0680810000 0.0000290000 0.0003090000 0.0382470000 10383388 96830484 1771163648 3.9898438454 4.1164927483 3.9694519043 573 1305031248.6180379391 0.0951962769 0.0799432019 0.1672170013 0.0429672961 0.1426690000 0.0114430000 0.0523440000 0.0003140000 0.0003570000 0.0715300000 10385542 96830484 1770119168 3.9759888649 4.1222510338 3.9552237988 574 1305031248.6494390965 0.0952382460 0.0799698484 0.1672170013 0.0429568577 0.1114360000 0.0112230000 0.0467090000 0.0000280000 0.0003050000 0.0422270000 10387728 96830484 1768701952 3.9738130569 4.1281394958 3.9510438442 575 1305031248.6860280037 0.0952812582 0.0799964769 0.1672170013 0.0429887221 0.1498460000 0.0090350000 0.0702500000 0.0003190000 0.0002800000 0.0631300000 10390010 96830484 1770102784 3.9722704887 4.1376290321 3.9496607780 576 1305031248.7199230194 0.0957785845 0.0800238764 0.1672170013 0.0429940231 0.1451110000 0.0107100000 0.0819860000 0.0000300000 0.0003690000 0.0451260000 10392196 96830484 1769082880 3.9700114727 4.1456108093 3.9459877014 577 1305031248.7498369217 0.0960308090 0.0800516180 0.1672170013 0.0430581993 0.1476890000 0.0089280000 0.0482040000 0.0003110000 0.0002730000 0.0831920000 10394350 96830484 1770762240 3.9671835899 4.1528105736 3.9426164627 578 1305031248.7856750488 0.0966056213 0.0800802582 0.1672170013 0.0431158563 0.1283590000 0.0119910000 0.0680770000 0.0000300000 0.0003840000 0.0411090000 10396600 96830484 1769701376 3.9584286213 4.1612186432 3.9323594570 579 1305031248.8181409836 0.0995612368 0.0801139041 0.1672170013 0.0430930568 0.1440780000 0.0111870000 0.0672270000 0.0003210000 0.0003580000 0.0538740000 10398786 96830484 1768210432 3.9524145126 4.1776747704 3.9337878227 580 1305031248.8496789932 0.0962825418 0.0801417811 0.1672170013 0.0430838610 0.1099520000 0.0097680000 0.0506230000 0.0000300000 0.0005400000 0.0422700000 10400972 96830484 1769869312 3.9524145126 4.1776747704 3.9337878227 581 1305031248.8855929375 0.0925913155 0.0801632088 0.1672170013 0.0430909352 0.1628910000 0.0111230000 0.0651020000 0.0000310000 0.0003130000 0.0717210000 10403222 96830484 1768718336 3.9524145126 4.1776747704 3.9337878227 582 1305031248.9178819656 0.0898175389 0.0801797970 0.1672170013 0.0430613706 0.1274880000 0.0097250000 0.0608560000 0.0000300000 0.0003700000 0.0453710000 10405408 96830484 1770618880 3.9524145126 4.1776747704 3.9337878227 583 1305031248.9526810646 0.0868477523 0.0801912343 0.1672170013 0.0430560755 0.1278640000 0.0121160000 0.0587710000 0.0000290000 0.0003140000 0.0473980000 10407658 96830484 1769336832 3.9524145126 4.1776747704 3.9337878227 584 1305031248.9845540524 0.0841324702 0.0801979830 0.1672170013 0.0430355822 0.1261600000 0.0097340000 0.0565330000 0.0000320000 0.0003800000 0.0469520000 10409844 96830484 1770778624 3.9524145126 4.1776747704 3.9337878227 585 1305031249.0169510841 0.0834745616 0.0802035840 0.1672170013 0.0430083586 0.1466250000 0.0111970000 0.0564780000 0.0000320000 0.0003100000 0.0717060000 10412030 96830484 1770082304 3.9524145126 4.1776747704 3.9337878227 586 1305031249.0523660183 0.0832721964 0.0802088206 0.1672170013 0.0429795925 0.1269850000 0.0112540000 0.0557200000 0.0000290000 0.0003190000 0.0454230000 10414280 96830484 1768607744 3.9524145126 4.1776747704 3.9337878227 587 1305031249.0845029354 0.0846876055 0.0802164505 0.1672170013 0.0429494181 0.1272700000 0.0097080000 0.0571370000 0.0000300000 0.0003230000 0.0456390000 10416466 96830484 1770250240 3.9524145126 4.1776747704 3.9337878227 588 1305031249.1168839931 0.0861347765 0.0802265157 0.1672170013 0.0429130209 0.1275030000 0.0115200000 0.0561900000 0.0000310000 0.0003600000 0.0455810000 10418652 96830484 1769209856 3.9524145126 4.1776747704 3.9337878227 589 1305031249.1534469128 0.0891353413 0.0802416410 0.1672170013 0.0429017595 0.1497450000 0.0095720000 0.0606680000 0.0000270000 0.0003580000 0.0718790000 10420902 96830484 1770741760 3.9524145126 4.1776747704 3.9337878227 590 1305031249.1847391129 0.0910389051 0.0802599415 0.1672170013 0.0428730728 0.1256570000 0.0116490000 0.0600500000 0.0000850000 0.0002910000 0.0452280000 10423088 96830484 1769750528 3.9524145126 4.1776747704 3.9337878227 591 1305031249.2168650627 0.0926555768 0.0802809155 0.1672170013 0.0428604947 0.1272140000 0.0112610000 0.0612810000 0.0000280000 0.0002830000 0.0452520000 10425274 96830484 1768333312 3.9524145126 4.1776747704 3.9337878227 592 1305031249.2532238960 0.0949108154 0.0803056282 0.1672170013 0.0429131077 0.1265480000 0.0094210000 0.0622180000 0.0000270000 0.0003150000 0.0451120000 10427524 96830484 1770082304 3.9524145126 4.1776747704 3.9337878227 593 1305031249.2848041058 0.0962796286 0.0803325658 0.1672170013 0.0429041655 0.1653840000 0.0112780000 0.0629320000 0.0000250000 0.0002800000 0.0745260000 10429678 96830484 1769209856 3.9524145126 4.1776747704 3.9337878227 594 1305031249.3174340725 0.0975725502 0.0803615893 0.1672170013 0.0428858713 0.1285470000 0.0094750000 0.0585310000 0.0000270000 0.0002920000 0.0456960000 10431896 96830484 1770893312 3.9524145126 4.1776747704 3.9337878227 595 1305031249.3527359962 0.0986248702 0.0803922839 0.1672170013 0.0428550237 0.1276870000 0.0113830000 0.0572980000 0.0000300000 0.0003210000 0.0449580000 10434114 96830484 1769717760 3.9524145126 4.1776747704 3.9337878227 596 1305031249.3847539425 0.0998153985 0.0804248730 0.1672170013 0.0428275349 0.1248680000 0.0113190000 0.0588180000 0.0000270000 0.0002970000 0.0449870000 10436300 96830484 1768321024 3.9524145126 4.1776747704 3.9337878227 597 1305031249.4178340435 0.0996701792 0.0804571097 0.1672170013 0.0428236906 0.1456090000 0.0096420000 0.0573590000 0.0000250000 0.0003470000 0.0711980000 10438486 96830484 1770000384 3.9524145126 4.1776747704 3.9337878227 598 1305031249.4537220001 0.1019232646 0.0804930063 0.1672170013 0.0428717019 0.1460440000 0.0113800000 0.0692500000 0.0000290000 0.0003790000 0.0453640000 10440736 96830484 1768828928 3.9524145126 4.1776747704 3.9337878227 599 1305031249.4859149456 0.1024012193 0.0805295809 0.1672170013 0.0429305978 0.1275480000 0.0095240000 0.0567530000 0.0000290000 0.0002920000 0.0455610000 10442922 96830484 1770655744 3.9524145126 4.1776747704 3.9337878227 600 1305031249.5177340508 0.1027220041 0.0805665683 0.1672170013 0.0429856649 0.1276820000 0.0116340000 0.0553620000 0.0000280000 0.0003070000 0.0451090000 10445108 96830484 1769717760 3.9524145126 4.1776747704 3.9337878227 601 1305031249.5543251038 0.1038378105 0.0806052892 0.1672170013 0.0430950238 0.1460200000 0.0112360000 0.0554950000 0.0000260000 0.0002840000 0.0719180000 10447358 96830484 1768214528 3.9524145126 4.1776747704 3.9337878227 602 1305031249.5859050751 0.1053370312 0.0806463718 0.1672170013 0.0431923935 0.1270930000 0.0094610000 0.0543450000 0.0000270000 0.0002870000 0.0450910000 10449512 96830484 1769873408 3.9524145126 4.1776747704 3.9337878227 603 1305031249.6180789471 0.2339046746 0.0809005315 0.2339046746 0.0432267669 0.1457730000 0.0114650000 0.0587440000 0.0002860000 0.0003420000 0.0526830000 10451698 96830484 1768701952 3.7858712673 4.1595611572 3.8298795223 604 1305031249.6542129517 0.2389166504 0.0811621476 0.2389166504 0.0436773389 0.1293860000 0.0094220000 0.0611560000 0.0000260000 0.0003570000 0.0448280000 10453916 96830484 1770491904 3.7690284252 4.1805872917 3.8439347744 605 1305031249.6856739521 0.2366427183 0.0814191403 0.2389166504 0.0437905704 0.1512760000 0.0116630000 0.0587350000 0.0003180000 0.0003510000 0.0731480000 10456102 96830484 1768939520 3.7662184238 4.1713776588 3.8455131054 606 1305031249.7177898884 0.2146009654 0.0816389123 0.2389166504 0.0439096652 0.1225500000 0.0099480000 0.0605100000 0.0000270000 0.0002920000 0.0380460000 10458288 96830484 1770782720 3.7812509537 4.1596131325 3.8576803207 607 1305031249.7539620399 0.2153664678 0.0818592212 0.2389166504 0.0442504180 0.1264120000 0.0113870000 0.0590960000 0.0000260000 0.0002810000 0.0375560000 10460506 96830484 1769611264 3.7812509537 4.1596131325 3.8576803207 608 1305031249.7854170799 0.2148800790 0.0820780056 0.2389166504 0.0444212988 0.1269630000 0.0111530000 0.0609510000 0.0000270000 0.0003720000 0.0380710000 10462660 96830484 1768194048 3.7812509537 4.1596131325 3.8576803207 609 1305031249.8186020851 0.2153730094 0.0822968808 0.2389166504 0.0445507263 0.1482840000 0.0094570000 0.0627750000 0.0000280000 0.0002860000 0.0639420000 10464910 96830484 1770000384 3.7812509537 4.1596131325 3.8576803207 610 1305031249.8537468910 0.2163635492 0.0825166622 0.2389166504 0.0450615481 0.1267300000 0.0113920000 0.0639210000 0.0000280000 0.0002820000 0.0374280000 10467096 96830484 1768448000 3.7812509537 4.1596131325 3.8576803207 611 1305031249.8855249882 0.2177208066 0.0827379456 0.2389166504 0.0451958764 0.1269360000 0.0097100000 0.0652420000 0.0000270000 0.0002840000 0.0376450000 10469282 96830484 1770237952 3.7812509537 4.1596131325 3.8576803207 612 1305031249.9170649052 0.2190986425 0.0829607572 0.2389166504 0.0452621700 0.1278700000 0.0117960000 0.0645450000 0.0000310000 0.0002990000 0.0373520000 10471500 96830484 1768685568 3.7812509537 4.1596131325 3.8576803207 613 1305031249.9533979893 0.2205777019 0.0831852546 0.2389166504 0.0453621991 0.1425790000 0.0099150000 0.0643910000 0.0000280000 0.0002890000 0.0607040000 10473718 96830484 1770508288 3.7812509537 4.1596131325 3.8576803207 614 1305031249.9851789474 0.2216833681 0.0834108216 0.2389166504 0.0454116338 0.1309920000 0.0116680000 0.0653050000 0.0000260000 0.0002850000 0.0380070000 10475904 96830484 1769082880 3.7812509537 4.1596131325 3.8576803207 615 1305031250.0164399147 0.2226202935 0.0836371785 0.2389166504 0.0454664427 0.1265740000 0.0093330000 0.0639180000 0.0000270000 0.0003520000 0.0378920000 10478090 96830484 1770889216 3.7812509537 4.1596131325 3.8576803207 616 1305031250.0531940460 0.2229890078 0.0838633990 0.2389166504 0.0455981453 0.1276970000 0.0111810000 0.0641060000 0.0000260000 0.0002850000 0.0383520000 10480340 96830484 1769463808 3.7812509537 4.1596131325 3.8576803207 617 1305031250.0845069885 0.1088010371 0.0839038165 0.2389166504 0.0637777705 0.1423700000 0.0107490000 0.0653050000 0.0003490000 0.0002740000 0.0585940000 10482494 96830484 1768067072 3.8925971985 4.0968689919 3.9156758785 618 1305031250.1208500862 0.0998947546 0.0839296918 0.2389166504 0.0638417084 0.1092350000 0.0090290000 0.0452230000 0.0000260000 0.0003820000 0.0322980000 10484776 96830484 1769746432 3.9003434181 4.0983643532 3.9276247025 619 1305031250.1532480717 0.0991923660 0.0839543488 0.2389166504 0.0639665065 0.1293840000 0.0109440000 0.0660660000 0.0003500000 0.0002740000 0.0398150000 10486930 96830484 1768431616 3.8973970413 4.0940289497 3.9305751324 620 1305031250.1853280067 0.0951425210 0.0839723943 0.2389166504 0.0639447915 0.1077670000 0.0090240000 0.0556930000 0.0000290000 0.0002960000 0.0326830000 10489084 96830484 1770004480 3.9000446796 4.0869235992 3.9357192516 621 1305031250.2214460373 0.0932129472 0.0839872744 0.2389166504 0.0639237561 0.1325840000 0.0115340000 0.0545380000 0.0003650000 0.0002890000 0.0585160000 10491366 96830484 1768955904 3.8933556080 4.0753927231 3.9375653267 622 1305031250.2537350655 0.0921611190 0.0840004156 0.2389166504 0.0639611217 0.1186700000 0.0092890000 0.0561410000 0.0000250000 0.0002910000 0.0318690000 10493552 96830484 1770655744 3.8958475590 4.0725450516 3.9417462349 623 1305031250.2852239609 0.0921854973 0.0840135538 0.2389166504 0.0639423534 0.1286960000 0.0110760000 0.0601440000 0.0003750000 0.0002930000 0.0402000000 10495706 96830484 1769463808 3.8969140053 4.0683455467 3.9439392090 624 1305031250.3208620548 0.0888336897 0.0840212783 0.2389166504 0.0639490836 0.1266170000 0.0110120000 0.0655290000 0.0000850000 0.0004620000 0.0327430000 10497924 96830484 1767956480 3.8957622051 4.0663700104 3.9495718479 625 1305031250.3517000675 0.0866430998 0.0840254733 0.2389166504 0.0639409552 0.1414320000 0.0089990000 0.0663950000 0.0002830000 0.0003380000 0.0580480000 10500078 96830484 1769762816 3.9019467831 4.0687074661 3.9555933475 626 1305031250.3851490021 0.0866353661 0.0840296424 0.2389166504 0.0639283903 0.1156460000 0.0109320000 0.0657730000 0.0000280000 0.0003040000 0.0310730000 10502264 96830484 1768083456 3.8969984055 4.0650119781 3.9578998089 627 1305031250.4215359688 0.0892383754 0.0840379498 0.2389166504 0.0639124395 0.1255430000 0.0090680000 0.0659750000 0.0002850000 0.0004880000 0.0407210000 10504546 96830484 1770082304 3.8941721916 4.0664019585 3.9569346905 628 1305031250.4540181160 0.0903062001 0.0840479311 0.2389166504 0.0639437449 0.1078620000 0.0107970000 0.0553370000 0.0000260000 0.0005530000 0.0334120000 10506796 96830484 1768955904 3.8913321495 4.0687680244 3.9582214355 629 1305031250.4856131077 0.0908322260 0.0840587169 0.2389166504 0.0639182493 0.1380680000 0.0094330000 0.0611990000 0.0003170000 0.0002790000 0.0595300000 10508950 96830484 1770762240 3.8912966251 4.0720019341 3.9603183270 630 1305031250.5215380192 0.0920137912 0.0840713440 0.2389166504 0.0638798052 0.1169690000 0.0113080000 0.0664200000 0.0000270000 0.0002850000 0.0314970000 10511232 96830484 1769611264 3.8855576515 4.0718650818 3.9600362778 631 1305031250.5536580086 0.0939352140 0.0840869762 0.2389166504 0.0638459480 0.1244550000 0.0110640000 0.0675420000 0.0003480000 0.0002660000 0.0379050000 10513482 96830484 1768194048 3.8809630871 4.0719308853 3.9604966640 632 1305031250.5853788853 0.0963244736 0.0841063393 0.2389166504 0.0638094684 0.1237410000 0.0093260000 0.0655850000 0.0000290000 0.0003510000 0.0335980000 10515668 96830484 1769889792 3.8774809837 4.0754394531 3.9591403008 633 1305031250.6213030815 0.0987485722 0.0841294708 0.2389166504 0.0637699405 0.1457090000 0.0109240000 0.0501730000 0.0003140000 0.0155700000 0.0472260000 10517950 96830484 1768685568 3.8754944801 4.0788545609 3.9585006237 634 1305031250.6535439491 0.0985092670 0.0841521519 0.2389166504 0.0637603330 0.1279600000 0.0093080000 0.0672390000 0.0000260000 0.0003610000 0.0345950000 10520232 96830484 1770491904 3.8740689754 4.0802145004 3.9609177113 635 1305031250.6852970123 0.0963520855 0.0841713643 0.2389166504 0.0637478135 0.1272600000 0.0115080000 0.0556350000 0.0003790000 0.0002720000 0.0417230000 10522418 96830484 1768955904 3.8786406517 4.0842390060 3.9656884670 636 1305031250.7216401100 0.0943270475 0.0841873324 0.2389166504 0.0637091201 0.1272070000 0.0096130000 0.0668930000 0.0000280000 0.0002940000 0.0338560000 10524700 96830484 1770782720 3.8786547184 4.0861978531 3.9693439007 637 1305031250.7534279823 0.0928993821 0.0842010091 0.2389166504 0.0636746442 0.1443700000 0.0111880000 0.0664790000 0.0002890000 0.0003360000 0.0585170000 10526918 96830484 1769590784 3.8649032116 4.0770406723 3.9724681377 638 1305031250.7853651047 0.0915802047 0.0842125752 0.2389166504 0.0636353942 0.1297520000 0.0110130000 0.0695260000 0.0000260000 0.0002880000 0.0327590000 10529136 96830484 1767972864 3.8557817936 4.0701742172 3.9770474434 639 1305031250.8217930794 0.0909415856 0.0842231058 0.2389166504 0.0635889139 0.1285560000 0.0094160000 0.0678340000 0.0004620000 0.0002720000 0.0402080000 10531482 96830484 1769762816 3.8537056446 4.0721697807 3.9781169891 640 1305031250.8538279533 0.0894464701 0.0842312673 0.2389166504 0.0635422673 0.1265260000 0.0110370000 0.0682400000 0.0000280000 0.0002820000 0.0332770000 10533732 96830484 1768321024 3.8556165695 4.0737690926 3.9793651104 641 1305031250.8820140362 0.0891718939 0.0842389749 0.2389166504 0.0634940752 0.1260190000 0.0094790000 0.0524540000 0.0003040000 0.0004830000 0.0555880000 10535886 96830484 1770209280 3.8557641506 4.0736117363 3.9799845219 642 1305031250.9217998981 0.0918563977 0.0842508401 0.2389166504 0.0634462034 0.1277220000 0.0117170000 0.0678990000 0.0000300000 0.0004310000 0.0320650000 10538232 96830484 1769353216 3.8531048298 4.0724081993 3.9772696495 643 1305031250.9535419941 0.0938356221 0.0842657464 0.2389166504 0.0634072338 0.1258920000 0.0098110000 0.0580360000 0.0003570000 0.0002700000 0.0395420000 10540482 96830484 1771126784 3.8494126797 4.0731506348 3.9739406109 644 1305031250.9853079319 0.0917228311 0.0842773258 0.2389166504 0.0633603781 0.1278570000 0.0113580000 0.0690640000 0.0000280000 0.0002810000 0.0320510000 10542668 96830484 1770098688 3.8525726795 4.0726881027 3.9753377438 645 1305031251.0214879513 0.0913849697 0.0842883454 0.2389166504 0.0633207168 0.1445650000 0.0114610000 0.0681340000 0.0002870000 0.0002650000 0.0570580000 10544950 96830484 1768595456 3.8551099300 4.0720782280 3.9748816490 646 1305031251.0534679890 0.0936948657 0.0843029065 0.2389166504 0.0633008964 0.1287770000 0.0096160000 0.0692650000 0.0000300000 0.0003000000 0.0318620000 10547168 96830484 1770233856 3.8516235352 4.0695719719 3.9710168839 647 1305031251.0851860046 0.0924231261 0.0843154571 0.2389166504 0.0632738760 0.1296280000 0.0116330000 0.0688390000 0.0002940000 0.0002730000 0.0395360000 10549386 96830484 1768558592 3.8534255028 4.0656590462 3.9707400799 648 1305031251.1214449406 0.0915830061 0.0843266725 0.2389166504 0.0632472591 0.1251800000 0.0096060000 0.0682970000 0.0000300000 0.0002870000 0.0320490000 10551668 96830484 1770233856 3.8572394848 4.0632009506 3.9698607922 649 1305031251.1537809372 0.0890795290 0.0843339958 0.2389166504 0.0632779323 0.1447540000 0.0111290000 0.0684640000 0.0002950000 0.0002720000 0.0570000000 10553918 96830484 1769336832 3.8629367352 4.0614976883 3.9690775871 650 1305031251.1851599216 0.0886649564 0.0843406588 0.2389166504 0.0632672636 0.1286530000 0.0093540000 0.0698900000 0.0000280000 0.0003050000 0.0312900000 10556104 96830484 1770868736 3.8673887253 4.0563802719 3.9678938389 651 1305031251.2204658985 0.0857196525 0.0843427771 0.2389166504 0.0632485765 0.1293130000 0.0112760000 0.0691870000 0.0003550000 0.0002690000 0.0384160000 10558354 96830484 1769971712 3.8731858730 4.0539612770 3.9685397148 652 1305031251.2524240017 0.0837165266 0.0843418166 0.2389166504 0.0632577412 0.1257400000 0.0112670000 0.0689230000 0.0000290000 0.0003830000 0.0314750000 10560540 96830484 1768464384 3.8791060448 4.0510344505 3.9687550068 653 1305031251.2844820023 0.0844436660 0.0843419726 0.2389166504 0.0633588094 0.1428380000 0.0094200000 0.0687250000 0.0003540000 0.0002690000 0.0563420000 10562758 96830484 1770123264 3.8831133842 4.0466308594 3.9658057690 654 1305031251.3190040588 0.0828966945 0.0843397627 0.2389166504 0.0633880819 0.0917740000 0.0107920000 0.0360440000 0.0000270000 0.0002960000 0.0335880000 10565008 96830484 1769082880 3.8919639587 4.0448412895 3.9665648937 655 1305031251.3532440662 0.0797882676 0.0843328138 0.2389166504 0.0634092967 0.1183270000 0.0094360000 0.0638470000 0.0002870000 0.0003430000 0.0362750000 10567194 96830484 1767829504 3.9005694389 4.0425190926 3.9693291187 656 1305031251.3870069981 0.0771368593 0.0843218444 0.2389166504 0.0634065255 0.1114790000 0.0091230000 0.0596900000 0.0000290000 0.0004900000 0.0315510000 10569412 96830484 1767071744 3.9097526073 4.0440850258 3.9733393192 657 1305031251.4210500717 0.0793388039 0.0843142598 0.2389166504 0.0634447982 0.1433200000 0.0094450000 0.0679060000 0.0003550000 0.0002730000 0.0576480000 10571630 96830484 1766150144 3.9121778011 4.0399594307 3.9697422981 658 1305031251.4496629238 0.0777278468 0.0843042501 0.2389166504 0.0634576114 0.1295470000 0.0107910000 0.0673400000 0.0000240000 0.0003510000 0.0324430000 10573752 96830484 1765273600 3.9238021374 4.0404748917 3.9755568504 659 1305031251.4890139103 0.0754624382 0.0842908331 0.2389166504 0.0634907785 0.1287580000 0.0097350000 0.0686780000 0.0002900000 0.0002630000 0.0396150000 10576034 96830484 1766907904 3.9299383163 4.0421948433 3.9779579639 660 1305031251.5207729340 0.0754628927 0.0842774574 0.2389166504 0.0635285873 0.0890460000 0.0097270000 0.0407660000 0.0000260000 0.0003580000 0.0304130000 10578252 96830484 1768697856 3.9383912086 4.0441370010 3.9804964066 661 1305031251.5530450344 0.0753555447 0.0842639598 0.2389166504 0.0635731767 0.1428830000 0.0086740000 0.0512390000 0.0003670000 0.0002710000 0.0628040000 10580438 96830484 1770590208 3.9445369244 4.0464901924 3.9810981750 662 1305031251.5887598991 0.0729445741 0.0842468610 0.2389166504 0.0635712994 0.1105290000 0.0115810000 0.0586660000 0.0000280000 0.0002910000 0.0315170000 10582656 96830484 1769447424 3.9456095695 4.0537700653 3.9817650318 663 1305031251.6208739281 0.0720410645 0.0842284511 0.2389166504 0.0635711646 0.1268730000 0.0096770000 0.0681290000 0.0002920000 0.0003440000 0.0381720000 10584874 96830484 1770844160 3.9498562813 4.0570373535 3.9844152927 664 1305031251.6528749466 0.0712212101 0.0842088619 0.2389166504 0.0635937047 0.1083070000 0.0117020000 0.0583220000 0.0000280000 0.0002910000 0.0301450000 10587060 96830484 1768955904 3.9525139332 4.0613021851 3.9849395752 665 1305031251.6897680759 0.0710935369 0.0841891396 0.2389166504 0.0635941666 0.1355170000 0.0099480000 0.0589110000 0.0002870000 0.0002690000 0.0583340000 10589310 96830484 1770479616 3.9533858299 4.0662961006 3.9848308563 666 1305031251.7204608917 0.0720753223 0.0841709507 0.2389166504 0.0636138267 0.1336720000 0.0118240000 0.0681240000 0.0000270000 0.0003470000 0.0317750000 10591496 96830484 1768701952 3.9583048820 4.0664172173 3.9871628284 667 1305031251.7531440258 0.0756037906 0.0841581064 0.2389166504 0.0636576118 0.1248900000 0.0099520000 0.0584200000 0.0003620000 0.0002770000 0.0401860000 10593682 96830484 1770225664 3.9668750763 4.0623970032 3.9890210629 668 1305031251.7892498970 0.0800695643 0.0841519858 0.2389166504 0.0636607926 0.1073010000 0.0118830000 0.0481170000 0.0000310000 0.0003000000 0.0346270000 10595932 96830484 1768194048 3.9745185375 4.0660605431 3.9934625626 669 1305031251.8209791183 0.0830153972 0.0841502868 0.2389166504 0.0636626963 0.1447440000 0.0098770000 0.0478230000 0.0001170000 0.0001050000 0.0668330000 10598118 96830484 1769955328 3.9811847210 4.0677275658 3.9990794659 670 1305031251.8537969589 0.0901912004 0.0841593031 0.2389166504 0.0637214511 0.1076940000 0.0117110000 0.0405870000 0.0000280000 0.0002940000 0.0384410000 10600304 96830484 1768194048 3.9921011925 4.0653777122 4.0036053658 671 1305031251.8896539211 0.0991447419 0.0841816361 0.2389166504 0.0636951969 0.1460790000 0.0100410000 0.0680980000 0.0003020000 0.0002700000 0.0486550000 10602522 96830484 1769971712 4.0032901764 4.0681061745 4.0101580620 672 1305031251.9219300747 0.0996476114 0.0842046510 0.2389166504 0.0636662261 0.1305970000 0.0123120000 0.0690170000 0.0000260000 0.0005320000 0.0407850000 10604740 96830484 1768194048 4.0046920776 4.0777382851 4.0166654587 673 1305031251.9538369179 0.0992615074 0.0842270237 0.2389166504 0.0636464612 0.1486590000 0.0097000000 0.0526980000 0.0003800000 0.0002810000 0.0775780000 10606894 96830484 1769955328 4.0047721863 4.0855016708 4.0208253860 674 1305031251.9898068905 0.0999254733 0.0842503152 0.2389166504 0.0636206368 0.1238470000 0.0116090000 0.0574710000 0.0000290000 0.0002940000 0.0450140000 10609144 96830484 1768194048 4.0067591667 4.0881018639 4.0233473778 675 1305031252.0221600533 0.1013503075 0.0842756485 0.2389166504 0.0636140348 0.1267030000 0.0097880000 0.0525140000 0.0003000000 0.0002900000 0.0543190000 10611362 96830484 1769861120 4.0094904900 4.0942120552 4.0271320343 676 1305031252.0537619591 0.1033612639 0.0843038817 0.2389166504 0.0635905854 0.1296690000 0.0117390000 0.0644680000 0.0000270000 0.0003110000 0.0452360000 10613548 96830484 1767796736 4.0132074356 4.1062502861 4.0343890190 677 1305031252.0895619392 0.1017697230 0.0843296805 0.2389166504 0.0636007488 0.1621860000 0.0098670000 0.0516570000 0.0003810000 0.0002800000 0.0844690000 10615766 96830484 1769607168 4.0116477013 4.1189575195 4.0356302261 678 1305031252.1221520901 0.0954697356 0.0843461113 0.2389166504 0.0636181354 0.1262340000 0.0114200000 0.0481920000 0.0000340000 0.0003170000 0.0479970000 10617984 96830484 1767809024 4.0064039230 4.1275191307 4.0314979553 679 1305031252.1539709568 0.0920075178 0.0843573947 0.2389166504 0.0636779241 0.1308950000 0.0097060000 0.0576160000 0.0003160000 0.0002610000 0.0549840000 10620106 96830484 1769459712 4.0029516220 4.1413497925 4.0299258232 680 1305031252.1897890568 0.0885372236 0.0843635415 0.2389166504 0.0636430230 0.1442630000 0.0113980000 0.0690350000 0.0000300000 0.0003040000 0.0477600000 10622356 96830484 1767575552 3.9868800640 4.1624984741 4.0243048668 681 1305031252.2220859528 0.0838257521 0.0843627518 0.2389166504 0.0636148679 0.1453220000 0.0097500000 0.0512350000 0.0000310000 0.0005390000 0.0755110000 10624574 96830484 1769349120 3.9868800640 4.1624984741 4.0243048668 682 1305031252.2530639172 0.0784201920 0.0843540383 0.2389166504 0.0635714266 0.1300700000 0.0096660000 0.0625480000 0.0000290000 0.0003100000 0.0483720000 10626760 96830484 1771110400 3.9868800640 4.1624984741 4.0243048668 683 1305031252.2888779640 0.2391479313 0.0845806765 0.2391479313 0.0652285498 0.1454400000 0.0116270000 0.0597810000 0.0003130000 0.0002750000 0.0561150000 10628946 96830484 1769955328 3.7648959160 4.1864709854 3.8884029388 684 1305031252.3206090927 0.2402067035 0.0848082000 0.2402067035 0.0651837885 0.1280720000 0.0115560000 0.0574880000 0.0000290000 0.0003020000 0.0475670000 10631132 96830484 1768337408 3.7648959160 4.1864709854 3.8884029388 685 1305031252.3528549671 0.2407701313 0.0850358816 0.2407701313 0.0651366470 0.1508820000 0.0100720000 0.0575380000 0.0000290000 0.0002990000 0.0749460000 10633286 96830484 1769869312 3.7648959160 4.1864709854 3.8884029388 686 1305031252.3893189430 0.2401493490 0.0852619946 0.2407701313 0.0651008398 0.1243770000 0.0111790000 0.0586330000 0.0000270000 0.0003010000 0.0460270000 10635536 96830484 1769209856 3.7648959160 4.1864709854 3.8884029388 687 1305031252.4217019081 0.2390976399 0.0854859183 0.2407701313 0.0650702662 0.1258770000 0.0097640000 0.0585180000 0.0000280000 0.0003860000 0.0479920000 10637754 96830484 1770856448 3.7648959160 4.1864709854 3.8884029388 688 1305031252.4538249969 0.2371550202 0.0857063676 0.2407701313 0.0650285419 0.1281950000 0.0113120000 0.0590700000 0.0000290000 0.0003050000 0.0477940000 10639940 96830484 1769717760 3.7648959160 4.1864709854 3.8884029388 689 1305031252.4895589352 0.2364929318 0.0859252160 0.2407701313 0.0649831047 0.1649430000 0.0117960000 0.0588520000 0.0000320000 0.0003060000 0.0782240000 10642126 96830484 1768067072 3.7648959160 4.1864709854 3.8884029388 690 1305031252.5221700668 0.2354640514 0.0861419390 0.2407701313 0.0649377939 0.1279580000 0.0096100000 0.0594020000 0.0000260000 0.0003730000 0.0480200000 10644344 96830484 1769861120 3.7648959160 4.1864709854 3.8884029388 691 1305031252.5537741184 0.2346402407 0.0863568425 0.2407701313 0.0649089114 0.1437110000 0.0117870000 0.0603130000 0.0000280000 0.0003090000 0.0482730000 10646530 96830484 1767829504 3.7648959160 4.1864709854 3.8884029388 692 1305031252.5897459984 0.2343383580 0.0865706886 0.2407701313 0.0648703883 0.1297880000 0.0096280000 0.0623350000 0.0000300000 0.0002950000 0.0476190000 10648748 96830484 1769336832 3.7648959160 4.1864709854 3.8884029388 693 1305031252.6221249104 0.2340670377 0.0867835260 0.2407701313 0.0648250521 0.1543780000 0.0098570000 0.0605560000 0.0000280000 0.0002980000 0.0754130000 10650966 96830484 1771110400 3.7648959160 4.1864709854 3.8884029388 694 1305031252.6578559875 0.2346728593 0.0869966231 0.2407701313 0.0647949449 0.1374490000 0.0131460000 0.0605190000 0.0000270000 0.0003870000 0.0479080000 10653184 96830484 1769971712 3.7648959160 4.1864709854 3.8884029388 695 1305031252.6889979839 0.2345528305 0.0872089341 0.2407701313 0.0647941490 0.1288320000 0.0121900000 0.0601300000 0.0000270000 0.0003020000 0.0479560000 10655338 96830484 1768337408 3.7648959160 4.1864709854 3.8884029388 696 1305031252.7216539383 0.2337487340 0.0874194798 0.2407701313 0.0648524384 0.1259580000 0.0101040000 0.0573020000 0.0000300000 0.0003700000 0.0482660000 10657524 96830484 1769828352 3.7648959160 4.1864709854 3.8884029388 697 1305031252.7578220367 0.2325048894 0.0876276368 0.2407701313 0.0651929413 0.1650580000 0.0116010000 0.0575920000 0.0000300000 0.0002990000 0.0786530000 10659806 96830484 1768321024 3.7648959160 4.1864709854 3.8884029388 698 1305031252.7896919250 0.2314010561 0.0878336159 0.2407701313 0.0653031707 0.1271030000 0.0100010000 0.0551810000 0.0000330000 0.0003040000 0.0482500000 10661960 96830484 1769967616 3.7648959160 4.1864709854 3.8884029388 699 1305031252.8224050999 0.2306690216 0.0880379584 0.2407701313 0.0653440799 0.1276650000 0.0113480000 0.0564610000 0.0000300000 0.0003750000 0.0478680000 10664178 96830484 1769209856 3.7648959160 4.1864709854 3.8884029388 700 1305031252.8539779186 0.2305487692 0.0882415453 0.2407701313 0.0653812930 0.1266220000 0.0095840000 0.0554440000 0.0000260000 0.0003770000 0.0479440000 10666300 96830484 1770762240 3.7648959160 4.1864709854 3.8884029388 701 1305031252.8897290230 0.2303262800 0.0884442339 0.2407701313 0.0653671866 0.1635560000 0.0115660000 0.0586080000 0.0000310000 0.0003780000 0.0787870000 10668550 96830484 1769844736 3.7648959160 4.1864709854 3.8884029388 702 1305031252.9206719398 0.4184213579 0.0889142868 0.4184213579 0.0661695021 0.1475420000 0.0116000000 0.0740890000 0.0000060000 0.0000730000 0.0493870000 10670736 96830484 1767940096 3.6105647087 4.1282219887 3.7549695969 703 1305031252.9578649998 0.4553964734 0.0894355986 0.4553964734 0.0662417664 0.1655400000 0.0102000000 0.0784740000 0.0003110000 0.0002740000 0.0617430000 10673050 96830484 1769635840 3.5744593143 4.1156396866 3.7351856232 704 1305031252.9894239902 0.4733904302 0.0899809890 0.4733904302 0.0663275397 0.1659350000 0.0109480000 0.0800780000 0.0000320000 0.0003080000 0.0565640000 10675172 96830484 1768583168 3.5533528328 4.1132349968 3.7291991711 705 1305031253.0196959972 0.4612766802 0.0905076495 0.4733904302 0.0664058303 0.1871220000 0.0093100000 0.0720180000 0.0003850000 0.0002870000 0.0888470000 10677358 96830484 1770262528 3.5581285954 4.1046147346 3.7389245033 706 1305031253.0574259758 0.4765660167 0.0910544744 0.4765660167 0.0664492443 0.1271410000 0.0113670000 0.0558770000 0.0000290000 0.0003670000 0.0446640000 10679640 96830484 1769218048 3.5403103828 4.0907740593 3.7325615883 707 1305031253.0895500183 0.4722172618 0.0915936014 0.4765660167 0.0664615218 0.1280670000 0.0093920000 0.0556210000 0.0004470000 0.0003640000 0.0520980000 10681794 96830484 1770897408 3.5431041718 4.0778145790 3.7327976227 708 1305031253.1197240353 0.4837771058 0.0921475329 0.4837771058 0.0664979489 0.1257410000 0.0112870000 0.0564850000 0.0000290000 0.0002980000 0.0431850000 10683980 96830484 1769836544 3.5297663212 4.0767636299 3.7272453308 709 1305031253.1573839188 0.4814272821 0.0926965876 0.4837771058 0.0664648165 0.1448350000 0.0114340000 0.0558360000 0.0000270000 0.0003110000 0.0687890000 10686230 96830484 1768325120 3.5297663212 4.0767636299 3.7272453308 710 1305031253.1892180443 0.4808574617 0.0932432930 0.4837771058 0.0664256299 0.1271000000 0.0096480000 0.0541660000 0.0000280000 0.0002950000 0.0435880000 10688384 96830484 1769877504 3.5297663212 4.0767636299 3.7272453308 711 1305031253.2180271149 0.4805606902 0.0937880432 0.4837771058 0.0663934697 0.1279130000 0.0114570000 0.0560150000 0.0000300000 0.0003010000 0.0436740000 10690570 96830484 1768996864 3.5297663212 4.0767636299 3.7272453308 712 1305031253.2578470707 0.4804765582 0.0943311451 0.4837771058 0.0663876507 0.1263480000 0.0101340000 0.0555860000 0.0000260000 0.0002990000 0.0432600000 10692884 96830484 1770643456 3.5297663212 4.0767636299 3.7272453308 713 1305031253.2897419930 0.4809578955 0.0948733986 0.4837771058 0.0663523123 0.1470740000 0.0115070000 0.0573550000 0.0000290000 0.0003010000 0.0693180000 10695038 96830484 1769598976 3.5297663212 4.0767636299 3.7272453308 714 1305031253.3220069408 0.4815095961 0.0954149059 0.4837771058 0.0663110670 0.1282360000 0.0117140000 0.0598450000 0.0000270000 0.0003630000 0.0433750000 10697256 96830484 1768091648 3.5297663212 4.0767636299 3.7272453308 715 1305031253.3578300476 0.1344647408 0.0954695210 0.4837771058 0.0674101367 0.1265160000 0.0095180000 0.0599490000 0.0002980000 0.0003590000 0.0433810000 10699474 96830484 1769852928 3.8272325993 4.0891361237 3.9291801453 716 1305031253.3880970478 0.0698693842 0.0954337666 0.4837771058 0.0674889285 0.1268980000 0.0112010000 0.0681740000 0.0002590000 0.0003090000 0.0335720000 10701628 96830484 1768345600 3.9460694790 4.0864620209 4.0075316429 717 1305031253.4213519096 0.0719728991 0.0954010458 0.4837771058 0.0674431865 0.1481220000 0.0096170000 0.0678940000 0.0002930000 0.0003380000 0.0615260000 10703846 96830484 1770123264 3.9486975670 4.0850491524 4.0087800026 718 1305031253.4579629898 0.0725741908 0.0953692535 0.4837771058 0.0673977357 0.1266860000 0.0117730000 0.0702710000 0.0000270000 0.0003550000 0.0348320000 10706096 96830484 1768759296 3.9484434128 4.0863575935 4.0097146034 719 1305031253.4896900654 0.0708761662 0.0953351880 0.4837771058 0.0673511890 0.1259100000 0.0097610000 0.0571630000 0.0003610000 0.0002740000 0.0423800000 10708282 96830484 1770242048 3.9446146488 4.0891938210 4.0096106529 720 1305031253.5207340717 0.0715427846 0.0953021430 0.4837771058 0.0673058229 0.1075480000 0.0114260000 0.0467720000 0.0000320000 0.0003160000 0.0349090000 10710468 96830484 1769250816 3.9438884258 4.0866756439 4.0084590912 721 1305031253.5578539371 0.0717638582 0.0952694963 0.4837771058 0.0672609617 0.1390890000 0.0097940000 0.0568150000 0.0003110000 0.0002660000 0.0634430000 10712718 96830484 1770876928 3.9409356117 4.0886182785 4.0071554184 722 1305031253.5898048878 0.0691295192 0.0952332913 0.4837771058 0.0672188655 0.0970230000 0.0119210000 0.0443820000 0.0000270000 0.0003110000 0.0318330000 10714904 96830484 1769631744 3.9375693798 4.0913314819 4.0100965500 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 03:29:13 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253987648 0.0253987648 0.0253987648 nan 0.1144280000 0.0158470000 0.0156510000 0.0001090000 0.0000120000 0.0804500000 8234222 96830484 1767612416 4.0000000000 4.0000000000 4.0000000000 2 1305031102.2112140656 0.0277590584 0.0265789116 0.0277590584 0.0329534858 0.0432330000 0.0100290000 0.0082400000 0.0000700000 0.0000040000 0.0233190000 8892104 96830484 1769771008 4.0000000000 4.0000000000 4.0000000000 3 1305031102.2432110310 0.0337214470 0.0289597567 0.0337214470 0.0304148611 0.0797460000 0.0363080000 0.0155490000 0.0000620000 0.0000040000 0.0258130000 8894614 96830484 1767641088 4.0000000000 4.0000000000 4.0000000000 4 1305031102.2753260136 0.0413634107 0.0320606702 0.0413634107 0.0283056894 0.0682040000 0.0106270000 0.0102290000 0.0001760000 0.0001360000 0.0463300000 8897148 96830484 1767649280 4.0000000000 4.0000000000 4.0000000000 5 1305031102.3112668991 0.0195333268 0.0295552015 0.0413634107 0.0301329162 0.1261920000 0.0088510000 0.0499120000 0.0003300000 0.0019600000 0.0634050000 8899718 96830484 1766903808 3.9956057072 3.9985215664 4.0339012146 6 1305031102.3432331085 0.0165448189 0.0273868044 0.0413634107 0.0279478040 0.1111050000 0.0090890000 0.0679690000 0.0000240000 0.0002770000 0.0318520000 8902560 96830484 1765867520 3.9933166504 3.9975037575 4.0460615158 7 1305031102.3753290176 0.0143035026 0.0255177613 0.0413634107 0.0256299190 0.0953490000 0.0092630000 0.0460290000 0.0003120000 0.0006510000 0.0372670000 8904714 96830484 1767485440 3.9915561676 3.9987485409 4.0578479767 8 1305031102.4112579823 0.0161063094 0.0243413298 0.0413634107 0.0248946262 0.0784350000 0.0090690000 0.0346410000 0.0000210000 0.0003430000 0.0324920000 8906996 96830484 1769267200 3.9903631210 4.0006780624 4.0697340965 9 1305031102.4432709217 0.0140135018 0.0231937934 0.0413634107 0.0252535638 0.1255080000 0.0097950000 0.0597280000 0.0004230000 0.0002770000 0.0548230000 8909822 96830484 1768390656 3.9873230457 4.0034270287 4.0821080208 10 1305031102.4753179550 0.0116270650 0.0220371205 0.0413634107 0.0240294950 0.0749620000 0.0085760000 0.0356830000 0.0000270000 0.0002960000 0.0298790000 8913288 96830484 1770180608 3.9876568317 4.0076665878 4.0952644348 11 1305031102.5112190247 0.0164490193 0.0215291113 0.0413634107 0.0234072113 0.0981670000 0.0105270000 0.0504210000 0.0002970000 0.0002750000 0.0345850000 8915538 96830484 1769279488 3.9873988628 4.0066909790 4.1077752113 12 1305031102.5432200432 0.0179887172 0.0212340785 0.0413634107 0.0223192355 0.1051950000 0.0103300000 0.0653560000 0.0000260000 0.0003600000 0.0270580000 8917756 96830484 1767919616 3.9864666462 4.0065851212 4.1198124886 13 1305031102.5752859116 0.0202986002 0.0211621186 0.0413634107 0.0221638080 0.1306470000 0.0091550000 0.0679180000 0.0004000000 0.0002760000 0.0505070000 8919910 96830484 1769562112 3.9835603237 4.0057654381 4.1314287186 14 1305031102.6112329960 0.0283821970 0.0216778385 0.0413634107 0.0226195854 0.1069200000 0.0108660000 0.0690920000 0.0000260000 0.0003620000 0.0244920000 8922160 96830484 1768173568 3.9843022823 4.0026168823 4.1423993111 15 1305031102.6432650089 0.0308798477 0.0222913058 0.0413634107 0.0225175673 0.0876230000 0.0089570000 0.0458510000 0.0003270000 0.0002610000 0.0300780000 8924346 96830484 1769816064 3.9798583984 4.0030717850 4.1535291672 16 1305031102.6752851009 0.0282558128 0.0226640875 0.0413634107 0.0223348935 0.0786850000 0.0119230000 0.0377190000 0.0000260000 0.0002850000 0.0264250000 8926532 96830484 1768427520 3.9764909744 4.0096969604 4.1653313637 17 1305031102.7112629414 0.0316540524 0.0231929089 0.0413634107 0.0218772512 0.1361670000 0.0084270000 0.0792080000 0.0000700000 0.0000520000 0.0458400000 8930062 96830484 1767280640 3.9767699242 4.0127444267 4.1776733398 18 1305031102.7432339191 0.0347451679 0.0238347011 0.0413634107 0.0212948966 0.0944010000 0.0087570000 0.0666110000 0.0000060000 0.0001800000 0.0182730000 8934904 96830484 1769054208 3.9764485359 4.0140333176 4.1902980804 19 1305031102.7754719257 0.0331700183 0.0243260336 0.0413634107 0.0211206091 0.1040370000 0.0094870000 0.0547280000 0.0002930000 0.0002730000 0.0368280000 8937058 96830484 1770659840 3.9771361351 4.0198812485 4.2032289505 20 1305031102.8112320900 0.0379331224 0.0250063880 0.0413634107 0.0206080147 0.0891110000 0.0106660000 0.0514170000 0.0000240000 0.0002820000 0.0259450000 8939308 96830484 1769406464 3.9763009548 4.0221447945 4.2156324387 21 1305031102.8432900906 0.0390089266 0.0256731756 0.0413634107 0.0201146418 0.1391860000 0.0089490000 0.0779630000 0.0002910000 0.0002590000 0.0510930000 8941526 96830484 1768628224 3.9773452282 4.0256042480 4.2279925346 22 1305031102.8753631115 0.0411536470 0.0263768334 0.0413634107 0.0197009263 0.0752840000 0.0090890000 0.0430600000 0.0000260000 0.0003550000 0.0217670000 8943680 96830484 1770192896 3.9738872051 4.0273647308 4.2397923470 23 1305031102.9111850262 0.0446395576 0.0271708649 0.0446395576 0.0193043963 0.0881480000 0.0110750000 0.0476720000 0.0003330000 0.0003400000 0.0273970000 8945930 96830484 1769279488 3.9713752270 4.0300016403 4.2513937950 24 1305031102.9432289600 0.0453404114 0.0279279293 0.0453404114 0.0191927461 0.1106470000 0.0110700000 0.0804320000 0.0000270000 0.0003870000 0.0180650000 8948148 96830484 1767612416 3.9698677063 4.0335602760 4.2626938820 25 1305031102.9752030373 0.0475470982 0.0287126961 0.0475470982 0.0199013822 0.0963600000 0.0087420000 0.0466530000 0.0003780000 0.0002660000 0.0396640000 8950270 96830484 1769287680 3.9655289650 4.0359401703 4.2742662430 26 1305031103.0112149715 0.0510637686 0.0295723527 0.0510637686 0.0195097764 0.1109110000 0.0098710000 0.0770350000 0.0000250000 0.0002820000 0.0209860000 8952552 96830484 1768554496 3.9648694992 4.0386037827 4.2861394882 27 1305031103.0432269573 0.0534251183 0.0304557885 0.0534251183 0.0191444226 0.1093280000 0.0092050000 0.0712710000 0.0003800000 0.0002700000 0.0258470000 8954770 96830484 1770405888 3.9658572674 4.0412397385 4.2976827621 28 1305031103.0753190517 0.0555827245 0.0313531790 0.0555827245 0.0193364758 0.0885380000 0.0112730000 0.0545860000 0.0000230000 0.0002830000 0.0205810000 8956924 96830484 1769533440 3.9671730995 4.0437254906 4.3083190918 29 1305031103.1112399101 0.0594807900 0.0323230967 0.0594807900 0.0191800378 0.1053730000 0.0101630000 0.0520890000 0.0002850000 0.0003700000 0.0395570000 8959174 96830484 1769025536 3.9668893814 4.0455904007 4.3178968430 30 1305031103.1433179379 0.0581783578 0.0331849387 0.0594807900 0.0188762913 0.1028410000 0.0096470000 0.0695370000 0.0000240000 0.0003780000 0.0198390000 8961360 96830484 1770684416 3.9674406052 4.0516290665 4.3274393082 31 1305031103.1754519939 0.0602659807 0.0340585207 0.0602659807 0.0185761688 0.1093480000 0.0113060000 0.0694290000 0.0002940000 0.0003040000 0.0260220000 8963546 96830484 1769660416 3.9664041996 4.0536804199 4.3364005089 32 1305031103.2112200260 0.0610772856 0.0349028571 0.0610772856 0.0191015557 0.0937080000 0.0110620000 0.0584150000 0.0000250000 0.0003110000 0.0209430000 8965796 96830484 1768157184 3.9658966064 4.0586519241 4.3452472687 33 1305031103.2432160378 0.0621651299 0.0357289866 0.0621651299 0.0188237163 0.1004950000 0.0095770000 0.0537370000 0.0003470000 0.0002650000 0.0358210000 8970574 96830484 1769897984 3.9667682648 4.0620660782 4.3542551994 34 1305031103.2753698826 0.0650250390 0.0365906352 0.0650250390 0.0188549288 0.0871870000 0.0104980000 0.0539220000 0.0000250000 0.0003060000 0.0193210000 8977976 96830484 1768792064 3.9674754143 4.0629887581 4.3626885414 35 1305031103.3112099171 0.0700971037 0.0375479628 0.0700971037 0.0192347256 0.0904650000 0.0095740000 0.0616960000 0.0000610000 0.0000530000 0.0183670000 8980226 96830484 1768009728 3.9659249783 4.0604496002 4.3701753616 36 1305031103.3432230949 0.0758352578 0.0386114988 0.0758352578 0.0198416100 0.1078280000 0.0089320000 0.0733130000 0.0000250000 0.0003450000 0.0244120000 8982444 96830484 1766264832 3.9654779434 4.0556130409 4.3751101494 37 1305031103.3753271103 0.0763708875 0.0396320228 0.0763708875 0.0198016773 0.1183600000 0.0098660000 0.0743500000 0.0003190000 0.0004400000 0.0301750000 8984598 96830484 1765363712 3.9692285061 4.0556783676 4.3777933121 38 1305031103.4112598896 0.0776000842 0.0406311823 0.0776000842 0.0196930750 0.1130080000 0.0113310000 0.0782820000 0.0000250000 0.0003490000 0.0191510000 8986848 96830484 1765117952 3.9701306820 4.0531792641 4.3786349297 39 1305031103.4432799816 0.0807347819 0.0416594798 0.0807347819 0.0195205338 0.1111450000 0.0100510000 0.0725850000 0.0002890000 0.0002640000 0.0249290000 8989066 96830484 1766850560 3.9694547653 4.0481357574 4.3773770332 40 1305031103.4752740860 0.0811195299 0.0426459810 0.0811195299 0.0192876299 0.0790140000 0.0093300000 0.0468110000 0.0000240000 0.0003110000 0.0191790000 8991220 96830484 1768628224 3.9697365761 4.0450878143 4.3745675087 41 1305031103.5113329887 0.0811937377 0.0435861702 0.0811937377 0.0191520969 0.1159020000 0.0090830000 0.0715620000 0.0002810000 0.0003300000 0.0337940000 8993470 96830484 1770278912 3.9700250626 4.0407810211 4.3698382378 42 1305031103.5434439182 0.0811153352 0.0444797218 0.0811937377 0.0190258079 0.1033090000 0.0118940000 0.0696240000 0.0000890000 0.0002800000 0.0187050000 8995688 96830484 1769025536 3.9700105190 4.0357704163 4.3631553650 43 1305031103.5754740238 0.0802901089 0.0453125215 0.0811937377 0.0188466609 0.0865060000 0.0093030000 0.0478610000 0.0003110000 0.0003010000 0.0244790000 8997842 96830484 1770848256 3.9711244106 4.0310397148 4.3548936844 44 1305031103.6112229824 0.0770352334 0.0460334922 0.0811937377 0.0187164430 0.1144600000 0.0114990000 0.0787870000 0.0000240000 0.0002770000 0.0202080000 9000092 96830484 1769787392 3.9729008675 4.0282773972 4.3457379341 45 1305031103.6434450150 0.0753333122 0.0466845993 0.0811937377 0.0185082496 0.1059470000 0.0121710000 0.0550490000 0.0002850000 0.0002580000 0.0373350000 9002310 96830484 1768136704 3.9738616943 4.0236878395 4.3359322548 46 1305031103.6755230427 0.0724235177 0.0472441410 0.0811937377 0.0183368469 0.0904980000 0.0089860000 0.0568760000 0.0000250000 0.0003820000 0.0200130000 9004464 96830484 1770070016 3.9728212357 4.0198321342 4.3255701065 47 1305031103.7116100788 0.0688500479 0.0477038411 0.0811937377 0.0181540021 0.0849720000 0.0109860000 0.0413220000 0.0010530000 0.0003430000 0.0270510000 9006714 96830484 1768808448 3.9737153053 4.0162124634 4.3144426346 48 1305031103.7433259487 0.0657440871 0.0480796796 0.0811937377 0.0180078788 0.0782910000 0.0096100000 0.0414830000 0.0000260000 0.0002810000 0.0229400000 9008932 96830484 1767493632 3.9762561321 4.0123734474 4.3024859428 49 1305031103.7753419876 0.0638268590 0.0484010506 0.0811937377 0.0178203752 0.1563880000 0.0106600000 0.0950420000 0.0000670000 0.0000530000 0.0496950000 9011086 96830484 1765961728 3.9764957428 4.0066742897 4.2898902893 50 1305031103.8112421036 0.0589402579 0.0486118348 0.0811937377 0.0180208948 0.1070590000 0.0091160000 0.0708290000 0.0000240000 0.0002820000 0.0228770000 9013336 96830484 1767673856 3.9777789116 4.0048780441 4.2767782211 51 1305031103.8432509899 0.0550169572 0.0487374254 0.0811937377 0.0180099100 0.0852830000 0.0093610000 0.0425370000 0.0005510000 0.0003030000 0.0282800000 9015554 96830484 1769267200 3.9791357517 4.0025796890 4.2640333176 52 1305031103.8753609657 0.0524370186 0.0488085714 0.0811937377 0.0179534453 0.1076500000 0.0109100000 0.0690480000 0.0000270000 0.0003880000 0.0233330000 9017708 96830484 1768284160 3.9783859253 3.9991269112 4.2519989014 53 1305031103.9112210274 0.0556469746 0.0489375979 0.0811937377 0.0189002852 0.1295100000 0.0095040000 0.0689680000 0.0002820000 0.0003730000 0.0461170000 9019958 96830484 1769943040 3.9784467220 3.9886476994 4.2391452789 54 1305031103.9432110786 0.0559278019 0.0490670461 0.0811937377 0.0187677380 0.1129860000 0.0112880000 0.0729940000 0.0000270000 0.0004960000 0.0246010000 9022176 96830484 1768644608 3.9791457653 3.9813356400 4.2256369591 55 1305031103.9753730297 0.0519804582 0.0491200172 0.0811937377 0.0187085763 0.1129970000 0.0093890000 0.0681790000 0.0002820000 0.0003680000 0.0304020000 9024362 96830484 1770323968 3.9803066254 3.9784333706 4.2111039162 56 1305031104.0112318993 0.0503447615 0.0491418877 0.0811937377 0.0189054175 0.0881440000 0.0111180000 0.0465880000 0.0000240000 0.0003410000 0.0258550000 9026580 96830484 1769279488 3.9830954075 3.9732320309 4.1966204643 57 1305031104.0432488918 0.0481104292 0.0491237919 0.0811937377 0.0188430247 0.1125040000 0.0124360000 0.0510580000 0.0003180000 0.0003380000 0.0473820000 9028798 96830484 1768120320 3.9865303040 3.9676463604 4.1817388535 58 1305031104.0754249096 0.0415253788 0.0489927848 0.0811937377 0.0188774161 0.0885300000 0.0088100000 0.0475550000 0.0000280000 0.0006950000 0.0271500000 9030952 96830484 1769824256 3.9870662689 3.9672503471 4.1664209366 59 1305031104.1112349033 0.0356972925 0.0487674375 0.0811937377 0.0188048766 0.1438750000 0.0103540000 0.0909240000 0.0002960000 0.0004470000 0.0370960000 9033202 96830484 1768783872 3.9883728027 3.9667317867 4.1516189575 60 1305031104.1432299614 0.0334594510 0.0485123044 0.0811937377 0.0187609821 0.1034820000 0.0091980000 0.0695570000 0.0000260000 0.0002990000 0.0233850000 9035420 96830484 1770442752 3.9907124043 3.9611370564 4.1371150017 61 1305031104.1754240990 0.0298805814 0.0482068663 0.0811937377 0.0187036659 0.1390730000 0.0124190000 0.0734180000 0.0002980000 0.0003590000 0.0515680000 9037574 96830484 1769398272 3.9874095917 3.9578232765 4.1231083870 62 1305031104.2112829685 0.0269712489 0.0478643563 0.0811937377 0.0186043180 0.1044350000 0.0087580000 0.0647470000 0.0000280000 0.0003020000 0.0287380000 9039824 96830484 1770967040 3.9879891872 3.9558835030 4.1095013618 63 1305031104.2431960106 0.0239898413 0.0474853958 0.0811937377 0.0184809640 0.1125060000 0.0113460000 0.0625340000 0.0003300000 0.0005000000 0.0329210000 9042042 96830484 1770033152 3.9891178608 3.9524784088 4.0963692665 64 1305031104.2755460739 0.0196891837 0.0470510799 0.0811937377 0.0183421673 0.1106890000 0.0109860000 0.0687460000 0.0000230000 0.0003610000 0.0273460000 9044196 96830484 1768509440 3.9895951748 3.9513337612 4.0832061768 65 1305031104.3112189770 0.0163906887 0.0465793816 0.0811937377 0.0182440285 0.1154610000 0.0094680000 0.0523560000 0.0002870000 0.0003570000 0.0519000000 9051566 96830484 1770143744 3.9910092354 3.9509389400 4.0705323219 66 1305031104.3433420658 0.0120294308 0.0460558975 0.0811937377 0.0181459678 0.0871840000 0.0105080000 0.0413550000 0.0000920000 0.0002810000 0.0301880000 9064280 96830484 1769144320 3.9925003052 3.9502465725 4.0582637787 67 1305031104.3758370876 0.0093790907 0.0455084825 0.0811937377 0.0180725086 0.1248590000 0.0087310000 0.0712620000 0.0002930000 0.0002620000 0.0390470000 9066434 96830484 1767653376 3.9932351112 3.9502403736 4.0463910103 68 1305031104.4115090370 0.0065488121 0.0449355462 0.0811937377 0.0180046183 0.0939080000 0.0085740000 0.0587940000 0.0000300000 0.0003040000 0.0251230000 9068684 96830484 1766899712 3.9934041500 3.9497330189 4.0350351334 69 1305031104.4432880878 0.0045649582 0.0443504652 0.0811937377 0.0179300298 0.1568480000 0.0084390000 0.0831470000 0.0002920000 0.0002640000 0.0635880000 9070870 96830484 1765879808 3.9936606884 3.9486634731 4.0246405602 70 1305031104.4754559994 0.0045528761 0.0437819282 0.0811937377 0.0178543297 0.1543050000 0.0091580000 0.1042680000 0.0000290000 0.0003100000 0.0394500000 9073056 96830484 1764212736 3.9928748608 3.9481408596 4.0151991844 71 1305031104.5113289356 0.0073812711 0.0432692429 0.0811937377 0.0179340269 0.1265300000 0.0089540000 0.0748390000 0.0003760000 0.0002810000 0.0372040000 9075306 96830484 1766109184 3.9901576042 3.9458861351 4.0059700012 72 1305031104.5433681011 0.0059097093 0.0427503605 0.0811937377 0.0179048439 0.0990890000 0.0095370000 0.0519530000 0.0000250000 0.0003530000 0.0322330000 9077524 96830484 1767858176 3.9909803867 3.9422261715 3.9962778091 73 1305031104.5753428936 0.0045450726 0.0422270004 0.0811937377 0.0180115909 0.1255430000 0.0095610000 0.0482210000 0.0002920000 0.0003460000 0.0620660000 9079646 96830484 1769508864 3.9940822124 3.9403133392 3.9862954617 74 1305031104.6113359928 0.0067754150 0.0417479249 0.0811937377 0.0186917464 0.0905290000 0.0110440000 0.0462480000 0.0000280000 0.0003100000 0.0317670000 9081928 96830484 1768275968 3.9984505177 3.9357542992 3.9751894474 75 1305031104.6432430744 0.0103702676 0.0413295561 0.0811937377 0.0186885520 0.0884860000 0.0096550000 0.0397290000 0.0003730000 0.0002810000 0.0372750000 9084114 96830484 1766744064 4.0061888695 3.9320552349 3.9621214867 76 1305031104.6755249500 0.0169763267 0.0410091189 0.0811937377 0.0185699655 0.0933860000 0.0090750000 0.0454880000 0.0000250000 0.0002860000 0.0328540000 9086300 96830484 1765490688 4.0108308792 3.9379608631 3.9479641914 77 1305031104.7112770081 0.0213681199 0.0407540410 0.0811937377 0.0187535366 0.1260510000 0.0095240000 0.0496260000 0.0002920000 0.0003560000 0.0649560000 9088550 96830484 1764999168 4.0135269165 3.9396533966 3.9331469536 78 1305031104.7432799339 0.0287825335 0.0406005601 0.0811937377 0.0186535773 0.0925730000 0.0089290000 0.0553490000 0.0000250000 0.0003590000 0.0267310000 9090736 96830484 1765097472 4.0140438080 3.9449622631 3.9176807404 79 1305031104.7753269672 0.0388257839 0.0405780946 0.0811937377 0.0185572630 0.1227370000 0.0086330000 0.0689790000 0.0000640000 0.0000520000 0.0398860000 9092890 96830484 1765101568 4.0167016983 3.9518997669 3.9037449360 80 1305031104.8114650249 0.0465838350 0.0406531663 0.0811937377 0.0184864607 0.1056590000 0.0095180000 0.0561250000 0.0000220000 0.0003780000 0.0337820000 9095172 96830484 1764843520 4.0193796158 3.9573681355 3.8916471004 81 1305031104.8432579041 0.0574107915 0.0408600506 0.0811937377 0.0183966553 0.1297090000 0.0105590000 0.0532870000 0.0004080000 0.0002810000 0.0639460000 9097358 96830484 1764823040 4.0243601799 3.9650542736 3.8812258244 82 1305031104.8753499985 0.0630765483 0.0411309835 0.0811937377 0.0184191395 0.1075650000 0.0088080000 0.0609200000 0.0000260000 0.0002910000 0.0349890000 9099544 96830484 1766633472 4.0252351761 3.9699285030 3.8749618530 83 1305031104.9115340710 0.0690311790 0.0414671304 0.0811937377 0.0183525578 0.1054470000 0.0094210000 0.0494560000 0.0003610000 0.0002750000 0.0401850000 9101794 96830484 1768370176 4.0268511772 3.9757339954 3.8711688519 84 1305031104.9432621002 0.0730400309 0.0418429983 0.0811937377 0.0182492426 0.0999750000 0.0091240000 0.0504760000 0.0000280000 0.0003290000 0.0344980000 9103980 96830484 1770143744 4.0282020569 3.9794754982 3.8702921867 85 1305031104.9752020836 0.0746874511 0.0422294036 0.0811937377 0.0182262783 0.1297730000 0.0109430000 0.0442900000 0.0003530000 0.0002730000 0.0675940000 9106166 96830484 1769271296 4.0282897949 3.9818048477 3.8721058369 86 1305031105.0112900734 0.0784074217 0.0426500783 0.0811937377 0.0182968158 0.1015530000 0.0098580000 0.0503370000 0.0000260000 0.0003170000 0.0353190000 9108416 96830484 1770930176 4.0290722847 3.9877672195 3.8782732487 87 1305031105.0433731079 0.0812790245 0.0430940891 0.0812790245 0.0182503200 0.1274190000 0.0111110000 0.0694670000 0.0004110000 0.0003130000 0.0405060000 9110602 96830484 1770053632 4.0290818214 3.9937782288 3.8861188889 88 1305031105.0753200054 0.0782015920 0.0434930380 0.0812790245 0.0181815940 0.0892740000 0.0112460000 0.0393360000 0.0000250000 0.0002770000 0.0361320000 9112788 96830484 1768783872 4.0258946419 3.9941718578 3.8962740898 89 1305031105.1112990379 0.0760665014 0.0438590320 0.0812790245 0.0180944843 0.1550990000 0.0090680000 0.0716100000 0.0003210000 0.0003540000 0.0665180000 9115038 96830484 1767747584 4.0239334106 3.9939510822 3.9075014591 90 1305031105.1431059837 0.0710759237 0.0441614419 0.0812790245 0.0180827960 0.1174750000 0.0095780000 0.0677880000 0.0000240000 0.0003600000 0.0334880000 9117224 96830484 1769279488 4.0195508003 3.9925286770 3.9200539589 91 1305031105.1751589775 0.0692781359 0.0444374495 0.0812790245 0.0185315430 0.0921790000 0.0106060000 0.0395730000 0.0002050000 0.0004640000 0.0400060000 9119410 96830484 1768275968 4.0151481628 3.9975731373 3.9364979267 92 1305031105.2112679482 0.0653553456 0.0446648180 0.0812790245 0.0185587548 0.0872520000 0.0092690000 0.0458650000 0.0000290000 0.0002960000 0.0305200000 9121660 96830484 1766617088 4.0103864670 3.9985861778 3.9543049335 93 1305031105.2432699203 0.0548791513 0.0447746495 0.0812790245 0.0185547193 0.1061190000 0.0092450000 0.0369860000 0.0002890000 0.0003040000 0.0579080000 9123846 96830484 1765224448 4.0067472458 3.9912419319 3.9692292213 94 1305031105.2752881050 0.0486195683 0.0448155529 0.0812790245 0.0187140038 0.1193270000 0.0092060000 0.0739110000 0.0000280000 0.0003390000 0.0297910000 9126032 96830484 1766739968 4.0028777122 3.9906735420 3.9858477116 95 1305031105.3112900257 0.0421545580 0.0447875424 0.0812790245 0.0187028593 0.0898770000 0.0092520000 0.0405440000 0.0003510000 0.0003070000 0.0346170000 9128282 96830484 1768513536 3.9951140881 3.9886126518 4.0023112297 96 1305031105.3433020115 0.0337566659 0.0446726375 0.0812790245 0.0186278834 0.0896050000 0.0092310000 0.0433230000 0.0000290000 0.0017670000 0.0282790000 9130468 96830484 1770270720 3.9893507957 3.9845988750 4.0176715851 97 1305031105.3753380775 0.0263208356 0.0444834436 0.0812790245 0.0187631166 0.1327590000 0.0213840000 0.0517790000 0.0002980000 0.0002730000 0.0574780000 9132654 96830484 1769144320 3.9844734669 3.9794332981 4.0319142342 98 1305031105.4112861156 0.0249329228 0.0442839485 0.0812790245 0.0187955012 0.1114970000 0.0089750000 0.0715760000 0.0000260000 0.0002780000 0.0282490000 9134904 96830484 1770840064 3.9821119308 3.9786615372 4.0462923050 99 1305031105.4433159828 0.0220991876 0.0440598600 0.0812790245 0.0187128967 0.0882770000 0.0111990000 0.0411290000 0.0003200000 0.0003450000 0.0330470000 9137090 96830484 1769779200 3.9774694443 3.9829995632 4.0610342026 100 1305031105.4752800465 0.0181025136 0.0438002866 0.0812790245 0.0186458688 0.0878110000 0.0114290000 0.0475780000 0.0000280000 0.0003830000 0.0265100000 9139276 96830484 1768255488 3.9746110439 3.9801471233 4.0751061440 101 1305031105.5113320351 0.0190977603 0.0435557071 0.0812790245 0.0186275634 0.1341150000 0.0109430000 0.0740280000 0.0003810000 0.0002630000 0.0470810000 9141526 96830484 1766854656 3.9733922482 3.9811279774 4.0892329216 102 1305031105.5432820320 0.0173174813 0.0432984696 0.0812790245 0.0185572302 0.0730860000 0.0089450000 0.0296400000 0.0000100000 0.0001090000 0.0276250000 9143712 96830484 1768538112 3.9719181061 3.9825706482 4.1032266617 103 1305031105.5754489899 0.0173526201 0.0430465681 0.0812790245 0.0184719113 0.1066800000 0.0084990000 0.0690360000 0.0002860000 0.0003380000 0.0270730000 9145898 96830484 1770147840 3.9712040424 3.9818038940 4.1167321205 104 1305031105.6113779545 0.0208574124 0.0428332109 0.0812790245 0.0183882405 0.1105860000 0.0115170000 0.0673190000 0.0000270000 0.0002870000 0.0241340000 9148148 96830484 1769271296 3.9703488350 3.9835608006 4.1304101944 105 1305031105.6432731152 0.0232898202 0.0426470833 0.0812790245 0.0183648558 0.0959630000 0.0096870000 0.0403110000 0.0006840000 0.0002880000 0.0435930000 9150334 96830484 1770778624 3.9703550339 3.9824869633 4.1442542076 106 1305031105.6751658916 0.0235811248 0.0424672158 0.0812790245 0.0183287363 0.0790310000 0.0109960000 0.0356960000 0.0000240000 0.0002810000 0.0249610000 9152520 96830484 1769906176 3.9692108631 3.9850571156 4.1583418846 107 1305031105.7113089561 0.0277904887 0.0423300501 0.0812790245 0.0184177616 0.1045610000 0.0106000000 0.0497710000 0.0003590000 0.0002670000 0.0366110000 9154770 96830484 1768292352 3.9712092876 3.9876525402 4.1717715263 108 1305031105.7433118820 0.0305813011 0.0422212654 0.0812790245 0.0183392797 0.0897090000 0.0090350000 0.0485430000 0.0000260000 0.0002870000 0.0287010000 9156956 96830484 1770041344 3.9726493359 3.9884433746 4.1854853630 109 1305031105.7753388882 0.0288878772 0.0420989408 0.0812790245 0.0182627384 0.1015970000 0.0105990000 0.0396540000 0.0002950000 0.0003470000 0.0491320000 9159142 96830484 1769033728 3.9728980064 3.9942011833 4.1993112564 110 1305031105.8112831116 0.0342766345 0.0420278289 0.0812790245 0.0181985723 0.0943810000 0.0086000000 0.0548370000 0.0000260000 0.0002800000 0.0270230000 9161392 96830484 1770713088 3.9727368355 3.9959852695 4.2128481865 111 1305031105.8432710171 0.0352599472 0.0419668570 0.0812790245 0.0181190012 0.1029840000 0.0106850000 0.0486860000 0.0003750000 0.0002800000 0.0348920000 9163578 96830484 1769320448 3.9726634026 3.9990584850 4.2265634537 112 1305031105.8753368855 0.0358782671 0.0419124946 0.0812790245 0.0180588084 0.1094890000 0.0086780000 0.0802840000 0.0000060000 0.0000670000 0.0189240000 9165764 96830484 1768792064 3.9747011662 4.0031290054 4.2401118279 113 1305031105.9112620354 0.0377229564 0.0418754190 0.0812790245 0.0180835067 0.1408130000 0.0108130000 0.0833360000 0.0000610000 0.0000540000 0.0450560000 9168014 96830484 1767895040 3.9756157398 4.0091114044 4.2542719841 114 1305031105.9432721138 0.0392302871 0.0418522161 0.0812790245 0.0180194668 0.0924010000 0.0102410000 0.0559500000 0.0000270000 0.0003120000 0.0213560000 9170200 96830484 1766875136 3.9771673679 4.0124669075 4.2675681114 115 1305031105.9753289223 0.0400737114 0.0418367508 0.0812790245 0.0180010872 0.1170670000 0.0090360000 0.0727810000 0.0003680000 0.0002710000 0.0269530000 9172386 96830484 1765879808 3.9757502079 4.0170855522 4.2805509567 116 1305031106.0112850666 0.0446847454 0.0418613025 0.0812790245 0.0179480292 0.0849860000 0.0093730000 0.0465250000 0.0000230000 0.0002800000 0.0216560000 9174636 96830484 1767481344 3.9755914211 4.0206022263 4.2933111191 117 1305031106.0433549881 0.0464579575 0.0419005902 0.0812790245 0.0178709280 0.0955460000 0.0091640000 0.0474780000 0.0003940000 0.0002790000 0.0366530000 9176854 96830484 1769254912 3.9773087502 4.0242180824 4.3055925369 118 1305031106.0753300190 0.0491667390 0.0419621677 0.0812790245 0.0178110825 0.1032620000 0.0101610000 0.0697970000 0.0000250000 0.0002860000 0.0200530000 9179008 96830484 1768001536 3.9761557579 4.0270938873 4.3177499771 119 1305031106.1113269329 0.0524580739 0.0420503686 0.0812790245 0.0177985192 0.0963560000 0.0096250000 0.0530180000 0.0002910000 0.0002660000 0.0254330000 9181258 96830484 1769889792 3.9733915329 4.0315046310 4.3292522430 120 1305031106.1433548927 0.0534461066 0.0421453331 0.0812790245 0.0177318938 0.1021500000 0.0106450000 0.0637640000 0.0000250000 0.0003660000 0.0199950000 9183476 96830484 1768927232 3.9727199078 4.0356831551 4.3409748077 121 1305031106.1755340099 0.0581270233 0.0422774132 0.0812790245 0.0176643269 0.0899810000 0.0095010000 0.0350980000 0.0001930000 0.0002190000 0.0399930000 9185630 96830484 1770696704 3.9719429016 4.0359096527 4.3518881798 122 1305031106.2112751007 0.0621824563 0.0424405692 0.0812790245 0.0175955506 0.0852950000 0.0107360000 0.0463090000 0.0000290000 0.0002870000 0.0200550000 9187880 96830484 1769656320 3.9704704285 4.0378646851 4.3617510796 123 1305031106.2432670593 0.0667567253 0.0426382616 0.0812790245 0.0175272899 0.1100680000 0.0105120000 0.0776620000 0.0000620000 0.0000520000 0.0201350000 9190098 96830484 1768251392 3.9685585499 4.0376806259 4.3709549904 124 1305031106.2763850689 0.0686906725 0.0428483617 0.0812790245 0.0174627945 0.1029820000 0.0096950000 0.0660220000 0.0000230000 0.0002810000 0.0186950000 9192284 96830484 1769918464 3.9681503773 4.0408797264 4.3785352707 125 1305031106.3112380505 0.0682527423 0.0430515967 0.0812790245 0.0174055511 0.1162660000 0.0108190000 0.0688820000 0.0003050000 0.0003410000 0.0342180000 9194502 96830484 1769140224 3.9683005810 4.0449581146 4.3853955269 126 1305031106.3432579041 0.0698074475 0.0432639447 0.0812790245 0.0174130496 0.1009030000 0.0091600000 0.0693780000 0.0000240000 0.0002800000 0.0189490000 9196720 96830484 1770844160 3.9694337845 4.0468654633 4.3916702271 127 1305031106.3753879070 0.0690072924 0.0434666483 0.0812790245 0.0174378566 0.1082470000 0.0111930000 0.0685460000 0.0002860000 0.0002610000 0.0245480000 9198874 96830484 1770033152 3.9689307213 4.0499219894 4.3965492249 128 1305031106.4113199711 0.0734201297 0.0437006598 0.0812790245 0.0175800245 0.0974330000 0.0115490000 0.0585200000 0.0000970000 0.0002810000 0.0183980000 9201124 96830484 1768128512 3.9698839188 4.0466055870 4.3997044563 129 1305031106.4432780743 0.0795561150 0.0439786091 0.0812790245 0.0177162043 0.0907320000 0.0096320000 0.0403510000 0.0003590000 0.0002750000 0.0361340000 9213550 96830484 1769652224 3.9674170017 4.0398249626 4.4007701874 130 1305031106.4753448963 0.0818890929 0.0442702282 0.0818890929 0.0177740351 0.1069710000 0.0114860000 0.0686300000 0.0000270000 0.0003480000 0.0177340000 9236728 96830484 1767743488 3.9651641846 4.0355868340 4.3989348412 131 1305031106.5111289024 0.0822610110 0.0445602342 0.0822610110 0.0177821339 0.1080530000 0.0097810000 0.0679880000 0.0002900000 0.0006660000 0.0236970000 9238882 96830484 1769381888 3.9656720161 4.0316543579 4.3946051598 132 1305031106.5433020592 0.0827172026 0.0448493021 0.0827172026 0.0177293839 0.0883580000 0.0095300000 0.0529100000 0.0000280000 0.0002990000 0.0190260000 9241100 96830484 1771077632 3.9648368359 4.0269985199 4.3879313469 133 1305031106.5752820969 0.0806899294 0.0451187805 0.0827172026 0.0176842667 0.1298190000 0.0110020000 0.0794590000 0.0004010000 0.0002910000 0.0369270000 9243254 96830484 1770168320 3.9670183659 4.0240988731 4.3790335655 134 1305031106.6111509800 0.0772115812 0.0453582790 0.0827172026 0.0177069942 0.0857790000 0.0109410000 0.0455720000 0.0000290000 0.0003040000 0.0210590000 9245504 96830484 1768128512 3.9659214020 4.0217919350 4.3692722321 135 1305031106.6432070732 0.0750316754 0.0455780820 0.0827172026 0.0176760692 0.0852430000 0.0088920000 0.0403280000 0.0003720000 0.0002820000 0.0259570000 9247722 96830484 1766625280 3.9654214382 4.0185146332 4.3589115143 136 1305031106.6752789021 0.0760517269 0.0458021529 0.0827172026 0.0176349839 0.0869590000 0.0089440000 0.0499790000 0.0000270000 0.0003010000 0.0189070000 9249876 96830484 1765220352 3.9655935764 4.0117316246 4.3473658562 137 1305031106.7115080357 0.0730783641 0.0460012493 0.0827172026 0.0176638243 0.0988310000 0.0093890000 0.0528610000 0.0004950000 0.0002800000 0.0340290000 9252126 96830484 1764065280 3.9652900696 4.0090966225 4.3350353241 138 1305031106.7433409691 0.0729746744 0.0461967089 0.0827172026 0.0176525641 0.0960060000 0.0105250000 0.0601800000 0.0000290000 0.0003070000 0.0190830000 9254344 96830484 1765085184 3.9651536942 4.0032825470 4.3222370148 139 1305031106.7753899097 0.0718718097 0.0463814219 0.0827172026 0.0175940233 0.1101570000 0.0097060000 0.0603160000 0.0003780000 0.0002840000 0.0376630000 9256498 96830484 1764970496 3.9664502144 3.9985854626 4.3087544441 140 1305031106.8112890720 0.0690547228 0.0465433740 0.0827172026 0.0175535023 0.1203730000 0.0133580000 0.0734060000 0.0000270000 0.0003210000 0.0252070000 9258748 96830484 1765093376 3.9699094296 3.9956488609 4.2942008972 141 1305031106.8434159756 0.0659255609 0.0466808363 0.0827172026 0.0175187030 0.1166650000 0.0104790000 0.0736800000 0.0003040000 0.0003620000 0.0300150000 9260934 96830484 1764990976 3.9711115360 3.9927227497 4.2797908783 142 1305031106.8759050369 0.0670725778 0.0468244402 0.0827172026 0.0176499155 0.0972010000 0.0116690000 0.0538250000 0.0000270000 0.0002910000 0.0220800000 9263120 96830484 1764061184 3.9705095291 3.9839797020 4.2641310692 143 1305031106.9112429619 0.0634713694 0.0469408522 0.0827172026 0.0177047426 0.1095310000 0.0105130000 0.0697980000 0.0006940000 0.0002820000 0.0264180000 9265370 96830484 1764081664 3.9659590721 3.9808139801 4.2469439507 144 1305031106.9434390068 0.0559218861 0.0470032205 0.0827172026 0.0176595191 0.0863560000 0.0098720000 0.0476160000 0.0000260000 0.0003170000 0.0224500000 9267556 96830484 1765728256 3.9669747353 3.9809834957 4.2293124199 145 1305031106.9755470753 0.0548778176 0.0470575281 0.0827172026 0.0176711622 0.1235610000 0.0095020000 0.0668220000 0.0003020000 0.0002720000 0.0447770000 9269742 96830484 1767616512 3.9663064480 3.9740445614 4.2116575241 146 1305031107.0115759373 0.0524479523 0.0470944488 0.0827172026 0.0176305332 0.0820860000 0.0088970000 0.0412050000 0.0000240000 0.0002960000 0.0225450000 9272024 96830484 1769381888 3.9651830196 3.9688789845 4.1933970451 147 1305031107.0432810783 0.0421863124 0.0470610601 0.0827172026 0.0176566260 0.1008560000 0.0104650000 0.0519600000 0.0002910000 0.0004250000 0.0282300000 9274210 96830484 1768529920 3.9649813175 3.9724922180 4.1755347252 148 1305031107.0754320621 0.0413084626 0.0470221912 0.0827172026 0.0176888596 0.1103850000 0.0096260000 0.0685500000 0.0000260000 0.0002840000 0.0231800000 9276364 96830484 1770143744 3.9630703926 3.9659259319 4.1593070030 149 1305031107.1112289429 0.0410611518 0.0469821843 0.0827172026 0.0176348134 0.1036180000 0.0111950000 0.0467450000 0.0003300000 0.0003380000 0.0428400000 9278614 96830484 1769271296 3.9622664452 3.9599425793 4.1429290771 150 1305031107.1432600021 0.0347255431 0.0469004733 0.0827172026 0.0176315430 0.0895540000 0.0093330000 0.0453920000 0.0000270000 0.0002830000 0.0255840000 9280832 96830484 1770823680 3.9627871513 3.9609069824 4.1273317337 151 1305031107.1753990650 0.0297356118 0.0467867987 0.0827172026 0.0175833322 0.1200460000 0.0105490000 0.0735370000 0.0002850000 0.0002630000 0.0331810000 9282986 96830484 1769660416 3.9639415741 3.9599637985 4.1125507355 152 1305031107.2113580704 0.0317038484 0.0466875688 0.0827172026 0.0176673158 0.0954210000 0.0141780000 0.0518130000 0.0000270000 0.0002970000 0.0249880000 9285236 96830484 1767763968 3.9625678062 3.9531295300 4.0978207588 153 1305031107.2433779240 0.0278547630 0.0465644786 0.0827172026 0.0176172235 0.1403990000 0.0096830000 0.0704670000 0.0004990000 0.0002710000 0.0499630000 9287422 96830484 1767890944 3.9638898373 3.9513638020 4.0834932327 154 1305031107.2753980160 0.0235567801 0.0464150779 0.0827172026 0.0175706961 0.1100580000 0.0098430000 0.0704420000 0.0000260000 0.0002840000 0.0261560000 9289608 96830484 1767251968 3.9652690887 3.9513483047 4.0696291924 155 1305031107.3112258911 0.0217702650 0.0462560791 0.0827172026 0.0175706132 0.1051350000 0.0096420000 0.0524840000 0.0002880000 0.0002670000 0.0327460000 9291858 96830484 1766891520 3.9670464993 3.9488041401 4.0556650162 156 1305031107.3435089588 0.0224424023 0.0461034274 0.0827172026 0.0176335132 0.0886800000 0.0107880000 0.0448910000 0.0000240000 0.0003100000 0.0274790000 9294076 96830484 1766731776 3.9658720493 3.9449784756 4.0422010422 157 1305031107.3754129410 0.0173853412 0.0459205096 0.0827172026 0.0176600542 0.1378110000 0.0108900000 0.0722770000 0.0002850000 0.0003390000 0.0520510000 9296230 96830484 1765584896 3.9710178375 3.9457402229 4.0293793678 158 1305031107.4112710953 0.0140196932 0.0457186057 0.0827172026 0.0176331104 0.0919900000 0.0090370000 0.0419570000 0.0000280000 0.0002870000 0.0306370000 9298480 96830484 1767350272 3.9761929512 3.9494309425 4.0195617676 159 1305031107.4434189796 0.0150360176 0.0455256335 0.0827172026 0.0175829825 0.1162070000 0.0094610000 0.0723470000 0.0003710000 0.0002820000 0.0317070000 9300698 96830484 1768919040 3.9796929359 3.9506971836 4.0114798546 160 1305031107.4753770828 0.0169464163 0.0453470134 0.0827172026 0.0175355222 0.0990930000 0.0092570000 0.0506110000 0.0000280000 0.0002930000 0.0290310000 9302884 96830484 1770672128 3.9859147072 3.9541108608 4.0057134628 161 1305031107.5113520622 0.0213123616 0.0451977298 0.0827172026 0.0175064890 0.1360210000 0.0112350000 0.0677550000 0.0003560000 0.0002710000 0.0543910000 9305102 96830484 1769783296 3.9894688129 3.9562778473 4.0014095306 162 1305031107.5436050892 0.0259443931 0.0450788820 0.0827172026 0.0175211743 0.0932620000 0.0110310000 0.0414990000 0.0000250000 0.0003560000 0.0309230000 9307320 96830484 1768529920 3.9929831028 3.9616818428 3.9998147488 163 1305031107.5754539967 0.0260496605 0.0449621384 0.0827172026 0.0175008148 0.1132900000 0.0092950000 0.0698200000 0.0003550000 0.0002680000 0.0314200000 9309474 96830484 1768296448 3.9949908257 3.9604074955 3.9987797737 164 1305031107.6112709045 0.0259535201 0.0448462321 0.0827172026 0.0174575532 0.0852040000 0.0097740000 0.0379470000 0.0000320000 0.0002830000 0.0349850000 9311724 96830484 1767497728 3.9976603985 3.9587264061 3.9980902672 165 1305031107.6433229446 0.0264583472 0.0447347904 0.0827172026 0.0174464998 0.1194970000 0.0095790000 0.0409080000 0.0002860000 0.0010490000 0.0576710000 9313942 96830484 1766637568 4.0024294853 3.9650578499 3.9997620583 166 1305031107.6755681038 0.0257566888 0.0446204645 0.0827172026 0.0174134722 0.1104380000 0.0096580000 0.0690190000 0.0000260000 0.0002780000 0.0287700000 9316096 96830484 1765847040 4.0016059875 3.9649908543 4.0012574196 167 1305031107.7113070488 0.0243686996 0.0444991965 0.0827172026 0.0173692634 0.0879790000 0.0092860000 0.0406940000 0.0003580000 0.0002750000 0.0352330000 9318346 96830484 1765232640 4.0018768311 3.9658167362 4.0030217171 168 1305031107.7435379028 0.0247703288 0.0443817627 0.0827172026 0.0173502277 0.0869080000 0.0088190000 0.0399600000 0.0000250000 0.0003600000 0.0323180000 9320532 96830484 1764855808 4.0003218651 3.9693136215 4.0055704117 169 1305031107.7758018970 0.0246973652 0.0442652870 0.0827172026 0.0173069050 0.1015510000 0.0087560000 0.0384810000 0.0003680000 0.0002740000 0.0515050000 9322718 96830484 1764974592 3.9986922741 3.9714429379 4.0082235336 170 1305031107.8115959167 0.0226556323 0.0441381714 0.0827172026 0.0172577633 0.0926270000 0.0086370000 0.0471420000 0.0000250000 0.0002960000 0.0292440000 9324968 96830484 1765101568 3.9976427555 3.9703066349 4.0107946396 171 1305031107.8433320522 0.0211777817 0.0440039001 0.0827172026 0.0172162894 0.1377910000 0.0088380000 0.0832230000 0.0000610000 0.0000530000 0.0352740000 9327154 96830484 1765101568 3.9987959862 3.9714431763 4.0133333206 172 1305031107.8753581047 0.0209378432 0.0438697951 0.0827172026 0.0171916096 0.1080090000 0.0085880000 0.0554010000 0.0000260000 0.0008090000 0.0328810000 9329340 96830484 1766842368 3.9980576038 3.9705920219 4.0153651237 173 1305031107.9115409851 0.0204664804 0.0437345158 0.0827172026 0.0171740637 0.1193000000 0.0085830000 0.0452370000 0.0019500000 0.0003520000 0.0610290000 9331590 96830484 1768493056 4.0000519753 3.9689412117 4.0168433189 174 1305031107.9431219101 0.0223554429 0.0436116476 0.0827172026 0.0171785744 0.0910050000 0.0088780000 0.0417460000 0.0000230000 0.0002820000 0.0292630000 9333776 96830484 1770147840 4.0023245811 3.9692497253 4.0179920197 175 1305031107.9758069515 0.0261119287 0.0435116492 0.0827172026 0.0171649258 0.1184100000 0.0108980000 0.0740510000 0.0003600000 0.0002670000 0.0306740000 9335962 96830484 1769017344 4.0066618919 3.9701023102 4.0189876556 176 1305031108.0113201141 0.0290663652 0.0434295737 0.0827172026 0.0171310378 0.0791420000 0.0096650000 0.0344070000 0.0000240000 0.0006000000 0.0273310000 9338212 96830484 1770840064 4.0114088058 3.9703371525 4.0201101303 177 1305031108.0434179306 0.0323142223 0.0433667751 0.0827172026 0.0170921897 0.1218040000 0.0119900000 0.0414340000 0.0010670000 0.0003520000 0.0562300000 9340398 96830484 1769779200 4.0183105469 3.9735164642 4.0215826035 178 1305031108.0753519535 0.0351434164 0.0433205765 0.0827172026 0.0170575970 0.1033290000 0.0114030000 0.0518090000 0.0000290000 0.0002910000 0.0293510000 9342552 96830484 1768275968 4.0269427299 3.9772152901 4.0230522156 179 1305031108.1113779545 0.0433770604 0.0433208920 0.0827172026 0.0170172761 0.1250580000 0.0098580000 0.0686950000 0.0002850000 0.0003270000 0.0352650000 9344802 96830484 1770045440 4.0321345329 3.9770221710 4.0245094299 180 1305031108.1433339119 0.0476943329 0.0433451889 0.0827172026 0.0169896476 0.1197720000 0.0111510000 0.0683530000 0.0000280000 0.0002860000 0.0292720000 9346988 96830484 1768910848 4.0388112068 3.9781639576 4.0270905495 181 1305031108.1760580540 0.0521919131 0.0433940659 0.0827172026 0.0170203997 0.1087370000 0.0097100000 0.0388990000 0.0000830000 0.0000740000 0.0578110000 9349174 96830484 1770524672 4.0504159927 3.9824686050 4.0300846100 182 1305031108.2114748955 0.0538353957 0.0434514358 0.0827172026 0.0170099263 0.0909420000 0.0106980000 0.0470100000 0.0000280000 0.0002850000 0.0306930000 9351424 96830484 1769525248 4.0601129532 3.9871504307 4.0344033241 183 1305031108.2433469296 0.0540325716 0.0435092562 0.0827172026 0.0170044543 0.1236590000 0.0093370000 0.0671480000 0.0003040000 0.0003640000 0.0353040000 9353610 96830484 1768382464 4.0697293282 3.9832324982 4.0378441811 184 1305031108.2753579617 0.0547649376 0.0435704284 0.0827172026 0.0169602614 0.1193510000 0.0099510000 0.0684650000 0.0000300000 0.0002940000 0.0292970000 9355796 96830484 1770078208 4.0798459053 3.9796724319 4.0405750275 185 1305031108.3113319874 0.0610215627 0.0436647589 0.0827172026 0.0170761632 0.1241470000 0.0114010000 0.0570060000 0.0003010000 0.0002780000 0.0528830000 9358046 96830484 1769013248 4.0874695778 3.9858644009 4.0441222191 186 1305031108.3432779312 0.0619250089 0.0437629322 0.0827172026 0.0170653878 0.1052720000 0.0112270000 0.0535800000 0.0000280000 0.0002960000 0.0289430000 9360264 96830484 1770696704 4.0963716507 3.9884235859 4.0483260155 187 1305031108.3754100800 0.0613588989 0.0438570283 0.0827172026 0.0170358091 0.0904800000 0.0115830000 0.0350150000 0.0000950000 0.0000850000 0.0362240000 9362418 96830484 1769652224 4.1067819595 3.9881591797 4.0522871017 188 1305031108.4113609791 0.0636053532 0.0439620726 0.0827172026 0.0169951682 0.1268100000 0.0092780000 0.0825680000 0.0000060000 0.0000580000 0.0291900000 9364668 96830484 1768542208 4.1183538437 3.9870934486 4.0560340881 189 1305031108.4436099529 0.0610511564 0.0440524910 0.0827172026 0.0170066390 0.1032490000 0.0091660000 0.0392540000 0.0002920000 0.0003500000 0.0518810000 9366886 96830484 1770143744 4.1321420670 3.9853467941 4.0588016510 190 1305031108.4754710197 0.0603045262 0.0441380281 0.0827172026 0.0170070232 0.0925260000 0.0108100000 0.0479090000 0.0000240000 0.0003000000 0.0286550000 9369040 96830484 1769021440 4.1443748474 3.9838459492 4.0613307953 191 1305031108.5113780499 0.0648809671 0.0442466298 0.0827172026 0.0172576247 0.0895520000 0.0095970000 0.0431210000 0.0002890000 0.0002660000 0.0339690000 9371290 96830484 1768382464 4.1558394432 3.9809415340 4.0625357628 192 1305031108.5437369347 0.0651872680 0.0443556957 0.0827172026 0.0173009214 0.1031190000 0.0093240000 0.0475490000 0.0000280000 0.0002780000 0.0295520000 9373508 96830484 1766215680 4.1684303284 3.9789249897 4.0620927811 193 1305031108.5754139423 0.0672675148 0.0444744098 0.0827172026 0.0173371965 0.1364140000 0.0091690000 0.0674280000 0.0006760000 0.0002780000 0.0489320000 9375662 96830484 1765765120 4.1781444550 3.9800875187 4.0626344681 194 1305031108.6114070415 0.0730691776 0.0446218055 0.0827172026 0.0173345397 0.1390030000 0.0162280000 0.0857460000 0.0000300000 0.0002950000 0.0327080000 9377912 96830484 1765257216 4.1860461235 3.9875307083 4.0636868477 195 1305031108.6433029175 0.0746914297 0.0447760087 0.0827172026 0.0173000820 0.1271400000 0.0092960000 0.0765740000 0.0002990000 0.0002720000 0.0327460000 9380130 96830484 1767014400 4.1959934235 3.9881064892 4.0646715164 196 1305031108.6753749847 0.0761756524 0.0449362109 0.0827172026 0.0172990817 0.0888770000 0.0093890000 0.0477110000 0.0000290000 0.0003140000 0.0268450000 9382284 96830484 1768640512 4.2047700882 3.9922254086 4.0665802956 197 1305031108.7114109993 0.0801886097 0.0451151571 0.0827172026 0.0173123605 0.1399950000 0.0094680000 0.0773290000 0.0003870000 0.0002690000 0.0501420000 9384502 96830484 1770524672 4.2138419151 3.9949607849 4.0679450035 198 1305031108.7435019016 0.0827131569 0.0453050460 0.0827172026 0.0172852944 0.0897430000 0.0107560000 0.0369450000 0.0000270000 0.0002890000 0.0291810000 9386720 96830484 1769398272 4.2213993073 3.9931154251 4.0688848495 199 1305031108.7754929066 0.0835303888 0.0454971332 0.0835303888 0.0172447509 0.1293090000 0.0094470000 0.0805650000 0.0003800000 0.0002740000 0.0334050000 9388874 96830484 1767895040 4.2290701866 3.9930701256 4.0694365501 200 1305031108.8112440109 0.0844490156 0.0456918926 0.0844490156 0.0172032758 0.1088720000 0.0097120000 0.0737720000 0.0000160000 0.0000590000 0.0205420000 9391124 96830484 1767137280 4.2368216515 3.9951155186 4.0694694519 201 1305031108.8432641029 0.0834107772 0.0458795487 0.0844490156 0.0185475987 0.1500320000 0.0113600000 0.0708110000 0.0003680000 0.0002800000 0.0559820000 9393342 96830484 1766395904 4.2438158989 3.9941990376 4.0684142113 202 1305031108.8765149117 0.0773150101 0.0460351698 0.0844490156 0.0185771142 0.1113290000 0.0171690000 0.0524670000 0.0000240000 0.0003050000 0.0297620000 9395528 96830484 1768239104 4.2509856224 3.9933383465 4.0665102005 203 1305031108.9113640785 0.0732727274 0.0461693450 0.0844490156 0.0186556201 0.0895610000 0.0088970000 0.0404620000 0.0002920000 0.0002600000 0.0357880000 9397746 96830484 1769766912 4.2562332153 3.9929716587 4.0641040802 204 1305031108.9432430267 0.0730029643 0.0463008823 0.0844490156 0.0187243363 0.0846250000 0.0104260000 0.0339370000 0.0000080000 0.0000800000 0.0282000000 9399964 96830484 1768890368 4.2589616776 3.9890429974 4.0609006882 205 1305031108.9752678871 0.0701466501 0.0464172031 0.0844490156 0.0187039350 0.1018970000 0.0092900000 0.0357690000 0.0001930000 0.0002200000 0.0540360000 9402150 96830484 1767477248 4.2592048645 3.9896485806 4.0581083298 206 1305031109.0112690926 0.0643198043 0.0465041090 0.0844490156 0.0186741709 0.0948490000 0.0095930000 0.0489640000 0.0000280000 0.0018940000 0.0274280000 9404368 96830484 1769193472 4.2577848434 3.9944663048 4.0564389229 207 1305031109.0432770252 0.0610844269 0.0465745453 0.0844490156 0.0186561052 0.1087530000 0.0107410000 0.0589720000 0.0002880000 0.0003410000 0.0353040000 9406586 96830484 1768144896 4.2558908463 3.9924623966 4.0542082787 208 1305031109.0754098892 0.0602934957 0.0466405018 0.0844490156 0.0186521317 0.0864700000 0.0093290000 0.0421410000 0.0000260000 0.0008430000 0.0273560000 9408740 96830484 1769918464 4.2494893074 3.9928936958 4.0531511307 209 1305031109.1112821102 0.0553139336 0.0466820014 0.0844490156 0.0186244583 0.1165390000 0.0116930000 0.0522930000 0.0002920000 0.0003530000 0.0494090000 9410990 96830484 1769054208 4.2422695160 3.9960994720 4.0529656410 210 1305031109.1433339119 0.0530725829 0.0467124328 0.0844490156 0.0186043637 0.0803530000 0.0096580000 0.0400920000 0.0000260000 0.0002920000 0.0278000000 9413208 96830484 1770696704 4.2355909348 3.9922027588 4.0519232750 211 1305031109.1754639149 0.0511658080 0.0467335388 0.0844490156 0.0186110071 0.1006160000 0.0108120000 0.0421580000 0.0003700000 0.0002860000 0.0341280000 9415362 96830484 1769656320 4.2281513214 3.9907858372 4.0510749817 212 1305031109.2113790512 0.0442025214 0.0467216001 0.0844490156 0.0186082527 0.1101460000 0.0110690000 0.0651750000 0.0000950000 0.0003160000 0.0268690000 9417612 96830484 1767895040 4.2201771736 3.9951505661 4.0516576767 213 1305031109.2432899475 0.0397391953 0.0466888188 0.0844490156 0.0185718849 0.0956570000 0.0092020000 0.0393700000 0.0003050000 0.0002740000 0.0439800000 9419830 96830484 1769537536 4.2112212181 3.9992878437 4.0534114838 214 1305031109.2753078938 0.0398385450 0.0466568082 0.0844490156 0.0187107124 0.0980620000 0.0134260000 0.0505680000 0.0000280000 0.0003090000 0.0236600000 9421984 96830484 1768386560 4.2011184692 3.9917733669 4.0537691116 215 1305031109.3113288879 0.0383289680 0.0466180741 0.0844490156 0.0187746792 0.0875070000 0.0100430000 0.0411310000 0.0002970000 0.0003410000 0.0291220000 9424234 96830484 1768534016 4.1893110275 3.9851784706 4.0533061028 216 1305031109.3432478905 0.0338363349 0.0465588993 0.0844490156 0.0188071156 0.0869260000 0.0097450000 0.0486500000 0.0000280000 0.0003840000 0.0236530000 9426452 96830484 1767788544 4.1777687073 3.9898068905 4.0540089607 217 1305031109.3753969669 0.0313684568 0.0464888973 0.0844490156 0.0187690295 0.0948740000 0.0095620000 0.0362610000 0.0003140000 0.0002800000 0.0449280000 9428606 96830484 1765224448 4.1656584740 3.9903407097 4.0551028252 218 1305031109.4113290310 0.0274855327 0.0464017259 0.0844490156 0.0187290350 0.0979550000 0.0090790000 0.0677820000 0.0000070000 0.0000600000 0.0184350000 9430856 96830484 1765117952 4.1551704407 3.9867489338 4.0553236008 219 1305031109.4433019161 0.0231742878 0.0462956645 0.0844490156 0.0187074522 0.0906770000 0.0103330000 0.0486120000 0.0003050000 0.0005070000 0.0282150000 9433042 96830484 1764970496 4.1443614960 3.9893722534 4.0557813644 220 1305031109.4753630161 0.0223584957 0.0461868592 0.0844490156 0.0186923522 0.0856620000 0.0090580000 0.0427870000 0.0000270000 0.0003010000 0.0244700000 9435196 96830484 1764974592 4.1311903000 3.9886262417 4.0558986664 221 1305031109.5112729073 0.0212029275 0.0460738098 0.0844490156 0.0186752423 0.1152280000 0.0086560000 0.0456260000 0.0006370000 0.0002960000 0.0572830000 9437446 96830484 1765117952 4.1180648804 3.9850854874 4.0549297333 222 1305031109.5432939529 0.0227358323 0.0459686837 0.0844490156 0.0186524709 0.0852350000 0.0093900000 0.0507640000 0.0000300000 0.0003850000 0.0219550000 9439664 96830484 1764970496 4.1044116020 3.9826178551 4.0532183647 223 1305031109.5753619671 0.0196201950 0.0458505291 0.0844490156 0.0186122887 0.1221850000 0.0096170000 0.0720520000 0.0003810000 0.0002790000 0.0316910000 9441850 96830484 1765130240 4.0937085152 3.9846663475 4.0513081551 224 1305031109.6113100052 0.0159079656 0.0457168569 0.0844490156 0.0185947409 0.0841740000 0.0090240000 0.0394910000 0.0000290000 0.0003890000 0.0252180000 9444068 96830484 1764970496 4.0802855492 3.9865970612 4.0496597290 225 1305031109.6432290077 0.0156311132 0.0455831425 0.0844490156 0.0185541326 0.1228060000 0.0104950000 0.0464770000 0.0003940000 0.0002820000 0.0510230000 9446286 96830484 1764954112 4.0679421425 3.9873344898 4.0485053062 226 1305031109.6752629280 0.0130746430 0.0454392996 0.0844490156 0.0185155244 0.1072870000 0.0093140000 0.0557220000 0.0000270000 0.0003120000 0.0290670000 9448440 96830484 1765101568 4.0582799911 3.9893171787 4.0477466583 227 1305031109.7113120556 0.0110458350 0.0452877865 0.0844490156 0.0185434403 0.1244690000 0.0089640000 0.0903050000 0.0000580000 0.0000520000 0.0224770000 9450690 96830484 1766723584 4.0456948280 3.9905552864 4.0477495193 228 1305031109.7432739735 0.0093845399 0.0451303162 0.0844490156 0.0185035942 0.0882270000 0.0110270000 0.0430730000 0.0000310000 0.0003210000 0.0237200000 9452908 96830484 1768497152 4.0324416161 3.9932219982 4.0487532616 229 1305031109.7752768993 0.0103132585 0.0449782766 0.0844490156 0.0184807779 0.1111650000 0.0095300000 0.0546900000 0.0003950000 0.0002790000 0.0435210000 9455062 96830484 1770270720 4.0196328163 3.9923398495 4.0500087738 230 1305031109.8113710880 0.0098466827 0.0448255305 0.0844490156 0.0184490266 0.1065730000 0.0109110000 0.0657590000 0.0000270000 0.0002990000 0.0234620000 9457312 96830484 1769271296 4.0069446564 3.9921753407 4.0511608124 231 1305031109.8432960510 0.0087213395 0.0446692353 0.0844490156 0.0184163917 0.0874280000 0.0096350000 0.0412230000 0.0010650000 0.0002920000 0.0290130000 9459530 96830484 1770778624 3.9940428734 3.9941029549 4.0530548096 232 1305031109.8753058910 0.0089074774 0.0445150898 0.0844490156 0.0183845547 0.0874870000 0.0112130000 0.0417310000 0.0000270000 0.0013000000 0.0242310000 9461684 96830484 1769783296 3.9803125858 3.9946904182 4.0558114052 233 1305031109.9112648964 0.0116020767 0.0443738323 0.0844490156 0.0183614617 0.1379560000 0.0126050000 0.0766730000 0.0003760000 0.0002740000 0.0452810000 9463934 96830484 1768386560 3.9615488052 3.9932863712 4.0589756966 234 1305031109.9432990551 0.0128739858 0.0442392175 0.0844490156 0.0183506032 0.0980350000 0.0089780000 0.0563090000 0.0000260000 0.0003110000 0.0252960000 9466152 96830484 1769918464 3.9498176575 3.9932188988 4.0623235703 235 1305031109.9752581120 0.0105193527 0.0440957287 0.0844490156 0.0183163711 0.1087750000 0.0125380000 0.0558130000 0.0003100000 0.0003440000 0.0331570000 9468306 96830484 1768894464 3.9374966621 3.9972164631 4.0661320686 236 1305031110.0112559795 0.0143398307 0.0439696444 0.0844490156 0.0182814073 0.0860840000 0.0090860000 0.0403290000 0.0000280000 0.0003830000 0.0259750000 9470556 96830484 1770696704 3.9242558479 3.9951193333 4.0696249008 237 1305031110.0432989597 0.0154586751 0.0438493450 0.0844490156 0.0182443726 0.0994510000 0.0106210000 0.0399720000 0.0003200000 0.0002790000 0.0453660000 9472774 96830484 1769652224 3.9114181995 3.9954738617 4.0732378960 238 1305031110.0753190517 0.0172749273 0.0437376878 0.0844490156 0.0182209273 0.0965290000 0.0092980000 0.0479700000 0.0000280000 0.0003820000 0.0248650000 9474928 96830484 1768673280 3.9007112980 3.9956800938 4.0767164230 239 1305031110.1113250256 0.0186849236 0.0436328645 0.0844490156 0.0182378148 0.1101660000 0.0094290000 0.0696280000 0.0006880000 0.0002840000 0.0273720000 9477178 96830484 1767899136 3.8858733177 3.9962623119 4.0806956291 240 1305031110.1434319019 0.0225126036 0.0435448634 0.0844490156 0.0182656968 0.1056640000 0.0088950000 0.0749630000 0.0000050000 0.0000610000 0.0189270000 9479396 96830484 1767239680 3.8739278316 3.9931409359 4.0840983391 241 1305031110.1756410599 0.0256059598 0.0434704281 0.0844490156 0.0182280867 0.1355150000 0.0095280000 0.0770350000 0.0003110000 0.0003530000 0.0454160000 9481550 96830484 1766637568 3.8641581535 3.9916155338 4.0874094963 242 1305031110.2116370201 0.0263216551 0.0433995654 0.0844490156 0.0181986633 0.0978820000 0.0085890000 0.0498080000 0.0000300000 0.0011220000 0.0258950000 9483832 96830484 1765879808 3.8545458317 3.9948425293 4.0898666382 243 1305031110.2433230877 0.0306648128 0.0433471590 0.0844490156 0.0181981847 0.0896360000 0.0097600000 0.0427680000 0.0003210000 0.0003480000 0.0314890000 9486018 96830484 1764954112 3.8444921970 3.9908068180 4.0924835205 244 1305031110.2793209553 0.0338020436 0.0433080397 0.0844490156 0.0181742011 0.1034950000 0.0092610000 0.0546190000 0.0000300000 0.0003770000 0.0253960000 9488268 96830484 1765117952 3.8338046074 3.9892866611 4.0943241119 245 1305031110.3114039898 0.0347042195 0.0432729221 0.0844490156 0.0181384934 0.1210110000 0.0097540000 0.0462540000 0.0003180000 0.0002770000 0.0503730000 9490422 96830484 1765117952 3.8247056007 3.9892888069 4.0950722694 246 1305031110.3433549404 0.0343021080 0.0432364553 0.0844490156 0.0181121417 0.0745730000 0.0095880000 0.0413080000 0.0000270000 0.0003800000 0.0203890000 9492608 96830484 1764954112 3.8134419918 3.9909245968 4.0956549644 247 1305031110.3792810440 0.0361635983 0.0432078203 0.0844490156 0.0181003938 0.1219530000 0.0084900000 0.0613760000 0.0003850000 0.0002820000 0.0381240000 9494858 96830484 1765101568 3.8040103912 3.9926257133 4.0961036682 248 1305031110.4114689827 0.0371960141 0.0431835791 0.0844490156 0.0180793832 0.1095120000 0.0090920000 0.0679240000 0.0000270000 0.0003020000 0.0272900000 9497044 96830484 1765064704 3.7931556702 3.9934790134 4.0967655182 249 1305031110.4432599545 0.0369571000 0.0431585732 0.0844490156 0.0180499882 0.1310510000 0.0092090000 0.0687340000 0.0003160000 0.0006720000 0.0491190000 9499230 96830484 1764954112 3.7818555832 3.9982919693 4.0979824066 250 1305031110.4793310165 0.0414361209 0.0431516834 0.0844490156 0.0180766678 0.1037370000 0.0093070000 0.0593120000 0.0000260000 0.0003660000 0.0271230000 9501512 96830484 1766723584 3.7712771893 3.9980027676 4.0995483398 251 1305031110.5114290714 0.0466605127 0.0431656628 0.0844490156 0.0180630373 0.1267520000 0.0094520000 0.0687220000 0.0003680000 0.0002760000 0.0332180000 9503666 96830484 1768493056 3.7637248039 3.9948525429 4.1017322540 252 1305031110.5434079170 0.0486239195 0.0431873225 0.0844490156 0.0180365480 0.1060270000 0.0093660000 0.0537360000 0.0000390000 0.0003790000 0.0279240000 9505884 96830484 1770147840 3.7536687851 3.9961104393 4.1035027504 253 1305031110.5794260502 0.0514740534 0.0432200764 0.0844490156 0.0180290190 0.1488700000 0.0115640000 0.0693270000 0.0002990000 0.0003550000 0.0539070000 9508134 96830484 1769017344 3.7441525459 4.0000872612 4.1053462029 254 1305031110.6113069057 0.0530667007 0.0432588427 0.0844490156 0.0180424180 0.0887940000 0.0098520000 0.0409670000 0.0000260000 0.0009630000 0.0283770000 9510288 96830484 1770823680 3.7330460548 4.0000643730 4.1076645851 255 1305031110.6434180737 0.0582870729 0.0433177769 0.0844490156 0.0180741787 0.1271140000 0.0114120000 0.0694060000 0.0003770000 0.0002650000 0.0344990000 9512506 96830484 1769656320 3.7268834114 3.9938387871 4.1097145081 256 1305031110.6796059608 0.0585824549 0.0433774045 0.0844490156 0.0180901044 0.1041560000 0.0115050000 0.0493400000 0.0000250000 0.0002990000 0.0284950000 9514724 96830484 1767858176 3.7175271511 3.9953083992 4.1099557877 257 1305031110.7114119530 0.0577670895 0.0434333955 0.0844490156 0.0180614974 0.1517500000 0.0099960000 0.0708900000 0.0002960000 0.0003590000 0.0550040000 9537390 96830484 1769508864 3.7098233700 3.9992740154 4.1108393669 258 1305031110.7432489395 0.0608196892 0.0435007843 0.0844490156 0.0180755139 0.1121790000 0.0215130000 0.0466060000 0.0000270000 0.0003690000 0.0285770000 9581560 96830484 1768534016 3.7057702541 3.9951753616 4.1122751236 259 1305031110.7791929245 0.0624135621 0.0435738066 0.0844490156 0.0180416832 0.1281830000 0.0096710000 0.0714080000 0.0003000000 0.0003470000 0.0348650000 9583810 96830484 1767997440 3.7005758286 3.9933569431 4.1130628586 260 1305031110.8113861084 0.0616559722 0.0436433534 0.0844490156 0.0180081886 0.1251910000 0.0095100000 0.0716670000 0.0000070000 0.0000600000 0.0284840000 9585996 96830484 1767669760 3.6981539726 3.9955675602 4.1128702164 261 1305031110.8432180882 0.0604915991 0.0437079060 0.0844490156 0.0179857620 0.1142760000 0.0097410000 0.0480820000 0.0003010000 0.0002850000 0.0527490000 9588182 96830484 1767272448 3.6944580078 3.9964327812 4.1129269600 262 1305031110.8793129921 0.0631260052 0.0437820209 0.0844490156 0.0179532706 0.1218610000 0.0101820000 0.0718550000 0.0000270000 0.0003510000 0.0293910000 9590432 96830484 1765744640 3.6929271221 3.9921572208 4.1147823334 263 1305031110.9113330841 0.0631991848 0.0438558504 0.0844490156 0.0179296572 0.1271870000 0.0097800000 0.0767590000 0.0003130000 0.0002730000 0.0351050000 9592618 96830484 1765253120 3.6951286793 3.9934635162 4.1150188446 264 1305031110.9438619614 0.0634544119 0.0439300874 0.0844490156 0.0179178399 0.1255180000 0.0098080000 0.0741920000 0.0000290000 0.0005370000 0.0283860000 9594836 96830484 1764950016 3.6957602501 3.9924302101 4.1160216331 265 1305031110.9793450832 0.0619878508 0.0439982299 0.0844490156 0.0179423268 0.1167900000 0.0098570000 0.0474640000 0.0002880000 0.0003430000 0.0556290000 9597022 96830484 1765003264 3.7000093460 3.9939880371 4.1160130501 266 1305031111.0114309788 0.0601439439 0.0440589281 0.0844490156 0.0179314502 0.0967370000 0.0095430000 0.0509360000 0.0000270000 0.0002850000 0.0288120000 9599240 96830484 1765130240 3.7066774368 3.9974310398 4.1158246994 267 1305031111.0433270931 0.0616664849 0.0441248740 0.0844490156 0.0178983936 0.1269910000 0.0097860000 0.0731810000 0.0000600000 0.0000520000 0.0339080000 9601426 96830484 1764982784 3.7123558521 3.9946832657 4.1169786453 268 1305031111.0792829990 0.0574848615 0.0441747247 0.0844490156 0.0178960764 0.1235130000 0.0095710000 0.0715280000 0.0000260000 0.0002920000 0.0264370000 9603644 96830484 1765109760 3.7165875435 3.9974181652 4.1160607338 269 1305031111.1115078926 0.0564948209 0.0442205243 0.0844490156 0.0178780735 0.1161290000 0.0098960000 0.0544150000 0.0004830000 0.0002900000 0.0478880000 9605862 96830484 1766895616 3.7246897221 3.9972341061 4.1152687073 270 1305031111.1432569027 0.0576976612 0.0442704396 0.0844490156 0.0178619392 0.1204230000 0.0087910000 0.0717160000 0.0000880000 0.0002930000 0.0259690000 9608048 96830484 1768628224 3.7343213558 3.9947199821 4.1152148247 271 1305031111.1793260574 0.0547304787 0.0443090376 0.0844490156 0.0179071106 0.1064590000 0.0094890000 0.0488430000 0.0002910000 0.0002660000 0.0317670000 9610298 96830484 1770283008 3.7425341606 3.9953453541 4.1140909195 272 1305031111.2114329338 0.0529592112 0.0443408397 0.0844490156 0.0178906515 0.1242840000 0.0113360000 0.0716250000 0.0000250000 0.0003100000 0.0254380000 9612452 96830484 1769414656 3.7551410198 3.9969327450 4.1126470566 273 1305031111.2432360649 0.0493327640 0.0443591251 0.0844490156 0.0179333242 0.1245750000 0.0096670000 0.0491510000 0.0002970000 0.0002730000 0.0495210000 9614638 96830484 1771233280 3.7613916397 3.9983148575 4.1108856201 274 1305031111.2793080807 0.0494234189 0.0443776079 0.0844490156 0.0179916648 0.1111250000 0.0118040000 0.0697820000 0.0000290000 0.0003670000 0.0241310000 9616888 96830484 1769279488 3.7719740868 3.9934668541 4.1099514961 275 1305031111.3115470409 0.0473756380 0.0443885099 0.0844490156 0.0180016390 0.0877750000 0.0097760000 0.0432530000 0.0003820000 0.0006190000 0.0297880000 9619074 96830484 1770704896 3.7849478722 3.9946870804 4.1089663506 276 1305031111.3433969021 0.0404905453 0.0443743868 0.0844490156 0.0181462554 0.1047860000 0.0119160000 0.0546700000 0.0000310000 0.0003760000 0.0237950000 9621260 96830484 1768771584 3.7895817757 4.0015425682 4.1070141792 277 1305031111.3791339397 0.0445863120 0.0443751519 0.0844490156 0.0182884100 0.1443350000 0.0101130000 0.0702690000 0.0003680000 0.0002750000 0.0473890000 9623510 96830484 1770323968 3.8029420376 3.9950275421 4.1090888977 278 1305031111.4112958908 0.0454461016 0.0443790042 0.0844490156 0.0182658761 0.1086650000 0.0119680000 0.0590020000 0.0000350000 0.0003080000 0.0237490000 9625664 96830484 1768517632 3.8150286674 3.9919223785 4.1087799072 279 1305031111.4433860779 0.0405131578 0.0443651481 0.0844490156 0.0182572970 0.1272630000 0.0100530000 0.0704370000 0.0003760000 0.0002810000 0.0302830000 9627882 96830484 1770053632 3.8229057789 3.9967994690 4.1074910164 280 1305031111.4792590141 0.0394502692 0.0443475950 0.0844490156 0.0187115500 0.1070670000 0.0117620000 0.0543270000 0.0000300000 0.0003580000 0.0243500000 9630132 96830484 1768157184 3.8423764706 3.9954161644 4.1068844795 281 1305031111.5112640858 0.0368413106 0.0443208822 0.0844490156 0.0187096695 0.1442460000 0.0100540000 0.0705200000 0.0002870000 0.0003490000 0.0470540000 9632286 96830484 1769897984 3.8570125103 3.9954600334 4.1045875549 282 1305031111.5432500839 0.0359830670 0.0442913155 0.0844490156 0.0186920401 0.1109030000 0.0118820000 0.0703740000 0.0000280000 0.0002860000 0.0237390000 9634504 96830484 1767755776 3.8645112514 3.9940881729 4.1026582718 283 1305031111.5792369843 0.0352769345 0.0442594626 0.0844490156 0.0187144740 0.1251960000 0.0095260000 0.0723130000 0.0003530000 0.0002710000 0.0291440000 9636754 96830484 1769517056 3.8784344196 3.9931416512 4.1007509232 284 1305031111.6112709045 0.0322761163 0.0442172677 0.0844490156 0.0187974874 0.0870960000 0.0114820000 0.0366380000 0.0000270000 0.0003600000 0.0241660000 9638876 96830484 1767538688 3.8891386986 3.9962632656 4.0993838310 285 1305031111.6433949471 0.0375329182 0.0441938138 0.0844490156 0.0188234167 0.1184690000 0.0091050000 0.0631930000 0.0003130000 0.0003560000 0.0421480000 9641094 96830484 1765711872 3.8995008469 3.9902050495 4.0995573997 286 1305031111.6793200970 0.0370683447 0.0441688996 0.0844490156 0.0190245620 0.0968450000 0.0094280000 0.0497970000 0.0000240000 0.0010760000 0.0236670000 9643312 96830484 1767358464 3.9181523323 3.9887294769 4.0982446671 287 1305031111.7117600441 0.0295241475 0.0441178726 0.0844490156 0.0190453151 0.1083870000 0.0094220000 0.0617920000 0.0003060000 0.0002750000 0.0279650000 9645530 96830484 1769164800 3.9327509403 3.9960427284 4.0961813927 288 1305031111.7433860302 0.0315820798 0.0440743455 0.0844490156 0.0191350303 0.1091450000 0.0098920000 0.0715500000 0.0000280000 0.0003050000 0.0223140000 9647716 96830484 1770815488 3.9459118843 3.9930047989 4.0948815346 289 1305031111.7794229984 0.0313148014 0.0440301949 0.0844490156 0.0192239967 0.0998790000 0.0114730000 0.0438020000 0.0006560000 0.0002960000 0.0402750000 9649966 96830484 1768792064 3.9609549046 3.9945516586 4.0932168961 290 1305031111.8114058971 0.0310157500 0.0439853175 0.0844490156 0.0192463486 0.1146370000 0.0092050000 0.0750670000 0.0000290000 0.0003010000 0.0219510000 9652120 96830484 1770295296 3.9711654186 3.9972064495 4.0914483070 291 1305031111.8432989120 0.0350947231 0.0439547656 0.0844490156 0.0192249236 0.1019170000 0.0117520000 0.0448450000 0.0003110000 0.0003520000 0.0281550000 9654306 96830484 1768538112 3.9798882008 3.9963486195 4.0900321007 292 1305031111.8794419765 0.0369944237 0.0439309288 0.0844490156 0.0192264326 0.1108930000 0.0098340000 0.0724230000 0.0000280000 0.0003680000 0.0218580000 9656524 96830484 1770180608 3.9914705753 4.0003967285 4.0898799896 293 1305031111.9113540649 0.0385360457 0.0439125162 0.0844490156 0.0192519004 0.1295050000 0.0115940000 0.0735670000 0.0003890000 0.0002760000 0.0401310000 9658742 96830484 1768263680 4.0034871101 3.9984610081 4.0902047157 294 1305031111.9433000088 0.0404054374 0.0439005874 0.0844490156 0.0192199556 0.1033490000 0.0101550000 0.0558600000 0.0000290000 0.0003730000 0.0223320000 9660928 96830484 1769644032 4.0166296959 3.9948825836 4.0906043053 295 1305031111.9794490337 0.0397111736 0.0438863860 0.0844490156 0.0193661339 0.0896060000 0.0112330000 0.0435980000 0.0003230000 0.0002720000 0.0271130000 9663146 96830484 1769168896 4.0330357552 3.9964785576 4.0908541679 296 1305031112.0114328861 0.0370807163 0.0438633939 0.0844490156 0.0193905002 0.0846360000 0.0099250000 0.0376730000 0.0000260000 0.0003100000 0.0231780000 9665364 96830484 1767747584 4.0461831093 3.9994947910 4.0893421173 297 1305031112.0432701111 0.0420460217 0.0438572748 0.0844490156 0.0193585995 0.1205020000 0.0105060000 0.0689520000 0.0003070000 0.0002720000 0.0368730000 9667550 96830484 1766248448 4.0535087585 3.9982392788 4.0880780220 298 1305031112.0793390274 0.0464146324 0.0438658565 0.0844490156 0.0193997435 0.1123630000 0.0103210000 0.0705520000 0.0000270000 0.0003760000 0.0216570000 9669800 96830484 1767895040 4.0643377304 3.9997014999 4.0865488052 299 1305031112.1114230156 0.0517554469 0.0438922431 0.0844490156 0.0194668018 0.1261640000 0.0094540000 0.0726350000 0.0003780000 0.0002870000 0.0279620000 9671954 96830484 1769771008 4.0703063011 4.0003404617 4.0853509903 300 1305031112.1443419456 0.0551218949 0.0439296753 0.0844490156 0.0194442802 0.1062100000 0.0110990000 0.0547870000 0.0000290000 0.0002890000 0.0223230000 9674140 96830484 1768538112 4.0792832375 4.0007505417 4.0850095749 301 1305031112.1793899536 0.0608122088 0.0439857634 0.0844490156 0.0195245593 0.1158840000 0.0098740000 0.0609580000 0.0002960000 0.0003570000 0.0408140000 9676326 96830484 1770307584 4.0900020599 4.0028071404 4.0845150948 302 1305031112.2112538815 0.0664504245 0.0440601497 0.0844490156 0.0195162744 0.1306040000 0.0108340000 0.0801190000 0.0000070000 0.0000590000 0.0223980000 9678512 96830484 1769271296 4.0984110832 3.9994602203 4.0841507912 303 1305031112.2433691025 0.0709164739 0.0441487845 0.0844490156 0.0195402104 0.0917860000 0.0094680000 0.0487570000 0.0003920000 0.0005430000 0.0276910000 9680730 96830484 1770950656 4.1093454361 3.9928011894 4.0823292732 304 1305031112.2793529034 0.0765592828 0.0442553979 0.0844490156 0.0195276050 0.0867860000 0.0113240000 0.0440680000 0.0000280000 0.0003090000 0.0228840000 9682948 96830484 1769906176 4.1201763153 3.9936940670 4.0811586380 305 1305031112.3113119602 0.0783690661 0.0443672460 0.0844490156 0.0195199426 0.1192180000 0.0099950000 0.0432240000 0.0003910000 0.0002750000 0.0477870000 9685166 96830484 1768902656 4.1307997704 3.9929635525 4.0801372528 306 1305031112.3433229923 0.0781511366 0.0444776509 0.0844490156 0.0194978047 0.1108000000 0.0098900000 0.0700960000 0.0000280000 0.0002960000 0.0245760000 9687352 96830484 1770422272 4.1436429024 3.9921443462 4.0785999298 307 1305031112.3793599606 0.0806252062 0.0445953954 0.0844490156 0.0194731491 0.1069290000 0.0114860000 0.0546570000 0.0003030000 0.0003560000 0.0308310000 9689634 96830484 1769275392 4.1556973457 3.9956898689 4.0777378082 308 1305031112.4114420414 0.0784931183 0.0447054529 0.0844490156 0.0194523865 0.0876100000 0.0097020000 0.0421980000 0.0000280000 0.0010870000 0.0254530000 9691788 96830484 1771077632 4.1688914299 3.9975543022 4.0771493912 309 1305031112.4433910847 0.0767106712 0.0448090297 0.0844490156 0.0194382132 0.1002110000 0.0113400000 0.0363630000 0.0003080000 0.0002800000 0.0483670000 9694006 96830484 1770184704 4.1817479134 3.9973990917 4.0764150620 310 1305031112.4794180393 0.0776981786 0.0449151237 0.0844490156 0.0194193897 0.1157960000 0.0110440000 0.0717980000 0.0000280000 0.0002990000 0.0254620000 9696256 96830484 1768529920 4.1946268082 3.9963071346 4.0753455162 311 1305031112.5115039349 0.0747632012 0.0450110982 0.0844490156 0.0194049945 0.0874460000 0.0096450000 0.0362010000 0.0003050000 0.0002780000 0.0328950000 9698410 96830484 1770270720 4.2069325447 3.9982101917 4.0741634369 312 1305031112.5432119370 0.0733391792 0.0451018934 0.0844490156 0.0193854778 0.1059280000 0.0111330000 0.0510730000 0.0000280000 0.0002950000 0.0288610000 9700596 96830484 1768128512 4.2178177834 3.9972820282 4.0735130310 313 1305031112.5792520046 0.0747143701 0.0451965019 0.0844490156 0.0193564732 0.1216670000 0.0093120000 0.0612680000 0.0003030000 0.0003460000 0.0468230000 9702814 96830484 1769918464 4.2274804115 3.9983196259 4.0732297897 314 1305031112.6112608910 0.0725925714 0.0452837505 0.0844490156 0.0193985855 0.0940070000 0.0116590000 0.0444200000 0.0000270000 0.0003120000 0.0259050000 9705000 96830484 1767874560 4.2380051613 3.9999442101 4.0729732513 315 1305031112.6432459354 0.0717445910 0.0453677532 0.0844490156 0.0194234825 0.1059230000 0.0099170000 0.0428240000 0.0003190000 0.0003470000 0.0329400000 9707218 96830484 1767411712 4.2458214760 4.0034384727 4.0732674599 316 1305031112.6799519062 0.0753435940 0.0454626135 0.0844490156 0.0194166842 0.0928660000 0.0096440000 0.0481260000 0.0000260000 0.0002910000 0.0309680000 9709468 96830484 1766481920 4.2498326302 4.0029883385 4.0737905502 317 1305031112.7112510204 0.0764710754 0.0455604320 0.0844490156 0.0194158225 0.1192370000 0.0095940000 0.0495310000 0.0002910000 0.0003430000 0.0557170000 9711622 96830484 1765740544 4.2528085709 4.0035657883 4.0747475624 318 1305031112.7432448864 0.0763865337 0.0456573694 0.0844490156 0.0194125135 0.0950640000 0.0096030000 0.0608810000 0.0000060000 0.0000620000 0.0209110000 9713840 96830484 1764974592 4.2550158501 4.0078396797 4.0763497353 319 1305031112.7793099880 0.0755646750 0.0457511227 0.0844490156 0.0194147939 0.1218650000 0.0094770000 0.0610700000 0.0003040000 0.0003490000 0.0336380000 9716090 96830484 1764970496 4.2554888725 4.0124731064 4.0786552429 320 1305031112.8113100529 0.0745446756 0.0458411025 0.0844490156 0.0194302730 0.0893600000 0.0096360000 0.0427450000 0.0000260000 0.0003130000 0.0268680000 9718244 96830484 1764982784 4.2560248375 4.0074028969 4.0795731544 321 1305031112.8432860374 0.0722963884 0.0459235178 0.0844490156 0.0194440953 0.1383770000 0.0093440000 0.0753030000 0.0003070000 0.0005270000 0.0491980000 9720430 96830484 1764974592 4.2550911903 4.0085935593 4.0811796188 322 1305031112.8794209957 0.0672354177 0.0459897038 0.0844490156 0.0194511840 0.1170640000 0.0088470000 0.0728490000 0.0000250000 0.0003020000 0.0262590000 9722680 96830484 1766723584 4.2551932335 4.0114812851 4.0825386047 323 1305031112.9114110470 0.0637429208 0.0460446673 0.0844490156 0.0194233846 0.0891690000 0.0094510000 0.0429700000 0.0003220000 0.0002690000 0.0320070000 9724898 96830484 1768497152 4.2543954849 4.0107855797 4.0835118294 324 1305031112.9433209896 0.0609511100 0.0460906749 0.0844490156 0.0193967186 0.0853850000 0.0093220000 0.0353640000 0.0000290000 0.0003730000 0.0264750000 9727084 96830484 1770147840 4.2516169548 4.0092258453 4.0840225220 325 1305031112.9792780876 0.0570000932 0.0461242423 0.0844490156 0.0194169747 0.1213280000 0.0106090000 0.0553760000 0.0005550000 0.0002840000 0.0506950000 9729334 96830484 1769271296 4.2476758957 4.0065927505 4.0840911865 326 1305031113.0113530159 0.0541311912 0.0461488035 0.0844490156 0.0193928138 0.0946550000 0.0110510000 0.0454010000 0.0000280000 0.0003060000 0.0253360000 9731488 96830484 1768022016 4.2431316376 4.0059695244 4.0838561058 327 1305031113.0432310104 0.0516353399 0.0461655819 0.0844490156 0.0193715853 0.0895940000 0.0091050000 0.0443830000 0.0002880000 0.0002650000 0.0316890000 9733706 96830484 1768660992 4.2359151840 4.0062522888 4.0838656425 328 1305031113.0792510509 0.0494192801 0.0461755017 0.0844490156 0.0193832138 0.0837960000 0.0091070000 0.0415980000 0.0000270000 0.0003250000 0.0229220000 9735956 96830484 1767604224 4.2271075249 4.0002999306 4.0826940536 329 1305031113.1113159657 0.0490085557 0.0461841128 0.0844490156 0.0193759524 0.1076340000 0.0096370000 0.0497280000 0.0003550000 0.0002680000 0.0437460000 9738110 96830484 1765097472 4.2190885544 3.9959857464 4.0807361603 330 1305031113.1433060169 0.0457899645 0.0461829184 0.0844490156 0.0193577548 0.0882930000 0.0094390000 0.0497580000 0.0000230000 0.0002880000 0.0248730000 9740328 96830484 1765117952 4.2087187767 3.9993803501 4.0799336433 331 1305031113.1793429852 0.0413099080 0.0461681963 0.0844490156 0.0193717384 0.1070190000 0.0093550000 0.0665130000 0.0002860000 0.0003400000 0.0267370000 9742578 96830484 1764954112 4.1978287697 3.9978981018 4.0792260170 332 1305031113.2112588882 0.0435838029 0.0461604120 0.0844490156 0.0193594218 0.0983440000 0.0092460000 0.0696700000 0.0000270000 0.0002950000 0.0152410000 9744732 96830484 1765101568 4.1868286133 3.9912886620 4.0775113106 333 1305031113.2432270050 0.0399685912 0.0461418180 0.0844490156 0.0193570767 0.0910270000 0.0096950000 0.0379600000 0.0004020000 0.0002790000 0.0387250000 9746950 96830484 1764970496 4.1756577492 3.9932761192 4.0770626068 334 1305031113.2793118954 0.0343526155 0.0461065209 0.0844490156 0.0193735229 0.1110320000 0.0090440000 0.0671190000 0.0000280000 0.0002990000 0.0236920000 9749168 96830484 1764974592 4.1641263962 3.9914381504 4.0770010948 335 1305031113.3114519119 0.0372433439 0.0460800637 0.0844490156 0.0194395475 0.1073750000 0.0107630000 0.0538730000 0.0002930000 0.0000630000 0.0307390000 9751354 96830484 1765101568 4.1523528099 3.9829258919 4.0758609772 336 1305031113.3432519436 0.0342598632 0.0460448845 0.0844490156 0.0194489845 0.1275230000 0.0106660000 0.0816430000 0.0000270000 0.0002860000 0.0232970000 9753540 96830484 1765101568 4.1397066116 3.9833469391 4.0746560097 337 1305031113.3793120384 0.0219508111 0.0459733888 0.0844490156 0.0194798313 0.1104170000 0.0093330000 0.0470970000 0.0002960000 0.0002720000 0.0493890000 9755758 96830484 1765076992 4.1279282570 3.9910070896 4.0762991905 338 1305031113.4116249084 0.0228382796 0.0459049417 0.0844490156 0.0195022268 0.0880110000 0.0089850000 0.0553940000 0.0000280000 0.0003070000 0.0192400000 9757976 96830484 1764818944 4.1127309799 3.9855494499 4.0778584480 339 1305031113.4432659149 0.0220412742 0.0458345474 0.0844490156 0.0194843009 0.1041230000 0.0089950000 0.0503600000 0.0002880000 0.0003400000 0.0366110000 9760162 96830484 1765097472 4.0978183746 3.9834470749 4.0787019730 340 1305031113.4793109894 0.0155048454 0.0457453424 0.0844490156 0.0195072250 0.1133800000 0.0092370000 0.0781090000 0.0000070000 0.0000630000 0.0217300000 9762380 96830484 1764986880 4.0783905983 3.9874064922 4.0809721947 341 1305031113.5115230083 0.0151730096 0.0456556875 0.0844490156 0.0194842588 0.1229180000 0.0136500000 0.0629100000 0.0003600000 0.0002800000 0.0416650000 9764598 96830484 1765097472 4.0603156090 3.9856994152 4.0831651688 342 1305031113.5432419777 0.0164416917 0.0455702664 0.0844490156 0.0194770701 0.0854230000 0.0097740000 0.0422310000 0.0000250000 0.0011160000 0.0233880000 9766784 96830484 1763950592 4.0450820923 3.9817178249 4.0843768120 343 1305031113.5793011189 0.0157439131 0.0454833091 0.0844490156 0.0194521823 0.1049190000 0.0095170000 0.0490130000 0.0018020000 0.0003460000 0.0288100000 9769002 96830484 1764597760 4.0279846191 3.9796702862 4.0851359367 344 1305031113.6112680435 0.0127974013 0.0453882919 0.0844490156 0.0194275995 0.0892180000 0.0099880000 0.0490080000 0.0000280000 0.0002820000 0.0231150000 9771220 96830484 1765580800 4.0123825073 3.9820337296 4.0866374969 345 1305031113.6432220936 0.0126407202 0.0452933714 0.0844490156 0.0194042629 0.1187590000 0.0095240000 0.0427680000 0.0003130000 0.0002730000 0.0364590000 9773406 96830484 1765216256 3.9987640381 3.9817426205 4.0874943733 346 1305031113.6792879105 0.0130960187 0.0452003155 0.0844490156 0.0193838497 0.0755450000 0.0106580000 0.0422390000 0.0000320000 0.0003790000 0.0181820000 9775688 96830484 1764814848 3.9837293625 3.9802846909 4.0879802704 347 1305031113.7119309902 0.0134619689 0.0451088505 0.0844490156 0.0193587074 0.1195540000 0.0088880000 0.0820180000 0.0000610000 0.0000540000 0.0244990000 9777842 96830484 1765113856 3.9697344303 3.9799847603 4.0882248878 348 1305031113.7435901165 0.0133938994 0.0450177156 0.0844490156 0.0193316798 0.0880820000 0.0111430000 0.0437160000 0.0000280000 0.0002870000 0.0285830000 9780060 96830484 1765113856 3.9549777508 3.9801867008 4.0886278152 349 1305031113.7793200016 0.0121832453 0.0449236340 0.0844490156 0.0193204033 0.1284810000 0.0093760000 0.0731740000 0.0003280000 0.0006650000 0.0409320000 9782278 96830484 1765093376 3.9425082207 3.9806964397 4.0890130997 350 1305031113.8112370968 0.0134048807 0.0448335805 0.0844490156 0.0192945734 0.1014990000 0.0105130000 0.0542710000 0.0000270000 0.0003830000 0.0276580000 9784432 96830484 1765072896 3.9276521206 3.9803233147 4.0901746750 351 1305031113.8432950974 0.0101739028 0.0447348349 0.0844490156 0.0192780790 0.1046910000 0.0093820000 0.0467680000 0.0002920000 0.0002640000 0.0293740000 9786650 96830484 1766866944 3.9151740074 3.9840095043 4.0910229683 352 1305031113.8792810440 0.0118704503 0.0446414702 0.0844490156 0.0193169177 0.1118400000 0.0095180000 0.0704100000 0.0000270000 0.0002790000 0.0275620000 9788900 96830484 1768275968 3.9000759125 3.9824504852 4.0923686028 353 1305031113.9112899303 0.0147956545 0.0445569212 0.0844490156 0.0192897606 0.1434730000 0.0094650000 0.0710290000 0.0003100000 0.0005020000 0.0450730000 9791086 96830484 1770029056 3.8875420094 3.9802684784 4.0936489105 354 1305031113.9432909489 0.0117904441 0.0444643605 0.0844490156 0.0192750277 0.0883200000 0.0111260000 0.0363310000 0.0000280000 0.0003140000 0.0266950000 9793272 96830484 1769119744 3.8767292500 3.9844946861 4.0943374634 355 1305031113.9792931080 0.0122416932 0.0443735924 0.0844490156 0.0192506936 0.1085400000 0.0109350000 0.0488320000 0.0003180000 0.0002730000 0.0389510000 9795522 96830484 1767124992 3.8625547886 3.9857172966 4.0950574875 356 1305031114.0112569332 0.0110353976 0.0442799458 0.0844490156 0.0192389535 0.1064900000 0.0090490000 0.0733970000 0.0000250000 0.0002870000 0.0194140000 9797708 96830484 1768783872 3.8477287292 3.9875316620 4.0959315300 357 1305031114.0433011055 0.0119548934 0.0441893994 0.0844490156 0.0192422302 0.0987050000 0.0096980000 0.0399320000 0.0003570000 0.0002750000 0.0441810000 9799894 96830484 1770672128 3.8307490349 3.9889526367 4.0980448723 358 1305031114.0792849064 0.0140027897 0.0441050793 0.0844490156 0.0192368091 0.1157690000 0.0112490000 0.0659930000 0.0000260000 0.0002800000 0.0246130000 9802144 96830484 1768648704 3.8166558743 3.9875998497 4.0999774933 359 1305031114.1112630367 0.0145096937 0.0440226409 0.0844490156 0.0192135175 0.0892880000 0.0096000000 0.0412180000 0.0009860000 0.0002720000 0.0307350000 9804330 96830484 1770291200 3.8029377460 3.9903061390 4.1020159721 360 1305031114.1432840824 0.0165037401 0.0439461995 0.0844490156 0.0191898272 0.0870880000 0.0116650000 0.0410100000 0.0000260000 0.0003510000 0.0248820000 9806548 96830484 1768374272 3.7877516747 3.9938583374 4.1050572395 361 1305031114.1793370247 0.0185472611 0.0438758423 0.0844490156 0.0192020972 0.1455780000 0.0127010000 0.0612640000 0.0002880000 0.0002780000 0.0537280000 9808798 96830484 1766592512 3.7774140835 3.9927034378 4.1072416306 362 1305031114.2113029957 0.0198239442 0.0438094006 0.0844490156 0.0191992898 0.1093840000 0.0095730000 0.0642430000 0.0000290000 0.0003710000 0.0258620000 9810952 96830484 1768357888 3.7649853230 3.9952239990 4.1096773148 363 1305031114.2433369160 0.0228127260 0.0437515585 0.0844490156 0.0192112489 0.0916940000 0.0096450000 0.0519770000 0.0002890000 0.0003450000 0.0252750000 9813138 96830484 1769926656 3.7463834286 4.0012450218 4.1133460999 364 1305031114.2793900967 0.0240178611 0.0436973451 0.0844490156 0.0192576374 0.1039260000 0.0115760000 0.0586860000 0.0000300000 0.0002800000 0.0260270000 9815388 96830484 1769160704 3.7347114086 3.9979872704 4.1168074608 365 1305031114.3114290237 0.0276927166 0.0436534968 0.0844490156 0.0192405191 0.1108370000 0.0095710000 0.0467180000 0.0005200000 0.0006960000 0.0490770000 9817574 96830484 1770962944 3.7224953175 3.9992613792 4.1211328506 366 1305031114.3433310986 0.0306066908 0.0436178498 0.0844490156 0.0192265535 0.1030420000 0.0110720000 0.0538820000 0.0000310000 0.0003820000 0.0266850000 9819792 96830484 1770029056 3.7140319347 4.0012760162 4.1244015694 367 1305031114.3793199062 0.0335297175 0.0435903617 0.0844490156 0.0192087802 0.1093870000 0.0118900000 0.0592440000 0.0002910000 0.0003430000 0.0334000000 9822042 96830484 1768247296 3.7075695992 4.0013360977 4.1268100739 368 1305031114.4113969803 0.0348506048 0.0435666123 0.0844490156 0.0191907306 0.0862470000 0.0095360000 0.0421180000 0.0000260000 0.0009340000 0.0278960000 9824228 96830484 1770037248 3.6948409081 4.0004806519 4.1293816566 369 1305031114.4433450699 0.0372539312 0.0435495048 0.0844490156 0.0191812577 0.1387640000 0.0117140000 0.0706150000 0.0003470000 0.0002630000 0.0514220000 9826414 96830484 1767993344 3.6804401875 3.9996654987 4.1329832077 370 1305031114.4793319702 0.0402024016 0.0435404586 0.0844490156 0.0191868492 0.1136250000 0.0096200000 0.0603900000 0.0000290000 0.0002860000 0.0292970000 9828664 96830484 1769754624 3.6716773510 3.9970636368 4.1365766525 371 1305031114.5112659931 0.0424194559 0.0435374370 0.0844490156 0.0191648035 0.1274980000 0.0116980000 0.0647910000 0.0003460000 0.0002710000 0.0357690000 9830818 96830484 1767649280 3.6636428833 3.9951593876 4.1402254105 372 1305031114.5432360172 0.0458965749 0.0435437788 0.0844490156 0.0191503065 0.1066590000 0.0098860000 0.0482830000 0.0000280000 0.0003510000 0.0295740000 9833036 96830484 1769390080 3.6581730843 3.9956653118 4.1446828842 373 1305031114.5792369843 0.0469496436 0.0435529098 0.0844490156 0.0191311920 0.1314090000 0.0109210000 0.0648550000 0.0002870000 0.0003360000 0.0506540000 9835286 96830484 1768124416 3.6556060314 3.9921238422 4.1461167336 374 1305031114.6113910675 0.0480198599 0.0435648535 0.0844490156 0.0191156019 0.1244160000 0.0088900000 0.0710570000 0.0000270000 0.0002870000 0.0301610000 9837440 96830484 1770057728 3.6490626335 3.9921207428 4.1486201286 375 1305031114.6441500187 0.0486573130 0.0435784334 0.0844490156 0.0190994171 0.1287840000 0.0113790000 0.0703550000 0.0002910000 0.0002670000 0.0357080000 9839658 96830484 1768886272 3.6435825825 3.9936246872 4.1500868797 376 1305031114.6792509556 0.0508374274 0.0435977392 0.0844490156 0.0190925854 0.0881230000 0.0097230000 0.0367930000 0.0000290000 0.0003080000 0.0308710000 9841844 96830484 1770672128 3.6406581402 3.9874579906 4.1520137787 377 1305031114.7113060951 0.0537826307 0.0436247549 0.0844490156 0.0190896186 0.1466060000 0.0108690000 0.0716640000 0.0003500000 0.0002710000 0.0590610000 9843998 96830484 1769644032 3.6397032738 3.9825699329 4.1538133621 378 1305031114.7432758808 0.0553157553 0.0436556834 0.0844490156 0.0190672755 0.1495070000 0.0093450000 0.0987320000 0.0000070000 0.0000590000 0.0331640000 9846216 96830484 1771278336 3.6395273209 3.9814651012 4.1542267799 379 1305031114.7792890072 0.0591746569 0.0436966306 0.0844490156 0.0190491419 0.1307090000 0.0109120000 0.0748370000 0.0003680000 0.0002820000 0.0397400000 9848466 96830484 1770659840 3.6393928528 3.9782669544 4.1568536758 380 1305031114.8113029003 0.0589837469 0.0437368598 0.0844490156 0.0190362034 0.1049930000 0.0112520000 0.0553290000 0.0000290000 0.0003860000 0.0303280000 9850620 96830484 1769156608 3.6384017467 3.9805502892 4.1568746567 381 1305031114.8432080746 0.0590879731 0.0437771515 0.0844490156 0.0190120562 0.1236290000 0.0096600000 0.0537320000 0.0002940000 0.0002730000 0.0550630000 9852838 96830484 1770815488 3.6381051540 3.9810178280 4.1567401886 382 1305031114.8792810440 0.0576951578 0.0438135860 0.0844490156 0.0189872017 0.1290630000 0.0111410000 0.0700260000 0.0000260000 0.0002830000 0.0302160000 9855056 96830484 1769664512 3.6393849850 3.9822249413 4.1555404663 383 1305031114.9128789902 0.0570954569 0.0438482646 0.0844490156 0.0189658980 0.1290720000 0.0114950000 0.0703730000 0.0002960000 0.0002730000 0.0364890000 9857306 96830484 1768284160 3.6433429718 3.9845395088 4.1548666954 384 1305031114.9432640076 0.0573050305 0.0438833082 0.0844490156 0.0189427128 0.1065480000 0.0096600000 0.0547080000 0.0000280000 0.0002930000 0.0295040000 9859428 96830484 1769910272 3.6469111443 3.9872977734 4.1561541557 385 1305031114.9792799950 0.0547887385 0.0439116340 0.0844490156 0.0189225106 0.1424500000 0.0115840000 0.0729380000 0.0002880000 0.0003440000 0.0527950000 9861678 96830484 1768865792 3.6550590992 3.9902355671 4.1547760963 386 1305031115.0113000870 0.0508348346 0.0439295698 0.0844490156 0.0189059727 0.1126540000 0.0090680000 0.0603100000 0.0000260000 0.0003470000 0.0288710000 9863864 96830484 1770688512 3.6595232487 3.9952721596 4.1527347565 387 1305031115.0435299873 0.0494176783 0.0439437509 0.0844490156 0.0189029040 0.1284760000 0.0111950000 0.0716140000 0.0002860000 0.0003360000 0.0337470000 9866082 96830484 1769775104 3.6703805923 3.9965896606 4.1527113914 388 1305031115.0792379379 0.0464785509 0.0439502839 0.0844490156 0.0188806483 0.1037790000 0.0114010000 0.0493560000 0.0000280000 0.0003530000 0.0270360000 9868332 96830484 1768394752 3.6817886829 3.9967157841 4.1520357132 389 1305031115.1112298965 0.0450091586 0.0439530060 0.0844490156 0.0188729429 0.1371270000 0.0098220000 0.0732050000 0.0003460000 0.0002650000 0.0491010000 9870486 96830484 1770160128 3.6931288242 3.9981343746 4.1527037621 390 1305031115.1432940960 0.0412913524 0.0439461812 0.0844490156 0.0188663223 0.0993220000 0.0116770000 0.0520570000 0.0000870000 0.0002920000 0.0264030000 9872704 96830484 1768521728 3.7106685638 3.9999532700 4.1509237289 391 1305031115.1794400215 0.0378935970 0.0439307015 0.0844490156 0.0188705430 0.1272180000 0.0097200000 0.0724640000 0.0002900000 0.0003490000 0.0315660000 9874954 96830484 1770164224 3.7191181183 3.9997591972 4.1517181396 392 1305031115.2113740444 0.0374699906 0.0439142200 0.0844490156 0.0188770440 0.1267250000 0.0111840000 0.0718720000 0.0000270000 0.0003460000 0.0253540000 9877108 96830484 1769283584 3.7322101593 3.9976077080 4.1533207893 393 1305031115.2432971001 0.0382032543 0.0438996883 0.0844490156 0.0188727719 0.1231600000 0.0111820000 0.0614520000 0.0003490000 0.0002700000 0.0454150000 9879326 96830484 1767976960 3.7493920326 3.9933850765 4.1551523209 394 1305031115.2799661160 0.0349633805 0.0438770073 0.0844490156 0.0189002216 0.1274810000 0.0096810000 0.0724920000 0.0000280000 0.0003480000 0.0246680000 9881544 96830484 1769656320 3.7593395710 3.9963414669 4.1575188637 395 1305031115.3117039204 0.0324441828 0.0438480635 0.0844490156 0.0189216024 0.1105470000 0.0108700000 0.0599820000 0.0002890000 0.0003360000 0.0301910000 9883762 96830484 1768538112 3.7755684853 3.9983129501 4.1590781212 396 1305031115.3434259892 0.0319568366 0.0438180351 0.0844490156 0.0189067093 0.1071850000 0.0095290000 0.0656750000 0.0000300000 0.0002860000 0.0241740000 9885948 96830484 1770164224 3.7922878265 3.9960234165 4.1596856117 397 1305031115.3791658878 0.0303563289 0.0437841266 0.0844490156 0.0191710532 0.1031400000 0.0113590000 0.0429550000 0.0003140000 0.0003540000 0.0435960000 9888134 96830484 1769156608 3.7991824150 4.0046119690 4.1620168686 398 1305031115.4112370014 0.0338554457 0.0437591801 0.0844490156 0.0191578620 0.1122300000 0.0096950000 0.0699290000 0.0000260000 0.0002870000 0.0228860000 9890320 96830484 1770831872 3.8105144501 4.0033106804 4.1648926735 399 1305031115.4431591034 0.0346712507 0.0437364034 0.0844490156 0.0191945910 0.1260700000 0.0113580000 0.0712710000 0.0003440000 0.0002700000 0.0287860000 9892506 96830484 1769791488 3.8316953182 4.0002102852 4.1685342789 400 1305031115.4792408943 0.0361810960 0.0437175151 0.0844490156 0.0191765789 0.1100190000 0.0114060000 0.0709090000 0.0000280000 0.0002840000 0.0226140000 9894756 96830484 1768230912 3.8501067162 4.0013751984 4.1709318161 401 1305031115.5112531185 0.0391334444 0.0437060835 0.0844490156 0.0192428780 0.0981680000 0.0093430000 0.0423370000 0.0003500000 0.0013480000 0.0401440000 9896910 96830484 1769926656 3.8665115833 3.9992067814 4.1728696823 402 1305031115.5436201096 0.0383780003 0.0436928296 0.0844490156 0.0192828397 0.1152680000 0.0116620000 0.0728620000 0.0000260000 0.0002850000 0.0218030000 9899128 96830484 1768267776 3.8897604942 3.9974541664 4.1730165482 403 1305031115.5793149471 0.0400318317 0.0436837452 0.0844490156 0.0192597811 0.1264930000 0.0097130000 0.0737360000 0.0002870000 0.0002670000 0.0276190000 9901378 96830484 1769910272 3.9063079357 3.9976017475 4.1716461182 404 1305031115.6114239693 0.0423356220 0.0436804083 0.0844490156 0.0192400354 0.0883770000 0.0110080000 0.0437740000 0.0000300000 0.0003180000 0.0212990000 9903532 96830484 1769156608 3.9198029041 3.9965505600 4.1705193520 405 1305031115.6432540417 0.0419253372 0.0436760747 0.0844490156 0.0192183502 0.1089980000 0.0112370000 0.0500010000 0.0002920000 0.0002680000 0.0422950000 9905718 96830484 1767993344 3.9368455410 3.9959573746 4.1690220833 406 1305031115.6792409420 0.0458988622 0.0436815496 0.0844490156 0.0192018366 0.0847380000 0.0093770000 0.0379970000 0.0000280000 0.0002990000 0.0223020000 9907968 96830484 1769799680 3.9525203705 3.9947786331 4.1674871445 407 1305031115.7113199234 0.0462926999 0.0436879652 0.0844490156 0.0192221339 0.1286520000 0.0104000000 0.0813590000 0.0000590000 0.0000520000 0.0272000000 9910154 96830484 1768648704 3.9674830437 3.9950647354 4.1660313606 408 1305031115.7432498932 0.0420753546 0.0436840127 0.0844490156 0.0192609037 0.0879690000 0.0093610000 0.0501900000 0.0000280000 0.0003590000 0.0205130000 9912372 96830484 1770307584 3.9873068333 3.9971847534 4.1640825272 409 1305031115.7794249058 0.0430179462 0.0436823842 0.0844490156 0.0192669400 0.1085960000 0.0114370000 0.0510580000 0.0002980000 0.0002750000 0.0408890000 9914622 96830484 1769246720 4.0083918571 3.9960868359 4.1615924835 410 1305031115.8112769127 0.0433439650 0.0436815588 0.0844490156 0.0192623670 0.1237090000 0.0093400000 0.0739930000 0.0000260000 0.0003000000 0.0212080000 9916776 96830484 1770958848 4.0207514763 3.9979701042 4.1597785950 411 1305031115.8432240486 0.0403454565 0.0436734417 0.0844490156 0.0192504301 0.1078210000 0.0117310000 0.0501100000 0.0003750000 0.0002880000 0.0268030000 9918994 96830484 1769918464 4.0370702744 4.0014233589 4.1581897736 412 1305031115.8791980743 0.0479081981 0.0436837203 0.0844490156 0.0192405993 0.0901140000 0.0114490000 0.0498550000 0.0000280000 0.0019460000 0.0207030000 9921180 96830484 1768394752 4.0491724014 3.9981822968 4.1574063301 413 1305031115.9111180305 0.0493793562 0.0436975112 0.0844490156 0.0192259817 0.1057420000 0.0100260000 0.0451900000 0.0003870000 0.0002810000 0.0423020000 9923366 96830484 1767395328 4.0620751381 3.9983291626 4.1565599442 414 1305031115.9433109760 0.0466701314 0.0437046914 0.0844490156 0.0192229187 0.0864790000 0.0095010000 0.0449000000 0.0000300000 0.0003070000 0.0208520000 9925520 96830484 1769037824 4.0761671066 4.0029478073 4.1565179825 415 1305031115.9807400703 0.0528398156 0.0437267037 0.0844490156 0.0192140738 0.1062780000 0.0095900000 0.0508270000 0.0003250000 0.0003490000 0.0303420000 9927770 96830484 1770663936 4.0852370262 4.0047488213 4.1574954987 416 1305031116.0113790035 0.0530221872 0.0437490487 0.0844490156 0.0192557703 0.0886680000 0.0114050000 0.0449700000 0.0000280000 0.0003040000 0.0208140000 9929924 96830484 1769644032 4.0966439247 4.0078773499 4.1578822136 417 1305031116.0431640148 0.0555051528 0.0437772408 0.0844490156 0.0192399896 0.1109370000 0.0099590000 0.0574730000 0.0003080000 0.0002820000 0.0382410000 9932142 96830484 1768493056 4.1048278809 4.0111074448 4.1587777138 418 1305031116.0800299644 0.0630924031 0.0438234493 0.0844490156 0.0192419855 0.0827790000 0.0093390000 0.0445140000 0.0000290000 0.0003750000 0.0214860000 9934392 96830484 1770160128 4.1126809120 4.0126323700 4.1609578133 419 1305031116.1112999916 0.0646324530 0.0438731128 0.0844490156 0.0192254442 0.1071050000 0.0106720000 0.0528810000 0.0003100000 0.0003620000 0.0341970000 9936546 96830484 1769263104 4.1221723557 4.0150709152 4.1633329391 420 1305031116.1434469223 0.0675560012 0.0439295006 0.0844490156 0.0192055341 0.1061520000 0.0088850000 0.0621050000 0.0000280000 0.0003140000 0.0232110000 9938732 96830484 1770835968 4.1319036484 4.0143795013 4.1652946472 421 1305031116.1795721054 0.0730549023 0.0439986821 0.0844490156 0.0191859086 0.1198630000 0.0122220000 0.0590420000 0.0003010000 0.0003670000 0.0431430000 9940982 96830484 1769897984 4.1416916847 4.0140051842 4.1670355797 422 1305031116.2113199234 0.0734071210 0.0440683703 0.0844490156 0.0191661021 0.1176870000 0.0105720000 0.0813620000 0.0000300000 0.0003100000 0.0206650000 9943168 96830484 1768267776 4.1512985229 4.0165233612 4.1689810753 423 1305031116.2433199883 0.0747838542 0.0441409838 0.0844490156 0.0191516524 0.1301290000 0.0090830000 0.0844170000 0.0003030000 0.0003500000 0.0310090000 9945354 96830484 1770037248 4.1613430977 4.0159440041 4.1700305939 424 1305031116.2793850899 0.0790866837 0.0442234029 0.0844490156 0.0191648074 0.1234830000 0.0106200000 0.0806510000 0.0000270000 0.0002970000 0.0201900000 9947636 96830484 1768882176 4.1697740555 4.0165348053 4.1695947647 425 1305031116.3113360405 0.0793179721 0.0443059783 0.0844490156 0.0191630520 0.1387020000 0.0096890000 0.0606610000 0.0000620000 0.0000550000 0.0442600000 9949790 96830484 1770516480 4.1780991554 4.0173912048 4.1696600914 426 1305031116.3432919979 0.0794373304 0.0443884463 0.0844490156 0.0191487259 0.1311210000 0.0110930000 0.0832270000 0.0000290000 0.0003200000 0.0231370000 9951976 96830484 1769644032 4.1862187386 4.0162615776 4.1682577133 427 1305031116.3793840408 0.0816616639 0.0444757372 0.0844490156 0.0191382372 0.1055760000 0.0112350000 0.0444950000 0.0003920000 0.0002820000 0.0302180000 9954194 96830484 1768030208 4.1918754578 4.0143356323 4.1652865410 428 1305031116.4113330841 0.0791825876 0.0445568280 0.0844490156 0.0191198544 0.1270890000 0.0097980000 0.0749610000 0.0000280000 0.0002830000 0.0230840000 9956412 96830484 1769799680 4.1972260475 4.0169420242 4.1627297401 429 1305031116.4433689117 0.0751102194 0.0446280480 0.0844490156 0.0191079698 0.1171160000 0.0111080000 0.0575920000 0.0003130000 0.0002620000 0.0429960000 9958630 96830484 1768775680 4.2027716637 4.0187773705 4.1614017487 430 1305031116.4798500538 0.0723449662 0.0446925059 0.0844490156 0.0190895901 0.0983690000 0.0094740000 0.0577340000 0.0000270000 0.0002880000 0.0233190000 9960880 96830484 1770434560 4.2053685188 4.0174093246 4.1593904495 431 1305031116.5112049580 0.0713332370 0.0447543174 0.0844490156 0.0190732991 0.1062750000 0.0113770000 0.0512080000 0.0002900000 0.0005070000 0.0300390000 9963034 96830484 1769390080 4.2026758194 4.0172548294 4.1569066048 432 1305031116.5432620049 0.0697030798 0.0448120691 0.0844490156 0.0190515322 0.0885440000 0.0111280000 0.0449150000 0.0000280000 0.0005880000 0.0240680000 9965220 96830484 1767866368 4.1985988617 4.0167531967 4.1548357010 433 1305031116.5793130398 0.0640625209 0.0448565275 0.0844490156 0.0190625977 0.1396800000 0.0097140000 0.0781510000 0.0002880000 0.0003390000 0.0461800000 9967470 96830484 1766961152 4.1930885315 4.0176987648 4.1535038948 434 1305031116.6112608910 0.0608972758 0.0448934877 0.0844490156 0.0190600894 0.1101580000 0.0093260000 0.0570670000 0.0000290000 0.0003760000 0.0238140000 9969624 96830484 1768529920 4.1866135597 4.0166654587 4.1519250870 435 1305031116.6433548927 0.0596482754 0.0449274068 0.0844490156 0.0190558357 0.1103110000 0.0096030000 0.0627370000 0.0002870000 0.0002650000 0.0291500000 9971810 96830484 1770283008 4.1765427589 4.0153245926 4.1507482529 436 1305031116.6792809963 0.0537038147 0.0449475361 0.0844490156 0.0190460605 0.1254350000 0.0113050000 0.0753970000 0.0000280000 0.0002920000 0.0210090000 9974124 96830484 1769156608 4.1661973000 4.0147624016 4.1501903534 437 1305031116.7116339207 0.0530997105 0.0449661910 0.0844490156 0.0190272386 0.1157000000 0.0097060000 0.0623160000 0.0003450000 0.0002670000 0.0381200000 9976278 96830484 1770958848 4.1534299850 4.0129923820 4.1494050026 438 1305031116.7432909012 0.0527016260 0.0449838518 0.0844490156 0.0190216376 0.0993760000 0.0114570000 0.0522400000 0.0000320000 0.0003140000 0.0202280000 9978464 96830484 1769791488 4.1389222145 4.0121417046 4.1492509842 439 1305031116.7792980671 0.0495910943 0.0449943467 0.0844490156 0.0190197014 0.0897350000 0.0113670000 0.0454130000 0.0003150000 0.0002760000 0.0269170000 9980714 96830484 1768284160 4.1241445541 4.0106649399 4.1488633156 440 1305031116.8113429546 0.0505703054 0.0450070193 0.0844490156 0.0190597435 0.1027560000 0.0110290000 0.0545770000 0.0000260000 0.0002880000 0.0197640000 9982900 96830484 1767104512 4.1094813347 4.0079069138 4.1476130486 441 1305031116.8460888863 0.0484867431 0.0450149098 0.0844490156 0.0191591204 0.0915770000 0.0097380000 0.0374180000 0.0002960000 0.0005740000 0.0385960000 9985118 96830484 1768890368 4.0941781998 4.0057702065 4.1464843750 442 1305031116.8801651001 0.0459591933 0.0450170462 0.0844490156 0.0191378007 0.0889210000 0.0087790000 0.0577290000 0.0000280000 0.0003180000 0.0168000000 9987336 96830484 1770643456 4.0796637535 4.0074720383 4.1458492279 443 1305031116.9120440483 0.0469240658 0.0450213510 0.0844490156 0.0191289529 0.1247300000 0.0110450000 0.0707880000 0.0002980000 0.0003530000 0.0314870000 9989522 96830484 1769537536 4.0650768280 4.0055880547 4.1458344460 444 1305031116.9432959557 0.0436567254 0.0450182775 0.0844490156 0.0191210298 0.1066730000 0.0116520000 0.0603630000 0.0000290000 0.0002920000 0.0245180000 9991708 96830484 1768140800 4.0513987541 4.0078492165 4.1454381943 445 1305031116.9793510437 0.0422343649 0.0450120215 0.0844490156 0.0191258782 0.1291140000 0.0098390000 0.0724880000 0.0002930000 0.0005100000 0.0408170000 9993926 96830484 1769783296 4.0344805717 4.0087695122 4.1455731392 446 1305031117.0113821030 0.0420183986 0.0450053094 0.0844490156 0.0191231634 0.0852860000 0.0105500000 0.0407370000 0.0000280000 0.0002870000 0.0197040000 9996144 96830484 1768669184 4.0185556412 4.0101137161 4.1448645592 447 1305031117.0432610512 0.0413926505 0.0449972274 0.0844490156 0.0191036912 0.0887180000 0.0098010000 0.0431340000 0.0003870000 0.0002790000 0.0260240000 9998330 96830484 1766993920 4.0001268387 4.0135750771 4.1451892853 448 1305031117.0795199871 0.0401911028 0.0449864994 0.0844490156 0.0190992855 0.0858390000 0.0111790000 0.0428610000 0.0000280000 0.0003780000 0.0199340000 10000580 96830484 1765597184 3.9858896732 4.0165905952 4.1457324028 449 1305031117.1112380028 0.0426434763 0.0449812811 0.0844490156 0.0190958476 0.1376130000 0.0094620000 0.0851140000 0.0000590000 0.0000520000 0.0377840000 10002734 96830484 1764605952 3.9745368958 4.0165705681 4.1471428871 450 1305031117.1432180405 0.0443929844 0.0449799738 0.0844490156 0.0190784430 0.1369780000 0.0089190000 0.0943140000 0.0000270000 0.0003010000 0.0236950000 10004952 96830484 1766199296 3.9629034996 4.0178174973 4.1491351128 451 1305031117.1792640686 0.0430218205 0.0449756320 0.0844490156 0.0190600000 0.0891450000 0.0085380000 0.0460850000 0.0002950000 0.0003460000 0.0285920000 10007202 96830484 1767727104 3.9545800686 4.0211825371 4.1501450539 452 1305031117.2113609314 0.0450004600 0.0449756869 0.0844490156 0.0190615976 0.0874470000 0.0086160000 0.0509640000 0.0000840000 0.0002860000 0.0223100000 10009388 96830484 1769504768 3.9458596706 4.0209078789 4.1518936157 453 1305031117.2432770729 0.0435015000 0.0449724326 0.0844490156 0.0190590120 0.1282260000 0.0101930000 0.0732090000 0.0003740000 0.0005200000 0.0387710000 10011574 96830484 1768374272 3.9435615540 4.0233998299 4.1536059380 454 1305031117.2792990208 0.0429868288 0.0449680590 0.0844490156 0.0190441531 0.0837410000 0.0088180000 0.0402210000 0.0000280000 0.0003590000 0.0204840000 10013824 96830484 1770180608 3.9390962124 4.0243582726 4.1552338600 455 1305031117.3111999035 0.0460483544 0.0449704333 0.0844490156 0.0190328702 0.0888210000 0.0111550000 0.0426790000 0.0003880000 0.0002770000 0.0263750000 10015978 96830484 1768755200 3.9349112511 4.0211429596 4.1570348740 456 1305031117.3432428837 0.0498133302 0.0449810537 0.0844490156 0.0190227950 0.1059180000 0.0098970000 0.0695830000 0.0000280000 0.0002820000 0.0205020000 10018196 96830484 1767624704 3.9301390648 4.0166640282 4.1580886841 457 1305031117.3794538975 0.0503853671 0.0449928793 0.0844490156 0.0190128087 0.1272880000 0.0098630000 0.0715340000 0.0008470000 0.0003100000 0.0395300000 10020446 96830484 1769418752 3.9285128117 4.0129547119 4.1580519676 458 1305031117.4112210274 0.0506009124 0.0450051240 0.0844490156 0.0189931453 0.1072610000 0.0108070000 0.0704430000 0.0000270000 0.0007840000 0.0199100000 10022632 96830484 1768103936 3.9270372391 4.0092425346 4.1574006081 459 1305031117.4432740211 0.0495726764 0.0450150751 0.0844490156 0.0189741833 0.1049650000 0.0096840000 0.0554470000 0.0003540000 0.0002690000 0.0259920000 10024818 96830484 1769652224 3.9275743961 4.0055131912 4.1565027237 460 1305031117.4794030190 0.0453883745 0.0450158866 0.0844490156 0.0189587228 0.0886460000 0.0112440000 0.0495590000 0.0000290000 0.0003010000 0.0200340000 10027068 96830484 1768792064 3.9285333157 4.0024814606 4.1554036140 461 1305031117.5113248825 0.0453819670 0.0450166807 0.0844490156 0.0189403942 0.1085730000 0.0111680000 0.0543820000 0.0002870000 0.0003380000 0.0370050000 10029254 96830484 1768120320 3.9280123711 3.9960749149 4.1546511650 462 1305031117.5442850590 0.0429341681 0.0450121731 0.0844490156 0.0189225695 0.1224350000 0.0090990000 0.0727710000 0.0000260000 0.0002860000 0.0206210000 10031408 96830484 1769558016 3.9272909164 3.9919197559 4.1536035538 463 1305031117.5791549683 0.0367431119 0.0449943133 0.0844490156 0.0189037538 0.1070900000 0.0108730000 0.0495330000 0.0002870000 0.0002620000 0.0266810000 10033690 96830484 1768919040 3.9272069931 3.9889523983 4.1532020569 464 1305031117.6111590862 0.0347094238 0.0449721476 0.0844490156 0.0188846329 0.0872970000 0.0094710000 0.0370180000 0.0000300000 0.0002890000 0.0222540000 10035844 96830484 1770688512 3.9263541698 3.9841868877 4.1544828415 465 1305031117.6432840824 0.0346841328 0.0449500229 0.0844490156 0.0188665292 0.1344510000 0.0113430000 0.0726360000 0.0003470000 0.0002710000 0.0445930000 10038062 96830484 1769517056 3.9263906479 3.9770042896 4.1565914154 466 1305031117.6792619228 0.0307867862 0.0449196296 0.0844490156 0.0188520381 0.1050490000 0.0105810000 0.0694980000 0.0000070000 0.0000890000 0.0188870000 10040312 96830484 1768157184 3.9254240990 3.9717361927 4.1592392921 467 1305031117.7112150192 0.0310560912 0.0448899433 0.0844490156 0.0188334510 0.1416360000 0.0114620000 0.0875730000 0.0000580000 0.0000520000 0.0207330000 10042466 96830484 1769881600 3.9264976978 3.9639651775 4.1628837585 468 1305031117.7431840897 0.0320963562 0.0448626065 0.0844490156 0.0188158234 0.1125040000 0.0108610000 0.0715980000 0.0000280000 0.0003510000 0.0213610000 10044652 96830484 1769029632 3.9271106720 3.9549534321 4.1668305397 469 1305031117.7794671059 0.0296696760 0.0448302122 0.0844490156 0.0187959344 0.1450760000 0.0093140000 0.0720560000 0.0002920000 0.0002690000 0.0429530000 10046902 96830484 1770815488 3.9259428978 3.9477956295 4.1704678535 470 1305031117.8113200665 0.0284142569 0.0447952847 0.0844490156 0.0187795436 0.1271450000 0.0116290000 0.0740380000 0.0000320000 0.0003840000 0.0226210000 10049088 96830484 1769644032 3.9278125763 3.9402520657 4.1743779182 471 1305031117.8433070183 0.0303644445 0.0447646459 0.0844490156 0.0187715470 0.1048030000 0.0109810000 0.0480120000 0.0003540000 0.0002630000 0.0278450000 10051210 96830484 1768267776 3.9296941757 3.9294815063 4.1786236763 472 1305031117.8794670105 0.0267885793 0.0447265611 0.0844490156 0.0187549198 0.1101060000 0.0093160000 0.0722790000 0.0000270000 0.0002820000 0.0223950000 10053460 96830484 1770053632 3.9303362370 3.9231245518 4.1819238663 473 1305031117.9114069939 0.0281082243 0.0446914271 0.0844490156 0.0187362105 0.1011510000 0.0109560000 0.0419440000 0.0010540000 0.0002740000 0.0414370000 10055614 96830484 1768771584 3.9288845062 3.9144716263 4.1860628128 474 1305031117.9432721138 0.0297173858 0.0446598363 0.0844490156 0.0187172001 0.1129970000 0.0088910000 0.0698870000 0.0000270000 0.0002830000 0.0226730000 10057800 96830484 1770516480 3.9281346798 3.9054863453 4.1907911301 475 1305031117.9792630672 0.0285743997 0.0446259723 0.0844490156 0.0187100144 0.1057720000 0.0111280000 0.0469170000 0.0003610000 0.0002750000 0.0280310000 10060050 96830484 1769185280 3.9260168076 3.8996460438 4.1953072548 476 1305031118.0112280846 0.0316004530 0.0445986077 0.0844490156 0.0186941272 0.1089730000 0.0091840000 0.0575620000 0.0000260000 0.0002900000 0.0294520000 10062204 96830484 1768656896 3.9235527515 3.8894197941 4.2009973526 477 1305031118.0435490608 0.0338154361 0.0445760015 0.0844490156 0.0186783906 0.1036200000 0.0089890000 0.0411420000 0.0003280000 0.0002640000 0.0473540000 10064422 96830484 1767247872 3.9253752232 3.8782410622 4.2064108849 478 1305031118.0793690681 0.0341919400 0.0445542775 0.0844490156 0.0186623486 0.0922990000 0.0089800000 0.0511400000 0.0000280000 0.0006990000 0.0259910000 10066672 96830484 1766125568 3.9230611324 3.8706626892 4.2115573883 479 1305031118.1112170219 0.0353859998 0.0445351371 0.0844490156 0.0186499006 0.1528440000 0.0088870000 0.0893660000 0.0000700000 0.0000540000 0.0323820000 10068826 96830484 1765109760 3.9242033958 3.8618078232 4.2163181305 480 1305031118.1432559490 0.0376769677 0.0445208492 0.0844490156 0.0186329318 0.1067790000 0.0110410000 0.0511490000 0.0000300000 0.0003050000 0.0234470000 10071044 96830484 1763823616 3.9224460125 3.8523898125 4.2209191322 481 1305031118.1793229580 0.0388025679 0.0445089609 0.0844490156 0.0186155264 0.0969390000 0.0081040000 0.0392990000 0.0003760000 0.0002760000 0.0434160000 10073294 96830484 1765728256 3.9211065769 3.8437025547 4.2253909111 482 1305031118.2112019062 0.0417934880 0.0445033271 0.0844490156 0.0186071416 0.1189990000 0.0083310000 0.0712350000 0.0000280000 0.0003080000 0.0264610000 10075448 96830484 1767350272 3.9210021496 3.8320248127 4.2297182083 483 1305031118.2431728840 0.0440902673 0.0445024719 0.0844490156 0.0185994256 0.1264680000 0.0081950000 0.0651560000 0.0003090000 0.0003510000 0.0312670000 10077634 96830484 1769005056 3.9177632332 3.8231818676 4.2337446213 484 1305031118.2791941166 0.0448973402 0.0445032878 0.0844490156 0.0186014616 0.1111280000 0.0082520000 0.0697550000 0.0000300000 0.0003770000 0.0264880000 10079884 96830484 1770905600 3.9169995785 3.8152580261 4.2371110916 485 1305031118.3112990856 0.0473827645 0.0445092248 0.0844490156 0.0185826910 0.1640130000 0.0099780000 0.0805220000 0.0004920000 0.0002810000 0.0518770000 10082070 96830484 1770033152 3.9154253006 3.8062865734 4.2408671379 486 1305031118.3433239460 0.0467859991 0.0445139096 0.0844490156 0.0185752458 0.1070860000 0.0107180000 0.0507400000 0.0000290000 0.0007060000 0.0248280000 10084256 96830484 1768636416 3.9145140648 3.8038041592 4.2435712814 487 1305031118.3792080879 0.0479472689 0.0445209596 0.0844490156 0.0185567353 0.0890880000 0.0091000000 0.0338120000 0.0002530000 0.0001830000 0.0322100000 10086506 96830484 1770295296 3.9123754501 3.7989342213 4.2473607063 488 1305031118.4112958908 0.0501895249 0.0445325755 0.0844490156 0.0185497364 0.1456330000 0.0102100000 0.0888970000 0.0000060000 0.0000590000 0.0279200000 10088692 96830484 1769291776 3.9089770317 3.7944319248 4.2516460419 489 1305031118.4457030296 0.0483825915 0.0445404487 0.0844490156 0.0185335715 0.1237810000 0.0091040000 0.0546630000 0.0003170000 0.0002790000 0.0535950000 10090910 96830484 1770971136 3.9121792316 3.7938742638 4.2553248405 490 1305031118.4792850018 0.0487951711 0.0445491318 0.0844490156 0.0185147262 0.0939560000 0.0108730000 0.0425710000 0.0000270000 0.0003060000 0.0286580000 10093096 96830484 1769783296 3.9124243259 3.7913298607 4.2582235336 491 1305031118.5112550259 0.0497094318 0.0445596416 0.0844490156 0.0185002020 0.1078810000 0.0087840000 0.0544870000 0.0003150000 0.0002740000 0.0376990000 10095282 96830484 1768415232 3.9123318195 3.7893145084 4.2609391212 492 1305031118.5451989174 0.0472117290 0.0445650320 0.0844490156 0.0184969216 0.1084850000 0.0081820000 0.0676620000 0.0000280000 0.0003010000 0.0265180000 10097500 96830484 1767407616 3.9138815403 3.7940354347 4.2627277374 493 1305031118.5792849064 0.0472099222 0.0445703969 0.0844490156 0.0184791505 0.1199940000 0.0093110000 0.0640560000 0.0003180000 0.0003670000 0.0402070000 10099750 96830484 1766092800 3.9151127338 3.7955553532 4.2639183998 494 1305031118.6161420345 0.0474924669 0.0445763121 0.0844490156 0.0184629508 0.1251460000 0.0099530000 0.0741510000 0.0000290000 0.0003030000 0.0256570000 10102000 96830484 1765355520 3.9159040451 3.7984046936 4.2639551163 495 1305031118.6453309059 0.0451657176 0.0445775028 0.0844490156 0.0184483693 0.1059350000 0.0113140000 0.0435730000 0.0003230000 0.0003410000 0.0312490000 10104154 96830484 1764081664 3.9179468155 3.8037824631 4.2627973557 496 1305031118.6792950630 0.0443695374 0.0445770835 0.0844490156 0.0184352508 0.0912640000 0.0097390000 0.0489620000 0.0000290000 0.0002960000 0.0247040000 10106404 96830484 1765728256 3.9190430641 3.8099162579 4.2614250183 497 1305031118.7114210129 0.0457598045 0.0445794632 0.0844490156 0.0184271358 0.1243140000 0.0096080000 0.0440370000 0.0003200000 0.0003390000 0.0485730000 10108558 96830484 1767354368 3.9182181358 3.8140363693 4.2588877678 498 1305031118.7468008995 0.0496056862 0.0445895560 0.0844490156 0.0184259404 0.1293160000 0.0083160000 0.0804770000 0.0000270000 0.0003060000 0.0256980000 10110808 96830484 1769000960 3.9173591137 3.8175952435 4.2559828758 499 1305031118.7792770863 0.0450306423 0.0445904400 0.0844490156 0.0184562876 0.1105450000 0.0099900000 0.0588460000 0.0003090000 0.0003450000 0.0318820000 10113026 96830484 1770905600 3.9192950726 3.8295543194 4.2532300949 500 1305031118.8112208843 0.0424889922 0.0445862371 0.0844490156 0.0184560296 0.1245920000 0.0103740000 0.0693970000 0.0000300000 0.0002950000 0.0264280000 10115180 96830484 1769779200 3.9220256805 3.8387613297 4.2496590614 501 1305031118.8467741013 0.0477858707 0.0445926236 0.0844490156 0.0184791919 0.1236970000 0.0112480000 0.0559790000 0.0003900000 0.0002880000 0.0500400000 10117430 96830484 1768255488 3.9250807762 3.8413741589 4.2438330650 502 1305031118.8792080879 0.0419879258 0.0445874349 0.0844490156 0.0185327915 0.0933140000 0.0087310000 0.0428840000 0.0000270000 0.0003710000 0.0270290000 10119648 96830484 1770061824 3.9254076481 3.8571412563 4.2375278473 503 1305031118.9111769199 0.0400833152 0.0445784804 0.0844490156 0.0185335309 0.1283720000 0.0109570000 0.0784120000 0.0003130000 0.0003410000 0.0294090000 10121802 96830484 1769398272 3.9244661331 3.8686444759 4.2315788269 504 1305031118.9470090866 0.0432268046 0.0445757985 0.0844490156 0.0185156365 0.1078210000 0.0086300000 0.0661590000 0.0000910000 0.0002970000 0.0229820000 10124052 96830484 1770971136 3.9257361889 3.8763408661 4.2241053581 505 1305031118.9793939590 0.0395271033 0.0445658011 0.0844490156 0.0185101321 0.1056840000 0.0111570000 0.0519990000 0.0000850000 0.0000550000 0.0342870000 10126270 96830484 1769533440 3.9249331951 3.8898000717 4.2171120644 506 1305031119.0113630295 0.0383067802 0.0445534315 0.0844490156 0.0184983838 0.1208550000 0.0150080000 0.0677830000 0.0000300000 0.0003670000 0.0228880000 10128424 96830484 1768255488 3.9229812622 3.9011495113 4.2108945847 507 1305031119.0471799374 0.0419192761 0.0445482359 0.0844490156 0.0184863244 0.0887110000 0.0092270000 0.0405870000 0.0003150000 0.0003450000 0.0275810000 10130674 96830484 1770061824 3.9222743511 3.9093084335 4.2038803101 508 1305031119.0792229176 0.0421912819 0.0445435962 0.0844490156 0.0184720555 0.0876980000 0.0111140000 0.0420220000 0.0000270000 0.0002990000 0.0244370000 10132828 96830484 1768890368 3.9211707115 3.9182100296 4.1971502304 509 1305031119.1113278866 0.0419985950 0.0445385962 0.0844490156 0.0184575167 0.1246200000 0.0115420000 0.0467220000 0.0007220000 0.0002830000 0.0455770000 10135046 96830484 1767510016 3.9197790623 3.9274835587 4.1903223991 510 1305031119.1476290226 0.0425660498 0.0445347285 0.0844490156 0.0184454746 0.0877950000 0.0085690000 0.0335460000 0.0000190000 0.0002120000 0.0265530000 10137296 96830484 1769299968 3.9204201698 3.9380767345 4.1837801933 511 1305031119.1792619228 0.0422549024 0.0445302670 0.0844490156 0.0184396695 0.1267840000 0.0094730000 0.0803180000 0.0003840000 0.0002780000 0.0295400000 10139482 96830484 1770778624 3.9195725918 3.9469871521 4.1773591042 512 1305031119.2113640308 0.0422506556 0.0445258146 0.0844490156 0.0184275381 0.1261970000 0.0124310000 0.0747090000 0.0000280000 0.0003020000 0.0231190000 10141668 96830484 1769525248 3.9202406406 3.9551177025 4.1711955070 513 1305031119.2476599216 0.0421089716 0.0445211034 0.0844490156 0.0184161597 0.0999780000 0.0095020000 0.0417890000 0.0010660000 0.0002980000 0.0410380000 10184878 96830484 1771192320 3.9204325676 3.9666590691 4.1651411057 514 1305031119.2792439461 0.0409608334 0.0445141769 0.0844490156 0.0184014427 0.0943880000 0.0116930000 0.0430100000 0.0000290000 0.0005080000 0.0230320000 10271032 96830484 1770270720 3.9195022583 3.9768133163 4.1599793434 515 1305031119.3112120628 0.0407824814 0.0445069308 0.0844490156 0.0183846799 0.1089490000 0.0095440000 0.0553030000 0.0003080000 0.0002750000 0.0287940000 10273218 96830484 1768505344 3.9200119972 3.9855496883 4.1553950310 516 1305031119.3477499485 0.0446998030 0.0445073046 0.0844490156 0.0183682942 0.0884870000 0.0092400000 0.0439140000 0.0000280000 0.0003150000 0.0226020000 10275468 96830484 1767403520 3.9211392403 3.9927315712 4.1510109901 517 1305031119.3792390823 0.0435716398 0.0445054948 0.0844490156 0.0183587686 0.1133760000 0.0102670000 0.0470170000 0.0003090000 0.0003390000 0.0494680000 10277654 96830484 1766387712 3.9204778671 4.0030665398 4.1470160484 518 1305031119.4114921093 0.0427839421 0.0445021714 0.0844490156 0.0183486210 0.0837220000 0.0093890000 0.0436830000 0.0000290000 0.0003130000 0.0241740000 10279840 96830484 1765228544 3.9211304188 4.0133128166 4.1431403160 519 1305031119.4477260113 0.0465387441 0.0445060954 0.0844490156 0.0183314903 0.1035240000 0.0095440000 0.0552610000 0.0003910000 0.0002780000 0.0291700000 10282122 96830484 1765117952 3.9220747948 4.0223932266 4.1394510269 520 1305031119.4792668819 0.0478547774 0.0445125352 0.0844490156 0.0183158447 0.1073180000 0.0092160000 0.0767330000 0.0000060000 0.0000580000 0.0151710000 10284244 96830484 1764843520 3.9208774567 4.0305714607 4.1352448463 521 1305031119.5112578869 0.0476166233 0.0445184931 0.0844490156 0.0183041173 0.1390730000 0.0094310000 0.0831020000 0.0003070000 0.0003560000 0.0398130000 10286430 96830484 1765105664 3.9188327789 4.0419225693 4.1318988800 522 1305031119.5474140644 0.0518744215 0.0445325849 0.0844490156 0.0182868876 0.1155100000 0.0093020000 0.0731550000 0.0000290000 0.0003090000 0.0215320000 10288712 96830484 1764937728 3.9185235500 4.0511932373 4.1285243034 523 1305031119.5795691013 0.0514883175 0.0445458846 0.0844490156 0.0182820807 0.1139930000 0.0091600000 0.0520760000 0.0003160000 0.0002760000 0.0276380000 10290898 96830484 1766617088 3.9201393127 4.0622587204 4.1256456375 524 1305031119.6150240898 0.0528654605 0.0445617617 0.0844490156 0.0182705207 0.1127170000 0.0114820000 0.0740010000 0.0000300000 0.0005450000 0.0205130000 10293148 96830484 1768370176 3.9185726643 4.0719857216 4.1230955124 525 1305031119.6488890648 0.0585905686 0.0445884832 0.0844490156 0.0182677563 0.0995990000 0.0091840000 0.0421610000 0.0003980000 0.0010910000 0.0406160000 10295366 96830484 1770020864 3.9174273014 4.0808134079 4.1215028763 526 1305031119.6792080402 0.0592287779 0.0446163165 0.0844490156 0.0182587229 0.1114370000 0.0113580000 0.0542540000 0.0000290000 0.0003090000 0.0237230000 10297488 96830484 1769017344 3.9157965183 4.0920209885 4.1201214790 527 1305031119.7152490616 0.0616138540 0.0446485699 0.0844490156 0.0182436082 0.1101290000 0.0098100000 0.0598390000 0.0003070000 0.0003600000 0.0277750000 10299738 96830484 1770717184 3.9131429195 4.1016645432 4.1194243431 528 1305031119.7471930981 0.0698319450 0.0446962656 0.0844490156 0.0182350273 0.1262180000 0.0115840000 0.0711210000 0.0000310000 0.0003090000 0.0230540000 10301956 96830484 1769672704 3.9114258289 4.1059455872 4.1191425323 529 1305031119.7791690826 0.0719562247 0.0447477968 0.0844490156 0.0182187490 0.1126410000 0.0111090000 0.0532900000 0.0003100000 0.0003500000 0.0414660000 10304142 96830484 1768128512 3.9103400707 4.1146826744 4.1183180809 530 1305031119.8145709038 0.0747204423 0.0448043489 0.0844490156 0.0182059696 0.1012400000 0.0093690000 0.0480940000 0.0000310000 0.0008220000 0.0238290000 10306328 96830484 1770016768 3.9109411240 4.1218314171 4.1175289154 531 1305031119.8474450111 0.0785783008 0.0448679533 0.0844490156 0.0181945288 0.1087610000 0.0109930000 0.0540200000 0.0003820000 0.0002780000 0.0289350000 10308578 96830484 1768648704 3.9124667645 4.1308054924 4.1166243553 532 1305031119.8792319298 0.0805755258 0.0449350728 0.0844490156 0.0181832320 0.0888320000 0.0094450000 0.0480950000 0.0000260000 0.0003590000 0.0230590000 10310732 96830484 1770553344 3.9104394913 4.1375231743 4.1150841713 533 1305031119.9114239216 0.0809798017 0.0450026990 0.0844490156 0.0181840068 0.1308170000 0.0113030000 0.0694610000 0.0003060000 0.0005250000 0.0428890000 10312918 96830484 1769144320 3.9089069366 4.1460881233 4.1130924225 534 1305031119.9474620819 0.0827664807 0.0450734177 0.0844490156 0.0181722398 0.1213630000 0.0098760000 0.0706640000 0.0000280000 0.0004480000 0.0245010000 10315200 96830484 1770844160 3.9092714787 4.1551547050 4.1114902496 535 1305031119.9795460701 0.0854006857 0.0451487957 0.0854006857 0.0181588556 0.1271720000 0.0111960000 0.0686490000 0.0003040000 0.0003560000 0.0293780000 10317386 96830484 1769799680 3.9084920883 4.1590247154 4.1104154587 536 1305031120.0152831078 0.0851666853 0.0452234560 0.0854006857 0.0181678971 0.1082740000 0.0111740000 0.0606520000 0.0000290000 0.0003030000 0.0236310000 10319604 96830484 1768402944 3.9064879417 4.1666178703 4.1093316078 537 1305031120.0473101139 0.0883045495 0.0453036815 0.0883045495 0.0181623174 0.1248590000 0.0093410000 0.0481590000 0.0003010000 0.0002850000 0.0461950000 10321822 96830484 1770061824 3.9075000286 4.1704745293 4.1095056534 538 1305031120.0794179440 0.0940743834 0.0453943333 0.0940743834 0.0181685968 0.1282770000 0.0111290000 0.0714620000 0.0000270000 0.0002910000 0.0242980000 10324008 96830484 1769000960 3.9085853100 4.1662425995 4.1104712486 539 1305031120.1152489185 0.0924839079 0.0454816980 0.0940743834 0.0181620409 0.1073770000 0.0095190000 0.0483250000 0.0002950000 0.0003480000 0.0294570000 10326226 96830484 1770717184 3.9075112343 4.1696376801 4.1097178459 540 1305031120.1481750011 0.0907716006 0.0455655682 0.0940743834 0.0181628726 0.1270790000 0.0110640000 0.0707810000 0.0000260000 0.0002870000 0.0242540000 10328444 96830484 1769799680 3.9080946445 4.1701455116 4.1094403267 541 1305031120.1792609692 0.0933140144 0.0456538278 0.0940743834 0.0181541276 0.1328500000 0.0114300000 0.0708380000 0.0003530000 0.0002740000 0.0437520000 10330598 96830484 1768529920 3.9078102112 4.1638936996 4.1107044220 542 1305031120.2152600288 0.0932519585 0.0457416473 0.0940743834 0.0181396130 0.1040620000 0.0092180000 0.0603030000 0.0000240000 0.0003520000 0.0234920000 10332848 96830484 1770188800 3.9083125591 4.1581635475 4.1106939316 543 1305031120.2480180264 0.0854031146 0.0458146886 0.0940743834 0.0181251118 0.1081820000 0.0113310000 0.0591530000 0.0002910000 0.0003500000 0.0287520000 10335066 96830484 1769017344 3.9048402309 4.1581406593 4.1086997986 544 1305031120.2794411182 0.0818010569 0.0458808401 0.0940743834 0.0181095306 0.1242370000 0.0096470000 0.0717650000 0.0000240000 0.0002950000 0.0232970000 10337252 96830484 1770827776 3.9009187222 4.1536078453 4.1080923080 545 1305031120.3152129650 0.0775141940 0.0459388829 0.0940743834 0.0180934006 0.1661600000 0.0110180000 0.0797720000 0.0000620000 0.0000540000 0.0462720000 10339470 96830484 1769889792 3.8965303898 4.1489906311 4.1073226929 546 1305031120.3477969170 0.0704296157 0.0459837377 0.0940743834 0.0180775418 0.1287920000 0.0116090000 0.0744760000 0.0000910000 0.0002860000 0.0242310000 10341688 96830484 1768529920 3.8942229748 4.1434240341 4.1067886353 547 1305031120.3794460297 0.0675806254 0.0460232202 0.0940743834 0.0180620328 0.1461990000 0.0087100000 0.0859570000 0.0000630000 0.0000540000 0.0284620000 10343874 96830484 1770430464 3.8945958614 4.1365380287 4.1091604233 548 1305031120.4154899120 0.0654494837 0.0460586695 0.0940743834 0.0181130267 0.1105210000 0.0115580000 0.0680690000 0.0000290000 0.0002790000 0.0225020000 10346092 96830484 1769152512 3.9038248062 4.1233701706 4.1106743813 549 1305031120.4474329948 0.0584185831 0.0460811830 0.0940743834 0.0181054555 0.1440270000 0.0095850000 0.0708350000 0.0002880000 0.0005220000 0.0438600000 10348310 96830484 1770852352 3.9017109871 4.1180262566 4.1139297485 550 1305031120.4794321060 0.0532333888 0.0460941871 0.0940743834 0.0180902711 0.1246030000 0.0113540000 0.0701000000 0.0000260000 0.0005180000 0.0221850000 10350496 96830484 1769807872 3.9065639973 4.1131038666 4.1171030998 551 1305031120.5148770809 0.0539035685 0.0461083602 0.0940743834 0.0180807319 0.1280550000 0.0113290000 0.0706790000 0.0002850000 0.0003410000 0.0274960000 10352714 96830484 1768300544 3.9087364674 4.1011419296 4.1216011047 552 1305031120.5478069782 0.0477262028 0.0461112910 0.0940743834 0.0180672711 0.1062710000 0.0096410000 0.0542310000 0.0000270000 0.0003760000 0.0211510000 10354932 96830484 1769897984 3.9115743637 4.0940661430 4.1252818108 553 1305031120.5795590878 0.0433917530 0.0461063732 0.0940743834 0.0180567009 0.1131410000 0.0109610000 0.0550590000 0.0003580000 0.0002690000 0.0399240000 10357118 96830484 1768677376 3.9152178764 4.0898156166 4.1294188499 554 1305031120.6152710915 0.0429004245 0.0461005863 0.0940743834 0.0180454802 0.1217870000 0.0096430000 0.0718360000 0.0000250000 0.0002850000 0.0210870000 10359304 96830484 1770561536 3.9182071686 4.0812053680 4.1342797279 555 1305031120.6473538876 0.0380123220 0.0460860129 0.0940743834 0.0180333544 0.1289050000 0.0112690000 0.0722270000 0.0003570000 0.0002670000 0.0281850000 10361522 96830484 1769660416 3.9197402000 4.0737118721 4.1383976936 556 1305031120.6793179512 0.0348369181 0.0460657807 0.0940743834 0.0180410477 0.0883800000 0.0111190000 0.0436500000 0.0000290000 0.0003790000 0.0220000000 10363676 96830484 1768173568 3.9218261242 4.0690093040 4.1425952911 557 1305031120.7145531178 0.0334554203 0.0460431409 0.0940743834 0.0180255066 0.1113550000 0.0111830000 0.0496500000 0.0038550000 0.0002840000 0.0398870000 10365926 96830484 1767014400 3.9227073193 4.0613255501 4.1468949318 558 1305031120.7473959923 0.0296384227 0.0460137418 0.0940743834 0.0180125832 0.1209140000 0.0095020000 0.0722850000 0.0000910000 0.0002850000 0.0222470000 10368144 96830484 1768820736 3.9221961498 4.0533566475 4.1512970924 559 1305031120.7799079418 0.0305206627 0.0459860261 0.0940743834 0.0180014072 0.1260380000 0.0092060000 0.0668210000 0.0002900000 0.0002630000 0.0284780000 10370362 96830484 1770409984 3.9228591919 4.0433607101 4.1556153297 560 1305031120.8149440289 0.0291183423 0.0459559052 0.0940743834 0.0179932751 0.0903430000 0.0112970000 0.0441860000 0.0000290000 0.0003870000 0.0226670000 10372580 96830484 1769263104 3.9233648777 4.0362653732 4.1591577530 561 1305031120.8479421139 0.0240866933 0.0459169227 0.0940743834 0.0179775147 0.1305520000 0.0101550000 0.0713340000 0.0002920000 0.0002670000 0.0420050000 10374798 96830484 1768550400 3.9222629070 4.0304369926 4.1627035141 562 1305031120.8834540844 0.0254053827 0.0458804253 0.0940743834 0.0179702319 0.0827150000 0.0093150000 0.0372150000 0.0000310000 0.0002970000 0.0257680000 10377016 96830484 1768058880 3.9244437218 4.0193009377 4.1658616066 563 1305031120.9154539108 0.0237612128 0.0458411371 0.0940743834 0.0179633562 0.0977520000 0.0087700000 0.0530940000 0.0003610000 0.0006180000 0.0282900000 10379202 96830484 1766649856 3.9235513210 4.0130515099 4.1690020561 564 1305031120.9475090504 0.0210654233 0.0457972086 0.0940743834 0.0179481715 0.1096580000 0.0090400000 0.0772180000 0.0000260000 0.0004890000 0.0163640000 10381388 96830484 1765490688 3.9222311974 4.0051312447 4.1718940735 565 1305031120.9833900928 0.0215640236 0.0457543180 0.0940743834 0.0179357069 0.1225360000 0.0097930000 0.0636590000 0.0000600000 0.0000530000 0.0424050000 10383638 96830484 1765011456 3.9219422340 3.9961872101 4.1748909950 566 1305031121.0150289536 0.0236254372 0.0457152210 0.0940743834 0.0179266431 0.0980240000 0.0092900000 0.0542150000 0.0000290000 0.0003090000 0.0234210000 10385792 96830484 1765113856 3.9204175472 3.9865791798 4.1777300835 567 1305031121.0477550030 0.0191606451 0.0456683875 0.0940743834 0.0179109461 0.0881420000 0.0095280000 0.0415830000 0.0003550000 0.0010630000 0.0281060000 10388042 96830484 1765130240 3.9204726219 3.9808070660 4.1799225807 568 1305031121.0831170082 0.0221816394 0.0456270376 0.0940743834 0.0178997390 0.1235810000 0.0095240000 0.0697690000 0.0000300000 0.0002820000 0.0238400000 10390260 96830484 1765130240 3.9178829193 3.9704744816 4.1825160980 569 1305031121.1148779392 0.0220793169 0.0455856532 0.0940743834 0.0178864472 0.1180580000 0.0094180000 0.0585840000 0.0002940000 0.0002680000 0.0428990000 10392414 96830484 1766723584 3.9193050861 3.9615519047 4.1847610474 570 1305031121.1473550797 0.0199433696 0.0455406668 0.0940743834 0.0178715766 0.0976640000 0.0092600000 0.0494090000 0.0000260000 0.0003570000 0.0242000000 10394632 96830484 1768378368 3.9175469875 3.9547579288 4.1868543625 571 1305031121.1832809448 0.0219377913 0.0454993307 0.0940743834 0.0178559647 0.1084820000 0.0091550000 0.0578730000 0.0002910000 0.0002680000 0.0297540000 10396882 96830484 1770029056 3.9152734280 3.9461722374 4.1892290115 572 1305031121.2114310265 0.0216316953 0.0454576041 0.0940743834 0.0178446862 0.0866570000 0.0114290000 0.0348060000 0.0000260000 0.0002860000 0.0257160000 10398972 96830484 1768898560 3.9158384800 3.9380192757 4.1914625168 573 1305031121.2472009659 0.0214872379 0.0454157710 0.0940743834 0.0178302437 0.1448770000 0.0105350000 0.0799310000 0.0002910000 0.0002660000 0.0472000000 10401222 96830484 1767518208 3.9141242504 3.9318580627 4.1941466331 574 1305031121.2828760147 0.0242979489 0.0453789804 0.0940743834 0.0178150158 0.0927020000 0.0090290000 0.0471050000 0.0000290000 0.0003530000 0.0294250000 10403472 96830484 1769181184 3.9120197296 3.9227247238 4.1975703239 575 1305031121.3135879040 0.0253112745 0.0453440800 0.0940743834 0.0178084830 0.1068270000 0.0091280000 0.0665140000 0.0003190000 0.0003420000 0.0238380000 10405626 96830484 1770913792 3.9131586552 3.9123456478 4.2005562782 576 1305031121.3475399017 0.0273024421 0.0453127577 0.0940743834 0.0177971095 0.1048080000 0.0114470000 0.0468100000 0.0000270000 0.0002810000 0.0283980000 10407844 96830484 1769787392 3.9103527069 3.9053988457 4.2041230202 577 1305031121.3832480907 0.0268682782 0.0452807916 0.0940743834 0.0177928043 0.1407170000 0.0112590000 0.0699030000 0.0002920000 0.0002650000 0.0522270000 10410094 96830484 1768247296 3.9115557671 3.8965251446 4.2076158524 578 1305031121.4143280983 0.0289864615 0.0452526007 0.0940743834 0.0177786593 0.1150790000 0.0087850000 0.0761770000 0.0000270000 0.0003560000 0.0227510000 10412248 96830484 1769959424 3.9100928307 3.8880605698 4.2101979256 579 1305031121.4473190308 0.0318609141 0.0452294717 0.0940743834 0.0177715935 0.1053820000 0.0107450000 0.0427800000 0.0003670000 0.0004930000 0.0314610000 10414466 96830484 1768898560 3.9066584110 3.8834784031 4.2138657570 580 1305031121.4830150604 0.0313157104 0.0452054824 0.0940743834 0.0177743929 0.1087890000 0.0095280000 0.0600330000 0.0000240000 0.0002790000 0.0254540000 10416684 96830484 1770598400 3.9089577198 3.8738250732 4.2167592049 581 1305031121.5141639709 0.0339417830 0.0451860957 0.0940743834 0.0177636776 0.1264310000 0.0110530000 0.0458910000 0.0003110000 0.0006600000 0.0506540000 10418838 96830484 1769680896 3.9068636894 3.8634250164 4.2195901871 582 1305031121.5472700596 0.0344471745 0.0451676439 0.0940743834 0.0177582215 0.1268040000 0.0114240000 0.0659680000 0.0000290000 0.0003620000 0.0269890000 10421088 96830484 1768427520 3.9064373970 3.8562886715 4.2236752510 583 1305031121.5832130909 0.0348105505 0.0451498788 0.0940743834 0.0177459245 0.1070650000 0.0093950000 0.0435220000 0.0003200000 0.0002720000 0.0320030000 10423338 96830484 1770053632 3.9063692093 3.8477451801 4.2265863419 584 1305031121.6147189140 0.0357946269 0.0451338595 0.0940743834 0.0177329827 0.1123580000 0.0116960000 0.0742270000 0.0000060000 0.0000780000 0.0196450000 10425492 96830484 1768390656 3.9063158035 3.8362514973 4.2293725014 585 1305031121.6471829414 0.0354351215 0.0451172805 0.0940743834 0.0177261132 0.1118150000 0.0094030000 0.0453660000 0.0001150000 0.0000990000 0.0499940000 10427678 96830484 1770024960 3.9087235928 3.8294723034 4.2316370010 586 1305031121.6832110882 0.0374454334 0.0451041886 0.0940743834 0.0177163096 0.1002220000 0.0116210000 0.0467910000 0.0000260000 0.0003150000 0.0269440000 10429960 96830484 1768263680 3.9067978859 3.8221509457 4.2348284721 587 1305031121.7145280838 0.0413049273 0.0450977162 0.0940743834 0.0177024926 0.1058750000 0.0094360000 0.0449870000 0.0003130000 0.0003550000 0.0322890000 10432114 96830484 1769922560 3.9036672115 3.8117573261 4.2373557091 588 1305031121.7471449375 0.0428845026 0.0450939523 0.0940743834 0.0176895537 0.1087300000 0.0105430000 0.0544080000 0.0000290000 0.0003790000 0.0262170000 10434300 96830484 1768919040 3.9034974575 3.8076748848 4.2404198647 589 1305031121.7828710079 0.0434755720 0.0450912046 0.0940743834 0.0176754447 0.1465750000 0.0091870000 0.0644510000 0.0003530000 0.0002710000 0.0520860000 10436550 96830484 1770688512 3.9049751759 3.8004865646 4.2435727119 590 1305031121.8115448952 0.0448746383 0.0450908375 0.0940743834 0.0176651942 0.1037750000 0.0106680000 0.0441700000 0.0000290000 0.0003180000 0.0264540000 10438672 96830484 1769549824 3.9047906399 3.7952737808 4.2466158867 591 1305031121.8473351002 0.0455292203 0.0450915793 0.0940743834 0.0176524145 0.1281110000 0.0108300000 0.0648280000 0.0002950000 0.0003530000 0.0323100000 10440922 96830484 1768046592 3.9069790840 3.7919490337 4.2493290901 592 1305031121.8821229935 0.0462396517 0.0450935186 0.0940743834 0.0176375029 0.1063920000 0.0088930000 0.0499760000 0.0000300000 0.0004380000 0.0266400000 10443140 96830484 1769705472 3.9064621925 3.7891125679 4.2516899109 593 1305031121.9149429798 0.0455612093 0.0450943073 0.0940743834 0.0176233547 0.1274400000 0.0106270000 0.0438220000 0.0003880000 0.0002780000 0.0521830000 10445358 96830484 1768665088 3.9077928066 3.7874968052 4.2531361580 594 1305031121.9473180771 0.0462600254 0.0450962698 0.0940743834 0.0176115594 0.0887430000 0.0087970000 0.0381510000 0.0000270000 0.0003630000 0.0283260000 10447544 96830484 1770414080 3.9069733620 3.7861816883 4.2542033195 595 1305031121.9829349518 0.0434018262 0.0450934220 0.0940743834 0.0175974365 0.1162440000 0.0106910000 0.0690150000 0.0002960000 0.0003480000 0.0286740000 10449794 96830484 1769152512 3.9091484547 3.7900271416 4.2546463013 596 1305031122.0144240856 0.0432253964 0.0450902877 0.0940743834 0.0175836083 0.0956480000 0.0087960000 0.0379950000 0.0000280000 0.0003570000 0.0277540000 10451980 96830484 1770979328 3.9080154896 3.7923488617 4.2543435097 597 1305031122.0473060608 0.0432801209 0.0450872556 0.0940743834 0.0175695953 0.1288880000 0.0103590000 0.0433040000 0.0002960000 0.0003500000 0.0541650000 10454166 96830484 1769807872 3.9076812267 3.7949724197 4.2531943321 598 1305031122.0829689503 0.0418909825 0.0450819107 0.0940743834 0.0175555232 0.1062950000 0.0109090000 0.0498670000 0.0000280000 0.0002810000 0.0263380000 10456416 96830484 1768390656 3.9073517323 3.8017296791 4.2514185905 599 1305031122.1146879196 0.0410867296 0.0450752409 0.0940743834 0.0175418933 0.1075270000 0.0090040000 0.0492270000 0.0003120000 0.0003500000 0.0316890000 10458570 96830484 1770196992 3.9073047638 3.8090522289 4.2483453751 600 1305031122.1507480145 0.0397663973 0.0450663928 0.0940743834 0.0175327627 0.0887500000 0.0113080000 0.0383770000 0.0000270000 0.0002830000 0.0272150000 10460820 96830484 1769025536 3.9071455002 3.8186709881 4.2455248833 601 1305031122.1830520630 0.0383441485 0.0450552077 0.0940743834 0.0175301916 0.1623550000 0.0089970000 0.0735030000 0.0000610000 0.0000540000 0.0549440000 10463038 96830484 1767993344 3.9088780880 3.8270711899 4.2413063049 602 1305031122.2149689198 0.0358396731 0.0450398995 0.0940743834 0.0175568682 0.1090980000 0.0093800000 0.0557110000 0.0000270000 0.0003160000 0.0286700000 10465192 96830484 1769562112 3.9077637196 3.8405034542 4.2383971214 603 1305031122.2513549328 0.0367872231 0.0450262135 0.0940743834 0.0175487145 0.1279440000 0.0118700000 0.0719860000 0.0003530000 0.0002740000 0.0306700000 10467474 96830484 1768538112 3.9055526257 3.8518877029 4.2346515656 604 1305031122.2838659286 0.0380178355 0.0450146102 0.0940743834 0.0175392863 0.1082910000 0.0090540000 0.0657370000 0.0000280000 0.0003530000 0.0247440000 10469692 96830484 1770160128 3.9047806263 3.8598756790 4.2285337448 605 1305031122.3143088818 0.0335367955 0.0449956386 0.0940743834 0.0175597081 0.1247150000 0.0112390000 0.0449740000 0.0003960000 0.0002750000 0.0495880000 10471814 96830484 1769025536 3.9041695595 3.8762567043 4.2240920067 606 1305031122.3513510227 0.0353713632 0.0449797570 0.0940743834 0.0175516263 0.0870080000 0.0091380000 0.0339270000 0.0000270000 0.0002860000 0.0257080000 10474064 96830484 1770835968 3.9050614834 3.8835842609 4.2199468613 607 1305031122.3826780319 0.0347524099 0.0449629080 0.0940743834 0.0175403202 0.1293520000 0.0110340000 0.0789270000 0.0002910000 0.0003400000 0.0290370000 10476282 96830484 1769680896 3.9067885876 3.8916437626 4.2147064209 608 1305031122.4150080681 0.0367101431 0.0449493344 0.0940743834 0.0175379394 0.1239050000 0.0109250000 0.0673350000 0.0000270000 0.0002850000 0.0240370000 10478404 96830484 1768247296 3.9062132835 3.8982319832 4.2090053558 609 1305031122.4512720108 0.0382842012 0.0449383900 0.0940743834 0.0175261404 0.0997710000 0.0092320000 0.0405920000 0.0002990000 0.0003340000 0.0422470000 10480686 96830484 1769959424 3.9071278572 3.9074265957 4.2032866478 610 1305031122.4833879471 0.0368163511 0.0449250752 0.0940743834 0.0175129078 0.0976220000 0.0112340000 0.0522450000 0.0000260000 0.0003850000 0.0229480000 10482872 96830484 1768665088 3.9065244198 3.9177186489 4.1975870132 611 1305031122.5151350498 0.0367262289 0.0449116564 0.0940743834 0.0175023726 0.0864950000 0.0090700000 0.0348470000 0.0002960000 0.0003550000 0.0300990000 10485058 96830484 1770287104 3.9067656994 3.9261360168 4.1922140121 612 1305031122.5515100956 0.0379976481 0.0449003590 0.0940743834 0.0174951341 0.1119600000 0.0106420000 0.0726820000 0.0000880000 0.0002780000 0.0208700000 10487308 96830484 1769406464 3.9070367813 3.9366734028 4.1868176460 613 1305031122.5832169056 0.0377671346 0.0448887225 0.0940743834 0.0174818461 0.0934480000 0.0092010000 0.0342220000 0.0002890000 0.0002650000 0.0423570000 10489494 96830484 1771106304 3.9068872929 3.9460506439 4.1814045906 614 1305031122.6150169373 0.0393844694 0.0448797579 0.0940743834 0.0174755407 0.0952370000 0.0110640000 0.0419750000 0.0000260000 0.0003650000 0.0249090000 10491648 96830484 1770061824 3.9061534405 3.9532339573 4.1758704185 615 1305031122.6488099098 0.0432834253 0.0448771622 0.0940743834 0.0174615526 0.1157080000 0.0099670000 0.0715740000 0.0000630000 0.0000540000 0.0264900000 10493898 96830484 1768415232 3.9059813023 3.9615440369 4.1703543663 616 1305031122.6834199429 0.0419981778 0.0448724885 0.0940743834 0.0174476884 0.1166340000 0.0091480000 0.0713630000 0.0000070000 0.0000610000 0.0226680000 10496116 96830484 1767780352 3.9057376385 3.9727835655 4.1653800011 617 1305031122.7152190208 0.0424880646 0.0448686240 0.0940743834 0.0174358263 0.1316910000 0.0092500000 0.0724940000 0.0000650000 0.0000540000 0.0424790000 10498270 96830484 1766490112 3.9057450294 3.9818835258 4.1612749100 618 1305031122.7513089180 0.0441339351 0.0448674352 0.0940743834 0.0174297136 0.1029730000 0.0094650000 0.0608840000 0.0000250000 0.0002840000 0.0228770000 10500552 96830484 1764958208 3.9074420929 3.9935333729 4.1572003365 619 1305031122.7834379673 0.0416052565 0.0448621651 0.0940743834 0.0174220932 0.1042280000 0.0097720000 0.0427970000 0.0003800000 0.0002780000 0.0293020000 10502738 96830484 1765105664 3.9075424671 4.0067229271 4.1541857719 620 1305031122.8125650883 0.0425806232 0.0448584852 0.0940743834 0.0174099477 0.1063350000 0.0093420000 0.0736590000 0.0000070000 0.0000690000 0.0160760000 10504892 96830484 1765130240 3.9083831310 4.0157670975 4.1515145302 621 1305031122.8514859676 0.0476450995 0.0448629725 0.0940743834 0.0174085989 0.1322130000 0.0091300000 0.0742660000 0.0003730000 0.0002740000 0.0406310000 10507174 96830484 1765130240 3.9078922272 4.0226736069 4.1490201950 622 1305031122.8837749958 0.0478735752 0.0448678127 0.0940743834 0.0173971523 0.1232810000 0.0091400000 0.0745440000 0.0000270000 0.0003030000 0.0227920000 10509392 96830484 1765113856 3.9096720219 4.0317749977 4.1464653015 623 1305031122.9145851135 0.0501932837 0.0448763608 0.0940743834 0.0173902638 0.1073410000 0.0093520000 0.0554690000 0.0003640000 0.0002780000 0.0269320000 10511514 96830484 1766604800 3.9072675705 4.0380434990 4.1437935829 624 1305031122.9514129162 0.0551415458 0.0448928114 0.0940743834 0.0173781344 0.0934300000 0.0093530000 0.0492780000 0.0000260000 0.0003510000 0.0271470000 10513796 96830484 1768398848 3.9059233665 4.0437698364 4.1412863731 625 1305031122.9830000401 0.0557839833 0.0449102373 0.0940743834 0.0173665682 0.1199620000 0.0102590000 0.0444380000 0.0003950000 0.0002820000 0.0431500000 10515982 96830484 1770143744 3.9070918560 4.0513253212 4.1390800476 626 1305031123.0154619217 0.0575076565 0.0449303610 0.0940743834 0.0173530368 0.0893290000 0.0111320000 0.0419750000 0.0000290000 0.0003490000 0.0212160000 10518136 96830484 1768648704 3.9056477547 4.0580077171 4.1369976997 627 1305031123.0518379211 0.0621785782 0.0449578701 0.0940743834 0.0173429324 0.1248060000 0.0099600000 0.0702820000 0.0002910000 0.0002610000 0.0274230000 10520418 96830484 1767239680 3.9056830406 4.0636019707 4.1346521378 628 1305031123.0829920769 0.0625293478 0.0449858501 0.0940743834 0.0173332187 0.1067370000 0.0097760000 0.0602330000 0.0000340000 0.0002880000 0.0214500000 10522604 96830484 1769046016 3.9049015045 4.0722031593 4.1322355270 629 1305031123.1139390469 0.0614472106 0.0450120208 0.0940743834 0.0173261643 0.1298780000 0.0093590000 0.0708140000 0.0002860000 0.0003390000 0.0417230000 10524726 96830484 1770655744 3.9065415859 4.0827484131 4.1300969124 630 1305031123.1508400440 0.0665995255 0.0450462867 0.0940743834 0.0173127245 0.0861580000 0.0111970000 0.0426710000 0.0000280000 0.0003850000 0.0218040000 10527008 96830484 1769652224 3.9044017792 4.0894479752 4.1289792061 631 1305031123.1821761131 0.0678935945 0.0450824948 0.0940743834 0.0173104262 0.1198940000 0.0099250000 0.0604930000 0.0005810000 0.0002790000 0.0275930000 10529194 96830484 1768652800 3.9038753510 4.0986375809 4.1275119781 632 1305031123.2147240639 0.0679368600 0.0451186568 0.0940743834 0.0172994090 0.0871390000 0.0093610000 0.0345470000 0.0000260000 0.0002890000 0.0232450000 10531380 96830484 1770336256 3.9065177441 4.1096496582 4.1265149117 633 1305031123.2506411076 0.0729690194 0.0451626542 0.0940743834 0.0173100337 0.1330840000 0.0111920000 0.0686170000 0.0003570000 0.0002730000 0.0451690000 10533630 96830484 1769127936 3.9033832550 4.1186838150 4.1259264946 634 1305031123.2823629379 0.0770603120 0.0452129659 0.0940743834 0.0173029340 0.1084750000 0.0091310000 0.0758570000 0.0000290000 0.0003170000 0.0157550000 10535816 96830484 1770971136 3.9066815376 4.1258201599 4.1266484261 635 1305031123.3209919930 0.0837417915 0.0452736413 0.0940743834 0.0172945675 0.1098360000 0.0107120000 0.0655750000 0.0000620000 0.0000530000 0.0258290000 10538098 96830484 1770160128 3.9051883221 4.1326050758 4.1271843910 636 1305031123.3504929543 0.0859746411 0.0453376365 0.0940743834 0.0172819816 0.0957400000 0.0120880000 0.0393330000 0.0000110000 0.0004760000 0.0224910000 10540252 96830484 1768763392 3.9047801495 4.1408152580 4.1270961761 637 1305031123.3822629452 0.0891944915 0.0454064856 0.0940743834 0.0172699401 0.1313660000 0.0092950000 0.0719330000 0.0002840000 0.0005190000 0.0419620000 10542438 96830484 1767895040 3.9068996906 4.1476540565 4.1271114349 638 1305031123.4213430882 0.0951683000 0.0454844822 0.0951683000 0.0172568455 0.1030060000 0.0097000000 0.0548470000 0.0000240000 0.0002890000 0.0236320000 10544720 96830484 1767157760 3.9070241451 4.1537413597 4.1270551682 639 1305031123.4512660503 0.0984435827 0.0455673603 0.0984435827 0.0172517531 0.0847760000 0.0093430000 0.0424880000 0.0027030000 0.0002940000 0.0223640000 10546842 96830484 1765879808 3.9058105946 4.1593770981 4.1265983582 640 1305031123.4836049080 0.0991966650 0.0456511561 0.0991966650 0.0172407752 0.1040100000 0.0095360000 0.0695600000 0.0000280000 0.0003570000 0.0169600000 10549060 96830484 1764978688 3.9073946476 4.1680073738 4.1254801750 641 1305031123.5197250843 0.1026064456 0.0457400099 0.1026064456 0.0172287298 0.1104120000 0.0093380000 0.0547150000 0.0003070000 0.0002790000 0.0359890000 10551278 96830484 1765064704 3.9070389271 4.1754689217 4.1243491173 642 1305031123.5515730381 0.1044935659 0.0458315263 0.1044935659 0.0172157492 0.1007480000 0.0110640000 0.0514200000 0.0000280000 0.0003660000 0.0239370000 10553496 96830484 1765105664 3.9087874889 4.1816015244 4.1235775948 643 1305031123.5796160698 0.1058000550 0.0459247900 0.1058000550 0.0172045409 0.1264670000 0.0092280000 0.0721460000 0.0003090000 0.0002770000 0.0298070000 10555586 96830484 1765105664 3.9091527462 4.1884860992 4.1226258278 644 1305031123.6203870773 0.1084734499 0.0460219152 0.1084734499 0.0171996756 0.1067250000 0.0094450000 0.0566470000 0.0000270000 0.0002840000 0.0247690000 10557900 96830484 1766617088 3.9112758636 4.1956882477 4.1217770576 645 1305031123.6524300575 0.1087838337 0.0461192205 0.1087838337 0.0171876136 0.1351290000 0.0097120000 0.0734400000 0.0003620000 0.0002740000 0.0437930000 10560086 96830484 1768243200 3.9139208794 4.2034301758 4.1212587357 646 1305031123.6837849617 0.1093635783 0.0462171220 0.1093635783 0.0171762480 0.1178540000 0.0096520000 0.0627800000 0.0000290000 0.0003570000 0.0245580000 10562272 96830484 1770020864 3.9131073952 4.2103347778 4.1208076477 647 1305031123.7199749947 0.1122284904 0.0463191488 0.1122284904 0.0171637975 0.1269050000 0.0114450000 0.0620430000 0.0002890000 0.0002670000 0.0297490000 10564522 96830484 1768763392 3.9130156040 4.2154822350 4.1203012466 648 1305031123.7519800663 0.1130075678 0.0464220631 0.1130075678 0.0171564838 0.1068890000 0.0095200000 0.0500360000 0.0000280000 0.0002830000 0.0251180000 10566708 96830484 1770463232 3.9126415253 4.2189369202 4.1195478439 649 1305031123.7841379642 0.1140159965 0.0465262140 0.1140159965 0.0171477098 0.1132630000 0.0112500000 0.0496110000 0.0003040000 0.0003530000 0.0441730000 10568862 96830484 1769381888 3.9138035774 4.2205095291 4.1192111969 650 1305031123.8196959496 0.1137116626 0.0466295762 0.1140159965 0.0171359465 0.1022660000 0.0098350000 0.0497970000 0.0000250000 0.0003570000 0.0247350000 10571144 96830484 1771098112 3.9152200222 4.2228398323 4.1182675362 651 1305031123.8515510559 0.1135845631 0.0467324256 0.1140159965 0.0171230555 0.1086790000 0.0112750000 0.0550010000 0.0002970000 0.0003530000 0.0300890000 10573330 96830484 1770287104 3.9160687923 4.2224907875 4.1176481247 652 1305031123.8838191032 0.1137235910 0.0468351728 0.1140159965 0.0171128961 0.1258490000 0.0116740000 0.0735290000 0.0000970000 0.0002800000 0.0245230000 10575516 96830484 1768763392 3.9156589508 4.2209239006 4.1174707413 653 1305031123.9157938957 0.1122376621 0.0469353298 0.1140159965 0.0171014414 0.1132570000 0.0097460000 0.0514110000 0.0003180000 0.0003420000 0.0437430000 10577670 96830484 1770586112 3.9157578945 4.2183008194 4.1168322563 654 1305031123.9515299797 0.1083910540 0.0470292988 0.1140159965 0.0171001546 0.1022970000 0.0116160000 0.0570650000 0.0000270000 0.0003550000 0.0234400000 10579952 96830484 1769398272 3.9163329601 4.2187852859 4.1162104607 655 1305031123.9834210873 0.1096994355 0.0471249784 0.1140159965 0.0170991322 0.1062050000 0.0095960000 0.0516500000 0.0003650000 0.0002740000 0.0295100000 10582138 96830484 1771208704 3.9155306816 4.2128782272 4.1180157661 656 1305031124.0197370052 0.1104471013 0.0472215060 0.1140159965 0.0171121379 0.1076400000 0.0115430000 0.0533480000 0.0002490000 0.0003030000 0.0301100000 10584388 96830484 1769926656 3.9144272804 4.2037596703 4.1206145287 657 1305031124.0515310764 0.1062570065 0.0473113622 0.1140159965 0.0171108829 0.1235010000 0.0114280000 0.0448280000 0.0004060000 0.0002780000 0.0471060000 10586542 96830484 1768620032 3.9155671597 4.2014656067 4.1207585335 658 1305031124.0839018822 0.1053815931 0.0473996148 0.1140159965 0.0171027198 0.1271150000 0.0095050000 0.0745390000 0.0000260000 0.0002800000 0.0239150000 10588728 96830484 1770164224 3.9162719250 4.1960225105 4.1233439445 659 1305031124.1196689606 0.1042746454 0.0474859198 0.1140159965 0.0171070029 0.1280020000 0.0115450000 0.0738350000 0.0002960000 0.0002670000 0.0289530000 10590978 96830484 1769271296 3.9099090099 4.1856102943 4.1255125999 660 1305031124.1474580765 0.1007820070 0.0475666715 0.1140159965 0.0171065847 0.1062420000 0.0096560000 0.0567080000 0.0000270000 0.0002820000 0.0231440000 10593132 96830484 1770803200 3.9188385010 4.1821951866 4.1279244423 661 1305031124.1827070713 0.0995469689 0.0476453104 0.1140159965 0.0170973901 0.1380430000 0.0115250000 0.0760390000 0.0003570000 0.0002820000 0.0417720000 10595350 96830484 1769525248 3.9171662331 4.1754140854 4.1306939125 662 1305031124.2171790600 0.0935416520 0.0477146402 0.1140159965 0.0171013252 0.0953000000 0.0111970000 0.0427190000 0.0000250000 0.0009000000 0.0231210000 10597568 96830484 1768017920 3.9046614170 4.1683344841 4.1286044121 663 1305031124.2493400574 0.0938234106 0.0477841858 0.1140159965 0.0170958232 0.1268700000 0.0103460000 0.0728340000 0.0003220000 0.0002740000 0.0280430000 10599722 96830484 1767628800 3.9212362766 4.1603097916 4.1346211433 664 1305031124.2825551033 0.0884952545 0.0478454977 0.1140159965 0.0170837630 0.1262140000 0.0099420000 0.0777840000 0.0000050000 0.0000600000 0.0230390000 10601940 96830484 1767366656 3.9199113846 4.1571307182 4.1354889870 665 1305031124.3167819977 0.0828718543 0.0478981689 0.1140159965 0.0170897329 0.0995460000 0.0097900000 0.0380710000 0.0003070000 0.0002790000 0.0431040000 10604158 96830484 1766985728 3.9130914211 4.1485381126 4.1342234612 666 1305031124.3503708839 0.0802280232 0.0479467122 0.1140159965 0.0170822231 0.1340320000 0.0134290000 0.0832640000 0.0000310000 0.0003000000 0.0227750000 10606344 96830484 1765072896 3.9155726433 4.1419415474 4.1360092163 667 1305031124.3824319839 0.0760088488 0.0479887844 0.1140159965 0.0170733754 0.1089310000 0.0098740000 0.0596810000 0.0003790000 0.0002780000 0.0278540000 10608562 96830484 1766596608 3.9172298908 4.1357078552 4.1363544464 668 1305031124.4185550213 0.0709363520 0.0480231370 0.1140159965 0.0170761787 0.1024030000 0.0097610000 0.0486680000 0.0000300000 0.0003770000 0.0216100000 10610844 96830484 1768636416 3.9212307930 4.1258201599 4.1367254257 669 1305031124.4502561092 0.0683485493 0.0480535188 0.1140159965 0.0170635734 0.1476750000 0.0095570000 0.0718680000 0.0003040000 0.0003570000 0.0451340000 10612966 96830484 1770299392 3.9200336933 4.1166524887 4.1373291016 670 1305031124.4801259041 0.0639179870 0.0480771971 0.1140159965 0.0170516709 0.1103020000 0.0116250000 0.0690060000 0.0000270000 0.0002960000 0.0215410000 10615152 96830484 1768259584 3.9212799072 4.1090555191 4.1371345520 671 1305031124.5167369843 0.0567115694 0.0480900651 0.1140159965 0.0170395594 0.1018850000 0.0098330000 0.0484490000 0.0003760000 0.0002830000 0.0292550000 10617402 96830484 1769807872 3.9231655598 4.1012101173 4.1377391815 672 1305031124.5505030155 0.0526622236 0.0480968689 0.1140159965 0.0170270508 0.0878640000 0.0115200000 0.0424350000 0.0000320000 0.0003070000 0.0217800000 10619620 96830484 1768112128 3.9217698574 4.0940260887 4.1391859055 673 1305031124.5846059322 0.0507910252 0.0481008721 0.1140159965 0.0170149250 0.1297310000 0.0106100000 0.0713820000 0.0003890000 0.0002740000 0.0392810000 10621838 96830484 1768026112 3.9226179123 4.0840768814 4.1413121223 674 1305031124.6176528931 0.0452000760 0.0480965682 0.1140159965 0.0170168223 0.0842540000 0.0091850000 0.0429630000 0.0000320000 0.0013530000 0.0217350000 10624056 96830484 1769811968 3.9231631756 4.0733103752 4.1437883377 675 1305031124.6513130665 0.0420462638 0.0480876048 0.1140159965 0.0170100489 0.1076070000 0.0117670000 0.0580080000 0.0003200000 0.0003420000 0.0281900000 10626242 96830484 1767636992 3.9233198166 4.0648498535 4.1465282440 676 1305031124.6854729652 0.0408707149 0.0480769289 0.1140159965 0.0170018813 0.1232470000 0.0091930000 0.0707220000 0.0000290000 0.0003040000 0.0221830000 10628460 96830484 1769295872 3.9245946407 4.0536360741 4.1495981216 677 1305031124.7157909870 0.0338941999 0.0480559796 0.1140159965 0.0169904756 0.0976240000 0.0094900000 0.0375230000 0.0003030000 0.0003570000 0.0419760000 10630646 96830484 1771061248 3.9255738258 4.0448145866 4.1525425911 678 1305031124.7499411106 0.0318150856 0.0480320254 0.1140159965 0.0169786958 0.0997540000 0.0112520000 0.0547410000 0.0000300000 0.0003830000 0.0225520000 10632864 96830484 1769037824 3.9245853424 4.0352997780 4.1562404633 679 1305031124.7851779461 0.0316107199 0.0480078409 0.1140159965 0.0169667993 0.1270770000 0.0103150000 0.0769470000 0.0003010000 0.0002780000 0.0288210000 10635082 96830484 1770790912 3.9242050648 4.0237836838 4.1604843140 680 1305031124.8166410923 0.0256364401 0.0479749418 0.1140159965 0.0169554683 0.0865070000 0.0120170000 0.0371570000 0.0000300000 0.0003790000 0.0242850000 10637268 96830484 1768656896 3.9227917194 4.0149235725 4.1651649475 681 1305031124.8505589962 0.0250680353 0.0479413046 0.1140159965 0.0169433002 0.1329110000 0.0107930000 0.0671390000 0.0003730000 0.0002830000 0.0392340000 10639486 96830484 1767096320 3.9225981236 4.0045900345 4.1706881523 682 1305031124.8835940361 0.0250851791 0.0479077912 0.1140159965 0.0169416386 0.0933950000 0.0111860000 0.0474330000 0.0000280000 0.0003730000 0.0262830000 10641672 96830484 1768775680 3.9246482849 3.9930226803 4.1762852669 683 1305031124.9187700748 0.0202873070 0.0478673513 0.1140159965 0.0169406203 0.1233980000 0.0094240000 0.0543660000 0.0003180000 0.0003370000 0.0381830000 10643922 96830484 1770315776 3.9243526459 3.9854264259 4.1822142601 684 1305031124.9507479668 0.0212188009 0.0478283914 0.1140159965 0.0169298212 0.1475010000 0.0117230000 0.0892830000 0.0000270000 0.0003590000 0.0272870000 10646076 96830484 1768402944 3.9220440388 3.9770941734 4.1884074211 685 1305031124.9864599705 0.0242606979 0.0477939860 0.1140159965 0.0169638105 0.1381030000 0.0103000000 0.0706880000 0.0003040000 0.0002780000 0.0485970000 10648326 96830484 1770045440 3.9233198166 3.9608607292 4.1943349838 686 1305031125.0194671154 0.0274193436 0.0477642854 0.1140159965 0.0169543392 0.1366890000 0.0119470000 0.0848500000 0.0000250000 0.0002880000 0.0233320000 10650544 96830484 1768382464 3.9215552807 3.9495813847 4.2002177238 687 1305031125.0507979393 0.0243944693 0.0477302682 0.1140159965 0.0169539219 0.0890180000 0.0098650000 0.0407610000 0.0002880000 0.0012200000 0.0286700000 10652698 96830484 1770045440 3.9213752747 3.9458396435 4.2053737640 688 1305031125.0834798813 0.0238225404 0.0476955186 0.1140159965 0.0169432902 0.0867620000 0.0117850000 0.0413890000 0.0000280000 0.0002860000 0.0239300000 10654916 96830484 1767858176 3.9217803478 3.9383528233 4.2106471062 689 1305031125.1190290451 0.0254707187 0.0476632620 0.1140159965 0.0169363481 0.1439500000 0.0111890000 0.0603570000 0.0003600000 0.0002700000 0.0524420000 10657166 96830484 1766252544 3.9194238186 3.9270298481 4.2155556679 690 1305031125.1510369778 0.0252382923 0.0476307620 0.1140159965 0.0169280451 0.1121820000 0.0091530000 0.0750300000 0.0000060000 0.0000600000 0.0197600000 10659320 96830484 1767919616 3.9199783802 3.9187579155 4.2194838524 691 1305031125.1870639324 0.0233515669 0.0475956257 0.1140159965 0.0169289935 0.1000180000 0.0090320000 0.0384970000 0.0002960000 0.0036620000 0.0270020000 10661602 96830484 1769664512 3.9170269966 3.9156439304 4.2235832214 692 1305031125.2190179825 0.0253410060 0.0475634658 0.1140159965 0.0169207588 0.0904400000 0.0108600000 0.0461670000 0.0000270000 0.0003890000 0.0241200000 10663788 96830484 1768767488 3.9146873951 3.9063606262 4.2271280289 693 1305031125.2506420612 0.0289170276 0.0475365590 0.1140159965 0.0169128168 0.1003930000 0.0100330000 0.0350620000 0.0002830000 0.0003380000 0.0460970000 10665942 96830484 1767796736 3.9134242535 3.8935239315 4.2303161621 694 1305031125.2863960266 0.0294576734 0.0475105087 0.1140159965 0.0169028563 0.1115740000 0.0094530000 0.0630110000 0.0000260000 0.0003490000 0.0284770000 10668192 96830484 1767272448 3.9101896286 3.8875524998 4.2334890366 695 1305031125.3191399574 0.0291252192 0.0474840551 0.1140159965 0.0168944242 0.0928180000 0.0093290000 0.0508730000 0.0002880000 0.0002620000 0.0238980000 10670410 96830484 1766371328 3.9100811481 3.8814487457 4.2365117073 696 1305031125.3488988876 0.0332901329 0.0474636615 0.1140159965 0.0168840382 0.0940010000 0.0091200000 0.0580300000 0.0000270000 0.0002850000 0.0183310000 10672532 96830484 1765351424 3.9055330753 3.8727920055 4.2391138077 697 1305031125.3867919445 0.0320895314 0.0474416039 0.1140159965 0.0168837721 0.1315650000 0.0091560000 0.0716680000 0.0002930000 0.0002710000 0.0389820000 10674846 96830484 1765113856 3.9050526619 3.8709070683 4.2425632477 698 1305031125.4195740223 0.0333322994 0.0474213900 0.1140159965 0.0168732344 0.1181150000 0.0106730000 0.0619600000 0.0000260000 0.0004970000 0.0247110000 10677032 96830484 1765101568 3.9052388668 3.8639543056 4.2456874847 699 1305031125.4512319565 0.0354372263 0.0474042453 0.1140159965 0.0168712342 0.1075350000 0.0090180000 0.0511600000 0.0003770000 0.0002750000 0.0301860000 10679218 96830484 1766617088 3.9024832249 3.8596272469 4.2486424446 700 1305031125.4869990349 0.0377905853 0.0473905115 0.1140159965 0.0168714526 0.0883370000 0.0093060000 0.0399440000 0.0000270000 0.0002860000 0.0260360000 10681468 96830484 1768243200 3.9041421413 3.8488321304 4.2506694794 701 1305031125.5193541050 0.0387351923 0.0473781644 0.1140159965 0.0168661018 0.1549950000 0.0085370000 0.0767810000 0.0003040000 0.0003550000 0.0607560000 10683686 96830484 1770020864 3.9027621746 3.8458635807 4.2531766891 702 1305031125.5510499477 0.0381711014 0.0473650489 0.1140159965 0.0168562820 0.0994720000 0.0108270000 0.0452360000 0.0000270000 0.0003000000 0.0303520000 10685840 96830484 1769037824 3.9041507244 3.8427789211 4.2546257973 703 1305031125.5853030682 0.0378934629 0.0473515758 0.1140159965 0.0168443942 0.1450230000 0.0086350000 0.0817100000 0.0000610000 0.0000540000 0.0343480000 10688058 96830484 1770717184 3.9055607319 3.8400177956 4.2555456161 704 1305031125.6178700924 0.0414034240 0.0473431268 0.1140159965 0.0168535352 0.1097970000 0.0116620000 0.0695570000 0.0000060000 0.0000610000 0.0201620000 10690276 96830484 1769889792 3.9043085575 3.8342163563 4.2551345825 705 1305031125.6505749226 0.0449500866 0.0473397324 0.1140159965 0.0168466185 0.1192130000 0.0104410000 0.0526970000 0.0006690000 0.0002990000 0.0468790000 10692462 96830484 1768529920 3.9029095173 3.8303534985 4.2533407211 706 1305031125.6846020222 0.0433215983 0.0473340410 0.1140159965 0.0168455991 0.1097030000 0.0094570000 0.0512290000 0.0000300000 0.0008230000 0.0243870000 10694648 96830484 1770172416 3.9027307034 3.8345737457 4.2512574196 707 1305031125.7156689167 0.0418528095 0.0473262882 0.1140159965 0.0168630111 0.1090170000 0.0110390000 0.0504110000 0.0003110000 0.0002720000 0.0309410000 10696834 96830484 1768382464 3.9042053223 3.8375027180 4.2492017746 708 1305031125.7512919903 0.0390299261 0.0473145701 0.1140159965 0.0168621976 0.1045760000 0.0093690000 0.0447500000 0.0000370000 0.0006490000 0.0259190000 10699084 96830484 1769914368 3.9068009853 3.8431172371 4.2460141182 709 1305031125.7868049145 0.0358567126 0.0472984095 0.1140159965 0.0168563923 0.1269230000 0.0111110000 0.0401190000 0.0003210000 0.0003550000 0.0500000000 10701334 96830484 1767895040 3.9068994522 3.8526751995 4.2436714172 710 1305031125.8194499016 0.0343166925 0.0472801254 0.1140159965 0.0168479346 0.1107350000 0.0089540000 0.0663460000 0.0000290000 0.0003130000 0.0251250000 10703552 96830484 1769553920 3.9087901115 3.8590490818 4.2402253151 711 1305031125.8547739983 0.0322152004 0.0472589371 0.1140159965 0.0168407496 0.1215810000 0.0093840000 0.0621180000 0.0003780000 0.0002780000 0.0306700000 10705738 96830484 1771335680 3.9091253281 3.8681781292 4.2367062569 712 1305031125.8866450787 0.0368794650 0.0472443592 0.1140159965 0.0168437519 0.1082470000 0.0114680000 0.0557800000 0.0000290000 0.0003680000 0.0250580000 10707956 96830484 1769127936 3.9043540955 3.8759622574 4.2317466736 713 1305031125.9193339348 0.0350715555 0.0472272865 0.1140159965 0.0168421844 0.1243090000 0.0091540000 0.0393770000 0.0003250000 0.0002700000 0.0524830000 10710174 96830484 1770930176 3.9052274227 3.8853149414 4.2294116020 714 1305031125.9552519321 0.0384465083 0.0472149885 0.1140159965 0.0168409666 0.1275420000 0.0113680000 0.0686260000 0.0000280000 0.0002990000 0.0250010000 10712392 96830484 1769144320 3.9043416977 3.8898646832 4.2255730629 715 1305031125.9870939255 0.0391596146 0.0472037222 0.1140159965 0.0168336092 0.1073300000 0.0094680000 0.0472160000 0.0003050000 0.0002690000 0.0307110000 10714578 96830484 1770934272 3.9062869549 3.8991081715 4.2224497795 716 1305031126.0195720196 0.0365394987 0.0471888281 0.1140159965 0.0168260209 0.1120010000 0.0114790000 0.0736120000 0.0000070000 0.0000610000 0.0180600000 10716796 96830484 1769144320 3.9071421623 3.9120893478 4.2201333046 717 1305031126.0550379753 0.0325593278 0.0471684243 0.1140159965 0.0168203924 0.1110210000 0.0097960000 0.0463610000 0.0010040000 0.0003680000 0.0443850000 10719014 96830484 1770803200 3.9122781754 3.9240980148 4.2180781364 718 1305031126.0870759487 0.0343727469 0.0471506030 0.1140159965 0.0168108159 0.1187130000 0.0116220000 0.0685080000 0.0000290000 0.0003850000 0.0248000000 10721200 96830484 1769017344 3.9155845642 3.9354715347 4.2156095505 719 1305031126.1194519997 0.0369324200 0.0471363914 0.1140159965 0.0168008013 0.1043090000 0.0097390000 0.0388970000 0.0002990000 0.0002810000 0.0311000000 10723418 96830484 1770676224 3.9149680138 3.9446454048 4.2130441666 720 1305031126.1549999714 0.0357770324 0.0471206145 0.1140159965 0.0167929747 0.1102960000 0.0123270000 0.0640280000 0.0000290000 0.0002910000 0.0231940000 10725604 96830484 1769889792 3.9185271263 3.9561257362 4.2107105255 721 1305031126.1871740818 0.0395981446 0.0471101811 0.1140159965 0.0167902258 0.1110000000 0.0112630000 0.0481220000 0.0003750000 0.0002830000 0.0425740000 10727822 96830484 1768546304 3.9185969830 3.9687345028 4.2090797424 722 1305031126.2194728851 0.0431868024 0.0471047471 0.1140159965 0.0167937242 0.1005650000 0.0097940000 0.0505880000 0.0000280000 0.0003020000 0.0231310000 10730040 96830484 1770188800 3.9204607010 3.9768080711 4.2066907883 723 1305031126.2552359104 0.0434575342 0.0470997025 0.1140159965 0.0167932771 0.1055640000 0.0109480000 0.0424270000 0.0003590000 0.0002850000 0.0284310000 10732290 96830484 1769418752 3.9225060940 3.9884223938 4.2041296959 724 1305031126.2871050835 0.0478779897 0.0471007775 0.1140159965 0.0167844249 0.1073760000 0.0091350000 0.0554170000 0.0000260000 0.0003700000 0.0221500000 10734444 96830484 1771225088 3.9231040478 3.9996323586 4.2013497353 725 1305031126.3197870255 0.0483231619 0.0471024635 0.1140159965 0.0167771629 0.1309290000 0.0114510000 0.0689570000 0.0003850000 0.0002850000 0.0412520000 10736662 96830484 1770053632 3.9236171246 4.0115880966 4.1991920471 726 1305031126.3554151058 0.0509368926 0.0471077451 0.1140159965 0.0167683628 0.1246410000 0.0114550000 0.0723460000 0.0000260000 0.0003000000 0.0215490000 10738880 96830484 1768673280 3.9234435558 4.0201430321 4.1967182159 727 1305031126.3874828815 0.0554441251 0.0471192119 0.1140159965 0.0167610396 0.0882170000 0.0095430000 0.0361730000 0.0003720000 0.0002740000 0.0283210000 10741098 96830484 1770442752 3.9224867821 4.0298199654 4.1938638687 728 1305031126.4197928905 0.0568149351 0.0471325302 0.1140159965 0.0167507801 0.1076210000 0.0107460000 0.0608410000 0.0000280000 0.0003140000 0.0222670000 10743252 96830484 1769508864 3.9205164909 4.0394644737 4.1914854050 729 1305031126.4553799629 0.0604454577 0.0471507921 0.1140159965 0.0167524574 0.1074210000 0.0108280000 0.0447000000 0.0003830000 0.0002680000 0.0419040000 10745470 96830484 1771225088 3.9217522144 4.0457944870 4.1891813278 730 1305031126.4903860092 0.0664846003 0.0471772768 0.1140159965 0.0167498754 0.1244430000 0.0113010000 0.0731180000 0.0000270000 0.0002870000 0.0205320000 10747720 96830484 1770180608 3.9213302135 4.0532536507 4.1862716675 731 1305031126.5223209858 0.0660385266 0.0472030788 0.1140159965 0.0167482580 0.1054890000 0.0114320000 0.0435560000 0.0005300000 0.0003640000 0.0261040000 10749906 96830484 1768783872 3.9223966599 4.0638923645 4.1837229729 732 1305031126.5582089424 0.0695538968 0.0472336127 0.1140159965 0.0167452198 0.0885070000 0.0092630000 0.0426620000 0.0000290000 0.0003130000 0.0199990000 10752156 96830484 1770442752 3.9238264561 4.0731835365 4.1819624901 733 1305031126.5901761055 0.0725786611 0.0472681898 0.1140159965 0.0167344273 0.1303390000 0.0117270000 0.0717590000 0.0002990000 0.0002770000 0.0376240000 10754342 96830484 1768509440 3.9222226143 4.0792708397 4.1810855865 734 1305031126.6186869144 0.0737641230 0.0473042878 0.1140159965 0.0167235368 0.1221340000 0.0099090000 0.0715050000 0.0000950000 0.0002930000 0.0203420000 10756464 96830484 1770041344 3.9222652912 4.0865240097 4.1795740128 735 1305031126.6544740200 0.0778627098 0.0473458639 0.1140159965 0.0167255064 0.0912330000 0.0116470000 0.0431860000 0.0003170000 0.0002800000 0.0259140000 10758746 96830484 1768402944 3.9235527515 4.0894241333 4.1790761948 736 1305031126.6900219917 0.0824055225 0.0473934993 0.1140159965 0.0167154008 0.1063340000 0.0097960000 0.0644570000 0.0000280000 0.0003650000 0.0209210000 10760996 96830484 1767903232 3.9235625267 4.0934243202 4.1773247719 737 1305031126.7157700062 0.0819377676 0.0474403708 0.1140159965 0.0167049905 0.1138680000 0.0095030000 0.0493350000 0.0003870000 0.0002810000 0.0457230000 10763054 96830484 1767399424 3.9251880646 4.0997691154 4.1751427650 738 1305031126.7553739548 0.0845828876 0.0474906994 0.1140159965 0.0166951926 0.1015870000 0.0090350000 0.0675140000 0.0000060000 0.0000680000 0.0164610000 10765368 96830484 1766223872 3.9239716530 4.1014800072 4.1729636192 739 1305031126.7875649929 0.0844424888 0.0475407018 0.1140159965 0.0166863387 0.1237820000 0.0091570000 0.0711830000 0.0003670000 0.0000580000 0.0309730000 10767554 96830484 1765228544 3.9252767563 4.1068577766 4.1697521210 740 1305031126.8199288845 0.0840674043 0.0475900622 0.1140159965 0.0166780747 0.1232470000 0.0103320000 0.0681740000 0.0000330000 0.0003030000 0.0214420000 10769740 96830484 1764970496 3.9266026020 4.1110315323 4.1673626900 741 1305031126.8583779335 0.0860400349 0.0476419515 0.1140159965 0.0166670771 0.1313820000 0.0091490000 0.0727070000 0.0003190000 0.0002810000 0.0401700000 10772054 96830484 1766469632 3.9279494286 4.1133036613 4.1661438942 742 1305031126.8881540298 0.0867206976 0.0476946183 0.1140159965 0.0166563668 0.1230180000 0.0092950000 0.0720050000 0.0000300000 0.0003030000 0.0217500000 10774208 96830484 1768243200 3.9279408455 4.1146883965 4.1643524170 743 1305031126.9194090366 0.0865430087 0.0477469042 0.1140159965 0.0166459114 0.0937630000 0.0091380000 0.0497110000 0.0003740000 0.0002870000 0.0254870000 10776362 96830484 1769893888 3.9296040535 4.1157512665 4.1627998352 744 1305031126.9555010796 0.0858973637 0.0477981817 0.1140159965 0.0166379290 0.1216640000 0.0110410000 0.0724470000 0.0000250000 0.0003630000 0.0213310000 10778612 96830484 1768873984 3.9296309948 4.1173272133 4.1612353325 745 1305031126.9873158932 0.0871798545 0.0478510430 0.1140159965 0.0166278684 0.1287590000 0.0097010000 0.0655700000 0.0003110000 0.0002760000 0.0425080000 10780830 96830484 1770680320 3.9293513298 4.1161298752 4.1603145599 746 1305031127.0195240974 0.0869793743 0.0479034938 0.1140159965 0.0166174185 0.1245510000 0.0111870000 0.0715340000 0.0000290000 0.0003030000 0.0219160000 10782984 96830484 1769398272 3.9295096397 4.1158752441 4.1594147682 747 1305031127.0533180237 0.0852544308 0.0479534951 0.1140159965 0.0166096546 0.1069880000 0.0095120000 0.0497010000 0.0003050000 0.0003500000 0.0271080000 10785202 96830484 1771225088 3.9319126606 4.1171264648 4.1589436531 748 1305031127.0886490345 0.0834982023 0.0480010147 0.1140159965 0.0166018111 0.1269270000 0.0112130000 0.0729890000 0.0000270000 0.0003010000 0.0216250000 10787452 96830484 1770180608 3.9320578575 4.1173624992 4.1589574814 749 1305031127.1209630966 0.0841396973 0.0480492640 0.1140159965 0.0165982330 0.1319270000 0.0112800000 0.0719670000 0.0003010000 0.0002770000 0.0394190000 10789606 96830484 1768783872 3.9309780598 4.1147723198 4.1590375900 750 1305031127.1576919556 0.0823352486 0.0480949786 0.1140159965 0.0165877213 0.1216320000 0.0092380000 0.0715770000 0.0000290000 0.0002950000 0.0215000000 10791888 96830484 1770422272 3.9284656048 4.1137890816 4.1581606865 751 1305031127.1875000000 0.0800589025 0.0481375404 0.1140159965 0.0165803328 0.1257800000 0.0118000000 0.0716390000 0.0003060000 0.0006900000 0.0267840000 10794042 96830484 1768620032 3.9293017387 4.1142516136 4.1585063934 752 1305031127.2218310833 0.0773893148 0.0481764391 0.1140159965 0.0165720316 0.1244420000 0.0095140000 0.0715160000 0.0000270000 0.0003070000 0.0210960000 10796260 96830484 1770295296 3.9280576706 4.1148257256 4.1581473351 753 1305031127.2597610950 0.0767370313 0.0482143682 0.1140159965 0.0165659471 0.1311460000 0.0110790000 0.0707320000 0.0003130000 0.0003510000 0.0398950000 10798542 96830484 1769545728 3.9262335300 4.1115112305 4.1591424942 754 1305031127.2870380878 0.0745389760 0.0482492814 0.1140159965 0.0165630501 0.1226660000 0.0094050000 0.0713730000 0.0000270000 0.0003020000 0.0214560000 10800632 96830484 1771225088 3.9260354042 4.1112627983 4.1596698761 755 1305031127.3204679489 0.0731676519 0.0482822859 0.1140159965 0.0165533550 0.1275970000 0.0112990000 0.0704090000 0.0003850000 0.0002780000 0.0268600000 10802850 96830484 1770180608 3.9252519608 4.1101999283 4.1608519554 756 1305031127.3534069061 0.0753340498 0.0483180687 0.1140159965 0.0165485894 0.1256100000 0.0114230000 0.0712410000 0.0000290000 0.0003780000 0.0214820000 10805036 96830484 1768783872 3.9259235859 4.1043591499 4.1628355980 757 1305031127.3837130070 0.0729542822 0.0483506132 0.1140159965 0.0165405562 0.1305280000 0.0094310000 0.0710160000 0.0005500000 0.0002910000 0.0403220000 10807222 96830484 1770422272 3.9259572029 4.1044406891 4.1638813019 758 1305031127.4196500778 0.0704297125 0.0483797413 0.1140159965 0.0165312052 0.1028830000 0.0116100000 0.0486890000 0.0000280000 0.0003050000 0.0210480000 10809440 96830484 1768620032 3.9264566898 4.1041145325 4.1654052734 759 1305031127.4542460442 0.0714399144 0.0484101236 0.1140159965 0.0165315765 0.1274850000 0.0096230000 0.0722730000 0.0003150000 0.0002720000 0.0273490000 10811690 96830484 1770442752 3.9262232780 4.1002001762 4.1671228409 760 1305031127.4872000217 0.0692231879 0.0484375092 0.1140159965 0.0165334959 0.1257890000 0.0119130000 0.0708160000 0.0000280000 0.0003870000 0.0213660000 10813876 96830484 1769545728 3.9269733429 4.1003479958 4.1685342789 761 1305031127.5218999386 0.0690202639 0.0484645562 0.1140159965 0.0165231466 0.1309130000 0.0110530000 0.0707090000 0.0003140000 0.0002750000 0.0395150000 10816126 96830484 1768128512 3.9268863201 4.0999717712 4.1706004143 762 1305031127.5537250042 0.0713306367 0.0484945642 0.1140159965 0.0165220978 0.1224690000 0.0100220000 0.0709160000 0.0000270000 0.0002990000 0.0207420000 10818280 96830484 1769934848 3.9258575439 4.0957126617 4.1724882126 763 1305031127.5866320133 0.0705359727 0.0485234520 0.1140159965 0.0165137431 0.1276920000 0.0109060000 0.0711050000 0.0003020000 0.0002780000 0.0269370000 10820498 96830484 1768546304 3.9247493744 4.0953502655 4.1734194756 764 1305031127.6206569672 0.0694867671 0.0485508909 0.1140159965 0.0165035905 0.0872320000 0.0092560000 0.0410650000 0.0000280000 0.0002950000 0.0206040000 10822716 96830484 1770151936 3.9271638393 4.0958833694 4.1750411987 765 1305031127.6546559334 0.0709768683 0.0485802059 0.1140159965 0.0164942144 0.1123990000 0.0112540000 0.0540080000 0.0003010000 0.0003530000 0.0372140000 10824902 96830484 1769017344 3.9268400669 4.0935215950 4.1762804985 766 1305031127.6871099472 0.0709986165 0.0486094727 0.1140159965 0.0164835425 0.1003930000 0.0094070000 0.0505120000 0.0000310000 0.0003030000 0.0209580000 10827120 96830484 1770778624 3.9282627106 4.0915999413 4.1767082214 767 1305031127.7232100964 0.0694617853 0.0486366596 0.1140159965 0.0164750850 0.1271870000 0.0112580000 0.0706170000 0.0003070000 0.0003650000 0.0266090000 10829370 96830484 1769672704 3.9279618263 4.0929765701 4.1773157120 768 1305031127.7546939850 0.0705664456 0.0486652140 0.1140159965 0.0164653577 0.1069930000 0.0110770000 0.0596970000 0.0000290000 0.0003000000 0.0204100000 10831524 96830484 1768255488 3.9272494316 4.0910615921 4.1783185005 769 1305031127.7876410484 0.0706405267 0.0486937905 0.1140159965 0.0164595888 0.1292870000 0.0095300000 0.0709050000 0.0003020000 0.0002800000 0.0391880000 10833774 96830484 1769951232 3.9262983799 4.0891232491 4.1780662537 770 1305031127.8201279640 0.0691289902 0.0487203297 0.1140159965 0.0164506273 0.1024260000 0.0110820000 0.0482240000 0.0000980000 0.0002990000 0.0210560000 10835928 96830484 1768509440 3.9259164333 4.0898637772 4.1778507233 771 1305031127.8551321030 0.0690571070 0.0487467068 0.1140159965 0.0164399751 0.1272280000 0.0093150000 0.0708720000 0.0003070000 0.0005280000 0.0263420000 10838146 96830484 1770172416 3.9260318279 4.0893054008 4.1781487465 772 1305031127.8871219158 0.0694627091 0.0487735410 0.1140159965 0.0164305454 0.1104840000 0.0114760000 0.0702280000 0.0000280000 0.0003120000 0.0194790000 10840364 96830484 1768890368 3.9253263474 4.0877614021 4.1782584190 773 1305031127.9225599766 0.0691109449 0.0487998508 0.1140159965 0.0164222705 0.1277320000 0.0096440000 0.0706370000 0.0002900000 0.0003370000 0.0377710000 10842614 96830484 1770463232 3.9235663414 4.0880670547 4.1785855293 774 1305031127.9550879002 0.0684727952 0.0488252680 0.1140159965 0.0164129111 0.1225310000 0.0111980000 0.0709480000 0.0000250000 0.0002860000 0.0209330000 10844800 96830484 1769381888 3.9250974655 4.0884509087 4.1797504425 775 1305031127.9870929718 0.0680566281 0.0488500827 0.1140159965 0.0164024838 0.1266550000 0.0098240000 0.0701650000 0.0005130000 0.0002810000 0.0264630000 10846986 96830484 1771208704 3.9252438545 4.0878500938 4.1812143326 776 1305031128.0217759609 0.0678090453 0.0488745143 0.1140159965 0.0163949974 0.1091600000 0.0112900000 0.0647610000 0.0000250000 0.0002900000 0.0206490000 10849236 96830484 1770307584 3.9249913692 4.0877661705 4.1830611229 777 1305031128.0557179451 0.0680764169 0.0488992272 0.1140159965 0.0163874611 0.1127450000 0.0114690000 0.0541400000 0.0002860000 0.0002650000 0.0374650000 10851422 96830484 1768763392 3.9247446060 4.0864439011 4.1853466034 778 1305031128.0872058868 0.0700526237 0.0489264166 0.1140159965 0.0163788769 0.0990820000 0.0095300000 0.0500470000 0.0000290000 0.0003080000 0.0208980000 10853608 96830484 1770696704 3.9247446060 4.0832381248 4.1872348785 779 1305031128.1247460842 0.0698977932 0.0489533375 0.1140159965 0.0163695233 0.1259180000 0.0112100000 0.0647260000 0.0003720000 0.0002740000 0.0264450000 10855890 96830484 1769398272 3.9254865646 4.0825295448 4.1886115074 780 1305031128.1577820778 0.0698978379 0.0489801895 0.1140159965 0.0163604800 0.0884020000 0.0095320000 0.0424570000 0.0000300000 0.0003190000 0.0208580000 10858108 96830484 1771208704 3.9272007942 4.0816349983 4.1905198097 781 1305031128.1872210503 0.0712285042 0.0490086764 0.1140159965 0.0163535748 0.1632780000 0.0112460000 0.0790230000 0.0000610000 0.0000530000 0.0409140000 10860230 96830484 1770016768 3.9271423817 4.0788946152 4.1912374496 782 1305031128.2254419327 0.0700814128 0.0490356236 0.1140159965 0.0163483095 0.1289260000 0.0121580000 0.0753030000 0.0000970000 0.0003200000 0.0209620000 10862512 96830484 1768673280 3.9269938469 4.0794358253 4.1914381981 783 1305031128.2560069561 0.0693868175 0.0490616150 0.1140159965 0.0163381275 0.0895220000 0.0095860000 0.0412640000 0.0010130000 0.0002710000 0.0265420000 10864666 96830484 1770295296 3.9268226624 4.0797338486 4.1922006607 784 1305031128.2912750244 0.0703815445 0.0490888087 0.1140159965 0.0163311870 0.1074910000 0.0111970000 0.0648990000 0.0000250000 0.0002910000 0.0199510000 10866916 96830484 1769635840 3.9266109467 4.0780267715 4.1925702095 785 1305031128.3241701126 0.0695883706 0.0491149228 0.1140159965 0.0163215176 0.1290400000 0.0110100000 0.0706310000 0.0002910000 0.0003440000 0.0371750000 10869102 96830484 1767899136 3.9282834530 4.0781245232 4.1925077438 786 1305031128.3552060127 0.0691598132 0.0491404252 0.1140159965 0.0163120033 0.1030910000 0.0096490000 0.0600810000 0.0000260000 0.0003510000 0.0201570000 10871288 96830484 1769558016 3.9272851944 4.0782189369 4.1924967766 787 1305031128.3913969994 0.0693783611 0.0491661405 0.1140159965 0.0163017970 0.1255490000 0.0113390000 0.0699440000 0.0002910000 0.0002700000 0.0258140000 10873538 96830484 1768153088 3.9255862236 4.0772385597 4.1924085617 788 1305031128.4236090183 0.0697654039 0.0491922817 0.1140159965 0.0162915761 0.1084180000 0.0090070000 0.0698780000 0.0000280000 0.0002880000 0.0197730000 10875724 96830484 1769803776 3.9250926971 4.0760478973 4.1922993660 789 1305031128.4554989338 0.0685784966 0.0492168523 0.1140159965 0.0162832334 0.1076230000 0.0112290000 0.0487880000 0.0002990000 0.0002700000 0.0373670000 10877910 96830484 1768153088 3.9243052006 4.0766415596 4.1918983459 790 1305031128.4895229340 0.0691090077 0.0492420323 0.1140159965 0.0162734681 0.1205130000 0.0094430000 0.0717660000 0.0000290000 0.0003830000 0.0210110000 10880160 96830484 1769930752 3.9240550995 4.0753731728 4.1921529770 791 1305031128.5236039162 0.0686473027 0.0492665649 0.1140159965 0.0162633923 0.1047250000 0.0111220000 0.0416030000 0.0010600000 0.0002720000 0.0266840000 10882346 96830484 1768169472 3.9241521358 4.0747895241 4.1919836998 792 1305031128.5556390285 0.0683581457 0.0492906704 0.1140159965 0.0162548423 0.0877390000 0.0088590000 0.0359920000 0.0000290000 0.0003640000 0.0217250000 10884532 96830484 1769820160 3.9255454540 4.0741047859 4.1919512749 793 1305031128.5914599895 0.0691612810 0.0493157279 0.1140159965 0.0162454677 0.1689640000 0.0111270000 0.0871710000 0.0000600000 0.0000530000 0.0410090000 10886782 96830484 1768407040 3.9234485626 4.0724453926 4.1916537285 794 1305031128.6233680248 0.0689817220 0.0493404962 0.1140159965 0.0162359448 0.1061930000 0.0092670000 0.0651220000 0.0000270000 0.0002830000 0.0199610000 10888968 96830484 1770201088 3.9246532917 4.0714960098 4.1913685799 795 1305031128.6555540562 0.0679841489 0.0493639473 0.1140159965 0.0162277485 0.1253740000 0.0113160000 0.0702860000 0.0002920000 0.0002680000 0.0258040000 10891154 96830484 1768771584 3.9248638153 4.0718436241 4.1909275055 796 1305031128.6904489994 0.0677223727 0.0493870106 0.1140159965 0.0162184745 0.1085050000 0.0093570000 0.0697020000 0.0000270000 0.0003670000 0.0194810000 10893404 96830484 1770303488 3.9246284962 4.0716137886 4.1906185150 797 1305031128.7229759693 0.0675925314 0.0494098532 0.1140159965 0.0162091871 0.1313610000 0.0111610000 0.0697840000 0.0003040000 0.0002740000 0.0402370000 10895590 96830484 1769390080 3.9242062569 4.0710611343 4.1901860237 798 1305031128.7546460629 0.0666644573 0.0494314755 0.1140159965 0.0162005392 0.1195340000 0.0092200000 0.0733040000 0.0000290000 0.0002990000 0.0204700000 10897776 96830484 1770811392 3.9235911369 4.0715827942 4.1895403862 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-19 03:30:52 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019025257 0.0019025257 0.0019025257 nan 0.2080690000 0.0177980000 0.0171920000 0.0001240000 0.0000120000 0.1372210000 15497082 96830484 1774424064 4.0000000000 4.0000000000 4.0000000000 2 1311867718.6768438816 0.0021839470 0.0020432363 0.0021839470 0.0015734782 0.0907160000 0.0237960000 0.0171100000 0.0000590000 0.0000040000 0.0389520000 25985332 96830484 1771900928 4.0000000000 4.0000000000 4.0000000000 3 1311867718.7114279270 0.0026191149 0.0022351959 0.0026191149 0.0052681777 0.0777800000 0.0172320000 0.0177040000 0.0000690000 0.0000040000 0.0317390000 25987874 96830484 1770885120 4.0000000000 4.0000000000 4.0000000000 4 1311867718.7410299778 0.0032201277 0.0024814288 0.0032201277 0.0047920722 0.0894710000 0.0159070000 0.0109560000 0.0000620000 0.0000880000 0.0560540000 25990344 96830484 1770668032 4.0000000000 4.0000000000 4.0000000000 5 1311867718.7767970562 0.0102618802 0.0040375191 0.0102618802 0.0093908740 0.2044910000 0.0107230000 0.1007330000 0.0003590000 0.0002670000 0.0745740000 25992914 96830484 1769504768 3.9892063141 3.9964056015 4.0032463074 6 1311867718.8094089031 0.0111374026 0.0052208330 0.0111374026 0.0088666867 0.1205480000 0.0109400000 0.0679720000 0.0000210000 0.0003110000 0.0347730000 25995756 96830484 1768480768 3.9877436161 3.9977455139 4.0040683746 7 1311867718.8408079147 0.0115064383 0.0061187766 0.0115064383 0.0081073943 0.1339470000 0.0092730000 0.0701090000 0.0003570000 0.0003010000 0.0419840000 25997910 96830484 1770123264 3.9869406223 3.9982502460 4.0042495728 8 1311867718.8767778873 0.0151337860 0.0072456528 0.0151337860 0.0077067087 0.0992190000 0.0113600000 0.0456370000 0.0000210000 0.0004230000 0.0356340000 26000160 96830484 1766948864 3.9833176136 3.9974684715 4.0047245026 9 1311867718.9088680744 0.0145941861 0.0080621565 0.0151337860 0.0072399251 0.1549070000 0.0102150000 0.0715190000 0.0003140000 0.0004930000 0.0660770000 26002954 96830484 1767731200 3.9835429192 3.9977228642 4.0048470497 10 1311867718.9438331127 0.0158720519 0.0088431460 0.0158720519 0.0068827351 0.1346670000 0.0094460000 0.0685680000 0.0000240000 0.0003850000 0.0360410000 26006516 96830484 1766465536 3.9821381569 3.9979324341 4.0057210922 11 1311867718.9784109592 0.0143935960 0.0093477324 0.0158720519 0.0067737003 0.1374590000 0.0092000000 0.0703800000 0.0002820000 0.0002940000 0.0416370000 26008766 96830484 1767964672 3.9839572906 3.9964573383 4.0056304932 12 1311867719.0091300011 0.0181231536 0.0100790175 0.0181231536 0.0067897077 0.1204980000 0.0094470000 0.0687810000 0.0000220000 0.0002830000 0.0351690000 26010888 96830484 1769762816 3.9798867702 3.9964544773 4.0065989494 13 1311867719.0441620350 0.0167894252 0.0105952027 0.0181231536 0.0065165275 0.1533470000 0.0111550000 0.0704600000 0.0003560000 0.0002750000 0.0648390000 26013138 96830484 1768742912 3.9810168743 3.9964642525 4.0068097115 14 1311867719.0776190758 0.0181547422 0.0111351698 0.0181547422 0.0063245432 0.1213250000 0.0095090000 0.0686340000 0.0000240000 0.0003690000 0.0358660000 26015356 96830484 1770250240 3.9797084332 3.9957439899 4.0073599815 15 1311867719.1086950302 0.0170223452 0.0115276482 0.0181547422 0.0061269012 0.1368910000 0.0113360000 0.0694840000 0.0003670000 0.0002800000 0.0407430000 26017542 96830484 1768878080 3.9809286594 3.9950649738 4.0075216293 16 1311867719.1437010765 0.0180021338 0.0119323035 0.0181547422 0.0059799049 0.0970290000 0.0098180000 0.0412240000 0.0000250000 0.0010960000 0.0348710000 26019760 96830484 1770614784 3.9795091152 3.9950249195 4.0081753731 17 1311867719.1810290813 0.0160394553 0.0121739007 0.0181547422 0.0059186263 0.1295700000 0.0112890000 0.0471320000 0.0003150000 0.0002740000 0.0640020000 26023290 96830484 1769271296 3.9816782475 3.9940738678 4.0082120895 18 1311867719.2127099037 0.0171447918 0.0124500613 0.0181547422 0.0057694990 0.1258250000 0.0113180000 0.0678770000 0.0000240000 0.0002940000 0.0344380000 26028100 96830484 1767862272 3.9804043770 3.9934437275 4.0087151527 19 1311867719.2412090302 0.0176467691 0.0127235722 0.0181547422 0.0056946464 0.1142760000 0.0095070000 0.0412440000 0.0011450000 0.0002970000 0.0404950000 26030222 96830484 1769472000 3.9793758392 3.9936635494 4.0092039108 20 1311867719.2779469490 0.0180098470 0.0129878860 0.0181547422 0.0058464799 0.1219600000 0.0117340000 0.0699040000 0.0000270000 0.0002910000 0.0335840000 26032440 96830484 1768124416 3.9786188602 3.9924759865 4.0094304085 21 1311867719.3104898930 0.0165103208 0.0131556210 0.0181547422 0.0057565055 0.1476110000 0.0095380000 0.0685880000 0.0003310000 0.0002810000 0.0624910000 26034658 96830484 1769852928 3.9797255993 3.9931633472 4.0097088814 22 1311867719.3413150311 0.0174168497 0.0133493132 0.0181547422 0.0056720951 0.1416270000 0.0115160000 0.0793810000 0.0000240000 0.0003490000 0.0336860000 26036844 96830484 1768488960 3.9786918163 3.9920165539 4.0100550652 23 1311867719.3772718906 0.0166156981 0.0134913299 0.0181547422 0.0055584216 0.1357760000 0.0093310000 0.0686370000 0.0003250000 0.0002740000 0.0396900000 26039062 96830484 1770106880 3.9793159962 3.9914216995 4.0097732544 24 1311867719.4105761051 0.0179588329 0.0136774759 0.0181547422 0.0055088663 0.1185020000 0.0113030000 0.0567690000 0.0000240000 0.0002760000 0.0345660000 26041280 96830484 1768742912 3.9776437283 3.9909567833 4.0101919174 25 1311867719.4427709579 0.0165197328 0.0137911662 0.0181547422 0.0055178861 0.1557100000 0.0091080000 0.0681780000 0.0015870000 0.0002740000 0.0589940000 26043498 96830484 1770487808 3.9794671535 3.9902577400 4.0101275444 26 1311867719.4787840843 0.0194290206 0.0140080067 0.0194290206 0.0054424079 0.1198760000 0.0113060000 0.0634250000 0.0000270000 0.0003630000 0.0342830000 26045716 96830484 1769144320 3.9766891003 3.9880363941 4.0103063583 27 1311867719.5104370117 0.0188076980 0.0141857731 0.0194290206 0.0054550441 0.1354780000 0.0109580000 0.0692790000 0.0003560000 0.0002710000 0.0401150000 26047902 96830484 1767751680 3.9772105217 3.9879314899 4.0100855827 28 1311867719.5449650288 0.0179877710 0.0143215587 0.0194290206 0.0054325974 0.1163070000 0.0093030000 0.0588800000 0.0000280000 0.0003500000 0.0340100000 26050120 96830484 1769345024 3.9765305519 3.9888217449 4.0108056068 29 1311867719.5771939754 0.0186438337 0.0144706027 0.0194290206 0.0054078413 0.1568840000 0.0107510000 0.0648450000 0.0003120000 0.0002650000 0.0630190000 26052338 96830484 1767989248 3.9762649536 3.9870550632 4.0106959343 30 1311867719.6112511158 0.0192630887 0.0146303522 0.0194290206 0.0053815141 0.0972100000 0.0092860000 0.0406270000 0.0000250000 0.0003830000 0.0341650000 26054556 96830484 1769725952 3.9751369953 3.9867448807 4.0111241341 31 1311867719.6421909332 0.0165311415 0.0146916680 0.0194290206 0.0053045550 0.1379250000 0.0112960000 0.0683160000 0.0003030000 0.0003880000 0.0404000000 26056710 96830484 1768378368 3.9774715900 3.9876356125 4.0113267899 32 1311867719.6770479679 0.0174132716 0.0147767181 0.0194290206 0.0052366379 0.1183580000 0.0092890000 0.0676460000 0.0000320000 0.0002960000 0.0337500000 26058960 96830484 1769979904 3.9768066406 3.9865071774 4.0118932724 33 1311867719.7107939720 0.0176968332 0.0148652064 0.0194290206 0.0051696920 0.1500930000 0.0113410000 0.0683110000 0.0003560000 0.0002780000 0.0633130000 26063706 96830484 1768615936 3.9759168625 3.9868388176 4.0125799179 34 1311867719.7442650795 0.0172630697 0.0149357318 0.0194290206 0.0051235255 0.1236530000 0.0094520000 0.0674910000 0.0000280000 0.0002930000 0.0341550000 26071140 96830484 1770352640 3.9756813049 3.9876880646 4.0134902000 35 1311867719.7861878872 0.0182197317 0.0150295604 0.0194290206 0.0050549753 0.1377660000 0.0112620000 0.0707270000 0.0002920000 0.0002750000 0.0401250000 26073518 96830484 1769009152 3.9749033451 3.9867806435 4.0141005516 36 1311867719.8099169731 0.0192591958 0.0151470503 0.0194290206 0.0050014079 0.1191730000 0.0106710000 0.0694410000 0.0000240000 0.0003570000 0.0321240000 26075544 96830484 1767616512 3.9736571312 3.9861969948 4.0145783424 37 1311867719.8454990387 0.0191344712 0.0152548184 0.0194290206 0.0049936024 0.1478650000 0.0096130000 0.0681280000 0.0002900000 0.0002630000 0.0631060000 26077794 96830484 1769209856 3.9745717049 3.9850063324 4.0145049095 38 1311867719.8771090508 0.0189708062 0.0153526075 0.0194290206 0.0049302105 0.1254760000 0.0115140000 0.0686320000 0.0000930000 0.0002860000 0.0346530000 26079980 96830484 1767854080 3.9743523598 3.9848647118 4.0147600174 39 1311867719.9114089012 0.0183653478 0.0154298573 0.0194290206 0.0049380247 0.1351910000 0.0096150000 0.0698880000 0.0003610000 0.0002740000 0.0400770000 26082230 96830484 1769590784 3.9738702774 3.9853909016 4.0152783394 40 1311867719.9461970329 0.0210905932 0.0155713757 0.0210905932 0.0049234038 0.1187760000 0.0111740000 0.0591450000 0.0000270000 0.0004560000 0.0343790000 26084448 96830484 1768243200 3.9716222286 3.9834170341 4.0158801079 41 1311867719.9807810783 0.0207995810 0.0156988929 0.0210905932 0.0048739927 0.1510120000 0.0093230000 0.0705650000 0.0003610000 0.0002700000 0.0640710000 26086666 96830484 1769877504 3.9724361897 3.9824569225 4.0158910751 42 1311867720.0117020607 0.0209273808 0.0158233807 0.0210905932 0.0048981960 0.1073150000 0.0117110000 0.0525450000 0.0000250000 0.0002900000 0.0346360000 26088852 96830484 1768247296 3.9701874256 3.9839458466 4.0166673660 43 1311867720.0452380180 0.0212999750 0.0159507434 0.0212999750 0.0048678572 0.1366890000 0.0097310000 0.0821270000 0.0000810000 0.0000540000 0.0381080000 26091038 96830484 1767456768 3.9695506096 3.9833881855 4.0168952942 44 1311867720.0772819519 0.0179723706 0.0159966894 0.0212999750 0.0048537084 0.1145250000 0.0096430000 0.0567130000 0.0000270000 0.0003770000 0.0348620000 26093256 96830484 1766187008 3.9735324383 3.9841971397 4.0174207687 45 1311867720.1172130108 0.0163765587 0.0160051310 0.0212999750 0.0048314414 0.1499800000 0.0091680000 0.0699940000 0.0003030000 0.0004610000 0.0634430000 26095570 96830484 1767813120 3.9765324593 3.9841699600 4.0178771019 46 1311867720.1451559067 0.0172947701 0.0160331666 0.0212999750 0.0047815858 0.1133050000 0.0096250000 0.0686850000 0.0000260000 0.0002980000 0.0283240000 26097660 96830484 1769480192 3.9754595757 3.9837982655 4.0184335709 47 1311867720.1781630516 0.0153367873 0.0160183500 0.0212999750 0.0047393645 0.1299560000 0.0111780000 0.0681830000 0.0003830000 0.0002790000 0.0411470000 26099846 96830484 1768488960 3.9774396420 3.9851977825 4.0189123154 48 1311867720.2094950676 0.0165647212 0.0160297328 0.0212999750 0.0047346124 0.1153850000 0.0095130000 0.0538860000 0.0000280000 0.0003010000 0.0348590000 26102032 96830484 1770115072 3.9740412235 3.9859323502 4.0197997093 49 1311867720.2421469688 0.0136165991 0.0159804851 0.0212999750 0.0047346781 0.1524980000 0.0112500000 0.0702070000 0.0003320000 0.0003560000 0.0635920000 26104250 96830484 1768988672 3.9784619808 3.9870643616 4.0200076103 50 1311867720.2770779133 0.0157530811 0.0159759371 0.0212999750 0.0047302274 0.1230790000 0.0098270000 0.0694370000 0.0000270000 0.0002960000 0.0345980000 26106468 96830484 1770749952 3.9759871960 3.9861102104 4.0211915970 51 1311867720.3094570637 0.0125350086 0.0159084679 0.0212999750 0.0047063578 0.1181270000 0.0112900000 0.0585160000 0.0003300000 0.0003610000 0.0404970000 26108654 96830484 1769738240 3.9797873497 3.9883227348 4.0219106674 52 1311867720.3430728912 0.0129976859 0.0158524913 0.0212999750 0.0047430027 0.1184510000 0.0098570000 0.0701070000 0.0000260000 0.0003330000 0.0317260000 26110872 96830484 1771421696 3.9793474674 3.9888434410 4.0231785774 53 1311867720.3779859543 0.0138159310 0.0158140656 0.0212999750 0.0047922786 0.1354070000 0.0116260000 0.0524530000 0.0003080000 0.0003420000 0.0633700000 26113058 96830484 1770369024 3.9818134308 3.9869794846 4.0234570503 54 1311867720.4096798897 0.0142540680 0.0157851768 0.0212999750 0.0048646610 0.1343930000 0.0116710000 0.0687170000 0.0000260000 0.0002880000 0.0341930000 26115244 96830484 1767985152 3.9814267159 3.9865858555 4.0241050720 55 1311867720.4461109638 0.0135648465 0.0157448071 0.0212999750 0.0048286426 0.1362530000 0.0096830000 0.0701600000 0.0002950000 0.0003460000 0.0398210000 26117526 96830484 1769771008 3.9825265408 3.9874124527 4.0244746208 56 1311867720.4799289703 0.0137727754 0.0157095923 0.0212999750 0.0048416036 0.1203260000 0.0116830000 0.0700630000 0.0000260000 0.0002940000 0.0313910000 26119744 96830484 1767477248 3.9838981628 3.9872281551 4.0244665146 57 1311867720.5104389191 0.0135812648 0.0156722532 0.0212999750 0.0048990109 0.1319890000 0.0101400000 0.0345910000 0.0000900000 0.0000910000 0.0682840000 26121898 96830484 1769136128 3.9823200703 3.9867765903 4.0242810249 58 1311867720.5467319489 0.0141886557 0.0156466739 0.0212999750 0.0050132337 0.0993770000 0.0096910000 0.0471230000 0.0000280000 0.0006510000 0.0343840000 26124180 96830484 1770786816 3.9856870174 3.9875600338 4.0246086121 59 1311867720.5793280602 0.0140336454 0.0156193345 0.0212999750 0.0050615950 0.1160160000 0.0114800000 0.0465780000 0.0003610000 0.0002690000 0.0407130000 26126366 96830484 1769734144 3.9835994244 3.9867300987 4.0251350403 60 1311867720.6121249199 0.0149037791 0.0156074086 0.0212999750 0.0050417619 0.1159840000 0.0098070000 0.0535770000 0.0000260000 0.0003910000 0.0351630000 26128552 96830484 1771384832 3.9845881462 3.9862725735 4.0251526833 61 1311867720.6463210583 0.0150370654 0.0155980587 0.0212999750 0.0050281986 0.1498880000 0.0114440000 0.0683670000 0.0002810000 0.0003740000 0.0625460000 26130802 96830484 1770278912 3.9844522476 3.9864571095 4.0256285667 62 1311867720.6798269749 0.0167943891 0.0156173543 0.0212999750 0.0050267363 0.1277960000 0.0122810000 0.0683730000 0.0000250000 0.0003320000 0.0341990000 26132956 96830484 1767985152 3.9873771667 3.9862909317 4.0256137848 63 1311867720.7102439404 0.0170160849 0.0156395564 0.0212999750 0.0049919412 0.1340270000 0.0099720000 0.0692730000 0.0003520000 0.0002970000 0.0418860000 26135142 96830484 1769771008 3.9858238697 3.9851644039 4.0256857872 64 1311867720.7451629639 0.0170575436 0.0156617124 0.0212999750 0.0049939705 0.1161690000 0.0115750000 0.0525040000 0.0000270000 0.0002930000 0.0343360000 26137360 96830484 1767350272 3.9861197472 3.9857151508 4.0256390572 65 1311867720.7790179253 0.0583623722 0.0163186457 0.0583623722 0.0061478687 0.1374520000 0.0095600000 0.0591390000 0.0003590000 0.0002720000 0.0611710000 26144730 96830484 1768988672 4.0317239761 3.9882154465 4.0336341858 66 1311867720.8115909100 0.0588523746 0.0169630961 0.0588523746 0.0061013289 0.1156940000 0.0095900000 0.0586030000 0.0000280000 0.0003810000 0.0335140000 26157412 96830484 1770913792 4.0313930511 3.9874618053 4.0340209007 67 1311867720.8467299938 0.0620981604 0.0176367538 0.0620981604 0.0060691784 0.1383690000 0.0111170000 0.0741130000 0.0002900000 0.0003420000 0.0391300000 26159662 96830484 1770008576 4.0343694687 3.9882056713 4.0344204903 68 1311867720.8813319206 0.0593771227 0.0182505827 0.0620981604 0.0061032137 0.1165140000 0.0116300000 0.0570660000 0.0000250000 0.0002810000 0.0335030000 26161880 96830484 1767952384 4.0311841965 3.9887735844 4.0350012779 69 1311867720.9149661064 0.0605550818 0.0188636914 0.0620981604 0.0060681201 0.1455820000 0.0095770000 0.0676410000 0.0002870000 0.0002680000 0.0610880000 26164066 96830484 1769734144 4.0316143036 3.9873104095 4.0352892876 70 1311867720.9500010014 0.0603486523 0.0194563337 0.0620981604 0.0060247028 0.1087900000 0.0120670000 0.0564750000 0.0000290000 0.0003030000 0.0328510000 26166284 96830484 1767460864 4.0310673714 3.9876811504 4.0358071327 71 1311867720.9797990322 0.0629412979 0.0200687980 0.0629412979 0.0059962532 0.1333040000 0.0097780000 0.0673080000 0.0002830000 0.0002590000 0.0399700000 26168406 96830484 1769115648 4.0336823463 3.9881138802 4.0357127190 72 1311867721.0093889236 0.0638582334 0.0206769846 0.0638582334 0.0059551575 0.0982730000 0.0096780000 0.0441610000 0.0000250000 0.0003950000 0.0338680000 26170560 96830484 1770770432 4.0344047546 3.9879655838 4.0359988213 73 1311867721.0478379726 0.0626026168 0.0212513083 0.0638582334 0.0059203183 0.1493780000 0.0114940000 0.0677860000 0.0003030000 0.0002860000 0.0622070000 26172874 96830484 1769734144 4.0327491760 3.9879574776 4.0359840393 74 1311867721.0794439316 0.0641218275 0.0218306397 0.0641218275 0.0058883237 0.1250270000 0.0115060000 0.0681640000 0.0000260000 0.0002820000 0.0340070000 26175028 96830484 1768607744 4.0339713097 3.9873917103 4.0362048149 75 1311867721.1103579998 0.0595897511 0.0223340945 0.0641218275 0.0058841092 0.1350640000 0.0097280000 0.0671650000 0.0003540000 0.0002690000 0.0408570000 26177214 96830484 1770344448 4.0286865234 3.9869539738 4.0363845825 76 1311867721.1467890739 0.0622668229 0.0228595251 0.0641218275 0.0058839752 0.1206940000 0.0113370000 0.0686060000 0.0000260000 0.0003430000 0.0334430000 26179464 96830484 1768988672 4.0307283401 3.9866080284 4.0363440514 77 1311867721.1774179935 0.0621140599 0.0233693243 0.0641218275 0.0059313879 0.1481470000 0.0108750000 0.0672880000 0.0003210000 0.0003530000 0.0622290000 26181650 96830484 1767841792 4.0304870605 3.9862675667 4.0365509987 78 1311867721.2112360001 0.0608043633 0.0238492607 0.0641218275 0.0058980011 0.1054690000 0.0095030000 0.0579020000 0.0000270000 0.0002850000 0.0309120000 26183836 96830484 1769598976 4.0286803246 3.9862232208 4.0367469788 79 1311867721.2469010353 0.0648248717 0.0243679393 0.0648248717 0.0058878734 0.1352570000 0.0113020000 0.0674140000 0.0002960000 0.0002680000 0.0411570000 26186086 96830484 1768861696 4.0326972008 3.9859499931 4.0367012024 80 1311867721.2800450325 0.0631196722 0.0248523360 0.0648248717 0.0058512962 0.1144420000 0.0089390000 0.0532210000 0.0000280000 0.0003660000 0.0347980000 26188272 96830484 1770614784 4.0300402641 3.9849932194 4.0369405746 81 1311867721.3099579811 0.0675087124 0.0253789579 0.0675087124 0.0058516915 0.1506620000 0.0109370000 0.0688080000 0.0003570000 0.0002710000 0.0631260000 26190426 96830484 1769750528 4.0344562531 3.9851186275 4.0370759964 82 1311867721.3483059406 0.0668375269 0.0258845502 0.0675087124 0.0058374945 0.1069350000 0.0112660000 0.0391880000 0.0000270000 0.0004110000 0.0360450000 26192708 96830484 1765916672 4.0333280563 3.9852325916 4.0370111465 83 1311867721.3790040016 0.0667085052 0.0263764051 0.0675087124 0.0058077659 0.1350680000 0.0098130000 0.0693030000 0.0002940000 0.0003550000 0.0402860000 26194830 96830484 1767317504 4.0326137543 3.9851398468 4.0372200012 84 1311867721.4092550278 0.0661966354 0.0268504554 0.0675087124 0.0057822266 0.1216850000 0.0095200000 0.0713840000 0.0000260000 0.0002980000 0.0322240000 26196984 96830484 1765040128 4.0312747955 3.9846348763 4.0377478600 85 1311867721.4478130341 0.0691283494 0.0273478424 0.0691283494 0.0057553326 0.1678190000 0.0095100000 0.0713960000 0.0003000000 0.0002780000 0.0597370000 26199330 96830484 1764409344 4.0336546898 3.9842467308 4.0381827354 86 1311867721.4768960476 0.0704291016 0.0278487873 0.0704291016 0.0057226227 0.0989590000 0.0103390000 0.0395020000 0.0000090000 0.0000960000 0.0405500000 26201452 96830484 1764925440 4.0346422195 3.9845747948 4.0385074615 87 1311867721.5093359947 0.0704826415 0.0283388316 0.0704826415 0.0056982811 0.1373970000 0.0089830000 0.0799150000 0.0000590000 0.0000530000 0.0412920000 26203606 96830484 1765052416 4.0342602730 3.9842588902 4.0383834839 88 1311867721.5451331139 0.0681211576 0.0287909035 0.0704826415 0.0056872466 0.1499290000 0.0088100000 0.0857830000 0.0000280000 0.0003090000 0.0354550000 26205824 96830484 1764036608 4.0308570862 3.9832592010 4.0387029648 89 1311867721.5769670010 0.0674590990 0.0292253776 0.0704826415 0.0056714061 0.1585390000 0.0092130000 0.0694820000 0.0003080000 0.0003110000 0.0675300000 26207946 96830484 1765662720 4.0299878120 3.9836428165 4.0385808945 90 1311867721.6129651070 0.0689830482 0.0296671295 0.0704826415 0.0056744557 0.1196510000 0.0091370000 0.0701460000 0.0000290000 0.0003150000 0.0331450000 26210164 96830484 1767329792 4.0309758186 3.9832911491 4.0387005806 91 1311867721.6496050358 0.0680750012 0.0300891940 0.0704826415 0.0056948745 0.1355720000 0.0095140000 0.0695910000 0.0003360000 0.0003440000 0.0415430000 26212446 96830484 1769091072 4.0292072296 3.9820065498 4.0384521484 92 1311867721.6800351143 0.0683223456 0.0305047717 0.0704826415 0.0056962674 0.1367970000 0.0107680000 0.0692740000 0.0000280000 0.0003810000 0.0355390000 26214600 96830484 1768079360 4.0295248032 3.9836673737 4.0386805534 93 1311867721.7162289619 0.0681782514 0.0309098629 0.0704826415 0.0056914167 0.1503720000 0.0092120000 0.0692280000 0.0003770000 0.0002800000 0.0643130000 26216882 96830484 1769709568 4.0291576385 3.9834637642 4.0388836861 94 1311867721.7467949390 0.0699489489 0.0313251724 0.0704826415 0.0057174801 0.1249630000 0.0117380000 0.0632920000 0.0000290000 0.0003020000 0.0352330000 26219036 96830484 1768591360 4.0296149254 3.9810171127 4.0388216972 95 1311867721.7787001133 0.0724346042 0.0317579032 0.0724346042 0.0056983016 0.0984230000 0.0092810000 0.0406870000 0.0002270000 0.0004860000 0.0405610000 26221222 96830484 1770364928 4.0324144363 3.9823589325 4.0392303467 96 1311867721.8154830933 0.0714762732 0.0321716362 0.0724346042 0.0056707307 0.1175660000 0.0116370000 0.0625960000 0.0000280000 0.0003050000 0.0357890000 26223472 96830484 1769099264 4.0306992531 3.9819428921 4.0392537117 97 1311867721.8485159874 0.0724783614 0.0325871695 0.0724783614 0.0056464574 0.1352100000 0.0108990000 0.0507230000 0.0003750000 0.0002760000 0.0655010000 26225690 96830484 1767825408 4.0309138298 3.9807276726 4.0391640663 98 1311867721.8778810501 0.0706475154 0.0329755404 0.0724783614 0.0056305825 0.1191720000 0.0096380000 0.0691820000 0.0000270000 0.0003020000 0.0330530000 26227844 96830484 1769472000 4.0288505554 3.9817559719 4.0391159058 99 1311867721.9146931171 0.0703399256 0.0333529584 0.0724783614 0.0056066054 0.0973990000 0.0114220000 0.0344690000 0.0000980000 0.0000870000 0.0439080000 26229966 96830484 1764515840 4.0278668404 3.9808592796 4.0388493538 100 1311867721.9467151165 0.0709024817 0.0337284536 0.0724783614 0.0055801583 0.1339900000 0.0100070000 0.0817600000 0.0000880000 0.0003010000 0.0345600000 26232152 96830484 1766289408 4.0278158188 3.9801523685 4.0387740135 101 1311867721.9773728848 0.0695544109 0.0340831661 0.0724783614 0.0055836877 0.1341770000 0.0096600000 0.0513310000 0.0003850000 0.0002840000 0.0654840000 26234338 96830484 1767940096 4.0262851715 3.9804728031 4.0385799408 102 1311867722.0166850090 0.0723202825 0.0344580398 0.0724783614 0.0056237307 0.1197550000 0.0092250000 0.0671870000 0.0000270000 0.0003050000 0.0358000000 26236556 96830484 1769738240 4.0287623405 3.9800059795 4.0384631157 103 1311867722.0475180149 0.0719993636 0.0348225186 0.0724783614 0.0056340588 0.1155660000 0.0117570000 0.0341920000 0.0000960000 0.0000860000 0.0452410000 26238646 96830484 1767305216 4.0282831192 3.9795539379 4.0381522179 104 1311867722.0800709724 0.0734302923 0.0351937472 0.0734302923 0.0056202992 0.1352250000 0.0098330000 0.0719190000 0.0000060000 0.0000600000 0.0295250000 26240864 96830484 1767313408 4.0293679237 3.9791059494 4.0381655693 105 1311867722.1161251068 0.0750826895 0.0355736419 0.0750826895 0.0055985049 0.1581540000 0.0093220000 0.0633040000 0.0005490000 0.0002790000 0.0666740000 26243114 96830484 1765806080 4.0301961899 3.9777686596 4.0381984711 106 1311867722.1479530334 0.0734939724 0.0359313809 0.0750826895 0.0056009609 0.1190790000 0.0092500000 0.0684100000 0.0000300000 0.0003740000 0.0338740000 26245268 96830484 1767542784 4.0276832581 3.9772822857 4.0381326675 107 1311867722.1798410416 0.0716640577 0.0362653311 0.0750826895 0.0055914214 0.1172290000 0.0093380000 0.0572600000 0.0003850000 0.0002770000 0.0428560000 26247454 96830484 1769193472 4.0257682800 3.9785931110 4.0379600525 108 1311867722.2146399021 0.0718272328 0.0365946080 0.0750826895 0.0055845144 0.1195840000 0.0112280000 0.0672430000 0.0000260000 0.0003050000 0.0333780000 26249704 96830484 1767837696 4.0250573158 3.9769103527 4.0380325317 109 1311867722.2469589710 0.0740310252 0.0369380614 0.0750826895 0.0055658947 0.1503060000 0.0093720000 0.0662440000 0.0003840000 0.0002710000 0.0665960000 26251890 96830484 1769574400 4.0273756981 3.9768679142 4.0380229950 110 1311867722.2780389786 0.0718603432 0.0372555367 0.0750826895 0.0055490745 0.1221120000 0.0111200000 0.0676340000 0.0000310000 0.0003750000 0.0354050000 26254076 96830484 1768566784 4.0250773430 3.9779167175 4.0380849838 111 1311867722.3154170513 0.0748131871 0.0375938939 0.0750826895 0.0055416693 0.1322890000 0.0095740000 0.0562390000 0.0003060000 0.0003450000 0.0432340000 26256326 96830484 1770209280 4.0275397301 3.9762306213 4.0384488106 112 1311867722.3488469124 0.0744558647 0.0379230186 0.0750826895 0.0055199603 0.1241850000 0.0120260000 0.0680570000 0.0000260000 0.0003020000 0.0344170000 26258512 96830484 1768964096 4.0265846252 3.9755434990 4.0384984016 113 1311867722.3777940273 0.0718543828 0.0382232962 0.0750826895 0.0055181340 0.1505830000 0.0093830000 0.0661490000 0.0003060000 0.0003400000 0.0671870000 26260666 96830484 1770463232 4.0243725777 3.9770014286 4.0379586220 114 1311867722.4150679111 0.0757782832 0.0385527259 0.0757782832 0.0055277445 0.1194710000 0.0115460000 0.0563440000 0.0000290000 0.0003110000 0.0370170000 26262820 96830484 1769099264 4.0275063515 3.9749224186 4.0387263298 115 1311867722.4467909336 0.0736099556 0.0388575714 0.0757782832 0.0055880128 0.1163310000 0.0112580000 0.0445080000 0.0003200000 0.0003560000 0.0437070000 26265006 96830484 1767706624 4.0244331360 3.9743113518 4.0387401581 116 1311867722.4777851105 0.0732209757 0.0391538076 0.0757782832 0.0055983344 0.1205010000 0.0093860000 0.0693370000 0.0000290000 0.0003080000 0.0342560000 26267160 96830484 1769463808 4.0240941048 3.9752962589 4.0389280319 117 1311867722.5147399902 0.0774714202 0.0394813086 0.0774714202 0.0055872099 0.1552510000 0.0115400000 0.0671110000 0.0003710000 0.0002770000 0.0683600000 26269378 96830484 1768464384 4.0282835960 3.9745528698 4.0396885872 118 1311867722.5469911098 0.0727098659 0.0397629065 0.0774714202 0.0056126061 0.1181580000 0.0092950000 0.0664830000 0.0000310000 0.0003050000 0.0347160000 26271564 96830484 1770209280 4.0224294662 3.9740889072 4.0393538475 119 1311867722.5802359581 0.0750337020 0.0400592997 0.0774714202 0.0056022658 0.1355040000 0.0117220000 0.0624110000 0.0003950000 0.0002770000 0.0439910000 26273750 96830484 1769091072 4.0248537064 3.9734611511 4.0394392014 120 1311867722.6146309376 0.0753346980 0.0403532614 0.0774714202 0.0055797072 0.1193460000 0.0106750000 0.0663470000 0.0000290000 0.0007020000 0.0340040000 26275968 96830484 1767944192 4.0249300003 3.9729695320 4.0394744873 121 1311867722.6560258865 0.0753040388 0.0406421108 0.0774714202 0.0055603545 0.1525320000 0.0094960000 0.0669300000 0.0004950000 0.0002750000 0.0679270000 26278314 96830484 1769701376 4.0244059563 3.9722740650 4.0395598412 122 1311867722.6778230667 0.0763084441 0.0409344578 0.0774714202 0.0055446526 0.1202100000 0.0112790000 0.0668190000 0.0000260000 0.0002980000 0.0341000000 26280372 96830484 1768599552 4.0251245499 3.9717543125 4.0399055481 123 1311867722.7252709866 0.0755622387 0.0412159845 0.0774714202 0.0055651515 0.1328130000 0.0093070000 0.0667360000 0.0003770000 0.0002820000 0.0444900000 26282782 96830484 1770336256 4.0238847733 3.9712414742 4.0396904945 124 1311867722.7449109554 0.0754760131 0.0414922750 0.0774714202 0.0055679438 0.1197370000 0.0111770000 0.0655760000 0.0000280000 0.0003800000 0.0350650000 26284744 96830484 1769234432 4.0238413811 3.9709947109 4.0391440392 125 1311867722.7770080566 0.0729168877 0.0417436719 0.0774714202 0.0056249515 0.1541720000 0.0110070000 0.0660140000 0.0003050000 0.0003480000 0.0687300000 26286962 96830484 1768325120 4.0205044746 3.9712367058 4.0389227867 126 1311867722.8162860870 0.0729997754 0.0419917362 0.0774714202 0.0056026992 0.1190000000 0.0093780000 0.0667400000 0.0000280000 0.0003770000 0.0350770000 26289212 96830484 1769955328 4.0204572678 3.9714043140 4.0390229225 127 1311867722.8466939926 0.0792112350 0.0422848032 0.0792112350 0.0056475953 0.1171080000 0.0115380000 0.0506780000 0.0003140000 0.0003510000 0.0452800000 26291366 96830484 1768853504 4.0256333351 3.9688332081 4.0406723022 128 1311867722.8819770813 0.0774205998 0.0425593016 0.0792112350 0.0056292521 0.1339250000 0.0095820000 0.0679750000 0.0000920000 0.0003080000 0.0387310000 26293616 96830484 1770590208 4.0226354599 3.9683611393 4.0409197807 129 1311867722.9150629044 0.0789450556 0.0428413617 0.0792112350 0.0056304457 0.1566470000 0.0112760000 0.0671670000 0.0003790000 0.0002810000 0.0697790000 26305946 96830484 1769472000 4.0246062279 3.9705841541 4.0416831970 130 1311867722.9485991001 0.0807027519 0.0431326031 0.0807027519 0.0056489209 0.1172840000 0.0108700000 0.0462430000 0.0000310000 0.0003910000 0.0389610000 26329188 96830484 1768452096 4.0249567032 3.9677088261 4.0422410965 131 1311867722.9821140766 0.0826493278 0.0434342575 0.0826493278 0.0056280012 0.1371840000 0.0091860000 0.0661560000 0.0003710000 0.0002770000 0.0451260000 26331374 96830484 1770209280 4.0256824493 3.9668180943 4.0440778732 132 1311867723.0147259235 0.0828013197 0.0437324928 0.0828013197 0.0056089074 0.1207480000 0.0112270000 0.0657470000 0.0000280000 0.0003030000 0.0357540000 26333560 96830484 1769091072 4.0267014503 3.9689846039 4.0440897942 133 1311867723.0460629463 0.0859017670 0.0440495551 0.0859017670 0.0056217272 0.1464020000 0.0114420000 0.0566890000 0.0003770000 0.0002780000 0.0698780000 26335714 96830484 1767944192 4.0280456543 3.9666035175 4.0457315445 134 1311867723.0845439434 0.0892426744 0.0443868171 0.0892426744 0.0056199661 0.1243060000 0.0091880000 0.0673740000 0.0000260000 0.0002800000 0.0383150000 26337996 96830484 1769721856 4.0310239792 3.9656612873 4.0461101532 135 1311867723.1140980721 0.0900465101 0.0447250371 0.0900465101 0.0056013997 0.1370490000 0.0112710000 0.0654540000 0.0006140000 0.0002980000 0.0448810000 26340150 96830484 1768464384 4.0311117172 3.9655635357 4.0469298363 136 1311867723.1505160332 0.0928428173 0.0450788443 0.0928428173 0.0055904540 0.1170300000 0.0092050000 0.0601620000 0.0000260000 0.0005250000 0.0384840000 26342400 96830484 1770082304 4.0326418877 3.9637959003 4.0478162766 137 1311867723.1811029911 0.0943776518 0.0454386896 0.0943776518 0.0055717144 0.1551850000 0.0114090000 0.0651760000 0.0002950000 0.0003490000 0.0701290000 26344554 96830484 1768964096 4.0330910683 3.9624009132 4.0482468605 138 1311867723.2201359272 0.0950688720 0.0457983286 0.0950688720 0.0055519353 0.0977690000 0.0091210000 0.0343510000 0.0000270000 0.0003020000 0.0410900000 26346836 96830484 1770590208 4.0334830284 3.9624280930 4.0483493805 139 1311867723.2486810684 0.0988344327 0.0461798833 0.0988344327 0.0055473760 0.1375360000 0.0117460000 0.0622740000 0.0003050000 0.0003550000 0.0463040000 26348958 96830484 1769345024 4.0368738174 3.9614522457 4.0490298271 140 1311867723.2846419811 0.0877287462 0.0464766609 0.0988344327 0.0055683913 0.0989540000 0.0114730000 0.0384460000 0.0000090000 0.0000930000 0.0411380000 26351208 96830484 1765163008 4.0247454643 3.9618635178 4.0454902649 141 1311867723.3132460117 0.0895809680 0.0467823652 0.0988344327 0.0055530327 0.1708880000 0.0100830000 0.0632170000 0.0003000000 0.0003580000 0.0769190000 26353330 96830484 1766969344 4.0261025429 3.9609150887 4.0459837914 142 1311867723.3499810696 0.0899336636 0.0470862476 0.0988344327 0.0055412750 0.1364210000 0.0092090000 0.0680130000 0.0000310000 0.0002980000 0.0403460000 26355612 96830484 1768574976 4.0257563591 3.9609110355 4.0465993881 143 1311867723.3822429180 0.0914562047 0.0473965270 0.0988344327 0.0055282729 0.1003890000 0.0091490000 0.0328320000 0.0001980000 0.0001910000 0.0503430000 26357830 96830484 1770336256 4.0272531509 3.9606907368 4.0467243195 144 1311867723.4193739891 0.0924464166 0.0477093735 0.0988344327 0.0055395673 0.1169080000 0.0114420000 0.0522680000 0.0000270000 0.0003180000 0.0401660000 26360080 96830484 1769218048 4.0277872086 3.9599568844 4.0479264259 145 1311867723.4455900192 0.0911379084 0.0480088806 0.0988344327 0.0055271116 0.1932290000 0.0108860000 0.0791570000 0.0000810000 0.0000550000 0.0756940000 26362170 96830484 1768198144 4.0266423225 3.9609081745 4.0472021103 146 1311867723.4825348854 0.0937434435 0.0483221310 0.0988344327 0.0055192936 0.0996090000 0.0099450000 0.0405860000 0.0000250000 0.0003580000 0.0397810000 26364452 96830484 1769844736 4.0279130936 3.9600479603 4.0485138893 147 1311867723.5147960186 0.0957856551 0.0486450122 0.0988344327 0.0055024631 0.1363500000 0.0116410000 0.0618280000 0.0003190000 0.0003580000 0.0464530000 26366606 96830484 1768837120 4.0294017792 3.9596705437 4.0493459702 148 1311867723.5451340675 0.0959996730 0.0489649761 0.0988344327 0.0054854242 0.0987200000 0.0093240000 0.0441160000 0.0000240000 0.0003800000 0.0371610000 26368792 96830484 1770479616 4.0289192200 3.9595983028 4.0497279167 149 1311867723.5809938908 0.0986760557 0.0492986075 0.0988344327 0.0054754171 0.1330930000 0.0114350000 0.0385660000 0.0002890000 0.0002700000 0.0747380000 26371042 96830484 1769472000 4.0307474136 3.9586157799 4.0506262779 150 1311867723.6132669449 0.1005403623 0.0496402192 0.1005403623 0.0054615342 0.1171410000 0.0109110000 0.0459300000 0.0000280000 0.0003130000 0.0406080000 26373260 96830484 1768341504 4.0327768326 3.9590573311 4.0509672165 151 1311867723.6453940868 0.0996110886 0.0499711521 0.1005403623 0.0054442582 0.1211550000 0.0093830000 0.0592740000 0.0003620000 0.0002720000 0.0442020000 26375414 96830484 1770098688 4.0323133469 3.9601960182 4.0501661301 152 1311867723.6809489727 0.1014421210 0.0503097769 0.1014421210 0.0054298446 0.1338290000 0.0115370000 0.0646870000 0.0000250000 0.0003450000 0.0410680000 26377664 96830484 1768996864 4.0332579613 3.9587168694 4.0508351326 153 1311867723.7130429745 0.1039372012 0.0506602829 0.1039372012 0.0054136945 0.1600290000 0.0109470000 0.0663110000 0.0002970000 0.0003520000 0.0739240000 26379850 96830484 1767960576 4.0351700783 3.9580836296 4.0519700050 154 1311867723.7471990585 0.1045558304 0.0510102540 0.1045558304 0.0053979450 0.1295090000 0.0094220000 0.0664560000 0.0000270000 0.0002830000 0.0403600000 26382068 96830484 1769701376 4.0359430313 3.9585101604 4.0515089035 155 1311867723.7809250355 0.1058973595 0.0513643644 0.1058973595 0.0053849830 0.1182800000 0.0114080000 0.0449770000 0.0003250000 0.0002790000 0.0481300000 26384286 96830484 1768599552 4.0364713669 3.9570856094 4.0512609482 156 1311867723.8157649040 0.1078942791 0.0517267356 0.1078942791 0.0053736179 0.0987380000 0.0093940000 0.0425380000 0.0000260000 0.0003790000 0.0388330000 26386504 96830484 1770336256 4.0380220413 3.9564790726 4.0510759354 157 1311867723.8468959332 0.1085747257 0.0520888247 0.1085747257 0.0053580437 0.1537670000 0.0115210000 0.0437410000 0.0003880000 0.0002820000 0.0773600000 26388690 96830484 1769218048 4.0396656990 3.9583523273 4.0503950119 158 1311867723.8826351166 0.1075404137 0.0524397842 0.1085747257 0.0053510939 0.1174990000 0.0116280000 0.0492720000 0.0000240000 0.0002910000 0.0413940000 26390908 96830484 1768198144 4.0377736092 3.9571201801 4.0496039391 159 1311867723.9172909260 0.1086381152 0.0527932328 0.1086381152 0.0053441434 0.0995860000 0.0092320000 0.0337490000 0.0001920000 0.0002120000 0.0485960000 26393062 96830484 1769828352 4.0389938354 3.9578106403 4.0498104095 160 1311867723.9490020275 0.1113909334 0.0531594684 0.1113909334 0.0053321782 0.1542970000 0.0111250000 0.0735160000 0.0000290000 0.0002950000 0.0549620000 26395216 96830484 1768583168 4.0420813560 3.9587640762 4.0503787994 161 1311867723.9839010239 0.1132869795 0.0535329312 0.1132869795 0.0053295560 0.1389710000 0.0113800000 0.0442580000 0.0003130000 0.0002770000 0.0751090000 26397466 96830484 1770209280 4.0430207253 3.9567968845 4.0506367683 162 1311867724.0132899284 0.1138642505 0.0539053468 0.1138642505 0.0053168120 0.1163820000 0.0113600000 0.0534790000 0.0000290000 0.0003030000 0.0422660000 26399588 96830484 1769091072 4.0436773300 3.9571585655 4.0507431030 163 1311867724.0475380421 0.1164713427 0.0542891872 0.1164713427 0.0053055957 0.1331740000 0.0110900000 0.0489380000 0.0003830000 0.0002720000 0.0493340000 26401838 96830484 1767817216 4.0464315414 3.9579370022 4.0517091751 164 1311867724.0824530125 0.1177881211 0.0546763758 0.1177881211 0.0052943333 0.1174440000 0.0100530000 0.0511960000 0.0000310000 0.0003020000 0.0423890000 26404056 96830484 1769447424 4.0469617844 3.9567904472 4.0523381233 165 1311867724.1132431030 0.1161629781 0.0550490219 0.1177881211 0.0052796260 0.1355490000 0.0110550000 0.0376640000 0.0000970000 0.0000870000 0.0786020000 26406242 96830484 1768345600 4.0457606316 3.9578156471 4.0510783195 166 1311867724.1547191143 0.1196969301 0.0554384672 0.1196969301 0.0052796140 0.1177210000 0.0096130000 0.0462130000 0.0000300000 0.0003180000 0.0425570000 26408588 96830484 1770082304 4.0486192703 3.9572916031 4.0528430939 167 1311867724.1810541153 0.1213366017 0.0558330668 0.1213366017 0.0052686099 0.1216310000 0.0113530000 0.0547410000 0.0002990000 0.0002800000 0.0467080000 26410678 96830484 1768828928 4.0496110916 3.9565272331 4.0539298058 168 1311867724.2139430046 0.1222818494 0.0562285952 0.1222818494 0.0052558672 0.1154280000 0.0096120000 0.0551180000 0.0000260000 0.0002920000 0.0425910000 26412896 96830484 1770463232 4.0501956940 3.9560704231 4.0542178154 169 1311867724.2507870197 0.1215219498 0.0566149464 0.1222818494 0.0052452510 0.1608440000 0.0116030000 0.0644070000 0.0002920000 0.0003640000 0.0760860000 26415146 96830484 1769345024 4.0497326851 3.9574825764 4.0536031723 170 1311867724.2855930328 0.1250474006 0.0570174903 0.1250474006 0.0052386500 0.1138970000 0.0110630000 0.0541790000 0.0000290000 0.0005150000 0.0398620000 26417364 96830484 1768071168 4.0525102615 3.9564013481 4.0550680161 171 1311867724.3144888878 0.1282733828 0.0574341914 0.1282733828 0.0052290982 0.1151580000 0.0095700000 0.0497570000 0.0003620000 0.0002740000 0.0474260000 26419486 96830484 1769717760 4.0549488068 3.9546816349 4.0558428764 172 1311867724.3517999649 0.1284058541 0.0578468174 0.1284058541 0.0052304301 0.0999100000 0.0114880000 0.0382120000 0.0000290000 0.0002890000 0.0415840000 26421800 96830484 1767047168 4.0546140671 3.9548447132 4.0565581322 173 1311867724.3888330460 0.1282766312 0.0582539261 0.1284058541 0.0052217051 0.1709830000 0.0089730000 0.0614720000 0.0002890000 0.0002700000 0.0843920000 26424018 96830484 1763627008 4.0549097061 3.9556012154 4.0556492805 174 1311867724.4160330296 0.1326705813 0.0586816080 0.1326705813 0.0052164109 0.1341640000 0.0099600000 0.0645540000 0.0000320000 0.0003130000 0.0422660000 26426140 96830484 1765277696 4.0581197739 3.9535079002 4.0581507683 175 1311867724.4509639740 0.1338030249 0.0591108733 0.1338030249 0.0052033271 0.1159070000 0.0097290000 0.0388670000 0.0001960000 0.0001720000 0.0525900000 26428358 96830484 1767051264 4.0590109825 3.9527544975 4.0577001572 176 1311867724.4830689430 0.1340352148 0.0595365798 0.1340352148 0.0051893701 0.1178130000 0.0096580000 0.0512390000 0.0000310000 0.0003200000 0.0420000000 26430544 96830484 1768701952 4.0592579842 3.9527573586 4.0570340157 177 1311867724.5208630562 0.1345792711 0.0599605498 0.1345792711 0.0051760193 0.1616510000 0.0095380000 0.0669360000 0.0002900000 0.0002680000 0.0766080000 26432762 96830484 1770500096 4.0589418411 3.9519951344 4.0575423241 178 1311867724.5523910522 0.1398444772 0.0604093359 0.1398444772 0.0051789070 0.1367160000 0.0115240000 0.0752510000 0.0000070000 0.0000600000 0.0418490000 26434980 96830484 1769598976 4.0633621216 3.9500784874 4.0594468117 179 1311867724.5861799717 0.1402947605 0.0608556232 0.1402947605 0.0051733642 0.1749960000 0.0109210000 0.0859440000 0.0003640000 0.0002880000 0.0668580000 26437166 96830484 1768579072 4.0626444817 3.9482383728 4.0599679947 180 1311867724.6193559170 0.1420267820 0.0613065740 0.1420267820 0.0051891747 0.1350870000 0.0095840000 0.0639370000 0.0000280000 0.0003000000 0.0480390000 26439352 96830484 1770225664 4.0640373230 3.9479227066 4.0601720810 181 1311867724.6529819965 0.1438385099 0.0617625516 0.1438385099 0.0051781137 0.1572850000 0.0133330000 0.0459200000 0.0003180000 0.0002800000 0.0798380000 26441570 96830484 1769226240 4.0657925606 3.9485130310 4.0603752136 182 1311867724.6818330288 0.1442007720 0.0622155089 0.1442007720 0.0051741333 0.0987590000 0.0112490000 0.0331070000 0.0000100000 0.0000910000 0.0452950000 26443692 96830484 1765396480 4.0654687881 3.9471130371 4.0597882271 183 1311867724.7153129578 0.1448241472 0.0626669222 0.1448241472 0.0051720921 0.1342680000 0.0103760000 0.0556410000 0.0005440000 0.0002660000 0.0570330000 26445910 96830484 1766449152 4.0655131340 3.9477174282 4.0606646538 184 1311867724.7518899441 0.1471860558 0.0631262653 0.1471860558 0.0051634416 0.1168540000 0.0090150000 0.0569410000 0.0000870000 0.0002920000 0.0422050000 26448160 96830484 1765416960 4.0676250458 3.9487526417 4.0616049767 185 1311867724.7853860855 0.1498652250 0.0635951245 0.1498652250 0.0051541608 0.1606280000 0.0098570000 0.0655030000 0.0003560000 0.0002870000 0.0766740000 26450378 96830484 1767043072 4.0687446594 3.9467020035 4.0634145737 186 1311867724.8179960251 0.1515696794 0.0640681060 0.1515696794 0.0051517296 0.1104530000 0.0095240000 0.0431820000 0.0000990000 0.0003120000 0.0438620000 26452564 96830484 1768693760 4.0699901581 3.9462850094 4.0639147758 187 1311867724.8547580242 0.1511144191 0.0645335943 0.1515696794 0.0051563507 0.1153410000 0.0101050000 0.0401510000 0.0003530000 0.0010650000 0.0497390000 26454782 96830484 1770471424 4.0696287155 3.9471964836 4.0631961823 188 1311867724.8830249310 0.1538339257 0.0650085961 0.1538339257 0.0051444028 0.1181170000 0.0117930000 0.0489570000 0.0000270000 0.0003550000 0.0437730000 26456904 96830484 1769242624 4.0711183548 3.9458954334 4.0649700165 189 1311867724.9137279987 0.1572757512 0.0654967821 0.1572757512 0.0051578967 0.1402020000 0.0111380000 0.0395610000 0.0003590000 0.0002840000 0.0803700000 26459090 96830484 1768079360 4.0730814934 3.9437162876 4.0667500496 190 1311867724.9535229206 0.1572179794 0.0659795252 0.1572757512 0.0051460201 0.1109670000 0.0096730000 0.0383720000 0.0000270000 0.0002850000 0.0460310000 26461372 96830484 1769742336 4.0732984543 3.9446272850 4.0662317276 191 1311867724.9843940735 0.1583428681 0.0664631029 0.1583428681 0.0051330493 0.1186190000 0.0112920000 0.0380690000 0.0001900000 0.0002170000 0.0536010000 26463558 96830484 1768734720 4.0739555359 3.9441950321 4.0669732094 192 1311867725.0159099102 0.1615549177 0.0669583728 0.1615549177 0.0051334455 0.1355510000 0.0096980000 0.0654450000 0.0000300000 0.0003470000 0.0432890000 26465712 96830484 1770487808 4.0753655434 3.9413683414 4.0694851875 193 1311867725.0518310070 0.1591882110 0.0674362476 0.1615549177 0.0051213463 0.1383270000 0.0111740000 0.0400760000 0.0002040000 0.0001840000 0.0783640000 26467962 96830484 1769603072 4.0736985207 3.9425647259 4.0674967766 194 1311867725.0813930035 0.1603417993 0.0679151422 0.1615549177 0.0051083734 0.0991960000 0.0111030000 0.0364170000 0.0000090000 0.0000930000 0.0432060000 26470116 96830484 1766187008 4.0742940903 3.9423906803 4.0683050156 195 1311867725.1151220798 0.1621178687 0.0683982331 0.1621178687 0.0050988781 0.1318230000 0.0102810000 0.0455280000 0.0003010000 0.0002760000 0.0611400000 26472334 96830484 1766973440 4.0752916336 3.9406318665 4.0686883926 196 1311867725.1557130814 0.1614791602 0.0688731358 0.1621178687 0.0050878389 0.1176220000 0.0115600000 0.0527450000 0.0000260000 0.0002960000 0.0431330000 26474648 96830484 1763373056 4.0747990608 3.9414739609 4.0679636002 197 1311867725.1843969822 0.1665092260 0.0693687505 0.1665092260 0.0050876177 0.1729390000 0.0103730000 0.0652350000 0.0002850000 0.0003520000 0.0808220000 26476770 96830484 1765175296 4.0774021149 3.9387421608 4.0721030235 198 1311867725.2150099277 0.1684945226 0.0698693857 0.1684945226 0.0050777370 0.1001670000 0.0097190000 0.0386930000 0.0000180000 0.0002020000 0.0433400000 26478956 96830484 1766805504 4.0776538849 3.9361031055 4.0735130310 199 1311867725.2516539097 0.1654363722 0.0703496218 0.1684945226 0.0050663315 0.1541780000 0.0089160000 0.0815040000 0.0003650000 0.0002800000 0.0509510000 26481238 96830484 1768583168 4.0765619278 3.9392056465 4.0700712204 200 1311867725.2816410065 0.1653484851 0.0708246161 0.1684945226 0.0050575580 0.1171620000 0.0097290000 0.0462060000 0.0000290000 0.0003190000 0.0447280000 26483392 96830484 1770233856 4.0764813423 3.9392023087 4.0695896149 201 1311867725.3196239471 0.1709583551 0.0713227939 0.1709583551 0.0050562282 0.1774440000 0.0109940000 0.0645030000 0.0003040000 0.0002770000 0.0819020000 26485642 96830484 1769238528 4.0792422295 3.9357836246 4.0739517212 202 1311867725.3517010212 0.1706619114 0.0718145717 0.1709583551 0.0050463362 0.1179680000 0.0096210000 0.0516790000 0.0000260000 0.0003050000 0.0442300000 26487796 96830484 1770868736 4.0788621902 3.9363861084 4.0741143227 203 1311867725.3837459087 0.1786202639 0.0723407082 0.1786202639 0.0050850885 0.1191830000 0.0113100000 0.0489470000 0.0003010000 0.0003620000 0.0497670000 26489918 96830484 1769857024 4.0826945305 3.9323642254 4.0820732117 204 1311867725.4178969860 0.1746102124 0.0728420293 0.1786202639 0.0050746597 0.1145480000 0.0116770000 0.0433620000 0.0000280000 0.0003150000 0.0445950000 26492168 96830484 1767800832 4.0813560486 3.9351091385 4.0768365860 205 1311867725.4492449760 0.1723714173 0.0733275385 0.1786202639 0.0050691559 0.1501940000 0.0100980000 0.0514580000 0.0004000000 0.0002840000 0.0795420000 26494322 96830484 1769639936 4.0796003342 3.9364738464 4.0750069618 206 1311867725.4836509228 0.1867416650 0.0738780925 0.1867416650 0.0051530593 0.1414180000 0.0112460000 0.0652070000 0.0000300000 0.0003070000 0.0448210000 26496540 96830484 1768476672 4.0865812302 3.9292762280 4.0882596970 207 1311867725.5178139210 0.1960955262 0.0744685149 0.1960955262 0.0051648273 0.1175740000 0.0095700000 0.0448370000 0.0003860000 0.0002850000 0.0520000000 26498822 96830484 1770254336 4.0903358459 3.9241807461 4.0972781181 208 1311867725.5497610569 0.2002658397 0.0750733097 0.2002658397 0.0051598554 0.1371220000 0.0117180000 0.0647240000 0.0000270000 0.0002980000 0.0451420000 26500976 96830484 1769095168 4.0919647217 3.9219315052 4.1006226540 209 1311867725.5815479755 0.1934832335 0.0756398643 0.2002658397 0.0051857067 0.1758260000 0.0101390000 0.0657760000 0.0003570000 0.0002840000 0.0838070000 26503162 96830484 1770762240 4.0899591446 3.9270637035 4.0923004150 210 1311867725.6194949150 0.2029598653 0.0762461501 0.2029598653 0.0051878553 0.1405180000 0.0119750000 0.0774250000 0.0000070000 0.0000610000 0.0424880000 26505444 96830484 1769480192 4.0944066048 3.9218823910 4.1001191139 211 1311867725.6515610218 0.2165531367 0.0769111121 0.2165531367 0.0053313893 0.1352130000 0.0108010000 0.0634310000 0.0002890000 0.0002690000 0.0517110000 26507630 96830484 1768349696 4.0982532501 3.9134483337 4.1142649651 212 1311867725.6834650040 0.2113618404 0.0775453136 0.2165531367 0.0053315268 0.1340560000 0.0097870000 0.0640240000 0.0000250000 0.0003490000 0.0448590000 26509816 96830484 1769996288 4.0970549583 3.9180822372 4.1080951691 213 1311867725.7201809883 0.2152427435 0.0781917804 0.2165531367 0.0053244532 0.1582070000 0.0115870000 0.0499810000 0.0002840000 0.0003450000 0.0806300000 26512066 96830484 1768988672 4.0987300873 3.9158396721 4.1105737686 214 1311867725.7515070438 0.2221477032 0.0788644717 0.2221477032 0.0053227406 0.1162520000 0.0111290000 0.0442980000 0.0000270000 0.0003120000 0.0455160000 26514252 96830484 1768222720 4.1009178162 3.9114241600 4.1167669296 215 1311867725.7835409641 0.1839655638 0.0793533140 0.2221477032 0.0055578277 0.1374270000 0.0099930000 0.0674620000 0.0002910000 0.0002680000 0.0509400000 26516406 96830484 1769873408 4.0738859177 3.9256153107 4.0911974907 216 1311867725.8211829662 0.1926571131 0.0798778686 0.2221477032 0.0055693023 0.1156770000 0.0116370000 0.0446850000 0.0000270000 0.0003070000 0.0448930000 26518720 96830484 1768607744 4.0770020485 3.9201908112 4.0989222527 217 1311867725.8517971039 0.1923837960 0.0803963291 0.2221477032 0.0055622971 0.1556830000 0.0097920000 0.0476440000 0.0003480000 0.0002730000 0.0832860000 26520906 96830484 1770233856 4.0764737129 3.9200940132 4.0981678963 218 1311867725.8837900162 0.1966030598 0.0809293875 0.2221477032 0.0055748433 0.1382020000 0.0117960000 0.0668530000 0.0000280000 0.0002840000 0.0451390000 26523028 96830484 1769496576 4.0783548355 3.9193971157 4.1021161079 219 1311867725.9192690849 0.2002336383 0.0814741557 0.2221477032 0.0055704563 0.1518370000 0.0115030000 0.0668780000 0.0003930000 0.0002770000 0.0529780000 26525278 96830484 1768460288 4.0804252625 3.9179041386 4.1038227081 220 1311867725.9511859417 0.2074058503 0.0820465725 0.2221477032 0.0055657524 0.1347440000 0.0095980000 0.0562240000 0.0000240000 0.0002810000 0.0456940000 26527464 96830484 1770090496 4.0825886726 3.9132082462 4.1102490425 221 1311867725.9829630852 0.2084781080 0.0826186609 0.2221477032 0.0055549573 0.1593410000 0.0121410000 0.0443560000 0.0003930000 0.0002780000 0.0840800000 26529618 96830484 1769099264 4.0835886002 3.9142930508 4.1107840538 222 1311867726.0219368935 0.2137008905 0.0832091214 0.2221477032 0.0055484179 0.1379730000 0.0111700000 0.0662220000 0.0000060000 0.0000580000 0.0464920000 26531932 96830484 1767952384 4.0855536461 3.9114239216 4.1144418716 223 1311867726.0504179001 0.2089262754 0.0837728755 0.2221477032 0.0055499833 0.1369900000 0.0097000000 0.0670470000 0.0002960000 0.0002680000 0.0511380000 26534022 96830484 1769615360 4.0833158493 3.9134275913 4.1090264320 224 1311867726.0845088959 0.2177626193 0.0843710440 0.2221477032 0.0055664597 0.1357670000 0.0116940000 0.0655500000 0.0000300000 0.0003030000 0.0448490000 26536272 96830484 1768718336 4.0861544609 3.9089229107 4.1179323196 225 1311867726.1199669838 0.2172350138 0.0849615505 0.2221477032 0.0055566497 0.1586440000 0.0098870000 0.0586950000 0.0003170000 0.0003370000 0.0809190000 26538490 96830484 1770344448 4.0859117508 3.9090819359 4.1165714264 226 1311867726.1506989002 0.2196577787 0.0855575515 0.2221477032 0.0055488436 0.1351190000 0.0115830000 0.0651840000 0.0000250000 0.0002800000 0.0450560000 26540676 96830484 1769242624 4.0860104561 3.9068915844 4.1185960770 227 1311867726.1824700832 0.2150917947 0.0861281870 0.2221477032 0.0055382133 0.1356610000 0.0113350000 0.0548920000 0.0006110000 0.0003630000 0.0526980000 26542862 96830484 1768206336 4.0840678215 3.9099888802 4.1142511368 228 1311867726.2198660374 0.2190221548 0.0867110552 0.2221477032 0.0055335817 0.1343990000 0.0100040000 0.0555260000 0.0000270000 0.0003410000 0.0458370000 26545112 96830484 1769963520 4.0860552788 3.9083178043 4.1167860031 229 1311867726.2506690025 0.2267663926 0.0873226506 0.2267663926 0.0055348927 0.1598750000 0.0124740000 0.0503840000 0.0002960000 0.0002740000 0.0811950000 26547298 96830484 1768837120 4.0881819725 3.9030601978 4.1237978935 230 1311867726.2845950127 0.2238692641 0.0879163315 0.2267663926 0.0055245926 0.1147980000 0.0099290000 0.0370340000 0.0000090000 0.0000920000 0.0489060000 26549484 96830484 1770463232 4.0873098373 3.9048566818 4.1202645302 231 1311867726.3187239170 0.2302618027 0.0885325457 0.2302618027 0.0055213758 0.1408080000 0.0119120000 0.0661920000 0.0002840000 0.0003360000 0.0527310000 26551734 96830484 1769234432 4.0899295807 3.9022395611 4.1259088516 232 1311867726.3524029255 0.2286043018 0.0891363033 0.2302618027 0.0055137804 0.1356250000 0.0113340000 0.0671280000 0.0000290000 0.0002860000 0.0464470000 26553952 96830484 1768071168 4.0901746750 3.9041647911 4.1232266426 233 1311867726.3835608959 0.2313851714 0.0897468134 0.2313851714 0.0055032278 0.1543970000 0.0100370000 0.0445510000 0.0003150000 0.0003530000 0.0842340000 26556106 96830484 1769848832 4.0905637741 3.9021492004 4.1254067421 234 1311867726.4218099117 0.2296737134 0.0903447916 0.2313851714 0.0054935779 0.1179060000 0.0118790000 0.0446180000 0.0000300000 0.0003090000 0.0456470000 26558420 96830484 1768464384 4.0909638405 3.9047503471 4.1227545738 235 1311867726.4504199028 0.2300311029 0.0909392015 0.2313851714 0.0054820933 0.1160240000 0.0099500000 0.0399140000 0.0002850000 0.0003430000 0.0533750000 26560542 96830484 1770082304 4.0907449722 3.9047517776 4.1230444908 236 1311867726.4843189716 0.2324637026 0.0915388816 0.2324637026 0.0054728236 0.1381090000 0.0120430000 0.0669500000 0.0000290000 0.0006950000 0.0453120000 26562760 96830484 1768837120 4.0912785530 3.9032609463 4.1250743866 237 1311867726.5207901001 0.2374686003 0.0921546188 0.2374686003 0.0054668209 0.1583330000 0.0098200000 0.0439060000 0.0003180000 0.0002860000 0.0841040000 26565010 96830484 1770483712 4.0922918320 3.8998262882 4.1299529076 238 1311867726.5524380207 0.2367027998 0.0927619641 0.2374686003 0.0054609561 0.1148700000 0.0118740000 0.0385830000 0.0000270000 0.0002980000 0.0489060000 26567196 96830484 1769119744 4.0921173096 3.9009461403 4.1290397644 239 1311867726.5874860287 0.2331828922 0.0933494993 0.2374686003 0.0054576426 0.1391340000 0.0115790000 0.0676990000 0.0003450000 0.0002660000 0.0502220000 26569446 96830484 1767706624 4.0910620689 3.9037132263 4.1253175735 240 1311867726.6204600334 0.2353507578 0.0939411712 0.2374686003 0.0054603719 0.1130920000 0.0100110000 0.0442540000 0.0000280000 0.0003130000 0.0463570000 26571632 96830484 1769447424 4.0924496651 3.9028749466 4.1270985603 241 1311867726.6509370804 0.2322545797 0.0945150858 0.2374686003 0.0054637995 0.1865060000 0.0115340000 0.0793650000 0.0000810000 0.0000560000 0.0862810000 26573786 96830484 1768345600 4.0916433334 3.9041006565 4.1228952408 242 1311867726.6916151047 0.2350385189 0.0950957611 0.2374686003 0.0054577955 0.1249250000 0.0096290000 0.0488510000 0.0000280000 0.0003140000 0.0558090000 26576132 96830484 1769955328 4.0923609734 3.9025049210 4.1259264946 243 1311867726.7201170921 0.2357664555 0.0956746529 0.2374686003 0.0054477724 0.1376960000 0.0120020000 0.0528390000 0.0003220000 0.0003570000 0.0595360000 26578222 96830484 1768726528 4.0934305191 3.9028890133 4.1262922287 244 1311867726.7513859272 0.2314085811 0.0962309395 0.2374686003 0.0054410307 0.1162990000 0.0101490000 0.0488350000 0.0000280000 0.0021680000 0.0449240000 26580408 96830484 1770483712 4.0913205147 3.9041411877 4.1221051216 245 1311867726.7880010605 0.2271551639 0.0967653241 0.2374686003 0.0054349991 0.1666460000 0.0121280000 0.0662150000 0.0002860000 0.0003400000 0.0786680000 26582690 96830484 1769345024 4.0896420479 3.9059324265 4.1181592941 246 1311867726.8198299408 0.2300957441 0.0973073176 0.2374686003 0.0054288456 0.1237940000 0.0118730000 0.0565870000 0.0000880000 0.0002930000 0.0453280000 26584844 96830484 1768218624 4.0910120010 3.9045159817 4.1210856438 247 1311867726.8500390053 0.2318302393 0.0978519449 0.2374686003 0.0054188734 0.1362430000 0.0099270000 0.0664720000 0.0003730000 0.0002820000 0.0505460000 26586998 96830484 1769828352 4.0916199684 3.9031472206 4.1227502823 248 1311867726.8927390575 0.2265504748 0.0983708905 0.2374686003 0.0054124914 0.1362310000 0.0119410000 0.0669000000 0.0000260000 0.0003030000 0.0447400000 26589376 96830484 1768583168 4.0901975632 3.9061238766 4.1173005104 249 1311867726.9216780663 0.2279072553 0.0988911169 0.2374686003 0.0054031364 0.1650200000 0.0100230000 0.0668380000 0.0002960000 0.0002790000 0.0786450000 26591498 96830484 1770209280 4.0903682709 3.9054915905 4.1195025444 250 1311867726.9543499947 0.2223765403 0.0993850586 0.2374686003 0.0054274339 0.1404730000 0.0141920000 0.0678210000 0.0000280000 0.0003670000 0.0445480000 26593684 96830484 1768992768 4.0893769264 3.9090178013 4.1135153770 251 1311867726.9902989864 0.2230026126 0.0998775588 0.2374686003 0.0054221148 0.1349730000 0.0112470000 0.0510730000 0.0002980000 0.0003630000 0.0524110000 26595902 96830484 1767964672 4.0889911652 3.9081268311 4.1149430275 252 1311867727.0208179951 0.2244826704 0.1003720235 0.2374686003 0.0054119654 0.1361360000 0.0096380000 0.0666390000 0.0000280000 0.0003620000 0.0452460000 26598088 96830484 1769574400 4.0896334648 3.9070065022 4.1163210869 253 1311867727.0536949635 0.2211200893 0.1008492886 0.2374686003 0.0054079632 0.1567050000 0.0115610000 0.0397590000 0.0003690000 0.0002800000 0.0827790000 26600274 96830484 1768472576 4.0888705254 3.9088077545 4.1129779816 254 1311867727.0911629200 0.2217408717 0.1013252397 0.2374686003 0.0053985840 0.1156600000 0.0103240000 0.0406670000 0.0000290000 0.0011790000 0.0449850000 26602556 96830484 1770229760 4.0886888504 3.9080646038 4.1145386696 255 1311867727.1196689606 0.2176604867 0.1017814564 0.2374686003 0.0053909311 0.1177580000 0.0116660000 0.0344630000 0.0000980000 0.0000880000 0.0521130000 26604614 96830484 1768964096 4.0871343613 3.9098167419 4.1106252670 256 1311867727.1514298916 0.2140534967 0.1022200190 0.2374686003 0.0053856399 0.1174280000 0.0093440000 0.0509150000 0.0000350000 0.0003020000 0.0448110000 26606832 96830484 1770590208 4.0855126381 3.9115335941 4.1080241203 257 1311867727.1904149055 0.2150035799 0.1026588656 0.2374686003 0.0053949799 0.1570880000 0.0124280000 0.0464160000 0.0003220000 0.0003460000 0.0823810000 26629562 96830484 1769472000 4.0858707428 3.9107067585 4.1097030640 258 1311867727.2208960056 0.2120631635 0.1030829133 0.2374686003 0.0053924131 0.1364430000 0.0114850000 0.0677450000 0.0000280000 0.0002990000 0.0439620000 26673732 96830484 1768202240 4.0844392776 3.9126820564 4.1083440781 259 1311867727.2544560432 0.2071583122 0.1034847488 0.2374686003 0.0053967577 0.1152610000 0.0096780000 0.0393960000 0.0002960000 0.0003460000 0.0514630000 26675918 96830484 1769828352 4.0826792717 3.9147017002 4.1032047272 260 1311867727.2870850563 0.2078850865 0.1038862885 0.2374686003 0.0053883690 0.1384710000 0.0118080000 0.0673620000 0.0000260000 0.0002870000 0.0445690000 26678136 96830484 1768464384 4.0826473236 3.9138207436 4.1047873497 261 1311867727.3192501068 0.2083279192 0.1042864480 0.2374686003 0.0053783699 0.1553940000 0.0099660000 0.0514110000 0.0002990000 0.0003550000 0.0785500000 26680322 96830484 1770209280 4.0833139420 3.9130473137 4.1050720215 262 1311867727.3502039909 0.2040047646 0.1046670523 0.2374686003 0.0053777275 0.1361120000 0.0118050000 0.0567950000 0.0000290000 0.0002920000 0.0436430000 26682476 96830484 1768865792 4.0812683105 3.9140708447 4.1011843681 263 1311867727.3894629478 0.2028098851 0.1050402190 0.2374686003 0.0053688788 0.1162570000 0.0102320000 0.0348950000 0.0000920000 0.0000840000 0.0542750000 26684726 96830484 1770463232 4.0806665421 3.9151742458 4.1018877029 264 1311867727.4182970524 0.2009023726 0.1054033332 0.2374686003 0.0053595199 0.1181890000 0.0120000000 0.0460160000 0.0000270000 0.0005880000 0.0441100000 26686880 96830484 1769099264 4.0800228119 3.9157681465 4.1012501717 265 1311867727.4495580196 0.1971276551 0.1057494627 0.2374686003 0.0053542917 0.1391340000 0.0112570000 0.0401310000 0.0003010000 0.0002890000 0.0778030000 26689002 96830484 1767854080 4.0783138275 3.9170413017 4.0982961655 266 1311867727.4858360291 0.1976986080 0.1060951362 0.2374686003 0.0053666515 0.1333440000 0.0096000000 0.0663310000 0.0000270000 0.0003760000 0.0430840000 26691284 96830484 1769447424 4.0776591301 3.9170062542 4.1012730598 267 1311867727.5198891163 0.1939710677 0.1064242595 0.2374686003 0.0053710881 0.1360640000 0.0116110000 0.0524660000 0.0003730000 0.0002810000 0.0510320000 26693470 96830484 1768108032 4.0769214630 3.9189057350 4.0970339775 268 1311867727.5494980812 0.1929846555 0.1067472461 0.2374686003 0.0053670059 0.1365440000 0.0098670000 0.0674470000 0.0000270000 0.0002960000 0.0433000000 26695624 96830484 1769828352 4.0758838654 3.9179923534 4.0966134071 269 1311867727.5905909538 0.1905314028 0.1070587113 0.2374686003 0.0053644576 0.1776940000 0.0118100000 0.0681810000 0.0003770000 0.0002890000 0.0803490000 26697970 96830484 1768726528 4.0752816200 3.9189398289 4.0945277214 270 1311867727.6176431179 0.1892607659 0.1073631634 0.2374686003 0.0053645440 0.1351820000 0.0098780000 0.0622020000 0.0000280000 0.0003730000 0.0434050000 26700060 96830484 1770463232 4.0734381676 3.9183781147 4.0946550369 271 1311867727.6497650146 0.1871099323 0.1076574319 0.2374686003 0.0053600253 0.1402980000 0.0118470000 0.0677300000 0.0003800000 0.0002810000 0.0502530000 26702246 96830484 1769107456 4.0724253654 3.9189701080 4.0927929878 272 1311867727.6884338856 0.1822837740 0.1079317935 0.2374686003 0.0053582889 0.0923270000 0.0110840000 0.0344300000 0.0000170000 0.0002110000 0.0371800000 26704432 96830484 1764925440 4.0708136559 3.9218027592 4.0881328583 273 1311867727.7184689045 0.1802968383 0.1081968669 0.2374686003 0.0053496149 0.1372610000 0.0102170000 0.0376670000 0.0004930000 0.0002810000 0.0793540000 26706618 96830484 1766330368 4.0695958138 3.9221513271 4.0859475136 274 1311867727.7523269653 0.1758788228 0.1084438813 0.2374686003 0.0053438395 0.1349790000 0.0097610000 0.0667860000 0.0000290000 0.0003650000 0.0423390000 26708836 96830484 1765535744 4.0659947395 3.9224753380 4.0824341774 275 1311867727.7856590748 0.1748065948 0.1086852003 0.2374686003 0.0053378288 0.1351590000 0.0097980000 0.0574310000 0.0002990000 0.0005300000 0.0498030000 26711022 96830484 1767305216 4.0648546219 3.9231736660 4.0824317932 276 1311867727.8181309700 0.1742065400 0.1089225964 0.2374686003 0.0053347515 0.0987730000 0.0091040000 0.0340600000 0.0000270000 0.0002860000 0.0444120000 26713240 96830484 1769066496 4.0640454292 3.9236161709 4.0824832916 277 1311867727.8548729420 0.1735976487 0.1091560804 0.2374686003 0.0053267256 0.1562210000 0.0112010000 0.0451100000 0.0003670000 0.0002850000 0.0897520000 26715490 96830484 1767960576 4.0637969971 3.9237239361 4.0816826820 278 1311867727.8882629871 0.1710298806 0.1093786480 0.2374686003 0.0053180162 0.0976250000 0.0094670000 0.0334740000 0.0000170000 0.0001970000 0.0447160000 26717708 96830484 1769574400 4.0627121925 3.9251561165 4.0796170235 279 1311867727.9193139076 0.1702911854 0.1095969725 0.2374686003 0.0053111964 0.1361070000 0.0116600000 0.0546080000 0.0003910000 0.0006200000 0.0500720000 26719862 96830484 1768345600 4.0617747307 3.9254069328 4.0800948143 280 1311867727.9556980133 0.1700634062 0.1098129241 0.2374686003 0.0053027966 0.1367630000 0.0100090000 0.0705240000 0.0000270000 0.0003480000 0.0419050000 26722112 96830484 1769955328 4.0622696877 3.9253358841 4.0792145729 281 1311867727.9869389534 0.1697143912 0.1100260965 0.2374686003 0.0052939944 0.1355700000 0.0117720000 0.0347710000 0.0001950000 0.0001740000 0.0793150000 26724330 96830484 1768964096 4.0621323586 3.9255166054 4.0791125298 282 1311867728.0179219246 0.1678768843 0.1102312412 0.2374686003 0.0052940093 0.1347440000 0.0099810000 0.0663400000 0.0000270000 0.0002870000 0.0419770000 26726452 96830484 1770606592 4.0616445541 3.9266622066 4.0776715279 283 1311867728.0555219650 0.1652097851 0.1104255117 0.2374686003 0.0052877599 0.1361310000 0.0118810000 0.0520260000 0.0002910000 0.0004630000 0.0498480000 26728734 96830484 1769598976 4.0597805977 3.9275016785 4.0764927864 284 1311867728.0892169476 0.1639620662 0.1106140207 0.2374686003 0.0052796042 0.1367740000 0.0113560000 0.0665660000 0.0000270000 0.0002890000 0.0421840000 26730952 96830484 1768599552 4.0595970154 3.9285814762 4.0756874084 285 1311867728.1177880764 0.1615484804 0.1107927381 0.2374686003 0.0052767768 0.1330040000 0.0099360000 0.0340890000 0.0000940000 0.0000860000 0.0794360000 26733106 96830484 1770098688 4.0583562851 3.9294667244 4.0738043785 286 1311867728.1556169987 0.1615221500 0.1109701136 0.2374686003 0.0052703693 0.1395410000 0.0114860000 0.0668620000 0.0000300000 0.0003010000 0.0424700000 26735356 96830484 1768706048 4.0584497452 3.9292714596 4.0739498138 287 1311867728.1882989407 0.1598398536 0.1111403915 0.2374686003 0.0052615299 0.1014690000 0.0095610000 0.0341140000 0.0000980000 0.0000880000 0.0484130000 26737606 96830484 1770479616 4.0580401421 3.9298837185 4.0719609261 288 1311867728.2182519436 0.1590796411 0.1113068472 0.2374686003 0.0052550649 0.1356560000 0.0107280000 0.0457590000 0.0000310000 0.0003820000 0.0690000000 26739760 96830484 1769488384 4.0571665764 3.9298214912 4.0717973709 289 1311867728.2558999062 0.1572483778 0.1114658144 0.2374686003 0.0052465869 0.1884440000 0.0117600000 0.0844020000 0.0000610000 0.0000540000 0.0826240000 26742010 96830484 1768341504 4.0563316345 3.9305219650 4.0702743530 290 1311867728.2875900269 0.1384987086 0.1115590313 0.2374686003 0.0053315351 0.1019140000 0.0096350000 0.0409250000 0.0000290000 0.0003750000 0.0416800000 26744196 96830484 1770098688 4.0363006592 3.9325058460 4.0645890236 291 1311867728.3226509094 0.1380493939 0.1116500635 0.2374686003 0.0053372301 0.1156060000 0.0115320000 0.0346610000 0.0002080000 0.0001860000 0.0518060000 26746446 96830484 1769361408 4.0369048119 3.9335482121 4.0642485619 292 1311867728.3597300053 0.1369448155 0.1117366893 0.2374686003 0.0053375142 0.0991090000 0.0110550000 0.0346220000 0.0000190000 0.0002060000 0.0432040000 26748664 96830484 1765797888 4.0357694626 3.9328835011 4.0635976791 293 1311867728.3861401081 0.1373871565 0.1118242336 0.2374686003 0.0053286266 0.1495900000 0.0100580000 0.0537080000 0.0003230000 0.0003490000 0.0754670000 26750786 96830484 1766924288 4.0364456177 3.9329192638 4.0637259483 294 1311867728.4175701141 0.1373165399 0.1119109421 0.2374686003 0.0053593750 0.0995790000 0.0096100000 0.0343160000 0.0000190000 0.0002060000 0.0444230000 26752972 96830484 1764667392 4.0358419418 3.9323267937 4.0634989738 295 1311867728.4568250179 0.1353064179 0.1119902488 0.2374686003 0.0053520014 0.1336230000 0.0101870000 0.0529790000 0.0003240000 0.0002810000 0.0516350000 26755254 96830484 1766273024 4.0347433090 3.9332346916 4.0618462563 296 1311867728.4875330925 0.1334301978 0.1120626811 0.2374686003 0.0053465472 0.1580730000 0.0093250000 0.0906470000 0.0000060000 0.0000620000 0.0470200000 26757408 96830484 1767976960 4.0343136787 3.9348104000 4.0603151321 297 1311867728.5187420845 0.1332066506 0.1121338729 0.2374686003 0.0053405182 0.1528720000 0.0099840000 0.0441400000 0.0003790000 0.0002810000 0.0888710000 26759562 96830484 1769717760 4.0342068672 3.9342958927 4.0595488548 298 1311867728.5550920963 0.1318526566 0.1122000433 0.2374686003 0.0053339213 0.1048500000 0.0113160000 0.0392820000 0.0000190000 0.0001980000 0.0430760000 26761844 96830484 1766166528 4.0332798958 3.9350428581 4.0591206551 299 1311867728.5878560543 0.1324269176 0.1122676917 0.2374686003 0.0053274915 0.1333410000 0.0104280000 0.0616090000 0.0003000000 0.0002770000 0.0489100000 26764062 96830484 1767325696 4.0344915390 3.9349546432 4.0584902763 300 1311867728.6187679768 0.1311303526 0.1123305673 0.2374686003 0.0053198651 0.1147190000 0.0100160000 0.0471400000 0.0000250000 0.0003740000 0.0411380000 26766184 96830484 1764143104 4.0336999893 3.9355041981 4.0574841499 301 1311867728.6580820084 0.1319130808 0.1123956254 0.2374686003 0.0053120131 0.1503890000 0.0099480000 0.0293470000 0.0002060000 0.0002320000 0.0772840000 26768498 96830484 1765167104 4.0341019630 3.9350497723 4.0580744743 302 1311867728.6893489361 0.1313455552 0.1124583735 0.2374686003 0.0053044025 0.1001040000 0.0123160000 0.0383540000 0.0000290000 0.0003860000 0.0388670000 26770684 96830484 1762623488 4.0331840515 3.9345898628 4.0578083992 303 1311867728.7210168839 0.1305775344 0.1125181728 0.2374686003 0.0053009512 0.1508460000 0.0102040000 0.0676470000 0.0003690000 0.0005050000 0.0484450000 26772870 96830484 1764380672 4.0331053734 3.9349701405 4.0571026802 304 1311867728.7584259510 0.1299009025 0.1125753528 0.2374686003 0.0052923254 0.1170350000 0.0109330000 0.0515990000 0.0000290000 0.0003060000 0.0416060000 26775120 96830484 1766055936 4.0327849388 3.9349424839 4.0563588142 305 1311867728.7858450413 0.1291183978 0.1126295923 0.2374686003 0.0052845389 0.1370960000 0.0098940000 0.0425110000 0.0003180000 0.0002810000 0.0747610000 26777274 96830484 1767813120 4.0316410065 3.9345614910 4.0559411049 306 1311867728.8203740120 0.1280095577 0.1126798536 0.2374686003 0.0052770195 0.1157070000 0.0098460000 0.0450610000 0.0000270000 0.0003130000 0.0417710000 26779460 96830484 1769463808 4.0315194130 3.9350533485 4.0540566444 307 1311867728.8545160294 0.1241085455 0.1127170806 0.2374686003 0.0052707336 0.1177420000 0.0113910000 0.0339760000 0.0001170000 0.0000880000 0.0516500000 26781678 96830484 1768726528 4.0296335220 3.9367439747 4.0505895615 308 1311867728.8860759735 0.1273767203 0.1127646769 0.2374686003 0.0052642315 0.1154750000 0.0098420000 0.0431010000 0.0000280000 0.0003130000 0.0414770000 26783896 96830484 1770479616 4.0314631462 3.9353029728 4.0530920029 309 1311867728.9193949699 0.1272177845 0.1128114507 0.2374686003 0.0052561919 0.1384110000 0.0119420000 0.0386390000 0.0000980000 0.0000880000 0.0779220000 26786050 96830484 1769615360 4.0309562683 3.9350912571 4.0536689758 310 1311867728.9585559368 0.1241376474 0.1128479868 0.2374686003 0.0052680227 0.1371230000 0.0112500000 0.0681860000 0.0000270000 0.0003580000 0.0407620000 26788428 96830484 1768599552 4.0297350883 3.9370234013 4.0511713028 311 1311867728.9886839390 0.1256235391 0.1128890657 0.2374686003 0.0052637707 0.1374180000 0.0098320000 0.0675510000 0.0003580000 0.0002770000 0.0486860000 26790518 96830484 1770209280 4.0300431252 3.9351241589 4.0525188446 312 1311867729.0231020451 0.1232379973 0.1129222354 0.2374686003 0.0052578028 0.1159420000 0.0119380000 0.0459500000 0.0000260000 0.0003170000 0.0409060000 26792768 96830484 1768980480 4.0290327072 3.9366416931 4.0512099266 313 1311867729.0583839417 0.1209549606 0.1129478990 0.2374686003 0.0052569953 0.1553420000 0.0097590000 0.0506230000 0.0007160000 0.0002810000 0.0772620000 26795018 96830484 1770606592 4.0270957947 3.9374356270 4.0508079529 314 1311867729.0882170200 0.1178674400 0.1129635664 0.2374686003 0.0052499533 0.1372590000 0.0117170000 0.0667560000 0.0000280000 0.0003200000 0.0415580000 26797172 96830484 1769598976 4.0247845650 3.9384713173 4.0486259460 315 1311867729.1263229847 0.1185316816 0.1129812429 0.2374686003 0.0052635763 0.1139930000 0.0120450000 0.0388700000 0.0003040000 0.0003600000 0.0505130000 26799454 96830484 1768599552 4.0249147415 3.9394624233 4.0504894257 316 1311867729.1556320190 0.1169424430 0.1129937784 0.2374686003 0.0052590671 0.1349710000 0.0095060000 0.0685930000 0.0000290000 0.0003710000 0.0409870000 26801576 96830484 1770336256 4.0240740776 3.9408354759 4.0488266945 317 1311867729.1888830662 0.1173351109 0.1130074734 0.2374686003 0.0052860915 0.1566760000 0.0117230000 0.0464150000 0.0010690000 0.0002950000 0.0775180000 26803794 96830484 1769218048 4.0236282349 3.9403069019 4.0490808487 318 1311867729.2240469456 0.1116052568 0.1130030639 0.2374686003 0.0052917814 0.1372650000 0.0112010000 0.0689730000 0.0000300000 0.0003800000 0.0414630000 26806012 96830484 1767833600 4.0196313858 3.9424107075 4.0457019806 319 1311867729.2579979897 0.1128467843 0.1130025740 0.2374686003 0.0052836615 0.1161760000 0.0098340000 0.0464470000 0.0003140000 0.0003590000 0.0481960000 26808262 96830484 1769574400 4.0187320709 3.9401555061 4.0477471352 320 1311867729.2880148888 0.1150601506 0.1130090040 0.2374686003 0.0052809624 0.1369300000 0.0115290000 0.0681680000 0.0000270000 0.0003130000 0.0407760000 26810416 96830484 1768218624 4.0178432465 3.9376289845 4.0516004562 321 1311867729.3236539364 0.1099524647 0.1129994820 0.2374686003 0.0052803209 0.1549570000 0.0095420000 0.0508350000 0.0005580000 0.0002760000 0.0763610000 26812634 96830484 1769955328 4.0139164925 3.9393398762 4.0501155853 322 1311867729.3580930233 0.1059064195 0.1129774539 0.2374686003 0.0052850055 0.1174970000 0.0120540000 0.0453830000 0.0000280000 0.0003770000 0.0408350000 26814884 96830484 1768853504 4.0113358498 3.9396042824 4.0483250618 323 1311867729.3882780075 0.1074716598 0.1129604081 0.2374686003 0.0052865254 0.1370330000 0.0097530000 0.0651160000 0.0003700000 0.0002820000 0.0476070000 26817006 96830484 1770463232 4.0108551979 3.9386022091 4.0513420105 324 1311867729.4253289700 0.1043894663 0.1129339546 0.2374686003 0.0052818813 0.1367450000 0.0117920000 0.0658110000 0.0000260000 0.0003590000 0.0402880000 26819288 96830484 1769234432 4.0091319084 3.9400978088 4.0505299568 325 1311867729.4572670460 0.1046557948 0.1129084833 0.2374686003 0.0052757494 0.1756190000 0.0112130000 0.0659070000 0.0002920000 0.0003360000 0.0772540000 26821474 96830484 1767854080 4.0092043877 3.9390571117 4.0511026382 326 1311867729.4887750149 0.1025086790 0.1128765821 0.2374686003 0.0052845854 0.1358950000 0.0099650000 0.0669850000 0.0000280000 0.0002840000 0.0402110000 26823692 96830484 1769447424 4.0088162422 3.9394369125 4.0493178368 327 1311867729.5223650932 0.1029651985 0.1128462720 0.2374686003 0.0052779088 0.1387270000 0.0115550000 0.0641130000 0.0003800000 0.0002770000 0.0474210000 26825878 96830484 1768091648 4.0083293915 3.9385328293 4.0508556366 328 1311867729.5603790283 0.1003913954 0.1128082998 0.2374686003 0.0052737059 0.1347930000 0.0096500000 0.0656180000 0.0000260000 0.0002930000 0.0405470000 26828160 96830484 1769828352 4.0074405670 3.9391798973 4.0491728783 329 1311867729.5890150070 0.1017166227 0.1127745865 0.2374686003 0.0052658116 0.1770390000 0.0118640000 0.0656650000 0.0003640000 0.0002800000 0.0762020000 26830282 96830484 1768464384 4.0087642670 3.9381260872 4.0499982834 330 1311867729.6254830360 0.0982540995 0.1127305850 0.2374686003 0.0052615268 0.1359730000 0.0103650000 0.0675980000 0.0000280000 0.0003600000 0.0398920000 26832532 96830484 1770082304 4.0066719055 3.9393379688 4.0485997200 331 1311867729.6614611149 0.0977049768 0.1126851905 0.2374686003 0.0052552556 0.1395850000 0.0118740000 0.0652720000 0.0002940000 0.0003450000 0.0471310000 26834782 96830484 1768718336 4.0071358681 3.9393303394 4.0485024452 332 1311867729.6888220310 0.0954833329 0.1126333776 0.2374686003 0.0052489644 0.1163140000 0.0095860000 0.0548700000 0.0000280000 0.0003530000 0.0397200000 26836840 96830484 1770463232 4.0054984093 3.9394485950 4.0471796989 333 1311867729.7230739594 0.0936983898 0.1125765158 0.2374686003 0.0052425159 0.1557430000 0.0117220000 0.0498350000 0.0003660000 0.0002770000 0.0744830000 26839090 96830484 1769119744 4.0039982796 3.9399628639 4.0470466614 334 1311867729.7570610046 0.0885036513 0.1125044414 0.2374686003 0.0052411095 0.0997920000 0.0114090000 0.0384560000 0.0000280000 0.0002940000 0.0393370000 26841212 96830484 1765920768 4.0026025772 3.9426238537 4.0430784225 335 1311867729.7899730206 0.0808553994 0.1124099666 0.2374686003 0.0052435253 0.1531100000 0.0098220000 0.0822480000 0.0002920000 0.0003490000 0.0494670000 26843430 96830484 1766424576 3.9986243248 3.9451930523 4.0368876457 336 1311867729.8264250755 0.0863510817 0.1123324104 0.2374686003 0.0052612054 0.1573900000 0.0097200000 0.0957190000 0.0000060000 0.0000620000 0.0416730000 26845648 96830484 1764933632 3.9990880489 3.9417877197 4.0437388420 337 1311867729.8550031185 0.0796946585 0.1122355625 0.2374686003 0.0052583459 0.1887390000 0.0098670000 0.0871610000 0.0002870000 0.0003410000 0.0812230000 26847770 96830484 1766653952 3.9957058430 3.9450519085 4.0395483971 338 1311867729.8881840706 0.0769990534 0.1121313125 0.2374686003 0.0052608907 0.1228440000 0.0097360000 0.0644060000 0.0000270000 0.0003600000 0.0384890000 26850020 96830484 1768304640 3.9955966473 3.9458181858 4.0361280441 339 1311867729.9233629704 0.0705018640 0.1120085117 0.2374686003 0.0052602777 0.1170000000 0.0095780000 0.0488900000 0.0003040000 0.0002810000 0.0469590000 26852238 96830484 1770102784 3.9904866219 3.9484114647 4.0328645706 340 1311867729.9569330215 0.0709055960 0.1118876208 0.2374686003 0.0052534246 0.1159060000 0.0117830000 0.0448070000 0.0000300000 0.0003860000 0.0400010000 26854456 96830484 1768738816 3.9915797710 3.9488012791 4.0334649086 341 1311867729.9865698814 0.0683293790 0.1117598840 0.2374686003 0.0052501880 0.1557800000 0.0099960000 0.0544150000 0.0003120000 0.0003500000 0.0720290000 26856578 96830484 1770336256 3.9890134335 3.9489591122 4.0317211151 342 1311867730.0230469704 0.0656663552 0.1116251076 0.2374686003 0.0052436813 0.1171830000 0.0117550000 0.0449600000 0.0000270000 0.0006850000 0.0396370000 26858828 96830484 1768972288 3.9870069027 3.9498889446 4.0301966667 343 1311867730.0557899475 0.0636953488 0.1114853707 0.2374686003 0.0052385799 0.1169850000 0.0123010000 0.0378880000 0.0002910000 0.0002730000 0.0493650000 26861046 96830484 1767600128 3.9853935242 3.9509806633 4.0296068192 344 1311867730.0871100426 0.0639404580 0.1113471588 0.2374686003 0.0052311200 0.1140620000 0.0095130000 0.0438310000 0.0000270000 0.0003180000 0.0396240000 26863232 96830484 1769320448 3.9856858253 3.9507908821 4.0295882225 345 1311867730.1231229305 0.0630662516 0.1112072141 0.2374686003 0.0052242479 0.1598450000 0.0124840000 0.0647910000 0.0002870000 0.0002700000 0.0717530000 26865482 96830484 1767964672 3.9849524498 3.9511981010 4.0290985107 346 1311867730.1568520069 0.0617379285 0.1110642393 0.2374686003 0.0052176311 0.1118300000 0.0090860000 0.0497960000 0.0000270000 0.0002990000 0.0391760000 26867700 96830484 1769574400 3.9857347012 3.9527888298 4.0278625488 347 1311867730.1882419586 0.0595104955 0.1109156694 0.2374686003 0.0052131512 0.1381480000 0.0116340000 0.0662000000 0.0002920000 0.0003550000 0.0465300000 26869854 96830484 1768218624 3.9857127666 3.9543626308 4.0257973671 348 1311867730.2224810123 0.0588592067 0.1107660819 0.2374686003 0.0052062655 0.1144210000 0.0096110000 0.0506520000 0.0000300000 0.0003700000 0.0387800000 26872104 96830484 1769955328 3.9852540493 3.9548830986 4.0259885788 349 1311867730.2575879097 0.0588833541 0.1106174208 0.2374686003 0.0052006723 0.1539830000 0.0118070000 0.0603580000 0.0002930000 0.0003520000 0.0709350000 26874322 96830484 1768591360 3.9875521660 3.9562466145 4.0251817703 350 1311867730.2914879322 0.0594985336 0.1104713668 0.2374686003 0.0051949703 0.1212970000 0.0094180000 0.0656530000 0.0000270000 0.0002910000 0.0359570000 26876540 96830484 1770356736 3.9883980751 3.9568836689 4.0262928009 351 1311867730.3230810165 0.0601777956 0.1103280803 0.2374686003 0.0051928025 0.1362550000 0.0116810000 0.0661770000 0.0002870000 0.0002800000 0.0455310000 26878726 96830484 1768992768 3.9905102253 3.9574644566 4.0257239342 352 1311867730.3554260731 0.0580505989 0.1101795647 0.2374686003 0.0051913066 0.1346930000 0.0112360000 0.0671350000 0.0000280000 0.0003500000 0.0385270000 26880912 96830484 1767600128 3.9873812199 3.9573163986 4.0254483223 353 1311867730.3982920647 0.0596616976 0.1100364546 0.2374686003 0.0051850804 0.1585110000 0.0098210000 0.0676740000 0.0002890000 0.0003400000 0.0702690000 26883258 96830484 1769193472 3.9904165268 3.9579865932 4.0259079933 354 1311867730.4225230217 0.0604993999 0.1098965194 0.2374686003 0.0051903256 0.1347300000 0.0113650000 0.0665560000 0.0000250000 0.0003540000 0.0379770000 26885348 96830484 1767837696 3.9924914837 3.9593889713 4.0263223648 355 1311867730.4600110054 0.0616727360 0.1097606778 0.2374686003 0.0051835225 0.1157900000 0.0096220000 0.0448520000 0.0003130000 0.0002780000 0.0447520000 26887598 96830484 1769574400 3.9932520390 3.9587371349 4.0260405540 356 1311867730.4948410988 0.0638090000 0.1096316000 0.2374686003 0.0051781534 0.1372030000 0.0118680000 0.0669460000 0.0000280000 0.0003520000 0.0382580000 26889816 96830484 1768321024 3.9959051609 3.9586074352 4.0265507698 357 1311867730.5300729275 0.0619735159 0.1094981040 0.2374686003 0.0051726904 0.1365180000 0.0099900000 0.0456760000 0.0003220000 0.0002820000 0.0701540000 26892034 96830484 1769828352 3.9938740730 3.9592328072 4.0262556076 358 1311867730.5597670078 0.0635211617 0.1093696768 0.2374686003 0.0051673924 0.1005960000 0.0116150000 0.0387710000 0.0000280000 0.0002890000 0.0394440000 26894188 96830484 1768464384 3.9952390194 3.9588146210 4.0271301270 359 1311867730.5940020084 0.0616475083 0.1092367459 0.2374686003 0.0051643300 0.1343060000 0.0097350000 0.0592700000 0.0002940000 0.0002740000 0.0507900000 26896438 96830484 1770209280 3.9924805164 3.9588100910 4.0267553329 360 1311867730.6230149269 0.0623791106 0.1091065858 0.2374686003 0.0051668127 0.1372020000 0.0120030000 0.0701160000 0.0000240000 0.0003600000 0.0376990000 26898528 96830484 1768865792 3.9959123135 3.9606273174 4.0267429352 361 1311867730.6614060402 0.0608445518 0.1089728960 0.2374686003 0.0051607101 0.1584980000 0.0097430000 0.0690400000 0.0002890000 0.0002660000 0.0690450000 26900810 96830484 1770610688 3.9944014549 3.9607415199 4.0261230469 362 1311867730.6922950745 0.0605023913 0.1088389996 0.2374686003 0.0051546765 0.1346240000 0.0114670000 0.0680940000 0.0000270000 0.0002920000 0.0379800000 26902996 96830484 1769246720 3.9955577850 3.9617359638 4.0255985260 363 1311867730.7275629044 0.0608085096 0.1087066842 0.2374686003 0.0051572261 0.1356380000 0.0113570000 0.0608610000 0.0002860000 0.0003450000 0.0445320000 26905214 96830484 1767854080 3.9977726936 3.9626038074 4.0246100426 364 1311867730.7572948933 0.0620071590 0.1085783888 0.2374686003 0.0051535464 0.1350390000 0.0097360000 0.0667250000 0.0000290000 0.0002860000 0.0373070000 26907368 96830484 1769574400 4.0001606941 3.9631032944 4.0248031616 365 1311867730.7932779789 0.0589009300 0.1084422862 0.2374686003 0.0051480413 0.1539430000 0.0116690000 0.0624570000 0.0002980000 0.0003470000 0.0687590000 26909650 96830484 1768226816 3.9977221489 3.9641141891 4.0230760574 366 1311867730.8240480423 0.0615224019 0.1083140898 0.2374686003 0.0051442632 0.1225980000 0.0092640000 0.0667890000 0.0000250000 0.0002950000 0.0358310000 26911772 96830484 1769828352 4.0005221367 3.9626681805 4.0232090950 367 1311867730.8591129780 0.0589493141 0.1081795808 0.2374686003 0.0051407669 0.1174220000 0.0119870000 0.0518220000 0.0002870000 0.0003590000 0.0426370000 26914022 96830484 1768583168 3.9991188049 3.9643251896 4.0223464966 368 1311867730.8922739029 0.0587358475 0.1080452229 0.2374686003 0.0051354175 0.1349610000 0.0094600000 0.0765780000 0.0000280000 0.0002900000 0.0370650000 26916144 96830484 1770209280 3.9993970394 3.9648954868 4.0232238770 369 1311867730.9270720482 0.0598526262 0.1079146196 0.2374686003 0.0051313936 0.1585420000 0.0116320000 0.0676310000 0.0003490000 0.0002640000 0.0682270000 26918394 96830484 1768845312 4.0024118423 3.9659976959 4.0237674713 370 1311867730.9611239433 0.0595861673 0.1077840022 0.2374686003 0.0051287846 0.1329500000 0.0094060000 0.0668660000 0.0000270000 0.0002870000 0.0369160000 26920580 96830484 1770590208 4.0028758049 3.9668774605 4.0245857239 371 1311867730.9928169250 0.0610489100 0.1076580316 0.2374686003 0.0051279706 0.1387040000 0.0118670000 0.0674940000 0.0002850000 0.0002660000 0.0437610000 26922766 96830484 1769246720 4.0058503151 3.9667570591 4.0241928101 372 1311867731.0221049786 0.0614807010 0.1075338990 0.2374686003 0.0051217961 0.1351240000 0.0110900000 0.0683150000 0.0000270000 0.0002870000 0.0364490000 26924920 96830484 1767837696 4.0068378448 3.9665226936 4.0242886543 373 1311867731.0609729290 0.0592213087 0.1074043746 0.2374686003 0.0051180402 0.1541990000 0.0095720000 0.0665350000 0.0002960000 0.0002710000 0.0672040000 26927202 96830484 1769447424 4.0056848526 3.9678087234 4.0242171288 374 1311867731.0900061131 0.0610148273 0.1072803384 0.2374686003 0.0051152357 0.1388610000 0.0113800000 0.0681880000 0.0000900000 0.0002950000 0.0365330000 26929324 96830484 1768099840 4.0079998970 3.9668264389 4.0245022774 375 1311867731.1276559830 0.0627338365 0.1071615477 0.2374686003 0.0051110338 0.1361030000 0.0100350000 0.0666390000 0.0003600000 0.0002780000 0.0426490000 26931606 96830484 1769828352 4.0111069679 3.9663810730 4.0241866112 376 1311867731.1551880836 0.0613927469 0.1070398222 0.2374686003 0.0051049196 0.1372890000 0.0117110000 0.0674350000 0.0000270000 0.0003600000 0.0362400000 26933728 96830484 1768464384 4.0107026100 3.9679446220 4.0252408981 377 1311867731.1935870647 0.0612194166 0.1069182826 0.2374686003 0.0050997675 0.1581080000 0.0099990000 0.0692970000 0.0003920000 0.0002850000 0.0676720000 26935978 96830484 1770082304 4.0116367340 3.9683010578 4.0252175331 378 1311867731.2235820293 0.0619015470 0.1067991907 0.2374686003 0.0050930436 0.1320310000 0.0115190000 0.0678990000 0.0003310000 0.0003150000 0.0361860000 26938164 96830484 1768853504 4.0127611160 3.9680309296 4.0260982513 379 1311867731.2602028847 0.0605358519 0.1066771239 0.2374686003 0.0050871345 0.1153560000 0.0097840000 0.0461000000 0.0002970000 0.0002840000 0.0427990000 26940382 96830484 1770463232 4.0128650665 3.9689259529 4.0256428719 380 1311867731.2900059223 0.0603831895 0.1065552977 0.2374686003 0.0051110570 0.1163440000 0.0117350000 0.0462980000 0.0000260000 0.0003690000 0.0368500000 26942536 96830484 1769107456 4.0139899254 3.9692008495 4.0256853104 381 1311867731.3230779171 0.0604503453 0.1064342874 0.2374686003 0.0051371970 0.1580240000 0.0122200000 0.0688290000 0.0003630000 0.0002780000 0.0656850000 26944754 96830484 1767854080 4.0153179169 3.9692173004 4.0250158310 382 1311867731.3570859432 0.0682764053 0.1063343976 0.2374686003 0.0051659856 0.1332500000 0.0094540000 0.0672150000 0.0000260000 0.0002880000 0.0357110000 26947004 96830484 1769447424 4.0257434845 3.9687249660 4.0253229141 383 1311867731.3915760517 0.0631618127 0.1062216755 0.2374686003 0.0051647215 0.1378640000 0.0123260000 0.0630410000 0.0002870000 0.0002670000 0.0426480000 26949190 96830484 1768091648 4.0208892822 3.9688985348 4.0240879059 384 1311867731.4279849529 0.0639255568 0.1061115293 0.2374686003 0.0051604474 0.1159120000 0.0097820000 0.0515850000 0.0000300000 0.0002910000 0.0351990000 26951472 96830484 1769828352 4.0226693153 3.9683687687 4.0230808258 385 1311867731.4602010250 0.0585135520 0.1059878982 0.2374686003 0.0051694989 0.1572730000 0.0117510000 0.0692050000 0.0002840000 0.0002720000 0.0650880000 26953658 96830484 1768464384 4.0169939995 3.9686269760 4.0219855309 386 1311867731.4926180840 0.0549567714 0.1058556932 0.2374686003 0.0051680851 0.1171110000 0.0095980000 0.0568860000 0.0000270000 0.0002830000 0.0345200000 26955844 96830484 1770082304 4.0146183968 3.9702732563 4.0206623077 387 1311867731.5259540081 0.0569093525 0.1057292169 0.2374686003 0.0051640053 0.1371990000 0.0117360000 0.0699910000 0.0003550000 0.0002680000 0.0414100000 26958030 96830484 1768718336 4.0187582970 3.9708733559 4.0204610825 388 1311867731.5589148998 0.0549255572 0.1055982796 0.2374686003 0.0051632943 0.1332800000 0.0094770000 0.0677450000 0.0000840000 0.0002860000 0.0349070000 26960216 96830484 1770463232 4.0183634758 3.9720914364 4.0194635391 389 1311867731.5967359543 0.0516844876 0.1054596838 0.2374686003 0.0051727765 0.1298620000 0.0123870000 0.0417950000 0.0003830000 0.0002850000 0.0643150000 26962530 96830484 1769209856 4.0151171684 3.9726960659 4.0191273689 390 1311867731.6247410774 0.0522400029 0.1053232230 0.2374686003 0.0051752251 0.1045840000 0.0110320000 0.0349250000 0.0000280000 0.0003540000 0.0366210000 26964620 96830484 1766178816 4.0154309273 3.9722635746 4.0195508003 391 1311867731.6616659164 0.0509396233 0.1051841345 0.2374686003 0.0051816215 0.1166230000 0.0105830000 0.0529750000 0.0003590000 0.0002810000 0.0416660000 26966902 96830484 1766424576 4.0144257545 3.9727315903 4.0196256638 392 1311867731.6925039291 0.0501270145 0.1050436827 0.2374686003 0.0051828060 0.0956080000 0.0094510000 0.0379270000 0.0000280000 0.0006940000 0.0364300000 26969056 96830484 1765281792 4.0144758224 3.9732334614 4.0194616318 393 1311867731.7299311161 0.0484283529 0.1048996233 0.2374686003 0.0051778180 0.1749910000 0.0096230000 0.0821690000 0.0002950000 0.0003540000 0.0669120000 26971338 96830484 1765044224 4.0124073029 3.9727711678 4.0198535919 394 1311867731.7615330219 0.0463716760 0.1047510753 0.2374686003 0.0051738242 0.1338330000 0.0097350000 0.0690800000 0.0000250000 0.0002870000 0.0340250000 26973524 96830484 1766543360 4.0103154182 3.9727623463 4.0196013451 395 1311867731.7939310074 0.0445410311 0.1045986448 0.2374686003 0.0051688573 0.1008620000 0.0095150000 0.0411040000 0.0010110000 0.0002760000 0.0383880000 26975710 96830484 1768304640 4.0087757111 3.9731962681 4.0196013451 396 1311867731.8252151012 0.0469401814 0.1044530426 0.2374686003 0.0051783025 0.1169730000 0.0097190000 0.0631380000 0.0000280000 0.0002860000 0.0332770000 26977864 96830484 1769955328 4.0116081238 3.9716963768 4.0193099976 397 1311867731.8593230247 0.0445239507 0.1043020877 0.2374686003 0.0051917580 0.1548150000 0.0115460000 0.0686330000 0.0003590000 0.0002730000 0.0631560000 26980082 96830484 1768599552 4.0094051361 3.9720108509 4.0186963081 398 1311867731.8910930157 0.0447091833 0.1041523568 0.2374686003 0.0051980782 0.1356650000 0.0094600000 0.0700150000 0.0000290000 0.0003530000 0.0339980000 26982300 96830484 1770336256 4.0107512474 3.9722166061 4.0182728767 399 1311867731.9224479198 0.0456545353 0.1040057457 0.2374686003 0.0051926849 0.1384010000 0.0122940000 0.0673130000 0.0002930000 0.0003440000 0.0405410000 26984486 96830484 1768992768 4.0127410889 3.9721210003 4.0177426338 400 1311867731.9598410130 0.0448873080 0.1038579496 0.2374686003 0.0051865170 0.1337810000 0.0108220000 0.0682290000 0.0000290000 0.0003570000 0.0336940000 26986704 96830484 1767600128 4.0126242638 3.9722383022 4.0173010826 401 1311867731.9915709496 0.0410448276 0.1037013084 0.2374686003 0.0051854945 0.1512180000 0.0096940000 0.0681090000 0.0002860000 0.0004600000 0.0620710000 26988890 96830484 1769209856 4.0093221664 3.9736149311 4.0165791512 402 1311867732.0239229202 0.0397756957 0.1035422895 0.2374686003 0.0051871467 0.1246430000 0.0111850000 0.0701940000 0.0000270000 0.0002850000 0.0320410000 26991076 96830484 1767964672 4.0079717636 3.9723002911 4.0159177780 403 1311867732.0619950294 0.0404076315 0.1033856278 0.2374686003 0.0051824930 0.1338420000 0.0095530000 0.0690400000 0.0003560000 0.0002730000 0.0406360000 26993358 96830484 1769574400 4.0091133118 3.9722881317 4.0149936676 404 1311867732.0918290615 0.0376236811 0.1032228507 0.2374686003 0.0051835485 0.1354310000 0.0115120000 0.0678640000 0.0000280000 0.0002870000 0.0334550000 26995512 96830484 1768226816 4.0067501068 3.9733366966 4.0141191483 405 1311867732.1221950054 0.0378719717 0.1030614905 0.2374686003 0.0051826055 0.1554620000 0.0099260000 0.0570850000 0.0002890000 0.0005070000 0.0645660000 26997698 96830484 1769975808 4.0070281029 3.9721901417 4.0132474899 406 1311867732.1605980396 0.0361891948 0.1028967804 0.2374686003 0.0051819163 0.1376830000 0.0121600000 0.0694610000 0.0000280000 0.0002830000 0.0339750000 26999948 96830484 1768611840 4.0060896873 3.9729483128 4.0124149323 407 1311867732.1931400299 0.0347230136 0.1027292773 0.2374686003 0.0051952072 0.1363200000 0.0098360000 0.0687030000 0.0003020000 0.0003430000 0.0402240000 27002166 96830484 1770356736 4.0060420036 3.9740772247 4.0116987228 408 1311867732.2232089043 0.0346886329 0.1025625110 0.2374686003 0.0052214288 0.1360690000 0.0118560000 0.0675250000 0.0000270000 0.0002890000 0.0334130000 27004288 96830484 1768992768 4.0057063103 3.9732000828 4.0108351707 409 1311867732.2590498924 0.0338310748 0.1023944635 0.2374686003 0.0052836836 0.1533360000 0.0115960000 0.0679220000 0.0002900000 0.0003420000 0.0621140000 27006538 96830484 1767600128 4.0064282417 3.9752795696 4.0102915764 410 1311867732.2903969288 0.0316691138 0.1022219626 0.2374686003 0.0052991915 0.1147620000 0.0097060000 0.0461340000 0.0000290000 0.0006830000 0.0333110000 27008724 96830484 1769193472 4.0033407211 3.9747643471 4.0103454590 411 1311867732.3218240738 0.0316771120 0.1020503207 0.2374686003 0.0052962360 0.1387600000 0.0123500000 0.0667600000 0.0003490000 0.0002760000 0.0403400000 27010910 96830484 1767948288 4.0033235550 3.9739484787 4.0095973015 412 1311867732.3607840538 0.0315638557 0.1018792370 0.2374686003 0.0052898859 0.1165180000 0.0096340000 0.0566180000 0.0000270000 0.0007990000 0.0332770000 27013192 96830484 1769574400 4.0055494308 3.9750657082 4.0089745522 413 1311867732.3899528980 0.0300789122 0.1017053863 0.2374686003 0.0052847059 0.1531470000 0.0113280000 0.0684900000 0.0002910000 0.0003460000 0.0616950000 27015314 96830484 1768226816 4.0043635368 3.9753317833 4.0084366798 414 1311867732.4218940735 0.0307049304 0.1015338877 0.2374686003 0.0052806660 0.1215770000 0.0095430000 0.0692430000 0.0000270000 0.0003580000 0.0318030000 27017532 96830484 1769955328 4.0056056976 3.9741842747 4.0074872971 415 1311867732.4593050480 0.0286871511 0.1013583533 0.2374686003 0.0052786007 0.1358760000 0.0114500000 0.0687850000 0.0002920000 0.0003500000 0.0396240000 27019782 96830484 1768611840 4.0050010681 3.9757373333 4.0069370270 416 1311867732.4918489456 0.0271700267 0.1011800160 0.2374686003 0.0052759403 0.0964700000 0.0097870000 0.0394760000 0.0000240000 0.0003660000 0.0350230000 27022000 96830484 1770356736 4.0029220581 3.9754688740 4.0063886642 417 1311867732.5229809284 0.0286751110 0.1010061433 0.2374686003 0.0052790868 0.1759930000 0.0117440000 0.0858250000 0.0003740000 0.0002840000 0.0667120000 27024154 96830484 1768992768 4.0078873634 3.9762704372 4.0053343773 418 1311867732.5698928833 0.0253849421 0.1008252314 0.2374686003 0.0052778743 0.1155550000 0.0108890000 0.0511170000 0.0000290000 0.0003030000 0.0337320000 27026564 96830484 1767600128 4.0052566528 3.9780578613 4.0052332878 419 1311867732.5926280022 0.0236775726 0.1006411081 0.2374686003 0.0052748304 0.1360700000 0.0095590000 0.0676110000 0.0003030000 0.0003440000 0.0400830000 27028622 96830484 1769193472 4.0024108887 3.9780337811 4.0048856735 420 1311867732.6242370605 0.0240780059 0.1004588150 0.2374686003 0.0052761026 0.1364890000 0.0114010000 0.0680770000 0.0000280000 0.0003180000 0.0335200000 27030808 96830484 1767837696 4.0042920113 3.9778957367 4.0040798187 421 1311867732.6630299091 0.0220624469 0.1002726003 0.2374686003 0.0052731038 0.1523590000 0.0101930000 0.0689150000 0.0003170000 0.0003450000 0.0616700000 27033090 96830484 1769594880 4.0020694733 3.9787175655 4.0042290688 422 1311867732.6922440529 0.0214332286 0.1000857772 0.2374686003 0.0052697802 0.1189090000 0.0113670000 0.0466360000 0.0000310000 0.0003060000 0.0335410000 27035244 96830484 1768210432 4.0032811165 3.9802386761 4.0041146278 423 1311867732.7260940075 0.0217484999 0.0999005827 0.2374686003 0.0052641367 0.0992230000 0.0100370000 0.0410950000 0.0003850000 0.0005150000 0.0364640000 27037462 96830484 1769828352 4.0028324127 3.9791886806 4.0034875870 424 1311867732.7601239681 0.0199623182 0.0997120490 0.2374686003 0.0052670836 0.1139390000 0.0114060000 0.0469170000 0.0000320000 0.0005250000 0.0329700000 27039648 96830484 1768464384 3.9988503456 3.9796149731 4.0031952858 425 1311867732.7919039726 0.0199457910 0.0995243637 0.2374686003 0.0052640419 0.1512330000 0.0100550000 0.0678370000 0.0003040000 0.0003510000 0.0617630000 27041866 96830484 1770209280 4.0019907951 3.9812977314 4.0030193329 426 1311867732.8280360699 0.0195726231 0.0993366836 0.2374686003 0.0052637585 0.1241600000 0.0117460000 0.0684030000 0.0000300000 0.0005390000 0.0322100000 27044084 96830484 1768865792 3.9985184669 3.9802000523 4.0024676323 427 1311867732.8589270115 0.0187548790 0.0991479674 0.2374686003 0.0052598278 0.0957030000 0.0093750000 0.0354100000 0.0003080000 0.0002840000 0.0392850000 27046270 96830484 1770590208 3.9986884594 3.9814493656 4.0023422241 428 1311867732.8912909031 0.0178499538 0.0989580188 0.2374686003 0.0052577826 0.1548450000 0.0117270000 0.0855910000 0.0000290000 0.0003820000 0.0374590000 27048456 96830484 1769246720 3.9962456226 3.9821662903 4.0023360252 429 1311867732.9262781143 0.0173521079 0.0987677952 0.2374686003 0.0052518736 0.1565330000 0.0117970000 0.0636130000 0.0003160000 0.0002750000 0.0636670000 27050706 96830484 1767948288 3.9971613884 3.9832642078 4.0026655197 430 1311867732.9602870941 0.0182913691 0.0985806407 0.2374686003 0.0052518514 0.1347690000 0.0096100000 0.0724640000 0.0000300000 0.0003110000 0.0328310000 27052892 96830484 1769463808 3.9953367710 3.9814867973 4.0026974678 431 1311867732.9987640381 0.0178168491 0.0983932537 0.2374686003 0.0052480333 0.1199570000 0.0114410000 0.0465150000 0.0003230000 0.0003510000 0.0390740000 27055206 96830484 1768099840 3.9974906445 3.9821276665 4.0026288033 432 1311867733.0276939869 0.0175683945 0.0982061592 0.2374686003 0.0052477538 0.1723110000 0.0091680000 0.1017600000 0.0000320000 0.0003070000 0.0364670000 27057360 96830484 1769828352 3.9931168556 3.9825124741 4.0033440590 433 1311867733.0607628822 0.0189379789 0.0980230918 0.2374686003 0.0052654938 0.1533380000 0.0122890000 0.0691240000 0.0003670000 0.0002740000 0.0600440000 27059546 96830484 1768464384 3.9942586422 3.9804222584 4.0032596588 434 1311867733.0977020264 0.0177812260 0.0978382027 0.2374686003 0.0052621447 0.1396750000 0.0094760000 0.0712370000 0.0000270000 0.0003760000 0.0324390000 27061796 96830484 1770098688 3.9939825535 3.9817237854 4.0033311844 435 1311867733.1263020039 0.0174589287 0.0976534227 0.2374686003 0.0052605178 0.1369760000 0.0123050000 0.0585580000 0.0003000000 0.0003490000 0.0385630000 27063918 96830484 1768873984 3.9903881550 3.9831280708 4.0038561821 436 1311867733.1625030041 0.0199277308 0.0974751528 0.2374686003 0.0052622948 0.0983490000 0.0099230000 0.0454370000 0.0000300000 0.0006920000 0.0312800000 27066168 96830484 1770471424 3.9896945953 3.9799582958 4.0035576820 437 1311867733.1926651001 0.0197428111 0.0972972756 0.2374686003 0.0052612906 0.1535740000 0.0116410000 0.0700670000 0.0003050000 0.0002750000 0.0599590000 27068322 96830484 1769107456 3.9879002571 3.9809029102 4.0036578178 438 1311867733.2259631157 0.0186850298 0.0971177956 0.2374686003 0.0052585289 0.1364020000 0.0110900000 0.0687390000 0.0000250000 0.0003000000 0.0321010000 27070540 96830484 1767735296 3.9886429310 3.9825637341 4.0039844513 439 1311867733.2618060112 0.0204556957 0.0969431666 0.2374686003 0.0052568280 0.1367000000 0.0098160000 0.0701650000 0.0003360000 0.0002740000 0.0385470000 27072790 96830484 1769455616 3.9857897758 3.9820055962 4.0040774345 440 1311867733.2919199467 0.0214130450 0.0967715073 0.2374686003 0.0052521721 0.1172080000 0.0114280000 0.0530760000 0.0000280000 0.0003730000 0.0325850000 27074912 96830484 1768108032 3.9842383862 3.9814984798 4.0037226677 441 1311867733.3300418854 0.0203343723 0.0965981804 0.2374686003 0.0052592907 0.1499580000 0.0095090000 0.0688490000 0.0003090000 0.0003460000 0.0595950000 27077194 96830484 1769836544 3.9858627319 3.9818093777 4.0036435127 442 1311867733.3602790833 0.0205355305 0.0964260930 0.2374686003 0.0052566877 0.1385330000 0.0117010000 0.0696610000 0.0000310000 0.0003140000 0.0325700000 27079380 96830484 1768472576 3.9870936871 3.9805467129 4.0030908585 443 1311867733.3923840523 0.0228219517 0.0962599437 0.2374686003 0.0052589067 0.1358430000 0.0101540000 0.0695610000 0.0003050000 0.0003600000 0.0382050000 27081566 96830484 1770217472 3.9833338261 3.9805548191 4.0029888153 444 1311867733.4289550781 0.0225793216 0.0960939964 0.2374686003 0.0052558078 0.0989610000 0.0118040000 0.0402110000 0.0000270000 0.0003030000 0.0328610000 27083816 96830484 1767186432 3.9826285839 3.9823186398 4.0029726028 445 1311867733.4588150978 0.0220854431 0.0959276850 0.2374686003 0.0052535005 0.1541180000 0.0100170000 0.0710330000 0.0004910000 0.0002910000 0.0606730000 27085906 96830484 1767571456 3.9837305546 3.9818034172 4.0024809837 446 1311867733.4956119061 0.0223731566 0.0957627645 0.2374686003 0.0052487846 0.1341280000 0.0108700000 0.0685880000 0.0000260000 0.0003010000 0.0325910000 27088092 96830484 1766322176 3.9832894802 3.9819908142 4.0022702217 447 1311867733.5290400982 0.0227354206 0.0955993924 0.2374686003 0.0052461646 0.1337550000 0.0099470000 0.0684490000 0.0003010000 0.0004480000 0.0378550000 27090310 96830484 1767931904 3.9819884300 3.9829812050 4.0024003983 448 1311867733.5630290508 0.0222040396 0.0954355635 0.2374686003 0.0052406064 0.1354750000 0.0099280000 0.0694740000 0.0000280000 0.0003000000 0.0323680000 27092528 96830484 1769582592 3.9829230309 3.9829528332 4.0021872520 449 1311867733.5922229290 0.0252267011 0.0952791963 0.2374686003 0.0052392800 0.1541550000 0.0130750000 0.0686150000 0.0003010000 0.0002950000 0.0601820000 27094650 96830484 1768235008 3.9800975323 3.9814000130 4.0018134117 450 1311867733.6283020973 0.0267582797 0.0951269276 0.2374686003 0.0052362871 0.1221120000 0.0096190000 0.0700830000 0.0000290000 0.0003000000 0.0308620000 27096900 96830484 1769984000 3.9784302711 3.9815223217 4.0021080971 451 1311867733.6601879597 0.0260283872 0.0949737158 0.2374686003 0.0052310545 0.1146860000 0.0117570000 0.0428240000 0.0003250000 0.0002750000 0.0387730000 27099086 96830484 1768620032 3.9790253639 3.9819538593 4.0017986298 452 1311867733.6917510033 0.0266045984 0.0948224567 0.2374686003 0.0052268059 0.0964130000 0.0105950000 0.0347400000 0.0000090000 0.0000840000 0.0341960000 27101272 96830484 1770217472 3.9787673950 3.9813992977 4.0015373230 453 1311867733.7288239002 0.0284300242 0.0946758950 0.2374686003 0.0052237126 0.1589660000 0.0124460000 0.0740330000 0.0005600000 0.0002900000 0.0598110000 27103522 96830484 1768853504 3.9776301384 3.9802341461 4.0015287399 454 1311867733.7597820759 0.0314458609 0.0945366218 0.2374686003 0.0052197649 0.1143020000 0.0095290000 0.0574060000 0.0000300000 0.0003090000 0.0327280000 27105644 96830484 1770618880 3.9746568203 3.9796605110 4.0018897057 455 1311867733.7924160957 0.0302572530 0.0943953484 0.2374686003 0.0052447553 0.1373060000 0.0116700000 0.0698110000 0.0003020000 0.0002910000 0.0385250000 27107830 96830484 1769254912 3.9759731293 3.9798779488 4.0019216537 456 1311867733.8282589912 0.0347251073 0.0942644927 0.2374686003 0.0052495881 0.1345390000 0.0112610000 0.0693960000 0.0000280000 0.0003020000 0.0322060000 27110080 96830484 1767845888 3.9726567268 3.9778590202 4.0015482903 457 1311867733.8608579636 0.0319689102 0.0941281785 0.2374686003 0.0052464237 0.1524730000 0.0101730000 0.0698670000 0.0005000000 0.0002740000 0.0603490000 27112202 96830484 1769455616 3.9754667282 3.9790844917 4.0010166168 458 1311867733.8918149471 0.0335140973 0.0939958333 0.2374686003 0.0052419473 0.1231800000 0.0112610000 0.0689730000 0.0000290000 0.0002970000 0.0308920000 27114324 96830484 1768099840 3.9740598202 3.9792947769 4.0009007454 459 1311867733.9289460182 0.0349783376 0.0938672549 0.2374686003 0.0052369306 0.1119870000 0.0096540000 0.0409210000 0.0003060000 0.0010300000 0.0380700000 27116574 96830484 1769836544 3.9735140800 3.9778573513 4.0003814697 460 1311867733.9595899582 0.0387615487 0.0937474599 0.2374686003 0.0052431636 0.1192660000 0.0127480000 0.0566370000 0.0000280000 0.0003820000 0.0330480000 27118760 96830484 1768472576 3.9702758789 3.9761335850 4.0002932549 461 1311867733.9941790104 0.0394804515 0.0936297440 0.2374686003 0.0052421247 0.1335540000 0.0094150000 0.0401920000 0.0003880000 0.0002770000 0.0602100000 27120978 96830484 1770090496 3.9702024460 3.9762709141 4.0005984306 462 1311867734.0275731087 0.0443227813 0.0935230190 0.2374686003 0.0052570432 0.1370830000 0.0121450000 0.0686610000 0.0000260000 0.0003540000 0.0326840000 27123228 96830484 1768734720 3.9660346508 3.9734907150 4.0006608963 463 1311867734.0599920750 0.0421252474 0.0934120087 0.2374686003 0.0052533263 0.1224960000 0.0096800000 0.0684030000 0.0002930000 0.0003400000 0.0323920000 27125382 96830484 1770471424 3.9684174061 3.9741227627 4.0003118515 464 1311867734.0956780910 0.0412753969 0.0932996453 0.2374686003 0.0052486266 0.1305400000 0.0118720000 0.0678580000 0.0000270000 0.0002880000 0.0320100000 27127632 96830484 1769127936 3.9695763588 3.9742877483 4.0003147125 465 1311867734.1274170876 0.0444118753 0.0931945103 0.2374686003 0.0052468981 0.1508530000 0.0110970000 0.0677570000 0.0003600000 0.0002760000 0.0596230000 27129850 96830484 1767735296 3.9676365852 3.9714443684 3.9998650551 466 1311867734.1618878841 0.0435399935 0.0930879556 0.2374686003 0.0052473154 0.1223540000 0.0095780000 0.0694890000 0.0000280000 0.0003590000 0.0314490000 27132036 96830484 1769476096 3.9683940411 3.9727320671 3.9994876385 467 1311867734.1942350864 0.0431054458 0.0929809266 0.2374686003 0.0052432032 0.1361080000 0.0113560000 0.0684430000 0.0002840000 0.0002680000 0.0383570000 27134254 96830484 1768091648 3.9687409401 3.9741032124 3.9995062351 468 1311867734.2291829586 0.0466687977 0.0928819691 0.2374686003 0.0052461926 0.1337660000 0.0095770000 0.0680290000 0.0000270000 0.0002920000 0.0320920000 27136440 96830484 1769709568 3.9661595821 3.9713807106 3.9993336201 469 1311867734.2607750893 0.0453359671 0.0927805917 0.2374686003 0.0052425923 0.1411930000 0.0117190000 0.0580040000 0.0003040000 0.0003520000 0.0590590000 27138626 96830484 1768361984 3.9673299789 3.9726393223 3.9992120266 470 1311867734.2941219807 0.0445748307 0.0926780262 0.2374686003 0.0052399545 0.1321400000 0.0092060000 0.0690410000 0.0000290000 0.0003000000 0.0323940000 27140812 96830484 1770110976 3.9679908752 3.9737651348 3.9995894432 471 1311867734.3263280392 0.0437051542 0.0925740499 0.2374686003 0.0052376301 0.1009700000 0.0125270000 0.0395430000 0.0012230000 0.0002910000 0.0356930000 27142998 96830484 1768747008 3.9692630768 3.9735085964 3.9994869232 472 1311867734.3610401154 0.0444883555 0.0924721734 0.2374686003 0.0052343594 0.1322400000 0.0095580000 0.0687060000 0.0000310000 0.0003030000 0.0322210000 27145216 96830484 1770344448 3.9689645767 3.9728012085 3.9998002052 473 1311867734.3941841125 0.0458125137 0.0923735272 0.2374686003 0.0052390667 0.1535430000 0.0122760000 0.0701200000 0.0002990000 0.0003570000 0.0588270000 27147434 96830484 1768980480 3.9673807621 3.9740278721 4.0005493164 474 1311867734.4276480675 0.0464657694 0.0922766754 0.2374686003 0.0052335893 0.1201690000 0.0111900000 0.0573680000 0.0000270000 0.0003060000 0.0319730000 27149652 96830484 1767608320 3.9669589996 3.9737246037 4.0007224083 475 1311867734.4586091042 0.0464276001 0.0921801510 0.2374686003 0.0052299563 0.1323580000 0.0095900000 0.0682370000 0.0003090000 0.0002900000 0.0376980000 27151806 96830484 1769328640 3.9673366547 3.9729704857 4.0010561943 476 1311867734.4938759804 0.0467209108 0.0920846484 0.2374686003 0.0052253586 0.1358220000 0.0113580000 0.0682290000 0.0000270000 0.0003610000 0.0310640000 27154056 96830484 1767972864 3.9670190811 3.9741170406 4.0014801025 477 1311867734.5300569534 0.0478517488 0.0919919170 0.2374686003 0.0052207952 0.1275030000 0.0104260000 0.0473680000 0.0003560000 0.0002710000 0.0573440000 27156306 96830484 1769598976 3.9662158489 3.9738240242 4.0020837784 478 1311867734.5595300198 0.0475206040 0.0918988807 0.2374686003 0.0052192493 0.1267880000 0.0116760000 0.0687060000 0.0000270000 0.0006690000 0.0304190000 27158428 96830484 1768226816 3.9671471119 3.9734630585 4.0024385452 479 1311867734.5953910351 0.0494666509 0.0918102957 0.2374686003 0.0052168887 0.1342210000 0.0096400000 0.0694100000 0.0002900000 0.0002650000 0.0368950000 27160646 96830484 1769963520 3.9648034573 3.9741685390 4.0034856796 480 1311867734.6285231113 0.0473865792 0.0917177463 0.2374686003 0.0052124721 0.1358500000 0.0116150000 0.0686170000 0.0000300000 0.0003110000 0.0306450000 27162864 96830484 1768599552 3.9674408436 3.9742746353 4.0031018257 481 1311867734.6593229771 0.0489217564 0.0916287733 0.2374686003 0.0052076848 0.1475720000 0.0102100000 0.0675090000 0.0002890000 0.0003410000 0.0574760000 27165018 96830484 1770233856 3.9659748077 3.9736566544 4.0030713081 482 1311867734.6947479248 0.0485192575 0.0915393345 0.2374686003 0.0052043414 0.0875980000 0.0119940000 0.0290360000 0.0000270000 0.0002860000 0.0322560000 27167236 96830484 1768861696 3.9663333893 3.9734413624 4.0032668114 483 1311867734.7310240269 0.0485942252 0.0914504212 0.2374686003 0.0052032699 0.1151620000 0.0114990000 0.0537440000 0.0002850000 0.0003380000 0.0363790000 27169518 96830484 1770598400 3.9667329788 3.9732623100 4.0032887459 484 1311867734.7607629299 0.0481192879 0.0913608941 0.2374686003 0.0051982100 0.1354610000 0.0122550000 0.0692600000 0.0000280000 0.0002780000 0.0305340000 27171640 96830484 1769254912 3.9677395821 3.9731528759 4.0031647682 485 1311867734.7976419926 0.0493681915 0.0912743112 0.2374686003 0.0051954086 0.1503070000 0.0117530000 0.0694100000 0.0002790000 0.0002620000 0.0566980000 27173922 96830484 1767845888 3.9664757252 3.9737195969 4.0035834312 486 1311867734.8298120499 0.0500370115 0.0911894608 0.2374686003 0.0051918648 0.1230020000 0.0095480000 0.0704970000 0.0000290000 0.0003440000 0.0303510000 27176108 96830484 1769582592 3.9659483433 3.9742469788 4.0038871765 487 1311867734.8645250797 0.0515300259 0.0911080246 0.2374686003 0.0051884878 0.1362890000 0.0114850000 0.0706440000 0.0002860000 0.0003460000 0.0362900000 27178326 96830484 1768218624 3.9643747807 3.9756999016 4.0046653748 488 1311867734.8943901062 0.0495919660 0.0910229507 0.2374686003 0.0051895131 0.0963650000 0.0094190000 0.0424730000 0.0000290000 0.0003190000 0.0303200000 27180512 96830484 1769836544 3.9668385983 3.9747803211 4.0043115616 489 1311867734.9263660908 0.0493430980 0.0909377158 0.2374686003 0.0051843677 0.1285990000 0.0115830000 0.0476230000 0.0002960000 0.0003410000 0.0567130000 27182666 96830484 1768472576 3.9675593376 3.9743933678 4.0046052933 490 1311867734.9631719589 0.0514898039 0.0908572099 0.2374686003 0.0051829899 0.1237360000 0.0096470000 0.0694940000 0.0000310000 0.0003480000 0.0301200000 27184788 96830484 1770217472 3.9659376144 3.9742584229 4.0045776367 491 1311867734.9948470592 0.0507476330 0.0907755203 0.2374686003 0.0051846777 0.1365190000 0.0117220000 0.0696920000 0.0002880000 0.0003420000 0.0364030000 27186974 96830484 1768873984 3.9662759304 3.9743711948 4.0042810440 492 1311867735.0292239189 0.0507298820 0.0906941267 0.2374686003 0.0051842502 0.1342220000 0.0097280000 0.0718460000 0.0000270000 0.0003500000 0.0298570000 27189256 96830484 1770471424 3.9665675163 3.9747705460 4.0041060448 493 1311867735.0596508980 0.0531806275 0.0906180345 0.2374686003 0.0051810804 0.1207430000 0.0122460000 0.0409230000 0.0003970000 0.0002850000 0.0549020000 27191346 96830484 1769115648 3.9638683796 3.9751920700 4.0045709610 494 1311867735.0952830315 0.0506572761 0.0905371422 0.2374686003 0.0051857364 0.1333200000 0.0108790000 0.0694410000 0.0000280000 0.0002910000 0.0305770000 27193596 96830484 1767862272 3.9665777683 3.9747793674 4.0043301582 495 1311867735.1313030720 0.0508721992 0.0904570110 0.2374686003 0.0051835400 0.1354760000 0.0098690000 0.0700420000 0.0003080000 0.0003550000 0.0361630000 27195846 96830484 1769455616 3.9662690163 3.9755063057 4.0045604706 496 1311867735.1603751183 0.0512689278 0.0903780028 0.2374686003 0.0051783871 0.1209130000 0.0114770000 0.0656980000 0.0000270000 0.0002930000 0.0303190000 27197968 96830484 1768099840 3.9660475254 3.9752938747 4.0047702789 497 1311867735.1994349957 0.0526513942 0.0903020941 0.2374686003 0.0051764511 0.1532500000 0.0095910000 0.0748430000 0.0003900000 0.0002800000 0.0558790000 27200250 96830484 1769836544 3.9651131630 3.9739348888 4.0051174164 498 1311867735.2263538837 0.0515440442 0.0902242667 0.2374686003 0.0051746538 0.1353420000 0.0113830000 0.0699660000 0.0000270000 0.0002900000 0.0305250000 27202404 96830484 1768472576 3.9660308361 3.9753456116 4.0053257942 499 1311867735.2655019760 0.0513531715 0.0901463687 0.2374686003 0.0051698087 0.0980140000 0.0104330000 0.0354930000 0.0005410000 0.0002720000 0.0389310000 27204654 96830484 1770090496 3.9662063122 3.9761888981 4.0056385994 500 1311867735.2961549759 0.0530285016 0.0900721330 0.2374686003 0.0051724078 0.1320780000 0.0116390000 0.0820450000 0.0000080000 0.0000590000 0.0239560000 27206840 96830484 1768726528 3.9648377895 3.9749276638 4.0064344406 501 1311867735.3321089745 0.0519644916 0.0899960698 0.2374686003 0.0051706138 0.1330110000 0.0094050000 0.0423080000 0.0003150000 0.0003530000 0.0599960000 27209090 96830484 1770471424 3.9657990932 3.9762294292 4.0067267418 502 1311867735.3666970730 0.0526964478 0.0899217678 0.2374686003 0.0051734758 0.0996760000 0.0124990000 0.0428210000 0.0000310000 0.0003970000 0.0308540000 27211244 96830484 1767313408 3.9654266834 3.9754979610 4.0070962906 503 1311867735.3943350315 0.0531379171 0.0898486389 0.2374686003 0.0051858462 0.1233490000 0.0101420000 0.0699000000 0.0003130000 0.0007610000 0.0297260000 27213334 96830484 1767825408 3.9652245045 3.9757416248 4.0073723793 504 1311867735.4322299957 0.0555384941 0.0897805632 0.2374686003 0.0051878375 0.1221700000 0.0100260000 0.0675820000 0.0000280000 0.0003660000 0.0308310000 27215648 96830484 1766432768 3.9627692699 3.9766323566 4.0077886581 505 1311867735.4628560543 0.0537987351 0.0897093121 0.2374686003 0.0051847425 0.1487700000 0.0093570000 0.0704530000 0.0003640000 0.0002750000 0.0563490000 27217802 96830484 1768206336 3.9652633667 3.9767432213 4.0077495575 506 1311867735.4973869324 0.0558245964 0.0896423462 0.2374686003 0.0051834356 0.1398930000 0.0097520000 0.0716820000 0.0000300000 0.0006170000 0.0304170000 27220052 96830484 1769836544 3.9628221989 3.9769961834 4.0084280968 507 1311867735.5293200016 0.0557074361 0.0895754134 0.2374686003 0.0051789180 0.0996860000 0.0125960000 0.0363880000 0.0003290000 0.0002820000 0.0366370000 27222206 96830484 1766297600 3.9631884098 3.9769625664 4.0087938309 508 1311867735.5632629395 0.0552966967 0.0895079357 0.2374686003 0.0051744535 0.1302410000 0.0100950000 0.0728570000 0.0000280000 0.0002900000 0.0302500000 27224456 96830484 1767190528 3.9639425278 3.9764013290 4.0090470314 509 1311867735.5976569653 0.0559344143 0.0894419759 0.2374686003 0.0051698703 0.1161130000 0.0096390000 0.0363220000 0.0001140000 0.0001000000 0.0575590000 27226674 96830484 1765797888 3.9634883404 3.9765818119 4.0092091560 510 1311867735.6363260746 0.0581755303 0.0893806691 0.2374686003 0.0051698227 0.1343510000 0.0097020000 0.0749930000 0.0000310000 0.0003720000 0.0305860000 27228924 96830484 1767415808 3.9615840912 3.9758281708 4.0094509125 511 1311867735.6626520157 0.0575829111 0.0893184426 0.2374686003 0.0051691022 0.1169560000 0.0096820000 0.0518660000 0.0003040000 0.0002820000 0.0368160000 27231046 96830484 1769066496 3.9625258446 3.9749503136 4.0092449188 512 1311867735.6952130795 0.0556149632 0.0892526155 0.2374686003 0.0051681896 0.0988370000 0.0117790000 0.0403800000 0.0000290000 0.0002950000 0.0309050000 27233232 96830484 1765007360 3.9645578861 3.9749832153 4.0086898804 513 1311867735.7291250229 0.0557533950 0.0891873149 0.2374686003 0.0051672250 0.1478570000 0.0101780000 0.0685750000 0.0003570000 0.0002680000 0.0560940000 27276410 96830484 1766809600 3.9645471573 3.9755060673 4.0084667206 514 1311867735.7631659508 0.0564430170 0.0891236100 0.2374686003 0.0051667082 0.1010490000 0.0094210000 0.0436890000 0.0000300000 0.0003170000 0.0308980000 27362628 96830484 1768304640 3.9637913704 3.9769468307 4.0085759163 515 1311867735.7963778973 0.0560819469 0.0890594514 0.2374686003 0.0051680661 0.1357490000 0.0094830000 0.0684780000 0.0002920000 0.0002690000 0.0361710000 27364814 96830484 1770102784 3.9644067287 3.9769005775 4.0085043907 516 1311867735.8277759552 0.0572248399 0.0889977565 0.2374686003 0.0051736041 0.1371670000 0.0127390000 0.0703360000 0.0000270000 0.0003560000 0.0302600000 27366968 96830484 1768472576 3.9633922577 3.9778261185 4.0085968971 517 1311867735.8638889790 0.0576073006 0.0889370399 0.2374686003 0.0051699654 0.1473460000 0.0103390000 0.0688400000 0.0002860000 0.0003430000 0.0553170000 27369122 96830484 1770209280 3.9631719589 3.9780218601 4.0089368820 518 1311867735.8951849937 0.0578953624 0.0888771139 0.2374686003 0.0051660480 0.1275670000 0.0120540000 0.0703470000 0.0000300000 0.0002920000 0.0310420000 27371308 96830484 1768865792 3.9629020691 3.9785902500 4.0094847679 519 1311867735.9322230816 0.0589989759 0.0888195452 0.2374686003 0.0051634591 0.1338020000 0.0096050000 0.0686130000 0.0002940000 0.0002740000 0.0364310000 27373590 96830484 1770463232 3.9617686272 3.9796073437 4.0102663040 520 1311867735.9623689651 0.0588841140 0.0887619771 0.2374686003 0.0051613387 0.0991530000 0.0117830000 0.0430970000 0.0000300000 0.0003130000 0.0309420000 27375744 96830484 1766924288 3.9616577625 3.9799783230 4.0105695724 521 1311867735.9945859909 0.0581788383 0.0887032762 0.2374686003 0.0051580693 0.1306730000 0.0101100000 0.0351980000 0.0002920000 0.0002680000 0.0606920000 27377898 96830484 1767833600 3.9622378349 3.9803767204 4.0108489990 522 1311867736.0290079117 0.0564088263 0.0886414095 0.2374686003 0.0051562817 0.1368150000 0.0101140000 0.0761530000 0.0000300000 0.0019480000 0.0310270000 27380148 96830484 1766440960 3.9638965130 3.9809787273 4.0109987259 523 1311867736.0642199516 0.0562187694 0.0885794159 0.2374686003 0.0051530867 0.1353360000 0.0096760000 0.0711700000 0.0003620000 0.0002760000 0.0368880000 27382398 96830484 1768050688 3.9641323090 3.9804244041 4.0111184120 524 1311867736.0946779251 0.0558487736 0.0885169528 0.2374686003 0.0051504777 0.1351950000 0.0100900000 0.0696290000 0.0000280000 0.0003590000 0.0306450000 27384520 96830484 1769701376 3.9644165039 3.9809267521 4.0114855766 525 1311867736.1299190521 0.0567441434 0.0884564332 0.2374686003 0.0051533337 0.1457410000 0.0121650000 0.0646020000 0.0002910000 0.0003480000 0.0557640000 27386770 96830484 1768345600 3.9633672237 3.9808323383 4.0115957260 526 1311867736.1631360054 0.0578575283 0.0883982604 0.2374686003 0.0051497838 0.1283270000 0.0099630000 0.0701540000 0.0000290000 0.0002970000 0.0305290000 27389020 96830484 1770082304 3.9619059563 3.9807674885 4.0120100975 527 1311867736.1942429543 0.0590253249 0.0883425243 0.2374686003 0.0051517849 0.1365380000 0.0117230000 0.0697620000 0.0002910000 0.0002690000 0.0362120000 27391142 96830484 1768738816 3.9605755806 3.9811117649 4.0118570328 528 1311867736.2298679352 0.0586223379 0.0882862360 0.2374686003 0.0051542263 0.1167370000 0.0097430000 0.0633590000 0.0000290000 0.0003530000 0.0304120000 27393392 96830484 1770352640 3.9603919983 3.9814047813 4.0121908188 529 1311867736.2633900642 0.0562454499 0.0882256674 0.2374686003 0.0051595240 0.1504320000 0.0117920000 0.0698200000 0.0003030000 0.0002700000 0.0556880000 27395610 96830484 1769119744 3.9626278877 3.9815618992 4.0121102333 530 1311867736.2995250225 0.0578121729 0.0881682835 0.2374686003 0.0051563688 0.1185630000 0.0113820000 0.0470670000 0.0000260000 0.0003830000 0.0308270000 27397860 96830484 1767727104 3.9610941410 3.9794652462 4.0123391151 531 1311867736.3304500580 0.0577580631 0.0881110138 0.2374686003 0.0051571373 0.1360840000 0.0100450000 0.0697460000 0.0002870000 0.0003410000 0.0357320000 27399982 96830484 1769320448 3.9609179497 3.9811394215 4.0127372742 532 1311867736.3637149334 0.0600008182 0.0880581751 0.2374686003 0.0051552377 0.1368930000 0.0115010000 0.0689620000 0.0000290000 0.0002860000 0.0306670000 27402200 96830484 1767964672 3.9587042332 3.9803009033 4.0130591393 533 1311867736.3943159580 0.0627367720 0.0880106677 0.2374686003 0.0051515840 0.1497960000 0.0103890000 0.0706280000 0.0002870000 0.0003480000 0.0558430000 27404322 96830484 1769701376 3.9561159611 3.9787271023 4.0131974220 534 1311867736.4313519001 0.0642422587 0.0879661576 0.2374686003 0.0051705170 0.1059540000 0.0115020000 0.0490050000 0.0000250000 0.0003510000 0.0301950000 27406636 96830484 1767051264 3.9548449516 3.9799354076 4.0138659477 535 1311867736.4625089169 0.0661625564 0.0879254032 0.2374686003 0.0051672081 0.1131350000 0.0097230000 0.0478690000 0.0003550000 0.0002720000 0.0361660000 27408822 96830484 1766932480 3.9527399540 3.9798598289 4.0139923096 536 1311867736.4987530708 0.0676059425 0.0878874938 0.2374686003 0.0051632731 0.1156630000 0.0096450000 0.0542820000 0.0000260000 0.0002810000 0.0328540000 27411040 96830484 1765568512 3.9515287876 3.9784853458 4.0141549110 537 1311867736.5321619511 0.0708995312 0.0878558588 0.2374686003 0.0051784190 0.1262680000 0.0104810000 0.0456970000 0.0003140000 0.0002750000 0.0569220000 27413258 96830484 1764171776 3.9482014179 3.9798815250 4.0145707130 538 1311867736.5634689331 0.0708624870 0.0878242726 0.2374686003 0.0051738905 0.1050310000 0.0098450000 0.0482740000 0.0000280000 0.0003550000 0.0311390000 27415444 96830484 1765892096 3.9482655525 3.9792096615 4.0148668289 539 1311867736.5958600044 0.0729442909 0.0877966660 0.2374686003 0.0051700805 0.1156300000 0.0098820000 0.0482960000 0.0002910000 0.0002720000 0.0376980000 27417630 96830484 1767542784 3.9461505413 3.9772489071 4.0149078369 540 1311867736.6320459843 0.0750059113 0.0877729794 0.2374686003 0.0051808918 0.1156810000 0.0097920000 0.0481450000 0.0000280000 0.0002930000 0.0317840000 27419880 96830484 1769209856 3.9442818165 3.9786140919 4.0152406693 541 1311867736.6635379791 0.0740024894 0.0877475256 0.2374686003 0.0051968097 0.1403840000 0.0125570000 0.0588630000 0.0002870000 0.0002640000 0.0557640000 27422066 96830484 1767964672 3.9448611736 3.9779915810 4.0149326324 542 1311867736.6945500374 0.0784901083 0.0877304455 0.2374686003 0.0051979747 0.1124700000 0.0098680000 0.0590610000 0.0000260000 0.0002890000 0.0308380000 27424188 96830484 1769701376 3.9404950142 3.9757306576 4.0150814056 543 1311867736.7332150936 0.0799168721 0.0877160559 0.2374686003 0.0051958425 0.1360730000 0.0122480000 0.0697680000 0.0002980000 0.0002750000 0.0373010000 27426470 96830484 1768337408 3.9390079975 3.9763436317 4.0151267052 544 1311867736.7636179924 0.0813392997 0.0877043339 0.2374686003 0.0051958850 0.1119800000 0.0095830000 0.0433140000 0.0000270000 0.0004010000 0.0313940000 27428656 96830484 1769955328 3.9381959438 3.9767751694 4.0152311325 545 1311867736.7952749729 0.0842414498 0.0876979800 0.2374686003 0.0051945866 0.1567790000 0.0125550000 0.0590760000 0.0002890000 0.0003420000 0.0594920000 27430810 96830484 1768591360 3.9351859093 3.9759924412 4.0153446198 546 1311867736.8325269222 0.0889803022 0.0877003286 0.2374686003 0.0052127151 0.1177690000 0.0101320000 0.0648340000 0.0000250000 0.0002830000 0.0300010000 27433060 96830484 1770336256 3.9308412075 3.9766306877 4.0161786079 547 1311867736.8640279770 0.0912754461 0.0877068644 0.2374686003 0.0052194513 0.0973930000 0.0117240000 0.0346120000 0.0002950000 0.0003620000 0.0377170000 27435278 96830484 1766055936 3.9287312031 3.9786100388 4.0165381432 548 1311867736.8945000172 0.0924673453 0.0877155515 0.2374686003 0.0052176511 0.1337500000 0.0103540000 0.0781540000 0.0000310000 0.0002950000 0.0321610000 27437400 96830484 1767694336 3.9278156757 3.9770364761 4.0166730881 549 1311867736.9362800121 0.0960776582 0.0877307830 0.2374686003 0.0052208240 0.1549040000 0.0093130000 0.0735020000 0.0003620000 0.0002750000 0.0589080000 27439746 96830484 1769209856 3.9244964123 3.9778335094 4.0168337822 550 1311867736.9632000923 0.0985170528 0.0877503944 0.2374686003 0.0052235902 0.1356280000 0.0111610000 0.0710950000 0.0000270000 0.0003640000 0.0323610000 27441868 96830484 1767837696 3.9222047329 3.9795658588 4.0180792809 551 1311867736.9954400063 0.0996677503 0.0877720230 0.2374686003 0.0052237030 0.1156570000 0.0108110000 0.0481640000 0.0003650000 0.0002830000 0.0382040000 27444054 96830484 1769574400 3.9212577343 3.9779577255 4.0180606842 552 1311867737.0307478905 0.1013388857 0.0877966006 0.2374686003 0.0052202353 0.1172580000 0.0115650000 0.0546180000 0.0000310000 0.0003840000 0.0325320000 27446272 96830484 1768226816 3.9196536541 3.9775035381 4.0184612274 553 1311867737.0629029274 0.1018158868 0.0878219520 0.2374686003 0.0052175824 0.1533360000 0.0098000000 0.0713740000 0.0003030000 0.0002790000 0.0590050000 27448490 96830484 1769955328 3.9193918705 3.9787356853 4.0190663338 554 1311867737.0977239609 0.1031905562 0.0878496931 0.2374686003 0.0052137572 0.1210810000 0.0118430000 0.0642470000 0.0000260000 0.0002850000 0.0318170000 27450708 96830484 1768611840 3.9180178642 3.9780271053 4.0190310478 555 1311867737.1300530434 0.1050583497 0.0878806997 0.2374686003 0.0052103177 0.1170280000 0.0097710000 0.0590780000 0.0002970000 0.0003530000 0.0350120000 27452862 96830484 1770209280 3.9161589146 3.9772710800 4.0190634727 556 1311867737.1655049324 0.1043919548 0.0879103962 0.2374686003 0.0052070112 0.1338340000 0.0119650000 0.0701990000 0.0000270000 0.0005170000 0.0318890000 27455112 96830484 1768992768 3.9169657230 3.9788851738 4.0192446709 557 1311867737.1952710152 0.1062704250 0.0879433586 0.2374686003 0.0052032884 0.1542950000 0.0127340000 0.0698290000 0.0002950000 0.0003450000 0.0580450000 27457266 96830484 1767600128 3.9152197838 3.9782783985 4.0191082954 558 1311867737.2333149910 0.1065974534 0.0879767888 0.2374686003 0.0051988916 0.1354160000 0.0098740000 0.0703310000 0.0000280000 0.0003590000 0.0316940000 27459580 96830484 1769320448 3.9151208401 3.9776105881 4.0192985535 559 1311867737.2693018913 0.1074424237 0.0880116111 0.2374686003 0.0051997264 0.1197470000 0.0125920000 0.0546340000 0.0003050000 0.0003390000 0.0376220000 27461798 96830484 1767964672 3.9147944450 3.9785833359 4.0192298889 560 1311867737.2957379818 0.1085382700 0.0880482658 0.2374686003 0.0051968920 0.1333120000 0.0096610000 0.0716870000 0.0000270000 0.0003560000 0.0315010000 27463888 96830484 1769574400 3.9139704704 3.9789578915 4.0196866989 561 1311867737.3316531181 0.1089278907 0.0880854844 0.2374686003 0.0051928443 0.1556680000 0.0126810000 0.0721720000 0.0002890000 0.0003430000 0.0573000000 27466170 96830484 1768226816 3.9138329029 3.9780750275 4.0199041367 562 1311867737.3659460545 0.1088327542 0.0881224013 0.2374686003 0.0051884581 0.1344530000 0.0097560000 0.0725190000 0.0000320000 0.0002860000 0.0312270000 27468356 96830484 1769955328 3.9138317108 3.9783589840 4.0201463699 563 1311867737.3967239857 0.1099043936 0.0881610904 0.2374686003 0.0051849439 0.1182130000 0.0125490000 0.0495740000 0.0003740000 0.0002870000 0.0372350000 27470542 96830484 1768611840 3.9129388332 3.9785194397 4.0204596519 564 1311867737.4355359077 0.1115103662 0.0882024898 0.2374686003 0.0051817608 0.1337500000 0.0098560000 0.0670700000 0.0000280000 0.0002840000 0.0323370000 27472824 96830484 1770209280 3.9114618301 3.9787116051 4.0211191177 565 1311867737.4691100121 0.1124417931 0.0882453913 0.2374686003 0.0051775187 0.1378580000 0.0126810000 0.0439910000 0.0003020000 0.0002750000 0.0606500000 27475042 96830484 1768853504 3.9106938839 3.9785227776 4.0217466354 566 1311867737.4959459305 0.1133250669 0.0882897016 0.2374686003 0.0051733584 0.1352290000 0.0098640000 0.0736080000 0.0000290000 0.0002900000 0.0309270000 27477132 96830484 1770590208 3.9097120762 3.9785790443 4.0221538544 567 1311867737.5353999138 0.1156513095 0.0883379584 0.2374686003 0.0051715266 0.1372220000 0.0124010000 0.0670940000 0.0003630000 0.0002810000 0.0374850000 27479446 96830484 1769246720 3.9077167511 3.9779305458 4.0231142044 568 1311867737.5654399395 0.1154969707 0.0883857736 0.2374686003 0.0051677585 0.1162870000 0.0123660000 0.0542360000 0.0000280000 0.0002980000 0.0313820000 27481568 96830484 1767837696 3.9084107876 3.9781286716 4.0233049393 569 1311867737.5958089828 0.1165432930 0.0884352596 0.2374686003 0.0051636664 0.1530150000 0.0097920000 0.0733100000 0.0005150000 0.0002930000 0.0563340000 27483754 96830484 1769594880 3.9077475071 3.9777548313 4.0239391327 570 1311867737.6330978870 0.1179403216 0.0884870228 0.2374686003 0.0051595538 0.1383840000 0.0115830000 0.0724970000 0.0000280000 0.0002840000 0.0305530000 27486036 96830484 1768210432 3.9066574574 3.9777553082 4.0243782997 571 1311867737.6624519825 0.1187296659 0.0885399872 0.2374686003 0.0051554863 0.1146660000 0.0105330000 0.0442030000 0.0003040000 0.0002900000 0.0375740000 27488190 96830484 1769828352 3.9061019421 3.9768295288 4.0246262550 572 1311867737.7032339573 0.1201653108 0.0885952762 0.2374686003 0.0051511579 0.1380820000 0.0128560000 0.0734560000 0.0000290000 0.0005470000 0.0311120000 27490472 96830484 1768464384 3.9050173759 3.9760766029 4.0251665115 573 1311867737.7314720154 0.1202794760 0.0886505715 0.2374686003 0.0051468146 0.1169160000 0.0101660000 0.0377920000 0.0002960000 0.0002700000 0.0556150000 27492594 96830484 1770229760 3.9051744938 3.9762864113 4.0254154205 574 1311867737.7658560276 0.1217918918 0.0887083090 0.2374686003 0.0051439112 0.1355080000 0.0117440000 0.0733580000 0.0000270000 0.0003070000 0.0303290000 27494812 96830484 1768865792 3.9040579796 3.9760844707 4.0258502960 575 1311867737.8011269569 0.1216456816 0.0887655914 0.2374686003 0.0051407091 0.1126740000 0.0105770000 0.0498190000 0.0002870000 0.0002730000 0.0367050000 27497062 96830484 1770463232 3.9043591022 3.9764101505 4.0258693695 576 1311867737.8323190212 0.1212140992 0.0888219256 0.2374686003 0.0051363976 0.0980660000 0.0120400000 0.0427270000 0.0000290000 0.0003810000 0.0298660000 27499248 96830484 1766182912 3.9050316811 3.9763634205 4.0261592865 577 1311867737.8633110523 0.1228844449 0.0888809594 0.2374686003 0.0051421019 0.1499010000 0.0105950000 0.0555590000 0.0003690000 0.0002810000 0.0593250000 27501402 96830484 1767821312 3.9041225910 3.9761853218 4.0272006989 578 1311867737.9004418850 0.1241073534 0.0889419047 0.2374686003 0.0051383362 0.1344550000 0.0108720000 0.0672740000 0.0000260000 0.0006950000 0.0305350000 27503620 96830484 1769447424 3.9033215046 3.9756400585 4.0277566910 579 1311867737.9305500984 0.1244266853 0.0890031911 0.2374686003 0.0051381767 0.1174180000 0.0122680000 0.0439750000 0.0003060000 0.0003600000 0.0368950000 27505774 96830484 1768091648 3.9032773972 3.9750967026 4.0283322334 580 1311867737.9630560875 0.1251834780 0.0890655709 0.2374686003 0.0051342628 0.1341810000 0.0102430000 0.0669340000 0.0000300000 0.0003700000 0.0308900000 27507992 96830484 1769828352 3.9029779434 3.9750294685 4.0288343430 581 1311867737.9996941090 0.1266200542 0.0891302085 0.2374686003 0.0051306753 0.1258680000 0.0126230000 0.0435690000 0.0002990000 0.0002800000 0.0558190000 27510242 96830484 1768456192 3.9020097256 3.9743022919 4.0296902657 582 1311867738.0315399170 0.1277986765 0.0891966492 0.2374686003 0.0051278314 0.1279480000 0.0098830000 0.0727500000 0.0000260000 0.0002860000 0.0301680000 27512428 96830484 1770082304 3.9011554718 3.9750528336 4.0303955078 583 1311867738.0629770756 0.1266394705 0.0892608736 0.2374686003 0.0051247308 0.1370700000 0.0120400000 0.0730300000 0.0002880000 0.0002720000 0.0367280000 27514614 96830484 1768865792 3.9029512405 3.9765830040 4.0314264297 584 1311867738.0998299122 0.1273047477 0.0893260172 0.2374686003 0.0051221805 0.1131260000 0.0098950000 0.0490290000 0.0000280000 0.0002920000 0.0307260000 27516832 96830484 1770463232 3.9029037952 3.9750654697 4.0321960449 585 1311867738.1308510303 0.1286125928 0.0893931738 0.2374686003 0.0051201363 0.1389080000 0.0128490000 0.0563030000 0.0003070000 0.0002790000 0.0557590000 27518986 96830484 1769099264 3.9021508694 3.9739308357 4.0329246521 586 1311867738.1635079384 0.1286977232 0.0894602464 0.2374686003 0.0051162607 0.1129450000 0.0112690000 0.0431430000 0.0000280000 0.0003160000 0.0307510000 27521204 96830484 1767727104 3.9025330544 3.9735293388 4.0335297585 587 1311867738.1992070675 0.1312665641 0.0895314667 0.2374686003 0.0051140804 0.1367420000 0.0105840000 0.0739110000 0.0003170000 0.0003390000 0.0362640000 27523422 96830484 1769447424 3.9007172585 3.9729053974 4.0346655846 588 1311867738.2306089401 0.1309446096 0.0896018972 0.2374686003 0.0051130614 0.1145060000 0.0118300000 0.0457230000 0.0000270000 0.0003150000 0.0320390000 27525608 96830484 1768099840 3.9014446735 3.9713711739 4.0348157883 589 1311867738.2632689476 0.1327251941 0.0896751116 0.2374686003 0.0051113119 0.1537560000 0.0102980000 0.0736070000 0.0002860000 0.0002660000 0.0562260000 27527826 96830484 1769717760 3.9001755714 3.9702305794 4.0351395607 590 1311867738.3008689880 0.1338797510 0.0897500347 0.2374686003 0.0051075825 0.1201050000 0.0122000000 0.0560300000 0.0000290000 0.0003070000 0.0305200000 27530076 96830484 1768361984 3.8996098042 3.9698164463 4.0351986885 591 1311867738.3339769840 0.1348002404 0.0898262618 0.2374686003 0.0051048297 0.1370550000 0.0108080000 0.0745890000 0.0002920000 0.0002650000 0.0368010000 27532262 96830484 1770082304 3.8992204666 3.9693539143 4.0353231430 592 1311867738.3651630878 0.1369834393 0.0899059192 0.2374686003 0.0051019319 0.1140420000 0.0121330000 0.0434550000 0.0000270000 0.0003920000 0.0313800000 27534448 96830484 1768738816 3.8972361088 3.9694175720 4.0353150368 593 1311867738.3995900154 0.1394775361 0.0899895138 0.2374686003 0.0051005054 0.1548840000 0.0101460000 0.0741580000 0.0005190000 0.0002820000 0.0566610000 27536698 96830484 1770483712 3.8952906132 3.9703261852 4.0356488228 594 1311867738.4334011078 0.1385305524 0.0900712328 0.2374686003 0.0050971705 0.1029970000 0.0119840000 0.0446830000 0.0000320000 0.0003800000 0.0324120000 27538916 96830484 1769119744 3.8963954449 3.9710865021 4.0353350639 595 1311867738.4643430710 0.1424960345 0.0901593417 0.2374686003 0.0050949184 0.1117240000 0.0118400000 0.0437930000 0.0003250000 0.0003470000 0.0371700000 27541070 96830484 1767727104 3.8932554722 3.9699475765 4.0356531143 596 1311867738.5000250340 0.1406544596 0.0902440650 0.2374686003 0.0050938331 0.1135330000 0.0097490000 0.0491670000 0.0000990000 0.0002960000 0.0305040000 27543320 96830484 1769320448 3.8957865238 3.9715938568 4.0359020233 597 1311867738.5332009792 0.1418329328 0.0903304785 0.2374686003 0.0050903649 0.1278650000 0.0125040000 0.0448410000 0.0003510000 0.0002750000 0.0564640000 27545506 96830484 1768075264 3.8953912258 3.9726703167 4.0361895561 598 1311867738.5634350777 0.1422439814 0.0904172904 0.2374686003 0.0050876512 0.1242870000 0.0100000000 0.0620880000 0.0000280000 0.0002870000 0.0304630000 27547692 96830484 1769701376 3.8956928253 3.9709713459 4.0364017487 599 1311867738.6022439003 0.1420362443 0.0905034656 0.2374686003 0.0050857501 0.1168940000 0.0126590000 0.0438890000 0.0003900000 0.0002900000 0.0374710000 27549974 96830484 1768337408 3.8968334198 3.9706923962 4.0363173485 600 1311867738.6328980923 0.1434066743 0.0905916376 0.2374686003 0.0050839397 0.1138780000 0.0103320000 0.0469720000 0.0000300000 0.0002920000 0.0305290000 27552128 96830484 1769955328 3.8964264393 3.9720752239 4.0366520882 601 1311867738.6628730297 0.1436923891 0.0906799916 0.2374686003 0.0050829024 0.1352340000 0.0128730000 0.0472940000 0.0002980000 0.0002740000 0.0609260000 27554314 96830484 1768591360 3.8968946934 3.9716246128 4.0363345146 602 1311867738.6996099949 0.1461508572 0.0907721359 0.2374686003 0.0050803422 0.1177660000 0.0102500000 0.0560760000 0.0002430000 0.0003070000 0.0306200000 27556564 96830484 1770336256 3.8954675198 3.9703035355 4.0367293358 603 1311867738.7314729691 0.1465199739 0.0908645867 0.2374686003 0.0050893679 0.1185360000 0.0126460000 0.0513400000 0.0003220000 0.0003620000 0.0375430000 27558750 96830484 1768980480 3.8959972858 3.9715223312 4.0369420052 604 1311867738.7626600266 0.1486433446 0.0909602469 0.2374686003 0.0050872003 0.1122390000 0.0099060000 0.0433470000 0.0000300000 0.0003860000 0.0311890000 27560904 96830484 1770717184 3.8949286938 3.9713690281 4.0375280380 605 1311867738.8032259941 0.1495122463 0.0910570271 0.2374686003 0.0050900767 0.1574620000 0.0127280000 0.0624420000 0.0003090000 0.0002750000 0.0600470000 27563218 96830484 1769353216 3.8951165676 3.9710440636 4.0376596451 606 1311867738.8306779861 0.1506983787 0.0911554452 0.2374686003 0.0050916359 0.0974980000 0.0123130000 0.0368170000 0.0000310000 0.0003060000 0.0331960000 27565340 96830484 1764122624 3.8946003914 3.9714715481 4.0379223824 607 1311867738.8639259338 0.1497122049 0.0912519143 0.2374686003 0.0050884369 0.1119550000 0.0105810000 0.0441350000 0.0003200000 0.0002820000 0.0376470000 27567558 96830484 1765781504 3.8964354992 3.9721736908 4.0380711555 608 1311867738.9000120163 0.1502663791 0.0913489776 0.2374686003 0.0050895052 0.1373040000 0.0100690000 0.0740750000 0.0000310000 0.0003100000 0.0315270000 27569808 96830484 1767424000 3.8966763020 3.9718947411 4.0380177498 609 1311867738.9307610989 0.1535515040 0.0914511164 0.2374686003 0.0050912700 0.1249720000 0.0099550000 0.0434230000 0.0003850000 0.0002880000 0.0576640000 27571962 96830484 1768939520 3.8940017223 3.9712567329 4.0385689735 610 1311867738.9664750099 0.1543849260 0.0915542865 0.2374686003 0.0050892283 0.1444420000 0.0116110000 0.0757750000 0.0000280000 0.0003720000 0.0311290000 27574212 96830484 1767469056 3.8937504292 3.9723167419 4.0389733315 611 1311867738.9989941120 0.1559590548 0.0916596953 0.2374686003 0.0050854359 0.1366500000 0.0105770000 0.0721740000 0.0002990000 0.0002780000 0.0377450000 27576430 96830484 1769230336 3.8927485943 3.9721963406 4.0391297340 612 1311867739.0329539776 0.1551288664 0.0917634031 0.2374686003 0.0050851232 0.1139830000 0.0114540000 0.0435020000 0.0000300000 0.0003150000 0.0317260000 27578648 96830484 1768083456 3.8940205574 3.9707536697 4.0389561653 613 1311867739.0664470196 0.1543139219 0.0918654431 0.2374686003 0.0050828880 0.1319090000 0.0107770000 0.0488640000 0.0003690000 0.0002830000 0.0582550000 27580834 96830484 1769865216 3.8953943253 3.9714717865 4.0391969681 614 1311867739.0997900963 0.1544226259 0.0919673278 0.2374686003 0.0050798958 0.1188030000 0.0116500000 0.0490340000 0.0000290000 0.0003020000 0.0321500000 27582956 96830484 1768828928 3.8957610130 3.9727759361 4.0394067764 615 1311867739.1321549416 0.1550106555 0.0920698373 0.2374686003 0.0050778909 0.1542260000 0.0105010000 0.0771320000 0.0003060000 0.0003520000 0.0383340000 27585110 96830484 1770479616 3.8956058025 3.9719429016 4.0398893356 616 1311867739.1687150002 0.1551227868 0.0921721959 0.2374686003 0.0050744614 0.1184250000 0.0124260000 0.0567770000 0.0000900000 0.0005350000 0.0319490000 27587360 96830484 1769590784 3.8957157135 3.9719381332 4.0402145386 617 1311867739.1999289989 0.1550588161 0.0922741192 0.2374686003 0.0050740984 0.1320170000 0.0101200000 0.0484170000 0.0003880000 0.0002770000 0.0591620000 27589514 96830484 1771384832 3.8960235119 3.9724898338 4.0410528183 618 1311867739.2313010693 0.1556622833 0.0923766890 0.2374686003 0.0050710504 0.1206240000 0.0118240000 0.0606820000 0.0000270000 0.0003120000 0.0323650000 27591668 96830484 1770627072 3.8954918385 3.9718503952 4.0412650108 619 1311867739.2672259808 0.1564984918 0.0924802783 0.2374686003 0.0050673361 0.1176460000 0.0123860000 0.0553090000 0.0003840000 0.0002840000 0.0354430000 27593950 96830484 1768349696 3.8944847584 3.9714059830 4.0413503647 620 1311867739.2996931076 0.1557549685 0.0925823343 0.2374686003 0.0050694507 0.1103270000 0.0104910000 0.0435670000 0.0000260000 0.0003810000 0.0321790000 27596136 96830484 1770135552 3.8952367306 3.9709537029 4.0417599678 621 1311867739.3319859505 0.1559954733 0.0926844488 0.2374686003 0.0050683511 0.1555370000 0.0126030000 0.0537370000 0.0003760000 0.0002800000 0.0616210000 27598322 96830484 1767682048 3.8951208591 3.9720857143 4.0423092842 622 1311867739.3670029640 0.1556082964 0.0927856126 0.2374686003 0.0050664441 0.1348450000 0.0108790000 0.0711620000 0.0000270000 0.0003100000 0.0322750000 27600540 96830484 1769500672 3.8953073025 3.9716615677 4.0426054001 623 1311867739.3990058899 0.1556046754 0.0928864458 0.2374686003 0.0050625651 0.1158100000 0.0101140000 0.0457580000 0.0003860000 0.0002790000 0.0393780000 27602758 96830484 1771130880 3.8950510025 3.9723036289 4.0428390503 624 1311867739.4311320782 0.1539122760 0.0929842436 0.2374686003 0.0050591023 0.1381690000 0.0117900000 0.0729610000 0.0000290000 0.0005570000 0.0322980000 27604912 96830484 1770229760 3.8968162537 3.9726474285 4.0431399345 625 1311867739.4668490887 0.1560209692 0.0930851023 0.2374686003 0.0050563083 0.1693220000 0.0131100000 0.0598180000 0.0003180000 0.0003560000 0.0553600000 27607162 96830484 1768337408 3.8947265148 3.9717319012 4.0438508987 626 1311867739.4988598824 0.1567028761 0.0931867282 0.2374686003 0.0050595353 0.1367860000 0.0107730000 0.0696070000 0.0000270000 0.0003800000 0.0320450000 27609348 96830484 1770008576 3.8940739632 3.9709787369 4.0446038246 627 1311867739.5316400528 0.1565096080 0.0932877216 0.2374686003 0.0050558622 0.1226360000 0.0119970000 0.0630840000 0.0003750000 0.0002820000 0.0330100000 27611502 96830484 1768976384 3.8943870068 3.9718532562 4.0446386337 628 1311867739.5670249462 0.1595349014 0.0933932107 0.2374686003 0.0050560852 0.1093310000 0.0100740000 0.0439380000 0.0000290000 0.0004020000 0.0327970000 27613752 96830484 1770749952 3.8915548325 3.9721374512 4.0458607674 629 1311867739.5990490913 0.1615816802 0.0935016185 0.2374686003 0.0050527479 0.1560300000 0.0125580000 0.0532350000 0.0003250000 0.0002820000 0.0635310000 27615938 96830484 1769721856 3.8894307613 3.9707651138 4.0465545654 630 1311867739.6325490475 0.1625714004 0.0936112530 0.2374686003 0.0050491347 0.1154500000 0.0129340000 0.0493640000 0.0000280000 0.0005390000 0.0318890000 27618156 96830484 1767829504 3.8882923126 3.9717364311 4.0472717285 631 1311867739.6706740856 0.1640704125 0.0937229157 0.2374686003 0.0050469053 0.1355210000 0.0107740000 0.0714970000 0.0003860000 0.0002870000 0.0389350000 27620438 96830484 1769484288 3.8864054680 3.9713163376 4.0476646423 632 1311867739.7001221180 0.1650298238 0.0938357431 0.2374686003 0.0050429782 0.1354050000 0.0117990000 0.0719990000 0.0000290000 0.0003080000 0.0325080000 27622592 96830484 1768497152 3.8855605125 3.9711906910 4.0489172935 633 1311867739.7323939800 0.1656451225 0.0939491861 0.2374686003 0.0050402031 0.1369870000 0.0101200000 0.0547110000 0.0003830000 0.0002880000 0.0578170000 27624778 96830484 1770106880 3.8847818375 3.9721121788 4.0495152473 634 1311867739.7662999630 0.1679238230 0.0940658653 0.2374686003 0.0050384739 0.1146610000 0.0115640000 0.0494860000 0.0000320000 0.0003080000 0.0323370000 27626996 96830484 1769115648 3.8823337555 3.9709973335 4.0502810478 635 1311867739.8016180992 0.1686440110 0.0941833112 0.2374686003 0.0050365856 0.1526440000 0.0116540000 0.0713600000 0.0003930000 0.0002800000 0.0389540000 27629246 96830484 1767989248 3.8813214302 3.9693620205 4.0507721901 636 1311867739.8325679302 0.1698096395 0.0943022205 0.2374686003 0.0050444843 0.1355680000 0.0103180000 0.0720600000 0.0000270000 0.0003070000 0.0325870000 27631400 96830484 1769725952 3.8800702095 3.9715495110 4.0516333580 637 1311867739.8701560497 0.1700860262 0.0944211904 0.2374686003 0.0050412539 0.1567260000 0.0122420000 0.0605530000 0.0003200000 0.0003520000 0.0628990000 27633650 96830484 1768718336 3.8793523312 3.9705393314 4.0522575378 638 1311867739.9036860466 0.1702167541 0.0945399922 0.2374686003 0.0050396520 0.1354210000 0.0098100000 0.0724240000 0.0000300000 0.0003040000 0.0326080000 27635900 96830484 1770344448 3.8784291744 3.9690265656 4.0521860123 639 1311867739.9317240715 0.1716889441 0.0946607261 0.2374686003 0.0050375159 0.1166720000 0.0128720000 0.0425210000 0.0003170000 0.0002810000 0.0395590000 27638022 96830484 1769226240 3.8766083717 3.9697556496 4.0527977943 640 1311867739.9668979645 0.1720175743 0.0947815962 0.2374686003 0.0050341611 0.1184320000 0.0125640000 0.0609070000 0.0000280000 0.0003200000 0.0303030000 27640240 96830484 1768206336 3.8759350777 3.9705591202 4.0531101227 641 1311867739.9987080097 0.1746911108 0.0949062600 0.2374686003 0.0050320506 0.1583940000 0.0101800000 0.0732060000 0.0003670000 0.0002770000 0.0604170000 27642458 96830484 1769963520 3.8725836277 3.9691927433 4.0537452698 642 1311867740.0328791142 0.1745820642 0.0950303656 0.2374686003 0.0050285751 0.1084320000 0.0121820000 0.0385460000 0.0000290000 0.0003060000 0.0350620000 27644676 96830484 1766060032 3.8721368313 3.9692671299 4.0539226532 643 1311867740.0671849251 0.1742035598 0.0951534966 0.2374686003 0.0050287603 0.1346110000 0.0109150000 0.0660480000 0.0003090000 0.0002750000 0.0408260000 27646862 96830484 1767460864 3.8723175526 3.9712595940 4.0543708801 644 1311867740.0992529392 0.1756820083 0.0952785408 0.2374686003 0.0050306467 0.1174360000 0.0101890000 0.0582180000 0.0000300000 0.0003100000 0.0325490000 27649080 96830484 1763885056 3.8704822063 3.9691441059 4.0545215607 645 1311867740.1347720623 0.1781121045 0.0954069650 0.2374686003 0.0050296030 0.1295060000 0.0110430000 0.0428210000 0.0003190000 0.0002750000 0.0607130000 27651266 96830484 1765552128 3.8672423363 3.9674782753 4.0546760559 646 1311867740.1666491032 0.1777539998 0.0955344371 0.2374686003 0.0050297274 0.1379490000 0.0102180000 0.0731370000 0.0000300000 0.0003070000 0.0348630000 27653484 96830484 1767350272 3.8675837517 3.9695322514 4.0548701286 647 1311867740.1993310452 0.1789488494 0.0956633620 0.2374686003 0.0050261620 0.1183590000 0.0098960000 0.0561050000 0.0003100000 0.0002750000 0.0378400000 27655702 96830484 1769074688 3.8661143780 3.9697914124 4.0553383827 648 1311867740.2383539677 0.1785461009 0.0957912675 0.2374686003 0.0050243511 0.1131960000 0.0115190000 0.0424680000 0.0000290000 0.0003190000 0.0333770000 27658016 96830484 1767952384 3.8659703732 3.9684693813 4.0550971031 649 1311867740.2664349079 0.1790782362 0.0959195987 0.2374686003 0.0050243393 0.1565720000 0.0101940000 0.0712930000 0.0003050000 0.0002750000 0.0605810000 27660106 96830484 1769709568 3.8652231693 3.9695403576 4.0553693771 650 1311867740.2981588840 0.1794311702 0.0960480781 0.2374686003 0.0050223113 0.1148350000 0.0114260000 0.0427600000 0.0000280000 0.0003130000 0.0329380000 27662292 96830484 1768591360 3.8646306992 3.9701228142 4.0556192398 651 1311867740.3347120285 0.1788309813 0.0961752408 0.2374686003 0.0050198472 0.1378330000 0.0100490000 0.0730770000 0.0005390000 0.0002980000 0.0392790000 27664574 96830484 1770217472 3.8647010326 3.9689204693 4.0552105904 652 1311867740.3665161133 0.1768025756 0.0962989023 0.2374686003 0.0050214747 0.1147910000 0.0122280000 0.0480810000 0.0000300000 0.0003160000 0.0329120000 27666728 96830484 1768972288 3.8666243553 3.9705350399 4.0547876358 653 1311867740.3993780613 0.1776516736 0.0964234854 0.2374686003 0.0050197048 0.1293460000 0.0105030000 0.0424310000 0.0003940000 0.0002780000 0.0616360000 27668914 96830484 1770598400 3.8656430244 3.9692778587 4.0547170639 654 1311867740.4346680641 0.1774910688 0.0965474420 0.2374686003 0.0050170762 0.1217120000 0.0122740000 0.0493930000 0.0000290000 0.0003100000 0.0333290000 27671164 96830484 1769254912 3.8659031391 3.9697251320 4.0542535782 655 1311867740.4664289951 0.1787393838 0.0966729259 0.2374686003 0.0050138713 0.1384830000 0.0119900000 0.0718960000 0.0003140000 0.0002770000 0.0397500000 27673350 96830484 1767862272 3.8645048141 3.9698534012 4.0538444519 656 1311867740.4993040562 0.1792506725 0.0967988066 0.2374686003 0.0050122229 0.1321270000 0.0101260000 0.0659130000 0.0000300000 0.0003790000 0.0331170000 27675536 96830484 1769455616 3.8645443916 3.9698264599 4.0538749695 657 1311867740.5354259014 0.1805199087 0.0969262359 0.2374686003 0.0050136797 0.1372550000 0.0125470000 0.0366480000 0.0003190000 0.0002760000 0.0644760000 27677786 96830484 1768099840 3.8636229038 3.9695169926 4.0536065102 658 1311867740.5666589737 0.1808233261 0.0970537391 0.2374686003 0.0050099352 0.1343090000 0.0103050000 0.0660000000 0.0000280000 0.0003050000 0.0330480000 27679972 96830484 1769836544 3.8634750843 3.9702072144 4.0532965660 659 1311867740.6008880138 0.1834246963 0.0971848028 0.2374686003 0.0050092997 0.1189380000 0.0130500000 0.0487830000 0.0003760000 0.0002810000 0.0400720000 27682190 96830484 1768480768 3.8610761166 3.9707393646 4.0535249710 660 1311867740.6346809864 0.1828114539 0.0973145401 0.2374686003 0.0050080716 0.1117570000 0.0100930000 0.0444830000 0.0000320000 0.0003850000 0.0375590000 27684408 96830484 1770217472 3.8616714478 3.9707396030 4.0532765388 661 1311867740.6665890217 0.1833620518 0.0974447179 0.2374686003 0.0050045625 0.1302100000 0.0118970000 0.0424430000 0.0003250000 0.0002830000 0.0608840000 27686594 96830484 1769115648 3.8609290123 3.9706530571 4.0529360771 662 1311867740.6994900703 0.1838913560 0.0975753020 0.2374686003 0.0050015672 0.1028820000 0.0109290000 0.0369790000 0.0000210000 0.0002100000 0.0357060000 27688780 96830484 1767845888 3.8603003025 3.9702200890 4.0525622368 663 1311867740.7368240356 0.1841663718 0.0977059069 0.2374686003 0.0050000723 0.1337800000 0.0097570000 0.0604140000 0.0003100000 0.0002780000 0.0398640000 27690966 96830484 1769345024 3.8599252701 3.9697690010 4.0523076057 664 1311867740.7668819427 0.1850608289 0.0978374655 0.2374686003 0.0049974906 0.1163640000 0.0119490000 0.0426220000 0.0000320000 0.0003230000 0.0335830000 27693120 96830484 1767972864 3.8588209152 3.9699122906 4.0521326065 665 1311867740.7996399403 0.1879977286 0.0979730449 0.2374686003 0.0049949827 0.1372220000 0.0101450000 0.0492630000 0.0003880000 0.0002910000 0.0629190000 27695338 96830484 1769709568 3.8557152748 3.9689919949 4.0526971817 666 1311867740.8349099159 0.1880174130 0.0981082466 0.2374686003 0.0049913010 0.1143610000 0.0116860000 0.0476630000 0.0000290000 0.0003010000 0.0329910000 27697524 96830484 1768353792 3.8554697037 3.9694213867 4.0524148941 667 1311867740.8668210506 0.1894468218 0.0982451860 0.2374686003 0.0049884658 0.1153100000 0.0103720000 0.0439870000 0.0006090000 0.0002870000 0.0401460000 27699742 96830484 1770082304 3.8537340164 3.9694678783 4.0525465012 668 1311867740.8993830681 0.1903654486 0.0983830906 0.2374686003 0.0049850044 0.1155500000 0.0126430000 0.0448490000 0.0000280000 0.0003870000 0.0331170000 27701928 96830484 1768738816 3.8521602154 3.9684889317 4.0523653030 669 1311867740.9399120808 0.1890059412 0.0985185508 0.2374686003 0.0049885768 0.1540810000 0.0099480000 0.0536220000 0.0004030000 0.0002850000 0.0630610000 27704274 96830484 1770463232 3.8531787395 3.9700703621 4.0523643494 670 1311867740.9665501118 0.1892952770 0.0986540384 0.2374686003 0.0049855714 0.1168890000 0.0124470000 0.0484240000 0.0000290000 0.0003030000 0.0328990000 27706364 96830484 1769361408 3.8524370193 3.9698107243 4.0518908501 671 1311867741.0021579266 0.1899344474 0.0987900748 0.2374686003 0.0049827728 0.1178790000 0.0120310000 0.0521240000 0.0003860000 0.0002850000 0.0385030000 27708614 96830484 1767964672 3.8513514996 3.9685285091 4.0516991615 672 1311867741.0367169380 0.1888795644 0.0989241365 0.2374686003 0.0049800092 0.1127080000 0.0099250000 0.0489480000 0.0000280000 0.0006400000 0.0333600000 27710832 96830484 1769574400 3.8521745205 3.9694888592 4.0513677597 673 1311867741.0666699409 0.1890511215 0.0990580548 0.2374686003 0.0049784147 0.1277950000 0.0123850000 0.0360530000 0.0003730000 0.0002810000 0.0642020000 27712986 96830484 1768226816 3.8518135548 3.9706220627 4.0512504578 674 1311867741.1009640694 0.1889469922 0.0991914212 0.2374686003 0.0049822179 0.1228170000 0.0098100000 0.0561500000 0.0000270000 0.0007070000 0.0331130000 27715204 96830484 1769955328 3.8513419628 3.9685213566 4.0507383347 675 1311867741.1357901096 0.1888153553 0.0993241974 0.2374686003 0.0049793883 0.1324480000 0.0132390000 0.0495260000 0.0007020000 0.0008190000 0.0402690000 27717422 96830484 1768853504 3.8509407043 3.9688937664 4.0501103401 676 1311867741.1675300598 0.1883313358 0.0994558647 0.2374686003 0.0049765633 0.1364950000 0.0099600000 0.0727000000 0.0000290000 0.0003040000 0.0328700000 27719640 96830484 1770463232 3.8515310287 3.9688410759 4.0500144958 677 1311867741.2014830112 0.1892753392 0.0995885375 0.2374686003 0.0049779501 0.1300780000 0.0127160000 0.0382780000 0.0003110000 0.0002850000 0.0638770000 27721826 96830484 1769234432 3.8506987095 3.9680902958 4.0495409966 678 1311867741.2411060333 0.1910201162 0.0997233923 0.2374686003 0.0049799243 0.1229180000 0.0114500000 0.0600080000 0.0000310000 0.0003660000 0.0334360000 27724140 96830484 1767854080 3.8486561775 3.9667732716 4.0492725372 679 1311867741.2668209076 0.1927209198 0.0998603548 0.2374686003 0.0049817119 0.1153540000 0.0097030000 0.0487760000 0.0003060000 0.0002840000 0.0405990000 27726230 96830484 1769463808 3.8472075462 3.9672081470 4.0493221283 680 1311867741.2997009754 0.1934129745 0.0999979322 0.2374686003 0.0049783077 0.1167800000 0.0116710000 0.0541100000 0.0000290000 0.0003040000 0.0338520000 27728416 96830484 1768210432 3.8468294144 3.9677400589 4.0491313934 681 1311867741.3348419666 0.1939414889 0.1001358816 0.2374686003 0.0049747693 0.1292360000 0.0098850000 0.0424080000 0.0003140000 0.0002820000 0.0620160000 27730666 96830484 1769828352 3.8465156555 3.9682595730 4.0490226746 682 1311867741.3701419830 0.1943525523 0.1002740292 0.2374686003 0.0049720739 0.1202170000 0.0116230000 0.0484230000 0.0000290000 0.0003100000 0.0343440000 27732884 96830484 1768464384 3.8465344906 3.9698512554 4.0489397049 683 1311867741.4066278934 0.1948669255 0.1004125254 0.2374686003 0.0049700781 0.1162180000 0.0100990000 0.0477510000 0.0003100000 0.0003560000 0.0407930000 27735166 96830484 1770229760 3.8463749886 3.9696366787 4.0487151146 684 1311867741.4393060207 0.1937237233 0.1005489453 0.2374686003 0.0049676940 0.1160770000 0.0120600000 0.0485730000 0.0000300000 0.0003710000 0.0340850000 27737384 96830484 1768865792 3.8478541374 3.9704275131 4.0485968590 685 1311867741.4667329788 0.1944739968 0.1006860622 0.2374686003 0.0049641201 0.1311250000 0.0102840000 0.0423670000 0.0003270000 0.0002780000 0.0630290000 27739474 96830484 1770590208 3.8476405144 3.9704868793 4.0487723351 686 1311867741.5025069714 0.1961795837 0.1008252656 0.2374686003 0.0049624646 0.1209720000 0.0119180000 0.0548510000 0.0000280000 0.0003140000 0.0349590000 27741724 96830484 1769488384 3.8465383053 3.9710478783 4.0490841866 687 1311867741.5368049145 0.1958517879 0.1009635865 0.2374686003 0.0049602846 0.1156960000 0.0124220000 0.0429020000 0.0003950000 0.0002830000 0.0425740000 27743942 96830484 1768345600 3.8473572731 3.9705407619 4.0490493774 688 1311867741.5688209534 0.1949690431 0.1011002224 0.2374686003 0.0049568778 0.1123720000 0.0098950000 0.0421950000 0.0000310000 0.0003190000 0.0341430000 27746128 96830484 1769955328 3.8488831520 3.9710962772 4.0490798950 689 1311867741.6046030521 0.1956111342 0.1012373935 0.2374686003 0.0049635044 0.1368170000 0.0122260000 0.0297980000 0.0000660000 0.0000580000 0.0680430000 27748346 96830484 1768710144 3.8488471508 3.9719059467 4.0492515564 690 1311867741.6355440617 0.1974125654 0.1013767778 0.2374686003 0.0049607990 0.1356650000 0.0099700000 0.0700230000 0.0000290000 0.0002970000 0.0341620000 27750532 96830484 1770336256 3.8474879265 3.9713535309 4.0492811203 691 1311867741.6679561138 0.1970607191 0.1015152495 0.2374686003 0.0049573377 0.1395070000 0.0128250000 0.0725700000 0.0002900000 0.0002840000 0.0387940000 27752750 96830484 1768980480 3.8485581875 3.9719603062 4.0492935181 692 1311867741.7048020363 0.1983206868 0.1016551418 0.2374686003 0.0049585793 0.1123830000 0.0117480000 0.0427330000 0.0000290000 0.0003160000 0.0342180000 27755000 96830484 1767600128 3.8480873108 3.9721379280 4.0491814613 693 1311867741.7345991135 0.1979337037 0.1017940719 0.2374686003 0.0049564969 0.1380860000 0.0104940000 0.0478640000 0.0002970000 0.0003410000 0.0646060000 27757122 96830484 1769320448 3.8490498066 3.9715228081 4.0488648415 694 1311867741.7702169418 0.1981731504 0.1019329466 0.2374686003 0.0049530925 0.1160420000 0.0119440000 0.0530550000 0.0000270000 0.0003610000 0.0343160000 27759372 96830484 1767964672 3.8496804237 3.9717135429 4.0488085747 695 1311867741.8058650494 0.1988960505 0.1020724619 0.2374686003 0.0049495698 0.1124470000 0.0097320000 0.0360030000 0.0003170000 0.0002820000 0.0419020000 27761622 96830484 1769574400 3.8498642445 3.9718344212 4.0485963821 696 1311867741.8388509750 0.1985358298 0.1022110587 0.2374686003 0.0049471489 0.1161140000 0.0119660000 0.0421940000 0.0000280000 0.0003490000 0.0342770000 27763872 96830484 1768329216 3.8509633541 3.9719653130 4.0484313965 697 1311867741.8683021069 0.2008625120 0.1023525959 0.2374686003 0.0049439629 0.1317020000 0.0103560000 0.0369360000 0.0002970000 0.0003510000 0.0692850000 27765994 96830484 1769955328 3.8492319584 3.9721455574 4.0485239029 698 1311867741.9065721035 0.1988437921 0.1024908354 0.2374686003 0.0049415473 0.1032740000 0.0116950000 0.0420190000 0.0000310000 0.0003870000 0.0343830000 27768276 96830484 1768611840 3.8518569469 3.9719145298 4.0475430489 699 1311867741.9387769699 0.2010918111 0.1026318955 0.2374686003 0.0049392952 0.1353290000 0.0100310000 0.0713100000 0.0003560000 0.0002780000 0.0388220000 27770494 96830484 1770209280 3.8506126404 3.9724862576 4.0478501320 700 1311867741.9665379524 0.2010788620 0.1027725340 0.2374686003 0.0049368846 0.1354920000 0.0122090000 0.0709780000 0.0000270000 0.0002920000 0.0351350000 27772584 96830484 1768845312 3.8512089252 3.9719851017 4.0472025871 701 1311867742.0029959679 0.2023294121 0.1029145552 0.2374686003 0.0049335891 0.1686780000 0.0101060000 0.0532810000 0.0003550000 0.0002760000 0.0640220000 27774834 96830484 1770590208 3.8510231972 3.9715144634 4.0474476814 702 1311867742.0344839096 0.2025292218 0.1030564565 0.2374686003 0.0049305487 0.1393310000 0.0123810000 0.0715310000 0.0000270000 0.0002860000 0.0351260000 27776988 96830484 1769246720 3.8517017365 3.9726631641 4.0471515656 703 1311867742.0674400330 0.2034174055 0.1031992174 0.2374686003 0.0049284124 0.1537980000 0.0131090000 0.0716300000 0.0003160000 0.0003390000 0.0422390000 27779174 96830484 1767837696 3.8517420292 3.9726965427 4.0473518372 704 1311867742.1030650139 0.2036960572 0.1033419686 0.2374686003 0.0049250077 0.0973300000 0.0101600000 0.0356620000 0.0000290000 0.0002880000 0.0364210000 27781392 96830484 1769463808 3.8528382778 3.9732558727 4.0473046303 705 1311867742.1348879337 0.2059194595 0.1034874686 0.2374686003 0.0049236389 0.1738010000 0.0120640000 0.0687770000 0.0003140000 0.0005040000 0.0662310000 27783546 96830484 1768210432 3.8516345024 3.9729154110 4.0473237038 706 1311867742.1672229767 0.2051941901 0.1036315291 0.2374686003 0.0049213779 0.1141840000 0.0104420000 0.0417980000 0.0000290000 0.0003180000 0.0354090000 27785764 96830484 1769828352 3.8530414104 3.9738857746 4.0473942757 707 1311867742.2028279305 0.2054113448 0.1037754893 0.2374686003 0.0049182645 0.1372160000 0.0121290000 0.0569180000 0.0002910000 0.0002680000 0.0434280000 27788046 96830484 1768464384 3.8538398743 3.9740374088 4.0473351479 708 1311867742.2362670898 0.2053097188 0.1039188992 0.2374686003 0.0049156363 0.1343530000 0.0105650000 0.0724390000 0.0000280000 0.0003540000 0.0354820000 27790232 96830484 1770229760 3.8548491001 3.9744417667 4.0472044945 709 1311867742.2674059868 0.2068423033 0.1040640662 0.2374686003 0.0049126763 0.1600300000 0.0121240000 0.0704790000 0.0002960000 0.0002750000 0.0619680000 27792418 96830484 1768865792 3.8541073799 3.9730679989 4.0478119850 710 1311867742.3028159142 0.2076639086 0.1042099815 0.2374686003 0.0049107258 0.1120530000 0.0098840000 0.0540210000 0.0000280000 0.0003390000 0.0331860000 27794668 96830484 1770463232 3.8538537025 3.9736533165 4.0476708412 711 1311867742.3350739479 0.2076567411 0.1043554762 0.2374686003 0.0049074926 0.1347060000 0.0123380000 0.0630460000 0.0003420000 0.0002640000 0.0431140000 27796822 96830484 1769099264 3.8542110920 3.9739007950 4.0471878052 712 1311867742.3694241047 0.2089155167 0.1045023302 0.2374686003 0.0049046653 0.1139360000 0.0119360000 0.0462530000 0.0000270000 0.0003150000 0.0367570000 27799072 96830484 1767727104 3.8531889915 3.9732711315 4.0472178459 713 1311867742.4062991142 0.2099848539 0.1046502720 0.2374686003 0.0049013509 0.1332820000 0.0098780000 0.0419510000 0.0001140000 0.0001030000 0.0665970000 27801322 96830484 1769447424 3.8523879051 3.9735012054 4.0467672348 714 1311867742.4346439838 0.2109474391 0.1047991476 0.2374686003 0.0048979977 0.1388470000 0.0115510000 0.0708950000 0.0000290000 0.0002940000 0.0377050000 27803444 96830484 1768099840 3.8517658710 3.9728975296 4.0468025208 715 1311867742.4666969776 0.2103963345 0.1049468360 0.2374686003 0.0048948082 0.1145930000 0.0107040000 0.0410130000 0.0011190000 0.0002990000 0.0445460000 27805630 96830484 1769701376 3.8526127338 3.9737772942 4.0461273193 716 1311867742.5047059059 0.2107223421 0.1050945671 0.2374686003 0.0048915836 0.1160680000 0.0120670000 0.0475950000 0.0000270000 0.0002810000 0.0360970000 27807880 96830484 1768345600 3.8527913094 3.9741041660 4.0460228920 717 1311867742.5359389782 0.2101298571 0.1052410599 0.2374686003 0.0048896435 0.1732590000 0.0097780000 0.0705220000 0.0002870000 0.0002700000 0.0670530000 27810066 96830484 1770082304 3.8538787365 3.9752755165 4.0460691452 718 1311867742.5678529739 0.2100786716 0.1053870733 0.2374686003 0.0048871611 0.0995150000 0.0131300000 0.0355170000 0.0000310000 0.0003810000 0.0354020000 27812284 96830484 1767305216 3.8543431759 3.9754352570 4.0460195541 719 1311867742.6054639816 0.2113531083 0.1055344530 0.2374686003 0.0048844563 0.1508580000 0.0104500000 0.0709650000 0.0003450000 0.0002720000 0.0435990000 27814534 96830484 1767456768 3.8534543514 3.9743108749 4.0461578369 720 1311867742.6347279549 0.2108315378 0.1056806989 0.2374686003 0.0048812682 0.1155180000 0.0104140000 0.0476010000 0.0000290000 0.0002990000 0.0361380000 27816656 96830484 1766076416 3.8543045521 3.9750902653 4.0461401939 721 1311867742.6724960804 0.2110397816 0.1058268280 0.2374686003 0.0048785252 0.1351210000 0.0105990000 0.0410870000 0.0008690000 0.0002880000 0.0674820000 27818970 96830484 1767669760 3.8543696404 3.9745497704 4.0462803841 722 1311867742.7046229839 0.2111297995 0.1059726770 0.2374686003 0.0048751526 0.0987320000 0.0097660000 0.0364800000 0.0000280000 0.0003210000 0.0375130000 27821124 96830484 1769320448 3.8545897007 3.9740684032 4.0462756157 723 1311867742.7356119156 0.2110134214 0.1061179616 0.2374686003 0.0048717955 0.1531690000 0.0119650000 0.0710620000 0.0002980000 0.0002770000 0.0445180000 27823310 96830484 1767964672 3.8551297188 3.9743678570 4.0462093353 724 1311867742.7726070881 0.2111468166 0.1062630291 0.2374686003 0.0048688336 0.1164430000 0.0102250000 0.0527670000 0.0000280000 0.0003000000 0.0369660000 27825592 96830484 1769701376 3.8555676937 3.9736592770 4.0462384224 725 1311867742.8034689426 0.2119338512 0.1064087819 0.2374686003 0.0048685623 0.1566590000 0.0119690000 0.0462810000 0.0002980000 0.0002720000 0.0703290000 27827778 96830484 1768353792 3.8547751904 3.9737405777 4.0461564064 726 1311867742.8352251053 0.2127084583 0.1065552002 0.2374686003 0.0048682358 0.1148680000 0.0098610000 0.0512880000 0.0000310000 0.0003880000 0.0369090000 27829932 96830484 1769971712 3.8547985554 3.9738254547 4.0463137627 727 1311867742.8705639839 0.2130523175 0.1067016887 0.2374686003 0.0048651301 0.1143810000 0.0120030000 0.0293940000 0.0000670000 0.0000600000 0.0471310000 27832150 96830484 1768599552 3.8546967506 3.9744031429 4.0461907387 728 1311867742.9046700001 0.2126015723 0.1068471556 0.2374686003 0.0048621408 0.1157880000 0.0106700000 0.0511180000 0.0000290000 0.0003600000 0.0370210000 27834368 96830484 1770336256 3.8557713032 3.9740102291 4.0464282036 729 1311867742.9382069111 0.2130249590 0.1069928041 0.2374686003 0.0048778360 0.1541840000 0.0120250000 0.0471430000 0.0003000000 0.0003460000 0.0692970000 27836618 96830484 1768992768 3.8551809788 3.9743678570 4.0462336540 730 1311867742.9707310200 0.2131968141 0.1071382891 0.2374686003 0.0048792689 0.1153440000 0.0120900000 0.0390410000 0.0000270000 0.0003500000 0.0394000000 27838804 96830484 1767600128 3.8555119038 3.9743244648 4.0462803841 731 1311867743.0024189949 0.2139351070 0.1072843860 0.2374686003 0.0048804299 0.1139140000 0.0100400000 0.0347110000 0.0002900000 0.0010540000 0.0440350000 27840958 96830484 1769320448 3.8549909592 3.9743244648 4.0464339256 732 1311867743.0345149040 0.2131983191 0.1074290771 0.2374686003 0.0048814499 0.1387950000 0.0117990000 0.0714970000 0.0000280000 0.0002820000 0.0372250000 27843144 96830484 1767964672 3.8562231064 3.9748897552 4.0462913513 733 1311867743.0722420216 0.2137927860 0.1075741845 0.2374686003 0.0048803904 0.1350420000 0.0099640000 0.0388840000 0.0003530000 0.0002690000 0.0707250000 27845426 96830484 1769574400 3.8560359478 3.9740202427 4.0459895134 734 1311867743.1045989990 0.2137862891 0.1077188876 0.2374686003 0.0048783834 0.1372350000 0.0115270000 0.0698840000 0.0000300000 0.0002900000 0.0378320000 27847612 96830484 1768226816 3.8564910889 3.9746537209 4.0461273193 735 1311867743.1350400448 0.2140110135 0.1078635028 0.2374686003 0.0048762545 0.1136610000 0.0098640000 0.0349210000 0.0002930000 0.0003490000 0.0474540000 27849766 96830484 1769955328 3.8570146561 3.9744019508 4.0461959839 736 1311867743.1704380512 0.2144453973 0.1080083151 0.2374686003 0.0048785592 0.1176810000 0.0127290000 0.0473860000 0.0000270000 0.0003440000 0.0380090000 27851984 96830484 1768611840 3.8566105366 3.9738662243 4.0458135605 737 1311867743.2037980556 0.2139135450 0.1081520129 0.2374686003 0.0048764799 0.1315460000 0.0105750000 0.0347710000 0.0003650000 0.0002730000 0.0706900000 27854202 96830484 1770209280 3.8575129509 3.9749000072 4.0452752113 738 1311867743.2358140945 0.2152895480 0.1082971857 0.2374686003 0.0048747735 0.1401090000 0.0115290000 0.0705270000 0.0000280000 0.0002880000 0.0373820000 27856356 96830484 1768845312 3.8568503857 3.9742157459 4.0459618568 739 1311867743.2708129883 0.2151700109 0.1084418039 0.2374686003 0.0048754727 0.1155810000 0.0105790000 0.0405090000 0.0011510000 0.0002780000 0.0454740000 27858606 96830484 1770590208 3.8571228981 3.9750077724 4.0460886955 740 1311867743.3032529354 0.2144991159 0.1085851245 0.2374686003 0.0048835626 0.0990980000 0.0122270000 0.0347150000 0.0000290000 0.0002910000 0.0364780000 27860792 96830484 1767448576 3.8579025269 3.9755992889 4.0459065437 741 1311867743.3363931179 0.2134812027 0.1087266847 0.2374686003 0.0048803636 0.1678950000 0.0103210000 0.0726640000 0.0002960000 0.0003490000 0.0687470000 27862978 96830484 1765548032 3.8591644764 3.9755418301 4.0461502075 742 1311867743.3707330227 0.2139942050 0.1088685547 0.2374686003 0.0048777218 0.1352040000 0.0103850000 0.0700930000 0.0000290000 0.0003720000 0.0376750000 27865196 96830484 1766690816 3.8586652279 3.9765720367 4.0459237099 743 1311867743.4043838978 0.2145953029 0.1090108518 0.2374686003 0.0048745524 0.1144780000 0.0100300000 0.0401100000 0.0002040000 0.0001850000 0.0454580000 27867414 96830484 1762369536 3.8583743572 3.9756748676 4.0466585159 744 1311867743.4352641106 0.2153302282 0.1091537542 0.2374686003 0.0048755477 0.1129680000 0.0112670000 0.0431080000 0.0000290000 0.0003230000 0.0378100000 27869600 96830484 1764003840 3.8576655388 3.9749820232 4.0467953682 745 1311867743.4768960476 0.2156890184 0.1092967545 0.2374686003 0.0048747942 0.1339820000 0.0103360000 0.0358340000 0.0003760000 0.0002890000 0.0716340000 27871914 96830484 1765793792 3.8576695919 3.9749066830 4.0472440720 746 1311867743.5035250187 0.2164241523 0.1094403569 0.2374686003 0.0048723540 0.1145730000 0.0098040000 0.0424840000 0.0000310000 0.0003810000 0.0377400000 27874036 96830484 1767161856 3.8570532799 3.9759299755 4.0470376015 747 1311867743.5389750004 0.2163631916 0.1095834933 0.2374686003 0.0048717952 0.1166770000 0.0103180000 0.0365030000 0.0003020000 0.0003630000 0.0478770000 27876254 96830484 1768828928 3.8569092751 3.9755361080 4.0469112396 748 1311867743.5749680996 0.2168341875 0.1097268765 0.2374686003 0.0048722707 0.1199070000 0.0120890000 0.0547160000 0.0000280000 0.0003080000 0.0370230000 27878504 96830484 1767456768 3.8571157455 3.9756700993 4.0467772484 749 1311867743.6036109924 0.2168830633 0.1098699422 0.2374686003 0.0048767250 0.1275200000 0.0100090000 0.0296840000 0.0003140000 0.0003600000 0.0719570000 27880626 96830484 1769066496 3.8565649986 3.9763171673 4.0468168259 750 1311867743.6354589462 0.2170604467 0.1100128629 0.2374686003 0.0048769574 0.1411880000 0.0112980000 0.0685190000 0.0000300000 0.0003130000 0.0383180000 27882812 96830484 1767837696 3.8562974930 3.9754071236 4.0467596054 751 1311867743.6759150028 0.2169557661 0.1101552636 0.2374686003 0.0048738036 0.1526160000 0.0105620000 0.0695140000 0.0003020000 0.0005130000 0.0445940000 27885126 96830484 1769467904 3.8562564850 3.9750964642 4.0464773178 752 1311867743.7034959793 0.2160556018 0.1102960885 0.2374686003 0.0048709803 0.1390460000 0.0122130000 0.0697080000 0.0000290000 0.0003780000 0.0378370000 27887248 96830484 1768083456 3.8569395542 3.9759051800 4.0460247993 753 1311867743.7388861179 0.2161989510 0.1104367297 0.2374686003 0.0048687828 0.1528500000 0.0099930000 0.0455310000 0.0003200000 0.0002790000 0.0716700000 27889498 96830484 1769701376 3.8566503525 3.9753038883 4.0457692146 754 1311867743.7733619213 0.2169161588 0.1105779491 0.2374686003 0.0048657595 0.1193400000 0.0125130000 0.0518760000 0.0000300000 0.0003120000 0.0379820000 27891748 96830484 1768353792 3.8557736874 3.9741234779 4.0459222794 755 1311867743.8064749241 0.2174912840 0.1107195562 0.2374686003 0.0048635058 0.1122900000 0.0100910000 0.0293740000 0.0003190000 0.0002800000 0.0480100000 27893902 96830484 1770102784 3.8550231457 3.9747862816 4.0456151962 756 1311867743.8391659260 0.2180962563 0.1108615889 0.2374686003 0.0048608967 0.1003180000 0.0125610000 0.0348090000 0.0000310000 0.0003800000 0.0370740000 27896088 96830484 1768738816 3.8539559841 3.9739518166 4.0450387001 757 1311867743.8726658821 0.2169924974 0.1110017882 0.2374686003 0.0048584107 0.1703230000 0.0098970000 0.0724930000 0.0003130000 0.0002760000 0.0721310000 27898338 96830484 1770336256 3.8550357819 3.9737811089 4.0450205803 758 1311867743.9031310081 0.2173702419 0.1111421160 0.2374686003 0.0048554071 0.1030520000 0.0117060000 0.0344590000 0.0000280000 0.0003120000 0.0409840000 27900492 96830484 1768972288 3.8547587395 3.9742698669 4.0446748734 759 1311867743.9453630447 0.2192403078 0.1112845378 0.2374686003 0.0048528123 0.1131680000 0.0117240000 0.0417390000 0.0002150000 0.0001900000 0.0436150000 27902838 96830484 1767600128 3.8527441025 3.9731636047 4.0448665619 760 1311867743.9741249084 0.2181245387 0.1114251168 0.2374686003 0.0048512390 0.1124090000 0.0101060000 0.0424600000 0.0000280000 0.0003150000 0.0386000000 27904960 96830484 1769320448 3.8535339832 3.9747667313 4.0436258316 761 1311867744.0042529106 0.2177416980 0.1115648232 0.2374686003 0.0048527233 0.1773270000 0.0124050000 0.0699000000 0.0003190000 0.0005310000 0.0735070000 27907082 96830484 1768075264 3.8541474342 3.9768893719 4.0435509682 762 1311867744.0407259464 0.2175238281 0.1117038770 0.2374686003 0.0048519676 0.1166880000 0.0107030000 0.0409400000 0.0000300000 0.0003150000 0.0486240000 27909364 96830484 1769574400 3.8544936180 3.9749753475 4.0438852310 763 1311867744.0716118813 0.2166802436 0.1118414607 0.2374686003 0.0048499764 0.1323750000 0.0131620000 0.0481280000 0.0003220000 0.0003550000 0.0458260000 27911518 96830484 1768337408 3.8553192616 3.9762468338 4.0437455177 764 1311867744.1111290455 0.2175847143 0.1119798681 0.2374686003 0.0048474344 0.1139680000 0.0104820000 0.0395180000 0.0000320000 0.0003900000 0.0386060000 27913736 96830484 1769955328 3.8543395996 3.9753634930 4.0438008308 765 1311867744.1412119865 0.2173588723 0.1121176185 0.2374686003 0.0048447502 0.1424420000 0.0130890000 0.0434970000 0.0003810000 0.0002820000 0.0696130000 27915890 96830484 1768599552 3.8544769287 3.9769575596 4.0431547165 766 1311867744.1734991074 0.2175290436 0.1122552313 0.2374686003 0.0048431726 0.1313700000 0.0099980000 0.0644830000 0.0000310000 0.0003780000 0.0380750000 27918108 96830484 1770336256 3.8547971249 3.9782671928 4.0434956551 767 1311867744.2046771049 0.2185146064 0.1123937702 0.2374686003 0.0048470795 0.1178800000 0.0124980000 0.0435880000 0.0003180000 0.0002790000 0.0456690000 27920262 96830484 1768992768 3.8536577225 3.9760925770 4.0435638428 768 1311867744.2400228977 0.2177532017 0.1125309570 0.2374686003 0.0048443596 0.1165010000 0.0119150000 0.0535970000 0.0000300000 0.0003100000 0.0348670000 27922544 96830484 1767600128 3.8540914059 3.9756143093 4.0428657532 769 1311867744.2773048878 0.2181119025 0.1126682534 0.2374686003 0.0048431353 0.1504640000 0.0099940000 0.0550270000 0.0003800000 0.0002820000 0.0691620000 27924794 96830484 1769340928 3.8539628983 3.9783704281 4.0429902077 770 1311867744.3032519817 0.2180772722 0.1128051482 0.2374686003 0.0048421822 0.1389980000 0.0114250000 0.0709640000 0.0000280000 0.0003740000 0.0376900000 27926884 96830484 1767964672 3.8537678719 3.9764409065 4.0431127548 771 1311867744.3391230106 0.2172745466 0.1129406468 0.2374686003 0.0048454271 0.1152770000 0.0103110000 0.0409860000 0.0009480000 0.0002970000 0.0459280000 27929134 96830484 1769574400 3.8544464111 3.9759314060 4.0424976349 772 1311867744.3707659245 0.2171431631 0.1130756242 0.2374686003 0.0048437058 0.1373200000 0.0124120000 0.0708340000 0.0000290000 0.0003070000 0.0379130000 27931288 96830484 1768337408 3.8549461365 3.9776284695 4.0425963402 773 1311867744.4027431011 0.2179760933 0.1132113298 0.2374686003 0.0048413879 0.1516680000 0.0102220000 0.0422020000 0.0003850000 0.0002830000 0.0726140000 27933506 96830484 1769975808 3.8543887138 3.9767086506 4.0431556702 774 1311867744.4383800030 0.2186301947 0.1133475299 0.2374686003 0.0048388461 0.1133690000 0.0135240000 0.0358790000 0.0000260000 0.0003200000 0.0381140000 27935724 96830484 1768611840 3.8536865711 3.9762911797 4.0429906845 775 1311867744.4717690945 0.2192908823 0.1134842310 0.2374686003 0.0048359674 0.1357060000 0.0106540000 0.0554090000 0.0003140000 0.0003610000 0.0508100000 27937942 96830484 1770209280 3.8529944420 3.9762735367 4.0427298546 776 1311867744.5026860237 0.2182483673 0.1136192363 0.2374686003 0.0048331692 0.1158400000 0.0126650000 0.0436670000 0.0000290000 0.0003200000 0.0386300000 27940128 96830484 1768992768 3.8544058800 3.9774374962 4.0427021980 777 1311867744.5383169651 0.2185330391 0.1137542605 0.2374686003 0.0048332963 0.1470440000 0.0129090000 0.0479780000 0.0007190000 0.0003000000 0.0692560000 27942378 96830484 1767600128 3.8541033268 3.9765079021 4.0423254967 778 1311867744.5726189613 0.2177392393 0.1138879173 0.2374686003 0.0048310474 0.1226790000 0.0097330000 0.0538750000 0.0000300000 0.0003010000 0.0383130000 27944596 96830484 1769320448 3.8547480106 3.9763100147 4.0416870117 779 1311867744.6028740406 0.2193374038 0.1140232825 0.2374686003 0.0048336799 0.1195720000 0.0128740000 0.0476710000 0.0003120000 0.0003570000 0.0425460000 27946750 96830484 1768083456 3.8539607525 3.9760549068 4.0426058769 780 1311867744.6386809349 0.2180064768 0.1141565943 0.2374686003 0.0048348277 0.1112500000 0.0100370000 0.0388360000 0.0000300000 0.0003790000 0.0403060000 27949000 96830484 1769828352 3.8547823429 3.9767837524 4.0418205261 781 1311867744.6707758904 0.2173849940 0.1142887689 0.2374686003 0.0048319064 0.1375550000 0.0133060000 0.0322600000 0.0003860000 0.0002800000 0.0752940000 27951186 96830484 1768480768 3.8553757668 3.9766685963 4.0416188240 782 1311867744.7029349804 0.2189079672 0.1144225531 0.2374686003 0.0048344301 0.1141150000 0.0099560000 0.0417900000 0.0000270000 0.0003190000 0.0380810000 27953372 96830484 1770209280 3.8546359539 3.9765274525 4.0421915054 783 1311867744.7396171093 0.2173595130 0.1145540179 0.2374686003 0.0048374606 0.1369290000 0.0135150000 0.0535600000 0.0003820000 0.0002890000 0.0467380000 27955622 96830484 1769091072 3.8556613922 3.9781289101 4.0416264534 784 1311867744.7705199718 0.2188475728 0.1146870454 0.2374686003 0.0048352272 0.1140470000 0.0122670000 0.0395420000 0.0000270000 0.0003890000 0.0381920000 27957776 96830484 1767727104 3.8541622162 3.9766163826 4.0422363281 785 1311867744.8035891056 0.2190432101 0.1148199832 0.2374686003 0.0048356052 0.1280690000 0.0104410000 0.0296200000 0.0000670000 0.0000590000 0.0722930000 27959994 96830484 1769447424 3.8541884422 3.9757039547 4.0419178009 786 1311867744.8424170017 0.2188910246 0.1149523891 0.2374686003 0.0048331228 0.1049700000 0.0114470000 0.0359990000 0.0000240000 0.0002050000 0.0398980000 27962276 96830484 1768091648 3.8545055389 3.9764795303 4.0416655540 787 1311867744.8727390766 0.2181728482 0.1150835460 0.2374686003 0.0048338347 0.1527710000 0.0098780000 0.0724180000 0.0003160000 0.0003620000 0.0455580000 27964462 96830484 1769828352 3.8548483849 3.9757127762 4.0419573784 788 1311867744.9029939175 0.2189866602 0.1152154027 0.2374686003 0.0048311555 0.1164320000 0.0131520000 0.0425810000 0.0000290000 0.0003940000 0.0381210000 27966616 96830484 1768464384 3.8538346291 3.9748702049 4.0416216850 789 1311867744.9392940998 0.2181077003 0.1153458112 0.2374686003 0.0048303706 0.1672180000 0.0106890000 0.0704180000 0.0003810000 0.0002740000 0.0698130000 27968898 96830484 1770098688 3.8553266525 3.9761443138 4.0409860611 790 1311867744.9708900452 0.2175638378 0.1154752011 0.2374686003 0.0048302303 0.1056460000 0.0121210000 0.0362230000 0.0000200000 0.0002520000 0.0404900000 27971020 96830484 1768865792 3.8556923866 3.9762427807 4.0410847664 791 1311867745.0027489662 0.2185045928 0.1156054532 0.2374686003 0.0048360370 0.1500500000 0.0101360000 0.0688620000 0.0000630000 0.0000550000 0.0389410000 27973206 96830484 1770463232 3.8550257683 3.9758138657 4.0401473045 792 1311867745.0384869576 0.2183549553 0.1157351874 0.2374686003 0.0048363183 0.1180920000 0.0125240000 0.0334080000 0.0000290000 0.0003100000 0.0466130000 27975456 96830484 1769099264 3.8548579216 3.9755907059 4.0398812294 793 1311867745.0729780197 0.2189017981 0.1158652840 0.2374686003 0.0048359874 0.1491770000 0.0124910000 0.0499910000 0.0003120000 0.0002790000 0.0701850000 27977674 96830484 1767837696 3.8544683456 3.9752612114 4.0398564339 794 1311867745.1118760109 0.2185359895 0.1159945922 0.2374686003 0.0048375455 0.1414110000 0.0102300000 0.0701380000 0.0000320000 0.0003070000 0.0381880000 27979956 96830484 1769447424 3.8548064232 3.9760046005 4.0397958755 795 1311867745.1405589581 0.2185000479 0.1161235299 0.2374686003 0.0048346747 0.1165040000 0.0121440000 0.0352920000 0.0003680000 0.0002850000 0.0457970000 27982078 96830484 1768083456 3.8550868034 3.9764657021 4.0398902893 796 1311867745.1729030609 0.2197894901 0.1162537635 0.2374686003 0.0048320523 0.1345400000 0.0102130000 0.0635970000 0.0000280000 0.0002950000 0.0388140000 27984264 96830484 1769701376 3.8538579941 3.9749455452 4.0400447845 797 1311867745.2068369389 0.2206728607 0.1163847787 0.2374686003 0.0048291282 0.1762390000 0.0128780000 0.0636480000 0.0002930000 0.0002720000 0.0740580000 27986482 96830484 1768329216 3.8529934883 3.9751992226 4.0401554108 798 1311867745.2430789471 0.2197364569 0.1165142921 0.2374686003 0.0048290967 0.1359550000 0.0104130000 0.0690580000 0.0000270000 0.0002900000 0.0388460000 27988732 96830484 1770082304 3.8545875549 3.9767642021 4.0405712128 799 1311867745.2729060650 0.2203346938 0.1166442300 0.2374686003 0.0048261109 0.1161770000 0.0122710000 0.0353870000 0.0003700000 0.0002730000 0.0490460000 27990886 96830484 1768738816 3.8540561199 3.9766631126 4.0404162407 800 1311867745.3112850189 0.2210297137 0.1167747119 0.2374686003 0.0048235188 0.1350800000 0.0098740000 0.0681430000 0.0000260000 0.0002820000 0.0388310000 27993136 96830484 1770463232 3.8537364006 3.9755024910 4.0411543846 801 1311867745.3395059109 0.2206876874 0.1169044409 0.2374686003 0.0048205328 0.1424100000 0.0121420000 0.0419300000 0.0003140000 0.0006990000 0.0705140000 27995290 96830484 1769361408 3.8542406559 3.9753761292 4.0408329964 802 1311867745.3733940125 0.2208507806 0.1170340498 0.2374686003 0.0048181924 0.1266720000 0.0117270000 0.0540390000 0.0000310000 0.0003050000 0.0391320000 27997508 96830484 1768325120 3.8544065952 3.9747819901 4.0410742760 803 1311867745.4102098942 0.2216187716 0.1171642923 0.2374686003 0.0048157633 0.1345400000 0.0101920000 0.0576140000 0.0002930000 0.0003500000 0.0464350000 27999758 96830484 1769971712 3.8543777466 3.9745016098 4.0419855118 804 1311867745.4433169365 0.2226684839 0.1172955164 0.2374686003 0.0048130446 0.1154640000 0.0127710000 0.0351620000 0.0000300000 0.0003040000 0.0415070000 28001976 96830484 1768865792 3.8531847000 3.9749972820 4.0413732529 805 1311867745.4708619118 0.2211051136 0.1174244724 0.2374686003 0.0048103911 0.1377660000 0.0106510000 0.0354700000 0.0003970000 0.0002770000 0.0747770000 28004066 96830484 1770643456 3.8548195362 3.9754579067 4.0408945084 806 1311867745.5099780560 0.2225826383 0.1175549416 0.2374686003 0.0048082839 0.1363590000 0.0115230000 0.0707850000 0.0000300000 0.0003010000 0.0375330000 28006380 96830484 1769611264 3.8538663387 3.9754076004 4.0414423943 807 1311867745.5417380333 0.2229184955 0.1176855037 0.2374686003 0.0048074875 0.1298750000 0.0105560000 0.0543400000 0.0003710000 0.0002880000 0.0464560000 28008566 96830484 1771241472 3.8539705276 3.9737284184 4.0416555405 808 1311867745.5704059601 0.2215346694 0.1178140299 0.2374686003 0.0048050312 0.1367130000 0.0123640000 0.0691870000 0.0000290000 0.0002990000 0.0387400000 28010688 96830484 1770229760 3.8553307056 3.9730401039 4.0411081314 809 1311867745.6133821011 0.2220579237 0.1179428851 0.2374686003 0.0048023996 0.1718690000 0.0124190000 0.0687370000 0.0002920000 0.0002710000 0.0738100000 28013066 96830484 1768210432 3.8551106453 3.9732022285 4.0411181450 810 1311867745.6438291073 0.2227970809 0.1180723347 0.2374686003 0.0048010556 0.1373670000 0.0102250000 0.0698040000 0.0000280000 0.0002830000 0.0394060000 28015252 96830484 1769992192 3.8547053337 3.9732420444 4.0415387154 811 1311867745.6709001064 0.2234413028 0.1182022595 0.2374686003 0.0048062127 0.1336990000 0.0127120000 0.0472090000 0.0003160000 0.0002820000 0.0469940000 28017310 96830484 1767571456 3.8543939590 3.9741697311 4.0416355133 812 1311867745.7088780403 0.2230978459 0.1183314412 0.2374686003 0.0048041093 0.1358140000 0.0105720000 0.0679520000 0.0000280000 0.0003860000 0.0402800000 28019624 96830484 1769246720 3.8550314903 3.9742953777 4.0408887863 813 1311867745.7423269749 0.2238556743 0.1184612373 0.2374686003 0.0048019661 0.1512080000 0.0103190000 0.0517020000 0.0007210000 0.0002850000 0.0723010000 28021810 96830484 1771008000 3.8542711735 3.9740092754 4.0413470268 814 1311867745.7760419846 0.2246544361 0.1185916958 0.2374686003 0.0048069421 0.1035310000 0.0115610000 0.0356800000 0.0000290000 0.0002890000 0.0396570000 28024028 96830484 1769992192 3.8538436890 3.9729239941 4.0415105820 815 1311867745.8116889000 0.2247014940 0.1187218919 0.2374686003 0.0048117692 0.1501850000 0.0123700000 0.0640960000 0.0003070000 0.0003510000 0.0477100000 28026278 96830484 1767587840 3.8542377949 3.9736227989 4.0420055389 816 1311867745.8389890194 0.2244638354 0.1188514776 0.2374686003 0.0048119474 0.1355750000 0.0108360000 0.0687490000 0.0000270000 0.0003000000 0.0397050000 28028400 96830484 1769373696 3.8547143936 3.9728462696 4.0427608490 817 1311867745.8709759712 0.2264752388 0.1189832080 0.2374686003 0.0048101250 0.1414090000 0.0103770000 0.0409750000 0.0010500000 0.0002840000 0.0724270000 28030554 96830484 1771024384 3.8527126312 3.9731633663 4.0431580544 818 1311867745.9108459949 0.2253636718 0.1191132575 0.2374686003 0.0048091092 0.1099680000 0.0122010000 0.0348560000 0.0000220000 0.0001930000 0.0430430000 28032868 96830484 1767186432 3.8541116714 3.9747097492 4.0426192284 819 1311867745.9435789585 0.2260499597 0.1192438273 0.2374686003 0.0048100901 0.1513820000 0.0108620000 0.0686950000 0.0003620000 0.0002800000 0.0479620000 28035086 96830484 1768574976 3.8534450531 3.9730741978 4.0424337387 820 1311867745.9732220173 0.2279060632 0.1193763423 0.2374686003 0.0048079583 0.1335340000 0.0107770000 0.0581310000 0.0000290000 0.0003540000 0.0405810000 28037208 96830484 1767432192 3.8525514603 3.9704289436 4.0445771217 821 1311867746.0083909035 0.2285937667 0.1195093720 0.2374686003 0.0048056718 0.1584370000 0.0110800000 0.0567680000 0.0002950000 0.0003470000 0.0736040000 28039426 96830484 1767051264 3.8522927761 3.9707565308 4.0448207855 822 1311867746.0391409397 0.2282395214 0.1196416471 0.2374686003 0.0048030273 0.1136950000 0.0103770000 0.0467600000 0.0000290000 0.0003990000 0.0397750000 28041644 96830484 1768718336 3.8532478809 3.9704458714 4.0452299118 823 1311867746.0728518963 0.2279827744 0.1197732888 0.2374686003 0.0048004889 0.1535750000 0.0112550000 0.0684580000 0.0003740000 0.0002780000 0.0483050000 28043830 96830484 1767723008 3.8536598682 3.9711790085 4.0445313454 824 1311867746.1113359928 0.2280497402 0.1199046923 0.2374686003 0.0047989416 0.1359700000 0.0107860000 0.0667510000 0.0000270000 0.0002790000 0.0407030000 28046080 96830484 1769484288 3.8539958000 3.9708375931 4.0442709923 825 1311867746.1412689686 0.2307191342 0.1200390128 0.2374686003 0.0047974666 0.1720250000 0.0118390000 0.0680810000 0.0005080000 0.0002890000 0.0747730000 28048266 96830484 1768345600 3.8520407677 3.9691174030 4.0457429886 826 1311867746.1721889973 0.2304175794 0.1201726431 0.2374686003 0.0047948520 0.1393920000 0.0099080000 0.0686720000 0.0000280000 0.0003610000 0.0413090000 28050420 96830484 1769992192 3.8520381451 3.9702222347 4.0444850922 827 1311867746.2066209316 0.2286617309 0.1203038270 0.2374686003 0.0047929373 0.1552890000 0.0122960000 0.0689210000 0.0002960000 0.0002810000 0.0489940000 28052638 96830484 1768595456 3.8537855148 3.9720928669 4.0430779457 828 1311867746.2386920452 0.2313697338 0.1204379645 0.2374686003 0.0047918709 0.1369380000 0.0105070000 0.0670410000 0.0000270000 0.0003510000 0.0420200000 28054856 96830484 1770373120 3.8514468670 3.9686098099 4.0449995995 829 1311867746.2704648972 0.2319743335 0.1205725078 0.2374686003 0.0047890110 0.1514960000 0.0120370000 0.0464330000 0.0003860000 0.0002830000 0.0759310000 28057042 96830484 1769230336 3.8511166573 3.9671301842 4.0458755493 830 1311867746.3068819046 0.2292178422 0.1207034058 0.2374686003 0.0047889353 0.1398410000 0.0102760000 0.0682020000 0.0000290000 0.0002980000 0.0413550000 28059260 96830484 1771008000 3.8537604809 3.9689631462 4.0449657440 831 1311867746.3393440247 0.2305318415 0.1208355700 0.2374686003 0.0047909372 0.1550950000 0.0120310000 0.0668470000 0.0003600000 0.0002800000 0.0497950000 28061478 96830484 1769848832 3.8526999950 3.9691069126 4.0449519157 832 1311867746.3797800541 0.2318214327 0.1209689664 0.2374686003 0.0047887868 0.1180080000 0.0122260000 0.0484420000 0.0000420000 0.0003070000 0.0403410000 28063792 96830484 1769103360 3.8514494896 3.9672563076 4.0460300446 833 1311867746.4078478813 0.2309900224 0.1211010445 0.2374686003 0.0047880074 0.1479440000 0.0101790000 0.0449320000 0.0003870000 0.0002810000 0.0760200000 28065914 96830484 1770881024 3.8525102139 3.9677362442 4.0459704399 834 1311867746.4389901161 0.2306493819 0.1212323975 0.2374686003 0.0047853226 0.1032050000 0.0116970000 0.0287840000 0.0000230000 0.0002380000 0.0447130000 28068068 96830484 1769725952 3.8526296616 3.9689369202 4.0458478928 835 1311867746.4774639606 0.2297395170 0.1213623461 0.2374686003 0.0047848149 0.1329330000 0.0130590000 0.0438540000 0.0003280000 0.0002800000 0.0500380000 28070382 96830484 1768726528 3.8530602455 3.9688379765 4.0449895859 836 1311867746.5066781044 0.2295772433 0.1214917898 0.2374686003 0.0047822381 0.1173890000 0.0101890000 0.0501570000 0.0000280000 0.0003070000 0.0403430000 28072504 96830484 1770352640 3.8534841537 3.9684531689 4.0450663567 837 1311867746.5406761169 0.2301060855 0.1216215559 0.2374686003 0.0047823523 0.1511920000 0.0120590000 0.0453920000 0.0003170000 0.0003550000 0.0766230000 28074722 96830484 1769345024 3.8529078960 3.9695479870 4.0454277992 838 1311867746.5748629570 0.2306746542 0.1217516909 0.2374686003 0.0047800980 0.1372220000 0.0119410000 0.0657470000 0.0000320000 0.0002980000 0.0424870000 28076972 96830484 1768198144 3.8523073196 3.9688639641 4.0457344055 839 1311867746.6067559719 0.2285605371 0.1218789959 0.2374686003 0.0047802254 0.1519320000 0.0096980000 0.0659340000 0.0003550000 0.0002740000 0.0506180000 28079126 96830484 1769844736 3.8536300659 3.9706015587 4.0437374115 840 1311867746.6396849155 0.2299580127 0.1220076614 0.2374686003 0.0047828277 0.1181560000 0.0130390000 0.0447130000 0.0000280000 0.0003180000 0.0424660000 28081376 96830484 1768488960 3.8527183533 3.9695777893 4.0450239182 841 1311867746.6749529839 0.2296706885 0.1221356792 0.2374686003 0.0047843312 0.1485850000 0.0098520000 0.0444990000 0.0003830000 0.0002820000 0.0772190000 28083594 96830484 1770242048 3.8527979851 3.9697904587 4.0441894531 842 1311867746.7095060349 0.2303159833 0.1222641594 0.2374686003 0.0047816331 0.1424380000 0.0116020000 0.0661960000 0.0000290000 0.0003640000 0.0427250000 28085812 96830484 1769246720 3.8526346684 3.9684267044 4.0450634956 843 1311867746.7391049862 0.2306049317 0.1223926775 0.2374686003 0.0047793778 0.1545320000 0.0122100000 0.0675530000 0.0003090000 0.0003560000 0.0499980000 28087934 96830484 1768198144 3.8525166512 3.9679837227 4.0452542305 844 1311867746.7751340866 0.2312055081 0.1225216027 0.2374686003 0.0047768188 0.1333150000 0.0102270000 0.0532190000 0.0000300000 0.0003030000 0.0431880000 28090216 96830484 1769828352 3.8521664143 3.9676065445 4.0455927849 845 1311867746.8070099354 0.2308354229 0.1226497847 0.2374686003 0.0047749300 0.1767560000 0.0122700000 0.0559860000 0.0002990000 0.0003650000 0.0807680000 28092402 96830484 1768710144 3.8524451256 3.9676969051 4.0449166298 846 1311867746.8401610851 0.2307713181 0.1227775879 0.2374686003 0.0047722974 0.1158980000 0.0101550000 0.0394500000 0.0000300000 0.0003890000 0.0430970000 28094588 96830484 1770352640 3.8525886536 3.9668939114 4.0449280739 847 1311867746.8748359680 0.2279271036 0.1229017314 0.2374686003 0.0047703730 0.1185130000 0.0124240000 0.0390700000 0.0003210000 0.0002840000 0.0497550000 28096838 96830484 1769119744 3.8547055721 3.9688425064 4.0421772003 848 1311867746.9086029530 0.2294413298 0.1230273677 0.2374686003 0.0047685005 0.1361700000 0.0112410000 0.0675760000 0.0000290000 0.0002970000 0.0401010000 28099024 96830484 1767944192 3.8541824818 3.9695720673 4.0435991287 849 1311867746.9389610291 0.2293557525 0.1231526073 0.2374686003 0.0047661156 0.1721380000 0.0096050000 0.0666090000 0.0005500000 0.0002840000 0.0786100000 28101210 96830484 1769721856 3.8546745777 3.9676482677 4.0441088676 850 1311867746.9748229980 0.2292453945 0.1232774223 0.2374686003 0.0047671603 0.1158100000 0.0120940000 0.0328350000 0.0000280000 0.0003690000 0.0458930000 28103460 96830484 1768337408 3.8554315567 3.9679870605 4.0436658859 851 1311867747.0066559315 0.2285044193 0.1234010733 0.2374686003 0.0047698425 0.1533550000 0.0104970000 0.0652100000 0.0002880000 0.0003530000 0.0507790000 28105614 96830484 1769955328 3.8552169800 3.9689695835 4.0426974297 852 1311867747.0389339924 0.2295797020 0.1235256961 0.2374686003 0.0047680542 0.1205950000 0.0130890000 0.0442960000 0.0000300000 0.0003890000 0.0434390000 28107800 96830484 1768591360 3.8547999859 3.9667820930 4.0442185402 853 1311867747.0749640465 0.2294936329 0.1236499258 0.2374686003 0.0047665169 0.1726210000 0.0098090000 0.0675400000 0.0003730000 0.0002860000 0.0780270000 28110082 96830484 1770356736 3.8554227352 3.9679973125 4.0440711975 854 1311867747.1066820621 0.2284966558 0.1237726972 0.2374686003 0.0047706013 0.1329410000 0.0117030000 0.0457040000 0.0000310000 0.0003170000 0.0437210000 28112236 96830484 1768992768 3.8561134338 3.9680154324 4.0439782143 855 1311867747.1389479637 0.2283547074 0.1238950153 0.2374686003 0.0047684053 0.1166780000 0.0124060000 0.0344250000 0.0003180000 0.0002820000 0.0508730000 28114422 96830484 1767600128 3.8566813469 3.9695603848 4.0441551208 856 1311867747.1744880676 0.2285728008 0.1240173024 0.2374686003 0.0047664540 0.1509580000 0.0098350000 0.0673760000 0.0000300000 0.0002850000 0.0437400000 28116672 96830484 1769209856 3.8565933704 3.9688389301 4.0441441536 857 1311867747.2066030502 0.2285064459 0.1241392268 0.2374686003 0.0047647335 0.1934580000 0.0126520000 0.0651210000 0.0004460000 0.0002780000 0.0762940000 28118858 96830484 1767981056 3.8566803932 3.9682095051 4.0440526009 858 1311867747.2385439873 0.2274731696 0.1242596626 0.2374686003 0.0047629120 0.1371990000 0.0102490000 0.0649520000 0.0000330000 0.0003640000 0.0435800000 28121076 96830484 1769582592 3.8576693535 3.9691584110 4.0428032875 859 1311867747.2745490074 0.2287471294 0.1243813011 0.2374686003 0.0047731011 0.1366370000 0.0122230000 0.0555990000 0.0003010000 0.0002770000 0.0507780000 28123326 96830484 1768345600 3.8572442532 3.9677574635 4.0442481041 860 1311867747.3064720631 0.2298444062 0.1245039326 0.2374686003 0.0047816049 0.1349390000 0.0097540000 0.0663600000 0.0000290000 0.0003620000 0.0417840000 28125448 96830484 1769836544 3.8565845490 3.9666581154 4.0452303886 861 1311867747.3388469219 0.2264635116 0.1246223526 0.2374686003 0.0048079982 0.1587540000 0.0121140000 0.0508840000 0.0002930000 0.0002710000 0.0782160000 28127698 96830484 1768480768 3.8590507507 3.9679594040 4.0427122116 862 1311867747.3758800030 0.2290292978 0.1247434743 0.2374686003 0.0048183734 0.1294810000 0.0100940000 0.0501900000 0.0000290000 0.0002920000 0.0440390000 28129916 96830484 1770217472 3.8576474190 3.9667377472 4.0447573662 863 1311867747.4068729877 0.2277567387 0.1248628408 0.2374686003 0.0048185644 0.1364820000 0.0125120000 0.0486130000 0.0005620000 0.0002800000 0.0509210000 28132102 96830484 1768873984 3.8587243557 3.9680049419 4.0440182686 864 1311867747.4396450520 0.2259663045 0.1249798587 0.2374686003 0.0048184851 0.1165810000 0.0102450000 0.0444040000 0.0000290000 0.0003170000 0.0447640000 28134256 96830484 1770487808 3.8601148129 3.9694457054 4.0424232483 865 1311867747.4756069183 0.2257903963 0.1250964026 0.2374686003 0.0048170179 0.1745800000 0.0122180000 0.0602650000 0.0002890000 0.0003490000 0.0789830000 28136506 96830484 1769115648 3.8600599766 3.9690544605 4.0420789719 866 1311867747.5095520020 0.2270482033 0.1252141299 0.2374686003 0.0048159867 0.1367160000 0.0119480000 0.0652140000 0.0004270000 0.0003090000 0.0417880000 28138756 96830484 1767862272 3.8598382473 3.9689874649 4.0441193581 867 1311867747.5405330658 0.2253880203 0.1253296707 0.2374686003 0.0048232424 0.1514440000 0.0099030000 0.0652830000 0.0003560000 0.0024270000 0.0494110000 28140910 96830484 1769455616 3.8606836796 3.9695982933 4.0417785645 868 1311867747.5766739845 0.2275978178 0.1254474912 0.2374686003 0.0048231204 0.1369130000 0.0125020000 0.0660330000 0.0000310000 0.0003630000 0.0408710000 28143160 96830484 1768099840 3.8591597080 3.9678356647 4.0434365273 869 1311867747.6086390018 0.2182731181 0.1255543101 0.2374686003 0.0048681872 0.1705850000 0.0098460000 0.0643640000 0.0003630000 0.0002750000 0.0789800000 28145346 96830484 1769836544 3.8646910191 3.9755799770 4.0335936546 870 1311867747.6432039738 0.2254826725 0.1256691702 0.2374686003 0.0048952116 0.1387840000 0.0116650000 0.0654040000 0.0000260000 0.0003630000 0.0443590000 28147596 96830484 1768718336 3.8607227802 3.9703483582 4.0417571068 871 1311867747.6760280132 0.2249943912 0.1257832061 0.2374686003 0.0048981270 0.1520500000 0.0099000000 0.0643380000 0.0003620000 0.0002780000 0.0523940000 28149782 96830484 1770344448 3.8611774445 3.9699089527 4.0417714119 872 1311867747.7068400383 0.2245210409 0.1258964376 0.2374686003 0.0048975979 0.1382380000 0.0127440000 0.0641800000 0.0000320000 0.0003110000 0.0439560000 28151936 96830484 1769099264 3.8600215912 3.9724378586 4.0387821198 873 1311867747.7480750084 0.2279630005 0.1260133523 0.2374686003 0.0049203078 0.1859380000 0.0128330000 0.0639620000 0.0003610000 0.0002730000 0.0827520000 28154346 96830484 1768845312 3.8580734730 3.9698245525 4.0430240631 874 1311867747.7826869488 0.2270012349 0.1261288991 0.2374686003 0.0049180579 0.1183020000 0.0105790000 0.0484970000 0.0000280000 0.0003600000 0.0419820000 28156564 96830484 1770487808 3.8590071201 3.9692316055 4.0428981781 875 1311867747.8149020672 0.2248716354 0.1262417479 0.2374686003 0.0049178448 0.1534580000 0.0119660000 0.0650200000 0.0003590000 0.0002750000 0.0517560000 28158750 96830484 1769369600 3.8598608971 3.9697389603 4.0407900810 876 1311867747.8466539383 0.2264647037 0.1263561577 0.2374686003 0.0049169138 0.1368520000 0.0119960000 0.0645890000 0.0000300000 0.0005130000 0.0425340000 28160904 96830484 1768587264 3.8587176800 3.9704704285 4.0420393944 877 1311867747.8827810287 0.2293699086 0.1264736192 0.2374686003 0.0049245697 0.1717000000 0.0097000000 0.0551780000 0.0002940000 0.0002690000 0.0821350000 28163186 96830484 1770344448 3.8564839363 3.9693107605 4.0444130898 878 1311867747.9150440693 0.2280478776 0.1265893074 0.2374686003 0.0049222372 0.1385670000 0.0123640000 0.0645390000 0.0000290000 0.0003680000 0.0441440000 28165404 96830484 1769226240 3.8561630249 3.9704148769 4.0419473648 879 1311867747.9477820396 0.2301612049 0.1267071366 0.2374686003 0.0049208381 0.1344980000 0.0114330000 0.0385750000 0.0003610000 0.0002800000 0.0657150000 28167590 96830484 1768206336 3.8547692299 3.9688482285 4.0445470810 880 1311867747.9826579094 0.2300794572 0.1268246052 0.2374686003 0.0049185116 0.1519870000 0.0101370000 0.0697590000 0.0000300000 0.0003690000 0.0469930000 28169808 96830484 1769869312 3.8546512127 3.9685726166 4.0450377464 881 1311867748.0146598816 0.2319394499 0.1269439183 0.2374686003 0.0049200478 0.1585510000 0.0122890000 0.0382490000 0.0003210000 0.0004950000 0.0809820000 28171994 96830484 1768873984 3.8528575897 3.9681308270 4.0467691422 882 1311867748.0469269753 0.2319433987 0.1270629653 0.2374686003 0.0049175698 0.1348830000 0.0095630000 0.0651500000 0.0000270000 0.0003030000 0.0428630000 28174180 96830484 1770598400 3.8518424034 3.9689283371 4.0462317467 883 1311867748.0828750134 0.2331723124 0.1271831345 0.2374686003 0.0049155130 0.1357320000 0.0120650000 0.0448940000 0.0003860000 0.0002870000 0.0514380000 28176462 96830484 1769480192 3.8503792286 3.9683003426 4.0473732948 884 1311867748.1150569916 0.2337271422 0.1273036594 0.2374686003 0.0049149177 0.1520830000 0.0118830000 0.0653990000 0.0000300000 0.0003070000 0.0440610000 28178616 96830484 1768460288 3.8500115871 3.9677164555 4.0487756729 885 1311867748.1486010551 0.2347975820 0.1274251214 0.2374686003 0.0049139145 0.1713050000 0.0101810000 0.0653510000 0.0002910000 0.0003430000 0.0781130000 28180834 96830484 1770106880 3.8480255604 3.9686732292 4.0481028557 886 1311867748.1831040382 0.2339206487 0.1275453195 0.2374686003 0.0049114673 0.1236980000 0.0116240000 0.0540200000 0.0000310000 0.0003750000 0.0404170000 28183020 96830484 1768988672 3.8487138748 3.9681680202 4.0480656624 887 1311867748.2148320675 0.2366520762 0.1276683260 0.2374686003 0.0049123865 0.1307800000 0.0111450000 0.0386690000 0.0001140000 0.0001000000 0.0540530000 28185238 96830484 1768206336 3.8465585709 3.9672353268 4.0504131317 888 1311867748.2466599941 0.2358897775 0.1277901970 0.2374686003 0.0049110724 0.1369370000 0.0098770000 0.0649720000 0.0000270000 0.0002880000 0.0435860000 28187392 96830484 1769869312 3.8468601704 3.9679584503 4.0494875908 889 1311867748.2827599049 0.2349691391 0.1279107583 0.2374686003 0.0049087534 0.1448620000 0.0121250000 0.0337290000 0.0003590000 0.0002760000 0.0800710000 28189642 96830484 1768964096 3.8474237919 3.9679172039 4.0489201546 890 1311867748.3148829937 0.2347235084 0.1280307726 0.2374686003 0.0049149001 0.1418100000 0.0097970000 0.0657910000 0.0000300000 0.0003550000 0.0431390000 28191828 96830484 1770635264 3.8477458954 3.9674208164 4.0493912697 891 1311867748.3470869064 0.2352109104 0.1281510646 0.2374686003 0.0049181754 0.1174740000 0.0125590000 0.0344980000 0.0002920000 0.0003420000 0.0525330000 28194014 96830484 1769508864 3.8468351364 3.9668235779 4.0489244461 892 1311867748.3826999664 0.2355403602 0.1282714561 0.2374686003 0.0049190070 0.1354240000 0.0115750000 0.0660610000 0.0000280000 0.0003660000 0.0401470000 28196264 96830484 1768734720 3.8466284275 3.9673235416 4.0493679047 893 1311867748.4148259163 0.2352632433 0.1283912678 0.2374686003 0.0049166332 0.1718750000 0.0098230000 0.0666240000 0.0003170000 0.0003440000 0.0777110000 28198418 96830484 1770471424 3.8462228775 3.9686198235 4.0482912064 894 1311867748.4520189762 0.2365553379 0.1285122567 0.2374686003 0.0049203703 0.1364260000 0.0118910000 0.0561230000 0.0000950000 0.0002850000 0.0430260000 28200700 96830484 1769345024 3.8448772430 3.9670648575 4.0496301651 895 1311867748.4831318855 0.2360667735 0.1286324293 0.2374686003 0.0049178459 0.1539260000 0.0119300000 0.0659520000 0.0003010000 0.0002740000 0.0498960000 28202886 96830484 1768325120 3.8447980881 3.9677512646 4.0487546921 896 1311867748.5149960518 0.2344740182 0.1287505561 0.2374686003 0.0049154747 0.1366530000 0.0098610000 0.0662650000 0.0000310000 0.0003930000 0.0426430000 28205072 96830484 1769971712 3.8460185528 3.9684689045 4.0478601456 897 1311867748.5467929840 0.2362016737 0.1288703455 0.2374686003 0.0049135566 0.1520460000 0.0119450000 0.0453140000 0.0003100000 0.0002780000 0.0768220000 28207226 96830484 1768964096 3.8444802761 3.9675183296 4.0494766235 898 1311867748.5827159882 0.2368600219 0.1289906013 0.2374686003 0.0049108735 0.1186820000 0.0100280000 0.0517950000 0.0000320000 0.0002970000 0.0393950000 28209476 96830484 1770606592 3.8433787823 3.9678254128 4.0493736267 899 1311867748.6147999763 0.2350881398 0.1291086186 0.2374686003 0.0049091441 0.1534560000 0.0120090000 0.0685430000 0.0003170000 0.0002650000 0.0502630000 28211694 96830484 1769504768 3.8448371887 3.9685943127 4.0490169525 900 1311867748.6470849514 0.2356765866 0.1292270274 0.2374686003 0.0049183100 0.1519110000 0.0124330000 0.0665590000 0.0000380000 0.0003790000 0.0420120000 28213848 96830484 1768579072 3.8442738056 3.9684314728 4.0500760078 901 1311867748.6827559471 0.2346577495 0.1293440426 0.2374686003 0.0049160698 0.1514090000 0.0099120000 0.0480400000 0.0002890000 0.0003510000 0.0757090000 28216098 96830484 1770225664 3.8451046944 3.9682343006 4.0499196053 902 1311867748.7147359848 0.2341148704 0.1294601966 0.2374686003 0.0049336255 0.1429710000 0.0115110000 0.0703900000 0.0000290000 0.0003610000 0.0431170000 28218284 96830484 1769107456 3.8459026814 3.9669275284 4.0505318642 903 1311867748.7499361038 0.2355958521 0.1295777333 0.2374686003 0.0049315560 0.1533420000 0.0118410000 0.0683170000 0.0003190000 0.0002730000 0.0492890000 28220502 96830484 1768325120 3.8442196846 3.9664916992 4.0511646271 904 1311867748.7828259468 0.2349918187 0.1296943418 0.2374686003 0.0049294178 0.1153970000 0.0106220000 0.0461130000 0.0000300000 0.0004500000 0.0409210000 28222752 96830484 1770098688 3.8442702293 3.9669661522 4.0505375862 905 1311867748.8151619434 0.2349100262 0.1298106022 0.2374686003 0.0049269767 0.1538150000 0.0119740000 0.0396750000 0.0001170000 0.0001060000 0.0777460000 28224938 96830484 1768980480 3.8441445827 3.9671552181 4.0508317947 906 1311867748.8466329575 0.2344508469 0.1299260992 0.2374686003 0.0049244128 0.1371730000 0.0115860000 0.0668180000 0.0000300000 0.0002990000 0.0407780000 28227060 96830484 1768218624 3.8441016674 3.9672989845 4.0506711006 907 1311867748.8829579353 0.2340402156 0.1300408887 0.2374686003 0.0049223634 0.1517220000 0.0097920000 0.0679090000 0.0003100000 0.0003490000 0.0491380000 28229310 96830484 1769861120 3.8436391354 3.9674484730 4.0502166748 908 1311867748.9149119854 0.2331051826 0.1301543956 0.2374686003 0.0049208367 0.1168790000 0.0129200000 0.0406420000 0.0000300000 0.0004000000 0.0410330000 28231528 96830484 1768964096 3.8437573910 3.9685540199 4.0498881340 909 1311867748.9472498894 0.2346496731 0.1302693519 0.2374686003 0.0049183162 0.1521620000 0.0102580000 0.0346410000 0.0003860000 0.0002820000 0.0810780000 28233714 96830484 1770606592 3.8418419361 3.9674639702 4.0507135391 910 1311867748.9829359055 0.2321440876 0.1303813022 0.2374686003 0.0049170106 0.1385160000 0.0125540000 0.0658780000 0.0000300000 0.0003070000 0.0414380000 28235964 96830484 1769500672 3.8431081772 3.9683537483 4.0489912033 911 1311867749.0159859657 0.2313289493 0.1304921119 0.2374686003 0.0049143184 0.1151130000 0.0121530000 0.0342970000 0.0003190000 0.0003590000 0.0503650000 28238150 96830484 1768452096 3.8432886600 3.9694795609 4.0483341217 912 1311867749.0467190742 0.2308717221 0.1306021773 0.2374686003 0.0049120531 0.1700960000 0.0138020000 0.0873780000 0.0000950000 0.0003110000 0.0408770000 28240304 96830484 1770098688 3.8433666229 3.9692888260 4.0484142303 913 1311867749.0828969479 0.2306027114 0.1307117069 0.2374686003 0.0049094969 0.1721000000 0.0125150000 0.0675420000 0.0003760000 0.0002830000 0.0738530000 28242554 96830484 1769091072 3.8431806564 3.9694490433 4.0482959747 914 1311867749.1158421040 0.2291117162 0.1308193655 0.2374686003 0.0049077944 0.1408320000 0.0110500000 0.0667630000 0.0000330000 0.0003690000 0.0406570000 28244772 96830484 1767981056 3.8443014622 3.9704313278 4.0476241112 915 1311867749.1485249996 0.2291050851 0.1309267816 0.2374686003 0.0049051244 0.1132100000 0.0099790000 0.0289020000 0.0005470000 0.0002860000 0.0504120000 28246990 96830484 1769717760 3.8439912796 3.9709298611 4.0476469994 916 1311867749.1829619408 0.2289685905 0.1310338142 0.2374686003 0.0049029575 0.1376780000 0.0125500000 0.0687070000 0.0000300000 0.0002990000 0.0385170000 28249208 96830484 1768853504 3.8433649540 3.9710409641 4.0474252701 917 1311867749.2156000137 0.2279371470 0.1311394885 0.2374686003 0.0049007117 0.1689570000 0.0098370000 0.0679980000 0.0003100000 0.0002860000 0.0730030000 28251362 96830484 1770496000 3.8441598415 3.9711456299 4.0469651222 918 1311867749.2468719482 0.2279480696 0.1312449444 0.2374686003 0.0049014074 0.1402460000 0.0118790000 0.0668510000 0.0000290000 0.0003810000 0.0409000000 28253516 96830484 1768853504 3.8439805508 3.9704003334 4.0465030670 919 1311867749.2828478813 0.2283537984 0.1313506124 0.2374686003 0.0049029152 0.1346940000 0.0105330000 0.0573660000 0.0003120000 0.0003500000 0.0472950000 28255766 96830484 1770622976 3.8437561989 3.9697868824 4.0476322174 920 1311867749.3148140907 0.2278178185 0.1314554680 0.2374686003 0.0049018889 0.1376450000 0.0118990000 0.0686180000 0.0000310000 0.0003080000 0.0389730000 28257984 96830484 1769852928 3.8435652256 3.9715821743 4.0460929871 921 1311867749.3468968868 0.2272217870 0.1315594489 0.2374686003 0.0048998061 0.1718890000 0.0117870000 0.0578110000 0.0003090000 0.0003560000 0.0754930000 28260138 96830484 1768837120 3.8435766697 3.9721729755 4.0457725525 922 1311867749.3828470707 0.2265265882 0.1316624501 0.2374686003 0.0048972502 0.1162900000 0.0103770000 0.0464730000 0.0000350000 0.0006540000 0.0401490000 28262388 96830484 1770479616 3.8432185650 3.9729666710 4.0443234444 923 1311867749.4147930145 0.2240993977 0.1317625985 0.2374686003 0.0048956081 0.1164320000 0.0126060000 0.0348650000 0.0003890000 0.0002840000 0.0497310000 28264606 96830484 1769472000 3.8448393345 3.9751839638 4.0428900719 924 1311867749.4467489719 0.2245584726 0.1318630269 0.2374686003 0.0048932535 0.1162530000 0.0124690000 0.0492680000 0.0000290000 0.0003810000 0.0361780000 28266760 96830484 1768361984 3.8438594341 3.9759542942 4.0428309441 925 1311867749.4829080105 0.2229392380 0.1319614877 0.2374686003 0.0048931858 0.1684230000 0.0098350000 0.0693140000 0.0003830000 0.0002790000 0.0711760000 28269010 96830484 1769971712 3.8442525864 3.9757220745 4.0420341492 926 1311867749.5159850121 0.2235775143 0.1320604251 0.2374686003 0.0048909902 0.1418110000 0.0115330000 0.0702900000 0.0000260000 0.0003040000 0.0389790000 28271196 96830484 1769082880 3.8432140350 3.9742107391 4.0428953171 927 1311867749.5468530655 0.2244040966 0.1321600407 0.2374686003 0.0048884335 0.1513730000 0.0121570000 0.0698940000 0.0003960000 0.0002850000 0.0460020000 28273382 96830484 1767854080 3.8412523270 3.9746868610 4.0421466827 928 1311867749.5830268860 0.2235516757 0.1322585230 0.2374686003 0.0048859967 0.1292480000 0.0103310000 0.0540010000 0.0000300000 0.0003640000 0.0390570000 28275632 96830484 1769590784 3.8412432671 3.9745645523 4.0418424606 929 1311867749.6148250103 0.2227054983 0.1323558825 0.2374686003 0.0048836082 0.1375980000 0.0125300000 0.0358660000 0.0003840000 0.0002800000 0.0706380000 28277786 96830484 1768591360 3.8411958218 3.9747416973 4.0412988663 930 1311867749.6469049454 0.2223857492 0.1324526888 0.2374686003 0.0048825195 0.0983620000 0.0097780000 0.0319080000 0.0000300000 0.0003230000 0.0382280000 28280004 96830484 1770373120 3.8414242268 3.9742088318 4.0418057442 931 1311867749.6829149723 0.2223682404 0.1325492684 0.2374686003 0.0048804110 0.1180770000 0.0116900000 0.0488740000 0.0003100000 0.0003560000 0.0389780000 28282254 96830484 1769472000 3.8401575089 3.9738247395 4.0411229134 932 1311867749.7160799503 0.2224117219 0.1326456873 0.2374686003 0.0048782256 0.1276010000 0.0117270000 0.0447810000 0.0000290000 0.0003910000 0.0387820000 28284440 96830484 1768452096 3.8394863605 3.9738342762 4.0404701233 933 1311867749.7468609810 0.2218503505 0.1327412979 0.2374686003 0.0048795578 0.1728420000 0.0102070000 0.0555120000 0.0003100000 0.0002890000 0.0785360000 28286626 96830484 1770225664 3.8399686813 3.9735369682 4.0404109955 934 1311867749.7828791142 0.2194806337 0.1328341666 0.2374686003 0.0048784446 0.1392230000 0.0124960000 0.0716040000 0.0000280000 0.0003010000 0.0370380000 28288876 96830484 1769107456 3.8412444592 3.9731621742 4.0393381119 935 1311867749.8148949146 0.2183689326 0.1329256476 0.2374686003 0.0048799453 0.1143360000 0.0114020000 0.0367680000 0.0003030000 0.0002830000 0.0476980000 28291030 96830484 1768325120 3.8416371346 3.9736416340 4.0388474464 936 1311867749.8469030857 0.2185492069 0.1330171258 0.2374686003 0.0048777362 0.1129700000 0.0097210000 0.0420450000 0.0000310000 0.0003150000 0.0378680000 28293248 96830484 1770082304 3.8412706852 3.9742269516 4.0391592979 937 1311867749.8829030991 0.2193878442 0.1331093037 0.2374686003 0.0048931700 0.1697350000 0.0125770000 0.0695600000 0.0003740000 0.0002900000 0.0691690000 28295498 96830484 1768964096 3.8402283192 3.9734215736 4.0390033722 938 1311867749.9149639606 0.2178339511 0.1331996285 0.2374686003 0.0049083360 0.1189210000 0.0097280000 0.0412490000 0.0000280000 0.0010280000 0.0374280000 28297652 96830484 1770606592 3.8406641483 3.9738311768 4.0382928848 939 1311867749.9508709908 0.2170946151 0.1332889735 0.2374686003 0.0049065284 0.1558610000 0.0130380000 0.0693280000 0.0003650000 0.0002750000 0.0449720000 28299902 96830484 1769598976 3.8411014080 3.9736700058 4.0384130478 940 1311867749.9827940464 0.2167684585 0.1333777815 0.2374686003 0.0049062490 0.1348820000 0.0124580000 0.0581120000 0.0000300000 0.0002890000 0.0377840000 28302120 96830484 1768488960 3.8408746719 3.9740817547 4.0380096436 941 1311867750.0147750378 0.2151765972 0.1334647090 0.2374686003 0.0049041512 0.1736120000 0.0104200000 0.0667120000 0.0002910000 0.0003380000 0.0680990000 28304306 96830484 1770225664 3.8419334888 3.9737303257 4.0375742912 942 1311867750.0470709801 0.2139875144 0.1335501897 0.2374686003 0.0049017157 0.1161000000 0.0130460000 0.0374100000 0.0000280000 0.0002820000 0.0396910000 28306492 96830484 1769107456 3.8426811695 3.9735190868 4.0371484756 943 1311867750.0829339027 0.2143544108 0.1336358782 0.2374686003 0.0048999439 0.1160070000 0.0114300000 0.0356680000 0.0003940000 0.0002770000 0.0440970000 28308742 96830484 1768325120 3.8418459892 3.9737596512 4.0370345116 944 1311867750.1156458855 0.2140313238 0.1337210428 0.2374686003 0.0048978530 0.1348820000 0.0100660000 0.0696180000 0.0000290000 0.0003620000 0.0370990000 28310928 96830484 1770098688 3.8417022228 3.9737541676 4.0367889404 945 1311867750.1474790573 0.2139098197 0.1338058987 0.2374686003 0.0048958783 0.1676410000 0.0124650000 0.0691800000 0.0003560000 0.0002720000 0.0673050000 28313114 96830484 1768996864 3.8415215015 3.9738600254 4.0368556976 946 1311867750.1828711033 0.2130421549 0.1338896579 0.2374686003 0.0048946721 0.1040950000 0.0107190000 0.0356490000 0.0000260000 0.0002830000 0.0381140000 28315364 96830484 1768198144 3.8418996334 3.9738910198 4.0363216400 947 1311867750.2156589031 0.2128186822 0.1339730043 0.2374686003 0.0048925384 0.1144290000 0.0099490000 0.0418180000 0.0003140000 0.0002760000 0.0439980000 28317550 96830484 1769955328 3.8417201042 3.9745812416 4.0362067223 948 1311867750.2469079494 0.2125687897 0.1340559113 0.2374686003 0.0048900343 0.1360930000 0.0121130000 0.0651210000 0.0001570000 0.0002960000 0.0363080000 28319704 96830484 1768964096 3.8415439129 3.9745762348 4.0360732079 949 1311867750.2829968929 0.2118418962 0.1341378775 0.2374686003 0.0048894609 0.1662030000 0.0118950000 0.0696240000 0.0002980000 0.0003470000 0.0657020000 28321954 96830484 1767981056 3.8419113159 3.9754042625 4.0363116264 950 1311867750.3150129318 0.2119905204 0.1342198277 0.2374686003 0.0048871613 0.1210090000 0.0095110000 0.0485540000 0.0000260000 0.0003560000 0.0355280000 28324172 96830484 1769734144 3.8412194252 3.9758329391 4.0359287262 951 1311867750.3469090462 0.2101154923 0.1342996338 0.2374686003 0.0048865926 0.1183750000 0.0124160000 0.0422220000 0.0002980000 0.0002740000 0.0430580000 28326326 96830484 1768980480 3.8429074287 3.9745090008 4.0358214378 952 1311867750.3828659058 0.2105767280 0.1343797568 0.2374686003 0.0048840983 0.1165800000 0.0126120000 0.0528890000 0.0000280000 0.0002880000 0.0325930000 28328576 96830484 1767833600 3.8422818184 3.9755020142 4.0358047485 953 1311867750.4148640633 0.2104966491 0.1344596277 0.2374686003 0.0048816403 0.1503600000 0.0096830000 0.0410080000 0.0010560000 0.0002770000 0.0689920000 28330794 96830484 1769717760 3.8420097828 3.9751894474 4.0358386040 954 1311867750.4469859600 0.2096897215 0.1345384852 0.2374686003 0.0048791449 0.1179200000 0.0126950000 0.0476530000 0.0000270000 0.0005110000 0.0354650000 28332948 96830484 1768833024 3.8423097134 3.9748725891 4.0355668068 955 1311867750.4829618931 0.2092818618 0.1346167505 0.2374686003 0.0048771618 0.1142890000 0.0102950000 0.0358570000 0.0003540000 0.0002700000 0.0453770000 28335166 96830484 1770496000 3.8421993256 3.9752621651 4.0346183777 956 1311867750.5148859024 0.2091940492 0.1346947602 0.2374686003 0.0048747965 0.0992300000 0.0126480000 0.0342500000 0.0000300000 0.0002890000 0.0339320000 28337320 96830484 1767301120 3.8419075012 3.9753899574 4.0342841148 957 1311867750.5476069450 0.2080843300 0.1347714474 0.2374686003 0.0048729251 0.1311580000 0.0102330000 0.0374750000 0.0002980000 0.0042540000 0.0607470000 28339538 96830484 1768218624 3.8427877426 3.9746472836 4.0339694023 958 1311867750.5827779770 0.2077225894 0.1348475968 0.2374686003 0.0048726048 0.1135300000 0.0099730000 0.0443310000 0.0000290000 0.0003890000 0.0355910000 28341788 96830484 1764257792 3.8428297043 3.9757308960 4.0337238312 959 1311867750.6148829460 0.2070266008 0.1349228616 0.2374686003 0.0048710332 0.1121600000 0.0106630000 0.0367900000 0.0003940000 0.0002860000 0.0425740000 28343942 96830484 1765908480 3.8430528641 3.9763035774 4.0332036018 960 1311867750.6469810009 0.2068050355 0.1349977389 0.2374686003 0.0048687601 0.1141140000 0.0103960000 0.0421150000 0.0000280000 0.0003210000 0.0350310000 28346160 96830484 1767686144 3.8426218033 3.9760527611 4.0328798294 961 1311867750.6829319000 0.2065624297 0.1350722079 0.2374686003 0.0048687617 0.1342290000 0.0103060000 0.0409240000 0.0003050000 0.0006610000 0.0640360000 28348410 96830484 1769336832 3.8424029350 3.9769361019 4.0330505371 962 1311867750.7149219513 0.2050943226 0.1351449959 0.2374686003 0.0048682843 0.1368350000 0.0112370000 0.0712260000 0.0000270000 0.0003620000 0.0345890000 28350628 96830484 1768325120 3.8435668945 3.9767343998 4.0328965187 963 1311867750.7469151020 0.2047617584 0.1352172875 0.2374686003 0.0048660479 0.1152180000 0.0101720000 0.0477960000 0.0003250000 0.0002980000 0.0388030000 28352782 96830484 1769992192 3.8436048031 3.9760580063 4.0329418182 964 1311867750.7832129002 0.2039690763 0.1352886068 0.2374686003 0.0048661902 0.1130610000 0.0116310000 0.0345300000 0.0000260000 0.0002850000 0.0367050000 28355000 96830484 1767956480 3.8440270424 3.9765222073 4.0331187248 965 1311867750.8149549961 0.2026589513 0.1353584206 0.2374686003 0.0048637631 0.1289280000 0.0107130000 0.0362980000 0.0003220000 0.0003550000 0.0630270000 28357122 96830484 1767473152 3.8452172279 3.9777622223 4.0332837105 966 1311867750.8468461037 0.2022638768 0.1354276809 0.2374686003 0.0048658484 0.1189750000 0.0093750000 0.0498080000 0.0000270000 0.0003530000 0.0338440000 28359308 96830484 1766690816 3.8451979160 3.9775524139 4.0330591202 967 1311867750.8828840256 0.2016653270 0.1354961790 0.2374686003 0.0048634980 0.1150070000 0.0102360000 0.0374500000 0.0002950000 0.0002700000 0.0462200000 28361590 96830484 1768464384 3.8455052376 3.9776620865 4.0329194069 968 1311867750.9147970676 0.2007384151 0.1355635780 0.2374686003 0.0048619669 0.0955770000 0.0098330000 0.0281950000 0.0000070000 0.0000600000 0.0355100000 28363744 96830484 1770225664 3.8463909626 3.9778788090 4.0330419540 969 1311867750.9468770027 0.2008556426 0.1356309589 0.2374686003 0.0048603783 0.1704350000 0.0125830000 0.0756070000 0.0008050000 0.0002960000 0.0627220000 28365930 96830484 1769340928 3.8460223675 3.9783253670 4.0330648422 970 1311867750.9830369949 0.2002655268 0.1356975924 0.2374686003 0.0048595434 0.1400400000 0.0113770000 0.0687490000 0.0000290000 0.0002900000 0.0332270000 28368212 96830484 1768579072 3.8463945389 3.9773235321 4.0329475403 971 1311867751.0168409348 0.1987982243 0.1357625776 0.2374686003 0.0048587611 0.1370750000 0.0104070000 0.0690100000 0.0002970000 0.0002740000 0.0389310000 28370430 96830484 1770352640 3.8474972248 3.9769177437 4.0325484276 972 1311867751.0470340252 0.1980252862 0.1358266339 0.2374686003 0.0048576048 0.1155730000 0.0119620000 0.0495160000 0.0000300000 0.0003090000 0.0334700000 28372584 96830484 1769250816 3.8475906849 3.9779343605 4.0320100784 973 1311867751.0828599930 0.1963500977 0.1358888369 0.2374686003 0.0048552466 0.1340880000 0.0105920000 0.0427120000 0.0003220000 0.0002830000 0.0620880000 28374802 96830484 1771028480 3.8488416672 3.9781227112 4.0312657356 974 1311867751.1174809933 0.1972059608 0.1359517908 0.2374686003 0.0048531190 0.1146240000 0.0119010000 0.0422570000 0.0000260000 0.0003850000 0.0334130000 28377052 96830484 1769869312 3.8474161625 3.9769423008 4.0308904648 975 1311867751.1468789577 0.1963721663 0.1360137604 0.2374686003 0.0048533600 0.1485510000 0.0123750000 0.0692330000 0.0000630000 0.0000540000 0.0341880000 28379174 96830484 1769086976 3.8482069969 3.9773213863 4.0305819511 976 1311867751.1835930347 0.1948130876 0.1360740056 0.2374686003 0.0048525333 0.1422730000 0.0115000000 0.0791760000 0.0000280000 0.0002880000 0.0328340000 28381456 96830484 1768325120 3.8490638733 3.9780974388 4.0300593376 977 1311867751.2161049843 0.1956404150 0.1361349743 0.2374686003 0.0048503700 0.1283870000 0.0096710000 0.0362350000 0.0003070000 0.0003560000 0.0635560000 28383642 96830484 1770082304 3.8478550911 3.9780483246 4.0298347473 978 1311867751.2468481064 0.1957242489 0.1361959040 0.2374686003 0.0048490604 0.1194810000 0.0113260000 0.0433220000 0.0000320000 0.0003130000 0.0331210000 28385796 96830484 1769091072 3.8477320671 3.9775834084 4.0295591354 979 1311867751.2831909657 0.1956628114 0.1362566465 0.2374686003 0.0048511232 0.1357340000 0.0115190000 0.0581920000 0.0002910000 0.0002720000 0.0403490000 28388078 96830484 1768071168 3.8474929333 3.9799346924 4.0295310020 980 1311867751.3149859905 0.1951692849 0.1363167615 0.2374686003 0.0048488272 0.1161280000 0.0101960000 0.0530010000 0.0000270000 0.0002920000 0.0335170000 28390232 96830484 1769844736 3.8477847576 3.9801774025 4.0293073654 981 1311867751.3498640060 0.1959815174 0.1363775818 0.2374686003 0.0048477113 0.1367180000 0.0127650000 0.0440700000 0.0003880000 0.0002850000 0.0606660000 28392482 96830484 1768964096 3.8464396000 3.9783673286 4.0289921761 982 1311867751.3834669590 0.1945601255 0.1364368309 0.2374686003 0.0048463369 0.1136630000 0.0096530000 0.0432950000 0.0000320000 0.0003210000 0.0330380000 28394700 96830484 1770622976 3.8473975658 3.9799704552 4.0282440186 983 1311867751.4151160717 0.1931840479 0.1364945595 0.2374686003 0.0048459261 0.1175870000 0.0123540000 0.0425330000 0.0002910000 0.0002750000 0.0397670000 28396886 96830484 1769607168 3.8489181995 3.9803593159 4.0275206566 984 1311867751.4513890743 0.1928046793 0.1365517852 0.2374686003 0.0048446920 0.1313700000 0.0123680000 0.0550870000 0.0000310000 0.0002910000 0.0324940000 28399104 96830484 1768706048 3.8488614559 3.9782903194 4.0272769928 985 1311867751.4838130474 0.1931323111 0.1366092273 0.2374686003 0.0048422836 0.1548180000 0.0101950000 0.0537920000 0.0002860000 0.0003450000 0.0635400000 28401322 96830484 1770369024 3.8485329151 3.9787805080 4.0267820358 986 1311867751.5149779320 0.1926798671 0.1366660941 0.2374686003 0.0048413642 0.1379410000 0.0124150000 0.0714040000 0.0000290000 0.0002950000 0.0329110000 28403508 96830484 1769472000 3.8484952450 3.9801154137 4.0265884399 987 1311867751.5495769978 0.1924131513 0.1367225754 0.2374686003 0.0048391401 0.1138990000 0.0117390000 0.0349560000 0.0002890000 0.0002680000 0.0421440000 28405726 96830484 1768452096 3.8484673500 3.9796667099 4.0264954567 988 1311867751.5829720497 0.1908624023 0.1367773728 0.2374686003 0.0048369805 0.1125880000 0.0099970000 0.0362450000 0.0000260000 0.0002960000 0.0332500000 28407912 96830484 1770225664 3.8502769470 3.9798150063 4.0263056755 989 1311867751.6149520874 0.1906782389 0.1368318732 0.2374686003 0.0048354566 0.1304110000 0.0125390000 0.0359470000 0.0002910000 0.0002730000 0.0622230000 28410098 96830484 1769218048 3.8502559662 3.9804253578 4.0261230469 990 1311867751.6501350403 0.1894340962 0.1368850068 0.2374686003 0.0048336464 0.1209620000 0.0109560000 0.0494800000 0.0000290000 0.0003000000 0.0332040000 28412316 96830484 1768071168 3.8508791924 3.9799587727 4.0257673264 991 1311867751.6839730740 0.1890386939 0.1369376341 0.2374686003 0.0048312643 0.1339920000 0.0099900000 0.0547230000 0.0002940000 0.0003510000 0.0395250000 28414566 96830484 1769848832 3.8510751724 3.9799268246 4.0255599022 992 1311867751.7150709629 0.1883829385 0.1369894943 0.2374686003 0.0048300690 0.1554280000 0.0128050000 0.0768900000 0.0000260000 0.0003830000 0.0341160000 28416688 96830484 1768464384 3.8515381813 3.9793992043 4.0253677368 993 1311867751.7507519722 0.1872891784 0.1370401485 0.2374686003 0.0048278950 0.1523080000 0.0100670000 0.0480020000 0.0003830000 0.0006270000 0.0640840000 28418938 96830484 1770209280 3.8522243500 3.9793684483 4.0250420570 994 1311867751.7830109596 0.1875143498 0.1370909274 0.2374686003 0.0048264073 0.1143410000 0.0131100000 0.0431220000 0.0000300000 0.0005550000 0.0324920000 28421124 96830484 1768865792 3.8516383171 3.9790835381 4.0249500275 995 1311867751.8149600029 0.1865624487 0.1371406475 0.2374686003 0.0048251342 0.1154360000 0.0121420000 0.0448180000 0.0004750000 0.0002800000 0.0391350000 28423310 96830484 1770606592 3.8523635864 3.9800057411 4.0248389244 996 1311867751.8509531021 0.1856015623 0.1371893031 0.2374686003 0.0048241838 0.1170610000 0.0119660000 0.0567240000 0.0000290000 0.0003780000 0.0291250000 28425560 96830484 1769725952 3.8529942036 3.9796259403 4.0245194435 997 1311867751.8832330704 0.1854788363 0.1372377379 0.2374686003 0.0048220481 0.1507410000 0.0113640000 0.0602640000 0.0003010000 0.0003550000 0.0597600000 28427746 96830484 1768718336 3.8526370525 3.9793219566 4.0244345665 998 1311867751.9149179459 0.1849467307 0.1372855425 0.2374686003 0.0048217742 0.1144760000 0.0098060000 0.0438680000 0.0000330000 0.0003120000 0.0326390000 28429900 96830484 1770352640 3.8525745869 3.9801309109 4.0243840218 999 1311867751.9530611038 0.1824396700 0.1373307418 0.2374686003 0.0048203044 0.1555380000 0.0129950000 0.0770850000 0.0003970000 0.0002840000 0.0390340000 28432214 96830484 1769361408 3.8547453880 3.9805328846 4.0241494179 1000 1311867751.9829521179 0.1816394627 0.1373750506 0.2374686003 0.0048185824 0.1149450000 0.0122190000 0.0393050000 0.0000300000 0.0003140000 0.0377970000 28434368 96830484 1768235008 3.8551406860 3.9800539017 4.0240197182 1001 1311867752.0153670311 0.1814720184 0.1374191035 0.2374686003 0.0048187457 0.1733650000 0.0107330000 0.0758920000 0.0000590000 0.0000550000 0.0607160000 28436522 96830484 1769971712 3.8548340797 3.9810342789 4.0240645409 1002 1311867752.0510330200 0.1793754399 0.1374609761 0.2374686003 0.0048169259 0.1167830000 0.0126540000 0.0499960000 0.0000330000 0.0003130000 0.0320860000 28438772 96830484 1768964096 3.8567988873 3.9816567898 4.0235490799 1003 1311867752.0828928947 0.1785702109 0.1375019623 0.2374686003 0.0048150073 0.1307590000 0.0099270000 0.0492500000 0.0003180000 0.0003450000 0.0389060000 28440990 96830484 1770590208 3.8570468426 3.9810292721 4.0232586861 1004 1311867752.1150529385 0.1753029078 0.1375396127 0.2374686003 0.0048133348 0.1172760000 0.0125710000 0.0437890000 0.0000300000 0.0003080000 0.0314610000 28443144 96830484 1769472000 3.8601689339 3.9807078838 4.0226855278 1005 1311867752.1509859562 0.1727999449 0.1375746976 0.2374686003 0.0048123452 0.1735330000 0.0120960000 0.0719020000 0.0002910000 0.0002700000 0.0575640000 28445394 96830484 1768452096 3.8617467880 3.9812433720 4.0222063065 1006 1311867752.1829679012 0.1728625745 0.1376097750 0.2374686003 0.0048113286 0.1152830000 0.0101200000 0.0499760000 0.0000300000 0.0002900000 0.0308820000 28447612 96830484 1770098688 3.8610947132 3.9809417725 4.0220623016 1007 1311867752.2150039673 0.1723402441 0.1376442641 0.2374686003 0.0048090002 0.1166530000 0.0125800000 0.0430880000 0.0002150000 0.0001870000 0.0380660000 28449798 96830484 1769091072 3.8609178066 3.9813935757 4.0216388702 1008 1311867752.2512340546 0.1708198339 0.1376771763 0.2374686003 0.0048087399 0.1144150000 0.0120130000 0.0442410000 0.0000290000 0.0003200000 0.0310140000 28452016 96830484 1766170624 3.8621048927 3.9823293686 4.0212330818 1009 1311867752.2833271027 0.1714368612 0.1377106349 0.2374686003 0.0048072851 0.1709720000 0.0105650000 0.0832590000 0.0003870000 0.0002720000 0.0574280000 28454202 96830484 1766678528 3.8612923622 3.9822583199 4.0214624405 1010 1311867752.3150799274 0.1685734242 0.1377411921 0.2374686003 0.0048095933 0.1169950000 0.0094690000 0.0556610000 0.0000330000 0.0002940000 0.0309480000 28456356 96830484 1768321024 3.8637294769 3.9813654423 4.0208964348 1011 1311867752.3509979248 0.1683900952 0.1377715075 0.2374686003 0.0048099445 0.1141850000 0.0109940000 0.0377790000 0.0002940000 0.0003450000 0.0391720000 28458606 96830484 1769971712 3.8640730381 3.9815151691 4.0210013390 1012 1311867752.3829851151 0.1690181494 0.1378023837 0.2374686003 0.0048077271 0.1146000000 0.0128480000 0.0374290000 0.0000320000 0.0003870000 0.0309750000 28460824 96830484 1768357888 3.8633244038 3.9807558060 4.0208878517 1013 1311867752.4160280228 0.1672157794 0.1378314196 0.2374686003 0.0048058591 0.1528920000 0.0102420000 0.0493850000 0.0002930000 0.0074750000 0.0536000000 28463010 96830484 1767821312 3.8649489880 3.9811246395 4.0203161240 1014 1311867752.4510710239 0.1680811495 0.1378612517 0.2374686003 0.0048092966 0.1138880000 0.0100830000 0.0430280000 0.0000280000 0.0002920000 0.0310360000 28465260 96830484 1769574400 3.8636834621 3.9814326763 4.0203061104 1015 1311867752.4829080105 0.1670377403 0.1378899970 0.2374686003 0.0048078383 0.1184360000 0.0129570000 0.0430250000 0.0002950000 0.0003500000 0.0413310000 28467446 96830484 1768472576 3.8648767471 3.9802649021 4.0198020935 1016 1311867752.5181159973 0.1669885516 0.1379186373 0.2374686003 0.0048082249 0.0951770000 0.0102100000 0.0367400000 0.0000300000 0.0003590000 0.0292190000 28469664 96830484 1770098688 3.8645577431 3.9799759388 4.0193738937 1017 1311867752.5511059761 0.1660025865 0.1379462518 0.2374686003 0.0048075668 0.1337820000 0.0123620000 0.0453640000 0.0003230000 0.0002730000 0.0560880000 28471850 96830484 1768964096 3.8656356335 3.9807155132 4.0188198090 1018 1311867752.5830090046 0.1654827744 0.1379733014 0.2374686003 0.0048054231 0.0979450000 0.0100720000 0.0376700000 0.0000270000 0.0002940000 0.0311370000 28474068 96830484 1770627072 3.8659386635 3.9809179306 4.0186161995 1019 1311867752.6167891026 0.1656269729 0.1380004395 0.2374686003 0.0048032354 0.1527930000 0.0120540000 0.0723560000 0.0003510000 0.0002750000 0.0367280000 28476254 96830484 1769500672 3.8658213615 3.9803488255 4.0181260109 1020 1311867752.6514921188 0.1662124991 0.1380280984 0.2374686003 0.0048023094 0.1141340000 0.0116570000 0.0372060000 0.0000280000 0.0002900000 0.0302490000 28478472 96830484 1768706048 3.8653011322 3.9808852673 4.0180835724 1021 1311867752.6830079556 0.1648552120 0.1380543737 0.2374686003 0.0048027450 0.1284640000 0.0100470000 0.0427060000 0.0006900000 0.0002820000 0.0559760000 28480658 96830484 1770463232 3.8667080402 3.9803609848 4.0175423622 1022 1311867752.7152869701 0.1640843898 0.1380798434 0.2374686003 0.0048038966 0.1017100000 0.0115640000 0.0315380000 0.0000550000 0.0001930000 0.0320900000 28482876 96830484 1769361408 3.8676164150 3.9796867371 4.0171837807 1023 1311867752.7510609627 0.1644460112 0.1381056167 0.2374686003 0.0048015518 0.1527230000 0.0118150000 0.0686170000 0.0003040000 0.0002820000 0.0370820000 28485062 96830484 1768325120 3.8671636581 3.9790058136 4.0166916847 1024 1311867752.7830440998 0.1644689739 0.1381313622 0.2374686003 0.0048105513 0.1142610000 0.0103190000 0.0448440000 0.0000310000 0.0003110000 0.0305320000 28487280 96830484 1769955328 3.8671309948 3.9801425934 4.0163202286 1025 1311867752.8162839413 0.1620843410 0.1381547310 0.2374686003 0.0048086731 0.1324700000 0.0128380000 0.0429680000 0.0002980000 0.0003010000 0.0562850000 28571386 96830484 1768984576 3.8694932461 3.9807519913 4.0154528618 1026 1311867752.8511059284 0.1612414271 0.1381772326 0.2374686003 0.0048064955 0.1198110000 0.0096310000 0.0559380000 0.0000290000 0.0003720000 0.0305780000 28741540 96830484 1770733568 3.8704388142 3.9808144569 4.0149111748 1027 1311867752.8833000660 0.1619555503 0.1382003858 0.2374686003 0.0048044186 0.1327500000 0.0128510000 0.0525210000 0.0003880000 0.0002820000 0.0413110000 28743758 96830484 1769725952 3.8696289062 3.9809393883 4.0148453712 1028 1311867752.9183809757 0.1602642983 0.1382218488 0.2374686003 0.0048022392 0.1354290000 0.0119740000 0.0720660000 0.0000280000 0.0003570000 0.0298780000 28746008 96830484 1768583168 3.8717467785 3.9815287590 4.0143632889 1029 1311867752.9511129856 0.1597546041 0.1382427747 0.2374686003 0.0048061799 0.1365380000 0.0098690000 0.0531900000 0.0002920000 0.0003430000 0.0538450000 28748162 96830484 1770242048 3.8721606731 3.9810423851 4.0141215324 1030 1311867752.9828579426 0.1601608247 0.1382640543 0.2374686003 0.0048040277 0.1161900000 0.0114310000 0.0497910000 0.0000280000 0.0003110000 0.0301730000 28750380 96830484 1769345024 3.8716905117 3.9808065891 4.0138473511 1031 1311867753.0168170929 0.1577882767 0.1382829915 0.2374686003 0.0048019263 0.1153820000 0.0119550000 0.0496580000 0.0003760000 0.0002840000 0.0336850000 28752566 96830484 1768198144 3.8743126392 3.9809992313 4.0133805275 1032 1311867753.0510199070 0.1594000012 0.1383034537 0.2374686003 0.0047997991 0.1107930000 0.0097970000 0.0381970000 0.0000270000 0.0002870000 0.0312630000 28754784 96830484 1769955328 3.8726346493 3.9804351330 4.0131373405 1033 1311867753.0829060078 0.1596449912 0.1383241135 0.2374686003 0.0047984032 0.1377140000 0.0127190000 0.0486220000 0.0002970000 0.0003460000 0.0562560000 28756938 96830484 1768853504 3.8721549511 3.9804966450 4.0125722885 1034 1311867753.1184310913 0.1582304835 0.1383433653 0.2374686003 0.0047962005 0.1342440000 0.0097650000 0.0728070000 0.0000310000 0.0003070000 0.0300700000 28759220 96830484 1770463232 3.8735396862 3.9818720818 4.0120887756 1035 1311867753.1510760784 0.1571799815 0.1383615649 0.2374686003 0.0047940671 0.1368950000 0.0127690000 0.0657070000 0.0003070000 0.0002800000 0.0365820000 28761374 96830484 1769361408 3.8745672703 3.9806256294 4.0119094849 1036 1311867753.1830070019 0.1575047672 0.1383800429 0.2374686003 0.0047920678 0.1143480000 0.0119740000 0.0446640000 0.0000310000 0.0003160000 0.0301510000 28763528 96830484 1766825984 3.8738265038 3.9796614647 4.0115404129 1037 1311867753.2186999321 0.1561145484 0.1383971446 0.2374686003 0.0047921690 0.1706860000 0.0104100000 0.0692150000 0.0000600000 0.0000550000 0.0599840000 28765810 96830484 1767055360 3.8751311302 3.9817984104 4.0113849640 1038 1311867753.2520470619 0.1556583941 0.1384137740 0.2374686003 0.0047899166 0.0971530000 0.0103520000 0.0368180000 0.0000300000 0.0003090000 0.0301260000 28767964 96830484 1768722432 3.8753924370 3.9819564819 4.0112543106 1039 1311867753.2829909325 0.1543645710 0.1384291261 0.2374686003 0.0047882749 0.1137830000 0.0099080000 0.0417010000 0.0003130000 0.0003480000 0.0365290000 28770150 96830484 1770352640 3.8761212826 3.9816668034 4.0108952522 1040 1311867753.3196740150 0.1500132084 0.1384402646 0.2374686003 0.0047904192 0.1181650000 0.0123180000 0.0541770000 0.0000300000 0.0002930000 0.0319750000 28772432 96830484 1769361408 3.8798227310 3.9828655720 4.0101113319 1041 1311867753.3509368896 0.1487502456 0.1384501685 0.2374686003 0.0047884036 0.1547000000 0.0100640000 0.0719370000 0.0003000000 0.0002750000 0.0530110000 28774554 96830484 1771008000 3.8808624744 3.9833323956 4.0099892616 1042 1311867753.3829340935 0.1501016915 0.1384613504 0.2374686003 0.0047878939 0.1144730000 0.0114730000 0.0425510000 0.0000280000 0.0003880000 0.0300020000 28776772 96830484 1769742336 3.8791313171 3.9813480377 4.0102472305 1043 1311867753.4182109833 0.1513576210 0.1384737150 0.2374686003 0.0047862092 0.1545500000 0.0128930000 0.0774620000 0.0003700000 0.0002810000 0.0365110000 28779022 96830484 1767956480 3.8773112297 3.9822306633 4.0098609924 1044 1311867753.4511721134 0.1500549465 0.1384848081 0.2374686003 0.0047841749 0.1159930000 0.0103960000 0.0546500000 0.0000280000 0.0003060000 0.0294520000 28781176 96830484 1769742336 3.8780665398 3.9828205109 4.0093493462 1045 1311867753.4831509590 0.1485280097 0.1384944188 0.2374686003 0.0047826431 0.1529130000 0.0126820000 0.0499970000 0.0002960000 0.0003490000 0.0583580000 28783394 96830484 1768599552 3.8788719177 3.9822020531 4.0085420609 1046 1311867753.5199849606 0.1476147473 0.1385031381 0.2374686003 0.0047804823 0.1343160000 0.0101870000 0.0715560000 0.0000310000 0.0002990000 0.0301140000 28785676 96830484 1770233856 3.8789644241 3.9829349518 4.0078434944 1047 1311867753.5532789230 0.1468434185 0.1385111040 0.2374686003 0.0047782890 0.1534560000 0.0123670000 0.0738930000 0.0003010000 0.0005270000 0.0356910000 28787862 96830484 1769242624 3.8790073395 3.9825475216 4.0075230598 1048 1311867753.5832290649 0.1449971348 0.1385172929 0.2374686003 0.0047764561 0.1154070000 0.0119150000 0.0428390000 0.0000310000 0.0003110000 0.0299080000 28790016 96830484 1768112128 3.8801760674 3.9825243950 4.0069189072 1049 1311867753.6183180809 0.1436555684 0.1385221912 0.2374686003 0.0047745099 0.1530540000 0.0108050000 0.0547470000 0.0003150000 0.0003470000 0.0576950000 28792266 96830484 1769873408 3.8805830479 3.9833710194 4.0064158440 1050 1311867753.6509299278 0.1439348161 0.1385273461 0.2374686003 0.0047725738 0.1339720000 0.0130100000 0.0558530000 0.0000300000 0.0003150000 0.0295270000 28794452 96830484 1768734720 3.8796870708 3.9825665951 4.0063190460 1051 1311867753.6830120087 0.1419223249 0.1385305763 0.2374686003 0.0047721645 0.1152290000 0.0100690000 0.0429140000 0.0003120000 0.0003500000 0.0357130000 28796606 96830484 1770487808 3.8811616898 3.9824187756 4.0056786537 1052 1311867753.7204821110 0.1403804868 0.1385323348 0.2374686003 0.0047700920 0.1155160000 0.0124310000 0.0442050000 0.0000300000 0.0003150000 0.0298270000 28798920 96830484 1769603072 3.8821833134 3.9833676815 4.0054464340 1053 1311867753.7510209084 0.1403013766 0.1385340148 0.2374686003 0.0047685217 0.1656830000 0.0116430000 0.0786620000 0.0003830000 0.0002790000 0.0549680000 28801042 96830484 1768861696 3.8814427853 3.9830420017 4.0054316521 1054 1311867753.7865459919 0.1384415329 0.1385339270 0.2374686003 0.0047680544 0.1426840000 0.0097990000 0.0720700000 0.0000280000 0.0003820000 0.0292010000 28803292 96830484 1770614784 3.8823373318 3.9822559357 4.0050420761 1055 1311867753.8151860237 0.1359204352 0.1385314498 0.2374686003 0.0047666979 0.1376040000 0.0122380000 0.0660110000 0.0005440000 0.0008030000 0.0349710000 28805414 96830484 1769603072 3.8847777843 3.9839365482 4.0048880577 1056 1311867753.8510670662 0.1354445666 0.1385285266 0.2374686003 0.0047659598 0.1151950000 0.0123890000 0.0495920000 0.0000310000 0.0003850000 0.0291580000 28807664 96830484 1767583744 3.8842742443 3.9839076996 4.0048246384 1057 1311867753.8831698895 0.1341405213 0.1385243752 0.2374686003 0.0047746917 0.1535060000 0.0104520000 0.0721440000 0.0003700000 0.0002800000 0.0507140000 28809882 96830484 1769259008 3.8849461079 3.9819595814 4.0045866966 1058 1311867753.9155960083 0.1326068491 0.1385187821 0.2374686003 0.0047731568 0.1165850000 0.0111860000 0.0559380000 0.0000270000 0.0003730000 0.0292390000 28812036 96830484 1768206336 3.8857660294 3.9827072620 4.0042901039 1059 1311867753.9511620998 0.1314418614 0.1385120995 0.2374686003 0.0047741095 0.1275230000 0.0103470000 0.0484910000 0.0003060000 0.0003690000 0.0359100000 28814286 96830484 1769873408 3.8862855434 3.9842667580 4.0045504570 1060 1311867753.9859020710 0.1314096600 0.1385053990 0.2374686003 0.0047739374 0.1369510000 0.0126820000 0.0637070000 0.0000310000 0.0003740000 0.0331120000 28816536 96830484 1768587264 3.8855624199 3.9829115868 4.0046291351 1061 1311867754.0151760578 0.1310095191 0.1384983341 0.2374686003 0.0047724192 0.1612370000 0.0108230000 0.0752210000 0.0003060000 0.0003520000 0.0549210000 28818658 96830484 1770274816 3.8847393990 3.9816529751 4.0047893524 1062 1311867754.0510439873 0.1272493452 0.1384877419 0.2374686003 0.0047787994 0.1466880000 0.0112200000 0.0715910000 0.0000310000 0.0002920000 0.0298870000 28820940 96830484 1769242624 3.8878319263 3.9833500385 4.0047965050 1063 1311867754.0839149952 0.1252632737 0.1384753012 0.2374686003 0.0047774244 0.1160340000 0.0115370000 0.0423770000 0.0003490000 0.0002690000 0.0354350000 28823126 96830484 1768333312 3.8891365528 3.9831590652 4.0045819283 1064 1311867754.1166028976 0.1236255094 0.1384613446 0.2374686003 0.0047759765 0.1350390000 0.0101480000 0.0706420000 0.0000290000 0.0002870000 0.0305660000 28825312 96830484 1770106880 3.8899290562 3.9824192524 4.0048933029 1065 1311867754.1511039734 0.1215795204 0.1384454931 0.2374686003 0.0047764585 0.1902250000 0.0121520000 0.0714900000 0.0003660000 0.0002770000 0.0638600000 28827498 96830484 1769353216 3.8911755085 3.9829287529 4.0046458244 1066 1311867754.1832261086 0.1205661148 0.1384287207 0.2374686003 0.0047745088 0.1320200000 0.0119110000 0.0550850000 0.0000280000 0.0003010000 0.0390670000 28829716 96830484 1768206336 3.8914878368 3.9838886261 4.0051889420 1067 1311867754.2166349888 0.1192197204 0.1384107179 0.2374686003 0.0047744701 0.1132460000 0.0099900000 0.0431540000 0.0003800000 0.0002790000 0.0367240000 28831902 96830484 1769963520 3.8914330006 3.9830763340 4.0049204826 1068 1311867754.2522869110 0.1183405295 0.1383919256 0.2374686003 0.0047789509 0.1370290000 0.0127020000 0.0712030000 0.0000300000 0.0003730000 0.0296470000 28834152 96830484 1768972288 3.8911278248 3.9825282097 4.0050506592 1069 1311867754.2873370647 0.1143117324 0.1383693997 0.2374686003 0.0047844250 0.1713420000 0.0105460000 0.0717030000 0.0003170000 0.0003620000 0.0574900000 28836402 96830484 1770725376 3.8939301968 3.9833087921 4.0049037933 1070 1311867754.3188319206 0.1166872382 0.1383491360 0.2374686003 0.0047825104 0.1161880000 0.0123120000 0.0424920000 0.0000290000 0.0003000000 0.0292180000 28838588 96830484 1769607168 3.8903799057 3.9826192856 4.0054564476 1071 1311867754.3511719704 0.1158168465 0.1383280974 0.2374686003 0.0047844374 0.1185080000 0.0116330000 0.0522490000 0.0003060000 0.0003520000 0.0338410000 28840774 96830484 1768607744 3.8903069496 3.9826087952 4.0055775642 1072 1311867754.3868899345 0.1139766723 0.1383053815 0.2374686003 0.0047852719 0.1117670000 0.0095520000 0.0484240000 0.0000280000 0.0003710000 0.0295030000 28842992 96830484 1770233856 3.8909821510 3.9832458496 4.0052418709 1073 1311867754.4159760475 0.1135781035 0.1382823365 0.2374686003 0.0047831824 0.1290870000 0.0126100000 0.0418760000 0.0003180000 0.0003540000 0.0538250000 28845178 96830484 1769000960 3.8908488750 3.9831395149 4.0052309036 1074 1311867754.4545960426 0.1106001586 0.1382565617 0.2374686003 0.0047976901 0.1405790000 0.0105590000 0.0706160000 0.0000310000 0.0002980000 0.0295520000 28847428 96830484 1767862272 3.8927803040 3.9821357727 4.0054993629 1075 1311867754.4863700867 0.1090562567 0.1382293986 0.2374686003 0.0048050599 0.1168410000 0.0100320000 0.0529270000 0.0003570000 0.0002770000 0.0335970000 28849614 96830484 1769472000 3.8938541412 3.9823470116 4.0056099892 1076 1311867754.5164580345 0.1083789989 0.1382016566 0.2374686003 0.0048034553 0.1146280000 0.0119380000 0.0426550000 0.0000290000 0.0005410000 0.0292840000 28851768 96830484 1765408768 3.8940401077 3.9829449654 4.0058560371 1077 1311867754.5513699055 0.1076667160 0.1381733048 0.2374686003 0.0048029719 0.1537460000 0.0109290000 0.0707420000 0.0002930000 0.0003550000 0.0512440000 28853954 96830484 1767104512 3.8942704201 3.9832558632 4.0061268806 1078 1311867754.5835940838 0.1048765704 0.1381424173 0.2374686003 0.0048044746 0.1327070000 0.0096320000 0.0650190000 0.0000290000 0.0002980000 0.0288990000 28856172 96830484 1768820736 3.8965752125 3.9818406105 4.0058126450 1079 1311867754.6154909134 0.1051779166 0.1381118663 0.2374686003 0.0048036884 0.1362750000 0.0102850000 0.0623460000 0.0003140000 0.0002840000 0.0351530000 28858326 96830484 1770471424 3.8957710266 3.9821321964 4.0061812401 1080 1311867754.6510920525 0.1045591682 0.1380807990 0.2374686003 0.0048017652 0.1371290000 0.0124740000 0.0691290000 0.0000290000 0.0002920000 0.0291590000 28860544 96830484 1769127936 3.8959295750 3.9826333523 4.0063276291 1081 1311867754.6872758865 0.1027760208 0.1380481396 0.2374686003 0.0048025075 0.1276970000 0.0112890000 0.0424870000 0.0002920000 0.0002820000 0.0530700000 28862794 96830484 1768079360 3.8971221447 3.9814980030 4.0062832832 1082 1311867754.7162959576 0.1028077751 0.1380155700 0.2374686003 0.0048003521 0.1007630000 0.0093660000 0.0353050000 0.0000280000 0.0002920000 0.0301740000 28864916 96830484 1769709568 3.8966152668 3.9821059704 4.0065312386 1083 1311867754.7516000271 0.1022384837 0.1379825348 0.2374686003 0.0048001935 0.1380390000 0.0120350000 0.0699560000 0.0002920000 0.0002740000 0.0350200000 28867166 96830484 1768464384 3.8967084885 3.9836025238 4.0069661140 1084 1311867754.7865269184 0.1004324630 0.1379478945 0.2374686003 0.0048006521 0.1125640000 0.0102830000 0.0482880000 0.0000320000 0.0003040000 0.0282870000 28869384 96830484 1769971712 3.8979640007 3.9832544327 4.0068659782 1085 1311867754.8154470921 0.1010640711 0.1379139002 0.2374686003 0.0047999374 0.1554180000 0.0128960000 0.0704470000 0.0006320000 0.0003640000 0.0508830000 28871506 96830484 1768738816 3.8968167305 3.9812462330 4.0070409775 1086 1311867754.8510210514 0.1004873812 0.1378794375 0.2374686003 0.0048138747 0.1355310000 0.0095440000 0.0709070000 0.0000280000 0.0002890000 0.0287780000 28873756 96830484 1770500096 3.8965818882 3.9819982052 4.0074810982 1087 1311867754.8877389431 0.0976363942 0.1378424154 0.2374686003 0.0048136224 0.1158540000 0.0123090000 0.0422660000 0.0003170000 0.0003560000 0.0348650000 28876038 96830484 1769598976 3.8986244202 3.9817597866 4.0071125031 1088 1311867754.9201259613 0.0956702456 0.1378036542 0.2374686003 0.0048124026 0.1345240000 0.0122360000 0.0714990000 0.0000260000 0.0002910000 0.0293130000 28878224 96830484 1768329216 3.8998353481 3.9802556038 4.0069947243 1089 1311867754.9510319233 0.0950108096 0.1377643586 0.2374686003 0.0048116522 0.1520630000 0.0099790000 0.0557690000 0.0003160000 0.0002750000 0.0553300000 28880378 96830484 1769971712 3.8996694088 3.9805088043 4.0068845749 1090 1311867754.9837870598 0.0937504396 0.1377239789 0.2374686003 0.0048108036 0.1386170000 0.0124480000 0.0753920000 0.0000300000 0.0002990000 0.0302100000 28882596 96830484 1768964096 3.8997371197 3.9816527367 4.0074791908 1091 1311867755.0183880329 0.0929137841 0.1376829063 0.2374686003 0.0048125601 0.1275550000 0.0100160000 0.0537280000 0.0003840000 0.0002920000 0.0341720000 28884814 96830484 1770590208 3.9000303745 3.9797747135 4.0077514648 1092 1311867755.0540831089 0.0937206224 0.1376426478 0.2374686003 0.0048133698 0.1546410000 0.0123330000 0.0800900000 0.0000270000 0.0002950000 0.0275770000 28887064 96830484 1769472000 3.8987865448 3.9788336754 4.0083913803 1093 1311867755.0850980282 0.0941722915 0.1376028762 0.2374686003 0.0048135329 0.1693550000 0.0118920000 0.0850780000 0.0000590000 0.0000540000 0.0518610000 28889250 96830484 1768472576 3.8979027271 3.9791371822 4.0088882446 1094 1311867755.1156959534 0.0938856974 0.1375629153 0.2374686003 0.0048151864 0.1388130000 0.0095090000 0.0718050000 0.0000280000 0.0003100000 0.0279270000 28891372 96830484 1770082304 3.8976559639 3.9789538383 4.0090742111 1095 1311867755.1556220055 0.0929468945 0.1375221701 0.2374686003 0.0048134289 0.1194180000 0.0125260000 0.0546920000 0.0002890000 0.0002720000 0.0314010000 28893686 96830484 1768726528 3.8979754448 3.9787094593 4.0092806816 1096 1311867755.1847031116 0.0935999602 0.1374820951 0.2374686003 0.0048118471 0.1325070000 0.0097710000 0.0724720000 0.0000290000 0.0002930000 0.0278530000 28895872 96830484 1770483712 3.8968529701 3.9775309563 4.0095500946 1097 1311867755.2151238918 0.0919750705 0.1374406119 0.2374686003 0.0048096939 0.1546740000 0.0123830000 0.0713170000 0.0003710000 0.0002800000 0.0499670000 28897994 96830484 1769119744 3.8979196548 3.9792890549 4.0095400810 1098 1311867755.2512340546 0.0920610055 0.1373992826 0.2374686003 0.0048089424 0.1356560000 0.0111640000 0.0718200000 0.0000300000 0.0003580000 0.0274000000 28900244 96830484 1767727104 3.8973305225 3.9778566360 4.0099081993 1099 1311867755.2832889557 0.0916545838 0.1373576587 0.2374686003 0.0048090179 0.1507840000 0.0099380000 0.0720150000 0.0003840000 0.0002950000 0.0341510000 28902430 96830484 1769320448 3.8972189426 3.9769401550 4.0095677376 1100 1311867755.3192110062 0.0904847309 0.1373150469 0.2374686003 0.0048074349 0.1368260000 0.0124970000 0.0718890000 0.0000270000 0.0003070000 0.0279340000 28904680 96830484 1767964672 3.8979756832 3.9783964157 4.0092310905 1101 1311867755.3553090096 0.0913703442 0.1372733170 0.2374686003 0.0048052674 0.1521310000 0.0100070000 0.0705010000 0.0002880000 0.0003440000 0.0508230000 28906962 96830484 1769701376 3.8967809677 3.9765260220 4.0091438293 1102 1311867755.3900220394 0.0929164514 0.1372330657 0.2374686003 0.0048033883 0.1195240000 0.0113460000 0.0600000000 0.0000290000 0.0006650000 0.0271840000 28909148 96830484 1768337408 3.8948295116 3.9745135307 4.0089097023 1103 1311867755.4156589508 0.0924325883 0.1371924488 0.2374686003 0.0048041193 0.1344940000 0.0102020000 0.0719400000 0.0003510000 0.0002750000 0.0315750000 28911270 96830484 1769955328 3.8947470188 3.9770777225 4.0085806847 1104 1311867755.4549160004 0.0920857489 0.1371515913 0.2374686003 0.0048026939 0.1347480000 0.0120920000 0.0718660000 0.0000290000 0.0002890000 0.0283020000 28913552 96830484 1768591360 3.8944454193 3.9781517982 4.0087633133 1105 1311867755.4860870838 0.0918814167 0.1371106228 0.2374686003 0.0048018837 0.1527970000 0.0099590000 0.0706520000 0.0003780000 0.0002880000 0.0512080000 28915706 96830484 1770336256 3.8943076134 3.9754116535 4.0085983276 1106 1311867755.5161950588 0.0939296633 0.1370715803 0.2374686003 0.0048041000 0.1372610000 0.0117410000 0.0708400000 0.0000290000 0.0003560000 0.0283050000 28917828 96830484 1768992768 3.8919949532 3.9767541885 4.0091300011 1107 1311867755.5550999641 0.0936083421 0.1370323181 0.2374686003 0.0048020592 0.1348640000 0.0118440000 0.0653660000 0.0004940000 0.0002850000 0.0344120000 28920142 96830484 1767600128 3.8919606209 3.9779317379 4.0092577934 1108 1311867755.5854589939 0.0934218913 0.1369929585 0.2374686003 0.0048002015 0.1097060000 0.0098960000 0.0363260000 0.0000290000 0.0002870000 0.0287210000 28922328 96830484 1769209856 3.8919162750 3.9778828621 4.0089840889 1109 1311867755.6171119213 0.0922489986 0.1369526123 0.2374686003 0.0047984600 0.1497840000 0.0125570000 0.0474940000 0.0003590000 0.0002840000 0.0684040000 28924482 96830484 1767837696 3.8928439617 3.9782354832 4.0087895393 1110 1311867755.6542940140 0.0917173177 0.1369118598 0.2374686003 0.0047963686 0.1402160000 0.0093060000 0.0727790000 0.0000080000 0.0000630000 0.0258200000 28926764 96830484 1769574400 3.8932626247 3.9783353806 4.0087952614 1111 1311867755.6831719875 0.0933124423 0.1368726164 0.2374686003 0.0047948482 0.1385020000 0.0121420000 0.0705920000 0.0002930000 0.0002740000 0.0340070000 28928886 96830484 1768337408 3.8915262222 3.9766759872 4.0086579323 1112 1311867755.7182741165 0.0920880064 0.1368323425 0.2374686003 0.0047931042 0.1327530000 0.0098850000 0.0707020000 0.0000250000 0.0002840000 0.0285230000 28931136 96830484 1769975808 3.8923163414 3.9763746262 4.0080461502 1113 1311867755.7511448860 0.0931170806 0.1367930655 0.2374686003 0.0047929954 0.1735550000 0.0120510000 0.0712350000 0.0002960000 0.0002720000 0.0573080000 28933322 96830484 1768611840 3.8908865452 3.9769723415 4.0077824593 1114 1311867755.7863750458 0.0941178054 0.1367547574 0.2374686003 0.0047911162 0.1125590000 0.0099840000 0.0404670000 0.0000200000 0.0001950000 0.0289780000 28935540 96830484 1770209280 3.8896691799 3.9773678780 4.0078344345 1115 1311867755.8156878948 0.0904372558 0.1367132170 0.2374686003 0.0047934852 0.1559210000 0.0124030000 0.0782440000 0.0003220000 0.0002810000 0.0346550000 28937726 96830484 1768853504 3.8931636810 3.9760313034 4.0067291260 1116 1311867755.8554079533 0.0889782757 0.1366704438 0.2374686003 0.0047926047 0.1341630000 0.0101980000 0.0700410000 0.0000290000 0.0003610000 0.0290510000 28939976 96830484 1770590208 3.8942706585 3.9785053730 4.0067105293 1117 1311867755.8848359585 0.0901946202 0.1366288361 0.2374686003 0.0047906826 0.1299150000 0.0126420000 0.0423640000 0.0004010000 0.0002860000 0.0535490000 28942162 96830484 1769246720 3.8927700520 3.9784226418 4.0069632530 1118 1311867755.9156229496 0.0890892670 0.1365863141 0.2374686003 0.0047922324 0.1180530000 0.0108070000 0.0424830000 0.0000290000 0.0003130000 0.0291570000 28944348 96830484 1767837696 3.8937056065 3.9759213924 4.0065279007 1119 1311867755.9550359249 0.0885519460 0.1365433879 0.2374686003 0.0047923828 0.1535060000 0.0098170000 0.0776010000 0.0003530000 0.0002730000 0.0346050000 28946598 96830484 1769447424 3.8938150406 3.9780216217 4.0066890717 1120 1311867755.9855198860 0.0896384045 0.1365015085 0.2374686003 0.0047907229 0.1549630000 0.0120720000 0.0790250000 0.0000290000 0.0003530000 0.0297250000 28948752 96830484 1768091648 3.8926360607 3.9780073166 4.0069594383 1121 1311867756.0173881054 0.0896466598 0.1364597111 0.2374686003 0.0047890297 0.1556080000 0.0104220000 0.0685560000 0.0003610000 0.0002780000 0.0555010000 28950906 96830484 1769828352 3.8924942017 3.9770443439 4.0068888664 1122 1311867756.0554430485 0.0870608017 0.1364156836 0.2374686003 0.0047874226 0.1359310000 0.0115000000 0.0704590000 0.0000280000 0.0002890000 0.0287760000 28953156 96830484 1768464384 3.8948488235 3.9787366390 4.0067420006 1123 1311867756.0835959911 0.0881079063 0.1363726668 0.2374686003 0.0047859124 0.1143020000 0.0100170000 0.0481340000 0.0003160000 0.0003560000 0.0350660000 28955310 96830484 1770098688 3.8937370777 3.9781613350 4.0068802834 1124 1311867756.1196908951 0.0903076604 0.1363316837 0.2374686003 0.0047863093 0.1148910000 0.0130940000 0.0438620000 0.0000310000 0.0003940000 0.0286490000 28957560 96830484 1767940096 3.8918108940 3.9753148556 4.0070834160 1125 1311867756.1519339085 0.0880244002 0.1362887439 0.2374686003 0.0047850297 0.1700820000 0.0101980000 0.0692490000 0.0000620000 0.0000560000 0.0563850000 28959650 96830484 1767456768 3.8938415051 3.9772114754 4.0066652298 1126 1311867756.1836869717 0.0896707326 0.1362473425 0.2374686003 0.0047853112 0.1356810000 0.0098890000 0.0702920000 0.0000280000 0.0002890000 0.0286990000 28961772 96830484 1769082880 3.8921935558 3.9781007767 4.0072908401 1127 1311867756.2230648994 0.0902108252 0.1362064938 0.2374686003 0.0047898514 0.1364780000 0.0117000000 0.0645510000 0.0003310000 0.0002820000 0.0352030000 28963958 96830484 1768218624 3.8919479847 3.9757237434 4.0073003769 1128 1311867756.2552509308 0.0895311162 0.1361651149 0.2374686003 0.0047904096 0.1130560000 0.0106110000 0.0496330000 0.0000290000 0.0006200000 0.0287660000 28966144 96830484 1769828352 3.8925957680 3.9760580063 4.0073437691 1129 1311867756.2851591110 0.0895834789 0.1361238557 0.2374686003 0.0047890198 0.1280820000 0.0126840000 0.0407920000 0.0001000000 0.0000890000 0.0535860000 28968330 96830484 1768464384 3.8926138878 3.9777903557 4.0075721741 1130 1311867756.3200058937 0.0905238613 0.1360835017 0.2374686003 0.0047871478 0.1206800000 0.0093230000 0.0547260000 0.0000280000 0.0003150000 0.0286140000 28970548 96830484 1770098688 3.8918809891 3.9765107632 4.0077385902 1131 1311867756.3546419144 0.0890823975 0.1360419446 0.2374686003 0.0047860874 0.1547620000 0.0123290000 0.0769260000 0.0003800000 0.0002780000 0.0345100000 28972798 96830484 1768865792 3.8934371471 3.9762227535 4.0074310303 1132 1311867756.3843090534 0.0900582075 0.1360013229 0.2374686003 0.0047857069 0.1129190000 0.0097870000 0.0417090000 0.0000920000 0.0002880000 0.0282150000 28974920 96830484 1770479616 3.8923933506 3.9773044586 4.0078496933 1133 1311867756.4231688976 0.0896543413 0.1359604165 0.2374686003 0.0047841008 0.2013510000 0.0123390000 0.0955850000 0.0000680000 0.0000570000 0.0695710000 28977170 96830484 1769246720 3.8929810524 3.9772293568 4.0079474449 1134 1311867756.4510979652 0.0908895954 0.1359206715 0.2374686003 0.0047824960 0.1517180000 0.0141890000 0.0777480000 0.0000280000 0.0003050000 0.0360050000 28979260 96830484 1767837696 3.8919112682 3.9753100872 4.0080871582 1135 1311867756.4865350723 0.0903797597 0.1358805473 0.2374686003 0.0047871534 0.1518560000 0.0103530000 0.0767130000 0.0002900000 0.0002720000 0.0367540000 28981542 96830484 1769447424 3.8924117088 3.9767866135 4.0084862709 1136 1311867756.5264549255 0.0899021626 0.1358400734 0.2374686003 0.0047855448 0.1366390000 0.0121250000 0.0703000000 0.0000280000 0.0003580000 0.0281490000 28983824 96830484 1768091648 3.8931169510 3.9762060642 4.0084900856 1137 1311867756.5525779724 0.0904448107 0.1358001479 0.2374686003 0.0047839684 0.1533170000 0.0099210000 0.0704230000 0.0003550000 0.0002770000 0.0518120000 28985946 96830484 1769844736 3.8927528858 3.9756288528 4.0087542534 1138 1311867756.5897810459 0.0892052725 0.1357592034 0.2374686003 0.0047823328 0.1169990000 0.0113160000 0.0477160000 0.0000290000 0.0003160000 0.0288530000 28988228 96830484 1768837120 3.8940393925 3.9762747288 4.0086283684 1139 1311867756.6202929020 0.0913223997 0.1357201895 0.2374686003 0.0047810355 0.1141080000 0.0101550000 0.0411520000 0.0004470000 0.0002760000 0.0342300000 28990350 96830484 1770463232 3.8922464848 3.9744112492 4.0092010498 1140 1311867756.6518390179 0.0914895386 0.1356813907 0.2374686003 0.0047789872 0.1154200000 0.0126540000 0.0392440000 0.0000310000 0.0002930000 0.0282730000 28992536 96830484 1767813120 3.8922009468 3.9737098217 4.0095510483 1141 1311867756.6839349270 0.0900469720 0.1356413956 0.2374686003 0.0047780832 0.1518350000 0.0100040000 0.0556300000 0.0004950000 0.0002940000 0.0516680000 28994690 96830484 1763770368 3.8933622837 3.9746301174 4.0094046593 1142 1311867756.7217059135 0.0904151499 0.1356017929 0.2374686003 0.0047786070 0.1313280000 0.0108340000 0.0696580000 0.0000300000 0.0002840000 0.0283410000 28996940 96830484 1765564416 3.8930079937 3.9739484787 4.0097618103 1143 1311867756.7516939640 0.0902455375 0.1355621112 0.2374686003 0.0047770368 0.1143020000 0.0099470000 0.0492390000 0.0002980000 0.0003500000 0.0335350000 28999094 96830484 1767190528 3.8930969238 3.9735395908 4.0097613335 1144 1311867756.7872660160 0.0914891660 0.1355235859 0.2374686003 0.0047755368 0.1340910000 0.0102780000 0.0721540000 0.0003800000 0.0003160000 0.0279000000 29001344 96830484 1768558592 3.8918933868 3.9735965729 4.0101504326 1145 1311867756.8227219582 0.0902759656 0.1354840683 0.2374686003 0.0047736205 0.1531620000 0.0100210000 0.0540300000 0.0003530000 0.0002690000 0.0552670000 29003594 96830484 1770209280 3.8930358887 3.9734802246 4.0102114677 1146 1311867756.8542120457 0.0906962901 0.1354449865 0.2374686003 0.0047801509 0.1140220000 0.0127530000 0.0358300000 0.0000290000 0.0003600000 0.0282910000 29005748 96830484 1766023168 3.8926534653 3.9724256992 4.0104198456 1147 1311867756.8841960430 0.0921465456 0.1354072372 0.2374686003 0.0047919713 0.1146670000 0.0102550000 0.0398310000 0.0002960000 0.0002730000 0.0403870000 29007934 96830484 1767432192 3.8910186291 3.9732027054 4.0110764503 1148 1311867756.9223539829 0.0914800465 0.1353689731 0.2374686003 0.0047908678 0.1136190000 0.0106130000 0.0469030000 0.0000300000 0.0003900000 0.0280930000 29010184 96830484 1762889728 3.8915100098 3.9726591110 4.0111002922 1149 1311867756.9552440643 0.0901431367 0.1353296120 0.2374686003 0.0047904820 0.1273480000 0.0108270000 0.0436560000 0.0002940000 0.0002710000 0.0510540000 29012402 96830484 1764638720 3.8928329945 3.9713518620 4.0106105804 1150 1311867756.9841780663 0.0907319114 0.1352908314 0.2374686003 0.0047899599 0.0997790000 0.0095960000 0.0369020000 0.0000320000 0.0002950000 0.0293370000 29014524 96830484 1766309888 3.8920292854 3.9726724625 4.0109829903 1151 1311867757.0282740593 0.0897162855 0.1352512358 0.2374686003 0.0047936389 0.1350400000 0.0105580000 0.0637110000 0.0003520000 0.0006230000 0.0331710000 29016902 96830484 1767940096 3.8928859234 3.9711384773 4.0109171867 1152 1311867757.0552940369 0.0894474909 0.1352114756 0.2374686003 0.0047920915 0.1358430000 0.0100290000 0.0710060000 0.0000300000 0.0002950000 0.0277430000 29019024 96830484 1769590784 3.8932971954 3.9699060917 4.0106930733 1153 1311867757.0858569145 0.0884610265 0.1351709288 0.2374686003 0.0047914532 0.1245580000 0.0122130000 0.0368160000 0.0002880000 0.0002740000 0.0537270000 29021178 96830484 1768480768 3.8939659595 3.9723460674 4.0107874870 1154 1311867757.1283040047 0.0880366489 0.1351300846 0.2374686003 0.0048022123 0.1230610000 0.0098300000 0.0602770000 0.0000340000 0.0002810000 0.0279300000 29023492 96830484 1770209280 3.8948409557 3.9687747955 4.0106730461 1155 1311867757.1522068977 0.0861073658 0.1350876407 0.2374686003 0.0048016031 0.1338920000 0.0123460000 0.0562770000 0.0003470000 0.0002760000 0.0341480000 29025518 96830484 1768853504 3.8967673779 3.9682197571 4.0098447800 1156 1311867757.1851921082 0.0900525674 0.1350486830 0.2374686003 0.0048047793 0.1148590000 0.0099480000 0.0454880000 0.0000290000 0.0003710000 0.0336180000 29027736 96830484 1770463232 3.8927447796 3.9702260494 4.0107007027 1157 1311867757.2192370892 0.0889441893 0.1350088347 0.2374686003 0.0048036649 0.1352770000 0.0123420000 0.0487270000 0.0002970000 0.0003450000 0.0522370000 29029986 96830484 1769123840 3.8942275047 3.9686658382 4.0099959373 1158 1311867757.2523930073 0.0876057819 0.1349678994 0.2374686003 0.0048244259 0.1167610000 0.0109930000 0.0537110000 0.0000330000 0.0002920000 0.0289520000 29032172 96830484 1767854080 3.8957767487 3.9681949615 4.0091810226 1159 1311867757.2835690975 0.0880053043 0.1349273795 0.2374686003 0.0048280745 0.1507220000 0.0097050000 0.0722620000 0.0002980000 0.0002710000 0.0351390000 29034326 96830484 1769447424 3.8952014446 3.9705436230 4.0089659691 1160 1311867757.3233768940 0.0903669596 0.1348889653 0.2374686003 0.0048375600 0.1161850000 0.0123000000 0.0424610000 0.0000320000 0.0002930000 0.0291640000 29036640 96830484 1768099840 3.8935596943 3.9700896740 4.0090265274 1161 1311867757.3555359840 0.0896487609 0.1348499987 0.2374686003 0.0048358491 0.1547290000 0.0098100000 0.0702680000 0.0002950000 0.0002800000 0.0529920000 29038858 96830484 1769848832 3.8942680359 3.9702162743 4.0087895393 1162 1311867757.3833439350 0.0895489380 0.1348110133 0.2374686003 0.0048356117 0.1156020000 0.0113580000 0.0432030000 0.0000260000 0.0003910000 0.0291300000 29040948 96830484 1768574976 3.8944132328 3.9714365005 4.0091257095 1163 1311867757.4264349937 0.0883043930 0.1347710248 0.2374686003 0.0048407521 0.0973350000 0.0076630000 0.0311510000 0.0002950000 0.0002720000 0.0348130000 29043262 96830484 1769889792 3.8951451778 3.9726238251 4.0067815781 ================================================ FILE: icra2018_results/tegra/violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-19 03:33:55 Properties: ================= frame-limit: 0 log-file: output//violons_libkfusion-cuda_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/libkfusion-cuda-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 compute-size-ratio: 1 integration-rate: 2 tracking-rate: 1 rendering-rate: 4 icp-threshold: 1e-05 mu: 0.1 volume-size: 8,8,8 volume-direction: 4,4,4 volume-resolution: 256,256,256 pyramid-level1: 10 pyramid-level2: 5 pyramid-level3: 4 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame Duration_Preprocessing Duration_Tracking Duration_Integration Duration_Raycasting Duration_Render CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520030 0.0582520030 0.0582520030 nan 0.1430140000 0.0245570000 0.0155410000 0.0000960000 0.0000110000 0.0641300000 15804914 96830484 1770934272 4.0000000000 4.0000000000 4.0000000000 2 1311867170.4941389561 0.0599970818 0.0591245424 0.0599970818 0.0035990404 0.1019250000 0.0241920000 0.0307720000 0.0003040000 0.0000210000 0.0382180000 26293100 96830484 1769693184 4.0000000000 4.0000000000 4.0000000000 3 1311867170.5264289379 0.0615839623 0.0599443490 0.0615839623 0.0081929966 0.0848160000 0.0169700000 0.0181340000 0.0000660000 0.0000050000 0.0243400000 26295642 96830484 1768529920 4.0000000000 4.0000000000 4.0000000000 4 1311867170.5623490810 0.0628964603 0.0606823768 0.0628964603 0.0105671055 0.0979760000 0.0125580000 0.0113640000 0.0000900000 0.0001270000 0.0576260000 26298240 96830484 1765875712 4.0000000000 4.0000000000 4.0000000000 5 1311867170.5942170620 0.0609255508 0.0607310116 0.0628964603 0.0111240522 0.1721570000 0.0121080000 0.0707980000 0.0003910000 0.0002710000 0.0674980000 26300714 96830484 1763966976 4.0031204224 3.9974741936 3.9970712662 6 1311867170.6260869503 0.0606068857 0.0607103240 0.0628964603 0.0110236689 0.1530400000 0.0108200000 0.0828730000 0.0000210000 0.0002800000 0.0386120000 26303556 96830484 1765011456 4.0016202927 3.9956722260 3.9953827858 7 1311867170.6621398926 0.0602267869 0.0606412472 0.0628964603 0.0105600055 0.1362940000 0.0113540000 0.0749060000 0.0003540000 0.0003060000 0.0390620000 26305838 96830484 1764585472 4.0018520355 3.9940953255 3.9936211109 8 1311867170.6942050457 0.0600393713 0.0605660127 0.0628964603 0.0100604432 0.1148600000 0.0094850000 0.0627040000 0.0000210000 0.0002850000 0.0329040000 26307992 96830484 1766244352 4.0011649132 3.9931421280 3.9919643402 9 1311867170.7263879776 0.0608413592 0.0605966068 0.0628964603 0.0100341190 0.1314870000 0.0090820000 0.0536170000 0.0003100000 0.0003770000 0.0614120000 26310818 96830484 1767870464 4.0015835762 3.9936788082 3.9908602238 10 1311867170.7620189190 0.0603601485 0.0605729610 0.0628964603 0.0098654994 0.1216210000 0.0091920000 0.0688800000 0.0000230000 0.0003050000 0.0331030000 26314412 96830484 1769521152 3.9995176792 3.9909095764 3.9892880917 11 1311867170.7941920757 0.0607255362 0.0605868314 0.0628964603 0.0096819937 0.1176770000 0.0107110000 0.0581590000 0.0003800000 0.0002660000 0.0392040000 26316534 96830484 1768566784 4.0003919601 3.9889512062 3.9876794815 12 1311867170.8262820244 0.0612730682 0.0606440178 0.0628964603 0.0096071606 0.1153620000 0.0089190000 0.0633360000 0.0000250000 0.0002820000 0.0333870000 26318752 96830484 1770283008 4.0014433861 3.9856188297 3.9859566689 13 1311867170.8622210026 0.0614246465 0.0607040662 0.0628964603 0.0096868568 0.1368790000 0.0108490000 0.0580610000 0.0003560000 0.0002690000 0.0605250000 26321002 96830484 1769455616 4.0042152405 3.9817748070 3.9834048748 14 1311867170.8943779469 0.0618292317 0.0607844352 0.0628964603 0.0094042355 0.0963760000 0.0102470000 0.0400770000 0.0000250000 0.0002860000 0.0350160000 26323156 96830484 1764970496 4.0020465851 3.9801175594 3.9812355042 15 1311867170.9263520241 0.0620423369 0.0608682953 0.0628964603 0.0093865211 0.1122580000 0.0107130000 0.0500970000 0.0002840000 0.0003380000 0.0380400000 26325374 96830484 1766662144 4.0028033257 3.9772746563 3.9783899784 16 1311867170.9621469975 0.0615640618 0.0609117807 0.0628964603 0.0091720081 0.0973930000 0.0087940000 0.0464760000 0.0000270000 0.0003140000 0.0346700000 26327624 96830484 1768423424 4.0006170273 3.9753031731 3.9754066467 17 1311867170.9942629337 0.0615488924 0.0609492578 0.0628964603 0.0090175198 0.1342220000 0.0092010000 0.0465010000 0.0003540000 0.0002780000 0.0635180000 26331058 96830484 1769775104 3.9983317852 3.9747266769 3.9725198746 18 1311867171.0262739658 0.0615876988 0.0609847268 0.0628964603 0.0087659622 0.1184540000 0.0108490000 0.0676330000 0.0000240000 0.0002970000 0.0325970000 26335900 96830484 1768677376 3.9982314110 3.9730978012 3.9697573185 19 1311867171.0623519421 0.0607667975 0.0609732568 0.0628964603 0.0091367860 0.1122540000 0.0089710000 0.0451080000 0.0003280000 0.0002690000 0.0392570000 26338150 96830484 1770283008 3.9972741604 3.9699807167 3.9667031765 20 1311867171.0942349434 0.0605248772 0.0609508378 0.0628964603 0.0090692939 0.1171090000 0.0106460000 0.0511780000 0.0000260000 0.0003390000 0.0335380000 26340304 96830484 1768648704 3.9972934723 3.9690694809 3.9645543098 21 1311867171.1262509823 0.0605401620 0.0609312819 0.0628964603 0.0089249978 0.1487860000 0.0096820000 0.0701510000 0.0000590000 0.0000510000 0.0617400000 26342522 96830484 1768169472 3.9977991581 3.9692590237 3.9624040127 22 1311867171.1622469425 0.0602495410 0.0609002936 0.0628964603 0.0088215898 0.0993840000 0.0090930000 0.0408610000 0.0000250000 0.0002860000 0.0331300000 26344772 96830484 1765240832 3.9996869564 3.9667265415 3.9608981609 23 1311867171.1942689419 0.0591715388 0.0608251304 0.0628964603 0.0090504679 0.1124000000 0.0091770000 0.0446170000 0.0003120000 0.0002770000 0.0397380000 26346926 96830484 1765244928 4.0015068054 3.9671711922 3.9596321583 24 1311867171.2262530327 0.0610397086 0.0608340711 0.0628964603 0.0090330389 0.0970790000 0.0085680000 0.0416860000 0.0000260000 0.0004380000 0.0351640000 26349144 96830484 1764847616 4.0051293373 3.9670662880 3.9591324329 25 1311867171.2622439861 0.0604354963 0.0608181281 0.0628964603 0.0090268282 0.1535660000 0.0090670000 0.0593840000 0.0005550000 0.0002910000 0.0659140000 26351394 96830484 1765011456 4.0063109398 3.9663758278 3.9580407143 26 1311867171.2943410873 0.0607758537 0.0608165022 0.0628964603 0.0090313839 0.1146610000 0.0085160000 0.0523420000 0.0000240000 0.0003120000 0.0346320000 26353516 96830484 1766633472 4.0050344467 3.9690012932 3.9576370716 27 1311867171.3263869286 0.0610807166 0.0608262879 0.0628964603 0.0092607707 0.1175940000 0.0087240000 0.0527100000 0.0003720000 0.0002780000 0.0404190000 26355734 96830484 1768378368 4.0014872551 3.9707021713 3.9562168121 28 1311867171.3622460365 0.0606384315 0.0608195788 0.0628964603 0.0091276392 0.0994030000 0.0088150000 0.0514700000 0.0000240000 0.0006270000 0.0316590000 26357984 96830484 1770029056 3.9982602596 3.9720211029 3.9548857212 29 1311867171.3941431046 0.0616840944 0.0608493896 0.0628964603 0.0093238705 0.1248790000 0.0109270000 0.0455100000 0.0003100000 0.0003530000 0.0607220000 26360138 96830484 1768910848 3.9963366985 3.9747731686 3.9538137913 30 1311867171.4262878895 0.0624736287 0.0609035309 0.0628964603 0.0092821065 0.1244840000 0.0090170000 0.0674950000 0.0000270000 0.0003080000 0.0326480000 26362356 96830484 1770696704 3.9951894283 3.9750590324 3.9522833824 31 1311867171.4622440338 0.0615481064 0.0609243237 0.0628964603 0.0092183771 0.1009760000 0.0107150000 0.0470770000 0.0003090000 0.0003490000 0.0353560000 26364606 96830484 1769967616 3.9948298931 3.9722583294 3.9500498772 32 1311867171.4944040775 0.0617246106 0.0609493327 0.0628964603 0.0091390726 0.0857170000 0.0107100000 0.0402650000 0.0000260000 0.0003110000 0.0271620000 26366760 96830484 1768804352 3.9956355095 3.9733610153 3.9481241703 33 1311867171.5261778831 0.0612912402 0.0609596935 0.0628964603 0.0089980268 0.1412600000 0.0090550000 0.0641700000 0.0004410000 0.0003180000 0.0603440000 26371538 96830484 1770528768 3.9946579933 3.9734306335 3.9461174011 34 1311867171.5622971058 0.0606500022 0.0609505849 0.0628964603 0.0088635966 0.0974800000 0.0106270000 0.0356150000 0.0000240000 0.0002780000 0.0346170000 26379036 96830484 1766371328 3.9947957993 3.9731707573 3.9447462559 35 1311867171.5942931175 0.0608569868 0.0609479107 0.0628964603 0.0087982148 0.1330340000 0.0093350000 0.0669900000 0.0006870000 0.0002770000 0.0396880000 26381190 96830484 1768017920 3.9960794449 3.9745070934 3.9438178539 36 1311867171.6263399124 0.0606701300 0.0609401946 0.0628964603 0.0087016668 0.0975110000 0.0091180000 0.0476730000 0.0000240000 0.0003340000 0.0332770000 26383408 96830484 1769684992 3.9952204227 3.9733436108 3.9432265759 37 1311867171.6622560024 0.0606159754 0.0609314319 0.0628964603 0.0086015283 0.1322060000 0.0109390000 0.0513730000 0.0003180000 0.0003340000 0.0618280000 26385658 96830484 1768288256 3.9915304184 3.9728064537 3.9424617290 38 1311867171.6943440437 0.0612193719 0.0609390093 0.0628964603 0.0087792985 0.0994950000 0.0088510000 0.0501280000 0.0000250000 0.0003730000 0.0331490000 26387812 96830484 1769893888 3.9923806190 3.9735386372 3.9422576427 39 1311867171.7262439728 0.0611849762 0.0609453161 0.0628964603 0.0086903417 0.1192500000 0.0109140000 0.0638960000 0.0003030000 0.0003010000 0.0362490000 26390030 96830484 1768796160 3.9922440052 3.9729046822 3.9418673515 40 1311867171.7621190548 0.0614482947 0.0609578906 0.0628964603 0.0086037227 0.1105750000 0.0088210000 0.0519200000 0.0000270000 0.0003320000 0.0331370000 26392280 96830484 1770528768 3.9937994480 3.9712657928 3.9414863586 41 1311867171.7941710949 0.0610062890 0.0609590710 0.0628964603 0.0085974340 0.1489560000 0.0101730000 0.0691820000 0.0003770000 0.0003160000 0.0617090000 26394434 96830484 1769701376 3.9931781292 3.9692983627 3.9404547215 42 1311867171.8262550831 0.0613993742 0.0609695544 0.0628964603 0.0085173730 0.1070680000 0.0106730000 0.0527300000 0.0000270000 0.0003040000 0.0335720000 26396652 96830484 1766092800 3.9928946495 3.9690437317 3.9393262863 43 1311867171.8623590469 0.0609293878 0.0609686203 0.0628964603 0.0084210042 0.0957880000 0.0094830000 0.0401970000 0.0003190000 0.0002760000 0.0382090000 26398902 96830484 1767272448 3.9888556004 3.9687583447 3.9379658699 44 1311867171.8944430351 0.0605780631 0.0609597440 0.0628964603 0.0085305044 0.1510950000 0.0080710000 0.0824470000 0.0000280000 0.0006580000 0.0452220000 26401088 96830484 1763180544 3.9858376980 3.9683296680 3.9371502399 45 1311867171.9262220860 0.0615070239 0.0609719058 0.0628964603 0.0084651109 0.1333500000 0.0101560000 0.0429470000 0.0003910000 0.0003130000 0.0648760000 26403274 96830484 1764859904 3.9849183559 3.9696943760 3.9369037151 46 1311867171.9624669552 0.0616462901 0.0609865663 0.0628964603 0.0084063409 0.1165450000 0.0087630000 0.0662860000 0.0000280000 0.0003950000 0.0332170000 26405524 96830484 1766621184 3.9828603268 3.9694330692 3.9368638992 47 1311867171.9946711063 0.0620016418 0.0610081637 0.0628964603 0.0084676552 0.1133380000 0.0089650000 0.0459820000 0.0003170000 0.0003480000 0.0401920000 26407710 96830484 1767989248 3.9826419353 3.9692745209 3.9370570183 48 1311867172.0262680054 0.0626903176 0.0610432085 0.0628964603 0.0085270340 0.1188780000 0.0088400000 0.0662220000 0.0000280000 0.0003040000 0.0336650000 26409896 96830484 1769672704 3.9832270145 3.9691503048 3.9375026226 49 1311867172.0622880459 0.0630677417 0.0610845255 0.0630677417 0.0084679911 0.1478660000 0.0111580000 0.0673570000 0.0003720000 0.0003100000 0.0613940000 26412146 96830484 1768558592 3.9815311432 3.9699618816 3.9382386208 50 1311867172.0941960812 0.0632554963 0.0611279450 0.0632554963 0.0084485749 0.1229190000 0.0091980000 0.0672450000 0.0000290000 0.0002980000 0.0327600000 26414332 96830484 1770274816 3.9807128906 3.9696776867 3.9387979507 51 1311867172.1263689995 0.0637623146 0.0611795993 0.0637623146 0.0084511155 0.1361090000 0.0110890000 0.0678810000 0.0003020000 0.0003820000 0.0389890000 26416518 96830484 1769177088 3.9780254364 3.9700536728 3.9398059845 52 1311867172.1623349190 0.0626442954 0.0612077665 0.0637623146 0.0084093777 0.1148180000 0.0104730000 0.0517850000 0.0000270000 0.0003010000 0.0332900000 26418768 96830484 1768431616 3.9731349945 3.9699816704 3.9402039051 53 1311867172.1944270134 0.0616533458 0.0612161737 0.0637623146 0.0083587378 0.1547930000 0.0087290000 0.0671570000 0.0003820000 0.0002780000 0.0596600000 26420954 96830484 1770020864 3.9676706791 3.9710264206 3.9405920506 54 1311867172.2264409065 0.0615787171 0.0612228874 0.0637623146 0.0085076846 0.1206110000 0.0108250000 0.0713680000 0.0000290000 0.0003060000 0.0306160000 26423140 96830484 1768923136 3.9636471272 3.9709110260 3.9409642220 55 1311867172.2622280121 0.0611496307 0.0612215555 0.0637623146 0.0084390079 0.1318260000 0.0090610000 0.0662260000 0.0003710000 0.0002740000 0.0390670000 26425390 96830484 1770688512 3.9609060287 3.9717552662 3.9413638115 56 1311867172.2944829464 0.0612984523 0.0612229286 0.0637623146 0.0083778860 0.0959280000 0.0108880000 0.0396010000 0.0000260000 0.0003810000 0.0343760000 26427576 96830484 1766481920 3.9581747055 3.9725735188 3.9417738914 57 1311867172.3263380527 0.0608702041 0.0612167405 0.0637623146 0.0083485764 0.1535590000 0.0108000000 0.0742110000 0.0003400000 0.0002720000 0.0605990000 26429762 96830484 1768140800 3.9550552368 3.9723949432 3.9422535896 58 1311867172.3624010086 0.0609766617 0.0612126012 0.0637623146 0.0082959001 0.1132140000 0.0091010000 0.0562500000 0.0000280000 0.0003080000 0.0330110000 26432012 96830484 1769807872 3.9512205124 3.9734847546 3.9424102306 59 1311867172.3942890167 0.0598670878 0.0611897959 0.0637623146 0.0082390077 0.1354550000 0.0112750000 0.0673770000 0.0003780000 0.0002820000 0.0387190000 26434198 96830484 1768542208 3.9469397068 3.9733154774 3.9423127174 60 1311867172.4265220165 0.0596600175 0.0611642996 0.0637623146 0.0082917403 0.1172550000 0.0088410000 0.0668760000 0.0000250000 0.0003820000 0.0332190000 26436384 96830484 1770139648 3.9418015480 3.9735672474 3.9418094158 61 1311867172.4623498917 0.0591419451 0.0611311462 0.0637623146 0.0082673059 0.1549260000 0.0113250000 0.0620100000 0.0004530000 0.0002780000 0.0641990000 26438634 96830484 1769041920 3.9384975433 3.9728069305 3.9413890839 62 1311867172.4952669144 0.0595941544 0.0611063560 0.0637623146 0.0083050305 0.0973060000 0.0109490000 0.0432930000 0.0000290000 0.0003130000 0.0332970000 26440788 96830484 1764569088 3.9373931885 3.9733579159 3.9412720203 63 1311867172.5263059139 0.0592598952 0.0610770471 0.0637623146 0.0082512130 0.1111730000 0.0096120000 0.0460000000 0.0003200000 0.0002750000 0.0392370000 26442974 96830484 1766391808 3.9349503517 3.9717154503 3.9406676292 64 1311867172.5624930859 0.0588509440 0.0610422643 0.0637623146 0.0082002447 0.0962060000 0.0091130000 0.0393860000 0.0000080000 0.0000970000 0.0353970000 26445224 96830484 1768026112 3.9306249619 3.9709284306 3.9400806427 65 1311867172.5945439339 0.0596711449 0.0610211701 0.0637623146 0.0082025184 0.1744050000 0.0087860000 0.0827970000 0.0003140000 0.0002750000 0.0630920000 26452498 96830484 1769377792 3.9333574772 3.9711189270 3.9393780231 66 1311867172.6263699532 0.0593869090 0.0609964086 0.0637623146 0.0081761680 0.1193010000 0.0108440000 0.0654980000 0.0000260000 0.0004150000 0.0334620000 26465212 96830484 1768280064 3.9303588867 3.9711532593 3.9385757446 67 1311867172.6624419689 0.0592229590 0.0609699392 0.0637623146 0.0081179003 0.0953570000 0.0095220000 0.0351500000 0.0002040000 0.0002360000 0.0415060000 26467462 96830484 1769918464 3.9275050163 3.9713408947 3.9379904270 68 1311867172.6945450306 0.0590793006 0.0609421357 0.0637623146 0.0081824799 0.1369750000 0.0114520000 0.0833060000 0.0000280000 0.0003010000 0.0332900000 26469648 96830484 1768914944 3.9258584976 3.9711616039 3.9375286102 69 1311867172.7263929844 0.0594211705 0.0609200927 0.0637623146 0.0081546162 0.1503330000 0.0092320000 0.0464800000 0.0003210000 0.0002750000 0.0652080000 26471834 96830484 1770647552 3.9233663082 3.9712274075 3.9371786118 70 1311867172.7623739243 0.0597567074 0.0609034729 0.0637623146 0.0081129478 0.1193020000 0.0120430000 0.0511400000 0.0000300000 0.0003020000 0.0339030000 26474084 96830484 1769533440 3.9207289219 3.9725017548 3.9369683266 71 1311867172.7944509983 0.0589838028 0.0608764353 0.0637623146 0.0080605372 0.1469200000 0.0117760000 0.0666940000 0.0000710000 0.0000550000 0.0393630000 26476238 96830484 1768808448 3.9160416126 3.9716811180 3.9364058971 72 1311867172.8263089657 0.0594336465 0.0608563966 0.0637623146 0.0080248448 0.1214760000 0.0092530000 0.0696380000 0.0000270000 0.0004140000 0.0334810000 26478456 96830484 1770393600 3.9132237434 3.9718620777 3.9355027676 73 1311867172.8632309437 0.0593185313 0.0608353299 0.0637623146 0.0079892377 0.1528750000 0.0112920000 0.0696070000 0.0025740000 0.0003200000 0.0614830000 26480738 96830484 1769549824 3.9104530811 3.9712836742 3.9346950054 74 1311867172.8944649696 0.0586204045 0.0608053985 0.0637623146 0.0079353911 0.1366160000 0.0109060000 0.0708310000 0.0000250000 0.0003380000 0.0337650000 26482860 96830484 1768534016 3.9072430134 3.9710445404 3.9340178967 75 1311867172.9263219833 0.0582705699 0.0607716008 0.0637623146 0.0078825655 0.1174850000 0.0105120000 0.0573650000 0.0004180000 0.0002850000 0.0395520000 26485078 96830484 1770266624 3.9041652679 3.9702188969 3.9334359169 76 1311867172.9623310566 0.0580972768 0.0607364123 0.0637623146 0.0078311138 0.0967870000 0.0110890000 0.0411550000 0.0000270000 0.0003730000 0.0333700000 26487328 96830484 1766076416 3.9026601315 3.9699106216 3.9327528477 77 1311867172.9945271015 0.0584635288 0.0607068944 0.0637623146 0.0078075574 0.1250450000 0.0094330000 0.0449270000 0.0004220000 0.0002870000 0.0621980000 26489482 96830484 1767772160 3.9039983749 3.9697606564 3.9322309494 78 1311867173.0262629986 0.0575079769 0.0606658826 0.0637623146 0.0077700458 0.1016990000 0.0090630000 0.0401400000 0.0000300000 0.0003370000 0.0346320000 26491668 96830484 1769504768 3.8992121220 3.9693017006 3.9320430756 79 1311867173.0624630451 0.0575752556 0.0606267607 0.0637623146 0.0077247073 0.1185240000 0.0106520000 0.0577800000 0.0003390000 0.0003470000 0.0392300000 26493918 96830484 1768660992 3.8990201950 3.9687981606 3.9317197800 80 1311867173.0945179462 0.0580349341 0.0605943629 0.0637623146 0.0077061306 0.1120830000 0.0093320000 0.0459880000 0.0000260000 0.0003120000 0.0334350000 26496104 96830484 1770266624 3.8985764980 3.9687404633 3.9317734241 81 1311867173.1267819405 0.0577851385 0.0605596811 0.0637623146 0.0076780788 0.1383570000 0.0115780000 0.0567750000 0.0003110000 0.0003540000 0.0616770000 26498322 96830484 1769148416 3.8967087269 3.9687883854 3.9315290451 82 1311867173.1622309685 0.0582004413 0.0605309099 0.0637623146 0.0076662800 0.1141620000 0.0102410000 0.0453730000 0.0000310000 0.0003090000 0.0331120000 26500572 96830484 1766592512 3.8968245983 3.9698104858 3.9316117764 83 1311867173.1943008900 0.0586032234 0.0605076848 0.0637623146 0.0076202893 0.1351250000 0.0103610000 0.0718370000 0.0003170000 0.0002760000 0.0394080000 26502726 96830484 1767010304 3.8961479664 3.9703531265 3.9316937923 84 1311867173.2264449596 0.0575914234 0.0604729674 0.0637623146 0.0075809640 0.1140640000 0.0092620000 0.0528350000 0.0000280000 0.0003680000 0.0333330000 26504912 96830484 1765847040 3.8909873962 3.9698333740 3.9317409992 85 1311867173.2622020245 0.0589147992 0.0604546360 0.0637623146 0.0075405380 0.1460190000 0.0089390000 0.0679190000 0.0003390000 0.0003510000 0.0609600000 26507162 96830484 1767632896 3.8932032585 3.9705605507 3.9319751263 86 1311867173.2942678928 0.0589867607 0.0604375677 0.0637623146 0.0074969450 0.1260970000 0.0093660000 0.0683770000 0.0000930000 0.0002930000 0.0326770000 26509316 96830484 1769377792 3.8909549713 3.9703869820 3.9319984913 87 1311867173.3262879848 0.0585804917 0.0604162220 0.0637623146 0.0075020822 0.1361910000 0.0109780000 0.0683880000 0.0003320000 0.0002820000 0.0396620000 26511502 96830484 1768534016 3.8878068924 3.9691002369 3.9320209026 88 1311867173.3623280525 0.0585228279 0.0603947061 0.0637623146 0.0074594217 0.1177830000 0.0091630000 0.0690760000 0.0000280000 0.0002910000 0.0315140000 26513784 96830484 1770172416 3.8852434158 3.9691107273 3.9319114685 89 1311867173.3942871094 0.0580641329 0.0603685199 0.0637623146 0.0074279854 0.1346470000 0.0113760000 0.0530450000 0.0002990000 0.0003610000 0.0617110000 26515938 96830484 1769168896 3.8819754124 3.9692664146 3.9317789078 90 1311867173.4262790680 0.0577776060 0.0603397320 0.0637623146 0.0074105332 0.1122490000 0.0104880000 0.0460150000 0.0000280000 0.0003580000 0.0335870000 26518124 96830484 1766866944 3.8797004223 3.9691491127 3.9314906597 91 1311867173.4622900486 0.0571836233 0.0603050495 0.0637623146 0.0073976053 0.1518740000 0.0102880000 0.0737750000 0.0002970000 0.0003110000 0.0391300000 26520374 96830484 1766899712 3.8768131733 3.9686460495 3.9310617447 92 1311867173.4943389893 0.0579163358 0.0602790852 0.0637623146 0.0074584493 0.1182140000 0.0098380000 0.0677090000 0.0000260000 0.0003640000 0.0324350000 26522560 96830484 1765486592 3.8756899834 3.9682323933 3.9305799007 93 1311867173.5263900757 0.0576199666 0.0602504925 0.0637623146 0.0074206456 0.1319850000 0.0097110000 0.0343010000 0.0000790000 0.0000780000 0.0671960000 26524778 96830484 1764851712 3.8733811378 3.9677715302 3.9301331043 94 1311867173.5624370575 0.0574126132 0.0602203023 0.0637623146 0.0074001370 0.1181400000 0.0091340000 0.0672970000 0.0000230000 0.0003560000 0.0332900000 26527028 96830484 1764106240 3.8714597225 3.9680230618 3.9299745560 95 1311867173.5943109989 0.0575315952 0.0601920001 0.0637623146 0.0073863877 0.1137380000 0.0096340000 0.0526650000 0.0002880000 0.0003410000 0.0392810000 26529182 96830484 1765728256 3.8692240715 3.9682145119 3.9296579361 96 1311867173.6263959408 0.0565164909 0.0601537136 0.0637623146 0.0073598229 0.1347020000 0.0094310000 0.0708190000 0.0000270000 0.0006900000 0.0334350000 26531368 96830484 1767473152 3.8651394844 3.9674844742 3.9291470051 97 1311867173.6623299122 0.0573306754 0.0601246101 0.0637623146 0.0073270024 0.1512920000 0.0091800000 0.0718710000 0.0004950000 0.0002920000 0.0618300000 26533618 96830484 1769123840 3.8655548096 3.9680991173 3.9287540913 98 1311867173.6943540573 0.0578837991 0.0601017447 0.0637623146 0.0072930485 0.1249890000 0.0110490000 0.0682920000 0.0000280000 0.0003510000 0.0333360000 26535804 96830484 1768005632 3.8650343418 3.9680962563 3.9283368587 99 1311867173.7267971039 0.0568750799 0.0600691521 0.0637623146 0.0072930823 0.1367760000 0.0094000000 0.0822270000 0.0003930000 0.0002790000 0.0365140000 26538022 96830484 1769791488 3.8597834110 3.9674205780 3.9273908138 100 1311867173.7623970509 0.0574045181 0.0600425057 0.0637623146 0.0072696127 0.1137740000 0.0108120000 0.0460620000 0.0000280000 0.0003030000 0.0340040000 26540272 96830484 1767510016 3.8598444462 3.9679765701 3.9268679619 101 1311867173.7943561077 0.0578601174 0.0600208979 0.0637623146 0.0072371107 0.1486120000 0.0101940000 0.0670360000 0.0004900000 0.0002890000 0.0625510000 26542394 96830484 1767534592 3.8592157364 3.9682660103 3.9263706207 102 1311867173.8265669346 0.0571436696 0.0599926898 0.0637623146 0.0072046286 0.1208620000 0.0100030000 0.0694600000 0.0000280000 0.0002880000 0.0330120000 26544612 96830484 1765613568 3.8563008308 3.9667377472 3.9253394604 103 1311867173.8635799885 0.0577008314 0.0599704388 0.0637623146 0.0072029886 0.1132440000 0.0094100000 0.0515110000 0.0003730000 0.0002870000 0.0401280000 26546830 96830484 1767264256 3.8542523384 3.9677751064 3.9248940945 104 1311867173.8946080208 0.0579137430 0.0599506628 0.0637623146 0.0071718085 0.1344010000 0.0097230000 0.0708290000 0.0000300000 0.0003650000 0.0337890000 26549016 96830484 1768648704 3.8541655540 3.9673631191 3.9240877628 105 1311867173.9266970158 0.0568218417 0.0599208646 0.0637623146 0.0071451070 0.1576920000 0.0090980000 0.0683820000 0.0003000000 0.0002750000 0.0653020000 26551234 96830484 1770393600 3.8500421047 3.9669020176 3.9229753017 106 1311867173.9625461102 0.0570559166 0.0598938367 0.0637623146 0.0071476223 0.1354300000 0.0115010000 0.0688450000 0.0000270000 0.0003110000 0.0337520000 26553484 96830484 1769304064 3.8480041027 3.9680950642 3.9225745201 107 1311867173.9944310188 0.0576230623 0.0598726146 0.0637623146 0.0071323957 0.1164910000 0.0115360000 0.0518150000 0.0003140000 0.0002710000 0.0395800000 26555638 96830484 1768140800 3.8490302563 3.9683346748 3.9220333099 108 1311867174.0264260769 0.0566545352 0.0598428175 0.0637623146 0.0072146437 0.0953610000 0.0093600000 0.0416870000 0.0000310000 0.0010540000 0.0341460000 26557824 96830484 1769893888 3.8442916870 3.9667720795 3.9209272861 109 1311867174.0624630451 0.0573899560 0.0598203142 0.0637623146 0.0071884438 0.1499190000 0.0111540000 0.0679380000 0.0003150000 0.0002680000 0.0619920000 26560074 96830484 1769066496 3.8460693359 3.9672398567 3.9204702377 110 1311867174.0945188999 0.0590773746 0.0598135602 0.0637623146 0.0071657101 0.1197930000 0.0094370000 0.0575460000 0.0000260000 0.0003580000 0.0339440000 26562260 96830484 1770782720 3.8470315933 3.9684183598 3.9209301472 111 1311867174.1264541149 0.0583969653 0.0598007981 0.0637623146 0.0071485724 0.1370750000 0.0114650000 0.0679750000 0.0003590000 0.0002690000 0.0397750000 26564446 96830484 1769684992 3.8437809944 3.9667174816 3.9200575352 112 1311867174.1624329090 0.0586246178 0.0597902965 0.0637623146 0.0071475141 0.0965510000 0.0111200000 0.0400060000 0.0000260000 0.0002870000 0.0336230000 26566696 96830484 1765199872 3.8410599232 3.9674363136 3.9199512005 113 1311867174.1943979263 0.0595935099 0.0597885550 0.0637623146 0.0071370278 0.1494330000 0.0101690000 0.0690610000 0.0003550000 0.0002680000 0.0614740000 26568882 96830484 1766907904 3.8419713974 3.9687659740 3.9202706814 114 1311867174.2267580032 0.0586531237 0.0597785951 0.0637623146 0.0071153379 0.1196150000 0.0093250000 0.0706810000 0.0000300000 0.0002990000 0.0313300000 26571100 96830484 1768521728 3.8372681141 3.9668915272 3.9199249744 115 1311867174.2626769543 0.0586626232 0.0597688910 0.0637623146 0.0070844412 0.1119280000 0.0095070000 0.0410940000 0.0011880000 0.0002790000 0.0396920000 26573318 96830484 1770020864 3.8344988823 3.9667725563 3.9197254181 116 1311867174.2945280075 0.0598962642 0.0597699890 0.0637623146 0.0070658757 0.1206670000 0.0125400000 0.0688560000 0.0000270000 0.0003610000 0.0308920000 26575504 96830484 1768923136 3.8351602554 3.9675381184 3.9196290970 117 1311867174.3265740871 0.0585832670 0.0597598461 0.0637623146 0.0070379619 0.1173840000 0.0095520000 0.0413990000 0.0003670000 0.0010450000 0.0571200000 26577690 96830484 1770528768 3.8306124210 3.9667012691 3.9187247753 118 1311867174.3624329567 0.0584417917 0.0597486761 0.0637623146 0.0070159571 0.1122150000 0.0112110000 0.0530900000 0.0000930000 0.0002890000 0.0331330000 26579972 96830484 1769431040 3.8275566101 3.9675989151 3.9188940525 119 1311867174.3946359158 0.0591085255 0.0597432967 0.0637623146 0.0070159042 0.1350200000 0.0110070000 0.0684600000 0.0002940000 0.0002680000 0.0390850000 26582126 96830484 1768669184 3.8267788887 3.9688591957 3.9190297127 120 1311867174.4266788960 0.0587439239 0.0597349686 0.0637623146 0.0069923968 0.1132050000 0.0098580000 0.0461540000 0.0000250000 0.0002920000 0.0334520000 26584344 96830484 1770307584 3.8232476711 3.9683456421 3.9189798832 121 1311867174.4630160332 0.0582034551 0.0597223115 0.0637623146 0.0069809184 0.1514750000 0.0122370000 0.0689120000 0.0004950000 0.0002860000 0.0614600000 26586562 96830484 1769304064 3.8203105927 3.9676790237 3.9187932014 122 1311867174.4945669174 0.0592569001 0.0597184966 0.0637623146 0.0069533442 0.1049690000 0.0107100000 0.0471870000 0.0000300000 0.0003150000 0.0334680000 26588748 96830484 1765339136 3.8213775158 3.9686639309 3.9189889431 123 1311867174.5267519951 0.0586591251 0.0597098839 0.0637623146 0.0069389225 0.1322710000 0.0098510000 0.0681410000 0.0002880000 0.0003390000 0.0391100000 26590966 96830484 1767145472 3.8181772232 3.9680457115 3.9187579155 124 1311867174.5623500347 0.0582337715 0.0596979797 0.0637623146 0.0069523861 0.1313670000 0.0094830000 0.0697780000 0.0000270000 0.0003600000 0.0334610000 26593216 96830484 1768751104 3.8147675991 3.9675164223 3.9187674522 125 1311867174.5944879055 0.0586924069 0.0596899351 0.0637623146 0.0069470229 0.1188900000 0.0095550000 0.0369440000 0.0002980000 0.0002790000 0.0637500000 26595370 96830484 1770528768 3.8146224022 3.9690346718 3.9190659523 126 1311867174.6265459061 0.0587740727 0.0596826664 0.0637623146 0.0069261208 0.1340160000 0.0112560000 0.0691020000 0.0000290000 0.0002950000 0.0332060000 26597556 96830484 1769431040 3.8113064766 3.9694843292 3.9196209908 127 1311867174.6624910831 0.0581208766 0.0596703688 0.0637623146 0.0069052719 0.0989890000 0.0117010000 0.0403000000 0.0008880000 0.0002860000 0.0374730000 26599806 96830484 1765863424 3.8073830605 3.9683787823 3.9196753502 128 1311867174.6945910454 0.0587996878 0.0596635666 0.0637623146 0.0069033486 0.1303190000 0.0097980000 0.0698240000 0.0000270000 0.0003290000 0.0337430000 26601992 96830484 1767272448 3.8070917130 3.9702427387 3.9203505516 129 1311867174.7265629768 0.0591099635 0.0596592751 0.0637623146 0.0069080670 0.1310280000 0.0096260000 0.0495370000 0.0003550000 0.0002690000 0.0615320000 26614386 96830484 1764069376 3.8039124012 3.9701864719 3.9207334518 130 1311867174.7623760700 0.0585926771 0.0596510705 0.0637623146 0.0069087016 0.1189340000 0.0098710000 0.0614380000 0.0000280000 0.0006260000 0.0328900000 26637660 96830484 1765113856 3.7996885777 3.9672994614 3.9206726551 131 1311867174.7944738865 0.0588013940 0.0596445845 0.0637623146 0.0068843321 0.1355520000 0.0095810000 0.0701380000 0.0003580000 0.0002710000 0.0398050000 26639782 96830484 1764343808 3.8008005619 3.9683547020 3.9202189445 132 1311867174.8273398876 0.0587673970 0.0596379391 0.0637623146 0.0068595480 0.1346600000 0.0099210000 0.0731250000 0.0000250000 0.0002780000 0.0395650000 26642000 96830484 1764986880 3.7979588509 3.9676225185 3.9202327728 133 1311867174.8624229431 0.0575898774 0.0596225401 0.0637623146 0.0068383071 0.1336730000 0.0098850000 0.0400760000 0.0004230000 0.0003610000 0.0624710000 26644250 96830484 1765003264 3.7946829796 3.9673156738 3.9190990925 134 1311867174.8944199085 0.0568429492 0.0596017969 0.0637623146 0.0068300270 0.1158120000 0.0093850000 0.0578130000 0.0000270000 0.0002750000 0.0333730000 26646404 96830484 1766719488 3.7914595604 3.9691569805 3.9182214737 135 1311867174.9270179272 0.0568432137 0.0595813630 0.0637623146 0.0068235120 0.1364460000 0.0095230000 0.0703130000 0.0002850000 0.0002640000 0.0398650000 26648622 96830484 1768402944 3.7906866074 3.9684281349 3.9177041054 136 1311867174.9626429081 0.0571424142 0.0595634295 0.0637623146 0.0068067751 0.1470020000 0.0093730000 0.0792140000 0.0000070000 0.0000590000 0.0382360000 26650872 96830484 1770147840 3.7909991741 3.9681379795 3.9168813229 137 1311867174.9943349361 0.0565158203 0.0595411842 0.0637623146 0.0068173389 0.1663110000 0.0128590000 0.0689870000 0.0002820000 0.0003310000 0.0634870000 26653026 96830484 1769050112 3.7862153053 3.9690082073 3.9163525105 138 1311867175.0265510082 0.0573840030 0.0595255525 0.0637623146 0.0068499656 0.0986860000 0.0114940000 0.0467710000 0.0000260000 0.0003150000 0.0315470000 26655244 96830484 1765482496 3.7855663300 3.9726147652 3.9166240692 139 1311867175.0633120537 0.0569344312 0.0595069113 0.0637623146 0.0068267262 0.1112800000 0.0098430000 0.0404540000 0.0003580000 0.0002680000 0.0491380000 26657494 96830484 1766883328 3.7812125683 3.9713575840 3.9166951180 140 1311867175.0947189331 0.0556002632 0.0594790067 0.0637623146 0.0068217621 0.1326270000 0.0096190000 0.0681950000 0.0000280000 0.0003160000 0.0338610000 26659680 96830484 1762529280 3.7697446346 3.9731466770 3.9162058830 141 1311867175.1265308857 0.0559610203 0.0594540564 0.0637623146 0.0068089480 0.1497890000 0.0104170000 0.0684670000 0.0003730000 0.0002830000 0.0617540000 26661866 96830484 1764196352 3.7718157768 3.9735155106 3.9168741703 142 1311867175.1625180244 0.0562411770 0.0594314305 0.0637623146 0.0068186703 0.1174690000 0.0095440000 0.0536750000 0.0000280000 0.0002850000 0.0333560000 26664116 96830484 1765978112 3.7708435059 3.9732406139 3.9173178673 143 1311867175.1946399212 0.0561500452 0.0594084838 0.0637623146 0.0067985115 0.0985260000 0.0094480000 0.0367590000 0.0003530000 0.0002700000 0.0433960000 26666270 96830484 1767346176 3.7687306404 3.9729685783 3.9174649715 144 1311867175.2270050049 0.0558357686 0.0593836732 0.0637623146 0.0068484449 0.1352810000 0.0096170000 0.0823840000 0.0000260000 0.0003690000 0.0332480000 26668488 96830484 1769029632 3.7659871578 3.9744989872 3.9180910587 145 1311867175.2624669075 0.0559898168 0.0593602673 0.0637623146 0.0068561267 0.1526350000 0.0113280000 0.0704330000 0.0004770000 0.0002960000 0.0615090000 26670706 96830484 1767878656 3.7666010857 3.9758222103 3.9181618690 146 1311867175.2944509983 0.0558760911 0.0593364031 0.0637623146 0.0068584961 0.1185980000 0.0093870000 0.0644910000 0.0000290000 0.0002870000 0.0333150000 26672892 96830484 1769631744 3.7595336437 3.9758112431 3.9188160896 147 1311867175.3267059326 0.0557256378 0.0593118401 0.0637623146 0.0068369256 0.1174720000 0.0112810000 0.0581510000 0.0007000000 0.0003570000 0.0385550000 26675110 96830484 1768787968 3.7618920803 3.9774940014 3.9195699692 148 1311867175.3625650406 0.0567103922 0.0592942627 0.0637623146 0.0068654671 0.1114180000 0.0095140000 0.0470330000 0.0000290000 0.0007050000 0.0333970000 26677328 96830484 1770520576 3.7564160824 3.9765965939 3.9204461575 149 1311867175.3945989609 0.0564466268 0.0592751511 0.0637623146 0.0068586024 0.1372790000 0.0128240000 0.0405470000 0.0010800000 0.0002780000 0.0621590000 26679514 96830484 1769676800 3.7568736076 3.9759356976 3.9204158783 150 1311867175.4266059399 0.0568188205 0.0592587755 0.0637623146 0.0068461540 0.1157930000 0.0122390000 0.0531810000 0.0000290000 0.0002820000 0.0329690000 26681700 96830484 1768529920 3.7502384186 3.9772160053 3.9211084843 151 1311867175.4625999928 0.0565607436 0.0592409078 0.0637623146 0.0068403977 0.1345670000 0.0095400000 0.0686390000 0.0002930000 0.0002710000 0.0389900000 26683982 96830484 1770299392 3.7487483025 3.9770584106 3.9212725163 152 1311867175.4945731163 0.0569804907 0.0592260366 0.0637623146 0.0068261985 0.1163770000 0.0117200000 0.0477590000 0.0000250000 0.0003620000 0.0333400000 26686168 96830484 1768529920 3.7432615757 3.9772169590 3.9217305183 153 1311867175.5264270306 0.0577893890 0.0592166468 0.0637623146 0.0068294725 0.1559170000 0.0103460000 0.0755360000 0.0003010000 0.0002750000 0.0607850000 26688322 96830484 1768153088 3.7385585308 3.9779481888 3.9220476151 154 1311867175.5625700951 0.0572657287 0.0592039785 0.0637623146 0.0068526989 0.1150680000 0.0095370000 0.0637780000 0.0000900000 0.0002890000 0.0330180000 26690604 96830484 1769885696 3.7367794514 3.9784927368 3.9221847057 155 1311867175.5946640968 0.0581558980 0.0591972166 0.0637623146 0.0068851995 0.1142720000 0.0114100000 0.0431300000 0.0003840000 0.0002800000 0.0401530000 26692758 96830484 1768787968 3.7347514629 3.9798717499 3.9225463867 156 1311867175.6264801025 0.0577339754 0.0591878369 0.0637623146 0.0068923508 0.1318900000 0.0100790000 0.0710690000 0.0000060000 0.0000590000 0.0312650000 26694944 96830484 1768046592 3.7307553291 3.9798586369 3.9227099419 157 1311867175.6624929905 0.0585080162 0.0591835068 0.0637623146 0.0069491710 0.1315930000 0.0102840000 0.0356590000 0.0002970000 0.0003550000 0.0644150000 26697194 96830484 1767153664 3.7309615612 3.9813852310 3.9231460094 158 1311867175.6947000027 0.0583270453 0.0591780862 0.0637623146 0.0069522247 0.1343010000 0.0105190000 0.0699520000 0.0000250000 0.0002840000 0.0330850000 26699380 96830484 1768775680 3.7280740738 3.9804687500 3.9232304096 159 1311867175.7273120880 0.0588257611 0.0591758703 0.0637623146 0.0069417341 0.1001980000 0.0110960000 0.0425170000 0.0007120000 0.0002890000 0.0369030000 26701598 96830484 1767751680 3.7255373001 3.9800338745 3.9235441685 160 1311867175.7624969482 0.0590208694 0.0591749015 0.0637623146 0.0069429318 0.1127080000 0.0095130000 0.0530970000 0.0000280000 0.0004760000 0.0383500000 26703848 96830484 1769504768 3.7214281559 3.9807844162 3.9235267639 161 1311867175.7948620319 0.0592135228 0.0591751414 0.0637623146 0.0069502385 0.1245640000 0.0115450000 0.0421060000 0.0003210000 0.0003590000 0.0614340000 26706002 96830484 1768660992 3.7187018394 3.9798462391 3.9235711098 162 1311867175.8287971020 0.0594074689 0.0591765756 0.0637623146 0.0069404343 0.1046970000 0.0097400000 0.0409270000 0.0000270000 0.0010740000 0.0334870000 26708252 96830484 1770299392 3.7143673897 3.9787166119 3.9233858585 163 1311867175.8625519276 0.0595676675 0.0591789749 0.0637623146 0.0069603497 0.1194300000 0.0118930000 0.0591410000 0.0003700000 0.0002820000 0.0390090000 26710470 96830484 1769295872 3.7129962444 3.9804303646 3.9233570099 164 1311867175.8946080208 0.0598642603 0.0591831535 0.0637623146 0.0069465221 0.1326800000 0.0110380000 0.0698750000 0.0000260000 0.0002860000 0.0332790000 26712624 96830484 1768534016 3.7105150223 3.9806709290 3.9228997231 165 1311867175.9282429218 0.0596055649 0.0591857135 0.0637623146 0.0069474021 0.1305160000 0.0098770000 0.0491600000 0.0003200000 0.0002820000 0.0621670000 26714842 96830484 1770139648 3.7057042122 3.9796178341 3.9223392010 166 1311867175.9629371166 0.0601581931 0.0591915718 0.0637623146 0.0069278820 0.1023560000 0.0115830000 0.0437280000 0.0000290000 0.0003140000 0.0336400000 26717060 96830484 1769041920 3.7028658390 3.9799458981 3.9225265980 167 1311867175.9983000755 0.0602459423 0.0591978854 0.0637623146 0.0069403159 0.1343690000 0.0105400000 0.0686790000 0.0002930000 0.0003420000 0.0394330000 26719278 96830484 1768296448 3.7022917271 3.9811835289 3.9223496914 168 1311867176.0268509388 0.0608684532 0.0592078293 0.0637623146 0.0069264457 0.1144010000 0.0100540000 0.0533280000 0.0000280000 0.0002900000 0.0334290000 26721400 96830484 1769902080 3.6976828575 3.9791688919 3.9221096039 169 1311867176.0627059937 0.0605797619 0.0592159472 0.0637623146 0.0069423670 0.1524520000 0.0114830000 0.0688590000 0.0003100000 0.0004870000 0.0625790000 26723650 96830484 1768914944 3.6929051876 3.9796609879 3.9216229916 170 1311867176.0946600437 0.0614854507 0.0592292973 0.0637623146 0.0069857777 0.1181540000 0.0096740000 0.0548030000 0.0000350000 0.0003000000 0.0335750000 26725804 96830484 1770647552 3.6905159950 3.9806201458 3.9213173389 171 1311867176.1268119812 0.0614754558 0.0592424327 0.0637623146 0.0069683029 0.1192170000 0.0114270000 0.0577160000 0.0003710000 0.0002850000 0.0394400000 26728022 96830484 1769803776 3.6919107437 3.9804301262 3.9204864502 172 1311867176.1625900269 0.0611371621 0.0592534486 0.0637623146 0.0070311923 0.1131350000 0.0112260000 0.0478140000 0.0000930000 0.0003100000 0.0335290000 26730272 96830484 1768124416 3.6886928082 3.9809346199 3.9198942184 173 1311867176.1946918964 0.0615816116 0.0592669061 0.0637623146 0.0070688893 0.1330170000 0.0101510000 0.0518970000 0.0003120000 0.0006230000 0.0609810000 26732458 96830484 1767645184 3.6878571510 3.9812874794 3.9191532135 174 1311867176.2265360355 0.0616400763 0.0592805451 0.0637623146 0.0070495266 0.1192350000 0.0108390000 0.0683860000 0.0000280000 0.0002860000 0.0307030000 26734644 96830484 1766772736 3.6853923798 3.9816877842 3.9187335968 175 1311867176.2625019550 0.0617031716 0.0592943886 0.0637623146 0.0070366040 0.1121170000 0.0095490000 0.0481580000 0.0003010000 0.0002730000 0.0390930000 26736894 96830484 1768488960 3.6818091869 3.9821805954 3.9178681374 176 1311867176.2946109772 0.0621450730 0.0593105857 0.0637623146 0.0070318642 0.1159560000 0.0095210000 0.0548300000 0.0000300000 0.0003020000 0.0337570000 26739048 96830484 1770139648 3.6788411140 3.9842307568 3.9174754620 177 1311867176.3266019821 0.0628553554 0.0593306127 0.0637623146 0.0070220330 0.1358510000 0.0116530000 0.0402570000 0.0002910000 0.0003450000 0.0620690000 26741234 96830484 1769037824 3.6762859821 3.9866404533 3.9171624184 178 1311867176.3624560833 0.0630615279 0.0593515729 0.0637623146 0.0070042253 0.1152220000 0.0105490000 0.0528220000 0.0000250000 0.0003650000 0.0335800000 26743516 96830484 1770807296 3.6752495766 3.9853229523 3.9163496494 179 1311867176.3952438831 0.0632760003 0.0593734970 0.0637623146 0.0069858292 0.1378730000 0.0115190000 0.0728560000 0.0003550000 0.0002820000 0.0393620000 26745670 96830484 1770078208 3.6740674973 3.9867479801 3.9159336090 180 1311867176.4268360138 0.0629471615 0.0593933507 0.0637623146 0.0069716696 0.1136330000 0.0117010000 0.0457900000 0.0000280000 0.0003820000 0.0332160000 26747856 96830484 1767874560 3.6736083031 3.9877173901 3.9151916504 181 1311867176.4629659653 0.0626396015 0.0594112858 0.0637623146 0.0070387842 0.1349750000 0.0103370000 0.0530110000 0.0002880000 0.0074740000 0.0549090000 26750106 96830484 1767387136 3.6711525917 3.9875349998 3.9144010544 182 1311867176.4945809841 0.0635263249 0.0594338959 0.0637623146 0.0070351833 0.1332910000 0.0095980000 0.0695630000 0.0000270000 0.0002830000 0.0336830000 26752260 96830484 1766645760 3.6689031124 3.9874906540 3.9135463238 183 1311867176.5266211033 0.0639283359 0.0594584557 0.0639283359 0.0070924214 0.1153950000 0.0107660000 0.0460930000 0.0002950000 0.0003410000 0.0400620000 26754478 96830484 1768361984 3.6666138172 3.9898157120 3.9128134251 184 1311867176.5636389256 0.0640100166 0.0594831924 0.0640100166 0.0070862306 0.1193130000 0.0092970000 0.0709630000 0.0000280000 0.0003520000 0.0299830000 26756760 96830484 1770012672 3.6648042202 3.9891560078 3.9120657444 185 1311867176.5946090221 0.0641005710 0.0595081512 0.0641005710 0.0070762845 0.1464950000 0.0115500000 0.0637090000 0.0003590000 0.0002710000 0.0616550000 26758914 96830484 1768910848 3.6606233120 3.9890828133 3.9111306667 186 1311867176.6283841133 0.0637375638 0.0595308900 0.0641005710 0.0070663208 0.1233810000 0.0094360000 0.0692550000 0.0000260000 0.0005120000 0.0342580000 26761132 96830484 1770774528 3.6597952843 3.9896109104 3.9103875160 187 1311867176.6625781059 0.0638457239 0.0595539640 0.0641005710 0.0070509458 0.1161390000 0.0113500000 0.0515220000 0.0002970000 0.0002700000 0.0402250000 26763350 96830484 1769930752 3.6565954685 3.9905467033 3.9097454548 188 1311867176.6945180893 0.0632914454 0.0595738442 0.0641005710 0.0070343709 0.1332530000 0.0114920000 0.0671690000 0.0000250000 0.0002860000 0.0335540000 26765504 96830484 1768787968 3.6557383537 3.9907639027 3.9087030888 189 1311867176.7265889645 0.0638218224 0.0595963203 0.0641005710 0.0070174881 0.1515850000 0.0106200000 0.0697330000 0.0003550000 0.0002700000 0.0618870000 26767722 96830484 1770520576 3.6515204906 3.9915661812 3.9083979130 190 1311867176.7632329464 0.0636170432 0.0596174820 0.0641005710 0.0070128436 0.1224580000 0.0116340000 0.0673430000 0.0000280000 0.0003100000 0.0336060000 26769972 96830484 1769693184 3.6508212090 3.9922757149 3.9080388546 191 1311867176.7947680950 0.0634887740 0.0596377505 0.0641005710 0.0070097733 0.1305750000 0.0112970000 0.0634830000 0.0003570000 0.0002750000 0.0398270000 26772126 96830484 1768660992 3.6488192081 3.9922249317 3.9075007439 192 1311867176.8266770840 0.0638324395 0.0596595979 0.0641005710 0.0069921697 0.1339220000 0.0097290000 0.0696800000 0.0000280000 0.0002870000 0.0341340000 26774344 96830484 1770393600 3.6456062794 3.9919981956 3.9071803093 193 1311867176.8627309799 0.0636728555 0.0596803920 0.0641005710 0.0069772314 0.1356590000 0.0124100000 0.0342990000 0.0000910000 0.0000820000 0.0672870000 26776594 96830484 1769549824 3.6438362598 3.9931752682 3.9066398144 194 1311867176.8949549198 0.0640572384 0.0597029530 0.0641005710 0.0069602157 0.1172690000 0.0118340000 0.0620280000 0.0000250000 0.0002910000 0.0338760000 26778780 96830484 1768398848 3.6390554905 3.9933063984 3.9064292908 195 1311867176.9268178940 0.0635102242 0.0597224775 0.0641005710 0.0069616705 0.0966360000 0.0095760000 0.0407660000 0.0002890000 0.0010080000 0.0361530000 26780966 96830484 1770172416 3.6379077435 3.9932651520 3.9060776234 196 1311867176.9650609493 0.0638350025 0.0597434598 0.0641005710 0.0069747373 0.1310820000 0.0109300000 0.0673630000 0.0000280000 0.0002990000 0.0342260000 26783216 96830484 1769414656 3.6357443333 3.9945154190 3.9060745239 197 1311867176.9947481155 0.0638586953 0.0597643493 0.0641005710 0.0069595067 0.1529690000 0.0121840000 0.0693010000 0.0003470000 0.0002680000 0.0615940000 26785370 96830484 1767653376 3.6339538097 3.9948725700 3.9057610035 198 1311867177.0267279148 0.0642172322 0.0597868386 0.0642172322 0.0069447887 0.1360660000 0.0099490000 0.0722910000 0.0000290000 0.0004350000 0.0339540000 26787556 96830484 1769394176 3.6302909851 3.9935727119 3.9055128098 199 1311867177.0626339912 0.0641310215 0.0598086686 0.0642172322 0.0069318069 0.1347270000 0.0113390000 0.0579810000 0.0002980000 0.0006640000 0.0481080000 26789806 96830484 1767399424 3.6300566196 3.9948554039 3.9052631855 200 1311867177.0946850777 0.0639357790 0.0598293042 0.0642172322 0.0069172979 0.0955860000 0.0098180000 0.0392210000 0.0000260000 0.0002960000 0.0355980000 26791992 96830484 1769140224 3.6278071404 3.9950425625 3.9046857357 201 1311867177.1266150475 0.0640558600 0.0598503318 0.0642172322 0.0069023902 0.1730860000 0.0100570000 0.0802840000 0.0002950000 0.0003530000 0.0618130000 26794178 96830484 1770790912 3.6266353130 3.9944016933 3.9045519829 202 1311867177.1627299786 0.0643496886 0.0598726059 0.0643496886 0.0068873192 0.1369160000 0.0125620000 0.0682480000 0.0000280000 0.0003730000 0.0346900000 26796428 96830484 1768796160 3.6237974167 3.9950401783 3.9046199322 203 1311867177.1946458817 0.0644704476 0.0598952554 0.0644704476 0.0068728435 0.1145290000 0.0108500000 0.0459840000 0.0002120000 0.0002440000 0.0407960000 26798614 96830484 1770450944 3.6200630665 3.9958410263 3.9043667316 204 1311867177.2264730930 0.0647448301 0.0599190278 0.0647448301 0.0068568833 0.1185480000 0.0113080000 0.0623500000 0.0000300000 0.0003150000 0.0341520000 26800800 96830484 1769291776 3.6181700230 3.9951097965 3.9039809704 205 1311867177.2638640404 0.0654245540 0.0599458840 0.0654245540 0.0068408529 0.1480380000 0.0112130000 0.0628770000 0.0007010000 0.0002870000 0.0636570000 26803082 96830484 1767899136 3.6150937080 3.9954776764 3.9039092064 206 1311867177.2946178913 0.0648053810 0.0599694738 0.0654245540 0.0068421139 0.1018470000 0.0096470000 0.0457960000 0.0000290000 0.0003100000 0.0341720000 26805236 96830484 1769676800 3.6136002541 3.9953498840 3.9033546448 207 1311867177.3276090622 0.0649021938 0.0599933034 0.0654245540 0.0068260910 0.0980630000 0.0113040000 0.0394150000 0.0003120000 0.0006640000 0.0371170000 26807454 96830484 1765367808 3.6098670959 3.9959831238 3.9029705524 208 1311867177.3627710342 0.0651217774 0.0600179595 0.0654245540 0.0068137174 0.1093210000 0.0096580000 0.0455550000 0.0000960000 0.0003200000 0.0347290000 26809672 96830484 1767133184 3.6091554165 3.9967429638 3.9026799202 209 1311867177.3946089745 0.0656144470 0.0600447369 0.0656144470 0.0068191897 0.1362440000 0.0099560000 0.0459510000 0.0003860000 0.0002920000 0.0650170000 26811858 96830484 1768767488 3.6057763100 3.9963197708 3.9024002552 210 1311867177.4312860966 0.0656707585 0.0600715275 0.0656707585 0.0068062146 0.0961280000 0.0101010000 0.0364520000 0.0000130000 0.0001160000 0.0355660000 26814140 96830484 1770434560 3.6045889854 3.9974062443 3.9021532536 211 1311867177.4626040459 0.0659724995 0.0600994942 0.0659724995 0.0067921572 0.1388020000 0.0126710000 0.0732790000 0.0003780000 0.0002800000 0.0400260000 26816326 96830484 1769672704 3.6014130116 3.9977769852 3.9018731117 212 1311867177.4946429729 0.0657514110 0.0601261542 0.0659724995 0.0067783113 0.1339490000 0.0115670000 0.0693860000 0.0000290000 0.0003100000 0.0342660000 26818512 96830484 1768009728 3.6006693840 3.9982299805 3.9013829231 213 1311867177.5276319981 0.0656745061 0.0601522028 0.0659724995 0.0067653961 0.1274500000 0.0097700000 0.0454460000 0.0003890000 0.0002890000 0.0623820000 26820698 96830484 1769676800 3.5997111797 3.9990282059 3.9009354115 214 1311867177.5626399517 0.0665292144 0.0601820019 0.0665292144 0.0067590858 0.1068810000 0.0109390000 0.0460610000 0.0002610000 0.0003180000 0.0341050000 26822916 96830484 1766141952 3.5979933739 3.9995114803 3.9009373188 215 1311867177.5947310925 0.0662876219 0.0602104001 0.0665292144 0.0067510895 0.1119820000 0.0099740000 0.0410880000 0.0013430000 0.0003700000 0.0408030000 26825102 96830484 1767133184 3.5908534527 3.9986770153 3.8996863365 216 1311867177.6311450005 0.0661071613 0.0602377000 0.0665292144 0.0067361215 0.0955310000 0.0095320000 0.0345340000 0.0000100000 0.0001010000 0.0340000000 26827384 96830484 1766756352 3.5893850327 3.9998819828 3.8990449905 217 1311867177.6624829769 0.0657379627 0.0602630468 0.0665292144 0.0067249114 0.1343220000 0.0097130000 0.0352220000 0.0000830000 0.0000750000 0.0677730000 26829570 96830484 1766268928 3.5891115665 4.0009365082 3.8984315395 218 1311867177.6945610046 0.0663603842 0.0602910162 0.0665292144 0.0067343849 0.1330280000 0.0105230000 0.0694740000 0.0000060000 0.0000600000 0.0347100000 26831756 96830484 1768009728 3.5843605995 4.0008368492 3.8982658386 219 1311867177.7305839062 0.0660203546 0.0603171776 0.0665292144 0.0067244804 0.1179570000 0.0094220000 0.0579400000 0.0003860000 0.0002770000 0.0399810000 26833974 96830484 1769512960 3.5847077370 4.0025696754 3.8975591660 220 1311867177.7625379562 0.0661658645 0.0603437625 0.0665292144 0.0067159106 0.0950370000 0.0112210000 0.0299870000 0.0000240000 0.0002620000 0.0355800000 26836160 96830484 1766973440 3.5852539539 4.0025892258 3.8971502781 221 1311867177.7945590019 0.0663686916 0.0603710247 0.0665292144 0.0067025393 0.1328340000 0.0110250000 0.0506160000 0.0003090000 0.0002790000 0.0611890000 26838346 96830484 1767141376 3.5823676586 4.0026450157 3.8963432312 222 1311867177.8309149742 0.0668215454 0.0604000811 0.0668215454 0.0066930936 0.1147170000 0.0097990000 0.0457960000 0.0000280000 0.0003180000 0.0335070000 26840596 96830484 1766379520 3.5798511505 4.0027055740 3.8955886364 223 1311867177.8625319004 0.0664227679 0.0604270886 0.0668215454 0.0066818840 0.1353440000 0.0102360000 0.0664880000 0.0003910000 0.0002820000 0.0397860000 26842782 96830484 1768005632 3.5812187195 4.0029282570 3.8948266506 224 1311867177.8946919441 0.0670675561 0.0604567336 0.0670675561 0.0066678777 0.1175810000 0.0094510000 0.0624340000 0.0000300000 0.0003880000 0.0329110000 26844936 96830484 1769766912 3.5780754089 4.0037851334 3.8946011066 225 1311867177.9317860603 0.0672896206 0.0604871020 0.0672896206 0.0066543299 0.1289370000 0.0112010000 0.0468550000 0.0003210000 0.0003590000 0.0607760000 26847250 96830484 1769066496 3.5761101246 4.0039243698 3.8938615322 226 1311867177.9627909660 0.0671489984 0.0605165794 0.0672896206 0.0066446479 0.1085400000 0.0095360000 0.0485920000 0.0000290000 0.0003050000 0.0404200000 26849404 96830484 1770676224 3.5764534473 4.0040411949 3.8928003311 227 1311867177.9947769642 0.0671435222 0.0605457730 0.0672896206 0.0066367270 0.1163300000 0.0111120000 0.0581910000 0.0003840000 0.0002870000 0.0367250000 26851526 96830484 1769553920 3.5750443935 4.0059514046 3.8919975758 228 1311867178.0306100845 0.0675451159 0.0605764718 0.0675451159 0.0066227425 0.0933430000 0.0115020000 0.0341980000 0.0000280000 0.0003100000 0.0346240000 26853776 96830484 1768136704 3.5720865726 4.0055036545 3.8913946152 229 1311867178.0634479523 0.0674151927 0.0606063352 0.0675451159 0.0066097360 0.1531550000 0.0097790000 0.0619440000 0.0003100000 0.0004690000 0.0607150000 26855962 96830484 1769824256 3.5727720261 4.0046920776 3.8906614780 230 1311867178.0951139927 0.0672140270 0.0606350643 0.0675451159 0.0065965165 0.1165020000 0.0123000000 0.0510980000 0.0000310000 0.0003040000 0.0334790000 26858148 96830484 1768787968 3.5705289841 4.0065832138 3.8900518417 231 1311867178.1307909489 0.0682805926 0.0606681619 0.0682805926 0.0065907884 0.1161650000 0.0097170000 0.0527630000 0.0003080000 0.0003590000 0.0392920000 26860398 96830484 1770418176 3.5651137829 4.0054240227 3.8899219036 232 1311867178.1627469063 0.0685650110 0.0607022000 0.0685650110 0.0066036614 0.1347040000 0.0112750000 0.0678440000 0.0000280000 0.0003100000 0.0335970000 26862584 96830484 1769680896 3.5633716583 4.0051388741 3.8894445896 233 1311867178.1950459480 0.0680682659 0.0607338140 0.0685650110 0.0066043262 0.1363530000 0.0144100000 0.0402260000 0.0003020000 0.0003520000 0.0643360000 26864738 96830484 1768284160 3.5645210743 4.0070977211 3.8889865875 234 1311867178.2307190895 0.0686119199 0.0607674811 0.0686119199 0.0065920022 0.1148350000 0.0098480000 0.0565430000 0.0000300000 0.0005560000 0.0336010000 26866988 96830484 1770045440 3.5600490570 4.0057764053 3.8884720802 235 1311867178.2628939152 0.0680804476 0.0607986001 0.0686119199 0.0065801515 0.1165640000 0.0115290000 0.0524940000 0.0003020000 0.0003540000 0.0395410000 26869206 96830484 1768923136 3.5596199036 4.0057301521 3.8878908157 236 1311867178.2954900265 0.0680062324 0.0608291410 0.0686119199 0.0065691433 0.1142430000 0.0097990000 0.0568500000 0.0000270000 0.0003060000 0.0336920000 26871392 96830484 1770569728 3.5570046902 4.0072550774 3.8876776695 237 1311867178.3306670189 0.0683264211 0.0608607750 0.0686119199 0.0065620061 0.1508410000 0.0113600000 0.0392960000 0.0006900000 0.0002920000 0.0625220000 26873610 96830484 1769431040 3.5543251038 4.0054516792 3.8875546455 238 1311867178.3627231121 0.0674279481 0.0608883682 0.0686119199 0.0065509031 0.1195390000 0.0118830000 0.0593640000 0.0000250000 0.0002900000 0.0382780000 26875828 96830484 1768300544 3.5551981926 4.0064563751 3.8870701790 239 1311867178.3949439526 0.0675423443 0.0609162091 0.0686119199 0.0065391332 0.1543270000 0.0097020000 0.0882030000 0.0002970000 0.0003440000 0.0463360000 26877982 96830484 1770061824 3.5520315170 4.0068793297 3.8868806362 240 1311867178.4306581020 0.0680461228 0.0609459171 0.0686119199 0.0065414876 0.1350610000 0.0115010000 0.0717900000 0.0000260000 0.0002850000 0.0382760000 26880232 96830484 1768939520 3.5487389565 4.0072102547 3.8871855736 241 1311867178.4628739357 0.0684089139 0.0609768839 0.0686119199 0.0065285147 0.1666880000 0.0106860000 0.0844820000 0.0002830000 0.0003310000 0.0612810000 26882418 96830484 1768177664 3.5463647842 4.0077605247 3.8873956203 242 1311867178.4946439266 0.0685336143 0.0610081100 0.0686119199 0.0065167534 0.1035410000 0.0092690000 0.0511380000 0.0000260000 0.0003620000 0.0334400000 26884604 96830484 1769893888 3.5441472530 4.0067539215 3.8874106407 243 1311867178.5306270123 0.0680693984 0.0610371688 0.0686119199 0.0065188558 0.1349270000 0.0113940000 0.0678750000 0.0003670000 0.0002700000 0.0400910000 26886854 96830484 1768796160 3.5441756248 4.0082988739 3.8871607780 244 1311867178.5626420975 0.0688551590 0.0610692098 0.0688551590 0.0065064549 0.1139600000 0.0098270000 0.0518530000 0.0000280000 0.0002870000 0.0336110000 26889072 96830484 1770426368 3.5406527519 4.0083012581 3.8876481056 245 1311867178.5947000980 0.0687497929 0.0611005591 0.0688551590 0.0065048401 0.1346620000 0.0116220000 0.0514620000 0.0003580000 0.0002760000 0.0613620000 26891258 96830484 1769050112 3.5400869846 4.0073423386 3.8874177933 246 1311867178.6306900978 0.0690522715 0.0611328831 0.0690522715 0.0065024985 0.1191440000 0.0108850000 0.0670030000 0.0000270000 0.0002950000 0.0312400000 26893476 96830484 1767895040 3.5375957489 4.0081405640 3.8873083591 247 1311867178.6626410484 0.0686505809 0.0611633192 0.0690522715 0.0065116743 0.1330060000 0.0095540000 0.0688100000 0.0003040000 0.0003640000 0.0416710000 26895694 96830484 1769656320 3.5373427868 4.0093216896 3.8871252537 248 1311867178.6946120262 0.0694235116 0.0611966264 0.0694235116 0.0065022389 0.1339770000 0.0114520000 0.0675020000 0.0000280000 0.0002980000 0.0333810000 26897848 96830484 1768296448 3.5340752602 4.0074615479 3.8871688843 249 1311867178.7307450771 0.0692439824 0.0612289451 0.0694235116 0.0064991915 0.1535350000 0.0096640000 0.0575090000 0.0003040000 0.0003580000 0.0641220000 26900098 96830484 1770012672 3.5332894325 4.0090246201 3.8867695332 250 1311867178.7632350922 0.0690544695 0.0612602472 0.0694235116 0.0064919071 0.1167490000 0.0128330000 0.0463670000 0.0000290000 0.0003100000 0.0336510000 26902316 96830484 1768505344 3.5327327251 4.0094408989 3.8864519596 251 1311867178.8006799221 0.0694094226 0.0612927140 0.0694235116 0.0064870473 0.0943880000 0.0099130000 0.0406390000 0.0003990000 0.0002830000 0.0332610000 26904566 96830484 1767772160 3.5304381847 4.0075979233 3.8862307072 252 1311867178.8309500217 0.0693724975 0.0613247767 0.0694235116 0.0064834489 0.1343900000 0.0095120000 0.0720030000 0.0000060000 0.0000590000 0.0299070000 26906720 96830484 1767010304 3.5294017792 4.0098986626 3.8861076832 253 1311867178.8627939224 0.0692077875 0.0613559348 0.0694235116 0.0064821337 0.1338820000 0.0101000000 0.0520820000 0.0003760000 0.0002850000 0.0611390000 26908938 96830484 1764950016 3.5293381214 4.0097508430 3.8858120441 254 1311867178.8952279091 0.0700111464 0.0613900104 0.0700111464 0.0064830122 0.1157930000 0.0095640000 0.0626660000 0.0000310000 0.0003040000 0.0331910000 26911124 96830484 1766711296 3.5275568962 4.0066156387 3.8856055737 255 1311867178.9306209087 0.0694753826 0.0614217178 0.0700111464 0.0064804958 0.1348910000 0.0096180000 0.0681850000 0.0003120000 0.0002740000 0.0393750000 26913342 96830484 1768361984 3.5293760300 4.0092391968 3.8845448494 256 1311867178.9627609253 0.0692568347 0.0614523237 0.0700111464 0.0064775131 0.0972160000 0.0098150000 0.0406980000 0.0000280000 0.0010670000 0.0334860000 26915560 96830484 1770045440 3.5293979645 4.0094809532 3.8837325573 257 1311867178.9946830273 0.0698282421 0.0614849148 0.0700111464 0.0064759851 0.1555460000 0.0112110000 0.0622990000 0.0003090000 0.0002750000 0.0644380000 26938226 96830484 1769295872 3.5236206055 4.0086231232 3.8831598759 258 1311867179.0309159756 0.0699310824 0.0615176519 0.0700111464 0.0065136487 0.1116570000 0.0113730000 0.0470740000 0.0000270000 0.0003040000 0.0335980000 26982460 96830484 1768550400 3.5218319893 4.0100965500 3.8826386929 259 1311867179.0628120899 0.0696294606 0.0615489716 0.0700111464 0.0065080055 0.1156540000 0.0096030000 0.0515120000 0.0003060000 0.0002810000 0.0395470000 26984678 96830484 1770172416 3.5223672390 4.0088915825 3.8817946911 260 1311867179.0968201160 0.0710006356 0.0615853242 0.0710006356 0.0066053010 0.1341760000 0.0114130000 0.0673680000 0.0000270000 0.0003640000 0.0331170000 26986864 96830484 1769037824 3.5176782608 4.0057716370 3.8812882900 261 1311867179.1310369968 0.0698549002 0.0616170084 0.0710006356 0.0065938795 0.1508510000 0.0117420000 0.0677750000 0.0003100000 0.0003530000 0.0607360000 26989050 96830484 1768132608 3.5213236809 4.0081877708 3.8799612522 262 1311867179.1627540588 0.0705292448 0.0616510246 0.0710006356 0.0065991254 0.1185820000 0.0091840000 0.0527060000 0.0000300000 0.0003180000 0.0336410000 26991236 96830484 1769656320 3.5195739269 4.0068998337 3.8787481785 263 1311867179.1957008839 0.0707279444 0.0616855376 0.0710006356 0.0065921435 0.1163900000 0.0119440000 0.0454680000 0.0003140000 0.0002780000 0.0402550000 26993422 96830484 1768280064 3.5146007538 4.0059132576 3.8772358894 264 1311867179.2307469845 0.0709180608 0.0617205092 0.0710006356 0.0066538816 0.1338160000 0.0091690000 0.0670040000 0.0000300000 0.0005340000 0.0337120000 26995640 96830484 1770012672 3.5122580528 4.0098524094 3.8764541149 265 1311867179.2634611130 0.0707891062 0.0617547304 0.0710006356 0.0066536047 0.1316800000 0.0125010000 0.0465900000 0.0003890000 0.0002760000 0.0620100000 26997890 96830484 1768914944 3.5105204582 4.0080900192 3.8755242825 266 1311867179.2959330082 0.0705926716 0.0617879557 0.0710006356 0.0066454402 0.1203480000 0.0098630000 0.0605980000 0.0000200000 0.0002030000 0.0333360000 27000044 96830484 1770520576 3.5091199875 4.0076498985 3.8746969700 267 1311867179.3307149410 0.0698551908 0.0618181701 0.0710006356 0.0066351568 0.1188320000 0.0113910000 0.0569260000 0.0003130000 0.0005330000 0.0397810000 27002262 96830484 1769549824 3.5115449429 4.0090861320 3.8739588261 268 1311867179.3629300594 0.0700643882 0.0618489395 0.0710006356 0.0066255403 0.1323080000 0.0108280000 0.0677660000 0.0000290000 0.0002920000 0.0333140000 27004512 96830484 1768804352 3.5092070103 4.0090994835 3.8736529350 269 1311867179.3948490620 0.0700306892 0.0618793550 0.0710006356 0.0066187008 0.1480030000 0.0092900000 0.0667600000 0.0002990000 0.0002770000 0.0616240000 27006634 96830484 1770393600 3.5078504086 4.0077915192 3.8731811047 270 1311867179.4308040142 0.0698200017 0.0619087648 0.0710006356 0.0066325830 0.1058990000 0.0116530000 0.0466020000 0.0000290000 0.0003090000 0.0331460000 27008916 96830484 1766850560 3.5059602261 4.0100646019 3.8730967045 271 1311867179.4637460709 0.0702280477 0.0619394632 0.0710006356 0.0066277067 0.1118130000 0.0097160000 0.0449290000 0.0003220000 0.0002800000 0.0405520000 27011134 96830484 1768042496 3.5042252541 4.0106930733 3.8735466003 272 1311867179.4949469566 0.0700365379 0.0619692319 0.0710006356 0.0066375726 0.1142330000 0.0094500000 0.0513360000 0.0000260000 0.0003700000 0.0342220000 27013288 96830484 1767284736 3.5042927265 4.0098156929 3.8731691837 273 1311867179.5307800770 0.0696864203 0.0619975000 0.0710006356 0.0066353737 0.1375470000 0.0107390000 0.0566980000 0.0002920000 0.0002650000 0.0595950000 27015538 96830484 1765736448 3.5044460297 4.0127339363 3.8731729984 274 1311867179.5627610683 0.0698376223 0.0620261136 0.0710006356 0.0066482472 0.1128850000 0.0091340000 0.0607850000 0.0000260000 0.0003680000 0.0324490000 27017724 96830484 1764978688 3.5030174255 4.0125737190 3.8732881546 275 1311867179.5946741104 0.0701818690 0.0620557708 0.0710006356 0.0066402865 0.1114940000 0.0097480000 0.0443500000 0.0003200000 0.0002830000 0.0399720000 27019910 96830484 1764978688 3.5011115074 4.0130467415 3.8734688759 276 1311867179.6306900978 0.0699935108 0.0620845308 0.0710006356 0.0066539106 0.1150060000 0.0093940000 0.0563120000 0.0000270000 0.0002900000 0.0340010000 27022128 96830484 1766617088 3.5014405251 4.0146870613 3.8734390736 277 1311867179.6625750065 0.0703672841 0.0621144324 0.0710006356 0.0066500256 0.1543350000 0.0093620000 0.0613990000 0.0003620000 0.0002840000 0.0620050000 27024346 96830484 1768361984 3.5010972023 4.0135817528 3.8736336231 278 1311867179.6946051121 0.0705588236 0.0621448079 0.0710006356 0.0066527024 0.0978640000 0.0094240000 0.0409360000 0.0000290000 0.0007150000 0.0343410000 27026500 96830484 1770012672 3.4995074272 4.0149369240 3.8738584518 279 1311867179.7309470177 0.0708470866 0.0621759989 0.0710006356 0.0066433374 0.1360200000 0.0111410000 0.0678940000 0.0003620000 0.0002720000 0.0396420000 27028782 96830484 1769164800 3.4995665550 4.0147528648 3.8740942478 280 1311867179.7627270222 0.0705421418 0.0622058780 0.0710006356 0.0066623079 0.1334140000 0.0108940000 0.0673810000 0.0000270000 0.0003130000 0.0337130000 27030968 96830484 1768132608 3.4989159107 4.0136337280 3.8738248348 281 1311867179.7948911190 0.0700582340 0.0622338223 0.0710006356 0.0066786502 0.1539400000 0.0100590000 0.0609860000 0.0002920000 0.0003470000 0.0618130000 27033122 96830484 1769885696 3.4987862110 4.0156526566 3.8736922741 282 1311867179.8307530880 0.0700020343 0.0622613691 0.0710006356 0.0066693442 0.1171940000 0.0120330000 0.0554780000 0.0000300000 0.0002960000 0.0336170000 27035404 96830484 1769058304 3.4991943836 4.0164437294 3.8739211559 283 1311867179.8627979755 0.0706371740 0.0622909656 0.0710006356 0.0066629368 0.1137760000 0.0092260000 0.0461010000 0.0003920000 0.0002870000 0.0400580000 27037590 96830484 1770680320 3.4966413975 4.0143284798 3.8743147850 284 1311867179.8948040009 0.0704804286 0.0623198018 0.0710006356 0.0066531811 0.1152270000 0.0115370000 0.0465270000 0.0000270000 0.0003240000 0.0345250000 27039776 96830484 1769676800 3.4976284504 4.0144047737 3.8744289875 285 1311867179.9309051037 0.0706815422 0.0623491412 0.0710006356 0.0066792412 0.1539330000 0.0115760000 0.0561080000 0.0003060000 0.0003520000 0.0640890000 27042026 96830484 1768914944 3.4962062836 4.0177121162 3.8750255108 286 1311867179.9635379314 0.0707716718 0.0623785906 0.0710006356 0.0066799837 0.1144480000 0.0101440000 0.0520380000 0.0000270000 0.0003570000 0.0336060000 27044244 96830484 1770393600 3.4952375889 4.0160088539 3.8751451969 287 1311867179.9958879948 0.0708429664 0.0624080832 0.0710006356 0.0066730453 0.1170010000 0.0115330000 0.0459560000 0.0003910000 0.0002850000 0.0403990000 27046398 96830484 1769168896 3.4934868813 4.0161042213 3.8754050732 288 1311867180.0309770107 0.0707237497 0.0624369571 0.0710006356 0.0066705951 0.1146900000 0.0107320000 0.0505450000 0.0000870000 0.0002970000 0.0339560000 27048648 96830484 1768407040 3.4942007065 4.0186934471 3.8759317398 289 1311867180.0626471043 0.0710996017 0.0624669316 0.0710996017 0.0066605388 0.1329730000 0.0095700000 0.0508520000 0.0002930000 0.0002740000 0.0618170000 27050834 96830484 1770012672 3.4932425022 4.0174779892 3.8761003017 290 1311867180.0947730541 0.0712055787 0.0624970649 0.0712055787 0.0066502862 0.1208310000 0.0113760000 0.0673650000 0.0000260000 0.0002870000 0.0315210000 27052988 96830484 1768914944 3.4899144173 4.0181670189 3.8759219646 291 1311867180.1307730675 0.0713937134 0.0625276375 0.0713937134 0.0066469165 0.1327550000 0.0095260000 0.0686570000 0.0002880000 0.0003370000 0.0394390000 27055238 96830484 1770680320 3.4924986362 4.0176744461 3.8759143353 292 1311867180.1636900902 0.0711831152 0.0625572796 0.0713937134 0.0066625490 0.1126380000 0.0112920000 0.0461740000 0.0000250000 0.0003170000 0.0341720000 27057488 96830484 1769267200 3.4947385788 4.0178790092 3.8757183552 293 1311867180.1949090958 0.0708970428 0.0625857429 0.0713937134 0.0066523368 0.1549460000 0.0120430000 0.0575200000 0.0002960000 0.0002670000 0.0627690000 27059610 96830484 1768534016 3.4946911335 4.0175962448 3.8749988079 294 1311867180.2308139801 0.0702919289 0.0626119545 0.0713937134 0.0066488476 0.1339900000 0.0097850000 0.0677430000 0.0000280000 0.0002900000 0.0331290000 27061828 96830484 1770266624 3.4960999489 4.0179114342 3.8739459515 295 1311867180.2637619972 0.0697340593 0.0626360972 0.0713937134 0.0066675591 0.1170890000 0.0120490000 0.0460590000 0.0002940000 0.0003420000 0.0397620000 27064046 96830484 1769439232 3.4968631268 4.0184206963 3.8730735779 296 1311867180.2947549820 0.0702406019 0.0626617881 0.0713937134 0.0066565335 0.1341030000 0.0108400000 0.0668420000 0.0000280000 0.0003090000 0.0334880000 27066200 96830484 1768259584 3.4951965809 4.0175948143 3.8729951382 297 1311867180.3308670521 0.0701146275 0.0626868818 0.0713937134 0.0066474802 0.1490330000 0.0099460000 0.0667260000 0.0003530000 0.0002700000 0.0614810000 27068450 96830484 1770139648 3.4951694012 4.0186805725 3.8725094795 298 1311867180.3658289909 0.0701224655 0.0627118334 0.0713937134 0.0066461973 0.1226580000 0.0113500000 0.0525870000 0.0000300000 0.0002910000 0.0334200000 27070668 96830484 1769295872 3.4949319363 4.0190315247 3.8720316887 299 1311867180.3964109421 0.0704028457 0.0627375559 0.0713937134 0.0066359108 0.1349440000 0.0109760000 0.0659550000 0.0003900000 0.0002860000 0.0417840000 27072854 96830484 1767878656 3.4965951443 4.0194196701 3.8720247746 300 1311867180.4309151173 0.0711429715 0.0627655739 0.0713937134 0.0066255905 0.1744670000 0.0088300000 0.1038800000 0.0000070000 0.0000630000 0.0439690000 27075072 96830484 1769631744 3.4936192036 4.0180859566 3.8717272282 301 1311867180.4670670033 0.0708465651 0.0627924211 0.0713937134 0.0066204095 0.1468550000 0.0114610000 0.0626370000 0.0002930000 0.0003400000 0.0617840000 27077322 96830484 1768804352 3.4948379993 4.0195388794 3.8713576794 302 1311867180.4947559834 0.0711042956 0.0628199439 0.0713937134 0.0066200070 0.1068880000 0.0092460000 0.0567670000 0.0000260000 0.0002870000 0.0305910000 27079412 96830484 1770520576 3.4960315228 4.0189747810 3.8712575436 303 1311867180.5308880806 0.0704975724 0.0628452826 0.0713937134 0.0066092595 0.1343100000 0.0111890000 0.0681170000 0.0002990000 0.0003430000 0.0395230000 27081694 96830484 1769422848 3.4982714653 4.0194020271 3.8709392548 304 1311867180.5629510880 0.0711205006 0.0628725037 0.0713937134 0.0065988956 0.1336900000 0.0107420000 0.0692800000 0.0000270000 0.0003760000 0.0333470000 27083880 96830484 1768660992 3.4972097874 4.0197362900 3.8713810444 305 1311867180.5946910381 0.0711788237 0.0628997375 0.0713937134 0.0065899943 0.1514680000 0.0104550000 0.0685540000 0.0003560000 0.0002790000 0.0614850000 27086066 96830484 1770266624 3.4972016811 4.0201354027 3.8715507984 306 1311867180.6308128834 0.0709988847 0.0629262053 0.0713937134 0.0065806055 0.1198290000 0.0111910000 0.0575150000 0.0000270000 0.0002850000 0.0328330000 27088316 96830484 1769168896 3.4985709190 4.0193586349 3.8717198372 307 1311867180.6640911102 0.0706930831 0.0629515046 0.0713937134 0.0065851353 0.0992900000 0.0106890000 0.0388760000 0.0002930000 0.0003460000 0.0385030000 27090502 96830484 1766219776 3.4991049767 4.0203566551 3.8718855381 308 1311867180.6957859993 0.0708906353 0.0629772810 0.0713937134 0.0065749812 0.1295100000 0.0100240000 0.0693530000 0.0000370000 0.0003190000 0.0345410000 27092688 96830484 1767010304 3.5000216961 4.0190958977 3.8722562790 309 1311867180.7309739590 0.0704931021 0.0630016040 0.0713937134 0.0065691919 0.1926150000 0.0090070000 0.1033920000 0.0000610000 0.0000560000 0.0696670000 27094938 96830484 1765867520 3.5011579990 4.0202908516 3.8721845150 310 1311867180.7650830746 0.0707636401 0.0630266429 0.0713937134 0.0065697421 0.1190530000 0.0097400000 0.0673770000 0.0000280000 0.0002840000 0.0313140000 27097156 96830484 1767473152 3.5025782585 4.0198850632 3.8722822666 311 1311867180.7949280739 0.0710646212 0.0630524884 0.0713937134 0.0065593557 0.0982860000 0.0091670000 0.0391440000 0.0003660000 0.0002760000 0.0391300000 27099278 96830484 1769156608 3.5027110577 4.0197920799 3.8726770878 312 1311867180.8309240341 0.0713080093 0.0630789485 0.0713937134 0.0065496860 0.1138040000 0.0109490000 0.0584460000 0.0000270000 0.0002910000 0.0329390000 27101560 96830484 1768300544 3.5032210350 4.0210433006 3.8731234074 313 1311867180.8652698994 0.0712479129 0.0631050474 0.0713937134 0.0065476955 0.1362180000 0.0095940000 0.0559240000 0.0003160000 0.0006850000 0.0594400000 27103778 96830484 1769758720 3.5036246777 4.0196661949 3.8732235432 314 1311867180.8966469765 0.0707930326 0.0631295314 0.0713937134 0.0065377764 0.1331780000 0.0111350000 0.0631480000 0.0000270000 0.0002870000 0.0329990000 27105964 96830484 1768787968 3.5059995651 4.0206804276 3.8730163574 315 1311867180.9306049347 0.0712864920 0.0631554265 0.0713937134 0.0065460076 0.0977960000 0.0097530000 0.0338020000 0.0000970000 0.0000730000 0.0416850000 27108182 96830484 1770393600 3.5051949024 4.0202980042 3.8733456135 316 1311867180.9631829262 0.0714161173 0.0631815679 0.0714161173 0.0065458183 0.1174940000 0.0135420000 0.0558440000 0.0000300000 0.0003170000 0.0365430000 27110368 96830484 1769275392 3.5056848526 4.0206160545 3.8732697964 317 1311867180.9948179722 0.0709248185 0.0632059946 0.0714161173 0.0065398621 0.1659130000 0.0100120000 0.0816680000 0.0003710000 0.0002910000 0.0629520000 27112522 96830484 1768550400 3.5097935200 4.0210986137 3.8735995293 318 1311867181.0308310986 0.0711913556 0.0632311058 0.0714161173 0.0065307642 0.1219030000 0.0093530000 0.0685350000 0.0000280000 0.0002890000 0.0330040000 27114772 96830484 1770172416 3.5111255646 4.0195555687 3.8737792969 319 1311867181.0627830029 0.0717672706 0.0632578649 0.0717672706 0.0065282079 0.1136790000 0.0113230000 0.0407760000 0.0003560000 0.0010560000 0.0398740000 27116990 96830484 1769168896 3.5129475594 4.0192213058 3.8740537167 320 1311867181.0948719978 0.0709318295 0.0632818461 0.0717672706 0.0065259183 0.1340140000 0.0113780000 0.0685800000 0.0000270000 0.0002900000 0.0328040000 27119176 96830484 1768407040 3.5157294273 4.0196757317 3.8740193844 321 1311867181.1311910152 0.0695094988 0.0633012469 0.0717672706 0.0065217585 0.1499000000 0.0099880000 0.0681160000 0.0002920000 0.0003570000 0.0608450000 27121426 96830484 1770012672 3.5210711956 4.0207281113 3.8733963966 322 1311867181.1629528999 0.0706409067 0.0633240408 0.0717672706 0.0065290111 0.1201710000 0.0113570000 0.0573930000 0.0000270000 0.0002900000 0.0323300000 27123612 96830484 1768914944 3.5206394196 4.0192613602 3.8737661839 323 1311867181.1972830296 0.0703893527 0.0633459149 0.0717672706 0.0065196136 0.1142960000 0.0095070000 0.0460340000 0.0003970000 0.0006050000 0.0398370000 27125830 96830484 1770520576 3.5219876766 4.0196213722 3.8735258579 324 1311867181.2342460155 0.0703274682 0.0633674629 0.0717672706 0.0065108388 0.0974690000 0.0114900000 0.0341500000 0.0000070000 0.0000770000 0.0340290000 27128112 96830484 1766465536 3.5248498917 4.0186262131 3.8732662201 325 1311867181.2629361153 0.0709365234 0.0633907523 0.0717672706 0.0065021518 0.1488980000 0.0102970000 0.0556140000 0.0003000000 0.0002720000 0.0596440000 27130234 96830484 1768153088 3.5251879692 4.0185580254 3.8736140728 326 1311867181.2948091030 0.0700902343 0.0634113029 0.0717672706 0.0064929554 0.1135840000 0.0101840000 0.0468850000 0.0000280000 0.0003150000 0.0326380000 27132388 96830484 1769791488 3.5288312435 4.0198993683 3.8733696938 327 1311867181.3317139149 0.0704307035 0.0634327689 0.0717672706 0.0064892027 0.0979600000 0.0124910000 0.0297040000 0.0000790000 0.0000720000 0.0412130000 27134670 96830484 1765601280 3.5285160542 4.0194005966 3.8733398914 328 1311867181.3626708984 0.0698893145 0.0634524535 0.0717672706 0.0064913035 0.1124410000 0.0100540000 0.0516770000 0.0000300000 0.0002920000 0.0326050000 27136824 96830484 1767407616 3.5319316387 4.0219264030 3.8736972809 329 1311867181.3948218822 0.0699930787 0.0634723338 0.0717672706 0.0064830269 0.1514700000 0.0093970000 0.0547260000 0.0002900000 0.0002800000 0.0562130000 27139010 96830484 1769123840 3.5320043564 4.0200977325 3.8735401630 330 1311867181.4308950901 0.0701649338 0.0634926144 0.0717672706 0.0064741960 0.1225350000 0.0119770000 0.0657250000 0.0000300000 0.0003750000 0.0336760000 27141196 96830484 1768280064 3.5330877304 4.0198035240 3.8736763000 331 1311867181.4628310204 0.0702327564 0.0635129774 0.0717672706 0.0064679524 0.1276940000 0.0093450000 0.0680910000 0.0003640000 0.0003700000 0.0366960000 27143382 96830484 1769918464 3.5357558727 4.0197482109 3.8742618561 332 1311867181.4963610172 0.0693652257 0.0635306046 0.0717672706 0.0064763280 0.1512950000 0.0112910000 0.0764150000 0.0000300000 0.0003560000 0.0384110000 27145600 96830484 1768914944 3.5391726494 4.0199728012 3.8742024899 333 1311867181.5359110832 0.0696174279 0.0635488834 0.0717672706 0.0064700295 0.1395240000 0.0097720000 0.0588550000 0.0003660000 0.0002770000 0.0598420000 27147882 96830484 1770647552 3.5405766964 4.0191264153 3.8741695881 334 1311867181.5671720505 0.0696075484 0.0635670231 0.0717672706 0.0064652018 0.1330860000 0.0111640000 0.0689770000 0.0000280000 0.0003010000 0.0324960000 27150036 96830484 1769803776 3.5412924290 4.0182733536 3.8736231327 335 1311867181.5948610306 0.0697766542 0.0635855593 0.0717672706 0.0064617900 0.1172390000 0.0121570000 0.0511330000 0.0003030000 0.0002810000 0.0392460000 27152126 96830484 1768660992 3.5423774719 4.0196743011 3.8738481998 336 1311867181.6313591003 0.0696007684 0.0636034617 0.0717672706 0.0064618069 0.0939080000 0.0095110000 0.0353360000 0.0000270000 0.0003730000 0.0342830000 27154408 96830484 1770266624 3.5450086594 4.0186944008 3.8735835552 337 1311867181.6628570557 0.0703723878 0.0636235476 0.0717672706 0.0064591558 0.1294880000 0.0116290000 0.0470390000 0.0003820000 0.0002860000 0.0594160000 27156594 96830484 1769295872 3.5448942184 4.0164575577 3.8732776642 338 1311867181.6949229240 0.0695089102 0.0636409599 0.0717672706 0.0064547424 0.1041180000 0.0108600000 0.0484950000 0.0000280000 0.0002970000 0.0326390000 27158748 96830484 1766719488 3.5475244522 4.0184836388 3.8727977276 339 1311867181.7310829163 0.0701479763 0.0636601546 0.0717672706 0.0064565279 0.1329170000 0.0096200000 0.0726620000 0.0003130000 0.0003500000 0.0384740000 27160998 96830484 1766756352 3.5503098965 4.0167884827 3.8725662231 340 1311867181.7634840012 0.0705329925 0.0636803688 0.0717672706 0.0064470842 0.1320750000 0.0094730000 0.0698500000 0.0000300000 0.0003030000 0.0319770000 27163216 96830484 1765740544 3.5492286682 4.0150628090 3.8720889091 341 1311867181.7948980331 0.0694961175 0.0636974238 0.0717672706 0.0064438584 0.1329940000 0.0101020000 0.0522640000 0.0003010000 0.0002830000 0.0593630000 27165338 96830484 1767378944 3.5535428524 4.0164198875 3.8713910580 342 1311867181.8308010101 0.0697663277 0.0637151692 0.0717672706 0.0064388999 0.1205020000 0.0093500000 0.0688070000 0.0000290000 0.0004850000 0.0313380000 27167588 96830484 1769123840 3.5544953346 4.0149269104 3.8714003563 343 1311867181.8627979755 0.0687764511 0.0637299251 0.0717672706 0.0064324723 0.1134510000 0.0110300000 0.0421400000 0.0003180000 0.0003550000 0.0387280000 27169806 96830484 1768005632 3.5573902130 4.0146226883 3.8711020947 344 1311867181.8949289322 0.0686112419 0.0637441150 0.0717672706 0.0064256066 0.1336200000 0.0098290000 0.0688890000 0.0000260000 0.0020590000 0.0323870000 27171960 96830484 1769758720 3.5599963665 4.0155749321 3.8712689877 345 1311867181.9307990074 0.0685176626 0.0637579513 0.0717672706 0.0064208241 0.1507760000 0.0117730000 0.0687900000 0.0002980000 0.0002780000 0.0587100000 27174242 96830484 1769062400 3.5611429214 4.0142407417 3.8708477020 346 1311867181.9629189968 0.0694903135 0.0637745189 0.0717672706 0.0064202191 0.1004960000 0.0093750000 0.0455410000 0.0000280000 0.0003910000 0.0318080000 27176428 96830484 1770647552 3.5600376129 4.0142107010 3.8714463711 347 1311867181.9955599308 0.0693318099 0.0637905341 0.0717672706 0.0064382181 0.1359240000 0.0115050000 0.0688170000 0.0003060000 0.0002840000 0.0382820000 27178614 96830484 1769549824 3.5622575283 4.0132532120 3.8721776009 348 1311867182.0320639610 0.0688298047 0.0638050148 0.0717672706 0.0064303924 0.1334850000 0.0112590000 0.0685840000 0.0000290000 0.0003790000 0.0314330000 27180864 96830484 1768554496 3.5644702911 4.0124945641 3.8722002506 349 1311867182.0629000664 0.0683442131 0.0638180211 0.0717672706 0.0064250125 0.1531240000 0.0097360000 0.0727580000 0.0003890000 0.0002830000 0.0594040000 27183050 96830484 1770139648 3.5669541359 4.0129079819 3.8723461628 350 1311867182.0948839188 0.0684382096 0.0638312216 0.0717672706 0.0064267856 0.1169770000 0.0111640000 0.0466380000 0.0000290000 0.0003090000 0.0316800000 27185204 96830484 1769041920 3.5688443184 4.0125236511 3.8725142479 351 1311867182.1314840317 0.0685903728 0.0638447804 0.0717672706 0.0064181339 0.1157660000 0.0112690000 0.0474300000 0.0003100000 0.0003600000 0.0383690000 27187486 96830484 1767878656 3.5710425377 4.0123815536 3.8730611801 352 1311867182.1629920006 0.0683245733 0.0638575071 0.0717672706 0.0064103002 0.0969650000 0.0090170000 0.0395750000 0.0000280000 0.0003960000 0.0337590000 27189672 96830484 1769631744 3.5723717213 4.0127511024 3.8731582165 353 1311867182.1994500160 0.0689721853 0.0638719963 0.0717672706 0.0064047250 0.1295770000 0.0109540000 0.0457980000 0.0003980000 0.0002910000 0.0605970000 27191890 96830484 1768804352 3.5727846622 4.0119829178 3.8736610413 354 1311867182.2307739258 0.0690228418 0.0638865467 0.0717672706 0.0063994710 0.1210030000 0.0091330000 0.0684180000 0.0000290000 0.0003040000 0.0319370000 27194044 96830484 1770520576 3.5745215416 4.0111784935 3.8741302490 355 1311867182.2629120350 0.0687283501 0.0639001856 0.0717672706 0.0064002310 0.1160640000 0.0114330000 0.0530200000 0.0003160000 0.0002790000 0.0382500000 27196262 96830484 1769422848 3.5774850845 4.0113425255 3.8744246960 356 1311867182.2973539829 0.0694568530 0.0639157942 0.0717672706 0.0063954612 0.1122760000 0.0108900000 0.0459400000 0.0000290000 0.0003160000 0.0313450000 27198480 96830484 1768423424 3.5773112774 4.0098023415 3.8747787476 357 1311867182.3308460712 0.0702396408 0.0639335081 0.0717672706 0.0064132975 0.1468110000 0.0098390000 0.0673340000 0.0003830000 0.0002790000 0.0579890000 27200666 96830484 1770045440 3.5770850182 4.0097613335 3.8754222393 358 1311867182.3629670143 0.0703148767 0.0639513331 0.0717672706 0.0064332530 0.1229350000 0.0114370000 0.0536830000 0.0000330000 0.0003230000 0.0321300000 27202884 96830484 1769295872 3.5782451630 4.0091891289 3.8758549690 359 1311867182.3990368843 0.0701379478 0.0639685660 0.0717672706 0.0064291448 0.1160780000 0.0116300000 0.0471560000 0.0006790000 0.0002940000 0.0376480000 27205102 96830484 1767878656 3.5801703930 4.0082159042 3.8760254383 360 1311867182.4308118820 0.0713287890 0.0639890111 0.0717672706 0.0064263267 0.0960760000 0.0096720000 0.0392150000 0.0000310000 0.0003070000 0.0332210000 27207288 96830484 1769631744 3.5794222355 4.0059432983 3.8763308525 361 1311867182.4629440308 0.0716174319 0.0640101424 0.0717672706 0.0064231306 0.1332940000 0.0111730000 0.0518620000 0.0003150000 0.0003490000 0.0583690000 27209506 96830484 1768787968 3.5797421932 4.0065913200 3.8761410713 362 1311867182.4969599247 0.0719195232 0.0640319916 0.0719195232 0.0064194727 0.1189290000 0.0095160000 0.0680940000 0.0000290000 0.0003030000 0.0298650000 27211692 96830484 1770283008 3.5825457573 4.0048837662 3.8761863708 363 1311867182.5309500694 0.0726451278 0.0640557192 0.0726451278 0.0064110337 0.1134560000 0.0113360000 0.0410260000 0.0003200000 0.0011640000 0.0370420000 27213910 96830484 1769021440 3.5824680328 4.0030884743 3.8756616116 364 1311867182.5629699230 0.0737487152 0.0640823483 0.0737487152 0.0064059217 0.0962520000 0.0112360000 0.0412880000 0.0000310000 0.0003140000 0.0310700000 27216096 96830484 1764573184 3.5819196701 4.0032305717 3.8752703667 365 1311867182.6036369801 0.0741428360 0.0641099113 0.0741428360 0.0064038011 0.1237330000 0.0098570000 0.0447290000 0.0002120000 0.0001850000 0.0575650000 27218410 96830484 1766391808 3.5810866356 4.0028858185 3.8738636971 366 1311867182.6308450699 0.0746326447 0.0641386619 0.0746326447 0.0064142312 0.1222830000 0.0093460000 0.0684480000 0.0000290000 0.0002960000 0.0310100000 27220500 96830484 1768026112 3.5815927982 4.0018324852 3.8733294010 367 1311867182.6635921001 0.0745689645 0.0641670824 0.0746326447 0.0064076017 0.1137390000 0.0099600000 0.0457730000 0.0003060000 0.0002810000 0.0377550000 27222718 96830484 1769377792 3.5829489231 4.0023789406 3.8732972145 368 1311867182.6970019341 0.0741581544 0.0641942320 0.0746326447 0.0064024499 0.1351410000 0.0120630000 0.0671330000 0.0000290000 0.0002990000 0.0311700000 27224904 96830484 1768280064 3.5865204334 4.0017647743 3.8726503849 369 1311867182.7330639362 0.0746878311 0.0642226700 0.0746878311 0.0063989510 0.1476810000 0.0098020000 0.0681420000 0.0003740000 0.0002900000 0.0578810000 27227154 96830484 1769791488 3.5872864723 4.0003795624 3.8719248772 370 1311867182.7631130219 0.0748696923 0.0642514457 0.0748696923 0.0063931150 0.1059830000 0.0116380000 0.0475180000 0.0000290000 0.0002980000 0.0312130000 27229244 96830484 1766232064 3.5899231434 4.0007934570 3.8720765114 371 1311867182.7970550060 0.0755648166 0.0642819400 0.0755648166 0.0063852383 0.1099930000 0.0098330000 0.0398010000 0.0003130000 0.0002790000 0.0400860000 27231494 96830484 1767264256 3.5905282497 3.9993751049 3.8716986179 372 1311867182.8306989670 0.0765971243 0.0643150453 0.0765971243 0.0063792513 0.0967510000 0.0101990000 0.0421880000 0.0000270000 0.0010490000 0.0314290000 27233680 96830484 1766248448 3.5905885696 3.9991395473 3.8714635372 373 1311867182.8641169071 0.0765779540 0.0643479217 0.0765971243 0.0063765247 0.1311660000 0.0087440000 0.0394120000 0.0003050000 0.0002830000 0.0583180000 27235866 96830484 1765105664 3.5918428898 3.9993367195 3.8713107109 374 1311867182.8969969749 0.0753540844 0.0643773500 0.0765971243 0.0063693479 0.1343510000 0.0098010000 0.0684510000 0.0000310000 0.0003020000 0.0321110000 27238084 96830484 1766584320 3.5957927704 3.9988143444 3.8712384701 375 1311867182.9318990707 0.0759604871 0.0644082383 0.0765971243 0.0063610275 0.1177730000 0.0099740000 0.0562720000 0.0003070000 0.0002800000 0.0379970000 27240302 96830484 1768361984 3.5970690250 3.9998524189 3.8715615273 376 1311867182.9630720615 0.0748989880 0.0644361393 0.0765971243 0.0063531178 0.1328690000 0.0095620000 0.0685020000 0.0000280000 0.0002920000 0.0310820000 27242488 96830484 1770012672 3.6009576321 3.9997727871 3.8717103004 377 1311867182.9983949661 0.0757226869 0.0644660771 0.0765971243 0.0063612033 0.1501950000 0.0118790000 0.0683490000 0.0003730000 0.0002830000 0.0581060000 27244706 96830484 1768787968 3.6015768051 3.9990029335 3.8719742298 378 1311867183.0308830738 0.0759473890 0.0644964509 0.0765971243 0.0063530048 0.1004670000 0.0090890000 0.0340910000 0.0000210000 0.0004110000 0.0333130000 27246892 96830484 1770520576 3.6030807495 3.9985511303 3.8723635674 379 1311867183.0628600121 0.0760276094 0.0645268761 0.0765971243 0.0063455759 0.1368030000 0.0117300000 0.0670830000 0.0003020000 0.0003650000 0.0381210000 27249110 96830484 1769693184 3.6053774357 3.9996330738 3.8729128838 380 1311867183.1000499725 0.0763633177 0.0645580247 0.0765971243 0.0063664421 0.1157160000 0.0119710000 0.0564470000 0.0000300000 0.0003070000 0.0319110000 27251328 96830484 1768534016 3.6062726974 3.9978749752 3.8731911182 381 1311867183.1344780922 0.0762528777 0.0645887198 0.0765971243 0.0063604900 0.1270510000 0.0092650000 0.0473430000 0.0003940000 0.0002840000 0.0585120000 27253578 96830484 1770139648 3.6080405712 3.9984307289 3.8735516071 382 1311867183.1673240662 0.0760155618 0.0646186330 0.0765971243 0.0063541800 0.1223110000 0.0111670000 0.0580100000 0.0000270000 0.0003770000 0.0314720000 27255796 96830484 1769168896 3.6099884510 3.9994442463 3.8738687038 383 1311867183.2004919052 0.0772239640 0.0646515451 0.0772239640 0.0063494806 0.1166800000 0.0114160000 0.0519250000 0.0003170000 0.0002800000 0.0394980000 27257982 96830484 1768022016 3.6099464893 3.9975230694 3.8746185303 384 1311867183.2311279774 0.0765262246 0.0646824687 0.0772239640 0.0063418290 0.1130420000 0.0093440000 0.0507100000 0.0000280000 0.0003180000 0.0316960000 27260136 96830484 1769779200 3.6128103733 3.9972534180 3.8748424053 385 1311867183.2633349895 0.0758376420 0.0647114432 0.0772239640 0.0063352581 0.1461690000 0.0116550000 0.0634280000 0.0003810000 0.0002800000 0.0589630000 27262354 96830484 1768652800 3.6152305603 3.9977157116 3.8748910427 386 1311867183.2991099358 0.0760598555 0.0647408433 0.0772239640 0.0063306441 0.1257390000 0.0093830000 0.0678270000 0.0000280000 0.0003100000 0.0316150000 27264572 96830484 1770283008 3.6159501076 3.9954981804 3.8748667240 387 1311867183.3320920467 0.0756816939 0.0647691142 0.0772239640 0.0063303666 0.1361710000 0.0112090000 0.0681220000 0.0002950000 0.0002820000 0.0378890000 27266790 96830484 1769156608 3.6179120541 3.9963722229 3.8748435974 388 1311867183.3695240021 0.0765629858 0.0647995108 0.0772239640 0.0063224384 0.1159560000 0.0094730000 0.0633950000 0.0000250000 0.0003070000 0.0317060000 27269072 96830484 1771065344 3.6182029247 3.9959998131 3.8751330376 389 1311867183.3986210823 0.0766939968 0.0648300878 0.0772239640 0.0063161940 0.1281370000 0.0117150000 0.0457090000 0.0003230000 0.0002740000 0.0584430000 27271194 96830484 1768902656 3.6187179089 3.9944667816 3.8747985363 390 1311867183.4311549664 0.0764509067 0.0648598848 0.0772239640 0.0063220526 0.1223530000 0.0094250000 0.0678020000 0.0000270000 0.0003730000 0.0316190000 27273380 96830484 1770704896 3.6206765175 3.9951384068 3.8747975826 391 1311867183.4667448997 0.0770079568 0.0648909541 0.0772239640 0.0063199975 0.1153100000 0.0115360000 0.0512980000 0.0003280000 0.0003600000 0.0375730000 27275630 96830484 1768923136 3.6222062111 3.9957506657 3.8751633167 392 1311867183.4988338947 0.0762020126 0.0649198088 0.0772239640 0.0063492698 0.1320860000 0.0095490000 0.0692300000 0.0000280000 0.0003860000 0.0318150000 27277848 96830484 1770553344 3.6246566772 3.9938051701 3.8749949932 393 1311867183.5321829319 0.0759641826 0.0649479115 0.0772239640 0.0063418687 0.1518530000 0.0122390000 0.0689820000 0.0003760000 0.0002920000 0.0581370000 27280034 96830484 1768505344 3.6262335777 3.9934332371 3.8752291203 394 1311867183.5661609173 0.0761142969 0.0649762526 0.0772239640 0.0063346611 0.1133370000 0.0099250000 0.0444420000 0.0000280000 0.0003830000 0.0316620000 27282252 96830484 1770283008 3.6281499863 3.9945018291 3.8756096363 395 1311867183.5985479355 0.0769021213 0.0650064447 0.0772239640 0.0063312246 0.1189400000 0.0123670000 0.0574100000 0.0006700000 0.0002810000 0.0365980000 27284438 96830484 1768140800 3.6284999847 3.9927146435 3.8755786419 396 1311867183.6310880184 0.0765616298 0.0650356244 0.0772239640 0.0063425329 0.1312840000 0.0095900000 0.0675670000 0.0000280000 0.0003710000 0.0316330000 27286624 96830484 1769918464 3.6308205128 3.9925231934 3.8758764267 397 1311867183.6649260521 0.0772356316 0.0650663549 0.0772356316 0.0063374176 0.1506650000 0.0119360000 0.0681680000 0.0003740000 0.0002820000 0.0581880000 27288842 96830484 1767870464 3.6324481964 3.9930126667 3.8767347336 398 1311867183.6993949413 0.0764980167 0.0650950777 0.0772356316 0.0063309331 0.1200780000 0.0102370000 0.0619120000 0.0000060000 0.0000620000 0.0315380000 27291092 96830484 1769521152 3.6357049942 3.9912254810 3.8770439625 399 1311867183.7308928967 0.0786978900 0.0651291700 0.0786978900 0.0063341984 0.1164130000 0.0111190000 0.0516020000 0.0002960000 0.0003530000 0.0379500000 27293214 96830484 1767616512 3.6344110966 3.9913055897 3.8776540756 400 1311867183.7676479816 0.0764623359 0.0651575029 0.0786978900 0.0063453544 0.1314400000 0.0093560000 0.0677500000 0.0000290000 0.0003760000 0.0318930000 27295496 96830484 1769304064 3.6399488449 3.9906473160 3.8779220581 401 1311867183.7971870899 0.0764666200 0.0651857052 0.0786978900 0.0063378416 0.1485930000 0.0100650000 0.0682600000 0.0003600000 0.0002830000 0.0583260000 27297618 96830484 1770954752 3.6415412426 3.9896123409 3.8782756329 402 1311867183.8309071064 0.0786354169 0.0652191622 0.0786978900 0.0063321344 0.1230980000 0.0115430000 0.0590140000 0.0000300000 0.0002890000 0.0321280000 27299804 96830484 1768923136 3.6402475834 3.9890098572 3.8791425228 403 1311867183.8655049801 0.0764888078 0.0652471265 0.0786978900 0.0063303904 0.1326840000 0.0101910000 0.0587410000 0.0002920000 0.0003470000 0.0426390000 27302022 96830484 1770700800 3.6451020241 3.9870524406 3.8789548874 404 1311867183.8970971107 0.0770129040 0.0652762498 0.0786978900 0.0063228092 0.1351000000 0.0121140000 0.0665850000 0.0000300000 0.0002870000 0.0316860000 27304176 96830484 1768505344 3.6456401348 3.9869313240 3.8792998791 405 1311867183.9314939976 0.0788517296 0.0653097695 0.0788517296 0.0063174420 0.1466280000 0.0101510000 0.0383930000 0.0003950000 0.0002760000 0.0599190000 27306426 96830484 1770160128 3.6444425583 3.9872021675 3.8799500465 406 1311867183.9658319950 0.0772304684 0.0653391308 0.0788517296 0.0063205984 0.1397410000 0.0122050000 0.0746090000 0.0000290000 0.0003920000 0.0314370000 27308612 96830484 1768534016 3.6478846073 3.9856536388 3.8799452782 407 1311867183.9966781139 0.0769592002 0.0653676813 0.0788517296 0.0063138766 0.1341320000 0.0101160000 0.0673920000 0.0003070000 0.0003540000 0.0380620000 27310798 96830484 1770311680 3.6497066021 3.9852030277 3.8801643848 408 1311867184.0309689045 0.0781295747 0.0653989605 0.0788517296 0.0063388453 0.0976570000 0.0110230000 0.0400760000 0.0000970000 0.0003130000 0.0326800000 27313016 96830484 1766739968 3.6499836445 3.9849216938 3.8808479309 409 1311867184.0647850037 0.0768690780 0.0654270048 0.0788517296 0.0063366910 0.1258240000 0.0102770000 0.0452260000 0.0003220000 0.0003550000 0.0577970000 27315234 96830484 1767751680 3.6527786255 3.9844436646 3.8810362816 410 1311867184.0968890190 0.0768668801 0.0654549069 0.0788517296 0.0063291187 0.1212730000 0.0096170000 0.0659120000 0.0000290000 0.0003060000 0.0314010000 27317388 96830484 1767264256 3.6540355682 3.9842057228 3.8814446926 411 1311867184.1312260628 0.0777659416 0.0654848608 0.0788517296 0.0063233814 0.1236790000 0.0095060000 0.0710520000 0.0003370000 0.0003730000 0.0309010000 27319606 96830484 1769041920 3.6543841362 3.9836969376 3.8820624352 412 1311867184.1650640965 0.0781818926 0.0655156788 0.0788517296 0.0063158518 0.1018530000 0.0113190000 0.0364070000 0.0000270000 0.0007080000 0.0330410000 27321792 96830484 1768153088 3.6552886963 3.9830558300 3.8824169636 413 1311867184.1969559193 0.0777710602 0.0655453528 0.0788517296 0.0063100209 0.1493020000 0.0100390000 0.0689780000 0.0003100000 0.0003560000 0.0581220000 27324010 96830484 1769820160 3.6578056812 3.9842457771 3.8827419281 414 1311867184.2309360504 0.0758688301 0.0655702888 0.0788517296 0.0063050158 0.1211760000 0.0108920000 0.0600960000 0.0000280000 0.0005310000 0.0311290000 27326228 96830484 1769041920 3.6631522179 3.9841852188 3.8832175732 415 1311867184.2681369781 0.0770735070 0.0655980074 0.0788517296 0.0063055228 0.1344730000 0.0096010000 0.0680030000 0.0003150000 0.0002830000 0.0378600000 27328510 96830484 1770819584 3.6627719402 3.9818000793 3.8831429482 416 1311867184.2983899117 0.0779454857 0.0656276888 0.0788517296 0.0062993529 0.1349680000 0.0115240000 0.0697260000 0.0000270000 0.0003770000 0.0310400000 27330664 96830484 1769660416 3.6636967659 3.9828705788 3.8838908672 417 1311867184.3314700127 0.0772751793 0.0656556205 0.0788517296 0.0062918136 0.1457110000 0.0122440000 0.0631280000 0.0003740000 0.0002760000 0.0579300000 27332850 96830484 1768009728 3.6667597294 3.9834740162 3.8842051029 418 1311867184.3697841167 0.0775903612 0.0656841725 0.0788517296 0.0062943691 0.1039870000 0.0095720000 0.0458490000 0.0000310000 0.0003140000 0.0312980000 27335132 96830484 1769680896 3.6682522297 3.9819099903 3.8840844631 419 1311867184.4000220299 0.0777333379 0.0657129294 0.0788517296 0.0063297470 0.1357970000 0.0111210000 0.0687330000 0.0003840000 0.0002860000 0.0381260000 27337286 96830484 1768538112 3.6715590954 3.9827854633 3.8847055435 420 1311867184.4310610294 0.0770881623 0.0657400133 0.0788517296 0.0063256901 0.1131370000 0.0093690000 0.0466530000 0.0000300000 0.0003170000 0.0323040000 27339472 96830484 1770295296 3.6752235889 3.9832873344 3.8853230476 421 1311867184.4655809402 0.0789941102 0.0657714957 0.0789941102 0.0063242315 0.1527020000 0.0119810000 0.0703610000 0.0003140000 0.0002800000 0.0580110000 27341690 96830484 1769168896 3.6742870808 3.9808461666 3.8850939274 422 1311867184.5037670135 0.0783218965 0.0658012360 0.0789941102 0.0063654325 0.0984590000 0.0097230000 0.0346540000 0.0000090000 0.0000990000 0.0334890000 27343972 96830484 1770926080 3.6774423122 3.9799695015 3.8842699528 423 1311867184.5310881138 0.0779495835 0.0658299555 0.0789941102 0.0063850942 0.1174390000 0.0123600000 0.0522200000 0.0003830000 0.0002830000 0.0384210000 27346094 96830484 1770061824 3.6805272102 3.9804008007 3.8837552071 424 1311867184.5682930946 0.0773816183 0.0658572000 0.0789941102 0.0063788884 0.1326820000 0.0112940000 0.0680870000 0.0000310000 0.0005190000 0.0315000000 27348376 96830484 1769316352 3.6840083599 3.9805862904 3.8831868172 425 1311867184.6018071175 0.0774029866 0.0658843666 0.0789941102 0.0063719474 0.1501180000 0.0100600000 0.0691240000 0.0003830000 0.0002880000 0.0584500000 27350562 96830484 1771057152 3.6851487160 3.9791774750 3.8824739456 426 1311867184.6367399693 0.0798339620 0.0659171121 0.0798339620 0.0063686124 0.0979940000 0.0117360000 0.0346960000 0.0000090000 0.0000970000 0.0329260000 27352812 96830484 1766891520 3.6847631931 3.9798002243 3.8833296299 427 1311867184.6662440300 0.0770224631 0.0659431199 0.0798339620 0.0063860843 0.1336610000 0.0100060000 0.0673670000 0.0015430000 0.0002920000 0.0377050000 27354934 96830484 1768280064 3.6906116009 3.9787218571 3.8831007481 428 1311867184.6994929314 0.0779494494 0.0659711721 0.0798339620 0.0063812573 0.1137060000 0.0094100000 0.0544180000 0.0000290000 0.0003130000 0.0312340000 27357184 96830484 1767776256 3.6912436485 3.9772717953 3.8832960129 429 1311867184.7359158993 0.0775118619 0.0659980735 0.0798339620 0.0063808561 0.1307190000 0.0091290000 0.0516320000 0.0003080000 0.0003540000 0.0575480000 27359370 96830484 1769422848 3.6950073242 3.9782547951 3.8837256432 430 1311867184.7690689564 0.0788772255 0.0660280250 0.0798339620 0.0063828395 0.1376500000 0.0108920000 0.0678860000 0.0000270000 0.0003810000 0.0313760000 27361620 96830484 1768411136 3.6955952644 3.9759957790 3.8846194744 431 1311867184.8001279831 0.0783855021 0.0660566966 0.0798339620 0.0063825038 0.1150280000 0.0096630000 0.0489750000 0.0001430000 0.0001060000 0.0380670000 27363774 96830484 1770020864 3.6987051964 3.9758384228 3.8851060867 432 1311867184.8348441124 0.0786740109 0.0660859034 0.0798339620 0.0063757614 0.1349790000 0.0112670000 0.0685690000 0.0000330000 0.0003070000 0.0307040000 27365960 96830484 1769050112 3.7013432980 3.9760301113 3.8861868382 433 1311867184.8690660000 0.0762893185 0.0661094678 0.0798339620 0.0063704944 0.1341190000 0.0099480000 0.0409080000 0.0003200000 0.0008580000 0.0598530000 27368178 96830484 1770655744 3.7068109512 3.9748613834 3.8866226673 434 1311867184.9055209160 0.0758073553 0.0661318132 0.0798339620 0.0063648812 0.1374350000 0.0114880000 0.0734130000 0.0000330000 0.0003060000 0.0348950000 27370364 96830484 1769938944 3.7104268074 3.9746010303 3.8875839710 435 1311867184.9332280159 0.0756692663 0.0661537384 0.0798339620 0.0063600256 0.1165810000 0.0111790000 0.0571980000 0.0003840000 0.0002870000 0.0356040000 27372454 96830484 1768796160 3.7140374184 3.9752886295 3.8892683983 436 1311867184.9656410217 0.0760798529 0.0661765047 0.0798339620 0.0063588037 0.1312730000 0.0093140000 0.0684410000 0.0000280000 0.0004620000 0.0311870000 27374640 96830484 1770401792 3.7155065536 3.9738304615 3.8904771805 437 1311867184.9983251095 0.0755157396 0.0661978760 0.0798339620 0.0063555166 0.1510770000 0.0117560000 0.0692360000 0.0003150000 0.0002760000 0.0573430000 27376858 96830484 1769451520 3.7187943459 3.9727611542 3.8914501667 438 1311867185.0360550880 0.0740877539 0.0662158894 0.0798339620 0.0063484181 0.1184160000 0.0110800000 0.0521260000 0.0000290000 0.0003020000 0.0308840000 27379108 96830484 1768288256 3.7243134975 3.9727561474 3.8928732872 439 1311867185.0652348995 0.0721460655 0.0662293977 0.0798339620 0.0063463554 0.1153670000 0.0094340000 0.0522470000 0.0003110000 0.0002750000 0.0373690000 27381262 96830484 1769799680 3.7294914722 3.9708144665 3.8939151764 440 1311867185.0991280079 0.0736479238 0.0662462580 0.0798339620 0.0063431630 0.1158870000 0.0114770000 0.0555900000 0.0000270000 0.0002980000 0.0323940000 27383480 96830484 1768923136 3.7302885056 3.9720833302 3.8955183029 441 1311867185.1360778809 0.0741121471 0.0662640945 0.0798339620 0.0063395393 0.1533450000 0.0094760000 0.0625010000 0.0002980000 0.0003640000 0.0603070000 27385730 96830484 1770401792 3.7327415943 3.9717328548 3.8973014355 442 1311867185.1648709774 0.0731485263 0.0662796702 0.0798339620 0.0063346276 0.1168930000 0.0125150000 0.0564950000 0.0000260000 0.0002910000 0.0306730000 27387884 96830484 1769177088 3.7369222641 3.9709327221 3.8988442421 443 1311867185.2000720501 0.0733669847 0.0662956686 0.0798339620 0.0063295119 0.1150100000 0.0108230000 0.0518390000 0.0002920000 0.0005100000 0.0364480000 27390070 96830484 1768161280 3.7404129505 3.9709124565 3.9005658627 444 1311867185.2342920303 0.0733717382 0.0663116057 0.0798339620 0.0063282499 0.1309190000 0.0091360000 0.0629450000 0.0000260000 0.0003430000 0.0315660000 27392320 96830484 1769639936 3.7443177700 3.9708776474 3.9025304317 445 1311867185.2663950920 0.0717203766 0.0663237602 0.0798339620 0.0063228093 0.1309870000 0.0115330000 0.0505320000 0.0002940000 0.0004190000 0.0560620000 27394538 96830484 1768685568 3.7489888668 3.9679629803 3.9035613537 446 1311867185.2970550060 0.0717999116 0.0663360386 0.0798339620 0.0063342352 0.1003020000 0.0094900000 0.0361080000 0.0000900000 0.0002900000 0.0324620000 27396692 96830484 1770180608 3.7518570423 3.9690737724 3.9051868916 447 1311867185.3360140324 0.0718610808 0.0663483989 0.0798339620 0.0063271462 0.1373440000 0.0121760000 0.0727830000 0.0002930000 0.0005110000 0.0371580000 27398974 96830484 1769172992 3.7551870346 3.9683496952 3.9068872929 448 1311867185.3681778908 0.0714570880 0.0663598022 0.0798339620 0.0063204760 0.1123380000 0.0092380000 0.0518700000 0.0000250000 0.0003630000 0.0301930000 27401192 96830484 1770782720 3.7583706379 3.9668853283 3.9079623222 449 1311867185.4036509991 0.0712918565 0.0663707867 0.0798339620 0.0063161993 0.1496210000 0.0123460000 0.0688520000 0.0002960000 0.0002800000 0.0556530000 27403410 96830484 1769558016 3.7613945007 3.9669027328 3.9090082645 450 1311867185.4386389256 0.0726463348 0.0663847324 0.0798339620 0.0063119132 0.1229390000 0.0114460000 0.0685260000 0.0000290000 0.0003120000 0.0305020000 27405628 96830484 1768562688 3.7627577782 3.9676423073 3.9105646610 451 1311867185.4655449390 0.0712587386 0.0663955395 0.0798339620 0.0063063635 0.1122100000 0.0091430000 0.0460260000 0.0003200000 0.0003430000 0.0373940000 27407718 96830484 1770020864 3.7673468590 3.9656391144 3.9113764763 452 1311867185.5013909340 0.0694573075 0.0664023133 0.0798339620 0.0063248935 0.1156890000 0.0122010000 0.0465710000 0.0000290000 0.0003180000 0.0305280000 27409968 96830484 1768779776 3.7721822262 3.9645748138 3.9115571976 453 1311867185.5336329937 0.0710659772 0.0664126084 0.0798339620 0.0063491596 0.1515760000 0.0096800000 0.0736300000 0.0000740000 0.0000550000 0.0559710000 27412154 96830484 1767522304 3.7732512951 3.9659824371 3.9126951694 454 1311867185.5666799545 0.0708480254 0.0664223780 0.0798339620 0.0063426043 0.1185500000 0.0096970000 0.0692750000 0.0000260000 0.0003650000 0.0268770000 27414372 96830484 1766252544 3.7767658234 3.9646551609 3.9135112762 455 1311867185.5970540047 0.0698489025 0.0664299089 0.0798339620 0.0063410417 0.1493140000 0.0093220000 0.0810640000 0.0002970000 0.0003590000 0.0363110000 27416526 96830484 1762041856 3.7802243233 3.9632544518 3.9137334824 456 1311867185.6329469681 0.0715788752 0.0664412005 0.0798339620 0.0063652640 0.1113710000 0.0105350000 0.0502170000 0.0000260000 0.0004990000 0.0303360000 27418776 96830484 1763708928 3.7820856571 3.9652185440 3.9146420956 457 1311867185.6664180756 0.0696993396 0.0664483299 0.0798339620 0.0063727183 0.1468530000 0.0100800000 0.0686460000 0.0002940000 0.0002700000 0.0553790000 27420962 96830484 1765588992 3.7879095078 3.9635796547 3.9153683186 458 1311867185.6973390579 0.0694794357 0.0664549480 0.0798339620 0.0063659166 0.1020480000 0.0092370000 0.0368330000 0.0000250000 0.0003500000 0.0314050000 27423148 96830484 1767124992 3.7904813290 3.9625566006 3.9160406590 459 1311867185.7351899147 0.0697010830 0.0664620202 0.0798339620 0.0063645194 0.1342010000 0.0096660000 0.0701360000 0.0003650000 0.0002750000 0.0360260000 27425398 96830484 1768902656 3.7945127487 3.9645726681 3.9176714420 460 1311867185.7649769783 0.0701190159 0.0664699702 0.0798339620 0.0063614008 0.1345890000 0.0107560000 0.0711620000 0.0000250000 0.0002900000 0.0298700000 27427584 96830484 1768022016 3.7964630127 3.9620792866 3.9188964367 461 1311867185.7989649773 0.0705033317 0.0664787193 0.0798339620 0.0063687134 0.1464690000 0.0097710000 0.0684190000 0.0002940000 0.0003450000 0.0552620000 27429770 96830484 1769664512 3.7989580631 3.9610626698 3.9197275639 462 1311867185.8327999115 0.0695302561 0.0664853244 0.0798339620 0.0063628703 0.1039010000 0.0111850000 0.0428390000 0.0000290000 0.0005510000 0.0294900000 27432020 96830484 1768910848 3.8033006191 3.9614741802 3.9206209183 463 1311867185.8649098873 0.0694272816 0.0664916785 0.0798339620 0.0063568476 0.1129530000 0.0096890000 0.0400970000 0.0003550000 0.0002720000 0.0360280000 27434206 96830484 1770541056 3.8057687283 3.9599997997 3.9216537476 464 1311867185.9030420780 0.0688889697 0.0664968451 0.0798339620 0.0063521517 0.1156790000 0.0113700000 0.0568920000 0.0000290000 0.0002910000 0.0301050000 27436456 96830484 1769148416 3.8086924553 3.9596126080 3.9223308563 465 1311867185.9396789074 0.0704073906 0.0665052549 0.0798339620 0.0063504233 0.1143190000 0.0108360000 0.0347640000 0.0002950000 0.0003530000 0.0555780000 27438738 96830484 1768402944 3.8090987206 3.9595351219 3.9241352081 466 1311867185.9650609493 0.0693893135 0.0665114438 0.0798339620 0.0063618787 0.1329950000 0.0094090000 0.0700100000 0.0000280000 0.0003550000 0.0295260000 27440764 96830484 1770012672 3.8118317127 3.9571206570 3.9249753952 467 1311867186.0039470196 0.0686961934 0.0665161221 0.0798339620 0.0063571308 0.1166740000 0.0119470000 0.0520760000 0.0002860000 0.0002660000 0.0358650000 27443078 96830484 1769181184 3.8148508072 3.9551384449 3.9259505272 468 1311867186.0396919250 0.0703980848 0.0665244169 0.0798339620 0.0063701297 0.1123330000 0.0106730000 0.0467300000 0.0000250000 0.0003170000 0.0296320000 27445328 96830484 1768419328 3.8149333000 3.9570362568 3.9273769855 469 1311867186.0653240681 0.0693337172 0.0665304069 0.0798339620 0.0063744965 0.1226730000 0.0098950000 0.0459510000 0.0002880000 0.0003400000 0.0538220000 27447450 96830484 1770139648 3.8168859482 3.9542224407 3.9280438423 470 1311867186.1047339439 0.0697350726 0.0665372253 0.0798339620 0.0063678165 0.0893230000 0.0117540000 0.0351620000 0.0000290000 0.0003590000 0.0295770000 27449732 96830484 1765605376 3.8172214031 3.9527831078 3.9286046028 471 1311867186.1361179352 0.0691580549 0.0665427897 0.0798339620 0.0063630985 0.1330110000 0.0116770000 0.0750620000 0.0002940000 0.0003370000 0.0329410000 27451886 96830484 1767276544 3.8198142052 3.9524018764 3.9291796684 472 1311867186.1649448872 0.0696346536 0.0665493403 0.0798339620 0.0063568406 0.0927390000 0.0095080000 0.0406910000 0.0000260000 0.0002880000 0.0299650000 27454040 96830484 1769123840 3.8205111027 3.9513163567 3.9296934605 473 1311867186.2044749260 0.0684471577 0.0665533526 0.0798339620 0.0063512178 0.1471260000 0.0108040000 0.0689020000 0.0002910000 0.0003440000 0.0541570000 27456354 96830484 1768275968 3.8237080574 3.9500751495 3.9297671318 474 1311867186.2359659672 0.0689954609 0.0665585047 0.0798339620 0.0063478616 0.1227260000 0.0095620000 0.0707780000 0.0000280000 0.0002880000 0.0291440000 27458508 96830484 1769885696 3.8246467113 3.9501340389 3.9305250645 475 1311867186.2674899101 0.0697019100 0.0665651224 0.0798339620 0.0063418849 0.1349570000 0.0114500000 0.0690650000 0.0006110000 0.0003610000 0.0357090000 27460694 96830484 1768914944 3.8257689476 3.9483091831 3.9312191010 476 1311867186.3030838966 0.0690674484 0.0665703794 0.0798339620 0.0063365164 0.0947570000 0.0096300000 0.0408480000 0.0000250000 0.0003060000 0.0290130000 27462944 96830484 1770426368 3.8287541866 3.9482460022 3.9318444729 477 1311867186.3349270821 0.0694001690 0.0665763118 0.0798339620 0.0063309737 0.1149470000 0.0114560000 0.0351140000 0.0003170000 0.0003490000 0.0551110000 27465098 96830484 1769549824 3.8306901455 3.9486813545 3.9329946041 478 1311867186.3670160770 0.0681311786 0.0665795647 0.0798339620 0.0063359688 0.0964500000 0.0109050000 0.0420330000 0.0000290000 0.0009700000 0.0289250000 27467252 96830484 1764589568 3.8338477612 3.9458413124 3.9334571362 479 1311867186.4019849300 0.0688126385 0.0665842266 0.0798339620 0.0063401479 0.1098870000 0.0100680000 0.0422010000 0.0003150000 0.0002810000 0.0356690000 27469470 96830484 1766240256 3.8348338604 3.9465034008 3.9345273972 480 1311867186.4360210896 0.0688180253 0.0665888804 0.0798339620 0.0063390372 0.1328120000 0.0103890000 0.0697650000 0.0000270000 0.0002860000 0.0296220000 27471688 96830484 1768013824 3.8377764225 3.9470548630 3.9362778664 481 1311867186.4659481049 0.0680998489 0.0665920217 0.0798339620 0.0063367795 0.1305870000 0.0101140000 0.0536470000 0.0002940000 0.0003520000 0.0536590000 27473842 96830484 1769648128 3.8400747776 3.9445855618 3.9371697903 482 1311867186.5031139851 0.0683501884 0.0665956693 0.0798339620 0.0063319258 0.1015410000 0.0115200000 0.0411260000 0.0000270000 0.0010740000 0.0288230000 27476124 96830484 1768525824 3.8411283493 3.9430747032 3.9379954338 483 1311867186.5363171101 0.0684366003 0.0665994808 0.0798339620 0.0063288035 0.1336290000 0.0092880000 0.0692110000 0.0003140000 0.0002780000 0.0350450000 27478310 96830484 1770287104 3.8438858986 3.9448518753 3.9395673275 484 1311867186.5651130676 0.0689378828 0.0666043122 0.0798339620 0.0063276071 0.1344700000 0.0124500000 0.0685350000 0.0000270000 0.0002930000 0.0293680000 27480464 96830484 1769164800 3.8445920944 3.9425351620 3.9402756691 485 1311867186.6014220715 0.0693290830 0.0666099303 0.0798339620 0.0063219254 0.1482250000 0.0113650000 0.0699990000 0.0003950000 0.0002890000 0.0533570000 27482714 96830484 1768402944 3.8461108208 3.9417543411 3.9404740334 486 1311867186.6362628937 0.0699442849 0.0666167911 0.0798339620 0.0063155788 0.1223830000 0.0097660000 0.0699970000 0.0000270000 0.0002870000 0.0288560000 27484932 96830484 1770033152 3.8473837376 3.9417080879 3.9407157898 487 1311867186.6650478840 0.0699614361 0.0666236590 0.0798339620 0.0063111645 0.1149220000 0.0118190000 0.0519810000 0.0002930000 0.0002680000 0.0351590000 27487054 96830484 1768656896 3.8494298458 3.9421203136 3.9408504963 488 1311867186.7043809891 0.0693783686 0.0666293039 0.0798339620 0.0063297334 0.1113070000 0.0094370000 0.0468300000 0.0000270000 0.0003120000 0.0288030000 27489400 96830484 1770303488 3.8520677090 3.9418075085 3.9404480457 489 1311867186.7337749004 0.0700146556 0.0666362269 0.0798339620 0.0063365774 0.1311230000 0.0121480000 0.0524770000 0.0002850000 0.0005170000 0.0530220000 27491522 96830484 1769312256 3.8529770374 3.9432559013 3.9404060841 490 1311867186.7673180103 0.0705719143 0.0666442589 0.0798339620 0.0063315999 0.1377830000 0.0106580000 0.0702910000 0.0000260000 0.0002870000 0.0288760000 27493740 96830484 1768550400 3.8543877602 3.9442684650 3.9406356812 491 1311867186.8047299385 0.0695259869 0.0666501280 0.0798339620 0.0063348997 0.1147530000 0.0098620000 0.0478260000 0.0002980000 0.0003420000 0.0348730000 27496022 96830484 1770266624 3.8569400311 3.9425940514 3.9397220612 492 1311867186.8340749741 0.0708747059 0.0666587145 0.0798339620 0.0063366900 0.1146010000 0.0119370000 0.0474410000 0.0000270000 0.0003550000 0.0289670000 27498144 96830484 1769148416 3.8571922779 3.9453723431 3.9397099018 493 1311867186.8775999546 0.0710839853 0.0666676907 0.0798339620 0.0063305716 0.1469880000 0.0112680000 0.0701560000 0.0002850000 0.0003480000 0.0520740000 27500522 96830484 1768296448 3.8600075245 3.9455897808 3.9398179054 494 1311867186.9052100182 0.0705305785 0.0666755103 0.0798339620 0.0063287834 0.1374250000 0.0097740000 0.0710910000 0.0000260000 0.0002860000 0.0287180000 27502612 96830484 1770012672 3.8629071712 3.9465072155 3.9397830963 495 1311867186.9334239960 0.0710485205 0.0666843447 0.0798339620 0.0063229231 0.1369630000 0.0119460000 0.0718670000 0.0002910000 0.0002670000 0.0340390000 27504798 96830484 1769185280 3.8643844128 3.9474341869 3.9396202564 496 1311867186.9663379192 0.0715902075 0.0666942356 0.0798339620 0.0063233155 0.1331730000 0.0117050000 0.0699180000 0.0000270000 0.0004750000 0.0286700000 27506952 96830484 1768402944 3.8669433594 3.9493682384 3.9399273396 497 1311867187.0017139912 0.0722893327 0.0667054933 0.0798339620 0.0063264232 0.1338750000 0.0100100000 0.0597150000 0.0002930000 0.0003440000 0.0509380000 27509106 96830484 1770033152 3.8685522079 3.9490370750 3.9396052361 498 1311867187.0336461067 0.0711598471 0.0667144378 0.0798339620 0.0063225072 0.1342980000 0.0114270000 0.0663930000 0.0000270000 0.0003530000 0.0280580000 27511292 96830484 1768640512 3.8729135990 3.9495759010 3.9390914440 499 1311867187.0749349594 0.0733130798 0.0667276615 0.0798339620 0.0063256073 0.1355900000 0.0099210000 0.0722740000 0.0003630000 0.0002860000 0.0342660000 27513638 96830484 1770287104 3.8740389347 3.9526262283 3.9395956993 500 1311867187.1016030312 0.0731310919 0.0667404684 0.0798339620 0.0063208840 0.1352450000 0.0126190000 0.0731380000 0.0000280000 0.0003010000 0.0278110000 27515760 96830484 1768910848 3.8767707348 3.9529752731 3.9397404194 501 1311867187.1342070103 0.0737473667 0.0667544542 0.0798339620 0.0063217915 0.1236690000 0.0099750000 0.0481180000 0.0003580000 0.0002760000 0.0520860000 27517946 96830484 1770557440 3.8779904842 3.9501531124 3.9392888546 502 1311867187.1710209846 0.0740899369 0.0667690667 0.0798339620 0.0063274033 0.1265090000 0.0119660000 0.0682870000 0.0000290000 0.0002880000 0.0279110000 27520196 96830484 1769144320 3.8812916279 3.9522402287 3.9394860268 503 1311867187.2041370869 0.0741819292 0.0667838040 0.0798339620 0.0063259664 0.1136470000 0.0115940000 0.0480670000 0.0002810000 0.0002630000 0.0339260000 27522414 96830484 1768402944 3.8852539062 3.9540052414 3.9393496513 504 1311867187.2331659794 0.0737632215 0.0667976521 0.0798339620 0.0063247429 0.1125390000 0.0102700000 0.0477340000 0.0000270000 0.0006240000 0.0275350000 27524568 96830484 1770139648 3.8865997791 3.9511189461 3.9384884834 505 1311867187.2707629204 0.0728841200 0.0668097045 0.0798339620 0.0063308364 0.1484230000 0.0123170000 0.0706600000 0.0003540000 0.0002730000 0.0518880000 27526818 96830484 1769312256 3.8904848099 3.9541099072 3.9380850792 506 1311867187.3015060425 0.0720218867 0.0668200052 0.0798339620 0.0063333809 0.1207390000 0.0107960000 0.0541000000 0.0000290000 0.0002850000 0.0293230000 27529004 96830484 1768529920 3.8926136494 3.9534828663 3.9376688004 507 1311867187.3336570263 0.0724876672 0.0668311841 0.0798339620 0.0063285770 0.1157110000 0.0097690000 0.0550750000 0.0002950000 0.0002660000 0.0349130000 27531158 96830484 1770139648 3.8921842575 3.9513859749 3.9369139671 508 1311867187.3707590103 0.0716811270 0.0668407312 0.0798339620 0.0063232915 0.1338810000 0.0116920000 0.0704720000 0.0000250000 0.0003470000 0.0277080000 27533440 96830484 1769168896 3.8947696686 3.9517607689 3.9364411831 509 1311867187.4033529758 0.0717646182 0.0668504048 0.0798339620 0.0063213897 0.1471820000 0.0117310000 0.0703210000 0.0002930000 0.0003490000 0.0513200000 27535658 96830484 1768022016 3.8957309723 3.9522771835 3.9357500076 510 1311867187.4335899353 0.0703053027 0.0668571791 0.0798339620 0.0063224446 0.1028680000 0.0098950000 0.0490500000 0.0000290000 0.0003090000 0.0276000000 27537812 96830484 1769758720 3.8989570141 3.9512505531 3.9350423813 511 1311867187.4763159752 0.0723535195 0.0668679352 0.0798339620 0.0063255259 0.1138580000 0.0115680000 0.0422240000 0.0003210000 0.0003540000 0.0340730000 27540158 96830484 1768902656 3.8992562294 3.9518475533 3.9345293045 512 1311867187.5056400299 0.0726401657 0.0668792091 0.0798339620 0.0063226247 0.1327620000 0.0098470000 0.0705270000 0.0000250000 0.0003500000 0.0283120000 27542280 96830484 1770647552 3.9013125896 3.9503550529 3.9336383343 513 1311867187.5342190266 0.0719441026 0.0668890822 0.0798339620 0.0063184004 0.1314530000 0.0122770000 0.0536100000 0.0003730000 0.0002860000 0.0515690000 27585394 96830484 1769693184 3.9055297375 3.9503571987 3.9327886105 514 1311867187.5709679127 0.0721333250 0.0668992850 0.0798339620 0.0063126211 0.1010820000 0.0111370000 0.0478200000 0.0000280000 0.0002850000 0.0281520000 27671612 96830484 1768529920 3.9090318680 3.9506578445 3.9318027496 515 1311867187.6045789719 0.0732491612 0.0669116148 0.0798339620 0.0063327907 0.1132660000 0.0097520000 0.0534920000 0.0003480000 0.0002820000 0.0345920000 27673862 96830484 1770266624 3.9098558426 3.9513981342 3.9304361343 516 1311867187.6353919506 0.0728091449 0.0669230442 0.0798339620 0.0063280789 0.1138150000 0.0117350000 0.0476550000 0.0000270000 0.0003550000 0.0280370000 27676016 96830484 1769168896 3.9126715660 3.9497947693 3.9289655685 517 1311867187.6707689762 0.0726433769 0.0669341086 0.0798339620 0.0063333998 0.1336040000 0.0118350000 0.0421310000 0.0003610000 0.0002710000 0.0552090000 27678234 96830484 1768148992 3.9162826538 3.9515860081 3.9280104637 518 1311867187.7035770416 0.0715505630 0.0669430207 0.0798339620 0.0063303249 0.1334610000 0.0099030000 0.0705870000 0.0000260000 0.0002830000 0.0282990000 27680452 96830484 1769664512 3.9210395813 3.9520096779 3.9272458553 519 1311867187.7345480919 0.0721352920 0.0669530251 0.0798339620 0.0063366999 0.1371920000 0.0119430000 0.0720520000 0.0003520000 0.0002780000 0.0342110000 27682478 96830484 1768808448 3.9206199646 3.9492878914 3.9257738590 520 1311867187.7707819939 0.0720104203 0.0669627508 0.0798339620 0.0063404506 0.1122770000 0.0095650000 0.0478270000 0.0000290000 0.0003500000 0.0281760000 27684728 96830484 1770299392 3.9231655598 3.9524281025 3.9250171185 521 1311867187.8017508984 0.0714329407 0.0669713309 0.0798339620 0.0063378923 0.1352750000 0.0129610000 0.0420190000 0.0003200000 0.0003620000 0.0561040000 27686914 96830484 1769295872 3.9265782833 3.9525043964 3.9240665436 522 1311867187.8339610100 0.0720211267 0.0669810048 0.0798339620 0.0063336187 0.1342670000 0.0127980000 0.0706930000 0.0000300000 0.0003020000 0.0285470000 27689100 96830484 1768165376 3.9274036884 3.9522700310 3.9231388569 523 1311867187.8708090782 0.0717208833 0.0669900677 0.0798339620 0.0063335217 0.1346500000 0.0102190000 0.0724810000 0.0003050000 0.0003540000 0.0345810000 27691350 96830484 1769758720 3.9303045273 3.9538674355 3.9225206375 524 1311867187.9038810730 0.0724904910 0.0670005646 0.0798339620 0.0063342586 0.0969130000 0.0115920000 0.0414030000 0.0000290000 0.0010830000 0.0295760000 27693600 96830484 1765351424 3.9314055443 3.9541568756 3.9218454361 525 1311867187.9363000393 0.0702639893 0.0670067807 0.0798339620 0.0063300414 0.1478710000 0.0102570000 0.0710980000 0.0003560000 0.0002800000 0.0527050000 27695754 96830484 1767133184 3.9370980263 3.9543781281 3.9209594727 526 1311867187.9713420868 0.0705674663 0.0670135501 0.0798339620 0.0063301244 0.1354980000 0.0100320000 0.0719780000 0.0000300000 0.0004880000 0.0286540000 27698004 96830484 1768890368 3.9392156601 3.9530713558 3.9195964336 527 1311867188.0047569275 0.0709874704 0.0670210907 0.0798339620 0.0063488963 0.1340890000 0.0102980000 0.0712250000 0.0002910000 0.0005110000 0.0343520000 27700222 96830484 1770393600 3.9422931671 3.9543485641 3.9185476303 528 1311867188.0333108902 0.0713389590 0.0670292685 0.0798339620 0.0063546079 0.1146190000 0.0116660000 0.0485910000 0.0000260000 0.0002970000 0.0292740000 27702344 96830484 1769439232 3.9450509548 3.9553155899 3.9177646637 529 1311867188.0698699951 0.0696732402 0.0670342665 0.0798339620 0.0063505931 0.1480790000 0.0100820000 0.0714890000 0.0002940000 0.0003410000 0.0529440000 27704562 96830484 1771048960 3.9504644871 3.9529256821 3.9163994789 530 1311867188.1088800430 0.0709499121 0.0670416546 0.0798339620 0.0063491022 0.1089190000 0.0115100000 0.0554910000 0.0000260000 0.0002920000 0.0269160000 27706908 96830484 1767510016 3.9517686367 3.9532918930 3.9147789478 531 1311867188.1359970570 0.0694721192 0.0670462317 0.0798339620 0.0063543030 0.1310570000 0.0102050000 0.0714860000 0.0000600000 0.0000550000 0.0349290000 27708998 96830484 1768509440 3.9551618099 3.9556527138 3.9136707783 532 1311867188.1703350544 0.0707239881 0.0670531448 0.0798339620 0.0063521288 0.1319790000 0.0099860000 0.0714370000 0.0000300000 0.0006500000 0.0281010000 27711216 96830484 1767747584 3.9578104019 3.9539821148 3.9123451710 533 1311867188.2026720047 0.0709118322 0.0670603843 0.0798339620 0.0063525650 0.1470580000 0.0098820000 0.0711750000 0.0003000000 0.0003560000 0.0523150000 27713434 96830484 1769541632 3.9597480297 3.9534473419 3.9108085632 534 1311867188.2352449894 0.0689948276 0.0670640069 0.0798339620 0.0063604887 0.1250260000 0.0114450000 0.0711730000 0.0000280000 0.0003040000 0.0286420000 27715588 96830484 1768382464 3.9654529095 3.9550282955 3.9098694324 535 1311867188.2706460953 0.0704294816 0.0670702975 0.0798339620 0.0063587772 0.1330480000 0.0099650000 0.0702910000 0.0002930000 0.0004960000 0.0346570000 27717838 96830484 1770160128 3.9675722122 3.9549918175 3.9087884426 536 1311867188.3047339916 0.0708631501 0.0670773737 0.0798339620 0.0063532361 0.1163300000 0.0116570000 0.0586950000 0.0000270000 0.0003530000 0.0302690000 27720088 96830484 1769058304 3.9705827236 3.9553556442 3.9075927734 537 1311867188.3398799896 0.0720459446 0.0670866262 0.0798339620 0.0063481443 0.1457180000 0.0096230000 0.0694930000 0.0002960000 0.0002640000 0.0529730000 27722338 96830484 1770668032 3.9723501205 3.9561605453 3.9064974785 538 1311867188.3718800545 0.0731435195 0.0670978843 0.0798339620 0.0063529197 0.1255070000 0.0114300000 0.0699680000 0.0000260000 0.0002870000 0.0288390000 27724492 96830484 1769545728 3.9740366936 3.9589431286 3.9060969353 539 1311867188.4054470062 0.0718146861 0.0671066354 0.0798339620 0.0063573978 0.1146880000 0.0113000000 0.0532650000 0.0003070000 0.0003590000 0.0355530000 27726678 96830484 1768783872 3.9786760807 3.9587879181 3.9055161476 540 1311867188.4398789406 0.0715079680 0.0671147860 0.0798339620 0.0063557495 0.1103340000 0.0095460000 0.0429460000 0.0000300000 0.0003840000 0.0289600000 27728928 96830484 1770393600 3.9818201065 3.9582369328 3.9047009945 541 1311867188.4724500179 0.0727252737 0.0671251566 0.0798339620 0.0063611273 0.1361630000 0.0119740000 0.0411440000 0.0003830000 0.0002860000 0.0569250000 27731114 96830484 1769414656 3.9837694168 3.9615967274 3.9043440819 542 1311867188.5049159527 0.0720944107 0.0671343249 0.0798339620 0.0063630630 0.1340040000 0.0099580000 0.0712920000 0.0000290000 0.0003520000 0.0287390000 27733300 96830484 1771192320 3.9876637459 3.9618849754 3.9040625095 543 1311867188.5389990807 0.0720060319 0.0671432968 0.0798339620 0.0063633464 0.1166180000 0.0128280000 0.0468860000 0.0002960000 0.0002710000 0.0348910000 27735550 96830484 1769144320 3.9897487164 3.9610433578 3.9032573700 544 1311867188.5723888874 0.0738410205 0.0671556088 0.0798339620 0.0063835812 0.1304090000 0.0102450000 0.0553670000 0.0000270000 0.0003700000 0.0300380000 27737736 96830484 1770795008 3.9912073612 3.9655511379 3.9031422138 545 1311867188.6045958996 0.0728333741 0.0671660267 0.0798339620 0.0063787514 0.1730110000 0.0118010000 0.0745980000 0.0020720000 0.0002950000 0.0556440000 27739922 96830484 1769922560 3.9955549240 3.9652793407 3.9031248093 546 1311867188.6398339272 0.0727016106 0.0671761651 0.0798339620 0.0063769723 0.0991200000 0.0121690000 0.0427820000 0.0000290000 0.0003030000 0.0298830000 27742108 96830484 1767010304 3.9980914593 3.9635488987 3.9027993679 547 1311867188.6715080738 0.0743620545 0.0671893020 0.0798339620 0.0063818367 0.1086610000 0.0092600000 0.0353940000 0.0003110000 0.0002830000 0.0390470000 27744326 96830484 1768161280 3.9988255501 3.9658119678 3.9021382332 548 1311867188.7038300037 0.0745451152 0.0672027250 0.0798339620 0.0063839951 0.0960100000 0.0098950000 0.0405490000 0.0000290000 0.0004030000 0.0282880000 27746512 96830484 1768017920 4.0008883476 3.9643208981 3.9013440609 549 1311867188.7393829823 0.0743636116 0.0672157685 0.0798339620 0.0063954586 0.1480250000 0.0097460000 0.0709680000 0.0003110000 0.0002900000 0.0530590000 27748730 96830484 1767362560 4.0039558411 3.9636919498 3.9002821445 550 1311867188.7721049786 0.0773985982 0.0672342828 0.0798339620 0.0063925037 0.1381820000 0.0100210000 0.0702120000 0.0000290000 0.0003050000 0.0292720000 27750948 96830484 1769160704 4.0039405823 3.9660577774 3.8991289139 551 1311867188.8045220375 0.0772178173 0.0672524017 0.0798339620 0.0063872726 0.1176830000 0.0118900000 0.0522020000 0.0003030000 0.0002830000 0.0355420000 27753166 96830484 1768001536 4.0088424683 3.9674615860 3.8983235359 552 1311867188.8402431011 0.0781993195 0.0672722331 0.0798339620 0.0063824978 0.1323880000 0.0096920000 0.0689550000 0.0000270000 0.0003690000 0.0289440000 27755384 96830484 1769795584 4.0119333267 3.9661762714 3.8974180222 553 1311867188.8705990314 0.0809244961 0.0672969207 0.0809244961 0.0063838370 0.1497550000 0.0117210000 0.0693380000 0.0003150000 0.0003650000 0.0544000000 27757538 96830484 1768673280 4.0120100975 3.9674768448 3.8963310719 554 1311867188.9016311169 0.0818027630 0.0673231046 0.0818027630 0.0063814192 0.1205620000 0.0095260000 0.0580090000 0.0000270000 0.0003130000 0.0302200000 27759724 96830484 1770303488 4.0151057243 3.9701390266 3.8952088356 555 1311867188.9401769638 0.0823347569 0.0673501526 0.0823347569 0.0063802108 0.1176070000 0.0122210000 0.0536910000 0.0003820000 0.0006270000 0.0361290000 27762038 96830484 1769291776 4.0188522339 3.9689295292 3.8941090107 556 1311867188.9709990025 0.0830841959 0.0673784512 0.0830841959 0.0063801845 0.1323620000 0.0096030000 0.0688520000 0.0000270000 0.0003120000 0.0305740000 27764160 96830484 1770921984 4.0208859444 3.9684641361 3.8933093548 557 1311867189.0052258968 0.0831320509 0.0674067342 0.0831320509 0.0063757122 0.1343390000 0.0115400000 0.0521810000 0.0003150000 0.0005210000 0.0561840000 27766410 96830484 1769795584 4.0250692368 3.9698243141 3.8927352428 558 1311867189.0400099754 0.0825699121 0.0674339083 0.0831320509 0.0063759455 0.0989110000 0.0113400000 0.0418730000 0.0000300000 0.0012710000 0.0306320000 27768596 96830484 1765998592 4.0302596092 3.9689810276 3.8926928043 559 1311867189.0724329948 0.0813492388 0.0674588016 0.0831320509 0.0063733966 0.1098630000 0.0096380000 0.0405920000 0.0003810000 0.0002880000 0.0367200000 27770846 96830484 1767763968 4.0346040726 3.9680624008 3.8928191662 560 1311867189.1026360989 0.0803448707 0.0674818124 0.0831320509 0.0063692080 0.1305060000 0.0102850000 0.0684900000 0.0000370000 0.0003190000 0.0305010000 27773000 96830484 1769414656 4.0392131805 3.9689009190 3.8934657574 561 1311867189.1417639256 0.0794764012 0.0675031931 0.0831320509 0.0063636137 0.1504740000 0.0115190000 0.0679050000 0.0003760000 0.0002890000 0.0562920000 27775314 96830484 1768525824 4.0438952446 3.9691395760 3.8942608833 562 1311867189.1717920303 0.0803393573 0.0675260333 0.0831320509 0.0063600397 0.1005390000 0.0094440000 0.0397640000 0.0000270000 0.0003690000 0.0316020000 27777468 96830484 1770393600 4.0440211296 3.9686441422 3.8949477673 563 1311867189.2019069195 0.0795118511 0.0675473225 0.0831320509 0.0063564421 0.1545830000 0.0111550000 0.0797970000 0.0000620000 0.0000540000 0.0368780000 27779622 96830484 1769566208 4.0478415489 3.9690148830 3.8961496353 564 1311867189.2390630245 0.0795254335 0.0675685603 0.0831320509 0.0063515342 0.1332420000 0.0114620000 0.0826550000 0.0000300000 0.0003030000 0.0250970000 27781872 96830484 1768783872 4.0501799583 3.9686672688 3.8970942497 565 1311867189.2722640038 0.0790393054 0.0675888625 0.0831320509 0.0063478005 0.1358030000 0.0083970000 0.0572210000 0.0003090000 0.0003600000 0.0561840000 27784058 96830484 1770393600 4.0526919365 3.9676189423 3.8979108334 566 1311867189.3046789169 0.0796341747 0.0676101440 0.0831320509 0.0063426377 0.1143180000 0.0110750000 0.0471420000 0.0000300000 0.0003890000 0.0305810000 27786276 96830484 1769275392 4.0542984009 3.9668080807 3.8988094330 567 1311867189.3397970200 0.0778677464 0.0676282350 0.0831320509 0.0063518617 0.0962360000 0.0093790000 0.0335460000 0.0003160000 0.0002790000 0.0387350000 27788494 96830484 1770921984 4.0583891869 3.9652559757 3.8994541168 568 1311867189.3720359802 0.0781360790 0.0676467347 0.0831320509 0.0063803872 0.1345250000 0.0115920000 0.0681100000 0.0000280000 0.0003040000 0.0303860000 27790680 96830484 1769529344 4.0614328384 3.9647817612 3.8998947144 569 1311867189.4056949615 0.0785367340 0.0676658735 0.0831320509 0.0063783157 0.1448760000 0.0111260000 0.0622220000 0.0003780000 0.0002760000 0.0570930000 27792898 96830484 1768804352 4.0641579628 3.9653310776 3.9012012482 570 1311867189.4405019283 0.0778577402 0.0676837540 0.0831320509 0.0063825899 0.1038590000 0.0092070000 0.0412970000 0.0000290000 0.0012910000 0.0300920000 27795116 96830484 1770393600 4.0681152344 3.9631392956 3.9018070698 571 1311867189.4729130268 0.0775371343 0.0677010103 0.0831320509 0.0063776372 0.1157530000 0.0113640000 0.0458830000 0.0003200000 0.0003530000 0.0370820000 27797334 96830484 1769422848 4.0723266602 3.9611203671 3.9021053314 572 1311867189.5060400963 0.0782674700 0.0677194832 0.0831320509 0.0063754960 0.1343060000 0.0113860000 0.0685060000 0.0000280000 0.0003020000 0.0309880000 27799520 96830484 1768275968 4.0750846863 3.9617068768 3.9024398327 573 1311867189.5394289494 0.0769233629 0.0677355458 0.0831320509 0.0063702660 0.1260620000 0.0093260000 0.0456070000 0.0003120000 0.0003590000 0.0568530000 27801706 96830484 1769885696 4.0800795555 3.9592020512 3.9022431374 574 1311867189.5720269680 0.0774568394 0.0677524819 0.0831320509 0.0063669630 0.1266490000 0.0110010000 0.0708040000 0.0000300000 0.0003020000 0.0307030000 27803924 96830484 1768914944 4.0821671486 3.9567065239 3.9013195038 575 1311867189.6112909317 0.0781263784 0.0677705234 0.0831320509 0.0063634917 0.1327390000 0.0094930000 0.0669400000 0.0003150000 0.0002780000 0.0375410000 27806206 96830484 1770520576 4.0869655609 3.9568712711 3.9011282921 576 1311867189.6424219608 0.0789180771 0.0677898768 0.0831320509 0.0063598357 0.0980940000 0.0111070000 0.0399260000 0.0000260000 0.0003060000 0.0327420000 27808392 96830484 1766473728 4.0898065567 3.9564175606 3.9010303020 577 1311867189.6728401184 0.0783708990 0.0678082148 0.0831320509 0.0063546761 0.1218270000 0.0097830000 0.0402610000 0.0003110000 0.0003520000 0.0571050000 27810578 96830484 1767899136 4.0937752724 3.9545719624 3.9007210732 578 1311867189.7065870762 0.0803731009 0.0678299534 0.0831320509 0.0063542068 0.1243820000 0.0091080000 0.0696700000 0.0000280000 0.0003800000 0.0312460000 27812764 96830484 1764696064 4.0958790779 3.9542062283 3.9009275436 579 1311867189.7401719093 0.0802595094 0.0678514206 0.0831320509 0.0063497130 0.1132080000 0.0098670000 0.0532360000 0.0003850000 0.0002870000 0.0355080000 27814982 96830484 1765502976 4.1009588242 3.9546270370 3.9020214081 580 1311867189.7729759216 0.0822733790 0.0678762861 0.0831320509 0.0063460572 0.1105730000 0.0094960000 0.0442800000 0.0000300000 0.0003240000 0.0316310000 27817168 96830484 1765105664 4.1020197868 3.9544010162 3.9027323723 581 1311867189.8073968887 0.0808101818 0.0678985475 0.0831320509 0.0063440211 0.1533400000 0.0098810000 0.0549180000 0.0003130000 0.0002800000 0.0644550000 27819386 96830484 1765122048 4.1067738533 3.9525718689 3.9034488201 582 1311867189.8405311108 0.0823107883 0.0679233108 0.0831320509 0.0063420444 0.1144840000 0.0095870000 0.0521480000 0.0000330000 0.0003050000 0.0311060000 27821572 96830484 1766584320 4.1087303162 3.9528932571 3.9043014050 583 1311867189.8713529110 0.0813504457 0.0679463419 0.0831320509 0.0063383551 0.0983910000 0.0100660000 0.0342930000 0.0006380000 0.0002810000 0.0394680000 27823758 96830484 1768267776 4.1132516861 3.9519717693 3.9051351547 584 1311867189.9102680683 0.0817479044 0.0679699747 0.0831320509 0.0063384084 0.1152270000 0.0108450000 0.0576300000 0.0000310000 0.0003120000 0.0311470000 27826040 96830484 1770012672 4.1156201363 3.9501025677 3.9050440788 585 1311867189.9402260780 0.0816948786 0.0679934361 0.0831320509 0.0063341254 0.1350860000 0.0113680000 0.0525400000 0.0003160000 0.0002830000 0.0565810000 27828226 96830484 1769041920 4.1188259125 3.9503803253 3.9052038193 586 1311867189.9727621078 0.0809746906 0.0680155884 0.0831320509 0.0063287788 0.1340800000 0.0093420000 0.0704150000 0.0001000000 0.0003050000 0.0306750000 27830412 96830484 1770520576 4.1235427856 3.9507830143 3.9056198597 587 1311867190.0107009411 0.0811682045 0.0680379949 0.0831320509 0.0063267852 0.1176810000 0.0116380000 0.0520470000 0.0003150000 0.0005110000 0.0362120000 27832662 96830484 1769566208 4.1269392967 3.9494338036 3.9055798054 588 1311867190.0402929783 0.0813006237 0.0680605504 0.0831320509 0.0063223884 0.1335790000 0.0112050000 0.0703500000 0.0000290000 0.0003070000 0.0300510000 27834816 96830484 1768550400 4.1300511360 3.9492013454 3.9056425095 589 1311867190.0719039440 0.0812679827 0.0680829739 0.0831320509 0.0063175480 0.1277770000 0.0096740000 0.0469820000 0.0003180000 0.0002770000 0.0566940000 27837002 96830484 1770012672 4.1331462860 3.9485075474 3.9055092335 590 1311867190.1096539497 0.0890239030 0.0681184670 0.0890239030 0.0063311226 0.1026040000 0.0110910000 0.0409490000 0.0000280000 0.0003100000 0.0307420000 27839284 96830484 1769058304 4.1254916191 3.9478237629 3.9038219452 591 1311867190.1396369934 0.0896842852 0.0681549574 0.0896842852 0.0063281132 0.1134860000 0.0098100000 0.0464020000 0.0003770000 0.0002860000 0.0368730000 27841470 96830484 1770647552 4.1277856827 3.9484462738 3.9032640457 592 1311867190.1706380844 0.0896504745 0.0681912674 0.0896842852 0.0063355584 0.1150410000 0.0121140000 0.0464140000 0.0000310000 0.0003020000 0.0303630000 27843592 96830484 1769693184 4.1305618286 3.9473173618 3.9030771255 593 1311867190.2096021175 0.0900800824 0.0682281794 0.0900800824 0.0063304378 0.1517350000 0.0121270000 0.0681800000 0.0003110000 0.0002910000 0.0566620000 27845906 96830484 1768660992 4.1322693825 3.9457538128 3.9015927315 594 1311867190.2394330502 0.0897825211 0.0682644661 0.0900800824 0.0063325175 0.1120350000 0.0093270000 0.0417950000 0.0000290000 0.0011740000 0.0311590000 27848028 96830484 1770172416 4.1359634399 3.9472308159 3.9009754658 595 1311867190.2714810371 0.0892115533 0.0682996713 0.0900800824 0.0063351985 0.1374650000 0.0122890000 0.0693700000 0.0002890000 0.0003410000 0.0377100000 27850246 96830484 1769295872 4.1395201683 3.9467771053 3.9005546570 596 1311867190.3072700500 0.0902210400 0.0683364522 0.0902210400 0.0063308260 0.1121440000 0.0110750000 0.0403680000 0.0000350000 0.0003150000 0.0311780000 27852496 96830484 1768153088 4.1410555840 3.9463396072 3.8999800682 597 1311867190.3414731026 0.0902558863 0.0683731681 0.0902558863 0.0063285928 0.1373980000 0.0096240000 0.0567520000 0.0002930000 0.0002680000 0.0565950000 27854714 96830484 1769631744 4.1444072723 3.9469349384 3.9001982212 598 1311867190.3716828823 0.0893853754 0.0684083056 0.0902558863 0.0063288901 0.1151880000 0.0108900000 0.0522070000 0.0000310000 0.0003770000 0.0319730000 27856868 96830484 1768660992 4.1486864090 3.9481124878 3.9006161690 599 1311867190.4101090431 0.0908927619 0.0684458423 0.0908927619 0.0063284368 0.0958570000 0.0095170000 0.0341020000 0.0002940000 0.0003590000 0.0377490000 27859118 96830484 1770266624 4.1494216919 3.9470908642 3.9004004002 600 1311867190.4394960403 0.0913216695 0.0684839686 0.0913216695 0.0063258836 0.1123880000 0.0128990000 0.0402200000 0.0000290000 0.0003600000 0.0316810000 27861336 96830484 1769041920 4.1522698402 3.9487354755 3.9013202190 601 1311867190.4708199501 0.0916135982 0.0685224539 0.0916135982 0.0063220480 0.1733470000 0.0121660000 0.0722970000 0.0003010000 0.0003540000 0.0614030000 27863458 96830484 1768042496 4.1546673775 3.9481174946 3.9020390511 602 1311867190.5097529888 0.0915673226 0.0685607344 0.0916135982 0.0063174555 0.1339120000 0.0096160000 0.0687810000 0.0000970000 0.0003020000 0.0309820000 27865804 96830484 1769504768 4.1568398476 3.9467325211 3.9021790028 603 1311867190.5405189991 0.0925707668 0.0686005520 0.0925707668 0.0063198687 0.1186120000 0.0118970000 0.0515120000 0.0003090000 0.0005200000 0.0390780000 27867926 96830484 1768550400 4.1590194702 3.9478824139 3.9027438164 604 1311867190.5708439350 0.0927871689 0.0686405961 0.0927871689 0.0063157242 0.1107930000 0.0091170000 0.0417450000 0.0000310000 0.0013770000 0.0321320000 27870080 96830484 1770139648 4.1612367630 3.9471483231 3.9034829140 605 1311867190.6067750454 0.0927774310 0.0686804917 0.0927871689 0.0063108846 0.1529240000 0.0126920000 0.0682010000 0.0002950000 0.0003620000 0.0572630000 27872330 96830484 1769177088 4.1636013985 3.9460256100 3.9035751820 606 1311867190.6389939785 0.0929587334 0.0687205548 0.0929587334 0.0063069279 0.1366890000 0.0104840000 0.0702490000 0.0000320000 0.0003580000 0.0311350000 27874548 96830484 1768030208 4.1663508415 3.9467952251 3.9043023586 607 1311867190.6723659039 0.0923092738 0.0687594159 0.0929587334 0.0063029038 0.1144780000 0.0095830000 0.0466190000 0.0002980000 0.0002680000 0.0369970000 27876734 96830484 1769639936 4.1699233055 3.9451277256 3.9050660133 608 1311867190.7114980221 0.0926874653 0.0687987713 0.0929587334 0.0063000573 0.1172540000 0.0120610000 0.0564950000 0.0000280000 0.0007600000 0.0309860000 27879016 96830484 1768669184 4.1725029945 3.9452478886 3.9057757854 609 1311867190.7392649651 0.0923640653 0.0688374663 0.0929587334 0.0062951946 0.1499680000 0.0090170000 0.0695160000 0.0002960000 0.0002660000 0.0568640000 27881106 96830484 1770180608 4.1748452187 3.9449763298 3.9062497616 610 1311867190.7751801014 0.0925988182 0.0688764194 0.0929587334 0.0062907891 0.1004770000 0.0109090000 0.0422640000 0.0000270000 0.0003870000 0.0312310000 27883356 96830484 1768300544 4.1770939827 3.9452276230 3.9067888260 611 1311867190.8070900440 0.0931433663 0.0689161362 0.0931433663 0.0062869822 0.1502490000 0.0092180000 0.0732140000 0.0004930000 0.0002860000 0.0375310000 27885574 96830484 1767776256 4.1789088249 3.9447119236 3.9075560570 612 1311867190.8414280415 0.0918131024 0.0689535495 0.0931433663 0.0062892585 0.0966750000 0.0096360000 0.0410940000 0.0000260000 0.0003640000 0.0311470000 27887792 96830484 1765613568 4.1825718880 3.9431607723 3.9083147049 613 1311867190.8739249706 0.0935951620 0.0689937479 0.0935951620 0.0062857188 0.1310940000 0.0097010000 0.0477390000 0.0002930000 0.0002640000 0.0587920000 27889978 96830484 1765617664 4.1828150749 3.9424540997 3.9088582993 614 1311867190.9076139927 0.0937406570 0.0690340523 0.0937406570 0.0062810113 0.1144220000 0.0089820000 0.0514000000 0.0000300000 0.0003210000 0.0311420000 27892196 96830484 1764855808 4.1852121353 3.9425649643 3.9096450806 615 1311867190.9393599033 0.0923245773 0.0690719231 0.0937406570 0.0062779245 0.1123130000 0.0104730000 0.0371640000 0.0003700000 0.0002820000 0.0416420000 27894350 96830484 1764745216 4.1887755394 3.9404473305 3.9103906155 616 1311867190.9741609097 0.0919559821 0.0691090725 0.0937406570 0.0062736812 0.1118640000 0.0108680000 0.0400420000 0.0000280000 0.0002900000 0.0321840000 27896600 96830484 1766395904 4.1915006638 3.9395177364 3.9105119705 617 1311867191.0085949898 0.0929932445 0.0691477827 0.0937406570 0.0062783211 0.1377160000 0.0099970000 0.0534830000 0.0005520000 0.0003010000 0.0592820000 27898818 96830484 1767989248 4.1938610077 3.9414706230 3.9115588665 618 1311867191.0396919250 0.0929869115 0.0691863573 0.0937406570 0.0062743434 0.0968930000 0.0088950000 0.0417610000 0.0000280000 0.0010870000 0.0310010000 27901004 96830484 1769672704 4.1962246895 3.9412970543 3.9124886990 619 1311867191.0764329433 0.0925956890 0.0692241753 0.0937406570 0.0062718015 0.1184050000 0.0112650000 0.0582780000 0.0002980000 0.0002760000 0.0339680000 27903254 96830484 1768808448 4.1980538368 3.9376449585 3.9126470089 620 1311867191.1103041172 0.0936874300 0.0692636322 0.0937406570 0.0062778167 0.1101380000 0.0094850000 0.0491280000 0.0000290000 0.0003160000 0.0308150000 27905472 96830484 1770422272 4.2008066177 3.9387445450 3.9138433933 621 1311867191.1388139725 0.0927503332 0.0693014529 0.0937406570 0.0062860250 0.1268830000 0.0123170000 0.0414310000 0.0003290000 0.0002740000 0.0581310000 27907626 96830484 1769312256 4.2044339180 3.9383718967 3.9148812294 622 1311867191.1742820740 0.0936048180 0.0693405259 0.0937406570 0.0062821502 0.1046060000 0.0094670000 0.0492370000 0.0000290000 0.0003020000 0.0315010000 27909844 96830484 1770942464 4.2057852745 3.9370143414 3.9152193069 623 1311867191.2077920437 0.0935264081 0.0693793475 0.0937406570 0.0062773168 0.1150370000 0.0113860000 0.0477460000 0.0003770000 0.0002840000 0.0376540000 27912062 96830484 1770205184 4.2094936371 3.9378077984 3.9162907600 624 1311867191.2408421040 0.0944261104 0.0694194866 0.0944261104 0.0062732415 0.1144080000 0.0127870000 0.0517710000 0.0000290000 0.0003710000 0.0309640000 27914280 96830484 1768517632 4.2113413811 3.9376535416 3.9170041084 625 1311867191.2769579887 0.0951582789 0.0694606686 0.0951582789 0.0062700172 0.1248610000 0.0102990000 0.0418440000 0.0003160000 0.0003530000 0.0577830000 27916498 96830484 1770184704 4.2134165764 3.9369163513 3.9175398350 626 1311867191.3085029125 0.0952767506 0.0695019084 0.0952767506 0.0062702314 0.1042220000 0.0118470000 0.0426760000 0.0000280000 0.0003220000 0.0310980000 27918588 96830484 1768407040 4.2165269852 3.9381318092 3.9184048176 627 1311867191.3404779434 0.0955505520 0.0695434533 0.0955505520 0.0062661553 0.1125940000 0.0097190000 0.0416200000 0.0003750000 0.0002770000 0.0375730000 27920774 96830484 1770037248 4.2188372612 3.9378252029 3.9191508293 628 1311867191.3794629574 0.0956710577 0.0695850577 0.0956710577 0.0062624495 0.1155290000 0.0137430000 0.0475780000 0.0000290000 0.0003080000 0.0308240000 27923088 96830484 1768026112 4.2203593254 3.9353344440 3.9195463657 629 1311867191.4091579914 0.0952509865 0.0696258621 0.0956710577 0.0062588750 0.1484980000 0.0103630000 0.0543690000 0.0003190000 0.0002840000 0.0573210000 27925210 96830484 1769783296 4.2232375145 3.9349858761 3.9202144146 630 1311867191.4415969849 0.0945697725 0.0696654556 0.0956710577 0.0062545813 0.1147490000 0.0126560000 0.0411610000 0.0000260000 0.0011210000 0.0313810000 27927396 96830484 1767772160 4.2273702621 3.9361104965 3.9213409424 631 1311867191.4775309563 0.0952636525 0.0697060232 0.0956710577 0.0062550147 0.1055600000 0.0122650000 0.0476050000 0.0003080000 0.0002850000 0.0306800000 27929614 96830484 1769549824 4.2279748917 3.9342186451 3.9214832783 632 1311867191.5075590611 0.0952739716 0.0697464789 0.0956710577 0.0062509419 0.1041730000 0.0109630000 0.0428930000 0.0000310000 0.0003140000 0.0314160000 27931736 96830484 1768792064 4.2302680016 3.9353098869 3.9222481251 633 1311867191.5390620232 0.0950550437 0.0697864608 0.0956710577 0.0062460333 0.1348530000 0.0094810000 0.0526840000 0.0003260000 0.0003520000 0.0576130000 27933922 96830484 1770422272 4.2321977615 3.9344079494 3.9227766991 634 1311867191.5764698982 0.0950561091 0.0698263183 0.0956710577 0.0062423116 0.1158880000 0.0114070000 0.0538270000 0.0000270000 0.0003010000 0.0310720000 27936172 96830484 1769046016 4.2346839905 3.9339275360 3.9237434864 635 1311867191.6118669510 0.0959151834 0.0698674031 0.0959151834 0.0062693646 0.1342150000 0.0116610000 0.0659510000 0.0003020000 0.0002810000 0.0372760000 27938422 96830484 1768284160 4.2367930412 3.9359803200 3.9246263504 636 1311867191.6451880932 0.0954526588 0.0699076315 0.0959151834 0.0062655295 0.1118040000 0.0095200000 0.0413520000 0.0000310000 0.0009470000 0.0313420000 27940608 96830484 1770020864 4.2389469147 3.9353289604 3.9256317616 637 1311867191.6827919483 0.0937152132 0.0699450060 0.0959151834 0.0062688975 0.1315620000 0.0123740000 0.0472580000 0.0003100000 0.0003650000 0.0567800000 27942922 96830484 1769189376 4.2423133850 3.9339506626 3.9267008305 638 1311867191.7119400501 0.0941958949 0.0699830168 0.0959151834 0.0062676029 0.1187870000 0.0098460000 0.0532430000 0.0000280000 0.0002980000 0.0314630000 27945044 96830484 1770819584 4.2439250946 3.9353752136 3.9276120663 639 1311867191.7457199097 0.0938951373 0.0700204380 0.0959151834 0.0062862690 0.1152820000 0.0118640000 0.0408290000 0.0003040000 0.0006560000 0.0373330000 27947198 96830484 1769807872 4.2447524071 3.9340074062 3.9281146526 640 1311867191.7763800621 0.0947676226 0.0700591055 0.0959151834 0.0062915612 0.1328820000 0.0122830000 0.0620780000 0.0000280000 0.0003020000 0.0306480000 27949352 96830484 1769046016 4.2455968857 3.9347057343 3.9290130138 641 1311867191.8097250462 0.0933478028 0.0700954373 0.0959151834 0.0062885023 0.1292480000 0.0096260000 0.0473050000 0.0006800000 0.0002870000 0.0569350000 27951570 96830484 1770655744 4.2490620613 3.9348437786 3.9306385517 642 1311867191.8395779133 0.0922206566 0.0701299002 0.0959151834 0.0062932289 0.1007130000 0.0111020000 0.0303240000 0.0000190000 0.0002020000 0.0327000000 27953724 96830484 1769955328 4.2508306503 3.9337477684 3.9310371876 643 1311867191.8745219707 0.0927826166 0.0701651300 0.0959151834 0.0062956624 0.1142930000 0.0117490000 0.0414120000 0.0003040000 0.0003610000 0.0367140000 27955942 96830484 1769062400 4.2520246506 3.9344227314 3.9322991371 644 1311867191.9077119827 0.0915265232 0.0701982998 0.0959151834 0.0062919807 0.1140510000 0.0100110000 0.0533130000 0.0000240000 0.0002870000 0.0301720000 27958160 96830484 1770782720 4.2548704147 3.9344971180 3.9336779118 645 1311867191.9391601086 0.0921154395 0.0702322799 0.0959151834 0.0062894867 0.1371660000 0.0122120000 0.0539290000 0.0002930000 0.0003410000 0.0557550000 27960346 96830484 1769664512 4.2545671463 3.9323668480 3.9340879917 646 1311867191.9755239487 0.0914020985 0.0702650505 0.0959151834 0.0062889177 0.1130320000 0.0108850000 0.0487030000 0.0000280000 0.0002940000 0.0306440000 27962564 96830484 1768939520 4.2571930885 3.9331779480 3.9354500771 647 1311867192.0076289177 0.0916603655 0.0702981190 0.0959151834 0.0062845268 0.1361010000 0.0098920000 0.0712930000 0.0003020000 0.0002830000 0.0369940000 27964750 96830484 1770528768 4.2582950592 3.9332604408 3.9361784458 648 1311867192.0447950363 0.0912584960 0.0703304653 0.0959151834 0.0062942671 0.1133350000 0.0118330000 0.0414030000 0.0000290000 0.0009280000 0.0308870000 27967032 96830484 1769574400 4.2588829994 3.9308443069 3.9364175797 649 1311867192.0751929283 0.0931749940 0.0703656649 0.0959151834 0.0062956956 0.1276420000 0.0118560000 0.0428720000 0.0003170000 0.0003640000 0.0573250000 27969154 96830484 1768665088 4.2581090927 3.9318685532 3.9368877411 650 1311867192.1073920727 0.0919264778 0.0703988353 0.0959151834 0.0062926870 0.1187150000 0.0097610000 0.0480990000 0.0000310000 0.0003120000 0.0306050000 27971372 96830484 1770307584 4.2622518539 3.9331836700 3.9385685921 651 1311867192.1433029175 0.0929595232 0.0704334908 0.0959151834 0.0062968103 0.1168390000 0.0124920000 0.0441760000 0.0003820000 0.0002740000 0.0366430000 27973622 96830484 1769431040 4.2611188889 3.9305839539 3.9383902550 652 1311867192.1754670143 0.0935942084 0.0704690133 0.0959151834 0.0063020694 0.1127310000 0.0124370000 0.0427480000 0.0000300000 0.0003810000 0.0309700000 27975808 96830484 1768284160 4.2624382973 3.9317121506 3.9392461777 653 1311867192.2077538967 0.0937597752 0.0705046807 0.0959151834 0.0062986633 0.1239070000 0.0099260000 0.0421440000 0.0003090000 0.0003440000 0.0564540000 27978026 96830484 1769893888 4.2645664215 3.9325392246 3.9405276775 654 1311867192.2451250553 0.0930344090 0.0705391298 0.0959151834 0.0063081662 0.1088520000 0.0117120000 0.0441980000 0.0000270000 0.0003150000 0.0302620000 27980308 96830484 1766477824 4.2658691406 3.9295852184 3.9412810802 655 1311867192.2744629383 0.0934835970 0.0705741595 0.0959151834 0.0063063220 0.1101510000 0.0107170000 0.0374590000 0.0003870000 0.0002880000 0.0372100000 27982430 96830484 1767415808 4.2678132057 3.9317281246 3.9419848919 656 1311867192.3067719936 0.0936230123 0.0706092950 0.0959151834 0.0063041847 0.1340940000 0.0099930000 0.0706520000 0.0000280000 0.0005550000 0.0308790000 27984616 96830484 1766383616 4.2695746422 3.9307384491 3.9431786537 657 1311867192.3427391052 0.0936004445 0.0706442891 0.0959151834 0.0063011941 0.1347590000 0.0105230000 0.0540010000 0.0003180000 0.0002760000 0.0549740000 27986866 96830484 1767895040 4.2709140778 3.9289646149 3.9435937405 658 1311867192.3755910397 0.0943549350 0.0706803235 0.0959151834 0.0063028727 0.1151250000 0.0094110000 0.0547690000 0.0000290000 0.0003020000 0.0301540000 27989084 96830484 1769656320 4.2726120949 3.9295637608 3.9441611767 659 1311867192.4059340954 0.0934413970 0.0707148623 0.0959151834 0.0062986627 0.1360900000 0.0124990000 0.0652350000 0.0003090000 0.0002840000 0.0370920000 27991206 96830484 1768787968 4.2757973671 3.9290795326 3.9448676109 660 1311867192.4447100163 0.0953436866 0.0707521787 0.0959151834 0.0062951875 0.1141660000 0.0103360000 0.0542440000 0.0000270000 0.0003050000 0.0306420000 27993520 96830484 1770283008 4.2757711411 3.9274871349 3.9449014664 661 1311867192.4748210907 0.0962966308 0.0707908239 0.0962966308 0.0062925920 0.1348360000 0.0125330000 0.0361330000 0.0003720000 0.0002820000 0.0621620000 27995674 96830484 1769021440 4.2772426605 3.9279539585 3.9454476833 662 1311867192.5077190399 0.0971616358 0.0708306590 0.0971616358 0.0062886088 0.1139620000 0.0115790000 0.0484470000 0.0000280000 0.0002950000 0.0306090000 27997860 96830484 1768042496 4.2783088684 3.9272506237 3.9459626675 663 1311867192.5427820683 0.0962330028 0.0708689732 0.0971616358 0.0062895426 0.1321630000 0.0102900000 0.0723820000 0.0002910000 0.0002740000 0.0343270000 28000110 96830484 1769537536 4.2803044319 3.9251124859 3.9456956387 664 1311867192.5787169933 0.0978306755 0.0709095782 0.0978306755 0.0062908922 0.1131660000 0.0116510000 0.0488860000 0.0000290000 0.0003840000 0.0303680000 28002328 96830484 1768529920 4.2813696861 3.9265320301 3.9457566738 665 1311867192.6109929085 0.1018751338 0.0709561429 0.1018751338 0.0062883242 0.1254960000 0.0101150000 0.0435110000 0.0002030000 0.0001820000 0.0566040000 28004514 96830484 1770139648 4.2784042358 3.9269268513 3.9456050396 666 1311867192.6435210705 0.1032860503 0.0710046863 0.1032860503 0.0062888467 0.1231690000 0.0117600000 0.0554640000 0.0000270000 0.0002930000 0.0306770000 28006732 96830484 1769168896 4.2779064178 3.9254717827 3.9451558590 667 1311867192.6790139675 0.1035377160 0.0710534615 0.1035377160 0.0062864192 0.1149710000 0.0114790000 0.0379900000 0.0002990000 0.0003550000 0.0449480000 28008982 96830484 1768042496 4.2800092697 3.9264245033 3.9457271099 668 1311867192.7113289833 0.1042718962 0.0711031897 0.1042718962 0.0062834679 0.1134730000 0.0107670000 0.0521370000 0.0000240000 0.0003600000 0.0301970000 28011136 96830484 1769631744 4.2805981636 3.9261248112 3.9459559917 669 1311867192.7439620495 0.1051943973 0.0711541481 0.1051943973 0.0062824068 0.1266350000 0.0124900000 0.0422080000 0.0003230000 0.0002770000 0.0563020000 28013354 96830484 1768660992 4.2803964615 3.9248373508 3.9458003044 670 1311867192.7760629654 0.1046278775 0.0712041089 0.1051943973 0.0062796837 0.1414460000 0.0094180000 0.0726440000 0.0000270000 0.0002870000 0.0302170000 28015540 96830484 1770139648 4.2830548286 3.9260535240 3.9464731216 671 1311867192.8091869354 0.1049865037 0.0712544553 0.1051943973 0.0062751505 0.1381980000 0.0127050000 0.0704900000 0.0005130000 0.0002990000 0.0364900000 28017758 96830484 1769185280 4.2840199471 3.9255528450 3.9468765259 672 1311867192.8422288895 0.1033568531 0.0713022267 0.1051943973 0.0062718298 0.1112110000 0.0095440000 0.0422610000 0.0000290000 0.0003140000 0.0303250000 28019944 96830484 1770774528 4.2866463661 3.9240305424 3.9472360611 673 1311867192.8792889118 0.1054705232 0.0713529968 0.1054705232 0.0062745465 0.1378650000 0.0124170000 0.0536500000 0.0003640000 0.0002730000 0.0561360000 28022226 96830484 1769803776 4.2861814499 3.9257402420 3.9478080273 674 1311867192.9092190266 0.1049300432 0.0714028144 0.1054705232 0.0062700419 0.1343010000 0.0110790000 0.0720340000 0.0000250000 0.0003580000 0.0300870000 28024348 96830484 1768787968 4.2878718376 3.9250044823 3.9487900734 675 1311867192.9434111118 0.1046124399 0.0714520138 0.1054705232 0.0062678129 0.1342160000 0.0098960000 0.0704820000 0.0003880000 0.0002840000 0.0365180000 28026598 96830484 1770266624 4.2887477875 3.9230070114 3.9487099648 676 1311867192.9776289463 0.1043244302 0.0715006417 0.1054705232 0.0062683258 0.1135730000 0.0118630000 0.0434670000 0.0000310000 0.0003930000 0.0302120000 28028784 96830484 1769295872 4.2912678719 3.9243588448 3.9495022297 677 1311867193.0086810589 0.1050389037 0.0715501812 0.1054705232 0.0062656147 0.1651470000 0.0125370000 0.0803140000 0.0004340000 0.0003600000 0.0562330000 28030970 96830484 1768169472 4.2913641930 3.9240946770 3.9498488903 678 1311867193.0430600643 0.1042213216 0.0715983687 0.1054705232 0.0062639471 0.1408900000 0.0091350000 0.0717360000 0.0000270000 0.0002900000 0.0302370000 28033188 96830484 1769758720 4.2927193642 3.9214439392 3.9499044418 679 1311867193.0767369270 0.1051540375 0.0716477880 0.1054705232 0.0062704887 0.1172780000 0.0126210000 0.0471200000 0.0003030000 0.0003560000 0.0369510000 28035374 96830484 1768534016 4.2940545082 3.9236166477 3.9501492977 680 1311867193.1105849743 0.1044403836 0.0716960124 0.1054705232 0.0062670722 0.1125920000 0.0101730000 0.0488730000 0.0000250000 0.0002850000 0.0305370000 28037592 96830484 1770139648 4.2965350151 3.9237658978 3.9507620335 681 1311867193.1429219246 0.1028148606 0.0717417082 0.1054705232 0.0062679910 0.1267870000 0.0120870000 0.0418520000 0.0003170000 0.0003460000 0.0570460000 28039810 96830484 1769189376 4.2981891632 3.9211499691 3.9506924152 682 1311867193.1767370701 0.1046196148 0.0717899163 0.1054705232 0.0062842678 0.1247960000 0.0112650000 0.0652610000 0.0000260000 0.0003450000 0.0304810000 28041996 96830484 1768042496 4.2994914055 3.9247374535 3.9508776665 683 1311867193.2122681141 0.1048465595 0.0718383154 0.1054705232 0.0062845732 0.1122110000 0.0097670000 0.0442410000 0.0003220000 0.0002860000 0.0366230000 28044246 96830484 1769504768 4.3002986908 3.9233164787 3.9512710571 684 1311867193.2432429790 0.1037139818 0.0718849173 0.1054705232 0.0062838471 0.1363240000 0.0123460000 0.0709060000 0.0000290000 0.0003690000 0.0305180000 28046432 96830484 1768534016 4.3024415970 3.9220004082 3.9513120651 685 1311867193.2773900032 0.1048474535 0.0719330378 0.1054705232 0.0062826959 0.1330990000 0.0104050000 0.0374210000 0.0002900000 0.0003510000 0.0612030000 28048650 96830484 1770045440 4.3033976555 3.9243483543 3.9514138699 686 1311867193.3139379025 0.1054318696 0.0719818699 0.1054705232 0.0062842370 0.1179180000 0.0120920000 0.0605110000 0.0000270000 0.0002930000 0.0298610000 28050900 96830484 1769168896 4.3036231995 3.9222385883 3.9510719776 687 1311867193.3426671028 0.1057342514 0.0720310000 0.1057342514 0.0062836491 0.1503570000 0.0115870000 0.0709930000 0.0003500000 0.0002690000 0.0366570000 28053022 96830484 1768042496 4.3046789169 3.9228701591 3.9512720108 688 1311867193.3788230419 0.1046820581 0.0720784579 0.1057342514 0.0062799369 0.1155430000 0.0098910000 0.0537500000 0.0000260000 0.0002930000 0.0299150000 28055272 96830484 1769537536 4.3081493378 3.9242141247 3.9516377449 689 1311867193.4126739502 0.1052367017 0.0721265831 0.1057342514 0.0062885326 0.1546210000 0.0122090000 0.0711940000 0.0003580000 0.0002710000 0.0554960000 28057458 96830484 1768660992 4.3082680702 3.9221184254 3.9514365196 690 1311867193.4440810680 0.1054534316 0.0721748829 0.1057342514 0.0062878242 0.1149140000 0.0096040000 0.0499860000 0.0000270000 0.0002990000 0.0303020000 28059676 96830484 1770139648 4.3096561432 3.9224061966 3.9513053894 691 1311867193.4782969952 0.1051616892 0.0722226207 0.1057342514 0.0062839262 0.1181270000 0.0127270000 0.0541980000 0.0003680000 0.0002750000 0.0352700000 28061894 96830484 1769185280 4.3121762276 3.9234962463 3.9516189098 692 1311867193.5199069977 0.1059692502 0.0722713875 0.1059692502 0.0062809590 0.1094200000 0.0098280000 0.0419800000 0.0000110000 0.0001140000 0.0303530000 28064176 96830484 1770774528 4.3128223419 3.9218463898 3.9515137672 693 1311867193.5431120396 0.1061910093 0.0723203335 0.1061910093 0.0062776213 0.1560960000 0.0128850000 0.0717380000 0.0002940000 0.0002710000 0.0555120000 28066266 96830484 1769549824 4.3138332367 3.9224283695 3.9515283108 694 1311867193.5765709877 0.1060947180 0.0723689998 0.1061910093 0.0062735383 0.0969290000 0.0111270000 0.0373120000 0.0000320000 0.0002910000 0.0319450000 28068452 96830484 1764700160 4.3161087036 3.9234786034 3.9516961575 695 1311867193.6127800941 0.1076225936 0.0724197244 0.1076225936 0.0062696613 0.1485290000 0.0105270000 0.0712250000 0.0002940000 0.0002770000 0.0366270000 28070734 96830484 1766354944 4.3151321411 3.9216902256 3.9509949684 696 1311867193.6461451054 0.1071832553 0.0724696720 0.1076225936 0.0062656927 0.1317080000 0.0103090000 0.0713340000 0.0000280000 0.0002940000 0.0303270000 28072920 96830484 1768108032 4.3172392845 3.9217567444 3.9510085583 697 1311867193.6757860184 0.1075156778 0.0725199532 0.1076225936 0.0062625049 0.1297240000 0.0097470000 0.0487670000 0.0002910000 0.0002680000 0.0555110000 28075074 96830484 1769791488 4.3193230629 3.9237585068 3.9514367580 698 1311867193.7122890949 0.1085697934 0.0725716005 0.1085697934 0.0062587225 0.1203260000 0.0111730000 0.0527590000 0.0000270000 0.0003680000 0.0301490000 28077324 96830484 1769041920 4.3187613487 3.9218301773 3.9511177540 699 1311867193.7430191040 0.1096967980 0.0726247124 0.1096967980 0.0062555675 0.1141840000 0.0102830000 0.0487280000 0.0003170000 0.0005340000 0.0361790000 28079478 96830484 1770520576 4.3192481995 3.9227523804 3.9510602951 700 1311867193.7760169506 0.1112946123 0.0726799551 0.1112946123 0.0062533580 0.0967700000 0.0121020000 0.0372120000 0.0000290000 0.0002900000 0.0313790000 28081664 96830484 1766494208 4.3194117546 3.9243063927 3.9505929947 701 1311867193.8139710426 0.1116809919 0.0727355914 0.1116809919 0.0062515113 0.1325920000 0.0106380000 0.0538310000 0.0002920000 0.0002750000 0.0521280000 28083978 96830484 1767899136 4.3202939034 3.9225196838 3.9508552551 702 1311867193.8436760902 0.1121819913 0.0727917829 0.1121819913 0.0062484793 0.1126790000 0.0099910000 0.0460200000 0.0000270000 0.0003170000 0.0300400000 28086100 96830484 1763028992 4.3210997581 3.9226393700 3.9507658482 703 1311867193.8771181107 0.1122963503 0.0728479771 0.1122963503 0.0062449068 0.1134800000 0.0107940000 0.0486440000 0.0002900000 0.0002730000 0.0359420000 28088318 96830484 1764847616 4.3228688240 3.9235296249 3.9505338669 704 1311867193.9151229858 0.1130011305 0.0729050129 0.1130011305 0.0062413258 0.1132960000 0.0099610000 0.0548530000 0.0000290000 0.0002840000 0.0297310000 28090568 96830484 1766457344 4.3233413696 3.9222741127 3.9504745007 705 1311867193.9425311089 0.1144213751 0.0729639013 0.1144213751 0.0062385692 0.1515500000 0.0096060000 0.0708960000 0.0002910000 0.0002750000 0.0552630000 28092722 96830484 1768140800 4.3232278824 3.9235284328 3.9502723217 706 1311867193.9781770706 0.1146052703 0.0730228834 0.1146052703 0.0062346725 0.1005660000 0.0099370000 0.0444960000 0.0000280000 0.0003290000 0.0299960000 28094972 96830484 1769885696 4.3247523308 3.9237000942 3.9502546787 707 1311867194.0148570538 0.1170591488 0.0730851695 0.1170591488 0.0062329582 0.1338490000 0.0119220000 0.0604150000 0.0003580000 0.0002750000 0.0363430000 28097190 96830484 1769041920 4.3232069016 3.9227771759 3.9495563507 708 1311867194.0433440208 0.1181027591 0.0731487537 0.1181027591 0.0062324375 0.1120760000 0.0103660000 0.0427560000 0.0000270000 0.0002920000 0.0298250000 28099344 96830484 1770647552 4.3236899376 3.9235281944 3.9496285915 709 1311867194.0746119022 0.1165393889 0.0732099535 0.1181027591 0.0062287460 0.1399150000 0.0123370000 0.0596060000 0.0002990000 0.0002680000 0.0519040000 28101498 96830484 1769676800 4.3269877434 3.9243502617 3.9501016140 710 1311867194.1131060123 0.1173160672 0.0732720747 0.1181027591 0.0062254482 0.1323760000 0.0112310000 0.0671290000 0.0000280000 0.0005130000 0.0297950000 28103812 96830484 1768534016 4.3266973495 3.9229962826 3.9497585297 711 1311867194.1428558826 0.1202788875 0.0733381884 0.1202788875 0.0062258094 0.1363960000 0.0101320000 0.0708990000 0.0003100000 0.0005250000 0.0357600000 28105966 96830484 1770139648 4.3246073723 3.9244346619 3.9495375156 712 1311867194.1758549213 0.1187694296 0.0734019963 0.1202788875 0.0062273674 0.1136010000 0.0122030000 0.0433230000 0.0000270000 0.0006620000 0.0293400000 28108152 96830484 1769168896 4.3274431229 3.9255785942 3.9500377178 713 1311867194.2138450146 0.1206021532 0.0734681957 0.1206021532 0.0062249109 0.1356780000 0.0119770000 0.0540690000 0.0003120000 0.0003490000 0.0533860000 28110434 96830484 1767751680 4.3255772591 3.9238426685 3.9496338367 714 1311867194.2451140881 0.1197747365 0.0735330508 0.1206021532 0.0062233660 0.1329180000 0.0100590000 0.0713710000 0.0000250000 0.0002930000 0.0297930000 28112556 96830484 1769377792 4.3277821541 3.9255657196 3.9499249458 715 1311867194.2760241032 0.1200721040 0.0735981404 0.1206021532 0.0062198776 0.1372540000 0.0120410000 0.0720160000 0.0003670000 0.0002790000 0.0361720000 28114710 96830484 1768427520 4.3280215263 3.9253034592 3.9504749775 716 1311867194.3139200211 0.1207387596 0.0736639792 0.1207387596 0.0062164774 0.1116690000 0.0098070000 0.0490840000 0.0000320000 0.0003930000 0.0294840000 28116992 96830484 1769885696 4.3275547028 3.9240014553 3.9500591755 717 1311867194.3447821140 0.1193383113 0.0737276812 0.1207387596 0.0062202687 0.1440570000 0.0124860000 0.0597720000 0.0002880000 0.0003290000 0.0554670000 28119178 96830484 1768931328 4.3301548958 3.9256811142 3.9507098198 718 1311867194.3802230358 0.1188977361 0.0737905922 0.1207387596 0.0062170076 0.1267730000 0.0100100000 0.0667830000 0.0000290000 0.0003590000 0.0296020000 28121396 96830484 1770426368 4.3310599327 3.9253497124 3.9511873722 719 1311867194.4124519825 0.1188206375 0.0738532209 0.1207387596 0.0062153845 0.1162840000 0.0124780000 0.0495200000 0.0003090000 0.0002770000 0.0361900000 28123550 96830484 1769549824 4.3310256004 3.9231972694 3.9516394138 720 1311867194.4447510242 0.1199808270 0.0739172870 0.1207387596 0.0062118514 0.1127530000 0.0114980000 0.0437470000 0.0000270000 0.0002920000 0.0299170000 28125768 96830484 1767497728 4.3307051659 3.9238278866 3.9516475201 721 1311867194.4805839062 0.1193146110 0.0739802514 0.1207387596 0.0062083516 0.1713870000 0.0103160000 0.0745410000 0.0000610000 0.0000550000 0.0586220000 28127954 96830484 1766608896 4.3323574066 3.9246346951 3.9519224167 722 1311867194.5174930096 0.1202521250 0.0740443399 0.1207387596 0.0062061911 0.1345780000 0.0103130000 0.0712600000 0.0000240000 0.0003720000 0.0302710000 28130268 96830484 1768267776 4.3313169479 3.9231491089 3.9516859055 723 1311867194.5439500809 0.1191101000 0.0741066715 0.1207387596 0.0062049996 0.1159470000 0.0102540000 0.0485340000 0.0002950000 0.0002770000 0.0364190000 28132326 96830484 1770012672 4.3331727982 3.9239914417 3.9517128468 724 1311867194.5795979500 0.1197203472 0.0741696738 0.1207387596 0.0062007417 0.1159210000 0.0128720000 0.0496740000 0.0000260000 0.0003160000 0.0328710000 28134544 96830484 1769062400 4.3329653740 3.9239413738 3.9522695541 725 1311867194.6129479408 0.1181329116 0.0742303128 0.1207387596 0.0061970600 0.1340220000 0.0104160000 0.0543760000 0.0002810000 0.0002680000 0.0532050000 28136762 96830484 1770520576 4.3348503113 3.9227025509 3.9528062344 726 1311867194.6493880749 0.1175622344 0.0742899986 0.1207387596 0.0062078819 0.1167280000 0.0113290000 0.0558200000 0.0000280000 0.0002860000 0.0297870000 28139044 96830484 1769549824 4.3360323906 3.9238562584 3.9535758495 727 1311867194.6784319878 0.1165924296 0.0743481863 0.1207387596 0.0062076662 0.1345150000 0.0124030000 0.0661970000 0.0002970000 0.0002720000 0.0359610000 28141166 96830484 1768132608 4.3372273445 3.9233119488 3.9538509846 728 1311867194.7133309841 0.1176685169 0.0744076922 0.1207387596 0.0062047400 0.1309100000 0.0096850000 0.0612820000 0.0000270000 0.0002870000 0.0297870000 28143384 96830484 1769758720 4.3363261223 3.9233849049 3.9537651539 729 1311867194.7475099564 0.1171156168 0.0744662765 0.1207387596 0.0062006804 0.1219700000 0.0127580000 0.0373210000 0.0003700000 0.0002720000 0.0554450000 28145602 96830484 1768804352 4.3377990723 3.9240305424 3.9543373585 730 1311867194.7784450054 0.1172848046 0.0745249320 0.1207387596 0.0061967985 0.1267410000 0.0097650000 0.0532030000 0.0000280000 0.0003870000 0.0297640000 28147788 96830484 1770393600 4.3379955292 3.9238662720 3.9547648430 731 1311867194.8130390644 0.1183126792 0.0745848331 0.1207387596 0.0061927953 0.1771700000 0.0117080000 0.1098560000 0.0019470000 0.0003010000 0.0363440000 28150006 96830484 1769295872 4.3368978500 3.9237127304 3.9548883438 732 1311867194.8476719856 0.1190515161 0.0746455800 0.1207387596 0.0061890248 0.1124850000 0.0113140000 0.0429870000 0.0000270000 0.0003640000 0.0292980000 28152224 96830484 1766600704 4.3363251686 3.9245569706 3.9546332359 733 1311867194.8814148903 0.1195220277 0.0747068030 0.1207387596 0.0061851840 0.1153020000 0.0103960000 0.0372150000 0.0003020000 0.0002780000 0.0512570000 28154442 96830484 1766883328 4.3356428146 3.9250223637 3.9548289776 734 1311867194.9104089737 0.1198493615 0.0747683051 0.1207387596 0.0061913755 0.0947910000 0.0099440000 0.0379440000 0.0000290000 0.0002940000 0.0307620000 28156564 96830484 1765740544 4.3352823257 3.9257795811 3.9549870491 735 1311867194.9451448917 0.1187999174 0.0748282120 0.1207387596 0.0061886712 0.1133550000 0.0112250000 0.0472500000 0.0003830000 0.0002890000 0.0358540000 28158814 96830484 1764323328 4.3353862762 3.9245460033 3.9554846287 736 1311867194.9787399769 0.1158159077 0.0748839018 0.1207387596 0.0061879146 0.1120770000 0.0108610000 0.0498580000 0.0000260000 0.0003720000 0.0290780000 28161032 96830484 1765949440 4.3378510475 3.9233407974 3.9560463428 737 1311867195.0132799149 0.1155362576 0.0749390611 0.1207387596 0.0061857328 0.1261280000 0.0099470000 0.0447700000 0.0003910000 0.0002850000 0.0550450000 28163250 96830484 1767600128 4.3374872208 3.9245090485 3.9564101696 738 1311867195.0464940071 0.1150917262 0.0749934685 0.1207387596 0.0061830072 0.1049280000 0.0097740000 0.0435790000 0.0000290000 0.0003790000 0.0294860000 28165436 96830484 1769283584 4.3368225098 3.9225821495 3.9566643238 739 1311867195.0781710148 0.1139007211 0.0750461170 0.1207387596 0.0061800775 0.1351610000 0.0120680000 0.0611450000 0.0002940000 0.0002640000 0.0368440000 28167622 96830484 1768427520 4.3376483917 3.9232821465 3.9569797516 740 1311867195.1115310192 0.1138682440 0.0750985793 0.1207387596 0.0061762643 0.1144430000 0.0101310000 0.0556320000 0.0000290000 0.0002860000 0.0293100000 28169808 96830484 1769885696 4.3372154236 3.9241187572 3.9573478699 741 1311867195.1458311081 0.1142344624 0.0751513943 0.1207387596 0.0061721082 0.1343660000 0.0125420000 0.0366820000 0.0002950000 0.0003470000 0.0599890000 28172058 96830484 1768914944 4.3355145454 3.9232983589 3.9569923878 742 1311867195.1780319214 0.1139732450 0.0752037148 0.1207387596 0.0061702120 0.1134790000 0.0101100000 0.0498440000 0.0000260000 0.0002940000 0.0291340000 28174244 96830484 1770393600 4.3354349136 3.9248886108 3.9572329521 743 1311867195.2114748955 0.1123232767 0.0752536739 0.1207387596 0.0061664401 0.0972370000 0.0122980000 0.0308370000 0.0002950000 0.0011340000 0.0347760000 28176430 96830484 1766080512 4.3355941772 3.9245417118 3.9573028088 744 1311867195.2436800003 0.1117941588 0.0753027874 0.1207387596 0.0061648870 0.0934290000 0.0112620000 0.0367010000 0.0000290000 0.0002920000 0.0291680000 28178648 96830484 1767890944 4.3352222443 3.9232835770 3.9575939178 745 1311867195.2780399323 0.1116789132 0.0753516144 0.1207387596 0.0061613048 0.1324790000 0.0101920000 0.0506290000 0.0002940000 0.0003480000 0.0550600000 28180866 96830484 1769541632 4.3343858719 3.9238061905 3.9576215744 746 1311867195.3123180866 0.1116301715 0.0754002452 0.1207387596 0.0061573298 0.1354910000 0.0116120000 0.0723280000 0.0000290000 0.0002930000 0.0291370000 28183084 96830484 1767763968 4.3333716393 3.9234826565 3.9577333927 747 1311867195.3425979614 0.1126634330 0.0754501290 0.1207387596 0.0061576589 0.1129980000 0.0107450000 0.0435450000 0.0003880000 0.0002900000 0.0355230000 28185238 96830484 1769414656 4.3303103447 3.9217355251 3.9569082260 748 1311867195.3782711029 0.1108172759 0.0754974113 0.1207387596 0.0061551095 0.1146800000 0.0120580000 0.0490780000 0.0000270000 0.0003720000 0.0301010000 28187488 96830484 1768423424 4.3313856125 3.9226005077 3.9568109512 749 1311867195.4119830132 0.1103117317 0.0755438924 0.1207387596 0.0061533511 0.1334170000 0.0102510000 0.0411740000 0.0003950000 0.0002820000 0.0579350000 28189674 96830484 1770012672 4.3305993080 3.9227175713 3.9567010403 750 1311867195.4435520172 0.1110874191 0.0755912837 0.1207387596 0.0061513796 0.1157450000 0.0123320000 0.0497210000 0.0000290000 0.0003220000 0.0293200000 28191892 96830484 1768914944 4.3274741173 3.9217033386 3.9558818340 751 1311867195.4788239002 0.1097469479 0.0756367640 0.1207387596 0.0061475577 0.1319320000 0.0104480000 0.0555360000 0.0003750000 0.0002880000 0.0357680000 28194110 96830484 1770520576 4.3280615807 3.9235830307 3.9557166100 752 1311867195.5113179684 0.1100536659 0.0756825311 0.1207387596 0.0061435744 0.1158440000 0.0126050000 0.0496630000 0.0000280000 0.0002980000 0.0291610000 28196296 96830484 1769549824 4.3262920380 3.9236166477 3.9557185173 753 1311867195.5439620018 0.1098145247 0.0757278591 0.1207387596 0.0061395472 0.1333440000 0.0119110000 0.0493000000 0.0003080000 0.0003510000 0.0552730000 28198514 96830484 1768423424 4.3238816261 3.9220306873 3.9554848671 754 1311867195.5782160759 0.1077753007 0.0757703624 0.1207387596 0.0061372454 0.1365340000 0.0097840000 0.0745000000 0.0000300000 0.0003020000 0.0327380000 28200732 96830484 1769918464 4.3249602318 3.9226622581 3.9559292793 755 1311867195.6119859219 0.1082231626 0.0758133462 0.1207387596 0.0061346190 0.1345590000 0.0129910000 0.0622760000 0.0003080000 0.0002750000 0.0360180000 28202950 96830484 1769041920 4.3226976395 3.9227097034 3.9558200836 756 1311867195.6430909634 0.1092056558 0.0758575159 0.1207387596 0.0061310200 0.1132220000 0.0104150000 0.0500350000 0.0000290000 0.0003120000 0.0289790000 28205104 96830484 1770520576 4.3192133904 3.9220993519 3.9551532269 757 1311867195.6779129505 0.1083710119 0.0759004664 0.1207387596 0.0061276204 0.1312510000 0.0123460000 0.0474670000 0.0003210000 0.0002830000 0.0546820000 28207354 96830484 1769566208 4.3184471130 3.9226291180 3.9551823139 758 1311867195.7107300758 0.1088567823 0.0759439444 0.1207387596 0.0061273164 0.1186470000 0.0110900000 0.0507250000 0.0000310000 0.0003820000 0.0292740000 28209508 96830484 1768402944 4.3156986237 3.9226202965 3.9552187920 759 1311867195.7458300591 0.1079575270 0.0759861230 0.1207387596 0.0061242208 0.1339520000 0.0107510000 0.0652610000 0.0003800000 0.0002800000 0.0359660000 28211758 96830484 1770045440 4.3143920898 3.9216053486 3.9551417828 760 1311867195.7821879387 0.1068070531 0.0760266769 0.1207387596 0.0061207335 0.1138050000 0.0128920000 0.0418330000 0.0000350000 0.0003170000 0.0299090000 28213976 96830484 1769189376 4.3140153885 3.9218182564 3.9555983543 761 1311867195.8100500107 0.1074029356 0.0760679072 0.1207387596 0.0061172038 0.1323820000 0.0117170000 0.0490800000 0.0003900000 0.0002820000 0.0545250000 28216098 96830484 1768042496 4.3114838600 3.9216570854 3.9554464817 762 1311867195.8458549976 0.1068146080 0.0761082572 0.1207387596 0.0061133681 0.1159080000 0.0098760000 0.0506550000 0.0000280000 0.0003130000 0.0292500000 28218348 96830484 1769631744 4.3097662926 3.9210653305 3.9553549290 763 1311867195.8778660297 0.1062604189 0.0761477751 0.1207387596 0.0061118447 0.1508990000 0.0131540000 0.0748010000 0.0003790000 0.0002860000 0.0353930000 28220566 96830484 1768660992 4.3090586662 3.9229428768 3.9554405212 764 1311867195.9098269939 0.1064628214 0.0761874545 0.1207387596 0.0061094852 0.1353250000 0.0101300000 0.0739720000 0.0000060000 0.0000630000 0.0302450000 28222752 96830484 1770139648 4.3069796562 3.9223761559 3.9555919170 765 1311867195.9458460808 0.1063312367 0.0762268581 0.1207387596 0.0061057155 0.1291600000 0.0141740000 0.0440960000 0.0003860000 0.0002820000 0.0540110000 28224970 96830484 1769168896 4.3048043251 3.9216759205 3.9554016590 766 1311867195.9778430462 0.1067886651 0.0762667560 0.1207387596 0.0061046435 0.1018300000 0.0110420000 0.0428190000 0.0000330000 0.0003160000 0.0295650000 28227188 96830484 1767751680 4.3034906387 3.9236822128 3.9556248188 767 1311867196.0100569725 0.1057399437 0.0763051826 0.1207387596 0.0061024868 0.1106520000 0.0096810000 0.0371920000 0.0001260000 0.0001080000 0.0361410000 28229374 96830484 1769377792 4.3028225899 3.9227285385 3.9558889866 768 1311867196.0498790741 0.1048999280 0.0763424153 0.1207387596 0.0060990738 0.1364830000 0.0123610000 0.0731000000 0.0000300000 0.0003110000 0.0291310000 28231688 96830484 1768423424 4.3017916679 3.9220180511 3.9555988312 769 1311867196.0793108940 0.1060020402 0.0763809844 0.1207387596 0.0061015672 0.1319670000 0.0101160000 0.0372780000 0.0011160000 0.0002970000 0.0571530000 28233874 96830484 1769918464 4.2998771667 3.9241929054 3.9558722973 770 1311867196.1113979816 0.1057676449 0.0764191489 0.1207387596 0.0060987095 0.1146650000 0.0125450000 0.0437440000 0.0000290000 0.0003840000 0.0290410000 28235996 96830484 1769062400 4.2979078293 3.9228472710 3.9558703899 771 1311867196.1473290920 0.1044202074 0.0764554668 0.1207387596 0.0060953453 0.0990790000 0.0104000000 0.0369700000 0.0006500000 0.0003660000 0.0345720000 28238278 96830484 1770520576 4.2973752022 3.9219665527 3.9560611248 772 1311867196.1811769009 0.1045340225 0.0764918379 0.1207387596 0.0060969337 0.0939300000 0.0116720000 0.0366640000 0.0000300000 0.0003780000 0.0289320000 28240496 96830484 1769549824 4.2960424423 3.9236974716 3.9559733868 773 1311867196.2114949226 0.1057116240 0.0765296384 0.1207387596 0.0060949330 0.1702630000 0.0113190000 0.0732400000 0.0005190000 0.0002800000 0.0570710000 28242618 96830484 1768423424 4.2928280830 3.9225203991 3.9557688236 774 1311867196.2462599277 0.1053459793 0.0765668689 0.1207387596 0.0060920370 0.1343910000 0.0102600000 0.0650150000 0.0000290000 0.0003710000 0.0295500000 28244868 96830484 1770045440 4.2914547920 3.9223024845 3.9558565617 775 1311867196.2800569534 0.1054168046 0.0766040946 0.1207387596 0.0060883098 0.0986560000 0.0125060000 0.0308260000 0.0003110000 0.0002800000 0.0370540000 28247086 96830484 1766346752 4.2898507118 3.9232053757 3.9557263851 776 1311867196.3111600876 0.1051698849 0.0766409062 0.1207387596 0.0060849388 0.1111070000 0.0106850000 0.0428060000 0.0000220000 0.0002180000 0.0379940000 28249240 96830484 1767661568 4.2880692482 3.9222395420 3.9557783604 777 1311867196.3484730721 0.1052472368 0.0766777226 0.1207387596 0.0060816231 0.1701640000 0.0103500000 0.0887500000 0.0003130000 0.0003630000 0.0535930000 28251522 96830484 1766518784 4.2863035202 3.9225959778 3.9556009769 778 1311867196.3842670918 0.1048306376 0.0767139088 0.1207387596 0.0060785158 0.1349980000 0.0099020000 0.0738420000 0.0000270000 0.0003040000 0.0289900000 28253740 96830484 1768108032 4.2852845192 3.9238266945 3.9558594227 779 1311867196.4107549191 0.1051099747 0.0767503608 0.1207387596 0.0060762935 0.1160330000 0.0101330000 0.0475930000 0.0003060000 0.0002840000 0.0372130000 28255830 96830484 1769758720 4.2829236984 3.9221949577 3.9560160637 780 1311867196.4463150501 0.1047282815 0.0767862299 0.1207387596 0.0060757726 0.1341970000 0.0129170000 0.0680390000 0.0000300000 0.0003030000 0.0293770000 28258080 96830484 1768787968 4.2820024490 3.9231941700 3.9561634064 781 1311867196.4798319340 0.1039606258 0.0768210243 0.1207387596 0.0060719489 0.1248210000 0.0101720000 0.0436140000 0.0003040000 0.0002790000 0.0537880000 28260298 96830484 1770393600 4.2814655304 3.9236648083 3.9567046165 782 1311867196.5113470554 0.1043979600 0.0768562889 0.1207387596 0.0060683714 0.1052200000 0.0120040000 0.0442310000 0.0003000000 0.0003180000 0.0291340000 28262452 96830484 1769168896 4.2787847519 3.9230237007 3.9565825462 783 1311867196.5468420982 0.1040388271 0.0768910048 0.1207387596 0.0060654671 0.1141340000 0.0120180000 0.0443880000 0.0003170000 0.0002810000 0.0354560000 28264702 96830484 1768153088 4.2768821716 3.9237360954 3.9568095207 784 1311867196.5795550346 0.1037781760 0.0769252996 0.1207387596 0.0060633371 0.1124960000 0.0100630000 0.0495040000 0.0000280000 0.0005110000 0.0283060000 28266920 96830484 1769631744 4.2764163017 3.9248974323 3.9573550224 785 1311867196.6108930111 0.1028045639 0.0769582668 0.1207387596 0.0060627025 0.1249480000 0.0127600000 0.0419120000 0.0003180000 0.0002820000 0.0531820000 28269074 96830484 1768660992 4.2751054764 3.9235491753 3.9577066898 786 1311867196.6521809101 0.1031164005 0.0769915469 0.1207387596 0.0060657871 0.1031810000 0.0097720000 0.0367720000 0.0000190000 0.0002090000 0.0299880000 28271420 96830484 1770266624 4.2723522186 3.9247753620 3.9575712681 787 1311867196.6805100441 0.1019484550 0.0770232584 0.1207387596 0.0060733764 0.1363190000 0.0127780000 0.0643940000 0.0003040000 0.0003570000 0.0341410000 28273542 96830484 1769291776 4.2717332840 3.9256689548 3.9581916332 788 1311867196.7112100124 0.1011655927 0.0770538958 0.1207387596 0.0060704110 0.0951030000 0.0117840000 0.0374900000 0.0000340000 0.0003120000 0.0279460000 28275696 96830484 1768005632 4.2706332207 3.9243960381 3.9588932991 789 1311867196.7464900017 0.1023306251 0.0770859323 0.1207387596 0.0060670517 0.1116700000 0.0096920000 0.0319910000 0.0003150000 0.0003550000 0.0529470000 28277946 96830484 1769631744 4.2674069405 3.9258115292 3.9590849876 790 1311867196.7783749104 0.1008155793 0.0771159698 0.1207387596 0.0060635803 0.0968670000 0.0111000000 0.0315970000 0.0000280000 0.0003080000 0.0307850000 28280164 96830484 1765093376 4.2667102814 3.9255056381 3.9594805241 791 1311867196.8109180927 0.1009145379 0.0771460565 0.1207387596 0.0060613975 0.1100540000 0.0103340000 0.0379020000 0.0002110000 0.0003280000 0.0342930000 28282286 96830484 1766862848 4.2641139030 3.9250729084 3.9596915245 792 1311867196.8488750458 0.1006964743 0.0771757918 0.1207387596 0.0060589874 0.1339430000 0.0099350000 0.0733370000 0.0000300000 0.0003070000 0.0277470000 28284600 96830484 1768488960 4.2619385719 3.9251902103 3.9599201679 793 1311867196.8821749687 0.1003371179 0.0772049991 0.1207387596 0.0060554217 0.1510820000 0.0105030000 0.0441740000 0.0003250000 0.0002760000 0.0545530000 28286786 96830484 1770266624 4.2604212761 3.9259290695 3.9602832794 794 1311867196.9115700722 0.0996247977 0.0772332356 0.1207387596 0.0060531447 0.1384650000 0.0122000000 0.0669460000 0.0000260000 0.0003730000 0.0303410000 28288908 96830484 1769168896 4.2586092949 3.9241807461 3.9604003429 795 1311867196.9482440948 0.0993509740 0.0772610566 0.1207387596 0.0060498487 0.1551890000 0.0117100000 0.0872460000 0.0000620000 0.0000550000 0.0385810000 28291190 96830484 1768153088 4.2565665245 3.9247927666 3.9604775906 796 1311867196.9809880257 0.0987282842 0.0772880255 0.1207387596 0.0060472674 0.0941020000 0.0098060000 0.0383160000 0.0000280000 0.0003690000 0.0291430000 28293408 96830484 1769631744 4.2550959587 3.9245166779 3.9606258869 797 1311867197.0154891014 0.0985771418 0.0773147371 0.1207387596 0.0060439772 0.1306050000 0.0133140000 0.0521730000 0.0003010000 0.0002770000 0.0476800000 28295594 96830484 1768660992 4.2531838417 3.9240469933 3.9606401920 798 1311867197.0490679741 0.0986759290 0.0773415055 0.1207387596 0.0060408259 0.1149830000 0.0096560000 0.0563390000 0.0000280000 0.0003040000 0.0271380000 28297812 96830484 1770139648 4.2507700920 3.9240238667 3.9604830742 799 1311867197.0806479454 0.0970269963 0.0773661432 0.1207387596 0.0060379968 0.0966580000 0.0129880000 0.0309710000 0.0003050000 0.0011400000 0.0325970000 28299934 96830484 1765838848 4.2505135536 3.9234907627 3.9604725838 800 1311867197.1148109436 0.0975873098 0.0773914196 0.1207387596 0.0060343150 0.1314370000 0.0109250000 0.0737780000 0.0000320000 0.0002990000 0.0273810000 28302184 96830484 1767665664 4.2473177910 3.9233634472 3.9599423409 801 1311867197.1468429565 0.0979024693 0.0774170264 0.1207387596 0.0060318408 0.1312020000 0.0097490000 0.0363460000 0.0003250000 0.0002750000 0.0556970000 28304370 96830484 1769123840 4.2451348305 3.9243829250 3.9598517418 802 1311867197.1792430878 0.0979625583 0.0774426443 0.1207387596 0.0060290953 0.0997670000 0.0118930000 0.0385410000 0.0000300000 0.0002960000 0.0296310000 28306588 96830484 1766600704 4.2426304817 3.9238233566 3.9597105980 803 1311867197.2143619061 0.0980375707 0.0774682918 0.1207387596 0.0060283009 0.1113100000 0.0101820000 0.0381290000 0.0003080000 0.0003620000 0.0429380000 28308806 96830484 1766756352 4.2402372360 3.9243216515 3.9596240520 804 1311867197.2459290028 0.0975567698 0.0774932774 0.1207387596 0.0060248712 0.1126730000 0.0100410000 0.0522430000 0.0000290000 0.0003070000 0.0287840000 28310992 96830484 1765359616 4.2390584946 3.9248130322 3.9598383904 805 1311867197.2799959183 0.0971904248 0.0775177459 0.1207387596 0.0060219607 0.1256810000 0.0104190000 0.0465990000 0.0003200000 0.0002810000 0.0510750000 28313242 96830484 1765105664 4.2370257378 3.9243505001 3.9600174427 806 1311867197.3157260418 0.0970621333 0.0775419946 0.1207387596 0.0060189182 0.1207700000 0.0095680000 0.0591660000 0.0000270000 0.0003120000 0.0272590000 28315428 96830484 1766617088 4.2346611023 3.9246406555 3.9598646164 807 1311867197.3468708992 0.0964142308 0.0775653802 0.1207387596 0.0060157491 0.1197210000 0.0105430000 0.0613810000 0.0003100000 0.0002810000 0.0306580000 28317614 96830484 1768361984 4.2332458496 3.9247510433 3.9600653648 808 1311867197.3784019947 0.0966966227 0.0775890575 0.1207387596 0.0060132639 0.1101310000 0.0096800000 0.0435430000 0.0000290000 0.0003190000 0.0272100000 28319768 96830484 1770053632 4.2305836678 3.9241025448 3.9598507881 809 1311867197.4155099392 0.0968900472 0.0776129153 0.1207387596 0.0060099685 0.1345170000 0.0130340000 0.0356030000 0.0003970000 0.0002870000 0.0549490000 28322018 96830484 1769066496 4.2279152870 3.9239966869 3.9594736099 810 1311867197.4478878975 0.0958662927 0.0776354504 0.1207387596 0.0060065537 0.0954810000 0.0100240000 0.0369160000 0.0000270000 0.0003080000 0.0271330000 28324204 96830484 1770655744 4.2275166512 3.9240965843 3.9594886303 811 1311867197.4793179035 0.0968226343 0.0776591091 0.1207387596 0.0060030726 0.1330280000 0.0126050000 0.0555870000 0.0003680000 0.0002920000 0.0340080000 28326326 96830484 1769811968 4.2240252495 3.9238021374 3.9584686756 812 1311867197.5150759220 0.0973457992 0.0776833537 0.1207387596 0.0060011410 0.1140620000 0.0120010000 0.0431980000 0.0000290000 0.0003040000 0.0275000000 28328576 96830484 1767899136 4.2214765549 3.9247176647 3.9577155113 813 1311867197.5469260216 0.0969757140 0.0777070836 0.1207387596 0.0059978874 0.1698670000 0.0102650000 0.0724440000 0.0002900000 0.0000580000 0.0502060000 28330730 96830484 1767145472 4.2203245163 3.9253723621 3.9574179649 814 1311867197.5802750587 0.0970065221 0.0777307930 0.1207387596 0.0059967120 0.1347220000 0.0119390000 0.0666690000 0.0000300000 0.0003840000 0.0274970000 28332948 96830484 1768751104 4.2177505493 3.9239625931 3.9566125870 815 1311867197.6152749062 0.0990348756 0.0777569329 0.1207387596 0.0059974435 0.1173060000 0.0102840000 0.0421540000 0.0003220000 0.0002810000 0.0415530000 28335166 96830484 1770528768 4.2135376930 3.9255368710 3.9552426338 816 1311867197.6470439434 0.0982437059 0.0777820393 0.1207387596 0.0059949592 0.1159680000 0.0134980000 0.0552290000 0.0001000000 0.0003160000 0.0284520000 28337352 96830484 1769705472 4.2132253647 3.9273381233 3.9549994469 817 1311867197.6800849438 0.0981184170 0.0778069308 0.1207387596 0.0059944252 0.1628500000 0.0117030000 0.0820570000 0.0003180000 0.0002830000 0.0513250000 28339570 96830484 1768542208 4.2104706764 3.9254271984 3.9542376995 818 1311867197.7143290043 0.0985441059 0.0778322819 0.1207387596 0.0059950016 0.1030340000 0.0099760000 0.0420850000 0.0000310000 0.0003200000 0.0273440000 28341788 96830484 1770147840 4.2087697983 3.9277834892 3.9535868168 819 1311867197.7463419437 0.0984882712 0.0778575029 0.1207387596 0.0059930099 0.1371470000 0.0126140000 0.0724090000 0.0003170000 0.0003630000 0.0341950000 28343974 96830484 1768923136 4.2068643570 3.9277610779 3.9529738426 820 1311867197.7793009281 0.0992407426 0.0778835800 0.1207387596 0.0059903713 0.1100150000 0.0095880000 0.0436250000 0.0000280000 0.0003180000 0.0273390000 28346192 96830484 1770655744 4.2032575607 3.9263930321 3.9517834187 821 1311867197.8146750927 0.0990423784 0.0779093520 0.1207387596 0.0059922210 0.1349210000 0.0138270000 0.0367220000 0.0003140000 0.0002810000 0.0550500000 28348442 96830484 1769832448 4.2025632858 3.9288275242 3.9511868954 822 1311867197.8467919827 0.0984598696 0.0779343526 0.1207387596 0.0059912287 0.1134920000 0.0124880000 0.0428670000 0.0000130000 0.0001190000 0.0278990000 28350596 96830484 1768398848 4.2012338638 3.9274144173 3.9505879879 823 1311867197.8802978992 0.0995289609 0.0779605915 0.1207387596 0.0059897640 0.0960730000 0.0100920000 0.0374760000 0.0003810000 0.0002880000 0.0308140000 28352782 96830484 1767124992 4.1975960732 3.9281749725 3.9492654800 824 1311867197.9148609638 0.0990902483 0.0779862343 0.1207387596 0.0059908995 0.1252440000 0.0097300000 0.0478660000 0.0000290000 0.0004070000 0.0275060000 28355032 96830484 1766129664 4.1970524788 3.9297420979 3.9488384724 825 1311867197.9470140934 0.0981865674 0.0780107195 0.1207387596 0.0059942749 0.1583850000 0.0108150000 0.0570770000 0.0003210000 0.0003560000 0.0633110000 28357218 96830484 1765003264 4.1955127716 3.9290122986 3.9481923580 826 1311867197.9812700748 0.0983349159 0.0780353251 0.1207387596 0.0059906843 0.1118940000 0.0111030000 0.0401440000 0.0000320000 0.0021300000 0.0280280000 28359436 96830484 1766498304 4.1933240891 3.9292483330 3.9474630356 827 1311867198.0145471096 0.0982588455 0.0780597792 0.1207387596 0.0059883674 0.1368120000 0.0101350000 0.0545870000 0.0003980000 0.0002920000 0.0500090000 28361686 96830484 1768243200 4.1920380592 3.9305539131 3.9473171234 828 1311867198.0463368893 0.0975219831 0.0780832843 0.1207387596 0.0059860523 0.0956170000 0.0104320000 0.0333600000 0.0000270000 0.0003880000 0.0313630000 28363840 96830484 1769893888 4.1905922890 3.9297449589 3.9467060566 829 1311867198.0787069798 0.0978854150 0.0781071710 0.1207387596 0.0059857383 0.1541460000 0.0136370000 0.0551150000 0.0003140000 0.0003550000 0.0570550000 28366058 96830484 1768669184 4.1884269714 3.9305248260 3.9461636543 830 1311867198.1143770218 0.0956415236 0.0781282968 0.1207387596 0.0059833131 0.1326730000 0.0100200000 0.0669400000 0.0000290000 0.0003040000 0.0277120000 28368276 96830484 1770274816 4.1891136169 3.9309751987 3.9459931850 831 1311867198.1463611126 0.0971262679 0.0781511583 0.1207387596 0.0059798285 0.1170340000 0.0134080000 0.0440440000 0.0004450000 0.0002880000 0.0342770000 28370462 96830484 1769320448 4.1852645874 3.9313700199 3.9451930523 832 1311867198.1822519302 0.0962153599 0.0781728701 0.1207387596 0.0059765262 0.1118120000 0.0108630000 0.0445520000 0.0000290000 0.0003910000 0.0276090000 28372712 96830484 1764466688 4.1840300560 3.9318871498 3.9444658756 833 1311867198.2144989967 0.0962923765 0.0781946222 0.1207387596 0.0059797599 0.1275770000 0.0106840000 0.0476650000 0.0003880000 0.0002820000 0.0513510000 28374898 96830484 1766273024 4.1820011139 3.9320745468 3.9439411163 834 1311867198.2464120388 0.0957278237 0.0782156452 0.1207387596 0.0059775605 0.1160800000 0.0097230000 0.0502020000 0.0000220000 0.0002100000 0.0279800000 28377084 96830484 1767862272 4.1804409027 3.9317176342 3.9431011677 835 1311867198.2821578979 0.0954217017 0.0782362513 0.1207387596 0.0059746609 0.1183480000 0.0109500000 0.0515980000 0.0003190000 0.0002800000 0.0381380000 28379334 96830484 1769512960 4.1785168648 3.9326066971 3.9424943924 836 1311867198.3159120083 0.0947624967 0.0782560195 0.1207387596 0.0059741381 0.1122950000 0.0117500000 0.0370270000 0.0000110000 0.0001180000 0.0297770000 28381520 96830484 1765736448 4.1770362854 3.9333980083 3.9415662289 837 1311867198.3481218815 0.0932742134 0.0782739624 0.1207387596 0.0059720323 0.1639810000 0.0102380000 0.0813870000 0.0003180000 0.0003510000 0.0544390000 28383706 96830484 1767165952 4.1762056351 3.9326238632 3.9409961700 838 1311867198.3828320503 0.0938324034 0.0782925286 0.1207387596 0.0059731746 0.1440400000 0.0097580000 0.0875670000 0.0000270000 0.0003090000 0.0280080000 28385956 96830484 1768624128 4.1732206345 3.9343125820 3.9399826527 839 1311867198.4242680073 0.0927322060 0.0783097392 0.1207387596 0.0059754489 0.1149930000 0.0096100000 0.0510560000 0.0003150000 0.0002800000 0.0345270000 28388174 96830484 1770307584 4.1712694168 3.9348297119 3.9389357567 840 1311867198.4497859478 0.0921658278 0.0783262345 0.1207387596 0.0059723581 0.1138670000 0.0126740000 0.0436360000 0.0000300000 0.0003180000 0.0285250000 28390200 96830484 1769029632 4.1694087982 3.9328804016 3.9379999638 841 1311867198.4856219292 0.0938143879 0.0783446509 0.1207387596 0.0059784886 0.1254500000 0.0116590000 0.0434850000 0.0003100000 0.0003690000 0.0523550000 28392386 96830484 1767886848 4.1649599075 3.9345204830 3.9368686676 842 1311867198.5190339088 0.0935195461 0.0783626733 0.1207387596 0.0059761658 0.1020710000 0.0097240000 0.0380020000 0.0000290000 0.0003860000 0.0296760000 28394604 96830484 1769512960 4.1628332138 3.9358532429 3.9360404015 843 1311867198.5499279499 0.0920250639 0.0783788802 0.1207387596 0.0059768049 0.1371760000 0.0117740000 0.0713370000 0.0003240000 0.0003510000 0.0346960000 28396790 96830484 1768542208 4.1614861488 3.9346194267 3.9350047112 844 1311867198.5824239254 0.0909595117 0.0783937861 0.1207387596 0.0059742891 0.1104740000 0.0095880000 0.0413180000 0.0000290000 0.0012650000 0.0282000000 28398976 96830484 1770037248 4.1604399681 3.9366500378 3.9341862202 845 1311867198.6147489548 0.0899303928 0.0784074389 0.1207387596 0.0059759684 0.1485300000 0.0123330000 0.0570660000 0.0003120000 0.0002830000 0.0612440000 28401162 96830484 1769058304 4.1589756012 3.9363489151 3.9334452152 846 1311867198.6482009888 0.0900218487 0.0784211675 0.1207387596 0.0059735218 0.1209160000 0.0096720000 0.0497510000 0.0000310000 0.0007120000 0.0280750000 28403348 96830484 1770647552 4.1563878059 3.9373261929 3.9325373173 847 1311867198.6827540398 0.0905873924 0.0784355314 0.1207387596 0.0059713103 0.1166670000 0.0123680000 0.0384900000 0.0003830000 0.0002840000 0.0394970000 28405566 96830484 1769422848 4.1531138420 3.9382922649 3.9315609932 848 1311867198.7146520615 0.0902809948 0.0784495001 0.1207387596 0.0059678043 0.1132740000 0.0118200000 0.0453470000 0.0000290000 0.0003830000 0.0305970000 28407720 96830484 1766211584 4.1515426636 3.9389631748 3.9310994148 849 1311867198.7467699051 0.0905002728 0.0784636942 0.1207387596 0.0059653600 0.1740730000 0.0105500000 0.0905490000 0.0004060000 0.0002870000 0.0534230000 28409874 96830484 1764057088 4.1490612030 3.9386079311 3.9302978516 850 1311867198.7842700481 0.0895619094 0.0784767509 0.1207387596 0.0059621563 0.0935260000 0.0098760000 0.0373060000 0.0000280000 0.0003910000 0.0284360000 28412124 96830484 1765486592 4.1481471062 3.9400424957 3.9298408031 851 1311867198.8149418831 0.0920359865 0.0784926842 0.1207387596 0.0059594649 0.1271870000 0.0093200000 0.0419010000 0.0001250000 0.0001750000 0.0345720000 28414278 96830484 1764978688 4.1425070763 3.9405434132 3.9284718037 852 1311867198.8464009762 0.0925057083 0.0785091315 0.1207387596 0.0059567323 0.1345140000 0.0105330000 0.0638520000 0.0000310000 0.0003040000 0.0333030000 28416464 96830484 1764614144 4.1400718689 3.9413204193 3.9277195930 853 1311867198.8845369816 0.0920894071 0.0785250521 0.1207387596 0.0059541406 0.1295690000 0.0102790000 0.0466530000 0.0003070000 0.0002860000 0.0547920000 28418682 96830484 1766330368 4.1390266418 3.9422557354 3.9271605015 854 1311867198.9147930145 0.0928490981 0.0785418249 0.1207387596 0.0059507141 0.1010110000 0.0096500000 0.0445360000 0.0000290000 0.0003070000 0.0285760000 28420836 96830484 1767981056 4.1366004944 3.9431056976 3.9263420105 855 1311867198.9465179443 0.0937027037 0.0785595570 0.1207387596 0.0059474029 0.1152060000 0.0093550000 0.0487540000 0.0003250000 0.0002740000 0.0374520000 28423022 96830484 1769664512 4.1339836121 3.9443371296 3.9252908230 856 1311867198.9839329720 0.0940481946 0.0785776512 0.1207387596 0.0059442415 0.1129020000 0.0126670000 0.0389630000 0.0000290000 0.0003870000 0.0283910000 28425336 96830484 1767108608 4.1316990852 3.9450449944 3.9244570732 857 1311867199.0148730278 0.0951777250 0.0785970211 0.1207387596 0.0059453909 0.1468410000 0.0102080000 0.0569630000 0.0003140000 0.0002840000 0.0614960000 28427490 96830484 1767264256 4.1286740303 3.9461910725 3.9233982563 858 1311867199.0468010902 0.0968683138 0.0786183164 0.1207387596 0.0059467965 0.1024520000 0.0096120000 0.0441670000 0.0000270000 0.0003080000 0.0286860000 28429676 96830484 1764573184 4.1262950897 3.9473526478 3.9225273132 859 1311867199.0849320889 0.0964642465 0.0786390916 0.1207387596 0.0059470950 0.1112350000 0.0100220000 0.0454850000 0.0003760000 0.0002890000 0.0357340000 28431990 96830484 1765122048 4.1255984306 3.9485681057 3.9217123985 860 1311867199.1149818897 0.0977376401 0.0786612992 0.1207387596 0.0059444483 0.0937760000 0.0099490000 0.0367160000 0.0000270000 0.0003080000 0.0275690000 28434112 96830484 1764958208 4.1228713989 3.9490330219 3.9205651283 861 1311867199.1465420723 0.0991054699 0.0786850439 0.1207387596 0.0059418947 0.1483740000 0.0115320000 0.0368370000 0.0004880000 0.0002780000 0.0576620000 28436298 96830484 1763979264 4.1205387115 3.9504969120 3.9192965031 862 1311867199.1823658943 0.1004623994 0.0787103077 0.1207387596 0.0059405281 0.1338280000 0.0096310000 0.0696930000 0.0000300000 0.0003060000 0.0303500000 28438548 96830484 1765441536 4.1183252335 3.9527590275 3.9180929661 863 1311867199.2146680355 0.1015569344 0.0787367811 0.1207387596 0.0059372899 0.1343590000 0.0097010000 0.0570430000 0.0003810000 0.0002940000 0.0448430000 28440766 96830484 1767219200 4.1156053543 3.9528737068 3.9168336391 864 1311867199.2467749119 0.1017049029 0.0787633646 0.1207387596 0.0059340387 0.1120960000 0.0102790000 0.0408950000 0.0000280000 0.0003940000 0.0283090000 28442920 96830484 1768869888 4.1144886017 3.9542484283 3.9159317017 865 1311867199.2833590508 0.1017837152 0.0787899777 0.1207387596 0.0059306209 0.1538510000 0.0119770000 0.0562050000 0.0003170000 0.0003640000 0.0673350000 28445202 96830484 1767915520 4.1129622459 3.9551017284 3.9148292542 866 1311867199.3159129620 0.1023951173 0.0788172354 0.1207387596 0.0059306740 0.1328060000 0.0093810000 0.0666320000 0.0000920000 0.0003030000 0.0281190000 28447324 96830484 1769394176 4.1109585762 3.9555146694 3.9135599136 867 1311867199.3465209007 0.1030695885 0.0788452081 0.1207387596 0.0059274973 0.1381660000 0.0119700000 0.0718660000 0.0003110000 0.0002830000 0.0339230000 28449478 96830484 1768402944 4.1088500023 3.9561555386 3.9123249054 868 1311867199.3829050064 0.1031517014 0.0788732110 0.1207387596 0.0059244492 0.1119460000 0.0101180000 0.0486910000 0.0000290000 0.0003090000 0.0278640000 28451760 96830484 1770012672 4.1069159508 3.9567823410 3.9112010002 869 1311867199.4147589207 0.1030040309 0.0789009795 0.1207387596 0.0059210789 0.1541000000 0.0127030000 0.0704520000 0.0003120000 0.0002830000 0.0524570000 28453914 96830484 1768787968 4.1050429344 3.9564692974 3.9100124836 870 1311867199.4512910843 0.1032607406 0.0789289792 0.1207387596 0.0059182639 0.0963330000 0.0098530000 0.0370360000 0.0000290000 0.0003030000 0.0290990000 28456196 96830484 1770393600 4.1026463509 3.9576513767 3.9086289406 871 1311867199.4837360382 0.1020185724 0.0789554885 0.1207387596 0.0059158540 0.1365730000 0.0125400000 0.0720080000 0.0003110000 0.0002790000 0.0338420000 28458382 96830484 1769443328 4.1022143364 3.9578626156 3.9079096317 872 1311867199.5150198936 0.1018079594 0.0789816955 0.1207387596 0.0059126154 0.1116590000 0.0110090000 0.0361220000 0.0000270000 0.0003020000 0.0300990000 28460568 96830484 1765195776 4.1004557610 3.9578928947 3.9070725441 873 1311867199.5544059277 0.1019641310 0.0790080213 0.1207387596 0.0059113251 0.1290260000 0.0108960000 0.0333780000 0.0002040000 0.0001830000 0.0559880000 28462882 96830484 1766883328 4.0977077484 3.9589440823 3.9061214924 874 1311867199.5835030079 0.1022670418 0.0790346334 0.1207387596 0.0059080240 0.0954850000 0.0098880000 0.0367920000 0.0000300000 0.0003080000 0.0284340000 28465036 96830484 1768361984 4.0951504707 3.9595263004 3.9054040909 875 1311867199.6158308983 0.1019174382 0.0790607852 0.1207387596 0.0059055523 0.1163310000 0.0099380000 0.0551220000 0.0003010000 0.0006830000 0.0323780000 28467158 96830484 1770045440 4.0926766396 3.9594161510 3.9047615528 876 1311867199.6538460255 0.1003004685 0.0790850314 0.1207387596 0.0059033081 0.1132120000 0.0118700000 0.0424690000 0.0000280000 0.0003070000 0.0280340000 28469472 96830484 1766346752 4.0917258263 3.9596409798 3.9044368267 877 1311867199.6824479103 0.1005373746 0.0791094925 0.1207387596 0.0059001554 0.1498820000 0.0106700000 0.0570140000 0.0003870000 0.0002840000 0.0638280000 28471594 96830484 1763811328 4.0890750885 3.9593710899 3.9038846493 878 1311867199.7146759033 0.0995351821 0.0791327564 0.1207387596 0.0058976993 0.0964000000 0.0095640000 0.0374720000 0.0000280000 0.0003140000 0.0278650000 28473812 96830484 1763028992 4.0876474380 3.9596374035 3.9034080505 879 1311867199.7511539459 0.0993602201 0.0791557683 0.1207387596 0.0058952974 0.1276040000 0.0104460000 0.0494240000 0.0003100000 0.0003570000 0.0347090000 28476030 96830484 1764724736 4.0853071213 3.9605672359 3.9031314850 880 1311867199.7826020718 0.0997331664 0.0791791517 0.1207387596 0.0058932821 0.0969660000 0.0099140000 0.0378070000 0.0000130000 0.0001160000 0.0308710000 28478216 96830484 1766203392 4.0821700096 3.9598469734 3.9026005268 881 1311867199.8150150776 0.0985824317 0.0792011758 0.1207387596 0.0058956582 0.1675770000 0.0090290000 0.0875130000 0.0000600000 0.0000550000 0.0534640000 28480402 96830484 1767870464 4.0804276466 3.9593937397 3.9020509720 882 1311867199.8519051075 0.0982703194 0.0792227962 0.1207387596 0.0058926785 0.1186130000 0.0093970000 0.0491000000 0.0000330000 0.0003090000 0.0287830000 28482652 96830484 1769631744 4.0785694122 3.9605855942 3.9017872810 883 1311867199.8839609623 0.0979915336 0.0792440518 0.1207387596 0.0058928209 0.1146830000 0.0125820000 0.0369030000 0.0003030000 0.0002770000 0.0349160000 28484870 96830484 1767751680 4.0760154724 3.9595515728 3.9014029503 884 1311867199.9148159027 0.0977289677 0.0792649624 0.1207387596 0.0058907503 0.0959710000 0.0098700000 0.0306310000 0.0000280000 0.0006450000 0.0369490000 28487056 96830484 1766862848 4.0737524033 3.9593222141 3.9010970592 885 1311867199.9520709515 0.0969550088 0.0792849511 0.1207387596 0.0058876642 0.1314480000 0.0109160000 0.0507260000 0.0003350000 0.0003600000 0.0453290000 28489306 96830484 1765867520 4.0728073120 3.9601876736 3.9009099007 886 1311867199.9828410149 0.0957011953 0.0793034796 0.1207387596 0.0058860554 0.1106590000 0.0098480000 0.0429210000 0.0000360000 0.0003110000 0.0282870000 28491460 96830484 1764741120 4.0715131760 3.9589765072 3.9005134106 887 1311867200.0144031048 0.0949729607 0.0793211453 0.1207387596 0.0058838147 0.1160920000 0.0098610000 0.0481720000 0.0001170000 0.0004600000 0.0389780000 28493646 96830484 1766203392 4.0700411797 3.9593884945 3.9001939297 888 1311867200.0539638996 0.0946184918 0.0793383721 0.1207387596 0.0058827693 0.1133030000 0.0096200000 0.0492620000 0.0000290000 0.0003040000 0.0283470000 28495960 96830484 1767886848 4.0683135986 3.9612514973 3.9001464844 889 1311867200.0830330849 0.0943689644 0.0793552794 0.1207387596 0.0058801967 0.1133450000 0.0101050000 0.0321050000 0.0004970000 0.0002830000 0.0527020000 28498082 96830484 1769631744 4.0661201477 3.9598169327 3.9001750946 890 1311867200.1174468994 0.0946930125 0.0793725128 0.1207387596 0.0058791303 0.1154700000 0.0113720000 0.0428040000 0.0000310000 0.0003140000 0.0280220000 28500300 96830484 1768407040 4.0629706383 3.9609584808 3.9000146389 891 1311867200.1517000198 0.0927581638 0.0793875359 0.1207387596 0.0058791975 0.1161830000 0.0098400000 0.0459560000 0.0007110000 0.0004940000 0.0416050000 28502518 96830484 1770012672 4.0632600784 3.9612336159 3.9003257751 892 1311867200.1853220463 0.0932668149 0.0794030957 0.1207387596 0.0058793477 0.0960800000 0.0117660000 0.0365430000 0.0000890000 0.0003080000 0.0292320000 28504768 96830484 1765965824 4.0600605011 3.9600193501 3.9003074169 893 1311867200.2179059982 0.0919669345 0.0794171649 0.1207387596 0.0058787425 0.1248610000 0.0103300000 0.0432680000 0.0003230000 0.0002750000 0.0526090000 28506954 96830484 1767645184 4.0599045753 3.9618046284 3.9004852772 894 1311867200.2522649765 0.0916552469 0.0794308541 0.1207387596 0.0058755134 0.1161530000 0.0099090000 0.0481450000 0.0000300000 0.0003780000 0.0280860000 28509172 96830484 1769123840 4.0578360558 3.9617097378 3.9009978771 895 1311867200.2825429440 0.0902215242 0.0794429107 0.1207387596 0.0058745055 0.1161920000 0.0121270000 0.0484740000 0.0003090000 0.0002840000 0.0343830000 28511326 96830484 1768153088 4.0567474365 3.9607007504 3.9013373852 896 1311867200.3148880005 0.0901222900 0.0794548296 0.1207387596 0.0058714499 0.1113750000 0.0101560000 0.0415020000 0.0000310000 0.0012650000 0.0286680000 28513544 96830484 1769758720 4.0548958778 3.9621453285 3.9018127918 897 1311867200.3514990807 0.0883766785 0.0794647759 0.1207387596 0.0058714618 0.1533610000 0.0123490000 0.0466770000 0.0003150000 0.0012860000 0.0644950000 28515762 96830484 1768787968 4.0539503098 3.9602932930 3.9024536610 898 1311867200.3837759495 0.0878027231 0.0794740610 0.1207387596 0.0058774891 0.1556240000 0.0098940000 0.0872810000 0.0000280000 0.0003750000 0.0332830000 28517980 96830484 1770266624 4.0522494316 3.9611992836 3.9028632641 899 1311867200.4162800312 0.0875983909 0.0794830980 0.1207387596 0.0058749490 0.1484790000 0.0154030000 0.0626370000 0.0003600000 0.0002810000 0.0438730000 28520134 96830484 1769021440 4.0499610901 3.9610226154 3.9031975269 900 1311867200.4522490501 0.0871932060 0.0794916648 0.1207387596 0.0058727488 0.1339960000 0.0117420000 0.0747480000 0.0000290000 0.0003740000 0.0277850000 28522384 96830484 1768042496 4.0470604897 3.9601900578 3.9033229351 901 1311867200.4850699902 0.0869870260 0.0794999838 0.1207387596 0.0058734164 0.1209430000 0.0101180000 0.0398710000 0.0002990000 0.0009860000 0.0518360000 28524570 96830484 1769504768 4.0445704460 3.9606878757 3.9036977291 902 1311867200.5143918991 0.0865205452 0.0795077671 0.1207387596 0.0058713077 0.1437590000 0.0111550000 0.0711450000 0.0002150000 0.0003100000 0.0283530000 28526756 96830484 1768550400 4.0423779488 3.9596841335 3.9043564796 903 1311867200.5505030155 0.0864427537 0.0795154470 0.1207387596 0.0058749422 0.1145620000 0.0098690000 0.0486540000 0.0002980000 0.0005780000 0.0341360000 28529006 96830484 1770045440 4.0393409729 3.9601964951 3.9047610760 904 1311867200.5832219124 0.0875200629 0.0795243017 0.1207387596 0.0058798993 0.1350340000 0.0126110000 0.0732140000 0.0000280000 0.0002940000 0.0283860000 28531192 96830484 1769168896 4.0359067917 3.9609119892 3.9053068161 905 1311867200.6145610809 0.0875145420 0.0795331307 0.1207387596 0.0058787520 0.1514390000 0.0114030000 0.0539030000 0.0002950000 0.0002710000 0.0559900000 28533346 96830484 1767751680 4.0326895714 3.9600021839 3.9058978558 906 1311867200.6504778862 0.0862423405 0.0795405360 0.1207387596 0.0058780311 0.1338530000 0.0098420000 0.0699730000 0.0000280000 0.0002990000 0.0276540000 28535596 96830484 1769377792 4.0312285423 3.9602806568 3.9064409733 907 1311867200.6851279736 0.0860417262 0.0795477038 0.1207387596 0.0058752540 0.1143640000 0.0121910000 0.0369880000 0.0003180000 0.0003660000 0.0369590000 28537846 96830484 1768427520 4.0284128189 3.9601118565 3.9067645073 908 1311867200.7189719677 0.0867719799 0.0795556600 0.1207387596 0.0058733667 0.1315330000 0.0100600000 0.0646900000 0.0000270000 0.0002920000 0.0278890000 28540064 96830484 1769885696 4.0243883133 3.9599137306 3.9071035385 909 1311867200.7503669262 0.0877968967 0.0795647263 0.1207387596 0.0058708868 0.1319990000 0.0120460000 0.0480090000 0.0003260000 0.0003600000 0.0529050000 28542218 96830484 1768914944 4.0206170082 3.9607589245 3.9075100422 910 1311867200.7832930088 0.0872011483 0.0795731180 0.1207387596 0.0058751156 0.1370880000 0.0093310000 0.0709240000 0.0000260000 0.0002900000 0.0276990000 28544436 96830484 1770426368 4.0187687874 3.9608025551 3.9080681801 911 1311867200.8181068897 0.0871462747 0.0795814310 0.1207387596 0.0058729222 0.1378940000 0.0123550000 0.0708840000 0.0003800000 0.0002790000 0.0346500000 28546654 96830484 1769418752 4.0152492523 3.9605534077 3.9084045887 912 1311867200.8501501083 0.0877052918 0.0795903387 0.1207387596 0.0058701588 0.0932620000 0.0115020000 0.0308870000 0.0000290000 0.0002860000 0.0296800000 28548808 96830484 1768132608 4.0123338699 3.9612216949 3.9089162350 913 1311867200.8845369816 0.0876076147 0.0795991200 0.1207387596 0.0058696127 0.1296040000 0.0099600000 0.0483830000 0.0003720000 0.0002820000 0.0526420000 28551090 96830484 1769758720 4.0096158981 3.9609105587 3.9095940590 914 1311867200.9194929600 0.0889260918 0.0796093245 0.1207387596 0.0058691244 0.1375760000 0.0112660000 0.0707670000 0.0000300000 0.0002960000 0.0278070000 28553308 96830484 1768787968 4.0054244995 3.9600503445 3.9100968838 915 1311867200.9512679577 0.0884359330 0.0796189711 0.1207387596 0.0058680667 0.1354000000 0.0099560000 0.0707580000 0.0002960000 0.0002720000 0.0346490000 28555462 96830484 1770266624 4.0034031868 3.9601182938 3.9105727673 916 1311867200.9856009483 0.0887873098 0.0796289802 0.1207387596 0.0058695023 0.1350910000 0.0126420000 0.0722160000 0.0000290000 0.0002950000 0.0281920000 28557712 96830484 1769295872 4.0017886162 3.9594075680 3.9107763767 917 1311867201.0184400082 0.0891239196 0.0796393346 0.1207387596 0.0058663130 0.1520550000 0.0112200000 0.0708090000 0.0002930000 0.0002700000 0.0510330000 28559898 96830484 1768169472 3.9998991489 3.9594938755 3.9108235836 918 1311867201.0555179119 0.0892251953 0.0796497767 0.1207387596 0.0058648202 0.1344460000 0.0094710000 0.0717900000 0.0000270000 0.0003100000 0.0282190000 28562180 96830484 1769664512 3.9982600212 3.9597821236 3.9107017517 919 1311867201.0825428963 0.0900535956 0.0796610975 0.1207387596 0.0058647572 0.1363880000 0.0121040000 0.0708450000 0.0003070000 0.0002790000 0.0346470000 28564270 96830484 1768787968 3.9959003925 3.9591460228 3.9107561111 920 1311867201.1193449497 0.0905423760 0.0796729250 0.1207387596 0.0058624619 0.1316390000 0.0094660000 0.0704950000 0.0000290000 0.0003060000 0.0278330000 28566552 96830484 1770266624 3.9940333366 3.9591197968 3.9108178616 921 1311867201.1506710052 0.0905997530 0.0796847891 0.1207387596 0.0058593929 0.1263500000 0.0123970000 0.0421960000 0.0003250000 0.0002750000 0.0527350000 28568674 96830484 1769295872 3.9929184914 3.9593217373 3.9107561111 922 1311867201.1830160618 0.0901846439 0.0796961772 0.1207387596 0.0058578735 0.1037490000 0.0107980000 0.0415130000 0.0000290000 0.0010660000 0.0284100000 28570860 96830484 1768280064 3.9921791553 3.9587543011 3.9108633995 923 1311867201.2196528912 0.0915190876 0.0797089864 0.1207387596 0.0058560490 0.1348260000 0.0095290000 0.0706320000 0.0003060000 0.0003640000 0.0347960000 28573078 96830484 1769758720 3.9889295101 3.9597632885 3.9106597900 924 1311867201.2503149509 0.0911564007 0.0797213754 0.1207387596 0.0058528801 0.1348860000 0.0122940000 0.0714450000 0.0000280000 0.0003090000 0.0282980000 28575264 96830484 1768804352 3.9881196022 3.9599792957 3.9108622074 925 1311867201.2824099064 0.0903721675 0.0797328897 0.1207387596 0.0058503775 0.1514170000 0.0097670000 0.0704050000 0.0003590000 0.0002740000 0.0524820000 28577450 96830484 1770393600 3.9875245094 3.9604613781 3.9106235504 926 1311867201.3180539608 0.0904048011 0.0797444145 0.1207387596 0.0058485312 0.1177140000 0.0113990000 0.0535070000 0.0000280000 0.0002890000 0.0283280000 28579700 96830484 1769168896 3.9851324558 3.9590415955 3.9105889797 927 1311867201.3522200584 0.0913914219 0.0797569787 0.1207387596 0.0058481145 0.1141230000 0.0115020000 0.0415540000 0.0002960000 0.0002690000 0.0345680000 28581918 96830484 1765842944 3.9821045399 3.9606103897 3.9103462696 928 1311867201.3842790127 0.0908222646 0.0797689025 0.1207387596 0.0058480722 0.1112810000 0.0098150000 0.0476260000 0.0000310000 0.0003000000 0.0286950000 28584104 96830484 1766629376 3.9806530476 3.9621989727 3.9103364944 929 1311867201.4198760986 0.0903210118 0.0797802610 0.1207387596 0.0058669933 0.1308750000 0.0097430000 0.0355610000 0.0002050000 0.0001860000 0.0559420000 28586290 96830484 1765486592 3.9772963524 3.9605376720 3.9099125862 930 1311867201.4558579922 0.0907047689 0.0797920078 0.1207387596 0.0058691019 0.0949940000 0.0101140000 0.0359100000 0.0000280000 0.0003570000 0.0281950000 28588476 96830484 1766998016 3.9738674164 3.9617512226 3.9097328186 931 1311867201.4853110313 0.0911088064 0.0798041634 0.1207387596 0.0058684850 0.1297130000 0.0093390000 0.0532870000 0.0002920000 0.0003000000 0.0346550000 28590630 96830484 1768742912 3.9714150429 3.9643788338 3.9096832275 932 1311867201.5198690891 0.0906557813 0.0798158067 0.1207387596 0.0058670887 0.1156190000 0.0100130000 0.0442540000 0.0000280000 0.0002860000 0.0322800000 28592880 96830484 1770393600 3.9685235023 3.9633672237 3.9097669125 933 1311867201.5527739525 0.0916986242 0.0798285429 0.1207387596 0.0058656458 0.1539770000 0.0125070000 0.0698330000 0.0003020000 0.0002810000 0.0525210000 28595034 96830484 1769418752 3.9641036987 3.9638216496 3.9094586372 934 1311867201.5840220451 0.0910760462 0.0798405852 0.1207387596 0.0058625942 0.1356520000 0.0108720000 0.0693800000 0.0000310000 0.0006980000 0.0283390000 28597220 96830484 1768005632 3.9625937939 3.9640758038 3.9093811512 935 1311867201.6197049618 0.0905603692 0.0798520502 0.1207387596 0.0058597920 0.1119010000 0.0099620000 0.0355520000 0.0002920000 0.0002670000 0.0369330000 28599470 96830484 1769664512 3.9609031677 3.9642641544 3.9089927673 936 1311867201.6515579224 0.0893144011 0.0798621595 0.1207387596 0.0058589245 0.1358350000 0.0119950000 0.0689320000 0.0000260000 0.0003570000 0.0286710000 28601624 96830484 1768808448 3.9599571228 3.9639089108 3.9087822437 937 1311867201.6839449406 0.0899300575 0.0798729043 0.1207387596 0.0058558393 0.1304070000 0.0101290000 0.0477190000 0.0007130000 0.0003640000 0.0529700000 28603842 96830484 1770266624 3.9569432735 3.9648373127 3.9083180428 938 1311867201.7189009190 0.0905401185 0.0798842766 0.1207387596 0.0058556533 0.1384270000 0.0110330000 0.0695950000 0.0000270000 0.0003680000 0.0280430000 28606092 96830484 1769295872 3.9547786713 3.9663450718 3.9083085060 939 1311867201.7507290840 0.0898506865 0.0798948905 0.1207387596 0.0058540006 0.1354280000 0.0111230000 0.0704460000 0.0003330000 0.0002810000 0.0345810000 28608278 96830484 1768169472 3.9530587196 3.9655575752 3.9079442024 940 1311867201.7858049870 0.0898463055 0.0799054771 0.1207387596 0.0058574345 0.1115790000 0.0098050000 0.0475590000 0.0000230000 0.0005680000 0.0279950000 28610464 96830484 1769758720 3.9505262375 3.9659645557 3.9077069759 941 1311867201.8190178871 0.0897442847 0.0799159328 0.1207387596 0.0058640099 0.1529840000 0.0125170000 0.0533040000 0.0002930000 0.0003480000 0.0552040000 28612714 96830484 1768804352 3.9500815868 3.9689168930 3.9079015255 942 1311867201.8505740166 0.0893186405 0.0799259144 0.1207387596 0.0058665557 0.1135060000 0.0097820000 0.0477500000 0.0000340000 0.0006480000 0.0276910000 28614868 96830484 1770520576 3.9486362934 3.9678351879 3.9076144695 943 1311867201.8862850666 0.0888456777 0.0799353734 0.1207387596 0.0058637432 0.1360990000 0.0123160000 0.0685650000 0.0002960000 0.0002700000 0.0347840000 28617086 96830484 1769672704 3.9479846954 3.9677519798 3.9075281620 944 1311867201.9195730686 0.0898208097 0.0799458452 0.1207387596 0.0058631532 0.1331990000 0.0117290000 0.0704980000 0.0000270000 0.0006660000 0.0279640000 28619336 96830484 1768271872 3.9459764957 3.9690866470 3.9073703289 945 1311867201.9516520500 0.0896360204 0.0799560994 0.1207387596 0.0058611567 0.1514640000 0.0099830000 0.0713650000 0.0002850000 0.0002630000 0.0509870000 28621458 96830484 1770049536 3.9447336197 3.9686005116 3.9068439007 946 1311867201.9894599915 0.0885951221 0.0799652315 0.1207387596 0.0058585734 0.1162290000 0.0117520000 0.0479550000 0.0000290000 0.0003150000 0.0280980000 28623772 96830484 1767903232 3.9449381828 3.9686720371 3.9062545300 947 1311867202.0184879303 0.0891911164 0.0799749738 0.1207387596 0.0058560438 0.1522660000 0.0103480000 0.0779570000 0.0003830000 0.0002810000 0.0361030000 28625894 96830484 1769517056 3.9432110786 3.9692275524 3.9057562351 948 1311867202.0507359505 0.0883316845 0.0799837889 0.1207387596 0.0058538323 0.1529990000 0.0136570000 0.0839250000 0.0000290000 0.0002940000 0.0278540000 28628080 96830484 1767489536 3.9436380863 3.9698741436 3.9052543640 949 1311867202.0866351128 0.0888513029 0.0799931329 0.1207387596 0.0058510564 0.1514990000 0.0102120000 0.0694520000 0.0003710000 0.0002910000 0.0524070000 28630330 96830484 1769304064 3.9420611858 3.9702196121 3.9048650265 950 1311867202.1185920238 0.0897509083 0.0800034043 0.1207387596 0.0058492203 0.1142780000 0.0098030000 0.0411260000 0.0000300000 0.0010830000 0.0279380000 28632516 96830484 1770954752 3.9394183159 3.9706258774 3.9045948982 951 1311867202.1516621113 0.0896125361 0.0800135085 0.1207387596 0.0058472945 0.1537310000 0.0132030000 0.0772430000 0.0003140000 0.0003510000 0.0348470000 28634734 96830484 1769033728 3.9386425018 3.9718165398 3.9046561718 952 1311867202.1866259575 0.0879597142 0.0800218554 0.1207387596 0.0058451648 0.1331190000 0.0104410000 0.0699290000 0.0000300000 0.0003020000 0.0279750000 28636952 96830484 1770684416 3.9394600391 3.9718248844 3.9046230316 953 1311867202.2191269398 0.0892093778 0.0800314960 0.1207387596 0.0058430410 0.1720470000 0.0125650000 0.0705680000 0.0003010000 0.0003520000 0.0551050000 28639138 96830484 1768648704 3.9364767075 3.9721939564 3.9044625759 954 1311867202.2513220310 0.0887510702 0.0800406360 0.1207387596 0.0058402792 0.1344840000 0.0103520000 0.0712070000 0.0000310000 0.0002990000 0.0283550000 28641292 96830484 1770323968 3.9358265400 3.9729681015 3.9046061039 955 1311867202.2868280411 0.0880240873 0.0800489956 0.1207387596 0.0058383540 0.1146660000 0.0114360000 0.0471300000 0.0003160000 0.0002730000 0.0345390000 28643542 96830484 1769562112 3.9354159832 3.9738998413 3.9045979977 956 1311867202.3199880123 0.0886856765 0.0800580298 0.1207387596 0.0058368545 0.1321800000 0.0116320000 0.0635200000 0.0000280000 0.0003030000 0.0282160000 28645728 96830484 1768128512 3.9328365326 3.9723672867 3.9045541286 957 1311867202.3523900509 0.0881567821 0.0800664925 0.1207387596 0.0058343340 0.1509950000 0.0102190000 0.0695510000 0.0002980000 0.0003550000 0.0519520000 28647914 96830484 1769795584 3.9318881035 3.9727263451 3.9043903351 958 1311867202.3883628845 0.0879781842 0.0800747510 0.1207387596 0.0058314792 0.1357830000 0.0114100000 0.0650670000 0.0000270000 0.0002930000 0.0279330000 28650164 96830484 1768923136 3.9307167530 3.9742257595 3.9044125080 959 1311867202.4196391106 0.0881600603 0.0800831820 0.1207387596 0.0058299573 0.1531110000 0.0098960000 0.0746510000 0.0003020000 0.0003600000 0.0387460000 28652350 96830484 1770684416 3.9294872284 3.9738926888 3.9043643475 960 1311867202.4529430866 0.0881414935 0.0800915761 0.1207387596 0.0058273092 0.1373190000 0.0125230000 0.0764540000 0.0000290000 0.0003650000 0.0291220000 28654536 96830484 1769926656 3.9285168648 3.9729003906 3.9044332504 961 1311867202.4875710011 0.0887506455 0.0801005866 0.1207387596 0.0058269700 0.1695000000 0.0110620000 0.0701080000 0.0003130000 0.0002710000 0.0684100000 28656754 96830484 1769164800 3.9275057316 3.9739637375 3.9048063755 962 1311867202.5206449032 0.0890618935 0.0801099018 0.1207387596 0.0058417390 0.1548300000 0.0104040000 0.0868220000 0.0000310000 0.0002980000 0.0306520000 28658940 96830484 1770795008 3.9260532856 3.9747519493 3.9046065807 963 1311867202.5508940220 0.0895644575 0.0801197197 0.1207387596 0.0058388201 0.1147260000 0.0123740000 0.0469570000 0.0003650000 0.0002880000 0.0341890000 28661094 96830484 1768144896 3.9246406555 3.9743309021 3.9047684669 964 1311867202.5864949226 0.0903063640 0.0801302867 0.1207387596 0.0058481205 0.0924150000 0.0099540000 0.0362910000 0.0000260000 0.0003550000 0.0269020000 28663376 96830484 1767870464 3.9230742455 3.9735612869 3.9047513008 965 1311867202.6185030937 0.0904193372 0.0801409489 0.1207387596 0.0058493269 0.1599830000 0.0105350000 0.0775200000 0.0002980000 0.0002710000 0.0523260000 28665562 96830484 1767534592 3.9215822220 3.9735355377 3.9041528702 966 1311867202.6514449120 0.0914716199 0.0801526784 0.1207387596 0.0058541692 0.1043690000 0.0095830000 0.0407860000 0.0000280000 0.0002910000 0.0283090000 28667748 96830484 1769123840 3.9185945988 3.9745554924 3.9034128189 967 1311867202.6866559982 0.0910091922 0.0801639054 0.1207387596 0.0058517028 0.1366480000 0.0115060000 0.0706600000 0.0003530000 0.0002730000 0.0347040000 28669998 96830484 1768169472 3.9179093838 3.9752757549 3.9027488232 968 1311867202.7185359001 0.0913222805 0.0801754327 0.1207387596 0.0058491629 0.1116570000 0.0104310000 0.0473270000 0.0000320000 0.0003140000 0.0280370000 28672184 96830484 1769664512 3.9154436588 3.9738860130 3.9016070366 969 1311867202.7507350445 0.0909521282 0.0801865541 0.1207387596 0.0058472111 0.1314740000 0.0120980000 0.0467910000 0.0002910000 0.0003400000 0.0529630000 28674370 96830484 1768787968 3.9138300419 3.9728577137 3.9002852440 970 1311867202.7897169590 0.0915393904 0.0801982581 0.1207387596 0.0058446130 0.0989830000 0.0094520000 0.0407090000 0.0000300000 0.0002870000 0.0290600000 28676684 96830484 1770393600 3.9120125771 3.9738695621 3.8994181156 971 1311867202.8190000057 0.0917898193 0.0802101958 0.1207387596 0.0058432869 0.1164370000 0.0118630000 0.0520540000 0.0002950000 0.0003550000 0.0328820000 28678838 96830484 1769549824 3.9101996422 3.9740819931 3.8983852863 972 1311867202.8527579308 0.0909212902 0.0802212155 0.1207387596 0.0058403641 0.1320810000 0.0105560000 0.0693640000 0.0000250000 0.0002890000 0.0289210000 28681024 96830484 1768804352 3.9092402458 3.9738492966 3.8973782063 973 1311867202.8873219490 0.0904139355 0.0802316910 0.1207387596 0.0058395893 0.1519430000 0.0095750000 0.0687390000 0.0002990000 0.0002740000 0.0542420000 28683242 96830484 1770393600 3.9088978767 3.9755334854 3.8969545364 974 1311867202.9199879169 0.0901468992 0.0802418709 0.1207387596 0.0058372990 0.1357420000 0.0116650000 0.0647190000 0.0000280000 0.0002860000 0.0299690000 28685428 96830484 1769422848 3.9089729786 3.9760556221 3.8972291946 975 1311867202.9525690079 0.0908464044 0.0802527474 0.1207387596 0.0058409724 0.1334440000 0.0113370000 0.0502130000 0.0003830000 0.0002860000 0.0424750000 28687646 96830484 1768275968 3.9078731537 3.9752016068 3.8972644806 976 1311867202.9868710041 0.0889865011 0.0802616959 0.1207387596 0.0058463068 0.1116730000 0.0096320000 0.0411540000 0.0000260000 0.0003610000 0.0296370000 28689864 96830484 1769918464 3.9099009037 3.9756414890 3.8978133202 977 1311867203.0202019215 0.0894738883 0.0802711250 0.1207387596 0.0058433501 0.1667520000 0.0121550000 0.0775080000 0.0002950000 0.0003480000 0.0574480000 28692050 96830484 1769185280 3.9094653130 3.9759974480 3.8981885910 978 1311867203.0560851097 0.0900260285 0.0802810993 0.1207387596 0.0058466876 0.1414590000 0.0103520000 0.0685030000 0.0000260000 0.0003570000 0.0332980000 28694300 96830484 1768423424 3.9091746807 3.9732520580 3.8986647129 979 1311867203.0865778923 0.0904606581 0.0802914972 0.1207387596 0.0058451496 0.1133390000 0.0117180000 0.0341690000 0.0003530000 0.0002810000 0.0419150000 28696454 96830484 1770139648 3.9100546837 3.9734914303 3.8991863728 980 1311867203.1189930439 0.0899900123 0.0803013936 0.1207387596 0.0058517569 0.1525210000 0.0123460000 0.0762710000 0.0000280000 0.0003030000 0.0308200000 28698640 96830484 1769291776 3.9112002850 3.9715619087 3.8995022774 981 1311867203.1549820900 0.0907758772 0.0803120710 0.1207387596 0.0058568315 0.1669850000 0.0117140000 0.0816950000 0.0003180000 0.0002800000 0.0536960000 28700890 96830484 1768550400 3.9105782509 3.9696762562 3.8995947838 982 1311867203.1877939701 0.0925720111 0.0803245557 0.1207387596 0.0058895742 0.1216930000 0.0093510000 0.0590930000 0.0000280000 0.0003090000 0.0284850000 28703076 96830484 1770139648 3.9089207649 3.9679713249 3.8993766308 983 1311867203.2185909748 0.0929369479 0.0803373862 0.1207387596 0.0058895734 0.1529220000 0.0122210000 0.0703840000 0.0003040000 0.0002830000 0.0356250000 28705262 96830484 1769037824 3.9101185799 3.9696147442 3.8993303776 984 1311867203.2552030087 0.0932162479 0.0803504745 0.1207387596 0.0058878829 0.1331710000 0.0095480000 0.0619160000 0.0000290000 0.0003810000 0.0325570000 28707512 96830484 1770774528 3.9099793434 3.9675042629 3.8991177082 985 1311867203.2864799500 0.0936274901 0.0803639537 0.1207387596 0.0058873726 0.1555000000 0.0120790000 0.0696190000 0.0003130000 0.0004600000 0.0538170000 28709666 96830484 1769926656 3.9092972279 3.9662830830 3.8984532356 986 1311867203.3194670677 0.0928654671 0.0803766327 0.1207387596 0.0058848233 0.1355470000 0.0110230000 0.0708160000 0.0000300000 0.0003770000 0.0289990000 28711916 96830484 1768894464 3.9107081890 3.9661939144 3.8980371952 987 1311867203.3547461033 0.0925251469 0.0803889412 0.1207387596 0.0058830037 0.1126870000 0.0099990000 0.0413470000 0.0009780000 0.0003020000 0.0350580000 28714102 96830484 1770553344 3.9116971493 3.9663434029 3.8978209496 988 1311867203.3865599632 0.0917746201 0.0804004652 0.1207387596 0.0058859076 0.1326240000 0.0127990000 0.0599250000 0.0000290000 0.0003110000 0.0281000000 28716288 96830484 1769549824 3.9123718739 3.9646670818 3.8975737095 989 1311867203.4183609486 0.0913590342 0.0804115456 0.1207387596 0.0058918391 0.1675060000 0.0115490000 0.0798020000 0.0003880000 0.0002870000 0.0562080000 28718506 96830484 1768804352 3.9119365215 3.9606723785 3.8968005180 990 1311867203.4545118809 0.0921964496 0.0804234496 0.1207387596 0.0058899477 0.1572900000 0.0093240000 0.0851940000 0.0000290000 0.0003140000 0.0285510000 28720756 96830484 1770266624 3.9112739563 3.9604451656 3.8965988159 991 1311867203.4864439964 0.0911420062 0.0804342655 0.1207387596 0.0058883925 0.1380340000 0.0121050000 0.0696610000 0.0003760000 0.0002830000 0.0350040000 28722910 96830484 1769312256 3.9122266769 3.9584729671 3.8964803219 992 1311867203.5185539722 0.0916117802 0.0804455331 0.1207387596 0.0058899572 0.1236040000 0.0111120000 0.0703500000 0.0000270000 0.0003020000 0.0221220000 28725128 96830484 1768169472 3.9112942219 3.9553139210 3.8957443237 993 1311867203.5560259819 0.0922272354 0.0804573979 0.1207387596 0.0058874370 0.1404670000 0.0091050000 0.0415130000 0.0009790000 0.0006470000 0.0568250000 28727378 96830484 1769758720 3.9106135368 3.9531042576 3.8951079845 994 1311867203.5876550674 0.0922618434 0.0804692736 0.1207387596 0.0058850864 0.1147090000 0.0122570000 0.0423620000 0.0000270000 0.0003070000 0.0293190000 28729564 96830484 1768534016 3.9108183384 3.9522440434 3.8947756290 995 1311867203.6191980839 0.0921490863 0.0804810121 0.1207387596 0.0058833782 0.0950290000 0.0097320000 0.0361100000 0.0001180000 0.0001050000 0.0295670000 28731750 96830484 1767391232 3.9106924534 3.9496245384 3.8944654465 996 1311867203.6557719707 0.0909615085 0.0804915347 0.1207387596 0.0058807853 0.1462720000 0.0094060000 0.0730340000 0.0000320000 0.0003800000 0.0293220000 28733968 96830484 1766395904 3.9119751453 3.9469375610 3.8938083649 997 1311867203.6866750717 0.0923079029 0.0805033866 0.1207387596 0.0058791224 0.1743910000 0.0098390000 0.0775210000 0.0003170000 0.0003450000 0.0571940000 28736154 96830484 1767854080 3.9099283218 3.9455442429 3.8933031559 998 1311867203.7195260525 0.0912934616 0.0805141983 0.1207387596 0.0058771976 0.1345880000 0.0097380000 0.0702810000 0.0000280000 0.0003070000 0.0287450000 28738340 96830484 1769504768 3.9115872383 3.9437830448 3.8930644989 999 1311867203.7566421032 0.0917728245 0.0805254682 0.1207387596 0.0058746070 0.1154340000 0.0120830000 0.0426320000 0.0003190000 0.0003540000 0.0352760000 28740622 96830484 1768534016 3.9116575718 3.9425561428 3.8930237293 1000 1311867203.7867228985 0.0919231772 0.0805368659 0.1207387596 0.0058716894 0.1323880000 0.0099360000 0.0695080000 0.0000280000 0.0002920000 0.0292730000 28742776 96830484 1770139648 3.9113788605 3.9405264854 3.8926959038 1001 1311867203.8193860054 0.0915399492 0.0805478580 0.1207387596 0.0058689357 0.1284880000 0.0121390000 0.0426740000 0.0003530000 0.0002770000 0.0536900000 28744962 96830484 1769168896 3.9120826721 3.9391484261 3.8921706676 1002 1311867203.8572859764 0.0921291783 0.0805594162 0.1207387596 0.0058674912 0.1012930000 0.0106550000 0.0349700000 0.0000260000 0.0003530000 0.0306890000 28747244 96830484 1768042496 3.9115140438 3.9379935265 3.8914716244 1003 1311867203.8891890049 0.0922226012 0.0805710445 0.1207387596 0.0058652452 0.1142020000 0.0097370000 0.0476360000 0.0003000000 0.0003500000 0.0356640000 28749430 96830484 1769631744 3.9110033512 3.9360892773 3.8905284405 1004 1311867203.9188020229 0.0921683535 0.0805825956 0.1207387596 0.0058628039 0.1344860000 0.0120660000 0.0698800000 0.0000240000 0.0002910000 0.0291520000 28751584 96830484 1768534016 3.9107921124 3.9346287251 3.8896958828 1005 1311867203.9553489685 0.0928325579 0.0805947846 0.1207387596 0.0058602546 0.1521180000 0.0104730000 0.0692560000 0.0002880000 0.0003500000 0.0525080000 28753834 96830484 1770172416 3.9103531837 3.9357240200 3.8886878490 1006 1311867203.9866371155 0.0920518562 0.0806061733 0.1207387596 0.0058608464 0.1357160000 0.0111380000 0.0708990000 0.0000290000 0.0002880000 0.0288940000 28756020 96830484 1769316352 3.9107058048 3.9325380325 3.8876888752 1007 1311867204.0199849606 0.0917919427 0.0806172814 0.1207387596 0.0058593198 0.1327940000 0.0111940000 0.0584480000 0.0003560000 0.0002840000 0.0363810000 28758206 96830484 1768153088 3.9111418724 3.9324164391 3.8864448071 1008 1311867204.0551509857 0.0931734666 0.0806297379 0.1207387596 0.0058567731 0.1326200000 0.0095650000 0.0688860000 0.0000280000 0.0003600000 0.0286940000 28760456 96830484 1769631744 3.9092309475 3.9311318398 3.8853631020 1009 1311867204.0867509842 0.0917239562 0.0806407332 0.1207387596 0.0058569638 0.1334060000 0.0117070000 0.0469940000 0.0002950000 0.0002720000 0.0543910000 28762642 96830484 1768660992 3.9104769230 3.9291453362 3.8841750622 1010 1311867204.1191530228 0.0923056751 0.0806522826 0.1207387596 0.0058542178 0.1352150000 0.0092410000 0.0706540000 0.0000290000 0.0002930000 0.0292270000 28764828 96830484 1770266624 3.9099400043 3.9280564785 3.8831610680 1011 1311867204.1555769444 0.0922042355 0.0806637089 0.1207387596 0.0058516465 0.1185050000 0.0125260000 0.0528700000 0.0002950000 0.0002670000 0.0330490000 28767046 96830484 1769295872 3.9100673199 3.9263632298 3.8823869228 1012 1311867204.1876530647 0.0914544389 0.0806743716 0.1207387596 0.0058507712 0.1476790000 0.0106990000 0.0717870000 0.0000280000 0.0002880000 0.0297250000 28769232 96830484 1768169472 3.9107928276 3.9246764183 3.8816888332 1013 1311867204.2187769413 0.0926095396 0.0806861536 0.1207387596 0.0058492792 0.1524670000 0.0094680000 0.0675140000 0.0007130000 0.0002930000 0.0550480000 28771418 96830484 1769631744 3.9095661640 3.9241302013 3.8812489510 1014 1311867204.2566440105 0.0919019803 0.0806972146 0.1207387596 0.0058469076 0.0984500000 0.0108210000 0.0360650000 0.0000270000 0.0003980000 0.0311050000 28773700 96830484 1765601280 3.9107415676 3.9224221706 3.8808202744 1015 1311867204.2867140770 0.0918784663 0.0807082306 0.1207387596 0.0058443563 0.1285970000 0.0096450000 0.0541100000 0.0003650000 0.0002960000 0.0365750000 28775854 96830484 1767010304 3.9103033543 3.9200494289 3.8800675869 1016 1311867204.3204538822 0.0925060213 0.0807198426 0.1207387596 0.0058417404 0.1132570000 0.0094970000 0.0462050000 0.0000260000 0.0003090000 0.0299440000 28778040 96830484 1764700160 3.9099400043 3.9195265770 3.8797242641 1017 1311867204.3625741005 0.0932226330 0.0807321364 0.1207387596 0.0058389640 0.1332720000 0.0095670000 0.0463450000 0.0003940000 0.0002840000 0.0568770000 28780418 96830484 1765105664 3.9092144966 3.9179909229 3.8796470165 1018 1311867204.3869600296 0.0940870568 0.0807452552 0.1207387596 0.0058364024 0.1348880000 0.0090830000 0.0669540000 0.0000300000 0.0003900000 0.0303460000 28782476 96830484 1762029568 3.9077849388 3.9167137146 3.8791887760 1019 1311867204.4240970612 0.0943585560 0.0807586147 0.1207387596 0.0058337130 0.1338020000 0.0098000000 0.0671950000 0.0003830000 0.0002890000 0.0362680000 28784758 96830484 1763704832 3.9076447487 3.9152729511 3.8789215088 1020 1311867204.4549949169 0.0947917700 0.0807723727 0.1207387596 0.0058319677 0.0937600000 0.0096800000 0.0341480000 0.0000300000 0.0007090000 0.0296940000 28786912 96830484 1765347328 3.9074587822 3.9147853851 3.8787860870 1021 1311867204.4872748852 0.0944490284 0.0807857680 0.1207387596 0.0058305175 0.1600250000 0.0098400000 0.0730660000 0.0003070000 0.0003620000 0.0569770000 28789098 96830484 1767092224 3.9075388908 3.9126193523 3.8783442974 1022 1311867204.5237219334 0.0960030705 0.0808006578 0.1207387596 0.0058280809 0.1264840000 0.0089140000 0.0570040000 0.0000300000 0.0003720000 0.0308180000 28791380 96830484 1768759296 3.9055762291 3.9112243652 3.8780951500 1023 1311867204.5581860542 0.0963458270 0.0808158534 0.1207387596 0.0058272438 0.1136070000 0.0091940000 0.0345570000 0.0003190000 0.0002900000 0.0378560000 28793598 96830484 1770520576 3.9055216312 3.9112119675 3.8779273033 1024 1311867204.5878469944 0.0960834324 0.0808307632 0.1207387596 0.0058251388 0.1414720000 0.0115750000 0.0716160000 0.0000280000 0.0003070000 0.0381280000 28795752 96830484 1769422848 3.9050834179 3.9086241722 3.8778624535 1025 1311867204.6241528988 0.0965165868 0.0808460664 0.1207387596 0.0058224823 0.1512670000 0.0100370000 0.0658780000 0.0003760000 0.0002780000 0.0543130000 28879922 96830484 1768534016 3.9038929939 3.9081177711 3.8778882027 1026 1311867204.6541819572 0.0965046287 0.0808613282 0.1207387596 0.0058199891 0.1318990000 0.0086910000 0.0668920000 0.0000310000 0.0003080000 0.0311310000 29050012 96830484 1770012672 3.9037623405 3.9060595036 3.8781144619 1027 1311867204.6871540546 0.0964937434 0.0808765496 0.1207387596 0.0058175002 0.1343230000 0.0116350000 0.0676610000 0.0003110000 0.0003540000 0.0343430000 29052198 96830484 1769189376 3.9036147594 3.9050545692 3.8781399727 1028 1311867204.7225689888 0.0977087468 0.0808929233 0.1207387596 0.0058171086 0.1283090000 0.0108810000 0.0517240000 0.0000300000 0.0002980000 0.0311460000 29054448 96830484 1768042496 3.9024939537 3.9052264690 3.8785083294 1029 1311867204.7539510727 0.0985571519 0.0809100897 0.1207387596 0.0058145622 0.1637970000 0.0092340000 0.0717170000 0.0003860000 0.0002920000 0.0624270000 29056634 96830484 1769504768 3.9004130363 3.9034416676 3.8788731098 1030 1311867204.7878720760 0.0981436521 0.0809268214 0.1207387596 0.0058127906 0.1435780000 0.0109790000 0.0663810000 0.0000290000 0.0003040000 0.0313740000 29058852 96830484 1768280064 3.8998196125 3.9016468525 3.8796172142 1031 1311867204.8227200508 0.0979936719 0.0809433750 0.1207387596 0.0058106348 0.1317060000 0.0091170000 0.0521170000 0.0003090000 0.0003550000 0.0423100000 29061070 96830484 1769885696 3.8999578953 3.9015810490 3.8810870647 1032 1311867204.8542668819 0.0968735814 0.0809588113 0.1207387596 0.0058103437 0.1353540000 0.0115500000 0.0665180000 0.0000280000 0.0002990000 0.0309930000 29063256 96830484 1768935424 3.9002771378 3.8993349075 3.8820996284 1033 1311867204.8864960670 0.0970880166 0.0809744252 0.1207387596 0.0058082203 0.1540170000 0.0090500000 0.0669210000 0.0003070000 0.0003570000 0.0576970000 29065442 96830484 1770401792 3.8992111683 3.8963146210 3.8832087517 1034 1311867204.9220221043 0.0983122066 0.0809911929 0.1207387596 0.0058056363 0.1150170000 0.0107060000 0.0460930000 0.0000280000 0.0003890000 0.0314740000 29067692 96830484 1768775680 3.8974187374 3.8949775696 3.8844232559 1035 1311867204.9542920589 0.0989958495 0.0810085887 0.1207387596 0.0058029842 0.1343540000 0.0107080000 0.0679780000 0.0003040000 0.0003590000 0.0349410000 29069878 96830484 1768050688 3.8962113857 3.8937375546 3.8854193687 1036 1311867204.9865999222 0.0973279178 0.0810243410 0.1207387596 0.0058019097 0.1116910000 0.0088260000 0.0498560000 0.0000300000 0.0003040000 0.0308660000 29072064 96830484 1769529344 3.8977866173 3.8903596401 3.8861389160 1037 1311867205.0227239132 0.0973769650 0.0810401101 0.1207387596 0.0058031021 0.1556350000 0.0112740000 0.0677700000 0.0003070000 0.0003630000 0.0556780000 29074314 96830484 1768267776 3.8977494240 3.8886179924 3.8868989944 1038 1311867205.0550808907 0.0968830064 0.0810553730 0.1207387596 0.0058167758 0.1115060000 0.0086720000 0.0441590000 0.0000180000 0.0002040000 0.0309010000 29076532 96830484 1769926656 3.8980786800 3.8884296417 3.8877358437 1039 1311867205.0880999565 0.0972018763 0.0810709135 0.1207387596 0.0058143017 0.1332820000 0.0121730000 0.0504570000 0.0003060000 0.0002860000 0.0378260000 29078654 96830484 1769070592 3.8971912861 3.8856277466 3.8885660172 1040 1311867205.1232450008 0.0992986485 0.0810884401 0.1207387596 0.0058144266 0.1118170000 0.0094160000 0.0393800000 0.0000100000 0.0000990000 0.0339870000 29080904 96830484 1770528768 3.8952608109 3.8845551014 3.8892750740 1041 1311867205.1545319557 0.0982069150 0.0811048844 0.1207387596 0.0058202023 0.1678400000 0.0126460000 0.0744050000 0.0003170000 0.0002820000 0.0600200000 29083058 96830484 1769558016 3.8979239464 3.8835930824 3.8900172710 1042 1311867205.1863510609 0.0980048478 0.0811211032 0.1207387596 0.0058270463 0.1396670000 0.0104020000 0.0631050000 0.0000300000 0.0003030000 0.0315980000 29085244 96830484 1768415232 3.8978393078 3.8808374405 3.8907389641 1043 1311867205.2223129272 0.0987359360 0.0811379918 0.1207387596 0.0058261672 0.1381730000 0.0090470000 0.0693820000 0.0003160000 0.0003700000 0.0390030000 29087494 96830484 1769893888 3.8967270851 3.8789854050 3.8912808895 1044 1311867205.2541849613 0.0973854214 0.0811535545 0.1207387596 0.0058245270 0.1329420000 0.0110310000 0.0649590000 0.0000290000 0.0003050000 0.0309150000 29089680 96830484 1768669184 3.8982129097 3.8773458004 3.8919620514 1045 1311867205.2880499363 0.0979147330 0.0811695939 0.1207387596 0.0058221263 0.1236940000 0.0094810000 0.0331500000 0.0003110000 0.0003690000 0.0604050000 29091898 96830484 1770274816 3.8976206779 3.8754594326 3.8928678036 1046 1311867205.3218879700 0.0980115905 0.0811856952 0.1207387596 0.0058205799 0.1420980000 0.0106010000 0.0661610000 0.0000300000 0.0003000000 0.0315890000 29094084 96830484 1769320448 3.8971526623 3.8730666637 3.8935439587 1047 1311867205.3542900085 0.0979742855 0.0812017301 0.1207387596 0.0058252563 0.1348640000 0.0103550000 0.0633130000 0.0003050000 0.0002860000 0.0390380000 29096302 96830484 1768177664 3.8971211910 3.8714475632 3.8945212364 1048 1311867205.3862779140 0.0987273902 0.0812184531 0.1207387596 0.0058324911 0.1315320000 0.0090440000 0.0651430000 0.0000290000 0.0003010000 0.0309360000 29098488 96830484 1769656320 3.8957946301 3.8702151775 3.8955569267 1049 1311867205.4225649834 0.0984642580 0.0812348933 0.1207387596 0.0058359794 0.1294290000 0.0116270000 0.0385090000 0.0003010000 0.0003660000 0.0583140000 29100738 96830484 1768796160 3.8951122761 3.8681497574 3.8960690498 1050 1311867205.4540419579 0.0981174707 0.0812509720 0.1207387596 0.0058379276 0.1179580000 0.0082380000 0.0492880000 0.0000290000 0.0003110000 0.0313630000 29102924 96830484 1770401792 3.8955249786 3.8674912453 3.8969929218 1051 1311867205.4865119457 0.0978677049 0.0812667824 0.1207387596 0.0058387438 0.1367400000 0.0111440000 0.0644480000 0.0003040000 0.0002920000 0.0377500000 29105110 96830484 1769177088 3.8941817284 3.8655221462 3.8981304169 1052 1311867205.5230340958 0.0972544700 0.0812819798 0.1207387596 0.0058492161 0.1317070000 0.0105650000 0.0629090000 0.0000300000 0.0003010000 0.0315600000 29107360 96830484 1768161280 3.8938682079 3.8633983135 3.8988902569 1053 1311867205.5542900562 0.0983638018 0.0812982019 0.1207387596 0.0058709562 0.1515650000 0.0091580000 0.0490450000 0.0003800000 0.0002900000 0.0612960000 29109546 96830484 1769639936 3.8920557499 3.8639919758 3.8998706341 1054 1311867205.5866839886 0.0978994668 0.0813139526 0.1207387596 0.0058682174 0.1346610000 0.0116270000 0.0639630000 0.0000290000 0.0003100000 0.0313810000 29111732 96830484 1768669184 3.8916440010 3.8627727032 3.9011175632 1055 1311867205.6226179600 0.0981874093 0.0813299464 0.1207387596 0.0058704787 0.1158620000 0.0087560000 0.0378970000 0.0002940000 0.0002770000 0.0377340000 29113982 96830484 1770164224 3.8890876770 3.8592827320 3.9020009041 1056 1311867205.6555979252 0.0994662419 0.0813471209 0.1207387596 0.0058687913 0.1545920000 0.0113560000 0.0845810000 0.0000280000 0.0003680000 0.0380590000 29116168 96830484 1769172992 3.8863732815 3.8576953411 3.9028553963 1057 1311867205.6902959347 0.0984620824 0.0813633129 0.1207387596 0.0058662841 0.1295340000 0.0096720000 0.0354880000 0.0000920000 0.0001060000 0.0642220000 29118418 96830484 1770782720 3.8870053291 3.8559508324 3.9036164284 1058 1311867205.7222061157 0.0980243832 0.0813790606 0.1207387596 0.0058635482 0.1361650000 0.0103110000 0.0640780000 0.0000950000 0.0002900000 0.0312360000 29120604 96830484 1769558016 3.8862519264 3.8529596329 3.9041182995 1059 1311867205.7548348904 0.0978019759 0.0813945686 0.1207387596 0.0058610662 0.1113090000 0.0107970000 0.0318830000 0.0000810000 0.0003980000 0.0384250000 29122822 96830484 1765720064 3.8854551315 3.8507974148 3.9043717384 1060 1311867205.7906379700 0.0987580270 0.0814109492 0.1207387596 0.0058592682 0.1341460000 0.0095950000 0.0692470000 0.0000260000 0.0002890000 0.0346020000 29125040 96830484 1767165952 3.8837859631 3.8494153023 3.9052813053 1061 1311867205.8232109547 0.0976651087 0.0814262689 0.1207387596 0.0058702886 0.1692540000 0.0086160000 0.0645700000 0.0002980000 0.0005620000 0.0621310000 29127258 96830484 1765892096 3.8839414120 3.8461205959 3.9056353569 1062 1311867205.8554759026 0.0982971340 0.0814421548 0.1207387596 0.0058726708 0.1312760000 0.0094150000 0.0621250000 0.0000280000 0.0003020000 0.0319080000 29129476 96830484 1767481344 3.8824818134 3.8451979160 3.9062242508 1063 1311867205.8905880451 0.0993279219 0.0814589805 0.1207387596 0.0058725321 0.1351700000 0.0088200000 0.0624610000 0.0003050000 0.0002870000 0.0380640000 29131662 96830484 1769132032 3.8806414604 3.8445003033 3.9065427780 1064 1311867205.9223020077 0.0981080979 0.0814746282 0.1207387596 0.0058809793 0.1341640000 0.0105850000 0.0637300000 0.0000310000 0.0004030000 0.0319580000 29133848 96830484 1768177664 3.8814065456 3.8427333832 3.9068949223 1065 1311867205.9544939995 0.0980872959 0.0814902270 0.1207387596 0.0058786459 0.1263690000 0.0090730000 0.0378800000 0.0002960000 0.0003580000 0.0586780000 29136034 96830484 1769766912 3.8805842400 3.8406434059 3.9072270393 1066 1311867205.9905850887 0.1001289040 0.0815077116 0.1207387596 0.0058877645 0.1394190000 0.0104600000 0.0631010000 0.0000290000 0.0002900000 0.0318690000 29138316 96830484 1768542208 3.8781268597 3.8406941891 3.9077904224 1067 1311867206.0259850025 0.0995961502 0.0815246643 0.1207387596 0.0058884325 0.1135680000 0.0091150000 0.0364150000 0.0002990000 0.0007010000 0.0373890000 29140534 96830484 1770147840 3.8786919117 3.8406980038 3.9078509808 1068 1311867206.0604250431 0.0997658297 0.0815417440 0.1207387596 0.0058951241 0.1164480000 0.0113350000 0.0484530000 0.0000260000 0.0002960000 0.0316970000 29142720 96830484 1769197568 3.8769390583 3.8365712166 3.9080076218 1069 1311867206.0903289318 0.0992165655 0.0815582780 0.1207387596 0.0058926255 0.1532060000 0.0106580000 0.0619550000 0.0004630000 0.0005270000 0.0590100000 29144874 96830484 1768050688 3.8769605160 3.8339867592 3.9080109596 1070 1311867206.1227540970 0.0982825011 0.0815739081 0.1207387596 0.0058901355 0.1329830000 0.0083660000 0.0633430000 0.0000300000 0.0002990000 0.0312990000 29147060 96830484 1769512960 3.8784422874 3.8327081203 3.9084131718 1071 1311867206.1546130180 0.0987756625 0.0815899695 0.1207387596 0.0058875935 0.1366220000 0.0107580000 0.0623160000 0.0003580000 0.0002690000 0.0380380000 29149246 96830484 1768542208 3.8773961067 3.8298642635 3.9080445766 1072 1311867206.1903800964 0.0992300510 0.0816064248 0.1207387596 0.0058888415 0.0939100000 0.0088110000 0.0306370000 0.0000270000 0.0002890000 0.0333500000 29151528 96830484 1770147840 3.8762745857 3.8275589943 3.9081282616 1073 1311867206.2239561081 0.0995029956 0.0816231038 0.1207387596 0.0058868613 0.1447070000 0.0116760000 0.0522770000 0.0002860000 0.0002770000 0.0597830000 29153746 96830484 1768923136 3.8759834766 3.8268229961 3.9079489708 1074 1311867206.2553579807 0.0994483531 0.0816397009 0.1207387596 0.0058855819 0.1235330000 0.0087310000 0.0608840000 0.0000290000 0.0002920000 0.0318250000 29155900 96830484 1770528768 3.8753113747 3.8245673180 3.9075336456 1075 1311867206.2904770374 0.0998869538 0.0816566750 0.1207387596 0.0058828752 0.1353420000 0.0110190000 0.0634940000 0.0005570000 0.0002920000 0.0384720000 29158118 96830484 1769570304 3.8739030361 3.8219780922 3.9072327614 1076 1311867206.3222041130 0.1008303985 0.0816744945 0.1207387596 0.0058803797 0.1319450000 0.0107830000 0.0634090000 0.0000240000 0.0005380000 0.0319040000 29160272 96830484 1768407040 3.8725466728 3.8216214180 3.9067251682 1077 1311867206.3542530537 0.1013769880 0.0816927884 0.1207387596 0.0058788178 0.1345460000 0.0089950000 0.0480610000 0.0002950000 0.0002850000 0.0565980000 29162490 96830484 1769885696 3.8710262775 3.8197760582 3.9063687325 1078 1311867206.3900070190 0.1001071855 0.0817098704 0.1207387596 0.0058783553 0.1127780000 0.0107020000 0.0386140000 0.0000260000 0.0003590000 0.0335200000 29164708 96830484 1766596608 3.8720934391 3.8171696663 3.9063353539 1079 1311867206.4220259190 0.1003769189 0.0817271707 0.1207387596 0.0058773647 0.1327230000 0.0091060000 0.0619570000 0.0004750000 0.0002990000 0.0381410000 29166894 96830484 1767391232 3.8717751503 3.8163800240 3.9061810970 1080 1311867206.4542310238 0.0993965045 0.0817435312 0.1207387596 0.0058748509 0.1120450000 0.0090470000 0.0406050000 0.0000090000 0.0000780000 0.0335980000 29169112 96830484 1766264832 3.8725397587 3.8145964146 3.9061832428 1081 1311867206.4905378819 0.0999523029 0.0817603756 0.1207387596 0.0058802691 0.1299390000 0.0093040000 0.0383080000 0.0002980000 0.0002780000 0.0613230000 29171330 96830484 1767727104 3.8709843159 3.8117792606 3.9061124325 1082 1311867206.5250329971 0.1006949544 0.0817778752 0.1207387596 0.0058817691 0.1006230000 0.0088340000 0.0370030000 0.0000270000 0.0003560000 0.0337030000 29173580 96830484 1769410560 3.8696954250 3.8093316555 3.9060242176 1083 1311867206.5539300442 0.0991824418 0.0817939459 0.1207387596 0.0058864129 0.1166610000 0.0113000000 0.0421950000 0.0003930000 0.0002730000 0.0387250000 29175734 96830484 1767526400 3.8715248108 3.8068664074 3.9059410095 1084 1311867206.5921130180 0.0987362340 0.0818095753 0.1207387596 0.0058856344 0.0947700000 0.0088850000 0.0276070000 0.0000110000 0.0000970000 0.0366780000 29177984 96830484 1766756352 3.8722460270 3.8055622578 3.9055473804 1085 1311867206.6226360798 0.1014299169 0.0818276585 0.1207387596 0.0058991420 0.1385730000 0.0098390000 0.0427960000 0.0003260000 0.0002760000 0.0645060000 29180138 96830484 1765740544 3.8692853451 3.8035192490 3.9054477215 1086 1311867206.6566751003 0.1001282334 0.0818445099 0.1207387596 0.0058974352 0.1414330000 0.0086090000 0.0689780000 0.0000270000 0.0002870000 0.0323060000 29182356 96830484 1767219200 3.8701884747 3.8014860153 3.9052877426 1087 1311867206.6945209503 0.1003535613 0.0818615375 0.1207387596 0.0058952552 0.1146290000 0.0090210000 0.0367830000 0.0003930000 0.0002740000 0.0395060000 29184638 96830484 1768902656 3.8701770306 3.8011305332 3.9048569202 1088 1311867206.7248480320 0.0989827439 0.0818772739 0.1207387596 0.0059034439 0.1148060000 0.0098530000 0.0430030000 0.0000280000 0.0003770000 0.0321090000 29186792 96830484 1765568512 3.8706851006 3.7979564667 3.9045732021 1089 1311867206.7587969303 0.1016715541 0.0818954505 0.1207387596 0.0059486238 0.1310270000 0.0091760000 0.0390160000 0.0003630000 0.0002870000 0.0615180000 29189042 96830484 1766518784 3.8688547611 3.7973778248 3.9041833878 1090 1311867206.7902839184 0.1001208872 0.0819121711 0.1207387596 0.0059672982 0.1170560000 0.0080580000 0.0520610000 0.0000270000 0.0002980000 0.0324510000 29191228 96830484 1762045952 3.8692038059 3.7957756519 3.9034585953 1091 1311867206.8229770660 0.1005976424 0.0819292980 0.1207387596 0.0059651857 0.1088940000 0.0095510000 0.0361560000 0.0001050000 0.0000730000 0.0389920000 29193414 96830484 1763835904 3.8681621552 3.7940578461 3.9028682709 1092 1311867206.8605449200 0.0998795256 0.0819457360 0.1207387596 0.0059625921 0.1094870000 0.0088040000 0.0381240000 0.0000100000 0.0000950000 0.0375600000 29195664 96830484 1765457920 3.8681371212 3.7910087109 3.9022066593 1093 1311867206.8907771111 0.0989458486 0.0819612896 0.1207387596 0.0059610872 0.1909480000 0.0092080000 0.0818240000 0.0003130000 0.0002800000 0.0667290000 29197818 96830484 1767219200 3.8693878651 3.7906746864 3.9015295506 1094 1311867206.9225020409 0.1005219966 0.0819782555 0.1207387596 0.0059584916 0.1342170000 0.0088090000 0.0613000000 0.0000290000 0.0003680000 0.0325940000 29200004 96830484 1768869888 3.8671152592 3.7884523869 3.9010400772 1095 1311867206.9592480659 0.1011104509 0.0819957278 0.1207387596 0.0059566522 0.1153830000 0.0099370000 0.0364590000 0.0003600000 0.0002750000 0.0394270000 29202286 96830484 1768042496 3.8663229942 3.7852654457 3.9005367756 1096 1311867206.9948680401 0.1011014357 0.0820131600 0.1207387596 0.0059670699 0.1319810000 0.0091130000 0.0623060000 0.0000300000 0.0002880000 0.0325410000 29204504 96830484 1769631744 3.8664209843 3.7834429741 3.9001326561 1097 1311867207.0247550011 0.1016284972 0.0820310409 0.1207387596 0.0059694470 0.1265390000 0.0107260000 0.0310200000 0.0003610000 0.0002880000 0.0632990000 29206690 96830484 1768787968 3.8668067455 3.7824060917 3.8999674320 1098 1311867207.0597259998 0.1019440219 0.0820491766 0.1207387596 0.0059669545 0.1203530000 0.0080760000 0.0470010000 0.0000270000 0.0002880000 0.0324280000 29208940 96830484 1770266624 3.8659241199 3.7799510956 3.8997244835 1099 1311867207.0942800045 0.1009399965 0.0820663657 0.1207387596 0.0059722171 0.1152160000 0.0112640000 0.0362170000 0.0002940000 0.0002760000 0.0396060000 29211126 96830484 1768124416 3.8669879436 3.7771196365 3.8995313644 1100 1311867207.1229140759 0.0999181718 0.0820825946 0.1207387596 0.0059747698 0.1121140000 0.0087290000 0.0416970000 0.0000290000 0.0003110000 0.0330000000 29213248 96830484 1767645184 3.8688569069 3.7766733170 3.8992593288 1101 1311867207.1583549976 0.1025833860 0.0821012148 0.1207387596 0.0059813073 0.1475280000 0.0086960000 0.0551400000 0.0007000000 0.0003150000 0.0616590000 29215498 96830484 1766518784 3.8660390377 3.7740294933 3.8993415833 1102 1311867207.1904919147 0.1007504910 0.0821181379 0.1207387596 0.0059812404 0.1215070000 0.0082760000 0.0617980000 0.0000270000 0.0003080000 0.0304560000 29217652 96830484 1768108032 3.8676967621 3.7724993229 3.8989913464 1103 1311867207.2226181030 0.1015661433 0.0821357698 0.1207387596 0.0059798600 0.1130120000 0.0083610000 0.0410250000 0.0002910000 0.0002720000 0.0394820000 29219870 96830484 1769758720 3.8667893410 3.7714185715 3.8991656303 1104 1311867207.2604830265 0.1008254811 0.0821526989 0.1207387596 0.0059785900 0.0953350000 0.0106440000 0.0259090000 0.0000260000 0.0003570000 0.0344690000 29222152 96830484 1765728256 3.8672959805 3.7697410583 3.8992447853 1105 1311867207.2926900387 0.0999186486 0.0821687767 0.1207387596 0.0059789570 0.1512370000 0.0094160000 0.0592010000 0.0002970000 0.0002750000 0.0609240000 29224338 96830484 1767137280 3.8676130772 3.7667243481 3.8996181488 1106 1311867207.3235239983 0.1005411968 0.0821853883 0.1207387596 0.0059827051 0.1124130000 0.0098880000 0.0305820000 0.0000200000 0.0001910000 0.0349870000 29226492 96830484 1762295808 3.8667387962 3.7651431561 3.9001498222 1107 1311867207.3597478867 0.1005617380 0.0822019884 0.1207387596 0.0059803924 0.1126930000 0.0096040000 0.0341850000 0.0000960000 0.0000860000 0.0473950000 29228774 96830484 1764106240 3.8662862778 3.7648036480 3.9006264210 1108 1311867207.3901309967 0.1001630798 0.0822181988 0.1207387596 0.0059813738 0.1107300000 0.0089620000 0.0349740000 0.0000290000 0.0002930000 0.0375950000 29230928 96830484 1765695488 3.8657588959 3.7620279789 3.9010903835 1109 1311867207.4227840900 0.1000838876 0.0822343085 0.1207387596 0.0059787794 0.1496300000 0.0091190000 0.0287820000 0.0003430000 0.0003670000 0.0631950000 29233114 96830484 1767473152 3.8644771576 3.7608561516 3.9010903835 1110 1311867207.4586789608 0.1001234129 0.0822504248 0.1207387596 0.0059782720 0.1004620000 0.0089270000 0.0315170000 0.0000290000 0.0007330000 0.0377250000 29235364 96830484 1769250816 3.8641352654 3.7602732182 3.9017589092 1111 1311867207.4927639961 0.1002585143 0.0822666337 0.1207387596 0.0059763532 0.1722500000 0.0107220000 0.0841620000 0.0003990000 0.0002810000 0.0480760000 29237582 96830484 1768534016 3.8624641895 3.7570936680 3.9019372463 1112 1311867207.5237300396 0.1010450497 0.0822835208 0.1207387596 0.0059781040 0.1116420000 0.0087520000 0.0367610000 0.0000300000 0.0003640000 0.0328770000 29239768 96830484 1770012672 3.8604583740 3.7543025017 3.9023666382 1113 1311867207.5598409176 0.0997054055 0.0822991739 0.1207387596 0.0059757400 0.1542340000 0.0113080000 0.0490100000 0.0003010000 0.0003550000 0.0721110000 29241986 96830484 1768787968 3.8614940643 3.7534985542 3.9027218819 1114 1311867207.5944800377 0.1008711532 0.0823158453 0.1207387596 0.0059750728 0.0982370000 0.0083540000 0.0354780000 0.0000280000 0.0003560000 0.0328320000 29244236 96830484 1770393600 3.8590941429 3.7516713142 3.9028811455 1115 1311867207.6259219646 0.0982775465 0.0823301607 0.1207387596 0.0059732818 0.1346520000 0.0111630000 0.0632750000 0.0002950000 0.0003420000 0.0385910000 29246390 96830484 1769422848 3.8604500294 3.7476863861 3.9033911228 1116 1311867207.6592938900 0.0982661545 0.0823444403 0.1207387596 0.0059715671 0.1161200000 0.0108920000 0.0504210000 0.0000280000 0.0002890000 0.0321090000 29248640 96830484 1766100992 3.8598446846 3.7470347881 3.9033141136 1117 1311867207.6923089027 0.0989011899 0.0823592628 0.1207387596 0.0059703789 0.1663060000 0.0092280000 0.0595340000 0.0002890000 0.0002730000 0.0585110000 29250826 96830484 1766883328 3.8586983681 3.7451455593 3.9034948349 1118 1311867207.7238640785 0.0983287767 0.0823735468 0.1207387596 0.0059698808 0.1152230000 0.0088420000 0.0457020000 0.0000290000 0.0003810000 0.0329930000 29253012 96830484 1768361984 3.8582785130 3.7416479588 3.9037952423 1119 1311867207.7588050365 0.0986890644 0.0823881273 0.1207387596 0.0059683154 0.1331580000 0.0087160000 0.0552320000 0.0003640000 0.0002810000 0.0402430000 29255166 96830484 1770045440 3.8569900990 3.7396075726 3.9036314487 1120 1311867207.7921919823 0.1005048901 0.0824043029 0.1207387596 0.0059662181 0.1170660000 0.0111340000 0.0357400000 0.0000280000 0.0002890000 0.0352620000 29257384 96830484 1768898560 3.8543033600 3.7382183075 3.9038841724 1121 1311867207.8237760067 0.0987582877 0.0824188917 0.1207387596 0.0059652861 0.1676490000 0.0124120000 0.0573080000 0.0005390000 0.0002910000 0.0759800000 29259570 96830484 1770520576 3.8556818962 3.7353732586 3.9039025307 1122 1311867207.8608479500 0.0984465629 0.0824331766 0.1207387596 0.0059638308 0.1364770000 0.0100210000 0.0606150000 0.0000300000 0.0003610000 0.0337720000 29261820 96830484 1769570304 3.8562772274 3.7341351509 3.9042277336 1123 1311867207.8937089443 0.0979906917 0.0824470301 0.1207387596 0.0059612950 0.1507150000 0.0108080000 0.0633360000 0.0002940000 0.0003500000 0.0452130000 29264038 96830484 1768407040 3.8568856716 3.7329962254 3.9041433334 1124 1311867207.9244139194 0.0996798500 0.0824623618 0.1207387596 0.0059594534 0.1316250000 0.0087560000 0.0638950000 0.0000270000 0.0002950000 0.0375050000 29266192 96830484 1769885696 3.8542003632 3.7305455208 3.9045825005 1125 1311867207.9614970684 0.0970237777 0.0824753053 0.1207387596 0.0059617991 0.1335970000 0.0107020000 0.0362350000 0.0003600000 0.0002860000 0.0648980000 29268378 96830484 1768660992 3.8569209576 3.7295517921 3.9046106339 1126 1311867207.9914131165 0.0970532075 0.0824882519 0.1207387596 0.0059762598 0.1122420000 0.0082850000 0.0423900000 0.0000290000 0.0009740000 0.0332800000 29270532 96830484 1770266624 3.8573353291 3.7283809185 3.9049894810 1127 1311867208.0248498917 0.0966132730 0.0825007852 0.1207387596 0.0059913498 0.1153800000 0.0110660000 0.0313500000 0.0001920000 0.0001770000 0.0463780000 29272782 96830484 1768632320 3.8566820621 3.7246153355 3.9052793980 1128 1311867208.0618500710 0.0978939235 0.0825144316 0.1207387596 0.0059911667 0.1201970000 0.0112850000 0.0596850000 0.0000300000 0.0002980000 0.0269980000 29274936 96830484 1767899136 3.8553566933 3.7232363224 3.9055538177 1129 1311867208.0924620628 0.0970887467 0.0825273407 0.1207387596 0.0059888071 0.1621860000 0.0083850000 0.0597940000 0.0002970000 0.0002740000 0.0629610000 29277090 96830484 1766772736 3.8566358089 3.7229249477 3.9054923058 1130 1311867208.1276559830 0.0973075926 0.0825404205 0.1207387596 0.0059872198 0.1144580000 0.0082900000 0.0498720000 0.0000280000 0.0003770000 0.0337540000 29279308 96830484 1768394752 3.8556766510 3.7205612659 3.9054250717 1131 1311867208.1596069336 0.0958258733 0.0825521672 0.1207387596 0.0059847087 0.1333440000 0.0090580000 0.0582190000 0.0002920000 0.0002730000 0.0407050000 29281494 96830484 1770139648 3.8574635983 3.7198503017 3.9051971436 1132 1311867208.1905009747 0.0980848372 0.0825658886 0.1207387596 0.0059828300 0.1333500000 0.0103030000 0.0602950000 0.0000280000 0.0003570000 0.0334660000 29283616 96830484 1769291776 3.8545227051 3.7185320854 3.9048869610 1133 1311867208.2280850410 0.0983443037 0.0825798148 0.1207387596 0.0059807838 0.1310920000 0.0098390000 0.0357460000 0.0003600000 0.0006260000 0.0629070000 29285930 96830484 1768550400 3.8542943001 3.7171990871 3.9047172070 1134 1311867208.2581789494 0.0975567997 0.0825930221 0.1207387596 0.0059788262 0.1143330000 0.0079820000 0.0351340000 0.0000300000 0.0002950000 0.0356340000 29288084 96830484 1770172416 3.8545808792 3.7150323391 3.9044806957 1135 1311867208.2901990414 0.0973718464 0.0826060431 0.1207387596 0.0059763695 0.1383180000 0.0103290000 0.0627530000 0.0004580000 0.0003460000 0.0429160000 29290238 96830484 1769033728 3.8547694683 3.7141962051 3.9040427208 1136 1311867208.3270208836 0.0981031582 0.0826196849 0.1207387596 0.0059788658 0.1297610000 0.0081790000 0.0590090000 0.0000270000 0.0003570000 0.0344080000 29292520 96830484 1770807296 3.8542921543 3.7131152153 3.9039697647 1137 1311867208.3580970764 0.0983769894 0.0826335435 0.1207387596 0.0059804339 0.1547900000 0.0101890000 0.0588320000 0.0002890000 0.0002770000 0.0638860000 29294706 96830484 1770053632 3.8535766602 3.7114486694 3.9039821625 1138 1311867208.3910560608 0.0971987769 0.0826463425 0.1207387596 0.0059786386 0.0966370000 0.0104190000 0.0299750000 0.0000330000 0.0003000000 0.0343100000 29296860 96830484 1766117376 3.8549869061 3.7105627060 3.9038381577 1139 1311867208.4260230064 0.0979028866 0.0826597372 0.1207387596 0.0059764351 0.1283300000 0.0086650000 0.0489500000 0.0002950000 0.0002770000 0.0410740000 29299110 96830484 1767907328 3.8533921242 3.7079966068 3.9036288261 1140 1311867208.4577419758 0.0982232019 0.0826733894 0.1207387596 0.0059776133 0.1318210000 0.0087870000 0.0571520000 0.0000310000 0.0003610000 0.0342690000 29301296 96830484 1769537536 3.8535699844 3.7068707943 3.9037680626 1141 1311867208.4907650948 0.0966176465 0.0826856105 0.1207387596 0.0059765307 0.1565280000 0.0105350000 0.0596470000 0.0003620000 0.0006220000 0.0636170000 29303514 96830484 1767526400 3.8554034233 3.7056069374 3.9037966728 1142 1311867208.5257411003 0.0968323573 0.0826979981 0.1207387596 0.0059748393 0.1094080000 0.0083660000 0.0291940000 0.0000290000 0.0003860000 0.0363370000 29305764 96830484 1769140224 3.8544447422 3.7043042183 3.9038529396 1143 1311867208.5583798885 0.0988681614 0.0827121453 0.1207387596 0.0059729601 0.1155040000 0.0088410000 0.0390540000 0.0003180000 0.0002790000 0.0424920000 29307950 96830484 1770938368 3.8516972065 3.7030999660 3.9045450687 1144 1311867208.5904500484 0.0997310504 0.0827270219 0.1207387596 0.0059715549 0.1161820000 0.0109220000 0.0409990000 0.0000210000 0.0002610000 0.0421870000 29310168 96830484 1769791488 3.8509476185 3.7028698921 3.9050748348 1145 1311867208.6259779930 0.0965911224 0.0827391303 0.1207387596 0.0059711799 0.1697760000 0.0109880000 0.0626440000 0.0003130000 0.0002820000 0.0639390000 29312354 96830484 1767759872 3.8538148403 3.7012975216 3.9053504467 1146 1311867208.6582078934 0.0968325362 0.0827514282 0.1207387596 0.0059686082 0.1325810000 0.0089100000 0.0606400000 0.0000310000 0.0003740000 0.0338720000 29314572 96830484 1769648128 3.8528482914 3.6996436119 3.9060149193 1147 1311867208.6910300255 0.0952488780 0.0827623240 0.1207387596 0.0059715680 0.1325320000 0.0106580000 0.0480280000 0.0002930000 0.0002720000 0.0408450000 29316758 96830484 1767489536 3.8534657955 3.6991403103 3.9065699577 1148 1311867208.7262260914 0.0963025540 0.0827741186 0.1207387596 0.0059735446 0.1120140000 0.0088010000 0.0397430000 0.0000190000 0.0002000000 0.0342160000 29319008 96830484 1769136128 3.8522970676 3.6979076862 3.9069411755 1149 1311867208.7591009140 0.0980117843 0.0827873803 0.1207387596 0.0059715057 0.1529730000 0.0088120000 0.0442910000 0.0003560000 0.0002760000 0.0679390000 29321194 96830484 1770917888 3.8498806953 3.6980080605 3.9074041843 1150 1311867208.7909750938 0.0957140103 0.0827986209 0.1207387596 0.0059709517 0.0969970000 0.0101770000 0.0296880000 0.0000100000 0.0000960000 0.0353760000 29323348 96830484 1767759872 3.8516547680 3.6962080002 3.9078595638 1151 1311867208.8259930611 0.0963594764 0.0828104027 0.1207387596 0.0059698481 0.1466800000 0.0090400000 0.0606620000 0.0002940000 0.0003380000 0.0409860000 29325598 96830484 1768378368 3.8501408100 3.6935737133 3.9084122181 1152 1311867208.8588190079 0.0976606086 0.0828232935 0.1207387596 0.0059743512 0.1329560000 0.0106250000 0.0561820000 0.0000280000 0.0003030000 0.0349810000 29327816 96830484 1766473728 3.8487820625 3.6940984726 3.9086735249 1153 1311867208.8916258812 0.0969758630 0.0828355680 0.1207387596 0.0059857821 0.1535860000 0.0086050000 0.0585840000 0.0003590000 0.0002830000 0.0640250000 29329970 96830484 1768124416 3.8479552269 3.6938409805 3.9091713428 1154 1311867208.9275119305 0.0977316499 0.0828484762 0.1207387596 0.0059880339 0.1321510000 0.0084440000 0.0585170000 0.0000270000 0.0003550000 0.0342310000 29332188 96830484 1769922560 3.8468134403 3.6909084320 3.9094429016 1155 1311867208.9577760696 0.0980044901 0.0828615983 0.1207387596 0.0059858145 0.1359980000 0.0106920000 0.0591930000 0.0002970000 0.0002710000 0.0414560000 29334342 96830484 1767780352 3.8457260132 3.6882109642 3.9094393253 1156 1311867208.9911639690 0.0961793363 0.0828731189 0.1207387596 0.0059832623 0.1103450000 0.0088320000 0.0409310000 0.0000280000 0.0003630000 0.0388130000 29336560 96830484 1769558016 3.8482294083 3.6884975433 3.9090094566 1157 1311867209.0270779133 0.0959646329 0.0828844339 0.1207387596 0.0059824773 0.1536020000 0.0086440000 0.0584080000 0.0002900000 0.0002730000 0.0645600000 29338810 96830484 1771208704 3.8480744362 3.6857564449 3.9090950489 1158 1311867209.0579569340 0.0978151634 0.0828973275 0.1207387596 0.0059804761 0.1341210000 0.0102560000 0.0584920000 0.0000260000 0.0003600000 0.0347500000 29340964 96830484 1769160704 3.8456411362 3.6850371361 3.9082818031 1159 1311867209.0906980038 0.0985539928 0.0829108362 0.1207387596 0.0059788252 0.1526280000 0.0085240000 0.0644940000 0.0002910000 0.0003460000 0.0500000000 29343182 96830484 1770827776 3.8448183537 3.6854650974 3.9078078270 1160 1311867209.1260778904 0.0981263891 0.0829239531 0.1207387596 0.0059765920 0.1134650000 0.0111370000 0.0336060000 0.0000200000 0.0001920000 0.0348880000 29345368 96830484 1766727680 3.8449163437 3.6845221519 3.9071600437 1161 1311867209.1600620747 0.0990397856 0.0829378341 0.1207387596 0.0059749232 0.1705690000 0.0087500000 0.0634690000 0.0006430000 0.0002830000 0.0754850000 29347618 96830484 1768415232 3.8434381485 3.6820511818 3.9069635868 1162 1311867209.1917839050 0.0997394919 0.0829522933 0.1207387596 0.0059731962 0.1136810000 0.0085650000 0.0380030000 0.0000270000 0.0002830000 0.0370050000 29349804 96830484 1770029056 3.8430328369 3.6828160286 3.9064710140 1163 1311867209.2259531021 0.0996296629 0.0829666333 0.1207387596 0.0059706776 0.1153940000 0.0109780000 0.0336870000 0.0001970000 0.0002250000 0.0414870000 29351990 96830484 1765998592 3.8425877094 3.6813070774 3.9059059620 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:00:58 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0413500000 86921331 0 921436160 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0091206590 0.0045603295 0.0091206590 0.0109384144 0.1597670000 98808100 0 1048420352 0.0022240358 0.0018558704 0.0004305617 3 0.0800000000 0.0102847572 0.0064684721 0.0102847572 0.0112365875 0.1115730000 102078690 0 1052258304 0.0058347303 -0.0071401927 0.0008932189 4 0.1200000000 0.0048796036 0.0060712550 0.0102847572 0.0110993170 0.0913850000 102080272 0 1053020160 0.0048465184 -0.0071327714 0.0010495052 5 0.1600000000 0.0032268881 0.0055023816 0.0102847572 0.0104725662 0.0837010000 102081862 0 1053528064 0.0006014031 -0.0013356443 0.0005571538 6 0.2000000000 0.0094214482 0.0061555594 0.0102847572 0.0095840825 0.0784090000 102083772 0 1054035968 0.0015696948 -0.0006562072 0.0007669924 7 0.2400000000 0.0100692660 0.0067146603 0.0102847572 0.0088211801 0.0731650000 102085026 0 1054543872 0.0016552011 -0.0002872772 0.0006694405 8 0.2800000000 0.0069246208 0.0067409054 0.0102847572 0.0083959484 0.0782280000 102086280 0 1055051776 0.0008991957 -0.0005901603 0.0006825746 9 0.3200000000 0.0075088795 0.0068262358 0.0102847572 0.0078950167 0.0717350000 102088206 0 1055686656 0.0011365548 -0.0000287040 0.0006530352 10 0.3600000000 0.0088686766 0.0070304799 0.0102847572 0.0074842781 0.0696410000 102090772 0 1056194560 0.0016014694 -0.0001619773 0.0008678896 11 0.4000000000 0.0085444609 0.0071681145 0.0102847572 0.0071151039 0.1020640000 102092026 0 1056702464 0.0020919847 -0.0009807276 0.0009022617 12 0.4400000000 0.0071545225 0.0071669819 0.0102847572 0.0068356975 0.0880000000 102093280 0 1057210368 0.0021309198 -0.0019654986 0.0003347530 13 0.4800000000 0.0069957580 0.0071538108 0.0102847572 0.0067184358 0.0777680000 102094534 0 1057718272 0.0014660374 -0.0006853301 0.0005426986 14 0.5200000000 0.0063389656 0.0070956076 0.0102847572 0.0065557992 0.0868360000 102095788 0 1058353152 0.0013995696 -0.0004661931 0.0004210388 15 0.5600000000 0.0058485926 0.0070124732 0.0102847572 0.0063318189 0.0850780000 102097042 0 1058861056 0.0014996264 -0.0004072366 0.0003044875 16 0.6000000000 0.0063145752 0.0069688546 0.0102847572 0.0061229689 0.0786670000 102098296 0 1059368960 0.0016341689 -0.0000938898 0.0002611615 17 0.6400000000 0.0049452637 0.0068498199 0.0102847572 0.0059460641 0.0786550000 102100894 0 1059876864 0.0013245471 -0.0008777804 0.0000737607 18 0.6800000000 0.0040671085 0.0066952248 0.0102847572 0.0058254318 0.0707210000 102104772 0 1060384768 0.0008719845 -0.0015044574 0.0000086878 19 0.7200000000 0.0063963928 0.0066794968 0.0102847572 0.0061291771 0.0833340000 102106026 0 1061019648 -0.0005786899 -0.0061492985 0.0008356494 20 0.7600000000 0.0099695576 0.0068439998 0.0102847572 0.0060827238 0.0848940000 102107280 0 1061527552 -0.0028933380 -0.0083671743 0.0013817921 21 0.8000000000 0.0113686090 0.0070594574 0.0113686090 0.0059900405 0.0825700000 102108534 0 1062035456 -0.0043779965 -0.0094175879 0.0016015979 22 0.8400000000 0.0078993458 0.0070976342 0.0113686090 0.0059876013 0.0847330000 102109788 0 1062543360 -0.0020900597 -0.0072775413 0.0010477796 23 0.8800000000 0.0049570105 0.0070045636 0.0113686090 0.0060791546 0.0954520000 102111042 0 1063051264 0.0000925793 -0.0036683546 0.0004564076 24 0.9200000000 0.0056984001 0.0069501401 0.0113686090 0.0060324397 0.0799350000 102112296 0 1063686144 0.0011216660 -0.0007411655 0.0001158502 25 0.9600000000 0.0068463641 0.0069459890 0.0113686090 0.0059188367 0.0850190000 102113550 0 1064194048 0.0009186671 -0.0007672459 0.0003470096 26 1.0000000000 0.0070991009 0.0069518780 0.0113686090 0.0058034221 0.0748260000 102114804 0 1064701952 0.0003017280 -0.0010629836 0.0002630062 27 1.0400000000 0.0065181693 0.0069358147 0.0113686090 0.0057000782 0.0749360000 102116058 0 1065209856 0.0005860382 -0.0014976242 0.0002165283 28 1.0800000000 0.0078901220 0.0069698971 0.0113686090 0.0056008012 0.1023360000 102117312 0 1065717760 0.0017145929 -0.0013833080 0.0006172636 29 1.1200000000 0.0087825013 0.0070324007 0.0113686090 0.0056500381 0.0950930000 102118566 0 1066352640 0.0013545447 -0.0022468038 0.0009896355 30 1.1600000000 0.0084846457 0.0070808088 0.0113686090 0.0058282852 0.0726030000 102119820 0 1066860544 0.0006885737 -0.0074584051 0.0017386023 31 1.2000000000 0.0122599471 0.0072478778 0.0122599471 0.0059252419 0.0764200000 102121074 0 1067368448 -0.0005240567 -0.0093893809 0.0024692249 32 1.2400000000 0.0151440315 0.0074946326 0.0151440315 0.0062264060 0.0786070000 102122328 0 1067876352 -0.0017021496 -0.0086230123 0.0027576752 33 1.2800000000 0.0111742811 0.0076061371 0.0151440315 0.0063088506 0.0756050000 102126270 0 1068511232 0.0026429573 -0.0104866037 0.0025847743 34 1.3200000000 0.0130516924 0.0077663005 0.0151440315 0.0064929524 0.0749080000 102132772 0 1069019136 -0.0002038370 -0.0096695945 0.0032182012 35 1.3600000000 0.0142639568 0.0079519478 0.0151440315 0.0068102961 0.0948500000 102134026 0 1069527040 -0.0000489941 -0.0118908240 0.0039279470 36 1.4000000000 0.0134083759 0.0081035153 0.0151440315 0.0069979059 0.0784930000 102135280 0 1070034944 0.0010264979 -0.0109905405 0.0042982968 37 1.4400000000 0.0140718734 0.0082648223 0.0151440315 0.0073653479 0.0800460000 102136534 0 1070669824 0.0010434890 -0.0099427560 0.0040654601 38 1.4800000000 0.0104460390 0.0083222227 0.0151440315 0.0089554202 0.0888460000 102137788 0 1071177728 0.0058590705 -0.0074572745 0.0037836637 39 1.5200000000 0.0119354920 0.0084148706 0.0151440315 0.0091952804 0.0786180000 102139042 0 1071685632 0.0060311188 -0.0067854808 0.0044121817 40 1.5600000000 0.0162894111 0.0086117341 0.0162894111 0.0093753658 0.0826170000 102140296 0 1072193536 0.0033293660 -0.0040198881 0.0047117802 41 1.6000000000 0.0144777941 0.0087548088 0.0162894111 0.0093640009 0.0867690000 102141550 0 1072828416 0.0070676482 -0.0070013124 0.0051823636 42 1.6400000000 0.0142536331 0.0088857332 0.0162894111 0.0095217500 0.0955300000 102142804 0 1073463296 0.0104181506 -0.0042577027 0.0048720110 43 1.6800000000 0.0170145985 0.0090747765 0.0170145985 0.0098191956 0.0801320000 102144058 0 1073971200 0.0093080392 -0.0017999051 0.0047747819 44 1.7200000000 0.0180440322 0.0092786233 0.0180440322 0.0100598017 0.0808190000 102145312 0 1074479104 0.0091421446 -0.0016704064 0.0051578186 45 1.7600000000 0.0197008774 0.0095102289 0.0197008774 0.0102773041 0.0892000000 102146566 0 1074987008 0.0099092182 -0.0026032438 0.0057378639 46 1.8000000000 0.0405470319 0.0101849420 0.0405470319 0.0108462128 0.0837890000 102147820 0 1075494912 0.0159597695 -0.0027785331 0.0055998396 47 1.8400000000 0.0864422768 0.0118074385 0.0864422768 0.0117852013 0.1720010000 114485258 0 1088319488 0.0303512663 -0.0106472997 0.0049245418 48 1.8800000000 0.0884779170 0.0134047401 0.0884779170 0.0118695004 0.0694680000 118144560 0 1092382720 0.0308954492 -0.0111535350 0.0051923762 49 1.9200000000 0.0901910737 0.0149718082 0.0901910737 0.0119560844 0.0721910000 121337910 0 1096065024 0.0315903388 -0.0116302157 0.0056239804 50 1.9600000000 0.0916732028 0.0165058361 0.0916732028 0.0119941173 0.1057100000 121339164 0 1096826880 0.0326637253 -0.0116916122 0.0058117160 51 2.0000000000 0.0932760462 0.0180111343 0.0932760462 0.0120056469 0.0699410000 121340418 0 1097334784 0.0339514576 -0.0121362517 0.0058847396 52 2.0400000000 0.0945445225 0.0194829302 0.0945445225 0.0120018146 0.0834210000 121341672 0 1097842688 0.0359139144 -0.0125346594 0.0058970251 53 2.0800000000 0.0952072591 0.0209116912 0.0952072591 0.0119986140 0.0818700000 121342926 0 1098350592 0.0366640389 -0.0128760412 0.0060080588 54 2.1200000000 0.0948954076 0.0222817600 0.0952072591 0.0119613562 0.0835430000 121344180 0 1098969088 0.0402381755 -0.0162322149 0.0062341518 55 2.1600000000 0.0969080031 0.0236386008 0.0969080031 0.0121125819 0.0874120000 121345434 0 1099476992 0.0417592339 -0.0081249690 0.0042843171 56 2.2000000000 0.1028798819 0.0250536236 0.1028798819 0.0123471008 0.0815050000 121346688 0 1099984896 0.0371917300 -0.0156724472 0.0064826752 57 2.2400000000 0.1017433405 0.0263990573 0.1028798819 0.0124507168 0.2723930000 140175998 0 1115095040 0.0379005969 -0.0159634613 0.0067268480 58 2.2800000000 0.1097521186 0.0278361790 0.1097521186 0.0130205333 0.0736150000 143835100 0 1119285248 0.0328597166 -0.0278659966 0.0123585546 59 2.3200000000 0.1098449305 0.0292261578 0.1098449305 0.0131892717 0.0976190000 147028450 0 1122967552 0.0345975757 -0.0274667423 0.0120229740 60 2.3600000000 0.1132180393 0.0306260225 0.1132180393 0.0133116070 0.0961850000 147029704 0 1123729408 0.0345937721 -0.0298064835 0.0124331992 61 2.4000000000 0.1128956228 0.0319747045 0.1132180393 0.0135198966 0.0734030000 147030958 0 1124237312 0.0366292857 -0.0289858151 0.0118234456 62 2.4400000000 0.1147622392 0.0333099873 0.1147622392 0.0136595083 0.0736380000 147032212 0 1124745216 0.0387914479 -0.0323417969 0.0117808105 63 2.4800000000 0.1187879369 0.0346667802 0.1187879369 0.0138727157 0.0733060000 147033466 0 1125380096 0.0383538641 -0.0307435635 0.0120011773 64 2.5200000000 0.1222811267 0.0360357543 0.1222811267 0.0139492968 0.2138210000 159335760 0 1138331648 0.0385964066 -0.0311834440 0.0117175598 65 2.5600000000 0.1256239265 0.0374140339 0.1256239265 0.0140355438 0.0629480000 163000646 0 1142394880 0.0392729864 -0.0292732399 0.0107975993 66 2.6000000000 0.1192431003 0.0386538683 0.1256239265 0.0140910434 0.1026600000 166204492 0 1146077184 0.0501562804 -0.0282212961 0.0080096414 67 2.6400000000 0.1199048460 0.0398665694 0.1256239265 0.0141740331 0.0806810000 166205746 0 1146839040 0.0528595485 -0.0265390798 0.0068335719 68 2.6800000000 0.1314337999 0.0412131463 0.1314337999 0.0144030743 0.0778190000 166207000 0 1147346944 0.0467971154 -0.0310099572 0.0086000124 69 2.7200000000 0.1331552565 0.0425456407 0.1331552565 0.0144531204 0.0828360000 166208254 0 1147854848 0.0485720485 -0.0316330642 0.0080705481 70 2.7600000000 0.1347827911 0.0438633143 0.1347827911 0.0145805351 0.0797010000 166209508 0 1148362752 0.0493050963 -0.0317905657 0.0080677401 71 2.8000000000 0.1384079903 0.0451949294 0.1384079903 0.0146432322 0.0744440000 166210762 0 1148997632 0.0500727147 -0.0336945094 0.0074054636 72 2.8400000000 0.1382068247 0.0464867613 0.1384079903 0.0147694984 0.0624620000 166212016 0 1149505536 0.0530518591 -0.0322083123 0.0062904325 73 2.8800000000 0.1392102689 0.0477569463 0.1392102689 0.0148531056 0.0810070000 166213270 0 1150013440 0.0545120090 -0.0333410986 0.0057409229 74 2.9200000000 0.1421648711 0.0490327291 0.1421648711 0.0148829202 0.0764240000 166214524 0 1150521344 0.0563257970 -0.0340695269 0.0048961849 75 2.9600000000 0.1392363757 0.0502354444 0.1421648711 0.0149963951 0.0717280000 166215778 0 1151029248 0.0607579276 -0.0321875028 0.0037280989 76 3.0000000000 0.1464711428 0.0515017036 0.1464711428 0.0149945683 0.0758110000 166217032 0 1151664128 0.0590206385 -0.0343701281 0.0036213298 77 3.0400000000 0.1481033117 0.0527562699 0.1481033117 0.0150155632 0.0781940000 166218286 0 1152172032 0.0606611595 -0.0352200046 0.0028769991 78 3.0800000000 0.1504198760 0.0540083674 0.1504198760 0.0149766468 0.0830110000 166219540 0 1152679936 0.0635003373 -0.0374394059 0.0017395262 79 3.1200000000 0.1516943425 0.0552448988 0.1516943425 0.0149687331 0.0944910000 166220794 0 1153187840 0.0666560531 -0.0392194316 0.0006719888 80 3.1600000000 0.1563203186 0.0565083415 0.1563203186 0.0152105055 0.0940020000 166222048 0 1153822720 0.0715752840 -0.0414340198 -0.0016417053 81 3.2000000000 0.1568872482 0.0577475873 0.1568872482 0.0151909294 0.2334920000 178523742 0 1166647296 0.0752607882 -0.0423674583 -0.0030950182 82 3.2400000000 0.1567130536 0.0589544832 0.1568872482 0.0151596351 0.0820980000 182182844 0 1170583552 0.0789448023 -0.0427818336 -0.0042539281 83 3.2800000000 0.1574497074 0.0601411726 0.1574497074 0.0151675069 0.0989170000 185376194 0 1174392832 0.0817186385 -0.0439359061 -0.0052525015 84 3.3200000000 0.1587626040 0.0613152373 0.1587626040 0.0151403761 0.0732040000 185377448 0 1175027712 0.0828248039 -0.0443317853 -0.0055701612 85 3.3600000000 0.1613975614 0.0624926764 0.1613975614 0.0151138394 0.0712490000 185378702 0 1175662592 0.0840242505 -0.0453317352 -0.0058514425 86 3.4000000000 0.1622802019 0.0636529965 0.1622802019 0.0151364924 0.0671200000 185379956 0 1176170496 0.0854384527 -0.0460699350 -0.0062265322 87 3.4400000000 0.1640655249 0.0648071635 0.1640655249 0.0151350034 0.0647600000 185381210 0 1176678400 0.0876689553 -0.0470963418 -0.0071104350 88 3.4800000000 0.1653950661 0.0659502078 0.1653950661 0.0151099696 0.0807580000 185382464 0 1177186304 0.0909384489 -0.0521303080 -0.0075548184 89 3.5200000000 0.1647283435 0.0670600745 0.1653950661 0.0150615939 0.0788780000 185383718 0 1177821184 0.0951037854 -0.0569883063 -0.0085250298 90 3.5600000000 0.1672313660 0.0681730889 0.1672313660 0.0150933603 0.0650990000 185384972 0 1178329088 0.0945988372 -0.0533833876 -0.0091470350 91 3.6000000000 0.1722405106 0.0693166869 0.1722405106 0.0151423438 0.0759050000 185386226 0 1178836992 0.0922746137 -0.0513556078 -0.0089484686 92 3.6400000000 0.1742052436 0.0704567799 0.1742052436 0.0151249183 0.0852150000 185387480 0 1179344896 0.0936912224 -0.0516121238 -0.0097217280 93 3.6800000000 0.1737679988 0.0715676532 0.1742052436 0.0150667084 0.0735500000 185388734 0 1179852800 0.0966724381 -0.0533468015 -0.0106428126 94 3.7200000000 0.1751435548 0.0726695245 0.1751435548 0.0150242230 0.0625690000 185389988 0 1180487680 0.0978759304 -0.0525041632 -0.0114174355 95 3.7600000000 0.1768467128 0.0737661265 0.1768467128 0.0149734405 0.0759770000 185391242 0 1180995584 0.0997503102 -0.0528405309 -0.0121339280 96 3.8000000000 0.1771904677 0.0748434634 0.1771904677 0.0149104852 0.2354810000 197696120 0 1193811968 0.1025548801 -0.0547292456 -0.0131927086 97 3.8400000000 0.1802594513 0.0759302262 0.1802594513 0.0148645797 0.1071010000 201355222 0 1197875200 0.1023856178 -0.0569829419 -0.0134340292 98 3.8800000000 0.1793727428 0.0769857620 0.1802594513 0.0148081990 0.0746430000 204548572 0 1201557504 0.1042153090 -0.0578171387 -0.0141466381 99 3.9200000000 0.1815830618 0.0780423004 0.1815830618 0.0147494327 0.0659130000 204549826 0 1202319360 0.1051650271 -0.0576911420 -0.0146960719 100 3.9600000000 0.1835815310 0.0790976927 0.1835815310 0.0146947435 0.0637430000 204551080 0 1202827264 0.1051682979 -0.0589054190 -0.0142824501 101 4.0000000000 0.1857120544 0.0801532805 0.1857120544 0.0146409510 0.0647270000 204552334 0 1203335168 0.1060220450 -0.0614581443 -0.0147653064 102 4.0400000000 0.1842857897 0.0811741874 0.1857120544 0.0145775444 0.0728960000 204553588 0 1203970048 0.1102172807 -0.0635523051 -0.0155617520 103 4.0800000000 0.1881524473 0.0822128113 0.1881524473 0.0145519596 0.0668200000 204554842 0 1204477952 0.1083488166 -0.0596980155 -0.0160680972 104 4.1200000000 0.1888053119 0.0832377392 0.1888053119 0.0145123907 0.0692890000 204556096 0 1204985856 0.1093756557 -0.0577046499 -0.0170738902 105 4.1600000000 0.1904377788 0.0842586920 0.1904377788 0.0144576980 0.0850320000 204557350 0 1205493760 0.1109477654 -0.0589184389 -0.0179020818 106 4.2000000000 0.1910746098 0.0852663893 0.1910746098 0.0144003124 0.0749470000 204558604 0 1206001664 0.1121699214 -0.0588914864 -0.0183742605 107 4.2400000000 0.1911151260 0.0862556298 0.1911151260 0.0143376116 0.0754940000 204559858 0 1206636544 0.1130303144 -0.0591586716 -0.0189429782 108 4.2800000000 0.1944056600 0.0872570190 0.1944056600 0.0142790016 0.0767910000 204561112 0 1207144448 0.1142597497 -0.0594924428 -0.0197464395 109 4.3200000000 0.1954405010 0.0882495280 0.1954405010 0.0142133556 0.0804780000 204562366 0 1207652352 0.1151665747 -0.0598383099 -0.0202087611 110 4.3600000000 0.1952624470 0.0892223727 0.1954405010 0.0141492065 0.0729330000 204563620 0 1208160256 0.1165602431 -0.0603235252 -0.0210129432 111 4.4000000000 0.1954635829 0.0901795007 0.1954635829 0.0140862944 0.0773410000 204564874 0 1208795136 0.1180775166 -0.0611669123 -0.0219831262 112 4.4400000000 0.1977941841 0.0911403461 0.1977941841 0.0140293672 0.0792480000 204566128 0 1209303040 0.1188287959 -0.0613298006 -0.0228613690 113 4.4800000000 0.1985685676 0.0920910383 0.1985685676 0.0139682875 0.0938160000 204567382 0 1209810944 0.1199009344 -0.0620819703 -0.0235494878 114 4.5200000000 0.1984438449 0.0930239577 0.1985685676 0.0139082968 0.0837920000 204568636 0 1210318848 0.1217564121 -0.0635037944 -0.0239901785 115 4.5600000000 0.1996832490 0.0939514298 0.1996832490 0.0138514450 0.0973680000 204569890 0 1210826752 0.1222844496 -0.0633066297 -0.0249559991 116 4.6000000000 0.1995759308 0.0948619858 0.1996832490 0.0137994433 0.0856730000 204571144 0 1211461632 0.1236629412 -0.0645784512 -0.0254718699 117 4.6400000000 0.2006489784 0.0957661482 0.2006489784 0.0137612398 0.0776190000 204572398 0 1211969536 0.1244336292 -0.0645826086 -0.0257959682 118 4.6800000000 0.2007572055 0.0966559029 0.2007572055 0.0137333181 0.0963700000 204573652 0 1212477440 0.1248843968 -0.0652252287 -0.0264977217 119 4.7200000000 0.2007483542 0.0975306294 0.2007572055 0.0136999364 0.1008770000 204574906 0 1212985344 0.1260308772 -0.0664782822 -0.0268840995 120 4.7600000000 0.2001126409 0.0983854795 0.2007572055 0.0136570442 0.0879740000 204576160 0 1213493248 0.1272743344 -0.0666577145 -0.0274620950 121 4.8000000000 0.1999617517 0.0992249528 0.2007572055 0.0136174365 0.0905710000 204577414 0 1214128128 0.1271383166 -0.0681403652 -0.0273792893 122 4.8400000000 0.1999243200 0.1000503574 0.2007572055 0.0135924870 0.1005530000 204578668 0 1214636032 0.1279734671 -0.0689399987 -0.0281486884 123 4.8800000000 0.1979672313 0.1008464296 0.2007572055 0.0135474527 0.0999120000 204579922 0 1215143936 0.1297892332 -0.0692976192 -0.0287462808 124 4.9200000000 0.1981337219 0.1016310045 0.2007572055 0.0135090635 0.0842220000 204581176 0 1215651840 0.1294830889 -0.0698249340 -0.0285235532 125 4.9600000000 0.1979630738 0.1024016611 0.2007572055 0.0134734299 0.0950370000 204582430 0 1216286720 0.1301824898 -0.0709069520 -0.0285690222 126 5.0000000000 0.1982938498 0.1031627102 0.2007572055 0.0134431810 0.1022410000 204583684 0 1216794624 0.1308576316 -0.0724432617 -0.0286625065 127 5.0400000000 0.1975817978 0.1039061676 0.2007572055 0.0134133320 0.0808970000 204584938 0 1217302528 0.1306795478 -0.0723758042 -0.0285157654 128 5.0800000000 0.1967633516 0.1046316143 0.2007572055 0.0133880942 0.0995500000 204586192 0 1217810432 0.1313420981 -0.0731384829 -0.0287919305 129 5.1200000000 0.1976432055 0.1053526344 0.2007572055 0.0133659645 0.0862350000 204598198 0 1218318336 0.1321212053 -0.0735684037 -0.0281147305 130 5.1600000000 0.1958843470 0.1060490322 0.2007572055 0.0133405210 0.0858750000 204620444 0 1218953216 0.1316960901 -0.0734839141 -0.0286900718 131 5.2000000000 0.1933574677 0.1067155088 0.2007572055 0.0133212128 0.0992450000 204621698 0 1219461120 0.1319788247 -0.0732036754 -0.0288096424 132 5.2400000000 0.1928096116 0.1073677369 0.2007572055 0.0132972796 0.0810200000 204622952 0 1220096000 0.1310764700 -0.0732028037 -0.0272293929 133 5.2800000000 0.1925492734 0.1080081995 0.2007572055 0.0132694362 0.0779090000 204624206 0 1220603904 0.1302027702 -0.0735361502 -0.0264725834 134 5.3200000000 0.1911381036 0.1086285720 0.2007572055 0.0132402143 0.0777190000 204625460 0 1221111808 0.1304899752 -0.0747593641 -0.0268168785 135 5.3600000000 0.1890845299 0.1092245420 0.2007572055 0.0132029435 0.0815720000 204626714 0 1221619712 0.1296024024 -0.0743323416 -0.0260330606 136 5.4000000000 0.1887505949 0.1098092924 0.2007572055 0.0131754852 0.0799690000 204627968 0 1222127616 0.1292964220 -0.0750147253 -0.0257262141 137 5.4400000000 0.1894884408 0.1103908920 0.2007572055 0.0131397791 0.0865370000 204629222 0 1222762496 0.1276578903 -0.0739007369 -0.0254320893 138 5.4800000000 0.1870580614 0.1109464512 0.2007572055 0.0131959221 0.0831940000 204630476 0 1223270400 0.1259597838 -0.0734698102 -0.0241444651 139 5.5200000000 0.1842456013 0.1114737832 0.2007572055 0.0131680376 0.0796650000 204631730 0 1223778304 0.1270706654 -0.0738799870 -0.0237685665 140 5.5600000000 0.1834056973 0.1119875826 0.2007572055 0.0131555648 0.0784190000 204632984 0 1224286208 0.1276291758 -0.0742867887 -0.0239962209 141 5.6000000000 0.1835715473 0.1124952703 0.2007572055 0.0131398510 0.0768380000 204634238 0 1224912896 0.1268808246 -0.0755026489 -0.0233428124 142 5.6400000000 0.1837214530 0.1129968632 0.2007572055 0.0131201910 0.0773400000 204635492 0 1225420800 0.1267465502 -0.0762134790 -0.0230685715 143 5.6800000000 0.1820441037 0.1134797110 0.2007572055 0.0130942492 0.0766870000 204636746 0 1225928704 0.1255792230 -0.0747617185 -0.0221780669 144 5.7200000000 0.1809592396 0.1139483188 0.2007572055 0.0130660081 0.0838800000 204638000 0 1226436608 0.1240854040 -0.0750002414 -0.0220386870 145 5.7600000000 0.1800791621 0.1144043936 0.2007572055 0.0130413332 0.0779720000 204639254 0 1226944512 0.1253936589 -0.0757547617 -0.0217713248 146 5.8000000000 0.1799381375 0.1148532549 0.2007572055 0.0130067701 0.0818910000 204640508 0 1227579392 0.1225292981 -0.0743729100 -0.0213208124 147 5.8400000000 0.1788498610 0.1152886059 0.2007572055 0.0129787644 0.0822590000 204641762 0 1228087296 0.1205739081 -0.0737889931 -0.0205103345 148 5.8800000000 0.1791667342 0.1157202149 0.2007572055 0.0129574493 0.0822700000 204643016 0 1228595200 0.1194429249 -0.0741116405 -0.0202094708 149 5.9200000000 0.1774844825 0.1161347402 0.2007572055 0.0129289442 0.0816900000 204644270 0 1229103104 0.1170819402 -0.0730409026 -0.0194288753 150 5.9600000000 0.1746820211 0.1165250554 0.2007572055 0.0129041758 0.0818660000 204645524 0 1229737984 0.1149766594 -0.0721930563 -0.0184845161 151 6.0000000000 0.1733251810 0.1169012152 0.2007572055 0.0128860124 0.0867510000 204646778 0 1230245888 0.1136507466 -0.0734824836 -0.0174030773 152 6.0400000000 0.1689778864 0.1172438249 0.2007572055 0.0128773720 0.0737070000 204648032 0 1230753792 0.1143412068 -0.0737789273 -0.0171599109 153 6.0800000000 0.1680802703 0.1175760892 0.2007572055 0.0128511445 0.0751320000 204649286 0 1231261696 0.1117437258 -0.0730794966 -0.0161661711 154 6.1200000000 0.1666680127 0.1178948679 0.2007572055 0.0128343268 0.0730040000 204650540 0 1231769600 0.1105878949 -0.0719690695 -0.0158145372 155 6.1600000000 0.1652884036 0.1182006327 0.2007572055 0.0128127786 0.0739950000 204651794 0 1232404480 0.1060078591 -0.0703772977 -0.0144144790 156 6.2000000000 0.1618569344 0.1184804808 0.2007572055 0.0127962401 0.0796190000 204653048 0 1232912384 0.1043033972 -0.0685900822 -0.0140167251 157 6.2400000000 0.1603433341 0.1187471231 0.2007572055 0.0127994746 0.0714970000 204654302 0 1233420288 0.1045058742 -0.0704492256 -0.0134459501 158 6.2800000000 0.1648894697 0.1190391633 0.2007572055 0.0127968581 0.0802250000 204655556 0 1233928192 0.0959503502 -0.0694241002 -0.0115057779 159 6.3200000000 0.1627550721 0.1193141061 0.2007572055 0.0127964398 0.0813300000 204656810 0 1234436096 0.0944356844 -0.0693475530 -0.0110832583 160 6.3600000000 0.1618007571 0.1195796477 0.2007572055 0.0127860898 0.0804300000 204658064 0 1235070976 0.0927834287 -0.0688796416 -0.0105956029 161 6.4000000000 0.1600513160 0.1198310245 0.2007572055 0.0128012553 0.0712010000 204659318 0 1235578880 0.0938887522 -0.0700677112 -0.0096742893 162 6.4400000000 0.1599395275 0.1200786079 0.2007572055 0.0127911529 0.0821000000 204660572 0 1236086784 0.0878342092 -0.0688798428 -0.0089914575 163 6.4800000000 0.1573803127 0.1203074527 0.2007572055 0.0127772096 0.0820670000 204661826 0 1236594688 0.0855689198 -0.0680951178 -0.0083212052 164 6.5200000000 0.1570303589 0.1205313729 0.2007572055 0.0127760929 0.0727020000 204663080 0 1237102592 0.0823861435 -0.0686990023 -0.0069157742 165 6.5600000000 0.1547664255 0.1207388580 0.2007572055 0.0127705606 0.0707810000 204664334 0 1237737472 0.0843391046 -0.0699166879 -0.0068084970 166 6.6000000000 0.1523288339 0.1209291591 0.2007572055 0.0127564710 0.0787020000 204665588 0 1238245376 0.0788668543 -0.0680837333 -0.0057566962 167 6.6400000000 0.1504098624 0.1211056902 0.2007572055 0.0127747749 0.0730010000 204666842 0 1238753280 0.0768890083 -0.0680470094 -0.0044804146 168 6.6800000000 0.1539875567 0.1213014156 0.2007572055 0.0127880657 0.0723460000 204668096 0 1239388160 0.0724498481 -0.0705136061 -0.0025227121 169 6.7200000000 0.1531772465 0.1214900300 0.2007572055 0.0128003885 0.0711410000 204669350 0 1239896064 0.0665036738 -0.0680410638 -0.0007917500 170 6.7600000000 0.1495420039 0.1216550416 0.2007572055 0.0128409902 0.0755360000 204670604 0 1240403968 0.0682346895 -0.0703189522 -0.0009266090 171 6.8000000000 0.1460092217 0.1217974637 0.2007572055 0.0128251734 0.0849270000 204671858 0 1240911872 0.0676165968 -0.0650874972 -0.0021164664 172 6.8400000000 0.1452227384 0.1219336572 0.2007572055 0.0128593958 0.0747040000 204673112 0 1241546752 0.0671968758 -0.0651222765 -0.0017893550 173 6.8800000000 0.1454636902 0.1220696689 0.2007572055 0.0128852886 0.0747620000 204674366 0 1242054656 0.0654697642 -0.0646605119 -0.0009155904 174 6.9200000000 0.1434414536 0.1221924953 0.2007572055 0.0129275821 0.0817570000 204675620 0 1242562560 0.0649473891 -0.0648712814 -0.0011487560 175 6.9600000000 0.1428266019 0.1223104045 0.2007572055 0.0130005013 0.0785550000 204676874 0 1243070464 0.0671061948 -0.0655617639 -0.0008774412 176 7.0000000000 0.1450542212 0.1224396307 0.2007572055 0.0130351322 0.0775490000 204678128 0 1243705344 0.0672755837 -0.0677521899 -0.0006653430 177 7.0400000000 0.1443480402 0.1225634070 0.2007572055 0.0130904170 0.0760550000 204679382 0 1244213248 0.0678131655 -0.0680209696 -0.0008258204 178 7.0800000000 0.1453375518 0.1226913517 0.2007572055 0.0131771675 0.0798970000 204680636 0 1244721152 0.0686182976 -0.0719214380 -0.0001755760 179 7.1200000000 0.1410599500 0.1227939695 0.2007572055 0.0132559440 0.0756860000 204681890 0 1245229056 0.0692098364 -0.0702755079 -0.0016657298 180 7.1600000000 0.1400179118 0.1228896581 0.2007572055 0.0132796743 0.0737830000 204683144 0 1245736960 0.0701461583 -0.0690142140 -0.0009646994 181 7.2000000000 0.1406048387 0.1229875320 0.2007572055 0.0132665601 0.0725810000 204684398 0 1246371840 0.0664288551 -0.0688016564 -0.0004886894 182 7.2400000000 0.1422176361 0.1230931919 0.2007572055 0.0132727642 0.0729340000 204685652 0 1246879744 0.0659007132 -0.0695940778 -0.0003694876 183 7.2800000000 0.1414528638 0.1231935180 0.2007572055 0.0132598815 0.0731900000 204686906 0 1247387648 0.0637963489 -0.0701973811 -0.0000933081 184 7.3200000000 0.1407754570 0.1232890720 0.2007572055 0.0132575142 0.0734760000 204688160 0 1247895552 0.0605623424 -0.0692607090 0.0003101233 185 7.3600000000 0.1391339600 0.1233747201 0.2007572055 0.0132493339 0.0751410000 204689414 0 1248403456 0.0596433505 -0.0701844245 0.0005715671 186 7.4000000000 0.1429893225 0.1234801749 0.2007572055 0.0132791151 0.0761220000 204690668 0 1249038336 0.0559268631 -0.0723349005 0.0021066729 187 7.4400000000 0.1374582201 0.1235549238 0.2007572055 0.0132867752 0.2172730000 216990770 0 1261862912 0.0559837669 -0.0690931752 0.0010740370 188 7.4800000000 0.1354077160 0.1236179706 0.2007572055 0.0132820279 0.0662120000 220649872 0 1265799168 0.0498525687 -0.0643807054 0.0014600719 189 7.5200000000 0.1356460005 0.1236816110 0.2007572055 0.0133133772 0.0637090000 223843222 0 1269600256 0.0484673642 -0.0645534173 0.0013370276 190 7.5600000000 0.1333096474 0.1237322848 0.2007572055 0.0133605122 0.1111220000 223844476 0 1270235136 0.0465805940 -0.0636839122 0.0021091818 191 7.6000000000 0.1342065781 0.1237871241 0.2007572055 0.0134051068 0.0961320000 223845730 0 1270870016 0.0463781059 -0.0641089752 0.0019854340 192 7.6400000000 0.1326206326 0.1238331319 0.2007572055 0.0134242862 0.0972750000 223846984 0 1271377920 0.0450558178 -0.0635706708 0.0021878267 193 7.6800000000 0.1324414909 0.1238777348 0.2007572055 0.0134628506 0.0926990000 223848238 0 1271885824 0.0446895026 -0.0637095496 0.0022922037 194 7.7200000000 0.1300828904 0.1239097202 0.2007572055 0.0134683157 0.0952560000 223849492 0 1272393728 0.0438015535 -0.0633543655 0.0022149186 195 7.7600000000 0.1314172596 0.1239482204 0.2007572055 0.0134705587 0.0897400000 223850746 0 1273028608 0.0442847125 -0.0631668866 0.0018191668 196 7.8000000000 0.1294997483 0.1239765445 0.2007572055 0.0134558996 0.0873550000 223852000 0 1273536512 0.0427972414 -0.0631059781 0.0019075277 197 7.8400000000 0.1322494894 0.1240185391 0.2007572055 0.0134940747 0.0843880000 223853254 0 1274044416 0.0436695144 -0.0636891201 0.0021912239 198 7.8800000000 0.1319258511 0.1240584751 0.2007572055 0.0135012963 0.0832920000 223854508 0 1274552320 0.0429439060 -0.0640272051 0.0022454057 199 7.9200000000 0.1339627504 0.1241082453 0.2007572055 0.0135587880 0.0894780000 223855762 0 1275060224 0.0458674617 -0.0640857443 0.0018380149 200 7.9600000000 0.1359016597 0.1241672124 0.2007572055 0.0135902012 0.0917740000 223857016 0 1275695104 0.0453391783 -0.0659725890 0.0020697347 201 8.0000000000 0.1355780810 0.1242239828 0.2007572055 0.0136102279 0.0808370000 223858270 0 1276203008 0.0463511422 -0.0643177256 0.0016613093 202 8.0400000000 0.1354752779 0.1242796823 0.2007572055 0.0136105402 0.0876940000 223859524 0 1276710912 0.0453520156 -0.0646868050 0.0018301524 203 8.0800000000 0.1343179792 0.1243291321 0.2007572055 0.0135903043 0.0819230000 223860778 0 1277218816 0.0452907793 -0.0644390583 0.0015617929 204 8.1200000000 0.1372203082 0.1243923241 0.2007572055 0.0135665029 0.0849170000 223862032 0 1277853696 0.0437094681 -0.0655817315 0.0020501569 205 8.1600000000 0.1352907270 0.1244454870 0.2007572055 0.0135409331 0.0808860000 223863286 0 1278361600 0.0418002158 -0.0649704635 0.0029476476 206 8.1999999990 0.1301074326 0.1244729722 0.2007572055 0.0135226327 0.0873900000 223864540 0 1278869504 0.0414339416 -0.0627736226 0.0031398349 207 8.2400000000 0.1324580312 0.1245115474 0.2007572055 0.0135338386 0.0779130000 223865794 0 1279377408 0.0408491604 -0.0652703568 0.0033810886 208 8.2799999990 0.1300931126 0.1245383818 0.2007572055 0.0135524674 0.0864770000 223867048 0 1279885312 0.0392245688 -0.0635329485 0.0047073993 209 8.3200000000 0.1320190877 0.1245741747 0.2007572055 0.0135748844 0.0807360000 223868302 0 1280520192 0.0393960737 -0.0656735301 0.0051786103 210 8.3599999990 0.1320472062 0.1246097605 0.2007572055 0.0135829238 0.0752990000 223869556 0 1281028096 0.0394341573 -0.0646704063 0.0042558722 211 8.4000000000 0.1327650994 0.1246484114 0.2007572055 0.0136138815 0.0815080000 223870810 0 1281536000 0.0368105806 -0.0647569820 0.0052694995 212 8.4399999990 0.1287108064 0.1246675737 0.2007572055 0.0136399962 0.0785730000 223872064 0 1282043904 0.0366242714 -0.0622722059 0.0058605894 213 8.4800000000 0.1288120598 0.1246870314 0.2007572055 0.0136549121 0.0742400000 223873318 0 1282678784 0.0356553420 -0.0634887516 0.0057490785 214 8.5200000000 0.1281346977 0.1247031419 0.2007572055 0.0136646368 0.0832590000 223874572 0 1283186688 0.0336954556 -0.0621627495 0.0067214654 215 8.5600000000 0.1255307049 0.1247069911 0.2007572055 0.0136975430 0.2051160000 236173746 0 1296138240 0.0329856612 -0.0613152608 0.0070980885 216 8.6000000000 0.1232833043 0.1247003999 0.2007572055 0.0137253867 0.1268030000 239833688 0 1300074496 0.0396939367 -0.0578656532 0.0061928551 217 8.6400000000 0.1282401085 0.1247167120 0.2007572055 0.0137774995 0.0957900000 243027038 0 1303883776 0.0431268886 -0.0649105161 0.0062046382 218 8.6800000000 0.1301386654 0.1247415833 0.2007572055 0.0137784279 0.0981230000 243028292 0 1304518656 0.0392443873 -0.0637818202 0.0086636078 219 8.7200000000 0.1243854612 0.1247399572 0.2007572055 0.0138371448 0.0905850000 243029546 0 1305153536 0.0420584008 -0.0583799221 0.0083875079 220 8.7600000000 0.1257905811 0.1247447327 0.2007572055 0.0139045409 0.0832970000 243030800 0 1305661440 0.0446058884 -0.0637234822 0.0097197909 221 8.8000000000 0.1273952723 0.1247567261 0.2007572055 0.0139761129 0.0919600000 243032054 0 1306169344 0.0480840467 -0.0665156245 0.0105430111 222 8.8400000000 0.1246738508 0.1247563528 0.2007572055 0.0139476270 0.0750760000 243033308 0 1306804224 0.0375525877 -0.0543967038 0.0115681067 223 8.8800000000 0.1232635528 0.1247496586 0.2007572055 0.0139929820 0.2246680000 255335950 0 1319628800 0.0365291163 -0.0539529622 0.0125523433 224 8.9200000000 0.1177111045 0.1247182365 0.2007572055 0.0140013303 0.0784970000 258995052 0 1323565056 0.0361052677 -0.0498189516 0.0120898020 225 8.9600000000 0.0956537798 0.1245890612 0.2007572055 0.0141027537 0.1042140000 262188402 0 1327374336 0.0226695873 -0.0471626334 0.0074042813 226 9.0000000000 0.0984409302 0.1244733615 0.2007572055 0.0140976365 0.0967480000 262189656 0 1328009216 0.0211610924 -0.0489265881 0.0068653016 227 9.0400000000 0.0970056355 0.1243523583 0.2007572055 0.0141084149 0.1057730000 262190910 0 1328644096 0.0202383604 -0.0497117676 0.0069884653 228 9.0800000000 0.0954114124 0.1242254243 0.2007572055 0.0141116860 0.0851280000 262192164 0 1329152000 0.0189140439 -0.0489629135 0.0069111721 229 9.1200000000 0.0945654809 0.1240959049 0.2007572055 0.0141177625 0.0787190000 262193418 0 1329659904 0.0182747040 -0.0500575453 0.0067356010 230 9.1600000000 0.0935348272 0.1239630306 0.2007572055 0.0141228306 0.0745400000 262194672 0 1330159616 0.0168784913 -0.0498302802 0.0066018384 231 9.2000000000 0.0920237228 0.1238247652 0.2007572055 0.0141261488 0.0755360000 262195926 0 1330794496 0.0157712009 -0.0494968593 0.0062891697 232 9.2400000000 0.0912754461 0.1236844665 0.2007572055 0.0141315548 0.0807110000 262197180 0 1331302400 0.0149843805 -0.0502667949 0.0063183089 233 9.2800000000 0.0920428261 0.1235486654 0.2007572055 0.0141351515 0.2629530000 274510790 0 1344126976 0.0137106981 -0.0503762364 0.0062794336 234 9.3200000000 0.0912767053 0.1234107511 0.2007572055 0.0141438311 0.0717220000 278169892 0 1348190208 0.0147675127 -0.0508434847 0.0048944126 235 9.3600000000 0.0901126787 0.1232690571 0.2007572055 0.0141651035 0.0722610000 281363242 0 1351872512 0.0140364598 -0.0507297702 0.0047488408 236 9.4000000000 0.0888638571 0.1231232724 0.2007572055 0.0142032610 0.1128590000 281364496 0 1352634368 0.0130890971 -0.0508081689 0.0046754684 237 9.4400000000 0.0862196088 0.1229675607 0.2007572055 0.0142389680 0.1036390000 281365750 0 1353269248 0.0120271277 -0.0511409901 0.0045595802 238 9.4800000000 0.0826263353 0.1227980598 0.2007572055 0.0142735818 0.1046750000 281367004 0 1353777152 0.0111544905 -0.0518138185 0.0044696415 239 9.5200000000 0.0826517642 0.1226300837 0.2007572055 0.0142802779 0.0986250000 281368258 0 1354285056 0.0096920757 -0.0514776967 0.0045538750 240 9.5600000000 0.0776845962 0.1224428108 0.2007572055 0.0144737719 0.3092060000 293671504 0 1367109632 0.0092186453 -0.0530227125 0.0047414489 241 9.6000000000 0.0768507347 0.1222536321 0.2007572055 0.0144716406 0.0622010000 297330606 0 1371172864 0.0071757068 -0.0520664565 0.0044284118 242 9.6400000000 0.0742944553 0.1220554536 0.2007572055 0.0144911938 0.0581710000 300523956 0 1374982144 0.0069000493 -0.0519706719 0.0044619716 243 9.6800000000 0.0721209794 0.1218499620 0.2007572055 0.0145139461 0.0554090000 300525210 0 1375744000 0.0063166777 -0.0524387546 0.0044795922 244 9.7200000000 0.0716085285 0.1216440545 0.2007572055 0.0145252398 0.0605090000 300526464 0 1376378880 0.0058240681 -0.0526874103 0.0045908587 245 9.7600000000 0.0723624378 0.1214429050 0.2007572055 0.0145203398 0.1280460000 300527718 0 1376886784 0.0048265918 -0.0526376292 0.0046016653 246 9.8000000000 0.0712809712 0.1212389947 0.2007572055 0.0145269181 0.1085810000 300528972 0 1377394688 0.0044915308 -0.0529425442 0.0045149866 247 9.8400000000 0.0708452910 0.1210349716 0.2007572055 0.0145290459 0.3150190000 312831094 0 1390219264 0.0030687258 -0.0528770573 0.0043342658 248 9.8800000000 0.0674848780 0.1208190438 0.2007572055 0.0145368911 0.0553910000 316490196 0 1394155520 0.0021592160 -0.0525850058 0.0045974026 249 9.9200000000 0.0654110461 0.1205965217 0.2007572055 0.0145406355 0.1245470000 319683546 0 1397964800 0.0010825935 -0.0530725755 0.0039379341 250 9.9600000000 0.0658550262 0.1203775558 0.2007572055 0.0145327258 0.1108670000 319684800 0 1398599680 0.0005306058 -0.0530817881 0.0036536132 251 10.0000000000 0.0645986870 0.1201553292 0.2007572055 0.0145336667 0.1093920000 319686054 0 1399234560 -0.0006441463 -0.0536311455 0.0033930817 252 10.0400000000 0.0636086389 0.1199309376 0.2007572055 0.0145374830 0.1113470000 319687308 0 1399742464 -0.0018786140 -0.0539707206 0.0029418620 253 10.0800000000 0.0638169721 0.1197091432 0.2007572055 0.0145337620 0.1020640000 319688562 0 1400250368 -0.0025826737 -0.0541562326 0.0025844835 254 10.1200000000 0.0632325411 0.1194867944 0.2007572055 0.0145327606 0.3467010000 331991548 0 1413074944 -0.0030571094 -0.0547440015 0.0023432176 255 10.1600000000 0.0630805939 0.1192655936 0.2007572055 0.0145288859 0.0533210000 335650650 0 1417138176 -0.0034835166 -0.0546351299 0.0019528425 256 10.2000000000 0.0631423220 0.1190463621 0.2007572055 0.0145308637 0.0537560000 338844000 0 1420820480 -0.0034304434 -0.0549080856 0.0017127573 257 10.2400000000 0.0617552139 0.1188234393 0.2007572055 0.0146477848 0.1296220000 338866758 0 1421582336 -0.0049340497 -0.0554190017 0.0011724107 258 10.2800000000 0.0624356084 0.1186048818 0.2007572055 0.0146500794 0.1187490000 338909996 0 1422217216 -0.0056514512 -0.0558114648 0.0007266335 259 10.3200000000 0.0623565130 0.1183877067 0.2007572055 0.0146397849 0.1154750000 338911250 0 1422725120 -0.0062198904 -0.0559052154 0.0003240446 260 10.3600000000 0.0619402938 0.1181706012 0.2007572055 0.0146286632 0.1115800000 338912504 0 1423360000 -0.0069685979 -0.0563809089 -0.0000747744 261 10.4000000000 0.0624119528 0.1179569666 0.2007572055 0.0146104872 0.1119220000 338913758 0 1423867904 -0.0071287267 -0.0570200607 -0.0005977491 262 10.4400000000 0.0627632886 0.1177463037 0.2007572055 0.0145939721 0.1041300000 338915012 0 1424375808 -0.0072863372 -0.0577048287 -0.0011398632 263 10.4800000000 0.0629360527 0.1175378997 0.2007572055 0.0145747676 0.4237120000 351240646 0 1437200384 -0.0082072001 -0.0579170026 -0.0015361034 264 10.5200000000 0.0623343624 0.1173287954 0.2007572055 0.0145628203 0.0502850000 354899748 0 1441263616 -0.0088057118 -0.0572912954 -0.0013451079 265 10.5600000000 0.0636575073 0.1171262622 0.2007572055 0.0145570036 0.0583040000 358093098 0 1444945920 -0.0084691094 -0.0577502102 -0.0024523423 266 10.6000000000 0.0643198118 0.1169277417 0.2007572055 0.0145482693 0.1182540000 358094352 0 1445707776 -0.0089827310 -0.0581186973 -0.0030443713 267 10.6400000000 0.0653246716 0.1167344718 0.2007572055 0.0145523307 0.1204690000 358095606 0 1446215680 -0.0095667876 -0.0582183599 -0.0037394019 268 10.6800000000 0.0661615208 0.1165457668 0.2007572055 0.0145580239 0.1291740000 358096860 0 1446723584 -0.0106281675 -0.0588645600 -0.0041051460 269 10.7200000000 0.0665757507 0.1163600046 0.2007572055 0.0145678427 0.1119280000 358098114 0 1447358464 -0.0115232626 -0.0590925962 -0.0047292789 270 10.7600000000 0.0681139082 0.1161813154 0.2007572055 0.0145739229 0.1087800000 358099368 0 1447866368 -0.0119676329 -0.0597563237 -0.0058504753 271 10.8000000000 0.0690425336 0.1160073715 0.2007572055 0.0145732867 0.1075600000 358100622 0 1448374272 -0.0128500145 -0.0605563149 -0.0066169263 272 10.8400000000 0.0699894950 0.1158381882 0.2007572055 0.0145850389 0.1033930000 358101876 0 1448882176 -0.0137381172 -0.0609608963 -0.0075163110 273 10.8800000000 0.0716096908 0.1156761790 0.2007572055 0.0145977288 0.1030520000 358103130 0 1449390080 -0.0143521531 -0.0618886054 -0.0085207829 274 10.9200000000 0.0722314045 0.1155176214 0.2007572055 0.0146023749 0.1010400000 358104384 0 1450024960 -0.0152709428 -0.0621753335 -0.0089249229 275 10.9600000000 0.0734491944 0.1153646453 0.2007572055 0.0146077253 0.1014350000 358105638 0 1450532864 -0.0157263372 -0.0631320626 -0.0096918289 276 11.0000000000 0.0749930292 0.1152183714 0.2007572055 0.0146027726 0.1000060000 358106892 0 1451040768 -0.0162699167 -0.0634951144 -0.0103072366 277 11.0400000000 0.0792447478 0.1150885027 0.2007572055 0.0149106929 0.0914750000 358108146 0 1451548672 -0.0187846571 -0.0647645071 -0.0127405049 278 11.0800000000 0.0791930929 0.1149593825 0.2007572055 0.0149030158 0.0919670000 358109400 0 1452056576 -0.0202668998 -0.0632106215 -0.0130432704 279 11.1200000000 0.0784262195 0.1148284393 0.2007572055 0.0148877509 0.0897330000 358110654 0 1452691456 -0.0223447494 -0.0618681982 -0.0126743112 280 11.1600000000 0.0789835900 0.1147004220 0.2007572055 0.0148760886 0.0894800000 358111908 0 1453199360 -0.0229148939 -0.0623803064 -0.0127918571 281 11.2000000000 0.0791894868 0.1145740485 0.2007572055 0.0148767250 0.0769990000 358113162 0 1453707264 -0.0236270092 -0.0615502931 -0.0130663514 282 11.2400000000 0.0802157372 0.1144522105 0.2007572055 0.0148726926 0.4618650000 370417340 0 1466531840 -0.0242665857 -0.0619773529 -0.0134116560 283 11.2800000000 0.0833294392 0.1143422361 0.2007572055 0.0148777301 0.0501280000 374076442 0 1470722048 -0.0214199275 -0.0646982044 -0.0141634848 284 11.3200000000 0.0843515769 0.1142366352 0.2007572055 0.0148862004 0.0471900000 377269792 0 1474404352 -0.0214139540 -0.0648574010 -0.0147828320 285 11.3600000000 0.0852998868 0.1141351027 0.2007572055 0.0148850920 0.0811430000 377271046 0 1475166208 -0.0213338584 -0.0650966614 -0.0154879401 286 11.4000000000 0.0857876167 0.1140359856 0.2007572055 0.0148740676 0.1157260000 377272300 0 1475674112 -0.0217320900 -0.0655245259 -0.0156721510 287 11.4400000000 0.0862971619 0.1139393347 0.2007572055 0.0148590118 0.1144130000 377273554 0 1476308992 -0.0219698977 -0.0659583658 -0.0159212220 288 11.4800000000 0.0871959552 0.1138464757 0.2007572055 0.0148387242 0.1099310000 377274808 0 1476816896 -0.0224201474 -0.0663464814 -0.0162644815 289 11.5200000000 0.0876617506 0.1137558711 0.2007572055 0.0148274197 0.1093860000 377276062 0 1477324800 -0.0221373681 -0.0669154972 -0.0166364424 290 11.5600000000 0.0882684141 0.1136679834 0.2007572055 0.0148135483 0.1047840000 377277316 0 1477832704 -0.0222445298 -0.0672139153 -0.0168332066 291 11.6000000000 0.0881025046 0.1135801295 0.2007572055 0.0147902539 0.1008470000 377278570 0 1478467584 -0.0229461659 -0.0671143085 -0.0167260189 292 11.6400000000 0.0890828669 0.1134962347 0.2007572055 0.0147669922 0.1005060000 377279824 0 1478975488 -0.0230394863 -0.0673035532 -0.0172402281 293 11.6800000000 0.0896739438 0.1134149300 0.2007572055 0.0147422547 0.4519280000 389583550 0 1491800064 -0.0225124247 -0.0681908429 -0.0175661556 294 11.7200000000 0.0913470611 0.1133398692 0.2007572055 0.0147224757 0.0441080000 393242652 0 1495736320 -0.0222878829 -0.0690754578 -0.0159409586 295 11.7600000000 0.0915770233 0.1132660969 0.2007572055 0.0147130769 0.0448490000 396436002 0 1499545600 -0.0222117063 -0.0694004372 -0.0162966121 296 11.8000000000 0.0915892050 0.1131928641 0.2007572055 0.0146953316 0.0415560000 396437256 0 1500180480 -0.0223848652 -0.0695774555 -0.0163571276 297 11.8400000000 0.0925579146 0.1131233862 0.2007572055 0.0146906979 0.0436050000 396438510 0 1500815360 -0.0219887923 -0.0687425956 -0.0169355329 298 11.8800000000 0.0948720649 0.1130621401 0.2007572055 0.0147433446 0.0620600000 396439764 0 1501323264 -0.0215428695 -0.0691192821 -0.0179024879 299 11.9200000000 0.0956589803 0.1130039356 0.2007572055 0.0147409010 0.1097880000 396441018 0 1501831168 -0.0220668223 -0.0704318359 -0.0180936772 300 11.9600000000 0.0966230556 0.1129493326 0.2007572055 0.0147712131 0.0860260000 396442272 0 1502466048 -0.0219667200 -0.0691974461 -0.0182835218 301 12.0000000000 0.0980589911 0.1128998631 0.2007572055 0.0147904152 0.4674740000 408751698 0 1515290624 -0.0217971262 -0.0690727979 -0.0188162606 302 12.0400000000 0.1036160067 0.1128691218 0.2007572055 0.0148902918 0.0565360000 412412456 0 1519226880 -0.0227850806 -0.0648167133 -0.0170610547 303 12.0800000000 0.1059426814 0.1128462623 0.2007572055 0.0148837402 0.0869040000 415605806 0 1523036160 -0.0224807095 -0.0645975843 -0.0178857241 304 12.1200000000 0.1082749069 0.1128312249 0.2007572055 0.0148756492 0.0882550000 415607060 0 1523671040 -0.0233898740 -0.0643632263 -0.0181368403 305 12.1600000000 0.1102969274 0.1128229158 0.2007572055 0.0148755420 0.0836790000 415608314 0 1524305920 -0.0236544181 -0.0639936030 -0.0185805093 306 12.2000000000 0.1121292561 0.1128206489 0.2007572055 0.0148902381 0.0790620000 415609568 0 1524813824 -0.0238838308 -0.0637795255 -0.0189084820 307 12.2400000000 0.1149511412 0.1128275886 0.2007572055 0.0148955964 0.3549670000 432975606 0 1531543552 -0.0238838308 -0.0637795255 -0.0189084820 308 12.2800000000 0.1201384291 0.1128513251 0.2007572055 0.0149086502 0.0544330000 436322600 0 1535479808 -0.0201329514 -0.0629448965 -0.0206434149 309 12.3200000000 0.1237167343 0.1128864882 0.2007572055 0.0149086172 0.0457780000 436400686 0 1536114688 -0.0201329514 -0.0629448965 -0.0206434149 310 12.3600000000 0.1273234487 0.1129330591 0.2007572055 0.0149051323 0.0382210000 436478772 0 1536876544 -0.0201329514 -0.0629448965 -0.0206434149 311 12.4000000000 0.1302700788 0.1129888051 0.2007572055 0.0149007306 0.0440200000 436556858 0 1537511424 -0.0201329514 -0.0629448965 -0.0206434149 312 12.4400000000 0.1332051307 0.1130536010 0.2007572055 0.0148913815 0.0317600000 436634944 0 1538146304 -0.0201329514 -0.0629448965 -0.0206434149 313 12.4800000000 0.1361470670 0.1131273821 0.2007572055 0.0148816126 0.0293410000 436713030 0 1538781184 -0.0201329514 -0.0629448965 -0.0206434149 314 12.5200000000 0.1386289448 0.1132085972 0.2007572055 0.0148718067 0.0278770000 436791116 0 1539416064 -0.0201329514 -0.0629448965 -0.0206434149 315 12.5600000000 0.1415090412 0.1132984399 0.2007572055 0.0148585507 0.0277670000 436869202 0 1540050944 -0.0201329514 -0.0629448965 -0.0206434149 316 12.6000000000 0.1443664730 0.1133967565 0.2007572055 0.0148436766 0.0299810000 436947288 0 1540685824 -0.0201329514 -0.0629448965 -0.0206434149 317 12.6400000000 0.1471765637 0.1135033174 0.2007572055 0.0148277407 0.0256260000 437025374 0 1541320704 -0.0201329514 -0.0629448965 -0.0206434149 318 12.6800000000 0.1499528885 0.1136179387 0.2007572055 0.0148116499 0.0271730000 437103460 0 1541955584 -0.0201329514 -0.0629448965 -0.0206434149 319 12.7200000000 0.1551072299 0.1137479992 0.2007572055 0.0148141082 0.0273400000 437181546 0 1542590464 -0.0201329514 -0.0629448965 -0.0206434149 320 12.7600000000 0.1573272496 0.1138841843 0.2007572055 0.0147956819 0.0312550000 437259632 0 1543233536 -0.0201329514 -0.0629448965 -0.0206434149 321 12.8000000000 0.1598829478 0.1140274826 0.2007572055 0.0147776268 0.0343870000 437337718 0 1543868416 -0.0201329514 -0.0629448965 -0.0206434149 322 12.8400000000 0.1624857485 0.1141779742 0.2007572055 0.0147580330 0.0291890000 437415804 0 1544503296 -0.0201329514 -0.0629448965 -0.0206434149 323 12.8800000000 0.1644719094 0.1143336829 0.2007572055 0.0147411187 0.0319110000 437493890 0 1545011200 -0.0201329514 -0.0629448965 -0.0206434149 324 12.9200000000 0.1668807417 0.1144958652 0.2007572055 0.0147227477 0.0348560000 437571976 0 1545646080 -0.0201329514 -0.0629448965 -0.0206434149 325 12.9600000000 0.1689698696 0.1146634775 0.2007572055 0.0147038795 0.0244820000 437650062 0 1546280960 -0.0201329514 -0.0629448965 -0.0206434149 326 13.0000000000 0.1713377237 0.1148373249 0.2007572055 0.0146858079 0.0259660000 437728148 0 1546915840 -0.0201329514 -0.0629448965 -0.0206434149 327 13.0400000000 0.1731617898 0.1150156872 0.2007572055 0.0146691414 0.0299110000 437806234 0 1547550720 -0.0201329514 -0.0629448965 -0.0206434149 328 13.0800000000 0.1752144992 0.1151992202 0.2007572055 0.0146505719 0.0341290000 437884320 0 1548312576 -0.0201329514 -0.0629448965 -0.0206434149 329 13.1200000000 0.1767641306 0.1153863475 0.2007572055 0.0146357764 0.0262620000 437962406 0 1548947456 -0.0201329514 -0.0629448965 -0.0206434149 330 13.1600000000 0.1782739609 0.1155769161 0.2007572055 0.0146222138 0.0236630000 438040492 0 1549455360 -0.0201329514 -0.0629448965 -0.0206434149 331 13.2000000000 0.1796562821 0.1157705093 0.2007572055 0.0146144934 0.0332420000 438118578 0 1550090240 -0.0201329514 -0.0629448965 -0.0206434149 332 13.2400000000 0.1807380766 0.1159661948 0.2007572055 0.0146076382 0.0258420000 438196664 0 1550852096 -0.0201329514 -0.0629448965 -0.0206434149 333 13.2800000000 0.1820316613 0.1161645896 0.2007572055 0.0146035620 0.0309330000 438274750 0 1551360000 -0.0201329514 -0.0629448965 -0.0206434149 334 13.3200000000 0.1839764416 0.1163676191 0.2007572055 0.0146717325 0.0345540000 438352836 0 1551994880 -0.0201329514 -0.0629448965 -0.0206434149 335 13.3600000000 0.1846056134 0.1165713146 0.2007572055 0.0146763499 0.0265170000 438430922 0 1552629760 -0.0201329514 -0.0629448965 -0.0206434149 336 13.4000000000 0.1852725595 0.1167757826 0.2007572055 0.0146836986 0.0541790000 438509008 0 1553264640 -0.0201329514 -0.0629448965 -0.0206434149 337 13.4400000000 0.1858642697 0.1169807929 0.2007572055 0.0146861979 0.0513720000 438587094 0 1553899520 -0.0201329514 -0.0629448965 -0.0206434149 338 13.4800000000 0.1864242703 0.1171862470 0.2007572055 0.0146918081 0.0463930000 438665180 0 1554534400 -0.0201329514 -0.0629448965 -0.0206434149 339 13.5200000000 0.1871680021 0.1173926828 0.2007572055 0.0147009395 0.0297450000 438743266 0 1555169280 -0.0201329514 -0.0629448965 -0.0206434149 340 13.5600000000 0.1874008328 0.1175985892 0.2007572055 0.0146974151 0.0511550000 438821352 0 1555804160 -0.0201329514 -0.0629448965 -0.0206434149 341 13.6000000000 0.1877413839 0.1178042865 0.2007572055 0.0146936864 0.0545280000 438899438 0 1556439040 -0.0201329514 -0.0629448965 -0.0206434149 342 13.6400000000 0.1887588352 0.1180117559 0.2007572055 0.0146958895 0.0270820000 438977524 0 1557073920 -0.0201329514 -0.0629448965 -0.0206434149 343 13.6800000000 0.1893257946 0.1182196686 0.2007572055 0.0147002212 0.0311410000 439055610 0 1557708800 -0.0201329514 -0.0629448965 -0.0206434149 344 13.7200000000 0.1898197532 0.1184278084 0.2007572055 0.0147087611 0.0267200000 439133696 0 1558343680 -0.0201329514 -0.0629448965 -0.0206434149 345 13.7600000000 0.1908570826 0.1186377483 0.2007572055 0.0148243037 0.0524470000 439211782 0 1558978560 -0.0201329514 -0.0629448965 -0.0206434149 346 13.8000000000 0.1913621575 0.1188479344 0.2007572055 0.0148294769 0.0442550000 439289868 0 1559613440 -0.0201329514 -0.0629448965 -0.0206434149 347 13.8400000000 0.1921405792 0.1190591524 0.2007572055 0.0148370698 0.0332830000 439367954 0 1560375296 -0.0201329514 -0.0629448965 -0.0206434149 348 13.8800000000 0.1929110140 0.1192713704 0.2007572055 0.0148366664 0.0372890000 439446040 0 1561010176 -0.0201329514 -0.0629448965 -0.0206434149 349 13.9200000000 0.1937445849 0.1194847607 0.2007572055 0.0148293415 0.0472310000 439524126 0 1561645056 -0.0201329514 -0.0629448965 -0.0206434149 350 13.9600000000 0.1944921762 0.1196990676 0.2007572055 0.0148338670 0.0393210000 439602212 0 1562279936 -0.0201329514 -0.0629448965 -0.0206434149 351 14.0000000000 0.1951848716 0.1199141269 0.2007572055 0.0148396861 0.0291220000 439680298 0 1562914816 -0.0201329514 -0.0629448965 -0.0206434149 352 14.0400000000 0.1958600879 0.1201298825 0.2007572055 0.0148474501 0.0407030000 439758384 0 1563549696 -0.0201329514 -0.0629448965 -0.0206434149 353 14.0800000000 0.1964731961 0.1203461525 0.2007572055 0.0148620200 0.0344320000 439836470 0 1564184576 -0.0201329514 -0.0629448965 -0.0206434149 354 14.1200000000 0.1969049722 0.1205624203 0.2007572055 0.0148724678 0.0340790000 439914556 0 1564819456 -0.0201329514 -0.0629448965 -0.0206434149 355 14.1600000000 0.1973847151 0.1207788212 0.2007572055 0.0148732284 0.0318470000 439992642 0 1565454336 -0.0201329514 -0.0629448965 -0.0206434149 356 14.2000000000 0.1981579065 0.1209961782 0.2007572055 0.0148724606 0.0304860000 440070728 0 1566089216 -0.0201329514 -0.0629448965 -0.0206434149 357 14.2400000000 0.1985703111 0.1212134726 0.2007572055 0.0148707721 0.0300830000 440148814 0 1566724096 -0.0201329514 -0.0629448965 -0.0206434149 358 14.2800000000 0.1988450140 0.1214303205 0.2007572055 0.0148743094 0.0304810000 440226900 0 1567358976 -0.0201329514 -0.0629448965 -0.0206434149 359 14.3200000000 0.1992028505 0.1216469571 0.2007572055 0.0148810035 0.0324170000 440304986 0 1567993856 -0.0201329514 -0.0629448965 -0.0206434149 360 14.3600000000 0.1995702684 0.1218634107 0.2007572055 0.0148825453 0.0225120000 440383072 0 1568628736 -0.0201329514 -0.0629448965 -0.0206434149 361 14.4000000000 0.1996883452 0.1220789923 0.2007572055 0.0148816254 0.0316300000 440461158 0 1569263616 -0.0201329514 -0.0629448965 -0.0206434149 362 14.4400000000 0.2207477093 0.1223515578 0.2207477093 0.0602973643 0.0725330000 440539244 0 1569898496 0.0113197099 -0.0374419019 -0.0183197167 363 14.4800000000 0.2419852018 0.1226811271 0.2419852018 0.0602714254 0.1400850000 429712734 0 1570533376 0.0376963727 -0.0470484942 -0.0205599293 364 14.5200000000 0.3147508800 0.1232087912 0.3147508800 0.0602525621 0.1508520000 438315756 0 1579675648 0.1220069826 -0.0802320018 -0.0390951112 365 14.5600000000 0.3133705258 0.1237297823 0.3147508800 0.0601737350 0.0445320000 442478842 0 1584119808 0.1202568561 -0.0793454051 -0.0380247124 366 14.6000000000 0.3140722811 0.1242498437 0.3147508800 0.0601168947 0.0452090000 442480096 0 1584754688 0.1200421080 -0.0796556771 -0.0359782279 367 14.6400000000 0.3150370419 0.1247696999 0.3150370419 0.0600436023 0.1398090000 442481350 0 1585262592 0.1197683439 -0.0829010829 -0.0349219702 368 14.6800000000 0.3141461015 0.1252843097 0.3150370419 0.0599717518 0.1392700000 442482604 0 1585770496 0.1175557151 -0.0861723498 -0.0326977931 369 14.7200000000 0.3126307428 0.1257920236 0.3150370419 0.0599153816 0.1357430000 442483858 0 1586405376 0.1138107330 -0.0886908695 -0.0290875565 370 14.7600000000 0.3090474308 0.1262873085 0.3150370419 0.0598434322 0.1296540000 442485112 0 1586913280 0.1107494906 -0.0875625387 -0.0275392197 371 14.8000000000 0.3062171936 0.1267722947 0.3150370419 0.0597699192 0.1298890000 442486366 0 1587421184 0.1099487916 -0.0832902938 -0.0264933351 372 14.8400000000 0.3066701591 0.1272558911 0.3150370419 0.0596998376 0.1206280000 442487620 0 1587929088 0.1123265028 -0.0802496374 -0.0249675084 373 14.8800000000 0.3046044111 0.1277313563 0.3150370419 0.0596278990 0.1104950000 442488874 0 1588436992 0.1126473770 -0.0760014653 -0.0239257812 374 14.9200000000 0.3040750623 0.1282028635 0.3150370419 0.0595548138 0.1113680000 442490128 0 1589071872 0.1127853766 -0.0756748989 -0.0222803857 375 14.9600000000 0.3013012409 0.1286644592 0.3150370419 0.0594763409 0.1428240000 442491382 0 1589579776 0.1156067029 -0.0650064945 -0.0233219974 376 15.0000000000 0.2985738814 0.1291163459 0.3150370419 0.0594024267 0.1400370000 442492636 0 1590087680 0.1149244234 -0.0624421388 -0.0224396531 377 15.0400000000 0.3076382577 0.1295898789 0.3150370419 0.0593621064 0.0990970000 442493890 0 1590595584 0.1196735501 -0.0771527663 -0.0172345862 378 15.0800000000 0.3050554097 0.1300540734 0.3150370419 0.0593029008 0.0907150000 442495144 0 1591103488 0.1170393080 -0.0785121173 -0.0155784935 379 15.1200000000 0.2994978726 0.1305011547 0.3150370419 0.0592327864 0.0948920000 442496398 0 1591738368 0.1125957221 -0.0777286291 -0.0145757440 380 15.1600000000 0.2967521250 0.1309386572 0.3150370419 0.0591632031 0.0927670000 442497652 0 1592246272 0.1121444851 -0.0768691450 -0.0149621656 381 15.2000000000 0.2944581509 0.1313678422 0.3150370419 0.0590914371 0.0881900000 442498906 0 1592754176 0.1130001917 -0.0732650012 -0.0146476105 382 15.2400000000 0.2980387211 0.1318041534 0.3150370419 0.0590227031 0.1225460000 442500160 0 1593389056 0.1239180565 -0.0643711165 -0.0163976457 383 15.2800000000 0.2921579182 0.1322228317 0.3150370419 0.0589472249 0.1270140000 442501414 0 1593896960 0.1222174093 -0.0582203344 -0.0175708719 384 15.3200000000 0.2944927514 0.1326454096 0.3150370419 0.0588834315 0.1158510000 442502668 0 1594404864 0.1265083998 -0.0595709048 -0.0172853135 385 15.3600000000 0.2918257415 0.1330588650 0.3150370419 0.0588107279 0.1240670000 442503922 0 1594920960 0.1277245730 -0.0570576079 -0.0179263912 386 15.4000000000 0.2908351421 0.1334676118 0.3150370419 0.0587371728 0.1107750000 442505176 0 1595555840 0.1296488792 -0.0551465042 -0.0186962299 387 15.4400000000 0.2874129117 0.1338654033 0.3150370419 0.0586636179 0.0896150000 442506430 0 1596063744 0.1298270077 -0.0522607639 -0.0173020922 388 15.4800000000 0.2898227572 0.1342673552 0.3150370419 0.0585923314 0.1012950000 442507684 0 1596571648 0.1359020919 -0.0519591495 -0.0167468786 389 15.5200000000 0.2905287743 0.1346690555 0.3150370419 0.0585241724 0.0932190000 442508938 0 1597071360 0.1383115053 -0.0525546297 -0.0158817116 390 15.5600000000 0.2897896767 0.1350668007 0.3150370419 0.0584520430 0.0908460000 442510192 0 1597579264 0.1413980871 -0.0525836647 -0.0158342402 391 15.6000000000 0.2899808288 0.1354630003 0.3150370419 0.0583812474 0.0964860000 442511446 0 1598214144 0.1440433860 -0.0526023731 -0.0149200270 392 15.6400000000 0.2888009846 0.1358541686 0.3150370419 0.0583109328 0.1008300000 442512700 0 1598722048 0.1469829679 -0.0521915779 -0.0151993902 393 15.6800000000 0.2877930403 0.1362407815 0.3150370419 0.0582422908 0.1012360000 442513954 0 1599229952 0.1488046199 -0.0519732162 -0.0150801539 394 15.7200000000 0.2867950797 0.1366228990 0.3150370419 0.0581745045 0.1014090000 442515208 0 1599737856 0.1508488357 -0.0511933863 -0.0153288106 395 15.7600000000 0.2855428755 0.1369999116 0.3150370419 0.0581059103 0.1030170000 442516462 0 1600245760 0.1527716219 -0.0511492379 -0.0154705746 396 15.8000000000 0.2848619819 0.1373733007 0.3150370419 0.0580361200 0.0963850000 442517716 0 1600880640 0.1548298150 -0.0517356098 -0.0151125174 397 15.8400000000 0.2828214765 0.1377396689 0.3150370419 0.0579664279 0.0926490000 442518970 0 1601388544 0.1565178931 -0.0505316928 -0.0155767016 398 15.8800000000 0.2823830843 0.1381030946 0.3150370419 0.0578967240 0.1071590000 442520224 0 1601896448 0.1573607177 -0.0501228683 -0.0163118653 399 15.9200000000 0.2807328999 0.1384605627 0.3150370419 0.0578290096 0.1012120000 442521478 0 1602404352 0.1592589915 -0.0499430634 -0.0164446998 400 15.9600000000 0.2798576057 0.1388140554 0.3150370419 0.0577594475 0.2505350000 454820556 0 1615228928 0.1603621244 -0.0502461717 -0.0166828949 401 16.0000000000 0.2622536421 0.1391218848 0.3150370419 0.0577446069 0.0687450000 458326034 0 1619038208 0.1258518845 -0.0746577606 -0.0013596367 402 16.0400000000 0.2610515356 0.1394251923 0.3150370419 0.0576767022 0.1381900000 461519384 0 1622847488 0.1266341358 -0.0748255625 -0.0013842353 403 16.0800000000 0.2604968846 0.1397256184 0.3150370419 0.0576095284 0.1138780000 461520638 0 1623482368 0.1280375123 -0.0761363953 -0.0014846219 404 16.1200000000 0.2595149875 0.1400221267 0.3150370419 0.0575462255 0.1078770000 461521892 0 1624117248 0.1286461055 -0.0764412507 -0.0013815881 405 16.1600000000 0.2589065135 0.1403156684 0.3150370419 0.0574814055 0.1151440000 461523146 0 1624625152 0.1301909536 -0.0760983601 -0.0019017245 406 16.2000000000 0.2578230202 0.1406050954 0.3150370419 0.0574142778 0.1101840000 461524400 0 1625133056 0.1316473633 -0.0759794340 -0.0021753304 407 16.2400000000 0.2560235858 0.1408886789 0.3150370419 0.0573509141 0.1065310000 461525654 0 1625640960 0.1328068227 -0.0761909410 -0.0026165117 408 16.2800000000 0.2555624247 0.1411697420 0.3150370419 0.0572878911 0.2575160000 473824180 0 1638465536 0.1347191930 -0.0766479746 -0.0027547313 409 16.3200000000 0.2543452382 0.1414464547 0.3150370419 0.0572210699 0.1162390000 477483282 0 1642528768 0.1369888335 -0.0766923353 -0.0032043038 410 16.3600000000 0.2526543140 0.1417176934 0.3150370419 0.0571567826 0.1286700000 480676632 0 1646211072 0.1385941952 -0.0772451684 -0.0032606209 411 16.3999999990 0.2505643666 0.1419825271 0.3150370419 0.0570952084 0.1128260000 480677886 0 1646845952 0.1400607526 -0.0783303231 -0.0032846660 412 16.4400000000 0.2494162917 0.1422432887 0.3150370419 0.0570331937 0.1081820000 480679140 0 1647480832 0.1408486068 -0.0783970952 -0.0033382548 413 16.4800000000 0.2484106272 0.1425003525 0.3150370419 0.0569714162 0.1086740000 480680394 0 1647988736 0.1428519934 -0.0802180097 -0.0029745658 414 16.5200000000 0.2462709248 0.1427510060 0.3150370419 0.0569064689 0.1036590000 480681648 0 1648496640 0.1430837661 -0.0794949755 -0.0037234486 415 16.5599999990 0.2451664209 0.1429977902 0.3150370419 0.0568416108 0.3017260000 492980726 0 1661448192 0.1438680142 -0.0794031844 -0.0041244975 416 16.6000000000 0.2439334095 0.1432404239 0.3150370419 0.0567756082 0.0602850000 496639828 0 1665384448 0.1437870711 -0.0793722868 -0.0045070243 417 16.6400000000 0.2431943864 0.1434801216 0.3150370419 0.0567111901 0.0602550000 499833178 0 1669193728 0.1449420601 -0.0797099173 -0.0046776612 418 16.6800000000 0.2423509955 0.1437166548 0.3150370419 0.0566461370 0.0925240000 499834432 0 1669828608 0.1450232267 -0.0801074505 -0.0047844602 419 16.7199999990 0.2409953922 0.1439488236 0.3150370419 0.0565819981 0.1319110000 499835686 0 1670336512 0.1461699158 -0.0808464736 -0.0051301746 420 16.7600000000 0.2396238595 0.1441766213 0.3150370419 0.0565196946 0.1177450000 499836940 0 1670844416 0.1469351053 -0.0817126855 -0.0047456822 421 16.8000000000 0.2378723770 0.1443991766 0.3150370419 0.0564577789 0.1147730000 499838194 0 1671479296 0.1478020549 -0.0825183839 -0.0041424828 422 16.8400000000 0.2372685373 0.1446192462 0.3150370419 0.0563954729 0.3152000000 512184068 0 1684295680 0.1485109925 -0.0823914409 -0.0043110317 423 16.8799999990 0.2354818135 0.1448340513 0.3150370419 0.0563310791 0.0541010000 515843170 0 1688231936 0.1492149234 -0.0826494396 -0.0044196569 424 16.9200000000 0.2334185988 0.1450429771 0.3150370419 0.0562685774 0.1315520000 519036520 0 1691914240 0.1499807239 -0.0833694637 -0.0043137469 425 16.9600000000 0.2325437963 0.1452488614 0.3150370419 0.0562099643 0.1227660000 519037774 0 1692676096 0.1514292359 -0.0838526189 -0.0040145470 426 17.0000000000 0.2295193225 0.1454466794 0.3150370419 0.0561471703 0.1204490000 519039028 0 1693184000 0.1519685686 -0.0853686631 -0.0034041982 427 17.0400000000 0.2275818586 0.1456390334 0.3150370419 0.0560859335 0.1220480000 519040282 0 1693691904 0.1529127806 -0.0862434581 -0.0037024189 428 17.0800000000 0.2257568687 0.1458262246 0.3150370419 0.0560251618 0.1268370000 519041536 0 1694326784 0.1538732201 -0.0863404796 -0.0041432213 429 17.1200000000 0.2241078317 0.1460086992 0.3150370419 0.0559638576 0.3345560000 531341790 0 1707151360 0.1545856148 -0.0867070407 -0.0041921684 430 17.1600000000 0.2227499634 0.1461871673 0.3150370419 0.0559043111 0.0526340000 535000892 0 1711087616 0.1543189138 -0.0861457139 -0.0057990258 431 17.2000000000 0.2212753743 0.1463613859 0.3150370419 0.0558422973 0.0817860000 538194242 0 1714769920 0.1549476832 -0.0864736214 -0.0061707930 432 17.2400000000 0.2179663479 0.1465271381 0.3150370419 0.0557795592 0.1312580000 538195496 0 1715531776 0.1556850374 -0.0883398205 -0.0057433518 433 17.2800000000 0.2160685956 0.1466877419 0.3150370419 0.0557198838 0.1238190000 538196750 0 1716039680 0.1561942101 -0.0896750093 -0.0022168541 434 17.3200000000 0.2141152918 0.1468431049 0.3150370419 0.0556607922 0.1101410000 538198004 0 1716674560 0.1569449008 -0.0907974392 0.0007883435 435 17.3600000000 0.2091317624 0.1469862972 0.3150370419 0.0556017972 0.1159650000 538199258 0 1717182464 0.1561360359 -0.0904127508 -0.0002018411 436 17.4000000000 0.2096572816 0.1471300380 0.3150370419 0.0555406801 0.3777590000 550500264 0 1730007040 0.1586281359 -0.0918055177 -0.0013379165 437 17.4400000000 0.0868810490 0.1469921685 0.3150370419 0.0806318674 0.1057280000 565065430 0 1734070272 0.0004344938 -0.0527256429 -0.0015423213 438 17.4800000000 0.0859775469 0.1468528657 0.3150370419 0.0805457021 0.1025520000 554237388 0 1734832128 0.0001247756 -0.0524123088 -0.0008984109 439 17.5200000000 0.0851000473 0.1467121987 0.3150370419 0.0804594837 0.1004220000 554238642 0 1735467008 -0.0007557612 -0.0527671985 -0.0005988048 440 17.5600000000 0.0844652578 0.1465707284 0.3150370419 0.0803721659 0.1058470000 554240408 0 1735974912 -0.0013857709 -0.0524876378 -0.0002796488 441 17.6000000000 0.0839255005 0.1464286757 0.3150370419 0.0802872404 0.1046670000 554241150 0 1736482816 -0.0020340120 -0.0527060032 0.0001946057 442 17.6400000000 0.0821482167 0.1462832448 0.3150370419 0.0802218729 0.0979380000 554242404 0 1736990720 -0.0054276204 -0.0528259017 0.0008373701 443 17.6800000000 0.0827790350 0.1461398944 0.3150370419 0.0801368725 0.0939350000 554243658 0 1737498624 -0.0055501941 -0.0522497110 0.0001155194 444 17.7200000000 0.0834462196 0.1459986925 0.3150370419 0.0800525244 0.0979580000 554244912 0 1738133504 -0.0072427322 -0.0529123619 0.0008843301 445 17.7600000000 0.0803605840 0.1458511911 0.3150370419 0.0799664944 0.0989750000 554246166 0 1738641408 -0.0080828601 -0.0534576736 0.0014589438 446 17.8000000000 0.0788227692 0.1457009032 0.3150370419 0.0798814470 0.0982010000 554247420 0 1739149312 -0.0086324858 -0.0534919016 0.0020294031 447 17.8400000000 0.0742034614 0.1455409536 0.3150370419 0.0797940560 0.0997210000 554248674 0 1739657216 -0.0083819795 -0.0532604270 0.0029322261 448 17.8800000000 0.0714711770 0.1453756193 0.3150370419 0.0797060548 0.0951350000 554249928 0 1740165120 -0.0084042912 -0.0535253920 0.0035718323 449 17.9200000000 0.0689384714 0.1452053807 0.3150370419 0.0796185962 0.0999050000 554251182 0 1740800000 -0.0093574300 -0.0535901524 0.0047284733 450 17.9600000000 0.0655626729 0.1450283969 0.3150370419 0.0795302574 0.0965600000 554252436 0 1741307904 -0.0095893489 -0.0538259335 0.0053101513 451 18.0000000000 0.0641766489 0.1448491247 0.3150370419 0.0794437362 0.0935990000 554253690 0 1741815808 -0.0098242350 -0.0540709533 0.0059043309 452 18.0400000000 0.0612027980 0.1446640665 0.3150370419 0.0793576563 0.1023370000 554254944 0 1742323712 -0.0094120195 -0.0534092821 0.0077325515 453 18.0800000000 0.0595193580 0.1444761090 0.3150370419 0.0792705474 0.0967950000 554256198 0 1742958592 -0.0090400390 -0.0540318526 0.0085390992 454 18.1200000000 0.0591054596 0.1442880680 0.3150370419 0.0791839334 0.1625190000 557791312 0 1743978496 -0.0086021638 -0.0547633208 0.0104198465 455 18.1600000000 0.0580715686 0.1440985812 0.3150370419 0.0790967922 0.0925830000 557527774 0 1746894848 -0.0070013758 -0.0559061877 0.0116014248 456 18.2000000000 0.0550588295 0.1439033185 0.3150370419 0.0790111708 0.0730340000 557529028 0 1747656704 -0.0075832964 -0.0550101325 0.0134809483 457 18.2400000000 0.0568434782 0.1437128156 0.3150370419 0.0789270428 0.0731430000 557530282 0 1748164608 -0.0078368075 -0.0545166619 0.0148601504 458 18.2800000000 0.0570565984 0.1435236099 0.3150370419 0.0788417936 0.0797760000 557531536 0 1748672512 -0.0071413442 -0.0544004366 0.0168617535 459 18.3200000000 0.0566117242 0.1433342594 0.3150370419 0.0787561696 0.0816050000 557532790 0 1749307392 -0.0067983731 -0.0543361045 0.0187286250 460 18.3600000000 0.0587300807 0.1431503373 0.3150370419 0.0786714584 0.0842250000 557534044 0 1749815296 -0.0073190974 -0.0530295186 0.0212331377 461 18.4000000000 0.0598841161 0.1429697164 0.3150370419 0.0785862536 0.0806810000 557535298 0 1750323200 -0.0061556478 -0.0535047054 0.0235470124 462 18.4400000000 0.0613415092 0.1427930320 0.3150370419 0.0785013367 0.0819640000 557536552 0 1750831104 -0.0043766648 -0.0533339046 0.0253290366 463 18.4800000000 0.0634593219 0.1426216848 0.3150370419 0.0784175180 0.0824880000 557537806 0 1751339008 -0.0049741236 -0.0517351031 0.0281690750 464 18.5200000000 0.0670562536 0.1424588283 0.3150370419 0.0783341342 0.0894070000 557539060 0 1751973888 -0.0050401562 -0.0510817319 0.0311025120 465 18.5600000000 0.0771541521 0.1423183882 0.3150370419 0.0782536013 0.0820730000 557540314 0 1752481792 -0.0039762170 -0.0489375405 0.0371417031 466 18.6000000000 0.0835146606 0.1421921999 0.3150370419 0.0781706447 0.0781820000 557541568 0 1752989696 -0.0031726300 -0.0478614718 0.0401892625 467 18.6400000000 0.0888101608 0.1420778915 0.3150370419 0.0780876303 0.0844170000 557542822 0 1753497600 -0.0020178061 -0.0477698073 0.0436238758 468 18.6800000000 0.0960595310 0.1419795616 0.3150370419 0.0780054865 0.0817030000 557544076 0 1754005504 -0.0014569812 -0.0459439568 0.0470825844 469 18.7200000000 0.1031592861 0.1418967892 0.3150370419 0.0779240639 0.0829930000 557545330 0 1754640384 -0.0009376215 -0.0449050777 0.0507161058 470 18.7600000000 0.1116105467 0.1418323504 0.3150370419 0.0778442452 0.0813540000 557546584 0 1755148288 -0.0002389366 -0.0433375724 0.0542028919 471 18.8000000000 0.1206852943 0.1417874522 0.3150370419 0.0777648788 0.0807010000 557547838 0 1755656192 0.0001590575 -0.0416081138 0.0580307618 472 18.8400000000 0.1298083961 0.1417620728 0.3150370419 0.0776837696 0.0813180000 557549092 0 1756164096 0.0012948241 -0.0396907739 0.0615166910 473 18.8800000000 0.1394506991 0.1417571862 0.3150370419 0.0776027902 0.0834320000 557550346 0 1756672000 0.0019973624 -0.0372885317 0.0651656240 474 18.9200000000 0.1481700987 0.1417707155 0.3150370419 0.0775225130 0.0921150000 557551600 0 1757433856 0.0027437175 -0.0351007842 0.0685824752 475 18.9600000000 0.1572389007 0.1418032801 0.3150370419 0.0774435806 0.0848490000 557552854 0 1757949952 0.0042232601 -0.0334983319 0.0723701343 476 19.0000000000 0.1649634689 0.1418519360 0.3150370419 0.0773643141 0.0873030000 557554108 0 1758457856 0.0053252033 -0.0324772187 0.0761450678 477 19.0400000000 0.1743258089 0.1419200154 0.3150370419 0.0772842865 0.0729240000 557555362 0 1758965760 0.0058988421 -0.0303497873 0.0797561407 478 19.0800000000 0.1836775839 0.1420073743 0.3150370419 0.0772047284 0.0845780000 557556616 0 1759473664 0.0071065910 -0.0277598146 0.0830281749 479 19.1200000000 0.1916472018 0.1421110065 0.3150370419 0.0771261253 0.0866190000 557557870 0 1760108544 0.0081587145 -0.0264888052 0.0867114738 480 19.1600000000 0.2000257969 0.1422316623 0.3150370419 0.0770478737 0.0831540000 557559124 0 1760616448 0.0100458041 -0.0249641649 0.0901557431 481 19.2000000000 0.2097707689 0.1423720763 0.3150370419 0.0769689050 0.0825870000 557560378 0 1761124352 0.0096098948 -0.0215423889 0.0933300182 482 19.2400000000 0.2182942778 0.1425295912 0.3150370419 0.0768932362 0.0890560000 557561632 0 1761632256 0.0114559950 -0.0199411642 0.0966244861 483 19.2800000000 0.2250081152 0.1427003542 0.3150370419 0.0768182613 0.0893820000 557562886 0 1762140160 0.0118976999 -0.0193808116 0.1003653035 484 19.3200000000 0.2322118133 0.1428852952 0.3150370419 0.0767428017 0.0973730000 557564140 0 1762775040 0.0132958181 -0.0189974401 0.1037580445 485 19.3600000000 0.2401424348 0.1430858254 0.3150370419 0.0766646774 0.0884570000 557565394 0 1763282944 0.0141192861 -0.0177199785 0.1071271971 486 19.4000000000 0.2486552149 0.1433030464 0.3150370419 0.0765866235 0.6639770000 569881044 0 1776234496 0.0148672517 -0.0151685709 0.1101610884 487 19.4400000000 0.2529851496 0.1435282663 0.3150370419 0.0765113783 0.0903680000 573386522 0 1780170752 0.0184918158 -0.0055582090 0.1130518690 488 19.4800000000 0.2606659532 0.1437683026 0.3150370419 0.0764338556 0.0924080000 576579872 0 1783853056 0.0186665244 -0.0045462581 0.1164069325 489 19.5200000000 0.2697188556 0.1440258702 0.3150370419 0.0763571698 0.0811780000 576581126 0 1784487936 0.0188665297 -0.0020567379 0.1195124015 490 19.5600000000 0.2779007852 0.1442990843 0.3150370419 0.0762802612 0.0817500000 576582380 0 1785122816 0.0189735815 -0.0003090387 0.1228951439 491 19.6000000000 0.2861585915 0.1445880038 0.3150370419 0.0762037334 0.0796690000 576583634 0 1785630720 0.0192200933 0.0018832464 0.1262011677 492 19.6400000000 0.2940262258 0.1448917401 0.3150370419 0.0761268596 0.0819180000 576584888 0 1786138624 0.0200628880 0.0029260518 0.1291946620 493 19.6800000000 0.3013590276 0.1452091179 0.3150370419 0.0760504634 0.0798880000 576586142 0 1786773504 0.0200755056 0.0038724446 0.1326308548 494 19.7200000000 0.3084303737 0.1455395253 0.3150370419 0.0759741001 0.0794560000 576587396 0 1787281408 0.0202388745 0.0043817805 0.1361218393 495 19.7600000000 0.3168324530 0.1458855716 0.3168324530 0.0758987047 0.0770760000 576588650 0 1787789312 0.0204360150 0.0058091711 0.1395484805 496 19.8000000000 0.3253858089 0.1462474673 0.3253858089 0.0758239700 0.0836830000 576589904 0 1786425344 0.0203664955 0.0079568690 0.1427364796 497 19.8400000000 0.3339523673 0.1466251431 0.3339523673 0.0757495005 0.0841050000 576591158 0 1785937920 0.0202161707 0.0100865085 0.1461415887 498 19.8800000000 0.3425546885 0.1470185760 0.3425546885 0.0756763356 0.0817090000 576592412 0 1786163200 0.0199846234 0.0124289421 0.1493643373 499 19.9200000000 0.3514603674 0.1474282790 0.3514603674 0.0756036996 0.0883630000 576593666 0 1785659392 0.0195904672 0.0147138499 0.1529641449 500 19.9600000000 0.3585171402 0.1478504567 0.3585171402 0.0755303757 0.0844380000 576594920 0 1785126912 0.0187476277 0.0155443074 0.1566485614 501 20.0000000000 0.3660390079 0.1482859628 0.3660390079 0.0754571465 0.0853200000 576596174 0 1785630720 0.0186164342 0.0165473409 0.1598439962 502 20.0400000000 0.3740752339 0.1487357422 0.3740752339 0.0753845194 0.0769110000 576597428 0 1786138624 0.0182154067 0.0183287784 0.1632629186 503 20.0800000000 0.3825487196 0.1492005791 0.3825487196 0.0753118531 0.0863670000 576598682 0 1786773504 0.0173507258 0.0206039250 0.1665649712 504 20.1200000000 0.3906530440 0.1496796515 0.3906530440 0.0752378310 0.0892300000 576599936 0 1787027456 0.0165852457 0.0222674105 0.1699006110 505 20.1600000000 0.3990407586 0.1501734358 0.3990407586 0.0751639909 0.0903020000 576601190 0 1787281408 0.0160130095 0.0244695190 0.1731526554 506 20.2000000000 0.4081240594 0.1506832197 0.4081240594 0.0750934274 0.0887180000 576602444 0 1787789312 0.0150626674 0.0271913987 0.1761469692 507 20.2400000000 0.4158055782 0.1512061435 0.4158055782 0.0750231867 0.0838960000 576603698 0 1786646528 0.0144863222 0.0293155853 0.1793715209 508 20.2800000000 0.4232577980 0.1517416782 0.4232577980 0.0749545598 0.0905160000 576604952 0 1786048512 0.0131809609 0.0310075693 0.1825257987 509 20.3200000000 0.4309397936 0.1522902010 0.4309397936 0.0748904908 0.0965810000 576606206 0 1786552320 0.0119611956 0.0333511345 0.1855498552 510 20.3600000000 0.4379359782 0.1528502908 0.4379359782 0.0748233611 0.0963030000 576607460 0 1787187200 0.0105296979 0.0350933224 0.1884690821 511 20.4000000000 0.4446677864 0.1534213622 0.4446677864 0.0747551680 0.0979820000 576608714 0 1787695104 0.0099049928 0.0367323048 0.1912066042 512 20.4400000000 0.4517448843 0.1540040253 0.4517448843 0.0746879700 0.1020350000 576609968 0 1787916288 0.0107011739 0.0388369076 0.1934805065 513 20.4800000000 0.4578761756 0.1545963687 0.4578761756 0.0746209908 0.0942410000 576652182 0 1786400768 0.0093594166 0.0403455570 0.1962567866 514 20.5200000000 0.4635960758 0.1551975355 0.4635960758 0.0745538449 0.0966640000 576737404 0 1786028032 0.0089577688 0.0414397717 0.1988172382 515 20.5600000000 0.4685351253 0.1558059580 0.4685351253 0.0744876375 0.0995100000 576738658 0 1786531840 0.0088515235 0.0422192030 0.2008888423 516 20.6000000000 0.4745676517 0.1564237132 0.4745676517 0.0744251886 0.0938010000 576739912 0 1787166720 0.0087577393 0.0441182740 0.2031969577 517 20.6400000000 0.4798214734 0.1570492408 0.4798214734 0.0743610087 0.1025870000 576741166 0 1787674624 0.0096268412 0.0454877056 0.2049837261 518 20.6800000000 0.4845899940 0.1576815588 0.4845899940 0.0742995538 0.0969430000 576742420 0 1787928576 0.0088034375 0.0464779139 0.2071898282 519 20.7200000000 0.4893500209 0.1583206117 0.4893500209 0.0742372730 0.0980620000 576743674 0 1786519552 0.0095760962 0.0478227399 0.2087946832 520 20.7600000000 0.4936673939 0.1589655094 0.4936673939 0.0741771699 0.1040630000 576744928 0 1787027456 0.0108264163 0.0489808992 0.2103973478 521 20.8000000000 0.4970999658 0.1596145199 0.4970999658 0.0741164669 0.0987750000 576746182 0 1787535360 0.0105581451 0.0492752679 0.2121466547 522 20.8400000000 0.5002575517 0.1602670927 0.5002575517 0.0740567005 0.6712920000 589060288 0 1787535360 0.0110922540 0.0494300388 0.2138638645 523 20.8800000000 0.5037910342 0.1609239263 0.5037910342 0.0740019866 0.0821920000 592719390 0 1788043264 0.0089928461 0.0480717011 0.2151818126 524 20.9200000000 0.5074090362 0.1615851574 0.5074090362 0.0739457956 0.0926290000 595912740 0 1786789888 0.0097381901 0.0494583957 0.2164165676 525 20.9600000000 0.5104650259 0.1622496905 0.5104650259 0.0738835349 0.1016630000 595913994 0 1785655296 0.0107692610 0.0498174615 0.2176192552 526 21.0000000000 0.5124804974 0.1629155285 0.5124804974 0.0738198905 0.0792160000 595915248 0 1785630720 0.0120426184 0.0501126759 0.2187191248 527 21.0400000000 0.5152925849 0.1635841757 0.5152925849 0.0737595008 0.0822700000 595916502 0 1786138624 0.0127466535 0.0503462069 0.2198583782 528 21.0800000000 0.5177885890 0.1642550174 0.5177885890 0.0736964380 0.0796650000 595917756 0 1786646528 0.0140784010 0.0509003028 0.2207430303 529 21.1200000000 0.5196924806 0.1649269218 0.5196924806 0.0736314748 0.0772750000 595919010 0 1787154432 0.0150156897 0.0510268658 0.2216972858 530 21.1600000000 0.5219061971 0.1656004676 0.5219061971 0.0735677188 0.0713660000 595920264 0 1787408384 0.0161079131 0.0514534898 0.2225045413 531 21.2000000000 0.5237210989 0.1662748944 0.5237210989 0.0735049121 0.0769990000 595921518 0 1787654144 0.0174414534 0.0515849292 0.2232968658 532 21.2400000000 0.5250567794 0.1669492965 0.5250567794 0.0734432884 0.0795960000 595922772 0 1786576896 0.0186729804 0.0514799692 0.2240642458 533 21.2800000000 0.5264164805 0.1676237190 0.5264164805 0.0733827211 0.0784080000 595924026 0 1786576896 0.0202605985 0.0521387681 0.2247580737 534 21.3200000000 0.5280330181 0.1682986428 0.5280330181 0.0733218862 0.6695790000 608237168 0 1787813888 0.0217057224 0.0520436689 0.2254598141 535 21.3600000000 0.5307369828 0.1689760976 0.5307369828 0.0732639358 0.0754950000 611896270 0 1787908096 0.0237522051 0.0515890010 0.2253859937 536 21.4000000000 0.5322530866 0.1696538532 0.5322530866 0.0732042941 0.1042220000 615089620 0 1786163200 0.0251389816 0.0520268716 0.2261081189 537 21.4400000000 0.5341663957 0.1703326475 0.5341663957 0.0731447640 0.0831710000 615090874 0 1786150912 0.0264066383 0.0523342490 0.2267074734 538 21.4800000000 0.5357427001 0.1710118483 0.5357427001 0.0730836097 0.0765830000 615092128 0 1786150912 0.0281120017 0.0528499670 0.2273983508 539 21.5200000000 0.5376701951 0.1716921050 0.5376701951 0.0730223364 0.0745630000 615093382 0 1786646528 0.0295792185 0.0529534519 0.2278550267 540 21.5600000000 0.5391665697 0.1723726133 0.5391665697 0.0729589790 0.0765720000 615094636 0 1787154432 0.0310886204 0.0532904118 0.2286649495 541 21.6000000000 0.5405648351 0.1730531904 0.5405648351 0.0728968997 0.0748150000 615095890 0 1787535360 0.0323250555 0.0536485165 0.2292441130 542 21.6400000000 0.5426563025 0.1737351149 0.5426563025 0.0728361204 0.0752840000 615097144 0 1787654144 0.0337779336 0.0535145141 0.2298702598 543 21.6800000000 0.5443115234 0.1744175761 0.5443115234 0.0727780681 0.0697960000 615098398 0 1786511360 0.0348403566 0.0540991724 0.2305535078 544 21.7200000000 0.5458474159 0.1751003515 0.5458474159 0.0727199316 0.0718800000 615099652 0 1786511360 0.0359150060 0.0547802486 0.2312255800 545 21.7600000000 0.5477626920 0.1757841356 0.5477626920 0.0726616663 0.0841510000 615100906 0 1787019264 0.0371405631 0.0557563938 0.2320971489 546 21.8000000000 0.5516815186 0.1764725924 0.5516815186 0.0726211492 0.0807650000 615102160 0 1787527168 0.0392061248 0.0557285137 0.2333387434 547 21.8400000000 0.5532469153 0.1771613937 0.5532469153 0.0725614400 0.0738820000 615103414 0 1787908096 0.0403997377 0.0564250872 0.2343099415 548 21.8800000000 0.5551764369 0.1778512022 0.5551764369 0.0725035140 0.0877590000 615104668 0 1788035072 0.0418596715 0.0570780374 0.2349921316 549 21.9200000000 0.5578597784 0.1785433854 0.5578597784 0.0724482430 0.0750780000 615105922 0 1786171392 0.0429491475 0.0575775132 0.2351851165 550 21.9600000000 0.5595150590 0.1792360612 0.5595150590 0.0723906398 0.0774960000 615107176 0 1786527744 0.0447102748 0.0578281023 0.2358706146 551 22.0000000000 0.5621550083 0.1799310139 0.5621550083 0.0723373748 0.0748720000 615108430 0 1787035648 0.0458496846 0.0582303852 0.2359131724 552 22.0400000000 0.5639558434 0.1806267110 0.5639558434 0.0722789265 0.0766260000 615109684 0 1787543552 0.0474594720 0.0595695265 0.2363604754 553 22.0800000000 0.5655712485 0.1813228133 0.5655712485 0.0722162508 0.0820600000 615110938 0 1788051456 0.0489777364 0.0591227151 0.2367844284 554 22.1200000000 0.5665348768 0.1820181419 0.5665348768 0.0721535719 0.0801540000 615112192 0 1788051456 0.0499151684 0.0591146536 0.2378017455 555 22.1600000000 0.5688829422 0.1827151956 0.5688829422 0.0720907773 0.0702670000 615113446 0 1786638336 0.0520860888 0.0595481768 0.2377127558 556 22.2000000000 0.5714431405 0.1834143466 0.5714431405 0.0720303729 0.6957340000 627424168 0 1786015744 0.0538735837 0.0604024418 0.2379465699 557 22.2400000000 0.5719300508 0.1841118613 0.5719300508 0.0719687628 0.0916010000 631083270 0 1787432960 0.0554070808 0.0631980598 0.2390622795 558 22.2800000000 0.5739595294 0.1848105130 0.5739595294 0.0719081893 0.1116530000 634276620 0 1786191872 0.0570895374 0.0649057254 0.2396707535 559 22.3200000000 0.5761989355 0.1855106712 0.5761989355 0.0718474141 0.0858920000 634277874 0 1785794560 0.0585129783 0.0659723654 0.2402384579 560 22.3600000000 0.5790071487 0.1862133435 0.5790071487 0.0717855328 0.0911520000 634279128 0 1785794560 0.0602479652 0.0657178536 0.2406553924 561 22.4000000000 0.5810175538 0.1869170943 0.5810175538 0.0717247167 0.0798430000 634280382 0 1785536512 0.0615034960 0.0668517500 0.2413647622 562 22.4400000000 0.5827067494 0.1876213464 0.5827067494 0.0716655250 0.0792530000 634281636 0 1785278464 0.0629279241 0.0687471256 0.2422635704 563 22.4800000000 0.5865461826 0.1883299162 0.5865461826 0.0716028250 0.0839260000 634282890 0 1785278464 0.0654947311 0.0684484243 0.2413059920 564 22.5200000000 0.5889778137 0.1890402849 0.5889778137 0.0715402334 0.0833880000 634284144 0 1785626624 0.0669540539 0.0687757060 0.2416116446 565 22.5600000000 0.5900849104 0.1897500984 0.5900849104 0.0714781359 0.0744780000 634285398 0 1786261504 0.0673466176 0.0698429048 0.2427549660 566 22.6000000000 0.5935960412 0.1904636071 0.5935960412 0.0714158821 0.0828660000 634286652 0 1786642432 0.0696415901 0.0700843260 0.2422719598 567 22.6400000000 0.5955052972 0.1911779663 0.5955052972 0.0713534380 0.0844250000 634287906 0 1786642432 0.0711763948 0.0708213449 0.2426936030 568 22.6800000000 0.5972436666 0.1918928707 0.5972436666 0.0712916123 0.0781140000 634291208 0 1787273216 0.0727754086 0.0720010623 0.2431947142 569 22.7200000000 0.5990958214 0.1926085174 0.5990958214 0.0712293633 0.0807100000 634292462 0 1787781120 0.0741899759 0.0720826164 0.2432294041 570 22.7600000000 0.6011916995 0.1933253300 0.6011916995 0.0711676025 0.0943950000 634293716 0 1786798080 0.0757024884 0.0730590969 0.2433983535 571 22.8000000000 0.6033695340 0.1940434459 0.6033695340 0.0711055266 0.0851350000 634294970 0 1786384384 0.0774440169 0.0738639012 0.2435834110 572 22.8400000000 0.6049299240 0.1947617789 0.6049299240 0.0710434383 0.0881860000 634296224 0 1786384384 0.0794496834 0.0750257224 0.2434938252 573 22.8800000000 0.6069468260 0.1954811246 0.6069468260 0.0709818126 0.0879610000 634297478 0 1786765312 0.0807788745 0.0755834803 0.2436084002 574 22.9200000000 0.6087799668 0.1962011574 0.6087799668 0.0709203846 0.0892280000 634298732 0 1787400192 0.0822472870 0.0766719952 0.2436470389 575 22.9600000000 0.6107575297 0.1969221250 0.6107575297 0.0708586901 0.0859300000 634299986 0 1787781120 0.0835234299 0.0776838139 0.2438082248 576 23.0000000000 0.6127260923 0.1976440069 0.6127260923 0.0707971264 0.0914920000 634301240 0 1787908096 0.0848731920 0.0789458603 0.2439287901 577 23.0400000000 0.6149415374 0.1983672262 0.6149415374 0.0707356903 0.0912090000 634302494 0 1786687488 0.0861251727 0.0800004900 0.2438888550 578 23.0800000000 0.6161441207 0.1990900236 0.6161441207 0.0706743871 0.5795490000 646610552 0 1786269696 0.0870381221 0.0807268620 0.2440987378 579 23.1200000000 0.6191302538 0.1998154817 0.6191302538 0.0706134596 0.0788150000 650269654 0 1787781120 0.0882458314 0.0804582834 0.2431823164 580 23.1600000000 0.6217675209 0.2005429852 0.6217675209 0.0705527726 0.1303600000 653463004 0 1786322944 0.0901162773 0.0825105608 0.2428614795 581 23.2000000000 0.6247838140 0.2012731759 0.6247838140 0.0704923179 0.1049640000 653464258 0 1786064896 0.0909158438 0.0830199569 0.2423197925 582 23.2400000000 0.6252971888 0.2020017395 0.6252971888 0.0704317320 0.1011970000 653465512 0 1786064896 0.0920547098 0.0852665231 0.2428752929 583 23.2800000000 0.6277772784 0.2027320578 0.6277772784 0.0703713592 0.0942720000 653466766 0 1786540032 0.0931046903 0.0865642801 0.2428702265 584 23.3200000000 0.6288882494 0.2034617773 0.6288882494 0.0703112326 0.0928190000 653468020 0 1787047936 0.0938376859 0.0878137350 0.2424378544 585 23.3600000000 0.6300590634 0.2041910034 0.6300590634 0.0702512654 0.1042700000 653469274 0 1787428864 0.0947669894 0.0883078799 0.2421390563 586 23.4000000000 0.6308738589 0.2049191312 0.6308738589 0.0701912155 0.0853010000 653470528 0 1787654144 0.0955496579 0.0901727527 0.2423205227 587 23.4400000000 0.6331474185 0.2056486512 0.6331474185 0.0701315162 0.0883540000 653471782 0 1786576896 0.0961636603 0.0904585645 0.2416421622 588 23.4800000000 0.6342831254 0.2063776214 0.6342831254 0.0700718507 0.0945430000 653473036 0 1786576896 0.0972122476 0.0913119018 0.2417553663 589 23.5200000000 0.6357099414 0.2071065388 0.6357099414 0.0700124087 0.0952140000 653474290 0 1787052032 0.0980909318 0.0922454074 0.2416277677 590 23.5600000000 0.6368093491 0.2078348486 0.6368093491 0.0699530862 0.0860800000 653475544 0 1787686912 0.0987776145 0.0929531530 0.2417052984 591 23.6000000000 0.6383411884 0.2085632857 0.6383411884 0.0698938979 0.0795950000 653476798 0 1787940864 0.0994050801 0.0939313993 0.2418923527 592 23.6400000000 0.6395737529 0.2092913440 0.6395737529 0.0698351593 0.1008630000 653478052 0 1786687488 0.1003777459 0.0947894305 0.2416435182 593 23.6800000000 0.6417571902 0.2100206287 0.6417571902 0.0697777473 0.0885530000 653479306 0 1786781696 0.1020366848 0.0962706134 0.2413885891 594 23.7200000000 0.6426689029 0.2107489928 0.6426689029 0.0697192116 0.0892640000 653480560 0 1787400192 0.1022186726 0.0961760059 0.2418114096 595 23.7600000000 0.6436158419 0.2114765001 0.6436158419 0.0696605284 0.0885070000 653481814 0 1787908096 0.1028581262 0.0972680226 0.2418092936 596 23.8000000000 0.6453399658 0.2122044589 0.6453399658 0.0696021065 0.1005440000 653483068 0 1785913344 0.1031601503 0.0976240113 0.2420644015 597 23.8400000000 0.6466526389 0.2129321778 0.6466526389 0.0695437729 0.0880790000 653484322 0 1786130432 0.1034293994 0.0983160362 0.2421659678 598 23.8800000000 0.6475883722 0.2136590277 0.6475883722 0.0694858187 0.0894540000 653485576 0 1786638336 0.1037241668 0.0987107530 0.2424104810 599 23.9200000000 0.6488324404 0.2143855275 0.6488324404 0.0694280961 0.0959090000 653486830 0 1787146240 0.1042132154 0.0993918106 0.2425918877 600 23.9600000000 0.6500223875 0.2151115890 0.6500223875 0.0693705953 0.0926100000 653488084 0 1787273216 0.1041646227 0.0999181420 0.2428171039 601 24.0000000000 0.6523039341 0.2158390305 0.6523039341 0.0693135058 0.0939550000 653489338 0 1787654144 0.1045052335 0.1012150347 0.2432583272 602 24.0400000000 0.6529204845 0.2165650794 0.6529204845 0.0692561489 0.0905190000 653490592 0 1786687488 0.1048174649 0.1013439670 0.2433863133 603 24.0800000000 0.6538491845 0.2172902603 0.6538491845 0.0691987796 0.0940440000 653491846 0 1786687488 0.1050980985 0.1018194631 0.2435792387 604 24.1200000000 0.6550315619 0.2180149976 0.6550315619 0.0691413962 0.7202900000 665800756 0 1786327040 0.1052808166 0.1020698994 0.2437421829 605 24.1600000000 0.6614149809 0.2187478901 0.6614149809 0.0690854896 0.0972510000 669459858 0 1786912768 0.1020942926 0.1011293232 0.2421196997 606 24.2000000000 0.6625747085 0.2194802776 0.6625747085 0.0690283715 0.1375860000 672653208 0 1785794560 0.1025026590 0.1023722440 0.2419203818 607 24.2400000000 0.6638560891 0.2202123630 0.6638560891 0.0689716847 0.1215230000 672654462 0 1785294848 0.1028267816 0.1022071317 0.2420066595 608 24.2800000000 0.6650335193 0.2209439767 0.6650335193 0.0689149916 0.1230270000 672655716 0 1785294848 0.1027803347 0.1021886691 0.2423172593 609 24.3200000000 0.6654023528 0.2216737934 0.6654023528 0.0688583067 0.1179060000 672656970 0 1785790464 0.1028638259 0.1030714884 0.2427645773 610 24.3600000000 0.6670247316 0.2224038769 0.6670247316 0.0688018479 0.1129190000 672658224 0 1786265600 0.1032572091 0.1037790477 0.2424820215 611 24.4000000000 0.6680625677 0.2231332692 0.6680625677 0.0687454417 0.1052980000 672659478 0 1786773504 0.1039227247 0.1046698540 0.2424835414 612 24.4400000000 0.6693048477 0.2238623077 0.6693048477 0.0686892833 0.1098500000 672660732 0 1786900480 0.1034465507 0.1052980870 0.2428187132 613 24.4800000000 0.6702381372 0.2245904902 0.6702381372 0.0686331815 0.1088670000 672661986 0 1787408384 0.1037356406 0.1064628661 0.2430549562 614 24.5200000000 0.6713784337 0.2253181578 0.6713784337 0.0685773763 0.1117030000 672663240 0 1787916288 0.1037208736 0.1071288288 0.2431796640 615 24.5600000000 0.6728522778 0.2260458556 0.6728522778 0.0685218165 0.1091850000 672664494 0 1786585088 0.1033619791 0.1079781801 0.2434874177 616 24.6000000000 0.6740275025 0.2267730985 0.6740275025 0.0684662810 0.1029750000 672665748 0 1786806272 0.1032459587 0.1086442024 0.2438567877 617 24.6400000000 0.6749061942 0.2274994082 0.6749061942 0.0684107994 0.1123160000 672667002 0 1787314176 0.1027007401 0.1095763221 0.2444843501 618 24.6800000000 0.6762420535 0.2282255290 0.6762420535 0.0683560854 0.1061920000 672668256 0 1787789312 0.1025816202 0.1101852730 0.2447642237 619 24.7200000000 0.6776890755 0.2289516414 0.6776890755 0.0683014341 0.1036040000 672669510 0 1787916288 0.1022045836 0.1112030819 0.2451554090 620 24.7600000000 0.6786269546 0.2296769241 0.6786269546 0.0682473833 0.1007560000 672670764 0 1786437632 0.1016710475 0.1117707267 0.2455677241 621 24.8000000000 0.6798665524 0.2304018672 0.6798665524 0.0681933667 0.1028220000 672672018 0 1786806272 0.1008492038 0.1123605072 0.2462722361 622 24.8400000000 0.6812744737 0.2311267427 0.6812744737 0.0681398638 0.1044330000 672673272 0 1787441152 0.1003394350 0.1131861806 0.2469837666 623 24.8800000000 0.6830186248 0.2318520909 0.6830186248 0.0680871942 0.1046000000 672674526 0 1787949056 0.0997128263 0.1145431325 0.2476702183 624 24.9200000000 0.6841455698 0.2325769202 0.6841455698 0.0680347903 0.0972020000 672675780 0 1787949056 0.0994899794 0.1148650721 0.2481479645 625 24.9600000000 0.6856823564 0.2333018889 0.6856823564 0.0679817170 0.0982520000 672677034 0 1786437632 0.0986950621 0.1158491448 0.2488597780 626 25.0000000000 0.6876365542 0.2340276631 0.6876365542 0.0679289886 0.1005030000 672678288 0 1786679296 0.0979416072 0.1170069873 0.2494632751 627 25.0400000000 0.6892048120 0.2347536235 0.6892048120 0.0678781750 0.0990880000 672679542 0 1787187200 0.0975174978 0.1182079390 0.2498247772 628 25.0800000000 0.6905173063 0.2354793618 0.6905173063 0.0678274542 0.0980560000 672680796 0 1787662336 0.0968038067 0.1191845015 0.2503509820 629 25.1200000000 0.6916868687 0.2362046520 0.6916868687 0.0677777615 0.1031910000 672682050 0 1787916288 0.0963044614 0.1199521646 0.2506548166 630 25.1600000000 0.6928231120 0.2369294432 0.6928231120 0.0677254984 0.1014260000 672683304 0 1786437632 0.0951083079 0.1205655709 0.2514783740 631 25.2000000000 0.6941915751 0.2376541058 0.6941915751 0.0676736154 0.0997780000 672684558 0 1786437632 0.0942691937 0.1212519333 0.2519164383 632 25.2400000000 0.6949894428 0.2383777377 0.6949894428 0.0676215855 0.1005940000 672685812 0 1786933248 0.0933174193 0.1214229763 0.2527957559 633 25.2800000000 0.6958255768 0.2391004041 0.6958255768 0.0675687737 0.1010680000 672687066 0 1787568128 0.0919713080 0.1221799850 0.2536541820 634 25.3200000000 0.6974288821 0.2398233197 0.6974288821 0.0675161118 0.0987320000 672688320 0 1787949056 0.0907560959 0.1232623681 0.2545281947 635 25.3600000000 0.6992735863 0.2405468634 0.6992735863 0.0674641040 0.1061240000 672689574 0 1787949056 0.0895541236 0.1238785163 0.2552408576 636 25.4000000000 0.7001734376 0.2412695467 0.7001734376 0.0674127156 0.1108750000 672690828 0 1786437632 0.0883134231 0.1244489774 0.2560867667 637 25.4400000000 0.7013386488 0.2419917902 0.7013386488 0.0673613255 0.1049790000 672692082 0 1786646528 0.0868866816 0.1249562278 0.2570795119 638 25.4800000000 0.7027126551 0.2427139232 0.7027126551 0.0673096746 0.1102980000 672693336 0 1787281408 0.0852370039 0.1254675537 0.2581616342 639 25.5200000000 0.7036731839 0.2434352992 0.7036731839 0.0672583744 0.1068370000 672694590 0 1787789312 0.0836443007 0.1257159561 0.2593565881 640 25.5600000000 0.7043523788 0.2441554821 0.7043523788 0.0672067875 0.1102540000 672695844 0 1787916288 0.0820118636 0.1257067472 0.2606575489 641 25.6000000000 0.7053927183 0.2448750410 0.7053927183 0.0671552527 0.1158000000 672697098 0 1786585088 0.0802711770 0.1258074194 0.2616773546 642 25.6400000000 0.7072829604 0.2455953026 0.7072829604 0.0671048148 0.1135760000 672698352 0 1786585088 0.0788870007 0.1266044676 0.2625483871 643 25.6800000000 0.7084138393 0.2463150825 0.7084138393 0.0670548341 0.1235510000 672699606 0 1787060224 0.0774264783 0.1272205263 0.2636932731 644 25.7200000000 0.7092872858 0.2470339835 0.7092872858 0.0670049734 0.1174750000 672700860 0 1787695104 0.0760203600 0.1272861212 0.2645789683 645 25.7600000000 0.7107548714 0.2477529306 0.7107548714 0.0669545273 0.1249090000 672702114 0 1787949056 0.0746839568 0.1278924495 0.2653784752 646 25.8000000000 0.7122306228 0.2484719363 0.7122306228 0.0669045083 0.1277800000 672703368 0 1786392576 0.0732697994 0.1285344362 0.2663038671 647 25.8400000000 0.7132859230 0.2491903505 0.7132859230 0.0668545175 0.1142600000 672704622 0 1786392576 0.0716012046 0.1287424117 0.2673378885 648 25.8800000000 0.7148235440 0.2499089203 0.7148235440 0.0668039132 0.1314420000 672705876 0 1786900480 0.0702007189 0.1294173747 0.2682443261 649 25.9200000000 0.7162536979 0.2506274792 0.7162536979 0.0667534772 0.1326170000 672707130 0 1787408384 0.0686771497 0.1301995218 0.2691925168 650 25.9600000000 0.7183000445 0.2513469755 0.7183000445 0.0667035443 0.1351180000 672708384 0 1787916288 0.0673590228 0.1314537674 0.2699375451 651 26.0000000000 0.7197040915 0.2520664181 0.7197040915 0.0666559929 0.1329340000 672709638 0 1787916288 0.0662971288 0.1322332025 0.2706663013 652 26.0400000000 0.7209721208 0.2527855986 0.7209721208 0.0666076623 0.1326880000 672710892 0 1786437632 0.0649553239 0.1330527961 0.2713390291 653 26.0800000000 0.7221802473 0.2535044265 0.7221802473 0.0665598022 0.1372430000 672712146 0 1786519552 0.0634887442 0.1336614490 0.2720586061 654 26.1200000000 0.7234515548 0.2542230001 0.7234515548 0.0665124917 0.1327890000 672713400 0 1787154432 0.0620205924 0.1340622157 0.2727771699 655 26.1600000000 0.7252018452 0.2549420518 0.7252018452 0.0664643826 0.1292870000 672714654 0 1787662336 0.0619434193 0.1357927620 0.2728155851 656 26.2000000000 0.7274662256 0.2556623630 0.7274662256 0.0664149235 0.1335730000 672715908 0 1787916288 0.0580614321 0.1364658624 0.2743848562 657 26.2400000000 0.7280957103 0.2563814397 0.7280957103 0.0663683140 0.1349450000 672717162 0 1788043264 0.0571879186 0.1367215961 0.2750352919 658 26.2800000000 0.7294253707 0.2571003514 0.7294253707 0.0663197748 0.7060050000 685029792 0 1786667008 0.0559637137 0.1372813582 0.2754267752 659 26.3200000000 0.7322580218 0.2578213797 0.7322580218 0.0662723469 0.1354770000 688688894 0 1785147392 0.0573216416 0.1394151896 0.2735405266 660 26.3600000000 0.7329502702 0.2585412720 0.7329502702 0.0662253663 0.1885650000 691885916 0 1786048512 0.0559405535 0.1399404258 0.2740423977 661 26.4000000000 0.7345061302 0.2592613399 0.7345061302 0.0661785046 0.1734830000 691887170 0 1786290176 0.0553470030 0.1411837935 0.2742437720 662 26.4400000000 0.7357031703 0.2599810405 0.7357031703 0.0661303456 0.1688950000 691888424 0 1786798080 0.0543066524 0.1422235072 0.2745550275 663 26.4800000000 0.7361202836 0.2606991993 0.7361202836 0.0660834419 0.1495510000 691889678 0 1787400192 0.0533807687 0.1420882344 0.2749476135 664 26.5200000000 0.7370972633 0.2614166662 0.7370972633 0.0660367978 0.1430960000 691890932 0 1787527168 0.0525138453 0.1425742358 0.2752247453 665 26.5600000000 0.7381210923 0.2621335150 0.7381210923 0.0659890330 0.1440230000 691892186 0 1787908096 0.0512609147 0.1435197443 0.2756616473 666 26.6000000000 0.7387702465 0.2628491858 0.7387702465 0.0659411844 0.1350620000 691893440 0 1786281984 0.0501959287 0.1439431906 0.2761058509 667 26.6400000000 0.7399010062 0.2635644059 0.7399010062 0.0658932776 0.1268390000 691894694 0 1786650624 0.0490230396 0.1444420367 0.2762273252 668 26.6800000000 0.7407922149 0.2642788188 0.7407922149 0.0658454903 0.1359570000 691895948 0 1787285504 0.0476489700 0.1452002525 0.2766474187 669 26.7200000000 0.7415095568 0.2649921681 0.7415095568 0.0657982451 0.1173290000 691897202 0 1787793408 0.0463324077 0.1459747851 0.2770377994 670 26.7600000000 0.7416953444 0.2657036654 0.7416953444 0.0657507136 0.1201470000 691898456 0 1787908096 0.0449654721 0.1455260813 0.2772859633 671 26.8000000000 0.7418180704 0.2664132249 0.7418180704 0.0657038648 0.1309540000 691899710 0 1786171392 0.0438202173 0.1454644799 0.2779019773 672 26.8400000000 0.7426566482 0.2671219205 0.7426566482 0.0656560905 0.1215550000 691900964 0 1786523648 0.0425216258 0.1452199519 0.2781370282 673 26.8800000000 0.7429646254 0.2678289676 0.7429646254 0.0656079911 0.1180000000 691902218 0 1787031552 0.0411754996 0.1453025788 0.2787036896 674 26.9200000000 0.7433168888 0.2685344393 0.7433168888 0.0655619671 0.1212660000 691903472 0 1787666432 0.0398087166 0.1450834274 0.2792302966 675 26.9600000000 0.7437226772 0.2692384218 0.7437226772 0.0655157480 0.1217420000 691904726 0 1787793408 0.0384926721 0.1450302899 0.2794986665 676 27.0000000000 0.7439590096 0.2699406712 0.7439590096 0.0654682139 0.1180360000 691905980 0 1786171392 0.0370957293 0.1451855451 0.2797876000 677 27.0400000000 0.7439522743 0.2706408361 0.7439590096 0.0654213957 0.1252970000 691907234 0 1786171392 0.0355917662 0.1453754008 0.2801517248 678 27.0800000000 0.7440970540 0.2713391491 0.7440970540 0.0653744723 0.1242080000 691908488 0 1786638336 0.0340812206 0.1452994794 0.2804453373 679 27.1200000000 0.7439877987 0.2720352443 0.7440970540 0.0653271192 0.1249570000 691909742 0 1787146240 0.0322491080 0.1448846608 0.2808080912 680 27.1600000000 0.7441936135 0.2727295948 0.7441936135 0.0652809511 0.1336200000 691910996 0 1787654144 0.0306631718 0.1447115988 0.2812957764 681 27.2000000000 0.7443271279 0.2734221022 0.7443271279 0.0652355678 0.1302770000 691912250 0 1787781120 0.0297594350 0.1446407586 0.2815826237 682 27.2400000000 0.7443250418 0.2741125758 0.7443271279 0.0651900722 0.1306820000 691913504 0 1786023936 0.0286132768 0.1444663852 0.2818340659 683 27.2800000000 0.7442499399 0.2748009174 0.7443271279 0.0651449720 0.1319060000 691914758 0 1786142720 0.0277678017 0.1441572905 0.2821717262 684 27.3200000000 0.7449986935 0.2754883411 0.7449986935 0.0650976698 0.1346790000 691916012 0 1786650624 0.0259767473 0.1442561001 0.2823849916 685 27.3600000000 0.7457395792 0.2761748392 0.7457395792 0.0650519016 1.0586670000 704330110 0 1785651200 0.0250889119 0.1446062773 0.2826162279 686 27.4000000000 0.7389934659 0.2768495020 0.7457395792 0.0650076805 0.1990510000 707989212 0 1786413056 0.0242951624 0.1495880783 0.2877928615 687 27.4400000000 0.7401088476 0.2775238241 0.7457395792 0.0649625323 0.1458400000 711182562 0 1785544704 0.0232810527 0.1496435404 0.2880954146 688 27.4800000000 0.7406327724 0.2781969476 0.7457395792 0.0649178169 0.1336130000 711183816 0 1785769984 0.0224167127 0.1499561667 0.2885318696 689 27.5200000000 0.7410206795 0.2788686802 0.7457395792 0.0648722528 0.1250850000 711185070 0 1786404864 0.0213578139 0.1506324708 0.2887063324 690 27.5600000000 0.7417694330 0.2795395508 0.7457395792 0.0648262745 0.1260210000 711186324 0 1786912768 0.0198686495 0.1508050412 0.2892684639 691 27.6000000000 0.7423419952 0.2802093084 0.7457395792 0.0647810694 0.1228600000 711187578 0 1787166720 0.0187786724 0.1508068293 0.2895795405 692 27.6400000000 0.7427545786 0.2808777264 0.7457395792 0.0647355299 0.1177600000 711188832 0 1787400192 0.0173491761 0.1516441554 0.2902565897 693 27.6800000000 0.7431910634 0.2815448452 0.7457395792 0.0646902983 0.1365520000 711190086 0 1788035072 0.0160202440 0.1512098610 0.2905135453 694 27.7200000000 0.7439697385 0.2822111635 0.7457395792 0.0646447140 0.1181080000 711191340 0 1786023936 0.0153188212 0.1513506621 0.2908894718 695 27.7600000000 0.7448177338 0.2828767844 0.7457395792 0.0645996533 0.1240490000 711192594 0 1786396672 0.0142921070 0.1512520611 0.2911151648 696 27.8000000000 0.7447136641 0.2835403432 0.7457395792 0.0645549753 0.1123560000 711193848 0 1786904576 0.0130051756 0.1508563757 0.2916831076 697 27.8400000000 0.7453520298 0.2842029137 0.7457395792 0.0645106272 0.1114780000 711195102 0 1787412480 0.0117656067 0.1511367857 0.2920811772 698 27.8800000000 0.7461340427 0.2848647062 0.7461340427 0.0644666652 0.1327640000 711196356 0 1787793408 0.0108734304 0.1509975791 0.2923498154 699 27.9200000000 0.7467712760 0.2855255167 0.7467712760 0.0644220310 0.1196220000 711197610 0 1787908096 0.0096657043 0.1515093148 0.2927191556 700 27.9600000000 0.7472292781 0.2861850935 0.7472292781 0.0643781854 0.1213240000 711198864 0 1786023936 0.0084925657 0.1517310143 0.2931024134 701 28.0000000000 0.7479319572 0.2868437909 0.7479319572 0.0643340825 0.1241380000 711200118 0 1786384384 0.0074617821 0.1520714313 0.2934218347 702 28.0400000000 0.7491042614 0.2875022816 0.7491042614 0.0642892864 0.1196230000 711201372 0 1786892288 0.0058512706 0.1526837200 0.2935499251 703 28.0800000000 0.7499535680 0.2881601071 0.7499535680 0.0642452053 1.2313240000 723533754 0 1786892288 0.0049198121 0.1527819186 0.2939673960 704 28.1200000000 0.7514199018 0.2888181465 0.7514199018 0.0642014390 0.1087070000 727192856 0 1785376768 0.0041308361 0.1515203118 0.2940054536 705 28.1600000000 0.7522982359 0.2894755651 0.7522982359 0.0641574812 0.1801860000 730386206 0 1786044416 0.0030208535 0.1512706131 0.2944478691 706 28.2000000000 0.7524789572 0.2901313773 0.7524789572 0.0641140077 0.1417540000 730387460 0 1786269696 0.0025840753 0.1511552036 0.2948096395 707 28.2400000000 0.7529460192 0.2907859949 0.7529460192 0.0640701066 0.1373980000 730388714 0 1787019264 0.0010580856 0.1510145813 0.2952651381 708 28.2800000000 0.7533846498 0.2914393828 0.7533846498 0.0640261307 0.1287060000 730389968 0 1787527168 0.0003451298 0.1509258598 0.2956639528 709 28.3200000000 0.7545607686 0.2920925865 0.7545607686 0.0639815226 0.1353740000 730391222 0 1787781120 -0.0008856107 0.1512877941 0.2959247231 710 28.3600000000 0.7549725175 0.2927445300 0.7549725175 0.0639373131 0.1225540000 730392476 0 1785655296 -0.0022088042 0.1516137719 0.2963069081 711 28.4000000000 0.7555289865 0.2933954224 0.7555289865 0.0638936283 0.1273020000 730393730 0 1785655296 -0.0033705209 0.1515799761 0.2968119085 712 28.4400000000 0.7560456991 0.2940452121 0.7560456991 0.0638493340 0.1265220000 730394984 0 1786138624 -0.0050690812 0.1516018063 0.2971425056 713 28.4800000000 0.7568722367 0.2946943383 0.7568722367 0.0638052127 0.1218640000 730396238 0 1786646528 -0.0064223520 0.1519393325 0.2975051403 714 28.5200000000 0.7574017644 0.2953423880 0.7574017644 0.0637614062 0.1337690000 730397492 0 1787281408 -0.0076935953 0.1517794877 0.2980189919 715 28.5600000000 0.7583041787 0.2959898870 0.7583041787 0.0637172026 0.1071880000 730398746 0 1787527168 -0.0091477456 0.1519268751 0.2984681427 716 28.6000000000 0.7586067319 0.2966359999 0.7586067319 0.0636738138 0.1062850000 730400000 0 1787781120 -0.0106746061 0.1516607553 0.2988847792 717 28.6400000000 0.7592452168 0.2972812010 0.7592452168 0.0636299805 0.1298830000 730401254 0 1785802752 -0.0120550385 0.1518157423 0.2991783917 718 28.6800000000 0.7600844502 0.2979257738 0.7600844502 0.0635864154 1.3283200000 742727524 0 1786003456 -0.0137899024 0.1520439386 0.2994600832 719 28.7200000000 0.7625588775 0.2985719951 0.7625588775 0.0635446072 0.1521410000 746386626 0 1785798656 -0.0143045830 0.1496704072 0.2982474267 720 28.7600000000 0.7631948590 0.2992173046 0.7631948590 0.0635027457 0.1230430000 749579976 0 1786576896 -0.0155964233 0.1498631537 0.2985290289 721 28.8000000000 0.7634733319 0.2998612103 0.7634733319 0.0634604964 0.1066740000 749581230 0 1787146240 -0.0166908689 0.1496340185 0.2990463674 722 28.8400000000 0.7637534142 0.3005037203 0.7637534142 0.0634175930 0.1092900000 749582484 0 1787654144 -0.0187509730 0.1491912603 0.2994113863 723 28.8800000000 0.7644112706 0.3011453628 0.7644112706 0.0633745353 0.1028710000 749583738 0 1787908096 -0.0197968725 0.1494541019 0.2996956408 724 28.9200000000 0.7648174763 0.3017857939 0.7648174763 0.0633312103 0.1039320000 749584992 0 1786318848 -0.0218082238 0.1491121352 0.3000341654 725 28.9600000000 0.7653083801 0.3024251354 0.7653083801 0.0632882369 0.1000690000 749586246 0 1786413056 -0.0228352360 0.1490536928 0.3004324138 726 29.0000000000 0.7658708692 0.3030634904 0.7658708692 0.0632452275 0.0981010000 749587500 0 1786920960 -0.0241008922 0.1490717381 0.3007071018 727 29.0400000000 0.7664698362 0.3037009132 0.7664698362 0.0632027912 0.0994860000 749588754 0 1787428864 -0.0252686776 0.1490437835 0.3010267913 728 29.0800000000 0.7666209340 0.3043367923 0.7666209340 0.0631609229 0.1154490000 749590008 0 1787682816 -0.0260980129 0.1488334388 0.3012461960 729 29.1200000000 0.7671273351 0.3049716216 0.7671273351 0.0631195976 0.1060790000 749591262 0 1787908096 -0.0270971041 0.1487249583 0.3015244305 730 29.1600000000 0.7673125267 0.3056049653 0.7673125267 0.0630781878 0.0974040000 749592516 0 1786384384 -0.0278311167 0.1484585404 0.3018359840 731 29.2000000000 0.7673017979 0.3062365615 0.7673125267 0.0630362281 0.1151670000 749593770 0 1786638336 -0.0294876546 0.1480903029 0.3019829392 732 29.2400000000 0.7677791715 0.3068670842 0.7677791715 0.0629943692 1.3635790000 761918248 0 1785434112 -0.0306072719 0.1480897367 0.3021555841 733 29.2800000000 0.7689863443 0.3074975334 0.7689863443 0.0629529828 0.1357040000 765577350 0 1786576896 -0.0305867884 0.1465208828 0.3016434610 734 29.3200000000 0.7691915035 0.3081265443 0.7691915035 0.0629105252 0.1153730000 768770700 0 1785630720 -0.0313310772 0.1463453323 0.3017600179 735 29.3600000000 0.7693424821 0.3087540490 0.7693424821 0.0628680422 0.1054210000 768771954 0 1785630720 -0.0326081403 0.1462686807 0.3018599749 736 29.4000000000 0.7691133022 0.3093795371 0.7693424821 0.0628262700 0.0943690000 768773208 0 1786384384 -0.0335311368 0.1457606256 0.3018921912 737 29.4400000000 0.7686834335 0.3100027445 0.7693424821 0.0627844304 0.0993010000 768774462 0 1786892288 -0.0344647691 0.1451955438 0.3020457625 738 29.4800000000 0.7685165405 0.3106240369 0.7693424821 0.0627424948 0.1024040000 768775716 0 1787019264 -0.0348418616 0.1447369158 0.3022692502 739 29.5200000000 0.7680844665 0.3112430632 0.7693424821 0.0627009581 0.1046490000 768776970 0 1787400192 -0.0352998376 0.1440989822 0.3024380505 740 29.5600000000 0.7676686049 0.3118598545 0.7693424821 0.0626598243 0.0965360000 768778224 0 1787908096 -0.0357541144 0.1434964687 0.3025603592 741 29.6000000000 0.7675688267 0.3124748464 0.7693424821 0.0626189046 0.0987310000 768779478 0 1786429440 -0.0365056470 0.1430841088 0.3027688563 742 29.6400000000 0.7674900293 0.3130880744 0.7693424821 0.0625779769 0.1073530000 768780732 0 1786671104 -0.0370350890 0.1426889300 0.3029296100 743 29.6800000000 0.7670845389 0.3136991060 0.7693424821 0.0625372821 0.0995640000 768781986 0 1787179008 -0.0374979824 0.1422796994 0.3029723465 744 29.7200000000 0.7663594484 0.3143075204 0.7693424821 0.0624975328 0.0918220000 768783240 0 1787686912 -0.0385825969 0.1410599500 0.3033048809 745 29.7600000000 0.7659499645 0.3149137519 0.7693424821 0.0624560843 0.1170590000 768784494 0 1787940864 -0.0387025476 0.1403021365 0.3034938574 746 29.8000000000 0.7659847736 0.3155184047 0.7693424821 0.0624143583 0.1095430000 768785748 0 1786257408 -0.0392483436 0.1400953829 0.3036512733 747 29.8400000000 0.7657821774 0.3161211675 0.7693424821 0.0623727992 0.0938600000 768787002 0 1786384384 -0.0396746174 0.1396044791 0.3038594425 748 29.8800000000 0.7655682564 0.3167220326 0.7693424821 0.0623310890 1.3294530000 781114204 0 1786773504 -0.0398875177 0.1391455382 0.3039731383 749 29.9200000000 0.7659931779 0.3173218605 0.7693424821 0.0622894573 0.0939460000 784773306 0 1787908096 -0.0402334817 0.1379654706 0.3039823472 750 29.9600000000 0.7660959363 0.3179202260 0.7693424821 0.0622479610 0.1293500000 787966656 0 1785659392 -0.0407423303 0.1378490180 0.3041048944 751 30.0000000000 0.7654151917 0.3185160914 0.7693424821 0.0622065062 0.1041200000 787967910 0 1785905152 -0.0406597182 0.1366114616 0.3043792546 752 30.0400000000 0.7653172612 0.3191102419 0.7693424821 0.0621651692 0.0894840000 787969164 0 1786540032 -0.0407617614 0.1361111850 0.3046344817 753 30.0800000000 0.7654504180 0.3197029911 0.7693424821 0.0621241214 0.0848740000 787970418 0 1787019264 -0.0411284417 0.1357641667 0.3049268723 754 30.1200000000 0.7653457522 0.3202940293 0.7693424821 0.0620834143 0.0895860000 787971672 0 1787400192 -0.0408806168 0.1352077723 0.3052476645 755 30.1600000000 0.7655265927 0.3208837413 0.7693424821 0.0620427554 0.0865160000 787972926 0 1787654144 -0.0407171808 0.1347773522 0.3056983948 756 30.2000000000 0.7657868862 0.3214722375 0.7693424821 0.0620017922 0.0827580000 787974180 0 1786318848 -0.0409703217 0.1344343275 0.3058805764 757 30.2400000000 0.7657901049 0.3220591832 0.7693424821 0.0619613529 0.0826090000 787975434 0 1786318848 -0.0408531055 0.1338541657 0.3063262403 758 30.2800000000 0.7669451833 0.3226461040 0.7693424821 0.0619214171 0.0801970000 787976688 0 1786793984 -0.0408623703 0.1342590898 0.3066223264 759 30.3200000000 0.7671331763 0.3232317260 0.7693424821 0.0618823847 0.0962920000 787977942 0 1787301888 -0.0408380777 0.1339737773 0.3070427477 760 30.3600000000 0.7669752836 0.3238155991 0.7693424821 0.0618446414 0.0959380000 787979196 0 1787682816 -0.0405421294 0.1331394166 0.3074463904 761 30.4000000000 0.7677860260 0.3243990031 0.7693424821 0.0618054743 1.2750780000 800304582 0 1787535360 -0.0400332697 0.1331612021 0.3079101443 762 30.4400000000 0.7691038847 0.3249826053 0.7693424821 0.0617655953 0.0897250000 803963684 0 1786003456 -0.0397811718 0.1316831559 0.3082313538 763 30.4800000000 0.7690386176 0.3255645922 0.7693424821 0.0617256050 0.1382820000 807157034 0 1786159104 -0.0392946787 0.1308737248 0.3088409305 764 30.5200000000 0.7691456676 0.3261451957 0.7693424821 0.0616864858 0.0861280000 807158288 0 1786793984 -0.0383357182 0.1303682774 0.3093670905 765 30.5600000000 0.7696314454 0.3267249163 0.7696314454 0.0616474248 0.0823260000 807159542 0 1787428864 -0.0377613008 0.1299034953 0.3098861575 766 30.6000000000 0.7698622346 0.3273034245 0.7698622346 0.0616099315 0.0836350000 807160796 0 1787682816 -0.0369614661 0.1293710917 0.3104319274 767 30.6400000000 0.7697463036 0.3278802731 0.7698622346 0.0615747619 0.0832240000 807162050 0 1787908096 -0.0359479748 0.1283991337 0.3109818101 768 30.6800000000 0.7703602910 0.3284564190 0.7703602910 0.0615396044 0.0835240000 807163304 0 1786318848 -0.0348743796 0.1281725615 0.3115079701 769 30.7200000000 0.7714744210 0.3290325152 0.7714744210 0.0615249476 1.1806030000 819489398 0 1787527168 -0.0327643417 0.1274704039 0.3126024604 770 30.7600000000 0.7707873583 0.3296062228 0.7714744210 0.0615001149 0.1165590000 823148500 0 1785421824 -0.0312611945 0.1254436672 0.3131604791 771 30.8000000000 0.7707179189 0.3301783521 0.7714744210 0.0614697504 0.0855990000 826341850 0 1785495552 -0.0300481990 0.1246464029 0.3135176301 772 30.8400000000 0.7708036304 0.3307491102 0.7714744210 0.0614389377 0.0728880000 826343104 0 1785749504 -0.0293151028 0.1242890358 0.3138027191 773 30.8800000000 0.7705850005 0.3313181088 0.7714744210 0.0614112282 0.0718140000 826344358 0 1784778752 -0.0280687045 0.1232342869 0.3142959177 774 30.9200000000 0.7698906064 0.3318847399 0.7714744210 0.0613822981 0.0706860000 826345612 0 1784778752 -0.0268957019 0.1220128387 0.3146720231 775 30.9600000000 0.7696896195 0.3324496495 0.7714744210 0.0613525751 0.0690640000 826346866 0 1785266176 -0.0258585811 0.1213960201 0.3149987459 776 31.0000000000 0.7695884109 0.3330129726 0.7714744210 0.0613250896 1.0656100000 838672336 0 1786171392 -0.0245311093 0.1205493286 0.3155338466 777 31.0400000000 0.7697965503 0.3335751136 0.7714744210 0.0612944750 0.0968080000 842331438 0 1786544128 -0.0231564082 0.1196217164 0.3161347508 778 31.0800000000 0.7695707679 0.3341355194 0.7714744210 0.0612623445 0.0732050000 845524788 0 1787162624 -0.0221244935 0.1184366047 0.3165689707 779 31.1200000000 0.7696188092 0.3346945480 0.7714744210 0.0612280154 0.0663420000 845526042 0 1785257984 -0.0209988058 0.1173538938 0.3172540367 780 31.1600000000 0.7697393894 0.3352522978 0.7714744210 0.0611926606 0.0670790000 845527296 0 1785376768 -0.0200545210 0.1164590120 0.3178858161 781 31.2000000000 0.7695471048 0.3358083731 0.7714744210 0.0611567466 0.0679450000 845528550 0 1785884672 -0.0193837974 0.1152755991 0.3184249699 782 31.2400000000 0.7695749402 0.3363630618 0.7714744210 0.0611220764 0.0595940000 845529804 0 1786392576 -0.0184212383 0.1139976233 0.3191880882 783 31.2800000000 0.7694579363 0.3369161842 0.7714744210 0.0610864070 0.8802160000 857851070 0 1787162624 -0.0175882708 0.1127322242 0.3198723495 784 31.3200000000 0.7694944739 0.3374679422 0.7714744210 0.0610511880 0.0842560000 861510172 0 1787789312 -0.0164946970 0.1104222164 0.3203923106 785 31.3600000000 0.7692922354 0.3380180369 0.7714744210 0.0610146868 0.0653000000 864703522 0 1786179584 -0.0158607941 0.1088869944 0.3208875656 786 31.4000000000 0.7691136003 0.3385665045 0.7714744210 0.0609773393 0.0602600000 864704776 0 1786527744 -0.0154316360 0.1077308208 0.3213438094 787 31.4400000000 0.7679494619 0.3391120991 0.7714744210 0.0609404209 0.0646030000 864706030 0 1785503744 -0.0148135321 0.1057368889 0.3220121562 788 31.4800000000 0.7677750587 0.3396560877 0.7714744210 0.0609050402 0.0630220000 864707284 0 1785503744 -0.0141397892 0.1041491628 0.3225910962 789 31.5200000000 0.7673171163 0.3401981168 0.7714744210 0.0608702040 0.0578730000 864708538 0 1786011648 -0.0137610156 0.1027733386 0.3232018650 790 31.5600000000 0.7664065957 0.3407376213 0.7714744210 0.0608363027 0.9073090000 877034464 0 1786900480 -0.0132597424 0.1005433872 0.3238393366 791 31.6000000000 0.7660272121 0.3412752819 0.7714744210 0.0608127225 0.0721330000 880693566 0 1787789312 -0.0128605422 0.0970786065 0.3246465623 792 31.6400000000 0.7658824325 0.3418114021 0.7714744210 0.0607776549 0.0621350000 883886916 0 1786327040 -0.0123686092 0.0958003849 0.3255184889 793 31.6800000000 0.7651785612 0.3423452825 0.7714744210 0.0607423283 0.0561630000 883888170 0 1786548224 -0.0122286193 0.0937361866 0.3262082338 794 31.7200000000 0.7658420205 0.3428786537 0.7714744210 0.0607056155 0.0539350000 883889424 0 1785524224 -0.0120787211 0.0932547897 0.3267019391 795 31.7600000000 0.7663994431 0.3434113842 0.7714744210 0.0606698499 0.0541190000 883890678 0 1785524224 -0.0122123202 0.0928128064 0.3272333145 796 31.8000000000 0.7662672997 0.3439426103 0.7714744210 0.0606372766 0.0539720000 883891932 0 1785163776 -0.0120422775 0.0911231339 0.3280687630 797 31.8400000000 0.7662729621 0.3444725103 0.7714744210 0.0606063292 0.0559210000 883893186 0 1785163776 -0.0120792491 0.0892846212 0.3289884031 798 31.8800000000 0.7653045654 0.3449998688 0.7714744210 0.0606105964 0.6643410000 896398024 0 1786179584 -0.0116088483 0.0835371837 0.3313009739 799 31.9200000000 0.7647552490 0.3455252197 0.7714744210 0.0605803341 0.0679210000 900057126 0 1786929152 -0.0114156511 0.0807555020 0.3324358165 800 31.9600000000 0.7651516199 0.3460497527 0.7714744210 0.0605460775 0.0573170000 903250476 0 1787662336 -0.0116972513 0.0793401822 0.3331903517 801 32.0000000000 0.7660745382 0.3465741282 0.7714744210 0.0605094597 0.0542100000 903251730 0 1785798656 -0.0116754463 0.0781535357 0.3341826797 802 32.0400000000 0.7657586336 0.3470968022 0.7714744210 0.0604718767 0.0541150000 903252984 0 1785798656 -0.0120382197 0.0755473748 0.3351326883 803 32.0800000000 0.7654854059 0.3476178340 0.7714744210 0.0604347341 0.0513890000 903254238 0 1785057280 -0.0123288948 0.0725742504 0.3362810016 804 32.1199999990 0.7663878202 0.3481386922 0.7714744210 0.0603989382 0.0509760000 903255492 0 1785057280 -0.0128305741 0.0678927898 0.3386075795 805 32.1600000000 0.7674389482 0.3486595621 0.7714744210 0.0603615883 0.7403230000 915576726 0 1786798080 -0.0131538818 0.0665481538 0.3396978378 806 32.2000000000 0.7690082788 0.3491810866 0.7714744210 0.0603244666 0.0594000000 919235828 0 1787781120 -0.0131767234 0.0644619241 0.3404328525 807 32.2400000000 0.7691568136 0.3497015026 0.7714744210 0.0602873329 0.0566950000 922429178 0 1787908096 -0.0135856681 0.0621039011 0.3419156373 808 32.2800000000 0.7704365849 0.3502222143 0.7714744210 0.0602500422 0.0483990000 922430432 0 1786429440 -0.0141041558 0.0601629317 0.3429557085 809 32.3200000000 0.7706974745 0.3507419613 0.7714744210 0.0602146941 0.0503960000 922431686 0 1785651200 -0.0144605013 0.0556866974 0.3446584344 810 32.3600000000 0.7708064914 0.3512605594 0.7714744210 0.0601781181 0.0479100000 922432940 0 1785651200 -0.0148195662 0.0521317199 0.3464318812 811 32.4000000000 0.7728514671 0.3517804003 0.7728514671 0.0601412768 0.0476240000 922434194 0 1785282560 -0.0154932765 0.0511764027 0.3474924564 812 32.4399999990 0.7744996548 0.3523009905 0.7744996548 0.0601042476 0.7114740000 934756872 0 1787654144 -0.0157570429 0.0491943248 0.3489468992 813 32.4800000000 0.7759914994 0.3528221350 0.7759914994 0.0600682609 0.0568850000 938415974 0 1787908096 -0.0158354528 0.0460180044 0.3505834937 814 32.5200000000 0.7772819400 0.3533435844 0.7772819400 0.0600329830 0.0478420000 941609324 0 1788035072 -0.0160708465 0.0425071716 0.3523511589 815 32.5600000000 0.7786517143 0.3538654349 0.7786517143 0.0599981500 0.0469180000 941610578 0 1785913344 -0.0165843330 0.0395629965 0.3541377187 816 32.6000000000 0.7808208466 0.3543886645 0.7808208466 0.0599625359 0.0479670000 941611832 0 1785409536 -0.0169911571 0.0373038650 0.3559390604 817 32.6400000000 0.7834942341 0.3549138856 0.7834942341 0.0599273489 0.0476840000 941613086 0 1785409536 -0.0172531977 0.0331427567 0.3580716550 818 32.6800000000 0.7854077816 0.3554401617 0.7854077816 0.0598928158 0.0476530000 941614340 0 1784639488 -0.0175717343 0.0282561556 0.3603519797 819 32.7200000000 0.7871268392 0.3559672517 0.7871268392 0.0598570957 0.0472020000 941615594 0 1784639488 -0.0181186702 0.0249069948 0.3622342944 820 32.7599999990 0.7889625430 0.3564952947 0.7889625430 0.0598207714 0.0463770000 941616848 0 1784287232 -0.0188402832 0.0229149051 0.3638388216 821 32.7999999990 0.7909878492 0.3570245183 0.7909878492 0.0597851654 0.0479420000 941618102 0 1784287232 -0.0192970634 0.0204121359 0.3654369712 822 32.8400000000 0.7928070426 0.3575546673 0.7928070426 0.0597513969 0.0506890000 941619356 0 1783513088 -0.0194479153 0.0164765976 0.3676788509 823 32.8800000000 0.7952680588 0.3580865184 0.7952680588 0.0597178942 0.0488580000 941620610 0 1783513088 -0.0193904322 0.0126837781 0.3694207072 824 32.9200000000 0.7977151275 0.3586200482 0.7977151275 0.0596830679 0.0493450000 941621864 0 1782849536 -0.0194325261 0.0092449943 0.3713482916 825 32.9600000000 0.7998169661 0.3591548324 0.7998169661 0.0596470506 0.5449490000 953933162 0 1786429440 -0.0196699761 0.0063732457 0.3729215860 826 33.0000000000 0.8019478321 0.3596909014 0.8019478321 0.0596109955 0.0519640000 957592264 0 1787047936 -0.0204455964 0.0038330362 0.3747162223 827 33.0400000000 0.8039568067 0.3602281032 0.8039568067 0.0595750757 0.0486110000 960785614 0 1787019264 -0.0204543024 0.0004766849 0.3763450086 828 33.0800000000 0.8056098819 0.3607660039 0.8056098819 0.0595391245 0.0457820000 960786868 0 1787400192 -0.0205870550 -0.0018683905 0.3776604831 829 33.1199999990 0.8073520064 0.3613047084 0.8073520064 0.0595035569 0.0446410000 960788122 0 1785425920 -0.0206008535 -0.0053685373 0.3792718649 830 33.1600000000 0.8095697761 0.3618447868 0.8095697761 0.0594681841 0.0445620000 960789376 0 1785520128 -0.0204938315 -0.0094705233 0.3811160922 831 33.2000000000 0.8114612699 0.3623858415 0.8114612699 0.0594326150 0.0444390000 960790630 0 1784885248 -0.0204844382 -0.0128865261 0.3827165067 832 33.2400000000 0.8136939406 0.3629282791 0.8136939406 0.0593975651 0.5560900000 978136488 0 1787908096 -0.0204844382 -0.0128865261 0.3827165067 833 33.2800000000 0.8183187842 0.3634749664 0.8183187842 0.0593645132 0.1791360000 981483482 0 1786306560 -0.0187006425 -0.0126505066 0.3810035586 834 33.3200000000 0.8206680417 0.3640231595 0.8206680417 0.0593296726 0.1616450000 981561568 0 1786654720 -0.0187006425 -0.0126505066 0.3810035586 835 33.3600000000 0.8226749301 0.3645724431 0.8226749301 0.0592945431 0.1568970000 981639654 0 1787416576 -0.0187006425 -0.0126505066 0.3810035586 836 33.4000000000 0.8253511786 0.3651236138 0.8253511786 0.0592594511 0.1353510000 981717740 0 1787654144 -0.0187006425 -0.0126505066 0.3810035586 837 33.4399999990 0.8283956051 0.3656771049 0.8283956051 0.0592246905 0.1359670000 981795826 0 1786306560 -0.0187006425 -0.0126505066 0.3810035586 838 33.4800000000 0.8746854067 0.3662845133 0.8746854067 0.0594043834 0.0819210000 981873912 0 1786400768 0.0550930277 0.0341660418 0.3454303741 839 33.5200000000 0.8736540079 0.3668892445 0.8746854067 0.0593713134 0.0565890000 971001922 0 1787035648 0.0541637018 0.0376409292 0.3489111662 840 33.5600000000 0.8738890290 0.3674928157 0.8746854067 0.0593372193 0.0571820000 971003176 0 1787670528 0.0554219633 0.0376469716 0.3505481780 841 33.6000000000 0.8771010041 0.3680987708 0.8771010041 0.0593054354 0.0567110000 971004430 0 1787908096 0.0566260889 0.0371339247 0.3516091108 842 33.6400000000 0.8802306056 0.3687070033 0.8802306056 0.0592708229 0.0562220000 971005684 0 1786171392 0.0547447838 0.0383176915 0.3532836437 843 33.6800000000 0.8773252964 0.3693103465 0.8802306056 0.0592369327 0.0564640000 971006938 0 1785892864 0.0517111085 0.0375413597 0.3566796780 844 33.7200000000 0.8790616393 0.3699143172 0.8802306056 0.0592020355 0.1082890000 977152396 0 1787781120 0.0514747687 0.0385796130 0.3565652966 845 33.7599999990 0.8819906712 0.3705203248 0.8819906712 0.0591675083 0.1093100000 990148738 0 1785020416 0.0514747687 0.0385796130 0.3565652966 846 33.7999999990 0.8830545545 0.3711261572 0.8830545545 0.0591332934 0.1068340000 991882896 0 1784401920 0.0514747687 0.0385796130 0.3565652966 847 33.8400000000 0.8837656379 0.3717313986 0.8837656379 0.0590985825 0.0955850000 991884170 0 1783635968 0.0514747687 0.0385796130 0.3565652966 848 33.8800000000 0.8882088065 0.3723404521 0.8882088065 0.0590648257 0.0834310000 991885444 0 1783590912 0.0514747687 0.0385796130 0.3565652966 849 33.9200000000 0.8901427984 0.3729503489 0.8901427984 0.0590304648 0.0792580000 991886718 0 1784098816 0.0514747687 0.0385796130 0.3565652966 850 33.9600000000 0.8898826838 0.3735585046 0.8901427984 0.0589959369 0.0772730000 991887992 0 1784606720 0.0514747687 0.0385796130 0.3565652966 851 34.0000000000 0.8916268945 0.3741672806 0.8916268945 0.0589615634 0.0808780000 991889266 0 1784987648 0.0514747687 0.0385796130 0.3565652966 852 34.0400000000 0.8920584917 0.3747751341 0.8920584917 0.0589271058 0.0793600000 991890540 0 1785241600 0.0514747687 0.0385796130 0.3565652966 853 34.0800000000 0.8924069405 0.3753819710 0.8924069405 0.0588927531 0.0814190000 991891814 0 1785749504 0.0514747687 0.0385796130 0.3565652966 854 34.1199999990 0.8941627145 0.3759894426 0.8941627145 0.0588586344 0.0819100000 991893088 0 1786257408 0.0514747687 0.0385796130 0.3565652966 855 34.1600000000 0.8954944611 0.3765970508 0.8954944611 0.0588248736 0.0736710000 991894362 0 1786892288 0.0514747687 0.0385796130 0.3565652966 856 34.2000000000 0.8946163058 0.3772022134 0.8954944611 0.0587915045 0.0645140000 991895636 0 1787400192 0.0514747687 0.0385796130 0.3565652966 857 34.2400000000 0.8938757777 0.3778050998 0.8954944611 0.0587574496 0.0643450000 991896910 0 1787908096 0.0514747687 0.0385796130 0.3565652966 858 34.2800000000 0.8937107921 0.3784063884 0.8954944611 0.0587233961 0.0697800000 991898184 0 1786306560 0.0514747687 0.0385796130 0.3565652966 859 34.3200000000 0.8923517466 0.3790046950 0.8954944611 0.0586898543 0.0713800000 991899458 0 1785798656 0.0514747687 0.0385796130 0.3565652966 860 34.3600000000 0.8914898038 0.3796006079 0.8954944611 0.0586564708 0.0590180000 991900732 0 1785749504 0.0514747687 0.0385796130 0.3565652966 861 34.4000000000 0.8908589482 0.3801944039 0.8954944611 0.0586233114 0.0600990000 991902006 0 1786257408 0.0514747687 0.0385796130 0.3565652966 862 34.4400000000 0.8907955885 0.3807867487 0.8954944611 0.0585912237 0.0579350000 991903280 0 1786765312 0.0514747687 0.0385796130 0.3565652966 863 34.4800000000 0.8911241293 0.3813781014 0.8954944611 0.0585580172 0.0484140000 991904554 0 1787146240 0.0514747687 0.0385796130 0.3565652966 864 34.5200000000 0.8887092471 0.3819652902 0.8954944611 0.0585250605 0.0496380000 992213040 0 1787400192 0.0514747687 0.0385796130 0.3565652966 865 34.5600000000 0.8874700665 0.3825496888 0.8954944611 0.0584923205 0.0506050000 992214314 0 1786306560 0.0514747687 0.0385796130 0.3565652966 866 34.6000000000 0.8877675533 0.3831330813 0.8954944611 0.0584594439 0.0482250000 992215588 0 1786306560 0.0514747687 0.0385796130 0.3565652966 867 34.6400000000 0.8871107101 0.3837143703 0.8954944611 0.0584258850 0.0585270000 992216862 0 1786781696 0.0514747687 0.0385796130 0.3565652966 868 34.6800000000 0.8856721520 0.3842926627 0.8954944611 0.0583924471 0.0582700000 992218136 0 1787289600 0.0514747687 0.0385796130 0.3565652966 869 34.7200000000 0.8854615092 0.3848693817 0.8954944611 0.0583590672 0.0531250000 992219410 0 1787670528 0.0514747687 0.0385796130 0.3565652966 870 34.7600000000 0.8853240609 0.3854446170 0.8954944611 0.0583255346 0.0525730000 992220684 0 1787908096 0.0514747687 0.0385796130 0.3565652966 871 34.8000000000 0.8853065372 0.3860185113 0.8954944611 0.0582920924 0.0529980000 992221958 0 1785925632 0.0514747687 0.0385796130 0.3565652966 872 34.8400000000 0.8862093687 0.3865921247 0.8954944611 0.0582589375 0.0529080000 992223232 0 1785815040 0.0514747687 0.0385796130 0.3565652966 873 34.8800000000 0.8863135576 0.3871645433 0.8954944611 0.0582262283 0.0535840000 992224506 0 1785815040 0.0514747687 0.0385796130 0.3565652966 874 34.9200000000 0.8856231570 0.3877348620 0.8954944611 0.0581931439 0.0459230000 992225780 0 1785016320 0.0514747687 0.0385796130 0.3565652966 875 34.9600000000 0.8858412504 0.3883041265 0.8954944611 0.0581599896 0.0490670000 992227054 0 1785016320 0.0514747687 0.0385796130 0.3565652966 876 35.0000000000 0.8863409758 0.3888726617 0.8954944611 0.0581270897 0.0454470000 992228328 0 1784287232 0.0514747687 0.0385796130 0.3565652966 877 35.0400000000 0.8857442141 0.3894392199 0.8954944611 0.0580939977 0.0452220000 992229602 0 1784287232 0.0514747687 0.0385796130 0.3565652966 878 35.0800000000 0.8858390450 0.3900045956 0.8954944611 0.0580609693 0.0565800000 992230876 0 1783504896 0.0514747687 0.0385796130 0.3565652966 879 35.1200000000 0.8861060143 0.3905689885 0.8954944611 0.0580281810 0.0542290000 992232150 0 1783504896 0.0514747687 0.0385796130 0.3565652966 880 35.1600000000 0.8850311637 0.3911308774 0.8954944611 0.0579963526 0.0488250000 992233424 0 1783988224 0.0514747687 0.0385796130 0.3565652966 881 35.2000000000 0.8837824464 0.3916900732 0.8954944611 0.0579634726 0.0481390000 992234698 0 1784623104 0.0514747687 0.0385796130 0.3565652966 882 35.2400000000 0.8833727837 0.3922475366 0.8954944611 0.0579308592 0.0467850000 992235972 0 1785131008 0.0514747687 0.0385796130 0.3565652966 883 35.2800000000 0.8827975392 0.3928030859 0.8954944611 0.0578983963 0.0439800000 992237246 0 1785241600 0.0514747687 0.0385796130 0.3565652966 884 35.3200000000 0.8815945983 0.3933560175 0.8954944611 0.0578661888 0.0444730000 992238520 0 1785749504 0.0514747687 0.0385796130 0.3565652966 885 35.3600000000 0.8807837367 0.3939067833 0.8954944611 0.0578343383 0.0481630000 992239794 0 1786257408 0.0514747687 0.0385796130 0.3565652966 886 35.4000000000 0.8798343539 0.3944552342 0.8954944611 0.0578026786 0.0436710000 992241068 0 1786765312 0.0514747687 0.0385796130 0.3565652966 887 35.4400000000 0.8785858154 0.3950010410 0.8954944611 0.0577712880 0.0400470000 992242342 0 1787273216 0.0514747687 0.0385796130 0.3565652966 888 35.4800000000 0.8776739836 0.3955445916 0.8954944611 0.0577395713 0.0404760000 992243616 0 1787908096 0.0514747687 0.0385796130 0.3565652966 889 35.5200000000 0.8766877055 0.3960858099 0.8954944611 0.0577086206 0.0442730000 992244890 0 1785925632 0.0514747687 0.0385796130 0.3565652966 890 35.5600000000 0.8753024340 0.3966242556 0.8954944611 0.0576773163 0.0485450000 992246164 0 1786146816 0.0514747687 0.0385796130 0.3565652966 891 35.6000000000 0.8751732111 0.3971613476 0.8954944611 0.0576460471 0.0484740000 992247438 0 1785417728 0.0514747687 0.0385796130 0.3565652966 892 35.6400000000 0.8738825321 0.3976957884 0.8954944611 0.0576156580 0.0473370000 992248712 0 1785044992 0.0514747687 0.0385796130 0.3565652966 893 35.6800000000 0.8725394011 0.3982275281 0.8954944611 0.0575849154 0.0489250000 992249986 0 1785032704 0.0514747687 0.0385796130 0.3565652966 894 35.7200000000 0.8723204732 0.3987578334 0.8954944611 0.0575544030 0.0597850000 992251260 0 1784279040 0.0514747687 0.0385796130 0.3565652966 895 35.7600000000 0.8721452355 0.3992867579 0.8954944611 0.0575249687 0.0515600000 992252534 0 1784279040 0.0514747687 0.0385796130 0.3565652966 896 35.8000000000 0.8708751202 0.3998130842 0.8954944611 0.0574967664 0.0485320000 992253808 0 1783627776 0.0514747687 0.0385796130 0.3565652966 897 35.8400000000 0.8701900840 0.4003374733 0.8954944611 0.0574675745 0.0478980000 992255082 0 1783599104 0.0514747687 0.0385796130 0.3565652966 898 35.8800000000 0.8694260120 0.4008598436 0.8954944611 0.0574371944 0.0491450000 992256356 0 1783263232 0.0514747687 0.0385796130 0.3565652966 899 35.9200000000 0.8696658611 0.4013813186 0.8954944611 0.0574074776 0.0621420000 992257630 0 1783263232 0.0514747687 0.0385796130 0.3565652966 900 35.9600000000 0.8692391515 0.4019011606 0.8954944611 0.0573774529 0.0565340000 992258904 0 1783742464 0.0514747687 0.0385796130 0.3565652966 901 36.0000000000 0.8686937094 0.4024192434 0.8954944611 0.0573476126 0.0577140000 992260178 0 1784377344 0.0514747687 0.0385796130 0.3565652966 902 36.0400000000 0.8683121204 0.4029357543 0.8954944611 0.0573182533 0.0524640000 992261452 0 1784631296 0.0514747687 0.0385796130 0.3565652966 903 36.0800000000 0.8672028780 0.4034498929 0.8954944611 0.0572884288 0.0611660000 992262726 0 1784868864 0.0514747687 0.0385796130 0.3565652966 904 36.1200000000 0.8671969771 0.4039628874 0.8954944611 0.0572592985 0.0657480000 992264000 0 1785376768 0.0514747687 0.0385796130 0.3565652966 905 36.1600000000 0.8664107323 0.4044738795 0.8954944611 0.0572303827 0.0773420000 992265274 0 1785884672 0.0514747687 0.0385796130 0.3565652966 906 36.2000000000 0.8658161759 0.4049830874 0.8954944611 0.0572014309 0.0647960000 992266548 0 1786519552 0.0514747687 0.0385796130 0.3565652966 907 36.2400000000 0.8660011292 0.4054913763 0.8954944611 0.0571723579 0.0708550000 992267822 0 1787027456 0.0514747687 0.0385796130 0.3565652966 908 36.2800000000 0.8654792309 0.4059979708 0.8954944611 0.0571430477 0.0794430000 992269096 0 1787535360 0.0514747687 0.0385796130 0.3565652966 909 36.3200000000 0.8651517630 0.4065030905 0.8954944611 0.0571130502 0.0700960000 992270370 0 1788043264 0.0514747687 0.0385796130 0.3565652966 910 36.3600000000 0.8650029302 0.4070069365 0.8954944611 0.0570829050 0.0795010000 992271644 0 1785933824 0.0514747687 0.0385796130 0.3565652966 911 36.4000000000 0.8652734756 0.4075099733 0.8954944611 0.0570529937 0.0712010000 992272918 0 1784758272 0.0514747687 0.0385796130 0.3565652966 912 36.4400000000 0.8657649755 0.4080124459 0.8954944611 0.0570234522 0.0745050000 992274192 0 1784758272 0.0514747687 0.0385796130 0.3565652966 913 36.4800000000 0.8650227785 0.4085130049 0.8954944611 0.0570021127 0.0863840000 992275466 0 1785266176 0.0514747687 0.0385796130 0.3565652966 914 36.5200000000 0.8652541637 0.4090127217 0.8954944611 0.0569732598 0.0733790000 992276740 0 1785774080 0.0514747687 0.0385796130 0.3565652966 915 36.5600000000 0.8654916883 0.4095116058 0.8954944611 0.0569440908 0.0919060000 992278014 0 1786281984 0.0514747687 0.0385796130 0.3565652966 916 36.6000000000 0.8654406667 0.4100093449 0.8954944611 0.0569149714 0.0839460000 992279288 0 1786662912 0.0514747687 0.0385796130 0.3565652966 917 36.6400000000 0.8655721545 0.4105061419 0.8954944611 0.0568857086 0.0872700000 992280562 0 1786900480 0.0514747687 0.0385796130 0.3565652966 918 36.6800000000 0.8658717871 0.4110021829 0.8954944611 0.0568567807 0.0925110000 992281836 0 1787408384 0.0514747687 0.0385796130 0.3565652966 919 36.7200000000 0.8662467003 0.4114975523 0.8954944611 0.0568282944 0.0934300000 992283110 0 1787916288 0.0514747687 0.0385796130 0.3565652966 920 36.7600000000 0.8660190701 0.4119915975 0.8954944611 0.0567996236 0.0846210000 992284384 0 1785933824 0.0514747687 0.0385796130 0.3565652966 921 36.8000000000 0.8666818738 0.4124852894 0.8954944611 0.0567704838 0.0828660000 992285658 0 1785315328 0.0514747687 0.0385796130 0.3565652966 922 36.8400000000 0.8676369786 0.4129789463 0.8954944611 0.0567418522 0.0828690000 992286932 0 1785249792 0.0514747687 0.0385796130 0.3565652966 923 36.8800000000 0.8687005639 0.4134726859 0.8954944611 0.0567137940 0.0854070000 992288206 0 1785757696 0.0514747687 0.0385796130 0.3565652966 924 36.9200000000 0.8693101406 0.4139660165 0.8954944611 0.0566858733 0.0842820000 992289480 0 1786265600 0.0514747687 0.0385796130 0.3565652966 925 36.9600000000 0.8697665334 0.4144587738 0.8954944611 0.0566579457 0.0853130000 992290754 0 1786646528 0.0514747687 0.0385796130 0.3565652966 926 37.0000000000 0.8700489402 0.4149507718 0.8954944611 0.0566293104 0.1086750000 992292028 0 1786900480 0.0514747687 0.0385796130 0.3565652966 927 37.0400000000 0.8709176779 0.4154426455 0.8954944611 0.0566009492 0.0995510000 992293302 0 1787408384 0.0514747687 0.0385796130 0.3565652966 928 37.0800000000 0.8711412549 0.4159337000 0.8954944611 0.0565732431 0.1100350000 992294576 0 1787916288 0.0514747687 0.0385796130 0.3565652966 929 37.1200000000 0.8706700206 0.4164231902 0.8954944611 0.0565448714 0.1324480000 992295850 0 1786314752 0.0514747687 0.0385796130 0.3565652966 930 37.1600000000 0.8703200817 0.4169112513 0.8954944611 0.0565160373 0.1459000000 992297124 0 1786535936 0.0514747687 0.0385796130 0.3565652966 931 37.2000000000 0.8705928922 0.4173985571 0.8954944611 0.0564873382 0.1415410000 992298398 0 1787027456 0.0514747687 0.0385796130 0.3565652966 932 37.2400000000 0.8703152537 0.4178845192 0.8954944611 0.0564597635 0.1396320000 992299672 0 1787535360 0.0514747687 0.0385796130 0.3565652966 933 37.2800000000 0.8692296743 0.4183682760 0.8954944611 0.0564328699 0.1469470000 992300946 0 1787662336 0.0514747687 0.0385796130 0.3565652966 934 37.3200000000 0.8685525060 0.4188502720 0.8954944611 0.0564058193 0.1357750000 992302220 0 1785929728 0.0514747687 0.0385796130 0.3565652966 935 37.3600000000 0.8673286438 0.4193299280 0.8954944611 0.0563777266 0.1505110000 992303494 0 1785929728 0.0514747687 0.0385796130 0.3565652966 936 37.4000000000 0.8669999838 0.4198082080 0.8954944611 0.0563497694 0.1522740000 992304768 0 1786408960 0.0514747687 0.0385796130 0.3565652966 937 37.4400000000 0.8662222028 0.4202846370 0.8954944611 0.0563215055 0.1546230000 992306042 0 1786916864 0.0514747687 0.0385796130 0.3565652966 938 37.4800000000 0.8660923839 0.4207599118 0.8954944611 0.0562925485 0.1683010000 992307316 0 1787535360 0.0514747687 0.0385796130 0.3565652966 939 37.5200000000 0.8658959270 0.4212339651 0.8954944611 0.0562638771 0.1815190000 992308590 0 1787535360 0.0514747687 0.0385796130 0.3565652966 940 37.5600000000 0.8657266498 0.4217068296 0.8954944611 0.0562351169 0.1902000000 992309864 0 1788035072 0.0514747687 0.0385796130 0.3565652966 941 37.6000000000 0.8646404743 0.4221775349 0.8954944611 0.0562062382 0.1661940000 992311138 0 1785925632 0.0514747687 0.0385796130 0.3565652966 942 37.6400000000 0.8636811376 0.4226462224 0.8954944611 0.0561771625 0.1621160000 992312412 0 1786273792 0.0514747687 0.0385796130 0.3565652966 943 37.6800000000 0.8633959293 0.4231136134 0.8954944611 0.0561481252 0.1812060000 992313686 0 1786765312 0.0514747687 0.0385796130 0.3565652966 944 37.7200000000 0.8636062741 0.4235802369 0.8954944611 0.0561194203 0.1910970000 992314960 0 1787273216 0.0514747687 0.0385796130 0.3565652966 945 37.7600000000 0.8650693893 0.4240474212 0.8954944611 0.0560911307 0.1790220000 992316234 0 1787400192 0.0514747687 0.0385796130 0.3565652966 946 37.8000000000 0.8650841713 0.4245136334 0.8954944611 0.0560627669 0.1848560000 992317508 0 1787908096 0.0514747687 0.0385796130 0.3565652966 947 37.8400000000 0.8649340272 0.4249787025 0.8954944611 0.0560341310 0.1761050000 992318782 0 1786306560 0.0514747687 0.0385796130 0.3565652966 948 37.8800000000 0.8668058515 0.4254447649 0.8954944611 0.0560055723 0.1882500000 992320056 0 1786527744 0.0514747687 0.0385796130 0.3565652966 949 37.9200000000 0.8735398650 0.4259169410 0.8954944611 0.0559804734 0.1710910000 992321330 0 1787019264 0.0514747687 0.0385796130 0.3565652966 950 37.9600000000 0.8815062046 0.4263965086 0.8954944611 0.0559533633 0.1765300000 992322604 0 1787527168 0.0514747687 0.0385796130 0.3565652966 951 38.0000000000 0.8843286633 0.4268780356 0.8954944611 0.0559257974 0.1699680000 992323878 0 1787654144 0.0514747687 0.0385796130 0.3565652966 952 38.0400000000 0.8845646381 0.4273587988 0.8954944611 0.0558977963 0.1732200000 992325152 0 1785925632 0.0514747687 0.0385796130 0.3565652966 953 38.0800000000 0.8849144578 0.4278389202 0.8954944611 0.0558693112 0.1637870000 992326426 0 1785925632 0.0514747687 0.0385796130 0.3565652966 954 38.1200000000 0.8862335086 0.4283194177 0.8954944611 0.0558416515 0.1177210000 992327700 0 1786400768 0.0514747687 0.0385796130 0.3565652966 955 38.1600000000 0.8848879337 0.4287974999 0.8954944611 0.0558140536 0.1196820000 992328974 0 1786892288 0.0514747687 0.0385796130 0.3565652966 956 38.2000000000 0.8853163123 0.4292750300 0.8954944611 0.0557867553 0.1448300000 992330248 0 1787273216 0.0514747687 0.0385796130 0.3565652966 957 38.2400000000 0.8843755722 0.4297505792 0.8954944611 0.0557587836 0.1529430000 992331522 0 1787527168 0.0514747687 0.0385796130 0.3565652966 958 38.2800000000 0.8818202019 0.4302224681 0.8954944611 0.0557303116 0.1373740000 992332796 0 1788035072 0.0514747687 0.0385796130 0.3565652966 959 38.3200000000 0.8815124035 0.4306930520 0.8954944611 0.0557024162 0.1274760000 992334070 0 1786306560 0.0514747687 0.0385796130 0.3565652966 960 38.3600000000 0.8826809525 0.4311638727 0.8954944611 0.0556753980 0.1463520000 992335344 0 1786654720 0.0514747687 0.0385796130 0.3565652966 961 38.4000000000 0.8814802170 0.4316324641 0.8954944611 0.0556474770 0.1449410000 992336618 0 1787146240 0.0514747687 0.0385796130 0.3565652966 962 38.4400000000 0.8810134530 0.4320995961 0.8954944611 0.0556198372 0.1501410000 992337892 0 1787654144 0.0514747687 0.0385796130 0.3565652966 963 38.4800000000 0.8789160848 0.4325635800 0.8954944611 0.0555919645 0.1258570000 992339166 0 1787781120 0.0514747687 0.0385796130 0.3565652966 964 38.5200000000 0.8798254728 0.4330275447 0.8954944611 0.0555645902 0.1460050000 992340440 0 1786052608 0.0514747687 0.0385796130 0.3565652966 965 38.5600000000 0.8784544468 0.4334891269 0.8954944611 0.0555366845 0.1399590000 992341714 0 1786273792 0.0514747687 0.0385796130 0.3565652966 966 38.6000000000 0.8779656887 0.4339492476 0.8954944611 0.0555087131 0.1176790000 992342988 0 1786781696 0.0514747687 0.0385796130 0.3565652966 967 38.6400000000 0.8799772859 0.4344104969 0.8954944611 0.0554811860 0.1181670000 992344262 0 1787289600 0.0514747687 0.0385796130 0.3565652966 968 38.6800000000 0.8783540726 0.4348691163 0.8954944611 0.0554536253 0.1267850000 992345536 0 1787416576 0.0514747687 0.0385796130 0.3565652966 969 38.7200000000 0.8788216114 0.4353272716 0.8954944611 0.0554270394 0.1320730000 992346810 0 1787908096 0.0514747687 0.0385796130 0.3565652966 970 38.7600000000 0.8776269555 0.4357832506 0.8954944611 0.0553999416 0.1284500000 992348084 0 1786433536 0.0514747687 0.0385796130 0.3565652966 971 38.8000000000 0.8760828376 0.4362367003 0.8954944611 0.0553724347 0.1431370000 992349358 0 1786654720 0.0514747687 0.0385796130 0.3565652966 972 38.8400000000 0.8757058382 0.4366888290 0.8954944611 0.0553459939 0.1460600000 992350632 0 1787289600 0.0514747687 0.0385796130 0.3565652966 973 38.8800000000 0.8747932911 0.4371390905 0.8954944611 0.0553190885 0.1379330000 992351906 0 1787797504 0.0514747687 0.0385796130 0.3565652966 974 38.9200000000 0.8749184012 0.4375885559 0.8954944611 0.0552925232 0.1434480000 992353180 0 1787797504 0.0514747687 0.0385796130 0.3565652966 975 38.9600000000 0.8743623495 0.4380365290 0.8954944611 0.0552657919 0.1342430000 992354454 0 1786052608 0.0514747687 0.0385796130 0.3565652966 976 39.0000000000 0.8732672930 0.4384824622 0.8954944611 0.0552384167 0.1358330000 992355728 0 1786130432 0.0514747687 0.0385796130 0.3565652966 977 39.0400000000 0.8727062345 0.4389269082 0.8954944611 0.0552121084 0.1328550000 992357002 0 1786638336 0.0514747687 0.0385796130 0.3565652966 978 39.0800000000 0.8710200787 0.4393687213 0.8954944611 0.0551846549 0.1375830000 992358276 0 1787146240 0.0514747687 0.0385796130 0.3565652966 979 39.1200000000 0.8688508272 0.4398074160 0.8954944611 0.0551572880 0.1410830000 992359550 0 1787400192 0.0514747687 0.0385796130 0.3565652966 980 39.1600000000 0.8672792315 0.4402436117 0.8954944611 0.0551301372 0.1216730000 992360824 0 1787781120 0.0514747687 0.0385796130 0.3565652966 981 39.2000000000 0.8668649197 0.4406784958 0.8954944611 0.0551030710 0.1301030000 992362098 0 1786433536 0.0514747687 0.0385796130 0.3565652966 982 39.2400000000 0.8653353453 0.4411109366 0.8954944611 0.0550763399 0.1266000000 992363372 0 1786527744 0.0514747687 0.0385796130 0.3565652966 983 39.2800000000 0.8638515472 0.4415409881 0.8954944611 0.0550496090 0.1379160000 992364646 0 1787019264 0.0514747687 0.0385796130 0.3565652966 984 39.3200000000 0.8629990816 0.4419692992 0.8954944611 0.0550225016 0.1256630000 992365920 0 1787527168 0.0514747687 0.0385796130 0.3565652966 985 39.3600000000 0.8605485559 0.4423942527 0.8954944611 0.0549954400 0.1303880000 992367194 0 1787781120 0.0514747687 0.0385796130 0.3565652966 986 39.4000000000 0.8589537144 0.4428167268 0.8954944611 0.0549682067 0.1313790000 992368468 0 1788162048 0.0514747687 0.0385796130 0.3565652966 987 39.4400000000 0.8574744463 0.4432368461 0.8954944611 0.0549408395 0.1191800000 992369742 0 1785536512 0.0514747687 0.0385796130 0.3565652966 988 39.4800000000 0.8561027646 0.4436547266 0.8954944611 0.0549137459 0.1386520000 992371016 0 1786019840 0.0514747687 0.0385796130 0.3565652966 989 39.5200000000 0.8537533879 0.4440693865 0.8954944611 0.0548869131 0.1258370000 992372290 0 1786527744 0.0514747687 0.0385796130 0.3565652966 990 39.5600000000 0.8524838090 0.4444819263 0.8954944611 0.0548604012 0.1092370000 992373564 0 1787162624 0.0514747687 0.0385796130 0.3565652966 991 39.6000000000 0.8500663638 0.4448911942 0.8954944611 0.0548333557 0.1223070000 992374838 0 1787400192 0.0514747687 0.0385796130 0.3565652966 992 39.6400000000 0.8481475115 0.4452977026 0.8954944611 0.0548063058 0.0978210000 992376112 0 1787654144 0.0514747687 0.0385796130 0.3565652966 993 39.6800000000 0.8465212584 0.4457017545 0.8954944611 0.0547792668 0.0921030000 992377386 0 1786052608 0.0514747687 0.0385796130 0.3565652966 994 39.7200000000 0.8434236050 0.4461018771 0.8954944611 0.0547522524 0.0903670000 992378660 0 1786052608 0.0514747687 0.0385796130 0.3565652966 995 39.7600000000 0.8402594924 0.4464980154 0.8954944611 0.0547252623 0.0929850000 992379934 0 1786527744 0.0514747687 0.0385796130 0.3565652966 996 39.8000000000 0.8378180861 0.4468909070 0.8954944611 0.0546978594 0.0630080000 992381208 0 1787162624 0.0514747687 0.0385796130 0.3565652966 997 39.8400000000 0.8361909986 0.4472813785 0.8954944611 0.0546704553 0.0667620000 992382482 0 1787416576 0.0514747687 0.0385796130 0.3565652966 998 39.8800000000 0.8340699077 0.4476689422 0.8954944611 0.0546430730 0.0573860000 992383756 0 1787654144 0.0514747687 0.0385796130 0.3565652966 999 39.9200000000 0.8295319080 0.4480511874 0.8954944611 0.0546157223 0.0536450000 992385030 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1000 39.9600000000 0.8276172280 0.4484307534 0.8954944611 0.0545884104 0.0540010000 992386304 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1001 40.0000000000 0.8252308369 0.4488071771 0.8954944611 0.0545611194 0.0533570000 992387578 0 1786527744 0.0514747687 0.0385796130 0.3565652966 1002 40.0400000000 0.8231158257 0.4491807386 0.8954944611 0.0545339143 0.0582920000 992388852 0 1787162624 0.0514747687 0.0385796130 0.3565652966 1003 40.0800000000 0.8213744760 0.4495518191 0.8954944611 0.0545067155 0.0579410000 992390126 0 1787400192 0.0514747687 0.0385796130 0.3565652966 1004 40.1200000000 0.8181843162 0.4499189829 0.8954944611 0.0544795760 0.0536010000 992391400 0 1787654144 0.0514747687 0.0385796130 0.3565652966 1005 40.1600000000 0.8174569011 0.4502846923 0.8954944611 0.0544527253 0.0584770000 992392674 0 1786433536 0.0514747687 0.0385796130 0.3565652966 1006 40.2000000000 0.8151412010 0.4506473727 0.8954944611 0.0544258492 0.0548720000 992393948 0 1786433536 0.0514747687 0.0385796130 0.3565652966 1007 40.2400000000 0.8118892908 0.4510061035 0.8954944611 0.0543988005 0.0538860000 992395222 0 1786908672 0.0514747687 0.0385796130 0.3565652966 1008 40.2800000000 0.8098412752 0.4513620908 0.8954944611 0.0543720262 0.0542320000 992396496 0 1787543552 0.0514747687 0.0385796130 0.3565652966 1009 40.3200000000 0.8069396019 0.4517144967 0.8954944611 0.0543454187 0.0531670000 992397770 0 1787797504 0.0514747687 0.0385796130 0.3565652966 1010 40.3600000000 0.8034868836 0.4520627862 0.8954944611 0.0543184891 0.0547170000 992399044 0 1788035072 0.0514747687 0.0385796130 0.3565652966 1011 40.4000000000 0.7998216748 0.4524067613 0.8954944611 0.0542918119 0.0530970000 992400318 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1012 40.4400000000 0.7969065905 0.4527471762 0.8954944611 0.0542651312 0.0543430000 992401592 0 1785286656 0.0514747687 0.0385796130 0.3565652966 1013 40.4800000000 0.7943965793 0.4530844411 0.8954944611 0.0542383890 0.0477910000 992402866 0 1785286656 0.0514747687 0.0385796130 0.3565652966 1014 40.5200000000 0.7920879126 0.4534187641 0.8954944611 0.0542117738 0.0506670000 992404140 0 1784651776 0.0514747687 0.0385796130 0.3565652966 1015 40.5600000000 0.7896046042 0.4537499817 0.8954944611 0.0541853623 0.0514170000 992405414 0 1784651776 0.0514747687 0.0385796130 0.3565652966 1016 40.6000000000 0.7877143621 0.4540786868 0.8954944611 0.0541588631 0.0508700000 992406688 0 1784381440 0.0514747687 0.0385796130 0.3565652966 1017 40.6400000000 0.7849507928 0.4544040281 0.8954944611 0.0541324339 0.0497680000 992407962 0 1784381440 0.0514747687 0.0385796130 0.3565652966 1018 40.6800000000 0.7827132344 0.4547265322 0.8954944611 0.0541060986 0.0523630000 992409236 0 1783746560 0.0514747687 0.0385796130 0.3565652966 1019 40.7200000000 0.7804223895 0.4550461552 0.8954944611 0.0540800957 0.0507340000 992410510 0 1783746560 0.0514747687 0.0385796130 0.3565652966 1020 40.7600000000 0.7787180543 0.4553634806 0.8954944611 0.0540540636 0.0524940000 992411784 0 1784242176 0.0514747687 0.0385796130 0.3565652966 1021 40.8000000000 0.7764181495 0.4556779318 0.8954944611 0.0540280914 0.0528570000 992413058 0 1784733696 0.0514747687 0.0385796130 0.3565652966 1022 40.8400000000 0.7749958038 0.4559903759 0.8954944611 0.0540019925 0.0512620000 992414332 0 1785114624 0.0514747687 0.0385796130 0.3565652966 1023 40.8800000000 0.7735086083 0.4563007554 0.8954944611 0.0539759659 0.0553290000 992415606 0 1785241600 0.0514747687 0.0385796130 0.3565652966 1024 40.9200000000 0.7716436386 0.4566087074 0.8954944611 0.0539507478 0.0521530000 992416880 0 1786130432 0.0514747687 0.0385796130 0.3565652966 1025 40.9600000000 0.7702136636 0.4569146635 0.8954944611 0.0539256759 0.0548790000 992418154 0 1786638336 0.0514747687 0.0385796130 0.3565652966 1026 41.0000000000 0.7670776248 0.4572169666 0.8954944611 0.0539004519 0.0586660000 992587364 0 1787527168 0.0514747687 0.0385796130 0.3565652966 1027 41.0400000000 0.7648350000 0.4575164973 0.8954944611 0.0538753466 0.0590020000 992588638 0 1785925632 0.0514747687 0.0385796130 0.3565652966 1028 41.0800000000 0.7630495429 0.4578137084 0.8954944611 0.0538500883 0.0565030000 992589912 0 1785925632 0.0514747687 0.0385796130 0.3565652966 1029 41.1200000000 0.7605420351 0.4581079050 0.8954944611 0.0538247004 0.0533420000 992591186 0 1786527744 0.0514747687 0.0385796130 0.3565652966 1030 41.1600000000 0.7584849000 0.4583995332 0.8954944611 0.0537995819 0.0522440000 992592460 0 1787035648 0.0514747687 0.0385796130 0.3565652966 1031 41.2000000000 0.7557610869 0.4586879537 0.8954944611 0.0537745570 0.0517390000 992593734 0 1787289600 0.0514747687 0.0385796130 0.3565652966 1032 41.2400000000 0.7535722256 0.4589736943 0.8954944611 0.0537490189 0.0500570000 992595008 0 1787654144 0.0514747687 0.0385796130 0.3565652966 1033 41.2800000000 0.7519055605 0.4592572682 0.8954944611 0.0537236377 0.0535480000 992596282 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1034 41.3200000000 0.7477418184 0.4595362668 0.8954944611 0.0537020630 0.0469550000 992597556 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1035 41.3600000000 0.7463989258 0.4598134288 0.8954944611 0.0536767974 0.0512740000 992598830 0 1786527744 0.0514747687 0.0385796130 0.3565652966 1036 41.4000000000 0.7442190647 0.4600879516 0.8954944611 0.0536521278 0.0478890000 992600104 0 1787035648 0.0514747687 0.0385796130 0.3565652966 1037 41.4400000000 0.7425441742 0.4603603298 0.8954944611 0.0536276395 0.0484180000 992601378 0 1787416576 0.0514747687 0.0385796130 0.3565652966 1038 41.4800000000 0.7403160930 0.4606300367 0.8954944611 0.0536028664 0.0473640000 992602652 0 1787654144 0.0514747687 0.0385796130 0.3565652966 1039 41.5200000000 0.7383724451 0.4608973538 0.8954944611 0.0535784636 0.0486240000 992603926 0 1786433536 0.0514747687 0.0385796130 0.3565652966 1040 41.5600000000 0.7366098762 0.4611624620 0.8954944611 0.0535540047 0.0500560000 992605200 0 1786433536 0.0514747687 0.0385796130 0.3565652966 1041 41.6000000000 0.7350382805 0.4614255511 0.8954944611 0.0535294082 0.0469320000 992606474 0 1786908672 0.0514747687 0.0385796130 0.3565652966 1042 41.6400000000 0.7331630588 0.4616863357 0.8954944611 0.0535052886 0.0470760000 992607748 0 1787416576 0.0514747687 0.0385796130 0.3565652966 1043 41.6800000000 0.7313262224 0.4619448591 0.8954944611 0.0534813012 0.0454150000 992609022 0 1787797504 0.0514747687 0.0385796130 0.3565652966 1044 41.7200000000 0.7301064134 0.4622017188 0.8954944611 0.0534569704 0.0426810000 992610296 0 1787908096 0.0514747687 0.0385796130 0.3565652966 1045 41.7600000000 0.7295688391 0.4624575725 0.8954944611 0.0534325560 0.0457870000 992611570 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1046 41.8000000000 0.7282702923 0.4627116956 0.8954944611 0.0534087508 0.0516110000 992612844 0 1785536512 0.0514747687 0.0385796130 0.3565652966 1047 41.8400000000 0.7278434634 0.4629649255 0.8954944611 0.0533844206 0.0489840000 992614118 0 1785544704 0.0514747687 0.0385796130 0.3565652966 1048 41.8800000000 0.7264358401 0.4632163291 0.8954944611 0.0533597942 0.0449540000 992615392 0 1784766464 0.0514747687 0.0385796130 0.3565652966 1049 41.9200000000 0.7249401212 0.4634658274 0.8954944611 0.0533354907 0.0469540000 992616666 0 1784778752 0.0514747687 0.0385796130 0.3565652966 1050 41.9600000000 0.7236068845 0.4637135808 0.8954944611 0.0533109670 0.0473130000 992617940 0 1784250368 0.0514747687 0.0385796130 0.3565652966 1051 42.0000000000 0.7224974632 0.4639598072 0.8954944611 0.0532866641 0.0427460000 992619214 0 1784250368 0.0514747687 0.0385796130 0.3565652966 1052 42.0400000000 0.7218516469 0.4642049515 0.8954944611 0.0532622347 0.0470170000 992620488 0 1783746560 0.0514747687 0.0385796130 0.3565652966 1053 42.0800000000 0.7205014825 0.4644483480 0.8954944611 0.0532382278 0.0491180000 992621762 0 1783746560 0.0514747687 0.0385796130 0.3565652966 1054 42.1200000000 0.7197427154 0.4646905628 0.8954944611 0.0532141046 0.0476720000 992623036 0 1783017472 0.0514747687 0.0385796130 0.3565652966 1055 42.1600000000 0.7191248536 0.4649317327 0.8954944611 0.0531899189 0.0452600000 992624310 0 1783017472 0.0514747687 0.0385796130 0.3565652966 1056 42.2000000000 0.7186408043 0.4651719875 0.8954944611 0.0531663225 0.0458390000 992625584 0 1782366208 0.0514747687 0.0385796130 0.3565652966 1057 42.2400000000 0.7180882692 0.4654112650 0.8954944611 0.0531426175 0.0458970000 992626858 0 1782321152 0.0514747687 0.0385796130 0.3565652966 1058 42.2800000000 0.7181184888 0.4656501187 0.8954944611 0.0531183980 0.0456540000 992628132 0 1781731328 0.0514747687 0.0385796130 0.3565652966 1059 42.3200000000 0.7183578610 0.4658887474 0.8954944611 0.0530945332 0.0502270000 992629406 0 1781731328 0.0514747687 0.0385796130 0.3565652966 1060 42.3600000000 0.7184921503 0.4661270525 0.8954944611 0.0530706736 0.0526770000 992630680 0 1780969472 0.0514747687 0.0385796130 0.3565652966 1061 42.4000000000 0.7187449932 0.4663651467 0.8954944611 0.0530467617 0.0466560000 992631954 0 1780969472 0.0514747687 0.0385796130 0.3565652966 1062 42.4400000000 0.7207314372 0.4666046629 0.8954944611 0.0530258334 0.0475930000 992633228 0 1780711424 0.0514747687 0.0385796130 0.3565652966 1063 42.4800000000 0.7214491367 0.4668444037 0.8954944611 0.0530016226 0.0462050000 992634502 0 1780711424 0.0514747687 0.0385796130 0.3565652966 1064 42.5200000000 0.7221353054 0.4670843388 0.8954944611 0.0529774224 0.0486850000 992635776 0 1780084736 0.0514747687 0.0385796130 0.3565652966 1065 42.5600000000 0.7231003046 0.4673247294 0.8954944611 0.0529532315 0.0490220000 992637050 0 1779552256 0.0514747687 0.0385796130 0.3565652966 1066 42.6000000000 0.7233498693 0.4675649031 0.8954944611 0.0529293344 0.0533140000 992638324 0 1779560448 0.0514747687 0.0385796130 0.3565652966 1067 42.6400000000 0.7239785790 0.4678052158 0.8954944611 0.0529057621 0.0523380000 992639598 0 1778937856 0.0514747687 0.0385796130 0.3565652966 1068 42.6800000000 0.7247758508 0.4680458250 0.8954944611 0.0528822025 0.0505950000 992640872 0 1778937856 0.0514747687 0.0385796130 0.3565652966 1069 42.7200000000 0.7251145840 0.4682863009 0.8954944611 0.0528588220 0.0532620000 992642146 0 1778302976 0.0514747687 0.0385796130 0.3565652966 1070 42.7600000000 0.7251301408 0.4685263419 0.8954944611 0.0528352891 0.0472360000 992643420 0 1778302976 0.0514747687 0.0385796130 0.3565652966 1071 42.8000000000 0.7266026735 0.4687673095 0.8954944611 0.0528115061 0.0469380000 992644694 0 1777668096 0.0514747687 0.0385796130 0.3565652966 1072 42.8400000000 0.7280364633 0.4690091651 0.8954944611 0.0527883652 0.0456860000 992645968 0 1777668096 0.0514747687 0.0385796130 0.3565652966 1073 42.8800000000 0.7281495929 0.4692506752 0.8954944611 0.0527649797 0.0485260000 992647242 0 1777299456 0.0514747687 0.0385796130 0.3565652966 1074 42.9200000000 0.7285320163 0.4694920918 0.8954944611 0.0527417463 0.0471540000 992648516 0 1777287168 0.0514747687 0.0385796130 0.3565652966 1075 42.9600000000 0.7286180258 0.4697331391 0.8954944611 0.0527179504 0.0516510000 992649790 0 1776668672 0.0514747687 0.0385796130 0.3565652966 1076 43.0000000000 0.7302508950 0.4699752560 0.8954944611 0.0526939769 0.0532600000 992651064 0 1776607232 0.0514747687 0.0385796130 0.3565652966 1077 43.0400000000 0.7327514887 0.4702192451 0.8954944611 0.0526699963 0.0516310000 992652338 0 1777115136 0.0514747687 0.0385796130 0.3565652966 1078 43.0800000000 0.7345156670 0.4704644180 0.8954944611 0.0526461106 0.0520110000 992653612 0 1777623040 0.0514747687 0.0385796130 0.3565652966 1079 43.1200000000 0.7371439338 0.4707115724 0.8954944611 0.0526220345 0.0467080000 992654886 0 1778003968 0.0514747687 0.0385796130 0.3565652966 1080 43.1600000000 0.7389634252 0.4709599537 0.8954944611 0.0525981764 0.0481910000 992656160 0 1778257920 0.0514747687 0.0385796130 0.3565652966 1081 43.2000000000 0.7414671779 0.4712101916 0.8954944611 0.0525745162 0.0466560000 992657434 0 1778892800 0.0514747687 0.0385796130 0.3565652966 1082 43.2400000000 0.7432761192 0.4714616389 0.8954944611 0.0525508489 0.0465130000 992658708 0 1779400704 0.0514747687 0.0385796130 0.3565652966 1083 43.2800000000 0.7452533841 0.4717144475 0.8954944611 0.0525275253 0.0504980000 992659982 0 1779908608 0.0514747687 0.0385796130 0.3565652966 1084 43.3200000000 0.7463469505 0.4719677985 0.8954944611 0.0525037274 0.0503860000 992661256 0 1780416512 0.0514747687 0.0385796130 0.3565652966 1085 43.3600000000 0.7473301291 0.4722215887 0.8954944611 0.0524799357 0.0505400000 992662530 0 1780924416 0.0514747687 0.0385796130 0.3565652966 1086 43.4000000000 0.7483822703 0.4724758803 0.8954944611 0.0524561789 0.0478810000 992663804 0 1781559296 0.0514747687 0.0385796130 0.3565652966 1087 43.4400000000 0.7500023246 0.4727311944 0.8954944611 0.0524323931 0.0499900000 992665078 0 1782067200 0.0514747687 0.0385796130 0.3565652966 1088 43.4800000000 0.7509876490 0.4729869449 0.8954944611 0.0524089396 0.0489770000 992666352 0 1782575104 0.0514747687 0.0385796130 0.3565652966 1089 43.5200000000 0.7526683807 0.4732437689 0.8954944611 0.0523855313 0.0522500000 992667626 0 1783083008 0.0514747687 0.0385796130 0.3565652966 1090 43.5600000000 0.7538015246 0.4735011614 0.8954944611 0.0523622707 0.0519250000 992668900 0 1783717888 0.0514747687 0.0385796130 0.3565652966 1091 43.6000000000 0.7552482486 0.4737594080 0.8954944611 0.0523389210 0.0543600000 992670174 0 1784225792 0.0514747687 0.0385796130 0.3565652966 1092 43.6400000000 0.7573933005 0.4740191460 0.8954944611 0.0523158991 0.0486370000 992671448 0 1784733696 0.0514747687 0.0385796130 0.3565652966 1093 43.6800000000 0.7597538233 0.4742805684 0.8954944611 0.0522925389 0.0518100000 992672722 0 1785241600 0.0514747687 0.0385796130 0.3565652966 1094 43.7200000000 0.7615488768 0.4745431537 0.8954944611 0.0522692382 0.0527790000 992673996 0 1785749504 0.0514747687 0.0385796130 0.3565652966 1095 43.7600000000 0.7639513612 0.4748074534 0.8954944611 0.0522460310 0.0513400000 992675270 0 1786384384 0.0514747687 0.0385796130 0.3565652966 1096 43.8000000000 0.7661206722 0.4750732502 0.8954944611 0.0522227331 0.0516190000 992676544 0 1786892288 0.0514747687 0.0385796130 0.3565652966 1097 43.8400000000 0.7680848241 0.4753403528 0.8954944611 0.0521993587 0.0534110000 992677818 0 1787400192 0.0514747687 0.0385796130 0.3565652966 1098 43.8800000000 0.7698434591 0.4756085706 0.8954944611 0.0521758751 0.0541510000 992679092 0 1787908096 0.0514747687 0.0385796130 0.3565652966 1099 43.9200000000 0.7710277438 0.4758773778 0.8954944611 0.0521525580 0.0529280000 992680366 0 1786052608 0.0514747687 0.0385796130 0.3565652966 1100 43.9600000000 0.7729572654 0.4761474504 0.8954944611 0.0521297743 0.0527210000 992681640 0 1785434112 0.0514747687 0.0385796130 0.3565652966 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:03:00 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0506070000 86795971 0 976482304 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0033705044 0.0016852522 0.0033705044 0.0054106945 0.2689160000 98518756 0 1095843840 0.0022963362 0.0028668733 0.0001717152 3 0.0800000000 0.0075102816 0.0036269287 0.0075102816 0.0054655237 0.1566880000 101789346 0 1099653120 0.0039740796 0.0039736638 0.0003096815 4 0.1200000000 0.0019486375 0.0032073559 0.0075102816 0.0061830273 0.1243500000 101790928 0 1100414976 0.0003381678 0.0002916229 -0.0001045707 5 0.1600000000 0.0012014543 0.0028061756 0.0075102816 0.0054261034 0.1518760000 101792518 0 1100922880 0.0002680846 -0.0001553374 0.0000558771 6 0.2000000000 0.0019333151 0.0026606988 0.0075102816 0.0050250951 0.1079960000 101794428 0 1101557760 -0.0000145821 -0.0004096011 -0.0002697191 7 0.2400000000 0.0019818847 0.0025637254 0.0075102816 0.0051560429 0.2162140000 101795682 0 1102065664 -0.0006491534 -0.0042378344 -0.0002625633 8 0.2800000000 0.0004956174 0.0023052119 0.0075102816 0.0049487851 0.1151190000 101796936 0 1102573568 -0.0002630980 -0.0013435701 -0.0000252999 9 0.3200000000 0.0008880292 0.0021477471 0.0075102816 0.0046562758 0.1271550000 101798862 0 1103081472 0.0000160443 -0.0002884316 -0.0001227701 10 0.3600000000 0.0012787767 0.0020608501 0.0075102816 0.0044065811 0.1235510000 101801428 0 1103589376 -0.0000999364 -0.0006757299 -0.0001430929 11 0.4000000000 0.0008700256 0.0019525933 0.0075102816 0.0041895496 0.1124520000 101802682 0 1104224256 -0.0000014565 -0.0004570811 -0.0000629745 12 0.4400000000 0.0002331002 0.0018093022 0.0075102816 0.0040102592 0.1261940000 101803936 0 1104732160 0.0000162739 -0.0002809684 0.0000549899 13 0.4800000000 0.0003654936 0.0016982400 0.0075102816 0.0038547841 0.1067440000 101805190 0 1105240064 0.0001998892 -0.0001442756 0.0002456309 14 0.5200000000 0.0001327949 0.0015864225 0.0075102816 0.0037514241 0.1074570000 101806444 0 1105747968 0.0001556035 0.0001755415 0.0002702832 15 0.5600000000 0.0004023565 0.0015074848 0.0075102816 0.0036971673 0.1160710000 101807698 0 1106255872 0.0003862177 -0.0000352905 0.0003557773 16 0.6000000000 0.0047872891 0.0017124725 0.0075102816 0.0040172387 0.1845090000 101808952 0 1106890752 0.0031236913 0.0040287138 0.0006492213 17 0.6400000000 0.0047073881 0.0018886441 0.0075102816 0.0038916914 0.1417220000 101811550 0 1107398656 0.0028081017 0.0039285207 0.0006309351 18 0.6800000000 0.0068192757 0.0021625680 0.0075102816 0.0038173695 0.1435480000 101815428 0 1107906560 0.0043711346 0.0047033643 0.0006183098 19 0.7200000000 0.0065569337 0.0023938504 0.0075102816 0.0037793953 0.1645760000 101816682 0 1108414464 0.0042978823 0.0044428748 0.0005996169 20 0.7600000000 0.0009596035 0.0023221381 0.0075102816 0.0043248293 0.1251130000 101817936 0 1109049344 0.0003886615 -0.0000759575 0.0002800639 21 0.8000000000 0.0010050923 0.0022594216 0.0075102816 0.0043186045 0.1085620000 101819190 0 1109557248 0.0000360385 -0.0001035897 0.0002880407 22 0.8400000000 0.0012565067 0.0022138346 0.0075102816 0.0042550251 0.1136160000 101820444 0 1110065152 0.0005358672 0.0002350141 0.0003399083 23 0.8800000000 0.0013974643 0.0021783402 0.0075102816 0.0041841664 0.1128850000 101821698 0 1110573056 0.0004167517 0.0001469732 0.0002423339 24 0.9200000000 0.0009360880 0.0021265797 0.0075102816 0.0040960658 0.1229670000 101822952 0 1111080960 0.0001515582 -0.0000836589 0.0001878129 25 0.9600000000 0.0008417661 0.0020751872 0.0075102816 0.0040107704 0.1310930000 101824206 0 1111715840 -0.0000231448 -0.0002493341 0.0001459979 26 1.0000000000 0.0005063048 0.0020148455 0.0075102816 0.0039329682 0.1280990000 101825460 0 1112223744 -0.0000088439 -0.0003446910 0.0000855407 27 1.0400000000 0.0006890377 0.0019657415 0.0075102816 0.0038604654 0.1267540000 101826714 0 1112731648 -0.0000671922 -0.0003712362 0.0000995821 28 1.0800000000 0.0008630786 0.0019263607 0.0075102816 0.0038020379 0.1224790000 101827968 0 1113239552 -0.0000567125 -0.0003129480 0.0001359894 29 1.1200000000 0.0009593936 0.0018930170 0.0075102816 0.0037374816 0.1381700000 101829222 0 1113874432 -0.0002111903 -0.0003649209 0.0001607218 30 1.1600000000 0.0008856904 0.0018594395 0.0075102816 0.0036837864 0.1282300000 101830476 0 1114390528 -0.0000815274 -0.0002421695 0.0001164390 31 1.2000000000 0.0009706324 0.0018307683 0.0075102816 0.0036369744 0.1328230000 101831730 0 1114898432 -0.0001835214 -0.0000525425 0.0000609605 32 1.2400000000 0.0015101746 0.0018207497 0.0075102816 0.0035812294 0.1122940000 101832984 0 1115406336 -0.0000278407 -0.0000367781 0.0001711443 33 1.2800000000 0.0012696389 0.0018040494 0.0075102816 0.0035487418 0.1278420000 101836926 0 1115914240 -0.0003917370 -0.0002156228 0.0001678474 34 1.3200000000 0.0016776330 0.0018003313 0.0075102816 0.0035084110 0.1272500000 101843428 0 1116549120 -0.0005087470 -0.0002377028 0.0002616532 35 1.3600000000 0.0021329615 0.0018098350 0.0075102816 0.0034683445 0.1270960000 101844682 0 1117057024 -0.0006695552 -0.0004785914 0.0001993448 36 1.4000000000 0.0023367726 0.0018244721 0.0075102816 0.0034212852 0.1273930000 101845936 0 1117564928 -0.0006791386 -0.0008514663 0.0002198265 37 1.4400000000 0.0057607903 0.0019308591 0.0075102816 0.0037331203 0.1761000000 101847190 0 1118072832 -0.0015467369 -0.0069879359 0.0003600914 38 1.4800000000 0.0050662206 0.0020133686 0.0075102816 0.0036842798 0.1452060000 101848444 0 1118707712 -0.0020507323 -0.0069252877 0.0000949507 39 1.5200000000 0.0031766803 0.0020431971 0.0075102816 0.0039984963 0.1343880000 101849698 0 1119215616 -0.0011515347 -0.0015846652 0.0003113441 40 1.5600000000 0.0089553241 0.0022160003 0.0089553241 0.0044105096 0.1674030000 101850952 0 1119723520 0.0046073073 -0.0057715164 0.0004771043 41 1.6000000000 0.0032915573 0.0022422334 0.0089553241 0.0044335751 0.1124850000 101852206 0 1120231424 -0.0011629034 -0.0008059608 0.0008079994 42 1.6400000000 0.0035956844 0.0022744584 0.0089553241 0.0044368500 0.1145630000 101853460 0 1120739328 -0.0014832758 -0.0009655903 0.0008577526 43 1.6800000000 0.0045333486 0.0023269908 0.0089553241 0.0044218459 0.1193450000 101854714 0 1121374208 -0.0010496870 -0.0002427112 0.0012416594 44 1.7200000000 0.0039190799 0.0023631746 0.0089553241 0.0043772988 0.1163950000 101855968 0 1121882112 -0.0019486464 -0.0005080145 0.0016405890 45 1.7600000000 0.0043323766 0.0024069347 0.0089553241 0.0043397733 0.1157480000 101857222 0 1122381824 -0.0019111163 -0.0007797289 0.0020544559 46 1.8000000000 0.0048116469 0.0024592110 0.0089553241 0.0043818866 0.1408940000 101858476 0 1122889728 -0.0023996443 -0.0006587082 0.0023703505 47 1.8400000000 0.0043525053 0.0024994939 0.0089553241 0.0044618011 0.1233600000 101859730 0 1123524608 -0.0027740898 -0.0016565421 0.0028689823 48 1.8800000000 0.0056460085 0.0025650463 0.0089553241 0.0045403992 0.1304670000 101860984 0 1124032512 -0.0026145983 -0.0005232323 0.0036485717 49 1.9200000000 0.0070281676 0.0026561304 0.0089553241 0.0046871352 0.1186750000 101862238 0 1124540416 -0.0020580790 -0.0005412224 0.0043325056 50 1.9600000000 0.0070757596 0.0027445229 0.0089553241 0.0048917575 0.1206790000 101863492 0 1125048320 -0.0023837923 -0.0011053989 0.0052002966 51 2.0000000000 0.0076266914 0.0028402517 0.0089553241 0.0049953519 0.2413070000 114206230 0 1137872896 -0.0024363105 -0.0007331793 0.0061414861 52 2.0400000000 0.0081350813 0.0029420754 0.0089553241 0.0050986634 0.1140180000 117865532 0 1141936128 -0.0021547377 -0.0006647139 0.0071947584 53 2.0800000000 0.0091084875 0.0030584228 0.0091084875 0.0051397064 0.1131420000 121058882 0 1145618432 -0.0024528140 -0.0006970538 0.0081672538 54 2.1200000000 0.0100579495 0.0031880436 0.0100579495 0.0051834914 0.1170610000 121060136 0 1146380288 -0.0019887474 -0.0005879120 0.0091766231 55 2.1600000000 0.0108699091 0.0033277139 0.0108699091 0.0051716092 0.1279530000 121061390 0 1147015168 -0.0020018180 -0.0001977275 0.0105141969 56 2.2000000000 0.0124243991 0.0034901547 0.0124243991 0.0051930902 0.1404190000 121062644 0 1147523072 -0.0049155685 0.0011767766 0.0117966961 57 2.2400000000 0.0129453856 0.0036560360 0.0129453856 0.0051586348 0.1224420000 121063898 0 1148030976 -0.0019366384 0.0007343963 0.0131135369 58 2.2800000000 0.0142660858 0.0038389679 0.0142660858 0.0052026168 0.1326790000 121065152 0 1148538880 -0.0019582857 0.0021178497 0.0145657873 59 2.3200000000 0.0155069772 0.0040367307 0.0155069772 0.0052376454 0.0954850000 121066406 0 1149173760 0.0005918027 0.0024798398 0.0161878187 60 2.3600000000 0.0183324050 0.0042749920 0.0183324050 0.0055139892 0.1105820000 121067660 0 1149681664 0.0013605029 0.0046957554 0.0178505722 61 2.4000000000 0.0195516404 0.0045254288 0.0195516404 0.0057360757 0.1229290000 121068914 0 1150189568 0.0012415835 0.0049176109 0.0193168335 62 2.4400000000 0.0216900166 0.0048022770 0.0216900166 0.0059809063 0.1076670000 121070168 0 1150697472 0.0016032651 0.0065515889 0.0209500492 63 2.4800000000 0.0227842610 0.0050877053 0.0227842610 0.0061569809 0.1202220000 121071422 0 1151332352 0.0011077924 0.0058922977 0.0224300250 64 2.5200000000 0.0228874348 0.0053658261 0.0228874348 0.0062848948 0.1067630000 121072676 0 1151840256 0.0025039418 0.0040447931 0.0238646697 65 2.5600000000 0.0250929631 0.0056693205 0.0250929631 0.0064866075 0.1339190000 121079306 0 1152348160 0.0036529431 0.0061918744 0.0257676151 66 2.6000000000 0.0283151213 0.0060124387 0.0283151213 0.0067992752 0.1345000000 121091056 0 1152856064 0.0054526119 0.0092866402 0.0274718069 67 2.6400000000 0.0287034698 0.0063511108 0.0287034698 0.0070911961 0.1405740000 121092310 0 1153490944 0.0057450645 0.0088234572 0.0290398076 68 2.6800000000 0.0309497006 0.0067128548 0.0309497006 0.0074450657 0.1527920000 121093564 0 1153998848 0.0058986922 0.0111893127 0.0307169054 69 2.7200000000 0.0327989906 0.0070909147 0.0327989906 0.0076238611 0.1428650000 121094818 0 1154506752 0.0077358102 0.0120365368 0.0323612466 70 2.7600000000 0.0330008641 0.0074610569 0.0330008641 0.0077623373 0.1354180000 121096072 0 1155014656 0.0079895835 0.0096314484 0.0335482359 71 2.8000000000 0.0358937420 0.0078615172 0.0358937420 0.0078019035 0.1311510000 121097326 0 1155649536 0.0090787327 0.0136451721 0.0354663469 72 2.8400000000 0.0360402353 0.0082528883 0.0360402353 0.0077939285 0.3521520000 139931536 0 1172283392 0.0099097528 0.0116930436 0.0368094072 73 2.8800000000 0.0377690122 0.0086572188 0.0377690122 0.0077984685 0.1105020000 143590638 0 1176457216 0.0092435041 0.0111742681 0.0376742184 74 2.9200000000 0.0391412601 0.0090691653 0.0391412601 0.0078010561 0.1561140000 146783988 0 1180139520 0.0109760500 0.0131260427 0.0395269729 75 2.9600000000 0.0403126962 0.0094857457 0.0403126962 0.0078643734 0.1180880000 146785242 0 1180901376 0.0113376863 0.0130785229 0.0408056565 76 3.0000000000 0.0424205624 0.0099190985 0.0424205624 0.0080249222 0.1217370000 146786496 0 1181409280 0.0124660842 0.0144313723 0.0422501005 77 3.0400000000 0.0438574292 0.0103598561 0.0438574292 0.0081839420 0.1198290000 146787750 0 1182044160 0.0128874220 0.0142820412 0.0434569865 78 3.0800000000 0.0452281870 0.0108068860 0.0452281870 0.0083849580 0.0992710000 146789004 0 1182552064 0.0132730762 0.0150245065 0.0449605845 79 3.1200000000 0.0464549363 0.0112581271 0.0464549363 0.0085556580 0.1013090000 146790258 0 1183059968 0.0140773859 0.0156867877 0.0464544073 80 3.1600000000 0.0480268113 0.0117177357 0.0480268113 0.0086879572 0.0962440000 146791512 0 1183567872 0.0144811533 0.0157056842 0.0476849973 81 3.2000000000 0.0496491492 0.0121860247 0.0496491492 0.0088360036 0.1060830000 146792766 0 1184202752 0.0148980040 0.0164070893 0.0491331294 82 3.2400000000 0.0506460778 0.0126550498 0.0506460778 0.0089771491 0.1186510000 146794020 0 1184710656 0.0157174338 0.0165956318 0.0505761839 83 3.2800000000 0.0523803346 0.0131336676 0.0523803346 0.0091575803 0.3837670000 159101814 0 1197662208 0.0160708390 0.0170491207 0.0520006195 84 3.3200000000 0.0540105961 0.0136202977 0.0540105961 0.0092357173 0.1106670000 162761324 0 1201598464 0.0169649683 0.0182526316 0.0534285158 85 3.3600000000 0.0553977638 0.0141117974 0.0553977638 0.0092951694 0.1450780000 165954674 0 1205407744 0.0177051034 0.0193522777 0.0548923463 86 3.4000000000 0.0568499714 0.0146087529 0.0568499714 0.0093472332 0.1076810000 165955928 0 1206169600 0.0178167522 0.0198497381 0.0563103482 87 3.4400000000 0.0582100302 0.0151099170 0.0582100302 0.0094097379 0.1127840000 165957182 0 1206677504 0.0180213153 0.0201747380 0.0578495339 88 3.4800000000 0.0600634515 0.0156207526 0.0600634515 0.0094909807 0.1005920000 165958436 0 1207185408 0.0180272218 0.0208794512 0.0592647754 89 3.5200000000 0.0612429157 0.0161333612 0.0612429157 0.0095610824 0.1093660000 165959690 0 1207693312 0.0188854653 0.0213758796 0.0609902292 90 3.5600000000 0.0626201481 0.0166498810 0.0626201481 0.0096597324 0.0993580000 165960944 0 1208328192 0.0192783643 0.0218784828 0.0625755191 91 3.6000000000 0.0643741786 0.0171743238 0.0643741786 0.0097924637 0.0896290000 165962198 0 1208836096 0.0197941177 0.0222470146 0.0642623752 92 3.6400000000 0.0657888949 0.0177027431 0.0657888949 0.0098664517 0.0892390000 165963452 0 1209344000 0.0202705786 0.0224418510 0.0659793690 93 3.6800000000 0.0673786774 0.0182368929 0.0673786774 0.0098648281 0.0921020000 165964706 0 1209851904 0.0205913521 0.0229823012 0.0676885396 94 3.7200000000 0.0689180493 0.0187760542 0.0689180493 0.0098386057 0.1165040000 165965960 0 1210359808 0.0210023280 0.0236028954 0.0693589672 95 3.7600000000 0.0703611076 0.0193190547 0.0703611076 0.0098208218 0.3226440000 178271014 0 1223184384 0.0218793154 0.0242173839 0.0711796284 96 3.8000000000 0.0732780173 0.0198811273 0.0732780173 0.0098617167 0.1686040000 181930116 0 1227247616 0.0215991344 0.0271517709 0.0730755553 97 3.8400000000 0.0732426718 0.0204312463 0.0732780173 0.0099142530 0.1312670000 185123466 0 1230929920 0.0247700159 0.0276406258 0.0753016695 98 3.8800000000 0.0749295354 0.0209873513 0.0749295354 0.0100434905 0.0992160000 185124720 0 1231691776 0.0243108012 0.0277295262 0.0768276528 99 3.9200000000 0.0760034397 0.0215430693 0.0760034397 0.0101410512 0.0946860000 185125974 0 1232326656 0.0257162787 0.0277465768 0.0786477253 100 3.9600000000 0.0798487365 0.0221261260 0.0798487365 0.0103082635 0.0977760000 185127228 0 1232834560 0.0228294451 0.0322749950 0.0803464949 101 4.0000000000 0.0792154521 0.0226913669 0.0798487365 0.0103386302 0.0925440000 185128482 0 1233342464 0.0246502776 0.0296860393 0.0821128413 102 4.0400000000 0.0807215869 0.0232602906 0.0807215869 0.0103471859 0.0909580000 185129736 0 1233850368 0.0251496360 0.0300020948 0.0836889148 103 4.0800000000 0.0821446180 0.0238319831 0.0821446180 0.0103564396 0.0811320000 185130990 0 1234358272 0.0250902399 0.0312192403 0.0854973570 104 4.1200000000 0.0836818367 0.0244074624 0.0836818367 0.0103595305 0.0991640000 185132244 0 1234984960 0.0257007200 0.0319182612 0.0872583538 105 4.1600000000 0.0848548040 0.0249831514 0.0848548040 0.0103599673 0.1061330000 185133498 0 1235492864 0.0260104164 0.0321116932 0.0886727348 106 4.2000000000 0.0873153955 0.0255711914 0.0873153955 0.0103716895 0.3072510000 197441736 0 1248317440 0.0256475322 0.0361083411 0.0906483606 107 4.2400000000 0.0886698067 0.0261608981 0.0886698067 0.0103469079 0.0942010000 201100838 0 1252253696 0.0260673072 0.0364402346 0.0921261311 108 4.2800000000 0.0897676200 0.0267498493 0.0897676200 0.0103291562 0.1186070000 204294188 0 1256062976 0.0263658073 0.0375606939 0.0936424509 109 4.3200000000 0.0910575837 0.0273398285 0.0910575837 0.0103087423 0.1084490000 204295442 0 1256824832 0.0263075065 0.0383497998 0.0947971269 110 4.3600000000 0.0926406235 0.0279334721 0.0926406235 0.0102685696 0.0941210000 204296696 0 1257332736 0.0253212787 0.0385944322 0.0957794189 111 4.4000000000 0.0933797583 0.0285230782 0.0933797583 0.0102443298 0.0994490000 204297950 0 1257840640 0.0270047039 0.0399702080 0.0977937356 112 4.4400000000 0.0944928676 0.0291120942 0.0944928676 0.0102055596 0.1010020000 204299204 0 1258475520 0.0268269982 0.0400450006 0.0989597961 113 4.4800000000 0.0959812179 0.0297038564 0.0959812179 0.0101720589 0.0911820000 204300458 0 1258983424 0.0258705504 0.0412953570 0.1000962555 114 4.5200000000 0.0968156680 0.0302925565 0.0968156680 0.0101368834 0.0930110000 204301712 0 1259491328 0.0270189941 0.0415610000 0.1015842110 115 4.5600000000 0.0976186618 0.0308780009 0.0976186618 0.0101037260 0.2921690000 216604854 0 1272442880 0.0272399690 0.0415005460 0.1030283049 116 4.6000000000 0.0972038880 0.0314497758 0.0976186618 0.0100690585 0.0910120000 220263956 0 1276379136 0.0304951817 0.0420827046 0.1052394807 117 4.6400000000 0.0990016460 0.0320271422 0.0990016460 0.0100401187 0.1254680000 223457306 0 1280188416 0.0301595498 0.0430889912 0.1064307019 118 4.6800000000 0.0993138850 0.0325973688 0.0993138850 0.0100047632 0.1226960000 223458560 0 1280950272 0.0307663716 0.0425002389 0.1081940383 119 4.7200000000 0.1017718390 0.0331786669 0.1017718390 0.0099835071 0.1009820000 223459814 0 1281458176 0.0298614372 0.0441739410 0.1094723865 120 4.7600000000 0.1020922959 0.0337529471 0.1020922959 0.0099519460 0.1006360000 223461068 0 1281966080 0.0313435271 0.0440290533 0.1116381809 121 4.8000000000 0.1035124660 0.0343294721 0.1035124660 0.0099345353 0.0960970000 223462322 0 1282600960 0.0316029564 0.0445303731 0.1132133082 122 4.8400000000 0.1044821143 0.0349044937 0.1044821143 0.0099343647 0.2575730000 235763636 0 1295425536 0.0317791216 0.0445716195 0.1151312068 123 4.8800000000 0.1064609140 0.0354862532 0.1064609140 0.0099216932 0.0703390000 239423578 0 1299361792 0.0310493242 0.0454397202 0.1165488288 124 4.9200000000 0.1070161089 0.0360631069 0.1070161089 0.0098912201 0.1145030000 242616928 0 1303044096 0.0321082026 0.0455728658 0.1186808050 125 4.9600000000 0.1076252833 0.0366356043 0.1076252833 0.0098907049 0.1122320000 242618182 0 1303805952 0.0344282985 0.0483441949 0.1222911328 126 5.0000000000 0.1099113002 0.0372171575 0.1099113002 0.0098823225 0.0946610000 242619436 0 1304440832 0.0324551165 0.0468215048 0.1223799065 127 5.0400000000 0.1111887097 0.0377996106 0.1111887097 0.0098804770 0.0924700000 242620690 0 1304948736 0.0331515931 0.0479761250 0.1247193739 128 5.0800000000 0.1133081540 0.0383895211 0.1133081540 0.0099078152 0.0906990000 242621944 0 1305456640 0.0327347368 0.0496389233 0.1262668073 129 5.1200000000 0.1139131412 0.0389749756 0.1139131412 0.0098834827 0.3245470000 254936538 0 1318281216 0.0335200876 0.0490965471 0.1283281147 130 5.1600000000 0.1155770123 0.0395642220 0.1155770123 0.0099225556 0.1276010000 258616120 0 1322344448 0.0361522436 0.0540183410 0.1318983436 131 5.2000000000 0.1154194847 0.0401432698 0.1155770123 0.0099013274 0.1079130000 261809470 0 1326026752 0.0371779725 0.0523583144 0.1337037683 132 5.2400000000 0.1163731441 0.0407207688 0.1163731441 0.0098752343 0.0990090000 261810724 0 1326788608 0.0375128388 0.0528196841 0.1355036050 133 5.2800000000 0.1175490916 0.0412984254 0.1175490916 0.0098674646 0.0940590000 261811978 0 1327423488 0.0380355977 0.0530909598 0.1371956617 134 5.3200000000 0.1189460531 0.0418778853 0.1189460531 0.0098929326 0.0830060000 261813232 0 1327931392 0.0382794812 0.0545566306 0.1391383410 135 5.3600000000 0.1196808964 0.0424542039 0.1196808964 0.0098923501 0.0859220000 261814486 0 1328439296 0.0398403816 0.0558145978 0.1413256079 136 5.4000000000 0.1210187301 0.0430318843 0.1210187301 0.0098965577 0.0905850000 261815740 0 1328947200 0.0400080718 0.0553240143 0.1422633380 137 5.4400000000 0.1223184094 0.0436106180 0.1223184094 0.0098920588 0.0837050000 261816994 0 1329455104 0.0406757034 0.0558346473 0.1437046230 138 5.4800000000 0.1229731515 0.0441857088 0.1229731515 0.0098749365 0.0839150000 261818248 0 1330089984 0.0416954719 0.0568702780 0.1457170844 139 5.5200000000 0.1248186156 0.0447658017 0.1248186156 0.0098568483 0.3612040000 274135546 0 1342914560 0.0414715707 0.0574583113 0.1463721246 140 5.5600000000 0.1267349720 0.0453512958 0.1267349720 0.0098461879 0.0647880000 277794648 0 1346977792 0.0409281179 0.0580318980 0.1471299231 141 5.6000000000 0.1283855736 0.0459401914 0.1283855736 0.0098934530 0.1139430000 280987998 0 1350660096 0.0412935577 0.0588933267 0.1500512064 142 5.6400000000 0.1283562183 0.0465205859 0.1283855736 0.0099011389 0.0833040000 280989252 0 1351421952 0.0419424213 0.0588113442 0.1522491425 143 5.6800000000 0.1297144592 0.0471023612 0.1297144592 0.0098925097 0.0828550000 280990506 0 1352056832 0.0414702445 0.0589409024 0.1529375464 144 5.7200000000 0.1259825081 0.0476501400 0.1297144592 0.0099229188 0.0737710000 280991760 0 1352564736 0.0445289165 0.0581766926 0.1583346725 145 5.7600000000 0.1295636296 0.0482150607 0.1297144592 0.0099259281 0.0828910000 280993014 0 1353072640 0.0435514897 0.0616410412 0.1580722183 146 5.8000000000 0.1314194947 0.0487849540 0.1314194947 0.0098982526 0.4056810000 293297696 0 1365897216 0.0411525555 0.0603673793 0.1571194828 147 5.8400000000 0.1325757951 0.0493549598 0.1325757951 0.0098717787 0.0660040000 296956798 0 1369960448 0.0400879160 0.0586130433 0.1568541080 148 5.8800000000 0.1332012564 0.0499214888 0.1332012564 0.0098523647 0.0606430000 300150148 0 1373642752 0.0402144082 0.0588656925 0.1579691619 149 5.9200000000 0.1335851550 0.0504829899 0.1335851550 0.0098375304 0.0701840000 300151402 0 1374404608 0.0399301015 0.0596044436 0.1597134620 150 5.9600000000 0.1334509999 0.0510361100 0.1335851550 0.0098114618 0.0731780000 300152656 0 1374912512 0.0397400744 0.0583404079 0.1611984670 151 6.0000000000 0.1356288046 0.0515963265 0.1356288046 0.0097879791 0.0638650000 300153910 0 1375547392 0.0382255912 0.0586123541 0.1607371122 152 6.0400000000 0.1325344443 0.0521288141 0.1356288046 0.0098028695 0.0692180000 300155164 0 1376055296 0.0405112989 0.0588402040 0.1661725938 153 6.0800000000 0.1373573244 0.0526858632 0.1373573244 0.0097797360 0.3823710000 312460110 0 1388879872 0.0372106284 0.0593784340 0.1635056287 154 6.1200000000 0.1376804560 0.0532377761 0.1376804560 0.0097611734 0.0593320000 316119212 0 1392816128 0.0378606319 0.0588662922 0.1648929715 155 6.1600000000 0.1386884004 0.0537890705 0.1386884004 0.0097373561 0.0623810000 319312562 0 1396625408 0.0367580503 0.0589410253 0.1658684313 156 6.2000000000 0.1355416775 0.0543131257 0.1386884004 0.0098342152 0.0839930000 319313816 0 1397387264 0.0379505530 0.0616694987 0.1757048815 157 6.2400000000 0.1357711107 0.0548319663 0.1386884004 0.0098107019 0.0746510000 319315070 0 1397895168 0.0373700373 0.0611570515 0.1774416864 158 6.2800000000 0.1363890469 0.0553481504 0.1386884004 0.0097915371 0.0624370000 319316324 0 1398403072 0.0369258448 0.0614514984 0.1791645736 159 6.3200000000 0.1403419077 0.0558827023 0.1403419077 0.0097819621 0.0627790000 319317578 0 1398910976 0.0342483446 0.0613419153 0.1766213626 160 6.3600000000 0.1412678361 0.0564163594 0.1412678361 0.0097596958 0.3593530000 331623200 0 1411735552 0.0334428884 0.0613730513 0.1776369810 161 6.4000000000 0.1435785443 0.0569577394 0.1435785443 0.0097539506 0.0482730000 335282302 0 1415798784 0.0315038078 0.0619031340 0.1772503704 162 6.4400000000 0.1450837851 0.0575017274 0.1450837851 0.0097602941 0.0499200000 338475652 0 1419481088 0.0300276242 0.0621912032 0.1776344031 163 6.4800000000 0.1461339742 0.0580454835 0.1461339742 0.0097459074 0.0531650000 338476906 0 1420242944 0.0286714621 0.0611637756 0.1775549650 164 6.5200000000 0.1476803273 0.0585920374 0.1476803273 0.0097256585 0.0577070000 338478160 0 1420877824 0.0270548500 0.0611103363 0.1776790470 165 6.5600000000 0.1489879340 0.0591398913 0.1489879340 0.0097153261 0.0546250000 338479414 0 1421385728 0.0256017111 0.0613705851 0.1784162670 166 6.6000000000 0.1498707235 0.0596864626 0.1498707235 0.0096941155 0.0521120000 338480668 0 1421893632 0.0246247463 0.0611690581 0.1791311651 167 6.6400000000 0.1510829926 0.0602337472 0.1510829926 0.0096728709 0.2713800000 350808314 0 1434845184 0.0232563838 0.0608986355 0.1795968860 168 6.6800000000 0.1572183967 0.0608110368 0.1572183967 0.0096514837 0.0458340000 354467416 0 1438908416 0.0205251146 0.0608509779 0.1744215190 169 6.7200000000 0.1586247683 0.0613898163 0.1586247683 0.0096340499 0.0442350000 357660766 0 1442590720 0.0196212791 0.0611864738 0.1745749861 170 6.7600000000 0.1597507596 0.0619684101 0.1597507596 0.0096145499 0.0499910000 357662020 0 1443352576 0.0179353543 0.0614091307 0.1752610952 171 6.8000000000 0.1618756652 0.0625526630 0.1618756652 0.0096019659 0.0523190000 357663274 0 1443860480 0.0169119723 0.0625942871 0.1753533632 172 6.8400000000 0.1614844948 0.0631278481 0.1618756652 0.0095772590 0.0510350000 357664528 0 1444495360 0.0162586756 0.0601849593 0.1758771092 173 6.8800000000 0.1627993435 0.0637039839 0.1627993435 0.0095577862 0.0506310000 357665782 0 1445003264 0.0145501094 0.0604024306 0.1757476777 174 6.9200000000 0.1639376581 0.0642800395 0.1639376581 0.0095330533 0.2098730000 375095384 0 1451732992 0.0145501094 0.0604024306 0.1757476777 175 6.9600000000 0.1648682803 0.0648548294 0.1648682803 0.0095098406 0.0281390000 378442378 0 1455669248 0.0125759728 0.0626510158 0.1773484647 176 7.0000000000 0.1656097770 0.0654273007 0.1656097770 0.0094858430 0.0273770000 378520464 0 1456431104 0.0125759728 0.0626510158 0.1773484647 177 7.0400000000 0.1666422784 0.0659991368 0.1666422784 0.0094617103 0.0240370000 378598550 0 1457065984 0.0125759728 0.0626510158 0.1773484647 178 7.0800000000 0.1675184667 0.0665694701 0.1675184667 0.0094358576 0.0336230000 378676636 0 1457700864 0.0125759728 0.0626510158 0.1773484647 179 7.1200000000 0.1683619767 0.0671381433 0.1683619767 0.0094097288 0.0344380000 378754722 0 1458335744 0.0125759728 0.0626510158 0.1773484647 180 7.1600000000 0.1693258137 0.0677058526 0.1693258137 0.0093848617 0.0335790000 378832808 0 1458843648 0.0125759728 0.0626510158 0.1773484647 181 7.2000000000 0.1698703617 0.0682702974 0.1698703617 0.0093602266 0.0319180000 378910894 0 1459478528 0.0125759728 0.0626510158 0.1773484647 182 7.2400000000 0.1703804582 0.0688313422 0.1703804582 0.0093355383 0.0393630000 378988980 0 1460113408 0.0125759728 0.0626510158 0.1773484647 183 7.2800000000 0.1706613898 0.0693877906 0.1706613898 0.0093119868 0.0439600000 379067066 0 1460748288 0.0125759728 0.0626510158 0.1773484647 184 7.3200000000 0.1713749021 0.0699420684 0.1713749021 0.0092913902 0.0333170000 379145152 0 1461383168 0.0125759728 0.0626510158 0.1773484647 185 7.3600000000 0.7667975426 0.0737088547 0.7667975426 0.0481681349 0.0620990000 379223238 0 1462018048 0.0134244384 0.5627515316 -0.1702681184 186 7.4000000000 0.8333530426 0.0777929632 0.8333530426 0.0483099193 0.0302480000 379301428 0 1462652928 0.0614960417 0.5953130126 -0.2304210216 187 7.4400000000 0.9332492948 0.0823675960 0.9332492948 0.0489462137 0.0398990000 382648526 0 1466335232 0.1250038892 0.6314059496 -0.3278312087 188 7.4800000000 0.9854480624 0.0871712155 0.9854480624 0.0496296130 0.0487320000 385995624 0 1470271488 0.1736255139 0.5994563699 -0.4168756902 189 7.5200000000 0.9773697257 0.0918812606 0.9854480624 0.0518454651 0.0350310000 389342722 0 1474207744 0.3022083938 0.4841976762 -0.4515588880 190 7.5600000000 0.9176164865 0.0962272354 0.9854480624 0.0534753945 0.0464520000 392691476 0 1478017024 0.4050713778 0.3487513959 -0.4074072242 191 7.6000000000 0.9210659266 0.1005457626 0.9854480624 0.0534072181 0.0346960000 396038574 0 1481953280 0.3507905304 0.3519909978 -0.4350549281 192 7.6400000000 0.9653490782 0.1050499465 0.9854480624 0.0536452864 0.0374220000 399385672 0 1485762560 0.3852492571 0.3074455559 -0.4897102714 193 7.6800000000 0.9929519296 0.1096504750 0.9929519296 0.0536483130 0.0393080000 402732770 0 1489698816 0.3893646002 0.3721213341 -0.4906646311 194 7.7200000000 1.0447623730 0.1144706394 1.0447623730 0.0536928049 0.0380070000 406079868 0 1493762048 0.4570563436 0.3751727045 -0.5174375772 195 7.7600000000 1.1101130247 0.1195764978 1.1101130247 0.0548653865 0.0409980000 409426966 0 1497571328 0.5047020912 0.2694006860 -0.6097202301 196 7.8000000000 1.1109585762 0.1246345696 1.1109585762 0.0547253549 0.0416650000 412773960 0 1501507584 0.5047020912 0.2694006860 -0.6097202301 197 7.8400000000 1.1117534637 0.1296453254 1.1117534637 0.0545860425 0.0339570000 412852046 0 1502269440 0.5047020912 0.2694006860 -0.6097202301 198 7.8800000000 1.1847978830 0.1349743787 1.1847978830 0.0561800614 0.0376230000 412930236 0 1502904320 0.5499780774 0.1289879829 -0.7005844712 199 7.9200000000 1.1850905418 0.1402513444 1.1850905418 0.0560386271 0.0428820000 416277230 0 1506586624 0.5499780774 0.1289879829 -0.7005844712 200 7.9600000000 1.1857656240 0.1454789158 1.1857656240 0.0558979499 0.0312340000 416355316 0 1507475456 0.5499780774 0.1289879829 -0.7005844712 201 8.0000000000 1.1864539385 0.1506578960 1.1864539385 0.0557581712 0.0313780000 416433402 0 1508110336 0.5499780774 0.1289879829 -0.7005844712 202 8.0400000000 1.3068032265 0.1563813877 1.3068032265 0.0613333321 0.0337970000 416511592 0 1508618240 0.8692589998 -0.1027513742 -0.6373730302 203 8.0800000000 1.3070225716 0.1620495709 1.3070225716 0.0611816013 0.0324250000 419858586 0 1512427520 0.8692589998 -0.1027513742 -0.6373730302 204 8.1200000000 1.3073813915 0.1676639426 1.3073813915 0.0610310413 0.0381760000 419936672 0 1513189376 0.8692589998 -0.1027513742 -0.6373730302 205 8.1600000000 1.3077808619 0.1732254885 1.3077808619 0.0608816578 0.0338950000 420014758 0 1513824256 0.8692589998 -0.1027513742 -0.6373730302 206 8.1999999990 1.6669752598 0.1804767010 1.6669752598 0.0660927824 0.0377890000 420092948 0 1514459136 1.1015284061 -0.1741067171 -0.9053421021 207 8.2400000000 1.6671833992 0.1876588589 1.6671833992 0.0659330932 0.0361950000 423439942 0 1518141440 1.1015284061 -0.1741067171 -0.9053421021 208 8.2799999990 2.1803345680 0.1972390306 2.1803345680 0.0724188059 0.0312480000 423518132 0 1518903296 1.1169028282 0.0062066759 -1.5314038992 209 8.3200000000 2.1803302765 0.2067275055 2.1803345680 0.0722451629 0.0302640000 426865126 0 1522712576 1.1169028282 0.0062066759 -1.5314038992 210 8.3599999990 2.6194758415 0.2182167833 2.6194758415 0.0920312176 0.0290840000 426943316 0 1523474432 0.8140007257 -0.9239175916 -1.9766316414 211 8.4000000000 2.6194043159 0.2295968190 2.6194758415 0.0918118489 0.0333030000 430290310 0 1527156736 0.8140007257 -0.9239175916 -1.9766316414 212 8.4399999990 2.6190547943 0.2408678472 2.6194758415 0.0915941319 0.0292940000 430368396 0 1527918592 0.8140007257 -0.9239175916 -1.9766316414 213 8.4800000000 2.6187820435 0.2520317636 2.6194758415 0.0913781178 0.0307300000 430446482 0 1528553472 0.8140007257 -0.9239175916 -1.9766316414 214 8.5200000000 2.6183445454 0.2630892999 2.6194758415 0.0911634964 0.0279420000 430524568 0 1529188352 0.8140007257 -0.9239175916 -1.9766316414 215 8.5600000000 2.6181354523 0.2740430030 2.6194758415 0.0909503196 0.0293530000 430602654 0 1529823232 0.8140007257 -0.9239175916 -1.9766316414 216 8.6000000000 2.7692706585 0.2855949829 2.7692706585 0.0940189840 0.0264000000 430680844 0 1530458112 1.7024410963 -0.6211200953 -1.7642440796 217 8.6400000000 2.7690930367 0.2970396744 2.7692706585 0.0938015198 0.0322180000 434027838 0 1534267392 1.7024410963 -0.6211200953 -1.7642440796 218 8.6800000000 2.7193231583 0.3081510665 2.7692706585 0.1018957657 0.0283130000 434106028 0 1535029248 1.6921172142 -1.9717653990 -0.5314866304 219 8.7200000000 2.9342343807 0.3201423145 2.9342343807 0.1061288650 0.0342830000 437453126 0 1538711552 1.4612048864 -2.5723168850 0.3228343725 220 8.7600000000 3.6244530678 0.3351619088 3.6244530678 0.1160767249 0.0305520000 440800736 0 1542647808 1.6488600969 -3.1909923553 -0.2923161089 221 8.8000000000 3.8354263306 0.3510002094 3.8354263306 0.1159673029 0.0348310000 444147834 0 1546457088 2.2668535709 -2.7240564823 -1.1779012680 222 8.8400000000 3.8355894089 0.3666965571 3.8355894089 0.1157056022 0.0264200000 447494828 0 1550393344 2.2668535709 -2.7240564823 -1.1779012680 223 8.8800000000 3.8358795643 0.3822534316 3.8358795643 0.1154457275 0.0290740000 447572914 0 1551155200 2.2668535709 -2.7240564823 -1.1779012680 224 8.9200000000 5.4047322273 0.4046752119 5.4047322273 0.1376163047 0.0255350000 447651104 0 1551790080 4.5366225243 -1.5760291815 -2.1700842381 225 8.9600000000 5.4048027992 0.4268980012 5.4048027992 0.1373093343 0.0201680000 449692474 0 1554202624 4.5366225243 -1.5760291815 -2.1700842381 226 9.0000000000 5.4047741890 0.4489240020 5.4048027992 0.1370046526 0.0202970000 449693748 0 1554964480 4.5366225243 -1.5760291815 -2.1700842381 227 9.0400000000 5.4048500061 0.4707562752 5.4048500061 0.1367017972 0.0198080000 449771834 0 1555599360 4.5366225243 -1.5760291815 -2.1700842381 228 9.0800000000 5.4049005508 0.4923972588 5.4049005508 0.1364012207 0.0257480000 451078732 0 1557377024 4.5366225243 -1.5760291815 -2.1700842381 229 9.1200000000 7.7883353233 0.5242572504 7.7883353233 0.1807242135 0.0252430000 451156922 0 1558011904 7.0789098740 1.1386873722 -2.7201826572 230 9.1600000000 4.9559421539 0.5435254456 7.7883353233 0.3419711981 0.0335470000 454504020 0 1561694208 3.3699328899 2.4834039211 2.9865684509 231 9.2000000000 3.6739246845 0.5570769575 7.7883353233 0.3520814546 0.0335800000 457851118 0 1565630464 3.2636406422 1.4062819481 1.2754521370 232 9.2400000000 3.3271827698 0.5690170687 7.7883353233 0.3529051996 0.0305130000 461198216 0 1569566720 3.0589253902 1.2903425694 0.0900879577 233 9.2800000000 3.8440098763 0.5830728319 7.7883353233 0.3539976810 0.0255810000 464545314 0 1573376000 3.3866596222 1.7392972708 0.8662852049 234 9.3200000000 3.5470762253 0.5957395130 7.7883353233 0.3540426047 0.0274610000 467892412 0 1577439232 2.9754927158 1.7238324881 1.1989424229 235 9.3600000000 3.5286345482 0.6082199174 7.7883353233 0.3532927702 0.0296490000 471239510 0 1581375488 3.0520753860 1.6004683971 1.0868453979 236 9.4000000000 3.5675969124 0.6207596505 7.7883353233 0.3525492852 0.0309030000 474586608 0 1585184768 3.0825812817 1.6228830814 1.0951585770 237 9.4400000000 3.3985877037 0.6324804439 7.7883353233 0.3521410928 0.0296090000 477933706 0 1589121024 2.8213903904 1.6759728193 1.2052025795 238 9.4800000000 3.6989598274 0.6453648111 7.7883353233 0.3523757017 0.0332450000 481280804 0 1593057280 2.8747045994 1.7300782204 1.8784948587 239 9.5200000000 3.6221003532 0.6578197715 7.7883353233 0.3516466396 0.0295050000 484627902 0 1596866560 2.9791004658 1.5283113718 1.7015730143 240 9.5600000000 3.5470609665 0.6698582765 7.7883353233 0.3510520085 0.0327460000 487975000 0 1600802816 2.7122519016 1.5480382442 2.0007443428 241 9.6000000000 3.6032299995 0.6820299434 7.7883353233 0.3503691762 0.0300700000 491322098 0 1604739072 2.7427160740 1.5427988768 2.0723571777 242 9.6400000000 3.5496869087 0.6938797656 7.7883353233 0.3496560515 0.0348020000 494669196 0 1608548352 2.7634325027 1.4992830753 1.9627922773 243 9.6800000000 3.5391914845 0.7055888673 7.7883353233 0.3489536174 0.0305750000 498016294 0 1612484608 2.6957750320 1.5043470860 2.0435721874 244 9.7200000000 3.5364172459 0.7171906230 7.7883353233 0.3482546343 0.0337460000 501363392 0 1616293888 2.8639829159 1.4112508297 1.8298811913 245 9.7600000000 3.6053798199 0.7289791503 7.7883353233 0.3477416632 0.0300070000 504710490 0 1620230144 2.6856074333 1.5418841839 2.1550042629 246 9.8000000000 3.7957258224 0.7414456002 7.7883353233 0.3473560766 0.0336560000 508057588 0 1624039424 3.0389938354 1.4842326641 2.0277504921 247 9.8400000000 3.6859827042 0.7533668030 7.7883353233 0.3467501027 0.0292300000 511404686 0 1627975680 3.0009782314 1.4854048491 1.8415893316 248 9.8800000000 3.7952425480 0.7656324310 7.7883353233 0.3461243866 0.0301470000 514751784 0 1631784960 3.2093694210 1.5254023075 1.6270905733 249 9.9200000000 3.7145249844 0.7774753730 7.7883353233 0.3456254774 0.0254460000 518098882 0 1635721216 3.3677861691 1.4464551210 0.8637861609 250 9.9600000000 4.1266312599 0.7908719966 7.7883353233 0.3460667891 0.0274790000 521445980 0 1639530496 3.8134288788 1.4765692949 0.7953075171 251 10.0000000000 4.2904686928 0.8048146129 7.7883353233 0.3468666498 0.0250910000 524796750 0 1643466752 3.4037940502 1.7066603899 2.2696385384 252 10.0400000000 4.3856921196 0.8190244443 7.7883353233 0.3472509119 0.0292380000 528143848 0 1647403008 2.2822258472 1.7019551992 3.6370861530 253 10.0800000000 3.8263583183 0.8309111394 7.7883353233 0.3495978690 0.0291370000 531490946 0 1651339264 3.0989513397 1.5753566027 1.8837918043 254 10.1200000000 3.3348910809 0.8407693282 7.7883353233 0.3532062897 0.0301120000 534838044 0 1655275520 3.0557515621 1.1455591917 -0.3277421296 255 10.1600000000 4.2979612350 0.8543269435 7.7883353233 0.3570708116 0.0268380000 538185142 0 1659084800 3.6208796501 2.2110419273 0.9284160733 256 10.2000000000 5.0723304749 0.8708035198 7.7883353233 0.3599852168 0.0326520000 541532240 0 1663021056 3.3726744652 3.0295383930 2.5615091324 257 10.2400000000 4.2966761589 0.8841337635 7.7883353233 0.3638066857 0.0326030000 544879338 0 1666957312 3.7592422962 2.0375933647 0.0106431171 258 10.2800000000 5.4336066246 0.9017673792 7.7883353233 0.3696066326 0.0366500000 548268420 0 1670766592 4.1792869568 3.1896615028 1.6364142895 259 10.3200000000 4.4900784492 0.9156218621 7.7883353233 0.3725602871 0.0313350000 551615518 0 1674702848 3.8410317898 2.2255825996 0.8922612071 260 10.3600000000 4.9290900230 0.9310582781 7.7883353233 0.3728603187 0.0352140000 554962616 0 1678512128 3.6981713772 2.7854666710 1.9610576630 261 10.4000000000 4.0787339211 0.9431183381 7.7883353233 0.3768375396 0.0318900000 558309714 0 1682448384 3.5339159966 1.9318739176 -0.2682833672 262 10.4400000000 5.0777196884 0.9588992593 7.7883353233 0.3816576027 0.0368150000 561656812 0 1686257664 4.2390708923 2.6742098331 1.0316517353 263 10.4800000000 4.0865793228 0.9707915789 7.7883353233 0.3865790462 0.0306540000 565003910 0 1690193920 3.1470172405 2.0930757523 1.8170827627 264 10.5200000000 3.3076159954 0.9796431865 7.7883353233 0.3893569162 0.0297520000 568351008 0 1694130176 2.8862426281 1.5789922476 0.4549001753 265 10.5600000000 4.0766839981 0.9913301330 7.7883353233 0.3940617739 0.0267370000 571698106 0 1697939456 2.5360174179 1.9762877226 2.7806482315 266 10.6000000000 3.8772203922 1.0021793445 7.7883353233 0.3935310225 0.0303180000 575045204 0 1701875712 2.1357069016 1.7245790958 3.0137693882 267 10.6400000000 3.9083068371 1.0130637171 7.7883353233 0.3928209952 0.0388430000 578392302 0 1705684992 2.3962266445 1.8358653784 2.7530572414 268 10.6800000000 3.9052066803 1.0238552953 7.7883353233 0.3920887976 0.0363750000 581739400 0 1709621248 2.3764224052 1.8485565186 2.7558274269 269 10.7200000000 4.3363695145 1.0361694746 7.7883353233 0.3925066274 0.0289150000 585086498 0 1713430528 2.5768601894 1.8944219351 3.1955401897 270 10.7600000000 4.3620638847 1.0484876020 7.7883353233 0.3918416908 0.0311890000 588433596 0 1717366784 2.3210177422 1.7484487295 3.5211803913 271 10.8000000000 4.3354768753 1.0606167138 7.7883353233 0.3912314410 0.0291560000 591780694 0 1721176064 2.8215606213 1.9297726154 2.9255344868 272 10.8400000000 5.1260390282 1.0755631193 7.7883353233 0.3942926400 0.0370300000 595127792 0 1725112320 2.9557251930 1.9931476116 3.9445667267 273 10.8800000000 5.1934132576 1.0906468195 7.7883353233 0.3936568545 0.0308480000 598474890 0 1729048576 2.6696608067 1.9484416246 4.2680110931 274 10.9200000000 5.4922728539 1.1067111481 7.7883353233 0.3932986439 0.0370950000 601821988 0 1732984832 3.7463629246 2.3906872272 3.4761059284 275 10.9600000000 6.2651214600 1.1254690037 7.7883353233 0.3957137902 0.0305490000 605169086 0 1736921088 5.1587395668 2.8496594429 2.3421468735 276 11.0000000000 6.2662925720 1.1440951761 7.7883353233 0.3949937196 0.0324680000 608516080 0 1740730368 5.1587395668 2.8496594429 2.3421468735 277 11.0400000000 6.2674617767 1.1625910844 7.7883353233 0.3942776181 0.0283120000 608594166 0 1741492224 5.1587395668 2.8496594429 2.3421468735 278 11.0800000000 6.2686018944 1.1809580297 7.7883353233 0.3935654594 0.0243580000 608672252 0 1742127104 5.1587395668 2.8496594429 2.3421468735 279 11.1200000000 6.2697234154 1.1991973322 7.7883353233 0.3928570647 0.0251130000 608750338 0 1742761984 5.1587395668 2.8496594429 2.3421468735 280 11.1600000000 6.2707080841 1.2173098706 7.7883353233 0.3921524146 0.0181210000 608751628 0 1743396864 5.1587395668 2.8496594429 2.3421468735 281 11.2000000000 6.2717452049 1.2352971850 7.7883353233 0.3914515587 0.0177010000 608752902 0 1743904768 5.1587395668 2.8496594429 2.3421468735 282 11.2400000000 6.2728514671 1.2531608526 7.7883353233 0.3907544416 0.0150570000 608754176 0 1744539648 5.1587395668 2.8496594429 2.3421468735 283 11.2800000000 6.2739739418 1.2709022416 7.7883353233 0.3900610188 0.0178040000 608755450 0 1745047552 5.1587395668 2.8496594429 2.3421468735 284 11.3200000000 7.2990255356 1.2921280279 7.7883353233 0.4182270000 0.0308790000 608833640 0 1745555456 -5.2510418892 -4.7411394119 -1.6010106802 285 11.3600000000 7.4396929741 1.3136984312 7.7883353233 0.4179854361 0.0372360000 610644714 0 1747714048 -5.6950378418 -4.1863136292 -2.1288154125 286 11.4000000000 7.4174003601 1.3350400463 7.7883353233 0.4173562105 0.0306590000 613991812 0 1751650304 -5.1001367569 -5.0781569481 -1.6013641357 287 11.4400000000 7.3969392776 1.3561616464 7.7883353233 0.4166495691 0.0411740000 617338910 0 1755459584 -5.0945086479 -5.0522351265 -1.6107586622 288 11.4800000000 7.6764783859 1.3781071907 7.7883353233 0.4164863692 0.0344740000 620686008 0 1759268864 -6.3345704079 -3.7551517487 -2.0082464218 289 11.5200000000 6.7306227684 1.3966280058 7.7883353233 0.4186110305 0.0411320000 624033106 0 1763205120 -4.0339078903 -4.7730951309 -2.2873330116 290 11.5600000000 6.0817723274 1.4127836759 7.7883353233 0.4194437103 0.0286750000 627380204 0 1767141376 -3.2375452518 -4.7851686478 -1.6850934029 291 11.6000000000 6.6711320877 1.4308536017 7.7883353233 0.4205704977 0.0309490000 630727302 0 1770950656 -2.7722992897 -5.7167878151 -1.8034375906 292 11.6400000000 6.1317129135 1.4469524350 7.7883353233 0.4212211287 0.0367960000 634074400 0 1774886912 -1.8440457582 -5.3519229889 -2.1131715775 293 11.6800000000 6.2449235916 1.4633277632 7.7883353233 0.4205980583 0.0259970000 637421498 0 1778696192 -1.4780815840 -5.6568431854 -1.9441287518 294 11.7200000000 6.0562520027 1.4789499544 7.7883353233 0.4200290453 0.0260680000 640768596 0 1782632448 -1.1847572327 -5.5314927101 -1.9096994400 295 11.7600000000 5.8669981956 1.4938246942 7.7883353233 0.4194364095 0.0290740000 644115694 0 1786568704 -0.9774264693 -5.4657049179 -1.6380074024 296 11.8000000000 4.5180048943 1.5040415192 7.7883353233 0.4288485533 0.0280290000 647462792 0 1786458112 1.0345913172 -3.9035835266 -1.7286231518 297 11.8400000000 4.3681697845 1.5136850488 7.7883353233 0.4283525769 0.0312060000 650809890 0 1786089472 1.4659985304 -3.5686552525 -1.7426160574 298 11.8800000000 3.8737156391 1.5216046145 7.7883353233 0.4288027568 0.0290430000 654158524 0 1787965440 1.5985637903 -3.0292224884 -1.4939649105 299 11.9200000000 3.5786824226 1.5284844734 7.7883353233 0.4289042731 0.0294570000 657505622 0 1787711488 2.2880816460 -2.3269743919 -1.1068581343 300 11.9600000000 3.9951758385 1.5367067779 7.7883353233 0.4292178254 0.0272440000 660852720 0 1787076608 2.4682905674 -2.8356733322 -0.9585337639 301 12.0000000000 3.8767099380 1.5444808748 7.7883353233 0.4285692315 0.0286450000 664199818 0 1786695680 2.4338889122 -2.7220366001 -0.9008374810 302 12.0400000000 3.8803138733 1.5522154212 7.7883353233 0.4278598552 0.0254360000 667546916 0 1787838464 2.4413263798 -2.7166028023 -0.9048494697 303 12.0800000000 3.7584559917 1.5594967432 7.7883353233 0.4272280980 0.0280020000 670894014 0 1787965440 2.4077539444 -2.5961639881 -0.8468504548 304 12.1200000000 3.6376066208 1.5663326309 7.7883353233 0.4268369964 0.0251370000 674241112 0 1787600896 2.8260874748 -2.0239841938 -0.5845021605 305 12.1600000000 3.6525981426 1.5731728457 7.7883353233 0.4261363540 0.0258360000 677588210 0 1787346944 2.8353993893 -2.0299885273 -0.5948269367 306 12.2000000000 4.3726854324 1.5823215797 7.7883353233 0.4275356215 0.0501150000 680935308 0 1786839040 3.5535860062 -2.3483812809 -0.3457204998 307 12.2400000000 4.0429463387 1.5903366440 7.7883353233 0.4271922027 0.0246580000 684282406 0 1786204160 3.0822706223 -2.3563926220 -0.6145302653 308 12.2800000000 4.5421514511 1.5999204583 7.7883353233 0.4277848838 0.0263050000 687629504 0 1787838464 3.3453919888 -2.9033863544 -0.3628259897 309 12.3200000000 4.5436744690 1.6094471704 7.7883353233 0.4270898946 0.0244980000 690976498 0 1787457536 3.3453919888 -2.9033863544 -0.3628259897 310 12.3600000000 4.5455675125 1.6189185263 7.7883353233 0.4263982933 0.0306590000 692590608 0 1787219968 3.3453919888 -2.9033863544 -0.3628259897 311 12.4000000000 4.5476140976 1.6283355539 7.7883353233 0.4257100282 0.0220060000 692668694 0 1787727872 3.3453919888 -2.9033863544 -0.3628259897 312 12.4400000000 4.5490245819 1.6376967366 7.7883353233 0.4250250733 0.0249950000 692746780 0 1786458112 3.3453919888 -2.9033863544 -0.3628259897 313 12.4800000000 4.5505285263 1.6470029085 7.7883353233 0.4243434703 0.0173310000 692748054 0 1787092992 3.3453919888 -2.9033863544 -0.3628259897 314 12.5200000000 4.5522885323 1.6562554105 7.7883353233 0.4236651783 0.0265440000 692826140 0 1787584512 3.3453919888 -2.9033863544 -0.3628259897 315 12.5600000000 4.5533251762 1.6654524574 7.7883353233 0.4229901019 0.0176340000 692827414 0 1785966592 3.3453919888 -2.9033863544 -0.3628259897 316 12.6000000000 4.5546793938 1.6745955806 7.7883353233 0.4223182258 0.0243010000 692905500 0 1786585088 3.3453919888 -2.9033863544 -0.3628259897 317 12.6400000000 4.5555596352 1.6836837953 7.7883353233 0.4216495164 0.0193500000 692906774 0 1787219968 3.3453919888 -2.9033863544 -0.3628259897 318 12.6800000000 4.5565848351 1.6927180753 7.7883353233 0.4209840718 0.0309510000 692984860 0 1785466880 3.3453919888 -2.9033863544 -0.3628259897 319 12.7200000000 4.5577797890 1.7016994599 7.7883353233 0.4203217390 0.0266610000 693062946 0 1786093568 3.3453919888 -2.9033863544 -0.3628259897 320 12.7600000000 4.5590672493 1.7106287343 7.7883353233 0.4196624920 0.0250450000 693141032 0 1786712064 3.3453919888 -2.9033863544 -0.3628259897 321 12.8000000000 4.5596709251 1.7195042551 7.7883353233 0.4190063175 0.0337120000 693219118 0 1785208832 3.3453919888 -2.9033863544 -0.3628259897 322 12.8400000000 4.5599603653 1.7283255474 7.7883353233 0.4183532213 0.0237230000 693297204 0 1785839616 3.3453919888 -2.9033863544 -0.3628259897 323 12.8800000000 4.5609707832 1.7370953469 7.7883353233 0.4177032422 0.0263790000 693375290 0 1786474496 3.3453919888 -2.9033863544 -0.3628259897 324 12.9200000000 4.5617856979 1.7458135270 7.7883353233 0.4170562074 0.0227220000 693453376 0 1786966016 3.3453919888 -2.9033863544 -0.3628259897 325 12.9600000000 4.5622963905 1.7544796281 7.7883353233 0.4164121357 0.0135200000 693454650 0 1785176064 3.3453919888 -2.9033863544 -0.3628259897 326 13.0000000000 4.5625581741 1.7630933660 7.7883353233 0.4157710458 0.0222060000 693532736 0 1785298944 3.3453919888 -2.9033863544 -0.3628259897 327 13.0400000000 4.5633354187 1.7716567973 7.7883353233 0.4151329187 0.0230950000 693610822 0 1785933824 3.3453919888 -2.9033863544 -0.3628259897 328 13.0800000000 4.5639357567 1.7801698429 7.7883353233 0.4144977083 0.0212960000 693688908 0 1786568704 3.3453919888 -2.9033863544 -0.3628259897 329 13.1200000000 4.5644197464 1.7886326086 7.7883353233 0.4138654038 0.0194300000 693690182 0 1785090048 3.3453919888 -2.9033863544 -0.3628259897 330 13.1600000000 4.5648322105 1.7970453347 7.7883353233 0.4132359965 0.0123840000 693691456 0 1785315328 3.3453919888 -2.9033863544 -0.3628259897 331 13.2000000000 4.5653634071 1.8054088334 7.7883353233 0.4126094419 0.0175680000 693692730 0 1785823232 3.3453919888 -2.9033863544 -0.3628259897 332 13.2400000000 4.5657005310 1.8137229650 7.7883353233 0.4119857211 0.0173920000 693694004 0 1786331136 3.3453919888 -2.9033863544 -0.3628259897 333 13.2800000000 4.5662798882 1.8219889017 7.7883353233 0.4113648177 0.0133240000 693695278 0 1786712064 3.3453919888 -2.9033863544 -0.3628259897 334 13.3200000000 4.5669283867 1.8302072834 7.7883353233 0.4107466918 0.0190280000 693696552 0 1785438208 3.3453919888 -2.9033863544 -0.3628259897 335 13.3600000000 4.5665979385 1.8383756137 7.7883353233 0.4101313620 0.0234850000 693697826 0 1785933824 3.3453919888 -2.9033863544 -0.3628259897 336 13.4000000000 4.5672230721 1.8464971835 7.7883353233 0.4095188764 0.0158110000 693699100 0 1786441728 3.3453919888 -2.9033863544 -0.3628259897 337 13.4400000000 4.5681533813 1.8545733147 7.7883353233 0.4089090557 0.0236960000 693700374 0 1786949632 3.3453919888 -2.9033863544 -0.3628259897 338 13.4800000000 4.5686874390 1.8626032381 7.7883353233 0.4083019357 0.0203860000 693701648 0 1785565184 3.3453919888 -2.9033863544 -0.3628259897 339 13.5200000000 4.5696883202 1.8705887398 7.7883353233 0.4076975223 0.0200290000 693702922 0 1785806848 3.3453919888 -2.9033863544 -0.3628259897 340 13.5600000000 4.5707421303 1.8785303674 7.7883353233 0.4070957761 0.0219320000 693704196 0 1786314752 3.3453919888 -2.9033863544 -0.3628259897 341 13.6000000000 4.5715937614 1.8864279141 7.7883353233 0.4064967006 0.0147930000 693705470 0 1786822656 3.3453919888 -2.9033863544 -0.3628259897 342 13.6400000000 4.5721063614 1.8942807750 7.7883353233 0.4059002482 0.0194940000 693706744 0 1787076608 3.3453919888 -2.9033863544 -0.3628259897 343 13.6800000000 4.5722274780 1.9020881998 7.7883353233 0.4053064058 0.0193700000 693708018 0 1785819136 3.3453919888 -2.9033863544 -0.3628259897 344 13.7200000000 4.5727005005 1.9098516077 7.7883353233 0.4047151538 0.0153670000 693709292 0 1786060800 3.3453919888 -2.9033863544 -0.3628259897 345 13.7600000000 4.5733604431 1.9175719231 7.7883353233 0.4041264904 0.0234850000 693710566 0 1786568704 3.3453919888 -2.9033863544 -0.3628259897 346 13.8000000000 4.5738692284 1.9252490830 7.7883353233 0.4035403844 0.0196910000 693711840 0 1787076608 3.3453919888 -2.9033863544 -0.3628259897 347 13.8400000000 4.5741572380 1.9328828240 7.7883353233 0.4029568456 0.0215240000 693713114 0 1785442304 3.3453919888 -2.9033863544 -0.3628259897 348 13.8800000000 4.5743579865 1.9404732699 7.7883353233 0.4023758089 0.0250610000 693714388 0 1785950208 3.3453919888 -2.9033863544 -0.3628259897 349 13.9200000000 4.5745058060 1.9480206411 7.7883353233 0.4017972910 0.0169840000 693715662 0 1786458112 3.3453919888 -2.9033863544 -0.3628259897 350 13.9600000000 4.5744676590 1.9555247754 7.7883353233 0.4012212604 0.0250690000 693716936 0 1786966016 3.3453919888 -2.9033863544 -0.3628259897 351 14.0000000000 4.5743827820 1.9629859093 7.7883353233 0.4006477081 0.0210360000 693718210 0 1785565184 3.3453919888 -2.9033863544 -0.3628259897 352 14.0400000000 4.5744366646 1.9704048035 7.7883353233 0.4000766102 0.0212750000 693719484 0 1785806848 3.3453919888 -2.9033863544 -0.3628259897 353 14.0800000000 4.5745148659 1.9777818859 7.7883353233 0.3995079431 0.0247190000 693720758 0 1786314752 3.3453919888 -2.9033863544 -0.3628259897 354 14.1200000000 4.5751314163 1.9851190314 7.7883353233 0.3989417104 0.0168070000 693722032 0 1786949632 3.3453919888 -2.9033863544 -0.3628259897 355 14.1600000000 4.5753450394 1.9924154427 7.7883353233 0.3983778763 0.0214720000 693723306 0 1785217024 3.3453919888 -2.9033863544 -0.3628259897 356 14.2000000000 4.5755085945 1.9996713223 7.7883353233 0.3978164312 0.0215470000 693724580 0 1785696256 3.3453919888 -2.9033863544 -0.3628259897 357 14.2400000000 4.5760016441 2.0068879339 7.7883353233 0.3972573928 0.0206070000 693725854 0 1786204160 3.3453919888 -2.9033863544 -0.3628259897 358 14.2800000000 4.5766153336 2.0140659434 7.7883353233 0.3967007174 0.0204980000 693727128 0 1784684544 3.3453919888 -2.9033863544 -0.3628259897 359 14.3200000000 4.5760807991 2.0212024750 7.7883353233 0.3961463715 0.0147350000 693728402 0 1785188352 3.3453919888 -2.9033863544 -0.3628259897 360 14.3600000000 4.5752582550 2.0282970744 7.7883353233 0.3955942617 0.0188480000 693729676 0 1785696256 3.3453919888 -2.9033863544 -0.3628259897 361 14.4000000000 4.5753626823 2.0353526578 7.7883353233 0.3950445337 0.0200470000 693730950 0 1786204160 3.3453919888 -2.9033863544 -0.3628259897 362 14.4400000000 4.5754380226 2.0423694682 7.7883353233 0.3944970249 0.0204340000 693732224 0 1786331136 3.3453919888 -2.9033863544 -0.3628259897 363 14.4800000000 4.5751481056 2.0493468198 7.7883353233 0.3939517717 0.0314910000 693810310 0 1784942592 3.3453919888 -2.9033863544 -0.3628259897 364 14.5200000000 4.5747814178 2.0562848270 7.7883353233 0.3934087869 0.0221180000 693811584 0 1785171968 3.3453919888 -2.9033863544 -0.3628259897 365 14.5600000000 4.5754213333 2.0631865708 7.7883353233 0.3928680312 0.0261060000 693812858 0 1785679872 3.3453919888 -2.9033863544 -0.3628259897 366 14.6000000000 4.5756626129 2.0700512595 7.7883353233 0.3923295235 0.0236330000 693814132 0 1784332288 3.3453919888 -2.9033863544 -0.3628259897 367 14.6400000000 4.5746288300 2.0768757215 7.7883353233 0.3917932520 0.0262070000 693892218 0 1784332288 3.3453919888 -2.9033863544 -0.3628259897 368 14.6800000000 4.5742187500 2.0836619797 7.7883353233 0.3912591293 0.0224490000 693893492 0 1784950784 3.3453919888 -2.9033863544 -0.3628259897 369 14.7200000000 4.5743441582 2.0904117959 7.7883353233 0.3907271893 0.0273630000 693894766 0 1783689216 3.3453919888 -2.9033863544 -0.3628259897 370 14.7600000000 4.5747170448 2.0971261344 7.7883353233 0.3901973970 0.0229080000 693896040 0 1783681024 3.3453919888 -2.9033863544 -0.3628259897 371 14.8000000000 4.5753650665 2.1038060238 7.7883353233 0.3896697588 0.0227120000 693897314 0 1784172544 3.3453919888 -2.9033863544 -0.3628259897 372 14.8400000000 4.5753030777 2.1104498330 7.7883353233 0.3891442958 0.0212490000 693898588 0 1784680448 3.3453919888 -2.9033863544 -0.3628259897 373 14.8800000000 4.5756106377 2.1170588432 7.7883353233 0.3886209578 0.0223810000 693899862 0 1783443456 3.3453919888 -2.9033863544 -0.3628259897 374 14.9200000000 4.5762605667 2.1236342489 7.7883353233 0.3880997843 0.0327020000 693977948 0 1783443456 3.3453919888 -2.9033863544 -0.3628259897 375 14.9600000000 4.5757341385 2.1301731820 7.7883353233 0.3875807344 0.0188160000 693979222 0 1784045568 3.3453919888 -2.9033863544 -0.3628259897 376 15.0000000000 4.5755534172 2.1366768528 7.7883353233 0.3870636688 0.0222620000 694057308 0 1784553472 3.3453919888 -2.9033863544 -0.3628259897 377 15.0400000000 4.5767722130 2.1431492543 7.7883353233 0.3865487183 0.0193640000 694058582 0 1782915072 3.3453919888 -2.9033863544 -0.3628259897 378 15.0800000000 4.5764031410 2.1495864339 7.7883353233 0.3860359420 0.0187650000 694059856 0 1782915072 3.3453919888 -2.9033863544 -0.3628259897 379 15.1200000000 4.5759124756 2.1559883496 7.7883353233 0.3855250472 0.0188400000 694061130 0 1783410688 3.3453919888 -2.9033863544 -0.3628259897 380 15.1600000000 4.5763206482 2.1623576451 7.7883353233 0.3850161127 0.0267250000 694139216 0 1783918592 3.3453919888 -2.9033863544 -0.3628259897 381 15.2000000000 4.5768022537 2.1686947700 7.7883353233 0.3845091961 0.0237130000 694140490 0 1782165504 3.3453919888 -2.9033863544 -0.3628259897 382 15.2400000000 4.5766348839 2.1749982782 7.7883353233 0.3840043129 0.0216220000 694141764 0 1782165504 3.3453919888 -2.9033863544 -0.3628259897 383 15.2800000000 4.5771574974 2.1812702344 7.7883353233 0.3835014498 0.0250430000 694219850 0 1782521856 3.3453919888 -2.9033863544 -0.3628259897 384 15.3200000000 4.5780372620 2.1875118152 7.7883353233 0.3830005767 0.0283390000 694297936 0 1782013952 3.3453919888 -2.9033863544 -0.3628259897 385 15.3600000000 8.6090078354 2.2041910256 8.6090078354 0.4395069945 0.0382410000 694376126 0 1782013952 -3.3157668114 -5.0478534698 -6.1798076630 386 15.4000000000 9.4798326492 2.2230398381 9.4798326492 0.4424765002 0.0293620000 697723224 0 1785298944 -0.9319510460 -6.6990051270 -6.6215929985 387 15.4400000000 10.5777873993 2.2446283331 10.5777873993 0.4457404123 0.0310990000 701070322 0 1786458112 -3.7400641441 -6.8807373047 -7.1593713760 388 15.4800000000 10.5763092041 2.2661017374 10.5777873993 0.4451642095 0.0203260000 702804480 0 1786597376 -3.7400641441 -6.8807373047 -7.1593713760 389 15.5200000000 11.0392694473 2.2886548678 11.0392694473 0.4456344645 0.0272330000 702882670 0 1786839040 -4.1244888306 -6.5619788170 -7.9146733284 390 15.5600000000 12.7843647003 2.3155669443 12.7843647003 0.4529457700 0.0270760000 706229768 0 1787727872 -7.8591365814 -5.6741924286 -8.4659929276 391 15.6000000000 13.4762620926 2.3441109216 13.4762620926 0.4534509682 0.0352040000 709576866 0 1788108800 6.8739862442 -5.5702228546 -10.0046834946 392 15.6400000000 13.4753351212 2.3725069017 13.4762620926 0.4528708479 0.0179350000 711311024 0 1787981824 6.8739862442 -5.5702228546 -10.0046834946 393 15.6800000000 13.4741725922 2.4007554149 13.4762620926 0.4522929514 0.0144670000 711619510 0 1786470400 6.8739862442 -5.5702228546 -10.0046834946 394 15.7200000000 14.4171895981 2.4312539788 14.4171895981 0.4617375119 0.0317630000 713233724 0 1787981824 10.6042966843 2.3948600292 -9.2284898758 395 15.7600000000 9.0675506592 2.4480547299 14.4171895981 0.5277719164 0.0340810000 716580718 0 1786486784 5.7312254906 -0.8435490131 -6.7912974358 396 15.8000000000 8.2214994431 2.4626341358 14.4171895981 0.5284900716 0.0266710000 716658804 0 1786855424 5.6672153473 -1.5909131765 -5.5236740112 397 15.8400000000 7.3327393532 2.4749014033 14.4171895981 0.5308315476 0.0254780000 716736890 0 1787363328 6.3369960785 -0.6357013583 -3.2591674328 398 15.8800000000 6.6830430031 2.4854746234 14.4171895981 0.5311624328 0.0306620000 716814976 0 1785962496 5.8364796638 -0.5776995420 -2.8086156845 399 15.9200000000 6.2740416527 2.4949697789 14.4171895981 0.5308705644 0.0291880000 716893062 0 1786077184 5.6358327866 -0.6687573791 -2.2074882984 400 15.9600000000 6.1196799278 2.5040315543 14.4171895981 0.5302917077 0.0329280000 716971148 0 1786585088 5.5567493439 -0.5026251674 -2.0176622868 401 16.0000000000 5.5548920631 2.5116396852 14.4171895981 0.5302339947 0.0281390000 717049234 0 1785348096 4.9065971375 -0.6828444600 -2.0773866177 402 16.0400000000 5.5552210808 2.5192107832 14.4171895981 0.5295724898 0.0310370000 717127320 0 1785348096 4.9065971375 -0.6828444600 -2.0773866177 403 16.0800000000 5.5554871559 2.5267449678 14.4171895981 0.5289135016 0.0303500000 718434218 0 1786839040 4.9065971375 -0.6828444600 -2.0773866177 404 16.1200000000 5.5548343658 2.5342402385 14.4171895981 0.5282570512 0.0372720000 718512304 0 1785192448 4.9065971375 -0.6828444600 -2.0773866177 405 16.1600000000 5.5551352501 2.5416992386 14.4171895981 0.5276030060 0.0191070000 718513578 0 1785315328 4.9065971375 -0.6828444600 -2.0773866177 406 16.2000000000 5.5550231934 2.5491212188 14.4171895981 0.5269513075 0.0197250000 718514852 0 1785823232 4.9065971375 -0.6828444600 -2.0773866177 407 16.2400000000 5.5552144051 2.5565071971 14.4171895981 0.5263021013 0.0234310000 718516126 0 1786331136 4.9065971375 -0.6828444600 -2.0773866177 408 16.2800000000 5.5548334122 2.5638560359 14.4171895981 0.5256552483 0.0163360000 718517400 0 1784840192 4.9065971375 -0.6828444600 -2.0773866177 409 16.3200000000 5.5546288490 2.5711684388 14.4171895981 0.5250107071 0.0233720000 718518674 0 1784840192 4.9065971375 -0.6828444600 -2.0773866177 410 16.3600000000 5.5543084145 2.5784443900 14.4171895981 0.5243685336 0.0192700000 718519948 0 1785315328 4.9065971375 -0.6828444600 -2.0773866177 411 16.3999999990 5.5539407730 2.5856840406 14.4171895981 0.5237287895 0.0200650000 718521222 0 1785823232 4.9065971375 -0.6828444600 -2.0773866177 412 16.4400000000 5.5536804199 2.5928879153 14.4171895981 0.5230913770 0.0238520000 718522496 0 1784459264 4.9065971375 -0.6828444600 -2.0773866177 413 16.4800000000 5.5535831451 2.6000566688 14.4171895981 0.5224562469 0.0144500000 718523770 0 1784459264 4.9065971375 -0.6828444600 -2.0773866177 414 16.5200000000 5.5530433655 2.6071894869 14.4171895981 0.5218233983 0.0230030000 718525044 0 1784807424 4.9065971375 -0.6828444600 -2.0773866177 415 16.5599999990 5.5524950027 2.6142866087 14.4171895981 0.5211928536 0.0198220000 718526318 0 1785442304 4.9065971375 -0.6828444600 -2.0773866177 416 16.6000000000 5.5520696640 2.6213485872 14.4171895981 0.5205646326 0.0201340000 718527592 0 1783803904 4.9065971375 -0.6828444600 -2.0773866177 417 16.6400000000 5.5519504547 2.6283764094 14.4171895981 0.5199387259 0.0197560000 718528866 0 1783803904 4.9065971375 -0.6828444600 -2.0773866177 418 16.6800000000 5.5520882607 2.6353709354 14.4171895981 0.5193150460 0.0188870000 718530140 0 1784283136 4.9065971375 -0.6828444600 -2.0773866177 419 16.7199999990 5.5516080856 2.6423309286 14.4171895981 0.5186936507 0.0198800000 718531414 0 1784791040 4.9065971375 -0.6828444600 -2.0773866177 420 16.7600000000 5.5507149696 2.6492556525 14.4171895981 0.5180745318 0.0231890000 718532688 0 1783308288 4.9065971375 -0.6828444600 -2.0773866177 421 16.8000000000 5.5501828194 2.6561462158 14.4171895981 0.5174574927 0.0145070000 718533962 0 1783296000 4.9065971375 -0.6828444600 -2.0773866177 422 16.8400000000 5.5488290787 2.6630009145 14.4171895981 0.5168426658 0.0266570000 718612048 0 1783791616 4.9065971375 -0.6828444600 -2.0773866177 423 16.8799999990 5.5487232208 2.6698229531 14.4171895981 0.5162300099 0.0184620000 718613322 0 1784426496 4.9065971375 -0.6828444600 -2.0773866177 424 16.9200000000 5.5479912758 2.6766110859 14.4171895981 0.5156195575 0.0188970000 718614596 0 1784807424 4.9065971375 -0.6828444600 -2.0773866177 425 16.9600000000 5.5466213226 2.6833640512 14.4171895981 0.5150114641 0.0200740000 718615870 0 1782788096 4.9065971375 -0.6828444600 -2.0773866177 426 17.0000000000 5.5453691483 2.6900823730 14.4171895981 0.5144054243 0.0193640000 718617144 0 1783283712 4.9065971375 -0.6828444600 -2.0773866177 427 17.0400000000 5.5443239212 2.6967667794 14.4171895981 0.5138014245 0.0195900000 718618418 0 1783791616 4.9065971375 -0.6828444600 -2.0773866177 428 17.0800000000 5.5416889191 2.7034137938 14.4171895981 0.5131995962 0.0187750000 718619692 0 1784299520 4.9065971375 -0.6828444600 -2.0773866177 429 17.1200000000 5.5400929451 2.7100260995 14.4171895981 0.5125998324 0.0171970000 718620966 0 1782161408 4.9065971375 -0.6828444600 -2.0773866177 430 17.1600000000 5.5394358635 2.7166061222 14.4171895981 0.5120020963 0.0236450000 718622240 0 1782161408 4.9065971375 -0.6828444600 -2.0773866177 431 17.2000000000 5.5378532410 2.7231519392 14.4171895981 0.5114064496 0.0206430000 718623514 0 1782665216 4.9065971375 -0.6828444600 -2.0773866177 432 17.2400000000 5.5367302895 2.7296648520 14.4171895981 0.5108129220 0.0206390000 718624788 0 1783173120 4.9065971375 -0.6828444600 -2.0773866177 433 17.2800000000 5.5357017517 2.7361453068 14.4171895981 0.5102214958 0.0239140000 718626062 0 1781665792 4.9065971375 -0.6828444600 -2.0773866177 434 17.3200000000 5.5343236923 2.7425927224 14.4171895981 0.5096320865 0.0161080000 718627336 0 1781665792 4.9065971375 -0.6828444600 -2.0773866177 435 17.3600000000 5.5333862305 2.7490083397 14.4171895981 0.5090447017 0.0249030000 718628610 0 1782140928 4.9065971375 -0.6828444600 -2.0773866177 436 17.4000000000 5.5315456390 2.7553903059 14.4171895981 0.5084594774 0.0218380000 718629884 0 1782648832 4.9065971375 -0.6828444600 -2.0773866177 437 17.4400000000 5.5299234390 2.7617393520 14.4171895981 0.5078763303 0.0280440000 718631158 0 1781010432 4.9065971375 -0.6828444600 -2.0773866177 438 17.4800000000 5.5277390480 2.7680544198 14.4171895981 0.5072951212 0.0219820000 718632432 0 1781010432 4.9065971375 -0.6828444600 -2.0773866177 439 17.5200000000 5.5245995522 2.7743335659 14.4171895981 0.5067159818 0.0215850000 718633706 0 1781506048 4.9065971375 -0.6828444600 -2.0773866177 440 17.5600000000 5.5230908394 2.7805807415 14.4171895981 0.5061387373 0.0228860000 718634980 0 1780895744 4.9065971375 -0.6828444600 -2.0773866177 441 17.6000000000 5.5215692520 2.7867961350 14.4171895981 0.5055634770 0.0231010000 718636254 0 1780895744 4.9065971375 -0.6828444600 -2.0773866177 442 17.6400000000 5.5203590393 2.7929806664 14.4171895981 0.5049901842 0.0259000000 718637528 0 1781268480 4.9065971375 -0.6828444600 -2.0773866177 443 17.6800000000 5.5192389488 2.7991347483 14.4171895981 0.5044187665 0.0267080000 718638802 0 1781903360 4.9065971375 -0.6828444600 -2.0773866177 444 17.7200000000 5.5181260109 2.8052586025 14.4171895981 0.5038492098 0.0279990000 718640076 0 1780490240 4.9065971375 -0.6828444600 -2.0773866177 445 17.7600000000 5.5172796249 2.8113530318 14.4171895981 0.5032815167 0.0311300000 718641350 0 1780744192 4.9065971375 -0.6828444600 -2.0773866177 446 17.8000000000 5.5163173676 2.8174179742 14.4171895981 0.5027157206 0.0247090000 718642624 0 1781252096 4.9065971375 -0.6828444600 -2.0773866177 447 17.8400000000 48.7155380249 2.9200983323 48.7155380249 2.1050506135 0.0430820000 718720710 0 1779998720 37.8575248718 3.3710958958 -30.3396110535 448 17.8800000000 48.7136573792 3.0223160980 48.7155380249 2.1026946636 0.0426780000 718798796 0 1779998720 37.8575248718 3.3710958958 -30.3396110535 449 17.9200000000 48.7119255066 3.1240746936 48.7155380249 2.1003466126 0.0301120000 718800070 0 1779609600 37.8575248718 3.3710958958 -30.3396110535 450 17.9600000000 48.7089576721 3.2253744335 48.7155380249 2.0980064147 0.0420090000 718878156 0 1779609600 37.8575248718 3.3710958958 -30.3396110535 451 18.0000000000 48.7073364258 3.3262213559 48.7155380249 2.0956740424 0.0297870000 718956242 0 1779240960 37.8575248718 3.3710958958 -30.3396110535 452 18.0400000000 48.7063713074 3.4266199178 48.7155380249 2.0933494278 0.0218450000 718957516 0 1779228672 37.8575248718 3.3710958958 -30.3396110535 453 18.0800000000 48.7050361633 3.5265722715 48.7155380249 2.0910325336 0.0204340000 718958790 0 1779712000 37.8575248718 3.3710958958 -30.3396110535 454 18.1200000000 456.8115844727 4.5249974085 456.8115844727 19.3442144679 0.0375100000 719036876 0 1780219904 322.8783264160 -68.5771255493 -315.7133483887 455 18.1600000000 456.8100585938 5.5190305100 456.8115844727 19.3228985234 0.0196120000 719038150 0 1778724864 322.8783264160 -68.5771255493 -315.7133483887 456 18.2000000000 456.8086547852 6.5087007387 456.8115844727 19.3016528903 0.0198740000 719039424 0 1778724864 322.8783264160 -68.5771255493 -315.7133483887 457 18.2400000000 456.8072204590 7.4940366681 456.8115844727 19.2804771850 0.0240490000 719040698 0 1779220480 322.8783264160 -68.5771255493 -315.7133483887 458 18.2800000000 456.8059692383 8.4750670885 456.8115844727 19.2593710215 0.0185410000 719041972 0 1779728384 322.8783264160 -68.5771255493 -315.7133483887 459 18.3200000000 456.8049011230 9.4518205396 456.8115844727 19.2383340236 0.0218270000 719043246 0 1778343936 322.8783264160 -68.5771255493 -315.7133483887 460 18.3600000000 456.8030700684 10.4243232559 456.8115844727 19.2173658102 0.0198590000 719044520 0 1778343936 322.8783264160 -68.5771255493 -315.7133483887 461 18.4000000000 456.8017272949 11.3926039588 456.8115844727 19.1964660068 0.0217840000 719045794 0 1778839552 322.8783264160 -68.5771255493 -315.7133483887 462 18.4400000000 456.8001098633 12.3566894695 456.8115844727 19.1756342482 0.0246300000 719047068 0 1779347456 322.8783264160 -68.5771255493 -315.7133483887 463 18.4800000000 456.7984619141 13.3166069045 456.8115844727 19.1548701598 0.0263350000 719125154 0 1777709056 322.8783264160 -68.5771255493 -315.7133483887 464 18.5200000000 456.7972106934 14.2723840679 456.8115844727 19.1341733770 0.0280060000 719203240 0 1777709056 322.8783264160 -68.5771255493 -315.7133483887 465 18.5600000000 456.7956542969 15.2240470146 456.8115844727 19.1135435385 0.0202400000 719204514 0 1778331648 322.8783264160 -68.5771255493 -315.7133483887 466 18.6000000000 456.7945861816 16.1716232789 456.8115844727 19.0929802813 0.0322800000 719282600 0 1776693248 322.8783264160 -68.5771255493 -315.7133483887 467 18.6400000000 456.7934875488 17.1151390482 456.8115844727 19.0724832494 0.0205450000 719283874 0 1776693248 322.8783264160 -68.5771255493 -315.7133483887 468 18.6800000000 456.7922668457 18.0546200905 456.8115844727 19.0520520899 0.0289800000 719361960 0 1777315840 322.8783264160 -68.5771255493 -315.7133483887 469 18.7200000000 456.7909545898 18.9900920191 456.8115844727 19.0316864524 0.0157270000 719363234 0 1777823744 322.8783264160 -68.5771255493 -315.7133483887 470 18.7600000000 456.7901306152 19.9215814629 456.8115844727 19.0113859829 0.0244580000 719441320 0 1776685056 322.8783264160 -68.5771255493 -315.7133483887 471 18.8000000000 456.7885742188 20.8491122331 456.8115844727 18.9911503446 0.0204270000 719442594 0 1777061888 322.8783264160 -68.5771255493 -315.7133483887 472 18.8400000000 456.7872619629 21.7727100080 456.8115844727 18.9709791964 0.0236120000 719520680 0 1777696768 322.8783264160 -68.5771255493 -315.7133483887 473 18.8800000000 456.7858276367 22.6923994744 456.8115844727 18.9508721826 0.0222570000 719521954 0 1776074752 322.8783264160 -68.5771255493 -315.7133483887 474 18.9200000000 456.7852783203 23.6082072357 456.8115844727 18.9308289530 0.0176550000 719523228 0 1776074752 322.8783264160 -68.5771255493 -315.7133483887 475 18.9600000000 456.7844543457 24.5201572296 456.8115844727 18.9108491839 0.0281650000 719601314 0 1776570368 322.8783264160 -68.5771255493 -315.7133483887 476 19.0000000000 456.7835693359 25.4282736416 456.8115844727 18.8909325464 0.0213050000 719602588 0 1777205248 322.8783264160 -68.5771255493 -315.7133483887 477 19.0400000000 456.7822265625 26.3325796226 456.8115844727 18.8710787014 0.0265090000 719603862 0 1775677440 322.8783264160 -68.5771255493 -315.7133483887 478 19.0800000000 456.7815246582 27.2331004281 456.8115844727 18.8512873198 0.0224320000 719605136 0 1775677440 322.8783264160 -68.5771255493 -315.7133483887 479 19.1200000000 456.7809143066 28.1298599560 456.8115844727 18.8315580789 0.0214670000 719606410 0 1776173056 322.8783264160 -68.5771255493 -315.7133483887 480 19.1600000000 456.7798767090 29.0228808242 456.8115844727 18.8118906533 0.0213160000 719607684 0 1776680960 322.8783264160 -68.5771255493 -315.7133483887 481 19.2000000000 456.7789611816 29.9121866046 456.8115844727 18.7922847191 0.0175780000 719608958 0 1775284224 322.8783264160 -68.5771255493 -315.7133483887 482 19.2400000000 456.7781677246 30.7978006733 456.8115844727 18.7727399581 0.0268210000 719687044 0 1775411200 322.8783264160 -68.5771255493 -315.7133483887 483 19.2800000000 456.7770996094 31.6797453916 456.8115844727 18.7532560559 0.0225960000 719688318 0 1776046080 322.8783264160 -68.5771255493 -315.7133483887 484 19.3200000000 456.7761535645 32.5580437556 456.8115844727 18.7338326903 0.0285560000 719689592 0 1774407680 322.8783264160 -68.5771255493 -315.7133483887 485 19.3600000000 456.7751464844 33.4327181942 456.8115844727 18.7144695511 0.0220320000 719690866 0 1774407680 322.8783264160 -68.5771255493 -315.7133483887 486 19.4000000000 456.7740478516 34.3037908890 456.8115844727 18.6951663289 0.0308830000 719768952 0 1774776320 322.8783264160 -68.5771255493 -315.7133483887 487 19.4400000000 456.7731323242 35.1712844032 456.8115844727 18.6759227163 0.0278160000 719847038 0 1773891584 322.8783264160 -68.5771255493 -315.7133483887 488 19.4800000000 456.7720031738 36.0352203024 456.8115844727 18.6567384066 0.0215460000 719848312 0 1773891584 322.8783264160 -68.5771255493 -315.7133483887 489 19.5200000000 456.7708435059 36.8956203498 456.8115844727 18.6376130957 0.0215680000 719849586 0 1774505984 322.8783264160 -68.5771255493 -315.7133483887 490 19.5600000000 456.7696838379 37.7525061937 456.8115844727 18.6185464800 0.0227240000 719850860 0 1775013888 322.8783264160 -68.5771255493 -315.7133483887 491 19.6000000000 456.7689819336 38.6059002379 456.8115844727 18.5995382628 0.0273600000 719852134 0 1773408256 322.8783264160 -68.5771255493 -315.7133483887 492 19.6400000000 456.7674865723 39.4558221614 456.8115844727 18.5805881440 0.0231760000 719853408 0 1773408256 322.8783264160 -68.5771255493 -315.7133483887 493 19.6800000000 456.7663574219 40.3022938353 456.8115844727 18.5616958297 0.0228290000 719854682 0 1773903872 322.8783264160 -68.5771255493 -315.7133483887 494 19.7200000000 456.7647705078 41.1453352861 456.8115844727 18.5428610258 0.0294790000 719932768 0 1772752896 322.8783264160 -68.5771255493 -315.7133483887 495 19.7600000000 396.5691528320 41.8633632003 456.8115844727 18.7818279202 0.0387910000 720010854 0 1772871680 280.8008422852 -31.2006320953 -278.2882690430 496 19.8000000000 396.5684509277 42.5784944256 456.8115844727 18.7628467909 0.0210950000 720012128 0 1773506560 280.8008422852 -31.2006320953 -278.2882690430 497 19.8400000000 396.5671997070 43.2907453416 456.8115844727 18.7439230904 0.0218260000 720013402 0 1774014464 280.8008422852 -31.2006320953 -278.2882690430 498 19.8800000000 396.5652465820 44.0001318903 456.8115844727 18.7250565305 0.0211120000 720014676 0 1772011520 280.8008422852 -31.2006320953 -278.2882690430 499 19.9200000000 396.5633239746 44.7066713534 456.8115844727 18.7062468260 0.0215290000 720015950 0 1772236800 280.8008422852 -31.2006320953 -278.2882690430 500 19.9600000000 396.5610961914 45.4103802031 456.8115844727 18.6874936918 0.0216060000 720017224 0 1772744704 280.8008422852 -31.2006320953 -278.2882690430 501 20.0000000000 396.5598449707 46.1112773384 456.8115844727 18.6687968499 0.0264450000 720095310 0 1771741184 280.8008422852 -31.2006320953 -278.2882690430 502 20.0400000000 396.5585021973 46.8093793799 456.8115844727 18.6501560158 0.0247850000 720096584 0 1771855872 280.8008422852 -31.2006320953 -278.2882690430 503 20.0800000000 396.5561828613 47.5047010568 456.8115844727 18.6315709035 0.0279540000 720174670 0 1772363776 280.8008422852 -31.2006320953 -278.2882690430 504 20.1200000000 396.5541381836 48.1972594638 456.8115844727 18.6130412415 0.0268050000 720175944 0 1772998656 280.8008422852 -31.2006320953 -278.2882690430 505 20.1600000000 396.5521545410 48.8870711372 456.8115844727 18.5945667557 0.0234650000 720177218 0 1771360256 280.8008422852 -31.2006320953 -278.2882690430 506 20.2000000000 396.5506896973 49.5741533873 456.8115844727 18.5761471739 0.0267680000 720178492 0 1771360256 280.8008422852 -31.2006320953 -278.2882690430 507 20.2400000000 396.5492858887 50.2585224850 456.8115844727 18.5577822234 0.0226300000 720179766 0 1771855872 280.8008422852 -31.2006320953 -278.2882690430 508 20.2800000000 396.5471191406 50.9401929508 456.8115844727 18.5394716325 0.0242840000 720181040 0 1770491904 280.8008422852 -31.2006320953 -278.2882690430 509 20.3200000000 396.5449218750 51.6191806304 456.8115844727 18.5212151339 0.0205950000 720182314 0 1770491904 280.8008422852 -31.2006320953 -278.2882690430 510 20.3600000000 396.5431213379 52.2955020828 456.8115844727 18.5030124665 0.0169850000 720183588 0 1770967040 280.8008422852 -31.2006320953 -278.2882690430 511 20.4000000000 396.5413513184 52.9691730207 456.8115844727 18.4848633608 0.0214850000 720184862 0 1771474944 280.8008422852 -31.2006320953 -278.2882690430 512 20.4400000000 396.5392150879 53.6402082591 456.8115844727 18.4667675550 0.0224760000 720186136 0 1769725952 280.8008422852 -31.2006320953 -278.2882690430 513 20.4800000000 396.5354003906 54.3086199396 456.8115844727 18.4487247901 0.0202910000 720187410 0 1769725952 280.8008422852 -31.2006320953 -278.2882690430 514 20.5200000000 396.5327453613 54.9744256311 456.8115844727 18.4307348083 0.0226370000 720272652 0 1770332160 280.8008422852 -31.2006320953 -278.2882690430 515 20.5600000000 396.5296936035 55.6376397437 456.8115844727 18.4127973510 0.0212790000 720273926 0 1770967040 280.8008422852 -31.2006320953 -278.2882690430 516 20.6000000000 305.4004821777 56.1216762600 456.8115844727 18.8980445244 0.0321670000 720352012 0 1769697280 224.7866668701 -135.6112976074 -155.9750213623 517 20.6400000000 305.3978271484 56.6038351592 456.8115844727 18.8797235863 0.0207160000 720353286 0 1769697280 224.7866668701 -135.6112976074 -155.9750213623 518 20.6800000000 305.3955383301 57.0841280225 456.8115844727 18.8614558301 0.0208870000 720354560 0 1770332160 224.7866668701 -135.6112976074 -155.9750213623 519 20.7200000000 305.3934936523 57.5625661066 456.8115844727 18.8432409990 0.0250240000 720355834 0 1770840064 224.7866668701 -135.6112976074 -155.9750213623 520 20.7600000000 305.3915100098 58.0391602295 456.8115844727 18.8250788361 0.0224090000 720357108 0 1769324544 224.7866668701 -135.6112976074 -155.9750213623 521 20.8000000000 305.3901367188 58.5139221805 456.8115844727 18.8069690890 0.0204060000 720358382 0 1769324544 224.7866668701 -135.6112976074 -155.9750213623 522 20.8400000000 305.3894653320 58.9868638340 456.8115844727 18.7889115079 0.0204680000 720359656 0 1769820160 224.7866668701 -135.6112976074 -155.9750213623 523 20.8800000000 305.3879394531 59.4579939977 456.8115844727 18.7709058393 0.0216620000 720360930 0 1770328064 224.7866668701 -135.6112976074 -155.9750213623 524 20.9200000000 305.3865051270 59.9273232175 456.8115844727 18.7529518373 0.0210320000 720362204 0 1768947712 224.7866668701 -135.6112976074 -155.9750213623 525 20.9600000000 305.3849792480 60.3948616099 456.8115844727 18.7350492552 0.0180460000 720363478 0 1768808448 224.7866668701 -135.6112976074 -155.9750213623 526 21.0000000000 305.3837280273 60.8606199111 456.8115844727 18.7171978485 0.0214590000 720364752 0 1769316352 224.7866668701 -135.6112976074 -155.9750213623 527 21.0400000000 305.3824462891 61.3246081964 456.8115844727 18.6993973745 0.0208280000 720366026 0 1769824256 224.7866668701 -135.6112976074 -155.9750213623 528 21.0800000000 305.3808898926 61.7868360027 456.8115844727 18.6816475915 0.0199980000 720367300 0 1767821312 224.7866668701 -135.6112976074 -155.9750213623 529 21.1200000000 305.3790588379 62.2473127944 456.8115844727 18.6639482591 0.0250190000 720368574 0 1767919616 224.7866668701 -135.6112976074 -155.9750213623 530 21.1600000000 305.3782348633 62.7060503832 456.8115844727 18.6462991375 0.0173410000 720369848 0 1768427520 224.7866668701 -135.6112976074 -155.9750213623 531 21.2000000000 305.3770141602 63.1630578480 456.8115844727 18.6286999882 0.0188980000 720371122 0 1769062400 224.7866668701 -135.6112976074 -155.9750213623 532 21.2400000000 305.3749389648 63.6183433388 456.8115844727 18.6111505772 0.0202010000 720372396 0 1767538688 224.7866668701 -135.6112976074 -155.9750213623 533 21.2800000000 305.3736877441 64.0719180938 456.8115844727 18.5936506706 0.0197420000 720373670 0 1767792640 224.7866668701 -135.6112976074 -155.9750213623 534 21.3200000000 305.3721618652 64.5237912094 456.8115844727 18.5762000357 0.0248950000 720374944 0 1768300544 224.7866668701 -135.6112976074 -155.9750213623 535 21.3600000000 305.3709106445 64.9739727411 456.8115844727 18.5587984425 0.0176210000 720376218 0 1768808448 224.7866668701 -135.6112976074 -155.9750213623 536 21.4000000000 305.3700256348 65.4224728398 456.8115844727 18.5414456628 0.0192050000 720377492 0 1767043072 224.7866668701 -135.6112976074 -155.9750213623 537 21.4400000000 305.3690185547 65.8693006716 456.8115844727 18.5241414662 0.0199930000 720378766 0 1767284736 224.7866668701 -135.6112976074 -155.9750213623 538 21.4800000000 305.3679504395 66.3144654482 456.8115844727 18.5068856293 0.0200300000 720380040 0 1767792640 224.7866668701 -135.6112976074 -155.9750213623 539 21.5200000000 305.3666687012 66.7579760293 456.8115844727 18.4896779267 0.0245270000 720381314 0 1768300544 224.7866668701 -135.6112976074 -155.9750213623 540 21.5600000000 305.3657836914 67.1998423398 456.8115844727 18.4725181325 0.0182610000 720382588 0 1766678528 224.7866668701 -135.6112976074 -155.9750213623 541 21.6000000000 305.3652648926 67.6400741745 456.8115844727 18.4554060274 0.0205470000 720383862 0 1766678528 224.7866668701 -135.6112976074 -155.9750213623 542 21.6400000000 305.3641052246 68.0786793978 456.8115844727 18.4383413902 0.0192850000 720385136 0 1767157760 224.7866668701 -135.6112976074 -155.9750213623 543 21.6800000000 305.3636169434 68.5156682331 456.8115844727 18.4213240022 0.0220790000 720386410 0 1767665664 224.7866668701 -135.6112976074 -155.9750213623 544 21.7200000000 305.3628845215 68.9510491454 456.8115844727 18.4043536450 0.0247460000 720387684 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 545 21.7600000000 305.3619384766 69.3848305937 456.8115844727 18.3874301035 0.0266480000 720465770 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 546 21.8000000000 305.3612976074 69.8170219252 456.8115844727 18.3705531636 0.0211720000 720467044 0 1766141952 224.7866668701 -135.6112976074 -155.9750213623 547 21.8400000000 305.3600463867 70.2476307451 456.8115844727 18.3537226134 0.0229970000 720468318 0 1765666816 224.7866668701 -135.6112976074 -155.9750213623 548 21.8800000000 305.3593444824 70.6766667191 456.8115844727 18.3369382355 0.0205210000 720469592 0 1765666816 224.7866668701 -135.6112976074 -155.9750213623 549 21.9200000000 305.3576965332 71.1041367187 456.8115844727 18.3201998269 0.0237800000 720470866 0 1766150144 224.7866668701 -135.6112976074 -155.9750213623 550 21.9600000000 305.3574218750 71.5300517826 456.8115844727 18.3035071666 0.0228410000 720472140 0 1766658048 224.7866668701 -135.6112976074 -155.9750213623 551 22.0000000000 305.3573608398 71.9544207646 456.8115844727 18.2868600505 0.0224340000 720473414 0 1764888576 224.7866668701 -135.6112976074 -155.9750213623 552 22.0400000000 305.3570556641 72.3772516249 456.8115844727 18.2702582725 0.0223080000 720474688 0 1764888576 224.7866668701 -135.6112976074 -155.9750213623 553 22.0800000000 305.3564147949 72.7985521008 456.8115844727 18.2537016319 0.0228420000 720475962 0 1765388288 224.7866668701 -135.6112976074 -155.9750213623 554 22.1200000000 305.3562622070 73.2183313609 456.8115844727 18.2371899193 0.0204640000 720477236 0 1765896192 224.7866668701 -135.6112976074 -155.9750213623 555 22.1600000000 305.3565979004 73.6365985078 456.8115844727 18.2207229315 0.0205510000 720478510 0 1765167104 224.7866668701 -135.6112976074 -155.9750213623 556 22.2000000000 305.3561096191 74.0533602185 456.8115844727 18.2043004694 0.0237820000 720479784 0 1765167104 224.7866668701 -135.6112976074 -155.9750213623 557 22.2400000000 305.3551635742 74.4686237793 456.8115844727 18.1879223314 0.0162370000 720481058 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 558 22.2800000000 305.3544921875 74.8823977370 456.8115844727 18.1715883187 0.0223510000 720482332 0 1766150144 224.7866668701 -135.6112976074 -155.9750213623 559 22.3200000000 305.3541870117 75.2946907411 456.8115844727 18.1552982351 0.0207090000 720483606 0 1765146624 224.7866668701 -135.6112976074 -155.9750213623 560 22.3600000000 305.3541564941 75.7055112156 456.8115844727 18.1390518819 0.0190720000 720484880 0 1765146624 224.7866668701 -135.6112976074 -155.9750213623 561 22.4000000000 305.3533630371 76.1148656752 456.8115844727 18.1228490655 0.0344350000 720562966 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 562 22.4400000000 305.3531799316 76.5227630315 456.8115844727 18.1066895914 0.0193480000 720564240 0 1765265408 224.7866668701 -135.6112976074 -155.9750213623 563 22.4800000000 305.3526916504 76.9292105069 456.8115844727 18.0905732667 0.0221380000 720565514 0 1765265408 224.7866668701 -135.6112976074 -155.9750213623 564 22.5200000000 305.3524780273 77.3342163003 456.8115844727 18.0744999002 0.0159750000 720566788 0 1765752832 224.7866668701 -135.6112976074 -155.9750213623 565 22.5600000000 305.3522644043 77.7377880669 456.8115844727 18.0584693022 0.0239470000 720568062 0 1766260736 224.7866668701 -135.6112976074 -155.9750213623 566 22.6000000000 305.3518066406 78.1399329760 456.8115844727 18.0424812810 0.0193710000 720569336 0 1766641664 224.7866668701 -135.6112976074 -155.9750213623 567 22.6400000000 305.3514099121 78.5406586849 456.8115844727 18.0265356498 0.0196580000 720570610 0 1764872192 224.7866668701 -135.6112976074 -155.9750213623 568 22.6800000000 305.3512573242 78.9399731191 456.8115844727 18.0106322216 0.0304380000 720648696 0 1764990976 224.7866668701 -135.6112976074 -155.9750213623 569 22.7200000000 305.3509826660 79.3378835050 456.8115844727 17.9947708123 0.0193960000 720649970 0 1765625856 224.7866668701 -135.6112976074 -155.9750213623 570 22.7600000000 305.3508605957 79.7343974999 456.8115844727 17.9789512346 0.0151510000 720651244 0 1766133760 224.7866668701 -135.6112976074 -155.9750213623 571 22.8000000000 305.3502197266 80.1295215318 456.8115844727 17.9631733086 0.0162170000 720652518 0 1765244928 224.7866668701 -135.6112976074 -155.9750213623 572 22.8400000000 305.3500366211 80.5232636910 456.8115844727 17.9474368477 0.0209390000 720653792 0 1765371904 224.7866668701 -135.6112976074 -155.9750213623 573 22.8800000000 305.3496398926 80.9156308397 456.8115844727 17.9317416722 0.0206820000 720655066 0 1766006784 224.7866668701 -135.6112976074 -155.9750213623 574 22.9200000000 305.3485412598 81.3066289415 456.8115844727 17.9160876015 0.0195700000 720656340 0 1766514688 224.7866668701 -135.6112976074 -155.9750213623 575 22.9600000000 305.3478088379 81.6962657761 456.8115844727 17.9004744561 0.0201490000 720657614 0 1765142528 224.7866668701 -135.6112976074 -155.9750213623 576 23.0000000000 305.3471374512 82.0845485394 456.8115844727 17.8849020603 0.0205030000 720658888 0 1765142528 224.7866668701 -135.6112976074 -155.9750213623 577 23.0400000000 305.3459472656 82.4714833726 456.8115844727 17.8693702344 0.0191380000 720660162 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 578 23.0800000000 305.3450622559 82.8570777997 456.8115844727 17.8538788028 0.0221730000 720661436 0 1766150144 224.7866668701 -135.6112976074 -155.9750213623 579 23.1200000000 305.3442382812 83.2413388714 456.8115844727 17.8384275904 0.0158130000 720662710 0 1765261312 224.7866668701 -135.6112976074 -155.9750213623 580 23.1600000000 305.3437500000 83.6242740630 456.8115844727 17.8230164241 0.0264460000 720663984 0 1765261312 224.7866668701 -135.6112976074 -155.9750213623 581 23.2000000000 305.3431091309 84.0058899581 456.8115844727 17.8076451307 0.0201630000 720665258 0 1765769216 224.7866668701 -135.6112976074 -155.9750213623 582 23.2400000000 305.3421630859 84.3861928329 456.8115844727 17.7923135390 0.0208570000 720666532 0 1766277120 224.7866668701 -135.6112976074 -155.9750213623 583 23.2800000000 305.3412780762 84.7651895486 456.8115844727 17.7770214797 0.0231560000 720667806 0 1765146624 224.7866668701 -135.6112976074 -155.9750213623 584 23.3200000000 305.3407592773 85.1428874419 456.8115844727 17.7617687816 0.0308310000 720745892 0 1765146624 224.7866668701 -135.6112976074 -155.9750213623 585 23.3600000000 305.3399963379 85.5192927563 456.8115844727 17.7465552778 0.0269730000 720747166 0 1765642240 224.7866668701 -135.6112976074 -155.9750213623 586 23.4000000000 305.3397216797 85.8944129422 456.8115844727 17.7313808011 0.0204720000 720748440 0 1765265408 224.7866668701 -135.6112976074 -155.9750213623 587 23.4400000000 305.3392333984 86.2682542036 456.8115844727 17.7162451817 0.0238350000 720749714 0 1765265408 224.7866668701 -135.6112976074 -155.9750213623 588 23.4800000000 305.3386230469 86.6408228581 456.8115844727 17.7011482558 0.0222890000 720750988 0 1765769216 224.7866668701 -135.6112976074 -155.9750213623 589 23.5200000000 305.3383483887 87.0121259575 456.8115844727 17.6860898591 0.0189110000 720752262 0 1766277120 224.7866668701 -135.6112976074 -155.9750213623 590 23.5600000000 305.3380432129 87.3821698850 456.8115844727 17.6710698272 0.0177570000 720753536 0 1764777984 224.7866668701 -135.6112976074 -155.9750213623 591 23.6000000000 305.3374633789 87.7509605677 456.8115844727 17.6560879975 0.0146350000 720754810 0 1764777984 224.7866668701 -135.6112976074 -155.9750213623 592 23.6400000000 305.3371276855 88.1185047690 456.8115844727 17.6411442109 0.0183930000 720756084 0 1765261312 224.7866668701 -135.6112976074 -155.9750213623 593 23.6800000000 305.3369445801 88.4848090519 456.8115844727 17.6262383028 0.0219430000 720757358 0 1765769216 224.7866668701 -135.6112976074 -155.9750213623 594 23.7200000000 305.3365478516 88.8498793193 456.8115844727 17.6113701139 0.0186390000 720758632 0 1765134336 224.7866668701 -135.6112976074 -155.9750213623 595 23.7600000000 305.3361206055 89.2137217416 456.8115844727 17.5965394875 0.0180240000 720759906 0 1765134336 224.7866668701 -135.6112976074 -155.9750213623 596 23.8000000000 308.7279052734 89.5820341301 456.8115844727 17.5959303460 0.0321440000 720837992 0 1765642240 224.0312042236 -131.9883575439 -166.5164489746 597 23.8400000000 308.7277832031 89.9491124367 456.8115844727 17.5811624654 0.0278920000 720839266 0 1766277120 224.0312042236 -131.9883575439 -166.5164489746 598 23.8800000000 308.7275695801 90.3149626995 456.8115844727 17.5664317053 0.0213590000 720840540 0 1765146624 224.0312042236 -131.9883575439 -166.5164489746 599 23.9200000000 308.7270812988 90.6795906104 456.8115844727 17.5517379100 0.0241650000 720841814 0 1765146624 224.0312042236 -131.9883575439 -166.5164489746 600 23.9600000000 308.7265319824 91.0430021793 456.8115844727 17.5370809261 0.0226900000 720843088 0 1765769216 224.0312042236 -131.9883575439 -166.5164489746 601 24.0000000000 308.7262573242 91.4052039350 456.8115844727 17.5224606007 0.0253490000 720844362 0 1765023744 224.0312042236 -131.9883575439 -166.5164489746 602 24.0400000000 308.7257690430 91.7662015514 456.8115844727 17.5078767812 0.0207380000 720845636 0 1765023744 224.0312042236 -131.9883575439 -166.5164489746 603 24.0800000000 308.7254943848 92.1260013737 456.8115844727 17.4933293170 0.0243810000 720846910 0 1765625856 224.0312042236 -131.9883575439 -166.5164489746 604 24.1200000000 308.7253417969 92.4846095532 456.8115844727 17.4788180546 0.0247580000 720848184 0 1766260736 224.0312042236 -131.9883575439 -166.5164489746 605 24.1600000000 308.7254943848 92.8420325034 456.8115844727 17.4643428442 0.0231790000 720849458 0 1765384192 224.0312042236 -131.9883575439 -166.5164489746 606 24.2000000000 308.7250976562 93.1982751851 456.8115844727 17.4499035358 0.0224610000 720850732 0 1765384192 224.0312042236 -131.9883575439 -166.5164489746 607 24.2400000000 308.7247314453 93.5533434821 456.8115844727 17.4354999827 0.0236940000 720852006 0 1765879808 224.0312042236 -131.9883575439 -166.5164489746 608 24.2800000000 308.7242736816 93.9072430383 456.8115844727 17.4211320375 0.0286640000 720853280 0 1765281792 224.0312042236 -131.9883575439 -166.5164489746 609 24.3200000000 308.7242126465 94.2599802627 456.8115844727 17.4067995546 0.0236290000 720854554 0 1765265408 224.0312042236 -131.9883575439 -166.5164489746 610 24.3600000000 308.7239074707 94.6115604712 456.8115844727 17.3925023893 0.0321120000 720855828 0 1765769216 224.0312042236 -131.9883575439 -166.5164489746 611 24.4000000000 308.7234191895 94.9619890452 456.8115844727 17.3782403946 0.0263200000 720857102 0 1765134336 224.0312042236 -131.9883575439 -166.5164489746 612 24.4400000000 308.7230834961 95.3112718793 456.8115844727 17.3640134282 0.0310060000 720858376 0 1765134336 224.0312042236 -131.9883575439 -166.5164489746 613 24.4800000000 308.7229309082 95.6594148793 456.8115844727 17.3498213448 0.0221360000 720859650 0 1765642240 224.0312042236 -131.9883575439 -166.5164489746 614 24.5200000000 308.7228088379 96.0064236643 456.8115844727 17.3356640049 0.0258330000 720860924 0 1766150144 224.0312042236 -131.9883575439 -166.5164489746 615 24.5600000000 308.7224731445 96.3523034195 456.8115844727 17.3215412692 0.0263280000 720862198 0 1765019648 224.0312042236 -131.9883575439 -166.5164489746 616 24.6000000000 308.7217102051 96.6970589500 456.8115844727 17.3074529929 0.0293340000 720863472 0 1765134336 224.0312042236 -131.9883575439 -166.5164489746 617 24.6400000000 308.7213134766 97.0406963155 456.8115844727 17.2933990342 0.0232700000 720864746 0 1765642240 224.0312042236 -131.9883575439 -166.5164489746 618 24.6800000000 308.7205200195 97.3832203021 456.8115844727 17.2793792553 0.0342440000 720866020 0 1765158912 224.0312042236 -131.9883575439 -166.5164489746 619 24.7200000000 0.5269345045 97.2267481118 456.8115844727 21.2704301167 0.1011800000 720867294 0 1765167104 0.0261404160 0.0354181044 0.0939771831 620 24.7600000000 0.5464697480 97.0708121790 456.8115844727 21.2532420309 0.1177580000 710104120 0 1765167104 0.0448915884 0.0287962351 0.1059620604 621 24.8000000000 0.5488612652 96.9153823063 456.8115844727 21.2360954142 0.1461950000 710105374 0 1765769216 0.0451278128 0.0389802903 0.1079674587 622 24.8400000000 0.5429821610 96.7604427563 456.8115844727 21.2189902207 0.1439750000 710106628 0 1766387712 0.0413524993 0.0415669605 0.1035460755 623 24.8800000000 0.5260822177 96.6059734777 456.8115844727 21.2019263136 0.1535790000 710107882 0 1766641664 0.0304782521 0.0341504812 0.0911817998 624 24.9200000000 0.5059294701 96.4519669969 456.8115844727 21.1849035768 0.1651660000 710109136 0 1767022592 0.0066808192 0.0092379861 0.0815676972 625 24.9600000000 0.4962549210 96.2984378576 456.8115844727 21.1679217237 0.1464410000 710110390 0 1767530496 -0.0084921438 -0.0058114100 0.0789038837 626 25.0000000000 0.4960875511 96.1453989593 456.8115844727 21.1509808805 0.1918760000 710111644 0 1768038400 -0.0446918122 -0.0546963178 0.0905962735 627 25.0400000000 0.4940210879 95.9928449276 456.8115844727 21.1340803773 0.1500730000 710112898 0 1768546304 -0.0488475673 -0.0599222332 0.0895717815 628 25.0800000000 0.4857862294 95.8407636240 456.8115844727 21.1172203258 0.1487960000 710114152 0 1769054208 -0.0583400726 -0.0642532483 0.0838634893 629 25.1200000000 0.4792529941 95.6891554990 456.8115844727 21.1004005619 0.1487640000 710115406 0 1769689088 -0.0652194768 -0.0703896657 0.0781330988 630 25.1600000000 0.4752960205 95.5380223887 456.8115844727 21.0836209271 0.1628960000 715032568 0 1775022080 -0.0681572184 -0.0794469938 0.0738860294 631 25.2000000000 0.4743174613 95.3873667549 456.8115844727 21.0668812493 0.0401780000 725946350 0 1775656960 -0.0681572184 -0.0794469938 0.0738860294 632 25.2400000000 0.4738376737 95.2371871203 456.8115844727 21.0501813809 0.0300180000 725947624 0 1776291840 -0.0681572184 -0.0794469938 0.0738860294 633 25.2800000000 0.4736236632 95.0874816488 456.8115844727 21.0335211640 0.0365990000 725948898 0 1776799744 -0.0681572184 -0.0794469938 0.0738860294 634 25.3200000000 0.4724819362 94.9382466335 456.8115844727 21.0169004416 0.0361320000 725950172 0 1777307648 -0.0681572184 -0.0794469938 0.0738860294 635 25.3600000000 0.4711474478 94.7894795481 456.8115844727 21.0003190581 0.0326080000 725951446 0 1777942528 -0.0681572184 -0.0794469938 0.0738860294 636 25.4000000000 0.4709740877 94.6411800112 456.8115844727 20.9837768589 0.0318260000 725952720 0 1778450432 -0.0681572184 -0.0794469938 0.0738860294 637 25.4400000000 0.4699832797 94.4933445376 456.8115844727 20.9672736894 0.0353100000 725953994 0 1778958336 -0.0681572184 -0.0794469938 0.0738860294 638 25.4800000000 0.4688597620 94.3459707370 456.8115844727 20.9508093966 0.0361620000 725955268 0 1779466240 -0.0681572184 -0.0794469938 0.0738860294 639 25.5200000000 0.4681903720 94.1990571527 456.8115844727 20.9343838283 0.0372760000 725956542 0 1779974144 -0.0681572184 -0.0794469938 0.0738860294 640 25.5600000000 0.4670734704 94.0526009282 456.8115844727 20.9179968327 0.0316250000 725957816 0 1780609024 -0.0681572184 -0.0794469938 0.0738860294 641 25.6000000000 0.4658430517 93.9065997458 456.8115844727 20.9016482592 0.0315460000 725959090 0 1781116928 -0.0681572184 -0.0794469938 0.0738860294 642 25.6400000000 0.4651687741 93.7610523456 456.8115844727 20.8853379576 0.0256460000 725960364 0 1781624832 -0.0681572184 -0.0794469938 0.0738860294 643 25.6800000000 0.4644508362 93.6159565423 456.8115844727 20.8690657793 0.0327280000 725961638 0 1782132736 -0.0681572184 -0.0794469938 0.0738860294 644 25.7200000000 0.4630798101 93.4713092182 456.8115844727 20.8528315756 0.0254810000 725962912 0 1782767616 -0.0681572184 -0.0794469938 0.0738860294 645 25.7600000000 0.4617271721 93.3271083158 456.8115844727 20.8366351992 0.0301010000 725964186 0 1783275520 -0.0681572184 -0.0794469938 0.0738860294 646 25.8000000000 0.4608927369 93.1833525641 456.8115844727 20.8204765040 0.0316370000 725965460 0 1783783424 -0.0681572184 -0.0794469938 0.0738860294 647 25.8400000000 0.4595863223 93.0400391696 456.8115844727 20.8043553430 0.0312910000 725966734 0 1784291328 -0.0681572184 -0.0794469938 0.0738860294 648 25.8800000000 0.4582850337 92.8971660922 456.8115844727 20.7882715715 0.0319050000 725968008 0 1784799232 -0.0681572184 -0.0794469938 0.0738860294 649 25.9200000000 0.4573040605 92.7547317902 456.8115844727 20.7722250456 0.0321160000 725969282 0 1785434112 -0.0681572184 -0.0794469938 0.0738860294 650 25.9600000000 0.4562154114 92.6127340727 456.8115844727 20.7562156219 0.0317120000 725970556 0 1785942016 -0.0681572184 -0.0794469938 0.0738860294 651 26.0000000000 0.4553316534 92.4711712425 456.8115844727 20.7402431571 0.0283450000 725971830 0 1786449920 -0.0681572184 -0.0794469938 0.0738860294 652 26.0400000000 0.4550445974 92.3300422139 456.8115844727 20.7243075092 0.0284870000 725973104 0 1786957824 -0.0681572184 -0.0794469938 0.0738860294 653 26.0800000000 0.4544131160 92.1893444665 456.8115844727 20.7084085369 0.0332370000 725974378 0 1787465728 -0.0681572184 -0.0794469938 0.0738860294 654 26.1200000000 0.4516555667 92.0490727709 456.8115844727 20.6925461023 0.0278140000 725975652 0 1788100608 -0.0681572184 -0.0794469938 0.0738860294 655 26.1600000000 0.4508034289 91.9092280849 456.8115844727 20.6767200611 0.0309690000 725976926 0 1786605568 -0.0681572184 -0.0794469938 0.0738860294 656 26.2000000000 0.4494009912 91.7698076168 456.8115844727 20.6609302770 0.0301510000 725978200 0 1786974208 -0.0681572184 -0.0794469938 0.0738860294 657 26.2400000000 0.4478653669 91.6308092267 456.8115844727 20.6451766111 0.0326830000 725979474 0 1786081280 -0.0681572184 -0.0794469938 0.0738860294 658 26.2800000000 0.4468525946 91.4922317850 456.8115844727 20.6294589259 0.0285010000 725980748 0 1786089472 -0.0681572184 -0.0794469938 0.0738860294 659 26.3200000000 0.4464120567 91.3540742437 456.8115844727 20.6137770850 0.0281630000 725982022 0 1786593280 -0.0681572184 -0.0794469938 0.0738860294 660 26.3600000000 0.4451629221 91.2163334690 456.8115844727 20.5981309522 0.0230910000 725983296 0 1787101184 -0.0681572184 -0.0794469938 0.0738860294 661 26.4000000000 0.4433950484 91.0790067845 456.8115844727 20.5825203925 0.0328520000 725984570 0 1784967168 -0.0681572184 -0.0794469938 0.0738860294 662 26.4400000000 0.4424554408 90.9420935650 456.8115844727 20.5669452713 0.0280760000 725985844 0 1784967168 -0.0681572184 -0.0794469938 0.0738860294 663 26.4800000000 0.4415268302 90.8055919560 456.8115844727 20.5514054547 0.0322440000 725987118 0 1785450496 -0.0681572184 -0.0794469938 0.0738860294 664 26.5200000000 0.4401863217 90.6694994777 456.8115844727 20.5359008099 0.0285170000 725988392 0 1785958400 -0.0681572184 -0.0794469938 0.0738860294 665 26.5600000000 0.4394620359 90.5338152108 456.8115844727 20.5204312038 0.0318340000 725989666 0 1786466304 -0.0681572184 -0.0794469938 0.0738860294 666 26.6000000000 0.4386112988 90.3985371269 456.8115844727 20.5049965057 0.0204000000 725990940 0 1786847232 -0.0681572184 -0.0794469938 0.0738860294 667 26.6400000000 0.4381494820 90.2636639820 456.8115844727 20.4895965829 0.0245600000 725992214 0 1787084800 -0.0681572184 -0.0794469938 0.0738860294 668 26.6800000000 0.4373311102 90.1291934238 456.8115844727 20.4742313060 0.0303700000 725993488 0 1787592704 -0.0681572184 -0.0794469938 0.0738860294 669 26.7200000000 0.4369818866 89.9951243483 456.8115844727 20.4589005451 0.0242050000 725994762 0 1788100608 -0.0681572184 -0.0794469938 0.0738860294 670 26.7600000000 0.4368754327 89.8614553200 456.8115844727 20.4436041731 0.0263470000 725996036 0 1786351616 -0.0681572184 -0.0794469938 0.0738860294 671 26.8000000000 0.4370929599 89.7281850334 456.8115844727 20.4283420585 0.0286780000 725997310 0 1786720256 -0.0681572184 -0.0794469938 0.0738860294 672 26.8400000000 0.4369317889 89.5953111446 456.8115844727 20.4131140728 0.0270190000 725998584 0 1787228160 -0.0681572184 -0.0794469938 0.0738860294 673 26.8800000000 0.4368007481 89.4628319315 456.8115844727 20.3979200919 0.0290230000 725999858 0 1785864192 -0.0681572184 -0.0794469938 0.0738860294 674 26.9200000000 0.4370755255 89.3307462395 456.8115844727 20.3827599878 0.0238800000 726001132 0 1785864192 -0.0681572184 -0.0794469938 0.0738860294 675 26.9600000000 0.4380031228 89.1990532868 456.8115844727 20.3676336333 0.0320480000 726002406 0 1786339328 -0.0681572184 -0.0794469938 0.0738860294 676 27.0000000000 0.4376648962 89.0677494578 456.8115844727 20.3525409055 0.0429590000 726003680 0 1785454592 -0.0681572184 -0.0794469938 0.0738860294 677 27.0400000000 0.4386574626 88.9368349940 456.8115844727 20.3374816804 0.0305990000 726004954 0 1785454592 -0.0681572184 -0.0794469938 0.0738860294 678 27.0800000000 0.4391468465 88.8063074303 456.8115844727 20.3224558333 0.0245230000 726006228 0 1784963072 -0.0681572184 -0.0794469938 0.0738860294 679 27.1200000000 0.4401302338 88.6761657850 456.8115844727 20.3074632416 0.0317930000 726007502 0 1784942592 -0.0681572184 -0.0794469938 0.0738860294 680 27.1600000000 0.4413760006 88.5464087412 456.8115844727 20.2925037828 0.0412710000 726008776 0 1785450496 -0.0681572184 -0.0794469938 0.0738860294 681 27.2000000000 0.4424807131 88.4170343975 456.8115844727 20.2775773353 0.0375170000 726010050 0 1784565760 -0.0681572184 -0.0794469938 0.0738860294 682 27.2400000000 0.4439710379 88.2880416360 456.8115844727 20.2626837776 0.0333590000 726011324 0 1784565760 -0.0681572184 -0.0794469938 0.0738860294 683 27.2800000000 0.4451397061 88.1594283096 456.8115844727 20.2478229887 0.0411720000 726012598 0 1784061952 -0.0681572184 -0.0794469938 0.0738860294 684 27.3200000000 0.4468265474 88.0311935117 456.8115844727 20.2329948489 0.0511250000 726013872 0 1784061952 -0.0681572184 -0.0794469938 0.0738860294 685 27.3600000000 0.4475821853 87.9033342251 456.8115844727 20.2181992386 0.0334390000 726015146 0 1783439360 -0.0681572184 -0.0794469938 0.0738860294 686 27.4000000000 0.4491358101 87.7758499709 456.8115844727 20.2034360396 0.0387990000 726016420 0 1783427072 -0.0681572184 -0.0794469938 0.0738860294 687 27.4400000000 0.4511295557 87.6487397519 456.8115844727 20.1887051339 0.0381140000 726017694 0 1783926784 -0.0681572184 -0.0794469938 0.0738860294 688 27.4800000000 0.4531050324 87.5220019108 456.8115844727 20.1740064032 0.0381810000 726018968 0 1783189504 -0.0681572184 -0.0794469938 0.0738860294 689 27.5200000000 0.4552496970 87.3956350715 456.8115844727 20.1593397307 0.0415890000 726020242 0 1783189504 -0.0681572184 -0.0794469938 0.0738860294 690 27.5600000000 0.4577285647 87.2696381056 456.8115844727 20.1447050006 0.0360870000 726021516 0 1782427648 -0.0681572184 -0.0794469938 0.0738860294 691 27.6000000000 0.4603368044 87.1440095943 456.8115844727 20.1301020964 0.0410010000 726022790 0 1782427648 -0.0681572184 -0.0794469938 0.0738860294 692 27.6400000000 0.4629583061 87.0187479595 456.8115844727 20.1155309044 0.0408590000 726024064 0 1782784000 -0.0681572184 -0.0794469938 0.0738860294 693 27.6800000000 0.4649036229 86.8938506372 456.8115844727 20.1009913089 0.0339830000 726025338 0 1783291904 -0.0681572184 -0.0794469938 0.0738860294 694 27.7200000000 0.4672589004 86.7693166434 456.8115844727 20.0864831952 0.0361220000 726026612 0 1783926784 -0.0681572184 -0.0794469938 0.0738860294 695 27.7600000000 0.4692849815 86.6451439359 456.8115844727 20.0720064499 0.0375610000 726027886 0 1784180736 -0.0681572184 -0.0794469938 0.0738860294 696 27.8000000000 0.4710379839 86.5213305653 456.8115844727 20.0575609603 0.0331750000 726029160 0 1784418304 -0.0681572184 -0.0794469938 0.0738860294 697 27.8400000000 0.4763903618 86.3978801490 456.8115844727 20.0431466152 0.0578930000 726030434 0 1785053184 -0.0681572184 -0.0794469938 0.0738860294 698 27.8800000000 0.4780937135 86.2747858990 456.8115844727 20.0287633010 0.0376080000 726031708 0 1785561088 -0.0681572184 -0.0794469938 0.0738860294 699 27.9200000000 0.4824891686 86.1520501383 456.8115844727 20.0144109087 0.0356180000 726032982 0 1786068992 -0.0681572184 -0.0794469938 0.0738860294 700 27.9600000000 0.4846348464 86.0296681165 456.8115844727 20.0000893252 0.0394440000 726034256 0 1786576896 -0.0681572184 -0.0794469938 0.0738860294 701 28.0000000000 0.4860007763 85.9076372073 456.8115844727 19.9857984418 0.0424070000 726035530 0 1787211776 -0.0681572184 -0.0794469938 0.0738860294 702 28.0400000000 0.4876014888 85.7859562447 456.8115844727 19.9715381496 0.0342730000 726036804 0 1787719680 -0.0681572184 -0.0794469938 0.0738860294 703 28.0800000000 0.4898405373 85.6646246435 456.8115844727 19.9573083396 0.0580110000 726038078 0 1786351616 -0.0681572184 -0.0794469938 0.0738860294 704 28.1200000000 0.4915844202 85.5436402113 456.8115844727 19.9431089016 0.0578380000 726039352 0 1786351616 -0.0681572184 -0.0794469938 0.0738860294 705 28.1600000000 0.4930543900 85.4230010825 456.8115844727 19.9289397286 0.0410660000 726040626 0 1786847232 -0.0681572184 -0.0794469938 0.0738860294 706 28.2000000000 0.4946155250 85.3027059188 456.8115844727 19.9148007145 0.0400050000 726041900 0 1787355136 -0.0681572184 -0.0794469938 0.0738860294 707 28.2400000000 0.4966185987 85.1827538858 456.8115844727 19.9006917514 0.0417710000 726043174 0 1787863040 -0.0681572184 -0.0794469938 0.0738860294 708 28.2800000000 0.4985258281 85.0631433942 456.8115844727 19.8866127323 0.0423140000 726044448 0 1787973632 -0.0681572184 -0.0794469938 0.0738860294 709 28.3200000000 0.4994767904 84.9438716501 456.8115844727 19.8725635521 0.0425230000 726045722 0 1786220544 -0.0681572184 -0.0794469938 0.0738860294 710 28.3600000000 0.5004215837 84.8249372134 456.8115844727 19.8585441058 0.0404210000 726046996 0 1786466304 -0.0681572184 -0.0794469938 0.0738860294 711 28.4000000000 0.5021574497 84.7063397735 456.8115844727 19.8445542884 0.0449820000 726048270 0 1785581568 -0.0681572184 -0.0794469938 0.0738860294 712 28.4400000000 0.5027388930 84.5880762891 456.8115844727 19.8305939959 0.0389600000 726049544 0 1785581568 -0.0681572184 -0.0794469938 0.0738860294 713 28.4800000000 1.1260044575 84.4710186848 456.8115844727 19.8167660565 0.0996240000 726050818 0 1785958400 -0.9595161676 -0.5867250562 -0.4678947330 714 28.5200000000 1.3378822803 84.3545857207 456.8115844727 19.8028669348 0.1310070000 720053220 0 1787973632 -1.0800040960 -0.7790067196 -0.2983394861 715 28.5600000000 1.3409808874 84.2384827769 456.8115844727 19.7889945243 0.0399860000 730968682 0 1786347520 -1.0800040960 -0.7790067196 -0.2983394861 716 28.6000000000 1.3436057568 84.1227078090 456.8115844727 19.7751512268 0.0339120000 730969956 0 1786466304 -1.0800040960 -0.7790067196 -0.2983394861 717 28.6400000000 1.3457713127 84.0072588041 456.8115844727 19.7613369414 0.0311120000 730971230 0 1785487360 -1.0800040960 -0.7790067196 -0.2983394861 718 28.6800000000 1.3479424715 83.8921344081 456.8115844727 19.7475515651 0.0389470000 730972504 0 1785487360 -1.0800040960 -0.7790067196 -0.2983394861 719 28.7200000000 1.3500707150 83.7773332068 456.8115844727 19.7337949983 0.0309300000 730973778 0 1785974784 -1.0800040960 -0.7790067196 -0.2983394861 720 28.7600000000 1.3524875641 83.6628542545 456.8115844727 19.7200671414 0.0340240000 730975052 0 1785323520 -1.0800040960 -0.7790067196 -0.2983394861 721 28.8000000000 1.3559316397 83.5486976351 456.8115844727 19.7063678941 0.0332450000 730976326 0 1785323520 -1.0800040960 -0.7790067196 -0.2983394861 722 28.8400000000 1.3590141535 83.4348615084 456.8115844727 19.6926971562 0.0310470000 730977600 0 1785094144 -1.0800040960 -0.7790067196 -0.2983394861 723 28.8800000000 1.3618378639 83.3213441866 456.8115844727 19.6790548298 0.0347760000 730978874 0 1785094144 -1.0800040960 -0.7790067196 -0.2983394861 724 28.9200000000 1.3646832705 83.2081443787 456.8115844727 19.6654408173 0.0300970000 730980148 0 1785569280 -1.0800040960 -0.7790067196 -0.2983394861 725 28.9600000000 1.3676108122 83.0952608842 456.8115844727 19.6518550210 0.0376730000 730981422 0 1784684544 -1.0800040960 -0.7790067196 -0.2983394861 726 29.0000000000 1.3701649904 82.9826918815 456.8115844727 19.6382973431 0.0393010000 730982696 0 1784684544 -1.0800040960 -0.7790067196 -0.2983394861 727 29.0400000000 1.3738961220 82.8704376921 456.8115844727 19.6247676874 0.0336440000 730983970 0 1784213504 -1.0800040960 -0.7790067196 -0.2983394861 728 29.0800000000 1.3773980141 82.7584967035 456.8115844727 19.6112659547 0.0330940000 730985244 0 1784201216 -1.0800040960 -0.7790067196 -0.2983394861 729 29.1200000000 1.3798249960 82.6468661525 456.8115844727 19.5977920505 0.0362720000 730986518 0 1784680448 -1.0800040960 -0.7790067196 -0.2983394861 730 29.1600000000 1.3824352026 82.5355450142 456.8115844727 19.5843458802 0.0350950000 730987792 0 1783795712 -1.0800040960 -0.7790067196 -0.2983394861 731 29.2000000000 1.3858906031 82.4245331750 456.8115844727 19.5709273493 0.0321840000 730989066 0 1783795712 -1.0800040960 -0.7790067196 -0.2983394861 732 29.2400000000 0.5408383608 82.3126702040 456.8115844727 19.5575677942 0.1479670000 730990340 0 1783324672 -0.4108691216 -0.2523251772 -0.4056287706 733 29.2800000000 0.7038409710 82.2013348298 456.8115844727 19.5442047490 0.1433870000 724992386 0 1787584512 -0.5749126077 -0.2754990458 -0.4053158462 734 29.3200000000 0.7072385550 82.0903074507 456.8115844727 19.5308685464 0.0385460000 735908228 0 1786470400 -0.5749126077 -0.2754990458 -0.4053158462 735 29.3600000000 0.7100993395 81.9795860791 456.8115844727 19.5175596072 0.0400340000 735909502 0 1786470400 -0.5749126077 -0.2754990458 -0.4053158462 736 29.4000000000 0.7127962112 81.8691692451 456.8115844727 19.5042778387 0.0412000000 735910776 0 1786232832 -0.5749126077 -0.2754990458 -0.4053158462 737 29.4400000000 0.7154961824 81.7590557131 456.8115844727 19.4910231486 0.0387510000 735912050 0 1786232832 -0.5749126077 -0.2754990458 -0.4053158462 738 29.4800000000 0.7184398770 81.6492445805 456.8115844727 19.4777954446 0.0364570000 735913324 0 1785724928 -0.5749126077 -0.2754990458 -0.4053158462 739 29.5200000000 0.7207149267 81.5397337150 456.8115844727 19.4645946343 0.0353800000 735914598 0 1785679872 -0.5749126077 -0.2754990458 -0.4053158462 740 29.5600000000 0.5025132895 81.4302239576 456.8115844727 19.4514758091 0.0834550000 735915872 0 1785339904 0.0115858791 0.1588230431 0.0629519373 741 29.6000000000 0.4496728778 81.3209384636 456.8115844727 19.4383288599 0.1503950000 729917798 0 1786949632 -0.0065241093 0.1492924988 0.0047926521 742 29.6400000000 0.3958241940 81.2118749673 456.8115844727 19.4252099382 0.0955930000 740833800 0 1785831424 -0.1212818921 0.1226191074 -0.1046628579 743 29.6800000000 0.3592178524 81.1030557787 456.8115844727 19.4121200548 0.1495260000 734835726 0 1786695680 -0.1863474995 -0.0623888038 -0.1945659518 744 29.7200000000 0.3605023324 80.9945308413 456.8115844727 19.3990523218 0.0459130000 745751768 0 1785581568 -0.1863474995 -0.0623888038 -0.1945659518 745 29.7600000000 0.3621448278 80.8862994507 456.8115844727 19.3860109436 0.0419700000 745753042 0 1785581568 -0.1863474995 -0.0623888038 -0.1945659518 746 29.8000000000 0.3637147248 80.7783603290 456.8115844727 19.3729958303 0.0427330000 745754316 0 1785229312 -0.1863474995 -0.0623888038 -0.1945659518 747 29.8400000000 0.3643903732 80.6707111055 456.8115844727 19.3600068952 0.0387330000 745755590 0 1785217024 -0.1863474995 -0.0623888038 -0.1945659518 748 29.8800000000 0.3666810393 80.5633527766 456.8115844727 19.3470440599 0.0442690000 745756864 0 1784184832 -0.1863474995 -0.0623888038 -0.1945659518 749 29.9200000000 0.3681307137 80.4562830542 456.8115844727 19.3341072200 0.0429550000 745758138 0 1784193024 -0.1863474995 -0.0623888038 -0.1945659518 750 29.9600000000 0.3691931665 80.3495002677 456.8115844727 19.3211962962 0.0394790000 745759412 0 1784680448 -0.1863474995 -0.0623888038 -0.1945659518 751 30.0000000000 0.3706212938 80.2430037577 456.8115844727 19.3083112028 0.0398800000 745760686 0 1784205312 -0.1863474995 -0.0623888038 -0.1945659518 752 30.0400000000 0.3720900118 80.1367924363 456.8115844727 19.2954518540 0.0432310000 745761960 0 1784426496 -0.1863474995 -0.0623888038 -0.1945659518 753 30.0800000000 0.5822871923 80.0311423629 456.8115844727 19.2826437435 0.0558580000 745763234 0 1783816192 -0.2925205529 0.2972625196 -0.6372153163 754 30.1200000000 0.9266038537 79.9262291818 456.8115844727 19.2698479038 0.1181860000 739764940 0 1788092416 -0.5881939530 0.1202022433 -0.9547102451 755 30.1600000000 0.9282881021 79.8215961473 456.8115844727 19.2570652508 0.0421100000 750681202 0 1786470400 -0.5881939530 0.1202022433 -0.9547102451 756 30.2000000000 0.9301695824 79.7172424085 456.8115844727 19.2443080021 0.0420070000 750682476 0 1786839040 -0.5881939530 0.1202022433 -0.9547102451 757 30.2400000000 0.9322020411 79.6131670579 456.8115844727 19.2315760757 0.0377880000 750683750 0 1786081280 -0.5881939530 0.1202022433 -0.9547102451 758 30.2800000000 0.7573574185 79.5091356468 456.8115844727 19.2189702675 0.0966630000 750685024 0 1786081280 -0.0237466432 0.5516751409 0.0862493590 759 30.3200000000 0.8608598113 79.4055147300 456.8115844727 19.2062893053 0.1487480000 744686570 0 1787457536 -0.0125125833 0.6620463133 0.1201995239 760 30.3600000000 0.4369533360 79.3016087282 456.8115844727 19.1936582371 0.0755290000 755602932 0 1786486784 -0.1766340733 0.2708331645 -0.3137171268 761 30.4000000000 0.5571061969 79.1981336920 456.8115844727 19.1810333249 0.1202440000 749604498 0 1787838464 -0.3194983900 0.2020023465 -0.5973573923 762 30.4400000000 0.5594251752 79.0949332871 456.8115844727 19.1684266658 0.0447600000 760520900 0 1785954304 -0.3194983900 0.2020023465 -0.5973573923 763 30.4800000000 0.5616140366 78.9920062632 456.8115844727 19.1558448301 0.0460250000 760522174 0 1786077184 -0.3194983900 0.2020023465 -0.5973573923 764 30.5200000000 0.5640033484 78.8893518091 456.8115844727 19.1432877372 0.0439430000 760523448 0 1786712064 -0.3194983900 0.2020023465 -0.5973573923 765 30.5600000000 0.5660586953 78.7869684194 456.8115844727 19.1307553077 0.0416750000 760524722 0 1787219968 -0.3194983900 0.2020023465 -0.5973573923 766 30.6000000000 0.5680264235 78.6848549181 456.8115844727 19.1182474600 0.0457000000 760525996 0 1787727872 -0.3194983900 0.2020023465 -0.5973573923 767 30.6400000000 0.5701662302 78.5830104739 456.8115844727 19.1057641115 0.0482020000 760527270 0 1787965440 -0.3194983900 0.2020023465 -0.5973573923 768 30.6800000000 0.5721367002 78.4814338154 456.8115844727 19.0933051839 0.0439120000 760528544 0 1786470400 -0.3194983900 0.2020023465 -0.5973573923 769 30.7200000000 0.5737063289 78.3801233765 456.8115844727 19.0808705982 0.0400840000 760529818 0 1786585088 -0.3194983900 0.2020023465 -0.5973573923 770 30.7600000000 0.5751793385 78.2790779946 456.8115844727 19.0684602746 0.0407660000 760531092 0 1786085376 -0.3194983900 0.2020023465 -0.5973573923 771 30.8000000000 0.5770359635 78.1782971360 456.8115844727 19.0560741355 0.0404220000 760532366 0 1786085376 -0.3194983900 0.2020023465 -0.5973573923 772 30.8400000000 0.5784053802 78.0777791415 456.8115844727 19.0437121023 0.0444940000 760533640 0 1785581568 -0.3194983900 0.2020023465 -0.5973573923 773 30.8800000000 0.5800622106 77.9775233628 456.8115844727 19.0313740958 0.0414070000 760534914 0 1785581568 -0.3194983900 0.2020023465 -0.5973573923 774 30.9200000000 0.5815658569 77.8775285856 456.8115844727 19.0190600383 0.0454230000 760536188 0 1785339904 -0.3194983900 0.2020023465 -0.5973573923 775 30.9600000000 0.5826366544 77.7777932412 456.8115844727 19.0067698529 0.0449370000 760537462 0 1785339904 -0.3194983900 0.2020023465 -0.5973573923 776 31.0000000000 0.5839588642 77.6783166505 456.8115844727 18.9945034632 0.0468740000 760538736 0 1784815616 -0.3194983900 0.2020023465 -0.5973573923 777 31.0400000000 0.5852833390 77.5790978174 456.8115844727 18.9822607925 0.0436480000 760540010 0 1784815616 -0.3194983900 0.2020023465 -0.5973573923 778 31.0800000000 0.5858652592 77.4801347936 456.8115844727 18.9700417646 0.0431360000 760541284 0 1784459264 -0.3194983900 0.2020023465 -0.5973573923 779 31.1200000000 0.5863324404 77.3814264465 456.8115844727 18.9578463038 0.0481360000 760542558 0 1784459264 -0.3194983900 0.2020023465 -0.5973573923 780 31.1600000000 0.5870577693 77.2829721277 456.8115844727 18.9456743358 0.0438470000 760543832 0 1784197120 -0.3194983900 0.2020023465 -0.5973573923 781 31.2000000000 0.5876884460 77.1847707402 456.8115844727 18.9335257831 0.0477970000 760545106 0 1784197120 -0.3194983900 0.2020023465 -0.5973573923 782 31.2400000000 0.5882572532 77.0868212344 456.8115844727 18.9214005706 0.0429070000 760546380 0 1783414784 -0.3194983900 0.2020023465 -0.5973573923 783 31.2800000000 0.5888074636 76.9891226217 456.8115844727 18.9092986232 0.0426130000 760547654 0 1783414784 -0.3194983900 0.2020023465 -0.5973573923 784 31.3200000000 0.5894215703 76.8916740234 456.8115844727 18.8972198647 0.0416120000 760548928 0 1783918592 -0.3194983900 0.2020023465 -0.5973573923 785 31.3600000000 0.5900331140 76.7944744808 456.8115844727 18.8851642214 0.0443560000 760550202 0 1784426496 -0.3194983900 0.2020023465 -0.5973573923 786 31.4000000000 0.5904254913 76.6975227646 456.8115844727 18.8731316212 0.0416730000 760551476 0 1784934400 -0.3194983900 0.2020023465 -0.5973573923 787 31.4400000000 0.5908385515 76.6008179562 456.8115844727 18.8611219924 0.0380560000 760552750 0 1785315328 -0.3194983900 0.2020023465 -0.5973573923 788 31.4800000000 0.5913255215 76.5043592094 456.8115844727 18.8491352611 0.0398600000 760554024 0 1785552896 -0.3194983900 0.2020023465 -0.5973573923 789 31.5200000000 0.5917056799 76.4081454534 456.8115844727 18.8371713547 0.0471310000 760555298 0 1786060800 -0.3194983900 0.2020023465 -0.5973573923 790 31.5600000000 0.5921193957 76.3121758001 456.8115844727 18.8252302040 0.0391760000 760556572 0 1786568704 -0.3194983900 0.2020023465 -0.5973573923 791 31.6000000000 0.5928671956 76.2164497463 456.8115844727 18.8133117344 0.0375220000 760557846 0 1787076608 -0.3194983900 0.2020023465 -0.5973573923 792 31.6400000000 0.5936617851 76.1209664281 456.8115844727 18.8014158700 0.0374500000 760559120 0 1787711488 -0.3194983900 0.2020023465 -0.5973573923 793 31.6800000000 0.5939738750 76.0257243190 456.8115844727 18.7895425429 0.0387950000 760560394 0 1786339328 -0.3194983900 0.2020023465 -0.5973573923 794 31.7200000000 0.5944324732 75.9307226920 456.8115844727 18.7776916833 0.0404440000 760561668 0 1786343424 -0.3194983900 0.2020023465 -0.5973573923 795 31.7600000000 0.5949983001 75.8359607745 456.8115844727 18.7658632198 0.0381120000 760562942 0 1785573376 -0.3194983900 0.2020023465 -0.5973573923 796 31.8000000000 0.5953323245 75.7414373719 456.8115844727 18.7540570814 0.0395630000 760564216 0 1785573376 -0.3194983900 0.2020023465 -0.5973573923 797 31.8400000000 0.5958142281 75.6471517720 456.8115844727 18.7422732037 0.0393140000 760565490 0 1785950208 -0.3194983900 0.2020023465 -0.5973573923 798 31.8800000000 0.5958380103 75.5531025066 456.8115844727 18.7305115134 0.0392440000 760566764 0 1786585088 -0.3194983900 0.2020023465 -0.5973573923 799 31.9200000000 0.5963311791 75.4592892759 456.8115844727 18.7187719323 0.0397340000 760568038 0 1787092992 -0.3194983900 0.2020023465 -0.5973573923 800 31.9600000000 0.5968309045 75.3657112030 456.8115844727 18.7070543933 0.0402000000 760569312 0 1787473920 -0.3194983900 0.2020023465 -0.5973573923 801 32.0000000000 0.5975520611 75.2723676834 456.8115844727 18.6953588294 0.0406890000 760570586 0 1787584512 -0.3194983900 0.2020023465 -0.5973573923 802 32.0400000000 0.5982807279 75.1792578493 456.8115844727 18.6836851745 0.0412080000 760571860 0 1788092416 -0.3194983900 0.2020023465 -0.5973573923 803 32.0800000000 0.5989398360 75.0863807410 456.8115844727 18.6720333598 0.0401300000 760573134 0 1786486784 -0.3194983900 0.2020023465 -0.5973573923 804 32.1199999990 0.5970591903 74.9937323311 456.8115844727 18.6604412525 0.0673690000 760574408 0 1785323520 0.0953711197 0.1407915503 0.1849199533 805 32.1600000000 0.6032242179 74.9013217620 456.8115844727 18.6488328921 0.0880360000 749658362 0 1785323520 0.0881869048 0.1377017498 0.1911722869 806 32.2000000000 0.6089181900 74.8091475640 456.8115844727 18.6372461753 0.0965150000 749659616 0 1785683968 0.0796639249 0.1423648298 0.1947480738 807 32.2400000000 0.6257522702 74.7172226628 456.8115844727 18.6256810665 0.0878690000 749660870 0 1786187776 0.0686622486 0.1532197595 0.2077072561 808 32.2800000000 0.6306163669 74.6255313184 456.8115844727 18.6141374302 0.0874350000 749662124 0 1786822656 0.0591920204 0.1629261971 0.2084608525 809 32.3200000000 0.6360412240 74.5340733578 456.8115844727 18.6026152201 0.0838140000 749663378 0 1787330560 0.0521157682 0.1672857255 0.2117117643 810 32.3600000000 0.6808903217 74.4428965886 456.8115844727 18.5911144732 0.0864580000 749664632 0 1787330560 0.0216734447 0.1912596524 0.2451337129 811 32.4000000000 0.6811096072 74.3519449401 456.8115844727 18.5796349373 0.0849770000 749665886 0 1787838464 0.0169277675 0.1928351074 0.2439941466 812 32.4399999990 0.6849537492 74.2612220445 456.8115844727 18.5681766456 0.0834840000 749667140 0 1786486784 0.0137279686 0.1981013715 0.2461404949 813 32.4800000000 0.6867385507 74.1707245248 456.8115844727 18.5567395268 0.0833050000 749668394 0 1786601472 0.0156496800 0.2081111819 0.2459123582 814 32.5200000000 0.6891899705 74.0804523694 456.8115844727 18.5453235207 0.0846540000 749669648 0 1787236352 0.0234480612 0.2208518982 0.2472261637 815 32.5600000000 0.6916992068 73.9904048195 456.8115844727 18.5339285522 0.0858400000 749670902 0 1787744256 0.0253180768 0.2330749482 0.2467547655 816 32.6000000000 0.6925557256 73.9005790240 456.8115844727 18.5225545632 0.0808610000 749672156 0 1787998208 0.0304188225 0.2463280410 0.2446379811 817 32.6400000000 0.6994439363 73.8109815514 456.8115844727 18.5112014850 0.1179140000 753217530 0 1783812096 0.0259066541 0.2531485558 0.2489697337 818 32.6800000000 0.6987929940 73.7216023478 456.8115844727 18.4998692535 0.0461900000 760591612 0 1783808000 0.0259066541 0.2531485558 0.2489697337 819 32.7200000000 0.6980028152 73.6324404436 456.8115844727 18.4885578086 0.0425120000 760592886 0 1784283136 0.0259066541 0.2531485558 0.2489697337 820 32.7599999990 0.5248655677 73.5432848645 456.8115844727 18.4772705188 0.0891000000 760594160 0 1784791040 0.0003392964 0.0597053170 0.1042163894 821 32.7999999990 0.5262132883 73.4543481147 456.8115844727 18.4660004726 0.1241080000 749678986 0 1785298944 -0.0062702103 0.0547793731 0.1039718613 822 32.8400000000 0.5277854204 73.3656296686 456.8115844727 18.4547510189 0.1239060000 749680240 0 1785806848 -0.0107100355 0.0558538698 0.1044290438 823 32.8800000000 0.5229011774 73.2771208855 456.8115844727 18.4435221064 0.1215640000 749681494 0 1786314752 -0.0122121405 0.0575996526 0.0990806967 824 32.9200000000 0.4963516891 73.1887947093 456.8115844727 18.4323139302 0.1176710000 749682748 0 1786822656 -0.0369191244 0.0604722761 0.0560900681 825 32.9600000000 0.4245604873 73.1005956375 456.8115844727 18.4211435944 0.2260270000 753227982 0 1785217024 -0.2072556466 -0.0354096889 -0.4230781496 826 33.0000000000 0.4244470000 73.0126099854 456.8115844727 18.4099758829 0.0406950000 760602064 0 1785200640 -0.2072556466 -0.0354096889 -0.4230781496 827 33.0400000000 0.4243031442 72.9248369421 456.8115844727 18.3988284570 0.0349660000 760603338 0 1785696256 -0.2072556466 -0.0354096889 -0.4230781496 828 33.0800000000 1.0049304962 72.8379771517 456.8115844727 18.3877081449 0.1096420000 760604612 0 1786187776 -0.7534652352 -0.2835271358 -0.3190307021 829 33.1199999990 1.0959987640 72.7514367676 456.8115844727 18.3766013871 0.1288980000 753233182 0 1784033280 -0.8478904963 -0.2858103812 -0.3205288053 830 33.1600000000 1.0956850052 72.6651045366 456.8115844727 18.3655144486 0.0395870000 760607264 0 1784045568 -0.8478904963 -0.2858103812 -0.3205288053 831 33.2000000000 1.0942884684 72.5789784041 456.8115844727 18.3544475539 0.0397950000 760608538 0 1784553472 -0.8478904963 -0.2858103812 -0.3205288053 832 33.2400000000 1.0939502716 72.4930588992 456.8115844727 18.3434006392 0.0338720000 760609812 0 1785061376 -0.8478904963 -0.2858103812 -0.3205288053 833 33.2800000000 1.0930343866 72.4073445840 456.8115844727 18.3323736472 0.0386280000 760611086 0 1785569280 -0.8478904963 -0.2858103812 -0.3205288053 834 33.3200000000 1.0923593044 72.3218350094 456.8115844727 18.3213665177 0.0412130000 760612360 0 1786077184 -0.8478904963 -0.2858103812 -0.3205288053 835 33.3600000000 1.0918530226 72.2365296417 456.8115844727 18.3103791908 0.0395730000 760613634 0 1786187776 -0.8478904963 -0.2858103812 -0.3205288053 836 33.4000000000 1.0907564163 72.1514270422 456.8115844727 18.2994116077 0.0381560000 760614908 0 1786695680 -0.8478904963 -0.2858103812 -0.3205288053 837 33.4399999990 1.0896738768 72.0665265007 456.8115844727 18.2884637092 0.0392060000 760616182 0 1787330560 -0.8478904963 -0.2858103812 -0.3205288053 838 33.4800000000 1.0886906385 71.9818274126 456.8115844727 18.2775354365 0.0293340000 760617456 0 1787973632 -0.8478904963 -0.2858103812 -0.3205288053 839 33.5200000000 0.4915156066 71.8966184593 456.8115844727 18.2666896873 0.0870440000 760618730 0 1786351616 0.3160119951 0.0615836680 0.1180372164 840 33.5600000000 0.4727072716 71.8115899936 456.8115844727 18.2558005416 0.1207620000 753247916 0 1784332288 0.3311191201 0.0684894249 0.0936788321 841 33.6000000000 0.4720585942 71.7267629646 456.8115844727 18.2449307594 0.0404050000 760621998 0 1784328192 0.3311191201 0.0684894249 0.0936788321 842 33.6400000000 0.4717942774 71.6421371111 456.8115844727 18.2340803718 0.0355480000 760623272 0 1785323520 0.3311191201 0.0684894249 0.0936788321 843 33.6800000000 0.4714621902 71.5577116367 456.8115844727 18.2232493184 0.0304180000 760624546 0 1786286080 0.3311191201 0.0684894249 0.0936788321 844 33.7200000000 0.4709579945 71.4734856252 456.8115844727 18.2124375421 0.0417780000 760625820 0 1786286080 0.3311191201 0.0684894249 0.0936788321 845 33.7599999990 0.4712422490 71.3894593017 456.8115844727 18.2016449872 0.0398080000 760627094 0 1786007552 0.3311191201 0.0684894249 0.0936788321 846 33.7999999990 0.4709374607 71.3056312617 456.8115844727 18.1908715962 0.0409860000 760628368 0 1786007552 0.3311191201 0.0684894249 0.0936788321 847 33.8400000000 0.4703095555 71.2220004214 456.8115844727 18.1801173121 0.0456010000 760629642 0 1785155584 0.3311191201 0.0684894249 0.0936788321 848 33.8800000000 0.4701944292 71.1385666880 456.8115844727 18.1693820790 0.0436980000 760630916 0 1785155584 0.3311191201 0.0684894249 0.0936788321 849 33.9200000000 0.4700533748 71.0553293342 456.8115844727 18.1586658410 0.0429470000 760632190 0 1785659392 0.3311191201 0.0684894249 0.0936788321 850 33.9600000000 0.4693177044 70.9722869676 456.8115844727 18.1479685424 0.0445770000 760633464 0 1786167296 0.3311191201 0.0684894249 0.0936788321 851 34.0000000000 0.4696345627 70.8894401375 456.8115844727 18.1372901271 0.0376530000 760634738 0 1786675200 0.3311191201 0.0684894249 0.0936788321 852 34.0400000000 0.4705144167 70.8067888163 456.8115844727 18.1266305387 0.0333590000 760636012 0 1787056128 0.3311191201 0.0684894249 0.0936788321 853 34.0800000000 0.4706242681 70.7243314135 456.8115844727 18.1159897218 0.0416870000 760637286 0 1787277312 0.3311191201 0.0684894249 0.0936788321 854 34.1199999990 0.4702729583 70.6420667080 456.8115844727 18.1053676221 0.0309360000 760638560 0 1787785216 0.3311191201 0.0684894249 0.0936788321 855 34.1600000000 0.4697376490 70.5599938086 456.8115844727 18.0947641851 0.0363990000 760639834 0 1786544128 0.3311191201 0.0684894249 0.0936788321 856 34.2000000000 0.4687222838 70.4781114820 456.8115844727 18.0841793577 0.0378850000 760641108 0 1786544128 0.3311191201 0.0684894249 0.0936788321 857 34.2400000000 0.4681054950 70.3964195264 456.8115844727 18.0736130843 0.0358740000 760642382 0 1786052608 0.3311191201 0.0684894249 0.0936788321 858 34.2800000000 0.4674011469 70.3149171740 456.8115844727 18.0630653091 0.0285200000 760643656 0 1786052608 0.3311191201 0.0684894249 0.0936788321 859 34.3200000000 0.4664256871 70.2336034470 456.8115844727 18.0525359801 0.0339780000 760644930 0 1786404864 0.3311191201 0.0684894249 0.0936788321 860 34.3600000000 0.4656412005 70.1524779095 456.8115844727 18.0420250423 0.0327490000 760646204 0 1785520128 0.3311191201 0.0684894249 0.0936788321 861 34.4000000000 0.4648139775 70.0715398561 456.8115844727 18.0315324424 0.0343540000 760647478 0 1785520128 0.3311191201 0.0684894249 0.0936788321 862 34.4400000000 0.4637050033 69.9907883076 456.8115844727 18.0210581276 0.0303390000 760648752 0 1785286656 0.3311191201 0.0684894249 0.0936788321 863 34.4800000000 0.4627470672 69.9102227905 456.8115844727 18.0106020448 0.0378220000 760650026 0 1785290752 0.3311191201 0.0684894249 0.0936788321 864 34.5200000000 0.4615331292 69.8298423626 456.8115844727 18.0001641415 0.0322460000 760651300 0 1785769984 0.3311191201 0.0684894249 0.0936788321 865 34.5600000000 0.4602885544 69.7496463467 456.8115844727 17.9897443651 0.0355030000 760652574 0 1784004608 0.3311191201 0.0684894249 0.0936788321 866 34.6000000000 0.4589574933 69.6696340039 456.8115844727 17.9793426628 0.0449160000 760653848 0 1784004608 0.3311191201 0.0684894249 0.0936788321 867 34.6400000000 0.4580496550 69.5898051869 456.8115844727 17.9689589823 0.0410410000 760655122 0 1784500224 0.3311191201 0.0684894249 0.0936788321 868 34.6800000000 0.4569263458 69.5101590131 456.8115844727 17.9585932718 0.0390730000 760656396 0 1785008128 0.3311191201 0.0684894249 0.0936788321 869 34.7200000000 0.4557690322 69.4306948129 456.8115844727 17.9482454795 0.0322020000 760657670 0 1785626624 0.3311191201 0.0684894249 0.0936788321 870 34.7600000000 0.4544832706 69.3514118111 456.8115844727 17.9379155545 0.0343330000 760658944 0 1786007552 0.3311191201 0.0684894249 0.0936788321 871 34.8000000000 0.4534231424 69.2723096427 456.8115844727 17.9276034449 0.0365610000 760660218 0 1786134528 0.3311191201 0.0684894249 0.0936788321 872 34.8400000000 0.4521182179 69.1933874048 456.8115844727 17.9173090990 0.0403520000 760661492 0 1786769408 0.3311191201 0.0684894249 0.0936788321 873 34.8800000000 0.4509949982 69.1146446873 456.8115844727 17.9070324677 0.0328080000 760662766 0 1787277312 0.3311191201 0.0684894249 0.0936788321 874 34.9200000000 0.4500328898 69.0360810583 456.8115844727 17.8967734982 0.0341660000 760664040 0 1787785216 0.3311191201 0.0684894249 0.0936788321 875 34.9600000000 0.4492443502 68.9576961020 456.8115844727 17.8865321421 0.0391480000 760665314 0 1786560512 0.3311191201 0.0684894249 0.0936788321 876 35.0000000000 0.4484779835 68.8794892320 456.8115844727 17.8763083463 0.0303200000 760666588 0 1786560512 0.3311191201 0.0684894249 0.0936788321 877 35.0400000000 0.4476569593 68.8014597767 456.8115844727 17.8661020614 0.0373690000 760667862 0 1785942016 0.3311191201 0.0684894249 0.0936788321 878 35.0800000000 0.4470316470 68.7236073529 456.8115844727 17.8559132378 0.0400250000 760669136 0 1785942016 0.3311191201 0.0684894249 0.0936788321 879 35.1200000000 0.4465959072 68.6459315720 456.8115844727 17.8457418254 0.0300150000 760670410 0 1786294272 0.3311191201 0.0684894249 0.0936788321 880 35.1600000000 0.4456453323 68.5684312467 456.8115844727 17.8355877758 0.0429730000 760671684 0 1785393152 0.3311191201 0.0684894249 0.0936788321 881 35.2000000000 0.4452905953 68.4911064559 456.8115844727 17.8254510407 0.0328250000 760672958 0 1785393152 0.3311191201 0.0684894249 0.0936788321 882 35.2400000000 0.4446401894 68.4139562674 456.8115844727 17.8153315675 0.0307180000 760674232 0 1784520704 0.3311191201 0.0684894249 0.0936788321 883 35.2800000000 0.4441901445 68.3369803149 456.8115844727 17.8052293092 0.0426180000 760675506 0 1784520704 0.3311191201 0.0684894249 0.0936788321 884 35.3200000000 0.4437756240 68.2601780471 456.8115844727 17.7951442170 0.0330330000 760676780 0 1785008128 0.3311191201 0.0684894249 0.0936788321 885 35.3600000000 0.4435361028 68.1835490732 456.8115844727 17.7850762424 0.0327470000 760678054 0 1785516032 0.3311191201 0.0684894249 0.0936788321 886 35.4000000000 0.4432524145 68.1070927564 456.8115844727 17.7750253371 0.0402540000 760679328 0 1786023936 0.3311191201 0.0684894249 0.0936788321 887 35.4400000000 0.4431384504 68.0308087042 456.8115844727 17.7649914531 0.0335550000 760680602 0 1786531840 0.3311191201 0.0684894249 0.0936788321 888 35.4800000000 0.4430361092 67.9546963477 456.8115844727 17.7549745428 0.0332550000 760681876 0 1786642432 0.3311191201 0.0684894249 0.0936788321 889 35.5200000000 0.7686513662 67.8791214939 456.8115844727 17.7449899837 0.1662840000 760683150 0 1787150336 0.2928316295 0.3494000733 0.3764582574 890 35.5600000000 0.7864459157 67.8037364652 456.8115844727 17.7350070185 0.1525520000 753311804 0 1782714368 0.3301922083 0.3471503258 0.3879092932 891 35.6000000000 0.7854624391 67.7285195471 456.8115844727 17.7250407337 0.0402620000 760685886 0 1782718464 0.3301922083 0.3471503258 0.3879092932 892 35.6400000000 0.7846961021 67.6534704177 456.8115844727 17.7150912329 0.0330700000 760687160 0 1783087104 0.3301922083 0.3471503258 0.3879092932 893 35.6800000000 0.7840234637 67.5785886182 456.8115844727 17.7051584684 0.0385250000 760688434 0 1783595008 0.3301922083 0.3471503258 0.3879092932 894 35.7200000000 0.7834052444 67.5038736479 456.8115844727 17.6952423927 0.0436560000 760689708 0 1784229888 0.3301922083 0.3471503258 0.3879092932 895 35.7600000000 0.7829353213 67.4293251135 456.8115844727 17.6853429582 0.0412110000 760690982 0 1784737792 0.3301922083 0.3471503258 0.3879092932 896 35.8000000000 0.7825071812 67.3549425042 456.8115844727 17.6754601192 0.0323430000 760692256 0 1785245696 0.3301922083 0.3471503258 0.3879092932 897 35.8400000000 0.7821764350 67.2807253737 456.8115844727 17.6655938289 0.0393550000 760693530 0 1785753600 0.3301922083 0.3471503258 0.3879092932 898 35.8800000000 0.7817580700 67.2066730716 456.8115844727 17.6557440425 0.0405570000 760694804 0 1786388480 0.3301922083 0.3471503258 0.3879092932 899 35.9200000000 0.7818897367 67.1327856596 456.8115844727 17.6459107149 0.0290540000 760696078 0 1786515456 0.3301922083 0.3471503258 0.3879092932 900 35.9600000000 0.7823812962 67.0590629881 456.8115844727 17.6360937998 0.0424040000 760697352 0 1786880000 0.3301922083 0.3471503258 0.3879092932 901 36.0000000000 0.7830243707 66.9855046767 456.8115844727 17.6262932494 0.0357400000 760698626 0 1787387904 0.3301922083 0.3471503258 0.3879092932 902 36.0400000000 0.7835013270 66.9121099944 456.8115844727 17.6165090185 0.0322120000 760699900 0 1788022784 0.3301922083 0.3471503258 0.3879092932 903 36.0800000000 0.7840723395 66.8388785020 456.8115844727 17.6067410627 0.0346130000 760701174 0 1786142720 0.3301922083 0.3471503258 0.3879092932 904 36.1200000000 0.7848303318 66.7658098647 456.8115844727 17.5969893368 0.0266750000 760702448 0 1786388480 0.3301922083 0.3471503258 0.3879092932 905 36.1600000000 0.7849676013 66.6929028566 456.8115844727 17.5872537963 0.0318200000 760703722 0 1785909248 0.3301922083 0.3471503258 0.3879092932 906 36.2000000000 0.7858236432 66.6201577361 456.8115844727 17.5775343966 0.0312770000 760704996 0 1785909248 0.3301922083 0.3471503258 0.3879092932 907 36.2400000000 0.7871622443 66.5475744996 456.8115844727 17.5678310931 0.0309830000 760706270 0 1786388480 0.3301922083 0.3471503258 0.3879092932 908 36.2800000000 0.7885534167 66.4751526702 456.8115844727 17.5581438415 0.0271570000 760707544 0 1785503744 0.3301922083 0.3471503258 0.3879092932 909 36.3200000000 0.7894691229 66.4028911922 456.8115844727 17.5484725974 0.0306730000 760708818 0 1785503744 0.3301922083 0.3471503258 0.3879092932 910 36.3600000000 0.7902923822 66.3307894352 456.8115844727 17.5388173168 0.0332660000 760710092 0 1784864768 0.3301922083 0.3471503258 0.3879092932 911 36.4000000000 0.7916826606 66.2588474959 456.8115844727 17.5291779561 0.0300920000 760711366 0 1784872960 0.3301922083 0.3471503258 0.3879092932 912 36.4400000000 0.7924202681 66.1870641327 456.8115844727 17.5195544712 0.0365000000 760712640 0 1785356288 0.3301922083 0.3471503258 0.3879092932 913 36.4800000000 0.7930561900 66.1154387132 456.8115844727 17.5099468185 0.0330020000 760713914 0 1784487936 0.3301922083 0.3471503258 0.3879092932 914 36.5200000000 0.7940973639 66.0439711625 456.8115844727 17.5003549550 0.0355750000 760715188 0 1784487936 0.3301922083 0.3471503258 0.3879092932 915 36.5600000000 0.7954342961 65.9726612862 456.8115844727 17.4907788373 0.0339260000 760716462 0 1784864768 0.3301922083 0.3471503258 0.3879092932 916 36.6000000000 0.7963776588 65.9015081381 456.8115844727 17.4812184227 0.0300960000 760717736 0 1783873536 0.3301922083 0.3471503258 0.3879092932 917 36.6400000000 0.7977652550 65.8305116900 456.8115844727 17.4716736680 0.0299200000 760719010 0 1783975936 0.3301922083 0.3471503258 0.3879092932 918 36.6800000000 0.7984688282 65.7596706847 456.8115844727 17.4621445306 0.0314540000 760720284 0 1783357440 0.3301922083 0.3471503258 0.3879092932 919 36.7200000000 0.7989845872 65.6889844104 456.8115844727 17.4526309678 0.0319260000 760721558 0 1783365632 0.3301922083 0.3471503258 0.3879092932 920 36.7600000000 0.7998604178 65.6184527539 456.8115844727 17.4431329375 0.0290090000 760722832 0 1783848960 0.3301922083 0.3471503258 0.3879092932 921 36.8000000000 0.8003364205 65.5480747774 456.8115844727 17.4336503973 0.0301430000 760724106 0 1782964224 0.3301922083 0.3471503258 0.3879092932 922 36.8400000000 0.8003702164 65.4778495013 456.8115844727 17.4241833053 0.0305500000 760725380 0 1782964224 0.3301922083 0.3471503258 0.3879092932 923 36.8800000000 0.8007799983 65.4077768367 456.8115844727 17.4147316205 0.0251930000 760726654 0 1783468032 0.3301922083 0.3471503258 0.3879092932 924 36.9200000000 0.8015884161 65.3378567193 456.8115844727 17.4052953001 0.0329880000 760727928 0 1782198272 0.3301922083 0.3471503258 0.3879092932 925 36.9600000000 0.8021494746 65.2680883872 456.8115844727 17.3958743014 0.0298160000 760729202 0 1782198272 0.3301922083 0.3471503258 0.3879092932 926 37.0000000000 0.8024962544 65.1984711170 456.8115844727 17.3864685836 0.0293400000 760730476 0 1782579200 0.3301922083 0.3471503258 0.3879092932 927 37.0400000000 0.8028824925 65.1290044626 456.8115844727 17.3770781061 0.0396040000 760731750 0 1780961280 0.3301922083 0.3471503258 0.3879092932 928 37.0800000000 0.8024313450 65.0596870347 456.8115844727 17.3677028276 0.0303950000 760733024 0 1780961280 0.3301922083 0.3471503258 0.3879092932 929 37.1200000000 0.8024948239 64.9905189053 456.8115844727 17.3583427079 0.0293690000 760734298 0 1781309440 0.3301922083 0.3471503258 0.3879092932 930 37.1600000000 0.8025228977 64.9214995548 456.8115844727 17.3489977050 0.0304900000 760735572 0 1781944320 0.3301922083 0.3471503258 0.3879092932 931 37.2000000000 0.8024706841 64.8526284174 456.8115844727 17.3396677787 0.0307430000 760736846 0 1782452224 0.3301922083 0.3471503258 0.3879092932 932 37.2400000000 0.8025941849 64.7839052047 456.8115844727 17.3303528885 0.0326750000 760738120 0 1782960128 0.3301922083 0.3471503258 0.3879092932 933 37.2800000000 0.8023363948 64.7153290324 456.8115844727 17.3210529941 0.0389660000 760739394 0 1783070720 0.3301922083 0.3471503258 0.3879092932 934 37.3200000000 0.8018493056 64.6468991826 456.8115844727 17.3117680556 0.0317260000 760740668 0 1783578624 0.3301922083 0.3471503258 0.3879092932 935 37.3600000000 0.8017473221 64.5786155977 456.8115844727 17.3024980337 0.0399460000 760741942 0 1784086528 0.3301922083 0.3471503258 0.3879092932 936 37.4000000000 0.8018040657 64.5104779785 456.8115844727 17.2932428868 0.0340240000 760743216 0 1784594432 0.3301922083 0.3471503258 0.3879092932 937 37.4400000000 0.8019125462 64.4424859130 456.8115844727 17.2840025752 0.0327270000 760744490 0 1785229312 0.3301922083 0.3471503258 0.3879092932 938 37.4800000000 0.8020455241 64.3746389616 456.8115844727 17.2747770599 0.0443420000 760745764 0 1785737216 0.3301922083 0.3471503258 0.3879092932 939 37.5200000000 0.8021534681 64.3069366341 456.8115844727 17.2655663013 0.0401450000 760747038 0 1786245120 0.3301922083 0.3471503258 0.3879092932 940 37.5600000000 0.8020988703 64.2393782961 456.8115844727 17.2563702602 0.0356930000 760748312 0 1786728448 0.3301922083 0.3471503258 0.3879092932 941 37.6000000000 0.8018034101 64.1719632324 456.8115844727 17.2471888977 0.0434920000 760749586 0 1787236352 0.3301922083 0.3471503258 0.3879092932 942 37.6400000000 0.8015981913 64.1046910827 456.8115844727 17.2380221749 0.0323540000 760750860 0 1787871232 0.3301922083 0.3471503258 0.3879092932 943 37.6800000000 0.5450391769 64.0372895430 456.8115844727 17.2288821052 0.0744390000 760752134 0 1786118144 0.3321880400 0.0890652463 0.1687380821 944 37.7200000000 0.5599036813 63.9700465495 456.8115844727 17.2197445676 0.1209480000 753380808 0 1783848960 0.3664121628 0.0889230147 0.1605073661 945 37.7600000000 0.5599001050 63.9029458655 456.8115844727 17.2106215243 0.0414590000 760754890 0 1783844864 0.3664121628 0.0889230147 0.1605073661 946 37.8000000000 0.5599194169 63.8359870637 456.8115844727 17.2015129659 0.0362220000 760756164 0 1784332288 0.3664121628 0.0889230147 0.1605073661 947 37.8400000000 0.5597608089 63.7691695070 456.8115844727 17.1924188537 0.0297490000 760757438 0 1784840192 0.3664121628 0.0889230147 0.1605073661 948 37.8800000000 0.5597042441 63.7024928558 456.8115844727 17.1833391501 0.0406790000 760758712 0 1785348096 0.3664121628 0.0889230147 0.1605073661 949 37.9200000000 0.5131455064 63.6359076637 456.8115844727 17.1742741089 0.0687810000 760759986 0 1785856000 0.3380002081 0.0806721374 0.1245211214 950 37.9600000000 0.5138804913 63.5694634246 456.8115844727 17.1652231095 0.1206350000 753388660 0 1783984128 0.3454783261 0.0826514810 0.1186627224 951 38.0000000000 0.5137853026 63.5031588209 456.8115844727 17.1561864031 0.0333140000 760762742 0 1783992320 0.3454783261 0.0826514810 0.1186627224 952 38.0400000000 0.5135543346 63.4369932699 456.8115844727 17.1471639544 0.0319490000 760764016 0 1784340480 0.3454783261 0.0826514810 0.1186627224 953 38.0800000000 0.5135343075 63.3709665554 456.8115844727 17.1381557251 0.0305800000 760765290 0 1784975360 0.3454783261 0.0826514810 0.1186627224 954 38.1200000000 0.5133538246 63.3050780724 456.8115844727 17.1291616780 0.0262730000 760766564 0 1785483264 0.3454783261 0.0826514810 0.1186627224 955 38.1600000000 0.5132541060 63.2393274714 456.8115844727 17.1201817764 0.0415990000 760767838 0 1785991168 0.3454783261 0.0826514810 0.1186627224 956 38.2000000000 0.5131739378 63.1737143401 456.8115844727 17.1112159830 0.0402870000 760769112 0 1786245120 0.3454783261 0.0826514810 0.1186627224 957 38.2400000000 0.5132601261 63.1082384214 456.8115844727 17.1022642610 0.0305840000 760770386 0 1786609664 0.3454783261 0.0826514810 0.1186627224 958 38.2800000000 0.5131266713 63.0428990563 456.8115844727 17.0933265735 0.0441750000 760771660 0 1787117568 0.3454783261 0.0826514810 0.1186627224 959 38.3200000000 0.5131102800 62.9776959398 456.8115844727 17.0844028840 0.0344260000 760772934 0 1787625472 0.3454783261 0.0826514810 0.1186627224 960 38.3600000000 0.5129584074 62.9126285048 456.8115844727 17.0754931557 0.0344990000 760774208 0 1786273792 0.3454783261 0.0826514810 0.1186627224 961 38.4000000000 0.5128642917 62.8476963881 456.8115844727 17.0665973526 0.0423440000 760775482 0 1786273792 0.3454783261 0.0826514810 0.1186627224 962 38.4400000000 0.5128030777 62.7828992017 456.8115844727 17.0577154384 0.0357150000 760776756 0 1786003456 0.3454783261 0.0826514810 0.1186627224 963 38.4800000000 0.5127490759 62.7182365328 456.8115844727 17.0488473769 0.0354470000 760778030 0 1786003456 0.3454783261 0.0826514810 0.1186627224 964 38.5200000000 0.5125738382 62.6537078371 456.8115844727 17.0399931321 0.0424110000 760779304 0 1785393152 0.3454783261 0.0826514810 0.1186627224 965 38.5600000000 0.5124172568 62.5893127173 456.8115844727 17.0311526684 0.0332650000 760780578 0 1785380864 0.3454783261 0.0826514810 0.1186627224 966 38.6000000000 0.5123637319 62.5250508653 456.8115844727 17.0223259498 0.0332820000 760781852 0 1785737216 0.3454783261 0.0826514810 0.1186627224 967 38.6400000000 0.5122821331 62.4609218387 456.8115844727 17.0135129407 0.0379940000 760783126 0 1784999936 0.3454783261 0.0826514810 0.1186627224 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:03:55 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0359950000 86789171 0 1093373952 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0010192674 0.0005096337 0.0010192674 0.0016461832 0.1005890000 98511972 0 1103286272 -0.0006004850 -0.0001168514 0.0001065529 3 0.0800000000 0.0050369492 0.0020187388 0.0050369492 0.0023323772 0.1028270000 101782562 0 1107095552 -0.0005712212 -0.0001159408 -0.0002626191 4 0.1200000000 0.0030104611 0.0022666694 0.0050369492 0.0021966427 0.1010610000 101784144 0 1107857408 -0.0008395689 -0.0004368157 -0.0003820120 5 0.1600000000 0.0058183502 0.0029770056 0.0058183502 0.0019631229 0.0952180000 101785734 0 1108365312 -0.0009796099 -0.0000026681 -0.0002612149 6 0.2000000000 0.0051384396 0.0033372446 0.0058183502 0.0018813674 0.0966620000 101787644 0 1108873216 -0.0005846015 -0.0000756629 -0.0006002688 7 0.2400000000 0.0052057360 0.0036041719 0.0058183502 0.0017249274 0.0953290000 101788898 0 1109381120 -0.0005683512 0.0000713196 -0.0004218031 8 0.2800000000 0.0065800366 0.0039761550 0.0065800366 0.0016589873 0.0943560000 101790152 0 1109889024 -0.0006064161 0.0001757641 -0.0005147499 9 0.3200000000 0.0080526276 0.0044290964 0.0080526276 0.0016338017 0.1069040000 101792078 0 1110523904 -0.0010380618 0.0000522985 -0.0005211149 10 0.3600000000 0.0081044836 0.0047966351 0.0081044836 0.0016452099 0.1078890000 101794644 0 1111031808 -0.0013087967 0.0000751047 -0.0004509388 11 0.4000000000 0.0093985079 0.0052149872 0.0093985079 0.0018086935 0.0938630000 101795898 0 1111539712 -0.0008956442 0.0000751497 -0.0001809046 12 0.4400000000 0.0094707115 0.0055696309 0.0094707115 0.0021760242 0.1019540000 101797152 0 1112047616 -0.0007592409 -0.0000004653 -0.0004498172 13 0.4800000000 0.0110083176 0.0059879914 0.0110083176 0.0022165767 0.0938020000 101798406 0 1112555520 -0.0016797759 -0.0000336222 -0.0001003948 14 0.5200000000 0.0109668421 0.0063436236 0.0110083176 0.0021936693 0.1372300000 101799660 0 1113063424 -0.0019601998 -0.0010239633 -0.0000114675 15 0.5600000000 0.0139693972 0.0068520085 0.0139693972 0.0021532663 0.0989020000 101800914 0 1113571328 -0.0020311738 0.0001297701 -0.0003221621 16 0.6000000000 0.0133044329 0.0072552850 0.0139693972 0.0022222525 0.0961540000 101802168 0 1114079232 -0.0015770770 -0.0000095433 -0.0005183020 17 0.6400000000 0.0138059678 0.0076406193 0.0139693972 0.0022506147 0.0952720000 101804766 0 1114587136 -0.0031563127 -0.0012518218 -0.0008958530 18 0.6800000000 0.0174066201 0.0081831749 0.0174066201 0.0023576268 0.0998800000 101808644 0 1115222016 -0.0016305163 -0.0045932359 -0.0006293858 19 0.7200000000 0.0175940525 0.0086784842 0.0175940525 0.0025287944 0.0836740000 101809898 0 1115729920 -0.0023679067 -0.0004590496 -0.0013908840 20 0.7600000000 0.0203371495 0.0092614175 0.0203371495 0.0025887978 0.0854530000 101811152 0 1116237824 -0.0026742879 -0.0005095035 -0.0014838526 21 0.8000000000 0.0241026115 0.0099681410 0.0241026115 0.0025306111 0.0934130000 101812406 0 1116745728 -0.0018643828 -0.0001886232 -0.0016553181 22 0.8400000000 0.0295360908 0.0108575933 0.0295360908 0.0026147085 0.0973900000 101813660 0 1117253632 -0.0021180592 -0.0002901079 -0.0015466685 23 0.8800000000 0.0290697664 0.0116494269 0.0295360908 0.0025784997 0.1002850000 101814914 0 1117761536 -0.0020464342 0.0000018626 -0.0023590252 24 0.9200000000 0.0353328027 0.0126362342 0.0353328027 0.0028168712 0.1086480000 101816168 0 1118269440 -0.0040983660 -0.0000607162 -0.0031312595 25 0.9600000000 0.0355542935 0.0135529566 0.0355542935 0.0027710757 0.0868120000 101817422 0 1118904320 -0.0050165136 0.0009018445 -0.0037801615 26 1.0000000000 0.0407121740 0.0145975419 0.0407121740 0.0028418536 0.1171870000 101818676 0 1119412224 -0.0061556743 0.0006631495 -0.0029550409 27 1.0400000000 0.0460832566 0.0157636795 0.0460832566 0.0030270922 0.0964130000 101819930 0 1119920128 -0.0064671142 0.0004708096 -0.0043465942 28 1.0800000000 0.0490001515 0.0169506963 0.0490001515 0.0033444868 0.1027600000 101821184 0 1120428032 -0.0083510950 -0.0004519974 -0.0040306961 29 1.1200000000 0.0525595061 0.0181785863 0.0525595061 0.0036697888 0.1033210000 101822438 0 1120935936 -0.0109448284 -0.0000379827 -0.0050467951 30 1.1600000000 0.0573767237 0.0194851909 0.0573767237 0.0041520138 0.1664190000 101823692 0 1121443840 -0.0156682190 -0.0000791074 -0.0038885016 31 1.2000000000 0.0600685775 0.0207943324 0.0600685775 0.0043312046 0.1415680000 101824946 0 1121951744 -0.0195193309 -0.0003718798 -0.0041893553 32 1.2400000000 0.0643006638 0.0221539053 0.0643006638 0.0044643146 0.1385900000 101826200 0 1122443264 -0.0222020932 -0.0007061152 -0.0050116563 33 1.2800000000 0.0680424720 0.0235444679 0.0680424720 0.0045866968 0.1209000000 101830142 0 1123078144 -0.0239877198 -0.0007081559 -0.0050798859 34 1.3200000000 0.0855101496 0.0253669879 0.0855101496 0.0055831589 0.1304010000 101836644 0 1123586048 -0.0347751044 -0.0007887363 -0.0049192882 35 1.3600000000 0.0872021392 0.0271337065 0.0872021392 0.0057592991 0.1247250000 101837898 0 1124093952 -0.0366729945 -0.0007462856 -0.0058052153 36 1.4000000000 0.0903559625 0.0288898803 0.0903559625 0.0061903276 0.1209150000 101839152 0 1124601856 -0.0393485166 -0.0010604571 -0.0064361827 37 1.4400000000 0.0969478339 0.0307292845 0.0969478339 0.0064239432 0.1159020000 101840406 0 1125109760 -0.0434892885 -0.0008661391 -0.0057029598 38 1.4800000000 0.1035949364 0.0326468016 0.1035949364 0.0065363723 0.1949170000 114180444 0 1137934336 -0.0486340076 -0.0006415468 -0.0051555680 39 1.5200000000 0.1064773276 0.0345398920 0.1064773276 0.0064705126 0.0934510000 117839746 0 1141997568 -0.0491356030 -0.0009606312 -0.0063160397 40 1.5600000000 0.1132199168 0.0365068927 0.1132199168 0.0064297140 0.1175990000 121033096 0 1145679872 -0.0522792265 -0.0013137306 -0.0061512156 41 1.6000000000 0.1197378337 0.0385369156 0.1197378337 0.0063955904 0.0904540000 121034350 0 1146441728 -0.0560408421 -0.0018513507 -0.0056608221 42 1.6400000000 0.1286498159 0.0406824609 0.1286498159 0.0064276900 0.0857710000 121035604 0 1146949632 -0.0603383929 -0.0006434981 -0.0049930047 43 1.6800000000 0.1333017945 0.0428363989 0.1333017945 0.0063694945 0.0872160000 121036858 0 1147457536 -0.0623640157 -0.0006048982 -0.0036623699 44 1.7200000000 0.1370738596 0.0449781593 0.1370738596 0.0063149847 0.0844220000 121038112 0 1147965440 -0.0649211630 -0.0013825274 -0.0045124171 45 1.7600000000 0.1418684423 0.0471312767 0.1418684423 0.0062740913 0.0788090000 121039366 0 1148473344 -0.0684483945 -0.0011991458 -0.0031572122 46 1.8000000000 0.1459868252 0.0492803104 0.1459868252 0.0062097267 0.0824850000 121040620 0 1149108224 -0.0702853426 -0.0000961047 -0.0036110729 47 1.8400000000 0.1493941247 0.0514103915 0.1493941247 0.0062227317 0.0901250000 121041874 0 1149616128 -0.0699011236 -0.0000683115 -0.0032839077 48 1.8800000000 0.1525115073 0.0535166648 0.1525115073 0.0061727624 0.0892330000 121043128 0 1150124032 -0.0712789521 -0.0000058564 -0.0029623264 49 1.9200000000 0.1568023711 0.0556245363 0.1568023711 0.0061523500 0.0932570000 121044382 0 1150631936 -0.0742351860 -0.0000374449 -0.0031260466 50 1.9600000000 0.1663611084 0.0578392678 0.1663611084 0.0063305015 0.0957320000 121045636 0 1151266816 -0.0789800286 0.0001922186 -0.0007714225 51 2.0000000000 0.1646321267 0.0599332454 0.1663611084 0.0062691031 0.0897100000 121046890 0 1151774720 -0.0790327266 -0.0014121289 -0.0016565060 52 2.0400000000 0.1675969064 0.0620037004 0.1675969064 0.0062190152 0.1071890000 121048144 0 1152282624 -0.0800501257 -0.0005165207 -0.0021492448 53 2.0800000000 0.1688640267 0.0640199330 0.1688640267 0.0062147252 0.1050800000 121049398 0 1152917504 -0.0808072686 -0.0011313070 -0.0032754063 54 2.1200000000 0.1772439331 0.0661166737 0.1772439331 0.0062195089 0.1025510000 121050652 0 1153425408 -0.0854749158 -0.0015865732 -0.0011929281 55 2.1600000000 0.1786862314 0.0681633930 0.1786862314 0.0062014509 0.1016010000 121051906 0 1153933312 -0.0862825438 -0.0015682332 -0.0012429463 56 2.2000000000 0.1919633746 0.0703741069 0.1919633746 0.0063137391 0.1137780000 121053160 0 1154441216 -0.0930492207 -0.0005078338 0.0018320929 57 2.2400000000 0.1952913553 0.0725656376 0.1952913553 0.0062723678 0.1100020000 121054414 0 1154949120 -0.0946560651 -0.0012937963 0.0022927416 58 2.2800000000 0.2007973045 0.0747765284 0.2007973045 0.0063730642 0.1127660000 121055668 0 1155457024 -0.0985274836 -0.0018216078 0.0036767516 59 2.3200000000 0.2106232196 0.0770790147 0.2106232196 0.0067582048 0.1133550000 121056922 0 1155964928 -0.1029786617 -0.0007484062 0.0055058072 60 2.3600000000 0.2125504464 0.0793368719 0.2125504464 0.0068116232 0.1169200000 121058176 0 1156472832 -0.1041355655 -0.0010752575 0.0052097286 61 2.4000000000 0.2172030210 0.0815969727 0.2172030210 0.0069252846 0.1190910000 121059430 0 1156980736 -0.1062975004 -0.0009658473 0.0052241022 62 2.4400000000 0.2334515750 0.0840462405 0.2334515750 0.0076095245 0.1194170000 121060684 0 1157615616 -0.1141443700 -0.0009315339 0.0087441392 63 2.4800000000 0.2387628257 0.0865020593 0.2387628257 0.0077835200 0.1266470000 121061938 0 1158123520 -0.1175163016 -0.0009856630 0.0096839033 64 2.5200000000 0.2462916523 0.0889987717 0.2462916523 0.0082246121 0.1136670000 121063192 0 1158631424 -0.1227097511 -0.0007826474 0.0113295736 65 2.5600000000 0.2572418153 0.0915871262 0.2572418153 0.0086204508 0.1197350000 121069822 0 1159139328 -0.1257663220 0.0003894773 0.0125722708 66 2.6000000000 0.2623173892 0.0941739484 0.2623173892 0.0088011315 0.1150730000 121081572 0 1159647232 -0.1314666420 0.0013748839 0.0131324045 67 2.6400000000 0.2714349926 0.0968196356 0.2714349926 0.0088960421 0.3049830000 139913762 0 1175265280 -0.1326480955 0.0019592273 0.0141250091 68 2.6800000000 0.2740630507 0.0994261564 0.2740630507 0.0088869646 0.1112060000 143572864 0 1179455488 -0.1410933435 0.0025807831 0.0144534279 69 2.7200000000 0.2804259062 0.1020493412 0.2804259062 0.0088478424 0.0975830000 146766214 0 1183264768 -0.1445049793 0.0029424820 0.0162140094 70 2.7600000000 0.2863983214 0.1046828980 0.2863983214 0.0087977167 0.0931710000 146767468 0 1183899648 -0.1474036723 0.0032726619 0.0160177704 71 2.8000000000 0.2908037007 0.1073043178 0.2908037007 0.0087591917 0.0822850000 146768722 0 1184534528 -0.1499914527 0.0036285678 0.0149056390 72 2.8400000000 0.3011327386 0.1099963792 0.3011327386 0.0088186243 0.0880560000 146769976 0 1185042432 -0.1558689773 0.0058258707 0.0157219935 73 2.8800000000 0.3076897860 0.1127045081 0.3076897860 0.0087747666 0.0828780000 146771230 0 1185550336 -0.1593580693 0.0061266497 0.0163147114 74 2.9200000000 0.3084312379 0.1153494639 0.3084312379 0.0087777664 0.0879830000 146772484 0 1186058240 -0.1605761051 0.0072926530 0.0152676115 75 2.9600000000 0.3094812334 0.1179378875 0.3094812334 0.0087656631 0.0921670000 146773738 0 1186566144 -0.1607934386 0.0085623395 0.0141087435 76 3.0000000000 0.3070740402 0.1204265211 0.3094812334 0.0087716127 0.0865940000 146774992 0 1187074048 -0.1609349698 0.0093191108 0.0111935809 77 3.0400000000 0.3058043122 0.1228340248 0.3094812334 0.0087704382 0.0950020000 146776246 0 1187581952 -0.1624144912 0.0103263780 0.0095799780 78 3.0800000000 0.3069617450 0.1251946366 0.3094812334 0.0087659300 0.0904010000 146777500 0 1188216832 -0.1594237685 0.0102999518 0.0063210814 79 3.1200000000 0.3114919364 0.1275528303 0.3114919364 0.0087476098 0.0900630000 146778754 0 1188724736 -0.1617866904 0.0115927914 0.0055054408 80 3.1600000000 0.3134737313 0.1298768416 0.3134737313 0.0087315322 0.0979160000 146780008 0 1189232640 -0.1632328033 0.0135562662 0.0043614320 81 3.2000000000 0.3214270771 0.1322416593 0.3214270771 0.0087521547 0.0896640000 146781262 0 1189740544 -0.1672520936 0.0126691861 0.0052987547 82 3.2400000000 0.3271830678 0.1346189935 0.3271830678 0.0087892711 0.0952560000 146782516 0 1190248448 -0.1699357033 0.0130136795 0.0050843102 83 3.2800000000 0.3321548104 0.1369989431 0.3321548104 0.0088726517 0.1013980000 146783770 0 1190756352 -0.1727226675 0.0139959315 0.0040165968 84 3.3200000000 0.3403632939 0.1394199473 0.3403632939 0.0089336685 0.0936820000 146785024 0 1191264256 -0.1770230830 0.0137648182 0.0040442226 85 3.3600000000 0.3491875827 0.1418878018 0.3491875827 0.0090055866 0.0983850000 146786278 0 1191772160 -0.1817945242 0.0144924475 0.0042581544 86 3.4000000000 0.3592995405 0.1444158453 0.3592995405 0.0091448772 0.0968520000 146787532 0 1192407040 -0.1865257323 0.0149873290 0.0054204720 87 3.4400000000 0.3656403422 0.1469586556 0.3656403422 0.0092904121 0.2592230000 159093206 0 1205231616 -0.1899069995 0.0142557556 0.0053101052 88 3.4800000000 0.3740038872 0.1495387151 0.3740038872 0.0094795904 0.1094450000 162752716 0 1209294848 -0.1945840418 0.0140960952 0.0048233559 89 3.5200000000 0.3801400363 0.1521297412 0.3801400363 0.0096347373 0.0857780000 165946066 0 1212977152 -0.1977722496 0.0143603971 0.0048310268 90 3.5600000000 0.3847074807 0.1547139383 0.3847074807 0.0097299221 0.0831230000 165947320 0 1213739008 -0.2006639689 0.0139332088 0.0047941692 91 3.6000000000 0.3940753937 0.1573442839 0.3940753937 0.0098491337 0.0743810000 165948574 0 1214246912 -0.2058265209 0.0133748082 0.0058844411 92 3.6400000000 0.4038735628 0.1600239500 0.4038735628 0.0099503863 0.0809840000 165949828 0 1214754816 -0.2113184929 0.0142174996 0.0077501321 93 3.6800000000 0.4068566561 0.1626780651 0.4068566561 0.0099280867 0.0804930000 165951082 0 1215389696 -0.2130350769 0.0138168084 0.0067035449 94 3.7200000000 0.4116717875 0.1653269345 0.4116717875 0.0099035882 0.0858270000 165952336 0 1215897600 -0.2154244184 0.0130082844 0.0065678246 95 3.7600000000 0.4202312231 0.1680101375 0.4202312231 0.0099428093 0.0812410000 165953590 0 1216405504 -0.2200245112 0.0138787469 0.0090536252 96 3.8000000000 0.4268130958 0.1707060017 0.4268130958 0.0099401043 0.0775190000 165954844 0 1216905216 -0.2235872597 0.0138840731 0.0089071477 97 3.8400000000 0.4306936860 0.1733862871 0.4306936860 0.0098979791 0.0889870000 165956098 0 1217413120 -0.2252798676 0.0127979182 0.0096284514 98 3.8800000000 0.4397839010 0.1761046301 0.4397839010 0.0099321604 0.0768810000 165957352 0 1218048000 -0.2308239192 0.0126727670 0.0115686338 99 3.9200000000 0.4437326491 0.1788079434 0.4437326491 0.0099007032 0.0806820000 165958606 0 1218555904 -0.2324966788 0.0136397230 0.0124858413 100 3.9600000000 0.4491146505 0.1815110105 0.4491146505 0.0098681630 0.0926240000 165959860 0 1219063808 -0.2354813367 0.0132174576 0.0141179049 101 4.0000000000 0.4549082220 0.1842179136 0.4549082220 0.0098308129 0.0936460000 165961114 0 1219571712 -0.2384860814 0.0124808550 0.0162986685 102 4.0400000000 0.4573957622 0.1868961278 0.4573957622 0.0097871864 0.0875670000 165962368 0 1220079616 -0.2396504730 0.0119439298 0.0167749655 103 4.0800000000 0.4643587470 0.1895899396 0.4643587470 0.0097620852 0.0968570000 165963622 0 1220587520 -0.2436052412 0.0116786240 0.0195942819 104 4.1200000000 0.4730614424 0.1923156271 0.4730614424 0.0097802122 0.0954550000 165964876 0 1221095424 -0.2481601238 0.0113258483 0.0243425574 105 4.1600000000 0.4751228690 0.1950090294 0.4751228690 0.0097563465 0.0938870000 165966130 0 1221603328 -0.2489835918 0.0110477526 0.0249507502 106 4.2000000000 0.4796699882 0.1976945102 0.4796699882 0.0097646795 0.0882590000 165967384 0 1222111232 -0.2511102557 0.0109400684 0.0264250226 107 4.2400000000 0.4800687432 0.2003335217 0.4800687432 0.0097299765 0.0899750000 165968638 0 1222619136 -0.2508455217 0.0104340622 0.0251630358 108 4.2800000000 0.4866400063 0.2029845077 0.4866400063 0.0097058582 0.0894080000 165969892 0 1223254016 -0.2543988228 0.0103207845 0.0281216577 109 4.3200000000 0.4877740741 0.2055972560 0.4877740741 0.0096718248 0.0899880000 165971146 0 1223761920 -0.2551061809 0.0107178232 0.0286552869 110 4.3600000000 0.4930076003 0.2082100773 0.4930076003 0.0096867540 0.0958890000 165972400 0 1224269824 -0.2581960261 0.0100554153 0.0321812220 111 4.4000000000 0.4974313974 0.2108156748 0.4974313974 0.0096880016 0.2410100000 178275634 0 1237094400 -0.2605571151 0.0092668608 0.0346407257 112 4.4400000000 0.5024985075 0.2134199858 0.5024985075 0.0096963698 0.1086660000 181934736 0 1241030656 -0.2638903856 0.0111531047 0.0377927795 113 4.4800000000 0.5051602125 0.2160017577 0.5051602125 0.0096928455 0.0789900000 185128086 0 1244712960 -0.2657294273 0.0093026869 0.0394728296 114 4.5200000000 0.5135342479 0.2186116918 0.5135342479 0.0097699125 0.0781210000 185129340 0 1245474816 -0.2690336704 0.0099213598 0.0440970212 115 4.5600000000 0.5143860579 0.2211836428 0.5143860579 0.0097583735 0.0705270000 185130594 0 1245982720 -0.2691613138 0.0099271284 0.0445166826 116 4.6000000000 0.5220249295 0.2237771022 0.5220249295 0.0098436793 0.0726460000 185131848 0 1246490624 -0.2728488147 0.0113700656 0.0491429269 117 4.6400000000 0.5280563235 0.2263777793 0.5280563235 0.0098738951 0.0781940000 185133102 0 1247125504 -0.2754949331 0.0128824841 0.0528927445 118 4.6800000000 0.5320696831 0.2289683887 0.5320696831 0.0098412381 0.0713020000 185134356 0 1247633408 -0.2774558067 0.0120930150 0.0543311760 119 4.7200000000 0.5367418528 0.2315547203 0.5367418528 0.0098036900 0.0709310000 185135610 0 1248141312 -0.2797791958 0.0117449444 0.0570881218 120 4.7600000000 0.5419793725 0.2341415924 0.5419793725 0.0097704644 0.0702700000 185136864 0 1248649216 -0.2821798325 0.0126319155 0.0601052418 121 4.8000000000 0.5499494672 0.2367515748 0.5499494672 0.0097474276 0.0812890000 185138118 0 1249157120 -0.2855708301 0.0128362654 0.0668155998 122 4.8400000000 0.5510703325 0.2393279581 0.5510703325 0.0097098883 0.0773080000 185139372 0 1249665024 -0.2861052752 0.0130581530 0.0670086220 123 4.8800000000 0.5555904508 0.2418991979 0.5555904508 0.0096925691 0.0767080000 185140626 0 1250172928 -0.2879988551 0.0144348331 0.0691579431 124 4.9200000000 0.5635634065 0.2444932641 0.5635634065 0.0097022347 0.0869420000 185141880 0 1250680832 -0.2912820876 0.0152677530 0.0750664547 125 4.9600000000 0.5669167638 0.2470726521 0.5669167638 0.0096884070 0.0803060000 185143134 0 1251315712 -0.2929042578 0.0152141396 0.0771134570 126 5.0000000000 0.5702695251 0.2496377066 0.5702695251 0.0096733318 0.0793720000 185144388 0 1251823616 -0.2952197492 0.0167719964 0.0803865269 127 5.0400000000 0.5793841481 0.2522341353 0.5793841481 0.0096625807 0.0871300000 185145642 0 1252331520 -0.2980814874 0.0169406775 0.0860854685 128 5.0800000000 0.5833221078 0.2548207601 0.5833221078 0.0096333247 0.0872120000 185146896 0 1252839424 -0.3003130555 0.0178292599 0.0886763781 129 5.1200000000 0.5871689320 0.2573971025 0.5871689320 0.0096042669 0.0868930000 185158902 0 1253339136 -0.3014850914 0.0170775410 0.0908955857 130 5.1600000000 0.5956909657 0.2599993630 0.5956909657 0.0096341896 0.0931200000 185181148 0 1253847040 -0.3044962585 0.0171563644 0.0974797383 131 5.2000000000 0.5992580652 0.2625891241 0.5992580652 0.0096502122 0.0877880000 185182402 0 1254481920 -0.3052431047 0.0185596105 0.0986716822 132 5.2400000000 0.5985656381 0.2651344007 0.5992580652 0.0096407069 0.0908260000 185183656 0 1254989824 -0.3058215678 0.0176202320 0.0982448906 133 5.2800000000 0.6084734201 0.2677158971 0.6084734201 0.0096858399 0.0935400000 185184910 0 1255497728 -0.3093174994 0.0179097857 0.1051143557 134 5.3200000000 0.6173092723 0.2703248029 0.6173092723 0.0097501343 0.2321270000 197491068 0 1268322304 -0.3121552765 0.0188397598 0.1108358204 135 5.3600000000 0.6196236610 0.2729122018 0.6196236610 0.0097593948 0.0816060000 201150170 0 1272258560 -0.3136005700 0.0190621782 0.1127997190 136 5.4000000000 0.6257668138 0.2755067210 0.6257668138 0.0098141125 0.1146730000 204343520 0 1275940864 -0.3164344132 0.0194947403 0.1176664755 137 5.4400000000 0.6306478381 0.2780989919 0.6306478381 0.0098644273 0.0905050000 204344774 0 1276702720 -0.3183650076 0.0203127265 0.1213771850 138 5.4800000000 0.6350725293 0.2806857567 0.6350725293 0.0099011492 0.0722070000 204346028 0 1277210624 -0.3203390539 0.0200729240 0.1231066957 139 5.5200000000 0.6397325397 0.2832688271 0.6397325397 0.0099427515 0.0703250000 204347282 0 1277845504 -0.3225022554 0.0196261592 0.1252690852 140 5.5600000000 0.6486890912 0.2858789718 0.6486890912 0.0100490751 0.0713300000 204348536 0 1278353408 -0.3254937232 0.0201435611 0.1304084957 141 5.6000000000 0.6532323956 0.2884843153 0.6532323956 0.0100841143 0.0789510000 204349790 0 1278861312 -0.3274008632 0.0203686543 0.1322867423 142 5.6400000000 0.6621269584 0.2911156015 0.6621269584 0.0101526183 0.0804040000 204351044 0 1279369216 -0.3305256963 0.0205939580 0.1376258433 143 5.6800000000 0.6675658822 0.2937481209 0.6675658822 0.0102259989 0.0749290000 204352298 0 1279877120 -0.3323757052 0.0216164291 0.1412525028 144 5.7200000000 0.6732456684 0.2963835206 0.6732456684 0.0102764313 0.0792680000 204353552 0 1280385024 -0.3345069289 0.0221333131 0.1441175938 145 5.7600000000 0.6780995727 0.2990160451 0.6780995727 0.0102797440 0.0925180000 204354806 0 1280892928 -0.3364561796 0.0217931904 0.1466945261 146 5.8000000000 0.6838271022 0.3016517372 0.6838271022 0.0102796446 0.0771570000 204356060 0 1281527808 -0.3384586275 0.0218819156 0.1501446217 147 5.8400000000 0.6950677633 0.3043280367 0.6950677633 0.0102960415 0.0811010000 204357314 0 1282035712 -0.3419132829 0.0218538828 0.1576835066 148 5.8800000000 0.6967379451 0.3069794550 0.6967379451 0.0102715452 0.0946920000 204358568 0 1282543616 -0.3423889577 0.0217575543 0.1588755399 149 5.9200000000 0.7021251917 0.3096314398 0.7021251917 0.0102576888 0.0905920000 204359822 0 1283051520 -0.3438850641 0.0220236182 0.1627967954 150 5.9600000000 0.7064827085 0.3122771150 0.7064827085 0.0102370428 0.0877380000 204361076 0 1283559424 -0.3451197445 0.0219351668 0.1660286933 151 6.0000000000 0.7110495567 0.3149179921 0.7110495567 0.0102150896 0.2395110000 216663078 0 1296384000 -0.3462056220 0.0222337842 0.1693883836 152 6.0400000000 0.7151370049 0.3175510119 0.7151370049 0.0102097029 0.1129910000 220322180 0 1300320256 -0.3475646079 0.0234801602 0.1740113050 153 6.0800000000 0.7192817330 0.3201767029 0.7192817330 0.0101965049 0.0902310000 223515530 0 1304002560 -0.3490438461 0.0228406768 0.1772301942 154 6.1200000000 0.7244675756 0.3228019683 0.7244675756 0.0102233302 0.0759640000 223516784 0 1304764416 -0.3511894047 0.0225636885 0.1821924448 155 6.1600000000 0.7278093696 0.3254149193 0.7278093696 0.0102526793 0.0724200000 223518038 0 1305399296 -0.3514260948 0.0231957659 0.1849165708 156 6.2000000000 0.7352050543 0.3280417791 0.7352050543 0.0103496057 0.0790250000 223519292 0 1305907200 -0.3526974916 0.0230849274 0.1896995306 157 6.2400000000 0.7390022278 0.3306593616 0.7390022278 0.0104080449 0.0736780000 223520546 0 1306415104 -0.3538649976 0.0230909418 0.1940160841 158 6.2800000000 0.7461206317 0.3332888633 0.7461206317 0.0104823876 0.0782810000 223521800 0 1306923008 -0.3543536961 0.0235638246 0.1993865669 159 6.3200000000 0.7486549616 0.3359012287 0.7486549616 0.0104917585 0.0776380000 223523054 0 1307430912 -0.3545030355 0.0233223271 0.2021942884 160 6.3600000000 0.7540528774 0.3385146765 0.7540528774 0.0105254767 0.0760280000 223524308 0 1307938816 -0.3547536135 0.0238053910 0.2076497823 161 6.4000000000 0.7569117546 0.3411134161 0.7569117546 0.0105038464 0.0848090000 223525562 0 1308446720 -0.3549450934 0.0236644112 0.2115329504 162 6.4400000000 0.7604390383 0.3437018459 0.7604390383 0.0104797875 0.2376640000 235827416 0 1321381888 -0.3548508286 0.0233563986 0.2156254053 163 6.4800000000 0.7651331425 0.3462873139 0.7651331425 0.0104641043 0.1073900000 239487358 0 1325318144 -0.3549914360 0.0238235556 0.2204719931 164 6.5200000000 0.7687261701 0.3488631606 0.7687261701 0.0104349902 0.0757770000 242680708 0 1329127424 -0.3551807702 0.0242688712 0.2249079943 165 6.5600000000 0.7752951980 0.3514475972 0.7752951980 0.0104045982 0.0773690000 242681962 0 1329889280 -0.3553781211 0.0249145329 0.2311642617 166 6.6000000000 0.7783526778 0.3540193146 0.7783526778 0.0103807911 0.0727390000 242683216 0 1330397184 -0.3551954925 0.0253710579 0.2354069203 167 6.6400000000 0.7819418311 0.3565817248 0.7819418311 0.0103550095 0.0705930000 242684470 0 1330905088 -0.3544251323 0.0256493222 0.2383809686 168 6.6800000000 0.7856276631 0.3591355697 0.7856276631 0.0103270489 0.0695210000 242685724 0 1331412992 -0.3542238176 0.0256500784 0.2432068735 169 6.7200000000 0.7900998592 0.3616856543 0.7900998592 0.0102986249 0.0765440000 242686978 0 1331920896 -0.3544889390 0.0252566878 0.2487178594 170 6.7600000000 0.7972372174 0.3642477223 0.7972372174 0.0103028253 0.0734850000 242688232 0 1332555776 -0.3551057875 0.0258583650 0.2548741102 171 6.8000000000 0.8000502586 0.3667962751 0.8000502586 0.0102913067 0.0758670000 242689486 0 1333063680 -0.3546607494 0.0267327037 0.2580031753 172 6.8400000000 0.8043819070 0.3693403776 0.8043819070 0.0102709757 0.0865670000 242690740 0 1333571584 -0.3544632494 0.0272247437 0.2626252472 173 6.8800000000 0.8098071814 0.3718864285 0.8098071814 0.0102522889 0.0787030000 242691994 0 1334079488 -0.3544661701 0.0278861765 0.2675212622 174 6.9200000000 0.8149161935 0.3744325766 0.8149161935 0.0102332352 0.0734550000 242693248 0 1334587392 -0.3549264967 0.0285196081 0.2720630169 175 6.9600000000 0.8190322518 0.3769731462 0.8190322518 0.0102120646 0.0868030000 242694502 0 1335095296 -0.3547048867 0.0289661475 0.2764002681 176 7.0000000000 0.8252726793 0.3795203026 0.8252726793 0.0101961476 0.0880010000 242695756 0 1335603200 -0.3551716805 0.0291148145 0.2816453576 177 7.0400000000 0.8273139596 0.3820502103 0.8273139596 0.0101868881 0.0863700000 242697010 0 1336111104 -0.3547866344 0.0280929171 0.2841733694 178 7.0800000000 0.8294712305 0.3845638115 0.8294712305 0.0101599772 0.0847910000 242698264 0 1336745984 -0.3543307185 0.0280307848 0.2866745889 179 7.1200000000 0.8346336484 0.3870781682 0.8346336484 0.0101504401 0.2884540000 255002974 0 1349443584 -0.3542712629 0.0287229512 0.2914314866 180 7.1600000000 0.8398844600 0.3895937587 0.8398844600 0.0101322287 0.1039110000 258662076 0 1353506816 -0.3537512124 0.0289259925 0.2954109907 181 7.2000000000 0.8428816199 0.3920981115 0.8428816199 0.0101044538 0.0829480000 261855426 0 1357189120 -0.3529670835 0.0292490758 0.2995298803 182 7.2400000000 0.8488826752 0.3946079168 0.8488826752 0.0100798589 0.0712790000 261856680 0 1357950976 -0.3527709246 0.0289577227 0.3043605089 183 7.2800000000 0.8561573029 0.3971300446 0.8561573029 0.0100593466 0.0764780000 261857934 0 1358458880 -0.3534481525 0.0297964364 0.3102976978 184 7.3200000000 0.8596983552 0.3996440028 0.8596983552 0.0100345289 0.0697590000 261859188 0 1358966784 -0.3524969220 0.0292860884 0.3136952519 185 7.3600000000 0.8648719192 0.4021587483 0.8648719192 0.0100188775 0.0743050000 261860442 0 1359474688 -0.3521735668 0.0294799246 0.3194408417 186 7.4000000000 0.8726631999 0.4046883421 0.8726631999 0.0100179632 0.0714570000 261861696 0 1360109568 -0.3520058095 0.0295402370 0.3258995116 187 7.4400000000 0.8744179010 0.4072002649 0.8744179010 0.0100060571 0.0703830000 261862950 0 1360617472 -0.3507229686 0.0293566138 0.3294228315 188 7.4800000000 0.8800787330 0.4097155759 0.8800787330 0.0100241411 0.0723870000 261864204 0 1361125376 -0.3500957489 0.0306585040 0.3342661560 189 7.5200000000 0.8865207434 0.4122383545 0.8865207434 0.0100109548 0.0735690000 261865458 0 1361633280 -0.3493975997 0.0313003846 0.3406423032 190 7.5600000000 0.8924891949 0.4147659905 0.8924891949 0.0099859756 0.0722990000 261866712 0 1362141184 -0.3479802310 0.0303374324 0.3454978466 191 7.6000000000 0.8985893726 0.4172990973 0.8985893726 0.0099856500 0.3410110000 274184510 0 1374973952 -0.3479679823 0.0313706808 0.3514595032 192 7.6400000000 0.9042173624 0.4198351299 0.9042173624 0.0099859615 0.1066670000 277843612 0 1378910208 -0.3464502394 0.0327632241 0.3561179340 193 7.6800000000 0.9120182395 0.4223853014 0.9120182395 0.0099641458 0.0751290000 281036962 0 1382719488 -0.3465333879 0.0319739506 0.3630455136 194 7.7200000000 0.9194725156 0.4249476067 0.9194725156 0.0099498943 0.0748710000 281038216 0 1383481344 -0.3465229869 0.0315765776 0.3687393069 195 7.7600000000 0.9249477386 0.4275117099 0.9249477386 0.0099621973 0.0742580000 281039470 0 1383989248 -0.3460325003 0.0316024087 0.3731586635 196 7.8000000000 0.9319409132 0.4300853283 0.9319409132 0.0100159442 0.0752150000 281040724 0 1384497152 -0.3453625739 0.0323707126 0.3790451586 197 7.8400000000 0.9366095662 0.4326565173 0.9366095662 0.0100520173 0.0721300000 281041978 0 1385005056 -0.3448157609 0.0335499234 0.3832895160 198 7.8800000000 0.9440625310 0.4352393760 0.9440625310 0.0100950575 0.0719200000 281043232 0 1385512960 -0.3442916572 0.0346424617 0.3892309964 199 7.9200000000 0.9504911304 0.4378285808 0.9504911304 0.0100956010 0.0689630000 281044486 0 1386020864 -0.3436577916 0.0342786908 0.3947914243 200 7.9600000000 0.9566283822 0.4404225798 0.9566283822 0.0100998046 0.3747210000 293350348 0 1398845440 -0.3437818289 0.0337360650 0.4000286460 201 8.0000000000 0.9649852514 0.4430323443 0.9649852514 0.0101476434 0.0894070000 297009450 0 1403035648 -0.3433530331 0.0339832902 0.4071685672 202 8.0400000000 0.9696269631 0.4456392484 0.9696269631 0.0101555908 0.0720390000 300202800 0 1406717952 -0.3420802653 0.0336733311 0.4099365473 203 8.0800000000 0.9767532349 0.4482555734 0.9767532349 0.0101804528 0.0715250000 300204054 0 1407479808 -0.3416115642 0.0343754329 0.4161137640 204 8.1200000000 0.9812716246 0.4508683972 0.9812716246 0.0101764893 0.0674250000 300205308 0 1407987712 -0.3411647081 0.0334879011 0.4213275611 205 8.1600000000 0.9857473969 0.4534775631 0.9857473969 0.0101665648 0.0635230000 300206562 0 1408495616 -0.3400350511 0.0337446854 0.4254910946 206 8.1999999990 0.9912689924 0.4560882011 0.9912689924 0.0101584979 0.0674400000 300207816 0 1409003520 -0.3386713862 0.0340815783 0.4300209284 207 8.2400000000 0.9962755442 0.4586978018 0.9962755442 0.0101532512 0.0684120000 300209070 0 1409638400 -0.3370545805 0.0344510227 0.4347391129 208 8.2799999990 1.0009080172 0.4613045816 1.0009080172 0.0101306186 0.0673830000 300210324 0 1410146304 -0.3354949653 0.0352069847 0.4392606914 209 8.3200000000 1.0050262213 0.4639061206 1.0050262213 0.0101069370 0.0607050000 300211578 0 1410654208 -0.3338902593 0.0351249203 0.4445423782 210 8.3599999990 1.0087178946 0.4665004624 1.0087178946 0.0100921815 0.0746830000 300212832 0 1411162112 -0.3319807351 0.0354911983 0.4478959739 211 8.4000000000 1.0135239363 0.4690929907 1.0135239363 0.0100752335 0.3953880000 312519698 0 1423986688 -0.3301270902 0.0349288210 0.4529427588 212 8.4399999990 1.0170174837 0.4716775402 1.0170174837 0.0100528531 0.0817980000 316178800 0 1427922944 -0.3273786902 0.0358248614 0.4566878378 213 8.4800000000 1.0218880177 0.4742606880 1.0218880177 0.0100291962 0.0684910000 319372150 0 1431732224 -0.3250841498 0.0371207297 0.4619652331 214 8.5200000000 1.0250253677 0.4768343547 1.0250253677 0.0100349660 0.0657960000 319373404 0 1432494080 -0.3226347864 0.0363857113 0.4669245780 215 8.5600000000 1.0274757147 0.4793954773 1.0274757147 0.0100234635 0.0624820000 319374658 0 1433001984 -0.3199805319 0.0362488069 0.4703410864 216 8.6000000000 1.0303477049 0.4819461820 1.0303477049 0.0100068571 0.0620170000 319375912 0 1433509888 -0.3167303503 0.0371038653 0.4742747843 217 8.6400000000 1.0357825756 0.4844984235 1.0357825756 0.0099979933 0.0616270000 319377166 0 1434017792 -0.3137926161 0.0377994031 0.4801640511 218 8.6800000000 1.0376106501 0.4870356355 1.0376106501 0.0100058536 0.0678690000 319378420 0 1434525696 -0.3103069365 0.0386480615 0.4836164713 219 8.7200000000 1.0389230251 0.4895556693 1.0389230251 0.0099886287 0.0605170000 319379674 0 1435033600 -0.3066602349 0.0395056680 0.4879801869 220 8.7600000000 1.0415954590 0.4920649411 1.0415954590 0.0099721950 0.0639490000 319380928 0 1435668480 -0.3030706644 0.0407580808 0.4920036793 221 8.8000000000 1.0448502302 0.4945662320 1.0448502302 0.0099666334 0.0771950000 319382182 0 1436176384 -0.2995093465 0.0413424335 0.4960340858 222 8.8400000000 1.0494520664 0.4970657177 1.0494520664 0.0099503175 0.0649920000 319383436 0 1436684288 -0.2963365316 0.0412582383 0.5011515617 223 8.8800000000 1.0508024693 0.4995488421 1.0508024693 0.0099359232 0.0633420000 319384690 0 1437192192 -0.2929980159 0.0422520526 0.5045568943 224 8.9200000000 1.0532546043 0.5020207429 1.0532546043 0.0099181047 0.0779940000 319385944 0 1437700096 -0.2886953652 0.0434423611 0.5085747838 225 8.9600000000 1.0542514324 0.5044751015 1.0542514324 0.0099017760 0.0725160000 319387198 0 1438208000 -0.2850067914 0.0438136235 0.5114227533 226 9.0000000000 1.0572477579 0.5069209982 1.0572477579 0.0098805559 0.0739980000 319388452 0 1438715904 -0.2813266814 0.0453793332 0.5155460238 227 9.0400000000 1.0582113266 0.5093495899 1.0582113266 0.0098652417 0.0780350000 319389706 0 1439223808 -0.2769026458 0.0476771183 0.5186905265 228 9.0800000000 1.0622458458 0.5117745735 1.0622458458 0.0098655348 0.0806610000 319390960 0 1439731712 -0.2728677392 0.0494769029 0.5236781240 229 9.1200000000 1.0634251833 0.5141835282 1.0634251833 0.0099010991 0.0763740000 319392214 0 1440239616 -0.2691063285 0.0506148972 0.5262110233 230 9.1600000000 1.0640877485 0.5165744161 1.0640877485 0.0099707888 0.0721550000 319393468 0 1440874496 -0.2656255364 0.0509344153 0.5285173655 231 9.2000000000 1.0650570393 0.5189487997 1.0650570393 0.0100736661 0.0728040000 319394722 0 1441382400 -0.2621500492 0.0518777482 0.5316764712 232 9.2400000000 1.0674654245 0.5213130955 1.0674654245 0.0101435249 0.0792130000 319395976 0 1441890304 -0.2586177886 0.0533359535 0.5342269540 233 9.2800000000 1.0686982870 0.5236623882 1.0686982870 0.0102098961 0.0803180000 319397230 0 1442398208 -0.2551952600 0.0544839166 0.5370000601 234 9.3200000000 1.0698795319 0.5259966495 1.0698795319 0.0102647464 0.0744370000 319398484 0 1442906112 -0.2521237135 0.0543070212 0.5393409133 235 9.3600000000 1.0713986158 0.5283175089 1.0713986158 0.0102885813 0.0790400000 319399738 0 1443414016 -0.2481801808 0.0566951036 0.5418210030 236 9.4000000000 1.0736641884 0.5306282999 1.0736641884 0.0103111334 0.0795280000 319400992 0 1443921920 -0.2448318899 0.0572929718 0.5449303389 237 9.4400000000 1.0747858286 0.5329243233 1.0747858286 0.0103211271 0.0761530000 319402246 0 1444429824 -0.2412774116 0.0585607812 0.5471639037 238 9.4800000000 1.0765223503 0.5352083486 1.0765223503 0.0103241480 0.0788920000 319403500 0 1444937728 -0.2373639494 0.0610507689 0.5500479341 239 9.5200000000 1.0785076618 0.5374815675 1.0785076618 0.0103509347 0.0750730000 319404754 0 1445445632 -0.2338252962 0.0620791279 0.5523306131 240 9.5600000000 1.0813223124 0.5397475706 1.0813223124 0.0103790575 0.0756950000 319406008 0 1446080512 -0.2304729074 0.0630045086 0.5551471710 241 9.6000000000 1.0834497213 0.5420035961 1.0834497213 0.0103974546 0.0777800000 319407262 0 1446588416 -0.2267772704 0.0642938763 0.5588783622 242 9.6400000000 1.0862194300 0.5442524218 1.0862194300 0.0103999378 0.4244810000 331715324 0 1459412992 -0.2233112454 0.0653612316 0.5616808534 243 9.6800000000 1.0872260332 0.5464868812 1.0872260332 0.0103947605 0.0999650000 335374426 0 1463349248 -0.2203142792 0.0667807385 0.5654063225 244 9.7200000000 1.0899795294 0.5487143100 1.0899795294 0.0104010282 0.0934430000 338567776 0 1467158528 -0.2165182829 0.0686636493 0.5678303242 245 9.7600000000 1.0919765234 0.5509317068 1.0919765234 0.0104142107 0.0925810000 338569030 0 1467793408 -0.2124854028 0.0696942359 0.5712326169 246 9.8000000000 1.0951728821 0.5531440693 1.0951728821 0.0104084933 0.0972060000 338570284 0 1468428288 -0.2089581788 0.0703627467 0.5742379427 247 9.8400000000 1.0989394188 0.5553537671 1.0989394188 0.0103982474 0.0924300000 338571538 0 1468936192 -0.2055997699 0.0704721808 0.5777372718 248 9.8800000000 1.1020497084 0.5575581862 1.1020497084 0.0103787831 0.0866970000 338572792 0 1469444096 -0.2023139000 0.0709169433 0.5807316899 249 9.9200000000 1.1043138504 0.5597539921 1.1043138504 0.0103620633 0.0827200000 338574046 0 1469952000 -0.1989833266 0.0713093206 0.5836230516 250 9.9600000000 1.1080093384 0.5619470135 1.1080093384 0.0103498510 0.0828650000 338575300 0 1470459904 -0.1952547729 0.0723114982 0.5866066217 251 10.0000000000 1.1113600731 0.5641359101 1.1113600731 0.0103361819 0.0845120000 338576554 0 1470967808 -0.1916813850 0.0732912198 0.5897135139 252 10.0400000000 1.1157010794 0.5663246608 1.1157010794 0.0103228723 0.0842840000 338577808 0 1471475712 -0.1886922717 0.0726661012 0.5936142206 253 10.0800000000 1.1198225021 0.5685123993 1.1198225021 0.0103139264 0.0818510000 338579062 0 1472110592 -0.1859738827 0.0713740587 0.5972085595 254 10.1200000000 1.1234194040 0.5706970726 1.1234194040 0.0103378261 0.0818600000 338580316 0 1472618496 -0.1824756265 0.0725731701 0.6004584432 255 10.1600000000 1.1272954941 0.5728798115 1.1272954941 0.0103563927 0.0901260000 338581570 0 1473126400 -0.1786149293 0.0750016421 0.6034691334 256 10.2000000000 1.1305195093 0.5750580915 1.1305195093 0.0103441151 0.0839140000 338582824 0 1473634304 -0.1746358722 0.0765582100 0.6066455841 257 10.2400000000 1.1342113018 0.5772337850 1.1342113018 0.0103273124 0.0827980000 338605582 0 1474142208 -0.1715226024 0.0763652846 0.6095930934 258 10.2800000000 1.1378731728 0.5794068058 1.1378731728 0.0103112775 0.0853560000 338648820 0 1474777088 -0.1675398648 0.0780268386 0.6130447984 259 10.3200000000 1.1403305531 0.5815725346 1.1403305531 0.0102924180 0.4870070000 350988538 0 1487593472 -0.1637909710 0.0794088691 0.6151978970 260 10.3600000000 1.1432216167 0.5837327234 1.1432216167 0.0102786512 0.1106490000 354647640 0 1491529728 -0.1600703001 0.0820147097 0.6184805036 261 10.4000000000 1.1455483437 0.5858852736 1.1455483437 0.0102639278 0.0914630000 357840990 0 1495212032 -0.1566589922 0.0817708522 0.6211354733 262 10.4400000000 1.1485308409 0.5880327758 1.1485308409 0.0102446523 0.0853570000 357842244 0 1495973888 -0.1533162743 0.0817176104 0.6235976219 263 10.4800000000 1.1503921747 0.5901710245 1.1503921747 0.0102253509 0.0833050000 357843498 0 1496608768 -0.1495514363 0.0821840391 0.6255800128 264 10.5200000000 1.1522901058 0.5923002634 1.1522901058 0.0102080642 0.0817060000 357844752 0 1497116672 -0.1458235383 0.0820602179 0.6278039813 265 10.5600000000 1.1546410322 0.5944223041 1.1546410322 0.0101913675 0.0806530000 357846006 0 1497624576 -0.1419044584 0.0825231895 0.6298875809 266 10.6000000000 1.1556470394 0.5965321715 1.1556470394 0.0101820487 0.0805920000 357847260 0 1498132480 -0.1377546191 0.0831671730 0.6314582229 267 10.6400000000 1.1564384699 0.5986291988 1.1564384699 0.0101777259 0.0767570000 357848514 0 1498640384 -0.1337623000 0.0828560069 0.6328725815 268 10.6800000000 1.1586514711 0.6007188342 1.1586514711 0.0101654471 0.0817620000 357849768 0 1499148288 -0.1297091842 0.0825574398 0.6350159645 269 10.7200000000 1.1583645344 0.6027918665 1.1586514711 0.0101529489 0.0916350000 357851022 0 1499656192 -0.1255283654 0.0824505389 0.6358839273 270 10.7600000000 1.1618512869 0.6048624569 1.1618512869 0.0101528922 0.0891250000 357852276 0 1500291072 -0.1165235043 0.0840214789 0.6396794915 271 10.8000000000 1.1624671221 0.6069200387 1.1624671221 0.0101773378 0.0833380000 357853530 0 1500798976 -0.1114866808 0.0852264613 0.6408154964 272 10.8400000000 1.1631122828 0.6089648632 1.1631122828 0.0102338531 0.0954740000 357854784 0 1501306880 -0.1071771160 0.0845486447 0.6421201229 273 10.8800000000 1.1644377708 0.6109995625 1.1644377708 0.0102366429 0.0868130000 357856038 0 1501814784 -0.1026350558 0.0847683996 0.6438310742 274 10.9200000000 1.1653928757 0.6130228957 1.1653928757 0.0102410835 0.0936880000 357857292 0 1502322688 -0.0979471281 0.0851557106 0.6450666785 275 10.9600000000 1.1658052206 0.6150330133 1.1658052206 0.0102465698 0.4649040000 370166234 0 1515274240 -0.0934501663 0.0851352662 0.6459681988 276 11.0000000000 1.1666945219 0.6170317868 1.1666945219 0.0102387624 0.1113670000 373825336 0 1519210496 -0.0877050906 0.0864810720 0.6476469040 277 11.0400000000 1.1675258875 0.6190191302 1.1675258875 0.0102418742 0.0948310000 377018686 0 1523011584 -0.0828922316 0.0869072750 0.6489626765 278 11.0800000000 1.1682015657 0.6209946066 1.1682015657 0.0102480765 0.0812210000 377019940 0 1523646464 -0.0780331045 0.0873834416 0.6505456567 279 11.1200000000 1.1694052219 0.6229602360 1.1694052219 0.0102581352 0.0766570000 377021194 0 1524281344 -0.0729058981 0.0879032835 0.6521978974 280 11.1600000000 1.1710208654 0.6249175954 1.1710208654 0.0102737931 0.0848220000 377022448 0 1524789248 -0.0681358799 0.0887938514 0.6527597308 281 11.2000000000 1.1717439890 0.6268635968 1.1717439890 0.0102835469 0.0839130000 377023702 0 1525297152 -0.0634755194 0.0890657976 0.6536659002 282 11.2400000000 1.1737449169 0.6288028923 1.1737449169 0.0102774400 0.0806970000 377024956 0 1525805056 -0.0591735207 0.0886294097 0.6553179622 283 11.2800000000 1.1746218204 0.6307315811 1.1746218204 0.0102635168 0.0808000000 377026210 0 1526312960 -0.0548661575 0.0890635401 0.6561244726 284 11.3200000000 1.1775275469 0.6326569190 1.1775275469 0.0102519972 0.0842040000 377027464 0 1526820864 -0.0504140146 0.0897729918 0.6579679251 285 11.3600000000 1.1791194677 0.6345743314 1.1791194677 0.0102547295 0.0902060000 377028718 0 1527328768 -0.0464388989 0.0898552984 0.6599023342 286 11.4000000000 1.1814823151 0.6364865971 1.1814823151 0.0102566688 0.0803020000 377029972 0 1527963648 -0.0425992832 0.0900143236 0.6608746648 287 11.4400000000 1.1835119724 0.6383926088 1.1835119724 0.0102524106 0.0834800000 377031226 0 1528471552 -0.0392187834 0.0897487774 0.6623755693 288 11.4800000000 1.1857118607 0.6402930229 1.1857118607 0.0102471315 0.1046230000 377032480 0 1528987648 -0.0360271893 0.0897394717 0.6636737585 289 11.5200000000 1.1893945932 0.6421930284 1.1893945932 0.0102431584 0.0922560000 377033734 0 1529495552 -0.0330840908 0.0895390809 0.6660023928 290 11.5600000000 1.1928281784 0.6440917702 1.1928281784 0.0102407993 0.0952050000 377034988 0 1530011648 -0.0301265009 0.0896064043 0.6680647731 291 11.6000000000 1.1969971657 0.6459917888 1.1969971657 0.0102350244 0.0957680000 377036242 0 1530519552 -0.0274198409 0.0892704800 0.6705003977 292 11.6400000000 1.2004373074 0.6478905748 1.2004373074 0.0102306266 0.1002400000 377037496 0 1531027456 -0.0245596711 0.0895347819 0.6725593805 293 11.6800000000 1.2045376301 0.6497903941 1.2045376301 0.0102234827 0.0977100000 377038750 0 1531535360 -0.0220078658 0.0894610062 0.6750724912 294 11.7200000000 1.2090724707 0.6516927141 1.2090724707 0.0102135162 0.1012950000 377040004 0 1532043264 -0.0199057031 0.0891406164 0.6774806380 295 11.7600000000 1.2134149075 0.6535968571 1.2134149075 0.0102070335 0.0998850000 377041258 0 1532678144 -0.0178239048 0.0889908001 0.6799201965 296 11.8000000000 1.2173588276 0.6555014584 1.2173588276 0.0102004097 0.1022180000 377042512 0 1533186048 -0.0157038886 0.0889090374 0.6823117733 297 11.8400000000 1.2220003605 0.6574088621 1.2220003605 0.0101974298 0.1032620000 377043766 0 1533693952 -0.0139495516 0.0886960775 0.6850124598 298 11.8800000000 1.2269097567 0.6593199389 1.2269097567 0.0102017099 0.1013350000 377045020 0 1534201856 -0.0121500110 0.0883871987 0.6878730655 299 11.9200000000 1.2319976091 0.6612352489 1.2319976091 0.0102008566 0.1015190000 377046274 0 1534709760 -0.0103196306 0.0882246122 0.6908285022 300 11.9600000000 1.2372682095 0.6631553587 1.2372682095 0.0101927707 0.5383590000 389356352 0 1547534336 -0.0084866565 0.0884066522 0.6937891841 301 12.0000000000 1.2420710325 0.6650786666 1.2420710325 0.0101853301 0.1193270000 393015454 0 1551597568 -0.0063400012 0.0884854421 0.6980793476 302 12.0400000000 1.2483757734 0.6670101140 1.2483757734 0.0101828496 0.0973410000 396208804 0 1555279872 -0.0048737805 0.0882406458 0.7015631199 303 12.0800000000 1.2543073893 0.6689483888 1.2543073893 0.0101890976 0.0854280000 396210058 0 1556041728 -0.0033955928 0.0882933885 0.7054798007 304 12.1200000000 1.2609407902 0.6708957322 1.2609407902 0.0102002745 0.0866360000 396211312 0 1556549632 -0.0017752241 0.0882142633 0.7090133429 305 12.1600000000 1.2680908442 0.6728537490 1.2680908442 0.0102103952 0.0886010000 396212566 0 1557057536 -0.0004161657 0.0880656838 0.7131412625 306 12.2000000000 1.2753077745 0.6748225530 1.2753077745 0.0102157169 0.0871160000 396213820 0 1557692416 0.0010344310 0.0878971219 0.7173578739 307 12.2400000000 1.2827430964 0.6768027502 1.2827430964 0.0102302897 0.0835250000 396215074 0 1558200320 0.0021298036 0.0879977643 0.7214166522 308 12.2800000000 1.2901220322 0.6787940466 1.2901220322 0.0102514382 0.0827550000 396216328 0 1558708224 0.0030899232 0.0880354419 0.7256569862 309 12.3200000000 1.2969012260 0.6807943934 1.2969012260 0.0102834852 0.0903570000 396217582 0 1559216128 0.0040244488 0.0877259672 0.7297107577 310 12.3600000000 1.3043224812 0.6828057744 1.3043224812 0.0103299619 0.1001970000 396218836 0 1559724032 0.0047762454 0.0874839872 0.7341158390 311 12.4000000000 1.3111323118 0.6848261169 1.3111323118 0.0103606722 0.0889620000 396220090 0 1560231936 0.0056737205 0.0877270326 0.7380772829 312 12.4400000000 1.3262665272 0.6868820157 1.3262665272 0.0104665311 0.0982860000 396221344 0 1560739840 0.0066728164 0.0874905065 0.7467588186 313 12.4800000000 1.3329354525 0.6889460842 1.3329354525 0.0104678148 0.1102900000 396222598 0 1561247744 0.0070480155 0.0872583538 0.7507681251 314 12.5200000000 1.3408042192 0.6910220655 1.3408042192 0.0104703388 0.1044970000 396223852 0 1561755648 0.0072270273 0.0869491994 0.7553464770 315 12.5600000000 1.3480296135 0.6931078037 1.3480296135 0.0104776425 0.1058790000 396225106 0 1562390528 0.0073787458 0.0868634135 0.7594581842 316 12.6000000000 1.3556011915 0.6952043018 1.3556011915 0.0104791978 0.1093080000 396226360 0 1562898432 0.0077359709 0.0869614333 0.7640995383 317 12.6400000000 1.3628543615 0.6973104534 1.3628543615 0.0104801449 0.1072540000 396227614 0 1563406336 0.0077903736 0.0867347047 0.7682954669 318 12.6800000000 1.3700052500 0.6994258459 1.3700052500 0.0104848149 0.1126850000 396228868 0 1563914240 0.0077551571 0.0864950269 0.7725846767 319 12.7200000000 1.3763047457 0.7015477233 1.3763047457 0.0104943829 0.1134850000 396230122 0 1564422144 0.0075820899 0.0864129141 0.7763491869 320 12.7600000000 1.3828784227 0.7036768817 1.3828784227 0.0105049740 0.1132930000 396231376 0 1564930048 0.0072409306 0.0863081440 0.7800908685 321 12.8000000000 1.3894332647 0.7058131944 1.3894332647 0.0105262323 0.1146230000 396232630 0 1565437952 0.0066538951 0.0859727263 0.7840276361 322 12.8400000000 1.3955305815 0.7079551739 1.3955305815 0.0105612702 0.1085400000 396233884 0 1565945856 0.0060897749 0.0861363560 0.7872561812 323 12.8800000000 1.4006607533 0.7100997732 1.4006607533 0.0106157835 0.1127740000 396235138 0 1566453760 0.0055557126 0.0856257528 0.7906527519 324 12.9200000000 1.4064388275 0.7122489678 1.4064388275 0.0106702512 0.6121050000 408548460 0 1579278336 0.0051747994 0.0853927732 0.7939394712 325 12.9600000000 1.4121723175 0.7144025781 1.4121723175 0.0107307640 0.1476470000 412209218 0 1583341568 0.0051475638 0.0863175318 0.7971737981 326 13.0000000000 1.4166582823 0.7165567367 1.4166582823 0.0108151253 0.1286780000 415402568 0 1587023872 0.0042077149 0.0861671194 0.7998187542 327 13.0400000000 1.4226861000 0.7187161538 1.4226861000 0.0109127661 0.1161920000 415403822 0 1587785728 0.0035180924 0.0861658603 0.8034307957 328 13.0800000000 1.4268804789 0.7208751913 1.4268804789 0.0110081896 0.1083750000 415405076 0 1588420608 0.0032547654 0.0869395137 0.8057091832 329 13.1200000000 1.4323899746 0.7230378502 1.4323899746 0.0110934610 0.0997620000 415406330 0 1588928512 0.0028637713 0.0872226357 0.8092136383 330 13.1600000000 1.4373104572 0.7252023127 1.4373104572 0.0111718647 0.0959490000 415407584 0 1589436416 0.0023011481 0.0872443467 0.8121885061 331 13.2000000000 1.4433510303 0.7273719463 1.4433510303 0.0112424615 0.0951120000 415408838 0 1589944320 0.0016490854 0.0872557610 0.8159117699 332 13.2400000000 1.4484903812 0.7295439898 1.4484903812 0.0112942709 0.0912520000 415410092 0 1590452224 0.0012503903 0.0874785036 0.8191731572 333 13.2800000000 1.4543063641 0.7317204533 1.4543063641 0.0113470428 0.5866390000 427719590 0 1603403776 0.0007834949 0.0876217708 0.8227665424 334 13.3200000000 1.4595321417 0.7338995303 1.4595321417 0.0114179105 0.1812170000 431378692 0 1607340032 -0.0003562724 0.0875260681 0.8254938722 335 13.3600000000 1.4648817778 0.7360815668 1.4648817778 0.0114673260 0.1550990000 434572042 0 1611022336 -0.0007683860 0.0879278928 0.8289424181 336 13.4000000000 1.4701861143 0.7382664018 1.4701861143 0.0115390184 0.1469490000 434573296 0 1611784192 -0.0013561749 0.0882852748 0.8316484690 337 13.4400000000 1.4750403166 0.7404526745 1.4750403166 0.0116499295 0.1479620000 434574550 0 1612419072 -0.0018656753 0.0891973227 0.8344497681 338 13.4800000000 1.4789291620 0.7426375162 1.4789291620 0.0117667196 0.1373610000 434575804 0 1612926976 -0.0023590934 0.0897431597 0.8369367719 339 13.5200000000 1.4823421240 0.7448195357 1.4823421240 0.0118854867 0.1385520000 434577058 0 1613561856 -0.0031696595 0.0897969380 0.8390609622 340 13.5600000000 1.4855993986 0.7469983000 1.4855993986 0.0119614525 0.1627000000 434578312 0 1614069760 -0.0040095588 0.0898766741 0.8408803940 341 13.6000000000 1.4886935949 0.7491733595 1.4886935949 0.0120393744 0.8987680000 446893410 0 1627148288 -0.0048437878 0.0899906680 0.8425883055 342 13.6400000000 1.4936816692 0.7513502844 1.4936816692 0.0121155283 0.1860700000 450552512 0 1631211520 -0.0071287351 0.0911619738 0.8431235552 343 13.6800000000 1.4966392517 0.7535231385 1.4966392517 0.0121525018 0.1485240000 453745862 0 1634893824 -0.0076749297 0.0916106626 0.8449537754 344 13.7200000000 1.4997862577 0.7556925081 1.4997862577 0.0122049633 0.1454370000 453747116 0 1635655680 -0.0077679208 0.0922632515 0.8474073410 345 13.7600000000 1.5034737587 0.7578599899 1.5034737587 0.0122868214 0.1395150000 453748370 0 1636290560 -0.0085869832 0.0919087604 0.8492196798 346 13.8000000000 1.5066417456 0.7600240991 1.5066417456 0.0123646634 0.1261750000 453749624 0 1636925440 -0.0091283303 0.0920137241 0.8510700464 347 13.8400000000 1.5092804432 0.7621833393 1.5092804432 0.0123993273 0.1224540000 453750878 0 1637433344 -0.0099105695 0.0915228277 0.8528875113 348 13.8800000000 1.5128917694 0.7643405474 1.5128917694 0.0124262957 0.1258480000 453752132 0 1638068224 -0.0101076290 0.0924016535 0.8551729321 349 13.9200000000 1.5163598061 0.7664953304 1.5163598061 0.0124627078 0.1277870000 453753386 0 1638576128 -0.0106637385 0.0922546163 0.8574703932 350 13.9600000000 1.5218012333 0.7686533472 1.5218012333 0.0125209468 1.2603210000 466126852 0 1651908608 -0.0112762973 0.0918371677 0.8607237339 351 14.0000000000 1.5319559574 0.7708279985 1.5319559574 0.0125443415 0.1821090000 469785954 0 1655971840 -0.0143578975 0.0933464020 0.8545121551 352 14.0400000000 1.5348793268 0.7729985989 1.5348793268 0.0125388753 0.1328220000 472979304 0 1659654144 -0.0146138882 0.0930053815 0.8562313318 353 14.0800000000 1.5373950005 0.7751640278 1.5373950005 0.0125246606 0.1299390000 472980558 0 1660416000 -0.0146341026 0.0927746370 0.8579201698 354 14.1200000000 1.5404330492 0.7773258047 1.5404330492 0.0125154477 0.1241170000 472981812 0 1660923904 -0.0144896246 0.0929444209 0.8596742153 355 14.1600000000 1.5432088375 0.7794832217 1.5432088375 0.0125055379 0.1214120000 472983066 0 1661558784 -0.0146104302 0.0923658088 0.8615536690 356 14.2000000000 1.5461014509 0.7816366437 1.5461014509 0.0124981754 0.1081670000 472984320 0 1662066688 -0.0144961867 0.0922073275 0.8632937074 357 14.2400000000 1.5496286154 0.7837878817 1.5496286154 0.0124910717 0.1385790000 472985574 0 1662574592 -0.0143571058 0.0924708694 0.8653556705 358 14.2800000000 1.5527447462 0.7859358059 1.5527447462 0.0124809954 0.1319510000 472986828 0 1663082496 -0.0144079225 0.0919109285 0.8675603271 359 14.3200000000 1.5559386015 0.7880806605 1.5559386015 0.0124667460 0.1330720000 472988082 0 1663590400 -0.0145350508 0.0912404358 0.8697298169 360 14.3600000000 1.5595964193 0.7902237598 1.5595964193 0.0124544723 0.1442630000 472989336 0 1664098304 -0.0146360677 0.0905014202 0.8721317053 361 14.4000000000 1.5634597540 0.7923656878 1.5634597540 0.0124450624 0.1394950000 472990590 0 1664606208 -0.0146104870 0.0904857293 0.8746890426 362 14.4400000000 1.5674757957 0.7945068759 1.5674757957 0.0124336547 0.1407730000 472991844 0 1665241088 -0.0145632764 0.0905535370 0.8772160411 363 14.4800000000 1.5720087290 0.7966487543 1.5720087290 0.0124199852 0.1649100000 472993098 0 1665748992 -0.0145506868 0.0907202587 0.8799048066 364 14.5200000000 1.5763734579 0.7987908551 1.5763734579 0.0124064209 0.1642810000 472994352 0 1666256896 -0.0146634299 0.0903665945 0.8827163577 365 14.5600000000 1.5805633068 0.8009326975 1.5805633068 0.0123925844 0.1704170000 472995606 0 1666764800 -0.0148130460 0.0899721682 0.8855302334 366 14.6000000000 1.5854942799 0.8030763084 1.5854942799 0.0123796539 0.1710110000 472996860 0 1667272704 -0.0148773044 0.0901041701 0.8884987831 367 14.6400000000 1.5901068449 0.8052208057 1.5901068449 0.0123659507 0.1686950000 472998114 0 1667907584 -0.0148919597 0.0904391184 0.8912107348 368 14.6800000000 1.5948760509 0.8073666080 1.5948760509 0.0123591746 0.1726350000 472999368 0 1668415488 -0.0149658117 0.0905465484 0.8941155672 369 14.7200000000 1.5993562937 0.8095129215 1.5993562937 0.0123635198 0.1743680000 473000622 0 1668923392 -0.0152047947 0.0904432386 0.8970378041 370 14.7600000000 1.6042542458 0.8116608711 1.6042542458 0.0123676810 0.1686080000 473001876 0 1669431296 -0.0152823795 0.0904835016 0.9000492692 371 14.8000000000 1.6087129116 0.8138092593 1.6087129116 0.0123699248 0.7023340000 485310930 0 1682382848 -0.0153164174 0.0902475193 0.9028111100 372 14.8400000000 1.6179759502 0.8159709977 1.6179759502 0.0123758764 0.1889900000 488970032 0 1686446080 -0.0154594788 0.0903754234 0.9004724622 373 14.8800000000 1.6225223541 0.8181333338 1.6225223541 0.0124125721 0.1261520000 492163382 0 1690255360 -0.0154598057 0.0902353302 0.9032278061 374 14.9200000000 1.6269242764 0.8202958764 1.6269242764 0.0124562710 0.1228940000 492164636 0 1690890240 -0.0154331801 0.0899423584 0.9061067104 375 14.9600000000 1.6311579943 0.8224581754 1.6311579943 0.0125275598 0.1289300000 492165890 0 1691525120 -0.0153108314 0.0898061022 0.9087929726 376 15.0000000000 1.6358718872 0.8246215098 1.6358718872 0.0126046039 0.1290350000 492167144 0 1692033024 -0.0150109483 0.0902323574 0.9115161300 377 15.0400000000 1.6440014839 0.8267949314 1.6440014839 0.0128714958 0.1280750000 492168398 0 1692532736 -0.0141157741 0.0905808434 0.9165133834 378 15.0800000000 1.6480624676 0.8289675969 1.6480624676 0.0129270242 0.1257650000 492169652 0 1693040640 -0.0133767603 0.0909902677 0.9189836383 379 15.1200000000 1.6515538692 0.8311380092 1.6515538692 0.0129715404 0.1250050000 492170906 0 1693548544 -0.0126259206 0.0911489949 0.9211542010 380 15.1600000000 1.6549040079 0.8333058145 1.6549040079 0.0130196006 0.1253820000 492172160 0 1694183424 -0.0115677472 0.0915558040 0.9231641889 381 15.2000000000 1.6580882072 0.8354705976 1.6580882072 0.0130646009 0.1458830000 492173414 0 1694691328 -0.0106579829 0.0919265300 0.9250569940 382 15.2400000000 1.6610032320 0.8376316778 1.6610032320 0.0131208035 0.9902010000 504483412 0 1707524096 -0.0097531984 0.0920424163 0.9269114733 383 15.2800000000 1.6655389071 0.8397933155 1.6655389071 0.0131795644 0.1768090000 508142514 0 1711460352 -0.0070177787 0.0935568959 0.9268395901 384 15.3200000000 1.6679121256 0.8419498749 1.6679121256 0.0132309465 0.1308230000 511335864 0 1715269632 -0.0060131666 0.0937752873 0.9282701612 385 15.3600000000 1.6694597006 0.8440992511 1.6694597006 0.0132822108 0.1200630000 511337118 0 1715904512 -0.0050998121 0.0935860500 0.9292258024 386 15.4000000000 1.6708122492 0.8462409946 1.6708122492 0.0133287120 0.1168940000 511338372 0 1716539392 -0.0039693508 0.0938196778 0.9300152063 387 15.4400000000 1.6722995043 0.8483755127 1.6722995043 0.0133989758 0.1132750000 511339626 0 1717047296 -0.0025963485 0.0945911780 0.9307564497 388 15.4800000000 1.6729902029 0.8505008083 1.6729902029 0.0135106839 0.1074910000 511340880 0 1717555200 -0.0015320550 0.0950338468 0.9310457706 389 15.5200000000 1.6736099720 0.8526167702 1.6736099720 0.0136221621 0.1035000000 511342134 0 1718063104 -0.0005757947 0.0950628817 0.9314054251 390 15.5600000000 1.6745631695 0.8547243250 1.6745631695 0.0137253805 0.1137980000 511343388 0 1718571008 0.0008452940 0.0962289721 0.9318235517 391 15.6000000000 1.6753196716 0.8568230344 1.6753196716 0.0137873617 0.8932160000 523653994 0 1731395584 0.0020714758 0.0962910503 0.9324144125 392 15.6400000000 1.6751003265 0.8589104764 1.6753196716 0.0138779105 0.1216200000 527313096 0 1735331840 0.0029119069 0.0961415768 0.9330649972 393 15.6800000000 1.6753613949 0.8609879597 1.6753613949 0.0139995494 0.1790720000 530506446 0 1739141120 0.0036465183 0.0954064354 0.9334001541 394 15.7200000000 1.6758714914 0.8630561920 1.6758714914 0.0141489893 0.1538420000 530507700 0 1739902976 0.0044465330 0.0946931764 0.9337313771 395 15.7600000000 1.6762844324 0.8651149977 1.6762844324 0.0142921088 0.1263680000 530508954 0 1740410880 0.0056178290 0.0949098319 0.9338564873 396 15.8000000000 1.6763879061 0.8671636666 1.6763879061 0.0144044454 0.1418630000 530510208 0 1740918784 0.0070148916 0.0950203240 0.9339041114 397 15.8400000000 1.6763979197 0.8692020401 1.6763979197 0.0145403055 0.1316500000 530511462 0 1741426688 0.0080232332 0.0947071239 0.9339137673 398 15.8800000000 1.6760941744 0.8712294072 1.6763979197 0.0146542190 0.1385480000 530512716 0 1741934592 0.0088837603 0.0940416008 0.9335384965 399 15.9200000000 1.6752057076 0.8732443854 1.6763979197 0.0147544589 0.1386000000 530513970 0 1742442496 0.0108334487 0.0947191715 0.9330486655 400 15.9600000000 1.6755686998 0.8752501962 1.6763979197 0.0148400318 1.4324560000 542830148 0 1755267072 0.0123032304 0.0949829221 0.9332334995 401 16.0000000000 1.6767392159 0.8772489220 1.6767392159 0.0149341982 0.1466530000 546489250 0 1759330304 0.0136403022 0.0947693959 0.9327381849 402 16.0400000000 1.6770970821 0.8792385940 1.6770970821 0.0150327671 0.1682260000 549682600 0 1763012608 0.0154332919 0.0949916989 0.9326678514 403 16.0800000000 1.6781030893 0.8812208880 1.6781030893 0.0151050877 0.1393870000 549683854 0 1763774464 0.0173884165 0.0948669240 0.9332400560 404 16.1200000000 1.6776318550 0.8831922023 1.6781030893 0.0151631548 0.1605740000 549685108 0 1764536320 0.0188318603 0.0949446186 0.9328694344 405 16.1600000000 1.6784924269 0.8851559066 1.6784924269 0.0152442968 0.1276130000 549686362 0 1765044224 0.0209654663 0.0949178562 0.9336030483 406 16.2000000000 1.6802200079 0.8871141925 1.6802200079 0.0153580426 0.1231600000 549687616 0 1765552128 0.0231350735 0.0954140127 0.9346218109 407 16.2400000000 1.6816797256 0.8890664420 1.6816797256 0.0154900122 1.7059960000 562007690 0 1778495488 0.0251240749 0.0958549827 0.9352164268 408 16.2800000000 1.6838473082 0.8910144343 1.6838473082 0.0156568858 0.1435450000 565666792 0 1782431744 0.0274715815 0.0960718095 0.9359596968 409 16.3200000000 1.6857405901 0.8929575301 1.6857405901 0.0158004320 0.1276780000 568860142 0 1786241024 0.0295901168 0.0970104635 0.9369710684 410 16.3600000000 1.6886647940 0.8948982795 1.6886647940 0.0159265594 0.1058440000 568861396 0 1786875904 0.0320332088 0.0978183001 0.9387014508 411 16.3999999990 1.6896084547 0.8968318809 1.6896084547 0.0160950769 0.1078260000 568862650 0 1787510784 0.0332471281 0.0974711478 0.9393545389 412 16.4400000000 1.6936280727 0.8987658522 1.6936280727 0.0163182358 0.0990300000 568863904 0 1788018688 0.0352775529 0.0974527299 0.9415896535 413 16.4800000000 1.6979572773 0.9007009404 1.6979572773 0.0165156167 0.1043070000 568865158 0 1785749504 0.0376199707 0.0977481008 0.9441885948 414 16.5200000000 1.7002074718 0.9026321156 1.7002074718 0.0166746347 1.5950360000 581186816 0 1786155008 0.0394880474 0.0970520675 0.9453816414 415 16.5599999990 1.7055565119 0.9045668732 1.7055565119 0.0168417284 0.1414770000 584845918 0 1785528320 0.0399574004 0.0942040831 0.9453280568 416 16.6000000000 1.7093108892 0.9065013540 1.7093108892 0.0170223615 0.1001130000 588039268 0 1786155008 0.0425758176 0.0941502750 0.9473147988 417 16.6400000000 1.7104984522 0.9084294046 1.7104984522 0.0171342707 0.0948550000 588040522 0 1785507840 0.0445846394 0.0945834592 0.9479320645 418 16.6800000000 1.7101509571 0.9103473987 1.7104984522 0.0172304610 0.0870810000 588041776 0 1785507840 0.0457054190 0.0935257226 0.9475005865 419 16.7199999990 1.7138668299 0.9122651062 1.7138668299 0.0173719954 0.0847200000 588043030 0 1786003456 0.0488404892 0.0945402384 0.9497346282 420 16.7600000000 1.7141726017 0.9141744098 1.7141726017 0.0174366001 0.0879980000 588044284 0 1786511360 0.0510208271 0.0952156782 0.9497446418 421 16.8000000000 1.7145451307 0.9160755279 1.7145451307 0.0174845920 1.1891350000 600363294 0 1786527744 0.0529552810 0.0937908068 0.9500788450 422 16.8400000000 1.7158814669 0.9179708026 1.7158814669 0.0177271044 0.1211470000 604022396 0 1785528320 0.0558838770 0.0914602503 0.9505034089 423 16.8799999990 1.7159270048 0.9198572239 1.7159270048 0.0177641858 0.0932130000 607215746 0 1786155008 0.0581325591 0.0908957273 0.9505378604 424 16.9200000000 1.7149599791 0.9217324662 1.7159270048 0.0177874654 0.0878590000 607217000 0 1785507840 0.0602342933 0.0900279433 0.9497458339 425 16.9600000000 1.7136602402 0.9235958257 1.7159270048 0.0178181137 0.0871890000 607218254 0 1785507840 0.0629985332 0.0901940838 0.9488388300 426 17.0000000000 1.7134028673 0.9254498328 1.7159270048 0.0178345941 0.0876740000 607219508 0 1786003456 0.0663226321 0.0901044980 0.9485870600 427 17.0400000000 1.7103952169 0.9272881124 1.7159270048 0.0178473414 0.0884510000 607220762 0 1786511360 0.0684024021 0.0889080614 0.9470403194 428 17.0800000000 1.7083880901 0.9291131124 1.7159270048 0.0178588614 0.7915980000 619533364 0 1787138048 0.0720283464 0.0882376730 0.9459530711 429 17.1200000000 1.7080996037 0.9309289317 1.7159270048 0.0178561486 0.0988240000 623192466 0 1787527168 0.0741720870 0.0872289538 0.9451263547 430 17.1600000000 1.7038437128 0.9327264079 1.7159270048 0.0178561698 0.1127820000 626385816 0 1786155008 0.0771489367 0.0858981088 0.9428019524 431 17.2000000000 1.7019668818 0.9345111886 1.7159270048 0.0178606289 0.1187790000 626387070 0 1785786368 0.0805680975 0.0847191662 0.9413781762 432 17.2400000000 1.6994414330 0.9362818605 1.7159270048 0.0178612281 0.1151980000 626388324 0 1785786368 0.0847331360 0.0839942023 0.9396747351 433 17.2800000000 1.6963089705 0.9380371194 1.7159270048 0.0178527856 0.1062220000 626389578 0 1786261504 0.0886625722 0.0834529847 0.9376364350 434 17.3200000000 1.6913063526 0.9397727628 1.7159270048 0.0178484528 0.1097210000 626390832 0 1786884096 0.0922697708 0.0819724575 0.9344035387 435 17.3600000000 1.6885149479 0.9414940092 1.7159270048 0.0178491470 0.0987660000 626392086 0 1787265024 0.0970474556 0.0817179382 0.9325670600 436 17.4000000000 1.6851494312 0.9431996409 1.7159270048 0.0178389489 0.0985360000 626393340 0 1787392000 0.1024822667 0.0830912665 0.9299815297 437 17.4400000000 1.6813325882 0.9448887323 1.7159270048 0.0178235687 0.0977930000 626394594 0 1787899904 0.1084410697 0.0848984718 0.9265646935 438 17.4800000000 1.6772227287 0.9465607277 1.7159270048 0.0178426260 0.0974280000 626395848 0 1786052608 0.1129817963 0.0850686207 0.9237574935 439 17.5200000000 1.6705762148 0.9482099658 1.7159270048 0.0178865735 1.0890560000 638708598 0 1786163200 0.1154623181 0.0832904354 0.9197617769 440 17.5600000000 1.6643949747 0.9498376590 1.7159270048 0.0178961534 0.1395120000 642367700 0 1785421824 0.1154237017 0.0814711973 0.9176580906 441 17.6000000000 1.6595206261 0.9514469174 1.7159270048 0.0178847314 0.1109970000 645561050 0 1786294272 0.1181408167 0.0789963752 0.9151854515 442 17.6400000000 1.6549055576 0.9530384528 1.7159270048 0.0178877590 0.1128720000 645562304 0 1785782272 0.1226115078 0.0792654157 0.9119409323 443 17.6800000000 1.6460261345 0.9546027590 1.7159270048 0.0179000971 0.0980900000 645563558 0 1785782272 0.1313370168 0.0807722583 0.9058856368 444 17.7200000000 1.6400797367 0.9561466261 1.7159270048 0.0178908408 0.0901070000 645564812 0 1786249216 0.1346535832 0.0804468915 0.9019970894 445 17.7600000000 1.6355972290 0.9576734814 1.7159270048 0.0178819121 0.0925100000 645566066 0 1786757120 0.1379788071 0.0795774385 0.8990322948 446 17.8000000000 1.6308348179 0.9591828118 1.7159270048 0.0178686885 0.5065740000 657873920 0 1787138048 0.1414325237 0.0797553509 0.8958250880 447 17.8400000000 1.6268906593 0.9606765653 1.7159270048 0.0178607416 0.1123350000 661533022 0 1785417728 0.1460151374 0.0790815204 0.8923996091 448 17.8800000000 1.6229144335 0.9621547749 1.7159270048 0.0178509152 0.1002660000 664726372 0 1786421248 0.1486986727 0.0785195008 0.8897032738 449 17.9200000000 1.6183656454 0.9636162690 1.7159270048 0.0178470936 0.0981110000 664727626 0 1785888768 0.1514215171 0.0779058337 0.8868572712 450 17.9600000000 1.6153368950 0.9650645371 1.7159270048 0.0178461731 0.1000950000 664728880 0 1785868288 0.1535945982 0.0764022321 0.8848146796 451 18.0000000000 1.6126321554 0.9665003854 1.7159270048 0.0178449375 0.0927100000 664730134 0 1786249216 0.1570774466 0.0763029978 0.8828158975 452 18.0400000000 1.6094868183 0.9679229218 1.7159270048 0.0178364388 0.0909170000 664731388 0 1786757120 0.1602775007 0.0761818588 0.8805841208 453 18.0800000000 1.6061635017 0.9693318414 1.7159270048 0.0178265487 0.0828040000 664732642 0 1787265024 0.1630354822 0.0749481097 0.8783275485 454 18.1200000000 1.6035454273 0.9707287876 1.7159270048 0.0178162751 0.5179070000 677151044 0 1787645952 0.1662907451 0.0746584833 0.8763887286 455 18.1600000000 1.6031582355 0.9721187424 1.7159270048 0.0178021804 0.1083430000 680810146 0 1786052608 0.1699582785 0.0753168240 0.8726592064 456 18.2000000000 1.5998079777 0.9734952539 1.7159270048 0.0177851517 0.1006980000 684003496 0 1787011072 0.1726450473 0.0738926008 0.8704397678 457 18.2400000000 1.5977826118 0.9748613094 1.7159270048 0.0177715861 0.0903440000 684004750 0 1785163776 0.1758893728 0.0730664134 0.8686469793 458 18.2800000000 1.5975896120 0.9762209782 1.7159270048 0.0177657242 0.0921430000 684006004 0 1785163776 0.1801530868 0.0735220015 0.8675199151 459 18.3200000000 1.5953234434 0.9775697853 1.7159270048 0.0177500445 0.0889320000 684007258 0 1785638912 0.1844354123 0.0742927268 0.8652479649 460 18.3600000000 1.5938169956 0.9789094532 1.7159270048 0.0177381645 0.0951020000 684008512 0 1786146816 0.1875210255 0.0729786456 0.8638478518 461 18.4000000000 1.5934431553 0.9802424981 1.7159270048 0.0177254493 0.0807590000 684009766 0 1786527744 0.1913000047 0.0722622424 0.8626632094 462 18.4400000000 1.5915106535 0.9815655893 1.7159270048 0.0177101197 0.0813760000 684011020 0 1786630144 0.1952190250 0.0725540593 0.8605907559 463 18.4800000000 1.5887882710 0.9828770854 1.7159270048 0.0176970200 0.0808680000 684012274 0 1787138048 0.1983523220 0.0718167722 0.8583170176 464 18.5200000000 1.5880467892 0.9841813304 1.7159270048 0.0176873984 0.0916570000 684013528 0 1787772928 0.2013809085 0.0707328171 0.8570362926 465 18.5600000000 1.5870954990 0.9854779200 1.7159270048 0.0176881065 0.0924940000 684014782 0 1786163200 0.2042301744 0.0693184808 0.8558505177 466 18.6000000000 1.5874787569 0.9867697673 1.7159270048 0.0177066368 0.1024090000 684016036 0 1786122240 0.2086585313 0.0697315484 0.8546224833 467 18.6400000000 1.5873515606 0.9880558097 1.7159270048 0.0177089203 0.5070670000 696324122 0 1786527744 0.2125435472 0.0690716580 0.8536289334 468 18.6800000000 1.5880186558 0.9893377816 1.7159270048 0.0177192741 0.1375230000 699983224 0 1785245696 0.2161539495 0.0670072436 0.8538195491 469 18.7200000000 1.5887383223 0.9906158211 1.7159270048 0.0177421083 0.0987630000 703176574 0 1785909248 0.2196651697 0.0665802732 0.8530926704 470 18.7600000000 1.5901316404 0.9918913867 1.7159270048 0.0177791277 0.0959470000 703177828 0 1785290752 0.2232010812 0.0654947087 0.8528401852 471 18.8000000000 1.5905061960 0.9931623311 1.7159270048 0.0178264907 0.0966390000 703179082 0 1785290752 0.2272956669 0.0649226308 0.8518617749 472 18.8400000000 1.5903050900 0.9944274641 1.7159270048 0.0178596338 0.0908380000 703180336 0 1785741312 0.2309703529 0.0651056021 0.8507061005 473 18.8800000000 1.5894411802 0.9956854212 1.7159270048 0.0178719410 0.0816660000 703181590 0 1786249216 0.2347533703 0.0650126413 0.8492215276 474 18.9200000000 1.5858156681 0.9969304217 1.7159270048 0.0178697725 0.0753030000 703182844 0 1786630144 0.2362735718 0.0645491481 0.8464555740 475 18.9600000000 1.5857769251 0.9981700986 1.7159270048 0.0178831792 0.0748440000 703184098 0 1786757120 0.2394512445 0.0638882592 0.8456566334 476 19.0000000000 1.5860688686 0.9994051800 1.7159270048 0.0178997778 0.0814010000 703185352 0 1787265024 0.2429174781 0.0638650954 0.8444297910 477 19.0400000000 1.5824495554 1.0006274953 1.7159270048 0.0178959682 0.0927570000 703186606 0 1787772928 0.2455118746 0.0638769418 0.8416938186 478 19.0800000000 1.5866740942 1.0018535342 1.7159270048 0.0179108637 0.0849740000 703187860 0 1786163200 0.2500692606 0.0636266768 0.8426826000 479 19.1200000000 1.5873174667 1.0030757971 1.7159270048 0.0179095177 0.0828840000 703189114 0 1785778176 0.2526628375 0.0627567768 0.8420033455 480 19.1600000000 1.5902931690 1.0042991666 1.7159270048 0.0179288148 0.1131760000 703190368 0 1785778176 0.2563533187 0.0619462989 0.8425945044 481 19.2000000000 1.5880562067 1.0055127987 1.7159270048 0.0179321440 0.0990460000 703191622 0 1786142720 0.2589471042 0.0627594665 0.8406551480 482 19.2400000000 1.5905966759 1.0067266657 1.7159270048 0.0179318223 0.0975800000 703192876 0 1786777600 0.2622406185 0.0626071095 0.8411065340 483 19.2800000000 1.5913628340 1.0079370925 1.7159270048 0.0179304151 0.1014240000 703194130 0 1787138048 0.2654627860 0.0618018843 0.8405909538 484 19.3200000000 1.5895371437 1.0091387455 1.7159270048 0.0179201725 0.1022620000 703195384 0 1787138048 0.2671852112 0.0618612021 0.8389413357 485 19.3600000000 1.5887019634 1.0103337212 1.7159270048 0.0179106890 0.5664270000 715512438 0 1786163200 0.2703552842 0.0629404038 0.8374657035 486 19.4000000000 1.5887453556 1.0115238686 1.7159270048 0.0178968860 0.1635090000 719171540 0 1785999360 0.2727695107 0.0639552474 0.8371161222 487 19.4400000000 1.5880693197 1.0127077402 1.7159270048 0.0178973095 0.1195830000 722364890 0 1786130432 0.2747305632 0.0625330061 0.8360899687 488 19.4800000000 1.5830874443 1.0138765511 1.7159270048 0.0178878220 0.1065600000 722366144 0 1785364480 0.2746823728 0.0617474802 0.8334851861 489 19.5200000000 1.5815235376 1.0150373833 1.7159270048 0.0178866924 0.1082990000 722367398 0 1785004032 0.2762931585 0.0615715645 0.8318797350 490 19.5600000000 1.5771254301 1.0161845018 1.7159270048 0.0178883906 0.1136970000 722368652 0 1784766464 0.2778564394 0.0611502118 0.8290172815 491 19.6000000000 1.5753394365 1.0173233102 1.7159270048 0.0178904835 0.1083710000 722369906 0 1784393728 0.2798312008 0.0604969785 0.8275718093 492 19.6400000000 1.5686147213 1.0184438212 1.7159270048 0.0178819524 0.1123680000 722371160 0 1784119296 0.2796886265 0.0610092282 0.8234496117 493 19.6800000000 1.5621637106 1.0195467013 1.7159270048 0.0178795154 0.1096570000 722372414 0 1783771136 0.2805420160 0.0608392097 0.8195036650 494 19.7200000000 1.5577518940 1.0206361855 1.7159270048 0.0178803608 0.1046360000 722373668 0 1783869440 0.2808444500 0.0588752814 0.8171070814 495 19.7600000000 1.5512037277 1.0217080391 1.7159270048 0.0178764168 0.1199350000 722374922 0 1784504320 0.2806434631 0.0580126084 0.8133817315 496 19.8000000000 1.5464144945 1.0227659151 1.7159270048 0.0178642308 0.1002540000 722376176 0 1784995840 0.2801460326 0.0580399968 0.8111058474 497 19.8400000000 1.5431277752 1.0238129208 1.7159270048 0.0178543573 0.1061660000 722377430 0 1785376768 0.2811818123 0.0569388866 0.8088012934 498 19.8800000000 1.5359236002 1.0248412555 1.7159270048 0.0178421480 0.1222190000 722378684 0 1785614336 0.2803259194 0.0565282851 0.8051497340 499 19.9200000000 1.5321727991 1.0258579520 1.7159270048 0.0178358755 0.1062340000 722379938 0 1786122240 0.2807907760 0.0561014824 0.8029125333 500 19.9600000000 1.5257076025 1.0268576513 1.7159270048 0.0178312538 0.1092540000 722381192 0 1786630144 0.2804313004 0.0553613827 0.7994704247 501 20.0000000000 1.5193606615 1.0278406912 1.7159270048 0.0178245424 0.1119860000 722382446 0 1787138048 0.2805866003 0.0547262318 0.7958326936 502 20.0400000000 1.5162296295 1.0288135776 1.7159270048 0.0178172152 0.1056440000 722383700 0 1787645952 0.2818022072 0.0537782870 0.7937894464 503 20.0800000000 1.5088154078 1.0297678556 1.7159270048 0.0178074167 0.1167880000 722384954 0 1786310656 0.2823980451 0.0538875572 0.7892029285 504 20.1200000000 1.5019673109 1.0307047592 1.7159270048 0.0177981587 0.1311450000 722386208 0 1786503168 0.2819941938 0.0525882654 0.7856487036 505 20.1600000000 1.4931738377 1.0316205396 1.7159270048 0.0177862459 0.1159710000 722387462 0 1787011072 0.2799318731 0.0517592989 0.7814346552 506 20.2000000000 1.4877297878 1.0325219413 1.7159270048 0.0177779460 0.1102840000 722388716 0 1787518976 0.2796552777 0.0525278375 0.7785605192 507 20.2400000000 1.4807254076 1.0334059718 1.7159270048 0.0177747876 0.1197270000 722389970 0 1787772928 0.2796187401 0.0528457277 0.7746973038 508 20.2800000000 1.4731642008 1.0342716376 1.7159270048 0.0177764437 0.1146050000 722391224 0 1788026880 0.2773747146 0.0521594957 0.7712605596 509 20.3200000000 1.4680711031 1.0351238959 1.7159270048 0.0177644704 0.1127830000 722392478 0 1786163200 0.2779263556 0.0514284819 0.7680501938 510 20.3600000000 1.4600192308 1.0359570240 1.7159270048 0.0177530534 0.1180680000 722393732 0 1786638336 0.2791974843 0.0518111475 0.7629921436 511 20.4000000000 1.4531685114 1.0367734848 1.7159270048 0.0177439836 0.1158490000 722394986 0 1787146240 0.2799915373 0.0532455072 0.7587873340 512 20.4400000000 1.4445296526 1.0375698836 1.7159270048 0.0177517600 0.1170920000 722396240 0 1787527168 0.2786868513 0.0533379018 0.7544215322 513 20.4800000000 1.4388620853 1.0383521296 1.7159270048 0.0177536645 0.1204010000 722440502 0 1787645952 0.2801400125 0.0528397858 0.7505637407 514 20.5200000000 1.4320929050 1.0391181622 1.7159270048 0.0177488464 0.1178160000 722525724 0 1786310656 0.2805474699 0.0533021912 0.7465817332 515 20.5600000000 1.4258238077 1.0398690470 1.7159270048 0.0177461277 0.1171980000 722526978 0 1786658816 0.2821041048 0.0540506989 0.7424080372 516 20.6000000000 1.4183795452 1.0406025944 1.7159270048 0.0177515237 0.1347360000 722528232 0 1787166720 0.2833380997 0.0540207252 0.7375077009 517 20.6400000000 1.4179974794 1.0413325652 1.7159270048 0.0177468518 0.1336320000 722529486 0 1787674624 0.2820602953 0.0531458370 0.7378002405 518 20.6800000000 1.4088170528 1.0420419947 1.7159270048 0.0177376223 0.1201910000 722530740 0 1787674624 0.2859450281 0.0530782081 0.7308601737 519 20.7200000000 1.4091962576 1.0427494210 1.7159270048 0.0177349112 0.1242170000 722531994 0 1786310656 0.2831345201 0.0539037734 0.7322933078 520 20.7600000000 1.4075731039 1.0434510050 1.7159270048 0.0177335002 0.1287120000 722533248 0 1786404864 0.2815985978 0.0547455326 0.7321119308 521 20.8000000000 1.4024609327 1.0441400836 1.7159270048 0.0177365268 0.1115420000 722534502 0 1786884096 0.2802233696 0.0538766123 0.7294684649 522 20.8400000000 1.3988666534 1.0448196364 1.7159270048 0.0177277451 0.1179490000 722535756 0 1787392000 0.2807202935 0.0525032654 0.7272070646 523 20.8800000000 1.3997302055 1.0454982417 1.7159270048 0.0177239723 0.1189870000 722537010 0 1787645952 0.2779434323 0.0519213453 0.7290405035 524 20.9200000000 1.3906631470 1.0461569534 1.7159270048 0.0177098628 0.1156980000 722538264 0 1787899904 0.2832315266 0.0521843731 0.7216542959 525 20.9600000000 1.3875130415 1.0468071554 1.7159270048 0.0177002348 0.1158960000 722539518 0 1786310656 0.2829478383 0.0518524162 0.7199574113 526 21.0000000000 1.3815108538 1.0474434743 1.7159270048 0.0176880776 0.1264550000 722540772 0 1786785792 0.2854281962 0.0504960455 0.7153546810 527 21.0400000000 1.3762077093 1.0480673153 1.7159270048 0.0176796321 0.5834950000 734850126 0 1785802752 0.2857747078 0.0507569425 0.7123116851 528 21.0800000000 1.3734433651 1.0486835578 1.7159270048 0.0176721300 0.0956200000 738512900 0 1786163200 0.2873893082 0.0516298115 0.7108402252 529 21.1200000000 1.3642424345 1.0492800774 1.7159270048 0.0176617054 0.1729650000 741706250 0 1785405440 0.2914718688 0.0508365035 0.7038452625 530 21.1600000000 1.3623598814 1.0498707940 1.7159270048 0.0176547124 0.1225410000 741707504 0 1784893440 0.2900350988 0.0512404814 0.7033196688 531 21.2000000000 1.3552964926 1.0504459837 1.7159270048 0.0176445576 0.1223880000 741708758 0 1784893440 0.2929427326 0.0507711694 0.6979156733 532 21.2400000000 1.3503940105 1.0510097958 1.7159270048 0.0176348515 0.1243510000 741710012 0 1785241600 0.2929013669 0.0501077101 0.6953388453 533 21.2800000000 1.3469139338 1.0515649630 1.7159270048 0.0176219525 0.1225440000 741711266 0 1785741312 0.2921097577 0.0500098579 0.6936119795 534 21.3200000000 1.3396309614 1.0521044124 1.7159270048 0.0176098205 0.1169500000 741712520 0 1786249216 0.2943422794 0.0493170470 0.6884651184 535 21.3600000000 1.3322137594 1.0526279813 1.7159270048 0.0175969131 0.1077300000 741713774 0 1786249216 0.2961444855 0.0501799360 0.6833094954 536 21.4000000000 1.3292106390 1.0531439937 1.7159270048 0.0175879807 0.1220970000 741715028 0 1786757120 0.2953424454 0.0499193743 0.6818874478 537 21.4400000000 1.3210448027 1.0536428779 1.7159270048 0.0175785132 0.1075210000 741716282 0 1787265024 0.2983457446 0.0492438786 0.6759434938 538 21.4800000000 1.3161931038 1.0541308895 1.7159270048 0.0175670426 0.1353180000 741717536 0 1787772928 0.2979792356 0.0493460931 0.6731080413 539 21.5200000000 1.3109860420 1.0546074297 1.7159270048 0.0175565265 0.1198090000 741718790 0 1786421248 0.2972393632 0.0492878854 0.6704697609 540 21.5600000000 1.3032346964 1.0550678505 1.7159270048 0.0175455415 0.1175480000 741720044 0 1786515456 0.2985651493 0.0495714247 0.6653645635 541 21.6000000000 1.2978929281 1.0555166954 1.7159270048 0.0175351894 0.1424230000 741721298 0 1787011072 0.2987719178 0.0502024069 0.6622429490 542 21.6400000000 1.2908483744 1.0559508867 1.7159270048 0.0175285926 0.1211480000 741722552 0 1787645952 0.2992835641 0.0496535711 0.6576730609 543 21.6800000000 1.2879076004 1.0563780630 1.7159270048 0.0175168990 0.1151420000 741723806 0 1787772928 0.2997334599 0.0488731042 0.6557389498 544 21.7200000000 1.2820651531 1.0567929289 1.7159270048 0.0175028496 0.1201700000 741725060 0 1788026880 0.2996662855 0.0492312722 0.6524102688 545 21.7600000000 1.2757221460 1.0571946339 1.7159270048 0.0174880362 0.1190630000 741726314 0 1786163200 0.3004948795 0.0488438569 0.6483550072 546 21.8000000000 1.2723159790 1.0575886291 1.7159270048 0.0174761431 0.1221360000 741727568 0 1786511360 0.3009899855 0.0491167977 0.6460470557 547 21.8400000000 1.2659709454 1.0579695839 1.7159270048 0.0174610296 0.1330700000 741728822 0 1787019264 0.3015504181 0.0497111604 0.6419939995 548 21.8800000000 1.2630131245 1.0583437510 1.7159270048 0.0174480243 0.1204720000 741730076 0 1787527168 0.3004914820 0.0497724935 0.6407775283 549 21.9200000000 1.2594397068 1.0587100460 1.7159270048 0.0174342445 0.1185160000 741731330 0 1787518976 0.3006014824 0.0496206395 0.6386511922 550 21.9600000000 1.2554605007 1.0590677741 1.7159270048 0.0174211653 0.1386530000 741732584 0 1788026880 0.3003733456 0.0504158065 0.6363775134 551 22.0000000000 1.2509679794 1.0594160503 1.7159270048 0.0174104135 0.1281280000 741733838 0 1786163200 0.3002711535 0.0504256412 0.6337010860 552 22.0400000000 1.2472457886 1.0597563216 1.7159270048 0.0173980642 0.1194530000 741735092 0 1786511360 0.3009209931 0.0510976836 0.6310184598 553 22.0800000000 1.2453150749 1.0600918709 1.7159270048 0.0173895114 0.1242800000 741736346 0 1787019264 0.3005052805 0.0509244762 0.6301600337 554 22.1200000000 1.2412720919 1.0604189110 1.7159270048 0.0173798230 0.1217160000 741737600 0 1787527168 0.3004948199 0.0505028851 0.6278234720 555 22.1600000000 1.2370243073 1.0607371189 1.7159270048 0.0173683672 0.4777190000 754044090 0 1786630144 0.3007141352 0.0514605828 0.6249504685 556 22.2000000000 1.2324521542 1.0610459589 1.7159270048 0.0173598673 0.1346050000 757703192 0 1785257984 0.2992283404 0.0518655889 0.6222970486 557 22.2400000000 1.2297348976 1.0613488116 1.7159270048 0.0173561131 0.1432190000 760896542 0 1786036224 0.2992691994 0.0509601347 0.6207703352 558 22.2800000000 1.2255414724 1.0616430636 1.7159270048 0.0173441902 0.1357300000 760897796 0 1785528320 0.2980417609 0.0501622707 0.6189659238 559 22.3200000000 1.2224717140 1.0619307714 1.7159270048 0.0173341561 0.1298800000 760899050 0 1785528320 0.2979200184 0.0509815402 0.6170397401 560 22.3600000000 1.2202364206 1.0622134601 1.7159270048 0.0173247723 0.1205680000 760900304 0 1786003456 0.2972567976 0.0510014445 0.6160110831 561 22.4000000000 1.2165096998 1.0624884979 1.7159270048 0.0173160808 0.1262080000 760901558 0 1786503168 0.2982751429 0.0503849313 0.6130619645 562 22.4400000000 1.2141866684 1.0627584235 1.7159270048 0.0173059969 0.1185440000 760902812 0 1786884096 0.2975962162 0.0512847118 0.6122297645 563 22.4800000000 1.2093607187 1.0630188184 1.7159270048 0.0172990802 0.1186070000 760904066 0 1786884096 0.2981389761 0.0512811840 0.6091211438 564 22.5200000000 1.2059811354 1.0632722976 1.7159270048 0.0172920385 0.1206210000 760905320 0 1787518976 0.2982573211 0.0506429709 0.6071143150 565 22.5600000000 1.2003438473 1.0635149022 1.7159270048 0.0172843298 0.1251410000 760906574 0 1788026880 0.2993377149 0.0500324704 0.6030070782 566 22.6000000000 1.1967467070 1.0637502940 1.7159270048 0.0172773145 0.1168800000 760907828 0 1786310656 0.2994143963 0.0497853681 0.6007198691 567 22.6400000000 1.1934287548 1.0639790038 1.7159270048 0.0172689771 0.1121350000 760909082 0 1786658816 0.2997499108 0.0496896282 0.5986277461 568 22.6800000000 1.1889743805 1.0641990661 1.7159270048 0.0172594196 0.1240690000 760910336 0 1787166720 0.3002726138 0.0490814820 0.5956752896 569 22.7200000000 1.1835163832 1.0644087626 1.7159270048 0.0172488091 0.5150120000 773217294 0 1786122240 0.3008184433 0.0486749411 0.5920929313 570 22.7600000000 1.1775671244 1.0646072861 1.7159270048 0.0172414895 0.1458710000 776876396 0 1785253888 0.3016247451 0.0494638905 0.5881247520 571 22.8000000000 1.1722220182 1.0647957532 1.7159270048 0.0172331255 0.1329340000 780069746 0 1785909248 0.3007456064 0.0501809120 0.5855494142 572 22.8400000000 1.1670891047 1.0649745877 1.7159270048 0.0172273527 0.1318440000 780071000 0 1785393152 0.3006222546 0.0489564985 0.5826187134 573 22.8800000000 1.1614720821 1.0651429952 1.7159270048 0.0172162956 0.1120320000 780072254 0 1785393152 0.3002763689 0.0489459373 0.5794433355 574 22.9200000000 1.1567131281 1.0653025251 1.7159270048 0.0172049369 0.1110990000 780073508 0 1785995264 0.2993556261 0.0495402142 0.5770576596 575 22.9600000000 1.1506814957 1.0654510103 1.7159270048 0.0171955653 0.1254240000 780074762 0 1786503168 0.2986883223 0.0485535190 0.5738564134 576 23.0000000000 1.1461541653 1.0655911199 1.7159270048 0.0171831163 0.1095760000 780076016 0 1786884096 0.2982059717 0.0476883203 0.5714042783 577 23.0400000000 1.1403584480 1.0657206993 1.7159270048 0.0171711575 0.1090590000 780077270 0 1786884096 0.2974591255 0.0482202061 0.5682185888 578 23.0800000000 1.1346173286 1.0658398976 1.7159270048 0.0171598901 0.1047370000 780078524 0 1787392000 0.2971695662 0.0481821895 0.5648820400 579 23.1200000000 1.1292231083 1.0659493678 1.7159270048 0.0171477373 0.1199340000 780079778 0 1787899904 0.2965581715 0.0475350767 0.5617859364 580 23.1600000000 1.1231142282 1.0660479279 1.7159270048 0.0171344337 0.1147340000 780081032 0 1786052608 0.2962805331 0.0472616814 0.5582759976 581 23.2000000000 1.1172837019 1.0661361134 1.7159270048 0.0171208253 0.1164000000 780082286 0 1786273792 0.2954874337 0.0474512987 0.5552030802 582 23.2400000000 1.1104302406 1.0662122201 1.7159270048 0.0171101050 0.1219610000 780083540 0 1786781696 0.2949309051 0.0469199494 0.5514264107 583 23.2800000000 1.1049685478 1.0662786975 1.7159270048 0.0170972893 0.1331160000 780084794 0 1787265024 0.2948328257 0.0456549115 0.5481676459 584 23.3200000000 1.0979448557 1.0663329204 1.7159270048 0.0170850404 0.5889380000 792392576 0 1785356288 0.2940617502 0.0458105579 0.5442727208 585 23.3600000000 1.0911215544 1.0663752941 1.7159270048 0.0170735033 0.1378200000 796051678 0 1786273792 0.2941451371 0.0463517457 0.5399113894 586 23.4000000000 1.0845981836 1.0664063912 1.7159270048 0.0170617518 0.1369830000 799245028 0 1785401344 0.2938315868 0.0454021208 0.5361920595 587 23.4400000000 1.0788298845 1.0664275556 1.7159270048 0.0170522257 0.1054300000 799246282 0 1784893440 0.2928842008 0.0451845750 0.5329471827 588 23.4800000000 1.0624529123 1.0664207960 1.7159270048 0.0170516768 0.1039340000 799247536 0 1784893440 0.2917356491 0.0459432453 0.5237812996 589 23.5200000000 1.0563842058 1.0664037560 1.7159270048 0.0170430957 0.0999950000 799248790 0 1785516032 0.2910198569 0.0466559790 0.5203399062 590 23.5600000000 1.0491728783 1.0663745511 1.7159270048 0.0170397326 0.0968880000 799250044 0 1786023936 0.2900403440 0.0469654761 0.5165129900 591 23.6000000000 1.0423132181 1.0663338382 1.7159270048 0.0170388120 0.0959340000 799251298 0 1786277888 0.2893722057 0.0466991849 0.5127271414 592 23.6400000000 1.0340743065 1.0662793457 1.7159270048 0.0170297635 0.1007060000 799252552 0 1786376192 0.2886679173 0.0461525507 0.5081156492 593 23.6800000000 1.0265631676 1.0662123707 1.7159270048 0.0170188232 0.0993910000 799253806 0 1786884096 0.2879366577 0.0461645350 0.5038013458 594 23.7200000000 1.0194283724 1.0661336098 1.7159270048 0.0170072643 0.1111770000 799255060 0 1787392000 0.2871931195 0.0462936126 0.4998240471 595 23.7600000000 1.0133749247 1.0660449397 1.7159270048 0.0169957990 0.5545370000 811562582 0 1786167296 0.2862607241 0.0460305251 0.4967394173 596 23.8000000000 1.0057505369 1.0659437746 1.7159270048 0.0169834797 0.1345010000 815221684 0 1786257408 0.2851630747 0.0460136607 0.4924625158 597 23.8400000000 0.9990291595 1.0658316898 1.7159270048 0.0169726163 0.1191090000 818415034 0 1785401344 0.2842425704 0.0468698293 0.4888202250 598 23.8800000000 0.9909989238 1.0657065514 1.7159270048 0.0169657386 0.0973200000 818416288 0 1784889344 0.2833501995 0.0467747189 0.4842039645 599 23.9200000000 0.9842855334 1.0655706232 1.7159270048 0.0169564969 0.0963000000 818417542 0 1784889344 0.2818285227 0.0474920943 0.4811317027 600 23.9600000000 0.9774020910 1.0654236756 1.7159270048 0.0169513175 0.1066820000 818418796 0 1785384960 0.2812040448 0.0476550497 0.4770942032 601 24.0000000000 0.9705827832 1.0652658705 1.7159270048 0.0169427999 0.0965520000 818420050 0 1785868288 0.2799595892 0.0473343320 0.4738009274 602 24.0400000000 0.9630426168 1.0650960644 1.7159270048 0.0169319826 0.1045270000 818421304 0 1786249216 0.2790395319 0.0479318313 0.4694675505 603 24.0800000000 0.9568701982 1.0649165854 1.7159270048 0.0169209544 0.0973970000 818422558 0 1786376192 0.2779284120 0.0477236658 0.4664180875 604 24.1200000000 0.9512371421 1.0647283744 1.7159270048 0.0169089495 0.0988970000 818423812 0 1786884096 0.2765995562 0.0483171865 0.4636409581 605 24.1600000000 0.9454037547 1.0645311436 1.7159270048 0.0168991351 0.1117670000 818425066 0 1787392000 0.2756261230 0.0477472171 0.4606584311 606 24.2000000000 0.9402121902 1.0643259968 1.7159270048 0.0168880484 0.0983190000 818426320 0 1787899904 0.2748171687 0.0470085815 0.4579858780 607 24.2400000000 0.9324925542 1.0641088083 1.7159270048 0.0168759690 0.0960530000 818427574 0 1786310656 0.2738297582 0.0473149978 0.4536539614 608 24.2800000000 0.9266779423 1.0638827706 1.7159270048 0.0168634807 0.1131620000 818428828 0 1786531840 0.2726934254 0.0478206426 0.4507333338 609 24.3200000000 0.9210874438 1.0636482956 1.7159270048 0.0168542654 0.6203530000 830737202 0 1786884096 0.2720903158 0.0470646247 0.4475412667 610 24.3600000000 0.9156928062 1.0634057456 1.7159270048 0.0168431755 0.1349540000 834396304 0 1784901632 0.2716371417 0.0454810970 0.4445855618 611 24.4000000000 0.9078715444 1.0631511888 1.7159270048 0.0168312383 0.1104220000 837589654 0 1785528320 0.2709669471 0.0454768613 0.4398974776 612 24.4400000000 0.9018774629 1.0628876696 1.7159270048 0.0168193294 0.0932380000 837590908 0 1784901632 0.2699666917 0.0461892076 0.4366863370 613 24.4800000000 0.8970356584 1.0626171117 1.7159270048 0.0168089911 0.0899430000 837592162 0 1784901632 0.2691435218 0.0453167334 0.4341230094 614 24.5200000000 0.8892001510 1.0623346736 1.7159270048 0.0167988543 0.0903010000 837593416 0 1785376768 0.2683306336 0.0449524000 0.4297735095 615 24.5600000000 0.8841151595 1.0620448858 1.7159270048 0.0167863068 0.0888670000 837594670 0 1785868288 0.2678076923 0.0449158959 0.4268907309 616 24.6000000000 0.8775936365 1.0617454520 1.7159270048 0.0167744356 0.0886420000 837595924 0 1786249216 0.2671970427 0.0440151729 0.4230992496 617 24.6400000000 0.8709970117 1.0614362973 1.7159270048 0.0167631021 0.0888920000 837597178 0 1786376192 0.2662429512 0.0435756445 0.4195897579 618 24.6800000000 0.8637729883 1.0611164537 1.7159270048 0.0167529554 0.0917900000 837598432 0 1786884096 0.2657059133 0.0436290503 0.4150636196 619 24.7200000000 0.8551456332 1.0607837061 1.7159270048 0.0167422777 0.1142480000 837599686 0 1787392000 0.2650982440 0.0434734933 0.4100065827 620 24.7600000000 0.8493508101 1.0604426853 1.7159270048 0.0167327294 0.6885180000 849909332 0 1787899904 0.2640506625 0.0438663512 0.4069276750 621 24.8000000000 0.8433729410 1.0600931366 1.7159270048 0.0167231939 0.1268670000 853568434 0 1786052608 0.2637977302 0.0440706685 0.4029035866 622 24.8400000000 0.8368777633 1.0597342694 1.7159270048 0.0167123946 0.0969210000 856761784 0 1786654720 0.2629742324 0.0436883010 0.3992734551 623 24.8800000000 0.8303101659 1.0593660124 1.7159270048 0.0167017894 0.0856440000 856763038 0 1785253888 0.2620408535 0.0439615175 0.3957574069 624 24.9200000000 0.8234837055 1.0589879959 1.7159270048 0.0166914564 0.0868890000 856764292 0 1785253888 0.2607589960 0.0441640690 0.3919490278 625 24.9600000000 0.8171039820 1.0586009815 1.7159270048 0.0166816107 0.0829080000 856765546 0 1785745408 0.2596884072 0.0438915975 0.3886338770 626 25.0000000000 0.8113119602 1.0582059511 1.7159270048 0.0166711868 0.0824410000 856766800 0 1786253312 0.2588000894 0.0431038812 0.3856223226 627 25.0400000000 0.8049522042 1.0578020376 1.7159270048 0.0166620018 0.0790220000 856768054 0 1786634240 0.2574618161 0.0432041958 0.3823799193 628 25.0800000000 0.7984738946 1.0573890947 1.7159270048 0.0166545790 0.6985810000 869077852 0 1787392000 0.2561298311 0.0440983251 0.3790724576 629 25.1200000000 0.7941467762 1.0569705855 1.7159270048 0.0166490721 0.0894250000 872736954 0 1787645952 0.2547084987 0.0434131175 0.3773222268 630 25.1600000000 0.7877354622 1.0565432281 1.7159270048 0.0166440191 0.0994320000 875930304 0 1785905152 0.2533239722 0.0436799601 0.3739566505 631 25.2000000000 0.7818808556 1.0561079470 1.7159270048 0.0166416699 0.0738600000 875931558 0 1786146816 0.2518083155 0.0439238958 0.3709999323 632 25.2400000000 0.7772818208 1.0556667664 1.7159270048 0.0166392231 0.0751370000 875932812 0 1785270272 0.2503928542 0.0435045622 0.3691696823 633 25.2800000000 0.7703670859 1.0552160560 1.7159270048 0.0166356237 0.0719440000 875934066 0 1785270272 0.2487654239 0.0437384769 0.3656253815 634 25.3200000000 0.7641927600 1.0547570288 1.7159270048 0.0166330011 0.0701200000 875935320 0 1785503744 0.2468115240 0.0444099233 0.3631500304 635 25.3600000000 0.7596920133 1.0542923595 1.7159270048 0.0166330207 0.6292620000 888243558 0 1786155008 0.2454039007 0.0441184454 0.3613113463 636 25.4000000000 0.7539919615 1.0538201890 1.7159270048 0.0166322835 0.1013980000 891902660 0 1787011072 0.2444045693 0.0438777544 0.3574246764 637 25.4400000000 0.7485645413 1.0533409808 1.7159270048 0.0166262883 0.0746170000 895096010 0 1787637760 0.2428149730 0.0437496193 0.3550416529 638 25.4800000000 0.7431157827 1.0528547344 1.7159270048 0.0166187328 0.0713800000 895097264 0 1785774080 0.2414893210 0.0436946340 0.3523777425 639 25.5200000000 0.7379610538 1.0523619430 1.7159270048 0.0166110973 0.0766170000 895098518 0 1785892864 0.2396542728 0.0428784378 0.3505336046 640 25.5600000000 0.7332288027 1.0518632975 1.7159270048 0.0166010824 0.0688770000 895099772 0 1786368000 0.2381607592 0.0428690575 0.3485248089 641 25.6000000000 0.7282140851 1.0513583845 1.7159270048 0.0165927051 0.0723090000 895101026 0 1786875904 0.2366375327 0.0422245190 0.3455916047 642 25.6400000000 0.7231659889 1.0508471814 1.7159270048 0.0165816657 0.0708170000 895102280 0 1787256832 0.2344932854 0.0428370200 0.3444467485 643 25.6800000000 0.7176060677 1.0503289215 1.7159270048 0.0165710928 0.0690680000 895103534 0 1787256832 0.2328008413 0.0425030217 0.3425045907 644 25.7200000000 0.7126086950 1.0498045112 1.7159270048 0.0165607989 0.0674020000 895104788 0 1787891712 0.2308001667 0.0423503965 0.3409957290 645 25.7600000000 0.7072393298 1.0492734024 1.7159270048 0.0165510446 0.0767750000 895106042 0 1786155008 0.2290957570 0.0421717055 0.3389032185 646 25.8000000000 0.7024743557 1.0487365618 1.7159270048 0.0165407493 0.0726550000 895107296 0 1785622528 0.2267735451 0.0418821275 0.3378560543 647 25.8400000000 0.6962872148 1.0481918178 1.7159270048 0.0165310370 0.0697540000 895108550 0 1785622528 0.2240863740 0.0421946347 0.3363802731 648 25.8800000000 0.6911410689 1.0476408136 1.7159270048 0.0165246239 0.5963050000 907417560 0 1786302464 0.2218951881 0.0426346436 0.3349402249 649 25.9200000000 0.6858353019 1.0470833321 1.7159270048 0.0165196110 0.0716160000 911076662 0 1787011072 0.2196065933 0.0422132835 0.3329892457 650 25.9600000000 0.6752999425 1.0465113576 1.7159270048 0.0165201086 0.0926170000 914270012 0 1787764736 0.2148815244 0.0404363535 0.3300499022 651 26.0000000000 0.6626234651 1.0459216681 1.7159270048 0.0165178882 0.0756450000 914271266 0 1786306560 0.2087020427 0.0414987206 0.3272281289 652 26.0400000000 0.6560737491 1.0453237418 1.7159270048 0.0165128287 0.0677230000 914272520 0 1786306560 0.2054361850 0.0410890579 0.3251986206 653 26.0800000000 0.6496378183 1.0447177909 1.7159270048 0.0165101092 0.0695810000 914273774 0 1786781696 0.2018578947 0.0423109718 0.3239607513 654 26.1200000000 0.6436085105 1.0441044740 1.7159270048 0.0165136405 0.0688030000 914275028 0 1787289600 0.1983090192 0.0429880135 0.3229171336 655 26.1600000000 0.6365723014 1.0434822875 1.7159270048 0.0165077507 0.0737100000 914276282 0 1787670528 0.1949324906 0.0426470004 0.3213405311 656 26.2000000000 0.6301890612 1.0428522673 1.7159270048 0.0165001716 0.0741490000 914277536 0 1787764736 0.1910924166 0.0437945649 0.3199898899 657 26.2400000000 0.6241871119 1.0422150296 1.7159270048 0.0164926213 0.0735220000 914278790 0 1786155008 0.1873403341 0.0438243970 0.3188630342 658 26.2800000000 0.6171100140 1.0415689734 1.7159270048 0.0164844653 0.0754770000 914280044 0 1785769984 0.1833657473 0.0447573625 0.3178187311 659 26.3200000000 0.6110477448 1.0409156786 1.7159270048 0.0164778810 0.0764710000 914281298 0 1785733120 0.1794568747 0.0451334044 0.3166274428 660 26.3600000000 0.6054566503 1.0402558922 1.7159270048 0.0164740353 0.0755770000 914282552 0 1786114048 0.1756305695 0.0454805940 0.3150388002 661 26.4000000000 0.5985256433 1.0395876165 1.7159270048 0.0164698678 0.0752070000 914283806 0 1786748928 0.1715193391 0.0460509285 0.3141902983 662 26.4400000000 0.5930595994 1.0389131029 1.7159270048 0.0164713970 0.0839960000 914285060 0 1787256832 0.1675219834 0.0466697887 0.3141549230 663 26.4800000000 0.5869347453 1.0382313859 1.7159270048 0.0164814200 0.0816240000 914286314 0 1787256832 0.1636852920 0.0469993055 0.3134850860 664 26.5200000000 0.5809198618 1.0375426637 1.7159270048 0.0164850030 0.0747020000 914287568 0 1787772928 0.1599437296 0.0471681505 0.3106820881 665 26.5600000000 0.5752242208 1.0368474480 1.7159270048 0.0164788737 0.0820510000 914288822 0 1786163200 0.1563433558 0.0475815460 0.3101126552 666 26.6000000000 0.5689951777 1.0361449671 1.7159270048 0.0164760374 0.5895220000 926598372 0 1787645952 0.1525899619 0.0480914637 0.3093928397 667 26.6400000000 0.5636240244 1.0354365399 1.7159270048 0.0164744379 0.0817720000 930257474 0 1786163200 0.1483124197 0.0499937572 0.3103607297 668 26.6800000000 0.5583036542 1.0347222692 1.7159270048 0.0164965252 0.0897800000 933450824 0 1786638336 0.1445834935 0.0509904698 0.3091849983 669 26.7200000000 0.5531569123 1.0340024405 1.7159270048 0.0165302639 0.0817580000 933452078 0 1785004032 0.1406985372 0.0513308682 0.3081911802 670 26.7600000000 0.5480945110 1.0332772048 1.7159270048 0.0165526578 0.0720720000 933453332 0 1785004032 0.1374203265 0.0511927083 0.3073943555 671 26.8000000000 0.5427744389 1.0325462022 1.7159270048 0.0165570955 0.0703080000 933454586 0 1785495552 0.1340309680 0.0513089150 0.3062549829 672 26.8400000000 0.5376021862 1.0318096783 1.7159270048 0.0165518400 0.0708780000 933455840 0 1786003456 0.1307316124 0.0523561537 0.3047099411 673 26.8800000000 0.5325007439 1.0310677631 1.7159270048 0.0165466828 0.0685550000 933457094 0 1786384384 0.1277716756 0.0519353896 0.3036665320 674 26.9200000000 0.5272780061 1.0303203006 1.7159270048 0.0165381450 0.0670520000 933458348 0 1786503168 0.1247259155 0.0526655912 0.3027613163 675 26.9600000000 0.5230216384 1.0295687470 1.7159270048 0.0165304917 0.0683760000 933459602 0 1787011072 0.1217786148 0.0532706454 0.3018937111 676 27.0000000000 0.5184892416 1.0288127122 1.7159270048 0.0165274416 0.0702490000 933460856 0 1787518976 0.1184565276 0.0543775484 0.3007672429 677 27.0400000000 0.5147455335 1.0280533811 1.7159270048 0.0165356572 0.0756640000 933462110 0 1788026880 0.1154744178 0.0547363535 0.3005319536 678 27.0800000000 0.5107076168 1.0272903343 1.7159270048 0.0165428623 0.0871030000 933463364 0 1786122240 0.1125919968 0.0556323305 0.2992765903 679 27.1200000000 0.5060350895 1.0265226535 1.7159270048 0.0165506278 0.0735480000 933464618 0 1785786368 0.1094829366 0.0562092923 0.2979594469 680 27.1600000000 0.5006820560 1.0257493585 1.7159270048 0.0165496800 0.0779680000 933465872 0 1785786368 0.1068804786 0.0559296831 0.2966064513 681 27.2000000000 0.4964081943 1.0249720587 1.7159270048 0.0165423031 0.0749110000 933467126 0 1786261504 0.1040785760 0.0561209805 0.2955384254 682 27.2400000000 0.4918543696 1.0241903612 1.7159270048 0.0165368231 0.0731070000 933468380 0 1786769408 0.1013265401 0.0566751361 0.2942788303 683 27.2800000000 0.4872366190 1.0234041917 1.7159270048 0.0165358278 0.0840360000 933469634 0 1787150336 0.0985809714 0.0574344546 0.2928841412 684 27.3200000000 0.4825084805 1.0226134085 1.7159270048 0.0165388389 0.0768510000 933470888 0 1787150336 0.0957470909 0.0576803386 0.2915239334 685 27.3600000000 0.4773454368 1.0218173969 1.7159270048 0.0165357881 0.0853840000 933472142 0 1787645952 0.0929603651 0.0581917986 0.2896119952 686 27.4000000000 0.4717593491 1.0210155630 1.7159270048 0.0165324837 0.0868700000 933473396 0 1786163200 0.0901151672 0.0591452494 0.2881859839 687 27.4400000000 0.4666229486 1.0202085869 1.7159270048 0.0165406312 0.1042410000 933474650 0 1786163200 0.0872379467 0.0597418621 0.2863652706 688 27.4800000000 0.4614079595 1.0193963766 1.7159270048 0.0165505226 0.1053870000 933475904 0 1786638336 0.0843007341 0.0608742796 0.2845107317 689 27.5200000000 0.4558690190 1.0185784850 1.7159270048 0.0165647171 0.0878720000 933477158 0 1787138048 0.0815871656 0.0600334331 0.2830336392 690 27.5600000000 0.4500064850 1.0177544676 1.7159270048 0.0165627421 0.1109920000 933478412 0 1787518976 0.0787953362 0.0611877739 0.2807419896 691 27.6000000000 0.4442024529 1.0169244357 1.7159270048 0.0165667884 0.1101250000 933479666 0 1787645952 0.0758925676 0.0619911328 0.2791127861 692 27.6400000000 0.4385449588 1.0160886272 1.7159270048 0.0165806856 0.1306770000 933480920 0 1785647104 0.0728847384 0.0631182939 0.2771313488 693 27.6800000000 0.4321999252 1.0152460750 1.7159270048 0.0166046462 0.1155730000 933482174 0 1785647104 0.0701678321 0.0630129799 0.2749819160 694 27.7200000000 0.4252564609 1.0143959459 1.7159270048 0.0166240029 0.0880400000 933483428 0 1786130432 0.0677207336 0.0611604750 0.2727365196 695 27.7600000000 0.4192001224 1.0135395490 1.7159270048 0.0166213114 0.0925220000 933484682 0 1786638336 0.0653224513 0.0614431500 0.2701382935 696 27.8000000000 0.4130880535 1.0126768313 1.7159270048 0.0166189058 0.5858450000 945794152 0 1787138048 0.0626524538 0.0617990606 0.2678919733 697 27.8400000000 0.4049872458 1.0118049668 1.7159270048 0.0166191835 0.1166360000 949453254 0 1785286656 0.0598309860 0.0634356216 0.2680985928 698 27.8800000000 0.3995594978 1.0109278243 1.7159270048 0.0166265934 0.0874680000 952646604 0 1785782272 0.0568153113 0.0644075349 0.2661805153 699 27.9200000000 0.3945361078 1.0100460049 1.7159270048 0.0166410602 0.0840290000 952647858 0 1786003456 0.0540350489 0.0652428046 0.2643429637 700 27.9600000000 0.3890180290 1.0091588221 1.7159270048 0.0166572841 0.0820850000 952649112 0 1785036800 0.0510491319 0.0660430416 0.2622515261 701 28.0000000000 0.3840566874 1.0082670930 1.7159270048 0.0166737459 0.0835010000 952650366 0 1785036800 0.0482653491 0.0666593313 0.2602340877 702 28.0400000000 0.3788093030 1.0073704295 1.7159270048 0.0166879755 0.0815740000 952651620 0 1785520128 0.0456089079 0.0664999187 0.2584303617 703 28.0800000000 0.3746280372 1.0064703692 1.7159270048 0.0166937554 0.0827180000 952652874 0 1786028032 0.0432206430 0.0665339604 0.2570796907 704 28.1200000000 0.3712598383 1.0055680815 1.7159270048 0.0167022768 0.0922310000 952654128 0 1786376192 0.0402750224 0.0683813766 0.2558439374 705 28.1600000000 0.3679697812 1.0046636867 1.7159270048 0.0167197773 0.0913150000 952655382 0 1786494976 0.0373827368 0.0697915182 0.2544285059 706 28.2000000000 0.3642567396 1.0037565947 1.7159270048 0.0167320107 0.1110010000 952656636 0 1787002880 0.0350134410 0.0694842413 0.2532495856 707 28.2400000000 0.3613256812 1.0028479230 1.7159270048 0.0167330074 0.1057420000 952657890 0 1787518976 0.0323593542 0.0705361068 0.2519794405 708 28.2800000000 0.3590180576 1.0019385588 1.7159270048 0.0167289224 0.6242460000 964967464 0 1786163200 0.0295545608 0.0718889907 0.2511351109 709 28.3200000000 0.3593102396 1.0010321719 1.7159270048 0.0167333172 0.1259290000 968626566 0 1785888768 0.0275090076 0.0696955845 0.2467775345 710 28.3600000000 0.3564693034 1.0001243368 1.7159270048 0.0167224185 0.0948090000 971819916 0 1786257408 0.0251204632 0.0702489913 0.2457153350 711 28.4000000000 0.3554538786 0.9992176273 1.7159270048 0.0167152068 0.0928660000 971821170 0 1785249792 0.0224904921 0.0719579682 0.2458080798 712 28.4400000000 0.3536188006 0.9983108874 1.7159270048 0.0167100952 0.0875400000 971822424 0 1785249792 0.0198959298 0.0725025162 0.2451207042 713 28.4800000000 0.3521474302 0.9974046273 1.7159270048 0.0167010361 0.0850050000 971823678 0 1785753600 0.0180402622 0.0717496499 0.2445915490 714 28.5200000000 0.3524671793 0.9965013536 1.7159270048 0.0166912758 0.0878580000 971824932 0 1786261504 0.0153732067 0.0735114962 0.2447749078 715 28.5600000000 0.3530118167 0.9956013682 1.7159270048 0.0166813739 0.1011080000 971826186 0 1786642432 0.0123575339 0.0757952631 0.2447208613 716 28.6000000000 0.3543435633 0.9947057567 1.7159270048 0.0166779621 0.0882970000 971827440 0 1786757120 0.0101046478 0.0758313835 0.2455946654 717 28.6400000000 0.3560111225 0.9938149692 1.7159270048 0.0166700141 0.0880130000 971828694 0 1787265024 0.0079555633 0.0763912648 0.2466090173 718 28.6800000000 0.3583596647 0.9929299340 1.7159270048 0.0166614441 0.1097220000 971829948 0 1787772928 0.0055427696 0.0781502724 0.2476953268 719 28.7200000000 0.3600149155 0.9920496628 1.7159270048 0.0166565378 0.1020400000 971831202 0 1786249216 0.0029738576 0.0792318359 0.2484959364 720 28.7600000000 0.3626753092 0.9911755317 1.7159270048 0.0166504569 0.1019750000 971832456 0 1786376192 0.0004830167 0.0799740478 0.2498416603 721 28.8000000000 0.3656958342 0.9903080148 1.7159270048 0.0166419206 0.5096750000 984138206 0 1786638336 -0.0018634029 0.0802050754 0.2514545619 722 28.8400000000 0.3688632846 0.9894472880 1.7159270048 0.0166355694 0.1155570000 987797308 0 1785106432 -0.0041437116 0.0790399835 0.2536787391 723 28.8800000000 0.3725700676 0.9885940692 1.7159270048 0.0166266617 0.1017720000 990990658 0 1785774080 -0.0067558726 0.0794764534 0.2555557191 724 28.9200000000 0.3765641749 0.9877487240 1.7159270048 0.0166181177 0.0820090000 990991912 0 1785126912 -0.0095040137 0.0799230039 0.2574385703 725 28.9600000000 0.3808591962 0.9869116350 1.7159270048 0.0166128193 0.0802190000 990993166 0 1785126912 -0.0123511124 0.0806463137 0.2595458329 726 29.0000000000 0.3851782382 0.9860828011 1.7159270048 0.0166119229 0.0826250000 990994420 0 1784385536 -0.0149682350 0.0809240118 0.2616876364 727 29.0400000000 0.3897246122 0.9852625010 1.7159270048 0.0166107403 0.0806720000 990995674 0 1784385536 -0.0181729998 0.0815952271 0.2637548447 728 29.0800000000 0.3948476017 0.9844514915 1.7159270048 0.0166106371 0.5626340000 1003302848 0 1787772928 -0.0210305508 0.0820715502 0.2661267221 729 29.1200000000 0.3995119929 0.9836491054 1.7159270048 0.0166063638 0.1053960000 1006961950 0 1786376192 -0.0237091109 0.0822307467 0.2697329223 730 29.1600000000 0.4046523869 0.9828559592 1.7159270048 0.0166011642 0.0844630000 1010155300 0 1786773504 -0.0265673958 0.0823086500 0.2721286714 731 29.2000000000 0.4098467529 0.9820720889 1.7159270048 0.0165949066 0.0776790000 1010156554 0 1785147392 -0.0297393743 0.0830528960 0.2744454443 732 29.2400000000 0.4156967998 0.9812983522 1.7159270048 0.0165909808 0.0745480000 1010157808 0 1785147392 -0.0331604704 0.0843786448 0.2767867446 733 29.2800000000 0.4223601222 0.9805358171 1.7159270048 0.0165861469 0.0730160000 1010159062 0 1785622528 -0.0363716781 0.0853580981 0.2796045244 734 29.3200000000 0.4296762645 0.9797853272 1.7159270048 0.0165791798 0.0731100000 1010160316 0 1786130432 -0.0395673290 0.0865045935 0.2827292085 735 29.3600000000 0.4366309643 0.9790463417 1.7159270048 0.0165720517 0.5276010000 1022468394 0 1786884096 -0.0425152630 0.0874993876 0.2857842445 736 29.4000000000 0.4438997209 0.9783192403 1.7159270048 0.0165652885 0.0895460000 1026127496 0 1787899904 -0.0455629751 0.0903126076 0.2884862721 737 29.4400000000 0.4508155882 0.9776034958 1.7159270048 0.0165581747 0.0748240000 1029320846 0 1788026880 -0.0483190678 0.0914027318 0.2914858758 738 29.4800000000 0.4579775929 0.9768993957 1.7159270048 0.0165569943 0.0720610000 1029322100 0 1786257408 -0.0513805263 0.0924409032 0.2944560051 739 29.5200000000 0.4649409056 0.9762066237 1.7159270048 0.0165639741 0.0710020000 1029323354 0 1785417728 -0.0538917854 0.0933299512 0.2976428568 740 29.5600000000 0.4716984332 0.9755248559 1.7159270048 0.0165707803 0.0680830000 1029324608 0 1785417728 -0.0564008132 0.0943600237 0.3005034924 741 29.6000000000 0.4788616002 0.9748545951 1.7159270048 0.0165792685 0.0746020000 1029325862 0 1785774080 -0.0587104931 0.0959666967 0.3034618795 742 29.6400000000 0.4859560132 0.9741957021 1.7159270048 0.0165836736 0.4609510000 1041631608 0 1786638336 -0.0607850850 0.0972280204 0.3066136241 743 29.6800000000 0.4920444489 0.9735467772 1.7159270048 0.0165772050 0.0797200000 1045290710 0 1787527168 -0.0623098761 0.0981261209 0.3090784550 744 29.7200000000 0.4974355400 0.9729068427 1.7159270048 0.0165688491 0.0724430000 1048484060 0 1787527168 -0.0639645234 0.0989260077 0.3114776909 745 29.7600000000 0.5028205514 0.9722758544 1.7159270048 0.0165617115 0.0694360000 1048485314 0 1786249216 -0.0658205897 0.0997266918 0.3135935962 746 29.8000000000 0.5076788068 0.9716530701 1.7159270048 0.0165534691 0.0699230000 1048486568 0 1785786368 -0.0672987625 0.1002135426 0.3159832954 747 29.8400000000 0.5127389431 0.9710387273 1.7159270048 0.0165456057 0.0693210000 1048487822 0 1785786368 -0.0691488162 0.1012058631 0.3179006279 748 29.8800000000 0.5179165602 0.9704329490 1.7159270048 0.0165388871 0.0691140000 1048489076 0 1786150912 -0.0708769783 0.1024686694 0.3198884428 749 29.9200000000 0.5226606727 0.9698351222 1.7159270048 0.0165312588 0.0693370000 1048490330 0 1786658816 -0.0722005144 0.1034887582 0.3219009936 750 29.9600000000 0.5270219445 0.9692447046 1.7159270048 0.0165236611 0.0677740000 1048491584 0 1787166720 -0.0735552385 0.1044555008 0.3237934411 751 30.0000000000 0.5310061574 0.9686611646 1.7159270048 0.0165161931 0.4274570000 1060798558 0 1787527168 -0.0749213696 0.1051514968 0.3253296316 752 30.0400000000 0.5349236131 0.9680843859 1.7159270048 0.0165077897 0.0656030000 1064457660 0 1786421248 -0.0760076791 0.1064945161 0.3265672326 753 30.0800000000 0.5380845666 0.9675133370 1.7159270048 0.0165002154 0.0825010000 1067651010 0 1786757120 -0.0774218589 0.1072163060 0.3279111683 754 30.1200000000 0.5413471460 0.9669481299 1.7159270048 0.0164958470 0.0752560000 1067652264 0 1785270272 -0.0786631182 0.1078531891 0.3291207254 755 30.1600000000 0.5443317294 0.9663883731 1.7159270048 0.0164930757 0.0738820000 1067653518 0 1785270272 -0.0799482241 0.1083313823 0.3303259313 756 30.2000000000 0.5478422046 0.9658347406 1.7159270048 0.0164902788 0.0750230000 1067654772 0 1785761792 -0.0814172924 0.1092791185 0.3315998912 757 30.2400000000 0.5511761904 0.9652869750 1.7159270048 0.0164844170 0.0760050000 1067656026 0 1786269696 -0.0831733570 0.1102534160 0.3326855302 758 30.2800000000 0.5546658039 0.9647452584 1.7159270048 0.0164785318 0.0727900000 1067657280 0 1786650624 -0.0847095400 0.1108117774 0.3338661194 759 30.3200000000 0.5584648252 0.9642099746 1.7159270048 0.0164792695 0.0741530000 1067658534 0 1786757120 -0.0865985528 0.1118746176 0.3350957036 760 30.3600000000 0.5625418425 0.9636814639 1.7159270048 0.0164791423 0.0737930000 1067659788 0 1787265024 -0.0887139663 0.1133961380 0.3362931013 761 30.4000000000 0.5662851334 0.9631592611 1.7159270048 0.0164767800 0.0732870000 1067661042 0 1787772928 -0.0908766687 0.1146224141 0.3371513784 762 30.4400000000 0.5697289109 0.9626429483 1.7159270048 0.0164708226 0.0759870000 1067662296 0 1786310656 -0.0930611268 0.1158748642 0.3380700648 763 30.4800000000 0.5734848976 0.9621329115 1.7159270048 0.0164646075 0.0771580000 1067663550 0 1786310656 -0.0955023840 0.1172580346 0.3388273418 764 30.5200000000 0.5772367716 0.9616291207 1.7159270048 0.0164591064 0.0770940000 1067664804 0 1786912768 -0.0980619490 0.1185409278 0.3396665156 765 30.5600000000 0.5811609030 0.9611317767 1.7159270048 0.0164530188 0.0865090000 1067666058 0 1787420672 -0.1006981730 0.1198125184 0.3404263854 766 30.6000000000 0.5850089788 0.9606407547 1.7159270048 0.0164475945 0.0806400000 1067667312 0 1787645952 -0.1033749059 0.1209586486 0.3412744105 767 30.6400000000 0.5889751911 0.9601561842 1.7159270048 0.0164424313 0.0790350000 1067668566 0 1787764736 -0.1060156822 0.1222597733 0.3420282304 768 30.6800000000 0.5928915739 0.9596779751 1.7159270048 0.0164391351 0.0785710000 1067669820 0 1786302464 -0.1089465395 0.1235327944 0.3427327573 769 30.7200000000 0.5971428752 0.9592065381 1.7159270048 0.0164355003 0.0799930000 1067671074 0 1785880576 -0.1116044894 0.1249418408 0.3435060978 770 30.7600000000 0.6013416052 0.9587417784 1.7159270048 0.0164300952 0.4547170000 1079982344 0 1786302464 -0.1144863963 0.1263508052 0.3443305790 771 30.8000000000 0.6035211086 0.9582810512 1.7159270048 0.0164203528 0.1190940000 1083641446 0 1785524224 -0.1179059744 0.1290116161 0.3461632431 772 30.8400000000 0.6070815325 0.9578261295 1.7159270048 0.0164152319 0.1045300000 1086834796 0 1786155008 -0.1207700744 0.1298179179 0.3468820453 773 30.8800000000 0.6111093760 0.9573775956 1.7159270048 0.0164107218 0.1025420000 1086836050 0 1785606144 -0.1235728636 0.1308642328 0.3473921418 774 30.9200000000 0.6148487329 0.9569350518 1.7159270048 0.0164085398 0.0963320000 1086837304 0 1785606144 -0.1262424737 0.1316607744 0.3482260406 775 30.9600000000 0.6182229519 0.9564980040 1.7159270048 0.0164072915 0.0931820000 1086838558 0 1786114048 -0.1290330887 0.1321771741 0.3487882912 776 31.0000000000 0.6218140721 0.9560667102 1.7159270048 0.0164069165 0.0912140000 1086839812 0 1786748928 -0.1319473088 0.1327985376 0.3493376672 777 31.0400000000 0.6256475449 0.9556414603 1.7159270048 0.0164081633 0.0934330000 1086841066 0 1787002880 -0.1347999424 0.1338704675 0.3497770131 778 31.0800000000 0.6293930411 0.9552221179 1.7159270048 0.0164043233 0.0963410000 1086842320 0 1787129856 -0.1375861466 0.1349801421 0.3501870930 779 31.1200000000 0.6329727173 0.9548084473 1.7159270048 0.0163989189 0.0963260000 1086843574 0 1787637760 -0.1402616352 0.1357408166 0.3507499099 780 31.1600000000 0.6365371346 0.9544004072 1.7159270048 0.0163940428 0.1055230000 1086844828 0 1786302464 -0.1428809613 0.1366267800 0.3512863517 781 31.2000000000 0.6398254633 0.9539976223 1.7159270048 0.0163889418 0.1044690000 1086846082 0 1786302464 -0.1454335898 0.1373715848 0.3517077565 782 31.2400000000 0.6428886056 0.9535997847 1.7159270048 0.0163820402 0.1041780000 1086847336 0 1786748928 -0.1478837579 0.1378113478 0.3521230519 783 31.2800000000 0.6461784840 0.9532071649 1.7159270048 0.0163747665 0.1141440000 1086848590 0 1787256832 -0.1502841413 0.1383711398 0.3526030481 784 31.3200000000 0.6491302252 0.9528193117 1.7159270048 0.0163674397 0.1156790000 1086849844 0 1787637760 -0.1525238305 0.1387814879 0.3531222343 785 31.3600000000 0.6518487930 0.9524359097 1.7159270048 0.0163594964 0.1149300000 1086851098 0 1787764736 -0.1546377689 0.1389857531 0.3534934521 786 31.4000000000 0.6546867490 0.9520570940 1.7159270048 0.0163514817 0.1134940000 1086852352 0 1786310656 -0.1567483097 0.1392571628 0.3539515138 787 31.4400000000 0.6575385332 0.9516828646 1.7159270048 0.0163431850 0.1140480000 1086853606 0 1786404864 -0.1587186009 0.1399145424 0.3543456495 788 31.4800000000 0.6601847410 0.9513129431 1.7159270048 0.0163352251 0.1144990000 1086854860 0 1786912768 -0.1604387909 0.1402211487 0.3549603522 789 31.5200000000 0.6624233723 0.9509467966 1.7159270048 0.0163271206 0.1131100000 1086856114 0 1787420672 -0.1621800810 0.1402342021 0.3553651571 790 31.5600000000 0.6648568511 0.9505846575 1.7159270048 0.0163189369 0.1118480000 1086857368 0 1787674624 -0.1639106274 0.1403460950 0.3557966650 791 31.6000000000 0.6670174599 0.9502261654 1.7159270048 0.0163115962 0.1124580000 1086858622 0 1787899904 -0.1654751599 0.1404000968 0.3562948108 792 31.6400000000 0.6690669060 0.9498711664 1.7159270048 0.0163036880 0.1112020000 1086859876 0 1786310656 -0.1668622047 0.1402817369 0.3567042649 793 31.6800000000 0.6706937551 0.9495191141 1.7159270048 0.0162952581 0.1123620000 1086861130 0 1786531840 -0.1680910289 0.1400111020 0.3572269380 794 31.7200000000 0.6722269654 0.9491698797 1.7159270048 0.0162875870 0.1082960000 1086862384 0 1787039744 -0.1692109853 0.1396310180 0.3576509356 795 31.7600000000 0.6737251878 0.9488234084 1.7159270048 0.0162813428 0.1087270000 1086863638 0 1787547648 -0.1702550501 0.1392998695 0.3580676913 796 31.8000000000 0.6753330231 0.9484798275 1.7159270048 0.0162781500 0.5047550000 1099179876 0 1787772928 -0.1712928563 0.1389214694 0.3586266935 797 31.8400000000 0.6781626940 0.9481406592 1.7159270048 0.0162741186 0.1381260000 1102838978 0 1786163200 -0.1710524708 0.1382670850 0.3580655754 798 31.8800000000 0.6793553233 0.9478038355 1.7159270048 0.0162693517 0.0977680000 1106032328 0 1786765312 -0.1719266474 0.1377875656 0.3585368991 799 31.9200000000 0.6805218458 0.9474693148 1.7159270048 0.0162619055 0.0888450000 1106033582 0 1785278464 -0.1727577001 0.1371625662 0.3589847982 800 31.9600000000 0.6815763712 0.9471369487 1.7159270048 0.0162540162 0.0905850000 1106034836 0 1785278464 -0.1735494733 0.1364716142 0.3595065475 801 32.0000000000 0.6829410791 0.9468071161 1.7159270048 0.0162481493 0.0897400000 1106036090 0 1785753600 -0.1741720438 0.1358744502 0.3601305187 802 32.0400000000 0.6841030717 0.9464795550 1.7159270048 0.0162410589 0.0899530000 1106037344 0 1786261504 -0.1748538613 0.1351536512 0.3607316017 803 32.0800000000 0.6856308579 0.9461547123 1.7159270048 0.0162369858 0.0883880000 1106038598 0 1786642432 -0.1751451939 0.1350609511 0.3616033792 804 32.1199999990 0.6868962646 0.9458322515 1.7159270048 0.0162348693 0.0871140000 1106039852 0 1786757120 -0.1754766703 0.1347997636 0.3622834086 805 32.1600000000 0.6880064607 0.9455119710 1.7159270048 0.0162323083 0.0860840000 1106041106 0 1787265024 -0.1758046895 0.1342042387 0.3630077243 806 32.2000000000 0.6889780760 0.9451936907 1.7159270048 0.0162286262 0.1096630000 1106042360 0 1787899904 -0.1761776060 0.1336897314 0.3635855615 807 32.2400000000 0.6895626783 0.9448769237 1.7159270048 0.0162259687 0.0883020000 1106043614 0 1786163200 -0.1763613671 0.1326306909 0.3642281592 808 32.2800000000 0.6905988455 0.9445622231 1.7159270048 0.0162199068 0.6008500000 1118360356 0 1787899904 -0.1767293215 0.1318186224 0.3649855852 809 32.3200000000 0.6916509867 0.9442496011 1.7159270048 0.0162129501 0.1234980000 1122019458 0 1786257408 -0.1765874028 0.1301473528 0.3654522598 810 32.3600000000 0.6925477982 0.9439388581 1.7159270048 0.0162056179 0.1007180000 1125212808 0 1787019264 -0.1768481284 0.1293844134 0.3660920262 811 32.4000000000 0.6931447387 0.9436296175 1.7159270048 0.0161963743 0.1000320000 1125214062 0 1785233408 -0.1771855205 0.1280376315 0.3668316603 812 32.4399999990 0.6938235760 0.9433219746 1.7159270048 0.0161877096 0.0941820000 1125215316 0 1785233408 -0.1774253696 0.1268606484 0.3675701022 813 32.4800000000 0.6950121522 0.9430165505 1.7159270048 0.0161796621 0.0885220000 1125216570 0 1785741312 -0.1774181575 0.1260057986 0.3685556054 814 32.5200000000 0.6961538792 0.9427132794 1.7159270048 0.0161713670 0.0869390000 1125217824 0 1786376192 -0.1775936931 0.1249964386 0.3694981337 815 32.5600000000 0.6972579360 0.9424121072 1.7159270048 0.0161618631 0.0878500000 1125219078 0 1786630144 -0.1778142899 0.1240202039 0.3704093993 816 32.6000000000 0.6982571483 0.9421128976 1.7159270048 0.0161526678 0.0884690000 1125220332 0 1786757120 -0.1778502464 0.1225157380 0.3715327382 817 32.6400000000 0.6994097829 0.9418158314 1.7159270048 0.0161428352 0.7217900000 1137536490 0 1787645952 -0.1780164093 0.1213594973 0.3724826872 818 32.6800000000 0.7007800341 0.9415211666 1.7159270048 0.0161330167 0.1204760000 1141195592 0 1786310656 -0.1781789511 0.1202398762 0.3737939000 819 32.7200000000 0.7027500868 0.9412296268 1.7159270048 0.0161237125 0.0936190000 1144388942 0 1786638336 -0.1781822890 0.1195574626 0.3752784431 820 32.7599999990 0.7048076987 0.9409413074 1.7159270048 0.0161145565 0.0900480000 1144390196 0 1785151488 -0.1784080863 0.1187809631 0.3766383827 821 32.7999999990 0.7072895169 0.9406567133 1.7159270048 0.0161092937 0.0876700000 1144391450 0 1785151488 -0.1780870259 0.1180243045 0.3785623908 822 32.8400000000 0.7096218467 0.9403756490 1.7159270048 0.0161117914 0.0853340000 1144392704 0 1785769984 -0.1781112105 0.1171534434 0.3801438212 823 32.8800000000 0.7121032476 0.9400982827 1.7159270048 0.0161056788 0.0844340000 1144393958 0 1786277888 -0.1784108430 0.1165010408 0.3818178475 824 32.9200000000 0.7152846456 0.9398254507 1.7159270048 0.0160977522 0.0868850000 1144395212 0 1786531840 -0.1784550846 0.1161326319 0.3837833703 825 32.9600000000 0.7182381749 0.9395568600 1.7159270048 0.0160951860 0.0851150000 1144396466 0 1786630144 -0.1785063595 0.1153438538 0.3857888579 826 33.0000000000 0.7214671373 0.9392928289 1.7159270048 0.0160902053 0.0832730000 1144397720 0 1787138048 -0.1787101030 0.1148782149 0.3878664076 827 33.0400000000 0.7243337035 0.9390329025 1.7159270048 0.0160905083 0.0963180000 1144398974 0 1787645952 -0.1788090169 0.1137665436 0.3898403645 828 33.0800000000 0.7268427014 0.9387766341 1.7159270048 0.0160923593 0.0940530000 1144400228 0 1786531840 -0.1788947433 0.1124735624 0.3916893005 829 33.1199999990 0.7299429774 0.9385247238 1.7159270048 0.0160890497 0.7826520000 1156718870 0 1787645952 -0.1791322678 0.1113426983 0.3937464952 830 33.1600000000 0.7329707146 0.9382770684 1.7159270048 0.0160845234 0.1203600000 1160377972 0 1786052608 -0.1792757660 0.1104583666 0.3954268694 831 33.2000000000 0.7358222008 0.9380334404 1.7159270048 0.0160807270 0.0978600000 1163571322 0 1786527744 -0.1793005913 0.1087798253 0.3976615965 832 33.2400000000 0.7389386892 0.9377941438 1.7159270048 0.0160742324 0.0941210000 1163572576 0 1785004032 -0.1794721931 0.1073927283 0.3998257816 833 33.2800000000 0.7425238490 0.9375597257 1.7159270048 0.0160663010 0.0920090000 1163573830 0 1785004032 -0.1797021478 0.1061859652 0.4021188021 834 33.3200000000 0.7456380725 0.9373296038 1.7159270048 0.0160605431 0.0871030000 1163575084 0 1785495552 -0.1799742281 0.1044865102 0.4042199552 835 33.3600000000 0.7491279840 0.9371042126 1.7159270048 0.0160537847 0.0867270000 1163576338 0 1786003456 -0.1803214699 0.1035706773 0.4062930644 836 33.4000000000 0.7525541782 0.9368834590 1.7159270048 0.0160478793 0.0854000000 1163577592 0 1786384384 -0.1805917025 0.1023483053 0.4085042775 837 33.4399999990 0.7561346889 0.9366675106 1.7159270048 0.0160434860 0.0854050000 1163578846 0 1786384384 -0.1809616387 0.1014409959 0.4106155634 838 33.4800000000 0.7589179873 0.9364553990 1.7159270048 0.0160451738 0.0914890000 1163580100 0 1786884096 -0.1810954660 0.0998233035 0.4125984609 839 33.5200000000 0.7623737454 0.9362479120 1.7159270048 0.0160441139 0.1052400000 1163581354 0 1787518976 -0.1812019348 0.0990186259 0.4147260785 840 33.5600000000 0.7652325034 0.9360443222 1.7159270048 0.0160393485 0.0962590000 1163582608 0 1788026880 -0.1819312125 0.0980918854 0.4163358212 841 33.6000000000 0.7683877945 0.9358449684 1.7159270048 0.0160306384 0.7524640000 1175900674 0 1786163200 -0.1826994419 0.0974641293 0.4180066884 842 33.6400000000 0.7714162469 0.9356496849 1.7159270048 0.0160215950 0.1218420000 1179559776 0 1785548800 -0.1833069623 0.0968515426 0.4195635021 843 33.6800000000 0.7742595673 0.9354582376 1.7159270048 0.0160131307 0.0969060000 1182753126 0 1786281984 -0.1836112589 0.0956827104 0.4213044345 844 33.7200000000 0.7765960097 0.9352700122 1.7159270048 0.0160067123 0.0944230000 1182754380 0 1785634816 -0.1838352829 0.0940209031 0.4229106307 845 33.7599999990 0.7791216373 0.9350852212 1.7159270048 0.0160008512 0.0943340000 1182755634 0 1785634816 -0.1838586330 0.0929209515 0.4246776104 846 33.7999999990 0.7818170190 0.9349040531 1.7159270048 0.0159929490 0.0902990000 1182756888 0 1786130432 -0.1842479259 0.0921839029 0.4261124134 847 33.8400000000 0.7834737301 0.9347252688 1.7159270048 0.0159842559 0.0868550000 1182758142 0 1786638336 -0.1845218241 0.0905276239 0.4273801744 848 33.8800000000 0.7856948376 0.9345495253 1.7159270048 0.0159751219 0.0837930000 1182759396 0 1787019264 -0.1848214120 0.0894204453 0.4286257029 849 33.9200000000 0.7872797251 0.9343760627 1.7159270048 0.0159660798 0.0824680000 1182760650 0 1787138048 -0.1850952059 0.0875466466 0.4298328161 850 33.9600000000 0.7891355157 0.9342051914 1.7159270048 0.0159576993 0.0865580000 1182761904 0 1787645952 -0.1853594184 0.0863643289 0.4310541451 851 34.0000000000 0.7913684845 0.9340373457 1.7159270048 0.0159487139 0.0997370000 1182763158 0 1786163200 -0.1856371313 0.0853479877 0.4323435724 852 34.0400000000 0.7929633260 0.9338717659 1.7159270048 0.0159394619 0.0959270000 1182764412 0 1786122240 -0.1856128573 0.0835742503 0.4335325360 853 34.0800000000 0.7945341468 0.9337084158 1.7159270048 0.0159302747 0.0940790000 1182765666 0 1786757120 -0.1858850420 0.0822911486 0.4345094562 854 34.1199999990 0.7962930799 0.9335475079 1.7159270048 0.0159212555 0.1063820000 1182766920 0 1787265024 -0.1859647632 0.0814509839 0.4357590079 855 34.1600000000 0.7979683280 0.9333889358 1.7159270048 0.0159133605 0.1125820000 1182768174 0 1787518976 -0.1859246045 0.0803221166 0.4367638826 856 34.2000000000 0.7993704677 0.9332323722 1.7159270048 0.0159052218 0.1075460000 1182769428 0 1787764736 -0.1860431731 0.0793945640 0.4377959371 857 34.2400000000 0.8012626767 0.9330783818 1.7159270048 0.0158961892 0.1047790000 1182770682 0 1786310656 -0.1863870174 0.0790268034 0.4387069643 858 34.2800000000 0.8027238846 0.9329264535 1.7159270048 0.0158873485 0.1076840000 1182771936 0 1786404864 -0.1868075728 0.0782993138 0.4394977391 859 34.3200000000 0.8032223582 0.9327754592 1.7159270048 0.0158789865 0.0998410000 1182773190 0 1786912768 -0.1866664290 0.0762918815 0.4400776923 860 34.3600000000 0.8037310839 0.9326254076 1.7159270048 0.0158699130 0.8011910000 1195307720 0 1787645952 -0.1868266463 0.0746494457 0.4406523705 861 34.4000000000 0.8048055172 0.9324769525 1.7159270048 0.0158607818 0.1296290000 1198966822 0 1786163200 -0.1868164241 0.0734874979 0.4416846931 862 34.4400000000 0.8055639267 0.9323297216 1.7159270048 0.0158517101 0.1019660000 1202160172 0 1786638336 -0.1871016324 0.0721903965 0.4422179163 863 34.4800000000 0.8057374954 0.9321830330 1.7159270048 0.0158428323 0.0968850000 1202161426 0 1785004032 -0.1869451851 0.0701384693 0.4426357448 864 34.5200000000 0.8063625693 0.9320374075 1.7159270048 0.0158336770 0.0957930000 1202162680 0 1784598528 -0.1868007928 0.0689875633 0.4433370233 865 34.5600000000 0.8076273799 0.9318935809 1.7159270048 0.0158251702 0.0890100000 1202163934 0 1784598528 -0.1870844364 0.0686314479 0.4438119829 866 34.6000000000 0.8084996343 0.9317510936 1.7159270048 0.0158188016 0.0860130000 1202165188 0 1784979456 -0.1876164675 0.0681308135 0.4441321790 867 34.6400000000 0.8091796637 0.9316097194 1.7159270048 0.0158101626 0.0847270000 1202166442 0 1785614336 -0.1875066608 0.0672686696 0.4446691275 868 34.6800000000 0.8094787598 0.9314690156 1.7159270048 0.0158013528 0.0863930000 1202167696 0 1785995264 -0.1876805276 0.0659815893 0.4449293613 869 34.7200000000 0.8096657991 0.9313288508 1.7159270048 0.0157923966 0.0869640000 1202168950 0 1785995264 -0.1874524355 0.0649499074 0.4452560246 870 34.7600000000 0.8099904656 0.9311893814 1.7159270048 0.0157834382 0.1009630000 1202170204 0 1786503168 -0.1878436208 0.0640116408 0.4454223514 871 34.8000000000 0.8105513453 0.9310508761 1.7159270048 0.0157745313 0.0885340000 1202171458 0 1787011072 -0.1881008297 0.0634322539 0.4456982613 872 34.8400000000 0.8110417128 0.9309132510 1.7159270048 0.0157655350 0.0875750000 1202172712 0 1787645952 -0.1884593815 0.0623947494 0.4458683431 873 34.8800000000 0.8118075728 0.9307768183 1.7159270048 0.0157565253 0.1004790000 1202173966 0 1786310656 -0.1885878891 0.0617137291 0.4463571310 874 34.9200000000 0.8126180172 0.9306416252 1.7159270048 0.0157475505 0.0996170000 1202175220 0 1786408960 -0.1888360977 0.0612926967 0.4467208982 875 34.9600000000 0.8139715791 0.9305082880 1.7159270048 0.0157386829 0.0892120000 1202176474 0 1786884096 -0.1892579794 0.0614029616 0.4472331107 876 35.0000000000 0.8148908019 0.9303763046 1.7159270048 0.0157300397 0.0935380000 1202177728 0 1787392000 -0.1895096004 0.0610127524 0.4477189779 877 35.0400000000 0.8159826398 0.9302458671 1.7159270048 0.0157211042 0.0936910000 1202178982 0 1787772928 -0.1897953153 0.0610044487 0.4481549561 878 35.0800000000 0.8169952035 0.9301168800 1.7159270048 0.0157123216 0.0887530000 1202180236 0 1787772928 -0.1901354194 0.0610423833 0.4485310614 879 35.1200000000 0.8178045750 0.9299891072 1.7159270048 0.0157034351 0.0931540000 1202181490 0 1786163200 -0.1903924495 0.0606764741 0.4489311278 880 35.1600000000 0.8188426495 0.9298628044 1.7159270048 0.0156948933 0.0949350000 1202182744 0 1785630720 -0.1905986071 0.0609748028 0.4494022429 881 35.2000000000 0.8199082017 0.9297379978 1.7159270048 0.0156862647 0.0915590000 1202183998 0 1785630720 -0.1909623891 0.0609315261 0.4498152435 882 35.2400000000 0.8198590875 0.9296134186 1.7159270048 0.0156775298 0.0915530000 1202185252 0 1785995264 -0.1908115000 0.0595700592 0.4499929249 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:06:10 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.0471660000 86899891 0 745693184 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0023446572 0.0011723286 0.0023446572 0.0021041625 0.1492910000 98786436 0 876662784 -0.0002852791 0.0014954667 0.0006866874 3 0.0800000000 0.0075948481 0.0033131684 0.0075948481 0.0080315103 0.1718690000 102057026 0 880447488 0.0012554106 0.0039727781 0.0004085181 4 0.1200000000 0.0050777206 0.0037543065 0.0075948481 0.0073383569 0.1100790000 102058608 0 881209344 0.0008574961 0.0019417178 -0.0002163760 5 0.1600000000 0.0045407121 0.0039115876 0.0075948481 0.0093500209 0.0894590000 102060198 0 881717248 -0.0011459948 0.0012547594 0.0010638405 6 0.2000000000 0.0107402997 0.0050497063 0.0107402997 0.0116118998 0.1176050000 102062108 0 882352128 0.0025259408 0.0054924614 0.0011174739 7 0.2400000000 0.0156035004 0.0065573912 0.0156035004 0.0114285807 0.1129570000 102063362 0 882860032 0.0043355413 0.0001782499 0.0011262146 8 0.2800000000 0.0071289954 0.0066288417 0.0156035004 0.0115473482 0.0974020000 102064616 0 883367936 0.0014490756 -0.0065932041 0.0005209973 9 0.3200000000 0.0013683990 0.0060443481 0.0156035004 0.0118275744 0.1000200000 102066542 0 883875840 0.0002015101 -0.0092197265 0.0017992224 10 0.3600000000 0.0089556947 0.0063354827 0.0156035004 0.0114770547 0.0976820000 102069108 0 884383744 0.0001396918 -0.0087586213 0.0011171554 11 0.4000000000 0.0053464146 0.0062455674 0.0156035004 0.0109826523 0.1082400000 102070362 0 885018624 -0.0006893562 -0.0086705703 0.0000857120 12 0.4400000000 0.0035623375 0.0060219649 0.0156035004 0.0111393019 0.1439490000 102071616 0 885526528 -0.0016122588 -0.0067996518 0.0014331206 13 0.4800000000 0.0025169421 0.0057523478 0.0156035004 0.0107423511 0.1198390000 102072870 0 886034432 -0.0022669565 -0.0039478885 0.0013786645 14 0.5200000000 0.0071462160 0.0058519098 0.0156035004 0.0105546336 0.0957480000 102074124 0 886542336 -0.0003283287 -0.0067178952 0.0002357676 15 0.5600000000 0.0086052809 0.0060354679 0.0156035004 0.0102425509 0.1136310000 102075378 0 887050240 0.0008428729 -0.0043073911 0.0002245001 16 0.6000000000 0.0078931181 0.0061515710 0.0156035004 0.0099692784 0.1046670000 102076632 0 887685120 -0.0002286811 -0.0063595036 0.0007458482 17 0.6400000000 0.0104427896 0.0064039957 0.0156035004 0.0097240717 0.0973340000 102079230 0 888193024 -0.0003984412 -0.0064314059 0.0002412419 18 0.6800000000 0.0102575570 0.0066180824 0.0156035004 0.0095047228 0.1031950000 102083108 0 888700928 0.0013745028 -0.0042889379 -0.0005667781 19 0.7200000000 0.0084796138 0.0067160577 0.0156035004 0.0093650972 0.1111230000 102084362 0 889208832 0.0024868674 -0.0017562904 -0.0007484712 20 0.7600000000 0.0097669782 0.0068686038 0.0156035004 0.0092607720 0.1060160000 102085616 0 889716736 0.0033084331 -0.0019663922 -0.0018465341 21 0.8000000000 0.0085105440 0.0069467914 0.0156035004 0.0093451422 0.1132660000 102086870 0 890351616 0.0017510556 -0.0037142611 -0.0016079081 22 0.8400000000 0.0092581846 0.0070518547 0.0156035004 0.0092126191 0.1242140000 102088124 0 890859520 0.0000844505 -0.0042872545 -0.0014144285 23 0.8800000000 0.0116193090 0.0072504397 0.0156035004 0.0093562632 0.0964020000 102089378 0 891367424 0.0053926622 -0.0032270055 -0.0027791692 24 0.9200000000 0.0136235114 0.0075159843 0.0156035004 0.0094693208 0.1139690000 102090632 0 891875328 0.0018477757 -0.0079759425 -0.0018416485 25 0.9600000000 0.0146757755 0.0078023760 0.0156035004 0.0094880274 0.0989270000 102091886 0 892383232 0.0040571289 -0.0045228451 -0.0041952366 26 1.0000000000 0.0146169951 0.0080644767 0.0156035004 0.0093275197 0.0889420000 102093140 0 893018112 0.0047017583 -0.0035957003 -0.0043082871 27 1.0400000000 0.0178340580 0.0084263131 0.0178340580 0.0091697983 0.1145340000 102094394 0 893526016 0.0056708986 -0.0046414016 -0.0050874124 28 1.0800000000 0.0181716345 0.0087743603 0.0181716345 0.0090257882 0.1049100000 102095648 0 894033920 0.0070423516 -0.0059747412 -0.0056901257 29 1.1200000000 0.0205717310 0.0091811661 0.0205717310 0.0088939043 0.0926240000 102096902 0 894541824 0.0075405282 -0.0058453805 -0.0058094794 30 1.1600000000 0.0187446196 0.0094999479 0.0205717310 0.0087671463 0.1014150000 102098156 0 895176704 0.0101546627 -0.0085139405 -0.0055602384 31 1.2000000000 0.0220228080 0.0099039112 0.0220228080 0.0086429310 0.1017210000 102099410 0 895684608 0.0098212417 -0.0058730347 -0.0063363886 32 1.2400000000 0.0214952044 0.0102661391 0.0220228080 0.0086112847 0.1158520000 102100664 0 896192512 0.0083449483 -0.0064250925 -0.0067757280 33 1.2800000000 0.0187942758 0.0105245675 0.0220228080 0.0087100083 0.1050310000 102104606 0 896700416 0.0108086132 -0.0084629394 -0.0071655335 34 1.3200000000 0.0256097335 0.0109682488 0.0256097335 0.0086796791 0.1096770000 102111108 0 897335296 0.0106691327 -0.0055570989 -0.0079707857 35 1.3600000000 0.0269767847 0.0114256356 0.0269767847 0.0085618351 0.1140390000 102112362 0 897843200 0.0095760170 -0.0050266567 -0.0083391173 36 1.4000000000 0.0285158213 0.0119003629 0.0285158213 0.0084669441 0.1245250000 102113616 0 898351104 0.0101622865 -0.0062897657 -0.0097047184 37 1.4400000000 0.0288674962 0.0123589341 0.0288674962 0.0083693373 0.1325260000 102114870 0 898859008 0.0134794898 -0.0073251314 -0.0107455878 38 1.4800000000 0.0280746315 0.0127725051 0.0288674962 0.0082571423 0.1252530000 102116124 0 899366912 0.0143910944 -0.0073716668 -0.0110385492 39 1.5200000000 0.0290368479 0.0131895395 0.0290368479 0.0081700035 0.1151430000 102117378 0 900001792 0.0142814787 -0.0087060677 -0.0109673142 40 1.5600000000 0.0300310738 0.0136105779 0.0300310738 0.0081470857 0.2113730000 114457156 0 912953344 0.0159455258 -0.0082074767 -0.0116755227 41 1.6000000000 0.0327784233 0.0140780863 0.0327784233 0.0082038735 0.0866070000 118116458 0 917016576 0.0177169312 -0.0089862384 -0.0117354030 42 1.6400000000 0.0336821824 0.0145448505 0.0336821824 0.0081096774 0.1154830000 121309808 0 920698880 0.0176363960 -0.0093701482 -0.0121651869 43 1.6800000000 0.0341573395 0.0150009549 0.0341573395 0.0080306259 0.1186940000 121311062 0 921460736 0.0195722189 -0.0099702142 -0.0128482264 44 1.7200000000 0.0360656157 0.0154796972 0.0360656157 0.0079522276 0.1021180000 121312316 0 921976832 0.0190209672 -0.0096221631 -0.0128637655 45 1.7600000000 0.0375743136 0.0159706887 0.0375743136 0.0080078402 0.1009790000 121313570 0 922484736 0.0194089469 -0.0101613179 -0.0134226503 46 1.8000000000 0.0389625505 0.0164705117 0.0389625505 0.0080035923 0.0998240000 121314824 0 922992640 0.0194951799 -0.0105294483 -0.0136002777 47 1.8400000000 0.0410766080 0.0169940457 0.0410766080 0.0079760889 0.1142650000 121316078 0 923627520 0.0190158002 -0.0110434340 -0.0138256755 48 1.8800000000 0.0426767841 0.0175291028 0.0426767841 0.0079195575 0.1224770000 121317332 0 924135424 0.0191692505 -0.0114871031 -0.0136568397 49 1.9200000000 0.0429848768 0.0180486083 0.0429848768 0.0078748052 0.0999630000 121318586 0 924643328 0.0205685943 -0.0115856640 -0.0142272143 50 1.9600000000 0.0419593789 0.0185268238 0.0429848768 0.0078523742 0.1275980000 121319840 0 925151232 0.0182639714 -0.0117189512 -0.0154621592 51 2.0000000000 0.0389960594 0.0189281813 0.0429848768 0.0078437988 0.1136760000 121321094 0 925786112 0.0200092364 -0.0074383873 -0.0162679050 52 2.0400000000 0.0418437868 0.0193688660 0.0429848768 0.0078154221 0.3204430000 140152444 0 941531136 0.0178129077 -0.0118710911 -0.0154884588 53 2.0800000000 0.0426446274 0.0198080313 0.0429848768 0.0077477187 0.0795120000 143811546 0 945721344 0.0181849971 -0.0139211444 -0.0159041174 54 2.1200000000 0.0443484038 0.0202624827 0.0443484038 0.0077524701 0.0755950000 147004896 0 949403648 0.0167223699 -0.0151377888 -0.0154685145 55 2.1600000000 0.0448228866 0.0207090355 0.0448228866 0.0077107475 0.0804930000 147006150 0 950165504 0.0173336957 -0.0149326939 -0.0157378651 56 2.2000000000 0.0458840020 0.0211585885 0.0458840020 0.0076635721 0.0869550000 147007404 0 950673408 0.0177841671 -0.0151837757 -0.0158775579 57 2.2400000000 0.0463602953 0.0216007237 0.0463602953 0.0076197380 0.1402860000 147008658 0 951308288 0.0186245032 -0.0168052316 -0.0165327135 58 2.2800000000 0.0365253575 0.0218580449 0.0463602953 0.0076407839 0.1009770000 147009912 0 951816192 0.0374587402 -0.0227341019 -0.0204167888 59 2.3200000000 0.0471371636 0.0222865046 0.0471371636 0.0078661027 0.1103720000 147011166 0 952324096 0.0270414688 -0.0202574600 -0.0179712214 60 2.3600000000 0.0497541912 0.0227442994 0.0497541912 0.0078350745 0.1032170000 147012420 0 952832000 0.0271624457 -0.0207383614 -0.0179441385 61 2.4000000000 0.0456060097 0.0231190815 0.0497541912 0.0077947626 0.0901820000 147013674 0 953466880 0.0322494060 -0.0226846654 -0.0198735334 62 2.4400000000 0.0488746762 0.0235344943 0.0497541912 0.0078095165 0.1046900000 147014928 0 953974784 0.0304814596 -0.0225332379 -0.0186404884 63 2.4800000000 0.0516718738 0.0239811194 0.0516718738 0.0077860380 0.0899980000 147016182 0 954482688 0.0338004418 -0.0235529393 -0.0188575685 64 2.5200000000 0.0556682423 0.0244762307 0.0556682423 0.0077377915 0.1034840000 147017436 0 954990592 0.0320303254 -0.0228566024 -0.0191421807 65 2.5600000000 0.0527386181 0.0249110366 0.0556682423 0.0076898975 0.0890080000 147024066 0 955498496 0.0367708355 -0.0246564653 -0.0204785690 66 2.6000000000 0.0539204665 0.0253505735 0.0556682423 0.0076478553 0.1199610000 147035816 0 956133376 0.0329423733 -0.0239021853 -0.0197705571 67 2.6400000000 0.0535459220 0.0257713995 0.0556682423 0.0076255943 0.1061800000 147037070 0 956641280 0.0349093825 -0.0257138163 -0.0204765908 68 2.6800000000 0.0576207824 0.0262397728 0.0576207824 0.0076168765 0.1142960000 147038324 0 957149184 0.0339988396 -0.0215932243 -0.0199335106 69 2.7200000000 0.0529138520 0.0266263537 0.0576207824 0.0075879008 0.3307470000 159343698 0 969973760 0.0416217670 -0.0244819727 -0.0220790450 70 2.7600000000 0.0529654585 0.0270026266 0.0576207824 0.0075879603 0.1302130000 163003208 0 974036992 0.0446687229 -0.0253513344 -0.0227360781 71 2.8000000000 0.0446725488 0.0272514988 0.0576207824 0.0075886083 0.0980860000 166196558 0 977719296 0.0602535754 -0.0303835366 -0.0270598941 72 2.8400000000 0.0518301241 0.0275928686 0.0576207824 0.0075917535 0.1038250000 166197812 0 978481152 0.0517880581 -0.0274863597 -0.0250456240 73 2.8800000000 0.0487315990 0.0278824402 0.0576207824 0.0075844372 0.1058330000 166199066 0 978989056 0.0613387823 -0.0305736940 -0.0282105990 74 2.9200000000 0.0483914651 0.0281595892 0.0576207824 0.0076301360 0.0822290000 166200320 0 979623936 0.0658889636 -0.0313582160 -0.0302424449 75 2.9600000000 0.0496652238 0.0284463310 0.0576207824 0.0076056569 0.1078110000 166201574 0 980131840 0.0716381371 -0.0337858573 -0.0311322175 76 3.0000000000 0.0613814481 0.0288796878 0.0613814481 0.0077035917 0.1021720000 166202828 0 980639744 0.0589238182 -0.0313868821 -0.0287633929 77 3.0400000000 0.0559787750 0.0292316240 0.0613814481 0.0076884087 0.1085820000 166204082 0 981147648 0.0711298957 -0.0348938815 -0.0317613259 78 3.0800000000 0.0655346066 0.0296970468 0.0655346066 0.0076510708 0.0971990000 166205336 0 981655552 0.0622566231 -0.0340403132 -0.0301289782 79 3.1200000000 0.0673735961 0.0301739652 0.0673735961 0.0076380236 0.1139780000 166206590 0 982290432 0.0642349347 -0.0350074768 -0.0306750629 80 3.1600000000 0.0670414567 0.0306348088 0.0673735961 0.0076040377 0.1123860000 166207844 0 982798336 0.0703428611 -0.0370010510 -0.0327879041 81 3.2000000000 0.0699768290 0.0311205128 0.0699768290 0.0075604612 0.1041490000 166209098 0 983306240 0.0729992241 -0.0389303714 -0.0330267362 82 3.2400000000 0.0667423755 0.0315549257 0.0699768290 0.0075522319 0.1338030000 166210352 0 983814144 0.0819198191 -0.0403837338 -0.0357418172 83 3.2800000000 0.0706671551 0.0320261574 0.0706671551 0.0075197464 0.1309920000 166211606 0 984567808 0.0806500837 -0.0420311764 -0.0357468985 84 3.3200000000 0.0720284954 0.0325023757 0.0720284954 0.0074846117 0.1295350000 166212860 0 985075712 0.0878955498 -0.0457560420 -0.0376482122 85 3.3600000000 0.0756126195 0.0330095551 0.0756126195 0.0074799550 0.1274630000 166214114 0 985583616 0.0956309438 -0.0482934862 -0.0386021174 86 3.4000000000 0.0781200305 0.0335340955 0.0781200305 0.0074833937 0.2887540000 178517728 0 998535168 0.0985398889 -0.0502106398 -0.0399175994 87 3.4400000000 0.0850352347 0.0341260626 0.0850352347 0.0074523530 0.1363020000 182176830 0 1002598400 0.0902819559 -0.0473564081 -0.0392928869 88 3.4800000000 0.0868615583 0.0347253296 0.0868615583 0.0074373519 0.1024340000 185370180 0 1006280704 0.0956710875 -0.0492710881 -0.0404466055 89 3.5200000000 0.0867309123 0.0353096620 0.0868615583 0.0074044068 0.0843510000 185371434 0 1007042560 0.0996499360 -0.0500074290 -0.0416929796 90 3.5600000000 0.0884745941 0.0359003834 0.0884745941 0.0073656896 0.0775530000 185372688 0 1007550464 0.1027112529 -0.0523335673 -0.0422995873 91 3.6000000000 0.0905790702 0.0365012481 0.0905790702 0.0073541110 0.0781610000 185373942 0 1008058368 0.1056649461 -0.0517211482 -0.0429051928 92 3.6400000000 0.0943108574 0.0371296135 0.0943108574 0.0073680757 0.0777860000 185375196 0 1008693248 0.1140515432 -0.0558256842 -0.0435609706 93 3.6800000000 0.1015111357 0.0378218879 0.1015111357 0.0073761843 0.0870250000 185376450 0 1009201152 0.1178732812 -0.0590029173 -0.0440135710 94 3.7200000000 0.1055991426 0.0385429225 0.1055991426 0.0073880972 0.0927730000 185377704 0 1009709056 0.1278229356 -0.0665987208 -0.0448068157 95 3.7600000000 0.1076369211 0.0392702278 0.1076369211 0.0073669703 0.0821290000 185378958 0 1010216960 0.1307404637 -0.0657595992 -0.0459948927 96 3.8000000000 0.1106893569 0.0400141770 0.1106893569 0.0073782708 0.1087290000 185380212 0 1010724864 0.1337665915 -0.0661747679 -0.0463331379 97 3.8400000000 0.1151148304 0.0407884106 0.1151148304 0.0073577226 0.0912800000 185381466 0 1011359744 0.1402732283 -0.0694147199 -0.0479473025 98 3.8800000000 0.1179597080 0.0415758728 0.1179597080 0.0073482545 0.0978380000 185382720 0 1011867648 0.1461829543 -0.0710576847 -0.0482799597 99 3.9200000000 0.1217731163 0.0423859459 0.1217731163 0.0073981917 0.1201100000 185383974 0 1012375552 0.1516732126 -0.0738751814 -0.0485540926 100 3.9600000000 0.1265914291 0.0432280008 0.1265914291 0.0073980248 0.1113570000 185385228 0 1012883456 0.1593605131 -0.0806526542 -0.0480499603 101 4.0000000000 0.1295034140 0.0440822128 0.1295034140 0.0074247213 0.2669970000 197692266 0 1025708032 0.1678364724 -0.0829302892 -0.0493343621 102 4.0400000000 0.1342088133 0.0449658069 0.1342088133 0.0074349507 0.1234830000 201351368 0 1029771264 0.1671169251 -0.0845772028 -0.0494868867 103 4.0800000000 0.1395084709 0.0458836969 0.1395084709 0.0074312669 0.0960430000 204544718 0 1033453568 0.1717514247 -0.0865261033 -0.0490636714 104 4.1200000000 0.1445075870 0.0468320035 0.1445075870 0.0074423677 0.1029810000 204545972 0 1034215424 0.1812996417 -0.0905916095 -0.0495928936 105 4.1600000000 0.1470055282 0.0477860371 0.1470055282 0.0074493012 0.0935120000 204547226 0 1034850304 0.1860718876 -0.0915233046 -0.0499631315 106 4.2000000000 0.1503248811 0.0487533846 0.1503248811 0.0074906793 0.0945330000 204548480 0 1035358208 0.1898166090 -0.0938502848 -0.0500957519 107 4.2400000000 0.1536316425 0.0497335553 0.1536316425 0.0074817459 0.0914290000 204549734 0 1035866112 0.1937211901 -0.0951797292 -0.0499085598 108 4.2800000000 0.1574023366 0.0507304884 0.1574023366 0.0074955875 0.0959440000 204550988 0 1036374016 0.1998293996 -0.0973704755 -0.0501830541 109 4.3200000000 0.1649531275 0.0517784026 0.1649531275 0.0075163009 0.1011970000 204552242 0 1037008896 0.2099792063 -0.1011440083 -0.0503278524 110 4.3600000000 0.1713483930 0.0528654025 0.1713483930 0.0074934218 0.0788150000 204553496 0 1037516800 0.2139188647 -0.1014194265 -0.0502396859 111 4.4000000000 0.1764026284 0.0539783505 0.1764026284 0.0074778526 0.1080970000 204554750 0 1038024704 0.2176921219 -0.1026591808 -0.0499921478 112 4.4400000000 0.1765143424 0.0550724218 0.1765143424 0.0074498075 0.0979860000 204556004 0 1038532608 0.2227055281 -0.1046247482 -0.0506653525 113 4.4800000000 0.1816013604 0.0561921469 0.1816013604 0.0074352057 0.1039130000 204557258 0 1039040512 0.2257590443 -0.1060148850 -0.0497962832 114 4.5200000000 0.1887051910 0.0573545421 0.1887051910 0.0074189746 0.1146120000 204558512 0 1039675392 0.2273830473 -0.1063679978 -0.0495321155 115 4.5600000000 0.1897052228 0.0585054175 0.1897052228 0.0074006160 0.1237800000 204559766 0 1040183296 0.2370331585 -0.1089343652 -0.0499379262 116 4.6000000000 0.1916138083 0.0596529037 0.1916138083 0.0073800511 0.1145020000 204561020 0 1040691200 0.2413674742 -0.1096886620 -0.0500810519 117 4.6400000000 0.1934023649 0.0607960615 0.1934023649 0.0073496077 0.1107150000 204562274 0 1041199104 0.2476536632 -0.1125185639 -0.0494411513 118 4.6800000000 0.1965098232 0.0619461781 0.1965098232 0.0073243622 0.1487580000 204563528 0 1041833984 0.2547376156 -0.1145596430 -0.0487082228 119 4.7200000000 0.2018470317 0.0631218155 0.2018470317 0.0073054685 0.1442940000 204564782 0 1042341888 0.2632668614 -0.1167949736 -0.0473830923 120 4.7600000000 0.2083689868 0.0643322086 0.2083689868 0.0073067560 0.2465240000 216867144 0 1055158272 0.2658759654 -0.1160895303 -0.0469702035 121 4.8000000000 0.2174192518 0.0655973908 0.2174192518 0.0073113278 0.1038350000 220526246 0 1059094528 0.2578173578 -0.1099933833 -0.0480902754 122 4.8400000000 0.2207250893 0.0668689293 0.2207250893 0.0073497704 0.0994450000 223719596 0 1062903808 0.2648192644 -0.1126110852 -0.0479722284 123 4.8800000000 0.2273484468 0.0681736408 0.2273484468 0.0073519539 0.0944470000 223720850 0 1063665664 0.2691218257 -0.1131604388 -0.0468435958 124 4.9200000000 0.2299914062 0.0694786228 0.2299914062 0.0073414516 0.0997160000 223722104 0 1064173568 0.2728041112 -0.1140193120 -0.0452550761 125 4.9600000000 0.2321390361 0.0707799061 0.2321390361 0.0073247600 0.0860190000 223723358 0 1064681472 0.2723898590 -0.1129892841 -0.0446005315 126 5.0000000000 0.2382302284 0.0721088769 0.2382302284 0.0073091466 0.0764380000 223724612 0 1065189376 0.2747725248 -0.1141173318 -0.0431050994 127 5.0400000000 0.2420458198 0.0734469631 0.2420458198 0.0072919429 0.0887160000 223725866 0 1065824256 0.2789830565 -0.1131772101 -0.0425254740 128 5.0800000000 0.2472168803 0.0748045406 0.2472168803 0.0072786015 0.0860250000 223727120 0 1066332160 0.2848909795 -0.1137406528 -0.0409461372 129 5.1200000000 0.2508780956 0.0761694518 0.2508780956 0.0072617298 0.1284130000 223739126 0 1066840064 0.2913889885 -0.1135259271 -0.0395674966 130 5.1600000000 0.2545478046 0.0775415930 0.2545478046 0.0072486834 0.0988680000 223761372 0 1067474944 0.2931685150 -0.1127327085 -0.0385605171 131 5.2000000000 0.2599724829 0.0789341952 0.2599724829 0.0072910790 0.0828220000 223762626 0 1067982848 0.2918215394 -0.1115486994 -0.0370579511 132 5.2400000000 0.2658070326 0.0803498985 0.2658070326 0.0073088421 0.0818890000 223763880 0 1068490752 0.2949352860 -0.1108253822 -0.0356073193 133 5.2800000000 0.2688957751 0.0817675367 0.2688957751 0.0073068407 0.0946320000 223765134 0 1068998656 0.3008747399 -0.1094287857 -0.0339744389 134 5.3200000000 0.2732163668 0.0831962593 0.2732163668 0.0073808417 0.0925410000 223766388 0 1069506560 0.3036437333 -0.1087186784 -0.0327402540 135 5.3600000000 0.2789370716 0.0846461913 0.2789370716 0.0074457778 0.2888170000 236067942 0 1082331136 0.3074990213 -0.1102863550 -0.0315163620 136 5.4000000000 0.2889692187 0.0861485665 0.2889692187 0.0074782279 0.0961930000 239727884 0 1086394368 0.3118303418 -0.1084893495 -0.0296641551 137 5.4400000000 0.2932677865 0.0876603856 0.2932677865 0.0074900690 0.0922750000 242921234 0 1090076672 0.3134568334 -0.1085861921 -0.0282947272 138 5.4800000000 0.2919602692 0.0891408195 0.2932677865 0.0075388352 0.0826780000 242922488 0 1090838528 0.3164393306 -0.1063859686 -0.0280740727 139 5.5200000000 0.2961331308 0.0906299728 0.2961331308 0.0075361820 0.0761350000 242923742 0 1091346432 0.3204540014 -0.1067075133 -0.0262108110 140 5.5600000000 0.3014851213 0.0921360810 0.3014851213 0.0075220019 0.0744290000 242924996 0 1091981312 0.3224600852 -0.1058126017 -0.0241449811 141 5.6000000000 0.3079373837 0.0936665867 0.3079373837 0.0075197577 0.0806180000 242926250 0 1092489216 0.3239088356 -0.1055553630 -0.0212976467 142 5.6400000000 0.3133380711 0.0952135690 0.3133380711 0.0075311492 0.0802410000 242927504 0 1092997120 0.3278335929 -0.1039396003 -0.0195049420 143 5.6800000000 0.3182535768 0.0967732894 0.3182535768 0.0075503801 0.0687900000 242928758 0 1093505024 0.3314819634 -0.1031861529 -0.0176225621 144 5.7200000000 0.3214817345 0.0983337647 0.3214817345 0.0075776030 0.0739760000 242930012 0 1094139904 0.3333022296 -0.1025603861 -0.0161112100 145 5.7600000000 0.3254010379 0.0998997459 0.3254010379 0.0075796251 0.0880870000 242931266 0 1094647808 0.3362205923 -0.1011418998 -0.0141296387 146 5.8000000000 0.3309759796 0.1014824598 0.3309759796 0.0075681498 0.0821890000 242932520 0 1095155712 0.3396304846 -0.0998571143 -0.0118817752 147 5.8400000000 0.3371334970 0.1030855281 0.3371334970 0.0075758387 0.0837690000 242933774 0 1095663616 0.3431979418 -0.0989288390 -0.0095948046 148 5.8800000000 0.3384422958 0.1046757765 0.3384422958 0.0075960024 0.0930310000 242935028 0 1096171520 0.3451755941 -0.0977221206 -0.0080369962 149 5.9200000000 0.3410536051 0.1062622049 0.3410536051 0.0075867822 0.0889520000 242936282 0 1096806400 0.3476338685 -0.0974684581 -0.0066617108 150 5.9600000000 0.3466626108 0.1078648743 0.3466626108 0.0075719574 0.0916480000 242937536 0 1097314304 0.3498699963 -0.0956650600 -0.0042336928 151 6.0000000000 0.3509037197 0.1094744030 0.3509037197 0.0075524963 0.0882780000 242938790 0 1097822208 0.3533932269 -0.0945594162 -0.0030446057 152 6.0400000000 0.3584677875 0.1111125174 0.3584677875 0.0075379062 0.1006640000 242940044 0 1098330112 0.3575778306 -0.0928641930 0.0007547804 153 6.0800000000 0.3630929589 0.1127594484 0.3630929589 0.0075250265 0.0892680000 242941298 0 1098838016 0.3604182005 -0.0919058323 0.0026973565 154 6.1200000000 0.3663211763 0.1144059531 0.3663211763 0.0075131579 0.0944170000 242942552 0 1099472896 0.3633424342 -0.0908300206 0.0042115152 155 6.1600000000 0.3684707582 0.1160450809 0.3684707582 0.0075111147 0.0941330000 242943806 0 1099980800 0.3649384081 -0.0897494778 0.0056586084 156 6.2000000000 0.3740585744 0.1176990135 0.3740585744 0.0075607047 0.0938170000 242945060 0 1100488704 0.3680219948 -0.0890556648 0.0078145675 157 6.2400000000 0.3775979280 0.1193544206 0.3775979280 0.0075862656 0.0973130000 242946314 0 1100996608 0.3709591031 -0.0877245963 0.0097673750 158 6.2800000000 0.3799107671 0.1210035114 0.3799107671 0.0075951046 0.0977300000 242947568 0 1101504512 0.3730024695 -0.0861224160 0.0115426052 159 6.3200000000 0.3845866323 0.1226612669 0.3845866323 0.0076500440 0.1023890000 242948822 0 1102131200 0.3757994771 -0.0845975652 0.0140394047 160 6.3600000000 0.3933760822 0.1243532345 0.3933760822 0.0077969686 0.1012580000 242950076 0 1102639104 0.3808179498 -0.0819976628 0.0190848298 161 6.4000000000 0.3960357904 0.1260407038 0.3960357904 0.0078194410 0.1073880000 242951330 0 1103147008 0.3825696409 -0.0800109282 0.0211905520 162 6.4400000000 0.4001250565 0.1277325825 0.4001250565 0.0078194818 0.0980250000 242952584 0 1103654912 0.3841667771 -0.0786629692 0.0240248609 163 6.4800000000 0.4041852653 0.1294286113 0.4041852653 0.0078443025 0.1109190000 242953838 0 1104289792 0.3866471052 -0.0769374818 0.0268301703 164 6.5200000000 0.4089301527 0.1311328890 0.4089301527 0.0078743892 0.1093670000 242955092 0 1104797696 0.3894955218 -0.0755080432 0.0299371686 165 6.5600000000 0.4150006473 0.1328532996 0.4150006473 0.0079130594 0.1250870000 242956346 0 1105305600 0.3926882744 -0.0735001490 0.0330891088 166 6.6000000000 0.4214200675 0.1345916536 0.4214200675 0.0079682565 0.1209830000 242957600 0 1105940480 0.3952524066 -0.0714069977 0.0364130661 167 6.6400000000 0.4246883988 0.1363287599 0.4246883988 0.0080229245 0.1273570000 242958854 0 1106448384 0.3970404267 -0.0698473528 0.0392061062 168 6.6800000000 0.4299143851 0.1380762934 0.4299143851 0.0080544372 0.1192340000 242960108 0 1106956288 0.3998131454 -0.0683357641 0.0422707647 169 6.7200000000 0.4372670054 0.1398466526 0.4372670054 0.0080750218 0.1231260000 242961362 0 1107464192 0.4024695456 -0.0653363317 0.0459607281 170 6.7600000000 0.4418758452 0.1416232949 0.4418758452 0.0081051645 0.1181650000 242962616 0 1107972096 0.4042514265 -0.0640024319 0.0491191782 171 6.8000000000 0.4490418732 0.1434210644 0.4490418732 0.0081024192 0.1294760000 242963870 0 1108606976 0.4073372483 -0.0612423718 0.0527413450 172 6.8400000000 0.4550897777 0.1452330918 0.4550897777 0.0080977581 0.1355780000 242965124 0 1109114880 0.4105818868 -0.0590357296 0.0561271720 173 6.8800000000 0.4579307735 0.1470405928 0.4579307735 0.0080781114 0.1339850000 242966378 0 1109622784 0.4119106233 -0.0574598089 0.0590053946 174 6.9200000000 0.4642122686 0.1488634186 0.4642122686 0.0080640504 0.1156360000 242967632 0 1110130688 0.4152249694 -0.0556297861 0.0623420589 175 6.9600000000 0.4723892808 0.1507121378 0.4723892808 0.0080589760 0.1114200000 242968886 0 1110638592 0.4182808399 -0.0532702915 0.0660763457 176 7.0000000000 0.4780602157 0.1525720700 0.4780602157 0.0080506947 0.1209780000 242970140 0 1111281664 0.4206732810 -0.0507869646 0.0696288422 177 7.0400000000 0.4821983576 0.1544343654 0.4821983576 0.0080865286 0.3368760000 255274550 0 1124233216 0.4217616320 -0.0491431952 0.0729456171 178 7.0800000000 0.4987752140 0.1563688646 0.4987752140 0.0081270387 0.1109220000 258933652 0 1128169472 0.4060869813 -0.0282272175 0.0700375438 179 7.1200000000 0.5047072768 0.1583148892 0.5047072768 0.0081211478 0.1107530000 262127002 0 1131978752 0.4077688456 -0.0268804841 0.0733277351 180 7.1600000000 0.5096848607 0.1602669446 0.5096848607 0.0081211721 0.1068080000 262128256 0 1132613632 0.4101954997 -0.0242674295 0.0767242685 181 7.2000000000 0.5137220621 0.1622197353 0.5137220621 0.0081042318 0.1044270000 262129510 0 1133248512 0.4111573696 -0.0224105790 0.0799969137 182 7.2400000000 0.5191026926 0.1641806307 0.5191026926 0.0080986289 0.1069160000 262130764 0 1133756416 0.4130366743 -0.0211913399 0.0833011270 183 7.2800000000 0.5247625113 0.1661510235 0.5247625113 0.0080884775 0.0941520000 262132018 0 1134264320 0.4142976403 -0.0196389295 0.0867383853 184 7.3200000000 0.5286800861 0.1681212902 0.5286800861 0.0080878318 0.0919420000 262133272 0 1134899200 0.4169238806 -0.0177295860 0.0895080641 185 7.3600000000 0.5319435596 0.1700878970 0.5319435596 0.0080825294 0.0905360000 262134526 0 1135407104 0.4180243611 -0.0166122578 0.0921159387 186 7.4000000000 0.5360766649 0.1720555786 0.5360766649 0.0080719846 0.1050200000 262135780 0 1135915008 0.4208754897 -0.0140578309 0.0956095979 187 7.4400000000 0.5408652425 0.1740278228 0.5408652425 0.0080806796 0.1077380000 262137034 0 1136422912 0.4221937954 -0.0127215451 0.0984561592 188 7.4800000000 0.5444045067 0.1759979115 0.5444045067 0.0080653249 0.1054200000 262138288 0 1136930816 0.4237858653 -0.0108472705 0.1010509506 189 7.5200000000 0.5475162268 0.1779636169 0.5475162268 0.0080496267 0.1081490000 262139542 0 1137438720 0.4247448444 -0.0097929519 0.1035427526 190 7.5600000000 0.5516505241 0.1799303901 0.5516505241 0.0080289385 0.1251710000 262140796 0 1138073600 0.4268872738 -0.0075352918 0.1069141924 191 7.6000000000 0.5553364158 0.1818958666 0.5553364158 0.0080186545 0.1265200000 262142050 0 1138581504 0.4284925163 -0.0049344795 0.1100169122 192 7.6400000000 0.5587789416 0.1838587993 0.5587789416 0.0080029166 0.1180160000 262143304 0 1139089408 0.4295641184 -0.0032375194 0.1131850258 193 7.6800000000 0.5654135942 0.1858357672 0.5654135942 0.0079995391 0.1165660000 262144558 0 1139597312 0.4316556156 -0.0007116632 0.1186301559 194 7.7200000000 0.5687385798 0.1878094930 0.5687385798 0.0079815485 0.1201290000 262145812 0 1140105216 0.4337461591 0.0020789732 0.1222713515 195 7.7600000000 0.5765580535 0.1898030754 0.5765580535 0.0079779346 0.1186330000 262147066 0 1140740096 0.4344662726 0.0055899834 0.1293816119 196 7.8000000000 0.5772345066 0.1917797663 0.5772345066 0.0079618280 0.1181470000 262148320 0 1141248000 0.4358718097 0.0076281563 0.1327709407 197 7.8400000000 0.5802883506 0.1937518911 0.5802883506 0.0079423987 0.1267000000 262149574 0 1141755904 0.4374753833 0.0103055853 0.1369868666 198 7.8800000000 0.5837762356 0.1957217111 0.5837762356 0.0079244682 0.1160880000 262150828 0 1142263808 0.4384146035 0.0131511837 0.1412452161 199 7.9200000000 0.5860236287 0.1976830272 0.5860236287 0.0079113026 0.1268720000 262152082 0 1142898688 0.4384934604 0.0154695343 0.1450832784 200 7.9600000000 0.5888246298 0.1996387352 0.5888246298 0.0078943627 0.1307910000 262153336 0 1143406592 0.4402964115 0.0183926914 0.1496478617 201 8.0000000000 0.5927562714 0.2015945439 0.5927562714 0.0078793474 0.1262740000 262154590 0 1143914496 0.4413624704 0.0208489001 0.1541832387 202 8.0400000000 0.5954751372 0.2035444478 0.5954751372 0.0078657973 0.1242300000 262155844 0 1144422400 0.4410250783 0.0233834721 0.1580630094 203 8.0800000000 0.5980523229 0.2054878364 0.5980523229 0.0078519188 0.1281720000 262157098 0 1145057280 0.4410783350 0.0259494912 0.1621775478 204 8.1200000000 0.6031624675 0.2074372218 0.6031624675 0.0078559551 0.1123390000 262158352 0 1145565184 0.4391579628 0.0276173688 0.1657969654 205 8.1600000000 0.6061635613 0.2093822283 0.6061635613 0.0078674294 0.1297930000 262159606 0 1146073088 0.4405485988 0.0306568332 0.1704927981 206 8.1999999990 0.6107641459 0.2113306842 0.6107641459 0.0078795836 0.5213970000 274478184 0 1158897664 0.4400315285 0.0334572159 0.1751773655 207 8.2400000000 0.6211568117 0.2133105206 0.6211568117 0.0078688297 0.1376390000 278137286 0 1162960896 0.4315277934 0.0429336652 0.1817036569 208 8.2799999990 0.6249996424 0.2152897952 0.6249996424 0.0078811249 0.1237530000 281330636 0 1166643200 0.4312190711 0.0450340398 0.1859505326 209 8.3200000000 0.6293308735 0.2172708530 0.6293308735 0.0078786381 0.1173140000 281331890 0 1167405056 0.4305422902 0.0469406471 0.1903973073 210 8.3599999990 0.6337412596 0.2192540454 0.6337412596 0.0078687184 0.1092020000 281333144 0 1168039936 0.4304889739 0.0492733121 0.1949903071 211 8.4000000000 0.6387413144 0.2212421368 0.6387413144 0.0078777417 0.1021860000 281334398 0 1168547840 0.4299453497 0.0511181727 0.1994888335 212 8.4399999990 0.6428077817 0.2232306540 0.6428077817 0.0078875270 0.1091290000 281335652 0 1169055744 0.4291049540 0.0530163832 0.2040602267 213 8.4800000000 0.6470503211 0.2252204176 0.6470503211 0.0079003060 0.1005380000 281336906 0 1169563648 0.4276046157 0.0545594580 0.2082097530 214 8.5200000000 0.6512829065 0.2272113639 0.6512829065 0.0079128355 0.0973840000 281338160 0 1170071552 0.4266194999 0.0562131479 0.2123129815 215 8.5600000000 0.6566907763 0.2292089425 0.6566907763 0.0079255834 0.0931830000 281339414 0 1170706432 0.4257469475 0.0575856157 0.2166254967 216 8.6000000000 0.6619607806 0.2312124233 0.6619607806 0.0079241514 0.1076980000 281340668 0 1171214336 0.4253723323 0.0590991154 0.2212765515 217 8.6400000000 0.6662425995 0.2332171706 0.6662425995 0.0079326811 0.1019270000 281341922 0 1171722240 0.4239626527 0.0591028668 0.2253694683 218 8.6800000000 0.6694979072 0.2352184584 0.6694979072 0.0079315829 0.1054270000 281343176 0 1172230144 0.4232797623 0.0600145869 0.2291439027 219 8.7200000000 0.6724271774 0.2372148452 0.6724271774 0.0079315688 0.1182550000 281344430 0 1172865024 0.4217837453 0.0607264303 0.2327954918 220 8.7600000000 0.6751096845 0.2392052763 0.6751096845 0.0079340703 0.1102750000 281345684 0 1173372928 0.4195565283 0.0607226864 0.2364304513 221 8.8000000000 0.6802744865 0.2412010646 0.6802744865 0.0079304423 0.1105560000 281346938 0 1173880832 0.4189881086 0.0629417822 0.2411293685 222 8.8400000000 0.6840406656 0.2431958376 0.6840406656 0.0079192669 0.1136270000 281348192 0 1174388736 0.4174068570 0.0648950040 0.2454192638 223 8.8800000000 0.6868602037 0.2451853639 0.6868602037 0.0079172420 0.1082910000 281349446 0 1174896640 0.4160667658 0.0647965595 0.2485888153 224 8.9200000000 0.6900575161 0.2471714003 0.6900575161 0.0079077314 0.1139690000 281350700 0 1175531520 0.4147398174 0.0673079044 0.2531032562 225 8.9600000000 0.6948449612 0.2491610606 0.6948449612 0.0078998360 0.5654610000 293654122 0 1188356096 0.4136928022 0.0693102702 0.2576993406 226 9.0000000000 0.7067045569 0.2511855893 0.7067045569 0.0079175271 0.1489950000 297313224 0 1192292352 0.4105144739 0.0720582083 0.2658814192 227 9.0400000000 0.7115302682 0.2532135394 0.7115302682 0.0079083386 0.1221990000 300506574 0 1195974656 0.4101135135 0.0735121742 0.2698948085 228 9.0800000000 0.7146241069 0.2552372700 0.7146241069 0.0079039360 0.1087480000 300507828 0 1196736512 0.4083671272 0.0746911466 0.2733823061 229 9.1200000000 0.7197740674 0.2572658150 0.7197740674 0.0079159108 0.1056730000 300509082 0 1197371392 0.4079902768 0.0755336508 0.2774415910 230 9.1600000000 0.7245171666 0.2592973426 0.7245171666 0.0079103809 0.1029890000 300510336 0 1197879296 0.4079297781 0.0764952600 0.2813315094 231 9.2000000000 0.7326830029 0.2613466311 0.7326830029 0.0079193719 0.1018840000 300511590 0 1198387200 0.4066172838 0.0778365657 0.2883380055 232 9.2400000000 0.7384071946 0.2634029267 0.7384071946 0.0079131187 0.1058840000 300512844 0 1198895104 0.4062635899 0.0796922296 0.2929504812 233 9.2800000000 0.7443332076 0.2654670051 0.7443332076 0.0079157741 0.1020050000 300514098 0 1199403008 0.4059559703 0.0809949040 0.2975180745 234 9.3200000000 0.7489380836 0.2675331209 0.7489380836 0.0079101891 0.0943940000 300515352 0 1200037888 0.4049791694 0.0827894285 0.3016566634 235 9.3600000000 0.7539065480 0.2696027950 0.7539065480 0.0079089987 0.1104280000 300516606 0 1200545792 0.4042761624 0.0838920549 0.3058139682 236 9.4000000000 0.7587592006 0.2716754916 0.7587592006 0.0079055717 0.1031770000 300517860 0 1201053696 0.4044665992 0.0850600749 0.3095431626 237 9.4400000000 0.7642574310 0.2737538965 0.7642574310 0.0079097097 0.1025680000 300519114 0 1201561600 0.4039737284 0.0869270712 0.3140148818 238 9.4800000000 0.7695871592 0.2758372295 0.7695871592 0.0079061224 0.1259880000 300520368 0 1202069504 0.4037113786 0.0881229937 0.3182357252 239 9.5200000000 0.7753565907 0.2779272687 0.7753565907 0.0079093158 0.1258990000 300521622 0 1202704384 0.4039080143 0.0898222774 0.3224440217 240 9.5600000000 0.7798188329 0.2800184835 0.7798188329 0.0079059908 0.1268920000 300522876 0 1203212288 0.4033625722 0.0901147500 0.3259474635 241 9.6000000000 0.7837765813 0.2821087661 0.7837765813 0.0078989064 0.1250880000 300524130 0 1203720192 0.4021438360 0.0910838246 0.3296109736 242 9.6400000000 0.7901633382 0.2842081651 0.7901633382 0.0079084167 0.1238220000 300525384 0 1204355072 0.4019809961 0.0926651582 0.3342187405 243 9.6800000000 0.7979553938 0.2863223513 0.7979553938 0.0079069823 0.1272620000 300526638 0 1204862976 0.4024208784 0.0941449553 0.3395242691 244 9.7200000000 0.8043756485 0.2884455205 0.8043756485 0.0079010726 0.1221190000 300527892 0 1205370880 0.4025062919 0.0960802808 0.3440659046 245 9.7600000000 0.8088027835 0.2905694277 0.8088027835 0.0078900492 0.1267420000 300529146 0 1205878784 0.4021508694 0.0970295742 0.3477959037 246 9.8000000000 0.8151637912 0.2927019251 0.8151637912 0.0078832759 0.5576320000 312834412 0 1218949120 0.4023531675 0.0987030119 0.3522112966 247 9.8400000000 0.8268701434 0.2948645495 0.8268701434 0.0079419345 0.1753070000 316493514 0 1222893568 0.3934002817 0.0986131728 0.3567458689 248 9.8800000000 0.8317147493 0.2970292680 0.8317147493 0.0079354593 0.1434130000 319686864 0 1226702848 0.3930487335 0.1003147289 0.3605766296 249 9.9200000000 0.8374407887 0.2991995954 0.8374407887 0.0079257247 0.1218550000 319688118 0 1227464704 0.3930448592 0.1011471897 0.3648204505 250 9.9600000000 0.8429034948 0.3013744110 0.8429034948 0.0079169932 0.1197210000 319689372 0 1228099584 0.3927616775 0.1022244394 0.3690593839 251 10.0000000000 0.8472291231 0.3035491310 0.8472291231 0.0079081942 0.1130660000 319690626 0 1228607488 0.3922026753 0.1026799679 0.3724357486 252 10.0400000000 0.8521206379 0.3057260020 0.8521206379 0.0078966998 0.1142290000 319691880 0 1229242368 0.3919911981 0.1035888791 0.3761203289 253 10.0800000000 0.8567885756 0.3079041150 0.8567885756 0.0078861219 0.1139820000 319693134 0 1229750272 0.3916557729 0.1045727283 0.3798203766 254 10.1200000000 0.8615351915 0.3100837649 0.8615351915 0.0078746968 0.1115290000 319694388 0 1230385152 0.3913088441 0.1056780368 0.3834460080 255 10.1600000000 0.8657802939 0.3122629670 0.8657802939 0.0078629541 0.1142550000 319695642 0 1230893056 0.3907535672 0.1066830233 0.3869082034 256 10.2000000000 0.8692034483 0.3144385157 0.8692034483 0.0078601717 0.1416250000 319696896 0 1231400960 0.3901650310 0.1069468483 0.3896319866 257 10.2400000000 0.8732532859 0.3166128923 0.8732532859 0.0078650749 0.1297390000 319719654 0 1232035840 0.3894616067 0.1078333259 0.3929902315 258 10.2800000000 0.8779990673 0.3187888077 0.8779990673 0.0078652895 0.1218330000 319762892 0 1232543744 0.3890294135 0.1092550233 0.3969357312 259 10.3200000000 0.8817980886 0.3209625887 0.8817980886 0.0078694825 0.1425010000 319764146 0 1233178624 0.3885051608 0.1097113118 0.3998478055 260 10.3600000000 0.8845775723 0.3231303386 0.8845775723 0.0078639061 0.1408890000 319765400 0 1233686528 0.3872780800 0.1106189340 0.4027958810 261 10.4000000000 0.8889652491 0.3252982885 0.8889652491 0.0078563552 0.1278360000 319766654 0 1234194432 0.3864506781 0.1116193458 0.4064587951 262 10.4400000000 0.8939126730 0.3274685724 0.8939126730 0.0078475848 0.1370010000 319767908 0 1234702336 0.3863872886 0.1123485565 0.4099728167 263 10.4800000000 0.8982131481 0.3296387038 0.8982131481 0.0078359573 0.1439300000 319769162 0 1235337216 0.3861494362 0.1135119721 0.4138163030 264 10.5200000000 0.9017545581 0.3318058093 0.9017545581 0.0078284559 0.6585630000 332078960 0 1248415744 0.3848164082 0.1138956547 0.4168703556 265 10.5600000000 0.9058960080 0.3339721875 0.9058960080 0.0078297660 0.1837920000 335738062 0 1252478976 0.3797853589 0.1126970053 0.4221573472 266 10.6000000000 0.9105395675 0.3361397340 0.9105395675 0.0078212569 0.1448710000 338931412 0 1256161280 0.3796378672 0.1132477522 0.4254981577 267 10.6400000000 0.9145209789 0.3383059559 0.9145209789 0.0078115924 0.1388060000 338932666 0 1256923136 0.3791327178 0.1141113043 0.4287814200 268 10.6800000000 0.9187290668 0.3404717138 0.9187290668 0.0078033746 0.1311280000 338933920 0 1257558016 0.3785457313 0.1151153073 0.4324266016 269 10.7200000000 0.9228248596 0.3426365953 0.9228248596 0.0077950352 0.1225020000 338935174 0 1258065920 0.3773592710 0.1157166734 0.4359586835 270 10.7600000000 0.9265984893 0.3447994172 0.9265984893 0.0077850368 0.1350820000 338936428 0 1258573824 0.3765250742 0.1169482395 0.4394284785 271 10.8000000000 0.9308834672 0.3469620889 0.9308834672 0.0077752060 0.1225580000 338937682 0 1259208704 0.3754815757 0.1179953516 0.4431793392 272 10.8400000000 0.9346867800 0.3491228415 0.9346867800 0.0077655190 0.1175540000 338938936 0 1259716608 0.3740350306 0.1189746782 0.4466156960 273 10.8800000000 0.9378597140 0.3512793868 0.9378597140 0.0077584198 0.1259250000 338940190 0 1260224512 0.3723207414 0.1193120405 0.4499736428 274 10.9200000000 0.9426268935 0.3534375894 0.9426268935 0.0077514736 0.1323800000 338941444 0 1260732416 0.3715507388 0.1203545108 0.4539382756 275 10.9600000000 0.9466356635 0.3555946733 0.9466356635 0.0077469342 0.1234640000 338942698 0 1261367296 0.3703964353 0.1222054511 0.4576471448 276 11.0000000000 0.9494445324 0.3577463032 0.9494445324 0.0077449464 0.1300850000 338943952 0 1261875200 0.3684273958 0.1221089438 0.4605930150 277 11.0400000000 0.9550879002 0.3599027711 0.9550879002 0.0077461523 0.6705100000 351253586 0 1275080704 0.3680556118 0.1231910586 0.4649813175 278 11.0800000000 0.9591282606 0.3620582584 0.9591282606 0.0077568132 0.2247880000 354912688 0 1279143936 0.3655512035 0.1226266995 0.4672151208 279 11.1200000000 0.9620295763 0.3642086933 0.9620295763 0.0077490756 0.1543780000 358106038 0 1282953216 0.3634556532 0.1229874417 0.4708876014 280 11.1600000000 0.9668336511 0.3663609253 0.9668336511 0.0077437221 0.1440020000 358107292 0 1283715072 0.3622334898 0.1243535429 0.4750201404 281 11.2000000000 0.9710839987 0.3685129647 0.9710839987 0.0077403942 0.1471670000 358108546 0 1284349952 0.3614231348 0.1260146648 0.4786018133 282 11.2400000000 0.9743227363 0.3706612263 0.9743227363 0.0077383091 0.1311680000 358109800 0 1284857856 0.3599781692 0.1267218590 0.4819687009 283 11.2800000000 0.9784792662 0.3728089932 0.9784792662 0.0077438827 0.1334740000 358111054 0 1285492736 0.3584678471 0.1281047314 0.4855413437 284 11.3200000000 0.9828648567 0.3749570772 0.9828648567 0.0077547236 0.1309050000 358112308 0 1286000640 0.3561477959 0.1289952993 0.4895971715 285 11.3600000000 0.9857973456 0.3771003764 0.9857973456 0.0077500178 0.1280940000 358113562 0 1286508544 0.3542934358 0.1294263154 0.4929333925 286 11.4000000000 0.9922077060 0.3792511013 0.9922077060 0.0077556831 0.1318670000 358114816 0 1287016448 0.3542512953 0.1307313442 0.4969077408 287 11.4400000000 0.9963058829 0.3814011180 0.9963058829 0.0077569173 0.1603640000 358116070 0 1287524352 0.3532996178 0.1319551021 0.5002007484 288 11.4800000000 0.9973737597 0.3835399119 0.9973737597 0.0077643882 0.1536040000 358117324 0 1288159232 0.3506135643 0.1327322274 0.5028024316 289 11.5200000000 0.9991244674 0.3856699623 0.9991244674 0.0077641266 0.1574620000 358118578 0 1288667136 0.3482081592 0.1325315982 0.5057034492 290 11.5600000000 1.0029774904 0.3877986089 1.0029774904 0.0077549470 0.1863190000 358119832 0 1289175040 0.3468887210 0.1329860538 0.5090473294 291 11.6000000000 1.0067744255 0.3899256736 1.0067744255 0.0077456920 0.1744620000 358121086 0 1289674752 0.3457919955 0.1341273934 0.5122497678 292 11.6400000000 1.0099308491 0.3920489790 1.0099308491 0.0077361212 0.1776040000 358122340 0 1290182656 0.3445479870 0.1344388872 0.5151150823 293 11.6800000000 1.0129877329 0.3941682239 1.0129877329 0.0077259326 0.1782130000 358123594 0 1290817536 0.3438202739 0.1352627724 0.5175755024 294 11.7200000000 1.0151333809 0.3962803503 1.0151333809 0.0077158792 0.1762960000 358124848 0 1291325440 0.3422255218 0.1350586116 0.5199460983 295 11.7600000000 1.0189262629 0.3983910144 1.0189262629 0.0077103242 0.8201270000 370462210 0 1304403968 0.3415065706 0.1353065521 0.5229574442 296 11.8000000000 1.0247628689 0.4005071355 1.0247628689 0.0077780791 0.2041350000 374121312 0 1308721152 0.3399482071 0.1312313229 0.5239140391 297 11.8400000000 1.0272804499 0.4026174834 1.0272804499 0.0077806539 0.1377740000 377314662 0 1312403456 0.3381677866 0.1313474476 0.5266546607 298 11.8800000000 1.0311028957 0.4047264948 1.0311028957 0.0077843978 0.1267670000 377315916 0 1313165312 0.3368203938 0.1312888563 0.5300491452 299 11.9200000000 1.0349447727 0.4068342482 1.0349447727 0.0077827860 0.1298910000 377317170 0 1313673216 0.3359920979 0.1311004013 0.5330497622 300 11.9600000000 1.0385906696 0.4089401030 1.0385906696 0.0077820675 0.1296240000 377318424 0 1314308096 0.3352024853 0.1307086349 0.5358364582 301 12.0000000000 1.0436943769 0.4110489212 1.0436943769 0.0077835911 0.1245510000 377319678 0 1314816000 0.3346293867 0.1308536381 0.5393595099 302 12.0400000000 1.0483248234 0.4131591063 1.0483248234 0.0077793839 0.1233910000 377320932 0 1315323904 0.3342040777 0.1309317648 0.5425226092 303 12.0800000000 1.0519111156 0.4152671987 1.0519111156 0.0077727334 0.1237670000 377322186 0 1315831808 0.3333620727 0.1305260211 0.5451858640 304 12.1200000000 1.0569745302 0.4173780781 1.0569745302 0.0077726477 0.1222340000 377323440 0 1316466688 0.3328485787 0.1307670325 0.5486648679 305 12.1600000000 1.0620962381 0.4194919081 1.0620962381 0.0077657593 0.5123530000 389631230 0 1329553408 0.3322859108 0.1310783029 0.5522564054 306 12.2000000000 1.0666354895 0.4216067564 1.0666354895 0.0077608589 0.1842660000 393290332 0 1333489664 0.3297158778 0.1315971315 0.5558839440 307 12.2400000000 1.0714001656 0.4237233473 1.0714001656 0.0077601397 0.1370040000 396483682 0 1337298944 0.3290272951 0.1322201192 0.5593997836 308 12.2800000000 1.0765683651 0.4258429740 1.0765683651 0.0077683212 0.1251650000 396484936 0 1337933824 0.3283726275 0.1325484216 0.5630459189 309 12.3200000000 1.0812953711 0.4279641792 1.0812953711 0.0077742292 0.1191440000 396486190 0 1338568704 0.3276613653 0.1327806413 0.5664310455 310 12.3600000000 1.0866528749 0.4300889814 1.0866528749 0.0077924242 0.1233160000 396487444 0 1339076608 0.3271684945 0.1336446106 0.5702388287 311 12.4000000000 1.0921223164 0.4322177060 1.0921223164 0.0078211078 0.1163210000 396488698 0 1339711488 0.3264986873 0.1343661845 0.5741124153 312 12.4400000000 1.0961637497 0.4343457382 1.0961637497 0.0078452355 0.1213320000 396489952 0 1340219392 0.3259967566 0.1338275224 0.5768653750 313 12.4800000000 1.1013382673 0.4364767047 1.1013382673 0.0078542608 0.1195130000 396491206 0 1340727296 0.3254548013 0.1340721846 0.5804519653 314 12.5200000000 1.1061241627 0.4386093399 1.1061241627 0.0078579604 0.1187410000 396492460 0 1341235200 0.3247218430 0.1344413608 0.5838733315 315 12.5600000000 1.1104127169 0.4407420491 1.1104127169 0.0078568304 0.1520890000 396493714 0 1341743104 0.3241158724 0.1347328722 0.5869316459 316 12.6000000000 1.1152949333 0.4428767101 1.1152949333 0.0078513591 0.7249590000 408808648 0 1354694656 0.3242138922 0.1343450993 0.5898079276 317 12.6400000000 1.1212478876 0.4450166823 1.1212478876 0.0078556946 0.1899430000 412469406 0 1358630912 0.3236680329 0.1337455958 0.5922520757 318 12.6800000000 1.1263105869 0.4471591159 1.1263105869 0.0078531654 0.1392730000 415662756 0 1362440192 0.3234488368 0.1343003064 0.5955936313 319 12.7200000000 1.1315367222 0.4493045003 1.1315367222 0.0078466605 0.1257710000 415664010 0 1363202048 0.3223472238 0.1353642941 0.5996098518 320 12.7600000000 1.1361892223 0.4514510150 1.1361892223 0.0078487078 0.1192630000 415665264 0 1363709952 0.3215697408 0.1357170343 0.6027025580 321 12.8000000000 1.1409204006 0.4535988947 1.1409204006 0.0078678727 0.1216220000 415666518 0 1364217856 0.3206159770 0.1363369226 0.6064013839 322 12.8400000000 1.1458073854 0.4557486105 1.1458073854 0.0078899308 0.1219770000 415667772 0 1364725760 0.3200747669 0.1370738596 0.6097651124 323 12.8800000000 1.1501313448 0.4578984023 1.1501313448 0.0079253311 0.1209270000 415669026 0 1365360640 0.3195261359 0.1374444962 0.6126700640 324 12.9200000000 1.1537430286 0.4600460709 1.1537430286 0.0079558494 0.1221590000 415670280 0 1365868544 0.3189832866 0.1374482512 0.6152647138 325 12.9600000000 1.1578493118 0.4621931578 1.1578493118 0.0079906239 0.8552080000 427982630 0 1378693120 0.3187205195 0.1374458820 0.6178978086 326 13.0000000000 1.1630682945 0.4643430815 1.1630682945 0.0080174836 0.1802280000 431641732 0 1382629376 0.3185032308 0.1370621920 0.6199389100 327 13.0400000000 1.1734340191 0.4665115553 1.1734340191 0.0082079311 0.1393100000 434835082 0 1386438656 0.3168168068 0.1387045681 0.6273192763 328 13.0800000000 1.1774079800 0.4686789225 1.1774079800 0.0082603960 0.1225120000 434836336 0 1387200512 0.3160470128 0.1388926208 0.6302785277 329 13.1200000000 1.1813868284 0.4708452079 1.1813868284 0.0082864423 0.1277530000 434837590 0 1387708416 0.3151894212 0.1391988546 0.6332146525 330 13.1600000000 1.1852345467 0.4730100241 1.1852345467 0.0083121295 0.1225120000 434838844 0 1388208128 0.3146026731 0.1391833872 0.6358963847 331 13.2000000000 1.1889185905 0.4751728899 1.1889185905 0.0083410780 0.1269090000 434840098 0 1388851200 0.3142384887 0.1390435398 0.6383340359 332 13.2400000000 1.1931380033 0.4773354354 1.1931380033 0.0083581014 0.9382890000 447153096 0 1401802752 0.3137047589 0.1394333392 0.6411975622 333 13.2800000000 1.1974200010 0.4794978515 1.1974200010 0.0083741720 0.1729580000 450812198 0 1405865984 0.3130141497 0.1398904473 0.6439389586 334 13.3200000000 1.2006535530 0.4816570003 1.2006535530 0.0084036271 0.1277690000 454005548 0 1409548288 0.3128293455 0.1397762895 0.6462520957 335 13.3600000000 1.2052520514 0.4838169855 1.2052520514 0.0084331718 0.1238200000 454006802 0 1410183168 0.3119315207 0.1406909525 0.6495329142 336 13.4000000000 1.2081681490 0.4859727926 1.2081681490 0.0084732718 0.1308190000 454008056 0 1410818048 0.3110574484 0.1409535706 0.6518801451 337 13.4400000000 1.2106878757 0.4881232824 1.2106878757 0.0085273478 0.1250540000 454009310 0 1411325952 0.3104773760 0.1405820101 0.6536939740 338 13.4800000000 1.2128611803 0.4902674774 1.2128611803 0.0085715147 0.1272210000 454010564 0 1411960832 0.3092621863 0.1405395418 0.6557126045 339 13.5200000000 1.2168543339 0.4924108014 1.2168543339 0.0086116054 1.0546580000 466326890 0 1424785408 0.3085212708 0.1409477443 0.6585215926 340 13.5600000000 1.1986827850 0.4944880720 1.2168543339 0.0086539018 0.1598140000 469985992 0 1428721664 0.3104307950 0.1468158364 0.6806380749 341 13.6000000000 1.2018338442 0.4965623998 1.2168543339 0.0086744526 0.1282740000 473179342 0 1432530944 0.3090384901 0.1472044885 0.6834844947 342 13.6400000000 1.2054955959 0.4986353038 1.2168543339 0.0086903793 0.1307520000 473180596 0 1433165824 0.3076649010 0.1480647624 0.6867286563 343 13.6800000000 1.2092257738 0.5007069962 1.2168543339 0.0087118379 0.1284520000 473181850 0 1433800704 0.3060631752 0.1494120508 0.6901333928 344 13.7200000000 1.2115443945 0.5027733840 1.2168543339 0.0087339489 0.1342050000 473183104 0 1434308608 0.3046654463 0.1501598060 0.6924721599 345 13.7600000000 1.2138489485 0.5048344726 1.2168543339 0.0087660415 0.1212220000 473184358 0 1434816512 0.3040505052 0.1496162117 0.6941193938 346 13.8000000000 1.2153731585 0.5068880526 1.2168543339 0.0087756596 0.8699690000 485500756 0 1447641088 0.3031801581 0.1496975422 0.6957212090 347 13.8400000000 1.2165338993 0.5089331415 1.2168543339 0.0087819813 0.1487710000 489159858 0 1451704320 0.3000983298 0.1503706127 0.6996701360 348 13.8800000000 1.2191028595 0.5109738590 1.2191028595 0.0087929830 0.1242420000 492353208 0 1455386624 0.2984932065 0.1505051404 0.7022983432 349 13.9200000000 1.2216325998 0.5130101305 1.2216325998 0.0087964979 0.1184660000 492354462 0 1456148480 0.2963699698 0.1506645232 0.7052260637 350 13.9600000000 1.2245268822 0.5150430355 1.2245268822 0.0088043574 0.1173900000 492355716 0 1456783360 0.2943264246 0.1510895640 0.7082011104 351 14.0000000000 1.2269308567 0.5170712059 1.2269308567 0.0088062350 0.1138220000 492356970 0 1457291264 0.2924474478 0.1517082602 0.7107324600 352 14.0400000000 1.2277746201 0.5190902497 1.2277746201 0.0088097333 0.1064610000 492358224 0 1457799168 0.2905848026 0.1514291763 0.7120212317 353 14.0800000000 1.2300451994 0.5211042864 1.2300451994 0.0088149475 0.6384610000 504669538 0 1470750720 0.2890568078 0.1508424282 0.7137892246 354 14.1200000000 1.2329410315 0.5231151247 1.2329410315 0.0088192997 0.1573130000 508328640 0 1474686976 0.2872158885 0.1523104906 0.7181837559 355 14.1600000000 1.2344800234 0.5251189695 1.2344800234 0.0088155759 0.1352580000 511521990 0 1478496256 0.2852810919 0.1526258290 0.7201163173 356 14.2000000000 1.2355567217 0.5271145811 1.2355567217 0.0088143421 0.1139960000 511523244 0 1479258112 0.2832046449 0.1526300609 0.7217834592 357 14.2400000000 1.2374563217 0.5291043339 1.2374563217 0.0088064384 0.1135890000 511524498 0 1479766016 0.2806870639 0.1530928463 0.7243018150 358 14.2800000000 1.2394604683 0.5310885689 1.2394604683 0.0087944915 0.1134800000 511525752 0 1480273920 0.2788425684 0.1531023085 0.7263482213 359 14.3200000000 1.2416800261 0.5330679323 1.2416800261 0.0087857730 0.1210150000 511527006 0 1480908800 0.2759993076 0.1544141918 0.7295508981 360 14.3600000000 1.2445194721 0.5350441866 1.2445194721 0.0087753318 0.5613010000 523890128 0 1493733376 0.2711220384 0.1556892693 0.7346540689 361 14.4000000000 1.2468502522 0.5370159485 1.2468502522 0.0087657278 0.1687380000 527549230 0 1497796608 0.2679754198 0.1576311290 0.7388200164 362 14.4400000000 1.2468309402 0.5389767634 1.2468502522 0.0087804655 0.1568570000 530742580 0 1501478912 0.2626615465 0.1574024260 0.7410347462 363 14.4800000000 1.2479475737 0.5409298511 1.2479475737 0.0087695556 0.1363780000 530743834 0 1502240768 0.2607883215 0.1569282115 0.7424077988 364 14.5200000000 1.2499498129 0.5428777081 1.2499498129 0.0087600492 0.1374870000 530745088 0 1502875648 0.2583572567 0.1570793092 0.7446817160 365 14.5600000000 1.2512723207 0.5448185153 1.2512723207 0.0087496438 0.1380020000 530746342 0 1503383552 0.2557048202 0.1571241319 0.7465807796 366 14.6000000000 1.2569527626 0.5467642372 1.2569527626 0.0087557072 0.1394100000 530747596 0 1503891456 0.2505035102 0.1589516550 0.7520986795 367 14.6400000000 1.2579692602 0.5487021256 1.2579692602 0.0087441431 0.7685710000 543064502 0 1516716032 0.2477257699 0.1603167802 0.7543696761 368 14.6800000000 1.2600480318 0.5506351308 1.2600480318 0.0087405599 0.1715000000 546723604 0 1520652288 0.2448071241 0.1594496220 0.7543895245 369 14.7200000000 1.2588589191 0.5525544364 1.2600480318 0.0087420913 0.1422200000 549916954 0 1524461568 0.2422762960 0.1589876711 0.7550083399 370 14.7600000000 1.2579445839 0.5544608963 1.2600480318 0.0087338714 0.1416990000 549918208 0 1525223424 0.2398619801 0.1587386578 0.7557644248 371 14.8000000000 1.2603329420 0.5563635164 1.2603329420 0.0087241592 0.1369180000 549919462 0 1525731328 0.2370208204 0.1593381017 0.7582092881 372 14.8400000000 1.2619147301 0.5582601594 1.2619147301 0.0087125621 0.1385430000 549920716 0 1526239232 0.2343697846 0.1598304063 0.7601599693 373 14.8800000000 1.2628417015 0.5601491180 1.2628417015 0.0087016403 0.1354480000 549921970 0 1526874112 0.2314699441 0.1602274179 0.7619647980 374 14.9200000000 1.2625606060 0.5620272235 1.2628417015 0.0086929490 0.8141920000 562235628 0 1539698688 0.2282656729 0.1607063413 0.7634353638 375 14.9600000000 1.2626895905 0.5638956565 1.2628417015 0.0086838396 0.1706950000 565894730 0 1543761920 0.2240571380 0.1616891176 0.7627917528 376 15.0000000000 1.2644001245 0.5657587003 1.2644001245 0.0086730328 0.1461570000 569088080 0 1547571200 0.2213618457 0.1615916491 0.7646479607 377 15.0400000000 1.2652577162 0.5676141354 1.2652577162 0.0086776622 0.1692630000 569089334 0 1548206080 0.2153571993 0.1620599180 0.7673293352 378 15.0800000000 1.2662547827 0.5694623911 1.2662547827 0.0086674125 0.1752850000 569090588 0 1548840960 0.2128077894 0.1621910781 0.7687367797 379 15.1200000000 1.2670798302 0.5713030703 1.2670798302 0.0086562746 0.1584400000 569091842 0 1549348864 0.2106157392 0.1620686501 0.7695686817 380 15.1600000000 1.2681366205 0.5731368428 1.2681366205 0.0086475970 0.1480110000 569093096 0 1549856768 0.2085758001 0.1616575867 0.7708076835 381 15.2000000000 1.2706174850 0.5749675007 1.2706174850 0.0086461499 0.6657640000 581404630 0 1562681344 0.2063386738 0.1618928611 0.7730515003 382 15.2400000000 1.2683265209 0.5767825766 1.2706174850 0.0086557902 0.1785110000 585063732 0 1566744576 0.2036108971 0.1618266106 0.7747096419 383 15.2800000000 1.2686290741 0.5785889644 1.2706174850 0.0086620294 0.1457060000 588257082 0 1570426880 0.2012591511 0.1618973613 0.7756961584 384 15.3200000000 1.2711701393 0.5803925612 1.2711701393 0.0086717704 0.1482080000 588258336 0 1571188736 0.1988037974 0.1621025652 0.7772138119 385 15.3600000000 1.2719945908 0.5821889301 1.2719945908 0.0086711843 0.1469300000 588259590 0 1571823616 0.1965830475 0.1621247232 0.7780208588 386 15.4000000000 1.2732942104 0.5839793583 1.2732942104 0.0086674537 0.1565470000 588260844 0 1572331520 0.1944893301 0.1621197760 0.7787584066 387 15.4400000000 1.2753177881 0.5857657625 1.2753177881 0.0086735645 0.1331010000 588262098 0 1572839424 0.1926656514 0.1622303277 0.7797821164 388 15.4800000000 1.2771199942 0.5875476033 1.2771199942 0.0086790057 0.1457850000 588263352 0 1573347328 0.1908940673 0.1623743773 0.7808359861 389 15.5200000000 1.2790315151 0.5893251969 1.2790315151 0.0086776958 0.1304410000 588264606 0 1573982208 0.1886799932 0.1626559943 0.7820006013 390 15.5600000000 1.2803819180 0.5910971372 1.2803819180 0.0086857190 0.5661850000 600571088 0 1586806784 0.1864520162 0.1626781970 0.7827427983 391 15.6000000000 1.2822492123 0.5928647896 1.2822492123 0.0086913321 0.1919650000 604230190 0 1590743040 0.1844471097 0.1626606882 0.7834789157 392 15.6400000000 1.2848731279 0.5946301170 1.2848731279 0.0087039477 0.1370870000 607423540 0 1594552320 0.1825677156 0.1627621800 0.7849479318 393 15.6800000000 1.2861546278 0.5963897213 1.2861546278 0.0086979680 0.1537960000 607424794 0 1595187200 0.1806573272 0.1626728028 0.7857232094 394 15.7200000000 1.2877924442 0.5981445506 1.2877924442 0.0086979906 0.1429430000 607426048 0 1595822080 0.1788364053 0.1626998782 0.7866413593 395 15.7600000000 1.2914959192 0.5998998705 1.2914959192 0.0087040136 0.1381540000 607427302 0 1596329984 0.1769237071 0.1627430469 0.7884016037 396 15.8000000000 1.2945075035 0.6016539302 1.2945075035 0.0087028252 0.1418110000 607428556 0 1596837888 0.1748723984 0.1630615294 0.7898814082 397 15.8400000000 1.2956911325 0.6034021347 1.2956911325 0.0086985955 0.1456760000 607429810 0 1597345792 0.1731420010 0.1628610790 0.7905082107 398 15.8800000000 1.3003360033 0.6051532248 1.3003360033 0.0087004038 0.1295890000 607431064 0 1597853696 0.1715272963 0.1627964079 0.7925530672 399 15.9200000000 1.3021467924 0.6069000759 1.3021467924 0.0086956835 0.7716460000 619737918 0 1610678272 0.1693229973 0.1632358134 0.7936521173 400 15.9600000000 1.3039344549 0.6086426618 1.3039344549 0.0086972089 0.1987310000 623397020 0 1614741504 0.1679565459 0.1629125774 0.7945954204 401 16.0000000000 1.3064384460 0.6103828009 1.3064384460 0.0086945231 0.1640210000 626590370 0 1618550784 0.1663040072 0.1626175493 0.7957227826 402 16.0400000000 1.3108983040 0.6121253768 1.3108983040 0.0086973229 0.1532250000 626591624 0 1619185664 0.1645205915 0.1625250429 0.7976003289 403 16.0800000000 1.3147720098 0.6138689168 1.3147720098 0.0086923520 0.1495370000 626592878 0 1619820544 0.1626986116 0.1625488549 0.7993406057 404 16.1200000000 1.3173961639 0.6156103209 1.3173961639 0.0086840172 0.1458500000 626594132 0 1620328448 0.1606495082 0.1624050587 0.8004716039 405 16.1600000000 1.3199294806 0.6173493806 1.3199294806 0.0086797968 0.1421020000 626595386 0 1620836352 0.1590058953 0.1621185839 0.8014966846 406 16.2000000000 1.3256517649 0.6190939677 1.3256517649 0.0086959266 0.1329600000 626596640 0 1621344256 0.1571245044 0.1621773690 0.8038240671 407 16.2400000000 1.3291462660 0.6208385680 1.3291462660 0.0086951394 0.5139030000 638902982 0 1634295808 0.1549205333 0.1625391543 0.8053870797 408 16.2800000000 1.3320508003 0.6225817352 1.3320508003 0.0087041574 0.2116490000 642562084 0 1638359040 0.1534653157 0.1626061201 0.8066632748 409 16.3200000000 1.3366634846 0.6243276563 1.3366634846 0.0087105841 0.1538760000 645755434 0 1642168320 0.1513868570 0.1626605392 0.8084652424 410 16.3600000000 1.3391975164 0.6260712414 1.3391975164 0.0087070140 0.1475000000 645756688 0 1642803200 0.1498526484 0.1626512408 0.8095422983 411 16.3999999990 1.3413136005 0.6278114904 1.3413136005 0.0086982944 0.1670020000 645757942 0 1643438080 0.1480921060 0.1627002060 0.8102990985 412 16.4400000000 1.3449714184 0.6295521699 1.3449714184 0.0086980219 0.1482940000 645759196 0 1643945984 0.1462723762 0.1626146883 0.8115940690 413 16.4800000000 1.3497674465 0.6312960325 1.3497674465 0.0087113292 0.1457130000 645760450 0 1644580864 0.1444638222 0.1628083289 0.8136844635 414 16.5200000000 1.3534861803 0.6330404532 1.3534861803 0.0087187657 0.7099710000 658068036 0 1657405440 0.1424424648 0.1631495804 0.8150440454 415 16.5599999990 1.3572300673 0.6347854884 1.3572300673 0.0087543865 0.3012790000 661727138 0 1661460480 0.1450120360 0.1632779092 0.8175269961 416 16.6000000000 1.3590260744 0.6365264513 1.3590260744 0.0087827531 0.2613460000 664920488 0 1665269760 0.1465074718 0.1636030227 0.8192851543 417 16.6400000000 1.3610589504 0.6382639393 1.3610589504 0.0087978116 0.2325270000 664921742 0 1665904640 0.1456194967 0.1637464464 0.8208004832 418 16.6800000000 1.3662970066 0.6400056452 1.3662970066 0.0088508607 0.2212150000 664922996 0 1666539520 0.1488630921 0.1632470340 0.8239936829 419 16.7199999990 1.3694366217 0.6417465306 1.3694366217 0.0088667188 0.3917580000 664924250 0 1667047424 0.1508933753 0.1614954621 0.8272836208 420 16.7600000000 1.3733644485 0.6434884780 1.3733644485 0.0088975942 0.2330060000 664925504 0 1667555328 0.1522202045 0.1609385312 0.8292202353 421 16.8000000000 1.3767534494 0.6452302001 1.3767534494 0.0089327354 0.9177670000 677232390 0 1680515072 0.1537129581 0.1595555246 0.8309805989 422 16.8400000000 1.3797419071 0.6469707491 1.3797419071 0.0089770298 0.2094420000 680891492 0 1684578304 0.1521098912 0.1599758565 0.8325748444 423 16.8799999990 1.3836265802 0.6487122523 1.3836265802 0.0090218483 0.1191280000 684084842 0 1688260608 0.1505223960 0.1600107849 0.8337796926 424 16.9200000000 1.3892312050 0.6504587592 1.3892312050 0.0091988031 0.1363040000 684086096 0 1689022464 0.1525850743 0.1596965343 0.8377102017 425 16.9600000000 1.3930525780 0.6522060388 1.3930525780 0.0093267075 0.1382870000 684087350 0 1689657344 0.1530341953 0.1578167677 0.8376865983 426 17.0000000000 1.3928335905 0.6539446011 1.3930525780 0.0097724046 0.1529140000 684088604 0 1690165248 0.1567478478 0.1597284824 0.8427324891 427 17.0400000000 1.3972032070 0.6556852536 1.3972032070 0.0101565701 0.1420410000 684089858 0 1690673152 0.1577846110 0.1554324329 0.8435909152 428 17.0800000000 1.3982852697 0.6574203004 1.3982852697 0.0105434747 0.1648040000 684091112 0 1691181056 0.1592237651 0.1592614800 0.8461067080 429 17.1200000000 1.3998790979 0.6591509736 1.3998790979 0.0106944694 0.1460400000 684092366 0 1691815936 0.1610811204 0.1550332457 0.8473911285 430 17.1600000000 1.4021654129 0.6608789141 1.4021654129 0.0108367288 0.1453920000 684093620 0 1692323840 0.1617241055 0.1575196534 0.8482005596 431 17.2000000000 1.4050517082 0.6626055331 1.4050517082 0.0108878825 0.8981120000 696398274 0 1705275392 0.1626546830 0.1557352096 0.8492157459 432 17.2400000000 1.4084850550 0.6643321061 1.4084850550 0.0109238187 0.1662300000 700057376 0 1709211648 0.1586827785 0.1575348824 0.8500745893 433 17.2800000000 1.4117519855 0.6660582490 1.4117519855 0.0109306108 0.1389170000 703250726 0 1713020928 0.1572822630 0.1577839106 0.8507290483 434 17.3200000000 1.4139437675 0.6677814875 1.4139437675 0.0109326199 0.1214240000 703251980 0 1713782784 0.1556041837 0.1580521613 0.8510776162 435 17.3600000000 1.4152228832 0.6694997436 1.4152228832 0.0109401219 0.1148740000 703253234 0 1714290688 0.1540788561 0.1577373892 0.8511269689 436 17.4000000000 1.4175794125 0.6712155227 1.4175794125 0.0109584474 0.1155510000 703254488 0 1714925568 0.1524420381 0.1576812267 0.8515582681 437 17.4400000000 1.4203323126 0.6729297487 1.4203323126 0.0109598807 0.1098470000 703255742 0 1715433472 0.1503794193 0.1579554826 0.8520558476 438 17.4800000000 1.4222345352 0.6746404903 1.4222345352 0.0109645596 0.6303010000 715567536 0 1728258048 0.1487482041 0.1576267481 0.8523463607 439 17.5200000000 1.4239524603 0.6763473512 1.4239524603 0.0110951834 0.1704000000 719226638 0 1732194304 0.1450262070 0.1604262888 0.8525519371 440 17.5600000000 1.4258267879 0.6780507136 1.4258267879 0.0111004286 0.1126440000 722419988 0 1736003584 0.1434603035 0.1603339761 0.8527598977 441 17.6000000000 1.4272909164 0.6797496710 1.4272909164 0.0111029672 0.1099180000 722421242 0 1736638464 0.1417870075 0.1602051556 0.8527829051 442 17.6400000000 1.4284391403 0.6814435386 1.4284391403 0.0111085492 0.1106750000 722422496 0 1737273344 0.1402464062 0.1597468257 0.8527245522 443 17.6800000000 1.4305435419 0.6831345092 1.4305435419 0.0111110449 0.1094070000 722423750 0 1737781248 0.1383931637 0.1599928737 0.8527474403 444 17.7200000000 1.4327183962 0.6848227612 1.4327183962 0.0111107443 0.1031750000 722425004 0 1738416128 0.1366015524 0.1598938257 0.8530039191 445 17.7600000000 1.4342433214 0.6865068524 1.4342433214 0.0111102984 0.7819060000 734729114 0 1751240704 0.1350809634 0.1598896980 0.8531720042 446 17.8000000000 1.4355081320 0.6881862274 1.4355081320 0.0111178651 0.1526020000 738391888 0 1755176960 0.1334145665 0.1597991735 0.8534786105 447 17.8400000000 1.4384230375 0.6898646095 1.4384230375 0.0111234107 0.1073870000 741585238 0 1758859264 0.1314196736 0.1597020328 0.8540753722 448 17.8800000000 1.4408959150 0.6915410187 1.4408959150 0.0111140160 0.1044110000 741586492 0 1759621120 0.1316535920 0.1595603526 0.8537810445 449 17.9200000000 1.4400794506 0.6932081422 1.4408959150 0.0111432665 0.1227550000 741587746 0 1760256000 0.1326466948 0.1596576720 0.8558132052 450 17.9600000000 1.4415673018 0.6948711625 1.4415673018 0.0111373237 0.1188580000 741589000 0 1760763904 0.1309734136 0.1592733711 0.8558712602 451 18.0000000000 1.4441162348 0.6965324598 1.4441162348 0.0111505473 0.1804750000 741590254 0 1761271808 0.1314388961 0.1593197882 0.8578683734 452 18.0400000000 1.4482711554 0.6981955985 1.4482711554 0.0111898840 0.1114060000 741591508 0 1761779712 0.1302865595 0.1579530388 0.8566055894 453 18.0800000000 1.4522866011 0.6998602586 1.4522866011 0.0111930257 0.1124020000 741592762 0 1762287616 0.1309854090 0.1574983746 0.8551373482 454 18.1200000000 1.4599658251 0.7015344999 1.4599658251 0.0112874454 0.2235710000 741594016 0 1762922496 0.1321498305 0.1564369202 0.8516552448 455 18.1600000000 1.4634101391 0.7032089518 1.4634101391 0.0112757554 0.1589640000 741595270 0 1763430400 0.1313225329 0.1562960297 0.8521232009 456 18.2000000000 1.4645580053 0.7048785770 1.4645580053 0.0112686164 0.1241950000 741596524 0 1763938304 0.1316625774 0.1561998576 0.8528932333 457 18.2400000000 1.4682482481 0.7065489701 1.4682482481 0.0112595429 0.1264420000 741597778 0 1764446208 0.1317782551 0.1560821831 0.8524635434 458 18.2800000000 1.4715057611 0.7082191815 1.4715057611 0.0112656869 0.1406260000 741599032 0 1765081088 0.1321493536 0.1556648463 0.8517416716 459 18.3200000000 1.4749832153 0.7098896913 1.4749832153 0.0112713652 0.2612050000 741600286 0 1765588992 0.1324457079 0.1547935158 0.8502591252 460 18.3600000000 1.4796384573 0.7115630582 1.4796384573 0.0113272765 0.1934060000 741601540 0 1766096896 0.1338313669 0.1532929540 0.8480267525 461 18.4000000000 1.4945433140 0.7132614969 1.4945433140 0.0122356549 0.5899500000 753906498 0 1778921472 0.1366089433 0.1482352614 0.8371552229 462 18.4400000000 1.4990364313 0.7149623085 1.4990364313 0.0122481247 0.1267220000 757565600 0 1782984704 0.1358308196 0.1477148980 0.8364545703 463 18.4800000000 1.5049819946 0.7166686145 1.5049819946 0.0124149797 0.1137590000 760758950 0 1786793984 0.1376933903 0.1447716504 0.8323153853 464 18.5200000000 1.5066543818 0.7183711700 1.5066543818 0.0124049048 0.1100170000 760760204 0 1787428864 0.1363043040 0.1442823261 0.8318086863 465 18.5600000000 1.5128551722 0.7200797378 1.5128551722 0.0124431408 0.1095910000 760761458 0 1788063744 0.1366945803 0.1431422532 0.8293474317 466 18.6000000000 1.5198825598 0.7217960529 1.5198825598 0.0125258819 0.1148780000 760762712 0 1786462208 0.1366608739 0.1407452226 0.8259415627 467 18.6400000000 1.5232363939 0.7235121992 1.5232363939 0.0125314953 0.1181770000 760763966 0 1786216448 0.1366303861 0.1400634050 0.8246811032 468 18.6800000000 1.5257766247 0.7252264394 1.5257766247 0.0125405501 0.1142530000 760765220 0 1786310656 0.1372369379 0.1390428096 0.8226150870 469 18.7200000000 1.5321009159 0.7269468541 1.5321009159 0.0126394905 0.1181220000 760766474 0 1786327040 0.1374312490 0.1370354295 0.8195868134 470 18.7600000000 1.5372363329 0.7286708743 1.5372363329 0.0127235542 0.7005010000 773068960 0 1786310656 0.1372897923 0.1344511658 0.8160811067 471 18.8000000000 1.5606240034 0.7304372291 1.5606240034 0.0148683297 0.1124620000 776728062 0 1786310656 0.1334805042 0.1251525134 0.7955416441 472 18.8400000000 1.5616663694 0.7321983078 1.5616663694 0.0148572448 0.1055570000 779921412 0 1787801600 0.1334874481 0.1257961094 0.7963961363 473 18.8800000000 1.5609704256 0.7339504687 1.5616663694 0.0148455431 0.1014610000 779922666 0 1786564608 0.1334563345 0.1250434369 0.7959637642 474 18.9200000000 1.5602560043 0.7356937293 1.5616663694 0.0148425267 0.0996560000 779923920 0 1787199488 0.1323926449 0.1251021028 0.7968405485 475 18.9600000000 1.5617758036 0.7374328495 1.5617758036 0.0148362288 0.0997170000 779925174 0 1787801600 0.1309082955 0.1249003783 0.7970772386 476 19.0000000000 1.5640226603 0.7391693827 1.5640226603 0.0148898491 0.0978050000 779926428 0 1788055552 0.1314760596 0.1272405982 0.7952545881 477 19.0400000000 1.5636187792 0.7408977881 1.5640226603 0.0148825147 0.0976160000 779927682 0 1786667008 0.1310215145 0.1263584495 0.7951875925 478 19.0800000000 1.5726059675 0.7426377634 1.5726059675 0.0149769585 0.0982280000 779928936 0 1787301888 0.1304489523 0.1266016513 0.7925844789 479 19.1200000000 1.5729697943 0.7443712332 1.5729697943 0.0149797502 0.0963020000 779930190 0 1787809792 0.1300941706 0.1267795712 0.7926425338 480 19.1600000000 1.5723042488 0.7460960937 1.5729697943 0.0149843256 0.0956060000 779931444 0 1786445824 0.1304008365 0.1271138489 0.7925066948 481 19.2000000000 1.5729949474 0.7478152181 1.5729949474 0.0150024964 0.0937890000 779932698 0 1786679296 0.1303977519 0.1279070526 0.7931287885 482 19.2400000000 1.5732545853 0.7495277479 1.5732545853 0.0150186027 0.0933740000 779933952 0 1786339328 0.1301346570 0.1282895654 0.7933559418 483 19.2800000000 1.5738698244 0.7512344603 1.5738698244 0.0150244993 0.3530400000 792235710 0 1787555840 0.1289896518 0.1274497658 0.7940759063 484 19.3200000000 1.5820026398 0.7529509235 1.5820026398 0.0153445680 0.0825920000 795894812 0 1787809792 0.1261215657 0.1278300732 0.7860676050 485 19.3600000000 1.5822924376 0.7546609060 1.5822924376 0.0153732973 0.0766320000 799088162 0 1787428864 0.1262641400 0.1276831925 0.7859042287 486 19.4000000000 1.5851659775 0.7563697641 1.5851659775 0.0153863170 0.0735170000 799089416 0 1785925632 0.1264341623 0.1273285747 0.7862703800 487 19.4400000000 1.5879697800 0.7580773617 1.5879697800 0.0154018615 0.0676650000 799090670 0 1786413056 0.1273282915 0.1263684928 0.7858294845 488 19.4800000000 1.5891219378 0.7597803219 1.5891219378 0.0155891149 0.0670020000 799091924 0 1786920960 0.1231006980 0.1278756559 0.7863317728 489 19.5200000000 1.5960097313 0.7614904025 1.5960097313 0.0156304831 0.0708070000 799093178 0 1785438208 0.1231082901 0.1276666671 0.7853093743 490 19.5600000000 1.5970885754 0.7631957049 1.5970885754 0.0156574937 0.0636640000 799094432 0 1786044416 0.1221030578 0.1273490041 0.7852649689 491 19.6000000000 1.6004687548 0.7649009453 1.6004687548 0.0156859651 0.0630620000 799095686 0 1786552320 0.1225564107 0.1276836097 0.7852280140 492 19.6400000000 1.6054834127 0.7666094463 1.6054834127 0.0157362654 0.0627560000 799096940 0 1787060224 0.1223815307 0.1275551617 0.7830950618 493 19.6800000000 1.6057633162 0.7683115839 1.6057633162 0.0157572997 0.0626440000 799098194 0 1787441152 0.1225015968 0.1275954545 0.7829729915 494 19.7200000000 1.6130298376 0.7700215399 1.6130298376 0.0159601959 0.0662010000 799099448 0 1787555840 0.1198612377 0.1291815341 0.7801262140 495 19.7600000000 1.6196838617 0.7717380294 1.6196838617 0.0160230951 0.0592600000 799100702 0 1788063744 0.1195296943 0.1290028095 0.7792679071 496 19.8000000000 1.6249001026 0.7734581143 1.6249001026 0.0160625068 0.0580560000 799101956 0 1786920960 0.1198721230 0.1288319528 0.7786316872 497 19.8400000000 1.6271309853 0.7751757659 1.6271309853 0.0161099177 0.0586110000 799103210 0 1786560512 0.1188724861 0.1288484186 0.7776519656 498 19.8800000000 1.6297663450 0.7768918113 1.6297663450 0.0161423051 0.0616590000 799104464 0 1787174912 0.1194461286 0.1296081245 0.7776560187 499 19.9200000000 1.6344472170 0.7786103592 1.6344472170 0.0161960312 0.3239700000 811403554 0 1787936768 0.1178523153 0.1298489124 0.7771045566 500 19.9600000000 1.6331458092 0.7803194301 1.6344472170 0.0162889098 0.0754630000 815062656 0 1788063744 0.1158105358 0.1302005351 0.7810791135 501 20.0000000000 1.6355041265 0.7820263856 1.6355041265 0.0163265465 0.0651950000 818256006 0 1787969536 0.1156058311 0.1308755279 0.7811201215 502 20.0400000000 1.6387780905 0.7837330623 1.6387780905 0.0163658709 0.0614250000 818257260 0 1786920960 0.1151112765 0.1309826672 0.7810963988 503 20.0800000000 1.6425675154 0.7854404866 1.6425675154 0.0164060510 0.0603570000 818258514 0 1786560512 0.1143167093 0.1313007474 0.7807514668 504 20.1200000000 1.6452559233 0.7871464696 1.6452559233 0.0164446803 0.0583610000 818259768 0 1787174912 0.1137430742 0.1316329688 0.7811914086 505 20.1600000000 1.6477042437 0.7888505444 1.6477042437 0.0164812510 0.0563520000 818261022 0 1786466304 0.1131115034 0.1317555755 0.7812311649 506 20.2000000000 1.6526434422 0.7905576450 1.6526434422 0.0165559287 0.0673600000 818262276 0 1785810944 0.1125781238 0.1312258840 0.7784852982 507 20.2400000000 1.6562495232 0.7922651241 1.6562495232 0.0165856774 0.0584340000 818263530 0 1786314752 0.1126653999 0.1309319735 0.7777168155 508 20.2800000000 1.6605117321 0.7939742709 1.6605117321 0.0166254704 0.0579780000 818264784 0 1785937920 0.1112704873 0.1306522787 0.7770093679 509 20.3200000000 1.6643502712 0.7956842434 1.6643502712 0.0166652563 0.0612330000 818266038 0 1786068992 0.1107915416 0.1301804036 0.7759395838 510 20.3600000000 1.6646596193 0.7973881167 1.6646596193 0.0166964585 0.0559680000 818267292 0 1786564608 0.1108366400 0.1299003810 0.7754346132 511 20.4000000000 1.6668398380 0.7990895878 1.6668398380 0.0167463716 0.0563870000 818268546 0 1785450496 0.1101670489 0.1301552057 0.7752293944 512 20.4400000000 1.6695448160 0.8007896957 1.6695448160 0.0167786686 0.0609640000 818269800 0 1786052608 0.1094325483 0.1301510185 0.7749639750 513 20.4800000000 1.6692596674 0.8024826196 1.6695448160 0.0168025312 0.0586470000 818314062 0 1785307136 0.1094976589 0.1300878525 0.7749951482 514 20.5200000000 1.6715885401 0.8041734871 1.6715885401 0.0168209082 0.0568050000 818399284 0 1784815616 0.1089370698 0.1300015301 0.7748498321 515 20.5600000000 1.6719776392 0.8058585437 1.6719776392 0.0168301402 0.0578560000 818400538 0 1785303040 0.1086783335 0.1301307231 0.7750007510 516 20.6000000000 1.6714516878 0.8075360498 1.6719776392 0.0168353106 0.0578310000 818401792 0 1784668160 0.1085639521 0.1303251237 0.7754747272 517 20.6400000000 1.6705800295 0.8092053805 1.6719776392 0.0168328897 0.0546170000 818403046 0 1785171968 0.1085658744 0.1300709993 0.7754381299 518 20.6800000000 1.6707168818 0.8108685302 1.6719776392 0.0168346799 0.0555690000 818404300 0 1784795136 0.1083551049 0.1299211234 0.7753911018 519 20.7200000000 1.6720854044 0.8125279076 1.6720854044 0.0168326854 0.0567380000 818405554 0 1784152064 0.1077718064 0.1296740323 0.7753874063 520 20.7600000000 1.6725380421 0.8141817732 1.6725380421 0.0168320759 0.0549720000 818406808 0 1784766464 0.1073939875 0.1295364350 0.7754102945 521 20.8000000000 1.6714913845 0.8158272811 1.6725380421 0.0168319610 0.0563250000 818408062 0 1784020992 0.1072799042 0.1294779629 0.7757268548 522 20.8400000000 1.6719738245 0.8174674086 1.6725380421 0.0168316648 0.0550890000 818409316 0 1784635392 0.1067814454 0.1292389482 0.7756367326 523 20.8800000000 1.6662592888 0.8190903376 1.6725380421 0.0168430222 0.0548440000 818410570 0 1784037376 0.1076485962 0.1291724741 0.7764425874 524 20.9200000000 1.6652853489 0.8207052136 1.6725380421 0.0168528038 0.0537650000 818411824 0 1784045568 0.1076174378 0.1287472546 0.7766953111 525 20.9600000000 1.6655395031 0.8223144217 1.6725380421 0.0168525361 0.0532470000 818413078 0 1784520704 0.1069774553 0.1286834329 0.7768708467 526 21.0000000000 1.6628191471 0.8239123395 1.6725380421 0.0168430862 0.0536320000 818414332 0 1783554048 0.1071971878 0.1281811893 0.7772117853 527 21.0400000000 1.6585536003 0.8254960990 1.6725380421 0.0168447305 0.0524810000 818415586 0 1783902208 0.1075609624 0.1279330552 0.7780661583 528 21.0800000000 1.6589863300 0.8270746790 1.6725380421 0.0168453704 0.3686970000 830715584 0 1787936768 0.1068266481 0.1274979115 0.7781856656 529 21.1200000000 1.6521749496 0.8286344148 1.6725380421 0.0169592775 0.0686880000 834374686 0 1786826752 0.1075874940 0.1256559342 0.7843075395 530 21.1600000000 1.6480108500 0.8301804081 1.6725380421 0.0169515086 0.0628710000 837568036 0 1787809792 0.1081608608 0.1251109391 0.7848486900 531 21.2000000000 1.6450110674 0.8317149291 1.6725380421 0.0169468004 0.0576460000 837569290 0 1786826752 0.1080978513 0.1250777692 0.7855362296 532 21.2400000000 1.6437883377 0.8332413829 1.6725380421 0.0169351067 0.0563920000 837570544 0 1786826752 0.1078363135 0.1244721338 0.7857770324 533 21.2800000000 1.6416928768 0.8347581774 1.6725380421 0.0169255988 0.0533550000 837571798 0 1787301888 0.1076998860 0.1241185144 0.7861612439 534 21.3200000000 1.6401094198 0.8362663258 1.6725380421 0.0169213068 0.0539150000 837573052 0 1787936768 0.1073684096 0.1238129511 0.7866489887 535 21.3600000000 1.6405930519 0.8377697403 1.6725380421 0.0169126439 0.0507610000 837574306 0 1786347520 0.1067326665 0.1236303300 0.7867977023 536 21.4000000000 1.6378227472 0.8392623765 1.6725380421 0.0169048086 0.0509610000 837575560 0 1786089472 0.1066429093 0.1231954321 0.7874220014 537 21.4400000000 1.6334601641 0.8407413295 1.6725380421 0.0169014809 0.0522030000 837576814 0 1786089472 0.1067404523 0.1226292849 0.7883623838 538 21.4800000000 1.6302316189 0.8422087836 1.6725380421 0.0168948423 0.0576610000 837578068 0 1785810944 0.1066650227 0.1221046299 0.7891162038 539 21.5200000000 1.6283732653 0.8436673448 1.6725380421 0.0168834334 0.0504740000 837579322 0 1785810944 0.1063774750 0.1217425168 0.7896251082 540 21.5600000000 1.6267212629 0.8451174446 1.6725380421 0.0168717853 0.0504900000 837580576 0 1784942592 0.1061738729 0.1212389544 0.7902092338 541 21.6000000000 1.6257393360 0.8465603687 1.6725380421 0.0168614528 0.0556710000 837581830 0 1784942592 0.1058446169 0.1208334640 0.7906460166 542 21.6400000000 1.6248161793 0.8479962650 1.6725380421 0.0168580286 0.0570680000 837583084 0 1785270272 0.1055357233 0.1204294041 0.7909700274 543 21.6800000000 1.6216222048 0.8494209905 1.6725380421 0.0168628928 0.0537930000 837584338 0 1785778176 0.1055539250 0.1197073907 0.7919394374 544 21.7200000000 1.6113802195 0.8508216508 1.6725380421 0.0169901151 0.0516020000 837585592 0 1786413056 0.1060481369 0.1179195270 0.7941938043 545 21.7600000000 1.6057943106 0.8522069218 1.6725380421 0.0170044065 0.0566920000 837586846 0 1786793984 0.1059970781 0.1172632203 0.7952708602 546 21.8000000000 1.6010172367 0.8535783692 1.6725380421 0.0170081223 0.0522540000 837588100 0 1786920960 0.1058444753 0.1166314632 0.7962526679 547 21.8400000000 1.5969760418 0.8549374143 1.6725380421 0.0170142395 0.2714280000 849888290 0 1786347520 0.1055052578 0.1160252318 0.7968378663 548 21.8800000000 1.5917978287 0.8562820501 1.6725380421 0.0170218854 0.0678420000 853547392 0 1787555840 0.1047252566 0.1166710258 0.7975117564 549 21.9200000000 1.5870522261 0.8576131433 1.6725380421 0.0170224633 0.0599020000 856740742 0 1786826752 0.1050182730 0.1155935898 0.7987985015 550 21.9600000000 1.5837579966 0.8589334067 1.6725380421 0.0170338125 0.0532910000 856741996 0 1787174912 0.1046384797 0.1149057075 0.7991155386 551 22.0000000000 1.5775188208 0.8602375545 1.6725380421 0.0170582712 0.0539610000 856743250 0 1786298368 0.1043266580 0.1142736375 0.8001942039 552 22.0400000000 1.5702546835 0.8615238174 1.6725380421 0.0170859292 0.0541160000 856744504 0 1786298368 0.1039917395 0.1138317809 0.8017395139 553 22.0800000000 1.5654761791 0.8627967873 1.6725380421 0.0170805501 0.0512440000 856745758 0 1786179584 0.1036539823 0.1134275571 0.8024861217 554 22.1200000000 1.5620555878 0.8640589873 1.6725380421 0.0170703410 0.0503850000 856747012 0 1786179584 0.1028905362 0.1132371649 0.8022334576 555 22.1600000000 1.5560004711 0.8653057287 1.6725380421 0.0170717002 0.3691220000 869046810 0 1787936768 0.1020577699 0.1132227927 0.8029711246 556 22.2000000000 1.5487889051 0.8665350150 1.6725380421 0.0172534636 0.0585710000 872705912 0 1786826752 0.0997989699 0.1183510497 0.8049257994 557 22.2400000000 1.5430786610 0.8677496355 1.6725380421 0.0172527023 0.0644800000 875899262 0 1787564032 0.0997667760 0.1173483506 0.8057792783 558 22.2800000000 1.5374908447 0.8689498886 1.6725380421 0.0172548882 0.0568400000 875900516 0 1786572800 0.0991087258 0.1172080413 0.8063097000 559 22.3200000000 1.5319056511 0.8701358560 1.6725380421 0.0172554620 0.0599010000 875901770 0 1786572800 0.0984964818 0.1170882657 0.8065732718 560 22.3600000000 1.5242646933 0.8713039432 1.6725380421 0.0172702864 0.0543900000 875903024 0 1786310656 0.0979061425 0.1172244921 0.8068377972 561 22.4000000000 1.5175404549 0.8724558799 1.6725380421 0.0172796164 0.0502070000 875904278 0 1786310656 0.0974566340 0.1168728620 0.8077390194 562 22.4400000000 1.5151250362 0.8735994194 1.6725380421 0.0172893915 0.0514390000 875905532 0 1786806272 0.0967025757 0.1170634404 0.8071893454 563 22.4800000000 1.5096276999 0.8747291321 1.6725380421 0.0172984536 0.0507920000 875906786 0 1787314176 0.0962026194 0.1170813367 0.8073778152 564 22.5200000000 1.5031988621 0.8758434401 1.6725380421 0.0173018254 0.2558570000 888205260 0 1787801600 0.0957962573 0.1170918569 0.8079040647 565 22.5600000000 1.4921478033 0.8769342443 1.6725380421 0.0173655687 0.0645320000 891864362 0 1786818560 0.0918952897 0.1183603778 0.8060317039 566 22.6000000000 1.4865475893 0.8780112997 1.6725380421 0.0173727998 0.0551930000 895057712 0 1787813888 0.0911739394 0.1183799878 0.8059530854 567 22.6400000000 1.4809070826 0.8790746080 1.6725380421 0.0173629611 0.1193750000 905948470 0 1786834944 0.0911739394 0.1183799878 0.8059530854 568 22.6800000000 1.4747930765 0.8801234081 1.6725380421 0.0173513149 0.1193080000 909295464 0 1785810944 0.0911739394 0.1183799878 0.8059530854 569 22.7200000000 1.4686679840 0.8811577571 1.6725380421 0.0173409874 0.1321580000 909373550 0 1785667584 0.0911739394 0.1183799878 0.8059530854 570 22.7600000000 1.4745756388 0.8821988411 1.6725380421 0.0204754875 0.1194530000 909451636 0 1785671680 0.0961553156 0.1323126256 0.7950268388 571 22.8000000000 1.4678237438 0.8832244539 1.6725380421 0.0204842569 0.1170600000 909529826 0 1786294272 0.0957978964 0.1328715831 0.7954765558 572 22.8400000000 1.4620182514 0.8842363311 1.6725380421 0.0204933164 0.1198250000 912876924 0 1786208256 0.0941561759 0.1339171529 0.7941716909 573 22.8800000000 1.4586191177 0.8852387444 1.6725380421 0.0204821142 0.1248120000 916224022 0 1786597376 0.0941479877 0.1338403672 0.7931072712 574 22.9200000000 1.4540668726 0.8862297341 1.6725380421 0.0204722382 0.1196870000 919571120 0 1786466304 0.0936219543 0.1327780634 0.7922428846 575 22.9600000000 1.4505765438 0.8872112069 1.6725380421 0.0205410995 0.1208980000 922918218 0 1786339328 0.0897222683 0.1281873286 0.7879059315 576 23.0000000000 1.4474430084 0.8881838315 1.6725380421 0.0205318092 0.1197790000 926265316 0 1786068992 0.0882270634 0.1280609965 0.7855538130 577 23.0400000000 1.4439010620 0.8891469463 1.6725380421 0.0205273712 0.1207990000 929612414 0 1786675200 0.0859695375 0.1280093640 0.7822679877 578 23.0800000000 1.4388759136 0.8900980345 1.6725380421 0.0205296873 0.1201230000 932959512 0 1786171392 0.0839847550 0.1285723895 0.7800339460 579 23.1200000000 1.4323776960 0.8910346142 1.6725380421 0.0205391208 0.1231040000 936306610 0 1786433536 0.0820648968 0.1296085566 0.7778300643 580 23.1600000000 1.4276816845 0.8919598678 1.6725380421 0.0205294796 0.1240340000 939654220 0 1786068992 0.0807222724 0.1297680587 0.7754352093 581 23.2000000000 1.4241049290 0.8928757801 1.6725380421 0.0205276950 0.1214470000 943001318 0 1786785792 0.0783749893 0.1301989704 0.7736928463 582 23.2400000000 1.4212430716 0.8937836277 1.6725380421 0.0205267597 0.1226710000 946348416 0 1786044416 0.0761662796 0.1305495054 0.7716657519 583 23.2800000000 1.4169124365 0.8946809327 1.6725380421 0.0205400302 0.1227230000 949695514 0 1786068992 0.0734882727 0.1295216829 0.7693338394 584 23.3200000000 1.4131422043 0.8955687088 1.6725380421 0.0205259566 0.1204850000 953042612 0 1786421248 0.0706825703 0.1298253387 0.7667176723 585 23.3600000000 1.4084336758 0.8964454011 1.6725380421 0.0205151514 0.1309460000 956389606 0 1786208256 0.0706825703 0.1298253387 0.7667176723 586 23.4000000000 1.4037176371 0.8973110533 1.6725380421 0.0205048554 0.1305610000 956467692 0 1785823232 0.0706825703 0.1298253387 0.7667176723 587 23.4400000000 1.4005717039 0.8981683969 1.6725380421 0.0205132715 0.1256220000 956545882 0 1785823232 0.0694520622 0.1305586398 0.7650099993 588 23.4800000000 1.3973958492 0.8990174232 1.6725380421 0.0205011124 0.1318960000 959892980 0 1786810368 0.0700423643 0.1294667870 0.7643486857 589 23.5200000000 1.3925039768 0.8998552611 1.6725380421 0.0204898479 0.1203840000 963239974 0 1786052608 0.0700423643 0.1294667870 0.7643486857 590 23.5600000000 1.3888329268 0.9006840368 1.6725380421 0.0206149237 0.1195430000 963318164 0 1785802752 0.0679410547 0.1297802776 0.7621409893 591 23.6000000000 1.3853732347 0.9015041539 1.6725380421 0.0206067727 0.1212460000 966665262 0 1786200064 0.0672376603 0.1288982183 0.7608728409 592 23.6400000000 1.3802967072 0.9023129251 1.6725380421 0.0205909408 0.1249840000 970012256 0 1786429440 0.0672376603 0.1288982183 0.7608728409 593 23.6800000000 1.3754738569 0.9031108356 1.6725380421 0.0205772662 0.1208390000 970090342 0 1786216448 0.0672376603 0.1288982183 0.7608728409 594 23.7200000000 1.3713563681 0.9038991277 1.6725380421 0.0205725802 0.1272630000 970168428 0 1785692160 0.0672376603 0.1288982183 0.7608728409 595 23.7600000000 1.3671910763 0.9046777697 1.6725380421 0.0205698799 0.1232220000 970246514 0 1785794560 0.0672376603 0.1288982183 0.7608728409 596 23.8000000000 1.3637677431 0.9054480549 1.6725380421 0.0207230868 0.1273130000 970324704 0 1786429440 0.0657919422 0.1294507086 0.7590584159 597 23.8400000000 1.3579936028 0.9062060876 1.6725380421 0.0207084032 0.1160300000 973671698 0 1785573376 0.0657919422 0.1294507086 0.7590584159 598 23.8800000000 1.3543977737 0.9069555720 1.6725380421 0.0207140070 0.1163640000 973749888 0 1785921536 0.0634608120 0.1292695552 0.7576023936 599 23.9200000000 1.3498083353 0.9076948922 1.6725380421 0.0207001921 0.1284900000 977096882 0 1786556416 0.0634608120 0.1292695552 0.7576023936 600 23.9600000000 1.3437420130 0.9084216374 1.6725380421 0.0207316621 0.1146860000 977175072 0 1787318272 0.0606647842 0.1296213567 0.7576223612 601 24.0000000000 1.3387013674 0.9091375770 1.6725380421 0.0207748836 0.1197280000 980522170 0 1786478592 0.0586003810 0.1301786602 0.7574045658 602 24.0400000000 1.3301535845 0.9098369392 1.6725380421 0.0207694217 0.0982370000 983869164 0 1786810368 0.0586003810 0.1301786602 0.7574045658 603 24.0800000000 1.3270397186 0.9105288177 1.6725380421 0.0207587034 0.0945030000 983947250 0 1786179584 0.0586003810 0.1301786602 0.7574045658 604 24.1200000000 1.3243285418 0.9112139166 1.6725380421 0.0207525437 0.0876190000 984025336 0 1785552896 0.0586003810 0.1301786602 0.7574045658 605 24.1600000000 1.3198797703 0.9118893974 1.6725380421 0.0207451922 0.0656190000 984103422 0 1785552896 0.0586003810 0.1301786602 0.7574045658 606 24.2000000000 1.3147503138 0.9125541844 1.6725380421 0.0207346397 0.0806910000 984181508 0 1786159104 0.0586003810 0.1301786602 0.7574045658 607 24.2400000000 1.3102105856 0.9132093020 1.6725380421 0.0207218146 0.0658610000 984259594 0 1786793984 0.0586003810 0.1301786602 0.7574045658 608 24.2800000000 1.3058518171 0.9138550956 1.6725380421 0.0207075906 0.0626640000 984337680 0 1787174912 0.0586003810 0.1301786602 0.7574045658 609 24.3200000000 1.3025379181 0.9144933268 1.6725380421 0.0206938948 0.0856990000 984415766 0 1787555840 0.0586003810 0.1301786602 0.7574045658 610 24.3600000000 1.2976988554 0.9151215326 1.6725380421 0.0206810825 0.0791910000 984493852 0 1786589184 0.0586003810 0.1301786602 0.7574045658 611 24.4000000000 1.2925473452 0.9157392508 1.6725380421 0.0206684829 0.0766930000 984571938 0 1786462208 0.0586003810 0.1301786602 0.7574045658 612 24.4400000000 1.2882560492 0.9163479384 1.6725380421 0.0206561711 0.0615070000 984650024 0 1785683968 0.0586003810 0.1301786602 0.7574045658 613 24.4800000000 1.2839703560 0.9169476487 1.6725380421 0.0206429264 0.0614520000 984728110 0 1785802752 0.0586003810 0.1301786602 0.7574045658 614 24.5200000000 1.2812409401 0.9175409602 1.6725380421 0.0206695475 0.0644750000 984806300 0 1785430016 0.0583987497 0.1293020248 0.7566962242 615 24.5600000000 1.2772988081 0.9181259324 1.6725380421 0.0206782728 0.0662250000 988153398 0 1786343424 0.0583035052 0.1291366071 0.7558414340 616 24.6000000000 1.2737760544 0.9187032864 1.6725380421 0.0207151071 0.0655460000 991500496 0 1787310080 0.0581528991 0.1288554370 0.7549642920 617 24.6400000000 1.2700635195 0.9192727520 1.6725380421 0.0206984690 0.0661360000 994847594 0 1786576896 0.0580005907 0.1289471537 0.7544903755 618 24.6800000000 1.2644852400 0.9198313482 1.6725380421 0.0207491146 0.0656300000 998194692 0 1787199488 0.0576976985 0.1288163960 0.7548139095 619 24.7200000000 1.2599411011 0.9203807986 1.6725380421 0.0207606676 0.0667090000 1001541790 0 1786089472 0.0571560673 0.1291645169 0.7544187307 620 24.7600000000 1.2505409718 0.9209133150 1.6725380421 0.0207551719 0.0711120000 1004888784 0 1787183104 0.0571560673 0.1291645169 0.7544187307 621 24.8000000000 1.2655159235 0.9214682306 1.6725380421 0.0374797463 0.0951160000 1004966870 0 1786183680 0.1221393794 0.1412643641 0.7758070230 622 24.8400000000 1.2951292992 0.9220689719 1.6725380421 0.0401678790 0.1189090000 997595564 0 1783922688 0.1404277533 0.1723900735 0.7449854016 623 24.8800000000 1.2357207537 0.9225724258 1.6725380421 0.0445184016 0.1687530000 1005123270 0 1783922688 0.1487289816 0.1663560420 0.8237215281 624 24.9200000000 1.2388647795 0.9230793046 1.6725380421 0.0444831992 0.2038730000 997577984 0 1787183104 0.1531504691 0.1644384712 0.8187776804 625 24.9600000000 1.2470463514 0.9235976518 1.6725380421 0.0444504472 0.2062010000 1001096938 0 1783779328 0.1608198434 0.1620022506 0.8089535236 626 25.0000000000 1.2436360121 0.9241088952 1.6725380421 0.0444152112 0.0568860000 1008471020 0 1783775232 0.1608198434 0.1620022506 0.8089535236 627 25.0400000000 1.2213406563 0.9245829491 1.6725380421 0.0448057915 0.1776820000 1008472294 0 1784262656 0.1534197778 0.1752922088 0.8259533048 628 25.0800000000 1.2213500738 0.9250555082 1.6725380421 0.0448136651 0.2498260000 997582980 0 1784770560 0.1563306898 0.1783055216 0.8233126402 629 25.1200000000 1.2221339941 0.9255278110 1.6725380421 0.0448524917 0.2276640000 1001102054 0 1783406592 0.1631282121 0.1810345799 0.8224815726 630 25.1600000000 1.2054108381 0.9259720698 1.6725380421 0.0448422386 0.1785020000 1008476136 0 1783394304 0.1515917331 0.1802075952 0.8286762834 631 25.2000000000 1.2040427923 0.9264127524 1.6725380421 0.0449192024 0.2309670000 1002502198 0 1786691584 0.1551677585 0.1858964562 0.8267601728 632 25.2400000000 1.1939052343 0.9268360000 1.6725380421 0.0449145211 0.1561390000 1013394000 0 1786707968 0.1507496536 0.1822439134 0.8308200836 633 25.2800000000 1.1934336424 0.9272571653 1.6725380421 0.0450178462 0.2308030000 1007420126 0 1786208256 0.1536445767 0.1883101314 0.8284050822 634 25.3200000000 1.1885867119 0.9276693570 1.6725380421 0.0461737703 0.1488640000 1018311968 0 1786208256 0.1458376199 0.1681275815 0.8212900162 635 25.3600000000 1.1825910807 0.9280708085 1.6725380421 0.0461507660 0.2124070000 1007422746 0 1786691584 0.1450386792 0.1696943790 0.8212468624 636 25.4000000000 1.1781232357 0.9284639727 1.6725380421 0.0461178269 0.2123720000 1007424000 0 1787183104 0.1426918358 0.1713004857 0.8206092715 637 25.4400000000 1.1733652353 0.9288484331 1.6725380421 0.0461027916 0.2140610000 1007425254 0 1787691008 0.1413966417 0.1738831401 0.8214671016 638 25.4800000000 1.1659489870 0.9292200641 1.6725380421 0.0461015620 0.2202950000 1007426512 0 1788071936 0.1397994012 0.1781227142 0.8210491538 639 25.5200000000 1.1599707603 0.9295811763 1.6725380421 0.0460762003 0.2224000000 1007427766 0 1786724352 0.1383261383 0.1801241934 0.8214967251 640 25.5600000000 1.1534838676 0.9299310242 1.6725380421 0.0460541234 0.2158950000 1010947100 0 1784938496 0.1372018158 0.1819602102 0.8221605420 641 25.6000000000 1.1464446783 0.9302687991 1.6725380421 0.0460208251 0.0724480000 1007429934 0 1784938496 0.1358334869 0.1820298284 0.8229973316 642 25.6400000000 1.1395043135 0.9305947111 1.6725380421 0.0459880124 0.0824420000 1007431188 0 1785405440 0.1345389932 0.1819621325 0.8240200877 643 25.6800000000 1.1317487955 0.9309075479 1.6725380421 0.0459579335 0.0863370000 1007432442 0 1785913344 0.1327899992 0.1820771992 0.8255345821 644 25.7200000000 1.1255173683 0.9312097371 1.6725380421 0.0459248904 0.0951630000 1007433696 0 1786421248 0.1313782930 0.1819929034 0.8267486691 645 25.7600000000 1.1208121777 0.9315036943 1.6725380421 0.0458908211 0.0959300000 1007434950 0 1786929152 0.1304695606 0.1818238050 0.8273717165 646 25.8000000000 1.1134288311 0.9317853122 1.6725380421 0.0458591708 0.0981690000 1007436204 0 1787437056 0.1287715733 0.1819617748 0.8287113905 647 25.8400000000 1.1063002348 0.9320550416 1.6725380421 0.0458281659 0.0892420000 1007437458 0 1787437056 0.1271665394 0.1823906451 0.8299612403 648 25.8800000000 1.0995426178 0.9323135101 1.6725380421 0.0457962968 0.0846760000 1007438712 0 1787944960 0.1258142143 0.1825597435 0.8308548927 649 25.9200000000 1.0937938690 0.9325623242 1.6725380421 0.0457639694 0.0769600000 1007439966 0 1786687488 0.1242539436 0.1828499734 0.8322758675 650 25.9600000000 1.0880918503 0.9328016004 1.6725380421 0.0457316267 0.0908310000 1007441220 0 1786597376 0.1227316856 0.1827102751 0.8334801197 651 26.0000000000 1.0819904804 0.9330307692 1.6725380421 0.0457016536 0.1413700000 1007442474 0 1786597376 0.1210660934 0.1823520511 0.8349068761 652 26.0400000000 1.0751498938 0.9332487433 1.6725380421 0.0456727672 0.1088790000 1007443728 0 1787056128 0.1193425059 0.1826256365 0.8363099098 653 26.0800000000 1.0704983473 0.9334589265 1.6725380421 0.0456417592 0.0895120000 1007444982 0 1787564032 0.1180950701 0.1826989055 0.8373192549 654 26.1200000000 1.0653558969 0.9336606038 1.6725380421 0.0456120242 0.0907890000 1007446236 0 1787944960 0.1166665703 0.1827700436 0.8384236693 655 26.1600000000 1.0603452921 0.9338540155 1.6725380421 0.0455824638 0.0878820000 1007447490 0 1788071936 0.1152058616 0.1826986521 0.8396099210 656 26.2000000000 1.0564676523 0.9340409265 1.6725380421 0.0455496695 0.0959960000 1007448744 0 1786429440 0.1140172854 0.1825565994 0.8405454755 657 26.2400000000 1.0535626411 0.9342228470 1.6725380421 0.0455174981 0.4469320000 1011146374 0 1787572224 0.1129127666 0.1823599190 0.8413610458 658 26.2800000000 1.0501303673 0.9343989982 1.6725380421 0.0454912023 0.0933660000 1011147732 0 1786454016 0.1136233956 0.1781217456 0.8434327245 659 26.3200000000 1.0462399721 0.9345687114 1.6725380421 0.0454587821 0.0968270000 1011148986 0 1786421248 0.1122285500 0.1781315804 0.8444432616 660 26.3600000000 1.0420980453 0.9347316346 1.6725380421 0.0454260660 0.0887820000 1011150240 0 1786802176 0.1110488251 0.1781007946 0.8451693654 661 26.4000000000 1.0382819176 0.9348882916 1.6725380421 0.0453932942 0.0912780000 1011151494 0 1787437056 0.1096424833 0.1781399846 0.8460868597 662 26.4400000000 1.0355371237 0.9350403291 1.6725380421 0.0453600842 0.1328910000 1011152748 0 1787817984 0.1082824916 0.1778825372 0.8470626473 663 26.4800000000 1.0322353840 0.9351869280 1.6725380421 0.0453276592 0.1590160000 1011154002 0 1787928576 0.1068409234 0.1777054965 0.8480790854 664 26.5200000000 1.0292054415 0.9353285221 1.6725380421 0.0452955601 0.1317830000 1011155256 0 1786302464 0.1056668535 0.1775574982 0.8488135934 665 26.5600000000 1.0224679708 0.9354595589 1.6725380421 0.0452726555 0.0927650000 1011156510 0 1786531840 0.1026921570 0.1780993342 0.8510158062 666 26.6000000000 1.0197311640 0.9355860929 1.6725380421 0.0452409533 0.0976760000 1011157764 0 1787039744 0.1013801396 0.1783721596 0.8518064022 667 26.6400000000 1.0162230730 0.9357069879 1.6725380421 0.0452096428 0.0918840000 1011159018 0 1787682816 0.0999040380 0.1785580665 0.8528262377 668 26.6800000000 1.0147802830 0.9358253611 1.6725380421 0.0451778653 0.0933170000 1011160272 0 1786089472 0.0988843367 0.1786793470 0.8534289598 669 26.7200000000 1.0117079020 0.9359387879 1.6725380421 0.0451475530 0.0905910000 1011161526 0 1786089472 0.0976604894 0.1788547188 0.8541263342 670 26.7600000000 1.0083768368 0.9360469044 1.6725380421 0.0451166517 0.0985620000 1011162780 0 1786564608 0.0963697433 0.1792895347 0.8548741341 671 26.8000000000 1.0071448088 0.9361528625 1.6725380421 0.0450855931 0.1201640000 1011164034 0 1787072512 0.0948601067 0.1793175489 0.8560501933 672 26.8400000000 1.0063199997 0.9362572779 1.6725380421 0.0450535473 0.1102760000 1011165288 0 1787453440 0.0937762335 0.1792815328 0.8566829562 673 26.8800000000 1.0046999454 0.9363589758 1.6725380421 0.0450232405 0.1110970000 1011166542 0 1787555840 0.0928377733 0.1789868921 0.8570774794 674 26.9200000000 1.0004131794 0.9364540117 1.6725380421 0.0449953546 0.1029160000 1011167796 0 1788063744 0.0914980918 0.1791998595 0.8578895926 675 26.9600000000 0.9968473911 0.9365434833 1.6725380421 0.0449665891 0.4372810000 1014865942 0 1787310080 0.0902556852 0.1791422367 0.8585174084 676 27.0000000000 0.9952958822 0.9366303952 1.6725380421 0.0449355554 0.1144670000 1014867300 0 1785942016 0.0892260969 0.1788102537 0.8593203425 677 27.0400000000 0.9951906204 0.9367168948 1.6725380421 0.0449038002 0.1181360000 1014868554 0 1785942016 0.0890656561 0.1785375923 0.8592952490 678 27.0800000000 0.9943481088 0.9368018966 1.6725380421 0.0448724866 0.1095080000 1014869808 0 1786290176 0.0882690996 0.1785120815 0.8597326875 679 27.1200000000 0.9936538935 0.9368856256 1.6725380421 0.0448437289 0.1060890000 1014871062 0 1786925056 0.0876883864 0.1783673912 0.8600463271 680 27.1600000000 0.9935283065 0.9369689236 1.6725380421 0.0448133504 0.1465480000 1014872316 0 1787305984 0.0871803537 0.1783079356 0.8602268100 681 27.2000000000 0.9931641221 0.9370514423 1.6725380421 0.0447820949 0.1011600000 1014873570 0 1787305984 0.0865384713 0.1781888604 0.8606256247 682 27.2400000000 0.9931985140 0.9371337694 1.6725380421 0.0447500982 0.1079320000 1014874824 0 1787936768 0.0855210274 0.1782863587 0.8611326814 683 27.2800000000 0.9946372509 0.9372179619 1.6725380421 0.0447185784 0.1187500000 1014876078 0 1786716160 0.0844977126 0.1783840656 0.8617046475 684 27.3200000000 0.9927175641 0.9372991016 1.6725380421 0.0446895873 0.1120470000 1014877332 0 1786937344 0.0836831257 0.1782321334 0.8621621728 685 27.3600000000 0.9911341071 0.9373776929 1.6725380421 0.0446580279 0.0985730000 1014878586 0 1787445248 0.0835642368 0.1779909432 0.8620199561 686 27.4000000000 0.9938337207 0.9374599903 1.6725380421 0.0446263622 0.1036180000 1014879840 0 1787953152 0.0829786286 0.1778857261 0.8623332977 687 27.4400000000 0.9956754446 0.9375447290 1.6725380421 0.0445951770 0.1108640000 1014881094 0 1788080128 0.0828606561 0.1775521189 0.8623246551 688 27.4800000000 0.9959918857 0.9376296812 1.6725380421 0.0445639740 0.1033670000 1014882348 0 1786716160 0.0824093446 0.1774723530 0.8625196218 689 27.5200000000 0.9980958104 0.9377174405 1.6725380421 0.0445343900 0.1313710000 1014883602 0 1786937344 0.0812729448 0.1775703430 0.8631264567 690 27.5600000000 0.9979720116 0.9378047659 1.6725380421 0.0445022796 0.1066750000 1014884856 0 1787445248 0.0817803815 0.1771150082 0.8626887202 691 27.6000000000 0.9983880520 0.9378924407 1.6725380421 0.0444706219 0.1101590000 1014886110 0 1787936768 0.0815704167 0.1769243181 0.8627091646 692 27.6400000000 0.9997281432 0.9379817987 1.6725380421 0.0444397420 0.0990540000 1014887364 0 1788063744 0.0816810131 0.1766103953 0.8625802398 693 27.6800000000 1.0005174875 0.9380720378 1.6725380421 0.0444117951 0.0996280000 1014888618 0 1786200064 0.0814657658 0.1763730198 0.8625401855 694 27.7200000000 1.0014848709 0.9381634107 1.6725380421 0.0443830117 0.1038820000 1014889872 0 1786429440 0.0814996809 0.1760456562 0.8622750640 695 27.7600000000 1.0030363798 0.9382567531 1.6725380421 0.0443566712 0.1701840000 1014891126 0 1787064320 0.0813947096 0.1756160408 0.8613864183 696 27.8000000000 1.0044362545 0.9383518386 1.6725380421 0.0443287237 0.1188070000 1014892380 0 1787572224 0.0811673105 0.1752087325 0.8612490892 697 27.8400000000 1.0072748661 0.9384507239 1.6725380421 0.0443071882 0.1284900000 1014893634 0 1788080128 0.0804612413 0.1745153964 0.8609160781 698 27.8800000000 1.0062232018 0.9385478191 1.6725380421 0.0442791271 0.1485560000 1014894888 0 1788080128 0.0793572292 0.1743618250 0.8608282804 699 27.9200000000 1.0082403421 0.9386475223 1.6725380421 0.0442485883 0.1026360000 1014896142 0 1786667008 0.0787317902 0.1745190322 0.8610348105 700 27.9600000000 1.0081391335 0.9387467960 1.6725380421 0.0442237135 0.1128200000 1014897396 0 1787047936 0.0777097642 0.1742598414 0.8607920408 701 28.0000000000 1.0052248240 0.9388416292 1.6725380421 0.0441971559 0.1258410000 1014898650 0 1787555840 0.0762730688 0.1739475876 0.8607037663 702 28.0400000000 1.0052858591 0.9389362791 1.6725380421 0.0441712439 0.1083230000 1014899904 0 1788063744 0.0759154484 0.1737506986 0.8604817986 703 28.0800000000 1.0086576939 0.9390354561 1.6725380421 0.0441458819 0.1090580000 1014901158 0 1788063744 0.0753436685 0.1734846085 0.8604185581 704 28.1200000000 1.0080457926 0.9391334821 1.6725380421 0.0441200477 0.1131990000 1014902412 0 1786716160 0.0745334625 0.1730138063 0.8598823547 705 28.1600000000 1.0080151558 0.9392311866 1.6725380421 0.0440915599 0.4349430000 1023516734 0 1787953152 0.0729973689 0.1726968437 0.8601494431 706 28.2000000000 1.0081990957 0.9393288749 1.6725380421 0.0440683464 0.1884510000 1023518092 0 1786605568 0.0712502003 0.1727868170 0.8608555794 707 28.2400000000 1.0093946457 0.9394279778 1.6725380421 0.0440383366 0.2605280000 1023519346 0 1786605568 0.0709763914 0.1726442873 0.8602585793 708 28.2800000000 1.0140867233 0.9395334280 1.6725380421 0.0440078249 0.1749920000 1023520600 0 1786953728 0.0710190460 0.1725070775 0.8599304557 709 28.3200000000 1.0159755945 0.9396412449 1.6725380421 0.0439793233 0.1741720000 1023521854 0 1787588608 0.0707276314 0.1722083390 0.8594150543 710 28.3600000000 1.0140790939 0.9397460869 1.6725380421 0.0439501271 0.1509910000 1023523108 0 1787936768 0.0703968853 0.1720898002 0.8587698340 711 28.4000000000 1.0171635151 0.9398549722 1.6725380421 0.0439213477 0.1554510000 1023524362 0 1787936768 0.0703490302 0.1722216457 0.8581585288 712 28.4400000000 1.0188674927 0.9399659448 1.6725380421 0.0438919862 0.1727070000 1023525616 0 1786310656 0.0698967725 0.1721769869 0.8577707410 713 28.4800000000 1.0181102753 0.9400755442 1.6725380421 0.0438640286 0.1614810000 1023526870 0 1786667008 0.0689558089 0.1723535657 0.8573289514 714 28.5200000000 1.0199658871 0.9401874354 1.6725380421 0.0438341825 0.1364100000 1023528124 0 1787174912 0.0680028275 0.1722905040 0.8574056625 715 28.5600000000 1.0237520933 0.9403043091 1.6725380421 0.0438041610 0.1540640000 1023529378 0 1787682816 0.0671893060 0.1721740067 0.8576404452 716 28.6000000000 1.0256630182 0.9404235251 1.6725380421 0.0437745990 0.1630680000 1023530632 0 1786048512 0.0662635267 0.1720752567 0.8575740457 717 28.6400000000 1.0261306763 0.9405430609 1.6725380421 0.0437466145 0.1796640000 1023531886 0 1786048512 0.0662961900 0.1716170460 0.8566311002 718 28.6800000000 1.0284062624 0.9406654331 1.6725380421 0.0437174120 0.1667300000 1023533140 0 1786556416 0.0660433620 0.1715385914 0.8562368155 719 28.7200000000 1.0334086418 0.9407944222 1.6725380421 0.0436883029 0.1689790000 1023534394 0 1787191296 0.0652865991 0.1717741936 0.8561501503 720 28.7600000000 1.0372599363 0.9409284021 1.6725380421 0.0436586011 0.1705620000 1023535648 0 1787445248 0.0644032285 0.1718610078 0.8563098311 721 28.8000000000 1.0383267403 0.9410634899 1.6725380421 0.0436288509 0.1612970000 1023536902 0 1787682816 0.0638446286 0.1718392074 0.8560339212 722 28.8400000000 1.0462650061 0.9412091984 1.6725380421 0.0436001839 0.1768380000 1023538156 0 1786667008 0.0628143400 0.1720377952 0.8569014072 723 28.8800000000 1.0545775890 0.9413660012 1.6725380421 0.0435730310 0.1728080000 1023539410 0 1786667008 0.0622307509 0.1721080393 0.8572450876 724 28.9200000000 1.0597590208 0.9415295274 1.6725380421 0.0435470598 0.1918300000 1023540664 0 1787174912 0.0618242361 0.1720562279 0.8572918773 725 28.9600000000 1.0669294596 0.9417024929 1.6725380421 0.0435203146 0.2196140000 1023541918 0 1787682816 0.0612044744 0.1722204536 0.8575826287 726 29.0000000000 1.0729663372 0.9418832971 1.6725380421 0.0434942228 0.1968210000 1023543172 0 1788063744 0.0604855232 0.1719682962 0.8577220440 727 29.0400000000 1.0883599520 0.9420847780 1.6725380421 0.0434720318 0.1675390000 1023544426 0 1786667008 0.0592425205 0.1719133556 0.8584788442 728 29.0800000000 1.1027767658 0.9423055088 1.6725380421 0.0434475328 0.2289070000 1023545680 0 1786667008 0.0584487505 0.1720360816 0.8589386940 729 29.1200000000 1.1079238653 0.9425326944 1.6725380421 0.0434200061 0.1660880000 1023546934 0 1787174912 0.0576472282 0.1711525768 0.8593720794 730 29.1600000000 1.1131740808 0.9427664498 1.6725380421 0.0433917448 0.1654810000 1023548188 0 1787809792 0.0571162887 0.1710461825 0.8595551252 731 29.2000000000 1.1256028414 0.9430165679 1.6725380421 0.0433641859 0.1736860000 1023549442 0 1788063744 0.0568145253 0.1708839536 0.8591732979 732 29.2400000000 1.1335822344 0.9432769036 1.6725380421 0.0433359199 0.2073910000 1023550696 0 1786667008 0.0558862425 0.1704226434 0.8587878942 733 29.2800000000 1.1401823759 0.9435455331 1.6725380421 0.0433096549 0.1534050000 1023551950 0 1786793984 0.0557233468 0.1699894220 0.8587496281 734 29.3200000000 1.1522414684 0.9438298600 1.6725380421 0.0432896489 0.1970790000 1023553204 0 1787301888 0.0560891405 0.1692120880 0.8581131697 735 29.3600000000 1.1610366106 0.9441253794 1.6725380421 0.0432628825 0.1751290000 1023554458 0 1787809792 0.0564320125 0.1685629487 0.8587197661 736 29.4000000000 1.1664590836 0.9444274632 1.6725380421 0.0432349529 0.1600280000 1023555712 0 1788063744 0.0562805012 0.1683068126 0.8588891029 737 29.4400000000 1.1754605770 0.9447409410 1.6725380421 0.0432069917 0.2071670000 1023556966 0 1786724352 0.0558852255 0.1681071073 0.8586050272 738 29.4800000000 1.1841074228 0.9450652858 1.6725380421 0.0431814415 0.1701070000 1023558220 0 1786802176 0.0558472350 0.1678852737 0.8590019941 739 29.5200000000 1.1863843203 0.9453918339 1.6725380421 0.0431532322 0.1626400000 1023559474 0 1787310080 0.0554351471 0.1678793281 0.8586766124 740 29.5600000000 1.1921206713 0.9457252513 1.6725380421 0.0431251107 0.1753490000 1023560728 0 1787944960 0.0554049686 0.1677736640 0.8584908247 741 29.6000000000 1.1983639002 0.9460661941 1.6725380421 0.0430979479 0.1754750000 1023561982 0 1788071936 0.0551828630 0.1676465869 0.8586789966 742 29.6400000000 1.2038418055 0.9464136006 1.6725380421 0.0430707091 0.1787190000 1023563236 0 1786724352 0.0541101508 0.1675714850 0.8588172793 743 29.6800000000 1.2104916573 0.9467690219 1.6725380421 0.0430452678 0.1624790000 1023564490 0 1786945536 0.0542890765 0.1675639898 0.8587956429 744 29.7200000000 1.2199436426 0.9471361921 1.6725380421 0.0430197012 0.4258600000 1032183808 0 1788088320 0.0541220196 0.1673845798 0.8591414690 745 29.7600000000 1.2249267101 0.9475090653 1.6725380421 0.0429937688 0.1650540000 1032185166 0 1786576896 0.0536920689 0.1675026715 0.8595522642 746 29.8000000000 1.2326951027 0.9478913522 1.6725380421 0.0429698708 0.1771540000 1032186420 0 1786576896 0.0532475039 0.1676309407 0.8600480556 747 29.8400000000 1.2302666903 0.9482693647 1.6725380421 0.0429447588 0.1829010000 1032187674 0 1787072512 0.0532883257 0.1673059314 0.8590057492 748 29.8800000000 1.2295000553 0.9486453416 1.6725380421 0.0429160705 0.1796460000 1032188928 0 1787564032 0.0532009527 0.1670048982 0.8586252332 749 29.9200000000 1.2365584373 0.9490297382 1.6725380421 0.0428879036 0.1695180000 1032190182 0 1788071936 0.0528476536 0.1671997458 0.8587926030 750 29.9600000000 1.2436473370 0.9494225617 1.6725380421 0.0428624588 0.1563930000 1032191436 0 1788071936 0.0524384864 0.1672151238 0.8589783907 751 30.0000000000 1.2468441725 0.9498185958 1.6725380421 0.0428349330 0.1672970000 1032192690 0 1786576896 0.0520327538 0.1671264321 0.8591286540 752 30.0400000000 1.2507750988 0.9502188039 1.6725380421 0.0428067166 0.1611470000 1032193944 0 1786945536 0.0518042333 0.1670859456 0.8593369722 753 30.0800000000 1.2587634325 0.9506285577 1.6725380421 0.0427800598 0.1446850000 1032195198 0 1787453440 0.0514797941 0.1670434475 0.8597869873 754 30.1200000000 1.2596170902 0.9510383569 1.6725380421 0.0427520714 0.1369230000 1032196452 0 1787944960 0.0508855879 0.1667385548 0.8596218824 755 30.1600000000 1.2560719252 0.9514423748 1.6725380421 0.0427239334 0.1462660000 1032197706 0 1788071936 0.0499271601 0.1661417633 0.8595528603 756 30.2000000000 1.2614979744 0.9518525013 1.6725380421 0.0426959894 0.1360430000 1032198960 0 1786576896 0.0499247126 0.1661971360 0.8594810367 757 30.2400000000 1.2663952112 0.9522680134 1.6725380421 0.0426685943 0.1663540000 1032200214 0 1786818560 0.0497417413 0.1662423462 0.8595049381 758 30.2800000000 1.2713959217 0.9526890265 1.6725380421 0.0426421024 0.1495490000 1032201468 0 1787326464 0.0493583456 0.1661932468 0.8595912457 759 30.3200000000 1.2767608166 0.9531159986 1.6725380421 0.0426151822 0.1393340000 1032202722 0 1787834368 0.0489092655 0.1659042388 0.8594976664 760 30.3600000000 1.2753415108 0.9535399795 1.6725380421 0.0425876433 0.1518410000 1032203976 0 1788071936 0.0479607657 0.1655970812 0.8590247035 761 30.4000000000 1.2770853043 0.9539651376 1.6725380421 0.0425597583 0.1488400000 1032205230 0 1786560512 0.0476401784 0.1656203866 0.8590345979 762 30.4400000000 1.2834069729 0.9543974760 1.6725380421 0.0425324496 0.1398310000 1032206484 0 1786675200 0.0472950339 0.1655901968 0.8591378331 763 30.4800000000 1.2869290113 0.9548332971 1.6725380421 0.0425049131 0.1664470000 1032207738 0 1787183104 0.0465641245 0.1652965993 0.8589311838 764 30.5200000000 1.2889782190 0.9552706596 1.6725380421 0.0424773812 0.1541930000 1032208992 0 1787691008 0.0462805629 0.1652840376 0.8586141467 765 30.5600000000 1.2921504974 0.9557110254 1.6725380421 0.0424503744 0.1563180000 1032210246 0 1788071936 0.0456064902 0.1654805392 0.8583465815 766 30.6000000000 1.2890967131 0.9561462548 1.6725380421 0.0424240127 0.1641960000 1032211500 0 1786679296 0.0449499339 0.1654256284 0.8575015068 767 30.6400000000 1.2932816744 0.9565858055 1.6725380421 0.0423967825 0.8660430000 1040832382 0 1786572800 0.0439629406 0.1657595038 0.8572029471 768 30.6800000000 1.2980329990 0.9570303982 1.6725380421 0.0423800783 0.2431040000 1040833740 0 1787047936 0.0433413610 0.1668280363 0.8583472371 769 30.7200000000 1.2927434444 0.9574669561 1.6725380421 0.0423547749 0.1652410000 1040834994 0 1787555840 0.0417064838 0.1660266072 0.8583394289 770 30.7600000000 1.2954231501 0.9579058603 1.6725380421 0.0423276152 0.1531450000 1040836248 0 1787936768 0.0415585190 0.1662313342 0.8573776484 771 30.8000000000 1.2999596596 0.9583495098 1.6725380421 0.0423018713 0.1934120000 1040837502 0 1788063744 0.0413784571 0.1668872684 0.8560329080 772 30.8400000000 1.2962764502 0.9587872390 1.6725380421 0.0422775921 0.1530440000 1040838756 0 1786347520 0.0394536927 0.1667326391 0.8560519814 773 30.8800000000 1.2941825390 0.9592211269 1.6725380421 0.0422527407 0.1485700000 1040840010 0 1786699776 0.0388695709 0.1666462868 0.8549275994 774 30.9200000000 1.2999053001 0.9596612873 1.6725380421 0.0422259613 0.1505320000 1040841264 0 1787301888 0.0377188325 0.1670182794 0.8553014398 775 30.9600000000 1.3061127663 0.9601083215 1.6725380421 0.0421996735 0.1440950000 1040842518 0 1787809792 0.0376265123 0.1668853462 0.8554281592 776 31.0000000000 1.3103998899 0.9605597281 1.6725380421 0.0421730667 0.1609680000 1040843772 0 1787936768 0.0368040800 0.1671283543 0.8558118939 777 31.0400000000 1.3095707893 0.9610089058 1.6725380421 0.0421494808 0.1637960000 1040845026 0 1786347520 0.0348737426 0.1674564481 0.8563448191 778 31.0800000000 1.3139735460 0.9614625879 1.6725380421 0.0421228174 0.7190570000 1049465860 0 1786347520 0.0341690965 0.1676827073 0.8564293385 779 31.1200000000 1.3174387217 0.9619195534 1.6725380421 0.0420961595 0.1841560000 1049467218 0 1786200064 0.0330509655 0.1682375371 0.8566465974 780 31.1600000000 1.3212676048 0.9623802560 1.6725380421 0.0420695407 0.1513770000 1049468472 0 1786200064 0.0320514441 0.1687903404 0.8566346765 781 31.2000000000 1.3205395937 0.9628388467 1.6725380421 0.0420434675 0.1425880000 1049469726 0 1786675200 0.0309118833 0.1689480096 0.8561865687 782 31.2400000000 1.3198677301 0.9632954054 1.6725380421 0.0420177666 0.1480520000 1049470980 0 1787183104 0.0293887891 0.1696485132 0.8561123013 783 31.2800000000 1.3179395199 0.9637483353 1.6725380421 0.0419913177 0.1495480000 1049472234 0 1787555840 0.0286074020 0.1697029024 0.8558071256 784 31.3200000000 1.3218889236 0.9642051473 1.6725380421 0.0419680397 0.1488660000 1049473488 0 1787682816 0.0262482241 0.1705866307 0.8573736548 785 31.3600000000 1.3260301352 0.9646660708 1.6725380421 0.0419419096 0.1408360000 1049474742 0 1786716160 0.0250611827 0.1709633619 0.8581828475 786 31.4000000000 1.3245364428 0.9651239211 1.6725380421 0.0419250321 0.1432200000 1049475996 0 1786716160 0.0223965067 0.1719768196 0.8599587679 787 31.4400000000 1.3242604733 0.9655802573 1.6725380421 0.0419032009 0.8459800000 1058098486 0 1786933248 0.0213304237 0.1735182703 0.8605772257 788 31.4800000000 1.3257317543 0.9660373023 1.6725380421 0.0419232147 0.1599070000 1058099844 0 1785671680 0.0158442855 0.1704811752 0.8680767417 789 31.5200000000 1.3280266523 0.9664960975 1.6725380421 0.0418969212 0.1583020000 1058101098 0 1785671680 0.0147940395 0.1708417088 0.8685134053 790 31.5600000000 1.3283789158 0.9669541770 1.6725380421 0.0418712330 0.1604160000 1058102352 0 1786159104 0.0134447720 0.1715118885 0.8695909381 791 31.6000000000 1.3331570625 0.9674171389 1.6725380421 0.0418472345 0.1388260000 1058103606 0 1786667008 0.0125201577 0.1718653440 0.8700501323 792 31.6400000000 1.3366149664 0.9678832978 1.6725380421 0.0418224597 0.1395060000 1058104860 0 1787047936 0.0123130679 0.1718285531 0.8697562218 793 31.6800000000 1.3349851370 0.9683462257 1.6725380421 0.0417978919 0.1321630000 1058106114 0 1787047936 0.0111691402 0.1727309078 0.8704602122 794 31.7200000000 1.3410769701 0.9688156599 1.6725380421 0.0417723218 0.1240020000 1058107368 0 1787682816 0.0103161884 0.1729821414 0.8707312942 795 31.7600000000 1.3453886509 0.9692893366 1.6725380421 0.0417470110 0.1203780000 1058108622 0 1786716160 0.0098546837 0.1731215715 0.8708714247 796 31.8000000000 1.3445248604 0.9697607380 1.6725380421 0.0417210345 0.1207180000 1058109876 0 1786716160 0.0093153119 0.1731314063 0.8708214164 797 31.8400000000 1.3456552029 0.9702323747 1.6725380421 0.0416956783 0.1289820000 1058111130 0 1787191296 0.0095635839 0.1727670431 0.8700090647 798 31.8800000000 1.3484522104 0.9707063344 1.6725380421 0.0416702365 0.1325080000 1058112384 0 1787699200 0.0093645006 0.1727652699 0.8700098395 799 31.9200000000 1.3557859659 0.9711882864 1.6725380421 0.0416488983 0.1318640000 1058113638 0 1788063744 0.0096147992 0.1724179685 0.8694536090 800 31.9600000000 1.3610452414 0.9716756076 1.6725380421 0.0416248533 0.1332220000 1058114892 0 1786707968 0.0098751383 0.1717507988 0.8692867160 801 32.0000000000 1.3552775383 0.9721545114 1.6725380421 0.0416013502 0.1329660000 1058116146 0 1786707968 0.0106940204 0.1711881459 0.8686798215 802 32.0400000000 1.3589311838 0.9726367766 1.6725380421 0.0415797295 0.1338260000 1058117400 0 1787183104 0.0115581565 0.1707462966 0.8678181767 803 32.0800000000 1.3650801182 0.9731254980 1.6725380421 0.0415552766 0.1234010000 1058118654 0 1787691008 0.0119303018 0.1698750108 0.8674859405 804 32.1199999990 1.3669961691 0.9736153869 1.6725380421 0.0415307426 0.1206680000 1058119908 0 1788071936 0.0116522079 0.1699251831 0.8674367070 805 32.1600000000 1.3704258204 0.9741083192 1.6725380421 0.0415098950 0.1460050000 1058121162 0 1786191872 0.0111950086 0.1702704430 0.8674207926 806 32.2000000000 1.3778492212 0.9746092384 1.6725380421 0.0414861043 0.9539200000 1066739392 0 1786802176 0.0098595405 0.1699374467 0.8674997091 807 32.2400000000 1.3822774887 0.9751144035 1.6725380421 0.0414629929 0.0998590000 1066740750 0 1785540608 0.0097370204 0.1709696054 0.8684896231 808 32.2800000000 1.3891412020 0.9756268129 1.6725380421 0.0414392456 0.1191210000 1066742004 0 1785516032 0.0092750052 0.1709522307 0.8684269190 809 32.3200000000 1.3975623846 0.9761483649 1.6725380421 0.0414174074 0.1102010000 1066743258 0 1786023936 0.0088955415 0.1709570736 0.8685063720 810 32.3600000000 1.4002381563 0.9766719326 1.6725380421 0.0413936199 0.1008490000 1066744512 0 1786658816 0.0086886222 0.1709927917 0.8685421944 811 32.4000000000 1.4074393511 0.9772030884 1.6725380421 0.0413724348 0.1057730000 1066745766 0 1787166720 0.0084354421 0.1709917188 0.8684739470 812 32.4399999990 1.4059348106 0.9777310832 1.6725380421 0.0413526297 0.1121230000 1066747020 0 1787547648 0.0083697271 0.1709930897 0.8684027791 813 32.4800000000 1.4137613773 0.9782674058 1.6725380421 0.0413290582 0.1014920000 1066748274 0 1787682816 0.0076128258 0.1709117442 0.8683387637 814 32.5200000000 1.4290950298 0.9788212481 1.6725380421 0.0413090819 0.1034730000 1066749528 0 1786458112 0.0065357690 0.1711362898 0.8685490489 815 32.5600000000 1.4323248863 0.9793776943 1.6725380421 0.0412865321 0.0900610000 1066750782 0 1786552320 0.0064317859 0.1710505337 0.8686276674 816 32.6000000000 1.4363305569 0.9799376855 1.6725380421 0.0412627655 0.1059430000 1066752036 0 1787060224 0.0062546926 0.1711255461 0.8684843779 817 32.6400000000 1.4442702532 0.9805060240 1.6725380421 0.0412404186 0.1105320000 1066753290 0 1787555840 0.0058807335 0.1710317433 0.8685199022 818 32.6800000000 1.4535596371 0.9810843292 1.6725380421 0.0412183348 0.1054300000 1066754544 0 1787809792 0.0054041939 0.1711537987 0.8686331511 819 32.7200000000 1.4585602283 0.9816673278 1.6725380421 0.0411947524 0.1034900000 1066755798 0 1787936768 0.0053607430 0.1711002439 0.8683660626 820 32.7599999990 1.4625556469 0.9822537770 1.6725380421 0.0411700881 0.1024500000 1066757052 0 1786716160 0.0048140562 0.1711167693 0.8685864806 821 32.7999999990 1.4708731174 0.9828489285 1.6725380421 0.0411462721 0.1165580000 1066758306 0 1786937344 0.0042022644 0.1712935567 0.8687030673 822 32.8400000000 1.4776208401 0.9834508408 1.6725380421 0.0411225058 0.1079580000 1066759560 0 1787572224 0.0039823172 0.1713410467 0.8685112596 823 32.8800000000 1.4830759764 0.9840579187 1.6725380421 0.0410985683 0.1206910000 1066760814 0 1788080128 0.0034356483 0.1713786423 0.8688020706 824 32.9200000000 1.4925159216 0.9846749794 1.6725380421 0.0410756994 0.1106100000 1066762068 0 1788080128 0.0029219326 0.1715682298 0.8687445521 825 32.9600000000 1.4955329895 0.9852942012 1.6725380421 0.0410521035 0.1189220000 1066763322 0 1786716160 0.0027178645 0.1715178937 0.8687492013 826 33.0000000000 1.4977010489 0.9859145485 1.6725380421 0.0410277078 0.1176650000 1066764576 0 1787047936 0.0022851331 0.1716299951 0.8686822057 827 33.0400000000 1.5079804659 0.9865458253 1.6725380421 0.0410052494 0.1164010000 1066765830 0 1787555840 0.0018681283 0.1716686934 0.8686248660 828 33.0800000000 1.5090585947 0.9871768794 1.6725380421 0.0409824252 0.1214540000 1066767084 0 1788063744 0.0017881781 0.1715933383 0.8686337471 829 33.1199999990 1.5120786428 0.9878100540 1.6725380421 0.0409594160 0.1203990000 1066768338 0 1786568704 0.0014212673 0.1717216074 0.8684583306 830 33.1600000000 1.5262951851 0.9884588312 1.6725380421 0.0409399688 0.1185890000 1066769592 0 1786568704 0.0007605085 0.1717964113 0.8686406612 831 33.2000000000 1.5312229395 0.9891119770 1.6725380421 0.0409167017 0.1217790000 1066770846 0 1786937344 0.0003514288 0.1719303727 0.8687833548 832 33.2400000000 1.5298000574 0.9897618425 1.6725380421 0.0408941471 0.1216870000 1066772100 0 1787445248 0.0003219240 0.1718575507 0.8685000539 833 33.2800000000 1.5343778133 0.9904156431 1.6725380421 0.0408713921 0.1229350000 1066773354 0 1788080128 -0.0001954957 0.1718997955 0.8685110807 834 33.3200000000 1.5422059298 0.9910772622 1.6725380421 0.0408495358 0.1236890000 1066774608 0 1788063744 -0.0005675754 0.1719436198 0.8685170412 835 33.3600000000 1.5493679047 0.9917458737 1.6725380421 0.0408267881 0.1225170000 1066775862 0 1786605568 -0.0010694420 0.1720331609 0.8685103059 836 33.4000000000 1.5549976826 0.9924196199 1.6725380421 0.0408034241 0.1271180000 1066777116 0 1786826752 -0.0015984102 0.1721133590 0.8685383797 837 33.4399999990 1.5594632626 0.9930970914 1.6725380421 0.0407800084 0.1249350000 1066778370 0 1787461632 -0.0020028220 0.1721241027 0.8684722185 838 33.4800000000 1.5633187294 0.9937775468 1.6725380421 0.0407564808 0.1286960000 1066779624 0 1787969536 -0.0023954648 0.1721247435 0.8684041500 839 33.5200000000 1.5688873529 0.9944630174 1.6725380421 0.0407327177 0.1254090000 1066780878 0 1787969536 -0.0031155942 0.1722287387 0.8682355881 840 33.5600000000 1.5677280426 0.9951454758 1.6725380421 0.0407094344 0.1274300000 1066782132 0 1786716160 -0.0034525155 0.1721262932 0.8679335713 841 33.6000000000 1.5701969862 0.9958292469 1.6725380421 0.0406864020 0.1271180000 1066783386 0 1786793984 -0.0038562007 0.1721112877 0.8677093983 842 33.6400000000 1.5758491755 0.9965181067 1.6725380421 0.0406643511 0.1279750000 1066784640 0 1787301888 -0.0043936162 0.1720169783 0.8676252365 843 33.6800000000 1.5823560953 0.9972130509 1.6725380421 0.0406468839 0.1196710000 1066785894 0 1787809792 -0.0054669306 0.1719125062 0.8673189282 844 33.7200000000 1.5879207850 0.9979129416 1.6725380421 0.0406234282 0.1285630000 1066787148 0 1788063744 -0.0060433876 0.1720013618 0.8670495749 845 33.7599999990 1.5956767797 0.9986203544 1.6725380421 0.0406000680 0.8089730000 1076633674 0 1785298944 -0.0067403973 0.1721111983 0.8669791222 846 33.7999999990 1.6019341946 0.9993334913 1.6725380421 0.0406169657 0.1815840000 1079092656 0 1785823232 -0.0034709109 0.1689762473 0.8626945615 847 33.8400000000 1.6062538624 1.0000500443 1.6725380421 0.0405960335 0.1735280000 1081551534 0 1784778752 -0.0044083162 0.1691213697 0.8624923825 848 33.8800000000 1.6059904099 1.0007645966 1.6725380421 0.0405738098 0.1548590000 1081552788 0 1784778752 -0.0052448888 0.1691586673 0.8620828390 849 33.9200000000 1.6112035513 1.0014836060 1.6725380421 0.0405513837 0.1451560000 1081554042 0 1785278464 -0.0058078854 0.1690819860 0.8619753122 850 33.9600000000 1.6127227545 1.0022027109 1.6725380421 0.0405288326 0.1607400000 1081555296 0 1785778176 -0.0067445189 0.1691952199 0.8614038229 851 34.0000000000 1.6135380268 1.0029210837 1.6725380421 0.0405056148 0.1440930000 1081556550 0 1786159104 -0.0072994558 0.1689793020 0.8608796000 852 34.0400000000 1.6183747053 1.0036434471 1.6725380421 0.0404828268 0.1448420000 1081557804 0 1786286080 -0.0081699397 0.1690965146 0.8606590629 853 34.0800000000 1.6218988895 1.0043682484 1.6725380421 0.0404595127 0.1385860000 1081559058 0 1786793984 -0.0090166517 0.1690423787 0.8603294492 854 34.1199999990 1.6260946989 1.0050962653 1.6725380421 0.0404360373 0.1339740000 1081560312 0 1787301888 -0.0098027727 0.1692005843 0.8600921035 855 34.1600000000 1.6292577982 1.0058262788 1.6725380421 0.0404126845 0.1495510000 1081561566 0 1787936768 -0.0103543578 0.1690130532 0.8596965671 856 34.2000000000 1.6303350925 1.0065558452 1.6725380421 0.0403900098 0.1360960000 1081562820 0 1786826752 -0.0111268414 0.1689899117 0.8591939211 857 34.2400000000 1.6337473392 1.0072876905 1.6725380421 0.0403666271 0.1435330000 1081564074 0 1787047936 -0.0117557663 0.1689838767 0.8588447571 858 34.2800000000 1.6351903677 1.0080195118 1.6725380421 0.0403434939 0.1512890000 1081565328 0 1787555840 -0.0124230273 0.1690879762 0.8584541082 859 34.3200000000 1.6398218870 1.0087550210 1.6725380421 0.0403206270 1.0076480000 1093873130 0 1786802176 -0.0132248290 0.1690469384 0.8581299186 860 34.3600000000 1.6449069977 1.0094947326 1.6725380421 0.0403012674 0.1738170000 1096331600 0 1786064896 -0.0130662946 0.1669405252 0.8584555387 861 34.4000000000 1.6471863985 1.0102353733 1.6725380421 0.0402781186 0.1379210000 1098795290 0 1786478592 -0.0135955187 0.1668654829 0.8581134081 862 34.4400000000 1.6501380205 1.0109777198 1.6725380421 0.0402549653 0.1366390000 1098796544 0 1786478592 -0.0142382747 0.1669027060 0.8578384519 863 34.4800000000 1.6521772146 1.0117207088 1.6725380421 0.0402316583 0.1273140000 1098797798 0 1786953728 -0.0149227036 0.1669958532 0.8575127125 864 34.5200000000 1.6571679115 1.0124677542 1.6725380421 0.0402086097 0.1317100000 1098799052 0 1787461632 -0.0156963915 0.1670841426 0.8573531508 865 34.5600000000 1.6586421728 1.0132147766 1.6725380421 0.0401857431 0.1369370000 1098800306 0 1787809792 -0.0161305070 0.1670001149 0.8568886518 866 34.6000000000 1.6593630314 1.0139609062 1.6725380421 0.0401638118 0.1300290000 1098801560 0 1787936768 -0.0161712877 0.1668607444 0.8563838601 867 34.6400000000 1.6701905727 1.0147178032 1.6725380421 0.0401494876 2.1038260000 1111210290 0 1785815040 -0.0173155367 0.1668687314 0.8558239937 868 34.6800000000 1.6733355522 1.0154765794 1.6733355522 0.0401273754 0.1368620000 1113678896 0 1786335232 -0.0156212645 0.1665138155 0.8566067815 869 34.7200000000 1.6791467667 1.0162402965 1.6791467667 0.0401064199 0.1335460000 1116142586 0 1786462208 -0.0162594840 0.1666063964 0.8564969301 870 34.7600000000 1.6833550930 1.0170070951 1.6833550930 0.0400845443 0.1225250000 1116143840 0 1786683392 -0.0169776622 0.1666464508 0.8561422825 871 34.8000000000 1.6836286783 1.0177724471 1.6836286783 0.0400627531 0.1197880000 1116145094 0 1787318272 -0.0174501315 0.1666825563 0.8556196094 872 34.8400000000 1.6884754896 1.0185416020 1.6884754896 0.0400416427 0.1289580000 1116146348 0 1787809792 -0.0178778227 0.1665801108 0.8553741574 873 34.8800000000 1.6902394295 1.0193110153 1.6902394295 0.0400206733 0.1166530000 1116147602 0 1787809792 -0.0188944042 0.1668069959 0.8550537825 874 34.9200000000 1.6970592737 1.0200864710 1.6970592737 0.0399990252 0.9936090000 1128455904 0 1787080704 -0.0196004361 0.1669531018 0.8549122214 875 34.9600000000 1.7007766962 1.0208644027 1.7007766962 0.0399768948 0.1534280000 1130924510 0 1785827328 -0.0201966371 0.1672963053 0.8550991416 876 35.0000000000 1.7037149668 1.0216439125 1.7037149668 0.0399542079 0.1169820000 1134002624 0 1786478592 -0.0208232049 0.1673581153 0.8547146916 877 35.0400000000 1.7018043995 1.0224194660 1.7037149668 0.0399322682 0.1084950000 1134003878 0 1786052608 -0.0213001445 0.1673598140 0.8540896177 878 35.0800000000 1.7045711279 1.0231964041 1.7045711279 0.0399101507 0.0990890000 1134005132 0 1786052608 -0.0217201207 0.1673508286 0.8537291288 879 35.1200000000 1.7113602161 1.0239792981 1.7113602161 0.0398883595 0.1111510000 1134006386 0 1786548224 -0.0226060841 0.1674701571 0.8536260128 880 35.1600000000 1.7118281126 1.0247609445 1.7118281126 0.0398659580 0.0977830000 1134007640 0 1787056128 -0.0232492182 0.1674692184 0.8528941870 881 35.2000000000 1.7129361629 1.0255420742 1.7129361629 0.0398434821 0.8147930000 1146316442 0 1786458112 -0.0236920249 0.1675138175 0.8524985313 882 35.2400000000 1.7161961794 1.0263251287 1.7161961794 0.0398210089 0.1157520000 1149706684 0 1786060800 -0.0244985446 0.1678045392 0.8521800041 883 35.2800000000 1.7232114077 1.0271143544 1.7232114077 0.0397995856 0.1095490000 1152784798 0 1787588608 -0.0252226405 0.1678933501 0.8520531058 884 35.3200000000 1.7235742807 1.0279022050 1.7235742807 0.0397772903 0.1056820000 1152786052 0 1785675776 -0.0259347800 0.1679699123 0.8515080214 885 35.3600000000 1.7234318256 1.0286881141 1.7235742807 0.0397552702 0.0903410000 1152787306 0 1785827328 -0.0263008215 0.1678508520 0.8507581353 886 35.4000000000 1.7288058996 1.0294783148 1.7288058996 0.0397342846 0.0896420000 1152788560 0 1786064896 -0.0264949854 0.1677134633 0.8504801393 887 35.4400000000 1.7364279032 1.0302753267 1.7364279032 0.0397129360 0.0985590000 1152789814 0 1785319424 -0.0272728559 0.1677419990 0.8502779007 888 35.4800000000 1.7398937941 1.0310744466 1.7398937941 0.0396909219 0.8466130000 1165100132 0 1787682816 -0.0277896691 0.1676877737 0.8497617841 889 35.5200000000 1.7442512512 1.0318766703 1.7442512512 0.0396696591 0.0936310000 1168490374 0 1787588608 -0.0284285154 0.1678649932 0.8495780230 890 35.5600000000 1.7497277260 1.0326832445 1.7497277260 0.0396490565 0.1058190000 1171568488 0 1787330560 -0.0292479377 0.1679597795 0.8493024111 891 35.6000000000 1.7568408251 1.0334959915 1.7568408251 0.0396277649 0.1064730000 1171569742 0 1786089472 -0.0304173380 0.1682101190 0.8490160108 892 35.6400000000 1.7624568939 1.0343132122 1.7624568939 0.0396064755 0.0963060000 1171570996 0 1786691584 -0.0311540738 0.1682829559 0.8485724926 893 35.6800000000 1.7640846968 1.0351304255 1.7640846968 0.0395853367 0.0897550000 1171572250 0 1787199488 -0.0317324325 0.1682328880 0.8479695916 894 35.7200000000 1.7653341293 1.0359472082 1.7653341293 0.0395657772 0.0885880000 1171573504 0 1787453440 -0.0325180218 0.1683142334 0.8473728299 895 35.7600000000 1.7718242407 1.0367694172 1.7718242407 0.0395452663 0.0857700000 1171574758 0 1787682816 -0.0335365124 0.1685207933 0.8469982147 896 35.8000000000 1.7761399746 1.0375946075 1.7761399746 0.0395239394 0.0841900000 1171576012 0 1786920960 -0.0344373584 0.1687087417 0.8466600776 897 35.8400000000 1.7815293074 1.0384239662 1.7815293074 0.0395024415 0.0896130000 1171577266 0 1786413056 -0.0358159952 0.1691170037 0.8462046981 898 35.8800000000 1.7832385302 1.0392533811 1.7832385302 0.0394807307 4.5255190000 1183885076 0 1786716160 -0.0366421081 0.1692629904 0.8456270695 899 35.9200000000 1.7855128050 1.0400834805 1.7855128050 0.0394608397 0.1088690000 1187275318 0 1785815040 -0.0348718315 0.1690354645 0.8428446651 900 35.9600000000 1.7852128744 1.0409114021 1.7855128050 0.0394400232 0.1035950000 1190391856 0 1786347520 -0.0352352224 0.1688941419 0.8419743180 901 36.0000000000 1.7885613441 1.0417412022 1.7885613441 0.0394220895 0.0882080000 1190393110 0 1785810944 -0.0355715416 0.1688915491 0.8415946960 902 36.0400000000 1.7977845669 1.0425793878 1.7977845669 0.0394050773 0.0858540000 1190394364 0 1785810944 -0.0366488248 0.1689578742 0.8412703276 903 36.0800000000 1.8014646769 1.0434197923 1.8014646769 0.0393862300 0.0836300000 1190395618 0 1786286080 -0.0372965820 0.1689749509 0.8407921195 904 36.1200000000 1.7925747633 1.0442485036 1.8014646769 0.0393694814 0.0837670000 1190396872 0 1786793984 -0.0375747643 0.1689148545 0.8396373391 905 36.1600000000 1.8056801558 1.0450898645 1.8056801558 0.0393653623 1.9277300000 1202704282 0 1787936768 -0.0405008346 0.1691506356 0.8379341364 906 36.2000000000 1.8099189997 1.0459340468 1.8099189997 0.0393450878 0.0879030000 1206132948 0 1786441728 -0.0415312424 0.1692386866 0.8372319341 907 36.2400000000 1.8122768402 1.0467789672 1.8122768402 0.0393255105 0.0808740000 1209249486 0 1787203584 -0.0419734083 0.1691671014 0.8367493749 908 36.2800000000 1.8163552284 1.0476265181 1.8163552284 0.0393081414 0.0758170000 1209250740 0 1785573376 -0.0426114239 0.1692309678 0.8365000486 909 36.3200000000 1.8149354458 1.0484706423 1.8163552284 0.0392887289 0.0841060000 1209251994 0 1785573376 -0.0435324423 0.1694371849 0.8355023861 910 36.3600000000 1.8123444319 1.0493100641 1.8163552284 0.0392679946 0.0844940000 1209253248 0 1786175488 -0.0440289266 0.1694748849 0.8346204162 911 36.4000000000 1.8124496937 1.0501477585 1.8163552284 0.0392484035 0.0812420000 1209254502 0 1786683392 -0.0443555973 0.1693833172 0.8341681957 912 36.4400000000 1.8150429726 1.0509864594 1.8163552284 0.0392282328 0.0814120000 1209255756 0 1787047936 -0.0454208329 0.1689355075 0.8336580396 913 36.4800000000 1.8163897991 1.0518247982 1.8163897991 0.0392078148 0.0807450000 1209257010 0 1787174912 -0.0461529791 0.1687938571 0.8330205679 914 36.5200000000 1.8180758953 1.0526631474 1.8180758953 0.0391871970 0.0859470000 1209258264 0 1787809792 -0.0467172563 0.1685994267 0.8325932026 915 36.5600000000 1.8159216642 1.0534973097 1.8180758953 0.0391665946 0.0771920000 1209259518 0 1786605568 -0.0475675762 0.1683151126 0.8317435980 916 36.6000000000 1.8166608810 1.0543304577 1.8180758953 0.0391463041 0.0833170000 1209260772 0 1786159104 -0.0483669564 0.1684753001 0.8309241533 917 36.6400000000 1.8176681995 1.0551628871 1.8180758953 0.0391254473 0.0813160000 1209262026 0 1786159104 -0.0489930324 0.1681376249 0.8304084539 918 36.6800000000 1.8196055889 1.0559956133 1.8196055889 0.0391047932 0.6284540000 1221568848 0 1787809792 -0.0496410318 0.1677258611 0.8299318552 919 36.7200000000 1.8192616701 1.0568261531 1.8196055889 0.0390843197 0.0909580000 1224997514 0 1786605568 -0.0503976718 0.1675959527 0.8288964033 920 36.7600000000 1.8228132725 1.0576587478 1.8228132725 0.0390637475 0.0937560000 1228114052 0 1786806272 -0.0511394925 0.1677641571 0.8284024000 921 36.8000000000 1.8190777302 1.0584854785 1.8228132725 0.0390430966 0.0903330000 1228115306 0 1785651200 -0.0519279949 0.1678736508 0.8272873163 922 36.8400000000 1.8171319962 1.0593083055 1.8228132725 0.0390226996 0.0925590000 1228116560 0 1785651200 -0.0525170453 0.1675432771 0.8262925148 923 36.8800000000 1.8162465096 1.0601283902 1.8228132725 0.0390016284 0.0889820000 1228117814 0 1786159104 -0.0529972725 0.1672597677 0.8256344199 924 36.9200000000 1.8182846308 1.0609489057 1.8228132725 0.0389825879 0.0893170000 1228119068 0 1786667008 -0.0541448258 0.1676463634 0.8246172667 925 36.9600000000 1.8191099167 1.0617685392 1.8228132725 0.0389617582 0.0864580000 1228120322 0 1787047936 -0.0550856665 0.1676471829 0.8236395121 926 37.0000000000 1.8201071024 1.0625874793 1.8228132725 0.0389416342 0.0882600000 1228121576 0 1787166720 -0.0565050133 0.1677461714 0.8221606016 927 37.0400000000 1.8178657293 1.0634022347 1.8228132725 0.0389209194 0.0902740000 1228122830 0 1787809792 -0.0573338792 0.1676914394 0.8209153414 928 37.0800000000 1.8186459541 1.0642160749 1.8228132725 0.0389012231 0.0877310000 1228124084 0 1786347520 -0.0580205992 0.1671871841 0.8202466369 929 37.1200000000 1.8186897039 1.0650282102 1.8228132725 0.0388805000 0.0873530000 1228125338 0 1786073088 -0.0586597286 0.1670121998 0.8193834424 930 37.1600000000 1.8183380365 1.0658382207 1.8228132725 0.0388599381 0.0906280000 1228126592 0 1786073088 -0.0594351776 0.1669434905 0.8184092641 931 37.2000000000 1.8208141327 1.0666491508 1.8228132725 0.0388395886 0.0961010000 1228127846 0 1786564608 -0.0601634048 0.1668415964 0.8178175092 932 37.2400000000 1.8172996044 1.0674545698 1.8228132725 0.0388197606 0.0927640000 1228129100 0 1787174912 -0.0606128126 0.1669330895 0.8166990280 933 37.2800000000 1.8180742264 1.0682590924 1.8228132725 0.0387991353 0.7232050000 1240439758 0 1786458112 -0.0614513122 0.1670863032 0.8156976700 934 37.3200000000 1.8197698593 1.0690637078 1.8228132725 0.0387832358 0.1177880000 1243868424 0 1785544704 -0.0634510517 0.1657836437 0.8159862757 935 37.3600000000 1.8173537254 1.0698640180 1.8228132725 0.0387626125 0.1064040000 1246984962 0 1786335232 -0.0640845671 0.1658348888 0.8148286939 936 37.4000000000 1.8134453297 1.0706584425 1.8228132725 0.0387419165 0.0858310000 1246986216 0 1785798656 -0.0644395128 0.1655955613 0.8137363791 937 37.4400000000 1.8110220432 1.0714485851 1.8228132725 0.0387212892 0.0839000000 1246987470 0 1785798656 -0.0649987534 0.1653794944 0.8126266599 938 37.4800000000 1.8125182390 1.0722386380 1.8228132725 0.0387011476 0.0848640000 1246988724 0 1785188352 -0.0656908453 0.1650733948 0.8119458556 939 37.5200000000 1.8124721050 1.0730269590 1.8228132725 0.0386809068 0.0806920000 1246989978 0 1785188352 -0.0665470511 0.1653996706 0.8108731508 940 37.5600000000 1.8085113764 1.0738093893 1.8228132725 0.0386603899 0.0945290000 1246991232 0 1785667584 -0.0669710040 0.1654091775 0.8096526861 941 37.6000000000 1.8087246418 1.0745903832 1.8228132725 0.0386404824 0.0906950000 1246992486 0 1786175488 -0.0675658882 0.1652007997 0.8088632822 942 37.6400000000 1.8100399971 1.0753711152 1.8228132725 0.0386206107 0.0919810000 1246993740 0 1786556416 -0.0682158098 0.1649316698 0.8081390262 943 37.6800000000 1.8071624041 1.0761471399 1.8228132725 0.0386002608 0.1002730000 1246994994 0 1786667008 -0.0688049942 0.1647646725 0.8069640994 944 37.7200000000 1.8043299913 1.0769185201 1.8228132725 0.0385800171 0.1033040000 1246996248 0 1787174912 -0.0691116899 0.1645923406 0.8061149120 945 37.7600000000 1.7999944687 1.0776836798 1.8228132725 0.0385609046 6.0149290000 1259303890 0 1786449920 -0.0695506558 0.1642375290 0.8048703671 946 37.8000000000 1.8014920950 1.0784488050 1.8228132725 0.0385416329 0.1266380000 1262732556 0 1786179584 -0.0693709105 0.1632909924 0.8064741492 947 37.8400000000 1.8029900789 1.0792138961 1.8228132725 0.0385244715 0.0955510000 1265849094 0 1786658816 -0.0700306445 0.1631512791 0.8057104349 948 37.8800000000 1.8021767139 1.0799765151 1.8228132725 0.0385070534 0.0931910000 1265850348 0 1785524224 -0.0705357492 0.1629583389 0.8048081994 949 37.9200000000 1.8039454222 1.0807393907 1.8228132725 0.0384890231 0.0923610000 1265851602 0 1785524224 -0.0711789206 0.1628608108 0.8040289283 950 37.9600000000 1.8035939932 1.0815002902 1.8228132725 0.0384699009 0.0946290000 1265852856 0 1786155008 -0.0717529878 0.1628026217 0.8031005859 951 38.0000000000 1.8031077385 1.0822590783 1.8228132725 0.0384507194 0.0929530000 1265854110 0 1786662912 -0.0722288862 0.1625653952 0.8022921085 952 38.0400000000 1.8042048216 1.0830174247 1.8228132725 0.0384317559 0.1040500000 1265855364 0 1786916864 -0.0728270337 0.1622599810 0.8014994264 953 38.0800000000 1.8030383587 1.0837729556 1.8228132725 0.0384141951 2.2870440000 1278167990 0 1786605568 -0.0734006688 0.1621983945 0.8005240560 954 38.1200000000 1.8053243160 1.0845292987 1.8228132725 0.0383946397 0.1262230000 1281596656 0 1785946112 -0.0710064471 0.1618663967 0.8018760085 955 38.1600000000 1.8053972721 1.0852841343 1.8228132725 0.0383757389 0.0993480000 1284713194 0 1786441728 -0.0715452358 0.1618769169 0.8009955287 956 38.2000000000 1.8065061569 1.0860385506 1.8228132725 0.0383560181 0.0890820000 1284714448 0 1785933824 -0.0722412094 0.1618069112 0.8000889421 957 38.2400000000 1.8083082438 1.0867932734 1.8228132725 0.0383362921 0.0962870000 1284715702 0 1785933824 -0.0729075149 0.1618055105 0.7992104292 958 38.2800000000 1.8105818033 1.0875487938 1.8228132725 0.0383173612 0.0846040000 1284716956 0 1786544128 -0.0734951422 0.1614822149 0.7985357642 959 38.3200000000 1.8107392788 1.0883029027 1.8228132725 0.0382975993 0.0845280000 1284718210 0 1787052032 -0.0741242543 0.1616848707 0.7975826859 960 38.3600000000 1.8092681170 1.0890539082 1.8228132725 0.0382777812 2.1058440000 1297028468 0 1787936768 -0.0748264268 0.1619356722 0.7963711619 961 38.4000000000 1.8087604046 1.0898028223 1.8228132725 0.0382616840 0.1130350000 1300457134 0 1786441728 -0.0754840821 0.1613634080 0.7955474854 962 38.4400000000 1.8086397648 1.0905500541 1.8228132725 0.0382420096 0.0872450000 1303573672 0 1786605568 -0.0759277493 0.1612306386 0.7947364450 963 38.4800000000 1.8091624975 1.0912962767 1.8228132725 0.0382227111 0.0815190000 1303574926 0 1786085376 -0.0766065940 0.1610443443 0.7937487364 964 38.5200000000 1.8084055185 1.0920401660 1.8228132725 0.0382034207 0.0731360000 1303576180 0 1786032128 -0.0771078169 0.1607905626 0.7928877473 965 38.5600000000 1.8108979464 1.0927850963 1.8228132725 0.0381840872 0.0722770000 1303577434 0 1786540032 -0.0778203458 0.1605497450 0.7920659184 966 38.6000000000 1.8115274906 1.0935291361 1.8228132725 0.0381649363 0.0712770000 1303578688 0 1787047936 -0.0786230713 0.1603538096 0.7912178040 967 38.6400000000 1.8111665249 1.0942712637 1.8228132725 0.0381460653 0.5109310000 1315886334 0 1787936768 -0.0789716020 0.1601350456 0.7902586460 968 38.6800000000 1.8137447834 1.0950145214 1.8228132725 0.0381274937 0.0741180000 1319315000 0 1786441728 -0.0803106204 0.1597912163 0.7896364331 969 38.7200000000 1.8132745028 1.0957557598 1.8228132725 0.0381081041 0.0614500000 1322431538 0 1787203584 -0.0805482939 0.1596487314 0.7888019681 970 38.7600000000 1.8170440197 1.0964993560 1.8228132725 0.0380898001 0.0600210000 1322432792 0 1785683968 -0.0813436434 0.1593641639 0.7884755135 971 38.8000000000 1.8188736439 1.0972433048 1.8228132725 0.0380705826 0.0600520000 1322434046 0 1785683968 -0.0817120373 0.1594742686 0.7875099182 972 38.8400000000 1.8199054003 1.0979867843 1.8228132725 0.0380513556 0.0593110000 1322435300 0 1785143296 -0.0823255256 0.1590274870 0.7868145108 973 38.8800000000 1.8200573921 1.0987288918 1.8228132725 0.0380319372 0.0553760000 1322436554 0 1785143296 -0.0826229304 0.1593217850 0.7856897116 974 38.9200000000 1.8186430931 1.0994680234 1.8228132725 0.0380128389 0.3533140000 1334757120 0 1786818560 -0.0831777751 0.1591407210 0.7849783301 975 38.9600000000 1.8178546429 1.1002048302 1.8228132725 0.0379936194 0.0580920000 1338339410 0 1787686912 -0.0835154206 0.1588110626 0.7839303613 976 39.0000000000 1.8178553581 1.1009401279 1.8228132725 0.0379748581 0.0644390000 1341532760 0 1788182528 -0.0839825347 0.1587824672 0.7829719186 977 39.0400000000 1.8177047968 1.1016737662 1.8228132725 0.0379563133 0.0559280000 1341534014 0 1786433536 -0.0844528154 0.1587710828 0.7819600701 978 39.0800000000 1.8152098656 1.1024033532 1.8228132725 0.0379374783 0.0561670000 1341535268 0 1785798656 -0.0848899558 0.1584151089 0.7809270620 979 39.1200000000 1.8179421425 1.1031342407 1.8228132725 0.0379217558 0.0523860000 1341536522 0 1785798656 -0.0855285078 0.1582431197 0.7805225253 980 39.1600000000 1.8194452524 1.1038651703 1.8228132725 0.0379050098 0.0555920000 1341537776 0 1785192448 -0.0868579671 0.1579799503 0.7797560692 981 39.2000000000 1.8186132908 1.1045937616 1.8228132725 0.0378860818 0.0522050000 1341539030 0 1785192448 -0.0870205536 0.1579601169 0.7784451842 982 39.2400000000 1.8173636198 1.1053195965 1.8228132725 0.0378679756 0.0521640000 1341540284 0 1784676352 -0.0870416835 0.1581190079 0.7777133584 983 39.2800000000 1.8173524141 1.1060439432 1.8228132725 0.0378501184 0.0585350000 1341541538 0 1784676352 -0.0885143355 0.1575551033 0.7774315476 984 39.3200000000 1.8174966574 1.1067669643 1.8228132725 0.0378324943 0.0525510000 1341542792 0 1785143296 -0.0886008441 0.1579576433 0.7760126591 985 39.3600000000 1.8179739714 1.1074890018 1.8228132725 0.0378143967 0.0557400000 1341544046 0 1785651200 -0.0891959816 0.1578384787 0.7751836777 986 39.4000000000 1.8151016235 1.1082066617 1.8228132725 0.0377965066 0.0563990000 1341545300 0 1786032128 -0.0895225108 0.1580792516 0.7743074298 987 39.4400000000 1.8137711287 1.1089215193 1.8228132725 0.0377789146 0.0600270000 1341546554 0 1786159104 -0.0898482203 0.1578066349 0.7734159827 988 39.4800000000 1.8134227991 1.1096345773 1.8228132725 0.0377606624 0.0591610000 1341547808 0 1786667008 -0.0903202817 0.1578195095 0.7723659873 989 39.5200000000 1.8134504557 1.1103462213 1.8228132725 0.0377419707 0.0601390000 1341549062 0 1787174912 -0.0907610655 0.1578645408 0.7714738846 990 39.5600000000 1.8128890991 1.1110558605 1.8228132725 0.0377230476 0.0582590000 1341550316 0 1787809792 -0.0913554654 0.1578768194 0.7705540657 991 39.6000000000 1.8090444803 1.1117601881 1.8228132725 0.0377041908 0.0573890000 1341551570 0 1786458112 -0.0917539969 0.1577741355 0.7694607973 992 39.6400000000 1.8074269295 1.1124614651 1.8228132725 0.0376853143 0.0611900000 1341552824 0 1786183680 -0.0922131762 0.1578265727 0.7684383988 993 39.6800000000 1.8025161028 1.1131563841 1.8228132725 0.0376670354 0.0608100000 1341554078 0 1786183680 -0.0925907716 0.1579749435 0.7673455477 994 39.7200000000 1.8004063368 1.1138477825 1.8228132725 0.0376490626 0.0621540000 1341555332 0 1785548800 -0.0930032283 0.1581554264 0.7662979364 995 39.7600000000 1.7989622355 1.1145363397 1.8228132725 0.0376311442 0.0576770000 1341556586 0 1785548800 -0.0936721787 0.1581244022 0.7653693557 996 39.8000000000 1.7969210148 1.1152214649 1.8228132725 0.0376126775 0.0606830000 1341557840 0 1786048512 -0.0938635617 0.1580650061 0.7643524408 997 39.8400000000 1.7952666283 1.1159035563 1.8228132725 0.0375944814 0.0622910000 1341559094 0 1786556416 -0.0944213122 0.1581609994 0.7632574439 998 39.8800000000 1.7945263386 1.1165835391 1.8228132725 0.0375764689 0.0580310000 1341560348 0 1786937344 -0.0952380225 0.1582275033 0.7622095942 999 39.9200000000 1.7909661531 1.1172585967 1.8228132725 0.0375607063 0.0604270000 1341561602 0 1787047936 -0.0956558511 0.1586134285 0.7609416246 1000 39.9600000000 1.7910274267 1.1179323656 1.8228132725 0.0375426756 0.0601220000 1341562856 0 1787555840 -0.0961286351 0.1584582925 0.7598860860 1001 40.0000000000 1.7910186052 1.1186047794 1.8228132725 0.0375240506 0.0635220000 1341564110 0 1788063744 -0.0963653103 0.1582994759 0.7590541840 1002 40.0400000000 1.7886105776 1.1192734479 1.8228132725 0.0375062985 0.0622290000 1341565364 0 1786458112 -0.0969075933 0.1585198045 0.7578603625 1003 40.0800000000 1.7869019508 1.1199390795 1.8228132725 0.0374878460 0.0636910000 1341566618 0 1786068992 -0.0975450054 0.1586186141 0.7566784620 1004 40.1200000000 1.7855619192 1.1206020504 1.8228132725 0.0374694073 0.0624090000 1341567872 0 1786068992 -0.0980137363 0.1591233164 0.7556649446 1005 40.1600000000 1.7850369215 1.1212631797 1.8228132725 0.0374509643 0.0601450000 1341569126 0 1786564608 -0.0992094278 0.1594126374 0.7547210455 1006 40.2000000000 1.7816562653 1.1219196340 1.8228132725 0.0374328832 0.0608320000 1341570380 0 1787072512 -0.0996329337 0.1598103642 0.7535205483 1007 40.2400000000 1.7784744501 1.1225716249 1.8228132725 0.0374144439 0.0638340000 1341571634 0 1787453440 -0.0991478860 0.1599473059 0.7523252368 1008 40.2800000000 1.7763546705 1.1232202192 1.8228132725 0.0373962498 0.0576940000 1341572888 0 1787555840 -0.0994519219 0.1596155316 0.7514102459 1009 40.3200000000 1.7738190889 1.1238650149 1.8228132725 0.0373778028 0.0581440000 1341574142 0 1788063744 -0.1005310789 0.1602140814 0.7503057718 1010 40.3600000000 1.7716155052 1.1245063520 1.8228132725 0.0373592852 0.0580920000 1341575396 0 1786716160 -0.1006338820 0.1607118547 0.7491679192 1011 40.4000000000 1.7713927031 1.1251462000 1.8228132725 0.0373425693 0.0614470000 1341576650 0 1786327040 -0.1015010551 0.1600358486 0.7486539483 1012 40.4400000000 1.7715115547 1.1257849010 1.8228132725 0.0373244515 2.8339450000 1353884984 0 1787969536 -0.1018547118 0.1601113379 0.7479110956 1013 40.4800000000 1.7713756561 1.1264222068 1.8228132725 0.0373069429 0.0591070000 1357544086 0 1787682816 -0.0982039273 0.1606303751 0.7515351176 1014 40.5200000000 1.7695142031 1.1270564198 1.8228132725 0.0372886992 0.0663270000 1360737436 0 1786347520 -0.0983057320 0.1605973691 0.7509153485 1015 40.5600000000 1.7703881264 1.1276902441 1.8228132725 0.0372739235 0.0664680000 1360738690 0 1785815040 -0.1003961489 0.1593038738 0.7502136230 1016 40.6000000000 1.7703874111 1.1283228201 1.8228132725 0.0372575075 0.0605840000 1360739944 0 1785815040 -0.0987661257 0.1606962979 0.7494288087 1017 40.6400000000 1.7677365541 1.1289515455 1.8228132725 0.0372402744 0.0640520000 1360741198 0 1785278464 -0.1003070250 0.1582329273 0.7492496371 1018 40.6800000000 1.7655410767 1.1295768790 1.8228132725 0.0372270856 0.0573960000 1360742452 0 1785270272 -0.0987675935 0.1598543823 0.7479242086 1019 40.7200000000 1.7628622055 1.1301983563 1.8228132725 0.0372092334 0.0552710000 1360743706 0 1785778176 -0.1006219834 0.1605526060 0.7470880151 1020 40.7600000000 1.7600682974 1.1308158758 1.8228132725 0.0371932012 0.0579500000 1360744960 0 1786413056 -0.0990043357 0.1601991802 0.7465928793 1021 40.8000000000 1.7569416761 1.1314291234 1.8228132725 0.0371751737 0.0575350000 1360746214 0 1786667008 -0.0987052396 0.1601612717 0.7457914352 1022 40.8400000000 1.7519875765 1.1320363235 1.8228132725 0.0371573953 0.0587590000 1360747468 0 1786920960 -0.0983512178 0.1601604819 0.7449866533 1023 40.8800000000 1.7482768297 1.1326387091 1.8228132725 0.0371397768 0.0607330000 1360748722 0 1787428864 -0.0982467756 0.1601391733 0.7442626953 1024 40.9200000000 1.7456034422 1.1332373075 1.8228132725 0.0371226571 0.0599520000 1360749976 0 1787936768 -0.0983275548 0.1600083411 0.7434067726 1025 40.9600000000 1.7417041063 1.1338309336 1.8228132725 0.0371045618 0.0563930000 1360836470 0 1786458112 -0.0984876156 0.1597600132 0.7422952056 1026 41.0000000000 1.7378484011 1.1344196446 1.8228132725 0.0370867739 0.0589600000 1361002340 0 1786195968 -0.0997710973 0.1603316367 0.7413239479 1027 41.0400000000 1.7379902601 1.1350073472 1.8228132725 0.0370700158 0.0583450000 1361003594 0 1786195968 -0.0982144326 0.1596553028 0.7409730554 1028 41.0800000000 1.7329863310 1.1355890389 1.8228132725 0.0370537506 0.0550260000 1361004848 0 1785659392 -0.0978219658 0.1600301266 0.7398299575 1029 41.1200000000 1.7327787876 1.1361693982 1.8228132725 0.0370381313 0.0538350000 1361006102 0 1785659392 -0.0982078388 0.1597972512 0.7391007543 1030 41.1600000000 1.7315410376 1.1367474289 1.8228132725 0.0370208137 0.0545850000 1361007356 0 1786159104 -0.0984546393 0.1599605083 0.7381545305 1031 41.2000000000 1.7290595770 1.1373219315 1.8228132725 0.0370029136 0.0548980000 1361008610 0 1786667008 -0.0980437994 0.1599223614 0.7373607159 1032 41.2400000000 1.7265220881 1.1378928619 1.8228132725 0.0369852712 0.0560770000 1361009864 0 1787047936 -0.0976877436 0.1596781760 0.7366370559 1033 41.2800000000 1.7233655453 1.1384596311 1.8228132725 0.0369678479 0.0549400000 1361011118 0 1787047936 -0.0976620018 0.1594478637 0.7356886864 1034 41.3200000000 1.7207781076 1.1390228018 1.8228132725 0.0369501362 0.0547930000 1361012372 0 1787682816 -0.0977615938 0.1594129652 0.7346916795 1035 41.3600000000 1.7186589241 1.1395828367 1.8228132725 0.0369330017 0.0606870000 1361013626 0 1786458112 -0.0976181552 0.1594195813 0.7340729237 1036 41.4000000000 1.7176508904 1.1401408175 1.8228132725 0.0369153393 0.0572600000 1361014880 0 1786458112 -0.0972848982 0.1596430987 0.7333456874 1037 41.4400000000 1.7173135281 1.1406973967 1.8228132725 0.0368994337 0.0565060000 1361016134 0 1786933248 -0.0975541770 0.1592285484 0.7325141430 1038 41.4800000000 1.7142046690 1.1412499086 1.8228132725 0.0368833987 0.0600580000 1361017388 0 1787441152 -0.0973897874 0.1591416746 0.7316583991 1039 41.5200000000 1.7125204802 1.1417997359 1.8228132725 0.0368659796 0.0570930000 1361018642 0 1787822080 -0.0974968672 0.1592680365 0.7306726575 1040 41.5600000000 1.7096334696 1.1423457299 1.8228132725 0.0368483380 0.0577670000 1361019896 0 1788063744 -0.0972664505 0.1592977196 0.7299405336 1041 41.6000000000 1.7109152079 1.1428919061 1.8228132725 0.0368318564 0.0583390000 1361021150 0 1786458112 -0.0974375606 0.1592796594 0.7293496728 1042 41.6400000000 1.7079792023 1.1434342164 1.8228132725 0.0368142091 0.0598680000 1361022404 0 1786068992 -0.0971779823 0.1593273729 0.7283424735 1043 41.6800000000 1.7047269344 1.1439723685 1.8228132725 0.0367974828 0.0587270000 1361023658 0 1786068992 -0.0967414156 0.1607140154 0.7273751497 1044 41.7200000000 1.7048424482 1.1445096004 1.8228132725 0.0367896755 0.0579170000 1361024912 0 1785552896 -0.0970434546 0.1590435207 0.7264886498 1045 41.7600000000 1.7034856081 1.1450445057 1.8228132725 0.0367724244 0.0609240000 1361026166 0 1785552896 -0.0971675366 0.1593229026 0.7256581783 1046 41.8000000000 1.6987695694 1.1455738796 1.8228132725 0.0367549632 0.0576310000 1361027420 0 1786048512 -0.0966341197 0.1594030559 0.7251078486 1047 41.8400000000 1.6985570192 1.1461020392 1.8228132725 0.0367380907 0.0591110000 1361028674 0 1786556416 -0.0964407697 0.1592206508 0.7244573236 1048 41.8800000000 1.6951296329 1.1466259205 1.8228132725 0.0367209345 0.0570820000 1361029928 0 1786937344 -0.0959936231 0.1591119766 0.7236630917 1049 41.9200000000 1.6936595440 1.1471474015 1.8228132725 0.0367041772 0.0573250000 1361031182 0 1786937344 -0.0961936936 0.1591432393 0.7229533792 1050 41.9600000000 1.6931568384 1.1476674105 1.8228132725 0.0366877852 0.0630460000 1361032436 0 1787555840 -0.0962591320 0.1591872722 0.7223622203 1051 42.0000000000 1.6928925514 1.1481861785 1.8228132725 0.0366709267 0.0589890000 1361037786 0 1788055552 -0.0961157605 0.1591210365 0.7216343284 1052 42.0400000000 1.6896014214 1.1487008318 1.8228132725 0.0366537151 0.3390230000 1373339280 0 1787293696 -0.0958067030 0.1590440571 0.7209864855 1053 42.0800000000 1.6865731478 1.1492116317 1.8228132725 0.0366366800 0.0677050000 1376998382 0 1787928576 -0.0957202837 0.1587238163 0.7187090516 1054 42.1200000000 1.6841424704 1.1497191562 1.8228132725 0.0366200928 0.0652140000 1380191732 0 1786449920 -0.0951578692 0.1588468999 0.7180706263 1055 42.1600000000 1.6812918186 1.1502230165 1.8228132725 0.0366062530 0.0709460000 1380192986 0 1786671104 -0.0951080918 0.1586783081 0.7167998552 1056 42.2000000000 1.6792477369 1.1507239869 1.8228132725 0.0365896103 0.0704460000 1380194240 0 1785647104 -0.0947960764 0.1586762667 0.7161431909 1057 42.2400000000 1.6758246422 1.1512207709 1.8228132725 0.0365728577 0.0657690000 1380195494 0 1785647104 -0.0942273960 0.1587700993 0.7154131532 1058 42.2800000000 1.6712906361 1.1517123303 1.8228132725 0.0365558341 0.0679250000 1380196748 0 1786277888 -0.0941649005 0.1585771441 0.7148019075 1059 42.3200000000 1.6681425571 1.1521999887 1.8228132725 0.0365393716 0.2345750000 1392494022 0 1787674624 -0.0938471183 0.1586332172 0.7143386006 1060 42.3600000000 1.6644778252 1.1526832697 1.8228132725 0.0365223634 0.0604850000 1396153124 0 1786339328 -0.0932314768 0.1586511880 0.7138367891 1061 42.4000000000 1.6612424850 1.1531625903 1.8228132725 0.0365055162 0.0736240000 1399346474 0 1786785792 -0.0925812721 0.1584909409 0.7132203579 1062 42.4400000000 1.6570291519 1.1536370410 1.8228132725 0.0364885632 0.0710140000 1399347728 0 1785540608 -0.0921395198 0.1582918763 0.7127583027 1063 42.4800000000 1.6535537243 1.1541073295 1.8228132725 0.0364717560 0.0691820000 1399348982 0 1785540608 -0.0919708908 0.1584922373 0.7121031284 1064 42.5200000000 1.6499783993 1.1545733737 1.8228132725 0.0364549637 0.0651170000 1399350236 0 1786028032 -0.0910398737 0.1582493931 0.7115896344 1065 42.5600000000 1.6470160484 1.1550357612 1.8228132725 0.0364379066 0.0633540000 1399351490 0 1786662912 -0.0908030272 0.1585900337 0.7111462355 1066 42.6000000000 1.6431999207 1.1554937013 1.8228132725 0.0364208618 0.0636480000 1399352744 0 1786916864 -0.0907987058 0.1586191654 0.7106209993 1067 42.6400000000 1.6401330233 1.1559479087 1.8228132725 0.0364040283 0.0644670000 1399353998 0 1787166720 -0.0902860686 0.1583980471 0.7101744413 1068 42.6800000000 1.6357259750 1.1563971391 1.8228132725 0.0363871873 0.2331980000 1411650176 0 1786449920 -0.0898599774 0.1581252664 0.7099134922 1069 42.7200000000 1.6322320700 1.1568422607 1.8228132725 0.0363706842 0.0671070000 1415309278 0 1787301888 -0.0897380635 0.1580882519 0.7091855407 1070 42.7600000000 1.6267564297 1.1572814328 1.8228132725 0.0363562491 0.0855350000 1418502628 0 1787674624 -0.0887774900 0.1584191769 0.7084857225 1071 42.8000000000 1.6210649014 1.1577144706 1.8228132725 0.0363469101 0.0680920000 1418503882 0 1786339328 -0.0884728506 0.1579800099 0.7079403996 1072 42.8400000000 1.6168110371 1.1581427323 1.8228132725 0.0363304061 0.0722990000 1418505136 0 1785823232 -0.0878546610 0.1580615044 0.7074937820 1073 42.8800000000 1.6108671427 1.1585646563 1.8228132725 0.0363136919 0.0722170000 1418506390 0 1785823232 -0.0872253850 0.1584311873 0.7070606351 1074 42.9200000000 1.6068583727 1.1589820620 1.8228132725 0.0362969408 0.0718060000 1418507644 0 1786298368 -0.0867108405 0.1584374607 0.7064599991 1075 42.9600000000 1.6005853415 1.1593928557 1.8228132725 0.0362804370 0.2244570000 1430803322 0 1787813888 -0.0858930871 0.1588530838 0.7059915662 1076 43.0000000000 1.5970033407 1.1597995569 1.8228132725 0.0362648387 0.0585440000 1434462424 0 1786449920 -0.0856151804 0.1589606702 0.7054476142 1077 43.0400000000 1.5943362713 1.1602030265 1.8228132725 0.0362489901 0.0731940000 1437655774 0 1787310080 -0.0853115916 0.1587345153 0.7050143480 1078 43.0800000000 1.5907785892 1.1606024472 1.8228132725 0.0362324060 0.0847690000 1437657028 0 1785806848 -0.0848978981 0.1591404676 0.7044863701 1079 43.1200000000 1.5872102976 1.1609978206 1.8228132725 0.0362158905 0.0717540000 1437658282 0 1785548800 -0.0845486447 0.1589461267 0.7040335536 1080 43.1600000000 1.5812429190 1.1613869364 1.8228132725 0.0362005240 0.0710570000 1437659536 0 1785548800 -0.0838190243 0.1588486582 0.7035081983 1081 43.2000000000 1.5763168335 1.1617707753 1.8228132725 0.0361838230 0.0687590000 1437660790 0 1786023936 -0.0832857713 0.1585934758 0.7031090856 1082 43.2400000000 1.5706543922 1.1621486715 1.8228132725 0.0361688442 0.0734340000 1437662044 0 1786531840 -0.0824330300 0.1591090858 0.7027720809 1083 43.2800000000 1.5639659166 1.1625196938 1.8228132725 0.0361529367 0.2563370000 1449960866 0 1787936768 -0.0816026628 0.1591344029 0.7022051811 1084 43.3200000000 1.5581800938 1.1628846942 1.8228132725 0.0361366265 0.0615350000 1453627960 0 1786679296 -0.0811440945 0.1585445106 0.7016748786 1085 43.3600000000 1.5541216135 1.1632452812 1.8228132725 0.0361202037 0.0704220000 1456821310 0 1787682816 -0.0806906298 0.1586833894 0.7013668418 1086 43.4000000000 1.5499268770 1.1636013416 1.8228132725 0.0361036547 0.0729030000 1456822564 0 1786073088 -0.0801241472 0.1585165411 0.7007987499 1087 43.4400000000 1.5443130732 1.1639515824 1.8228132725 0.0360873777 0.0770300000 1456823818 0 1786073088 -0.0794127509 0.1587824523 0.7005347610 1088 43.4800000000 1.5399770737 1.1642971941 1.8228132725 0.0360710409 0.0754000000 1456825072 0 1786548224 -0.0789348409 0.1588445157 0.7001882195 1089 43.5200000000 1.5355219841 1.1646380800 1.8228132725 0.0360549184 0.0751940000 1456826326 0 1787183104 -0.0783595517 0.1589287668 0.6997061372 1090 43.5600000000 1.5290373564 1.1649723913 1.8228132725 0.0360389292 0.3016600000 1469126120 0 1786347520 -0.0775270909 0.1591202617 0.6992021799 1091 43.6000000000 1.5234686136 1.1653009854 1.8228132725 0.0360230067 0.0541850000 1472785222 0 1787076608 -0.0769184157 0.1589429379 0.6986870170 1092 43.6400000000 0.5413922071 1.1647296404 1.8228132725 0.0560818442 0.1623330000 1486796656 0 1785544704 0.5636346936 0.1775609851 -0.0938599110 1093 43.6800000000 0.5388419628 1.1641570076 1.8228132725 0.0560622464 0.1474030000 1479425018 0 1785065472 0.5473965406 0.1704185903 -0.0958997607 1094 43.7200000000 1.5020209551 1.1644658412 1.8228132725 0.0691193372 0.0476080000 1486799100 0 1785286656 -0.1633229554 0.2723601460 0.5919704437 1095 43.7600000000 1.5257073641 1.1647957421 1.8228132725 0.0692467687 0.1176080000 1484814778 0 1786458112 -0.1886310875 0.2782032788 0.6066876054 1096 43.8000000000 1.4861072302 1.1650889095 1.8228132725 0.0779941213 0.0787980000 1498490132 0 1787699200 -0.0722479150 0.3196024597 0.6464288235 1097 43.8400000000 1.4458420277 1.1653448376 1.8228132725 0.0784871925 0.1254850000 1500926678 0 1786441728 -0.0610389821 0.3514969051 0.5992263556 1098 43.8800000000 0.7231163383 1.1649420794 1.8228132725 0.1066180700 0.3027610000 1515907696 0 1785700352 0.3835693598 0.0393604040 0.1040179953 1099 43.9200000000 0.7261863351 1.1645428476 1.8228132725 0.1065704745 0.1294190000 1508436298 0 1786458112 0.3792975843 0.0535764322 0.1083694771 1100 43.9600000000 0.7266761661 1.1641447870 1.8228132725 0.1065222755 0.1300770000 1508437552 0 1787187200 0.3779479861 0.0607122369 0.1142226532 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 06:09:22 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287480354 0.0606188439 0.0606188439 0.0606188439 nan 0.0459180000 87244243 0 443711488 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644249916 0.0582198836 0.0594193637 0.0606188439 0.1449896693 0.1766930000 99459356 0 576020480 0.0075847739 -0.0009307559 0.0055031846 3 1305031229.5966000557 0.0850225389 0.0679537555 0.0850225389 0.1660447018 0.2008610000 102730458 0 579817472 -0.0065036328 -0.0385077633 0.0017556350 4 1305031229.6287529469 0.0755757987 0.0698592663 0.0850225389 0.1359203707 0.1671440000 102732520 0 580452352 0.0003893150 -0.0246820245 0.0047542513 5 1305031229.6646571159 0.1048541293 0.0768582389 0.1048541293 0.1216100049 0.1727690000 102734686 0 580960256 0.0034678692 -0.0613471866 0.0029658086 6 1305031229.6968269348 0.1058274657 0.0816864433 0.1058274657 0.1087786396 0.1548810000 102737108 0 581595136 0.0068523260 -0.0620819591 0.0051611504 7 1305031229.7290639877 0.0956967846 0.0836879207 0.1058274657 0.0996455404 0.1522250000 102738842 0 582103040 0.0126664378 -0.0502570271 0.0102340644 8 1305031229.7648479939 0.1127030104 0.0873148069 0.1127030104 0.0929062719 0.2022860000 115080236 0 594927616 0.0066439202 -0.0663514808 0.0056229839 9 1305031229.7969090939 0.1001381129 0.0887396187 0.1127030104 0.0869549340 0.1839250000 118740722 0 599252992 0.0062874602 -0.0513773523 0.0092008868 10 1305031229.8256130219 0.0939616039 0.0892618172 0.1127030104 0.0824297417 0.1459190000 121935832 0 602935296 0.0105969273 -0.0410361178 0.0098013990 11 1305031229.8630549908 0.1040657982 0.0906076336 0.1127030104 0.0787764460 0.1221680000 121937726 0 603570176 0.0063505233 -0.0532467961 0.0092139263 12 1305031229.8969290257 0.0972355753 0.0911599621 0.1127030104 0.0752434286 0.1810720000 121939492 0 604078080 0.0089381142 -0.0427655429 0.0108096777 13 1305031229.9262480736 0.0949130654 0.0914486624 0.1127030104 0.0723565276 0.1238850000 121941226 0 604585984 0.0087361364 -0.0373091064 0.0107552195 14 1305031229.9661600590 0.1028540879 0.0922633356 0.1127030104 0.0698585080 0.1184550000 121943120 0 605220864 0.0088830823 -0.0455219671 0.0097054103 15 1305031229.9979169369 0.1038322523 0.0930345967 0.1127030104 0.0676012712 0.3016880000 140776010 0 621219840 0.0085426522 -0.0492417365 0.0132510066 16 1305031230.0299909115 0.1088541523 0.0940233190 0.1127030104 0.0654079187 0.2022210000 144435624 0 625410048 0.0023167264 -0.0571449809 0.0139710624 17 1305031230.0656869411 0.1077007204 0.0948278720 0.1127030104 0.0633761219 0.1569240000 147630894 0 629092352 -0.0002145964 -0.0551155247 0.0139374649 18 1305031230.0982420444 0.1115516424 0.0957569703 0.1127030104 0.0616285631 0.1534040000 147635284 0 629727232 -0.0000854294 -0.0585942380 0.0129970694 19 1305031230.1299190521 0.1108925864 0.0965535817 0.1127030104 0.0599761881 0.1577450000 147637050 0 630235136 -0.0001810999 -0.0577651374 0.0144796614 20 1305031230.1657710075 0.1111962199 0.0972857136 0.1127030104 0.0583883538 0.1402390000 147638880 0 630870016 -0.0012313195 -0.0592076182 0.0172504205 21 1305031230.1977720261 0.1104284525 0.0979115583 0.1127030104 0.0570737690 0.1444770000 147640646 0 631377920 -0.0027280659 -0.0582633354 0.0177159104 22 1305031230.2298300266 0.1134077087 0.0986159288 0.1134077087 0.0559366336 0.2402520000 159943472 0 644194304 -0.0026526034 -0.0627318174 0.0207365546 23 1305031230.2655799389 0.1130353138 0.0992428586 0.1134077087 0.0546589931 0.0724700000 163603558 0 648257536 0.0022964559 -0.0611039512 0.0246488024 24 1305031230.2979819775 0.1103662103 0.0997063316 0.1134077087 0.0535824144 0.2012080000 166797420 0 652066816 0.0033781927 -0.0564559251 0.0267272424 25 1305031230.3256850243 0.1063938290 0.0999738315 0.1134077087 0.0525871873 0.1781880000 166799122 0 652701696 0.0001570042 -0.0534735136 0.0291596074 26 1305031230.3656499386 0.1126961485 0.1004631514 0.1134077087 0.0516297335 0.1802650000 166801016 0 653209600 0.0016810417 -0.0582444817 0.0290983934 27 1305031230.3972649574 0.1122406349 0.1008993545 0.1134077087 0.0507523007 0.1635070000 166802814 0 653971456 0.0009853444 -0.0579219759 0.0320193693 28 1305031230.4256699085 0.1119963154 0.1012956745 0.1134077087 0.0499183529 0.1628390000 166804484 0 654487552 0.0013629787 -0.0568037443 0.0347360186 29 1305031230.4652199745 0.1207584962 0.1019668063 0.1207584962 0.0491619165 0.1885580000 179103338 0 667312128 0.0083308574 -0.0664841533 0.0484716669 30 1305031230.4972279072 0.1293676049 0.1028801662 0.1293676049 0.0487656399 0.1833180000 182762984 0 671375360 0.0204016119 -0.0683096498 0.0606010668 31 1305031230.5267200470 0.1437136680 0.1041973760 0.1437136680 0.0489166567 0.1954670000 185956782 0 675057664 0.0297343265 -0.0790940672 0.0829152092 32 1305031230.5660839081 0.1403280050 0.1053264581 0.1437136680 0.0485317477 0.3222660000 185958676 0 675692544 0.0206939597 -0.0768282115 0.0737663582 33 1305031230.5988249779 0.1479142010 0.1066169958 0.1479142010 0.0482172266 0.2184890000 185963130 0 676327424 0.0240361337 -0.0806952938 0.0845632181 34 1305031230.6260280609 0.1525755972 0.1079687193 0.1525755972 0.0477861707 0.2191870000 185970080 0 676835328 0.0255677197 -0.0813917667 0.0907549784 35 1305031230.6657950878 0.1689900905 0.1097121871 0.1689900905 0.0471354894 0.2407970000 185971974 0 677470208 0.0348663218 -0.0872843862 0.1082126945 36 1305031230.6979320049 0.1773742735 0.1115916895 0.1773742735 0.0468046991 0.3166610000 198283092 0 690548736 0.0361653902 -0.0906621888 0.1231781170 37 1305031230.7256710529 0.1736514717 0.1132689809 0.1773742735 0.0462528825 0.2466000000 201942642 0 694611968 0.0313228592 -0.0886526704 0.1166409254 38 1305031230.7658538818 0.1671401262 0.1146866426 0.1773742735 0.0457855578 0.1988140000 205136632 0 698421248 0.0233566817 -0.0848950371 0.1100723669 39 1305031230.7973029613 0.1626969278 0.1159176756 0.1773742735 0.0453098615 0.1922260000 205138398 0 699056128 0.0182909798 -0.0826780051 0.1052820012 40 1305031230.8257288933 0.1764943600 0.1174320927 0.1773742735 0.0452369987 0.1981310000 205140068 0 699564032 0.0244828053 -0.0876185223 0.1259950548 41 1305031230.8655230999 0.1812244803 0.1189880046 0.1812244803 0.0447445099 0.1675050000 205141962 0 700071936 0.0227088481 -0.0915147662 0.1303520948 42 1305031230.8973789215 0.1826707423 0.1205042602 0.1826707423 0.0444016603 0.1781150000 205143760 0 700579840 0.0218906738 -0.0918376073 0.1320496500 43 1305031230.9258599281 0.1883170158 0.1220813011 0.1883170158 0.0439225870 0.3089660000 217448958 0 713531392 0.0219081081 -0.1000320986 0.1299502552 44 1305031230.9649760723 0.2299691588 0.1245332978 0.2299691588 0.0439297434 0.3139070000 221108700 0 717721600 0.0432220250 -0.1206819341 0.1668955386 45 1305031230.9970800877 0.2330471575 0.1269447169 0.2330471575 0.0435349929 0.2925500000 224302594 0 721403904 0.0442953221 -0.1209858954 0.1718543917 46 1305031231.0256528854 0.2377261519 0.1293530090 0.2377261519 0.0431398856 0.2501780000 224304264 0 722038784 0.0443032384 -0.1239267886 0.1788186431 47 1305031231.0644218922 0.2375081033 0.1316541812 0.2377261519 0.0427191557 0.2520130000 224306126 0 722546688 0.0444041938 -0.1221698597 0.1820621043 48 1305031231.0967750549 0.2382691056 0.1338753255 0.2382691056 0.0422816896 0.2340680000 224307924 0 723054592 0.0455152281 -0.1215007752 0.1840593964 49 1305031231.1257278919 0.2372906804 0.1359858429 0.2382691056 0.0418389516 0.2216840000 224309626 0 723689472 0.0440732464 -0.1226318404 0.1837970763 50 1305031231.1652410030 0.2410370857 0.1380868678 0.2410370857 0.0414978982 0.2104330000 224311520 0 724197376 0.0465600118 -0.1257093996 0.1864926964 51 1305031231.1977469921 0.2493741214 0.1402689708 0.2493741214 0.0413468004 0.2166490000 224313318 0 724705280 0.0499618389 -0.1286833137 0.1988619417 52 1305031231.2257111073 0.2565735579 0.1425055975 0.2565735579 0.0411096802 0.2532240000 224314988 0 725340160 0.0522668213 -0.1339854300 0.2085947096 53 1305031231.2655940056 0.2653544545 0.1448235004 0.2653544545 0.0416732997 0.2182950000 224316882 0 726220800 0.0557974502 -0.1379351318 0.2237513214 54 1305031231.2978460789 0.2738498151 0.1472128766 0.2738498151 0.0415446943 0.2416630000 224318680 0 726855680 0.0600445345 -0.1425377131 0.2356470078 55 1305031231.3257410526 0.2749552131 0.1495354646 0.2749552131 0.0415644497 0.2018160000 224320350 0 727363584 0.0648196563 -0.1453996003 0.2347286195 56 1305031231.3650660515 0.2716448903 0.1517159900 0.2749552131 0.0413988280 0.2277500000 224322244 0 728125440 0.0660928339 -0.1467738897 0.2319629490 57 1305031231.3971281052 0.2669104040 0.1537369447 0.2749552131 0.0412214286 0.3812300000 236632522 0 741584896 0.0677826852 -0.1464032978 0.2262724638 58 1305031231.4256880283 0.2526540756 0.1554424124 0.2749552131 0.0411387155 0.2151850000 240292880 0 745648128 0.0684347302 -0.1390307397 0.2093089521 59 1305031231.4649178982 0.2350188047 0.1567911648 0.2749552131 0.0407909209 0.1878980000 243486870 0 749203456 0.0650452077 -0.1298279911 0.1925935149 60 1305031231.4936690331 0.2166326493 0.1577885229 0.2749552131 0.0405665066 0.1797040000 243488572 0 749838336 0.0599288680 -0.1188565046 0.1759380251 61 1305031231.5257549286 0.2040553838 0.1585469960 0.2749552131 0.0403983869 0.1764910000 243490370 0 750473216 0.0580610894 -0.1098294705 0.1634506285 62 1305031231.5650520325 0.1872448176 0.1590098641 0.2749552131 0.0400840197 0.1960080000 243492232 0 750981120 0.0505452901 -0.1009569019 0.1465507746 63 1305031231.5937368870 0.1896201074 0.1594957410 0.2749552131 0.0398630034 0.1662520000 243493934 0 751489024 0.0565339625 -0.1016657054 0.1401622146 64 1305031231.6257040501 0.1581548154 0.1594747890 0.2749552131 0.0404480844 0.4825910000 255803148 0 764821504 0.0349136777 -0.0840244368 0.1046611592 65 1305031231.6650450230 0.1602266729 0.1594863565 0.2749552131 0.0401457984 0.1224110000 259468266 0 768884736 0.0384434164 -0.0844498053 0.1032696366 66 1305031231.6937019825 0.1615561247 0.1595177166 0.2749552131 0.0399524255 0.1031170000 262672560 0 772694016 0.0405055881 -0.0854412839 0.1041710675 67 1305031231.7258861065 0.1647984684 0.1595965338 0.2749552131 0.0398853552 0.1912150000 262674326 0 773328896 0.0424793735 -0.0887543708 0.1071893275 68 1305031231.7654778957 0.1656830758 0.1596860418 0.2749552131 0.0397955325 0.1842760000 262676220 0 773836800 0.0427435338 -0.0910522714 0.1088723391 69 1305031231.7937231064 0.1650925428 0.1597643969 0.2749552131 0.0397066618 0.1781040000 262677954 0 774344704 0.0444514938 -0.0901264846 0.1061212793 70 1305031231.8256859779 0.1631587446 0.1598128875 0.2749552131 0.0395702164 0.1464420000 262679688 0 774852608 0.0511149019 -0.0838117078 0.1155891418 71 1305031231.8649399281 0.1611477733 0.1598316888 0.2749552131 0.0432712852 0.1767150000 279983502 0 781836288 0.0511149019 -0.0838117078 0.1155891418 72 1305031231.8937270641 0.1525037289 0.1597299115 0.2749552131 0.0444463877 0.0253500000 283330944 0 785645568 0.0323060453 -0.0838439986 0.0791980848 73 1305031231.9257059097 0.1511159241 0.1596119117 0.2749552131 0.0455189479 0.0213930000 283409542 0 786280448 0.0323060453 -0.0838439986 0.0791980848 74 1305031231.9650099277 0.1496974379 0.1594779323 0.2749552131 0.0470900659 0.0151650000 283488268 0 786915328 0.0323060453 -0.0838439986 0.0791980848 75 1305031231.9937260151 0.1489006132 0.1593369014 0.2749552131 0.0475087394 0.0529660000 283566802 0 787550208 0.0323060453 -0.0838439986 0.0791980848 76 1305031232.0257899761 0.1475743502 0.1591821310 0.2749552131 0.0481629401 0.0171820000 283645432 0 788185088 0.0323060453 -0.0838439986 0.0791980848 77 1305031232.0651218891 0.1460317522 0.1590113469 0.2749552131 0.0494874946 0.0133600000 283724126 0 788803584 0.0323060453 -0.0838439986 0.0791980848 78 1305031232.0937249660 0.1448853314 0.1588302441 0.2749552131 0.0498370221 0.0270390000 283802692 0 789438464 0.0323060453 -0.0838439986 0.0791980848 79 1305031232.1256620884 0.1438064128 0.1586400690 0.2749552131 0.0500789548 0.0236710000 283881258 0 790073344 0.0323060453 -0.0838439986 0.0791980848 80 1305031232.1650319099 0.1423330009 0.1584362307 0.2749552131 0.0506676140 0.0266200000 283959984 0 790708224 0.0323060453 -0.0838439986 0.0791980848 81 1305031232.1937160492 0.1413783878 0.1582256400 0.2749552131 0.0509980912 0.0361150000 284038550 0 791216128 0.0323060453 -0.0838439986 0.0791980848 82 1305031232.2256829739 0.1405703723 0.1580103319 0.2749552131 0.0512822666 0.0192600000 284117116 0 791851008 0.0323060453 -0.0838439986 0.0791980848 83 1305031232.2626910210 3.7058579922 0.2007554844 3.7058579922 0.3236660347 0.0314020000 284195810 0 792485888 3.3745608330 0.0812631398 1.5834894180 84 1305031232.2938549519 4.3241529465 0.2498435494 4.3241529465 0.3320604047 0.0257980000 284274512 0 793120768 4.1080031395 -0.1402351707 1.3747650385 85 1305031232.3256189823 5.6772851944 0.3136958041 5.6772851944 0.3881671937 0.0281660000 287622090 0 796930048 5.5229930878 -0.9694495201 0.8083788753 86 1305031232.3647379875 5.6766476631 0.3760557094 5.6772851944 0.3859563684 0.0182740000 290969692 0 800866304 5.5229930878 -0.9694495201 0.8083788753 87 1305031232.3937139511 5.6763315201 0.4369784199 5.6772851944 0.3837341407 0.0173280000 291048290 0 801501184 5.5229930878 -0.9694495201 0.8083788753 88 1305031232.4257209301 5.6762256622 0.4965153204 5.6772851944 0.3815406259 0.0252180000 291126856 0 802136064 5.5229930878 -0.9694495201 0.8083788753 89 1305031232.4647030830 5.6761097908 0.5547130110 5.6772851944 0.3793933646 0.0259280000 291205550 0 802770944 5.5229930878 -0.9694495201 0.8083788753 90 1305031232.4936499596 5.6761837006 0.6116182409 5.6772851944 0.3772800325 0.0224920000 291284116 0 803405824 5.5229930878 -0.9694495201 0.8083788753 91 1305031232.5257809162 5.6762328148 0.6672733461 5.6772851944 0.3752141251 0.0191920000 291362714 0 803913728 5.5229930878 -0.9694495201 0.8083788753 92 1305031232.5647139549 5.6759166718 0.7217151214 5.6772851944 0.3732018596 0.0156640000 291441440 0 804548608 5.5229930878 -0.9694495201 0.8083788753 93 1305031232.5937221050 5.6756978035 0.7749837524 5.6772851944 0.3712168292 0.0285360000 291519942 0 805183488 5.5229930878 -0.9694495201 0.8083788753 94 1305031232.6257829666 5.6759638786 0.8271218388 5.6772851944 0.3692805239 0.0240670000 291598572 0 805818368 5.5229930878 -0.9694495201 0.8083788753 95 1305031232.6646950245 5.6761074066 0.8781637922 5.6772851944 0.3673760008 0.0231920000 291677298 0 806453248 5.5229930878 -0.9694495201 0.8083788753 96 1305031232.6937010288 11.1344156265 0.9849997488 11.1344156265 0.6511611826 0.0279490000 291755968 0 807088128 10.5522785187 -2.4573972225 2.5408914089 97 1305031232.7258760929 11.4980630875 1.0933818451 11.4980630875 0.6494616365 0.1094330000 295103546 0 810897408 10.9858064651 -2.3667905331 2.3992030621 98 1305031232.7617189884 11.4979896545 1.1995513125 11.4980630875 0.6461437100 0.0311240000 298451116 0 814833664 10.9858064651 -2.3667905331 2.3992030621 99 1305031232.7936720848 11.4982814789 1.3035788900 11.4982814789 0.6428905715 0.0225220000 298529746 0 815468544 10.9858064651 -2.3667905331 2.3992030621 100 1305031232.8257670403 11.4986209869 1.4055293109 11.4986209869 0.6396592923 0.0256680000 298608312 0 816103424 10.9858064651 -2.3667905331 2.3992030621 101 1305031232.8616659641 11.4987125397 1.5054618181 11.4987125397 0.6364691880 0.0304110000 298686974 0 816738304 10.9858064651 -2.3667905331 2.3992030621 102 1305031232.8936829567 11.4992799759 1.6034404275 11.4992799759 0.6333178112 0.0147590000 298765604 0 817373184 10.9858064651 -2.3667905331 2.3992030621 103 1305031232.9257559776 11.4991111755 1.6995149008 11.4992799759 0.6302073421 0.0081430000 298767366 0 817881088 10.9858064651 -2.3667905331 2.3992030621 104 1305031232.9616620541 11.4997634888 1.7937480603 11.4997634888 0.6271412247 0.0070830000 298769216 0 818515968 10.9858064651 -2.3667905331 2.3992030621 105 1305031232.9936408997 11.5000019073 1.8861885731 11.5000019073 0.6241244827 0.0067330000 298771010 0 819023872 10.9858064651 -2.3667905331 2.3992030621 106 1305031233.0257461071 11.5009145737 1.9768935354 11.5009145737 0.6211957327 0.0284310000 298849576 0 819531776 10.9858064651 -2.3667905331 2.3992030621 107 1305031233.0616970062 11.5021448135 2.0659145754 11.5021448135 0.6183259485 0.0364930000 298928238 0 820166656 10.9858064651 -2.3667905331 2.3992030621 108 1305031233.0937008858 11.5085306168 2.1533462054 11.5085306168 0.6158922223 0.0307120000 299006908 0 820801536 10.9656877518 -2.4753296375 2.4054255486 109 1305031233.1258459091 19.2908878326 2.3105713579 19.2908878326 0.9494385933 0.0413880000 302354518 0 824610816 16.2485332489 -7.8756151199 6.7596244812 110 1305031233.1617441177 19.3942852020 2.4658778474 19.3942852020 0.9452538670 0.0338530000 305702192 0 828547072 16.2995491028 -7.9782538414 6.8111133575 111 1305031233.1937611103 25.2736301422 2.6713530933 25.2736301422 1.0944316220 0.0402260000 309049770 0 832356352 14.6937665939 -18.1398296356 9.6390018463 112 1305031233.2257630825 24.9920387268 2.8706449294 25.2736301422 1.0897981774 0.0345500000 312397412 0 836292608 14.4598951340 -17.9662208557 9.5811004639 113 1305031233.2616870403 28.3478202820 3.0961066581 28.3478202820 1.1368098228 0.0385170000 315745086 0 840228864 19.0223350525 -18.6789588928 9.5652666092 114 1305031233.2938020229 28.3519077301 3.3176487728 28.3519077301 1.1319344176 0.0115940000 317479724 0 842514432 19.0223350525 -18.6789588928 9.5652666092 115 1305031233.3257980347 142.0740203857 4.5242259173 142.0740203857 11.1784189176 0.0298640000 317558426 0 843149312 117.3082580566 -46.2354621887 -65.2595748901 116 1305031233.3617999554 142.0794525146 5.7100468362 142.0794525146 11.1297200743 0.0114520000 319293160 0 845434880 117.3082580566 -46.2354621887 -65.2595748901 117 1305031233.3936851025 142.0864410400 6.8756570431 142.0864410400 11.0816593271 0.0105150000 319294946 0 846069760 117.3082580566 -46.2354621887 -65.2595748901 118 1305031233.4257080555 142.0905914307 8.0215463175 142.0905914307 11.0342069677 0.0067100000 319296700 0 846577664 117.3082580566 -46.2354621887 -65.2595748901 119 1305031233.4618360996 142.0937347412 9.1482033631 142.0937347412 10.9873542611 0.0070730000 319298582 0 847085568 117.3082580566 -46.2354621887 -65.2595748901 120 1305031233.4936919212 142.0970153809 10.2561101299 142.0970153809 10.9410930636 0.0130130000 319607580 0 847847424 117.3082580566 -46.2354621887 -65.2595748901 121 1305031233.5257079601 142.0993347168 11.3457235563 142.0993347168 10.8954111828 0.0113720000 319609334 0 848482304 117.3082580566 -46.2354621887 -65.2595748901 122 1305031233.5617849827 142.1017150879 12.4174939787 142.1017150879 10.8502977696 0.0114720000 319611216 0 849117184 117.3082580566 -46.2354621887 -65.2595748901 123 1305031233.5937600136 142.1048583984 13.4718627951 142.1048583984 10.8057454775 0.0079310000 319612970 0 849625088 117.3082580566 -46.2354621887 -65.2595748901 124 1305031233.6257069111 142.1063690186 14.5092378453 142.1063690186 10.7617336280 0.0155770000 319614756 0 850132992 117.3082580566 -46.2354621887 -65.2595748901 125 1305031233.6617000103 142.1075134277 15.5300240499 142.1075134277 10.7182540242 0.0125280000 319616638 0 850640896 117.3082580566 -46.2354621887 -65.2595748901 126 1305031233.6937789917 142.1084747314 16.5346149284 142.1084747314 10.6752964767 0.0215690000 319618392 0 851148800 117.3082580566 -46.2354621887 -65.2595748901 127 1305031233.7255749702 142.1082458496 17.5233836758 142.1084747314 10.6328498117 0.0392920000 321233046 0 853180416 117.3082580566 -46.2354621887 -65.2595748901 128 1305031233.7616429329 160.3410339355 18.6391465684 160.3410339355 10.7139406340 0.0531440000 322540624 0 855085056 131.8607330322 -52.5266494751 -74.3022003174 129 1305031233.7937469482 160.3395385742 19.7375992196 160.3410339355 10.6720077810 0.0162890000 324582506 0 857624576 131.8607330322 -52.5266494751 -74.3022003174 130 1305031233.8256869316 160.3379974365 20.8191407444 160.3410339355 10.6305629842 0.0125490000 324605284 0 858386432 131.8607330322 -52.5266494751 -74.3022003174 131 1305031233.8616130352 146.8258209229 21.7810237992 160.3410339355 11.8396397415 0.0379130000 324684050 0 858894336 -1.9850684404 -123.7471694946 -78.7892456055 132 1305031233.8937180042 146.8260955811 22.7283349490 160.3410339355 11.7943638266 0.0286190000 328031588 0 862703616 -1.9850684404 -123.7471694946 -78.7892456055 133 1305031233.9258410931 146.8260498047 23.6614004743 160.3410339355 11.7496033718 0.0073700000 328033342 0 863338496 -1.9850684404 -123.7471694946 -78.7892456055 134 1305031233.9617478848 146.8260345459 24.5805395345 160.3410339355 11.7053486828 0.0124170000 328035192 0 863973376 -1.9850684404 -123.7471694946 -78.7892456055 135 1305031233.9937219620 146.8803558350 25.4864640997 160.3410339355 11.6628926363 0.0337250000 328113926 0 864481280 -2.1999320984 -123.4218063354 -79.3935241699 136 1305031234.0257859230 146.8801116943 26.3790644497 160.3410339355 11.6196167236 0.0186610000 329850220 0 866639872 -2.1999320984 -123.4218063354 -79.3935241699 137 1305031234.0616750717 146.8799591064 27.2586330238 160.3410339355 11.5768192351 0.0118810000 329852070 0 867274752 -2.1999320984 -123.4218063354 -79.3935241699 138 1305031234.0937900543 146.8797149658 28.1254524582 160.3410339355 11.5344915889 0.0118250000 329853824 0 867909632 -2.1999320984 -123.4218063354 -79.3935241699 139 1305031234.1296060085 146.8795471191 28.9797984629 160.3410339355 11.4926246149 0.0105000000 329855674 0 868417536 -2.1999320984 -123.4218063354 -79.3935241699 140 1305031234.1617290974 146.8801574707 29.8219438844 160.3410339355 11.4512098545 0.0131680000 329857492 0 868925440 -2.1999320984 -123.4218063354 -79.3935241699 141 1305031234.1937100887 146.8801727295 30.6521440890 160.3410339355 11.4102406757 0.0274800000 331164870 0 870703104 -2.1999320984 -123.4218063354 -79.3935241699 142 1305031234.2297461033 146.8802795410 31.4706520851 160.3410339355 11.3697072336 0.0129910000 331473932 0 871464960 -2.1999320984 -123.4218063354 -79.3935241699 143 1305031234.2617518902 146.8811035156 32.2777181790 160.3410339355 11.3296026483 0.0086140000 331475750 0 872226816 -2.1999320984 -123.4218063354 -79.3935241699 144 1305031234.2936971188 146.8815002441 33.0735777767 160.3410339355 11.2899196937 0.0161420000 331477504 0 872734720 -2.1999320984 -123.4218063354 -79.3935241699 145 1305031234.3296539783 146.8816986084 33.8584613686 160.3410339355 11.2506507689 0.0109770000 331479354 0 873242624 -2.1999320984 -123.4218063354 -79.3935241699 146 1305031234.3616120815 146.8819885254 34.6325951163 160.3410339355 11.2117887039 0.0081550000 331481172 0 873750528 -2.1999320984 -123.4218063354 -79.3935241699 147 1305031234.3937230110 146.8819885254 35.3961964320 160.3410339355 11.1733269295 0.0085420000 331482958 0 874258432 -2.1999320984 -123.4218063354 -79.3935241699 148 1305031234.4297029972 146.8813018799 36.1494741715 160.3410339355 11.1352582529 0.0175390000 331484776 0 874893312 -2.1999320984 -123.4218063354 -79.3935241699 149 1305031234.4616899490 146.8803863525 36.8926346560 160.3410339355 11.0975765403 0.0083500000 331486594 0 875401216 -2.1999320984 -123.4218063354 -79.3935241699 150 1305031234.4938309193 146.8793945312 37.6258797218 160.3410339355 11.0602747171 0.0116260000 331488348 0 875909120 -2.1999320984 -123.4218063354 -79.3935241699 151 1305031234.5296449661 146.8777313232 38.3494019178 160.3410339355 11.0233468925 0.0257470000 331567010 0 876417024 -2.1999320984 -123.4218063354 -79.3935241699 152 1305031234.5616750717 146.8761444092 39.0633936447 160.3410339355 10.9867860576 0.0154780000 331568828 0 877051904 -2.1999320984 -123.4218063354 -79.3935241699 153 1305031234.5937800407 146.8739624023 39.7680378850 160.3410339355 10.9505872863 0.0110200000 331570582 0 877559808 -2.1999320984 -123.4218063354 -79.3935241699 154 1305031234.6300129890 146.8722686768 40.4635199031 160.3410339355 10.9147434174 0.0082540000 331572464 0 878202880 -2.1999320984 -123.4218063354 -79.3935241699 155 1305031234.6616179943 146.8706665039 41.1500176231 160.3410339355 10.8792490031 0.0128620000 331574250 0 878710784 -2.1999320984 -123.4218063354 -79.3935241699 156 1305031234.6937499046 146.8686370850 41.8277010812 160.3410339355 10.8441004524 0.0127140000 331576004 0 879218688 -2.1999320984 -123.4218063354 -79.3935241699 157 1305031234.7297639847 146.8674468994 42.4967440482 160.3410339355 10.8092886851 0.0099710000 331577854 0 879726592 -2.1999320984 -123.4218063354 -79.3935241699 158 1305031234.7618150711 146.8658447266 43.1573079766 160.3410339355 10.7748105426 0.0082230000 331579672 0 880234496 -2.1999320984 -123.4218063354 -79.3935241699 159 1305031234.7937159538 146.8647308350 43.8095559191 160.3410339355 10.7406600580 0.0130660000 331581426 0 880869376 -2.1999320984 -123.4218063354 -79.3935241699 160 1305031234.8297719955 145.8182220459 44.4471100823 160.3410339355 10.7086806249 0.0391950000 331660224 0 881377280 -2.8072099686 -123.0430755615 -78.0251235962 161 1305031234.8618729115 145.8177032471 45.0767410958 160.3410339355 10.6751639781 0.0356980000 334700518 0 884932608 -2.8072099686 -123.0430755615 -78.0251235962 162 1305031234.8937599659 145.8178405762 45.6985997346 160.3410339355 10.6419598999 0.0120770000 334702304 0 885567488 -2.8072099686 -123.0430755615 -78.0251235962 163 1305031234.9296660423 145.8189849854 46.3128352269 160.3410339355 10.6090636439 0.0098320000 334704122 0 886075392 -2.8072099686 -123.0430755615 -78.0251235962 164 1305031234.9616589546 145.8203887939 46.9195886023 160.3410339355 10.5764704794 0.0245260000 334782752 0 886583296 -2.8072099686 -123.0430755615 -78.0251235962 165 1305031234.9937489033 145.8232727051 47.5190048696 160.3410339355 10.5441768321 0.0152010000 335091750 0 887472128 -2.8072099686 -123.0430755615 -78.0251235962 166 1305031235.0297009945 145.8251037598 48.1112102846 160.3410339355 10.5121764319 0.0156160000 335093568 0 888107008 -2.8072099686 -123.0430755615 -78.0251235962 167 1305031235.0615909100 145.8275756836 48.6963382211 160.3410339355 10.4804664899 0.0082920000 335095386 0 888614912 -2.8072099686 -123.0430755615 -78.0251235962 168 1305031235.0936210155 145.8308258057 49.2745196948 160.3410339355 10.4490418946 0.0128840000 335097140 0 889249792 -2.8072099686 -123.0430755615 -78.0251235962 169 1305031235.1296789646 145.8329925537 49.8458716052 160.3410339355 10.4178973285 0.0162420000 335098990 0 889757696 -2.8072099686 -123.0430755615 -78.0251235962 170 1305031235.1614909172 145.8354797363 50.4105163590 160.3410339355 10.3870300862 0.0128250000 335100808 0 890265600 -2.8072099686 -123.0430755615 -78.0251235962 171 1305031235.1936049461 145.8391418457 50.9685784963 160.3410339355 10.3564363377 0.0179150000 335102562 0 890773504 -2.8072099686 -123.0430755615 -78.0251235962 172 1305031235.2296350002 145.8416595459 51.5201661768 160.3410339355 10.3261105807 0.0176810000 335104380 0 891408384 -2.8072099686 -123.0430755615 -78.0251235962 173 1305031235.2616291046 145.7857360840 52.0650538642 160.3410339355 10.2991216062 0.0402960000 335183082 0 891916288 -1.4790347815 -123.7783126831 -76.7800521851 174 1305031235.2936770916 145.7896423340 52.6037009243 160.3410339355 10.2693138483 0.0171250000 337224964 0 894455808 -1.4790347815 -123.7783126831 -76.7800521851 175 1305031235.3296489716 145.7930145264 53.1362112878 160.3410339355 10.2397628734 0.0111780000 337226814 0 895090688 -1.4790347815 -123.7783126831 -76.7800521851 176 1305031235.3616530895 145.7960205078 53.6626874765 160.3410339355 10.2104653686 0.0133100000 337228600 0 895598592 -1.4790347815 -123.7783126831 -76.7800521851 177 1305031235.3936860561 145.8003997803 54.1832395234 160.3410339355 10.1814186142 0.0088840000 337230386 0 896106496 -1.4790347815 -123.7783126831 -76.7800521851 178 1305031235.4296660423 127.6852188110 54.5961719913 160.3410339355 10.2704721577 0.0532520000 338537964 0 897884160 116.1982955933 -22.5211296082 -47.6233673096 179 1305031235.4616689682 127.6849975586 55.0044894526 160.3410339355 10.2415832110 0.0149300000 340272634 0 900169728 116.1982955933 -22.5211296082 -47.6233673096 180 1305031235.4936649799 127.6856842041 55.4082738679 160.3410339355 10.2129374590 0.0109520000 340274420 0 900804608 116.1982955933 -22.5211296082 -47.6233673096 181 1305031235.5297379494 127.6865005493 55.8076010871 160.3410339355 10.1845297003 0.0100080000 340276270 0 901312512 116.1982955933 -22.5211296082 -47.6233673096 182 1305031235.5616750717 127.6868743896 56.2025421492 160.3410339355 10.1563576078 0.0099480000 340278056 0 901947392 116.1982955933 -22.5211296082 -47.6233673096 183 1305031235.5937259197 127.6878890991 56.5931724604 160.3410339355 10.1284198726 0.0135120000 340279874 0 902455296 116.1982955933 -22.5211296082 -47.6233673096 184 1305031235.6297979355 127.6886291504 56.9795608120 160.3410339355 10.1007097440 0.0274200000 341894528 0 904486912 116.1982955933 -22.5211296082 -47.6233673096 185 1305031235.6616690159 127.6898422241 57.3617785494 160.3410339355 10.0732260627 0.0185710000 341896346 0 905121792 116.1982955933 -22.5211296082 -47.6233673096 186 1305031235.6936979294 127.6910781860 57.7398930635 160.3410339355 10.0459665294 0.0183410000 341898100 0 905629696 116.1982955933 -22.5211296082 -47.6233673096 187 1305031235.7296609879 127.6920242310 58.1139686313 160.3410339355 10.0189261209 0.0146760000 341899950 0 906264576 116.1982955933 -22.5211296082 -47.6233673096 188 1305031235.7618179321 127.6931381226 58.4840705967 160.3410339355 9.9921031747 0.0135580000 341901768 0 906772480 116.1982955933 -22.5211296082 -47.6233673096 189 1305031235.7936279774 127.6944351196 58.8502630015 160.3410339355 9.9654950680 0.0185150000 341903586 0 907280384 116.1982955933 -22.5211296082 -47.6233673096 190 1305031235.8296630383 127.6949844360 59.2126036407 160.3410339355 9.9390972939 0.0101630000 341905436 0 907788288 116.1982955933 -22.5211296082 -47.6233673096 191 1305031235.8616030216 127.6958160400 59.5711544909 160.3410339355 9.9129081262 0.0200290000 341907286 0 908423168 116.1982955933 -22.5211296082 -47.6233673096 192 1305031235.8936979771 127.6967926025 59.9259755228 160.3410339355 9.8869256429 0.0164210000 341909104 0 908931072 116.1982955933 -22.5211296082 -47.6233673096 193 1305031235.9296638966 127.6975097656 60.2771233686 160.3410339355 9.8611453134 0.0104750000 341910954 0 909565952 116.1982955933 -22.5211296082 -47.6233673096 194 1305031235.9617040157 127.6984252930 60.6246558527 160.3410339355 9.8355659458 0.0097740000 341912804 0 910200832 116.1982955933 -22.5211296082 -47.6233673096 195 1305031235.9936730862 127.6992263794 60.9686280093 160.3410339355 9.8101845821 0.0083690000 341914622 0 910708736 116.1982955933 -22.5211296082 -47.6233673096 196 1305031236.0296521187 127.7000045776 61.3090942163 160.3410339355 9.7849984235 0.0351940000 341993316 0 911343616 116.1982955933 -22.5211296082 -47.6233673096 197 1305031236.0616300106 127.7005004883 61.6461064308 160.3410339355 9.7600051942 0.0079640000 341995134 0 911851520 116.1982955933 -22.5211296082 -47.6233673096 198 1305031236.0936880112 127.7012176514 61.9797181037 160.3410339355 9.7352023515 0.0107640000 341996952 0 912359424 116.1982955933 -22.5211296082 -47.6233673096 199 1305031236.1296598911 127.7014694214 62.3099781605 160.3410339355 9.7105875622 0.0071520000 341998802 0 912994304 116.1982955933 -22.5211296082 -47.6233673096 200 1305031236.1616699696 127.7015075684 62.6369358076 160.3410339355 9.6861584573 0.0103680000 342000652 0 913502208 116.1982955933 -22.5211296082 -47.6233673096 201 1305031236.1935970783 127.7019119263 62.9606421564 160.3410339355 9.6619129255 0.0072920000 342002502 0 914010112 116.1982955933 -22.5211296082 -47.6233673096 202 1305031236.2297210693 127.7017364502 63.2811426232 160.3410339355 9.6378483570 0.0101980000 342004352 0 914644992 116.1982955933 -22.5211296082 -47.6233673096 203 1305031236.2616689205 127.7015838623 63.5984846983 160.3410339355 9.6139627224 0.0093100000 342006170 0 915152896 116.1982955933 -22.5211296082 -47.6233673096 204 1305031236.2936480045 127.7008438110 63.9127119489 160.3410339355 9.5902541313 0.0089920000 342008020 0 915660800 116.1982955933 -22.5211296082 -47.6233673096 205 1305031236.3296630383 127.7002563477 64.2238707020 160.3410339355 9.5667201081 0.0118500000 342009870 0 916168704 116.1982955933 -22.5211296082 -47.6233673096 206 1305031236.3615880013 127.6994400024 64.5320045336 160.3410339355 9.5433585175 0.0077070000 342011720 0 916803584 116.1982955933 -22.5211296082 -47.6233673096 207 1305031236.3936851025 127.6979370117 64.8371539658 160.3410339355 9.5201676578 0.0340130000 342090318 0 917311488 116.1982955933 -22.5211296082 -47.6233673096 208 1305031236.4296619892 127.6968154907 65.1393638770 160.3410339355 9.4971448961 0.0109250000 342092232 0 917946368 116.1982955933 -22.5211296082 -47.6233673096 209 1305031236.4616539478 127.6955795288 65.4386759136 160.3410339355 9.4742883384 0.0141960000 342094050 0 918454272 116.1982955933 -22.5211296082 -47.6233673096 210 1305031236.4936580658 127.6941375732 65.7351304930 160.3410339355 9.4515962938 0.0132370000 342095868 0 918962176 116.1982955933 -22.5211296082 -47.6233673096 211 1305031236.5296950340 127.6929550171 66.0287694717 160.3410339355 9.4290664138 0.0127360000 342097750 0 919470080 116.1982955933 -22.5211296082 -47.6233673096 212 1305031236.5616779327 127.6922531128 66.3196349606 160.3410339355 9.4066966117 0.0075140000 342099568 0 919977984 116.1982955933 -22.5211296082 -47.6233673096 213 1305031236.5936820507 127.6906051636 66.6077615813 160.3410339355 9.3844861874 0.0138750000 342101386 0 920612864 116.1982955933 -22.5211296082 -47.6233673096 214 1305031236.6296420097 127.6895675659 66.8931905812 160.3410339355 9.3624316407 0.0135300000 342103268 0 921120768 116.1982955933 -22.5211296082 -47.6233673096 215 1305031236.6616549492 127.6890716553 67.1759621211 160.3410339355 9.3405319406 0.0079040000 342105054 0 921628672 116.1982955933 -22.5211296082 -47.6233673096 216 1305031236.6936669350 127.6876678467 67.4561089069 160.3410339355 9.3187858572 0.0157720000 342106840 0 922136576 116.1982955933 -22.5211296082 -47.6233673096 217 1305031236.7296929359 127.6868667603 67.7336700030 160.3410339355 9.2971901332 0.0138210000 342108658 0 922771456 116.1982955933 -22.5211296082 -47.6233673096 218 1305031236.7617490292 127.6860961914 68.0086811323 160.3410339355 9.2757440246 0.0076300000 342110476 0 923279360 116.1982955933 -22.5211296082 -47.6233673096 219 1305031236.7936749458 127.6852416992 68.2811768426 160.3410339355 9.2544463967 0.0075660000 342112230 0 923787264 116.1982955933 -22.5211296082 -47.6233673096 220 1305031236.8297049999 127.6844940186 68.5511919207 160.3410339355 9.2332940702 0.0117110000 342114080 0 924295168 116.1982955933 -22.5211296082 -47.6233673096 221 1305031236.8616170883 127.6837539673 68.8187600747 160.3410339355 9.2122862657 0.0078310000 342115898 0 924930048 116.1982955933 -22.5211296082 -47.6233673096 222 1305031236.8935050964 127.6827392578 69.0839131341 160.3410339355 9.1914217469 0.0142670000 342117684 0 925437952 116.1982955933 -22.5211296082 -47.6233673096 223 1305031236.9296689034 127.6817855835 69.3466838626 160.3410339355 9.1706978558 0.0078550000 342119534 0 925945856 116.1982955933 -22.5211296082 -47.6233673096 224 1305031236.9616389275 127.6809997559 69.6071049157 160.3410339355 9.1501138210 0.0075800000 342121320 0 926453760 116.1982955933 -22.5211296082 -47.6233673096 225 1305031236.9936800003 127.6794891357 69.8652044011 160.3410339355 9.1296678526 0.0110150000 342123074 0 926961664 116.1982955933 -22.5211296082 -47.6233673096 226 1305031237.0297141075 127.6785812378 70.1210158030 160.3410339355 9.1093583590 0.0107980000 342124924 0 927596544 116.1982955933 -22.5211296082 -47.6233673096 227 1305031237.0617289543 127.6772537231 70.3745675119 160.3410339355 9.0891832916 0.0121530000 342126742 0 928104448 116.1982955933 -22.5211296082 -47.6233673096 228 1305031237.0936949253 127.6757354736 70.6258884241 160.3410339355 9.0691425012 0.0076820000 342128496 0 928612352 116.1982955933 -22.5211296082 -47.6233673096 229 1305031237.1297740936 127.6735382080 70.8750047987 160.3410339355 9.0492333761 0.0148040000 342130346 0 929247232 116.1982955933 -22.5211296082 -47.6233673096 230 1305031237.1616609097 127.6715698242 71.1219463857 160.3410339355 9.0294543486 0.0187310000 342132164 0 929755136 116.1982955933 -22.5211296082 -47.6233673096 231 1305031237.1936419010 127.6686630249 71.3667373669 160.3410339355 9.0098050338 0.0113270000 342133950 0 930263040 116.1982955933 -22.5211296082 -47.6233673096 232 1305031237.2296910286 127.6667785645 71.6094099582 160.3410339355 8.9902828857 0.0306880000 342212612 0 930770944 116.1982955933 -22.5211296082 -47.6233673096 233 1305031237.2616629601 127.6650238037 71.8499919919 160.3410339355 8.9708867353 0.0103240000 342214398 0 931405824 116.1982955933 -22.5211296082 -47.6233673096 234 1305031237.2937090397 127.6627426147 72.0885080202 160.3410339355 8.9516163804 0.0106400000 342216184 0 932040704 116.1982955933 -22.5211296082 -47.6233673096 235 1305031237.3296720982 127.6608428955 72.3249860409 160.3410339355 8.9324691039 0.0064110000 342218002 0 932548608 116.1982955933 -22.5211296082 -47.6233673096 236 1305031237.3616180420 127.6601715088 72.5594571658 160.3410339355 8.9134447618 0.0100920000 342219820 0 933056512 116.1982955933 -22.5211296082 -47.6233673096 237 1305031237.3936710358 127.6585464478 72.7919427746 160.3410339355 8.8945410418 0.0069890000 342221574 0 933564416 116.1982955933 -22.5211296082 -47.6233673096 238 1305031237.4297928810 127.6572113037 73.0224691129 160.3410339355 8.8757565788 0.0133440000 342223424 0 934199296 116.1982955933 -22.5211296082 -47.6233673096 239 1305031237.4616460800 127.6558074951 73.2510604869 160.3410339355 8.8570910188 0.0113740000 342225242 0 934707200 116.1982955933 -22.5211296082 -47.6233673096 240 1305031237.4937019348 127.6548080444 73.4777427684 160.3410339355 8.8385426908 0.0112230000 342226996 0 935215104 116.1982955933 -22.5211296082 -47.6233673096 241 1305031237.5297350883 127.6537628174 73.7025395321 160.3410339355 8.8201100740 0.0098850000 342228846 0 935723008 116.1982955933 -22.5211296082 -47.6233673096 242 1305031237.5616691113 112.6001663208 73.8632735271 160.3410339355 8.8952062221 0.0476080000 342307580 0 936230912 27.1500473022 -103.9922485352 33.5031738281 243 1305031237.5936799049 112.6003265381 74.0226852679 160.3410339355 8.8768087859 0.0146610000 344042218 0 938516480 27.1500473022 -103.9922485352 33.5031738281 244 1305031237.6297049522 112.6003799438 74.1807905739 160.3410339355 8.8585250060 0.0123640000 344351280 0 939405312 27.1500473022 -103.9922485352 33.5031738281 245 1305031237.6616559029 112.6003189087 74.3376049753 160.3410339355 8.8403536560 0.0067770000 344353098 0 940040192 27.1500473022 -103.9922485352 33.5031738281 246 1305031237.6936929226 112.5997238159 74.4931420438 160.3410339355 8.8222938238 0.0065500000 344354884 0 940548096 27.1500473022 -103.9922485352 33.5031738281 247 1305031237.7297520638 112.5995712280 74.6474190850 160.3410339355 8.8043441355 0.0065440000 344356734 0 941056000 27.1500473022 -103.9922485352 33.5031738281 248 1305031237.7616539001 112.5992279053 74.8004505722 160.3410339355 8.7865035052 0.0087810000 344358520 0 941563904 27.1500473022 -103.9922485352 33.5031738281 249 1305031237.7937250137 112.5988998413 74.9522515733 160.3410339355 8.7687710585 0.0100170000 344360274 0 942198784 27.1500473022 -103.9922485352 33.5031738281 250 1305031237.8297688961 112.6809234619 75.1031662608 160.3410339355 8.7516348061 0.0415960000 345667852 0 943976448 28.1027870178 -104.0159683228 32.9135627747 251 1305031237.8618359566 112.6805953979 75.2528771339 160.3410339355 8.7341140212 0.0169380000 347402554 0 946135040 28.1027870178 -104.0159683228 32.9135627747 252 1305031237.8937709332 112.6804122925 75.4013990988 160.3410339355 8.7166982953 0.0109390000 347404308 0 946769920 28.1027870178 -104.0159683228 32.9135627747 253 1305031237.9298489094 112.6802673340 75.5487464041 160.3410339355 8.6993863671 0.0074180000 347406158 0 947277824 28.1027870178 -104.0159683228 32.9135627747 254 1305031237.9616580009 112.6797485352 75.6949314518 160.3410339355 8.6821770638 0.0107580000 347407944 0 947785728 28.1027870178 -104.0159683228 32.9135627747 255 1305031237.9936830997 112.6795883179 75.8399693219 160.3410339355 8.6650702270 0.0288590000 348715322 0 949563392 28.1027870178 -104.0159683228 32.9135627747 256 1305031238.0297091007 112.6796569824 75.9838743518 160.3410339355 8.6480638261 0.0074640000 348717172 0 950198272 28.1027870178 -104.0159683228 32.9135627747 257 1305031238.0616700649 112.6801681519 76.1266614872 160.3410339355 8.6311579976 0.0093020000 348718990 0 950833152 28.1027870178 -104.0159683228 32.9135627747 258 1305031238.0936849117 112.6809844971 76.2683449097 160.3410339355 8.6143527862 0.0077370000 348762760 0 951341056 28.1027870178 -104.0159683228 32.9135627747 259 1305031238.1297469139 112.6818313599 76.4089375215 160.3410339355 8.5976434482 0.0149540000 348764610 0 951975936 28.1027870178 -104.0159683228 32.9135627747 260 1305031238.1616818905 112.6828994751 76.5484527598 160.3410339355 8.5810323989 0.0081770000 348766396 0 952483840 28.1027870178 -104.0159683228 32.9135627747 261 1305031238.1937921047 112.6847305298 76.6869059313 160.3410339355 8.5645175932 0.0145450000 348768182 0 952991744 28.1027870178 -104.0159683228 32.9135627747 262 1305031238.2300119400 112.6858749390 76.8243065764 160.3410339355 8.5480959927 0.0110360000 348770032 0 953499648 28.1027870178 -104.0159683228 32.9135627747 263 1305031238.2616040707 112.6873779297 76.9606680644 160.3410339355 8.5317686306 0.0101090000 348771818 0 954134528 28.1027870178 -104.0159683228 32.9135627747 264 1305031238.2936708927 112.6901397705 77.0960069724 160.3410339355 8.5155370125 0.0318620000 348850416 0 954642432 28.1027870178 -104.0159683228 32.9135627747 265 1305031238.3296620846 112.6919784546 77.2303313931 160.3410339355 8.4993953641 0.0135920000 349159478 0 955404288 28.1027870178 -104.0159683228 32.9135627747 266 1305031238.3616399765 112.6938552856 77.3636529115 160.3410339355 8.4833447003 0.0092130000 349161264 0 956039168 28.1027870178 -104.0159683228 32.9135627747 267 1305031238.3936669827 112.6971359253 77.4959880539 160.3410339355 8.4673865099 0.0087500000 349163050 0 956674048 28.1027870178 -104.0159683228 32.9135627747 268 1305031238.4296729565 112.6993942261 77.6273440470 160.3410339355 8.4515161032 0.0164390000 349164900 0 957181952 28.1027870178 -104.0159683228 32.9135627747 269 1305031238.4616849422 112.7017517090 77.7577321796 160.3410339355 8.4357346084 0.0169090000 349166686 0 957689856 28.1027870178 -104.0159683228 32.9135627747 270 1305031238.4936790466 112.7042999268 77.8871639120 160.3410339355 8.4200412549 0.0080310000 349168472 0 958324736 28.1027870178 -104.0159683228 32.9135627747 271 1305031238.5296700001 112.7063140869 78.0156478610 160.3410339355 8.4044344335 0.0121200000 349170322 0 958832640 28.1027870178 -104.0159683228 32.9135627747 272 1305031238.5616240501 112.7083129883 78.1431944240 160.3410339355 8.3889143507 0.0126380000 349172108 0 959340544 28.1027870178 -104.0159683228 32.9135627747 273 1305031238.5937409401 112.7116851807 78.2698189322 160.3410339355 8.3734803838 0.0139770000 349173862 0 959848448 28.1027870178 -104.0159683228 32.9135627747 274 1305031238.6297509670 112.7139739990 78.3955275274 160.3410339355 8.3581307415 0.0078700000 349175712 0 960483328 28.1027870178 -104.0159683228 32.9135627747 275 1305031238.6616280079 112.7164688110 78.5203309502 160.3410339355 8.3428652692 0.0116640000 349177530 0 960991232 28.1027870178 -104.0159683228 32.9135627747 276 1305031238.6938550472 112.7197494507 78.6442418868 160.3410339355 8.3276836609 0.0109480000 349179316 0 961499136 28.1027870178 -104.0159683228 32.9135627747 277 1305031238.7297289371 113.1074676514 78.7686578643 160.3410339355 8.3127849846 0.0522220000 349258082 0 962007040 27.9793529510 -104.3485183716 33.2858924866 278 1305031238.7616579533 113.1097946167 78.8921871332 160.3410339355 8.2977666363 0.0126800000 350992784 0 964292608 27.9793529510 -104.3485183716 33.2858924866 279 1305031238.7936909199 113.1128463745 79.0148418258 160.3410339355 8.2828299713 0.0088920000 350994538 0 964927488 27.9793529510 -104.3485183716 33.2858924866 280 1305031238.8297300339 113.1151962280 79.1366288058 160.3410339355 8.2679733307 0.0121870000 350996452 0 965435392 27.9793529510 -104.3485183716 33.2858924866 281 1305031238.8618259430 113.1168899536 79.2575550021 160.3410339355 8.2531960133 0.0119600000 351305482 0 966197248 27.9793529510 -104.3485183716 33.2858924866 282 1305031238.8937339783 113.1188964844 79.3776306811 160.3410339355 8.2384976541 0.0143430000 351307300 0 966832128 27.9793529510 -104.3485183716 33.2858924866 283 1305031238.9298369884 113.1203842163 79.4968630257 160.3410339355 8.2238775784 0.0103340000 351309182 0 967340032 27.9793529510 -104.3485183716 33.2858924866 284 1305031238.9616560936 113.1216964722 79.6152603266 160.3410339355 8.2093350258 0.0079580000 351311000 0 967974912 27.9793529510 -104.3485183716 33.2858924866 285 1305031238.9937040806 113.1236038208 79.7328334617 160.3410339355 8.1948694799 0.0079060000 351312818 0 968482816 27.9793529510 -104.3485183716 33.2858924866 286 1305031239.0296700001 113.1248016357 79.8495885951 160.3410339355 8.1804800189 0.0081710000 351314700 0 968990720 27.9793529510 -104.3485183716 33.2858924866 287 1305031239.0616769791 113.1257400513 79.9655333737 160.3410339355 8.1661659720 0.0126760000 351316518 0 969498624 27.9793529510 -104.3485183716 33.2858924866 288 1305031239.0936889648 113.1244277954 80.0806684238 160.3410339355 8.1520157811 0.0534830000 352624096 0 971276288 27.9534130096 -104.3939819336 33.1574172974 289 1305031239.1297380924 113.1244125366 80.1950066387 160.3410339355 8.1378506808 0.0168720000 354666042 0 973815808 27.9534130096 -104.3939819336 33.1574172974 290 1305031239.1617560387 113.1241531372 80.3085554198 160.3410339355 8.1237593097 0.0438600000 355973516 0 975720448 27.9534130096 -104.3939819336 33.1574172974 291 1305031239.1937060356 113.1235427856 80.4213216994 160.3410339355 8.1097407750 0.0067750000 355975334 0 976355328 27.9534130096 -104.3939819336 33.1574172974 292 1305031239.2298820019 113.1231231689 80.5333141702 160.3410339355 8.0957946045 0.0065890000 355977216 0 976863232 27.9534130096 -104.3939819336 33.1574172974 293 1305031239.2617208958 113.1222534180 80.6445392188 160.3410339355 8.0819202588 0.0135340000 355979034 0 977301504 27.9534130096 -104.3939819336 33.1574172974 294 1305031239.2936739922 113.1208648682 80.7550029115 160.3410339355 8.0681172339 0.0119790000 355980884 0 977920000 27.9534130096 -104.3939819336 33.1574172974 295 1305031239.3297049999 113.1195678711 80.8647133012 160.3410339355 8.0543844855 0.0208280000 355982734 0 978427904 27.9534130096 -104.3939819336 33.1574172974 296 1305031239.3617150784 113.1184844971 80.9736787444 160.3410339355 8.0407217352 0.0311540000 356061364 0 978935808 27.9534130096 -104.3939819336 33.1574172974 297 1305031239.3937180042 113.1170883179 81.0819057127 160.3410339355 8.0271284838 0.0161030000 356063150 0 979570688 27.9534130096 -104.3939819336 33.1574172974 298 1305031239.4297440052 113.1154785156 81.1894009234 160.3410339355 8.0136040149 0.0153760000 356065000 0 980078592 27.9534130096 -104.3939819336 33.1574172974 299 1305031239.4617080688 113.1141586304 81.2961726883 160.3410339355 8.0001474764 0.0133950000 356066818 0 980586496 27.9534130096 -104.3939819336 33.1574172974 300 1305031239.4937200546 113.1125183105 81.4022271737 160.3410339355 7.9867586269 0.0153100000 356068572 0 981221376 27.9534130096 -104.3939819336 33.1574172974 301 1305031239.5296618938 113.1110610962 81.5075721369 160.3410339355 7.9734367915 0.0224530000 356070422 0 981729280 27.9534130096 -104.3939819336 33.1574172974 302 1305031239.5617330074 113.1093597412 81.6122138177 160.3410339355 7.9601813039 0.0105090000 356072240 0 982237184 27.9534130096 -104.3939819336 33.1574172974 303 1305031239.5939209461 113.1072463989 81.7161578196 160.3410339355 7.9469921008 0.0157200000 356073994 0 982745088 27.9534130096 -104.3939819336 33.1574172974 304 1305031239.6297230721 113.1054000854 81.8194119060 160.3410339355 7.9338680202 0.0149960000 356075844 0 983252992 27.9534130096 -104.3939819336 33.1574172974 305 1305031239.6616590023 113.1036987305 81.9219833383 160.3410339355 7.9208085223 0.0191860000 356077662 0 983830528 27.9534130096 -104.3939819336 33.1574172974 306 1305031239.6937329769 113.1013107300 82.0238765650 160.3410339355 7.9078138313 0.0109380000 356079448 0 984338432 27.9534130096 -104.3939819336 33.1574172974 307 1305031239.7298939228 113.1379470825 82.1252253289 160.3410339355 7.8976546167 0.0485590000 356158182 0 984846336 27.4038200378 -104.8486785889 32.3016586304 308 1305031239.7619130611 113.1355361938 82.2259081564 160.3410339355 7.8847824859 0.0169560000 357585672 0 986877952 27.4038200378 -104.8486785889 32.3016586304 309 1305031239.7935850620 100.7357711792 82.2858106257 160.3410339355 7.9155300730 0.0403650000 359200398 0 989036544 19.3017387390 -98.0527648926 12.1937026978 310 1305031239.8296658993 100.7326507568 82.3453165616 160.3410339355 7.9027125109 0.0263350000 362547904 0 992845824 19.3017387390 -98.0527648926 12.1937026978 311 1305031239.8616919518 100.7293930054 82.4044293476 160.3410339355 7.8899569642 0.0173580000 362856902 0 993734656 19.3017387390 -98.0527648926 12.1937026978 312 1305031239.8937399387 100.7259597778 82.4631522016 160.3410339355 7.8772632135 0.0095810000 362858688 0 994369536 19.3017387390 -98.0527648926 12.1937026978 313 1305031239.9297060966 100.7230300903 82.5214904696 160.3410339355 7.8646297951 0.0116750000 362860538 0 994877440 19.3017387390 -98.0527648926 12.1937026978 314 1305031239.9617099762 100.7204437256 82.5794489195 160.3410339355 7.8520569374 0.0106300000 362862356 0 995512320 19.3017387390 -98.0527648926 12.1937026978 315 1305031239.9936909676 100.7168045044 82.6370278261 160.3410339355 7.8395449967 0.0168340000 362864142 0 996020224 19.3017387390 -98.0527648926 12.1937026978 316 1305031240.0296199322 100.7144393921 82.6942348247 160.3410339355 7.8270920810 0.0112810000 362865992 0 996528128 19.3017387390 -98.0527648926 12.1937026978 317 1305031240.0619289875 100.7124862671 82.7510747346 160.3410339355 7.8146982624 0.0196200000 362867778 0 997163008 19.3017387390 -98.0527648926 12.1937026978 318 1305031240.0936510563 100.7099914551 82.8075493155 160.3410339355 7.8023639614 0.0113200000 362869532 0 997670912 19.3017387390 -98.0527648926 12.1937026978 319 1305031240.1296648979 100.7081375122 82.8636640120 160.3410339355 7.7900879174 0.0288540000 362948194 0 998178816 19.3017387390 -98.0527648926 12.1937026978 320 1305031240.1617228985 100.7068405151 82.9194239386 160.3410339355 7.7778687285 0.0162800000 362949980 0 998813696 19.3017387390 -98.0527648926 12.1937026978 321 1305031240.1936759949 100.7049102783 82.9748304381 160.3410339355 7.7657083757 0.0287490000 363028578 0 999321600 19.3017387390 -98.0527648926 12.1937026978 322 1305031240.2296609879 100.7034454346 83.0298882487 160.3410339355 7.7536044349 0.0214350000 363030396 0 999956480 19.3017387390 -98.0527648926 12.1937026978 323 1305031240.2616999149 100.7027816772 83.0846030890 160.3410339355 7.7415557850 0.0106830000 363032214 0 1000591360 19.3017387390 -98.0527648926 12.1937026978 324 1305031240.2936460972 100.7016220093 83.1389766042 160.3410339355 7.7295644923 0.0154920000 363033968 0 1001099264 19.3017387390 -98.0527648926 12.1937026978 325 1305031240.3296699524 100.7011489868 83.1930140577 160.3410339355 7.7176275665 0.0146250000 363035818 0 1001607168 19.3017387390 -98.0527648926 12.1937026978 326 1305031240.3616850376 100.7002410889 83.2467172081 160.3410339355 7.7057456028 0.0128340000 363037636 0 1002115072 19.3017387390 -98.0527648926 12.1937026978 327 1305031240.3936951160 100.6996002197 83.3000899390 160.3410339355 7.6939189528 0.0148750000 363039390 0 1002749952 19.3017387390 -98.0527648926 12.1937026978 328 1305031240.4297070503 100.6987533569 83.3531346445 160.3410339355 7.6821458276 0.0159590000 363041240 0 1003257856 19.3017387390 -98.0527648926 12.1937026978 329 1305031240.4616730213 100.6979904175 83.4058545709 160.3410339355 7.6704264677 0.0110860000 363043058 0 1003765760 19.3017387390 -98.0527648926 12.1937026978 330 1305031240.4937129021 100.6976318359 83.4582538959 160.3410339355 7.6587606094 0.0100550000 363044844 0 1004273664 19.3017387390 -98.0527648926 12.1937026978 331 1305031240.5296719074 100.6972351074 83.5103354102 160.3410339355 7.6471476854 0.0130180000 363046662 0 1004781568 19.3017387390 -98.0527648926 12.1937026978 332 1305031240.5617480278 100.6965942383 83.5621012500 160.3410339355 7.6355873895 0.0101780000 363048480 0 1005289472 19.3017387390 -98.0527648926 12.1937026978 333 1305031240.5936789513 100.6329345703 83.6133650137 160.3410339355 7.6241454292 0.0363650000 363127182 0 1005924352 19.4127254486 -97.9552459717 12.2777223587 334 1305031240.6310579777 100.6326599121 83.6643209865 160.3410339355 7.6126893899 0.0256520000 364861916 0 1008082944 19.4127254486 -97.9552459717 12.2777223587 335 1305031240.6616289616 100.6328582764 83.7149733366 160.3410339355 7.6012848855 0.0092880000 364863702 0 1008717824 19.4127254486 -97.9552459717 12.2777223587 336 1305031240.6937999725 85.2550811768 83.7195569909 160.3410339355 7.9338637462 0.0531720000 366171184 0 1010495488 20.4917545319 61.1870002747 -55.6656265259 337 1305031240.7296330929 85.2562408447 83.7241168836 160.3410339355 7.9220491888 0.0372860000 369518754 0 1014304768 20.4917545319 61.1870002747 -55.6656265259 338 1305031240.7616069317 85.2569732666 83.7286519617 160.3410339355 7.9102867943 0.0171600000 369827752 0 1015193600 20.4917545319 61.1870002747 -55.6656265259 339 1305031240.7935900688 73.3968582153 83.6981746940 160.3410339355 8.2981128713 0.0422430000 369906454 0 1015828480 22.8476142883 -39.5829200745 57.4333572388 340 1305031240.8296198845 73.3958663940 83.6678737872 160.3410339355 8.2858656483 0.0105400000 371641188 0 1017987072 22.8476142883 -39.5829200745 57.4333572388 341 1305031240.8616340160 73.3946380615 83.6377469963 160.3410339355 8.2736720952 0.0093280000 371642974 0 1018621952 22.8476142883 -39.5829200745 57.4333572388 342 1305031240.8936851025 73.3934173584 83.6077928160 160.3410339355 8.2615327086 0.0136660000 371644760 0 1019256832 22.8476142883 -39.5829200745 57.4333572388 343 1305031240.9296729565 73.3920593262 83.5780093365 160.3410339355 8.2494469534 0.0172070000 371953822 0 1020018688 22.8476142883 -39.5829200745 57.4333572388 344 1305031240.9617090225 73.3911895752 83.5483964883 160.3410339355 8.2374141352 0.0133620000 371955576 0 1020653568 22.8476142883 -39.5829200745 57.4333572388 345 1305031240.9936430454 73.3890762329 83.5189491832 160.3410339355 8.2254339362 0.0143170000 371957330 0 1021161472 22.8476142883 -39.5829200745 57.4333572388 346 1305031241.0296230316 73.3881683350 83.4896694698 160.3410339355 8.2135063522 0.0097680000 371959212 0 1021669376 22.8476142883 -39.5829200745 57.4333572388 347 1305031241.0619900227 73.3865814209 83.4605539423 160.3410339355 8.2016292563 0.0219190000 371960998 0 1022177280 22.8476142883 -39.5829200745 57.4333572388 348 1305031241.0936150551 73.3858184814 83.4316035530 160.3410339355 8.1898048607 0.0098790000 371962784 0 1022812160 22.8476142883 -39.5829200745 57.4333572388 349 1305031241.1297609806 73.3847808838 83.4028160955 160.3410339355 8.1780303481 0.0127990000 371964602 0 1023320064 22.8476142883 -39.5829200745 57.4333572388 350 1305031241.1617250443 73.3838958740 83.3741906092 160.3410339355 8.1663066207 0.0185740000 371966420 0 1023827968 22.8476142883 -39.5829200745 57.4333572388 351 1305031241.1937139034 73.3836975098 83.3457276659 160.3410339355 8.1546347629 0.0168980000 371968174 0 1024335872 22.8476142883 -39.5829200745 57.4333572388 352 1305031241.2296020985 73.3836059570 83.3174261837 160.3410339355 8.1430110531 0.0108940000 371970024 0 1024843776 22.8476142883 -39.5829200745 57.4333572388 353 1305031241.2616620064 73.3839111328 83.2892859145 160.3410339355 8.1314364693 0.0098000000 371971810 0 1025478656 22.8476142883 -39.5829200745 57.4333572388 354 1305031241.2938039303 73.3851394653 83.2613080997 160.3410339355 8.1199123336 0.0100400000 371973596 0 1025986560 22.8476142883 -39.5829200745 57.4333572388 355 1305031241.3299100399 73.3863067627 83.2334911945 160.3410339355 8.1084364146 0.0146730000 371975446 0 1026494464 22.8476142883 -39.5829200745 57.4333572388 356 1305031241.3616580963 73.3884658813 83.2058366290 160.3410339355 8.0970087728 0.0126560000 371977264 0 1027002368 22.8476142883 -39.5829200745 57.4333572388 357 1305031241.3937180042 73.3910598755 83.1783442571 160.3410339355 8.0856294360 0.0258110000 373284674 0 1028780032 22.8476142883 -39.5829200745 57.4333572388 358 1305031241.4296689034 74.0175247192 83.1527553757 160.3410339355 8.0745012565 0.0395870000 374592220 0 1030557696 23.1291561127 -39.5096359253 58.1681098938 359 1305031241.4616780281 74.0189285278 83.1273129611 160.3410339355 8.0632163308 0.0142510000 376634102 0 1033224192 23.1291561127 -39.5096359253 58.1681098938 360 1305031241.4937360287 73.9745559692 83.1018886361 160.3410339355 8.0524611487 0.0377380000 376712804 0 1033859072 22.6606483459 -39.3082618713 58.4311637878 361 1305031241.5297579765 73.9750671387 83.0766065821 160.3410339355 8.0412694331 0.0148650000 378447538 0 1036144640 22.6606483459 -39.3082618713 58.4311637878 362 1305031241.5616860390 73.9752349854 83.0514646716 160.3410339355 8.0301242367 0.0095170000 378449324 0 1036779520 22.6606483459 -39.3082618713 58.4311637878 363 1305031241.5936799049 73.9755401611 83.0264621248 160.3410339355 8.0190252762 0.0094210000 378451078 0 1037287424 22.6606483459 -39.3082618713 58.4311637878 364 1305031241.6297600269 73.9761581421 83.0015986523 160.3410339355 8.0079722788 0.0120680000 378452928 0 1037922304 22.6606483459 -39.3082618713 58.4311637878 365 1305031241.6616580486 73.9761810303 82.9768714807 160.3410339355 7.9969647969 0.0406330000 380067582 0 1039953920 22.6606483459 -39.3082618713 58.4311637878 366 1305031241.6936290264 73.9763412476 82.9522798681 160.3410339355 7.9860025579 0.0219260000 381374960 0 1041731584 22.6606483459 -39.3082618713 58.4311637878 367 1305031241.7297000885 73.9761810303 82.9278218331 160.3410339355 7.9750852734 0.0247840000 381453622 0 1042366464 22.6606483459 -39.3082618713 58.4311637878 368 1305031241.7616779804 73.1419982910 82.9012299213 160.3410339355 7.9647221475 0.0347290000 381532356 0 1043001344 21.6837806702 -39.2060241699 57.8170089722 369 1305031241.7936940193 85.1891326904 82.9074301998 160.3410339355 8.0942463645 0.0386750000 384879934 0 1046937600 -82.5944061279 20.3613662720 -5.4509124756 370 1305031241.8297588825 84.6387786865 82.9121095200 160.3410339355 8.0835408692 0.0383770000 388227608 0 1050746880 -82.1250610352 19.9531402588 -5.4778323174 371 1305031241.8616719246 84.6381759644 82.9167619902 160.3410339355 8.0726098760 0.0146590000 390269522 0 1053286400 -82.1250610352 19.9531402588 -5.4778323174 372 1305031241.8936219215 84.6368484497 82.9213858786 160.3410339355 8.0617231844 0.0117720000 390271340 0 1053921280 -82.1250610352 19.9531402588 -5.4778323174 373 1305031241.9296860695 84.6357879639 82.9259821308 160.3410339355 8.0508803079 0.0103070000 390273126 0 1054429184 -82.1250610352 19.9531402588 -5.4778323174 374 1305031241.9616849422 84.6345977783 82.9305506219 160.3410339355 8.0400810109 0.0087250000 390274944 0 1055064064 -82.1250610352 19.9531402588 -5.4778323174 375 1305031241.9936869144 84.6325607300 82.9350893155 160.3410339355 8.0293254010 0.0151720000 390276698 0 1055571968 -82.1250610352 19.9531402588 -5.4778323174 376 1305031242.0297560692 84.6314239502 82.9396008438 160.3410339355 8.0186126929 0.0112170000 390278548 0 1056079872 -82.1250610352 19.9531402588 -5.4778323174 377 1305031242.0616540909 84.6297760010 82.9440840670 160.3410339355 8.0079427763 0.0208250000 390357178 0 1056587776 -82.1250610352 19.9531402588 -5.4778323174 378 1305031242.0937249660 84.6986160278 82.9487256859 160.3410339355 8.0005390005 0.0381420000 391664660 0 1058492416 -82.0703964233 20.9758033752 -3.1042695045 379 1305031242.1296820641 87.9604949951 82.9619493517 160.3410339355 7.9929163621 0.0480010000 395012334 0 1062301696 -84.9204864502 23.0519828796 -2.5080204010 380 1305031242.1616680622 87.9595031738 82.9751008091 160.3410339355 7.9823648358 0.0107650000 396747036 0 1064587264 -84.9204864502 23.0519828796 -2.5080204010 381 1305031242.1936829090 78.1156692505 82.9623463955 160.3410339355 7.9880653498 0.0370660000 396825706 0 1065222144 -72.2439880371 29.8695888519 -1.6211289167 382 1305031242.2296719551 45.2657661438 82.8636642483 160.3410339355 8.1477322286 0.0420790000 400173380 0 1069158400 -42.0324134827 9.7335720062 -13.8476305008 383 1305031242.2618839741 57.4323196411 82.7972638707 160.3410339355 8.1610973900 0.0325470000 403521022 0 1073094656 -52.0860939026 13.7371282578 -20.0409908295 384 1305031242.2938199043 58.2326583862 82.7332935439 160.3410339355 8.1505692532 0.0301660000 406868600 0 1077030912 -52.6887855530 14.0180110931 -20.5729236603 385 1305031242.3298890591 58.2328720093 82.6696560854 160.3410339355 8.1399496489 0.0136740000 408910578 0 1079697408 -52.6887855530 14.0180110931 -20.5729236603 386 1305031242.3617289066 59.1446990967 82.6087106010 160.3410339355 8.1295405637 0.0396770000 410525304 0 1081856000 -53.3708343506 14.3716049194 -21.1632480621 387 1305031242.3936789036 59.9444084167 82.5501465126 160.3410339355 8.1191102347 0.0474230000 413872946 0 1085665280 -54.0201339722 14.6618938446 -21.5644359589 388 1305031242.4297111034 59.9437637329 82.4918826395 160.3410339355 8.1086136932 0.0094230000 415607648 0 1087950848 -54.0201339722 14.6618938446 -21.5644359589 389 1305031242.4616949558 59.9427986145 82.4339158425 160.3410339355 8.0981578184 0.0120090000 415609466 0 1088585728 -54.0201339722 14.6618938446 -21.5644359589 390 1305031242.4937419891 59.9403839111 82.3762401196 160.3410339355 8.0877422569 0.0097180000 415611284 0 1089220608 -54.0201339722 14.6618938446 -21.5644359589 391 1305031242.5297100544 59.9379882812 82.3188532863 160.3410339355 8.0773668504 0.0091580000 415613134 0 1089728512 -54.0201339722 14.6618938446 -21.5644359589 392 1305031242.5615689754 59.8751716614 82.2615989964 160.3410339355 8.0670638735 0.0353890000 416920648 0 1091506176 -53.9490394592 14.5599346161 -21.6424770355 393 1305031242.5936930180 57.4465751648 82.1984564421 160.3410339355 8.0590050806 0.0314740000 420268290 0 1095315456 -29.1131076813 47.4880332947 14.4156093597 394 1305031242.6297109127 58.9540481567 82.1394604820 160.3410339355 8.0492096710 0.0756210000 423615964 0 1099251712 -29.4907970428 49.0153999329 14.6293706894 395 1305031242.6617820263 100.2943191528 82.1854221495 160.3410339355 8.3547778940 0.0293720000 426963606 0 1103060992 23.7344608307 97.4375000000 -2.3583736420 396 1305031242.6936709881 100.2941741943 82.2311513214 160.3410339355 8.3441961900 0.0089510000 428698340 0 1105346560 23.7344608307 97.4375000000 -2.3583736420 397 1305031242.7297909260 102.2433319092 82.2815598367 160.3410339355 8.3346326041 0.0307560000 430313130 0 1107505152 25.2950038910 99.0461425781 -2.7812237740 398 1305031242.7619299889 102.2430267334 82.3317142761 160.3410339355 8.3241291961 0.0565760000 433660668 0 1111441408 25.2950038910 99.0461425781 -2.7812237740 399 1305031242.7936990261 102.2419662476 82.3816146570 160.3410339355 8.3136656449 0.0173720000 433969698 0 1112330240 25.2950038910 99.0461425781 -2.7812237740 400 1305031242.8298120499 102.2404327393 82.4312617022 160.3410339355 8.3032413903 0.0103880000 433971580 0 1112838144 25.2950038910 99.0461425781 -2.7812237740 401 1305031242.8616819382 102.2382354736 82.4806556518 160.3410339355 8.2928561992 0.0144060000 433973398 0 1113473024 25.2950038910 99.0461425781 -2.7812237740 402 1305031242.8936789036 102.2344894409 82.5297945418 160.3410339355 8.2825100822 0.0083550000 433975216 0 1113980928 25.2950038910 99.0461425781 -2.7812237740 403 1305031242.9296770096 102.2312622070 82.5786815584 160.3410339355 8.2722022727 0.0129700000 433977130 0 1114615808 25.2950038910 99.0461425781 -2.7812237740 404 1305031242.9617309570 102.2280349731 82.6273185718 160.3410339355 8.2619330282 0.0122890000 433978948 0 1115123712 25.2950038910 99.0461425781 -2.7812237740 405 1305031242.9939510822 318.8058471680 83.2104754325 318.8058471680 13.7238609031 0.0352860000 434057682 0 1115631616 -38.1943244934 312.8952331543 -48.0346412659 406 1305031243.0296640396 318.8023376465 83.7907509552 318.8058471680 13.7069075793 0.0104700000 435792480 0 1117917184 -38.1943244934 312.8952331543 -48.0346412659 407 1305031243.0617039204 318.7992553711 84.3681674279 318.8058471680 13.6900168721 0.0095040000 435794330 0 1118552064 -38.1943244934 312.8952331543 -48.0346412659 408 1305031243.0937390327 318.7958984375 84.9427452000 318.8058471680 13.6731884158 0.0164750000 435796148 0 1119059968 -38.1943244934 312.8952331543 -48.0346412659 409 1305031243.1296861172 318.7947692871 85.5145105401 318.8058471680 13.6564217876 0.0122040000 436105210 0 1119821824 -38.1943244934 312.8952331543 -48.0346412659 410 1305031243.1616430283 318.7950744629 86.0834875253 318.8058471680 13.6397167192 0.0138020000 436107060 0 1120456704 -38.1943244934 312.8952331543 -48.0346412659 411 1305031243.1936519146 318.7970581055 86.6497005924 318.8058471680 13.6230728858 0.0120610000 436108910 0 1120964608 -38.1943244934 312.8952331543 -48.0346412659 412 1305031243.2297160625 305.6576538086 87.1812732944 318.8058471680 13.6280128554 0.0451280000 437416488 0 1122869248 -38.9449043274 300.4833068848 -40.6958770752 413 1305031243.2617199421 305.6607360840 87.7102792575 318.8058471680 13.6114644582 0.0136120000 439151222 0 1125027840 -38.9449043274 300.4833068848 -40.6958770752 414 1305031243.2936539650 306.3476257324 88.2383887901 318.8058471680 13.5950765452 0.0357230000 440458768 0 1126932480 -39.0648994446 301.0918884277 -41.2223930359 415 1305031243.3298029900 306.3485412598 88.7639554225 318.8058471680 13.5786476342 0.0137500000 442193534 0 1129218048 -39.0648994446 301.0918884277 -41.2223930359 416 1305031243.3616859913 306.3494873047 89.2869975665 318.8058471680 13.5622784109 0.0088270000 442195352 0 1129725952 -39.0648994446 301.0918884277 -41.2223930359 417 1305031243.3937079906 306.3488769531 89.8075296513 318.8058471680 13.5459680690 0.0088740000 442197202 0 1130360832 -39.0648994446 301.0918884277 -41.2223930359 418 1305031243.4297819138 306.3479919434 90.3255690348 318.8058471680 13.5297164320 0.0157380000 442506264 0 1131122688 -39.0648994446 301.0918884277 -41.2223930359 419 1305031243.4616219997 306.3467712402 90.8411327632 318.8058471680 13.5135231905 0.0092280000 442508114 0 1131757568 -39.0648994446 301.0918884277 -41.2223930359 420 1305031243.4976289272 301.9394226074 91.3437477391 318.8058471680 13.5018692175 0.0401400000 443815724 0 1133535232 -38.2418136597 297.2195129395 -37.4247474670 421 1305031243.5297050476 301.9375610352 91.8439705735 318.8058471680 13.4857862466 0.0165610000 445857638 0 1135947776 -38.2418136597 297.2195129395 -37.4247474670 422 1305031243.5617949963 301.9356689453 92.3418182000 318.8058471680 13.4697605616 0.0088020000 445859456 0 1136582656 -38.2418136597 297.2195129395 -37.4247474670 423 1305031243.5976779461 301.9342956543 92.8373086904 318.8058471680 13.4537919678 0.0169160000 445861274 0 1137217536 -38.2418136597 297.2195129395 -37.4247474670 424 1305031243.6296401024 301.9346313477 93.3304627533 318.8058471680 13.4378802119 0.0171740000 446170272 0 1137979392 -38.2418136597 297.2195129395 -37.4247474670 425 1305031243.6617190838 301.9356994629 93.8212986043 318.8058471680 13.4220250607 0.0131910000 446172090 0 1138614272 -38.2418136597 297.2195129395 -37.4247474670 426 1305031243.6976819038 301.9378051758 94.3098350047 318.8058471680 13.4062256625 0.0173030000 446173940 0 1139122176 -38.2418136597 297.2195129395 -37.4247474670 427 1305031243.7296760082 20450.9550781250 141.9834772603 20450.9550781250 976.9718721155 0.0461170000 447481454 0 1140899840 14258.1083984375 -1620.6459960938 -14569.0029296875 428 1305031243.7616670132 20450.9550781250 189.4343454866 20450.9550781250 975.8272063868 0.0100470000 449216124 0 1143058432 14258.1083984375 -1620.6459960938 -14569.0029296875 429 1305031243.7976500988 20450.9531250000 236.6639929913 20450.9550781250 974.6865546967 0.0119480000 449217942 0 1143693312 14258.1083984375 -1620.6459960938 -14569.0029296875 430 1305031243.8296658993 20450.9492187500 283.6739586326 20450.9550781250 973.5498936165 0.0115700000 449526940 0 1144455168 14258.1083984375 -1620.6459960938 -14569.0029296875 431 1305031243.8616569042 20450.9472656250 330.4657760502 20450.9550781250 972.4171999401 0.0157170000 449528726 0 1145090048 14258.1083984375 -1620.6459960938 -14569.0029296875 432 1305031243.8976891041 20450.9433593750 377.0409556413 20450.9550781250 971.2884506499 0.0118680000 449530576 0 1145724928 14258.1083984375 -1620.6459960938 -14569.0029296875 433 1305031243.9296560287 20450.9394531250 423.4009983606 20450.9550781250 970.1636228890 0.0129660000 449532330 0 1146232832 14258.1083984375 -1620.6459960938 -14569.0029296875 434 1305031243.9616739750 20450.9375000000 469.5473958298 20450.9550781250 969.0426940120 0.0095320000 449534148 0 1146740736 14258.1083984375 -1620.6459960938 -14569.0029296875 435 1305031243.9976348877 20450.9335937500 515.4816169745 20450.9550781250 967.9256415520 0.0151830000 449535998 0 1147375616 14258.1083984375 -1620.6459960938 -14569.0029296875 436 1305031244.0295569897 20450.9335937500 561.2051306827 20450.9550781250 966.8124432080 0.0250070000 450843376 0 1149153280 14258.1083984375 -1620.6459960938 -14569.0029296875 437 1305031244.0617549419 20450.9335937500 606.7193834586 20450.9550781250 965.7030768730 0.0104080000 450845194 0 1149788160 14258.1083984375 -1620.6459960938 -14569.0029296875 438 1305031244.0976209641 20450.9316406250 652.0258041370 20450.9550781250 964.5975206155 0.0100770000 450847044 0 1150296064 14258.1083984375 -1620.6459960938 -14569.0029296875 439 1305031244.1296620369 20450.9335937500 697.1258218810 20450.9550781250 963.4957526740 0.0191860000 450848830 0 1150803968 14258.1083984375 -1620.6459960938 -14569.0029296875 440 1305031244.1617009640 20450.9316406250 742.0208351054 20450.9550781250 962.3977514604 0.0141090000 450850616 0 1151438848 14258.1083984375 -1620.6459960938 -14569.0029296875 441 1305031244.1976718903 20450.9296875000 786.7122383989 20450.9550781250 961.3034955635 0.0455560000 450929278 0 1151946752 14258.1083984375 -1620.6459960938 -14569.0029296875 442 1305031244.2296679020 20450.9296875000 831.2014181480 20450.9550781250 960.2129637390 0.0134460000 450931032 0 1152581632 14258.1083984375 -1620.6459960938 -14569.0029296875 443 1305031244.2616760731 20450.9277343750 875.4897394035 20450.9550781250 959.1261349102 0.0295140000 451009662 0 1153089536 14258.1083984375 -1620.6459960938 -14569.0029296875 444 1305031244.2976799011 20450.9238281250 919.5785549187 20450.9550781250 958.0429881697 0.0175070000 451011512 0 1153724416 14258.1083984375 -1620.6459960938 -14569.0029296875 445 1305031244.3296849728 20450.9218750000 963.4692140649 20450.9550781250 956.9635027712 0.0099040000 451013266 0 1154232320 14258.1083984375 -1620.6459960938 -14569.0029296875 446 1305031244.3616650105 20450.9199218750 1007.1630497327 20450.9550781250 955.8876581348 0.0149700000 451015084 0 1154740224 14258.1083984375 -1620.6459960938 -14569.0029296875 447 1305031244.3976149559 20450.9179687500 1050.6613828848 20450.9550781250 954.8154338440 0.0130820000 451016934 0 1155248128 14258.1083984375 -1620.6459960938 -14569.0029296875 448 1305031244.4297399521 20450.9160156250 1093.9655226901 20450.9550781250 953.7468096341 0.0179110000 451018688 0 1155756032 14258.1083984375 -1620.6459960938 -14569.0029296875 449 1305031244.4617409706 20450.9160156250 1137.0767710039 20450.9550781250 952.6817654060 0.0105450000 451020506 0 1156263936 14258.1083984375 -1620.6459960938 -14569.0029296875 450 1305031244.4976789951 20450.9160156250 1179.9964137698 20450.9550781250 951.6202812172 0.0239610000 451099168 0 1156898816 14258.1083984375 -1620.6459960938 -14569.0029296875 451 1305031244.5296900272 20450.9179687500 1222.7257298562 20450.9550781250 950.5623372764 0.0129530000 451100922 0 1157533696 14258.1083984375 -1620.6459960938 -14569.0029296875 452 1305031244.5616719723 20478.5546875000 1265.3271213554 20478.5546875000 949.5165137448 0.0448190000 451179656 0 1158041600 14270.0263671875 -1579.1577148438 -14600.6757812500 453 1305031244.5977001190 20478.5566406250 1307.7404315525 20478.5566406250 948.4655820309 0.0537610000 454527226 0 1161850880 14270.0263671875 -1579.1577148438 -14600.6757812500 454 1305031244.6297531128 20478.5566406250 1349.9668989733 20478.5566406250 947.4181321461 0.0123950000 454528980 0 1162485760 14270.0263671875 -1579.1577148438 -14600.6757812500 455 1305031244.6617109776 20478.5585937500 1392.0077598410 20478.5585937500 946.3741449069 0.0097820000 454530798 0 1163120640 14270.0263671875 -1579.1577148438 -14600.6757812500 456 1305031244.6976668835 20478.5605468750 1433.8642352511 20478.5605468750 945.3336012777 0.0136150000 454532648 0 1163628544 14270.0263671875 -1579.1577148438 -14600.6757812500 457 1305031244.7297570705 20478.5585937500 1475.5375270641 20478.5605468750 944.2964823691 0.0186800000 454534402 0 1164136448 14270.0263671875 -1579.1577148438 -14600.6757812500 458 1305031244.7617380619 20478.5605468750 1517.0288437012 20478.5605468750 943.2627694362 0.0227450000 454613032 0 1164644352 14270.0263671875 -1579.1577148438 -14600.6757812500 459 1305031244.7976291180 20478.5585937500 1558.3393660325 20478.5605468750 942.2324438799 0.0236770000 455920506 0 1166548992 14270.0263671875 -1579.1577148438 -14600.6757812500 460 1305031244.8296599388 20478.5546875000 1599.4702689052 20478.5605468750 941.2054872577 0.0241960000 455999040 0 1167183872 14270.0263671875 -1579.1577148438 -14600.6757812500 461 1305031244.8616359234 20478.5546875000 1640.4227296831 20478.5605468750 940.1818812047 0.0168370000 456000858 0 1167818752 14270.0263671875 -1579.1577148438 -14600.6757812500 462 1305031244.8976349831 20478.5546875000 1681.1979070809 20478.5605468750 939.1616075659 0.0125480000 456002708 0 1168326656 14270.0263671875 -1579.1577148438 -14600.6757812500 463 1305031244.9296810627 20478.5546875000 1721.7969498032 20478.5605468750 938.1446482990 0.0225130000 456081274 0 1168834560 14270.0263671875 -1579.1577148438 -14600.6757812500 464 1305031244.9616940022 20478.5527343750 1762.2209924424 20478.5605468750 937.1309854984 0.0128370000 456083092 0 1169469440 14270.0263671875 -1579.1577148438 -14600.6757812500 465 1305031244.9976880550 20478.5527343750 1802.4711682315 20478.5605468750 936.1206013946 0.0108360000 456084910 0 1170104320 14270.0263671875 -1579.1577148438 -14600.6757812500 466 1305031245.0296700001 20478.5527343750 1842.5485964850 20478.5605468750 935.1134783473 0.0396430000 456163508 0 1170612224 14270.0263671875 -1579.1577148438 -14600.6757812500 467 1305031245.0617969036 20478.5546875000 1882.4543911125 20478.5605468750 934.1095988542 0.0236420000 456242106 0 1171247104 14270.0263671875 -1579.1577148438 -14600.6757812500 468 1305031245.0979061127 20478.5566406250 1922.1896523294 20478.5605468750 933.1089455421 0.0150120000 456243956 0 1171881984 14270.0263671875 -1579.1577148438 -14600.6757812500 469 1305031245.1299250126 20478.5585937500 1961.7554709678 20478.5605468750 932.1115011680 0.0100220000 456245742 0 1172389888 14270.0263671875 -1579.1577148438 -14600.6757812500 470 1305031245.1617209911 20478.5585937500 2001.1529244205 20478.5605468750 931.1172486173 0.0151550000 456247528 0 1172897792 14270.0263671875 -1579.1577148438 -14600.6757812500 471 1305031245.1976549625 20498.3867187500 2040.4251830072 20498.3867187500 930.1311968634 0.0395630000 456326262 0 1173532672 14275.8154296875 -1551.0762939453 -14625.8251953125 472 1305031245.2296841145 20498.3886718750 2079.5310378565 20498.3886718750 929.1432717878 0.0266040000 458444956 0 1176199168 14275.8154296875 -1551.0762939453 -14625.8251953125 473 1305031245.2617490292 20498.3906250000 2118.4715443832 20498.3906250000 928.1584879705 0.0341220000 459752366 0 1177976832 14275.8154296875 -1551.0762939453 -14625.8251953125 474 1305031245.2976479530 20498.3906250000 2157.2477449753 20498.3906250000 927.1768288009 0.0310070000 459831028 0 1178611712 14275.8154296875 -1551.0762939453 -14625.8251953125 475 1305031245.3297359943 20498.3906250000 2195.8606773543 20498.3906250000 926.1982777904 0.0154270000 459832814 0 1179373568 14275.8154296875 -1551.0762939453 -14625.8251953125 476 1305031245.3617970943 20459.7636718750 2234.2302214604 20498.3906250000 925.2701107898 0.0617350000 459911516 0 1179881472 14230.1337890625 -1450.9156494141 -14626.5595703125 477 1305031245.3976640701 20459.7597656250 2272.4388787857 20498.3906250000 924.2976774159 0.0185580000 460421078 0 1180897280 14230.1337890625 -1450.9156494141 -14626.5595703125 478 1305031245.4296739101 20459.7597656250 2310.4876672519 20498.3906250000 923.3283036037 0.0141530000 460730044 0 1181786112 14230.1337890625 -1450.9156494141 -14626.5595703125 479 1305031245.4617340565 20459.7597656250 2348.3775881253 20498.3906250000 922.3619733523 0.0203570000 460731830 0 1182420992 14230.1337890625 -1450.9156494141 -14626.5595703125 480 1305031245.4976971149 20459.7578125000 2386.1096302594 20498.3906250000 921.3986707737 0.0199930000 460733680 0 1182928896 14230.1337890625 -1450.9156494141 -14626.5595703125 481 1305031245.5296850204 20459.7578125000 2423.6847824055 20498.3906250000 920.4383800826 0.0138460000 460735434 0 1183563776 14230.1337890625 -1450.9156494141 -14626.5595703125 482 1305031245.5616409779 20459.7578125000 2461.1040210571 20498.3906250000 919.4810856216 0.0260250000 462042876 0 1185341440 14230.1337890625 -1450.9156494141 -14626.5595703125 483 1305031245.5975880623 20459.7578125000 2498.3683146212 20498.3906250000 918.5267718387 0.0111830000 462044726 0 1185976320 14230.1337890625 -1450.9156494141 -14626.5595703125 484 1305031245.6296100616 20459.7558593750 2535.4786194657 20498.3906250000 917.5754232983 0.0138880000 462046448 0 1186484224 14230.1337890625 -1450.9156494141 -14626.5595703125 485 1305031245.6616649628 20459.7578125000 2572.4358961524 20498.3906250000 916.6270246796 0.0182440000 462048298 0 1186992128 14230.1337890625 -1450.9156494141 -14626.5595703125 486 1305031245.6978080273 20459.7578125000 2609.2410852807 20498.3906250000 915.6815607664 0.0188220000 462050116 0 1187500032 14230.1337890625 -1450.9156494141 -14626.5595703125 487 1305031245.7296969891 20459.7578125000 2645.8951237349 20498.3906250000 914.7390164542 0.0133090000 462051902 0 1188134912 14230.1337890625 -1450.9156494141 -14626.5595703125 488 1305031245.7618420124 20459.7578125000 2682.3989407201 20498.3906250000 913.7993767513 0.0178470000 462053720 0 1188642816 14230.1337890625 -1450.9156494141 -14626.5595703125 489 1305031245.7975080013 20459.7578125000 2718.7534578403 20498.3906250000 912.8626267709 0.0172210000 462055538 0 1189150720 14230.1337890625 -1450.9156494141 -14626.5595703125 490 1305031245.8297789097 20459.7597656250 2754.9595931623 20498.3906250000 911.9287517244 0.0120000000 462057324 0 1189658624 14230.1337890625 -1450.9156494141 -14626.5595703125 491 1305031245.8617019653 20459.7597656250 2791.0182493180 20498.3906250000 910.9977369367 0.0203640000 462059110 0 1190293504 14230.1337890625 -1450.9156494141 -14626.5595703125 492 1305031245.8976840973 20459.7597656250 2826.9303255707 20498.3906250000 910.0695678436 0.0157230000 462060992 0 1190801408 14230.1337890625 -1450.9156494141 -14626.5595703125 493 1305031245.9296269417 20459.7617187500 2862.6967178489 20498.3906250000 909.1442299681 0.0155730000 462062746 0 1191309312 14230.1337890625 -1450.9156494141 -14626.5595703125 494 1305031245.9616880417 20459.7617187500 2898.3183069196 20498.3906250000 908.2217089522 0.0171490000 462064532 0 1191817216 14230.1337890625 -1450.9156494141 -14626.5595703125 495 1305031245.9976129532 20459.7617187500 2933.7959703778 20498.3906250000 907.3019905358 0.0202460000 462066414 0 1192325120 14230.1337890625 -1450.9156494141 -14626.5595703125 496 1305031246.0296230316 20459.7617187500 2969.1305787415 20498.3906250000 906.3850605508 0.0321980000 462144980 0 1192960000 14230.1337890625 -1450.9156494141 -14626.5595703125 497 1305031246.0616579056 20459.7617187500 3004.3229955222 20498.3906250000 905.4709049388 0.0308210000 463452422 0 1194737664 14230.1337890625 -1450.9156494141 -14626.5595703125 498 1305031246.0976560116 20459.7656250000 3039.3740851396 20498.3906250000 904.5595097402 0.0138850000 463454272 0 1195499520 14230.1337890625 -1450.9156494141 -14626.5595703125 499 1305031246.1295800209 20459.7656250000 3074.2846894279 20498.3906250000 903.6508610849 0.0219110000 463455994 0 1196007424 14230.1337890625 -1450.9156494141 -14626.5595703125 500 1305031246.1616809368 20459.7675781250 3109.0556552053 20498.3906250000 902.7449452108 0.0156890000 463457780 0 1196515328 14230.1337890625 -1450.9156494141 -14626.5595703125 501 1305031246.1976530552 20459.7695312500 3143.6878186305 20498.3906250000 901.8417484444 0.0153820000 463459630 0 1197150208 14230.1337890625 -1450.9156494141 -14626.5595703125 502 1305031246.2296369076 20459.7695312500 3178.1820053091 20498.3906250000 900.9412572101 0.0565280000 463538228 0 1197658112 14230.1337890625 -1450.9156494141 -14626.5595703125 503 1305031246.2618930340 20459.7714843750 3212.5390420468 20498.3906250000 900.0434580280 0.0162660000 463540046 0 1198166016 14230.1337890625 -1450.9156494141 -14626.5595703125 504 1305031246.2976129055 20459.7734375000 3246.7597452123 20498.3906250000 899.1483375131 0.0137610000 463541896 0 1198800896 14230.1337890625 -1450.9156494141 -14626.5595703125 505 1305031246.3297309875 20459.7753906250 3280.8449247082 20498.3906250000 898.2558823691 0.0156150000 463543650 0 1199308800 14230.1337890625 -1450.9156494141 -14626.5595703125 506 1305031246.3615291119 20388.0957031250 3314.6537207130 20498.3906250000 897.3773546097 0.0492300000 463622352 0 1199943680 14200.6425781250 -1447.2135009766 -14555.3359375000 507 1305031246.3977379799 20388.0996093750 3348.3291563908 20498.3906250000 896.4901795528 0.0137380000 464128338 0 1200832512 14200.6425781250 -1447.2135009766 -14555.3359375000 508 1305031246.4296538830 20388.1015625000 3381.8720154580 20498.3906250000 895.6056305680 0.0253740000 465742928 0 1202991104 14200.6425781250 -1447.2135009766 -14555.3359375000 509 1305031246.4617550373 20388.1035156250 3415.2830793090 20498.3906250000 894.7236947278 0.0174800000 465744778 0 1203625984 14200.6425781250 -1447.2135009766 -14555.3359375000 510 1305031246.4977169037 20388.1054687500 3448.5631232098 20498.3906250000 893.8443591917 0.0426400000 465823472 0 1204260864 14200.6425781250 -1447.2135009766 -14555.3359375000 511 1305031246.5297288895 20388.1093750000 3481.7129201801 20498.3906250000 892.9676112044 0.0148240000 465825290 0 1204768768 14200.6425781250 -1447.2135009766 -14555.3359375000 512 1305031246.5616788864 20388.1093750000 3514.7332257559 20498.3906250000 892.0934381034 0.0323870000 465903920 0 1205276672 14200.6425781250 -1447.2135009766 -14555.3359375000 513 1305031246.5975799561 20388.1113281250 3547.6248010042 20498.3906250000 891.2218273091 0.0165730000 465905834 0 1206038528 14200.6425781250 -1447.2135009766 -14555.3359375000 514 1305031246.6301050186 20388.1132812500 3580.3883972693 20498.3906250000 890.3527663267 0.0127950000 465991620 0 1206673408 14200.6425781250 -1447.2135009766 -14555.3359375000 515 1305031246.6616840363 20388.1152343750 3613.0247600598 20498.3906250000 889.4862427499 0.0145830000 465993470 0 1207181312 14200.6425781250 -1447.2135009766 -14555.3359375000 516 1305031246.6976709366 20388.1152343750 3645.5346253201 20498.3906250000 888.6222442585 0.0177260000 465995384 0 1207816192 14200.6425781250 -1447.2135009766 -14555.3359375000 517 1305031246.7298250198 20388.1171875000 3677.9187308562 20498.3906250000 887.7607586058 0.0161600000 465997170 0 1208324096 14200.6425781250 -1447.2135009766 -14555.3359375000 518 1305031246.7617440224 20388.1171875000 3710.1778012358 20498.3906250000 886.9017736391 0.0113080000 465999020 0 1208832000 14200.6425781250 -1447.2135009766 -14555.3359375000 519 1305031246.7976179123 20388.1171875000 3742.3125592055 20498.3906250000 886.0452772839 0.0186510000 466000934 0 1209339904 14200.6425781250 -1447.2135009766 -14555.3359375000 520 1305031246.8296990395 20388.1171875000 3774.3237219522 20498.3906250000 885.1912575442 0.0182280000 466002752 0 1209847808 14200.6425781250 -1447.2135009766 -14555.3359375000 521 1305031246.8616819382 20388.1152343750 3806.2119974079 20498.3906250000 884.3397025081 0.0107530000 466004634 0 1210355712 14200.6425781250 -1447.2135009766 -14555.3359375000 522 1305031246.8976190090 20388.1152343750 3837.9780955630 20498.3906250000 883.4906003463 0.0177240000 466006548 0 1210990592 14200.6425781250 -1447.2135009766 -14555.3359375000 523 1305031246.9297189713 20388.1132812500 3869.6227135089 20498.3906250000 882.6439393028 0.0107100000 466008366 0 1211498496 14200.6425781250 -1447.2135009766 -14555.3359375000 524 1305031246.9615809917 20388.1132812500 3901.1465504702 20498.3906250000 881.7997077028 0.0278710000 466087028 0 1212006400 14200.6425781250 -1447.2135009766 -14555.3359375000 525 1305031246.9976840019 20388.1093750000 3932.5502891836 20498.3906250000 880.9578939546 0.0135990000 466088942 0 1212514304 14200.6425781250 -1447.2135009766 -14555.3359375000 526 1305031247.0295639038 20388.1074218750 3963.8346183332 20498.3906250000 880.1184865335 0.0167290000 466090792 0 1213149184 14200.6425781250 -1447.2135009766 -14555.3359375000 527 1305031247.0617609024 20388.1054687500 3995.0002176699 20498.3906250000 879.2814739969 0.0109350000 466092642 0 1213784064 14200.6425781250 -1447.2135009766 -14555.3359375000 528 1305031247.0975708961 20388.1054687500 4026.0477654939 20498.3906250000 878.4468449785 0.0187380000 466094556 0 1214291968 14200.6425781250 -1447.2135009766 -14555.3359375000 529 1305031247.1296939850 20388.1035156250 4056.9779275924 20498.3906250000 877.6145881892 0.0186550000 466096406 0 1214799872 14200.6425781250 -1447.2135009766 -14555.3359375000 530 1305031247.1616880894 20388.1035156250 4087.7913720982 20498.3906250000 876.7846924125 0.0407700000 466175068 0 1215307776 14200.6425781250 -1447.2135009766 -14555.3359375000 531 1305031247.1976759434 20388.1015625000 4118.4887547543 20498.3906250000 875.9571465068 0.0105500000 466176982 0 1215942656 14200.6425781250 -1447.2135009766 -14555.3359375000 532 1305031247.2296841145 20388.1035156250 4149.0707373875 20498.3906250000 875.1319394029 0.0130230000 466178832 0 1216450560 14200.6425781250 -1447.2135009766 -14555.3359375000 533 1305031247.2616710663 20388.1035156250 4179.5379658645 20498.3906250000 874.3090601062 0.0194940000 466180682 0 1217085440 14200.6425781250 -1447.2135009766 -14555.3359375000 534 1305031247.2975540161 20388.1054687500 4209.8910885291 20498.3906250000 873.4884976924 0.0270000000 466259408 0 1217593344 14200.6425781250 -1447.2135009766 -14555.3359375000 535 1305031247.3297290802 20388.1054687500 4240.1307415762 20498.3906250000 872.6702413098 0.0405240000 467566850 0 1219497984 14200.6425781250 -1447.2135009766 -14555.3359375000 536 1305031247.3616259098 20388.1074218750 4270.2575637409 20498.3906250000 871.8542801788 0.0096400000 467568700 0 1220132864 14200.6425781250 -1447.2135009766 -14555.3359375000 537 1305031247.3975400925 20388.1074218750 4300.2721817263 20498.3906250000 871.0406035876 0.0137260000 467570646 0 1220767744 14200.6425781250 -1447.2135009766 -14555.3359375000 538 1305031247.4297029972 20388.1093750000 4330.1752248365 20498.3906250000 870.2292008936 0.0178430000 467572464 0 1221259264 14200.6425781250 -1447.2135009766 -14555.3359375000 539 1305031247.4616940022 20388.1093750000 4359.9673104583 20498.3906250000 869.4200615290 0.0096880000 467574314 0 1221767168 14200.6425781250 -1447.2135009766 -14555.3359375000 540 1305031247.4976270199 20388.1113281250 4389.6490586392 20498.3906250000 868.6131749907 0.0104970000 467576260 0 1222275072 14200.6425781250 -1447.2135009766 -14555.3359375000 541 1305031247.5296189785 20388.1113281250 4419.2210776216 20498.3906250000 867.8085308415 0.0109510000 467578046 0 1222909952 14200.6425781250 -1447.2135009766 -14555.3359375000 542 1305031247.5617430210 20388.1132812500 4448.6839783663 20498.3906250000 867.0061187163 0.0257070000 467656708 0 1223417856 14200.6425781250 -1447.2135009766 -14555.3359375000 543 1305031247.5977010727 20388.1113281250 4478.0383565426 20498.3906250000 866.2059283149 0.0159230000 467658622 0 1224052736 14200.6425781250 -1447.2135009766 -14555.3359375000 544 1305031247.6297180653 20388.1113281250 4507.2848142110 20498.3906250000 865.4079494028 0.0136700000 467660408 0 1224560640 14200.6425781250 -1447.2135009766 -14555.3359375000 545 1305031247.6616809368 20388.1113281250 4536.4239454292 20498.3906250000 864.6121718131 0.0180420000 467662226 0 1225068544 14200.6425781250 -1447.2135009766 -14555.3359375000 546 1305031247.6975688934 20388.1113281250 4565.4563399030 20498.3906250000 863.8185854463 0.0220360000 467740920 0 1225703424 14200.6425781250 -1447.2135009766 -14555.3359375000 547 1305031247.7296841145 20388.1113281250 4594.3825830259 20498.3906250000 863.0271802579 0.0192960000 467742706 0 1226211328 14200.6425781250 -1447.2135009766 -14555.3359375000 548 1305031247.7617230415 20388.1113281250 4623.2032559184 20498.3906250000 862.2379462797 0.0115290000 467744524 0 1226846208 14200.6425781250 -1447.2135009766 -14555.3359375000 549 1305031247.7976500988 20388.1093750000 4651.9189319094 20498.3906250000 861.4508736057 0.0499180000 467823218 0 1227354112 14200.6425781250 -1447.2135009766 -14555.3359375000 550 1305031247.8296570778 20388.1074218750 4680.5301837094 20498.3906250000 860.6659523795 0.0267470000 467901752 0 1227997184 14200.6425781250 -1447.2135009766 -14555.3359375000 551 1305031247.8616878986 20388.1054687500 4709.0375798710 20498.3906250000 859.8831728250 0.0200220000 467903602 0 1228632064 14200.6425781250 -1447.2135009766 -14555.3359375000 552 1305031247.8976380825 20388.1015625000 4737.4416812888 20498.3906250000 859.1025252194 0.0233340000 467905452 0 1229266944 14200.6425781250 -1447.2135009766 -14555.3359375000 553 1305031247.9298069477 20388.1015625000 4765.7430553958 20498.3906250000 858.3239998912 0.0279660000 467984018 0 1229774848 14200.6425781250 -1447.2135009766 -14555.3359375000 554 1305031247.9616999626 20388.0976562500 4793.9422514263 20498.3906250000 857.5475872541 0.0338140000 468062616 0 1230282752 14200.6425781250 -1447.2135009766 -14555.3359375000 555 1305031247.9975569248 20388.0917968750 4822.0398181748 20498.3906250000 856.7732777734 0.0190830000 468064466 0 1230917632 14200.6425781250 -1447.2135009766 -14555.3359375000 556 1305031248.0296840668 20388.0898437500 4850.0363110266 20498.3906250000 856.0010619580 0.0227080000 468066252 0 1231425536 14200.6425781250 -1447.2135009766 -14555.3359375000 557 1305031248.0617458820 20388.0859375000 4877.9322708587 20498.3906250000 855.2309303974 0.0490780000 468144850 0 1232060416 14200.6425781250 -1447.2135009766 -14555.3359375000 558 1305031248.0981791019 20388.0800781250 4905.7282346710 20498.3906250000 854.4628737378 0.0273980000 468223480 0 1232695296 14200.6425781250 -1447.2135009766 -14555.3359375000 559 1305031248.1298580170 20388.0742187500 4933.4247391148 20498.3906250000 853.6968826663 0.0164950000 468225266 0 1233203200 14200.6425781250 -1447.2135009766 -14555.3359375000 560 1305031248.1617319584 20388.0703125000 4961.0223204958 20498.3906250000 852.9329479453 0.0146790000 468227052 0 1233838080 14200.6425781250 -1447.2135009766 -14555.3359375000 561 1305031248.1977460384 20388.0644531250 4988.5215043329 20498.3906250000 852.1710603989 0.0136770000 468228902 0 1234345984 14200.6425781250 -1447.2135009766 -14555.3359375000 562 1305031248.2296700478 20388.0625000000 5015.9228228306 20498.3906250000 851.4112108893 0.0115810000 468230656 0 1234853888 14200.6425781250 -1447.2135009766 -14555.3359375000 563 1305031248.2616910934 20388.0585937500 5043.2267940045 20498.3906250000 850.6533903499 0.0272760000 468309254 0 1235361792 14200.6425781250 -1447.2135009766 -14555.3359375000 564 1305031248.2976450920 20388.0546875000 5070.4339356596 20498.3906250000 849.8975897661 0.0258540000 468387948 0 1235996672 14200.6425781250 -1447.2135009766 -14555.3359375000 565 1305031248.3296880722 20388.0527343750 5097.5447653919 20498.3906250000 849.1438001830 0.0195290000 468389702 0 1236631552 14200.6425781250 -1447.2135009766 -14555.3359375000 566 1305031248.3617050648 20388.0527343750 5124.5597971392 20498.3906250000 848.3920126983 0.0153270000 468391488 0 1237139456 14200.6425781250 -1447.2135009766 -14555.3359375000 567 1305031248.3983058929 20388.0507812500 5151.4795343246 20498.3906250000 847.6422184641 0.0137610000 468393370 0 1237647360 14200.6425781250 -1447.2135009766 -14555.3359375000 568 1305031248.4296898842 20388.0488281250 5178.3044802643 20498.3906250000 846.8944086881 0.0144280000 468395124 0 1238282240 14200.6425781250 -1447.2135009766 -14555.3359375000 569 1305031248.4616739750 20388.0488281250 5205.0351381692 20498.3906250000 846.1485746321 0.0163510000 468396910 0 1238790144 14200.6425781250 -1447.2135009766 -14555.3359375000 570 1305031248.4975969791 20388.0468750000 5231.6720008654 20498.3906250000 845.4047076114 0.0155670000 468398760 0 1239298048 14200.6425781250 -1447.2135009766 -14555.3359375000 571 1305031248.5296781063 20388.0449218750 5258.2155611474 20498.3906250000 844.6627989939 0.0371870000 468477326 0 1239805952 14200.6425781250 -1447.2135009766 -14555.3359375000 572 1305031248.5616800785 20388.0429687500 5284.6663083635 20498.3906250000 843.9228402035 0.0157120000 468479112 0 1240440832 14200.6425781250 -1447.2135009766 -14555.3359375000 573 1305031248.5975770950 20388.0410156250 5311.0247284459 20498.3906250000 843.1848227151 0.0111240000 468480962 0 1240948736 14200.6425781250 -1447.2135009766 -14555.3359375000 574 1305031248.6297268867 20388.0410156250 5337.2913073435 20498.3906250000 842.4487380532 0.0198920000 468482748 0 1241456640 14200.6425781250 -1447.2135009766 -14555.3359375000 575 1305031248.6616599560 20388.0390625000 5363.4665208307 20498.3906250000 841.7145777960 0.0157390000 468484534 0 1242091520 14200.6425781250 -1447.2135009766 -14555.3359375000 576 1305031248.7011339664 20388.0371093750 5389.5508447691 20498.3906250000 840.9823335751 0.0341380000 468563260 0 1242599424 14200.6425781250 -1447.2135009766 -14555.3359375000 577 1305031248.7297689915 20388.0371093750 5415.5447551064 20498.3906250000 840.2519970660 0.0198440000 468564982 0 1243234304 14200.6425781250 -1447.2135009766 -14555.3359375000 578 1305031248.7617149353 20388.0332031250 5441.4487143590 20498.3906250000 839.5235600048 0.0136880000 468566768 0 1243742208 14200.6425781250 -1447.2135009766 -14555.3359375000 579 1305031248.7978229523 20388.0332031250 5467.2631953414 20498.3906250000 838.7970141676 0.0280100000 468645430 0 1244250112 14200.6425781250 -1447.2135009766 -14555.3359375000 580 1305031248.8297278881 20388.0312500000 5492.9886575046 20498.3906250000 838.0723513861 0.0174750000 468647216 0 1244884992 14200.6425781250 -1447.2135009766 -14555.3359375000 581 1305031248.8617119789 20388.0292968750 5518.6255604983 20498.3906250000 837.3495635416 0.0106930000 468649034 0 1245392896 14200.6425781250 -1447.2135009766 -14555.3359375000 582 1305031248.8977398872 20388.0253906250 5544.1743574573 20498.3906250000 836.6286425626 0.0178360000 468650884 0 1245900800 14200.6425781250 -1447.2135009766 -14555.3359375000 583 1305031248.9297659397 20388.0234375000 5569.6355051075 20498.3906250000 835.9095804259 0.0179120000 468652638 0 1246535680 14200.6425781250 -1447.2135009766 -14555.3359375000 584 1305031248.9617550373 20388.0195312500 5595.0094503577 20498.3906250000 835.1923691586 0.0131470000 468654424 0 1247043584 14200.6425781250 -1447.2135009766 -14555.3359375000 585 1305031248.9976139069 20388.0175781250 5620.2966437385 20498.3906250000 834.4770008315 0.0145600000 468656306 0 1247551488 14200.6425781250 -1447.2135009766 -14555.3359375000 586 1305031249.0296969414 20388.0175781250 5645.4975327050 20498.3906250000 833.7634675671 0.0152740000 468658060 0 1248059392 14200.6425781250 -1447.2135009766 -14555.3359375000 587 1305031249.0623369217 20409.3359375000 5670.6488758137 20498.3906250000 833.0526796686 0.0391660000 468736794 0 1248567296 14221.2724609375 -1442.8012695312 -14565.5039062500 588 1305031249.0976889133 20409.3359375000 5695.7146701363 20498.3906250000 832.3427922969 0.0391770000 470855520 0 1251233792 14221.2724609375 -1442.8012695312 -14565.5039062500 589 1305031249.1297810078 20409.3398437500 5720.6953580372 20498.3906250000 831.6347166331 0.0122820000 470857306 0 1251868672 14221.2724609375 -1442.8012695312 -14565.5039062500 590 1305031249.1617488861 20409.3398437500 5745.5913656401 20498.3906250000 830.9284449849 0.0098880000 470859092 0 1252376576 14221.2724609375 -1442.8012695312 -14565.5039062500 591 1305031249.1976730824 20409.3437500000 5770.4031294038 20498.3906250000 830.2239697044 0.0130440000 470860942 0 1252884480 14221.2724609375 -1442.8012695312 -14565.5039062500 592 1305031249.2297680378 20409.3457031250 5795.1310729405 20498.3906250000 829.5212831908 0.0127000000 470862728 0 1253392384 14221.2724609375 -1442.8012695312 -14565.5039062500 593 1305031249.2616090775 20409.3476562500 5819.7756202985 20498.3906250000 828.8203778858 0.0097560000 470864514 0 1254027264 14221.2724609375 -1442.8012695312 -14565.5039062500 594 1305031249.2979500294 20409.3496093750 5844.3371926707 20498.3906250000 828.1212462769 0.0106900000 470866396 0 1254535168 14221.2724609375 -1442.8012695312 -14565.5039062500 595 1305031249.3296790123 20409.3496093750 5868.8162051358 20498.3906250000 827.4238808941 0.0104980000 470868118 0 1255043072 14221.2724609375 -1442.8012695312 -14565.5039062500 596 1305031249.3617539406 20409.3496093750 5893.2130732637 20498.3906250000 826.7282743139 0.0180540000 470869904 0 1255550976 14221.2724609375 -1442.8012695312 -14565.5039062500 597 1305031249.3977370262 20409.3515625000 5917.5282131116 20498.3906250000 826.0344191576 0.0135140000 470871754 0 1256058880 14221.2724609375 -1442.8012695312 -14565.5039062500 598 1305031249.4298510551 20409.3515625000 5941.7620314217 20498.3906250000 825.3423080879 0.0219950000 470950352 0 1256693760 14221.2724609375 -1442.8012695312 -14565.5039062500 599 1305031249.4617938995 20409.3535156250 5965.9149387409 20498.3906250000 824.6519338098 0.0247130000 472257762 0 1258471424 14221.2724609375 -1442.8012695312 -14565.5039062500 600 1305031249.4976849556 21230.4804687500 5991.3558812909 21230.4804687500 825.1541532682 0.0397050000 472336528 0 1259106304 14589.3457031250 -1440.6325683594 -15353.8974609375 601 1305031249.5296919346 21230.4804687500 6016.7121618024 21230.4804687500 824.4662380608 0.0273250000 475684034 0 1262915584 14589.3457031250 -1440.6325683594 -15353.8974609375 602 1305031249.5618629456 21230.4785156250 6041.9841989350 21230.4804687500 823.7800404952 0.0144120000 475685820 0 1263550464 14589.3457031250 -1440.6325683594 -15353.8974609375 603 1305031249.5978050232 21230.4785156250 6067.1724150490 21230.4804687500 823.0955534416 0.0203210000 475764450 0 1264185344 14589.3457031250 -1440.6325683594 -15353.8974609375 604 1305031249.6297600269 21230.4785156250 6092.2772264738 21230.4804687500 822.4127697914 0.0122310000 475766236 0 1264820224 14589.3457031250 -1440.6325683594 -15353.8974609375 605 1305031249.6622838974 21230.4785156250 6117.2990467864 21230.4804687500 821.7316825040 0.0130110000 475768022 0 1265328128 14589.3457031250 -1440.6325683594 -15353.8974609375 606 1305031249.6976530552 21230.4804687500 6142.2382900570 21230.4804687500 821.0522845732 0.0123000000 475769872 0 1265836032 14589.3457031250 -1440.6325683594 -15353.8974609375 607 1305031249.7299690247 21230.4804687500 6167.0953611916 21230.4804687500 820.3745690044 0.0161350000 475771594 0 1266343936 14589.3457031250 -1440.6325683594 -15353.8974609375 608 1305031249.7618219852 21230.4804687500 6191.8706656448 21230.4804687500 819.6985288792 0.0220230000 475850192 0 1266978816 14589.3457031250 -1440.6325683594 -15353.8974609375 609 1305031249.7976670265 21230.4824218750 6216.5646094153 21230.4824218750 819.0241573081 0.0150220000 475852042 0 1267486720 14589.3457031250 -1440.6325683594 -15353.8974609375 610 1305031249.8297970295 21230.4843750000 6241.1775926375 21230.4843750000 818.3514474267 0.0207780000 475930608 0 1268121600 14589.3457031250 -1440.6325683594 -15353.8974609375 611 1305031249.8617289066 21230.4843750000 6265.7100096299 21230.4843750000 817.6803924327 0.0137070000 475932426 0 1268756480 14589.3457031250 -1440.6325683594 -15353.8974609375 612 1305031249.8975479603 21167.7753906250 6290.0597896643 21230.4843750000 817.0162100730 0.0445400000 476011192 0 1269391360 14556.8339843750 -1446.6230468750 -15297.5175781250 613 1305031249.9297540188 21167.7773437500 6314.3301282517 21230.4843750000 816.3484402814 0.0132830000 476824230 0 1270788096 14556.8339843750 -1446.6230468750 -15297.5175781250 614 1305031249.9622321129 21167.7792968750 6338.5214135426 21230.4843750000 815.6823051765 0.0148450000 476826080 0 1271422976 14556.8339843750 -1446.6230468750 -15297.5175781250 615 1305031249.9976871014 21167.7792968750 6362.6340279870 21230.4843750000 815.0177981055 0.0098900000 476827898 0 1272057856 14556.8339843750 -1446.6230468750 -15297.5175781250 616 1305031250.0300250053 21167.7832031250 6386.6683610636 21230.4843750000 814.3549124395 0.0229930000 478135308 0 1273708544 14556.8339843750 -1446.6230468750 -15297.5175781250 617 1305031250.0619239807 21167.7851562500 6410.6247902292 21230.4843750000 813.6936415988 0.0121600000 478137094 0 1274343424 14556.8339843750 -1446.6230468750 -15297.5175781250 618 1305031250.0976040363 21167.7890625000 6434.5036968186 21230.4843750000 813.0339790411 0.0123680000 478138944 0 1274978304 14556.8339843750 -1446.6230468750 -15297.5175781250 619 1305031250.1297800541 21271.6523437500 6458.4732422902 21271.6523437500 814.5823474764 0.0385810000 478217614 0 1275486208 14319.2519531250 -1709.7397460938 -15634.8632812500 620 1305031250.1618089676 21271.6562500000 6482.3654729478 21271.6562500000 813.9240990179 0.0169830000 480259496 0 1278025728 14319.2519531250 -1709.7397460938 -15634.8632812500 621 1305031250.1976170540 21271.6621093750 6506.1807654380 21271.6621093750 813.2674437367 0.0118410000 480261314 0 1278660608 14319.2519531250 -1709.7397460938 -15634.8632812500 622 1305031250.2296700478 21271.6640625000 6529.9194845651 21271.6640625000 812.6123752157 0.0147480000 480263100 0 1279295488 14319.2519531250 -1709.7397460938 -15634.8632812500 623 1305031250.2619171143 21271.6679687500 6553.5820021963 21271.6679687500 811.9588870775 0.0146530000 480264886 0 1279803392 14319.2519531250 -1709.7397460938 -15634.8632812500 624 1305031250.2981820107 21271.6738281250 6577.1686878147 21271.6738281250 811.3069729791 0.0148020000 480266736 0 1280311296 14319.2519531250 -1709.7397460938 -15634.8632812500 625 1305031250.3297090530 21271.6757812500 6600.6798991642 21271.6757812500 810.6566266082 0.0188000000 480268458 0 1280819200 14319.2519531250 -1709.7397460938 -15634.8632812500 626 1305031250.3615961075 21271.6796875000 6624.1160010625 21271.6796875000 810.0078416927 0.0146810000 480270244 0 1281454080 14319.2519531250 -1709.7397460938 -15634.8632812500 627 1305031250.3977839947 21271.6835937500 6647.4773528850 21271.6835937500 809.3606119942 0.0139080000 480272094 0 1281961984 14319.2519531250 -1709.7397460938 -15634.8632812500 628 1305031250.4297308922 21271.6855468750 6670.7643086079 21271.6855468750 808.7149313117 0.0150260000 480273880 0 1282469888 14319.2519531250 -1709.7397460938 -15634.8632812500 629 1305031250.4617791176 21271.6894531250 6693.9772261668 21271.6894531250 808.0707934745 0.0185790000 480275698 0 1282977792 14319.2519531250 -1709.7397460938 -15634.8632812500 630 1305031250.4981379509 21271.6914062500 6717.1164550240 21271.6914062500 807.4281923488 0.0137740000 480277580 0 1283485696 14319.2519531250 -1709.7397460938 -15634.8632812500 631 1305031250.5297000408 21271.6953125000 6740.1823486175 21271.6953125000 806.7871218325 0.0153260000 480279366 0 1284120576 14319.2519531250 -1709.7397460938 -15634.8632812500 632 1305031250.5618190765 21271.6972656250 6763.1752519672 21271.6972656250 806.1475758579 0.0146660000 480281184 0 1284628480 14319.2519531250 -1709.7397460938 -15634.8632812500 633 1305031250.5976500511 21197.2148437500 6785.9778421596 21271.6972656250 805.5821702457 0.0349030000 481589850 0 1286406144 14249.0478515625 -1858.8342285156 -15580.7207031250 634 1305031250.6296610832 21197.2187500000 6808.7085060521 21271.6972656250 804.9455979073 0.0165920000 483324552 0 1288564736 14249.0478515625 -1858.8342285156 -15580.7207031250 635 1305031250.6619520187 21197.2187500000 6831.3675773024 21271.6972656250 804.3105322503 0.0137950000 483326402 0 1289199616 14249.0478515625 -1858.8342285156 -15580.7207031250 636 1305031250.6977679729 21197.2226562500 6853.9553997536 21271.6972656250 803.6769673434 0.0254450000 484941120 0 1291358208 14249.0478515625 -1858.8342285156 -15580.7207031250 637 1305031250.7297470570 21197.2246093750 6876.4723058911 21271.6972656250 803.0448972763 0.0157070000 484942938 0 1291993088 14249.0478515625 -1858.8342285156 -15580.7207031250 638 1305031250.7617890835 21197.2265625000 6898.9186291773 21271.6972656250 802.4143161845 0.0111820000 484944756 0 1292500992 14249.0478515625 -1858.8342285156 -15580.7207031250 639 1305031250.7978379726 21197.2285156250 6921.2947009871 21271.6972656250 801.7852182324 0.0176510000 484946638 0 1293135872 14249.0478515625 -1858.8342285156 -15580.7207031250 640 1305031250.8297851086 21197.2285156250 6943.6008475725 21271.6972656250 801.1575976134 0.0192290000 484948488 0 1293643776 14249.0478515625 -1858.8342285156 -15580.7207031250 641 1305031250.8618729115 21197.2304687500 6965.8373992436 21271.6972656250 800.5314485555 0.0129200000 484950338 0 1294151680 14249.0478515625 -1858.8342285156 -15580.7207031250 642 1305031250.8976039886 21197.2304687500 6988.0046781681 21271.6972656250 799.9067653185 0.0162620000 484952220 0 1294786560 14249.0478515625 -1858.8342285156 -15580.7207031250 643 1305031250.9301199913 21197.2304687500 7010.1030075469 21271.6972656250 799.2835421890 0.0160400000 484954038 0 1295040512 14249.0478515625 -1858.8342285156 -15580.7207031250 644 1305031250.9618170261 21197.2285156250 7032.1327055408 21271.6972656250 798.6617734900 0.0138980000 484955888 0 1295548416 14249.0478515625 -1858.8342285156 -15580.7207031250 645 1305031250.9976119995 21197.2304687500 7054.0940974217 21271.6972656250 798.0414535744 0.0180040000 484957770 0 1296056320 14249.0478515625 -1858.8342285156 -15580.7207031250 646 1305031251.0297889709 21197.2285156250 7075.9874943539 21271.6972656250 797.4225768212 0.0185850000 484959588 0 1296691200 14249.0478515625 -1858.8342285156 -15580.7207031250 647 1305031251.0618538857 21197.2265625000 7097.8132116154 21271.6972656250 796.8051376463 0.0133430000 484961406 0 1297199104 14249.0478515625 -1858.8342285156 -15580.7207031250 648 1305031251.0976850986 21197.2246093750 7119.5715625378 21271.6972656250 796.1891304958 0.0148820000 484963288 0 1297707008 14249.0478515625 -1858.8342285156 -15580.7207031250 649 1305031251.1297309399 21197.2226562500 7141.2628585220 21271.6972656250 795.5745498353 0.0185860000 484965074 0 1298214912 14249.0478515625 -1858.8342285156 -15580.7207031250 650 1305031251.1616990566 21197.2187500000 7162.8874060473 21271.6972656250 794.9613901726 0.0110790000 484966924 0 1298722816 14249.0478515625 -1858.8342285156 -15580.7207031250 651 1305031251.1976718903 21197.2167968750 7184.4455157107 21271.6972656250 794.3496460446 0.0152770000 484968838 0 1299357696 14249.0478515625 -1858.8342285156 -15580.7207031250 652 1305031251.2298820019 21197.2128906250 7205.9374902121 21271.6972656250 793.7393120014 0.0183380000 484970560 0 1299865600 14249.0478515625 -1858.8342285156 -15580.7207031250 653 1305031251.2618720531 19899.2871093750 7225.3760041771 21271.6972656250 795.7335835369 0.0397980000 485049294 0 1300373504 12921.9726562500 -2073.5661621094 -14987.9287109375 654 1305031251.2977221012 19899.2832031250 7244.7550671724 21271.6972656250 795.1240594596 0.0167830000 486784060 0 1302659072 12921.9726562500 -2073.5661621094 -14987.9287109375 655 1305031251.3296079636 19899.2792968750 7264.0749514926 21271.6972656250 794.5159339010 0.0313730000 488091438 0 1304563712 12921.9726562500 -2073.5661621094 -14987.9287109375 656 1305031251.3618309498 19899.2753906250 7283.3359277718 21271.6972656250 793.9092015261 0.0181040000 488400468 0 1305325568 12921.9726562500 -2073.5661621094 -14987.9287109375 657 1305031251.3977360725 19906.1015625000 7302.5486608535 21271.6972656250 793.3049659322 0.0469070000 488479234 0 1306087424 12928.2734375000 -2055.4763183594 -14994.0576171875 658 1305031251.4299569130 19906.0996093750 7321.7029936020 21271.6972656250 792.7010031811 0.0181820000 490521084 0 1308499968 12928.2734375000 -2055.4763183594 -14994.0576171875 659 1305031251.4622879028 19906.0957031250 7340.7991889124 21271.6972656250 792.0984177670 0.0133370000 490522902 0 1309134848 12928.2734375000 -2055.4763183594 -14994.0576171875 660 1305031251.4977610111 19906.0917968750 7359.8375110457 21271.6972656250 791.4972044674 0.0144500000 490524720 0 1309769728 12928.2734375000 -2055.4763183594 -14994.0576171875 661 1305031251.5298271179 19906.0898437500 7378.8182256186 21271.6972656250 790.8973580765 0.0115520000 490526506 0 1310277632 12928.2734375000 -2055.4763183594 -14994.0576171875 662 1305031251.5617070198 19906.0859375000 7397.7415907423 21271.6972656250 790.2988734256 0.0227540000 491833948 0 1312055296 12928.2734375000 -2055.4763183594 -14994.0576171875 663 1305031251.5976569653 19906.0839843750 7416.6078688624 21271.6972656250 789.7017453729 0.0139930000 491835798 0 1312563200 12928.2734375000 -2055.4763183594 -14994.0576171875 664 1305031251.6297779083 19906.0820312500 7435.4173179021 21271.6972656250 789.1059687981 0.0125840000 491837552 0 1313198080 12928.2734375000 -2055.4763183594 -14994.0576171875 665 1305031251.6618139744 19906.0800781250 7454.1701942333 21271.6972656250 788.5115386122 0.0126460000 491839338 0 1313705984 12928.2734375000 -2055.4763183594 -14994.0576171875 666 1305031251.6983299255 19906.0781250000 7472.8667526879 21271.6972656250 787.9184497576 0.0270250000 491918000 0 1314213888 12928.2734375000 -2055.4763183594 -14994.0576171875 667 1305031251.7301750183 19906.0761718750 7491.5072465697 21271.6972656250 787.3266971841 0.0218260000 493225410 0 1316118528 12928.2734375000 -2055.4763183594 -14994.0576171875 668 1305031251.7617549896 19906.0742187500 7510.0919276658 21271.6972656250 786.7362758891 0.0358140000 493304040 0 1316753408 12928.2734375000 -2055.4763183594 -14994.0576171875 669 1305031251.7976779938 19906.0742187500 7528.6210491772 21271.6972656250 786.1471808954 0.0324510000 493382670 0 1317388288 12928.2734375000 -2055.4763183594 -14994.0576171875 670 1305031251.8298690319 19906.0742187500 7547.0948598780 21271.6972656250 785.5594072299 0.0170740000 493384456 0 1318023168 12928.2734375000 -2055.4763183594 -14994.0576171875 671 1305031251.8621430397 19906.0722656250 7565.5136041489 21271.6972656250 784.9729499666 0.0250680000 493463086 0 1318658048 12928.2734375000 -2055.4763183594 -14994.0576171875 672 1305031251.8978729248 19906.0722656250 7583.8775307285 21271.6972656250 784.3878042026 0.0253970000 493541748 0 1319292928 12928.2734375000 -2055.4763183594 -14994.0576171875 673 1305031251.9298980236 19906.0722656250 7602.1868839750 21271.6972656250 783.8039650447 0.0133600000 493543502 0 1319800832 12928.2734375000 -2055.4763183594 -14994.0576171875 674 1305031251.9619040489 19906.0722656250 7620.4419067964 21271.6972656250 783.2214276454 0.0145100000 493545288 0 1320435712 12928.2734375000 -2055.4763183594 -14994.0576171875 675 1305031251.9983429909 19906.0722656250 7638.6428406613 21271.6972656250 782.6401871779 0.0103680000 493547138 0 1321070592 12928.2734375000 -2055.4763183594 -14994.0576171875 676 1305031252.0297839642 19906.0703125000 7656.7899227203 21271.6972656250 782.0602388338 0.0157220000 493548892 0 1321578496 12928.2734375000 -2055.4763183594 -14994.0576171875 677 1305031252.0620169640 19906.0683593750 7674.8833916075 21271.6972656250 781.4815778330 0.0142290000 493550710 0 1322086400 12928.2734375000 -2055.4763183594 -14994.0576171875 678 1305031252.0987350941 19906.0664062500 7692.9234845494 21271.6972656250 780.9041994206 0.0290880000 493629340 0 1322594304 12928.2734375000 -2055.4763183594 -14994.0576171875 679 1305031252.1297190189 19906.0644531250 7710.9104373750 21271.6972656250 780.3280988653 0.0435980000 493707906 0 1323229184 12928.2734375000 -2055.4763183594 -14994.0576171875 680 1305031252.1617779732 19906.0625000000 7728.8444845260 21271.6972656250 779.7532714605 0.0241010000 493786536 0 1323864064 12928.2734375000 -2055.4763183594 -14994.0576171875 681 1305031252.1978518963 19906.0605468750 7746.7258590668 21271.6972656250 779.1797125222 0.0191840000 493788418 0 1324371968 12928.2734375000 -2055.4763183594 -14994.0576171875 682 1305031252.2298820019 19906.0644531250 7764.5548012869 21271.6972656250 778.6074173953 0.0150000000 493790140 0 1325006848 12928.2734375000 -2055.4763183594 -14994.0576171875 683 1305031252.2617468834 19906.0625000000 7782.3315329102 21271.6972656250 778.0363814422 0.0142680000 493791926 0 1325641728 12928.2734375000 -2055.4763183594 -14994.0576171875 684 1305031252.2976710796 19906.0625000000 7800.0562857860 21271.6972656250 777.4666000540 0.0148140000 493793776 0 1326149632 12928.2734375000 -2055.4763183594 -14994.0576171875 685 1305031252.3299539089 19906.0625000000 7817.7292875586 21271.6972656250 776.8980686436 0.0137870000 493795530 0 1326784512 12928.2734375000 -2055.4763183594 -14994.0576171875 686 1305031252.3616869450 19906.0625000000 7835.3507645447 21271.6972656250 776.3307826471 0.0169040000 493797316 0 1327292416 12928.2734375000 -2055.4763183594 -14994.0576171875 687 1305031252.3974940777 19906.0644531250 7852.9209445863 21271.6972656250 775.7647375266 0.0398960000 493875978 0 1327800320 12928.2734375000 -2055.4763183594 -14994.0576171875 688 1305031252.4296720028 19906.0644531250 7870.4400485231 21271.6972656250 775.1999287611 0.0168290000 493877732 0 1328435200 12928.2734375000 -2055.4763183594 -14994.0576171875 689 1305031252.4617218971 19906.0664062500 7887.9083015822 21271.6972656250 774.6363518575 0.0139020000 493879518 0 1328943104 12928.2734375000 -2055.4763183594 -14994.0576171875 690 1305031252.4976549149 19906.0683593750 7905.3259248544 21271.6972656250 774.0740023449 0.0178120000 493881368 0 1329451008 12928.2734375000 -2055.4763183594 -14994.0576171875 691 1305031252.5296919346 19906.0703125000 7922.6931381505 21271.6972656250 773.5128757745 0.0131290000 493883154 0 1330085888 12928.2734375000 -2055.4763183594 -14994.0576171875 692 1305031252.5618619919 19906.0703125000 7940.0101571886 21271.6972656250 772.9529677213 0.0172750000 493884940 0 1330593792 12928.2734375000 -2055.4763183594 -14994.0576171875 693 1305031252.5976469517 19906.0722656250 7957.2772020781 21271.6972656250 772.3942737802 0.0291320000 493963570 0 1331101696 12928.2734375000 -2055.4763183594 -14994.0576171875 694 1305031252.6298389435 19906.0722656250 7974.4944860314 21271.6972656250 771.8367895692 0.0147810000 493965356 0 1331736576 12928.2734375000 -2055.4763183594 -14994.0576171875 695 1305031252.6615939140 19906.0742187500 7991.6622266540 21271.6972656250 771.2805107308 0.0165230000 493967110 0 1332244480 12928.2734375000 -2055.4763183594 -14994.0576171875 696 1305031252.6980121136 19906.0761718750 8008.7806374948 21271.6972656250 770.7254329335 0.0203310000 493968960 0 1332879360 12928.2734375000 -2055.4763183594 -14994.0576171875 697 1305031252.7298109531 19906.0761718750 8025.8499280750 21271.6972656250 770.1715518581 0.0197310000 493970746 0 1333387264 12928.2734375000 -2055.4763183594 -14994.0576171875 698 1305031252.7616798878 19906.0761718750 8042.8703095131 21271.6972656250 769.6188632160 0.0230280000 493972564 0 1333895168 12928.2734375000 -2055.4763183594 -14994.0576171875 699 1305031252.7976830006 19906.0781250000 8059.8419945138 21271.6972656250 769.0673627273 0.0244460000 493974382 0 1334403072 12928.2734375000 -2055.4763183594 -14994.0576171875 700 1305031252.8310210705 19906.0800781250 8076.7651917761 21271.6972656250 768.5170461244 0.0181260000 493976200 0 1335037952 12928.2734375000 -2055.4763183594 -14994.0576171875 701 1305031252.8658039570 19906.0800781250 8093.6401060220 21271.6972656250 767.9679091924 0.0228680000 493978018 0 1335545856 12928.2734375000 -2055.4763183594 -14994.0576171875 702 1305031252.8975970745 19906.0820312500 8110.4669463713 21271.6972656250 767.4199477205 0.0248330000 493979804 0 1336053760 12928.2734375000 -2055.4763183594 -14994.0576171875 703 1305031252.9296870232 19906.0839843750 8127.2459179758 21271.6972656250 766.8731575251 0.0176770000 493981558 0 1336561664 12928.2734375000 -2055.4763183594 -14994.0576171875 704 1305031252.9657709599 19906.0859375000 8143.9772248218 21271.6972656250 766.3275344415 0.0233870000 493983440 0 1337069568 12928.2734375000 -2055.4763183594 -14994.0576171875 705 1305031252.9976520538 19906.0878906250 8160.6610697378 21271.6972656250 765.7830743181 0.0228040000 493985226 0 1337704448 12928.2734375000 -2055.4763183594 -14994.0576171875 706 1305031253.0298841000 19906.0917968750 8177.2976571700 21271.6972656250 765.2397730324 0.0192940000 493987012 0 1338212352 12928.2734375000 -2055.4763183594 -14994.0576171875 707 1305031253.0659010410 19906.0937500000 8193.8871848826 21271.6972656250 764.6976264780 0.0195840000 493988862 0 1338720256 12928.2734375000 -2055.4763183594 -14994.0576171875 708 1305031253.0979468822 19906.0957031250 8210.4298522813 21271.6972656250 764.1566305679 0.0229260000 493990680 0 1339228160 12928.2734375000 -2055.4763183594 -14994.0576171875 709 1305031253.1297280788 19906.0976562500 8226.9258576465 21271.6972656250 763.6167812393 0.0276720000 494069214 0 1339863040 12928.2734375000 -2055.4763183594 -14994.0576171875 710 1305031253.1659770012 19906.0996093750 8243.3753981419 21271.6972656250 763.0780744498 0.0227650000 494071064 0 1340370944 12928.2734375000 -2055.4763183594 -14994.0576171875 711 1305031253.1976099014 19906.1015625000 8259.7786698218 21271.6972656250 762.5405061735 0.0211350000 494072882 0 1341005824 12928.2734375000 -2055.4763183594 -14994.0576171875 712 1305031253.2299060822 19906.1015625000 8276.1358648957 21271.6972656250 762.0040724072 0.0218840000 494074636 0 1341513728 12928.2734375000 -2055.4763183594 -14994.0576171875 713 1305031253.2655360699 19906.1015625000 8292.4471772346 21271.6972656250 761.4687691679 0.0344460000 494153298 0 1342148608 12928.2734375000 -2055.4763183594 -14994.0576171875 714 1305031253.2976000309 19906.1035156250 8308.7128023584 21271.6972656250 760.9345924847 0.0353020000 494231928 0 1342783488 12928.2734375000 -2055.4763183594 -14994.0576171875 715 1305031253.3299720287 19906.1035156250 8324.9329292301 21271.6972656250 760.4015384146 0.0400110000 494310494 0 1343418368 12928.2734375000 -2055.4763183594 -14994.0576171875 716 1305031253.3662569523 19906.1015625000 8341.1077457570 21271.6972656250 759.8696030314 0.0189380000 494312376 0 1344053248 12928.2734375000 -2055.4763183594 -14994.0576171875 717 1305031253.3977351189 19906.1015625000 8357.2374442462 21271.6972656250 759.3387824270 0.0244060000 494314162 0 1344561152 12928.2734375000 -2055.4763183594 -14994.0576171875 718 1305031253.4297530651 19906.1035156250 8373.3222159334 21271.6972656250 758.8090727135 0.0254310000 494315916 0 1345196032 12928.2734375000 -2055.4763183594 -14994.0576171875 719 1305031253.4657158852 19906.1054687500 8389.3622482738 21271.6972656250 758.2804700217 0.0552720000 494394578 0 1345703936 12928.2734375000 -2055.4763183594 -14994.0576171875 720 1305031253.4976971149 19906.1054687500 8405.3577249690 21271.6972656250 757.7529705005 0.0297880000 494473208 0 1346338816 12928.2734375000 -2055.4763183594 -14994.0576171875 721 1305031253.5297060013 19906.1074218750 8421.3088341186 21271.6972656250 757.2265703189 0.0193590000 494474962 0 1346973696 12928.2734375000 -2055.4763183594 -14994.0576171875 722 1305031253.5656700134 19906.1093750000 8437.2157600755 21271.6972656250 756.7012656633 0.0204650000 494476812 0 1347481600 12928.2734375000 -2055.4763183594 -14994.0576171875 723 1305031253.5981209278 19906.1093750000 8453.0786834710 21271.6972656250 756.1770527390 0.0539960000 494555410 0 1348116480 12928.2734375000 -2055.4763183594 -14994.0576171875 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 06:09:52 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 nan 0.0432760000 87265011 0 923815936 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0280409548 0.0267198924 0.0280409548 0.0123609044 0.2895260000 99480040 0 935124992 -0.0006099615 0.0053528892 0.0072600655 3 1305031102.2432110310 0.0359880105 0.0298092651 0.0359880105 0.0133845120 0.2466490000 102751142 0 939061248 0.0004206164 0.0173057783 0.0178165194 4 1305031102.2753260136 0.0412140600 0.0326604638 0.0412140600 0.0132691698 0.2172740000 102753236 0 939696128 0.0000183965 0.0268396381 0.0280537456 5 1305031102.3112668991 0.0443367288 0.0349957168 0.0443367288 0.0118007662 0.2227200000 102755402 0 940204032 0.0009339002 0.0341212861 0.0394116901 6 1305031102.3432331085 0.0495219305 0.0374167524 0.0495219305 0.0105784811 0.2341970000 102757824 0 940711936 0.0022950524 0.0422406010 0.0488620810 7 1305031102.3753290176 0.0541357584 0.0398051819 0.0541357584 0.0105536279 0.2370800000 102759558 0 941219840 0.0059042498 0.0497328453 0.0601434559 8 1305031102.4112579823 0.0587387830 0.0421718820 0.0587387830 0.0129466068 0.2963290000 115105264 0 954044416 0.0049435357 0.0585378297 0.0682741329 9 1305031102.4432709217 0.0705640092 0.0453265628 0.0705640092 0.0146364270 0.2462780000 118765750 0 958234624 0.0050407043 0.0739800259 0.0760361850 10 1305031102.4753179550 0.0762758404 0.0484214906 0.0762758404 0.0141625327 0.1463690000 121960892 0 961916928 0.0062921657 0.0837072954 0.0880063474 11 1305031102.5112190247 0.0837449655 0.0516327156 0.0837449655 0.0141769256 0.1426240000 121962722 0 962551808 0.0087088859 0.0947596729 0.0997449011 12 1305031102.5432200432 0.0844418555 0.0543668106 0.0844418555 0.0137624912 0.1613690000 121964520 0 963059712 0.0083554359 0.0988506675 0.1107230857 13 1305031102.5752859116 0.0856451467 0.0567728364 0.0856451467 0.0131918578 0.1911340000 121966254 0 963694592 0.0096977651 0.1027918980 0.1229809597 14 1305031102.6112329960 0.0854976401 0.0588246081 0.0856451467 0.0131287382 0.1881890000 121968084 0 964202496 0.0153419254 0.1040718704 0.1368853301 15 1305031102.6432650089 0.0851280242 0.0605781692 0.0856451467 0.0131382369 0.4925010000 140805226 0 981979136 0.0109507181 0.1076509058 0.1414096951 16 1305031102.6752851009 0.0913586617 0.0625019500 0.0913586617 0.0131252396 0.2202400000 144464840 0 986169344 0.0122755188 0.1182418317 0.1526604146 17 1305031102.7112629414 0.0926472619 0.0642752036 0.0926472619 0.0127598182 0.1314910000 147660110 0 989978624 0.0136291366 0.1237345114 0.1651421487 18 1305031102.7432339191 0.1016466394 0.0663513945 0.1016466394 0.0133851975 0.1344850000 147664532 0 990613504 0.0136293545 0.1379199475 0.1747663170 19 1305031102.7754719257 0.1050806418 0.0683897759 0.1050806418 0.0135722825 0.1335440000 147666266 0 991121408 0.0129614212 0.1464011371 0.1866202056 20 1305031102.8112320900 0.1074474677 0.0703426605 0.1074474677 0.0139546207 0.1322360000 147668096 0 991629312 0.0110666584 0.1551139802 0.1970042735 21 1305031102.8432900906 0.1082745790 0.0721489423 0.1082745790 0.0137519569 0.1380250000 147669894 0 992391168 0.0115381507 0.1605361849 0.2093610615 22 1305031102.8753631115 0.1056974083 0.0736738726 0.1082745790 0.0136849399 0.4526810000 159980408 0 1005342720 0.0103813717 0.1624312848 0.2200519443 23 1305031102.9111850262 0.1140114069 0.0754276785 0.1140114069 0.0142030643 0.2424730000 163640494 0 1009278976 0.0090856245 0.1773365438 0.2322068959 24 1305031102.9432289600 0.1081655100 0.0767917548 0.1140114069 0.0140097413 0.1632660000 166834388 0 1012961280 0.0072690644 0.1757756621 0.2430645376 25 1305031102.9752030373 0.1049468443 0.0779179583 0.1140114069 0.0137430807 0.1711030000 166836090 0 1013596160 0.0047128615 0.1773274392 0.2526886463 26 1305031103.0112149715 0.1073129848 0.0790485363 0.1140114069 0.0135729819 0.1664330000 166837952 0 1014104064 0.0050748205 0.1845207661 0.2631732821 27 1305031103.0432269573 0.1094893143 0.0801759725 0.1140114069 0.0134123994 0.1583860000 166839750 0 1014992896 0.0045559113 0.1918150783 0.2735345364 28 1305031103.0753190517 0.1128568500 0.0813431467 0.1140114069 0.0133746294 0.1443960000 166841484 0 1015500800 0.0039165453 0.1999519616 0.2831188440 29 1305031103.1112399101 0.1174356118 0.0825877145 0.1174356118 0.0137198390 0.1430610000 166843314 0 1016008704 0.0042740759 0.2093916237 0.2906775773 30 1305031103.1433179379 0.1181251183 0.0837722946 0.1181251183 0.0135434338 0.4241070000 179151120 0 1028833280 0.0031665335 0.2150489092 0.2999287844 31 1305031103.1754519939 0.1233252883 0.0850481976 0.1233252883 0.0136139685 0.2468720000 182810734 0 1032769536 0.0029874602 0.2247044295 0.3077725768 32 1305031103.2112200260 0.1249431521 0.0862949149 0.1249431521 0.0140122755 0.1571670000 186004660 0 1036451840 0.0022184844 0.2320996672 0.3156119287 33 1305031103.2432160378 0.1258185357 0.0874926004 0.1258185357 0.0138591756 0.1609890000 186009146 0 1037086720 0.0038264887 0.2365263849 0.3234617412 34 1305031103.2753698826 0.1187374815 0.0884115675 0.1258185357 0.0136721658 0.2145040000 186016128 0 1037594624 0.0034705531 0.2321949005 0.3310245574 35 1305031103.3112099171 0.1117349714 0.0890779505 0.1258185357 0.0141878327 0.2372670000 186017958 0 1038229504 0.0037406336 0.2263019085 0.3356229365 36 1305031103.3432230949 0.1206511855 0.0899549848 0.1258185357 0.0142110724 0.1811040000 186019756 0 1038737408 0.0053313058 0.2361204177 0.3367928267 37 1305031103.3753271103 0.1209194362 0.0907918619 0.1258185357 0.0140191382 0.1856820000 186021490 0 1039245312 0.0067182127 0.2357201278 0.3376424611 38 1305031103.4112598896 0.1149394512 0.0914273247 0.1258185357 0.0140969394 0.1838200000 186023320 0 1039753216 0.0071959160 0.2269238830 0.3367514610 39 1305031103.4432799816 0.1136595160 0.0919973809 0.1258185357 0.0139236171 0.1779490000 186025118 0 1040261120 0.0067229890 0.2233940214 0.3329893649 40 1305031103.4752740860 0.1112292781 0.0924781783 0.1258185357 0.0139415878 0.1607470000 186026852 0 1040896000 0.0075629121 0.2169501036 0.3286167383 41 1305031103.5113329887 0.1089102700 0.0928789611 0.1258185357 0.0139633399 0.1666100000 186028682 0 1041403904 0.0083710961 0.2088232934 0.3225900531 42 1305031103.5434439182 0.1046742275 0.0931598008 0.1258185357 0.0141073171 0.1966400000 186030480 0 1041911808 0.0077962535 0.1993260533 0.3135044575 43 1305031103.5754740238 0.1050309986 0.0934358751 0.1258185357 0.0140353775 0.1820130000 186032214 0 1042419712 0.0059858952 0.1952284425 0.3035504818 44 1305031103.6112229824 0.1025248095 0.0936424418 0.1258185357 0.0140793796 0.1735760000 186034044 0 1043054592 0.0060129128 0.1858225465 0.2941935956 45 1305031103.6434450150 0.1016419530 0.0938202087 0.1258185357 0.0141266640 0.1826270000 186035842 0 1043562496 0.0071310648 0.1784377545 0.2837885022 46 1305031103.6755230427 0.1021944433 0.0940022573 0.1258185357 0.0141168092 0.1822510000 186037576 0 1044111360 0.0075140870 0.1727252603 0.2723749280 47 1305031103.7116100788 0.1038668975 0.0942121433 0.1258185357 0.0140990744 0.2227740000 186039406 0 1044619264 0.0083113788 0.1672116816 0.2607157230 48 1305031103.7433259487 0.1006774008 0.0943468361 0.1258185357 0.0140948472 0.2216260000 186041204 0 1045254144 0.0096221184 0.1566605121 0.2492003441 49 1305031103.7753419876 0.1025304645 0.0945138490 0.1258185357 0.0140467175 0.4886380000 198353602 0 1058045952 0.0109966388 0.1516114771 0.2359484881 50 1305031103.8112421036 0.1040229797 0.0947040316 0.1258185357 0.0139495737 0.2244900000 202013280 0 1062236160 0.0095864385 0.1471234560 0.2230069041 51 1305031103.8432509899 0.1059886143 0.0949252979 0.1258185357 0.0139077900 0.1344180000 205207174 0 1065918464 0.0074059572 0.1443535984 0.2101191878 52 1305031103.8753609657 0.0907848328 0.0948456736 0.1258185357 0.0150700354 0.1766240000 205208908 0 1066553344 0.0131068770 0.1201519966 0.2028072029 53 1305031103.9112210274 0.0858437642 0.0946758262 0.1258185357 0.0155792637 0.1317120000 205210738 0 1067188224 0.0134672532 0.1075667590 0.1908919066 54 1305031103.9432110786 0.0856530592 0.0945087379 0.1258185357 0.0155317710 0.1356410000 205212536 0 1067950080 0.0140065979 0.1013291627 0.1772824675 55 1305031103.9753730297 0.0834478959 0.0943076317 0.1258185357 0.0154025103 0.1311140000 205214302 0 1068457984 0.0136394035 0.0934629962 0.1646468341 56 1305031104.0112318993 0.0814026743 0.0940771861 0.1258185357 0.0154887026 0.1576650000 205216100 0 1068965888 0.0124152508 0.0853345320 0.1517742425 57 1305031104.0432488918 0.0830439180 0.0938836200 0.1258185357 0.0153626691 0.1878940000 205217898 0 1069473792 0.0129075618 0.0809104070 0.1369756758 58 1305031104.0754249096 0.0835767686 0.0937059156 0.1258185357 0.0152753911 0.4707230000 217525540 0 1082298368 0.0088287555 0.0775597245 0.1223084927 59 1305031104.1112349033 0.0811043754 0.0934923302 0.1258185357 0.0152961615 0.2331530000 221185218 0 1086361600 0.0111401286 0.0685676336 0.1121171787 60 1305031104.1432299614 0.0735675395 0.0931602503 0.1258185357 0.0153220410 0.1721360000 224379112 0 1090043904 0.0134797534 0.0546281151 0.1016634330 61 1305031104.1754240990 0.0691964403 0.0927674010 0.1258185357 0.0152012578 0.1529770000 224380846 0 1090551808 0.0132658100 0.0450257547 0.0898855925 62 1305031104.2112829685 0.0644418970 0.0923105380 0.1258185357 0.0152258367 0.1589280000 224382676 0 1091186688 0.0146368286 0.0345601849 0.0800129697 63 1305031104.2431960106 0.0621443205 0.0918317092 0.1258185357 0.0151734663 0.1567430000 224384474 0 1091694592 0.0159664117 0.0268861875 0.0695858970 64 1305031104.2755460739 0.0606399179 0.0913443374 0.1258185357 0.0150596598 0.1591610000 224386208 0 1092202496 0.0145912059 0.0216040239 0.0583238788 65 1305031104.3112189770 0.0607658811 0.0908738997 0.1258185357 0.0149517233 0.1852250000 224393414 0 1092710400 0.0110405236 0.0183048137 0.0469532497 66 1305031104.3433420658 0.0608006008 0.0904182436 0.1258185357 0.0148405358 0.1673140000 224405708 0 1093345280 0.0101314401 0.0148279071 0.0362470709 67 1305031104.3758370876 0.0574015379 0.0899254570 0.1258185357 0.0149350091 0.1628800000 224407442 0 1093853184 0.0098412344 0.0077834423 0.0275839735 68 1305031104.4115090370 0.0504694320 0.0893452213 0.1258185357 0.0148266064 0.2045930000 224409272 0 1094361088 0.0096175224 -0.0021281096 0.0203148108 69 1305031104.4432880878 0.0397866666 0.0886269814 0.1258185357 0.0148109931 0.4992600000 236717478 0 1107312640 0.0100453608 -0.0160920005 0.0141980005 70 1305031104.4754559994 0.0362855755 0.0878792470 0.1258185357 0.0147194360 0.2674150000 240377932 0 1111502848 0.0059025297 -0.0204311498 0.0089312671 71 1305031104.5113289356 0.0299140196 0.0870628354 0.1258185357 0.0149200394 0.1645210000 243571858 0 1115185152 0.0065808892 -0.0309081543 0.0038947258 72 1305031104.5433681011 0.0305610877 0.0862780889 0.1258185357 0.0148598731 0.2119570000 243573656 0 1115820032 0.0081030168 -0.0338837840 -0.0031739180 73 1305031104.5753428936 0.0334631950 0.0855545972 0.1258185357 0.0148181562 0.1786250000 243575358 0 1116327936 0.0105000939 -0.0353515632 -0.0075465860 74 1305031104.6113359928 0.0377725251 0.0849088935 0.1258185357 0.0149605279 0.1726880000 243577220 0 1116962816 0.0177807510 -0.0446102060 -0.0097509697 75 1305031104.6432430744 0.0380404294 0.0842839806 0.1258185357 0.0149598871 0.1733170000 243578986 0 1117470720 0.0208068006 -0.0486456081 -0.0197284874 76 1305031104.6755249500 0.0338662863 0.0836205899 0.1258185357 0.0148622515 0.1570190000 243580752 0 1117978624 0.0174933933 -0.0563543998 -0.0265044738 77 1305031104.7112770081 0.0308865216 0.0829357319 0.1258185357 0.0149249384 0.5984380000 255892618 0 1130795008 0.0161396563 -0.0654211044 -0.0360112377 78 1305031104.7432799339 0.0280194841 0.0822316774 0.1258185357 0.0148945865 0.2024180000 259552232 0 1134985216 0.0157109927 -0.0649651363 -0.0473018587 79 1305031104.7753269672 0.0267012659 0.0815287608 0.1258185357 0.0148525586 0.1917050000 262746062 0 1138667520 0.0153689161 -0.0661407262 -0.0548774563 80 1305031104.8114650249 0.0279357918 0.0808588487 0.1258185357 0.0147979223 0.1622730000 262747924 0 1139302400 0.0161558297 -0.0633143410 -0.0628866255 81 1305031104.8432579041 0.0283468012 0.0802105518 0.1258185357 0.0147237882 0.1580710000 262749690 0 1139937280 0.0166794360 -0.0609674677 -0.0684912652 82 1305031104.8753499985 0.0293618962 0.0795904463 0.1258185357 0.0146871977 0.1786740000 262751456 0 1140445184 0.0135885850 -0.0562375598 -0.0742660612 83 1305031104.9115340710 0.0321150459 0.0790184535 0.1258185357 0.0145993695 0.1653680000 262753286 0 1140953088 0.0147867044 -0.0520602912 -0.0752525777 84 1305031104.9432621002 0.0324172489 0.0784636773 0.1258185357 0.0145129678 0.7066030000 275075016 0 1153777664 0.0151381455 -0.0503222086 -0.0748067871 85 1305031104.9752020836 0.0597072989 0.0782430140 0.1258185357 0.0149998943 0.2507790000 278734630 0 1157967872 0.0021161637 -0.0212537944 -0.0755712762 86 1305031105.0112900734 0.0635678321 0.0780723723 0.1258185357 0.0149594078 0.2272900000 281928556 0 1161650176 0.0021514953 -0.0143314730 -0.0710351765 87 1305031105.0433731079 0.0667078272 0.0779417454 0.1258185357 0.0149000355 0.2387890000 281930322 0 1162285056 -0.0003932840 -0.0089193340 -0.0663068742 88 1305031105.0753200054 0.0688386261 0.0778383008 0.1258185357 0.0148330682 0.2282970000 281932088 0 1162792960 -0.0015413043 -0.0040668156 -0.0584678501 89 1305031105.1112990379 0.0641900897 0.0776849501 0.1258185357 0.0147671898 0.2117580000 281933918 0 1163427840 -0.0045493837 -0.0054141753 -0.0507548861 90 1305031105.1431059837 0.0711191744 0.0776119971 0.1258185357 0.0147371900 0.1975770000 281935684 0 1163935744 -0.0106810620 0.0039121029 -0.0449290834 91 1305031105.1751589775 0.0801711082 0.0776401192 0.1258185357 0.0148120356 0.2077560000 281937450 0 1164443648 -0.0154339019 0.0165659618 -0.0344643816 92 1305031105.2112679482 0.0713274926 0.0775715037 0.1258185357 0.0149404019 0.2094340000 281939280 0 1165078528 -0.0208320487 0.0103083653 -0.0247408692 93 1305031105.2432699203 0.0727573559 0.0775197386 0.1258185357 0.0148906047 0.2023690000 281941046 0 1165713408 -0.0262308195 0.0142194694 -0.0155175589 94 1305031105.2752881050 0.0761536956 0.0775052063 0.1258185357 0.0149825353 0.2168130000 281942812 0 1166221312 -0.0329310820 0.0201223884 -0.0058156410 95 1305031105.3112900257 0.0729939267 0.0774577191 0.1258185357 0.0149579566 0.7343130000 294254438 0 1179172864 -0.0367725268 0.0202240869 0.0050740680 96 1305031105.3433020115 0.0730391070 0.0774116919 0.1258185357 0.0148899574 0.2324360000 297914052 0 1183363072 -0.0330724344 0.0264873412 0.0160501674 97 1305031105.3753380775 0.0717866197 0.0773537015 0.1258185357 0.0148199165 0.1704670000 301107914 0 1187045376 -0.0315123945 0.0308286361 0.0302082337 98 1305031105.4112861156 0.0794444531 0.0773750357 0.1258185357 0.0149074189 0.1736210000 301109744 0 1187680256 -0.0354039259 0.0414767452 0.0384834819 99 1305031105.4433159828 0.0765174031 0.0773663727 0.1258185357 0.0148403731 0.1717720000 301111510 0 1188188160 -0.0312888213 0.0446865447 0.0529094860 100 1305031105.4752800465 0.0718631074 0.0773113401 0.1258185357 0.0147974804 0.1700860000 301113276 0 1188696064 -0.0261219945 0.0437410474 0.0639347136 101 1305031105.5113320351 0.0743062571 0.0772815868 0.1258185357 0.0147959219 0.1735540000 301115106 0 1189203968 -0.0237947460 0.0493510850 0.0744978786 102 1305031105.5432820320 0.0700239241 0.0772104332 0.1258185357 0.0147298739 0.9849790000 313425972 0 1202028544 -0.0219374634 0.0485487133 0.0869585797 103 1305031105.5754489899 0.0743800402 0.0771829537 0.1258185357 0.0147360221 0.2258690000 317085586 0 1206218752 -0.0121076452 0.0555302128 0.0986600295 104 1305031105.6113779545 0.0742178336 0.0771544429 0.1258185357 0.0146955636 0.1626500000 320279512 0 1210028032 -0.0085783647 0.0580267645 0.1121783108 105 1305031105.6432731152 0.0752126351 0.0771359495 0.1258185357 0.0146259260 0.1615290000 320281278 0 1210535936 -0.0087708319 0.0626668781 0.1236242205 106 1305031105.6751658916 0.0819254816 0.0771811338 0.1258185357 0.0146738484 0.2152980000 320283044 0 1211162624 -0.0075847576 0.0745082200 0.1359191835 107 1305031105.7113089561 0.0818531066 0.0772247971 0.1258185357 0.0146586251 0.1828730000 320284874 0 1211670528 -0.0017294500 0.0772205070 0.1507064104 108 1305031105.7433118820 0.0885910392 0.0773300400 0.1258185357 0.0147625773 0.2289050000 320286640 0 1212178432 -0.0027110297 0.0886281878 0.1600270718 109 1305031105.7753388882 0.0906622261 0.0774523537 0.1258185357 0.0147221516 0.1651800000 320288406 0 1212686336 0.0022666121 0.0950158909 0.1745031327 110 1305031105.8112831116 0.0916314274 0.0775812543 0.1258185357 0.0147151225 0.1588120000 320290236 0 1213321216 0.0024108929 0.1006458625 0.1870572567 111 1305031105.8432710171 0.0931119993 0.0777211710 0.1258185357 0.0146899510 0.1638110000 320292002 0 1213829120 0.0064071552 0.1061880738 0.1989982128 112 1305031105.8753368855 0.0979682729 0.0779019487 0.1258185357 0.0147631981 1.1450350000 332603824 0 1226653696 0.0056502628 0.1171558872 0.2091848254 113 1305031105.9112620354 0.1022040322 0.0781170113 0.1258185357 0.0150362396 0.2111470000 336263502 0 1230843904 0.0127211101 0.1294123530 0.2278487831 114 1305031105.9432721138 0.1045055017 0.0783484893 0.1258185357 0.0150377427 0.1469010000 339457364 0 1234526208 0.0148715656 0.1374467313 0.2394900769 115 1305031105.9753289223 0.1052464768 0.0785823849 0.1258185357 0.0150285781 0.1328870000 339459130 0 1235161088 0.0156428609 0.1448221803 0.2511797547 116 1305031106.0112850666 0.1067381054 0.0788251066 0.1258185357 0.0150677989 0.1336040000 339460960 0 1235668992 0.0182970930 0.1522796750 0.2622857094 117 1305031106.0433549881 0.1054585129 0.0790527426 0.1258185357 0.0150184347 0.1562290000 339462758 0 1236176896 0.0184748154 0.1571991891 0.2740578651 118 1305031106.0753300190 0.1050837785 0.0792733446 0.1258185357 0.0149911282 0.1428260000 339464492 0 1236692992 0.0183873903 0.1631498039 0.2849638164 119 1305031106.1113269329 0.1074277610 0.0795099363 0.1258185357 0.0150198971 1.2772000000 351803298 0 1249517568 0.0177072175 0.1721076518 0.2952114046 120 1305031106.1433548927 0.1063378602 0.0797335023 0.1258185357 0.0149938510 0.2065750000 355462944 0 1253834752 0.0149895679 0.1796819270 0.3106202483 121 1305031106.1755340099 0.1053270772 0.0799450195 0.1258185357 0.0149672431 0.1465860000 358656774 0 1257644032 0.0144121628 0.1836599708 0.3199511766 122 1305031106.2112751007 0.1008817703 0.0801166322 0.1258185357 0.0149097473 0.1380460000 358658604 0 1258278912 0.0128471404 0.1842179000 0.3287973106 123 1305031106.2432670593 0.1009809747 0.0802862610 0.1258185357 0.0149067653 0.1387890000 358660402 0 1258786816 0.0116317756 0.1889364570 0.3355457485 124 1305031106.2763850689 0.1034107581 0.0804727489 0.1258185357 0.0148560141 0.1482460000 358662168 0 1259294720 0.0100146383 0.1961085498 0.3408252597 125 1305031106.3112380505 0.1043047681 0.0806634050 0.1258185357 0.0148106681 0.1461930000 358663966 0 1259802624 0.0103443479 0.2003700733 0.3465785682 126 1305031106.3432579041 0.1080380082 0.0808806638 0.1258185357 0.0147741416 0.1481580000 358665764 0 1260437504 0.0123469513 0.2061761618 0.3505576849 127 1305031106.3753879070 0.1135031059 0.0811375334 0.1258185357 0.0147546600 0.1592620000 358667498 0 1260945408 0.0141083430 0.2135720849 0.3543061614 128 1305031106.4113199711 0.1066367924 0.0813367464 0.1258185357 0.0147093601 0.1495400000 358669328 0 1261453312 0.0130669940 0.2066333592 0.3553913534 129 1305031106.4432780743 0.0989859253 0.0814735617 0.1258185357 0.0147242214 0.1743210000 358681846 0 1261961216 0.0103476839 0.1982478797 0.3536376357 130 1305031106.4753448963 0.0959840864 0.0815851811 0.1258185357 0.0147070401 0.1694210000 358704604 0 1262596096 0.0088209109 0.1933493018 0.3497304916 131 1305031106.5111289024 0.0907734260 0.0816553204 0.1258185357 0.0147400791 0.1433650000 358706338 0 1263104000 0.0069835270 0.1843611300 0.3438494503 132 1305031106.5433020592 0.0921031237 0.0817344704 0.1258185357 0.0147160548 0.1662870000 358708136 0 1263611904 0.0079729445 0.1807751060 0.3352246284 133 1305031106.5752820969 0.0928482339 0.0818180325 0.1258185357 0.0146884732 0.2009590000 358709870 0 1264246784 0.0086617079 0.1759108305 0.3255386055 134 1305031106.6111509800 0.0944922864 0.0819126165 0.1258185357 0.0146857397 0.2026590000 358711700 0 1264754688 0.0064935032 0.1730975956 0.3150493503 135 1305031106.6432070732 0.0896742567 0.0819701102 0.1258185357 0.0148566377 0.1482390000 358713498 0 1265262592 0.0083279340 0.1606078595 0.3043553233 136 1305031106.6752789021 0.0895552635 0.0820258833 0.1258185357 0.0148221586 0.1617910000 358715232 0 1265770496 0.0062676799 0.1559806019 0.2921255231 137 1305031106.7115080357 0.0860839039 0.0820555039 0.1258185357 0.0149123125 0.1771580000 358717062 0 1266405376 0.0040078880 0.1475319713 0.2804771364 138 1305031106.7433409691 0.0866164267 0.0820885541 0.1258185357 0.0149180708 0.1644810000 358718860 0 1267032064 0.0027912611 0.1431127191 0.2672169507 139 1305031106.7753899097 0.0875492990 0.0821278400 0.1258185357 0.0149199950 0.1816290000 358720594 0 1267539968 0.0024922921 0.1386426240 0.2530903518 140 1305031106.8112890720 0.0895752162 0.0821810356 0.1258185357 0.0148863240 0.1800800000 358722424 0 1268047872 0.0019451790 0.1350385696 0.2382789552 141 1305031106.8434159756 0.0825598463 0.0821837222 0.1258185357 0.0150205164 1.2261610000 371035174 0 1280880640 -0.0010467031 0.1228619069 0.2257853299 142 1305031106.8759050369 0.0844203308 0.0821994729 0.1258185357 0.0150394716 0.2274610000 374694788 0 1285070848 -0.0008538043 0.1184722409 0.2114635408 143 1305031106.9112429619 0.0907409638 0.0822592037 0.1258185357 0.0150031816 0.1831630000 377888714 0 1288880128 -0.0007767321 0.1178188324 0.1938659102 144 1305031106.9434390068 0.0847740024 0.0822766675 0.1258185357 0.0151191187 0.1621800000 377890480 0 1289388032 -0.0037465079 0.1060356721 0.1799692065 145 1305031106.9755470753 0.0787559748 0.0822523869 0.1258185357 0.0150947049 0.1682750000 377892246 0 1290022912 -0.0073972200 0.0942573175 0.1648314595 146 1305031107.0115759373 0.0873184204 0.0822870858 0.1258185357 0.0150551538 0.1617730000 377894108 0 1290530816 -0.0076992288 0.0951987505 0.1453590542 147 1305031107.0432810783 0.0812717602 0.0822801788 0.1258185357 0.0150532893 0.1672240000 377895874 0 1291038720 -0.0105027650 0.0838864595 0.1331751943 148 1305031107.0754320621 0.0722571090 0.0822124553 0.1258185357 0.0150595572 0.1568590000 377897608 0 1291546624 -0.0139999902 0.0692621395 0.1209180877 149 1305031107.1112289429 0.0763505027 0.0821731134 0.1258185357 0.0150246659 1.6451190000 390213210 0 1304371200 -0.0153061217 0.0670131817 0.1050557718 150 1305031107.1432600021 0.0802261159 0.0821601334 0.1258185357 0.0149813062 0.2226050000 393872856 0 1308688384 -0.0117811086 0.0651740655 0.0908768550 151 1305031107.1753990650 0.0718946308 0.0820921499 0.1258185357 0.0149865854 0.2239090000 397066686 0 1312370688 -0.0129246404 0.0520713925 0.0809241310 152 1305031107.2113580704 0.0685895532 0.0820033171 0.1258185357 0.0149910799 0.1942020000 397068516 0 1313005568 -0.0146737508 0.0432176068 0.0688280240 153 1305031107.2433779240 0.0710318834 0.0819316083 0.1258185357 0.0149507703 0.1632220000 397070282 0 1313513472 -0.0157963540 0.0409679078 0.0556689836 154 1305031107.2753980160 0.0675189272 0.0818380195 0.1258185357 0.0149112339 0.1806570000 397072048 0 1314021376 -0.0164116118 0.0332346186 0.0453567579 155 1305031107.3112258911 0.0638246760 0.0817218044 0.1258185357 0.0148989669 0.1935720000 397073878 0 1314656256 -0.0169074759 0.0246398635 0.0367137082 156 1305031107.3435089588 0.0615635291 0.0815925847 0.1258185357 0.0148791024 0.1776330000 397075676 0 1315164160 -0.0191969406 0.0176548306 0.0260752141 157 1305031107.3754129410 0.0672710761 0.0815013649 0.1258185357 0.0148894202 0.1585640000 397077410 0 1315672064 -0.0172505900 0.0194911361 0.0144021185 158 1305031107.4112710953 0.0677540079 0.0814143563 0.1258185357 0.0148511860 0.1834710000 397079240 0 1316179968 -0.0148280561 0.0159670934 0.0077010496 159 1305031107.4434189796 0.0710331500 0.0813490657 0.1258185357 0.0148078452 1.8400680000 409399894 0 1328996352 -0.0121623864 0.0162524581 0.0020860452 160 1305031107.4753770828 0.0701607242 0.0812791385 0.1258185357 0.0147701474 0.2231660000 413061164 0 1333186560 -0.0066387267 0.0136354528 0.0007661673 161 1305031107.5113520622 0.0766277984 0.0812502482 0.1258185357 0.0147350355 0.1712770000 416255058 0 1336995840 -0.0052210288 0.0179629996 -0.0048031248 162 1305031107.5436050892 0.0748321787 0.0812106305 0.1258185357 0.0146950987 0.1636160000 416256856 0 1337503744 -0.0013506491 0.0158180632 -0.0046243030 163 1305031107.5754539967 0.0702137500 0.0811431650 0.1258185357 0.0146684181 0.1750680000 416258590 0 1338138624 0.0028640982 0.0121692391 -0.0014941298 164 1305031107.6112709045 0.0770150647 0.0811179936 0.1258185357 0.0146423134 0.1649030000 416260420 0 1338646528 0.0054775747 0.0190892182 -0.0056106858 165 1305031107.6433229446 0.0776638240 0.0810970593 0.1258185357 0.0146006204 0.1682360000 416262218 0 1339154432 0.0044341651 0.0216333643 -0.0044307653 166 1305031107.6755681038 0.0769259334 0.0810719320 0.1258185357 0.0145581146 0.2328820000 416263952 0 1339662336 0.0075244163 0.0237629283 -0.0005206705 167 1305031107.7113070488 0.0792169794 0.0810608245 0.1258185357 0.0145230749 0.2351090000 416265782 0 1340297216 0.0077779894 0.0293114167 0.0010051751 168 1305031107.7435379028 0.0836010575 0.0810759449 0.1258185357 0.0144928456 0.2432870000 416267548 0 1340805120 0.0075154454 0.0366053507 0.0034750649 169 1305031107.7758018970 0.0791928098 0.0810648021 0.1258185357 0.0144565067 0.2396540000 416269314 0 1341313024 0.0074377414 0.0344501510 0.0056629661 170 1305031107.8115959167 0.0801706463 0.0810595424 0.1258185357 0.0144181242 0.2255850000 416271144 0 1341820928 0.0102933059 0.0377333276 0.0072750156 171 1305031107.8433320522 0.0789327696 0.0810471051 0.1258185357 0.0143774936 0.1817110000 416272910 0 1342464000 0.0131061878 0.0379106216 0.0085350312 172 1305031107.8753581047 0.0728028193 0.0809991732 0.1258185357 0.0143567926 0.1975640000 416274676 0 1342971904 0.0169581641 0.0327838250 0.0111036235 173 1305031107.9115409851 0.0717093870 0.0809454750 0.1258185357 0.0143460655 0.1860490000 416276506 0 1343733760 0.0201960895 0.0336929001 0.0130852675 174 1305031107.9431219101 0.0699605048 0.0808823430 0.1258185357 0.0143201002 0.2056150000 416278272 0 1344241664 0.0262105335 0.0322574750 0.0147664277 175 1305031107.9758069515 0.0680744424 0.0808091550 0.1258185357 0.0143041475 0.2077160000 416280038 0 1344749568 0.0336712562 0.0313268080 0.0175476801 176 1305031108.0113201141 0.0681299418 0.0807371140 0.1258185357 0.0142843891 0.2350090000 416281868 0 1345257472 0.0445354246 0.0313034058 0.0184242446 177 1305031108.0434179306 0.0724487081 0.0806902869 0.1258185357 0.0142697765 0.2369360000 416283634 0 1345892352 0.0600120053 0.0351012424 0.0195606779 178 1305031108.0753519535 0.0701685846 0.0806311762 0.1258185357 0.0142600640 0.2351300000 416285368 0 1346400256 0.0714629441 0.0335056521 0.0239781737 179 1305031108.1113779545 0.0668420717 0.0805541421 0.1258185357 0.0142301326 0.2283350000 416287198 0 1346908160 0.0783165917 0.0321402326 0.0270788632 180 1305031108.1433339119 0.0714360774 0.0805034862 0.1258185357 0.0142056314 1.9890760000 428601252 0 1359859712 0.0934598222 0.0356598906 0.0264181457 181 1305031108.1760580540 0.0976410881 0.0805981691 0.1258185357 0.0144959560 0.2107100000 432260866 0 1363922944 0.1100988463 0.0649099275 0.0301182587 182 1305031108.2114748955 0.0941528603 0.0806726454 0.1258185357 0.0144599728 0.1732240000 435454792 0 1367605248 0.1222930923 0.0627873167 0.0345639773 183 1305031108.2433469296 0.0860629678 0.0807021007 0.1258185357 0.0144224284 0.1834030000 435456558 0 1368240128 0.1388152242 0.0563543625 0.0431809612 184 1305031108.2753579617 0.0917511955 0.0807621501 0.1258185357 0.0143905464 0.1538530000 435458324 0 1368748032 0.1512733102 0.0625217780 0.0414796211 185 1305031108.3113319874 0.0929644629 0.0808281086 0.1258185357 0.0143873522 0.1790370000 435460154 0 1369382912 0.1606755704 0.0674347952 0.0423932746 186 1305031108.3432779312 0.0933167562 0.0808952519 0.1258185357 0.0143517227 0.1848200000 435461952 0 1369890816 0.1713001281 0.0706217140 0.0458033234 187 1305031108.3754100800 0.0910996348 0.0809498207 0.1258185357 0.0143175074 0.1680310000 435463686 0 1370398720 0.1800211668 0.0717902929 0.0499774925 188 1305031108.4113609791 0.0877666324 0.0809860804 0.1258185357 0.0142977566 0.1644480000 435465516 0 1370906624 0.1939068437 0.0721345395 0.0545109548 189 1305031108.4436099529 0.0876468271 0.0810213224 0.1258185357 0.0142869538 1.5763550000 447778758 0 1383731200 0.2085560411 0.0744164661 0.0579442680 190 1305031108.4754710197 0.1003335118 0.0811229655 0.1258185357 0.0142862191 0.1945780000 451438340 0 1387921408 0.2240228951 0.0907543674 0.0666169375 191 1305031108.5113780499 0.0963874906 0.0812028845 0.1258185357 0.0143727323 0.1511090000 454632266 0 1391730688 0.2439470589 0.0885371640 0.0748011023 192 1305031108.5437369347 0.0947187096 0.0812732794 0.1258185357 0.0143863704 0.1617460000 454634064 0 1392238592 0.2598576248 0.0870837271 0.0792259425 193 1305031108.5754139423 0.0996911302 0.0813687087 0.1258185357 0.0143862338 0.1373710000 454635798 0 1392873472 0.2720145881 0.0933106691 0.0747835338 194 1305031108.6114070415 0.0981777534 0.0814553533 0.1258185357 0.0144006451 0.1497720000 454637628 0 1393381376 0.2870837152 0.0945402756 0.0798262879 195 1305031108.6433029175 0.0997868031 0.0815493607 0.1258185357 0.0143935025 0.1485290000 454639426 0 1393889280 0.2969952822 0.0985300243 0.0800684020 196 1305031108.6753749847 0.1041751280 0.0816647983 0.1258185357 0.0143924167 0.1338970000 454641160 0 1394397184 0.3134362400 0.1034196541 0.0816032216 197 1305031108.7114109993 0.0981250927 0.0817483531 0.1258185357 0.0143890348 0.8598900000 466949454 0 1407221760 0.3226481080 0.1011690572 0.0849028230 198 1305031108.7435019016 0.0920393467 0.0818003278 0.1258185357 0.0143604594 0.1768900000 470609100 0 1411403776 0.3252760768 0.0979211256 0.0847642273 199 1305031108.7754929066 0.0931852534 0.0818575385 0.1258185357 0.0143273268 0.1409270000 473802930 0 1415086080 0.3337570131 0.1002498195 0.0857785493 200 1305031108.8112440109 0.0883224234 0.0818898629 0.1258185357 0.0142981019 0.1438400000 473804760 0 1415720960 0.3346976042 0.0989096388 0.0883504078 201 1305031108.8432641029 0.0858576894 0.0819096033 0.1258185357 0.0156557087 0.1348900000 473806558 0 1416355840 0.3351881802 0.0958615541 0.0895202160 202 1305031108.8765149117 0.0853526369 0.0819266481 0.1258185357 0.0157386303 0.1359170000 473808324 0 1416863744 0.3347719312 0.0954252481 0.0876712799 203 1305031108.9113640785 0.0823009834 0.0819284921 0.1258185357 0.0158738187 0.1498030000 473810122 0 1417371648 0.3374864161 0.0919118524 0.0876004919 204 1305031108.9432430267 0.0816071332 0.0819269168 0.1258185357 0.0159534857 0.1466340000 473811920 0 1417879552 0.3351470828 0.0914856493 0.0837947950 205 1305031108.9752678871 0.0882079005 0.0819575557 0.1258185357 0.0159197811 0.1466090000 473813686 0 1418395648 0.3331376016 0.0967513323 0.0763480514 206 1305031109.0112690926 0.0915849134 0.0820042905 0.1258185357 0.0158827832 0.1368240000 473815484 0 1419030528 0.3347894847 0.0978439525 0.0746845827 207 1305031109.0432770252 0.0914558917 0.0820499504 0.1258185357 0.0158488797 0.1648460000 473817282 0 1419538432 0.3285194039 0.0967639759 0.0714991093 208 1305031109.0754098892 0.0974209830 0.0821238496 0.1258185357 0.0158223661 0.1611460000 473819016 0 1420046336 0.3199258447 0.1018998548 0.0650659055 209 1305031109.1112821102 0.0963795111 0.0821920585 0.1258185357 0.0158115223 0.2607750000 473820846 0 1420554240 0.3108963370 0.1002645120 0.0672885031 210 1305031109.1433339119 0.0900312141 0.0822293878 0.1258185357 0.0158070504 0.2142630000 473822644 0 1421189120 0.2908408642 0.0949679986 0.0653171167 211 1305031109.1754639149 0.0971762091 0.0823002258 0.1258185357 0.0157905489 0.1684550000 473824378 0 1421697024 0.2817046344 0.1014705226 0.0624816157 212 1305031109.2113790512 0.1060484648 0.0824122458 0.1258185357 0.0157644145 0.1557510000 473826208 0 1422204928 0.2756440938 0.1091587171 0.0555751212 213 1305031109.2432899475 0.1048766747 0.0825177126 0.1258185357 0.0157328547 0.1600260000 473828006 0 1422712832 0.2617006898 0.1098561957 0.0591696911 214 1305031109.2753078938 0.0920647755 0.0825623251 0.1258185357 0.0157839821 0.1384200000 473829740 0 1423220736 0.2425889969 0.0985788107 0.0702914894 215 1305031109.3113288879 0.0952775255 0.0826214655 0.1258185357 0.0157992942 0.1481930000 473831570 0 1423855616 0.2256860733 0.1008585244 0.0645377934 216 1305031109.3432478905 0.1023746580 0.0827129155 0.1258185357 0.0157648546 0.1379980000 473833368 0 1424363520 0.2124619186 0.1072981358 0.0587135926 217 1305031109.3753969669 0.0960459784 0.0827743582 0.1258185357 0.0157572646 0.6574980000 486139422 0 1437188096 0.1960042119 0.1013473794 0.0644741133 218 1305031109.4113290310 0.0976810530 0.0828427375 0.1258185357 0.0157676489 0.1876430000 489799100 0 1441505280 0.1793871671 0.1021448299 0.0615426265 219 1305031109.4433019161 0.1019902006 0.0829301689 0.1258185357 0.0157343163 0.1614080000 492992962 0 1445187584 0.1686207801 0.1055876464 0.0577678829 220 1305031109.4753630161 0.1000125036 0.0830078158 0.1258185357 0.0157127666 0.1464680000 492994696 0 1445822464 0.1567115486 0.1028755382 0.0598327927 221 1305031109.5112729073 0.0989295244 0.0830798598 0.1258185357 0.0156965619 0.1469040000 492996526 0 1446330368 0.1435382068 0.1001258045 0.0618193895 222 1305031109.5432939529 0.0995093733 0.0831538666 0.1258185357 0.0156656431 0.1426730000 492998324 0 1446965248 0.1296220571 0.0998363942 0.0574533045 223 1305031109.5753619671 0.1031107828 0.0832433595 0.1258185357 0.0156324892 0.1394380000 493000090 0 1447473152 0.1159763709 0.1028285921 0.0542582497 224 1305031109.6113100052 0.1036211848 0.0833343319 0.1258185357 0.0156151580 0.1442920000 493001888 0 1447981056 0.1033420116 0.1019935980 0.0526546128 225 1305031109.6432290077 0.1066414863 0.0834379193 0.1258185357 0.0155804630 0.1446610000 493003686 0 1448488960 0.0912102312 0.1051328033 0.0496767275 226 1305031109.6752629280 0.1096486151 0.0835538958 0.1258185357 0.0155497380 0.1512540000 493005420 0 1449123840 0.0740051270 0.1087111607 0.0471893474 227 1305031109.7113120556 0.1107226536 0.0836735819 0.1258185357 0.0155309170 0.1438120000 493007250 0 1449631744 0.0648100600 0.1098014191 0.0463774502 228 1305031109.7432739735 0.1108161435 0.0837926283 0.1258185357 0.0155034038 1.3535810000 505370800 0 1462456320 0.0524104014 0.1106397063 0.0467459746 229 1305031109.7752768993 0.1067722589 0.0838929760 0.1258185357 0.0155594512 0.2048950000 509030382 0 1466646528 0.0408280902 0.1051210761 0.0333145782 230 1305031109.8113710880 0.1091388240 0.0840027406 0.1258185357 0.0155452019 0.1711340000 512224308 0 1470455808 0.0265360232 0.1078976095 0.0343676247 231 1305031109.8432960510 0.1088571474 0.0841103354 0.1258185357 0.0155150764 0.1606810000 512226106 0 1471090688 0.0124645894 0.1088329852 0.0360097289 232 1305031109.8753058910 0.1089027375 0.0842171992 0.1258185357 0.0154982178 0.1708140000 512227840 0 1471598592 -0.0028482545 0.1101074964 0.0393575206 233 1305031109.9112648964 0.1056569740 0.0843092154 0.1258185357 0.0154756916 0.1607690000 512229670 0 1472106496 -0.0159575082 0.1072889566 0.0438720658 234 1305031109.9432990551 0.1114330217 0.0844251291 0.1258185357 0.0154653282 0.1786000000 512231468 0 1472741376 -0.0258042272 0.1132133678 0.0430319607 235 1305031109.9752581120 0.1086226702 0.0845280974 0.1258185357 0.0154614310 0.1490230000 512233202 0 1473249280 -0.0394141227 0.1113271937 0.0477994792 236 1305031110.0112559795 0.1096362993 0.0846344880 0.1258185357 0.0154399289 0.1481970000 512235032 0 1473884160 -0.0505745932 0.1119140461 0.0508715622 237 1305031110.0432989597 0.1095357910 0.0847395568 0.1258185357 0.0154149793 1.4191120000 524546386 0 1486708736 -0.0623517074 0.1123905480 0.0541534126 238 1305031110.0753190517 0.1136105508 0.0848608635 0.1258185357 0.0153908608 0.1994810000 528205968 0 1490898944 -0.0694887191 0.1161225140 0.0582434237 239 1305031110.1113250256 0.1134104952 0.0849803181 0.1258185357 0.0153945123 0.1615240000 531399894 0 1494581248 -0.0840570778 0.1164948493 0.0616851784 240 1305031110.1434319019 0.1088974327 0.0850799727 0.1258185357 0.0153756812 0.1619470000 531401692 0 1495216128 -0.0961697996 0.1127309948 0.0652243048 241 1305031110.1756410599 0.1135630980 0.0851981599 0.1258185357 0.0153462973 0.1563160000 531403426 0 1495724032 -0.1065995097 0.1179039404 0.0639149174 242 1305031110.2116370201 0.1118106395 0.0853081289 0.1258185357 0.0153304845 0.1566070000 531405288 0 1496231936 -0.1183253527 0.1162502095 0.0680812523 243 1305031110.2433230877 0.1096887663 0.0854084607 0.1258185357 0.0153029084 0.1674660000 531407054 0 1496866816 -0.1287220120 0.1143363193 0.0702755973 244 1305031110.2793209553 0.1112117320 0.0855142118 0.1258185357 0.0152843931 0.1673040000 531408884 0 1497374720 -0.1365763843 0.1137699187 0.0717020929 245 1305031110.3114039898 0.1113920286 0.0856198356 0.1258185357 0.0152556169 0.1480330000 531410618 0 1497882624 -0.1486504376 0.1149385422 0.0709081739 246 1305031110.3433549404 0.1143588722 0.0857366609 0.1258185357 0.0152251891 0.1611480000 531412384 0 1498390528 -0.1588988453 0.1180485561 0.0699285939 247 1305031110.3792810440 0.1151942238 0.0858559223 0.1258185357 0.0152208831 0.1835180000 531414214 0 1498898432 -0.1698294431 0.1179120839 0.0703738704 248 1305031110.4114689827 0.1181039214 0.0859859546 0.1258185357 0.0151944437 0.1564500000 531415980 0 1499533312 -0.1822551191 0.1217874512 0.0644190907 249 1305031110.4432599545 0.1196064875 0.0861209768 0.1258185357 0.0151858943 1.3404830000 543725542 0 1512357888 -0.1926832199 0.1237884164 0.0652241111 250 1305031110.4793310165 0.1177321300 0.0862474214 0.1258185357 0.0152018442 0.1872060000 547385252 0 1516421120 -0.2029283047 0.1205362454 0.0658128709 251 1305031110.5114290714 0.1178941354 0.0863735039 0.1258185357 0.0151786178 0.1492670000 550579082 0 1520230400 -0.2135004997 0.1212327853 0.0659026429 252 1305031110.5434079170 0.1225772500 0.0865171696 0.1258185357 0.0151501118 0.1307380000 550580880 0 1520865280 -0.2227059454 0.1266473532 0.0651715696 253 1305031110.5794260502 0.1265112162 0.0866752488 0.1265112162 0.0151349353 0.1508980000 550582710 0 1521373184 -0.2309602052 0.1300510317 0.0655578747 254 1305031110.6113069057 0.1234582737 0.0868200639 0.1265112162 0.0151469408 0.1506170000 550584444 0 1521881088 -0.2376922369 0.1255502701 0.0712985918 255 1305031110.6434180737 0.1223407835 0.0869593608 0.1265112162 0.0151229557 0.1567920000 550586242 0 1522515968 -0.2466195375 0.1247050017 0.0718017593 256 1305031110.6796059608 0.1288236678 0.0871228933 0.1288236678 0.0151228470 0.1578590000 550588040 0 1523023872 -0.2542613149 0.1318001002 0.0684350207 257 1305031110.7114119530 0.1278520674 0.0872813725 0.1288236678 0.0150959116 0.1580330000 550611310 0 1523531776 -0.2595424950 0.1301842779 0.0715983361 258 1305031110.7432489395 0.1272693425 0.0874363647 0.1288236678 0.0150823465 0.1332260000 550655060 0 1524166656 -0.2647740245 0.1294737160 0.0723436326 259 1305031110.7791929245 0.1299373209 0.0876004610 0.1299373209 0.0150548113 0.1774620000 550656890 0 1524674560 -0.2673908174 0.1314096749 0.0718753263 260 1305031110.8113861084 0.1301773787 0.0877642184 0.1301773787 0.0150276127 0.1564960000 550658656 0 1525309440 -0.2700560987 0.1319669187 0.0716397390 261 1305031110.8432180882 0.1291648149 0.0879228414 0.1301773787 0.0150062736 0.1559090000 550660422 0 1525817344 -0.2735063136 0.1319030374 0.0727199242 262 1305031110.8793129921 0.1294441968 0.0880813198 0.1301773787 0.0149795401 0.1881150000 550662252 0 1526325248 -0.2715888023 0.1316575706 0.0732690468 263 1305031110.9113330841 0.1294299066 0.0882385388 0.1301773787 0.0149564410 0.1659080000 550664018 0 1526833152 -0.2710407078 0.1326776296 0.0730592906 264 1305031110.9438619614 0.1300380528 0.0883968703 0.1301773787 0.0149459399 0.1767190000 550665816 0 1527341056 -0.2666997313 0.1332489699 0.0744411275 265 1305031110.9793450832 0.1332747340 0.0885662207 0.1332747340 0.0149460093 0.1736550000 550667582 0 1527975936 -0.2580058277 0.1366275698 0.0759413913 266 1305031111.0114309788 0.1323943287 0.0887309880 0.1332747340 0.0149294942 0.1651870000 550669380 0 1528483840 -0.2481633574 0.1339441985 0.0785060823 267 1305031111.0433270931 0.1307543963 0.0888883791 0.1332747340 0.0149097669 0.1513950000 550671146 0 1528991744 -0.2429980785 0.1338889897 0.0770127252 268 1305031111.0792829990 0.1289100945 0.0890377138 0.1332747340 0.0148872919 0.1525360000 550672944 0 1529499648 -0.2392403036 0.1363543123 0.0756686777 269 1305031111.1115078926 0.1258220226 0.0891744585 0.1332747340 0.0148786678 0.1451240000 550674742 0 1530134528 -0.2269630432 0.1306739748 0.0786604807 270 1305031111.1432569027 0.1236988828 0.0893023267 0.1332747340 0.0148525611 0.1488720000 550676508 0 1530642432 -0.2182191014 0.1282232851 0.0795297995 271 1305031111.1793260574 0.1257550418 0.0894368386 0.1332747340 0.0148916229 0.1569960000 550678338 0 1531150336 -0.2041439414 0.1296291947 0.0818452239 272 1305031111.2114329338 0.1263206601 0.0895724409 0.1332747340 0.0148849913 0.1633850000 550680072 0 1531650048 -0.1924830973 0.1292405427 0.0797758251 273 1305031111.2432360649 0.1183469519 0.0896778420 0.1332747340 0.0148877618 0.1506010000 550681838 0 1532284928 -0.1902163327 0.1245444268 0.0777743831 274 1305031111.2793080807 0.1176728457 0.0897800136 0.1332747340 0.0149547808 0.2091270000 550683668 0 1532792832 -0.1711726338 0.1201243922 0.0807848647 275 1305031111.3115470409 0.1190827861 0.0898865691 0.1332747340 0.0150256352 0.1452720000 550685434 0 1533300736 -0.1692405194 0.1274046898 0.0746964142 276 1305031111.3433969021 0.1169836074 0.0899847468 0.1332747340 0.0150101496 0.1439220000 550687200 0 1533808640 -0.1639374793 0.1282763779 0.0749376640 277 1305031111.3791339397 0.1099710092 0.0900568993 0.1332747340 0.0150886990 0.1224970000 550689030 0 1534443520 -0.1451054811 0.1179565340 0.0808688477 278 1305031111.4112958908 0.1094566882 0.0901266827 0.1332747340 0.0151123216 0.1610910000 550690764 0 1534951424 -0.1398073435 0.1207384244 0.0747897029 279 1305031111.4433860779 0.1146317422 0.0902145145 0.1332747340 0.0151062669 0.1430020000 550692562 0 1535459328 -0.1226449385 0.1235767826 0.0842184424 280 1305031111.4792590141 0.1141654328 0.0903000535 0.1332747340 0.0152507524 0.1598770000 550694392 0 1535967232 -0.0982405916 0.1174875796 0.0925216079 281 1305031111.5112640858 0.1107372418 0.0903727837 0.1332747340 0.0153094148 0.1749110000 550696126 0 1536475136 -0.0898414329 0.1165383533 0.0864482000 282 1305031111.5432500839 0.1072776169 0.0904327299 0.1332747340 0.0152864251 0.1718220000 550697924 0 1536991232 -0.0750104710 0.1110273451 0.0889648050 283 1305031111.5792369843 0.1080818176 0.0904950942 0.1332747340 0.0153357671 0.1724280000 550699754 0 1537626112 -0.0619715378 0.1149460077 0.0840128586 284 1305031111.6112709045 0.1034310609 0.0905406434 0.1332747340 0.0153412201 0.1793820000 550701456 0 1538134016 -0.0590047278 0.1145320311 0.0810843855 285 1305031111.6433949471 0.0993622094 0.0905715962 0.1332747340 0.0154028319 0.1867880000 550703254 0 1538641920 -0.0382177532 0.1059244275 0.0886014104 286 1305031111.6793200970 0.1059007347 0.0906251946 0.1332747340 0.0154984371 0.1910710000 550705052 0 1539149824 -0.0230078250 0.1146370322 0.0874006227 287 1305031111.7117600441 0.1043477431 0.0906730084 0.1332747340 0.0154772287 0.6931650000 563017458 0 1552101376 -0.0099678161 0.1132305339 0.0887635276 288 1305031111.7433860302 0.1025651097 0.0907143004 0.1332747340 0.0154772384 0.1916790000 566677072 0 1556291584 0.0086738281 0.1091892198 0.0893107131 289 1305031111.7794229984 0.1030788422 0.0907570843 0.1332747340 0.0155345762 0.1741660000 569870998 0 1559973888 0.0228972919 0.1121106222 0.0864311904 290 1305031111.8114058971 0.0985035375 0.0907837962 0.1332747340 0.0155406380 0.1477390000 569872732 0 1560608768 0.0299191885 0.1100511402 0.0889687687 291 1305031111.8432989120 0.0979537889 0.0908084353 0.1332747340 0.0155439521 0.1534180000 569874498 0 1561243648 0.0419727340 0.1107076034 0.0864998400 292 1305031111.8794419765 0.0949090272 0.0908224785 0.1332747340 0.0155283446 0.1583590000 569876296 0 1561751552 0.0473524183 0.1119185984 0.0860199109 293 1305031111.9113540649 0.0886239111 0.0908149748 0.1332747340 0.0155120977 0.1432280000 569878094 0 1562259456 0.0514601059 0.1078907251 0.0897021070 294 1305031111.9433000088 0.0895671397 0.0908107305 0.1332747340 0.0155024570 1.4050810000 582190280 0 1575084032 0.0658893809 0.1087131351 0.0882392675 295 1305031111.9794490337 0.0928604603 0.0908176787 0.1332747340 0.0156999536 0.2237810000 585849926 0 1579274240 0.0961932987 0.1085168347 0.0895261914 296 1305031112.0114328861 0.0929240286 0.0908247948 0.1332747340 0.0156788500 0.1653970000 589043820 0 1582956544 0.1113394275 0.1074630842 0.0932887271 297 1305031112.0432701111 0.0938957408 0.0908351346 0.1332747340 0.0156565294 0.1571620000 589045586 0 1583591424 0.1275615841 0.1067658067 0.0905561969 298 1305031112.0793390274 0.0929449946 0.0908422147 0.1332747340 0.0156906725 0.1796460000 589047416 0 1584099328 0.1440393627 0.1056449264 0.0916337594 299 1305031112.1114230156 0.0913351998 0.0908438635 0.1332747340 0.0157492798 0.1650040000 589049150 0 1584607232 0.1464677453 0.1074018106 0.0874599367 300 1305031112.1443419456 0.0942444205 0.0908551987 0.1332747340 0.0157322605 0.1626080000 589050916 0 1585242112 0.1669585407 0.1071283445 0.0848314092 301 1305031112.1793899536 0.0925691053 0.0908608927 0.1332747340 0.0157408691 5.8662070000 601366142 0 1598066688 0.1819357574 0.1062885374 0.0869093686 302 1305031112.2112538815 0.1047847793 0.0909069983 0.1332747340 0.0158469734 0.1954340000 605025756 0 1602129920 0.1893544346 0.1208001301 0.0897371396 303 1305031112.2433691025 0.1012277007 0.0909410600 0.1332747340 0.0158365125 0.1733390000 608219650 0 1605939200 0.1995579451 0.1168104485 0.0921041146 304 1305031112.2793529034 0.1030771732 0.0909809815 0.1332747340 0.0158422507 0.1433300000 608221448 0 1606447104 0.2046791911 0.1194656491 0.0949528292 305 1305031112.3113119602 0.1059669033 0.0910301156 0.1332747340 0.0158166157 0.1462310000 608223246 0 1607081984 0.2185373753 0.1208221912 0.0939863771 306 1305031112.3433229923 0.1058038324 0.0910783957 0.1332747340 0.0157938875 0.1302360000 608225012 0 1607589888 0.2240310460 0.1200736016 0.0936046317 307 1305031112.3793599606 0.1065094098 0.0911286596 0.1332747340 0.0157696904 0.1397890000 608226874 0 1608097792 0.2347304672 0.1200965717 0.0919955149 308 1305031112.4114420414 0.1070333421 0.0911802982 0.1332747340 0.0157546985 1.6493870000 620533236 0 1621049344 0.2450531572 0.1205101535 0.0911467820 309 1305031112.4433910847 0.1055533215 0.0912268129 0.1332747340 0.0157466025 0.1919240000 624192882 0 1625239552 0.2589782476 0.1184298620 0.0919353813 310 1305031112.4794180393 0.1070579812 0.0912778811 0.1332747340 0.0157269484 0.1601850000 627386808 0 1628921856 0.2650542259 0.1201125607 0.0914596990 311 1305031112.5115039349 0.1064149365 0.0913265533 0.1332747340 0.0157156132 0.1728290000 627388542 0 1629556736 0.2743725479 0.1195647642 0.0900579691 312 1305031112.5432119370 0.1058475897 0.0913730951 0.1332747340 0.0157059974 0.1662400000 627390308 0 1630191616 0.2849713564 0.1190105528 0.0892250836 313 1305031112.5792520046 0.1057402715 0.0914189966 0.1332747340 0.0156891784 0.1702890000 627392106 0 1630699520 0.2928845882 0.1195019186 0.0885650069 314 1305031112.6112608910 0.1083529815 0.0914729265 0.1332747340 0.0157482235 0.1641850000 627393872 0 1631199232 0.3100616634 0.1225322708 0.0856526792 315 1305031112.6432459354 0.1079255193 0.0915251570 0.1332747340 0.0157510337 0.1579280000 627395670 0 1631707136 0.3202153742 0.1230789497 0.0858877599 316 1305031112.6799519062 0.1050217375 0.0915678677 0.1332747340 0.0157390096 0.1623340000 627397500 0 1632215040 0.3224200904 0.1220488697 0.0865338519 317 1305031112.7112510204 0.1046827286 0.0916092395 0.1332747340 0.0157273309 0.1600600000 627399234 0 1632849920 0.3241728842 0.1235778406 0.0862461627 318 1305031112.7432448864 0.1093758419 0.0916651093 0.1332747340 0.0157074954 0.1721670000 627401032 0 1633357824 0.3263774812 0.1299420595 0.0839617923 319 1305031112.7793099880 0.1032910794 0.0917015544 0.1332747340 0.0156928075 0.1716190000 627402862 0 1633865728 0.3253005147 0.1271525323 0.0886546895 320 1305031112.8113100529 0.0983213782 0.0917222413 0.1332747340 0.0157019747 0.1696940000 627404596 0 1634373632 0.3150370121 0.1239144057 0.0909955502 321 1305031112.8432860374 0.1014449373 0.0917525301 0.1332747340 0.0156789822 0.1612310000 627406362 0 1634881536 0.3123060763 0.1284786314 0.0902484730 322 1305031112.8794209957 0.0993466079 0.0917761142 0.1332747340 0.0156848672 0.1728610000 627408192 0 1635516416 0.3104393482 0.1283345073 0.0928482935 323 1305031112.9114110470 0.0976231024 0.0917942163 0.1332747340 0.0156652935 0.1687870000 627409990 0 1636032512 0.3023751080 0.1270612329 0.0939917117 324 1305031112.9433209896 0.0972296968 0.0918109925 0.1332747340 0.0156428372 0.1687610000 627411756 0 1636540416 0.2961319089 0.1271006465 0.0955598727 325 1305031112.9792780876 0.0979380086 0.0918298448 0.1332747340 0.0156778234 0.1563860000 627413586 0 1637175296 0.2919316590 0.1276059896 0.0953939185 326 1305031113.0113530159 0.1017773598 0.0918603587 0.1332747340 0.0156565370 0.1645780000 627415320 0 1637683200 0.2882253528 0.1304681748 0.0922848433 327 1305031113.0432310104 0.1029735729 0.0918943440 0.1332747340 0.0156336962 0.1566350000 627417118 0 1638191104 0.2809469998 0.1307081878 0.0917555168 328 1305031113.0792510509 0.0988051370 0.0919154135 0.1332747340 0.0156463997 0.1366660000 627418948 0 1638699008 0.2693389356 0.1243768260 0.0939229131 329 1305031113.1113159657 0.1039728671 0.0919520623 0.1332747340 0.0156315948 0.1463880000 627420682 0 1639206912 0.2587832808 0.1274302453 0.0889073685 330 1305031113.1433060169 0.1121266410 0.0920131974 0.1332747340 0.0156129358 0.1901580000 627422480 0 1639841792 0.2513863146 0.1340848655 0.0879131779 331 1305031113.1793429852 0.1066400856 0.0920573874 0.1332747340 0.0156361320 0.1767140000 627424310 0 1640349696 0.2361754775 0.1259717345 0.0882843658 332 1305031113.2112588882 0.1073049158 0.0921033137 0.1332747340 0.0156145761 0.1452380000 627426044 0 1640857600 0.2214437723 0.1246849969 0.0854133219 333 1305031113.2432270050 0.1137388349 0.0921682852 0.1332747340 0.0155943106 1.8665050000 639738266 0 1653682176 0.2107712179 0.1284831762 0.0785081089 334 1305031113.2793118954 0.1143570468 0.0922347187 0.1332747340 0.0156457169 0.1962050000 643397912 0 1657872384 0.1830409616 0.1263597161 0.0777416453 335 1305031113.3114519119 0.1110669002 0.0922909341 0.1332747340 0.0156414670 0.1611380000 646591774 0 1661681664 0.1649676561 0.1206415519 0.0807403624 336 1305031113.3432519436 0.1205787957 0.0923751242 0.1332747340 0.0156320168 0.1438710000 646593540 0 1662189568 0.1511133313 0.1274252981 0.0724041313 337 1305031113.3793120384 0.1244073883 0.0924701754 0.1332747340 0.0156330933 0.1478930000 646595338 0 1662951424 0.1360359937 0.1291353852 0.0724275261 338 1305031113.4116249084 0.1200873032 0.0925518829 0.1332747340 0.0156206870 0.1310370000 646597136 0 1663459328 0.1216953173 0.1230706647 0.0788860172 339 1305031113.4432659149 0.1250839978 0.0926478478 0.1332747340 0.0155995752 0.1382850000 646598902 0 1663967232 0.1082933322 0.1253259480 0.0737515166 340 1305031113.4793109894 0.1300628632 0.0927578920 0.1332747340 0.0156091156 0.1250660000 646600700 0 1664602112 0.0926279649 0.1276460141 0.0725803524 341 1305031113.5115230083 0.1281550676 0.0928616960 0.1332747340 0.0155949102 1.9076540000 658909766 0 1677426688 0.0777811483 0.1239738986 0.0731953755 342 1305031113.5432419777 0.1271621436 0.0929619897 0.1332747340 0.0156108186 0.2090540000 662569380 0 1681489920 0.0679210275 0.1205750257 0.0711644441 343 1305031113.5793011189 0.1331907958 0.0930792749 0.1332747340 0.0155948704 0.1775180000 665763274 0 1685299200 0.0574818775 0.1234472618 0.0693284422 344 1305031113.6112680435 0.1343752295 0.0931993213 0.1343752295 0.0155760378 0.1615460000 665765072 0 1685807104 0.0462073907 0.1234994382 0.0692027062 345 1305031113.6432220936 0.1349294633 0.0933202782 0.1349294633 0.0155546028 0.1666330000 665766838 0 1686441984 0.0344935656 0.1235388294 0.0692552626 346 1305031113.6792879105 0.1358226091 0.0934431173 0.1358226091 0.0155381412 0.2038960000 665768700 0 1686949888 0.0220255852 0.1228428409 0.0710384175 347 1305031113.7119309902 0.1355261505 0.0935643941 0.1358226091 0.0155227620 0.1880060000 665770434 0 1687584768 0.0118123647 0.1218546256 0.0725484714 348 1305031113.7435901165 0.1374435574 0.0936904836 0.1374435574 0.0155012353 0.2049560000 665772232 0 1688092672 0.0006389013 0.1229535043 0.0719473436 349 1305031113.7793200016 0.1369481683 0.0938144311 0.1374435574 0.0154879423 0.1670360000 665774030 0 1688600576 -0.0121376514 0.1210533530 0.0729953870 350 1305031113.8112370968 0.1381649077 0.0939411468 0.1381649077 0.0154663164 0.1714850000 665775764 0 1689108480 -0.0228568073 0.1220537573 0.0717025995 351 1305031113.8432950974 0.1403927207 0.0940734874 0.1403927207 0.0154494127 0.1771770000 665777562 0 1689616384 -0.0345642157 0.1241631582 0.0722962245 352 1305031113.8792810440 0.1369653195 0.0941953392 0.1403927207 0.0154608539 0.1739250000 665779392 0 1690251264 -0.0494986363 0.1203787699 0.0778340399 353 1305031113.9112899303 0.1392707229 0.0943230315 0.1403927207 0.0154449670 0.1789670000 665781158 0 1690759168 -0.0587572120 0.1218071878 0.0741425008 354 1305031113.9432909489 0.1411858350 0.0944554123 0.1411858350 0.0154258662 2.4327360000 678098852 0 1703575552 -0.0680310205 0.1228253841 0.0763073340 355 1305031113.9792931080 0.1377609670 0.0945773998 0.1411858350 0.0154148564 0.2022970000 681758530 0 1707765760 -0.0822899491 0.1180743128 0.0777600259 356 1305031114.0112569332 0.1391442716 0.0947025877 0.1411858350 0.0154050120 0.1746000000 684952392 0 1711583232 -0.0967612788 0.1203757972 0.0776030794 357 1305031114.0433011055 0.1381290257 0.0948242304 0.1411858350 0.0153906314 0.1566530000 684954158 0 1712218112 -0.1142644510 0.1213663444 0.0781798586 358 1305031114.0792849064 0.1402494907 0.0949511166 0.1411858350 0.0153791113 0.1633960000 684955988 0 1712852992 -0.1261235178 0.1212289631 0.0792161301 359 1305031114.1112630367 0.1434292346 0.0950861531 0.1434292346 0.0153579517 0.1716320000 684957754 0 1713360896 -0.1376311034 0.1241676211 0.0781330839 360 1305031114.1432840824 0.1443913281 0.0952231119 0.1443913281 0.0153497376 0.1707150000 684959552 0 1713868800 -0.1481836438 0.1246461347 0.0791833177 361 1305031114.1793370247 0.1446381360 0.0953599956 0.1446381360 0.0153503733 0.1746990000 684961382 0 1714376704 -0.1551378220 0.1205337346 0.0801635534 362 1305031114.2113029957 0.1508520842 0.0955132887 0.1508520842 0.0153457344 0.1904630000 684963116 0 1714884608 -0.1677663475 0.1283724904 0.0770959631 363 1305031114.2433369160 0.1478997022 0.0956576039 0.1508520842 0.0153333376 0.1676260000 684964882 0 1715519488 -0.1824338138 0.1277531981 0.0804024190 364 1305031114.2793900967 0.1476912051 0.0958005533 0.1508520842 0.0153561295 0.1832710000 684966712 0 1716027392 -0.1959712952 0.1268745810 0.0784840509 365 1305031114.3114290237 0.1491735876 0.0959467808 0.1508520842 0.0153368889 1.9275780000 697282002 0 1728851968 -0.2056039274 0.1282476038 0.0788613409 366 1305031114.3433310986 0.1474875659 0.0960876026 0.1508520842 0.0153164036 0.2068870000 700941648 0 1732915200 -0.2159934044 0.1267869323 0.0824063569 367 1305031114.3793199062 0.1498291194 0.0962340373 0.1508520842 0.0153006521 0.1570920000 704135574 0 1736724480 -0.2227340639 0.1254854500 0.0842944831 368 1305031114.4113969803 0.1496676654 0.0963792374 0.1508520842 0.0152886321 0.1710010000 704137340 0 1737359360 -0.2348310798 0.1261690110 0.0838937685 369 1305031114.4433450699 0.1503820419 0.0965255864 0.1508520842 0.0152699443 0.1546790000 704139106 0 1737867264 -0.2464620620 0.1278193891 0.0838112235 370 1305031114.4793319702 0.1509844810 0.0966727726 0.1509844810 0.0152692939 0.1559320000 704140936 0 1738375168 -0.2566632330 0.1263972670 0.0847537518 371 1305031114.5112659931 0.1551590264 0.0968304175 0.1551590264 0.0152516753 0.1502010000 704142670 0 1739010048 -0.2614354491 0.1281640828 0.0844270140 372 1305031114.5432360172 0.1570564657 0.0969923155 0.1570564657 0.0152386751 0.1551310000 704144468 0 1739517952 -0.2629683912 0.1262901872 0.0880124792 373 1305031114.5792369843 0.1583342254 0.0971567710 0.1583342254 0.0152225661 0.1448460000 704146298 0 1740025856 -0.2673441470 0.1246704236 0.0886283293 374 1305031114.6113910675 0.1604751796 0.0973260716 0.1604751796 0.0152034454 0.1542500000 704148032 0 1740533760 -0.2726872265 0.1266022176 0.0873107240 375 1305031114.6441359520 0.1584620178 0.0974891008 0.1604751796 0.0151856895 0.1694190000 704149798 0 1741168640 -0.2800712883 0.1256749034 0.0885139033 376 1305031114.6792509556 0.1572620571 0.0976480714 0.1604751796 0.0151719130 0.1768690000 704151596 0 1741676544 -0.2835492790 0.1226296499 0.0900874287 377 1305031114.7113060951 0.1575967222 0.0978070864 0.1604751796 0.0151614489 0.1642130000 704153330 0 1742184448 -0.2833625376 0.1205671206 0.0922553763 378 1305031114.7432000637 0.1576894820 0.0979655054 0.1604751796 0.0151420078 0.1895350000 704155096 0 1742692352 -0.2836416662 0.1193636507 0.0933620706 379 1305031114.7792890072 0.1593056172 0.0981273527 0.1604751796 0.0151242982 0.1892470000 704156958 0 1743327232 -0.2825405896 0.1201473027 0.0920474604 380 1305031114.8113029003 0.1610331982 0.0982928944 0.1610331982 0.0151090303 0.1819900000 704158692 0 1743835136 -0.2819538713 0.1230204627 0.0907121897 381 1305031114.8432080746 0.1595212221 0.0984535987 0.1610331982 0.0150901061 0.1934150000 704160490 0 1744343040 -0.2806114554 0.1223595962 0.0909034163 382 1305031114.8792810440 0.1599475741 0.0986145777 0.1610331982 0.0150704365 0.1930360000 704162288 0 1744850944 -0.2770673037 0.1251087338 0.0902228057 383 1305031114.9128789902 0.1590870023 0.0987724691 0.1610331982 0.0150530795 0.1871940000 704164118 0 1745485824 -0.2742841542 0.1268111765 0.0899168178 384 1305031114.9432339668 0.1611612737 0.0989349400 0.1611612737 0.0150339613 0.1893060000 704165788 0 1745993728 -0.2655161321 0.1296065897 0.0926319063 385 1305031114.9792799950 0.1578533053 0.0990879747 0.1611612737 0.0150200925 0.1765230000 704167650 0 1746501632 -0.2608250082 0.1316620559 0.0930470377 386 1305031115.0113000870 0.1586829722 0.0992423659 0.1611612737 0.0150038079 0.1583500000 704169416 0 1747009536 -0.2539241910 0.1359655410 0.0947379768 387 1305031115.0435080528 0.1556053162 0.0993880065 0.1611612737 0.0149944737 0.1697200000 704171182 0 1747517440 -0.2414084077 0.1320462525 0.0998966619 388 1305031115.0792379379 0.1540735662 0.0995289487 0.1611612737 0.0149868494 0.1774320000 704173044 0 1748152320 -0.2334142327 0.1360713840 0.1007384136 389 1305031115.1112298965 0.1559222192 0.0996739186 0.1611612737 0.0149814605 0.1706280000 704174778 0 1748660224 -0.2173198760 0.1368734390 0.1087435856 390 1305031115.1432750225 0.1502036899 0.0998034821 0.1611612737 0.0149634478 0.1631390000 704176544 0 1749168128 -0.2094428092 0.1334380507 0.1092355326 391 1305031115.1794400215 0.1437527239 0.0999158842 0.1611612737 0.0149595004 0.1605820000 704178406 0 1749803008 -0.2059692740 0.1352473795 0.1093185768 392 1305031115.2113740444 0.1398476958 0.1000177511 0.1611612737 0.0149721080 0.1386410000 704180140 0 1750310912 -0.1880612373 0.1280582249 0.1167845577 393 1305031115.2432971001 0.1349449605 0.1001066244 0.1611612737 0.0149545121 0.1563580000 704181938 0 1750818816 -0.1759557575 0.1237068921 0.1189303845 394 1305031115.2799661160 0.1358562708 0.1001973595 0.1611612737 0.0149793158 0.1863190000 704183736 0 1751326720 -0.1643472910 0.1313662976 0.1226193011 395 1305031115.3117039204 0.1307321340 0.1002746628 0.1611612737 0.0149952970 0.1571580000 704185534 0 1751961600 -0.1450543404 0.1235601902 0.1324787736 396 1305031115.3432350159 0.1306096911 0.1003512664 0.1611612737 0.0149868210 0.1856700000 704187236 0 1752469504 -0.1326347888 0.1265538931 0.1306612641 397 1305031115.3791658878 0.1238750517 0.1004105202 0.1611612737 0.0150670779 0.1669360000 704189066 0 1752977408 -0.1339688003 0.1323788911 0.1246778741 398 1305031115.4112370014 0.1178833395 0.1004544218 0.1611612737 0.0150616572 0.1764240000 704190832 0 1753485312 -0.1212719604 0.1294403821 0.1323125511 399 1305031115.4431591034 0.1164272875 0.1004944540 0.1611612737 0.0150668715 0.1857980000 704192598 0 1753993216 -0.1007262543 0.1277276874 0.1396582574 400 1305031115.4792408943 0.1118532121 0.1005228509 0.1611612737 0.0150512001 0.1997910000 704194428 0 1754501120 -0.0860962048 0.1280380338 0.1398050785 401 1305031115.5112531185 0.1104277149 0.1005475514 0.1611612737 0.0151009573 0.2110170000 704196162 0 1755136000 -0.0639655367 0.1259029806 0.1527016312 402 1305031115.5436038971 0.1068997160 0.1005633528 0.1611612737 0.0150916120 1.3356610000 716520372 0 1767960576 -0.0431958325 0.1208028048 0.1522627026 403 1305031115.5793149471 0.1005710140 0.1005633718 0.1611612737 0.0150897982 0.2065510000 720180082 0 1772023808 -0.0387333333 0.1231576651 0.1491510570 404 1305031115.6114239693 0.0982189700 0.1005575688 0.1611612737 0.0150765198 0.1712720000 723373912 0 1775833088 -0.0257530920 0.1226723567 0.1504590511 405 1305031115.6432540417 0.0960014164 0.1005463190 0.1611612737 0.0150663640 0.1480920000 723375678 0 1776467968 -0.0105778957 0.1207149327 0.1510715932 406 1305031115.6792409420 0.0916352570 0.1005243706 0.1611612737 0.0150488874 0.1510950000 723377508 0 1776975872 -0.0019141260 0.1198433116 0.1472357661 407 1305031115.7113199234 0.0944004357 0.1005093241 0.1611612737 0.0150831384 0.1439150000 723379274 0 1777483776 0.0173884742 0.1224397495 0.1478365064 408 1305031115.7432498932 0.0937111974 0.1004926620 0.1611612737 0.0150858067 0.1443630000 723381072 0 1778118656 0.0365407318 0.1213365644 0.1521726251 409 1305031115.7794249058 0.0908994228 0.1004692067 0.1611612737 0.0150949570 0.1437920000 723382902 0 1778626560 0.0493909679 0.1209120527 0.1497509331 410 1305031115.8112769127 0.0922316015 0.1004491149 0.1611612737 0.0150963654 2.0890680000 735701484 0 1787908096 0.0649585500 0.1226884350 0.1476022452 411 1305031115.8432240486 0.0924415588 0.1004296318 0.1611612737 0.0151067674 0.1763240000 739364802 0 1786765312 0.0873942971 0.1224245876 0.1517115980 412 1305031115.8791980743 0.0851202011 0.1003924730 0.1611612737 0.0150930847 0.1284800000 742558664 0 1787133952 0.0951087996 0.1189781055 0.1519259512 413 1305031115.9111180305 0.0872689411 0.1003606969 0.1611612737 0.0150914838 0.1320630000 742560430 0 1786277888 0.1101092398 0.1223129332 0.1501260251 414 1305031115.9433109760 0.0876310617 0.1003299490 0.1611612737 0.0150834280 0.1449850000 742562164 0 1785991168 0.1228021234 0.1245644912 0.1497129798 415 1305031115.9807400703 0.0848409534 0.1002926261 0.1611612737 0.0150909518 0.1325990000 742563994 0 1786626048 0.1355331689 0.1253385097 0.1497296393 416 1305031116.0113790035 0.0841555521 0.1002538351 0.1611612737 0.0151135844 0.1392420000 742565728 0 1787133952 0.1515626013 0.1262620240 0.1506116539 417 1305031116.0431640148 0.0811080635 0.1002079220 0.1611612737 0.0150962231 2.0951060000 754881334 0 1786515456 0.1614605933 0.1259762943 0.1520531029 418 1305031116.0800299644 0.0797420815 0.1001589606 0.1611612737 0.0151064283 0.1745850000 758541012 0 1786634240 0.1729202271 0.1287257820 0.1512519121 419 1305031116.1112999916 0.0765971243 0.1001027271 0.1611612737 0.0150898755 0.1392340000 761734842 0 1786400768 0.1816902757 0.1283993274 0.1536335796 420 1305031116.1434409618 0.0730318725 0.1000382727 0.1611612737 0.0150981490 0.1475020000 761736576 0 1785880576 0.1818616092 0.1284621060 0.1567045450 421 1305031116.1795721054 0.0724466145 0.0999727343 0.1611612737 0.0150961435 0.1432040000 761738438 0 1785864192 0.1877816319 0.1300028563 0.1590290517 422 1305031116.2112989426 0.0730203688 0.0999088662 0.1611612737 0.0150900908 0.1107340000 761740172 0 1786372096 0.1918579489 0.1319985688 0.1619103402 423 1305031116.2433199883 0.0693428218 0.0998366060 0.1611612737 0.0150774464 0.1108810000 761741970 0 1786880000 0.1976756305 0.1291532815 0.1665972918 424 1305031116.2793850899 0.0698565841 0.0997658984 0.1611612737 0.0150702593 1.8122960000 774053496 0 1786253312 0.2053210139 0.1294335723 0.1674715132 425 1305031116.3113360405 0.0727373734 0.0997023019 0.1611612737 0.0150651636 0.1468440000 777713078 0 1786908672 0.2193184197 0.1339352280 0.1609383523 426 1305031116.3432919979 0.0742268041 0.0996425002 0.1611612737 0.0150720042 0.1383300000 780906940 0 1786781696 0.2190261483 0.1340284497 0.1650775373 427 1305031116.3793840408 0.0810900033 0.0995990518 0.1611612737 0.0150584439 0.1298230000 780908738 0 1786146816 0.2188220769 0.1373508722 0.1630396694 428 1305031116.4113330841 0.0869198218 0.0995694274 0.1611612737 0.0150422772 0.1180600000 780910536 0 1785892864 0.2202787548 0.1420414299 0.1570629478 429 1305031116.4433689117 0.0868548304 0.0995397896 0.1611612737 0.0150331184 0.1126730000 780912334 0 1785249792 0.2207684815 0.1408289224 0.1532233208 430 1305031116.4798500538 0.0853549764 0.0995068017 0.1611612737 0.0150195653 0.1143740000 780914164 0 1785880576 0.2193547934 0.1389312446 0.1542857885 431 1305031116.5112049580 0.0877327621 0.0994794837 0.1611612737 0.0150028060 0.1085020000 780915898 0 1786372096 0.2182419300 0.1412373036 0.1502488405 432 1305031116.5432620049 0.0885382965 0.0994541569 0.1611612737 0.0149856840 0.1145640000 780917664 0 1786880000 0.2148455381 0.1415552348 0.1478571892 433 1305031116.5793130398 0.0956414640 0.0994453516 0.1611612737 0.0149817685 0.1101930000 780919494 0 1787006976 0.2103531957 0.1496672183 0.1443347782 434 1305031116.6112608910 0.1028230861 0.0994531344 0.1611612737 0.0149848648 0.1435550000 780921228 0 1787387904 0.2041173875 0.1572836637 0.1460683495 435 1305031116.6433548927 0.1038473845 0.0994632361 0.1611612737 0.0149763016 0.1593780000 780922994 0 1788022784 0.1981993914 0.1585119665 0.1472940147 436 1305031116.6792809963 0.1020707637 0.0994692167 0.1611612737 0.0149666844 0.1520240000 780924888 0 1786626048 0.1939365566 0.1566503495 0.1484367400 437 1305031116.7116339207 0.1039640605 0.0994795024 0.1611612737 0.0149542770 0.1434870000 780926622 0 1787133952 0.1882655472 0.1573042125 0.1489339769 438 1305031116.7432909012 0.1069591492 0.0994965792 0.1611612737 0.0149387570 0.1537730000 780928388 0 1787768832 0.1812364012 0.1588885486 0.1494865119 439 1305031116.7792980671 0.1086131558 0.0995173459 0.1611612737 0.0149403506 0.1455870000 780930218 0 1785872384 0.1747505516 0.1571978778 0.1509333253 440 1305031116.8113179207 0.1148879677 0.0995522791 0.1611612737 0.0149359436 0.1516100000 780931952 0 1786380288 0.1650128514 0.1610984802 0.1561027765 441 1305031116.8460888863 0.1204609722 0.0995996911 0.1611612737 0.0149704524 0.1459300000 780933782 0 1787006976 0.1574877203 0.1618720591 0.1522795111 442 1305031116.8801651001 0.1222016066 0.0996508267 0.1611612737 0.0149781026 0.1397550000 780935580 0 1787514880 0.1504315436 0.1597109735 0.1522254199 443 1305031116.9120440483 0.1292891949 0.0997177305 0.1611612737 0.0149619653 0.1399880000 780937346 0 1787768832 0.1417245716 0.1634362936 0.1561826020 444 1305031116.9432959557 0.1327464730 0.0997921195 0.1611612737 0.0149781606 6.1857560000 793342592 0 1786253312 0.1331041604 0.1633728147 0.1529979110 445 1305031116.9793510437 0.1289265752 0.0998575902 0.1611612737 0.0150337741 0.1673120000 797002238 0 1786765312 0.1175442412 0.1560552418 0.1463395506 446 1305031117.0113821030 0.1352792531 0.0999370110 0.1611612737 0.0150341094 0.1460500000 800196132 0 1786634240 0.1111001223 0.1580854058 0.1445440352 447 1305031117.0432610512 0.1410148293 0.1000289077 0.1611612737 0.0150303812 0.1413090000 800197898 0 1785999360 0.1055360287 0.1592469960 0.1409446150 448 1305031117.0795199871 0.1497042924 0.1001397902 0.1611612737 0.0150525386 0.1323320000 800199728 0 1785389056 0.0991819277 0.1621420532 0.1474938244 449 1305031117.1112380028 0.1558643281 0.1002638983 0.1611612737 0.0150642543 0.1313730000 800201462 0 1786019840 0.0960650668 0.1637112647 0.1470296234 450 1305031117.1432180405 0.1622570008 0.1004016608 0.1622570008 0.0150813922 0.1298350000 800203260 0 1786527744 0.0948772356 0.1642524004 0.1441661119 451 1305031117.1792640686 0.1687648594 0.1005532421 0.1687648594 0.0150737307 0.6610780000 812504206 0 1786650624 0.0907196924 0.1663618684 0.1471068114 452 1305031117.2113609314 0.1702986956 0.1007075462 0.1702986956 0.0151025545 0.1963170000 816163820 0 1786654720 0.0889493152 0.1642211676 0.1432184726 453 1305031117.2432770729 0.1742768288 0.1008699508 0.1742768288 0.0150967980 0.2151610000 819357682 0 1786781696 0.0903109834 0.1628081948 0.1405360550 454 1305031117.2792990208 0.1754909009 0.1010343142 0.1754909009 0.0150811849 0.2082480000 819359512 0 1787387904 0.0875054821 0.1621648222 0.1438849270 455 1305031117.3111999035 0.1760662794 0.1011992196 0.1760662794 0.0150700453 0.1809460000 819361246 0 1787768832 0.0851268694 0.1619063467 0.1462751478 456 1305031117.3432428837 0.1767168492 0.1013648284 0.1767168492 0.0150547772 0.1757330000 819363044 0 1788022784 0.0831118673 0.1621058583 0.1490997225 457 1305031117.3794538975 0.1777056754 0.1015318762 0.1777056754 0.0150425582 0.1565670000 819364874 0 1786277888 0.0814160928 0.1610295177 0.1500841081 458 1305031117.4112210274 0.1791522950 0.1017013531 0.1791522950 0.0150290932 0.1556150000 819366640 0 1786912768 0.0797550157 0.1608329266 0.1530758142 459 1305031117.4432740211 0.1801162213 0.1018721916 0.1801162213 0.0150143946 0.1519820000 819368406 0 1787420672 0.0796042681 0.1586288959 0.1505629271 460 1305031117.4794030190 0.1814155281 0.1020451119 0.1814155281 0.0150055481 0.1509690000 819370236 0 1787895808 0.0777498633 0.1560078710 0.1521135569 461 1305031117.5113248825 0.1832656115 0.1022212952 0.1832656115 0.0149908804 0.1612730000 819372002 0 1788022784 0.0764501542 0.1540282369 0.1554189920 462 1305031117.5442850590 0.1853263378 0.1024011763 0.1853263378 0.0149787227 0.1618040000 819373736 0 1786515456 0.0753666162 0.1523054540 0.1551873684 463 1305031117.5791549683 0.1897207499 0.1025897714 0.1897207499 0.0149634761 0.1614810000 819375598 0 1787150336 0.0754047632 0.1506326199 0.1542427391 464 1305031117.6111590862 0.1913371086 0.1027810373 0.1913371086 0.0149482030 0.1772890000 819377332 0 1787658240 0.0740455464 0.1480011940 0.1550852507 465 1305031117.6432518959 0.1924209893 0.1029738113 0.1924209893 0.0149327620 0.1740260000 819379098 0 1788149760 0.0725071654 0.1447132081 0.1560447961 466 1305031117.6792619228 0.1962346286 0.1031739419 0.1962346286 0.0149188731 0.1776260000 819380960 0 1788149760 0.0712565109 0.1425520182 0.1571802646 467 1305031117.7111840248 0.1965882778 0.1033739726 0.1965882778 0.0149033280 0.1782280000 819382662 0 1786413056 0.0695695207 0.1380440742 0.1590744704 468 1305031117.7431840897 0.1979564577 0.1035760719 0.1979564577 0.0148881241 0.1865630000 819384460 0 1786413056 0.0676462650 0.1341835409 0.1608281285 469 1305031117.7794671059 0.2032068223 0.1037885042 0.2032068223 0.0148737992 0.1805550000 819386290 0 1786908672 0.0666227639 0.1318360865 0.1619279087 470 1305031117.8113200665 0.2039665729 0.1040016490 0.2039665729 0.0148618391 0.1822360000 819388056 0 1787416576 0.0646305010 0.1259571016 0.1640954167 471 1305031117.8432910442 0.2072452605 0.1042208499 0.2072452605 0.0148508302 0.1933950000 819389726 0 1787768832 0.0650104210 0.1213361621 0.1648709178 472 1305031117.8794510365 0.2136667967 0.1044527269 0.2136667967 0.0148364170 0.1799980000 819391556 0 1787895808 0.0639664456 0.1185321212 0.1663936675 473 1305031117.9114069939 0.2150345445 0.1046865151 0.2150345445 0.0148259051 0.1818540000 819393322 0 1786880000 0.0605684407 0.1138103828 0.1684085280 474 1305031117.9432530403 0.2198013961 0.1049293735 0.2198013961 0.0148139215 0.1757160000 819395056 0 1787387904 0.0596621335 0.1112804860 0.1702430844 475 1305031117.9792280197 0.2254793495 0.1051831629 0.2254793495 0.0148113381 0.1674560000 819396886 0 1788022784 0.0561608449 0.1086316928 0.1726604998 476 1305031118.0112280846 0.2263367474 0.1054376872 0.2263367474 0.0147986975 0.1764290000 819398652 0 1785864192 0.0536176302 0.1024166122 0.1752717048 477 1305031118.0435209274 0.2303790003 0.1056996187 0.2303790003 0.0147857359 0.1788250000 819400418 0 1786499072 0.0521483496 0.0986338481 0.1768002510 478 1305031118.0793340206 0.2369632423 0.1059742288 0.2369632423 0.0147714694 0.1794880000 819402248 0 1787006976 0.0510367081 0.0948655158 0.1784994751 479 1305031118.1112170219 0.2396653295 0.1062533334 0.2396653295 0.0147577259 1.1456540000 831712178 0 1787039744 0.0500201583 0.0894434527 0.1798927486 480 1305031118.1432559490 0.2400435209 0.1065320630 0.2400435209 0.0147549258 0.2400070000 835371824 0 1786396672 0.0477410704 0.0826840550 0.1838552505 481 1305031118.1793229580 0.2447257340 0.1068193679 0.2447257340 0.0147398086 0.1810530000 838565750 0 1786507264 0.0448578522 0.0778881237 0.1863279790 482 1305031118.2112019062 0.2477433830 0.1071117414 0.2477433830 0.0147282282 0.1715560000 838567484 0 1785880576 0.0403857119 0.0745822117 0.1879319549 483 1305031118.2431728840 0.2521028817 0.1074119301 0.2521028817 0.0147212180 0.1505480000 838569250 0 1786384384 0.0389421508 0.0711562559 0.1879723668 484 1305031118.2791941166 0.2572160959 0.1077214428 0.2572160959 0.0147169287 0.1673240000 838571080 0 1787019264 0.0372693948 0.0663585663 0.1898914576 485 1305031118.3112990856 0.2620368004 0.1080396188 0.2620368004 0.0147044445 0.1479660000 838572846 0 1787273216 0.0359299555 0.0636951849 0.1891757697 486 1305031118.3433239460 0.2668479085 0.1083663848 0.2668479085 0.0146971907 0.9409540000 850880412 0 1787031552 0.0368494317 0.0611903854 0.1898407042 487 1305031118.3792080879 0.2704017162 0.1086991062 0.2704017162 0.0146847278 0.2129420000 854540090 0 1786880000 0.0336615853 0.0584609658 0.1921169758 488 1305031118.4112958908 0.2740644217 0.1090379696 0.2740644217 0.0146724874 0.1688820000 857733952 0 1786253312 0.0332749598 0.0579057969 0.1927251816 489 1305031118.4456920624 0.2758165598 0.1093790301 0.2758165598 0.0146597919 0.1630490000 857735718 0 1785221120 0.0337407030 0.0565341115 0.1935527176 490 1305031118.4792850018 0.2762497663 0.1097195826 0.2762497663 0.0146454813 0.1512710000 857737516 0 1785982976 0.0328271016 0.0549920760 0.1939735562 491 1305031118.5112550259 0.2781721056 0.1100626631 0.2781721056 0.0146352315 0.1576600000 857739282 0 1786490880 0.0350782797 0.0560477860 0.1939151883 492 1305031118.5444140434 0.2780419886 0.1104040845 0.2781721056 0.0146215112 0.1414590000 857741048 0 1786998784 0.0357247144 0.0576788709 0.1941686869 493 1305031118.5792849064 0.2741477787 0.1107362218 0.2781721056 0.0146072063 0.1436540000 857742910 0 1787252736 0.0369204991 0.0574931055 0.1941771656 494 1305031118.6161420345 0.2702426016 0.1110591092 0.2781721056 0.0145953204 0.1556500000 857744740 0 1787514880 0.0388156697 0.0594904758 0.1946711987 495 1305031118.6453249454 0.2702914178 0.1113807907 0.2781721056 0.0145811235 0.1595510000 857746442 0 1788149760 0.0402165987 0.0635600612 0.1948180795 496 1305031118.6792950630 0.2633030713 0.1116870856 0.2781721056 0.0145684779 0.2167080000 857748304 0 1786138624 0.0405996516 0.0656153634 0.1951917410 497 1305031118.7114210129 0.2564394772 0.1119783379 0.2781721056 0.0145648898 0.1475430000 857750038 0 1786638336 0.0396360978 0.0663395971 0.1946106106 498 1305031118.7467699051 0.2509353161 0.1122573680 0.2781721056 0.0145508140 0.1578800000 857751836 0 1787273216 0.0404605716 0.0717901587 0.1941750199 499 1305031118.7792770863 0.2498179227 0.1125330404 0.2781721056 0.0145453791 0.1919590000 857753666 0 1787781120 0.0453468449 0.0784853175 0.1936936826 500 1305031118.8112208843 0.2395366132 0.1127870476 0.2781721056 0.0145725333 0.1619990000 857755400 0 1787908096 0.0459890366 0.0768935978 0.1925615966 501 1305031118.8467528820 0.2324717790 0.1130259392 0.2781721056 0.0145751717 0.1467360000 857757198 0 1786626048 0.0501844659 0.0802748576 0.1897320896 502 1305031118.8792080879 0.2326886207 0.1132643111 0.2781721056 0.0145827871 0.1478200000 857759028 0 1787133952 0.0543996617 0.0892962441 0.1864181757 503 1305031118.9111769199 0.2254643738 0.1134873729 0.2781721056 0.0145985672 0.1563910000 857760762 0 1787641856 0.0549964830 0.0915020406 0.1852335781 504 1305031118.9469740391 0.2191535830 0.1136970281 0.2781721056 0.0145922519 0.1547470000 857762560 0 1788149760 0.0572821721 0.0969828069 0.1828121096 505 1305031118.9793739319 0.2171691209 0.1139019233 0.2781721056 0.0145815873 0.1564490000 857764358 0 1788149760 0.0587584898 0.1039661393 0.1806411296 506 1305031119.0113630295 0.2132622749 0.1140982876 0.2781721056 0.0145752351 0.1830760000 857766124 0 1786785792 0.0598671436 0.1087477803 0.1789276153 507 1305031119.0471720695 0.2064409852 0.1142804231 0.2781721056 0.0145637577 0.1767370000 857767922 0 1786118144 0.0605313145 0.1126848012 0.1770820022 508 1305031119.0792229176 0.2033081055 0.1144556745 0.2781721056 0.0145510430 0.1910480000 857769688 0 1786753024 0.0609977543 0.1174478084 0.1748027653 509 1305031119.1113278866 0.2011914253 0.1146260787 0.2781721056 0.0145452456 0.1893040000 857771486 0 1787260928 0.0623435006 0.1221212596 0.1724515706 510 1305031119.1476159096 0.1985500008 0.1147906354 0.2781721056 0.0145322232 0.1799140000 857773284 0 1787768832 0.0637783706 0.1278766394 0.1694085151 511 1305031119.1792259216 0.1958567500 0.1149492775 0.2781721056 0.0145375084 0.1856260000 857775050 0 1787895808 0.0646658242 0.1309281737 0.1679738015 512 1305031119.2113640308 0.1962042302 0.1151079786 0.2781721056 0.0145307445 0.1807620000 857776848 0 1786626048 0.0678661913 0.1360090524 0.1648027152 513 1305031119.2473990917 0.1937852055 0.1152613455 0.2781721056 0.0145181998 0.1827740000 857821654 0 1787260928 0.0686871335 0.1409575492 0.1627846062 514 1305031119.2792119980 0.1934386194 0.1154134414 0.2781721056 0.0145064764 0.1882860000 857907388 0 1788022784 0.0710159689 0.1451421380 0.1612332761 515 1305031119.3112120628 0.1919763386 0.1155621072 0.2781721056 0.0144940210 0.1825000000 857909186 0 1786269696 0.0718628019 0.1492474973 0.1590706110 516 1305031119.3477408886 0.1889484823 0.1157043288 0.2781721056 0.0144802528 0.1909200000 857910984 0 1786777600 0.0722373948 0.1529601067 0.1571978331 517 1305031119.3792390823 0.1897660494 0.1158475817 0.2781721056 0.0144699761 0.1922710000 857912782 0 1787260928 0.0747180358 0.1576960981 0.1550091207 518 1305031119.4114840031 0.1898200065 0.1159903856 0.2781721056 0.0144631049 0.9052680000 870221972 0 1786150912 0.0768335238 0.1618570685 0.1537052840 519 1305031119.4477059841 0.1884046793 0.1161299122 0.2781721056 0.0144520375 0.2196640000 873881682 0 1786511360 0.0795394406 0.1639497280 0.1521412730 520 1305031119.4792668819 0.1882826239 0.1162686674 0.2781721056 0.0144440675 0.1744720000 877075512 0 1786142720 0.0805045441 0.1687060148 0.1500044763 521 1305031119.5112400055 0.1878855973 0.1164061279 0.2781721056 0.0144313177 0.1659750000 877077246 0 1785745408 0.0808752701 0.1733400375 0.1491702795 522 1305031119.5473821163 0.1871951669 0.1165417391 0.2781721056 0.0144185999 0.1535320000 877079108 0 1786245120 0.0818333477 0.1781111509 0.1472652256 523 1305031119.5795590878 0.1891650409 0.1166805982 0.2781721056 0.0144128552 0.1608830000 877080874 0 1786880000 0.0841166154 0.1837041229 0.1459970772 524 1305031119.6150169373 0.1883752346 0.1168174200 0.2781721056 0.0144108969 0.1721640000 877082704 0 1787260928 0.0840172395 0.1865793616 0.1454886347 525 1305031119.6479029655 0.1891767085 0.1169552472 0.2781721056 0.0144108473 0.1469750000 877084502 0 1787260928 0.0842743814 0.1927097738 0.1443616301 526 1305031119.6792080402 0.1909714788 0.1170959625 0.2781721056 0.0144007895 0.1352180000 877086236 0 1787895808 0.0865350291 0.1969055533 0.1434569806 527 1305031119.7152318954 0.1909196079 0.1172360453 0.2781721056 0.0143912370 0.1487810000 877088034 0 1786769408 0.0867173821 0.2002104372 0.1435873508 528 1305031119.7471930981 0.1900654584 0.1173739798 0.2781721056 0.0143782836 0.1694800000 877089864 0 1787277312 0.0854789242 0.2035660446 0.1430046707 529 1305031119.7791690826 0.1908269525 0.1175128323 0.2781721056 0.0143676389 0.1586900000 877091630 0 1787912192 0.0852396041 0.2074603885 0.1427845806 530 1305031119.8145370483 0.1929232031 0.1176551160 0.2781721056 0.0143653450 0.1572130000 877093364 0 1788166144 0.0867962837 0.2116691768 0.1423255652 531 1305031119.8474290371 0.1951950192 0.1178011422 0.2781721056 0.0143607826 0.1956370000 877095194 0 1786753024 0.0881952867 0.2154717147 0.1412586868 532 1305031119.8792140484 0.1961950511 0.1179484992 0.2781721056 0.0143563159 0.1784500000 877096928 0 1787387904 0.0882394388 0.2173095196 0.1401271671 533 1305031119.9114010334 0.1978706717 0.1180984470 0.2781721056 0.0143628467 0.1734540000 877098694 0 1787895808 0.0882583037 0.2238522023 0.1387116015 534 1305031119.9473919868 0.1996412575 0.1182511489 0.2781721056 0.0143539992 0.1751400000 877100556 0 1788149760 0.0880401358 0.2270306647 0.1377221346 535 1305031119.9795370102 0.2011362165 0.1184060742 0.2781721056 0.0143424839 0.1749120000 877102322 0 1786269696 0.0886537656 0.2288936824 0.1363106817 536 1305031120.0152640343 0.2030424327 0.1185639779 0.2781721056 0.0143530728 0.1737220000 877104120 0 1786744832 0.0885773823 0.2361349016 0.1359951794 537 1305031120.0472900867 0.2038813382 0.1187228556 0.2781721056 0.0143653975 1.8211310000 889416114 0 1788157952 0.0869988203 0.2351107746 0.1368259490 538 1305031120.0794179440 0.2055530548 0.1188842501 0.2781721056 0.0143822202 0.0993170000 893075760 0 1787920384 0.0915539786 0.2359583676 0.1289435327 539 1305031120.1152319908 0.2063162476 0.1190464616 0.2781721056 0.0143765308 0.2259010000 896269622 0 1786130432 0.0920189396 0.2378894836 0.1283379197 540 1305031120.1481568813 0.2065775394 0.1192085561 0.2781721056 0.0143847029 0.0991400000 896271420 0 1786765312 0.0925404727 0.2360103726 0.1289068609 541 1305031120.1792459488 0.2063057870 0.1193695492 0.2781721056 0.0143755028 0.1908900000 896273154 0 1787273216 0.0929907933 0.2331942171 0.1288910955 542 1305031120.2152490616 0.2042354047 0.1195261282 0.2781721056 0.0143638558 0.1882110000 896274984 0 1787273216 0.0915836841 0.2295734882 0.1287024319 543 1305031120.2480030060 0.2032758743 0.1196803635 0.2781721056 0.0143528048 0.1778780000 896276782 0 1787895808 0.0916298032 0.2289601117 0.1289310902 544 1305031120.2794299126 0.2016412616 0.1198310269 0.2781721056 0.0143430603 0.1720050000 896278548 0 1786753024 0.0912669003 0.2253497690 0.1294767261 545 1305031120.3151960373 0.1991673261 0.1199765981 0.2781721056 0.0143314538 0.1666910000 896280346 0 1787387904 0.0902233273 0.2214389145 0.1304495186 546 1305031120.3477869034 0.1964778155 0.1201167102 0.2781721056 0.0143209739 0.1560600000 896282144 0 1787895808 0.0898742750 0.2180399150 0.1314133555 547 1305031120.3794369698 0.1935382783 0.1202509361 0.2781721056 0.0143102348 0.1591170000 896283910 0 1788149760 0.0886465758 0.2124171257 0.1338801682 548 1305031120.4154450893 0.1901255846 0.1203784446 0.2781721056 0.0143042561 0.1664770000 896285708 0 1786769408 0.0876006261 0.2051669657 0.1354143769 549 1305031120.4474170208 0.1877250671 0.1205011161 0.2781721056 0.0143034180 0.1595040000 896287506 0 1787277312 0.0871581733 0.2040687054 0.1362201273 550 1305031120.4794321060 0.1848650277 0.1206181414 0.2781721056 0.0142923383 0.1594660000 896289304 0 1787768832 0.0859311670 0.1968372166 0.1393891871 551 1305031120.5148189068 0.1812671870 0.1207282122 0.2781721056 0.0142812818 0.1660030000 896291070 0 1788149760 0.0834681168 0.1922874749 0.1411451250 552 1305031120.5477359295 0.1790019423 0.1208337806 0.2781721056 0.0142719780 0.1853780000 896292868 0 1786150912 0.0824977905 0.1878644675 0.1423154324 553 1305031120.5795509815 0.1763268858 0.1209341298 0.2781721056 0.0142604400 0.1737710000 896294634 0 1786658816 0.0801436454 0.1831338704 0.1444243044 554 1305031120.6152360439 0.1763245910 0.1210341125 0.2781721056 0.0142511289 0.1774430000 896296400 0 1787166720 0.0801222697 0.1786969751 0.1476494968 555 1305031120.6473538876 0.1754015982 0.1211320720 0.2781721056 0.0142425073 0.1767920000 896298230 0 1787674624 0.0794580281 0.1735666096 0.1492726505 556 1305031120.6793179512 0.1759215891 0.1212306143 0.2781721056 0.0142570308 1.5395290000 908608840 0 1786900480 0.0795302838 0.1712789088 0.1514002681 557 1305031120.7145218849 0.1790811419 0.1213344752 0.2781721056 0.0142485472 0.2219330000 912268486 0 1786654720 0.0810277015 0.1693442464 0.1578062624 558 1305031120.7473690510 0.1782553494 0.1214364839 0.2781721056 0.0142407134 0.1416250000 915462380 0 1786249216 0.0791835114 0.1645061076 0.1597061753 559 1305031120.7798941135 0.1785421520 0.1215386408 0.2781721056 0.0142289881 0.1541950000 915464178 0 1785610240 0.0792034566 0.1594247371 0.1616856456 560 1305031120.8149440289 0.1800635010 0.1216431494 0.2781721056 0.0142299562 0.1539660000 915466008 0 1785122816 0.0786659494 0.1571315080 0.1626688987 561 1305031120.8479208946 0.1806818843 0.1217483878 0.2781721056 0.0142227710 0.1495960000 915467774 0 1785495552 0.0770807862 0.1520256102 0.1642146856 562 1305031120.8834350109 0.1816421896 0.1218549604 0.2781721056 0.0142108633 0.1552620000 915469572 0 1786003456 0.0769880936 0.1469213963 0.1650582403 563 1305031120.9154438972 0.1833276153 0.1219641481 0.2781721056 0.0142097809 0.1576240000 915471338 0 1786638336 0.0755835697 0.1445893943 0.1658141315 564 1305031120.9474880695 0.1851974130 0.1220762638 0.2781721056 0.0141990485 0.1646840000 915473104 0 1786638336 0.0740924403 0.1397928745 0.1666780859 565 1305031120.9833660126 0.1862042844 0.1221897647 0.2781721056 0.0141909079 0.1784600000 915474934 0 1787006976 0.0721363351 0.1357406974 0.1682469249 566 1305031121.0150189400 0.1873116642 0.1223048211 0.2781721056 0.0141808999 0.1653670000 915476668 0 1787514880 0.0710465387 0.1311766058 0.1688818485 567 1305031121.0474979877 0.1916974783 0.1224272067 0.2781721056 0.0141695023 0.1800570000 915478466 0 1788149760 0.0697980821 0.1285965592 0.1697212607 568 1305031121.0830988884 0.1914814264 0.1225487811 0.2781721056 0.0141617209 0.1618270000 915480296 0 1786769408 0.0670888424 0.1225286424 0.1704690009 569 1305031121.1146960258 0.1948454827 0.1226758403 0.2781721056 0.0141507522 0.1818330000 915482030 0 1787404288 0.0665502474 0.1195593253 0.1708006561 570 1305031121.1473309994 0.1990356445 0.1228098048 0.2781721056 0.0141412386 0.1839620000 915483828 0 1787912192 0.0644739643 0.1158772856 0.1713026017 571 1305031121.1832709312 0.2016333640 0.1229478496 0.2781721056 0.0141291895 0.1956960000 915485658 0 1788149760 0.0634012669 0.1116707698 0.1717649102 572 1305031121.2114200592 0.2049283832 0.1230911722 0.2781721056 0.0141185719 1.7555060000 927797856 0 1787416576 0.0633846670 0.1069591641 0.1719442606 573 1305031121.2471940517 0.2115165740 0.1232454923 0.2781721056 0.0141093490 0.2169610000 931457534 0 1786880000 0.0611672960 0.1060842797 0.1744259000 574 1305031121.2828760147 0.2130830437 0.1234020037 0.2781721056 0.0140972984 0.1885480000 934651492 0 1786118144 0.0594208688 0.1008079425 0.1756626219 575 1305031121.3135681152 0.2155168205 0.1235622034 0.2781721056 0.0140855717 0.1563560000 934653194 0 1785483264 0.0583647825 0.0957637802 0.1762161553 576 1305031121.3475170135 0.2216458470 0.1237324875 0.2781721056 0.0140747041 0.1511410000 934654992 0 1785982976 0.0559229739 0.0932965428 0.1771678030 577 1305031121.3832259178 0.2240910679 0.1239064192 0.2781721056 0.0140673723 0.1485480000 934656822 0 1786490880 0.0557494722 0.0870148391 0.1775194108 578 1305031121.4143180847 0.2288236022 0.1240879368 0.2781721056 0.0140576091 0.1393860000 934658556 0 1786998784 0.0544893742 0.0840478763 0.1776162386 579 1305031121.4473190308 0.2355573028 0.1242804573 0.2781721056 0.0140485323 0.1442950000 934660386 0 1787133952 0.0534063913 0.0809614882 0.1776282638 580 1305031121.4829640388 0.2373833358 0.1244754622 0.2781721056 0.0140402629 2.0119920000 946974528 0 1787260928 0.0523951836 0.0747523829 0.1795835644 581 1305031121.5141069889 0.2448472530 0.1246826426 0.2781721056 0.0140478328 0.2056730000 950634110 0 1786638336 0.0526142977 0.0735176504 0.1772658825 582 1305031121.5472700596 0.2520608008 0.1249015054 0.2781721056 0.0140374180 0.1564380000 953828068 0 1786396672 0.0517609827 0.0708640963 0.1785867065 583 1305031121.5832040310 0.2541807592 0.1251232537 0.2781721056 0.0140259638 0.1559120000 953829866 0 1785372672 0.0500461347 0.0652460232 0.1790325344 584 1305031121.6147000790 0.2580002248 0.1253507828 0.2781721056 0.0140159917 0.1275850000 953831600 0 1785368576 0.0487206317 0.0617260970 0.1791882217 585 1305031121.6471829414 0.2655016780 0.1255903570 0.2781721056 0.0140112877 0.1260800000 953833398 0 1785876480 0.0486061573 0.0594941340 0.1790607125 586 1305031121.6831998825 0.2679559290 0.1258333016 0.2781721056 0.0140094483 0.1266990000 953835228 0 1786384384 0.0451130010 0.0564092807 0.1793566644 587 1305031121.7145199776 0.2700761259 0.1260790305 0.2781721056 0.0140002529 0.1361790000 953836962 0 1786753024 0.0422987193 0.0528536811 0.1794380993 588 1305031121.7471449375 0.2754311264 0.1263330306 0.2781721056 0.0139886365 0.1182740000 953838760 0 1787006976 0.0417543240 0.0508403182 0.1802480221 589 1305031121.7828350067 0.2762513757 0.1265875609 0.2781721056 0.0139769021 0.1318290000 953840558 0 1787514880 0.0407231152 0.0467714965 0.1808667779 590 1305031121.8115398884 0.2789623141 0.1268458232 0.2789623141 0.0139683094 0.1472220000 953842260 0 1788022784 0.0411445722 0.0450623743 0.1816577017 591 1305031121.8473351002 0.2803976238 0.1271056401 0.2803976238 0.0139592121 0.1413530000 953844122 0 1786527744 0.0395914949 0.0436805859 0.1815523952 592 1305031121.8820600510 0.2799456716 0.1273638159 0.2803976238 0.0139482447 0.1413710000 953845888 0 1786007552 0.0378548652 0.0421659574 0.1819700152 593 1305031121.9149310589 0.2790926695 0.1276196824 0.2803976238 0.0139370527 0.1613240000 953847686 0 1786007552 0.0370310470 0.0417370833 0.1835135669 594 1305031121.9472880363 0.2782409489 0.1278732535 0.2803976238 0.0139274905 0.1660010000 953849452 0 1786499072 0.0390880704 0.0412386023 0.1831744909 595 1305031121.9829258919 0.2782371640 0.1281259660 0.2803976238 0.0139159533 0.1606660000 953851282 0 1787006976 0.0405697152 0.0432916358 0.1827021539 596 1305031122.0142560005 0.2747146785 0.1283719202 0.2803976238 0.0139051623 0.1551050000 953853048 0 1787387904 0.0398279354 0.0442780815 0.1834304184 597 1305031122.0473060608 0.2703783810 0.1286097870 0.2803976238 0.0138942929 0.1598120000 953854846 0 1787514880 0.0409207679 0.0467212908 0.1828651279 598 1305031122.0829589367 0.2670367360 0.1288412702 0.2803976238 0.0138829474 0.1517040000 953856644 0 1788022784 0.0428130031 0.0495615192 0.1822201908 599 1305031122.1146719456 0.2655561268 0.1290695087 0.2803976238 0.0138729356 0.1515790000 953858378 0 1786286080 0.0445915237 0.0549928024 0.1804817915 600 1305031122.1507248878 0.2578539550 0.1292841494 0.2803976238 0.0138641071 0.1276310000 953860208 0 1786118144 0.0464754775 0.0589941964 0.1810682118 601 1305031122.1830420494 0.2553248405 0.1294938677 0.2803976238 0.0138603597 0.1466560000 953862006 0 1786015744 0.0499541685 0.0641002283 0.1792786419 602 1305031122.2149589062 0.2538710535 0.1297004743 0.2803976238 0.0138627068 0.1548660000 953863740 0 1786511360 0.0513925403 0.0732861981 0.1785359085 603 1305031122.2513189316 0.2416194528 0.1298860779 0.2803976238 0.0138575418 0.1383340000 953865602 0 1787019264 0.0512896441 0.0746528879 0.1780963391 604 1305031122.2835600376 0.2394566238 0.1300674861 0.2803976238 0.0138489614 0.2612770000 953867400 0 1787400192 0.0533173606 0.0830839798 0.1803799868 605 1305031122.3142890930 0.2373870164 0.1302448738 0.2803976238 0.0138417289 0.1757600000 953869102 0 1787514880 0.0550591573 0.0916065946 0.1811719835 606 1305031122.3513269424 0.2283816487 0.1304068156 0.2803976238 0.0138371290 0.1949720000 953870932 0 1788022784 0.0567548499 0.0940842777 0.1803001463 607 1305031122.3826301098 0.2252133787 0.1305630044 0.2803976238 0.0138299008 0.1631980000 953872698 0 1786286080 0.0573254190 0.0998956561 0.1792414039 608 1305031122.4149971008 0.2204954475 0.1307109196 0.2803976238 0.0138316089 0.2122150000 953874432 0 1785659392 0.0578036420 0.1032541618 0.1777286977 609 1305031122.4512569904 0.2164710611 0.1308517408 0.2803976238 0.0138205467 0.1336580000 953876294 0 1786269696 0.0600405186 0.1085195839 0.1756934375 610 1305031122.4833600521 0.2140541375 0.1309881382 0.2803976238 0.0138206686 0.1596780000 953878060 0 1786777600 0.0613009036 0.1126990095 0.1740622371 611 1305031122.5150969028 0.2130062878 0.1311223741 0.2803976238 0.0138175718 0.1485910000 953879826 0 1787285504 0.0638709068 0.1171849966 0.1714264899 612 1305031122.5514900684 0.2106158286 0.1312522654 0.2803976238 0.0138103132 0.1770080000 953881656 0 1787514880 0.0669286251 0.1219467893 0.1693902016 613 1305031122.5832080841 0.2085291594 0.1313783288 0.2803976238 0.0138011613 0.1641890000 953883422 0 1787768832 0.0680315420 0.1260664314 0.1674012244 614 1305031122.6149799824 0.2052288800 0.1314986066 0.2803976238 0.0137938591 0.1859570000 953885156 0 1786531840 0.0673009157 0.1299019903 0.1658206284 615 1305031122.6487879753 0.2030356675 0.1316149270 0.2803976238 0.0137835918 0.1982240000 953886986 0 1787039744 0.0691161603 0.1350416839 0.1637929529 616 1305031122.6834020615 0.2010289878 0.1317276122 0.2803976238 0.0137748038 0.1759710000 953888784 0 1787674624 0.0699914843 0.1393386871 0.1595865637 617 1305031122.7152080536 0.1999509484 0.1318381849 0.2803976238 0.0137657622 1.6113310000 966204906 0 1786179584 0.0700642914 0.1446809322 0.1590791941 618 1305031122.7512979507 0.2003567964 0.1319490564 0.2803976238 0.0137615772 0.2458320000 969864616 0 1786011648 0.0723503828 0.1524645388 0.1588046700 619 1305031122.7834229469 0.2008036375 0.1320602916 0.2803976238 0.0137512234 0.1780950000 973058478 0 1786781696 0.0732648894 0.1587523967 0.1585411280 620 1305031122.8125550747 0.2006440908 0.1321709106 0.2803976238 0.0137466900 0.1666340000 973060212 0 1785102336 0.0755422637 0.1615842879 0.1580809355 621 1305031122.8514180183 0.2001528591 0.1322803824 0.2803976238 0.0137457309 0.1747790000 973062074 0 1785737216 0.0782232955 0.1654400229 0.1572632939 622 1305031122.8837540150 0.1992967725 0.1323881258 0.2803976238 0.0137387160 0.1576070000 973063872 0 1786245120 0.0782806799 0.1698923260 0.1566542089 623 1305031122.9145710468 0.1968351305 0.1324915720 0.2803976238 0.0137311834 0.1593360000 973065574 0 1786753024 0.0769061297 0.1729103774 0.1558629870 624 1305031122.9513409138 0.1962370276 0.1325937282 0.2803976238 0.0137222303 0.1656410000 973067436 0 1787006976 0.0782876089 0.1759469211 0.1542606503 625 1305031122.9828150272 0.1964443624 0.1326958892 0.2803976238 0.0137115814 0.1622760000 973069202 0 1787387904 0.0784967393 0.1808138192 0.1529956609 626 1305031123.0154500008 0.1962946355 0.1327974846 0.2803976238 0.0137042928 0.1643010000 973070936 0 1787895808 0.0796202794 0.1822971851 0.1515887827 627 1305031123.0518269539 0.1962761432 0.1328987265 0.2803976238 0.0136961759 0.1859010000 973072798 0 1786658816 0.0806953758 0.1850897372 0.1500773281 628 1305031123.0829749107 0.1979380995 0.1330022924 0.2803976238 0.0136894335 0.1841910000 973074564 0 1787166720 0.0820761919 0.1909862608 0.1486517191 629 1305031123.1138730049 0.1977727264 0.1331052661 0.2803976238 0.0136790906 0.1694290000 973076266 0 1787674624 0.0817055553 0.1954341531 0.1478293687 630 1305031123.1508219242 0.1967884153 0.1332063504 0.2803976238 0.0136691717 0.1883630000 973078128 0 1788055552 0.0808753595 0.1988071203 0.1479628533 631 1305031123.1821548939 0.1980053186 0.1333090429 0.2803976238 0.0136688062 0.1860800000 973079894 0 1788149760 0.0823430866 0.2038805038 0.1477072090 632 1305031123.2147040367 0.1977461278 0.1334110003 0.2803976238 0.0136586719 0.1858670000 973081660 0 1786286080 0.0825164393 0.2080341130 0.1472520530 633 1305031123.2506179810 0.1965396553 0.1335107296 0.2803976238 0.0136640666 0.1654390000 973083490 0 1785880576 0.0824216008 0.2140260786 0.1463286430 634 1305031123.2823469639 0.1979546100 0.1336123761 0.2803976238 0.0136686372 0.1992120000 973085256 0 1786249216 0.0844645500 0.2182858586 0.1466140151 635 1305031123.3113269806 0.1980278343 0.1337138178 0.2803976238 0.0136593600 2.4615040000 985402654 0 1788014592 0.0843928978 0.2225766182 0.1480245739 636 1305031123.3504810333 0.1970406920 0.1338133884 0.2803976238 0.0136561436 0.2024500000 989062396 0 1785991168 0.0860718340 0.2259637713 0.1439826041 637 1305031123.3822550774 0.1989836991 0.1339156965 0.2803976238 0.0136488357 0.1578520000 992256258 0 1785741312 0.0880260691 0.2305230498 0.1439410448 638 1305031123.4113628864 0.1987032890 0.1340172445 0.2803976238 0.0136437915 0.1303970000 992257960 0 1784000512 0.0876202956 0.2331686020 0.1436951905 639 1305031123.4512550831 0.1998897791 0.1341203314 0.2803976238 0.0136474612 0.1407170000 992259822 0 1784623104 0.0885102451 0.2389068007 0.1428208202 640 1305031123.4835939407 0.2014397383 0.1342255180 0.2803976238 0.0136454162 0.1350340000 992261620 0 1785131008 0.0899974182 0.2434426397 0.1422522068 641 1305031123.5113599300 0.2020451277 0.1343313208 0.2803976238 0.0136362861 0.1352180000 992263322 0 1785737216 0.0897776261 0.2471446395 0.1426312923 642 1305031123.5515129566 0.2027967423 0.1344379648 0.2803976238 0.0136266318 0.1319780000 992265216 0 1786118144 0.0909527093 0.2512953579 0.1413877308 643 1305031123.5795829296 0.2036529630 0.1345456086 0.2803976238 0.0136200732 0.1259010000 992266886 0 1786245120 0.0911990926 0.2547587454 0.1417753100 644 1305031123.6113350391 0.2060602754 0.1346566562 0.2803976238 0.0136106512 0.1177440000 992268620 0 1786753024 0.0945858732 0.2600623667 0.1401025057 645 1305031123.6524109840 0.2076674104 0.1347698512 0.2803976238 0.0136104001 1.7150860000 1004581014 0 1786511360 0.0957063287 0.2650727928 0.1404895335 646 1305031123.6837530136 0.2124066353 0.1348900320 0.2803976238 0.0136022243 0.1892850000 1008240628 0 1784987648 0.1003945470 0.2685984075 0.1411736161 647 1305031123.7113230228 0.2133323699 0.1350112721 0.2803976238 0.0135930233 0.1449330000 1011434394 0 1783967744 0.1014914587 0.2726638913 0.1405011714 648 1305031123.7517230511 0.2135527432 0.1351324780 0.2803976238 0.0135849523 0.1378610000 1011436320 0 1783255040 0.1002535298 0.2731281817 0.1407250017 649 1305031123.7838580608 0.2143409550 0.1352545250 0.2803976238 0.0135805176 0.1313820000 1011438054 0 1783242752 0.1007196382 0.2738811970 0.1404822320 650 1305031123.8116080761 0.2146513164 0.1353766739 0.2803976238 0.0135715099 0.1284480000 1011439788 0 1783480320 0.1009963378 0.2752326429 0.1400559545 651 1305031123.8514440060 0.2137757093 0.1354971025 0.2803976238 0.0135627730 0.1366160000 1011441650 0 1784086528 0.1003079712 0.2748106420 0.1390959173 652 1305031123.8837859631 0.2139011472 0.1356173541 0.2803976238 0.0135639829 0.1261340000 1011443448 0 1784594432 0.0991870388 0.2707799673 0.1402969807 653 1305031123.9112429619 0.2127844840 0.1357355274 0.2803976238 0.0135540434 0.1447530000 1011445118 0 1784594432 0.0995481834 0.2692505717 0.1385698766 654 1305031123.9514420033 0.2115385383 0.1358514341 0.2803976238 0.0135544711 0.1216110000 1011447012 0 1785102336 0.0995056778 0.2703860998 0.1387483329 655 1305031123.9834148884 0.2081681192 0.1359618413 0.2803976238 0.0135843408 0.1311010000 1011448810 0 1785610240 0.0948590636 0.2625783980 0.1407677829 656 1305031124.0113019943 0.2058212310 0.1360683343 0.2803976238 0.0135831673 0.1360050000 1011450480 0 1786118144 0.0935820192 0.2565782666 0.1407899559 657 1305031124.0515050888 0.2038488090 0.1361715009 0.2803976238 0.0135863971 0.1468740000 1011452374 0 1786626048 0.0945574492 0.2566575110 0.1408506334 658 1305031124.0838370323 0.2015118152 0.1362708023 0.2803976238 0.0135834968 0.1392120000 1011454140 0 1787133952 0.0922032967 0.2521932423 0.1440088302 659 1305031124.1113309860 0.1999606937 0.1363674485 0.2803976238 0.0135761171 0.1353540000 1011455842 0 1787641856 0.0925064832 0.2447768599 0.1448401660 660 1305031124.1474459171 0.1976276636 0.1364602671 0.2803976238 0.0135725259 0.1342740000 1011457704 0 1786286080 0.0935372710 0.2434759736 0.1450117677 661 1305031124.1826939583 0.1951349527 0.1365490336 0.2803976238 0.0135661306 0.1400640000 1011459502 0 1786638336 0.0919095278 0.2390441447 0.1482075900 662 1305031124.2113959789 0.1937146783 0.1366353865 0.2803976238 0.0135560019 0.1908750000 1011461204 0 1787146240 0.0922877416 0.2333705723 0.1496532112 663 1305031124.2493269444 0.1909507811 0.1367173102 0.2803976238 0.0135644662 0.1619470000 1011463034 0 1787654144 0.0920701474 0.2330563664 0.1504946053 664 1305031124.2825450897 0.1882629544 0.1367949392 0.2803976238 0.0135571339 0.1774240000 1011464832 0 1787908096 0.0903155580 0.2287146449 0.1525139511 665 1305031124.3113610744 0.1867634207 0.1368700798 0.2803976238 0.0135515187 0.1557970000 1011466534 0 1788149760 0.0901603848 0.2201365680 0.1541444212 666 1305031124.3503539562 0.1847116798 0.1369419140 0.2803976238 0.0135418948 0.1612910000 1011468396 0 1786511360 0.0898221508 0.2163466364 0.1546906531 667 1305031124.3824200630 0.1821591705 0.1370097060 0.2803976238 0.0135336224 0.1586250000 1011470194 0 1787019264 0.0885782242 0.2099079192 0.1553774923 668 1305031124.4114389420 0.1793913096 0.1370731515 0.2803976238 0.0135242761 0.1583510000 1011471896 0 1787527168 0.0873510614 0.2025116831 0.1556687206 669 1305031124.4502449036 0.1787713021 0.1371354806 0.2803976238 0.0135174245 0.1751240000 1011473758 0 1787908096 0.0878422335 0.1956785321 0.1560495198 670 1305031124.4800989628 0.1748443991 0.1371917625 0.2803976238 0.0135102063 0.1653350000 1011475524 0 1788022784 0.0848934427 0.1887371093 0.1556437910 671 1305031124.5113239288 0.1735842377 0.1372459987 0.2803976238 0.0135024434 0.1625840000 1011477258 0 1786372096 0.0838886723 0.1842932701 0.1555189937 672 1305031124.5504369736 0.1725160331 0.1372984839 0.2803976238 0.0134943328 0.1621050000 1011479152 0 1787006976 0.0825691000 0.1792369485 0.1560932547 673 1305031124.5794041157 0.1717887074 0.1373497324 0.2803976238 0.0134849569 1.5511990000 1023792978 0 1787531264 0.0816504657 0.1733196229 0.1577626914 674 1305031124.6113579273 0.1734106541 0.1374032352 0.2803976238 0.0134764658 0.1982850000 1027452560 0 1785221120 0.0809711814 0.1719037443 0.1617957652 675 1305031124.6512711048 0.1737437844 0.1374570731 0.2803976238 0.0134677617 0.1581390000 1030646550 0 1784881152 0.0799727961 0.1666803807 0.1630341709 676 1305031124.6793620586 0.1723388731 0.1375086734 0.2803976238 0.0134588846 0.1300040000 1030648284 0 1784492032 0.0791145712 0.1587415785 0.1644675881 677 1305031124.7112510204 0.1725371480 0.1375604141 0.2803976238 0.0134494256 0.1374610000 1030650018 0 1783758848 0.0786517337 0.1534380466 0.1652011722 678 1305031124.7498900890 0.1718733460 0.1376110231 0.2803976238 0.0134408036 0.1373670000 1030651912 0 1784238080 0.0762015954 0.1464730054 0.1671406925 679 1305031124.7793650627 0.1712223440 0.1376605243 0.2803976238 0.0134321350 0.1506160000 1030653646 0 1784745984 0.0742112026 0.1402490586 0.1691969782 680 1305031124.8113598824 0.1720853895 0.1377111492 0.2803976238 0.0134244613 0.1535230000 1030655380 0 1785253888 0.0733218342 0.1348726600 0.1711359173 681 1305031124.8505349159 0.1726808101 0.1377624996 0.2803976238 0.0134196845 0.1285700000 1030657242 0 1785475072 0.0711383969 0.1273356378 0.1734535247 682 1305031124.8793549538 0.1737622619 0.1378152852 0.2803976238 0.0134136419 0.1273090000 1030658976 0 1785729024 0.0716249645 0.1196845695 0.1760828346 683 1305031124.9114480019 0.1756407022 0.1378706665 0.2803976238 0.0134128015 0.1659030000 1030660742 0 1786245120 0.0705177560 0.1158058196 0.1775623709 684 1305031124.9507300854 0.1769302785 0.1379277712 0.2803976238 0.0134091974 0.1718330000 1030662604 0 1786880000 0.0690230280 0.1089213938 0.1810895354 685 1305031124.9794380665 0.1738161147 0.1379801629 0.2803976238 0.0134079236 1.5957690000 1042970646 0 1786372096 0.0656058863 0.0989861116 0.1836213619 686 1305031125.0114541054 0.1745131910 0.1380334180 0.2803976238 0.0133996220 0.2248910000 1046630260 0 1785237504 0.0636794344 0.0930912495 0.1846039742 687 1305031125.0507628918 0.1812907904 0.1380963837 0.2803976238 0.0133985396 0.1702040000 1049824218 0 1786028032 0.0656837225 0.0892739445 0.1864793897 688 1305031125.0793640614 0.1816437989 0.1381596793 0.2803976238 0.0133907221 0.1492300000 1049825952 0 1785511936 0.0633216128 0.0833994970 0.1884981990 689 1305031125.1113638878 0.1814904660 0.1382225687 0.2803976238 0.0133847073 0.1481700000 1049827718 0 1785626624 0.0603362322 0.0762333572 0.1901419461 690 1305031125.1510128975 0.1883595288 0.1382952310 0.2803976238 0.0133780496 0.1445940000 1049829580 0 1786118144 0.0610608608 0.0717569292 0.1909597516 691 1305031125.1793529987 0.1928047389 0.1383741159 0.2803976238 0.0133763480 0.1478500000 1049831282 0 1786753024 0.0593109354 0.0703739673 0.1915024370 692 1305031125.2113199234 0.1920935512 0.1384517452 0.2803976238 0.0133676599 0.1416480000 1049833080 0 1787006976 0.0560542382 0.0631394610 0.1938090175 693 1305031125.2506320477 0.1953533739 0.1385338543 0.2803976238 0.0133624061 0.1443970000 1049834942 0 1787260928 0.0534160510 0.0571175776 0.1956305951 694 1305031125.2794671059 0.1995907426 0.1386218325 0.2803976238 0.0133572458 2.1279090000 1062145604 0 1785864192 0.0522064529 0.0545658134 0.1948988140 695 1305031125.3114929199 0.2021313459 0.1387132131 0.2803976238 0.0133699973 0.2395650000 1065805218 0 1785753600 0.0585056171 0.0441844724 0.1967798620 696 1305031125.3488800526 0.2080330998 0.1388128107 0.2803976238 0.0133614885 0.1753740000 1068999144 0 1786372096 0.0566054061 0.0416143276 0.1968504041 697 1305031125.3794009686 0.2119540125 0.1389177478 0.2803976238 0.0133537730 0.1747880000 1069000910 0 1787006976 0.0577297658 0.0383844785 0.1979455352 698 1305031125.4113349915 0.2146163881 0.1390261986 0.2803976238 0.0133455650 0.1389260000 1069002644 0 1787641856 0.0569491014 0.0353184678 0.1987515241 699 1305031125.4511950016 0.2160928100 0.1391364513 0.2803976238 0.0133493767 0.1511210000 1069004570 0 1787641856 0.0540174618 0.0320822597 0.2004235685 700 1305031125.4794239998 0.2154765278 0.1392455085 0.2803976238 0.0133415060 0.1543060000 1069006272 0 1788022784 0.0523318425 0.0274840016 0.2015525997 701 1305031125.5113160610 0.2181604207 0.1393580833 0.2803976238 0.0133423034 0.1455540000 1069008038 0 1786286080 0.0516604893 0.0273404587 0.2008655220 702 1305031125.5510199070 0.2196698487 0.1394724875 0.2803976238 0.0133350021 0.1337290000 1069009932 0 1786908672 0.0517682582 0.0254781730 0.2009585500 703 1305031125.5793080330 0.2191064656 0.1395857649 0.2803976238 0.0133268744 0.1316730000 1069011666 0 1787387904 0.0516160727 0.0241041742 0.2016272694 704 1305031125.6115329266 0.2157742828 0.1396939872 0.2803976238 0.0133202058 0.1630520000 1069013400 0 1787768832 0.0495024696 0.0214753952 0.2020647079 705 1305031125.6505749226 0.2128547877 0.1397977614 0.2803976238 0.0133118102 0.1517460000 1069015326 0 1787895808 0.0464692451 0.0215404164 0.2005069405 706 1305031125.6793279648 0.2152253091 0.1399045992 0.2803976238 0.0133037929 0.1490020000 1069017028 0 1786028032 0.0459473729 0.0262019709 0.1962482631 707 1305031125.7114429474 0.2127147913 0.1400075840 0.2803976238 0.0133308343 0.1727370000 1069018762 0 1786142720 0.0479434058 0.0257638153 0.1963154674 708 1305031125.7512600422 0.2152237743 0.1401138215 0.2803976238 0.0133282771 0.1709410000 1069020656 0 1786777600 0.0520323738 0.0320663117 0.1924709380 709 1305031125.7793478966 0.2140337378 0.1402180809 0.2803976238 0.0133192956 0.1476250000 1069022390 0 1787260928 0.0539337397 0.0357264094 0.1913529634 710 1305031125.8115730286 0.2143348306 0.1403224707 0.2803976238 0.0133115128 0.1471850000 1069024156 0 1787514880 0.0568350777 0.0410469361 0.1893884093 711 1305031125.8474121094 0.2089577019 0.1404190041 0.2803976238 0.0133062344 0.1734200000 1069025986 0 1787768832 0.0573479980 0.0450390317 0.1888808459 712 1305031125.8793179989 0.2062143236 0.1405114132 0.2803976238 0.0132971489 0.1547730000 1069027752 0 1786138624 0.0569240600 0.0500594489 0.1864111871 713 1305031125.9113049507 0.2040357888 0.1406005077 0.2803976238 0.0132978878 0.1302210000 1069029486 0 1786138624 0.0560351647 0.0570028387 0.1832602173 714 1305031125.9473431110 0.1951561868 0.1406769163 0.2803976238 0.0132954491 0.1688400000 1069031348 0 1786634240 0.0552002452 0.0592424721 0.1814179271 715 1305031125.9793241024 0.1943711340 0.1407520131 0.2803976238 0.0132917573 0.1455620000 1069033114 0 1787133952 0.0585031062 0.0658107698 0.1809103340 716 1305031126.0113329887 0.1943012625 0.1408268025 0.2803976238 0.0132948471 0.2389800000 1069034848 0 1787641856 0.0638922229 0.0730812177 0.1846575737 717 1305031126.0473239422 0.1916341931 0.1408976636 0.2803976238 0.0132964858 0.2328180000 1069036710 0 1787641856 0.0697952136 0.0796284378 0.1853318214 718 1305031126.0793559551 0.1886308789 0.1409641444 0.2803976238 0.0132875021 0.1706180000 1069038444 0 1788276736 0.0715105385 0.0859087184 0.1852814257 719 1305031126.1113700867 0.1846123636 0.1410248512 0.2803976238 0.0132882284 0.1795000000 1069040210 0 1786138624 0.0731900111 0.0901509300 0.1856176257 720 1305031126.1474320889 0.1807401329 0.1410800113 0.2803976238 0.0132974470 0.1838810000 1069042072 0 1786626048 0.0749244913 0.0985397249 0.1857442260 721 1305031126.1793839931 0.1780467331 0.1411312828 0.2803976238 0.0132925850 0.1756410000 1069043838 0 1787133952 0.0753329098 0.1058362350 0.1856947988 722 1305031126.2113189697 0.1748306155 0.1411779578 0.2803976238 0.0132875729 0.1997010000 1069045572 0 1787641856 0.0776951090 0.1093793437 0.1851798743 723 1305031126.2472980022 0.1715119183 0.1412199135 0.2803976238 0.0132869348 0.2177150000 1069047434 0 1787641856 0.0787424669 0.1172093600 0.1842803806 724 1305031126.2793629169 0.1706237346 0.1412605265 0.2803976238 0.0132787079 0.1932630000 1069049200 0 1786028032 0.0802737474 0.1236726269 0.1840975434 725 1305031126.3113319874 0.1699201614 0.1413000570 0.2803976238 0.0132722939 2.1743510000 1081362262 0 1785757696 0.0809344277 0.1310143769 0.1836586297 726 1305031126.3473629951 0.1709885895 0.1413409503 0.2803976238 0.0132641751 0.1994030000 1085021972 0 1785643008 0.0853467435 0.1362655610 0.1836142838 727 1305031126.3794229031 0.1703139246 0.1413808031 0.2803976238 0.0132570923 0.1569540000 1088215834 0 1784233984 0.0852056816 0.1424323916 0.1826840639 728 1305031126.4114649296 0.1707701534 0.1414211731 0.2803976238 0.0132484663 0.1454010000 1088217568 0 1783595008 0.0860657245 0.1489098817 0.1819005311 729 1305031126.4473609924 0.1690908521 0.1414591287 0.2803976238 0.0132484204 0.1431530000 1088219398 0 1783226368 0.0868460685 0.1518294960 0.1803076416 730 1305031126.4795329571 0.1689714789 0.1414968169 0.2803976238 0.0132397036 0.1433040000 1088221196 0 1783468032 0.0870788693 0.1571588665 0.1787449718 731 1305031126.5114099979 0.1702909321 0.1415362069 0.2803976238 0.0132314226 0.1430570000 1088222930 0 1783959552 0.0882325023 0.1646746695 0.1773452908 732 1305031126.5473740101 0.1717890203 0.1415775359 0.2803976238 0.0132251890 0.1483780000 1088224760 0 1784467456 0.0908955857 0.1692318022 0.1774542779 733 1305031126.5794539452 0.1723810732 0.1416195598 0.2803976238 0.0132173142 0.1400970000 1088226558 0 1784721408 0.0920000747 0.1737579852 0.1765200943 734 1305031126.6115279198 0.1729142368 0.1416621956 0.2803976238 0.0132085662 0.1347480000 1088228292 0 1784848384 0.0931120217 0.1780665666 0.1757326424 735 1305031126.6473760605 0.1724796295 0.1417041241 0.2803976238 0.0132010678 0.1569650000 1088230122 0 1785483264 0.0939258784 0.1807592511 0.1754940152 736 1305031126.6794788837 0.1730612367 0.1417467289 0.2803976238 0.0131927874 0.1604430000 1088231888 0 1785991168 0.0954097509 0.1836892813 0.1740593910 737 1305031126.7115828991 0.1734356284 0.1417897260 0.2803976238 0.0131850753 0.1558140000 1088233654 0 1786499072 0.0961557850 0.1885743886 0.1728492230 738 1305031126.7473158836 0.1740077287 0.1418333819 0.2803976238 0.0131807563 0.1737250000 1088235484 0 1787006976 0.0978937373 0.1881315410 0.1713966876 739 1305031126.7793788910 0.1748458594 0.1418780537 0.2803976238 0.0131742101 0.1750450000 1088237250 0 1787514880 0.0990358815 0.1924230605 0.1700837761 740 1305031126.8116021156 0.1764547229 0.1419247789 0.2803976238 0.0131666587 0.1749270000 1088239016 0 1788022784 0.1014014259 0.1943818778 0.1690548360 741 1305031126.8473429680 0.1767641455 0.1419717956 0.2803976238 0.0131587253 0.1747400000 1088240846 0 1785507840 0.1025886834 0.1967343688 0.1673147231 742 1305031126.8793570995 0.1764578521 0.1420182728 0.2803976238 0.0131508361 0.1735680000 1088242612 0 1786015744 0.1027221084 0.1987365633 0.1664302349 743 1305031126.9113640785 0.1771806479 0.1420655976 0.2803976238 0.0131420622 0.1941740000 1088244378 0 1786499072 0.1040094346 0.1994190514 0.1657834798 744 1305031126.9474370480 0.1755761653 0.1421106387 0.2803976238 0.0131370907 0.1722220000 1088246240 0 1787133952 0.1031166837 0.2007845491 0.1645532697 745 1305031126.9793369770 0.1753366292 0.1421552374 0.2803976238 0.0131285168 0.1745520000 1088248006 0 1787514880 0.1026589498 0.2007451952 0.1651575714 746 1305031127.0113708973 0.1761430055 0.1422007974 0.2803976238 0.0131213179 0.1950630000 1088249740 0 1787514880 0.1044013724 0.1992066056 0.1636188924 747 1305031127.0472970009 0.1758121997 0.1422457926 0.2803976238 0.0131163165 0.1733760000 1088251602 0 1788022784 0.1040015370 0.2003964037 0.1638322324 748 1305031127.0792989731 0.1753290445 0.1422900215 0.2803976238 0.0131097420 0.1735130000 1088253368 0 1786028032 0.1033846438 0.2001337856 0.1640774161 749 1305031127.1114349365 0.1733180881 0.1423314475 0.2803976238 0.0131091094 0.1705360000 1088255070 0 1786245120 0.1017056033 0.1985383779 0.1633761674 750 1305031127.1473069191 0.1728988290 0.1423722040 0.2803976238 0.0131011331 0.1722770000 1088256932 0 1786753024 0.1010226384 0.1963534057 0.1635870188 751 1305031127.1793489456 0.1724663973 0.1424122762 0.2803976238 0.0130932408 0.1739520000 1088258698 0 1787387904 0.1005549580 0.1962635368 0.1637235284 752 1305031127.2116999626 0.1746369451 0.1424551281 0.2803976238 0.0130895609 0.1978300000 1088260464 0 1787514880 0.1028920561 0.1947798878 0.1646438390 753 1305031127.2473740578 0.1732469499 0.1424960203 0.2803976238 0.0130847439 0.1792650000 1088262294 0 1787895808 0.1014270484 0.1921786517 0.1656129509 754 1305031127.2794649601 0.1724446714 0.1425357400 0.2803976238 0.0130875679 0.1731640000 1088264028 0 1786118144 0.1005844027 0.1921782941 0.1657790095 755 1305031127.3113620281 0.1722908318 0.1425751507 0.2803976238 0.0130791174 0.1790930000 1088265794 0 1786245120 0.1003864110 0.1905372590 0.1668006480 756 1305031127.3473560810 0.1705659926 0.1426121757 0.2803976238 0.0130827928 0.1798550000 1088267656 0 1786753024 0.0987170562 0.1866764575 0.1683647633 757 1305031127.3792619705 0.1696825325 0.1426479357 0.2803976238 0.0130783957 0.1780750000 1088269422 0 1787260928 0.0978381485 0.1869878620 0.1685997844 758 1305031127.4113709927 0.1708137244 0.1426850937 0.2803976238 0.0130703537 0.2032030000 1088271156 0 1787641856 0.0986862332 0.1862528473 0.1696590930 759 1305031127.4473330975 0.1691607386 0.1427199760 0.2803976238 0.0130718735 0.1741910000 1088272986 0 1787895808 0.0968977883 0.1827450544 0.1711217612 760 1305031127.4793620110 0.1691771150 0.1427547880 0.2803976238 0.0130759700 0.1695430000 1088274752 0 1785610240 0.0963693336 0.1836773008 0.1715783924 761 1305031127.5113561153 0.1696816534 0.1427901716 0.2803976238 0.0130683434 0.1895130000 1088276518 0 1786118144 0.0963837132 0.1832914054 0.1728056222 762 1305031127.5473480225 0.1690768450 0.1428246685 0.2803976238 0.0130660811 0.1909970000 1088278380 0 1786626048 0.0959493667 0.1801558286 0.1739611924 763 1305031127.5793449879 0.1688564271 0.1428587861 0.2803976238 0.0130608723 0.1707130000 1088280146 0 1787133952 0.0954749957 0.1804095209 0.1745484620 764 1305031127.6112709045 0.1688442379 0.1428927985 0.2803976238 0.0130525916 0.1622300000 1088281880 0 1787514880 0.0953980908 0.1809877157 0.1751183420 765 1305031127.6473579407 0.1683545560 0.1429260819 0.2803976238 0.0130456900 0.1670600000 1088283742 0 1787514880 0.0952581093 0.1793316603 0.1761536747 766 1305031127.6792979240 0.1675463468 0.1429582232 0.2803976238 0.0130375898 0.1668660000 1088285476 0 1788141568 0.0946019962 0.1779448241 0.1764522344 767 1305031127.7113749981 0.1684702337 0.1429914853 0.2803976238 0.0130306298 0.1813290000 1088287242 0 1786130432 0.0949750543 0.1794166118 0.1764235646 768 1305031127.7473039627 0.1684508175 0.1430246354 0.2803976238 0.0130231678 0.1604750000 1088289104 0 1786499072 0.0947041437 0.1782981753 0.1771146208 769 1305031127.7793459892 0.1683602333 0.1430575816 0.2803976238 0.0130192138 0.1769390000 1088290838 0 1787133952 0.0945812091 0.1760713160 0.1769803762 770 1305031127.8118290901 0.1688330621 0.1430910563 0.2803976238 0.0130117436 0.1749590000 1088292636 0 1787641856 0.0943379775 0.1771323830 0.1767313331 771 1305031127.8473660946 0.1694142371 0.1431251979 0.2803976238 0.0130033000 0.1690270000 1088294466 0 1787641856 0.0940811858 0.1767458469 0.1768224686 772 1305031127.8793799877 0.1692441851 0.1431590308 0.2803976238 0.0129954428 0.1623950000 1088296200 0 1788149760 0.0934069827 0.1760795563 0.1771370023 773 1305031127.9114758968 0.1689608842 0.1431924096 0.2803976238 0.0129871688 0.1832990000 1088297966 0 1786253312 0.0927756205 0.1761933267 0.1773170978 774 1305031127.9473659992 0.1688289940 0.1432255318 0.2803976238 0.0129842790 0.1629880000 1088299796 0 1786761216 0.0922876894 0.1768837124 0.1779060066 775 1305031127.9793710709 0.1686529219 0.1432583413 0.2803976238 0.0129784528 0.1572450000 1088301562 0 1787269120 0.0923848152 0.1758167595 0.1785935611 776 1305031128.0114269257 0.1687095016 0.1432911392 0.2803976238 0.0129703965 0.1596000000 1088303328 0 1787650048 0.0930686817 0.1759181619 0.1790869236 777 1305031128.0473690033 0.1677016467 0.1433225556 0.2803976238 0.0129638649 0.1549840000 1088305190 0 1787768832 0.0929149613 0.1741587818 0.1812632680 778 1305031128.0793340206 0.1668315828 0.1433527728 0.2803976238 0.0129556754 0.1755370000 1088306956 0 1786138624 0.0926824585 0.1724619269 0.1822959483 779 1305031128.1113910675 0.1662973613 0.1433822267 0.2803976238 0.0129478903 0.1666520000 1088308690 0 1786138624 0.0926149040 0.1722092330 0.1832663417 780 1305031128.1474180222 0.1653933227 0.1434104461 0.2803976238 0.0129397542 0.1546880000 1088310552 0 1786634240 0.0925121903 0.1720792800 0.1839910895 781 1305031128.1793498993 0.1648741961 0.1434379285 0.2803976238 0.0129368870 0.1758700000 1088312286 0 1787142144 0.0928560793 0.1690551341 0.1846429110 782 1305031128.2114470005 0.1645749360 0.1434649579 0.2803976238 0.0129333416 0.1621570000 1088314052 0 1787650048 0.0925424844 0.1700789034 0.1847848147 783 1305031128.2474799156 0.1641758531 0.1434914086 0.2803976238 0.0129253704 0.1521120000 1088315914 0 1787641856 0.0919943377 0.1707507223 0.1852916926 784 1305031128.2793359756 0.1638204306 0.1435173385 0.2803976238 0.0129217544 0.1514680000 1088317680 0 1788149760 0.0918487087 0.1691844463 0.1856743842 785 1305031128.3114829063 0.1644887626 0.1435440537 0.2803976238 0.0129146145 0.1679220000 1088319414 0 1786015744 0.0922886431 0.1693285406 0.1853927672 786 1305031128.3474230766 0.1647943407 0.1435710897 0.2803976238 0.0129073102 0.1498850000 1088321276 0 1786523648 0.0916993022 0.1695434302 0.1854960620 787 1305031128.3794040680 0.1648595780 0.1435981398 0.2803976238 0.0129002841 0.1582580000 1088323010 0 1787158528 0.0910945684 0.1690282822 0.1856665760 788 1305031128.4113368988 0.1649736315 0.1436252661 0.2803976238 0.0128939876 0.1571650000 1088324776 0 1787539456 0.0908353776 0.1682798862 0.1853512675 789 1305031128.4472959042 0.1656376719 0.1436531652 0.2803976238 0.0128866034 0.1723210000 1088326606 0 1787641856 0.0907970518 0.1683732420 0.1850567311 790 1305031128.4792959690 0.1656797975 0.1436810470 0.2803976238 0.0128784961 0.1545170000 1088328372 0 1788149760 0.0902668983 0.1682098508 0.1852877885 791 1305031128.5114328861 0.1657535881 0.1437089516 0.2803976238 0.0128706272 0.1517630000 1088330138 0 1786138624 0.0902682617 0.1674473733 0.1850415021 792 1305031128.5473990440 0.1660538614 0.1437371649 0.2803976238 0.0128627654 0.1500110000 1088331968 0 1786507264 0.0906104967 0.1671428084 0.1848313063 793 1305031128.5794548988 0.1658232808 0.1437650162 0.2803976238 0.0128564119 0.1608330000 1088333734 0 1787015168 0.0908276960 0.1656858027 0.1846669465 794 1305031128.6113948822 0.1653286666 0.1437921745 0.2803976238 0.0128495086 0.1597730000 1088335500 0 1787650048 0.0899350196 0.1657260507 0.1844379157 795 1305031128.6473519802 0.1649532765 0.1438187922 0.2803976238 0.0128438364 0.1706340000 1088337330 0 1787641856 0.0889371485 0.1661698073 0.1842667162 796 1305031128.6792819500 0.1655434370 0.1438460845 0.2803976238 0.0128371379 0.1804500000 1088339096 0 1788022784 0.0895900875 0.1652184576 0.1840952784 797 1305031128.7114570141 0.1664597839 0.1438744580 0.2803976238 0.0128297833 0.1590540000 1088340862 0 1785917440 0.0904426798 0.1649047732 0.1836992949 798 1305031128.7473630905 0.1672144979 0.1439037062 0.2803976238 0.0128228058 0.1588150000 1088342692 0 1786523648 0.0907956660 0.1651635766 0.1831703484 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 06:14:03 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6417100430 0.0019026520 0.0019026520 0.0019026520 nan 0.0624830000 94528067 0 877420544 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0025652444 0.0022339482 0.0025652444 0.0019624690 0.2335310000 116573264 0 1003802624 0.0009610364 -0.0003349602 0.0001371624 3 1311867718.7114160061 0.0043678656 0.0029452540 0.0043678656 0.0029368388 0.2619050000 119844366 0 1007611904 0.0000202624 -0.0024260706 -0.0004448985 4 1311867718.7409899235 0.0023795010 0.0028038158 0.0043678656 0.0033251583 0.1465640000 119846364 0 1008517120 -0.0006771828 0.0000691075 0.0006482161 5 1311867718.7767970562 0.0018156213 0.0026061769 0.0043678656 0.0029313804 0.1524640000 119848594 0 1009008640 -0.0007969409 0.0002572367 0.0012054094 6 1311867718.8094038963 0.0045337696 0.0029274423 0.0045337696 0.0035567057 0.1768140000 119850984 0 1009516544 -0.0004509087 -0.0028540355 0.0003419270 7 1311867718.8408079147 0.0035068772 0.0030102187 0.0045337696 0.0033358959 0.1436850000 119852750 0 1010151424 -0.0004536401 -0.0009327424 0.0006168497 8 1311867718.8767778873 0.0044556139 0.0031908931 0.0045337696 0.0032274671 0.1783350000 119854580 0 1010659328 -0.0012482518 -0.0023233241 0.0008721164 9 1311867718.9088499546 0.0060166540 0.0035048666 0.0060166540 0.0032666061 0.1822680000 119856954 0 1011167232 -0.0029006661 -0.0033974235 0.0004115086 10 1311867718.9438269138 0.0051292013 0.0036673000 0.0060166540 0.0031476166 0.1810870000 119860096 0 1011675136 -0.0035915412 -0.0020427082 0.0010834427 11 1311867718.9784109592 0.0032697143 0.0036311559 0.0060166540 0.0030241180 0.1517720000 119861958 0 1012330496 -0.0015786496 -0.0000847512 0.0023594161 12 1311867719.0090429783 0.0038173213 0.0036466697 0.0060166540 0.0029262482 0.1638870000 119863628 0 1012817920 -0.0015499371 -0.0004925239 0.0022571257 13 1311867719.0441069603 0.0051419255 0.0037616893 0.0060166540 0.0028131502 0.2011170000 119865458 0 1013325824 -0.0031693419 -0.0025662284 0.0021456012 14 1311867719.0768620968 0.0055146152 0.0038868983 0.0060166540 0.0027612881 0.1754490000 119867256 0 1013833728 -0.0032300637 -0.0032299121 0.0025507663 15 1311867719.1086890697 0.0063125612 0.0040486092 0.0063125612 0.0027868417 0.2205980000 119869022 0 1014489088 -0.0014643940 -0.0040101171 0.0028270686 16 1311867719.1436860561 0.0059815743 0.0041694195 0.0063125612 0.0026951608 0.1694690000 119870820 0 1014996992 -0.0021267682 -0.0036424815 0.0030031705 17 1311867719.1810290813 0.0057456642 0.0042621398 0.0063125612 0.0026180011 0.3198440000 132220950 0 1027801088 -0.0032143076 -0.0035535609 0.0034535334 18 1311867719.2126939297 0.0042600026 0.0042620211 0.0063125612 0.0026432237 0.2221280000 135883356 0 1031737344 -0.0021714072 -0.0018143915 0.0045128576 19 1311867719.2412030697 0.0057258043 0.0043390623 0.0063125612 0.0025987948 0.1256650000 139077154 0 1035419648 -0.0029616295 -0.0041189417 0.0050517577 20 1311867719.2779400349 0.0055931979 0.0044017691 0.0063125612 0.0029525882 0.1442490000 139078952 0 1036308480 -0.0039888723 -0.0044414434 0.0055654836 21 1311867719.3104751110 0.0056587579 0.0044616257 0.0063125612 0.0030019058 0.1602980000 139080750 0 1036816384 -0.0051875766 -0.0043362104 0.0053361477 22 1311867719.3412981033 0.0045584780 0.0044660280 0.0063125612 0.0030114398 0.1382100000 139082516 0 1037324288 -0.0044978368 -0.0031855050 0.0059039192 23 1311867719.3772559166 0.0040892898 0.0044496481 0.0063125612 0.0029731981 0.1270730000 139084314 0 1037959168 -0.0049460852 -0.0033128711 0.0069643287 24 1311867719.4105629921 0.0051137102 0.0044773174 0.0063125612 0.0029486016 0.1442370000 139086112 0 1038467072 -0.0055641094 -0.0043405122 0.0061056777 25 1311867719.4427659512 0.0019465759 0.0043760877 0.0063125612 0.0030080199 0.1620570000 139087910 0 1038974976 -0.0055956165 -0.0010930659 0.0077638784 26 1311867719.4787509441 0.0008374940 0.0042399880 0.0063125612 0.0030149738 0.1628920000 139089708 0 1039491072 -0.0075892834 -0.0000426638 0.0086693373 27 1311867719.5103800297 0.0049102241 0.0042648115 0.0063125612 0.0034199798 0.1397950000 139091474 0 1039998976 -0.0046976623 -0.0044523259 0.0074818223 28 1311867719.5449209213 0.0028644418 0.0042147983 0.0063125612 0.0035122216 0.1549270000 139093272 0 1040633856 -0.0069426466 -0.0023292513 0.0076187858 29 1311867719.5771799088 0.0027038264 0.0041626958 0.0063125612 0.0034676330 0.1772260000 139095070 0 1041141760 -0.0064835227 -0.0006597953 0.0096191624 30 1311867719.6112289429 0.0037313292 0.0041483170 0.0063125612 0.0034594230 0.1648710000 139096868 0 1041649664 -0.0065211509 -0.0026207943 0.0086098155 31 1311867719.6421790123 0.0036624905 0.0041326451 0.0063125612 0.0034057373 0.4992780000 157935778 0 1059680256 -0.0076975292 -0.0027222296 0.0084433323 32 1311867719.6770379543 0.0027146386 0.0040883324 0.0063125612 0.0033827864 0.1339520000 161595456 0 1063870464 -0.0094479881 -0.0030171785 0.0095565589 33 1311867719.7107799053 0.0057717152 0.0041393440 0.0063125612 0.0034110436 0.2594080000 164792006 0 1067552768 -0.0108804870 -0.0058693667 0.0085842358 34 1311867719.7442409992 0.0054827277 0.0041788553 0.0063125612 0.0033633875 0.1901040000 164799020 0 1068441600 -0.0114164138 -0.0047288290 0.0085734008 35 1311867719.7806169987 0.0060466398 0.0042322206 0.0063125612 0.0034627146 0.1570750000 164800882 0 1068949504 -0.0128578199 -0.0049513946 0.0091517204 36 1311867719.8098258972 0.0038685377 0.0042221183 0.0063125612 0.0035502426 0.1283770000 164802584 0 1069457408 -0.0108896578 -0.0027609346 0.0106033944 37 1311867719.8454849720 0.0029639697 0.0041881143 0.0063125612 0.0035235976 0.1488830000 164804414 0 1070112768 -0.0109125627 -0.0015560201 0.0118649658 38 1311867719.8770980835 0.0035632125 0.0041716695 0.0063125612 0.0034874676 0.1291350000 164806180 0 1070600192 -0.0110600935 -0.0023687342 0.0117430463 39 1311867719.9113459587 0.0033822919 0.0041514290 0.0063125612 0.0034947428 0.1345850000 164808010 0 1071108096 -0.0113209784 -0.0019347576 0.0124686053 40 1311867719.9461910725 0.0036072666 0.0041378250 0.0063125612 0.0034578295 0.1614260000 164809808 0 1071616000 -0.0108169401 -0.0015486282 0.0134144649 41 1311867719.9807810783 0.0045932280 0.0041489324 0.0063125612 0.0034347747 0.1406450000 164811638 0 1072123904 -0.0107408669 -0.0028238697 0.0135793909 42 1311867720.0116190910 0.0055317418 0.0041818564 0.0063125612 0.0034397303 0.1502230000 164813340 0 1072771072 -0.0115359155 -0.0047090831 0.0130192395 43 1311867720.0450179577 0.0060887877 0.0042262036 0.0063125612 0.0034005072 0.1630830000 164815138 0 1073258496 -0.0102711329 -0.0035793195 0.0143258125 44 1311867720.0772368908 0.0048806067 0.0042410764 0.0063125612 0.0034423551 0.1479980000 164816936 0 1073766400 -0.0113843745 -0.0002490946 0.0148822870 45 1311867720.1121330261 0.0053924830 0.0042666632 0.0063125612 0.0034235820 0.1984770000 164818734 0 1074274304 -0.0111861741 0.0007636109 0.0147180967 46 1311867720.1451458931 0.0063793557 0.0043125913 0.0063793557 0.0034248925 0.1627580000 164820500 0 1074929664 -0.0102569172 -0.0005124587 0.0146345245 47 1311867720.1781549454 0.0060508735 0.0043495761 0.0063793557 0.0033900479 0.1334500000 164822266 0 1075417088 -0.0106836613 -0.0004448512 0.0146807628 48 1311867720.2094950676 0.0053283768 0.0043699677 0.0063793557 0.0033678809 0.4414660000 177132504 0 1088241664 -0.0123596676 -0.0013454215 0.0138467466 49 1311867720.2421309948 0.0053976839 0.0043909415 0.0063793557 0.0033350442 0.1143220000 180792526 0 1092198400 -0.0129932314 0.0000686494 0.0138361389 50 1311867720.2770709991 0.0061717047 0.0044265568 0.0063793557 0.0034115351 0.1033810000 183986420 0 1095987200 -0.0132325534 -0.0017826653 0.0140827727 51 1311867720.3094489574 0.0073996903 0.0044848535 0.0073996903 0.0034084858 0.1543540000 183988186 0 1096896512 -0.0132363010 -0.0023688814 0.0137984762 52 1311867720.3430650234 0.0065468904 0.0045245081 0.0073996903 0.0034893883 0.1709420000 183989984 0 1097383936 -0.0120665450 0.0002632845 0.0156142656 53 1311867720.3779759407 0.0079081096 0.0045883496 0.0079081096 0.0035018603 0.2087560000 183991750 0 1098018816 -0.0099327173 0.0008871620 0.0185858048 54 1311867720.4091560841 0.0086159008 0.0046629339 0.0086159008 0.0036990351 0.1580900000 183993516 0 1098526720 -0.0106329164 -0.0004248387 0.0175525285 55 1311867720.4412200451 0.0081026480 0.0047254742 0.0086159008 0.0036868278 0.1837750000 183995314 0 1099182080 -0.0118969586 0.0025443200 0.0173657481 56 1311867720.4798839092 0.0091529423 0.0048045361 0.0091529423 0.0036817182 0.1818620000 183997176 0 1099669504 -0.0117837684 0.0052383444 0.0183942728 57 1311867720.5104320049 0.0079288632 0.0048593489 0.0091529423 0.0037726035 0.1465520000 183998910 0 1100177408 -0.0118700042 0.0013671513 0.0179693736 58 1311867720.5410339832 0.0083339484 0.0049192557 0.0091529423 0.0037900504 0.1443090000 184000676 0 1100685312 -0.0126275187 0.0009550299 0.0170915332 59 1311867720.5793080330 0.0096082725 0.0049987306 0.0096082725 0.0038114487 0.1451800000 184002538 0 1101340672 -0.0112040397 0.0030640827 0.0194422435 60 1311867720.6121180058 0.0092232032 0.0050691385 0.0096082725 0.0037856021 0.1512940000 184004304 0 1101828096 -0.0119784055 0.0013430361 0.0186365712 61 1311867720.6410660744 0.0095468890 0.0051425442 0.0096082725 0.0038000233 0.1387530000 184006038 0 1102336000 -0.0126199536 0.0007184605 0.0181964114 62 1311867720.6797840595 0.0105502261 0.0052297649 0.0105502261 0.0038344178 0.1700190000 184007868 0 1102843904 -0.0120869614 0.0023792398 0.0190696083 63 1311867720.7102301121 0.0110318437 0.0053218614 0.0110318437 0.0038063090 0.1601550000 184009634 0 1103499264 -0.0119570838 0.0017435632 0.0202074219 64 1311867720.7411010265 0.0108328722 0.0054079709 0.0110318437 0.0038248684 0.1661290000 184011400 0 1103978496 -0.0129127642 -0.0010915897 0.0181117374 65 1311867720.7789759636 0.0112099294 0.0054972318 0.0112099294 0.0037998996 0.1573670000 184018638 0 1104486400 -0.0134879965 -0.0002047571 0.0178922005 66 1311867720.8115720749 0.0119350506 0.0055947745 0.0119350506 0.0037773471 0.4336600000 196335040 0 1117310976 -0.0130578950 -0.0005344090 0.0191741548 67 1311867720.8408989906 0.0074777761 0.0056228790 0.0119350506 0.0039535334 0.1239830000 199994590 0 1121247232 -0.0193935428 0.0023137855 0.0170009416 68 1311867720.8813259602 0.0073700598 0.0056485729 0.0119350506 0.0039305758 0.0968760000 203188612 0 1124929536 -0.0198756326 0.0021652919 0.0167605560 69 1311867720.9105548859 0.0084035974 0.0056885008 0.0119350506 0.0039116959 0.1133240000 203190314 0 1125818368 -0.0194427073 0.0037743815 0.0171595085 70 1311867720.9409220219 0.0085023232 0.0057286982 0.0119350506 0.0039080708 0.1144070000 203192048 0 1126326272 -0.0191210359 0.0038404574 0.0172361117 71 1311867720.9797680378 0.0086448519 0.0057697708 0.0119350506 0.0039028440 0.2350420000 203193878 0 1126961152 -0.0198360514 0.0047132894 0.0173494313 72 1311867721.0093820095 0.0068240855 0.0057844141 0.0119350506 0.0039267290 0.1948230000 203195612 0 1127469056 -0.0206978023 0.0008785164 0.0168718435 73 1311867721.0410830975 0.0076955669 0.0058105943 0.0119350506 0.0039115219 0.1194780000 203197378 0 1127976960 -0.0203129780 0.0029621937 0.0167202447 74 1311867721.0794250965 0.0081887143 0.0058427310 0.0119350506 0.0039162623 0.1371470000 203199240 0 1128484864 -0.0202894397 0.0029312882 0.0165215563 75 1311867721.1103479862 0.0089292619 0.0058838848 0.0119350506 0.0038968851 0.1077900000 203201006 0 1129140224 -0.0197685976 0.0040247724 0.0171811022 76 1311867721.1413290501 0.0075916485 0.0059063553 0.0119350506 0.0039040817 0.1697750000 203202740 0 1129627648 -0.0208277851 -0.0003624700 0.0165541917 77 1311867721.1773610115 0.0081023453 0.0059348747 0.0119350506 0.0038823196 0.1636390000 203204602 0 1130135552 -0.0209017601 -0.0019396156 0.0162727796 78 1311867721.2112181187 0.0083709592 0.0059661065 0.0119350506 0.0038645618 0.1470550000 203206368 0 1130643456 -0.0204691254 0.0005287379 0.0162750874 79 1311867721.2409920692 0.0086754793 0.0060004024 0.0119350506 0.0038793735 0.1555860000 203208102 0 1131298816 -0.0202498026 -0.0014873202 0.0170073770 80 1311867721.2799990177 0.0092309862 0.0060407847 0.0119350506 0.0038605052 0.1962250000 203209964 0 1131786240 -0.0200466383 0.0003310418 0.0161166172 81 1311867721.3099579811 0.0091844536 0.0060795954 0.0119350506 0.0038392219 0.1542980000 203211730 0 1132294144 -0.0201107282 0.0014283073 0.0165646374 82 1311867721.3409619331 0.0090873223 0.0061162750 0.0119350506 0.0038512230 0.1478530000 203213464 0 1132802048 -0.0215287786 -0.0025821547 0.0154562714 83 1311867721.3789949417 0.0097267013 0.0061597741 0.0119350506 0.0038367760 0.1750580000 203215262 0 1133457408 -0.0209473148 -0.0009609900 0.0149408076 84 1311867721.4092490673 0.0100863772 0.0062065194 0.0119350506 0.0038205874 0.1639210000 203216996 0 1133944832 -0.0214721132 -0.0011539487 0.0140974009 85 1311867721.4412109852 0.0094497129 0.0062446746 0.0119350506 0.0037997489 0.1512120000 203218794 0 1134452736 -0.0225983765 -0.0003101043 0.0137876254 86 1311867721.4768860340 0.0102471728 0.0062912153 0.0119350506 0.0037797361 0.1474010000 203220624 0 1134960640 -0.0222432744 -0.0009732565 0.0139064323 87 1311867721.5093119144 0.0096744671 0.0063301033 0.0119350506 0.0037627608 0.1356010000 203222358 0 1135616000 -0.0222051125 0.0008932548 0.0148965521 88 1311867721.5411579609 0.0104295127 0.0063766874 0.0119350506 0.0037479567 0.1431740000 203224156 0 1136103424 -0.0220522881 0.0001617784 0.0142602287 89 1311867721.5769670010 0.0103148324 0.0064209363 0.0119350506 0.0037313926 0.1624070000 203225890 0 1136611328 -0.0240082163 -0.0015899012 0.0127946064 90 1311867721.6094360352 0.0090402346 0.0064500396 0.0119350506 0.0037463519 0.1259410000 203227624 0 1137119232 -0.0233642347 0.0021822872 0.0146718686 91 1311867721.6409630775 0.0108096339 0.0064979472 0.0119350506 0.0037590258 0.3858140000 215535874 0 1149943808 -0.0235324409 -0.0020049356 0.0133297443 92 1311867721.6800279617 0.0183279924 0.0066265347 0.0183279924 0.0038999971 0.2291490000 219195584 0 1153880064 -0.0187768694 -0.0073516052 0.0118716545 93 1311867721.7089879513 0.0165187232 0.0067329023 0.0183279924 0.0038900696 0.2012610000 222389414 0 1157709824 -0.0184918735 -0.0037235734 0.0136911189 94 1311867721.7410759926 0.0167351514 0.0068393092 0.0183279924 0.0038812569 0.1845160000 222391180 0 1158451200 -0.0209265370 -0.0072959512 0.0137534020 95 1311867721.7786920071 0.0170966163 0.0069472808 0.0183279924 0.0038658153 0.1555810000 222393042 0 1159106560 -0.0206503589 -0.0058553373 0.0116141252 96 1311867721.8090760708 0.0156741627 0.0070381859 0.0183279924 0.0038534538 0.1576400000 222394776 0 1159593984 -0.0206956547 -0.0035870657 0.0130840037 97 1311867721.8409729004 0.0175316203 0.0071463656 0.0183279924 0.0038466741 0.1652340000 222396542 0 1160101888 -0.0203399155 -0.0061652483 0.0133787747 98 1311867721.8778719902 0.0166429915 0.0072432699 0.0183279924 0.0038392705 0.1547850000 222398404 0 1160609792 -0.0209996495 -0.0039544730 0.0111229578 99 1311867721.9089739323 0.0171506759 0.0073433447 0.0183279924 0.0038205199 0.1445660000 222400010 0 1161117696 -0.0202017669 -0.0039907596 0.0120609468 100 1311867721.9409759045 0.0186699368 0.0074566107 0.0186699368 0.0038160465 0.1447840000 222401808 0 1161752576 -0.0194911752 -0.0056255981 0.0122031067 101 1311867721.9773590565 0.0183739793 0.0075647034 0.0186699368 0.0038149261 0.1593990000 222403638 0 1162260480 -0.0207215007 -0.0062340354 0.0105959745 102 1311867722.0090909004 0.0184509307 0.0076714311 0.0186699368 0.0038189130 0.1477900000 222405340 0 1162768384 -0.0199585725 -0.0052833883 0.0119183306 103 1311867722.0409901142 0.0184630062 0.0077762037 0.0186699368 0.0038080093 0.1353550000 222407042 0 1163423744 -0.0207222607 -0.0063175014 0.0111734569 104 1311867722.0800709724 0.0193120427 0.0078871252 0.0193120427 0.0037933840 0.1627890000 222408936 0 1163911168 -0.0203483943 -0.0069044982 0.0108092139 105 1311867722.1090641022 0.0199824870 0.0080023192 0.0199824870 0.0037789935 0.1485840000 222410606 0 1164419072 -0.0202341694 -0.0076644649 0.0114876470 106 1311867722.1409659386 0.0205907561 0.0081210780 0.0205907561 0.0037704774 0.1451290000 222412372 0 1164926976 -0.0215688348 -0.0093356343 0.0097963903 107 1311867722.1798129082 0.0190028287 0.0082227766 0.0205907561 0.0037683297 0.1349400000 222414234 0 1165582336 -0.0228198841 -0.0075208824 0.0086952364 108 1311867722.2090559006 0.0170250833 0.0083042795 0.0205907561 0.0037660295 0.1393040000 222415936 0 1166069760 -0.0224594045 -0.0045217900 0.0106530497 109 1311867722.2409958839 0.0187934786 0.0084005106 0.0205907561 0.0037784734 0.1314130000 222417734 0 1166577664 -0.0224179178 -0.0071514915 0.0096417936 110 1311867722.2778589725 0.0186074767 0.0084933012 0.0205907561 0.0037618374 0.1373750000 222419596 0 1167085568 -0.0239978768 -0.0072577856 0.0076804087 111 1311867722.3090419769 0.0183385871 0.0085819975 0.0205907561 0.0037471027 0.1323790000 222421298 0 1167593472 -0.0224454254 -0.0058549321 0.0100613004 112 1311867722.3409590721 0.0189048499 0.0086741658 0.0205907561 0.0037382452 0.1287080000 222423096 0 1168248832 -0.0231197197 -0.0072059357 0.0097977892 113 1311867722.3777840137 0.0187848639 0.0087636410 0.0205907561 0.0037219203 0.1434580000 222424926 0 1168736256 -0.0238901731 -0.0071561052 0.0082986290 114 1311867722.4089860916 0.0182116888 0.0088465186 0.0205907561 0.0037088522 0.1324930000 222426628 0 1169244160 -0.0231721550 -0.0058729132 0.0102186836 115 1311867722.4409530163 0.0192525107 0.0089370055 0.0205907561 0.0037211497 0.1315560000 222428362 0 1169752064 -0.0237912741 -0.0079305386 0.0102448398 116 1311867722.4777851105 0.0193965435 0.0090271740 0.0205907561 0.0037456002 0.1419990000 222430192 0 1170407424 -0.0249437019 -0.0081191501 0.0083260993 117 1311867722.5090739727 0.0175784472 0.0091002618 0.0205907561 0.0038227295 0.1332550000 222431926 0 1170894848 -0.0265161879 -0.0066534346 0.0088782711 118 1311867722.5411169529 0.0164350886 0.0091624213 0.0205907561 0.0038430803 0.1294560000 222433628 0 1171402752 -0.0279818606 -0.0059480271 0.0078455070 119 1311867722.5802209377 0.0161636844 0.0092212555 0.0205907561 0.0038291421 0.1330540000 222435490 0 1171910656 -0.0266538300 -0.0048302403 0.0090214591 120 1311867722.6091809273 0.0145711768 0.0092658381 0.0205907561 0.0038206880 0.1373640000 222437192 0 1172418560 -0.0281257443 -0.0043420279 0.0094062351 121 1311867722.6411309242 0.0163174551 0.0093241160 0.0205907561 0.0038186795 0.1313800000 222438990 0 1173053440 -0.0280138385 -0.0070129577 0.0097203776 122 1311867722.6778120995 0.0165412016 0.0093832724 0.0205907561 0.0038101630 0.1403180000 222440852 0 1173561344 -0.0292985234 -0.0078544719 0.0083891340 123 1311867722.7090990543 0.0156076569 0.0094338772 0.0205907561 0.0038693479 0.1312680000 222442586 0 1174069248 -0.0294427928 -0.0066958768 0.0092229135 124 1311867722.7411129475 0.0148919988 0.0094778943 0.0205907561 0.0038788598 0.1493900000 222444352 0 1174577152 -0.0330015644 -0.0081940414 0.0084681679 125 1311867722.7770080566 0.0172754955 0.0095402751 0.0205907561 0.0038832247 0.1624630000 222446214 0 1175232512 -0.0310883671 -0.0090455851 0.0067727985 126 1311867722.8090240955 0.0167095922 0.0095971744 0.0205907561 0.0038729422 0.1503820000 222447948 0 1175740416 -0.0366106294 -0.0095302425 0.0054379744 127 1311867722.8412160873 0.0140328277 0.0096321008 0.0205907561 0.0038599751 0.3492020000 234751778 0 1188564992 -0.0337924547 -0.0070928675 0.0090334974 128 1311867722.8771059513 0.0149592599 0.0096737193 0.0205907561 0.0038688527 0.2354250000 238411456 0 1192501248 -0.0415744670 -0.0071479580 0.0047782166 129 1311867722.9092500210 0.0152746616 0.0097171374 0.0205907561 0.0038578562 0.1799850000 241616038 0 1196163072 -0.0435662977 -0.0045807939 0.0027339344 130 1311867722.9413120747 0.0136453174 0.0097473542 0.0205907561 0.0038526200 0.1555110000 241638764 0 1197051904 -0.0416272432 -0.0060088085 0.0062623410 131 1311867722.9771549702 0.0160721224 0.0097956349 0.0205907561 0.0038400761 0.1550900000 241640594 0 1197559808 -0.0439247005 -0.0068016085 0.0040655527 132 1311867723.0092680454 0.0167350061 0.0098482059 0.0205907561 0.0038282228 0.1538830000 241642328 0 1198215168 -0.0458485633 -0.0041891038 0.0018068540 133 1311867723.0411980152 0.0146072004 0.0098839878 0.0205907561 0.0038804494 0.1446310000 241644094 0 1198702592 -0.0458014272 -0.0051530339 0.0050757760 134 1311867723.0773079395 0.0139042353 0.0099139896 0.0205907561 0.0040125824 0.1480810000 241645956 0 1199210496 -0.0441326760 -0.0051699476 0.0058892141 135 1311867723.1091949940 0.0175773166 0.0099707550 0.0205907561 0.0040046592 0.1516270000 241647690 0 1199718400 -0.0468255207 -0.0074634366 0.0034937607 136 1311867723.1411499977 0.0160907079 0.0100157547 0.0205907561 0.0039902855 0.1641770000 241649424 0 1200226304 -0.0466893651 -0.0076671531 0.0055075996 137 1311867723.1769969463 0.0183613524 0.0100766714 0.0205907561 0.0039763116 0.1765110000 241651286 0 1200734208 -0.0490160659 -0.0098123532 0.0045481832 138 1311867723.2092559338 0.0195569079 0.0101453688 0.0205907561 0.0039625308 0.1575590000 241653020 0 1201389568 -0.0510224402 -0.0104604224 0.0035564688 139 1311867723.2410740852 0.0214671064 0.0102268201 0.0214671064 0.0039506337 0.1532570000 241654786 0 1201876992 -0.0536043718 -0.0116059817 0.0025145113 140 1311867723.2773449421 0.0235279575 0.0103218283 0.0235279575 0.0039419735 0.1735680000 241656648 0 1202376704 -0.0566307381 -0.0124950623 0.0015474687 141 1311867723.3093810081 0.0288213138 0.0104530303 0.0288213138 0.0039337958 0.1765160000 241658350 0 1202884608 -0.0615088828 -0.0160163473 -0.0000558896 142 1311867723.3412499428 0.0371591337 0.0106411014 0.0371591337 0.0039398678 0.1686600000 241660148 0 1203392512 -0.0690210685 -0.0199985988 -0.0037363684 143 1311867723.3772110939 0.0433521569 0.0108698501 0.0433521569 0.0039360863 0.1651840000 241661978 0 1204047872 -0.0749246702 -0.0232928339 -0.0052872887 144 1311867723.4093298912 0.0526884980 0.0111602574 0.0526884980 0.0039311191 0.1636340000 241663712 0 1204535296 -0.0838558227 -0.0269117951 -0.0084993979 145 1311867723.4410910606 0.0631496757 0.0115188051 0.0631496757 0.0039601704 0.1600280000 241665510 0 1205043200 -0.0915380418 -0.0335350782 -0.0114746895 146 1311867723.4770638943 0.0681205839 0.0119064885 0.0681205839 0.0039559040 0.1602810000 241667340 0 1205551104 -0.0949139819 -0.0371311493 -0.0137417158 147 1311867723.5092871189 0.0718340650 0.0123141591 0.0718340650 0.0039512617 0.1571110000 241669074 0 1206206464 -0.0965117812 -0.0403470658 -0.0154967047 148 1311867723.5412330627 0.0737922713 0.0127295517 0.0737922713 0.0039411310 0.1566840000 241670872 0 1206693888 -0.0967868865 -0.0417168327 -0.0177199207 149 1311867723.5771219730 0.0750518590 0.0131478222 0.0750518590 0.0039357432 0.1565670000 241672702 0 1207201792 -0.0972241610 -0.0429405496 -0.0185749885 150 1311867723.6092190742 0.0756139979 0.0135642634 0.0756139979 0.0039269962 0.1558800000 241674436 0 1207709696 -0.0973626822 -0.0432003886 -0.0193489920 151 1311867723.6412839890 0.0753073320 0.0139731579 0.0756139979 0.0039218172 0.1608740000 241676234 0 1208225792 -0.0977091491 -0.0422744825 -0.0194262099 152 1311867723.6771829128 0.0737068728 0.0143661429 0.0756139979 0.0039118062 0.1549270000 241678064 0 1208881152 -0.0978154093 -0.0407753922 -0.0182531942 153 1311867723.7092189789 0.0732773244 0.0147511833 0.0756139979 0.0039002263 0.1547390000 241679830 0 1209368576 -0.0978322253 -0.0408358686 -0.0176351909 154 1311867723.7412030697 0.0726088807 0.0151268826 0.0756139979 0.0038880377 0.1559260000 241681596 0 1209876480 -0.0976336077 -0.0405780934 -0.0172210280 155 1311867723.7771170139 0.0697687268 0.0154794106 0.0756139979 0.0039159483 0.4071760000 253985206 0 1222819840 -0.0978469402 -0.0392175913 -0.0129179871 156 1311867723.8093750477 0.0705913231 0.0158326921 0.0756139979 0.0039073996 0.0839820000 257645660 0 1226756096 -0.0973308757 -0.0411439389 -0.0140000749 157 1311867723.8410520554 0.0715550333 0.0161876115 0.0756139979 0.0038980812 0.1695410000 260839522 0 1230438400 -0.0983058885 -0.0412434153 -0.0151332645 158 1311867723.8770780563 0.0687907413 0.0165205427 0.0756139979 0.0039007777 0.0793270000 260841352 0 1231327232 -0.0978635252 -0.0392537117 -0.0134021360 159 1311867723.9092159271 0.0723903030 0.0168719248 0.0756139979 0.0039074252 0.1337700000 260843054 0 1231835136 -0.0990266576 -0.0422170758 -0.0161592942 160 1311867723.9411931038 0.0745587721 0.0172324676 0.0756139979 0.0039005804 0.1312270000 260844788 0 1232343040 -0.1007569730 -0.0426071845 -0.0183023978 161 1311867723.9773468971 0.0711594298 0.0175674177 0.0756139979 0.0038964402 0.1344350000 260846650 0 1232977920 -0.0991965830 -0.0412399024 -0.0150817949 162 1311867724.0091340542 0.0729503930 0.0179092879 0.0756139979 0.0038937954 0.1299180000 260848352 0 1233485824 -0.1002760604 -0.0419452414 -0.0169133060 163 1311867724.0412750244 0.0736100003 0.0182510101 0.0756139979 0.0038836327 0.1339020000 260850150 0 1233993728 -0.1008228883 -0.0418961383 -0.0176965166 164 1311867724.0771689415 0.0707220435 0.0185709554 0.0756139979 0.0038738395 0.1331760000 260851980 0 1234501632 -0.0995127559 -0.0408845767 -0.0147333620 165 1311867724.1093120575 0.0719318092 0.0188943545 0.0756139979 0.0038664154 0.1335740000 260853746 0 1235136512 -0.0999091864 -0.0423924774 -0.0151649164 166 1311867724.1413280964 0.0735680014 0.0192237138 0.0756139979 0.0038569883 0.1410570000 260855512 0 1235644416 -0.1008662432 -0.0430064052 -0.0169219561 167 1311867724.1770989895 0.0711423755 0.0195346040 0.0756139979 0.0038528594 0.1096840000 260857342 0 1236152320 -0.1000838429 -0.0412405729 -0.0151717244 168 1311867724.2094969749 0.0723353550 0.0198488942 0.0756139979 0.0038438244 0.1064470000 260859108 0 1236660224 -0.1003683284 -0.0428823382 -0.0154979769 169 1311867724.2412230968 0.0735671595 0.0201667538 0.0756139979 0.0038346729 0.1361920000 260860874 0 1237315584 -0.1011908054 -0.0433190092 -0.0165932979 170 1311867724.2771489620 0.0717733800 0.0204703222 0.0756139979 0.0038250276 0.1085600000 260862704 0 1237823488 -0.1008646712 -0.0418066867 -0.0152674112 171 1311867724.3092370033 0.0711498931 0.0207666939 0.0756139979 0.0038138059 0.1126690000 260864470 0 1238310912 -0.1005324945 -0.0420940258 -0.0141554596 172 1311867724.3412630558 0.0726858154 0.0210685493 0.0756139979 0.0038049527 0.1072850000 260866236 0 1238818816 -0.1011543870 -0.0430507809 -0.0159057658 173 1311867724.3775219917 0.0721393675 0.0213637563 0.0756139979 0.0037951953 0.1119300000 260868098 0 1239326720 -0.1009394079 -0.0435121655 -0.0146328360 174 1311867724.4092609882 0.0701148808 0.0216439352 0.0756139979 0.0037880264 0.1202080000 260869800 0 1239834624 -0.1007841453 -0.0418501720 -0.0131704453 175 1311867724.4451010227 0.0703667179 0.0219223511 0.0756139979 0.0037805730 0.1283590000 260871630 0 1240489984 -0.1007559076 -0.0432727784 -0.0129299341 176 1311867724.4770729542 0.0710224584 0.0222013290 0.0756139979 0.0037702159 0.1230900000 260873428 0 1240977408 -0.1010542512 -0.0446226262 -0.0130947065 177 1311867724.5095100403 0.0709013268 0.0224764702 0.0756139979 0.0037618402 0.1123310000 260875194 0 1241485312 -0.1014267355 -0.0447261035 -0.0132522276 178 1311867724.5453720093 0.0615055673 0.0226957348 0.0756139979 0.0037862207 0.1210550000 260876928 0 1242001408 -0.0968764275 -0.0376190729 -0.0102699790 179 1311867724.5771729946 0.0628608912 0.0229201212 0.0756139979 0.0037765602 0.1058440000 260878694 0 1242656768 -0.0986904278 -0.0383721292 -0.0109427534 180 1311867724.6092879772 0.0670083165 0.0231650556 0.0756139979 0.0037718758 0.1200170000 260880492 0 1243144192 -0.1011666805 -0.0422476865 -0.0121923769 181 1311867724.6451389790 0.0680699572 0.0234131490 0.0756139979 0.0037640095 0.1257210000 260882290 0 1243652096 -0.1014064997 -0.0440602154 -0.0124036185 182 1311867724.6771860123 0.0627580285 0.0236293296 0.0756139979 0.0037743527 0.1037980000 260884056 0 1244160000 -0.0995621830 -0.0401149988 -0.0094698239 183 1311867724.7093029022 0.0679305121 0.0238714126 0.0756139979 0.0037873178 0.1190970000 260885822 0 1244667904 -0.1018624157 -0.0444638692 -0.0124258166 184 1311867724.7452270985 0.0699541643 0.0241218623 0.0756139979 0.0037822745 0.3254470000 273189776 0 1257639936 -0.1028029248 -0.0462822542 -0.0132915284 185 1311867724.7772819996 0.1343840063 0.0247178739 0.1343840063 0.0058404385 0.0954730000 276849422 0 1261428736 -0.1299171001 -0.1097126305 -0.0107363714 186 1311867724.8093879223 0.1334135085 0.0253022590 0.1343840063 0.0058268653 0.1588290000 280043284 0 1265238016 -0.1296318322 -0.1091151312 -0.0092604011 187 1311867724.8454389572 0.1347709149 0.0258876529 0.1347709149 0.0058123028 0.0843730000 280045050 0 1265999872 -0.1303033978 -0.1103746817 -0.0104270149 188 1311867724.8771960735 0.1341211945 0.0264633632 0.1347709149 0.0057975238 0.0957190000 280046816 0 1266634752 -0.1305021495 -0.1095385253 -0.0102743711 189 1311867724.9093389511 0.1330594867 0.0270273639 0.1347709149 0.0057924265 0.1236800000 280048550 0 1267142656 -0.1308298856 -0.1089193523 -0.0093458379 190 1311867724.9453830719 0.1341559887 0.0275911988 0.1347709149 0.0057791587 0.0815600000 280050412 0 1267650560 -0.1309921592 -0.1104004681 -0.0098829567 191 1311867724.9773509502 0.1331500858 0.0281438631 0.1347709149 0.0057650429 0.0920020000 280052178 0 1268158464 -0.1311494410 -0.1093127206 -0.0098016281 192 1311867725.0094170570 0.1335496902 0.0286928518 0.1347709149 0.0057603444 0.1125030000 280053944 0 1268666368 -0.1315184385 -0.1097386181 -0.0091289012 193 1311867725.0453710556 0.1345652193 0.0292414133 0.1347709149 0.0057459231 0.1003390000 280055774 0 1269301248 -0.1317781359 -0.1111829728 -0.0091914078 194 1311867725.0771648884 0.1348805428 0.0297859449 0.1348805428 0.0057322952 0.1158440000 280057540 0 1269809152 -0.1320157796 -0.1115890667 -0.0097821001 195 1311867725.1093239784 0.1331142485 0.0303158336 0.1348805428 0.0057197727 0.1181650000 280059274 0 1270317056 -0.1318241656 -0.1102601811 -0.0080262804 196 1311867725.1454000473 0.1350778490 0.0308503337 0.1350778490 0.0057065863 0.1189780000 280061136 0 1270824960 -0.1324124336 -0.1125468090 -0.0089033032 197 1311867725.1774249077 0.1355579346 0.0313818443 0.1355579346 0.0056925322 0.1374330000 280062934 0 1271480320 -0.1324503124 -0.1135369763 -0.0086172987 198 1311867725.2095530033 0.1336607337 0.0318984044 0.1355579346 0.0056818106 0.1220980000 280064668 0 1271967744 -0.1326274574 -0.1118138805 -0.0070703984 199 1311867725.2453670502 0.1356374472 0.0324197061 0.1356374472 0.0056709533 0.1303580000 280066498 0 1272475648 -0.1331029087 -0.1141161770 -0.0081778448 200 1311867725.2774178982 0.1340664178 0.0329279397 0.1356374472 0.0056591257 0.1103330000 280068264 0 1272983552 -0.1331609488 -0.1127905920 -0.0076529407 201 1311867725.3092849255 0.1351826340 0.0334366695 0.1356374472 0.0056456728 0.1203400000 280069998 0 1273491456 -0.1336535513 -0.1142257750 -0.0067203948 202 1311867725.3453240395 0.1344765276 0.0339368668 0.1356374472 0.0056324485 0.1289130000 280071860 0 1274146816 -0.1335769594 -0.1135876849 -0.0072283475 203 1311867725.3772640228 0.1361406296 0.0344403336 0.1361406296 0.0056395327 0.1250910000 280073626 0 1274634240 -0.1344273239 -0.1144925505 -0.0084231086 204 1311867725.4093959332 0.1362607777 0.0349394534 0.1362607777 0.0057096573 0.1169160000 280075328 0 1275142144 -0.1342948228 -0.1143876910 -0.0075702006 205 1311867725.4453248978 0.1382135600 0.0354432296 0.1382135600 0.0057339761 0.1286550000 280077158 0 1275797504 -0.1349203587 -0.1168123633 -0.0081899874 206 1311867725.4772880077 0.1372474730 0.0359374249 0.1382135600 0.0057222774 0.1291530000 280078924 0 1276284928 -0.1349398792 -0.1157454327 -0.0076343389 207 1311867725.5093019009 0.1350548863 0.0364162533 0.1382135600 0.0057193520 0.3766240000 292392454 0 1289109504 -0.1352769285 -0.1134653091 -0.0064994604 208 1311867725.5453770161 0.1281073391 0.0368570758 0.1382135600 0.0057735170 0.0778170000 296052164 0 1293066240 -0.1210623980 -0.1140591949 0.0015046096 209 1311867725.5771839619 0.1299643070 0.0373025649 0.1382135600 0.0057753869 0.1900780000 299246026 0 1296728064 -0.1213882342 -0.1162922010 0.0011010304 210 1311867725.6094019413 0.1270664334 0.0377300119 0.1382135600 0.0057658384 0.0753910000 299247760 0 1297489920 -0.1217164770 -0.1132304221 0.0026543511 211 1311867725.6453518867 0.1279796809 0.0381577355 0.1382135600 0.0057612943 0.1062780000 299249622 0 1298124800 -0.1222555488 -0.1144783348 0.0029909399 212 1311867725.6771790981 0.1296793222 0.0385894411 0.1382135600 0.0057594602 0.1331780000 299251388 0 1298632704 -0.1226303428 -0.1160132214 0.0017915005 213 1311867725.7093379498 0.1287628412 0.0390127904 0.1382135600 0.0057472157 0.1151720000 299253122 0 1299140608 -0.1237816289 -0.1147089154 0.0021493768 214 1311867725.7453689575 0.1273034811 0.0394253637 0.1382135600 0.0057351547 0.0990640000 299254984 0 1299795968 -0.1236239448 -0.1136394218 0.0036159803 215 1311867725.7772219181 0.1309926063 0.0398512578 0.1382135600 0.0057321918 0.1271860000 299256750 0 1300283392 -0.1239592880 -0.1177215353 0.0022302344 216 1311867725.8093860149 0.1307152063 0.0402719243 0.1382135600 0.0057198371 0.1158370000 299258516 0 1300791296 -0.1251516342 -0.1171141639 0.0027281821 217 1311867725.8453550339 0.1311303526 0.0406906267 0.1382135600 0.0057107752 0.1146740000 299260346 0 1301299200 -0.1260058731 -0.1173092052 0.0023371428 218 1311867725.8772621155 0.1327472031 0.0411129046 0.1382135600 0.0057033246 0.1253130000 299262112 0 1301807104 -0.1258595735 -0.1194711328 0.0006097081 219 1311867725.9092769623 0.1308102161 0.0415224813 0.1382135600 0.0056928245 0.1184120000 299263814 0 1302462464 -0.1257726997 -0.1175062209 0.0028612069 220 1311867725.9454469681 0.1310790628 0.0419295567 0.1382135600 0.0056802082 0.1136360000 299265676 0 1302949888 -0.1262808889 -0.1178449094 0.0035983000 221 1311867725.9772861004 0.1327638477 0.0423405716 0.1382135600 0.0056715399 0.1283720000 299267442 0 1303457792 -0.1266526431 -0.1195218489 0.0021343317 222 1311867726.0092771053 0.1314660758 0.0427420378 0.1382135600 0.0056593429 0.1050490000 299269208 0 1304113152 -0.1271178871 -0.1180234700 0.0032682514 223 1311867726.0452640057 0.1302969605 0.0431346608 0.1382135600 0.0056492522 0.1122740000 299271006 0 1304600576 -0.1275609434 -0.1168818921 0.0045170276 224 1311867726.0773530006 0.1320632398 0.0435316634 0.1382135600 0.0056385037 0.1071060000 299272772 0 1305108480 -0.1286555678 -0.1185186431 0.0027289505 225 1311867726.1094279289 0.1317627728 0.0439238017 0.1382135600 0.0056265065 0.1132920000 299274538 0 1305616384 -0.1285771579 -0.1184540242 0.0040618270 226 1311867726.1454188824 0.1309329420 0.0443087978 0.1382135600 0.0056145855 0.1092990000 299276368 0 1306251264 -0.1282396019 -0.1181436330 0.0045881276 227 1311867726.1773889065 0.1349042952 0.0447078970 0.1382135600 0.0056131046 0.3573770000 311576982 0 1319202816 -0.1287532598 -0.1224437654 0.0034927970 228 1311867726.2094309330 0.1343357712 0.0451010017 0.1382135600 0.0056102287 0.0749600000 315236596 0 1323139072 -0.1294174045 -0.1215833724 0.0034758996 229 1311867726.2453389168 0.1332676411 0.0454860088 0.1382135600 0.0055998550 0.0778610000 318430490 0 1327357952 -0.1295859069 -0.1208666638 0.0048934598 230 1311867726.2772760391 0.1347265393 0.0458740111 0.1382135600 0.0055890237 0.0712120000 318432256 0 1327964160 -0.1305581778 -0.1224301606 0.0047056782 231 1311867726.3095979691 0.1361658424 0.0462648849 0.1382135600 0.0055800227 0.1475180000 318434022 0 1328599040 -0.1306993812 -0.1240295917 0.0037832754 232 1311867726.3454029560 0.1349452883 0.0466471280 0.1382135600 0.0055685050 0.0830830000 318435852 0 1329106944 -0.1307861805 -0.1228124201 0.0044111582 233 1311867726.3772161007 0.1348729581 0.0470257796 0.1382135600 0.0055565472 0.0841960000 318437618 0 1329614848 -0.1312232912 -0.1226383001 0.0045491238 234 1311867726.4093179703 0.1354607344 0.0474037068 0.1382135600 0.0055455847 0.0960920000 318439352 0 1330122752 -0.1315280944 -0.1229894012 0.0037688785 235 1311867726.4452810287 0.1359939277 0.0477806864 0.1382135600 0.0055341787 0.1025470000 318441214 0 1330647040 -0.1319826841 -0.1232369095 0.0036884327 236 1311867726.4774739742 0.1364207417 0.0481562799 0.1382135600 0.0055228800 0.0989160000 318443012 0 1331265536 -0.1318911761 -0.1236427128 0.0042655785 237 1311867726.5095689297 0.1361016482 0.0485273574 0.1382135600 0.0055115464 0.0929050000 318444746 0 1331773440 -0.1323610097 -0.1231113523 0.0046795686 238 1311867726.5453538895 0.1363364309 0.0488963031 0.1382135600 0.0055001129 0.0931210000 318446576 0 1332281344 -0.1325881779 -0.1233525798 0.0048244339 239 1311867726.5773959160 0.1372599602 0.0492660255 0.1382135600 0.0054974097 0.1116570000 318448342 0 1332805632 -0.1328021586 -0.1245517060 0.0044900924 240 1311867726.6093170643 0.1357909888 0.0496265462 0.1382135600 0.0054914210 0.0993440000 318450108 0 1333424128 -0.1328406483 -0.1228253916 0.0047979872 241 1311867726.6452519894 0.1355653405 0.0499831387 0.1382135600 0.0054806793 0.0929690000 318451938 0 1333932032 -0.1336427480 -0.1224776730 0.0052855299 242 1311867726.6773920059 0.1359872669 0.0503385276 0.1382135600 0.0054698128 0.0939070000 318453704 0 1334439936 -0.1334007680 -0.1232352331 0.0050127539 243 1311867726.7095000744 0.1357263178 0.0506899177 0.1382135600 0.0054590885 0.1026850000 318455470 0 1334947840 -0.1337153316 -0.1228635535 0.0047510448 244 1311867726.7453930378 0.1346182972 0.0510338865 0.1382135600 0.0054491329 0.0862460000 318457300 0 1335472128 -0.1332018822 -0.1220020354 0.0060244836 245 1311867726.7774538994 0.1345013380 0.0513745700 0.1382135600 0.0054383294 0.0836160000 318459066 0 1336090624 -0.1334050745 -0.1219634861 0.0059398199 246 1311867726.8095800877 0.1353216171 0.0517158181 0.1382135600 0.0054281210 0.0887480000 318460832 0 1336598528 -0.1330121458 -0.1230949089 0.0052053411 247 1311867726.8453249931 0.1347206980 0.0520518703 0.1382135600 0.0054211826 0.0832010000 318462662 0 1337106432 -0.1329821944 -0.1223231182 0.0052231490 248 1311867726.8773889542 0.1355533451 0.0523885698 0.1382135600 0.0054156987 0.0880730000 318464428 0 1337614336 -0.1326967627 -0.1233513281 0.0050260522 249 1311867726.9094569683 0.1359612942 0.0527242032 0.1382135600 0.0054049455 0.0935900000 318466162 0 1338269696 -0.1326725781 -0.1236282140 0.0046573784 250 1311867726.9454600811 0.1343717128 0.0530507932 0.1382135600 0.0054001420 0.0818450000 318468024 0 1338757120 -0.1327487528 -0.1219917610 0.0046794415 251 1311867726.9773380756 0.1343627274 0.0533747452 0.1382135600 0.0053899862 0.0908740000 318469790 0 1339265024 -0.1325229406 -0.1220334023 0.0049683452 252 1311867727.0096790791 0.1347634941 0.0536977164 0.1382135600 0.0053795287 0.0903740000 318471524 0 1339772928 -0.1323244423 -0.1224610656 0.0048755477 253 1311867727.0456500053 0.1337046027 0.0540139491 0.1382135600 0.0053697805 0.0791360000 318473354 0 1340297216 -0.1319734305 -0.1215098575 0.0051794136 254 1311867727.0772669315 0.1331175119 0.0543253805 0.1382135600 0.0053597132 0.0717570000 318475152 0 1340936192 -0.1318185627 -0.1209329888 0.0049527888 255 1311867727.1094319820 0.1325829029 0.0546322727 0.1382135600 0.0053509728 0.0939100000 318476886 0 1341423616 -0.1314525604 -0.1204532459 0.0052983905 256 1311867727.1452639103 0.1322930157 0.0549356350 0.1382135600 0.0053407338 0.0898720000 318478652 0 1341931520 -0.1311954558 -0.1201093048 0.0049204733 257 1311867727.1773788929 0.1324372143 0.0552371976 0.1382135600 0.0053306616 0.0843060000 318501954 0 1342439424 -0.1309986711 -0.1202094778 0.0040583829 258 1311867727.2096951008 0.1340435594 0.0555426486 0.1382135600 0.0053266833 0.0679460000 318545672 0 1343074304 -0.1304277331 -0.1216306835 0.0028347573 259 1311867727.2453041077 0.1331582516 0.0558423227 0.1382135600 0.0053178628 0.0768130000 318547470 0 1343598592 -0.1301350445 -0.1205871999 0.0041330680 260 1311867727.2773349285 0.1325451881 0.0561373338 0.1382135600 0.0053086124 0.0847370000 318549268 0 1344217088 -0.1295862049 -0.1200149655 0.0033335935 261 1311867727.3093569279 0.1316617578 0.0564266994 0.1382135600 0.0053006319 0.1192310000 318551002 0 1344724992 -0.1294607520 -0.1188762262 0.0037122502 262 1311867727.3453900814 0.1306025833 0.0567098134 0.1382135600 0.0052939676 0.1074230000 318552864 0 1345232896 -0.1287562549 -0.1180301160 0.0047081495 263 1311867727.3774650097 0.1318370402 0.0569954683 0.1382135600 0.0052898642 0.1136640000 318554566 0 1345888256 -0.1283890158 -0.1189680323 0.0027440519 264 1311867727.4095671177 0.1317001432 0.0572784405 0.1382135600 0.0052845899 0.1124740000 318556300 0 1346375680 -0.1280733794 -0.1184419543 0.0025513978 265 1311867727.4455111027 0.1313442290 0.0575579341 0.1382135600 0.0052804139 0.1031700000 318558162 0 1346883584 -0.1273864508 -0.1181936339 0.0030835292 266 1311867727.4774019718 0.1330266446 0.0578416510 0.1382135600 0.0052729835 0.1048260000 318559928 0 1347391488 -0.1268484443 -0.1198077798 0.0010730205 267 1311867727.5093801022 0.1318045110 0.0581186655 0.1382135600 0.0052634341 0.1095330000 318561662 0 1347899392 -0.1263487339 -0.1184236184 0.0014302206 268 1311867727.5455400944 0.1305155307 0.0583888030 0.1382135600 0.0052645153 0.0998790000 318563492 0 1348554752 -0.1261438727 -0.1168071404 0.0024842210 269 1311867727.5773611069 0.1295774132 0.0586534447 0.1382135600 0.0052567574 0.1072340000 318565258 0 1349042176 -0.1259698868 -0.1159729213 0.0026395693 270 1311867727.6094770432 0.1297701448 0.0589168399 0.1382135600 0.0052482397 0.1059520000 318567024 0 1349550080 -0.1255337894 -0.1164218783 0.0020217120 271 1311867727.6453289986 0.1291866750 0.0591761382 0.1382135600 0.0052426617 0.1040710000 318568854 0 1350057984 -0.1252910644 -0.1162821352 0.0018083663 272 1311867727.6773209572 0.1290342212 0.0594329694 0.1382135600 0.0052330921 0.0964330000 318570556 0 1350713344 -0.1248453930 -0.1165292189 0.0016804571 273 1311867727.7094900608 0.1302865297 0.0596925062 0.1382135600 0.0052250416 0.1089360000 318572290 0 1351200768 -0.1252350807 -0.1179585159 0.0011233096 274 1311867727.7455639839 0.1295679212 0.0599475260 0.1382135600 0.0052190096 0.1016500000 318574120 0 1351708672 -0.1255313903 -0.1173450425 0.0022060056 275 1311867727.7773749828 0.1317315847 0.0602085589 0.1382135600 0.0052135321 0.1069340000 318575886 0 1352208384 -0.1256194562 -0.1197110415 0.0007918398 276 1311867727.8096098900 0.1326887161 0.0604711682 0.1382135600 0.0052052324 0.0859070000 318577652 0 1352716288 -0.1256971061 -0.1205950454 -0.0000657452 277 1311867727.8454129696 0.1319267154 0.0607291305 0.1382135600 0.0051964914 0.0895240000 318579482 0 1353371648 -0.1253353357 -0.1197760925 0.0005140678 278 1311867727.8773849010 0.1324325353 0.0609870564 0.1382135600 0.0051872653 0.0968860000 318581280 0 1353859072 -0.1255209744 -0.1199284121 0.0000870667 279 1311867727.9093821049 0.1315742880 0.0612400572 0.1382135600 0.0051784838 0.1016200000 318583046 0 1354366976 -0.1250491440 -0.1188231483 -0.0012022122 280 1311867727.9453790188 0.1318018138 0.0614920635 0.1382135600 0.0051694203 0.0923180000 318584844 0 1354874880 -0.1249502748 -0.1187449768 -0.0007637795 281 1311867727.9773490429 0.1323447675 0.0617442083 0.1382135600 0.0051606387 0.0927160000 318586642 0 1355530240 -0.1244974956 -0.1192149967 -0.0006267970 282 1311867728.0096199512 0.1318060905 0.0619926547 0.1382135600 0.0051565050 0.1038960000 318588376 0 1356017664 -0.1245773807 -0.1186151505 -0.0008554404 283 1311867728.0455679893 0.1314897090 0.0622382274 0.1382135600 0.0051473956 0.0924090000 318590206 0 1356525568 -0.1241347939 -0.1180186346 -0.0017387620 284 1311867728.0775840282 0.1320977956 0.0624842118 0.1382135600 0.0051394058 0.0991640000 318592004 0 1357033472 -0.1237056702 -0.1186378896 -0.0016833126 285 1311867728.1093900204 0.1323995143 0.0627295286 0.1382135600 0.0051347896 0.0955700000 318593738 0 1357541376 -0.1232600063 -0.1185357571 -0.0022998259 286 1311867728.1453619003 0.1317941546 0.0629710133 0.1382135600 0.0051274111 0.1017740000 318595568 0 1358196736 -0.1230117530 -0.1175762862 -0.0028204527 287 1311867728.1773409843 0.1323725879 0.0632128306 0.1382135600 0.0051188517 0.0930470000 318597366 0 1358684160 -0.1223082617 -0.1182873547 -0.0034777354 288 1311867728.2095170021 0.1330748796 0.0634554072 0.1382135600 0.0051111763 0.0934070000 318599100 0 1359192064 -0.1224454194 -0.1186614856 -0.0029620812 289 1311867728.2453820705 0.1330843270 0.0636963377 0.1382135600 0.0051023583 0.0981200000 318600930 0 1359847424 -0.1220993772 -0.1184074804 -0.0026258565 290 1311867728.2773799896 0.1326678693 0.0639341706 0.1382135600 0.0050946642 0.0942600000 318602728 0 1360334848 -0.1220669225 -0.1176885962 -0.0032647452 291 1311867728.3094980717 0.1334264874 0.0641729758 0.1382135600 0.0050876352 0.0956390000 318604462 0 1360842752 -0.1211316809 -0.1187075749 -0.0049217846 292 1311867728.3455080986 0.1320628971 0.0644054755 0.1382135600 0.0050887311 0.1002060000 318606292 0 1361350656 -0.1213129908 -0.1172546744 -0.0039449418 293 1311867728.3773488998 0.1326004714 0.0646382230 0.1382135600 0.0050965671 0.0897720000 318608090 0 1361874944 -0.1205625236 -0.1179353446 -0.0049443054 294 1311867728.4095909595 0.1332702786 0.0648716653 0.1382135600 0.0050952903 0.0941280000 318609824 0 1362493440 -0.1202583238 -0.1183295324 -0.0045769061 295 1311867728.4456090927 0.1333366930 0.0651037502 0.1382135600 0.0050912887 0.0896170000 318611654 0 1363001344 -0.1203793362 -0.1180548072 -0.0056790612 296 1311867728.4774570465 0.1320182532 0.0653298127 0.1382135600 0.0050843135 0.0917140000 318613420 0 1363517440 -0.1201625466 -0.1166507080 -0.0064598969 297 1311867728.5095710754 0.1331645697 0.0655582125 0.1382135600 0.0050786318 0.0936490000 318615186 0 1364025344 -0.1200937852 -0.1180035174 -0.0055156141 298 1311867728.5455050468 0.1338742822 0.0657874611 0.1382135600 0.0050707786 0.1136060000 318617016 0 1364680704 -0.1205394119 -0.1184418797 -0.0059692990 299 1311867728.5774528980 0.1337411404 0.0660147309 0.1382135600 0.0050626668 0.0989590000 318618814 0 1365168128 -0.1202386320 -0.1183664203 -0.0054727532 300 1311867728.6095349789 0.1335543245 0.0662398629 0.1382135600 0.0050543624 0.0935970000 318620548 0 1365676032 -0.1199693680 -0.1181984842 -0.0068736291 301 1311867728.6454720497 0.1333123147 0.0664626950 0.1382135600 0.0050464774 0.0896890000 318622378 0 1366183936 -0.1198101938 -0.1177890524 -0.0071448535 302 1311867728.6776139736 0.1328542382 0.0666825345 0.1382135600 0.0050392594 0.1012100000 318624144 0 1366691840 -0.1199179813 -0.1170644909 -0.0061318059 303 1311867728.7094600201 0.1332082450 0.0669020913 0.1382135600 0.0050384588 0.1029400000 318625910 0 1367326720 -0.1199961081 -0.1176915839 -0.0061114584 304 1311867728.7454140186 0.1342013776 0.0671234705 0.1382135600 0.0050305536 0.0981600000 318627740 0 1367834624 -0.1196128428 -0.1188095063 -0.0063556945 305 1311867728.7775039673 0.1338131279 0.0673421252 0.1382135600 0.0050238527 0.0921410000 318629538 0 1368342528 -0.1196204126 -0.1183215231 -0.0057474300 306 1311867728.8095550537 0.1333090663 0.0675577034 0.1382135600 0.0050161783 0.1077720000 318631272 0 1368850432 -0.1195513159 -0.1177922115 -0.0058521270 307 1311867728.8454689980 0.1330657899 0.0677710848 0.1382135600 0.0050116839 0.1032500000 318633102 0 1369374720 -0.1191294268 -0.1173782051 -0.0066733467 308 1311867728.8774468899 0.1339337379 0.0679858986 0.1382135600 0.0050041260 0.0970680000 318634900 0 1369993216 -0.1191753149 -0.1181864664 -0.0065581705 309 1311867728.9095330238 0.1338388324 0.0681990149 0.1382135600 0.0049962879 0.0947020000 318636634 0 1370501120 -0.1191423014 -0.1179592162 -0.0068797437 310 1311867728.9456429482 0.1336316317 0.0684100878 0.1382135600 0.0049885782 0.1002880000 318638464 0 1371009024 -0.1184098721 -0.1178068370 -0.0076108146 311 1311867728.9774780273 0.1325539500 0.0686163382 0.1382135600 0.0049861378 0.1036850000 318640262 0 1371643904 -0.1185113564 -0.1164438948 -0.0076160454 312 1311867729.0094010830 0.1337041408 0.0688249529 0.1382135600 0.0049872058 0.1084720000 318641996 0 1372151808 -0.1178736761 -0.1177557111 -0.0077575594 313 1311867729.0454490185 0.1337309927 0.0690323205 0.1382135600 0.0049832040 0.1003640000 318643826 0 1372659712 -0.1175818071 -0.1176034883 -0.0083928443 314 1311867729.0774519444 0.1336917728 0.0692382423 0.1382135600 0.0049752783 0.1009310000 318645624 0 1373184000 -0.1176529154 -0.1173523366 -0.0084050018 315 1311867729.1096370220 0.1346324086 0.0694458428 0.1382135600 0.0049764179 0.1122220000 318647358 0 1373802496 -0.1176678985 -0.1184388250 -0.0080726417 316 1311867729.1455519199 0.1340654194 0.0696503352 0.1382135600 0.0049696895 0.1011220000 318649188 0 1374310400 -0.1176767573 -0.1177713200 -0.0091663422 317 1311867729.1775870323 0.1340627074 0.0698535288 0.1382135600 0.0049984530 0.1007460000 318650986 0 1374818304 -0.1181361824 -0.1177330613 -0.0085689761 318 1311867729.2097380161 0.1336541027 0.0700541595 0.1382135600 0.0050073696 0.1040180000 318652720 0 1375473664 -0.1181316897 -0.1176326275 -0.0084442319 319 1311867729.2454650402 0.1329348385 0.0702512776 0.1382135600 0.0050472809 0.0989180000 318654550 0 1375961088 -0.1183153987 -0.1163201332 -0.0074880091 320 1311867729.2776589394 0.1319655031 0.0704441346 0.1382135600 0.0050417430 0.1044650000 318656348 0 1376468992 -0.1185903773 -0.1152400300 -0.0080485409 321 1311867729.3094971180 0.1313455254 0.0706338585 0.1382135600 0.0050399096 0.0999590000 318658114 0 1376976896 -0.1178911179 -0.1149865463 -0.0079942495 322 1311867729.3456869125 0.1304714233 0.0708196895 0.1382135600 0.0050350385 0.1008420000 318659912 0 1377484800 -0.1173502356 -0.1143627688 -0.0072585503 323 1311867729.3774700165 0.1304275990 0.0710042341 0.1382135600 0.0050484238 0.0903240000 318661710 0 1378009088 -0.1165302321 -0.1139865965 -0.0097230775 324 1311867729.4097099304 0.1300920397 0.0711866039 0.1382135600 0.0050419235 0.1054680000 318663444 0 1378627584 -0.1161464453 -0.1135164648 -0.0101330169 325 1311867729.4455790520 0.1300738305 0.0713677953 0.1382135600 0.0050362474 0.0976070000 318665274 0 1379135488 -0.1154054627 -0.1134829223 -0.0083949780 326 1311867729.4778299332 0.1291490346 0.0715450384 0.1382135600 0.0050479305 0.0890300000 318667072 0 1379643392 -0.1145006493 -0.1130487472 -0.0102464929 327 1311867729.5097289085 0.1283291578 0.0717186901 0.1382135600 0.0050408561 0.0916560000 318668838 0 1380151296 -0.1141914502 -0.1122010127 -0.0104453685 328 1311867729.5456240177 0.1261159331 0.0718845354 0.1382135600 0.0050355699 0.0934040000 318670636 0 1380675584 -0.1141005307 -0.1097453386 -0.0116842128 329 1311867729.5778779984 0.1260514706 0.0720491765 0.1382135600 0.0050373707 0.0923740000 318672402 0 1381294080 -0.1136071533 -0.1102149710 -0.0100559555 330 1311867729.6095120907 0.1270208657 0.0722157574 0.1382135600 0.0050380345 0.1005120000 318674168 0 1381801984 -0.1135201752 -0.1116264462 -0.0095375394 331 1311867729.6454730034 0.1250829101 0.0723754769 0.1382135600 0.0050323315 0.0940190000 318675998 0 1382457344 -0.1130418405 -0.1099417806 -0.0100347782 332 1311867729.6776039600 0.1242180169 0.0725316291 0.1382135600 0.0050255013 0.0952780000 318677764 0 1382944768 -0.1134100780 -0.1088931859 -0.0108797261 333 1311867729.7095260620 0.1236170530 0.0726850388 0.1382135600 0.0050183161 0.0954690000 318679466 0 1383452672 -0.1126035303 -0.1088050604 -0.0107546523 334 1311867729.7457098961 0.1232468933 0.0728364216 0.1382135600 0.0050119158 0.1058360000 318681328 0 1383960576 -0.1124267951 -0.1086292565 -0.0088593801 335 1311867729.7775330544 0.1216823682 0.0729822304 0.1382135600 0.0050082267 0.0991510000 318683030 0 1384468480 -0.1123490185 -0.1069727391 -0.0079287672 336 1311867729.8096089363 0.1218452156 0.0731276560 0.1382135600 0.0050022785 0.1014970000 318684796 0 1384992768 -0.1119810790 -0.1072551757 -0.0092301415 337 1311867729.8455319405 0.1220383048 0.0732727914 0.1382135600 0.0049959250 0.0957180000 318686594 0 1385631744 -0.1111817434 -0.1077347025 -0.0107945651 338 1311867729.8776299953 0.1211334690 0.0734143911 0.1382135600 0.0049901675 0.0996700000 318688360 0 1386119168 -0.1110627651 -0.1068137065 -0.0087571898 339 1311867729.9097530842 0.1210240647 0.0735548326 0.1382135600 0.0049847409 0.0965910000 318690126 0 1386627072 -0.1109659150 -0.1067175642 -0.0106260609 340 1311867729.9454579353 0.1210208535 0.0736944385 0.1382135600 0.0049789812 0.1067800000 318691924 0 1387134976 -0.1106405407 -0.1067596972 -0.0103747742 341 1311867729.9775550365 0.1200087592 0.0738302576 0.1382135600 0.0049732348 0.0985030000 318693722 0 1387659264 -0.1104079857 -0.1057457328 -0.0092603816 342 1311867730.0098500252 0.1195542291 0.0739639535 0.1382135600 0.0049673693 0.1020250000 318695456 0 1388277760 -0.1106065512 -0.1050486192 -0.0080187125 343 1311867730.0455420017 0.1191168129 0.0740955944 0.1382135600 0.0049614257 0.0977540000 318697318 0 1388785664 -0.1099822670 -0.1046122089 -0.0110904798 344 1311867730.0778129101 0.1189788580 0.0742260691 0.1382135600 0.0049544379 0.1094620000 318699116 0 1389293568 -0.1097582579 -0.1044039130 -0.0106704868 345 1311867730.1098239422 0.1199216247 0.0743585199 0.1382135600 0.0049475955 0.1028150000 318700850 0 1389801472 -0.1098210663 -0.1053966433 -0.0090670725 346 1311867730.1454300880 0.1189978123 0.0744875352 0.1382135600 0.0049413849 0.0947620000 318702648 0 1390325760 -0.1093571857 -0.1041555703 -0.0108982194 347 1311867730.1775400639 0.1190907136 0.0746160747 0.1382135600 0.0049346289 0.1041000000 318704446 0 1390944256 -0.1092571393 -0.1041178107 -0.0098733967 348 1311867730.2094900608 0.1187952757 0.0747430264 0.1382135600 0.0049293602 0.1015820000 318706180 0 1391452160 -0.1090638489 -0.1037201658 -0.0097728418 349 1311867730.2456400394 0.1185124591 0.0748684402 0.1382135600 0.0049226649 0.1054130000 318708042 0 1391960064 -0.1086759120 -0.1033614427 -0.0103269676 350 1311867730.2777209282 0.1190674007 0.0749947230 0.1382135600 0.0049161603 0.1053930000 318709808 0 1392615424 -0.1084495187 -0.1037796587 -0.0108832642 351 1311867730.3096349239 0.1187503189 0.0751193828 0.1382135600 0.0049104058 0.1046760000 318711574 0 1393102848 -0.1083366126 -0.1032437235 -0.0104449270 352 1311867730.3455030918 0.1188947782 0.0752437447 0.1382135600 0.0049051095 0.1042560000 318713372 0 1393610752 -0.1082672998 -0.1031471565 -0.0101322290 353 1311867730.3779098988 0.1181953028 0.0753654205 0.1382135600 0.0048986917 0.0951840000 318715202 0 1394118656 -0.1079536155 -0.1021631137 -0.0103296135 354 1311867730.4096369743 0.1196321025 0.0754904676 0.1382135600 0.0048932145 0.1051450000 318716904 0 1394626560 -0.1077295542 -0.1035884917 -0.0114002097 355 1311867730.4455609322 0.1198849380 0.0756155225 0.1382135600 0.0048876838 0.1036010000 318718734 0 1395261440 -0.1076558754 -0.1034284011 -0.0109012881 356 1311867730.4776659012 0.1186422408 0.0757363840 0.1382135600 0.0048818658 0.1006300000 318720532 0 1395769344 -0.1077099070 -0.1015551314 -0.0104327267 357 1311867730.5096940994 0.1198026240 0.0758598189 0.1382135600 0.0048754558 0.1047700000 318722266 0 1396404224 -0.1073734090 -0.1026990488 -0.0103682317 358 1311867730.5457289219 0.1191702262 0.0759807977 0.1382135600 0.0048686971 0.1036930000 318724096 0 1396912128 -0.1072398946 -0.1015391275 -0.0100105675 359 1311867730.5776000023 0.1194583401 0.0761019050 0.1382135600 0.0048620173 0.1054330000 318725862 0 1397420032 -0.1069328263 -0.1018150225 -0.0095688412 360 1311867730.6094939709 0.1192333996 0.0762217148 0.1382135600 0.0048556635 0.1008750000 318727596 0 1397944320 -0.1069426015 -0.1012189239 -0.0097754486 361 1311867730.6456940174 0.1175022721 0.0763360653 0.1382135600 0.0048517150 0.1046170000 318729426 0 1398562816 -0.1063032448 -0.0992696956 -0.0100018671 362 1311867730.6776220798 0.1183422729 0.0764521046 0.1382135600 0.0048452844 0.1024330000 318731192 0 1399070720 -0.1059517264 -0.1001827791 -0.0100260377 363 1311867730.7097771168 0.1178979129 0.0765662804 0.1382135600 0.0048416648 0.1012830000 318732958 0 1399578624 -0.1055071875 -0.0996875912 -0.0101650078 364 1311867730.7456669807 0.1181537360 0.0766805316 0.1382135600 0.0048354508 0.1053330000 318734788 0 1400233984 -0.1050249413 -0.0996830687 -0.0112350760 365 1311867730.7776470184 0.1200292483 0.0767992952 0.1382135600 0.0048304836 0.1027420000 318736554 0 1400721408 -0.1047815830 -0.1010796949 -0.0125413900 366 1311867730.8097639084 0.1184574515 0.0769131153 0.1382135600 0.0048255918 0.0911620000 318738320 0 1401229312 -0.1037157699 -0.0992786288 -0.0107239885 367 1311867730.8457670212 0.1195752919 0.0770293610 0.1382135600 0.0048205193 0.0985900000 318740150 0 1401737216 -0.1035328060 -0.0996088013 -0.0123469103 368 1311867730.8774909973 0.1194082871 0.0771445211 0.1382135600 0.0048143373 0.0987090000 318741852 0 1402261504 -0.1029919907 -0.0987351909 -0.0130835222 369 1311867730.9097859859 0.1193106249 0.0772587924 0.1382135600 0.0048086875 0.1057460000 318743586 0 1402880000 -0.1023401245 -0.0980108008 -0.0137263956 370 1311867730.9455358982 0.1199920923 0.0773742878 0.1382135600 0.0048050354 0.1043800000 318745416 0 1403387904 -0.1016321778 -0.0980471522 -0.0151714599 371 1311867730.9775540829 0.1187081337 0.0774856998 0.1382135600 0.0047999445 0.1072020000 318747214 0 1403895808 -0.1009625196 -0.0963826105 -0.0136475246 372 1311867731.0096011162 0.1179818958 0.0775945606 0.1382135600 0.0047951671 0.1067490000 318748948 0 1404403712 -0.1004571617 -0.0955448002 -0.0125616463 373 1311867731.0456199646 0.1179456189 0.0777027403 0.1382135600 0.0047891784 0.1088830000 318750778 0 1405059072 -0.0996724367 -0.0951355845 -0.0145026445 374 1311867731.0775210857 0.1171318889 0.0778081659 0.1382135600 0.0047833715 0.1099470000 318752544 0 1405546496 -0.0991498679 -0.0943543389 -0.0120520815 375 1311867731.1096100807 0.1163880453 0.0779110456 0.1382135600 0.0047780613 0.1016190000 318754310 0 1406054400 -0.0972077623 -0.0940842479 -0.0130938161 376 1311867731.1456789970 0.1186458617 0.0780193828 0.1382135600 0.0047758439 0.1060800000 318756140 0 1406709760 -0.0981370732 -0.0954703018 -0.0138997650 377 1311867731.1777400970 0.1148424894 0.0781170569 0.1382135600 0.0047804917 0.0994060000 318757906 0 1407197184 -0.0962322429 -0.0917297825 -0.0134266904 378 1311867731.2096519470 0.1149311960 0.0782144488 0.1382135600 0.0047745606 0.1090690000 318759640 0 1407705088 -0.0963587165 -0.0913789719 -0.0126005132 379 1311867731.2455980778 0.1126311347 0.0783052580 0.1382135600 0.0047706194 0.1021490000 318761470 0 1408212992 -0.0944231600 -0.0893508345 -0.0123253493 380 1311867731.2775490284 0.1124302596 0.0783950606 0.1382135600 0.0047659850 0.1151040000 318763268 0 1408868352 -0.0951664820 -0.0883451626 -0.0111601753 381 1311867731.3097438812 0.1106155291 0.0784796287 0.1382135600 0.0047665009 0.1130570000 318765002 0 1409355776 -0.0940090045 -0.0866576955 -0.0103381909 382 1311867731.3457999229 0.1090733409 0.0785597170 0.1382135600 0.0047604072 0.4112650000 331068988 0 1422172160 -0.0922822654 -0.0860342383 -0.0097012017 383 1311867731.3777329922 0.1093206257 0.0786400327 0.1382135600 0.0047552289 0.0747330000 334728634 0 1426128896 -0.0923259705 -0.0865564942 -0.0087227179 384 1311867731.4096930027 0.1094430909 0.0787202490 0.1382135600 0.0047512168 0.0733340000 337922464 0 1429798912 -0.0917834118 -0.0872193277 -0.0082511427 385 1311867731.4455540180 0.1092951819 0.0787996644 0.1382135600 0.0047461879 0.0722730000 337924294 0 1430687744 -0.0914311931 -0.0873990357 -0.0078204237 386 1311867731.4776530266 0.1085292771 0.0788766841 0.1382135600 0.0047414396 0.0738190000 337926092 0 1431195648 -0.0912002698 -0.0864259750 -0.0092442622 387 1311867731.5096719265 0.1085074767 0.0789532495 0.1382135600 0.0047417992 0.1132370000 337927826 0 1431719936 -0.0904978290 -0.0866536424 -0.0096167885 388 1311867731.5457088947 0.1086402535 0.0790297624 0.1382135600 0.0047435366 0.1342390000 337929656 0 1432338432 -0.0900909379 -0.0866833255 -0.0098585319 389 1311867731.5777149200 0.1115247905 0.0791132971 0.1382135600 0.0047401841 0.1585240000 337931422 0 1432846336 -0.0901366994 -0.0895153508 -0.0115301274 390 1311867731.6097021103 0.1105129197 0.0791938090 0.1382135600 0.0047653725 0.1410200000 337933156 0 1433354240 -0.0895277560 -0.0886729881 -0.0107987272 391 1311867731.6456029415 0.1096779481 0.0792717736 0.1382135600 0.0047732352 0.1407950000 337934986 0 1433989120 -0.0887525901 -0.0874213278 -0.0105483243 392 1311867731.6776618958 0.1088420525 0.0793472079 0.1382135600 0.0047677226 0.1468460000 337936784 0 1434497024 -0.0882556885 -0.0862460434 -0.0107091200 393 1311867731.7099699974 0.1040743440 0.0794101269 0.1382135600 0.0047658968 0.1575900000 337938550 0 1435004928 -0.0862030312 -0.0817812830 -0.0088103246 394 1311867731.7457799911 0.1069100723 0.0794799237 0.1382135600 0.0047656083 0.1442520000 337940380 0 1435512832 -0.0864248723 -0.0848070905 -0.0091064852 395 1311867731.7777240276 0.1075025350 0.0795508670 0.1382135600 0.0047596991 0.1417690000 337942146 0 1436037120 -0.0861243606 -0.0852487236 -0.0101907644 396 1311867731.8099861145 0.1045075655 0.0796138890 0.1382135600 0.0047630644 0.1427870000 337943912 0 1436655616 -0.0855587944 -0.0821355581 -0.0077628624 397 1311867731.8457460403 0.1043594629 0.0796762204 0.1382135600 0.0047576050 0.1422890000 337945742 0 1437163520 -0.0854387358 -0.0820031166 -0.0082479650 398 1311867731.8775570393 0.1040754244 0.0797375249 0.1382135600 0.0047516501 0.1391160000 337947508 0 1437671424 -0.0844612867 -0.0824398547 -0.0081354892 399 1311867731.9097321033 0.1039749607 0.0797982704 0.1382135600 0.0047475059 0.1366480000 337949242 0 1438179328 -0.0844238997 -0.0824117884 -0.0081765903 400 1311867731.9456660748 0.1027258709 0.0798555894 0.1382135600 0.0047437618 0.1378730000 337951072 0 1438814208 -0.0843526348 -0.0809869096 -0.0082313213 401 1311867731.9777350426 0.1047168449 0.0799175875 0.1382135600 0.0047390766 0.1357830000 337952838 0 1439322112 -0.0847603604 -0.0829219669 -0.0104294699 402 1311867732.0095889568 0.1025801152 0.0799739620 0.1382135600 0.0047359001 0.1282600000 337954572 0 1439830016 -0.0832301974 -0.0815558583 -0.0080950474 403 1311867732.0458478928 0.1016644686 0.0800277846 0.1382135600 0.0047326497 0.1306560000 337956434 0 1440337920 -0.0832763016 -0.0803673491 -0.0068157222 404 1311867732.0776910782 0.1048649326 0.0800892626 0.1382135600 0.0047433289 0.1270680000 337958200 0 1440862208 -0.0842687488 -0.0829858407 -0.0098016113 405 1311867732.1098160744 0.1018320471 0.0801429485 0.1382135600 0.0047487054 0.1224480000 337959934 0 1441480704 -0.0829235241 -0.0804593638 -0.0071987621 406 1311867732.1455659866 0.1034610346 0.0802003822 0.1382135600 0.0047554716 0.1204030000 337961796 0 1441988608 -0.0833561644 -0.0823489502 -0.0095969504 407 1311867732.1777989864 0.1057670638 0.0802631996 0.1382135600 0.0047521870 0.1223450000 337963562 0 1442496512 -0.0845429301 -0.0838336200 -0.0121501694 408 1311867732.2096500397 0.1035412252 0.0803202536 0.1382135600 0.0047509669 0.1187990000 337965328 0 1443151872 -0.0828409940 -0.0825361237 -0.0091762664 409 1311867732.2458050251 0.1052008644 0.0803810864 0.1382135600 0.0047627396 0.1221000000 337967158 0 1443639296 -0.0840156004 -0.0831204876 -0.0122842547 410 1311867732.2778968811 0.1063512340 0.0804444282 0.1382135600 0.0047652495 0.1169070000 337968956 0 1444147200 -0.0831502452 -0.0845926031 -0.0126237208 411 1311867732.3097560406 0.1041929200 0.0805022105 0.1382135600 0.0047818304 0.1144520000 337970658 0 1444655104 -0.0815583691 -0.0834582075 -0.0100062266 412 1311867732.3456790447 0.1047048122 0.0805609546 0.1382135600 0.0047838331 0.1219660000 337972488 0 1445163008 -0.0833808556 -0.0817403942 -0.0139915654 413 1311867732.3777399063 0.1042643338 0.0806183478 0.1382135600 0.0047787895 0.1175060000 337974286 0 1445797888 -0.0812957808 -0.0827814192 -0.0129786693 414 1311867732.4096240997 0.1057732701 0.0806791085 0.1382135600 0.0047744733 0.1057790000 337976052 0 1446305792 -0.0811325535 -0.0849651918 -0.0113780880 415 1311867732.4456939697 0.1045101583 0.0807365327 0.1382135600 0.0047887315 0.1126160000 337977850 0 1446961152 -0.0817021504 -0.0820432231 -0.0138836000 416 1311867732.4777801037 0.1045067534 0.0807936727 0.1382135600 0.0047833413 0.1112580000 337979648 0 1447448576 -0.0806027725 -0.0827737451 -0.0126393093 417 1311867732.5097730160 0.1037190035 0.0808486495 0.1382135600 0.0047851543 0.1109530000 337981414 0 1447956480 -0.0805815756 -0.0811136514 -0.0128717050 418 1311867732.5458118916 0.1045044586 0.0809052423 0.1382135600 0.0047812190 0.1111040000 337983212 0 1448464384 -0.0802698806 -0.0816202015 -0.0150152650 419 1311867732.5782780647 0.1054525748 0.0809638278 0.1382135600 0.0047757282 0.1116980000 337984978 0 1448972288 -0.0800764486 -0.0822971836 -0.0162973497 420 1311867732.6098470688 0.1049966738 0.0810210489 0.1382135600 0.0047710902 0.1088120000 337986776 0 1449627648 -0.0789399520 -0.0826036334 -0.0142760817 421 1311867732.6457130909 0.1039268970 0.0810754571 0.1382135600 0.0047687599 0.1131220000 337988574 0 1450115072 -0.0783821568 -0.0812386200 -0.0147502320 422 1311867732.6777091026 0.1049083993 0.0811319333 0.1382135600 0.0047651468 0.4204120000 350290296 0 1462956032 -0.0793642402 -0.0807570219 -0.0186015014 423 1311867732.7097430229 0.1093398258 0.0811986186 0.1382135600 0.0047719631 0.0865440000 353949878 0 1466875904 -0.0797661692 -0.0859364271 -0.0193152484 424 1311867732.7456200123 0.1102773696 0.0812672005 0.1382135600 0.0047672381 0.0978440000 357143804 0 1470705664 -0.0800280347 -0.0867765844 -0.0185944904 425 1311867732.7777669430 0.1103132814 0.0813355443 0.1382135600 0.0047627156 0.0686500000 357145570 0 1471447040 -0.0800307095 -0.0860369727 -0.0216600876 426 1311867732.8099739552 0.1102839261 0.0814034982 0.1382135600 0.0047575776 0.0655950000 357147336 0 1472081920 -0.0795771703 -0.0862670690 -0.0204859357 427 1311867732.8458719254 0.1110611334 0.0814729540 0.1382135600 0.0047525563 0.0670430000 357149166 0 1472589824 -0.0798157379 -0.0868440345 -0.0205001179 428 1311867732.8777840137 0.1111006439 0.0815421776 0.1382135600 0.0047479903 0.0623420000 357150932 0 1473097728 -0.0799967572 -0.0862971544 -0.0219078939 429 1311867732.9097430706 0.1109580845 0.0816107461 0.1382135600 0.0047436419 0.0679660000 357152698 0 1473622016 -0.0797772035 -0.0855805352 -0.0233776476 430 1311867732.9457380772 0.1095846593 0.0816758018 0.1382135600 0.0047389694 0.1569980000 357154528 0 1474240512 -0.0780893192 -0.0855296701 -0.0194429196 431 1311867732.9777500629 0.1103729084 0.0817423844 0.1382135600 0.0047345674 0.1382170000 357156294 0 1474748416 -0.0784531981 -0.0859867483 -0.0204453990 432 1311867733.0097920895 0.1102712080 0.0818084233 0.1382135600 0.0047299325 0.1362890000 357158092 0 1475256320 -0.0778639317 -0.0858604386 -0.0220386758 433 1311867733.0458159447 0.1097928211 0.0818730524 0.1382135600 0.0047270730 0.1458060000 357159890 0 1475764224 -0.0785979480 -0.0851727128 -0.0168157406 434 1311867733.0778040886 0.1090145186 0.0819355904 0.1382135600 0.0047219352 0.1516490000 357161688 0 1476272128 -0.0778689981 -0.0845434591 -0.0184859075 435 1311867733.1097800732 0.1096922755 0.0819993988 0.1382135600 0.0047200174 0.1368400000 357163422 0 1476927488 -0.0769217536 -0.0855319947 -0.0213929135 436 1311867733.1458189487 0.1097171754 0.0820629717 0.1382135600 0.0047174622 0.1403300000 357165220 0 1477414912 -0.0782429874 -0.0852185264 -0.0156425685 437 1311867733.1777689457 0.1100410968 0.0821269949 0.1382135600 0.0047126378 0.1356930000 357167018 0 1477922816 -0.0780299231 -0.0855510682 -0.0176564269 438 1311867733.2097411156 0.1102489457 0.0821912002 0.1382135600 0.0047092912 0.1357690000 357168752 0 1478430720 -0.0777167454 -0.0853613392 -0.0205825977 439 1311867733.2458369732 0.1104081571 0.0822554758 0.1382135600 0.0047045705 0.1428440000 357170582 0 1478955008 -0.0781930834 -0.0850488171 -0.0182342120 440 1311867733.2777390480 0.1100168079 0.0823185697 0.1382135600 0.0046998816 0.1373030000 357172380 0 1479593984 -0.0782135203 -0.0844162628 -0.0166283511 441 1311867733.3098380566 0.1096048579 0.0823804434 0.1382135600 0.0046960452 0.1435450000 357174114 0 1480081408 -0.0773370191 -0.0843142122 -0.0172515269 442 1311867733.3457000256 0.1095473170 0.0824419069 0.1382135600 0.0046923193 0.1417790000 357175944 0 1480589312 -0.0779847279 -0.0836838484 -0.0139664477 443 1311867733.3779110909 0.1106676534 0.0825056219 0.1382135600 0.0046876010 0.1327250000 357177710 0 1481097216 -0.0776165128 -0.0852469504 -0.0150486734 444 1311867733.4098379612 0.1108312979 0.0825694185 0.1382135600 0.0046845553 0.1349100000 357179476 0 1481605120 -0.0773278326 -0.0848896578 -0.0184399839 445 1311867733.4457030296 0.1107963696 0.0826328498 0.1382135600 0.0046804397 0.1368730000 357181274 0 1482260480 -0.0765146017 -0.0852919817 -0.0177758951 446 1311867733.4778809547 0.1115862355 0.0826977677 0.1382135600 0.0046755379 0.1362310000 357183040 0 1482747904 -0.0768003762 -0.0858838335 -0.0178932454 447 1311867733.5098519325 0.1117057577 0.0827626625 0.1382135600 0.0046718156 0.1225210000 357184710 0 1483255808 -0.0763557777 -0.0856438801 -0.0207033716 448 1311867733.5457990170 0.1115666702 0.0828269572 0.1382135600 0.0046716759 0.1257270000 357186540 0 1483763712 -0.0760599896 -0.0858328193 -0.0191847831 449 1311867733.5777399540 0.1119612455 0.0828918443 0.1382135600 0.0046705406 0.1334290000 357188306 0 1484271616 -0.0766490549 -0.0860381871 -0.0158931874 450 1311867733.6138761044 0.1118092537 0.0829561052 0.1382135600 0.0047054088 0.1228450000 357190168 0 1484906496 -0.0761197060 -0.0864691287 -0.0175198670 451 1311867733.6456980705 0.1118140966 0.0830200919 0.1382135600 0.0047426529 0.1329520000 357191870 0 1485414400 -0.0763782784 -0.0855259448 -0.0174087919 452 1311867733.6778860092 0.1119506806 0.0830840976 0.1382135600 0.0047377085 0.1248380000 357193668 0 1486069760 -0.0767851621 -0.0852981210 -0.0167399440 453 1311867733.7137401104 0.1118124351 0.0831475155 0.1382135600 0.0047330325 0.1297810000 357195466 0 1486557184 -0.0764395669 -0.0852605179 -0.0151100587 454 1311867733.7458200455 0.1117340326 0.0832104814 0.1382135600 0.0047871033 0.1299520000 357197232 0 1487065088 -0.0753014907 -0.0862566382 -0.0152926687 455 1311867733.7778670788 0.1118125096 0.0832733430 0.1382135600 0.0048182314 0.1223910000 357198966 0 1487572992 -0.0744992942 -0.0867551714 -0.0154649904 456 1311867733.8138499260 0.1116670221 0.0833356099 0.1382135600 0.0048136565 0.1301330000 357200796 0 1488228352 -0.0743421838 -0.0868862420 -0.0113441376 457 1311867733.8457639217 0.1125806868 0.0833996035 0.1382135600 0.0048086490 0.1295740000 357202498 0 1488715776 -0.0755220056 -0.0865295306 -0.0141674494 458 1311867733.8778181076 0.1121877581 0.0834624597 0.1382135600 0.0048061570 0.1223010000 357204232 0 1489223680 -0.0748874098 -0.0863090679 -0.0135440202 459 1311867733.9139699936 0.1128513888 0.0835264879 0.1382135600 0.0048015854 0.4579090000 369505066 0 1502048256 -0.0745564252 -0.0873162523 -0.0124426661 460 1311867733.9457590580 0.1124776527 0.0835894252 0.1382135600 0.0048073878 0.2037010000 373164648 0 1505984512 -0.0691489130 -0.0919404849 -0.0097841900 461 1311867733.9777710438 0.1071379632 0.0836405066 0.1382135600 0.0048154885 0.1993260000 376358510 0 1509683200 -0.0675818771 -0.0862299800 -0.0107215168 462 1311867734.0139269829 0.1067032069 0.0836904259 0.1382135600 0.0048155870 0.1922590000 376360340 0 1510555648 -0.0672330186 -0.0859507620 -0.0088671632 463 1311867734.0458869934 0.1059546247 0.0837385127 0.1382135600 0.0048136367 0.1809340000 376362106 0 1511190528 -0.0672250837 -0.0848876014 -0.0113916444 464 1311867734.0779299736 0.1061257645 0.0837867611 0.1382135600 0.0048090398 0.1781630000 376363904 0 1511698432 -0.0668307543 -0.0854029581 -0.0122625269 465 1311867734.1137819290 0.1062886789 0.0838351523 0.1382135600 0.0048044535 0.1798090000 376365734 0 1512206336 -0.0664260313 -0.0861191377 -0.0089727985 466 1311867734.1458649635 0.1064937338 0.0838837759 0.1382135600 0.0048046490 0.1765260000 376367468 0 1512714240 -0.0661839023 -0.0865536630 -0.0118419705 467 1311867734.1778779030 0.1062506586 0.0839316707 0.1382135600 0.0047999133 0.1672790000 376369234 0 1513222144 -0.0654277429 -0.0863246769 -0.0136306752 468 1311867734.2139220238 0.1063154936 0.0839794994 0.1382135600 0.0047992372 0.1684210000 376371096 0 1513877504 -0.0653090328 -0.0866986662 -0.0096526034 469 1311867734.2458229065 0.1063478738 0.0840271932 0.1382135600 0.0047968298 0.1759520000 376372830 0 1514364928 -0.0650165156 -0.0869808793 -0.0118864644 470 1311867734.2779779434 0.1067801192 0.0840756036 0.1382135600 0.0047948734 0.1639190000 376374596 0 1514872832 -0.0645199269 -0.0876634270 -0.0136993499 471 1311867734.3137800694 0.1062388644 0.0841226594 0.1382135600 0.0047906675 0.1620890000 376376394 0 1515380736 -0.0644467250 -0.0869859457 -0.0112295914 472 1311867734.3457100391 0.1061533913 0.0841693347 0.1382135600 0.0047866022 0.1657840000 376378128 0 1515905024 -0.0640713423 -0.0871748179 -0.0124489469 473 1311867734.3778929710 0.1071126759 0.0842178407 0.1382135600 0.0047828936 0.1595960000 376379894 0 1516523520 -0.0644376352 -0.0877666548 -0.0146153793 474 1311867734.4139640331 0.1072536558 0.0842664394 0.1382135600 0.0047784871 0.1571030000 376381756 0 1517031424 -0.0639264286 -0.0885075554 -0.0126902526 475 1311867734.4458029270 0.1071987152 0.0843147179 0.1382135600 0.0047734768 0.1550670000 376383490 0 1517539328 -0.0637422726 -0.0886521786 -0.0117315799 476 1311867734.4778079987 0.1069623902 0.0843622971 0.1382135600 0.0047715654 0.1572740000 376385288 0 1518047232 -0.0623716079 -0.0895140022 -0.0128895603 477 1311867734.5140230656 0.1077167988 0.0844112583 0.1382135600 0.0047671911 0.1569800000 376387118 0 1518555136 -0.0628629550 -0.0902626663 -0.0113754822 478 1311867734.5457649231 0.1080116779 0.0844606315 0.1382135600 0.0047641975 0.1583220000 376388852 0 1519210496 -0.0626159236 -0.0908778459 -0.0106609305 479 1311867734.5780689716 0.1084392071 0.0845106912 0.1382135600 0.0047656119 0.1518670000 376390618 0 1519697920 -0.0639194325 -0.0896035507 -0.0123998914 480 1311867734.6139369011 0.1076942235 0.0845589902 0.1382135600 0.0047643313 0.1526200000 376392480 0 1520205824 -0.0634269640 -0.0890611708 -0.0121921580 481 1311867734.6459009647 0.1078476906 0.0846074075 0.1382135600 0.0047600210 0.1549670000 376394214 0 1520713728 -0.0634159446 -0.0894695595 -0.0102111800 482 1311867734.6778221130 0.1080080122 0.0846559565 0.1382135600 0.0047570933 0.1471230000 376395948 0 1521221632 -0.0633248761 -0.0895085111 -0.0103784166 483 1311867734.7139430046 0.1074389964 0.0847031263 0.1382135600 0.0047555942 0.1461610000 376397746 0 1521876992 -0.0631776378 -0.0888538435 -0.0104130153 484 1311867734.7457649708 0.1068584025 0.0847489017 0.1382135600 0.0047538943 0.1473700000 376399544 0 1522364416 -0.0632427111 -0.0876402184 -0.0106243407 485 1311867734.7778189182 0.1077070609 0.0847962381 0.1382135600 0.0047511616 0.1468410000 376401310 0 1522872320 -0.0621893071 -0.0896141231 -0.0106323939 486 1311867734.8139710426 0.1082165465 0.0848444280 0.1382135600 0.0047467888 0.1411230000 376403108 0 1523507200 -0.0621387959 -0.0898592621 -0.0121777533 487 1311867734.8457450867 0.1078274474 0.0848916211 0.1382135600 0.0047423868 0.1419000000 376404874 0 1524015104 -0.0615560561 -0.0897066519 -0.0118135000 488 1311867734.8778049946 0.1078773811 0.0849387230 0.1382135600 0.0047381442 0.5514770000 388727908 0 1536839680 -0.0619703121 -0.0893188715 -0.0094677787 489 1311867734.9138820171 0.1082722619 0.0849864399 0.1382135600 0.0047535561 0.0663170000 392387618 0 1540775936 -0.0589818247 -0.0928771943 -0.0088304719 490 1311867734.9458339214 0.1122721285 0.0850421250 0.1382135600 0.0047493594 0.2171270000 395581416 0 1544585216 -0.0609438419 -0.0958775803 -0.0103094587 491 1311867734.9778809547 0.1099816188 0.0850929182 0.1382135600 0.0047460195 0.0692500000 395583118 0 1545347072 -0.0600201450 -0.0938870385 -0.0080970852 492 1311867735.0137929916 0.1095314771 0.0851425901 0.1382135600 0.0047416631 0.0632360000 395584948 0 1545981952 -0.0599338003 -0.0934606045 -0.0096159820 493 1311867735.0459361076 0.1089527458 0.0851908866 0.1382135600 0.0047376429 0.0954400000 395586650 0 1546489856 -0.0594857857 -0.0929459557 -0.0111860353 494 1311867735.0778191090 0.1092651263 0.0852396198 0.1382135600 0.0047340260 0.0626100000 395588448 0 1546997760 -0.0596335828 -0.0934737623 -0.0090365838 495 1311867735.1139230728 0.1110583469 0.0852917789 0.1382135600 0.0047370830 0.2027440000 395590246 0 1547505664 -0.0594042353 -0.0960860625 -0.0096860649 496 1311867735.1458799839 0.1111902371 0.0853439935 0.1382135600 0.0047330008 0.1959490000 395592012 0 1548161024 -0.0583973750 -0.0971327126 -0.0091516757 497 1311867735.1779301167 0.1081203222 0.0853898211 0.1382135600 0.0047430946 0.0600830000 395593810 0 1548648448 -0.0594381355 -0.0920249820 -0.0073794103 498 1311867735.2137629986 0.1087249964 0.0854366789 0.1382135600 0.0047407352 0.1009720000 395595608 0 1549156352 -0.0588979833 -0.0932591781 -0.0098554250 499 1311867735.2458269596 0.1094831377 0.0854848682 0.1382135600 0.0047518962 0.1978470000 395597374 0 1549664256 -0.0556680672 -0.0969977304 -0.0095692417 500 1311867735.2779319286 0.1098279729 0.0855335544 0.1382135600 0.0047543658 0.1877480000 395599140 0 1550188544 -0.0573807843 -0.0965090841 -0.0082825227 501 1311867735.3140900135 0.1099369898 0.0855822639 0.1382135600 0.0047497440 0.1924970000 395600938 0 1550807040 -0.0578261837 -0.0960412249 -0.0104150428 502 1311867735.3461539745 0.1081150994 0.0856271500 0.1382135600 0.0047478561 0.1140000000 395602672 0 1551314944 -0.0588684902 -0.0920810997 -0.0101547036 503 1311867735.3780119419 0.1073376164 0.0856703120 0.1382135600 0.0047508619 0.1565370000 395604470 0 1551949824 -0.0592426695 -0.0909670219 -0.0097598080 504 1311867735.4139440060 0.1086330563 0.0857158730 0.1382135600 0.0047546462 0.0954530000 395606236 0 1552457728 -0.0589891449 -0.0928607434 -0.0105757313 505 1311867735.4463770390 0.1135694087 0.0857710285 0.1382135600 0.0047677608 0.1870070000 395608034 0 1552965632 -0.0584816411 -0.0999955982 -0.0097419797 506 1311867735.4778969288 0.1100247502 0.0858189607 0.1382135600 0.0047698429 0.1782510000 395609800 0 1553473536 -0.0584613308 -0.0950498581 -0.0095476126 507 1311867735.5137150288 0.1100761741 0.0858668054 0.1382135600 0.0047656545 0.1748540000 395611662 0 1554128896 -0.0583265312 -0.0949513391 -0.0096940501 508 1311867735.5458450317 0.1110723689 0.0859164226 0.1382135600 0.0047709533 0.1160820000 395613364 0 1554616320 -0.0594289862 -0.0942936391 -0.0091110477 509 1311867735.5778179169 0.1105423942 0.0859648037 0.1382135600 0.0047767592 0.1635280000 395615162 0 1555124224 -0.0591557994 -0.0947345942 -0.0084189884 510 1311867735.6139240265 0.1106648073 0.0860132351 0.1382135600 0.0047726963 0.1478070000 395617024 0 1555632128 -0.0593259111 -0.0945155993 -0.0087977005 511 1311867735.6459200382 0.1119371876 0.0860639669 0.1382135600 0.0047710395 0.1584230000 395618726 0 1556131840 -0.0603526756 -0.0951340869 -0.0068780337 512 1311867735.6778628826 0.1169506833 0.0861242925 0.1382135600 0.0047830469 0.5090400000 407920540 0 1569103872 -0.0600145906 -0.1027122363 -0.0053015556 513 1311867735.7137730122 0.1200109422 0.0861903483 0.1382135600 0.0047921721 0.0662650000 411623194 0 1573027840 -0.0592308342 -0.1072752923 -0.0118241431 514 1311867735.7458720207 0.1216897294 0.0862594133 0.1382135600 0.0047890703 0.1286560000 414901024 0 1576837120 -0.0595939904 -0.1089387760 -0.0131527036 515 1311867735.7779068947 0.1225360334 0.0863298533 0.1382135600 0.0047877039 0.2033690000 414902822 0 1577598976 -0.0582288019 -0.1106657684 -0.0123241367 516 1311867735.8139519691 0.1205618605 0.0863961944 0.1382135600 0.0047857819 0.1593350000 414904620 0 1578233856 -0.0571378097 -0.1090582535 -0.0141459331 517 1311867735.8461170197 0.1210172921 0.0864631598 0.1382135600 0.0047903222 0.1581770000 414906386 0 1578741760 -0.0570258796 -0.1086674258 -0.0147648919 518 1311867735.8779520988 0.1221521273 0.0865320574 0.1382135600 0.0047905769 0.1368860000 414908088 0 1579397120 -0.0588240102 -0.1086843908 -0.0152057791 519 1311867735.9139308929 0.1211356446 0.0865987310 0.1382135600 0.0047887469 0.1512120000 414909918 0 1579884544 -0.0569917411 -0.1083330736 -0.0157284923 520 1311867735.9461469650 0.1209082007 0.0866647107 0.1382135600 0.0047851272 0.1637350000 414911684 0 1580392448 -0.0569560714 -0.1080303788 -0.0150702931 521 1311867735.9778470993 0.1220409274 0.0867326113 0.1382135600 0.0047816603 0.1277950000 414913450 0 1580900352 -0.0584487617 -0.1080868468 -0.0150245409 522 1311867736.0138840675 0.1234939471 0.0868030354 0.1382135600 0.0047827053 0.1351870000 414915280 0 1581555712 -0.0605307296 -0.1081870347 -0.0164201707 523 1311867736.0458500385 0.1263645440 0.0868786788 0.1382135600 0.0047789219 0.1622110000 414917014 0 1582043136 -0.0638431534 -0.1091035530 -0.0160381570 524 1311867736.0778849125 0.1224692091 0.0869465996 0.1382135600 0.0047764939 0.1122000000 414918812 0 1582551040 -0.0591805615 -0.1082220003 -0.0148893725 525 1311867736.1139700413 0.1263001859 0.0870215589 0.1382135600 0.0047764055 0.1473210000 414920610 0 1583058944 -0.0638341606 -0.1093640029 -0.0159306861 526 1311867736.1458110809 0.1236060336 0.0870911111 0.1382135600 0.0047744524 0.2972010000 427224920 0 1595883520 -0.0599596687 -0.1094631478 -0.0155406510 527 1311867736.1779921055 0.1120814160 0.0871385310 0.1382135600 0.0048584862 0.0612790000 430886222 0 1599819776 -0.0608901531 -0.0936955363 -0.0144532975 528 1311867736.2138609886 0.1127523035 0.0871870420 0.1382135600 0.0048557836 0.0587330000 434080116 0 1603502080 -0.0608462431 -0.0946081951 -0.0147191007 529 1311867736.2459011078 0.1122133136 0.0872343506 0.1382135600 0.0048590451 0.0588560000 434081882 0 1604390912 -0.0614136718 -0.0939689428 -0.0146372309 530 1311867736.2780930996 0.1129806712 0.0872829286 0.1382135600 0.0048555785 0.1173800000 434083616 0 1604898816 -0.0625090674 -0.0941528380 -0.0126193287 531 1311867736.3138680458 0.1132295951 0.0873317923 0.1382135600 0.0048590676 0.1101620000 434085446 0 1605406720 -0.0624444894 -0.0948852897 -0.0162508041 532 1311867736.3458290100 0.1149222627 0.0873836541 0.1382135600 0.0048597665 0.1985460000 434087212 0 1606041600 -0.0636447072 -0.0962448493 -0.0137997689 533 1311867736.3779211044 0.1149588004 0.0874353899 0.1382135600 0.0048581517 0.1932840000 434088978 0 1606549504 -0.0638472065 -0.0971058831 -0.0121980021 534 1311867736.4138979912 0.1138461828 0.0874848483 0.1382135600 0.0048549584 0.1833830000 434090776 0 1607073792 -0.0622143261 -0.0970271975 -0.0155972186 535 1311867736.4458179474 0.1141600236 0.0875347084 0.1382135600 0.0048531175 0.1849020000 434092542 0 1607712768 -0.0629398823 -0.0970537439 -0.0139182145 536 1311867736.4780380726 0.1151903570 0.0875863048 0.1382135600 0.0048532281 0.1799790000 434094340 0 1608200192 -0.0647084862 -0.0968975127 -0.0126519576 537 1311867736.5138549805 0.1143061072 0.0876360623 0.1382135600 0.0048507798 0.1750780000 434096138 0 1608835072 -0.0628435686 -0.0974924341 -0.0153394993 538 1311867736.5459420681 0.1148584411 0.0876866615 0.1382135600 0.0048481583 0.1733080000 434097936 0 1609342976 -0.0636762306 -0.0978213400 -0.0153389489 539 1311867736.5779209137 0.1157643422 0.0877387537 0.1382135600 0.0048451319 0.2461650000 446395186 0 1622167552 -0.0655731782 -0.0979519114 -0.0125589399 540 1311867736.6140410900 0.1204620451 0.0877993524 0.1382135600 0.0048571570 0.1164530000 450054896 0 1626103808 -0.0653731748 -0.1045608371 -0.0166130029 541 1311867736.6459450722 0.1260186732 0.0878699981 0.1382135600 0.0048611138 0.2046570000 453248726 0 1629786112 -0.0707454011 -0.1067878380 -0.0170429759 542 1311867736.6779170036 0.1278524846 0.0879437665 0.1382135600 0.0048595479 0.1932020000 453250492 0 1630547968 -0.0739066154 -0.1070960984 -0.0141577180 543 1311867736.7140109539 0.1254855245 0.0880129042 0.1382135600 0.0048929067 0.1933150000 453252258 0 1631182848 -0.0682189539 -0.1102356166 -0.0154587124 544 1311867736.7458450794 0.1217942610 0.0880750023 0.1382135600 0.0048956615 0.1543020000 453254024 0 1631690752 -0.0660238713 -0.1066427454 -0.0170697141 545 1311867736.7780408859 0.1225579903 0.0881382738 0.1382135600 0.0049041919 0.1625380000 453255822 0 1632198656 -0.0673279241 -0.1072282121 -0.0163258314 546 1311867736.8139879704 0.1234075576 0.0882028696 0.1382135600 0.0049040351 0.1807740000 453257652 0 1632854016 -0.0661358982 -0.1089160293 -0.0198782776 547 1311867736.8458929062 0.1227423921 0.0882660131 0.1382135600 0.0049013939 0.3419230000 465559370 0 1645658112 -0.0650119111 -0.1083404869 -0.0231511872 548 1311867736.8779690266 0.1139428467 0.0883128687 0.1382135600 0.0049104028 0.1213240000 469218984 0 1649594368 -0.0552543812 -0.1055619642 -0.0183814149 549 1311867736.9140260220 0.1146549210 0.0883608505 0.1382135600 0.0049070690 0.1059740000 472412910 0 1653293056 -0.0548486374 -0.1064931899 -0.0196304265 550 1311867736.9459569454 0.1139630377 0.0884074000 0.1382135600 0.0049043747 0.1030980000 472414676 0 1654165504 -0.0536938794 -0.1053667143 -0.0242602248 551 1311867736.9779520035 0.1235735342 0.0884712224 0.1382135600 0.0049010520 0.2028460000 472416442 0 1654689792 -0.0617395006 -0.1113112494 -0.0223464649 552 1311867737.0140330791 0.1221340820 0.0885322058 0.1382135600 0.0048972137 0.1918290000 472418240 0 1655308288 -0.0598124601 -0.1113897637 -0.0215205085 553 1311867737.0459079742 0.1146245971 0.0885793891 0.1382135600 0.0048956838 0.0527270000 472420038 0 1655832576 -0.0551818423 -0.1050955579 -0.0218622722 554 1311867737.0781080723 0.1146683842 0.0886264812 0.1382135600 0.0048922105 0.1836490000 484716064 0 1668767744 -0.0548086092 -0.1057639197 -0.0199503191 555 1311867737.1139400005 0.1176261529 0.0886787329 0.1382135600 0.0048889777 0.0510570000 488375774 0 1672577024 -0.0585239641 -0.1064357460 -0.0212996528 556 1311867737.1460459232 0.1173935533 0.0887303782 0.1382135600 0.0048864565 0.0554850000 491569604 0 1676275712 -0.0580075458 -0.1061820462 -0.0230963156 557 1311867737.1779479980 0.1117224842 0.0887716567 0.1382135600 0.0048879231 0.2021370000 491571370 0 1677148160 -0.0555334426 -0.1009471416 -0.0223742202 558 1311867737.2139670849 0.1174204350 0.0888229986 0.1382135600 0.0048894911 0.0590350000 491573232 0 1677647872 -0.0577476881 -0.1065478623 -0.0227120351 559 1311867737.2461230755 0.1187521517 0.0888765391 0.1382135600 0.0048966828 0.1271120000 491574966 0 1678282752 -0.0581291988 -0.1073764265 -0.0240012053 560 1311867737.2783720493 0.1237422526 0.0889387993 0.1382135600 0.0049056115 0.1787470000 491576732 0 1678938112 -0.0656467751 -0.1064381152 -0.0265412275 561 1311867737.3138759136 0.1175231710 0.0889897518 0.1382135600 0.0049074451 0.1115460000 491578594 0 1679425536 -0.0570231117 -0.1061820909 -0.0236550868 562 1311867737.3459680080 0.1173772514 0.0890402634 0.1382135600 0.0049033184 0.1460340000 491580296 0 1679933440 -0.0563327149 -0.1064493656 -0.0246849582 563 1311867737.3780488968 0.1181300581 0.0890919327 0.1382135600 0.0049007884 0.1468380000 503874310 0 1692758016 -0.0570579879 -0.1065406427 -0.0244529787 564 1311867737.4141969681 0.1250436455 0.0891556768 0.1382135600 0.0049038221 0.1734800000 507533956 0 1696567296 -0.0622605346 -0.1104191020 -0.0276678074 565 1311867737.4462239742 0.1251896471 0.0892194538 0.1382135600 0.0049019215 0.0642390000 519077394 0 1700265984 -0.0622605346 -0.1104191020 -0.0276678074 566 1311867737.4780650139 0.1253574193 0.0892833018 0.1382135600 0.0048995686 0.0356800000 522424900 0 1704202240 -0.0622605346 -0.1104191020 -0.0276678074 567 1311867737.5141921043 0.1253057718 0.0893468335 0.1382135600 0.0048961293 0.0282060000 522503562 0 1705095168 -0.0622605346 -0.1104191020 -0.0276678074 568 1311867737.5464630127 0.1257097870 0.0894108527 0.1382135600 0.0048961441 0.0298120000 522582160 0 1705709568 -0.0622605346 -0.1104191020 -0.0276678074 569 1311867737.5780799389 0.1259402782 0.0894750521 0.1382135600 0.0048948645 0.0294800000 522660790 0 1706344448 -0.0622605346 -0.1104191020 -0.0276678074 570 1311867737.6142530441 0.1261463761 0.0895393877 0.1382135600 0.0048963682 0.0314530000 522739420 0 1706999808 -0.0622605346 -0.1104191020 -0.0276678074 571 1311867737.6460239887 0.1261485964 0.0896035019 0.1382135600 0.0048959995 0.0304840000 522818018 0 1707487232 -0.0622605346 -0.1104191020 -0.0276678074 572 1311867737.6780090332 0.1260608584 0.0896672386 0.1382135600 0.0048956470 0.0317270000 522896616 0 1708269568 -0.0622605346 -0.1104191020 -0.0276678074 573 1311867737.7139749527 0.1260424256 0.0897307206 0.1382135600 0.0048928503 0.0292420000 522975246 0 1708904448 -0.0622605346 -0.1104191020 -0.0276678074 574 1311867737.7460410595 0.1261326820 0.0897941386 0.1382135600 0.0048901986 0.0322610000 523053844 0 1709518848 -0.0622605346 -0.1104191020 -0.0276678074 575 1311867737.7782158852 0.1261543781 0.0898573738 0.1382135600 0.0048914465 0.0319990000 523132474 0 1710174208 -0.0622605346 -0.1104191020 -0.0276678074 576 1311867737.8140470982 0.1261951476 0.0899204602 0.1382135600 0.0048889308 0.0271010000 523211136 0 1710788608 -0.0622605346 -0.1104191020 -0.0276678074 577 1311867737.8460240364 0.1265044212 0.0899838640 0.1382135600 0.0048958052 0.0298790000 523289702 0 1711423488 -0.0622605346 -0.1104191020 -0.0276678074 578 1311867737.8779919147 0.1266514063 0.0900473026 0.1382135600 0.0048945689 0.0283470000 523368332 0 1712058368 -0.0622605346 -0.1104191020 -0.0276678074 579 1311867737.9140400887 0.1269911230 0.0901111089 0.1382135600 0.0048948136 0.0299240000 523446930 0 1712693248 -0.0622605346 -0.1104191020 -0.0276678074 580 1311867737.9459939003 0.1270793676 0.0901748473 0.1382135600 0.0048958341 0.0294420000 523525528 0 1713328128 -0.0622605346 -0.1104191020 -0.0276678074 581 1311867737.9781990051 0.1272735596 0.0902387005 0.1382135600 0.0048961317 0.0263960000 523604158 0 1713963008 -0.0622605346 -0.1104191020 -0.0276678074 582 1311867738.0141079426 0.1276325583 0.0903029511 0.1382135600 0.0048956730 0.0295600000 523682820 0 1714597888 -0.0622605346 -0.1104191020 -0.0276678074 583 1311867738.0460178852 0.1281136274 0.0903678065 0.1382135600 0.0048935235 0.0302620000 523761386 0 1715232768 -0.0622605346 -0.1104191020 -0.0276678074 584 1311867738.0781040192 0.1287371069 0.0904335073 0.1382135600 0.0048907333 0.0259550000 523839984 0 1715867648 -0.0622605346 -0.1104191020 -0.0276678074 585 1311867738.1140170097 0.1291628480 0.0904997113 0.1382135600 0.0048993431 0.0312370000 523918582 0 1716502528 -0.0622605346 -0.1104191020 -0.0276678074 586 1311867738.1460049152 0.1293729395 0.0905660479 0.1382135600 0.0048982373 0.0319560000 523997180 0 1717137408 -0.0622605346 -0.1104191020 -0.0276678074 587 1311867738.1779909134 0.1295851022 0.0906325199 0.1382135600 0.0048975429 0.0366560000 524075810 0 1717772288 -0.0622605346 -0.1104191020 -0.0276678074 588 1311867738.2141749859 0.1296741664 0.0906989172 0.1382135600 0.0049018195 0.0326100000 524154472 0 1718423552 -0.0622605346 -0.1104191020 -0.0276678074 589 1311867738.2461900711 0.1295118481 0.0907648135 0.1382135600 0.0049067566 0.0345310000 524233070 0 1719058432 -0.0622605346 -0.1104191020 -0.0276678074 590 1311867738.2781438828 0.1295244992 0.0908305079 0.1382135600 0.0049117725 0.0276310000 524311668 0 1719824384 -0.0622605346 -0.1104191020 -0.0276678074 591 1311867738.3141109943 0.1291831583 0.0908954024 0.1382135600 0.0049170398 0.0328220000 524390330 0 1720459264 -0.0622605346 -0.1104191020 -0.0276678074 592 1311867738.3461089134 0.1290913969 0.0909599227 0.1382135600 0.0049386315 0.0306810000 524468928 0 1721073664 -0.0622605346 -0.1104191020 -0.0276678074 593 1311867738.3781440258 0.1291232109 0.0910242790 0.1382135600 0.0049392806 0.0386460000 524547526 0 1721708544 -0.0622605346 -0.1104191020 -0.0276678074 594 1311867738.4142370224 0.1293209940 0.0910887516 0.1382135600 0.0049383026 0.0342300000 524626156 0 1722343424 -0.0622605346 -0.1104191020 -0.0276678074 595 1311867738.4462459087 0.1292499453 0.0911528880 0.1382135600 0.0049371877 0.0326300000 524704786 0 1722978304 -0.0622605346 -0.1104191020 -0.0276678074 596 1311867738.4781920910 0.1296976805 0.0912175605 0.1382135600 0.0049352017 0.0254980000 524783416 0 1723613184 -0.0622605346 -0.1104191020 -0.0276678074 597 1311867738.5140159130 0.1302761734 0.0912829853 0.1382135600 0.0049326909 0.0333640000 524862078 0 1724248064 -0.0622605346 -0.1104191020 -0.0276678074 598 1311867738.5462310314 0.1306960732 0.0913488935 0.1382135600 0.0049300302 0.0327420000 524940644 0 1724882944 -0.0622605346 -0.1104191020 -0.0276678074 599 1311867738.5779619217 0.1313985288 0.0914157543 0.1382135600 0.0049319814 0.0281410000 525019242 0 1725517824 -0.0622605346 -0.1104191020 -0.0276678074 600 1311867738.6140589714 0.1318631172 0.0914831666 0.1382135600 0.0049323878 0.0349130000 525097872 0 1726300160 -0.0622605346 -0.1104191020 -0.0276678074 601 1311867738.6460950375 0.1326405853 0.0915516482 0.1382135600 0.0049323499 0.0392630000 525176502 0 1726935040 -0.0622605346 -0.1104191020 -0.0276678074 602 1311867738.6780719757 0.1329670995 0.0916204446 0.1382135600 0.0049459429 0.0316910000 525255100 0 1727557632 -0.0622605346 -0.1104191020 -0.0276678074 603 1311867738.7142090797 0.1330763996 0.0916891941 0.1382135600 0.0049444098 0.0327180000 525333730 0 1728192512 -0.0622605346 -0.1104191020 -0.0276678074 604 1311867738.7460970879 0.1338351518 0.0917589722 0.1382135600 0.0049816488 0.0368360000 525412360 0 1728827392 -0.0622605346 -0.1104191020 -0.0276678074 605 1311867738.7783861160 0.1344897449 0.0918296015 0.1382135600 0.0049903689 0.0548800000 525490958 0 1729462272 -0.0622605346 -0.1104191020 -0.0276678074 606 1311867738.8142549992 0.1349717528 0.0919007932 0.1382135600 0.0050119787 0.0353150000 525569588 0 1730097152 -0.0622605346 -0.1104191020 -0.0276678074 607 1311867738.8462960720 0.1353938580 0.0919724457 0.1382135600 0.0050098482 0.0341040000 525648218 0 1730732032 -0.0622605346 -0.1104191020 -0.0276678074 608 1311867738.8781909943 0.1358453035 0.0920446050 0.1382135600 0.0050095561 0.0433630000 525726816 0 1731383296 -0.0622605346 -0.1104191020 -0.0276678074 609 1311867738.9141190052 0.1361961514 0.0921171035 0.1382135600 0.0050176208 0.0421160000 525805446 0 1732018176 -0.0622605346 -0.1104191020 -0.0276678074 610 1311867738.9461998940 0.1365197450 0.0921898947 0.1382135600 0.0050201228 0.0360060000 525884076 0 1732763648 -0.0622605346 -0.1104191020 -0.0276678074 611 1311867738.9781630039 0.1368580461 0.0922630013 0.1382135600 0.0050187444 0.0352910000 525962674 0 1733419008 -0.0622605346 -0.1104191020 -0.0276678074 612 1311867739.0142040253 0.1370128989 0.0923361220 0.1382135600 0.0050286106 0.0393060000 526041368 0 1734033408 -0.0622605346 -0.1104191020 -0.0276678074 613 1311867739.0461840630 0.1370363832 0.0924090425 0.1382135600 0.0050809594 0.0347140000 526119934 0 1734668288 -0.0622605346 -0.1104191020 -0.0276678074 614 1311867739.0781500340 0.1374081522 0.0924823310 0.1382135600 0.0050795626 0.0345080000 526198532 0 1735303168 -0.0622605346 -0.1104191020 -0.0276678074 615 1311867739.1145129204 0.1376563758 0.0925557847 0.1382135600 0.0050952665 0.0375800000 526277098 0 1735938048 -0.0622605346 -0.1104191020 -0.0276678074 616 1311867739.1463479996 0.1376446187 0.0926289809 0.1382135600 0.0051015395 0.0290720000 526355632 0 1736572928 -0.0622605346 -0.1104191020 -0.0276678074 617 1311867739.1784689426 0.1375703216 0.0927018194 0.1382135600 0.0050993948 0.0317480000 526434230 0 1737207808 -0.0622605346 -0.1104191020 -0.0276678074 618 1311867739.2143969536 0.1374218911 0.0927741819 0.1382135600 0.0050992802 0.0353660000 526512860 0 1737859072 -0.0622605346 -0.1104191020 -0.0276678074 619 1311867739.2462329865 0.1371620893 0.0928458910 0.1382135600 0.0051011100 0.0347700000 526591490 0 1738477568 -0.0622605346 -0.1104191020 -0.0276678074 620 1311867739.2781720161 0.1367172003 0.0929166512 0.1382135600 0.0050993732 0.0356550000 526670088 0 1739259904 -0.0622605346 -0.1104191020 -0.0276678074 621 1311867739.3142199516 0.1365509033 0.0929869157 0.1382135600 0.0050977204 0.0373640000 526748782 0 1739894784 -0.0622605346 -0.1104191020 -0.0276678074 622 1311867739.3466510773 0.1364315897 0.0930567624 0.1382135600 0.0050943223 0.0284780000 526827348 0 1740509184 -0.0622605346 -0.1104191020 -0.0276678074 623 1311867739.3781549931 0.1362815201 0.0931261440 0.1382135600 0.0050918205 0.0336020000 526905946 0 1741144064 -0.0622605346 -0.1104191020 -0.0276678074 624 1311867739.4140689373 0.1362718344 0.0931952878 0.1382135600 0.0050904608 0.0421780000 526984576 0 1741778944 -0.0622605346 -0.1104191020 -0.0276678074 625 1311867739.4460690022 0.1363295913 0.0932643027 0.1382135600 0.0050879418 0.0396980000 527063174 0 1742413824 -0.0622605346 -0.1104191020 -0.0276678074 626 1311867739.4783449173 0.1363046467 0.0933330572 0.1382135600 0.0050966124 0.0351610000 527141804 0 1743048704 -0.0622605346 -0.1104191020 -0.0276678074 627 1311867739.5141808987 0.1363476068 0.0934016610 0.1382135600 0.0050950270 0.0333130000 527220434 0 1743683584 -0.0622605346 -0.1104191020 -0.0276678074 628 1311867739.5462429523 0.1364634931 0.0934702307 0.1382135600 0.0050921516 0.0393720000 527299032 0 1744334848 -0.0622605346 -0.1104191020 -0.0276678074 629 1311867739.5781390667 0.1363682747 0.0935384311 0.1382135600 0.0050948589 0.0358290000 527377630 0 1744969728 -0.0622605346 -0.1104191020 -0.0276678074 630 1311867739.6142079830 0.1362878084 0.0936062873 0.1382135600 0.0050935302 0.0390230000 527456292 0 1745715200 -0.0622605346 -0.1104191020 -0.0276678074 631 1311867739.6460380554 0.1361479163 0.0936737067 0.1382135600 0.0050909632 0.0439790000 527534858 0 1746350080 -0.0622605346 -0.1104191020 -0.0276678074 632 1311867739.6830139160 0.1359884739 0.0937406604 0.1382135600 0.0050934541 0.0475370000 527613584 0 1746984960 -0.0622605346 -0.1104191020 -0.0276678074 633 1311867739.7142000198 0.1358519644 0.0938071870 0.1382135600 0.0050900310 0.0418300000 527692118 0 1747619840 -0.0622605346 -0.1104191020 -0.0276678074 634 1311867739.7461159229 0.1358566135 0.0938735110 0.1382135600 0.0050876162 0.0451760000 527770748 0 1748254720 -0.0622605346 -0.1104191020 -0.0276678074 635 1311867739.7782371044 0.1355145276 0.0939390874 0.1382135600 0.0050901760 0.0366550000 527849346 0 1748889600 -0.0622605346 -0.1104191020 -0.0276678074 636 1311867739.8140680790 0.1352184713 0.0940039921 0.1382135600 0.0050901033 0.0336820000 527927976 0 1749671936 -0.0622605346 -0.1104191020 -0.0276678074 637 1311867739.8462030888 0.1348965317 0.0940681876 0.1382135600 0.0050871909 0.0420680000 528006606 0 1750306816 -0.0622605346 -0.1104191020 -0.0276678074 638 1311867739.8784179688 0.1342240125 0.0941311277 0.1382135600 0.0050872648 0.0354260000 528085204 0 1750921216 -0.0622605346 -0.1104191020 -0.0276678074 639 1311867739.9141149521 0.1333433092 0.0941924927 0.1382135600 0.0050893002 0.0377920000 528163898 0 1751556096 -0.0622605346 -0.1104191020 -0.0276678074 640 1311867739.9462161064 0.1328922361 0.0942529610 0.1382135600 0.0050873728 0.0270920000 528165668 0 1752190976 -0.0622605346 -0.1104191020 -0.0276678074 641 1311867739.9781019688 0.1324379295 0.0943125319 0.1382135600 0.0050888223 0.0419270000 528244266 0 1752698880 -0.0622605346 -0.1104191020 -0.0276678074 642 1311867740.0140759945 0.1316017509 0.0943706148 0.1382135600 0.0050894717 0.0499670000 528322960 0 1753481216 -0.0622605346 -0.1104191020 -0.0276678074 643 1311867740.0462660789 0.1312048882 0.0944278999 0.1382135600 0.0050855742 0.0378250000 528401526 0 1754116096 -0.0622605346 -0.1104191020 -0.0276678074 644 1311867740.0782411098 0.1309379190 0.0944845924 0.1382135600 0.0050834508 0.0502510000 528480124 0 1754730496 -0.0622605346 -0.1104191020 -0.0276678074 645 1311867740.1140639782 0.1301842928 0.0945399408 0.1382135600 0.0050888567 0.0345440000 528558754 0 1755365376 -0.0622605346 -0.1104191020 -0.0276678074 646 1311867740.1463708878 0.1296150237 0.0945942366 0.1382135600 0.0050905401 0.0342150000 528637384 0 1756000256 -0.0622605346 -0.1104191020 -0.0276678074 647 1311867740.1781940460 0.1294038147 0.0946480381 0.1382135600 0.0050881380 0.0367010000 528715982 0 1756635136 -0.0622605346 -0.1104191020 -0.0276678074 648 1311867740.2142000198 0.1289170384 0.0947009224 0.1382135600 0.0050862252 0.0340620000 528794612 0 1757270016 -0.0622605346 -0.1104191020 -0.0276678074 649 1311867740.2462930679 0.1285396814 0.0947530622 0.1382135600 0.0050853234 0.0299440000 528873242 0 1757904896 -0.0622605346 -0.1104191020 -0.0276678074 650 1311867740.2782120705 0.1284065992 0.0948048369 0.1382135600 0.0050819810 0.0383780000 528951840 0 1758666752 -0.0622605346 -0.1104191020 -0.0276678074 651 1311867740.3143200874 0.1280580908 0.0948559172 0.1382135600 0.0050787009 0.0355370000 529030470 0 1759301632 -0.0622605346 -0.1104191020 -0.0276678074 652 1311867740.3463900089 0.1277736574 0.0949064045 0.1382135600 0.0050754050 0.0378850000 529109100 0 1759936512 -0.0622605346 -0.1104191020 -0.0276678074 653 1311867740.3781099319 0.1277417392 0.0949566883 0.1382135600 0.0050716883 0.0380190000 529187698 0 1760571392 -0.0622605346 -0.1104191020 -0.0276678074 654 1311867740.4140830040 0.1277141273 0.0950067761 0.1382135600 0.0050700339 0.0366640000 529266360 0 1761206272 -0.0622605346 -0.1104191020 -0.0276678074 655 1311867740.4461269379 0.1274643391 0.0950563297 0.1382135600 0.0050661584 0.0345400000 529344958 0 1761841152 -0.0622605346 -0.1104191020 -0.0276678074 656 1311867740.4782450199 0.1274006516 0.0951056350 0.1382135600 0.0050630630 0.0448740000 529423556 0 1762623488 -0.0622605346 -0.1104191020 -0.0276678074 657 1311867740.5142049789 0.1274435073 0.0951548556 0.1382135600 0.0050654544 0.0359600000 529502218 0 1763237888 -0.0622605346 -0.1104191020 -0.0276678074 658 1311867740.5463099480 0.1275620759 0.0952041066 0.1382135600 0.0050676787 0.0361540000 529580816 0 1763872768 -0.0622605346 -0.1104191020 -0.0276678074 659 1311867740.5782189369 0.1277567297 0.0952535036 0.1382135600 0.0050705618 0.0382120000 529659414 0 1764507648 -0.0622605346 -0.1104191020 -0.0276678074 660 1311867740.6141209602 0.1277889460 0.0953027998 0.1382135600 0.0050686489 0.0353010000 529738076 0 1765142528 -0.0622605346 -0.1104191020 -0.0276678074 661 1311867740.6463210583 0.1274676025 0.0953514606 0.1382135600 0.0050652310 0.0356860000 529816674 0 1765777408 -0.0622605346 -0.1104191020 -0.0276678074 662 1311867740.6782870293 0.1269832104 0.0953992427 0.1382135600 0.0050614732 0.0441870000 529895272 0 1766428672 -0.0622605346 -0.1104191020 -0.0276678074 663 1311867740.7142190933 0.1267769337 0.0954465695 0.1382135600 0.0050638250 0.0405470000 529973934 0 1767174144 -0.0622605346 -0.1104191020 -0.0276678074 664 1311867740.7462959290 0.1264368445 0.0954932416 0.1382135600 0.0050625350 0.0313440000 530052436 0 1767809024 -0.0622605346 -0.1104191020 -0.0276678074 665 1311867740.7784550190 0.1258988827 0.0955389644 0.1382135600 0.0050623808 0.0304340000 530131034 0 1768443904 -0.0622605346 -0.1104191020 -0.0276678074 666 1311867740.8142650127 0.1254413575 0.0955838629 0.1382135600 0.0050635121 0.0363440000 530209664 0 1769078784 -0.0622605346 -0.1104191020 -0.0276678074 667 1311867740.8461530209 0.1249823719 0.0956279386 0.1382135600 0.0050614506 0.0323460000 530288262 0 1769713664 -0.0622605346 -0.1104191020 -0.0276678074 668 1311867740.8782610893 0.1245575398 0.0956712464 0.1382135600 0.0050638897 0.0329100000 530366892 0 1770364928 -0.0622605346 -0.1104191020 -0.0276678074 669 1311867740.9145269394 0.1239036173 0.0957134473 0.1382135600 0.0050602257 0.0348400000 530445554 0 1771118592 -0.0622605346 -0.1104191020 -0.0276678074 670 1311867740.9468269348 0.1235620603 0.0957550123 0.1382135600 0.0050570537 0.0227430000 530447340 0 1771753472 -0.0622605346 -0.1104191020 -0.0276678074 671 1311867740.9783740044 0.1230665073 0.0957957150 0.1382135600 0.0050543920 0.0326490000 530525938 0 1772261376 -0.0622605346 -0.1104191020 -0.0276678074 672 1311867741.0141980648 0.1224882081 0.0958354360 0.1382135600 0.0050530794 0.0295900000 530604568 0 1772896256 -0.0622605346 -0.1104191020 -0.0276678074 673 1311867741.0462551117 0.1221776307 0.0958745774 0.1382135600 0.0050499463 0.0371560000 530683198 0 1773547520 -0.0622605346 -0.1104191020 -0.0276678074 674 1311867741.0782248974 0.1218418628 0.0959131046 0.1382135600 0.0050466991 0.0386120000 530761796 0 1774292992 -0.0622605346 -0.1104191020 -0.0276678074 675 1311867741.1144049168 0.1211113781 0.0959504353 0.1382135600 0.0050478553 0.0346160000 530840426 0 1774927872 -0.0622605346 -0.1104191020 -0.0276678074 676 1311867741.1466870308 0.1207784340 0.0959871632 0.1382135600 0.0050443909 0.0264280000 530842244 0 1775562752 -0.0622605346 -0.1104191020 -0.0276678074 677 1311867741.1783940792 0.1205199882 0.0960234007 0.1382135600 0.0050419635 0.0306500000 530920842 0 1776070656 -0.0622605346 -0.1104191020 -0.0276678074 678 1311867741.2143990993 0.1201062873 0.0960589212 0.1382135600 0.0050493510 0.0270870000 530999472 0 1776852992 -0.0622605346 -0.1104191020 -0.0276678074 679 1311867741.2465291023 0.1198582947 0.0960939718 0.1382135600 0.0050547319 0.0332380000 531078102 0 1777487872 -0.0622605346 -0.1104191020 -0.0276678074 680 1311867741.2784590721 0.1198345125 0.0961288844 0.1382135600 0.0050539856 0.0361340000 531156700 0 1778102272 -0.0622605346 -0.1104191020 -0.0276678074 681 1311867741.3143949509 0.1199154109 0.0961638132 0.1382135600 0.0050554923 0.0258750000 531235362 0 1778737152 -0.0622605346 -0.1104191020 -0.0276678074 682 1311867741.3464109898 0.1202456579 0.0961991238 0.1382135600 0.0050527282 0.0273610000 531237148 0 1779372032 -0.0622605346 -0.1104191020 -0.0276678074 683 1311867741.3783149719 0.1206835434 0.0962349722 0.1382135600 0.0050492007 0.0369360000 531315746 0 1779896320 -0.0622605346 -0.1104191020 -0.0276678074 684 1311867741.4153189659 0.1211813092 0.0962714434 0.1382135600 0.0050470475 0.0282960000 531394440 0 1780662272 -0.0622605346 -0.1104191020 -0.0276678074 685 1311867741.4480650425 0.1217274666 0.0963086055 0.1382135600 0.0050455568 0.0339140000 531473038 0 1781276672 -0.0622605346 -0.1104191020 -0.0276678074 686 1311867741.4784660339 0.1222853363 0.0963464724 0.1382135600 0.0050426633 0.0372590000 531551604 0 1781911552 -0.0622605346 -0.1104191020 -0.0276678074 687 1311867741.5143730640 0.1226907745 0.0963848193 0.1382135600 0.0050419168 0.0343630000 531630234 0 1782546432 -0.0622605346 -0.1104191020 -0.0276678074 688 1311867741.5461940765 0.1230728105 0.0964236100 0.1382135600 0.0050409618 0.0351190000 531708832 0 1783181312 -0.0622605346 -0.1104191020 -0.0276678074 689 1311867741.5782639980 0.1235913336 0.0964630407 0.1382135600 0.0050384025 0.0411150000 531787462 0 1783816192 -0.0622605346 -0.1104191020 -0.0276678074 690 1311867741.6143341064 0.1237591058 0.0965026002 0.1382135600 0.0050396796 0.0441080000 531866124 0 1784598528 -0.0622605346 -0.1104191020 -0.0276678074 691 1311867741.6464450359 0.1244172081 0.0965429976 0.1382135600 0.0050476722 0.0295190000 531944722 0 1785212928 -0.0622605346 -0.1104191020 -0.0276678074 692 1311867741.6783308983 0.1248755679 0.0965839406 0.1382135600 0.0050448432 0.0341080000 532023320 0 1785847808 -0.0622605346 -0.1104191020 -0.0276678074 693 1311867741.7144010067 0.1253561080 0.0966254589 0.1382135600 0.0050416424 0.0405130000 532101950 0 1784496128 -0.0622605346 -0.1104191020 -0.0276678074 694 1311867741.7463901043 0.1258708984 0.0966675993 0.1382135600 0.0050406032 0.0361280000 532180580 0 1785114624 -0.0622605346 -0.1104191020 -0.0276678074 695 1311867741.7783830166 0.1263251305 0.0967102720 0.1382135600 0.0050371523 0.0347160000 532259178 0 1783451648 -0.0622605346 -0.1104191020 -0.0276678074 696 1311867741.8143899441 0.1267803013 0.0967534761 0.1382135600 0.0050350851 0.0376290000 532337808 0 1784074240 -0.0622605346 -0.1104191020 -0.0276678074 697 1311867741.8486139774 0.1273518503 0.0967973762 0.1382135600 0.0050366499 0.0344670000 532416470 0 1783472128 -0.0622605346 -0.1104191020 -0.0276678074 698 1311867741.8782730103 0.1279568225 0.0968420172 0.1382135600 0.0050404761 0.0454220000 532495036 0 1784233984 -0.0622605346 -0.1104191020 -0.0276678074 699 1311867741.9144229889 0.1287127286 0.0968876119 0.1382135600 0.0050392043 0.0436730000 532573698 0 1782706176 -0.0622605346 -0.1104191020 -0.0276678074 700 1311867741.9468739033 0.1292435378 0.0969338347 0.1382135600 0.0050371719 0.0381000000 532652296 0 1783341056 -0.0622605346 -0.1104191020 -0.0276678074 701 1311867741.9784300327 0.1296364665 0.0969804861 0.1382135600 0.0050369531 0.0386850000 532730894 0 1781690368 -0.0622605346 -0.1104191020 -0.0276678074 702 1311867742.0142560005 0.1305405796 0.0970282925 0.1382135600 0.0050359952 0.0387920000 532809556 0 1782452224 -0.0622605346 -0.1104191020 -0.0276678074 703 1311867742.0462529659 0.1312348992 0.0970769505 0.1382135600 0.0050345961 0.0383870000 532888122 0 1781927936 -0.0622605346 -0.1104191020 -0.0276678074 704 1311867742.0786769390 0.1321456283 0.0971267640 0.1382135600 0.0050340717 0.0455450000 532966720 0 1782726656 -0.0622605346 -0.1104191020 -0.0276678074 705 1311867742.1144309044 0.1333292276 0.0971781150 0.1382135600 0.0050349486 0.0353280000 533045318 0 1781039104 -0.0622605346 -0.1104191020 -0.0276678074 706 1311867742.1462900639 0.1337604076 0.0972299313 0.1382135600 0.0050342164 0.0406600000 533123916 0 1781673984 -0.0622605346 -0.1104191020 -0.0276678074 707 1311867742.1782898903 0.1345163733 0.0972826702 0.1382135600 0.0050317135 0.0405690000 533202546 0 1781059584 -0.0622605346 -0.1104191020 -0.0276678074 708 1311867742.2143509388 0.1353551745 0.0973364450 0.1382135600 0.0050339255 0.0362130000 533281176 0 1781694464 -0.0622605346 -0.1104191020 -0.0276678074 709 1311867742.2463901043 0.1359306723 0.0973908797 0.1382135600 0.0050350853 0.0419570000 533359806 0 1780170752 -0.0622605346 -0.1104191020 -0.0276678074 710 1311867742.2785389423 0.1362949610 0.0974456742 0.1382135600 0.0050378167 0.0474850000 533438436 0 1779425280 -0.0622605346 -0.1104191020 -0.0276678074 711 1311867742.3143260479 0.1365803331 0.0975007159 0.1382135600 0.0050349787 0.0370160000 533517066 0 1780023296 -0.0622605346 -0.1104191020 -0.0276678074 712 1311867742.3464210033 0.1366863549 0.0975557519 0.1382135600 0.0050316537 0.0378080000 533595664 0 1778642944 -0.0622605346 -0.1104191020 -0.0276678074 713 1311867742.3784179688 0.1368096024 0.0976108064 0.1382135600 0.0050287949 0.0348590000 533674262 0 1779261440 -0.0622605346 -0.1104191020 -0.0276678074 714 1311867742.4143109322 0.1370446682 0.0976660359 0.1382135600 0.0050254461 0.0332470000 533752924 0 1777766400 -0.0622605346 -0.1104191020 -0.0276678074 715 1311867742.4462630749 0.1374091804 0.0977216207 0.1382135600 0.0050229679 0.0414240000 533831490 0 1778372608 -0.0622605346 -0.1104191020 -0.0276678074 716 1311867742.4782900810 0.1376919895 0.0977774452 0.1382135600 0.0050223775 0.0409130000 533910120 0 1778028544 -0.0622605346 -0.1104191020 -0.0276678074 717 1311867742.5144250393 0.1380869299 0.0978336649 0.1382135600 0.0050190927 0.0396690000 533988750 0 1778626560 -0.0622605346 -0.1104191020 -0.0276678074 718 1311867742.5463809967 0.1384115070 0.0978901800 0.1384115070 0.0050157738 0.0442590000 534067380 0 1776836608 -0.0622605346 -0.1104191020 -0.0276678074 719 1311867742.5783019066 0.1387207806 0.0979469680 0.1387207806 0.0050127409 0.0377160000 534145978 0 1777520640 -0.0622605346 -0.1104191020 -0.0276678074 720 1311867742.6142919064 0.1390839219 0.0980041027 0.1390839219 0.0050103511 0.0440090000 534224608 0 1777102848 -0.0622605346 -0.1104191020 -0.0276678074 721 1311867742.6462519169 0.1392100006 0.0980612537 0.1392100006 0.0050076592 0.0359420000 534303206 0 1777737728 -0.0622605346 -0.1104191020 -0.0276678074 722 1311867742.6823589802 0.1393166035 0.0981183941 0.1393166035 0.0050060183 0.0391760000 534381900 0 1777123328 -0.0622605346 -0.1104191020 -0.0276678074 723 1311867742.7143929005 0.1394775659 0.0981755990 0.1394775659 0.0050037038 0.0389250000 534460498 0 1777758208 -0.0622605346 -0.1104191020 -0.0276678074 724 1311867742.7463440895 0.1397172809 0.0982329771 0.1397172809 0.0050019742 0.0351390000 534539096 0 1776250880 -0.0622605346 -0.1104191020 -0.0276678074 725 1311867742.7823669910 0.1399456114 0.0982905117 0.1399456114 0.0050013051 0.0448240000 534617758 0 1776848896 -0.0622605346 -0.1104191020 -0.0276678074 726 1311867742.8142659664 0.1397794336 0.0983476590 0.1399456114 0.0049986170 0.0424000000 534696356 0 1775996928 -0.0622605346 -0.1104191020 -0.0276678074 727 1311867742.8464159966 0.1402421147 0.0984052855 0.1402421147 0.0050004435 0.0405050000 534774954 0 1776631808 -0.0622605346 -0.1104191020 -0.0276678074 728 1311867742.8823649883 0.1404867619 0.0984630897 0.1404867619 0.0049978479 0.0392220000 534853616 0 1775452160 -0.0622605346 -0.1104191020 -0.0276678074 729 1311867742.9142940044 0.1407492608 0.0985210954 0.1407492608 0.0049966440 0.0358790000 534932182 0 1776087040 -0.0622605346 -0.1104191020 -0.0276678074 730 1311867742.9464008808 0.1408327818 0.0985790566 0.1408327818 0.0050026607 0.0382380000 535010812 0 1774456832 -0.0622605346 -0.1104191020 -0.0276678074 731 1311867742.9822909832 0.1410789639 0.0986371961 0.1410789639 0.0050045979 0.0402210000 535089474 0 1775091712 -0.0622605346 -0.1104191020 -0.0276678074 732 1311867743.0144410133 0.1413589567 0.0986955591 0.1413589567 0.0050012137 0.0342810000 535168040 0 1774600192 -0.0622605346 -0.1104191020 -0.0276678074 733 1311867743.0463359356 0.1414497197 0.0987538868 0.1414497197 0.0049979434 0.0387240000 535246638 0 1775235072 -0.0622605346 -0.1104191020 -0.0276678074 734 1311867743.0824029446 0.1418789327 0.0988126402 0.1418789327 0.0050021862 0.0422540000 535325300 0 1773547520 -0.0622605346 -0.1104191020 -0.0276678074 735 1311867743.1142439842 0.1421289295 0.0988715739 0.1421289295 0.0049989858 0.0392440000 535403866 0 1774182400 -0.0622605346 -0.1104191020 -0.0276678074 736 1311867743.1462910175 0.1423495263 0.0989306473 0.1423495263 0.0049975952 0.0363880000 535482464 0 1773674496 -0.0622605346 -0.1104191020 -0.0276678074 737 1311867743.1824851036 0.1427160800 0.0989900576 0.1427160800 0.0049963346 0.0387090000 535561158 0 1774309376 -0.0622605346 -0.1104191020 -0.0276678074 738 1311867743.2143781185 0.1433109939 0.0990501131 0.1433109939 0.0049955531 0.0379620000 535639692 0 1772658688 -0.0622605346 -0.1104191020 -0.0276678074 739 1311867743.2463059425 0.1434334815 0.0991101718 0.1434334815 0.0049936167 0.0353800000 535718290 0 1773293568 -0.0622605346 -0.1104191020 -0.0276678074 740 1311867743.2824048996 0.1436153948 0.0991703140 0.1436153948 0.0049903771 0.0389990000 535796984 0 1772548096 -0.0622605346 -0.1104191020 -0.0276678074 741 1311867743.3143129349 0.1438202858 0.0992305703 0.1438202858 0.0049873778 0.0382540000 535875582 0 1773182976 -0.0622605346 -0.1104191020 -0.0276678074 742 1311867743.3463358879 0.1437741965 0.0992906022 0.1438202858 0.0049846080 0.0361450000 535954148 0 1771642880 -0.0622605346 -0.1104191020 -0.0276678074 743 1311867743.3822519779 0.1439569592 0.0993507184 0.1439569592 0.0049829229 0.0405330000 536032810 0 1772277760 -0.0622605346 -0.1104191020 -0.0276678074 744 1311867743.4145960808 0.1438130736 0.0994104796 0.1439569592 0.0049802007 0.0397820000 536111472 0 1771663360 -0.0622605346 -0.1104191020 -0.0276678074 745 1311867743.4463078976 0.1439432949 0.0994702552 0.1439569592 0.0049812214 0.0427270000 536190006 0 1770233856 -0.0622605346 -0.1104191020 -0.0276678074 746 1311867743.4828910828 0.1441495717 0.0995301471 0.1441495717 0.0049780216 0.0355630000 536268700 0 1771008000 -0.0622605346 -0.1104191020 -0.0276678074 747 1311867743.5145409107 0.1441662908 0.0995899009 0.1441662908 0.0049747161 0.0422070000 536347298 0 1769865216 -0.0622605346 -0.1104191020 -0.0276678074 748 1311867743.5463149548 0.1443876773 0.0996497910 0.1443876773 0.0049734913 0.0390320000 536425864 0 1770536960 -0.0622605346 -0.1104191020 -0.0276678074 749 1311867743.5824689865 0.1445255727 0.0997097053 0.1445255727 0.0049727264 0.0379030000 536504526 0 1770409984 -0.0622605346 -0.1104191020 -0.0276678074 750 1311867743.6143229008 0.1450153887 0.0997701129 0.1450153887 0.0049766879 0.0364620000 536583092 0 1771134976 -0.0622605346 -0.1104191020 -0.0276678074 751 1311867743.6465840340 0.1442104280 0.0998292877 0.1450153887 0.0049783725 0.0403930000 536661722 0 1769394176 -0.0622605346 -0.1104191020 -0.0276678074 752 1311867743.6827230453 0.1440479606 0.0998880891 0.1450153887 0.0049750790 0.0385570000 536740384 0 1770012672 -0.0622605346 -0.1104191020 -0.0276678074 753 1311867743.7143280506 0.1437582821 0.0999463497 0.1450153887 0.0049724585 0.0425730000 536818982 0 1769521152 -0.0622605346 -0.1104191020 -0.0276678074 754 1311867743.7468709946 0.1436496079 0.1000043116 0.1450153887 0.0049707327 0.0353790000 536897580 0 1770246144 -0.0622605346 -0.1104191020 -0.0276678074 755 1311867743.7823519707 0.1432739347 0.1000616223 0.1450153887 0.0049682534 0.0386480000 536976242 0 1768505344 -0.0622605346 -0.1104191020 -0.0276678074 756 1311867743.8146069050 0.1429439634 0.1001183450 0.1450153887 0.0049652574 0.0383950000 537054808 0 1769123840 -0.0622605346 -0.1104191020 -0.0276678074 757 1311867743.8466429710 0.1425501257 0.1001743975 0.1450153887 0.0049621713 0.0343960000 537133406 0 1767333888 -0.0622605346 -0.1104191020 -0.0276678074 758 1311867743.8825910091 0.1424670368 0.1002301926 0.1450153887 0.0049591449 0.0383350000 537212100 0 1767997440 -0.0622605346 -0.1104191020 -0.0276678074 759 1311867743.9143130779 0.1423856616 0.1002857334 0.1450153887 0.0049563297 0.0392060000 537290698 0 1767600128 -0.0622605346 -0.1104191020 -0.0276678074 760 1311867743.9475100040 0.1422054917 0.1003408910 0.1450153887 0.0049540574 0.0332480000 537369296 0 1768198144 -0.0622605346 -0.1104191020 -0.0276678074 761 1311867743.9825859070 0.1423897743 0.1003961457 0.1450153887 0.0049519199 0.0446220000 537447926 0 1767489536 -0.0622605346 -0.1104191020 -0.0276678074 762 1311867744.0145549774 0.1424234062 0.1004512996 0.1450153887 0.0049515505 0.0385740000 537526492 0 1768124416 -0.0622605346 -0.1104191020 -0.0276678074 763 1311867744.0465490818 0.1424570829 0.1005063531 0.1450153887 0.0049487499 0.0343370000 537605122 0 1766436864 -0.0622605346 -0.1104191020 -0.0276678074 764 1311867744.0825159550 0.1422398388 0.1005609781 0.1450153887 0.0049486191 0.0386250000 537683784 0 1767071744 -0.0622605346 -0.1104191020 -0.0276678074 765 1311867744.1155200005 0.1424841136 0.1006157795 0.1450153887 0.0049474135 0.0384460000 537762286 0 1765965824 -0.0622605346 -0.1104191020 -0.0276678074 766 1311867744.1485710144 0.1428054571 0.1006708574 0.1450153887 0.0049473379 0.0365120000 537840916 0 1766690816 -0.0622605346 -0.1104191020 -0.0276678074 767 1311867744.1825850010 0.1431979984 0.1007263035 0.1450153887 0.0049544157 0.0439490000 537919578 0 1765421056 -0.0622605346 -0.1104191020 -0.0276678074 768 1311867744.2144110203 0.1430865526 0.1007814601 0.1450153887 0.0049523520 0.0398940000 537998144 0 1766182912 -0.0622605346 -0.1104191020 -0.0276678074 769 1311867744.2465009689 0.1432907730 0.1008367388 0.1450153887 0.0049497443 0.0445260000 538076742 0 1765330944 -0.0622605346 -0.1104191020 -0.0276678074 770 1311867744.2824139595 0.1434988230 0.1008921441 0.1450153887 0.0049562359 0.0365690000 538155404 0 1765965824 -0.0622605346 -0.1104191020 -0.0276678074 771 1311867744.3143589497 0.1434212625 0.1009473051 0.1450153887 0.0049556315 0.0391120000 538234002 0 1764569088 -0.0622605346 -0.1104191020 -0.0276678074 772 1311867744.3465039730 0.1435424834 0.1010024802 0.1450153887 0.0049525924 0.0413480000 538312600 0 1765294080 -0.0622605346 -0.1104191020 -0.0276678074 773 1311867744.3825259209 0.1440160125 0.1010581251 0.1450153887 0.0049497025 0.0375820000 538391294 0 1764659200 -0.0622605346 -0.1104191020 -0.0276678074 774 1311867744.4144279957 0.1439962834 0.1011136008 0.1450153887 0.0049466127 0.0349310000 538469860 0 1765294080 -0.0622605346 -0.1104191020 -0.0276678074 775 1311867744.4466331005 0.1440752149 0.1011690351 0.1450153887 0.0049460094 0.0393000000 538548458 0 1764569088 -0.0622605346 -0.1104191020 -0.0276678074 776 1311867744.4825220108 0.1443539858 0.1012246858 0.1450153887 0.0049428613 0.0383460000 538627120 0 1765294080 -0.0622605346 -0.1104191020 -0.0276678074 777 1311867744.5144040585 0.1445457339 0.1012804401 0.1450153887 0.0049400793 0.0339870000 538705750 0 1764823040 -0.0622605346 -0.1104191020 -0.0276678074 778 1311867744.5464859009 0.1445368975 0.1013360396 0.1450153887 0.0049374492 0.0392440000 538784316 0 1765457920 -0.0622605346 -0.1104191020 -0.0276678074 779 1311867744.5825068951 0.1449305266 0.1013920017 0.1450153887 0.0049375400 0.0413470000 538862978 0 1764659200 -0.0622605346 -0.1104191020 -0.0276678074 780 1311867744.6143949032 0.1446029097 0.1014474003 0.1450153887 0.0049367338 0.0333670000 538941576 0 1765294080 -0.0622605346 -0.1104191020 -0.0276678074 781 1311867744.6464331150 0.1447208971 0.1015028081 0.1450153887 0.0049336586 0.0369540000 539020174 0 1764823040 -0.0622605346 -0.1104191020 -0.0276678074 782 1311867744.6825749874 0.1452497393 0.1015587505 0.1452497393 0.0049324276 0.0362660000 539098868 0 1765457920 -0.0622605346 -0.1104191020 -0.0276678074 783 1311867744.7144720554 0.1449601352 0.1016141801 0.1452497393 0.0049339884 0.0374650000 539177466 0 1763770368 -0.0622605346 -0.1104191020 -0.0276678074 784 1311867744.7465579510 0.1451214254 0.1016696741 0.1452497393 0.0049313857 0.0416100000 539256032 0 1764405248 -0.0622605346 -0.1104191020 -0.0276678074 785 1311867744.7823460102 0.1454057097 0.1017253888 0.1454057097 0.0049326852 0.0389440000 539334694 0 1763934208 -0.0622605346 -0.1104191020 -0.0276678074 786 1311867744.8143870831 0.1447423398 0.1017801177 0.1454057097 0.0049354565 0.0361690000 539413324 0 1764659200 -0.0622605346 -0.1104191020 -0.0276678074 787 1311867744.8480839729 0.1447262019 0.1018346871 0.1454057097 0.0049325178 0.0375340000 539491954 0 1764024320 -0.0622605346 -0.1104191020 -0.0276678074 788 1311867744.8824019432 0.1451190710 0.1018896165 0.1454057097 0.0049349400 0.0416950000 539570552 0 1764806656 -0.0622605346 -0.1104191020 -0.0276678074 789 1311867744.9143979549 0.1444135010 0.1019435124 0.1454057097 0.0049362417 0.0409680000 539649150 0 1764171776 -0.0622605346 -0.1104191020 -0.0276678074 790 1311867744.9465999603 0.1445179135 0.1019974040 0.1454057097 0.0049334937 0.0429480000 539727748 0 1764806656 -0.0622605346 -0.1104191020 -0.0276678074 791 1311867744.9824030399 0.1447467506 0.1020514487 0.1454057097 0.0049356411 0.0371220000 539806410 0 1764007936 -0.0622605346 -0.1104191020 -0.0276678074 792 1311867745.0145809650 0.1445860267 0.1021051540 0.1454057097 0.0049336291 0.0388100000 539884976 0 1764642816 -0.0622605346 -0.1104191020 -0.0276678074 793 1311867745.0466170311 0.1446691751 0.1021588287 0.1454057097 0.0049419199 0.0399750000 539963574 0 1764171776 -0.0622605346 -0.1104191020 -0.0276678074 794 1311867745.0825409889 0.1447674334 0.1022124919 0.1454057097 0.0049430315 0.0357050000 540042236 0 1764806656 -0.0622605346 -0.1104191020 -0.0276678074 795 1311867745.1145880222 0.1445542723 0.1022657520 0.1454057097 0.0049414571 0.0382040000 540120866 0 1764007936 -0.0622605346 -0.1104191020 -0.0276678074 796 1311867745.1469609737 0.1445816755 0.1023189127 0.1454057097 0.0049407467 0.0384600000 540199432 0 1764806656 -0.0622605346 -0.1104191020 -0.0276678074 797 1311867745.1825649738 0.1448177397 0.1023722362 0.1454057097 0.0049431602 0.0355000000 540278094 0 1764282368 -0.0622605346 -0.1104191020 -0.0276678074 798 1311867745.2146100998 0.1446799934 0.1024252535 0.1454057097 0.0049440080 0.0369980000 540356660 0 1764917248 -0.0622605346 -0.1104191020 -0.0276678074 799 1311867745.2490229607 0.1448340416 0.1024783308 0.1454057097 0.0049410161 0.0408850000 540435322 0 1764134912 -0.0622605346 -0.1104191020 -0.0276678074 800 1311867745.2828390598 0.1449104995 0.1025313710 0.1454057097 0.0049382870 0.0331480000 540513952 0 1764933632 -0.0622605346 -0.1104191020 -0.0276678074 801 1311867745.3148200512 0.1449418217 0.1025843179 0.1454057097 0.0049365834 0.0394990000 540592550 0 1764298752 -0.0622605346 -0.1104191020 -0.0276678074 802 1311867745.3468639851 0.1451783329 0.1026374276 0.1454057097 0.0049356460 0.0356090000 540671116 0 1764933632 -0.0622605346 -0.1104191020 -0.0276678074 803 1311867745.3826758862 0.1452094316 0.1026904438 0.1454057097 0.0049355564 0.0338080000 540749778 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 804 1311867745.4151210785 0.1454105228 0.1027435783 0.1454105228 0.0049337780 0.0393110000 540828376 0 1764777984 -0.0622605346 -0.1104191020 -0.0276678074 805 1311867745.4468600750 0.1449864656 0.1027960539 0.1454105228 0.0049333708 0.0405750000 540906974 0 1764306944 -0.0622605346 -0.1104191020 -0.0276678074 806 1311867745.4826099873 0.1456496865 0.1028492222 0.1456496865 0.0049407813 0.0434320000 540985636 0 1764941824 -0.0622605346 -0.1104191020 -0.0276678074 807 1311867745.5146310329 0.1459303945 0.1029026065 0.1459303945 0.0049400404 0.0363510000 541064234 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 808 1311867745.5466570854 0.1458800435 0.1029557964 0.1459303945 0.0049391627 0.0390440000 541142832 0 1764941824 -0.0622605346 -0.1104191020 -0.0276678074 809 1311867745.5826489925 0.1457262486 0.1030086647 0.1459303945 0.0049468269 0.0381820000 541221526 0 1764417536 -0.0622605346 -0.1104191020 -0.0276678074 810 1311867745.6148099899 0.1456892937 0.1030613568 0.1459303945 0.0049484638 0.0361800000 541300092 0 1765052416 -0.0622605346 -0.1104191020 -0.0276678074 811 1311867745.6478629112 0.1457379460 0.1031139790 0.1459303945 0.0049513245 0.0353690000 541378722 0 1764270080 -0.0622605346 -0.1104191020 -0.0276678074 812 1311867745.6825740337 0.1458216459 0.1031665747 0.1459303945 0.0049510089 0.0363360000 541457352 0 1765068800 -0.0622605346 -0.1104191020 -0.0276678074 813 1311867745.7146449089 0.1464443654 0.1032198069 0.1464443654 0.0049516214 0.0331310000 541535982 0 1764433920 -0.0622605346 -0.1104191020 -0.0276678074 814 1311867745.7466299534 0.1462810785 0.1032727077 0.1464443654 0.0049493835 0.0374660000 541614548 0 1765068800 -0.0622605346 -0.1104191020 -0.0276678074 815 1311867745.7826039791 0.1466575712 0.1033259407 0.1466575712 0.0049489180 0.0386290000 541693210 0 1763762176 -0.0622605346 -0.1104191020 -0.0276678074 816 1311867745.8145930767 0.1469440013 0.1033793942 0.1469440013 0.0049461515 0.0323630000 541771840 0 1764433920 -0.0622605346 -0.1104191020 -0.0276678074 817 1311867745.8465878963 0.1469078958 0.1034326726 0.1469440013 0.0049451453 0.0388250000 541850406 0 1763647488 -0.0622605346 -0.1104191020 -0.0276678074 818 1311867745.8826999664 0.1468252838 0.1034857198 0.1469440013 0.0049444245 0.0370610000 541929100 0 1764433920 -0.0622605346 -0.1104191020 -0.0276678074 819 1311867745.9146699905 0.1471228600 0.1035390008 0.1471228600 0.0049465218 0.0332580000 542007698 0 1763016704 -0.0622605346 -0.1104191020 -0.0276678074 820 1311867745.9467720985 0.1470186412 0.1035920248 0.1471228600 0.0049462155 0.0406490000 542086232 0 1763778560 -0.0622605346 -0.1104191020 -0.0276678074 821 1311867745.9827370644 0.1474540383 0.1036454499 0.1474540383 0.0049549547 0.0371370000 542164926 0 1763143680 -0.0622605346 -0.1104191020 -0.0276678074 822 1311867746.0146980286 0.1470692158 0.1036982769 0.1474540383 0.0049655340 0.0342140000 542243492 0 1763868672 -0.0622605346 -0.1104191020 -0.0276678074 823 1311867746.0465910435 0.1472184211 0.1037511568 0.1474540383 0.0049666775 0.0363870000 542322090 0 1763651584 -0.0622605346 -0.1104191020 -0.0276678074 824 1311867746.0825810432 0.1476105005 0.1038043841 0.1476105005 0.0049676438 0.0373970000 542400752 0 1764544512 -0.0622605346 -0.1104191020 -0.0276678074 825 1311867746.1145880222 0.1477552801 0.1038576579 0.1477552801 0.0049685736 0.0458620000 542479350 0 1763926016 -0.0622605346 -0.1104191020 -0.0276678074 826 1311867746.1468839645 0.1477828026 0.1039108361 0.1477828026 0.0049700835 0.0464910000 542557948 0 1764560896 -0.0622605346 -0.1104191020 -0.0276678074 827 1311867746.1826870441 0.1479820162 0.1039641265 0.1479820162 0.0049681151 0.0385330000 542636642 0 1763926016 -0.0622605346 -0.1104191020 -0.0276678074 828 1311867746.2146589756 0.1479311883 0.1040172268 0.1479820162 0.0049654336 0.0403480000 542715240 0 1764651008 -0.0622605346 -0.1104191020 -0.0276678074 829 1311867746.2467160225 0.1477671713 0.1040700012 0.1479820162 0.0049676634 0.0375590000 542793806 0 1764052992 -0.0622605346 -0.1104191020 -0.0276678074 830 1311867746.2827060223 0.1472484022 0.1041220233 0.1479820162 0.0049736679 0.0406490000 542872500 0 1764687872 -0.0622605346 -0.1104191020 -0.0276678074 831 1311867746.3147549629 0.1475169063 0.1041742434 0.1479820162 0.0049756900 0.0386620000 542951066 0 1763905536 -0.0622605346 -0.1104191020 -0.0276678074 832 1311867746.3466849327 0.1472875625 0.1042260623 0.1479820162 0.0049763885 0.0399950000 543029664 0 1764540416 -0.0622605346 -0.1104191020 -0.0276678074 833 1311867746.3826711178 0.1471077502 0.1042775409 0.1479820162 0.0049828522 0.0403240000 543108358 0 1764032512 -0.0622605346 -0.1104191020 -0.0276678074 834 1311867746.4146850109 0.1465751827 0.1043282575 0.1479820162 0.0049831334 0.0380000000 543186924 0 1764667392 -0.0622605346 -0.1104191020 -0.0276678074 835 1311867746.4467220306 0.1468740851 0.1043792106 0.1479820162 0.0049857419 0.0343380000 543265522 0 1764179968 -0.0622605346 -0.1104191020 -0.0276678074 836 1311867746.4826610088 0.1465962231 0.1044297094 0.1479820162 0.0049853031 0.0408090000 543344184 0 1764904960 -0.0622605346 -0.1104191020 -0.0276678074 837 1311867746.5145390034 0.1462246478 0.1044796436 0.1479820162 0.0049834250 0.0388850000 543422814 0 1764052992 -0.0622605346 -0.1104191020 -0.0276678074 838 1311867746.5468180180 0.1464352012 0.1045297099 0.1479820162 0.0049821835 0.0349120000 543501380 0 1764777984 -0.0622605346 -0.1104191020 -0.0276678074 839 1311867746.5825469494 0.1462741941 0.1045794650 0.1479820162 0.0049795982 0.0393850000 543580042 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 840 1311867746.6145970821 0.1461523175 0.1046289565 0.1479820162 0.0049795174 0.0395420000 543658640 0 1764941824 -0.0622605346 -0.1104191020 -0.0276678074 841 1311867746.6467320919 0.1460852325 0.1046782505 0.1479820162 0.0049773186 0.0364610000 543737238 0 1764052992 -0.0622605346 -0.1104191020 -0.0276678074 842 1311867746.6827459335 0.1460470706 0.1047273821 0.1479820162 0.0049814504 0.0412450000 543815932 0 1764777984 -0.0622605346 -0.1104191020 -0.0276678074 843 1311867746.7145600319 0.1459582746 0.1047762918 0.1479820162 0.0049804863 0.0394610000 543894498 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 844 1311867746.7465538979 0.1457429379 0.1048248305 0.1479820162 0.0049779434 0.0330450000 543973096 0 1764777984 -0.0622605346 -0.1104191020 -0.0276678074 845 1311867746.7827410698 0.1456119567 0.1048730993 0.1479820162 0.0049757633 0.0293210000 544051790 0 1764306944 -0.0622605346 -0.1104191020 -0.0276678074 846 1311867746.8146500587 0.1456935406 0.1049213504 0.1479820162 0.0049747784 0.0427690000 544130388 0 1764941824 -0.0622605346 -0.1104191020 -0.0276678074 847 1311867746.8467810154 0.1455204189 0.1049692832 0.1479820162 0.0049734798 0.0368630000 544208954 0 1764290560 -0.0622605346 -0.1104191020 -0.0276678074 848 1311867746.8827800751 0.1457644850 0.1050173908 0.1479820162 0.0049712560 0.0324270000 544287648 0 1764888576 -0.0622605346 -0.1104191020 -0.0276678074 849 1311867746.9145510197 0.1460705549 0.1050657455 0.1479820162 0.0049709402 0.0399240000 544366246 0 1764417536 -0.0622605346 -0.1104191020 -0.0276678074 850 1311867746.9466409683 0.1459385604 0.1051138311 0.1479820162 0.0049730195 0.0357070000 544444812 0 1765068800 -0.0622605346 -0.1104191020 -0.0276678074 851 1311867746.9826910496 0.1460354924 0.1051619177 0.1479820162 0.0049706925 0.0391040000 544523506 0 1764270080 -0.0622605346 -0.1104191020 -0.0276678074 852 1311867747.0145750046 0.1466277540 0.1052105865 0.1479820162 0.0049741351 0.0338310000 544525260 0 1764904960 -0.0622605346 -0.1104191020 -0.0276678074 853 1311867747.0465710163 0.1460879743 0.1052585084 0.1479820162 0.0049729831 0.0370210000 544603858 0 1764270080 -0.0622605346 -0.1104191020 -0.0276678074 854 1311867747.0825779438 0.1461850852 0.1053064318 0.1479820162 0.0049711506 0.0407750000 544682520 0 1764904960 -0.0622605346 -0.1104191020 -0.0276678074 855 1311867747.1146280766 0.1464209706 0.1053545190 0.1479820162 0.0049687437 0.0424170000 544761118 0 1764179968 -0.0622605346 -0.1104191020 -0.0276678074 856 1311867747.1475419998 0.1466784775 0.1054027947 0.1479820162 0.0049660505 0.0403050000 544839748 0 1764777984 -0.0622605346 -0.1104191020 -0.0276678074 857 1311867747.1825768948 0.1465787590 0.1054508413 0.1479820162 0.0049635886 0.0353450000 544918378 0 1764270080 -0.0622605346 -0.1104191020 -0.0276678074 858 1311867747.2146298885 0.1465787590 0.1054987759 0.1479820162 0.0049633593 0.0412080000 544996976 0 1764904960 -0.0622605346 -0.1104191020 -0.0276678074 859 1311867747.2468459606 0.1467217654 0.1055467654 0.1479820162 0.0049618135 0.0471370000 545075574 0 1764179968 -0.0622605346 -0.1104191020 -0.0276678074 860 1311867747.2828319073 0.1467277855 0.1055946503 0.1479820162 0.0049829134 0.0411980000 545154236 0 1762254848 -0.0622605346 -0.1104191020 -0.0276678074 861 1311867747.3145720959 0.1470912844 0.1056428462 0.1479820162 0.0049832141 0.0422080000 545232802 0 1762889728 -0.0622605346 -0.1104191020 -0.0276678074 862 1311867747.3468389511 0.1468631029 0.1056906655 0.1479820162 0.0049849512 0.0374620000 545311432 0 1762131968 -0.0622605346 -0.1104191020 -0.0276678074 863 1311867747.3826510906 0.1470229179 0.1057385592 0.1479820162 0.0049830595 0.0453900000 545390094 0 1762742272 -0.0622605346 -0.1104191020 -0.0276678074 864 1311867747.4149589539 0.1473197639 0.1057866856 0.1479820162 0.0049828823 0.0410090000 545472364 0 1763401728 -0.0622605346 -0.1104191020 -0.0276678074 865 1311867747.4467270374 0.1473899186 0.1058347818 0.1479820162 0.0049812214 0.0373420000 545550930 0 1764036608 -0.0622605346 -0.1104191020 -0.0276678074 866 1311867747.4827909470 0.1472303271 0.1058825827 0.1479820162 0.0049788087 0.0411360000 545629624 0 1763528704 -0.0622605346 -0.1104191020 -0.0276678074 867 1311867747.5157780647 0.1475284249 0.1059306171 0.1479820162 0.0049771401 0.0397910000 545708190 0 1764290560 -0.0622605346 -0.1104191020 -0.0276678074 868 1311867747.5466940403 0.1475818008 0.1059786023 0.1479820162 0.0049826873 0.0386300000 545786788 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 869 1311867747.5828940868 0.1476907730 0.1060266025 0.1479820162 0.0049843708 0.0472620000 545865482 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 870 1311867747.6151599884 0.1476637423 0.1060744613 0.1479820162 0.0049820622 0.0438990000 545944048 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 871 1311867747.6474270821 0.1477469206 0.1061223057 0.1479820162 0.0049820617 0.0364030000 546022678 0 1764016128 -0.0622605346 -0.1104191020 -0.0276678074 872 1311867747.6827778816 0.1475244015 0.1061697852 0.1479820162 0.0049797228 0.0407450000 546101308 0 1763508224 -0.0622605346 -0.1104191020 -0.0276678074 873 1311867747.7146589756 0.1472091675 0.1062167948 0.1479820162 0.0049771654 0.0410190000 546179938 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 874 1311867747.7479619980 0.1471792907 0.1062636626 0.1479820162 0.0049744787 0.0437560000 546258504 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 875 1311867747.7826869488 0.1470777243 0.1063103073 0.1479820162 0.0049721863 0.0398230000 546337166 0 1764016128 -0.0622605346 -0.1104191020 -0.0276678074 876 1311867747.8149020672 0.1467578262 0.1063564802 0.1479820162 0.0049700085 0.0435320000 546415764 0 1764306944 -0.0622605346 -0.1104191020 -0.0276678074 877 1311867747.8466539383 0.1467876732 0.1064025819 0.1479820162 0.0049674163 0.0388190000 546494330 0 1762639872 -0.0622605346 -0.1104191020 -0.0276678074 878 1311867747.8827810287 0.1468073130 0.1064486010 0.1479820162 0.0049685534 0.0430580000 546573024 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 879 1311867747.9150440693 0.1465502381 0.1064942229 0.1479820162 0.0049694015 0.0379340000 546651654 0 1762619392 -0.0622605346 -0.1104191020 -0.0276678074 880 1311867747.9477820396 0.1463029832 0.1065394601 0.1479820162 0.0049673474 0.0442440000 546730252 0 1763381248 -0.0622605346 -0.1104191020 -0.0276678074 881 1311867747.9826579094 0.1460522413 0.1065843100 0.1479820162 0.0049663545 0.0479750000 546808882 0 1762619392 -0.0622605346 -0.1104191020 -0.0276678074 882 1311867748.0146598816 0.1456727982 0.1066286280 0.1479820162 0.0049666520 0.0405740000 546887480 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 883 1311867748.0469100475 0.1452976465 0.1066724208 0.1479820162 0.0049665875 0.0380540000 546966046 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 884 1311867748.0828750134 0.1449852437 0.1067157611 0.1479820162 0.0049674305 0.0390980000 547044772 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 885 1311867748.1150569916 0.1447725445 0.1067587631 0.1479820162 0.0049686404 0.0416450000 547123338 0 1762365440 -0.0622605346 -0.1104191020 -0.0276678074 886 1311867748.1486010551 0.1447230875 0.1068016122 0.1479820162 0.0049665982 0.0427760000 547201968 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 887 1311867748.1831040382 0.1446571499 0.1068442904 0.1479820162 0.0049646568 0.0409540000 547280566 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 888 1311867748.2148320675 0.1445449144 0.1068867461 0.1479820162 0.0049627010 0.0494460000 547359196 0 1762619392 -0.0622605346 -0.1104191020 -0.0276678074 889 1311867748.2466599941 0.1446028352 0.1069291714 0.1479820162 0.0049660991 0.0442260000 547437762 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 890 1311867748.2827599049 0.1445070058 0.1069713937 0.1479820162 0.0049655428 0.0382130000 547516424 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 891 1311867748.3148829937 0.1442715973 0.1070132570 0.1479820162 0.0049659926 0.0431350000 547595022 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 892 1311867748.3470869064 0.1441816539 0.1070549256 0.1479820162 0.0049732531 0.0381950000 547673620 0 1763037184 -0.0622605346 -0.1104191020 -0.0276678074 893 1311867748.3826999664 0.1441676319 0.1070964852 0.1479820162 0.0049748688 0.0353870000 547752282 0 1763672064 -0.0622605346 -0.1104191020 -0.0276678074 894 1311867748.4148259163 0.1441277415 0.1071379071 0.1479820162 0.0049748695 0.0395380000 547830848 0 1762889728 -0.0622605346 -0.1104191020 -0.0276678074 895 1311867748.4520189762 0.1437391788 0.1071788024 0.1479820162 0.0049778296 0.0385890000 547909542 0 1763524608 -0.0622605346 -0.1104191020 -0.0276678074 896 1311867748.4831318855 0.1438271850 0.1072197046 0.1479820162 0.0049766733 0.0368860000 547988140 0 1762762752 -0.0622605346 -0.1104191020 -0.0276678074 897 1311867748.5149960518 0.1437906474 0.1072604749 0.1479820162 0.0049779195 0.0385110000 548066738 0 1763524608 -0.0622605346 -0.1104191020 -0.0276678074 898 1311867748.5467929840 0.1437042356 0.1073010582 0.1479820162 0.0049789066 0.0373920000 548145304 0 1762889728 -0.0622605346 -0.1104191020 -0.0276678074 899 1311867748.5827159882 0.1436679363 0.1073415108 0.1479820162 0.0049782418 0.0434950000 548223966 0 1763524608 -0.0622605346 -0.1104191020 -0.0276678074 900 1311867748.6147999763 0.1435978413 0.1073817956 0.1479820162 0.0049795352 0.0340340000 548302596 0 1762762752 -0.0622605346 -0.1104191020 -0.0276678074 901 1311867748.6469130516 0.1433949769 0.1074217658 0.1479820162 0.0049824296 0.0404910000 548381130 0 1763524608 -0.0622605346 -0.1104191020 -0.0276678074 902 1311867748.6827559471 0.1432929486 0.1074615343 0.1479820162 0.0049802928 0.0406010000 548459824 0 1762762752 -0.0622605346 -0.1104191020 -0.0276678074 903 1311867748.7147359848 0.1432527751 0.1075011702 0.1479820162 0.0050025118 0.0385250000 548538422 0 1763397632 -0.0622605346 -0.1104191020 -0.0276678074 904 1311867748.7499361038 0.1429627836 0.1075403977 0.1479820162 0.0050003943 0.0374850000 548617052 0 1762635776 -0.0622605346 -0.1104191020 -0.0276678074 905 1311867748.7828259468 0.1427079588 0.1075792569 0.1479820162 0.0049996706 0.0414890000 548695714 0 1763233792 -0.0622605346 -0.1104191020 -0.0276678074 906 1311867748.8151469231 0.1424539983 0.1076177499 0.1479820162 0.0049979875 0.0386860000 548774280 0 1762508800 -0.0622605346 -0.1104191020 -0.0276678074 907 1311867748.8466329575 0.1421190947 0.1076557889 0.1479820162 0.0049966136 0.0352070000 548852846 0 1763143680 -0.0622605346 -0.1104191020 -0.0276678074 908 1311867748.8829579353 0.1416780204 0.1076932583 0.1479820162 0.0049976969 0.0324140000 548931508 0 1762381824 -0.0622605346 -0.1104191020 -0.0276678074 909 1311867748.9149119854 0.1411994994 0.1077301189 0.1479820162 0.0049994522 0.0398200000 549010138 0 1763274752 -0.0622605346 -0.1104191020 -0.0276678074 910 1311867748.9472498894 0.1408493817 0.1077665137 0.1479820162 0.0049991018 0.0377650000 549088736 0 1762492416 -0.0622605346 -0.1104191020 -0.0276678074 911 1311867748.9829359055 0.1404555142 0.1078023962 0.1479820162 0.0049978701 0.0400250000 549167398 0 1763147776 -0.0622605346 -0.1104191020 -0.0276678074 912 1311867749.0159759521 0.1403530836 0.1078380878 0.1479820162 0.0049973380 0.0384020000 549245964 0 1763147776 -0.0622605346 -0.1104191020 -0.0276678074 913 1311867749.0467190742 0.1402544677 0.1078735931 0.1479820162 0.0049967421 0.0450310000 549324562 0 1763782656 -0.0622605346 -0.1104191020 -0.0276678074 914 1311867749.0828969479 0.1398771107 0.1079086079 0.1479820162 0.0049955750 0.0351590000 549403224 0 1763164160 -0.0622605346 -0.1104191020 -0.0276678074 915 1311867749.1158421040 0.1399492919 0.1079436250 0.1479820162 0.0049953203 0.0429620000 549481854 0 1763889152 -0.0622605346 -0.1104191020 -0.0276678074 916 1311867749.1485249996 0.1398883760 0.1079784992 0.1479820162 0.0049940234 0.0397130000 549560484 0 1763270656 -0.0622605346 -0.1104191020 -0.0276678074 917 1311867749.1829619408 0.1395124644 0.1080128874 0.1479820162 0.0049948822 0.0394260000 549639114 0 1763905536 -0.0622605346 -0.1104191020 -0.0276678074 918 1311867749.2156000137 0.1394709945 0.1080471555 0.1479820162 0.0049929401 0.0351530000 549717680 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 919 1311867749.2468719482 0.1394766867 0.1080813552 0.1479820162 0.0049908470 0.0382430000 549796246 0 1764143104 -0.0622605346 -0.1104191020 -0.0276678074 920 1311867749.2828478813 0.1391906291 0.1081151696 0.1479820162 0.0049898349 0.0378890000 549874908 0 1763545088 -0.0622605346 -0.1104191020 -0.0276678074 921 1311867749.3148140907 0.1391068101 0.1081488196 0.1479820162 0.0049918978 0.0357940000 549953538 0 1764179968 -0.0622605346 -0.1104191020 -0.0276678074 922 1311867749.3468968868 0.1388186812 0.1081820841 0.1479820162 0.0049942020 0.0450390000 550032104 0 1763528704 -0.0622605346 -0.1104191020 -0.0276678074 923 1311867749.3828470707 0.1386512518 0.1082150951 0.1479820162 0.0049966505 0.0371980000 550110766 0 1762725888 -0.0622605346 -0.1104191020 -0.0276678074 924 1311867749.4147930145 0.1386001110 0.1082479793 0.1479820162 0.0049989896 0.0463890000 550189396 0 1763401728 -0.0622605346 -0.1104191020 -0.0276678074 925 1311867749.4467489719 0.1387168169 0.1082809186 0.1479820162 0.0050054161 0.0402720000 550267962 0 1762648064 -0.0622605346 -0.1104191020 -0.0276678074 926 1311867749.4829080105 0.1382249296 0.1083132556 0.1479820162 0.0050063567 0.0358560000 550346624 0 1763274752 -0.0622605346 -0.1104191020 -0.0276678074 927 1311867749.5159850121 0.1378266066 0.1083450931 0.1479820162 0.0050057594 0.0411670000 550425222 0 1762521088 -0.0622605346 -0.1104191020 -0.0276678074 928 1311867749.5468530655 0.1373888701 0.1083763902 0.1479820162 0.0050068380 0.0392110000 550503820 0 1763274752 -0.0622605346 -0.1104191020 -0.0276678074 929 1311867749.5830268860 0.1367871314 0.1084069723 0.1479820162 0.0050061771 0.0349060000 550582482 0 1762373632 -0.0622605346 -0.1104191020 -0.0276678074 930 1311867749.6148250103 0.1360605061 0.1084367073 0.1479820162 0.0050065664 0.0385380000 550661048 0 1763000320 -0.0622605346 -0.1104191020 -0.0276678074 931 1311867749.6469049454 0.1358762830 0.1084661805 0.1479820162 0.0050071597 0.0392440000 550739678 0 1763274752 -0.0622605346 -0.1104191020 -0.0276678074 932 1311867749.6829149723 0.1350045800 0.1084946552 0.1479820162 0.0050075182 0.0351610000 550818340 0 1764036608 -0.0622605346 -0.1104191020 -0.0276678074 933 1311867749.7160799503 0.1346510500 0.1085226899 0.1479820162 0.0050079845 0.0386940000 550896938 0 1762656256 -0.0622605346 -0.1104191020 -0.0276678074 934 1311867749.7468609810 0.1345134974 0.1085505173 0.1479820162 0.0050102090 0.0430310000 550975536 0 1763381248 -0.0622605346 -0.1104191020 -0.0276678074 935 1311867749.7828791142 0.1339299381 0.1085776611 0.1479820162 0.0050100104 0.0402570000 551054198 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 936 1311867749.8148949146 0.1334328949 0.1086042158 0.1479820162 0.0050099973 0.0355870000 551132764 0 1763545088 -0.0622605346 -0.1104191020 -0.0276678074 937 1311867749.8469030857 0.1333289891 0.1086306030 0.1479820162 0.0050084446 0.0394540000 551211394 0 1762893824 -0.0622605346 -0.1104191020 -0.0276678074 938 1311867749.8829030991 0.1332819164 0.1086568837 0.1479820162 0.0050296837 0.0420860000 551290056 0 1763491840 -0.0622605346 -0.1104191020 -0.0276678074 939 1311867749.9149639606 0.1326980144 0.1086824866 0.1479820162 0.0050397382 0.0392780000 551368622 0 1763020800 -0.0622605346 -0.1104191020 -0.0276678074 940 1311867749.9508650303 0.1324298829 0.1087077498 0.1479820162 0.0050402280 0.0433880000 551447252 0 1763655680 -0.0622605346 -0.1104191020 -0.0276678074 941 1311867749.9827940464 0.1321189255 0.1087326289 0.1479820162 0.0050449213 0.0385030000 551525914 0 1763037184 -0.0622605346 -0.1104191020 -0.0276678074 942 1311867750.0147750378 0.1318504214 0.1087571700 0.1479820162 0.0050467996 0.0396550000 551604512 0 1763762176 -0.0622605346 -0.1104191020 -0.0276678074 943 1311867750.0470540524 0.1316164583 0.1087814111 0.1479820162 0.0050457734 0.0371210000 551683078 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 944 1311867750.0829339027 0.1314578205 0.1088054327 0.1479820162 0.0050474665 0.0438290000 551761772 0 1763508224 -0.0622605346 -0.1104191020 -0.0276678074 945 1311867750.1156339645 0.1312692761 0.1088292039 0.1479820162 0.0050492344 0.0474170000 551840338 0 1762746368 -0.0622605346 -0.1104191020 -0.0276678074 946 1311867750.1474790573 0.1311583370 0.1088528077 0.1479820162 0.0050513464 0.0425640000 551918968 0 1763164160 -0.0622605346 -0.1104191020 -0.0276678074 947 1311867750.1828711033 0.1311385483 0.1088763407 0.1479820162 0.0050503147 0.0402640000 551997630 0 1763799040 -0.0622605346 -0.1104191020 -0.0276678074 948 1311867750.2156400681 0.1309851259 0.1088996622 0.1479820162 0.0050493136 0.0343110000 552076196 0 1763147776 -0.0622605346 -0.1104191020 -0.0276678074 949 1311867750.2469079494 0.1309693605 0.1089229179 0.1479820162 0.0050498643 0.0421360000 552154794 0 1763762176 -0.0622605346 -0.1104191020 -0.0276678074 950 1311867750.2829968929 0.1309717745 0.1089461272 0.1479820162 0.0050549205 0.0401250000 552233456 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 951 1311867750.3150129318 0.1309725940 0.1089692886 0.1479820162 0.0050559093 0.0365660000 552312086 0 1763164160 -0.0622605346 -0.1104191020 -0.0276678074 952 1311867750.3469090462 0.1309154183 0.1089923413 0.1479820162 0.0050536603 0.0427280000 552390652 0 1762492416 -0.0622605346 -0.1104191020 -0.0276678074 953 1311867750.3828659058 0.1311502457 0.1090155920 0.1479820162 0.0050514166 0.0398500000 552469314 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 954 1311867750.4148640633 0.1310064644 0.1090386432 0.1479820162 0.0050501543 0.0363940000 552547944 0 1762656256 -0.0622605346 -0.1104191020 -0.0276678074 955 1311867750.4469859600 0.1306486726 0.1090612715 0.1479820162 0.0050493193 0.0420770000 552626510 0 1763291136 -0.0622605346 -0.1104191020 -0.0276678074 956 1311867750.4829618931 0.1306681335 0.1090838728 0.1479820162 0.0050515895 0.0429540000 552705140 0 1762492416 -0.0622605346 -0.1104191020 -0.0276678074 957 1311867750.5148859024 0.1305555850 0.1091063093 0.1479820162 0.0050502765 0.0419750000 552783706 0 1763291136 -0.0622605346 -0.1104191020 -0.0276678074 958 1311867750.5476069450 0.1304958463 0.1091286366 0.1479820162 0.0050490661 0.0357800000 552862336 0 1762512896 -0.0622605346 -0.1104191020 -0.0276678074 959 1311867750.5827779770 0.1304405779 0.1091508597 0.1479820162 0.0050495378 0.0391570000 552940998 0 1763147776 -0.0622605346 -0.1104191020 -0.0276678074 960 1311867750.6148650646 0.1305313259 0.1091731310 0.1479820162 0.0050535783 0.0478980000 553019532 0 1762385920 -0.0622605346 -0.1104191020 -0.0276678074 961 1311867750.6469810009 0.1302878708 0.1091951026 0.1479820162 0.0050531405 0.0415660000 553098194 0 1763147776 -0.0622605346 -0.1104191020 -0.0276678074 962 1311867750.6829319000 0.1302746385 0.1092170148 0.1479820162 0.0050588088 0.0411450000 553176856 0 1762258944 -0.0622605346 -0.1104191020 -0.0276678074 963 1311867750.7149219513 0.1303231120 0.1092389318 0.1479820162 0.0050570009 0.0360640000 553255486 0 1762893824 -0.0622605346 -0.1104191020 -0.0276678074 964 1311867750.7469151020 0.1301430166 0.1092606166 0.1479820162 0.0050563791 0.0413340000 553334052 0 1762766848 -0.0622605346 -0.1104191020 -0.0276678074 965 1311867750.7832129002 0.1300403625 0.1092821500 0.1479820162 0.0050589174 0.0338450000 553412682 0 1763401728 -0.0622605346 -0.1104191020 -0.0276678074 966 1311867750.8149549961 0.1301840097 0.1093037875 0.1479820162 0.0050593082 0.0331920000 553491216 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 967 1311867750.8468461037 0.1303931773 0.1093255966 0.1479820162 0.0050576576 0.0371260000 553569814 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 968 1311867750.8828840256 0.1303969175 0.1093473645 0.1479820162 0.0050558434 0.0398110000 553648508 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 969 1311867750.9147970676 0.1304780245 0.1093691712 0.1479820162 0.0050551717 0.0334200000 553727074 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 970 1311867750.9468770027 0.1307686418 0.1093912325 0.1479820162 0.0050551483 0.0381600000 553805672 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 971 1311867750.9830369949 0.1306732893 0.1094131502 0.1479820162 0.0050539490 0.0366930000 553884366 0 1763000320 -0.0622605346 -0.1104191020 -0.0276678074 972 1311867751.0168409348 0.1305046380 0.1094348492 0.1479820162 0.0050552386 0.0335860000 553962996 0 1762111488 -0.0622605346 -0.1104191020 -0.0276678074 973 1311867751.0470340252 0.1303250641 0.1094563191 0.1479820162 0.0050609402 0.0377430000 554041562 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 974 1311867751.0828599930 0.1301888674 0.1094776051 0.1479820162 0.0050615435 0.0366520000 554120192 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 975 1311867751.1174809933 0.1298840493 0.1094985348 0.1479820162 0.0050601594 0.0347760000 554198854 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 976 1311867751.1468789577 0.1298308671 0.1095193671 0.1479820162 0.0050607235 0.0382350000 554277388 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 977 1311867751.1834619045 0.1297313720 0.1095400549 0.1479820162 0.0050624730 0.0410650000 554356050 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 978 1311867751.2160820961 0.1295429319 0.1095605078 0.1479820162 0.0050614541 0.0379240000 554434648 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 979 1311867751.2468481064 0.1295738220 0.1095809504 0.1479820162 0.0050604617 0.0452070000 554513246 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 980 1311867751.2831590176 0.1298891455 0.1096016730 0.1479820162 0.0050630248 0.0359500000 554591908 0 1762365440 -0.0622605346 -0.1104191020 -0.0276678074 981 1311867751.3149859905 0.1298282892 0.1096222914 0.1479820162 0.0050620943 0.0385790000 554670506 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 982 1311867751.3498549461 0.1295259595 0.1096425599 0.1479820162 0.0050606294 0.0375840000 554749136 0 1762766848 -0.0622605346 -0.1104191020 -0.0276678074 983 1311867751.3834669590 0.1294472963 0.1096627071 0.1479820162 0.0050613226 0.0326230000 554827798 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 984 1311867751.4151160717 0.1296108365 0.1096829796 0.1479820162 0.0050600084 0.0408770000 554906396 0 1762619392 -0.0622605346 -0.1104191020 -0.0276678074 985 1311867751.4513740540 0.1292656660 0.1097028605 0.1479820162 0.0050622873 0.0371810000 554984994 0 1763254272 -0.0622605346 -0.1104191020 -0.0276678074 986 1311867751.4838130474 0.1295073777 0.1097229462 0.1479820162 0.0050599133 0.0350640000 555063656 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 987 1311867751.5149779320 0.1293263435 0.1097428078 0.1479820162 0.0050608161 0.0377890000 555142254 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 988 1311867751.5495579243 0.1291517168 0.1097624525 0.1479820162 0.0050616179 0.0384250000 555220852 0 1762529280 -0.0622605346 -0.1104191020 -0.0276678074 989 1311867751.5829720497 0.1293389499 0.1097822467 0.1479820162 0.0050632719 0.0348640000 555299482 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 990 1311867751.6149520874 0.1292792261 0.1098019406 0.1479820162 0.0050685060 0.0397310000 555378080 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 991 1311867751.6501100063 0.1289858371 0.1098212987 0.1479820162 0.0050715014 0.0390760000 555456678 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 992 1311867751.6837968826 0.1289267987 0.1098405583 0.1479820162 0.0050713210 0.0435120000 555535340 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 993 1311867751.7150709629 0.1289231926 0.1098597755 0.1479820162 0.0050701106 0.0385580000 555613906 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 994 1311867751.7506999969 0.1286235452 0.1098786525 0.1479820162 0.0050682712 0.0400910000 555692536 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 995 1311867751.7830109596 0.1285628974 0.1098974306 0.1479820162 0.0050691567 0.0458790000 555771166 0 1761869824 -0.0622605346 -0.1104191020 -0.0276678074 996 1311867751.8149600029 0.1282871068 0.1099158942 0.1479820162 0.0050686959 0.0405360000 555849764 0 1762365440 -0.0622605346 -0.1104191020 -0.0276678074 997 1311867751.8509531021 0.1283674091 0.1099344012 0.1479820162 0.0050675357 0.0424470000 555928426 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 998 1311867751.8832330704 0.1280033737 0.1099525064 0.1479820162 0.0050685307 0.0377190000 556007024 0 1763418112 -0.0622605346 -0.1104191020 -0.0276678074 999 1311867751.9149179459 0.1280890405 0.1099706611 0.1479820162 0.0050772413 0.0403220000 556085590 0 1762783232 -0.0622605346 -0.1104191020 -0.0276678074 1000 1311867751.9530498981 0.1283166409 0.1099890071 0.1479820162 0.0050831430 0.0397150000 556164284 0 1763508224 -0.0622605346 -0.1104191020 -0.0276678074 1001 1311867751.9829521179 0.1281951815 0.1100071950 0.1479820162 0.0050878970 0.0409730000 556242882 0 1762238464 -0.0622605346 -0.1104191020 -0.0276678074 1002 1311867752.0153670311 0.1282093972 0.1100253609 0.1479820162 0.0050996866 0.0352890000 556321448 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1003 1311867752.0510149002 0.1284424961 0.1100437230 0.1479820162 0.0051117562 0.0515810000 556400078 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1004 1311867752.0828840733 0.1282650381 0.1100618717 0.1479820162 0.0051202101 0.0375650000 556478708 0 1763381248 -0.0622605346 -0.1104191020 -0.0276678074 1005 1311867752.1150429249 0.1284800023 0.1100801982 0.1479820162 0.0051280163 0.0446550000 556557274 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1006 1311867752.1509859562 0.1283860207 0.1100983948 0.1479820162 0.0051393767 0.0462240000 556635968 0 1763545088 -0.0622605346 -0.1104191020 -0.0276678074 1007 1311867752.1829679012 0.1283283234 0.1101164980 0.1479820162 0.0051528380 0.0372060000 556714598 0 1762746368 -0.0622605346 -0.1104191020 -0.0276678074 1008 1311867752.2150039673 0.1283837408 0.1101346203 0.1479820162 0.0051593809 0.0402330000 556793196 0 1763381248 -0.0622605346 -0.1104191020 -0.0276678074 1009 1311867752.2512340546 0.1289234757 0.1101532416 0.1479820162 0.0051616274 0.0405180000 556871826 0 1762402304 -0.0622605346 -0.1104191020 -0.0276678074 1010 1311867752.2833271027 0.1290706992 0.1101719717 0.1479820162 0.0051685258 0.0458890000 556950424 0 1762115584 -0.0622605346 -0.1104191020 -0.0276678074 1011 1311867752.3150799274 0.1286962926 0.1101902945 0.1479820162 0.0051668403 0.0412080000 557028990 0 1762746368 -0.0622605346 -0.1104191020 -0.0276678074 1012 1311867752.3509979248 0.1291290373 0.1102090087 0.1479820162 0.0051674170 0.0384560000 557107652 0 1762402304 -0.0622605346 -0.1104191020 -0.0276678074 1013 1311867752.3829851151 0.1289377660 0.1102274971 0.1479820162 0.0051657285 0.0426820000 557186282 0 1763127296 -0.0622605346 -0.1104191020 -0.0276678074 1014 1311867752.4160280228 0.1289092004 0.1102459208 0.1479820162 0.0051633764 0.0403540000 557264880 0 1762402304 -0.0622605346 -0.1104191020 -0.0276678074 1015 1311867752.4510710239 0.1285640597 0.1102639683 0.1479820162 0.0051659021 0.0434780000 557343542 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1016 1311867752.4829080105 0.1285669804 0.1102819830 0.1479820162 0.0051655457 0.0379760000 557422140 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1017 1311867752.5179650784 0.1281270683 0.1102995298 0.1479820162 0.0051647124 0.0415800000 557500738 0 1763381248 -0.0622605346 -0.1104191020 -0.0276678074 1018 1311867752.5511059761 0.1284961253 0.1103174047 0.1479820162 0.0051665495 0.0446250000 557579368 0 1762910208 -0.0622605346 -0.1104191020 -0.0276678074 1019 1311867752.5830090046 0.1282373965 0.1103349905 0.1479820162 0.0051643011 0.0490880000 557657998 0 1761865728 -0.0622605346 -0.1104191020 -0.0276678074 1020 1311867752.6157000065 0.1284263134 0.1103527271 0.1479820162 0.0051626015 0.0457860000 557736532 0 1762639872 -0.0622605346 -0.1104191020 -0.0276678074 1021 1311867752.6514921188 0.1285347939 0.1103705352 0.1479820162 0.0051613531 0.0450490000 557815226 0 1761615872 -0.0622605346 -0.1104191020 -0.0276678074 1022 1311867752.6830079556 0.1284126639 0.1103881890 0.1479820162 0.0051631155 0.0455540000 557893824 0 1762365440 -0.0622605346 -0.1104191020 -0.0276678074 1023 1311867752.7152760029 0.1285365522 0.1104059293 0.1479820162 0.0051626259 0.0413030000 557972422 0 1762893824 -0.0622605346 -0.1104191020 -0.0276678074 1024 1311867752.7510609627 0.1282295585 0.1104233352 0.1479820162 0.0051603176 0.0432180000 558051052 0 1763491840 -0.0622605346 -0.1104191020 -0.0276678074 1025 1311867752.7830259800 0.1280536950 0.1104405355 0.1479820162 0.0051657229 0.0466700000 558129650 0 1764163584 -0.0622605346 -0.1104191020 -0.0276678074 1026 1311867752.8162770271 0.1282055378 0.1104578504 0.1479820162 0.0051641653 0.0400150000 558376184 0 1765015552 -0.0622605346 -0.1104191020 -0.0276678074 1027 1311867752.8511059284 0.1284856647 0.1104754042 0.1479820162 0.0051627915 0.0406790000 558454846 0 1765650432 -0.0622605346 -0.1104191020 -0.0276678074 1028 1311867752.8833000660 0.1286054850 0.1104930405 0.1479820162 0.0051621298 0.0392970000 558533476 0 1766285312 -0.0622605346 -0.1104191020 -0.0276678074 1029 1311867752.9183709621 0.1292102188 0.1105112302 0.1479820162 0.0051606515 0.0487050000 558612106 0 1766793216 -0.0622605346 -0.1104191020 -0.0276678074 1030 1311867752.9511129856 0.1292883158 0.1105294603 0.1479820162 0.0051599854 0.0446830000 558690704 0 1767428096 -0.0622605346 -0.1104191020 -0.0276678074 1031 1311867752.9828579426 0.1292701364 0.1105476375 0.1479820162 0.0051595293 0.0557420000 558769334 0 1767936000 -0.0622605346 -0.1104191020 -0.0276678074 1032 1311867753.0168049335 0.1295323074 0.1105660335 0.1479820162 0.0051579354 0.0402360000 558847900 0 1768570880 -0.0622605346 -0.1104191020 -0.0276678074 1033 1311867753.0510199070 0.1294968277 0.1105843596 0.1479820162 0.0051559513 0.0514950000 558926562 0 1769205760 -0.0622605346 -0.1104191020 -0.0276678074 1034 1311867753.0829060078 0.1294532716 0.1106026080 0.1479820162 0.0051567351 0.0526380000 559005128 0 1769713664 -0.0622605346 -0.1104191020 -0.0276678074 1035 1311867753.1184151173 0.1296831071 0.1106210433 0.1479820162 0.0051559740 0.0404610000 559083790 0 1770348544 -0.0622605346 -0.1104191020 -0.0276678074 1036 1311867753.1510760784 0.1295975745 0.1106393604 0.1479820162 0.0051551316 0.0408380000 559162388 0 1771110400 -0.0622605346 -0.1104191020 -0.0276678074 1037 1311867753.1830070019 0.1292910725 0.1106573466 0.1479820162 0.0051548761 0.0414140000 559240954 0 1771614208 -0.0622605346 -0.1104191020 -0.0276678074 1038 1311867753.2186250687 0.1295726299 0.1106755694 0.1479820162 0.0051568173 0.0462060000 559319616 0 1772253184 -0.0622605346 -0.1104191020 -0.0276678074 1039 1311867753.2520470619 0.1296423674 0.1106938243 0.1479820162 0.0051579791 0.0439490000 559398214 0 1772888064 -0.0622605346 -0.1104191020 -0.0276678074 1040 1311867753.2829909325 0.1294256151 0.1107118356 0.1479820162 0.0051579715 0.0419430000 559476812 0 1773522944 -0.0622605346 -0.1104191020 -0.0276678074 1041 1311867753.3178219795 0.1294608563 0.1107298462 0.1479820162 0.0051682398 0.0423070000 559555410 0 1774178304 -0.0622605346 -0.1104191020 -0.0276678074 1042 1311867753.3509368896 0.1296062022 0.1107479617 0.1479820162 0.0051731217 0.0409810000 559634040 0 1774665728 -0.0622605346 -0.1104191020 -0.0276678074 1043 1311867753.3829340935 0.1294168085 0.1107658609 0.1479820162 0.0051708122 0.0470990000 559712670 0 1775300608 -0.0622605346 -0.1104191020 -0.0276678074 1044 1311867753.4181840420 0.1295038462 0.1107838092 0.1479820162 0.0051707290 0.0470380000 559791268 0 1775935488 -0.0622605346 -0.1104191020 -0.0276678074 1045 1311867753.4511721134 0.1293000877 0.1108015281 0.1479820162 0.0051720709 0.0423930000 559869898 0 1776570368 -0.0622605346 -0.1104191020 -0.0276678074 1046 1311867753.4831509590 0.1288849711 0.1108188163 0.1479820162 0.0051747998 0.0459700000 559948528 0 1777078272 -0.0622605346 -0.1104191020 -0.0276678074 1047 1311867753.5199398994 0.1284923702 0.1108356965 0.1479820162 0.0051779546 0.0423700000 560027190 0 1777860608 -0.0622605346 -0.1104191020 -0.0276678074 1048 1311867753.5532588959 0.1280780286 0.1108521491 0.1479820162 0.0051793216 0.0382310000 560105788 0 1778348032 -0.0622605346 -0.1104191020 -0.0276678074 1049 1311867753.5832290649 0.1277311891 0.1108682397 0.1479820162 0.0051814292 0.0439710000 560184386 0 1778982912 -0.0622605346 -0.1104191020 -0.0276678074 1050 1311867753.6183090210 0.1273821443 0.1108839672 0.1479820162 0.0051867678 0.0519000000 560263016 0 1779617792 -0.0622605346 -0.1104191020 -0.0276678074 1051 1311867753.6509299278 0.1271656752 0.1108994588 0.1479820162 0.0051859660 0.0420480000 560341646 0 1780252672 -0.0622605346 -0.1104191020 -0.0276678074 1052 1311867753.6830120087 0.1269284934 0.1109146956 0.1479820162 0.0051845991 0.0431820000 560420212 0 1780887552 -0.0622605346 -0.1104191020 -0.0276678074 1053 1311867753.7204699516 0.1268821210 0.1109298593 0.1479820162 0.0051844849 0.0439280000 560498906 0 1781395456 -0.0622605346 -0.1104191020 -0.0276678074 1054 1311867753.7510209084 0.1263891309 0.1109445266 0.1479820162 0.0051832854 0.0402370000 560577472 0 1782030336 -0.0622605346 -0.1104191020 -0.0276678074 1055 1311867753.7865009308 0.1257972419 0.1109586050 0.1479820162 0.0051897886 0.0438160000 560656102 0 1782665216 -0.0622605346 -0.1104191020 -0.0276678074 1056 1311867753.8151769638 0.1261829585 0.1109730220 0.1479820162 0.0051896085 0.0704170000 560734636 0 1783427072 -0.0622605346 -0.1104191020 -0.0276678074 1057 1311867753.8510670662 0.1256623566 0.1109869192 0.1479820162 0.0051953649 0.0913190000 560736626 0 1783943168 -0.0622605346 -0.1104191020 -0.0276678074 1058 1311867753.8831028938 0.1251796782 0.1110003339 0.1479820162 0.0051989235 0.0446340000 560738412 0 1784578048 -0.0622605346 -0.1104191020 -0.0276678074 1059 1311867753.9155681133 0.1248955503 0.1110134549 0.1479820162 0.0051985679 0.0389460000 560816978 0 1785085952 -0.0622605346 -0.1104191020 -0.0276678074 1060 1311867753.9511620998 0.1247021705 0.1110263688 0.1479820162 0.0052010816 0.0441370000 560895672 0 1785593856 -0.0622605346 -0.1104191020 -0.0276678074 1061 1311867753.9858930111 0.1239469349 0.1110385465 0.1479820162 0.0051992170 0.0471060000 560974302 0 1784213504 -0.0622605346 -0.1104191020 -0.0276678074 1062 1311867754.0151700974 0.1231337488 0.1110499356 0.1479820162 0.0051976861 0.0478150000 561052836 0 1784758272 -0.0622605346 -0.1104191020 -0.0276678074 1063 1311867754.0510439873 0.1229798570 0.1110611585 0.1479820162 0.0052063568 0.0480900000 561131562 0 1783488512 -0.0622605346 -0.1104191020 -0.0276678074 1064 1311867754.0839030743 0.1225150228 0.1110719234 0.1479820162 0.0052100673 0.0484610000 561210128 0 1784123392 -0.0622605346 -0.1104191020 -0.0276678074 1065 1311867754.1166028976 0.1218995154 0.1110820902 0.1479820162 0.0052084585 0.0479620000 561288758 0 1783324672 -0.0622605346 -0.1104191020 -0.0276678074 1066 1311867754.1511039734 0.1216047406 0.1110919613 0.1479820162 0.0052168539 0.0495140000 561367356 0 1782218752 -0.0622605346 -0.1104191020 -0.0276678074 1067 1311867754.1832070351 0.1802211851 0.1111567497 0.1802211851 0.0140104068 0.1082010000 561445954 0 1782218752 0.0868925154 -0.1631446034 0.0203023273 1068 1311867754.2166299820 0.1805143207 0.1112216913 0.1805143207 0.0140065981 0.1755780000 553170140 0 1781948416 0.0922945291 -0.1570381522 0.0285457950 1069 1311867754.2522869110 0.1835927665 0.1112893911 0.1835927665 0.0140035698 0.1694910000 553172002 0 1782456320 0.0972512960 -0.1563294530 0.0314239785 1070 1311867754.2873139381 0.1878019273 0.1113608981 0.1878019273 0.0139992070 0.1138550000 553173800 0 1783091200 0.1007097661 -0.1579709798 0.0320918821 1071 1311867754.3174090385 0.1914031059 0.1114356341 0.1914031059 0.0139968813 0.1187160000 553175534 0 1783689216 0.1042302176 -0.1595759988 0.0347875506 1072 1311867754.3511719704 0.1914855093 0.1115103074 0.1914855093 0.0139923653 0.1268390000 553177364 0 1784344576 0.1047490761 -0.1575701684 0.0365507342 1073 1311867754.3868749142 0.1942989230 0.1115874637 0.1942989230 0.0139882034 0.1182140000 553179130 0 1784832000 0.1075420305 -0.1592620313 0.0362785459 1074 1311867754.4159760475 0.1938486844 0.1116640570 0.1942989230 0.0139824911 0.1123760000 553180928 0 1785339904 0.1061433628 -0.1586333513 0.0378058106 1075 1311867754.4545960426 0.1921983212 0.1117389726 0.1942989230 0.0139799960 0.1210940000 553182758 0 1785847808 0.1030387804 -0.1589155644 0.0386120267 1076 1311867754.4863569736 0.1960463524 0.1118173252 0.1960463524 0.0139777390 0.1226680000 553184492 0 1784377344 0.1051388606 -0.1603248715 0.0418795273 1077 1311867754.5159039497 0.1937750876 0.1118934234 0.1960463524 0.0139732879 0.1220820000 553186194 0 1783361536 0.1040422767 -0.1589375436 0.0391238146 1078 1311867754.5513699055 0.1960826814 0.1119715210 0.1960826814 0.0139677244 0.1198860000 553188024 0 1783721984 0.1054550260 -0.1609938145 0.0398244485 1079 1311867754.5835869312 0.1971390247 0.1120504529 0.1971390247 0.0139625715 0.1216380000 553190302 0 1780916224 0.1047604308 -0.1610854566 0.0438949615 1080 1311867754.6154859066 0.1951044649 0.1121273547 0.1971390247 0.0139568802 0.1262690000 553191524 0 1781424128 0.1044184789 -0.1597029865 0.0419259518 1081 1311867754.6510920525 0.1967448294 0.1122056318 0.1971390247 0.0139512202 0.1214820000 553193354 0 1782050816 0.1048224121 -0.1616130173 0.0425143652 1082 1311867754.6872670650 0.1974407434 0.1122844073 0.1974407434 0.0139453050 0.1218540000 553195152 0 1782583296 0.1039696038 -0.1620833576 0.0454790480 1083 1311867754.7162880898 0.1950891465 0.1123608660 0.1974407434 0.0139400697 0.1309170000 553196854 0 1783070720 0.1032816097 -0.1599173695 0.0450890362 1084 1311867754.7516000271 0.1970015168 0.1124389477 0.1974407434 0.0139350614 0.1216830000 553198716 0 1783615488 0.1065969393 -0.1611212939 0.0424831174 1085 1311867754.7865169048 0.1988671571 0.1125186051 0.1988671571 0.0139292825 0.1208120000 553200482 0 1784197120 0.1064865068 -0.1629745811 0.0448206067 1086 1311867754.8154330254 0.1981336325 0.1125974403 0.1988671571 0.0139230869 0.1159280000 553202184 0 1784705024 0.1041420847 -0.1625885963 0.0477330573 1087 1311867754.8510210514 0.1960566044 0.1126742196 0.1988671571 0.0139206658 0.1135340000 553204046 0 1785212928 0.1039993688 -0.1605983377 0.0456893593 1088 1311867754.8877279758 0.1973159015 0.1127520153 0.1988671571 0.0139143305 0.1145150000 553205876 0 1785720832 0.1029857323 -0.1612705886 0.0493733548 1089 1311867754.9201200008 0.1966595501 0.1128290654 0.1988671571 0.0139084675 0.1172210000 553207642 0 1784250368 0.1010580733 -0.1603608578 0.0520992987 1090 1311867754.9510319233 0.1968979239 0.1129061928 0.1988671571 0.0139032208 0.1176110000 553209408 0 1783234560 0.1027818620 -0.1600205600 0.0498930439 1091 1311867754.9837698936 0.1997044533 0.1129857512 0.1997044533 0.0138989215 0.1191600000 553211174 0 1783451648 0.1055182591 -0.1615441442 0.0490154512 1092 1311867755.0183610916 0.1982481033 0.1130638303 0.1997044533 0.0138931882 0.1201910000 553212972 0 1783234560 0.1023081020 -0.1610920429 0.0513485968 1093 1311867755.0540759563 0.1993756294 0.1131427981 0.1997044533 0.0138876994 0.1249700000 553214802 0 1783705600 0.1021693349 -0.1615703404 0.0531382151 1094 1311867755.0850980282 0.2010473758 0.1132231496 0.2010473758 0.0138838313 0.1175470000 553216600 0 1784377344 0.1034262106 -0.1626206040 0.0534131043 1095 1311867755.1156840324 0.2017258853 0.1133039740 0.2017258853 0.0138783162 0.1162790000 553218270 0 1784958976 0.1038370132 -0.1628128588 0.0531935133 1096 1311867755.1555950642 0.2022864074 0.1133851624 0.2022864074 0.0138720168 0.1168710000 553220164 0 1785466880 0.1030342057 -0.1628721207 0.0549847037 1097 1311867755.1846981049 0.2025908679 0.1134664803 0.2025908679 0.0138658575 0.1192210000 553221930 0 1785974784 0.1025287062 -0.1633579284 0.0547796264 1098 1311867755.2151050568 0.2029290795 0.1135479580 0.2029290795 0.0138601518 0.1190710000 553223632 0 1783980032 0.1037802398 -0.1631189585 0.0533289872 1099 1311867755.2512140274 0.2029101849 0.1136292703 0.2029290795 0.0138544404 0.1265520000 553225462 0 1784213504 0.1011723801 -0.1630547792 0.0572993308 1100 1311867755.2832860947 0.2018155456 0.1137094397 0.2029290795 0.0138482227 0.1160480000 553227228 0 1783980032 0.0999178216 -0.1622495651 0.0579160824 1101 1311867755.3191769123 0.2010185122 0.1137887395 0.2029290795 0.0138424706 0.1222500000 553229058 0 1783705600 0.1010121852 -0.1617720127 0.0546691939 1102 1311867755.3552980423 0.2009898573 0.1138678694 0.2029290795 0.0138373843 0.1148750000 553230920 0 1784213504 0.0987406746 -0.1616287977 0.0584368482 1103 1311867755.3900039196 0.2036786228 0.1139492934 0.2036786228 0.0138319146 0.1214620000 553232686 0 1784758272 0.0993980318 -0.1639239043 0.0603082962 1104 1311867755.4156520367 0.2003668994 0.1140275702 0.2036786228 0.0138279887 0.1205130000 553234388 0 1785339904 0.1007191613 -0.1614141911 0.0541503690 1105 1311867755.4548349380 0.2030056268 0.1141080934 0.2036786228 0.0138221784 0.1172430000 553236250 0 1785847808 0.1011921316 -0.1631374359 0.0566485114 1106 1311867755.4860599041 0.2038424313 0.1141892275 0.2038424313 0.0138168739 0.1188120000 553237984 0 1784344576 0.0992247984 -0.1635600924 0.0607129075 1107 1311867755.5161869526 0.2009203285 0.1142675754 0.2038424313 0.0138140300 0.1254400000 553239686 0 1783218176 0.0998218209 -0.1610818505 0.0559750013 1108 1311867755.5550830364 0.2018751651 0.1143466436 0.2038424313 0.0138078901 0.1098620000 553241580 0 1783726080 0.0999158546 -0.1618204266 0.0559470654 1109 1311867755.5853939056 0.2020934075 0.1144257660 0.2038424313 0.0138016992 0.1150400000 553243346 0 1781321728 0.0993939117 -0.1617365628 0.0566311777 1110 1311867755.6171081066 0.2042881846 0.1145067231 0.2042881846 0.0137962331 0.1213920000 553245080 0 1781911552 0.1021983251 -0.1628702879 0.0553992353 1111 1311867755.6542870998 0.2052372396 0.1145883888 0.2052372396 0.0137900297 0.1137550000 553246942 0 1782419456 0.1023362726 -0.1629793197 0.0567328297 1112 1311867755.6831660271 0.2031378895 0.1146680196 0.2052372396 0.0137849997 0.1239470000 553248644 0 1782927360 0.0989231318 -0.1621960998 0.0575991794 1113 1311867755.7182629108 0.2030208558 0.1147474022 0.2052372396 0.0137790869 0.1201640000 553250474 0 1783480320 0.0988200009 -0.1620871276 0.0574592724 1114 1311867755.7511401176 0.2031922936 0.1148267962 0.2052372396 0.0137729623 0.1097990000 553252240 0 1784061952 0.0999028012 -0.1620346904 0.0559184812 1115 1311867755.7863209248 0.2041417658 0.1149068993 0.2052372396 0.0137668010 0.1173380000 553254038 0 1784569856 0.0994104892 -0.1629285514 0.0574083403 1116 1311867755.8156828880 0.2033248842 0.1149861269 0.2052372396 0.0137607702 0.1249200000 553255804 0 1785094144 0.0989437774 -0.1621711701 0.0572775379 1117 1311867755.8553929329 0.2054961026 0.1150671564 0.2054961026 0.0137561997 0.1176870000 553257634 0 1785733120 0.1031904146 -0.1636284739 0.0525518879 1118 1311867755.8848280907 0.2037426978 0.1151464727 0.2054961026 0.0137505661 0.1204340000 553259400 0 1783607296 0.0999798179 -0.1627056897 0.0543254241 1119 1311867755.9156160355 0.2061642855 0.1152278112 0.2061642855 0.0137452669 0.1185380000 553261166 0 1783824384 0.1006919295 -0.1639370173 0.0572786219 1120 1311867755.9550280571 0.2063419670 0.1153091631 0.2063419670 0.0137397339 0.1229780000 553262996 0 1783607296 0.1035258174 -0.1632799506 0.0532595813 1121 1311867755.9855079651 0.2063452452 0.1153903728 0.2063452452 0.0137339392 0.1317590000 553264730 0 1783316480 0.1028339565 -0.1632696092 0.0539507307 1122 1311867756.0173759460 0.2062764466 0.1154713764 0.2063452452 0.0137279988 0.1117640000 553266464 0 1783951360 0.1012969166 -0.1632025391 0.0561943986 1123 1311867756.0554299355 0.2065537423 0.1155524827 0.2065537423 0.0137225624 0.1134750000 553268294 0 1784459264 0.1039545164 -0.1629339606 0.0525787063 1124 1311867756.0835859776 0.2068153769 0.1156336775 0.2068153769 0.0137165255 0.1300870000 553270028 0 1785225216 0.1026577950 -0.1633479744 0.0544740371 1125 1311867756.1196799278 0.2072052360 0.1157150744 0.2072052360 0.0137112070 0.1136270000 553271858 0 1785712640 0.0995763093 -0.1648107171 0.0581324585 1126 1311867756.1518061161 0.2051440179 0.1157944962 0.2072052360 0.0137055464 0.1106510000 553273528 0 1784115200 0.1013336256 -0.1626599878 0.0538295880 1127 1311867756.1836869717 0.2066096812 0.1158750776 0.2072052360 0.0136996807 0.1318910000 553275262 0 1783607296 0.1029826999 -0.1632580757 0.0541516729 1128 1311867756.2153429985 0.2067195922 0.1159556135 0.2072052360 0.0136940187 0.1231890000 553276964 0 1783316480 0.1002922803 -0.1640228033 0.0581349768 1129 1311867756.2550570965 0.2049997300 0.1160344834 0.2072052360 0.0136882549 0.1199430000 553278762 0 1783099392 0.1011790261 -0.1622489393 0.0551681817 1130 1311867756.2851510048 0.2048377097 0.1161130703 0.2072052360 0.0136837633 0.1247230000 553280528 0 1783570432 0.1014146283 -0.1626348197 0.0534287021 1131 1311867756.3154039383 0.2073991299 0.1161937830 0.2073991299 0.0136783552 0.1180700000 553282230 0 1784078336 0.1026508883 -0.1644851267 0.0552018546 1132 1311867756.3546020985 0.2069148719 0.1162739253 0.2073991299 0.0136725562 0.1110950000 553284156 0 1784696832 0.1012691557 -0.1644486487 0.0565377139 1133 1311867756.3842909336 0.2074617296 0.1163544088 0.2074617296 0.0136669538 0.1177580000 553285858 0 1785204736 0.1039192602 -0.1643258780 0.0538599305 1134 1311867756.4153299332 0.2049688697 0.1164325521 0.2074617296 0.0136615983 0.1096490000 553287560 0 1785860096 0.1007356122 -0.1631148905 0.0552741997 1135 1311867756.4510889053 0.2064521909 0.1165118645 0.2074617296 0.0136562471 0.1183080000 553289358 0 1784242176 0.1016833112 -0.1640246511 0.0568317361 1136 1311867756.4865260124 0.2055950165 0.1165902828 0.2074617296 0.0136516049 0.1301360000 553291220 0 1783734272 0.1030900702 -0.1635241807 0.0541861355 1137 1311867756.5153410435 0.2053885013 0.1166683815 0.2074617296 0.0136457258 0.1174340000 553292954 0 1783734272 0.1025772840 -0.1632818878 0.0553613566 1138 1311867756.5525779724 0.2065962106 0.1167474042 0.2074617296 0.0136406169 0.1189830000 553294816 0 1783083008 0.1048734561 -0.1642121375 0.0534703955 1139 1311867756.5897810459 0.2041681856 0.1168241564 0.2074617296 0.0136353727 0.1243150000 553296678 0 1783590912 0.1012572572 -0.1629179567 0.0555156767 1140 1311867756.6152539253 0.2040971667 0.1169007117 0.2074617296 0.0136295315 0.1207350000 553298284 0 1784225792 0.1005022675 -0.1628049165 0.0573433712 1141 1311867756.6518189907 0.2042051405 0.1169772274 0.2074617296 0.0136235762 0.1137280000 553300114 0 1784823808 0.1005580276 -0.1629870385 0.0577347837 1142 1311867756.6838989258 0.2039377987 0.1170533750 0.2074617296 0.0136177855 0.1143780000 553301848 0 1785331712 0.1014637277 -0.1627948433 0.0558877066 1143 1311867756.7151489258 0.2066611946 0.1171317721 0.2074617296 0.0136125312 0.1209900000 553304094 0 1785839616 0.1029751673 -0.1643975824 0.0571750440 1144 1311867756.7516241074 0.2064295262 0.1172098295 0.2074617296 0.0136067855 0.1188350000 553305412 0 1784094720 0.1025434583 -0.1643073857 0.0580642670 1145 1311867756.7839419842 0.2064975053 0.1172878100 0.2074617296 0.0136018504 0.1170600000 553307210 0 1783861248 0.1026536599 -0.1642861366 0.0580593981 1146 1311867756.8152918816 0.2066810280 0.1173658146 0.2074617296 0.0135962723 0.1177780000 553308912 0 1783353344 0.1036011726 -0.1643938422 0.0569027103 1147 1311867756.8541939259 0.2067288458 0.1174437248 0.2074617296 0.0135907619 0.1170670000 553310806 0 1781932032 0.1019426510 -0.1648998559 0.0594302043 1148 1311867756.8841879368 0.2056431770 0.1175205536 0.2074617296 0.0135878018 0.1271870000 553312572 0 1782554624 0.1024661139 -0.1636473835 0.0579472110 1149 1311867756.9152240753 0.2065325230 0.1175980227 0.2074617296 0.0135820512 0.1177920000 553314274 0 1783062528 0.1021195427 -0.1642204225 0.0601560622 1150 1311867756.9552290440 0.2059731483 0.1176748706 0.2074617296 0.0135761961 0.1266200000 553316200 0 1783607296 0.1007293612 -0.1644180119 0.0606625229 1151 1311867756.9841670990 0.2066552788 0.1177521777 0.2074617296 0.0135708962 0.1174950000 553317902 0 1784115200 0.1035989076 -0.1642784774 0.0577151217 1152 1311867757.0153179169 0.2079485804 0.1178304732 0.2079485804 0.0135654199 0.1171410000 553319636 0 1784696832 0.1017732993 -0.1656728983 0.0621502735 1153 1311867757.0552799702 0.2046380043 0.1179057616 0.2079485804 0.0135606475 0.1219780000 553321562 0 1785204736 0.0991212949 -0.1636648923 0.0614909753 1154 1311867757.0858480930 0.2053260952 0.1179815157 0.2079485804 0.0135549123 0.1252290000 553323296 0 1785729024 0.1007039696 -0.1639575958 0.0604077429 1155 1311867757.1154010296 0.2073561400 0.1180588964 0.2079485804 0.0135516063 0.1188020000 553324998 0 1784242176 0.0955764577 -0.1665978730 0.0692364350 1156 1311867757.1521968842 0.2079132348 0.1181366250 0.2079485804 0.0135459032 0.1242370000 553326796 0 1783734272 0.0975559503 -0.1676169187 0.0661656410 1157 1311867757.1851840019 0.2074402124 0.1182138105 0.2079485804 0.0135401555 0.1186870000 553328594 0 1783226368 0.0974390060 -0.1673547626 0.0663290694 1158 1311867757.2152419090 0.2036036551 0.1182875496 0.2079485804 0.0135425688 0.1253910000 553330360 0 1783226368 0.0952837393 -0.1642828435 0.0663104430 1159 1311867757.2523880005 0.2055735588 0.1183628611 0.2079485804 0.0135423937 0.1214160000 553332190 0 1783697408 0.0969838127 -0.1657792926 0.0665690005 1160 1311867757.2835650444 0.2021047920 0.1184350524 0.2079485804 0.0135388205 0.1332670000 553333924 0 1784205312 0.0980329663 -0.1634132564 0.0608335435 1161 1311867757.3154449463 0.2030642033 0.1185079457 0.2079485804 0.0135352817 0.1270900000 553335722 0 1784823808 0.0971548334 -0.1648039371 0.0629224926 1162 1311867757.3555309772 0.2012825310 0.1185791803 0.2079485804 0.0135307521 0.1269980000 553337616 0 1785331712 0.0974283293 -0.1633915603 0.0619113781 1163 1311867757.3833310604 0.2006626576 0.1186497594 0.2079485804 0.0135250054 0.1223690000 553339286 0 1785856000 0.0983285233 -0.1629576236 0.0600566603 1164 1311867757.4153690338 0.2024205923 0.1187217274 0.2079485804 0.0135196612 0.1138530000 553341052 0 1784369152 0.0975504220 -0.1644287109 0.0633517504 ================================================ FILE: icra2018_results/tegra/violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 06:16:07 Properties: ================= frame-limit: 0 log-file: output//violons_liblsdslam-cpp_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/liblsdslam-cpp-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 camera-path: package-path: lsdslam/src/cpp/ kfusage: 5 kfdist: 5 minUseGrad: 5 fabmap: true kfreactive: false subpixelstereo: true maxLoopClosureCandiates: 20 randSeed: 1 use-pose-optim: true Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 nan 0.0569700000 94835795 0 1289920512 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0611953549 0.0597236995 0.0611953549 0.0088769346 0.1819430000 116880924 0 1300484096 -0.0043363627 0.0014787407 -0.0000160180 3 1311867170.5264289379 0.0625342205 0.0606605398 0.0625342205 0.0068025817 0.1749810000 120152058 0 1304293376 -0.0085155768 0.0024614935 -0.0014082161 4 1311867170.5623490810 0.0622892939 0.0610677283 0.0625342205 0.0056800369 0.1158610000 120154216 0 1305165824 -0.0138590951 0.0014301802 -0.0037234668 5 1311867170.5942170620 0.0654902533 0.0619522333 0.0654902533 0.0068551669 0.1401150000 120156286 0 1305690112 -0.0167241544 0.0025477943 -0.0027489252 6 1311867170.6260869503 0.0636746362 0.0622393005 0.0654902533 0.0065549394 0.1579970000 120158708 0 1306308608 -0.0159827154 0.0008288115 -0.0052628033 7 1311867170.6621398926 0.0643371046 0.0625389868 0.0654902533 0.0060781757 0.1321510000 120160570 0 1306816512 -0.0173256006 0.0007432570 -0.0061667264 8 1311867170.6942050457 0.0630389825 0.0626014862 0.0654902533 0.0060112824 0.1353270000 120162304 0 1307324416 -0.0195133612 -0.0026966156 -0.0083137639 9 1311867170.7263879776 0.0669525266 0.0630849351 0.0669525266 0.0067839943 0.1545660000 120164742 0 1307832320 -0.0229993649 0.0007934144 -0.0076974337 10 1311867170.7620189190 0.0720806420 0.0639845058 0.0720806420 0.0072763251 0.1614310000 120167916 0 1308356608 -0.0307751019 0.0007661089 -0.0061874175 11 1311867170.7941920757 0.0731059760 0.0648137304 0.0731059760 0.0070369634 0.1630130000 120169618 0 1308975104 -0.0310605839 -0.0009098459 -0.0065512597 12 1311867170.8262820244 0.0742821619 0.0656027663 0.0742821619 0.0068540051 0.1649750000 120171416 0 1309483008 -0.0355211608 -0.0067018000 -0.0075827013 13 1311867170.8622210026 0.0700561404 0.0659453336 0.0742821619 0.0086520444 0.1737880000 120173246 0 1309990912 -0.0378693044 -0.0211869460 -0.0120584108 14 1311867170.8943779469 0.0706328228 0.0662801542 0.0742821619 0.0085797613 0.2311960000 132516124 0 1322815488 -0.0409508497 -0.0300084185 -0.0146712763 15 1311867170.9263520241 0.0708773285 0.0665866325 0.0742821619 0.0083456637 0.1742520000 136175970 0 1326751744 -0.0409714617 -0.0347238630 -0.0168486144 16 1311867170.9621469975 0.0736370534 0.0670272838 0.0742821619 0.0081640308 0.1405080000 139369896 0 1330561024 -0.0462509580 -0.0373524614 -0.0186943542 17 1311867170.9942629337 0.0731007308 0.0673845454 0.0742821619 0.0080046334 0.1151710000 139372974 0 1331322880 -0.0456846878 -0.0414447486 -0.0215295106 18 1311867171.0262739658 0.0743198320 0.0677698391 0.0743198320 0.0077843252 0.1182800000 139377396 0 1331957760 -0.0467521511 -0.0464044996 -0.0233519319 19 1311867171.0623519421 0.0761784613 0.0682123982 0.0761784613 0.0080128196 0.1049150000 139379226 0 1332465664 -0.0494860746 -0.0508915633 -0.0252896696 20 1311867171.0942349434 0.0748374909 0.0685436528 0.0761784613 0.0078415347 0.1087420000 139380960 0 1332973568 -0.0463114567 -0.0521720275 -0.0274562370 21 1311867171.1262509823 0.0768263862 0.0689380687 0.0768263862 0.0076636631 0.1102320000 139382758 0 1333481472 -0.0486748070 -0.0558159910 -0.0286860969 22 1311867171.1622469425 0.0769624189 0.0693028119 0.0769624189 0.0076427352 0.1099330000 139384588 0 1334005760 -0.0471723117 -0.0565028824 -0.0299092103 23 1311867171.1942689419 0.0741562024 0.0695138289 0.0769624189 0.0081756823 0.1312540000 139386322 0 1334624256 -0.0426738597 -0.0556349866 -0.0309651438 24 1311867171.2262530327 0.0746658817 0.0697284977 0.0769624189 0.0081105300 0.1586480000 139388120 0 1335132160 -0.0389052592 -0.0581661463 -0.0320588760 25 1311867171.2622439861 0.0721969530 0.0698272359 0.0769624189 0.0079460212 0.1572750000 139389950 0 1335640064 -0.0333669372 -0.0564755946 -0.0338429809 26 1311867171.2943410873 0.0698427707 0.0698278334 0.0769624189 0.0078782854 0.1515570000 139391652 0 1336164352 -0.0277461056 -0.0563492663 -0.0355957225 27 1311867171.3263869286 0.0706397146 0.0698579031 0.0769624189 0.0078539652 0.1753020000 139393450 0 1336782848 -0.0253314413 -0.0575823970 -0.0366530456 28 1311867171.3622460365 0.0699633509 0.0698616691 0.0769624189 0.0077699082 0.1485670000 139395280 0 1337290752 -0.0246620458 -0.0550452434 -0.0379052013 29 1311867171.3941431046 0.0706799701 0.0698898864 0.0769624189 0.0076870584 0.1540140000 139397014 0 1337798656 -0.0254849531 -0.0532474108 -0.0388439298 30 1311867171.4262878895 0.0756544769 0.0700820394 0.0769624189 0.0076648140 0.1492100000 139398812 0 1338306560 -0.0310866944 -0.0571308620 -0.0385525897 31 1311867171.4622440338 0.0756526366 0.0702617361 0.0769624189 0.0075678760 0.1506610000 139400642 0 1338830848 -0.0319574773 -0.0573463142 -0.0408649594 32 1311867171.4944040775 0.0755995661 0.0704285433 0.0769624189 0.0074581568 0.1450330000 139402376 0 1339449344 -0.0316610150 -0.0573766530 -0.0424761325 33 1311867171.5261778831 0.0781080648 0.0706612560 0.0781080648 0.0073802156 0.1370770000 139406862 0 1339957248 -0.0355408527 -0.0583893098 -0.0429100320 34 1311867171.5622971058 0.0758313462 0.0708133175 0.0781080648 0.0073201524 0.1326560000 139413940 0 1340481536 -0.0341810808 -0.0571149290 -0.0450164936 35 1311867171.5942931175 0.0745134354 0.0709190352 0.0781080648 0.0072644033 0.1332920000 139415674 0 1341100032 -0.0318957306 -0.0575894415 -0.0459549725 36 1311867171.6263399124 0.0767289698 0.0710804222 0.0781080648 0.0071821094 0.1312290000 139417472 0 1341607936 -0.0365838706 -0.0581785142 -0.0459040254 37 1311867171.6622560024 0.0777033269 0.0712594197 0.0781080648 0.0071057593 0.1375490000 139419302 0 1342115840 -0.0399250351 -0.0574695207 -0.0462646075 38 1311867171.6943440437 0.0787382871 0.0714562320 0.0787382871 0.0071020177 0.1313550000 139421036 0 1342623744 -0.0421684571 -0.0568594299 -0.0459044427 39 1311867171.7262439728 0.0801272392 0.0716785655 0.0801272392 0.0070489391 0.1197880000 139422834 0 1343148032 -0.0464187190 -0.0569241866 -0.0458193086 40 1311867171.7621190548 0.0815541670 0.0719254555 0.0815541670 0.0069673851 0.1213850000 139424664 0 1343766528 -0.0495326892 -0.0583437532 -0.0458065756 41 1311867171.7941710949 0.0801966637 0.0721271923 0.0815541670 0.0069588736 0.1405960000 139426398 0 1344274432 -0.0499933138 -0.0596882477 -0.0469153635 42 1311867171.8262550831 0.0800721943 0.0723163590 0.0815541670 0.0068822138 0.1328060000 139428196 0 1344782336 -0.0514225289 -0.0604605675 -0.0479370467 43 1311867171.8623590469 0.0835907385 0.0725785539 0.0835907385 0.0068602766 0.1546350000 139430026 0 1345417216 -0.0594737567 -0.0601891316 -0.0470573828 44 1311867171.8944430351 0.0842806995 0.0728445117 0.0842806995 0.0070256381 0.1610130000 139431792 0 1345925120 -0.0641992316 -0.0582966730 -0.0477170795 45 1311867171.9262220860 0.0848530754 0.0731113687 0.0848530754 0.0069755512 0.1575050000 139433558 0 1346433024 -0.0675188750 -0.0585206077 -0.0476200432 46 1311867171.9624669552 0.0845508203 0.0733600524 0.0848530754 0.0069737253 0.1674980000 139435388 0 1346940928 -0.0711470023 -0.0566070750 -0.0479781255 47 1311867171.9946711063 0.0850523412 0.0736088245 0.0850523412 0.0070017092 0.1625540000 139437154 0 1347575808 -0.0748927444 -0.0551521592 -0.0476201288 48 1311867172.0262680054 0.0854368806 0.0738552424 0.0854368806 0.0071503574 0.1679010000 139438920 0 1348083712 -0.0791122764 -0.0533948392 -0.0472032279 49 1311867172.0622880459 0.0856718719 0.0740963981 0.0856718719 0.0071045620 0.1643840000 139440750 0 1348591616 -0.0831826404 -0.0516581424 -0.0463511795 50 1311867172.0941960812 0.0870929435 0.0743563290 0.0870929435 0.0070430865 0.1668490000 139442516 0 1349099520 -0.0884288922 -0.0515818968 -0.0451273285 51 1311867172.1263689995 0.0889250040 0.0746419893 0.0889250040 0.0071288219 0.1480800000 139444282 0 1349734400 -0.0937078148 -0.0502844863 -0.0439713672 52 1311867172.1623349190 0.0890306458 0.0749186942 0.0890306458 0.0070834569 0.1598820000 139446112 0 1350242304 -0.0977197364 -0.0487202406 -0.0435591899 53 1311867172.1944270134 0.0886843130 0.0751784229 0.0890306458 0.0070199920 0.3831600000 158280594 0 1366638592 -0.1000753194 -0.0481056087 -0.0431115143 54 1311867172.2264409065 0.0849899948 0.0753601187 0.0890306458 0.0070601981 0.1813130000 161940208 0 1370939392 -0.0965256542 -0.0456651561 -0.0436446853 55 1311867172.2622280121 0.0841381177 0.0755197186 0.0890306458 0.0069975681 0.1223470000 165134134 0 1374621696 -0.0986744016 -0.0441995263 -0.0433749519 56 1311867172.2944829464 0.0847942829 0.0756853359 0.0890306458 0.0069361342 0.1195100000 165135900 0 1375510528 -0.1017029360 -0.0432034954 -0.0424855053 57 1311867172.3263380527 0.0856886655 0.0758608329 0.0890306458 0.0069178926 0.1170170000 165137666 0 1376018432 -0.1067240164 -0.0415253900 -0.0421048403 58 1311867172.3624010086 0.0877941921 0.0760665804 0.0890306458 0.0068891608 0.1151890000 165139496 0 1376526336 -0.1114722490 -0.0405990109 -0.0405959748 59 1311867172.3942890167 0.0877317637 0.0762642954 0.0890306458 0.0068429625 0.1173170000 165141262 0 1377050624 -0.1152382195 -0.0399758443 -0.0408228897 60 1311867172.4265220165 0.0906556845 0.0765041519 0.0906556845 0.0068900045 0.1215590000 165143028 0 1377669120 -0.1196732298 -0.0398743600 -0.0394906029 61 1311867172.4623498917 0.0872515514 0.0766803388 0.0906556845 0.0069172407 0.1164880000 165144858 0 1378177024 -0.1183418706 -0.0387484282 -0.0410931073 62 1311867172.4952669144 0.0891652629 0.0768817085 0.0906556845 0.0069066713 0.1201130000 165146592 0 1378684928 -0.1215594932 -0.0395075828 -0.0401822701 63 1311867172.5263059139 0.0929110050 0.0771361418 0.0929110050 0.0069245840 0.1408440000 165148358 0 1379192832 -0.1270460635 -0.0412444398 -0.0385706834 64 1311867172.5624930859 0.0905001536 0.0773449545 0.0929110050 0.0068822479 0.1263840000 165150188 0 1379827712 -0.1272225529 -0.0398295112 -0.0406066813 65 1311867172.5945439339 0.0911238641 0.0775569377 0.0929110050 0.0068338943 0.1231210000 165157298 0 1380335616 -0.1298922598 -0.0397991538 -0.0410118997 66 1311867172.6263699532 0.0925570950 0.0777842128 0.0929110050 0.0068467118 0.1557690000 165169592 0 1380843520 -0.1339006126 -0.0390447304 -0.0415452197 67 1311867172.6624419689 0.0915907249 0.0779902802 0.0929110050 0.0067958930 0.1497960000 165171422 0 1381367808 -0.1363732964 -0.0385508388 -0.0428781286 68 1311867172.6945450306 0.0924443901 0.0782028406 0.0929110050 0.0068674160 0.1481900000 165173188 0 1381986304 -0.1390291899 -0.0372332260 -0.0428831726 69 1311867172.7263929844 0.0919665024 0.0784023140 0.0929110050 0.0068461587 0.1578980000 165174954 0 1382494208 -0.1425430179 -0.0357939973 -0.0440768227 70 1311867172.7623739243 0.0935761258 0.0786190827 0.0935761258 0.0068090857 0.1637390000 165176784 0 1383002112 -0.1485834271 -0.0341769680 -0.0438654460 71 1311867172.7944509983 0.0928275511 0.0788192020 0.0935761258 0.0067819504 0.1644960000 165178518 0 1383526400 -0.1518794000 -0.0335688554 -0.0452361517 72 1311867172.8263089657 0.0922959372 0.0790063788 0.0935761258 0.0067685973 0.1623520000 165180316 0 1384144896 -0.1546336710 -0.0334405079 -0.0468167774 73 1311867172.8632309437 0.0925136805 0.0791914104 0.0935761258 0.0067266276 0.1621360000 165182178 0 1384652800 -0.1589122415 -0.0323452987 -0.0479338467 74 1311867172.8944649696 0.0931694806 0.0793803032 0.0935761258 0.0066836360 0.1645260000 165183880 0 1385160704 -0.1620777249 -0.0325480513 -0.0481896326 75 1311867172.9263219833 0.0999852493 0.0796550358 0.0999852493 0.0066610409 0.2242870000 165185678 0 1385668608 -0.1688062847 -0.0344890691 -0.0433854796 76 1311867172.9623310566 0.0985876769 0.0799041495 0.0999852493 0.0066228976 0.1688760000 165187508 0 1386303488 -0.1693524867 -0.0329541750 -0.0452672914 77 1311867172.9945271015 0.0994125530 0.0801575054 0.0999852493 0.0065818459 0.1611660000 165189242 0 1386811392 -0.1718998849 -0.0329957157 -0.0457610227 78 1311867173.0262629986 0.0989909023 0.0803989592 0.0999852493 0.0065436392 0.1707740000 165191008 0 1387319296 -0.1728550345 -0.0336012170 -0.0464854985 79 1311867173.0624630451 0.0986180604 0.0806295808 0.0999852493 0.0065022796 0.1660970000 165192838 0 1387843584 -0.1736802608 -0.0344673470 -0.0470911264 80 1311867173.0945179462 0.1003993228 0.0808767025 0.1003993228 0.0065314437 0.1654780000 165194604 0 1388462080 -0.1762401015 -0.0345441215 -0.0465153493 81 1311867173.1267819405 0.0981804058 0.0810903285 0.1003993228 0.0065271327 0.1645650000 165196402 0 1388969984 -0.1760121584 -0.0335537791 -0.0480852872 82 1311867173.1622309685 0.0979960412 0.0812964957 0.1003993228 0.0065234599 0.1648750000 165198232 0 1389477888 -0.1776926219 -0.0328369662 -0.0487437733 83 1311867173.1943008900 0.0990618765 0.0815105365 0.1003993228 0.0064877679 0.1664630000 165199966 0 1389985792 -0.1808742583 -0.0325756036 -0.0485748947 84 1311867173.2264449596 0.0975084379 0.0817009877 0.1003993228 0.0064681206 0.1642240000 165201732 0 1390510080 -0.1817342192 -0.0312151704 -0.0493276156 85 1311867173.2622020245 0.0994479135 0.0819097750 0.1003993228 0.0064919292 0.1752970000 165203562 0 1391128576 -0.1835024059 -0.0308395494 -0.0469812043 86 1311867173.2942678928 0.1005602255 0.0821266407 0.1005602255 0.0064679468 0.3471210000 177512056 0 1403953152 -0.1878036857 -0.0300379507 -0.0471897870 87 1311867173.3262879848 0.1015295014 0.0823496621 0.1015295014 0.0064326899 0.1643250000 181172078 0 1407889408 -0.1907767802 -0.0288560726 -0.0465970151 88 1311867173.3623280525 0.1031364277 0.0825858754 0.1031364277 0.0064026220 0.1645750000 184366036 0 1411571712 -0.1947569549 -0.0280129965 -0.0461238399 89 1311867173.3942871094 0.1033833921 0.0828195553 0.1033833921 0.0063773720 0.1339970000 184367770 0 1412460544 -0.1971790045 -0.0282016434 -0.0456869788 90 1311867173.4262790680 0.1051931009 0.0830681503 0.1051931009 0.0063451898 0.1425150000 184369536 0 1412968448 -0.2011307180 -0.0282800440 -0.0446485840 91 1311867173.4622900486 0.1045551598 0.0833042713 0.1051931009 0.0063448618 0.1352070000 184371366 0 1413492736 -0.2031039745 -0.0284266584 -0.0447140373 92 1311867173.4943389893 0.1058208570 0.0835490168 0.1058208570 0.0064354790 0.1348960000 184373132 0 1414111232 -0.2048809081 -0.0285580829 -0.0443494469 93 1311867173.5263900757 0.1055361629 0.0837854377 0.1058208570 0.0064026909 0.1311230000 184374930 0 1414746112 -0.2071815133 -0.0283513833 -0.0450559445 94 1311867173.5624370575 0.1047548652 0.0840085167 0.1058208570 0.0064039631 0.1387520000 184376760 0 1415254016 -0.2088948190 -0.0281716995 -0.0454036146 95 1311867173.5943109989 0.1073393449 0.0842541044 0.1073393449 0.0064271668 0.1248050000 184378494 0 1415888896 -0.2124691755 -0.0280254968 -0.0438574329 96 1311867173.6263959408 0.1085701510 0.0845073965 0.1085701510 0.0064047750 0.1483120000 184380260 0 1416396800 -0.2161315978 -0.0288066193 -0.0434241556 97 1311867173.6623299122 0.1075584218 0.0847450360 0.1085701510 0.0063807741 0.1298920000 184382090 0 1416921088 -0.2164996713 -0.0285301413 -0.0446059592 98 1311867173.6943540573 0.1096313372 0.0849989778 0.1096313372 0.0063506738 0.1331390000 184383856 0 1417539584 -0.2195519805 -0.0289636403 -0.0436759405 99 1311867173.7267971039 0.1105020046 0.0852565841 0.1105020046 0.0063282198 0.1482440000 184385654 0 1418047488 -0.2214422822 -0.0284876898 -0.0434862301 100 1311867173.7623970509 0.1075902432 0.0854799207 0.1105020046 0.0063016667 0.1534760000 184387484 0 1418682368 -0.2211091369 -0.0280575529 -0.0465455800 101 1311867173.7943561077 0.1112653166 0.0857352217 0.1112653166 0.0062788700 0.1485820000 184389186 0 1419190272 -0.2248759270 -0.0292429999 -0.0442931429 102 1311867173.8265669346 0.1115680784 0.0859884850 0.1115680784 0.0062485835 0.1442540000 184390984 0 1419698176 -0.2273778319 -0.0292184651 -0.0452668630 103 1311867173.8635799885 0.1108164415 0.0862295331 0.1115680784 0.0062304089 0.1543820000 184392782 0 1420222464 -0.2285989523 -0.0290017594 -0.0466857404 104 1311867173.8946080208 0.1149415076 0.0865056098 0.1149415076 0.0062217746 0.1492510000 184394548 0 1420840960 -0.2327703387 -0.0292864162 -0.0444787592 105 1311867173.9266970158 0.1155844480 0.0867825511 0.1155844480 0.0061981025 0.1685100000 184396346 0 1421357056 -0.2364445180 -0.0304001663 -0.0453026518 106 1311867173.9625461102 0.1124966517 0.0870251370 0.1155844480 0.0061892943 0.1627520000 184398176 0 1421864960 -0.2361299545 -0.0285978727 -0.0480887890 107 1311867173.9944310188 0.1154800132 0.0872910704 0.1155844480 0.0061728773 0.1703930000 184399910 0 1422389248 -0.2395751476 -0.0285519343 -0.0460462607 108 1311867174.0264260769 0.1157245263 0.0875543431 0.1157245263 0.0061634783 0.1663800000 184401676 0 1423134720 -0.2410613745 -0.0287440475 -0.0465872772 109 1311867174.0624630451 0.1113917530 0.0877730349 0.1157245263 0.0061426089 0.1710050000 184403506 0 1423642624 -0.2396119833 -0.0265994668 -0.0499596745 110 1311867174.0945188999 0.1146012470 0.0880169278 0.1157245263 0.0061554368 0.1687510000 184405272 0 1424150528 -0.2429358959 -0.0261080936 -0.0480650216 111 1311867174.1264541149 0.1166232675 0.0882746426 0.1166232675 0.0061567311 0.1731410000 184407038 0 1424658432 -0.2466658950 -0.0257470571 -0.0472873487 112 1311867174.1624329090 0.1141073927 0.0885052921 0.1166232675 0.0061441106 0.1740370000 184408868 0 1425182720 -0.2474601418 -0.0257547013 -0.0502009839 113 1311867174.1943979263 0.1149771586 0.0887395564 0.1166232675 0.0061248085 0.1571220000 184410634 0 1425801216 -0.2496740520 -0.0247853361 -0.0492836647 114 1311867174.2267580032 0.1176447272 0.0889931105 0.1176447272 0.0061053073 0.1726790000 184412432 0 1426309120 -0.2532842755 -0.0242655799 -0.0470261872 115 1311867174.2626769543 0.1149622947 0.0892189295 0.1176447272 0.0060970713 0.1851370000 184414230 0 1426817024 -0.2536660135 -0.0242488645 -0.0492180586 116 1311867174.2945280075 0.1166725308 0.0894555985 0.1176447272 0.0061412060 0.1705750000 184415996 0 1427341312 -0.2547323704 -0.0236618575 -0.0475947522 117 1311867174.3265740871 0.1189241186 0.0897074662 0.1189241186 0.0061249212 0.1758370000 184417762 0 1427959808 -0.2590416074 -0.0237465128 -0.0469760448 118 1311867174.3624329567 0.1176654845 0.0899443986 0.1189241186 0.0061023659 0.1817060000 184419624 0 1428467712 -0.2609449327 -0.0233536027 -0.0485761724 119 1311867174.3946359158 0.1192604154 0.0901907517 0.1192604154 0.0061118111 0.1716170000 184421358 0 1428975616 -0.2639997900 -0.0225741994 -0.0479970127 120 1311867174.4266788960 0.1225407794 0.0904603352 0.1225407794 0.0061176602 0.1741250000 184423156 0 1429483520 -0.2672364116 -0.0207098294 -0.0451817438 121 1311867174.4630160332 0.1198656484 0.0907033543 0.1225407794 0.0061681962 0.1771540000 184424954 0 1430007808 -0.2684063613 -0.0221297145 -0.0472081862 122 1311867174.4945669174 0.1194636747 0.0909390947 0.1225407794 0.0061495820 0.1829040000 184426720 0 1430626304 -0.2688951194 -0.0211197287 -0.0471783727 123 1311867174.5267519951 0.1222673655 0.0911937961 0.1225407794 0.0061303843 0.1699680000 184428518 0 1431134208 -0.2728068829 -0.0205009039 -0.0445776582 124 1311867174.5623500347 0.1198518202 0.0914249091 0.1225407794 0.0061235627 0.1766530000 184430348 0 1431642112 -0.2734705508 -0.0209979434 -0.0467581376 125 1311867174.5944879055 0.1207904667 0.0916598336 0.1225407794 0.0061194794 0.1750900000 184432082 0 1432166400 -0.2758122981 -0.0197826643 -0.0458438508 126 1311867174.6265459061 0.1226474866 0.0919057674 0.1226474866 0.0061127458 0.1646690000 184433848 0 1432784896 -0.2791363597 -0.0191327557 -0.0439577773 127 1311867174.6624910831 0.1225956455 0.0921474199 0.1226474866 0.0060912887 0.1749510000 184435678 0 1433292800 -0.2815983593 -0.0195982810 -0.0440450646 128 1311867174.6945910454 0.1194132417 0.0923604342 0.1226474866 0.0060797414 0.1838810000 184437444 0 1433800704 -0.2825924754 -0.0187526718 -0.0472589768 129 1311867174.7265629768 0.1246949509 0.0926110893 0.1246949509 0.0061229603 0.1725790000 184449930 0 1434324992 -0.2858832777 -0.0170751140 -0.0418492369 130 1311867174.7623760700 0.1238916665 0.0928517092 0.1246949509 0.0061139864 0.1735270000 184472784 0 1434943488 -0.2875468731 -0.0173454769 -0.0424268022 131 1311867174.7944738865 0.1229425296 0.0930814101 0.1246949509 0.0060961679 0.1718750000 184474486 0 1435467776 -0.2884570956 -0.0172269791 -0.0430308320 132 1311867174.8273301125 0.1246913001 0.0933208790 0.1246949509 0.0060770232 0.4011700000 196781132 0 1448529920 -0.2913402319 -0.0179152247 -0.0416163318 133 1311867174.8624229431 0.1257068515 0.0935643825 0.1257068515 0.0063368761 0.2121120000 200440842 0 1452466176 -0.2918991148 0.0003961760 -0.0442835353 134 1311867174.8944199085 0.1249983385 0.0937989643 0.1257068515 0.0063153128 0.1604180000 203634672 0 1456148480 -0.2925125659 -0.0001927452 -0.0442086644 135 1311867174.9269750118 0.1244578660 0.0940260672 0.1257068515 0.0062953331 0.1443110000 203636438 0 1457037312 -0.2934811413 -0.0002284128 -0.0446377359 136 1311867174.9626429081 0.1273500025 0.0942710962 0.1273500025 0.0062818351 0.1459600000 203638300 0 1457545216 -0.2977862060 -0.0005378220 -0.0428557880 137 1311867174.9943349361 0.1269254237 0.0945094489 0.1273500025 0.0062686924 0.1457250000 203640034 0 1458053120 -0.2998116612 0.0020003784 -0.0447605886 138 1311867175.0265510082 0.1283425838 0.0947546166 0.1283425838 0.0062543829 0.1411550000 203641832 0 1458688000 -0.3027724028 0.0034142833 -0.0439472236 139 1311867175.0633120537 0.1294873953 0.0950044927 0.1294873953 0.0062359521 0.1363390000 203643662 0 1459195904 -0.3061295450 0.0035378824 -0.0431826524 140 1311867175.0947189331 0.1283049136 0.0952423528 0.1294873953 0.0062273898 0.1669600000 203645428 0 1459703808 -0.3063491285 0.0048682569 -0.0435961932 141 1311867175.1265308857 0.1278164387 0.0954733747 0.1294873953 0.0062066871 0.1482800000 203647194 0 1460211712 -0.3073268533 0.0049900771 -0.0432381593 142 1311867175.1625180244 0.1285547763 0.0957063423 0.1294873953 0.0062183862 0.1678170000 203649024 0 1460736000 -0.3090090752 0.0057126218 -0.0424988493 143 1311867175.1946399212 0.1288411915 0.0959380546 0.1294873953 0.0061965376 0.1422290000 203650758 0 1461354496 -0.3107477129 0.0060432646 -0.0422585607 144 1311867175.2270050049 0.1273968518 0.0961565184 0.1294873953 0.0062330618 0.1567890000 203652556 0 1461862400 -0.3105556965 0.0088473856 -0.0422175229 145 1311867175.2624669075 0.1301475912 0.0963909396 0.1301475912 0.0062950541 0.1805370000 203654354 0 1462370304 -0.3144305944 0.0089502698 -0.0401158445 146 1311867175.2944509983 0.1302578896 0.0966229050 0.1302578896 0.0062737847 0.1552170000 203656120 0 1462878208 -0.3161566257 0.0106120259 -0.0396865048 147 1311867175.3267059326 0.1290474534 0.0968434802 0.1302578896 0.0062552231 0.1552480000 203657918 0 1463402496 -0.3164112270 0.0130596077 -0.0393480435 148 1311867175.3625650406 0.1302266568 0.0970690422 0.1302578896 0.0062536433 0.1544480000 203659716 0 1464020992 -0.3199499547 0.0112382853 -0.0378755815 149 1311867175.3945989609 0.1307660788 0.0972951968 0.1307660788 0.0062325644 0.1554150000 203661482 0 1464528896 -0.3227186799 0.0119687300 -0.0372081175 150 1311867175.4266059399 0.1311814934 0.0975211055 0.1311814934 0.0062147592 0.1541770000 203663248 0 1465036800 -0.3254599869 0.0138727603 -0.0366752222 151 1311867175.4625999928 0.1327475458 0.0977543931 0.1327475458 0.0061940133 0.1811620000 203665110 0 1465671680 -0.3305369020 0.0137462746 -0.0349336304 152 1311867175.4945731163 0.1335877031 0.0979901386 0.1335877031 0.0061781011 0.1529470000 203666876 0 1466179584 -0.3342170417 0.0150053771 -0.0342635140 153 1311867175.5264270306 0.1330386549 0.0982192139 0.1335877031 0.0061699259 0.1530500000 203668610 0 1466687488 -0.3356001675 0.0159702413 -0.0342280269 154 1311867175.5625700951 0.1331973523 0.0984463446 0.1335877031 0.0061640142 0.2036760000 203670472 0 1467211776 -0.3381659985 0.0179294962 -0.0334017202 155 1311867175.5946640968 0.1352551430 0.0986838208 0.1352551430 0.0061800648 0.1686410000 203672206 0 1467830272 -0.3426599801 0.0170855392 -0.0320344009 156 1311867175.6264801025 0.1365862340 0.0989267849 0.1365862340 0.0061710978 0.1877500000 203673972 0 1468338176 -0.3464866579 0.0197863169 -0.0312683359 157 1311867175.6624929905 0.1378076673 0.0991744339 0.1378076673 0.0062171328 0.2119040000 203675802 0 1468862464 -0.3493108749 0.0212488528 -0.0304941386 158 1311867175.6947000027 0.1383021474 0.0994220776 0.1383021474 0.0062170538 0.1957070000 203677568 0 1469480960 -0.3536348045 0.0197233334 -0.0297243036 159 1311867175.7273120880 0.1373840719 0.0996608323 0.1383021474 0.0061977230 0.2051460000 203679366 0 1469980672 -0.3544257879 0.0209507272 -0.0301895496 160 1311867175.7624969482 0.1378409714 0.0998994582 0.1383021474 0.0061878439 0.1977340000 203681196 0 1470488576 -0.3568253219 0.0216659270 -0.0298208799 161 1311867175.7948620319 0.1385799050 0.1001397094 0.1385799050 0.0061896590 0.1832990000 203682930 0 1470996480 -0.3603772223 0.0197375119 -0.0286196973 162 1311867175.8287971020 0.1393852681 0.1003819659 0.1393852681 0.0061785667 0.1802620000 203684760 0 1471520768 -0.3640182912 0.0211809631 -0.0289971046 163 1311867175.8625519276 0.1399197578 0.1006245291 0.1399197578 0.0061655912 0.2346440000 203686558 0 1472139264 -0.3671398461 0.0227942076 -0.0287650824 164 1311867175.8946080208 0.1413120925 0.1008726240 0.1413120925 0.0061599092 0.2198940000 203688292 0 1472647168 -0.3712887168 0.0218261108 -0.0279822163 165 1311867175.9282429218 0.1415864974 0.1011193747 0.1415864974 0.0061471044 0.2018570000 203690090 0 1473155072 -0.3745068610 0.0209365562 -0.0274023414 166 1311867175.9629371166 0.1409215927 0.1013591471 0.1415864974 0.0061299345 0.2273430000 203691888 0 1473679360 -0.3760634363 0.0233162213 -0.0285435859 167 1311867175.9983000755 0.1413101256 0.1015983745 0.1415864974 0.0061151782 0.1892740000 203693686 0 1474297856 -0.3786272407 0.0229676906 -0.0280812960 168 1311867176.0268509388 0.1431729198 0.1018458421 0.1431729198 0.0061014041 0.1826200000 203695388 0 1474805760 -0.3819849789 0.0204199087 -0.0265182536 169 1311867176.0627059937 0.1425483525 0.1020866853 0.1431729198 0.0061395229 0.2339780000 203697218 0 1475313664 -0.3844063580 0.0222302154 -0.0282631610 170 1311867176.0946600437 0.1434117705 0.1023297741 0.1434117705 0.0062022991 0.2190770000 203698952 0 1475821568 -0.3860163689 0.0234728493 -0.0287402868 171 1311867176.1268119812 0.1446505040 0.1025772637 0.1446505040 0.0061929503 0.1926950000 203700750 0 1476456448 -0.3885708153 0.0237172842 -0.0285736434 172 1311867176.1625900269 0.1440149248 0.1028181804 0.1446505040 0.0062639619 0.2367940000 203702580 0 1476964352 -0.3889652193 0.0236651804 -0.0285124499 173 1311867176.1946918964 0.1437693983 0.1030548926 0.1446505040 0.0063032288 0.2116700000 203704346 0 1477472256 -0.3889237344 0.0256019998 -0.0296761580 174 1311867176.2265360355 0.1452748775 0.1032975362 0.1452748775 0.0062906995 0.2190300000 203706112 0 1477996544 -0.3916657567 0.0254910942 -0.0286940541 175 1311867176.2625019550 0.1465459913 0.1035446702 0.1465459913 0.0062773951 0.2168630000 203707942 0 1478615040 -0.3943026066 0.0252079181 -0.0282128546 176 1311867176.2946109772 0.1473711580 0.1037936844 0.1473711580 0.0062814254 0.1864680000 203709676 0 1479122944 -0.3963253796 0.0309474804 -0.0299066771 177 1311867176.3266019821 0.1488829255 0.1040484258 0.1488829255 0.0062649844 0.2064930000 203711442 0 1479630848 -0.3987723887 0.0297943931 -0.0286359899 178 1311867176.3624560833 0.1494993716 0.1043037682 0.1494993716 0.0062522242 0.1911410000 203713304 0 1480138752 -0.4011508524 0.0310859885 -0.0295018181 179 1311867176.3952438831 0.1490083337 0.1045535144 0.1494993716 0.0062361362 0.1913680000 203715038 0 1480663040 -0.4014931917 0.0323442332 -0.0302213952 180 1311867176.4268360138 0.1489403695 0.1048001080 0.1494993716 0.0062191607 0.1933800000 203716804 0 1481281536 -0.4026386440 0.0336810872 -0.0307082683 181 1311867176.4629659653 0.1493016779 0.1050459731 0.1494993716 0.0062700569 0.1932260000 203718634 0 1481789440 -0.4046755731 0.0325613096 -0.0299888607 182 1311867176.4945809841 0.1507201046 0.1052969298 0.1507201046 0.0062790550 0.2029810000 203720368 0 1482297344 -0.4068117738 0.0345981270 -0.0310190488 183 1311867176.5266211033 0.1520067602 0.1055521748 0.1520067602 0.0063147873 0.3958160000 216030910 0 1495248896 -0.4092281461 0.0362301506 -0.0310685299 184 1311867176.5636389256 0.1499194652 0.1057933014 0.1520067602 0.0063238435 0.2377910000 219690620 0 1499185152 -0.4089381397 0.0337595306 -0.0320549421 185 1311867176.5946090221 0.1502135098 0.1060334106 0.1520067602 0.0063095046 0.1636490000 222884450 0 1503121408 -0.4113758206 0.0355861373 -0.0331222638 186 1311867176.6283841133 0.1506026238 0.1062730300 0.1520067602 0.0062951938 0.1443230000 222886248 0 1503883264 -0.4125407934 0.0361847468 -0.0326533765 187 1311867176.6625781059 0.1507114917 0.1065106689 0.1520067602 0.0062822884 0.1510030000 222888046 0 1504518144 -0.4149997532 0.0363223664 -0.0328635499 188 1311867176.6945180893 0.1519390643 0.1067523093 0.1520067602 0.0062712996 0.1390660000 222889780 0 1505026048 -0.4176613986 0.0371944718 -0.0323784575 189 1311867176.7265889645 0.1527418047 0.1069956399 0.1527418047 0.0062559827 0.1296780000 222891578 0 1505533952 -0.4208508432 0.0378995687 -0.0325288847 190 1311867176.7632329464 0.1535126120 0.1072404661 0.1535126120 0.0062426323 0.1441660000 222893408 0 1506058240 -0.4240179062 0.0385877453 -0.0322820731 191 1311867176.7947680950 0.1543495953 0.1074871108 0.1543495953 0.0062398497 0.1340210000 222895142 0 1506803712 -0.4263260961 0.0388206802 -0.0316121727 192 1311867176.8266770840 0.1544453949 0.1077316852 0.1544453949 0.0062242953 0.1325670000 222896940 0 1507311616 -0.4283052981 0.0387130491 -0.0316884406 193 1311867176.8627309799 0.1542883813 0.1079729116 0.1544453949 0.0062131428 0.1637520000 222898770 0 1507819520 -0.4302960336 0.0400473662 -0.0324455351 194 1311867176.8949549198 0.1567957550 0.1082245757 0.1567957550 0.0061986011 0.1452020000 222900536 0 1508327424 -0.4342347682 0.0395777561 -0.0303734355 195 1311867176.9268178940 0.1564194411 0.1084717289 0.1567957550 0.0061950057 0.1408760000 222902302 0 1508851712 -0.4370300174 0.0401835404 -0.0310012400 196 1311867176.9650609493 0.1567651331 0.1087181238 0.1567957550 0.0062076788 0.1780830000 222904132 0 1509470208 -0.4397691786 0.0419284366 -0.0314924121 197 1311867176.9947481155 0.1580654234 0.1089686177 0.1580654234 0.0061926063 0.1596920000 222905866 0 1510010880 -0.4418878555 0.0409326255 -0.0297417454 198 1311867177.0267279148 0.1584398746 0.1092184725 0.1584398746 0.0061788183 0.1527220000 222907632 0 1510502400 -0.4445057511 0.0408143289 -0.0297895446 199 1311867177.0626339912 0.1578895897 0.1094630510 0.1584398746 0.0061654960 0.1572700000 222909462 0 1511002112 -0.4463389814 0.0424211249 -0.0308748297 200 1311867177.0946850777 0.1590323448 0.1097108975 0.1590323448 0.0061500614 0.1594050000 222911228 0 1511620608 -0.4483631253 0.0415087529 -0.0295402370 201 1311867177.1266150475 0.1601798683 0.1099619869 0.1601798683 0.0061380404 0.1582690000 222912994 0 1512128512 -0.4518058896 0.0422481932 -0.0292976983 202 1311867177.1627299786 0.1602497250 0.1102109361 0.1602497250 0.0061233932 0.1630440000 222914824 0 1512652800 -0.4542314410 0.0431205630 -0.0294040535 203 1311867177.1946458817 0.1606425643 0.1104593677 0.1606425643 0.0061115542 0.1726460000 222916590 0 1513156608 -0.4561194181 0.0435692593 -0.0291733164 204 1311867177.2264730930 0.1619329005 0.1107116890 0.1619329005 0.0060979086 0.1731300000 222918356 0 1513779200 -0.4586590528 0.0432411022 -0.0280187298 205 1311867177.2638640404 0.1616791040 0.1109603105 0.1619329005 0.0060838875 0.1850990000 222920218 0 1514287104 -0.4607628286 0.0443512686 -0.0289263241 206 1311867177.2946178913 0.1635143757 0.1112154273 0.1635143757 0.0060745702 0.1809070000 222921952 0 1514795008 -0.4640573561 0.0441034175 -0.0272305552 207 1311867177.3276090622 0.1623105109 0.1114622635 0.1635143757 0.0060617164 0.1787650000 222923750 0 1515302912 -0.4657940567 0.0455707014 -0.0291204676 208 1311867177.3627710342 0.1635517925 0.1117126939 0.1635517925 0.0060494368 0.1974330000 222925548 0 1515937792 -0.4686800539 0.0459677987 -0.0284550544 209 1311867177.3946089745 0.1645458937 0.1119654843 0.1645458937 0.0060617819 0.2037130000 222927314 0 1516462080 -0.4711175263 0.0466957651 -0.0282521676 210 1311867177.4267480373 0.1648917645 0.1122175143 0.1648917645 0.0060502151 0.1935840000 222929080 0 1516986368 -0.4735398889 0.0474337339 -0.0283610225 211 1311867177.4626040459 0.1649901271 0.1124676214 0.1649901271 0.0060383724 0.1860390000 222930942 0 1517461504 -0.4756185710 0.0476423055 -0.0284578819 212 1311867177.4946429729 0.1654856801 0.1127177066 0.1654856801 0.0060242255 0.1770810000 222932708 0 1517985792 -0.4772789776 0.0482020564 -0.0280113500 213 1311867177.5276169777 0.1659535915 0.1129676403 0.1659535915 0.0060109649 0.1739080000 222934442 0 1518604288 -0.4797194898 0.0499695837 -0.0285620391 214 1311867177.5626399517 0.1671395302 0.1132207800 0.1671395302 0.0060070110 0.1785930000 222936272 0 1519112192 -0.4824629426 0.0493511558 -0.0277127586 215 1311867177.5947310925 0.1672928929 0.1134722782 0.1672928929 0.0059943707 0.1773700000 222938038 0 1519628288 -0.4837050140 0.0504504256 -0.0280446745 216 1311867177.6311450005 0.1676062793 0.1137228986 0.1676062793 0.0059813128 0.1698530000 222939900 0 1520152576 -0.4855948389 0.0510538965 -0.0280953143 217 1311867177.6624829769 0.1677621603 0.1139719274 0.1677621603 0.0059676653 0.1696890000 222941666 0 1520783360 -0.4868852496 0.0522339158 -0.0283525940 218 1311867177.6945610046 0.1681808531 0.1142205922 0.1681808531 0.0059692712 0.1702550000 222943432 0 1521303552 -0.4886426032 0.0526731163 -0.0281354059 219 1311867177.7305839062 0.1675368249 0.1144640454 0.1681808531 0.0059567597 0.1791670000 222945230 0 1521811456 -0.4893763065 0.0538579412 -0.0293214452 220 1311867177.7625379562 0.1687242687 0.1147106827 0.1687242687 0.0059442346 0.1706540000 222946996 0 1522319360 -0.4903605580 0.0537290499 -0.0284227896 221 1311867177.7945590019 0.1699494869 0.1149606321 0.1699494869 0.0059356804 0.1808360000 222948762 0 1522954240 -0.4922153652 0.0542330816 -0.0284596235 222 1311867177.8309149742 0.1699732840 0.1152084368 0.1699732840 0.0059272298 0.1943590000 222950592 0 1523462144 -0.4934230447 0.0539734326 -0.0290944390 223 1311867177.8625319004 0.1698713601 0.1154535620 0.1699732840 0.0059140717 0.1625950000 222952358 0 1523970048 -0.4940527380 0.0547940098 -0.0298557673 224 1311867177.8946919441 0.1705665886 0.1156996023 0.1705665886 0.0059030418 0.1828230000 222954092 0 1524477952 -0.4950186610 0.0557562262 -0.0299565867 225 1311867177.9317860603 0.1712359339 0.1159464305 0.1712359339 0.0058900287 0.1626680000 222955986 0 1524985856 -0.4962112606 0.0557259955 -0.0296563935 226 1311867177.9627909660 0.1718886793 0.1161939625 0.1718886793 0.0058953970 0.1852840000 222957720 0 1525620736 -0.4976949096 0.0570980012 -0.0301333684 227 1311867177.9947769642 0.1726761758 0.1164427829 0.1726761758 0.0058855537 0.1763680000 222959422 0 1526128640 -0.4995739758 0.0580527596 -0.0306460392 228 1311867178.0306100845 0.1736386418 0.1166936419 0.1736386418 0.0058737749 0.1854240000 222961252 0 1526636544 -0.5020213127 0.0572247431 -0.0302446689 229 1311867178.0634479523 0.1734364629 0.1169414271 0.1736386418 0.0058650722 0.1868120000 222963018 0 1527271424 -0.5027893782 0.0589611568 -0.0312636271 230 1311867178.0951139927 0.1733517349 0.1171866893 0.1736386418 0.0058523422 0.1840930000 222964784 0 1527779328 -0.5040448904 0.0591976307 -0.0316815339 231 1311867178.1307909489 0.1748582125 0.1174363496 0.1748582125 0.0058405403 0.1858290000 222966614 0 1528287232 -0.5061767101 0.0582250804 -0.0300626177 232 1311867178.1627469063 0.1745806783 0.1176826614 0.1748582125 0.0058574874 0.1883460000 222968380 0 1528795136 -0.5080780983 0.0595932156 -0.0315537564 233 1311867178.1950459480 0.1755993813 0.1179312310 0.1755993813 0.0058521503 0.1873310000 222970114 0 1529430016 -0.5110421181 0.0602743402 -0.0315282308 234 1311867178.2307190895 0.1769393682 0.1181834025 0.1769393682 0.0058463868 0.1877320000 222971944 0 1529937920 -0.5136762261 0.0586585365 -0.0301780086 235 1311867178.2628939152 0.1762017459 0.1184302891 0.1769393682 0.0058348396 0.1922730000 222973742 0 1530445824 -0.5157731175 0.0606240183 -0.0318076238 236 1311867178.2954900265 0.1765705645 0.1186766462 0.1769393682 0.0058232130 0.1871230000 222975508 0 1530953728 -0.5179343224 0.0606454089 -0.0316306055 237 1311867178.3306670189 0.1774295717 0.1189245488 0.1774295717 0.0058126260 0.1872110000 222977306 0 1531461632 -0.5205904841 0.0594897196 -0.0304841138 238 1311867178.3627231121 0.1770340949 0.1191687066 0.1774295717 0.0058027727 0.1867900000 222979104 0 1532096512 -0.5228835940 0.0611764789 -0.0313408971 239 1311867178.3949439526 0.1776335090 0.1194133292 0.1776335090 0.0057909883 0.1866740000 222980838 0 1532604416 -0.5246751904 0.0602546521 -0.0302823540 240 1311867178.4306581020 0.1768545806 0.1196526677 0.1776335090 0.0057859647 0.1787600000 222982668 0 1533112320 -0.5250768065 0.0620938055 -0.0307433214 241 1311867178.4628739357 0.1779685169 0.1198946422 0.1779685169 0.0057739728 0.1811430000 222984434 0 1533620224 -0.5284847021 0.0612746179 -0.0298953298 242 1311867178.4946439266 0.1781797856 0.1201354899 0.1781797856 0.0057630942 0.1833560000 222986200 0 1534255104 -0.5309417248 0.0612225719 -0.0298968200 243 1311867178.5306270123 0.1777240038 0.1203724797 0.1781797856 0.0057611271 0.1788960000 222988030 0 1534763008 -0.5332183838 0.0627922937 -0.0308897421 244 1311867178.5626420975 0.1790946424 0.1206131443 0.1790946424 0.0057506542 0.1735770000 222989828 0 1535270912 -0.5339360833 0.0633761585 -0.0287266076 245 1311867178.5947000980 0.1796340495 0.1208540459 0.1796340495 0.0057408393 0.1861550000 222991594 0 1535778816 -0.5365003347 0.0622993074 -0.0282930378 246 1311867178.6306900978 0.1790868491 0.1210907646 0.1796340495 0.0057308957 0.1663890000 222993392 0 1536413696 -0.5368000269 0.0631728396 -0.0286074858 247 1311867178.6626410484 0.1801386923 0.1213298251 0.1801386923 0.0057356898 0.1765650000 222995190 0 1536921600 -0.5384504199 0.0628756955 -0.0272109024 248 1311867178.6946120262 0.1801271588 0.1215669111 0.1801386923 0.0057272035 0.1865930000 222996924 0 1537429504 -0.5401586294 0.0623912103 -0.0275586676 249 1311867178.7307450771 0.1800753921 0.1218018849 0.1801386923 0.0057230225 0.1816390000 222998754 0 1537937408 -0.5415155888 0.0646667629 -0.0287044700 250 1311867178.7632350922 0.1819171607 0.1220423460 0.1819171607 0.0057121326 0.1849710000 223000552 0 1538572288 -0.5442110896 0.0644337386 -0.0275184084 251 1311867178.8006799221 0.1807119399 0.1222760894 0.1819171607 0.0057044195 0.1737340000 223002382 0 1539080192 -0.5433593392 0.0644882545 -0.0282378998 252 1311867178.8309500217 0.1803256869 0.1225064450 0.1819171607 0.0056980657 0.1838100000 223004116 0 1539588096 -0.5444707870 0.0660890564 -0.0296137091 253 1311867178.8627939224 0.1816096902 0.1227400546 0.1819171607 0.0056913810 0.1879910000 223005914 0 1540096000 -0.5450103283 0.0640802607 -0.0275198668 254 1311867178.8950169086 0.1819018126 0.1229729749 0.1819171607 0.0056812047 0.1896940000 223007648 0 1540730880 -0.5445760489 0.0623147078 -0.0267824233 255 1311867178.9306209087 0.1796183437 0.1231951137 0.1819171607 0.0056750995 0.1597440000 223009478 0 1541238784 -0.5407805443 0.0644155741 -0.0289976560 256 1311867178.9627609253 0.1827479899 0.1234277421 0.1827479899 0.0056660519 0.1911120000 223011276 0 1541746688 -0.5449561477 0.0635031015 -0.0275855716 257 1311867178.9946830273 0.1829547286 0.1236593646 0.1829547286 0.0056592513 0.1785310000 223034546 0 1542254592 -0.5480152369 0.0648651123 -0.0293983575 258 1311867179.0309159756 0.1838008761 0.1238924712 0.1838008761 0.0056711609 0.1815170000 223078360 0 1542889472 -0.5516114831 0.0674696341 -0.0310146119 259 1311867179.0628120899 0.1847799867 0.1241275582 0.1847799867 0.0056623671 0.1753830000 223080158 0 1543397376 -0.5518174767 0.0656001568 -0.0292952843 260 1311867179.0968120098 0.1844243407 0.1243594689 0.1847799867 0.0056718728 0.1788430000 223081892 0 1544032256 -0.5491933227 0.0622811690 -0.0279975720 261 1311867179.1310369968 0.1833636314 0.1245855384 0.1847799867 0.0056636829 0.1718940000 223083690 0 1544540160 -0.5491812229 0.0644202158 -0.0307052899 262 1311867179.1627540588 0.1876330674 0.1248261779 0.1876330674 0.0057119616 0.1863210000 223085456 0 1545048064 -0.5529906750 0.0620780066 -0.0282749441 263 1311867179.1956849098 0.1870429665 0.1250627436 0.1876330674 0.0057053447 0.1737100000 223087190 0 1545555968 -0.5554166436 0.0642629638 -0.0313255824 264 1311867179.2307469845 0.1876052469 0.1252996470 0.1876330674 0.0057037809 0.1707250000 223089020 0 1546190848 -0.5596380830 0.0658305138 -0.0336010531 265 1311867179.2634611130 0.1882778257 0.1255373005 0.1882778257 0.0057030650 0.1726730000 223090850 0 1546698752 -0.5632148981 0.0638758987 -0.0337856300 266 1311867179.2959198952 0.1875156015 0.1257703017 0.1882778257 0.0056934800 0.5154250000 235396400 0 1559523328 -0.5633979440 0.0653392822 -0.0349870846 267 1311867179.3307149410 0.1802621037 0.1259743908 0.1882778257 0.0057481214 0.1721240000 239056078 0 1563459584 -0.5594091415 0.0618985593 -0.0401080996 268 1311867179.3629300594 0.1808391511 0.1261791101 0.1882778257 0.0057378189 0.1122000000 242250004 0 1567674368 -0.5613098145 0.0619145148 -0.0400928780 269 1311867179.3948490620 0.1831158847 0.1263907709 0.1882778257 0.0057320883 0.1520780000 242251706 0 1568563200 -0.5651564598 0.0621242337 -0.0390930027 270 1311867179.4308040142 0.1820830554 0.1265970387 0.1882778257 0.0057357468 0.1577830000 242253568 0 1569165312 -0.5657467246 0.0654577911 -0.0406096019 271 1311867179.4637460709 0.1821410209 0.1268019980 0.1882778257 0.0057386549 0.1425050000 242255366 0 1569673216 -0.5668101311 0.0645991489 -0.0396853052 272 1311867179.4949469566 0.1819855422 0.1270048787 0.1882778257 0.0057303999 0.1386650000 242257100 0 1570291712 -0.5666514635 0.0642394349 -0.0389742926 273 1311867179.5307800770 0.1815038472 0.1272045086 0.1882778257 0.0057286620 0.1415000000 242258930 0 1570799616 -0.5663051009 0.0669016913 -0.0389132239 274 1311867179.5627610683 0.1828797013 0.1274077027 0.1882778257 0.0057335118 0.1268900000 242260696 0 1571307520 -0.5688405633 0.0661049187 -0.0373194963 275 1311867179.5946741104 0.1822773218 0.1276072286 0.1882778257 0.0057257372 0.1334520000 242262462 0 1571942400 -0.5704482198 0.0686367825 -0.0388356298 276 1311867179.6306900978 0.1833909154 0.1278093434 0.1882778257 0.0057478186 0.1525630000 242264260 0 1572450304 -0.5723565221 0.0698163137 -0.0380000137 277 1311867179.6625750065 0.1837832928 0.1280114154 0.1882778257 0.0057387521 0.1322970000 242266058 0 1572950016 -0.5725331903 0.0687567890 -0.0367315337 278 1311867179.6946051121 0.1832139194 0.1282099856 0.1882778257 0.0057450197 0.1349630000 242267792 0 1573457920 -0.5723722577 0.0701799765 -0.0370374955 279 1311867179.7309470177 0.1831165403 0.1284067833 0.1882778257 0.0057354428 0.1596770000 242269654 0 1573998592 -0.5732362270 0.0696830302 -0.0369409695 280 1311867179.7627270222 0.1840487123 0.1286055045 0.1882778257 0.0057436637 0.1281580000 242271420 0 1574600704 -0.5746805072 0.0694108978 -0.0358236618 281 1311867179.7948911190 0.1832010895 0.1287997948 0.1882778257 0.0057576362 0.1333180000 242273154 0 1575108608 -0.5743109584 0.0723450258 -0.0370057970 282 1311867179.8307530880 0.1841258854 0.1289959866 0.1882778257 0.0057495428 0.1466000000 242275016 0 1575616512 -0.5761479735 0.0721367896 -0.0360591821 283 1311867179.8627979755 0.1844275743 0.1291918580 0.1882778257 0.0057399879 0.1370120000 242276782 0 1576157184 -0.5771936774 0.0705749169 -0.0350308008 284 1311867179.8948040009 0.1838970184 0.1293844818 0.1882778257 0.0057301937 0.1131250000 242278548 0 1576759296 -0.5763372779 0.0714514628 -0.0348983854 285 1311867179.9309051037 0.1831042022 0.1295729720 0.1882778257 0.0057389123 0.1302180000 242280378 0 1577267200 -0.5750923157 0.0727053806 -0.0350573175 286 1311867179.9634931087 0.1843055487 0.1297643446 0.1882778257 0.0057334113 0.1351970000 242282144 0 1577775104 -0.5776445270 0.0703166723 -0.0335311815 287 1311867179.9958879948 0.1843786240 0.1299546383 0.1882778257 0.0057298053 0.1392850000 242283910 0 1578315776 -0.5786311030 0.0736662149 -0.0342609361 288 1311867180.0309770107 0.1843127161 0.1301433816 0.1882778257 0.0057200823 0.1607370000 242285740 0 1578917888 -0.5791987777 0.0749134719 -0.0341891274 289 1311867180.0626471043 0.1849178523 0.1303329127 0.1882778257 0.0057107969 0.1410120000 242287506 0 1579425792 -0.5799671412 0.0743291900 -0.0333082192 290 1311867180.0947730541 0.1855751127 0.1305234030 0.1882778257 0.0057023558 0.1294870000 242289240 0 1579933696 -0.5797368288 0.0760789290 -0.0329480208 291 1311867180.1307730675 0.1853339523 0.1307117554 0.1882778257 0.0056991905 0.1423850000 242291070 0 1580474368 -0.5786858201 0.0744142160 -0.0328405760 292 1311867180.1636800766 0.1838562787 0.1308937572 0.1882778257 0.0057202184 0.1376720000 242292868 0 1581076480 -0.5750769377 0.0738640502 -0.0332928076 293 1311867180.1949090958 0.1827056259 0.1310705895 0.1882778257 0.0057137124 0.1192530000 242294602 0 1581584384 -0.5746323466 0.0725801587 -0.0348554812 294 1311867180.2308139801 0.1831107736 0.1312475970 0.1882778257 0.0057079667 0.1496970000 242296400 0 1582219264 -0.5745853186 0.0726533383 -0.0356435888 295 1311867180.2637619972 0.1843207628 0.1314275060 0.1882778257 0.0057330814 0.1503840000 242298198 0 1582735360 -0.5758617520 0.0732561722 -0.0358736515 296 1311867180.2947549820 0.1840012521 0.1316051200 0.1882778257 0.0057238997 0.1253410000 242299932 0 1583243264 -0.5753042698 0.0733709186 -0.0365305133 297 1311867180.3308670521 0.1839413196 0.1317813362 0.1882778257 0.0057168539 0.1419620000 242301762 0 1583751168 -0.5741176009 0.0731015578 -0.0367503390 298 1311867180.3658199310 0.1833443195 0.1319543663 0.1882778257 0.0057118031 0.1220460000 242303528 0 1584291840 -0.5715590715 0.0730607808 -0.0371460617 299 1311867180.3961660862 0.1833999902 0.1321264252 0.1882778257 0.0057029065 0.1439740000 242305262 0 1584893952 -0.5718826652 0.0718964487 -0.0377550684 300 1311867180.4309151173 0.1837425977 0.1322984792 0.1882778257 0.0056944765 0.1486190000 242307124 0 1585418240 -0.5717871189 0.0725475773 -0.0382787362 301 1311867180.4670670033 0.1834301949 0.1324683520 0.1882778257 0.0056861827 0.1612730000 242308954 0 1588244480 -0.5708994865 0.0733805224 -0.0391341187 302 1311867180.4947559834 0.1836111844 0.1326376991 0.1882778257 0.0056899182 0.1513890000 242310624 0 1588346880 -0.5704654455 0.0722340792 -0.0391447395 303 1311867180.5308880806 0.1833531410 0.1328050768 0.1882778257 0.0056810703 0.1556210000 242312486 0 1588871168 -0.5691946149 0.0730221868 -0.0395152904 304 1311867180.5629510880 0.1837970763 0.1329728136 0.1882778257 0.0056719435 0.1304710000 242314252 0 1589473280 -0.5681808591 0.0731068775 -0.0388739184 305 1311867180.5946910381 0.1832302213 0.1331375920 0.1882778257 0.0056630175 0.1458590000 242316018 0 1589981184 -0.5669988394 0.0731961057 -0.0392780378 306 1311867180.6308128834 0.1831290126 0.1333009627 0.1882778257 0.0056557332 0.1371660000 242317848 0 1590489088 -0.5666291714 0.0723152235 -0.0392135903 307 1311867180.6640911102 0.1824465692 0.1334610461 0.1882778257 0.0056706075 0.1382710000 242319614 0 1590996992 -0.5654780865 0.0728969425 -0.0395087153 308 1311867180.6957600117 0.1822940856 0.1336195949 0.1882778257 0.0056616226 0.1318230000 242321348 0 1591537664 -0.5648111701 0.0723583847 -0.0394190960 309 1311867180.7309739590 0.1820357591 0.1337762815 0.1882778257 0.0056571531 0.1442590000 242323210 0 1592139776 -0.5636087060 0.0735852420 -0.0397832878 310 1311867180.7650380135 0.1825917214 0.1339337507 0.1882778257 0.0056653879 0.1362800000 242324976 0 1592647680 -0.5637978911 0.0721660256 -0.0392516293 311 1311867180.7949280739 0.1814123839 0.1340864151 0.1882778257 0.0056601034 0.1280060000 242326710 0 1593155584 -0.5615770817 0.0731874555 -0.0398674943 312 1311867180.8309240341 0.1818579286 0.1342395289 0.1882778257 0.0056512418 0.1406090000 242328572 0 1593663488 -0.5616626143 0.0729293972 -0.0395418517 313 1311867180.8652539253 0.1812077016 0.1343895870 0.1882778257 0.0056474217 0.1326920000 242330338 0 1594204160 -0.5602326393 0.0723849609 -0.0395367295 314 1311867180.8966469765 0.1816821098 0.1345402001 0.1882778257 0.0056404898 0.1460420000 242332136 0 1594806272 -0.5597156286 0.0725509822 -0.0395512879 315 1311867180.9306049347 0.1810000986 0.1346876919 0.1882778257 0.0056555534 0.1383740000 242333934 0 1595314176 -0.5588352084 0.0723085329 -0.0399278775 316 1311867180.9631829262 0.1808653474 0.1348338237 0.1882778257 0.0056539562 0.1335510000 242335700 0 1595822080 -0.5575383306 0.0735660270 -0.0403683968 317 1311867180.9948179722 0.1805875599 0.1349781572 0.1882778257 0.0056451525 0.1166750000 242337434 0 1596362752 -0.5563236475 0.0733807161 -0.0405211560 318 1311867181.0308310986 0.1802275777 0.1351204510 0.1882778257 0.0056399496 0.1498380000 242339264 0 1596964864 -0.5546541810 0.0722338483 -0.0404679775 319 1311867181.0627830029 0.1798651069 0.1352607164 0.1882778257 0.0056362019 0.1537870000 242341062 0 1597472768 -0.5522681475 0.0724124089 -0.0410548225 320 1311867181.0948719978 0.1795525998 0.1353991285 0.1882778257 0.0056327869 0.1246030000 242342828 0 1597980672 -0.5502317548 0.0734255463 -0.0412169993 321 1311867181.1311910152 0.1786625832 0.1355339056 0.1882778257 0.0056302745 0.1291820000 242344658 0 1598488576 -0.5466158390 0.0720149800 -0.0412056670 322 1311867181.1629040241 0.1791828573 0.1356694614 0.1882778257 0.0056355415 0.1302770000 242346392 0 1599123456 -0.5454740524 0.0715023279 -0.0412889719 323 1311867181.1972510815 0.1781115681 0.1358008611 0.1882778257 0.0056270476 0.1147990000 242348190 0 1599631360 -0.5434142947 0.0712528825 -0.0424809456 324 1311867181.2342460155 0.1777212471 0.1359302450 0.1882778257 0.0056198726 0.1464070000 242350084 0 1600139264 -0.5417277813 0.0701499656 -0.0432791784 325 1311867181.2629361153 0.1766884178 0.1360556548 0.1882778257 0.0056115347 0.1347840000 242351786 0 1600663552 -0.5394825339 0.0705937743 -0.0443746038 326 1311867181.2948091030 0.1765200943 0.1361797788 0.1882778257 0.0056034636 0.1291780000 242353520 0 1601282048 -0.5365843773 0.0704233050 -0.0438128412 327 1311867181.3316988945 0.1761642694 0.1363020555 0.1882778257 0.0056015811 0.1494770000 242355350 0 1601789952 -0.5357242823 0.0700840056 -0.0444742925 328 1311867181.3626708984 0.1754076332 0.1364212799 0.1882778257 0.0055977048 0.1220820000 242357116 0 1602297856 -0.5333663225 0.0716778561 -0.0450412482 329 1311867181.3948218822 0.1759218425 0.1365413424 0.1882778257 0.0055903113 0.1501420000 242358882 0 1602838528 -0.5334262252 0.0700133294 -0.0445780382 330 1311867181.4308950901 0.1748172790 0.1366573301 0.1882778257 0.0055840450 0.1508130000 242360648 0 1603440640 -0.5309453011 0.0706189871 -0.0456297435 331 1311867181.4628310204 0.1735974848 0.1367689317 0.1882778257 0.0055810149 0.1457740000 242362414 0 1603956736 -0.5276822448 0.0701794922 -0.0462075770 332 1311867181.4963400364 0.1728519499 0.1368776155 0.1882778257 0.0055896520 0.1526000000 242364180 0 1604481024 -0.5250660181 0.0699907541 -0.0463024788 333 1311867181.5359110832 0.1741763651 0.1369896238 0.1882778257 0.0055853416 0.1393350000 242366074 0 1605083136 -0.5241342187 0.0684958100 -0.0451736934 334 1311867181.5632140636 0.1724316329 0.1370957376 0.1882778257 0.0055798331 0.1513390000 242367712 0 1605591040 -0.5210880041 0.0677487627 -0.0465440005 335 1311867181.5948610306 0.1715333760 0.1371985365 0.1882778257 0.0055723025 0.1646880000 242369478 0 1606098944 -0.5200823545 0.0689327046 -0.0483542196 336 1311867181.6309840679 0.1728222817 0.1373045595 0.1882778257 0.0055670474 0.1584590000 242371308 0 1606639616 -0.5193006992 0.0679099038 -0.0474155135 337 1311867181.6628570557 0.1724520177 0.1374088547 0.1882778257 0.0055602366 0.1543040000 242373106 0 1607241728 -0.5170457959 0.0661530644 -0.0478779711 338 1311867181.6949229240 0.1708498895 0.1375077927 0.1882778257 0.0055566784 0.1577200000 242374840 0 1607749632 -0.5143483877 0.0673550591 -0.0496639982 339 1311867181.7310829163 0.1729168594 0.1376122442 0.1882778257 0.0055748566 0.1711300000 242376670 0 1608257536 -0.5128748417 0.0647994578 -0.0479003191 340 1311867181.7634770870 0.1713348329 0.1377114283 0.1882778257 0.0055700919 0.1580330000 242378436 0 1608798208 -0.5117076039 0.0649827942 -0.0503255278 341 1311867181.7948980331 0.1712504476 0.1378097832 0.1882778257 0.0055680430 0.1569390000 242380170 0 1609400320 -0.5099596977 0.0654722229 -0.0513472557 342 1311867181.8308010101 0.1719348133 0.1379095639 0.1882778257 0.0055634394 0.1606610000 242382000 0 1609908224 -0.5087663531 0.0635693595 -0.0505745336 343 1311867181.8627979755 0.1706134826 0.1380049106 0.1882778257 0.0055611462 0.1637860000 242383798 0 1610416128 -0.5062243342 0.0636118948 -0.0513175651 344 1311867181.8949289322 0.1699816138 0.1380978662 0.1882778257 0.0055577476 0.1635020000 242385532 0 1610924032 -0.5028617978 0.0632396415 -0.0513496287 345 1311867181.9307990074 0.1708662510 0.1381928470 0.1882778257 0.0055601491 0.1627830000 242387394 0 1611464704 -0.5021992922 0.0618074685 -0.0509252250 346 1311867181.9629189968 0.1692881733 0.1382827179 0.1882778257 0.0055532513 0.1847750000 242389160 0 1612066816 -0.5005636811 0.0625345483 -0.0530116223 347 1311867181.9955511093 0.1693883538 0.1383723595 0.1882778257 0.0055730582 0.1637170000 242390894 0 1612574720 -0.4984672070 0.0609952286 -0.0515732020 348 1311867182.0319390297 0.1687984616 0.1384597908 0.1882778257 0.0055658798 0.1730720000 242392724 0 1613082624 -0.4966978133 0.0604502670 -0.0519306958 349 1311867182.0629000664 0.1682012677 0.1385450100 0.1882778257 0.0055592442 0.1699520000 242394522 0 1613623296 -0.4957979321 0.0602163598 -0.0527742803 350 1311867182.0948839188 0.1679674387 0.1386290740 0.1882778257 0.0055610988 0.1622370000 242396256 0 1614225408 -0.4936456382 0.0604894273 -0.0528395213 351 1311867182.1314530373 0.1678189188 0.1387122360 0.1882778257 0.0055533438 0.1649190000 242398086 0 1614733312 -0.4912084043 0.0600523874 -0.0523444451 352 1311867182.1629920006 0.1675448865 0.1387941469 0.1882778257 0.0055468009 0.1650020000 242399884 0 1615273984 -0.4892168045 0.0599856488 -0.0521957465 353 1311867182.1994419098 0.1679976135 0.1388768763 0.1882778257 0.0055439167 0.1758640000 242401650 0 1615876096 -0.4880354702 0.0590375587 -0.0515154824 354 1311867182.2307739258 0.1673769951 0.1389573851 0.1882778257 0.0055389038 0.1741360000 242403416 0 1616375808 -0.4855665267 0.0583151579 -0.0513579845 355 1311867182.2629120350 0.1667600274 0.1390357024 0.1882778257 0.0055370814 0.1757360000 242405214 0 1616883712 -0.4846508801 0.0579905510 -0.0522540510 356 1311867182.2973039150 0.1679658890 0.1391169670 0.1882778257 0.0055321124 0.1714410000 242406980 0 1617391616 -0.4836996198 0.0568287335 -0.0509488024 357 1311867182.3308460712 0.1670749933 0.1391952808 0.1882778257 0.0055389976 0.1891680000 242408778 0 1618026496 -0.4825275540 0.0571576729 -0.0522124656 358 1311867182.3629670143 0.1665980071 0.1392718247 0.1882778257 0.0055656706 0.1903510000 242410576 0 1618542592 -0.4805043340 0.0566176139 -0.0519944094 359 1311867182.3990280628 0.1669869423 0.1393490256 0.1882778257 0.0055659337 0.1851690000 242412342 0 1619050496 -0.4794119298 0.0558158942 -0.0515301861 360 1311867182.4308118820 0.1679109484 0.1394283643 0.1882778257 0.0055619004 0.1865010000 242414140 0 1619558400 -0.4783327579 0.0547734424 -0.0507178791 361 1311867182.4629440308 0.1678184718 0.1395070072 0.1882778257 0.0055571794 0.1875930000 242415938 0 1620099072 -0.4766171873 0.0547220483 -0.0511910468 362 1311867182.4969530106 0.1693460643 0.1395894355 0.1882778257 0.0055503297 0.1743760000 242417672 0 1620701184 -0.4736101925 0.0531479046 -0.0492221452 363 1311867182.5309500694 0.1692513525 0.1396711488 0.1882778257 0.0055434816 0.1992050000 242419502 0 1621241856 -0.4730331898 0.0525026284 -0.0507641025 364 1311867182.5629699230 0.1680319607 0.1397490631 0.1882778257 0.0055469403 0.1971630000 242421268 0 1621843968 -0.4722730815 0.0519733131 -0.0538385324 365 1311867182.6036369801 0.1689291447 0.1398290086 0.1882778257 0.0055412512 0.1717990000 242423162 0 1622351872 -0.4695786238 0.0511271209 -0.0529715568 366 1311867182.6308450699 0.1683469117 0.1399069263 0.1882778257 0.0055484430 0.1986930000 242424832 0 1622859776 -0.4692114294 0.0505900756 -0.0550764576 367 1311867182.6635720730 0.1673879176 0.1399818064 0.1882778257 0.0055421276 0.2031940000 242426598 0 1623367680 -0.4673123360 0.0503360033 -0.0561795048 368 1311867182.6969909668 0.1681008190 0.1400582168 0.1882778257 0.0055379601 0.2142480000 242428364 0 1623908352 -0.4639164805 0.0492653772 -0.0554450564 369 1311867182.7330501080 0.1685255915 0.1401353641 0.1882778257 0.0055342018 0.1728450000 242430194 0 1624510464 -0.4626049697 0.0481144302 -0.0560032539 370 1311867182.7631070614 0.1677809209 0.1402100819 0.1882778257 0.0055267450 0.2007170000 242431864 0 1625018368 -0.4602501392 0.0479358584 -0.0572664589 371 1311867182.7970440388 0.1685686707 0.1402865201 0.1882778257 0.0055194178 0.1780400000 242433694 0 1625526272 -0.4584954083 0.0469633788 -0.0568117574 372 1311867182.8306899071 0.1680976748 0.1403612813 0.1882778257 0.0055121863 0.1826090000 242435460 0 1626034176 -0.4572675526 0.0466890596 -0.0583226010 373 1311867182.8640909195 0.1665329784 0.1404314467 0.1882778257 0.0055194329 0.2117070000 242437226 0 1626574848 -0.4552205205 0.0459554009 -0.0598147660 374 1311867182.8969850540 0.1660211831 0.1404998684 0.1882778257 0.0055120461 0.2169430000 242439024 0 1627082752 -0.4535909891 0.0462767370 -0.0607151426 375 1311867182.9318869114 0.1659480929 0.1405677304 0.1882778257 0.0055060784 0.1809500000 242440822 0 1627684864 -0.4516643584 0.0467399880 -0.0608415529 376 1311867182.9630560875 0.1663872600 0.1406363993 0.1882778257 0.0054992707 0.1949060000 242442588 0 1628192768 -0.4492624700 0.0465604551 -0.0596518032 377 1311867182.9983499050 0.1660634279 0.1407038450 0.1882778257 0.0055046056 0.2011760000 242444386 0 1628700672 -0.4467850924 0.0453617200 -0.0592744276 378 1311867183.0308830738 0.1656296253 0.1407697862 0.1882778257 0.0054977480 0.2067490000 242446184 0 1629241344 -0.4453196824 0.0456326976 -0.0599153936 379 1311867183.0628600121 0.1655766815 0.1408352398 0.1882778257 0.0054930474 0.2239790000 242447982 0 1629843456 -0.4429541230 0.0458529629 -0.0596378967 380 1311867183.1000399590 0.1660926044 0.1409017065 0.1882778257 0.0055133378 0.1971210000 242449748 0 1630351360 -0.4413353801 0.0445916317 -0.0583611354 381 1311867183.1344680786 0.1643864065 0.1409633462 0.1882778257 0.0055066001 0.2192870000 242451578 0 1630859264 -0.4396128654 0.0455087498 -0.0603985153 382 1311867183.1673240662 0.1645429730 0.1410250729 0.1882778257 0.0054994504 0.1968560000 242453408 0 1631367168 -0.4382899404 0.0454193950 -0.0599633381 383 1311867183.2004730701 0.1651054323 0.1410879459 0.1882778257 0.0054931763 0.1799490000 242455142 0 1631891456 -0.4363965988 0.0438784361 -0.0582847409 384 1311867183.2311279774 0.1642043144 0.1411481448 0.1882778257 0.0054864576 0.1986830000 242456908 0 1632509952 -0.4347148240 0.0444666669 -0.0593506806 385 1311867183.2633240223 0.1647120118 0.1412093497 0.1882778257 0.0054793221 0.2242910000 242458674 0 1633017856 -0.4336117804 0.0439155847 -0.0586256571 386 1311867183.2990970612 0.1656464189 0.1412726581 0.1882778257 0.0054747047 0.1778890000 242460472 0 1633525760 -0.4314838350 0.0424584337 -0.0564901903 387 1311867183.3320920467 0.1638823003 0.1413310810 0.1882778257 0.0054695936 0.2110670000 242462302 0 1634066432 -0.4300278723 0.0430494472 -0.0590009987 388 1311867183.3695240021 0.1650332361 0.1413921690 0.1882778257 0.0054626498 0.1998590000 242464164 0 1634668544 -0.4289000630 0.0425382517 -0.0579583123 389 1311867183.3985459805 0.1650686115 0.1414530339 0.1882778257 0.0054559359 0.2051800000 242465834 0 1635176448 -0.4271103144 0.0407821164 -0.0572216995 390 1311867183.4311549664 0.1637873948 0.1415103015 0.1882778257 0.0054568253 0.1856000000 242467632 0 1635684352 -0.4262142479 0.0415692516 -0.0597776361 391 1311867183.4667379856 0.1639884114 0.1415677903 0.1882778257 0.0054539012 0.1849870000 242469430 0 1636225024 -0.4238393009 0.0414357744 -0.0594039299 392 1311867183.4988279343 0.1645537913 0.1416264280 0.1882778257 0.0054722354 0.2103900000 242471228 0 1636827136 -0.4221695364 0.0396873616 -0.0578938834 393 1311867183.5321719646 0.1628931910 0.1416805419 0.1882778257 0.0054681388 0.2112190000 242472994 0 1637326848 -0.4204157293 0.0398403145 -0.0596183352 394 1311867183.5661509037 0.1630638987 0.1417348144 0.1882778257 0.0054621934 0.1858910000 242474792 0 1637834752 -0.4181944430 0.0403239168 -0.0592526123 395 1311867183.5985350609 0.1636513025 0.1417902992 0.1882778257 0.0054586522 0.2068260000 242476558 0 1638342656 -0.4163243473 0.0380704403 -0.0578778945 396 1311867183.6310880184 0.1626449078 0.1418429623 0.1882778257 0.0054704673 0.1992100000 242478356 0 1638883328 -0.4149735272 0.0391605087 -0.0596861877 397 1311867183.6648790836 0.1628260016 0.1418958163 0.1882778257 0.0054642678 0.2015350000 242480090 0 1639485440 -0.4122664332 0.0385770537 -0.0586060323 398 1311867183.6993529797 0.1627206206 0.1419481400 0.1882778257 0.0054575562 0.2074010000 242481952 0 1639993344 -0.4097891450 0.0372820646 -0.0578410588 399 1311867183.7308928967 0.1624402255 0.1419994986 0.1882778257 0.0054529422 0.2071920000 242483686 0 1640501248 -0.4080259502 0.0370434225 -0.0582136139 400 1311867183.7676239014 0.1614814699 0.1420482035 0.1882778257 0.0054603416 0.2278100000 242485516 0 1641009152 -0.4047570229 0.0365764201 -0.0581362806 401 1311867183.7971758842 0.1618811190 0.1420976622 0.1882778257 0.0054535904 0.2129500000 242487218 0 1641549824 -0.4035265148 0.0358507037 -0.0575027354 402 1311867183.8309071064 0.1613844484 0.1421456392 0.1882778257 0.0054470620 0.2331410000 242489016 0 1642151936 -0.4011714458 0.0353383496 -0.0573729835 403 1311867183.8654990196 0.1624056995 0.1421959123 0.1882778257 0.0054409279 0.2174110000 242490782 0 1642659840 -0.3995648324 0.0338216461 -0.0557062365 404 1311867183.8970859051 0.1608787775 0.1422421571 0.1882778257 0.0054371656 0.2136860000 242492516 0 1643167744 -0.3979523182 0.0336623602 -0.0573632866 405 1311867183.9314830303 0.1606434286 0.1422875923 0.1882778257 0.0054309788 0.1992510000 242494346 0 1643802624 -0.3958757818 0.0328677148 -0.0568591505 406 1311867183.9658210278 0.1608527154 0.1423333192 0.1882778257 0.0054288764 0.2167370000 242496112 0 1644310528 -0.3944193721 0.0318932682 -0.0559461787 407 1311867183.9966681004 0.1614231318 0.1423802229 0.1882778257 0.0054256382 0.2066130000 242497878 0 1644859392 -0.3935270011 0.0319665745 -0.0556696765 408 1311867184.0309689045 0.1606041938 0.1424248895 0.1882778257 0.0054405418 0.2045770000 242499708 0 1645461504 -0.3917384744 0.0314021483 -0.0563311875 409 1311867184.0647230148 0.1608968377 0.1424700532 0.1882778257 0.0054355347 0.2010810000 242501474 0 1645969408 -0.3906752765 0.0301774014 -0.0552169196 410 1311867184.0968110561 0.1600320041 0.1425128872 0.1882778257 0.0054300941 0.1849560000 242503208 0 1646477312 -0.3892914355 0.0304549392 -0.0561281890 411 1311867184.1312260628 0.1604603976 0.1425565551 0.1882778257 0.0054239193 0.2053840000 242505038 0 1646985216 -0.3873804808 0.0303012002 -0.0549897924 412 1311867184.1650540829 0.1605568975 0.1426002453 0.1882778257 0.0054175922 0.1926130000 242506772 0 1647525888 -0.3859554827 0.0289702881 -0.0542476587 413 1311867184.1969459057 0.1600064486 0.1426423911 0.1882778257 0.0054120194 0.1993440000 242508570 0 1648128000 -0.3842068613 0.0307115018 -0.0554159991 414 1311867184.2309360504 0.1597620696 0.1426837429 0.1882778257 0.0054060378 0.2189840000 242510400 0 1648635904 -0.3820803761 0.0295938812 -0.0548798814 415 1311867184.2681019306 0.1607390046 0.1427272496 0.1882778257 0.0054009677 0.1982130000 242512230 0 1649143808 -0.3805334568 0.0279584844 -0.0534329452 416 1311867184.2983698845 0.1598127931 0.1427683206 0.1882778257 0.0053994844 0.1935330000 242513964 0 1649684480 -0.3781636953 0.0297691878 -0.0545157678 417 1311867184.3314700127 0.1590070128 0.1428072623 0.1882778257 0.0053949792 0.2135910000 242515762 0 1650286592 -0.3756933212 0.0291959830 -0.0546522662 418 1311867184.3697628975 0.1599149704 0.1428481898 0.1882778257 0.0053957366 0.2139030000 242517592 0 1650794496 -0.3747405708 0.0273983795 -0.0538826063 419 1311867184.4000060558 0.1590944380 0.1428869637 0.1882778257 0.0054235481 0.2102020000 242519326 0 1651302400 -0.3724909723 0.0294465348 -0.0559789650 420 1311867184.4310610294 0.1600676328 0.1429278701 0.1882778257 0.0054185245 0.2094990000 242521124 0 1651843072 -0.3701548874 0.0302270446 -0.0546974763 421 1311867184.4655740261 0.1607780755 0.1429702696 0.1882778257 0.0054149639 0.2187390000 242522890 0 1652445184 -0.3681258559 0.0268464666 -0.0530110002 422 1311867184.5037670135 0.1600269675 0.1430106883 0.1882778257 0.0054665900 0.2226110000 242524784 0 1652969472 -0.3642381430 0.0262541194 -0.0536087900 423 1311867184.5310881138 0.1588894129 0.1430482267 0.1882778257 0.0054882345 0.2154780000 242526486 0 1653587968 -0.3613285124 0.0274159536 -0.0559603311 424 1311867184.5682799816 0.1601757407 0.1430886218 0.1882778257 0.0054844302 0.4639980000 254831616 0 1666412544 -0.3596439362 0.0254552104 -0.0549939983 425 1311867184.5979928970 0.1508114785 0.1431067932 0.1882778257 0.0055781496 0.2295640000 258492006 0 1670238208 -0.3513058126 0.0208386444 -0.0608677641 426 1311867184.6355450153 0.1504362226 0.1431239984 0.1882778257 0.0055763729 0.1575420000 261685964 0 1674031104 -0.3485653996 0.0219682269 -0.0618510097 427 1311867184.6662440300 0.1504491419 0.1431411533 0.1882778257 0.0055869209 0.1544030000 261687730 0 1674809344 -0.3459555805 0.0192280542 -0.0605717823 428 1311867184.6994769573 0.1494137943 0.1431558090 0.1882778257 0.0055818749 0.1536080000 261689528 0 1675419648 -0.3424206078 0.0183195472 -0.0606195033 429 1311867184.7359089851 0.1497968435 0.1431712893 0.1882778257 0.0055793896 0.1488910000 261691294 0 1675927552 -0.3407165408 0.0184387937 -0.0609988943 430 1311867184.7690219879 0.1494862437 0.1431859752 0.1882778257 0.0055762602 0.1571100000 261693124 0 1676476416 -0.3377597034 0.0157174114 -0.0597578958 431 1311867184.7995340824 0.1484272927 0.1431981361 0.1882778257 0.0055773371 0.1423210000 261694858 0 1677078528 -0.3341355920 0.0164387394 -0.0600895137 432 1311867184.8348250389 0.1483135372 0.1432099773 0.1882778257 0.0055718521 0.1484280000 261696624 0 1677586432 -0.3315777779 0.0158620887 -0.0597512685 433 1311867184.8685739040 0.1480102688 0.1432210634 0.1882778257 0.0055667335 0.1443210000 261698422 0 1678094336 -0.3289072514 0.0135515407 -0.0584484227 434 1311867184.9055209160 0.1477131844 0.1432314139 0.1882778257 0.0055617078 0.1766450000 261700220 0 1678635008 -0.3261958659 0.0140277641 -0.0584236048 435 1311867184.9332180023 0.1469738632 0.1432400172 0.1882778257 0.0055611403 0.1511170000 261701858 0 1679237120 -0.3230683506 0.0139522254 -0.0580002703 436 1311867184.9656269550 0.1461214721 0.1432466261 0.1882778257 0.0055657821 0.1549250000 261703624 0 1679745024 -0.3195218146 0.0108906301 -0.0559060536 437 1311867184.9983150959 0.1458866596 0.1432526673 0.1882778257 0.0055648738 0.1768940000 261705422 0 1680252928 -0.3172323108 0.0110238418 -0.0556883253 438 1311867185.0360450745 0.1451999843 0.1432571133 0.1882778257 0.0055587732 0.1692460000 261707252 0 1680793600 -0.3128565252 0.0104871774 -0.0543203428 439 1311867185.0652229786 0.1441644877 0.1432591802 0.1882778257 0.0055555986 0.1671120000 261708986 0 1681395712 -0.3092452288 0.0078527797 -0.0529003218 440 1311867185.0991089344 0.1442123652 0.1432613465 0.1882778257 0.0055514858 0.1679660000 261710784 0 1681903616 -0.3073776364 0.0089063663 -0.0527182035 441 1311867185.1360650063 0.1435292363 0.1432619540 0.1882778257 0.0055462154 0.1724380000 261712614 0 1682411520 -0.3036745489 0.0084483474 -0.0514560826 442 1311867185.1648139954 0.1426183581 0.1432604979 0.1882778257 0.0055445355 0.1730280000 261714348 0 1682919424 -0.3000176549 0.0065217484 -0.0498497635 443 1311867185.2000079155 0.1418074071 0.1432572178 0.1882778257 0.0055389892 0.1750900000 261716114 0 1683460096 -0.2961332798 0.0072848462 -0.0496630780 444 1311867185.2342638969 0.1416196376 0.1432535295 0.1882778257 0.0055369131 0.1779670000 261717944 0 1684062208 -0.2929998636 0.0062119681 -0.0483133607 445 1311867185.2663319111 0.1413798332 0.1432493190 0.1882778257 0.0055313493 0.1785000000 261719710 0 1684570112 -0.2900915146 0.0032095385 -0.0463578813 446 1311867185.2970130444 0.1399729997 0.1432419730 0.1882778257 0.0055596472 0.2008030000 261721476 0 1685078016 -0.2862156332 0.0044078398 -0.0463909917 447 1311867185.3359839916 0.1398935914 0.1432344822 0.1882778257 0.0055536553 0.1771380000 261723338 0 1685585920 -0.2834891379 0.0036141712 -0.0452686809 448 1311867185.3681640625 0.1395204067 0.1432261918 0.1882778257 0.0055482092 0.1766200000 261725136 0 1686126592 -0.2802692354 0.0015724951 -0.0437049940 449 1311867185.4036369324 0.1390230805 0.1432168308 0.1882778257 0.0055431754 0.1830930000 261726934 0 1686728704 -0.2775495946 0.0019054918 -0.0437430628 450 1311867185.4373219013 0.1388924420 0.1432072210 0.1882778257 0.0055373662 0.1861110000 261728732 0 1687236608 -0.2750483751 0.0028442899 -0.0435680449 451 1311867185.4654970169 0.1390440017 0.1431979899 0.1882778257 0.0055322633 0.1652790000 261730402 0 1687744512 -0.2716743052 -0.0001203392 -0.0409367569 452 1311867185.5006229877 0.1381391287 0.1431867978 0.1882778257 0.0055456575 0.1809370000 261732200 0 1688252416 -0.2688627839 -0.0007020163 -0.0414503627 453 1311867185.5336239338 0.1378882527 0.1431751012 0.1882778257 0.0055534753 0.1814590000 261733998 0 1688793088 -0.2662932575 0.0002450569 -0.0418564267 454 1311867185.5666689873 0.1378182620 0.1431633020 0.1882778257 0.0055483464 0.1755480000 261735796 0 1689395200 -0.2627477050 -0.0025959562 -0.0400170684 455 1311867185.5969750881 0.1371703446 0.1431501307 0.1882778257 0.0055459277 0.1666090000 261737530 0 1689903104 -0.2596997023 -0.0034077498 -0.0398961268 456 1311867185.6329400539 0.1372070163 0.1431370975 0.1882778257 0.0055539262 0.1884220000 261739360 0 1690411008 -0.2567779422 -0.0028345974 -0.0404187106 457 1311867185.6664080620 0.1367824972 0.1431231925 0.1882778257 0.0055585808 0.1804280000 261741126 0 1691045888 -0.2530222833 -0.0047348444 -0.0392286293 458 1311867185.6973319054 0.1362219900 0.1431081243 0.1882778257 0.0055527990 0.1906360000 261742892 0 1691553792 -0.2502447665 -0.0057357252 -0.0389150269 459 1311867185.7351789474 0.1372582018 0.1430953794 0.1882778257 0.0055502804 0.1838110000 261744722 0 1692102656 -0.2496347427 -0.0042572990 -0.0394025557 460 1311867185.7649710178 0.1360303015 0.1430800206 0.1882778257 0.0055495738 0.1810590000 261746488 0 1692704768 -0.2444473207 -0.0079134740 -0.0367514826 461 1311867185.7989521027 0.1371075660 0.1430670651 0.1882778257 0.0055656787 0.1698890000 261748254 0 1693212672 -0.2428869009 -0.0074456506 -0.0364077613 462 1311867185.8327920437 0.1362807602 0.1430523761 0.1882778257 0.0055602277 0.1842350000 261750084 0 1693720576 -0.2400459349 -0.0080535151 -0.0364325270 463 1311867185.8649039268 0.1353797466 0.1430358046 0.1882778257 0.0055573220 0.1824170000 261751850 0 1694244864 -0.2363791764 -0.0104233567 -0.0349425785 464 1311867185.8951730728 0.1360623240 0.1430207755 0.1882778257 0.0055520333 0.1736410000 261753552 0 1694769152 -0.2355186492 -0.0104330517 -0.0344398320 465 1311867185.9359779358 0.1363272965 0.1430063810 0.1882778257 0.0055469958 0.1803200000 261755446 0 1695371264 -0.2341650277 -0.0097394241 -0.0342544802 466 1311867185.9650509357 0.1339983195 0.1429870504 0.1882778257 0.0055688362 0.1911470000 261757148 0 1695879168 -0.2286728024 -0.0135667762 -0.0319410823 467 1311867185.9952309132 0.1340532303 0.1429679201 0.1882778257 0.0055660418 0.1883400000 261758914 0 1696387072 -0.2272621691 -0.0135089755 -0.0319292285 468 1311867186.0359640121 0.1346301287 0.1429501043 0.1882778257 0.0055632095 0.2042610000 261760808 0 1696927744 -0.2270537019 -0.0127166891 -0.0321328230 469 1311867186.0653049946 0.1333329827 0.1429295987 0.1882778257 0.0055684935 0.1947630000 261762574 0 1697529856 -0.2240360528 -0.0160516128 -0.0301887840 470 1311867186.0952839851 0.1333819926 0.1429092847 0.1882778257 0.0055635635 0.1769630000 261764244 0 1698037760 -0.2233475596 -0.0167096835 -0.0298399888 471 1311867186.1361019611 0.1330510974 0.1428883543 0.1882778257 0.0055606470 0.1823980000 261766170 0 1698537472 -0.2213399559 -0.0171286203 -0.0297767352 472 1311867186.1649360657 0.1325143874 0.1428663756 0.1882778257 0.0055576887 0.1991990000 261767904 0 1699061760 -0.2191219479 -0.0192165505 -0.0287833568 473 1311867186.1951880455 0.1324946880 0.1428444481 0.1882778257 0.0055518797 0.1830910000 261769606 0 1699586048 -0.2178238034 -0.0194888636 -0.0287759360 474 1311867186.2358930111 0.1323762983 0.1428223634 0.1882778257 0.0055476368 0.1657760000 261771532 0 1700188160 -0.2159510404 -0.0191820841 -0.0288274139 475 1311867186.2674899101 0.1320706904 0.1427997283 0.1882778257 0.0055435658 0.1904180000 261773330 0 1700823040 -0.2131429911 -0.0215207022 -0.0275415853 476 1311867186.2951989174 0.1315256208 0.1427760432 0.1882778257 0.0055381339 0.1910070000 261774968 0 1701330944 -0.2112896293 -0.0213262457 -0.0277699102 477 1311867186.3349149227 0.1311337650 0.1427516359 0.1882778257 0.0055368985 0.1962730000 261776862 0 1701838848 -0.2086441368 -0.0216167811 -0.0272875279 478 1311867186.3669641018 0.1308523566 0.1427267421 0.1882778257 0.0055402553 0.1935910000 261778596 0 1702346752 -0.2060361952 -0.0253178813 -0.0251461156 479 1311867186.3951311111 0.1310686618 0.1427024037 0.1882778257 0.0055406074 0.1797660000 261780266 0 1702887424 -0.2058670819 -0.0242388900 -0.0258399807 480 1311867186.4360098839 0.1310400665 0.1426781072 0.1882778257 0.0055409246 0.1971410000 261782192 0 1703395328 -0.2036015242 -0.0233634710 -0.0253172796 481 1311867186.4659481049 0.1302716434 0.1426523141 0.1882778257 0.0055416030 0.1963100000 261783958 0 1703997440 -0.2004489005 -0.0273244642 -0.0226962455 482 1311867186.4952139854 0.1300463527 0.1426261606 0.1882778257 0.0055359852 0.1951200000 261785628 0 1704505344 -0.1993846446 -0.0273477584 -0.0228692777 483 1311867186.5362739563 0.1299480349 0.1425999119 0.1882778257 0.0055439291 0.1891170000 261787554 0 1705013248 -0.1973079890 -0.0265227687 -0.0227702390 484 1311867186.5651071072 0.1290932298 0.1425720056 0.1882778257 0.0055637401 0.1945210000 261789288 0 1705545728 -0.1945356876 -0.0292519983 -0.0210600533 485 1311867186.5951600075 0.1295136958 0.1425450812 0.1882778257 0.0055581920 0.1897500000 261790990 0 1706070016 -0.1935504228 -0.0298792385 -0.0208757203 486 1311867186.6362359524 0.1295764744 0.1425183968 0.1882778257 0.0055525394 0.1788190000 261792916 0 1706672128 -0.1916182041 -0.0297311246 -0.0213362779 487 1311867186.6650140285 0.1295851916 0.1424918399 0.1882778257 0.0055489243 0.1846400000 261794618 0 1707180032 -0.1903364062 -0.0287311319 -0.0222180113 488 1311867186.7043650150 0.1296909153 0.1424656085 0.1882778257 0.0055656827 0.1994290000 261796544 0 1707687936 -0.1883062273 -0.0301947407 -0.0215186737 489 1311867186.7337520123 0.1293276548 0.1424387416 0.1882778257 0.0055710767 0.2052730000 261798246 0 1708228608 -0.1870104223 -0.0270612165 -0.0236038696 490 1311867186.7672879696 0.1306244582 0.1424146308 0.1882778257 0.0055666540 0.1643990000 261800044 0 1708736512 -0.1867303252 -0.0268087015 -0.0230423044 491 1311867186.8047199249 0.1313794106 0.1423921558 0.1882778257 0.0055624028 0.1744140000 261801906 0 1709330432 -0.1851792336 -0.0280082114 -0.0220055357 492 1311867186.8340680599 0.1312371641 0.1423694830 0.1882778257 0.0055604282 0.1837580000 261803608 0 1709838336 -0.1843627840 -0.0252752341 -0.0241599511 493 1311867186.8691000938 0.1297390759 0.1423438636 0.1882778257 0.0055597316 0.6002990000 274113242 0 1722695680 -0.1809034050 -0.0257383157 -0.0248378757 494 1311867186.9051868916 0.1229921132 0.1423046900 0.1882778257 0.0055889552 0.1149950000 277772920 0 1726631936 -0.1752678752 -0.0309237074 -0.0291886181 495 1311867186.9334180355 0.1228222698 0.1422653315 0.1882778257 0.0055839143 0.2014750000 280966782 0 1730408448 -0.1729407161 -0.0303559098 -0.0294262078 496 1311867186.9656929970 0.1225337237 0.1422255501 0.1882778257 0.0055831869 0.1777970000 280968484 0 1731203072 -0.1696673781 -0.0270521026 -0.0302858520 497 1311867187.0017049313 0.1227981895 0.1421864608 0.1882778257 0.0055881976 0.1452120000 280970250 0 1731837952 -0.1667572558 -0.0297369156 -0.0289025363 498 1311867187.0336399078 0.1232729107 0.1421484818 0.1882778257 0.0055940439 0.1590730000 280972016 0 1732440064 -0.1651134044 -0.0276518669 -0.0303460639 499 1311867187.0632801056 0.1227976680 0.1421097026 0.1882778257 0.0055886085 0.1557180000 280973750 0 1732947968 -0.1620049477 -0.0252247117 -0.0310778059 500 1311867187.1015949249 0.1230241060 0.1420715314 0.1882778257 0.0055859493 0.1522540000 280975644 0 1733455872 -0.1590098739 -0.0269050170 -0.0300839413 501 1311867187.1339790821 0.1236574128 0.1420347767 0.1882778257 0.0055861223 0.1276430000 280977410 0 1733963776 -0.1567170620 -0.0302313138 -0.0289982390 502 1311867187.1632618904 0.1232836619 0.1419974239 0.1882778257 0.0055869237 0.1496320000 280979144 0 1734471680 -0.1546204090 -0.0260506440 -0.0313680619 503 1311867187.2041230202 0.1243510097 0.1419623415 0.1882778257 0.0055889569 0.1481330000 280981038 0 1735012352 -0.1521012783 -0.0266829692 -0.0313831680 504 1311867187.2331590652 0.1243523881 0.1419274012 0.1882778257 0.0055877652 0.1661260000 280982772 0 1735614464 -0.1500988752 -0.0287112370 -0.0309494920 505 1311867187.2633500099 0.1248014495 0.1418934884 0.1882778257 0.0055875516 0.1563800000 280984506 0 1736122368 -0.1495075077 -0.0252831876 -0.0328385122 506 1311867187.3014860153 0.1245850772 0.1418592820 0.1882778257 0.0055898937 0.1477530000 280986336 0 1736630272 -0.1474789232 -0.0271114763 -0.0320622586 507 1311867187.3336489201 0.1248247474 0.1418256834 0.1882778257 0.0055846620 0.1670050000 280988102 0 1737154560 -0.1465219259 -0.0274059623 -0.0323230587 508 1311867187.3631711006 0.1245171577 0.1417916115 0.1882778257 0.0055793384 0.1331660000 280989868 0 1737678848 -0.1453055143 -0.0271262620 -0.0329819918 509 1311867187.4033451080 0.1256300062 0.1417598598 0.1882778257 0.0055757544 0.1526670000 280991762 0 1738280960 -0.1451354623 -0.0272674263 -0.0331972465 510 1311867187.4335799217 0.1253997386 0.1417277811 0.1882778257 0.0055745086 0.1415910000 280993496 0 1738788864 -0.1433019042 -0.0275364611 -0.0335988700 511 1311867187.4631900787 0.1244087294 0.1416938886 0.1882778257 0.0055691361 0.1658400000 280995230 0 1739296768 -0.1398896277 -0.0264733881 -0.0346760973 512 1311867187.5056259632 0.1255657375 0.1416623883 0.1882778257 0.0055658271 0.1389740000 280997124 0 1739804672 -0.1370774060 -0.0286523905 -0.0342471302 513 1311867187.5341889858 0.1259723604 0.1416318035 0.1882778257 0.0055638181 0.1662740000 281041866 0 1740345344 -0.1348019689 -0.0284284651 -0.0353835598 514 1311867187.5632169247 0.1258604079 0.1416011198 0.1882778257 0.0055585404 0.1720560000 281127568 0 1741074432 -0.1313451082 -0.0286048427 -0.0359718986 515 1311867187.6045610905 0.1269133091 0.1415725998 0.1882778257 0.0055890949 0.1552080000 281129494 0 1741582336 -0.1295101047 -0.0293608159 -0.0369137302 516 1311867187.6353919506 0.1267214566 0.1415438185 0.1882778257 0.0055851321 0.1575190000 281131260 0 1742123008 -0.1256188154 -0.0300486889 -0.0371135250 517 1311867187.6632699966 0.1264413595 0.1415146068 0.1882778257 0.0055878112 0.1606740000 281132930 0 1742725120 -0.1234130412 -0.0270749945 -0.0395882651 518 1311867187.7035639286 0.1283035129 0.1414891028 0.1882778257 0.0055910976 0.1551030000 281134824 0 1743233024 -0.1222029850 -0.0285053644 -0.0394771248 519 1311867187.7345390320 0.1280526966 0.1414632137 0.1882778257 0.0056019686 0.1780620000 281136430 0 1743757312 -0.1189539805 -0.0319565311 -0.0381728783 520 1311867187.7631900311 0.1276048571 0.1414365631 0.1882778257 0.0056066962 0.1677110000 281138164 0 1744281600 -0.1178094596 -0.0262456890 -0.0420804881 521 1311867187.8017048836 0.1283626258 0.1414114691 0.1882778257 0.0056041459 0.1540930000 281140026 0 1744883712 -0.1154509708 -0.0279612783 -0.0413002819 522 1311867187.8339490891 0.1283809990 0.1413865065 0.1882778257 0.0055997618 0.1602890000 281141792 0 1745391616 -0.1132206395 -0.0275421161 -0.0419379734 523 1311867187.8634109497 0.1294167042 0.1413636197 0.1882778257 0.0055967824 0.1779940000 281143526 0 1745899520 -0.1122577637 -0.0261807498 -0.0429731123 524 1311867187.9038710594 0.1289429516 0.1413399162 0.1882778257 0.0055954775 0.1663690000 281145452 0 1746407424 -0.1094983816 -0.0247521717 -0.0438430682 525 1311867187.9332211018 0.1291875243 0.1413167688 0.1882778257 0.0055910935 0.1598590000 281147154 0 1746948096 -0.1068565249 -0.0257295836 -0.0435699522 526 1311867187.9635341167 0.1289543211 0.1412932660 0.1882778257 0.0056025019 0.1641150000 281148920 0 1747550208 -0.1034208685 -0.0274019092 -0.0432316102 527 1311867188.0047419071 0.1294233054 0.1412707424 0.1882778257 0.0056058408 0.1798500000 281150814 0 1748058112 -0.0997783691 -0.0245998595 -0.0453056172 528 1311867188.0333039761 0.1299303174 0.1412492643 0.1882778257 0.0056090599 0.1652560000 281152516 0 1748566016 -0.0973291099 -0.0255460776 -0.0455620363 529 1311867188.0634179115 0.1302060634 0.1412283887 0.1882778257 0.0056040915 0.1978540000 281154250 0 1749073920 -0.0940162018 -0.0284014400 -0.0448045209 530 1311867188.1088800430 0.1311867535 0.1412094422 0.1882778257 0.0056028721 0.1525560000 281156272 0 1749614592 -0.0913056210 -0.0273233596 -0.0468098707 531 1311867188.1359899044 0.1295438260 0.1411874730 0.1882778257 0.0056100977 0.1822600000 281157910 0 1750216704 -0.0881013572 -0.0262180660 -0.0482290126 532 1311867188.1633601189 0.1315317601 0.1411693232 0.1882778257 0.0056194009 0.1764880000 281159612 0 1750724608 -0.0854175761 -0.0290224161 -0.0474305972 533 1311867188.2026538849 0.1325816363 0.1411532112 0.1882778257 0.0056166245 0.1685190000 281161506 0 1751232512 -0.0842635855 -0.0288064703 -0.0492485128 534 1311867188.2352008820 0.1321606785 0.1411363713 0.1882778257 0.0056230866 0.1691340000 281163240 0 1751740416 -0.0813937634 -0.0278924014 -0.0507050231 535 1311867188.2632720470 0.1322957575 0.1411198468 0.1882778257 0.0056205778 0.1688180000 281164974 0 1752256512 -0.0779706165 -0.0291136373 -0.0510867238 536 1311867188.3047189713 0.1333452761 0.1411053420 0.1882778257 0.0056166512 0.1817750000 281166900 0 1752875008 -0.0745036080 -0.0289212409 -0.0518018231 537 1311867188.3314530849 0.1329989731 0.1410902463 0.1882778257 0.0056123398 0.1727500000 281168570 0 1753415680 -0.0725558177 -0.0273206104 -0.0538225658 538 1311867188.3633821011 0.1333677173 0.1410758922 0.1882778257 0.0056121265 0.1963850000 281170336 0 1754017792 -0.0700982437 -0.0255821422 -0.0549740307 539 1311867188.4020431042 0.1338226944 0.1410624354 0.1882778257 0.0056111477 0.1734810000 281172198 0 1754533888 -0.0669921562 -0.0262519568 -0.0546218008 540 1311867188.4313850403 0.1332862377 0.1410480350 0.1882778257 0.0056066698 0.1789970000 281173932 0 1755041792 -0.0626727641 -0.0263841674 -0.0540728979 541 1311867188.4632470608 0.1337431669 0.1410345325 0.1882778257 0.0056062870 0.1724840000 281175698 0 1755566080 -0.0615560375 -0.0221053511 -0.0571858734 542 1311867188.5049009323 0.1349001378 0.1410232144 0.1882778257 0.0056089640 0.1782150000 281177592 0 1756090368 -0.0587841272 -0.0232848693 -0.0560383312 543 1311867188.5314350128 0.1336734593 0.1410096790 0.1882778257 0.0056096773 0.1894200000 281179294 0 1756692480 -0.0543043204 -0.0241695531 -0.0556012690 544 1311867188.5633320808 0.1332179308 0.1409953559 0.1882778257 0.0056275971 0.1770220000 281181060 0 1757233152 -0.0517002419 -0.0191590562 -0.0583840087 545 1311867188.6045799255 0.1347836852 0.1409839583 0.1882778257 0.0056234915 0.1886760000 281182954 0 1757835264 -0.0493266359 -0.0208561532 -0.0562673062 546 1311867188.6315000057 0.1346054077 0.1409722760 0.1882778257 0.0056202630 0.1761290000 281184624 0 1758343168 -0.0470037423 -0.0221443716 -0.0562111437 547 1311867188.6633369923 0.1348694414 0.1409611191 0.1882778257 0.0056243236 0.1763240000 281186390 0 1758851072 -0.0452066027 -0.0202411022 -0.0577626787 548 1311867188.7038140297 0.1349395663 0.1409501309 0.1882778257 0.0056316798 0.1643940000 281188284 0 1759391744 -0.0409759991 -0.0225160904 -0.0571311824 549 1311867188.7315850258 0.1356485784 0.1409404741 0.1882778257 0.0056294545 0.1797430000 281189986 0 1759993856 -0.0384979844 -0.0234428477 -0.0565361492 550 1311867188.7632939816 0.1352449805 0.1409301187 0.1882778257 0.0056288108 0.1666680000 281191752 0 1760501760 -0.0353546776 -0.0214021914 -0.0593750030 551 1311867188.8045160770 0.1360980421 0.1409213490 0.1882778257 0.0056287318 0.1712440000 281193678 0 1761009664 -0.0315016434 -0.0207234547 -0.0603200346 552 1311867188.8313500881 0.1368728727 0.1409140148 0.1882778257 0.0056241493 0.6808830000 293510216 0 1773867008 -0.0293849278 -0.0232327655 -0.0602789074 553 1311867188.8635439873 0.1378619373 0.1409084957 0.1882778257 0.0056336085 0.2123970000 297169830 0 1777770496 -0.0279283822 -0.0203581266 -0.0638552681 554 1311867188.9016199112 0.1390694529 0.1409051761 0.1882778257 0.0056335327 0.1657540000 300363788 0 1781485568 -0.0253678225 -0.0189692508 -0.0654331222 555 1311867188.9314649105 0.1399066597 0.1409033770 0.1882778257 0.0056295921 0.1506990000 300365522 0 1782341632 -0.0229723342 -0.0227863509 -0.0650562495 556 1311867188.9634439945 0.1404723525 0.1409026018 0.1882778257 0.0056298006 0.1457060000 300367320 0 1782865920 -0.0204405542 -0.0211267006 -0.0671010613 557 1311867189.0052158833 0.1411877871 0.1409031138 0.1882778257 0.0056265289 0.1529600000 300369214 0 1783390208 -0.0163939800 -0.0196107775 -0.0676398426 558 1311867189.0314381123 0.1400506198 0.1409015860 0.1882778257 0.0056233301 0.1532530000 300370884 0 1783992320 -0.0109554892 -0.0205522794 -0.0670347363 559 1311867189.0635390282 0.1409299374 0.1409016367 0.1882778257 0.0056194191 0.1467240000 300372682 0 1784500224 -0.0097677363 -0.0211308636 -0.0678318292 560 1311867189.1026289463 0.1412401050 0.1409022411 0.1882778257 0.0056166910 0.1431570000 300374544 0 1785008128 -0.0071888976 -0.0194736421 -0.0680965483 561 1311867189.1313118935 0.1411542445 0.1409026903 0.1882778257 0.0056118587 0.1495720000 300376246 0 1785643008 -0.0045100446 -0.0200489871 -0.0671835691 562 1311867189.1634199619 0.1415820718 0.1409038992 0.1882778257 0.0056090088 0.1377400000 300378044 0 1783918592 -0.0038544408 -0.0209128074 -0.0669622868 563 1311867189.2018899918 0.1412166655 0.1409044547 0.1882778257 0.0056050017 0.1371840000 300379906 0 1783410688 -0.0006652671 -0.0201839935 -0.0659183711 564 1311867189.2312850952 0.1415720582 0.1409056384 0.1882778257 0.0056001346 0.1354120000 300381608 0 1782628352 0.0002967331 -0.0212427061 -0.0653129518 565 1311867189.2633450031 0.1423567981 0.1409082069 0.1882778257 0.0055961834 0.1515050000 300383374 0 1783263232 0.0008237948 -0.0221788529 -0.0649094805 566 1311867189.3046789169 0.1424392462 0.1409109119 0.1882778257 0.0055922434 0.1532130000 300385332 0 1783771136 0.0037782248 -0.0226357467 -0.0638296157 567 1311867189.3314049244 0.1425080001 0.1409137286 0.1882778257 0.0055877023 0.1437180000 300386970 0 1784406016 0.0054793875 -0.0246298872 -0.0627090931 568 1311867189.3633348942 0.1424542218 0.1409164407 0.1882778257 0.0055830732 0.1330750000 300388736 0 1785008128 0.0083086602 -0.0239335913 -0.0623391084 569 1311867189.4056839943 0.1429839730 0.1409200744 0.1882778257 0.0055791429 0.1369290000 300390662 0 1785516032 0.0110623175 -0.0228002537 -0.0620477796 570 1311867189.4314579964 0.1429345757 0.1409236086 0.1882778257 0.0055780681 0.1366000000 300392332 0 1782902784 0.0151029630 -0.0257640742 -0.0591616035 571 1311867189.4634540081 0.1427036077 0.1409267259 0.1882778257 0.0055754127 0.1319870000 300394098 0 1783119872 0.0179816764 -0.0269407537 -0.0598105006 572 1311867189.5059370995 0.1438127011 0.1409317713 0.1882778257 0.0055712793 0.1464840000 300396024 0 1782628352 0.0205089524 -0.0274565071 -0.0603469275 573 1311867189.5314168930 0.1442654580 0.1409375893 0.1882778257 0.0055684716 0.1447700000 300397694 0 1783263232 0.0240907446 -0.0294948351 -0.0584008545 574 1311867189.5633189678 0.1448177844 0.1409443492 0.1882778257 0.0055652486 0.1553610000 300399460 0 1783771136 0.0274444707 -0.0324030146 -0.0580908656 575 1311867189.5993690491 0.1446561962 0.1409508046 0.1882778257 0.0055612722 0.1516610000 300401322 0 1784406016 0.0310032628 -0.0309779439 -0.0601346307 576 1311867189.6313779354 0.1453656703 0.1409584693 0.1882778257 0.0055582071 0.1459590000 300403056 0 1785008128 0.0350138396 -0.0312086940 -0.0595080443 577 1311867189.6634690762 0.1454073191 0.1409661796 0.1882778257 0.0055635360 0.1566440000 300404822 0 1785516032 0.0392225944 -0.0334227644 -0.0587400422 578 1311867189.6997840405 0.1464780569 0.1409757157 0.1882778257 0.0055718421 0.1330220000 300406620 0 1783627776 0.0418560393 -0.0329856016 -0.0598486960 579 1311867189.7314579487 0.1466061622 0.1409854401 0.1882778257 0.0055682831 0.1474010000 300408386 0 1783402496 0.0453533158 -0.0308744963 -0.0612482652 580 1311867189.7633609772 0.1462038606 0.1409944374 0.1882778257 0.0055673170 0.1489580000 300410184 0 1782603776 0.0494884178 -0.0320571773 -0.0606586188 581 1311867189.7994859219 0.1473903656 0.1410054459 0.1882778257 0.0055679089 0.1458180000 300411982 0 1783238656 0.0523817800 -0.0332359411 -0.0581412800 582 1311867189.8313660622 0.1473564953 0.1410163584 0.1882778257 0.0055646991 0.1534490000 300413748 0 1783746560 0.0538083464 -0.0338759683 -0.0602583103 583 1311867189.8634099960 0.1483351439 0.1410289120 0.1882778257 0.0055606677 0.1493630000 300415546 0 1784397824 0.0588809513 -0.0331221186 -0.0566943735 584 1311867189.8995211124 0.1495964378 0.1410435824 0.1882778257 0.0055563443 0.1736870000 300417376 0 1784999936 0.0604311973 -0.0343718752 -0.0559615605 585 1311867189.9313640594 0.1495044082 0.1410580454 0.1882778257 0.0055536518 0.1575130000 300419110 0 1785507840 0.0627084076 -0.0345547386 -0.0572330542 586 1311867189.9633400440 0.1499047279 0.1410731421 0.1882778257 0.0055492704 0.1926480000 300420908 0 1783906304 0.0659909099 -0.0349691249 -0.0565374158 587 1311867189.9994339943 0.1504104137 0.1410890489 0.1882778257 0.0055447597 0.1572360000 300422706 0 1783402496 0.0701280609 -0.0348387584 -0.0550195798 588 1311867190.0315160751 0.1500131339 0.1411042259 0.1882778257 0.0055403225 0.1603570000 300424472 0 1782599680 0.0729480013 -0.0356013812 -0.0564437024 589 1311867190.0634539127 0.1527440399 0.1411239879 0.1882778257 0.0055402148 0.1746480000 300426238 0 1783234560 0.0758961812 -0.0350465998 -0.0532329492 590 1311867190.0995900631 0.1533619314 0.1411447302 0.1882778257 0.0055358507 0.1798260000 300428036 0 1783906304 0.0789694786 -0.0368959457 -0.0523696430 591 1311867190.1314220428 0.1522662342 0.1411635483 0.1882778257 0.0055318609 0.1523210000 300429834 0 1784619008 0.0828220472 -0.0369233340 -0.0540148914 592 1311867190.1635251045 0.1542956680 0.1411857309 0.1882778257 0.0055317874 0.1649770000 300431632 0 1785126912 0.0844322294 -0.0380970277 -0.0522003695 593 1311867190.1994919777 0.1546643227 0.1412084604 0.1882778257 0.0055282182 0.5925600000 312738898 0 1783492608 0.0862806886 -0.0407450758 -0.0526374280 594 1311867190.2313890457 0.1678461134 0.1412533050 0.1882778257 0.0057527082 0.1944800000 316398448 0 1785569280 0.0680259317 -0.0316227041 -0.0645586103 595 1311867190.2633810043 0.1683485359 0.1412988432 0.1882778257 0.0057478909 0.1356400000 319592342 0 1783144448 0.0704638883 -0.0329668410 -0.0640131608 596 1311867190.2993760109 0.1693501025 0.1413459090 0.1882778257 0.0057438190 0.1328160000 319594140 0 1783898112 0.0723409131 -0.0331644043 -0.0641708374 597 1311867190.3313589096 0.1702087671 0.1413942555 0.1882778257 0.0057403392 0.1228890000 319595906 0 1784516608 0.0744101852 -0.0326114073 -0.0641815215 598 1311867190.3634369373 0.1696090996 0.1414414375 0.1882778257 0.0057412931 0.1287910000 319597704 0 1785024512 0.0783825442 -0.0310833920 -0.0641389638 599 1311867190.3994669914 0.1692934632 0.1414879351 0.1882778257 0.0057370480 0.1251730000 319599502 0 1785569280 0.0813197941 -0.0320547670 -0.0641911477 600 1311867190.4313740730 0.1697227806 0.1415349932 0.1882778257 0.0057346631 0.1295430000 319601300 0 1783664640 0.0839355662 -0.0291694496 -0.0642420352 601 1311867190.4633409977 0.1705723852 0.1415833083 0.1882778257 0.0057331242 0.1238480000 319603066 0 1783373824 0.0853045210 -0.0315800533 -0.0636017993 602 1311867190.4993569851 0.1705339849 0.1416313991 0.1882778257 0.0057294660 0.1299020000 319604928 0 1783156736 0.0875352919 -0.0325243324 -0.0636603758 603 1311867190.5318090916 0.1707943827 0.1416797623 0.1882778257 0.0057269300 0.1582750000 319606662 0 1782628352 0.0906470716 -0.0301391985 -0.0638492405 604 1311867190.5633530617 0.1707697362 0.1417279245 0.1882778257 0.0057226935 0.1317810000 319608428 0 1783263232 0.0928234532 -0.0321536064 -0.0630759671 605 1311867190.5994510651 0.1709944159 0.1417762988 0.1882778257 0.0057186269 0.1068710000 319610258 0 1783771136 0.0947876871 -0.0333381295 -0.0631225780 606 1311867190.6314210892 0.1719857156 0.1418261494 0.1882778257 0.0057160640 0.1409450000 319611992 0 1784500224 0.0968372002 -0.0319208577 -0.0625828728 607 1311867190.6634240150 0.1712529212 0.1418746284 0.1882778257 0.0057161991 0.1356170000 319613790 0 1785008128 0.1002577022 -0.0338859893 -0.0618352070 608 1311867190.6996390820 0.1722413152 0.1419245736 0.1882778257 0.0057131729 0.1136380000 319615588 0 1785516032 0.1015054956 -0.0333531722 -0.0621631630 609 1311867190.7313809395 0.1726648211 0.1419750502 0.1882778257 0.0057087286 0.1178050000 319617322 0 1784045568 0.1032158062 -0.0336353220 -0.0616849326 610 1311867190.7634749413 0.1726062596 0.1420252653 0.1882778257 0.0057046641 0.1384590000 319619120 0 1783537664 0.1054675132 -0.0339338854 -0.0612226799 611 1311867190.7994329929 0.1727727503 0.1420755885 0.1882778257 0.0057005600 0.1371780000 319620918 0 1780989952 0.1073889062 -0.0347191691 -0.0607958920 612 1311867190.8317101002 0.1722442806 0.1421248838 0.1882778257 0.0056979681 0.1284200000 319622716 0 1781506048 0.1101791859 -0.0373805799 -0.0591911934 613 1311867190.8634259701 0.1728305817 0.1421749746 0.1882778257 0.0056937579 0.1257840000 319624482 0 1782104064 0.1120277569 -0.0373142697 -0.0590932444 614 1311867190.8994319439 0.1734738052 0.1422259499 0.1882778257 0.0056895084 0.1403720000 319626344 0 1782648832 0.1133204699 -0.0375750437 -0.0591322444 615 1311867190.9316470623 0.1736554950 0.1422770549 0.1882778257 0.0056857028 0.1425810000 319628078 0 1783156736 0.1160237864 -0.0387438759 -0.0571119078 616 1311867190.9635319710 0.1738833636 0.1423283638 0.1882778257 0.0056814312 0.1319990000 319629876 0 1783738368 0.1179044545 -0.0398138091 -0.0570514575 617 1311867190.9994399548 0.1742324680 0.1423800722 0.1882778257 0.0056791911 0.1239990000 319631706 0 1784246272 0.1202782393 -0.0371587314 -0.0579592064 618 1311867191.0313270092 0.1736173630 0.1424306180 0.1882778257 0.0056770215 0.1499190000 319633408 0 1784754176 0.1230612025 -0.0393197276 -0.0567665473 619 1311867191.0636270046 0.1744459271 0.1424823390 0.1882778257 0.0056745659 0.1464250000 319635206 0 1785294848 0.1252032220 -0.0413819477 -0.0540417507 620 1311867191.0994319916 0.1743183434 0.1425336874 0.1882778257 0.0056716641 0.1478410000 319637068 0 1782992896 0.1272329539 -0.0407101139 -0.0555124022 621 1311867191.1313030720 0.1742593199 0.1425847754 0.1882778257 0.0056672879 0.1615320000 319638802 0 1783283712 0.1303149015 -0.0409126393 -0.0543131828 622 1311867191.1633949280 0.1753381938 0.1426374336 0.1882778257 0.0056870433 0.1502540000 319640568 0 1782480896 0.1324830502 -0.0420340747 -0.0521021783 623 1311867191.1993889809 0.1746430099 0.1426888070 0.1882778257 0.0056923615 0.1452370000 319642366 0 1783115776 0.1352121979 -0.0417344049 -0.0539901517 624 1311867191.2313950062 0.1750260442 0.1427406294 0.1882778257 0.0056880705 0.1639000000 319644132 0 1783623680 0.1380917430 -0.0419805571 -0.0523334220 625 1311867191.2634680271 0.1754931360 0.1427930335 0.1882778257 0.0056838304 0.1386820000 319645930 0 1784373248 0.1406887472 -0.0426465459 -0.0511496626 626 1311867191.2997128963 0.1752961725 0.1428449554 0.1882778257 0.0056806615 0.1482810000 319647760 0 1784881152 0.1433584690 -0.0419495851 -0.0523835272 627 1311867191.3316600323 0.1771472394 0.1428996640 0.1882778257 0.0056837132 0.1434140000 319649430 0 1785389056 0.1450997740 -0.0418555029 -0.0499591231 628 1311867191.3634359837 0.1787872910 0.1429568099 0.1882778257 0.0056801583 0.1623980000 319651196 0 1783627776 0.1456372589 -0.0433527939 -0.0478903651 629 1311867191.3995709419 0.1776730418 0.1430120026 0.1882778257 0.0056759773 0.1438770000 319653026 0 1783283712 0.1488899738 -0.0441634916 -0.0481809750 630 1311867191.4315879345 0.1769165695 0.1430658194 0.1882778257 0.0056720172 0.1496540000 319654760 0 1782611968 0.1522926688 -0.0427633040 -0.0484853387 631 1311867191.4634139538 0.1777327359 0.1431207591 0.1882778257 0.0056715424 0.1487720000 319656558 0 1783246848 0.1533478349 -0.0451860912 -0.0469921380 632 1311867191.4996531010 0.1785874218 0.1431768772 0.1882778257 0.0056683118 0.1427650000 319658292 0 1783754752 0.1543186605 -0.0441982932 -0.0475075878 633 1311867191.5314459801 0.1784587651 0.1432326148 0.1882778257 0.0056663721 0.1625050000 319660058 0 1784373248 0.1573247313 -0.0445471853 -0.0451187007 634 1311867191.5636389256 0.1782736182 0.1432878845 0.1882778257 0.0056643660 0.1494650000 319661824 0 1784913920 0.1593340486 -0.0448364280 -0.0452379882 635 1311867191.5998470783 0.1789817065 0.1433440952 0.1882778257 0.0056667777 0.1400370000 319663654 0 1785516032 0.1611412317 -0.0437235981 -0.0451391153 636 1311867191.6314690113 0.1792334914 0.1434005251 0.1882778257 0.0056656424 0.1499020000 319665388 0 1783914496 0.1627059132 -0.0447860546 -0.0431102216 637 1311867191.6636199951 0.1795526892 0.1434572789 0.1882778257 0.0056691467 0.1610910000 319667186 0 1783410688 0.1636627316 -0.0453177877 -0.0422875360 638 1311867191.6995730400 0.1786165833 0.1435123875 0.1882778257 0.0056682619 0.1403820000 319669048 0 1782738944 0.1663300842 -0.0431621186 -0.0422554463 639 1311867191.7314870358 0.1793409586 0.1435684573 0.1882778257 0.0056673192 0.1421870000 319670718 0 1783373824 0.1675335020 -0.0444863997 -0.0393693633 640 1311867191.7635788918 0.1803639233 0.1436259502 0.1882778257 0.0056634634 0.1459770000 319672484 0 1783881728 0.1679017097 -0.0444488451 -0.0395269617 641 1311867191.7997710705 0.1797766089 0.1436823475 0.1882778257 0.0056633008 0.1446400000 319674346 0 1784500224 0.1696249545 -0.0442685857 -0.0392709188 642 1311867191.8315110207 0.1794787943 0.1437381052 0.1882778257 0.0056600928 0.1540680000 319676080 0 1785135104 0.1710374206 -0.0459302366 -0.0377070829 643 1311867191.8634710312 0.1797619760 0.1437941299 0.1882778257 0.0056569573 0.1467750000 319677846 0 1785675776 0.1719819009 -0.0441524237 -0.0380239673 644 1311867191.8996229172 0.1807195991 0.1438514675 0.1882778257 0.0056546744 0.1406640000 319679676 0 1783877632 0.1726796925 -0.0440895036 -0.0361791290 645 1311867191.9316298962 0.1803455055 0.1439080474 0.1882778257 0.0056518431 0.1502210000 319681442 0 1783373824 0.1737305671 -0.0462106019 -0.0343297012 646 1311867191.9634699821 0.1796156764 0.1439633224 0.1882778257 0.0056478831 0.1414200000 319683208 0 1782358016 0.1754496843 -0.0454041064 -0.0357399732 647 1311867191.9995260239 0.1797923744 0.1440186996 0.1882778257 0.0056455856 0.1565160000 319685006 0 1783029760 0.1774006635 -0.0449633002 -0.0333784707 648 1311867192.0315270424 0.1815491170 0.1440766169 0.1882778257 0.0056416387 0.1538340000 319686772 0 1783664640 0.1769562960 -0.0470833182 -0.0304413997 649 1311867192.0634949207 0.1805539131 0.1441328223 0.1882778257 0.0056422584 0.1532040000 319688570 0 1784373248 0.1781820804 -0.0472716987 -0.0323487669 650 1311867192.0998060703 0.1799221188 0.1441878828 0.1882778257 0.0056428748 0.1456310000 319690400 0 1784897536 0.1810332090 -0.0446370281 -0.0319520645 651 1311867192.1316659451 0.1824018210 0.1442465831 0.1882778257 0.0056408498 0.1427050000 319692134 0 1785421824 0.1803854704 -0.0469765626 -0.0279094707 652 1311867192.1635160446 0.1801646799 0.1443016722 0.1882778257 0.0056377412 0.1555080000 319693932 0 1783410688 0.1827421486 -0.0476244614 -0.0307474304 653 1311867192.1996529102 0.1819584072 0.1443593395 0.1882778257 0.0056369251 0.1440360000 319695730 0 1782390784 0.1839988381 -0.0455183797 -0.0281172842 654 1311867192.2316989899 0.1828026325 0.1444181213 0.1882778257 0.0056333796 0.1424430000 319697496 0 1782607872 0.1840588301 -0.0484454483 -0.0263552330 655 1311867192.2635419369 0.1805850863 0.1444733381 0.1882778257 0.0056323787 0.1527820000 319699294 0 1783152640 0.1870731711 -0.0482712612 -0.0282787681 656 1311867192.2994730473 0.1821323484 0.1445307451 0.1882778257 0.0056285505 0.1375600000 319701092 0 1783750656 0.1886815280 -0.0469827689 -0.0255215615 657 1311867192.3315188885 0.1825274229 0.1445885787 0.1882778257 0.0056248353 0.7614680000 332009034 0 1784057856 0.1892543733 -0.0498649813 -0.0250010714 658 1311867192.3636200428 0.1880418956 0.1446546172 0.1882778257 0.0056379876 0.1978650000 335668680 0 1785442304 0.1833276451 -0.0482706763 -0.0304752663 659 1311867192.3994910717 0.1880463660 0.1447204620 0.1882778257 0.0056357804 0.1488390000 338862606 0 1784131584 0.1855954379 -0.0490264371 -0.0296090525 660 1311867192.4316198826 0.1890005022 0.1447875530 0.1890005022 0.0056321508 0.1273710000 338864340 0 1784930304 0.1865292490 -0.0510604903 -0.0286122113 661 1311867192.4635419846 0.1889379621 0.1448543463 0.1890005022 0.0056295577 0.1244220000 338866106 0 1785565184 0.1891859919 -0.0496086217 -0.0294088144 662 1311867192.4995899200 0.1891385913 0.1449212410 0.1891385913 0.0056255475 0.1250160000 338867936 0 1783627776 0.1909949929 -0.0505992882 -0.0287388526 663 1311867192.5316200256 0.1899688989 0.1449891861 0.1899688989 0.0056214501 0.1246220000 338869702 0 1784135680 0.1917296797 -0.0524824820 -0.0279676616 664 1311867192.5636320114 0.1896824092 0.1450564952 0.1899688989 0.0056173211 0.1160190000 338871468 0 1784680448 0.1939666122 -0.0514681078 -0.0292294994 665 1311867192.5996320248 0.1901839375 0.1451243560 0.1901839375 0.0056131852 0.1106770000 338873298 0 1785188352 0.1955160648 -0.0515541323 -0.0284476317 666 1311867192.6315209866 0.1907474548 0.1451928592 0.1907474548 0.0056144843 0.1173780000 338875032 0 1785769984 0.1961788684 -0.0537042990 -0.0277917590 667 1311867192.6636250019 0.1902185231 0.1452603639 0.1907474548 0.0056107159 0.1274360000 338876830 0 1784176640 0.1987007707 -0.0521766394 -0.0288439486 668 1311867192.6996068954 0.1907965839 0.1453285319 0.1907965839 0.0056065657 0.1249340000 338878660 0 1783775232 0.1996395588 -0.0529763736 -0.0279677007 669 1311867192.7316179276 0.1912833750 0.1453972238 0.1912833750 0.0056032445 0.1160530000 338880394 0 1783136256 0.2003336400 -0.0541551113 -0.0276087169 670 1311867192.7636420727 0.1912433505 0.1454656508 0.1912833750 0.0056000476 0.1316500000 338882192 0 1782140928 0.2020580322 -0.0526640937 -0.0280720871 671 1311867192.7994999886 0.1917704493 0.1455346595 0.1917704493 0.0055962955 0.1227620000 338883990 0 1782648832 0.2031109482 -0.0535885729 -0.0268133432 672 1311867192.8316929340 0.1924551129 0.1456044816 0.1924551129 0.0055921726 0.1201740000 338885788 0 1783119872 0.2033923566 -0.0547379777 -0.0264712144 673 1311867192.8636040688 0.1918793619 0.1456732407 0.1924551129 0.0055883235 0.1217670000 338887554 0 1783627776 0.2053592801 -0.0532494634 -0.0268301200 674 1311867192.8996539116 0.1921424270 0.1457421861 0.1924551129 0.0055849375 0.1125030000 338889384 0 1784246272 0.2064231038 -0.0527849831 -0.0262582880 675 1311867192.9316558838 0.1930885762 0.1458123289 0.1930885762 0.0055814025 0.1285570000 338891150 0 1784778752 0.2059671283 -0.0555984117 -0.0249860436 676 1311867192.9638249874 0.1915903389 0.1458800478 0.1930885762 0.0055779118 0.1316650000 338892948 0 1785286656 0.2091123909 -0.0537051447 -0.0265960600 677 1311867192.9997138977 0.1930121630 0.1459496669 0.1930885762 0.0055745590 0.1307700000 338894714 0 1783275520 0.2091505080 -0.0539351776 -0.0250116978 678 1311867193.0316529274 0.1938354671 0.1460202949 0.1938354671 0.0055727603 0.1277060000 338896480 0 1782259712 0.2090213895 -0.0565227866 -0.0238287207 679 1311867193.0636160374 0.1923135519 0.1460884735 0.1938354671 0.0055694049 0.1149130000 338898246 0 1782476800 0.2121237665 -0.0542979911 -0.0259212572 680 1311867193.0996270180 0.1933233887 0.1461579366 0.1938354671 0.0055661502 0.1258260000 338900044 0 1782095872 0.2130011171 -0.0538708605 -0.0245460030 681 1311867193.1316359043 0.1935208142 0.1462274856 0.1938354671 0.0055660134 0.1179760000 338901842 0 1782730752 0.2135747522 -0.0568502732 -0.0231617857 682 1311867193.1638090611 0.1933949888 0.1462966462 0.1938354671 0.0055652991 0.1302030000 338903608 0 1783238656 0.2156967372 -0.0533690527 -0.0254705697 683 1311867193.1995921135 0.1948799789 0.1463677784 0.1948799789 0.0055616138 0.1219970000 338905406 0 1783857152 0.2158533037 -0.0545990653 -0.0227538515 684 1311867193.2316339016 0.1937888712 0.1464371075 0.1948799789 0.0055611503 0.1285780000 338907204 0 1784365056 0.2178867459 -0.0560452938 -0.0231396370 685 1311867193.2635540962 0.1936405897 0.1465060177 0.1948799789 0.0055575001 0.1235840000 338908970 0 1784872960 0.2199071944 -0.0537834913 -0.0236011613 686 1311867193.2995169163 0.1952930391 0.1465771358 0.1952930391 0.0055537608 0.1237240000 338910800 0 1785413632 0.2196285278 -0.0561378971 -0.0215087887 687 1311867193.3314299583 0.1943030059 0.1466466058 0.1952930391 0.0055499005 0.1225330000 338912534 0 1783132160 0.2219947278 -0.0550166145 -0.0232009273 688 1311867193.3636779785 0.1943207681 0.1467158996 0.1952930391 0.0055468052 0.1361030000 338914300 0 1783386112 0.2233339846 -0.0543761775 -0.0237577297 689 1311867193.3995571136 0.1954481006 0.1467866285 0.1954481006 0.0055465875 0.1230790000 338916098 0 1782730752 0.2239464968 -0.0563750044 -0.0213944614 690 1311867193.4318170547 0.1949782819 0.1468564715 0.1954481006 0.0055426315 0.1227270000 338917896 0 1782382592 0.2257101089 -0.0555402376 -0.0232002083 691 1311867193.4635589123 0.1949905753 0.1469261301 0.1954481006 0.0055389590 0.1350220000 338919662 0 1781878784 0.2271664739 -0.0551087633 -0.0236429926 692 1311867193.4995489120 0.1961046308 0.1469971973 0.1961046308 0.0055351400 0.1280530000 338921460 0 1781587968 0.2279398590 -0.0567115061 -0.0213122182 693 1311867193.5316190720 0.1954634041 0.1470671341 0.1961046308 0.0055315100 0.1265580000 338923258 0 1782132736 0.2300718874 -0.0559347197 -0.0231989715 694 1311867193.5635840893 0.1960588843 0.1471377274 0.1961046308 0.0055280329 0.1332100000 338925024 0 1782648832 0.2315664589 -0.0549734868 -0.0227546804 695 1311867193.5995330811 0.1977019608 0.1472104817 0.1977019608 0.0055247622 0.1250600000 338926854 0 1783263232 0.2312271744 -0.0567191839 -0.0212590694 696 1311867193.6317420006 0.1963123381 0.1472810303 0.1977019608 0.0055212740 0.1363910000 338928620 0 1783771136 0.2336624712 -0.0568410382 -0.0229564495 697 1311867193.6635909081 0.1959768832 0.1473508953 0.1977019608 0.0055178167 0.1339030000 338930386 0 1784373248 0.2358387411 -0.0551870391 -0.0241404083 698 1311867193.6995389462 0.1981055290 0.1474236096 0.1981055290 0.0055151826 0.1321770000 338932216 0 1784881152 0.2353625596 -0.0568276607 -0.0214106068 699 1311867193.7315680981 0.1971040517 0.1474946832 0.1981055290 0.0055126231 0.1247970000 338933950 0 1785389056 0.2374414206 -0.0564354211 -0.0231951419 700 1311867193.7635669708 0.1967602819 0.1475650627 0.1981055290 0.0055089136 0.1336210000 338935716 0 1783410688 0.2393232733 -0.0561406724 -0.0236872528 701 1311867193.7996909618 0.1981210858 0.1476371825 0.1981210858 0.0055055774 0.1426940000 338937578 0 1782247424 0.2396702170 -0.0571328588 -0.0218282118 702 1311867193.8315539360 0.1983935833 0.1477094851 0.1983935833 0.0055059560 0.1286710000 338939312 0 1782484992 0.2408990264 -0.0565363988 -0.0226746649 703 1311867193.8635230064 0.1982761472 0.1477814149 0.1983935833 0.0055021680 0.1340290000 338941078 0 1783029760 0.2425258011 -0.0562306419 -0.0231087860 704 1311867193.8996899128 0.1987472028 0.1478538095 0.1987472028 0.0054989038 0.1209750000 338942908 0 1783537664 0.2437283546 -0.0574320480 -0.0220094323 705 1311867193.9315669537 0.1989893764 0.1479263422 0.1989893764 0.0054950631 0.1429380000 338944674 0 1784152064 0.2443358451 -0.0569471344 -0.0239895489 706 1311867193.9637041092 0.1995204091 0.1479994216 0.1995204091 0.0054911900 0.1331410000 338946440 0 1784754176 0.2455866486 -0.0568047129 -0.0231424458 707 1311867193.9997029305 0.1999555081 0.1480729097 0.1999555081 0.0054875020 0.1315680000 338948270 0 1785262080 0.2468803674 -0.0573453270 -0.0219609793 708 1311867194.0316889286 0.1991230547 0.1481450145 0.1999555081 0.0054849733 0.1325610000 338950036 0 1785769984 0.2486570776 -0.0572714470 -0.0240226444 709 1311867194.0636529922 0.1993032694 0.1482171700 0.1999555081 0.0054811315 0.1335620000 338951802 0 1783660544 0.2498011589 -0.0570884459 -0.0241575930 710 1311867194.0996799469 0.1993565857 0.1482891973 0.1999555081 0.0054836604 0.1480940000 338953664 0 1782882304 0.2502037883 -0.0578803830 -0.0226899106 711 1311867194.1317200661 0.1996054053 0.1483613720 0.1999555081 0.0054874240 0.1427400000 338955398 0 1783156736 0.2512149811 -0.0576601811 -0.0245065093 712 1311867194.1635859013 0.1987940818 0.1484322045 0.1999555081 0.0054847795 0.1333520000 338957164 0 1783627776 0.2532050908 -0.0560099483 -0.0244247746 713 1311867194.1996850967 0.2006167918 0.1485053946 0.2006167918 0.0054865325 0.1436800000 338958962 0 1784135680 0.2521347702 -0.0581733026 -0.0219715685 714 1311867194.2315490246 0.1999399215 0.1485774318 0.2006167918 0.0054833413 0.1387890000 338960728 0 1784786944 0.2530812621 -0.0576164238 -0.0238298830 715 1311867194.2636189461 0.1995700151 0.1486487501 0.2006167918 0.0054795502 0.1394150000 338962462 0 1785389056 0.2543215156 -0.0568867475 -0.0236287266 716 1311867194.2997159958 0.2004845887 0.1487211465 0.2006167918 0.0054757728 0.1390430000 338964260 0 1783283712 0.2540012002 -0.0580332652 -0.0217934400 717 1311867194.3317608833 0.2004581541 0.1487933041 0.2006167918 0.0054757795 0.1392310000 338966058 0 1782484992 0.2545415163 -0.0572991632 -0.0232238118 718 1311867194.3637061119 0.2008125484 0.1488657543 0.2008125484 0.0054782920 0.1290800000 338967824 0 1780195328 0.2552635372 -0.0562620163 -0.0218267720 719 1311867194.3996109962 0.2012187690 0.1489385680 0.2012187690 0.0054807238 0.1516550000 338969654 0 1780740096 0.2553531229 -0.0581749529 -0.0201113410 720 1311867194.4318029881 0.2006621510 0.1490104063 0.2012187690 0.0054779886 0.1313810000 338971388 0 1781248000 0.2559594512 -0.0582888685 -0.0215802900 721 1311867194.4638750553 0.2006866932 0.1490820793 0.2012187690 0.0054744779 0.1400190000 338973186 0 1781719040 0.2565238774 -0.0579176024 -0.0218952764 722 1311867194.4996290207 0.2012471408 0.1491543301 0.2012471408 0.0054709271 0.1352320000 338974952 0 1782226944 0.2567770183 -0.0583727770 -0.0205650628 723 1311867194.5316059589 0.2005236596 0.1492253804 0.2012471408 0.0054682691 0.1277620000 338976718 0 1782976512 0.2571685314 -0.0583352819 -0.0214519389 724 1311867194.5637359619 0.2009820342 0.1492968675 0.2012471408 0.0054659298 0.1376310000 338978484 0 1783484416 0.2575422227 -0.0581681877 -0.0213951655 725 1311867194.5996220112 0.2011401802 0.1493683755 0.2012471408 0.0054621773 0.1351660000 338980314 0 1783992320 0.2578153014 -0.0585650913 -0.0205929223 726 1311867194.6318879128 0.2009020597 0.1494393585 0.2012471408 0.0054659490 0.1399230000 338982048 0 1784500224 0.2580904663 -0.0579793416 -0.0216516498 727 1311867194.6636140347 0.2011036277 0.1495104235 0.2012471408 0.0054622366 0.1334450000 338983814 0 1785040896 0.2589427233 -0.0571132563 -0.0194269791 728 1311867194.6996710300 0.2012171596 0.1495814493 0.2012471408 0.0054588260 0.1442380000 338985644 0 1785643008 0.2588602901 -0.0577695332 -0.0197807495 729 1311867194.7317550182 0.2009214610 0.1496518745 0.2012471408 0.0054557039 0.1353370000 338987410 0 1783750656 0.2594990134 -0.0577081107 -0.0199752785 730 1311867194.7635860443 0.2010386288 0.1497222673 0.2012471408 0.0054520039 0.1328940000 338989176 0 1783537664 0.2598653734 -0.0576007254 -0.0193465576 731 1311867194.7997260094 0.2009931952 0.1497924054 0.2012471408 0.0054570576 0.1319350000 338991038 0 1781850112 0.2601345181 -0.0577021539 -0.0196425822 732 1311867194.8318910599 0.2012063712 0.1498626431 0.2012471408 0.0054533522 0.1309600000 338992772 0 1782358016 0.2600233853 -0.0576644093 -0.0193643719 733 1311867194.8636679649 0.2010708451 0.1499325042 0.2012471408 0.0054496514 0.1302930000 338994538 0 1782992896 0.2599079311 -0.0575892106 -0.0195113868 734 1311867194.8995881081 0.2009758800 0.1500020456 0.2012471408 0.0054583430 0.1335140000 338996400 0 1783500800 0.2598023415 -0.0571960956 -0.0194064677 735 1311867194.9318230152 0.2018135935 0.1500725375 0.2018135935 0.0054549770 0.1325750000 338998134 0 1784119296 0.2587530017 -0.0572624579 -0.0180438757 736 1311867194.9638640881 0.2016659975 0.1501426373 0.2018135935 0.0054514617 0.1440460000 338999900 0 1784627200 0.2583549917 -0.0578020103 -0.0173698552 737 1311867194.9998569489 0.2012814581 0.1502120251 0.2018135935 0.0054478768 0.1299890000 339001730 0 1785167872 0.2580285072 -0.0570698343 -0.0178007446 738 1311867195.0318229198 0.2021728009 0.1502824327 0.2021728009 0.0054464180 0.1465820000 339003496 0 1785769984 0.2560915053 -0.0581299737 -0.0156175382 739 1311867195.0636589527 0.2011209875 0.1503512264 0.2021728009 0.0054430170 0.1385770000 339005262 0 1784168448 0.2562680244 -0.0572495572 -0.0177908633 740 1311867195.0998389721 0.2002214342 0.1504186185 0.2021728009 0.0054439913 0.1310400000 339007060 0 1783664640 0.2566297352 -0.0567117557 -0.0179794151 741 1311867195.1317551136 0.2005581558 0.1504862832 0.2021728009 0.0054410993 0.1350220000 339008858 0 1781002240 0.2556724548 -0.0571971275 -0.0174396187 742 1311867195.1637389660 0.2002780437 0.1505533880 0.2021728009 0.0054380770 0.1347980000 339010624 0 1781469184 0.2545896769 -0.0564479195 -0.0186715852 743 1311867195.1996819973 0.2007984221 0.1506210126 0.2021728009 0.0054367653 0.1450070000 339012454 0 1781977088 0.2530552447 -0.0563758835 -0.0181321464 744 1311867195.2319529057 0.1993334442 0.1506864863 0.2021728009 0.0054344326 0.1288190000 339014220 0 1782484992 0.2531494200 -0.0568619147 -0.0175533891 745 1311867195.2639589310 0.1990852505 0.1507514511 0.2021728009 0.0054313735 0.1295570000 339016018 0 1783029760 0.2526445389 -0.0566907488 -0.0182244517 746 1311867195.2998430729 0.1996910572 0.1508170537 0.2021728009 0.0054284584 0.1255000000 339017816 0 1783648256 0.2511858344 -0.0561436228 -0.0179492943 747 1311867195.3316628933 0.2005020231 0.1508835664 0.2021728009 0.0054255763 0.1414030000 339019550 0 1784152064 0.2492132783 -0.0580363050 -0.0162271932 748 1311867195.3636600971 0.1991378367 0.1509480775 0.2021728009 0.0054225766 0.1317230000 339021316 0 1784754176 0.2489009798 -0.0569824837 -0.0188979208 749 1311867195.3998188972 0.1989356279 0.1510121463 0.2021728009 0.0054280032 0.1361540000 339023146 0 1785262080 0.2479912490 -0.0567653142 -0.0187603198 750 1311867195.4317750931 0.1997997463 0.1510771964 0.2021728009 0.0054255345 0.1314640000 339024912 0 1783156736 0.2455776036 -0.0573524721 -0.0179320481 751 1311867195.4637739658 0.1983525157 0.1511401463 0.2021728009 0.0054279742 0.1307640000 339026678 0 1782861824 0.2451720238 -0.0564692169 -0.0203133617 752 1311867195.4998610020 0.1981390119 0.1512026448 0.2021728009 0.0054243906 0.1121060000 339028508 0 1782648832 0.2443077564 -0.0560440682 -0.0196072217 753 1311867195.5318269730 0.1982385367 0.1512651094 0.2021728009 0.0054220506 0.1288050000 339030274 0 1781977088 0.2424097061 -0.0569593459 -0.0187721290 754 1311867195.5637209415 0.1974148452 0.1513263160 0.2021728009 0.0054187094 0.1264460000 339032072 0 1782611968 0.2412711084 -0.0563832931 -0.0200461335 755 1311867195.5997560024 0.1975242943 0.1513875053 0.2021728009 0.0054151476 0.1375630000 339033902 0 1783119872 0.2396865785 -0.0565408319 -0.0193990655 756 1311867195.6317939758 0.1973313540 0.1514482776 0.2021728009 0.0054128239 0.1211880000 339035636 0 1783738368 0.2378299236 -0.0570873097 -0.0191939697 757 1311867195.6637549400 0.1971520185 0.1515086525 0.2021728009 0.0054105756 0.1343740000 339037402 0 1784279040 0.2359592021 -0.0566411875 -0.0201274324 758 1311867195.6999230385 0.1967717558 0.1515683663 0.2021728009 0.0054210141 0.1352350000 339039232 0 1784778752 0.2343228310 -0.0568015277 -0.0198547002 759 1311867195.7320320606 0.1966384202 0.1516277471 0.2021728009 0.0054185365 0.1280020000 339040998 0 1785380864 0.2322923392 -0.0578205585 -0.0192024093 760 1311867195.7676620483 0.1955283433 0.1516855111 0.2021728009 0.0054150943 0.1210000000 339042796 0 1782980608 0.2316138148 -0.0569334067 -0.0201296080 761 1311867195.7996349335 0.1961612701 0.1517439549 0.2021728009 0.0054120612 0.1330550000 339044594 0 1783255040 0.2291755080 -0.0569397733 -0.0195674933 762 1311867195.8317549229 0.1962627470 0.1518023785 0.2021728009 0.0054086419 0.1299620000 339046328 0 1780084736 0.2270705253 -0.0571760908 -0.0194566231 763 1311867195.8676300049 0.1946834028 0.1518585791 0.2021728009 0.0054063184 0.1307120000 339048190 0 1780707328 0.2265685648 -0.0558892079 -0.0205653291 764 1311867195.8998401165 0.1951112598 0.1519151925 0.2021728009 0.0054039484 0.1050540000 339049956 0 1781379072 0.2246933877 -0.0556499735 -0.0198747162 765 1311867195.9319150448 0.1945575178 0.1519709341 0.2021728009 0.0054013560 0.1219900000 339051722 0 1781850112 0.2232554704 -0.0566772781 -0.0197743401 766 1311867195.9677369595 0.1944896430 0.1520264416 0.2021728009 0.0053988952 0.1222780000 339053552 0 1782358016 0.2216604650 -0.0554600582 -0.0204284508 767 1311867195.9996581078 0.1945510656 0.1520818844 0.2021728009 0.0053954543 0.1193070000 339055350 0 1782976512 0.2207181007 -0.0547758266 -0.0191458706 768 1311867196.0318861008 0.1940953732 0.1521365895 0.2021728009 0.0053934150 0.1236600000 339057084 0 1783484416 0.2190144211 -0.0566445924 -0.0195956901 769 1311867196.0677540302 0.1935236007 0.1521904087 0.2021728009 0.0053908662 0.1128690000 339058914 0 1783992320 0.2181793749 -0.0545559973 -0.0207836926 770 1311867196.0996539593 0.1941647977 0.1522449209 0.2021728009 0.0053884643 0.1241590000 339060712 0 1784532992 0.2159935534 -0.0553492233 -0.0195833296 771 1311867196.1317958832 0.1940601468 0.1522991560 0.2021728009 0.0053851646 0.1219390000 339062446 0 1785135104 0.2143681943 -0.0556505732 -0.0195733998 772 1311867196.1677470207 0.1924811453 0.1523512052 0.2021728009 0.0053872933 0.1118710000 339064276 0 1785643008 0.2145481259 -0.0540258437 -0.0202532299 773 1311867196.1997110844 0.1925517917 0.1524032111 0.2021728009 0.0053860627 0.1346100000 339066074 0 1784172544 0.2122987956 -0.0562718585 -0.0196791589 774 1311867196.2319200039 0.1919005364 0.1524542412 0.2021728009 0.0053830395 0.1203620000 339067808 0 1783533568 0.2108837068 -0.0560163632 -0.0200848598 775 1311867196.2679240704 0.1917511672 0.1525049470 0.2021728009 0.0053804084 0.1145560000 339069638 0 1783029760 0.2097308636 -0.0552433170 -0.0203240756 776 1311867196.2997319698 0.1922799647 0.1525562034 0.2021728009 0.0053773429 0.1167560000 339071404 0 1780867072 0.2076555789 -0.0557717793 -0.0197805688 777 1311867196.3318328857 0.1915485412 0.1526063866 0.2021728009 0.0053752816 0.1166320000 339073138 0 1781342208 0.2064785957 -0.0558281839 -0.0204868726 778 1311867196.3687291145 0.1907847226 0.1526554590 0.2021728009 0.0053723249 0.1296330000 339075000 0 1781850112 0.2057618648 -0.0544776693 -0.0208448172 779 1311867196.3997390270 0.1917857230 0.1527056904 0.2021728009 0.0053690360 0.1327640000 339076734 0 1782394880 0.2028824091 -0.0557750762 -0.0198782217 780 1311867196.4320199490 0.1906456798 0.1527543314 0.2021728009 0.0053665113 0.1268340000 339078500 0 1782992896 0.2022920251 -0.0552517548 -0.0204069186 781 1311867196.4677999020 0.1903204173 0.1528024314 0.2021728009 0.0053636989 0.1292430000 339080330 0 1783611392 0.2010349780 -0.0542684086 -0.0204278212 782 1311867196.4997680187 0.1907328665 0.1528509358 0.2021728009 0.0053606281 0.1283690000 339082096 0 1784119296 0.1989927143 -0.0548412688 -0.0197265204 783 1311867196.5319259167 0.1898317337 0.1528981654 0.2021728009 0.0053573162 0.1269990000 339083862 0 1784627200 0.1979518831 -0.0544854105 -0.0202517789 784 1311867196.5677669048 0.1894486994 0.1529447860 0.2021728009 0.0053540906 0.1318060000 339085692 0 1785167872 0.1966803670 -0.0532908328 -0.0200502761 785 1311867196.5997130871 0.1890757084 0.1529908127 0.2021728009 0.0053547237 0.1322000000 339087426 0 1782992896 0.1947281510 -0.0544978753 -0.0195278451 786 1311867196.6319940090 0.1887855828 0.1530363531 0.2021728009 0.0053517957 0.1278470000 339089224 0 1782775808 0.1932992041 -0.0537502468 -0.0198556520 787 1311867196.6677370071 0.1883868724 0.1530812712 0.2021728009 0.0053519985 0.1209480000 339091054 0 1782484992 0.1916461587 -0.0517854877 -0.0193292964 788 1311867196.6997001171 0.1883502454 0.1531260287 0.2021728009 0.0053513701 0.1431300000 339092788 0 1782136832 0.1895768195 -0.0531788431 -0.0188339073 789 1311867196.7317600250 0.1875692904 0.1531696831 0.2021728009 0.0053481339 0.1251500000 339094554 0 1782607872 0.1883297265 -0.0521827303 -0.0188721307 790 1311867196.7677071095 0.1876515746 0.1532133310 0.2021728009 0.0053449818 0.1440260000 339096416 0 1783115776 0.1854979545 -0.0518382080 -0.0185041074 791 1311867196.7997360229 0.1874355376 0.1532565955 0.2021728009 0.0053418312 0.1223690000 339098150 0 1783865344 0.1836371571 -0.0523091778 -0.0183285289 792 1311867196.8318669796 0.1866113394 0.1532987101 0.2021728009 0.0053387581 0.1196530000 339099916 0 1784373248 0.1823447198 -0.0521627888 -0.0183783118 793 1311867196.8677489758 0.1866994202 0.1533408295 0.2021728009 0.0053389700 0.1343090000 339101746 0 1784881152 0.1799126267 -0.0511569828 -0.0182775874 794 1311867196.8997149467 0.1869703233 0.1533831840 0.2021728009 0.0053361146 0.1245520000 339103544 0 1785389056 0.1776828021 -0.0519387200 -0.0173560884 795 1311867196.9319748878 0.1865143478 0.1534248585 0.2021728009 0.0053329239 0.1228390000 339105278 0 1783398400 0.1757300794 -0.0516759194 -0.0176847558 796 1311867196.9679110050 0.1849844754 0.1534645062 0.2021728009 0.0053297694 0.1227050000 339107108 0 1782378496 0.1745529920 -0.0522097982 -0.0182826873 797 1311867196.9998660088 0.1849821806 0.1535040516 0.2021728009 0.0053270559 0.1281520000 339108906 0 1782480896 0.1725231856 -0.0526827388 -0.0181408022 798 1311867197.0319790840 0.1850871444 0.1535436294 0.2021728009 0.0053252578 0.1232140000 339110640 0 1782120448 0.1703361571 -0.0523269624 -0.0181520097 799 1311867197.0678169727 0.1842703968 0.1535820860 0.2021728009 0.0053221847 0.1326980000 339112406 0 1782755328 0.1687149704 -0.0525821820 -0.0188045241 800 1311867197.0998361111 0.1839737296 0.1536200755 0.2021728009 0.0053191250 0.1302390000 339114172 0 1783242752 0.1669158489 -0.0533251502 -0.0188510437 801 1311867197.1318700314 0.1838383377 0.1536578012 0.2021728009 0.0053163770 0.1219300000 339115970 0 1783992320 0.1651476026 -0.0518678911 -0.0192472208 802 1311867197.1677129269 0.1835680604 0.1536950958 0.2021728009 0.0053130964 0.1240760000 339117800 0 1784500224 0.1629089266 -0.0525506549 -0.0187368337 803 1311867197.1997759342 0.1829118580 0.1537314803 0.2021728009 0.0053107281 0.1256010000 339119534 0 1785008128 0.1613722742 -0.0526433364 -0.0191495400 804 1311867197.2319281101 0.1831007451 0.1537680092 0.2021728009 0.0053076580 0.1341940000 339121300 0 1785516032 0.1592364013 -0.0516088828 -0.0194855053 805 1311867197.2679190636 0.1825238615 0.1538037308 0.2021728009 0.0053050294 0.1380910000 339123162 0 1783373824 0.1570368260 -0.0524341278 -0.0191044230 806 1311867197.2998099327 0.1818445474 0.1538385209 0.2021728009 0.0053018008 0.1244530000 339124960 0 1782648832 0.1556932926 -0.0520660356 -0.0193634257 807 1311867197.3320178986 0.1819358766 0.1538733379 0.2021728009 0.0052988844 0.1361600000 339126694 0 1780367360 0.1535621881 -0.0513976663 -0.0192424171 808 1311867197.3678550720 0.1817381680 0.1539078241 0.2021728009 0.0052958680 0.1230600000 339128492 0 1780834304 0.1515425593 -0.0516240932 -0.0186032504 809 1311867197.3998820782 0.1815876067 0.1539420389 0.2021728009 0.0052937365 0.1235130000 339130226 0 1781506048 0.1495270431 -0.0519553758 -0.0190099422 810 1311867197.4319560528 0.1807167977 0.1539750942 0.2021728009 0.0052906776 0.1251880000 339131992 0 1782140928 0.1483949721 -0.0513017960 -0.0199191067 811 1311867197.4679911137 0.1807994097 0.1540081698 0.2021728009 0.0052875519 0.1202910000 339133790 0 1782648832 0.1460839957 -0.0521712303 -0.0197206512 812 1311867197.4999949932 0.1809373945 0.1540413338 0.2021728009 0.0052847578 0.1384490000 339135556 0 1783230464 0.1439004242 -0.0514652357 -0.0208047517 813 1311867197.5318820477 0.1801112145 0.1540734001 0.2021728009 0.0052815867 0.1344080000 339137290 0 1783771136 0.1430864930 -0.0505292676 -0.0219371095 814 1311867197.5678689480 0.1799878776 0.1541052361 0.2021728009 0.0052785295 0.1205220000 339139120 0 1784373248 0.1412688047 -0.0512937643 -0.0213801153 815 1311867197.5999100208 0.1794085205 0.1541362830 0.2021728009 0.0052755188 0.1309520000 339140886 0 1784881152 0.1397108138 -0.0512879975 -0.0228877217 816 1311867197.6319630146 0.1789485663 0.1541666903 0.2021728009 0.0052732632 0.1526250000 339142652 0 1785380864 0.1386217773 -0.0490677394 -0.0244721547 817 1311867197.6679289341 0.1794670522 0.1541976577 0.2021728009 0.0052741088 0.1403160000 339144482 0 1783619584 0.1354626566 -0.0510075390 -0.0232937448 818 1311867197.6997439861 0.1785125732 0.1542273825 0.2021728009 0.0052709204 0.1309910000 339146248 0 1783402496 0.1348471940 -0.0492463186 -0.0252917614 819 1311867197.7320039272 0.1783032119 0.1542567791 0.2021728009 0.0052677577 0.1553920000 339148014 0 1782890496 0.1335086972 -0.0483316369 -0.0254725832 820 1311867197.7679040432 0.1791807115 0.1542871741 0.2021728009 0.0052651602 0.1374260000 339149844 0 1783361536 0.1303927451 -0.0503129587 -0.0248105768 821 1311867197.7998349667 0.1780071259 0.1543160657 0.2021728009 0.0052624088 0.1327730000 339151610 0 1784033280 0.1299817413 -0.0483327843 -0.0270598400 822 1311867197.8319869041 0.1783331931 0.1543452836 0.2021728009 0.0052592930 0.1519780000 339153376 0 1784745984 0.1281507909 -0.0489434525 -0.0265780594 823 1311867197.8679409027 0.1780468374 0.1543740826 0.2021728009 0.0052567085 0.1339300000 339155206 0 1785253888 0.1265008897 -0.0489804223 -0.0272152498 824 1311867197.8999540806 0.1772451699 0.1544018387 0.2021728009 0.0052578113 0.1354100000 339157004 0 1785761792 0.1254261881 -0.0471197851 -0.0293711480 825 1311867197.9320459366 0.1777035892 0.1544300833 0.2021728009 0.0052561733 0.1546710000 339158706 0 1783894016 0.1230753511 -0.0478800498 -0.0286848005 826 1311867197.9679460526 0.1771648973 0.1544576073 0.2021728009 0.0052533832 0.1377220000 339160568 0 1783402496 0.1214477941 -0.0477582514 -0.0295339786 827 1311867197.9997749329 0.1766953468 0.1544844969 0.2021728009 0.0052504333 0.1422750000 339162334 0 1783271424 0.1202814355 -0.0459397733 -0.0309434440 828 1311867198.0318191051 0.1771372706 0.1545118553 0.2021728009 0.0052473015 0.1545890000 339164068 0 1783742464 0.1180262789 -0.0464760512 -0.0300334692 829 1311867198.0678160191 0.1764053106 0.1545382648 0.2021728009 0.0052452173 0.1359530000 339165930 0 1784250368 0.1165524572 -0.0458302125 -0.0312754512 830 1311867198.0997960567 0.1759724021 0.1545640891 0.2021728009 0.0052423763 0.1440670000 339167728 0 1784999936 0.1153751388 -0.0447015762 -0.0321834348 831 1311867198.1318290234 0.1762905568 0.1545902341 0.2021728009 0.0052393470 0.1423460000 339169430 0 1785507840 0.1130516902 -0.0450725183 -0.0317594297 832 1311867198.1679520607 0.1755363494 0.1546154097 0.2021728009 0.0052366093 0.1434640000 339171292 0 1783386112 0.1114878058 -0.0445088930 -0.0328278691 833 1311867198.1998140812 0.1754061431 0.1546403685 0.2021728009 0.0052349973 0.1446590000 339173058 0 1782730752 0.1098692641 -0.0440707877 -0.0332363993 834 1311867198.2320029736 0.1757687777 0.1546657024 0.2021728009 0.0052318667 0.1513020000 339174824 0 1782521856 0.1076690853 -0.0442160554 -0.0330042653 835 1311867198.2679619789 0.1748416275 0.1546898651 0.2021728009 0.0052294188 0.1453590000 339176654 0 1782992896 0.1057597846 -0.0433023125 -0.0349920876 836 1311867198.2998640537 0.1747470498 0.1547138570 0.2021728009 0.0052263850 0.1459290000 339178420 0 1783664640 0.1039811671 -0.0428219400 -0.0351981670 837 1311867198.3318629265 0.1753034294 0.1547384562 0.2021728009 0.0052295410 0.1454180000 339180154 0 1784279040 0.1012813747 -0.0428349115 -0.0349682570 838 1311867198.3679699898 0.1740569919 0.1547615094 0.2021728009 0.0052266157 0.1357800000 339181984 0 1784881152 0.0996985137 -0.0417178608 -0.0370571278 839 1311867198.3999059200 0.1742559373 0.1547847447 0.2021728009 0.0052237619 0.1242950000 339183750 0 1785389056 0.0972990096 -0.0411339477 -0.0377390310 840 1311867198.4319880009 0.1746152192 0.1548083524 0.2021728009 0.0052377664 0.1264910000 339185324 0 1783537664 0.0948854983 -0.0422256477 -0.0359445997 841 1311867198.4679210186 0.1736151278 0.1548307148 0.2021728009 0.0052446568 0.1513300000 339187154 0 1783029760 0.0922699794 -0.0415005907 -0.0394451506 842 1311867198.5000751019 0.1740627736 0.1548535557 0.2021728009 0.0052468009 0.1480010000 339188920 0 1781882880 0.0895369649 -0.0402037315 -0.0402165130 843 1311867198.5321249962 0.1746637821 0.1548770554 0.2021728009 0.0052449983 0.1475100000 339190654 0 1782390784 0.0865618289 -0.0410972647 -0.0391755849 844 1311867198.5679900646 0.1727513373 0.1548982335 0.2021728009 0.0052421525 0.1486350000 339192484 0 1782861824 0.0845243037 -0.0395801514 -0.0432512350 845 1311867198.5999510288 0.1724691689 0.1549190275 0.2021728009 0.0052400954 0.1571510000 339194250 0 1783533568 0.0827950537 -0.0394655056 -0.0428703167 846 1311867198.6319661140 0.1713541150 0.1549384543 0.2021728009 0.0052381057 0.1495000000 339196016 0 1784246272 0.0810385644 -0.0396662317 -0.0439608283 847 1311867198.6680729389 0.1713388860 0.1549578173 0.2021728009 0.0052359385 0.1479940000 339197846 0 1784754176 0.0780241117 -0.0389802530 -0.0456581414 848 1311867198.6998438835 0.1708758473 0.1549765885 0.2021728009 0.0052328818 0.1609150000 339199548 0 1785262080 0.0765335783 -0.0378373377 -0.0465481393 849 1311867198.7318739891 0.1711204648 0.1549956037 0.2021728009 0.0052300418 0.1482190000 339201314 0 1785769984 0.0742209777 -0.0378547423 -0.0464067571 850 1311867198.7679109573 0.1695382297 0.1550127127 0.2021728009 0.0052284408 0.1531420000 339203144 0 1783918592 0.0731536523 -0.0367378518 -0.0483626686 851 1311867198.7998390198 0.1706784219 0.1550311212 0.2021728009 0.0052256160 0.1404990000 339204846 0 1783410688 0.0704190880 -0.0368209444 -0.0474870391 852 1311867198.8319530487 0.1704712510 0.1550492435 0.2021728009 0.0052227001 0.1627200000 339206612 0 1782099968 0.0682296902 -0.0363541767 -0.0488493070 853 1311867198.8678910732 0.1694501936 0.1550661262 0.2021728009 0.0052205765 0.1529980000 339208442 0 1782771712 0.0672332123 -0.0357400589 -0.0499022678 854 1311867198.8998548985 0.1697563082 0.1550833278 0.2021728009 0.0052175835 0.1584760000 339210176 0 1783242752 0.0654502809 -0.0354321450 -0.0502191447 855 1311867198.9318809509 0.1698747873 0.1551006277 0.2021728009 0.0052145913 0.1580060000 339211942 0 1783750656 0.0637140796 -0.0344151258 -0.0509876497 856 1311867198.9680769444 0.1692036390 0.1551171032 0.2021728009 0.0052123835 0.1754540000 339213804 0 1784406016 0.0630834699 -0.0335609168 -0.0515008308 857 1311867199.0000500679 0.1696287245 0.1551340363 0.2021728009 0.0052194136 0.1767980000 339215570 0 1785008128 0.0614676736 -0.0327390134 -0.0523124933 858 1311867199.0318429470 0.1690289676 0.1551502308 0.2021728009 0.0052179269 0.1624910000 339217304 0 1785516032 0.0606318600 -0.0319936275 -0.0530679412 859 1311867199.0679919720 0.1689618677 0.1551663096 0.2021728009 0.0052158382 0.1749830000 339219166 0 1783521280 0.0599531792 -0.0306765772 -0.0541752987 860 1311867199.0998599529 0.1695583314 0.1551830445 0.2021728009 0.0052164106 0.1531240000 339220900 0 1783009280 0.0582316630 -0.0303514116 -0.0544014499 861 1311867199.1320021152 0.1694143116 0.1551995732 0.2021728009 0.0052263383 0.1680800000 339222698 0 1782013952 0.0574512854 -0.0300529394 -0.0552150495 862 1311867199.1678910255 0.1684750915 0.1552149741 0.2021728009 0.0052282972 0.1762080000 339224528 0 1782521856 0.0573409833 -0.0283159520 -0.0571264550 863 1311867199.2001259327 0.1696464568 0.1552316965 0.2021728009 0.0052266762 0.1582960000 339226294 0 1782992896 0.0555423051 -0.0283701029 -0.0571188480 864 1311867199.2340989113 0.1698051095 0.1552485639 0.2021728009 0.0052239460 0.1661790000 339228124 0 1783500800 0.0539784133 -0.0276014935 -0.0582433715 865 1311867199.2679419518 0.1692441255 0.1552647437 0.2021728009 0.0052209719 0.1770360000 339229890 0 1784152064 0.0534608290 -0.0261217374 -0.0591989607 866 1311867199.3000299931 0.1701502949 0.1552819326 0.2021728009 0.0052183657 0.1707370000 339231656 0 1784754176 0.0511567965 -0.0264666192 -0.0594997592 867 1311867199.3318800926 0.1702545583 0.1552992021 0.2021728009 0.0052170874 0.1859370000 339233358 0 1785262080 0.0500756204 -0.0260777492 -0.0604850464 868 1311867199.3681409359 0.1699247062 0.1553160517 0.2021728009 0.0052141437 0.1671400000 339235220 0 1785769984 0.0486813784 -0.0254325233 -0.0617278926 869 1311867199.3999199867 0.1705111265 0.1553335374 0.2021728009 0.0052119537 0.1865660000 339236954 0 1783775232 0.0467202738 -0.0251566079 -0.0621367916 870 1311867199.4320480824 0.1697251350 0.1553500795 0.2021728009 0.0052092215 0.1626190000 339238720 0 1783279616 0.0453156717 -0.0251209401 -0.0639781356 871 1311867199.4679720402 0.1692583561 0.1553660477 0.2021728009 0.0052064891 0.1505070000 339240550 0 1782267904 0.0437634289 -0.0243760366 -0.0649477020 872 1311867199.5001809597 0.1691773683 0.1553818863 0.2021728009 0.0052037352 0.1723800000 339242348 0 1782865920 0.0419322327 -0.0243689884 -0.0655215755 873 1311867199.5322530270 0.1687003523 0.1553971423 0.2021728009 0.0052024113 0.1682630000 339244082 0 1783410688 0.0404192507 -0.0234443396 -0.0666448697 874 1311867199.5682659149 0.1689409316 0.1554126386 0.2021728009 0.0051995779 0.1545980000 339245944 0 1783918592 0.0375260748 -0.0229641590 -0.0672639757 875 1311867199.6003990173 0.1687640399 0.1554278974 0.2021728009 0.0051966926 0.1660190000 339247678 0 1784516608 0.0351357535 -0.0229628049 -0.0677213967 876 1311867199.6322081089 0.1685262173 0.1554428498 0.2021728009 0.0051948676 0.1606900000 339249444 0 1785040896 0.0328085944 -0.0225213319 -0.0683409274 877 1311867199.6680541039 0.1683205068 0.1554575336 0.2021728009 0.0051924338 0.1611740000 339251274 0 1785643008 0.0307547245 -0.0223372318 -0.0680329576 878 1311867199.6999409199 0.1680166870 0.1554718378 0.2021728009 0.0051895317 0.1648260000 339253072 0 1783521280 0.0284370463 -0.0221352968 -0.0689660385 879 1311867199.7320048809 0.1673010141 0.1554852954 0.2021728009 0.0051956380 0.1686150000 339254806 0 1783156736 0.0261193421 -0.0216033794 -0.0696916208 880 1311867199.7680690289 0.1671472043 0.1554985475 0.2021728009 0.0052050896 0.1627980000 339256636 0 1782140928 0.0239278618 -0.0219130740 -0.0694916397 881 1311867199.8000559807 0.1678349078 0.1555125502 0.2021728009 0.0052063354 0.1634590000 339258370 0 1782648832 0.0210483596 -0.0219245628 -0.0692157969 882 1311867199.8324799538 0.1659924090 0.1555244322 0.2021728009 0.0052037646 0.1680560000 339260168 0 1783119872 0.0200433303 -0.0210980959 -0.0709606558 883 1311867199.8679389954 0.1667162478 0.1555371069 0.2021728009 0.0052011189 0.1637170000 339261998 0 1783627776 0.0172535274 -0.0214568339 -0.0698168278 884 1311867199.8999218941 0.1669708192 0.1555500410 0.2021728009 0.0051986140 0.1667470000 339263764 0 1784246272 0.0144302156 -0.0216657799 -0.0702958107 885 1311867199.9322059155 0.1659398973 0.1555617809 0.2021728009 0.0051959056 0.1640350000 339265530 0 1784754176 0.0130606890 -0.0208678693 -0.0714690313 886 1311867199.9679698944 0.1656342447 0.1555731494 0.2021728009 0.0051931486 0.1591690000 339267360 0 1785294848 0.0109647689 -0.0210617073 -0.0709745362 887 1311867200.0000519753 0.1655356139 0.1555843810 0.2021728009 0.0051904117 0.1582620000 339269094 0 1783275520 0.0086210798 -0.0212924909 -0.0716234073 888 1311867200.0322039127 0.1645994931 0.1555945332 0.2021728009 0.0051875685 0.1462050000 339270892 0 1782767616 0.0073293806 -0.0193936247 -0.0727166086 889 1311867200.0680060387 0.1646293253 0.1556046961 0.2021728009 0.0051858656 0.1656350000 339272722 0 1782095872 0.0045742732 -0.0206965897 -0.0714904964 890 1311867200.1000580788 0.1641629040 0.1556143120 0.2021728009 0.0051846202 0.1561530000 339274488 0 1782730752 0.0025747612 -0.0200877544 -0.0721930489 891 1311867200.1321730614 0.1634016186 0.1556230520 0.2021728009 0.0051819442 0.1612730000 339276254 0 1783238656 0.0013049407 -0.0190207008 -0.0725559145 892 1311867200.1680541039 0.1641044170 0.1556325602 0.2021728009 0.0051805861 0.1764370000 339278084 0 1783857152 -0.0015880731 -0.0200062208 -0.0707089156 893 1311867200.2000620365 0.1632144451 0.1556410506 0.2021728009 0.0051794142 0.7748760000 351583194 0 1785954304 -0.0030283830 -0.0187812354 -0.0725238770 894 1311867200.2321259975 0.1640936434 0.1556505054 0.2021728009 0.0051770460 0.1495920000 355242808 0 1785696256 -0.0063124257 -0.0188032724 -0.0717260763 895 1311867200.2681920528 0.1639631987 0.1556597933 0.2021728009 0.0051744251 0.1598980000 358436766 0 1783787520 -0.0090258708 -0.0196536779 -0.0707675517 896 1311867200.3000659943 0.1628774554 0.1556678488 0.2021728009 0.0051732079 0.1506190000 358438532 0 1784676352 -0.0100348517 -0.0178289115 -0.0716368705 897 1311867200.3321170807 0.1631297171 0.1556761674 0.2021728009 0.0051745978 0.1430720000 358440266 0 1785311232 -0.0131377177 -0.0195817426 -0.0696235150 898 1311867200.3681631088 0.1630953699 0.1556844294 0.2021728009 0.0051816225 0.1390090000 358442128 0 1782865920 -0.0159571730 -0.0182194225 -0.0702750534 899 1311867200.4000649452 0.1628616005 0.1556924129 0.2021728009 0.0051788246 0.1398020000 358443862 0 1783373824 -0.0176911671 -0.0178262759 -0.0694637150 900 1311867200.4321138859 0.1623901874 0.1556998548 0.2021728009 0.0051768404 0.1397670000 358445628 0 1783881728 -0.0201828815 -0.0193762593 -0.0686483011 901 1311867200.4681320190 0.1614344120 0.1557062195 0.2021728009 0.0051744701 0.1442470000 358447458 0 1784426496 -0.0219916124 -0.0184466075 -0.0687990785 902 1311867200.5000898838 0.1620586663 0.1557132621 0.2021728009 0.0051775589 0.1418590000 358449224 0 1784934400 -0.0251626689 -0.0188437607 -0.0675335154 903 1311867200.5321609974 0.1615529954 0.1557197292 0.2021728009 0.0051840546 0.1554860000 358450990 0 1785516032 -0.0276131947 -0.0189866647 -0.0673291311 904 1311867200.5682120323 0.1604973823 0.1557250142 0.2021728009 0.0051874500 0.1315620000 358452852 0 1783541760 -0.0292293821 -0.0179983359 -0.0672518834 905 1311867200.6000909805 0.1606892943 0.1557304996 0.2021728009 0.0051858776 0.1408930000 358454618 0 1782902784 -0.0316637866 -0.0188256875 -0.0659522414 906 1311867200.6320428848 0.1603804678 0.1557356320 0.2021728009 0.0051835014 0.1600830000 358456352 0 1782231040 -0.0343052410 -0.0185688492 -0.0654084831 907 1311867200.6682040691 0.1595439762 0.1557398308 0.2021728009 0.0051812892 0.1502710000 358458214 0 1782865920 -0.0363688283 -0.0181412604 -0.0649934337 908 1311867200.7001199722 0.1599607319 0.1557444794 0.2021728009 0.0051787894 0.1332990000 358459948 0 1783373824 -0.0389652997 -0.0179652032 -0.0638927072 909 1311867200.7321701050 0.1590658724 0.1557481333 0.2021728009 0.0051798655 0.1356060000 358461714 0 1783992320 -0.0406885669 -0.0175264403 -0.0641307533 910 1311867200.7680790424 0.1589701325 0.1557516739 0.2021728009 0.0051782235 0.1440860000 358463544 0 1784516608 -0.0430877693 -0.0167418141 -0.0631926954 911 1311867200.8000760078 0.1583660990 0.1557545438 0.2021728009 0.0051762484 0.1528060000 358465278 0 1785040896 -0.0451090485 -0.0177631490 -0.0620655231 912 1311867200.8321371078 0.1573658437 0.1557563106 0.2021728009 0.0051739548 0.1543910000 358467076 0 1785643008 -0.0468852483 -0.0168110412 -0.0622919537 913 1311867200.8681581020 0.1567756981 0.1557574271 0.2021728009 0.0051743247 0.1317570000 358468906 0 1784041472 -0.0487217642 -0.0163530707 -0.0612493567 914 1311867200.8999950886 0.1567566097 0.1557585203 0.2021728009 0.0051727576 0.1565130000 358470704 0 1783537664 -0.0506007336 -0.0172416940 -0.0601430796 915 1311867200.9320290089 0.1560374796 0.1557588252 0.2021728009 0.0051712249 0.1545930000 358472406 0 1783029760 -0.0520131029 -0.0173753891 -0.0597740300 916 1311867200.9681539536 0.1557470560 0.1557588123 0.2021728009 0.0051737134 0.1474460000 358474268 0 1783500800 -0.0536859967 -0.0172485653 -0.0595368408 917 1311867201.0000619888 0.1563282460 0.1557594333 0.2021728009 0.0051714616 0.1481580000 358476002 0 1784008704 -0.0558980852 -0.0180055387 -0.0590103269 918 1311867201.0321929455 0.1563469768 0.1557600733 0.2021728009 0.0051688725 0.1437350000 358477800 0 1784627200 -0.0573757701 -0.0170833115 -0.0595449395 919 1311867201.0679559708 0.1564912945 0.1557608690 0.2021728009 0.0051666414 0.1348650000 358479630 0 1785167872 -0.0590997413 -0.0179325752 -0.0589492582 920 1311867201.1002171040 0.1561975479 0.1557613436 0.2021728009 0.0051672708 0.1589930000 358481396 0 1783160832 -0.0601418763 -0.0175575707 -0.0596502982 921 1311867201.1322419643 0.1551078707 0.1557606341 0.2021728009 0.0051644832 0.1553320000 358483162 0 1782140928 -0.0599788316 -0.0172894392 -0.0600509867 922 1311867201.1681909561 0.1557780206 0.1557606530 0.2021728009 0.0051617349 0.1404570000 358484960 0 1782358016 -0.0618098825 -0.0174445715 -0.0593023710 923 1311867201.2001469135 0.1561006904 0.1557610214 0.2021728009 0.0051589414 0.1507540000 358486726 0 1782902784 -0.0636489838 -0.0178872962 -0.0594569109 924 1311867201.2320559025 0.1555984467 0.1557608454 0.2021728009 0.0051605056 0.1518310000 358488428 0 1783500800 -0.0646145120 -0.0170640666 -0.0600265004 925 1311867201.2694900036 0.1550126374 0.1557600365 0.2021728009 0.0051578004 0.1447210000 358490322 0 1784119296 -0.0656083897 -0.0166101549 -0.0601415150 926 1311867201.2998940945 0.1554658860 0.1557597189 0.2021728009 0.0051581505 0.1624540000 358492088 0 1784627200 -0.0674622357 -0.0176556706 -0.0591459088 927 1311867201.3322761059 0.1563312113 0.1557603354 0.2021728009 0.0051561455 0.1475600000 358493822 0 1785167872 -0.0703190416 -0.0163128432 -0.0597586781 928 1311867201.3682329655 0.1551314890 0.1557596577 0.2021728009 0.0051562182 0.1655370000 358495652 0 1785769984 -0.0716468617 -0.0144723477 -0.0610461049 929 1311867201.4002270699 0.1561402082 0.1557600674 0.2021728009 0.0051628303 0.1650560000 358497386 0 1783500800 -0.0746971294 -0.0158743244 -0.0589462370 930 1311867201.4327609539 0.1555590481 0.1557598512 0.2021728009 0.0051608332 0.1531770000 358499152 0 1783283712 -0.0768003389 -0.0145419026 -0.0596113913 931 1311867201.4680800438 0.1544252038 0.1557584177 0.2021728009 0.0051591170 0.1467870000 358500886 0 1782759424 -0.0782407597 -0.0120771211 -0.0604476444 932 1311867201.5000870228 0.1545856446 0.1557571593 0.2021728009 0.0051586285 0.1716820000 358502652 0 1783267328 -0.0811027810 -0.0128146783 -0.0596258752 933 1311867201.5321950912 0.1549324840 0.1557562754 0.2021728009 0.0051569332 0.1566620000 358504418 0 1783754752 -0.0835261494 -0.0121088577 -0.0585295483 934 1311867201.5681428909 0.1537655592 0.1557541440 0.2021728009 0.0051544635 0.1548060000 358506248 0 1784373248 -0.0851481706 -0.0117679406 -0.0589483008 935 1311867201.6001029015 0.1537811011 0.1557520338 0.2021728009 0.0051533833 0.1546120000 358507982 0 1784881152 -0.0870438144 -0.0113592967 -0.0587938689 936 1311867201.6320679188 0.1537487507 0.1557498936 0.2021728009 0.0051509502 0.1587730000 358509748 0 1785421824 -0.0890166834 -0.0113154948 -0.0584189519 937 1311867201.6680500507 0.1529822648 0.1557469399 0.2021728009 0.0051562004 0.1504810000 358511610 0 1783627776 -0.0906829089 -0.0110929767 -0.0588590056 938 1311867201.7002921104 0.1522533447 0.1557432154 0.2021728009 0.0051537991 0.1541340000 358513408 0 1783410688 -0.0915226117 -0.0090743182 -0.0596462339 939 1311867201.7321999073 0.1531672180 0.1557404720 0.2021728009 0.0051549370 0.1577080000 358515142 0 1782902784 -0.0937803835 -0.0094807036 -0.0587080270 940 1311867201.7682011127 0.1524864286 0.1557370103 0.2021728009 0.0051658974 0.1525170000 358516972 0 1783373824 -0.0952668488 -0.0093254559 -0.0585140400 941 1311867201.8002099991 0.1517898887 0.1557328157 0.2021728009 0.0051642562 0.1544830000 358518770 0 1783881728 -0.0966298878 -0.0069257207 -0.0599350818 942 1311867201.8321559429 0.1519023329 0.1557287493 0.2021728009 0.0051640804 0.1538980000 358520504 0 1784500224 -0.0976428911 -0.0068817353 -0.0587601438 943 1311867201.8682188988 0.1518117636 0.1557245956 0.2021728009 0.0051692528 0.1571770000 358522334 0 1785008128 -0.0987305567 -0.0076866588 -0.0582635365 944 1311867201.9000771046 0.1519176960 0.1557205628 0.2021728009 0.0051678121 0.1531750000 358524036 0 1785516032 -0.0998510048 -0.0054397280 -0.0593348481 945 1311867201.9322619438 0.1516533494 0.1557162589 0.2021728009 0.0051651345 0.1495610000 358525834 0 1783545856 -0.1002412289 -0.0052403845 -0.0588779524 946 1311867201.9681720734 0.1506740898 0.1557109289 0.2021728009 0.0051634637 0.1644680000 358527664 0 1782759424 -0.1009270325 -0.0068126689 -0.0594808459 947 1311867202.0001900196 0.1513643861 0.1557063391 0.2021728009 0.0051688180 0.1532970000 358529398 0 1783029760 -0.1022972167 -0.0056025391 -0.0598371029 948 1311867202.0322389603 0.1505170166 0.1557008652 0.2021728009 0.0051739723 0.1689490000 358531196 0 1783500800 -0.1025520414 -0.0056575700 -0.0606393367 949 1311867202.0681519508 0.1505705565 0.1556954591 0.2021728009 0.0051714276 0.1493060000 358533026 0 1784008704 -0.1030058637 -0.0054518874 -0.0605035126 950 1311867202.1003150940 0.1508389860 0.1556903471 0.2021728009 0.0051753447 0.1615990000 358534760 0 1784627200 -0.1048688367 -0.0054647746 -0.0610351637 951 1311867202.1324090958 0.1506243050 0.1556850200 0.2021728009 0.0051779335 0.1537350000 358536558 0 1785135104 -0.1058069840 -0.0039696465 -0.0616995282 952 1311867202.1682789326 0.1501196921 0.1556791741 0.2021728009 0.0051768259 0.1531500000 358538388 0 1783144448 -0.1062409580 -0.0036254269 -0.0612956956 953 1311867202.2001249790 0.1507928669 0.1556740468 0.2021728009 0.0051741619 0.1476260000 358540186 0 1782378496 -0.1077903956 -0.0038437501 -0.0605556853 954 1311867202.2323749065 0.1503592879 0.1556684757 0.2021728009 0.0051714870 0.1455220000 358541888 0 1782124544 -0.1085458323 -0.0026846745 -0.0609930009 955 1311867202.2681009769 0.1485395283 0.1556610109 0.2021728009 0.0051735355 0.1568490000 358543718 0 1782628352 -0.1085214317 -0.0015817222 -0.0621729009 956 1311867202.3001070023 0.1497507244 0.1556548286 0.2021728009 0.0051740369 0.1608150000 358545452 0 1783263232 -0.1098786741 -0.0030687256 -0.0594035164 957 1311867202.3323650360 0.1495698690 0.1556484702 0.2021728009 0.0051714563 0.1525730000 358547218 0 1784119296 -0.1116145626 -0.0029783875 -0.0601915903 958 1311867202.3683099747 0.1494736969 0.1556420247 0.2021728009 0.0051693621 0.1516670000 358549048 0 1784627200 -0.1131927073 -0.0014467097 -0.0606121048 959 1311867202.4002919197 0.1490631998 0.1556351646 0.2021728009 0.0051674921 0.1588300000 358550814 0 1785135104 -0.1132710800 -0.0015690966 -0.0597560555 960 1311867202.4321858883 0.1489278674 0.1556281779 0.2021728009 0.0051658069 0.1556930000 358552548 0 1785643008 -0.1138147116 -0.0024686176 -0.0591941401 961 1311867202.4681179523 0.1479810923 0.1556202204 0.2021728009 0.0051634962 0.1826490000 358554410 0 1784172544 -0.1146233082 -0.0015944571 -0.0610746369 962 1311867202.5002439022 0.1485980600 0.1556129209 0.2021728009 0.0051610557 0.1782130000 358556144 0 1781006336 -0.1154297814 -0.0018601244 -0.0600497797 963 1311867202.5322799683 0.1496641487 0.1556067436 0.2021728009 0.0051658655 0.1569880000 358557942 0 1781465088 -0.1173766404 -0.0012197862 -0.0594946370 964 1311867202.5681829453 0.1486400217 0.1555995167 0.2021728009 0.0051845967 0.1563420000 358559772 0 1782136832 -0.1170633957 -0.0013226059 -0.0598341003 965 1311867202.6002409458 0.1479244381 0.1555915632 0.2021728009 0.0051828177 0.1526820000 358561538 0 1782607872 -0.1172408089 -0.0022842684 -0.0602792576 966 1311867202.6324090958 0.1507442296 0.1555865453 0.2021728009 0.0051950357 0.1550020000 358563304 0 1783115776 -0.1209401786 -0.0008587731 -0.0596154965 967 1311867202.6682538986 0.1501093060 0.1555808811 0.2021728009 0.0052031176 0.1501390000 358565134 0 1783771136 -0.1228360608 -0.0011560069 -0.0613062792 968 1311867202.7002909184 0.1506255716 0.1555757620 0.2021728009 0.0052011998 0.1505560000 358566868 0 1784373248 -0.1233267859 -0.0010434798 -0.0602061078 969 1311867202.7322840691 0.1501910090 0.1555702050 0.2021728009 0.0051990356 0.1496400000 358568666 0 1784881152 -0.1244667172 -0.0032259831 -0.0606673956 970 1311867202.7681059837 0.1491242498 0.1555635597 0.2021728009 0.0051966192 0.1547000000 358570496 0 1785389056 -0.1249754876 -0.0014861013 -0.0630280897 971 1311867202.8002150059 0.1504838914 0.1555583283 0.2021728009 0.0051946412 0.1549940000 358572294 0 1783119872 -0.1274333298 -0.0021891280 -0.0627118424 972 1311867202.8323709965 0.1509898454 0.1555536282 0.2021728009 0.0051934993 0.1673050000 358574028 0 1783410688 -0.1295071244 -0.0027975640 -0.0628153011 973 1311867202.8681859970 0.1501133889 0.1555480370 0.2021728009 0.0051911568 0.1471260000 358575858 0 1783029760 -0.1303779930 -0.0013814539 -0.0646076277 974 1311867202.9003429413 0.1491370201 0.1555414548 0.2021728009 0.0051886798 0.1489280000 358577592 0 1783664640 -0.1301350594 0.0002068533 -0.0656516030 975 1311867202.9321599007 0.1491057575 0.1555348541 0.2021728009 0.0051947482 0.1545660000 358579358 0 1784172544 -0.1300894618 -0.0009202340 -0.0649994165 976 1311867202.9681980610 0.1488555968 0.1555280106 0.2021728009 0.0051922771 0.1494850000 358581220 0 1784754176 -0.1304664761 -0.0008594436 -0.0653611347 977 1311867203.0002338886 0.1482057869 0.1555205160 0.2021728009 0.0051934808 0.1562290000 358582986 0 1785262080 -0.1307651103 0.0004845380 -0.0663224086 978 1311867203.0322840214 0.1479720920 0.1555127978 0.2021728009 0.0051922573 0.1597700000 358584752 0 1783144448 -0.1296768636 -0.0013980214 -0.0644047558 979 1311867203.0681869984 0.1476035118 0.1555047189 0.2021728009 0.0051899310 0.1577330000 358586550 0 1783742464 -0.1286000013 -0.0014277099 -0.0645806417 980 1311867203.1003499031 0.1482270956 0.1554972927 0.2021728009 0.0052003024 0.1543040000 358588316 0 1784258560 -0.1277626455 -0.0017026257 -0.0645181239 981 1311867203.1324429512 0.1488153487 0.1554904814 0.2021728009 0.0052176775 0.1600710000 358590050 0 1784651776 -0.1277526915 -0.0039022726 -0.0630355477 982 1311867203.1682100296 0.1485490650 0.1554834127 0.2021728009 0.0052164273 0.1616970000 358591880 0 1785253888 -0.1263051331 -0.0053396355 -0.0630593821 983 1311867203.2002859116 0.1494165510 0.1554772409 0.2021728009 0.0052481579 0.1563890000 358593678 0 1785761792 -0.1274832487 -0.0049685012 -0.0649541020 984 1311867203.2322111130 0.1506009549 0.1554722853 0.2021728009 0.0052458719 0.1571640000 358595412 0 1783660544 -0.1272310764 -0.0049481741 -0.0640683174 985 1311867203.2681829929 0.1505288184 0.1554672666 0.2021728009 0.0052444649 0.1739330000 358597242 0 1780994048 -0.1267531365 -0.0072270334 -0.0638599396 986 1311867203.3002059460 0.1516036242 0.1554633481 0.2021728009 0.0052445284 0.1567400000 358599040 0 1781485568 -0.1279912889 -0.0065288828 -0.0650027916 987 1311867203.3322260380 0.1509737670 0.1554587994 0.2021728009 0.0052419693 0.1576000000 358600774 0 1782145024 -0.1270368546 -0.0063637039 -0.0661426783 988 1311867203.3681290150 0.1512221992 0.1554545113 0.2021728009 0.0052398954 0.1525220000 358602604 0 1782611968 -0.1267287433 -0.0063884701 -0.0660123974 989 1311867203.4001998901 0.1525927484 0.1554516177 0.2021728009 0.0052376331 0.1703600000 358604402 0 1783119872 -0.1272437423 -0.0105413003 -0.0630340874 990 1311867203.4322550297 0.1523024887 0.1554484368 0.2021728009 0.0052361702 0.1552430000 358606136 0 1783738368 -0.1267073303 -0.0108522521 -0.0643241778 991 1311867203.4682049751 0.1517688185 0.1554447238 0.2021728009 0.0052347874 0.1663740000 358607966 0 1784279040 -0.1262887418 -0.0111889243 -0.0653950498 992 1311867203.5004940033 0.1524228156 0.1554416775 0.2021728009 0.0052331926 0.1691510000 358609764 0 1784881152 -0.1266408414 -0.0142373322 -0.0641505122 993 1311867203.5322470665 0.1529283226 0.1554391464 0.2021728009 0.0052311243 0.1408520000 358611498 0 1785389056 -0.1269315630 -0.0160361305 -0.0647553653 994 1311867203.5682868958 0.1522967368 0.1554359850 0.2021728009 0.0052287493 0.1639770000 358613360 0 1783398400 -0.1265292168 -0.0168171134 -0.0665442571 995 1311867203.6002469063 0.1526903957 0.1554332256 0.2021728009 0.0052262378 0.1838720000 358615126 0 1782902784 -0.1265808344 -0.0183049999 -0.0662888438 996 1311867203.6323809624 0.1532278806 0.1554310114 0.2021728009 0.0052238285 0.1836680000 358616860 0 1783537664 -0.1271792650 -0.0211319402 -0.0660285875 997 1311867203.6683659554 0.1530624628 0.1554286358 0.2021728009 0.0052262946 0.1828990000 358618722 0 1784045568 -0.1269864142 -0.0222582035 -0.0668323189 998 1311867203.7004671097 0.1526768357 0.1554258785 0.2021728009 0.0052312261 0.1798270000 358620424 0 1784659968 -0.1264665723 -0.0241995286 -0.0672418401 999 1311867203.7322630882 0.1526096314 0.1554230594 0.2021728009 0.0052286409 0.1653740000 358622222 0 1785167872 -0.1258561611 -0.0247724652 -0.0678248107 1000 1311867203.7681419849 0.1535867304 0.1554212231 0.2021728009 0.0052261168 0.1890390000 358624052 0 1782996992 -0.1265689582 -0.0264230538 -0.0677202716 1001 1311867203.8001880646 0.1533572376 0.1554191611 0.2021728009 0.0052235156 0.1619380000 358625786 0 1782763520 -0.1261630207 -0.0274519138 -0.0682746470 1002 1311867203.8324379921 0.1531448811 0.1554168914 0.2021728009 0.0052211249 0.1874070000 358627584 0 1782276096 -0.1256208867 -0.0285892729 -0.0688126534 1003 1311867203.8681540489 0.1543434113 0.1554158211 0.2021728009 0.0052185918 0.1864320000 358629414 0 1782743040 -0.1264542341 -0.0300526787 -0.0684661642 1004 1311867203.9002060890 0.1547578424 0.1554151658 0.2021728009 0.0052160324 0.1667850000 358631180 0 1783267328 -0.1273643523 -0.0316497907 -0.0694263652 1005 1311867203.9324600697 0.1548368037 0.1554145903 0.2021728009 0.0052136924 0.1691950000 358632946 0 1783738368 -0.1270459592 -0.0307980180 -0.0706797242 1006 1311867203.9682869911 0.1551084816 0.1554142860 0.2021728009 0.0052126239 0.1648970000 358634776 0 1784246272 -0.1275040060 -0.0329615884 -0.0710579306 1007 1311867204.0003368855 0.1552046239 0.1554140778 0.2021728009 0.0052102069 0.1684930000 358636542 0 1784754176 -0.1274073720 -0.0333618633 -0.0721717402 1008 1311867204.0323688984 0.1559142917 0.1554145740 0.2021728009 0.0052085690 0.1699540000 358638308 0 1785294848 -0.1279146224 -0.0340540297 -0.0729793385 1009 1311867204.0682060719 0.1560336500 0.1554151876 0.2021728009 0.0052080349 0.1658730000 358640106 0 1783664640 -0.1283934414 -0.0361078307 -0.0737188980 1010 1311867204.1003429890 0.1557158232 0.1554154853 0.2021728009 0.0052055811 0.1762090000 358641872 0 1780736000 -0.1280703694 -0.0374632627 -0.0747571215 1011 1311867204.1322948933 0.1554763019 0.1554155454 0.2021728009 0.0052032940 0.1672280000 358643606 0 1781362688 -0.1275873780 -0.0388031080 -0.0758941919 1012 1311867204.1682620049 0.1559968293 0.1554161198 0.2021728009 0.0052011945 0.1657010000 358645436 0 1781870592 -0.1285443455 -0.0410053991 -0.0762914196 1013 1311867204.2003049850 0.1565168649 0.1554172064 0.2021728009 0.0051990140 1.1173210000 370956346 0 1785430016 -0.1289645582 -0.0413335226 -0.0771419182 1014 1311867204.2324359417 0.1598155648 0.1554215441 0.2021728009 0.0051985119 0.1051950000 374615992 0 1786195968 -0.1383086741 -0.0445195138 -0.0825019926 1015 1311867204.2681810856 0.1604328156 0.1554264813 0.2021728009 0.0051961138 0.2176320000 377809918 0 1783406592 -0.1387572736 -0.0470167585 -0.0824625865 1016 1311867204.3003020287 0.1605013609 0.1554314762 0.2021728009 0.0051935650 0.1691250000 377811652 0 1784143872 -0.1390488297 -0.0483567044 -0.0831653625 1017 1311867204.3325190544 0.1608489901 0.1554368032 0.2021728009 0.0051915399 0.1510080000 377813450 0 1784905728 -0.1388293952 -0.0481789559 -0.0837308243 1018 1311867204.3683750629 0.1611658186 0.1554424309 0.2021728009 0.0051891082 0.1581740000 377815280 0 1785430016 -0.1395234466 -0.0504117124 -0.0839536414 1019 1311867204.4002819061 0.1614975780 0.1554483731 0.2021728009 0.0051866455 0.1591040000 377817046 0 1783156736 -0.1398221999 -0.0513556600 -0.0841944292 1020 1311867204.4324340820 0.1613618881 0.1554541707 0.2021728009 0.0051842162 0.1543290000 377818812 0 1782857728 -0.1394715160 -0.0516955741 -0.0850386173 1021 1311867204.4682960510 0.1615700871 0.1554601608 0.2021728009 0.0051817689 0.1514070000 377820642 0 1782476800 -0.1395952851 -0.0533443801 -0.0850737095 1022 1311867204.5002770424 0.1618500799 0.1554664132 0.2021728009 0.0051792327 0.1406030000 377822376 0 1783128064 -0.1402672380 -0.0550451092 -0.0856128559 1023 1311867204.5324790478 0.1619976014 0.1554727975 0.2021728009 0.0051769855 0.1417860000 377824174 0 1783615488 -0.1399190277 -0.0550718606 -0.0859750658 1024 1311867204.5682110786 0.1629006714 0.1554800513 0.2021728009 0.0051753926 0.1665580000 377826004 0 1784365056 -0.1410826296 -0.0565681085 -0.0858745649 1025 1311867204.6002640724 0.1626208872 0.1554870180 0.2021728009 0.0051728683 0.1430680000 377913754 0 1784872960 -0.1410910189 -0.0576005168 -0.0862383768 1026 1311867204.6324179173 0.1621265560 0.1554934893 0.2021728009 0.0051710364 0.1441810000 378083488 0 1785651200 -0.1412542909 -0.0589869954 -0.0860940814 1027 1311867204.6684520245 0.1623996049 0.1555002138 0.2021728009 0.0051690488 0.1724180000 378085318 0 1783644160 -0.1417203695 -0.0603253692 -0.0861753151 1028 1311867204.7002611160 0.1621704698 0.1555067024 0.2021728009 0.0051669998 0.1437660000 378087116 0 1783263232 -0.1411491334 -0.0605142415 -0.0863387808 1029 1311867204.7322928905 0.1620953232 0.1555131053 0.2021728009 0.0051646313 0.1447790000 378088850 0 1782755328 -0.1415210366 -0.0618488602 -0.0861059129 1030 1311867204.7683119774 0.1631748676 0.1555205439 0.2021728009 0.0051623002 0.1483780000 378090680 0 1783242752 -0.1433427632 -0.0634373575 -0.0849089026 1031 1311867204.8004341125 0.1631619185 0.1555279556 0.2021728009 0.0051602304 0.1503280000 378092414 0 1783894016 -0.1439255476 -0.0635922775 -0.0843826309 1032 1311867204.8324959278 0.1616113037 0.1555338503 0.2021728009 0.0051578912 0.1459240000 378094212 0 1784365056 -0.1428815275 -0.0644835904 -0.0840596110 1033 1311867204.8682460785 0.1615951806 0.1555397180 0.2021728009 0.0051561547 0.1551390000 378096042 0 1784889344 -0.1440441757 -0.0673635453 -0.0826429129 1034 1311867204.9002239704 0.1624533832 0.1555464043 0.2021728009 0.0051547401 0.1470540000 378097776 0 1785413632 -0.1453755051 -0.0687062591 -0.0816348493 1035 1311867204.9363629818 0.1618899554 0.1555525333 0.2021728009 0.0051541429 0.1490470000 378099606 0 1783762944 -0.1450188011 -0.0693716034 -0.0813362077 1036 1311867204.9682190418 0.1613476425 0.1555581271 0.2021728009 0.0051518336 0.1796090000 378101404 0 1781862400 -0.1449357420 -0.0717300028 -0.0805305317 1037 1311867205.0003349781 0.1611018628 0.1555634730 0.2021728009 0.0051493858 0.1647000000 378103202 0 1782370304 -0.1453855187 -0.0738887563 -0.0801322237 1038 1311867205.0363259315 0.1615633518 0.1555692532 0.2021728009 0.0051484410 0.1576970000 378104968 0 1782857728 -0.1451962590 -0.0736840442 -0.0801410526 1039 1311867205.0686368942 0.1613070667 0.1555747757 0.2021728009 0.0051585072 0.1726630000 378106798 0 1783365632 -0.1455437690 -0.0751284733 -0.0794675872 1040 1311867205.1007649899 0.1613682956 0.1555803464 0.2021728009 0.0051723185 0.1675660000 378108468 0 1784016896 -0.1455236673 -0.0770009160 -0.0788962916 1041 1311867205.1363010406 0.1616124660 0.1555861409 0.2021728009 0.0051712510 0.1632030000 378110298 0 1784619008 -0.1454790384 -0.0778546482 -0.0783168077 1042 1311867205.1682898998 0.1622912884 0.1555925758 0.2021728009 0.0051688301 0.1711330000 378112064 0 1785159680 -0.1455878615 -0.0794663727 -0.0777799860 1043 1311867205.2003710270 0.1616434455 0.1555983772 0.2021728009 0.0051673169 0.1806380000 378113830 0 1783160832 -0.1450201571 -0.0816445053 -0.0773089603 1044 1311867205.2364439964 0.1615312696 0.1556040601 0.2021728009 0.0051668547 0.1557050000 378115628 0 1782636544 -0.1448790133 -0.0829201713 -0.0766528919 1045 1311867205.2683920860 0.1614621282 0.1556096659 0.2021728009 0.0051693164 0.1783760000 378117426 0 1781489664 -0.1449227035 -0.0844413862 -0.0762348697 1046 1311867205.3004579544 0.1616074443 0.1556153999 0.2021728009 0.0051679551 0.1817210000 378119192 0 1781977088 -0.1452987492 -0.0862927660 -0.0756397247 1047 1311867205.3362879753 0.1615770459 0.1556210939 0.2021728009 0.0051657611 0.1738480000 378121022 0 1782611968 -0.1452237517 -0.0874827281 -0.0752180070 1048 1311867205.3684389591 0.1615741402 0.1556267743 0.2021728009 0.0051686356 0.1803690000 378122788 0 1783119872 -0.1455848217 -0.0889271721 -0.0745571479 1049 1311867205.4004759789 0.1618818343 0.1556327372 0.2021728009 0.0051794593 0.1776540000 378124522 0 1783738368 -0.1466048807 -0.0905680209 -0.0738274157 1050 1311867205.4362900257 0.1613551080 0.1556381870 0.2021728009 0.0051803835 0.1764900000 378126384 0 1784279040 -0.1466712803 -0.0917417184 -0.0736538768 1051 1311867205.4683609009 0.1613222510 0.1556435953 0.2021728009 0.0051817551 0.1695420000 378128150 0 1784881152 -0.1469032615 -0.0925781205 -0.0730163231 1052 1311867205.5002589226 0.1607413590 0.1556484411 0.2021728009 0.0051912848 0.1807390000 378129884 0 1785389056 -0.1480451226 -0.0949550495 -0.0718458518 1053 1311867205.5362849236 0.1606393903 0.1556531808 0.2021728009 0.0051923474 0.1799920000 378131746 0 1783398400 -0.1486431211 -0.0954114050 -0.0714619905 1054 1311867205.5683689117 0.1613868624 0.1556586207 0.2021728009 0.0052022681 0.2132310000 378133512 0 1782910976 -0.1500078887 -0.0956286415 -0.0700496882 1055 1311867205.6003179550 0.1605180651 0.1556632268 0.2021728009 0.0052062071 0.1932290000 378135278 0 1783361536 -0.1509066373 -0.0979733840 -0.0692652240 1056 1311867205.6363780499 0.1595809758 0.1556669368 0.2021728009 0.0052042876 0.1688080000 378137108 0 1783902208 -0.1506365240 -0.0987531170 -0.0690700486 1057 1311867205.6686398983 0.1592419893 0.1556703191 0.2021728009 0.0052023303 0.1988640000 378138906 0 1784373248 -0.1513115168 -0.1007521302 -0.0681328326 1058 1311867205.7002930641 0.1596166641 0.1556740491 0.2021728009 0.0052002624 0.1865960000 378140672 0 1784881152 -0.1523844004 -0.1029741988 -0.0671009570 1059 1311867205.7364819050 0.1598275602 0.1556779712 0.2021728009 0.0051981710 0.1649350000 378142470 0 1785516032 -0.1538629085 -0.1054269001 -0.0666989088 1060 1311867205.7683310509 0.1598275751 0.1556818859 0.2021728009 0.0051971056 0.1892390000 378144236 0 1783418880 -0.1539374441 -0.1052556708 -0.0670660138 1061 1311867205.8002939224 0.1590780318 0.1556850868 0.2021728009 0.0051970394 0.1888620000 378146034 0 1782505472 -0.1540761590 -0.1077008322 -0.0664559677 1062 1311867205.8363699913 0.1598791927 0.1556890361 0.2021728009 0.0051947794 0.1927240000 378147832 0 1783140352 -0.1556600928 -0.1095118821 -0.0657738149 1063 1311867205.8685131073 0.1599146575 0.1556930113 0.2021728009 0.0051951017 0.1792940000 378149630 0 1783664640 -0.1564646810 -0.1101945043 -0.0658823103 1064 1311867205.9003169537 0.1595394909 0.1556966264 0.2021728009 0.0051954312 0.1785590000 378151396 0 1784164352 -0.1568879485 -0.1117279530 -0.0657732785 1065 1311867205.9363129139 0.1595457345 0.1557002406 0.2021728009 0.0052040456 0.1832460000 378153194 0 1784745984 -0.1573734730 -0.1134165600 -0.0651536584 1066 1311867205.9685149193 0.1601407528 0.1557044061 0.2021728009 0.0052016809 0.1858880000 378154992 0 1785253888 -0.1584442407 -0.1146220267 -0.0649064928 1067 1311867206.0006539822 0.1609311551 0.1557093047 0.2021728009 0.0052157543 0.2072480000 378156726 0 1785761792 -0.1590474695 -0.1136407107 -0.0651958808 1068 1311867206.0367360115 0.1605657041 0.1557138519 0.2021728009 0.0052176252 0.2256170000 378158556 0 1783771136 -0.1596755981 -0.1162676364 -0.0644682944 1069 1311867206.0684130192 0.1594623327 0.1557173584 0.2021728009 0.0052153235 0.1937080000 378160290 0 1783291904 -0.1592251807 -0.1192169935 -0.0644852668 1070 1311867206.1004180908 0.1599525511 0.1557213165 0.2021728009 0.0052133428 0.1817580000 378162088 0 1783758848 -0.1591952592 -0.1195077300 -0.0643826798 1071 1311867206.1364219189 0.1601309627 0.1557254339 0.2021728009 0.0052136682 0.1875140000 378163886 0 1784283136 -0.1596197635 -0.1217697561 -0.0641041696 1072 1311867206.1682798862 0.1605998725 0.1557299809 0.2021728009 0.0052117898 0.1877520000 378165652 0 1784754176 -0.1604897082 -0.1244603023 -0.0638948828 1073 1311867206.2004311085 0.1609013975 0.1557348005 0.2021728009 0.0052153181 0.1996870000 378167418 0 1785294848 -0.1609787345 -0.1250999421 -0.0646535829 1074 1311867206.2363541126 0.1610958129 0.1557397921 0.2021728009 0.0052236811 0.2109180000 378169248 0 1783160832 -0.1608145982 -0.1256829053 -0.0648846626 1075 1311867206.2685620785 0.1611348689 0.1557448108 0.2021728009 0.0052256883 0.2111460000 378171014 0 1783631872 -0.1614952832 -0.1280866861 -0.0648426265 1076 1311867206.3004291058 0.1612268686 0.1557499056 0.2021728009 0.0052239905 0.2107750000 378172812 0 1784135680 -0.1616922319 -0.1289617717 -0.0652488694 1077 1311867206.3366179466 0.1619596183 0.1557556714 0.2021728009 0.0052255147 0.2122280000 378174610 0 1784627200 -0.1626415551 -0.1299823523 -0.0652514100 1078 1311867206.3684759140 0.1612651795 0.1557607823 0.2021728009 0.0052261258 0.2120320000 378176376 0 1785167872 -0.1626341045 -0.1319578290 -0.0653698668 1079 1311867206.4004108906 0.1610385776 0.1557656736 0.2021728009 0.0052245476 0.1859530000 378178142 0 1783410688 -0.1620658636 -0.1331547946 -0.0654942244 1080 1311867206.4365398884 0.1614532620 0.1557709399 0.2021728009 0.0052229445 0.1892660000 378179940 0 1779867648 -0.1625157446 -0.1344561875 -0.0654803887 1081 1311867206.4684751034 0.1613067836 0.1557760610 0.2021728009 0.0052211357 0.1808830000 378181738 0 1780486144 -0.1628356874 -0.1365400106 -0.0654162988 1082 1311867206.5005669594 0.1622463912 0.1557820409 0.2021728009 0.0052204488 0.2246530000 378183504 0 1780985856 -0.1640957147 -0.1384200752 -0.0651140139 1083 1311867206.5365779400 0.1618317813 0.1557876270 0.2021728009 0.0052184721 0.2247470000 378185334 0 1781510144 -0.1638237387 -0.1401892751 -0.0653167367 1084 1311867206.5683178902 0.1619115174 0.1557932764 0.2021728009 0.0052177195 0.1870130000 378187100 0 1781997568 -0.1633633822 -0.1415990144 -0.0653949156 1085 1311867206.6004528999 0.1621791273 0.1557991619 0.2021728009 0.0052154152 0.2101730000 378188834 0 1782505472 -0.1641014814 -0.1436316222 -0.0656800717 1086 1311867206.6364800930 0.1629504561 0.1558057469 0.2021728009 0.0052216480 0.2338920000 378190664 0 1783009280 -0.1644639522 -0.1447796822 -0.0657941476 1087 1311867206.6685130596 0.1624790281 0.1558118861 0.2021728009 0.0052214807 0.2046770000 378192430 0 1783611392 -0.1638113260 -0.1458618492 -0.0661894381 1088 1311867206.7005600929 0.1624848992 0.1558180194 0.2021728009 0.0052197566 0.2035040000 378194196 0 1784119296 -0.1638708264 -0.1472574621 -0.0662849173 1089 1311867206.7363760471 0.1626666486 0.1558243083 0.2021728009 0.0052190471 0.2002970000 378196026 0 1784627200 -0.1637011319 -0.1492342353 -0.0662664622 1090 1311867206.7683479786 0.1635827422 0.1558314261 0.2021728009 0.0052233303 0.2157920000 378197792 0 1785135104 -0.1645361632 -0.1495104134 -0.0668906942 1091 1311867206.8005199432 0.1637099385 0.1558386475 0.2021728009 0.0052243926 0.2333870000 378199558 0 1783021568 -0.1653488129 -0.1514538825 -0.0670422316 1092 1311867206.8364160061 0.1630905420 0.1558452884 0.2021728009 0.0052229071 0.2069360000 378201388 0 1782505472 -0.1649996340 -0.1533845365 -0.0677024126 1093 1311867206.8685629368 0.1631893516 0.1558520076 0.2021728009 0.0052255982 0.2017550000 378203186 0 1782992896 -0.1646155417 -0.1538590193 -0.0684277266 1094 1311867206.9005689621 0.1637316942 0.1558592103 0.2021728009 0.0052232921 0.2008050000 378204920 0 1783500800 -0.1652542651 -0.1551873982 -0.0687199831 1095 1311867206.9364409447 0.1641367525 0.1558667697 0.2021728009 0.0052278986 0.1957900000 378206782 0 1784119296 -0.1660351902 -0.1581757069 -0.0689508915 1096 1311867206.9686069489 0.1644896716 0.1558746373 0.2021728009 0.0052285871 0.1929550000 378208548 0 1784659968 -0.1656542420 -0.1595334709 -0.0692321584 1097 1311867207.0006439686 0.1644973159 0.1558824975 0.2021728009 0.0052384025 0.2068170000 378210314 0 1785262080 -0.1657772660 -0.1608034819 -0.0699775070 1098 1311867207.0365860462 0.1652686447 0.1558910459 0.2021728009 0.0052411691 0.2060550000 378212144 0 1785769984 -0.1656514108 -0.1627081335 -0.0700002909 1099 1311867207.0684070587 0.1651455611 0.1558994668 0.2021728009 0.0052439167 0.2169420000 378213910 0 1783799808 -0.1659788936 -0.1649779230 -0.0702962950 1100 1311867207.1005458832 0.1645717770 0.1559073507 0.2021728009 0.0052477815 0.1970760000 378215644 0 1783160832 -0.1638616323 -0.1649360806 -0.0710195154 1101 1311867207.1364729404 0.1657252461 0.1559162679 0.2021728009 0.0052657720 0.2019800000 378217442 0 1783648256 -0.1643669605 -0.1663955301 -0.0710960403 1102 1311867207.1687068939 0.1656220704 0.1559250754 0.2021728009 0.0052650229 0.2017630000 378219240 0 1784135680 -0.1646679938 -0.1688710302 -0.0710111931 1103 1311867207.2006540298 0.1657830626 0.1559340128 0.2021728009 0.0052631475 0.2017370000 378221006 0 1784659968 -0.1645958871 -0.1697974205 -0.0709288940 1104 1311867207.2365870476 0.1658974737 0.1559430377 0.2021728009 0.0052612430 0.1762280000 378222836 0 1785262080 -0.1646618396 -0.1711017191 -0.0708091110 1105 1311867207.2686169147 0.1659603268 0.1559521031 0.2021728009 0.0052593343 0.2024970000 378224602 0 1785769984 -0.1650582254 -0.1725868881 -0.0705874115 1106 1311867207.3004999161 0.1660086811 0.1559611958 0.2021728009 0.0052576929 0.2051990000 378226368 0 1783672832 -0.1653072089 -0.1743150353 -0.0700518861 1107 1311867207.3366520405 0.1662744135 0.1559705122 0.2021728009 0.0052596160 0.2018960000 378228166 0 1784123392 -0.1652003676 -0.1744810343 -0.0700658187 1108 1311867207.3685789108 0.1659210324 0.1559794928 0.2021728009 0.0052606383 0.1919210000 378229964 0 1784795136 -0.1653232425 -0.1757405847 -0.0695888400 1109 1311867207.4006979465 0.1658521146 0.1559883951 0.2021728009 0.0052588484 0.2032600000 378231762 0 1785040896 -0.1668323725 -0.1786824763 -0.0691495985 1110 1311867207.4365799427 0.1659973264 0.1559974121 0.2021728009 0.0052583972 0.2255700000 378233560 0 1785643008 -0.1673122346 -0.1790738553 -0.0689477772 1111 1311867207.4686470032 0.1660643667 0.1560064733 0.2021728009 0.0052564521 0.2042230000 378235326 0 1783267328 -0.1681679636 -0.1803822517 -0.0684699491 1112 1311867207.5006010532 0.1659741253 0.1560154370 0.2021728009 0.0052569276 0.2150160000 378237060 0 1782992896 -0.1693789810 -0.1830807179 -0.0680772588 1113 1311867207.5365080833 0.1643934995 0.1560229645 0.2021728009 0.0052586631 0.2011030000 378238890 0 1783517184 -0.1687364876 -0.1848080456 -0.0684810430 1114 1311867207.5687060356 0.1652376354 0.1560312362 0.2021728009 0.0052570448 0.2070950000 378240688 0 1784152064 -0.1700974107 -0.1861419380 -0.0676981509 1115 1311867207.6005868912 0.1655931771 0.1560398119 0.2021728009 0.0052553299 0.2022090000 378242454 0 1784754176 -0.1715750396 -0.1883899868 -0.0676022619 1116 1311867207.6364910603 0.1654111892 0.1560482092 0.2021728009 0.0052568717 0.2019170000 378244252 0 1785294848 -0.1720890403 -0.1892975122 -0.0680840835 1117 1311867207.6687729359 0.1656264067 0.1560567841 0.2021728009 0.0052588318 0.2028570000 378246050 0 1783271424 -0.1724961251 -0.1903938055 -0.0680444911 1118 1311867207.7005620003 0.1663612723 0.1560660010 0.2021728009 0.0052566319 0.2069580000 378247816 0 1782784000 -0.1741139442 -0.1925831586 -0.0675081760 1119 1311867207.7365009785 0.1661924869 0.1560750506 0.2021728009 0.0052567782 0.2110080000 378249614 0 1783250944 -0.1744686514 -0.1946690977 -0.0673680380 1120 1311867207.7686090469 0.1665237695 0.1560843798 0.2021728009 0.0052546145 0.1848890000 378251380 0 1783775232 -0.1746756583 -0.1951237768 -0.0677402616 1121 1311867207.8009910583 0.1671791822 0.1560942771 0.2021728009 0.0052526260 0.2252050000 378253114 0 1784152064 -0.1758764386 -0.1971296519 -0.0670567229 1122 1311867207.8365540504 0.1658511907 0.1561029731 0.2021728009 0.0052575363 0.1986810000 378254976 0 1784754176 -0.1747921258 -0.1993546039 -0.0674033761 1123 1311867207.8687729836 0.1662459224 0.1561120051 0.2021728009 0.0052651037 0.1928650000 378256742 0 1785262080 -0.1745109111 -0.2002849281 -0.0670531243 1124 1311867207.9008998871 0.1662787348 0.1561210502 0.2021728009 0.0052632964 0.1972410000 378258476 0 1785769984 -0.1748451293 -0.2022645622 -0.0670373663 1125 1311867207.9365339279 0.1661458313 0.1561299611 0.2021728009 0.0052647764 0.2180490000 378260306 0 1783398400 -0.1751114726 -0.2034959346 -0.0669244081 1126 1311867207.9684898853 0.1671205014 0.1561397218 0.2021728009 0.0052643502 0.1826050000 378262040 0 1784016896 -0.1751627773 -0.2027563900 -0.0670507923 1127 1311867208.0006649494 0.1670230925 0.1561493788 0.2021728009 0.0052775286 0.9809900000 390593170 0 1783402496 -0.1757162064 -0.2061377615 -0.0659418181 1128 1311867208.0367650986 0.1651972979 0.1561574000 0.2021728009 0.0052928808 0.1312890000 394252816 0 1783418880 -0.1741153747 -0.2085145861 -0.0662780553 1129 1311867208.0699250698 0.1651245803 0.1561653426 0.2021728009 0.0052914481 0.1073270000 397446678 0 1784033280 -0.1731981039 -0.2084493339 -0.0668380335 1130 1311867208.1011340618 0.1655617952 0.1561736580 0.2021728009 0.0052891474 0.2853920000 397448348 0 1783402496 -0.1742512733 -0.2105198503 -0.0662319288 1131 1311867208.1366329193 0.1662096530 0.1561825316 0.2021728009 0.0052873532 0.2490850000 397450178 0 1784160256 -0.1748996377 -0.2112080455 -0.0666152015 1132 1311867208.1686830521 0.1658951044 0.1561911116 0.2021728009 0.0052861318 0.2333380000 397451976 0 1784647680 -0.1748192310 -0.2125733495 -0.0668570325 1133 1311867208.2005209923 0.1657419354 0.1561995412 0.2021728009 0.0052896722 0.2098360000 397453710 0 1785008128 -0.1743745953 -0.2140117884 -0.0666633025 1134 1311867208.2365610600 0.1668055207 0.1562088940 0.2021728009 0.0052876234 0.2062700000 397455540 0 1785634816 -0.1756585240 -0.2152353972 -0.0668149889 1135 1311867208.2684400082 0.1662067026 0.1562177026 0.2021728009 0.0052863597 0.1983740000 397457306 0 1783402496 -0.1749515235 -0.2164978385 -0.0674366057 1136 1311867208.3005969524 0.1662755609 0.1562265564 0.2021728009 0.0052842795 0.2047740000 397459040 0 1783873536 -0.1746520847 -0.2172916085 -0.0676078498 1137 1311867208.3365280628 0.1667525321 0.1562358140 0.2021728009 0.0052869991 0.2149310000 397460870 0 1784414208 -0.1749047041 -0.2184520960 -0.0678856000 1138 1311867208.3685109615 0.1673521101 0.1562455823 0.2021728009 0.0052889882 0.1881280000 397462668 0 1784754176 -0.1752723008 -0.2190506756 -0.0678846911 1139 1311867208.4005920887 0.1674374342 0.1562554083 0.2021728009 0.0052867706 0.2268490000 397464434 0 1785262080 -0.1761624515 -0.2210531682 -0.0676412955 1140 1311867208.4364600182 0.1671843529 0.1562649951 0.2021728009 0.0052845492 0.2021860000 397466264 0 1783033856 -0.1757817715 -0.2227661908 -0.0677698702 1141 1311867208.4686639309 0.1669699997 0.1562743773 0.2021728009 0.0052842407 0.1976910000 397468030 0 1783652352 -0.1747785658 -0.2230665386 -0.0684272423 1142 1311867208.5005640984 0.1676537693 0.1562843417 0.2021728009 0.0052820829 0.2239650000 397469764 0 1784176640 -0.1758238673 -0.2246752828 -0.0676128268 1143 1311867208.5365219116 0.1682451218 0.1562948061 0.2021728009 0.0052809945 0.2013300000 397471594 0 1784406016 -0.1764806509 -0.2253449857 -0.0673661605 1144 1311867208.5686440468 0.1681027859 0.1563051277 0.2021728009 0.0052789771 0.1942090000 397473392 0 1785008128 -0.1764895320 -0.2258603424 -0.0672760829 1145 1311867208.6005949974 0.1678389311 0.1563152009 0.2021728009 0.0052768348 0.1998060000 397475158 0 1785516032 -0.1763351262 -0.2268962264 -0.0668649524 1146 1311867208.6364450455 0.1674481183 0.1563249155 0.2021728009 0.0052752012 0.2058760000 397476956 0 1783668736 -0.1767662764 -0.2282821834 -0.0661240071 1147 1311867208.6684880257 0.1676374972 0.1563347783 0.2021728009 0.0052736434 0.1870410000 397478754 0 1779691520 -0.1766516864 -0.2281889319 -0.0660988539 1148 1311867208.7006061077 0.1676950008 0.1563446739 0.2021728009 0.0052713697 0.1932980000 397480552 0 1780326400 -0.1773184240 -0.2292319983 -0.0653676763 1149 1311867208.7367100716 0.1676881164 0.1563545464 0.2021728009 0.0052697210 0.1796780000 397482350 0 1780875264 -0.1783204377 -0.2305827886 -0.0647967905 1150 1311867208.7688069344 0.1678937525 0.1563645805 0.2021728009 0.0052674810 0.1764120000 397484116 0 1781383168 -0.1785869598 -0.2302810550 -0.0645704493 1151 1311867208.8006410599 0.1667321324 0.1563735879 0.2021728009 0.0052659624 0.2012400000 397485850 0 1782018048 -0.1785938293 -0.2329690009 -0.0638808012 1152 1311867208.8368830681 0.1661177725 0.1563820464 0.2021728009 0.0052645660 0.2104440000 397487712 0 1782521856 -0.1783684194 -0.2338962257 -0.0638762489 1153 1311867208.8684909344 0.1679287702 0.1563920609 0.2021728009 0.0052677001 0.1804710000 397489478 0 1783103488 -0.1795065403 -0.2327991575 -0.0636046082 1154 1311867208.9008109570 0.1678028852 0.1564019490 0.2021728009 0.0052674193 0.1910050000 397491180 0 1783611392 -0.1807349026 -0.2344023138 -0.0631728694 1155 1311867208.9365160465 0.1670154333 0.1564111381 0.2021728009 0.0052672176 0.2016060000 397493010 0 1784152064 -0.1814989001 -0.2377282530 -0.0627252832 1156 1311867208.9687321186 0.1671103239 0.1564203935 0.2021728009 0.0052650418 0.1927370000 397494776 0 1784754176 -0.1810837090 -0.2376355380 -0.0635868534 1157 1311867209.0007669926 0.1667550057 0.1564293257 0.2021728009 0.0052628257 0.2158940000 397496510 0 1785262080 -0.1807385832 -0.2388435006 -0.0640380010 1158 1311867209.0365889072 0.1665167212 0.1564380368 0.2021728009 0.0052690342 0.2225930000 397498340 0 1785769984 -0.1818031669 -0.2407948822 -0.0643366054 1159 1311867209.0688478947 0.1685056537 0.1564484489 0.2021728009 0.0052749502 0.1989730000 397500138 0 1783779328 -0.1824640930 -0.2399592996 -0.0649461672 1160 1311867209.1008369923 0.1686737090 0.1564589879 0.2021728009 0.0052727385 0.2205340000 397501872 0 1783283712 -0.1826721579 -0.2404380590 -0.0653756559 1161 1311867209.1452479362 0.1688667238 0.1564696750 0.2021728009 0.0052727899 0.1967420000 397503862 0 1783754752 -0.1830424219 -0.2422885895 -0.0655982047 1162 1311867209.1686758995 0.1693255603 0.1564807386 0.2021728009 0.0052711114 0.1953830000 397505468 0 1784426496 -0.1827785969 -0.2418842167 -0.0659187734 1163 1311867209.2006080151 0.1690957099 0.1564915855 0.2021728009 0.0052689690 0.2043720000 397507234 0 1785040896 -0.1828368753 -0.2429858446 -0.0661301538 1164 1311867209.2365789413 0.1696129590 0.1565028582 0.2021728009 0.0052667875 0.1966030000 397509032 0 1785643008 -0.1841975152 -0.2443964630 -0.0664621517 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_living_room_traj0_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:19:40 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_living_room_traj0_loop.log input: datasets/ICL_NUIM/living_room_traj0_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1632210000 225837088 0 1777274880 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0030761305 0.0015380653 0.0030761305 0.0050352369 0.1863150000 229418242 0 1780850688 -0.0023614559 -0.0065556234 0.0031459653 3 0.0800000000 0.0029567843 0.0020109716 0.0030761305 0.0039262776 0.1893980000 229348376 0 1782755328 -0.0006512312 -0.0133153237 0.0026897315 4 0.1200000000 0.0018992918 0.0019830517 0.0030761305 0.0048957544 0.1858810000 229351098 0 1784786944 -0.0013885585 -0.0067196619 0.0020441550 5 0.1600000000 0.0021113290 0.0020087071 0.0030761305 0.0047032188 0.1891560000 229352824 0 1786437632 -0.0011853365 -0.0047804979 0.0010219942 6 0.2000000000 0.0033422562 0.0022309653 0.0033422562 0.0042354051 0.1928230000 229355510 0 1785462784 -0.0021036821 -0.0093260454 0.0021020130 7 0.2400000000 0.0031160696 0.0023574088 0.0033422562 0.0041499128 0.1855540000 229357444 0 1786728448 -0.0014354170 -0.0108568929 0.0032472673 8 0.2800000000 0.0015626880 0.0022580687 0.0033422562 0.0041416896 0.1867430000 229358938 0 1785425920 0.0014953644 -0.0086082434 0.0023589029 9 0.3200000000 0.0044389777 0.0025003919 0.0044389777 0.0039609339 0.1896840000 229365892 0 1784299520 -0.0022548572 -0.0093639223 0.0021255775 10 0.3600000000 0.0035266681 0.0026030195 0.0044389777 0.0038025209 0.1882190000 229365566 0 1782116352 -0.0000836422 -0.0092411749 0.0026449261 11 0.4000000000 0.0015971031 0.0025115726 0.0044389777 0.0037954663 0.1838420000 229369708 0 1782882304 0.0037863615 -0.0096969353 0.0025819750 12 0.4400000000 0.0013512711 0.0024148808 0.0044389777 0.0036999384 0.1921460000 229371098 0 1785405440 0.0040715719 -0.0092478171 0.0017615580 13 0.4800000000 0.0011637234 0.0023186379 0.0044389777 0.0036749922 0.1833250000 229372480 0 1784152064 0.0031247311 -0.0076855263 0.0012696367 14 0.5200000000 0.0023846119 0.0023233503 0.0044389777 0.0036988023 0.1871300000 229373862 0 1783152640 0.0013261873 -0.0072735064 0.0006949953 15 0.5600000000 0.0016954945 0.0022814933 0.0044389777 0.0035751766 0.1783370000 229374420 0 1778577408 0.0023334278 -0.0065663056 0.0001167352 16 0.6000000000 0.0015236762 0.0022341297 0.0044389777 0.0035092960 0.1915890000 229376934 0 1776041984 0.0037503247 -0.0049368027 0.0002885128 17 0.6400000000 0.0015232284 0.0021923120 0.0044389777 0.0034247450 0.1832400000 229379296 0 1777549312 0.0028266904 -0.0049030348 0.0000484341 18 0.6800000000 0.0027088681 0.0022210095 0.0044389777 0.0033342895 0.1867070000 229382126 0 1779736576 0.0036603538 -0.0061567230 0.0001309143 19 0.7200000000 0.0026093691 0.0022414495 0.0044389777 0.0035944607 0.1848510000 229388664 0 1781755904 0.0030368126 -0.0048488025 -0.0001543637 20 0.7600000000 0.0015803262 0.0022083934 0.0044389777 0.0035062372 0.1881320000 229388474 0 1783533568 0.0056790384 -0.0047433143 -0.0011815794 21 0.8000000000 0.0020582578 0.0022012440 0.0044389777 0.0034590927 0.1816110000 229389712 0 1784532992 0.0024941794 -0.0040484187 -0.0020064565 22 0.8400000000 0.0012012173 0.0021557883 0.0044389777 0.0034140675 0.1829460000 229391266 0 1786564608 0.0036218755 -0.0019794463 -0.0022608233 23 0.8800000000 0.0023933605 0.0021661175 0.0044389777 0.0033585994 0.1873430000 229392836 0 1783132160 0.0019405616 -0.0037930126 -0.0017895577 24 0.9200000000 0.0021302889 0.0021646247 0.0044389777 0.0033359332 0.1835310000 229394098 0 1781653504 0.0041130055 -0.0062269405 -0.0013941998 25 0.9600000000 0.0031642492 0.0022046096 0.0044389777 0.0033792192 0.1826860000 229398296 0 1783812096 0.0039941855 -0.0032803209 0.0002192634 26 1.0000000000 0.0016847550 0.0021846152 0.0044389777 0.0033928932 0.1842490000 229400038 0 1785548800 0.0050348439 -0.0064686663 -0.0015232207 27 1.0400000000 0.0038887630 0.0022477318 0.0044389777 0.0033450729 0.1891260000 229400644 0 1784647680 0.0049339901 -0.0075014471 0.0002288621 28 1.0800000000 0.0040130173 0.0023107777 0.0044389777 0.0032884431 0.1846900000 229402166 0 1783799808 0.0043402971 -0.0048199771 -0.0002723997 29 1.1200000000 0.0042851651 0.0023788600 0.0044389777 0.0034465598 0.1892280000 229407080 0 1780219904 0.0052719973 -0.0043555619 -0.0002677773 30 1.1600000000 0.0047449074 0.0024577283 0.0047449074 0.0036904220 0.1824740000 229406366 0 1778352128 0.0041599367 -0.0074365744 0.0002274528 31 1.2000000000 0.0040154681 0.0025079780 0.0047449074 0.0038716227 0.1800740000 229409868 0 1776812032 0.0069435528 -0.0061867307 0.0001363961 32 1.2400000000 0.0039387620 0.0025526900 0.0047449074 0.0042411176 0.1828120000 229413006 0 1775681536 0.0093268473 -0.0029753691 0.0000977538 33 1.2800000000 0.0038193737 0.0025910743 0.0047449074 0.0046841486 0.1833780000 229416484 0 1777160192 0.0093733259 -0.0048866798 0.0022751703 34 1.3200000000 0.0024399639 0.0025866299 0.0047449074 0.0048512106 0.1795470000 229424722 0 1779343360 0.0111994129 -0.0036377155 0.0014547179 35 1.3600000000 0.0069062891 0.0027100487 0.0069062891 0.0052076115 0.1839580000 229428620 0 1780994048 0.0063097971 -0.0032405206 0.0042099589 36 1.4000000000 0.0052687484 0.0027811237 0.0069062891 0.0056130500 0.1887320000 229430606 0 1782898688 0.0106265955 -0.0031343771 0.0045006280 37 1.4400000000 0.0068635484 0.0028914595 0.0069062891 0.0060360063 0.1796370000 229435128 0 1784676352 0.0091767302 -0.0032784124 0.0048538968 38 1.4800000000 0.0066833026 0.0029912449 0.0069062891 0.0081687961 0.1870970000 229440998 0 1786183680 0.0106039513 -0.0058842120 0.0075870305 39 1.5200000000 0.0037842982 0.0030115796 0.0069062891 0.0085232228 0.1818310000 229445708 0 1784688640 0.0152855190 -0.0059136311 0.0078164348 40 1.5600000000 0.0074296664 0.0031220317 0.0074296664 0.0086440154 0.1788120000 229445938 0 1783635968 0.0175249018 -0.0010114381 0.0088466313 41 1.6000000000 0.0093481634 0.0032738886 0.0093481634 0.0087676078 0.1773090000 229453520 0 1785548800 0.0139612965 -0.0058923084 0.0111000184 42 1.6400000000 0.0087585961 0.0034044769 0.0093481634 0.0089056389 0.1847490000 229454542 0 1786707968 0.0165371485 -0.0056965998 0.0111277411 43 1.6800000000 0.0073585720 0.0034964326 0.0093481634 0.0091986389 0.1748360000 229458024 0 1783250944 0.0183778089 -0.0057834242 0.0112569621 44 1.7200000000 0.0079416223 0.0035974596 0.0093481634 0.0094700539 0.1765450000 229461934 0 1782255616 0.0196657497 -0.0041482863 0.0132307643 45 1.7600000000 0.0071115452 0.0036755504 0.0093481634 0.0097895269 0.1762030000 229465768 0 1784041472 0.0229356885 -0.0045452532 0.0123366127 46 1.8000000000 0.0066065132 0.0037392670 0.0093481634 0.0110539480 0.1756210000 229468650 0 1785692160 0.0493498147 -0.0089066206 0.0061824424 47 1.8400000000 0.0055287546 0.0037773412 0.0093481634 0.0109948302 0.1794970000 229471048 0 1784758272 0.1116423532 -0.0102205612 -0.0033675293 48 1.8800000000 0.0052944073 0.0038089467 0.0093481634 0.0111262650 0.1707380000 229474894 0 1783783424 0.1136989221 -0.0127982572 -0.0030996166 49 1.9200000000 0.0040461197 0.0038137870 0.0093481634 0.0112781577 0.1722720000 229478424 0 1782767616 0.1175550893 -0.0135598928 -0.0055162599 50 1.9600000000 0.0039440375 0.0038163920 0.0093481634 0.0113807886 0.1706800000 229481874 0 1784553472 0.1198525429 -0.0143955117 -0.0036456157 51 2.0000000000 0.0091437558 0.0039208501 0.0093481634 0.0114025106 0.1689050000 229482736 0 1786183680 0.1203217655 -0.0097789606 -0.0007736646 52 2.0400000000 0.0048013199 0.0039377822 0.0093481634 0.0115699028 0.1704200000 229488946 0 1784680448 0.1254391819 -0.0183261763 -0.0038121752 53 2.0800000000 0.0117320633 0.0040848441 0.0117320633 0.0116419368 0.1687930000 229491552 0 1783517184 0.1281225532 -0.0062294733 -0.0017989017 54 2.1200000000 0.0079958467 0.0041572701 0.0117320633 0.0116861655 0.1924240000 229492818 0 1785556992 0.1312522739 -0.0097314548 -0.0036535189 55 2.1600000000 0.0208868440 0.0044614442 0.0208868440 0.0116746489 0.1664100000 229495896 0 1784565760 0.1253854632 -0.0000723004 0.0025891382 56 2.2000000000 0.0141741894 0.0046348861 0.0208868440 0.0118212072 0.1599570000 229497082 0 1783664640 0.1289074123 -0.0077242004 -0.0011588130 57 2.2400000000 0.0025337276 0.0045980236 0.0208868440 0.0121242778 0.1776560000 229811341 0 1782738944 0.1366297156 -0.0195769463 -0.0055514518 58 2.2800000000 0.0057726707 0.0046182762 0.0208868440 0.0122712139 0.2241900000 230040635 0 1785704448 0.1362371743 -0.0228710063 -0.0069802999 59 2.3200000000 0.0046302453 0.0046184790 0.0208868440 0.0124469334 0.3154380000 230628155 0 1786806272 0.1394420266 -0.0189077146 -0.0084983781 60 2.3600000000 0.0226706974 0.0049193493 0.0226706974 0.0129516758 0.1673170000 230537662 0 1783848960 0.1655023396 -0.0103238840 -0.0095301922 61 2.4000000000 0.0179612525 0.0051331510 0.0226706974 0.0131515372 0.1639280000 230037040 0 1781915648 0.1600188911 -0.0087129241 -0.0048545487 62 2.4400000000 0.0162620377 0.0053126492 0.0226706974 0.0133174445 0.1693700000 230042370 0 1783287808 0.1613202095 -0.0094700865 -0.0046866275 63 2.4800000000 0.0178387016 0.0055114754 0.0226706974 0.0135072886 0.1574180000 230044984 0 1785176064 0.1627069563 -0.0055612614 -0.0059114769 64 2.5200000000 0.0178852398 0.0057048155 0.0226706974 0.0136884219 0.1573150000 230047906 0 1784438784 0.1710521579 -0.0104388613 -0.0105953962 65 2.5600000000 0.0195070356 0.0059171573 0.0226706974 0.0137669605 0.1560380000 230050148 0 1783795712 0.1755282134 -0.0087193018 -0.0098825321 66 2.6000000000 0.0197411589 0.0061266119 0.0226706974 0.0138108376 0.1562090000 230059622 0 1783160832 0.1789695174 -0.0081672817 -0.0135570690 67 2.6400000000 0.0220971163 0.0063649777 0.0226706974 0.0138780776 0.1516450000 230064684 0 1784926208 0.1788813174 -0.0042104963 -0.0138261989 68 2.6800000000 0.0220561046 0.0065957295 0.0226706974 0.0139936451 0.1626650000 230066546 0 1786466304 0.1806647331 -0.0034098621 -0.0147017948 69 2.7200000000 0.0273631476 0.0068967066 0.0273631476 0.0140949174 0.1540630000 230068072 0 1783427072 0.1887868643 -0.0011825842 -0.0175935142 70 2.7600000000 0.0275999773 0.0071924676 0.0275999773 0.0142340316 0.1543640000 230071422 0 1782521856 0.1878492385 -0.0010481783 -0.0196813457 71 2.8000000000 0.0190006830 0.0073587805 0.0275999773 0.0143839682 0.1513710000 230074688 0 1784438784 0.1928426623 -0.0106338151 -0.0200565867 72 2.8400000000 0.0230708048 0.0075770031 0.0275999773 0.0144827933 0.1726780000 230377078 0 1786232832 0.1895393878 -0.0054693758 -0.0185786113 73 2.8800000000 0.0167271607 0.0077023477 0.0275999773 0.0147031353 0.3069120000 231045891 0 1784492032 0.2003755867 -0.0155246770 -0.0237321369 74 2.9200000000 0.0147255743 0.0077972562 0.0275999773 0.0147658761 0.2188780000 230924142 0 1784029184 0.2036474794 -0.0171396472 -0.0283507705 75 2.9600000000 0.0179056749 0.0079320351 0.0275999773 0.0148534641 0.1626240000 230356476 0 1781878784 0.2024207711 -0.0115143200 -0.0290485583 76 3.0000000000 0.0145968264 0.0080197297 0.0275999773 0.0148917121 0.1619140000 230360634 0 1783521280 0.2073128819 -0.0175458398 -0.0333379805 77 3.0400000000 0.0159346759 0.0081225212 0.0275999773 0.0149649088 0.1487380000 230361284 0 1785282560 0.2122381032 -0.0183579065 -0.0364435017 78 3.0800000000 0.0158810560 0.0082219896 0.0275999773 0.0149718629 0.1466720000 230362530 0 1784381440 0.2150148004 -0.0184936114 -0.0377538577 79 3.1200000000 0.0241458043 0.0084235569 0.0275999773 0.0150024566 0.1472180000 230365864 0 1783390208 0.2177155167 -0.0098726386 -0.0381321795 80 3.1600000000 0.0206216890 0.0085760335 0.0275999773 0.0154480622 0.1484930000 230367310 0 1782132736 0.2299792469 -0.0158339702 -0.0468420424 81 3.2000000000 0.0142173246 0.0086456791 0.0275999773 0.0154878257 0.1796040000 230372044 0 1784049664 0.2315704674 -0.0224406179 -0.0483968742 82 3.2400000000 0.0191951357 0.0087743310 0.0275999773 0.0154891172 0.1404310000 230375218 0 1785679872 0.2369265556 -0.0205376334 -0.0525067970 83 3.2800000000 0.0112529099 0.0088041934 0.0275999773 0.0155082505 0.1470170000 230373252 0 1784762368 0.2286328077 -0.0275294483 -0.0511019006 84 3.3200000000 0.0166460481 0.0088975488 0.0275999773 0.0155288806 0.1432290000 230377314 0 1784279040 0.2366332114 -0.0249154381 -0.0525392592 85 3.3600000000 0.0192164239 0.0090189473 0.0275999773 0.0155292743 0.1437100000 230380280 0 1783259136 0.2424739152 -0.0240933187 -0.0554974265 86 3.4000000000 0.0174545348 0.0091170356 0.0275999773 0.0155749522 0.1399420000 230381526 0 1784918016 0.2459214032 -0.0275936984 -0.0576124340 87 3.4400000000 0.0196268503 0.0092378380 0.0275999773 0.0155635850 0.1412010000 230385544 0 1786695680 0.2423661798 -0.0245365798 -0.0580058359 88 3.4800000000 0.0202069934 0.0093624875 0.0275999773 0.0155877790 0.1416220000 230387918 0 1783255040 0.2491284907 -0.0231660269 -0.0618017167 89 3.5200000000 0.0242060982 0.0095292697 0.0275999773 0.0156145877 0.1434750000 230390144 0 1782517760 0.2561034560 -0.0205662381 -0.0642158836 90 3.5600000000 0.0209552702 0.0096562252 0.0275999773 0.0156074089 0.1386510000 230390386 0 1779593216 0.2562767267 -0.0257346369 -0.0642739162 91 3.6000000000 0.0209831335 0.0097806967 0.0275999773 0.0156205978 0.1644090000 230730588 0 1778823168 0.2572093904 -0.0263193119 -0.0649413317 92 3.6400000000 0.0240833331 0.0099361602 0.0275999773 0.0155958719 0.3174560000 230797558 0 1778708480 0.2579547465 -0.0220228340 -0.0666498542 93 3.6800000000 0.0196065325 0.0100401427 0.0275999773 0.0155581329 0.2449720000 231650419 0 1783422976 0.2595176697 -0.0277280752 -0.0693469197 94 3.7200000000 0.0239689890 0.0101883219 0.0275999773 0.0155652439 0.2021360000 231597070 0 1783771136 0.2751346827 -0.0280691274 -0.0749800131 95 3.7600000000 0.0279745068 0.0103755449 0.0279745068 0.0155405805 0.1724640000 230775420 0 1784942592 0.2806580365 -0.0245591458 -0.0768049806 96 3.8000000000 0.0191017929 0.0104664433 0.0279745068 0.0155086491 0.1552140000 230776306 0 1786626048 0.2804179192 -0.0342127346 -0.0803740174 97 3.8400000000 0.0177179500 0.0105412011 0.0279745068 0.0154573096 0.1585360000 230777952 0 1783316480 0.2780878246 -0.0326183140 -0.0798560083 98 3.8800000000 0.0252363216 0.0106911513 0.0279745068 0.0154315331 0.1516190000 230778710 0 1782173696 0.2862187028 -0.0296392571 -0.0845715031 99 3.9200000000 0.0207837150 0.0107930964 0.0279745068 0.0153836971 0.1504420000 230780320 0 1784451072 0.2881177664 -0.0356896147 -0.0850414485 100 3.9600000000 0.0181793664 0.0108669591 0.0279745068 0.0153220757 0.1526630000 230781258 0 1785991168 0.2879536450 -0.0392171331 -0.0856064782 101 4.0000000000 0.0202346463 0.0109597085 0.0279745068 0.0152731799 0.1465430000 230782232 0 1785081856 0.2912741303 -0.0352349915 -0.0874247253 102 4.0400000000 0.0203008186 0.0110512880 0.0279745068 0.0152136503 0.1496570000 230785790 0 1786736640 0.2908503115 -0.0322336927 -0.0886088386 103 4.0800000000 0.0248386580 0.0111851460 0.0279745068 0.0151648184 0.1482230000 230786476 0 1783566336 0.2906022072 -0.0250490271 -0.0888569281 104 4.1200000000 0.0294891559 0.0113611461 0.0294891559 0.0151269674 0.1492870000 230788734 0 1782792192 0.2926031947 -0.0198966973 -0.0854847133 105 4.1600000000 0.0175889749 0.0114204587 0.0294891559 0.0151127260 0.1488010000 230791588 0 1784995840 0.2956872582 -0.0320527367 -0.0900333822 106 4.2000000000 0.0221454073 0.0115216375 0.0294891559 0.0150558017 0.1454680000 230793034 0 1786626048 0.3006477952 -0.0279879421 -0.0933835730 107 4.2400000000 0.0177735705 0.0115800668 0.0294891559 0.0149985916 0.1470050000 230794212 0 1783566336 0.3007609546 -0.0336800888 -0.0927551687 108 4.2800000000 0.0230723321 0.0116864766 0.0294891559 0.0149342754 0.1486290000 230798758 0 1782554624 0.3074894249 -0.0265252627 -0.0978422835 109 4.3200000000 0.0231837127 0.0117919559 0.0294891559 0.0148702818 0.1448690000 230800616 0 1783975936 0.3032023609 -0.0220245384 -0.0950703546 110 4.3600000000 0.0165296867 0.0118350261 0.0294891559 0.0148204992 0.1472200000 230802446 0 1785737216 0.3051908612 -0.0296532139 -0.0980302691 111 4.4000000000 0.0227466766 0.0119333293 0.0294891559 0.0147675993 0.1940470000 231157125 0 1784565760 0.3167305291 -0.0337038264 -0.1054988131 112 4.4400000000 0.0230233707 0.0120323475 0.0294891559 0.0147147734 0.3419560000 231180854 0 1783287808 0.3154224455 -0.0222439561 -0.1050706133 113 4.4800000000 0.0224266164 0.0121243322 0.0294891559 0.0146529083 0.2863140000 232362667 0 1785454592 0.3181262016 -0.0231758375 -0.1071567833 114 4.5200000000 0.0191266835 0.0121857563 0.0294891559 0.0145898269 0.2064990000 232304289 0 1784487936 0.3154672384 -0.0219590086 -0.1060765013 115 4.5600000000 0.0170325302 0.0122279022 0.0294891559 0.0145544360 0.2062940000 232231356 0 1783468032 0.3170752227 -0.0295625478 -0.1126174480 116 4.6000000000 0.0184201375 0.0122812835 0.0294891559 0.0144992779 0.1744660000 231189674 0 1780695040 0.3187248111 -0.0243639462 -0.1128669903 117 4.6400000000 0.0165124759 0.0123174476 0.0294891559 0.0144591870 0.1716220000 231192868 0 1780031488 0.3181598485 -0.0268575139 -0.1139247566 118 4.6800000000 0.0198016595 0.0123808731 0.0294891559 0.0144361472 0.1638830000 231192650 0 1779159040 0.3199403584 -0.0162377339 -0.1133040339 119 4.7200000000 0.0169943944 0.0124196422 0.0294891559 0.0144048500 0.1672360000 231198252 0 1780649984 0.3189412653 -0.0194758363 -0.1152173653 120 4.7600000000 0.0204866547 0.0124868673 0.0294891559 0.0143543862 0.1638800000 231198114 0 1782448128 0.3217007220 -0.0154608907 -0.1170161143 121 4.8000000000 0.0206857696 0.0125546268 0.0294891559 0.0143077279 0.1640270000 231197588 0 1784225792 0.3213933110 -0.0164723694 -0.1175195798 122 4.8400000000 0.0216143858 0.0126288871 0.0294891559 0.0142738978 0.1644300000 231201898 0 1786003456 0.3212409616 -0.0090097487 -0.1166887134 123 4.8800000000 0.0210268982 0.0126971636 0.0294891559 0.0142285116 0.1676220000 231204276 0 1784238080 0.3205406070 -0.0103561841 -0.1166886911 124 4.9200000000 0.0197404716 0.0127539645 0.0294891559 0.0141927733 0.1597230000 231204890 0 1783713792 0.3172348440 -0.0047860318 -0.1165582910 125 4.9600000000 0.0179286953 0.0127953624 0.0294891559 0.0141455889 0.1569560000 231206996 0 1785368576 0.3158850074 -0.0048046787 -0.1148177087 126 5.0000000000 0.0195426792 0.0128489125 0.0294891559 0.0141072646 0.1603400000 231209242 0 1784467456 0.3166109920 -0.0016008804 -0.1167803034 127 5.0400000000 0.0171992779 0.0128831673 0.0294891559 0.0140916789 0.1606950000 231210284 0 1783185408 0.3094080985 0.0062716189 -0.1118295416 128 5.0800000000 0.0181577634 0.0129243751 0.0294891559 0.0140654256 0.1570210000 231213866 0 1781567488 0.3137198091 -0.0028314239 -0.1158800721 129 5.1200000000 0.0169077683 0.0129552541 0.0294891559 0.0140369701 0.1656610000 231217068 0 1781174272 0.3123843372 0.0029048412 -0.1140417680 130 5.1600000000 0.0170410909 0.0129866836 0.0294891559 0.0140104932 0.1568920000 231237334 0 1782829056 0.3107964098 0.0023105636 -0.1135865301 131 5.2000000000 0.0127199451 0.0129846475 0.0294891559 0.0140099364 0.1549720000 231238656 0 1784606720 0.3047536612 0.0004551603 -0.1116312817 132 5.2400000000 0.0177413486 0.0130206831 0.0294891559 0.0139836765 0.1653720000 231242246 0 1786257408 0.3066651225 0.0059778178 -0.1112985015 133 5.2800000000 0.0150297191 0.0130357886 0.0294891559 0.0139562748 0.1652750000 231244508 0 1784352768 0.3036904037 0.0013721078 -0.1099446267 134 5.3200000000 0.0157091562 0.0130557391 0.0294891559 0.0139183455 0.1637100000 231247546 0 1782853632 0.3022240102 0.0059027388 -0.1078018397 135 5.3600000000 0.0161966663 0.0130790053 0.0294891559 0.0138818773 0.1589810000 231247392 0 1784872960 0.3003604412 0.0024222741 -0.1064411178 136 5.4000000000 0.0190784298 0.0131231187 0.0294891559 0.0138474955 0.1642990000 231252430 0 1786511360 0.3013674915 0.0085178558 -0.1053168401 137 5.4400000000 0.0157175176 0.0131420559 0.0294891559 0.0138168052 0.1655180000 231252972 0 1783459840 0.2977257967 0.0090305163 -0.1017201096 138 5.4800000000 0.0202265102 0.0131933925 0.0294891559 0.0138647003 0.2002210000 231257366 0 1782312960 0.2983671725 0.0096899373 -0.1005237103 139 5.5200000000 0.0217312928 0.0132548163 0.0294891559 0.0138302046 0.1678720000 231257880 0 1784213504 0.2972767055 0.0072972621 -0.1010108441 140 5.5600000000 0.0187586658 0.0132941295 0.0294891559 0.0138159208 0.1691870000 231259634 0 1785876480 0.2930967212 0.0106935538 -0.0995889232 141 5.6000000000 0.0166779254 0.0133181280 0.0294891559 0.0137927840 0.1640640000 231261064 0 1785221120 0.2897059619 0.0100702830 -0.0962574705 142 5.6400000000 0.0159484837 0.0133366517 0.0294891559 0.0137647184 0.1672650000 231262642 0 1784233984 0.2876549661 0.0159450807 -0.0939463079 143 5.6800000000 0.0169932637 0.0133622224 0.0294891559 0.0137425011 0.1626360000 231264684 0 1783205888 0.2861318588 0.0165682584 -0.0932832062 144 5.7200000000 0.0160004385 0.0133805433 0.0294891559 0.0137148262 0.1630280000 231266258 0 1782095872 0.2815348506 0.0214843564 -0.0891405717 145 5.7600000000 0.0178589337 0.0134114288 0.0294891559 0.0136857840 0.1608330000 231267656 0 1784246272 0.2826561034 0.0191433188 -0.0903596729 146 5.8000000000 0.0164132286 0.0134319890 0.0294891559 0.0136584269 0.1583890000 231269486 0 1785876480 0.2786739469 0.0181043316 -0.0900268778 147 5.8400000000 0.0153796868 0.0134452387 0.0294891559 0.0136442539 0.1690210000 231271392 0 1784983552 0.2747171521 0.0231152084 -0.0860609710 148 5.8800000000 0.0165737215 0.0134663771 0.0294891559 0.0136199554 0.1623460000 231272690 0 1786118144 0.2742553055 0.0224830937 -0.0868755803 149 5.9200000000 0.0183452014 0.0134991209 0.0294891559 0.0136022547 0.1626680000 231274456 0 1784348672 0.2712582052 0.0287492406 -0.0839862674 150 5.9600000000 0.0150514552 0.0135094698 0.0294891559 0.0135816526 0.1626510000 231278018 0 1783070720 0.2662648857 0.0232575182 -0.0790071934 151 6.0000000000 0.0169476680 0.0135322393 0.0294891559 0.0135589559 0.1633150000 231279300 0 1785262080 0.2645523548 0.0183662251 -0.0790098608 152 6.0400000000 0.0143171726 0.0135374033 0.0294891559 0.0135463304 0.1651460000 231282090 0 1784246272 0.2581497431 0.0179586187 -0.0776671544 153 6.0800000000 0.0147857293 0.0135455623 0.0294891559 0.0135229254 0.1660880000 231284192 0 1783095296 0.2545753419 0.0187633988 -0.0746609271 154 6.1200000000 0.0172372628 0.0135695344 0.0294891559 0.0135097378 0.1702150000 231285862 0 1781694464 0.2538689375 0.0197217930 -0.0739942715 155 6.1600000000 0.0158228595 0.0135840720 0.0294891559 0.0135213809 0.1746590000 231287708 0 1783971840 0.2478521764 0.0279082861 -0.0679608285 156 6.2000000000 0.0138526447 0.0135857936 0.0294891559 0.0135221944 0.1657750000 231289774 0 1785622528 0.2425173521 0.0210827906 -0.0659894571 157 6.2400000000 0.0167865623 0.0136061807 0.0294891559 0.0135241919 0.1712610000 231293372 0 1784578048 0.2400510907 0.0301302001 -0.0650339201 158 6.2800000000 0.0143786110 0.0136110695 0.0294891559 0.0135464968 0.1669170000 231295066 0 1783222272 0.2335872054 0.0336316898 -0.0618270412 159 6.3200000000 0.0157887004 0.0136247652 0.0294891559 0.0135451420 0.1668770000 231296304 0 1782206464 0.2327172905 0.0295311771 -0.0624104515 160 6.3600000000 0.0152775617 0.0136350952 0.0294891559 0.0135474723 0.1672310000 231298382 0 1783971840 0.2292149365 0.0317746401 -0.0591657460 161 6.4000000000 0.0184219051 0.0136648270 0.0294891559 0.0135482385 0.1637830000 231299684 0 1785749504 0.2283407003 0.0350140408 -0.0599378198 162 6.4400000000 0.0084365122 0.0136325534 0.0294891559 0.0135604362 0.1759680000 231302138 0 1784578048 0.2160485387 0.0289344452 -0.0525812507 163 6.4800000000 0.0140942354 0.0136353858 0.0294891559 0.0135535897 0.1653670000 231303360 0 1783984128 0.2173647285 0.0278922804 -0.0544917062 164 6.5200000000 0.0114234416 0.0136218984 0.0294891559 0.0135471324 0.1663540000 231304858 0 1782841344 0.2116359472 0.0255182777 -0.0526025854 165 6.5600000000 0.0104612205 0.0136027427 0.0294891559 0.0135360424 0.1677380000 231307204 0 1784352768 0.2064765990 0.0279345289 -0.0505139902 166 6.6000000000 0.0132681234 0.0136007270 0.0294891559 0.0135384206 0.1645220000 231309174 0 1786130432 0.2039481550 0.0285103060 -0.0472451709 167 6.6400000000 0.0109163504 0.0135846528 0.0294891559 0.0135505833 0.1936320000 231311472 0 1785131008 0.1973131597 0.0291789193 -0.0452199914 168 6.6800000000 0.0153425587 0.0135951166 0.0294891559 0.0135489213 0.1712990000 231315242 0 1787006976 0.1972189099 0.0310622696 -0.0467094816 169 6.7200000000 0.0122852391 0.0135873658 0.0294891559 0.0135915904 0.1713690000 231316368 0 1783070720 0.1906533539 0.0320049301 -0.0417155027 170 6.7600000000 0.0147864129 0.0135944190 0.0294891559 0.0136137534 0.1674650000 231317338 0 1782059008 0.1882204860 0.0328915007 -0.0425728783 171 6.8000000000 0.0127829788 0.0135896738 0.0294891559 0.0136112862 0.1680650000 231318656 0 1783955456 0.1848451793 0.0253480151 -0.0375380255 172 6.8400000000 0.0138071151 0.0135909380 0.0294891559 0.0136289818 0.1653330000 231320622 0 1785622528 0.1844840646 0.0306727197 -0.0366018154 173 6.8800000000 0.0115016913 0.0135788614 0.0294891559 0.0136757178 0.1644010000 231322780 0 1784578048 0.1808742583 0.0321844555 -0.0388521515 174 6.9200000000 0.0106341541 0.0135619378 0.0294891559 0.0136857459 0.1711620000 231324022 0 1783582720 0.1790154129 0.0285420548 -0.0366886854 175 6.9600000000 0.0129767573 0.0135585939 0.0294891559 0.0137185443 0.1669450000 231327248 0 1782714368 0.1809601784 0.0277712420 -0.0371197164 176 7.0000000000 0.0090545695 0.0135330029 0.0294891559 0.0137392287 0.1688090000 231328154 0 1783971840 0.1767621934 0.0338792242 -0.0353043675 177 7.0400000000 0.0099024288 0.0135124911 0.0294891559 0.0137782440 0.1680710000 231330612 0 1786150912 0.1746547967 0.0373586677 -0.0342998207 178 7.0800000000 0.0105300033 0.0134957356 0.0294891559 0.0138198274 0.1712650000 231332586 0 1784602624 0.1731337905 0.0373935923 -0.0309197586 179 7.1200000000 0.0109321177 0.0134814137 0.0294891559 0.0138720065 0.1670450000 231333720 0 1783238656 0.1716607213 0.0363324657 -0.0340403952 180 7.1600000000 0.0100190369 0.0134621783 0.0294891559 0.0138958524 0.1663090000 231335854 0 1784963072 0.1707149595 0.0348703526 -0.0329678245 181 7.2000000000 0.0100289099 0.0134432099 0.0294891559 0.0138876241 0.1625730000 231337876 0 1786630144 0.1673751324 0.0370784216 -0.0322442837 182 7.2400000000 0.0090340963 0.0134189840 0.0294891559 0.0138780767 0.1619620000 231338838 0 1783554048 0.1665144861 0.0349739902 -0.0335160866 183 7.2800000000 0.0119759552 0.0134110986 0.0294891559 0.0138665780 0.1906900000 231753917 0 1782431744 0.1643008739 0.0390513763 -0.0326975510 184 7.3200000000 0.0127168000 0.0134073253 0.0294891559 0.0138682953 0.4110690000 231757235 0 1784250368 0.1623162329 0.0397213884 -0.0330522731 185 7.3600000000 0.0126766246 0.0134033755 0.0294891559 0.0138502213 0.3572480000 233150124 0 1784320000 0.1584634334 0.0374177769 -0.0320149064 186 7.4000000000 0.0112954089 0.0133920424 0.0294891559 0.0138582515 0.2433120000 233088157 0 1783394304 0.1572228372 0.0365385376 -0.0305833332 187 7.4400000000 0.0112891179 0.0133807968 0.0294891559 0.0138876883 0.2710300000 233017800 0 1778434048 0.1528363973 0.0391060859 -0.0271603838 188 7.4800000000 0.0116239414 0.0133714518 0.0294891559 0.0138988223 0.1760910000 231763622 0 1778470912 0.1508206129 0.0376337171 -0.0275987312 189 7.5200000000 0.0122812670 0.0133656836 0.0294891559 0.0139302289 0.1852850000 231765888 0 1780613120 0.1482696682 0.0403786562 -0.0266353004 190 7.5600000000 0.0112598799 0.0133546005 0.0294891559 0.0139773908 0.1842780000 231767522 0 1782288384 0.1455286145 0.0369496383 -0.0263444595 191 7.6000000000 0.0112885879 0.0133437837 0.0294891559 0.0140161921 0.1768050000 231769512 0 1783939072 0.1440916061 0.0390200950 -0.0260488112 192 7.6400000000 0.0146455560 0.0133505637 0.0294891559 0.0140420537 0.2121440000 231770986 0 1785827328 0.1424290836 0.0428406633 -0.0248170570 193 7.6800000000 0.0157499239 0.0133629956 0.0294891559 0.0140558119 0.1751800000 231772552 0 1784926208 0.1441468149 0.0409414433 -0.0253300071 194 7.7200000000 0.0133159868 0.0133627533 0.0294891559 0.0140631596 0.1760240000 231776418 0 1784205312 0.1394052058 0.0384398848 -0.0241005160 195 7.7600000000 0.0118193300 0.0133548383 0.0294891559 0.0140614796 0.1825050000 231777376 0 1781882880 0.1387719512 0.0395047404 -0.0240539610 196 7.8000000000 0.0114468792 0.0133451038 0.0294891559 0.0140416428 0.1766230000 231779062 0 1781010432 0.1353979558 0.0372421741 -0.0253351368 197 7.8400000000 0.0119327977 0.0133379348 0.0294891559 0.0140543499 0.1822960000 231780736 0 1782906880 0.1389758140 0.0396215208 -0.0247628056 198 7.8800000000 0.0109156314 0.0133257009 0.0294891559 0.0140599222 0.1771200000 231782594 0 1784700928 0.1351907700 0.0407478437 -0.0251849443 199 7.9200000000 0.0145751778 0.0133319797 0.0294891559 0.0140861631 0.1772020000 231784652 0 1786478592 0.1413756609 0.0460966304 -0.0252276342 200 7.9600000000 0.0091060419 0.0133108500 0.0294891559 0.0140966893 0.1718510000 231786286 0 1783570432 0.1364889592 0.0431813449 -0.0244902074 201 8.0000000000 0.0108753340 0.0132987330 0.0294891559 0.0141008074 0.1737510000 231787040 0 1782132736 0.1425935775 0.0392907411 -0.0243025143 202 8.0400000000 0.0114025446 0.0132893459 0.0294891559 0.0140956545 0.1731740000 231789342 0 1781522432 0.1414269060 0.0406264588 -0.0236223750 203 8.0800000000 0.0111154504 0.0132786371 0.0294891559 0.0140798967 0.1791080000 231791660 0 1780883456 0.1373212785 0.0438539013 -0.0238282476 204 8.1200000000 0.0115045700 0.0132699407 0.0294891559 0.0140563300 0.1752830000 231794022 0 1783177216 0.1329876333 0.0502391607 -0.0224335287 205 8.1600000000 0.0091988239 0.0132500816 0.0294891559 0.0140282952 0.1687160000 231794200 0 1784811520 0.1314023882 0.0449143723 -0.0224272385 206 8.1999999990 0.0110746762 0.0132395214 0.0294891559 0.0140079135 0.1711630000 231796866 0 1786478592 0.1309614331 0.0427087247 -0.0216043815 207 8.2400000000 0.0118462155 0.0132327904 0.0294891559 0.0140003361 0.1711570000 231798596 0 1783439360 0.1297722459 0.0446819142 -0.0189352240 208 8.2799999990 0.0122877825 0.0132282471 0.0294891559 0.0140180587 0.1716540000 231800106 0 1782153216 0.1294876188 0.0433294736 -0.0164931212 209 8.3200000000 0.0104996022 0.0132151914 0.0294891559 0.0140225224 0.1715760000 231801436 0 1781665792 0.1279737651 0.0417137593 -0.0167047344 210 8.3599999990 0.0096506448 0.0131982174 0.0294891559 0.0140337639 0.1635080000 231801862 0 1780883456 0.1243835688 0.0447748788 -0.0163523108 211 8.4000000000 0.0107399067 0.0131865666 0.0294891559 0.0140650045 0.1648450000 231805180 0 1782796288 0.1233146191 0.0453812517 -0.0154309282 212 8.4399999990 0.0110688591 0.0131765774 0.0294891559 0.0140920592 0.1649880000 231806134 0 1784446976 0.1238725930 0.0434656329 -0.0144899208 213 8.4800000000 0.0133368624 0.0131773299 0.0294891559 0.0140998470 0.1739090000 231807468 0 1786208256 0.1218138859 0.0458927192 -0.0129647441 214 8.5200000000 0.0122292731 0.0131728998 0.0294891559 0.0141186771 0.1650270000 231808698 0 1784823808 0.1190230399 0.0466032587 -0.0127109177 215 8.5600000000 0.0102136675 0.0131591359 0.0294891559 0.0141428318 0.1647250000 231810100 0 1784041472 0.1167848930 0.0417240933 -0.0094032614 216 8.6000000000 0.0111260433 0.0131497234 0.0294891559 0.0141460781 0.1620000000 231812466 0 1785860096 0.1208994612 0.0395895168 -0.0081311613 217 8.6400000000 0.0110676894 0.0131401288 0.0294891559 0.0141583560 0.1654240000 231812152 0 1784950784 0.1202795580 0.0474361293 -0.0066089351 218 8.6800000000 0.0079498990 0.0131163204 0.0294891559 0.0141741516 0.1677810000 231814010 0 1784057856 0.1178203896 0.0487556718 -0.0055724513 219 8.7200000000 0.0111193974 0.0131072020 0.0294891559 0.0141808403 0.1589980000 231816620 0 1785970688 0.1256007105 0.0425191037 -0.0008281730 220 8.7600000000 0.0109437900 0.0130973683 0.0294891559 0.0142122371 0.1962490000 231816326 0 1784950784 0.1235838160 0.0468918830 0.0028897580 221 8.8000000000 0.0099973818 0.0130833412 0.0294891559 0.0142333642 0.1643910000 231817452 0 1782145024 0.1248506233 0.0461977646 0.0051793046 222 8.8400000000 0.0115767783 0.0130765549 0.0294891559 0.0142612604 0.1896850000 232294991 0 1780994048 0.1237697229 0.0505555458 0.0077496562 223 8.8800000000 0.0118268663 0.0130709509 0.0294891559 0.0142917414 0.4211600000 232279661 0 1780555776 0.1232257634 0.0491482913 0.0091553014 224 8.9200000000 0.0154952174 0.0130817736 0.0294891559 0.0143186037 0.3616250000 232906830 0 1785389056 0.1220939830 0.0515486971 0.0099053290 225 8.9600000000 0.0151032591 0.0130907579 0.0294891559 0.0144520707 0.2864900000 233883248 0 1784504320 0.0806054100 0.0447886474 -0.0050329603 226 9.0000000000 0.0138069903 0.0130939271 0.0294891559 0.0144616628 0.3198670000 233792950 0 1782386688 0.0764797926 0.0433256738 -0.0066717397 227 9.0400000000 0.0107222749 0.0130834793 0.0294891559 0.0144658667 0.2192560000 232289993 0 1783603200 0.0696494505 0.0425242819 -0.0051284190 228 9.0800000000 0.0094905933 0.0130677210 0.0294891559 0.0144779830 0.1653480000 232290179 0 1785745408 0.0643047988 0.0426595733 -0.0040022740 229 9.1200000000 0.0088910470 0.0130494823 0.0294891559 0.0144780413 0.1794210000 232293505 0 1784758272 0.0596714094 0.0414226763 -0.0045833653 230 9.1600000000 0.0074519920 0.0130251454 0.0294891559 0.0144904568 0.1733030000 232297511 0 1783869440 0.0521714017 0.0430907980 -0.0047509558 231 9.2000000000 0.0076683052 0.0130019556 0.0294891559 0.0144886899 0.1620260000 232299217 0 1785782272 0.0493698828 0.0413593277 -0.0041272156 232 9.2400000000 0.0074665132 0.0129780959 0.0294891559 0.0145015573 0.1612340000 232301323 0 1784868864 0.0432175957 0.0423496403 -0.0030477308 233 9.2800000000 0.0104856817 0.0129673989 0.0294891559 0.0145068934 0.2022850000 232844357 0 1784094720 0.0455633104 0.0433882885 -0.0048745954 234 9.3200000000 0.0108157657 0.0129582038 0.0294891559 0.0145100178 0.4869000000 232817971 0 1785929728 0.0414804295 0.0439301655 -0.0055965129 235 9.3600000000 0.0103446562 0.0129470824 0.0294891559 0.0145260875 0.4544330000 233734540 0 1785552896 0.0380895138 0.0430253297 -0.0047167828 236 9.4000000000 0.0114861531 0.0129408920 0.0294891559 0.0145741980 0.3345220000 234787094 0 1784033280 0.0354208723 0.0440296568 -0.0056650946 237 9.4400000000 0.0081477752 0.0129206679 0.0294891559 0.0146057047 0.3929690000 234680152 0 1781587968 0.0268803742 0.0405504927 -0.0061908481 238 9.4800000000 0.0089338934 0.0129039167 0.0294891559 0.0146279033 0.2339760000 232828459 0 1781907456 0.0236311443 0.0374530181 -0.0069605634 239 9.5200000000 0.0086932834 0.0128862990 0.0294891559 0.0146382897 0.1902210000 232830457 0 1783656448 0.0206250791 0.0377634615 -0.0075075952 240 9.5600000000 0.0091040283 0.0128705395 0.0294891559 0.0147830038 0.1984270000 232831679 0 1785581568 0.0169074498 0.0318287537 -0.0054542338 241 9.6000000000 0.0090406667 0.0128546480 0.0294891559 0.0147788959 0.1867640000 232833737 0 1784410112 0.0124372710 0.0315790176 -0.0059422571 242 9.6400000000 0.0096249767 0.0128413022 0.0294891559 0.0147941269 0.1905630000 232836239 0 1781796864 0.0121620130 0.0299751479 -0.0055490970 243 9.6800000000 0.0084241331 0.0128231246 0.0294891559 0.0148058686 0.1814970000 232837701 0 1780109312 0.0125811733 0.0261063948 -0.0065124398 244 9.7200000000 0.0086490735 0.0128060178 0.0294891559 0.0148120270 0.1759540000 232839343 0 1777577984 0.0102919582 0.0255602989 -0.0054119364 245 9.7600000000 0.0085565932 0.0127886732 0.0294891559 0.0148123494 0.1718040000 232840905 0 1776328704 0.0075111995 0.0263954718 -0.0058075306 246 9.8000000000 0.0096054254 0.0127757332 0.0294891559 0.0148225732 0.1692390000 232842347 0 1777598464 0.0066602649 0.0262510404 -0.0063095745 247 9.8400000000 0.0084757665 0.0127583244 0.0294891559 0.0148193662 0.1640750000 232844025 0 1779892224 0.0014990638 0.0239487253 -0.0057031084 248 9.8800000000 0.0083890287 0.0127407063 0.0294891559 0.0148136941 0.1649840000 232846395 0 1781501952 0.0008122304 0.0206877869 -0.0068359356 249 9.9200000000 0.0085541150 0.0127238926 0.0294891559 0.0148150721 0.2060280000 233402985 0 1783152640 -0.0069329771 0.0171303656 -0.0076043936 250 9.9600000000 0.0089421095 0.0127087655 0.0294891559 0.0148080214 0.5060830000 233373544 0 1784930304 -0.0087983105 0.0179118346 -0.0083943717 251 10.0000000000 0.0092750238 0.0126950853 0.0294891559 0.0148121177 0.4544350000 235552541 0 1784606720 -0.0099505540 0.0158325639 -0.0092948945 252 10.0400000000 0.0093680089 0.0126818826 0.0294891559 0.0148227108 0.3328200000 235503886 0 1784057856 -0.0145844305 0.0137329865 -0.0103177018 253 10.0800000000 0.0113637159 0.0126766724 0.0294891559 0.0148208168 0.3773530000 235407512 0 1782751232 -0.0204063244 0.0144360950 -0.0103242341 254 10.1200000000 0.0113383178 0.0126714033 0.0294891559 0.0148177291 0.1956530000 233380480 0 1782833152 -0.0239621568 0.0121464496 -0.0107479459 255 10.1600000000 0.0121749211 0.0126694563 0.0294891559 0.0148163480 0.2000060000 233381934 0 1784725504 -0.0277074352 0.0120205777 -0.0125566935 256 10.2000000000 0.0109603871 0.0126627803 0.0294891559 0.0148023465 0.1953020000 233383756 0 1786363904 -0.0294220671 0.0098120598 -0.0131687801 257 10.2400000000 0.0129654575 0.0126639580 0.0294891559 0.0149380909 0.2061990000 233385234 0 1785507840 -0.0357656032 0.0072444775 -0.0134309568 258 10.2800000000 0.0128813535 0.0126648006 0.0294891559 0.0149404730 0.1985460000 233428680 0 1784217600 -0.0373408198 0.0071763238 -0.0155318789 259 10.3200000000 0.0131325480 0.0126666066 0.0294891559 0.0149281053 0.1909410000 233430126 0 1782071296 -0.0404681154 0.0050611352 -0.0152760092 260 10.3600000000 0.0129862055 0.0126678358 0.0294891559 0.0149175670 0.1869920000 233431440 0 1783418880 -0.0417314321 0.0036231547 -0.0162724722 261 10.4000000000 0.0127363605 0.0126680984 0.0294891559 0.0148955131 0.1853620000 233433286 0 1785094144 -0.0436538421 0.0020122721 -0.0173174553 262 10.4400000000 0.0146628907 0.0126757121 0.0294891559 0.0148874414 0.1858760000 233434664 0 1783959552 -0.0466963314 0.0018961825 -0.0176123343 263 10.4800000000 0.0124436077 0.0126748296 0.0294891559 0.0148622691 0.1909440000 233436494 0 1782960128 -0.0467317700 -0.0006752174 -0.0192949772 264 10.5200000000 0.0126785077 0.0126748435 0.0294891559 0.0148444666 0.1825450000 233437880 0 1784709120 -0.0492117293 -0.0022647788 -0.0194758810 265 10.5600000000 0.0132890726 0.0126771613 0.0294891559 0.0148319535 0.1806240000 233439494 0 1785856000 -0.0518457741 -0.0035388889 -0.0214274526 266 10.6000000000 0.0137628522 0.0126812429 0.0294891559 0.0148285363 0.1877380000 233440964 0 1783959552 -0.0543119311 -0.0048642638 -0.0230862349 267 10.6400000000 0.0127394609 0.0126814609 0.0294891559 0.0148267679 0.1812400000 233442870 0 1782833152 -0.0534885451 -0.0053643738 -0.0255910512 268 10.6800000000 0.0126366504 0.0126812937 0.0294891559 0.0148214848 0.1810630000 233444040 0 1778245632 -0.0586194098 -0.0086327353 -0.0261576977 269 10.7200000000 0.0116154887 0.0126773316 0.0294891559 0.0148356851 0.1733010000 233445778 0 1777467392 -0.0596464053 -0.0104616750 -0.0291492287 270 10.7600000000 0.0147157032 0.0126848812 0.0294891559 0.0148573534 0.1738740000 233447132 0 1778753536 -0.0647514760 -0.0100520793 -0.0304837283 271 10.8000000000 0.0121968593 0.0126830803 0.0294891559 0.0148470972 0.1743120000 233448614 0 1781407744 -0.0670843422 -0.0145901423 -0.0330188721 272 10.8400000000 0.0127718393 0.0126834067 0.0294891559 0.0148510645 0.1722890000 233450152 0 1782546432 -0.0711801872 -0.0170560200 -0.0344486125 273 10.8800000000 0.0142635182 0.0126891946 0.0294891559 0.0148980958 0.1793720000 233451926 0 1784324096 -0.0722867176 -0.0160516836 -0.0366044492 274 10.9200000000 0.0134062348 0.0126918115 0.0294891559 0.0148920653 0.2141870000 233996260 0 1785974784 -0.0769163594 -0.0202997327 -0.0385087915 275 10.9600000000 0.0127721829 0.0126921038 0.0294891559 0.0149015491 0.5188130000 233956102 0 1783885824 -0.0775105506 -0.0219531469 -0.0403133333 276 11.0000000000 0.0129790809 0.0126931436 0.0294891559 0.0148973616 0.4331830000 235418483 0 1784066048 -0.0793530941 -0.0224003382 -0.0416918583 277 11.0400000000 0.0128353601 0.0126936570 0.0294891559 0.0152108407 0.3574790000 236226880 0 1784782848 -0.0879479945 -0.0307809748 -0.0483374856 278 11.0800000000 0.0072565651 0.0126740991 0.0294891559 0.0151942711 0.4155240000 236084514 0 1780682752 -0.0834441110 -0.0359625816 -0.0516931415 279 11.1200000000 0.0080261510 0.0126574398 0.0294891559 0.0151916336 0.2102910000 233964690 0 1781723136 -0.0846749619 -0.0370147116 -0.0529573783 280 11.1600000000 0.0081341332 0.0126412851 0.0294891559 0.0151802978 0.2413960000 233966244 0 1783377920 -0.0853547156 -0.0381195843 -0.0531060696 281 11.2000000000 0.0090510622 0.0126285085 0.0294891559 0.0151807484 0.1960600000 233967706 0 1785405440 -0.0874916315 -0.0396917202 -0.0535966158 282 11.2400000000 0.0088739246 0.0126151944 0.0294891559 0.0151772343 0.1984620000 233969344 0 1786929152 -0.0878057480 -0.0405326970 -0.0550710857 283 11.2800000000 0.0082551101 0.0125997878 0.0294891559 0.0151654907 0.2132330000 233970966 0 1782988800 -0.0899499208 -0.0433412418 -0.0563893914 284 11.3200000000 0.0081715584 0.0125841954 0.0294891559 0.0151751492 0.1955140000 233972296 0 1784135680 -0.0915837213 -0.0450072549 -0.0573290288 285 11.3600000000 0.0078999726 0.0125677595 0.0294891559 0.0151642428 0.1968940000 233973702 0 1786548224 -0.0924393311 -0.0476167463 -0.0580640584 286 11.4000000000 0.0085246740 0.0125536229 0.0294891559 0.0151558447 0.1948670000 233975108 0 1783398400 -0.0934143290 -0.0487645492 -0.0594178438 287 11.4400000000 0.0085657509 0.0125397278 0.0294891559 0.0151397322 0.1944820000 233976602 0 1778946048 -0.0916676670 -0.0498508550 -0.0602936670 288 11.4800000000 0.0069839433 0.0125204369 0.0294891559 0.0151150953 0.1980590000 233978124 0 1780072448 -0.0944897234 -0.0542598516 -0.0615455955 289 11.5200000000 0.0089833941 0.0125081980 0.0294891559 0.0151117137 0.1906110000 233979714 0 1782251520 -0.0963225514 -0.0546887182 -0.0616885722 290 11.5600000000 0.0086746002 0.0124949787 0.0294891559 0.0150983442 0.1875100000 233981144 0 1783635968 -0.0956553668 -0.0558539629 -0.0620199069 291 11.6000000000 0.0084546087 0.0124810943 0.0294891559 0.0150742603 0.1984150000 233982674 0 1785659392 -0.0960549340 -0.0570110418 -0.0635529235 292 11.6400000000 0.0079881791 0.0124657076 0.0294891559 0.0150490309 0.1925080000 233984496 0 1786916864 -0.0969573706 -0.0602673218 -0.0641387329 293 11.6800000000 0.0073190685 0.0124481423 0.0294891559 0.0150235219 0.1871460000 233986002 0 1783140352 -0.0968350992 -0.0628147423 -0.0645810813 294 11.7200000000 0.0074592014 0.0124311731 0.0294891559 0.0150009899 0.1877130000 233987464 0 1779961856 -0.0980475023 -0.0637236461 -0.0654823631 295 11.7600000000 0.0076648700 0.0124150161 0.0294891559 0.0149814593 0.1873290000 233988878 0 1778565120 -0.0971687138 -0.0685346276 -0.0652932227 296 11.8000000000 0.0085037192 0.0124018023 0.0294891559 0.0149621027 0.1885130000 233990440 0 1779961856 -0.0975504518 -0.0695171282 -0.0656001419 297 11.8400000000 0.0081321457 0.0123874263 0.0294891559 0.0149461757 0.1847210000 233992406 0 1781616640 -0.0983858407 -0.0708957464 -0.0666549206 298 11.8800000000 0.0084947078 0.0123743635 0.0294891559 0.0149883471 0.1801540000 233993436 0 1783529472 -0.0987834483 -0.0743104964 -0.0683688745 299 11.9200000000 0.0075472426 0.0123582193 0.0294891559 0.0149824682 0.1875630000 233995442 0 1784926208 -0.0994770154 -0.0765959024 -0.0701847523 300 11.9600000000 0.0072785970 0.0123412872 0.0294891559 0.0149986742 0.1849950000 233996676 0 1786421248 -0.0998003557 -0.0786736906 -0.0708500892 301 12.0000000000 0.0099660670 0.0123333961 0.0294891559 0.0150214435 0.1805890000 233997846 0 1785176064 -0.1013364494 -0.0780934989 -0.0711117014 302 12.0400000000 0.0080343438 0.0123191609 0.0294891559 0.0150355768 0.1800030000 233999000 0 1784520704 -0.1030491069 -0.0834525079 -0.0748214051 303 12.0800000000 0.0073109772 0.0123026322 0.0294891559 0.0150192705 0.1790710000 234000086 0 1782390784 -0.1033487171 -0.0852537826 -0.0774509981 304 12.1200000000 0.0076763984 0.0122874143 0.0294891559 0.0150078314 0.1808840000 234001956 0 1779073024 -0.1062389612 -0.0871717185 -0.0796230584 305 12.1600000000 0.0077501489 0.0122725380 0.0294891559 0.0150012782 0.1797680000 234003498 0 1777803264 -0.1064800173 -0.0884688795 -0.0808197856 306 12.2000000000 0.0067989626 0.0122546505 0.0294891559 0.0149933720 0.1758110000 234005360 0 1779437568 -0.1079814434 -0.0913127065 -0.0833231583 307 12.2400000000 0.0095890062 0.0122459677 0.0294891559 0.0150346509 0.1836930000 234006394 0 1781342208 -0.1079488248 -0.0904162377 -0.0838404447 308 12.2800000000 0.0077993441 0.0122315306 0.0294891559 0.0150295226 0.1853710000 234008116 0 1782865920 -0.1089147031 -0.0938968733 -0.0869789049 309 12.3200000000 0.0069850273 0.0122145516 0.0294891559 0.0150317139 0.1791050000 234009510 0 1784397824 -0.1120495498 -0.0962214619 -0.0906774029 310 12.3600000000 0.0090166908 0.0122042359 0.0294891559 0.0150466666 0.1771900000 234011044 0 1786167296 -0.1128617823 -0.0953601450 -0.0935395658 311 12.4000000000 0.0091641163 0.0121944606 0.0294891559 0.0150446351 0.1741550000 234012078 0 1785188352 -0.1156502813 -0.0968123823 -0.0957948267 312 12.4400000000 0.0085665742 0.0121828328 0.0294891559 0.0150359699 0.1776400000 234013288 0 1786822656 -0.1151337400 -0.0980607346 -0.0990183651 313 12.4800000000 0.0062589725 0.0121639067 0.0294891559 0.0150151133 0.1771720000 234016554 0 1783517184 -0.1175547540 -0.1022032052 -0.1019926518 314 12.5200000000 0.0052891420 0.0121420125 0.0294891559 0.0150063458 0.1732500000 234016980 0 1781714944 -0.1182672754 -0.1041032970 -0.1048230678 315 12.5600000000 0.0071947114 0.0121263068 0.0294891559 0.0150195584 0.1743170000 234018650 0 1782738944 -0.1209215894 -0.1031322107 -0.1069713533 316 12.6000000000 0.0083046043 0.0121142128 0.0294891559 0.0150292793 0.1744520000 234020612 0 1784651776 -0.1208515167 -0.1031917557 -0.1086479127 317 12.6400000000 0.0096288854 0.0121063727 0.0294891559 0.0150265549 0.1744610000 234021862 0 1786691584 -0.1220597848 -0.1024320126 -0.1111797094 318 12.6800000000 0.0092190197 0.0120972930 0.0294891559 0.0150096714 0.1704580000 234023628 0 1783390208 -0.1237136722 -0.1039403901 -0.1134097278 319 12.7200000000 0.0073126974 0.0120822942 0.0294891559 0.0150097460 0.1713450000 234024318 0 1782390784 -0.1263783872 -0.1068013832 -0.1195700467 320 12.7600000000 0.0056352848 0.0120621473 0.0294891559 0.0149894560 0.2172790000 234614708 0 1784283136 -0.1261983514 -0.1092691571 -0.1220156848 321 12.8000000000 0.0059598861 0.0120431372 0.0294891559 0.0149780057 0.5592890000 235186093 0 1784283136 -0.1275559813 -0.1092213392 -0.1242312267 322 12.8400000000 0.0053531849 0.0120223609 0.0294891559 0.0149617814 0.3729210000 236186766 0 1784176640 -0.1295058429 -0.1102860570 -0.1270588040 323 12.8800000000 0.0053636292 0.0120017456 0.0294891559 0.0149432450 0.3052130000 236115104 0 1781903360 -0.1342583001 -0.1140238643 -0.1295130551 324 12.9200000000 0.0049087345 0.0119798536 0.0294891559 0.0149267836 0.2077350000 234581136 0 1783488512 -0.1352491975 -0.1143228784 -0.1320649087 325 12.9600000000 0.0051250858 0.0119587620 0.0294891559 0.0149064135 0.2185190000 234583142 0 1784643584 -0.1366334707 -0.1142412648 -0.1339722574 326 13.0000000000 0.0050108437 0.0119374494 0.0294891559 0.0148874433 0.2158730000 234584364 0 1786675200 -0.1377438605 -0.1152101234 -0.1359417140 327 13.0400000000 0.0052405545 0.0119169696 0.0294891559 0.0148720215 0.2083070000 234585810 0 1783156736 -0.1384806335 -0.1126917377 -0.1366914660 328 13.0800000000 0.0052910345 0.0118967686 0.0294891559 0.0148502786 0.2535410000 234587264 0 1784918016 -0.1404569894 -0.1114037931 -0.1394992918 329 13.1200000000 0.0055062510 0.0118773445 0.0294891559 0.0148360906 0.2042860000 234589362 0 1785786368 -0.1413423866 -0.1096968874 -0.1405262500 330 13.1600000000 0.0055072103 0.0118580411 0.0294891559 0.0148180032 0.2137460000 234591836 0 1785151488 -0.1429534256 -0.1080209017 -0.1424585879 331 13.2000000000 0.0055075637 0.0118388553 0.0294891559 0.0148004883 0.2118320000 234592798 0 1786720256 -0.1442975402 -0.1059145704 -0.1443581432 332 13.2400000000 0.0055300836 0.0118198530 0.0294891559 0.0147834209 0.2065690000 234594028 0 1783136256 -0.1454882622 -0.1032874361 -0.1454475224 333 13.2800000000 0.0053783753 0.0118005092 0.0294891559 0.0147742992 0.2021030000 234595642 0 1784786944 -0.1458239406 -0.1004518196 -0.1460683197 334 13.3200000000 0.0056635384 0.0117821351 0.0294891559 0.0147990407 0.2053340000 234597580 0 1786294272 -0.1489245445 -0.0958889723 -0.1485118568 335 13.3600000000 0.0057576760 0.0117641516 0.0294891559 0.0147851143 0.2107810000 234599170 0 1785065472 -0.1493139863 -0.0920871571 -0.1487063468 336 13.4000000000 0.0055743274 0.0117457295 0.0294891559 0.0147737831 0.2009960000 234600684 0 1786822656 -0.1503978819 -0.0891719460 -0.1495851576 337 13.4400000000 0.0061578541 0.0117291483 0.0294891559 0.0147567822 0.2018190000 234601978 0 1785176064 -0.1528061926 -0.0858912915 -0.1515180469 338 13.4800000000 0.0059414236 0.0117120248 0.0294891559 0.0147674544 0.1993480000 234603668 0 1786662912 -0.1525876522 -0.0848065093 -0.1503374279 339 13.5200000000 0.0057510776 0.0116944409 0.0294891559 0.0147777994 0.1977690000 234604930 0 1785323520 -0.1536934078 -0.0823717266 -0.1510487646 340 13.5600000000 0.0053106504 0.0116756651 0.0294891559 0.0147736141 0.2025990000 234606444 0 1786552320 -0.1540524215 -0.0791692063 -0.1513393223 341 13.6000000000 0.0056187036 0.0116579027 0.0294891559 0.0147683956 0.2023340000 234608142 0 1783541760 -0.1556922495 -0.0771321058 -0.1517762691 342 13.6400000000 0.0050620073 0.0116386165 0.0294891559 0.0147688503 0.1991220000 234609696 0 1782755328 -0.1558344662 -0.0742109939 -0.1517323405 343 13.6800000000 0.0058976491 0.0116218790 0.0294891559 0.0147750189 0.1971160000 234611502 0 1784557568 -0.1575085223 -0.0721962601 -0.1514465362 344 13.7200000000 0.0057513542 0.0116048135 0.0294891559 0.0147777083 0.1926080000 234612800 0 1785896960 -0.1586032063 -0.0681129918 -0.1528194398 345 13.7600000000 0.0047406484 0.0115849174 0.0294891559 0.0149641428 0.1942150000 234614474 0 1784659968 -0.1587961018 -0.0646446794 -0.1521594822 346 13.8000000000 0.0052855504 0.0115667111 0.0294891559 0.0149756161 0.2050810000 234616064 0 1786183680 -0.1597224921 -0.0616724603 -0.1517064124 347 13.8400000000 0.0064497543 0.0115519648 0.0294891559 0.0149653196 0.1994430000 234617270 0 1784807424 -0.1628921479 -0.0585902333 -0.1532926857 348 13.8800000000 0.0057092994 0.0115351756 0.0294891559 0.0149553746 0.1945000000 234618776 0 1786310656 -0.1624199152 -0.0555047654 -0.1525132358 349 13.9200000000 0.0057239681 0.0115185245 0.0294891559 0.0149342903 0.1925740000 234619898 0 1784791040 -0.1629869640 -0.0510924235 -0.1525284946 350 13.9600000000 0.0060481289 0.0115028948 0.0294891559 0.0149245049 0.1910610000 234621924 0 1786437632 -0.1642805487 -0.0504980013 -0.1524795890 351 14.0000000000 0.0063443268 0.0114881981 0.0294891559 0.0149124052 0.1956220000 234622962 0 1784918016 -0.1657277197 -0.0453575626 -0.1532894671 352 14.0400000000 0.0052629882 0.0114705128 0.0294891559 0.0149124122 0.2229670000 234624760 0 1785532416 -0.1650341153 -0.0430494100 -0.1525942832 353 14.0800000000 0.0056479946 0.0114540184 0.0294891559 0.0149410111 0.2014030000 234626142 0 1785151488 -0.1659580320 -0.0422688797 -0.1526807845 354 14.1200000000 0.0059233881 0.0114383952 0.0294891559 0.0149481802 0.1896020000 234627916 0 1786949632 -0.1671072394 -0.0363342874 -0.1520839036 355 14.1600000000 0.0055514434 0.0114218122 0.0294891559 0.0149820269 0.1918980000 234629490 0 1783263232 -0.1665766835 -0.0345506370 -0.1507555842 356 14.2000000000 0.0053651668 0.0114047992 0.0294891559 0.0149802705 0.1890880000 234630552 0 1780215808 -0.1672605127 -0.0300795883 -0.1510744989 357 14.2400000000 0.0053810603 0.0113879259 0.0294891559 0.0149873278 0.1911150000 234632334 0 1781612544 -0.1676504016 -0.0276812594 -0.1503157616 358 14.2800000000 0.0055241697 0.0113715467 0.0294891559 0.0149914936 0.1862420000 234633540 0 1783128064 -0.1685355604 -0.0246232711 -0.1500652283 359 14.3200000000 0.0061613875 0.0113570337 0.0294891559 0.0149861366 0.1897860000 234635558 0 1784897536 -0.1699937433 -0.0216059722 -0.1504751891 360 14.3600000000 0.0068852380 0.0113446121 0.0294891559 0.0150101495 0.1874500000 234636580 0 1786421248 -0.1703526378 -0.0213812366 -0.1492565274 361 14.4000000000 0.0058937990 0.0113295129 0.0294891559 0.0150030054 0.1957990000 234638194 0 1784266752 -0.1694509685 -0.0177717060 -0.1479099840 362 14.4400000000 0.0062901373 0.0113155920 0.0294891559 0.0150226393 0.1879460000 234639668 0 1780105216 -0.1677566767 -0.0152198952 -0.1446327567 363 14.4800000000 0.0057579610 0.0113002817 0.0294891559 0.0150184046 0.1917460000 234641198 0 1778319360 -0.1696557105 -0.0123846615 -0.1466491669 364 14.5200000000 0.0051540169 0.0112833963 0.0294891559 0.0150112743 0.1888950000 234643624 0 1779298304 -0.1689976305 -0.0083737541 -0.1458168179 365 14.5600000000 0.0048436038 0.0112657531 0.0294891559 0.0150253937 0.1885090000 234644830 0 1781760000 -0.1681550443 -0.0070688715 -0.1443154067 366 14.6000000000 0.0050611799 0.0112488007 0.0294891559 0.0151234880 0.1828370000 234646512 0 1783390208 -0.1679783165 -0.0022556449 -0.1431690753 367 14.6400000000 0.0051853303 0.0112322790 0.0294891559 0.0151265206 0.1826300000 234647658 0 1785040896 -0.1667775214 0.0028759330 -0.1408236772 368 14.6800000000 0.0049674311 0.0112152549 0.0294891559 0.0151508921 0.1854990000 234649132 0 1786417152 -0.1662611961 0.0046907887 -0.1396882683 369 14.7200000000 0.0052950187 0.0111992109 0.0294891559 0.0151740983 0.1870520000 234650554 0 1783762944 -0.1649624854 0.0110213850 -0.1367735118 370 14.7600000000 0.0042323698 0.0111803816 0.0294891559 0.0151750554 0.1884360000 234651960 0 1781112832 -0.1614219397 0.0156199923 -0.1337316185 371 14.8000000000 0.0044616032 0.0111622717 0.0294891559 0.0151724758 0.1866950000 234653818 0 1780342784 -0.1600989550 0.0184645727 -0.1311956793 372 14.8400000000 0.0050487709 0.0111458376 0.0294891559 0.0151680938 0.1864920000 234655040 0 1781989376 -0.1607404053 0.0206158347 -0.1294362843 373 14.8800000000 0.0054844939 0.0111306597 0.0294891559 0.0151800703 0.2283790000 235231694 0 1784139776 -0.1574438214 0.0209129546 -0.1251162589 374 14.9200000000 0.0063396902 0.0111178496 0.0294891559 0.0151774406 0.5448840000 235189348 0 1784700928 -0.1563901156 0.0226455964 -0.1227465495 375 14.9600000000 0.0066764816 0.0111060060 0.0294891559 0.0151736512 0.4657110000 237487453 0 1782165504 -0.1543133855 0.0250324421 -0.1195345372 376 15.0000000000 0.0047202948 0.0110890227 0.0294891559 0.0151634331 0.2924640000 237409992 0 1781403648 -0.1521603465 0.0303009357 -0.1175100133 377 15.0400000000 0.0060198600 0.0110755766 0.0294891559 0.0151855390 0.3868770000 237309616 0 1781022720 -0.1508144438 0.0311701410 -0.1141296104 378 15.0800000000 0.0052538933 0.0110601754 0.0294891559 0.0151882041 0.2230430000 235198092 0 1781547008 -0.1489148140 0.0351976082 -0.1124193966 379 15.1200000000 0.0051013231 0.0110444528 0.0294891559 0.0151890853 0.2133860000 235199658 0 1783582720 -0.1460999846 0.0370448083 -0.1101097241 380 15.1600000000 0.0055062845 0.0110298787 0.0294891559 0.0151950357 0.2162880000 235201632 0 1785470976 -0.1435164511 0.0388414711 -0.1072146744 381 15.2000000000 0.0053234985 0.0110149013 0.0294891559 0.0151978128 0.2220520000 235202686 0 1784713216 -0.1421573907 0.0406511016 -0.1057050675 382 15.2400000000 0.0055049048 0.0110004772 0.0294891559 0.0151926935 0.2107080000 235204192 0 1783848960 -0.1404293925 0.0424240977 -0.1035211533 383 15.2800000000 0.0047612404 0.0109841868 0.0294891559 0.0151870320 0.2141300000 235205674 0 1785606144 -0.1377277076 0.0445707887 -0.1019374877 384 15.3200000000 0.0055257995 0.0109699722 0.0294891559 0.0151960545 0.2100670000 235207240 0 1784958976 -0.1356645375 0.0469342023 -0.0989877880 385 15.3600000000 0.0047605205 0.0109538438 0.0294891559 0.0151999808 0.2192860000 235208630 0 1784332288 -0.1321098655 0.0471878052 -0.0973966271 386 15.4000000000 0.0048939167 0.0109381445 0.0294891559 0.0151954252 0.2054350000 235210352 0 1786097664 -0.1304529458 0.0497921705 -0.0954600275 387 15.4400000000 0.0051759905 0.0109232552 0.0294891559 0.0151986729 0.2040560000 235212026 0 1784086528 -0.1280857176 0.0497035421 -0.0927154869 388 15.4800000000 0.0053364290 0.0109088562 0.0294891559 0.0152142894 0.2020160000 235213332 0 1783312384 -0.1255441159 0.0504297540 -0.0902350992 389 15.5200000000 0.0053968574 0.0108946865 0.0294891559 0.0152111616 0.1993660000 235214898 0 1785225216 -0.1233537719 0.0529522002 -0.0883510113 390 15.5600000000 0.0058992356 0.0108818777 0.0294891559 0.0152077864 0.2100630000 235216488 0 1786368000 -0.1203848869 0.0521732420 -0.0848259702 391 15.6000000000 0.0048944028 0.0108665644 0.0294891559 0.0152001673 0.2079240000 235217594 0 1783418880 -0.1176125407 0.0542452000 -0.0835045651 392 15.6400000000 0.0048172632 0.0108511325 0.0294891559 0.0151919738 0.2063290000 235219084 0 1785479168 -0.1133944765 0.0553096421 -0.0808386728 393 15.6800000000 0.0048053968 0.0108357490 0.0294891559 0.0152016087 0.2008990000 235220682 0 1784741888 -0.1109165698 0.0537647754 -0.0784693509 394 15.7200000000 0.0047139330 0.0108202114 0.0294891559 0.0152027235 0.2008420000 235222056 0 1783734272 -0.1078194827 0.0553411804 -0.0766139701 395 15.7600000000 0.0046622036 0.0108046215 0.0294891559 0.0152165588 0.1990910000 235223638 0 1785630720 -0.1043523401 0.0547877997 -0.0747576207 396 15.8000000000 0.0047315327 0.0107892854 0.0294891559 0.0152081633 0.2013360000 235225028 0 1784848384 -0.1010780334 0.0557710938 -0.0729373917 397 15.8400000000 0.0048860912 0.0107744159 0.0294891559 0.0152004694 0.2050960000 235226326 0 1782202368 -0.0986863747 0.0569844507 -0.0705371201 398 15.8800000000 0.0054925084 0.0107611448 0.0294891559 0.0151964039 0.1936500000 235228176 0 1784090624 -0.0974768698 0.0574582331 -0.0701364875 399 15.9200000000 0.0051983688 0.0107472030 0.0294891559 0.0151915921 0.1964510000 235229458 0 1785761792 -0.0948770717 0.0579902865 -0.0687067062 400 15.9600000000 0.0047097653 0.0107321094 0.0294891559 0.0151831620 0.1927790000 235231136 0 1784848384 -0.0915558636 0.0577426068 -0.0680586696 401 16.0000000000 0.0044383425 0.0107164142 0.0294891559 0.0151673345 0.1985270000 235232350 0 1781686272 -0.0910478234 0.0590778366 -0.0674448237 402 16.0400000000 0.0044385577 0.0107007977 0.0294891559 0.0151637629 0.1954030000 235233832 0 1783197696 -0.0891543925 0.0578375123 -0.0662280098 403 16.0800000000 0.0043262001 0.0106849798 0.0294891559 0.0151578513 0.1895700000 235235866 0 1785106432 -0.0877695084 0.0575208217 -0.0658494532 404 16.1200000000 0.0040662549 0.0106685968 0.0294891559 0.0151738047 0.1938890000 235237056 0 1784332288 -0.0846379772 0.0560520291 -0.0648723617 405 16.1600000000 0.0048792628 0.0106543022 0.0294891559 0.0151710305 0.1914800000 235238730 0 1782829056 -0.0820409060 0.0570328645 -0.0631935149 406 16.2000000000 0.0040011187 0.0106379150 0.0294891559 0.0151704597 0.1952120000 235240104 0 1781776384 -0.0795059428 0.0575192571 -0.0626747683 407 16.2400000000 0.0044666650 0.0106227522 0.0294891559 0.0151788902 0.1877250000 235241402 0 1783836672 -0.0778422356 0.0570092537 -0.0613082610 408 16.2800000000 0.0047787460 0.0106084287 0.0294891559 0.0151825607 0.1892810000 235242976 0 1785360384 -0.0752228051 0.0578084849 -0.0598740950 409 16.3200000000 0.0047160080 0.0105940218 0.0294891559 0.0151732916 0.1830340000 235244366 0 1785085952 -0.0712603107 0.0576931760 -0.0579788461 410 16.3600000000 0.0042338441 0.0105785092 0.0294891559 0.0151690278 0.1812670000 235245924 0 1786613760 -0.0666726157 0.0587227233 -0.0564608052 411 16.3999999990 0.0035766864 0.0105614731 0.0294891559 0.0151755349 0.1834390000 235247254 0 1783570432 -0.0629299432 0.0576644987 -0.0556066409 412 16.4400000000 0.0036370505 0.0105446662 0.0294891559 0.0151792736 0.1847170000 235249100 0 1782304768 -0.0596382916 0.0580645502 -0.0555318668 413 16.4800000000 0.0034427869 0.0105274704 0.0294891559 0.0151817718 0.1839350000 235250430 0 1781927936 -0.0594784468 0.0568472706 -0.0531472638 414 16.5200000000 0.0032949226 0.0105100005 0.0294891559 0.0151789737 0.1865480000 235252408 0 1783455744 -0.0545347594 0.0561489090 -0.0529453978 415 16.5599999990 0.0033941395 0.0104928538 0.0294891559 0.0151698732 0.1836620000 235253602 0 1785233408 -0.0516091436 0.0564131029 -0.0530299060 416 16.6000000000 0.0032800708 0.0104755154 0.0294891559 0.0151563424 0.1791320000 235254924 0 1784696832 -0.0513485819 0.0571191162 -0.0513680056 417 16.6400000000 0.0033807759 0.0104585016 0.0294891559 0.0151474891 0.1804720000 235256538 0 1784123392 -0.0490820184 0.0582486577 -0.0505562313 418 16.6800000000 0.0041752076 0.0104434698 0.0294891559 0.0151378319 0.2182430000 235777024 0 1780912128 -0.0470234156 0.0568350330 -0.0505090207 419 16.7199999990 0.0041766539 0.0104285132 0.0294891559 0.0151303170 0.5139030000 235737878 0 1779785728 -0.0446539558 0.0565602854 -0.0496421158 420 16.7600000000 0.0043389280 0.0104140142 0.0294891559 0.0151273538 0.4598330000 235888128 0 1780895744 -0.0425831266 0.0544257648 -0.0478389114 421 16.8000000000 0.0038233614 0.0103983595 0.0294891559 0.0151284094 0.4651430000 237643177 0 1784770560 -0.0409124531 0.0527720824 -0.0465197042 422 16.8400000000 0.0039524767 0.0103830849 0.0294891559 0.0151242259 0.3763310000 238878612 0 1783951360 -0.0391237512 0.0534029193 -0.0459203124 423 16.8799999990 0.0053411960 0.0103711655 0.0294891559 0.0151183707 0.2506330000 238780301 0 1786486784 -0.0357051417 0.0532451943 -0.0452708527 424 16.9200000000 0.0035909461 0.0103551744 0.0294891559 0.0151112689 0.4469880000 238710266 0 1779732480 -0.0341517255 0.0489421003 -0.0440859124 425 16.9600000000 0.0035221376 0.0103390967 0.0294891559 0.0151165799 0.2005950000 235746242 0 1779937280 -0.0317820311 0.0498624146 -0.0420490317 426 17.0000000000 0.0034332091 0.0103228857 0.0294891559 0.0151127422 0.2033560000 235747512 0 1780551680 -0.0294506606 0.0448974855 -0.0407431424 427 17.0400000000 0.0022391598 0.0103039542 0.0294891559 0.0151078126 0.2052040000 235749002 0 1782976512 -0.0278171003 0.0442511030 -0.0393785648 428 17.0800000000 0.0021341606 0.0102848659 0.0294891559 0.0151035674 0.2061990000 235750256 0 1784897536 -0.0253575183 0.0432215817 -0.0381096005 429 17.1200000000 0.0016151157 0.0102646567 0.0294891559 0.0150954051 0.1997040000 235751846 0 1786658816 -0.0232177470 0.0429636799 -0.0374150015 430 17.1600000000 0.0033696606 0.0102486219 0.0294891559 0.0150859423 0.1919720000 235752848 0 1783619584 -0.0188578703 0.0455890484 -0.0369116440 431 17.2000000000 0.0014636832 0.0102282392 0.0294891559 0.0150784723 0.1941090000 235754318 0 1780838400 -0.0191502795 0.0452068262 -0.0359212011 432 17.2400000000 0.0068293707 0.0102203714 0.0294891559 0.0150834067 0.1914720000 235755664 0 1782353920 -0.0103624240 0.0406382307 -0.0365455374 433 17.2800000000 0.0034617665 0.0102047626 0.0294891559 0.0150913540 0.1898830000 235755874 0 1784008704 -0.0125261601 0.0372700468 -0.0339280516 434 17.3200000000 0.0043516816 0.0101912763 0.0294891559 0.0150939940 0.1861310000 235757728 0 1786040320 -0.0089519825 0.0345404483 -0.0323322192 435 17.3600000000 0.0032231382 0.0101752576 0.0294891559 0.0150954845 0.1831910000 235757926 0 1785405440 -0.0089842901 0.0338001139 -0.0314502642 436 17.4000000000 0.0035901957 0.0101601542 0.0294891559 0.0150942706 0.1809650000 235758912 0 1786568704 -0.0063392171 0.0301675908 -0.0305244923 437 17.4400000000 0.0044869906 0.0101471721 0.0294891559 0.0150872526 0.1807200000 235761026 0 1783726080 -0.0056971498 0.0314749368 -0.0294871256 438 17.4800000000 0.0076989871 0.0101415827 0.0294891559 0.0150964164 0.1819030000 235762004 0 1782075392 -0.0040591182 0.0341396146 -0.0291666910 439 17.5200000000 0.0076894676 0.0101359970 0.0294891559 0.0151008877 0.1771680000 235761606 0 1781465088 -0.0085595744 0.0349516831 -0.0270515997 440 17.5600000000 0.0076776468 0.0101304098 0.0294891559 0.0151078350 0.1814980000 235761976 0 1780826112 -0.0080129225 0.0338055603 -0.0278043449 441 17.6000000000 0.0050625573 0.0101189181 0.0294891559 0.0151193937 0.1791420000 235764854 0 1780215808 -0.0113887712 0.0310688354 -0.0256943442 442 17.6400000000 0.0022755698 0.0101011730 0.0294891559 0.0152264707 0.1803060000 235766632 0 1779793920 -0.0205115099 0.0213152189 -0.0259768106 443 17.6800000000 0.0047867773 0.0100891766 0.0294891559 0.0152298473 0.1827230000 235771166 0 1781579776 -0.0213809125 0.0241218247 -0.0266007558 444 17.7200000000 0.0023072741 0.0100716498 0.0294891559 0.0152335801 0.1745150000 235769424 0 1783500800 -0.0270979311 0.0248571616 -0.0248451009 445 17.7600000000 0.0022292149 0.0100540263 0.0294891559 0.0152385936 0.1770460000 235771638 0 1785151488 -0.0294143818 0.0210837591 -0.0250272900 446 17.8000000000 0.0084875878 0.0100505141 0.0294891559 0.0152546406 0.1826160000 235774572 0 1786421248 -0.0239945129 0.0174653903 -0.0258536153 447 17.8400000000 0.0048619178 0.0100389066 0.0294891559 0.0152501715 0.1813680000 235773858 0 1783762944 -0.0266226940 0.0116423480 -0.0236506127 448 17.8800000000 0.0038818275 0.0100251631 0.0294891559 0.0152407165 0.1787220000 235778004 0 1782329344 -0.0269192848 0.0107919667 -0.0225702468 449 17.9200000000 0.0015255543 0.0100062330 0.0294891559 0.0152313343 0.1816370000 235780374 0 1781719040 -0.0318709947 0.0054931324 -0.0190370120 450 17.9600000000 0.0039969259 0.0099928790 0.0294891559 0.0152178859 0.1783360000 235780984 0 1780936704 -0.0284004845 0.0054090321 -0.0191328265 451 18.0000000000 0.0044328724 0.0099805508 0.0294891559 0.0152129698 0.1793310000 235784122 0 1780322304 -0.0269417446 0.0024270266 -0.0152846798 452 18.0400000000 0.0032371229 0.0099656317 0.0294891559 0.0152035908 0.1748950000 235784956 0 1782087680 -0.0283141788 0.0018821855 -0.0125647625 453 18.0800000000 0.0036494078 0.0099516886 0.0294891559 0.0151942250 0.1777260000 235786958 0 1783902208 -0.0264295358 -0.0010464205 -0.0087191006 454 18.1200000000 0.0060080476 0.0099430022 0.0294891559 0.0151834009 0.1764610000 235789152 0 1785659392 -0.0250281747 -0.0050192238 -0.0055270800 455 18.1600000000 0.0050498140 0.0099322479 0.0294891559 0.0151679637 0.1841710000 235789382 0 1785122816 -0.0235933289 -0.0010492717 -0.0016621687 456 18.2000000000 0.0043825130 0.0099200774 0.0294891559 0.0151601520 0.1863970000 235792052 0 1784369152 -0.0229809508 -0.0060373871 0.0042398572 457 18.2400000000 0.0039843004 0.0099070889 0.0294891559 0.0151533415 0.1811490000 235792818 0 1786040320 -0.0233183261 -0.0031347468 0.0091402894 458 18.2800000000 0.0040337574 0.0098942650 0.0294891559 0.0151411058 0.1811900000 235794520 0 1785167872 -0.0227363482 -0.0020430491 0.0135121169 459 18.3200000000 0.0068777944 0.0098876932 0.0294891559 0.0151286015 0.1853190000 235796382 0 1783635968 -0.0206871852 -0.0064112232 0.0202282276 460 18.3600000000 0.0014624846 0.0098693775 0.0294891559 0.0151130211 0.1819710000 235796068 0 1785786368 -0.0213732906 0.0023014965 0.0276144706 461 18.4000000000 0.0048954585 0.0098585881 0.0294891559 0.0150982637 0.1885190000 235798990 0 1784913920 -0.0166260730 0.0033712653 0.0338115580 462 18.4400000000 0.0058811302 0.0098499789 0.0294891559 0.0150828259 0.1813780000 235800500 0 1784131584 -0.0122477757 0.0035867130 0.0411586538 463 18.4800000000 0.0071445541 0.0098441356 0.0294891559 0.0150703653 0.1787400000 235800874 0 1785933824 -0.0114076072 0.0046588127 0.0474191867 464 18.5200000000 0.0038005030 0.0098311106 0.0294891559 0.0150568572 0.1799400000 235802480 0 1785294848 -0.0134184165 0.0061014239 0.0594317876 465 18.5600000000 0.0033043472 0.0098170745 0.0294891559 0.0150442620 0.1806450000 235805670 0 1784520704 -0.0097469566 0.0160171147 0.0789098814 466 18.6000000000 0.0058560837 0.0098085745 0.0294891559 0.0150321801 0.1898780000 235807428 0 1783250944 -0.0058581191 0.0157410186 0.0871083811 467 18.6400000000 0.0067697233 0.0098020673 0.0294891559 0.0150175212 0.1769900000 235807862 0 1782460416 -0.0015509452 0.0165804271 0.0985592753 468 18.6800000000 0.0064568040 0.0097949193 0.0294891559 0.0150031532 0.1842450000 235810788 0 1780477952 -0.0016447981 0.0190012846 0.1110311076 469 18.7200000000 0.0047063264 0.0097840695 0.0294891559 0.0149909133 0.1789230000 235810966 0 1779666944 -0.0021496022 0.0235525779 0.1220982894 470 18.7600000000 0.0031754326 0.0097700085 0.0294891559 0.0149840550 0.1770500000 235814060 0 1781469184 0.0014374102 0.0339745246 0.1363100559 471 18.8000000000 0.0027878913 0.0097551845 0.0294891559 0.0149788582 0.1821110000 235815918 0 1783267328 0.0005459292 0.0359519646 0.1489243060 472 18.8400000000 0.0024996679 0.0097398127 0.0294891559 0.0149636821 0.1807280000 235815444 0 1784897536 0.0023718385 0.0461372808 0.1619586796 473 18.8800000000 0.0021077895 0.0097236773 0.0294891559 0.0149480847 0.1747400000 235817894 0 1786658816 0.0078419223 0.0519409962 0.1712554097 474 18.9200000000 0.0017353399 0.0097068243 0.0294891559 0.0149369193 0.1749540000 235818548 0 1783619584 0.0106796660 0.0593456626 0.1825962663 475 18.9600000000 0.0011549856 0.0096888204 0.0294891559 0.0149270722 0.1783380000 235818490 0 1782603776 0.0137830079 0.0627290606 0.1958328784 476 19.0000000000 0.0025863321 0.0096738992 0.0294891559 0.0149161830 0.1764640000 235820072 0 1784627200 0.0177219920 0.0641781166 0.2073999345 477 19.0400000000 0.0016893361 0.0096571601 0.0294891559 0.0149027041 0.1764030000 235823050 0 1786040320 0.0189557038 0.0724392906 0.2184681892 478 19.0800000000 0.0028142831 0.0096428444 0.0294891559 0.0148895310 0.1793720000 235824312 0 1784893440 0.0235265810 0.0783826485 0.2307919115 479 19.1200000000 0.0062007718 0.0096356585 0.0294891559 0.0148763787 0.1724950000 235826950 0 1783730176 0.0293757878 0.0795195103 0.2410087287 480 19.1600000000 0.0027500908 0.0096213135 0.0294891559 0.0148735060 0.1775550000 235826852 0 1785659392 0.0311983787 0.0889383107 0.2552065849 481 19.2000000000 0.0035274203 0.0096086443 0.0294891559 0.0148606116 0.1780480000 235828726 0 1784520704 0.0318221822 0.1015770733 0.2647573054 482 19.2400000000 0.0023448630 0.0095935742 0.0294891559 0.0148590484 0.1741780000 235831860 0 1783877632 0.0336309746 0.1052974984 0.2755644321 483 19.2800000000 0.0041633863 0.0095823316 0.0294891559 0.0148592766 0.1757790000 235831358 0 1780576256 0.0376553237 0.1075760499 0.2863654792 484 19.3200000000 0.0052135871 0.0095733053 0.0294891559 0.0148577909 0.1717410000 235833172 0 1779961856 0.0417213589 0.1098479182 0.2987374067 485 19.3600000000 0.0043266551 0.0095624874 0.0294891559 0.0148434505 0.1760980000 235833106 0 1781579776 0.0457503349 0.1104973778 0.3082820773 486 19.4000000000 0.0076200855 0.0095584907 0.0294891559 0.0148295471 0.1744680000 235835748 0 1783373824 0.0468795560 0.1228473186 0.3198634386 487 19.4400000000 0.0023075521 0.0095436017 0.0294891559 0.0148166766 0.1717820000 235837238 0 1785024512 0.0475837439 0.1205548421 0.3313968778 488 19.4800000000 0.0034455170 0.0095311057 0.0294891559 0.0148018955 0.1746790000 235838232 0 1786777600 0.0510130636 0.1223213375 0.3419605196 489 19.5200000000 0.0032709243 0.0095183037 0.0294891559 0.0147887235 0.1692370000 235839938 0 1783373824 0.0502640717 0.1273579001 0.3524880707 490 19.5600000000 0.0020669834 0.0095030969 0.0294891559 0.0147737007 0.1700570000 235843260 0 1782468608 0.0493581071 0.1333929300 0.3631688058 491 19.6000000000 0.0053933072 0.0094947266 0.0294891559 0.0147595586 0.1712880000 235844390 0 1784492032 0.0487047732 0.1367902458 0.3740861416 492 19.6400000000 0.0034744896 0.0094824904 0.0294891559 0.0147458603 0.1759780000 235845328 0 1786167296 0.0544841662 0.1440083981 0.3830135465 493 19.6800000000 0.0057034553 0.0094748250 0.0294891559 0.0147329752 0.1869350000 235847814 0 1784913920 0.0567131862 0.1518883109 0.3952740729 494 19.7200000000 0.0063002585 0.0094683988 0.0294891559 0.0147228745 0.1961190000 235848376 0 1781858304 0.0553763546 0.1440734267 0.4050387442 495 19.7600000000 0.0023418867 0.0094540018 0.0294891559 0.0147087040 0.1754640000 235850510 0 1779953664 0.0542824492 0.1525316238 0.4165091515 496 19.8000000000 0.0032797167 0.0094415536 0.0294891559 0.0146951477 0.1757110000 235851256 0 1778700288 0.0562515035 0.1606305838 0.4268077314 497 19.8400000000 0.0064887656 0.0094356124 0.0294891559 0.0146861555 0.1755650000 235852494 0 1779937280 0.0595674217 0.1673605889 0.4391892552 498 19.8800000000 0.0031675440 0.0094230259 0.0294891559 0.0146759538 0.1709320000 235853764 0 1782214656 0.0535004251 0.1715227515 0.4490998983 499 19.9200000000 0.0032610432 0.0094106772 0.0294891559 0.0146674508 0.2113370000 236387986 0 1783865344 0.0494000241 0.1784141660 0.4634909928 500 19.9600000000 0.0034750181 0.0093988059 0.0294891559 0.0146552425 0.4771930000 236339296 0 1782145024 0.0472752340 0.1839989275 0.4741404057 501 20.0000000000 0.0030461629 0.0093861260 0.0294891559 0.0146454072 0.4143470000 236334542 0 1783795712 0.0469160751 0.1872048825 0.4851535559 502 20.0400000000 0.0039083473 0.0093752141 0.0294891559 0.0146366518 0.3925800000 237592123 0 1784758272 0.0466802157 0.1914006770 0.4980223477 503 20.0800000000 0.0041958322 0.0093649171 0.0294891559 0.0146250252 0.3094390000 239452517 0 1784041472 0.0476996750 0.1988536566 0.5069542527 504 20.1200000000 0.0034963898 0.0093532732 0.0294891559 0.0146105516 0.2825690000 239295552 0 1785851904 0.0434548594 0.2035230249 0.5185943246 505 20.1600000000 0.0058959001 0.0093464269 0.0294891559 0.0145970685 0.4554780000 239251056 0 1784823808 0.0372216590 0.2075879127 0.5315513611 506 20.2000000000 0.0035853621 0.0093350414 0.0294891559 0.0145875821 0.2546360000 236343732 0 1785823232 0.0388180427 0.2144760489 0.5390930772 507 20.2400000000 0.0048102979 0.0093261169 0.0294891559 0.0145835007 0.1928930000 236345990 0 1784926208 0.0349427797 0.2196009457 0.5510999560 508 20.2800000000 0.0041787345 0.0093159842 0.0294891559 0.0145782158 0.1978460000 236347136 0 1781747712 0.0326334424 0.2272373140 0.5612557530 509 20.3200000000 0.0068600317 0.0093111592 0.0294891559 0.0145943608 0.1930680000 236349546 0 1783402496 0.0277632587 0.2297530472 0.5715060830 510 20.3600000000 0.0067452099 0.0093061279 0.0294891559 0.0145906484 0.1913330000 236351912 0 1785057280 0.0237755515 0.2402920276 0.5816158652 511 20.4000000000 0.0041895746 0.0092961151 0.0294891559 0.0145893692 0.2067000000 236351830 0 1784152064 0.0226476490 0.2436771095 0.5882607698 512 20.4400000000 0.0034522929 0.0092847014 0.0294891559 0.0145937020 0.1889860000 236354680 0 1783386112 0.0234457552 0.2485352755 0.5959663987 513 20.4800000000 0.0036090587 0.0092736377 0.0294891559 0.0145966673 0.2200010000 236355426 0 1785167872 0.0237765983 0.2539588809 0.6046985388 514 20.5200000000 0.0044618305 0.0092642762 0.0294891559 0.0146005156 0.1937390000 236441200 0 1786691584 0.0213976931 0.2536931634 0.6135327220 515 20.5600000000 0.0034934487 0.0092530707 0.0294891559 0.0146063405 0.1880500000 236442094 0 1783799808 0.0202523936 0.2561094761 0.6195430160 516 20.6000000000 0.0040938859 0.0092430723 0.0294891559 0.0146224878 0.1918990000 236442476 0 1780879360 0.0194144100 0.2617107630 0.6270408630 517 20.6400000000 0.0051038014 0.0092350660 0.0294891559 0.0146369600 0.1851370000 236446314 0 1782239232 0.0200834963 0.2631077468 0.6333884597 518 20.6800000000 0.0044516870 0.0092258317 0.0294891559 0.0146532843 0.1858860000 236444212 0 1784152064 0.0215033535 0.2674026191 0.6405026317 519 20.7200000000 0.0048082354 0.0092173199 0.0294891559 0.0146647309 0.1903970000 236449342 0 1785929728 0.0217784680 0.2732107639 0.6469450593 520 20.7600000000 0.0050933515 0.0092093892 0.0294891559 0.0147015035 0.1930430000 236449656 0 1784778752 0.0229009055 0.2734640539 0.6514077783 521 20.8000000000 0.0032287373 0.0091979100 0.0294891559 0.0147248128 0.1864280000 236449938 0 1781501952 0.0260152444 0.2750778198 0.6554511189 522 20.8400000000 0.0035768778 0.0091871418 0.0294891559 0.0147467218 0.1876470000 236452404 0 1779589120 0.0265340693 0.2769221067 0.6615498066 523 20.8800000000 0.0056126285 0.0091803071 0.0294891559 0.0147805090 0.1874420000 236453446 0 1778438144 0.0293542780 0.2724059820 0.6651785970 524 20.9200000000 0.0041660871 0.0091707380 0.0294891559 0.0148152167 0.1869840000 236456572 0 1779712000 0.0310799703 0.2781592906 0.6696645617 525 20.9600000000 0.0031571612 0.0091592836 0.0294891559 0.0148311282 0.1815170000 236456318 0 1781768192 0.0370084308 0.2810814083 0.6737478375 526 21.0000000000 0.0034510680 0.0091484315 0.0294891559 0.0148419588 0.1903950000 236457416 0 1783152640 0.0369830392 0.2795478106 0.6764433980 527 21.0400000000 0.0043467819 0.0091393202 0.0294891559 0.0148598977 0.1859810000 236459130 0 1785016320 0.0407935940 0.2814876437 0.6820432544 528 21.0800000000 0.0054372014 0.0091323086 0.0294891559 0.0148657685 0.1839210000 236458940 0 1786683392 0.0423914492 0.2852521837 0.6858429909 529 21.1200000000 0.0054218234 0.0091252944 0.0294891559 0.0148649647 0.1880220000 236458906 0 1783791616 0.0486603528 0.2886951566 0.6886288524 530 21.1600000000 0.0029855308 0.0091137100 0.0294891559 0.0148765004 0.1780730000 236463584 0 1782407168 0.0536699444 0.2853665054 0.6889601946 531 21.2000000000 0.0028427274 0.0091019002 0.0294891559 0.0148859522 0.1803000000 236464506 0 1784692736 0.0559564754 0.2860495448 0.6924064159 532 21.2400000000 0.0047189859 0.0090936617 0.0294891559 0.0149037010 0.1730960000 236464732 0 1786429440 0.0606277995 0.2816823721 0.6923043728 533 21.2800000000 0.0047822446 0.0090855727 0.0294891559 0.0149236233 0.1764050000 236467174 0 1784401920 0.0651222765 0.2821714878 0.6935206056 534 21.3200000000 0.0053126449 0.0090785073 0.0294891559 0.0149419324 0.1782470000 236470100 0 1783160832 0.0661056414 0.2810502946 0.6961215734 535 21.3600000000 0.0032122137 0.0090675423 0.0294891559 0.0149534067 0.1763690000 236471522 0 1784274944 0.0725473762 0.2892168462 0.6986441016 536 21.4000000000 0.0044418825 0.0090589123 0.0294891559 0.0149810539 0.1742270000 236471044 0 1786302464 0.0760295317 0.2832856178 0.7000542879 537 21.4400000000 0.0046793749 0.0090507567 0.0294891559 0.0149925043 0.1795970000 236475294 0 1785081856 0.0817548558 0.2844468355 0.7023327947 538 21.4800000000 0.0051107970 0.0090434334 0.0294891559 0.0150055490 0.1739950000 236474200 0 1786966016 0.0880262852 0.2871068120 0.7042077780 539 21.5200000000 0.0044455105 0.0090349029 0.0294891559 0.0150153905 0.2016170000 236477602 0 1783173120 0.0875606760 0.2857115269 0.7081924677 540 21.5600000000 0.0039105131 0.0090254133 0.0294891559 0.0150164316 0.1798220000 236480668 0 1784950784 0.0951626226 0.2883135974 0.7077929974 541 21.6000000000 0.0028507395 0.0090139999 0.0294891559 0.0150203676 0.1741360000 236479062 0 1786310656 0.0959459022 0.2875418365 0.7111434340 542 21.6400000000 0.0035078281 0.0090038409 0.0294891559 0.0150223315 0.2174980000 236949556 0 1785315328 0.0981486738 0.2895413637 0.7147177458 543 21.6800000000 0.0067103491 0.0089996171 0.0294891559 0.0150356794 0.4466190000 236917062 0 1784246272 0.0990299210 0.2926442921 0.7194537520 544 21.7200000000 0.0033846013 0.0089892954 0.0294891559 0.0150528356 0.4123290000 237038660 0 1786408960 0.1054257751 0.2918273211 0.7199320793 545 21.7600000000 0.0055793780 0.0089830387 0.0294891559 0.0150663128 0.4162070000 238247453 0 1785290752 0.1078494713 0.2940067947 0.7236832976 546 21.8000000000 0.0036566625 0.0089732834 0.0294891559 0.0151361627 0.3595990000 239945784 0 1782722560 0.1149923131 0.2972580791 0.7265133858 547 21.8400000000 0.0034426409 0.0089631726 0.0294891559 0.0151507934 0.2430310000 239688929 0 1784360960 0.1187248603 0.2940818965 0.7262704372 548 21.8800000000 0.0042838920 0.0089546337 0.0294891559 0.0151608561 0.4131560000 239616194 0 1779105792 0.1224516034 0.2970551848 0.7309502363 549 21.9200000000 0.0041961051 0.0089459661 0.0294891559 0.0151755479 0.2279150000 236929566 0 1779978240 0.1268916428 0.3011139631 0.7339482307 550 21.9600000000 0.0070996471 0.0089426091 0.0294891559 0.0151918576 0.1927990000 236930476 0 1781121024 0.1299623698 0.3027591407 0.7374853492 551 22.0000000000 0.0060753957 0.0089374055 0.0294891559 0.0152384698 0.1917550000 236932322 0 1783541760 0.1363293827 0.2980621755 0.7316959500 552 22.0400000000 0.0057863630 0.0089316971 0.0294891559 0.0152405728 0.1879660000 236932312 0 1785430016 0.1375534236 0.3068684340 0.7389135361 553 22.0800000000 0.0023005020 0.0089197058 0.0294891559 0.0152418420 0.1948140000 236935882 0 1786699776 0.1447513849 0.3044001460 0.7355839014 554 22.1200000000 0.0076993313 0.0089175029 0.0294891559 0.0152368155 0.1864160000 236935460 0 1783431168 0.1448388398 0.3003980517 0.7421327829 555 22.1600000000 0.0014285484 0.0089040093 0.0294891559 0.0152283876 0.1885660000 236938394 0 1782374400 0.1550590992 0.3062818944 0.7403274179 556 22.2000000000 0.0018044506 0.0088912403 0.0294891559 0.0152272021 0.1908200000 236940104 0 1784274944 0.1603893787 0.3087324500 0.7397230268 557 22.2400000000 0.0063763671 0.0088867253 0.0294891559 0.0152271089 0.1810590000 236940594 0 1785933824 0.1628378034 0.3060507476 0.7427453399 558 22.2800000000 0.0042020106 0.0088783297 0.0294891559 0.0152261910 0.2172780000 236940984 0 1784930304 0.1706549525 0.3111222088 0.7456241250 559 22.3200000000 0.0043299948 0.0088701932 0.0294891559 0.0152196366 0.1833530000 236941802 0 1786970112 0.1732827723 0.3164703846 0.7485771179 560 22.3600000000 0.0056489767 0.0088644410 0.0294891559 0.0152130576 0.1864550000 236945392 0 1782882304 0.1769894958 0.3208052218 0.7520822287 561 22.4000000000 0.0062936358 0.0088598585 0.0294891559 0.0152240868 0.1846280000 236947150 0 1782149120 0.1882850677 0.3163847327 0.7478580475 562 22.4400000000 0.0035565372 0.0088504220 0.0294891559 0.0152178182 0.1787450000 236948380 0 1783648256 0.1898028851 0.3223735690 0.7537848949 563 22.4800000000 0.0039014793 0.0088416317 0.0294891559 0.0152131174 0.1800210000 236950898 0 1785298944 0.1987437904 0.3258128762 0.7523025870 564 22.5200000000 0.0057576592 0.0088361636 0.0294891559 0.0152006098 0.1834170000 236952112 0 1784176640 0.1968336403 0.3297750950 0.7579635978 565 22.5600000000 0.0054213428 0.0088301197 0.0294891559 0.0151928269 0.1802620000 236952514 0 1783263232 0.2045040578 0.3346989751 0.7573027611 566 22.6000000000 0.0056232647 0.0088244539 0.0294891559 0.0151824073 0.1768130000 236954220 0 1778221056 0.2063903660 0.3360952735 0.7604234219 567 22.6400000000 0.0065423008 0.0088204289 0.0294891559 0.0151735813 0.1902980000 236957038 0 1777438720 0.2146478295 0.3395171463 0.7618455887 568 22.6800000000 0.0052219466 0.0088140936 0.0294891559 0.0151629813 0.1805490000 236960216 0 1779343360 0.2183602899 0.3399562240 0.7627648711 569 22.7200000000 0.0043855333 0.0088063105 0.0294891559 0.0151520018 0.1812630000 236959222 0 1781129216 0.2264842093 0.3409463465 0.7581340075 570 22.7600000000 0.0029665139 0.0087960652 0.0294891559 0.0151415725 0.1787490000 236961788 0 1782759424 0.2258847505 0.3404507637 0.7621990442 571 22.8000000000 0.0077980077 0.0087943173 0.0294891559 0.0151299502 0.1818980000 236963090 0 1784410112 0.2285342962 0.3479523361 0.7663747072 572 22.8400000000 0.0029689514 0.0087841331 0.0294891559 0.0151199165 0.1753220000 236963760 0 1786187776 0.2395486385 0.3468062282 0.7623277903 573 22.8800000000 0.0071775774 0.0087813294 0.0294891559 0.0151077359 0.2131880000 237387846 0 1785077760 0.2401886731 0.3541277647 0.7659217119 574 22.9200000000 0.0048589059 0.0087744959 0.0294891559 0.0150966747 0.4390850000 237379040 0 1784213504 0.2464346737 0.3556255996 0.7647215128 575 22.9600000000 0.0047410894 0.0087674812 0.0294891559 0.0150837060 0.3890860000 237380022 0 1782710272 0.2494253069 0.3577338159 0.7656716108 576 23.0000000000 0.0037636752 0.0087587941 0.0294891559 0.0150707910 0.3656250000 238571511 0 1785335808 0.2543693185 0.3605215549 0.7654551864 577 23.0400000000 0.0089731403 0.0087591656 0.0294891559 0.0150589576 0.2758330000 240168570 0 1783975936 0.2566026151 0.3680959344 0.7693089247 578 23.0800000000 0.0058539156 0.0087541392 0.0294891559 0.0150462332 0.2707960000 240103300 0 1783017472 0.2606998980 0.3686944246 0.7665404677 579 23.1200000000 0.0066211889 0.0087504553 0.0294891559 0.0150347036 0.4301440000 240071704 0 1781583872 0.2660657167 0.3726686835 0.7666074038 580 23.1600000000 0.0047088056 0.0087434870 0.0294891559 0.0150224932 0.2021850000 237384452 0 1780842496 0.2684907019 0.3775578141 0.7647144198 581 23.2000000000 0.0107669458 0.0087469697 0.0294891559 0.0150110943 0.1878800000 237386878 0 1783111680 0.2714117169 0.3865808845 0.7687336206 582 23.2400000000 0.0051291026 0.0087407534 0.0294891559 0.0150005392 0.1837870000 237387004 0 1784999936 0.2747812867 0.3860862553 0.7645180821 583 23.2800000000 0.0034602077 0.0087316959 0.0294891559 0.0149878991 0.1857300000 237387622 0 1786777600 0.2802945971 0.3891125023 0.7626271248 584 23.3200000000 0.0055223298 0.0087262004 0.0294891559 0.0149772947 0.1884300000 237389304 0 1783238656 0.2810812593 0.3944383264 0.7639309764 585 23.3600000000 0.0069845249 0.0087232232 0.0294891559 0.0149652115 0.1877350000 237392058 0 1780064256 0.2838784456 0.3963782191 0.7662727833 586 23.4000000000 0.0080636274 0.0087220976 0.0294891559 0.0149532995 0.1874140000 237395912 0 1778888704 0.2861604691 0.4013056159 0.7654548883 587 23.4400000000 0.0050664949 0.0087158700 0.0294891559 0.0149414794 0.1813380000 237394542 0 1780191232 0.2864473760 0.4014398754 0.7642717957 588 23.4800000000 0.0062068361 0.0087116029 0.0294891559 0.0149292364 0.1830810000 237396776 0 1782333440 0.2858541012 0.4038697481 0.7644566298 589 23.5200000000 0.0086450819 0.0087114900 0.0294891559 0.0149179602 0.1887910000 237400346 0 1784111104 0.2917378545 0.4094287753 0.7668058276 590 23.5600000000 0.0095403176 0.0087128948 0.0294891559 0.0149054191 0.1764410000 237399820 0 1785516032 0.2936200202 0.4124502242 0.7671535015 591 23.6000000000 0.0127591128 0.0087197412 0.0294891559 0.0148940541 0.1754730000 237402154 0 1784995840 0.2984483838 0.4178523421 0.7691947222 592 23.6400000000 0.0115605518 0.0087245398 0.0294891559 0.0148826933 0.1744300000 237403828 0 1786798080 0.3003980517 0.4209603667 0.7658035755 593 23.6800000000 0.0112660602 0.0087288257 0.0294891559 0.0148737644 0.2087600000 237848418 0 1784135680 0.3041390479 0.4231470227 0.7678347826 594 23.7200000000 0.0114685511 0.0087334380 0.0294891559 0.0148612487 0.4396380000 237845376 0 1783418880 0.3041577637 0.4233625531 0.7695527077 595 23.7600000000 0.0131766908 0.0087409057 0.0294891559 0.0148492686 0.3749470000 237843966 0 1784872960 0.3060773611 0.4268204570 0.7707008719 596 23.8000000000 0.0144831818 0.0087505404 0.0294891559 0.0148370230 0.3699740000 237983908 0 1784119296 0.3080157638 0.4310339391 0.7710518241 597 23.8400000000 0.0138237281 0.0087590382 0.0294891559 0.0148248972 0.3692450000 240880157 0 1785475072 0.3088810444 0.4326278567 0.7711489201 598 23.8800000000 0.0107207410 0.0087623186 0.0294891559 0.0148135374 0.3434010000 240880882 0 1780658176 0.3092143536 0.4306435883 0.7710113525 599 23.9200000000 0.0095337024 0.0087636064 0.0294891559 0.0148029666 0.2322050000 240826081 0 1782460416 0.3109405041 0.4317336977 0.7707121372 600 23.9600000000 0.0110545186 0.0087674246 0.0294891559 0.0147931249 0.4105000000 240753914 0 1777422336 0.3102511168 0.4349015653 0.7723475695 601 24.0000000000 0.0111135114 0.0087713282 0.0294891559 0.0147833927 0.1836580000 237827978 0 1777618944 0.3111993372 0.4381425083 0.7746132612 602 24.0400000000 0.0114052510 0.0087757035 0.0294891559 0.0147734503 0.1838490000 237830028 0 1779486720 0.3118898273 0.4385336637 0.7756963968 603 24.0800000000 0.0125737041 0.0087820020 0.0294891559 0.0147627316 0.1803970000 237832010 0 1780752384 0.3124149740 0.4414465725 0.7760345936 604 24.1200000000 0.0142283123 0.0087910191 0.0294891559 0.0147512857 0.1852530000 237832612 0 1782513664 0.3130844235 0.4432351291 0.7789608240 605 24.1600000000 0.0144494930 0.0088003719 0.0294891559 0.0147392258 0.1740290000 237831694 0 1784291328 0.3145717382 0.4483505487 0.7795614004 606 24.2000000000 0.0146355648 0.0088100010 0.0294891559 0.0147270577 0.1767090000 237835900 0 1785688064 0.3145315945 0.4499862492 0.7808206677 607 24.2400000000 0.0114648798 0.0088143747 0.0294891559 0.0147159426 0.1814900000 237836302 0 1784922112 0.3148642182 0.4483318031 0.7800785303 608 24.2800000000 0.0118790800 0.0088194154 0.0294891559 0.0147040141 0.2117040000 238272712 0 1786576896 0.3173476458 0.4498854280 0.7809537053 609 24.3200000000 0.0109876785 0.0088229757 0.0294891559 0.0146922168 0.4392600000 238258574 0 1785417728 0.3180537522 0.4510491490 0.7800765038 610 24.3600000000 0.0092893504 0.0088237403 0.0294891559 0.0146804935 0.3754780000 238264028 0 1785040896 0.3183026910 0.4518577158 0.7802593708 611 24.4000000000 0.0119773140 0.0088289016 0.0294891559 0.0146687271 0.3767360000 239213397 0 1786011648 0.3192309737 0.4569548666 0.7814157605 612 24.4400000000 0.0118840681 0.0088338937 0.0294891559 0.0146567277 0.2817280000 240916097 0 1782407168 0.3187846541 0.4583305120 0.7829451561 613 24.4800000000 0.0136881508 0.0088418126 0.0294891559 0.0146449343 0.2670090000 240821869 0 1780932608 0.3194272220 0.4630483985 0.7833207846 614 24.5200000000 0.0145983687 0.0088511881 0.0294891559 0.0146335899 0.4083940000 240796566 0 1778634752 0.3164578676 0.4656537473 0.7845143080 615 24.5600000000 0.0153811136 0.0088618058 0.0294891559 0.0146229252 0.2097340000 238269170 0 1778245632 0.3163300157 0.4697123468 0.7850524783 616 24.6000000000 0.0131561514 0.0088687772 0.0294891559 0.0146119102 0.1934870000 238274424 0 1779879936 0.3148622513 0.4685355723 0.7869833112 617 24.6400000000 0.0119929397 0.0088738406 0.0294891559 0.0146002713 0.1868460000 238275194 0 1782312960 0.3147156835 0.4696636498 0.7875074148 618 24.6800000000 0.0134147871 0.0088811885 0.0294891559 0.0145903576 0.1869710000 238274192 0 1783308288 0.3134217262 0.4725314379 0.7899072170 619 24.7200000000 0.0163256191 0.0088932150 0.0294891559 0.0145817360 0.1883480000 238275690 0 1785450496 0.3113043010 0.4779355228 0.7927470803 620 24.7600000000 0.0141673218 0.0089017216 0.0294891559 0.0145730143 0.1801090000 238278760 0 1783832576 0.3097316921 0.4774363935 0.7931249142 621 24.8000000000 0.0129026854 0.0089081644 0.0294891559 0.0145642267 0.1806170000 238277942 0 1781915648 0.3084752262 0.4781458378 0.7945769429 622 24.8400000000 0.0133879241 0.0089153666 0.0294891559 0.0145569335 0.1819680000 238280744 0 1777991680 0.3055428267 0.4806829095 0.7966527939 623 24.8800000000 0.0108128069 0.0089184122 0.0294891559 0.0145507887 0.1791910000 238279558 0 1776578560 0.3068349361 0.4819698632 0.7974149585 624 24.9200000000 0.0128460741 0.0089247066 0.0294891559 0.0145449889 0.1818100000 238282360 0 1774444544 0.3033122718 0.4841365516 0.8007770181 625 24.9600000000 0.0149685591 0.0089343767 0.0294891559 0.0145382377 0.1775900000 238284342 0 1776070656 0.3005713820 0.4887244701 0.8036967516 626 25.0000000000 0.0129431849 0.0089407806 0.0294891559 0.0145309773 0.1813710000 238285696 0 1778376704 0.2995679975 0.4907042980 0.8046501875 627 25.0400000000 0.0126370378 0.0089466757 0.0294891559 0.0145271680 0.1785070000 238287562 0 1780133888 0.2987933159 0.4940981269 0.8053832054 628 25.0800000000 0.0107107498 0.0089494848 0.0294891559 0.0145259756 0.1877960000 238289652 0 1781784576 0.2957218289 0.4946883619 0.8060724139 629 25.1200000000 0.0149678197 0.0089590529 0.0294891559 0.0145294701 0.1814680000 238290262 0 1783562240 0.2963236570 0.5008890629 0.8091627955 630 25.1600000000 0.0125189684 0.0089647035 0.0294891559 0.0145246161 0.1765260000 238290672 0 1785212928 0.2898567915 0.4998785555 0.8106135130 631 25.2000000000 0.0118819335 0.0089693267 0.0294891559 0.0145179848 0.1809590000 238293810 0 1784209408 0.2906544209 0.5022541285 0.8114856482 632 25.2400000000 0.0143791279 0.0089778865 0.0294891559 0.0145118060 0.1800220000 238297404 0 1783062528 0.2857519686 0.5038812160 0.8163893223 633 25.2800000000 0.0115519678 0.0089819530 0.0294891559 0.0145025558 0.1780910000 238297974 0 1777983488 0.2820507586 0.5028628111 0.8173018694 634 25.3200000000 0.0139418077 0.0089897761 0.0294891559 0.0144952194 0.1752760000 238300324 0 1776840704 0.2772786617 0.5079534054 0.8205617666 635 25.3600000000 0.0158121716 0.0090005200 0.0294891559 0.0144873388 0.1761030000 238301346 0 1777856512 0.2745211720 0.5117436051 0.8246536851 636 25.4000000000 0.0145051526 0.0090091751 0.0294891559 0.0144811742 0.1739540000 238301364 0 1779982336 0.2697688937 0.5121739507 0.8255295753 637 25.4400000000 0.0127193546 0.0090149996 0.0294891559 0.0144740558 0.2081240000 238762006 0 1781633024 0.2663328350 0.5122125149 0.8270211220 638 25.4800000000 0.0143733267 0.0090233982 0.0294891559 0.0144671239 0.4528920000 238748120 0 1781563392 0.2619596124 0.5145090222 0.8318272233 639 25.5200000000 0.0118023874 0.0090277472 0.0294891559 0.0144595007 0.4341620000 238755046 0 1784123392 0.2569742203 0.5126117468 0.8337042928 640 25.5600000000 0.0120787872 0.0090325144 0.0294891559 0.0144507034 0.4134960000 238899900 0 1785712640 0.2517305911 0.5112801790 0.8385147452 641 25.6000000000 0.0127306953 0.0090382838 0.0294891559 0.0144426243 0.3559750000 242119333 0 1784238080 0.2472117245 0.5128384829 0.8409475684 642 25.6400000000 0.0116747562 0.0090423905 0.0294891559 0.0144375734 0.3307810000 242046058 0 1783001088 0.2419751585 0.5137461424 0.8439221978 643 25.6800000000 0.0134525504 0.0090492492 0.0294891559 0.0144355268 0.2324400000 241982145 0 1784475648 0.2367311418 0.5157580972 0.8486663103 644 25.7200000000 0.0121261999 0.0090540271 0.0294891559 0.0144300100 0.4319270000 241910414 0 1779724288 0.2314374596 0.5140058994 0.8509051204 645 25.7600000000 0.0109292492 0.0090569344 0.0294891559 0.0144238964 0.2206620000 238761622 0 1779863552 0.2273681462 0.5145797133 0.8529268503 646 25.8000000000 0.0091227777 0.0090570363 0.0294891559 0.0144180052 0.1952560000 238764392 0 1781129216 0.2244343311 0.5164343715 0.8533030748 647 25.8400000000 0.0082636066 0.0090558100 0.0294891559 0.0144107858 0.1945000000 238768106 0 1783418880 0.2201698124 0.5157988071 0.8563593030 648 25.8800000000 0.0105335517 0.0090580905 0.0294891559 0.0144034396 0.1955990000 238767112 0 1785065472 0.2143312246 0.5191810131 0.8603359461 649 25.9200000000 0.0098280404 0.0090592768 0.0294891559 0.0143950082 0.1919790000 238768234 0 1786572800 0.2119317800 0.5212558508 0.8623611927 650 25.9600000000 0.0079594636 0.0090575848 0.0294891559 0.0143876253 0.1915540000 238769748 0 1783451648 0.2072770894 0.5218479633 0.8650819659 651 26.0000000000 0.0106892120 0.0090600912 0.0294891559 0.0143879828 0.1911670000 238771998 0 1779875840 0.2026649117 0.5266243815 0.8678652644 652 26.0400000000 0.0106468331 0.0090625248 0.0294891559 0.0143842837 0.1946290000 238776800 0 1781272576 0.1991866976 0.5285162926 0.8701627254 653 26.0800000000 0.0097206160 0.0090635326 0.0294891559 0.0143816380 0.1927690000 238778298 0 1783054336 0.1943673342 0.5291032791 0.8720518947 654 26.1200000000 0.0102197323 0.0090653005 0.0294891559 0.0143819761 0.1929960000 238778456 0 1784684544 0.1895963848 0.5302208662 0.8750425577 655 26.1600000000 0.0093889460 0.0090657946 0.0294891559 0.0143765746 0.1943580000 238779418 0 1786335232 0.1876882613 0.5330971479 0.8763722181 656 26.2000000000 0.0099502932 0.0090671429 0.0294891559 0.0143728930 0.1899960000 238779888 0 1784848384 0.1782047451 0.5384626985 0.8788183928 657 26.2400000000 0.0095593650 0.0090678921 0.0294891559 0.0143689439 0.1842450000 238782370 0 1786589184 0.1759925485 0.5379630923 0.8812181354 658 26.2800000000 0.0068289568 0.0090644895 0.0294891559 0.0143610097 0.1891400000 238784504 0 1785212928 0.1722729206 0.5347635150 0.8830201626 659 26.3200000000 0.0107814269 0.0090670949 0.0294891559 0.0143586512 0.1998930000 238785750 0 1787011072 0.1672308445 0.5432006717 0.8857206106 660 26.3600000000 0.0085841548 0.0090663631 0.0294891559 0.0143548110 0.1926780000 238788184 0 1785364480 0.1674571484 0.5442168117 0.8849512339 661 26.4000000000 0.0066649951 0.0090627302 0.0294891559 0.0143527447 0.1862840000 238788926 0 1784434688 0.1636440456 0.5465956330 0.8843681812 662 26.4400000000 0.0080162464 0.0090611494 0.0294891559 0.0143476222 0.1938630000 238791060 0 1782521856 0.1590806246 0.5495942831 0.8864248395 663 26.4800000000 0.0084532499 0.0090602325 0.0294891559 0.0143445140 0.2273860000 239295922 0 1784037376 0.1558811963 0.5498042107 0.8884624243 664 26.5200000000 0.0078131594 0.0090583544 0.0294891559 0.0143424367 0.4939480000 239266004 0 1786232832 0.1536781043 0.5511680245 0.8886733055 665 26.5600000000 0.0072418018 0.0090556227 0.0294891559 0.0143391271 0.4522470000 239271326 0 1784979456 0.1499203742 0.5523107052 0.8898185492 666 26.6000000000 0.0097069256 0.0090566007 0.0294891559 0.0143340616 0.4117000000 239437084 0 1786912768 0.1455581635 0.5541936159 0.8929032087 667 26.6400000000 0.0078239022 0.0090547525 0.0294891559 0.0143285580 0.4253610000 242018605 0 1783111680 0.1429314464 0.5558267832 0.8921887875 668 26.6800000000 0.0080733895 0.0090532834 0.0294891559 0.0143250318 0.3303660000 243189796 0 1783685120 0.1411272883 0.5594862700 0.8924712539 669 26.7200000000 0.0086808493 0.0090527267 0.0294891559 0.0143200579 0.2763400000 243198950 0 1785540608 0.1357481629 0.5606219172 0.8948447108 670 26.7600000000 0.0078677433 0.0090509581 0.0294891559 0.0143134365 0.4841070000 242776242 0 1784528896 0.1336010098 0.5589659810 0.8960511684 671 26.8000000000 0.0090969913 0.0090510267 0.0294891559 0.0143077584 0.2063120000 239277674 0 1779933184 0.1292638481 0.5582744479 0.8990660906 672 26.8400000000 0.0089785866 0.0090509189 0.0294891559 0.0142993234 0.2056800000 239279588 0 1781809152 0.1252742708 0.5575517416 0.9008476138 673 26.8800000000 0.0090359002 0.0090508966 0.0294891559 0.0142897848 0.2011310000 239282314 0 1783197696 0.1210043132 0.5568725467 0.9025166035 674 26.9200000000 0.0069748643 0.0090478164 0.0294891559 0.0142851569 0.1991890000 239281304 0 1784856576 0.1180519015 0.5549629331 0.9024958611 675 26.9600000000 0.0078452975 0.0090460349 0.0294891559 0.0142804709 0.1944080000 239281982 0 1786634240 0.1126997396 0.5556653738 0.9040363431 676 27.0000000000 0.0083393799 0.0090449896 0.0294891559 0.0142731734 0.2060560000 239282960 0 1783369728 0.1087716073 0.5561957359 0.9054081440 677 27.0400000000 0.0077831522 0.0090431257 0.0294891559 0.0142653327 0.1912700000 239284230 0 1785126912 0.1057256237 0.5564525127 0.9055705667 678 27.0800000000 0.0099676372 0.0090444893 0.0294891559 0.0142580161 0.1966970000 239286520 0 1786634240 0.0975106657 0.5567543507 0.9081788659 679 27.1200000000 0.0092431521 0.0090447819 0.0294891559 0.0142490514 0.1997860000 239288318 0 1783230464 0.0926154107 0.5551073551 0.9087156057 680 27.1600000000 0.0079084989 0.0090431109 0.0294891559 0.0142426606 0.1925830000 239290156 0 1785266176 0.0903976262 0.5540697575 0.9092418551 681 27.2000000000 0.0101276226 0.0090447034 0.0294891559 0.0142379611 0.1944590000 239292482 0 1786642432 0.0856843367 0.5551667213 0.9114392400 682 27.2400000000 0.0074576801 0.0090423764 0.0294891559 0.0142328109 0.1964980000 239293804 0 1783103488 0.0853781998 0.5536876321 0.9099043012 683 27.2800000000 0.0065375138 0.0090387089 0.0294891559 0.0142269988 0.1908250000 239295470 0 1784471552 0.0821246207 0.5521599054 0.9100677967 684 27.3200000000 0.0073349909 0.0090362181 0.0294891559 0.0142177130 0.2247080000 239296660 0 1786134528 0.0751587451 0.5536632538 0.9114617705 685 27.3600000000 0.0077842795 0.0090343905 0.0294891559 0.0142113111 0.1913630000 239300514 0 1784885248 0.0740751475 0.5552407503 0.9124549031 686 27.4000000000 0.0059530865 0.0090298988 0.0294891559 0.0142054526 0.1904820000 239298652 0 1786916864 0.0697518140 0.5517140031 0.9131111503 687 27.4400000000 0.0080449861 0.0090284651 0.0294891559 0.0141999254 0.1943270000 239301026 0 1784905728 0.0639721751 0.5522657633 0.9165984988 688 27.4800000000 0.0092995977 0.0090288592 0.0294891559 0.0141986780 0.1869760000 239303324 0 1786531840 0.0619871914 0.5548909903 0.9181879163 689 27.5200000000 0.0079825623 0.0090273406 0.0294891559 0.0141949003 0.2269260000 239791386 0 1785159680 0.0608059838 0.5560419559 0.9172112942 690 27.5600000000 0.0077971811 0.0090255578 0.0294891559 0.0141885053 0.4626810000 239762232 0 1785233408 0.0578637421 0.5559552908 0.9186044931 691 27.6000000000 0.0072863763 0.0090230409 0.0294891559 0.0141822846 0.4316670000 239765142 0 1783939072 0.0542234182 0.5562455654 0.9190412760 692 27.6400000000 0.0078559387 0.0090213543 0.0294891559 0.0141765869 0.4095480000 239924132 0 1785823232 0.0494323671 0.5577455759 0.9207028747 693 27.6800000000 0.0088059893 0.0090210436 0.0294891559 0.0141709768 0.4373070000 242335049 0 1785356288 0.0476464778 0.5585347414 0.9213525057 694 27.7200000000 0.0074165612 0.0090187316 0.0294891559 0.0141630569 0.3112560000 243971188 0 1784061952 0.0436080098 0.5571353436 0.9226197600 695 27.7600000000 0.0087169269 0.0090182974 0.0294891559 0.0141586339 0.2880530000 243740014 0 1786052608 0.0421734005 0.5588474274 0.9239767194 696 27.8000000000 0.0080426252 0.0090168956 0.0294891559 0.0141517507 0.5498880000 243525022 0 1780498432 0.0353368893 0.5552968979 0.9260141850 697 27.8400000000 0.0086497795 0.0090163688 0.0294891559 0.0141487239 0.2641290000 239774918 0 1781092352 0.0309713073 0.5556324124 0.9277012944 698 27.8800000000 0.0086347330 0.0090158221 0.0294891559 0.0141440183 0.1993730000 239776204 0 1782235136 0.0288865156 0.5570609570 0.9282104373 699 27.9200000000 0.0077855741 0.0090140621 0.0294891559 0.0141382608 0.1997510000 239776858 0 1784528896 0.0258120000 0.5580360889 0.9281587005 700 27.9600000000 0.0076820506 0.0090121592 0.0294891559 0.0141352804 0.1946540000 239777852 0 1786290176 0.0214463286 0.5564855337 0.9300048947 701 28.0000000000 0.0068384847 0.0090090584 0.0294891559 0.0141325140 0.2243840000 239779726 0 1784635392 0.0177658871 0.5570654869 0.9299827218 702 28.0400000000 0.0076788105 0.0090071634 0.0294891559 0.0141281009 0.1969320000 239781692 0 1786687488 0.0133558903 0.5606906414 0.9307401776 703 28.0800000000 0.0083439993 0.0090062201 0.0294891559 0.0141232658 0.1926130000 239783390 0 1783484416 0.0104641896 0.5619249344 0.9322134256 704 28.1200000000 0.0063030575 0.0090023804 0.0294891559 0.0141170492 0.2321850000 240279812 0 1780830208 0.0083122756 0.5591259599 0.9325914979 705 28.1600000000 0.0066400487 0.0089990296 0.0294891559 0.0141118892 0.4880480000 240251778 0 1779314688 0.0053184703 0.5587425828 0.9344816208 706 28.2000000000 0.0060329284 0.0089948283 0.0294891559 0.0141064147 0.4256390000 240249700 0 1780572160 0.0027374364 0.5569684505 0.9350765944 707 28.2400000000 0.0057082875 0.0089901797 0.0294891559 0.0141015813 0.4162860000 240418706 0 1782919168 -0.0004175007 0.5569552779 0.9359581470 708 28.2800000000 0.0054243347 0.0089851432 0.0294891559 0.0140952042 0.4634750000 242512807 0 1785851904 -0.0040935092 0.5562018156 0.9366601110 709 28.3200000000 0.0057117618 0.0089805263 0.0294891559 0.0140886233 0.3251440000 244885710 0 1784492032 -0.0068431422 0.5581390262 0.9379535913 710 28.3600000000 0.0053766556 0.0089754504 0.0294891559 0.0140822002 0.3066820000 244510192 0 1786605568 -0.0099300928 0.5584751368 0.9385503531 711 28.4000000000 0.0043823593 0.0089689904 0.0294891559 0.0140760002 0.2301650000 244555433 0 1783312384 -0.0137754753 0.5570963621 0.9391871095 712 28.4400000000 0.0075769173 0.0089670352 0.0294891559 0.0140715749 0.4979630000 244485410 0 1780838400 -0.0192560554 0.5598784089 0.9422909617 713 28.4800000000 0.0077835629 0.0089653754 0.0294891559 0.0140648841 0.2729370000 240262698 0 1775861760 -0.0233636051 0.5601190329 0.9438270926 714 28.5200000000 0.0080799246 0.0089641353 0.0294891559 0.0140590261 0.1946410000 240264096 0 1777209344 -0.0268698707 0.5605768561 0.9449062943 715 28.5600000000 0.0102999341 0.0089660035 0.0294891559 0.0140515570 0.1915960000 240265386 0 1779503104 -0.0309385359 0.5625233054 0.9477738142 716 28.6000000000 0.0089474712 0.0089659776 0.0294891559 0.0140463381 0.1937960000 240266892 0 1781284864 -0.0356816314 0.5611190200 0.9474934936 717 28.6400000000 0.0087354081 0.0089656560 0.0294891559 0.0140384633 0.2214260000 240267654 0 1782808576 -0.0418140069 0.5603370667 0.9486229420 718 28.6800000000 0.0088881599 0.0089655481 0.0294891559 0.0140333117 0.2291810000 240767492 0 1784475648 -0.0464267768 0.5627561808 0.9482491016 719 28.7200000000 0.0085616494 0.0089649864 0.0294891559 0.0140295320 0.5087290000 240738326 0 1786363904 -0.0495451950 0.5612996817 0.9489540458 720 28.7600000000 0.0079955896 0.0089636400 0.0294891559 0.0140291951 0.4310070000 240740160 0 1785266176 -0.0533889607 0.5612174869 0.9493086934 721 28.8000000000 0.0077871731 0.0089620083 0.0294891559 0.0140248606 0.4242350000 240908278 0 1783627776 -0.0564732179 0.5594320893 0.9510461092 722 28.8400000000 0.0082989661 0.0089610899 0.0294891559 0.0140211260 0.4297710000 243182405 0 1780879360 -0.0609332696 0.5591580868 0.9517925978 723 28.8800000000 0.0087579954 0.0089608090 0.0294891559 0.0140148191 0.2826950000 245789072 0 1780908032 -0.0640003234 0.5595732331 0.9530785680 724 28.9200000000 0.0077164616 0.0089590903 0.0294891559 0.0140071185 0.3117720000 245266072 0 1782902784 -0.0691852123 0.5579742193 0.9532554746 725 28.9600000000 0.0091624558 0.0089593708 0.0294891559 0.0140006375 0.2364620000 245312789 0 1784205312 -0.0730059817 0.5589456558 0.9547524452 726 29.0000000000 0.0095810248 0.0089602271 0.0294891559 0.0139948962 0.4969020000 245242638 0 1781719040 -0.0760242045 0.5589218736 0.9560412169 727 29.0400000000 0.0089838104 0.0089602595 0.0294891559 0.0139894633 0.2548380000 240747622 0 1781248000 -0.0799591243 0.5576617122 0.9573707581 728 29.0800000000 0.0088351592 0.0089600877 0.0294891559 0.0139854720 0.1900880000 240750248 0 1783570432 -0.0821303725 0.5567857027 0.9576778412 729 29.1200000000 0.0088667935 0.0089599597 0.0294891559 0.0139838939 0.2057220000 240751570 0 1785184256 -0.0850555748 0.5565423369 0.9585615396 730 29.1600000000 0.0096127084 0.0089608539 0.0294891559 0.0139823009 0.1965510000 240752716 0 1786834944 -0.0881475285 0.5561160445 0.9600416422 731 29.2000000000 0.0101285735 0.0089624513 0.0294891559 0.0139804089 0.1912060000 240752450 0 1783189504 -0.0929582715 0.5559280515 0.9600989819 732 29.2400000000 0.0090028159 0.0089625065 0.0294891559 0.0139759406 0.2315830000 241230728 0 1780121600 -0.0985740796 0.5546066761 0.9604403973 733 29.2800000000 0.0096561573 0.0089634528 0.0294891559 0.0139717221 0.4938460000 241196298 0 1777057792 -0.1000425965 0.5536338091 0.9614762068 734 29.3200000000 0.0103247529 0.0089653074 0.0294891559 0.0139652093 0.4450090000 241197384 0 1779089408 -0.1018395573 0.5535501242 0.9622494578 735 29.3600000000 0.0089933919 0.0089653456 0.0294891559 0.0139574357 0.4242230000 241366270 0 1780109312 -0.1064741164 0.5517703295 0.9620051980 736 29.4000000000 0.0090572033 0.0089654704 0.0294891559 0.0139521396 0.4127280000 243224639 0 1787080704 -0.1085720211 0.5507470965 0.9617876410 737 29.4400000000 0.0104508577 0.0089674859 0.0294891559 0.0139479824 0.3172330000 246080313 0 1783717888 -0.1104629338 0.5506781340 0.9620485902 738 29.4800000000 0.0083295526 0.0089666215 0.0294891559 0.0139401619 0.3941110000 246008666 0 1782382592 -0.1127545834 0.5464749932 0.9623650312 739 29.5200000000 0.0086323265 0.0089661691 0.0294891559 0.0139348572 0.2449620000 245824601 0 1784172544 -0.1135052815 0.5449564457 0.9626405239 740 29.5600000000 0.0100266524 0.0089676022 0.0294891559 0.0139326645 0.5421660000 245830034 0 1781407744 -0.1139007881 0.5449255109 0.9629110694 741 29.6000000000 0.0097514000 0.0089686599 0.0294891559 0.0139300500 0.2702480000 241203598 0 1781002240 -0.1159384251 0.5435708761 0.9629359245 742 29.6400000000 0.0102673620 0.0089704102 0.0294891559 0.0139264628 0.2219860000 241679316 0 1783169024 -0.1185855493 0.5427753329 0.9639614224 743 29.6800000000 0.0108351670 0.0089729200 0.0294891559 0.0139244510 0.4932690000 241645702 0 1781276672 -0.1199552938 0.5417500138 0.9644027352 744 29.7200000000 0.0096185990 0.0089737878 0.0294891559 0.0139228117 0.4446420000 241647144 0 1783296000 -0.1243556961 0.5364473462 0.9651101828 745 29.7600000000 0.0108484104 0.0089763041 0.0294891559 0.0139168320 0.4218070000 241813742 0 1784692736 -0.1236966848 0.5354916453 0.9659515619 746 29.8000000000 0.0090969671 0.0089764658 0.0294891559 0.0139085473 0.4283830000 243868639 0 1785319424 -0.1260128915 0.5336846709 0.9650490284 747 29.8400000000 0.0100981956 0.0089779675 0.0294891559 0.0139010343 0.3124210000 246693993 0 1783554048 -0.1267886162 0.5324053168 0.9666119814 748 29.8800000000 0.0111093773 0.0089808170 0.0294891559 0.0138919941 0.3960670000 246620878 0 1782321152 -0.1258695722 0.5322234035 0.9666815400 749 29.9200000000 0.0103135360 0.0089825963 0.0294891559 0.0138832451 0.2459960000 246643846 0 1784508416 -0.1297076344 0.5299624801 0.9674674869 750 29.9600000000 0.0084444555 0.0089818788 0.0294891559 0.0138746294 0.5383480000 246431682 0 1779978240 -0.1322385371 0.5280222893 0.9666033983 751 30.0000000000 0.0085487654 0.0089813021 0.0294891559 0.0138658581 0.2169390000 241649202 0 1781145600 -0.1309273243 0.5238754749 0.9681922793 752 30.0400000000 0.0095259678 0.0089820264 0.0294891559 0.0138574002 0.1823570000 241648024 0 1782358016 -0.1299122572 0.5233690739 0.9690699577 753 30.0800000000 0.0097806752 0.0089830870 0.0294891559 0.0138515257 0.2249000000 242077766 0 1783517184 -0.1335474402 0.5229632854 0.9696710706 754 30.1200000000 0.0094940886 0.0089837647 0.0294891559 0.0138442293 0.4641590000 242043584 0 1781927936 -0.1325585693 0.5203795433 0.9710464478 755 30.1600000000 0.0090518631 0.0089838549 0.0294891559 0.0138373062 0.4322280000 242045114 0 1783894016 -0.1320036501 0.5188172460 0.9718403220 756 30.2000000000 0.0093011260 0.0089842746 0.0294891559 0.0138293822 0.3935410000 242046648 0 1785430016 -0.1333889961 0.5181205273 0.9726411700 757 30.2400000000 0.0093778837 0.0089847945 0.0294891559 0.0138219211 0.4084890000 244062473 0 1784942592 -0.1321565658 0.5162886977 0.9740529060 758 30.2800000000 0.0112349521 0.0089877631 0.0294891559 0.0138183291 0.3455730000 247287983 0 1783717888 -0.1318266243 0.5198371410 0.9754344225 759 30.3200000000 0.0102318516 0.0089894022 0.0294891559 0.0138132040 0.3208200000 247279030 0 1782026240 -0.1326340139 0.5175999403 0.9763291478 760 30.3600000000 0.0102017876 0.0089909974 0.0294891559 0.0138118065 0.2648020000 247294548 0 1784504320 -0.1296999156 0.5157081485 0.9770486355 761 30.4000000000 0.0093293283 0.0089914420 0.0294891559 0.0138053179 0.2125490000 247086409 0 1786097664 -0.1301209033 0.5137311220 0.9791476130 762 30.4400000000 0.0095617538 0.0089921905 0.0294891559 0.0137963034 0.4876730000 247012562 0 1778511872 -0.1299504042 0.5124707222 0.9813494086 763 30.4800000000 0.0099774599 0.0089934818 0.0294891559 0.0137873943 0.2859600000 242444270 0 1780699136 -0.1283408552 0.5107674599 0.9828797579 764 30.5200000000 0.0091719506 0.0089937154 0.0294891559 0.0137795634 0.4159150000 242425400 0 1776730112 -0.1267504096 0.5080929995 0.9839089513 765 30.5600000000 0.0105032809 0.0089956887 0.0294891559 0.0137721731 0.3870480000 242424902 0 1778683904 -0.1247074604 0.5074558258 0.9867882133 766 30.6000000000 0.0099959932 0.0089969945 0.0294891559 0.0137683972 0.3490880000 242560652 0 1779941376 -0.1234726757 0.5055953860 0.9875535369 767 30.6400000000 0.0086482847 0.0089965399 0.0294891559 0.0137719779 0.3467930000 244509725 0 1785061376 -0.1201078445 0.5002325773 0.9893845916 768 30.6800000000 0.0091406498 0.0089967275 0.0294891559 0.0137772202 0.3167650000 247804311 0 1785933824 -0.1160404682 0.5002627969 0.9915610552 769 30.7200000000 0.0100292452 0.0089980702 0.0294891559 0.0138329283 0.2369240000 247632080 0 1784737792 -0.1087928116 0.4993569255 0.9955684543 770 30.7600000000 0.0088519817 0.0089978805 0.0294891559 0.0138586933 0.2540600000 247441644 0 1786757120 -0.1059610844 0.4933702946 0.9961283803 771 30.8000000000 0.0093945079 0.0089983949 0.0294891559 0.0138808928 0.2068130000 247432853 0 1782849536 -0.1021103263 0.4913440049 0.9980534315 772 30.8400000000 0.0121837324 0.0090025210 0.0294891559 0.0138985518 0.4571400000 247440458 0 1783992320 -0.1003922671 0.4911222756 1.0016891956 773 30.8800000000 0.0096108820 0.0090033080 0.0294891559 0.0139196909 0.2929580000 242824802 0 1774739456 -0.0965816826 0.4870886207 1.0006449223 774 30.9200000000 0.0097283842 0.0090042448 0.0294891559 0.0139397538 0.4181470000 242803740 0 1776582656 -0.0931734443 0.4828659296 1.0021331310 775 30.9600000000 0.0095168436 0.0090049062 0.0294891559 0.0139559716 0.3339670000 242802530 0 1778409472 -0.0902743936 0.4810262322 1.0026495457 776 31.0000000000 0.0097228913 0.0090058315 0.0294891559 0.0139786977 0.3159600000 242805956 0 1780383744 -0.0873582363 0.4781794250 1.0039144754 777 31.0400000000 0.0095058186 0.0090064750 0.0294891559 0.0139887244 0.3251070000 244680129 0 1783697408 -0.0847548395 0.4751914740 1.0051724911 778 31.0800000000 0.0091427267 0.0090066501 0.0294891559 0.0139951943 0.3297460000 247592911 0 1784328192 -0.0804226995 0.4728456736 1.0063618422 779 31.1200000000 0.0091875512 0.0090068823 0.0294891559 0.0139931894 0.2192530000 247838190 0 1784754176 -0.0773130357 0.4684197903 1.0091516972 780 31.1600000000 0.0084650870 0.0090061877 0.0294891559 0.0139879774 0.2594250000 247598098 0 1786351616 -0.0741847157 0.4649067819 1.0106580257 781 31.2000000000 0.0088678133 0.0090060105 0.0294891559 0.0139836377 0.2024420000 247469365 0 1783357440 -0.0726791620 0.4618014693 1.0121378899 782 31.2400000000 0.0090309028 0.0090060424 0.0294891559 0.0139800239 0.4325690000 247471630 0 1784950784 -0.0678861439 0.4565480649 1.0162150860 783 31.2800000000 0.0095529892 0.0090067409 0.0294891559 0.0139760893 0.2598180000 243208478 0 1781452800 -0.0668122768 0.4533827901 1.0177602768 784 31.3200000000 0.0090071047 0.0090067413 0.0294891559 0.0139726839 0.3834680000 243189032 0 1777717248 -0.0640678108 0.4489920735 1.0188442469 785 31.3600000000 0.0102052726 0.0090082681 0.0294891559 0.0139671343 0.3221380000 243186590 0 1780285440 -0.0621684492 0.4448797405 1.0219373703 786 31.4000000000 0.0106863119 0.0090104030 0.0294891559 0.0139611105 0.2980760000 243181464 0 1781518336 -0.0616388917 0.4418849051 1.0230495930 787 31.4400000000 0.0086178472 0.0090099042 0.0294891559 0.0139526210 0.3032300000 245057265 0 1784451072 -0.0586611331 0.4338006377 1.0237823725 788 31.4800000000 0.0098694526 0.0090109950 0.0294891559 0.0139492534 0.3168590000 246834659 0 1784315904 -0.0579800308 0.4297470748 1.0260492563 789 31.5200000000 0.0100461114 0.0090123070 0.0294891559 0.0139478617 0.1928070000 248649662 0 1784619008 -0.0564594567 0.4254912734 1.0277705193 790 31.5600000000 0.0108134858 0.0090145870 0.0294891559 0.0139470206 0.2907670000 248226162 0 1783271424 -0.0558353662 0.4194157124 1.0295141935 791 31.6000000000 0.0108477138 0.0090169044 0.0294891559 0.0139722429 0.1796180000 248401590 0 1785126912 -0.0529835224 0.4113171697 1.0329359770 792 31.6400000000 0.0090463795 0.0090169417 0.0294891559 0.0139672094 0.1704660000 248134747 0 1786777600 -0.0522862375 0.4050090611 1.0340850353 793 31.6800000000 0.0101731122 0.0090183996 0.0294891559 0.0139638670 0.3935110000 248051588 0 1779548160 -0.0523675978 0.4002228379 1.0356193781 794 31.7200000000 0.0095423786 0.0090190595 0.0294891559 0.0139597233 0.2535830000 243467876 0 1773645824 -0.0510397553 0.3987877667 1.0370433331 795 31.7600000000 0.0087853223 0.0090187655 0.0294891559 0.0139536731 0.3063590000 243448438 0 1775702016 -0.0505570769 0.3967792094 1.0384092331 796 31.8000000000 0.0090978649 0.0090188649 0.0294891559 0.0139499869 0.2667710000 243449612 0 1776947200 -0.0497282743 0.3915539980 1.0411968231 797 31.8400000000 0.0101414826 0.0090202735 0.0294891559 0.0139566933 0.2551090000 243532694 0 1778999296 -0.0498585403 0.3877753019 1.0432513952 798 31.8800000000 0.0087737367 0.0090199645 0.0294891559 0.0140120194 0.2661760000 245925407 0 1785843712 -0.0497108102 0.3678470850 1.0486314297 799 31.9200000000 0.0095221028 0.0090205930 0.0294891559 0.0140226658 0.2266500000 248964319 0 1783971840 -0.0482611954 0.3598056436 1.0528638363 800 31.9600000000 0.0097515751 0.0090215067 0.0294891559 0.0140363652 0.1655010000 248439307 0 1783054336 -0.0499943793 0.3562223315 1.0541170835 801 32.0000000000 0.0085574985 0.0090209274 0.0294891559 0.0140299735 0.2485990000 248351860 0 1784573952 -0.0509505570 0.3506764174 1.0563744307 802 32.0400000000 0.0089718727 0.0090208663 0.0294891559 0.0140213897 0.1585190000 248172011 0 1786605568 -0.0515296459 0.3433250189 1.0594048500 803 32.0800000000 0.0098750023 0.0090219299 0.0294891559 0.0140129937 0.1354960000 248249953 0 1783066624 -0.0522741079 0.3348852098 1.0629982948 804 32.1199999990 0.0094740856 0.0090224923 0.0294891559 0.0140072142 0.3412980000 248160514 0 1781829632 -0.0565303564 0.3164177537 1.0694459677 805 32.1600000000 0.0087412838 0.0090221430 0.0294891559 0.0139990415 0.2290710000 243438954 0 1778442240 -0.0554842651 0.3124800622 1.0732842684 806 32.2000000000 0.0098659322 0.0090231899 0.0294891559 0.0139908266 0.1391880000 243639660 0 1778941952 -0.0594013333 0.3074612617 1.0758831501 807 32.2400000000 0.0125303082 0.0090275357 0.0294891559 0.0139843252 0.2669460000 243638146 0 1774321664 -0.0609168112 0.3031832576 1.0802813768 808 32.2800000000 0.0109985555 0.0090299751 0.0294891559 0.0139793937 0.2143340000 243636888 0 1776910336 -0.0606468916 0.2960414290 1.0843396187 809 32.3200000000 0.0102553926 0.0090314899 0.0294891559 0.0139710537 0.2109550000 245370729 0 1779908608 -0.0605798066 0.2823170424 1.0886845589 810 32.3600000000 0.0093142726 0.0090318390 0.0294891559 0.0139625153 0.2103630000 246299383 0 1785831424 -0.0605469048 0.2686658800 1.0937132835 811 32.4000000000 0.0083819153 0.0090310376 0.0294891559 0.0139555734 0.1592250000 248617541 0 1786200064 -0.0637625456 0.2643141150 1.0962188244 812 32.4399999990 0.0097678667 0.0090319450 0.0294891559 0.0139484293 0.1416460000 248618847 0 1783427072 -0.0654147565 0.2606737912 1.1002843380 813 32.4800000000 0.0113938330 0.0090348502 0.0294891559 0.0139421345 0.2123130000 248514236 0 1782358016 -0.0668320060 0.2524439394 1.1062974930 814 32.5200000000 0.0098656798 0.0090358708 0.0294891559 0.0139355537 0.1458720000 248899174 0 1784700928 -0.0677317679 0.2393141836 1.1110937595 815 32.5600000000 0.0096149035 0.0090365813 0.0294891559 0.0139289565 0.3590760000 248496416 0 1786454016 -0.0665597916 0.2310869396 1.1148120165 816 32.6000000000 0.0099771805 0.0090377340 0.0294891559 0.0139209442 0.2391430000 243793448 0 1781452800 -0.0694964230 0.2234188914 1.1206347942 817 32.6400000000 0.0096200798 0.0090384468 0.0294891559 0.0139157857 0.2104550000 243817998 0 1777057792 -0.0718123615 0.2092222571 1.1273581982 818 32.6800000000 0.0102200052 0.0090398912 0.0294891559 0.0139086549 0.2000140000 243817448 0 1778827264 -0.0692350566 0.1942298114 1.1350502968 819 32.7200000000 0.0107737798 0.0090420083 0.0294891559 0.0139013060 0.2028110000 245821780 0 1781571584 -0.0731498599 0.1836081445 1.1403825283 820 32.7599999990 0.0131920408 0.0090470693 0.0294891559 0.0138950765 0.2461280000 246090706 0 1783906304 -0.0738803148 0.1812310815 1.1444307566 821 32.7999999990 0.0130583253 0.0090519551 0.0294891559 0.0138868245 0.2395940000 244232351 0 1782738944 -0.0766314268 0.1715696454 1.1495528221 822 32.8400000000 0.0110820485 0.0090544248 0.0294891559 0.0138789461 0.2188160000 243992652 0 1777672192 -0.0748977363 0.1589622051 1.1536736488 823 32.8800000000 0.0117142852 0.0090576568 0.0294891559 0.0138727263 0.1992910000 243992230 0 1779712000 -0.0753519833 0.1472598761 1.1597757339 824 32.9200000000 0.0118013499 0.0090609865 0.0294891559 0.0138653457 0.1858440000 244043328 0 1781489664 -0.0745251775 0.1366962492 1.1653498411 825 32.9600000000 0.0096807824 0.0090617377 0.0294891559 0.0138595690 0.2064980000 246542896 0 1787133952 -0.0749308467 0.1250066906 1.1690831184 826 33.0000000000 0.0144716473 0.0090682873 0.0294891559 0.0138537153 0.2307580000 246801266 0 1784033280 -0.0758254230 0.1214352548 1.1747057438 827 33.0400000000 0.0103924070 0.0090698884 0.0294891559 0.0138500698 0.2055790000 244133714 0 1785933824 -0.0750641823 0.1069030762 1.1787359715 828 33.0800000000 0.0126218246 0.0090741782 0.0294891559 0.0138438210 0.2213030000 244149940 0 1781235712 -0.0737322271 0.1013431847 1.1837127209 829 33.1199999990 0.0107644992 0.0090762172 0.0294891559 0.0138408937 0.1961330000 244307305 0 1782886400 -0.0740035474 0.0890561938 1.1865165234 830 33.1600000000 0.0142074367 0.0090823993 0.0294891559 0.0138382322 0.2073570000 244393263 0 1784524800 -0.0725075603 0.0795210004 1.1924040318 831 33.2000000000 0.0132251931 0.0090873847 0.0294891559 0.0138312119 0.1879190000 244434314 0 1786580992 -0.0723425448 0.0671985000 1.1959595680 832 33.2400000000 0.0108401822 0.0090894914 0.0294891559 0.0138310515 0.1976400000 244508539 0 1783750656 -0.0723492801 0.0566992648 1.1975752115 833 33.2800000000 0.0135556832 0.0090948530 0.0294891559 0.0138240858 0.1813690000 244545730 0 1785298944 -0.0749472678 0.0484233573 1.2026940584 834 33.3200000000 0.0109535698 0.0090970816 0.0294891559 0.0138198998 0.1995980000 244633819 0 1785139200 -0.0728025138 0.0368923992 1.2052860260 835 33.3600000000 0.0135858981 0.0091024575 0.0294891559 0.0138133103 0.1869810000 244645214 0 1781886976 -0.0702365637 0.0331580564 1.2073279619 836 33.4000000000 0.0125626223 0.0091065964 0.0294891559 0.0138090270 0.1882820000 244651608 0 1781010432 -0.0706211627 0.0234453864 1.2103712559 837 33.4399999990 0.0138281863 0.0091122375 0.0294891559 0.0138046296 0.1746240000 246728492 0 1783140352 -0.0721391737 0.0135474168 1.2133154869 838 33.4800000000 0.0133384066 0.0091172807 0.0294891559 0.0137998077 0.1929200000 247614039 0 1786208256 -0.0717895329 0.0027206894 1.2158415318 839 33.5200000000 0.0121247675 0.0091208653 0.0294891559 0.0137927724 0.2161900000 247426234 0 1783545856 -0.0689314306 -0.0064366274 1.2179632187 840 33.5600000000 0.0119251972 0.0091242038 0.0294891559 0.0137849030 0.1774150000 244745111 0 1782423552 -0.0684888363 -0.0128978305 1.2186239958 841 33.6000000000 0.0133987069 0.0091292864 0.0294891559 0.0137840014 0.1838020000 244846253 0 1777377280 -0.0646835566 -0.0237393100 1.2234280109 842 33.6400000000 0.0124459462 0.0091332254 0.0294891559 0.0137769514 0.1748830000 244857828 0 1778114560 -0.0641143918 -0.0378850102 1.2268552780 843 33.6800000000 0.0124785574 0.0091371938 0.0294891559 0.0137702069 0.1744630000 244975685 0 1780740096 -0.0652828217 -0.0443930179 1.2273460627 844 33.7200000000 0.0141054131 0.0091430803 0.0294891559 0.0137655351 0.1695410000 244963844 0 1781997568 -0.0656911731 -0.0498441309 1.2276511192 845 33.7599999990 0.0133451996 0.0091480532 0.0294891559 0.0137723041 0.1670960000 245073097 0 1784029184 -0.0606047809 -0.0604415238 1.2304251194 846 33.7999999990 0.0113487439 0.0091506545 0.0294891559 0.0137723546 0.1944170000 245058943 0 1785552896 -0.0595712662 -0.0673484653 1.2297959328 847 33.8400000000 0.0134261949 0.0091557024 0.0294891559 0.0137694866 0.1673320000 247395292 0 1786454016 -0.0614910722 -0.0711275041 1.2304518223 848 33.8800000000 0.0120662125 0.0091591346 0.0294891559 0.0137695157 0.1810160000 248198926 0 1786454016 -0.0573530793 -0.0837199613 1.2337903976 849 33.9200000000 0.0132580977 0.0091639626 0.0294891559 0.0137623727 0.1890690000 248018270 0 1784061952 -0.0610470772 -0.0904083624 1.2344782352 850 33.9600000000 0.0136080151 0.0091691909 0.0294891559 0.0137566137 0.1779940000 245203903 0 1781567488 -0.0643208623 -0.0945928171 1.2329952717 851 34.0000000000 0.0144797387 0.0091754312 0.0294891559 0.0137494366 0.1755840000 245226394 0 1774522368 -0.0649773479 -0.1004825979 1.2335364819 852 34.0400000000 0.0119275711 0.0091786615 0.0294891559 0.0137463528 0.1676340000 245338615 0 1776254976 -0.0586394370 -0.1061125249 1.2327456474 853 34.0800000000 0.0137653239 0.0091840386 0.0294891559 0.0137396097 0.1793620000 245410069 0 1777913856 -0.0636793673 -0.1092046052 1.2324159145 854 34.1199999990 0.0122637143 0.0091876447 0.0294891559 0.0137426796 0.1687030000 245424803 0 1779515392 -0.0632487535 -0.1180554181 1.2324748039 855 34.1600000000 0.0135476273 0.0091927441 0.0294891559 0.0137353709 0.1642260000 245534069 0 1781481472 -0.0611493886 -0.1217586547 1.2337009907 856 34.2000000000 0.0131455865 0.0091973619 0.0294891559 0.0137301228 0.1584830000 245519583 0 1783271424 -0.0619151592 -0.1237675324 1.2314198017 857 34.2400000000 0.0146837858 0.0092037638 0.0294891559 0.0137245947 0.1610270000 247954024 0 1785925632 -0.0646784306 -0.1262354255 1.2314875126 858 34.2800000000 0.0134144155 0.0092086713 0.0294891559 0.0137293973 0.1785760000 248787786 0 1786089472 -0.0617861152 -0.1300495565 1.2306900024 859 34.3200000000 0.0113934698 0.0092112148 0.0294891559 0.0137418195 0.2011930000 246348267 0 1784659968 -0.0572124124 -0.1330603063 1.2284772396 860 34.3600000000 0.0120649869 0.0092145331 0.0294891559 0.0137386809 0.1685350000 245593904 0 1778892800 -0.0561314225 -0.1348412931 1.2275446653 861 34.4000000000 0.0131323226 0.0092190834 0.0294891559 0.0137326668 0.1779740000 245696405 0 1779949568 -0.0573808849 -0.1349909902 1.2258547544 862 34.4400000000 0.0120634958 0.0092223832 0.0294891559 0.0137449264 0.1671580000 245710356 0 1781792768 -0.0561994314 -0.1394895017 1.2252948284 863 34.4800000000 0.0132962484 0.0092271038 0.0294891559 0.0137519942 0.1802130000 245837565 0 1783500800 -0.0533722639 -0.1413781047 1.2246025801 864 34.5200000000 0.0132322730 0.0092317394 0.0294891559 0.0137568743 0.1831320000 245915123 0 1785290752 -0.0533636212 -0.1412067115 1.2224286795 865 34.5600000000 0.0129401647 0.0092360266 0.0294891559 0.0137599460 0.1809810000 245932146 0 1784471552 -0.0527819097 -0.1428404748 1.2207736969 866 34.6000000000 0.0146017345 0.0092422225 0.0294891559 0.0137570985 0.1756530000 246052423 0 1783062528 -0.0529336333 -0.1457937062 1.2208174467 867 34.6400000000 0.0129984524 0.0092465550 0.0294891559 0.0137546050 0.1889230000 246135285 0 1782362112 -0.0499206781 -0.1490146965 1.2206623554 868 34.6800000000 0.0132342922 0.0092511491 0.0294891559 0.0137483699 0.1844710000 246150712 0 1784553472 -0.0507173836 -0.1499127746 1.2183744907 869 34.7200000000 0.0132344887 0.0092557330 0.0294891559 0.0137422917 0.1828880000 246267393 0 1786101760 -0.0503270924 -0.1531042606 1.2187132835 870 34.7600000000 0.0129379919 0.0092599654 0.0294891559 0.0137365359 0.1923470000 249516559 0 1785409536 -0.0471213460 -0.1549786776 1.2173502445 871 34.8000000000 0.0129391784 0.0092641896 0.0294891559 0.0137310978 0.2022920000 249769024 0 1784455168 -0.0475497544 -0.1586997211 1.2164993286 872 34.8400000000 0.0137965074 0.0092693872 0.0294891559 0.0137248020 0.2137960000 246309411 0 1783054336 -0.0477911532 -0.1618041396 1.2163462639 873 34.8800000000 0.0149878664 0.0092759376 0.0294891559 0.0137173643 0.1719080000 246310974 0 1777602560 -0.0464444458 -0.1629841328 1.2164243460 874 34.9200000000 0.0141761955 0.0092815443 0.0294891559 0.0137115663 0.1820950000 246416059 0 1779843072 -0.0487195849 -0.1665388048 1.2147313356 875 34.9600000000 0.0147517687 0.0092877959 0.0294891559 0.0137042417 0.1695410000 246507329 0 1780785152 -0.0489960313 -0.1693219244 1.2146841288 876 35.0000000000 0.0181706883 0.0092979362 0.0294891559 0.0136972304 0.1767940000 246607643 0 1783386112 -0.0507873893 -0.1691564322 1.2137676477 877 35.0400000000 0.0155686261 0.0093050864 0.0294891559 0.0136912495 0.1742950000 246696905 0 1785036800 -0.0508748293 -0.1745900512 1.2127633095 878 35.0800000000 0.0148922550 0.0093114499 0.0294891559 0.0136854029 0.1596400000 246704747 0 1784594432 -0.0459323823 -0.1764738560 1.2116432190 879 35.1200000000 0.0182318836 0.0093215983 0.0294891559 0.0136809194 0.1696870000 246824165 0 1784037376 -0.0534077585 -0.1800699979 1.2110794783 880 35.1600000000 0.0152171627 0.0093282978 0.0294891559 0.0136737882 0.1747430000 246891379 0 1781231616 -0.0516866446 -0.1871077716 1.2085179090 881 35.2000000000 0.0162707139 0.0093361780 0.0294891559 0.0136680664 0.1734670000 246987101 0 1779556352 -0.0504716337 -0.1859678179 1.2066299915 882 35.2400000000 0.0146182692 0.0093421667 0.0294891559 0.0136609135 0.1648970000 246996115 0 1779027968 -0.0488100946 -0.1898523867 1.2058666945 883 35.2800000000 0.0129055297 0.0093462022 0.0294891559 0.0136561706 0.1565230000 247021057 0 1780846592 -0.0482706130 -0.1936557293 1.2033315897 884 35.3200000000 0.0130188325 0.0093503568 0.0294891559 0.0136538519 0.1722700000 249947574 0 1785556992 -0.0496956408 -0.1966812313 1.2027713060 885 35.3600000000 0.0127388295 0.0093541856 0.0294891559 0.0136538016 0.1979340000 250204592 0 1783771136 -0.0499978662 -0.1995700300 1.2021571398 886 35.4000000000 0.0101705752 0.0093551070 0.0294891559 0.0136521065 0.2148010000 247334965 0 1782820864 -0.0488909781 -0.2024919391 1.1990981102 887 35.4400000000 0.0130384630 0.0093592596 0.0294891559 0.0136617082 0.1827060000 247126502 0 1784930304 -0.0516217649 -0.2013177276 1.1977851391 888 35.4800000000 0.0123200193 0.0093625938 0.0294891559 0.0136621906 0.1684360000 247151503 0 1779982336 -0.0528972745 -0.2042801082 1.1958504915 889 35.5200000000 0.0147037832 0.0093686019 0.0294891559 0.0136781980 0.1609060000 247248009 0 1781452800 -0.0559121370 -0.2045369893 1.1944704056 890 35.5600000000 0.0119227534 0.0093714717 0.0294891559 0.0136771943 0.1792210000 250161038 0 1785180160 -0.0546047390 -0.2067383528 1.1925984621 891 35.6000000000 0.0100729968 0.0093722591 0.0294891559 0.0136774212 0.2150710000 250408616 0 1784008704 -0.0544542372 -0.2108917683 1.1909748316 892 35.6400000000 0.0128230713 0.0093761277 0.0294891559 0.0136974499 0.1802900000 247308336 0 1780670464 -0.0571838617 -0.2092894167 1.1889023781 893 35.6800000000 0.0128276488 0.0093799928 0.0294891559 0.0137053247 0.1572360000 247326497 0 1777598464 -0.0615872443 -0.2120695859 1.1869912148 894 35.7200000000 0.0125908796 0.0093835844 0.0294891559 0.0137225331 0.1485890000 247352671 0 1779884032 -0.0605852604 -0.2128891349 1.1866520643 895 35.7600000000 0.0104858894 0.0093848160 0.0294891559 0.0137301140 0.1671700000 250077220 0 1784307712 -0.0602980256 -0.2163338065 1.1849514246 896 35.8000000000 0.0119449710 0.0093876733 0.0294891559 0.0137535562 0.1762590000 250337034 0 1783652352 -0.0641679764 -0.2167033255 1.1837196350 897 35.8400000000 0.0093619451 0.0093876446 0.0294891559 0.0137631394 0.1783820000 247595589 0 1782157312 -0.0603080690 -0.2171230912 1.1833113432 898 35.8800000000 0.0135708954 0.0093923030 0.0294891559 0.0137855881 0.1682970000 247489779 0 1775558656 -0.0658366382 -0.2151191682 1.1822650433 899 35.9200000000 0.0086692404 0.0093914987 0.0294891559 0.0137817630 0.1696540000 247588709 0 1776775168 -0.0597360134 -0.2184725404 1.1822161674 900 35.9600000000 0.0118718194 0.0093942547 0.0294891559 0.0137920410 0.1532440000 247601715 0 1779236864 -0.0570202172 -0.2155309319 1.1817374229 901 36.0000000000 0.0125190811 0.0093977228 0.0294891559 0.0138044662 0.1583050000 247704473 0 1780916224 -0.0607292354 -0.2152067870 1.1805646420 902 36.0400000000 0.0105422400 0.0093989917 0.0294891559 0.0138079370 0.1627520000 250437014 0 1786822656 -0.0607790947 -0.2174360603 1.1793541908 903 36.0800000000 0.0101966923 0.0093998751 0.0294891559 0.0138166309 0.1779070000 250660416 0 1785360384 -0.0638509095 -0.2182675302 1.1780154705 904 36.1200000000 0.0117436051 0.0094024677 0.0294891559 0.0138370702 0.1760690000 247677015 0 1784352768 -0.0639502406 -0.2176740617 1.1776157618 905 36.1600000000 0.0114620402 0.0094047435 0.0294891559 0.0138584624 0.1601380000 247689729 0 1779269632 -0.0647737980 -0.2183125913 1.1764566898 906 36.2000000000 0.0138001600 0.0094095949 0.0294891559 0.0138911114 0.1588520000 247792763 0 1781325824 -0.0707165003 -0.2164154947 1.1752331257 907 36.2400000000 0.0132018728 0.0094137761 0.0294891559 0.0139109917 0.1696320000 250462484 0 1785053184 -0.0716791153 -0.2184946835 1.1749595404 908 36.2800000000 0.0121615576 0.0094168022 0.0294891559 0.0139204829 0.1851750000 250703562 0 1785229312 -0.0675528646 -0.2187512070 1.1747994423 909 36.3200000000 0.0115548391 0.0094191543 0.0294891559 0.0139283819 0.1590250000 247766569 0 1784590336 -0.0736818314 -0.2198977470 1.1735210419 910 36.3600000000 0.0138344523 0.0094240063 0.0294891559 0.0139456778 0.1462670000 247774715 0 1778855936 -0.0762075186 -0.2182656527 1.1731828451 911 36.4000000000 0.0145830903 0.0094296694 0.0294891559 0.0139542389 0.1392980000 248015930 0 1780854784 -0.0777676702 -0.2188023329 1.1731848717 912 36.4400000000 0.0142774563 0.0094349850 0.0294891559 0.0139584631 0.1657530000 250596750 0 1784668160 -0.0777054429 -0.2200945020 1.1733903885 913 36.4800000000 0.0139535246 0.0094399341 0.0294891559 0.0140283787 0.1624740000 250405898 0 1784725504 -0.0820941925 -0.2207561582 1.1716294289 914 36.5200000000 0.0122836279 0.0094430453 0.0294891559 0.0140375919 0.1487620000 247870703 0 1786454016 -0.0803461075 -0.2226998508 1.1721391678 915 36.5600000000 0.0109155094 0.0094446546 0.0294891559 0.0140518588 0.1593010000 247992089 0 1779916800 -0.0838395357 -0.2246781588 1.1717681885 916 36.6000000000 0.0112945400 0.0094466741 0.0294891559 0.0140701426 0.1674610000 248095399 0 1781665792 -0.0868141055 -0.2245611250 1.1709064245 917 36.6400000000 0.0134079112 0.0094509939 0.0294891559 0.0140882673 0.1768960000 248173153 0 1783316480 -0.0896604657 -0.2233581394 1.1716872454 918 36.6800000000 0.0120227532 0.0094537954 0.0294891559 0.0140951886 0.1561280000 248184967 0 1784967168 -0.0913495421 -0.2250844091 1.1703150272 919 36.7200000000 0.0130440202 0.0094577020 0.0294891559 0.0141181477 0.1634930000 248858026 0 1786765312 -0.0932994485 -0.2248198837 1.1708492041 920 36.7600000000 0.0128802611 0.0094614222 0.0294891559 0.0141348881 0.1799340000 251444843 0 1784438784 -0.0955004096 -0.2251404375 1.1705164909 921 36.8000000000 0.0122281052 0.0094644262 0.0294891559 0.0141395581 0.2014640000 251261674 0 1782640640 -0.0959287882 -0.2261782736 1.1711809635 922 36.8400000000 0.0103625944 0.0094654004 0.0294891559 0.0141395269 0.1755770000 248357431 0 1781743616 -0.0946308374 -0.2280926406 1.1717803478 923 36.8800000000 0.0114922151 0.0094675963 0.0294891559 0.0141523615 0.1721780000 248382678 0 1777790976 -0.0986688137 -0.2275810093 1.1718090773 924 36.9200000000 0.0128787635 0.0094712880 0.0294891559 0.0141594634 0.1734560000 248513359 0 1779281920 -0.1008902192 -0.2270206660 1.1727735996 925 36.9600000000 0.0117868651 0.0094737913 0.0294891559 0.0141580283 0.1806360000 248607125 0 1780912128 -0.1017538309 -0.2277569324 1.1724386215 926 37.0000000000 0.0109653696 0.0094754021 0.0294891559 0.0141596273 0.1880350000 248616335 0 1782538240 -0.1037542224 -0.2289675027 1.1722127199 927 37.0400000000 0.0117694959 0.0094778768 0.0294891559 0.0141675579 0.1850520000 251331488 0 1785307136 -0.1046640277 -0.2287601382 1.1730616093 928 37.0800000000 0.0116239088 0.0094801894 0.0294891559 0.0141802904 0.2028060000 251592598 0 1785311232 -0.1074030995 -0.2285234928 1.1722774506 929 37.1200000000 0.0139909973 0.0094850449 0.0294891559 0.0142020436 0.1896660000 248776339 0 1783779328 -0.1099560857 -0.2254275978 1.1717340946 930 37.1600000000 0.0117271720 0.0094874558 0.0294891559 0.0142028210 0.1548740000 248688951 0 1778970624 -0.1104143858 -0.2271747738 1.1715104580 931 37.2000000000 0.0115039619 0.0094896218 0.0294891559 0.0142070128 0.1674800000 248799513 0 1780056064 -0.1109229922 -0.2275325656 1.1718212366 932 37.2400000000 0.0133851320 0.0094938015 0.0294891559 0.0142334199 0.1542910000 248807055 0 1782251520 -0.1139382124 -0.2261482328 1.1713824272 933 37.2800000000 0.0130919302 0.0094976580 0.0294891559 0.0142580270 0.1568100000 251223916 0 1787469824 -0.1169028878 -0.2264002115 1.1699970961 934 37.3200000000 0.0120083205 0.0095003461 0.0294891559 0.0142759397 0.1539090000 252031730 0 1785962496 -0.1172283888 -0.2255406529 1.1693019867 935 37.3600000000 0.0139267053 0.0095050802 0.0294891559 0.0142976785 0.1052820000 254260038 0 1785348096 -0.1195837855 -0.2231286317 1.1681144238 936 37.4000000000 0.0129236588 0.0095087325 0.0294891559 0.0143058540 0.1001470000 253825270 0 1784385536 -0.1193644404 -0.2237178385 1.1680316925 937 37.4400000000 0.0142975645 0.0095138433 0.0294891559 0.0143182519 0.1493860000 253627752 0 1783414784 -0.1210017204 -0.2208597511 1.1679365635 938 37.4800000000 0.0142026208 0.0095188420 0.0294891559 0.0143205871 0.0980640000 254105664 0 1785499648 -0.1255586147 -0.2212608010 1.1658232212 939 37.5200000000 0.0147014409 0.0095243613 0.0294891559 0.0143264945 0.0944360000 253540090 0 1784573952 -0.1258593202 -0.2205262482 1.1663358212 940 37.5600000000 0.0137142967 0.0095288187 0.0294891559 0.0143254562 0.0946840000 253514296 0 1783521280 -0.1260332465 -0.2212154269 1.1663889885 941 37.6000000000 0.0164908897 0.0095362173 0.0294891559 0.0143279217 0.2621740000 253473128 0 1781645312 -0.1368876100 -0.2298607677 1.1680797338 942 37.6400000000 0.0171637405 0.0095443144 0.0294891559 0.0143269894 0.1448860000 248798231 0 1780514816 -0.1399970055 -0.2302090228 1.1653145552 943 37.6800000000 0.0158713628 0.0095510239 0.0294891559 0.0143288288 0.1063690000 248865981 0 1782124544 -0.1384605765 -0.2315423191 1.1665561199 944 37.7200000000 0.0161651783 0.0095580304 0.0294891559 0.0143335429 0.1268270000 249353042 0 1778249728 -0.1402386427 -0.2308365256 1.1659307480 945 37.7600000000 0.0167098343 0.0095655985 0.0294891559 0.0143345176 0.0905710000 249141654 0 1779761152 -0.1421384215 -0.2310721725 1.1677129269 946 37.8000000000 0.0167505257 0.0095731935 0.0294891559 0.0143406396 0.0894600000 248866151 0 1780809728 -0.1437351704 -0.2305867821 1.1667029858 947 37.8400000000 0.0165623762 0.0095805739 0.0294891559 0.0143436129 0.1022890000 248945533 0 1782460416 -0.1449167728 -0.2296134382 1.1663304567 948 37.8800000000 0.0166344997 0.0095880147 0.0294891559 0.0143410449 0.1361680000 249414818 0 1784348672 -0.1460788250 -0.2306267917 1.1686890125 949 37.9200000000 0.0167453848 0.0095955567 0.0294891559 0.0143468510 0.0766300000 249113298 0 1786507264 -0.1475090384 -0.2234692425 1.1772868633 950 37.9600000000 0.0160618499 0.0096023634 0.0294891559 0.0143436378 0.0869290000 248947707 0 1783914496 -0.1484804749 -0.2206450105 1.1872259378 951 38.0000000000 0.0155398371 0.0096086068 0.0294891559 0.0143427514 0.0987990000 248948989 0 1782898688 -0.1495540738 -0.2198714167 1.1900756359 952 38.0400000000 0.0163868386 0.0096157267 0.0294891559 0.0143414126 0.0905400000 248951467 0 1783410688 -0.1515675783 -0.2197525054 1.1905195713 953 38.0800000000 0.0162789281 0.0096227186 0.0294891559 0.0143441813 0.0728340000 248953593 0 1782648832 -0.1525082588 -0.2174634188 1.1905620098 954 38.1200000000 0.0161805768 0.0096295926 0.0294891559 0.0143410656 0.0788180000 248956163 0 1781760000 -0.1541370153 -0.2178786546 1.1909673214 955 38.1600000000 0.0163223706 0.0096366008 0.0294891559 0.0143514598 0.0770940000 248956525 0 1780744192 -0.1523728073 -0.2157871574 1.1920009851 956 38.2000000000 0.0159711000 0.0096432268 0.0294891559 0.0143496833 0.0762680000 248958483 0 1779609600 -0.1545897126 -0.2163142562 1.1912772655 957 38.2400000000 0.0159442164 0.0096498109 0.0294891559 0.0143469906 0.0755070000 248960593 0 1778212864 -0.1558372378 -0.2166215926 1.1903754473 958 38.2800000000 0.0162437335 0.0096566939 0.0294891559 0.0143468624 0.0792860000 248961599 0 1776328704 -0.1576033831 -0.2171057612 1.1860713959 959 38.3200000000 0.0158169139 0.0096631175 0.0294891559 0.0143439445 0.0979900000 248963433 0 1774264320 -0.1578541398 -0.2179544419 1.1859815121 960 38.3600000000 0.0159276221 0.0096696430 0.0294891559 0.0143478461 0.1125780000 249063563 0 1772871680 -0.1582430601 -0.2145370245 1.1881861687 961 38.4000000000 0.0159384646 0.0096761663 0.0294891559 0.0143450999 0.1473500000 249621988 0 1772158976 -0.1594992876 -0.2145912945 1.1861650944 962 38.4400000000 0.0158115737 0.0096825440 0.0294891559 0.0143395786 0.0888350000 249513578 0 1774284800 -0.1602317095 -0.2163053751 1.1862256527 963 38.4800000000 0.0154531747 0.0096885364 0.0294891559 0.0143377392 0.0798850000 249068137 0 1774653440 -0.1608896852 -0.2164027989 1.1829787493 964 38.5200000000 0.0157942679 0.0096948701 0.0294891559 0.0143389079 0.0726220000 249070447 0 1776689152 -0.1636435091 -0.2149734646 1.1828427315 965 38.5600000000 0.0150171667 0.0097003855 0.0294891559 0.0143346038 0.0846260000 249072097 0 1778339840 -0.1638174653 -0.2158971727 1.1812748909 966 38.6000000000 0.0157490578 0.0097066470 0.0294891559 0.0143360470 0.0822810000 249074943 0 1780101120 -0.1650292277 -0.2153609395 1.1814430952 967 38.6400000000 0.0151353627 0.0097122610 0.0294891559 0.0143329812 0.1080380000 249182081 0 1781768192 -0.1666389108 -0.2148479521 1.1826035976 968 38.6800000000 0.0156221306 0.0097183662 0.0294891559 0.0143377664 0.1557840000 249610874 0 1783832576 -0.1672253013 -0.2154441178 1.1812690496 969 38.7200000000 0.0159530099 0.0097248003 0.0294891559 0.0143470454 0.1387450000 249729004 0 1785360384 -0.1702689528 -0.2149234563 1.1801525354 970 38.7600000000 0.0159193147 0.0097311864 0.0294891559 0.0143498980 0.0777890000 249180559 0 1784139776 -0.1715658009 -0.2145877630 1.1779642105 971 38.8000000000 0.0162373334 0.0097378869 0.0294891559 0.0143508048 0.0768090000 249182209 0 1785065472 -0.1731343865 -0.2146783322 1.1755640507 972 38.8400000000 0.0159940142 0.0097443232 0.0294891559 0.0143494821 0.0809440000 249183123 0 1783173120 -0.1742714047 -0.2149037570 1.1751680374 973 38.8800000000 0.0160692781 0.0097508237 0.0294891559 0.0143520784 0.0861480000 249185701 0 1782116352 -0.1746410728 -0.2143974453 1.1745618582 974 38.9200000000 0.0157888792 0.0097570229 0.0294891559 0.0143492850 0.1116420000 249303851 0 1780244480 -0.1751133800 -0.2142288536 1.1751825809 975 38.9600000000 0.0161529705 0.0097635829 0.0294891559 0.0143505434 0.1674370000 249757207 0 1783582720 -0.1759735644 -0.2127826661 1.1752259731 976 39.0000000000 0.0155911902 0.0097695538 0.0294891559 0.0143465171 0.1448760000 249902726 0 1785221120 -0.1771624684 -0.2141329646 1.1724867821 977 39.0400000000 0.0162058752 0.0097761416 0.0294891559 0.0143499403 0.1110330000 249302770 0 1785749504 -0.1788600683 -0.2122129649 1.1717095375 978 39.0800000000 0.0155251436 0.0097820200 0.0294891559 0.0143457842 0.1092720000 249303115 0 1787273216 -0.1789152622 -0.2125350088 1.1696095467 979 39.1200000000 0.0161321908 0.0097885064 0.0294891559 0.0143459697 0.1169560000 249406461 0 1783365632 -0.1792118251 -0.2130388618 1.1682231426 980 39.1600000000 0.0165095739 0.0097953646 0.0294891559 0.0143439426 0.1637600000 250098723 0 1782079488 -0.1795120239 -0.2130106986 1.1678122282 981 39.2000000000 0.0156715624 0.0098013546 0.0294891559 0.0143399093 0.1296010000 250019996 0 1781161984 -0.1809148192 -0.2134398073 1.1650880575 982 39.2400000000 0.0158496518 0.0098075138 0.0294891559 0.0143410195 0.0883580000 249412844 0 1780457472 -0.1822026074 -0.2123409361 1.1627125740 983 39.2800000000 0.0165845528 0.0098144080 0.0294891559 0.0143396146 0.0800360000 249413306 0 1777516544 -0.1825461984 -0.2125382423 1.1629368067 984 39.3200000000 0.0156737417 0.0098203626 0.0294891559 0.0143371589 0.0826260000 249414412 0 1775992832 -0.1830530763 -0.2116007805 1.1602910757 985 39.3600000000 0.0157672372 0.0098264000 0.0294891559 0.0143382275 0.0866910000 249417266 0 1774342144 -0.1839394271 -0.2104252130 1.1567908525 986 39.4000000000 0.0153729366 0.0098320253 0.0294891559 0.0143359605 0.1046210000 249528175 0 1772195840 -0.1834578812 -0.2103683650 1.1553611755 987 39.4400000000 0.0152873686 0.0098375525 0.0294891559 0.0143343989 0.1713810000 250043329 0 1771823104 -0.1835674942 -0.2097158879 1.1530383825 988 39.4800000000 0.0164635647 0.0098442590 0.0294891559 0.0143362224 0.1720300000 250353494 0 1769455616 -0.1840271652 -0.2100150883 1.1532542706 989 39.5200000000 0.0168738756 0.0098513668 0.0294891559 0.0143367447 0.1089500000 249531922 0 1769807872 -0.1840701401 -0.2101336122 1.1515810490 990 39.5600000000 0.0165116563 0.0098580944 0.0294891559 0.0143356317 0.1010980000 249534048 0 1770926080 -0.1843540519 -0.2091458142 1.1493573189 991 39.6000000000 0.0162153300 0.0098645094 0.0294891559 0.0143327742 0.0890710000 249536082 0 1772957696 -0.1843642741 -0.2093901783 1.1465255022 992 39.6400000000 0.0155185321 0.0098702090 0.0294891559 0.0143280626 0.0939290000 249538860 0 1774735360 -0.1847327948 -0.2096417248 1.1433295012 993 39.6800000000 0.0155639900 0.0098759429 0.0294891559 0.0143260139 0.0971650000 249684096 0 1776164864 -0.1848855317 -0.2094517052 1.1416794062 994 39.7200000000 0.0159372650 0.0098820408 0.0294891559 0.0143231040 0.1842080000 250267371 0 1779560448 -0.1850161403 -0.2103862464 1.1391057968 995 39.7600000000 0.0153629044 0.0098875492 0.0294891559 0.0143185792 0.1519450000 250538710 0 1781080064 -0.1847022772 -0.2095253021 1.1363133192 996 39.8000000000 0.0150497714 0.0098927322 0.0294891559 0.0143150603 0.1135630000 249690048 0 1782673408 -0.1849273294 -0.2079522312 1.1334507465 997 39.8400000000 0.0155000659 0.0098983564 0.0294891559 0.0143141952 0.0988090000 249689842 0 1784434688 -0.1848635226 -0.2072129250 1.1331311464 998 39.8800000000 0.0163803361 0.0099048513 0.0294891559 0.0143108204 0.0984820000 249691308 0 1786101760 -0.1860294938 -0.2058987916 1.1312521696 999 39.9200000000 0.0156978536 0.0099106501 0.0294891559 0.0143165115 0.0897180000 249695182 0 1784627200 -0.1864260435 -0.2038066387 1.1255013943 1000 39.9600000000 0.0158375483 0.0099165770 0.0294891559 0.0143128198 0.1142890000 249698688 0 1781403648 -0.1868251264 -0.2037913799 1.1240473986 1001 40.0000000000 0.0158558823 0.0099225104 0.0294891559 0.0143096983 0.1133730000 249701258 0 1779896320 -0.1874083281 -0.2017998397 1.1211673021 1002 40.0400000000 0.0153401494 0.0099279172 0.0294891559 0.0143099549 0.1040700000 249700040 0 1778372608 -0.1871478707 -0.2019591033 1.1190704107 1003 40.0800000000 0.0154658090 0.0099334386 0.0294891559 0.0143062279 0.0882880000 249702810 0 1777213440 -0.1882266104 -0.2005852461 1.1160680056 1004 40.1200000000 0.0165938754 0.0099400725 0.0294891559 0.0143109262 0.0927700000 249702604 0 1775706112 -0.1877700984 -0.1998164058 1.1151964664 1005 40.1600000000 0.0159816016 0.0099460839 0.0294891559 0.0143090288 0.0942630000 249706662 0 1774055424 -0.1882335842 -0.1998040676 1.1130263805 1006 40.2000000000 0.0147747751 0.0099508838 0.0294891559 0.0143133935 0.0925430000 249708220 0 1772658688 -0.1877897978 -0.2015050799 1.1094658375 1007 40.2400000000 0.0154304523 0.0099563253 0.0294891559 0.0143122004 0.0900430000 249710346 0 1771261952 -0.1880075037 -0.1997286677 1.1062946320 1008 40.2800000000 0.0160859320 0.0099624063 0.0294891559 0.0143093513 0.0929120000 249712472 0 1769848832 -0.1883303374 -0.1995234489 1.1046149731 1009 40.3200000000 0.0145111596 0.0099669144 0.0294891559 0.0143026044 0.0936260000 249713278 0 1768722432 -0.1880640388 -0.1994826794 1.0995424986 1010 40.3600000000 0.0155595019 0.0099724517 0.0294891559 0.0143058663 0.0948470000 249714008 0 1767579648 -0.1879189163 -0.1991554201 1.0981826782 1011 40.4000000000 0.0146743022 0.0099771024 0.0294891559 0.0143067803 0.0932920000 249716026 0 1766182912 -0.1876357347 -0.1990566254 1.0932806730 1012 40.4400000000 0.0147321178 0.0099818010 0.0294891559 0.0143122355 0.0929450000 249719072 0 1765150720 -0.1871109754 -0.1985143721 1.0912567377 1013 40.4800000000 0.0154575156 0.0099872064 0.0294891559 0.0143090965 0.0912170000 249719710 0 1763897344 -0.1881994903 -0.1959960163 1.0879112482 1014 40.5200000000 0.0161310118 0.0099932654 0.0294891559 0.0143141973 0.0928700000 249724520 0 1764278272 -0.1882358938 -0.1952182502 1.0871322155 1015 40.5600000000 0.0179605447 0.0100011149 0.0294891559 0.0143162118 0.0919850000 249725234 0 1764151296 -0.1899774224 -0.1915628612 1.0854500532 1016 40.6000000000 0.0152867213 0.0100063173 0.0294891559 0.0143191970 0.0937490000 249727552 0 1765167104 -0.1890033334 -0.1919127107 1.0814696550 1017 40.6400000000 0.0151010454 0.0100113269 0.0294891559 0.0143213527 0.0961850000 249733558 0 1765036032 -0.1886745989 -0.1913043112 1.0795011520 1018 40.6800000000 0.0152903823 0.0100165126 0.0294891559 0.0143256979 0.0965210000 249735116 0 1765154816 -0.1892015338 -0.1905682087 1.0775672197 1019 40.7200000000 0.0146414125 0.0100210513 0.0294891559 0.0143282239 0.0971980000 249737330 0 1764003840 -0.1890075505 -0.1892113090 1.0752959251 1020 40.7600000000 0.0156550463 0.0100265748 0.0294891559 0.0143301755 0.0974780000 249738548 0 1764159488 -0.1892935336 -0.1866409928 1.0754270554 1021 40.8000000000 0.0158271603 0.0100322561 0.0294891559 0.0143287810 0.0974290000 249743154 0 1764270080 -0.1902230382 -0.1845076382 1.0726933479 1022 40.8400000000 0.0177622680 0.0100398197 0.0294891559 0.0143276172 0.1050830000 249745996 0 1764413440 -0.1920675039 -0.1804966331 1.0722721815 1023 40.8800000000 0.0168469548 0.0100464738 0.0294891559 0.0143309874 0.0963590000 249751206 0 1763770368 -0.1917682588 -0.1799415350 1.0711970329 1024 40.9200000000 0.0161887743 0.0100524721 0.0294891559 0.0143325344 0.1358040000 250073239 0 1763889152 -0.1918271780 -0.1778781861 1.0687935352 1025 40.9600000000 0.0166982263 0.0100589558 0.0294891559 0.0143486204 0.2688460000 250559577 0 1765847040 -0.1921636760 -0.1771050692 1.0683048964 1026 41.0000000000 0.0153362555 0.0100640993 0.0294891559 0.0143502979 0.1930680000 251105706 0 1768001536 -0.1925129592 -0.1747000813 1.0633335114 1027 41.0400000000 0.0157915186 0.0100696762 0.0294891559 0.0143617544 0.1418890000 250256694 0 1768566784 -0.1925850809 -0.1733271480 1.0624111891 1028 41.0800000000 0.0160320681 0.0100754762 0.0294891559 0.0143647537 0.1361010000 250263408 0 1770315776 -0.1931365728 -0.1699138582 1.0606646538 1029 41.1200000000 0.0151174469 0.0100803760 0.0294891559 0.0143648335 0.1389010000 250267510 0 1772093440 -0.1924306303 -0.1681704670 1.0584135056 1030 41.1600000000 0.0157142151 0.0100858458 0.0294891559 0.0143632857 0.1339570000 250272024 0 1773871104 -0.1931008995 -0.1663006246 1.0567017794 1031 41.2000000000 0.0146533977 0.0100902760 0.0294891559 0.0143706720 0.1402630000 250275594 0 1775521792 -0.1924993545 -0.1655584127 1.0540968180 1032 41.2400000000 0.0151907541 0.0100952183 0.0294891559 0.0143666404 0.1318830000 250277012 0 1777283072 -0.1929749250 -0.1624652743 1.0523782969 1033 41.2800000000 0.0149887037 0.0100999555 0.0294891559 0.0143621496 0.1371920000 250282906 0 1778950144 -0.1926038265 -0.1614957005 1.0515469313 1034 41.3200000000 0.0152041800 0.0101048919 0.0294891559 0.0143719117 0.1376210000 250289200 0 1780600832 -0.1929250211 -0.1563151479 1.0484809875 1035 41.3600000000 0.0156898368 0.0101102880 0.0294891559 0.0143682775 0.1398930000 250291690 0 1781747712 -0.1927202940 -0.1555790305 1.0486667156 1036 41.4000000000 0.0148516484 0.0101148646 0.0294891559 0.0143626417 0.1405410000 250296232 0 1783775232 -0.1934114546 -0.1514067948 1.0449948311 1037 41.4400000000 0.0150837144 0.0101196561 0.0294891559 0.0143639815 0.1482070000 250301822 0 1785552896 -0.1937253624 -0.1481659710 1.0440032482 1038 41.4800000000 0.0145067470 0.0101238826 0.0294891559 0.0143630214 0.1425690000 250303244 0 1783902208 -0.1935012937 -0.1466113627 1.0419801474 1039 41.5200000000 0.0149093783 0.0101284885 0.0294891559 0.0143655634 0.1719890000 250307302 0 1782902784 -0.1943237782 -0.1434905082 1.0403430462 1040 41.5600000000 0.0150740445 0.0101332438 0.0294891559 0.0143699213 0.1451960000 250310596 0 1778188288 -0.1945483834 -0.1410294920 1.0391190052 1041 41.6000000000 0.0144697279 0.0101374095 0.0294891559 0.0143711784 0.1371130000 250312710 0 1776934912 -0.1938994378 -0.1380878687 1.0382493734 1042 41.6400000000 0.0155109381 0.0101425664 0.0294891559 0.0143722563 0.1354550000 250316716 0 1778331648 -0.1947325170 -0.1339541078 1.0374246836 1043 41.6800000000 0.0147374850 0.0101469719 0.0294891559 0.0143739988 0.1348510000 250319442 0 1780367360 -0.1945712864 -0.1310272664 1.0344629288 1044 41.7200000000 0.0144972680 0.0101511389 0.0294891559 0.0143787378 0.1396080000 250319812 0 1781981184 -0.1940996200 -0.1300860792 1.0343697071 1045 41.7600000000 0.0162450280 0.0101569704 0.0294891559 0.0143797315 0.1374250000 250323502 0 1783648256 -0.1952702999 -0.1275850534 1.0358504057 1046 41.8000000000 0.0153069738 0.0101618939 0.0294891559 0.0143762145 0.1462250000 250324992 0 1785298944 -0.1950754225 -0.1259714961 1.0336077213 1047 41.8400000000 0.0156037752 0.0101670915 0.0294891559 0.0143718420 0.1415750000 250327378 0 1784029184 -0.1952454448 -0.1246061325 1.0334079266 1048 41.8800000000 0.0144473538 0.0101711757 0.0294891559 0.0143711351 0.1378680000 250328844 0 1783046144 -0.1939857155 -0.1245395318 1.0328133106 1049 41.9200000000 0.0142857973 0.0101750981 0.0294891559 0.0143713314 0.1402830000 250330218 0 1782136832 -0.1940628737 -0.1236735806 1.0312986374 1050 41.9600000000 0.0141500691 0.0101788838 0.0294891559 0.0143661873 0.1351690000 250332336 0 1781379072 -0.1943965554 -0.1208146587 1.0294860601 1051 42.0000000000 0.0145955384 0.0101830861 0.0294891559 0.0143617431 0.1387270000 250334462 0 1779343360 -0.1944673061 -0.1186172888 1.0290207863 1052 42.0400000000 0.0142726181 0.0101869735 0.0294891559 0.0143584622 0.1386080000 250334908 0 1778585600 -0.1944745630 -0.1180084273 1.0282388926 1053 42.0800000000 0.0156678818 0.0101921786 0.0294891559 0.0143572630 0.1349360000 250336742 0 1777061888 -0.1951822340 -0.1160025001 1.0287644863 1054 42.1200000000 0.0144160828 0.0101961861 0.0294891559 0.0143559026 0.1335820000 250338868 0 1778950144 -0.1942036748 -0.1161422580 1.0275465250 1055 42.1600000000 0.0152674988 0.0102009930 0.0294891559 0.0143500928 0.1341840000 250340542 0 1780473856 -0.1950683296 -0.1120764688 1.0278296471 1056 42.2000000000 0.0133774206 0.0102040010 0.0294891559 0.0143529128 0.1396070000 250342284 0 1782124544 -0.1940625906 -0.1114439368 1.0262269974 1057 42.2400000000 0.0141752278 0.0102077580 0.0294891559 0.0143511792 0.1349030000 250343842 0 1783885824 -0.1947559118 -0.1099824905 1.0264343023 1058 42.2800000000 0.0161907375 0.0102134130 0.0294891559 0.0143468333 0.1407160000 250345500 0 1785663488 -0.1961516738 -0.1062493622 1.0283523798 1059 42.3200000000 0.0145265628 0.0102174859 0.0294891559 0.0143478825 0.1350910000 250346966 0 1785061376 -0.1948634684 -0.1080257446 1.0282709599 1060 42.3600000000 0.0166613441 0.0102235650 0.0294891559 0.0143440159 0.1387830000 250348348 0 1781633024 -0.1976037472 -0.1029507443 1.0278398991 1061 42.4000000000 0.0166760162 0.0102296465 0.0294891559 0.0143401019 0.1393350000 250349554 0 1779982336 -0.1979068220 -0.1023713499 1.0287437439 1062 42.4400000000 0.0150298988 0.0102341665 0.0294891559 0.0143591459 0.1986210000 251062571 0 1778458624 -0.1969487965 -0.1021223962 1.0310304165 1063 42.4800000000 0.0153034693 0.0102389354 0.0294891559 0.0143535208 0.5192670000 251835653 0 1780473856 -0.1974490583 -0.1009770706 1.0319774151 1064 42.5200000000 0.0151938628 0.0102435922 0.0294891559 0.0143473759 0.2697150000 252674119 0 1784930304 -0.1973758340 -0.0995947793 1.0329023600 1065 42.5600000000 0.0160296187 0.0102490251 0.0294891559 0.0143407554 0.2740860000 252506882 0 1785094144 -0.1982185245 -0.0964415297 1.0338165760 1066 42.6000000000 0.0165264439 0.0102549139 0.0294891559 0.0143347592 0.2147790000 251181548 0 1783881728 -0.1984218061 -0.0947988406 1.0352410078 1067 42.6400000000 0.0176579449 0.0102618521 0.0294891559 0.0143310105 0.2227640000 251182946 0 1782861824 -0.1988157481 -0.0933573321 1.0375503302 1068 42.6800000000 0.0170827657 0.0102682387 0.0294891559 0.0143258182 0.2275190000 251184320 0 1784668160 -0.1982270628 -0.0911336467 1.0375494957 1069 42.7200000000 0.0170568693 0.0102745891 0.0294891559 0.0143255059 0.2131500000 251185602 0 1785774080 -0.1979388297 -0.0905298144 1.0382769108 1070 42.7600000000 0.0168914739 0.0102807731 0.0294891559 0.0143244175 0.2090610000 251187804 0 1785151488 -0.1976162195 -0.0898647085 1.0389006138 1071 42.8000000000 0.0170593057 0.0102871023 0.0294891559 0.0143197720 0.2088080000 251188810 0 1786556416 -0.1974819899 -0.0877994597 1.0409022570 1072 42.8400000000 0.0164632313 0.0102928636 0.0294891559 0.0143193576 0.2136150000 251190192 0 1783361536 -0.1975834370 -0.0887520313 1.0419716835 1073 42.8800000000 0.0160560831 0.0102982347 0.0294891559 0.0143138562 0.2115680000 251191842 0 1785057280 -0.1973025501 -0.0857973993 1.0416109562 1074 42.9200000000 0.0155585529 0.0103031326 0.0294891559 0.0143101300 0.2114200000 251193508 0 1784795136 -0.1974455118 -0.0857024118 1.0414001942 1075 42.9600000000 0.0159760471 0.0103084098 0.0294891559 0.0143043461 0.2112370000 251195250 0 1784147968 -0.1973835975 -0.0844337717 1.0427330732 1076 43.0000000000 0.0166450627 0.0103142988 0.0294891559 0.0142978715 0.2092730000 251196256 0 1785442304 -0.1972909570 -0.0812904909 1.0445789099 1077 43.0400000000 0.0159206670 0.0103195044 0.0294891559 0.0143000801 0.2048010000 251197446 0 1784795136 -0.1971261799 -0.0835840851 1.0474725962 1078 43.0800000000 0.0159788169 0.0103247542 0.0294891559 0.0142956458 0.2025040000 251199404 0 1784184832 -0.1969084740 -0.0817572251 1.0496159792 1079 43.1200000000 0.0162786618 0.0103302722 0.0294891559 0.0142895296 0.2011410000 251200518 0 1786204160 -0.1971146762 -0.0789482966 1.0522269011 1080 43.1600000000 0.0165601149 0.0103360406 0.0294891559 0.0142867305 0.2042630000 251202260 0 1784029184 -0.1964630187 -0.0785030648 1.0559619665 1081 43.2000000000 0.0164223760 0.0103416708 0.0294891559 0.0142866265 0.2050510000 251203726 0 1783144448 -0.1968516558 -0.0787137896 1.0577126741 1082 43.2400000000 0.0172092859 0.0103480180 0.0294891559 0.0142814210 0.2023830000 251204924 0 1785184256 -0.1971300989 -0.0760173053 1.0599780083 1083 43.2800000000 0.0159261767 0.0103531686 0.0294891559 0.0142876056 0.1996050000 251206298 0 1784541184 -0.1963219792 -0.0773833916 1.0616557598 1084 43.3200000000 0.0166895930 0.0103590141 0.0294891559 0.0142816270 0.2039260000 251207872 0 1783894016 -0.1961490661 -0.0752406567 1.0636870861 1085 43.3600000000 0.0161415152 0.0103643436 0.0294891559 0.0142763211 0.1988210000 251209430 0 1785675776 -0.1958379596 -0.0750369355 1.0645030737 1086 43.4000000000 0.0159020852 0.0103694428 0.0294891559 0.0142731041 0.1978530000 251210812 0 1785049088 -0.1956606954 -0.0748482943 1.0657474995 1087 43.4400000000 0.0162344407 0.0103748383 0.0294891559 0.0142696402 0.1982160000 251212278 0 1784291328 -0.1953705847 -0.0743316114 1.0685542822 1088 43.4800000000 0.0163304899 0.0103803123 0.0294891559 0.0142634192 0.1975290000 251213860 0 1786036224 -0.1950755566 -0.0711833760 1.0694530010 1089 43.5200000000 0.0163026843 0.0103857506 0.0294891559 0.0142607146 0.2016800000 251215326 0 1784029184 -0.1950809062 -0.0710207671 1.0712827444 1090 43.5600000000 0.0165599100 0.0103914150 0.0294891559 0.0142572315 0.1971620000 251216700 0 1783128064 -0.1944686770 -0.0706037879 1.0735296011 1091 43.6000000000 0.0164385401 0.0103969578 0.0294891559 0.0142510529 0.1999550000 251218166 0 1785167872 -0.1932078600 -0.0681430027 1.0755709410 1092 43.6400000000 0.0157204345 0.0104018327 0.0294891559 0.0142539882 0.2346920000 251219732 0 1786437632 -0.1925584972 -0.0696996748 1.0775858164 1093 43.6800000000 0.0162742082 0.0104072054 0.0294891559 0.0142539809 0.1966930000 251221014 0 1783631872 -0.1924934089 -0.0701201335 1.0809559822 1094 43.7200000000 0.0155387837 0.0104118961 0.0294891559 0.0142502004 0.1980040000 251222572 0 1782345728 -0.1916000247 -0.0686418191 1.0818994045 1095 43.7600000000 0.0161097888 0.0104170997 0.0294891559 0.0142569282 0.2005900000 251223946 0 1784406016 -0.1909326315 -0.0710892826 1.0862469673 1096 43.8000000000 0.0166952442 0.0104228279 0.0294891559 0.0142513254 0.2015100000 251225436 0 1786056704 -0.1905348599 -0.0662733912 1.0889335871 1097 43.8400000000 0.0164725017 0.0104283426 0.0294891559 0.0142461233 0.1989720000 251226910 0 1784766464 -0.1900089979 -0.0656876713 1.0905581713 1098 43.8800000000 0.0166350268 0.0104339953 0.0294891559 0.0142400001 0.1966050000 251228484 0 1782116352 -0.1891423762 -0.0640289858 1.0932035446 1099 43.9200000000 0.0172591209 0.0104402057 0.0294891559 0.0142338637 0.2020990000 251229582 0 1783517184 -0.1883630455 -0.0616896637 1.0958259106 1100 43.9600000000 0.0167050473 0.0104459010 0.0294891559 0.0142368212 0.1953360000 251231416 0 1785167872 -0.1877464205 -0.0631701946 1.0981891155 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_living_room_traj1_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:25:12 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_living_room_traj1_loop.log input: datasets/ICL_NUIM/living_room_traj1_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1594190000 225821264 0 1771626496 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0006322594 0.0003161297 0.0006322594 0.0016329817 0.1793020000 229169542 0 1774051328 0.0000740347 0.0006893943 -0.0004102595 3 0.0800000000 0.0019706578 0.0008676391 0.0019706578 0.0021090803 0.1780700000 229095992 0 1775955968 0.0004180617 -0.0041669640 -0.0010802659 4 0.1200000000 0.0028546657 0.0013643957 0.0028546657 0.0018938772 0.1771980000 229101398 0 1777967104 -0.0015396876 -0.0038877153 -0.0007328999 5 0.1600000000 0.0007072779 0.0012329722 0.0028546657 0.0021302526 0.1793610000 229103120 0 1779638272 -0.0006572722 -0.0014357914 -0.0001916429 6 0.2000000000 0.0007236152 0.0011480793 0.0028546657 0.0020760364 0.1836220000 229108634 0 1781268480 -0.0004263424 -0.0027798826 -0.0006840291 7 0.2400000000 0.0030840011 0.0014246396 0.0030840011 0.0024607709 0.1872270000 229110352 0 1783066624 -0.0020272180 -0.0048149424 -0.0011664431 8 0.2800000000 0.0014514155 0.0014279866 0.0030840011 0.0029855460 0.1831250000 229112810 0 1785098240 -0.0011865910 -0.0002369150 0.0001306492 9 0.3200000000 0.0011034871 0.0013919311 0.0030840011 0.0028712116 0.1784140000 229114304 0 1786875904 0.0009762178 -0.0012516276 0.0000825028 10 0.3600000000 0.0014781026 0.0014005482 0.0030840011 0.0028584187 0.1792950000 229117454 0 1782169600 -0.0006603656 -0.0031134326 -0.0009575582 11 0.4000000000 0.0024387294 0.0014949283 0.0030840011 0.0027725045 0.1792800000 229118488 0 1781665792 0.0007106397 -0.0035659946 -0.0004142506 12 0.4400000000 0.0008053528 0.0014374637 0.0030840011 0.0026875389 0.1786680000 229120842 0 1783468032 -0.0002612591 -0.0011601700 -0.0003452653 13 0.4800000000 0.0009643648 0.0014010715 0.0030840011 0.0026784768 0.1795890000 229121612 0 1785077760 0.0006748838 -0.0000419959 0.0007681635 14 0.5200000000 0.0009418047 0.0013682667 0.0030840011 0.0026330034 0.1788770000 229123002 0 1784074240 0.0009396579 0.0002901095 0.0000325352 15 0.5600000000 0.0018550168 0.0014007167 0.0030840011 0.0026616996 0.1777100000 229124652 0 1782968320 0.0006903705 -0.0014758960 0.0009087144 16 0.6000000000 0.0015899934 0.0014125465 0.0030840011 0.0026338977 0.1861070000 229126678 0 1780412416 -0.0011135135 0.0007081383 0.0002338964 17 0.6400000000 0.0029016323 0.0015001398 0.0030840011 0.0028104406 0.1736560000 229127300 0 1778630656 0.0008341246 -0.0028495672 0.0002482499 18 0.6800000000 0.0026437019 0.0015636710 0.0030840011 0.0027342212 0.1724300000 229132602 0 1780137984 0.0017353209 -0.0028343769 -0.0002608570 19 0.7200000000 0.0013841158 0.0015542207 0.0030840011 0.0029685891 0.1710910000 229135240 0 1782665216 -0.0009793595 -0.0014016455 0.0000036493 20 0.7600000000 0.0020791844 0.0015804689 0.0030840011 0.0030269925 0.1706360000 229136154 0 1783955456 -0.0008780963 -0.0027447653 -0.0003605862 21 0.8000000000 0.0025227708 0.0016253404 0.0030840011 0.0030195704 0.1811540000 229137180 0 1785733120 0.0002488398 -0.0034164025 -0.0007020697 22 0.8400000000 0.0007032672 0.0015834280 0.0030840011 0.0030594338 0.1739380000 229138822 0 1784750080 0.0005290636 -0.0011969036 -0.0003459814 23 0.8800000000 0.0021605825 0.0016085217 0.0030840011 0.0030695323 0.1819330000 229140592 0 1785987072 -0.0012710718 -0.0029044305 -0.0002749765 24 0.9200000000 0.0019384924 0.0016222705 0.0030840011 0.0030559386 0.1906740000 229143938 0 1784090624 -0.0018487467 -0.0011707458 -0.0012662968 25 0.9600000000 0.0026929893 0.0016650992 0.0030840011 0.0030276238 0.1735800000 229144408 0 1782681600 -0.0031013119 0.0000512454 -0.0006449151 26 1.0000000000 0.0012302565 0.0016483745 0.0030840011 0.0030297292 0.1765140000 229146050 0 1783816192 -0.0004446412 -0.0017377858 -0.0003976426 27 1.0400000000 0.0022008303 0.0016688358 0.0030840011 0.0029960349 0.2090280000 229148212 0 1786339328 -0.0017958576 -0.0024478578 -0.0005460715 28 1.0800000000 0.0037557126 0.0017433671 0.0037557126 0.0029923480 0.1864080000 229149522 0 1783947264 -0.0033816034 -0.0032763432 -0.0009839400 29 1.1200000000 0.0015328801 0.0017361090 0.0037557126 0.0029635968 0.1765620000 229151284 0 1783451648 -0.0021522476 -0.0014428742 -0.0005574360 30 1.1600000000 0.0024999930 0.0017615718 0.0037557126 0.0029447747 0.1742410000 229152546 0 1785614336 -0.0031022150 -0.0011651883 -0.0005185237 31 1.2000000000 0.0019528458 0.0017677419 0.0037557126 0.0029439066 0.1784790000 229153256 0 1784090624 -0.0030238330 0.0000164677 -0.0003462074 32 1.2400000000 0.0023218042 0.0017850564 0.0037557126 0.0029055908 0.1781160000 229154986 0 1783050240 -0.0036291890 -0.0011400258 -0.0003315952 33 1.2800000000 0.0029741928 0.0018210908 0.0037557126 0.0028922411 0.1872780000 229159336 0 1779499008 -0.0033492940 -0.0029428091 -0.0000933873 34 1.3200000000 0.0031949694 0.0018614990 0.0037557126 0.0029012478 0.1754940000 229164198 0 1778372608 -0.0048223450 -0.0024621380 0.0002698250 35 1.3600000000 0.0017624055 0.0018586677 0.0037557126 0.0028670400 0.1761530000 229166620 0 1779367936 -0.0040355334 -0.0022886312 -0.0003190385 36 1.4000000000 0.0025464518 0.0018777729 0.0037557126 0.0028350384 0.1761360000 229167546 0 1781657600 -0.0050165406 -0.0030083298 0.0001558601 37 1.4400000000 0.0030912303 0.0019105690 0.0037557126 0.0028222039 0.1744360000 229170288 0 1783435264 -0.0031680325 -0.0044659125 0.0002473333 38 1.4800000000 0.0016173215 0.0019028520 0.0037557126 0.0028010909 0.1835150000 229171814 0 1785085952 -0.0037254884 -0.0034244768 0.0003017987 39 1.5200000000 0.0012397778 0.0018858501 0.0037557126 0.0027747403 0.1739290000 229175820 0 1786847232 -0.0040215026 -0.0046435231 0.0000718867 40 1.5600000000 0.0010661966 0.0018653587 0.0037557126 0.0028279500 0.1716910000 229174506 0 1783087104 -0.0047245971 -0.0030583544 0.0009319994 41 1.6000000000 0.0027354958 0.0018865816 0.0037557126 0.0029738479 0.1680130000 229178480 0 1782034432 -0.0054088556 -0.0043252511 0.0009664802 42 1.6400000000 0.0023792791 0.0018983125 0.0037557126 0.0030212118 0.1674000000 229180378 0 1783963648 -0.0056550531 -0.0043545868 0.0011053110 43 1.6800000000 0.0009376288 0.0018759710 0.0037557126 0.0030618734 0.1725830000 229183492 0 1785466880 -0.0044610943 -0.0029487011 0.0016971997 44 1.7200000000 0.0019649407 0.0018779930 0.0037557126 0.0030462908 0.1734010000 229182718 0 1784090624 -0.0058144829 -0.0037824127 0.0021414391 45 1.7600000000 0.0025348498 0.0018925898 0.0037557126 0.0030855822 0.1788730000 229184972 0 1783050240 -0.0080408901 -0.0035733534 0.0028424086 46 1.8000000000 0.0026151109 0.0019082968 0.0037557126 0.0030736924 0.1804730000 229186486 0 1779490816 -0.0043473081 -0.0054348912 0.0035986949 47 1.8400000000 0.0021897028 0.0019142842 0.0037557126 0.0033372386 0.1719440000 229186980 0 1778249728 -0.0076254643 -0.0054919114 0.0043397113 48 1.8800000000 0.0022388746 0.0019210465 0.0037557126 0.0035540298 0.1685010000 229190330 0 1779101696 -0.0086945910 -0.0037350142 0.0063083791 49 1.9200000000 0.0021226024 0.0019251599 0.0037557126 0.0037167822 0.1690650000 229193496 0 1781399552 -0.0065717055 -0.0074835196 0.0071044913 50 1.9600000000 0.0027524980 0.0019417066 0.0037557126 0.0039856625 0.1748810000 229197302 0 1783046144 -0.0076995101 -0.0082788551 0.0079200985 51 2.0000000000 0.0008597912 0.0019204926 0.0037557126 0.0041197293 0.1753940000 229199964 0 1785069568 -0.0068888022 -0.0063706753 0.0102356849 52 2.0400000000 0.0019684210 0.0019214143 0.0037557126 0.0042691191 0.1707780000 229202818 0 1784209408 -0.0071076034 -0.0072740228 0.0126053793 53 2.0800000000 0.0023848505 0.0019301584 0.0037557126 0.0042779113 0.1684260000 229205468 0 1782915072 -0.0046136556 -0.0091864830 0.0147836488 54 2.1200000000 0.0035249169 0.0019596910 0.0037557126 0.0043635844 0.2122790000 229206378 0 1782079488 -0.0041519003 -0.0113207614 0.0155715095 55 2.1600000000 0.0021754568 0.0019636140 0.0037557126 0.0044076364 0.1684290000 229209320 0 1783541760 -0.0056612561 -0.0089334352 0.0187724940 56 2.2000000000 0.0017650556 0.0019600683 0.0037557126 0.0043721695 0.1717250000 229209562 0 1785348096 -0.0044466550 -0.0086550005 0.0214814227 57 2.2400000000 0.0027368269 0.0019736956 0.0037557126 0.0043503286 0.1701160000 229210684 0 1784303616 -0.0003739454 -0.0090831742 0.0225307681 58 2.2800000000 0.0006514623 0.0019508985 0.0037557126 0.0044601849 0.1676780000 229215606 0 1783443456 -0.0014496073 -0.0058944901 0.0257200971 59 2.3200000000 0.0007966585 0.0019313351 0.0037557126 0.0045776892 0.1698700000 229214256 0 1782059008 -0.0010956508 -0.0065092859 0.0291598327 60 2.3600000000 0.0021287561 0.0019346255 0.0037557126 0.0047470214 0.1697870000 229221486 0 1783955456 0.0025236844 -0.0083523858 0.0313164033 61 2.4000000000 0.0005721042 0.0019122890 0.0037557126 0.0050562154 0.1708070000 229223336 0 1785712640 0.0014273005 -0.0083419858 0.0343332887 62 2.4400000000 0.0003074753 0.0018864050 0.0037557126 0.0052820096 0.1738220000 229224290 0 1784311808 0.0030223520 -0.0077484115 0.0368696302 63 2.4800000000 0.0017146536 0.0018836787 0.0037557126 0.0054854592 0.1668260000 229223812 0 1786368000 0.0030015041 -0.0096234595 0.0393676646 64 2.5200000000 0.0024752922 0.0018929227 0.0037557126 0.0056486244 0.1714890000 229229326 0 1785114624 0.0040059644 -0.0069053173 0.0427217744 65 2.5600000000 0.0028738363 0.0019080137 0.0037557126 0.0058816043 0.1667070000 229231344 0 1786208256 0.0046614418 -0.0098463660 0.0449065566 66 2.6000000000 0.0023697747 0.0019150101 0.0037557126 0.0061897881 0.1678970000 229242722 0 1785225216 0.0070980075 -0.0110796439 0.0485591143 67 2.6400000000 0.0034755187 0.0019383012 0.0037557126 0.0064919126 0.1744410000 229246664 0 1784467456 0.0103240060 -0.0048736176 0.0517510138 68 2.6800000000 0.0037199238 0.0019645016 0.0037557126 0.0069720589 0.1698240000 229249190 0 1782693888 0.0077148131 -0.0081384964 0.0543445311 69 2.7200000000 0.0041290005 0.0019958711 0.0041290005 0.0071856888 0.1729560000 229249760 0 1781149696 0.0100930454 -0.0062481295 0.0572341830 70 2.7600000000 0.0041803587 0.0020270781 0.0041803587 0.0073245936 0.1737100000 229253374 0 1783173120 0.0108011086 -0.0105278669 0.0584840514 71 2.8000000000 0.0028812033 0.0020391080 0.0041803587 0.0073282952 0.1648910000 229253372 0 1784696832 0.0132400868 -0.0083149513 0.0619864464 72 2.8400000000 0.0038211117 0.0020638581 0.0041803587 0.0073215773 0.1714400000 229257842 0 1786474496 0.0136760771 -0.0090745706 0.0652097613 73 2.8800000000 0.0042189937 0.0020933805 0.0042189937 0.0073149407 0.2101530000 229741057 0 1783189504 0.0156339500 -0.0069822352 0.0681566149 74 2.9200000000 0.0045390804 0.0021264305 0.0045390804 0.0073433034 0.2941370000 230107547 0 1785126912 0.0161378570 -0.0070738038 0.0709542036 75 2.9600000000 0.0012331710 0.0021145203 0.0045390804 0.0073517073 0.4411870000 231046488 0 1784717312 0.0204606988 -0.0083609056 0.0735316277 76 3.0000000000 0.0033435423 0.0021306917 0.0045390804 0.0075721464 0.2406940000 230991586 0 1783537664 0.0198169537 -0.0096967025 0.0757791400 77 3.0400000000 0.0092324372 0.0022229221 0.0092324372 0.0075597478 0.2425860000 230833666 0 1782480896 0.0329905972 -0.0080304975 0.0783189535 78 3.0800000000 0.0087035866 0.0023060076 0.0092324372 0.0077890080 0.1759530000 230086695 0 1784119296 0.0339644738 -0.0073626935 0.0810000971 79 3.1200000000 0.0085816076 0.0023854456 0.0092324372 0.0079979044 0.2069830000 230088269 0 1785753600 0.0350765362 -0.0109366728 0.0837942138 80 3.1600000000 0.0100311246 0.0024810166 0.0100311246 0.0080934232 0.1845810000 230092087 0 1783865344 0.0375597179 -0.0126096476 0.0855790377 81 3.2000000000 0.0074396553 0.0025422343 0.0100311246 0.0083130873 0.1801610000 230092985 0 1783246848 0.0363499783 -0.0103351846 0.0882302374 82 3.2400000000 0.0098429555 0.0026312675 0.0100311246 0.0084448293 0.1808940000 230100823 0 1778913280 0.0390050411 -0.0089394320 0.0905602276 83 3.2800000000 0.0120960930 0.0027453015 0.0120960930 0.0085938554 0.2094660000 230501833 0 1777659904 0.0426268242 -0.0137738753 0.0926814899 84 3.3200000000 0.0089793745 0.0028195167 0.0120960930 0.0087499143 0.3880270000 230626713 0 1778786304 0.0400177389 -0.0150213651 0.0952434763 85 3.3600000000 0.0088170813 0.0028900763 0.0120960930 0.0088064305 0.2237860000 231384363 0 1782886400 0.0407149829 -0.0131928418 0.0978928283 86 3.4000000000 0.0099626016 0.0029723149 0.0120960930 0.0088494862 0.2102810000 231215684 0 1783107584 0.0426781736 -0.0114793917 0.1005718336 87 3.4400000000 0.0125365546 0.0030822487 0.0125365546 0.0088916312 0.1729130000 230463136 0 1783619584 0.0461152755 -0.0113377348 0.1039270237 88 3.4800000000 0.0118909422 0.0031823475 0.0125365546 0.0089712452 0.1820920000 230464138 0 1785016320 0.0461991131 -0.0140046570 0.1071112826 89 3.5200000000 0.0087634074 0.0032450561 0.0125365546 0.0091094036 0.1742520000 230467536 0 1786793984 0.0439825580 -0.0126640378 0.1088761911 90 3.5600000000 0.0135605158 0.0033596723 0.0135605158 0.0091559425 0.1817130000 230472446 0 1782853632 0.0490088090 -0.0151694436 0.1125165671 91 3.6000000000 0.0126958136 0.0034622672 0.0135605158 0.0093434143 0.1799970000 230474456 0 1782366208 0.0493663996 -0.0109557444 0.1162844151 92 3.6400000000 0.0110807568 0.0035450769 0.0135605158 0.0094519410 0.1753860000 230478494 0 1784295424 0.0485228151 -0.0127929449 0.1182438731 93 3.6800000000 0.0116303209 0.0036320150 0.0135605158 0.0094493213 0.1741630000 230479344 0 1785905152 0.0495248362 -0.0132624395 0.1215557754 94 3.7200000000 0.0107473349 0.0037077099 0.0135605158 0.0094347867 0.1789280000 230482882 0 1785180160 0.0493645929 -0.0151894325 0.1249041557 95 3.7600000000 0.0117278090 0.0037921320 0.0135605158 0.0094310041 0.1718580000 230482472 0 1786814464 0.0511385649 -0.0121239265 0.1280285120 96 3.8000000000 0.0107354708 0.0038644585 0.0135605158 0.0094479945 0.1714060000 230486502 0 1785020416 0.0512080565 -0.0133975269 0.1312761903 97 3.8400000000 0.0118519086 0.0039468033 0.0135605158 0.0095444636 0.1701770000 230489976 0 1786687488 0.0528555214 -0.0133742038 0.1343710870 98 3.8800000000 0.0125279967 0.0040343665 0.0135605158 0.0096624611 0.1757080000 230492830 0 1785061376 0.0541504323 -0.0113439029 0.1377373189 99 3.9200000000 0.0113528566 0.0041082906 0.0135605158 0.0097878193 0.1685220000 230493452 0 1784532992 0.0540680028 -0.0122377407 0.1413340569 100 3.9600000000 0.0099797351 0.0041670051 0.0135605158 0.0099264750 0.1723430000 230496542 0 1782616064 0.0528027639 -0.0118338130 0.1433989257 101 4.0000000000 0.0122301374 0.0042468381 0.0135605158 0.0099649532 0.1969530000 230951653 0 1781731328 0.0556450039 -0.0090291090 0.1478330791 102 4.0400000000 0.0117949694 0.0043208394 0.0135605158 0.0099741570 0.4140640000 230956203 0 1783308288 0.0559668280 -0.0106360745 0.1508120000 103 4.0800000000 0.0127758877 0.0044029272 0.0135605158 0.0099765820 0.3204590000 232041716 0 1783947264 0.0572691709 -0.0091789691 0.1541854888 104 4.1200000000 0.0156604499 0.0045111726 0.0156604499 0.0099892411 0.2622570000 231991162 0 1778892800 0.0603796579 -0.0050923824 0.1584480703 105 4.1600000000 0.0148580149 0.0046097140 0.0156604499 0.0099976786 0.1791200000 230931405 0 1779281920 0.0602353103 -0.0057204776 0.1605324447 106 4.2000000000 0.0134348460 0.0046929699 0.0156604499 0.0099899474 0.1791800000 230931787 0 1780359168 0.0591131896 -0.0059282719 0.1629520357 107 4.2400000000 0.0158113241 0.0047968798 0.0158113241 0.0099530282 0.1770720000 230937881 0 1782390784 0.0621640086 -0.0072264010 0.1668454111 108 4.2800000000 0.0152995875 0.0048941271 0.0158113241 0.0099607459 0.1806090000 230938239 0 1784168448 0.0612804107 -0.0038662404 0.1692799032 109 4.3200000000 0.0147013636 0.0049841017 0.0158113241 0.0099425550 0.1746060000 230942189 0 1785819136 0.0608711690 -0.0030469843 0.1720084697 110 4.3600000000 0.0151820118 0.0050768100 0.0158113241 0.0099037598 0.1769170000 230943051 0 1784799232 0.0617843755 -0.0028176638 0.1746326685 111 4.4000000000 0.0134331649 0.0051520925 0.0158113241 0.0098653539 0.1648390000 230945221 0 1786454016 0.0606884994 -0.0032896679 0.1768778116 112 4.4400000000 0.0147126419 0.0052374545 0.0158113241 0.0098376165 0.1676480000 230948751 0 1784930304 0.0625972003 -0.0038364888 0.1798998713 113 4.4800000000 0.0147179151 0.0053213524 0.0158113241 0.0097978050 0.1646870000 230952745 0 1786707968 0.0625116676 -0.0042568045 0.1813798994 114 4.5200000000 0.0134383775 0.0053925544 0.0158113241 0.0097612533 0.1699770000 230957203 0 1784066048 0.0616275556 -0.0073918672 0.1834260076 115 4.5600000000 0.0144988066 0.0054717392 0.0158113241 0.0097499168 0.1660490000 230959433 0 1782644736 0.0629941598 -0.0047314707 0.1871369481 116 4.6000000000 0.0181805901 0.0055812983 0.0181805901 0.0097128980 0.1618460000 230961411 0 1783537664 0.0665622279 -0.0065682251 0.1898478270 117 4.6400000000 0.0146400537 0.0056587235 0.0181805901 0.0097265923 0.1997680000 231496717 0 1785421824 0.0627867803 -0.0019062271 0.1920291781 118 4.6800000000 0.0140197165 0.0057295794 0.0181805901 0.0096941699 0.4483380000 231466555 0 1786327040 0.0623587295 -0.0023369973 0.1946467161 119 4.7200000000 0.0132720023 0.0057929611 0.0181805901 0.0096578668 0.4058780000 231902092 0 1786212352 0.0625483394 -0.0050427094 0.1962255388 120 4.7600000000 0.0136853149 0.0058587307 0.0181805901 0.0096575460 0.3118180000 232906718 0 1784000512 0.0623540953 -0.0012353710 0.1988166422 121 4.8000000000 0.0184435919 0.0059627378 0.0184435919 0.0096753180 0.3023320000 232803660 0 1783083008 0.0659471527 0.0019534312 0.2063246071 122 4.8400000000 0.0165145658 0.0060492282 0.0184435919 0.0096770959 0.1763730000 231480559 0 1782878208 0.0645872205 0.0002831863 0.2092729211 123 4.8800000000 0.0168511141 0.0061370484 0.0184435919 0.0096550242 0.1724610000 231478457 0 1784369152 0.0652257279 0.0000725503 0.2122491896 124 4.9200000000 0.0177072696 0.0062303567 0.0184435919 0.0096328359 0.1705390000 231481487 0 1786503168 0.0657294840 0.0007283187 0.2165599763 125 4.9600000000 0.0169462766 0.0063160840 0.0184435919 0.0096026661 0.2083320000 231482545 0 1782833152 0.0663012639 -0.0025565799 0.2191413343 126 5.0000000000 0.0154816285 0.0063888264 0.0184435919 0.0096094097 0.1941140000 231962939 0 1784651776 0.0646240786 -0.0001274762 0.2217125595 127 5.0400000000 0.0156521089 0.0064617657 0.0184435919 0.0096070886 0.4398070000 231931333 0 1784696832 0.0652040169 0.0003377136 0.2248924673 128 5.0800000000 0.0159531869 0.0065359174 0.0184435919 0.0096220316 0.3783920000 232002795 0 1786785792 0.0654904023 0.0016175450 0.2288666964 129 5.1200000000 0.0177189652 0.0066226077 0.0184435919 0.0096289965 0.3079920000 233563095 0 1782120448 0.0659984201 0.0049259276 0.2331138849 130 5.1600000000 0.0160547048 0.0066951623 0.0184435919 0.0096080782 0.2297920000 233542418 0 1781510144 0.0673035830 -0.0000373884 0.2339318991 131 5.2000000000 0.0194522236 0.0067925444 0.0194522236 0.0096261430 0.2759190000 233468272 0 1780854784 0.0692332759 0.0042592213 0.2390935719 132 5.2400000000 0.0193502568 0.0068876786 0.0194522236 0.0095974806 0.1973650000 231954815 0 1781456896 0.0703343600 0.0027121482 0.2422733307 133 5.2800000000 0.0185724646 0.0069755341 0.0194522236 0.0095926032 0.1632240000 231956157 0 1783377920 0.0703256205 0.0024706628 0.2439097464 134 5.3200000000 0.0173363052 0.0070528533 0.0194522236 0.0096128203 0.1670000000 231959379 0 1785028608 0.0701367408 0.0024532252 0.2459831983 135 5.3600000000 0.0195351206 0.0071453146 0.0195351206 0.0096199145 0.1614630000 231961141 0 1786425344 0.0718074366 0.0048053358 0.2485132217 136 5.4000000000 0.0194337815 0.0072356709 0.0195351206 0.0096118371 0.1702060000 231960687 0 1784143872 0.0732223839 0.0014006137 0.2520665526 137 5.4400000000 0.0185356997 0.0073181529 0.0195351206 0.0096230250 0.1582580000 231963793 0 1783029760 0.0725600868 0.0031677680 0.2530337274 138 5.4800000000 0.0198573116 0.0074090164 0.0198573116 0.0096017625 0.1950320000 232442127 0 1785049088 0.0746389329 0.0017056041 0.2572723031 139 5.5200000000 0.0189749282 0.0074922244 0.0198573116 0.0095870759 0.4409520000 232404961 0 1785585664 0.0739292055 0.0025345557 0.2585434914 140 5.5600000000 0.0178830065 0.0075664443 0.0198573116 0.0095709348 0.3640720000 232405099 0 1784078336 0.0733542591 0.0016370318 0.2602284551 141 5.6000000000 0.0198373701 0.0076534721 0.0198573116 0.0096199839 0.3330100000 233183424 0 1786449920 0.0752961487 0.0008767778 0.2657303214 142 5.6400000000 0.0201858412 0.0077417282 0.0201858412 0.0096275787 0.2745230000 234219758 0 1783189504 0.0754532367 0.0005293228 0.2679752111 143 5.6800000000 0.0183652528 0.0078160186 0.0201858412 0.0096180569 0.1735770000 234215340 0 1784958976 0.0731270686 0.0011715954 0.2685666680 144 5.7200000000 0.0199415889 0.0079002239 0.0201858412 0.0096403952 0.2756060000 234137882 0 1782669312 0.0734115243 0.0017721821 0.2727378607 145 5.7600000000 0.0194875784 0.0079801367 0.0201858412 0.0096275862 0.1475950000 232411485 0 1782661120 0.0719056576 0.0028921179 0.2737623155 146 5.8000000000 0.0186783075 0.0080534119 0.0201858412 0.0096156191 0.1670400000 232721011 0 1784729600 0.0710180998 0.0024743015 0.2748175263 147 5.8400000000 0.0196145419 0.0081320590 0.0201858412 0.0096073616 0.3547230000 232730793 0 1786736640 0.0710236207 0.0022685267 0.2763242722 148 5.8800000000 0.0196361020 0.0082097890 0.0201858412 0.0095875155 0.2881540000 232795327 0 1782095872 0.0702372640 0.0012290766 0.2781454027 149 5.9200000000 0.0197963435 0.0082875512 0.0201858412 0.0095700205 0.2292980000 234726900 0 1780064256 0.0692368597 0.0011118632 0.2806005776 150 5.9600000000 0.0193733349 0.0083614564 0.0201858412 0.0095466204 0.2021390000 234618716 0 1779240960 0.0684487224 0.0005196324 0.2814236879 151 6.0000000000 0.0189854372 0.0084318139 0.0201858412 0.0095230270 0.3116820000 234524492 0 1775616000 0.0672972277 -0.0005850364 0.2833945453 152 6.0400000000 0.0201050453 0.0085086114 0.0201858412 0.0095170465 0.1447830000 232723707 0 1776259072 0.0664654821 0.0004155813 0.2863183618 153 6.0800000000 0.0176028758 0.0085680511 0.0201858412 0.0094968911 0.1462720000 233026865 0 1777393664 0.0632253960 -0.0001075901 0.2864505947 154 6.1200000000 0.0183465965 0.0086315481 0.0201858412 0.0094802624 0.3019460000 232999152 0 1779568640 0.0628847554 -0.0009978293 0.2892801762 155 6.1600000000 0.0189762972 0.0086982884 0.0201858412 0.0094728006 0.2292820000 233068106 0 1781727232 0.0605525151 0.0010929126 0.2915832996 156 6.2000000000 0.0177665111 0.0087564181 0.0201858412 0.0094705150 0.2245110000 235070395 0 1785810944 0.0571934208 -0.0009536901 0.2951431870 157 6.2400000000 0.0180745274 0.0088157691 0.0201858412 0.0094501214 0.2177690000 235018772 0 1784135680 0.0565090701 -0.0012416951 0.2969441414 158 6.2800000000 0.0199762546 0.0088864051 0.0201858412 0.0094473453 0.1392920000 235021119 0 1786466304 0.0550641865 0.0009192266 0.3001206517 159 6.3200000000 0.0189053062 0.0089494170 0.0201858412 0.0094290310 0.2226810000 234933228 0 1780736000 0.0530343875 -0.0006195819 0.3021430075 160 6.3600000000 0.0178764798 0.0090052112 0.0201858412 0.0094156692 0.1334390000 233264632 0 1782521856 0.0503011569 0.0000318056 0.3022295833 161 6.4000000000 0.0169618335 0.0090546312 0.0201858412 0.0093983072 0.2383820000 233251174 0 1784528896 0.0488471612 -0.0017527910 0.3042068779 162 6.4400000000 0.0171293654 0.0091044752 0.0201858412 0.0093992735 0.2259050000 233968987 0 1785221120 0.0472852364 -0.0021377355 0.3063422740 163 6.4800000000 0.0169039983 0.0091523251 0.0201858412 0.0093981443 0.1893990000 234724260 0 1784381440 0.0450412333 -0.0010798164 0.3060469925 164 6.5200000000 0.0159833413 0.0091939776 0.0201858412 0.0093817342 0.1256930000 234741191 0 1783631872 0.0431765392 -0.0028909715 0.3101961315 165 6.5600000000 0.0169575959 0.0092410298 0.0201858412 0.0093708574 0.2233980000 234654788 0 1776627712 0.0423183963 -0.0020429539 0.3111977279 166 6.6000000000 0.0176007971 0.0092913899 0.0201858412 0.0093591054 0.1530900000 233260428 0 1776508928 0.0407895744 -0.0015872708 0.3144428730 167 6.6400000000 0.0172185767 0.0093388581 0.0201858412 0.0093428702 0.1427800000 233260878 0 1777639424 0.0387553573 -0.0006727446 0.3149685860 168 6.6800000000 0.0173996314 0.0093868389 0.0201858412 0.0093279590 0.1299640000 233265520 0 1780183040 0.0372780859 -0.0011438318 0.3169497848 169 6.7200000000 0.0166045818 0.0094295474 0.0201858412 0.0093081098 0.1168930000 233263678 0 1781440512 0.0361585990 -0.0025120601 0.3167831004 170 6.7600000000 0.0175460987 0.0094772918 0.0201858412 0.0093057390 0.1287770000 233524866 0 1783484416 0.0337502956 -0.0004177419 0.3201232255 171 6.8000000000 0.0175105333 0.0095242698 0.0201858412 0.0092905195 0.2570710000 233557910 0 1784766464 0.0327784494 -0.0011689644 0.3211319149 172 6.8400000000 0.0190452449 0.0095796243 0.0201858412 0.0092834275 0.2180290000 234727799 0 1784684544 0.0314595439 -0.0004105214 0.3247725368 173 6.8800000000 0.0181089528 0.0096289268 0.0201858412 0.0092615934 0.2017070000 235119740 0 1784844288 0.0305680558 -0.0016400153 0.3241197467 174 6.9200000000 0.0182287358 0.0096783510 0.0201858412 0.0092854961 0.2442100000 235044174 0 1784455168 0.0303512439 -0.0030874750 0.3266163170 175 6.9600000000 0.0181299467 0.0097266458 0.0201858412 0.0092995980 0.1205170000 233539726 0 1784680448 0.0276631564 -0.0021736845 0.3274118006 176 7.0000000000 0.0191486944 0.0097801802 0.0201858412 0.0093128809 0.1247370000 233545768 0 1786494976 0.0294085667 -0.0036808448 0.3286142647 177 7.0400000000 0.0196111202 0.0098357222 0.0201858412 0.0093320925 0.1285340000 233554666 0 1783934976 0.0254478045 -0.0008643745 0.3286118209 178 7.0800000000 0.0189012364 0.0098866521 0.0201858412 0.0093339307 0.1291340000 233562992 0 1783144448 0.0257409960 -0.0023594145 0.3274993896 179 7.1200000000 0.0171482284 0.0099272196 0.0201858412 0.0093315587 0.1248000000 233564410 0 1782038528 0.0237252638 -0.0039017820 0.3283405900 180 7.1600000000 0.0153396763 0.0099572888 0.0201858412 0.0093507064 0.1261230000 233571128 0 1785053184 0.0215192549 -0.0055014254 0.3290801942 181 7.2000000000 0.0175782349 0.0099993934 0.0201858412 0.0093756916 0.1319410000 233574806 0 1785589760 0.0205833055 -0.0033899653 0.3305159509 182 7.2400000000 0.0155481463 0.0100298811 0.0201858412 0.0093839138 0.1337290000 233579356 0 1784692736 0.0213292465 -0.0061567314 0.3293526173 183 7.2800000000 0.0171327777 0.0100686947 0.0201858412 0.0094213076 0.1330760000 233582538 0 1784422400 0.0221672822 -0.0057498547 0.3311677575 184 7.3200000000 0.0182648953 0.0101132393 0.0201858412 0.0095447798 0.1792690000 234246100 0 1783406592 0.0227272920 -0.0052983752 0.3296471834 185 7.3600000000 0.0173089728 0.0101521352 0.0201858412 0.0095924075 0.5364270000 234325274 0 1781415936 0.0209305268 -0.0068236445 0.3335765898 186 7.4000000000 0.0186820142 0.0101979947 0.0201858412 0.0095821274 0.3659650000 236490527 0 1784168448 0.0216398183 -0.0055326335 0.3324890137 187 7.4400000000 0.0178129859 0.0102387166 0.0201858412 0.0095635144 0.2764290000 236407921 0 1783488512 0.0215449017 -0.0070070131 0.3339950740 188 7.4800000000 0.0179233402 0.0102795923 0.0201858412 0.0095552619 0.3562660000 236337126 0 1783050240 0.0220206175 -0.0088895047 0.3381668031 189 7.5200000000 0.0159456264 0.0103095713 0.0201858412 0.0095576979 0.2129390000 234232886 0 1783640064 0.0220107362 -0.0100839762 0.3334764540 190 7.5600000000 0.0157080665 0.0103379844 0.0201858412 0.0095607040 0.1951150000 234235492 0 1785962496 0.0219218694 -0.0111258868 0.3385457993 191 7.6000000000 0.0150033776 0.0103624105 0.0201858412 0.0095486794 0.1992350000 234238002 0 1783906304 0.0215762146 -0.0126930429 0.3416894674 192 7.6400000000 0.0168461017 0.0103961798 0.0201858412 0.0095411609 0.2172510000 234244152 0 1781874688 0.0221446436 -0.0098823318 0.3421515524 193 7.6800000000 0.0170566011 0.0104306897 0.0201858412 0.0095268971 0.1926180000 234245786 0 1783676928 0.0231560990 -0.0099397833 0.3416117132 194 7.7200000000 0.0171100684 0.0104651195 0.0201858412 0.0095112802 0.1952990000 234247164 0 1785311232 0.0237392783 -0.0102115450 0.3423166275 195 7.7600000000 0.0206006635 0.0105170967 0.0206006635 0.0095058798 0.1903480000 234249422 0 1784279040 0.0246721506 -0.0068439208 0.3462032378 196 7.8000000000 0.0221878029 0.0105766411 0.0221878029 0.0094942683 0.1951400000 234250992 0 1783783424 0.0244006254 -0.0039748857 0.3431133628 197 7.8400000000 0.0147020267 0.0105975821 0.0221878029 0.0095051436 0.1858410000 234253262 0 1785417728 0.0241223425 -0.0142619452 0.3433259726 198 7.8800000000 0.0164536517 0.0106271582 0.0221878029 0.0094835522 0.1931740000 234254400 0 1784528896 0.0262132883 -0.0140615059 0.3437112272 199 7.9200000000 0.0167686492 0.0106580200 0.0221878029 0.0094790992 0.1903130000 234257198 0 1780752384 0.0266025439 -0.0138769737 0.3453870118 200 7.9600000000 0.0185786672 0.0106976232 0.0221878029 0.0095007590 0.1852730000 234258376 0 1778958336 0.0233361311 -0.0082999617 0.3487631381 201 8.0000000000 0.0180747621 0.0107343254 0.0221878029 0.0094816816 0.1924920000 234259282 0 1779593216 0.0265936889 -0.0116964318 0.3450700343 202 8.0400000000 0.0168833993 0.0107647664 0.0221878029 0.0094767761 0.1867910000 234261336 0 1782247424 0.0270893052 -0.0141176898 0.3479114473 203 8.0800000000 0.0162778292 0.0107919243 0.0221878029 0.0094727354 0.1871420000 234263830 0 1784025088 0.0264826864 -0.0141515024 0.3485240936 204 8.1200000000 0.0220151339 0.0108469401 0.0221878029 0.0095558543 0.1808740000 234265340 0 1785040896 0.0211934820 -0.0061595030 0.3588640392 205 8.1600000000 0.0198556464 0.0108908850 0.0221878029 0.0095651882 0.1847070000 234266346 0 1785331712 0.0203064680 -0.0094247665 0.3606105447 206 8.1999999990 0.0186424758 0.0109285140 0.0221878029 0.0095669089 0.1900690000 234268348 0 1781903360 0.0243774131 -0.0120620318 0.3586516082 207 8.2400000000 0.0177691672 0.0109615607 0.0221878029 0.0095700707 0.1804740000 234270146 0 1781264384 0.0230323896 -0.0093921348 0.3551414013 208 8.2799999990 0.0190078355 0.0110002447 0.0221878029 0.0096350989 0.1810120000 234272024 0 1777438720 0.0214624703 -0.0093750916 0.3595684767 209 8.3200000000 0.0181804262 0.0110345996 0.0221878029 0.0096826552 0.1829260000 234273858 0 1775026176 0.0283620059 -0.0148681179 0.3552082479 210 8.3599999990 0.0431589931 0.0111875729 0.0431589931 0.0101516710 0.1812000000 234275108 0 1778196480 0.0167423189 0.0170752220 0.3650145233 211 8.4000000000 0.0391153842 0.0113199322 0.0431589931 0.0101515990 0.1920270000 234277438 0 1778679808 0.0184431002 0.0121157262 0.3658821881 212 8.4399999990 0.0285343342 0.0114011322 0.0431589931 0.0102499094 0.1794030000 234279180 0 1780596736 0.0175854042 -0.0035319049 0.3692688048 213 8.4800000000 0.0386962071 0.0115292781 0.0431589931 0.0103043931 0.1832080000 234281478 0 1782374400 0.0170038790 0.0102071464 0.3684687912 214 8.5200000000 0.0240306277 0.0115876957 0.0431589931 0.0103747227 0.1802000000 234283180 0 1784025088 0.0205187649 -0.0055662617 0.3631117940 215 8.5600000000 0.0292594805 0.0116698900 0.0431589931 0.0103762244 0.1787220000 234284406 0 1785802752 0.0204076543 0.0036772825 0.3591456115 216 8.6000000000 0.0339012481 0.0117728130 0.0431589931 0.0103830896 0.1810340000 234286508 0 1784172544 0.0222966671 0.0093658324 0.3565483689 217 8.6400000000 0.0417091213 0.0119107683 0.0431589931 0.0105680331 0.1804470000 234287634 0 1783279616 0.0141575933 0.0068153813 0.3768830597 218 8.6800000000 0.0369921252 0.0120258204 0.0431589931 0.0105472835 0.1759470000 234289648 0 1778454528 0.0134320259 0.0087964069 0.3675558269 219 8.7200000000 0.0276273414 0.0120970602 0.0431589931 0.0105743618 0.1788690000 234292122 0 1777438720 0.0166976154 0.0006443150 0.3624508381 220 8.7600000000 0.0319739729 0.0121874098 0.0431589931 0.0106513379 0.1790090000 234294680 0 1778343936 0.0140020847 -0.0038034804 0.3720631897 221 8.8000000000 0.0265687164 0.0122524836 0.0431589931 0.0106427464 0.1724230000 234295382 0 1780744192 0.0167096257 0.0020176973 0.3584895134 222 8.8400000000 0.0282322336 0.0123244645 0.0431589931 0.0106514041 0.1713950000 234297500 0 1782374400 0.0138349682 0.0025698189 0.3610829711 223 8.8800000000 0.0214774795 0.0123655094 0.0431589931 0.0106786593 0.1759870000 234299690 0 1784135680 0.0180201232 -0.0038757622 0.3569656014 224 8.9200000000 0.0383110270 0.0124813376 0.0431589931 0.0108184667 0.1734370000 234301544 0 1785802752 0.0124724060 0.0126624834 0.3641357422 225 8.9600000000 0.0237889998 0.0125315938 0.0431589931 0.0110115574 0.1799290000 234303862 0 1784926208 0.0139087737 -0.0103962328 0.3638601899 226 9.0000000000 0.0282831844 0.0126012911 0.0431589931 0.0110577392 0.1707390000 234305476 0 1786691584 0.0145756304 -0.0011710934 0.3632816672 227 9.0400000000 0.0388770066 0.0127170432 0.0431589931 0.0111159825 0.1672150000 234307646 0 1784315904 0.0123645663 0.0048598796 0.3716959357 228 9.0800000000 0.0255146269 0.0127731730 0.0431589931 0.0111173099 0.1716440000 234308756 0 1782288384 0.0157724619 0.0001652446 0.3571670651 229 9.1200000000 0.0187807847 0.0127994071 0.0431589931 0.0111341743 0.1701190000 234310082 0 1782153216 0.0182742923 -0.0054743551 0.3505240977 230 9.1600000000 0.0276964698 0.0128641769 0.0431589931 0.0111746976 0.1685290000 234312800 0 1783644160 0.0161324888 0.0031115580 0.3554918170 231 9.2000000000 0.0285155103 0.0129319316 0.0431589931 0.0112717111 0.1684190000 234314606 0 1785692160 0.0126023144 -0.0067090113 0.3628184795 232 9.2400000000 0.0220244639 0.0129711235 0.0431589931 0.0112632708 0.1653140000 234316600 0 1784520704 0.0165572912 -0.0051323138 0.3528220057 233 9.2800000000 0.0239302590 0.0130181585 0.0431589931 0.0112840846 0.1668290000 234318086 0 1784057856 0.0145667791 -0.0041959751 0.3546545208 234 9.3200000000 0.0450975560 0.0131552499 0.0450975560 0.0114841367 0.1680790000 234321740 0 1782800384 0.0045240074 0.0121969283 0.3692911863 235 9.3600000000 0.0268429946 0.0132134956 0.0450975560 0.0115494635 0.1648980000 234322930 0 1784803328 0.0122401118 -0.0004096068 0.3544499874 236 9.4000000000 0.0280418545 0.0132763277 0.0450975560 0.0115690510 0.1615160000 234324600 0 1786580992 0.0122658163 -0.0038117394 0.3564877808 237 9.4400000000 0.0279268306 0.0133381441 0.0450975560 0.0115656524 0.1645920000 234326810 0 1783631872 0.0101035684 -0.0049380120 0.3561717868 238 9.4800000000 0.0221831053 0.0133753078 0.0450975560 0.0115950916 0.1659360000 234328516 0 1782362112 0.0125312954 -0.0012528114 0.3451015353 239 9.5200000000 0.0416026674 0.0134934139 0.0450975560 0.0118226923 0.1710770000 234329478 0 1782259712 -0.0023527443 -0.0004743729 0.3665028214 240 9.5600000000 0.0165387504 0.0135061028 0.0450975560 0.0119916962 0.1648280000 234332760 0 1783554048 0.0155312270 -0.0090317000 0.3337648809 241 9.6000000000 0.0571899042 0.0136873634 0.0571899042 0.0127397262 0.1619580000 234334658 0 1785331712 -0.0062298775 -0.0093123494 0.3809461892 242 9.6400000000 0.0522908755 0.0138468821 0.0571899042 0.0127590066 0.1669590000 234336224 0 1784266752 -0.0075940639 0.0003988072 0.3742497861 243 9.6800000000 0.0243519135 0.0138901126 0.0571899042 0.0130401660 0.1599690000 234337578 0 1783910400 0.0108475834 -0.0200187452 0.3377993107 244 9.7200000000 0.0206885543 0.0139179751 0.0571899042 0.0130503768 0.1601050000 234339240 0 1783164928 0.0172904730 -0.0094661824 0.3170499802 245 9.7600000000 0.0298679154 0.0139830769 0.0571899042 0.0133587874 0.1706640000 234340906 0 1785057280 -0.0013214499 0.0035157269 0.3472846448 246 9.8000000000 0.0488855243 0.0141249568 0.0571899042 0.0135264634 0.1923550000 234342748 0 1786855424 -0.0115597695 0.0095649865 0.3637444973 247 9.8400000000 0.0247513317 0.0141679785 0.0571899042 0.0135880096 0.1613800000 234344334 0 1783791616 -0.0007954389 0.0015265874 0.3396748006 248 9.8800000000 0.0670482442 0.0143812054 0.0670482442 0.0141231674 0.1599460000 234345796 0 1782743040 -0.0012205243 0.0583231263 0.3419728875 249 9.9200000000 0.0266463496 0.0144304630 0.0670482442 0.0148869906 0.1621400000 234347330 0 1784803328 -0.0014752001 -0.0022060592 0.3384797573 250 9.9600000000 0.0301071294 0.0144931697 0.0670482442 0.0149263944 0.1619590000 234349232 0 1786580992 -0.0028709024 0.0010829004 0.3405988514 251 10.0000000000 0.0249633193 0.0145348834 0.0670482442 0.0149397110 0.1574350000 234351106 0 1783541760 -0.0012533963 -0.0034115708 0.3326065540 252 10.0400000000 0.0366199762 0.0146225227 0.0670482442 0.0151253944 0.1628690000 234352536 0 1782509568 0.0070325732 -0.0285049472 0.3182940483 253 10.0800000000 0.0272247698 0.0146723339 0.0670482442 0.0153806695 0.1522180000 234355074 0 1784532992 -0.0031799376 0.0070926505 0.3315528035 254 10.1200000000 0.0217380077 0.0147001516 0.0670482442 0.0153960781 0.1566410000 234356228 0 1786347520 -0.0036394298 -0.0028823134 0.3230811059 255 10.1600000000 0.0391335599 0.0147959688 0.0670482442 0.0156054268 0.1666210000 234357954 0 1784672256 -0.0137751549 0.0210694186 0.3386223316 256 10.2000000000 0.0264345650 0.0148414321 0.0670482442 0.0155962114 0.1577130000 234359580 0 1783398400 -0.0097281039 0.0212432500 0.3221420646 257 10.2400000000 0.0322952680 0.0149093459 0.0670482442 0.0157476447 0.1560810000 234361622 0 1785548800 -0.0147822499 0.0054664202 0.3323708177 258 10.2800000000 0.0365300290 0.0149931470 0.0670482442 0.0160191190 0.1621250000 234404988 0 1784827904 0.0048629194 -0.0218407139 0.3021360338 259 10.3200000000 0.0242777206 0.0150289947 0.0670482442 0.0162181269 0.1584150000 234406762 0 1784164352 -0.0064518601 0.0115164360 0.3181645274 260 10.3600000000 0.0453750268 0.0151457102 0.0670482442 0.0164390124 0.1539040000 234408288 0 1783529472 -0.0173095167 -0.0015764888 0.3394372463 261 10.4000000000 0.0562242642 0.0153030993 0.0670482442 0.0167576099 0.1633170000 234410114 0 1785184256 -0.0348468572 0.0442810617 0.3357206285 262 10.4400000000 0.0210802350 0.0153251495 0.0670482442 0.0169747145 0.1543390000 234411648 0 1784557568 -0.0146578699 0.0175861008 0.3113324940 263 10.4800000000 0.0289565139 0.0153769798 0.0670482442 0.0169760316 0.1583360000 234413274 0 1784057856 -0.0205615908 0.0305796824 0.3125447929 264 10.5200000000 0.0358575620 0.0154545577 0.0670482442 0.0169699932 0.1530830000 234414728 0 1783128064 -0.0171332508 0.0452282205 0.3027220964 265 10.5600000000 0.0241810866 0.0154874880 0.0670482442 0.0170848659 0.1498950000 234416690 0 1785036800 -0.0222624093 0.0241496060 0.3089733720 266 10.6000000000 0.0248262752 0.0155225962 0.0670482442 0.0170947084 0.1561840000 234418828 0 1786601472 -0.0177358687 0.0176961310 0.3097254932 267 10.6400000000 0.0347501710 0.0155946096 0.0670482442 0.0172376411 0.1547040000 234420054 0 1783541760 -0.0098473877 0.0448572040 0.2794211209 268 10.6800000000 0.0537560470 0.0157370031 0.0670482442 0.0173686894 0.1551390000 234421572 0 1782784000 -0.0239806622 0.0648918897 0.3006687760 269 10.7200000000 0.0487824976 0.0158598488 0.0670482442 0.0173889208 0.1563740000 234423042 0 1784295424 -0.0257387310 0.0558470264 0.3071660995 270 10.7600000000 0.0192654952 0.0158724623 0.0670482442 0.0175372292 0.1583540000 234424812 0 1786327040 -0.0196745545 0.0250250511 0.2940941453 271 10.8000000000 0.0205628872 0.0158897701 0.0670482442 0.0175208254 0.1602690000 234426390 0 1784557568 -0.0226153284 0.0267389342 0.2938221097 272 10.8400000000 0.0580656938 0.0160448286 0.0670482442 0.0177639294 0.1577480000 234427988 0 1783279616 -0.0183988735 0.0728901476 0.2815673649 273 10.8800000000 0.0297299754 0.0160949574 0.0670482442 0.0180194558 0.1551420000 234429322 0 1784573952 -0.0078902245 0.0363028198 0.2781638503 274 10.9200000000 0.0429407060 0.0161929346 0.0670482442 0.0184894459 0.1524710000 234431124 0 1786437632 -0.0190791488 -0.0232054070 0.2831913233 275 10.9600000000 0.0300719179 0.0162434036 0.0670482442 0.0190062934 0.1600590000 234433094 0 1784274944 -0.0151527226 0.0422296561 0.2690681219 276 11.0000000000 0.0555689000 0.0163858873 0.0670482442 0.0192078945 0.1876990000 234434708 0 1782632448 -0.0285883248 0.0613472573 0.3017601967 277 11.0400000000 0.0431476533 0.0164825002 0.0670482442 0.0192981482 0.1468310000 234436074 0 1782423552 -0.0194489360 0.0577648431 0.2624565065 278 11.0800000000 0.0170376953 0.0164844973 0.0670482442 0.0195595911 0.1580760000 234437324 0 1781514240 -0.0165782943 0.0150239058 0.2661773562 279 11.1200000000 0.0212920997 0.0165017288 0.0670482442 0.0195920769 0.1547510000 234439626 0 1781133312 -0.0263468102 0.0236308090 0.2824783623 280 11.1600000000 0.0128686642 0.0164887536 0.0670482442 0.0195904919 0.1533610000 234440912 0 1782771712 -0.0226917788 0.0186108593 0.2660216093 281 11.2000000000 0.0275017172 0.0165279456 0.0670482442 0.0195824916 0.1567460000 234442494 0 1784549376 -0.0118160248 0.0235270280 0.2480690777 282 11.2400000000 0.0360229090 0.0165970767 0.0670482442 0.0198151334 0.1568000000 234444240 0 1786056704 -0.0404520407 0.0441195071 0.2833920121 283 11.2800000000 0.0462382622 0.0167018159 0.0670482442 0.0197982452 0.1595810000 234445506 0 1784655872 -0.0458586887 0.0459764376 0.2934060395 284 11.3200000000 0.0307136290 0.0167511532 0.0670482442 0.0198439173 0.1590490000 234447328 0 1783291904 -0.0384447351 0.0254438836 0.2857265472 285 11.3600000000 0.0382107235 0.0168264500 0.0670482442 0.0198145870 0.1806450000 234942166 0 1784643584 -0.0380970761 0.0296480972 0.2906804085 286 11.4000000000 0.0394329093 0.0169054935 0.0670482442 0.0197803185 0.3353740000 235748055 0 1785745408 -0.0397161096 0.0319889747 0.2893355489 287 11.4400000000 0.3404764533 0.0180329185 0.3404764533 0.0305658464 0.2048490000 235636246 0 1786335232 0.0740382448 0.0109835975 -0.0697503015 288 11.4800000000 0.3441500068 0.0191652695 0.3441500068 0.0305141961 0.1873100000 234900304 0 1784135680 0.0746061578 0.0082405433 -0.0749764815 289 11.5200000000 0.3401965797 0.0202761045 0.3441500068 0.0304653171 0.1742920000 234901774 0 1785810944 0.0713806450 0.0133860540 -0.0727292448 290 11.5600000000 0.3410243094 0.0213821328 0.3441500068 0.0304185053 0.1822320000 234903396 0 1784897536 0.0694098473 0.0043704584 -0.0755028129 291 11.6000000000 0.3408730924 0.0224800398 0.3441500068 0.0303678450 0.1815490000 234904930 0 1784135680 0.0664203838 0.0010075497 -0.0774323121 292 11.6400000000 0.3388459980 0.0235634849 0.3441500068 0.0303167439 0.1730650000 234906744 0 1786064896 0.0636189282 0.0026733247 -0.0773219019 293 11.6800000000 0.3423289657 0.0246514217 0.3441500068 0.0302688927 0.1707810000 234908190 0 1784496128 0.0662070066 0.0027164221 -0.0811309591 294 11.7200000000 0.3388856649 0.0257202457 0.3441500068 0.0302200948 0.1657740000 234909760 0 1784029184 0.0603235662 0.0052919509 -0.0808651075 295 11.7600000000 0.3420300484 0.0267924823 0.3441500068 0.0301700699 0.1782830000 234911174 0 1786175488 0.0597175322 0.0021649972 -0.0851131454 296 11.8000000000 0.3382475972 0.0278446955 0.3441500068 0.0301215086 0.1694760000 234912396 0 1784516608 0.0536926240 0.0046926001 -0.0841018856 297 11.8400000000 0.3378760815 0.0288885722 0.3441500068 0.0300708494 0.1641600000 234914126 0 1782988800 0.0515576042 0.0049500084 -0.0851607248 298 11.8800000000 0.3329660594 0.0299089665 0.3441500068 0.0300229795 0.1605460000 234915808 0 1782886400 0.0468735546 0.0053419629 -0.0824064165 299 11.9200000000 0.3427842855 0.0309553722 0.3441500068 0.0299873724 0.1604300000 234917186 0 1784782848 0.0507847480 -0.0014917562 -0.0917061120 300 11.9600000000 0.3409270048 0.0319886110 0.3441500068 0.0299393853 0.1532180000 234918492 0 1786433536 0.0472891890 -0.0001157387 -0.0917163342 301 12.0000000000 0.3376047015 0.0330039469 0.3441500068 0.0298922788 0.1594820000 234920650 0 1783525376 0.0430528298 0.0003272723 -0.0903466269 302 12.0400000000 0.3349606395 0.0340038035 0.3441500068 0.0298448389 0.1553270000 234921904 0 1782087680 0.0395624265 0.0021671229 -0.0893923789 303 12.0800000000 0.3341160417 0.0349942729 0.3441500068 0.0297968342 0.1489590000 234923190 0 1783734272 0.0382244140 0.0033483012 -0.0898041800 304 12.1200000000 0.3386928141 0.0359932812 0.3441500068 0.0297546647 0.1838000000 234924780 0 1785925632 0.0373360291 0.0037501152 -0.0954926237 305 12.1600000000 0.3354386687 0.0369750694 0.3441500068 0.0297093435 0.1483320000 234926718 0 1785016320 0.0321880840 0.0013931561 -0.0944371819 306 12.2000000000 0.3391832709 0.0379626779 0.3441500068 0.0296645612 0.1501680000 234927972 0 1786834944 0.0331607424 0.0000074832 -0.0984238535 307 12.2400000000 0.3342511356 0.0389277869 0.3441500068 0.0296218984 0.1499280000 234929486 0 1783504896 0.0263941400 0.0046034879 -0.0964335054 308 12.2800000000 0.3380617499 0.0398990010 0.3441500068 0.0295756315 0.1443340000 234930892 0 1781981184 0.0258713067 0.0009783939 -0.1009337902 309 12.3200000000 0.3411896825 0.0408740518 0.3441500068 0.0295331854 0.1415460000 234932666 0 1781604352 0.0257716440 -0.0044808150 -0.1044522077 310 12.3600000000 0.3321304619 0.0418135886 0.3441500068 0.0294944430 0.1435090000 234934188 0 1780842496 0.0172577053 -0.0004851571 -0.0985465050 311 12.4000000000 0.3343007863 0.0427540619 0.3441500068 0.0294474921 0.1459120000 234935274 0 1780207616 0.0175650902 -0.0007326119 -0.1006600112 312 12.4400000000 0.3361417651 0.0436944071 0.3441500068 0.0294011877 0.1414890000 234937704 0 1779830784 0.0156176984 -0.0003598779 -0.1036246717 313 12.4800000000 0.3351490498 0.0446255721 0.3441500068 0.0293546738 0.1418710000 234938674 0 1781497856 0.0143150240 -0.0025468003 -0.1032084674 314 12.5200000000 0.3380441964 0.0455600263 0.3441500068 0.0293112744 0.1371820000 234940128 0 1783132160 0.0124614388 -0.0092985062 -0.1063751727 315 12.5600000000 0.3317597806 0.0464685970 0.3441500068 0.0292689913 0.1345640000 234941742 0 1784893440 0.0075540170 -0.0056829005 -0.1017589793 316 12.6000000000 0.3376865387 0.0473901727 0.3441500068 0.0292302071 0.1368750000 234943172 0 1786671104 0.0085876845 -0.0045661675 -0.1076183766 317 12.6400000000 0.3355266154 0.0482991205 0.3441500068 0.0291879013 0.1379390000 234945254 0 1783377920 0.0033050962 -0.0117943138 -0.1069750264 318 12.6800000000 0.3364070356 0.0492051202 0.3441500068 0.0291535454 0.1315710000 234946532 0 1782108160 0.0042325296 -0.0070338072 -0.1079339534 319 12.7200000000 0.3380400836 0.0501105590 0.3441500068 0.0291147787 0.1315240000 234947646 0 1781731328 0.0052374415 -0.0040456494 -0.1099546701 320 12.7600000000 0.3320087492 0.0509914908 0.3441500068 0.0290748050 0.1351460000 234949592 0 1783386112 -0.0034095682 -0.0103404652 -0.1067059487 321 12.8000000000 0.3289140463 0.0518572932 0.3441500068 0.0290300000 0.1343180000 234951186 0 1785307136 -0.0080018751 -0.0120820766 -0.1056799665 322 12.8400000000 0.3324724138 0.0527287687 0.3441500068 0.0289874125 0.1344490000 234952532 0 1784627200 -0.0052672401 -0.0121246558 -0.1090545282 323 12.8800000000 0.3258047998 0.0535742054 0.3441500068 0.0289464613 0.1337760000 234954130 0 1784016896 -0.0073711909 -0.0069624395 -0.1036743820 324 12.9200000000 0.3296040595 0.0544261493 0.3441500068 0.0289053484 0.1331250000 234955620 0 1783128064 -0.0076696724 -0.0076382216 -0.1087180674 325 12.9600000000 0.3294342458 0.0552723281 0.3441500068 0.0288637812 0.1383030000 234957578 0 1780600832 -0.0069137774 -0.0039590313 -0.1092545837 326 13.0000000000 0.3314459324 0.0561194864 0.3441500068 0.0288243772 0.1284430000 234958884 0 1780056064 -0.0075252876 -0.0023960937 -0.1127333567 327 13.0400000000 0.3270742893 0.0569480944 0.3441500068 0.0287857510 0.1332560000 234960474 0 1779470336 -0.0138735399 -0.0104487846 -0.1110992655 328 13.0800000000 0.3257086277 0.0577674862 0.3441500068 0.0287435236 0.1324800000 234961444 0 1781092352 -0.0166280381 -0.0103841778 -0.1115317196 329 13.1200000000 0.3369398713 0.0586160345 0.3441500068 0.0287115909 0.1289390000 234963234 0 1782870016 -0.0076911636 -0.0107407812 -0.1214080825 330 13.1600000000 0.3262740374 0.0594271194 0.3441500068 0.0286807778 0.1281940000 234965024 0 1784631296 -0.0173514187 -0.0053809164 -0.1150849983 331 13.2000000000 0.3287729025 0.0602408529 0.3441500068 0.0286411188 0.1333640000 234966322 0 1786298368 -0.0147466920 -0.0017890236 -0.1183449030 332 13.2400000000 0.3221150935 0.0610296307 0.3441500068 0.0285990365 0.1655050000 235364364 0 1784414208 -0.0200953074 -0.0028801975 -0.1146246940 333 13.2800000000 0.3236346543 0.0618182344 0.3441500068 0.0285599126 0.2488240000 235979453 0 1780477952 -0.0196426325 -0.0034880466 -0.1180645972 334 13.3200000000 0.3619376421 0.0627167955 0.3619376421 0.0287264770 0.1937320000 235834980 0 1779220480 -0.0236783139 0.0245120637 -0.1612089574 335 13.3600000000 0.3604061902 0.0636054205 0.3619376421 0.0286852042 0.1459280000 235370802 0 1781141504 -0.0262568183 0.0223409031 -0.1619846672 336 13.4000000000 0.3608853817 0.0644901823 0.3619376421 0.0286585173 0.1531970000 235372392 0 1782775808 -0.0276452862 0.0243649147 -0.1650127172 337 13.4400000000 0.3616899848 0.0653720808 0.3619376421 0.0286246226 0.1848370000 235373622 0 1784266752 -0.0285259932 0.0232721400 -0.1692141294 338 13.4800000000 0.3608450592 0.0662462612 0.3619376421 0.0285851233 0.1442800000 235375196 0 1786314752 -0.0284702480 0.0232305191 -0.1702696979 339 13.5200000000 0.3588530123 0.0671094080 0.3619376421 0.0285490297 0.1589570000 235376694 0 1784549376 -0.0340697728 0.0231966246 -0.1722797453 340 13.5600000000 0.3625063896 0.0679782227 0.3625063896 0.0285099495 0.1551880000 235378484 0 1782927360 -0.0293921866 0.0204777494 -0.1771443635 341 13.6000000000 0.3636759520 0.0688453714 0.3636759520 0.0284691365 0.1532350000 235379406 0 1785081856 -0.0305889845 0.0245924462 -0.1806148887 342 13.6400000000 0.3592721522 0.0696945725 0.3636759520 0.0284288943 0.1494580000 235381256 0 1786712064 -0.0364515744 0.0244188178 -0.1801084578 343 13.6800000000 0.3603081107 0.0705418423 0.3636759520 0.0283880462 0.1481250000 235382762 0 1783275520 -0.0372666344 0.0205468144 -0.1838949919 344 13.7200000000 0.3604780734 0.0713846802 0.3636759520 0.0283496907 0.1497190000 235384444 0 1782132736 -0.0349523574 0.0230948403 -0.1861219704 345 13.7600000000 0.3582473397 0.0722161662 0.3636759520 0.0283118378 0.1531250000 235385966 0 1783885824 -0.0399741083 0.0235656500 -0.1881938279 346 13.8000000000 0.3604539037 0.0730492232 0.3636759520 0.0282716528 0.1481250000 235386988 0 1785315328 -0.0390603356 0.0247261282 -0.1926068664 347 13.8400000000 0.3586872816 0.0738723877 0.3636759520 0.0282313458 0.1501410000 235388938 0 1784270848 -0.0425419249 0.0228094310 -0.1945795864 348 13.8800000000 0.3577181399 0.0746880364 0.3636759520 0.0281912163 0.1522000000 235390228 0 1783640064 -0.0448226072 0.0236794986 -0.1964056939 349 13.9200000000 0.3585826457 0.0755014880 0.3636759520 0.0281518415 0.1470660000 235391526 0 1782808576 -0.0448575392 0.0205446519 -0.2000561655 350 13.9600000000 0.3574951887 0.0763071843 0.3636759520 0.0281133361 0.1467140000 235392908 0 1784918016 -0.0460346751 0.0230516903 -0.2021217197 351 14.0000000000 0.3580552340 0.0771098853 0.3636759520 0.0280742987 0.1449360000 235394766 0 1786601472 -0.0473496728 0.0206613876 -0.2057813704 352 14.0400000000 0.3585456312 0.0779094186 0.3636759520 0.0280371011 0.1486710000 235396180 0 1783025664 -0.0483019836 0.0203838237 -0.2094320357 353 14.0800000000 0.3572992980 0.0787008914 0.3636759520 0.0279988508 0.1556980000 235397402 0 1781604352 -0.0497020856 0.0212553646 -0.2110676765 354 14.1200000000 0.3590473831 0.0794928306 0.3636759520 0.0279607689 0.1456780000 235399384 0 1780846592 -0.0485772640 0.0232504476 -0.2150139809 355 14.1600000000 0.3571882248 0.0802750712 0.3636759520 0.0279226701 0.1416030000 235400974 0 1779974144 -0.0514908656 0.0197036304 -0.2163798362 356 14.2000000000 0.3557136953 0.0810487752 0.3636759520 0.0278838672 0.1428420000 235402280 0 1781633024 -0.0531046167 0.0208788514 -0.2177028656 357 14.2400000000 0.3560099304 0.0818189745 0.3636759520 0.0278455071 0.1391920000 235403586 0 1783410688 -0.0534513555 0.0184934549 -0.2207151353 358 14.2800000000 0.3568143547 0.0825871180 0.3636759520 0.0278080409 0.1552700000 235404784 0 1784700928 -0.0538479201 0.0171587206 -0.2235812247 359 14.3200000000 0.3560509980 0.0833488558 0.3636759520 0.0277716316 0.1496050000 235406390 0 1786699776 -0.0560238212 0.0204519518 -0.2255901545 360 14.3600000000 0.3535434604 0.0840993964 0.3636759520 0.0277345765 0.1451350000 235408012 0 1783021568 -0.0595009550 0.0206376128 -0.2262183428 361 14.4000000000 0.3570432961 0.0848554737 0.3636759520 0.0277014133 0.1411530000 235409602 0 1781878784 -0.0557099245 0.0195507072 -0.2308820933 362 14.4400000000 0.3524581492 0.0855947076 0.3636759520 0.0276647189 0.1377240000 235411224 0 1784176640 -0.0593863018 0.0172827896 -0.2300131321 363 14.4800000000 0.3510851860 0.0863260863 0.3636759520 0.0276326163 0.1402400000 235412730 0 1785839616 -0.0654364079 0.0194181055 -0.2320811152 364 14.5200000000 0.3537241220 0.0870606963 0.3636759520 0.0275982374 0.1411590000 235414220 0 1785057280 -0.0627459735 0.0195882730 -0.2363719493 365 14.5600000000 0.3570936918 0.0878005127 0.3636759520 0.0275625889 0.1444190000 235415366 0 1786716160 -0.0585567318 0.0160347708 -0.2411487252 366 14.6000000000 0.3523459435 0.0885233144 0.3636759520 0.0275318707 0.1372260000 235417308 0 1783652352 -0.0648344904 0.0226891544 -0.2399294674 367 14.6400000000 0.3538629115 0.0892463106 0.3636759520 0.0274953560 0.1372160000 235418630 0 1782640640 -0.0639844686 0.0197272673 -0.2437053770 368 14.6800000000 0.3554216921 0.0899696133 0.3636759520 0.0274607475 0.1417990000 235420280 0 1781751808 -0.0634631738 0.0188364852 -0.2475440353 369 14.7200000000 0.3539741039 0.0906850726 0.3636759520 0.0274265009 0.1693650000 235421654 0 1783046144 -0.0638100579 0.0215349253 -0.2480190843 370 14.7600000000 0.3521237969 0.0913916638 0.3636759520 0.0273928949 0.1345060000 235423560 0 1785204736 -0.0672209263 0.0159141961 -0.2495535910 371 14.8000000000 0.3535569012 0.0920983086 0.3636759520 0.0273569368 0.1402740000 235424858 0 1786822656 -0.0661211759 0.0200953800 -0.2530465424 372 14.8400000000 0.3541953862 0.0928028706 0.3636759520 0.0273212061 0.1428150000 235425996 0 1783025664 -0.0655412301 0.0204161722 -0.2563374043 373 14.8800000000 0.3525523543 0.0934992500 0.3636759520 0.0272877474 0.1424410000 235427318 0 1782370304 -0.0677171722 0.0205531344 -0.2579231560 374 14.9200000000 0.3492648900 0.0941831153 0.3636759520 0.0272608631 0.1401280000 235429008 0 1779228672 -0.0731476024 0.0188890919 -0.2582795024 375 14.9600000000 0.3476018906 0.0948588987 0.3636759520 0.0272334513 0.1369300000 235430766 0 1778466816 -0.0778910518 0.0211593453 -0.2593396306 376 15.0000000000 0.3525979221 0.0955443748 0.3636759520 0.0271979382 0.1420560000 235432404 0 1775800320 -0.0721959323 0.0234443825 -0.2649648190 377 15.0400000000 0.3499239981 0.0962191218 0.3636759520 0.0271675699 0.1398990000 235433918 0 1775292416 -0.0731340423 0.0174027905 -0.2651053369 378 15.0800000000 0.3492619395 0.0968885473 0.3636759520 0.0271395297 0.1354440000 235435048 0 1772630016 -0.0775464252 0.0174278356 -0.2682761848 379 15.1200000000 0.3455762267 0.0975447153 0.3636759520 0.0271105789 0.1344660000 235436638 0 1771737088 -0.0826127231 0.0158694033 -0.2680723965 380 15.1600000000 0.3500193954 0.0982091224 0.3636759520 0.0270770680 0.1370420000 235438196 0 1770848256 -0.0771998391 0.0191751514 -0.2737182975 381 15.2000000000 0.3464209437 0.0988605970 0.3636759520 0.0270459053 0.1380500000 235439970 0 1772343296 -0.0812285915 0.0157754570 -0.2731557786 382 15.2400000000 0.3457431495 0.0995068864 0.3636759520 0.0270122829 0.1344850000 235441376 0 1774120960 -0.0856937245 0.0189124495 -0.2762427032 383 15.2800000000 0.3493541181 0.1001592290 0.3636759520 0.0269771627 0.1371930000 235442950 0 1775775744 -0.0816062987 0.0192644428 -0.2808640897 384 15.3200000000 0.3485805988 0.1008061597 0.3636759520 0.0269422479 0.1335660000 235444164 0 1777442816 -0.0838990062 0.0214336645 -0.2828223407 385 15.3600000000 0.3481822908 0.1014486951 0.3636759520 0.0269100591 0.1356840000 235445294 0 1779220480 -0.0826743245 0.0189990047 -0.2842415273 386 15.4000000000 0.3493070006 0.1020908150 0.3636759520 0.0268753979 0.1405700000 235447100 0 1780854784 -0.0835431740 0.0186723731 -0.2883785069 387 15.4400000000 0.3425053060 0.1027120411 0.3636759520 0.0268468203 0.1596430000 235858594 0 1782632448 -0.0917364657 0.0218165517 -0.2856973410 388 15.4800000000 0.3437595367 0.1033332975 0.3636759520 0.0268133088 0.3058660000 236630719 0 1785712640 -0.0909793451 0.0214140564 -0.2885578871 389 15.5200000000 0.3535300791 0.1039764769 0.3636759520 0.0267793214 0.1744000000 236536436 0 1784385536 -0.0851261467 0.0237935372 -0.2995232642 390 15.5600000000 0.3570685983 0.1046254311 0.3636759520 0.0267469871 0.1774530000 235880592 0 1783820288 -0.0851454437 0.0311019383 -0.3044305444 391 15.6000000000 0.3559376597 0.1052681733 0.3636759520 0.0267143409 0.1623320000 235881598 0 1780461568 -0.0859384313 0.0312385373 -0.3054939806 392 15.6400000000 0.3550494611 0.1059053705 0.3636759520 0.0266849030 0.1624490000 235883724 0 1779605504 -0.0873643681 0.0315079726 -0.3071471751 393 15.6800000000 0.3564567864 0.1065429059 0.3636759520 0.0266526423 0.1609270000 235884554 0 1778716672 -0.0894234776 0.0327641331 -0.3112374544 394 15.7200000000 0.3578262329 0.1071806809 0.3636759520 0.0266211665 0.1608890000 235886404 0 1780502528 -0.0889989585 0.0329227000 -0.3145472407 395 15.7600000000 0.3541283011 0.1078058647 0.3636759520 0.0265931088 0.1569550000 235888054 0 1781645312 -0.0941864252 0.0313928202 -0.3144958615 396 15.8000000000 0.3546167314 0.1084291245 0.3636759520 0.0265624811 0.1589950000 235889620 0 1783791616 -0.0939416066 0.0310707353 -0.3176730871 397 15.8400000000 0.3557422459 0.1090520794 0.3636759520 0.0265330129 0.1641860000 235890818 0 1785421824 -0.0942086801 0.0335450023 -0.3204560578 398 15.8800000000 0.3569930792 0.1096750468 0.3636759520 0.0265050017 0.1606270000 235892592 0 1784389632 -0.0960903317 0.0344506055 -0.3243140876 399 15.9200000000 0.3561638892 0.1102928133 0.3636759520 0.0264734762 0.1577040000 235893830 0 1784037376 -0.0965596065 0.0335997492 -0.3255528808 400 15.9600000000 0.3542189598 0.1109026287 0.3636759520 0.0264415490 0.1878970000 235895552 0 1783402496 -0.0999638662 0.0337728336 -0.3267689645 401 16.0000000000 0.3526261747 0.1115054305 0.3636759520 0.0264153965 0.1592180000 235896874 0 1784909824 -0.1021796018 0.0334722102 -0.3277959526 402 16.0400000000 0.3535194993 0.1121074556 0.3636759520 0.0263874688 0.1548010000 235898364 0 1786597376 -0.1040126234 0.0291835312 -0.3314696550 403 16.0800000000 0.3560450971 0.1127127599 0.3636759520 0.0263565443 0.1555780000 235899494 0 1783631872 -0.1035337895 0.0334742889 -0.3356558084 404 16.1200000000 0.3522298634 0.1133056240 0.3636759520 0.0263366045 0.1636410000 235901428 0 1782509568 -0.1078808606 0.0391457975 -0.3349160254 405 16.1600000000 0.3555962741 0.1139038725 0.3636759520 0.0263163859 0.1552520000 235902718 0 1782255616 -0.1050288379 0.0347823910 -0.3394804299 406 16.2000000000 0.3566033840 0.1145016546 0.3636759520 0.0262851848 0.1582350000 235904500 0 1779986432 -0.1050660536 0.0359956995 -0.3428473771 407 16.2400000000 0.3529331088 0.1150874812 0.3636759520 0.0262652599 0.1519430000 235905966 0 1779187712 -0.1080976129 0.0394485593 -0.3410483599 408 16.2800000000 0.3561574817 0.1156783391 0.3636759520 0.0262376180 0.1530670000 235907128 0 1781010432 -0.1078440994 0.0375500992 -0.3465285301 409 16.3200000000 0.3514838815 0.1162548808 0.3636759520 0.0262100041 0.1511180000 235908786 0 1782898688 -0.1119960994 0.0381204523 -0.3446476758 410 16.3600000000 0.3520193994 0.1168299162 0.3636759520 0.0261782999 0.1575700000 235910308 0 1784410112 -0.1118752584 0.0402808525 -0.3471429050 411 16.3999999990 0.3506833613 0.1173989027 0.3636759520 0.0261542288 0.1521370000 235911790 0 1786187776 -0.1131051257 0.0407160446 -0.3480269015 412 16.4400000000 0.3504972160 0.1179646753 0.3636759520 0.0261277591 0.1465970000 235913572 0 1784541184 -0.1150056124 0.0415881984 -0.3503586650 413 16.4800000000 0.3504375219 0.1185275635 0.3636759520 0.0260995121 0.1517690000 235914762 0 1783382016 -0.1155345440 0.0418490805 -0.3522617221 414 16.5200000000 0.3562120199 0.1191016806 0.3636759520 0.0260688956 0.1557360000 235916084 0 1785671680 -0.1114677936 0.0439165160 -0.3590981066 415 16.5599999990 0.3520469964 0.1196629946 0.3636759520 0.0260400747 0.1491870000 235917858 0 1784803328 -0.1174146384 0.0463036261 -0.3586187363 416 16.6000000000 0.3509891033 0.1202190669 0.3636759520 0.0260118072 0.1456220000 235919424 0 1784311808 -0.1161431521 0.0453547947 -0.3593538404 417 16.6400000000 0.3500380814 0.1207701917 0.3636759520 0.0259875131 0.1474940000 235920822 0 1783672832 -0.1184709370 0.0413519070 -0.3616319895 418 16.6800000000 0.3502286375 0.1213191353 0.3636759520 0.0259596126 0.1478650000 235922420 0 1785311232 -0.1175717711 0.0440981127 -0.3636218011 419 16.7199999990 0.3488413393 0.1218621477 0.3636759520 0.0259431097 0.1456770000 235923882 0 1784659968 -0.1222241595 0.0401905254 -0.3664669991 420 16.7600000000 0.3502707481 0.1224059777 0.3636759520 0.0259213990 0.1560820000 235924896 0 1784201216 -0.1233266667 0.0409700908 -0.3706199825 421 16.8000000000 0.3457915187 0.1229365847 0.3636759520 0.0258968538 0.1473200000 235926378 0 1782509568 -0.1284180284 0.0406659096 -0.3700003326 422 16.8400000000 0.3458108604 0.1234647228 0.3636759520 0.0258680690 0.1449730000 235927716 0 1782366208 -0.1276683509 0.0427450500 -0.3726481795 423 16.8799999990 0.3470222950 0.1239932277 0.3636759520 0.0258400927 0.1498900000 235930026 0 1781657600 -0.1254449487 0.0429163128 -0.3757845461 424 16.9200000000 0.3479037583 0.1245213186 0.3636759520 0.0258111244 0.1504910000 235932004 0 1783386112 -0.1246567965 0.0470987633 -0.3791951537 425 16.9600000000 0.3493591249 0.1250503487 0.3636759520 0.0257923426 0.1475030000 235932926 0 1784819712 -0.1239264011 0.0439668037 -0.3839577436 426 17.0000000000 0.3485718369 0.1255750471 0.3636759520 0.0257661288 0.1450500000 235934240 0 1786564608 -0.1286426485 0.0499014966 -0.3867028654 427 17.0400000000 0.3508108258 0.1261025313 0.3636759520 0.0257361987 0.1516950000 235936466 0 1783775232 -0.1264468282 0.0494188480 -0.3913219869 428 17.0800000000 0.3478135467 0.1266205477 0.3636759520 0.0257064513 0.1436740000 235937772 0 1782870016 -0.1270841956 0.0492969006 -0.3922173679 429 17.1200000000 0.3451304138 0.1271298947 0.3636759520 0.0256778375 0.1501620000 235938702 0 1784930304 -0.1303146482 0.0494809002 -0.3934697807 430 17.1600000000 0.3495090306 0.1276470555 0.3636759520 0.0256495682 0.1463370000 235940720 0 1786601472 -0.1268782169 0.0470702574 -0.4003195763 431 17.2000000000 0.3456903100 0.1281529563 0.3636759520 0.0256208642 0.1749020000 235942118 0 1783504896 -0.1305476278 0.0483007133 -0.4008148313 432 17.2400000000 0.3458973169 0.1286569942 0.3636759520 0.0255925739 0.1518880000 235943492 0 1782489088 -0.1303703189 0.0501495749 -0.4038258195 433 17.2800000000 0.3446893096 0.1291559141 0.3636759520 0.0255665355 0.1517030000 235944798 0 1784655872 -0.1323520839 0.0529496595 -0.4060533345 434 17.3200000000 0.3459475636 0.1296554340 0.3636759520 0.0255410738 0.1458720000 235946188 0 1786470400 -0.1305113435 0.0487635322 -0.4105223119 435 17.3600000000 0.3451924026 0.1301509213 0.3636759520 0.0255126645 0.1503340000 235948170 0 1783382016 -0.1335040182 0.0518868528 -0.4136472642 436 17.4000000000 0.3451461196 0.1306440296 0.3636759520 0.0254951781 0.1503770000 235949576 0 1782493184 -0.1336236447 0.0474416837 -0.4173923433 437 17.4400000000 0.3453636467 0.1311353788 0.3636759520 0.0254731796 0.1448610000 235950854 0 1784266752 -0.1324618459 0.0527182072 -0.4199202061 438 17.4800000000 0.3467043042 0.1316275453 0.3636759520 0.0254478017 0.1473340000 235952444 0 1785696256 -0.1298778504 0.0503660850 -0.4244528413 439 17.5200000000 0.3463218808 0.1321165984 0.3636759520 0.0254218060 0.1502720000 235953642 0 1784643584 -0.1261286438 0.0523407236 -0.4266931415 440 17.5600000000 0.3449696004 0.1326003553 0.3636759520 0.0253993186 0.1540230000 235955408 0 1784168448 -0.1308126301 0.0523161367 -0.4291208386 441 17.6000000000 0.3437586725 0.1330791723 0.3636759520 0.0253777500 0.1490360000 235956506 0 1782898688 -0.1320323050 0.0516090915 -0.4310178757 442 17.6400000000 0.3439598978 0.1335562780 0.3636759520 0.0253556398 0.1477810000 235958372 0 1784537088 -0.1295021772 0.0575999767 -0.4328692257 443 17.6800000000 0.3408442736 0.1340241968 0.3636759520 0.0253352497 0.1463830000 235959710 0 1786040320 -0.1344792545 0.0572915077 -0.4330367744 444 17.7200000000 0.3419216871 0.1344924343 0.3636759520 0.0253083577 0.1496210000 235961108 0 1784782848 -0.1354777366 0.0552863814 -0.4371913075 445 17.7600000000 0.3445371687 0.1349644450 0.3636759520 0.0252825834 0.1478670000 235962774 0 1786568704 -0.1316701919 0.0502992757 -0.4424335361 446 17.8000000000 0.3430326283 0.1354309656 0.3636759520 0.0252550823 0.1533950000 235964808 0 1785057280 -0.1340379119 0.0526118204 -0.4439058900 447 17.8400000000 0.3453048468 0.1359004821 0.3636759520 0.0252307184 0.1492820000 235965646 0 1786822656 -0.1324759573 0.0553024635 -0.4482047260 448 17.8800000000 0.3396115303 0.1363551943 0.3636759520 0.0252064367 0.1519200000 235967212 0 1785180160 -0.1384674311 0.0553741381 -0.4460955560 449 17.9200000000 0.3423980474 0.1368140870 0.3636759520 0.0251817002 0.1504220000 235969062 0 1784295424 -0.1352246553 0.0499860197 -0.4510470331 450 17.9600000000 0.3400469422 0.1372657156 0.3636759520 0.0251549537 0.1485490000 235970468 0 1782386688 -0.1401444077 0.0519542955 -0.4544920325 451 18.0000000000 0.3413842916 0.1377183067 0.3636759520 0.0251334414 0.1524290000 235971514 0 1781374976 -0.1361446530 0.0534710474 -0.4575206637 452 18.0400000000 0.3416674137 0.1381695215 0.3636759520 0.0251114097 0.1480500000 235973372 0 1783140352 -0.1382158697 0.0524697974 -0.4602207839 453 18.0800000000 0.3410667181 0.1386174182 0.3636759520 0.0250902174 0.1455020000 235974686 0 1784643584 -0.1405702531 0.0532874018 -0.4621987343 454 18.1200000000 0.3388570845 0.1390584747 0.3636759520 0.0250673714 0.1495480000 235976436 0 1786675200 -0.1392536014 0.0516700335 -0.4626703858 455 18.1600000000 0.3393391371 0.1394986520 0.3636759520 0.0250415799 0.1856280000 236417614 0 1782644736 -0.1409681141 0.0571268164 -0.4659490883 456 18.2000000000 0.3383068442 0.1399346349 0.3636759520 0.0250148795 0.3751450000 236757019 0 1782755328 -0.1433441490 0.0571639240 -0.4680673480 457 18.2400000000 0.3392536044 0.1403707814 0.3636759520 0.0249924490 0.2020860000 237358773 0 1785319424 -0.1424447894 0.0565570407 -0.4712879062 458 18.2800000000 0.3410873115 0.1408090271 0.3636759520 0.0249841445 0.2122210000 237225024 0 1785774080 -0.1419487894 0.0439675525 -0.4767775834 459 18.3200000000 0.3409356773 0.1412450329 0.3636759520 0.0249675860 0.1720220000 236429418 0 1784586240 -0.1441837251 0.0436786413 -0.4794666469 460 18.3600000000 0.3419435918 0.1416813341 0.3636759520 0.0249464317 0.2089130000 236431360 0 1786372096 -0.1447778642 0.0423855558 -0.4835463166 461 18.4000000000 0.3416037560 0.1421150053 0.3636759520 0.0249215110 0.1820070000 236432598 0 1784840192 -0.1448282748 0.0442993790 -0.4858253598 462 18.4400000000 0.3429343998 0.1425496793 0.3636759520 0.0249052722 0.1763150000 236434372 0 1786642432 -0.1451645494 0.0436905771 -0.4896450937 463 18.4800000000 0.3408063948 0.1429778796 0.3636759520 0.0248860119 0.1750230000 236435870 0 1785094144 -0.1471090317 0.0439702719 -0.4906585217 464 18.5200000000 0.3418351412 0.1434064513 0.3636759520 0.0248637981 0.1786590000 236437392 0 1786118144 -0.1476383358 0.0413190201 -0.4943167567 465 18.5600000000 0.3415497541 0.1438325659 0.3636759520 0.0248392264 0.1726220000 236439074 0 1784713216 -0.1485809535 0.0438247323 -0.4970274270 466 18.6000000000 0.3387259245 0.1442507920 0.3636759520 0.0248138068 0.1759740000 236440396 0 1786605568 -0.1533462107 0.0454638526 -0.4979805648 467 18.6400000000 0.3400667906 0.1446700982 0.3636759520 0.0247876908 0.1772790000 236441594 0 1785241600 -0.1521343589 0.0465851426 -0.5020900369 468 18.6800000000 0.3400564492 0.1450875904 0.3636759520 0.0247617914 0.1722300000 236442984 0 1784336384 -0.1555795074 0.0466539487 -0.5056690574 469 18.7200000000 0.3398041129 0.1455027642 0.3636759520 0.0247398600 0.1713200000 236444926 0 1782554624 -0.1559251398 0.0466271043 -0.5082405806 470 18.7600000000 0.3392407596 0.1459149727 0.3636759520 0.0247139548 0.1714880000 236446032 0 1781559296 -0.1593348980 0.0490219742 -0.5114026666 471 18.8000000000 0.3401028812 0.1463272613 0.3636759520 0.0247017103 0.1707710000 236447462 0 1783345152 -0.1590650976 0.0495711043 -0.5147755742 472 18.8400000000 0.3368935287 0.1467310033 0.3636759520 0.0247207861 0.1738570000 236448852 0 1784844288 -0.1611117125 0.0505131036 -0.5147693157 473 18.8800000000 0.3382171392 0.1471358366 0.3636759520 0.0247226632 0.1713410000 236450642 0 1786621952 -0.1621362418 0.0502286330 -0.5191249847 474 18.9200000000 0.3376745284 0.1475378170 0.3636759520 0.0246997236 0.1758330000 236452548 0 1782321152 -0.1659428328 0.0522675961 -0.5215577483 475 18.9600000000 0.3391953409 0.1479413065 0.3636759520 0.0246756938 0.1679470000 236453746 0 1781432320 -0.1648820937 0.0531784818 -0.5255653858 476 19.0000000000 0.3371509314 0.1483388057 0.3636759520 0.0246622869 0.1681820000 236455344 0 1783214080 -0.1665324569 0.0551006794 -0.5264478922 477 19.0400000000 0.3387438655 0.1487379777 0.3636759520 0.0246393578 0.1792500000 236456974 0 1784700928 -0.1657469273 0.0565445200 -0.5308997631 478 19.0800000000 0.3360955417 0.1491299392 0.3636759520 0.0246149261 0.1791370000 236458372 0 1786621952 -0.1692887545 0.0589507744 -0.5311967134 479 19.1200000000 0.3358983696 0.1495198524 0.3636759520 0.0245926845 0.1709810000 236460030 0 1783336960 -0.1724866331 0.0596033931 -0.5338363647 480 19.1600000000 0.3372171819 0.1499108885 0.3636759520 0.0245702545 0.1712750000 236461612 0 1782464512 -0.1735198796 0.0618920252 -0.5377376080 481 19.2000000000 0.3364194334 0.1502986402 0.3636759520 0.0245483886 0.1748750000 236462750 0 1784250368 -0.1768690795 0.0612646490 -0.5397577286 482 19.2400000000 0.3365659714 0.1506850869 0.3636759520 0.0245257988 0.1691490000 236464248 0 1785606144 -0.1760523617 0.0621829703 -0.5422146320 483 19.2800000000 0.3346202374 0.1510659050 0.3636759520 0.0245137034 0.1668400000 236466122 0 1783975936 -0.1806025505 0.0631123632 -0.5427994132 484 19.3200000000 0.3366093934 0.1514492593 0.3636759520 0.0244916551 0.1686420000 236467320 0 1782829056 -0.1773052216 0.0627421290 -0.5463404059 485 19.3600000000 0.3343063891 0.1518262843 0.3636759520 0.0244672448 0.1693580000 236468642 0 1781288960 -0.1791783124 0.0648735538 -0.5459234715 486 19.4000000000 0.3353499472 0.1522039050 0.3636759520 0.0244429717 0.1664460000 236470240 0 1782849536 -0.1803815663 0.0634933785 -0.5492327213 487 19.4400000000 0.3337236643 0.1525766356 0.3636759520 0.0244195490 0.1703470000 236471554 0 1784225792 -0.1815413982 0.0647185668 -0.5497104526 488 19.4800000000 0.3345946670 0.1529496233 0.3636759520 0.0243966460 0.2063440000 236473152 0 1785987072 -0.1817922890 0.0652507991 -0.5527540445 489 19.5200000000 0.3355485797 0.1533230363 0.3636759520 0.0243766741 0.1611990000 236474590 0 1784754176 -0.1819504350 0.0647493154 -0.5555831194 490 19.5600000000 0.3362216949 0.1536962989 0.3636759520 0.0243529442 0.1651990000 236476432 0 1786515456 -0.1800816059 0.0662380606 -0.5579406023 491 19.6000000000 0.3343287706 0.1540641858 0.3636759520 0.0243298175 0.1671700000 236477654 0 1784844288 -0.1832619905 0.0644113868 -0.5584294796 492 19.6400000000 0.3346417546 0.1544312134 0.3636759520 0.0243055257 0.1710760000 236479176 0 1786621952 -0.1842175722 0.0639918149 -0.5609551072 493 19.6800000000 0.3335004747 0.1547944370 0.3636759520 0.0242818728 0.1735250000 236481174 0 1785102336 -0.1854431927 0.0653556287 -0.5617930889 494 19.7200000000 0.3344717622 0.1551581563 0.3636759520 0.0242573120 0.1662670000 236482520 0 1784340480 -0.1857327074 0.0672048330 -0.5647665858 495 19.7600000000 0.3330468833 0.1555175275 0.3636759520 0.0242387295 0.1692970000 236484318 0 1782448128 -0.1863905489 0.0650979429 -0.5654981136 496 19.8000000000 0.3331875801 0.1558757332 0.3636759520 0.0242169236 0.1663560000 236485188 0 1781559296 -0.1896424294 0.0663255006 -0.5682234168 497 19.8400000000 0.3331795633 0.1562324814 0.3636759520 0.0241952965 0.1659330000 236486862 0 1783218176 -0.1879062355 0.0654322803 -0.5699005723 498 19.8800000000 0.3321078718 0.1565856448 0.3636759520 0.0241724847 0.1675170000 236488384 0 1784590336 -0.1895353794 0.0651676059 -0.5703915954 499 19.9200000000 0.3321548402 0.1569374869 0.3636759520 0.0241482763 0.1642800000 236490358 0 1786368000 -0.1888505667 0.0645249188 -0.5726416111 500 19.9600000000 0.3329700232 0.1572895520 0.3636759520 0.0241242347 0.1670250000 236491664 0 1784127488 -0.1880554855 0.0651027560 -0.5757599473 501 20.0000000000 0.3336984813 0.1576416656 0.3636759520 0.0241113098 0.1665460000 236492710 0 1782702080 -0.1885187775 0.0616496205 -0.5789737701 502 20.0400000000 0.3329143524 0.1579908144 0.3636759520 0.0240960704 0.1658700000 236494232 0 1784356864 -0.1922110021 0.0630095452 -0.5811961889 503 20.0800000000 0.3333178461 0.1583393771 0.3636759520 0.0240741906 0.1654990000 236495906 0 1786118144 -0.1875151098 0.0608783811 -0.5840776563 504 20.1200000000 0.3330216706 0.1586859689 0.3636759520 0.0240505044 0.1735220000 236497380 0 1784492032 -0.1898925602 0.0636366606 -0.5862964392 505 20.1600000000 0.3313712180 0.1590279199 0.3636759520 0.0240269539 0.1659700000 236498718 0 1786531840 -0.1880170107 0.0649594516 -0.5871455073 506 20.2000000000 0.3338710666 0.1593734597 0.3636759520 0.0240035221 0.1644760000 236500516 0 1783336960 -0.1877852082 0.0677918196 -0.5919229388 507 20.2400000000 0.3322916627 0.1597145213 0.3636759520 0.0239812893 0.1633920000 236501906 0 1782464512 -0.1894156933 0.0683365464 -0.5929095149 508 20.2800000000 0.3315851390 0.1600528492 0.3636759520 0.0239588075 0.1592560000 236503628 0 1784594432 -0.1905230582 0.0675579309 -0.5951520801 509 20.3200000000 0.3318462074 0.1603903608 0.3636759520 0.0239402403 0.1573790000 236505242 0 1786376192 -0.1890411228 0.0639819652 -0.5976244807 510 20.3600000000 0.3320759833 0.1607269992 0.3636759520 0.0239219056 0.1639750000 236507024 0 1784995840 -0.1908365190 0.0640944988 -0.6004897952 511 20.4000000000 0.3328099549 0.1610637565 0.3636759520 0.0238987074 0.1608100000 236508378 0 1786777600 -0.1897383034 0.0667995065 -0.6036302447 512 20.4400000000 0.3337187767 0.1614009733 0.3636759520 0.0238754772 0.1609520000 236509824 0 1785278464 -0.1892553419 0.0674695075 -0.6073541641 513 20.4800000000 0.3350893557 0.1617395472 0.3636759520 0.0238532747 0.1585860000 236510954 0 1784496128 -0.1827417910 0.0679007769 -0.6111804247 514 20.5200000000 0.3348779082 0.1620763922 0.3636759520 0.0238327130 0.1560750000 236596772 0 1782579200 -0.1856324375 0.0671539903 -0.6145552397 515 20.5600000000 0.3346234858 0.1624114351 0.3636759520 0.0238107449 0.1908200000 237018294 0 1781710848 -0.1846283525 0.0681574047 -0.6170035005 516 20.6000000000 0.3341589272 0.1627442791 0.3636759520 0.0237904737 0.3730680000 237067604 0 1782833152 -0.1834365427 0.0679946393 -0.6192792058 517 20.6400000000 0.3341173530 0.1630757551 0.3636759520 0.0237683035 0.2981280000 238135357 0 1785532416 -0.1810144484 0.0679964274 -0.6216462255 518 20.6800000000 0.3350343704 0.1634077215 0.3636759520 0.0237486186 0.2054470000 238083206 0 1785516032 -0.1798936427 0.0658466816 -0.6253257990 519 20.7200000000 0.3355037868 0.1637393132 0.3636759520 0.0237279171 0.1895210000 237030298 0 1785921536 -0.1787627190 0.0660168529 -0.6284873486 520 20.7600000000 0.3348458111 0.1640683641 0.3636759520 0.0237072327 0.1796170000 237031512 0 1784913920 -0.1777767688 0.0655500740 -0.6302352548 521 20.8000000000 0.3357304037 0.1643978498 0.3636759520 0.0236847953 0.1752880000 237034126 0 1786679296 -0.1790514737 0.0666657835 -0.6335341930 522 20.8400000000 0.3359796703 0.1647265506 0.3636759520 0.0236623452 0.1822220000 237034796 0 1785040896 -0.1777779758 0.0686204731 -0.6361038089 523 20.8800000000 0.3359217048 0.1650538836 0.3636759520 0.0236404172 0.1725740000 237036678 0 1786806272 -0.1779251844 0.0668728650 -0.6385045052 524 20.9200000000 0.3367905617 0.1653816253 0.3636759520 0.0236183138 0.1766680000 237038084 0 1785167872 -0.1763659418 0.0662989467 -0.6417220831 525 20.9600000000 0.3354553580 0.1657055753 0.3636759520 0.0235972958 0.1718150000 237039506 0 1784389632 -0.1765397489 0.0684808642 -0.6426657438 526 21.0000000000 0.3359604180 0.1660292537 0.3636759520 0.0235769546 0.1704100000 237041028 0 1783136256 -0.1764433682 0.0697667450 -0.6453741193 527 21.0400000000 0.3345321119 0.1663489935 0.3636759520 0.0235549437 0.1729010000 237042474 0 1782247424 -0.1761334389 0.0689300895 -0.6458758116 528 21.0800000000 0.3367951810 0.1666718082 0.3636759520 0.0235371011 0.1699320000 237044424 0 1784033280 -0.1743876040 0.0681632757 -0.6499244571 529 21.1200000000 0.3348567188 0.1669897381 0.3636759520 0.0235189014 0.1642330000 237045746 0 1785536512 -0.1756241173 0.0706306249 -0.6498783231 530 21.1600000000 0.3355810046 0.1673078349 0.3636759520 0.0235005075 0.1620110000 237047144 0 1784025088 -0.1749387830 0.0693896711 -0.6524398327 531 21.2000000000 0.3360273540 0.1676255741 0.3636759520 0.0234850251 0.1707260000 237048810 0 1782607872 -0.1717574894 0.0696552247 -0.6544734240 532 21.2400000000 0.3345376551 0.1679393186 0.3636759520 0.0234697888 0.1677760000 237049964 0 1780961280 -0.1739673913 0.0691159964 -0.6548350453 533 21.2800000000 0.3363985419 0.1682553772 0.3636759520 0.0234543693 0.1658440000 237051886 0 1782890496 -0.1731430739 0.0670509040 -0.6583582163 534 21.3200000000 0.3359326422 0.1685693795 0.3636759520 0.0234330200 0.1662120000 237053200 0 1784500224 -0.1732664704 0.0657813102 -0.6593801975 535 21.3600000000 0.3361487687 0.1688826120 0.3636759520 0.0234140606 0.1682030000 237055146 0 1786277888 -0.1726047993 0.0661610365 -0.6608641148 536 21.4000000000 0.3356847465 0.1691938100 0.3636759520 0.0233944174 0.1634790000 237056416 0 1785274368 -0.1739288568 0.0657511801 -0.6621502638 537 21.4400000000 0.3367209435 0.1695057786 0.3636759520 0.0233758308 0.1631140000 237057930 0 1784528896 -0.1728004068 0.0650452226 -0.6643307209 538 21.4800000000 0.3363402188 0.1698158798 0.3636759520 0.0233632380 0.1636510000 237059300 0 1782599680 -0.1729762405 0.0659075081 -0.6651242971 539 21.5200000000 0.3361171782 0.1701244165 0.3636759520 0.0233506445 0.1662350000 237060622 0 1781604352 -0.1725118160 0.0636512041 -0.6662316322 540 21.5600000000 0.3372009397 0.1704338175 0.3636759520 0.0233370240 0.1578890000 237062028 0 1783390208 -0.1726272851 0.0631590635 -0.6686068773 541 21.6000000000 0.3368265033 0.1707413826 0.3636759520 0.0233207775 0.1579250000 237063666 0 1784766464 -0.1726585776 0.0639851540 -0.6694671512 542 21.6400000000 0.3375746310 0.1710491930 0.3636759520 0.0233018989 0.1654240000 237065464 0 1786396672 -0.1731027067 0.0606842488 -0.6715345979 543 21.6800000000 0.3364541531 0.1713538062 0.3636759520 0.0232868346 0.1563940000 237066910 0 1783107584 -0.1730723083 0.0628410131 -0.6713456511 544 21.7200000000 0.3361697495 0.1716567766 0.3636759520 0.0232664302 0.1567480000 237068700 0 1782476800 -0.1751688421 0.0602724403 -0.6725193858 545 21.7600000000 0.3354185820 0.1719572570 0.3636759520 0.0232459947 0.1925970000 237069830 0 1784532992 -0.1745530069 0.0602979362 -0.6726205945 546 21.8000000000 0.3361929357 0.1722580550 0.3636759520 0.0232301836 0.1556170000 237071100 0 1786269696 -0.1758732498 0.0593134612 -0.6744744182 547 21.8400000000 0.3368518353 0.1725589577 0.3636759520 0.0232243268 0.1629630000 237073038 0 1784885248 -0.1745738983 0.0586929768 -0.6759892702 548 21.8800000000 0.3367830515 0.1728586367 0.3636759520 0.0232107605 0.1939540000 237645076 0 1786798080 -0.1750143468 0.0565651208 -0.6771643758 549 21.9200000000 0.3366684914 0.1731570153 0.3636759520 0.0231957389 0.4605700000 237617542 0 1784098816 -0.1747316867 0.0522999167 -0.6780270338 550 21.9600000000 0.3375519216 0.1734559151 0.3636759520 0.0231816026 0.3513990000 238901755 0 1785114624 -0.1761669219 0.0515208840 -0.6800649166 551 22.0000000000 0.3362199366 0.1737513126 0.3636759520 0.0231635242 0.2104490000 238859957 0 1784598528 -0.1766541302 0.0548961759 -0.6796880960 552 22.0400000000 0.3342476189 0.1740420668 0.3636759520 0.0231434976 0.2205590000 238789898 0 1784262656 -0.1796798110 0.0494648069 -0.6790703535 553 22.0800000000 0.3339332938 0.1743312010 0.3636759520 0.0231270184 0.1831510000 237625230 0 1784393728 -0.1783325821 0.0497097075 -0.6793678403 554 22.1200000000 0.3345638514 0.1746204296 0.3636759520 0.0231121548 0.1860300000 237626592 0 1786421248 -0.1824231446 0.0485347360 -0.6812317967 555 22.1600000000 0.3337890804 0.1749072200 0.3636759520 0.0230962029 0.1910450000 237628006 0 1784881152 -0.1804451793 0.0497851148 -0.6813669801 556 22.2000000000 0.3347356617 0.1751946812 0.3636759520 0.0230759708 0.1846050000 237629240 0 1786933248 -0.1812425852 0.0478142947 -0.6833939552 557 22.2400000000 0.3343962431 0.1754805009 0.3636759520 0.0230556301 0.1814910000 237630026 0 1783595008 -0.1807685941 0.0445954055 -0.6838129163 558 22.2800000000 0.3333234489 0.1757633736 0.3636759520 0.0230388360 0.1774020000 237631168 0 1782599680 -0.1800866425 0.0462362543 -0.6832228303 559 22.3200000000 0.3342225552 0.1760468426 0.3636759520 0.0230241660 0.1764960000 237633082 0 1784639488 -0.1836755723 0.0464892387 -0.6853080988 560 22.3600000000 0.3335062563 0.1763280201 0.3636759520 0.0230053895 0.1704270000 237634936 0 1786306560 -0.1824578047 0.0455834717 -0.6852717400 561 22.4000000000 0.3338506520 0.1766088091 0.3636759520 0.0229872882 0.1806220000 237636062 0 1784520704 -0.1813688576 0.0443068817 -0.6862912178 562 22.4400000000 0.3331120610 0.1768872846 0.3636759520 0.0229743810 0.1678830000 237637088 0 1783214080 -0.1814200580 0.0499732792 -0.6859030128 563 22.4800000000 0.3342851996 0.1771668547 0.3636759520 0.0229560244 0.1656240000 237637338 0 1785020416 -0.1805022657 0.0479042754 -0.6877633333 564 22.5200000000 0.3323132992 0.1774419370 0.3636759520 0.0229374807 0.1647480000 237639176 0 1784647680 -0.1827769727 0.0463248044 -0.6866165996 565 22.5600000000 0.3317693770 0.1777150829 0.3636759520 0.0229233187 0.1586100000 237639770 0 1783762944 -0.1837425232 0.0477008224 -0.6867431998 566 22.6000000000 0.3333782256 0.1779901061 0.3636759520 0.0229071454 0.1598540000 237642760 0 1782837248 -0.1823954284 0.0462779477 -0.6888229847 567 22.6400000000 0.3337728977 0.1782648553 0.3636759520 0.0228885782 0.1564470000 237641706 0 1784512512 -0.1819868088 0.0414426029 -0.6902650595 568 22.6800000000 0.3317934573 0.1785351522 0.3636759520 0.0228723881 0.1557150000 237643988 0 1786310656 -0.1816652864 0.0431589931 -0.6884578466 569 22.7200000000 0.3325910568 0.1788059007 0.3636759520 0.0228581860 0.1550370000 237644670 0 1784397824 -0.1801399589 0.0416895747 -0.6897616982 570 22.7600000000 0.3329510689 0.1790763308 0.3636759520 0.0228442475 0.1879030000 237647060 0 1782853632 -0.1844290197 0.0436867326 -0.6909739971 571 22.8000000000 0.3310712278 0.1793425215 0.3636759520 0.0228308133 0.1606980000 237645442 0 1781858304 -0.1835485697 0.0449662358 -0.6895960569 572 22.8400000000 0.3319247365 0.1796092736 0.3636759520 0.0228169636 0.1950680000 238212872 0 1781071872 -0.1833769530 0.0419427305 -0.6913328171 573 22.8800000000 0.3308149576 0.1798731579 0.3636759520 0.0227998424 0.4043260000 238173098 0 1781596160 -0.1831638217 0.0424682274 -0.6909726262 574 22.9200000000 0.3316227794 0.1801375301 0.3636759520 0.0227836847 0.3410590000 239733371 0 1785016320 -0.1832806915 0.0415557697 -0.6928268671 575 22.9600000000 0.3325183690 0.1804025402 0.3636759520 0.0227693563 0.2408610000 239680037 0 1784205312 -0.1831371635 0.0410919115 -0.6945524216 576 23.0000000000 0.3331944048 0.1806678039 0.3636759520 0.0227552274 0.2465720000 239605642 0 1782857728 -0.1846885830 0.0396319106 -0.6964374781 577 23.0400000000 0.3334206939 0.1809325402 0.3636759520 0.0227410528 0.1815430000 238177314 0 1783648256 -0.1824764311 0.0372703820 -0.6973636746 578 23.0800000000 0.3323096633 0.1811944384 0.3636759520 0.0227283699 0.1671680000 238179452 0 1785196544 -0.1824925691 0.0375605673 -0.6970071197 579 23.1200000000 0.3340018988 0.1814583546 0.3636759520 0.0227140556 0.1713670000 238181534 0 1784401920 -0.1833555549 0.0346022621 -0.6997593641 580 23.1600000000 0.3334525526 0.1817204135 0.3636759520 0.0227015524 0.1748210000 238182944 0 1783939072 -0.1828223020 0.0350827575 -0.6998674870 581 23.2000000000 0.3319306076 0.1819789509 0.3636759520 0.0226864848 0.1672550000 238182934 0 1780719616 -0.1809312105 0.0340777859 -0.6986705065 582 23.2400000000 0.3329170644 0.1822382947 0.3636759520 0.0226720882 0.1667430000 238184532 0 1780092928 -0.1849137098 0.0335727409 -0.7006754279 583 23.2800000000 0.3335586190 0.1824978493 0.3636759520 0.0226599946 0.1612130000 238185906 0 1782018048 -0.1816070676 0.0338180810 -0.7017454505 584 23.3200000000 0.3323006928 0.1827543610 0.3636759520 0.0226445514 0.1601490000 238186532 0 1784160256 -0.1807946861 0.0335131958 -0.7009580135 585 23.3600000000 0.3327096105 0.1830106948 0.3636759520 0.0226339494 0.1550030000 238185778 0 1785810944 -0.1814388633 0.0333164260 -0.7016043663 586 23.4000000000 0.3335735798 0.1832676280 0.3636759520 0.0226254058 0.1573870000 238185348 0 1784045568 -0.1805174351 0.0331921689 -0.7029646635 587 23.4400000000 0.3339650929 0.1835243528 0.3636759520 0.0226108979 0.1534830000 238187830 0 1783668736 -0.1835696250 0.0316234082 -0.7041613460 588 23.4800000000 0.3306127191 0.1837745031 0.3636759520 0.0225998086 0.1488750000 238185244 0 1785032704 -0.1799870133 0.0340479985 -0.7002432346 589 23.5200000000 0.3326925933 0.1840273352 0.3636759520 0.0225877057 0.1596870000 238188286 0 1784819712 -0.1823060215 0.0328458510 -0.7030510306 590 23.5600000000 0.3317477703 0.1842777088 0.3636759520 0.0225744721 0.1471610000 238189300 0 1783664640 -0.1813625693 0.0342479274 -0.7022614479 591 23.6000000000 0.3314713836 0.1845267675 0.3636759520 0.0225584626 0.1458850000 238191554 0 1783140352 -0.1793293655 0.0326556489 -0.7017884254 592 23.6400000000 0.3315801322 0.1847751684 0.3636759520 0.0225483737 0.1434520000 238192608 0 1784901632 -0.1816828251 0.0326825157 -0.7023897171 593 23.6800000000 0.3329455853 0.1850250342 0.3636759520 0.0225356113 0.1434100000 238192722 0 1786589184 -0.1807491481 0.0316752456 -0.7038333416 594 23.7200000000 0.3313913941 0.1852714422 0.3636759520 0.0225181598 0.1441950000 238193940 0 1783263232 -0.1806452572 0.0293213539 -0.7028914094 595 23.7600000000 0.3352356255 0.1855234829 0.3636759520 0.0225048745 0.1440050000 238198150 0 1782362112 -0.1849643588 0.0294042490 -0.7072083354 596 23.8000000000 0.3315718472 0.1857685305 0.3636759520 0.0224916839 0.1748930000 238197696 0 1784049664 -0.1813804805 0.0292256102 -0.7033578753 597 23.8400000000 0.3319868445 0.1860134523 0.3636759520 0.0224750199 0.1360690000 238199710 0 1785827328 -0.1803796887 0.0269840322 -0.7036536932 598 23.8800000000 0.3315789402 0.1862568728 0.3636759520 0.0224612799 0.1465080000 238197016 0 1784430592 -0.1823272407 0.0313158929 -0.7033145428 599 23.9200000000 0.3318460286 0.1864999265 0.3636759520 0.0224437170 0.1410240000 238201306 0 1783906304 -0.1796959937 0.0295898430 -0.7032673359 600 23.9600000000 0.3330466151 0.1867441710 0.3636759520 0.0224264767 0.1362530000 238201248 0 1780207616 -0.1822105348 0.0261911154 -0.7050303221 601 24.0000000000 0.3326070309 0.1869868712 0.3636759520 0.0224103436 0.1385830000 238202502 0 1779077120 -0.1832262278 0.0267392229 -0.7045827508 602 24.0400000000 0.3316238523 0.1872271320 0.3636759520 0.0223937250 0.1371320000 238204440 0 1777430528 -0.1823984683 0.0231997333 -0.7035785913 603 24.0800000000 0.3295162916 0.1874631008 0.3636759520 0.0223828391 0.1359160000 238207038 0 1776029696 -0.1818615198 0.0253850631 -0.7009977102 604 24.1200000000 0.3317860663 0.1877020461 0.3636759520 0.0223688876 0.1375110000 238207252 0 1774637056 -0.1803821027 0.0220870078 -0.7030722499 605 24.1600000000 0.3313178420 0.1879394276 0.3636759520 0.0223581235 0.1335630000 238211386 0 1775636480 -0.1773916185 0.0274918452 -0.7019708753 606 24.2000000000 0.3332334459 0.1881791867 0.3636759520 0.0223432385 0.1302580000 238210448 0 1777819648 -0.1820601523 0.0217763316 -0.7046744823 607 24.2400000000 0.3315435350 0.1884153717 0.3636759520 0.0223271780 0.1315940000 238211798 0 1779449856 -0.1792492568 0.0251870845 -0.7024474144 608 24.2800000000 0.3331419826 0.1886534089 0.3636759520 0.0223095976 0.1376560000 238215144 0 1781080064 -0.1794061661 0.0220183097 -0.7042069435 609 24.3200000000 0.3302767873 0.1888859596 0.3636759520 0.0222921138 0.1304880000 238216238 0 1782370304 -0.1770325303 0.0219994057 -0.7009452581 610 24.3600000000 0.3314525783 0.1891196754 0.3636759520 0.0222794699 0.1755150000 238609496 0 1784381440 -0.1779786050 0.0249018744 -0.7023202181 611 24.4000000000 0.3330680728 0.1893552702 0.3636759520 0.0222623414 0.3610330000 238656906 0 1786707968 -0.1788077950 0.0239651818 -0.7038742900 612 24.4400000000 0.3306566477 0.1895861548 0.3636759520 0.0222449259 0.2707720000 240042515 0 1783451648 -0.1763818860 0.0195257813 -0.7018334866 613 24.4800000000 0.3304007351 0.1898158686 0.3636759520 0.0222293788 0.2733600000 239989728 0 1782480896 -0.1768484116 0.0233447310 -0.7013552189 614 24.5200000000 0.3306831717 0.1900452942 0.3636759520 0.0222121463 0.1653610000 238607988 0 1783545856 -0.1783648729 0.0223989300 -0.7018731833 615 24.5600000000 0.3300320208 0.1902729149 0.3636759520 0.0221943960 0.1593040000 238608466 0 1785319424 -0.1789382994 0.0226142704 -0.7013733387 616 24.6000000000 0.3312387764 0.1905017556 0.3636759520 0.0221790011 0.1634610000 238614212 0 1783914496 -0.1780880988 0.0207761228 -0.7028770447 617 24.6400000000 0.3316944838 0.1907305930 0.3636759520 0.0221641238 0.1689370000 238621614 0 1782411264 -0.1786270738 0.0186913572 -0.7034319043 618 24.6800000000 0.3295726776 0.1909552566 0.3636759520 0.0221517848 0.1657660000 238617812 0 1780998144 -0.1754225791 0.0217020828 -0.7008783221 619 24.7200000000 0.3287994564 0.1911779451 0.3636759520 0.0221407959 0.1614480000 238622326 0 1783197696 -0.1761504412 0.0198914167 -0.7006817460 620 24.7600000000 0.3277816474 0.1913982737 0.3636759520 0.0221290731 0.1649030000 238625544 0 1784938496 -0.1754267514 0.0222635865 -0.7004331350 621 24.8000000000 0.3296654522 0.1916209261 0.3636759520 0.0221121710 0.1547250000 238623138 0 1786101760 -0.1758362353 0.0220095906 -0.7026585340 622 24.8400000000 0.3292698562 0.1918422267 0.3636759520 0.0220947366 0.1596160000 238627592 0 1784934400 -0.1756741107 0.0217914600 -0.7023659945 623 24.8800000000 0.3290941119 0.1920625347 0.3636759520 0.0220772942 0.1608230000 238627430 0 1786736640 -0.1746265292 0.0191051308 -0.7022981644 624 24.9200000000 0.3301407993 0.1922838140 0.3636759520 0.0220601103 0.1621940000 238630864 0 1783279616 -0.1723866761 0.0191613529 -0.7035005093 625 24.9600000000 0.3319172561 0.1925072275 0.3636759520 0.0220437612 0.1935790000 238633694 0 1782411264 -0.1724233329 0.0195165183 -0.7051942348 626 25.0000000000 0.3322311938 0.1927304287 0.3636759520 0.0220264944 0.1593530000 238636592 0 1784324096 -0.1731740534 0.0200787485 -0.7056573629 627 25.0400000000 0.3334335089 0.1929548355 0.3636759520 0.0220093207 0.1563430000 238636718 0 1785700352 -0.1726231575 0.0206361432 -0.7069289684 628 25.0800000000 0.3318410516 0.1931759919 0.3636759520 0.0219924277 0.1582160000 238641396 0 1784315904 -0.1702570915 0.0194891971 -0.7053183317 629 25.1200000000 0.3323435485 0.1933972440 0.3636759520 0.0219754017 0.1597480000 238641238 0 1783537664 -0.1683296263 0.0196278859 -0.7063242197 630 25.1600000000 0.3315038979 0.1936164609 0.3636759520 0.0219599528 0.1585260000 238646552 0 1782013952 -0.1663987041 0.0210149605 -0.7051470280 631 25.2000000000 0.3330146372 0.1938373772 0.3636759520 0.0219439532 0.1560730000 238647798 0 1783287808 -0.1658251584 0.0192684904 -0.7064689994 632 25.2400000000 0.3329823911 0.1940575433 0.3636759520 0.0219275640 0.1550040000 238649392 0 1785065472 -0.1651179790 0.0163751803 -0.7066740394 633 25.2800000000 0.3353913724 0.1942808195 0.3636759520 0.0219110295 0.1609350000 238651838 0 1784061952 -0.1629320085 0.0195488278 -0.7089237571 634 25.3200000000 0.3351183832 0.1945029608 0.3636759520 0.0218957712 0.1619820000 238654200 0 1782538240 -0.1611746848 0.0187596735 -0.7080730200 635 25.3600000000 0.3386308849 0.1947299339 0.3636759520 0.0218807319 0.1549780000 238655038 0 1781886976 -0.1611126065 0.0185268726 -0.7110146880 636 25.4000000000 0.3351696730 0.1949507511 0.3636759520 0.0218648162 0.1550000000 238658188 0 1783291904 -0.1568411589 0.0206533130 -0.7074186206 637 25.4400000000 0.3366757035 0.1951732393 0.3636759520 0.0218503946 0.1555800000 238660498 0 1784049664 -0.1566600800 0.0192375481 -0.7087745070 638 25.4800000000 0.3376934528 0.1953966252 0.3636759520 0.0218345484 0.1655500000 238660020 0 1787342848 -0.1549578905 0.0202157777 -0.7091068029 639 25.5200000000 0.3366399705 0.1956176633 0.3636759520 0.0218176756 0.1546760000 238660294 0 1782558720 -0.1523599923 0.0197351929 -0.7079452872 640 25.5600000000 0.3368500769 0.1958383389 0.3636759520 0.0218019321 0.1526650000 238662040 0 1781649408 -0.1500937939 0.0172396284 -0.7077451944 641 25.6000000000 0.3371269107 0.1960587579 0.3636759520 0.0217853708 0.1496320000 238662118 0 1783308288 -0.1460999548 0.0218037274 -0.7069680691 642 25.6400000000 0.3391546309 0.1962816487 0.3636759520 0.0217710214 0.1519510000 238664348 0 1784664064 -0.1443239152 0.0188763142 -0.7090942860 643 25.6800000000 0.3440751135 0.1965114985 0.3636759520 0.0217560431 0.1544180000 238666846 0 1786462208 -0.1448846161 0.0220729336 -0.7138941884 644 25.7200000000 0.3419172764 0.1967372839 0.3636759520 0.0217405254 0.1526790000 238666936 0 1785184256 -0.1415547729 0.0205556024 -0.7109423280 645 25.7600000000 0.3436892033 0.1969651163 0.3636759520 0.0217237824 0.1480620000 238669626 0 1784426496 -0.1374146938 0.0192290805 -0.7119232416 646 25.8000000000 0.3368403018 0.1971816414 0.3636759520 0.0217076694 0.1494780000 238671540 0 1782665216 -0.1323888600 0.0192568451 -0.7044196129 647 25.8400000000 0.3427134454 0.1974065746 0.3636759520 0.0216921807 0.1483950000 238676482 0 1781649408 -0.1342168450 0.0223329142 -0.7097206116 648 25.8800000000 0.3489944041 0.1976405065 0.3636759520 0.0216787035 0.1472800000 238673496 0 1783050240 -0.1346618831 0.0186478347 -0.7156749964 649 25.9200000000 0.3442761898 0.1978664474 0.3636759520 0.0216634940 0.1460030000 238677050 0 1784557568 -0.1274242699 0.0198528692 -0.7100181580 650 25.9600000000 0.3471455872 0.1980961076 0.3636759520 0.0216485919 0.1500810000 238677900 0 1786335232 -0.1262743473 0.0242098346 -0.7120728493 651 26.0000000000 0.3431979716 0.1983189984 0.3636759520 0.0216330178 0.1535780000 238683026 0 1785057280 -0.1203915775 0.0248179901 -0.7072598934 652 26.0400000000 0.3498594165 0.1985514223 0.3636759520 0.0216238168 0.1478210000 238683336 0 1786843136 -0.1239277422 0.0190449692 -0.7150442004 653 26.0800000000 0.3462938070 0.1987776741 0.3636759520 0.0216082399 0.1489730000 238685506 0 1783934976 -0.1194614470 0.0215394795 -0.7108966708 654 26.1200000000 0.3468873203 0.1990041414 0.3636759520 0.0215926055 0.1462290000 238684544 0 1782284288 -0.1113291085 0.0215208344 -0.7093493342 655 26.1600000000 0.3437335193 0.1992251023 0.3636759520 0.0215763807 0.1494140000 238689010 0 1784176640 -0.1078522503 0.0194754470 -0.7057622671 656 26.2000000000 0.3488526046 0.1994531930 0.3636759520 0.0215612343 0.1795510000 238687780 0 1785552896 -0.1070657372 0.0223807879 -0.7098933458 657 26.2400000000 0.3445525765 0.1996740444 0.3636759520 0.0215455573 0.1527750000 238691502 0 1784061952 -0.1015463769 0.0208483674 -0.7042578459 658 26.2800000000 0.3440651000 0.1998934837 0.3636759520 0.0215291845 0.1507390000 238691084 0 1782919168 -0.0987194777 0.0204469189 -0.7031353116 659 26.3200000000 0.3451977074 0.2001139757 0.3636759520 0.0215160184 0.1475120000 238693174 0 1781395456 -0.0946908891 0.0257980376 -0.7035979033 660 26.3600000000 0.3474285007 0.2003371795 0.3636759520 0.0215002046 0.1482740000 238693912 0 1783181312 -0.0932852328 0.0232901536 -0.7052862644 661 26.4000000000 0.3447507918 0.2005556570 0.3636759520 0.0214844973 0.1530200000 238697902 0 1784664064 -0.0876162648 0.0220739171 -0.7010067105 662 26.4400000000 0.3476397693 0.2007778385 0.3636759520 0.0214695025 0.1506600000 238698228 0 1786462208 -0.0886705518 0.0199770145 -0.7038179636 663 26.4800000000 0.3469642997 0.2009983309 0.3636759520 0.0214533163 0.1479280000 238699366 0 1784823808 -0.0862276256 0.0200453065 -0.7025579214 664 26.5200000000 0.3471319675 0.2012184116 0.3636759520 0.0214385566 0.1467800000 238702644 0 1786589184 -0.0843094587 0.0223272219 -0.7016316056 665 26.5600000000 0.3498740792 0.2014419540 0.3636759520 0.0214245271 0.1478020000 238701206 0 1783934976 -0.0816076994 0.0147464536 -0.7045267820 666 26.6000000000 0.3493032753 0.2016639680 0.3636759520 0.0214128087 0.1432310000 238702056 0 1782267904 -0.0787988007 0.0157606304 -0.7033255100 667 26.6400000000 0.3509847820 0.2018878373 0.3636759520 0.0214016845 0.1431580000 238703242 0 1783652352 -0.0784758329 0.0186499618 -0.7048416138 668 26.6800000000 0.3527792394 0.2021137226 0.3636759520 0.0213884132 0.1476980000 238706444 0 1785425920 -0.0739624202 0.0184958763 -0.7059177160 669 26.7200000000 0.3520246446 0.2023378047 0.3636759520 0.0213757125 0.1544700000 238706770 0 1784717312 -0.0716985762 0.0218266621 -0.7048137188 670 26.7600000000 0.3501201272 0.2025583753 0.3636759520 0.0213623911 0.1431590000 238704904 0 1786335232 -0.0676061511 0.0195724964 -0.7030369043 671 26.8000000000 0.3521622717 0.2027813320 0.3636759520 0.0213487792 0.1435790000 238710850 0 1783783424 -0.0684960783 0.0174680408 -0.7060036659 672 26.8400000000 0.3519781828 0.2030033511 0.3636759520 0.0213363595 0.1378740000 238709728 0 1782640640 -0.0624999106 0.0204183832 -0.7053083181 673 26.8800000000 0.3535401225 0.2032270313 0.3636759520 0.0213244201 0.1412540000 238710118 0 1780260864 -0.0616379976 0.0184003767 -0.7073176503 674 26.9200000000 0.3524937332 0.2034484952 0.3636759520 0.0213185008 0.1424580000 238715376 0 1779843072 -0.0556761026 0.0207305122 -0.7061202526 675 26.9600000000 0.3550236225 0.2036730510 0.3636759520 0.0213059293 0.1860710000 239255990 0 1778483200 -0.0573287904 0.0145281386 -0.7106825113 676 27.0000000000 0.3556864560 0.2038979229 0.3636759520 0.0212908223 0.4138440000 239677503 0 1777192960 -0.0547630787 0.0149256960 -0.7112055421 677 27.0400000000 0.3560638726 0.2041226879 0.3636759520 0.0212765765 0.2786540000 240513697 0 1781432320 -0.0526603758 0.0128405429 -0.7129219770 678 27.0800000000 0.3582063317 0.2043499499 0.3636759520 0.0212627902 0.2224980000 240441342 0 1781469184 -0.0500770509 0.0138180917 -0.7156368494 679 27.1200000000 0.3598722816 0.2045789961 0.3636759520 0.0212492280 0.1807210000 239233698 0 1782460416 -0.0490857065 0.0137213441 -0.7185491323 680 27.1600000000 0.3591897190 0.2048063648 0.3636759520 0.0212371722 0.1858140000 239235492 0 1783844864 -0.0467051566 0.0172376782 -0.7189183235 681 27.2000000000 0.3591891825 0.2050330650 0.3636759520 0.0212217304 0.1910940000 239237414 0 1785622528 -0.0435383022 0.0152304349 -0.7202109694 682 27.2400000000 0.3583020270 0.2052577995 0.3636759520 0.0212064592 0.1835840000 239241300 0 1784762368 -0.0416904986 0.0127846617 -0.7211309075 683 27.2800000000 0.3609155118 0.2054857025 0.3636759520 0.0211921954 0.1842560000 239241602 0 1784496128 -0.0398623347 0.0137089621 -0.7249818444 684 27.3200000000 0.3609458506 0.2057129834 0.3636759520 0.0211775160 0.2121970000 239244608 0 1783615488 -0.0374086797 0.0165062770 -0.7265339494 685 27.3600000000 0.3600820899 0.2059383397 0.3636759520 0.0211624571 0.1777840000 239245018 0 1785798656 -0.0331726968 0.0130523117 -0.7266837955 686 27.4000000000 0.3632188141 0.2061676116 0.3636759520 0.0211513738 0.1882320000 239242060 0 1783742464 -0.0326937735 0.0121439900 -0.7316875458 687 27.4400000000 0.3619398177 0.2063943542 0.3636759520 0.0211401459 0.1774800000 239245698 0 1782964224 -0.0301235318 0.0132669788 -0.7322989702 688 27.4800000000 0.3623995483 0.2066211060 0.3636759520 0.0211290074 0.1775660000 239251708 0 1784872960 -0.0257228017 0.0131760165 -0.7345837355 689 27.5200000000 0.3637239933 0.2068491218 0.3637239933 0.0211175455 0.1765220000 239252958 0 1786687488 -0.0247214139 0.0124188131 -0.7382211685 690 27.5600000000 0.3636051416 0.2070763044 0.3637239933 0.0211067695 0.1765750000 239249268 0 1783341056 -0.0220555067 0.0116919298 -0.7405365705 691 27.6000000000 0.3634157479 0.2073025554 0.3637239933 0.0210929643 0.1748560000 239254006 0 1782452224 -0.0172261298 0.0162132941 -0.7422924042 692 27.6400000000 0.3639342189 0.2075289017 0.3639342189 0.0210789352 0.1706050000 239255144 0 1784492032 -0.0133267045 0.0156071568 -0.7452851534 693 27.6800000000 0.3630593121 0.2077533324 0.3639342189 0.0210681124 0.1726880000 239254834 0 1786179584 -0.0127200484 0.0106673799 -0.7468194962 694 27.7200000000 0.3628782630 0.2079768553 0.3639342189 0.0210535419 0.1768410000 239257260 0 1784504320 -0.0091036260 0.0131897563 -0.7486060858 695 27.7600000000 0.3649639189 0.2082027360 0.3649639189 0.0210390579 0.1748470000 239262386 0 1783234560 -0.0079736114 0.0101136435 -0.7529473901 696 27.8000000000 0.3658908308 0.2084292993 0.3658908308 0.0210251324 0.1701500000 239260820 0 1785163776 -0.0058148205 0.0088860784 -0.7555957437 697 27.8400000000 0.3672699034 0.2086571912 0.3672699034 0.0210135658 0.1718300000 239261386 0 1784496128 -0.0017075241 0.0120842308 -0.7617278099 698 27.8800000000 0.3672029674 0.2088843341 0.3672699034 0.0209991118 0.1669040000 239260424 0 1783853056 0.0022368729 0.0130248535 -0.7630434632 699 27.9200000000 0.3659147918 0.2091089843 0.3672699034 0.0209951676 0.1674970000 239266198 0 1783001088 0.0073252618 0.0122231888 -0.7657854557 700 27.9600000000 0.3728306592 0.2093428724 0.3728306592 0.0209840576 0.1734240000 239264016 0 1782476800 0.0064570606 0.0139324982 -0.7747747898 701 28.0000000000 0.3675898015 0.2095686169 0.3728306592 0.0209705661 0.1629020000 239265110 0 1784004608 0.0116774738 0.0071236929 -0.7710345984 702 28.0400000000 0.3676812649 0.2097938486 0.3728306592 0.0209635460 0.1615070000 239265244 0 1786056704 0.0128965080 0.0094731059 -0.7724459767 703 28.0800000000 0.3673596978 0.2100179821 0.3728306592 0.0209607322 0.1696810000 239263746 0 1784504320 0.0152658224 0.0093321502 -0.7741217017 704 28.1200000000 0.3704256415 0.2102458339 0.3728306592 0.0209580649 0.1581910000 239267856 0 1782726656 0.0154851675 0.0150809186 -0.7783231735 705 28.1600000000 0.3676432669 0.2104690927 0.3728306592 0.0209451512 0.1580340000 239267806 0 1782345728 0.0191769898 0.0087458473 -0.7772362232 706 28.2000000000 0.3716634512 0.2106974133 0.3728306592 0.0209420104 0.1593880000 239268828 0 1784238080 0.0187448561 0.0118017700 -0.7825118303 707 28.2400000000 0.3703845143 0.2109232791 0.3728306592 0.0209308484 0.1539740000 239267382 0 1785528320 0.0212983787 0.0103169605 -0.7830218077 708 28.2800000000 0.3676964045 0.2111447100 0.3728306592 0.0209167237 0.1536170000 239269732 0 1784655872 0.0262300074 0.0078087822 -0.7819408774 709 28.3200000000 0.3704849184 0.2113694494 0.3728306592 0.0209022215 0.1575930000 239266606 0 1783508992 0.0264423192 0.0077817161 -0.7855715752 710 28.3600000000 0.3696613908 0.2115923958 0.3728306592 0.0208898364 0.1491730000 239269984 0 1782599680 0.0294148326 0.0070586782 -0.7853842974 711 28.4000000000 0.3738143146 0.2118205560 0.3738143146 0.0208804582 0.1516980000 239277298 0 1781747712 0.0298043489 0.0111980308 -0.7907015085 712 28.4400000000 0.3710553944 0.2120442004 0.3738143146 0.0208665585 0.1908180000 239275264 0 1781616640 0.0331556797 0.0107677206 -0.7881509066 713 28.4800000000 0.3732212186 0.2122702552 0.3738143146 0.0208530337 0.1508570000 239279254 0 1783758848 0.0345415473 0.0082918890 -0.7908532619 714 28.5200000000 0.3742589653 0.2124971301 0.3742589653 0.0208422334 0.1497960000 239277204 0 1785409536 0.0366123021 0.0103965551 -0.7925652266 715 28.5600000000 0.3728431165 0.2127213902 0.3742589653 0.0208282655 0.1488330000 239274586 0 1786535936 0.0401343405 0.0083475430 -0.7919481993 716 28.6000000000 0.3770808578 0.2129509426 0.3770808578 0.0208137948 0.1425500000 239272948 0 1783332864 0.0410280824 0.0100016911 -0.7964221239 717 28.6400000000 0.3714343011 0.2131719793 0.3770808578 0.0208036199 0.1479730000 239275934 0 1782190080 0.0471074879 0.0094771944 -0.7907029390 718 28.6800000000 0.3733963370 0.2133951330 0.3770808578 0.0207911606 0.1466310000 239281928 0 1784520704 0.0477991402 0.0043738596 -0.7930926681 719 28.7200000000 0.3745565712 0.2136192797 0.3770808578 0.0207801475 0.1448690000 239283326 0 1786679296 0.0533054471 0.0087692291 -0.7933459282 720 28.7600000000 0.3799807131 0.2138503372 0.3799807131 0.0207685729 0.1450260000 239280852 0 1782460416 0.0517123342 0.0082716905 -0.7983646393 721 28.8000000000 0.3759549558 0.2140751703 0.3799807131 0.0207602759 0.1443820000 239286010 0 1782083584 0.0579336882 0.0085394308 -0.7942149639 722 28.8400000000 0.3778445423 0.2143019976 0.3799807131 0.0207484437 0.1376550000 239279880 0 1784254464 0.0626956224 0.0128056556 -0.7950296402 723 28.8800000000 0.3764046431 0.2145262060 0.3799807131 0.0207347199 0.1411530000 239284078 0 1785647104 0.0650235415 0.0093563758 -0.7932342887 724 28.9200000000 0.3815686703 0.2147569276 0.3815686703 0.0207222856 0.1453480000 239281760 0 1784598528 0.0680923760 0.0123663247 -0.7972806692 725 28.9600000000 0.3810405731 0.2149862844 0.3815686703 0.0207084815 0.1441360000 239286710 0 1784266752 0.0705188513 0.0134858377 -0.7955445051 726 29.0000000000 0.3834381700 0.2152183118 0.3834381700 0.0206966545 0.1408100000 239290112 0 1783234560 0.0754212439 0.0128294267 -0.7971152067 727 29.0400000000 0.3791368008 0.2154437843 0.3834381700 0.0206862261 0.1325590000 239285178 0 1784508416 0.0804458559 0.0120669790 -0.7916749716 728 29.0800000000 0.3807383180 0.2156708372 0.3834381700 0.0206724066 0.1313640000 239285804 0 1786376192 0.0825899243 0.0128218941 -0.7922741175 729 29.1200000000 0.3818258643 0.2158987590 0.3834381700 0.0206588507 0.1340610000 239290718 0 1783214080 0.0868747830 0.0102652945 -0.7919780612 730 29.1600000000 0.3859188259 0.2161316632 0.3859188259 0.0206531214 0.1350840000 239289372 0 1782472704 0.0880924761 0.0125929974 -0.7948081493 731 29.2000000000 0.3843063414 0.2163617244 0.3859188259 0.0206470751 0.1261580000 239285586 0 1781329920 0.0935775936 0.0136811808 -0.7914838195 732 29.2400000000 0.3845916688 0.2165915467 0.3859188259 0.0206345005 0.1295570000 239289992 0 1782841344 0.0952920020 0.0117082372 -0.7907596827 733 29.2800000000 0.3823158145 0.2168176371 0.3859188259 0.0206302424 0.1306280000 239291398 0 1784344576 0.1016745865 0.0172411986 -0.7870349884 734 29.3200000000 0.3852701187 0.2170471364 0.3859188259 0.0206191917 0.1330240000 239291572 0 1785995264 0.1033394039 0.0087835975 -0.7895035744 735 29.3600000000 0.3844331503 0.2172748725 0.3859188259 0.0206081247 0.1282020000 239291858 0 1784905728 0.1082742512 0.0112218410 -0.7872817516 736 29.4000000000 0.3878932297 0.2175066909 0.3878932297 0.0205948400 0.1271340000 239294248 0 1786523648 0.1103125513 0.0112169087 -0.7894365788 737 29.4400000000 0.3866299689 0.2177361662 0.3878932297 0.0205831695 0.1235360000 239292786 0 1785032704 0.1147679687 0.0091297477 -0.7871734500 738 29.4800000000 0.3837626278 0.2179611343 0.3878932297 0.0205715511 0.1187280000 239292652 0 1786667008 0.1180829704 0.0097085014 -0.7832265496 739 29.5200000000 0.3881559670 0.2181914385 0.3881559670 0.0205591538 0.1210400000 239294002 0 1785139200 0.1198769212 0.0112058744 -0.7863264084 740 29.5600000000 0.3902266920 0.2184239186 0.3902266920 0.0205467625 0.1187910000 239299656 0 1786904576 0.1194877923 0.0070961230 -0.7875253558 741 29.6000000000 0.3872890770 0.2186518068 0.3902266920 0.0205448479 0.1198730000 239297778 0 1783889920 0.1263978183 0.0074776150 -0.7832893133 742 29.6400000000 0.3881950378 0.2188803017 0.3902266920 0.0205399161 0.1170040000 239297616 0 1782599680 0.1289559007 0.0101313516 -0.7830326557 743 29.6800000000 0.3886548281 0.2191088004 0.3902266920 0.0205271870 0.1185310000 239298582 0 1781329920 0.1282877028 0.0062349364 -0.7831369638 744 29.7200000000 0.3881547153 0.2193360126 0.3902266920 0.0205182754 0.1387280000 239544880 0 1780293632 0.1319176257 0.0108287036 -0.7812825441 745 29.7600000000 0.3889116943 0.2195636310 0.3902266920 0.0205055241 0.2681610000 239893261 0 1782493184 0.1330887377 0.0077771172 -0.7817264199 746 29.8000000000 0.3884205520 0.2197899808 0.3902266920 0.0204929427 0.2102510000 240764198 0 1783902208 0.1364082098 0.0131241381 -0.7804962993 747 29.8400000000 0.3889116049 0.2200163819 0.3902266920 0.0204827209 0.1417900000 240984765 0 1783148544 0.1358174384 0.0118249133 -0.7801846266 748 29.8800000000 0.3817128539 0.2202325536 0.3902266920 0.0204835536 0.2092290000 240895822 0 1779994624 0.1524971128 0.0025436804 -0.7708718777 749 29.9200000000 0.3837153912 0.2204508218 0.3902266920 0.0204706781 0.1292160000 239543994 0 1779937280 0.1545665860 0.0054212883 -0.7720170021 750 29.9600000000 0.3847678602 0.2206699111 0.3902266920 0.0204574466 0.1215900000 239545800 0 1782099968 0.1537991464 0.0043794960 -0.7726861238 751 30.0000000000 0.3830597699 0.2208861426 0.3902266920 0.0204450465 0.1218470000 239547598 0 1783734272 0.1590828598 0.0039044991 -0.7702286243 752 30.0400000000 0.3857764304 0.2211054116 0.3902266920 0.0204317025 0.1257400000 239545072 0 1785638912 0.1605832279 0.0068731755 -0.7723551989 753 30.0800000000 0.3845349252 0.2213224495 0.3902266920 0.0204208787 0.1223270000 239551678 0 1784274944 0.1622401327 0.0058508739 -0.7704994678 754 30.1200000000 0.3828429580 0.2215366677 0.3902266920 0.0204089254 0.1210150000 239548968 0 1783259136 0.1661999822 0.0030111596 -0.7683131099 755 30.1600000000 0.3852397203 0.2217534929 0.3902266920 0.0203956192 0.1205920000 239552314 0 1782624256 0.1671029478 0.0050384402 -0.7701797485 756 30.2000000000 0.3896856606 0.2219756254 0.3902266920 0.0203852396 0.1173730000 239552012 0 1781862400 0.1600674540 0.0003354177 -0.7746629715 757 30.2400000000 0.3846820891 0.2221905613 0.3902266920 0.0203962922 0.1126770000 239550890 0 1778556928 0.1716225594 0.0065712109 -0.7676447630 758 30.2800000000 0.3844326437 0.2224046010 0.3902266920 0.0203919156 0.1158500000 239551828 0 1777287168 0.1733572036 0.0011248589 -0.7674934864 759 30.3200000000 0.3846904933 0.2226184164 0.3902266920 0.0203948291 0.1262990000 239712884 0 1775763456 0.1772159040 0.0040594861 -0.7670639753 760 30.3600000000 0.3898093700 0.2228384045 0.3902266920 0.0203931141 0.2087140000 239952439 0 1773445120 0.1753303111 0.0078546405 -0.7716804147 761 30.4000000000 0.3872814178 0.2230544926 0.3902266920 0.0203853613 0.1397850000 240847251 0 1777623040 0.1785446554 0.0040675178 -0.7689852118 762 30.4400000000 0.3842571080 0.2232660445 0.3902266920 0.0203817092 0.1073980000 240803863 0 1779191808 0.1842302531 0.0005508438 -0.7651333809 763 30.4800000000 0.3916356862 0.2234867125 0.3916356862 0.0203887453 0.1546350000 240709948 0 1779339264 0.1787326038 0.0059199855 -0.7726899385 764 30.5200000000 0.3919185698 0.2237071730 0.3919185698 0.0203818429 0.1643730000 239854412 0 1781116928 0.1815284044 0.0019101128 -0.7727043629 765 30.5600000000 0.3918366432 0.2239269501 0.3919185698 0.0203861365 0.1229350000 241134721 0 1785204736 0.1841463000 0.0040659979 -0.7721892595 766 30.6000000000 0.3922527432 0.2241466966 0.3922527432 0.0203874809 0.1620770000 241040230 0 1786220544 0.1884376109 0.0054077208 -0.7723876834 767 30.6400000000 0.3916225135 0.2243650484 0.3922527432 0.0203785994 0.1587800000 240060034 0 1786245120 0.1904140860 0.0061822459 -0.7717748880 768 30.6800000000 0.3930253983 0.2245846582 0.3930253983 0.0203666966 0.1606150000 240576482 0 1784332288 0.1896727681 0.0013881400 -0.7735360861 769 30.7200000000 0.3934376836 0.2248042330 0.3934376836 0.0203662188 0.1669810000 240207042 0 1780744192 0.1924903393 0.0077711493 -0.7738456130 770 30.7600000000 0.3949505389 0.2250252022 0.3949505389 0.0203534923 0.1767020000 240605940 0 1778212864 0.1907285601 0.0051742643 -0.7761166096 771 30.8000000000 0.3933806717 0.2252435621 0.3949505389 0.0203442036 0.1628250000 240557733 0 1779326976 0.1980632991 0.0050901622 -0.7741958499 772 30.8400000000 0.3948102593 0.2254632081 0.3949505389 0.0203372571 0.1236940000 241592133 0 1784340480 0.1956961155 0.0065543801 -0.7760571241 773 30.8800000000 0.3924885690 0.2256792823 0.3949505389 0.0203276029 0.1149930000 241569128 0 1785667584 0.2032881379 0.0051546842 -0.7736294270 774 30.9200000000 0.3930026591 0.2258954624 0.3949505389 0.0203182976 0.1607310000 241433046 0 1783783424 0.2047151923 0.0111029148 -0.7739682198 775 30.9600000000 0.3945289254 0.2261130539 0.3949505389 0.0203062396 0.0919280000 240222262 0 1783427072 0.2036799490 0.0130366385 -0.7759510875 776 31.0000000000 0.3936744332 0.2263289836 0.3949505389 0.0202996727 0.0892700000 240226604 0 1785159680 0.2074363828 0.0072949380 -0.7755336761 777 31.0400000000 0.3934298754 0.2265440426 0.3949505389 0.0202878963 0.0962800000 240227642 0 1786789888 0.2075914443 0.0070814118 -0.7754741311 778 31.0800000000 0.3941619694 0.2267594898 0.3949505389 0.0202748791 0.0959070000 240227652 0 1785696256 0.2102479637 0.0092413202 -0.7768117189 779 31.1200000000 0.3945350945 0.2269748629 0.3949505389 0.0202659161 0.0923920000 240227578 0 1783373824 0.2128681242 0.0143894330 -0.7774980068 780 31.1600000000 0.3954437077 0.2271908486 0.3954437077 0.0202860053 0.1118590000 240227352 0 1783156736 0.2087369561 0.0101410598 -0.7793586850 781 31.2000000000 0.3949804008 0.2274056879 0.3954437077 0.0202901538 0.1325820000 240358394 0 1781743616 0.2129250914 0.0121225119 -0.7789163589 782 31.2400000000 0.3936377466 0.2276182609 0.3954437077 0.0203098122 0.1916610000 240396016 0 1779822592 0.2117817998 0.0061930791 -0.7783994675 783 31.2800000000 0.3935661614 0.2278301995 0.3954437077 0.0203097988 0.1374310000 241743341 0 1785376768 0.2128031254 0.0098573864 -0.7784448862 784 31.3200000000 0.3928809166 0.2280407234 0.3954437077 0.0203098413 0.1223280000 241812995 0 1784537088 0.2166936249 0.0080633536 -0.7777760029 785 31.3600000000 0.3942105472 0.2282524047 0.3954437077 0.0202979836 0.1748710000 241720428 0 1779617792 0.2166839689 0.0103168786 -0.7791278362 786 31.4000000000 0.3945176601 0.2284639381 0.3954437077 0.0202860949 0.1576280000 240533368 0 1779023872 0.2185687870 0.0082870126 -0.7799522281 787 31.4400000000 0.3946478665 0.2286750993 0.3954437077 0.0202766696 0.1591590000 241722397 0 1777664000 0.2166671306 0.0092589408 -0.7805410624 788 31.4800000000 0.3959018290 0.2288873160 0.3959018290 0.0202676567 0.1385790000 241854142 0 1776230400 0.2178685814 0.0108853132 -0.7818403244 789 31.5200000000 0.3962762654 0.2290994693 0.3962762654 0.0202612652 0.1758870000 241774108 0 1771937792 0.2155399770 0.0107305646 -0.7828161716 790 31.5600000000 0.3951931894 0.2293097145 0.3962762654 0.0202712633 0.1115770000 240507828 0 1769668608 0.2174365669 0.0101693198 -0.7818332314 791 31.6000000000 0.3927105665 0.2295162895 0.3962762654 0.0202840020 0.1150970000 240661714 0 1771569152 0.2207702398 0.0095794126 -0.7792412043 792 31.6400000000 0.3948538899 0.2297250491 0.3962762654 0.0202759944 0.2097580000 240709864 0 1771814912 0.2229785770 0.0134319291 -0.7809791565 793 31.6800000000 0.3942712247 0.2299325475 0.3962762654 0.0202794002 0.1709670000 242108641 0 1776652288 0.2216551155 0.0096483789 -0.7808713317 794 31.7200000000 0.3944065273 0.2301396935 0.3962762654 0.0202811288 0.1425280000 242127686 0 1778417664 0.2224482000 0.0110202357 -0.7809535265 795 31.7600000000 0.3947420716 0.2303467406 0.3962762654 0.0202824245 0.1935740000 242038120 0 1779466240 0.2233907878 0.0148724578 -0.7807171345 796 31.8000000000 0.3971298635 0.2305562671 0.3971298635 0.0202869095 0.1228420000 240677912 0 1779892224 0.2209688127 0.0179079771 -0.7829760313 797 31.8400000000 0.3947035670 0.2307622236 0.3971298635 0.0203283447 0.1044540000 240681338 0 1781477376 0.2244169414 0.0169802532 -0.7801523209 798 31.8800000000 0.3970478177 0.2309706015 0.3971298635 0.0203730091 0.1075320000 240685392 0 1783037952 0.2230249047 0.0158822518 -0.7826077938 799 31.9200000000 0.3990002871 0.2311809015 0.3990002871 0.0203850160 0.1078450000 240690026 0 1784901632 0.2223769128 0.0190617684 -0.7841423154 800 31.9600000000 0.3971199691 0.2313883253 0.3990002871 0.0203945258 0.1153760000 240696864 0 1786314752 0.2240404189 0.0148937423 -0.7821882963 801 32.0000000000 0.3959958553 0.2315938278 0.3990002871 0.0203849374 0.1120920000 240695474 0 1783812096 0.2255335897 0.0203129817 -0.7801885605 802 32.0400000000 0.3963797987 0.2317992966 0.3990002871 0.0203812678 0.1477120000 240975160 0 1782775808 0.2244688123 0.0171988346 -0.7804613113 803 32.0800000000 0.3986304402 0.2320070565 0.3990002871 0.0203699195 0.2986720000 240986494 0 1780523008 0.2254794985 0.0202990025 -0.7821438909 804 32.1199999990 0.3981189132 0.2322136633 0.3990002871 0.0203612947 0.2519620000 241821263 0 1784250368 0.2256280482 0.0204022173 -0.7810042500 805 32.1600000000 0.3973643482 0.2324188194 0.3990002871 0.0203544251 0.2279360000 243074256 0 1785184256 0.2281352729 0.0187486969 -0.7797899842 806 32.2000000000 0.3987061083 0.2326251312 0.3990002871 0.0203450971 0.1527380000 242822951 0 1786724352 0.2256245464 0.0214265119 -0.7805106640 807 32.2400000000 0.3973296881 0.2328292260 0.3990002871 0.0203343108 0.2508360000 242739128 0 1782022144 0.2291009873 0.0199162420 -0.7785068750 808 32.2800000000 0.3980366290 0.2330336906 0.3990002871 0.0203220019 0.1576850000 241002464 0 1781510144 0.2304172218 0.0210158080 -0.7785482407 809 32.3200000000 0.3984805048 0.2332381984 0.3990002871 0.0203112518 0.1396000000 241004930 0 1783422976 0.2300272286 0.0211718269 -0.7784497738 810 32.3600000000 0.3992243707 0.2334431196 0.3992243707 0.0203030529 0.1749270000 241008196 0 1785413632 0.2307324708 0.0167994834 -0.7786372304 811 32.4000000000 0.3992263079 0.2336475379 0.3992263079 0.0202909305 0.1330200000 241007058 0 1784029184 0.2316377014 0.0189142525 -0.7777223587 812 32.4399999990 0.3989386857 0.2338510984 0.3992263079 0.0202790550 0.1387440000 241011556 0 1783144448 0.2317140698 0.0211454313 -0.7764465213 813 32.4800000000 0.4000033736 0.2340554677 0.4000033736 0.0202673725 0.1361250000 241012074 0 1782288384 0.2329831868 0.0198906604 -0.7767914534 814 32.5200000000 0.3988604546 0.2342579309 0.4000033736 0.0202567128 0.1330880000 241012732 0 1781129216 0.2348646671 0.0202611797 -0.7745307088 815 32.5600000000 0.3997237980 0.2344609565 0.4000033736 0.0202502328 0.1388560000 241017522 0 1779478528 0.2356265038 0.0227373317 -0.7742450237 816 32.6000000000 0.3998706639 0.2346636644 0.4000033736 0.0202408689 0.1387610000 241017036 0 1775923200 0.2359549999 0.0209545884 -0.7737670541 817 32.6400000000 0.4008973837 0.2348671329 0.4008973837 0.0202330285 0.1375910000 241016850 0 1774510080 0.2364977002 0.0205843765 -0.7738424540 818 32.6800000000 0.4017082453 0.2350710951 0.4017082453 0.0202265567 0.1346930000 241019292 0 1773113344 0.2363166511 0.0201754048 -0.7738157511 819 32.7200000000 0.4031783044 0.2352763542 0.4031783044 0.0202190749 0.1326670000 241021758 0 1771352064 0.2355686575 0.0210741702 -0.7742224336 820 32.7599999990 0.4010564387 0.2354785251 0.4031783044 0.0202097164 0.1365560000 241027560 0 1770336256 0.2369963527 0.0203366857 -0.7711338401 821 32.7999999990 0.4020147920 0.2356813707 0.4031783044 0.0202026984 0.1336780000 241028338 0 1771606016 0.2382428199 0.0204250552 -0.7713152170 822 32.8400000000 0.4037980139 0.2358858922 0.4037980139 0.0201962621 0.1339510000 241025312 0 1773789184 0.2373254597 0.0191513356 -0.7722594738 823 32.8800000000 0.4068948627 0.2360936795 0.4068948627 0.0201994844 0.1300450000 241026174 0 1775403008 0.2370307595 0.0223970022 -0.7739553452 824 32.9200000000 0.4021363258 0.2362951876 0.4068948627 0.0201910203 0.1239470000 241026884 0 1777307648 0.2408116013 0.0192304850 -0.7681636214 825 32.9600000000 0.4036217034 0.2364980076 0.4068948627 0.0201906625 0.1264480000 241027938 0 1779318784 0.2398529500 0.0202496909 -0.7686935663 826 33.0000000000 0.3994908035 0.2366953354 0.4068948627 0.0201813994 0.1238360000 241034696 0 1780588544 0.2411247492 0.0156556871 -0.7640776038 827 33.0400000000 0.4019645751 0.2368951773 0.4068948627 0.0201783351 0.1245920000 241031678 0 1782132736 0.2379001081 0.0162265673 -0.7658915520 828 33.0800000000 0.4019346535 0.2370945004 0.4068948627 0.0201756357 0.1252100000 241036360 0 1783910400 0.2395564914 0.0175969861 -0.7649948001 829 33.1199999990 0.3994945884 0.2372903991 0.4068948627 0.0201672429 0.1258110000 241039338 0 1785540608 0.2394938767 0.0128992014 -0.7622557878 830 33.1600000000 0.4004161358 0.2374869362 0.4068948627 0.0201608865 0.1281170000 241042660 0 1784176640 0.2380765826 0.0162250698 -0.7618879080 831 33.2000000000 0.4019137025 0.2376848023 0.4068948627 0.0201546479 0.1237650000 241045698 0 1783160832 0.2386798561 0.0166681446 -0.7620773315 832 33.2400000000 0.3999876976 0.2378798779 0.4068948627 0.0201429876 0.1266610000 241043960 0 1781637120 0.2390776277 0.0131675638 -0.7591202259 833 33.2800000000 0.4017221928 0.2380765674 0.4068948627 0.0201322676 0.1228820000 241044770 0 1780604928 0.2384963930 0.0148061849 -0.7599821687 834 33.3200000000 0.4018015563 0.2382728803 0.4068948627 0.0201218112 0.1228560000 241045592 0 1782280192 0.2366115451 0.0162168294 -0.7592053413 835 33.3600000000 0.3990013897 0.2384653695 0.4068948627 0.0201101250 0.1247280000 241051930 0 1783824384 0.2364112139 0.0153388977 -0.7553141117 836 33.4000000000 0.3996157348 0.2386581331 0.4068948627 0.0200997079 0.1207360000 241053036 0 1785540608 0.2381362617 0.0196899585 -0.7545045018 837 33.4399999990 0.3991343975 0.2388498610 0.4068948627 0.0200910164 0.1220660000 241052426 0 1786937344 0.2344636619 0.0139223859 -0.7537307739 838 33.4800000000 0.4023780525 0.2390450021 0.4068948627 0.0200820036 0.1578530000 241507264 0 1783287808 0.2296475768 0.0129589401 -0.7566347718 839 33.5200000000 0.3968836069 0.2392331291 0.4068948627 0.0200707670 0.3697440000 241491634 0 1780928512 0.2332979739 0.0105314367 -0.7504844069 840 33.5600000000 0.3984229565 0.2394226408 0.4068948627 0.0200608536 0.3431190000 242689663 0 1786175488 0.2326048315 0.0131966807 -0.7509900331 841 33.6000000000 0.3974188566 0.2396105079 0.4068948627 0.0200508445 0.2609430000 243485516 0 1782820864 0.2332925498 0.0132321268 -0.7485200167 842 33.6400000000 0.3987531364 0.2397995134 0.4068948627 0.0200478319 0.2714500000 243374418 0 1780461568 0.2321026027 0.0151676834 -0.7489953041 843 33.6800000000 0.3988797963 0.2399882207 0.4068948627 0.0200395196 0.1570020000 241481722 0 1781555200 0.2288348079 0.0109214112 -0.7488306761 844 33.7200000000 0.3982133865 0.2401756913 0.4068948627 0.0200292982 0.1591710000 241490132 0 1783308288 0.2266479731 0.0089674145 -0.7472890019 845 33.7599999990 0.3953030407 0.2403592740 0.4068948627 0.0200195601 0.1580030000 241490234 0 1784815616 0.2269633412 0.0076494738 -0.7441300154 846 33.7999999990 0.3957417607 0.2405429412 0.4068948627 0.0200141421 0.1621840000 241494900 0 1786847232 0.2276466191 0.0128772333 -0.7435076237 847 33.8400000000 0.3972334862 0.2407279360 0.4068948627 0.0200048548 0.1608090000 241501126 0 1783156736 0.2244698107 0.0098440647 -0.7443637848 848 33.8800000000 0.3975613713 0.2409128811 0.4068948627 0.0199939038 0.1527770000 241493260 0 1782398976 0.2240996957 0.0116793215 -0.7439907789 849 33.9200000000 0.3965442479 0.2410961924 0.4068948627 0.0199829607 0.1506730000 241497706 0 1783672832 0.2243210673 0.0151940137 -0.7421594858 850 33.9600000000 0.3979867995 0.2412807696 0.4068948627 0.0199769228 0.1513280000 241498776 0 1785450496 0.2214689553 0.0116727203 -0.7427662611 851 34.0000000000 0.3992335498 0.2414663781 0.4068948627 0.0199711454 0.1592640000 241502006 0 1784066048 0.2198143303 0.0086663738 -0.7440501451 852 34.0400000000 0.3956169188 0.2416473059 0.4068948627 0.0199626120 0.1578750000 241507392 0 1782542336 0.2226324677 0.0175390393 -0.7398086190 853 34.0800000000 0.3969581425 0.2418293819 0.4068948627 0.0199598036 0.1596160000 241512918 0 1782018048 0.2182136178 0.0129353702 -0.7413002253 854 34.1199999990 0.3954750597 0.2420092949 0.4068948627 0.0199493555 0.1526590000 241512224 0 1783566336 0.2182950974 0.0149487779 -0.7386140823 855 34.1600000000 0.3986959457 0.2421925542 0.4068948627 0.0199410014 0.1524070000 241509690 0 1784946688 0.2150360346 0.0139221847 -0.7407180071 856 34.2000000000 0.3979177177 0.2423744761 0.4068948627 0.0199326417 0.1596150000 241514428 0 1786699776 0.2153980136 0.0152885541 -0.7379864454 857 34.2400000000 0.3925023079 0.2425496544 0.4068948627 0.0199219942 0.1487550000 241510666 0 1782775808 0.2190863490 0.0088154525 -0.7315235138 858 34.2800000000 0.3954472542 0.2427278567 0.4068948627 0.0199138870 0.1496630000 241515440 0 1781907456 0.2165645659 0.0122008026 -0.7330316305 859 34.3200000000 0.3953715861 0.2429055561 0.4068948627 0.0199040926 0.1458130000 241515430 0 1783693312 0.2152670622 0.0095566288 -0.7314463854 860 34.3600000000 0.3966055810 0.2430842770 0.4068948627 0.0198944422 0.1468730000 241518708 0 1784922112 0.2122383416 0.0081034228 -0.7316310406 861 34.4000000000 0.3939188421 0.2432594624 0.4068948627 0.0198836542 0.1538100000 241522770 0 1786826752 0.2112850249 0.0079978034 -0.7274112701 862 34.4400000000 0.3953548968 0.2434359072 0.4068948627 0.0198728739 0.1549830000 241529292 0 1782542336 0.2099273503 0.0109992325 -0.7268760204 863 34.4800000000 0.3941831589 0.2436105853 0.4068948627 0.0198645131 0.1506030000 241527186 0 1781653504 0.2074927688 0.0048151612 -0.7246163487 864 34.5200000000 0.3948858082 0.2437856724 0.4068948627 0.0198532306 0.1502670000 241530540 0 1783820288 0.2095413953 0.0079424307 -0.7227984071 865 34.5600000000 0.3962619007 0.2439619455 0.4068948627 0.0198464582 0.1436890000 241526050 0 1785196544 0.2027955055 0.0082672462 -0.7224505544 866 34.6000000000 0.3957029283 0.2441371660 0.4068948627 0.0198351783 0.1422840000 241528624 0 1786847232 0.2019995302 0.0094647706 -0.7193456888 867 34.6400000000 0.3930375874 0.2443089082 0.4068948627 0.0198238291 0.1448470000 241527494 0 1783050240 0.2009155899 0.0102171227 -0.7148115635 868 34.6800000000 0.3951895535 0.2444827338 0.4068948627 0.0198162373 0.1383010000 241528364 0 1782034432 0.1992942095 0.0060925335 -0.7151269317 869 34.7200000000 0.3924382627 0.2446529933 0.4068948627 0.0198086922 0.1409040000 241529426 0 1778225152 0.1955189556 0.0067278370 -0.7104182243 870 34.7600000000 0.3929979801 0.2448235048 0.4068948627 0.0198003038 0.1433000000 241535536 0 1776447488 0.1941047907 0.0124305449 -0.7081283331 871 34.8000000000 0.3907591105 0.2449910543 0.4068948627 0.0197954020 0.1457020000 241536682 0 1777733632 0.1939719468 0.0114730112 -0.7031599283 872 34.8400000000 0.3918677568 0.2451594909 0.4068948627 0.0197851573 0.1402700000 241537404 0 1779757056 0.1894697398 0.0098671876 -0.7016681433 873 34.8800000000 0.3915558755 0.2453271843 0.4068948627 0.0197756514 0.1748750000 241542974 0 1781366784 0.1876082718 0.0112925284 -0.6990544796 874 34.9200000000 0.3894132972 0.2454920426 0.4068948627 0.0197661149 0.1402510000 241542372 0 1783398400 0.1852447242 0.0099967606 -0.6948990226 875 34.9600000000 0.3898624480 0.2456570373 0.4068948627 0.0197634065 0.1346070000 241534882 0 1784815616 0.1804185510 0.0087357014 -0.6934096813 876 35.0000000000 0.3913274407 0.2458233277 0.4068948627 0.0197550717 0.1486370000 241540252 0 1786593280 0.1778396517 0.0112257674 -0.6924731135 877 35.0400000000 0.3902899027 0.2459880559 0.4068948627 0.0197467071 0.1415490000 241540922 0 1783197696 0.1785055548 0.0170464516 -0.6884307265 878 35.0800000000 0.3896818161 0.2461517162 0.4068948627 0.0197491598 0.1397130000 241542652 0 1782415360 0.1730901748 0.0111168623 -0.6860888004 879 35.1200000000 0.3862482905 0.2463110980 0.4068948627 0.0197401713 0.1426280000 241545662 0 1778606080 0.1748632491 0.0161198415 -0.6798787117 880 35.1600000000 0.3855184317 0.2464692881 0.4068948627 0.0197402097 0.1449140000 241549876 0 1776955392 0.1687432975 0.0150725730 -0.6771871448 881 35.2000000000 0.3843792081 0.2466258260 0.4068948627 0.0197467584 0.1392870000 241548722 0 1778352128 0.1697295159 0.0107900053 -0.6737292409 882 35.2400000000 0.3847478628 0.2467824270 0.4068948627 0.0197374670 0.1474780000 241549960 0 1780645888 0.1686008126 0.0171495490 -0.6710640788 883 35.2800000000 0.3826262653 0.2469362705 0.4068948627 0.0197359183 0.1414270000 241554126 0 1781874688 0.1641222537 0.0081173591 -0.6673618555 884 35.3200000000 0.3848432004 0.2470922738 0.4068948627 0.0197254856 0.1402010000 241556116 0 1783672832 0.1619325727 0.0122676436 -0.6674860716 885 35.3600000000 0.3800045252 0.2472424572 0.4068948627 0.0197171207 0.1803310000 242063052 0 1785303040 0.1600987464 0.0153871663 -0.6604522467 886 35.4000000000 0.3849428296 0.2473978752 0.4068948627 0.0197082784 0.3978400000 242023412 0 1784004608 0.1555586010 0.0154524520 -0.6634948254 887 35.4400000000 0.3819204271 0.2475495353 0.4068948627 0.0196997885 0.3421530000 242602809 0 1784418304 0.1528028548 0.0103718974 -0.6588374376 888 35.4800000000 0.3808775842 0.2476996795 0.4068948627 0.0196889031 0.2766720000 243777224 0 1784102912 0.1503483057 0.0111267306 -0.6558613777 889 35.5200000000 0.3682418764 0.2478352726 0.4068948627 0.0196820848 0.2953060000 243518384 0 1782800384 0.1538050622 0.0035864189 -0.6408597827 890 35.5600000000 0.3698091209 0.2479723218 0.4068948627 0.0196730957 0.1977440000 242137696 0 1783070720 0.1492911279 0.0019616336 -0.6410075426 891 35.6000000000 0.3694964051 0.2481087125 0.4068948627 0.0196625179 0.1723480000 242142978 0 1784758272 0.1476201415 0.0039936397 -0.6388698220 892 35.6400000000 0.3665736914 0.2482415208 0.4068948627 0.0196538830 0.1793270000 242144288 0 1786503168 0.1452320814 -0.0006932877 -0.6344158053 893 35.6800000000 0.3717996180 0.2483798837 0.4068948627 0.0196458121 0.1756190000 242148194 0 1783570432 0.1425491273 0.0059448425 -0.6381101608 894 35.7200000000 0.3710430264 0.2485170908 0.4068948627 0.0196357595 0.1699630000 242147348 0 1782448128 0.1415183842 0.0073214211 -0.6357148886 895 35.7600000000 0.3652532995 0.2486475223 0.4068948627 0.0196270905 0.1670020000 242145390 0 1781448704 0.1410312951 0.0058156103 -0.6283081770 896 35.8000000000 0.3712552190 0.2487843613 0.4068948627 0.0196219381 0.1655710000 242147180 0 1780797440 0.1343467087 0.0058082715 -0.6336325407 897 35.8400000000 0.3687085807 0.2489180561 0.4068948627 0.0196114261 0.1603370000 242144314 0 1782583296 0.1344322264 0.0064794160 -0.6296639442 898 35.8800000000 0.3713266850 0.2490543686 0.4068948627 0.0196057522 0.1647410000 242152600 0 1784868864 0.1286507249 0.0042380998 -0.6317698956 899 35.9200000000 0.3666577935 0.2491851844 0.4068948627 0.0195977037 0.1958120000 242149790 0 1785995264 0.1306237131 0.0116543137 -0.6254074574 900 35.9600000000 0.3675595224 0.2493167114 0.4068948627 0.0195933005 0.1671170000 242152140 0 1784369152 0.1253343821 0.0040091211 -0.6263507009 901 36.0000000000 0.3659178317 0.2494461244 0.4068948627 0.0195835835 0.1628000000 242155654 0 1783209984 0.1250839233 0.0067683607 -0.6242468357 902 36.0400000000 0.3640387654 0.2495731673 0.4068948627 0.0195740685 0.1685940000 242160196 0 1783357440 0.1221302077 0.0042582629 -0.6222984791 903 36.0800000000 0.3651725054 0.2497011843 0.4068948627 0.0195644972 0.1665970000 242159822 0 1784631296 0.1192748323 0.0042378111 -0.6230846047 904 36.1200000000 0.3589337468 0.2498220167 0.4068948627 0.0195553233 0.1590920000 242156872 0 1786540032 0.1190946996 0.0023070807 -0.6163927913 905 36.1600000000 0.3599891067 0.2499437483 0.4068948627 0.0195457809 0.1642240000 242163010 0 1783570432 0.1159616411 0.0085284263 -0.6168261766 906 36.2000000000 0.3605978489 0.2500658831 0.4068948627 0.0195417178 0.1582200000 242159768 0 1782300672 0.1135093644 0.0012733284 -0.6174849868 907 36.2400000000 0.3626319766 0.2501899912 0.4068948627 0.0195336280 0.1619330000 242159894 0 1781956608 0.1089650169 0.0031852890 -0.6201810241 908 36.2800000000 0.3657449484 0.2503172544 0.4068948627 0.0195249113 0.1601730000 242164160 0 1783234560 0.1055958420 0.0021680603 -0.6239159703 909 36.3200000000 0.3538963497 0.2504312028 0.4068948627 0.0195187726 0.1564490000 242164430 0 1785397248 0.1079697162 0.0062441239 -0.6110535264 910 36.3600000000 0.3619210720 0.2505537192 0.4068948627 0.0195125697 0.1593000000 242169580 0 1786540032 0.1027777791 0.0055215014 -0.6196128130 911 36.4000000000 0.3607693017 0.2506747022 0.4068948627 0.0195032129 0.1617100000 242171402 0 1783951360 0.0989474356 0.0058456776 -0.6189791560 912 36.4400000000 0.3577867150 0.2507921496 0.4068948627 0.0194941641 0.1599790000 242172488 0 1782935552 0.1006930396 0.0107879732 -0.6150403619 913 36.4800000000 0.3563245237 0.2509077382 0.4068948627 0.0194872274 0.1543570000 242171478 0 1784975360 0.0954734385 0.0057664732 -0.6140129566 914 36.5200000000 0.3643904030 0.2510318987 0.4068948627 0.0194831802 0.1574860000 242174880 0 1786662912 0.0885204002 0.0048205229 -0.6228104234 915 36.5600000000 0.3605868518 0.2511516308 0.4068948627 0.0194820914 0.1583640000 242175618 0 1783861248 0.0835630298 -0.0048505729 -0.6197934747 916 36.6000000000 0.3643381596 0.2512751969 0.4068948627 0.0194740391 0.1556750000 242178664 0 1782706176 0.0834843367 0.0044479826 -0.6231969595 917 36.6400000000 0.3607243299 0.2513945526 0.4068948627 0.0194647477 0.1557530000 242178430 0 1784635392 0.0854004323 0.0077760359 -0.6190124154 918 36.6800000000 0.3663860261 0.2515198156 0.4068948627 0.0194567176 0.1500800000 242179056 0 1786249216 0.0798540711 0.0080191679 -0.6250309348 919 36.7200000000 0.3624624312 0.2516405366 0.4068948627 0.0194463673 0.1681740000 242184198 0 1783971840 0.0777470544 0.0076377131 -0.6209053397 920 36.7600000000 0.3672354221 0.2517661833 0.4068948627 0.0194363262 0.1539330000 242182792 0 1782845440 0.0770084858 0.0105684670 -0.6254364252 921 36.8000000000 0.3597264588 0.2518834040 0.4068948627 0.0194288704 0.1514580000 242183246 0 1784614912 0.0770589933 0.0037181762 -0.6175944209 922 36.8400000000 0.3569956124 0.2519974085 0.4068948627 0.0194191980 0.1582210000 242185596 0 1786097664 0.0772873908 0.0057896413 -0.6140395403 923 36.8800000000 0.3602510393 0.2521146931 0.4068948627 0.0194104326 0.1631010000 242191282 0 1784475648 0.0752630159 0.0119469846 -0.6170315146 924 36.9200000000 0.3652577400 0.2522371423 0.4068948627 0.0194173670 0.1537710000 242191284 0 1786519552 0.0682709068 -0.0003154532 -0.6233594418 925 36.9600000000 0.3552475274 0.2523485048 0.4068948627 0.0194190592 0.1648700000 242193854 0 1785364480 0.0744797140 0.0105481613 -0.6116032004 926 37.0000000000 0.3599303067 0.2524646839 0.4068948627 0.0194104090 0.1602050000 242194424 0 1784500224 0.0698293000 0.0141174244 -0.6167204976 927 37.0400000000 0.3583283424 0.2525788842 0.4068948627 0.0194063276 0.1534530000 242193990 0 1782697984 0.0657732338 0.0055755000 -0.6158326864 928 37.0800000000 0.3635846078 0.2526985024 0.4068948627 0.0193977414 0.1507930000 242194828 0 1781813248 0.0627134740 0.0128390025 -0.6205868721 929 37.1200000000 0.3585556448 0.2528124498 0.4068948627 0.0194002224 0.1778610000 242199854 0 1783599104 0.0618333817 0.0009086271 -0.6154645681 930 37.1600000000 0.3665040731 0.2529346989 0.4068948627 0.0194007667 0.1543830000 242202848 0 1785208832 0.0565775447 -0.0049637775 -0.6238131523 931 37.2000000000 0.3599157929 0.2530496087 0.4068948627 0.0193965099 0.1523330000 242204706 0 1786224640 0.0603815168 0.0044276030 -0.6162297130 932 37.2400000000 0.3530487418 0.2531569039 0.4068948627 0.0193893846 0.1566240000 242200752 0 1785257984 0.0628784001 0.0036093341 -0.6087558270 933 37.2800000000 0.3540628850 0.2532650561 0.4068948627 0.0193803416 0.1655130000 242208630 0 1784758272 0.0643314049 0.0111004859 -0.6088517904 934 37.3200000000 0.3589430749 0.2533782018 0.4068948627 0.0193764724 0.1545400000 242207912 0 1782956032 0.0609046444 0.0051878048 -0.6139125824 935 37.3600000000 0.3536317348 0.2534854248 0.4068948627 0.0193710364 0.1524470000 242208734 0 1781813248 0.0622912906 0.0090506244 -0.6080768108 936 37.4000000000 0.3619848192 0.2536013429 0.4068948627 0.0193627569 0.1580990000 242212800 0 1783451648 0.0600980744 0.0122419512 -0.6166644096 937 37.4400000000 0.3560763001 0.2537107079 0.4068948627 0.0193568678 0.1519830000 242211138 0 1784827904 0.0622003227 0.0049343440 -0.6104545593 938 37.4800000000 0.3580047488 0.2538218956 0.4068948627 0.0193492172 0.1547880000 242207620 0 1786626048 0.0568179116 0.0057475166 -0.6131966710 939 37.5200000000 0.3576347232 0.2539324524 0.4068948627 0.0193399420 0.1503750000 242212870 0 1783074816 0.0587177873 0.0032781439 -0.6128275990 940 37.5600000000 0.3569696546 0.2540420664 0.4068948627 0.0193308319 0.1642620000 242219136 0 1782210560 0.0595274605 0.0096875373 -0.6120338440 941 37.6000000000 0.3549285233 0.2541492784 0.4068948627 0.0193221938 0.1556820000 242217658 0 1784250368 0.0616089776 0.0142295435 -0.6094044447 942 37.6400000000 0.3546916544 0.2542560113 0.4068948627 0.0193140144 0.1518630000 242221916 0 1785225216 0.0619982369 0.0104973419 -0.6093040109 943 37.6800000000 0.3577337861 0.2543657438 0.4068948627 0.0193049657 0.1536880000 242223858 0 1784102912 0.0624171458 0.0166256148 -0.6123754978 944 37.7200000000 0.3548344374 0.2544721725 0.4068948627 0.0192972851 0.1543770000 242222020 0 1783189504 0.0666342229 0.0180838034 -0.6088582277 945 37.7600000000 0.3604464233 0.2545843145 0.4068948627 0.0192961183 0.1583480000 242223158 0 1781460992 0.0598424599 0.0130493753 -0.6160436869 946 37.8000000000 0.3574953079 0.2546931000 0.4068948627 0.0192879433 0.1493880000 242225752 0 1780449280 0.0620996132 0.0177570693 -0.6126279235 947 37.8400000000 0.3556529582 0.2547997102 0.4068948627 0.0192786116 0.1541990000 242229074 0 1782431744 0.0643609539 0.0171280690 -0.6104275584 948 37.8800000000 0.3512127101 0.2549014116 0.4068948627 0.0192707404 0.1487870000 242228056 0 1783865344 0.0663663074 0.0196276493 -0.6055649519 949 37.9200000000 0.3589730859 0.2550110762 0.4068948627 0.0192624037 0.1514020000 242230750 0 1785606144 0.0640983731 0.0222917534 -0.6139466763 950 37.9600000000 0.3628440499 0.2551245846 0.4068948627 0.0192536671 0.1548920000 242233620 0 1785131008 0.0619656965 0.0220329948 -0.6184760928 951 38.0000000000 0.3637239933 0.2552387795 0.4068948627 0.0192441484 0.1559080000 242234566 0 1786626048 0.0633983091 0.0270485654 -0.6190310717 952 38.0400000000 0.3601554334 0.2553489861 0.4068948627 0.0192408922 0.1600490000 242234960 0 1783201792 0.0613908619 0.0189587958 -0.6160201430 953 38.0800000000 0.3664505780 0.2554655670 0.4068948627 0.0192338302 0.1473020000 242234134 0 1782059008 0.0589059591 0.0156686082 -0.6232641935 954 38.1200000000 0.3563352525 0.2555713004 0.4068948627 0.0192412346 0.1492010000 242236344 0 1781555200 0.0696684569 0.0278344620 -0.6108688116 955 38.1600000000 0.3664171100 0.2556873693 0.4068948627 0.0192472618 0.1543610000 242241782 0 1780645888 0.0587002710 0.0196057409 -0.6232580543 956 38.2000000000 0.3527900875 0.2557889412 0.4068948627 0.0192447560 0.1493760000 242240028 0 1782722560 0.0651860461 0.0173214413 -0.6088845134 957 38.2400000000 0.3533607125 0.2558908971 0.4068948627 0.0192396998 0.1487380000 242240690 0 1783992320 0.0691200048 0.0273273662 -0.6085585356 958 38.2800000000 0.3621863425 0.2560018527 0.4068948627 0.0192370837 0.1546710000 242244664 0 1785987072 0.0629664809 0.0200078338 -0.6189202666 959 38.3200000000 0.3536908031 0.2561037181 0.4068948627 0.0192306032 0.1491580000 242246314 0 1784856576 0.0656883270 0.0105396258 -0.6103963852 960 38.3600000000 0.3551501334 0.2562068915 0.4068948627 0.0192216771 0.1810220000 242244492 0 1783857152 0.0633062422 0.0142773520 -0.6121852994 961 38.4000000000 0.3596790433 0.2563145628 0.4068948627 0.0192127830 0.1485950000 242245622 0 1785606144 0.0649087578 0.0136492327 -0.6167533994 962 38.4400000000 0.3599717617 0.2564223146 0.4068948627 0.0192088947 0.1481350000 242249512 0 1784995840 0.0645412728 0.0266764350 -0.6168323159 963 38.4800000000 0.3612572551 0.2565311774 0.4068948627 0.0191997540 0.1508480000 242249062 0 1784131584 0.0638011023 0.0213210750 -0.6186807156 964 38.5200000000 0.3619014919 0.2566404827 0.4068948627 0.0191916829 0.1530390000 242255368 0 1783480320 0.0617894717 0.0151167754 -0.6199752092 965 38.5600000000 0.3587317169 0.2567462768 0.4068948627 0.0191839641 0.1456620000 242252594 0 1784606720 0.0642109886 0.0205779225 -0.6163378358 966 38.6000000000 0.3628775775 0.2568561435 0.4068948627 0.0191748010 0.1518230000 242255372 0 1786765312 0.0646333322 0.0194325447 -0.6207088828 967 38.6400000000 0.3600166440 0.2569628245 0.4068948627 0.0191655826 0.1556210000 242257162 0 1783578624 0.0668353885 0.0175047815 -0.6177403927 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_living_room_traj2_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:29:41 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_living_room_traj2_loop.log input: datasets/ICL_NUIM/living_room_traj2_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1550350000 225832032 0 1771012096 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0014313232 0.0007156616 0.0014313232 0.0012994849 0.2121070000 229184250 0 1770524672 0.0006581696 0.0002409728 -0.0004112680 3 0.0800000000 0.0015986046 0.0010099759 0.0015986046 0.0012106350 0.1923260000 229113605 0 1769631744 -0.0043599396 0.0007933624 -0.0005638560 4 0.1200000000 0.0025625008 0.0013981072 0.0025625008 0.0015030597 0.1831090000 229116466 0 1771405312 -0.0007651650 0.0010692495 -0.0008835325 5 0.1600000000 0.0033080552 0.0017800968 0.0033080552 0.0016293658 0.1819140000 229118240 0 1772883968 -0.0045461673 -0.0007636446 0.0008597028 6 0.2000000000 0.0010997391 0.0016667038 0.0033080552 0.0018582507 0.1847850000 229123454 0 1774534656 -0.0045890105 0.0020316094 -0.0003118569 7 0.2400000000 0.0011017808 0.0015860005 0.0033080552 0.0017081959 0.1849270000 229125180 0 1776566272 -0.0049471781 0.0021273063 -0.0001025872 8 0.2800000000 0.0026124064 0.0017143013 0.0033080552 0.0016681742 0.1835710000 229126806 0 1778089984 -0.0045765373 0.0022254123 -0.0000543934 9 0.3200000000 0.0013466377 0.0016734498 0.0033080552 0.0018296116 0.1836890000 229128556 0 1779613696 -0.0078928396 0.0013401783 -0.0005790861 10 0.3600000000 0.0032167227 0.0018277771 0.0033080552 0.0018284254 0.1826390000 229130978 0 1781645312 -0.0064287814 0.0035329887 -0.0002855470 11 0.4000000000 0.0016429899 0.0018109782 0.0033080552 0.0020160400 0.1812040000 229133240 0 1783169024 -0.0086579695 0.0004761029 0.0014675055 12 0.4400000000 0.0008761504 0.0017330759 0.0033080552 0.0023816688 0.1864350000 229134602 0 1784967168 -0.0107537834 0.0002679621 0.0000298793 13 0.4800000000 0.0015374204 0.0017180255 0.0033080552 0.0024827525 0.1891400000 229135904 0 1786597376 -0.0112762246 0.0006451863 0.0001494178 14 0.5200000000 0.0034266028 0.0018400667 0.0034266028 0.0023905376 0.1826970000 229138546 0 1783091200 -0.0095544988 0.0005430994 -0.0008344530 15 0.5600000000 0.0009415949 0.0017801686 0.0034266028 0.0024006183 0.1894040000 229140300 0 1782034432 -0.0160803571 0.0020275211 0.0010757227 16 0.6000000000 0.0026617956 0.0018352703 0.0034266028 0.0023944184 0.1824530000 229141782 0 1783312384 -0.0124555193 0.0022582377 -0.0001530996 17 0.6400000000 0.0036080938 0.0019395540 0.0036080938 0.0024345379 0.1814700000 229143612 0 1785503744 -0.0146324635 -0.0029591334 -0.0022498947 18 0.6800000000 0.0017785733 0.0019306107 0.0036080938 0.0024035281 0.1815350000 229147034 0 1784344576 -0.0178455506 -0.0014289076 -0.0015437480 19 0.7200000000 0.0044847336 0.0020650382 0.0044847336 0.0023830012 0.1860730000 229149024 0 1783451648 -0.0191986505 -0.0042364202 -0.0015589664 20 0.7600000000 0.0029233287 0.0021079527 0.0044847336 0.0024826552 0.1806320000 229151630 0 1779408896 -0.0222831499 -0.0039281002 -0.0015793118 21 0.8000000000 0.0054242653 0.0022658723 0.0054242653 0.0024329833 0.1844310000 229154780 0 1778368512 -0.0215592124 -0.0032885198 -0.0016858662 22 0.8400000000 0.0044204351 0.0023638070 0.0054242653 0.0023765304 0.1868880000 229158422 0 1780006912 -0.0283740442 -0.0038597609 -0.0022924212 23 0.8800000000 0.0064602704 0.0025419141 0.0064602704 0.0023593829 0.1810890000 229159640 0 1781403648 -0.0248624086 -0.0028821700 -0.0046925945 24 0.9200000000 0.0058363420 0.0026791819 0.0064602704 0.0023209396 0.1816570000 229163362 0 1783570432 -0.0342931375 -0.0026345411 -0.0054048188 25 0.9600000000 0.0047086249 0.0027603597 0.0064602704 0.0022994096 0.1771450000 229165424 0 1784856576 -0.0364596024 -0.0011650682 -0.0057174251 26 1.0000000000 0.0056688362 0.0028722241 0.0064602704 0.0022616013 0.1762050000 229166090 0 1786634240 -0.0419057533 -0.0024756331 -0.0058216825 27 1.0400000000 0.0058540511 0.0029826622 0.0064602704 0.0023438986 0.2019780000 229168592 0 1783574528 -0.0467933007 -0.0004914570 -0.0068055941 28 1.0800000000 0.0040868837 0.0030220987 0.0064602704 0.0025304410 0.1778080000 229171754 0 1785614336 -0.0553563610 -0.0030685039 -0.0073033413 29 1.1200000000 0.0046187984 0.0030771573 0.0064602704 0.0026787045 0.1768310000 229174444 0 1784709120 -0.0605350733 -0.0026142881 -0.0107380766 30 1.1600000000 0.0043244767 0.0031187346 0.0064602704 0.0027372247 0.1771480000 229177134 0 1783717888 -0.0686885267 -0.0004705007 -0.0075295828 31 1.2000000000 0.0044127894 0.0031604783 0.0064602704 0.0027276073 0.1767730000 229179996 0 1782849536 -0.0754016787 -0.0005745856 -0.0102658309 32 1.2400000000 0.0064034802 0.0032618221 0.0064602704 0.0027825837 0.1757670000 229182270 0 1784721408 -0.0805095509 -0.0016229552 -0.0126366820 33 1.2800000000 0.0056035062 0.0033327822 0.0064602704 0.0028330372 0.1783700000 229185412 0 1786630144 -0.0882319137 -0.0038777082 -0.0118118906 34 1.3200000000 0.0031875810 0.0033285116 0.0064602704 0.0028738846 0.1768210000 229192110 0 1783447552 -0.1196961179 -0.0033451796 -0.0118917823 35 1.3600000000 0.0051884740 0.0033816534 0.0064602704 0.0032724079 0.1821260000 229194028 0 1781772288 -0.1184015647 -0.0002659525 -0.0152553022 36 1.4000000000 0.0083054565 0.0035184257 0.0083054565 0.0038637342 0.1740870000 229195266 0 1784229888 -0.1219767109 -0.0021543859 -0.0183373652 37 1.4400000000 0.0038985442 0.0035286992 0.0083054565 0.0038709067 0.1783300000 229198028 0 1785860096 -0.1361968517 -0.0014676850 -0.0150895445 38 1.4800000000 0.0031177877 0.0035178857 0.0083054565 0.0038231293 0.1776480000 229200526 0 1784856576 -0.1489492953 -0.0012886865 -0.0153722540 39 1.5200000000 0.0030725361 0.0035064665 0.0083054565 0.0037868828 0.1786590000 229202380 0 1786494976 -0.1520166099 -0.0012764528 -0.0171504728 40 1.5600000000 0.0045988210 0.0035337753 0.0083054565 0.0037789379 0.1748350000 229204282 0 1782927360 -0.1612601131 -0.0054960060 -0.0186817516 41 1.6000000000 0.0018794789 0.0034934267 0.0083054565 0.0038481811 0.1731500000 229206488 0 1781915648 -0.1737936884 -0.0053910473 -0.0158038568 42 1.6400000000 0.0007594588 0.0034283322 0.0083054565 0.0038136314 0.1767860000 229209578 0 1781551104 -0.1881669611 -0.0035411189 -0.0126697440 43 1.6800000000 0.0042145746 0.0034466169 0.0083054565 0.0037892510 0.1732850000 229210676 0 1783320576 -0.1915484220 -0.0013622099 -0.0102223512 44 1.7200000000 0.0036090321 0.0034503081 0.0083054565 0.0038036586 0.1729330000 229213670 0 1785352192 -0.1982260495 -0.0034890007 -0.0111872572 45 1.7600000000 0.0018778522 0.0034153647 0.0083054565 0.0038820173 0.1741940000 229215432 0 1786859520 -0.2115889788 -0.0001864925 -0.0073935483 46 1.8000000000 0.0034776025 0.0034167177 0.0083054565 0.0039071332 0.1781110000 229218262 0 1783312384 -0.2186075300 0.0016900502 -0.0074814409 47 1.8400000000 0.0020418027 0.0033874642 0.0083054565 0.0039814164 0.1812000000 229219752 0 1782063104 -0.2211188227 -0.0021322661 -0.0087150782 48 1.8800000000 0.0040450147 0.0034011631 0.0083054565 0.0040159835 0.1738910000 229221014 0 1781026816 -0.2228236943 0.0010480208 -0.0071889814 49 1.9200000000 0.0019453039 0.0033714517 0.0083054565 0.0039804911 0.1790530000 229223032 0 1780539392 -0.2292384803 -0.0009724108 -0.0064476039 50 1.9600000000 0.0006246613 0.0033165159 0.0083054565 0.0039538719 0.1792720000 229224878 0 1780015104 -0.2452408224 -0.0016744845 -0.0010578819 51 2.0000000000 0.0035712300 0.0033215103 0.0083054565 0.0039402036 0.1792910000 229225744 0 1781940224 -0.2413468063 0.0003226941 -0.0036178511 52 2.0400000000 0.0025256218 0.0033062048 0.0083054565 0.0039343208 0.1758070000 229228474 0 1783828480 -0.2499829531 -0.0011146957 -0.0048162472 53 2.0800000000 0.0033417589 0.0033068756 0.0083054565 0.0039689531 0.1822090000 229229572 0 1785733120 -0.2526609898 -0.0043185200 -0.0071903002 54 2.1200000000 0.0021989581 0.0032863586 0.0083054565 0.0040004855 0.2139080000 229231238 0 1784078336 -0.2641378939 -0.0067758439 -0.0013691615 55 2.1600000000 0.0032856415 0.0032863456 0.0083054565 0.0041259229 0.1755290000 229232612 0 1785724928 -0.2660660446 -0.0037566447 -0.0002128780 56 2.2000000000 0.0037232765 0.0032941479 0.0083054565 0.0041465112 0.1806260000 229235250 0 1784680448 -0.2877717316 -0.0032696540 0.0080956612 57 2.2400000000 0.0025316142 0.0032807701 0.0083054565 0.0041186422 0.1754140000 229235780 0 1784086528 -0.2898827493 -0.0054164887 0.0083681289 58 2.2800000000 0.0027154642 0.0032710235 0.0083054565 0.0041263615 0.1756700000 229236566 0 1783160832 -0.3010892272 -0.0078460965 0.0113822613 59 2.3200000000 0.0037592936 0.0032792992 0.0083054565 0.0042373402 0.1778800000 229238176 0 1784307712 -0.3162419498 -0.0058683665 0.0175232515 60 2.3600000000 0.0003290194 0.0032301279 0.0083054565 0.0043727870 0.1742940000 229239434 0 1786105856 -0.3162730038 -0.0071107596 0.0133377239 61 2.4000000000 0.0031536699 0.0032288745 0.0083054565 0.0044612645 0.1810680000 229242356 0 1784594432 -0.3238817453 -0.0061782170 0.0145355817 62 2.4400000000 0.0076294625 0.0032998517 0.0083054565 0.0046768338 0.1759220000 229244862 0 1783320576 -0.3433142602 -0.0020977643 0.0258434005 63 2.4800000000 0.0050271251 0.0033272688 0.0083054565 0.0048136332 0.1769520000 229247472 0 1785344000 -0.3590135574 -0.0077484353 0.0278136265 64 2.5200000000 0.0041248384 0.0033397308 0.0083054565 0.0051872839 0.1743070000 229250442 0 1784479744 -0.3686864674 -0.0054737781 0.0320438705 65 2.5600000000 0.0091334423 0.0034288648 0.0091334423 0.0053535747 0.1759470000 229251576 0 1783197696 -0.3875519037 -0.0021165861 0.0365006886 66 2.6000000000 0.0038967147 0.0034359534 0.0091334423 0.0055504949 0.1779610000 229264386 0 1782272000 -0.3961123526 -0.0076670195 0.0365253538 67 2.6400000000 0.0022232167 0.0034178529 0.0091334423 0.0055902163 0.1746140000 229266716 0 1784057856 -0.4041239023 -0.0040631965 0.0387736894 68 2.6800000000 0.0035177355 0.0034193218 0.0091334423 0.0055709671 0.1957980000 229636243 0 1785851904 -0.4160120487 -0.0029914065 0.0386105292 69 2.7200000000 0.0030806982 0.0034144142 0.0091334423 0.0055328377 0.2486470000 229911481 0 1786298368 -0.4255627096 -0.0032822485 0.0428374112 70 2.7600000000 0.0033689253 0.0034137643 0.0091334423 0.0055025423 0.3654130000 230650225 0 1786527744 -0.4330729842 -0.0003542806 0.0426674671 71 2.8000000000 0.0168734118 0.0036033368 0.0168734118 0.0059980279 0.2702540000 230523272 0 1783439360 -0.4462290406 -0.0157507490 0.0295318738 72 2.8400000000 0.0155074364 0.0037686715 0.0168734118 0.0065438670 0.1688230000 229902890 0 1782984704 -0.4580355585 -0.0106477998 0.0331004038 73 2.8800000000 0.0162331089 0.0039394173 0.0168734118 0.0066316620 0.1731580000 229904780 0 1785278464 -0.4708706737 -0.0086945966 0.0335344896 74 2.9200000000 0.0152966687 0.0040928936 0.0168734118 0.0067148808 0.1679770000 229906138 0 1784631296 -0.4719649255 -0.0064782561 0.0307784379 75 2.9600000000 0.0171179473 0.0042665610 0.0171179473 0.0067517873 0.1734360000 229910328 0 1783877632 -0.4743030667 -0.0042309435 0.0271935910 76 3.0000000000 0.0179570448 0.0044466990 0.0179570448 0.0067517073 0.1724320000 229912326 0 1782861824 -0.4691089988 -0.0009979783 0.0164519176 77 3.0400000000 0.0171132460 0.0046111996 0.0179570448 0.0067836757 0.1681790000 229915716 0 1784627200 -0.4711896479 -0.0008174547 0.0116453618 78 3.0800000000 0.0175309759 0.0047768377 0.0179570448 0.0067443555 0.1666600000 229917866 0 1786314752 -0.4702144265 -0.0001873048 0.0049653426 79 3.1200000000 0.0158091094 0.0049164867 0.0179570448 0.0067020512 0.1931100000 229920800 0 1784406016 -0.4789864123 0.0055015176 0.0031514466 80 3.1600000000 0.0182422828 0.0050830592 0.0182422828 0.0066763770 0.1676900000 229923514 0 1781088256 -0.4829075336 0.0058350652 -0.0011486188 81 3.2000000000 0.0175654870 0.0052371632 0.0182422828 0.0066519068 0.1886720000 230251972 0 1779953664 -0.4919309616 0.0057443175 0.0003626645 82 3.2400000000 0.0203464516 0.0054214228 0.0203464516 0.0066708813 0.3765190000 230576889 0 1782837248 -0.5036988258 0.0029331052 0.0006454140 83 3.2800000000 0.0190325920 0.0055854128 0.0203464516 0.0066980457 0.1965230000 231027467 0 1785413632 -0.5081084371 0.0063066995 -0.0036239177 84 3.3200000000 0.0182013866 0.0057356030 0.0203464516 0.0066663133 0.2080150000 230771952 0 1784758272 -0.5247070193 0.0068004518 -0.0020258576 85 3.3600000000 0.0199758504 0.0059031353 0.0203464516 0.0066478917 0.1607990000 230235600 0 1786773504 -0.5431401134 0.0078332536 -0.0001847595 86 3.4000000000 0.0215244610 0.0060847786 0.0215244610 0.0066661293 0.1669630000 230236706 0 1783345152 -0.5624165535 0.0095923655 0.0067539662 87 3.4400000000 0.0219367649 0.0062669854 0.0219367649 0.0068105484 0.1705260000 230240236 0 1781444608 -0.5711866617 0.0075262189 0.0044180602 88 3.4800000000 0.0221030843 0.0064469410 0.0221030843 0.0069544510 0.1670420000 230242658 0 1782931456 -0.5833905935 0.0065427152 0.0051171035 89 3.5200000000 0.0207513236 0.0066076644 0.0221030843 0.0070889109 0.1636520000 230245292 0 1784979456 -0.5916268229 0.0081494404 0.0043533295 90 3.5600000000 0.0219147820 0.0067777435 0.0221030843 0.0071640540 0.1735130000 230246078 0 1786249216 -0.5997579694 0.0050369371 0.0034521222 91 3.6000000000 0.0177716222 0.0068985554 0.0221030843 0.0072278745 0.1645060000 230250040 0 1785233408 -0.6126963496 0.0078873634 0.0077571273 92 3.6400000000 0.0189828593 0.0070299065 0.0221030843 0.0072513025 0.1631980000 230251362 0 1784090624 -0.6239806414 0.0065275268 0.0099954754 93 3.6800000000 0.0183982309 0.0071521466 0.0221030843 0.0072266360 0.1659180000 230252508 0 1782345728 -0.6303004622 0.0077146618 0.0064126998 94 3.7200000000 0.0166019145 0.0072526760 0.0221030843 0.0071935921 0.1602910000 230255562 0 1780576256 -0.6392347813 0.0085284561 0.0081810355 95 3.7600000000 0.0194877330 0.0073814661 0.0221030843 0.0071827582 0.1801520000 230570164 0 1781948416 -0.6549201012 0.0084551182 0.0142833292 96 3.8000000000 0.0199014265 0.0075118823 0.0221030843 0.0071615849 0.3611620000 230638338 0 1782878208 -0.6621932387 0.0053658960 0.0117236972 97 3.8400000000 0.0197122805 0.0076376596 0.0221030843 0.0071248674 0.2867510000 231561231 0 1784922112 -0.6683913469 0.0029115630 0.0145378709 98 3.8800000000 0.0258586798 0.0078235884 0.0258586798 0.0071126215 0.2492680000 231510950 0 1782243328 -0.6897287369 -0.0001503415 0.0188107491 99 3.9200000000 0.0245360732 0.0079924014 0.0258586798 0.0070849670 0.1745490000 230611824 0 1782013952 -0.6944977045 0.0018152799 0.0233054906 100 3.9600000000 0.0256247893 0.0081687253 0.0258586798 0.0070505869 0.1666970000 230613010 0 1783971840 -0.7060575485 0.0032664491 0.0297220498 101 4.0000000000 0.0256820191 0.0083421242 0.0258586798 0.0070188130 0.1725850000 230614316 0 1785712640 -0.7135745883 0.0004803659 0.0337415338 102 4.0400000000 0.0247873291 0.0085033517 0.0258586798 0.0069948937 0.1718410000 230615898 0 1783955456 -0.7163184285 -0.0001879437 0.0346066505 103 4.0800000000 0.0265210103 0.0086782804 0.0265210103 0.0069651797 0.1677540000 230619696 0 1783062528 -0.7277283072 -0.0018517682 0.0395227224 104 4.1200000000 0.0245148111 0.0088305548 0.0265210103 0.0069464606 0.1931950000 230620942 0 1782300672 -0.7378095388 -0.0035575181 0.0522672981 105 4.1600000000 0.0272037741 0.0090055378 0.0272037741 0.0069425176 0.1622850000 230622236 0 1783955456 -0.7424259186 -0.0070879236 0.0560517013 106 4.2000000000 0.0266331714 0.0091718362 0.0272037741 0.0069398057 0.1642020000 230626958 0 1785331712 -0.7508689165 -0.0034220181 0.0628247708 107 4.2400000000 0.0256752595 0.0093260738 0.0272037741 0.0069251586 0.1653500000 230627120 0 1786990592 -0.7499859333 -0.0065397806 0.0585798174 108 4.2800000000 0.0307244044 0.0095242065 0.0307244044 0.0069033061 0.1881490000 230995399 0 1782571008 -0.7632479668 -0.0118188458 0.0685553700 109 4.3200000000 0.0291330144 0.0097041039 0.0307244044 0.0068841055 0.4050340000 231023324 0 1780125696 -0.7637913227 -0.0102176676 0.0678348839 110 4.3600000000 0.0276302062 0.0098670684 0.0307244044 0.0068816134 0.3610850000 232306817 0 1785470976 -0.7695745230 -0.0100706015 0.0741252154 111 4.4000000000 0.0282287411 0.0100324889 0.0307244044 0.0068950087 0.2193920000 232243099 0 1784860672 -0.7762898803 -0.0122743649 0.0814999342 112 4.4400000000 0.0175917055 0.0100999819 0.0307244044 0.0069617090 0.2404100000 232171426 0 1783517184 -0.7753413916 -0.0057811663 0.0911149681 113 4.4800000000 0.0220536683 0.0102057667 0.0307244044 0.0069982919 0.1782110000 231033920 0 1782706176 -0.7785100341 -0.0112316655 0.0915656537 114 4.5200000000 0.0167849436 0.0102634788 0.0307244044 0.0070325158 0.1747970000 231035014 0 1785229312 -0.7899960279 -0.0051442795 0.1075779796 115 4.5600000000 0.0201410558 0.0103493708 0.0307244044 0.0070642604 0.1758980000 231037656 0 1786519552 -0.7912861109 -0.0088171344 0.1075988710 116 4.6000000000 0.0225785151 0.0104547944 0.0307244044 0.0071219319 0.1724140000 231038742 0 1782976512 -0.8023347855 -0.0079650804 0.1175454259 117 4.6400000000 0.0210423507 0.0105452864 0.0307244044 0.0071212821 0.1728590000 231040104 0 1781190656 -0.8101071715 -0.0040478557 0.1303501278 118 4.6800000000 0.0181323998 0.0106095840 0.0307244044 0.0070970489 0.1696350000 231044006 0 1782325248 -0.8156031370 -0.0020815842 0.1361618340 119 4.7200000000 0.0201697014 0.0106899211 0.0307244044 0.0070731859 0.1740760000 231045844 0 1784356864 -0.8223853707 -0.0049982313 0.1427302957 120 4.7600000000 0.0173388254 0.0107453286 0.0307244044 0.0070511982 0.1661900000 231047698 0 1786118144 -0.8273177147 -0.0014320984 0.1511458606 121 4.8000000000 0.0195847116 0.0108183814 0.0307244044 0.0070392619 0.1737040000 231050584 0 1785012224 -0.8401814699 -0.0021220129 0.1707593501 122 4.8400000000 0.0196197722 0.0108905239 0.0307244044 0.0070139911 0.1720710000 231053566 0 1786789888 -0.8420336246 -0.0006664060 0.1724432856 123 4.8800000000 0.0206671339 0.0109700085 0.0307244044 0.0069944668 0.1741830000 231055232 0 1785143296 -0.8463616371 0.0007629786 0.1771906465 124 4.9200000000 0.0184014160 0.0110299393 0.0307244044 0.0069757899 0.1936080000 231391479 0 1784250368 -0.8522579670 0.0037841611 0.1890950352 125 4.9600000000 0.0196340773 0.0110987724 0.0307244044 0.0069540075 0.3918660000 231395924 0 1781772288 -0.8639112115 0.0085290857 0.2006191909 126 5.0000000000 0.0192592908 0.0111635384 0.0307244044 0.0069599359 0.3638260000 231729461 0 1784422400 -0.8629517555 0.0034844913 0.2036879510 127 5.0400000000 0.0188133977 0.0112237735 0.0307244044 0.0069332046 0.3189660000 232768312 0 1784344576 -0.8738042712 0.0059574004 0.2218247354 128 5.0800000000 0.0142374532 0.0112473179 0.0307244044 0.0069193111 0.3102840000 232681230 0 1782046720 -0.8756940365 0.0089199767 0.2278404385 129 5.1200000000 0.0140741002 0.0112692309 0.0307244044 0.0068982196 0.1737560000 231402308 0 1781665792 -0.8775557280 0.0083070174 0.2331257761 130 5.1600000000 0.0147793684 0.0112962320 0.0307244044 0.0068864862 0.1713540000 231426458 0 1783955456 -0.8873302937 0.0073287115 0.2524803281 131 5.2000000000 0.0150416140 0.0113248227 0.0307244044 0.0068917161 0.1727860000 231429932 0 1785712640 -0.8937215805 0.0107962806 0.2564377487 132 5.2400000000 0.0134224910 0.0113407141 0.0307244044 0.0069121958 0.1672100000 231430302 0 1783951360 -0.8908676505 0.0096733868 0.2534901202 133 5.2800000000 0.0134893050 0.0113568689 0.0307244044 0.0069072303 0.1738790000 231433404 0 1782972416 -0.9010875821 0.0110103581 0.2711313367 134 5.3200000000 0.0147607848 0.0113822713 0.0307244044 0.0069388350 0.1690580000 231436658 0 1781317632 -0.9120032191 0.0113950912 0.2907316387 135 5.3600000000 0.0129373744 0.0113937905 0.0307244044 0.0069332853 0.1694910000 231437212 0 1783062528 -0.9165723324 0.0176377241 0.2956281304 136 5.4000000000 0.0144256884 0.0114160839 0.0307244044 0.0069815606 0.1758990000 231440718 0 1784459264 -0.9231365323 0.0137027539 0.3067457974 137 5.4400000000 0.0140547203 0.0114353440 0.0307244044 0.0070434229 0.1676350000 231442996 0 1786236928 -0.9255093336 0.0116053540 0.3152931631 138 5.4800000000 0.0137146376 0.0114518607 0.0307244044 0.0070818515 0.1689210000 231444242 0 1785004032 -0.9327130318 0.0122006312 0.3215903342 139 5.5200000000 0.0153749445 0.0114800843 0.0307244044 0.0071238209 0.1923270000 231833181 0 1786654720 -0.9416117668 0.0112892147 0.3270421922 140 5.5600000000 0.0163100194 0.0115145838 0.0307244044 0.0071996000 0.4230670000 231843011 0 1784918016 -0.9489176273 0.0090897884 0.3384699225 141 5.6000000000 0.0169376824 0.0115530455 0.0307244044 0.0072143621 0.3713460000 231927209 0 1787011072 -0.9573327303 0.0114302356 0.3478508890 142 5.6400000000 0.0144006396 0.0115730990 0.0307244044 0.0072534024 0.2871830000 233530446 0 1784012800 -0.9632942677 0.0128319524 0.3594229817 143 5.6800000000 0.0148683321 0.0115961426 0.0307244044 0.0073149356 0.2267460000 233454044 0 1782366208 -0.9700455666 0.0160153396 0.3701007664 144 5.7200000000 0.0096916948 0.0115829172 0.0307244044 0.0073463903 0.3066200000 233383194 0 1781538816 -0.9724935889 0.0217930488 0.3789726794 145 5.7600000000 0.0099439211 0.0115716138 0.0307244044 0.0073437676 0.1846950000 231854453 0 1783500800 -0.9790885448 0.0211184397 0.3880647123 146 5.8000000000 0.0117431004 0.0115727884 0.0307244044 0.0073319323 0.1796080000 231857239 0 1785278464 -0.9863182902 0.0194483325 0.3981386721 147 5.8400000000 0.0109136999 0.0115683048 0.0307244044 0.0073122274 0.1737180000 231856669 0 1786929152 -0.9947896004 0.0178388953 0.4168752432 148 5.8800000000 0.0121358251 0.0115721394 0.0307244044 0.0072925647 0.1763060000 231861095 0 1783373824 -0.9990774989 0.0214827098 0.4233807027 149 5.9200000000 0.0110833412 0.0115688589 0.0307244044 0.0072731033 0.1767180000 231861117 0 1782771712 -1.0021320581 0.0208762959 0.4338004291 150 5.9600000000 0.0111940615 0.0115663602 0.0307244044 0.0072513712 0.1718920000 231863327 0 1784811520 -1.0058131218 0.0206959024 0.4416467845 151 6.0000000000 0.0110694077 0.0115630691 0.0307244044 0.0072331274 0.2071850000 231863781 0 1786183680 -1.0079801083 0.0276174322 0.4491070509 152 6.0400000000 0.0095983259 0.0115501432 0.0307244044 0.0072263118 0.1625080000 231865771 0 1785171968 -1.0101470947 0.0256218351 0.4596394002 153 6.0800000000 0.0086771380 0.0115313654 0.0307244044 0.0072166979 0.1676820000 231865729 0 1786691584 -1.0130984783 0.0264019482 0.4698626399 154 6.1200000000 0.0122864256 0.0115362684 0.0307244044 0.0072193339 0.1861300000 232225179 0 1785303040 -1.0216939449 0.0254306681 0.4846155345 155 6.1600000000 0.0109843612 0.0115327077 0.0307244044 0.0072950243 0.4090180000 232239821 0 1784942592 -1.0212596655 0.0228243917 0.4875712097 156 6.2000000000 0.0112360762 0.0115308062 0.0307244044 0.0074111582 0.3458440000 232338391 0 1786757120 -1.0269335508 0.0218487568 0.5055704117 157 6.2400000000 0.0120876087 0.0115343527 0.0307244044 0.0074656290 0.3432490000 234101780 0 1783812096 -1.0294189453 0.0287483782 0.5179307461 158 6.2800000000 0.0100356098 0.0115248670 0.0307244044 0.0075605392 0.2583740000 234071278 0 1782669312 -1.0309908390 0.0255528316 0.5323721170 159 6.3200000000 0.0135039045 0.0115373138 0.0307244044 0.0075741642 0.3820920000 233944320 0 1780674560 -1.0327315331 0.0313169472 0.5445599556 160 6.3600000000 0.0114965839 0.0115370592 0.0307244044 0.0076093802 0.1705370000 232248955 0 1781035008 -1.0318207741 0.0326876007 0.5567817688 161 6.4000000000 0.0130044883 0.0115461737 0.0307244044 0.0075948063 0.1666730000 232251025 0 1781940224 -1.0341455936 0.0306116641 0.5720230937 162 6.4400000000 0.0124167986 0.0115515479 0.0307244044 0.0075738996 0.1827950000 232589255 0 1784082432 -1.0346113443 0.0274119377 0.5813335180 163 6.4800000000 0.0122674955 0.0115559402 0.0307244044 0.0075555205 0.3886980000 232624414 0 1786142720 -1.0345728397 0.0311431177 0.5938460827 164 6.5200000000 0.0123782950 0.0115609546 0.0307244044 0.0075373909 0.3545600000 232626908 0 1785565184 -1.0359302759 0.0297132023 0.6051621437 165 6.5600000000 0.0133807855 0.0115719839 0.0307244044 0.0075253180 0.3539090000 233303505 0 1784029184 -1.0369441509 0.0340647697 0.6223542690 166 6.6000000000 0.0135640400 0.0115839842 0.0307244044 0.0075356979 0.2800770000 234642978 0 1783721984 -1.0363811255 0.0345959254 0.6343709826 167 6.6400000000 0.0124525456 0.0115891852 0.0307244044 0.0075352476 0.2166920000 234611397 0 1785589760 -1.0346922874 0.0353495441 0.6438932419 168 6.6800000000 0.0140017094 0.0116035454 0.0307244044 0.0075621188 0.3467330000 234579618 0 1784250368 -1.0313529968 0.0417427048 0.6571153402 169 6.7200000000 0.0141848382 0.0116188193 0.0307244044 0.0075512659 0.2524500000 232633102 0 1785331712 -1.0333688259 0.0371569619 0.6740757227 170 6.7600000000 0.0123948697 0.0116233843 0.0307244044 0.0075458102 0.1815390000 232635844 0 1784201216 -1.0331161022 0.0397335030 0.6879999638 171 6.8000000000 0.0136795174 0.0116354085 0.0307244044 0.0075352439 0.1699420000 232636630 0 1783091200 -1.0319650173 0.0443162359 0.6973724365 172 6.8400000000 0.0106092095 0.0116294422 0.0307244044 0.0075193230 0.1698690000 232639108 0 1781694464 -1.0314079523 0.0413565971 0.7099057436 173 6.8800000000 0.0098283263 0.0116190312 0.0307244044 0.0074996863 0.1662360000 232641486 0 1783181312 -1.0322022438 0.0408045240 0.7233285904 174 6.9200000000 0.0125469817 0.0116243642 0.0307244044 0.0074814599 0.1657960000 232642356 0 1784709120 -1.0331894159 0.0472441316 0.7363001108 175 6.9600000000 0.0113198068 0.0116226239 0.0307244044 0.0074602817 0.1865130000 233004142 0 1786597376 -1.0325810909 0.0464689881 0.7478779554 176 7.0000000000 0.0109244650 0.0116186571 0.0307244044 0.0074409037 0.3919950000 233004580 0 1782091776 -1.0333274603 0.0462965816 0.7598089576 177 7.0400000000 0.0128676901 0.0116257138 0.0307244044 0.0074591614 0.3595410000 233007470 0 1783496704 -1.0337762833 0.0457727350 0.7710543275 178 7.0800000000 0.0124426363 0.0116303032 0.0307244044 0.0074443266 0.3539160000 233600483 0 1786777600 -1.0308696032 0.0461813174 0.7786495686 179 7.1200000000 0.0128614465 0.0116371811 0.0307244044 0.0074276261 0.2627010000 235178013 0 1782857728 -1.0321413279 0.0481164828 0.7908994555 180 7.1600000000 0.0114973523 0.0116364043 0.0307244044 0.0074080416 0.2439360000 235134835 0 1781972992 -1.0294899940 0.0497386158 0.8005145788 181 7.2000000000 0.0127930520 0.0116427946 0.0307244044 0.0073980012 0.3654140000 235105112 0 1781592064 -1.0299737453 0.0495098419 0.8180773854 182 7.2400000000 0.0113149714 0.0116409934 0.0307244044 0.0073776701 0.2030270000 233011604 0 1781317632 -1.0290685892 0.0496954471 0.8284123540 183 7.2800000000 0.0130922180 0.0116489236 0.0307244044 0.0073638172 0.1660880000 233011814 0 1783353344 -1.0312166214 0.0524345115 0.8444218636 184 7.3200000000 0.0124792298 0.0116534361 0.0307244044 0.0073453844 0.1655490000 233013456 0 1785004032 -1.0272145271 0.0527987927 0.8549700975 185 7.3600000000 0.0098630711 0.0116437585 0.0307244044 0.0073505202 0.1615760000 233015114 0 1786634240 -1.0277042389 0.0441500284 0.8677571416 186 7.4000000000 0.0121098263 0.0116462642 0.0307244044 0.0073458992 0.1831790000 233356140 0 1783091200 -1.0272033215 0.0511764809 0.8877157569 187 7.4400000000 0.0130571639 0.0116538091 0.0307244044 0.0073378985 0.3944900000 233382254 0 1779666944 -1.0251895189 0.0511636883 0.8999234438 188 7.4800000000 0.0133597432 0.0116628832 0.0307244044 0.0073428149 0.3443230000 233384444 0 1782022144 -1.0219240189 0.0559104085 0.9161710143 189 7.5200000000 0.0100086927 0.0116541309 0.0307244044 0.0073264062 0.3336640000 233897781 0 1783742464 -1.0186035633 0.0556774735 0.9305822849 190 7.5600000000 0.0125671560 0.0116589363 0.0307244044 0.0073169360 0.2507250000 235848147 0 1783394304 -1.0178620815 0.0566809103 0.9443087578 191 7.6000000000 0.0121618286 0.0116615692 0.0307244044 0.0073104840 0.2294920000 235713288 0 1782423552 -1.0144550800 0.0577382445 0.9548385143 192 7.6400000000 0.0162779111 0.0116856127 0.0307244044 0.0073050430 0.4083090000 235616906 0 1776427008 -1.0179532766 0.0638501197 0.9798966646 193 7.6800000000 0.0159907453 0.0117079191 0.0307244044 0.0073007422 0.1759660000 233391086 0 1776533504 -1.0175731182 0.0640042648 0.9988695979 194 7.7200000000 0.0165221393 0.0117327346 0.0307244044 0.0073008454 0.1652940000 233393948 0 1777913856 -1.0193188190 0.0575351790 1.0155712366 195 7.7600000000 0.0178244375 0.0117639741 0.0307244044 0.0073087389 0.1863440000 233705866 0 1780064256 -1.0166602135 0.0622003004 1.0300992727 196 7.8000000000 0.0165650602 0.0117884695 0.0307244044 0.0073536003 0.3602750000 233732408 0 1782054912 -1.0169496536 0.0608238578 1.0423800945 197 7.8400000000 0.0153826913 0.0118067143 0.0307244044 0.0073816620 0.3102610000 233735210 0 1784086528 -1.0133683681 0.0652295798 1.0557700396 198 7.8800000000 0.0146935396 0.0118212942 0.0307244044 0.0073983136 0.2996700000 234155819 0 1785991168 -1.0110232830 0.0704665780 1.0680025816 199 7.9200000000 0.0160075966 0.0118423309 0.0307244044 0.0073880901 0.2557470000 236355845 0 1784463360 -1.0110700130 0.0699782893 1.0871962309 200 7.9600000000 0.0158784501 0.0118625115 0.0307244044 0.0073756048 0.2519370000 236286980 0 1783377920 -1.0109349489 0.0681158826 1.1012754440 201 8.0000000000 0.0174664240 0.0118903916 0.0307244044 0.0073835860 0.1784920000 236242577 0 1785458688 -1.0117502213 0.0688230768 1.1209931374 202 8.0400000000 0.0173856243 0.0119175958 0.0307244044 0.0074086015 0.3221270000 236169330 0 1781501952 -1.0055339336 0.0731181502 1.1358653307 203 8.0800000000 0.0142561262 0.0119291156 0.0307244044 0.0074300982 0.2033300000 234034078 0 1781280768 -1.0012335777 0.0751710609 1.1474487782 204 8.1200000000 0.0183290057 0.0119604876 0.0307244044 0.0074357170 0.3136550000 234057288 0 1783242752 -0.9958930612 0.0823440477 1.1582980156 205 8.1600000000 0.0172874276 0.0119864727 0.0307244044 0.0074468595 0.2855340000 234059506 0 1785241600 -0.9989756942 0.0729309693 1.1768825054 206 8.1999999990 0.0174934603 0.0120132056 0.0307244044 0.0074384193 0.2836410000 234925263 0 1784512512 -0.9972259998 0.0695405528 1.1910331249 207 8.2400000000 0.0184234362 0.0120441729 0.0307244044 0.0074500201 0.2125950000 236822481 0 1783877632 -0.9888806939 0.0803972259 1.2043082714 208 8.2799999990 0.0189975072 0.0120776024 0.0307244044 0.0074416112 0.2377940000 236657874 0 1783750656 -0.9866852760 0.0778641105 1.2207798958 209 8.3200000000 0.0161053166 0.0120968738 0.0307244044 0.0074327562 0.1750100000 236706509 0 1785851904 -0.9808490276 0.0821220130 1.2259349823 210 8.3599999990 0.0166002903 0.0121183186 0.0307244044 0.0074824146 0.3147240000 236630802 0 1781694464 -0.9771014452 0.0783407837 1.2409965992 211 8.4000000000 0.0205381811 0.0121582232 0.0307244044 0.0075202727 0.2162000000 234355134 0 1780891648 -0.9701167345 0.0812690184 1.2604784966 212 8.4399999990 0.0202948041 0.0121966033 0.0307244044 0.0075138544 0.3370460000 234421856 0 1781444608 -0.9666160345 0.0803860649 1.2703132629 213 8.4800000000 0.0215765946 0.0122406408 0.0307244044 0.0075145790 0.3164820000 234420334 0 1783373824 -0.9582036138 0.0860351250 1.2879788876 214 8.5200000000 0.0213221312 0.0122830777 0.0307244044 0.0075716615 0.3143730000 235404991 0 1786429440 -0.9508531094 0.0859819651 1.3003066778 215 8.5600000000 0.0234997068 0.0123352481 0.0307244044 0.0075857623 0.2228990000 237390961 0 1784131584 -0.9418517351 0.0896334052 1.3118765354 216 8.6000000000 0.0203449726 0.0123723301 0.0307244044 0.0075746321 0.2512610000 237251763 0 1782353920 -0.9340751767 0.0885782689 1.3213189840 217 8.6400000000 0.0209646262 0.0124119259 0.0307244044 0.0076029133 0.1859160000 237209345 0 1784573952 -0.9267282486 0.0916772634 1.3372755051 218 8.6800000000 0.0182926953 0.0124389020 0.0307244044 0.0076292063 0.3614890000 237193386 0 1782120448 -0.9154515266 0.0915370733 1.3452336788 219 8.7200000000 0.0173086002 0.0124611380 0.0307244044 0.0076273458 0.2127780000 234439930 0 1781886976 -0.9066134095 0.0938440561 1.3524043560 220 8.7600000000 0.0217964649 0.0125035713 0.0307244044 0.0076386057 0.1821770000 234755224 0 1784184832 -0.8975343704 0.0998311490 1.3695108891 221 8.8000000000 0.0239655674 0.0125554356 0.0307244044 0.0076745354 0.3706240000 234799286 0 1784369152 -0.8869722486 0.1011781543 1.3853850365 222 8.8400000000 0.0241553262 0.0126076873 0.0307244044 0.0076872838 0.3408100000 234802884 0 1785720832 -0.8806169033 0.0978337228 1.3992735147 223 8.8800000000 0.0214596204 0.0126473821 0.0307244044 0.0076842020 0.3471990000 235470121 0 1786089472 -0.8688048124 0.1047186032 1.4044646025 224 8.9200000000 0.0227177329 0.0126923390 0.0307244044 0.0076904263 0.2880310000 237977867 0 1784934400 -0.8570553660 0.1085962132 1.4178775549 225 8.9600000000 0.0228405371 0.0127374421 0.0307244044 0.0076900748 0.2887610000 237905268 0 1783914496 -0.8484864235 0.1072123349 1.4258122444 226 9.0000000000 0.0188784227 0.0127646146 0.0307244044 0.0076775133 0.1949260000 237865056 0 1785720832 -0.8360767365 0.1146465540 1.4313300848 227 9.0400000000 0.0204055030 0.0127982749 0.0307244044 0.0076636402 0.4084620000 237728974 0 1779990528 -0.8217912912 0.1205052808 1.4450402260 228 9.0800000000 0.0203029625 0.0128311902 0.0307244044 0.0076714959 0.1791860000 234813152 0 1780043776 -0.8109620810 0.1251256466 1.4585636854 229 9.1200000000 0.0244584419 0.0128819642 0.0307244044 0.0077398599 0.1685200000 234815382 0 1781878784 -0.8001979589 0.1292012334 1.4717224836 230 9.1600000000 0.0217614733 0.0129205708 0.0307244044 0.0078236069 0.1705430000 234818760 0 1784037376 -0.7879785299 0.1350270808 1.4753292799 231 9.2000000000 0.0242872909 0.0129697774 0.0307244044 0.0080185790 0.1639750000 234821286 0 1785839616 -0.7782436609 0.1373786330 1.4856280088 232 9.2400000000 0.0188599918 0.0129951662 0.0307244044 0.0081536977 0.1847910000 235182556 0 1784565760 -0.7707087398 0.1367050707 1.4868988991 233 9.2800000000 0.0177778043 0.0130156926 0.0307244044 0.0082783493 0.3930610000 235225826 0 1785298944 -0.7611970901 0.1384282708 1.4929146767 234 9.3200000000 0.0181191880 0.0130375024 0.0307244044 0.0083791668 0.3727560000 235223456 0 1786650624 -0.7514978051 0.1422694176 1.5000321865 235 9.3600000000 0.0195198003 0.0130650866 0.0307244044 0.0084518354 0.3520920000 235369126 0 1783382016 -0.7400861979 0.1473884881 1.5098724365 236 9.4000000000 0.0194314960 0.0130920629 0.0307244044 0.0085068703 0.3665850000 237905899 0 1784041472 -0.7302592993 0.1509844810 1.5181159973 237 9.4400000000 0.0198170971 0.0131204386 0.0307244044 0.0085340345 0.2239690000 238858134 0 1784733696 -0.7199280858 0.1555595845 1.5251175165 238 9.4800000000 0.0186871886 0.0131438283 0.0307244044 0.0085457278 0.2452890000 238508787 0 1786015744 -0.7088360786 0.1607245356 1.5320219994 239 9.5200000000 0.0198016800 0.0131716854 0.0307244044 0.0085871728 0.1874160000 238516045 0 1785266176 -0.6972144842 0.1671504229 1.5410144329 240 9.5600000000 0.0208091494 0.0132035082 0.0307244044 0.0086367341 0.4100090000 238444066 0 1778704384 -0.6854028702 0.1757763028 1.5494188070 241 9.6000000000 0.0221761204 0.0132407389 0.0307244044 0.0086900420 0.1952960000 235236378 0 1779048448 -0.6745558977 0.1782958508 1.5593439341 242 9.6400000000 0.0202124845 0.0132695478 0.0307244044 0.0087062352 0.1702370000 235239484 0 1780662272 -0.6664351821 0.1781885028 1.5665246248 243 9.6800000000 0.0174196474 0.0132866264 0.0307244044 0.0087182383 0.1914950000 235586174 0 1782190080 -0.6575565338 0.1826829463 1.5697766542 244 9.7200000000 0.0180137362 0.0133059998 0.0307244044 0.0087605627 0.4077650000 235603040 0 1784356864 -0.6441579461 0.1908073127 1.5790704489 245 9.7600000000 0.0179862063 0.0133251027 0.0307244044 0.0088226258 0.3435900000 235598242 0 1785753600 -0.6360343695 0.1920033544 1.5864673853 246 9.8000000000 0.0178999156 0.0133436995 0.0307244044 0.0088369727 0.3400040000 235616012 0 1784262656 -0.6233692169 0.1958148330 1.5963950157 247 9.8400000000 0.0171988867 0.0133593075 0.0307244044 0.0088431020 0.3544260000 239272121 0 1784205312 -0.6162727475 0.1947277188 1.6044611931 248 9.8800000000 0.0178641696 0.0133774723 0.0307244044 0.0088284416 0.2732880000 239236156 0 1783373824 -0.6053363085 0.1982168555 1.6139370203 249 9.9200000000 0.0176274218 0.0133945404 0.0307244044 0.0088126411 0.2440290000 239290670 0 1785778176 -0.5967276692 0.1992574632 1.6212158203 250 9.9600000000 0.0187646411 0.0134160208 0.0307244044 0.0087996868 0.1847950000 239118267 0 1783967744 -0.5833001137 0.2026791573 1.6335309744 251 10.0000000000 0.0205454361 0.0134444248 0.0307244044 0.0087832597 0.3995800000 239044308 0 1777491968 -0.5732266307 0.2082929909 1.6425944567 252 10.0400000000 0.0249727182 0.0134901720 0.0307244044 0.0087719875 0.2580670000 235974064 0 1777319936 -0.5654803514 0.2098606825 1.6568797827 253 10.0800000000 0.0253860839 0.0135371914 0.0307244044 0.0087550053 0.3978580000 235982470 0 1778139136 -0.5579918027 0.2065431923 1.6675086021 254 10.1200000000 0.0244087521 0.0135799929 0.0307244044 0.0087749806 0.3448010000 235984940 0 1780264960 -0.5484939218 0.2094464600 1.6757620573 255 10.1600000000 0.0241706651 0.0136215249 0.0307244044 0.0087852813 0.3357170000 237076209 0 1783431168 -0.5380061865 0.2169923335 1.6836001873 256 10.2000000000 0.0242040902 0.0136628630 0.0307244044 0.0087723553 0.2998500000 239835363 0 1783963648 -0.5262348652 0.2207450420 1.6934547424 257 10.2400000000 0.0236121248 0.0137015761 0.0307244044 0.0087598441 0.3015750000 239763440 0 1783455744 -0.5192168951 0.2192870080 1.7012869120 258 10.2800000000 0.0232999623 0.0137387792 0.0307244044 0.0087440066 0.2231150000 240123604 0 1785282560 -0.5067880154 0.2255308479 1.7098515034 259 10.3200000000 0.0225853436 0.0137729358 0.0307244044 0.0087362607 0.1807570000 239718197 0 1786585088 -0.4973051548 0.2285880148 1.7155237198 260 10.3600000000 0.0275836978 0.0138260541 0.0307244044 0.0087563052 0.4247950000 239646750 0 1777147904 -0.4842387140 0.2317403555 1.7303833961 261 10.4000000000 0.0290829483 0.0138845096 0.0307244044 0.0087534048 0.2230880000 236016210 0 1777442816 -0.4727942348 0.2319266051 1.7390508652 262 10.4400000000 0.0277677085 0.0139374990 0.0307244044 0.0087433867 0.1665990000 236019304 0 1779093504 -0.4660440683 0.2306148559 1.7451784611 263 10.4800000000 0.0276484396 0.0139896318 0.0307244044 0.0087303429 0.1723100000 236022526 0 1780600832 -0.4552698731 0.2343784869 1.7491292953 264 10.5200000000 0.0283507835 0.0140440301 0.0307244044 0.0087173166 0.1761080000 236021308 0 1782251520 -0.4434246421 0.2339497507 1.7564895153 265 10.5600000000 0.0294481646 0.0141021589 0.0307244044 0.0087012965 0.1862060000 236022586 0 1784049664 -0.4317817390 0.2366396189 1.7636005878 266 10.6000000000 0.0272956491 0.0141517585 0.0307244044 0.0086885013 0.1664560000 236022660 0 1785679872 -0.4198863506 0.2364862263 1.7670814991 267 10.6400000000 0.0281485431 0.0142041809 0.0307244044 0.0086844334 0.1735650000 236027806 0 1784188928 -0.4084436893 0.2353384644 1.7723884583 268 10.6800000000 0.0279309358 0.0142554002 0.0307244044 0.0086766140 0.1750150000 236030476 0 1783320576 -0.3977705240 0.2345755547 1.7783274651 269 10.7200000000 0.0272522494 0.0143037156 0.0307244044 0.0086653831 0.1695500000 236030466 0 1781776384 -0.3873601556 0.2347967029 1.7792614698 270 10.7600000000 0.0244128816 0.0143411569 0.0307244044 0.0086535262 0.1668780000 236033880 0 1783033856 -0.3623686433 0.2381276488 1.7871558666 271 10.8000000000 0.0245652515 0.0143788842 0.0307244044 0.0086690162 0.1924210000 236417094 0 1784537088 -0.3486560881 0.2433871031 1.7893487215 272 10.8400000000 0.0266508460 0.0144240017 0.0307244044 0.0087267748 0.4157800000 236422572 0 1784184832 -0.3352200389 0.2422281802 1.7957006693 273 10.8800000000 0.0265097171 0.0144682717 0.0307244044 0.0087333748 0.3981990000 236422302 0 1786204160 -0.3230135441 0.2422475815 1.8004820347 274 10.9200000000 0.0247886889 0.0145059375 0.0307244044 0.0087378337 0.3594760000 237694095 0 1786761216 -0.3098896742 0.2434511334 1.8019092083 275 10.9600000000 0.0277636107 0.0145541472 0.0307244044 0.0087450643 0.2931360000 240351893 0 1782779904 -0.2964538634 0.2452240437 1.8073780537 276 11.0000000000 0.0252190698 0.0145927882 0.0307244044 0.0087410195 0.3316460000 240323628 0 1781825536 -0.2839324474 0.2440282702 1.8099098206 277 11.0400000000 0.0275137667 0.0146394344 0.0307244044 0.0087467259 0.2124200000 240404354 0 1783582720 -0.2698570192 0.2486486286 1.8141441345 278 11.0800000000 0.0327416845 0.0147045504 0.0327416845 0.0087631110 0.4760400000 240051666 0 1781796864 -0.2560673356 0.2503328919 1.8242146969 279 11.1200000000 0.0293396506 0.0147570059 0.0327416845 0.0087674175 0.2015580000 236430778 0 1781829632 -0.2436364293 0.2496691644 1.8252151012 280 11.1600000000 0.0294641238 0.0148095314 0.0327416845 0.0087740420 0.1747410000 236431880 0 1783119872 -0.2301211357 0.2505889535 1.8293386698 281 11.2000000000 0.0294817593 0.0148617457 0.0327416845 0.0087782185 0.1720810000 236433982 0 1785114624 -0.2166766226 0.2522419989 1.8317021132 282 11.2400000000 0.0306403469 0.0149176982 0.0327416845 0.0087739465 0.1713650000 236435192 0 1784258560 -0.2035998404 0.2535397410 1.8368023634 283 11.2800000000 0.0299015306 0.0149706446 0.0327416845 0.0087592575 0.1708350000 236436854 0 1783115776 -0.1921375692 0.2538573146 1.8388009071 284 11.3200000000 0.0283638183 0.0150178037 0.0327416845 0.0087490497 0.1744340000 236435132 0 1782226944 -0.1816920638 0.2536422908 1.8430159092 285 11.3600000000 0.0307237860 0.0150729124 0.0327416845 0.0087456671 0.1704780000 236440098 0 1783504896 -0.1671007574 0.2558613420 1.8503412008 286 11.4000000000 0.0297432989 0.0151242074 0.0327416845 0.0087375056 0.1658010000 236441292 0 1785262080 -0.1572193205 0.2565364242 1.8526957035 287 11.4400000000 0.0307438970 0.0151786314 0.0327416845 0.0087225191 0.1953140000 236825454 0 1784004608 -0.1472557187 0.2550014257 1.8586959839 288 11.4800000000 0.0283317138 0.0152243018 0.0327416845 0.0087084542 0.4058980000 236809184 0 1778900992 -0.1402313709 0.2555171847 1.8590013981 289 11.5200000000 0.0293705259 0.0152732507 0.0327416845 0.0086946039 0.3598050000 236950182 0 1780305920 -0.1311479509 0.2556228638 1.8667979240 290 11.5600000000 0.0277190637 0.0153161673 0.0327416845 0.0086874447 0.3599740000 238351647 0 1786634240 -0.1224208176 0.2547820508 1.8715629578 291 11.6000000000 0.0263409484 0.0153540532 0.0327416845 0.0086764921 0.2602230000 240959521 0 1784168448 -0.1149277687 0.2548732162 1.8763513565 292 11.6400000000 0.0260792486 0.0153907833 0.0327416845 0.0086640885 0.3345470000 240886230 0 1783099392 -0.1072009802 0.2557493150 1.8817828894 293 11.6800000000 0.0261785295 0.0154276015 0.0327416845 0.0086493480 0.2078050000 241096110 0 1785167872 -0.1010427773 0.2570751905 1.8877358437 294 11.7200000000 0.0273050312 0.0154680010 0.0327416845 0.0086404962 0.4605470000 240704728 0 1777696768 -0.0916608274 0.2581742406 1.8962148428 295 11.7600000000 0.0287346747 0.0155129727 0.0327416845 0.0086308296 0.2254340000 236798978 0 1777983488 -0.0848263204 0.2594761848 1.9042958021 296 11.8000000000 0.0283448342 0.0155563236 0.0327416845 0.0086219069 0.1611370000 236799564 0 1779671040 -0.0789377987 0.2590123415 1.9108448029 297 11.8400000000 0.0277770627 0.0155974709 0.0327416845 0.0086116115 0.1652730000 236801470 0 1781149696 -0.0748139918 0.2586932778 1.9174082279 298 11.8800000000 0.0273739398 0.0156369892 0.0327416845 0.0086045994 0.1857950000 237164664 0 1783054336 -0.0697725713 0.2575729787 1.9252965450 299 11.9200000000 0.0283586308 0.0156795365 0.0327416845 0.0085941969 0.3912470000 237147214 0 1784958976 -0.0641715527 0.2570086718 1.9353046417 300 11.9600000000 0.0274605434 0.0157188066 0.0327416845 0.0085812482 0.3377000000 237149048 0 1786609664 -0.0595166385 0.2570796311 1.9429873228 301 12.0000000000 0.0272922348 0.0157572565 0.0327416845 0.0085673039 0.3312870000 238378489 0 1785536512 -0.0545313954 0.2581197321 1.9515217543 302 12.0400000000 0.0272289217 0.0157952421 0.0327416845 0.0085562712 0.3008120000 240803759 0 1783386112 -0.0503205359 0.2567132413 1.9622700214 303 12.0800000000 0.0276185703 0.0158342630 0.0327416845 0.0085485548 0.3460610000 240732432 0 1782427648 -0.0464232266 0.2588922679 1.9713411331 304 12.1200000000 0.0249813385 0.0158643521 0.0327416845 0.0085493486 0.2140650000 240573183 0 1784102912 -0.0455610752 0.2571043372 1.9788682461 305 12.1600000000 0.0269384943 0.0159006607 0.0327416845 0.0085511579 0.4446050000 240570328 0 1783418880 -0.0380068421 0.2598594427 1.9916161299 306 12.2000000000 0.0287388228 0.0159426155 0.0327416845 0.0085416912 0.2326540000 237158816 0 1783836672 -0.0332425833 0.2607431710 2.0049059391 307 12.2400000000 0.0290448721 0.0159852939 0.0327416845 0.0085398107 0.1707580000 237161150 0 1785724928 -0.0305758715 0.2616209984 2.0166363716 308 12.2800000000 0.0288444906 0.0160270445 0.0327416845 0.0085440773 0.1720200000 237162880 0 1786888192 -0.0270101726 0.2605256438 2.0291521549 309 12.3200000000 0.0259385519 0.0160591206 0.0327416845 0.0085573019 0.1681240000 237161714 0 1783955456 -0.0264831483 0.2589283586 2.0371756554 310 12.3600000000 0.0271156989 0.0160947870 0.0327416845 0.0085710693 0.1680300000 237165592 0 1783177216 -0.0238336325 0.2585975528 2.0505876541 311 12.4000000000 0.0268439893 0.0161293503 0.0327416845 0.0085883954 0.1689100000 237167126 0 1785090048 -0.0203865469 0.2588855326 2.0615158081 312 12.4400000000 0.0298249349 0.0161732464 0.0327416845 0.0086187570 0.1960570000 237543724 0 1784475648 -0.0163613260 0.2603362501 2.0879378319 313 12.4800000000 0.0284001864 0.0162123101 0.0327416845 0.0086106822 0.3963690000 237531634 0 1779634176 -0.0167006850 0.2598737180 2.0971069336 314 12.5200000000 0.0286862198 0.0162520360 0.0327416845 0.0086016614 0.3590330000 237532216 0 1781084160 -0.0168440640 0.2590669394 2.1098210812 315 12.5600000000 0.0295548607 0.0162942671 0.0327416845 0.0086002072 0.3550100000 238646037 0 1784631296 -0.0157071352 0.2604542673 2.1213877201 316 12.6000000000 0.0290461704 0.0163346213 0.0327416845 0.0085890870 0.3009670000 240933847 0 1783828480 -0.0161510706 0.2606109977 2.1330888271 317 12.6400000000 0.0280121863 0.0163714590 0.0327416845 0.0085758460 0.3011490000 240878050 0 1783406592 -0.0192762613 0.2600184381 2.1430225372 318 12.6800000000 0.0269823410 0.0164048266 0.0327416845 0.0085625625 0.2085490000 240780655 0 1785081856 -0.0188878775 0.2590280771 2.1537497044 319 12.7200000000 0.0269325599 0.0164378289 0.0327416845 0.0085508176 0.4236660000 240708008 0 1781186560 -0.0209233761 0.2570153773 2.1653535366 320 12.7600000000 0.0276444387 0.0164728495 0.0327416845 0.0085379280 0.2454490000 237909100 0 1779146752 -0.0212003589 0.2583201826 2.1758666039 321 12.8000000000 0.0278874766 0.0165084091 0.0327416845 0.0085273539 0.3930530000 237912574 0 1780690944 -0.0239489675 0.2578980625 2.1861808300 322 12.8400000000 0.0278552305 0.0165436477 0.0327416845 0.0085170124 0.3368150000 237911108 0 1782468608 -0.0251376331 0.2590865195 2.1948561668 323 12.8800000000 0.0283542387 0.0165802130 0.0327416845 0.0085061801 0.3401350000 237928066 0 1784397824 -0.0265559852 0.2574242055 2.2046582699 324 12.9200000000 0.0287503488 0.0166177751 0.0327416845 0.0084937028 0.3518840000 241632103 0 1785524224 -0.0278982222 0.2571832836 2.2140624523 325 12.9600000000 0.0279549994 0.0166526589 0.0327416845 0.0084808637 0.2712820000 241701615 0 1782349824 -0.0301770121 0.2581912577 2.2218732834 326 13.0000000000 0.0284364782 0.0166888056 0.0327416845 0.0084687060 0.2400440000 241673419 0 1784385536 -0.0313497186 0.2585109174 2.2292301655 327 13.0400000000 0.0280336775 0.0167234994 0.0327416845 0.0084567313 0.1818880000 241576893 0 1786163200 -0.0336822271 0.2572805285 2.2396595478 328 13.0800000000 0.0309095234 0.0167667495 0.0327416845 0.0084454841 0.4192560000 241503082 0 1782120448 -0.0325675011 0.2617684305 2.2483336926 329 13.1200000000 0.0308525860 0.0168095635 0.0327416845 0.0084328293 0.2399730000 238385186 0 1776726016 -0.0334759615 0.2625227273 2.2573230267 330 13.1600000000 0.0311170630 0.0168529196 0.0327416845 0.0084214116 0.4342920000 238356364 0 1779507200 -0.0352789909 0.2630504668 2.2653868198 331 13.2000000000 0.0321598127 0.0168991640 0.0327416845 0.0084093574 0.3813240000 238363494 0 1781657600 -0.0365419462 0.2647120655 2.2756593227 332 13.2400000000 0.0313609727 0.0169427237 0.0327416845 0.0083981978 0.3628090000 238491740 0 1783488512 -0.0393635109 0.2651809454 2.2831060886 333 13.2800000000 0.0305792056 0.0169836741 0.0327416845 0.0083872238 0.3668940000 240408665 0 1786212352 -0.0425617397 0.2644868195 2.2922561169 334 13.3200000000 0.0312897302 0.0170265066 0.0327416845 0.0083757374 0.2306530000 242863427 0 1784434688 -0.0434779972 0.2653799355 2.3003993034 335 13.3600000000 0.0302990377 0.0170661261 0.0327416845 0.0083640467 0.3148490000 242794034 0 1783193600 -0.0455577224 0.2649705708 2.3089509010 336 13.4000000000 0.0302768145 0.0171054436 0.0327416845 0.0083517231 0.1996250000 243105648 0 1785802752 -0.0470185429 0.2667807341 2.3168609142 337 13.4400000000 0.0307109393 0.0171458160 0.0327416845 0.0083499173 0.1654460000 242678633 0 1784745984 -0.0483974367 0.2696786821 2.3245346546 338 13.4800000000 0.0316190906 0.0171886363 0.0327416845 0.0083532664 0.4231610000 242601518 0 1773146112 -0.0505788326 0.2699259520 2.3328192234 339 13.5200000000 0.0308132339 0.0172288269 0.0327416845 0.0083659140 0.2087510000 238797738 0 1775259648 -0.0524983406 0.2698422372 2.3374216557 340 13.5600000000 0.0316567384 0.0172712619 0.0327416845 0.0083599353 0.3997130000 238786868 0 1777045504 -0.0546776056 0.2705405951 2.3432314396 341 13.6000000000 0.0305622201 0.0173102383 0.0327416845 0.0083520273 0.3466130000 238785874 0 1778384896 -0.0568273664 0.2699675560 2.3473176956 342 13.6400000000 0.0308013335 0.0173496860 0.0327416845 0.0083442351 0.3350860000 240129663 0 1780568064 -0.0587389469 0.2711989880 2.3526935577 343 13.6800000000 0.0309002902 0.0173891921 0.0327416845 0.0083325818 0.3566150000 242687237 0 1782546432 -0.0610046983 0.2712219954 2.3577587605 344 13.7200000000 0.0310647748 0.0174289467 0.0327416845 0.0083206036 0.1951810000 244106616 0 1782743040 -0.0620277226 0.2723503411 2.3637559414 345 13.7600000000 0.0308557563 0.0174678650 0.0327416845 0.0083121287 0.2932410000 243549572 0 1784897536 -0.0633607507 0.2720710635 2.3690371513 346 13.8000000000 0.0312216487 0.0175076158 0.0327416845 0.0083058417 0.1827430000 243725996 0 1786802176 -0.0649259686 0.2729580402 2.3738646507 347 13.8400000000 0.0310750939 0.0175467152 0.0327416845 0.0082951431 0.1728950000 243450397 0 1783611392 -0.0666034222 0.2718416750 2.3779942989 348 13.8800000000 0.0305603128 0.0175841106 0.0327416845 0.0082835013 0.3950490000 243373486 0 1781796864 -0.0666474104 0.2729238272 2.3838369846 349 13.9200000000 0.0303841121 0.0176207868 0.0327416845 0.0082804904 0.2691290000 239229682 0 1778323456 -0.0685239434 0.2719733119 2.3898029327 350 13.9600000000 0.0303635225 0.0176571946 0.0327416845 0.0082707165 0.3744290000 239203508 0 1775206400 -0.0708786249 0.2699116468 2.3989608288 351 14.0000000000 0.0305511411 0.0176939295 0.0327416845 0.0082592789 0.3232670000 239207942 0 1777233920 -0.0707262754 0.2709912360 2.4031603336 352 14.0400000000 0.0302354749 0.0177295589 0.0327416845 0.0082500298 0.3329330000 240641619 0 1779044352 -0.0711141825 0.2709573209 2.4072260857 353 14.0800000000 0.0304216538 0.0177655138 0.0327416845 0.0082383867 0.3375020000 241738607 0 1785831424 -0.0710227489 0.2698777914 2.4117617607 354 14.1200000000 0.0296756197 0.0177991582 0.0327416845 0.0082275410 0.2225780000 245185251 0 1784049664 -0.0719520450 0.2694798708 2.4163150787 355 14.1600000000 0.0294510107 0.0178319803 0.0327416845 0.0082161863 0.3298200000 244474626 0 1783205888 -0.0723199844 0.2675302327 2.4210839272 356 14.2000000000 0.0304796491 0.0178675075 0.0327416845 0.0082072147 0.1998480000 245196435 0 1785290752 -0.0713911653 0.2688044012 2.4260981083 357 14.2400000000 0.0307277180 0.0179035305 0.0327416845 0.0081958687 0.1682570000 244369237 0 1784250368 -0.0710723996 0.2692055106 2.4320406914 358 14.2800000000 0.0245607216 0.0179221260 0.0327416845 0.0081984940 0.4469490000 244290566 0 1777410048 -0.0741864443 0.2603129447 2.4341611862 359 14.3200000000 0.0243869014 0.0179401337 0.0327416845 0.0081897722 0.2084940000 239218134 0 1773916160 -0.0736584067 0.2592752278 2.4391961098 360 14.3600000000 0.0250219833 0.0179598055 0.0327416845 0.0081805877 0.1598830000 239219776 0 1773613056 -0.0743770599 0.2582803369 2.4459180832 361 14.4000000000 0.0241916571 0.0179770683 0.0327416845 0.0081754184 0.1528440000 239220830 0 1775788032 -0.0742642879 0.2577794194 2.4516186714 362 14.4400000000 0.0244137365 0.0179948491 0.0327416845 0.0081691259 0.1520240000 239223044 0 1777455104 -0.0736602545 0.2591240108 2.4579513073 363 14.4800000000 0.0250010453 0.0180141499 0.0327416845 0.0081584992 0.1526860000 239224238 0 1778728960 -0.0730692744 0.2604479790 2.4655675888 364 14.5200000000 0.0250669643 0.0180335258 0.0327416845 0.0081482920 0.1494940000 239223744 0 1780867072 -0.0737959146 0.2593016028 2.4730799198 365 14.5600000000 0.0254499335 0.0180538447 0.0327416845 0.0081378910 0.1494920000 239228350 0 1782394880 -0.0741913319 0.2585361302 2.4804987907 366 14.6000000000 0.0250854138 0.0180730567 0.0327416845 0.0081278889 0.1495500000 239229404 0 1784422400 -0.0738282204 0.2607054412 2.4873559475 367 14.6400000000 0.0243243910 0.0180900903 0.0327416845 0.0081170439 0.1504280000 239229454 0 1785692160 -0.0736665726 0.2613016367 2.4939491749 368 14.6800000000 0.0252896845 0.0181096544 0.0327416845 0.0081099823 0.1784020000 239661416 0 1785221120 -0.0751351118 0.2608516812 2.5031437874 369 14.7200000000 0.0250708368 0.0181285194 0.0327416845 0.0081073680 0.3682610000 239617758 0 1786732544 -0.0757893324 0.2604228258 2.5103933811 370 14.7600000000 0.0251097903 0.0181473877 0.0327416845 0.0081029988 0.2969990000 239621476 0 1783324672 -0.0760166049 0.2610462308 2.5182392597 371 14.8000000000 0.0249605458 0.0181657520 0.0327416845 0.0080962298 0.3019350000 239645006 0 1785253888 -0.0759712458 0.2609187067 2.5252602100 372 14.8400000000 0.0254064184 0.0181852161 0.0327416845 0.0080934669 0.3190300000 242303773 0 1783074816 -0.0759582520 0.2603079081 2.5328183174 373 14.8800000000 0.0258937702 0.0182058825 0.0327416845 0.0080902326 0.2228910000 244694358 0 1782394880 -0.0757168531 0.2603076398 2.5405735970 374 14.9200000000 0.0255330894 0.0182254740 0.0327416845 0.0080839957 0.2912190000 244528518 0 1781178368 -0.0764461756 0.2593215704 2.5476620197 375 14.9600000000 0.0258127786 0.0182457068 0.0327416845 0.0080890240 0.1964340000 244816344 0 1783107584 -0.0755794644 0.2589599192 2.5548849106 376 15.0000000000 0.0253332630 0.0182645567 0.0327416845 0.0080901726 0.4361710000 244232388 0 1784885248 -0.0777313113 0.2594447434 2.5620663166 377 15.0400000000 0.0246772598 0.0182815665 0.0327416845 0.0080809905 0.1935290000 239630706 0 1781501952 -0.0753617883 0.2609620690 2.5743436813 378 15.0800000000 0.0250604283 0.0182995000 0.0327416845 0.0080709045 0.1526740000 239632560 0 1781719040 -0.0737615824 0.2621047199 2.5812592506 379 15.1200000000 0.0248548519 0.0183167964 0.0327416845 0.0080602990 0.1479470000 239633826 0 1783738368 -0.0715165734 0.2621991634 2.5868940353 380 15.1600000000 0.0243401825 0.0183326474 0.0327416845 0.0080504481 0.1448500000 239634584 0 1785782272 -0.0687724948 0.2633844614 2.5916662216 381 15.2000000000 0.0244760234 0.0183487718 0.0327416845 0.0080402343 0.1506940000 239638294 0 1784025088 -0.0667217374 0.2643183470 2.5968894958 382 15.2400000000 0.0246984214 0.0183653939 0.0327416845 0.0080311093 0.1492430000 239638216 0 1783111680 -0.0638938844 0.2649265230 2.6018886566 383 15.2800000000 0.0251764078 0.0183831772 0.0327416845 0.0080214038 0.1492200000 239638186 0 1782116352 -0.0607904494 0.2657475471 2.6070206165 384 15.3200000000 0.0252184011 0.0184009773 0.0327416845 0.0080115604 0.1839670000 240047092 0 1783885824 -0.0587010682 0.2665850222 2.6107842922 385 15.3600000000 0.0247640777 0.0184175048 0.0327416845 0.0080017348 0.3801470000 240010522 0 1780473856 -0.0562579930 0.2657336295 2.6130330563 386 15.4000000000 0.0250535812 0.0184346967 0.0327416845 0.0079982160 0.3373660000 240020480 0 1782386688 -0.0531296730 0.2666779459 2.6153919697 387 15.4400000000 0.0242583454 0.0184497449 0.0327416845 0.0079981459 0.3302160000 240042834 0 1784012800 -0.0496412218 0.2685181797 2.6167907715 388 15.4800000000 0.0243309028 0.0184649025 0.0327416845 0.0079887294 0.3433090000 242881383 0 1783013376 -0.0462578684 0.2694835067 2.6179552078 389 15.5200000000 0.0238264818 0.0184786855 0.0327416845 0.0079798213 0.2401650000 245997373 0 1783623680 -0.0436540246 0.2699853778 2.6182754040 390 15.5600000000 0.0239144359 0.0184926233 0.0327416845 0.0079697639 0.3057180000 245597232 0 1782788096 -0.0391184166 0.2736611068 2.6193904877 391 15.6000000000 0.0242035408 0.0185072293 0.0327416845 0.0079780312 0.2511300000 245906974 0 1784913920 -0.0356378369 0.2750117481 2.6206140518 392 15.6400000000 0.0235810708 0.0185201727 0.0327416845 0.0079700475 0.1867160000 245440479 0 1786286080 -0.0333094597 0.2730779946 2.6211609840 393 15.6800000000 0.0222424865 0.0185296443 0.0327416845 0.0079614869 0.4942540000 245366256 0 1777733632 -0.0299064070 0.2732310295 2.6196074486 394 15.7200000000 0.0225841720 0.0185399350 0.0327416845 0.0079561346 0.2745990000 240042276 0 1773473792 -0.0282378122 0.2704211771 2.6214540005 395 15.7600000000 0.0222253129 0.0185492650 0.0327416845 0.0079548648 0.1785680000 240043114 0 1774309376 -0.0246499479 0.2715384066 2.6212546825 396 15.8000000000 0.0221934170 0.0185584674 0.0327416845 0.0079514049 0.1740640000 240045380 0 1775960064 -0.0212153196 0.2707956731 2.6218824387 397 15.8400000000 0.0220120624 0.0185671667 0.0327416845 0.0079527096 0.1731700000 240049018 0 1777590272 -0.0186496377 0.2705024779 2.6215152740 398 15.8800000000 0.0219726972 0.0185757233 0.0327416845 0.0079466230 0.1982680000 240051204 0 1779515392 -0.0155006647 0.2681855857 2.6211526394 399 15.9200000000 0.0216971189 0.0185835463 0.0327416845 0.0079381244 0.1711220000 240051182 0 1781039104 -0.0110222101 0.2698404193 2.6193883419 400 15.9600000000 0.0224861186 0.0185933028 0.0327416845 0.0079307899 0.1737970000 240056036 0 1782927360 -0.0066912174 0.2702795565 2.6210191250 401 16.0000000000 0.0218464881 0.0186014154 0.0327416845 0.0079270374 0.1721540000 240056922 0 1784090624 -0.0025677085 0.2715250254 2.6205439568 402 16.0400000000 0.0222070254 0.0186103846 0.0327416845 0.0079181183 0.1999730000 240465536 0 1786228736 0.0035088062 0.2720222175 2.6212539673 403 16.0800000000 0.0221637040 0.0186192018 0.0327416845 0.0079123708 0.4213360000 240430710 0 1784213504 0.0087217093 0.2717388868 2.6227085590 404 16.1200000000 0.0220765993 0.0186277597 0.0327416845 0.0079036238 0.3511880000 240430608 0 1786302464 0.0128644705 0.2728254199 2.6214020252 405 16.1600000000 0.0220186878 0.0186361324 0.0327416845 0.0078945097 0.3689330000 240451446 0 1783988224 0.0186012387 0.2734520137 2.6227972507 406 16.2000000000 0.0218697507 0.0186440969 0.0327416845 0.0078867295 0.3765780000 244429695 0 1785102336 0.0235440731 0.2742463946 2.6257352829 407 16.2400000000 0.0219294410 0.0186521690 0.0327416845 0.0078782148 0.2367140000 245993006 0 1783750656 0.0293822289 0.2758408785 2.6274342537 408 16.2800000000 0.0216911621 0.0186596175 0.0327416845 0.0078799475 0.2871830000 245403972 0 1785737216 0.0341324806 0.2753511071 2.6305997372 409 16.3200000000 0.0221414920 0.0186681307 0.0327416845 0.0078806483 0.2106780000 245164417 0 1787158528 0.0409630537 0.2798345685 2.6332297325 410 16.3600000000 0.0227739196 0.0186781448 0.0327416845 0.0078710964 0.4756710000 245092114 0 1777811456 0.0468443036 0.2830909193 2.6382527351 411 16.3999999990 0.0234451573 0.0186897434 0.0327416845 0.0078646937 0.2514350000 240447886 0 1773412352 0.0522158146 0.2825385332 2.6402649879 412 16.4400000000 0.0223451350 0.0186986157 0.0327416845 0.0078799000 0.1738100000 240451020 0 1774419968 0.0544358492 0.2806662023 2.6461477280 413 16.4800000000 0.0222486872 0.0187072115 0.0327416845 0.0078948978 0.1755040000 240452414 0 1775800320 0.0615442991 0.2816064954 2.6530933380 414 16.5200000000 0.0223575309 0.0187160287 0.0327416845 0.0078920059 0.1736580000 240455172 0 1777401856 0.0638993979 0.2786095440 2.6569123268 415 16.5599999990 0.0217523221 0.0187233451 0.0327416845 0.0079018953 0.1722220000 240454534 0 1779073024 0.0677767992 0.2744285166 2.6611351967 416 16.6000000000 0.0221163742 0.0187315014 0.0327416845 0.0079851687 0.2044410000 240828300 0 1780977664 0.0732481480 0.2721319795 2.6681559086 417 16.6400000000 0.0225915145 0.0187407580 0.0327416845 0.0080166184 0.4086650000 240819922 0 1783050240 0.0829228163 0.2755115628 2.6697676182 418 16.6800000000 0.0224086270 0.0187495328 0.0327416845 0.0080206221 0.3744770000 240821468 0 1784770560 0.0833768845 0.2706981301 2.6695761681 419 16.7199999990 0.0212050565 0.0187553933 0.0327416845 0.0080484611 0.3505290000 240971938 0 1786687488 0.0891033411 0.2738955915 2.6735496521 420 16.7600000000 0.0231010281 0.0187657400 0.0327416845 0.0080393632 0.3580610000 243402883 0 1783218176 0.0989495516 0.2783454061 2.6750791073 421 16.8000000000 0.0226321984 0.0187749240 0.0327416845 0.0080496765 0.2586510000 245690210 0 1780699136 0.1028391123 0.2747344375 2.6750032902 422 16.8400000000 0.0222581662 0.0187831781 0.0327416845 0.0080481680 0.3090580000 245404294 0 1779552256 0.1132719517 0.2661021948 2.6776239872 423 16.8799999990 0.0213168338 0.0187891679 0.0327416845 0.0080447134 0.2058120000 245221269 0 1781657600 0.1205775738 0.2671501637 2.6753110886 424 16.9200000000 0.0255988520 0.0188052284 0.0327416845 0.0080362705 0.4569340000 245230726 0 1778716672 0.1293010712 0.2649758756 2.6777567863 425 16.9600000000 0.0257684626 0.0188216125 0.0327416845 0.0080351362 0.2194410000 241159810 0 1779662848 0.1367481947 0.2676185966 2.6742737293 426 17.0000000000 0.0280622356 0.0188433041 0.0327416845 0.0080278221 0.3857320000 241155076 0 1776377856 0.1463943720 0.2685747445 2.6755275726 427 17.0400000000 0.0259524975 0.0188599533 0.0327416845 0.0080236907 0.3502870000 241154858 0 1777983488 0.1517788172 0.2635809779 2.6693844795 428 17.0800000000 0.0278236438 0.0188808965 0.0327416845 0.0080159701 0.3723730000 242601275 0 1780027392 0.1619250774 0.2609914541 2.6687231064 429 17.1200000000 0.0259893965 0.0188974664 0.0327416845 0.0080097754 0.3569900000 245633101 0 1784561664 0.1710448265 0.2616102993 2.6640133858 430 17.1600000000 0.0283690561 0.0189194934 0.0327416845 0.0080091177 0.2046490000 246442668 0 1784410112 0.1811250448 0.2556920052 2.6612219810 431 17.2000000000 0.0246914160 0.0189328853 0.0327416845 0.0080033944 0.2804290000 245927541 0 1786327040 0.1882495880 0.2534854710 2.6522924900 432 17.2400000000 0.0265669730 0.0189505568 0.0327416845 0.0080011601 0.1935320000 245580027 0 1785270272 0.2038542032 0.2509422600 2.6501164436 433 17.2800000000 0.0360364988 0.0189900162 0.0360364988 0.0079965085 0.4077710000 245591296 0 1786134528 0.2206792831 0.2581538558 2.6483449936 434 17.3200000000 0.0312065575 0.0190181650 0.0360364988 0.0079885705 0.2274810000 241515584 0 1784365056 0.2265204191 0.2497785389 2.6379029751 435 17.3600000000 0.0321340673 0.0190483165 0.0360364988 0.0079975965 0.3988360000 241602450 0 1780199424 0.2409849167 0.2495256066 2.6328723431 436 17.4000000000 0.0304944646 0.0190745691 0.0360364988 0.0080016146 0.3996180000 241603504 0 1781850112 0.2548055649 0.2531157732 2.6244571209 437 17.4400000000 0.0314399190 0.0191028651 0.0360364988 0.0079993567 0.3789390000 241746302 0 1783373824 0.2750151157 0.2607005239 2.6141872406 438 17.4800000000 0.0303590763 0.0191285642 0.0360364988 0.0081040157 0.3837500000 244069487 0 1785233408 0.2858502865 0.2602921426 2.6072239876 439 17.5200000000 0.0267772097 0.0191459871 0.0360364988 0.0082329189 0.2735710000 246281553 0 1781665792 0.2884112597 0.2515704632 2.5953054428 440 17.5600000000 0.0296359174 0.0191698278 0.0360364988 0.0082603331 0.3165280000 246176814 0 1780711424 0.2990285158 0.2461389601 2.5871512890 441 17.6000000000 0.0331540965 0.0192015382 0.0360364988 0.0082534234 0.2157720000 246018745 0 1782349824 0.3074676991 0.2402857244 2.5832962990 442 17.6400000000 0.0306606386 0.0192274638 0.0360364988 0.0083162592 0.4974660000 245947078 0 1780555776 0.3222198486 0.2346683741 2.5754532814 443 17.6800000000 0.0289738327 0.0192494646 0.0360364988 0.0083365534 0.2352510000 241921254 0 1781817344 0.3437751532 0.2395009547 2.5565946102 444 17.7200000000 0.0290154647 0.0192714601 0.0360364988 0.0083314826 0.3601630000 241964592 0 1778118656 0.3532288671 0.2392152399 2.5456485748 445 17.7600000000 0.0315096490 0.0192989616 0.0360364988 0.0083297995 0.3414430000 241967898 0 1779171328 0.3655855060 0.2398208976 2.5377655029 446 17.8000000000 0.0290676914 0.0193208646 0.0360364988 0.0083225176 0.3339950000 242117868 0 1781342208 0.3743241429 0.2356822938 2.5289900303 447 17.8400000000 0.0299310461 0.0193446010 0.0360364988 0.0083204073 0.3220670000 244678453 0 1784602624 0.3828402162 0.2366466820 2.5194439888 448 17.8800000000 0.0307538230 0.0193700681 0.0360364988 0.0083133558 0.2074900000 246162368 0 1784266752 0.3914964199 0.2315912247 2.5151493549 449 17.9200000000 0.0296146646 0.0193928845 0.0360364988 0.0083048051 0.2176730000 245697205 0 1783377920 0.3981806040 0.2304272205 2.5053977966 450 17.9600000000 0.0296586305 0.0194156973 0.0360364988 0.0082969901 0.1906210000 245768187 0 1785163776 0.4049332738 0.2272154391 2.4990675449 451 18.0000000000 0.0293583758 0.0194377431 0.0360364988 0.0083016614 0.3675460000 245697420 0 1778761728 0.4174889326 0.2271727771 2.4920666218 452 18.0400000000 0.0299941860 0.0194610981 0.0360364988 0.0082950391 0.2055610000 242239248 0 1778348032 0.4260939956 0.2297181338 2.4846234322 453 18.0800000000 0.0273173004 0.0194784407 0.0360364988 0.0082864054 0.3244450000 242299170 0 1776734208 0.4331049323 0.2253087759 2.4756546021 454 18.1200000000 0.0281428639 0.0194975254 0.0360364988 0.0082832828 0.3266840000 242454424 0 1779240960 0.4380187392 0.2249666452 2.4713807106 455 18.1600000000 0.0283931270 0.0195170761 0.0360364988 0.0082792027 0.3222670000 244492869 0 1786040320 0.4548079967 0.2233993411 2.4662020206 456 18.2000000000 0.0290333293 0.0195379451 0.0360364988 0.0082720584 0.2357430000 246088708 0 1784049664 0.4584037662 0.2220559120 2.4595990181 457 18.2400000000 0.0295580048 0.0195598708 0.0360364988 0.0082760655 0.2238400000 245782417 0 1785810944 0.4733362794 0.2189706117 2.4548168182 458 18.2800000000 0.0280458853 0.0195783992 0.0360364988 0.0082933395 0.1872310000 246036519 0 1784262656 0.4827090502 0.2213194221 2.4491469860 459 18.3200000000 0.0270394497 0.0195946543 0.0360364988 0.0082877915 0.3711870000 245966228 0 1782411264 0.4925423265 0.2241026312 2.4410769939 460 18.3600000000 0.0260674078 0.0196087255 0.0360364988 0.0082862297 0.3416000000 242576304 0 1777606656 0.5004527569 0.2190699279 2.4370782375 461 18.4000000000 0.0267054848 0.0196241197 0.0360364988 0.0082786011 0.3069160000 242727338 0 1779621888 0.5116990805 0.2182316184 2.4337503910 462 18.4400000000 0.0258485582 0.0196375925 0.0360364988 0.0082735296 0.3225660000 244981439 0 1784561664 0.5204272866 0.2157583833 2.4308278561 463 18.4800000000 0.0267726611 0.0196530031 0.0360364988 0.0082682834 0.3806610000 244849324 0 1780187136 0.5271750689 0.2139095664 2.4252996445 464 18.5200000000 0.0251055788 0.0196647543 0.0360364988 0.0082607535 0.3054700000 242852916 0 1779494912 0.5367728472 0.2096515894 2.4210433960 465 18.5600000000 0.0246313140 0.0196754351 0.0360364988 0.0082649239 0.3176690000 243181266 0 1780834304 0.5452530980 0.2088698298 2.4130916595 466 18.6000000000 0.0271719657 0.0196915221 0.0360364988 0.0082727349 0.3021220000 243110012 0 1782992896 0.5540710092 0.2094469666 2.4143652916 467 18.6400000000 0.0267716162 0.0197066829 0.0360364988 0.0082710561 0.3110210000 243438314 0 1784401920 0.5682780147 0.2096057981 2.4092857838 468 18.6800000000 0.0275350511 0.0197234101 0.0360364988 0.0082720292 0.3202770000 243397744 0 1786167296 0.5770082474 0.2071188390 2.4080553055 469 18.7200000000 0.0259541851 0.0197366954 0.0360364988 0.0082941560 0.3327800000 243714118 0 1785307136 0.5866320133 0.2041629851 2.4060685635 470 18.7600000000 0.0278450716 0.0197539472 0.0360364988 0.0083085880 0.3170410000 243829520 0 1786978304 0.5965074301 0.2029148042 2.4061117172 471 18.8000000000 0.0264618751 0.0197681891 0.0360364988 0.0083585602 0.3331000000 244139230 0 1783558144 0.6070135832 0.2001473606 2.4031314850 472 18.8400000000 0.0273997877 0.0197843578 0.0360364988 0.0083894425 0.3032210000 244277424 0 1785614336 0.6152048707 0.1984408200 2.4041128159 473 18.8800000000 0.0271152817 0.0197998565 0.0360364988 0.0084033767 0.3239480000 244550762 0 1784008704 0.6273007989 0.2004731447 2.3971650600 474 18.9200000000 0.0263329409 0.0198136394 0.0360364988 0.0084003488 0.3277910000 244860080 0 1783214080 0.6348556876 0.1983107328 2.3899343014 475 18.9600000000 0.0277586058 0.0198303657 0.0360364988 0.0083997388 0.3252770000 244830810 0 1785303040 0.6417071819 0.1984807104 2.3863012791 476 19.0000000000 0.0237659384 0.0198386337 0.0360364988 0.0084083389 0.3238860000 245064204 0 1784193024 0.6516383886 0.1933871210 2.3841092587 477 19.0400000000 0.0248676203 0.0198491766 0.0360364988 0.0084046468 0.3092970000 245151369 0 1783468032 0.6572020054 0.1937013566 2.3765881062 478 19.0800000000 0.0260324441 0.0198621123 0.0360364988 0.0083968004 0.3326890000 245350620 0 1785188352 0.6697752476 0.1935067028 2.3811562061 479 19.1200000000 0.0260363985 0.0198750023 0.0360364988 0.0083907610 0.3265280000 245505182 0 1784193024 0.6784831285 0.1923077255 2.3782415390 480 19.1600000000 0.0272888709 0.0198904478 0.0360364988 0.0083927191 0.3226310000 245631952 0 1783504896 0.6854581237 0.1905531287 2.3804085255 481 19.2000000000 0.0284970943 0.0199083411 0.0360364988 0.0084077056 0.3543760000 245802446 0 1785348096 0.6914976835 0.1936343908 2.3735175133 482 19.2400000000 0.0282902848 0.0199257310 0.0360364988 0.0083995763 0.3398330000 246020636 0 1784008704 0.6999037266 0.1918440908 2.3757431507 483 19.2800000000 0.0274888817 0.0199413897 0.0360364988 0.0083916330 0.3545950000 246302914 0 1784782848 0.7101264596 0.1896091104 2.3741061687 484 19.3200000000 0.0289074760 0.0199599147 0.0360364988 0.0083872652 0.3334500000 246384000 0 1786318848 0.7131919265 0.1897872090 2.3697471619 485 19.3600000000 0.0300727654 0.0199807659 0.0360364988 0.0083846455 0.3403790000 246624602 0 1785610240 0.7250970006 0.1955552101 2.3652133942 486 19.4000000000 0.0296555329 0.0200006728 0.0360364988 0.0083853989 0.3462280000 246949808 0 1785679872 0.7299740911 0.1962188780 2.3623721600 487 19.4400000000 0.0294584967 0.0200200934 0.0360364988 0.0084306097 0.3617110000 247071914 0 1784967168 0.7359947562 0.1915332079 2.3615643978 488 19.4800000000 0.0328503139 0.0200463849 0.0360364988 0.0084337647 0.3544620000 247144932 0 1786744832 0.7375670671 0.1945066750 2.3535046577 489 19.5200000000 0.0292795338 0.0200652665 0.0360364988 0.0084271278 0.3811430000 247380546 0 1785270272 0.7433344126 0.1897079796 2.3496012688 490 19.5600000000 0.0319475941 0.0200895162 0.0360364988 0.0084195592 0.3736530000 247540252 0 1787011072 0.7431683540 0.1899166703 2.3410818577 491 19.6000000000 0.0317311957 0.0201132263 0.0360364988 0.0084118897 0.4122050000 247837710 0 1784655872 0.7504169941 0.1885934919 2.3383905888 492 19.6400000000 0.0309049506 0.0201351607 0.0360364988 0.0084035581 0.3830350000 247911592 0 1785589760 0.7505161762 0.1889197379 2.3249518871 493 19.6800000000 0.0312232710 0.0201576518 0.0360364988 0.0084014890 0.3879120000 248119486 0 1784008704 0.7536669970 0.1883563846 2.3150601387 494 19.7200000000 0.0333892629 0.0201844365 0.0360364988 0.0084017344 0.3756760000 248204300 0 1783263232 0.7535977364 0.1866583377 2.3056287766 495 19.7600000000 0.0344525985 0.0202132610 0.0360364988 0.0083956262 0.3824460000 248239706 0 1784803328 0.7539684772 0.1855150312 2.2941012383 496 19.8000000000 0.0320281871 0.0202370815 0.0360364988 0.0083929523 0.3900380000 248529732 0 1786580992 0.7521934509 0.1811937094 2.2891504765 497 19.8400000000 0.0342686847 0.0202653141 0.0360364988 0.0083855659 0.4043430000 248479802 0 1783300096 0.7512873411 0.1779736578 2.2832212448 498 19.8800000000 0.0319064148 0.0202886898 0.0360364988 0.0083824478 0.3973950000 248540912 0 1785483264 0.7552368641 0.1780654937 2.2708690166 499 19.9200000000 0.0296319295 0.0203074137 0.0360364988 0.0083743158 0.4122000000 248828894 0 1786937344 0.7572063208 0.1748975217 2.2635326385 500 19.9600000000 0.0338978097 0.0203345945 0.0360364988 0.0083689159 0.4151520000 248837208 0 1783058432 0.7502139211 0.1735521853 2.2545042038 501 20.0000000000 0.0306754857 0.0203552350 0.0360364988 0.0083671797 0.4405560000 248884426 0 1784860672 0.7592357397 0.1729245037 2.2438008785 502 20.0400000000 0.0344734900 0.0203833590 0.0360364988 0.0083646628 0.4330800000 249076964 0 1786302464 0.7547354698 0.1716568917 2.2350463867 503 20.0800000000 0.0319401845 0.0204063348 0.0360364988 0.0083596465 0.4478060000 251651889 0 1783418880 0.7578171492 0.1678073108 2.2248222828 504 20.1200000000 0.0361303687 0.0204375333 0.0361303687 0.0083551057 0.4838980000 249694965 0 1777156096 0.7558170557 0.1695686877 2.2144250870 505 20.1600000000 0.0334098153 0.0204632210 0.0361303687 0.0083527547 0.4083770000 248923090 0 1776336896 0.7523674965 0.1648087800 2.2006146908 506 20.2000000000 0.0372844376 0.0204964645 0.0372844376 0.0083497528 0.4347020000 248924624 0 1777721344 0.7504149675 0.1714032739 2.1914517879 507 20.2400000000 0.0352057219 0.0205254768 0.0372844376 0.0083471758 0.4165230000 249120626 0 1779048448 0.7524819374 0.1710401624 2.1799962521 508 20.2800000000 0.0317066722 0.0205474870 0.0372844376 0.0083515532 0.4776490000 250871404 0 1786077184 0.7477753162 0.1658931971 2.1704051495 509 20.3200000000 0.0355670713 0.0205769951 0.0372844376 0.0083459789 0.5109920000 249267342 0 1779093504 0.7471026182 0.1662882119 2.1612975597 510 20.3600000000 0.0365777612 0.0206083691 0.0372844376 0.0083396422 0.4542540000 249267948 0 1780912128 0.7541056871 0.1707982421 2.1459231377 511 20.4000000000 0.0424726456 0.0206511564 0.0424726456 0.0083400933 0.4417540000 250703889 0 1782943744 0.7465735078 0.1733433902 2.1351788044 512 20.4400000000 0.0343271606 0.0206778673 0.0424726456 0.0083646744 0.3717520000 253553375 0 1783590912 0.7565041780 0.1741396189 2.1205959320 513 20.4800000000 0.0419549681 0.0207193431 0.0424726456 0.0083774990 0.3763050000 253483304 0 1782960128 0.7525074482 0.1757859141 2.1103522778 514 20.5200000000 0.0450825244 0.0207667423 0.0450825244 0.0083735477 0.2537470000 253464043 0 1784713216 0.7491838336 0.1766017973 2.1004519463 515 20.5600000000 0.0456710681 0.0208151002 0.0456710681 0.0083979090 0.5292670000 253381144 0 1777561600 0.7651032209 0.1871735603 2.0875420570 516 20.6000000000 0.0450644158 0.0208620950 0.0456710681 0.0084036492 0.4307080000 249650028 0 1779052544 0.7675629854 0.1856021285 2.0733418465 517 20.6400000000 0.0438256487 0.0209065120 0.0456710681 0.0084026414 0.4555110000 249955138 0 1781272576 0.7665044069 0.1842909306 2.0710563660 518 20.6800000000 0.0433351435 0.0209498105 0.0456710681 0.0083953505 0.4433200000 249905808 0 1783050240 0.7808043957 0.1836375296 2.0517070293 519 20.7200000000 0.0471720621 0.0210003350 0.0471720621 0.0083907035 0.4299640000 249987162 0 1784827904 0.7673699856 0.1889846325 2.0542008877 520 20.7600000000 0.0454131216 0.0210472827 0.0471720621 0.0083942362 0.4388790000 250092444 0 1786732544 0.7651625872 0.1912560612 2.0527999401 521 20.8000000000 0.0427817740 0.0210889996 0.0471720621 0.0084086314 0.4480600000 253119721 0 1784328192 0.7635488510 0.1863303781 2.0462057590 522 20.8400000000 0.0429989472 0.0211309727 0.0471720621 0.0084046660 0.2578560000 254877418 0 1783152640 0.7681583762 0.1842161268 2.0382628441 523 20.8800000000 0.0400552973 0.0211671568 0.0471720621 0.0083985345 0.2718990000 254170426 0 1786257408 0.7583978176 0.1803639531 2.0425717831 524 20.9200000000 0.0460644811 0.0212146708 0.0471720621 0.0083976652 0.2297380000 254219591 0 1784811520 0.7658374906 0.1820538640 2.0260961056 525 20.9600000000 0.0383819304 0.0212473704 0.0471720621 0.0083994073 0.4818830000 254149576 0 1780654080 0.7739887834 0.1772549152 2.0185053349 526 21.0000000000 0.0373811312 0.0212780429 0.0471720621 0.0083927852 0.2216320000 250343320 0 1780981760 0.7818232179 0.1729621291 2.0041191578 527 21.0400000000 0.0432108194 0.0213196611 0.0471720621 0.0083909843 0.4842930000 250377598 0 1779998720 0.7809717059 0.1785616130 1.9973484278 528 21.0800000000 0.0404748619 0.0213559399 0.0471720621 0.0083844118 0.4687010000 250378468 0 1782136832 0.7847362757 0.1756095886 1.9913709164 529 21.1200000000 0.0425258055 0.0213959585 0.0471720621 0.0083822237 0.4686910000 252228669 0 1786118144 0.7901800871 0.1711833626 1.9741301537 530 21.1600000000 0.0400157943 0.0214310903 0.0471720621 0.0083802071 0.3620490000 255099439 0 1782525952 0.7911867499 0.1713460833 1.9712309837 531 21.2000000000 0.0437167585 0.0214730595 0.0471720621 0.0083769652 0.3523840000 255029484 0 1781264384 0.8024906516 0.1759256870 1.9547830820 532 21.2400000000 0.0403093994 0.0215084662 0.0471720621 0.0083734059 0.2482920000 255383324 0 1783463936 0.8002560139 0.1691493988 1.9484826326 533 21.2800000000 0.0423621014 0.0215475912 0.0471720621 0.0083675982 0.2240520000 254920341 0 1785044992 0.7969248891 0.1696061492 1.9431626797 534 21.3200000000 0.0420628153 0.0215860092 0.0471720621 0.0083666265 0.5215360000 254850670 0 1776668672 0.8069271445 0.1697788835 1.9244192839 535 21.3600000000 0.0413525589 0.0216229560 0.0471720621 0.0083626890 0.1974200000 250362826 0 1776738304 0.8140791655 0.1718777418 1.9088920355 536 21.4000000000 0.0399667099 0.0216571795 0.0471720621 0.0083570544 0.2172510000 250703592 0 1777979392 0.8114260435 0.1691076159 1.9063725471 537 21.4400000000 0.0390058644 0.0216894861 0.0471720621 0.0083497927 0.4656410000 250739210 0 1781342208 0.8199638128 0.1665188372 1.8903496265 538 21.4800000000 0.0422825329 0.0217277632 0.0471720621 0.0083435490 0.4607730000 250741100 0 1783476224 0.8178761601 0.1690126210 1.8823411465 539 21.5200000000 0.0406275317 0.0217628277 0.0471720621 0.0083388961 0.4526210000 252551393 0 1786822656 0.8212198019 0.1689365655 1.8731369972 540 21.5600000000 0.0368393846 0.0217907472 0.0471720621 0.0083355281 0.3806400000 255576867 0 1783930880 0.8205334544 0.1644586474 1.8594225645 541 21.6000000000 0.0442726165 0.0218323034 0.0471720621 0.0083360844 0.4096410000 255506980 0 1782763520 0.8151093721 0.1714154780 1.8512332439 542 21.6400000000 0.0444365814 0.0218740087 0.0471720621 0.0083367725 0.2493550000 255576140 0 1784872960 0.8225393295 0.1718603820 1.8380461931 543 21.6800000000 0.0424660519 0.0219119314 0.0471720621 0.0083320343 0.2120760000 255395825 0 1786245120 0.8195690513 0.1646842659 1.8342543840 544 21.7200000000 0.0389364772 0.0219432265 0.0471720621 0.0083431070 0.5260540000 255326126 0 1778884608 0.8287993670 0.1665985286 1.8188132048 545 21.7600000000 0.0407713316 0.0219777735 0.0471720621 0.0083396716 0.2009880000 250750190 0 1778745344 0.8295254707 0.1665368378 1.8070410490 546 21.8000000000 0.0374345034 0.0220060825 0.0471720621 0.0083432398 0.2021230000 250751748 0 1780776960 0.8360391259 0.1652229130 1.8005523682 547 21.8400000000 0.0400552936 0.0220390793 0.0471720621 0.0083430708 0.2026470000 250753398 0 1781391360 0.8367688656 0.1693642437 1.7877726555 548 21.8800000000 0.0364992619 0.0220654665 0.0471720621 0.0083374843 0.1996000000 250754804 0 1784225792 0.8327288628 0.1652907431 1.7855064869 549 21.9200000000 0.0411641113 0.0221002545 0.0471720621 0.0083334970 0.2015070000 250756110 0 1785331712 0.8320681453 0.1690857708 1.7788512707 550 21.9600000000 0.0392992869 0.0221315255 0.0471720621 0.0083268747 0.2055940000 250758520 0 1784963072 0.8332692385 0.1698885560 1.7724947929 551 22.0000000000 0.0360063240 0.0221567066 0.0471720621 0.0083259226 0.2328920000 251134074 0 1786601472 0.8396471143 0.1679121554 1.7630336285 552 22.0400000000 0.0367509536 0.0221831455 0.0471720621 0.0083197658 0.4870210000 251128228 0 1782259712 0.8385593891 0.1691854298 1.7556595802 553 22.0800000000 0.0373911522 0.0222106464 0.0471720621 0.0083158669 0.4806330000 251129602 0 1784041472 0.8373568654 0.1696043909 1.7536180019 554 22.1200000000 0.0400209799 0.0222427950 0.0471720621 0.0083102805 0.4441630000 252803643 0 1786372096 0.8350613117 0.1696820855 1.7479956150 555 22.1600000000 0.0413320921 0.0222771901 0.0471720621 0.0083037167 0.3899890000 255841833 0 1783037952 0.8371095657 0.1744299829 1.7395079136 556 22.2000000000 0.0391990393 0.0223076251 0.0471720621 0.0083022903 0.3602230000 255771738 0 1782267904 0.8406791687 0.1755524278 1.7301855087 557 22.2400000000 0.0421893671 0.0223433194 0.0471720621 0.0083106804 0.2498330000 256153604 0 1784303616 0.8367138505 0.1751628816 1.7270132303 558 22.2800000000 0.0412344262 0.0223771745 0.0471720621 0.0083036321 0.2175870000 255660671 0 1786048512 0.8341584206 0.1712526679 1.7216757536 559 22.3200000000 0.0341297351 0.0223981987 0.0471720621 0.0083233481 0.5579360000 255591004 0 1774899200 0.8466639519 0.1684228480 1.7111623287 560 22.3600000000 0.0319860093 0.0224153198 0.0471720621 0.0083171471 0.2297060000 251111764 0 1774731264 0.8443369865 0.1663596928 1.7078822851 561 22.4000000000 0.0361175761 0.0224397445 0.0471720621 0.0083120032 0.2025880000 251113546 0 1776754688 0.8475548029 0.1697249413 1.6981654167 562 22.4400000000 0.0313790925 0.0224556508 0.0471720621 0.0083080141 0.2029960000 251115020 0 1778012160 0.8430650830 0.1661396325 1.6967999935 563 22.4800000000 0.0334751047 0.0224752236 0.0471720621 0.0083033559 0.1991440000 251116494 0 1779945472 0.8413801193 0.1679733396 1.6881338358 564 22.5200000000 0.0312621705 0.0224908033 0.0471720621 0.0083007350 0.1967890000 251118336 0 1781596160 0.8428170681 0.1637736708 1.6824510098 565 22.5600000000 0.0359403230 0.0225146077 0.0471720621 0.0082960230 0.1964710000 251119450 0 1783484416 0.8439417481 0.1655481607 1.6722652912 566 22.6000000000 0.0392180867 0.0225441192 0.0471720621 0.0082935075 0.2193180000 251497424 0 1785151488 0.8462852240 0.1684575677 1.6633229256 567 22.6400000000 0.0351368301 0.0225663285 0.0471720621 0.0082894682 0.4971190000 251510870 0 1784532992 0.8498836160 0.1640057713 1.6571087837 568 22.6800000000 0.0374015234 0.0225924468 0.0471720621 0.0082826614 0.4640410000 251517140 0 1784057856 0.8512567282 0.1639278829 1.6497378349 569 22.7200000000 0.0369604118 0.0226176981 0.0471720621 0.0082785644 0.4656250000 251527466 0 1785872384 0.8498919010 0.1613618731 1.6401475668 570 22.7600000000 0.0357614458 0.0226407573 0.0471720621 0.0082743750 0.4220670000 255921431 0 1785548800 0.8505047560 0.1629859507 1.6296926737 571 22.8000000000 0.0373928100 0.0226665928 0.0471720621 0.0082686854 0.3781480000 255851332 0 1784619008 0.8505142331 0.1660842150 1.6205959320 572 22.8400000000 0.0413292684 0.0226992198 0.0471720621 0.0082659727 0.2535470000 256061444 0 1786302464 0.8501925468 0.1659086645 1.6110373735 573 22.8800000000 0.0355230048 0.0227215999 0.0471720621 0.0082690463 0.5571760000 255680012 0 1777721344 0.8555390835 0.1594457626 1.6004551649 574 22.9200000000 0.0363713801 0.0227453800 0.0471720621 0.0082625272 0.2331570000 251523904 0 1777938432 0.8538335562 0.1615739167 1.5928024054 575 22.9600000000 0.0293993149 0.0227569521 0.0471720621 0.0082638753 0.2035880000 251525210 0 1779462144 0.8513535261 0.1514419168 1.5849528313 576 23.0000000000 0.0354791358 0.0227790392 0.0471720621 0.0082653852 0.1967690000 251526792 0 1781477376 0.8484833241 0.1541895121 1.5776488781 577 23.0400000000 0.0334369093 0.0227975104 0.0471720621 0.0082637962 0.1990210000 251527906 0 1783513088 0.8454092741 0.1536120176 1.5695980787 578 23.0800000000 0.0347094983 0.0228181194 0.0471720621 0.0082594040 0.1962530000 251529464 0 1785290752 0.8489736915 0.1542745829 1.5572338104 579 23.1200000000 0.0303595867 0.0228311443 0.0471720621 0.0082553425 0.1938320000 251530810 0 1784770560 0.8492518663 0.1468597502 1.5500049591 580 23.1600000000 0.0368013382 0.0228552309 0.0471720621 0.0082591844 0.1982750000 251532860 0 1783226368 0.8461840153 0.1526018083 1.5389199257 581 23.2000000000 0.0355042629 0.0228770020 0.0471720621 0.0082539717 0.1928920000 251533974 0 1785274368 0.8475122452 0.1512790620 1.5285723209 582 23.2400000000 0.0330079384 0.0228944091 0.0471720621 0.0082498032 0.1921080000 251535448 0 1784934400 0.8441227674 0.1465678811 1.5201678276 583 23.2800000000 0.0322544016 0.0229104640 0.0471720621 0.0082442841 0.1942750000 251536738 0 1784287232 0.8434969783 0.1427896321 1.5088202953 584 23.3200000000 0.0355073065 0.0229320339 0.0471720621 0.0082454105 0.2187060000 251937872 0 1785925632 0.8407216668 0.1464280337 1.4980822802 585 23.3600000000 0.0339648686 0.0229508935 0.0471720621 0.0082419530 0.5160660000 251938514 0 1783689216 0.8425742388 0.1439056695 1.4856011868 586 23.4000000000 0.0355928577 0.0229724668 0.0471720621 0.0082390441 0.4636270000 251938780 0 1785221120 0.8386457562 0.1424561739 1.4762263298 587 23.4400000000 0.0350126848 0.0229929783 0.0471720621 0.0082388448 0.4621840000 251950298 0 1784578048 0.8393467069 0.1410245299 1.4670835733 588 23.4800000000 0.0335150585 0.0230108729 0.0471720621 0.0082435811 0.4049120000 256217299 0 1784942592 0.8383263350 0.1415304840 1.4390919209 589 23.5200000000 0.0318992436 0.0230259636 0.0471720621 0.0082390189 0.3478310000 256210856 0 1783767040 0.8343881965 0.1411572844 1.4319269657 590 23.5600000000 0.0331000090 0.0230430382 0.0471720621 0.0082346753 0.2515670000 256294532 0 1785978880 0.8310292959 0.1442054212 1.4199244976 591 23.6000000000 0.0290393904 0.0230531843 0.0471720621 0.0082435234 0.5464110000 255908168 0 1780809728 0.8295630217 0.1375415325 1.4092955589 592 23.6400000000 0.0292142760 0.0230635916 0.0471720621 0.0082379375 0.2394490000 251946244 0 1781026816 0.8303312063 0.1350462139 1.3958249092 593 23.6800000000 0.0282638017 0.0230723609 0.0471720621 0.0082334587 0.1956410000 251947750 0 1782267904 0.8267620802 0.1342571229 1.3830335140 594 23.7200000000 0.0288350638 0.0230820624 0.0471720621 0.0082279360 0.1878720000 251949172 0 1784713216 0.8238430023 0.1342324615 1.3730416298 595 23.7600000000 0.0261203330 0.0230871688 0.0471720621 0.0082240484 0.1882390000 251950914 0 1786322944 0.8229931593 0.1304648221 1.3633871078 596 23.8000000000 0.0281429105 0.0230956515 0.0471720621 0.0082233506 0.1852420000 251952036 0 1784311808 0.8205014467 0.1338312030 1.3510007858 597 23.8400000000 0.0269420762 0.0231020945 0.0471720621 0.0082183126 0.1881460000 251953794 0 1783181312 0.8205028772 0.1343692690 1.3392795324 598 23.8800000000 0.0283487830 0.0231108682 0.0471720621 0.0082118618 0.1845110000 251955560 0 1784946688 0.8187251091 0.1360040605 1.3244160414 599 23.9200000000 0.0233163536 0.0231112112 0.0471720621 0.0082126378 0.1880320000 251956498 0 1786200064 0.8177428842 0.1323328614 1.3143200874 600 23.9600000000 0.0231704805 0.0231113100 0.0471720621 0.0082079640 0.1886520000 251957628 0 1784946688 0.8131543398 0.1328164935 1.3030073643 601 24.0000000000 0.0284087528 0.0231201244 0.0471720621 0.0082045622 0.1876690000 251959486 0 1786613760 0.8097995520 0.1379203498 1.2946952581 602 24.0400000000 0.0271919593 0.0231268882 0.0471720621 0.0081994757 0.1852040000 251960976 0 1784930304 0.8102009296 0.1369515955 1.2791223526 603 24.0800000000 0.0238850806 0.0231281456 0.0471720621 0.0081961101 0.1871600000 251962450 0 1786740736 0.8089809418 0.1334977895 1.2682061195 604 24.1200000000 0.0299645830 0.0231394642 0.0471720621 0.0081988378 0.1856900000 251963764 0 1785184256 0.8019680977 0.1410985738 1.2615916729 605 24.1600000000 0.0247062333 0.0231420539 0.0471720621 0.0082042681 0.1812270000 251965162 0 1786978304 0.8013063669 0.1332507133 1.2564305067 606 24.2000000000 0.0239063725 0.0231433152 0.0471720621 0.0081982658 0.1801070000 251966836 0 1785450496 0.7991129756 0.1308208108 1.2452099323 607 24.2400000000 0.0220537502 0.0231415202 0.0471720621 0.0081932469 0.2204830000 251968234 0 1784442880 0.7989587784 0.1268610358 1.2344586849 608 24.2800000000 0.0293854028 0.0231517897 0.0471720621 0.0081965422 0.1829150000 251970008 0 1782509568 0.7977503538 0.1365275383 1.2219014168 609 24.3200000000 0.0255330708 0.0231556999 0.0471720621 0.0081938462 0.1832210000 251971246 0 1783656448 0.7928993702 0.1304486245 1.2146825790 610 24.3600000000 0.0261357296 0.0231605852 0.0471720621 0.0081876265 0.1849200000 251972904 0 1785688064 0.7922562361 0.1267239302 1.2062673569 611 24.4000000000 0.0239840671 0.0231619329 0.0471720621 0.0081833905 0.1790460000 251974318 0 1784184832 0.7894474864 0.1237166151 1.1942112446 612 24.4400000000 0.0249574669 0.0231648668 0.0471720621 0.0081795152 0.1818120000 251975640 0 1783037952 0.7847852707 0.1257466078 1.1849472523 613 24.4800000000 0.0264275428 0.0231701893 0.0471720621 0.0081745657 0.1790670000 251977322 0 1778974720 0.7850017548 0.1245191768 1.1778122187 614 24.5200000000 0.0271439347 0.0231766612 0.0471720621 0.0081689591 0.1830710000 251978628 0 1777958912 0.7804776430 0.1232806146 1.1662704945 615 24.5600000000 0.0246154983 0.0231790007 0.0471720621 0.0081637574 0.2120370000 252525830 0 1779212288 0.7799407244 0.1192257106 1.1570585966 616 24.6000000000 0.0220969524 0.0231772442 0.0471720621 0.0081592529 0.5664240000 252506176 0 1779126272 0.7802355886 0.1134008169 1.1449329853 617 24.6400000000 0.0262565874 0.0231822350 0.0471720621 0.0081625055 0.5054380000 252508014 0 1780785152 0.7788128853 0.1162919700 1.1338827610 618 24.6800000000 0.0231285058 0.0231821481 0.0471720621 0.0081609215 0.4569880000 252677564 0 1782505472 0.7775551081 0.1112172753 1.1203122139 619 24.7200000000 0.0247595385 0.0231846964 0.0471720621 0.0081595134 0.4507070000 256645409 0 1783099392 0.7772200108 0.1114210114 1.1067800522 620 24.7600000000 0.0279266518 0.0231923447 0.0471720621 0.0081610246 0.3420910000 256722842 0 1782902784 0.7736868858 0.1162815765 1.0966016054 621 24.8000000000 0.0247387867 0.0231948349 0.0471720621 0.0081555768 0.2716900000 256757030 0 1784758272 0.7713598013 0.1125544310 1.0859651566 622 24.8400000000 0.0221190061 0.0231931053 0.0471720621 0.0081528975 0.5649660000 256464564 0 1785991168 0.7652488947 0.1093986630 1.0724924803 623 24.8800000000 0.0208817199 0.0231893952 0.0471720621 0.0081476620 0.2743920000 252517166 0 1784434688 0.7619448900 0.1087194905 1.0626933575 624 24.9200000000 0.0220987797 0.0231876474 0.0471720621 0.0081420894 0.2031790000 252518756 0 1786052608 0.7601838112 0.1106478870 1.0511920452 625 24.9600000000 0.0262829755 0.0231925999 0.0471720621 0.0081375956 0.2079950000 252520506 0 1785159680 0.7588254213 0.1131171137 1.0400352478 626 25.0000000000 0.0265402421 0.0231979476 0.0471720621 0.0081319995 0.2056600000 252522088 0 1786957824 0.7550570965 0.1112799868 1.0330891609 627 25.0400000000 0.0243626796 0.0231998052 0.0471720621 0.0081296140 0.1950540000 252523210 0 1785421824 0.7517374754 0.1092082858 1.0208820105 628 25.0800000000 0.0244172290 0.0232017438 0.0471720621 0.0081238602 0.1964840000 252525308 0 1784528896 0.7496064901 0.1108198762 1.0107133389 629 25.1200000000 0.0233675372 0.0232020074 0.0471720621 0.0081212504 0.1961470000 252526270 0 1782616064 0.7476489544 0.1088117063 1.0047491789 630 25.1600000000 0.0227181483 0.0232012394 0.0471720621 0.0081154300 0.1980120000 252528236 0 1784287232 0.7429956198 0.1082132608 0.9943823218 631 25.2000000000 0.0235038307 0.0232017189 0.0471720621 0.0081125461 0.1959850000 252529490 0 1785667584 0.7386817336 0.1097080857 0.9889967442 632 25.2400000000 0.0266981814 0.0232072513 0.0471720621 0.0081132510 0.1935550000 252531296 0 1784164352 0.7389600873 0.1112011224 0.9791823626 633 25.2800000000 0.0258505419 0.0232114271 0.0471720621 0.0081076513 0.1953650000 252532426 0 1783160832 0.7326575518 0.1118936688 0.9698079824 634 25.3200000000 0.0243526809 0.0232132272 0.0471720621 0.0081056502 0.1900090000 252533964 0 1784782848 0.7277432680 0.1118494198 0.9606494904 635 25.3600000000 0.0266921129 0.0232187057 0.0471720621 0.0081203134 0.1954370000 252535762 0 1786540032 0.7193862200 0.1132787913 0.9641102552 636 25.4000000000 0.0271079373 0.0232248209 0.0471720621 0.0081205724 0.1905080000 252537168 0 1783398400 0.7185508013 0.1132266894 0.9482824802 637 25.4400000000 0.0205214061 0.0232205769 0.0471720621 0.0081241443 0.1934400000 252538506 0 1780224000 0.7142547369 0.1062268913 0.9440000653 638 25.4800000000 0.0253308658 0.0232238846 0.0471720621 0.0081200495 0.1904410000 252540304 0 1781604352 0.7125948071 0.1097687706 0.9317716360 639 25.5200000000 0.0184339527 0.0232163886 0.0471720621 0.0081237733 0.1867570000 252541618 0 1783767040 0.7081145048 0.1000442058 0.9229411483 640 25.5600000000 0.0211903658 0.0232132229 0.0471720621 0.0081237256 0.1881760000 252542956 0 1785540608 0.7020936608 0.1022631377 0.9225336313 641 25.6000000000 0.0250504781 0.0232160892 0.0471720621 0.0081221284 0.1882290000 252544570 0 1784438784 0.6958466768 0.1052951962 0.9166767597 642 25.6400000000 0.0196067337 0.0232104671 0.0471720621 0.0081235368 0.1892990000 252546244 0 1782009856 0.6932541132 0.0979208052 0.9095624089 643 25.6800000000 0.0217434354 0.0232081856 0.0471720621 0.0081185212 0.1929350000 252547794 0 1780494336 0.6886776090 0.0983906537 0.9038118124 644 25.7200000000 0.0261684693 0.0232127823 0.0471720621 0.0081167311 0.1852050000 252549232 0 1781985280 0.6817842722 0.1018574014 0.9020523429 645 25.7600000000 0.0314699002 0.0232255840 0.0471720621 0.0081152078 0.1809870000 252550922 0 1783508992 0.6771553755 0.1057023406 0.8926571608 646 25.8000000000 0.0185127836 0.0232182887 0.0471720621 0.0081467229 0.1828860000 252552444 0 1785413632 0.6705842614 0.0883450657 0.8954840302 647 25.8400000000 0.0268934984 0.0232239690 0.0471720621 0.0081583007 0.1812680000 252554090 0 1784184832 0.6601207256 0.0993915200 0.8884117007 648 25.8800000000 0.0158574022 0.0232126009 0.0471720621 0.0081882530 0.1849550000 252555452 0 1781743616 0.6534380317 0.0860083997 0.8850362301 649 25.9200000000 0.0221496727 0.0232109631 0.0471720621 0.0081871016 0.2075480000 252556974 0 1779974144 0.6498717070 0.0910257399 0.8761227131 650 25.9600000000 0.0142859612 0.0231972323 0.0471720621 0.0081867360 0.1821310000 252558512 0 1782386688 0.6340343952 0.0763389319 0.8663276434 651 26.0000000000 0.0138021903 0.0231828006 0.0471720621 0.0081851693 0.1809730000 252560594 0 1783635968 0.6181353331 0.0749043450 0.8568665981 652 26.0400000000 0.0199593082 0.0231778566 0.0471720621 0.0081861744 0.1800720000 252561612 0 1785778176 0.6090873480 0.0829264224 0.8480760455 653 26.0800000000 0.0254722405 0.0231813702 0.0471720621 0.0081873567 0.1795070000 252562774 0 1785040896 0.5989236832 0.0910677537 0.8486741781 654 26.1200000000 0.0284099113 0.0231893649 0.0471720621 0.0081863967 0.1810040000 252564564 0 1784283136 0.5876194239 0.0946108997 0.8423407078 655 26.1600000000 0.0220221113 0.0231875829 0.0471720621 0.0081908886 0.1758900000 252566346 0 1782886400 0.5790938735 0.0855472386 0.8358337879 656 26.2000000000 0.0102878567 0.0231679186 0.0471720621 0.0082097277 0.1812050000 252567776 0 1782231040 0.5694060922 0.0697727501 0.8341220021 657 26.2400000000 0.0155331809 0.0231562980 0.0471720621 0.0082274607 0.1843000000 252569498 0 1784033280 0.5558471680 0.0767663568 0.8352602720 658 26.2800000000 0.0109731006 0.0231377825 0.0471720621 0.0082317461 0.1800270000 252570620 0 1785683968 0.5477753282 0.0723835528 0.8260613680 659 26.3200000000 0.0180865861 0.0231301176 0.0471720621 0.0082552573 0.1867290000 252572094 0 1784659968 0.5330303311 0.0843152031 0.8270829320 660 26.3600000000 0.0123226587 0.0231137427 0.0471720621 0.0082616086 0.1846030000 252573760 0 1784446976 0.5238540173 0.0797344372 0.8192279935 661 26.4000000000 0.0328877494 0.0231285294 0.0471720621 0.0083410399 0.1780160000 252575426 0 1785831424 0.5072839260 0.1033767760 0.8231199980 662 26.4400000000 0.0211040732 0.0231254713 0.0471720621 0.0084441335 0.2233520000 253143056 0 1785278464 0.5028526783 0.0939316377 0.8023809791 663 26.4800000000 0.0202235077 0.0231210942 0.0471720621 0.0084606834 0.5590840000 253108310 0 1778274304 0.4911233187 0.0937883779 0.8017525077 664 26.5200000000 0.0209208820 0.0231177807 0.0471720621 0.0084645379 0.4970770000 253126140 0 1780396032 0.4811265767 0.0914385319 0.7957119346 665 26.5600000000 0.0198596809 0.0231128813 0.0471720621 0.0084603749 0.4171230000 256227297 0 1783033856 0.4714651406 0.0901392102 0.7923470736 666 26.6000000000 0.0216870625 0.0231107404 0.0471720621 0.0084543023 0.3322610000 256160582 0 1782476800 0.4594996572 0.0944855958 0.7874477506 667 26.6400000000 0.0228868462 0.0231104047 0.0471720621 0.0084637530 0.4701710000 256022112 0 1776054272 0.4470074773 0.0945620835 0.7771749496 668 26.6800000000 0.0226336140 0.0231096910 0.0471720621 0.0084771302 0.2492460000 253120648 0 1776402432 0.4344155788 0.1000999212 0.7754254937 669 26.7200000000 0.0190147758 0.0231035700 0.0471720621 0.0085412758 0.2180360000 253121870 0 1778462720 0.4251787663 0.0973609462 0.7744522095 670 26.7600000000 0.0215742402 0.0231012874 0.0471720621 0.0085587882 0.2190450000 253123552 0 1779970048 0.4146632552 0.0986455604 0.7687665224 671 26.8000000000 0.0193885677 0.0230957543 0.0471720621 0.0085717890 0.2194480000 253125242 0 1781985280 0.4049536884 0.0959376320 0.7652161121 672 26.8400000000 0.0193949863 0.0230902472 0.0471720621 0.0085662875 0.2135850000 253127016 0 1783619584 0.3941852450 0.1002077758 0.7622508407 673 26.8800000000 0.0216754060 0.0230881449 0.0471720621 0.0085607623 0.2132660000 253128262 0 1785667584 0.3867985606 0.1021546870 0.7573255301 674 26.9200000000 0.0202299058 0.0230839042 0.0471720621 0.0085564933 0.2148320000 253129800 0 1784786944 0.3780812621 0.1038567647 0.7568735480 675 26.9600000000 0.0219908431 0.0230822849 0.0471720621 0.0085525499 0.2109770000 253131290 0 1783431168 0.3687137365 0.1049649119 0.7498574853 676 27.0000000000 0.0189388506 0.0230761555 0.0471720621 0.0085522022 0.2090240000 253132604 0 1785159680 0.3599466681 0.1058686152 0.7477650046 677 27.0400000000 0.0222249236 0.0230748982 0.0471720621 0.0085542799 0.2066100000 253133726 0 1784406016 0.3515196741 0.1112220958 0.7434763908 678 27.0800000000 0.0219251271 0.0230732024 0.0471720621 0.0085614123 0.2101620000 253135508 0 1783500800 0.3419310749 0.1158314794 0.7429481149 679 27.1200000000 0.0209893733 0.0230701334 0.0471720621 0.0085723842 0.2071760000 253137458 0 1785049088 0.3340907693 0.1165245995 0.7394669652 680 27.1600000000 0.0198641382 0.0230654187 0.0471720621 0.0085760633 0.2065040000 253138496 0 1786720256 0.3267963827 0.1160887182 0.7364718914 681 27.2000000000 0.0213443413 0.0230628914 0.0471720621 0.0085717324 0.2034970000 253139826 0 1783517184 0.3180177808 0.1164395660 0.7292147875 682 27.2400000000 0.0198017582 0.0230581097 0.0471720621 0.0085661791 0.2049130000 253141484 0 1784774656 0.3091463447 0.1185186133 0.7256571054 683 27.2800000000 0.0248611029 0.0230607495 0.0471720621 0.0085614259 0.2037700000 253142866 0 1786826752 0.3017812371 0.1269567311 0.7198241353 684 27.3200000000 0.0253924746 0.0230641585 0.0471720621 0.0085674363 0.2071180000 253144440 0 1783279616 0.2927618027 0.1316743493 0.7195915580 685 27.3600000000 0.0186128784 0.0230576602 0.0471720621 0.0086031437 0.2082870000 253146190 0 1785032704 0.2842637300 0.1211038008 0.7111858130 686 27.4000000000 0.0233895332 0.0230581440 0.0471720621 0.0086062504 0.2020670000 253147512 0 1786699776 0.2763929069 0.1334906965 0.7084153295 687 27.4400000000 0.0250739530 0.0230610782 0.0471720621 0.0086186000 0.2011120000 253148902 0 1783496704 0.2688542008 0.1347478479 0.6974629164 688 27.4800000000 0.0237217955 0.0230620386 0.0471720621 0.0086293771 0.1977200000 253150308 0 1785430016 0.2585485876 0.1372888386 0.6944308281 689 27.5200000000 0.0232337229 0.0230622878 0.0471720621 0.0086394279 0.2030420000 253152174 0 1784549376 0.2507782876 0.1389843971 0.6898167729 690 27.5600000000 0.0196624137 0.0230573604 0.0471720621 0.0086511783 0.2010470000 253153688 0 1783627776 0.2454845458 0.1362148970 0.6849811077 691 27.6000000000 0.0235820133 0.0230581197 0.0471720621 0.0086473630 0.2277630000 253155018 0 1785192448 0.2355107069 0.1422705203 0.6741716862 692 27.6400000000 0.0266169757 0.0230632625 0.0471720621 0.0086527912 0.2004070000 253156516 0 1784532992 0.2277254462 0.1519275606 0.6704574823 693 27.6800000000 0.0224592108 0.0230623909 0.0471720621 0.0087345027 0.2008740000 253157822 0 1783537664 0.2190357894 0.1424062550 0.6589077711 694 27.7200000000 0.0205770489 0.0230588097 0.0471720621 0.0087493999 0.1971870000 253159488 0 1785159680 0.2116335183 0.1459357440 0.6573971510 695 27.7600000000 0.0203867462 0.0230549650 0.0471720621 0.0087488102 0.1939150000 253160886 0 1786826752 0.2056327909 0.1458745152 0.6522055864 696 27.8000000000 0.0213227384 0.0230524762 0.0471720621 0.0087479337 0.1967440000 253162616 0 1783369728 0.1979535520 0.1460991800 0.6403194070 697 27.8400000000 0.0171267875 0.0230439745 0.0471720621 0.0087513930 0.1987720000 253164122 0 1785159680 0.1890330017 0.1474855691 0.6373748183 698 27.8800000000 0.0199954025 0.0230396069 0.0471720621 0.0087486426 0.1935540000 253165568 0 1786826752 0.1800017357 0.1548566967 0.6297150850 699 27.9200000000 0.0098415883 0.0230207256 0.0471720621 0.0087975179 0.2328520000 253694014 0 1782775808 0.1723133922 0.1501981914 0.6321089268 700 27.9600000000 0.0097465403 0.0230017625 0.0471720621 0.0088110203 0.5525060000 253657496 0 1786757120 0.1638752818 0.1534070969 0.6272531152 701 28.0000000000 0.0109983729 0.0229846392 0.0471720621 0.0088296425 0.4839170000 254821637 0 1784369152 0.1570871770 0.1560719013 0.6226533055 702 28.0400000000 0.0114724040 0.0229682400 0.0471720621 0.0088449408 0.3678870000 256713649 0 1783279616 0.1496263444 0.1567151845 0.6188119650 703 28.0800000000 0.0114443917 0.0229518477 0.0471720621 0.0088493866 0.3017800000 256663633 0 1782697984 0.1423605978 0.1580662578 0.6136294007 704 28.1200000000 0.0227394775 0.0229515460 0.0471720621 0.0089897547 0.4488460000 256593930 0 1782505472 0.1386857182 0.1536263973 0.5882586837 705 28.1600000000 0.0249989349 0.0229544501 0.0471720621 0.0089956852 0.2222290000 253667658 0 1782403072 0.1309511065 0.1626534909 0.5813201666 706 28.2000000000 0.0258834157 0.0229585988 0.0471720621 0.0090150819 0.2105550000 253669388 0 1784307712 0.1239991635 0.1618024409 0.5763009787 707 28.2400000000 0.0236575473 0.0229595874 0.0471720621 0.0090167978 0.2093870000 253670910 0 1785577472 0.1156040281 0.1649421006 0.5746086240 708 28.2800000000 0.0252988152 0.0229628914 0.0471720621 0.0090173517 0.2128830000 253672400 0 1784827904 0.1065210402 0.1662988663 0.5692110062 709 28.3200000000 0.0239844657 0.0229643322 0.0471720621 0.0090139025 0.2332580000 253673830 0 1784197120 0.1015667617 0.1669411957 0.5683318973 710 28.3600000000 0.0278088246 0.0229711555 0.0471720621 0.0090166630 0.2019390000 253675512 0 1785856000 0.0932898968 0.1725531220 0.5599247217 711 28.4000000000 0.0260172170 0.0229754397 0.0471720621 0.0090110227 0.2053850000 253676810 0 1784205312 0.0841972828 0.1780933738 0.5593760610 712 28.4400000000 0.0262660589 0.0229800613 0.0471720621 0.0090055579 0.1995660000 253678384 0 1783926784 0.0749916732 0.1816338450 0.5561096072 713 28.4800000000 0.0248114038 0.0229826298 0.0471720621 0.0089994275 0.2010810000 253679958 0 1785622528 0.0708696395 0.1751355231 0.5570055842 714 28.5200000000 0.0255873874 0.0229862779 0.0471720621 0.0090131410 0.1992600000 253681456 0 1784332288 0.0622077733 0.1826702356 0.5553320050 715 28.5600000000 0.0263573341 0.0229909927 0.0471720621 0.0090079902 0.2009780000 253683138 0 1783562240 0.0535150468 0.1908368915 0.5541587472 716 28.6000000000 0.0258663148 0.0229950085 0.0471720621 0.0090213757 0.1945070000 253684392 0 1785352192 0.0482407659 0.1883167773 0.5575713515 717 28.6400000000 0.0231087878 0.0229951672 0.0471720621 0.0090177345 0.1890990000 253685606 0 1787002880 0.0420598090 0.1926944554 0.5635991096 718 28.6800000000 0.0247763414 0.0229976479 0.0471720621 0.0090137859 0.1898540000 253687296 0 1782272000 0.0362014472 0.1968214512 0.5654444695 719 28.7200000000 0.0246491209 0.0229999449 0.0471720621 0.0090110553 0.1841340000 253688886 0 1779515392 0.0278762877 0.1993922442 0.5671966076 720 28.7600000000 0.0260102544 0.0230041258 0.0471720621 0.0090057898 0.1874160000 253690416 0 1777864704 0.0198656917 0.2039730102 0.5689661503 721 28.8000000000 0.0252649691 0.0230072615 0.0471720621 0.0090009172 0.1806320000 253691202 0 1776717824 0.0138471127 0.2044790089 0.5750272274 722 28.8400000000 0.0271432847 0.0230129901 0.0471720621 0.0089973806 0.2195040000 254245068 0 1777971200 0.0053136647 0.2103325576 0.5770485401 723 28.8800000000 0.0273407176 0.0230189759 0.0471720621 0.0089911893 0.5311490000 254211542 0 1776005120 -0.0021117032 0.2119275630 0.5824418068 724 28.9200000000 0.0274260268 0.0230250630 0.0471720621 0.0089850823 0.4617040000 255577999 0 1779671040 -0.0095280111 0.2142415345 0.5880981684 725 28.9600000000 0.0276815649 0.0230314857 0.0471720621 0.0089801613 0.3656150000 257377173 0 1784446976 -0.0178533196 0.2180598676 0.5939328074 726 29.0000000000 0.0271931775 0.0230372181 0.0471720621 0.0089843963 0.2986350000 257326595 0 1782837248 -0.0262840688 0.2188772857 0.6001685262 727 29.0400000000 0.0311185569 0.0230483341 0.0471720621 0.0089809381 0.4530580000 257256688 0 1781960704 -0.0345997810 0.2291372269 0.6050338745 728 29.0800000000 0.0290139988 0.0230565287 0.0471720621 0.0089913788 0.2458170000 254218396 0 1782898688 -0.0437871516 0.2283766270 0.6124550700 729 29.1200000000 0.0302341208 0.0230663745 0.0471720621 0.0089859761 0.1970890000 254220018 0 1785036800 -0.0533105135 0.2334612906 0.6186456084 730 29.1600000000 0.0311328340 0.0230774245 0.0471720621 0.0089813461 0.1956690000 254221264 0 1786703872 -0.0608221889 0.2352622896 0.6252958775 731 29.2000000000 0.0296389218 0.0230864005 0.0471720621 0.0089772671 0.1938860000 254222518 0 1783537664 -0.0702986717 0.2370968312 0.6330751777 732 29.2400000000 0.0302236993 0.0230961509 0.0471720621 0.0089721643 0.1884690000 254222528 0 1779982336 -0.0802342296 0.2415836602 0.6390466094 733 29.2800000000 0.0311478022 0.0231071354 0.0471720621 0.0089670357 0.1831110000 254224374 0 1781235712 -0.0884698033 0.2464457154 0.6478269100 734 29.3200000000 0.0315358490 0.0231186187 0.0471720621 0.0089615829 0.1835230000 254226400 0 1783402496 -0.0952610075 0.2500971556 0.6582542658 735 29.3600000000 0.0314454548 0.0231299477 0.0471720621 0.0089578150 0.1739940000 254226678 0 1785053184 -0.1064724624 0.2534066439 0.6648171544 736 29.4000000000 0.0317698792 0.0231416868 0.0471720621 0.0089548503 0.1738190000 254228020 0 1786728448 -0.1129631996 0.2590570748 0.6759680510 737 29.4400000000 0.0323133953 0.0231541314 0.0471720621 0.0089493020 0.1703880000 254228954 0 1783418880 -0.1205080748 0.2627827227 0.6846568584 738 29.4800000000 0.0322497748 0.0231664561 0.0471720621 0.0089457372 0.1705550000 254229740 0 1782525952 -0.1302852035 0.2666878700 0.6924254894 739 29.5200000000 0.0317115188 0.0231780191 0.0471720621 0.0089573887 0.2044320000 254779986 0 1782636544 -0.1387049258 0.2688116431 0.7008105516 740 29.5600000000 0.0330641232 0.0231913787 0.0471720621 0.0089728604 0.4769300000 254746432 0 1780588544 -0.1435917318 0.2726006508 0.7100858688 741 29.6000000000 0.0312288869 0.0232022256 0.0471720621 0.0089950799 0.4201900000 256522309 0 1784999936 -0.1521621048 0.2754524648 0.7190519571 742 29.6400000000 0.0329929069 0.0232154206 0.0471720621 0.0090056246 0.3471250000 257512118 0 1784467456 -0.1574541628 0.2804403305 0.7271609306 743 29.6800000000 0.0295793284 0.0232239857 0.0471720621 0.0090081548 0.4507680000 257367792 0 1784360960 -0.1623310447 0.2802554369 0.7400157452 744 29.7200000000 0.0293640643 0.0232322385 0.0471720621 0.0090026660 0.1821120000 254744056 0 1785036800 -0.1675506532 0.2820971608 0.7469691038 745 29.7600000000 0.0298995394 0.0232411879 0.0471720621 0.0090007179 0.1757660000 254743598 0 1786814464 -0.1735682786 0.2855563760 0.7522392273 746 29.8000000000 0.0306106452 0.0232510665 0.0471720621 0.0089954521 0.1674340000 254741432 0 1782976512 -0.1772991717 0.2879336774 0.7589398026 747 29.8400000000 0.0314829014 0.0232620864 0.0471720621 0.0089896867 0.1642660000 254744866 0 1781981184 -0.1809407771 0.2912075520 0.7651748061 748 29.8800000000 0.0331334434 0.0232752834 0.0471720621 0.0089852112 0.1592570000 254745996 0 1781329920 -0.1847276986 0.2965217829 0.7713479996 749 29.9200000000 0.0316368341 0.0232864470 0.0471720621 0.0089812413 0.1582170000 254746362 0 1782366208 -0.1905183196 0.2984229624 0.7768985033 750 29.9600000000 0.0298327301 0.0232951754 0.0471720621 0.0089784883 0.1555430000 254746504 0 1784639488 -0.1957269311 0.2992370129 0.7821441889 751 30.0000000000 0.0304060951 0.0233046440 0.0471720621 0.0089739863 0.1878920000 254751106 0 1786290176 -0.1995416582 0.3020976484 0.7864301205 752 30.0400000000 0.0301075410 0.0233136904 0.0471720621 0.0089686548 0.1529420000 254751952 0 1784541184 -0.2042194307 0.3066285253 0.7919535637 753 30.0800000000 0.0318037383 0.0233249654 0.0471720621 0.0089653356 0.1537490000 254753190 0 1783394304 -0.2069460750 0.3093648553 0.7944684029 754 30.1200000000 0.0307551082 0.0233348197 0.0471720621 0.0089707960 0.1521360000 254753112 0 1782853632 -0.2112863660 0.3108230531 0.7984521389 755 30.1600000000 0.0308620185 0.0233447895 0.0471720621 0.0089809440 0.1507510000 254755514 0 1781874688 -0.2149879932 0.3115565479 0.8012145758 756 30.2000000000 0.0326681770 0.0233571220 0.0471720621 0.0089856992 0.1500960000 254760752 0 1781096448 -0.2166585624 0.3152289093 0.8055315614 757 30.2400000000 0.0312752277 0.0233675818 0.0471720621 0.0089864586 0.1449560000 254760734 0 1779572736 -0.2241911292 0.3182917833 0.8079159856 758 30.2800000000 0.0302842017 0.0233767067 0.0471720621 0.0089902912 0.1483720000 254759668 0 1778806784 -0.2282580435 0.3185979426 0.8127196431 759 30.3200000000 0.0314381160 0.0233873278 0.0471720621 0.0089997760 0.1489210000 254762418 0 1780592640 -0.2334185541 0.3222700357 0.8151794672 760 30.3600000000 0.0316558555 0.0233982074 0.0471720621 0.0090075420 0.1753090000 255186148 0 1782358016 -0.2398669124 0.3281966746 0.8189074993 761 30.4000000000 0.0312031787 0.0234084636 0.0471720621 0.0090153387 0.3866820000 255199550 0 1781493760 -0.2471392751 0.3311155438 0.8208349943 762 30.4400000000 0.0312473141 0.0234187508 0.0471720621 0.0090154535 0.2762230000 257019187 0 1784451072 -0.2520840168 0.3337422013 0.8241480589 763 30.4800000000 0.0322870985 0.0234303738 0.0471720621 0.0090115119 0.1976420000 256938801 0 1784188928 -0.2591301203 0.3390455544 0.8260689974 764 30.5200000000 0.0322429165 0.0234419086 0.0471720621 0.0090066541 0.2674580000 256863770 0 1783091200 -0.2689576745 0.3461633325 0.8298939466 765 30.5600000000 0.0345639177 0.0234564471 0.0471720621 0.0090018933 0.1713390000 255158462 0 1783451648 -0.2744335830 0.3514551818 0.8318412304 766 30.6000000000 0.0340024196 0.0234702147 0.0471720621 0.0089998780 0.1607740000 255160636 0 1784594432 -0.2836031318 0.3552000821 0.8338004351 767 30.6400000000 0.0351326317 0.0234854200 0.0471720621 0.0089961824 0.1646800000 255162466 0 1786482688 -0.2901318669 0.3593434691 0.8359529376 768 30.6800000000 0.0350470915 0.0235004742 0.0471720621 0.0089965406 0.1584380000 255162364 0 1783549952 -0.2973811030 0.3624183834 0.8389813304 769 30.7200000000 0.0336403921 0.0235136601 0.0471720621 0.0089979192 0.1586970000 255165994 0 1782808576 -0.3080051541 0.3666507304 0.8410141468 770 30.7600000000 0.0364423171 0.0235304505 0.0471720621 0.0089931034 0.1552780000 255166420 0 1784848384 -0.3139446378 0.3733831644 0.8442226052 771 30.8000000000 0.0344505049 0.0235446140 0.0471720621 0.0089931543 0.1516000000 255165526 0 1786626048 -0.3239220977 0.3748902082 0.8445734978 772 30.8400000000 0.0355326533 0.0235601426 0.0471720621 0.0089883411 0.1508260000 255167616 0 1783185408 -0.3323725462 0.3795572817 0.8470486403 773 30.8800000000 0.0356519744 0.0235757853 0.0471720621 0.0089872752 0.1510230000 255172238 0 1782661120 -0.3393638134 0.3810555041 0.8481624126 774 30.9200000000 0.0349841267 0.0235905248 0.0471720621 0.0089895426 0.1508720000 255172364 0 1784721408 -0.3488861918 0.3837667704 0.8500506878 775 30.9600000000 0.0350304134 0.0236052859 0.0471720621 0.0089927607 0.1490910000 255173350 0 1786245120 -0.3576412201 0.3856091797 0.8513706923 776 31.0000000000 0.0334553905 0.0236179793 0.0471720621 0.0090040308 0.1469050000 255175200 0 1784844288 -0.3689005971 0.3867041469 0.8516077995 777 31.0400000000 0.0356229395 0.0236334297 0.0471720621 0.0090052959 0.1479040000 255176630 0 1783721984 -0.3753843606 0.3923114538 0.8543826938 778 31.0800000000 0.0352651216 0.0236483805 0.0471720621 0.0090069446 0.1473720000 255175736 0 1785704448 -0.3826838136 0.3947379589 0.8562918305 779 31.1200000000 0.0359398723 0.0236641591 0.0471720621 0.0090024801 0.1755750000 255178706 0 1787011072 -0.3912178874 0.3981971145 0.8573621511 780 31.1600000000 0.0352801494 0.0236790514 0.0471720621 0.0090026165 0.1748120000 255603012 0 1783578624 -0.3990151882 0.3997278810 0.8583412170 781 31.2000000000 0.0353535898 0.0236939995 0.0471720621 0.0089996604 0.3940020000 255609030 0 1782345728 -0.4067389369 0.4022573531 0.8593670130 782 31.2400000000 0.0355484486 0.0237091587 0.0471720621 0.0089945360 0.2923300000 256656104 0 1785143296 -0.4132336974 0.4035587907 0.8610780239 783 31.2800000000 0.0358809642 0.0237247038 0.0471720621 0.0089892341 0.1837590000 257169457 0 1786888192 -0.4189923406 0.4049741924 0.8634447455 784 31.3200000000 0.0339713134 0.0237377734 0.0471720621 0.0089859645 0.2554730000 257091506 0 1781964800 -0.4289910495 0.4071457684 0.8664246798 785 31.3600000000 0.0343519971 0.0237512947 0.0471720621 0.0089805219 0.1710300000 255568186 0 1781788672 -0.4347692728 0.4079215825 0.8678143024 786 31.4000000000 0.0344352871 0.0237648876 0.0471720621 0.0089758261 0.1641600000 255571508 0 1783836672 -0.4420030713 0.4093357623 0.8684105873 787 31.4400000000 0.0352187827 0.0237794415 0.0471720621 0.0089721772 0.1635110000 255570798 0 1785466880 -0.4462372065 0.4115278125 0.8704580069 788 31.4800000000 0.0348940864 0.0237935463 0.0471720621 0.0089685108 0.1640590000 255573640 0 1784217600 -0.4521339536 0.4125782847 0.8721151948 789 31.5200000000 0.0342108905 0.0238067496 0.0471720621 0.0089643956 0.1643030000 255575806 0 1783558144 -0.4580063820 0.4121791720 0.8732615113 790 31.5600000000 0.0350268520 0.0238209522 0.0471720621 0.0089601689 0.1613530000 255575972 0 1782308864 -0.4629473090 0.4133757353 0.8748697042 791 31.6000000000 0.0347901396 0.0238348197 0.0471720621 0.0089547276 0.1564420000 255575254 0 1783853056 -0.4681251049 0.4131746292 0.8749675155 792 31.6400000000 0.0359043628 0.0238500591 0.0471720621 0.0089496196 0.1574800000 255579344 0 1784832000 -0.4714004099 0.4137338996 0.8767072558 793 31.6800000000 0.0354815908 0.0238647268 0.0471720621 0.0089445399 0.1618940000 255581670 0 1786974208 -0.4764126539 0.4129961133 0.8773188591 794 31.7200000000 0.0353115872 0.0238791435 0.0471720621 0.0089451593 0.1595890000 255582524 0 1783218176 -0.4790437222 0.4112083316 0.8786751032 795 31.7600000000 0.0358805656 0.0238942396 0.0471720621 0.0089520130 0.1566020000 255581354 0 1781694464 -0.4825372398 0.4109524786 0.8795452714 796 31.8000000000 0.0360974260 0.0239095703 0.0471720621 0.0089651188 0.1491450000 255578160 0 1783291904 -0.4846165180 0.4098467827 0.8822097778 797 31.8400000000 0.0355712138 0.0239242022 0.0471720621 0.0089788095 0.1526190000 255582870 0 1785069568 -0.4874651134 0.4084575772 0.8839442730 798 31.8800000000 0.0364880972 0.0239399464 0.0471720621 0.0089940605 0.1474810000 255583164 0 1786736640 -0.4910943508 0.4083486795 0.8842949867 799 31.9200000000 0.0364869907 0.0239556499 0.0471720621 0.0090040818 0.1506300000 255585766 0 1782923264 -0.4921490550 0.4060806930 0.8872080445 800 31.9600000000 0.0364881419 0.0239713155 0.0471720621 0.0090055241 0.1521380000 255588828 0 1781817344 -0.4956560731 0.4046356678 0.8878339529 801 32.0000000000 0.0372560248 0.0239879006 0.0471720621 0.0090209409 0.1495490000 255587534 0 1783578624 -0.4951645732 0.4026756287 0.8912365437 802 32.0400000000 0.0357385352 0.0240025523 0.0471720621 0.0090214377 0.1471440000 255591156 0 1785466880 -0.4997685552 0.4000726342 0.8918242455 803 32.0800000000 0.0368461795 0.0240185469 0.0471720621 0.0090313234 0.1442580000 255591474 0 1783980032 -0.4997876883 0.4006860256 0.8946084976 804 32.1199999990 0.0364419483 0.0240339988 0.0471720621 0.0090423651 0.1484840000 255595940 0 1782796288 -0.5006406307 0.3989764452 0.8958901167 805 32.1600000000 0.0366045758 0.0240496145 0.0471720621 0.0090528277 0.1467440000 255596326 0 1781563392 -0.5033092499 0.3982952237 0.8972253799 806 32.2000000000 0.0372542888 0.0240659974 0.0471720621 0.0090673233 0.1693810000 255596836 0 1783582720 -0.5031936169 0.3970884085 0.9000061750 807 32.2400000000 0.0371731035 0.0240822392 0.0471720621 0.0090816386 0.1563470000 255601110 0 1784832000 -0.5047007799 0.3939151764 0.9004329443 808 32.2800000000 0.0365625955 0.0240976852 0.0471720621 0.0090869334 0.1802040000 256027332 0 1786863616 -0.5040048957 0.3904410899 0.9051334858 809 32.3200000000 0.0371685326 0.0241138420 0.0471720621 0.0090912631 0.3854200000 255993930 0 1782108160 -0.5040078163 0.3873337507 0.9074395895 810 32.3600000000 0.0379359685 0.0241309063 0.0471720621 0.0090978168 0.3429150000 257797791 0 1784455168 -0.5057454109 0.3864096403 0.9088940024 811 32.4000000000 0.0373832658 0.0241472471 0.0471720621 0.0090944779 0.2181060000 257722886 0 1782984704 -0.5056099296 0.3815243244 0.9121603966 812 32.4399999990 0.0376679115 0.0241638982 0.0471720621 0.0090930755 0.2781780000 257659086 0 1782501376 -0.5065537095 0.3783676922 0.9138972759 813 32.4800000000 0.0379294232 0.0241808299 0.0471720621 0.0090914412 0.1614270000 255997998 0 1783910400 -0.5073806047 0.3764923513 0.9165757298 814 32.5200000000 0.0383596867 0.0241982487 0.0471720621 0.0090899151 0.1586560000 256001068 0 1785012224 -0.5074138641 0.3737866282 0.9192612767 815 32.5600000000 0.0383459330 0.0242156078 0.0471720621 0.0090867959 0.1593500000 256003150 0 1786802176 -0.5089553595 0.3711943924 0.9216421843 816 32.6000000000 0.0382789150 0.0242328422 0.0471720621 0.0090834694 0.1594180000 256005956 0 1783537664 -0.5087622404 0.3665565550 0.9248862863 817 32.6400000000 0.0375338756 0.0242491226 0.0471720621 0.0090788033 0.1569680000 256005890 0 1782771712 -0.5092528462 0.3623560071 0.9286264777 818 32.6800000000 0.0379141979 0.0242658280 0.0471720621 0.0090736513 0.1577290000 256009360 0 1784516608 -0.5103353262 0.3594044447 0.9318306446 819 32.7200000000 0.0380157381 0.0242826167 0.0471720621 0.0090694830 0.1545440000 256009854 0 1785794560 -0.5119138360 0.3582660556 0.9354621768 820 32.7599999990 0.0381513797 0.0242995298 0.0471720621 0.0090661293 0.1625800000 256012068 0 1784156160 -0.5120397806 0.3554975986 0.9390276670 821 32.7999999990 0.0378963128 0.0243160911 0.0471720621 0.0090675988 0.1539170000 256013138 0 1783390208 -0.5115535259 0.3535092771 0.9451993704 822 32.8400000000 0.0381154753 0.0243328786 0.0471720621 0.0090841116 0.1540480000 256015764 0 1781882880 -0.5127609372 0.3514305949 0.9491380453 823 32.8800000000 0.0378445275 0.0243492962 0.0471720621 0.0090902053 0.1529520000 256018306 0 1783132160 -0.5128491521 0.3489337862 0.9544130564 824 32.9200000000 0.0386857167 0.0243666948 0.0471720621 0.0090953100 0.1519710000 256018732 0 1785151488 -0.5146400332 0.3497626781 0.9599133730 825 32.9600000000 0.0382325053 0.0243835018 0.0471720621 0.0091028360 0.1494850000 256022610 0 1786912768 -0.5139293075 0.3467205763 0.9670953155 826 33.0000000000 0.0383062437 0.0244003574 0.0471720621 0.0091090648 0.1486940000 256022092 0 1783357440 -0.5139180422 0.3451712132 0.9729764462 827 33.0400000000 0.0363762937 0.0244148386 0.0471720621 0.0091157496 0.1492970000 256025386 0 1779961856 -0.5145270228 0.3399384618 0.9795699120 828 33.0800000000 0.0366890132 0.0244296625 0.0471720621 0.0091414501 0.1503090000 256028480 0 1778675712 -0.5159052610 0.3370828032 0.9847099185 829 33.1199999990 0.0402085520 0.0244486961 0.0471720621 0.0091694716 0.1533850000 256034190 0 1777278976 -0.5147628188 0.3365561962 0.9893913269 830 33.1600000000 0.0363873504 0.0244630801 0.0471720621 0.0091736847 0.1933080000 256544016 0 1778565120 -0.5178010464 0.3305497766 0.9968109131 831 33.2000000000 0.0374556705 0.0244787149 0.0471720621 0.0091912288 0.4382790000 256511646 0 1780584448 -0.5176385641 0.3267225027 1.0030810833 832 33.2400000000 0.0376617946 0.0244945600 0.0471720621 0.0091988170 0.3825810000 257468655 0 1785049088 -0.5187039375 0.3233044147 1.0099475384 833 33.2800000000 0.0400332324 0.0245132139 0.0471720621 0.0092031234 0.3215030000 258522912 0 1784786944 -0.5193544626 0.3221061230 1.0152708292 834 33.3200000000 0.0349266864 0.0245257000 0.0471720621 0.0091989421 0.3550770000 258442438 0 1781248000 -0.5206884742 0.3115396500 1.0225301981 835 33.3600000000 0.0362519473 0.0245397435 0.0471720621 0.0092035313 0.1770630000 256524550 0 1782042624 -0.5208526850 0.3095774651 1.0279405117 836 33.4000000000 0.0354721732 0.0245528205 0.0471720621 0.0092093064 0.1821910000 256525320 0 1783685120 -0.5228796005 0.3059535921 1.0349462032 837 33.4399999990 0.0358255990 0.0245662886 0.0471720621 0.0092204785 0.1787620000 256528934 0 1785716736 -0.5235444903 0.3036304116 1.0414354801 838 33.4800000000 0.0357266031 0.0245796064 0.0471720621 0.0092454698 0.1820140000 256532340 0 1784614912 -0.5243034363 0.2989021242 1.0473661423 839 33.5200000000 0.0342720710 0.0245911588 0.0471720621 0.0092642328 0.1792140000 256532406 0 1783574528 -0.5246802568 0.2948901653 1.0543839931 840 33.5600000000 0.0338932127 0.0246022327 0.0471720621 0.0092809634 0.1805390000 256534612 0 1780400128 -0.5266999006 0.2922541201 1.0599792004 841 33.6000000000 0.0356473923 0.0246153660 0.0471720621 0.0092831191 0.1815970000 256538342 0 1776971776 -0.5281138420 0.2919215262 1.0640982389 842 33.6400000000 0.0349458642 0.0246276350 0.0471720621 0.0092803166 0.1764840000 256532776 0 1775828992 -0.5298163891 0.2892533839 1.0695115328 843 33.6800000000 0.0353363492 0.0246403381 0.0471720621 0.0092792884 0.1732790000 256536834 0 1776955392 -0.5313522816 0.2865722775 1.0745271444 844 33.7200000000 0.0348818004 0.0246524726 0.0471720621 0.0092828192 0.1667850000 256538400 0 1778896896 -0.5316159129 0.2811284363 1.0800229311 845 33.7599999990 0.0352188386 0.0246649771 0.0471720621 0.0092897626 0.1709450000 256539730 0 1780637696 -0.5322317481 0.2787499130 1.0854394436 846 33.7999999990 0.0354546048 0.0246777308 0.0471720621 0.0092932697 0.1701760000 256542156 0 1782415360 -0.5328914523 0.2763322294 1.0894129276 847 33.8400000000 0.0340921804 0.0246888459 0.0471720621 0.0092908109 0.1677410000 256539734 0 1784066048 -0.5347697735 0.2704485953 1.0927878618 848 33.8800000000 0.0361695960 0.0247023845 0.0471720621 0.0092859122 0.1678330000 256543724 0 1785462784 -0.5346864462 0.2688069046 1.0962345600 849 33.9200000000 0.0343169868 0.0247137091 0.0471720621 0.0092812138 0.1675520000 256545246 0 1784303616 -0.5367515087 0.2619695663 1.0999467373 850 33.9600000000 0.0344196521 0.0247251279 0.0471720621 0.0092761627 0.1614500000 256544120 0 1783341056 -0.5368384123 0.2579946518 1.1033991575 851 34.0000000000 0.0349955484 0.0247371965 0.0471720621 0.0092707402 0.1646210000 256545218 0 1781559296 -0.5381127000 0.2556141615 1.1063261032 852 34.0400000000 0.0347996019 0.0247490069 0.0471720621 0.0092654836 0.1676740000 256550076 0 1783451648 -0.5387258530 0.2510342002 1.1110485792 853 34.0800000000 0.0356077962 0.0247617370 0.0471720621 0.0092623300 0.1652290000 256550930 0 1785081856 -0.5400459170 0.2477937937 1.1125055552 854 34.1199999990 0.0340995267 0.0247726712 0.0471720621 0.0092592843 0.2075890000 257040156 0 1786859520 -0.5400888324 0.2437334955 1.1169747114 855 34.1600000000 0.0346127003 0.0247841800 0.0471720621 0.0092590168 0.4475090000 256999150 0 1783373824 -0.5406293273 0.2415687144 1.1206774712 856 34.2000000000 0.0354784727 0.0247966733 0.0471720621 0.0092583307 0.3846130000 257836967 0 1787449344 -0.5405817628 0.2394532114 1.1232742071 857 34.2400000000 0.0354067758 0.0248090538 0.0471720621 0.0092534734 0.3353910000 259103136 0 1784389632 -0.5419533253 0.2384274602 1.1258327961 858 34.2800000000 0.0369087309 0.0248231560 0.0471720621 0.0092489837 0.1960590000 259135983 0 1786122240 -0.5425394177 0.2376586348 1.1279752254 859 34.3200000000 0.0355546549 0.0248356490 0.0471720621 0.0092451268 0.3291470000 259060840 0 1779552256 -0.5413072705 0.2290508896 1.1286789179 860 34.3600000000 0.0357408524 0.0248483295 0.0471720621 0.0092398760 0.1764140000 257005968 0 1779744768 -0.5415593386 0.2244574726 1.1305587292 861 34.4000000000 0.0360510983 0.0248613408 0.0471720621 0.0092355704 0.1699380000 257005242 0 1782042624 -0.5409215689 0.2216219455 1.1344403028 862 34.4400000000 0.0351941437 0.0248733279 0.0471720621 0.0092308162 0.1701520000 257006064 0 1783435264 -0.5423474908 0.2169483155 1.1353125572 863 34.4800000000 0.0349225774 0.0248849724 0.0471720621 0.0092255411 0.1711450000 257009202 0 1785196544 -0.5412423015 0.2097069323 1.1363130808 864 34.5200000000 0.0359484851 0.0248977774 0.0471720621 0.0092210506 0.1677670000 257008636 0 1784074240 -0.5407970548 0.2079276592 1.1389267445 865 34.5600000000 0.0349474922 0.0249093956 0.0471720621 0.0092163242 0.1657160000 257009482 0 1782800384 -0.5434688926 0.2061511129 1.1393719912 866 34.6000000000 0.0363379717 0.0249225925 0.0471720621 0.0092133872 0.1638170000 257009284 0 1781768192 -0.5427846313 0.2059900463 1.1420164108 867 34.6400000000 0.0355957448 0.0249349030 0.0471720621 0.0092099927 0.1698170000 257014746 0 1783439360 -0.5435142517 0.2028820217 1.1434261799 868 34.6800000000 0.0365632251 0.0249482997 0.0471720621 0.0092057708 0.1639090000 257014848 0 1784958976 -0.5434326530 0.1998105943 1.1439362764 869 34.7200000000 0.0344763584 0.0249592641 0.0471720621 0.0092014179 0.1703060000 257019374 0 1786720256 -0.5439746976 0.1944622397 1.1445504427 870 34.7600000000 0.0358940251 0.0249718327 0.0471720621 0.0091967917 0.1692830000 257020052 0 1782800384 -0.5445111990 0.1934388578 1.1451038122 871 34.8000000000 0.0346606560 0.0249829565 0.0471720621 0.0091917814 0.1640270000 257020506 0 1781784576 -0.5459553599 0.1904983222 1.1460826397 872 34.8400000000 0.0346794240 0.0249940763 0.0471720621 0.0091872823 0.1627860000 257023860 0 1783418880 -0.5469722748 0.1875162274 1.1471347809 873 34.8800000000 0.0340514556 0.0250044513 0.0471720621 0.0091826250 0.1659210000 257025150 0 1784807424 -0.5484998226 0.1850443929 1.1476174593 874 34.9200000000 0.0353972092 0.0250163424 0.0471720621 0.0091785986 0.1578380000 257025052 0 1786482688 -0.5475509763 0.1850541234 1.1502283812 875 34.9600000000 0.0357435122 0.0250286020 0.0471720621 0.0091749036 0.1645720000 257027714 0 1783033856 -0.5501474738 0.1858504862 1.1505157948 876 35.0000000000 0.0357348435 0.0250408237 0.0471720621 0.0091701949 0.1610980000 257029028 0 1781268480 -0.5504812002 0.1847513616 1.1519275904 877 35.0400000000 0.0352962799 0.0250525175 0.0471720621 0.0091650390 0.1576710000 257029966 0 1782403072 -0.5521227717 0.1843728572 1.1532303095 878 35.0800000000 0.0347485505 0.0250635608 0.0471720621 0.0091599945 0.1571590000 257030588 0 1784672256 -0.5528398156 0.1839883178 1.1550836563 879 35.1200000000 0.0338329747 0.0250735374 0.0471720621 0.0091551847 0.1558380000 257033358 0 1786339328 -0.5545834899 0.1819861233 1.1552987099 880 35.1600000000 0.0351478830 0.0250849855 0.0471720621 0.0091505529 0.1589120000 257034180 0 1784840192 -0.5546363592 0.1845327467 1.1574580669 881 35.2000000000 0.0351191945 0.0250963751 0.0471720621 0.0091465025 0.1579350000 257037394 0 1786871808 -0.5552220345 0.1839592159 1.1584385633 882 35.2400000000 0.0352923088 0.0251079351 0.0471720621 0.0091420974 0.1880680000 257038124 0 1783562240 -0.5541695952 0.1803524196 1.1601960659 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_living_room_traj3_loop.log ================================================ SLAMBench Report run started: 2018-02-18 06:35:09 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_living_room_traj3_loop.log input: datasets/ICL_NUIM/living_room_traj3_loop.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: RGB-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.751875,1,0.4992185,0.4989583 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 0.0000000000 0.0000000000 0.0000000000 0.0000000000 nan 0.1691740000 225847256 0 1771155456 0.0000000000 0.0000000000 0.0000000000 2 0.0400000000 0.0010897097 0.0005448548 0.0010897097 0.0014839020 0.2291410000 229438938 0 1771220992 -0.0012844919 0.0042652939 0.0021963941 3 0.0800000000 0.0013292350 0.0008063149 0.0013292350 0.0015329618 0.1909380000 229373516 0 1773096960 -0.0012266875 -0.0029063171 0.0019270806 4 0.1200000000 0.0019475541 0.0010916247 0.0019475541 0.0020683224 0.1849420000 229374394 0 1774854144 -0.0015680999 -0.0003982396 -0.0003852027 5 0.1600000000 0.0004263747 0.0009585747 0.0019475541 0.0042795138 0.1794700000 229378716 0 1776885760 -0.0010454102 0.0050546336 0.0031648702 6 0.2000000000 0.0014089583 0.0010336386 0.0019475541 0.0044040737 0.1903340000 229378686 0 1778155520 0.0021619396 -0.0037960541 0.0031455329 7 0.2400000000 0.0033068131 0.0013583778 0.0033068131 0.0044113168 0.1866250000 229384432 0 1780187136 0.0035648961 -0.0122877341 0.0003435582 8 0.2800000000 0.0021067387 0.0014519230 0.0033068131 0.0041722849 0.1853840000 229384406 0 1781837824 0.0010523186 -0.0115250954 -0.0014175348 9 0.3200000000 0.0034815895 0.0016774415 0.0034815895 0.0049296663 0.1837610000 229386488 0 1783599104 0.0008803632 -0.0065985434 0.0012371071 10 0.3600000000 0.0030050520 0.0018102025 0.0034815895 0.0046584793 0.1880240000 229390906 0 1785266176 -0.0006643084 -0.0152667994 -0.0002088121 11 0.4000000000 0.0036626898 0.0019786104 0.0036626898 0.0044876190 0.1882050000 229392908 0 1783869440 -0.0006999715 -0.0104615688 -0.0011614891 12 0.4400000000 0.0013733611 0.0019281730 0.0036626898 0.0046174564 0.1826650000 229395402 0 1782722560 -0.0022540195 -0.0019266580 0.0012917893 13 0.4800000000 0.0014250341 0.0018894700 0.0036626898 0.0044215678 0.1800800000 229395556 0 1778917376 0.0011247306 -0.0051611462 0.0011935129 14 0.5200000000 0.0008290971 0.0018137291 0.0036626898 0.0044185953 0.1788860000 229396950 0 1777410048 0.0023454896 -0.0124667129 -0.0007519674 15 0.5600000000 0.0037759738 0.0019445454 0.0037759738 0.0044727263 0.1766640000 229399892 0 1778806784 0.0069665448 -0.0080516525 -0.0010445147 16 0.6000000000 0.0013666431 0.0019084265 0.0037759738 0.0044264314 0.1827060000 229402722 0 1780715520 0.0054885093 -0.0098581035 -0.0002116395 17 0.6400000000 0.0028192920 0.0019620068 0.0037759738 0.0043319377 0.1845990000 229401824 0 1782345728 0.0086121270 -0.0126774013 -0.0025703153 18 0.6800000000 0.0004475505 0.0018778704 0.0037759738 0.0042744496 0.1860190000 229407242 0 1784123392 0.0050970879 -0.0129319914 -0.0047337683 19 0.7200000000 0.0035743257 0.0019671575 0.0037759738 0.0043185139 0.1808190000 229409408 0 1785774080 0.0059073344 -0.0051843189 -0.0038469264 20 0.7600000000 0.0018366415 0.0019606317 0.0037759738 0.0046066551 0.1799110000 229409846 0 1785028608 0.0038627568 -0.0093244649 -0.0062140473 21 0.8000000000 0.0014608994 0.0019368349 0.0037759738 0.0047773431 0.1820460000 229412044 0 1786814464 0.0078258682 -0.0055387965 -0.0060994127 22 0.8400000000 0.0018678652 0.0019336999 0.0037759738 0.0047223703 0.1917820000 229414774 0 1783390208 0.0094478577 -0.0031012180 -0.0056509222 23 0.8800000000 0.0015659926 0.0019177127 0.0037759738 0.0046811940 0.1929540000 229415336 0 1779695616 0.0115567809 -0.0095785856 -0.0093213292 24 0.9200000000 0.0011029402 0.0018837638 0.0037759738 0.0046493189 0.1802200000 229417742 0 1781092352 0.0117116962 -0.0089901583 -0.0095319459 25 0.9600000000 0.0013806415 0.0018636389 0.0037759738 0.0045675526 0.1808020000 229418544 0 1783148544 0.0129484013 -0.0108677503 -0.0131272059 26 1.0000000000 0.0020260806 0.0018698867 0.0037759738 0.0044852229 0.1909770000 229423098 0 1784750080 0.0118004605 -0.0120713282 -0.0122739878 27 1.0400000000 0.0007452878 0.0018282349 0.0037759738 0.0044141175 0.1857840000 229425596 0 1786781696 0.0121284649 -0.0161258858 -0.0160607658 28 1.0800000000 0.0027112076 0.0018597696 0.0037759738 0.0043560477 0.1838760000 229427586 0 1782861824 0.0094645070 -0.0165056232 -0.0178513005 29 1.1200000000 0.0022842360 0.0018744064 0.0037759738 0.0043965697 0.1845920000 229429044 0 1781489664 0.0133955711 -0.0190797914 -0.0184712559 30 1.1600000000 0.0022026566 0.0018853480 0.0037759738 0.0043748106 0.1812080000 229432742 0 1783468032 0.0167246331 -0.0184581913 -0.0185844842 31 1.2000000000 0.0024676572 0.0019041322 0.0037759738 0.0043599350 0.1847600000 229433844 0 1785262080 0.0223955289 -0.0177642498 -0.0206158571 32 1.2400000000 0.0012918083 0.0018849971 0.0037759738 0.0044153818 0.1728330000 229436394 0 1786654720 0.0211895332 -0.0144908605 -0.0225620456 33 1.2800000000 0.0029378247 0.0019169010 0.0037759738 0.0046121947 0.1835210000 229441880 0 1782849536 0.0225998797 -0.0091091543 -0.0207041465 34 1.3200000000 0.0018362683 0.0019145294 0.0037759738 0.0048116859 0.1808640000 229450426 0 1781858304 0.0309542567 -0.0081882309 -0.0232106112 35 1.3600000000 0.0016857549 0.0019079930 0.0037759738 0.0047480219 0.1806180000 229454116 0 1781080064 0.0287817959 -0.0103555433 -0.0244356412 36 1.4000000000 0.0013182574 0.0018916115 0.0037759738 0.0046886404 0.1788850000 229456370 0 1780584448 0.0288975723 -0.0126282750 -0.0284155514 37 1.4400000000 0.0015897738 0.0018834537 0.0037759738 0.0046292162 0.1788760000 229457816 0 1780064256 0.0310113616 -0.0130180046 -0.0310204420 38 1.4800000000 0.0015914938 0.0018757705 0.0037759738 0.0045696812 0.1762010000 229461278 0 1781719040 0.0316874310 -0.0146699455 -0.0307779089 39 1.5200000000 0.0019619602 0.0018779805 0.0037759738 0.0045204681 0.1774000000 229464344 0 1783369728 0.0312314387 -0.0124671813 -0.0318422467 40 1.5600000000 0.0019554824 0.0018799181 0.0037759738 0.0047102442 0.1838040000 229465482 0 1785257984 0.0366277806 -0.0114576938 -0.0325154625 41 1.6000000000 0.0037432478 0.0019253651 0.0037759738 0.0048851251 0.1738790000 229468540 0 1786892288 0.0404062644 -0.0079400772 -0.0323721990 42 1.6400000000 0.0030582820 0.0019523393 0.0037759738 0.0048431683 0.1746040000 229474338 0 1783631872 0.0404191241 -0.0087510422 -0.0340900309 43 1.6800000000 0.0036781225 0.0019924738 0.0037759738 0.0048282433 0.1765200000 229476292 0 1782472704 0.0438616015 -0.0076358989 -0.0363855585 44 1.7200000000 0.0048520160 0.0020574634 0.0048520160 0.0047930762 0.1679090000 229479482 0 1784877056 0.0420278609 -0.0073033771 -0.0356349833 45 1.7600000000 0.0048567643 0.0021196701 0.0048567643 0.0049612840 0.1731990000 229481196 0 1784410112 0.0438816026 -0.0056207897 -0.0369635448 46 1.8000000000 0.0035262068 0.0021502470 0.0048567643 0.0050744816 0.1675830000 229484102 0 1783349248 0.0468560271 -0.0059192725 -0.0369519964 47 1.8400000000 0.0077226362 0.0022688085 0.0077226362 0.0050507409 0.1678900000 229487820 0 1782603776 0.0448390283 -0.0016221177 -0.0359001420 48 1.8800000000 0.0056115906 0.0023384498 0.0077226362 0.0050552591 0.1690880000 229489250 0 1784377344 0.0482172519 -0.0023151450 -0.0362273194 49 1.9200000000 0.0022988301 0.0023376412 0.0077226362 0.0050880648 0.1652150000 229492396 0 1786281984 0.0533936135 -0.0045997188 -0.0405771136 50 1.9600000000 0.0040996871 0.0023728821 0.0077226362 0.0050561303 0.1745670000 229494838 0 1784627200 0.0454712585 -0.0039036344 -0.0409325175 51 2.0000000000 0.0031924662 0.0023889524 0.0077226362 0.0050953139 0.1663950000 229500056 0 1784115200 0.0449715033 -0.0008877285 -0.0417690948 52 2.0400000000 0.0017219143 0.0023761247 0.0077226362 0.0050916143 0.1701180000 229501122 0 1785499648 0.0490240268 -0.0009215187 -0.0419294797 53 2.0800000000 0.0032461076 0.0023925395 0.0077226362 0.0050521170 0.1804050000 229504812 0 1784893440 0.0487607718 -0.0036841664 -0.0437868610 54 2.1200000000 0.0013847256 0.0023738763 0.0077226362 0.0051125232 0.2058170000 229507070 0 1784500224 0.0496721752 -0.0060387338 -0.0452425480 55 2.1600000000 0.0038494065 0.0024007041 0.0077226362 0.0051082868 0.1600990000 229509508 0 1786519552 0.0517266281 0.0001721758 -0.0440374352 56 2.2000000000 0.0025977294 0.0024042224 0.0077226362 0.0050954149 0.1660160000 229512410 0 1783615488 0.0505242348 -0.0013365813 -0.0448669642 57 2.2400000000 0.0010359169 0.0023802171 0.0077226362 0.0051704012 0.1657880000 229513572 0 1781702656 0.0510517284 -0.0069666333 -0.0485932045 58 2.2800000000 0.0030591763 0.0023919233 0.0077226362 0.0053405552 0.1681040000 229516922 0 1781071872 0.0554818846 -0.0078781303 -0.0481559895 59 2.3200000000 0.0003291253 0.0023569606 0.0077226362 0.0054704558 0.1624240000 229520136 0 1782472704 0.0585027561 -0.0021138894 -0.0479200222 60 2.3600000000 0.0013192288 0.0023396650 0.0077226362 0.0055072003 0.1650040000 229523310 0 1784504320 0.0610090792 -0.0068758754 -0.0510834977 61 2.4000000000 0.0037063507 0.0023620697 0.0077226362 0.0055190936 0.1868030000 229950269 0 1786281984 0.0607343167 -0.0127947154 -0.0517351814 62 2.4400000000 0.0029980894 0.0023723281 0.0077226362 0.0055247184 0.2689000000 230310583 0 1784393728 0.0610116757 -0.0090041738 -0.0515308306 63 2.4800000000 0.0035030378 0.0023902759 0.0077226362 0.0055577473 0.3964530000 231116295 0 1786961920 0.0672620311 -0.0084432643 -0.0513378121 64 2.5200000000 0.0104761040 0.0025166169 0.0104761040 0.0057433881 0.2877540000 230989222 0 1783857152 0.0804557353 -0.0037942876 -0.0550852120 65 2.5600000000 0.0118288882 0.0026598827 0.0118288882 0.0057263744 0.1786050000 230276148 0 1783443456 0.0838192850 -0.0038204514 -0.0565069355 66 2.6000000000 0.0101396954 0.0027732132 0.0118288882 0.0056860266 0.1812640000 230290458 0 1785753600 0.0792589113 -0.0086742323 -0.0575272515 67 2.6400000000 0.0114768548 0.0029031183 0.0118288882 0.0057061879 0.1860970000 230292984 0 1784840192 0.0812702030 -0.0107793584 -0.0601821989 68 2.6800000000 0.0092759700 0.0029968367 0.0118288882 0.0057758069 0.1785470000 230295874 0 1786880000 0.0847110823 -0.0147218527 -0.0592478588 69 2.7200000000 0.0102760354 0.0031023323 0.0118288882 0.0057723224 0.1814450000 230297316 0 1783562240 0.0850989372 -0.0105729541 -0.0601306371 70 2.7600000000 0.0107715279 0.0032118922 0.0118288882 0.0058072418 0.1767230000 230299970 0 1781567488 0.0889658108 -0.0099418852 -0.0611674003 71 2.8000000000 0.0104827164 0.0033142982 0.0118288882 0.0058417735 0.1769050000 230303180 0 1781301248 0.0912318528 -0.0094327806 -0.0636114478 72 2.8400000000 0.0111651244 0.0034233375 0.0118288882 0.0058625129 0.1752090000 230305238 0 1783193600 0.0947140381 -0.0115415631 -0.0645052269 73 2.8800000000 0.0095049553 0.0035066473 0.0118288882 0.0059103885 0.1751930000 230306264 0 1784971264 0.0957541689 -0.0097419610 -0.0673055127 74 2.9200000000 0.0101321265 0.0035961808 0.0118288882 0.0059820585 0.1742400000 230309446 0 1786605568 0.0976142138 -0.0083936322 -0.0701092854 75 2.9600000000 0.0130221918 0.0037218609 0.0130221918 0.0060265158 0.2008830000 230673197 0 1783328768 0.1053773537 -0.0067241103 -0.0725135580 76 3.0000000000 0.0102055147 0.0038071722 0.0130221918 0.0060264393 0.3942540000 230892125 0 1785061376 0.1056820303 -0.0054546464 -0.0729632452 77 3.0400000000 0.0092121325 0.0038773665 0.0130221918 0.0060393786 0.1958800000 231483067 0 1785434112 0.1072847322 -0.0049020196 -0.0729086101 78 3.0800000000 0.0132596027 0.0039976515 0.0132596027 0.0060842668 0.2084490000 231218976 0 1783566336 0.1165132523 -0.0145580778 -0.0804336220 79 3.1200000000 0.0112635558 0.0040896250 0.0132596027 0.0060743015 0.1656020000 230641136 0 1783873536 0.1172909066 -0.0078497734 -0.0804178044 80 3.1600000000 0.0108098947 0.0041736284 0.0132596027 0.0060675671 0.1704100000 230642302 0 1785774080 0.1217105091 -0.0117772073 -0.0830982774 81 3.2000000000 0.0118283080 0.0042681306 0.0132596027 0.0060479392 0.1691690000 230645140 0 1784143872 0.1285618693 -0.0137118734 -0.0838988274 82 3.2400000000 0.0101254713 0.0043395616 0.0132596027 0.0060175694 0.1919800000 231021631 0 1782734848 0.1308928430 -0.0162105151 -0.0862439051 83 3.2800000000 0.0092897033 0.0043992019 0.0132596027 0.0060095944 0.3942500000 231023584 0 1780334592 0.1309805959 -0.0113372467 -0.0867268145 84 3.3200000000 0.0123473471 0.0044938226 0.0132596027 0.0059919795 0.2850830000 232008209 0 1784627200 0.1407945454 -0.0133436974 -0.0917718336 85 3.3600000000 0.0124055566 0.0045869019 0.0132596027 0.0059582130 0.2605470000 231955776 0 1786347520 0.1512924284 -0.0106593082 -0.0926350355 86 3.4000000000 0.0099308472 0.0046490408 0.0132596027 0.0059737257 0.1900020000 230999594 0 1783918592 0.1517149806 -0.0108688986 -0.0942183882 87 3.4400000000 0.0150182610 0.0047682272 0.0150182610 0.0059522735 0.1752590000 231000076 0 1782493184 0.1588314325 -0.0112913270 -0.0984441265 88 3.4800000000 0.0139480345 0.0048725432 0.0150182610 0.0059362596 0.1737710000 231001962 0 1784422400 0.1628074348 -0.0052972543 -0.0988498405 89 3.5200000000 0.0137220677 0.0049719760 0.0150182610 0.0059190238 0.1739830000 231005920 0 1785798656 0.1657488048 -0.0067783017 -0.1004267335 90 3.5600000000 0.0162885450 0.0050977157 0.0162885450 0.0058936407 0.1728890000 231005978 0 1785073664 0.1712512672 -0.0060919053 -0.1023510247 91 3.6000000000 0.0129105533 0.0051835711 0.0162885450 0.0059242106 0.1659540000 231008772 0 1786834944 0.1742352843 -0.0084786406 -0.1028456837 92 3.6400000000 0.0139602916 0.0052789702 0.0162885450 0.0060081327 0.1712010000 231012110 0 1784299520 0.1848903447 -0.0056168041 -0.1020753086 93 3.6800000000 0.0129347891 0.0053612908 0.0162885450 0.0059956466 0.1670440000 231016256 0 1783418880 0.1915515959 0.0017125604 -0.1040030569 94 3.7200000000 0.0107522132 0.0054186411 0.0162885450 0.0059808481 0.1904940000 231395031 0 1784918016 0.1975358129 -0.0021737188 -0.1072368994 95 3.7600000000 0.0105700353 0.0054728663 0.0162885450 0.0059523977 0.3931580000 231406540 0 1785036800 0.2036612928 -0.0012515883 -0.1092192754 96 3.8000000000 0.0064672017 0.0054832239 0.0162885450 0.0059563679 0.3458610000 232685949 0 1785352192 0.2075721323 -0.0022798427 -0.1090415791 97 3.8400000000 0.0088346656 0.0055177749 0.0162885450 0.0059344530 0.2233800000 232627539 0 1783783424 0.2175484151 -0.0003905357 -0.1131663173 98 3.8800000000 0.0121562351 0.0055855143 0.0162885450 0.0059087788 0.2362650000 232554434 0 1784201216 0.2288624942 -0.0044984920 -0.1148268357 99 3.9200000000 0.0113312807 0.0056435523 0.0162885450 0.0059589534 0.1704670000 231412592 0 1785475072 0.2366627008 0.0016108819 -0.1148138568 100 3.9600000000 0.0146949450 0.0057340662 0.0162885450 0.0059345988 0.1730320000 231415874 0 1784434688 0.2475958765 -0.0016564227 -0.1177847385 101 4.0000000000 0.0140793743 0.0058166930 0.0162885450 0.0059266283 0.1750050000 231417108 0 1784156160 0.2558389604 0.0011587240 -0.1182267964 102 4.0400000000 0.0125352889 0.0058825616 0.0162885450 0.0059462474 0.2124810000 231420626 0 1780617216 0.2586295605 0.0019328658 -0.1205588728 103 4.0800000000 0.0123073431 0.0059449382 0.0162885450 0.0059197595 0.1691630000 231420900 0 1782628352 0.2663627565 0.0068058362 -0.1190787852 104 4.1200000000 0.0149080083 0.0060311215 0.0162885450 0.0058952985 0.1819530000 231423402 0 1783652352 0.2795542181 0.0055963970 -0.1211483777 105 4.1600000000 0.0200794991 0.0061649156 0.0200794991 0.0058716813 0.1652170000 231424972 0 1785446400 0.2908344567 0.0068417857 -0.1237043589 106 4.2000000000 0.0132629797 0.0062318785 0.0200794991 0.0059244633 0.1761400000 231427790 0 1783644160 0.2919679284 0.0053401343 -0.1221290454 107 4.2400000000 0.0163244624 0.0063262017 0.0200794991 0.0059008075 0.1657520000 231427736 0 1783037952 0.3023748994 0.0071717212 -0.1249267980 108 4.2800000000 0.0159493331 0.0064153047 0.0200794991 0.0058785948 0.2002790000 231822403 0 1781780480 0.3105869889 0.0056087608 -0.1274453700 109 4.3200000000 0.0153100388 0.0064969078 0.0200794991 0.0058588339 0.4204060000 231831629 0 1781649408 0.3267349601 0.0018972196 -0.1300140321 110 4.3600000000 0.0187583491 0.0066083755 0.0200794991 0.0058732664 0.3579860000 232199694 0 1785257984 0.3421596289 0.0071236035 -0.1320250630 111 4.4000000000 0.0140939672 0.0066758132 0.0200794991 0.0058551290 0.3035510000 233205592 0 1783967744 0.3474064171 0.0043332865 -0.1327494681 112 4.4400000000 0.0126317339 0.0067289911 0.0200794991 0.0058366792 0.3391670000 233124554 0 1783697408 0.3517187834 -0.0004213483 -0.1352482736 113 4.4800000000 0.0117461141 0.0067733904 0.0200794991 0.0058122597 0.1831080000 231835177 0 1785405440 0.3594109416 -0.0016269514 -0.1363010556 114 4.5200000000 0.0143817095 0.0068401300 0.0200794991 0.0058116503 0.1731860000 231836291 0 1784377344 0.3736485839 -0.0002350139 -0.1363944113 115 4.5600000000 0.0140637364 0.0069029440 0.0200794991 0.0058001476 0.1693150000 231838645 0 1783140352 0.3826800287 -0.0047400659 -0.1386015117 116 4.6000000000 0.0132464645 0.0069576295 0.0200794991 0.0057753840 0.1955200000 232254503 0 1781993472 0.3899144530 -0.0066103213 -0.1400694549 117 4.6400000000 0.0156286340 0.0070317407 0.0200794991 0.0057831312 0.4302330000 232255357 0 1782231040 0.3987289071 -0.0098346043 -0.1434820890 118 4.6800000000 0.0137884077 0.0070890006 0.0200794991 0.0057807134 0.3780320000 232337647 0 1783103488 0.4065510333 -0.0090797059 -0.1427006721 119 4.7200000000 0.0141891390 0.0071486656 0.0200794991 0.0058249129 0.3095280000 233956428 0 1784934400 0.4214151502 -0.0073082549 -0.1403109431 120 4.7600000000 0.0153345680 0.0072168815 0.0200794991 0.0058074931 0.2330240000 233840558 0 1784565760 0.4330415428 -0.0094354600 -0.1392033994 121 4.8000000000 0.0134512223 0.0072684049 0.0200794991 0.0058241031 0.3347950000 233800452 0 1783508992 0.4411475658 -0.0056013260 -0.1386091709 122 4.8400000000 0.0130627947 0.0073158999 0.0200794991 0.0058210960 0.2505570000 232632851 0 1783521280 0.4495310485 -0.0044010570 -0.1394221485 123 4.8800000000 0.0120337568 0.0073542565 0.0200794991 0.0057974898 0.4161190000 232642137 0 1784836096 0.4596082568 -0.0013692128 -0.1373977065 124 4.9200000000 0.0139476946 0.0074074294 0.0200794991 0.0057777009 0.3685240000 232734511 0 1786601472 0.4678453803 -0.0030553695 -0.1349074394 125 4.9600000000 0.0136571955 0.0074574275 0.0200794991 0.0057683882 0.3537230000 234504728 0 1782632448 0.4716318250 -0.0031021973 -0.1319435239 126 5.0000000000 0.0123903016 0.0074965773 0.0200794991 0.0057505703 0.2569070000 234472698 0 1781133312 0.4793567359 -0.0045148721 -0.1302755028 127 5.0400000000 0.0123137590 0.0075345079 0.0200794991 0.0057475348 0.3804680000 234332972 0 1777385472 0.4897098541 0.0007689474 -0.1267650276 128 5.0800000000 0.0127325365 0.0075751175 0.0200794991 0.0057392586 0.1907950000 232648995 0 1777905664 0.5017099380 0.0032627704 -0.1230216622 129 5.1200000000 0.0123160891 0.0076118692 0.0200794991 0.0057336351 0.1702190000 232651041 0 1779937280 0.5131254196 0.0013510315 -0.1190097332 130 5.1600000000 0.0107633118 0.0076361110 0.0200794991 0.0057171317 0.1643400000 232673679 0 1781530624 0.5177483559 0.0045709908 -0.1164758950 131 5.2000000000 0.0133314440 0.0076795869 0.0200794991 0.0057273164 0.1845990000 233039173 0 1783320576 0.5271064043 0.0011601094 -0.1151962727 132 5.2400000000 0.0133687919 0.0077226869 0.0200794991 0.0057123500 0.4060400000 233048056 0 1785139200 0.5378101468 0.0028878143 -0.1112025380 133 5.2800000000 0.0119850598 0.0077547348 0.0200794991 0.0056935160 0.3653630000 233049446 0 1784573952 0.5470489860 0.0048212949 -0.1053860635 134 5.3200000000 0.0159685258 0.0078160318 0.0200794991 0.0057006959 0.3443630000 233792379 0 1784619008 0.5595233440 0.0024167430 -0.1051666737 135 5.3600000000 0.0159410555 0.0078762171 0.0200794991 0.0057194011 0.3070700000 235127614 0 1783386112 0.5690740943 0.0052317567 -0.1015235782 136 5.4000000000 0.0166389234 0.0079406488 0.0200794991 0.0057417052 0.1976390000 235004339 0 1784365056 0.5836365223 0.0140123498 -0.0953484327 137 5.4400000000 0.0096597355 0.0079531969 0.0200794991 0.0057578645 0.3244430000 234927484 0 1782050816 0.5818713903 0.0180315580 -0.0889887363 138 5.4800000000 0.0099022994 0.0079673208 0.0200794991 0.0057943780 0.1641160000 233052396 0 1782329344 0.5862295032 0.0150034428 -0.0868050158 139 5.5200000000 0.0094184224 0.0079777604 0.0200794991 0.0057747755 0.1911770000 233053662 0 1784475648 0.5947042108 0.0152257830 -0.0816610456 140 5.5600000000 0.0093598561 0.0079876325 0.0200794991 0.0057618871 0.1620070000 233055180 0 1785729024 0.6025540233 0.0135073829 -0.0777221173 141 5.6000000000 0.0084982067 0.0079912536 0.0200794991 0.0057451336 0.1922710000 233378530 0 1784823808 0.6095994115 0.0122290514 -0.0725615472 142 5.6400000000 0.0076744189 0.0079890224 0.0200794991 0.0057368288 0.4006520000 233426844 0 1784446976 0.6209951639 0.0168223847 -0.0663412958 143 5.6800000000 0.0077176928 0.0079871250 0.0200794991 0.0057263823 0.3671530000 233429154 0 1786118144 0.6299993396 0.0199742261 -0.0606456250 144 5.7200000000 0.0079394709 0.0079867940 0.0200794991 0.0057340768 0.3296750000 233770319 0 1784852480 0.6360632777 0.0173174795 -0.0570237935 145 5.7600000000 0.0084146094 0.0079897445 0.0200794991 0.0057178928 0.2777480000 235689053 0 1784598528 0.6445809603 0.0180021189 -0.0516330004 146 5.8000000000 0.0096429698 0.0080010679 0.0200794991 0.0057024344 0.2250120000 235566566 0 1783906304 0.6550558209 0.0211067479 -0.0469892919 147 5.8400000000 0.0072006243 0.0079956227 0.0200794991 0.0056847289 0.3841120000 235466348 0 1780432896 0.6624327898 0.0255278852 -0.0391970277 148 5.8800000000 0.0078762555 0.0079948162 0.0200794991 0.0057096225 0.1713360000 233436508 0 1780789248 0.6666795611 0.0227076299 -0.0360217690 149 5.9200000000 0.0058876011 0.0079806738 0.0200794991 0.0056943543 0.1653360000 233438230 0 1782521856 0.6708173752 0.0228873491 -0.0307600796 150 5.9600000000 0.0063275052 0.0079696527 0.0200794991 0.0057021953 0.1668750000 233440904 0 1784152064 0.6798119545 0.0264834408 -0.0233326256 151 6.0000000000 0.0064483220 0.0079595777 0.0200794991 0.0056935904 0.1686350000 233439826 0 1785802752 0.6877877116 0.0289968699 -0.0186806619 152 6.0400000000 0.0059689302 0.0079464813 0.0200794991 0.0056947944 0.1679350000 233440760 0 1784172544 0.7000602484 0.0263262354 -0.0096260905 153 6.0800000000 0.0064741918 0.0079368585 0.0200794991 0.0057097459 0.1628980000 233441118 0 1783406592 0.7081415653 0.0298561715 -0.0057709813 154 6.1200000000 0.0070362119 0.0079310101 0.0200794991 0.0056930648 0.1826790000 233791496 0 1782263808 0.7153197527 0.0323072337 0.0003138185 155 6.1600000000 0.0066988273 0.0079230606 0.0200794991 0.0056922241 0.3840290000 233784358 0 1784975360 0.7185589671 0.0341805406 0.0045873225 156 6.2000000000 0.0070395409 0.0079173970 0.0200794991 0.0056962828 0.3437340000 233787880 0 1786437632 0.7282330394 0.0342026427 0.0102138817 157 6.2400000000 0.0061659203 0.0079062411 0.0200794991 0.0057093477 0.3573760000 233898794 0 1784696832 0.7341331244 0.0349233299 0.0165182948 158 6.2800000000 0.0092245629 0.0079145849 0.0200794991 0.0057069801 0.2810060000 236172807 0 1784336384 0.7410557270 0.0356357582 0.0198169351 159 6.3200000000 0.0094942031 0.0079245196 0.0200794991 0.0057277112 0.2526830000 236097904 0 1781080064 0.7485882044 0.0372928381 0.0263133943 160 6.3600000000 0.0097474093 0.0079359127 0.0200794991 0.0057785713 0.1746860000 236063935 0 1782927360 0.7625963688 0.0417270437 0.0416311026 161 6.4000000000 0.0082735261 0.0079380096 0.0200794991 0.0057882605 0.3461650000 235988600 0 1781321728 0.7647716999 0.0451885834 0.0483336747 162 6.4400000000 0.0072254781 0.0079336113 0.0200794991 0.0057783704 0.1627540000 233792820 0 1781411840 0.7695199251 0.0452779159 0.0568881631 163 6.4800000000 0.0095340787 0.0079434301 0.0200794991 0.0057781211 0.1621840000 233794170 0 1783418880 0.7779843807 0.0486425757 0.0643989146 164 6.5200000000 0.0082264272 0.0079451557 0.0200794991 0.0057944592 0.1596090000 233794016 0 1785196544 0.7845997214 0.0469381884 0.0722891688 165 6.5600000000 0.0090075769 0.0079515946 0.0200794991 0.0057933180 0.1587050000 233797974 0 1786466304 0.7938925028 0.0505547896 0.0810198784 166 6.6000000000 0.0094082477 0.0079603696 0.0200794991 0.0058132803 0.1551120000 233795216 0 1783328768 0.8021924496 0.0534224398 0.0894964039 167 6.6400000000 0.0104671130 0.0079753801 0.0200794991 0.0058467016 0.1585710000 233795934 0 1782435840 0.8075404167 0.0556834862 0.0973811448 168 6.6800000000 0.0101281041 0.0079881939 0.0200794991 0.0058473617 0.1853060000 234179968 0 1784311808 0.8145159483 0.0584075376 0.1067818701 169 6.7200000000 0.0120251086 0.0080120810 0.0200794991 0.0058388592 0.4154680000 234170074 0 1783500800 0.8249473572 0.0615858138 0.1163427532 170 6.7600000000 0.0080938721 0.0080125621 0.0200794991 0.0058619934 0.3748440000 234173436 0 1785405440 0.8272652626 0.0641776845 0.1268122196 171 6.8000000000 0.0110380901 0.0080302552 0.0200794991 0.0058530072 0.3426780000 234297378 0 1786732544 0.8385400176 0.0711733252 0.1376492083 172 6.8400000000 0.0104635339 0.0080444022 0.0200794991 0.0058397947 0.3551640000 236204103 0 1783984128 0.8468273282 0.0712495521 0.1471427977 173 6.8800000000 0.0078824321 0.0080434660 0.0200794991 0.0058347470 0.2817090000 236682018 0 1784184832 0.8475538492 0.0680058002 0.1529616117 174 6.9200000000 0.0069606425 0.0080372428 0.0200794991 0.0058223552 0.2018590000 236582343 0 1786052608 0.8554782867 0.0691888034 0.1641670167 175 6.9600000000 0.0094009340 0.0080450354 0.0200794991 0.0058144824 0.3849830000 236557884 0 1785077760 0.8677430153 0.0749970004 0.1738381684 176 7.0000000000 0.0070201345 0.0080392121 0.0200794991 0.0057997999 0.1899990000 234180200 0 1784811520 0.8724899292 0.0781842023 0.1852890253 177 7.0400000000 0.0078566214 0.0080381805 0.0200794991 0.0058420967 0.1629640000 234184242 0 1786961920 0.8778966069 0.0773421079 0.1926327348 178 7.0800000000 0.0085222246 0.0080408998 0.0200794991 0.0058649868 0.1689900000 234185300 0 1783529472 0.8823696375 0.0811741054 0.2026679814 179 7.1200000000 0.0090780705 0.0080466941 0.0200794991 0.0058536161 0.2208190000 234593634 0 1782894592 0.8898110986 0.0805017352 0.2107586265 180 7.1600000000 0.0080476888 0.0080466996 0.0200794991 0.0058421761 0.4399590000 234581848 0 1782280192 0.8951106071 0.0822218508 0.2202844620 181 7.2000000000 0.0094280737 0.0080543315 0.0200794991 0.0058272582 0.3730830000 234584262 0 1783836672 0.8999860287 0.0845936611 0.2294225395 182 7.2400000000 0.0103847040 0.0080671358 0.0200794991 0.0058137580 0.3580580000 234718056 0 1785544704 0.9060860276 0.0874995515 0.2364273965 183 7.2800000000 0.0103363656 0.0080795359 0.0200794991 0.0057981749 0.3634600000 235632585 0 1786052608 0.9112608433 0.0899740979 0.2461317182 184 7.3200000000 0.0099969115 0.0080899564 0.0200794991 0.0057883917 0.2507770000 237291985 0 1783824384 0.9169667363 0.0892710388 0.2538162470 185 7.3600000000 0.0084904404 0.0080921212 0.0200794991 0.0057800420 0.2481140000 237183701 0 1783009280 0.9191282988 0.0874600559 0.2590426505 186 7.4000000000 0.0073347962 0.0080880496 0.0200794991 0.0057674724 0.4162160000 237146778 0 1781686272 0.9237754941 0.0887066349 0.2694121301 187 7.4400000000 0.0069989506 0.0080822255 0.0200794991 0.0057695367 0.2360250000 234594074 0 1781473280 0.9286522865 0.0902852863 0.2789412141 188 7.4800000000 0.0070843501 0.0080769177 0.0200794991 0.0057545998 0.1695470000 234596448 0 1783615488 0.9325648546 0.0919426382 0.2847519219 189 7.5200000000 0.0063877418 0.0080679802 0.0200794991 0.0057480844 0.1740670000 234600314 0 1785536512 0.9349963069 0.0889566317 0.2895713449 190 7.5600000000 0.0066475943 0.0080605045 0.0200794991 0.0057442424 0.1824520000 234600752 0 1786806272 0.9408180118 0.0912601054 0.2997616827 191 7.6000000000 0.0070773694 0.0080553572 0.0200794991 0.0057335769 0.1832920000 234603406 0 1783123968 0.9446032047 0.0941857472 0.3068153858 192 7.6400000000 0.0064994330 0.0080472534 0.0200794991 0.0057202297 0.1749700000 234605808 0 1782124544 0.9470525384 0.0953827202 0.3163487315 193 7.6800000000 0.0073424578 0.0080436016 0.0200794991 0.0057104640 0.1765540000 234606930 0 1783885824 0.9523482323 0.0994770750 0.3329607546 194 7.7200000000 0.0077171871 0.0080419191 0.0200794991 0.0056977388 0.1675090000 234604416 0 1785409536 0.9567124248 0.1014448553 0.3399229944 195 7.7600000000 0.0076953564 0.0080401419 0.0200794991 0.0056834410 0.2035560000 235065122 0 1784160256 0.9619957209 0.1018044353 0.3590329587 196 7.8000000000 0.0073944544 0.0080368475 0.0200794991 0.0056767779 0.4683900000 235040656 0 1782231040 0.9622842669 0.0979131982 0.3670575023 197 7.8400000000 0.0094495211 0.0080440185 0.0200794991 0.0056726659 0.4254980000 235043582 0 1783496704 0.9657807350 0.1036782116 0.3767865002 198 7.8800000000 0.0081393626 0.0080445000 0.0200794991 0.0056587960 0.4018320000 235042388 0 1785663488 0.9660668969 0.1047463194 0.3880417049 199 7.9200000000 0.0066076820 0.0080372798 0.0200794991 0.0056556216 0.3833480000 235692565 0 1784901632 0.9656578302 0.1019013226 0.3984566331 200 7.9600000000 0.0083688423 0.0080389376 0.0200794991 0.0056423061 0.3336280000 238023571 0 1781866496 0.9697225094 0.1023682728 0.4087252617 201 8.0000000000 0.0078982152 0.0080382375 0.0200794991 0.0056286383 0.2970230000 237994632 0 1781030912 0.9716084003 0.1023289934 0.4204688370 202 8.0400000000 0.0088872183 0.0080424404 0.0200794991 0.0056216556 0.2065700000 237886319 0 1783078912 0.9723559618 0.0996072218 0.4292138219 203 8.0800000000 0.0077272938 0.0080408879 0.0200794991 0.0056205532 0.4176670000 237816140 0 1780256768 0.9708324671 0.1037290022 0.4424741864 204 8.1200000000 0.0081239138 0.0080412949 0.0200794991 0.0056137176 0.2171560000 235050164 0 1780506624 0.9718476534 0.1031263024 0.4519542754 205 8.1600000000 0.0083295116 0.0080427009 0.0200794991 0.0056201951 0.1777820000 235052786 0 1781760000 0.9727860093 0.1058601886 0.4629659951 206 8.1999999990 0.0077217161 0.0080411427 0.0200794991 0.0056220868 0.2039290000 235516788 0 1783681024 0.9719594717 0.1091709882 0.4743986428 207 8.2400000000 0.0078940075 0.0080404319 0.0200794991 0.0056154635 0.4697510000 235490646 0 1784840192 0.9737445116 0.1101977751 0.4875853658 208 8.2799999990 0.0077392943 0.0080389841 0.0200794991 0.0056129969 0.4001690000 235492780 0 1786212352 0.9725279808 0.1145491153 0.4988864064 209 8.3200000000 0.0066443984 0.0080323114 0.0200794991 0.0056038619 0.4061840000 235496278 0 1785733120 0.9723354578 0.1143255755 0.5110872984 210 8.3599999990 0.0072595058 0.0080286314 0.0200794991 0.0055923340 0.4024560000 236402863 0 1785106432 0.9735600948 0.1165173575 0.5233229399 211 8.4000000000 0.0074426983 0.0080258545 0.0200794991 0.0055887854 0.2954330000 238732269 0 1782669312 0.9736716747 0.1205985099 0.5373740196 212 8.4399999990 0.0071387216 0.0080216699 0.0200794991 0.0055911302 0.3026080000 238708906 0 1781850112 0.9724462032 0.1196948364 0.5467400551 213 8.4800000000 0.0067579336 0.0080157369 0.0200794991 0.0055812757 0.2082900000 238589969 0 1782951936 0.9712066054 0.1209131032 0.5588129163 214 8.5200000000 0.0084136622 0.0080175963 0.0200794991 0.0055829114 0.4497390000 238515642 0 1779875840 0.9722577333 0.1256196946 0.5721238256 215 8.5600000000 0.0084028821 0.0080193884 0.0200794991 0.0055786095 0.2506670000 235933550 0 1780170752 0.9728510380 0.1260468066 0.5833442211 216 8.6000000000 0.0076415222 0.0080176390 0.0200794991 0.0055747734 0.4468050000 235909252 0 1780019200 0.9716357589 0.1313821226 0.5952196121 217 8.6400000000 0.0092202965 0.0080231812 0.0200794991 0.0055635399 0.3734340000 235910758 0 1782632448 0.9726036191 0.1326355785 0.6064337492 218 8.6800000000 0.0086959759 0.0080262674 0.0200794991 0.0055564236 0.3789480000 235911824 0 1784074240 0.9703626633 0.1340238750 0.6170147657 219 8.7200000000 0.0069737495 0.0080214614 0.0200794991 0.0055536544 0.4044920000 236831129 0 1784848384 0.9657031298 0.1355793029 0.6286838651 220 8.7600000000 0.0080134794 0.0080214251 0.0200794991 0.0055427140 0.3010730000 239335275 0 1783840768 0.9627957344 0.1370951533 0.6381238699 221 8.8000000000 0.0077631632 0.0080202565 0.0200794991 0.0055307444 0.3476920000 239289250 0 1783218176 0.9632374048 0.1390121728 0.6509931087 222 8.8400000000 0.0081635956 0.0080209022 0.0200794991 0.0055196392 0.2110280000 239239872 0 1784954880 0.9623210430 0.1391161233 0.6606464982 223 8.8800000000 0.0074787708 0.0080184711 0.0200794991 0.0055074528 0.4463960000 239117628 0 1781186560 0.9589403272 0.1390075237 0.6709122062 224 8.9200000000 0.0075719049 0.0080164775 0.0200794991 0.0054962661 0.2193860000 235922116 0 1779343360 0.9564735293 0.1409194171 0.6817275286 225 8.9600000000 0.0063608089 0.0080091189 0.0200794991 0.0054946849 0.1980920000 236359938 0 1779740672 0.9566798210 0.1392233074 0.6927407980 226 9.0000000000 0.0080265999 0.0080091963 0.0200794991 0.0054837913 0.4557160000 236335336 0 1782214656 0.9592285156 0.1421454996 0.7141940594 227 9.0400000000 0.0061075259 0.0080008189 0.0200794991 0.0054724433 0.4056030000 236334346 0 1784176640 0.9572865963 0.1442873180 0.7244973779 228 9.0800000000 0.0059928154 0.0079920119 0.0200794991 0.0054614647 0.3973460000 236335380 0 1785827328 0.9544754028 0.1464887261 0.7338384986 229 9.1200000000 0.0055595906 0.0079813899 0.0200794991 0.0054679128 0.3831850000 237188097 0 1786011648 0.9544352293 0.1479378343 0.7451730967 230 9.1600000000 0.0072185034 0.0079780730 0.0200794991 0.0054663331 0.3119440000 239954059 0 1783730176 0.9567854404 0.1498629153 0.7556471229 231 9.2000000000 0.0049150032 0.0079648130 0.0200794991 0.0054654646 0.3503010000 239880924 0 1782710272 0.9536954761 0.1507098824 0.7742289305 232 9.2400000000 0.0061716242 0.0079570837 0.0200794991 0.0054543949 0.2218650000 239971024 0 1784729600 0.9559532404 0.1527730227 0.7859013677 233 9.2800000000 0.0054366579 0.0079462665 0.0200794991 0.0054598260 0.4483390000 239725520 0 1781395456 0.9559601545 0.1547771096 0.7974215150 234 9.3200000000 0.0057648243 0.0079369440 0.0200794991 0.0054562037 0.2305690000 236346656 0 1782456320 0.9552761316 0.1573640406 0.8078185916 235 9.3600000000 0.0056985421 0.0079274189 0.0200794991 0.0054543160 0.2221930000 236770054 0 1783185408 0.9543207884 0.1606826484 0.8198750019 236 9.4000000000 0.0060843090 0.0079196091 0.0200794991 0.0054471908 0.4445460000 236750784 0 1783902208 0.9565007091 0.1609030664 0.8287684917 237 9.4400000000 0.0065296562 0.0079137444 0.0200794991 0.0054526700 0.3992050000 236756166 0 1786060800 0.9576227665 0.1637124419 0.8396679163 238 9.4800000000 0.0052914377 0.0079027263 0.0200794991 0.0054504132 0.3914860000 236905048 0 1785196544 0.9574851990 0.1645663977 0.8508511782 239 9.5200000000 0.0052701328 0.0078917112 0.0200794991 0.0054532546 0.3918030000 238162269 0 1786118144 0.9583113194 0.1676870883 0.8609358668 240 9.5600000000 0.0050060116 0.0078796875 0.0200794991 0.0054498492 0.2658350000 240582895 0 1785409536 0.9580017924 0.1685698926 0.8713331223 241 9.6000000000 0.0053041396 0.0078690006 0.0200794991 0.0054390589 0.3460720000 240508404 0 1782530048 0.9555063844 0.1708536446 0.8804711103 242 9.6400000000 0.0048323208 0.0078564523 0.0200794991 0.0054392740 0.2135460000 240356051 0 1784258560 0.9568529129 0.1729093790 0.8934525847 243 9.6800000000 0.0097085778 0.0078640742 0.0200794991 0.0054390315 0.4582510000 240349600 0 1785597952 0.9636878967 0.1782956123 0.9059875011 244 9.7200000000 0.0063565574 0.0078578959 0.0200794991 0.0054329113 0.2502800000 237253528 0 1784967168 0.9626890421 0.1795785129 0.9182313681 245 9.7600000000 0.0060760933 0.0078506232 0.0200794991 0.0054236534 0.4851080000 237249922 0 1775919104 0.9624216557 0.1801618040 0.9278963208 246 9.8000000000 0.0063083125 0.0078443537 0.0200794991 0.0054127777 0.4204890000 237243452 0 1777844224 0.9643070698 0.1827480346 0.9389913082 247 9.8400000000 0.0068512540 0.0078403330 0.0200794991 0.0054020385 0.4720670000 237249262 0 1779269632 0.9651324749 0.1854009628 0.9503971934 248 9.8800000000 0.0065190871 0.0078350054 0.0200794991 0.0053958128 0.4761100000 237261384 0 1781039104 0.9651672244 0.1882470846 0.9611949921 249 9.9200000000 0.0055066124 0.0078256544 0.0200794991 0.0053867936 0.4289220000 241263285 0 1784393728 0.9660774469 0.1878794730 0.9716016054 250 9.9600000000 0.0050430875 0.0078145242 0.0200794991 0.0053770361 0.2729760000 241424046 0 1784426496 0.9661777020 0.1895003170 0.9824643135 251 10.0000000000 0.0042958395 0.0078005055 0.0200794991 0.0053697373 0.2589270000 241174921 0 1786200064 0.9641976357 0.1907549948 0.9913933873 252 10.0400000000 0.0055574765 0.0077916046 0.0200794991 0.0053604377 0.2135800000 241247451 0 1784991744 0.9660556316 0.1933985054 1.0014358759 253 10.0800000000 0.0088581452 0.0077958202 0.0200794991 0.0053535688 0.4959720000 241176412 0 1782652928 0.9681117535 0.1977265477 1.0097244978 254 10.1200000000 0.0068101059 0.0077919394 0.0200794991 0.0053511976 0.2693650000 237262764 0 1783496704 0.9673596621 0.1972027123 1.0186249018 255 10.1600000000 0.0087022167 0.0077955091 0.0200794991 0.0053453877 0.1801970000 237261878 0 1784651776 0.9676480293 0.2013828754 1.0282593966 256 10.2000000000 0.0071933307 0.0077931569 0.0200794991 0.0053485767 0.1873010000 237264332 0 1786445824 0.9657250643 0.2010733634 1.0365010500 257 10.2400000000 0.0067103254 0.0077889435 0.0200794991 0.0053589642 0.2080710000 237265490 0 1783652352 0.9653820992 0.2009821683 1.0449794531 258 10.2800000000 0.0076284702 0.0077883215 0.0200794991 0.0053558832 0.2309260000 237804428 0 1785016320 0.9659405947 0.2041321546 1.0545811653 259 10.3200000000 0.0077993264 0.0077883640 0.0200794991 0.0053658684 0.5282020000 237770018 0 1783025664 0.9651183486 0.2058045268 1.0628942251 260 10.3600000000 0.0075894566 0.0077875990 0.0200794991 0.0053680697 0.4874770000 237768200 0 1784766464 0.9624338746 0.2073229551 1.0705755949 261 10.4000000000 0.0075082351 0.0077865286 0.0200794991 0.0053597736 0.4357170000 237764978 0 1786650624 0.9610146284 0.2088689804 1.0795357227 262 10.4400000000 0.0076095723 0.0077858532 0.0200794991 0.0053500802 0.3921790000 237930780 0 1783451648 0.9624799490 0.2095318586 1.0884652138 263 10.4800000000 0.0090454742 0.0077906426 0.0200794991 0.0053444734 0.4037260000 239827615 0 1783259136 0.9625132680 0.2134033591 1.0989661217 264 10.5200000000 0.0076325224 0.0077900437 0.0200794991 0.0053429496 0.2547310000 242415808 0 1783881728 0.9600833654 0.2118118405 1.1058018208 265 10.5600000000 0.0075439946 0.0077891152 0.0200794991 0.0053373338 0.3273200000 242017022 0 1786523648 0.9572647810 0.2136607170 1.1137119532 266 10.6000000000 0.0052929576 0.0077797312 0.0200794991 0.0053315499 0.2183520000 241878514 0 1784299520 0.9561676979 0.2129635960 1.1224750280 267 10.6400000000 0.0068161003 0.0077761221 0.0200794991 0.0053236679 0.4988570000 241865400 0 1785888768 0.9574174881 0.2153432667 1.1318091154 268 10.6800000000 0.0053157504 0.0077669416 0.0200794991 0.0053206659 0.3062970000 238224716 0 1777991680 0.9550415277 0.2160261571 1.1407327652 269 10.7200000000 0.0065615764 0.0077624607 0.0200794991 0.0053132211 0.4464550000 238214750 0 1779339264 0.9548304081 0.2172018737 1.1498403549 270 10.7600000000 0.0074165817 0.0077611796 0.0200794991 0.0053049106 0.4313280000 238220488 0 1781559296 0.9536430240 0.2200569361 1.1589645147 271 10.8000000000 0.0052917884 0.0077520675 0.0200794991 0.0053045288 0.4015570000 238224950 0 1783382016 0.9487229586 0.2217585444 1.1695489883 272 10.8400000000 0.0054553035 0.0077436235 0.0200794991 0.0052959996 0.3768320000 239579779 0 1786556416 0.9467236996 0.2227874398 1.1781482697 273 10.8800000000 0.0067535285 0.0077399968 0.0200794991 0.0052887873 0.3381890000 242804661 0 1785724928 0.9440653324 0.2241656035 1.1871302128 274 10.9200000000 0.0056012184 0.0077321910 0.0200794991 0.0052792021 0.3087360000 242802080 0 1784782848 0.9401108027 0.2265186906 1.1976560354 275 10.9600000000 0.0058075385 0.0077251923 0.0200794991 0.0052731634 0.2646580000 242604298 0 1786626048 0.9386771917 0.2295148224 1.2069668770 276 11.0000000000 0.0063971737 0.0077203806 0.0200794991 0.0052661306 0.1985330000 242621963 0 1784094720 0.9352813959 0.2295138240 1.2149655819 277 11.0400000000 0.0064783222 0.0077158966 0.0200794991 0.0052640707 0.4744750000 242547936 0 1769721856 0.9362590313 0.2306755185 1.2264297009 278 11.0800000000 0.0076234676 0.0077155642 0.0200794991 0.0052580411 0.3644650000 238684000 0 1771700224 0.9330459237 0.2300131321 1.2346875668 279 11.1200000000 0.0077941655 0.0077158459 0.0200794991 0.0052506828 0.4981680000 238664598 0 1773740032 0.9282941818 0.2309307903 1.2440910339 280 11.1600000000 0.0056200149 0.0077083608 0.0200794991 0.0052487315 0.4550500000 238665688 0 1774743552 0.9224081039 0.2349492908 1.2559988499 281 11.2000000000 0.0068049743 0.0077051459 0.0200794991 0.0052434315 0.4161510000 238666398 0 1776975872 0.9220509529 0.2377009392 1.2640285492 282 11.2400000000 0.0060956106 0.0076994383 0.0200794991 0.0052371506 0.4575590000 240110723 0 1780264960 0.9171076417 0.2404015362 1.2745174170 283 11.2800000000 0.0075106788 0.0076987713 0.0200794991 0.0052386823 0.4140260000 243787114 0 1786232832 0.9168071747 0.2413433492 1.2825671434 284 11.3200000000 0.0082747350 0.0077007994 0.0200794991 0.0052315473 0.2905620000 243476943 0 1783320576 0.9124640226 0.2444476932 1.2934037447 285 11.3600000000 0.0079576597 0.0077017006 0.0200794991 0.0052223497 0.2659110000 243570357 0 1784905728 0.9071553946 0.2453283072 1.3021445274 286 11.4000000000 0.0065563582 0.0076976959 0.0200794991 0.0052204678 0.2125660000 243291803 0 1784729600 0.9070079327 0.2485911995 1.3132038116 287 11.4400000000 0.0063336627 0.0076929432 0.0200794991 0.0052138060 0.4948470000 243231402 0 1780051968 0.9047508836 0.2509642839 1.3222472668 288 11.4800000000 0.0064729182 0.0076887070 0.0200794991 0.0052082567 0.3355700000 238677212 0 1781485568 0.8981592059 0.2500007749 1.3288934231 289 11.5200000000 0.0070622554 0.0076865393 0.0200794991 0.0052014465 0.2148840000 238678886 0 1781874688 0.8927990198 0.2502166629 1.3357645273 290 11.5600000000 0.0070530064 0.0076843548 0.0200794991 0.0051941092 0.2092320000 239086860 0 1784016896 0.8897950649 0.2511195242 1.3444062471 291 11.6000000000 0.0069093686 0.0076816916 0.0200794991 0.0051862728 0.4853620000 239097886 0 1778991104 0.8867967725 0.2544993162 1.3527030945 292 11.6400000000 0.0056883339 0.0076748650 0.0200794991 0.0051815519 0.4377330000 239101816 0 1781010432 0.8820836544 0.2560749054 1.3615579605 293 11.6800000000 0.0078519946 0.0076754695 0.0200794991 0.0051746037 0.4117160000 239240122 0 1783238656 0.8830204606 0.2576243579 1.3668982983 294 11.7200000000 0.0053002168 0.0076673904 0.0200794991 0.0051802189 0.4113830000 241031551 0 1785856000 0.8761952519 0.2568585873 1.3744443655 295 11.7600000000 0.0066437484 0.0076639205 0.0200794991 0.0051727654 0.3231880000 244360922 0 1784348672 0.8765914440 0.2574849725 1.3818597794 296 11.8000000000 0.0053711464 0.0076561746 0.0200794991 0.0051976259 0.3464520000 244045088 0 1783259136 0.8728167415 0.2581030726 1.3905482292 297 11.8400000000 0.0062085055 0.0076513003 0.0200794991 0.0052116222 0.2541560000 244592614 0 1785962496 0.8695310354 0.2555029094 1.3960107565 298 11.8800000000 0.0081798593 0.0076530740 0.0200794991 0.0052167704 0.2012050000 243914707 0 1785065472 0.8690226078 0.2560041845 1.4050292969 299 11.9200000000 0.0050555230 0.0076443865 0.0200794991 0.0052374484 0.4823410000 243859758 0 1781219328 0.8623117208 0.2575575411 1.4140002728 300 11.9600000000 0.0049114688 0.0076352768 0.0200794991 0.0052324052 0.3535320000 239111052 0 1782104064 0.8615024090 0.2549058497 1.4210690260 301 12.0000000000 0.0041568805 0.0076237207 0.0200794991 0.0052343735 0.2052630000 239110662 0 1783529472 0.8591002226 0.2571016252 1.4317060709 302 12.0400000000 0.0050235530 0.0076151109 0.0200794991 0.0052292854 0.1820710000 239112184 0 1785163776 0.8576618433 0.2584376633 1.4398123026 303 12.0800000000 0.0042300578 0.0076039391 0.0200794991 0.0052245272 0.1899870000 239116254 0 1784569856 0.8549489975 0.2576180995 1.4485639334 304 12.1200000000 0.0053559160 0.0075965442 0.0200794991 0.0052198090 0.1825720000 239115540 0 1783656448 0.8571249247 0.2566619813 1.4563324451 305 12.1600000000 0.0045895041 0.0075866851 0.0200794991 0.0052155648 0.2152740000 239574606 0 1778831360 0.8540292978 0.2592845261 1.4671629667 306 12.2000000000 0.0049891048 0.0075781963 0.0200794991 0.0052073319 0.4737040000 239546580 0 1775915008 0.8522867560 0.2598142326 1.4753116369 307 12.2400000000 0.0047375727 0.0075689434 0.0200794991 0.0052019043 0.4290260000 239555250 0 1778421760 0.8498061299 0.2619146705 1.4853087664 308 12.2800000000 0.0050283601 0.0075606948 0.0200794991 0.0052005070 0.4002890000 239552720 0 1780269056 0.8483738899 0.2631832957 1.4950488806 309 12.3200000000 0.0047485968 0.0075515941 0.0200794991 0.0051962191 0.4141970000 241448221 0 1785602048 0.8473437428 0.2634348273 1.5043487549 310 12.3600000000 0.0050109182 0.0075433984 0.0200794991 0.0051972608 0.3903900000 245069116 0 1784958976 0.8468984962 0.2656467557 1.5138204098 311 12.4000000000 0.0044881986 0.0075335746 0.0200794991 0.0052261721 0.2948720000 244837816 0 1784229888 0.8440262079 0.2685011625 1.5250576735 312 12.4400000000 0.0048805624 0.0075250714 0.0200794991 0.0052253587 0.2717140000 244915684 0 1785536512 0.8444470167 0.2671175897 1.5323177576 313 12.4800000000 0.0046492098 0.0075158833 0.0200794991 0.0052238286 0.2282610000 244595917 0 1784983552 0.8435539603 0.2679114938 1.5421118736 314 12.5200000000 0.0046637389 0.0075068001 0.0200794991 0.0052217761 0.4993100000 244518462 0 1780817920 0.8412696123 0.2694919705 1.5514717102 315 12.5600000000 0.0045236223 0.0074973296 0.0200794991 0.0052166846 0.3364500000 239558730 0 1776041984 0.8395314217 0.2704028487 1.5596219301 316 12.6000000000 0.0044573066 0.0074877093 0.0200794991 0.0052107005 0.1899740000 239561616 0 1776951296 0.8416031599 0.2689881623 1.5671501160 317 12.6400000000 0.0049817166 0.0074798040 0.0200794991 0.0052040812 0.2288020000 240062610 0 1778135040 0.8420114517 0.2699483633 1.5759153366 318 12.6800000000 0.0055446117 0.0074737185 0.0200794991 0.0051978288 0.4755550000 240035176 0 1781465088 0.8419034481 0.2723342180 1.5848853588 319 12.7200000000 0.0047433097 0.0074651592 0.0200794991 0.0051935120 0.4309770000 240035130 0 1782976512 0.8382570148 0.2746513486 1.5953152180 320 12.7600000000 0.0049394765 0.0074572664 0.0200794991 0.0051911919 0.4122380000 240038016 0 1784766464 0.8362099528 0.2760078013 1.6044982672 321 12.8000000000 0.0039670751 0.0074463936 0.0200794991 0.0052037242 0.4032290000 241772525 0 1786187776 0.8333467245 0.2773449421 1.6139951944 322 12.8400000000 0.0047702920 0.0074380827 0.0200794991 0.0052084345 0.4219480000 245316019 0 1783574528 0.8327690363 0.2803065479 1.6227039099 323 12.8800000000 0.0043875528 0.0074286383 0.0200794991 0.0052159755 0.2282910000 246181066 0 1782796288 0.8316727877 0.2815872729 1.6310908794 324 12.9200000000 0.0054527414 0.0074225399 0.0200794991 0.0052192065 0.3458570000 245802115 0 1785143296 0.8314522505 0.2819261551 1.6371431351 325 12.9600000000 0.0042275488 0.0074127091 0.0200794991 0.0052434859 0.2297780000 245309589 0 1786793984 0.8291728497 0.2822167277 1.6449797153 326 13.0000000000 0.0046006078 0.0074040831 0.0200794991 0.0052528476 0.5763230000 245316976 0 1777786880 0.8278855681 0.2832437456 1.6528991461 327 13.0400000000 0.0045322631 0.0073953007 0.0200794991 0.0053359796 0.3289740000 240051470 0 1779675136 0.8248785138 0.2872920036 1.6721538305 328 13.0800000000 0.0044013341 0.0073861728 0.0200794991 0.0053513111 0.1797250000 240052036 0 1779347456 0.8225335479 0.2878629267 1.6799860001 329 13.1200000000 0.0048632496 0.0073785043 0.0200794991 0.0053562685 0.1895420000 240051982 0 1780740096 0.8206127882 0.2896169424 1.6880691051 330 13.1600000000 0.0042717508 0.0073690899 0.0200794991 0.0053561164 0.2132390000 240056448 0 1782763520 0.8187749386 0.2896491289 1.6958194971 331 13.2000000000 0.0045460882 0.0073605612 0.0200794991 0.0053532264 0.2209500000 240576830 0 1784807424 0.8183554411 0.2896423340 1.7022467852 332 13.2400000000 0.0045481897 0.0073520902 0.0200794991 0.0053483051 0.4778740000 240543172 0 1783361536 0.8170210123 0.2910293937 1.7098206282 333 13.2800000000 0.0044822232 0.0073434720 0.0200794991 0.0053428536 0.4158670000 240548538 0 1785143296 0.8163291216 0.2921055555 1.7171033621 334 13.3200000000 0.0046769399 0.0073354884 0.0200794991 0.0053437298 0.3992710000 240546032 0 1787142144 0.8157521486 0.2929158211 1.7235523462 335 13.3600000000 0.0047428114 0.0073277490 0.0200794991 0.0053463710 0.3910930000 242468997 0 1785024512 0.8139317632 0.2955844998 1.7320713997 336 13.4000000000 0.0045909313 0.0073196037 0.0200794991 0.0053536962 0.4129180000 246137099 0 1784229888 0.8115859032 0.2963634133 1.7383443117 337 13.4400000000 0.0046907566 0.0073118030 0.0200794991 0.0053740419 0.2330130000 247056050 0 1784127488 0.8095659018 0.2960981727 1.7437137365 338 13.4800000000 0.0048157084 0.0073044181 0.0200794991 0.0053976592 0.3617500000 246698576 0 1785892864 0.8060068488 0.2963962555 1.7492036819 339 13.5200000000 0.0042922175 0.0072955326 0.0200794991 0.0054090351 0.2288400000 246145409 0 1785339904 0.8042773604 0.2971161902 1.7565046549 340 13.5600000000 0.0042610643 0.0072866077 0.0200794991 0.0054314022 0.5472810000 246220690 0 1780043776 0.7992799282 0.2974492013 1.7622978687 341 13.6000000000 0.0043837023 0.0072780947 0.0200794991 0.0054386685 0.4171200000 240551538 0 1780973568 0.7960602641 0.2987245321 1.7697244883 342 13.6400000000 0.0039950381 0.0072684952 0.0200794991 0.0054456770 0.2312280000 240562924 0 1781354496 0.7918712497 0.3006934524 1.7780636549 343 13.6800000000 0.0044882679 0.0072603895 0.0200794991 0.0054601185 0.2314940000 241118774 0 1782476800 0.7870936394 0.3045589030 1.7862781286 344 13.7200000000 0.0045880890 0.0072526212 0.0200794991 0.0054636540 0.4655110000 241081852 0 1780097024 0.7830552459 0.3066315055 1.7921382189 345 13.7600000000 0.0043440750 0.0072441907 0.0200794991 0.0054617591 0.3972040000 241082574 0 1782153216 0.7816406488 0.3054580986 1.7969477177 346 13.8000000000 0.0047540669 0.0072369938 0.0200794991 0.0054620529 0.3760870000 241235840 0 1783746560 0.7788088322 0.3061092496 1.8006546497 347 13.8400000000 0.0046980875 0.0072296770 0.0200794991 0.0054647287 0.3993990000 243668089 0 1785139200 0.7750282288 0.3052124083 1.8061876297 348 13.8800000000 0.0048077516 0.0072227175 0.0200794991 0.0054773270 0.3449140000 247644247 0 1781878784 0.7705030441 0.3060074747 1.8130818605 349 13.9200000000 0.0044465060 0.0072147627 0.0200794991 0.0054842039 0.2290260000 247193651 0 1780899840 0.7640549541 0.3059897721 1.8204662800 350 13.9600000000 0.0043793335 0.0072066615 0.0200794991 0.0054891826 0.3084870000 247484899 0 1783209984 0.7586092353 0.3071472347 1.8280686140 351 14.0000000000 0.0045062727 0.0071989681 0.0200794991 0.0054879616 0.2060200000 246961669 0 1784872960 0.7531692982 0.3086034060 1.8342001438 352 14.0400000000 0.0044364259 0.0071911200 0.0200794991 0.0054901878 0.4248230000 246886478 0 1784201216 0.7477056384 0.3088926673 1.8389549255 353 14.0800000000 0.0044211969 0.0071832731 0.0200794991 0.0054854407 0.3272400000 241093435 0 1779298304 0.7431078553 0.3076215386 1.8439856768 354 14.1200000000 0.0047399206 0.0071763710 0.0200794991 0.0054901997 0.1886470000 241084320 0 1780416512 0.7370504141 0.3105514646 1.8535233736 355 14.1600000000 0.0045772460 0.0071690495 0.0200794991 0.0054831336 0.1781360000 241513622 0 1781293056 0.7313907146 0.3109636605 1.8581687212 356 14.2000000000 0.0044977618 0.0071615459 0.0200794991 0.0054778720 0.3813080000 241484460 0 1778888704 0.7256199718 0.3109833598 1.8628286123 357 14.2400000000 0.0044055274 0.0071538260 0.0200794991 0.0054738618 0.3183220000 241483570 0 1780920320 0.7178266048 0.3120716810 1.8690812588 358 14.2800000000 0.0044776932 0.0071463508 0.0200794991 0.0054663821 0.3132290000 243250531 0 1783382016 0.7121284008 0.3122027516 1.8744056225 359 14.3200000000 0.0044747940 0.0071389091 0.0200794991 0.0054592741 0.3312620000 244372637 0 1783287808 0.7031815052 0.3159974217 1.8822727203 360 14.3600000000 0.0043447786 0.0071311476 0.0200794991 0.0054569111 0.2237500000 246531784 0 1784852480 0.6878805161 0.3189884126 1.8942172527 361 14.4000000000 0.0044816774 0.0071238084 0.0200794991 0.0054516155 0.2588490000 246270336 0 1786580992 0.6780663729 0.3241666853 1.9030308723 362 14.4400000000 0.0045311176 0.0071166462 0.0200794991 0.0054475257 0.4625470000 246009144 0 1781526528 0.6613289118 0.3236248195 1.9094822407 363 14.4800000000 0.0045265094 0.0071095109 0.0200794991 0.0054405074 0.2364580000 241501094 0 1779646464 0.6552925110 0.3223323524 1.9131996632 364 14.5200000000 0.0048920503 0.0071034189 0.0200794991 0.0054342881 0.1767630000 241501704 0 1779830784 0.6482732296 0.3232645988 1.9194734097 365 14.5600000000 0.0048014806 0.0070971123 0.0200794991 0.0054273557 0.1539070000 241503386 0 1782235136 0.6393041611 0.3234884739 1.9246813059 366 14.6000000000 0.0045500458 0.0070901531 0.0200794991 0.0054201821 0.2069230000 242099052 0 1784012800 0.6230112314 0.3295611441 1.9394551516 367 14.6400000000 0.0044893376 0.0070830664 0.0200794991 0.0054129336 0.4362220000 242050266 0 1781501952 0.6133772135 0.3336513340 1.9444892406 368 14.6800000000 0.0048395572 0.0070769699 0.0200794991 0.0054078143 0.3773050000 244732753 0 1785176064 0.6043446064 0.3346753716 1.9483768940 369 14.7200000000 0.0047965804 0.0070707900 0.0200794991 0.0054014043 0.2432230000 244624349 0 1784963072 0.5957610607 0.3324416578 1.9495685101 370 14.7600000000 0.0042317756 0.0070631170 0.0200794991 0.0053944880 0.3380130000 244549966 0 1783353344 0.5880576372 0.3303150833 1.9512231350 371 14.8000000000 0.0041393721 0.0070552362 0.0200794991 0.0053884553 0.2142330000 242065514 0 1784102912 0.5786092281 0.3324744403 1.9578957558 372 14.8400000000 0.0040732631 0.0070472202 0.0200794991 0.0053838334 0.1730140000 242065524 0 1785884672 0.5698735714 0.3340982795 1.9630756378 373 14.8800000000 0.0040497114 0.0070391840 0.0200794991 0.0053812860 0.1783500000 242067574 0 1785110528 0.5600938797 0.3352760375 1.9675993919 374 14.9200000000 0.0043025604 0.0070318668 0.0200794991 0.0053806166 0.1722640000 242069724 0 1784479744 0.5489888191 0.3367330432 1.9708285332 375 14.9600000000 0.0042656292 0.0070244902 0.0200794991 0.0053775451 0.1723220000 242071722 0 1783717888 0.5385223627 0.3359335065 1.9719140530 376 15.0000000000 0.0040826602 0.0070166661 0.0200794991 0.0053705333 0.1678270000 242074708 0 1783119872 0.5292118788 0.3353758752 1.9773918390 377 15.0400000000 0.0044726310 0.0070099180 0.0200794991 0.0053714124 0.1637970000 242074498 0 1784864768 0.5085902810 0.3367592394 1.9844883680 378 15.0800000000 0.0045254743 0.0070033454 0.0200794991 0.0053648762 0.1645080000 242077424 0 1786372096 0.4995642304 0.3372610509 1.9883949757 379 15.1200000000 0.0046094456 0.0069970291 0.0200794991 0.0053579057 0.1624750000 242080794 0 1784885248 0.4920989573 0.3366644382 1.9910337925 380 15.1600000000 0.0047432096 0.0069910980 0.0200794991 0.0053544548 0.2117350000 242691896 0 1783332864 0.4848428369 0.3355175257 1.9949457645 381 15.2000000000 0.0046368996 0.0069849190 0.0200794991 0.0053597691 0.4669210000 243862361 0 1786753024 0.4768328369 0.3366847634 2.0011310577 382 15.2400000000 0.0045957463 0.0069786646 0.0200794991 0.0053650314 0.2892040000 244714355 0 1784008704 0.4666446745 0.3360987902 2.0019567013 383 15.2800000000 0.0047048409 0.0069727277 0.0200794991 0.0053754957 0.2521670000 244643032 0 1784066048 0.4573313892 0.3364205658 2.0045294762 384 15.3200000000 0.0046843500 0.0069667684 0.0200794991 0.0053838973 0.1815840000 242640656 0 1784545280 0.4488810897 0.3376918733 2.0102181435 385 15.3600000000 0.0047683599 0.0069610583 0.0200794991 0.0053836549 0.1942320000 242642430 0 1786195968 0.4410001636 0.3375219405 2.0124750137 386 15.4000000000 0.0048786695 0.0069556635 0.0200794991 0.0053823420 0.1884280000 242642900 0 1784414208 0.4335022569 0.3379191756 2.0156602859 387 15.4400000000 0.0047686538 0.0069500123 0.0200794991 0.0053849993 0.1895910000 242645886 0 1783283712 0.4269779325 0.3385106325 2.0194246769 388 15.4800000000 0.0048524337 0.0069446061 0.0200794991 0.0053878078 0.1803850000 242646792 0 1783017472 0.4205571413 0.3393024802 2.0230512619 389 15.5200000000 0.0051829577 0.0069400775 0.0200794991 0.0053885390 0.1781920000 242648782 0 1784672256 0.4131876230 0.3407073915 2.0270767212 390 15.5600000000 0.0049000205 0.0069348466 0.0200794991 0.0053969699 0.1651400000 242650064 0 1786449920 0.4050651789 0.3407428861 2.0303261280 391 15.6000000000 0.0044762930 0.0069285587 0.0200794991 0.0053934091 0.1665060000 242651478 0 1783500800 0.3977122307 0.3409218192 2.0339195728 392 15.6400000000 0.0048198919 0.0069231795 0.0200794991 0.0053965506 0.1662830000 242652976 0 1782378496 0.3916387558 0.3417670131 2.0388512611 393 15.6800000000 0.0049000615 0.0069180316 0.0200794991 0.0053919260 0.1658530000 242655066 0 1782235136 0.3850038648 0.3415126204 2.0418322086 394 15.7200000000 0.0049010981 0.0069129125 0.0200794991 0.0053894523 0.1616440000 242656932 0 1783910400 0.3782072067 0.3416579068 2.0447981358 395 15.7600000000 0.0051688408 0.0069084971 0.0200794991 0.0053909918 0.1661330000 242660338 0 1785688064 0.3719009161 0.3426826000 2.0511724949 396 15.8000000000 0.0057763150 0.0069056380 0.0200794991 0.0053891850 0.1673350000 242660940 0 1784811520 0.3649017811 0.3446201086 2.0555653572 397 15.8400000000 0.0052395966 0.0069014415 0.0200794991 0.0053832339 0.1650310000 242664562 0 1784287232 0.3588044047 0.3435223699 2.0587656498 398 15.8800000000 0.0055195633 0.0068979694 0.0200794991 0.0053827599 0.1596850000 242665132 0 1782403072 0.3533738852 0.3442457020 2.0654749870 399 15.9200000000 0.0052606529 0.0068938659 0.0200794991 0.0053815217 0.1631470000 242666746 0 1781108736 0.3449611664 0.3456522822 2.0689268112 400 15.9600000000 0.0052511878 0.0068897592 0.0200794991 0.0053797254 0.1601750000 242668820 0 1783529472 0.3397936225 0.3446654677 2.0727863312 401 16.0000000000 0.0056776847 0.0068867365 0.0200794991 0.0053786632 0.1708270000 242670718 0 1785180160 0.3341405988 0.3441310525 2.0768909454 402 16.0400000000 0.0053800852 0.0068829886 0.0200794991 0.0053737834 0.1671930000 242672492 0 1786814464 0.3285816908 0.3443039060 2.0839962959 403 16.0800000000 0.0049007768 0.0068780700 0.0200794991 0.0053695373 0.1658070000 242674986 0 1783627776 0.3222212791 0.3440422118 2.0896301270 404 16.1200000000 0.0049276673 0.0068732423 0.0200794991 0.0053699194 0.1677050000 242675908 0 1782611968 0.3141271472 0.3444180489 2.0943031311 405 16.1600000000 0.0053449888 0.0068694688 0.0200794991 0.0053655183 0.1620880000 242677306 0 1784688640 0.3096451163 0.3435643613 2.0979652405 406 16.2000000000 0.0053903246 0.0068658256 0.0200794991 0.0053788704 0.1567000000 242681488 0 1786703872 0.3030536175 0.3449247777 2.1065778732 407 16.2400000000 0.0048739216 0.0068609315 0.0200794991 0.0053779728 0.1611620000 242686770 0 1783537664 0.2955551744 0.3466458023 2.1125423908 408 16.2800000000 0.0048744143 0.0068560626 0.0200794991 0.0053792527 0.1638070000 242688852 0 1781891072 0.2898581028 0.3469580710 2.1166090965 409 16.3200000000 0.0049567427 0.0068514188 0.0200794991 0.0053866427 0.1929150000 242690122 0 1781497856 0.2829620242 0.3482239842 2.1237895489 410 16.3600000000 0.0049627242 0.0068468122 0.0200794991 0.0053829167 0.1608100000 242692200 0 1783259136 0.2781152725 0.3486205041 2.1279554367 411 16.3999999990 0.0055625299 0.0068436874 0.0200794991 0.0053875483 0.1568180000 242693354 0 1785180160 0.2713332176 0.3496387899 2.1307468414 412 16.4400000000 0.0052400450 0.0068397951 0.0200794991 0.0053813359 0.1657380000 242694968 0 1784295424 0.2666094899 0.3490481675 2.1363964081 413 16.4800000000 0.0047574816 0.0068347531 0.0200794991 0.0053886268 0.1542560000 242696258 0 1783762944 0.2598195076 0.3501332998 2.1435480118 414 16.5200000000 0.0044467854 0.0068289851 0.0200794991 0.0053993509 0.1631620000 242698216 0 1782747136 0.2530426383 0.3514704704 2.1488933563 415 16.5599999990 0.0052753016 0.0068252413 0.0200794991 0.0054230007 0.1560160000 242699438 0 1782038528 0.2467491627 0.3546294272 2.1554002762 416 16.6000000000 0.0055218050 0.0068221080 0.0200794991 0.0054305446 0.1583980000 242701780 0 1781514240 0.2402624488 0.3562577367 2.1591224670 417 16.6400000000 0.0051545240 0.0068181090 0.0200794991 0.0054251784 0.1605780000 242702734 0 1780871168 0.2362543941 0.3561223745 2.1630883217 418 16.6800000000 0.0050342577 0.0068138414 0.0200794991 0.0054368096 0.1566300000 242704616 0 1779970048 0.2250587344 0.3577382565 2.1722774506 419 16.7199999990 0.0049601346 0.0068094173 0.0200794991 0.0054435996 0.1520960000 242706038 0 1779462144 0.2185897231 0.3593208492 2.1785349846 420 16.7600000000 0.0052204477 0.0068056341 0.0200794991 0.0054491988 0.2023240000 243440039 0 1778700288 0.2134786844 0.3610858023 2.1843883991 421 16.8000000000 0.0053164721 0.0068020969 0.0200794991 0.0054528252 0.5114600000 245100835 0 1782947840 0.2082657814 0.3618983626 2.1893792152 422 16.8400000000 0.0052499841 0.0067984189 0.0200794991 0.0054867843 0.2801500000 245012990 0 1783574528 0.2014822364 0.3630106449 2.1947689056 423 16.8799999990 0.0051597501 0.0067945449 0.0200794991 0.0054988802 0.1851480000 243392462 0 1784696832 0.1968349814 0.3628904521 2.2001101971 424 16.9200000000 0.0053041494 0.0067910299 0.0200794991 0.0055831279 0.1883430000 243393960 0 1786224640 0.1855003834 0.3649370074 2.2097351551 425 16.9600000000 0.0050882827 0.0067870234 0.0200794991 0.0055883942 0.1957740000 243395374 0 1784770560 0.1810529232 0.3654787540 2.2131395340 426 17.0000000000 0.0050407941 0.0067829243 0.0200794991 0.0056062279 0.1872190000 243396580 0 1780482048 0.1755360365 0.3670414984 2.2183098793 427 17.0400000000 0.0052026496 0.0067792234 0.0200794991 0.0056211052 0.1814100000 243398338 0 1781473280 0.1699541807 0.3689900637 2.2227094173 428 17.0800000000 0.0050274865 0.0067751305 0.0200794991 0.0056274468 0.1824770000 243399852 0 1783877632 0.1651338339 0.3709367812 2.2269749641 429 17.1200000000 0.0053472174 0.0067718021 0.0200794991 0.0056330344 0.1825850000 243400982 0 1785659392 0.1603937149 0.3713727891 2.2288646698 430 17.1600000000 0.0052631339 0.0067682935 0.0200794991 0.0056341400 0.1796300000 243402740 0 1784426496 0.1554676294 0.3716031015 2.2322988510 431 17.2000000000 0.0050851684 0.0067643884 0.0200794991 0.0056343327 0.1756630000 243403978 0 1783894016 0.1508407593 0.3710100651 2.2360687256 432 17.2400000000 0.0052333255 0.0067608443 0.0200794991 0.0056385961 0.1744140000 243405784 0 1780322304 0.1456408501 0.3718058467 2.2407574654 433 17.2800000000 0.0051429863 0.0067571079 0.0200794991 0.0056364135 0.1769280000 243407458 0 1778950144 0.1417914629 0.3730690181 2.2444095612 434 17.3200000000 0.0052136206 0.0067535514 0.0200794991 0.0056360385 0.2103680000 243408880 0 1779945472 0.1361181736 0.3743115366 2.2467308044 435 17.3600000000 0.0052468381 0.0067500877 0.0200794991 0.0056325562 0.1738930000 243410478 0 1782243328 0.1309106350 0.3727751374 2.2479701042 436 17.4000000000 0.0050775353 0.0067462516 0.0200794991 0.0056330042 0.1727710000 243411648 0 1784258560 0.1258789301 0.3723715544 2.2509517670 437 17.4400000000 0.0050745555 0.0067424262 0.0200794991 0.0056311511 0.1700420000 243413286 0 1785638912 0.1195808649 0.3736695647 2.2540402412 438 17.4800000000 0.0051093828 0.0067386978 0.0200794991 0.0056306823 0.1672230000 243414716 0 1785028608 0.1146885157 0.3722877502 2.2564582825 439 17.5200000000 0.0048017721 0.0067342857 0.0200794991 0.0056272327 0.1589110000 243416314 0 1784000512 0.1095874310 0.3719625473 2.2589685917 440 17.5600000000 0.0049366928 0.0067302002 0.0200794991 0.0056260559 0.1612890000 243417996 0 1783001088 0.1046583652 0.3717406392 2.2609634399 441 17.6000000000 0.0050240657 0.0067263314 0.0200794991 0.0056239504 0.1649880000 243419058 0 1782001664 0.0990905762 0.3713355958 2.2621281147 442 17.6400000000 0.0049331682 0.0067222745 0.0200794991 0.0056220727 0.1598750000 243420924 0 1781751808 0.0941967964 0.3698962927 2.2635533810 443 17.6800000000 0.0051020002 0.0067186170 0.0200794991 0.0056247913 0.1593630000 243422114 0 1779335168 0.0884456635 0.3711522222 2.2653510571 444 17.7200000000 0.0050867060 0.0067149415 0.0200794991 0.0056216679 0.1513530000 243421932 0 1778958336 0.0826991796 0.3707013130 2.2677350044 445 17.7600000000 0.0050198464 0.0067111323 0.0200794991 0.0056176543 0.1537370000 243425162 0 1780830208 0.0781575441 0.3702458143 2.2692439556 446 17.8000000000 0.0053557018 0.0067080933 0.0200794991 0.0056214206 0.1480840000 243426576 0 1782624256 0.0726222992 0.3696362078 2.2707540989 447 17.8400000000 0.0053896047 0.0067051436 0.0200794991 0.0056223581 0.1529510000 243425406 0 1784401920 0.0668429136 0.3693113625 2.2742378712 448 17.8800000000 0.0050764154 0.0067015081 0.0200794991 0.0056173183 0.1500820000 243429196 0 1786163200 0.0604468584 0.3687775135 2.2761316299 449 17.9200000000 0.0051635206 0.0066980827 0.0200794991 0.0056143303 0.2059850000 244149337 0 1783767040 0.0553017855 0.3677923679 2.2770829201 450 17.9600000000 0.0051187119 0.0066945730 0.0200794991 0.0056109404 0.4644610000 245153711 0 1780404224 0.0500401258 0.3663584590 2.2785837650 451 18.0000000000 0.0054265452 0.0066917614 0.0200794991 0.0056102654 0.2191210000 245083948 0 1779769344 0.0368608236 0.3654232919 2.2827072144 452 18.0400000000 0.0054584458 0.0066890328 0.0200794991 0.0056076029 0.1813070000 244104792 0 1779417088 0.0310444832 0.3652427197 2.2851605415 453 18.0800000000 0.0054859244 0.0066863770 0.0200794991 0.0056037541 0.1847700000 244105746 0 1781583872 0.0248631239 0.3635997772 2.2874608040 454 18.1200000000 0.0055084000 0.0066837823 0.0200794991 0.0056037848 0.1808500000 244106172 0 1783615488 0.0173461437 0.3636679053 2.2908818722 455 18.1600000000 0.0055866512 0.0066813710 0.0200794991 0.0056015036 0.1874350000 244110246 0 1785376768 0.0104411840 0.3638928235 2.2944238186 456 18.2000000000 0.0055725118 0.0066789393 0.0200794991 0.0055964436 0.1768970000 244111652 0 1786662912 0.0051279068 0.3623508215 2.2959575653 457 18.2400000000 0.0056038806 0.0066765869 0.0200794991 0.0055937814 0.1759090000 244113426 0 1783607296 -0.0018106699 0.3622252345 2.2987885475 458 18.2800000000 0.0055278381 0.0066740787 0.0200794991 0.0055948724 0.1728130000 244114656 0 1782444032 -0.0089572668 0.3623523712 2.3005394936 459 18.3200000000 0.0057499916 0.0066720654 0.0200794991 0.0055932149 0.1690930000 244113930 0 1784504320 -0.0151557922 0.3614126444 2.3016893864 460 18.3600000000 0.0055631255 0.0066696547 0.0200794991 0.0055898715 0.2008640000 244113504 0 1786302464 -0.0208294392 0.3601804078 2.3036379814 461 18.4000000000 0.0054943045 0.0066671051 0.0200794991 0.0055843409 0.1703340000 244117142 0 1784770560 -0.0279279947 0.3588824272 2.3065514565 462 18.4400000000 0.0054862928 0.0066645493 0.0200794991 0.0055791804 0.1614150000 244116708 0 1783734272 -0.0352095366 0.3582349420 2.3094131947 463 18.4800000000 0.0058381138 0.0066627643 0.0200794991 0.0055747409 0.1619040000 244122410 0 1783373824 -0.0406147242 0.3586789966 2.3098475933 464 18.5200000000 0.0056573483 0.0066605975 0.0200794991 0.0055699657 0.2026620000 244826175 0 1785147392 -0.0475751162 0.3572030962 2.3107633591 465 18.5600000000 0.0058192816 0.0066587882 0.0200794991 0.0055682714 0.5217320000 245949633 0 1786585088 -0.0540977120 0.3561503291 2.3136498928 466 18.6000000000 0.0054997550 0.0066563010 0.0200794991 0.0055637392 0.3073050000 245852718 0 1781178368 -0.0606769919 0.3548067808 2.3169181347 467 18.6400000000 0.0054798918 0.0066537819 0.0200794991 0.0055598692 0.1934820000 244771994 0 1781088256 -0.0666838884 0.3552671671 2.3182406425 468 18.6800000000 0.0055639176 0.0066514531 0.0200794991 0.0055583972 0.1938320000 244772772 0 1782714368 -0.0717484355 0.3543668985 2.3177325726 469 18.7200000000 0.0054665105 0.0066489266 0.0200794991 0.0055529087 0.1933700000 244774526 0 1784766464 -0.0782542229 0.3542729020 2.3199384212 470 18.7600000000 0.0055688713 0.0066466286 0.0200794991 0.0055481323 0.1862100000 244776784 0 1786290176 -0.0842024684 0.3533980250 2.3206868172 471 18.8000000000 0.0054305997 0.0066440468 0.0200794991 0.0055537231 0.1731410000 244774718 0 1784365056 -0.0978773236 0.3490264714 2.3219811916 472 18.8400000000 0.0054966090 0.0066416158 0.0200794991 0.0055488729 0.1579820000 244773776 0 1783103488 -0.1025089025 0.3478218615 2.3231816292 473 18.8800000000 0.0056238621 0.0066394641 0.0200794991 0.0055466261 0.1536230000 244775270 0 1783095296 -0.1045163274 0.3459050059 2.3219618797 474 18.9200000000 0.0055753109 0.0066372190 0.0200794991 0.0055459294 0.1505610000 244775820 0 1784238080 -0.1068187952 0.3440290093 2.3221025467 475 18.9600000000 0.0054437565 0.0066347065 0.0200794991 0.0055447140 0.1494140000 244774758 0 1786396672 -0.1104340553 0.3431575894 2.3239440918 476 19.0000000000 0.0056411913 0.0066326193 0.0200794991 0.0055600352 0.1436500000 244774784 0 1783631872 -0.1152389646 0.3405350447 2.3239202499 477 19.0400000000 0.0053790244 0.0066299912 0.0200794991 0.0055674911 0.1393100000 244771514 0 1782599680 -0.1175291538 0.3380437791 2.3236191273 478 19.0800000000 0.0053624385 0.0066273394 0.0200794991 0.0055826266 0.1366180000 244772928 0 1781211136 -0.1238739491 0.3358213902 2.3296568394 479 19.1200000000 0.0052285236 0.0066244191 0.0200794991 0.0055792624 0.1371360000 244776026 0 1780060160 -0.1240710020 0.3356194496 2.3301284313 480 19.1600000000 0.0052639078 0.0066215847 0.0200794991 0.0055885913 0.1373170000 244772536 0 1777938432 -0.1244435310 0.3350636363 2.3290708065 481 19.2000000000 0.0050156685 0.0066182460 0.0200794991 0.0055953152 0.1283750000 244769806 0 1777164288 -0.1259825230 0.3342161477 2.3311533928 482 19.2400000000 0.0054638879 0.0066158511 0.0200794991 0.0056123818 0.1305280000 244774268 0 1776488448 -0.1265357733 0.3348135948 2.3309385777 483 19.2800000000 0.0052820719 0.0066130896 0.0200794991 0.0056242160 0.1670070000 245305005 0 1776254976 -0.1275266409 0.3334992528 2.3326630592 484 19.3200000000 0.0052504842 0.0066102743 0.0200794991 0.0056304290 0.3905830000 246301553 0 1781301248 -0.1269614100 0.3329799771 2.3336546421 485 19.3600000000 0.0052607222 0.0066074918 0.0200794991 0.0056566373 0.1933740000 246261997 0 1783156736 -0.1267557740 0.3329325914 2.3336837292 486 19.4000000000 0.0047402917 0.0066036498 0.0200794991 0.0056573645 0.1899010000 246180506 0 1783812096 -0.1269767284 0.3321824670 2.3371121883 487 19.4400000000 0.0047364146 0.0065998156 0.0200794991 0.0056718552 0.1538790000 245239170 0 1783590912 -0.1265018582 0.3323462009 2.3392775059 488 19.4800000000 0.0046555731 0.0065958315 0.0200794991 0.0056839114 0.1474770000 245235700 0 1785622528 -0.1264820099 0.3311382532 2.3419094086 489 19.5200000000 0.0045433692 0.0065916343 0.0200794991 0.0056931389 0.1468220000 245237862 0 1784975360 -0.1289494038 0.3315988779 2.3476469517 490 19.5600000000 0.0045965114 0.0065875626 0.0200794991 0.0056976195 0.1532830000 245241408 0 1784000512 -0.1277483106 0.3323436975 2.3488576412 491 19.6000000000 0.0044786548 0.0065832675 0.0200794991 0.0057086744 0.1506070000 245238566 0 1783484416 -0.1276714802 0.3326910436 2.3523414135 492 19.6400000000 0.0046035629 0.0065792437 0.0200794991 0.0057141669 0.1541450000 245243492 0 1784721408 -0.1268233657 0.3330256939 2.3553292751 493 19.6800000000 0.0045960578 0.0065752210 0.0200794991 0.0057239865 0.1511820000 245243682 0 1786748928 -0.1246467829 0.3345884085 2.3556797504 494 19.7200000000 0.0045442833 0.0065711098 0.0200794991 0.0057472837 0.1470630000 245246632 0 1783341056 -0.1256451607 0.3343561292 2.3606975079 495 19.7600000000 0.0047004311 0.0065673306 0.0200794991 0.0057650905 0.1462590000 245245806 0 1781444608 -0.1263484955 0.3343768120 2.3664567471 496 19.8000000000 0.0047582006 0.0065636832 0.0200794991 0.0057758627 0.1466280000 245248764 0 1780162560 -0.1263985634 0.3351529241 2.3710145950 497 19.8400000000 0.0047104997 0.0065599544 0.0200794991 0.0057800078 0.1495260000 245252242 0 1779376128 -0.1252661943 0.3363377750 2.3724470139 498 19.8800000000 0.0047264048 0.0065562726 0.0200794991 0.0057860656 0.1468290000 245253932 0 1780260864 -0.1243973374 0.3369270563 2.3751215935 499 19.9200000000 0.0047159316 0.0065525846 0.0200794991 0.0057876744 0.1492220000 245256014 0 1782804480 -0.1241105199 0.3363849521 2.3795843124 500 19.9600000000 0.0047276486 0.0065489347 0.0200794991 0.0057924232 0.1459520000 245254776 0 1784332288 -0.1237792969 0.3376483917 2.3824789524 501 20.0000000000 0.0048706755 0.0065455849 0.0200794991 0.0058017074 0.1467590000 245255546 0 1786359808 -0.1232529581 0.3383560777 2.3849575520 502 20.0400000000 0.0047572581 0.0065420225 0.0200794991 0.0058090302 0.1414260000 245255372 0 1783484416 -0.1229443550 0.3386435509 2.3885030746 503 20.0800000000 0.0048360368 0.0065386308 0.0200794991 0.0058202435 0.1459740000 245259610 0 1782583296 -0.1240618527 0.3396167755 2.3917326927 504 20.1200000000 0.0046446435 0.0065348729 0.0200794991 0.0058293179 0.1409160000 245259888 0 1779261440 -0.1243829131 0.3397284150 2.3952605724 505 20.1600000000 0.0045557199 0.0065309538 0.0200794991 0.0058388812 0.1390030000 245261266 0 1777352704 -0.1250004768 0.3405151963 2.3978059292 506 20.2000000000 0.0047194138 0.0065273737 0.0200794991 0.0058521623 0.1336610000 245259760 0 1779134464 -0.1245503724 0.3408169150 2.3999423981 507 20.2400000000 0.0049096276 0.0065241829 0.0200794991 0.0058586486 0.1324830000 245262026 0 1781026816 -0.1249218583 0.3404819369 2.4024581909 508 20.2800000000 0.0048437938 0.0065208750 0.0200794991 0.0058707606 0.1336470000 245259584 0 1782804480 -0.1269323826 0.3399887383 2.4062116146 509 20.3200000000 0.0047091874 0.0065173157 0.0200794991 0.0058829911 0.1314810000 245261790 0 1784582144 -0.1267161071 0.3392840326 2.4093530178 510 20.3600000000 0.0048585408 0.0065140632 0.0200794991 0.0058914574 0.1231340000 245259148 0 1786359808 -0.1262673885 0.3400101066 2.4088358879 511 20.4000000000 0.0048761377 0.0065108579 0.0200794991 0.0058926283 0.1264170000 245261766 0 1782800384 -0.1269803345 0.3392767906 2.4108042717 512 20.4400000000 0.0051303930 0.0065081617 0.0200794991 0.0059014383 0.1534760000 245591114 0 1781825536 -0.1290287673 0.3398806453 2.4126484394 513 20.4800000000 0.0050510317 0.0065053212 0.0200794991 0.0059035965 0.2707920000 245729501 0 1779224576 -0.1290121228 0.3399932683 2.4124612808 514 20.5200000000 0.0051941928 0.0065027704 0.0200794991 0.0059104028 0.1435500000 246323599 0 1782575104 -0.1306542456 0.3402003348 2.4143371582 515 20.5600000000 0.0044474853 0.0064987796 0.0200794991 0.0059133183 0.1444760000 246002386 0 1783361536 -0.1333266646 0.3400615752 2.4150834084 516 20.6000000000 0.0045217881 0.0064949482 0.0200794991 0.0059170487 0.1175030000 245621420 0 1784066048 -0.1350151896 0.3401148021 2.4149162769 517 20.6400000000 0.0046473704 0.0064913745 0.0200794991 0.0059183779 0.1211650000 245622270 0 1786183680 -0.1359451115 0.3397524953 2.4138762951 518 20.6800000000 0.0050897212 0.0064886686 0.0200794991 0.0059247622 0.1450050000 245620364 0 1785348096 -0.1377346069 0.3395204246 2.4136323929 519 20.7200000000 0.0044794292 0.0064847973 0.0200794991 0.0059251231 0.1157940000 245623054 0 1784573952 -0.1409521997 0.3387588859 2.4145429134 520 20.7600000000 0.0041835052 0.0064803717 0.0200794991 0.0059242417 0.1209900000 245621716 0 1782779904 -0.1422192603 0.3364321291 2.4145674706 521 20.8000000000 0.0039085713 0.0064754354 0.0200794991 0.0059280134 0.1157340000 245625954 0 1782026240 -0.1452976912 0.3359398246 2.4139745235 522 20.8400000000 0.0036552213 0.0064700327 0.0200794991 0.0059294111 0.1131690000 245625852 0 1780772864 -0.1477795243 0.3342571855 2.4140009880 523 20.8800000000 0.0051259478 0.0064674628 0.0200794991 0.0059420960 0.1152730000 245630066 0 1779884032 -0.1485596001 0.3367522359 2.4098989964 524 20.9200000000 0.0054359548 0.0064654942 0.0200794991 0.0059450320 0.1128020000 245629640 0 1781796864 -0.1497562677 0.3352988958 2.4086978436 525 20.9600000000 0.0038068430 0.0064604302 0.0200794991 0.0059403035 0.1131870000 245632174 0 1783025664 -0.1531970799 0.3313177228 2.4090745449 526 21.0000000000 0.0046699857 0.0064570263 0.0200794991 0.0059439282 0.1117650000 245633344 0 1784803328 -0.1557672918 0.3326000571 2.4062089920 527 21.0400000000 0.0052522076 0.0064547401 0.0200794991 0.0059448790 0.1182070000 245636438 0 1786454016 -0.1581664085 0.3330162466 2.4019799232 528 21.0800000000 0.0062875962 0.0064544235 0.0200794991 0.0059515327 0.1133670000 245637072 0 1785335808 -0.1621514261 0.3318171799 2.4018294811 529 21.1200000000 0.0065994002 0.0064546976 0.0200794991 0.0059582930 0.1108440000 245637306 0 1784426496 -0.1677104533 0.3313761950 2.4005658627 530 21.1600000000 0.0057300478 0.0064533303 0.0200794991 0.0059527826 0.1158010000 245639740 0 1782640640 -0.1697817296 0.3308850229 2.3951060772 531 21.2000000000 0.0074484199 0.0064552043 0.0200794991 0.0059645223 0.1183320000 245641854 0 1781899264 -0.1739297360 0.3318015933 2.3928942680 532 21.2400000000 0.0066575850 0.0064555847 0.0200794991 0.0059612179 0.1071940000 245640288 0 1780756480 -0.1776094735 0.3303146958 2.3903985023 533 21.2800000000 0.0058646160 0.0064544760 0.0200794991 0.0059578811 0.1082610000 245645042 0 1779597312 -0.1809673756 0.3290348649 2.3891811371 534 21.3200000000 0.0072086165 0.0064558882 0.0200794991 0.0059653703 0.1082330000 245645768 0 1776058368 -0.1852527857 0.3277940154 2.3867330551 535 21.3600000000 0.0099579832 0.0064624342 0.0200794991 0.0059884362 0.1145830000 245645350 0 1774661632 -0.1906425506 0.3293517828 2.3872292042 536 21.4000000000 0.0012608117 0.0064527297 0.0200794991 0.0060330375 0.1104210000 245648896 0 1773232128 -0.1944690645 0.3198477030 2.3845767975 537 21.4400000000 0.0114964247 0.0064621220 0.0200794991 0.0061638587 0.1085670000 245648918 0 1771995136 -0.1994692683 0.3310608566 2.3796701431 538 21.4800000000 0.0025324931 0.0064548179 0.0200794991 0.0062150762 0.1054540000 245648204 0 1770598400 -0.2036694735 0.3224536180 2.3764061928 539 21.5200000000 0.0025263946 0.0064475295 0.0200794991 0.0062170162 0.1043370000 245649098 0 1771995136 -0.2084900439 0.3214660585 2.3751304150 540 21.5600000000 0.0044039618 0.0064437451 0.0200794991 0.0062208871 0.1031600000 245651236 0 1773785088 -0.2128400207 0.3224347532 2.3708183765 541 21.6000000000 0.0017202594 0.0064350141 0.0200794991 0.0062328171 0.1011620000 245653582 0 1775661056 -0.2185001969 0.3193763494 2.3710885048 542 21.6400000000 0.0012352306 0.0064254204 0.0200794991 0.0062505719 0.1301620000 245884427 0 1777041408 -0.2216121554 0.3145621419 2.3700878620 543 21.6800000000 0.0027446991 0.0064186419 0.0200794991 0.0062724101 0.2251650000 246061785 0 1779724288 -0.2249153554 0.3109917045 2.3675522804 544 21.7200000000 0.0013670323 0.0064093559 0.0200794991 0.0063627101 0.1566230000 246353094 0 1782054912 -0.2334820926 0.3087114096 2.3569991589 545 21.7600000000 0.0033099181 0.0064036688 0.0200794991 0.0063650785 0.1066970000 245874658 0 1783451648 -0.2375837713 0.3088216186 2.3515067101 546 21.8000000000 0.0032964619 0.0063979780 0.0200794991 0.0063657270 0.1013730000 245875520 0 1785118720 -0.2421446741 0.3080334961 2.3472816944 547 21.8400000000 0.0043424345 0.0063942201 0.0200794991 0.0063725555 0.1119680000 245880106 0 1786515456 -0.2456295490 0.3050530255 2.3425488472 548 21.8800000000 0.0039404607 0.0063897425 0.0200794991 0.0063672872 0.0988680000 245875324 0 1784000512 -0.2516576350 0.3098685443 2.3362271786 549 21.9200000000 0.0065341922 0.0063900056 0.0200794991 0.0063631921 0.0958870000 245876350 0 1783111680 -0.2562217712 0.3101938665 2.3324310780 550 21.9600000000 0.0036351788 0.0063849968 0.0200794991 0.0063762045 0.1164190000 246037063 0 1781735424 -0.2606102824 0.3054564893 2.3287014961 551 22.0000000000 0.0034025812 0.0063795841 0.0200794991 0.0063848801 0.1815980000 246153925 0 1781190656 -0.2649614215 0.3040148616 2.3219604492 552 22.0400000000 0.0067768781 0.0063803038 0.0200794991 0.0063822818 0.1469090000 246488262 0 1783607296 -0.2700967193 0.3068088889 2.3151276112 553 22.0800000000 0.0033370529 0.0063748006 0.0200794991 0.0063896500 0.0955310000 246029138 0 1784987648 -0.2746348977 0.3114367127 2.3087852001 554 22.1200000000 0.0024796831 0.0063677697 0.0200794991 0.0063908507 0.0919330000 246031908 0 1786630144 -0.2801844478 0.3093068302 2.3036968708 555 22.1600000000 0.0044395919 0.0063642955 0.0200794991 0.0063912424 0.1085190000 246172989 0 1782345728 -0.2831815481 0.3086588085 2.2987055779 556 22.2000000000 0.0080358963 0.0063673020 0.0200794991 0.0063978314 0.1781970000 246364563 0 1781493760 -0.2866052389 0.3035603166 2.2952461243 557 22.2400000000 0.0055230567 0.0063657863 0.0200794991 0.0064018348 0.1437030000 246664994 0 1784242176 -0.2907615304 0.3081939518 2.2876722813 558 22.2800000000 0.0064512598 0.0063659395 0.0200794991 0.0063977913 0.1150330000 246303643 0 1784512512 -0.2941032946 0.3059649765 2.2818889618 559 22.3200000000 0.0067978916 0.0063667122 0.0200794991 0.0063935455 0.1761900000 246477817 0 1786433536 -0.2967241108 0.3041005135 2.2755897045 560 22.3600000000 0.0030492947 0.0063607883 0.0200794991 0.0064115866 0.0963670000 246861451 0 1786331136 -0.3012614548 0.3065220416 2.2668550014 561 22.4000000000 0.0077921567 0.0063633397 0.0200794991 0.0064204542 0.1312360000 246546334 0 1781993472 -0.3036570549 0.3016490936 2.2615687847 562 22.4400000000 0.0076209330 0.0063655774 0.0200794991 0.0064314588 0.1647390000 246464856 0 1780031488 -0.3073877096 0.2979493737 2.2592418194 563 22.4800000000 0.0068615298 0.0063664583 0.0200794991 0.0064320904 0.1386160000 247176680 0 1781710848 -0.3095498979 0.2964352667 2.2521152496 564 22.5200000000 0.0065488289 0.0063667817 0.0200794991 0.0064297173 0.1702300000 246861292 0 1783349248 -0.3127599657 0.2975275218 2.2446796894 565 22.5600000000 0.0054247100 0.0063651143 0.0200794991 0.0064544308 0.1575680000 246886740 0 1785266176 -0.3191922605 0.3012516499 2.2288436890 566 22.6000000000 0.0056238226 0.0063638046 0.0200794991 0.0064563293 0.1659720000 246786107 0 1786822656 -0.3229085803 0.2980880439 2.2236993313 567 22.6400000000 0.0063454313 0.0063637722 0.0200794991 0.0064515157 0.1410900000 246798742 0 1784410112 -0.3269476891 0.2958924770 2.2168321609 568 22.6800000000 0.0040982864 0.0063597837 0.0200794991 0.0064832041 0.1361440000 246923026 0 1783353344 -0.3287269175 0.3010324240 2.2064797878 569 22.7200000000 0.0061016968 0.0063593301 0.0200794991 0.0064901632 0.1426610000 246919946 0 1779687424 -0.3344340026 0.2986805141 2.2030205727 570 22.7600000000 0.0054624924 0.0063577567 0.0200794991 0.0064872908 0.1308350000 247847922 0 1779167232 -0.3360892236 0.2951311767 2.1956012249 571 22.8000000000 0.0058643073 0.0063568925 0.0200794991 0.0064841965 0.1349360000 247531006 0 1776869376 -0.3372343779 0.2915526628 2.1877627373 572 22.8400000000 0.0053859940 0.0063551951 0.0200794991 0.0064983613 0.1366740000 247156787 0 1778282496 -0.3404639065 0.2972012460 2.1790075302 573 22.8800000000 0.0053552929 0.0063534501 0.0200794991 0.0064974899 0.1326010000 247143934 0 1780432896 -0.3454334140 0.2960106134 2.1744070053 574 22.9200000000 0.0050742789 0.0063512216 0.0200794991 0.0065160293 0.1280940000 247150480 0 1782472704 -0.3487695456 0.2966737151 2.1649997234 575 22.9600000000 0.0047153272 0.0063483765 0.0200794991 0.0065171051 0.1119790000 248135984 0 1786433536 -0.3515924215 0.2956793606 2.1567940712 576 23.0000000000 0.0060661137 0.0063478865 0.0200794991 0.0065193786 0.1491080000 247837476 0 1783320576 -0.3544057310 0.2911667228 2.1488296986 577 23.0400000000 0.0049976204 0.0063455464 0.0200794991 0.0065251841 0.1360370000 247274330 0 1785393152 -0.3588632643 0.2895107865 2.1424381733 578 23.0800000000 0.0053578718 0.0063438376 0.0200794991 0.0065218469 0.1111350000 248241709 0 1785434112 -0.3609675467 0.2895133495 2.1345133781 579 23.1200000000 0.0045085582 0.0063406678 0.0200794991 0.0065235942 0.0963630000 248359492 0 1784324096 -0.3630889952 0.2881174088 2.1268153191 580 23.1600000000 0.0037246256 0.0063361574 0.0200794991 0.0065282121 0.1281750000 247961804 0 1781870592 -0.3644725978 0.2893060744 2.1201529503 581 23.2000000000 0.0039042325 0.0063319717 0.0200794991 0.0065439146 0.1333850000 247456061 0 1783840768 -0.3698836863 0.2882122099 2.1131834984 582 23.2400000000 0.0023544971 0.0063251375 0.0200794991 0.0065509111 0.1320070000 247470304 0 1785217024 -0.3781237900 0.2835758328 2.1084549427 583 23.2800000000 0.0027897472 0.0063190734 0.0200794991 0.0065492416 0.1351910000 247598729 0 1784217600 -0.3798550963 0.2832917273 2.1013948917 584 23.3200000000 0.0032447467 0.0063138091 0.0200794991 0.0065527518 0.1382280000 247586492 0 1783439360 -0.3827367723 0.2827455699 2.0948877335 585 23.3600000000 0.0048310673 0.0063112745 0.0200794991 0.0065531570 0.1345410000 247698360 0 1782030336 -0.3881291151 0.2793775797 2.0869939327 586 23.4000000000 0.0034078562 0.0063063199 0.0200794991 0.0065534367 0.1351680000 247692404 0 1781149696 -0.3929293156 0.2777856588 2.0823931694 587 23.4400000000 0.0047407998 0.0063036529 0.0200794991 0.0065798801 0.1465060000 247919933 0 1780809728 -0.3958454728 0.2784313560 2.0741274357 588 23.4800000000 0.0031700677 0.0062983237 0.0200794991 0.0065887931 0.1404160000 247800128 0 1780752384 -0.4039799571 0.2773024738 2.0680439472 589 23.5200000000 0.0031934779 0.0062930523 0.0200794991 0.0065885270 0.1481490000 247954585 0 1779920896 -0.4103181362 0.2741045356 2.0609183311 590 23.5600000000 0.0026553874 0.0062868868 0.0200794991 0.0065912042 0.1476280000 247944884 0 1781649408 -0.4169830084 0.2727090120 2.0532016754 591 23.6000000000 0.0039931014 0.0062830056 0.0200794991 0.0065912654 0.1422090000 247987010 0 1783402496 -0.4221445918 0.2713174224 2.0454659462 592 23.6400000000 0.0033225026 0.0062780047 0.0200794991 0.0065908219 0.1452430000 249424450 0 1784389632 -0.4289389849 0.2706093192 2.0380501747 593 23.6800000000 0.0039662621 0.0062741063 0.0200794991 0.0065877694 0.1789220000 249233754 0 1782038528 -0.4339355826 0.2703022957 2.0310962200 594 23.7200000000 0.0046084495 0.0062713022 0.0200794991 0.0065891234 0.1707870000 248120132 0 1779306496 -0.4406309724 0.2669723630 2.0241975784 595 23.7600000000 0.0033173829 0.0062663376 0.0200794991 0.0066120780 0.1665680000 248167302 0 1779286016 -0.4505171180 0.2646746635 2.0160036087 596 23.8000000000 0.0039444366 0.0062624418 0.0200794991 0.0066226416 0.1221520000 249513147 0 1783926784 -0.4578310847 0.2635872960 2.0078744888 597 23.8400000000 0.0032384756 0.0062573765 0.0200794991 0.0066214663 0.1272230000 249967544 0 1785659392 -0.4616557956 0.2622694969 2.0007519722 598 23.8800000000 0.0034711268 0.0062527173 0.0200794991 0.0066231216 0.1996740000 249275904 0 1783549952 -0.4702317119 0.2623177767 1.9922009706 599 23.9200000000 0.0033847515 0.0062479293 0.0200794991 0.0066209433 0.2538180000 248437486 0 1781624832 -0.4785497189 0.2607894540 1.9839160442 600 23.9600000000 0.0031429618 0.0062427544 0.0200794991 0.0066195742 0.2439220000 248515052 0 1783898112 -0.4846994877 0.2591224313 1.9765160084 601 24.0000000000 0.0021190429 0.0062358930 0.0200794991 0.0066322360 0.1788880000 250131637 0 1785458688 -0.4929065108 0.2589395642 1.9688594341 602 24.0400000000 0.0038406842 0.0062319142 0.0200794991 0.0066812032 0.1490860000 250465792 0 1781456896 -0.5084203482 0.2595924735 1.9508789778 603 24.0800000000 0.0045670876 0.0062291533 0.0200794991 0.0066908438 0.2234790000 250053032 0 1778933760 -0.5169808269 0.2589831948 1.9428805113 604 24.1200000000 0.0044975160 0.0062262864 0.0200794991 0.0066884888 0.1216090000 248458240 0 1779257344 -0.5283259153 0.2552320957 1.9340206385 605 24.1600000000 0.0046296823 0.0062236474 0.0200794991 0.0067094353 0.1317950000 248465886 0 1781006336 -0.5351269245 0.2566335201 1.9260603189 606 24.2000000000 0.0046275789 0.0062210136 0.0200794991 0.0067141601 0.1263100000 248469320 0 1782636544 -0.5405846238 0.2567644119 1.9179261923 607 24.2400000000 0.0051467526 0.0062192438 0.0200794991 0.0067098023 0.1338810000 248474334 0 1784143872 -0.5461747646 0.2545222044 1.9092667103 608 24.2800000000 0.0050554755 0.0062173297 0.0200794991 0.0067193178 0.1337600000 248479500 0 1786191872 -0.5553362370 0.2544489503 1.9001489878 609 24.3200000000 0.0055972985 0.0062163116 0.0200794991 0.0067235007 0.1296910000 248479998 0 1784938496 -0.5634150505 0.2548273504 1.8919161558 610 24.3600000000 0.0049157673 0.0062141795 0.0200794991 0.0067212123 0.1298040000 248485988 0 1786433536 -0.5679581761 0.2529675066 1.8842861652 611 24.4000000000 0.0053534200 0.0062127708 0.0200794991 0.0067226973 0.1302530000 248486478 0 1783910400 -0.5724557042 0.2524780631 1.8754415512 612 24.4400000000 0.0061865319 0.0062127279 0.0200794991 0.0067242177 0.1294210000 248489980 0 1782906880 -0.5776022077 0.2497795671 1.8660848141 613 24.4800000000 0.0054896181 0.0062115483 0.0200794991 0.0067431153 0.1299030000 248493278 0 1780097024 -0.5870271921 0.2514644861 1.8578699827 614 24.5200000000 0.0038648888 0.0062077264 0.0200794991 0.0067392141 0.1268610000 248494704 0 1778335744 -0.5937949419 0.2481968254 1.8498846292 615 24.5600000000 0.0051201256 0.0062059579 0.0200794991 0.0067444079 0.1750480000 249104861 0 1776939008 -0.5979840755 0.2484323382 1.8421858549 616 24.6000000000 0.0045420933 0.0062032568 0.0200794991 0.0067405841 0.4954270000 249068500 0 1777938432 -0.6054585576 0.2466630340 1.8336455822 617 24.6400000000 0.0040040556 0.0061996925 0.0200794991 0.0067417759 0.3688270000 250702813 0 1783492608 -0.6129962802 0.2458451539 1.8250758648 618 24.6800000000 0.0021472387 0.0061931351 0.0200794991 0.0067532149 0.3177220000 250651422 0 1782927360 -0.6217197180 0.2457615584 1.8169438839 619 24.7200000000 0.0021523994 0.0061866073 0.0200794991 0.0067538994 0.1897420000 249079522 0 1783787520 -0.6248213649 0.2460536063 1.8093760014 620 24.7600000000 0.0033741985 0.0061820711 0.0200794991 0.0067818752 0.1978890000 249084908 0 1785274368 -0.6376755834 0.2454932630 1.7910995483 621 24.8000000000 0.0034042308 0.0061775979 0.0200794991 0.0067788083 0.1906660000 249083678 0 1784143872 -0.6417701840 0.2431245148 1.7835499048 622 24.8400000000 0.0034940802 0.0061732836 0.0200794991 0.0067909873 0.1880660000 249086172 0 1781846016 -0.6497558355 0.2421560884 1.7724034786 623 24.8800000000 0.0037185415 0.0061693434 0.0200794991 0.0067911517 0.1870570000 249088382 0 1780346880 -0.6544899940 0.2384862900 1.7646653652 624 24.9200000000 0.0034022261 0.0061649089 0.0200794991 0.0068107294 0.1837270000 249088264 0 1782345728 -0.6588398218 0.2401280999 1.7541421652 625 24.9600000000 0.0030662755 0.0061599511 0.0200794991 0.0068054449 0.1853980000 249089498 0 1783869440 -0.6640133262 0.2383560240 1.7437653542 626 25.0000000000 0.0041688932 0.0061567705 0.0200794991 0.0068218348 0.1762870000 249092372 0 1785126912 -0.6713460684 0.2397166193 1.7317180634 627 25.0400000000 0.0037917630 0.0061529986 0.0200794991 0.0068462940 0.1771530000 249093622 0 1784291328 -0.6769037843 0.2354642153 1.7241548300 628 25.0800000000 0.0042877048 0.0061500284 0.0200794991 0.0068569499 0.1764900000 249094992 0 1783103488 -0.6813543439 0.2362335026 1.7131420374 629 25.1200000000 0.0033373404 0.0061455567 0.0200794991 0.0068576598 0.1720710000 249097266 0 1778933760 -0.6889639497 0.2334524095 1.7010176182 630 25.1600000000 0.0069113257 0.0061467722 0.0200794991 0.0069023957 0.1718370000 249100784 0 1777537024 -0.6940643191 0.2380070388 1.6891574860 631 25.2000000000 0.0046944497 0.0061444706 0.0200794991 0.0069062130 0.1744820000 249102670 0 1778933760 -0.6961960793 0.2346987724 1.6795953512 632 25.2400000000 0.0071898391 0.0061461246 0.0200794991 0.0069108158 0.1722690000 249102964 0 1780969472 -0.7071521282 0.2336798459 1.6671434641 633 25.2800000000 0.0063394951 0.0061464301 0.0200794991 0.0069064728 0.1684210000 249103090 0 1782456320 -0.7107148170 0.2330980897 1.6543183327 634 25.3200000000 0.0073889433 0.0061483899 0.0200794991 0.0069033605 0.1763920000 249106000 0 1784504320 -0.7121211290 0.2331190407 1.6447074413 635 25.3600000000 0.0055715623 0.0061474815 0.0200794991 0.0069161493 0.1720180000 249107054 0 1786028032 -0.7156186104 0.2276158631 1.6376798153 636 25.4000000000 0.0055575762 0.0061465540 0.0200794991 0.0069632178 0.1747200000 249108276 0 1785008128 -0.7228263617 0.2286033481 1.6222718954 637 25.4400000000 0.0059653865 0.0061462696 0.0200794991 0.0069629404 0.1663680000 249109238 0 1784143872 -0.7344082594 0.2277876735 1.6065261364 638 25.4800000000 0.0058657196 0.0061458299 0.0200794991 0.0069630275 0.1702910000 249112968 0 1782484992 -0.7328451872 0.2290133834 1.5975034237 639 25.5200000000 0.0073641757 0.0061477365 0.0200794991 0.0069632496 0.1652800000 249111378 0 1781604352 -0.7368246913 0.2300886065 1.5863301754 640 25.5600000000 0.0075149178 0.0061498727 0.0200794991 0.0069615260 0.1732850000 249117632 0 1783529472 -0.7425290346 0.2284091413 1.5733571053 641 25.6000000000 0.0063844011 0.0061502386 0.0200794991 0.0069600957 0.1652790000 249118002 0 1784889344 -0.7453559637 0.2255097628 1.5623924732 642 25.6400000000 0.0057973317 0.0061496889 0.0200794991 0.0069551629 0.1655880000 249120596 0 1786535936 -0.7469109297 0.2240497768 1.5515244007 643 25.6800000000 0.0080440762 0.0061526351 0.0200794991 0.0069543721 0.1655790000 249121330 0 1783271424 -0.7516500950 0.2240285724 1.5389704704 644 25.7200000000 0.0050016032 0.0061508477 0.0200794991 0.0069521985 0.1716280000 249122156 0 1782362112 -0.7521834373 0.2204061747 1.5272271633 645 25.7600000000 0.0070320596 0.0061522140 0.0200794991 0.0069532784 0.1665770000 249125802 0 1784164352 -0.7594652176 0.2203563750 1.5143270493 646 25.8000000000 0.0056114709 0.0061513769 0.0200794991 0.0069495463 0.1918870000 249126684 0 1785528320 -0.7593381405 0.2188368589 1.5039577484 647 25.8400000000 0.0063648946 0.0061517069 0.0200794991 0.0069506453 0.1752300000 249128630 0 1784299520 -0.7631262541 0.2190777212 1.4916688204 648 25.8800000000 0.0098559381 0.0061574233 0.0200794991 0.0069567765 0.1690210000 249130952 0 1783492608 -0.7600495219 0.2172920257 1.4895255566 649 25.9200000000 0.0076346588 0.0061596995 0.0200794991 0.0069823632 0.1634920000 249133274 0 1782259712 -0.7667829990 0.2171571106 1.4719781876 650 25.9600000000 0.0057074865 0.0061590038 0.0200794991 0.0069826375 0.1669340000 249133768 0 1784025088 -0.7723184824 0.2117129862 1.4596769810 651 26.0000000000 0.0066068224 0.0061596917 0.0200794991 0.0069872779 0.1655840000 249136558 0 1785655296 -0.7750669122 0.2096408010 1.4505062103 652 26.0400000000 0.0081265615 0.0061627083 0.0200794991 0.0070122641 0.1710470000 249138416 0 1784172544 -0.7758287191 0.2112035155 1.4384388924 653 26.0800000000 0.0066103712 0.0061633939 0.0200794991 0.0070093764 0.1680270000 249141706 0 1782644736 -0.7810121179 0.2062735558 1.4248607159 654 26.1200000000 0.0079485262 0.0061661235 0.0200794991 0.0070126383 0.1664520000 249140844 0 1781370880 -0.7849495411 0.2037046254 1.4160950184 655 26.1600000000 0.0079561705 0.0061688564 0.0200794991 0.0070213580 0.1663870000 249144446 0 1783246848 -0.7859671116 0.2014088184 1.4054372311 656 26.2000000000 0.0074897427 0.0061708699 0.0200794991 0.0070177222 0.1770500000 249146080 0 1784893440 -0.7913284898 0.1976267695 1.3944313526 657 26.2400000000 0.0084926486 0.0061744038 0.0200794991 0.0070364156 0.2214700000 249745449 0 1786798080 -0.7970225811 0.1961736381 1.3803204298 658 26.2800000000 0.0093622971 0.0061792486 0.0200794991 0.0070369193 0.4735760000 251128211 0 1785372672 -0.7994409800 0.1942601800 1.3708591461 659 26.3200000000 0.0090727257 0.0061836393 0.0200794991 0.0070324956 0.3224070000 251000252 0 1787019264 -0.8050674200 0.1908934265 1.3577877283 660 26.3600000000 0.0087995613 0.0061876029 0.0200794991 0.0070282857 0.1997420000 249704008 0 1782820864 -0.8081690073 0.1878703088 1.3466334343 661 26.4000000000 0.0077094552 0.0061899052 0.0200794991 0.0070259642 0.2032890000 249705678 0 1784115200 -0.8111257553 0.1852765530 1.3355882168 662 26.4400000000 0.0083251055 0.0061931306 0.0200794991 0.0070288043 0.1979940000 249707084 0 1786294272 -0.8166753054 0.1840138435 1.3233226538 663 26.4800000000 0.0090248752 0.0061974017 0.0200794991 0.0070300936 0.2026500000 249708330 0 1783742464 -0.8216825128 0.1838642061 1.3098475933 664 26.5200000000 0.0081650168 0.0062003650 0.0200794991 0.0070286914 0.1978300000 249710828 0 1782329344 -0.8258942366 0.1802662611 1.2978806496 665 26.5600000000 0.0088919252 0.0062044124 0.0200794991 0.0070545472 0.1898490000 249712282 0 1781039104 -0.8345735669 0.1788175851 1.2731455564 666 26.6000000000 0.0086262012 0.0062080487 0.0200794991 0.0070503354 0.1904590000 249714692 0 1780297728 -0.8394730091 0.1783464551 1.2594084740 667 26.6400000000 0.0083978213 0.0062113318 0.0200794991 0.0070478747 0.1844220000 249716514 0 1782210560 -0.8422778845 0.1779567450 1.2476017475 668 26.6800000000 0.0086916145 0.0062150448 0.0200794991 0.0070464580 0.1897770000 249717008 0 1784115200 -0.8482598066 0.1769922823 1.2340497971 669 26.7200000000 0.0080053816 0.0062177209 0.0200794991 0.0070439414 0.1884050000 249719214 0 1785765888 -0.8501518965 0.1772507131 1.2221254110 670 26.7600000000 0.0076552480 0.0062198665 0.0200794991 0.0070389722 0.2222030000 249721136 0 1784995840 -0.8533120155 0.1773761660 1.2096834183 671 26.8000000000 0.0082941875 0.0062229579 0.0200794991 0.0070427278 0.1828450000 249722866 0 1784401920 -0.8588132858 0.1766417772 1.1965737343 672 26.8400000000 0.0088013681 0.0062267948 0.0200794991 0.0070459381 0.1832470000 249723772 0 1786294272 -0.8640750647 0.1747829914 1.1834306717 673 26.8800000000 0.0091101946 0.0062310792 0.0200794991 0.0070476630 0.1834490000 249725922 0 1784639488 -0.8681696653 0.1724997759 1.1705102921 674 26.9200000000 0.0086521497 0.0062346713 0.0200794991 0.0070430508 0.1808830000 249728196 0 1783615488 -0.8686065674 0.1704740524 1.1590011120 675 26.9600000000 0.0096082855 0.0062396692 0.0200794991 0.0070637000 0.1797740000 249728730 0 1786003456 -0.8700687885 0.1694334745 1.1469819546 676 27.0000000000 0.0095952172 0.0062446330 0.0200794991 0.0070686722 0.1751550000 249730268 0 1784758272 -0.8738296032 0.1678345352 1.1335690022 677 27.0400000000 0.0090276860 0.0062487439 0.0200794991 0.0070704970 0.1732410000 249732074 0 1783599104 -0.8761047125 0.1669666618 1.1229050159 678 27.0800000000 0.0092903990 0.0062532301 0.0200794991 0.0070747581 0.1729750000 249733748 0 1783459840 -0.8791465759 0.1667064726 1.1119486094 679 27.1200000000 0.0089892577 0.0062572596 0.0200794991 0.0070759446 0.1706700000 249735146 0 1784750080 -0.8829082251 0.1638418287 1.1002326012 680 27.1600000000 0.0085762208 0.0062606698 0.0200794991 0.0070744645 0.1722980000 249736468 0 1786527744 -0.8853782415 0.1626721770 1.0902473927 681 27.2000000000 0.0093073631 0.0062651437 0.0200794991 0.0070900510 0.1741170000 249738242 0 1783853056 -0.8882080317 0.1630199254 1.0802633762 682 27.2400000000 0.0089488495 0.0062690788 0.0200794991 0.0070902221 0.1656240000 249740016 0 1782816768 -0.8921662569 0.1621116996 1.0692763329 683 27.2800000000 0.0084761549 0.0062723102 0.0200794991 0.0070867700 0.1666630000 249741590 0 1784623104 -0.8961135149 0.1622370183 1.0565236807 684 27.3200000000 0.0114962626 0.0062799476 0.0200794991 0.0070995185 0.2203990000 250385123 0 1786867712 -0.8928321600 0.1614487171 1.0563441515 685 27.3600000000 0.0119255371 0.0062881893 0.0200794991 0.0071060496 0.5185900000 251194773 0 1786363904 -0.8937082887 0.1608698815 1.0470378399 686 27.4000000000 0.0120408414 0.0062965751 0.0200794991 0.0071108481 0.2816180000 252012923 0 1784541184 -0.8985188007 0.1596463919 1.0346171856 687 27.4400000000 0.0111726820 0.0063036728 0.0200794991 0.0071202843 0.2517690000 251943384 0 1783627776 -0.9022895098 0.1585267037 1.0212557316 688 27.4800000000 0.0113856727 0.0063110594 0.0200794991 0.0071177473 0.1991870000 250349672 0 1784614912 -0.9046387672 0.1585960537 1.0117471218 689 27.5200000000 0.0104612224 0.0063170828 0.0200794991 0.0071136168 0.2030990000 250351186 0 1786265600 -0.9097451568 0.1568020731 0.9981795549 690 27.5600000000 0.0107535440 0.0063235125 0.0200794991 0.0071130707 0.2004740000 250352340 0 1784483840 -0.9106669426 0.1565523893 0.9877617955 691 27.6000000000 0.0111701302 0.0063305264 0.0200794991 0.0071116087 0.1974450000 250354138 0 1781813248 -0.9125702381 0.1559602171 0.9769332409 692 27.6400000000 0.0136611704 0.0063411198 0.0200794991 0.0071086040 0.1887810000 250355860 0 1783853056 -0.9132367969 0.1530894935 0.9687379599 693 27.6800000000 0.0108329374 0.0063476015 0.0200794991 0.0071095880 0.2270860000 250357366 0 1785884672 -0.9181624651 0.1523785591 0.9518226981 694 27.7200000000 0.0105723152 0.0063536890 0.0200794991 0.0071075329 0.1823470000 250359032 0 1784119296 -0.9193716049 0.1493284851 0.9406818151 695 27.7600000000 0.0107447179 0.0063600070 0.0200794991 0.0071043329 0.1898040000 250360546 0 1783066624 -0.9211853147 0.1465246528 0.9282767773 696 27.8000000000 0.0115991663 0.0063675346 0.0200794991 0.0071002000 0.1967430000 250361876 0 1784594432 -0.9238253832 0.1452742517 0.9160466194 697 27.8400000000 0.0100758793 0.0063728550 0.0200794991 0.0071046693 0.1832020000 250363710 0 1786793984 -0.9288319349 0.1363029629 0.8887391090 698 27.8800000000 0.0106110647 0.0063789269 0.0200794991 0.0071011560 0.1862950000 250364908 0 1782845440 -0.9272547960 0.1331470460 0.8792674541 699 27.9200000000 0.0116445804 0.0063864601 0.0200794991 0.0071191807 0.1814460000 250366230 0 1781944320 -0.9305421114 0.1356960088 0.8649032116 700 27.9600000000 0.0115744919 0.0063938715 0.0200794991 0.0071178642 0.1863480000 250367920 0 1783726080 -0.9309483767 0.1359067708 0.8503686786 701 28.0000000000 0.0112472102 0.0064007950 0.0200794991 0.0071199558 0.1778200000 250369394 0 1785122816 -0.9298920631 0.1341619343 0.8382260799 702 28.0400000000 0.0112459725 0.0064076970 0.0200794991 0.0071170593 0.1763730000 250371236 0 1784479744 -0.9290187359 0.1355613917 0.8245246410 703 28.0800000000 0.0111870226 0.0064144954 0.0200794991 0.0071134204 0.1716760000 250372434 0 1783611392 -0.9327561259 0.1331388205 0.8096551895 704 28.1200000000 0.0107557056 0.0064206619 0.0200794991 0.0071140497 0.1752120000 250373908 0 1780150272 -0.9326738715 0.1297796518 0.7956336737 705 28.1600000000 0.0109099224 0.0064270297 0.0200794991 0.0071158168 0.1693680000 250375482 0 1779654656 -0.9328321815 0.1251215637 0.7825569510 706 28.2000000000 0.0102681629 0.0064324704 0.0200794991 0.0071204694 0.2239070000 251047919 0 1781936128 -0.9345176816 0.1206797510 0.7679113150 707 28.2400000000 0.0107834935 0.0064386246 0.0200794991 0.0071357414 0.4770090000 251034490 0 1783386112 -0.9347213507 0.1213105470 0.7529056072 708 28.2800000000 0.0106969103 0.0064446391 0.0200794991 0.0071340930 0.2923720000 252574246 0 1784971264 -0.9377356768 0.1222919822 0.7374330163 709 28.3200000000 0.0097093480 0.0064492438 0.0200794991 0.0071380791 0.2402990000 252456750 0 1786667008 -0.9388519526 0.1185146645 0.7216095924 710 28.3600000000 0.0099249212 0.0064541391 0.0200794991 0.0071353440 0.1796340000 250990796 0 1784623104 -0.9357510209 0.1177231967 0.7118014097 711 28.4000000000 0.0099077281 0.0064589965 0.0200794991 0.0071313873 0.1861070000 250992618 0 1783468032 -0.9368368983 0.1164984480 0.6992149949 712 28.4400000000 0.0101754339 0.0064642162 0.0200794991 0.0071289607 0.1815730000 250993732 0 1785106432 -0.9379203320 0.1140238643 0.6870156527 713 28.4800000000 0.0093198856 0.0064682213 0.0200794991 0.0071244560 0.1789420000 250995298 0 1786482688 -0.9358289838 0.1099144369 0.6769714952 714 28.5200000000 0.0092673730 0.0064721417 0.0200794991 0.0071295833 0.1841430000 250996956 0 1782816768 -0.9362280965 0.1093637794 0.6657309532 715 28.5600000000 0.0099034170 0.0064769407 0.0200794991 0.0071436094 0.1769500000 250998238 0 1782431744 -0.9378652573 0.1121774688 0.6508905292 716 28.6000000000 0.0097289952 0.0064814827 0.0200794991 0.0071411687 0.1753450000 250999920 0 1784745984 -0.9379330873 0.1111866236 0.6383469105 717 28.6400000000 0.0095189577 0.0064857190 0.0200794991 0.0071451007 0.2077890000 251001058 0 1785978880 -0.9367293715 0.1065056846 0.6299790144 718 28.6800000000 0.0096482895 0.0064901237 0.0200794991 0.0071477391 0.1801850000 251002716 0 1784848384 -0.9372769594 0.1058790535 0.6210419536 719 28.7200000000 0.0100173252 0.0064950294 0.0200794991 0.0071495907 0.1689310000 251004498 0 1786630144 -0.9395114183 0.1056053787 0.6088300347 720 28.7600000000 0.0108045377 0.0065010149 0.0200794991 0.0071503283 0.1728620000 251005964 0 1785106432 -0.9418216348 0.1049840674 0.5979173183 721 28.8000000000 0.0101460274 0.0065060703 0.0200794991 0.0071488730 0.1705380000 251007346 0 1786884096 -0.9395276904 0.1063470542 0.5866684914 722 28.8400000000 0.0097665656 0.0065105863 0.0200794991 0.0071515196 0.1665150000 251008636 0 1785384960 -0.9465945363 0.1075731143 0.5725523233 723 28.8800000000 0.0103474334 0.0065158931 0.0200794991 0.0071564556 0.1650330000 251010394 0 1784455168 -0.9523237944 0.1076486632 0.5617657304 724 28.9200000000 0.0112639926 0.0065224513 0.0200794991 0.0071566244 0.1655130000 251011656 0 1782669312 -0.9546630979 0.1091406792 0.5533356071 725 28.9600000000 0.0101986397 0.0065275219 0.0200794991 0.0071545348 0.2156150000 251696545 0 1782054912 -0.9585592747 0.1084622443 0.5418189764 726 29.0000000000 0.0104644345 0.0065329446 0.0200794991 0.0071581495 0.4546140000 251672644 0 1781833728 -0.9616217017 0.1063649952 0.5282851458 727 29.0400000000 0.0105898622 0.0065385250 0.0200794991 0.0071604854 0.3085200000 252969873 0 1786507264 -0.9714339375 0.1053057313 0.5087019205 728 29.0800000000 0.0100812605 0.0065433914 0.0200794991 0.0071681970 0.2304790000 252838156 0 1784360960 -0.9835894108 0.1038418487 0.4923368394 729 29.1200000000 0.0102255233 0.0065484423 0.0200794991 0.0072054936 0.1749550000 251633082 0 1784860672 -0.9868637919 0.0981966779 0.4843068123 730 29.1600000000 0.0104727158 0.0065538180 0.0200794991 0.0072039634 0.1788990000 251634956 0 1786634240 -0.9893641472 0.0983476713 0.4755292535 731 29.2000000000 0.0099387337 0.0065584485 0.0200794991 0.0071992520 0.1841930000 251636614 0 1783476224 -0.9977816343 0.1003052816 0.4610266387 732 29.2400000000 0.0102469567 0.0065634875 0.0200794991 0.0072064360 0.1750220000 251637928 0 1782603776 -1.0035867691 0.1016402170 0.4496549964 733 29.2800000000 0.0101856058 0.0065684290 0.0200794991 0.0072100199 0.1701930000 251639458 0 1784102912 -1.0068228245 0.1043212265 0.4393962622 734 29.3200000000 0.0105408924 0.0065738411 0.0200794991 0.0072072562 0.1686210000 251641232 0 1785618432 -1.0149278641 0.1088314205 0.4266532362 735 29.3600000000 0.0104987230 0.0065791810 0.0200794991 0.0072501646 0.1773640000 251642522 0 1784610816 -1.0195991993 0.1068918332 0.4174413085 736 29.4000000000 0.0102849957 0.0065842161 0.0200794991 0.0072558835 0.1694660000 251644104 0 1783889920 -1.0223886967 0.1074713022 0.4087390304 737 29.4400000000 0.0109072821 0.0065900819 0.0200794991 0.0072521746 0.1717190000 251645394 0 1781592064 -1.0278028250 0.1128534973 0.3957173824 738 29.4800000000 0.0101032611 0.0065948423 0.0200794991 0.0072819988 0.1723400000 251647176 0 1780801536 -1.0325306654 0.1130284742 0.3844660521 739 29.5200000000 0.0114837149 0.0066014578 0.0200794991 0.0073153751 0.1623820000 251648414 0 1782841344 -1.0320717096 0.1126026362 0.3813990057 740 29.5600000000 0.0111260582 0.0066075721 0.0200794991 0.0073140439 0.1633040000 251649988 0 1784872960 -1.0347926617 0.1117530391 0.3718481064 741 29.6000000000 0.0112937074 0.0066138962 0.0200794991 0.0073105144 0.1602260000 251651302 0 1786126336 -1.0372235775 0.1121627465 0.3607446551 742 29.6400000000 0.0106212851 0.0066192970 0.0200794991 0.0073075514 0.1889560000 251652692 0 1784614912 -1.0401947498 0.1124441326 0.3484028280 743 29.6800000000 0.0115950694 0.0066259939 0.0200794991 0.0073079284 0.1602670000 251654274 0 1783848960 -1.0432325602 0.1151054129 0.3422169089 744 29.7200000000 0.0118978089 0.0066330796 0.0200794991 0.0073110337 0.1587600000 251656208 0 1783218176 -1.0491642952 0.1179797500 0.3313078880 745 29.7600000000 0.0117384903 0.0066399325 0.0200794991 0.0073294056 0.1637070000 251657262 0 1782689792 -1.0523062944 0.1183358580 0.3254715502 746 29.8000000000 0.0116063599 0.0066465899 0.0200794991 0.0073464435 0.1559780000 251658752 0 1784619008 -1.0563925505 0.1191864312 0.3182109296 747 29.8400000000 0.0116296690 0.0066532607 0.0200794991 0.0073826169 0.1550290000 251660306 0 1786269696 -1.0527511835 0.1173275709 0.3119583130 748 29.8800000000 0.0111971628 0.0066593355 0.0200794991 0.0073845866 0.1556600000 251661772 0 1784635392 -1.0500572920 0.1138670743 0.3097773790 749 29.9200000000 0.0117808152 0.0066661732 0.0200794991 0.0073865701 0.1579740000 251663430 0 1782845440 -1.0545897484 0.1140444130 0.3025448322 750 29.9600000000 0.0117986761 0.0066730166 0.0200794991 0.0073818559 0.1523840000 251665036 0 1783111680 -1.0587661266 0.1164490581 0.2898732722 751 30.0000000000 0.0112652937 0.0066791314 0.0200794991 0.0073885091 0.1536720000 251666510 0 1782308864 -1.0594948530 0.1148849875 0.2851099074 752 30.0400000000 0.0113611482 0.0066853575 0.0200794991 0.0073865766 0.1577340000 251667900 0 1784238080 -1.0614744425 0.1140359938 0.2822110653 753 30.0800000000 0.0107643148 0.0066907745 0.0200794991 0.0073825396 0.1567770000 251669182 0 1785888768 -1.0655834675 0.1169245914 0.2727143466 754 30.1200000000 0.0115209566 0.0066971805 0.0200794991 0.0074050290 0.1535090000 251670756 0 1785143296 -1.0649019480 0.1144338250 0.2681018412 755 30.1600000000 0.0110977311 0.0067030091 0.0200794991 0.0074076239 0.1608470000 251672506 0 1784627200 -1.0600739717 0.1114784628 0.2660311759 756 30.2000000000 0.0109078037 0.0067085710 0.0200794991 0.0074036836 0.1520430000 251673644 0 1784000512 -1.0632576942 0.1104748845 0.2569482327 757 30.2400000000 0.0109001445 0.0067141081 0.0200794991 0.0074025415 0.2151120000 252373837 0 1783697408 -1.0649842024 0.1097177267 0.2507643104 758 30.2800000000 0.0113889258 0.0067202754 0.0200794991 0.0074002751 0.4861870000 252367820 0 1786449920 -1.0671818256 0.1106375754 0.2451581061 759 30.3200000000 0.0111878105 0.0067261615 0.0200794991 0.0073957073 0.3389760000 253770849 0 1784266752 -1.0683816671 0.1131701320 0.2341438830 760 30.3600000000 0.0112375440 0.0067320975 0.0200794991 0.0074356409 0.2246230000 253715742 0 1783476224 -1.0648005009 0.1095725447 0.2314993441 761 30.4000000000 0.0113978004 0.0067382285 0.0200794991 0.0074352321 0.2042160000 252318346 0 1784066048 -1.0643733740 0.1083637923 0.2268596739 762 30.4400000000 0.0114651332 0.0067444318 0.0200794991 0.0074324513 0.1914110000 252319836 0 1785610240 -1.0673216581 0.1084691286 0.2193757296 763 30.4800000000 0.0114162909 0.0067505548 0.0200794991 0.0074408230 0.1932500000 252321934 0 1784565760 -1.0675076246 0.1057922840 0.2117852867 764 30.5200000000 0.0115552004 0.0067568436 0.0200794991 0.0074374281 0.1848140000 252323148 0 1783840768 -1.0661420822 0.1072386727 0.2050927281 765 30.5600000000 0.0115543846 0.0067631149 0.0200794991 0.0074355781 0.1848640000 252324630 0 1782808576 -1.0656701326 0.1060773656 0.1960184723 766 30.6000000000 0.0112124886 0.0067689235 0.0200794991 0.0074469205 0.1837800000 252326096 0 1781145600 -1.0609810352 0.1000598744 0.1922835112 767 30.6400000000 0.0115265111 0.0067751263 0.0200794991 0.0074446586 0.2079880000 252327378 0 1778249728 -1.0608938932 0.1005211994 0.1822580397 768 30.6800000000 0.0118259545 0.0067817029 0.0200794991 0.0074438220 0.1748550000 252329212 0 1779597312 -1.0599967241 0.0994536877 0.1740494072 769 30.7200000000 0.0115608405 0.0067879177 0.0200794991 0.0074499782 0.1784900000 252330618 0 1781653504 -1.0544760227 0.0931133479 0.1706428975 770 30.7600000000 0.0115008652 0.0067940384 0.0200794991 0.0074508572 0.1818700000 252332092 0 1783414784 -1.0531868935 0.0925666541 0.1632574499 771 30.8000000000 0.0119308215 0.0068007009 0.0200794991 0.0074514602 0.1705300000 252333398 0 1785065472 -1.0534154177 0.0908373147 0.1535312682 772 30.8400000000 0.0128639927 0.0068085549 0.0200794991 0.0074473237 0.1748520000 252334912 0 1786736640 -1.0462505817 0.0873369798 0.1496893466 773 30.8800000000 0.0123738535 0.0068157545 0.0200794991 0.0074521452 0.1662930000 252336026 0 1783529472 -1.0415164232 0.0846718848 0.1420412064 774 30.9200000000 0.0129026147 0.0068236187 0.0200794991 0.0074716325 0.1649430000 252337772 0 1782661120 -1.0432187319 0.0866282284 0.1319083869 775 30.9600000000 0.0119754523 0.0068302662 0.0200794991 0.0074669882 0.1613210000 252339702 0 1784700928 -1.0445133448 0.0843902826 0.1250635982 776 31.0000000000 0.0132723153 0.0068385678 0.0200794991 0.0074687682 0.1599560000 252341100 0 1786605568 -1.0443789959 0.0850248635 0.1209608912 777 31.0400000000 0.0139462464 0.0068477154 0.0200794991 0.0074692404 0.1601500000 252342214 0 1783447552 -1.0393865108 0.0861768574 0.1136180162 778 31.0800000000 0.0127018234 0.0068552399 0.0200794991 0.0074729389 0.1592620000 252343872 0 1782136832 -1.0404428244 0.0853166804 0.1044397280 779 31.1200000000 0.0116648916 0.0068614141 0.0200794991 0.0074845351 0.1561850000 252344626 0 1780654080 -1.0418162346 0.0871911198 0.0932656154 780 31.1600000000 0.0131807756 0.0068695158 0.0200794991 0.0074868809 0.1538160000 252346860 0 1779634176 -1.0401750803 0.0940837115 0.0872249305 781 31.2000000000 0.0124401106 0.0068766485 0.0200794991 0.0074834642 0.1546660000 252347982 0 1778491392 -1.0354498625 0.0937457383 0.0786731243 782 31.2400000000 0.0120365573 0.0068832468 0.0200794991 0.0074803487 0.1523280000 252348620 0 1777733632 -1.0314999819 0.0914522186 0.0716041550 783 31.2800000000 0.0132930856 0.0068914331 0.0200794991 0.0074801168 0.1529770000 252350410 0 1775296512 -1.0283482075 0.0919437259 0.0673945993 784 31.3200000000 0.0113111027 0.0068970704 0.0200794991 0.0074768773 0.1560630000 252351956 0 1774923776 -1.0262521505 0.0908382982 0.0566696152 785 31.3600000000 0.0133848973 0.0069053352 0.0200794991 0.0075050961 0.1505650000 252352794 0 1776304128 -1.0196572542 0.0814335868 0.0609966964 786 31.4000000000 0.0123875253 0.0069123100 0.0200794991 0.0075376509 0.1473420000 252352376 0 1778479104 -1.0251456499 0.0806589276 0.0514873117 787 31.4400000000 0.0155506283 0.0069232862 0.0200794991 0.0075394166 0.1493840000 252350462 0 1780240384 -1.0230813026 0.0797212422 0.0504334643 788 31.4800000000 0.0101756481 0.0069274136 0.0200794991 0.0075583828 0.1460550000 252351660 0 1782018048 -1.0105762482 0.0701777190 0.0448293760 789 31.5200000000 0.0114846900 0.0069331896 0.0200794991 0.0076013889 0.1447660000 252353558 0 1783541760 -1.0175362825 0.0798448622 0.0319185592 790 31.5600000000 0.0072931433 0.0069336452 0.0200794991 0.0076014423 0.1479790000 252353592 0 1785065472 -1.0099705458 0.0758429170 0.0312397704 791 31.6000000000 0.0073225149 0.0069341368 0.0200794991 0.0076006097 0.1546400000 252354430 0 1784324096 -1.0119987726 0.0780788437 0.0230602287 792 31.6400000000 0.0056909411 0.0069325672 0.0200794991 0.0076074090 0.1499270000 252358588 0 1783017472 -1.0091454983 0.0711340606 0.0185902119 793 31.6800000000 0.0148542989 0.0069425567 0.0200794991 0.0076239417 0.1532510000 252359986 0 1781923840 -1.0054203272 0.0616559982 0.0253598802 794 31.7200000000 0.0097326590 0.0069460707 0.0200794991 0.0076961475 0.1408500000 252360356 0 1783832576 -1.0075842142 0.0757129490 0.0111960247 795 31.7600000000 0.0107044838 0.0069507983 0.0200794991 0.0076939768 0.1424790000 252362982 0 1785327616 -1.0111514330 0.0775505006 0.0037729070 796 31.8000000000 0.0211458504 0.0069686313 0.0211458504 0.0077212124 0.1529120000 252364296 0 1784078336 -1.0161492825 0.0844865069 -0.0003544614 797 31.8400000000 0.0085551832 0.0069706219 0.0211458504 0.0077660547 0.1776600000 252364466 0 1782046720 -1.0027284622 0.0698805228 -0.0009828880 798 31.8800000000 0.0123238396 0.0069773302 0.0211458504 0.0077839727 0.1525750000 252365296 0 1781170176 -1.0105764866 0.0723708123 -0.0052587837 799 31.9200000000 0.0103738308 0.0069815811 0.0211458504 0.0078080404 0.1439570000 252365958 0 1780391936 -1.0044751167 0.0753721073 -0.0135715827 800 31.9600000000 0.0101123899 0.0069854947 0.0211458504 0.0078349990 0.1422570000 252368820 0 1782026240 -1.0137964487 0.0707333237 -0.0201716721 801 32.0000000000 0.0111682769 0.0069907166 0.0211458504 0.0078392083 0.1467570000 252369934 0 1783803904 -1.0067658424 0.0610788278 -0.0152496174 802 32.0400000000 0.0096489284 0.0069940311 0.0211458504 0.0078454319 0.1461870000 252370404 0 1784946688 -1.0090731382 0.0573992878 -0.0202844217 803 32.0800000000 0.0068778321 0.0069938864 0.0211458504 0.0078592931 0.1395970000 252369278 0 1784225792 -1.0053611994 0.0560231954 -0.0284172967 804 32.1199999990 0.0065470501 0.0069933306 0.0211458504 0.0078545389 0.1382850000 252370100 0 1783312384 -1.0037941933 0.0481990129 -0.0314481854 805 32.1600000000 0.0125877932 0.0070002803 0.0211458504 0.0078934019 0.1449450000 252371842 0 1782308864 -1.0086317062 0.0547164455 -0.0334344730 806 32.2000000000 0.0112724733 0.0070055807 0.0211458504 0.0079414525 0.1380400000 252371744 0 1784078336 -0.9991532564 0.0567835122 -0.0520298332 807 32.2400000000 0.0128326677 0.0070128014 0.0211458504 0.0079418467 0.1415540000 252370986 0 1785581568 -0.9961910844 0.0567454956 -0.0559897497 808 32.2800000000 0.0149776395 0.0070226589 0.0211458504 0.0080001285 0.1472780000 252372936 0 1784225792 -1.0083584785 0.0684364736 -0.0672480091 809 32.3200000000 0.0100018186 0.0070263414 0.0211458504 0.0079996690 0.1421920000 252375882 0 1783328768 -1.0060749054 0.0621863976 -0.0757303387 810 32.3600000000 0.0047469675 0.0070235274 0.0211458504 0.0080176364 0.1391500000 252377724 0 1782185984 -1.0113264322 0.0535862446 -0.0826914683 811 32.4000000000 0.0129664419 0.0070308553 0.0211458504 0.0080226257 0.1383570000 252379390 0 1783410688 -1.0064847469 0.0513336211 -0.0825853869 812 32.4399999990 0.0113811009 0.0070362127 0.0211458504 0.0080383211 0.1366450000 252379200 0 1785073664 -1.0085381269 0.0436637141 -0.0828232691 813 32.4800000000 0.0118955597 0.0070421898 0.0211458504 0.0080771523 0.1375620000 252381142 0 1784225792 -1.0118497610 0.0525196791 -0.0945357531 814 32.5200000000 0.0081084613 0.0070434997 0.0211458504 0.0081000224 0.1408410000 252381604 0 1783418880 -1.0162051916 0.0624803528 -0.1160433516 815 32.5600000000 0.0109771350 0.0070483262 0.0211458504 0.0081295565 0.1382130000 252385946 0 1781567488 -1.0177183151 0.0560486540 -0.1159316823 816 32.6000000000 0.0139664942 0.0070568044 0.0211458504 0.0081295086 0.1391510000 252388632 0 1783824384 -1.0120611191 0.0525594391 -0.1194696203 817 32.6400000000 0.0153699620 0.0070669796 0.0211458504 0.0081331045 0.1376500000 252391846 0 1785454592 -1.0178654194 0.0548317693 -0.1259918958 818 32.6800000000 0.0331885852 0.0070989131 0.0331885852 0.0082503924 0.1894400000 253014622 0 1784352768 -0.9985128641 0.0515327938 -0.1327061653 819 32.7200000000 0.0343288071 0.0071321608 0.0343288071 0.0082495090 0.4359140000 253014138 0 1784832000 -0.9999773502 0.0453046747 -0.1359924376 820 32.7599999990 0.0331961773 0.0071639462 0.0343288071 0.0082496063 0.3122180000 254442435 0 1783681024 -1.0002369881 0.0458186418 -0.1438179314 821 32.7999999990 0.0285917055 0.0071900458 0.0343288071 0.0082725823 0.2312520000 254385968 0 1778974720 -1.0088499784 0.0519448593 -0.1596022546 822 32.8400000000 0.0281173233 0.0072155048 0.0343288071 0.0082692753 0.2071840000 252961996 0 1779351552 -1.0119169950 0.0497448891 -0.1676003635 823 32.8800000000 0.0296715181 0.0072427903 0.0343288071 0.0082666211 0.1928970000 252963002 0 1780830208 -1.0125212669 0.0511009544 -0.1717679650 824 32.9200000000 0.0297561977 0.0072701124 0.0343288071 0.0082675801 0.1893190000 252963824 0 1782775808 -1.0171128511 0.0532844812 -0.1818349659 825 32.9600000000 0.0289106704 0.0072963434 0.0343288071 0.0082732778 0.2231790000 252965934 0 1784516608 -1.0178360939 0.0465898477 -0.1854893565 826 33.0000000000 0.0288969576 0.0073224943 0.0343288071 0.0082709016 0.1999160000 252967676 0 1786159104 -1.0152599812 0.0470517799 -0.1917963028 827 33.0400000000 0.0314156078 0.0073516274 0.0343288071 0.0082683620 0.1994160000 252969418 0 1785286656 -1.0184180737 0.0462464318 -0.1996542662 828 33.0800000000 0.0287988875 0.0073775299 0.0343288071 0.0082851553 0.1868410000 252970976 0 1784385536 -1.0195794106 0.0349133611 -0.2014670074 829 33.1199999990 0.0296979994 0.0074044545 0.0343288071 0.0083065599 0.1877490000 252970418 0 1782738944 -1.0185374022 0.0383825116 -0.2068477571 830 33.1600000000 0.0296068862 0.0074312044 0.0343288071 0.0083110824 0.1859450000 252973540 0 1784418304 -1.0260446072 0.0411986187 -0.2185456306 831 33.2000000000 0.0253261216 0.0074527386 0.0343288071 0.0083167061 0.1847720000 252974094 0 1785905152 -1.0306261778 0.0361061767 -0.2276636064 832 33.2400000000 0.0281497259 0.0074776148 0.0343288071 0.0083145558 0.1824910000 252976120 0 1785032704 -1.0260283947 0.0344196968 -0.2260655761 833 33.2800000000 0.0294316486 0.0075039702 0.0343288071 0.0083159407 0.1833880000 252978138 0 1786564608 -1.0232546329 0.0320070051 -0.2318721414 834 33.3200000000 0.0282943677 0.0075288987 0.0343288071 0.0083223958 0.1881080000 252977672 0 1785548800 -1.0279325247 0.0314208381 -0.2413661182 835 33.3600000000 0.0265832879 0.0075517183 0.0343288071 0.0083257967 0.1801440000 252979966 0 1784643584 -1.0316638947 0.0316371657 -0.2510417104 836 33.4000000000 0.0264772028 0.0075743565 0.0343288071 0.0083314291 0.1782930000 252979944 0 1783373824 -1.0324736834 0.0333638452 -0.2597402334 837 33.4399999990 0.0281698257 0.0075989628 0.0343288071 0.0083274011 0.1752480000 252981702 0 1784897536 -1.0295791626 0.0294516869 -0.2639664412 838 33.4800000000 0.0277056005 0.0076229564 0.0343288071 0.0083241266 0.1765730000 252982732 0 1786400768 -1.0286035538 0.0257209353 -0.2708944678 839 33.5200000000 0.0242844932 0.0076428152 0.0343288071 0.0083207515 0.1826950000 252984230 0 1785290752 -1.0281938314 0.0222844705 -0.2812780142 840 33.5600000000 0.0276155900 0.0076665923 0.0343288071 0.0083213339 0.1738090000 252985996 0 1784532992 -1.0196599960 0.0203985870 -0.2847218812 841 33.6000000000 0.0272584781 0.0076898882 0.0343288071 0.0083186995 0.1778440000 252989050 0 1783504896 -1.0161844492 0.0163260624 -0.2912715077 842 33.6400000000 0.0294780433 0.0077157649 0.0343288071 0.0083168701 0.1708620000 252988752 0 1780703232 -1.0141645670 0.0136527047 -0.2956513464 843 33.6800000000 0.0224219114 0.0077332099 0.0343288071 0.0083576291 0.1673540000 252987458 0 1780080640 -1.0115964413 0.0106072426 -0.3196805716 844 33.7200000000 0.0245773587 0.0077531674 0.0343288071 0.0083625234 0.1656340000 252989700 0 1781211136 -1.0082741976 0.0111078024 -0.3280693889 845 33.7599999990 0.0243135113 0.0077727655 0.0343288071 0.0083674943 0.1662150000 252992454 0 1782861824 -1.0077910423 0.0114022344 -0.3389097154 846 33.7999999990 0.0274080280 0.0077959750 0.0343288071 0.0083816093 0.1696900000 252991284 0 1784893440 -1.0056729317 0.0195755847 -0.3483374715 847 33.8400000000 0.0281399917 0.0078199939 0.0343288071 0.0083779949 0.1627290000 252993578 0 1786183680 -1.0000138283 0.0209222399 -0.3592112660 848 33.8800000000 0.0229741000 0.0078378643 0.0343288071 0.0083894746 0.1736470000 252997108 0 1785528320 -0.9951040745 0.0169162713 -0.3700824678 849 33.9200000000 0.0271716528 0.0078606367 0.0343288071 0.0083869313 0.1628140000 252996074 0 1784406016 -0.9897533059 0.0128048025 -0.3747719228 850 33.9600000000 0.0243312214 0.0078800139 0.0343288071 0.0083839276 0.1624310000 252998568 0 1782882304 -0.9846774340 0.0104475785 -0.3861882985 851 34.0000000000 0.0266056508 0.0079020182 0.0343288071 0.0083813001 0.1638630000 252997734 0 1781985280 -0.9769288301 0.0110398903 -0.3931220770 852 34.0400000000 0.0235412177 0.0079203740 0.0343288071 0.0083813390 0.1962930000 253001332 0 1783767040 -0.9746139050 0.0039313156 -0.4006053507 853 34.0800000000 0.0230816845 0.0079381481 0.0343288071 0.0083773769 0.1599080000 253003358 0 1785143296 -0.9696047306 0.0063341372 -0.4109457731 854 34.1199999990 0.0271128379 0.0079606009 0.0343288071 0.0083749576 0.1610360000 253003704 0 1784168448 -0.9632395506 0.0073682759 -0.4175773859 855 34.1600000000 0.0232367143 0.0079784677 0.0343288071 0.0083782555 0.1569000000 253004158 0 1783255040 -0.9624336958 0.0030295141 -0.4260953367 856 34.2000000000 0.0262401346 0.0079998015 0.0343288071 0.0083822144 0.1608070000 253005356 0 1782255616 -0.9534111619 0.0046980362 -0.4324926138 857 34.2400000000 0.0234961156 0.0080178835 0.0343288071 0.0083810657 0.1556580000 253007290 0 1784147968 -0.9506360292 -0.0023269206 -0.4410114288 858 34.2800000000 0.0218047705 0.0080339521 0.0343288071 0.0083848469 0.1596340000 253010160 0 1785651200 -0.9471781254 -0.0020099077 -0.4496403039 859 34.3200000000 0.0215829685 0.0080497252 0.0343288071 0.0083838281 0.1604300000 253010706 0 1784020992 -0.9436138868 -0.0001135450 -0.4589791000 860 34.3600000000 0.0225207340 0.0080665519 0.0343288071 0.0083884779 0.1644630000 253011620 0 1783001088 -0.9394637942 0.0024346523 -0.4682205617 861 34.4000000000 0.0221137423 0.0080828669 0.0343288071 0.0083846673 0.1582780000 253012442 0 1781874688 -0.9339885712 -0.0020703413 -0.4749978781 862 34.4400000000 0.0213025473 0.0080982029 0.0343288071 0.0083804411 0.1581760000 253013672 0 1783767040 -0.9304485917 -0.0028087795 -0.4831794798 863 34.4800000000 0.0231772438 0.0081156757 0.0343288071 0.0083766804 0.1547700000 253013666 0 1785540608 -0.9233505726 -0.0016602799 -0.4885875583 864 34.5200000000 0.0189178623 0.0081281783 0.0343288071 0.0083839525 0.1987250000 253541084 0 1784422400 -0.9229223132 -0.0001509599 -0.5017905235 865 34.5600000000 0.0185895059 0.0081402723 0.0343288071 0.0083879208 0.4043210000 253537094 0 1784348672 -0.9181815386 -0.0051337481 -0.5078270435 866 34.6000000000 0.0198943783 0.0081538452 0.0343288071 0.0083889805 0.2750180000 254528115 0 1785380864 -0.9139266014 -0.0172694735 -0.5074294209 867 34.6400000000 0.0168962888 0.0081639287 0.0343288071 0.0084574212 0.2059970000 254387026 0 1786413056 -0.9169511199 -0.0169332139 -0.5239095092 868 34.6800000000 0.0200965684 0.0081776760 0.0343288071 0.0084576925 0.1655200000 253493088 0 1787129856 -0.9081035256 -0.0186618865 -0.5263726711 869 34.7200000000 0.0204866864 0.0081918406 0.0343288071 0.0084639293 0.1697560000 253491702 0 1782931456 -0.9059658647 -0.0180967003 -0.5353100896 870 34.7600000000 0.0197643898 0.0082051424 0.0343288071 0.0084685650 0.1633780000 253490592 0 1782185984 -0.9012942910 -0.0190867223 -0.5457769036 871 34.8000000000 0.0194078162 0.0082180042 0.0343288071 0.0084652536 0.1629750000 253494198 0 1783701504 -0.8963383436 -0.0221991744 -0.5500999689 872 34.8400000000 0.0181435160 0.0082293867 0.0343288071 0.0084662064 0.1619410000 253493732 0 1785217024 -0.8940981030 -0.0263780300 -0.5572685599 873 34.8800000000 0.0205009766 0.0082434435 0.0343288071 0.0084794467 0.1713410000 253495974 0 1786855424 -0.8858654499 -0.0190595724 -0.5650818944 874 34.9200000000 0.0217819754 0.0082589338 0.0343288071 0.0084753579 0.1576230000 253497004 0 1782566912 -0.8838002682 -0.0202455539 -0.5712490082 875 34.9600000000 0.0191846471 0.0082714203 0.0343288071 0.0084796289 0.1585640000 253497742 0 1781821440 -0.8801742196 -0.0173016898 -0.5815216303 876 35.0000000000 0.0220181346 0.0082871129 0.0343288071 0.0084767244 0.1576480000 253498412 0 1783046144 -0.8739404082 -0.0157265980 -0.5879794955 877 35.0400000000 0.0174088310 0.0082975140 0.0343288071 0.0084758413 0.1523570000 253499442 0 1784979456 -0.8671715260 -0.0226015784 -0.5941435695 878 35.0800000000 0.0208805576 0.0083118455 0.0343288071 0.0084743386 0.1581760000 253502252 0 1786757120 -0.8623200655 -0.0238525067 -0.5970408916 879 35.1200000000 0.0220279768 0.0083274497 0.0343288071 0.0084921326 0.1846390000 253501878 0 1782820864 -0.8587241769 -0.0181329325 -0.6086061001 880 35.1600000000 0.0210040640 0.0083418549 0.0343288071 0.0084898214 0.1507200000 253500856 0 1781948416 -0.8506994843 -0.0229622554 -0.6132390499 881 35.2000000000 0.0230263881 0.0083585230 0.0343288071 0.0084876527 0.1472210000 253501770 0 1783840768 -0.8440945745 -0.0249254480 -0.6163958311 882 35.2400000000 0.0153131932 0.0083664081 0.0343288071 0.0084933863 0.1458680000 253504412 0 1785217024 -0.8420222998 -0.0282492153 -0.6302344799 883 35.2800000000 0.0150131797 0.0083739356 0.0343288071 0.0084889082 0.1501630000 253505366 0 1784115200 -0.8383941054 -0.0314647853 -0.6393728852 884 35.3200000000 0.0197911691 0.0083868510 0.0343288071 0.0084871127 0.1446460000 253506288 0 1782964224 -0.8266986012 -0.0331029482 -0.6401703358 885 35.3600000000 0.0204385389 0.0084004687 0.0343288071 0.0084892861 0.1452780000 253506846 0 1782185984 -0.8211955428 -0.0351360179 -0.6448929906 886 35.4000000000 0.0176064912 0.0084108593 0.0343288071 0.0084923164 0.1402520000 253506704 0 1783988224 -0.8212609887 -0.0467173234 -0.6513485312 887 35.4400000000 0.0163311474 0.0084197886 0.0343288071 0.0084935410 0.1454210000 253505366 0 1785327616 -0.8185842633 -0.0507369377 -0.6620588303 888 35.4800000000 0.0125239044 0.0084244103 0.0343288071 0.0084917084 0.1451200000 253510552 0 1784115200 -0.8147129416 -0.0556842349 -0.6730915308 889 35.5200000000 0.0099524241 0.0084261291 0.0343288071 0.0084947039 0.1374540000 253510454 0 1782947840 -0.8159443736 -0.0599270314 -0.6789471507 890 35.5600000000 0.0195247661 0.0084385995 0.0343288071 0.0085381563 0.1391740000 253513496 0 1781055488 -0.8027330041 -0.0521325320 -0.6859400868 891 35.6000000000 0.0223668925 0.0084542317 0.0343288071 0.0085396745 0.1364770000 253512210 0 1780428800 -0.7965816855 -0.0551228374 -0.6915544868 892 35.6400000000 0.0216656253 0.0084690427 0.0343288071 0.0085405446 0.1362480000 253514344 0 1779023872 -0.7944621444 -0.0512969866 -0.7020207644 893 35.6800000000 0.0256781969 0.0084883138 0.0343288071 0.0085388269 0.1366310000 253518082 0 1778229248 -0.7866663933 -0.0510287471 -0.7047575712 894 35.7200000000 0.0222223494 0.0085036763 0.0343288071 0.0085355386 0.1354770000 253517664 0 1777250304 -0.7741231322 -0.0582778268 -0.7154690027 895 35.7600000000 0.0233302023 0.0085202423 0.0343288071 0.0085831558 0.1755190000 253942042 0 1774202880 -0.7749419808 -0.0453501493 -0.7273885608 896 35.8000000000 0.0262523722 0.0085400326 0.0343288071 0.0085806694 0.3394910000 254800163 0 1773199360 -0.7692901492 -0.0421095677 -0.7327666879 897 35.8400000000 0.0189387202 0.0085516253 0.0343288071 0.0086519678 0.2219000000 254680384 0 1775058944 -0.7721533179 -0.0582507625 -0.7428469062 898 35.8800000000 0.0179616753 0.0085621042 0.0343288071 0.0086672063 0.1604660000 253904060 0 1775710208 -0.7664265633 -0.0591090210 -0.7511601448 899 35.9200000000 0.0167794358 0.0085712447 0.0343288071 0.0086700708 0.1639240000 253907614 0 1777086464 -0.7577024102 -0.0603909791 -0.7592192292 900 35.9600000000 0.0177872553 0.0085814847 0.0343288071 0.0086762295 0.1564680000 253908528 0 1779109888 -0.7489957213 -0.0649597943 -0.7609349489 901 36.0000000000 0.0158254746 0.0085895247 0.0343288071 0.0086872549 0.1629490000 253909734 0 1780494336 -0.7487234473 -0.0727548748 -0.7684388161 902 36.0400000000 0.0213138014 0.0086036314 0.0343288071 0.0086976786 0.1666320000 253912436 0 1782538240 -0.7387769818 -0.0693266466 -0.7752655745 903 36.0800000000 0.0170781817 0.0086130163 0.0343288071 0.0087054828 0.1554240000 253911250 0 1784061952 -0.7321783900 -0.0740307570 -0.7865857482 904 36.1200000000 0.0153185148 0.0086204339 0.0343288071 0.0087071802 0.1508480000 253913868 0 1786093568 -0.7209759951 -0.0743367076 -0.7849820256 905 36.1600000000 0.0195133444 0.0086324703 0.0343288071 0.0087405911 0.1515210000 253916110 0 1784578048 -0.6937750578 -0.0749235749 -0.8075019121 906 36.2000000000 0.0209107026 0.0086460224 0.0343288071 0.0087480789 0.1484170000 253914940 0 1786748928 -0.6902419925 -0.0732387900 -0.8143258095 907 36.2400000000 0.0196689591 0.0086581756 0.0343288071 0.0087526986 0.1463810000 253916806 0 1782935552 -0.6861793399 -0.0864094198 -0.8212589622 908 36.2800000000 0.0219851490 0.0086728529 0.0343288071 0.0087605108 0.1441200000 253916264 0 1781379072 -0.6815017462 -0.0809777901 -0.8246753216 909 36.3200000000 0.0220164806 0.0086875323 0.0343288071 0.0087595045 0.1679050000 253916818 0 1782300672 -0.6684032679 -0.0794792622 -0.8286293149 910 36.3600000000 0.0214287434 0.0087015337 0.0343288071 0.0087801736 0.1413310000 253920708 0 1784463360 -0.6622536182 -0.0900189430 -0.8342626691 911 36.4000000000 0.0183141902 0.0087120854 0.0343288071 0.0087901262 0.1463490000 253921378 0 1786347520 -0.6546204090 -0.0846411288 -0.8362424374 912 36.4400000000 0.0170887411 0.0087212703 0.0343288071 0.0087944123 0.1495370000 253922852 0 1785335808 -0.6503719091 -0.0808368102 -0.8436994553 913 36.4800000000 0.0152417775 0.0087284122 0.0343288071 0.0087942718 0.1451990000 253922686 0 1784098816 -0.6430592537 -0.0852046162 -0.8509160280 914 36.5200000000 0.0140482709 0.0087342326 0.0343288071 0.0087971112 0.1458690000 253927044 0 1782448128 -0.6389485002 -0.0899897367 -0.8573179245 915 36.5600000000 0.0211479403 0.0087477995 0.0343288071 0.0087929203 0.1446170000 253928910 0 1779879936 -0.6289585233 -0.0949762017 -0.8533323407 916 36.6000000000 0.0175975300 0.0087574608 0.0343288071 0.0087995831 0.1442590000 253928760 0 1781395456 -0.6198425889 -0.0892686248 -0.8604996204 917 36.6400000000 0.0173990838 0.0087668846 0.0343288071 0.0088083195 0.1378570000 253929390 0 1783554048 -0.6177637577 -0.0964638442 -0.8672087789 918 36.6800000000 0.0197731107 0.0087788739 0.0343288071 0.0088065734 0.1439440000 253931548 0 1785585664 -0.6086870432 -0.1029293686 -0.8683234453 919 36.7200000000 0.0183516983 0.0087892905 0.0343288071 0.0088115239 0.1405370000 253932978 0 1786601472 -0.6060048938 -0.0984477326 -0.8744801879 920 36.7600000000 0.0107124504 0.0087913809 0.0343288071 0.0088128380 0.1456420000 253934476 0 1783336960 -0.5938119888 -0.0937580541 -0.8852287531 921 36.8000000000 0.0147772785 0.0087978802 0.0343288071 0.0088100325 0.1432320000 253939142 0 1782173696 -0.5825682282 -0.0907719582 -0.8819497228 922 36.8400000000 0.0188233200 0.0088087538 0.0343288071 0.0088720982 0.1433890000 253939636 0 1784082432 -0.5809515715 -0.1034477130 -0.8914783001 923 36.8800000000 0.0195644312 0.0088204068 0.0343288071 0.0088881499 0.1434110000 253942330 0 1785856000 -0.5668665767 -0.1020526513 -0.8823511004 924 36.9200000000 0.0162085444 0.0088284026 0.0343288071 0.0088917740 0.1397770000 253942632 0 1784598528 -0.5553445220 -0.0957275331 -0.8918517232 925 36.9600000000 0.0186400060 0.0088390097 0.0343288071 0.0088989072 0.1422070000 253943178 0 1786638336 -0.5464058518 -0.0972455367 -0.8954158425 926 37.0000000000 0.0161248725 0.0088468778 0.0343288071 0.0089181199 0.1430530000 253949240 0 1783418880 -0.5313556194 -0.0936761349 -0.9054644704 927 37.0400000000 0.0202895701 0.0088592216 0.0343288071 0.0089173545 0.1443410000 253950654 0 1781764096 -0.5184935331 -0.0964736044 -0.9049217105 928 37.0800000000 0.0180394612 0.0088691141 0.0343288071 0.0089139879 0.1415860000 253953856 0 1783422976 -0.5073742867 -0.0975101292 -0.9076686502 929 37.1200000000 0.0152230645 0.0088759537 0.0343288071 0.0089121392 0.1450770000 253956522 0 1785712640 -0.4986782372 -0.1017054766 -0.9147870541 930 37.1600000000 0.0128356731 0.0088802114 0.0343288071 0.0089130961 0.1398940000 253956732 0 1784213504 -0.4872471690 -0.0996027738 -0.9192743301 931 37.2000000000 0.0167069882 0.0088886183 0.0343288071 0.0089117650 0.1466430000 253959878 0 1783672832 -0.4812110364 -0.1066531613 -0.9223173261 932 37.2400000000 0.0119438712 0.0088918965 0.0343288071 0.0089235871 0.1462920000 253961468 0 1782419456 -0.4687249362 -0.0956301466 -0.9241752625 933 37.2800000000 0.0116794333 0.0088948842 0.0343288071 0.0089392431 0.1748940000 254356418 0 1784713216 -0.4610753953 -0.0989897549 -0.9322621822 934 37.3200000000 0.0104274638 0.0088965251 0.0343288071 0.0089417040 0.3313470000 254614639 0 1787318272 -0.4517693818 -0.0970358178 -0.9397841692 935 37.3600000000 0.0126180779 0.0089005053 0.0343288071 0.0089430866 0.1934750000 255244533 0 1784250368 -0.4412737489 -0.0978436321 -0.9393024445 936 37.4000000000 0.0147444000 0.0089067488 0.0343288071 0.0089423441 0.1945390000 255014544 0 1783205888 -0.4245744348 -0.1068403795 -0.9383237362 937 37.4400000000 0.0150154643 0.0089132682 0.0343288071 0.0089406411 0.1532170000 254339966 0 1782259712 -0.4126371443 -0.1096617654 -0.9403047562 938 37.4800000000 0.0174804889 0.0089224017 0.0343288071 0.0089369147 0.1572010000 254341312 0 1781743616 -0.4060000181 -0.1143071949 -0.9414899945 939 37.5200000000 0.0148803964 0.0089287468 0.0343288071 0.0089410206 0.1912030000 254341806 0 1783037952 -0.3914831281 -0.1105050370 -0.9491910338 940 37.5600000000 0.0124099413 0.0089324502 0.0343288071 0.0089393828 0.1551110000 254342000 0 1784950784 -0.3785311580 -0.1063073948 -0.9518508315 941 37.6000000000 0.0142671289 0.0089381193 0.0343288071 0.0089373051 0.1532480000 254344458 0 1786728448 -0.3723746538 -0.1101736724 -0.9518435597 942 37.6400000000 0.0142308325 0.0089437379 0.0343288071 0.0089356007 0.1527060000 254345772 0 1784176640 -0.3649648428 -0.1136095747 -0.9572792649 943 37.6800000000 0.0142337447 0.0089493477 0.0343288071 0.0089347110 0.1520410000 254347738 0 1783013376 -0.3542261720 -0.1139423922 -0.9569798112 944 37.7200000000 0.0146321850 0.0089553676 0.0343288071 0.0089301538 0.1554100000 254350164 0 1785704448 -0.3438800871 -0.1159994975 -0.9555747509 945 37.7600000000 0.0127481380 0.0089593812 0.0343288071 0.0089296618 0.1570980000 254353142 0 1785827328 -0.3338240981 -0.1154369861 -0.9562941790 946 37.8000000000 0.0136216385 0.0089643095 0.0343288071 0.0089301108 0.1539810000 254353136 0 1783943168 -0.3239759207 -0.1182287186 -0.9560347199 947 37.8400000000 0.0126352580 0.0089681859 0.0343288071 0.0089312358 0.1532890000 254357110 0 1783287808 -0.3155736923 -0.1191823483 -0.9610931277 948 37.8800000000 0.0131208766 0.0089725664 0.0343288071 0.0089311652 0.1499990000 254360188 0 1784426496 -0.3044934273 -0.1222071871 -0.9632191062 949 37.9200000000 0.0127211623 0.0089765165 0.0343288071 0.0089320717 0.1455370000 254358234 0 1786474496 -0.2977244556 -0.1210559905 -0.9627138972 950 37.9600000000 0.0126141440 0.0089803456 0.0343288071 0.0089286388 0.1482510000 254360016 0 1782759424 -0.2862662673 -0.1217104867 -0.9646911621 951 38.0000000000 0.0090077063 0.0089803743 0.0343288071 0.0089358397 0.1766150000 254739970 0 1782034432 -0.2757710814 -0.1205263212 -0.9670976996 952 38.0400000000 0.0102654118 0.0089817242 0.0343288071 0.0089326444 0.3548110000 255002475 0 1783828480 -0.2660584450 -0.1239731535 -0.9679952860 953 38.0800000000 0.0096705677 0.0089824470 0.0343288071 0.0089356330 0.1884810000 255647633 0 1784459264 -0.2579189241 -0.1234907433 -0.9693979025 954 38.1200000000 0.0043642595 0.0089776061 0.0343288071 0.0089688969 0.2114560000 255408076 0 1783889920 -0.2394663692 -0.1164269224 -0.9728233218 955 38.1600000000 0.0059624822 0.0089744489 0.0343288071 0.0089728485 0.1485270000 254744358 0 1783619584 -0.2281354368 -0.1152418256 -0.9769300222 956 38.2000000000 0.0060731973 0.0089714141 0.0343288071 0.0089692451 0.1523460000 254744284 0 1786015744 -0.2172665745 -0.1173729897 -0.9782824516 957 38.2400000000 0.0069445563 0.0089692962 0.0343288071 0.0089677393 0.1461710000 254745958 0 1784360960 -0.2078568488 -0.1210441291 -0.9804968834 958 38.2800000000 0.0051220083 0.0089652802 0.0343288071 0.0089657504 0.1709880000 255080424 0 1783906304 -0.2002913952 -0.1210655347 -0.9838225245 959 38.3200000000 0.0049573202 0.0089611009 0.0343288071 0.0089638040 0.3172270000 255099494 0 1785810944 -0.1891732067 -0.1183192208 -0.9865510464 960 38.3600000000 0.0055365069 0.0089575336 0.0343288071 0.0089631394 0.2398800000 256051247 0 1784705024 -0.1757620871 -0.1155189648 -0.9885699749 961 38.4000000000 0.0033275543 0.0089516752 0.0343288071 0.0089740805 0.1619280000 255918530 0 1786060800 -0.1674636155 -0.1186549962 -0.9883493185 962 38.4400000000 0.0054410361 0.0089480259 0.0343288071 0.0089744480 0.1366580000 255060132 0 1783300096 -0.1566994935 -0.1174639687 -0.9921404123 963 38.4800000000 0.0045920354 0.0089435025 0.0343288071 0.0089806449 0.1584350000 255343362 0 1784922112 -0.1446738541 -0.1227681562 -0.9932295680 964 38.5200000000 0.0032491903 0.0089375955 0.0343288071 0.0089824679 0.2843340000 255387224 0 1785552896 -0.1356802285 -0.1248246431 -0.9926621914 965 38.5600000000 0.0028427572 0.0089312797 0.0343288071 0.0089818334 0.2040280000 256300713 0 1784217600 -0.1264436245 -0.1263984144 -0.9929612875 966 38.6000000000 0.0045295227 0.0089267230 0.0343288071 0.0089821194 0.1865950000 256235098 0 1785507840 -0.1176593676 -0.1260624528 -0.9932417274 967 38.6400000000 0.0067830104 0.0089245061 0.0343288071 0.0089890105 0.2155340000 255629162 0 1786114048 -0.1032290161 -0.1306201816 -1.0024076700 968 38.6800000000 0.0080951806 0.0089236494 0.0343288071 0.0089938118 0.1741240000 256655667 0 1784311808 -0.0965544507 -0.1248450801 -0.9968569279 969 38.7200000000 0.0074028033 0.0089220799 0.0343288071 0.0089953984 0.2381590000 256532100 0 1781919744 -0.0829496235 -0.1357398331 -1.0051766634 970 38.7600000000 0.0034222687 0.0089164099 0.0343288071 0.0089942574 0.2743520000 256012635 0 1784066048 -0.0786586702 -0.1349378526 -1.0015805960 971 38.8000000000 0.0102598649 0.0089177935 0.0343288071 0.0089948492 0.2175340000 256826684 0 1784836096 -0.0695707127 -0.1265118122 -1.0007840395 972 38.8400000000 0.0064822063 0.0089152878 0.0343288071 0.0090012320 0.1952930000 256722734 0 1782956032 -0.0544190854 -0.1380557865 -1.0108973980 973 38.8800000000 0.0103876982 0.0089168010 0.0343288071 0.0090237306 0.1563040000 255748982 0 1782411264 -0.0504712127 -0.1297349632 -1.0010929108 974 38.9200000000 0.0154079320 0.0089234655 0.0343288071 0.0090582928 0.1344730000 255755380 0 1784561664 -0.0371089540 -0.1498372108 -1.0159932375 975 38.9600000000 0.0084997946 0.0089230309 0.0343288071 0.0090607603 0.1263420000 255755846 0 1786556416 -0.0276337601 -0.1394581199 -1.0160169601 976 39.0000000000 0.0046729264 0.0089186763 0.0343288071 0.0090628254 0.1227480000 255755880 0 1782489088 -0.0216742009 -0.1447956711 -1.0092960596 977 39.0400000000 0.0054232622 0.0089150986 0.0343288071 0.0090625550 0.1197240000 255755350 0 1782128640 -0.0110921673 -0.1399090439 -1.0041626692 978 39.0800000000 0.0079821590 0.0089141447 0.0343288071 0.0090607243 0.1184780000 255758144 0 1780744192 -0.0056274189 -0.1404297501 -1.0001022816 979 39.1200000000 0.0071198996 0.0089123119 0.0343288071 0.0090740482 0.1217670000 255759834 0 1779617792 0.0075703729 -0.1421843469 -1.0163905621 980 39.1600000000 0.0098890066 0.0089133086 0.0343288071 0.0090795753 0.1196730000 255760964 0 1778987008 0.0191280115 -0.1398341358 -1.0199989080 981 39.2000000000 0.0177415647 0.0089223078 0.0343288071 0.0090954565 0.1255440000 255762850 0 1778167808 0.0253316686 -0.1599680334 -1.0086023808 982 39.2400000000 0.0152005600 0.0089287011 0.0343288071 0.0090947046 0.1174990000 255760120 0 1775534080 0.0317673981 -0.1564460844 -1.0019038916 983 39.2800000000 0.0154030081 0.0089352874 0.0343288071 0.0091016277 0.1182470000 255763554 0 1775513600 0.0439129621 -0.1604387760 -1.0122089386 984 39.3200000000 0.0121627040 0.0089385673 0.0343288071 0.0091120410 0.1219180000 255766244 0 1775411200 0.0500909947 -0.1472257376 -0.9998432994 985 39.3600000000 0.0138941100 0.0089435983 0.0343288071 0.0091086635 0.1200060000 255772118 0 1774632960 0.0603313260 -0.1497834772 -0.9972690344 986 39.4000000000 0.0024575009 0.0089370201 0.0343288071 0.0091144073 0.1208640000 255777216 0 1776414720 0.0731824562 -0.1506114453 -1.0059937239 987 39.4400000000 0.0123428674 0.0089404708 0.0343288071 0.0091121732 0.1205860000 255776050 0 1778446336 0.0779964775 -0.1600218862 -0.9999604821 988 39.4800000000 0.0151260560 0.0089467316 0.0343288071 0.0091103420 0.1349300000 255781968 0 1779826688 0.0910194293 -0.1656150818 -1.0032782555 989 39.5200000000 0.0087046381 0.0089464868 0.0343288071 0.0091131090 0.1199520000 255779434 0 1781604352 0.1027994081 -0.1581267267 -1.0104136467 990 39.5600000000 0.0130585916 0.0089506404 0.0343288071 0.0091098424 0.1259050000 255782156 0 1783382016 0.1096948534 -0.1641360670 -1.0038710833 991 39.6000000000 0.0051639415 0.0089468193 0.0343288071 0.0091129652 0.1212600000 255780098 0 1785159680 0.1249633878 -0.1514678001 -1.0023645163 992 39.6400000000 0.0209553186 0.0089589247 0.0343288071 0.0091382803 0.1225250000 255779872 0 1786556416 0.1240411848 -0.1646131873 -0.9901527166 993 39.6800000000 0.0009760338 0.0089508855 0.0343288071 0.0091408920 0.1245420000 255787546 0 1783533568 0.1397720128 -0.1448703855 -0.9935072064 994 39.7200000000 0.0130906180 0.0089550502 0.0343288071 0.0091543763 0.2027120000 255786208 0 1785286656 0.1439241320 -0.1542989165 -0.9860737324 995 39.7600000000 0.0071741990 0.0089532604 0.0343288071 0.0091544521 0.2261680000 255967344 0 1784430592 0.1579727679 -0.1479424685 -0.9965512156 996 39.8000000000 0.0093743615 0.0089536832 0.0343288071 0.0091540690 0.2326370000 257261775 0 1781776384 0.1685930938 -0.1547531337 -0.9905008078 997 39.8400000000 0.0171916876 0.0089619460 0.0343288071 0.0091545738 0.2218450000 256028082 0 1778053120 0.1834792495 -0.1499759555 -1.0006345510 998 39.8800000000 0.0130619174 0.0089660542 0.0343288071 0.0091560051 0.1664560000 256032276 0 1779404800 0.1895638704 -0.1403457224 -0.9944493771 999 39.9200000000 0.0231848117 0.0089802872 0.0343288071 0.0091663439 0.1295540000 256030962 0 1781485568 0.2041210085 -0.1506642848 -1.0008907318 1000 39.9600000000 0.0237810127 0.0089950879 0.0343288071 0.0091639647 0.1334740000 256028816 0 1783115776 0.2160708606 -0.1491892934 -1.0007333755 1001 40.0000000000 0.0099002821 0.0089959922 0.0343288071 0.0091690455 0.1305430000 256032326 0 1784893440 0.2188036442 -0.1409476101 -0.9872323275 1002 40.0400000000 0.0216586944 0.0090086296 0.0343288071 0.0091718743 0.1287410000 256031708 0 1786290176 0.2351725549 -0.1486626863 -0.9945670366 1003 40.0800000000 0.0247123819 0.0090242864 0.0343288071 0.0091683240 0.1300020000 256034254 0 1784373248 0.2492368817 -0.1463988572 -0.9943134785 1004 40.1200000000 0.0060155219 0.0090212896 0.0343288071 0.0091922122 0.1311190000 256038740 0 1783386112 0.2444555759 -0.1374397427 -0.9726161361 1005 40.1600000000 0.0135901188 0.0090258357 0.0343288071 0.0091956200 0.1278610000 256036310 0 1782370304 0.2598021328 -0.1486556679 -0.9795803428 1006 40.2000000000 0.0055171605 0.0090223480 0.0343288071 0.0091946180 0.1314300000 256041552 0 1784025088 0.2658808529 -0.1439612508 -0.9664908648 1007 40.2400000000 0.0206858516 0.0090339304 0.0343288071 0.0092021719 0.1279800000 256039426 0 1785765888 0.2811761796 -0.1485678107 -0.9773820043 1008 40.2800000000 0.0114014037 0.0090362791 0.0343288071 0.0092124912 0.1543920000 256243970 0 1784909824 0.2812734246 -0.1310382783 -0.9651248455 1009 40.3200000000 0.0191239752 0.0090462768 0.0343288071 0.0092198233 0.2686610000 256302850 0 1784311808 0.2956297398 -0.1444559842 -0.9711350203 1010 40.3600000000 0.0087231910 0.0090459569 0.0343288071 0.0092310260 0.2493710000 257730079 0 1784545280 0.2999909818 -0.1299557388 -0.9537178874 1011 40.4000000000 0.0191961844 0.0090559967 0.0343288071 0.0092407109 0.2619440000 257643036 0 1781731328 0.3132202625 -0.1368958652 -0.9671217203 1012 40.4400000000 0.0065691709 0.0090535394 0.0343288071 0.0092399155 0.2486480000 256512016 0 1783214080 0.3164784312 -0.1412505060 -0.9524130225 1013 40.4800000000 0.0099586947 0.0090544329 0.0343288071 0.0092398110 0.2496370000 258083849 0 1785286656 0.3223465085 -0.1327489018 -0.9474009871 1014 40.5200000000 0.0091893049 0.0090545659 0.0343288071 0.0092364779 0.2808210000 257996174 0 1784156160 0.3288672268 -0.1387250870 -0.9451974630 1015 40.5600000000 0.0190687012 0.0090644321 0.0343288071 0.0092414699 0.2586930000 256713482 0 1783549952 0.3425336778 -0.1473965496 -0.9549992085 1016 40.6000000000 0.0106406854 0.0090659835 0.0343288071 0.0092403030 0.2663260000 257790923 0 1784791040 0.3471990824 -0.1449426115 -0.9458329678 1017 40.6400000000 0.0107826022 0.0090676714 0.0343288071 0.0092435138 0.2020910000 258147135 0 1784217600 0.3567406237 -0.1364569068 -0.9411298037 1018 40.6800000000 0.0432312042 0.0091012309 0.0432312042 0.0092901819 0.2561460000 258070950 0 1781841920 0.3758248687 -0.1505854726 -0.9695999622 1019 40.7200000000 0.0440197848 0.0091354983 0.0440197848 0.0092889499 0.1428700000 256718322 0 1782325248 0.3869157732 -0.1421028972 -0.9656437635 1020 40.7600000000 0.0404117294 0.0091661613 0.0440197848 0.0092850027 0.1339490000 256720748 0 1783848960 0.3929400444 -0.1439770460 -0.9582331777 1021 40.8000000000 0.0421582349 0.0091984748 0.0440197848 0.0092814286 0.1349740000 256725638 0 1785606144 0.4039021134 -0.1410763711 -0.9545376897 1022 40.8400000000 0.0425666571 0.0092311247 0.0440197848 0.0092773679 0.1455180000 256729304 0 1784377344 0.4111298621 -0.1406238824 -0.9486495256 1023 40.8800000000 0.0429719053 0.0092641069 0.0440197848 0.0092751625 0.1446080000 256731770 0 1783697408 0.4147167206 -0.1421288848 -0.9448499680 1024 40.9200000000 0.0393138006 0.0092934523 0.0440197848 0.0092714987 0.1430160000 256736468 0 1782321152 0.4246676862 -0.1407406032 -0.9361766577 1025 40.9600000000 0.0445058309 0.0093278058 0.0445058309 0.0092694133 0.1689490000 256962698 0 1784000512 0.4373391569 -0.1429055929 -0.9344333410 1026 41.0000000000 0.0417556614 0.0093594119 0.0445058309 0.0092694032 0.3118560000 257159932 0 1786114048 0.4436611235 -0.1334980875 -0.9257616401 1027 41.0400000000 0.0472565107 0.0093963127 0.0472565107 0.0092687147 0.2664250000 257162866 0 1785679872 0.4529913366 -0.1321098208 -0.9290705919 1028 41.0800000000 0.0452111512 0.0094311520 0.0472565107 0.0092644412 0.2124320000 258833209 0 1784573952 0.4645193219 -0.1317125559 -0.9194173813 1029 41.1200000000 0.0402567163 0.0094611089 0.0472565107 0.0092642351 0.1965910000 258903454 0 1782059008 0.4687308967 -0.1335299164 -0.9134258628 1030 41.1600000000 0.0466580205 0.0094972224 0.0472565107 0.0092645442 0.2288580000 258712154 0 1779290112 0.4804020226 -0.1359089166 -0.9157319069 1031 41.2000000000 0.0516878553 0.0095381444 0.0516878553 0.0092806147 0.1555800000 257172998 0 1779396608 0.4871747792 -0.1442793608 -0.9165367484 1032 41.2400000000 0.0527429581 0.0095800095 0.0527429581 0.0092799912 0.1471000000 257177236 0 1781432320 0.4975877106 -0.1367752701 -0.9123973250 1033 41.2800000000 0.0533275940 0.0096223596 0.0533275940 0.0092789480 0.1448840000 257174418 0 1782951936 0.5090580583 -0.1367284805 -0.9067037702 1034 41.3200000000 0.0526769646 0.0096639985 0.0533275940 0.0092833356 0.1488050000 257177268 0 1784713216 0.5196169615 -0.1365821511 -0.9003149867 1035 41.3600000000 0.0580932088 0.0097107900 0.0580932088 0.0092925475 0.1608290000 257184718 0 1786109952 0.5276309252 -0.1397706866 -0.9013853669 1036 41.4000000000 0.0637890548 0.0097629891 0.0637890548 0.0092958416 0.1482720000 257185276 0 1785241600 0.5351338387 -0.1469746232 -0.9034643769 1037 41.4400000000 0.0691444650 0.0098202518 0.0691444650 0.0092958471 0.1524820000 257183550 0 1784356864 0.5515104532 -0.1429609656 -0.9033836126 1038 41.4800000000 0.0626758561 0.0098711724 0.0691444650 0.0092924806 0.1458670000 257186508 0 1782693888 0.5552204251 -0.1398248971 -0.8929753304 1039 41.5200000000 0.0537383482 0.0099133930 0.0691444650 0.0092907755 0.1451340000 257185562 0 1781952512 0.5572605729 -0.1390067488 -0.8816742897 1040 41.5600000000 0.0645309910 0.0099659099 0.0691444650 0.0092892324 0.1764360000 257467148 0 1783681024 0.5727822185 -0.1391737312 -0.8851701617 1041 41.6000000000 0.0652717873 0.0100190376 0.0691444650 0.0092867639 0.3346960000 257481666 0 1782968320 0.5813813806 -0.1362108588 -0.8844565749 1042 41.6400000000 0.0639609024 0.0100708052 0.0691444650 0.0092878750 0.3058120000 257554196 0 1784782848 0.5902783871 -0.1367623061 -0.8773603439 1043 41.6800000000 0.0655737966 0.0101240200 0.0691444650 0.0092951483 0.2255070000 259407659 0 1783402496 0.5981822610 -0.1338846684 -0.8733562231 1044 41.7200000000 0.0628849268 0.0101745572 0.0691444650 0.0093452797 0.2289480000 259351468 0 1782304768 0.6087653637 -0.1317560226 -0.8670470715 1045 41.7600000000 0.0558407605 0.0102182569 0.0691444650 0.0093629306 0.2630430000 259243048 0 1779838976 0.6129325032 -0.1354190558 -0.8564960957 1046 41.8000000000 0.0599174984 0.0102657706 0.0691444650 0.0093628680 0.1699080000 257484784 0 1780117504 0.6225584745 -0.1321650296 -0.8526030183 1047 41.8400000000 0.0611207411 0.0103143426 0.0691444650 0.0093605201 0.1707310000 257487566 0 1782370304 0.6300687790 -0.1325452626 -0.8509764671 1048 41.8800000000 0.0600373782 0.0103617883 0.0691444650 0.0093634323 0.1707290000 257491956 0 1784016896 0.6346020699 -0.1371141374 -0.8443478346 1049 41.9200000000 0.0611703657 0.0104102235 0.0691444650 0.0093600126 0.1605820000 257494290 0 1785667584 0.6451663375 -0.1337802112 -0.8401368856 1050 41.9600000000 0.0575647354 0.0104551326 0.0691444650 0.0093580312 0.1589790000 257492568 0 1784053760 0.6465294361 -0.1305550337 -0.8356009722 1051 42.0000000000 0.0578702167 0.0105002469 0.0691444650 0.0093560536 0.1925150000 257827798 0 1783246848 0.6525051594 -0.1321746409 -0.8331545591 1052 42.0400000000 0.0654426739 0.0105524735 0.0691444650 0.0093538570 0.3677950000 257826988 0 1781989376 0.6660308838 -0.1255736798 -0.8327202201 1053 42.0800000000 0.0579420999 0.0105974779 0.0691444650 0.0093572823 0.3117690000 257827966 0 1783971840 0.6659337282 -0.1358239204 -0.8225610852 1054 42.1200000000 0.0637368858 0.0106478948 0.0691444650 0.0093572662 0.3150940000 258680931 0 1786617856 0.6739917397 -0.1394551098 -0.8224516511 1055 42.1600000000 0.0593054332 0.0106940157 0.0691444650 0.0093567530 0.2505850000 259698176 0 1783668736 0.6838935614 -0.1312669516 -0.8118517399 1056 42.2000000000 0.0585811660 0.0107393634 0.0691444650 0.0093534316 0.1804300000 259667903 0 1785397248 0.6879537702 -0.1286219358 -0.8072977066 1057 42.2400000000 0.0741711110 0.0107993745 0.0741711110 0.0093570092 0.2571720000 259588456 0 1785532416 0.7070332766 -0.1249017417 -0.8130066991 1058 42.2800000000 0.0705168024 0.0108558182 0.0741711110 0.0093564445 0.2175220000 258166052 0 1786306560 0.7084983587 -0.1239891648 -0.8035573959 1059 42.3200000000 0.0692972168 0.0109110036 0.0741711110 0.0093539564 0.3588790000 258155870 0 1784201216 0.7132621408 -0.1234078109 -0.7971757054 1060 42.3600000000 0.0662107095 0.0109631731 0.0741711110 0.0093557793 0.3006740000 258234536 0 1785868288 0.7142841816 -0.1249917448 -0.7894915938 1061 42.4000000000 0.0689303279 0.0110178076 0.0741711110 0.0093531479 0.2821850000 259807101 0 1783738368 0.7198474407 -0.1245040521 -0.7869151235 1062 42.4400000000 0.0737830549 0.0110769086 0.0741711110 0.0093538036 0.2420550000 260165564 0 1783914496 0.7260237336 -0.1259860396 -0.7848209739 1063 42.4800000000 0.0684833899 0.0111309128 0.0741711110 0.0093552466 0.1726500000 260170969 0 1785233408 0.7288709879 -0.1204743311 -0.7743568420 1064 42.5200000000 0.0616839379 0.0111784250 0.0741711110 0.0093575159 0.2925690000 260090598 0 1781829632 0.7330892086 -0.1204738244 -0.7615824342 1065 42.5600000000 0.0581168011 0.0112224986 0.0741711110 0.0093574682 0.3513350000 258489534 0 1783312384 0.7342230678 -0.1202902570 -0.7537904382 1066 42.6000000000 0.0591366738 0.0112674463 0.0741711110 0.0093573629 0.3092450000 258570688 0 1785667584 0.7365553975 -0.1225514859 -0.7490102649 1067 42.6400000000 0.0604519770 0.0113135424 0.0741711110 0.0093550602 0.3168040000 260623705 0 1784082432 0.7432926893 -0.1198853254 -0.7446756959 1068 42.6800000000 0.0603882819 0.0113594925 0.0741711110 0.0093514500 0.2672500000 260648194 0 1783857152 0.7477036715 -0.1156784371 -0.7384070158 1069 42.7200000000 0.0600751825 0.0114050638 0.0741711110 0.0093540889 0.1753190000 260642041 0 1785532416 0.7520717382 -0.1141594425 -0.7321470380 1070 42.7600000000 0.0563564636 0.0114470744 0.0741711110 0.0093601211 0.2898520000 260561058 0 1782595584 0.7599393129 -0.0967032537 -0.7195243835 1071 42.8000000000 0.0516359620 0.0114845991 0.0741711110 0.0093772032 0.1762070000 258902120 0 1783046144 0.7574998140 -0.0991242453 -0.7092882991 1072 42.8400000000 0.0533072576 0.0115236127 0.0741711110 0.0093730965 0.3429350000 258910188 0 1786339328 0.7636397481 -0.0928432271 -0.7037393451 1073 42.8800000000 0.0522669330 0.0115615841 0.0741711110 0.0093732627 0.3486690000 259001746 0 1783988224 0.7651560903 -0.0977845192 -0.6956496239 1074 42.9200000000 0.0531469099 0.0116003042 0.0741711110 0.0093706986 0.2631410000 261193099 0 1783316480 0.7720059156 -0.0962495953 -0.6892569661 1075 42.9600000000 0.0532161519 0.0116390166 0.0741711110 0.0093675825 0.2095280000 261067037 0 1783283712 0.7749866247 -0.0925150663 -0.6811889410 1076 43.0000000000 0.0459400639 0.0116708949 0.0741711110 0.0093739570 0.3300670000 261025814 0 1780178944 0.7749006152 -0.0946940854 -0.6689395905 1077 43.0400000000 0.0021188662 0.0116620258 0.0741711110 0.0096314255 0.3817930000 259046970 0 1780469760 0.7696008086 -0.0868517533 -0.6199591756 1078 43.0800000000 0.0025176096 0.0116535430 0.0741711110 0.0096299310 0.2367300000 259047448 0 1782403072 0.7730679512 -0.0844579116 -0.6143891215 1079 43.1200000000 0.0065395078 0.0116488034 0.0741711110 0.0096266180 0.2215590000 259044222 0 1784066048 0.7799907923 -0.0802573338 -0.6103194952 1080 43.1600000000 0.0028273244 0.0116406354 0.0741711110 0.0096246515 0.3552940000 260957107 0 1786028032 0.7809321284 -0.0785466209 -0.5984443426 1081 43.2000000000 0.0027733799 0.0116324326 0.0741711110 0.0096222774 0.2691010000 259792257 0 1784692736 0.7847172618 -0.0778267682 -0.5912561417 1082 43.2400000000 0.0073713199 0.0116284944 0.0741711110 0.0096191597 0.5756600000 259709870 0 1787023360 0.7879549265 -0.0709220245 -0.5860477090 1083 43.2800000000 0.0077456003 0.0116249091 0.0741711110 0.0096148168 0.4296640000 260576741 0 1783578624 0.7913322449 -0.0689213723 -0.5759856701 1084 43.3200000000 0.0027085396 0.0116166836 0.0741711110 0.0096139627 0.4117970000 264572603 0 1786851328 0.7960024476 -0.0776261464 -0.5658885837 1085 43.3600000000 0.0052282587 0.0116107957 0.0741711110 0.0096117540 0.2370030000 270151462 0 1783640064 0.8014839888 -0.0689057633 -0.5623345375 1086 43.4000000000 0.0091491668 0.0116085290 0.0741711110 0.0096082347 0.2135570000 267721678 0 1779806208 0.8077929616 -0.0630515367 -0.5546144843 1087 43.4400000000 0.0064492999 0.0116037827 0.0741711110 0.0096047312 0.2141640000 267722984 0 1781395456 0.8118627667 -0.0674480125 -0.5460488796 1088 43.4800000000 0.0043517947 0.0115971173 0.0741711110 0.0096004365 0.3829860000 267725510 0 1782317056 0.8102999926 -0.0645643026 -0.5401324630 1089 43.5200000000 0.0069067627 0.0115928102 0.0741711110 0.0095961850 0.5217490000 260235271 0 1784102912 0.8146782517 -0.0612403303 -0.5334008336 1090 43.5600000000 0.0092310114 0.0115906434 0.0741711110 0.0095924098 0.1807990000 259233024 0 1783848960 0.8167198300 -0.0570948310 -0.5259015560 1091 43.6000000000 0.0100221019 0.0115892057 0.0741711110 0.0095904431 0.1840870000 259244486 0 1785516032 0.8216826916 -0.0543527491 -0.5147251487 1092 43.6400000000 0.0089070257 0.0115867495 0.0741711110 0.0095881769 0.1893220000 259242956 0 1787301888 0.8224210739 -0.0527864397 -0.5080367923 1093 43.6800000000 0.0073733991 0.0115828947 0.0741711110 0.0095868095 0.1819160000 259243582 0 1785556992 0.8279401660 -0.0541797765 -0.4997053444 1094 43.7200000000 0.0074330298 0.0115791014 0.0741711110 0.0095847796 0.1895990000 259249008 0 1784827904 0.8276785016 -0.0509928390 -0.4930016994 1095 43.7600000000 0.0122015933 0.0115796699 0.0741711110 0.0095815177 0.1880580000 259248282 0 1786191872 0.8291867375 -0.0448847637 -0.4864597619 1096 43.8000000000 0.0077534039 0.0115761787 0.0741711110 0.0095785309 0.1896320000 259251044 0 1787555840 0.8310039639 -0.0483961254 -0.4797316194 1097 43.8400000000 0.0141473832 0.0115785226 0.0741711110 0.0095751084 0.1958660000 259255634 0 1785319424 0.8365176916 -0.0402326137 -0.4699880183 1098 43.8800000000 0.0118997041 0.0115788151 0.0741711110 0.0095813579 0.1883470000 259256280 0 1786793984 0.8375256062 -0.0398562662 -0.4565235972 1099 43.9200000000 0.0066483174 0.0115743288 0.0741711110 0.0095859704 0.1918370000 259260662 0 1788063744 0.8378673196 -0.0431411043 -0.4497488141 1100 43.9600000000 0.0123814642 0.0115750625 0.0741711110 0.0095826078 0.1947800000 259257512 0 1785315328 0.8412626386 -0.0360380262 -0.4433259368 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 06:40:54 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_rgbd_dataset_freiburg1_rpy.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_rpy.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031229.5287840366 0.0606188439 0.0606188439 0.0606188439 nan 0.1654270000 225877524 0 1771491328 0.0000000000 0.0000000000 0.0000000000 2 1305031229.5644419193 0.0549066812 0.0577627625 0.0606188439 0.0478177145 0.2316440000 230430119 0 1774559232 -0.0097887106 -0.0017962920 0.0139603131 3 1305031229.5966169834 0.0754603073 0.0636619441 0.0754603073 0.0540476947 0.2731810000 230871457 0 1776709632 0.0064977058 -0.0176140685 -0.0036115781 4 1305031229.6287899017 0.0668348819 0.0644551786 0.0754603073 0.0460729872 0.4338340000 231254541 0 1781067776 -0.0026182048 -0.0099314647 0.0066217524 5 1305031229.6646571159 0.0781336203 0.0671908669 0.0781336203 0.0435545113 0.2036860000 231897728 0 1783988224 0.0072961459 -0.0243324209 0.0039660381 6 1305031229.6968429089 0.0799928531 0.0693245313 0.0799928531 0.0390568118 0.2191840000 231683296 0 1784655872 0.0095342174 -0.0231424775 0.0036479309 7 1305031229.7290771008 0.0703819320 0.0694755885 0.0799928531 0.0362216327 0.1936280000 231338541 0 1785540608 0.0038926164 -0.0166511778 0.0132943504 8 1305031229.7648689747 0.0744591877 0.0700985384 0.0799928531 0.0340356223 0.3725910000 231453038 0 1785430016 0.0089694019 -0.0219360385 0.0147525724 9 1305031229.7969229221 0.0777243450 0.0709458503 0.0799928531 0.0321801940 0.1956220000 232177872 0 1784147968 0.0079661598 -0.0202800855 0.0114423735 10 1305031229.8256299496 0.0769411251 0.0715453777 0.0799928531 0.0304160179 0.2117720000 232001388 0 1783226368 0.0022928987 -0.0186542496 0.0124030542 11 1305031229.8630619049 0.0767598376 0.0720194195 0.0799928531 0.0295683412 0.4728640000 231858509 0 1784700928 0.0097849499 -0.0193411000 0.0158564840 12 1305031229.8969380856 0.0815814584 0.0728162561 0.0815814584 0.0299887795 0.3055670000 232955250 0 1784872960 0.0017516396 -0.0194088221 0.0108419470 13 1305031229.9262549877 0.0764834657 0.0730983492 0.0815814584 0.0289288415 0.2277300000 232901204 0 1780936704 0.0077238432 -0.0155790243 0.0173914507 14 1305031229.9662408829 0.0756134316 0.0732779979 0.0815814584 0.0281393480 0.2079950000 232369199 0 1781194752 0.0117745753 -0.0139043592 0.0212687030 15 1305031229.9979310036 0.0705998912 0.0730994575 0.0815814584 0.0276755441 0.4180290000 232331069 0 1782636544 0.0107828211 -0.0070806844 0.0244363956 16 1305031230.0300021172 0.0708796307 0.0729607183 0.0815814584 0.0270687425 0.3142180000 233690213 0 1785294848 0.0180494078 -0.0073594525 0.0305358358 17 1305031230.0656960011 0.0694372579 0.0727534559 0.0815814584 0.0268864740 0.3152840000 233556084 0 1782161408 0.0107641332 -0.0104264356 0.0324032865 18 1305031230.0982739925 0.0676894262 0.0724721209 0.0815814584 0.0262060883 0.2530730000 232873691 0 1781862400 0.0092845839 -0.0069934581 0.0335203074 19 1305031230.1299350262 0.0694242343 0.0723117059 0.0815814584 0.0255088961 0.4363650000 232834485 0 1784414208 0.0075261826 -0.0063952645 0.0319920927 20 1305031230.1657800674 0.0703847185 0.0722153565 0.0815814584 0.0249718382 0.3518730000 234377446 0 1784459264 0.0071103377 -0.0075753476 0.0341353044 21 1305031230.1977820396 0.0723244771 0.0722205527 0.0815814584 0.0244825990 0.2303170000 234303056 0 1783009280 0.0069268662 -0.0075032171 0.0329429246 22 1305031230.2298529148 0.0745700225 0.0723273468 0.0815814584 0.0240876969 0.2369300000 234233910 0 1782001664 0.0052377116 -0.0089077149 0.0326392055 23 1305031230.2655899525 0.0825344548 0.0727711341 0.0825344548 0.0239424621 0.1656800000 232847033 0 1783480320 0.0084357373 -0.0113044623 0.0284742750 24 1305031230.2979929447 0.0833468065 0.0732117871 0.0833468065 0.0235822124 0.1775480000 232850315 0 1785376768 0.0121354368 -0.0110755842 0.0338820666 25 1305031230.3351120949 0.0832133070 0.0736118479 0.0833468065 0.0233141093 0.1741540000 232854169 0 1784254464 0.0066639995 -0.0130862286 0.0329595543 26 1305031230.3656799793 0.0826289877 0.0739586610 0.0833468065 0.0228758237 0.2085040000 233386371 0 1783214080 0.0052834759 -0.0086381920 0.0334812030 27 1305031230.3973290920 0.0823461339 0.0742693081 0.0833468065 0.0224452442 0.4218060000 233401145 0 1785946112 0.0028576599 -0.0085927937 0.0346707851 28 1305031230.4368140697 0.0843181610 0.0746281957 0.0843181610 0.0230899138 0.3059350000 234261058 0 1784123392 -0.0023848070 -0.0091642058 0.0314507559 29 1305031230.4653120041 0.0799013749 0.0748100295 0.0843181610 0.0229288642 0.2716480000 234670984 0 1780080640 -0.0221481435 -0.0116284657 0.0263331383 30 1305031230.4972999096 0.0865149572 0.0752001937 0.0865149572 0.0227468408 0.2061550000 233842839 0 1780219904 -0.0277950093 -0.0126945041 0.0179840606 31 1305031230.5301918983 0.0775116310 0.0752747562 0.0865149572 0.0226242858 0.4285620000 233874417 0 1781215232 -0.0371573195 -0.0124333482 0.0257411655 32 1305031230.5661149025 0.0741599798 0.0752399195 0.0865149572 0.0227024440 0.2930270000 235296862 0 1784864768 -0.0420885384 -0.0108396020 0.0294172484 33 1305031230.5988430977 0.0721698701 0.0751468877 0.0865149572 0.0223723164 0.1975150000 235270260 0 1784025088 -0.0542452931 -0.0093404381 0.0262890141 34 1305031230.6319139004 0.0763012245 0.0751808388 0.0865149572 0.0221305936 0.2760710000 235206106 0 1783013376 -0.0594357699 -0.0094545111 0.0204058420 35 1305031230.6660470963 0.0727758110 0.0751121237 0.0865149572 0.0219807873 0.4066030000 234317910 0 1784655872 -0.0648382306 -0.0048830817 0.0213945191 36 1305031230.6979451180 0.0666179582 0.0748761746 0.0865149572 0.0218542563 0.2693290000 235376489 0 1784860672 -0.0773691535 -0.0001398744 0.0229364075 37 1305031230.7336409092 0.0568427853 0.0743887857 0.0865149572 0.0217492771 0.3031890000 235637168 0 1781731328 -0.0876602083 0.0015696455 0.0310263969 38 1305031230.7659239769 0.0561621860 0.0739091384 0.0865149572 0.0215214946 0.3573990000 234698004 0 1781907456 -0.0944156647 0.0008022711 0.0305984039 39 1305031230.7973229885 0.0530404001 0.0733740425 0.0865149572 0.0214284226 0.2536620000 236129793 0 1784934400 -0.1064566970 0.0004862184 0.0331732109 40 1305031230.8317570686 0.0609017089 0.0730622342 0.0865149572 0.0212410349 0.3237690000 235998808 0 1781284864 -0.1074471027 -0.0024428992 0.0237049367 41 1305031230.8655419350 0.0593208224 0.0727270778 0.0865149572 0.0213298322 0.3351390000 235039850 0 1782579200 -0.1191643551 -0.0036433525 0.0250730589 42 1305031230.8973939419 0.0606670752 0.0724399349 0.0865149572 0.0212424843 0.2242000000 236409627 0 1785208832 -0.1277126223 -0.0011551045 0.0228098724 43 1305031230.9373099804 0.0699814633 0.0723827611 0.0865149572 0.0210299784 0.3031860000 236375694 0 1782145024 -0.1395586729 0.0055409390 0.0121889133 44 1305031230.9650349617 0.0797144473 0.0725493904 0.0865149572 0.0212154547 0.2907600000 235579480 0 1782755328 -0.1543332040 0.0066739116 0.0081860088 45 1305031230.9971239567 0.0798824281 0.0727123467 0.0865149572 0.0210329707 0.2819800000 235778518 0 1784623104 -0.1532219946 0.0083469562 0.0063540884 46 1305031231.0367500782 0.0818044096 0.0729100003 0.0865149572 0.0209935556 0.2791940000 236028497 0 1786793984 -0.1625947803 0.0126344431 0.0106588509 47 1305031231.0644741058 0.0799600184 0.0730600007 0.0865149572 0.0208103253 0.2819870000 236463901 0 1784451072 -0.1563319564 0.0131987184 0.0085962294 48 1305031231.0967879295 0.0814204738 0.0732341772 0.0865149572 0.0206632650 0.2026660000 237460063 0 1784844288 -0.1515679359 0.0114434566 0.0050541176 49 1305031231.1347110271 0.0841862485 0.0734576889 0.0865149572 0.0204746330 0.2662930000 237615118 0 1783791616 -0.1547218114 0.0144156944 0.0050132307 50 1305031231.1652760506 0.0911805406 0.0738121459 0.0911805406 0.0203003405 0.2593920000 236193188 0 1786101760 -0.1518613994 0.0207233801 -0.0035730849 51 1305031231.1977710724 0.0941498801 0.0742109250 0.0941498801 0.0202944621 0.2690370000 237529661 0 1782816768 -0.1537764072 0.0357511863 -0.0022739102 52 1305031231.2344679832 0.1060143784 0.0748225299 0.1060143784 0.0206921808 0.2857610000 237590372 0 1779757056 -0.1514813900 0.0506205633 -0.0094439629 53 1305031231.2656350136 0.0920280442 0.0751471622 0.1060143784 0.0210944479 0.3254590000 237010405 0 1781788672 -0.1251310110 0.0497091413 -0.0007836558 54 1305031231.2978610992 0.0891960189 0.0754073262 0.1060143784 0.0211745516 0.3395100000 237238800 0 1783967744 -0.1260045171 0.0583847165 0.0096227750 55 1305031231.3351519108 0.0880955383 0.0756380210 0.1060143784 0.0212018830 0.3425530000 237298595 0 1786044416 -0.1049451306 0.0524760224 0.0078074280 56 1305031231.3650770187 0.0763067380 0.0756499624 0.1060143784 0.0210306641 0.3148450000 237323557 0 1785200640 -0.1004926413 0.0474662855 0.0208311640 57 1305031231.3973300457 0.0728679225 0.0756011546 0.1060143784 0.0208750048 0.3219650000 237323075 0 1786224640 -0.0892144293 0.0451873057 0.0252223443 58 1305031231.4368579388 0.0633146688 0.0753893187 0.1060143784 0.0209469555 0.3288980000 237453268 0 1785352192 -0.0842661038 0.0360670164 0.0356445760 59 1305031231.4649889469 0.0609810948 0.0751451115 0.1060143784 0.0207762270 0.2741160000 239506897 0 1785548800 -0.0808639601 0.0361567214 0.0397335738 60 1305031231.4992439747 0.0542678535 0.0747971572 0.1060143784 0.0206323491 0.2328400000 239380404 0 1784053760 -0.0813229233 0.0409705453 0.0487806499 61 1305031231.5331959724 0.0534862578 0.0744477982 0.1060143784 0.0205222666 0.3103290000 239269564 0 1781899264 -0.0819345713 0.0351959728 0.0509805307 62 1305031231.5650680065 0.0563268550 0.0741555249 0.1060143784 0.0205002219 0.3922210000 237734876 0 1782075392 -0.0764185935 0.0350132585 0.0490040593 63 1305031231.6013169289 0.0565472022 0.0738760277 0.1060143784 0.0203576406 0.3827060000 237744274 0 1784602624 -0.0707201734 0.0349231139 0.0494905040 64 1305031231.6331589222 0.0596334077 0.0736534868 0.1060143784 0.0203205761 0.3599370000 237880246 0 1785929728 -0.0627840459 0.0328332745 0.0477293283 65 1305031231.6650550365 0.0597962514 0.0734402986 0.1060143784 0.0201711556 0.2869260000 240652613 0 1784471552 -0.0570881367 0.0316680036 0.0484468862 66 1305031231.7035079002 0.0585958250 0.0732153823 0.1060143784 0.0203082047 0.2407940000 240601602 0 1783648256 -0.0562947318 0.0312175099 0.0504806340 67 1305031231.7339379787 0.0595026650 0.0730107149 0.1060143784 0.0204917134 0.3858550000 240463984 0 1781100544 -0.0521015748 0.0340611413 0.0495126024 68 1305031231.7655088902 0.0495202132 0.0726652663 0.1060143784 0.0205943680 0.1999660000 238238028 0 1781301248 -0.0524958335 0.0416760147 0.0590161607 69 1305031231.8011910915 0.0540319532 0.0723952183 0.1060143784 0.0206095094 0.4179640000 238212902 0 1781796864 -0.0494802967 0.0407317132 0.0549639426 70 1305031231.8332920074 0.0545377247 0.0721401112 0.1060143784 0.0207850400 0.3875500000 238215868 0 1783947264 -0.0464321896 0.0364257097 0.0553768314 71 1305031231.8649590015 0.0588121340 0.0719523933 0.1060143784 0.0209345778 0.3453000000 238358674 0 1785573376 -0.0437013209 0.0366102420 0.0507464074 72 1305031231.9012699127 0.0643319711 0.0718465541 0.1060143784 0.0210293573 0.3018350000 241546083 0 1785044992 -0.0428116322 0.0367554277 0.0448109582 73 1305031231.9330461025 0.0678839013 0.0717922711 0.1060143784 0.0209534144 0.2723220000 241476728 0 1784041472 -0.0424793586 0.0346456729 0.0412295386 74 1305031231.9650299549 0.0639462993 0.0716862445 0.1060143784 0.0210033599 0.1761370000 241387951 0 1785729024 -0.0379033834 0.0304357912 0.0451842509 75 1305031232.0007200241 0.0600160435 0.0715306418 0.1060143784 0.0209114997 0.3542120000 241318676 0 1784336384 -0.0393474996 0.0288165286 0.0490633622 76 1305031232.0332028866 0.0537834987 0.0712971268 0.1060143784 0.0222042093 0.1948940000 238739484 0 1784352768 -0.0219642185 0.0086708758 0.0677235872 77 1305031232.0651450157 0.0527245030 0.0710559239 0.1060143784 0.0221219594 0.4445700000 238711138 0 1783066624 -0.0196451750 0.0093548521 0.0673378929 78 1305031232.1007990837 0.0540035032 0.0708373031 0.1060143784 0.0220378670 0.3896580000 238714164 0 1784066048 -0.0181382690 0.0069819428 0.0665660501 79 1305031232.1328380108 0.0555806160 0.0706441805 0.1060143784 0.0219134431 0.3689930000 238859790 0 1786351616 -0.0186028071 0.0045011137 0.0650459453 80 1305031232.1650519371 0.0568212122 0.0704713934 0.1060143784 0.0218691241 0.3623040000 242030567 0 1783607296 -0.0127156535 0.0037615241 0.0628858060 81 1305031232.1992239952 0.0643223897 0.0703954797 0.1060143784 0.0217755565 0.3236570000 242027086 0 1783500800 0.0029472988 0.0051531531 0.0549216270 82 1305031232.2364680767 0.0928169638 0.0706689125 0.1060143784 0.0220870332 0.1800950000 241947779 0 1785315328 0.0147029273 -0.0207200162 0.0413470268 83 1305031232.2626979351 0.1080675647 0.0711194986 0.1080675647 0.0221962021 0.3681910000 241878416 0 1784619008 0.0247187614 -0.0310612656 0.0327682011 84 1305031232.2980248928 0.1124120355 0.0716110765 0.1124120355 0.0221590860 0.1959620000 239218960 0 1784176640 0.0112005770 -0.0333056822 0.0182814505 85 1305031232.3321430683 0.1119906381 0.0720861301 0.1124120355 0.0221010616 0.4204790000 239178122 0 1784434688 0.0057306197 -0.0347007737 0.0164577588 86 1305031232.3647489548 0.1080086082 0.0725038334 0.1124120355 0.0220975814 0.3760740000 239180716 0 1786654720 0.0020551174 -0.0293482654 0.0140415179 87 1305031232.4008779526 0.1073949486 0.0729048807 0.1124120355 0.0220946144 0.3542450000 239323022 0 1784381440 -0.0102984030 -0.0303004235 0.0127004161 88 1305031232.4331440926 0.1097117811 0.0733231409 0.1124120355 0.0219725505 0.3029230000 242139011 0 1785651200 -0.0141047016 -0.0310747102 0.0085742818 89 1305031232.4647209644 0.1256475449 0.0739110555 0.1256475449 0.0219107414 0.2298050000 242010236 0 1782763520 -0.0239634104 -0.0457754619 -0.0001032116 90 1305031232.5015261173 0.1226703972 0.0744528260 0.1256475449 0.0218005760 0.3623280000 241944514 0 1782411264 -0.0131014241 -0.0448439717 0.0010491917 91 1305031232.5324640274 0.1257999241 0.0750170798 0.1257999241 0.0216904694 0.2317250000 239689330 0 1781985280 -0.0136839775 -0.0479775891 -0.0017489810 92 1305031232.5647449493 0.1291724294 0.0756057249 0.1291724294 0.0215927182 0.4297410000 239651708 0 1780838400 -0.0172489081 -0.0502736717 -0.0062173754 93 1305031232.6003499031 0.1306767166 0.0761978861 0.1306767166 0.0214801470 0.3717740000 239653994 0 1782902784 -0.0166431442 -0.0505626686 -0.0098927058 94 1305031232.6294269562 0.1385603696 0.0768613168 0.1385603696 0.0214046598 0.3554590000 240624967 0 1786400768 -0.0162767377 -0.0562977679 -0.0170719102 95 1305031232.6647078991 0.1312524825 0.0774338554 0.1385603696 0.0213507023 0.3177950000 241875100 0 1783275520 -0.0294662565 -0.0521102771 -0.0125279445 96 1305031232.7005090714 0.1346874684 0.0780302472 0.1385603696 0.0212517983 0.3858080000 241791758 0 1781891072 -0.0330947191 -0.0562723726 -0.0144263534 97 1305031232.7327980995 0.1381685436 0.0786502296 0.1385603696 0.0212397658 0.1801100000 239660654 0 1782214656 -0.0240927786 -0.0574452467 -0.0213847347 98 1305031232.7684600353 0.1339762956 0.0792147813 0.1385603696 0.0212074823 0.1736600000 239662824 0 1784606720 -0.0262583029 -0.0553931184 -0.0200316403 99 1305031232.8045380116 0.1346357167 0.0797745888 0.1385603696 0.0211521548 0.1751450000 239665818 0 1786400768 -0.0307426117 -0.0584392510 -0.0206436608 100 1305031232.8346450329 0.1292280704 0.0802691236 0.1385603696 0.0210936379 0.2114330000 240173752 0 1785147392 -0.0296041276 -0.0550990552 -0.0192335807 101 1305031232.8685569763 0.1246317923 0.0807083579 0.1385603696 0.0210762745 0.4174000000 240125502 0 1786523648 -0.0323448740 -0.0518266708 -0.0181625299 102 1305031232.9041829109 0.1149661541 0.0810442187 0.1385603696 0.0210522837 0.3661590000 240231604 0 1783463936 -0.0379756615 -0.0452223457 -0.0126718599 103 1305031232.9330000877 0.1074985042 0.0813010564 0.1385603696 0.0209963671 0.3523500000 242683985 0 1783980032 -0.0394960903 -0.0376036987 -0.0102356579 104 1305031232.9683640003 0.1097160727 0.0815742777 0.1385603696 0.0209049203 0.2354860000 242570730 0 1782976512 -0.0401146039 -0.0393634811 -0.0139101753 105 1305031233.0011510849 0.1078324541 0.0818243556 0.1385603696 0.0209096832 0.3874530000 242441808 0 1781686272 -0.0491082221 -0.0344123207 -0.0129037397 106 1305031233.0330219269 0.0942080095 0.0819411825 0.1385603696 0.0209342971 0.3959470000 240572992 0 1782525952 -0.0498102605 -0.0133048333 -0.0106950281 107 1305031233.0688428879 0.0904358625 0.0820205720 0.1385603696 0.0209215199 0.3508760000 240574986 0 1784496128 -0.0383573249 -0.0105883963 -0.0120655820 108 1305031233.1004469395 0.0765428692 0.0819698526 0.1385603696 0.0209945863 0.3411310000 241444843 0 1784508416 -0.0439224578 0.0175744537 -0.0049955114 109 1305031233.1328918934 0.0946242735 0.0820859482 0.1385603696 0.0219217101 0.3253740000 242681485 0 1783992320 -0.0319052562 -0.0023482246 -0.0196545981 110 1305031233.1684799194 0.1054750457 0.0822985763 0.1385603696 0.0220644944 0.3899720000 242542630 0 1783209984 -0.0356217027 -0.0228035375 -0.0165319908 111 1305031233.2006340027 0.1064426079 0.0825160901 0.1385603696 0.0220441613 0.4383510000 241008490 0 1783873536 -0.0335848331 -0.0229363088 -0.0153741017 112 1305031233.2330091000 0.1022656187 0.0826924252 0.1385603696 0.0219979641 0.3798960000 241009744 0 1785401344 -0.0380143560 -0.0177329965 -0.0107230106 113 1305031233.2684679031 0.0991439149 0.0828380136 0.1385603696 0.0222463446 0.3511880000 241135014 0 1784373248 -0.0321507677 -0.0078821406 -0.0101246675 114 1305031233.3003950119 0.1057794914 0.0830392546 0.1385603696 0.0223555978 0.3654400000 244134626 0 1783185408 -0.0399150215 -0.0016991796 -0.0166040398 115 1305031233.3325300217 0.1091766506 0.0832665363 0.1385603696 0.0224677252 0.4499120000 244063444 0 1777156096 -0.0603485703 -0.0031434968 -0.0129280575 116 1305031233.3686299324 0.1104208156 0.0835006250 0.1385603696 0.0226969385 0.3576420000 241569520 0 1778937856 -0.0532270148 -0.0127881775 -0.0067868913 117 1305031233.4008929729 0.1131509915 0.0837540469 0.1385603696 0.0226222580 0.3664050000 241572906 0 1780170752 -0.0600056276 -0.0094728814 -0.0084279487 118 1305031233.4330079556 0.1062810495 0.0839449537 0.1385603696 0.0228651174 0.3512580000 241575288 0 1782480896 -0.0616057552 -0.0114870463 0.0032795090 119 1305031233.4687869549 0.0931719691 0.0840224916 0.1385603696 0.0230895012 0.3503700000 242741433 0 1784627200 -0.0468516052 -0.0051884549 0.0168509129 120 1305031233.5007359982 0.0874429122 0.0840509951 0.1385603696 0.0230445201 0.2626150000 244684683 0 1783083008 -0.0443803668 -0.0021219174 0.0241140034 121 1305031233.5341610909 0.0921996310 0.0841183392 0.1385603696 0.0230616861 0.2661230000 244559285 0 1782218752 -0.0428670794 -0.0064191385 0.0241509788 122 1305031233.5697269440 0.0976816490 0.0842295139 0.1385603696 0.0231009575 0.4260690000 244484734 0 1780174848 -0.0548410863 -0.0044522686 0.0162539817 123 1305031233.6012749672 0.1021240205 0.0843749977 0.1385603696 0.0230822305 0.4745890000 242039382 0 1778806784 -0.0569839180 -0.0085926354 0.0149337463 124 1305031233.6330409050 0.1014777198 0.0845129229 0.1385603696 0.0230455275 0.4070580000 242041612 0 1780584448 -0.0552274957 -0.0079823714 0.0161480159 125 1305031233.6717829704 0.0981419906 0.0846219554 0.1385603696 0.0229569746 0.4006910000 242043854 0 1782976512 -0.0519165136 -0.0052863443 0.0196259189 126 1305031233.7022960186 0.0979526043 0.0847277542 0.1385603696 0.0230371857 0.3778600000 243887091 0 1785122816 -0.0385085568 -0.0095798010 0.0271980464 127 1305031233.7312009335 0.0833629444 0.0847170077 0.1385603696 0.0232560583 0.3252410000 246655713 0 1782566912 -0.0323732607 0.0045729973 0.0387740694 128 1305031233.7691600323 0.0738508403 0.0846321158 0.1385603696 0.0233510628 0.3650620000 246523834 0 1781698560 -0.0323699079 0.0095632225 0.0474596731 129 1305031233.7997679710 0.0716991127 0.0845318599 0.1385603696 0.0233348991 0.2078670000 246428157 0 1783353344 -0.0372707471 0.0131034357 0.0447311439 130 1305031233.8338310719 0.0760546327 0.0844666505 0.1385603696 0.0233388855 0.4273050000 246514336 0 1780768768 -0.0362098366 0.0029794248 0.0454113148 131 1305031233.8655700684 0.0809352770 0.0844396934 0.1385603696 0.0233081993 0.3141700000 242559534 0 1780883456 -0.0331813246 0.0014506949 0.0410556458 132 1305031233.8986968994 0.0790832788 0.0843991145 0.1385603696 0.0232284409 0.4543190000 242590137 0 1778606080 -0.0313462988 0.0013803752 0.0439299978 133 1305031233.9320030212 0.0775900483 0.0843479185 0.1385603696 0.0231977050 0.4030410000 242512946 0 1779707904 -0.0264334716 -0.0007145467 0.0498692170 134 1305031233.9681589603 0.0745847598 0.0842750592 0.1385603696 0.0231234606 0.3959800000 242647224 0 1782120448 -0.0250014439 0.0017581849 0.0511935465 135 1305031233.9989380836 0.0720425993 0.0841844483 0.1385603696 0.0230556483 0.3781500000 246575221 0 1784180736 -0.0234797392 0.0004895378 0.0560418367 136 1305031234.0370678902 0.0714540705 0.0840908426 0.1385603696 0.0229833850 0.3247560000 246880136 0 1783865344 -0.0213402547 0.0047454569 0.0523014478 137 1305031234.0687561035 0.0690754950 0.0839812415 0.1385603696 0.0229092964 0.2170720000 246799754 0 1785655296 -0.0200991593 0.0068845563 0.0531015992 138 1305031234.0997409821 0.0718658790 0.0838934491 0.1385603696 0.0228596320 0.4444360000 246533942 0 1783627776 -0.0208472982 0.0078329407 0.0469998717 139 1305031234.1350688934 0.0706592798 0.0837982392 0.1385603696 0.0227888215 0.2337700000 242522170 0 1783279616 -0.0220041797 0.0081804432 0.0474402346 140 1305031234.1659009457 0.0706744269 0.0837044977 0.1385603696 0.0227456069 0.1953980000 242524240 0 1785802752 -0.0195558555 0.0141361393 0.0443541221 141 1305031234.2010040283 0.0797704905 0.0836765969 0.1385603696 0.0227722714 0.2193340000 243018146 0 1784819712 -0.0161550567 0.0035951319 0.0414511599 142 1305031234.2385749817 0.0753660053 0.0836180716 0.1385603696 0.0227118039 0.4480920000 242979852 0 1783656448 -0.0171693899 0.0123196915 0.0407343321 143 1305031234.2655100822 0.0742068663 0.0835522590 0.1385603696 0.0226319399 0.4277830000 242981858 0 1785745408 -0.0157191716 0.0153285572 0.0420175008 144 1305031234.3024549484 0.0745938867 0.0834900481 0.1385603696 0.0225542349 0.4099940000 242983764 0 1784561664 -0.0162849538 0.0123716146 0.0430835374 145 1305031234.3384580612 0.0732251033 0.0834192554 0.1385603696 0.0224814742 0.3934630000 245178781 0 1786228736 -0.0172914676 0.0152213238 0.0431846641 146 1305031234.3661808968 0.0699756742 0.0833271760 0.1385603696 0.0224394438 0.2899320000 247479491 0 1784221696 -0.0191038698 0.0210584812 0.0434009507 147 1305031234.4000349045 0.0717155263 0.0832481852 0.1385603696 0.0223681660 0.2998640000 247416956 0 1786040320 -0.0153384674 0.0184829906 0.0444568619 148 1305031234.4367709160 0.0706272423 0.0831629086 0.1385603696 0.0223967828 0.4583740000 247232330 0 1781104640 -0.0138612427 0.0124178277 0.0489832126 149 1305031234.4676060677 0.0669362023 0.0830540045 0.1385603696 0.0223400036 0.2290510000 242991158 0 1780977664 -0.0137276389 0.0158831403 0.0507099107 150 1305031234.4977810383 0.0688950270 0.0829596113 0.1385603696 0.0222652430 0.2099840000 243444784 0 1783349248 -0.0105126975 0.0122179883 0.0513784513 151 1305031234.5376710892 0.0694598109 0.0828702087 0.1385603696 0.0223254256 0.4113300000 243404838 0 1785065472 -0.0091887489 0.0096507464 0.0501310602 152 1305031234.5690369606 0.0708232000 0.0827909521 0.1385603696 0.0223290735 0.3536090000 243402540 0 1786646528 -0.0057078395 0.0157481357 0.0452313647 153 1305031234.5982480049 0.0714559183 0.0827168669 0.1385603696 0.0222625489 0.3452120000 243565882 0 1783914496 -0.0053485464 0.0131268539 0.0440234691 154 1305031234.6336491108 0.0716837123 0.0826452230 0.1385603696 0.0222009194 0.3271960000 245717631 0 1785618432 -0.0013573300 0.0163960233 0.0423102081 155 1305031234.6658589840 0.0757501349 0.0826007386 0.1385603696 0.0221382454 0.2297440000 247759149 0 1784426496 0.0021208106 0.0148457652 0.0385407992 156 1305031234.6987318993 0.0747700036 0.0825505415 0.1385603696 0.0220716557 0.2560550000 247661088 0 1783468032 0.0024534278 0.0190939102 0.0376458988 157 1305031234.7344369888 0.0805172920 0.0825375909 0.1385603696 0.0220281454 0.1649390000 247595349 0 1785745408 0.0053552482 0.0212759245 0.0305452533 158 1305031234.7689719200 0.0861034095 0.0825601594 0.1385603696 0.0219656692 0.3539040000 247526302 0 1781395456 0.0099630384 0.0196991935 0.0260675009 159 1305031234.8015530109 0.0864914805 0.0825848847 0.1385603696 0.0219655797 0.2981340000 243721522 0 1779175424 0.0078940159 0.0293182600 0.0222234391 160 1305031234.8378078938 0.0848612264 0.0825991118 0.1385603696 0.0219031301 0.2727470000 243876272 0 1780547584 0.0068827490 0.0240319166 0.0240108352 161 1305031234.8693211079 0.0886935666 0.0826369656 0.1385603696 0.0218513506 0.2647820000 245806657 0 1786449920 0.0095307417 0.0327152275 0.0206251387 162 1305031234.9019980431 0.0895554721 0.0826796724 0.1385603696 0.0217866465 0.2317570000 247176013 0 1783836672 0.0078411167 0.0321745798 0.0194599219 163 1305031234.9381608963 0.0886189118 0.0827161094 0.1385603696 0.0218177814 0.3010990000 247031296 0 1781022720 0.0037446315 0.0379266217 0.0206469875 164 1305031234.9730799198 0.0966399759 0.0828010111 0.1385603696 0.0217823497 0.2633570000 244170708 0 1783484416 0.0064451681 0.0396009274 0.0157849491 165 1305031235.0050830841 0.0936069861 0.0828665018 0.1385603696 0.0218066635 0.2621040000 244222666 0 1783603200 0.0014065793 0.0465503186 0.0203622021 166 1305031235.0399720669 0.0948192477 0.0829385063 0.1385603696 0.0217523076 0.2867830000 245695259 0 1786195968 0.0036724564 0.0374906696 0.0225472432 167 1305031235.0729401112 0.0953391045 0.0830127614 0.1385603696 0.0217111045 0.3236780000 245823542 0 1784033280 -0.0004136132 0.0411633886 0.0229264386 168 1305031235.0995910168 0.0897344202 0.0830527713 0.1385603696 0.0216632515 0.2951480000 244712500 0 1782632448 -0.0014740329 0.0361017622 0.0303155147 169 1305031235.1362709999 0.0888644755 0.0830871601 0.1385603696 0.0216270406 0.2869630000 244819757 0 1781252096 -0.0032160988 0.0416937508 0.0330714807 170 1305031235.1663711071 0.0852058083 0.0830996227 0.1385603696 0.0216405182 0.3002370000 244776568 0 1783529472 -0.0077339252 0.0457408205 0.0375324376 171 1305031235.1998469830 0.0780570135 0.0830701338 0.1385603696 0.0216187504 0.3056250000 246972237 0 1784279040 -0.0172426663 0.0470990539 0.0437887348 172 1305031235.2375700474 0.0725486502 0.0830089623 0.1385603696 0.0216895035 0.2326970000 248950831 0 1784459264 -0.0193992276 0.0561542995 0.0515070260 173 1305031235.2690389156 0.0699768215 0.0829336320 0.1385603696 0.0216288516 0.2454050000 248640750 0 1786576896 -0.0289100017 0.0551440269 0.0535564236 174 1305031235.3064870834 0.0623425059 0.0828152922 0.1385603696 0.0216413078 0.3847600000 248380886 0 1778843648 -0.0281709917 0.0533139631 0.0637354553 175 1305031235.3380000591 0.0592855550 0.0826808366 0.1385603696 0.0215902520 0.2157100000 245180266 0 1779191808 -0.0298276525 0.0568341576 0.0689524636 176 1305031235.3698880672 0.0605356023 0.0825550114 0.1385603696 0.0215796824 0.4204420000 245177956 0 1780113408 -0.0318778530 0.0519129112 0.0694227964 177 1305031235.4060161114 0.0625917390 0.0824422246 0.1385603696 0.0216689747 0.4063600000 245181070 0 1782562816 -0.0366540737 0.0588192716 0.0703771189 178 1305031235.4381530285 0.0601238944 0.0823168407 0.1385603696 0.0216205342 0.3834380000 245342808 0 1784352768 -0.0384677500 0.0583646074 0.0745296553 179 1305031235.4700589180 0.0636096671 0.0822123313 0.1385603696 0.0215871679 0.4076090000 249900829 0 1785352192 -0.0379413627 0.0531579144 0.0738363490 180 1305031235.5059850216 0.0655646473 0.0821198442 0.1385603696 0.0215394356 0.2820010000 250822356 0 1785626624 -0.0392307267 0.0510408171 0.0765278414 181 1305031235.5385539532 0.0639867857 0.0820196615 0.1385603696 0.0214847509 0.2805350000 250656710 0 1785282560 -0.0407339111 0.0542077944 0.0797166675 182 1305031235.5703649521 0.0657662377 0.0819303570 0.1385603696 0.0214269004 0.5096010000 250029522 0 1779761152 -0.0446338169 0.0549686290 0.0811249316 183 1305031235.6060059071 0.0650861859 0.0818383124 0.1385603696 0.0214517600 0.2647560000 245650274 0 1779879936 -0.0499904379 0.0639940351 0.0848317817 184 1305031235.6389510632 0.0668129697 0.0817566529 0.1385603696 0.0214205634 0.5037780000 245634340 0 1778442240 -0.0509205945 0.0572366640 0.0882815793 185 1305031235.6705160141 0.0689538196 0.0816874484 0.1385603696 0.0213669240 0.4530570000 245636322 0 1780310016 -0.0542158559 0.0576515719 0.0903385580 186 1305031235.7057778835 0.0671397597 0.0816092350 0.1385603696 0.0213106247 0.4248980000 245638860 0 1782091776 -0.0535917282 0.0547754653 0.0991884917 187 1305031235.7387969494 0.0711757541 0.0815534410 0.1385603696 0.0212605317 0.4100270000 245659806 0 1783742464 -0.0584591404 0.0556776188 0.1001972705 188 1305031235.7696299553 0.0701335967 0.0814926971 0.1385603696 0.0212138014 0.4106210000 251095519 0 1784483840 -0.0606907643 0.0586894080 0.1051839665 189 1305031235.8072249889 0.0740947798 0.0814535547 0.1385603696 0.0211658895 0.2835270000 251353601 0 1784872960 -0.0604074970 0.0504511595 0.1135467440 190 1305031235.8388121128 0.0769044533 0.0814296121 0.1385603696 0.0211243337 0.2706780000 251549216 0 1786839040 -0.0637460649 0.0518146642 0.1153805703 191 1305031235.8700668812 0.0787140355 0.0814153944 0.1385603696 0.0211065387 0.1850030000 251144093 0 1784225792 -0.0668562055 0.0522242337 0.1208644956 192 1305031235.9061110020 0.0818453133 0.0814176336 0.1385603696 0.0210610814 0.4460210000 251075062 0 1777127424 -0.0662024245 0.0486428142 0.1289744079 193 1305031235.9382328987 0.0888003111 0.0814558858 0.1385603696 0.0210190125 0.2664830000 246208786 0 1777401856 -0.0700082481 0.0453474708 0.1306554228 194 1305031235.9700109959 0.0912431255 0.0815063355 0.1385603696 0.0209708378 0.4511400000 246198256 0 1774870528 -0.0738585070 0.0479217172 0.1315449923 195 1305031236.0068531036 0.0898291618 0.0815490166 0.1385603696 0.0209219774 0.3914190000 246199922 0 1776852992 -0.0768736526 0.0561535768 0.1318890303 196 1305031236.0380480289 0.0933988690 0.0816094751 0.1385603696 0.0208708175 0.3670290000 246201740 0 1778413568 -0.0791586041 0.0557685792 0.1349099278 197 1305031236.0698781013 0.0909356698 0.0816568162 0.1385603696 0.0208400787 0.3438920000 246714546 0 1780584448 -0.0821260065 0.0650963485 0.1331908107 198 1305031236.1058719158 0.0910123736 0.0817040664 0.1385603696 0.0207894217 0.3483510000 251470599 0 1783746560 -0.0846922398 0.0705484822 0.1333761513 199 1305031236.1383249760 0.0891134217 0.0817412994 0.1385603696 0.0207391717 0.2408390000 251637754 0 1783885824 -0.0861062482 0.0765801892 0.1341706961 200 1305031236.1709330082 0.0879396573 0.0817722912 0.1385603696 0.0206922966 0.2466180000 251385596 0 1785192448 -0.0810013115 0.0752814263 0.1362490058 201 1305031236.2071900368 0.0868974775 0.0817977896 0.1385603696 0.0206489936 0.4046350000 251382444 0 1784410112 -0.0842233002 0.0813966841 0.1371761858 202 1305031236.2383749485 0.0808444098 0.0817930699 0.1385603696 0.0205992073 0.2702950000 246795308 0 1779867648 -0.0786217377 0.0856406614 0.1360132694 203 1305031236.2699589729 0.0798198655 0.0817833497 0.1385603696 0.0205508298 0.4530910000 246762562 0 1779245056 -0.0789017379 0.0868127197 0.1363028288 204 1305031236.3069939613 0.0796123371 0.0817727075 0.1385603696 0.0205459490 0.3940400000 246759180 0 1780998144 -0.0805054307 0.0862614065 0.1375307441 205 1305031236.3392169476 0.0789845735 0.0817591068 0.1385603696 0.0204967683 0.3779340000 249679565 0 1786470400 -0.0786021501 0.0836218223 0.1353855282 206 1305031236.3700959682 0.0746703297 0.0817246953 0.1385603696 0.0204508261 0.2640320000 251685375 0 1783779328 -0.0796520635 0.0880242586 0.1355879605 207 1305031236.4058690071 0.0717535987 0.0816765257 0.1385603696 0.0204321370 0.2746480000 251630212 0 1782779904 -0.0761588588 0.0859279484 0.1310994178 208 1305031236.4387879372 0.0682552382 0.0816120003 0.1385603696 0.0203907775 0.4617500000 251476778 0 1780224000 -0.0759479105 0.0925863236 0.1238451675 209 1305031236.4751410484 0.0607873946 0.0815123611 0.1385603696 0.0203460452 0.2371790000 247244826 0 1780301824 -0.0695470497 0.0910552293 0.1231504679 210 1305031236.5077209473 0.0589801334 0.0814050647 0.1385603696 0.0203016658 0.4631520000 247206284 0 1780260864 -0.0668027848 0.0884927660 0.1189142466 211 1305031236.5386450291 0.0555208735 0.0812823908 0.1385603696 0.0202825817 0.4443030000 247208510 0 1781657600 -0.0610653274 0.0833713561 0.1166777238 212 1305031236.5740950108 0.0531450398 0.0811496675 0.1385603696 0.0202604162 0.4187140000 247210780 0 1783308288 -0.0571736023 0.0781766027 0.1120735034 213 1305031236.6057569981 0.0489690080 0.0809985846 0.1385603696 0.0202421764 0.4189740000 250403189 0 1785786368 -0.0528556854 0.0800070837 0.1065178663 214 1305031236.6384010315 0.0489792712 0.0808489616 0.1385603696 0.0201968346 0.3194500000 252923759 0 1783140352 -0.0504385866 0.0694153309 0.1066554189 215 1305031236.6751470566 0.0454616025 0.0806843692 0.1385603696 0.0201772160 0.3376110000 252931428 0 1782448128 -0.0450386405 0.0654852986 0.1030875146 216 1305031236.7033619881 0.0590219237 0.0805840801 0.1385603696 0.0202173364 0.2170450000 252732959 0 1784229888 -0.0416930430 0.0397326201 0.1018957868 217 1305031236.7339220047 0.0822370872 0.0805916977 0.1385603696 0.0202291426 0.5300570000 252663392 0 1779916800 -0.0381115191 0.0090183392 0.0989304557 218 1305031236.7740409374 0.0802889615 0.0805903090 0.1385603696 0.0202309313 0.2460970000 247676812 0 1780006912 -0.0376172885 0.0066379211 0.0918592364 219 1305031236.8025879860 0.0820405856 0.0805969313 0.1385603696 0.0203829767 0.4943920000 247634494 0 1779277824 -0.0374443308 0.0053308569 0.0827766061 220 1305031236.8364150524 0.0761519372 0.0805767267 0.1385603696 0.0203390763 0.4623300000 247635872 0 1781776384 -0.0329775438 0.0070352945 0.0781091154 221 1305031236.8743979931 0.0724257678 0.0805398446 0.1385603696 0.0203060202 0.4692670000 247638542 0 1783611392 -0.0309973769 0.0088859648 0.0691583902 222 1305031236.9060690403 0.0738161728 0.0805095578 0.1385603696 0.0203003485 0.4661050000 247662548 0 1785319424 -0.0287128314 0.0052793645 0.0628477186 223 1305031236.9344370365 0.0715962350 0.0804695877 0.1385603696 0.0202716143 0.4657390000 253939949 0 1783951360 -0.0282607973 0.0077948817 0.0555509813 224 1305031236.9744000435 0.0699378252 0.0804225709 0.1385603696 0.0202357438 0.2735100000 254954972 0 1782558720 -0.0251926053 0.0060561849 0.0498694740 225 1305031237.0074260235 0.0712675676 0.0803818820 0.1385603696 0.0201954966 0.3028050000 254387846 0 1784684544 -0.0190263577 0.0043414859 0.0446528904 226 1305031237.0370240211 0.0714828297 0.0803425057 0.1385603696 0.0201690715 0.2161750000 254003771 0 1786519552 -0.0145332851 0.0081893187 0.0377014130 227 1305031237.0734269619 0.0738118142 0.0803137361 0.1385603696 0.0201517317 0.5313230000 253934608 0 1776173056 -0.0066876607 0.0033962084 0.0356640257 228 1305031237.1059679985 0.0771283656 0.0802997652 0.1385603696 0.0201133552 0.2696290000 248068936 0 1776467968 -0.0015596226 -0.0029393933 0.0346269608 229 1305031237.1378319263 0.0779565871 0.0802895330 0.1385603696 0.0200808277 0.4336210000 248052002 0 1777848320 0.0025159530 -0.0004141675 0.0291832499 230 1305031237.1712269783 0.0792579725 0.0802850479 0.1385603696 0.0200991188 0.4084070000 248058044 0 1779625984 0.0054557920 0.0042107417 0.0216658562 231 1305031237.2042291164 0.0803842098 0.0802854772 0.1385603696 0.0201043690 0.3957670000 248221110 0 1781264384 0.0074150092 -0.0029951311 0.0182571895 232 1305031237.2375690937 0.0820331872 0.0802930104 0.1385603696 0.0201003256 0.3659880000 251199723 0 1784995840 0.0110002682 0.0063685407 0.0110432468 233 1305031237.2746589184 0.0801430419 0.0802923668 0.1385603696 0.0200835395 0.3594450000 254381865 0 1785909248 0.0125756944 0.0063816523 0.0102823786 234 1305031237.3058099747 0.0887043178 0.0803283153 0.1385603696 0.0200489576 0.2188450000 254740532 0 1783504896 0.0210389234 0.0078351405 0.0030189138 235 1305031237.3371419907 0.0921549276 0.0803786413 0.1385603696 0.0200405412 0.2771240000 254982658 0 1785827328 0.0247622654 0.0090333605 -0.0000839299 236 1305031237.3741660118 0.0965675339 0.0804472383 0.1385603696 0.0200169015 0.1928810000 254500187 0 1784958976 0.0249295272 0.0072643519 -0.0114596402 237 1305031237.4057340622 0.0970214978 0.0805171719 0.1385603696 0.0200197563 0.4086640000 254431112 0 1781030912 0.0269914605 0.0136816381 -0.0129261892 238 1305031237.4377219677 0.0926249251 0.0805680448 0.1385603696 0.0200337903 0.2498910000 248071176 0 1776635904 0.0294103362 0.0087881107 -0.0022223396 239 1305031237.4741280079 0.0933151692 0.0806213800 0.1385603696 0.0200218869 0.1892030000 248391354 0 1776828416 0.0304884072 0.0047516054 -0.0049813576 240 1305031237.5060451031 0.0973840430 0.0806912245 0.1385603696 0.0200000819 0.3299710000 248375116 0 1774665728 0.0318761468 0.0124889659 -0.0135324243 241 1305031237.5376501083 0.0941342562 0.0807470047 0.1385603696 0.0199628591 0.3016790000 248529242 0 1776312320 0.0327750891 0.0092919916 -0.0077995379 242 1305031237.5739479065 0.1002149135 0.0808274506 0.1385603696 0.0199473721 0.3173480000 250658524 0 1782444032 0.0359246656 0.0137532577 -0.0158891752 243 1305031237.6068129539 0.0996494368 0.0809049073 0.1385603696 0.0199148264 0.3268020000 248918283 0 1780600832 0.0363867059 0.0166682433 -0.0156846158 244 1305031237.6378550529 0.0997399166 0.0809821000 0.1385603696 0.0198854811 0.2996330000 248874544 0 1782202368 0.0362556130 0.0183451530 -0.0168551132 245 1305031237.6752760410 0.0978580043 0.0810509812 0.1385603696 0.0198636910 0.3027360000 249098886 0 1784107008 0.0352748372 0.0185313225 -0.0147212688 246 1305031237.7071180344 0.1014280021 0.0811338146 0.1385603696 0.0198280966 0.2962620000 249362788 0 1786208256 0.0371983424 0.0211905949 -0.0183438063 247 1305031237.7416670322 0.1023004502 0.0812195095 0.1385603696 0.0198008769 0.2919950000 249446054 0 1784573952 0.0364392102 0.0233180281 -0.0207326263 248 1305031237.7743060589 0.0983307287 0.0812885064 0.1385603696 0.0198292609 0.3061170000 249617016 0 1786290176 0.0360817537 0.0175054856 -0.0147698941 249 1305031237.8064959049 0.0993620232 0.0813610908 0.1385603696 0.0198105302 0.3010460000 249861786 0 1784770560 0.0357181691 0.0181397200 -0.0184957199 250 1305031237.8430309296 0.1133133546 0.0814888998 0.1385603696 0.0198259879 0.3066270000 250112076 0 1786859520 0.0369634815 0.0326649994 -0.0363464281 251 1305031237.8754220009 0.0987845808 0.0815578069 0.1385603696 0.0199931978 0.3151420000 250347650 0 1783549952 0.0369286984 0.0174530726 -0.0153625617 252 1305031237.9077839851 0.0983595476 0.0816244805 0.1385603696 0.0200037978 0.3288980000 250601440 0 1785303040 0.0355940051 0.0156126413 -0.0178748034 253 1305031237.9441869259 0.1138379499 0.0817518065 0.1385603696 0.0200519789 0.3082730000 250834126 0 1786773504 0.0371272415 0.0277336165 -0.0389181748 254 1305031237.9738099575 0.1109225452 0.0818666519 0.1385603696 0.0200257193 0.3223880000 251076180 0 1784057856 0.0354154482 0.0322892182 -0.0324551463 255 1305031238.0069320202 0.1139305159 0.0819923925 0.1385603696 0.0199916501 0.3368020000 251325438 0 1785974784 0.0354134850 0.0293230824 -0.0360404588 256 1305031238.0431399345 0.1092274040 0.0820987793 0.1385603696 0.0202061334 0.3511290000 251582928 0 1784672256 0.0300070308 0.0382695422 -0.0284101143 257 1305031238.0740320683 0.1059432402 0.0821915593 0.1385603696 0.0202619518 0.3730040000 251936042 0 1786785792 0.0205099694 0.0518045425 -0.0232902486 258 1305031238.1065878868 0.0999731421 0.0822604802 0.1385603696 0.0202882647 0.3749460000 251953560 0 1784000512 0.0167366993 0.0527336821 -0.0151625276 259 1305031238.1433279514 0.0929202586 0.0823016376 0.1385603696 0.0203886771 0.3750150000 251959974 0 1785630720 0.0138690555 0.0487585962 -0.0043979175 260 1305031238.1723001003 0.0920666456 0.0823391953 0.1385603696 0.0203676977 0.3739410000 252123440 0 1784135680 -0.0004926492 0.0672496334 -0.0027715154 261 1305031238.2054259777 0.0802308396 0.0823311174 0.1385603696 0.0203384823 0.3887610000 255910549 0 1782153216 -0.0002227286 0.0415765420 0.0020178407 262 1305031238.2401471138 0.0771557763 0.0823113641 0.1385603696 0.0203202986 0.3138860000 260958727 0 1782804480 -0.0054297266 0.0428592004 0.0047562686 263 1305031238.2725269794 0.0785630494 0.0822971120 0.1385603696 0.0202957377 0.2202810000 259649122 0 1782026240 -0.0037354028 0.0404078364 0.0064375116 264 1305031238.3060529232 0.0781186819 0.0822812846 0.1385603696 0.0204738551 0.3659060000 261390631 0 1783910400 -0.0086057326 0.0524526611 0.0107498644 265 1305031238.3425960541 0.0742586404 0.0822510105 0.1385603696 0.0205136240 0.2256530000 259270096 0 1785618432 -0.0089622792 0.0401788466 0.0146838073 266 1305031238.3741040230 0.0756795928 0.0822263059 0.1385603696 0.0206161890 0.2203310000 259146191 0 1784299520 -0.0161228925 0.0414433889 0.0119596375 267 1305031238.4060359001 0.0756742954 0.0822017665 0.1385603696 0.0205787542 0.5749160000 259059476 0 1776668672 -0.0172262471 0.0473167524 0.0146228271 268 1305031238.4434239864 0.0712047741 0.0821607330 0.1385603696 0.0205442077 0.2821850000 251877284 0 1777885184 -0.0194063149 0.0400189720 0.0214244220 269 1305031238.4740819931 0.0681416169 0.0821086173 0.1385603696 0.0205087221 0.1972510000 251879126 0 1778221056 -0.0214225240 0.0392385982 0.0264131334 270 1305031238.5058109760 0.0704964250 0.0820656092 0.1385603696 0.0205493830 0.2403020000 251881152 0 1780326400 -0.0240526572 0.0323415622 0.0257642269 271 1305031238.5432639122 0.0721519291 0.0820290273 0.1385603696 0.0205300611 0.2082540000 251883526 0 1781993472 -0.0272672027 0.0263504293 0.0273071919 272 1305031238.5741839409 0.0693378150 0.0819823685 0.1385603696 0.0205012718 0.2104230000 251885448 0 1783754752 -0.0315951109 0.0315788426 0.0287109222 273 1305031238.6058249474 0.0680475682 0.0819313253 0.1385603696 0.0204657996 0.2041380000 251887594 0 1785536512 -0.0323959813 0.0320200399 0.0321197473 274 1305031238.6427590847 0.0680367127 0.0818806150 0.1385603696 0.0204358607 0.2051990000 251889608 0 1784393728 -0.0302729718 0.0295575894 0.0367882848 275 1305031238.6738131046 0.0684890300 0.0818319183 0.1385603696 0.0204094914 0.2090910000 251891294 0 1783513088 -0.0306962803 0.0286494158 0.0409000926 276 1305031238.7051889896 0.0660550892 0.0817747559 0.1385603696 0.0203759306 0.1962160000 251893380 0 1785298944 -0.0328174829 0.0319888070 0.0439075865 277 1305031238.7413070202 0.0760576129 0.0817541164 0.1385603696 0.0204873226 0.1897740000 251895510 0 1784426496 -0.0286334045 0.0122798979 0.0546483770 278 1305031238.7717959881 0.0752300397 0.0817306485 0.1385603696 0.0204574181 0.1895020000 251897620 0 1780314112 -0.0289910026 0.0129487226 0.0595840067 279 1305031238.8070189953 0.0762013271 0.0817108301 0.1385603696 0.0204404147 0.1923110000 251899634 0 1778810880 -0.0336545222 0.0138316145 0.0598746873 280 1305031238.8429400921 0.0742286518 0.0816841081 0.1385603696 0.0204051847 0.1868950000 251901664 0 1780084736 -0.0353126079 0.0159937274 0.0634203032 281 1305031238.8737230301 0.0696392134 0.0816412437 0.1385603696 0.0203700534 0.1864380000 251903974 0 1782235136 -0.0373821072 0.0226514563 0.0644600093 282 1305031238.9061720371 0.0677918494 0.0815921323 0.1385603696 0.0203381124 0.1852470000 251905964 0 1783754752 -0.0378268249 0.0255845282 0.0653895289 283 1305031238.9427859783 0.0705012232 0.0815529419 0.1385603696 0.0203026718 0.1805410000 251908086 0 1785516032 -0.0376423746 0.0241506472 0.0659229532 284 1305031238.9723079205 0.0655273348 0.0814965137 0.1385603696 0.0202685262 0.2190430000 252445640 0 1784410112 -0.0429796167 0.0305245705 0.0641355589 285 1305031239.0104830265 0.0689702258 0.0814525618 0.1385603696 0.0202647486 0.5043900000 252425538 0 1780756480 -0.0440159068 0.0279630329 0.0645458624 286 1305031239.0408790112 0.0673295185 0.0814031805 0.1385603696 0.0202328032 0.4303800000 252428532 0 1782423552 -0.0443817973 0.0300158113 0.0667044669 287 1305031239.0746610165 0.0623461083 0.0813367796 0.1385603696 0.0202074036 0.4175810000 252430198 0 1784123392 -0.0470527634 0.0369019024 0.0651764572 288 1305031239.1109058857 0.0620204881 0.0812697091 0.1385603696 0.0201767846 0.4293670000 256022351 0 1786601472 -0.0471484400 0.0376682281 0.0648095086 289 1305031239.1417789459 0.0588165931 0.0811920167 0.1385603696 0.0201449750 0.4002320000 259631498 0 1784811520 -0.0481059849 0.0416378379 0.0629478768 290 1305031239.1757500172 0.0557482205 0.0811042794 0.1385603696 0.0201127828 0.3178290000 259303911 0 1783934976 -0.0481875539 0.0449213013 0.0619851798 291 1305031239.2096450329 0.0578862838 0.0810244925 0.1385603696 0.0200796715 0.3065970000 259488642 0 1785876480 -0.0452446900 0.0421818346 0.0620004795 292 1305031239.2417099476 0.0583152920 0.0809467213 0.1385603696 0.0200589635 0.5343770000 259018862 0 1778798592 -0.0438833162 0.0405561626 0.0623407364 293 1305031239.2738199234 0.0571186915 0.0808653969 0.1385603696 0.0200454208 0.2447820000 252439718 0 1776431104 -0.0431155488 0.0416096710 0.0604509264 294 1305031239.3101770878 0.0568425581 0.0807836866 0.1385603696 0.0200122359 0.1844840000 252442040 0 1776807936 -0.0416427478 0.0416596681 0.0593024828 295 1305031239.3419699669 0.0571651645 0.0807036238 0.1385603696 0.0199787067 0.2035170000 252444342 0 1777750016 -0.0409946218 0.0405567288 0.0580097325 296 1305031239.3750240803 0.0569681264 0.0806234363 0.1385603696 0.0199634334 0.1973090000 252446208 0 1780211712 -0.0404379740 0.0404578894 0.0556952953 297 1305031239.4106309414 0.0586523004 0.0805494594 0.1385603696 0.0199358197 0.2042690000 252448814 0 1782095872 -0.0369460024 0.0385106876 0.0550701953 298 1305031239.4415419102 0.0602694117 0.0804814056 0.1385603696 0.0199121697 0.2339510000 252907992 0 1783746560 -0.0356916338 0.0352698080 0.0544193387 299 1305031239.4733181000 0.0620021075 0.0804196019 0.1385603696 0.0198861988 0.4953170000 252874810 0 1785634816 -0.0327249989 0.0327583104 0.0536785722 300 1305031239.5097389221 0.0614528544 0.0803563794 0.1385603696 0.0198550868 0.4530560000 252876696 0 1783873536 -0.0322002620 0.0329764858 0.0517516211 301 1305031239.5438020229 0.0738121271 0.0803346377 0.1385603696 0.0199167080 0.4491850000 252878898 0 1783291904 -0.0308327600 0.0137126278 0.0521022230 302 1305031239.5761160851 0.0803173333 0.0803345804 0.1385603696 0.0198863331 0.4580640000 254698248 0 1784922112 -0.0299045928 0.0065616868 0.0473493710 303 1305031239.6111609936 0.0816959292 0.0803390733 0.1385603696 0.0198554333 0.4865230000 260165613 0 1786155008 -0.0285148472 0.0039119325 0.0461551771 304 1305031239.6414220333 0.0822693929 0.0803454230 0.1385603696 0.0198232987 0.2828130000 261409372 0 1784053760 -0.0285204649 0.0022813238 0.0436716527 305 1305031239.6710560322 0.0794853792 0.0803426032 0.1385603696 0.0198112902 0.3520620000 260776002 0 1786122240 -0.0283956286 0.0075922110 0.0380379446 306 1305031239.7075550556 0.0807642490 0.0803439812 0.1385603696 0.0198372792 0.2226280000 260373495 0 1785380864 -0.0257311556 0.0036238350 0.0373016000 307 1305031239.7417550087 0.0805028304 0.0803444986 0.1385603696 0.0198105568 0.6128130000 260304528 0 1778888704 -0.0250147004 0.0036227428 0.0335244499 308 1305031239.7712600231 0.0846100226 0.0803583477 0.1385603696 0.0197947745 0.2414320000 252888580 0 1779191808 -0.0215750206 -0.0033497778 0.0319840536 309 1305031239.8060870171 0.0813462883 0.0803615449 0.1385603696 0.0198647207 0.2232190000 253328726 0 1781092352 -0.0200391188 -0.0022688648 0.0296206288 310 1305031239.8392889500 0.0828967169 0.0803697229 0.1385603696 0.0198437347 0.5144830000 253303372 0 1779871744 -0.0178341232 0.0005192109 0.0214836970 311 1305031239.8744299412 0.0807838216 0.0803710544 0.1385603696 0.0198291133 0.4741640000 253305214 0 1781444608 -0.0167802479 0.0015717614 0.0200241283 312 1305031239.9090619087 0.0818397403 0.0803757617 0.1385603696 0.0198311302 0.4622530000 253307552 0 1783529472 -0.0097507127 0.0006305394 0.0213406570 313 1305031239.9403729439 0.0850823596 0.0803907988 0.1385603696 0.0198083097 0.4547520000 253457898 0 1785110528 -0.0060614473 0.0001079091 0.0162212662 314 1305031239.9710669518 0.0840621293 0.0804024909 0.1385603696 0.0198160882 0.4578400000 258610055 0 1781932032 -0.0026304936 0.0019732602 0.0169156548 315 1305031240.0088651180 0.0888575763 0.0804293324 0.1385603696 0.0198755217 0.3299270000 264382918 0 1781948416 0.0002812822 -0.0043608807 0.0107356980 316 1305031240.0396599770 0.0868264809 0.0804495766 0.1385603696 0.0198612988 0.2345880000 263025048 0 1780994048 0.0002320628 -0.0028620709 0.0092148557 317 1305031240.0711870193 0.0884389132 0.0804747795 0.1385603696 0.0198301422 0.4330130000 262894190 0 1782558720 0.0017140219 -0.0056919088 0.0062897913 318 1305031240.1093459129 0.0938301459 0.0805167775 0.1385603696 0.0198464142 0.2258260000 264842460 0 1785036800 0.0097875511 -0.0108943786 0.0046731825 319 1305031240.1435019970 0.0935932621 0.0805577697 0.1385603696 0.0198846860 0.1898990000 262716474 0 1786826752 0.0151387379 -0.0058538471 0.0050347019 320 1305031240.1775770187 0.0948321670 0.0806023772 0.1385603696 0.0198766977 0.5034230000 262516030 0 1782362112 0.0148062408 0.0041981745 -0.0044255382 321 1305031240.2093310356 0.0993136764 0.0806606678 0.1385603696 0.0199432254 0.3569010000 253345287 0 1775583232 0.0239018146 -0.0135191949 0.0036914053 322 1305031240.2410049438 0.1026053354 0.0807288189 0.1385603696 0.0199513427 0.1771180000 253321260 0 1775763456 0.0260727480 -0.0055148480 -0.0078952760 323 1305031240.2774341106 0.1003396735 0.0807895337 0.1385603696 0.0199453750 0.1766330000 253615510 0 1777414144 0.0271125901 0.0030220412 -0.0084660864 324 1305031240.3089289665 0.1052390337 0.0808649951 0.1385603696 0.0199240541 0.3441330000 253779720 0 1775157248 0.0308857188 0.0004532179 -0.0153337400 325 1305031240.3422729969 0.1016080007 0.0809288197 0.1385603696 0.0199261877 0.2969660000 254092266 0 1776934912 0.0309917107 0.0058880346 -0.0112527572 326 1305031240.3774259090 0.1061790958 0.0810062746 0.1385603696 0.0199494575 0.2729180000 254237732 0 1778827264 0.0360290781 0.0078248410 -0.0158247985 327 1305031240.4091110229 0.1061561555 0.0810831855 0.1385603696 0.0199248619 0.2937200000 254474390 0 1779552256 0.0344676152 0.0094511751 -0.0221447200 328 1305031240.4417860508 0.1074526757 0.0811635803 0.1385603696 0.0198949115 0.2715600000 254626352 0 1782231040 0.0351383463 0.0130007844 -0.0246918574 329 1305031240.4776389599 0.1103832796 0.0812523940 0.1385603696 0.0198666805 0.2789870000 254529446 0 1784045568 0.0364726707 0.0191999488 -0.0290607996 330 1305031240.5084490776 0.1110969186 0.0813428319 0.1385603696 0.0198541662 0.2709430000 254534424 0 1785597952 0.0360875651 0.0189258680 -0.0330288038 331 1305031240.5412700176 0.1119564176 0.0814353201 0.1385603696 0.0198697038 0.2791510000 258236801 0 1785200640 0.0354516432 0.0202080011 -0.0358348489 332 1305031240.5759088993 0.1100012884 0.0815213622 0.1385603696 0.0198445522 0.3079440000 259045976 0 1781805056 0.0341515169 0.0232935734 -0.0322395153 333 1305031240.6101338863 0.1145527437 0.0816205555 0.1385603696 0.0198179421 0.2789250000 254720558 0 1778929664 0.0355086997 0.0218640454 -0.0377093107 334 1305031240.6398229599 0.1115329862 0.0817101137 0.1385603696 0.0198037775 0.2558180000 254866772 0 1780408320 0.0319215730 0.0208759308 -0.0355177373 335 1305031240.6747570038 0.1059966907 0.0817826109 0.1385603696 0.0197779241 0.2702390000 257005053 0 1786294272 0.0307643209 0.0204747878 -0.0260094702 336 1305031240.7079319954 0.1063323691 0.0818556757 0.1385603696 0.0197910764 0.2915660000 256836938 0 1781075968 0.0313285142 0.0165236741 -0.0240993723 337 1305031240.7439579964 0.1043054909 0.0819222923 0.1385603696 0.0197713400 0.3133440000 255083014 0 1781956608 0.0297543854 0.0232042503 -0.0186945312 338 1305031240.7768330574 0.1070686579 0.0819966899 0.1385603696 0.0197507442 0.2905640000 255247336 0 1783365632 0.0298306309 0.0208414495 -0.0222385321 339 1305031240.8096249104 0.1059042811 0.0820672137 0.1385603696 0.0197528404 0.3189420000 255599874 0 1785266176 0.0283972360 0.0222419649 -0.0187905673 340 1305031240.8425960541 0.0966826528 0.0821102003 0.1385603696 0.0197691021 0.3300690000 255796088 0 1784107008 0.0206651539 0.0350433588 -0.0069352277 341 1305031240.8794100285 0.0977309942 0.0821560091 0.1385603696 0.0197511651 0.3276720000 255859855 0 1783894016 0.0198994223 0.0327793434 -0.0082929153 342 1305031240.9084498882 0.0936774313 0.0821896975 0.1385603696 0.0197595252 0.3354110000 255855260 0 1785962496 0.0122727975 0.0421577357 -0.0052227117 343 1305031240.9423189163 0.0897900462 0.0822118559 0.1385603696 0.0197898756 0.3533420000 256093086 0 1785278464 0.0044025797 0.0565408058 0.0031494182 344 1305031240.9779360294 0.0831010044 0.0822144407 0.1385603696 0.0197640166 0.4185760000 258697412 0 1784147968 0.0054552471 0.0423794948 0.0090899197 345 1305031241.0083029270 0.0864848718 0.0822268187 0.1385603696 0.0198622624 0.4244780000 255994222 0 1780133888 -0.0006448096 0.0519733280 0.0030592252 346 1305031241.0401480198 0.0778851584 0.0822142706 0.1385603696 0.0198689004 0.3988160000 256001860 0 1782059008 -0.0030158535 0.0539252721 0.0156080127 347 1305031241.0759329796 0.0755649135 0.0821951082 0.1385603696 0.0198664592 0.3946110000 256171450 0 1783943168 -0.0097047715 0.0452126078 0.0104053076 348 1305031241.1065559387 0.0736227855 0.0821704750 0.1385603696 0.0198469700 0.4206440000 259922859 0 1784635392 -0.0131899556 0.0461375266 0.0128770322 349 1305031241.1400520802 0.0717165619 0.0821405211 0.1385603696 0.0198502414 0.2939800000 263681670 0 1783418880 -0.0127514461 0.0464027822 0.0177635923 350 1305031241.1781818867 0.0707367286 0.0821079389 0.1385603696 0.0198766248 0.3794390000 262618946 0 1782403072 -0.0136121372 0.0489700176 0.0211463273 351 1305031241.2106790543 0.0685470849 0.0820693040 0.1385603696 0.0198512511 0.2424200000 262220261 0 1784115200 -0.0174389202 0.0540867075 0.0235363357 352 1305031241.2393150330 0.0664457232 0.0820249188 0.1385603696 0.0198580111 0.5594670000 262141094 0 1781239808 -0.0186979305 0.0492861345 0.0264310054 353 1305031241.2768468857 0.0649836287 0.0819766432 0.1385603696 0.0198722875 0.2737420000 256008802 0 1775640576 -0.0187413935 0.0443838984 0.0291389376 354 1305031241.3063299656 0.0631278977 0.0819233981 0.1385603696 0.0198461274 0.1940030000 256010492 0 1776435200 -0.0198129360 0.0460966490 0.0319390222 355 1305031241.3424758911 0.0616510287 0.0818662929 0.1385603696 0.0198492709 0.2027200000 256012974 0 1778212864 -0.0220671799 0.0530387722 0.0323732197 356 1305031241.3795149326 0.0649117827 0.0818186678 0.1385603696 0.0199217820 0.2092490000 256014864 0 1779892224 -0.0261066295 0.0421624891 0.0311122872 357 1305031241.4096820354 0.0698431432 0.0817851230 0.1385603696 0.0199192208 0.2067150000 256016498 0 1781252096 -0.0324513763 0.0413998067 0.0261846334 358 1305031241.4455459118 0.0678633451 0.0817462353 0.1385603696 0.0198995566 0.2070490000 256018916 0 1783029760 -0.0345691517 0.0449742973 0.0295229666 359 1305031241.4775071144 0.0667734146 0.0817045283 0.1385603696 0.0201528232 0.2048300000 256020774 0 1784680448 -0.0299862605 0.0361554027 0.0406431854 360 1305031241.5098490715 0.0679228008 0.0816662457 0.1385603696 0.0201428370 0.2051730000 256045157 0 1786441728 -0.0280390158 0.0304531120 0.0473255403 361 1305031241.5477299690 0.0726830661 0.0816413616 0.1385603696 0.0201232799 0.2112480000 256025082 0 1783300096 -0.0261002183 0.0223124065 0.0513415523 362 1305031241.5783948898 0.0704090148 0.0816103330 0.1385603696 0.0201351407 0.2092020000 256088265 0 1785081856 -0.0273088962 0.0278705396 0.0466526859 363 1305031241.6092638969 0.0725752190 0.0815854429 0.1385603696 0.0201415996 0.2113240000 256029050 0 1786458112 -0.0278753042 0.0226660669 0.0475875959 364 1305031241.6475839615 0.0734679997 0.0815631422 0.1385603696 0.0201142490 0.2042510000 256030920 0 1783193600 -0.0288191065 0.0189172346 0.0475710183 365 1305031241.6783659458 0.0694769174 0.0815300292 0.1385603696 0.0201424023 0.2100480000 256081203 0 1784696832 -0.0267980043 0.0264125206 0.0434171595 366 1305031241.7098269463 0.0706661120 0.0815003464 0.1385603696 0.0201210983 0.2092590000 256034708 0 1786204160 -0.0250299554 0.0242665596 0.0432551540 367 1305031241.7471020222 0.0703226328 0.0814698894 0.1385603696 0.0201024566 0.2217640000 256094695 0 1785356288 -0.0257270597 0.0255608708 0.0396148302 368 1305031241.7782680988 0.0691421330 0.0814363901 0.1385603696 0.0200916041 0.2107460000 256061753 0 1784303616 -0.0246800818 0.0253871959 0.0410666876 369 1305031241.8098289967 0.0701639578 0.0814058415 0.1385603696 0.0201029969 0.2123690000 256106855 0 1782538240 -0.0253869798 0.0288471021 0.0347101167 370 1305031241.8464360237 0.0735640451 0.0813846474 0.1385603696 0.0201095242 0.2133180000 256043404 0 1784320000 -0.0262945928 0.0217924118 0.0348570645 371 1305031241.8787989616 0.0734639093 0.0813632977 0.1385603696 0.0202360575 0.2054310000 256045338 0 1785569280 -0.0271798950 0.0252222754 0.0309959836 372 1305031241.9114871025 0.0696179420 0.0813317242 0.1385603696 0.0202581371 0.2131250000 256047364 0 1784066048 -0.0265077651 0.0324126929 0.0306705646 373 1305031241.9477050304 0.0707980245 0.0813034837 0.1385603696 0.0202773285 0.2390610000 256048970 0 1783173120 -0.0267267618 0.0288042594 0.0319572389 374 1305031241.9783430099 0.0679525658 0.0812677861 0.1385603696 0.0204685889 0.2158830000 256051232 0 1784958976 -0.0279379040 0.0333321318 0.0317686647 375 1305031242.0105700493 0.0671350583 0.0812300988 0.1385603696 0.0205692007 0.2086320000 256052934 0 1786458112 -0.0250357613 0.0358336717 0.0336490683 376 1305031242.0463600159 0.0687460676 0.0811968966 0.1385603696 0.0206588654 0.2103780000 256055252 0 1783427072 -0.0245707408 0.0326186866 0.0352437682 377 1305031242.0795490742 0.0696990415 0.0811663983 0.1385603696 0.0208124779 0.2036740000 256057470 0 1785208832 -0.0256106518 0.0306206308 0.0354981273 378 1305031242.1105840206 0.0744308904 0.0811485795 0.1385603696 0.0209494040 0.2053930000 256059380 0 1786728448 -0.0258484352 0.0262850448 0.0320521742 379 1305031242.1466050148 0.0748140812 0.0811318658 0.1385603696 0.0211563258 0.2074860000 256061378 0 1782050816 -0.0284086876 0.0248185713 0.0313776135 380 1305031242.1797080040 0.0738620237 0.0811127346 0.1385603696 0.0213213017 0.2043680000 256063320 0 1783955456 -0.0326758623 0.0268184952 0.0282359868 381 1305031242.2087249756 0.0765299425 0.0811007063 0.1385603696 0.0213954814 0.2035590000 256064974 0 1785425920 -0.0370288640 0.0212317351 0.0255627166 382 1305031242.2478089333 0.0798938498 0.0810975470 0.1385603696 0.0214885992 0.2063240000 256067372 0 1786699776 -0.0405855998 0.0146418838 0.0234597847 383 1305031242.2794981003 0.0795039907 0.0810933863 0.1385603696 0.0215599145 0.2051120000 256069826 0 1783152640 -0.0382734351 0.0120797865 0.0265512541 384 1305031242.3097639084 0.0800816193 0.0810907515 0.1385603696 0.0216232726 0.2035690000 256071112 0 1784971264 -0.0384339951 0.0101536233 0.0256573968 385 1305031242.3471269608 0.0846954212 0.0811001142 0.1385603696 0.0217758384 0.2057070000 256073586 0 1786458112 -0.0368413925 0.0038299996 0.0233638287 386 1305031242.3784790039 0.0814493895 0.0811010191 0.1385603696 0.0219501265 0.2120510000 256075244 0 1782919168 -0.0376508720 0.0080903051 0.0220433921 387 1305031242.4109969139 0.0845796540 0.0811100078 0.1385603696 0.0220185802 0.2110920000 256077346 0 1784717312 -0.0373417214 0.0023522107 0.0208019204 388 1305031242.4470989704 0.0851499811 0.0811204201 0.1385603696 0.0222591846 0.2099090000 256079244 0 1786077184 -0.0427449532 0.0006915042 0.0161491521 389 1305031242.4776470661 0.0859147012 0.0811327448 0.1385603696 0.0223786285 0.2163430000 256082022 0 1784823808 -0.0394804999 0.0001082008 0.0153494384 390 1305031242.5097260475 0.0887003392 0.0811521488 0.1385603696 0.0227186542 0.2048780000 256083472 0 1786859520 -0.0448971428 -0.0059919488 0.0117087681 391 1305031242.5485460758 0.0840245038 0.0811594950 0.1385603696 0.0233069668 0.2400710000 256551358 0 1783152640 -0.0448344760 0.0032821519 0.0097052250 392 1305031242.5748429298 0.0881108567 0.0811772281 0.1385603696 0.0234845928 0.5381180000 256538452 0 1785270272 -0.0431709886 0.0026813170 0.0054835938 393 1305031242.6061151028 0.0891959965 0.0811976321 0.1385603696 0.0236054763 0.4877820000 256540818 0 1786585088 -0.0415947437 0.0005553851 0.0059961062 394 1305031242.6438109875 0.0914535075 0.0812236622 0.1385603696 0.0239240871 0.4710420000 256542672 0 1783214080 -0.0454623252 0.0010914073 0.0011351593 395 1305031242.6752018929 0.0879840106 0.0812407770 0.1385603696 0.0242661653 0.4540320000 256713046 0 1785004032 -0.0508927330 0.0019183825 0.0029792953 396 1305031242.7139821053 0.0908861533 0.0812651340 0.1385603696 0.0247289608 0.4618970000 261430627 0 1785131008 -0.0508860238 0.0031341480 0.0003461093 397 1305031242.7452580929 0.0974500179 0.0813059020 0.1385603696 0.0248401245 0.3840890000 266266673 0 1786662912 -0.0421696454 0.0014830729 0.0003933869 398 1305031242.7775399685 0.0949766487 0.0813402506 0.1385603696 0.0250679296 0.2725880000 265085310 0 1783537664 -0.0508156568 0.0026896521 -0.0008991659 399 1305031242.8140709400 0.0991695002 0.0813849354 0.1385603696 0.0253089998 0.3327670000 266072534 0 1785675776 -0.0441652983 0.0064631375 -0.0001755580 400 1305031242.8443179131 0.1028299779 0.0814385481 0.1385603696 0.0253819733 0.2450030000 264832255 0 1784987648 -0.0459687412 0.0070237052 -0.0038217008 401 1305031242.8740880489 0.1057165787 0.0814990918 0.1385603696 0.0254646692 0.6097440000 264763208 0 1777352704 -0.0566049330 0.0017534150 -0.0080509316 402 1305031242.9137070179 0.1096313596 0.0815690725 0.1385603696 0.0256311558 0.3037150000 256996496 0 1778380800 -0.0549741164 0.0035882937 -0.0091847293 403 1305031242.9444379807 0.1066125259 0.0816312151 0.1385603696 0.0258594015 0.5257700000 256989686 0 1776422912 -0.0616178960 0.0072857277 -0.0083504003 404 1305031242.9760620594 0.1092062071 0.0816994700 0.1385603696 0.0259344292 0.4799680000 256995860 0 1777197056 -0.0581020787 0.0096044708 -0.0085115638 405 1305031243.0141661167 0.1073451638 0.0817627927 0.1385603696 0.0260200854 0.4803450000 256993994 0 1778581504 -0.0619303025 0.0117382500 -0.0061425008 406 1305031243.0469100475 0.1055075750 0.0818212774 0.1385603696 0.0260382517 0.4590760000 257161352 0 1780801536 -0.0642835796 0.0152830854 -0.0057341717 407 1305031243.0780448914 0.1048338041 0.0818778193 0.1385603696 0.0260348349 0.4845550000 262752973 0 1784893440 -0.0667879209 0.0166418795 -0.0059647113 408 1305031243.1136150360 0.1010386273 0.0819247820 0.1385603696 0.0260566025 0.2981190000 267547768 0 1784344576 -0.0691807419 0.0213491917 -0.0051362682 409 1305031243.1458160877 0.0993580669 0.0819674062 0.1385603696 0.0260252254 0.3569990000 266425462 0 1785995264 -0.0664330646 0.0238146856 -0.0032236837 410 1305031243.1780760288 0.0958855152 0.0820013528 0.1385603696 0.0260304658 0.3366200000 267429280 0 1785634816 -0.0702627003 0.0244511068 -0.0028068721 411 1305031243.2136580944 0.0970015973 0.0820378497 0.1385603696 0.0260926914 0.2501220000 266030010 0 1784557568 -0.0611848198 0.0240840204 -0.0008082502 412 1305031243.2455608845 0.1006638631 0.0820830585 0.1385603696 0.0264542263 0.6330530000 265927042 0 1773301760 -0.0669091046 0.0175761022 -0.0061915740 413 1305031243.2781798840 0.0979494974 0.0821214760 0.1385603696 0.0265626119 0.3358060000 257443478 0 1774981120 -0.0794516280 0.0138501432 -0.0073795766 414 1305031243.3142709732 0.1029520035 0.0821717913 0.1385603696 0.0266762121 0.5155340000 257438832 0 1771352064 -0.0707811266 0.0126576535 -0.0094136633 415 1305031243.3460359573 0.1032868996 0.0822226711 0.1385603696 0.0270777698 0.4894670000 257440918 0 1773383680 -0.0731812418 0.0109135266 -0.0089785494 416 1305031243.3789350986 0.1023810953 0.0822711288 0.1385603696 0.0271485829 0.4768110000 257443128 0 1774669824 -0.0732241422 0.0111461151 -0.0061620437 417 1305031243.4139740467 0.1006218493 0.0823151354 0.1385603696 0.0273162188 0.4946000000 257617930 0 1776726016 -0.0724014714 0.0171810370 -0.0046290867 418 1305031243.4470911026 0.1028860286 0.0823643480 0.1385603696 0.0275695046 0.4933510000 262538923 0 1783201792 -0.0748963058 0.0152213201 -0.0045242347 419 1305031243.4780371189 0.1014412791 0.0824098777 0.1385603696 0.0276347990 0.4272140000 267932022 0 1783787520 -0.0739601925 0.0203034952 -0.0021024644 420 1305031243.5154008865 0.1027385071 0.0824582792 0.1385603696 0.0278490210 0.2832230000 266743592 0 1782579200 -0.0700392723 0.0232782774 0.0006492399 421 1305031243.5459430218 0.1037777513 0.0825089193 0.1385603696 0.0279373164 0.3908250000 267714930 0 1785081856 -0.0746093392 0.0234865490 -0.0001680814 422 1305031243.5779840946 0.1059521735 0.0825644720 0.1385603696 0.0279783220 0.2716920000 266431110 0 1786662912 -0.0774725080 0.0248248000 -0.0026209578 423 1305031243.6140549183 0.1081408784 0.0826249363 0.1385603696 0.0283416817 0.6670550000 266300584 0 1773199360 -0.0739131719 0.0269657411 -0.0026444085 424 1305031243.6461870670 0.1126782000 0.0826958167 0.1385603696 0.0287453580 0.3209850000 257848256 0 1774874624 -0.0743207633 0.0205783397 -0.0044657104 425 1305031243.6782801151 0.1081489399 0.0827557064 0.1385603696 0.0287850056 0.5236440000 257845186 0 1771663360 -0.0841149092 0.0235422198 -0.0050039627 426 1305031243.7142961025 0.1072515771 0.0828132084 0.1385603696 0.0293065515 0.4954180000 257846460 0 1773080576 -0.0670216084 0.0293237101 -0.0000898149 427 1305031243.7473781109 0.1096424162 0.0828760403 0.1385603696 0.0296746829 0.4874710000 257848686 0 1775468544 -0.0633016378 0.0210617445 0.0018959232 428 1305031243.7790360451 0.1025208309 0.0829219393 0.1385603696 0.0298758514 0.4642320000 258026288 0 1777106944 -0.0775905997 0.0260826908 -0.0015975386 429 1305031243.8141930103 0.0947086290 0.0829494141 0.1385603696 0.0304841396 0.4485630000 262547369 0 1780178944 -0.0726772696 0.0335185379 0.0020262394 430 1305031243.8462920189 0.1003020853 0.0829897692 0.1385603696 0.0309655305 0.4374460000 265242003 0 1782730752 -0.0607863590 0.0224486068 0.0039051566 431 1305031243.8788089752 0.0974114686 0.0830232302 0.1385603696 0.0311304484 0.2645080000 269265482 0 1784483840 -0.0570518002 0.0256773531 0.0047036912 432 1305031243.9140000343 0.0912851244 0.0830423550 0.1385603696 0.0314783252 0.3977370000 267563300 0 1783525376 -0.0532778278 0.0246301629 0.0111881755 433 1305031243.9470779896 0.0929920077 0.0830653334 0.1385603696 0.0316736834 0.2945360000 268785330 0 1785761792 -0.0457969755 0.0195078626 0.0137759373 434 1305031243.9816520214 0.0890540034 0.0830791321 0.1385603696 0.0318095644 0.2424450000 267198644 0 1785118720 -0.0411111861 0.0228955969 0.0176716689 435 1305031244.0112700462 0.0867362842 0.0830875394 0.1385603696 0.0319054261 0.6179220000 267084232 0 1784606720 -0.0357468538 0.0241781026 0.0220610108 436 1305031244.0438230038 0.0840663910 0.0830897845 0.1385603696 0.0319220327 0.4039110000 258211292 0 1786228736 -0.0352306366 0.0337541029 0.0204470716 437 1305031244.0818090439 0.0817735642 0.0830867725 0.1385603696 0.0319682275 0.5411000000 258203638 0 1771630592 -0.0353998207 0.0384557433 0.0211430341 438 1305031244.1127901077 0.0835813731 0.0830879017 0.1385603696 0.0320541545 0.4833310000 258205236 0 1773506560 -0.0330902338 0.0372873098 0.0217556134 439 1305031244.1484949589 0.0895699486 0.0831026672 0.1385603696 0.0320611796 0.4752490000 258206902 0 1774645248 -0.0326600969 0.0423997790 0.0133073535 440 1305031244.1824309826 0.0791815519 0.0830937556 0.1385603696 0.0321725111 0.4450600000 258396920 0 1776922624 -0.0324855261 0.0473541170 0.0246910602 441 1305031244.2124009132 0.0786252990 0.0830836230 0.1385603696 0.0322878592 0.4816330000 263462281 0 1785245696 -0.0303770918 0.0480478853 0.0278147310 442 1305031244.2473471165 0.0727374628 0.0830602154 0.1385603696 0.0324580452 0.4182110000 270961343 0 1784090624 -0.0322938226 0.0537536256 0.0312148556 443 1305031244.2831470966 0.0710849091 0.0830331831 0.1385603696 0.0326191756 0.2588600000 268395936 0 1783025664 -0.0294820555 0.0576730967 0.0321365818 444 1305031244.3137950897 0.0672922805 0.0829977307 0.1385603696 0.0327631612 0.4556770000 268408672 0 1784770560 -0.0263525452 0.0629720613 0.0355455428 445 1305031244.3459599018 0.0641992390 0.0829554869 0.1385603696 0.0329928691 0.2558330000 271356778 0 1784737792 -0.0226538908 0.0671328008 0.0399267301 446 1305031244.3808560371 0.0648879856 0.0829149768 0.1385603696 0.0331648907 0.5785210000 267973016 0 1782681600 -0.0211189371 0.0712988228 0.0370959602 447 1305031244.4130189419 0.0585268065 0.0828604171 0.1385603696 0.0333855250 0.5259880000 258567010 0 1770729472 -0.0218920503 0.0761627406 0.0435744897 448 1305031244.4451670647 0.0559466891 0.0828003418 0.1385603696 0.0334540823 0.5891860000 258571316 0 1772634112 -0.0228654183 0.0833784044 0.0432808176 449 1305031244.4806590080 0.0572898090 0.0827435255 0.1385603696 0.0335352240 0.4885310000 258573586 0 1774088192 -0.0243669003 0.0871586427 0.0401087329 450 1305031244.5142281055 0.0614387132 0.0826961815 0.1385603696 0.0336404207 0.4855340000 258575676 0 1776295936 -0.0239473432 0.0878355280 0.0386091992 451 1305031244.5462141037 0.0620732419 0.0826504543 0.1385603696 0.0336420780 0.4823130000 258750594 0 1778188288 -0.0235756785 0.0910314620 0.0391272232 452 1305031244.5808050632 0.0607947931 0.0826021011 0.1385603696 0.0336891846 0.4811810000 263927215 0 1785831424 -0.0264493227 0.0936248899 0.0404782519 453 1305031244.6132769585 0.0620592386 0.0825567526 0.1385603696 0.0337808283 0.4383500000 268052629 0 1785204736 -0.0267304126 0.0948284417 0.0412664227 454 1305031244.6428399086 0.0610293560 0.0825093354 0.1385603696 0.0337702812 0.2681080000 272211380 0 1782501376 -0.0281102676 0.0979546383 0.0416551083 455 1305031244.6806099415 0.0626962036 0.0824657901 0.1385603696 0.0338387211 0.4686890000 269312104 0 1784664064 -0.0322616398 0.1002588421 0.0401531979 456 1305031244.7152500153 0.0653971881 0.0824283589 0.1385603696 0.0338799760 0.2633130000 272355014 0 1784733696 -0.0316252746 0.1032029465 0.0381198525 457 1305031244.7458879948 0.0643464401 0.0823887924 0.1385603696 0.0340807432 0.2539040000 268886060 0 1786388480 -0.0303795803 0.1027167886 0.0420718230 458 1305031244.7818510532 0.0698660016 0.0823614500 0.1385603696 0.0341563194 0.5562650000 268832244 0 1775742976 -0.0286271386 0.1028628051 0.0370997265 459 1305031244.8140940666 0.0638619959 0.0823211462 0.1385603696 0.0350353438 0.5324010000 258931462 0 1774047232 -0.0304007493 0.1036479920 0.0474750884 460 1305031244.8418219090 0.0595261008 0.0822715918 0.1385603696 0.0350216346 0.5305340000 258935600 0 1770741760 -0.0280469488 0.1058311015 0.0522935465 461 1305031244.8818008900 0.0576141663 0.0822181050 0.1385603696 0.0349905439 0.5129530000 258936746 0 1772634112 -0.0287496131 0.1101825386 0.0503137112 462 1305031244.9149079323 0.0572949089 0.0821641586 0.1385603696 0.0349743722 0.5121040000 258938732 0 1774587904 -0.0263259597 0.1115107760 0.0502738543 463 1305031244.9458680153 0.0562503785 0.0821081894 0.1385603696 0.0349372542 0.4775800000 259128378 0 1776238592 -0.0240402184 0.1139096245 0.0514086634 464 1305031244.9818000793 0.0558512844 0.0820516012 0.1385603696 0.0349558720 0.4924190000 263893815 0 1781596160 -0.0270092823 0.1175342426 0.0515832268 465 1305031245.0140550137 0.0504232459 0.0819835832 0.1385603696 0.0349233746 0.4791420000 268244441 0 1783439360 -0.0255399980 0.1172825992 0.0599605963 466 1305031245.0464398861 0.0568864495 0.0819297267 0.1385603696 0.0348910087 0.2665330000 272329040 0 1782902784 -0.0233037844 0.1188417003 0.0520128459 467 1305031245.0817689896 0.0493689440 0.0818600034 0.1385603696 0.0348810441 0.4534680000 269512842 0 1784631296 -0.0263250135 0.1194619387 0.0616499856 468 1305031245.1143150330 0.0518497154 0.0817958789 0.1385603696 0.0348852685 0.2940960000 272142792 0 1784852480 -0.0241602417 0.1161842123 0.0626524091 469 1305031245.1457099915 0.0520115271 0.0817323728 0.1385603696 0.0348717270 0.2491870000 269152053 0 1785495552 -0.0291646123 0.1152282506 0.0613001026 470 1305031245.1818709373 0.0523799509 0.0816699208 0.1385603696 0.0348821494 0.6479270000 268771562 0 1773518848 -0.0297023132 0.1125785783 0.0606418252 471 1305031245.2140939236 0.0501796231 0.0816030624 0.1385603696 0.0350046403 0.4505380000 259314438 0 1768325120 -0.0313749462 0.1097984761 0.0616670921 472 1305031245.2487950325 0.0528503172 0.0815421456 0.1385603696 0.0352793248 0.4833270000 259315788 0 1770311680 -0.0357075483 0.1093757451 0.0541587472 473 1305031245.2807950974 0.0575647056 0.0814914533 0.1385603696 0.0353646055 0.4690500000 259317950 0 1771618304 -0.0388753936 0.1044451073 0.0475268662 474 1305031245.3143179417 0.0514881164 0.0814281552 0.1385603696 0.0355583206 0.4626660000 259320336 0 1774149632 -0.0378690660 0.0985722616 0.0537967160 475 1305031245.3491809368 0.0577476397 0.0813783015 0.1385603696 0.0358037640 0.4728270000 259486102 0 1775730688 -0.0365170613 0.1002889648 0.0409813225 476 1305031245.3806860447 0.0532332063 0.0813191731 0.1385603696 0.0360787988 0.4972460000 264840611 0 1784528896 -0.0414662138 0.0951388925 0.0420453995 477 1305031245.4133110046 0.0572924241 0.0812688026 0.1385603696 0.0362995841 0.4308470000 272063607 0 1783812096 -0.0442358553 0.0935422033 0.0321034044 478 1305031245.4489970207 0.0669837892 0.0812389176 0.1385603696 0.0362893927 0.2494120000 270087967 0 1780420608 -0.0360298976 0.0803074837 0.0263755005 479 1305031245.4846711159 0.0662890300 0.0812077070 0.1385603696 0.0365800803 0.4389390000 270018832 0 1782304768 -0.0358819440 0.0790138021 0.0235964768 480 1305031245.5124320984 0.0683444440 0.0811809085 0.1385603696 0.0366744574 0.2732760000 273019428 0 1784123392 -0.0363467187 0.0789777637 0.0191186145 481 1305031245.5481460094 0.0689935163 0.0811555709 0.1385603696 0.0368572244 0.2494210000 269597956 0 1785495552 -0.0368158966 0.0780276209 0.0163348019 482 1305031245.5786890984 0.0736368895 0.0811399720 0.1385603696 0.0368642982 0.6382940000 269284840 0 1779863552 -0.0327004530 0.0752843469 0.0129132494 483 1305031245.6104750633 0.0771649331 0.0811317421 0.1385603696 0.0369677127 0.4649070000 259371399 0 1781788672 -0.0342042744 0.0699079931 0.0077414438 484 1305031245.6494629383 0.0781070217 0.0811254927 0.1385603696 0.0371759468 0.2747340000 259707976 0 1781809152 -0.0349621922 0.0707239509 0.0047720890 485 1305031245.6802349091 0.0788779035 0.0811208584 0.1385603696 0.0372119690 0.5111810000 259676294 0 1775759360 -0.0355438702 0.0741761923 0.0030381621 486 1305031245.7110319138 0.0808869749 0.0811203772 0.1385603696 0.0372305764 0.4887230000 259676788 0 1777537024 -0.0351681784 0.0700751320 0.0015519431 487 1305031245.7497749329 0.0826462135 0.0811235103 0.1385603696 0.0373141017 0.4875250000 259679262 0 1779187712 -0.0332135297 0.0716203526 0.0010781890 488 1305031245.7818500996 0.0858498067 0.0811331954 0.1385603696 0.0373538765 0.5091920000 264067479 0 1780953088 -0.0266321879 0.0702654868 0.0035431241 489 1305031245.8135690689 0.0870024636 0.0811451980 0.1385603696 0.0375018601 0.4853060000 265453127 0 1783201792 -0.0270478111 0.0733881965 0.0020801981 490 1305031245.8491089344 0.0929718316 0.0811693340 0.1385603696 0.0375304974 0.3147930000 272588104 0 1783914496 -0.0280308444 0.0642688572 -0.0046059126 491 1305031245.8820281029 0.0907038450 0.0811887525 0.1385603696 0.0376013502 0.3264600000 269934058 0 1783128064 -0.0337269492 0.0658780113 -0.0068437583 492 1305031245.9126079082 0.0896985903 0.0812060489 0.1385603696 0.0376237123 0.3505080000 272558228 0 1785151488 -0.0370597467 0.0650925860 -0.0075711836 493 1305031245.9458959103 0.0923344195 0.0812286217 0.1385603696 0.0376968972 0.2617620000 269583702 0 1786802176 -0.0442481935 0.0608699173 -0.0146648968 494 1305031245.9808180332 0.0918741524 0.0812501713 0.1385603696 0.0377394628 0.5979560000 269499392 0 1780027392 -0.0423600078 0.0598318689 -0.0128554041 495 1305031246.0110030174 0.0917356387 0.0812713541 0.1385603696 0.0377678250 0.4901410000 259667170 0 1774051328 -0.0456596576 0.0580189265 -0.0148308910 496 1305031246.0483930111 0.0939760432 0.0812969684 0.1385603696 0.0378631479 0.2292590000 259669276 0 1775132672 -0.0485340543 0.0528927781 -0.0180898346 497 1305031246.0805249214 0.0940524265 0.0813226333 0.1385603696 0.0379504157 0.2243410000 259671130 0 1776893952 -0.0558054894 0.0501897708 -0.0214017760 498 1305031246.1123559475 0.0968893841 0.0813538918 0.1385603696 0.0380583033 0.2525170000 260102936 0 1778544640 -0.0598767027 0.0461129770 -0.0255164541 499 1305031246.1484489441 0.1022726223 0.0813958131 0.1385603696 0.0381718718 0.5442550000 260082490 0 1775751168 -0.0501362160 0.0435198061 -0.0245579109 500 1305031246.1805961132 0.1077446714 0.0814485109 0.1385603696 0.0382314099 0.4903590000 260083664 0 1777434624 -0.0445857346 0.0430202000 -0.0264466275 501 1305031246.2111370564 0.1042664647 0.0814940557 0.1385603696 0.0383562778 0.4973890000 260081162 0 1779339264 -0.0575703196 0.0390807427 -0.0290772244 502 1305031246.2469689846 0.1031892374 0.0815372732 0.1385603696 0.0385302520 0.5079610000 260265792 0 1781084160 -0.0609109625 0.0427892469 -0.0297949947 503 1305031246.2796959877 0.1093552634 0.0815925773 0.1385603696 0.0385975346 0.4767830000 264826389 0 1784004608 -0.0620234646 0.0327133015 -0.0337413028 504 1305031246.3124730587 0.1133578196 0.0816556036 0.1385603696 0.0387219812 0.4683840000 267933103 0 1785413632 -0.0588237718 0.0324933268 -0.0346022435 505 1305031246.3482720852 0.1132104322 0.0817180884 0.1385603696 0.0388552056 0.2708930000 272144062 0 1784414208 -0.0632896125 0.0295293666 -0.0339673050 506 1305031246.3782060146 0.1138867512 0.0817816628 0.1385603696 0.0390383291 0.3773720000 270478654 0 1786060800 -0.0601092726 0.0314641744 -0.0306691937 507 1305031246.4156370163 0.1139702871 0.0818451513 0.1385603696 0.0391964679 0.3363240000 271737830 0 1785565184 -0.0635360479 0.0333435088 -0.0300536416 508 1305031246.4452888966 0.1176482812 0.0819156299 0.1385603696 0.0393208842 0.2557880000 270121599 0 1785044992 -0.0677331463 0.0329438634 -0.0351401046 509 1305031246.4774649143 0.1186480597 0.0819877957 0.1385603696 0.0394407756 0.6650750000 269787196 0 1773199360 -0.0716353804 0.0320925713 -0.0361325331 510 1305031246.5163950920 0.1171862930 0.0820568124 0.1385603696 0.0395946533 0.4588700000 260510592 0 1774936064 -0.0764050856 0.0348829366 -0.0348997004 511 1305031246.5491750240 0.1173032075 0.0821257877 0.1385603696 0.0397361259 0.5250310000 260504882 0 1771278336 -0.0744321123 0.0382326916 -0.0321505852 512 1305031246.5795109272 0.1125666425 0.0821852425 0.1385603696 0.0398475201 0.5007130000 260505792 0 1773322240 -0.0801102966 0.0452607498 -0.0301082321 513 1305031246.6164529324 0.1141407341 0.0822475339 0.1385603696 0.0399361988 0.5050610000 260507938 0 1774919680 -0.0821972564 0.0442577787 -0.0297783166 514 1305031246.6477630138 0.1214177534 0.0823237406 0.1385603696 0.0399956675 0.4943180000 260761036 0 1776386048 -0.0763155743 0.0447071455 -0.0321785286 515 1305031246.6807579994 0.1119703799 0.0823813069 0.1385603696 0.0400916533 0.4919090000 265497277 0 1783521280 -0.0868500918 0.0496094637 -0.0275087804 516 1305031246.7169740200 0.1172203273 0.0824488244 0.1385603696 0.0402562914 0.4068480000 272484849 0 1783201792 -0.0800952539 0.0513564497 -0.0280652065 517 1305031246.7491660118 0.1173081622 0.0825162505 0.1385603696 0.0403605224 0.2531890000 270443790 0 1782734848 -0.0812630430 0.0545228869 -0.0292222295 518 1305031246.7808170319 0.1126209870 0.0825743678 0.1385603696 0.0404464479 0.4486620000 270472974 0 1784385536 -0.0870093256 0.0596713983 -0.0284853615 519 1305031246.8168079853 0.1318994164 0.0826694064 0.1385603696 0.0405052678 0.2522090000 273615590 0 1784516608 -0.0768589526 0.0492937863 -0.0400026515 520 1305031246.8488121033 0.1266027391 0.0827538936 0.1385603696 0.0405505802 0.2391430000 269957924 0 1786175488 -0.0811962858 0.0540794171 -0.0385177657 521 1305031246.8806428909 0.1236427948 0.0828323752 0.1385603696 0.0406414916 0.6699740000 269769180 0 1775345664 -0.0851054713 0.0606246516 -0.0406860411 522 1305031246.9166710377 0.1186305806 0.0829009541 0.1385603696 0.0407350328 0.4891650000 261016296 0 1771237376 -0.0856398568 0.0608871914 -0.0352140442 523 1305031246.9495339394 0.1253042221 0.0829820311 0.1385603696 0.0407462584 0.5448690000 261005906 0 1773015040 -0.0806586891 0.0615603998 -0.0404450521 524 1305031246.9775969982 0.1314513832 0.0830745299 0.1385603696 0.0407325237 0.4907870000 261007884 0 1774653440 -0.0767169744 0.0568670481 -0.0434359685 525 1305031247.0167899132 0.1297835708 0.0831634995 0.1385603696 0.0408378525 0.4822360000 261006562 0 1776467968 -0.0790881068 0.0582772680 -0.0448834971 526 1305031247.0479340553 0.1202424243 0.0832339917 0.1385603696 0.0408254598 0.4852760000 261012360 0 1778221056 -0.0877585933 0.0623530075 -0.0430571884 527 1305031247.0778899193 0.1207725257 0.0833052223 0.1385603696 0.0408374486 0.4674580000 263120042 0 1779871744 -0.0895054862 0.0648127943 -0.0493232831 528 1305031247.1162130833 0.1197974011 0.0833743363 0.1385603696 0.0408245886 0.4721040000 266622753 0 1783828480 -0.1007392257 0.0661087260 -0.0591490939 529 1305031247.1473660469 0.1211761907 0.0834457954 0.1385603696 0.0408208745 0.3022830000 272030098 0 1784082432 -0.1004628167 0.0668949187 -0.0629057363 530 1305031247.1796920300 0.1193647683 0.0835135670 0.1385603696 0.0407842253 0.3522320000 270657536 0 1785712640 -0.0989790112 0.0640599206 -0.0595378391 531 1305031247.2169430256 0.1228916422 0.0835877254 0.1385603696 0.0407614214 0.3264420000 271976214 0 1785753600 -0.0950024948 0.0623628944 -0.0621731579 532 1305031247.2487928867 0.1138224602 0.0836445576 0.1385603696 0.0407361556 0.2456830000 270192376 0 1784643584 -0.1039508730 0.0702730939 -0.0610989928 533 1305031247.2794220448 0.1178186461 0.0837086741 0.1385603696 0.0407123719 0.6598450000 270007486 0 1773678592 -0.1059142053 0.0669796020 -0.0655125603 534 1305031247.3166429996 0.1195803508 0.0837758495 0.1385603696 0.0407296424 0.4324200000 260998472 0 1775071232 -0.1012255847 0.0620008186 -0.0608721003 535 1305031247.3477900028 0.1176239476 0.0838391170 0.1385603696 0.0407799837 0.2415030000 261456974 0 1775906816 -0.1101789847 0.0628946573 -0.0612209365 536 1305031247.3786110878 0.1180529222 0.0839029487 0.1385603696 0.0407897551 0.5220050000 261431244 0 1771982848 -0.1116845608 0.0631041229 -0.0625161231 537 1305031247.4168620110 0.1196979210 0.0839696060 0.1385603696 0.0408458575 0.5021570000 261433378 0 1773322240 -0.1099782065 0.0625518784 -0.0613002740 538 1305031247.4487700462 0.1241691336 0.0840443263 0.1385603696 0.0410471704 0.4748410000 261434436 0 1775669248 -0.1059914529 0.0611674450 -0.0619128346 539 1305031247.4802629948 0.1222152859 0.0841151444 0.1385603696 0.0411123498 0.4717570000 261612974 0 1777307648 -0.1097436249 0.0648357123 -0.0616556816 540 1305031247.5178461075 0.1264566183 0.0841935546 0.1385603696 0.0412438369 0.4821670000 266116315 0 1784557568 -0.1046979055 0.0628479496 -0.0599716827 541 1305031247.5459010601 0.1256085038 0.0842701071 0.1385603696 0.0413420668 0.4149290000 271611810 0 1783480320 -0.1085927784 0.0659359545 -0.0617758408 542 1305031247.5779209137 0.1281647682 0.0843510936 0.1385603696 0.0414628347 0.2706000000 270284712 0 1782501376 -0.1032141298 0.0643011034 -0.0600968823 543 1305031247.6152799129 0.1345453262 0.0844435323 0.1385603696 0.0416511147 0.3753670000 271415798 0 1784737792 -0.0971685350 0.0612843074 -0.0621720850 544 1305031247.6484000683 0.1370434314 0.0845402233 0.1385603696 0.0418106522 0.2540660000 270074611 0 1786376192 -0.0919119269 0.0597361140 -0.0615601167 545 1305031247.6835579872 0.1304433793 0.0846244493 0.1385603696 0.0419831150 0.6584650000 269824528 0 1774964736 -0.0973601490 0.0628695562 -0.0591955259 546 1305031247.7159609795 0.1329473853 0.0847129528 0.1385603696 0.0421950076 0.4589920000 261400588 0 1771163648 -0.0891634971 0.0616585650 -0.0572148263 547 1305031247.7469019890 0.1319469064 0.0847993038 0.1385603696 0.0424817674 0.2416820000 261854382 0 1770606592 -0.0763552114 0.0618296377 -0.0479661301 548 1305031247.7822608948 0.1279041469 0.0848779622 0.1385603696 0.0426763061 0.5209670000 261828656 0 1773662208 -0.0871097445 0.0603223965 -0.0537055135 549 1305031247.8139829636 0.1301362514 0.0849603999 0.1385603696 0.0429657464 0.4768360000 261829658 0 1776386048 -0.0915730670 0.0532918312 -0.0594862625 550 1305031247.8484420776 0.1326357275 0.0850470823 0.1385603696 0.0431893218 0.4685460000 261832464 0 1778163712 -0.0703597516 0.0524564683 -0.0487268232 551 1305031247.8820719719 0.1400340647 0.0851468772 0.1400340647 0.0432909561 0.4398700000 262000366 0 1780092928 -0.0729390606 0.0421494246 -0.0597696267 552 1305031247.9173319340 0.1290756464 0.0852264583 0.1400340647 0.0432619372 0.4648760000 266538039 0 1786810368 -0.0811804906 0.0577669218 -0.0649607778 553 1305031247.9496860504 0.1310439557 0.0853093109 0.1400340647 0.0433480519 0.3840620000 271855737 0 1784176640 -0.0718793049 0.0603893138 -0.0656970516 554 1305031247.9861450195 0.1395893544 0.0854072894 0.1400340647 0.0435674801 0.2629630000 270496688 0 1783644160 -0.0609427467 0.0487960204 -0.0695276037 555 1305031248.0181560516 0.1271031797 0.0854824171 0.1400340647 0.0435360647 0.3413520000 271689990 0 1785856000 -0.0658419952 0.0589465350 -0.0669276267 556 1305031248.0499138832 0.1285840422 0.0855599380 0.1400340647 0.0435906734 0.2528740000 270353587 0 1784950784 -0.0599640943 0.0605804622 -0.0702538490 557 1305031248.0857460499 0.1342368722 0.0856473293 0.1400340647 0.0438078073 0.6116540000 270101852 0 1777733632 -0.0479429290 0.0536933802 -0.0737347752 558 1305031248.1175789833 0.1269548833 0.0857213571 0.1400340647 0.0438401962 0.3514020000 262238620 0 1779372032 -0.0458045639 0.0559863336 -0.0685988888 559 1305031248.1493461132 0.1225419566 0.0857872258 0.1400340647 0.0438506102 0.4705880000 262233814 0 1775738880 -0.0424717627 0.0608705208 -0.0676352605 560 1305031248.1848630905 0.1245175302 0.0858563871 0.1400340647 0.0440251379 0.4689590000 262229816 0 1777516544 -0.0313154534 0.0598871857 -0.0657904446 561 1305031248.2167689800 0.1269087195 0.0859295642 0.1400340647 0.0440664717 0.5439550000 262231914 0 1779466240 -0.0228783786 0.0594106987 -0.0651175380 562 1305031248.2488510609 0.1235822663 0.0859965618 0.1400340647 0.0440859390 0.4541210000 262430068 0 1781174272 -0.0289906040 0.0627800077 -0.0738916695 563 1305031248.2847399712 0.1225025430 0.0860614037 0.1400340647 0.0441712026 0.4543420000 266332197 0 1783586816 -0.0180490687 0.0674394667 -0.0651906580 564 1305031248.3161809444 0.1225640625 0.0861261248 0.1400340647 0.0442462855 0.4260210000 268583567 0 1785397248 -0.0131372437 0.0687495992 -0.0625911951 565 1305031248.3488430977 0.1232609972 0.0861918502 0.1400340647 0.0443226174 0.2650910000 274832235 0 1782693888 -0.0113715716 0.0643786937 -0.0633238256 566 1305031248.3881969452 0.1220897585 0.0862552741 0.1400340647 0.0443235253 0.2808970000 271983812 0 1784590336 -0.0140656568 0.0700530335 -0.0697712973 567 1305031248.4155070782 0.1229608431 0.0863200105 0.1400340647 0.0443786212 0.3213290000 274605749 0 1784283136 -0.0094007589 0.0696595833 -0.0668433979 568 1305031248.4482519627 0.1229562610 0.0863845110 0.1400340647 0.0443920030 0.2323370000 271523392 0 1783492608 -0.0070612356 0.0723377019 -0.0662549809 569 1305031248.4852969646 0.1185159609 0.0864409810 0.1400340647 0.0444390852 0.2235340000 271488465 0 1785180160 -0.0080817752 0.0699287653 -0.0609519295 570 1305031248.5154309273 0.1171773151 0.0864949044 0.1400340647 0.0444114878 0.5536410000 271364432 0 1784393728 -0.0091192611 0.0763395056 -0.0627062619 571 1305031248.5470030308 0.1201225668 0.0865537970 0.1400340647 0.0444357683 0.4471020000 262218166 0 1778438144 -0.0027818680 0.0823793784 -0.0610593222 572 1305031248.5860579014 0.1183258221 0.0866093425 0.1400340647 0.0444912933 0.2517260000 262590228 0 1772105728 -0.0021549910 0.0784509480 -0.0604380518 573 1305031248.6180379391 0.1239704415 0.0866745451 0.1400340647 0.0445548565 0.4446120000 262588106 0 1774387200 -0.0001066774 0.0807961524 -0.0695270374 574 1305031248.6494390965 0.1191550046 0.0867311312 0.1400340647 0.0445420254 0.4573070000 262593356 0 1777065984 -0.0031677373 0.0819828659 -0.0670560524 575 1305031248.6860280037 0.1190737635 0.0867873793 0.1400340647 0.0445919924 0.4256220000 262591742 0 1778749440 -0.0006701164 0.0869882926 -0.0664616004 576 1305031248.7199230194 0.1208289564 0.0868464793 0.1400340647 0.0446030613 0.4136160000 262799804 0 1780736000 0.0021247827 0.0911520422 -0.0688934103 577 1305031248.7498369217 0.1189080626 0.0869020453 0.1400340647 0.0446822667 0.4336290000 267246857 0 1785294848 0.0036783330 0.0907988101 -0.0650615916 578 1305031248.7856750488 0.1122765765 0.0869459458 0.1400340647 0.0447204099 0.3316250000 272926891 0 1782067200 0.0026268065 0.0932436436 -0.0584263094 579 1305031248.8181409836 0.1102324277 0.0869861643 0.1400340647 0.0446902762 0.2238810000 271599476 0 1781198848 0.0028082393 0.1057222933 -0.0617811345 580 1305031248.8496789932 0.1050739363 0.0870173501 0.1400340647 0.0447291057 0.3673060000 271520068 0 1783050240 0.0010574088 0.1070679650 -0.0613671541 581 1305031248.8855929375 0.0999080688 0.0870395372 0.1400340647 0.0447297002 0.2205050000 273398218 0 1785507840 0.0016145706 0.1124587059 -0.0595005602 582 1305031248.9178819656 0.0913479701 0.0870469400 0.1400340647 0.0447009944 0.2295230000 271303843 0 1784451072 0.0018761531 0.1181359291 -0.0487900972 583 1305031248.9526810646 0.0895611718 0.0870512526 0.1400340647 0.0447179815 0.5913990000 271234676 0 1775374336 0.0056268591 0.1177604795 -0.0472332910 584 1305031248.9845540524 0.0895370618 0.0870555091 0.1400340647 0.0447132475 0.4231800000 262931980 0 1776730112 0.0093446728 0.1206401885 -0.0497237891 585 1305031249.0169510841 0.0816132799 0.0870462062 0.1400340647 0.0447049512 0.4230260000 262963734 0 1772765184 0.0036899094 0.1256094426 -0.0474275798 586 1305031249.0523660183 0.0828238502 0.0870390008 0.1400340647 0.0446849090 0.4123700000 262965216 0 1773821952 0.0048434213 0.1260382533 -0.0500906073 587 1305031249.0845029354 0.0848985612 0.0870353544 0.1400340647 0.0446692933 0.4302870000 263397918 0 1774882816 0.0054159276 0.1297701299 -0.0520710051 588 1305031249.1168839931 0.0855011418 0.0870327452 0.1400340647 0.0446362234 0.4043480000 263434949 0 1776709632 0.0081558600 0.1274290681 -0.0480008498 589 1305031249.1534469128 0.0841181129 0.0870277967 0.1400340647 0.0446064543 0.4150400000 263312314 0 1778475008 0.0030476060 0.1307474077 -0.0477404036 590 1305031249.1847391129 0.0887592509 0.0870307314 0.1400340647 0.0445902172 0.4070670000 263314344 0 1780113408 0.0018483996 0.1305663884 -0.0529308654 591 1305031249.2168650627 0.0894039422 0.0870347470 0.1400340647 0.0445641703 0.4029220000 263344122 0 1782030336 0.0051140059 0.1216540784 -0.0472579747 592 1305031249.2532238960 0.0960103646 0.0870499085 0.1400340647 0.0445491990 0.4086260000 268747023 0 1784709120 0.0018930361 0.1261656433 -0.0568342730 593 1305031249.2848041058 0.0927429125 0.0870595088 0.1400340647 0.0445390608 0.2677750000 275672634 0 1784479744 0.0049804952 0.1181604713 -0.0466588363 594 1305031249.3174340725 0.0933757126 0.0870701422 0.1400340647 0.0445134707 0.2290550000 273134848 0 1783205888 0.0094476026 0.1178818345 -0.0407685563 595 1305031249.3527359962 0.0799998567 0.0870582594 0.1400340647 0.0444829912 0.4354160000 272872006 0 1785020416 -0.0042435098 0.1256454289 -0.0357383266 596 1305031249.3847539425 0.0787567198 0.0870443306 0.1400340647 0.0444724373 0.5441240000 276244556 0 1780510720 -0.0000583585 0.1179583520 -0.0264479760 597 1305031249.4178340435 0.0756810531 0.0870252966 0.1400340647 0.0445086621 0.5020420000 263624162 0 1770405888 0.0009893756 0.1145359650 -0.0170589387 598 1305031249.4537220001 0.0776331425 0.0870095907 0.1400340647 0.0445566117 0.5181190000 263654000 0 1771974656 -0.0006404556 0.1179579422 -0.0219600350 599 1305031249.4859149456 0.0775735602 0.0869938377 0.1400340647 0.0445998534 0.4432060000 263654966 0 1773625344 -0.0042329654 0.1175425276 -0.0262124985 600 1305031249.5177340508 0.0788846165 0.0869803223 0.1400340647 0.0446087259 0.4204300000 263656784 0 1775403008 -0.0036603771 0.1136735082 -0.0267024208 601 1305031249.5543251038 0.0855612829 0.0869779612 0.1400340647 0.0447177581 0.4065240000 267849441 0 1777795072 0.0018554926 0.1064608395 -0.0293684602 602 1305031249.5859050751 0.0918259621 0.0869860144 0.1400340647 0.0448838064 0.3885390000 269929795 0 1785745408 -0.0018122531 0.1097397804 -0.0452068150 603 1305031249.6180789471 0.0927915275 0.0869956421 0.1400340647 0.0449085439 0.2476600000 276270118 0 1784291328 -0.0018132925 0.1038002372 -0.0458862260 604 1305031249.6542129517 0.0942984074 0.0870077328 0.1400340647 0.0451559087 0.2536850000 273383444 0 1782771712 0.0004252307 0.1008133516 -0.0443375781 605 1305031249.6856739521 0.1043246239 0.0870363557 0.1400340647 0.0452721141 0.3087220000 276044997 0 1784385536 0.0078274310 0.1034564450 -0.0490640402 606 1305031249.7177898884 0.1022178456 0.0870614077 0.1400340647 0.0453574060 0.2206330000 273025514 0 1786683392 0.0005469024 0.1018575877 -0.0550018661 607 1305031249.7539620399 0.1121011525 0.0871026593 0.1400340647 0.0454439876 0.2207740000 273083197 0 1785368576 0.0157422461 0.0983099863 -0.0468565822 608 1305031249.7854170799 0.1150291190 0.0871485910 0.1400340647 0.0454791016 0.6586400000 273013606 0 1780436992 0.0162131768 0.0918647870 -0.0486118421 609 1305031249.8186020851 0.1143833697 0.0871933115 0.1400340647 0.0454923324 0.4386790000 264016342 0 1773015040 0.0106210206 0.0855895579 -0.0522954203 610 1305031249.8537468910 0.1169004142 0.0872420117 0.1400340647 0.0456440006 0.4880090000 264046264 0 1774850048 0.0149391647 0.0843203366 -0.0481466055 611 1305031249.8855249882 0.1351909190 0.0873204878 0.1400340647 0.0456661673 0.4291420000 264048090 0 1776279552 0.0279599242 0.0791265965 -0.0596656799 612 1305031249.9170649052 0.1270542741 0.0873854123 0.1400340647 0.0456840917 0.4164000000 264046128 0 1778069504 0.0164461527 0.0715226009 -0.0599454418 613 1305031249.9533979893 0.1218424141 0.0874416227 0.1400340647 0.0457002920 0.4343740000 268584221 0 1779859456 0.0069747493 0.0686237812 -0.0613658614 614 1305031249.9851789474 0.1149652451 0.0874864495 0.1400340647 0.0457286540 0.4329660000 270311063 0 1782931456 -0.0008549392 0.0649653673 -0.0576188639 615 1305031250.0164399147 0.1131796241 0.0875282270 0.1400340647 0.0457207196 0.3035430000 277792770 0 1781145600 -0.0052766148 0.0657383651 -0.0576631874 616 1305031250.0531940460 0.1191672161 0.0875795890 0.1400340647 0.0457881673 0.2266240000 275145789 0 1779855360 -0.0062978249 0.0572036691 -0.0621195734 617 1305031250.0845069885 0.1177567914 0.0876284985 0.1400340647 0.0458777618 0.3696760000 275084592 0 1781764096 -0.0120520592 0.0539966673 -0.0614172034 618 1305031250.1208500862 0.1180709675 0.0876777582 0.1400340647 0.0459980508 0.2690730000 278005260 0 1783209984 -0.0155840255 0.0613622516 -0.0602649972 619 1305031250.1532480717 0.1123311222 0.0877175859 0.1400340647 0.0462758826 0.2265980000 275063413 0 1784926208 -0.0295431148 0.0664471164 -0.0569100082 620 1305031250.1853280067 0.1088128611 0.0877516106 0.1400340647 0.0462982069 0.6765380000 274596390 0 1784758272 -0.0391797014 0.0659578517 -0.0553042293 621 1305031250.2214460373 0.1213494167 0.0878057133 0.1400340647 0.0463069922 0.4710860000 264430142 0 1772068864 -0.0267719422 0.0602559038 -0.0560055748 622 1305031250.2537350655 0.1222912073 0.0878611562 0.1400340647 0.0464044567 0.4438410000 264443692 0 1773670400 -0.0312546901 0.0618162788 -0.0547816455 623 1305031250.2852239609 0.1092739031 0.0878955266 0.1400340647 0.0464261898 0.4580110000 264445214 0 1775587328 -0.0555312112 0.0495581254 -0.0526338853 624 1305031250.3208620548 0.1119520813 0.0879340788 0.1400340647 0.0464698711 0.4504030000 264446912 0 1777238016 -0.0502646454 0.0525798798 -0.0480181091 625 1305031250.3517000675 0.1085875109 0.0879671243 0.1400340647 0.0464914661 0.4574360000 264454738 0 1778900992 -0.0533852652 0.0506957769 -0.0421978533 626 1305031250.3851490021 0.1228967309 0.0880229224 0.1400340647 0.0464986034 0.4537230000 270299595 0 1786634240 -0.0475323722 0.0450280346 -0.0498133898 627 1305031250.4215359688 0.1276457310 0.0880861166 0.1400340647 0.0465101836 0.2875080000 278267470 0 1783885824 -0.0500707440 0.0396839455 -0.0532728918 628 1305031250.4540181160 0.1181646064 0.0881340123 0.1400340647 0.0466550697 0.2402170000 275465404 0 1782382592 -0.0545234494 0.0477466732 -0.0414696038 629 1305031250.4856131077 0.1090585068 0.0881672786 0.1400340647 0.0466659283 0.4042930000 275521236 0 1784221696 -0.0614723489 0.0536918864 -0.0324817523 630 1305031250.5215380192 0.1167733669 0.0882126851 0.1400340647 0.0466453343 0.2533980000 278841452 0 1782665216 -0.0619854815 0.0455106795 -0.0373732448 631 1305031250.5536580086 0.1278804541 0.0882755500 0.1400340647 0.0466435453 0.2305530000 275133754 0 1784152064 -0.0595905297 0.0456744805 -0.0453171618 632 1305031250.5853788853 0.1295982003 0.0883409340 0.1400340647 0.0466217995 0.4941110000 275140200 0 1781571584 -0.0581032187 0.0406235419 -0.0412645750 633 1305031250.6213030815 0.1253672689 0.0883994274 0.1400340647 0.0466074477 0.4993020000 264583991 0 1776496640 -0.0656389296 0.0406751782 -0.0375697874 634 1305031250.6535439491 0.1247268170 0.0884567261 0.1400340647 0.0466374951 0.3135490000 264818928 0 1776672768 -0.0657839850 0.0406351611 -0.0318898149 635 1305031250.6852970123 0.1267958134 0.0885171026 0.1400340647 0.0466614385 0.4705520000 264798130 0 1772236800 -0.0614841729 0.0440124832 -0.0282697566 636 1305031250.7216401100 0.1247170940 0.0885740208 0.1400340647 0.0466411791 0.4630890000 264799796 0 1774444544 -0.0699287578 0.0485026389 -0.0308321007 637 1305031250.7534279823 0.1228282675 0.0886277952 0.1400340647 0.0466196581 0.4709180000 264825459 0 1776209920 -0.0734759271 0.0468825102 -0.0261162035 638 1305031250.7853651047 0.1255817860 0.0886857168 0.1400340647 0.0465994857 0.4549200000 264901347 0 1778032640 -0.0720055699 0.0497309119 -0.0277228933 639 1305031250.8217930794 0.1216448694 0.0887372961 0.1400340647 0.0465663903 0.4526580000 270986605 0 1784287232 -0.0724080205 0.0523247942 -0.0224323887 640 1305031250.8538279533 0.1120354012 0.0887736993 0.1400340647 0.0465363330 0.3073690000 278438908 0 1782321152 -0.0841834247 0.0555265471 -0.0188083276 641 1305031250.8820140362 0.1182922497 0.0888197501 0.1400340647 0.0465021759 0.2571510000 275650673 0 1779527680 -0.0808873922 0.0524167307 -0.0223703776 642 1305031250.9217998981 0.1139256582 0.0888588559 0.1400340647 0.0464699368 0.4700600000 275167588 0 1780879360 -0.0848595947 0.0564569756 -0.0215253495 643 1305031250.9535419941 0.1201376617 0.0889075010 0.1400340647 0.0464508490 0.2541100000 279360750 0 1784020992 -0.0804785490 0.0528468005 -0.0260412041 644 1305031250.9853079319 0.1102304682 0.0889406112 0.1400340647 0.0464286212 0.2461000000 275368320 0 1785823232 -0.0895142257 0.0553903319 -0.0211017560 645 1305031251.0214879513 0.1222103238 0.0889921922 0.1400340647 0.0464043925 0.6031500000 275050910 0 1781800960 -0.0844754875 0.0530469567 -0.0335945077 646 1305031251.0534679890 0.1241050512 0.0890465464 0.1400340647 0.0464156869 0.4546260000 264862581 0 1768558592 -0.0810936242 0.0509991832 -0.0358737595 647 1305031251.0851860046 0.1160389483 0.0890882658 0.1400340647 0.0464171985 0.2061330000 264816258 0 1768865792 -0.0893832594 0.0516488701 -0.0344895460 648 1305031251.1214449406 0.1147451773 0.0891278598 0.1400340647 0.0464189812 0.2151110000 264818448 0 1770516480 -0.0883542374 0.0478538908 -0.0339535587 649 1305031251.1537809372 0.1191926152 0.0891741845 0.1400340647 0.0465358513 0.2147400000 264820790 0 1772527616 -0.0805965662 0.0441818386 -0.0390042625 650 1305031251.1851599216 0.1102331355 0.0892065829 0.1400340647 0.0465634652 0.2098870000 264822380 0 1774452736 -0.0908394381 0.0425580442 -0.0379122198 651 1305031251.2204658985 0.0970953107 0.0892187007 0.1400340647 0.0465767921 0.2688810000 265241782 0 1776230400 -0.0941001177 0.0458816960 -0.0299301147 652 1305031251.2524240017 0.1013916060 0.0892373708 0.1400340647 0.0466566304 0.5111480000 265222652 0 1778049024 -0.0844667777 0.0435942039 -0.0333746523 653 1305031251.2844820023 0.1063393950 0.0892635608 0.1400340647 0.0468938742 0.4844080000 265224242 0 1780219904 -0.0776238143 0.0387379602 -0.0390643738 654 1305031251.3190040588 0.1102080494 0.0892955860 0.1400340647 0.0470042298 0.4680700000 265226088 0 1781858304 -0.0694587752 0.0344251059 -0.0417029522 655 1305031251.3532440662 0.1129158661 0.0893316475 0.1400340647 0.0471157161 0.4555500000 265400666 0 1783635968 -0.0641009957 0.0315648764 -0.0461000018 656 1305031251.3870069981 0.1075998917 0.0893594954 0.1400340647 0.0471704807 0.4698480000 270344823 0 1785679872 -0.0618668012 0.0361976400 -0.0428911671 657 1305031251.4210500717 0.1077550128 0.0893874947 0.1400340647 0.0472715297 0.4232490000 274392817 0 1783803904 -0.0595114157 0.0340410545 -0.0448672548 658 1305031251.4496629238 0.1079425961 0.0894156939 0.1400340647 0.0473410083 0.2519820000 278951404 0 1783463936 -0.0545700975 0.0333014242 -0.0447656550 659 1305031251.4890139103 0.1055177525 0.0894401280 0.1400340647 0.0474464886 0.3642260000 275897306 0 1785655296 -0.0508950204 0.0352260470 -0.0441189148 660 1305031251.5207729340 0.1104386523 0.0894719439 0.1400340647 0.0475537803 0.2957930000 278829064 0 1782657024 -0.0406942777 0.0315633975 -0.0452275723 661 1305031251.5530450344 0.1069308668 0.0894983568 0.1400340647 0.0476749197 0.2427500000 275600833 0 1780547584 -0.0376002304 0.0321673006 -0.0426383242 662 1305031251.5887598991 0.1119574830 0.0895322830 0.1400340647 0.0477243710 0.5300320000 275531546 0 1778782208 -0.0321706720 0.0312527493 -0.0471036062 663 1305031251.6208739281 0.1051162258 0.0895557882 0.1400340647 0.0477610574 0.5039680000 265279875 0 1766899712 -0.0353028998 0.0363036953 -0.0450788215 664 1305031251.6528749466 0.1054383963 0.0895797078 0.1400340647 0.0478588948 0.2167570000 265217772 0 1767137280 -0.0345082581 0.0305706561 -0.0464832149 665 1305031251.6897680759 0.1041970253 0.0896016887 0.1400340647 0.0479024810 0.2326670000 265594666 0 1768550400 -0.0340686589 0.0378494337 -0.0481110439 666 1305031251.7204608917 0.1033827290 0.0896223810 0.1400340647 0.0479562222 0.4754230000 265577736 0 1771470848 -0.0316906497 0.0406519324 -0.0473588109 667 1305031251.7531440258 0.1009187549 0.0896393171 0.1400340647 0.0480763253 0.4417250000 265574826 0 1773649920 -0.0305462535 0.0381004065 -0.0453280434 668 1305031251.7892498970 0.1153890416 0.0896778646 0.1400340647 0.0481457843 0.4235540000 265580604 0 1775681536 -0.0194445811 0.0357775539 -0.0547654666 669 1305031251.8209791183 0.1188116074 0.0897214128 0.1400340647 0.0481827868 0.4240260000 265766526 0 1777496064 -0.0165851377 0.0391131490 -0.0588854961 670 1305031251.8537969589 0.1256220788 0.0897749958 0.1400340647 0.0483456131 0.4275900000 270303307 0 1781432320 -0.0073235203 0.0339087024 -0.0601482950 671 1305031251.8896539211 0.1317591667 0.0898375654 0.1400340647 0.0483711740 0.4070190000 273328405 0 1783566336 -0.0007068031 0.0326933563 -0.0626151934 672 1305031251.9219300747 0.1297032684 0.0898968894 0.1400340647 0.0483790970 0.2419060000 279428015 0 1783885824 0.0041135997 0.0434372723 -0.0571152195 673 1305031251.9538369179 0.1248910353 0.0899488866 0.1400340647 0.0483977040 0.2232810000 276387961 0 1784864768 0.0064573865 0.0518742576 -0.0482047908 674 1305031251.9898068905 0.1270046830 0.0900038655 0.1400340647 0.0484004785 0.4243130000 275682116 0 1787691008 0.0064416137 0.0514234900 -0.0523747019 675 1305031252.0221600533 0.1155763045 0.0900417506 0.1400340647 0.0484197340 0.2265450000 279728894 0 1785425920 0.0007621627 0.0546150655 -0.0431938991 676 1305031252.0537619591 0.1065519750 0.0900661740 0.1400340647 0.0484294099 0.2214610000 275876448 0 1786847232 -0.0022764876 0.0566296056 -0.0364820398 677 1305031252.0895619392 0.0972308069 0.0900767569 0.1400340647 0.0484690381 0.2062340000 275895378 0 1786200064 -0.0054586846 0.0672888905 -0.0314732380 678 1305031252.1221520901 0.0968041793 0.0900866794 0.1400340647 0.0485459844 0.5374300000 275494382 0 1784782848 -0.0030203853 0.0692574233 -0.0316157416 679 1305031252.1539709568 0.0938082561 0.0900921604 0.1400340647 0.0487179764 0.4307490000 265569334 0 1778507776 0.0019291621 0.0704661161 -0.0251556151 680 1305031252.1897890568 0.0614496432 0.0900500390 0.1400340647 0.0487102176 0.2229640000 265919684 0 1779548160 -0.0200351533 0.0778995529 -0.0031453697 681 1305031252.2220859528 0.0717999414 0.0900232400 0.1400340647 0.0487041240 0.4133490000 265913206 0 1775558656 -0.0163249765 0.0926876366 -0.0189836379 682 1305031252.2530639172 0.0765669495 0.0900035094 0.1400340647 0.0487964301 0.4198500000 265913832 0 1776676864 -0.0124917179 0.0956606418 -0.0227038749 683 1305031252.2888779640 0.0598078482 0.0899592991 0.1400340647 0.0488677249 0.3953070000 265915766 0 1778016256 -0.0166969672 0.0925103277 -0.0015790444 684 1305031252.3206090927 0.0648518652 0.0899225923 0.1400340647 0.0488424990 0.4093850000 269833391 0 1781321728 -0.0137445983 0.0951207131 -0.0063890144 685 1305031252.3528549671 0.0595807545 0.0898782976 0.1400340647 0.0488306904 0.3895120000 271529473 0 1782403072 -0.0168991107 0.0981895849 -0.0025897138 686 1305031252.3893189430 0.0603401884 0.0898352392 0.1400340647 0.0488159525 0.2668120000 278257792 0 1782657024 -0.0152929407 0.0996906310 -0.0003522281 687 1305031252.4217019081 0.0738976523 0.0898120404 0.1400340647 0.0488177092 0.2836610000 275331850 0 1783640064 -0.0101230163 0.1013869271 -0.0139582530 688 1305031252.4538249969 0.0622769892 0.0897720185 0.1400340647 0.0487980596 0.3097430000 278054948 0 1783422976 -0.0163754802 0.1000969708 0.0001726300 689 1305031252.4895589352 0.0613595247 0.0897307812 0.1400340647 0.0487658691 0.2431970000 275090466 0 1782550528 -0.0197501555 0.1015153751 -0.0006528031 690 1305031252.5221700668 0.0597580001 0.0896873424 0.1400340647 0.0487386735 0.5635310000 274777888 0 1781354496 -0.0213931277 0.1011351570 0.0023977328 691 1305031252.5537741184 0.0651433170 0.0896518228 0.1400340647 0.0487143527 0.4539370000 265910106 0 1769693184 -0.0171446782 0.0997800976 0.0027098786 692 1305031252.5897459984 0.0778476745 0.0896347648 0.1400340647 0.0486922026 0.2332700000 266252596 0 1770340352 -0.0108217243 0.1016063318 -0.0097994525 693 1305031252.6221249104 0.0646115020 0.0895986562 0.1400340647 0.0486800113 0.4307390000 266240394 0 1772118016 -0.0182564408 0.0998897105 0.0052500870 694 1305031252.6578559875 0.0644906536 0.0895624775 0.1400340647 0.0486646480 0.4336600000 266242432 0 1774026752 -0.0190339517 0.0989676267 0.0062358063 695 1305031252.6889979839 0.0628160387 0.0895239934 0.1400340647 0.0486890035 0.4210180000 266396570 0 1775595520 -0.0230542757 0.1005951390 0.0044116024 696 1305031252.7216539383 0.0661066696 0.0894903478 0.1400340647 0.0487510419 0.4244300000 270762839 0 1780051968 -0.0219427571 0.1009977907 0.0029536933 697 1305031252.7578220367 0.0728380680 0.0894664565 0.1400340647 0.0488862731 0.3969050000 272648461 0 1784365056 -0.0218033921 0.0999225453 -0.0060096700 698 1305031252.7896919250 0.0602031648 0.0894245320 0.1400340647 0.0490659792 0.2673070000 279418884 0 1782861824 -0.0315101072 0.0997462273 0.0036473833 699 1305031252.8224050999 0.0720206052 0.0893996337 0.1400340647 0.0491892315 0.2360710000 277003413 0 1781952512 -0.0269953832 0.0974158719 -0.0067125270 700 1305031252.8539779186 0.0776110142 0.0893827928 0.1400340647 0.0491778345 0.6339710000 276538534 0 1782001664 -0.0251545683 0.0929787830 -0.0108433003 701 1305031252.8897290230 0.0794558153 0.0893686316 0.1400340647 0.0492195050 0.4984240000 266509310 0 1769652224 -0.0267643109 0.0905828625 -0.0133696431 702 1305031252.9206719398 0.0833397731 0.0893600435 0.1400340647 0.0492241117 0.4414160000 266587832 0 1771290624 -0.0265187901 0.0896878764 -0.0162770227 703 1305031252.9578649998 0.0857323110 0.0893548831 0.1400340647 0.0492956771 0.4484810000 266588478 0 1773080576 -0.0250561535 0.0850810409 -0.0137793608 704 1305031252.9894239902 0.0920740291 0.0893587456 0.1400340647 0.0493678168 0.4296940000 266727076 0 1774718976 -0.0265983064 0.0831878260 -0.0205035638 705 1305031253.0196959972 0.0935415104 0.0893646786 0.1400340647 0.0494568146 0.4424860000 271656797 0 1781092352 -0.0294012874 0.0843122602 -0.0219721757 706 1305031253.0574259758 0.0964064226 0.0893746527 0.1400340647 0.0495169802 0.4217280000 275821379 0 1786241024 -0.0336700752 0.0801566616 -0.0247734766 707 1305031253.0895500183 0.0989796221 0.0893882382 0.1400340647 0.0495476424 0.2410790000 280405530 0 1782874112 -0.0370498858 0.0734885186 -0.0285440944 708 1305031253.1197240353 0.1040095389 0.0894088898 0.1400340647 0.0495515976 0.3224290000 277362274 0 1784000512 -0.0390593447 0.0692224056 -0.0327761099 709 1305031253.1573839188 0.1068615392 0.0894335057 0.1400340647 0.0496607357 0.3057130000 280259522 0 1784565760 -0.0465286970 0.0672704950 -0.0394914486 710 1305031253.1892180443 0.1065314040 0.0894575872 0.1400340647 0.0497088386 0.2366790000 276976036 0 1783570432 -0.0501008444 0.0682246089 -0.0398696810 711 1305031253.2180271149 0.1042935997 0.0894784536 0.1400340647 0.0497029597 0.4957140000 276990966 0 1782177792 -0.0481042750 0.0700191259 -0.0348346680 712 1305031253.2578470707 0.1078190953 0.0895042129 0.1400340647 0.0496911675 0.4897560000 266716345 0 1776386048 -0.0491575897 0.0668626800 -0.0380861312 713 1305031253.2897419930 0.1123342887 0.0895362327 0.1400340647 0.0496585529 0.2328750000 266603982 0 1776599040 -0.0485105179 0.0635542348 -0.0418485738 714 1305031253.3220069408 0.1022458225 0.0895540332 0.1400340647 0.0496431025 0.2067070000 266640409 0 1778348032 -0.0506341755 0.0603039674 -0.0303479582 715 1305031253.3578300476 0.1055829823 0.0895764513 0.1400340647 0.0496176347 0.2100580000 266608126 0 1780125696 -0.0450817421 0.0529279076 -0.0280319452 716 1305031253.3880970478 0.1063945517 0.0895999403 0.1400340647 0.0495839450 0.2140100000 266660141 0 1782157312 -0.0428324603 0.0566905141 -0.0282165520 717 1305031253.4213519096 0.1081616431 0.0896258283 0.1400340647 0.0495531260 0.2067750000 266634331 0 1783808000 -0.0436957814 0.0562186465 -0.0303988848 718 1305031253.4579629898 0.1095912457 0.0896536353 0.1400340647 0.0495256656 0.2095010000 266647945 0 1785585664 -0.0396559238 0.0543816984 -0.0262102615 719 1305031253.4896900654 0.1039687768 0.0896735451 0.1400340647 0.0494937433 0.2078890000 266699423 0 1784315904 -0.0436776914 0.0613677576 -0.0228310060 720 1305031253.5207340717 0.1017445475 0.0896903104 0.1400340647 0.0494616218 0.2093200000 266678105 0 1783676928 -0.0484647080 0.0566320494 -0.0216261577 721 1305031253.5578539371 0.1082057133 0.0897159905 0.1400340647 0.0494306006 0.2101980000 266662511 0 1785479168 -0.0445494018 0.0553812720 -0.0244214609 722 1305031253.5898048878 0.1137278378 0.0897492480 0.1400340647 0.0494048360 0.2067770000 266677817 0 1786871808 -0.0485398397 0.0604258068 -0.0342967324 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 06:46:53 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_rgbd_dataset_freiburg1_xyz.log input: datasets/TUM/freiburg1/rgbd_dataset_freiburg1_xyz.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9235938,1.229375,0.5171875,0.4875 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 RGB-intrinsics-parameters: 0.8082812,1.076042,0.4978125,0.531875 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1305031102.1753039360 0.0253988300 0.0253988300 0.0253988300 nan 0.1760650000 225849628 0 1770418176 0.0000000000 0.0000000000 0.0000000000 2 1305031102.2112140656 0.0281997994 0.0267993147 0.0281997994 0.0139400400 0.1920400000 229928426 0 1772769280 -0.0009392386 0.0071761515 0.0118162083 3 1305031102.2432110310 0.0226107799 0.0254031364 0.0281997994 0.0101199005 0.1832070000 229999091 0 1774530560 -0.0015280230 0.0054240790 0.0250633340 4 1305031102.2753260136 0.0196907222 0.0239750328 0.0281997994 0.0089455725 0.1765810000 229932945 0 1776562176 -0.0022966457 0.0065464829 0.0368976444 5 1305031102.3112668991 0.0145704467 0.0220941156 0.0281997994 0.0079847658 0.1795880000 229990351 0 1778212864 -0.0013605448 0.0047888514 0.0502236448 6 1305031102.3432331085 0.0125778643 0.0205080737 0.0281997994 0.0077675227 0.1740290000 229986797 0 1780244480 -0.0023762945 0.0058158776 0.0618077181 7 1305031102.3753290176 0.0107081681 0.0191080872 0.0281997994 0.0071883332 0.1733520000 229983635 0 1781784576 -0.0034944536 0.0063511785 0.0740375891 8 1305031102.4112579823 0.0084442534 0.0177751080 0.0281997994 0.0095948311 0.1821150000 229938757 0 1783164928 -0.0078060534 0.0117714321 0.0844790190 9 1305031102.4432709217 0.0118500246 0.0171167654 0.0281997994 0.0102635140 0.2063700000 230386557 0 1785327616 -0.0072081340 0.0183398761 0.0957835615 10 1305031102.4753179550 0.0124255605 0.0166476449 0.0281997994 0.0096771363 0.2853290000 230824063 0 1783988224 -0.0048524723 0.0175617728 0.1098261178 11 1305031102.5112190247 0.0134435929 0.0163563674 0.0281997994 0.0093402653 0.4298800000 231739052 0 1785290752 -0.0041227727 0.0182263516 0.1222831905 12 1305031102.5432200432 0.0137100322 0.0161358395 0.0281997994 0.0089945805 0.2632150000 231762012 0 1783046144 -0.0075365826 0.0151832281 0.1347708106 13 1305031102.5752859116 0.0216076653 0.0165567492 0.0281997994 0.0090302717 0.2290720000 231253869 0 1783017472 -0.0061662453 0.0106101092 0.1489485502 14 1305031102.6112329960 0.0234710313 0.0170506265 0.0281997994 0.0087317361 0.4431310000 231473314 0 1785823232 -0.0100440122 0.0095551014 0.1606478840 15 1305031102.6432650089 0.0178443678 0.0171035426 0.0281997994 0.0091624466 0.2574600000 232302042 0 1783197696 -0.0155601343 0.0176504515 0.1700938195 16 1305031102.6752851009 0.0213156771 0.0173668010 0.0281997994 0.0089434239 0.2674880000 232382780 0 1783459840 -0.0142212389 0.0204134844 0.1834713221 17 1305031102.7112629414 0.0268274751 0.0179233112 0.0281997994 0.0089893847 0.1876880000 231339271 0 1784459264 -0.0140554793 0.0201388523 0.1974963099 18 1305031102.7432339191 0.0245568398 0.0182918406 0.0281997994 0.0089359133 0.1962720000 231296433 0 1786499072 -0.0153387450 0.0276378319 0.2087470591 19 1305031102.7754719257 0.0307075772 0.0189453004 0.0307075772 0.0087725632 0.1968960000 231286955 0 1783361536 -0.0121594528 0.0285779964 0.2229142338 20 1305031102.8112320900 0.0317675434 0.0195864126 0.0317675434 0.0087147032 0.1882740000 231275441 0 1783832576 -0.0153705087 0.0317394249 0.2346003950 21 1305031102.8432900906 0.0368335508 0.0204077049 0.0368335508 0.0085698875 0.2162090000 231712693 0 1786118144 -0.0164439082 0.0317659676 0.2481490523 22 1305031102.8753631115 0.0383273475 0.0212222341 0.0383273475 0.0085889776 0.4564360000 231766385 0 1783914496 -0.0205264464 0.0345006771 0.2598372996 23 1305031102.9111850262 0.0401128344 0.0220435645 0.0401128344 0.0084178906 0.3424600000 232795648 0 1783824384 -0.0213341285 0.0383135825 0.2711260021 24 1305031102.9432289600 0.0423059650 0.0228878312 0.0423059650 0.0086978869 0.2519900000 232827372 0 1784414208 -0.0284330025 0.0399188101 0.2822503150 25 1305031102.9752030373 0.0426024832 0.0236764173 0.0426024832 0.0087277795 0.2008160000 231692925 0 1785237504 -0.0337034278 0.0447420962 0.2929314673 26 1305031103.0112149715 0.0450158641 0.0244971652 0.0450158641 0.0085849685 0.1954740000 231715473 0 1786994688 -0.0326820575 0.0480779000 0.3035570383 27 1305031103.0432269573 0.0477955602 0.0253600688 0.0477955602 0.0084302086 0.1911890000 231752051 0 1782706176 -0.0323862880 0.0518181473 0.3160433173 28 1305031103.0753190517 0.0545276180 0.0264017669 0.0545276180 0.0085591474 0.1869580000 231796337 0 1780035584 -0.0276061147 0.0519869588 0.3283344507 29 1305031103.1112399101 0.0516098030 0.0272710096 0.0545276180 0.0087170022 0.1948700000 231777091 0 1781047296 -0.0286610909 0.0594374388 0.3351837397 30 1305031103.1433179379 0.0562013760 0.0282353551 0.0562013760 0.0086508468 0.2230300000 232181679 0 1783107584 -0.0273701400 0.0607136451 0.3460086882 31 1305031103.1754519939 0.0544212088 0.0290800601 0.0562013760 0.0085482430 0.4722440000 232179047 0 1783832576 -0.0290849637 0.0665966049 0.3534446955 32 1305031103.2112200260 0.0546567068 0.0298793303 0.0562013760 0.0088768916 0.4095320000 233550226 0 1784791040 -0.0304349884 0.0714762509 0.3618676662 33 1305031103.2432160378 0.0564859845 0.0306855925 0.0564859845 0.0087599675 0.2304540000 233480916 0 1784147968 -0.0302155893 0.0743763223 0.3699198663 34 1305031103.2753698826 0.0579487979 0.0314874515 0.0579487979 0.0088773074 0.2633590000 233416882 0 1784414208 -0.0362127237 0.0746595562 0.3754440248 35 1305031103.3112099171 0.0657556504 0.0324665429 0.0657556504 0.0092964874 0.4488690000 232647171 0 1785372672 -0.0350652412 0.0699373856 0.3829217255 36 1305031103.3432230949 0.0662027970 0.0334036611 0.0662027970 0.0095386875 0.4250100000 232700089 0 1784729600 -0.0280501619 0.0712916926 0.3842768371 37 1305031103.3753271103 0.0669726357 0.0343109307 0.0669726357 0.0094076029 0.3479580000 234148668 0 1782628352 -0.0276126992 0.0697868094 0.3848309219 38 1305031103.4112598896 0.0684289634 0.0352087736 0.0684289634 0.0094187684 0.3331450000 234233148 0 1780187136 -0.0298517291 0.0659426525 0.3842765689 39 1305031103.4432799816 0.0682734549 0.0360565860 0.0684289634 0.0093741697 0.2396090000 233077437 0 1780547584 -0.0303105339 0.0635723323 0.3806731403 40 1305031103.4752740860 0.0685526952 0.0368689887 0.0685526952 0.0093111700 0.4485540000 233105045 0 1780027392 -0.0294004213 0.0600548461 0.3761331439 41 1305031103.5113329887 0.0681685358 0.0376323923 0.0685526952 0.0092439490 0.4287750000 233128173 0 1782939648 -0.0293394811 0.0556595363 0.3696846366 42 1305031103.5434439182 0.0660886690 0.0383099227 0.0685526952 0.0091736329 0.3268310000 234667214 0 1783508992 -0.0282806028 0.0522234812 0.3612573743 43 1305031103.5754740238 0.0614987314 0.0388491973 0.0685526952 0.0090889718 0.2485480000 234655340 0 1783013376 -0.0297692381 0.0504010282 0.3514533043 44 1305031103.6112229824 0.0599800870 0.0393294448 0.0685526952 0.0090006976 0.2847220000 234593636 0 1780711424 -0.0274071805 0.0461637191 0.3423226774 45 1305031103.6434450150 0.0562571995 0.0397056171 0.0685526952 0.0089171940 0.1980160000 233052809 0 1782054912 -0.0268806629 0.0427239202 0.3306122422 46 1305031103.6755230427 0.0534213483 0.0400037852 0.0685526952 0.0088633912 0.2048380000 233083769 0 1783705600 -0.0240487289 0.0393270999 0.3194668293 47 1305031103.7116100788 0.0497793965 0.0402117769 0.0685526952 0.0087974531 0.2011640000 233105923 0 1785466880 -0.0207522120 0.0357633233 0.3065636456 48 1305031103.7433259487 0.0488253385 0.0403912261 0.0685526952 0.0087411397 0.2045700000 233060879 0 1784729600 -0.0180397909 0.0295799505 0.2943863869 49 1305031103.7753419876 0.0420774780 0.0404256394 0.0685526952 0.0086660347 0.2010860000 233141735 0 1784082432 -0.0175435096 0.0284316204 0.2795263827 50 1305031103.8112421036 0.0363424718 0.0403439761 0.0685526952 0.0087857772 0.2015770000 233142361 0 1785864192 -0.0168319084 0.0273052771 0.2655138075 51 1305031103.8432509899 0.0284879077 0.0401115041 0.0685526952 0.0087852232 0.2035640000 233068333 0 1784344576 -0.0194330923 0.0266878810 0.2500098944 52 1305031103.8753609657 0.0327070206 0.0399691102 0.0685526952 0.0089575015 0.2024920000 233113349 0 1783828480 -0.0195962694 0.0163110811 0.2405598164 53 1305031103.9112210274 0.0336285792 0.0398494776 0.0685526952 0.0093136712 0.1980640000 233073621 0 1785483264 -0.0169666745 0.0087893028 0.2269614786 54 1305031103.9432110786 0.0299595557 0.0396663309 0.0685526952 0.0092488845 0.1956440000 233122957 0 1784856576 -0.0143425968 0.0055429600 0.2108614445 55 1305031103.9753730297 0.0311121922 0.0395108011 0.0685526952 0.0093508250 0.2003310000 233098883 0 1784246272 -0.0096243564 -0.0005505383 0.1980264485 56 1305031104.0112318993 0.0304454453 0.0393489197 0.0685526952 0.0094992634 0.1972530000 233081139 0 1786011648 -0.0065068789 -0.0055556186 0.1842629910 57 1305031104.0432488918 0.0262183733 0.0391185593 0.0685526952 0.0094736517 0.2198940000 233552637 0 1785204736 -0.0024636388 -0.0078180134 0.1668121219 58 1305031104.0754249096 0.0215393677 0.0388154698 0.0685526952 0.0094280616 0.4549890000 233560009 0 1785491456 -0.0004496146 -0.0077504776 0.1510075927 59 1305031104.1112349033 0.0238699820 0.0385621564 0.0685526952 0.0095894762 0.4102900000 233621813 0 1784668160 0.0042126281 -0.0129209058 0.1404516995 60 1305031104.1432299614 0.0172513723 0.0382069767 0.0685526952 0.0095681307 0.3461550000 235385098 0 1784434688 0.0014787968 -0.0175580271 0.1243782938 61 1305031104.1754240990 0.0134011367 0.0378003236 0.0685526952 0.0095101012 0.2671510000 235341578 0 1783451648 0.0009228960 -0.0199981555 0.1102358997 62 1305031104.2112829685 0.0134240976 0.0374071586 0.0685526952 0.0095927395 0.3432250000 235333124 0 1782919168 0.0028766454 -0.0247331597 0.0966456756 63 1305031104.2431960106 0.0125154685 0.0370120524 0.0685526952 0.0095477216 0.2163320000 233591471 0 1782767616 0.0036397320 -0.0272235163 0.0834865645 64 1305031104.2755460739 0.0131813893 0.0366396983 0.0685526952 0.0094726200 0.1972500000 233587585 0 1784307712 0.0040585352 -0.0272593051 0.0693521500 65 1305031104.3112189770 0.0152191091 0.0363101508 0.0685526952 0.0094699447 0.1939200000 233620007 0 1786052608 0.0056457268 -0.0294203348 0.0579404980 66 1305031104.3433420658 0.0199742764 0.0360626375 0.0685526952 0.0094550914 0.1993390000 233627833 0 1785196544 0.0090721073 -0.0292417146 0.0461949706 67 1305031104.3758370876 0.0207486134 0.0358340700 0.0685526952 0.0096073016 0.1932530000 233662183 0 1786941440 0.0089413524 -0.0317181051 0.0345238745 68 1305031104.4115090370 0.0200361572 0.0356017478 0.0685526952 0.0096148357 0.2314780000 234005423 0 1783631872 0.0064578983 -0.0338101536 0.0243566353 69 1305031104.4432880878 0.0210281145 0.0353905357 0.0685526952 0.0095522660 0.4701280000 234113555 0 1784795136 0.0023652539 -0.0335297436 0.0147452010 70 1305031104.4754559994 0.0208282173 0.0351825026 0.0685526952 0.0094879523 0.4142920000 234081169 0 1786433536 -0.0006854411 -0.0362405628 0.0037935362 71 1305031104.5113289356 0.0193447005 0.0349594349 0.0685526952 0.0096677959 0.3755460000 235911789 0 1782198272 -0.0004181250 -0.0401079096 -0.0045802365 72 1305031104.5433681011 0.0216937736 0.0347751896 0.0685526952 0.0096399705 0.2452840000 235999820 0 1781493760 -0.0003323358 -0.0402407497 -0.0141184507 73 1305031104.5753428936 0.0245256536 0.0346347850 0.0685526952 0.0097650305 0.3161780000 235765578 0 1781747712 0.0082918555 -0.0434861779 -0.0216012560 74 1305031104.6113359928 0.0280505829 0.0345458093 0.0685526952 0.0100154298 0.2550720000 234454112 0 1781653504 0.0149827776 -0.0473009422 -0.0285427980 75 1305031104.6432430744 0.0324023329 0.0345172296 0.0685526952 0.0100928151 0.4316550000 234431102 0 1781522432 0.0152716227 -0.0435517021 -0.0419021025 76 1305031104.6755249500 0.0306183808 0.0344659290 0.0685526952 0.0100328951 0.3783100000 234433912 0 1783001088 0.0135902325 -0.0463218726 -0.0526102372 77 1305031104.7112770081 0.0340023413 0.0344599084 0.0685526952 0.0101958492 0.3537360000 234443937 0 1785036800 0.0135189574 -0.0445584878 -0.0646613091 78 1305031104.7432799339 0.0369566679 0.0344919181 0.0685526952 0.0101549788 0.2532640000 236653425 0 1783517184 0.0147931213 -0.0434496962 -0.0763213709 79 1305031104.7753269672 0.0396458507 0.0345571578 0.0685526952 0.0101088714 0.2284650000 236505254 0 1782476800 0.0109707583 -0.0415459462 -0.0879631639 80 1305031104.8114650249 0.0447201021 0.0346841946 0.0685526952 0.0102944639 0.3162380000 236462790 0 1780830208 0.0227388572 -0.0384740978 -0.0889519006 81 1305031104.8432579041 0.0490798689 0.0348619190 0.0685526952 0.0102377973 0.1918590000 234873142 0 1780908032 0.0218567066 -0.0345734507 -0.0984633490 82 1305031104.8753499985 0.0534691997 0.0350888370 0.0685526952 0.0102052583 0.3904700000 234919997 0 1780948992 0.0177419856 -0.0292640701 -0.1025867984 83 1305031104.9115340710 0.0570538193 0.0353534754 0.0685526952 0.0101492381 0.3608450000 234958511 0 1783001088 0.0193759538 -0.0250866264 -0.1038364768 84 1305031104.9432621002 0.0594960526 0.0356408870 0.0685526952 0.0100934851 0.3541000000 235576475 0 1786740736 0.0183769390 -0.0221442953 -0.1037037149 85 1305031104.9752020836 0.0642825738 0.0359778480 0.0685526952 0.0100960239 0.2982250000 237217825 0 1783635968 0.0167490263 -0.0156490989 -0.0992770642 86 1305031105.0112900734 0.0620910972 0.0362814904 0.0685526952 0.0100614265 0.2407870000 237143464 0 1784619008 0.0190823488 -0.0160227418 -0.0939504877 87 1305031105.0433731079 0.0637012199 0.0365966597 0.0685526952 0.0100304350 0.3625220000 237087278 0 1783803904 0.0177768525 -0.0116376309 -0.0851798207 88 1305031105.0753200054 0.0596147068 0.0368582285 0.0685526952 0.0099847643 0.2417670000 234877888 0 1783848960 0.0186101422 -0.0131090628 -0.0757706538 89 1305031105.1112990379 0.0534650236 0.0370448217 0.0685526952 0.0099535132 0.1992210000 234902895 0 1785860096 0.0150354886 -0.0160744414 -0.0637321025 90 1305031105.1431059837 0.0591037571 0.0372899209 0.0685526952 0.0099646896 0.1843670000 234883308 0 1784377344 0.0094019687 -0.0065533542 -0.0520405322 91 1305031105.1751589775 0.0616718344 0.0375578541 0.0685526952 0.0100575067 0.1900780000 234885562 0 1781460992 0.0073815119 0.0006011778 -0.0366246700 92 1305031105.2112679482 0.0474634506 0.0376655236 0.0685526952 0.0102354751 0.2118680000 234888428 0 1780056064 0.0015313243 -0.0099873785 -0.0234193560 93 1305031105.2432699203 0.0461799130 0.0377570762 0.0685526952 0.0102066388 0.1942200000 234890822 0 1781940224 -0.0016432129 -0.0065116258 -0.0073595047 94 1305031105.2752881050 0.0430735946 0.0378136349 0.0685526952 0.0103659918 0.1897880000 234893400 0 1783717888 -0.0061568008 -0.0053113261 0.0058297333 95 1305031105.3112900257 0.0384513326 0.0378203475 0.0685526952 0.0104950050 0.1934910000 234896106 0 1785241600 -0.0131074693 -0.0061724945 0.0177168008 96 1305031105.3433020115 0.0268519986 0.0377060938 0.0685526952 0.0104523028 0.1962570000 234926901 0 1784373248 -0.0112494454 -0.0133677945 0.0321646258 97 1305031105.3753380775 0.0215205178 0.0375392322 0.0685526952 0.0104383597 0.2034000000 234900882 0 1783603200 -0.0127064530 -0.0146235721 0.0465111248 98 1305031105.4112861156 0.0258563180 0.0374200188 0.0685526952 0.0105298283 0.2019590000 234903328 0 1785008128 -0.0126529457 -0.0059202756 0.0605926812 99 1305031105.4433159828 0.0164240375 0.0372079382 0.0685526952 0.0104802417 0.2010840000 234949971 0 1784614912 -0.0129964137 -0.0116831269 0.0763164982 100 1305031105.4752800465 0.0149671491 0.0369855303 0.0685526952 0.0104320211 0.2048210000 234933185 0 1783857152 -0.0138239386 -0.0100189131 0.0894353464 101 1305031105.5113320351 0.0163222551 0.0367809434 0.0685526952 0.0104693275 0.1989240000 234954375 0 1785241600 -0.0118556079 -0.0075942362 0.1036793813 102 1305031105.5432820320 0.0130018331 0.0365478149 0.0685526952 0.0104209363 0.2112800000 234987985 0 1784864768 -0.0138880499 -0.0086072963 0.1186864823 103 1305031105.5754489899 0.0117087150 0.0363066586 0.0685526952 0.0103995117 0.2043480000 234978531 0 1784401920 -0.0158434547 -0.0067754467 0.1321467608 104 1305031105.6113779545 0.0156906378 0.0361084276 0.0685526952 0.0103683076 0.2045690000 235021805 0 1786019840 -0.0134721436 -0.0088286363 0.1479492635 105 1305031105.6432731152 0.0147790844 0.0359052910 0.0685526952 0.0103277616 0.2062720000 235017567 0 1784868864 -0.0162262823 -0.0064346697 0.1619787961 106 1305031105.6751658916 0.0182408914 0.0357386457 0.0685526952 0.0103003875 0.2052090000 234993365 0 1784090624 -0.0142239286 -0.0038803229 0.1756630242 107 1305031105.7113089561 0.0247293487 0.0356357551 0.0685526952 0.0103156337 0.1972730000 234960583 0 1785892864 -0.0108105000 -0.0048305560 0.1918559670 108 1305031105.7433118820 0.0220338199 0.0355098113 0.0685526952 0.0103279924 0.2065870000 234957689 0 1785126912 -0.0117220012 0.0028952872 0.2040916383 109 1305031105.7753388882 0.0273171328 0.0354346491 0.0685526952 0.0102931782 0.1972510000 234946979 0 1786892288 -0.0096449368 0.0015780786 0.2191943228 110 1305031105.8112831116 0.0269122124 0.0353571724 0.0685526952 0.0102520871 0.1910970000 234981421 0 1783992320 -0.0121015012 0.0043957168 0.2327856421 111 1305031105.8432710171 0.0301841889 0.0353105689 0.0685526952 0.0102106670 0.1913850000 234962119 0 1781346304 -0.0097292336 0.0067096562 0.2469343096 112 1305031105.8753368855 0.0278781764 0.0352442083 0.0685526952 0.0102068131 0.2243100000 235429796 0 1780441088 -0.0093456414 0.0147326719 0.2597864270 113 1305031105.9112620354 0.0306085609 0.0352031849 0.0685526952 0.0102544311 0.4764380000 235414482 0 1780785152 -0.0094536757 0.0179577172 0.2742670476 114 1305031105.9432721138 0.0309980251 0.0351662975 0.0685526952 0.0102196293 0.4288570000 235416532 0 1783095296 -0.0106229633 0.0226699039 0.2864606678 115 1305031105.9753289223 0.0333083458 0.0351501414 0.0685526952 0.0101862452 0.4102760000 235534146 0 1784926208 -0.0111560384 0.0265184250 0.2987992764 116 1305031106.0112850666 0.0362312868 0.0351594616 0.0685526952 0.0101889406 0.3800200000 237908307 0 1785122816 -0.0122856926 0.0308046751 0.3115769923 117 1305031106.0433549881 0.0396102369 0.0351975024 0.0685526952 0.0101450992 0.2862970000 237848022 0 1783787520 -0.0134143122 0.0332088508 0.3233235776 118 1305031106.0753300190 0.0423500910 0.0352581176 0.0685526952 0.0101123236 0.4451710000 237730394 0 1782751232 -0.0135237779 0.0375436246 0.3360783160 119 1305031106.1113269329 0.0438545309 0.0353303563 0.0685526952 0.0101086233 0.2141250000 235427438 0 1782702080 -0.0151181212 0.0431787074 0.3468430936 120 1305031106.1433548927 0.0474564433 0.0354314071 0.0685526952 0.0100793875 0.2269830000 235904768 0 1784836096 -0.0190038141 0.0447822660 0.3580273986 121 1305031106.1755340099 0.0514867529 0.0355640959 0.0685526952 0.0100486867 0.4916770000 235896395 0 1785737216 -0.0203268602 0.0466440879 0.3682726920 122 1305031106.2112751007 0.0577398576 0.0357458644 0.0685526952 0.0100145441 0.4808650000 235949685 0 1785511936 -0.0213018842 0.0464273542 0.3784663975 123 1305031106.2432670593 0.0591353476 0.0359360228 0.0685526952 0.0100098939 0.4544540000 235971159 0 1784770560 -0.0227683354 0.0498485267 0.3860277534 124 1305031106.2763850689 0.0586430058 0.0361191436 0.0685526952 0.0099732942 0.4347880000 236663495 0 1785257984 -0.0233849324 0.0551668033 0.3921904564 125 1305031106.3112380505 0.0598176569 0.0363087317 0.0685526952 0.0099429878 0.3067570000 238474089 0 1784500224 -0.0225781687 0.0582256988 0.3984903395 126 1305031106.3432579041 0.0570472889 0.0364733235 0.0685526952 0.0099665554 0.2914140000 238495548 0 1785892864 -0.0246579386 0.0638382286 0.4015707970 127 1305031106.3753879070 0.0611005612 0.0366672387 0.0685526952 0.0099516341 0.4193460000 238370596 0 1781862400 -0.0196918845 0.0631951019 0.4046529233 128 1305031106.4113199711 0.0696506575 0.0369249217 0.0696506575 0.0099549263 0.2402540000 236359688 0 1781960704 -0.0191219077 0.0552709699 0.4070059061 129 1305031106.4432780743 0.0709390566 0.0371885972 0.0709390566 0.0100014123 0.4862130000 236406839 0 1782931456 -0.0242709573 0.0514975414 0.4047942162 130 1305031106.4753448963 0.0704563707 0.0374445031 0.0709390566 0.0099933945 0.4423830000 236409673 0 1785094144 -0.0275174025 0.0492394790 0.4012296796 131 1305031106.5111289024 0.0713751912 0.0377035160 0.0713751912 0.0099903160 0.4439580000 236368154 0 1786658816 -0.0292771012 0.0439748578 0.3951627612 132 1305031106.5433020592 0.0682611614 0.0379350133 0.0713751912 0.0099594582 0.4330890000 237256235 0 1785020416 -0.0265142173 0.0427291542 0.3861796856 133 1305031106.5752820969 0.0651092529 0.0381393309 0.0713751912 0.0099250017 0.3074760000 239178535 0 1784008704 -0.0261621140 0.0402168855 0.3751735389 134 1305031106.6111509800 0.0589571558 0.0382946878 0.0713751912 0.0099341429 0.2907310000 239242036 0 1783062528 -0.0272513293 0.0403817147 0.3643299341 135 1305031106.6432070732 0.0605762899 0.0384597367 0.0713751912 0.0099620419 0.4881650000 239144022 0 1785020416 -0.0258949939 0.0328719094 0.3531294167 136 1305031106.6752789021 0.0540619083 0.0385744586 0.0713751912 0.0099372328 0.2112070000 236376812 0 1785733120 -0.0289532728 0.0327752531 0.3392934799 137 1305031106.7115080357 0.0533279665 0.0386821484 0.0713751912 0.0099557201 0.2040180000 236379290 0 1784819712 -0.0283967461 0.0283687599 0.3281677067 138 1305031106.7433409691 0.0499447398 0.0387637614 0.0713751912 0.0099366446 0.2049550000 236381540 0 1783660544 -0.0302512459 0.0245143007 0.3125179112 139 1305031106.7753899097 0.0468868501 0.0388222009 0.0713751912 0.0099238659 0.2089050000 236409895 0 1784934400 -0.0253025796 0.0220878292 0.2974879146 140 1305031106.8112890720 0.0424827859 0.0388483479 0.0713751912 0.0099045950 0.2086940000 236448905 0 1784320000 -0.0238916054 0.0206362046 0.2820820510 141 1305031106.8434159756 0.0482059047 0.0389147135 0.0713751912 0.0100088023 0.2099680000 236387654 0 1783021568 -0.0205591321 0.0088668726 0.2687895894 142 1305031106.8759050369 0.0428794660 0.0389426343 0.0713751912 0.0100068498 0.2083810000 236390180 0 1784705024 -0.0185605846 0.0070388690 0.2504639924 143 1305031106.9112429619 0.0351545289 0.0389161441 0.0713751912 0.0100133986 0.2055120000 236485215 0 1786458112 -0.0190600604 0.0072843339 0.2306072861 144 1305031106.9434390068 0.0341027603 0.0388827178 0.0713751912 0.0100592047 0.2137150000 236394280 0 1783291904 -0.0186147336 0.0012266655 0.2150561959 145 1305031106.9755470753 0.0355361104 0.0388596378 0.0713751912 0.0100306333 0.2118160000 236396326 0 1785188352 -0.0159369055 -0.0067886263 0.1990198493 146 1305031107.0115759373 0.0229837969 0.0387508991 0.0713751912 0.0100380520 0.2332410000 236465017 0 1784717312 -0.0174361318 -0.0025137179 0.1762808710 147 1305031107.0432810783 0.0240506716 0.0386508976 0.0713751912 0.0100100211 0.2093100000 236456107 0 1784078336 -0.0166057609 -0.0101128388 0.1618745625 148 1305031107.0754320621 0.0190608725 0.0385185325 0.0713751912 0.0099787267 0.2065520000 236402616 0 1785192448 -0.0199807882 -0.0143677369 0.1457915008 149 1305031107.1112289429 0.0152331786 0.0383622550 0.0713751912 0.0099528690 0.2100560000 236463463 0 1784594432 -0.0178875700 -0.0151465880 0.1290178448 150 1305031107.1432600021 0.0131519763 0.0381941865 0.0713751912 0.0099265270 0.2154910000 236538169 0 1784332288 -0.0149377594 -0.0153317172 0.1133478731 151 1305031107.1753990650 0.0148823913 0.0380398037 0.0713751912 0.0099226205 0.2041120000 236436903 0 1786097664 -0.0133571690 -0.0241022520 0.1004261374 152 1305031107.2113580704 0.0149484975 0.0378878872 0.0713751912 0.0099487287 0.2010660000 236411452 0 1784946688 -0.0104143266 -0.0272983629 0.0867650062 153 1305031107.2433779240 0.0129407113 0.0377248338 0.0713751912 0.0099324792 0.2025660000 236450927 0 1786732544 -0.0094480161 -0.0281460565 0.0717425793 154 1305031107.2753980160 0.0154334093 0.0375800843 0.0713751912 0.0099284217 0.1954750000 236415484 0 1783300096 -0.0054617990 -0.0310634524 0.0607973635 155 1305031107.3112258911 0.0141825881 0.0374291327 0.0713751912 0.0099431543 0.1939050000 236417834 0 1783934976 -0.0045940001 -0.0369191580 0.0490852147 156 1305031107.3435089588 0.0169184934 0.0372976542 0.0713751912 0.0099766660 0.2219410000 236879620 0 1786585088 0.0008178980 -0.0427552164 0.0373128243 157 1305031107.3754129410 0.0186982341 0.0371791866 0.0713751912 0.0100158072 0.4613880000 236855582 0 1777557504 0.0013936558 -0.0360118710 0.0237894002 158 1305031107.4112710953 0.0191160794 0.0370648631 0.0713751912 0.0100009459 0.4230750000 236857284 0 1778896896 0.0027463085 -0.0365659371 0.0162804257 159 1305031107.4434189796 0.0227988064 0.0369751395 0.0713751912 0.0099772479 0.3998750000 236986538 0 1780928512 0.0067901667 -0.0359947048 0.0102095902 160 1305031107.4753770828 0.0237329919 0.0368923761 0.0713751912 0.0099514326 0.4029070000 239626415 0 1785716736 0.0094904788 -0.0362265445 0.0074287155 161 1305031107.5113520622 0.0284331013 0.0368398340 0.0713751912 0.0099344849 0.3529100000 239883693 0 1783074816 0.0095158815 -0.0302865151 0.0040947865 162 1305031107.5436050892 0.0268146154 0.0367779499 0.0713751912 0.0099203607 0.2036060000 239663652 0 1784827904 0.0145034194 -0.0328551047 0.0043714559 163 1305031107.5754539967 0.0223418083 0.0366893847 0.0713751912 0.0099109956 0.4192120000 239731326 0 1783201792 0.0173148718 -0.0372420065 0.0051435120 164 1305031107.6112709045 0.0289114248 0.0366419581 0.0713751912 0.0099081923 0.2773480000 237309972 0 1780523008 0.0164983664 -0.0285503976 0.0041927155 165 1305031107.6433229446 0.0267338753 0.0365819091 0.0713751912 0.0098803827 0.4567790000 237443247 0 1782808576 0.0182175804 -0.0288450941 0.0058329967 166 1305031107.6755681038 0.0244488697 0.0365088185 0.0713751912 0.0098555811 0.4242940000 237467833 0 1784840192 0.0165345389 -0.0284965672 0.0083253598 167 1305031107.7113070488 0.0248225946 0.0364388411 0.0713751912 0.0098316715 0.4283460000 238083821 0 1785880576 0.0161040965 -0.0246551279 0.0105115594 168 1305031107.7435379028 0.0268095583 0.0363815239 0.0713751912 0.0098095096 0.3082900000 240291791 0 1783767040 0.0138972783 -0.0200074278 0.0115496218 169 1305031107.7758018970 0.0219783410 0.0362962980 0.0713751912 0.0097879560 0.2862420000 240316686 0 1782607872 0.0139537314 -0.0222842768 0.0155576235 170 1305031107.8115959167 0.0227202196 0.0362164387 0.0713751912 0.0097644703 0.4522200000 240296720 0 1780826112 0.0151312165 -0.0190816056 0.0181690417 171 1305031107.8433320522 0.0214167405 0.0361298908 0.0713751912 0.0097369836 0.2865330000 237431627 0 1780666368 0.0166610330 -0.0193806905 0.0194848999 172 1305031107.8753581047 0.0185899809 0.0360279146 0.0713751912 0.0097211639 0.2146870000 237418125 0 1782661120 0.0207259413 -0.0224148929 0.0223355647 173 1305031107.9115409851 0.0171954706 0.0359190565 0.0713751912 0.0097436275 0.2028250000 237406279 0 1784033280 0.0241016168 -0.0221332461 0.0244725645 174 1305031107.9431219101 0.0167766213 0.0358090425 0.0713751912 0.0097420129 0.2015710000 237375133 0 1785937920 0.0291640088 -0.0230315123 0.0263667088 175 1305031107.9758069515 0.0142011754 0.0356855690 0.0713751912 0.0097531207 0.1978570000 237343115 0 1785085952 0.0338959284 -0.0238390733 0.0286562480 176 1305031108.0113201141 0.0141616408 0.0355632739 0.0713751912 0.0097441013 0.2277150000 237777344 0 1786847232 0.0403504074 -0.0230825450 0.0302505698 177 1305031108.0434179306 0.0182800330 0.0354656285 0.0713751912 0.0097261631 0.4561700000 237758046 0 1781870592 0.0515079089 -0.0185237080 0.0321166143 178 1305031108.0753519535 0.0152116986 0.0353518424 0.0713751912 0.0097356117 0.3794710000 237760260 0 1782808576 0.0592447557 -0.0197985657 0.0363406464 179 1305031108.1113779545 0.0136696491 0.0352307128 0.0713751912 0.0097182087 0.3790640000 237762278 0 1785339904 0.0624488741 -0.0217942800 0.0392299034 180 1305031108.1433339119 0.0190088153 0.0351405912 0.0713751912 0.0097064764 0.3715440000 238650427 0 1785741312 0.0755373985 -0.0139033590 0.0415707491 181 1305031108.1760580540 0.0243560243 0.0350810079 0.0713751912 0.0097365602 0.2898070000 241039965 0 1783717888 0.0829579234 -0.0095013417 0.0449302793 182 1305031108.2114748955 0.0202963930 0.0349997738 0.0713751912 0.0097215564 0.2947150000 241007440 0 1783386112 0.0949613452 -0.0138278063 0.0483711213 183 1305031108.2433469296 0.0138312671 0.0348840989 0.0713751912 0.0097016752 0.1934130000 240892717 0 1785180160 0.1081342250 -0.0200021155 0.0539511591 184 1305031108.2753579617 0.0164694730 0.0347840194 0.0713751912 0.0096926251 0.3906420000 240829904 0 1781915648 0.1191796511 -0.0113793518 0.0582689047 185 1305031108.3113319874 0.0222073998 0.0347160377 0.0713751912 0.0097668479 0.2588810000 238277642 0 1782169600 0.1242259443 -0.0079437159 0.0632262081 186 1305031108.3432779312 0.0229419973 0.0346527364 0.0713751912 0.0097475700 0.4591520000 238272413 0 1782263808 0.1327932179 -0.0058434983 0.0678677186 187 1305031108.3754100800 0.0247266255 0.0345996556 0.0713751912 0.0097232405 0.4256860000 238296531 0 1784274944 0.1394611448 -0.0059780567 0.0732066855 188 1305031108.4113609791 0.0249243323 0.0345481911 0.0713751912 0.0097033508 0.4201660000 238304497 0 1786200064 0.1523538530 -0.0059312847 0.0783022493 189 1305031108.4436099529 0.0193941146 0.0344680108 0.0713751912 0.0097240407 0.4342060000 239215465 0 1784029184 0.1685901731 -0.0078074951 0.0797959194 190 1305031108.4754710197 0.0186715107 0.0343848713 0.0713751912 0.0097165506 0.3480250000 241891491 0 1782636544 0.1805433184 -0.0087332781 0.0837312043 191 1305031108.5113780499 0.0223675575 0.0343219534 0.0713751912 0.0098848944 0.3428830000 241822052 0 1781862400 0.1952750981 -0.0148506118 0.0851367563 192 1305031108.5437369347 0.0256861988 0.0342769755 0.0713751912 0.0098812941 0.2160730000 241676739 0 1783476224 0.2047775239 -0.0165215712 0.0881869271 193 1305031108.5754139423 0.0242106132 0.0342248182 0.0713751912 0.0099365873 0.4328360000 241666788 0 1779261440 0.2133382559 -0.0055749347 0.0858098492 194 1305031108.6114070415 0.0253643543 0.0341791457 0.0713751912 0.0100442678 0.2693090000 238795700 0 1779437568 0.2290112823 -0.0063786479 0.0862192661 195 1305031108.6433029175 0.0299282130 0.0341573461 0.0713751912 0.0100720303 0.4552510000 238759226 0 1779908608 0.2343704253 -0.0021076058 0.0881296769 196 1305031108.6753749847 0.0288036987 0.0341300315 0.0713751912 0.0100646933 0.4270860000 238762324 0 1782394880 0.2469717711 0.0010441320 0.0870401561 197 1305031108.7114109993 0.0328834392 0.0341237037 0.0713751912 0.0101278894 0.4187350000 238764910 0 1784168448 0.2568122447 -0.0005473974 0.0912226588 198 1305031108.7435019016 0.0391925611 0.0341493039 0.0713751912 0.0101132813 0.4112960000 238943824 0 1786150912 0.2609728873 -0.0030479822 0.0919496045 199 1305031108.7754929066 0.0366562232 0.0341619015 0.0713751912 0.0101052198 0.3972380000 240901049 0 1784045568 0.2711855173 0.0009664805 0.0911279321 200 1305031108.8112440109 0.0456535891 0.0342193600 0.0713751912 0.0101050662 0.2392310000 242727052 0 1783685120 0.2713724077 -0.0005262373 0.0961083025 201 1305031108.8432641029 0.0534892268 0.0343152300 0.0713751912 0.0118527624 0.2554090000 242587558 0 1785466880 0.2720210552 -0.0019004163 0.0967738777 202 1305031108.8765149117 0.0530732945 0.0344080917 0.0713751912 0.0119601366 0.2103670000 242495543 0 1784311808 0.2718595266 -0.0015631840 0.0930557549 203 1305031108.9113640785 0.0550173931 0.0345096153 0.0713751912 0.0121035242 0.4066380000 242426480 0 1780457472 0.2715605199 -0.0078935120 0.0908483714 204 1305031108.9432430267 0.0601462610 0.0346352851 0.0713751912 0.0121686494 0.2518910000 238777116 0 1780850688 0.2676068842 -0.0119713023 0.0854168087 205 1305031108.9752678871 0.0605058931 0.0347614832 0.0713751912 0.0121585023 0.1763130000 238779122 0 1782624256 0.2616297603 -0.0043402039 0.0848204494 206 1305031109.0112690926 0.0484596640 0.0348279793 0.0713751912 0.0121354845 0.1945360000 238807093 0 1784250368 0.2675237358 -0.0026883623 0.0836383551 207 1305031109.0432770252 0.0538451299 0.0349198495 0.0713751912 0.0121385713 0.2011100000 238783338 0 1786011648 0.2557681203 -0.0035083937 0.0831407458 208 1305031109.0754098892 0.0509313084 0.0349968277 0.0713751912 0.0121117075 0.2060060000 238785704 0 1784754176 0.2505889535 0.0021845484 0.0780532062 209 1305031109.1112821102 0.0482761674 0.0350603652 0.0713751912 0.0120958004 0.1876370000 238787718 0 1786953728 0.2428655624 -0.0039549889 0.0778768882 210 1305031109.1433339119 0.0533667095 0.0351475383 0.0713751912 0.0120711260 0.1940790000 238790172 0 1783377920 0.2285305113 -0.0070928186 0.0749462694 211 1305031109.1754639149 0.0478758030 0.0352078618 0.0713751912 0.0120595466 0.1966050000 238792110 0 1784266752 0.2222970128 0.0003866006 0.0735049471 212 1305031109.2113790512 0.0400007516 0.0352304698 0.0713751912 0.0120992890 0.1893970000 238794272 0 1786408960 0.2158547789 0.0140841883 0.0742340386 213 1305031109.2432899475 0.0411333032 0.0352581826 0.0713751912 0.0120813269 0.1925210000 238796334 0 1783504896 0.2025069743 0.0067921891 0.0744962990 214 1305031109.2753078938 0.0408856496 0.0352844792 0.0713751912 0.0121474745 0.1901130000 238798676 0 1780850688 0.1947008669 -0.0101297442 0.0719666630 215 1305031109.3113288879 0.0369908549 0.0352924158 0.0713751912 0.0122305205 0.2174980000 238800478 0 1781960704 0.1796599478 -0.0058178613 0.0702543110 216 1305031109.3432478905 0.0342401043 0.0352875440 0.0713751912 0.0122033895 0.2181230000 239266892 0 1784385536 0.1676665246 0.0018095626 0.0676140487 217 1305031109.3753969669 0.0257344879 0.0352435207 0.0713751912 0.0121922989 0.4486720000 239237922 0 1782607872 0.1632714123 -0.0013061711 0.0706640184 218 1305031109.4113290310 0.0224505384 0.0351848373 0.0713751912 0.0122002686 0.4327040000 239240024 0 1784631296 0.1496431082 -0.0034738551 0.0664320588 219 1305031109.4433019161 0.0177381430 0.0351051720 0.0713751912 0.0121742327 0.4380170000 239242450 0 1786331136 0.1394770741 0.0025497833 0.0670236647 220 1305031109.4753630161 0.0180527288 0.0350276609 0.0713751912 0.0121559777 0.4266330000 239423868 0 1783832576 0.1269706488 -0.0011093151 0.0680565834 221 1305031109.5112729073 0.0152821019 0.0349383145 0.0713751912 0.0121433382 0.4376660000 241029665 0 1783746560 0.1150529236 -0.0062114014 0.0649861246 222 1305031109.5432939529 0.0100530628 0.0348262188 0.0713751912 0.0121178347 0.3070360000 243420976 0 1783447552 0.1069559902 -0.0042700730 0.0619693808 223 1305031109.5753619671 0.0100167580 0.0347149656 0.0713751912 0.0120919454 0.2949230000 243098426 0 1781841920 0.0932559371 -0.0017604465 0.0591783002 224 1305031109.6113100052 0.0081381332 0.0345963190 0.0713751912 0.0120907430 0.5508900000 242876804 0 1780629504 0.0793342516 -0.0013039922 0.0566255897 225 1305031109.6432290077 0.0044781170 0.0344624604 0.0713751912 0.0120658088 0.2694150000 239287883 0 1780572160 0.0717923343 0.0009356197 0.0544062145 226 1305031109.6752629280 0.0128946388 0.0343670275 0.0713751912 0.0120543503 0.2234280000 239672292 0 1782546432 0.0534117706 0.0060533639 0.0511251576 227 1305031109.7113120556 0.0094153741 0.0342571083 0.0713751912 0.0120653007 0.4622300000 239650038 0 1780580352 0.0423055813 0.0071864054 0.0498867780 228 1305031109.7432739735 0.0082424097 0.0341430088 0.0713751912 0.0120428789 0.4390490000 239652284 0 1782362112 0.0311410017 0.0072709979 0.0516460016 229 1305031109.7752768993 0.0047278288 0.0340145582 0.0713751912 0.0120223505 0.4246510000 239686979 0 1783562240 0.0230892617 0.0057033985 0.0524984114 230 1305031109.8113710880 0.0072438880 0.0338981640 0.0713751912 0.0120227439 0.4354530000 240827431 0 1784913920 0.0090521043 0.0089517944 0.0536051132 231 1305031109.8432960510 0.0055421987 0.0337754109 0.0713751912 0.0120019938 0.3406430000 243505621 0 1783922688 -0.0044214525 0.0082549388 0.0529028811 232 1305031109.8753058910 0.0071919807 0.0336608271 0.0713751912 0.0119874106 0.3544110000 243436062 0 1781518336 -0.0174526535 0.0098612271 0.0578825139 233 1305031109.9112648964 0.0082104020 0.0335515979 0.0713751912 0.0119738162 0.2233560000 243335317 0 1783263232 -0.0283612479 0.0055452944 0.0600294732 234 1305031109.9432990551 0.0130841983 0.0334641303 0.0713751912 0.0120017641 0.4716660000 243266246 0 1779490816 -0.0399174094 0.0138295498 0.0619102828 235 1305031109.9752581120 0.0131439697 0.0333776616 0.0713751912 0.0120012275 0.2816480000 240102350 0 1779195904 -0.0523619205 0.0116028842 0.0666220337 236 1305031110.0112559795 0.0194611140 0.0333186931 0.0713751912 0.0119879858 0.5057950000 240086684 0 1778376704 -0.0628986135 0.0114670657 0.0710133687 237 1305031110.0432989597 0.0197644681 0.0332615023 0.0713751912 0.0119689053 0.4629250000 240087926 0 1781174272 -0.0757341459 0.0128230387 0.0736609325 238 1305031110.0753190517 0.0209992956 0.0332099804 0.0713751912 0.0119495524 0.4730920000 240089584 0 1782648832 -0.0873956457 0.0151890079 0.0762546882 239 1305031110.1113250256 0.0235314630 0.0331694846 0.0713751912 0.0119533366 0.4470320000 241039325 0 1784266752 -0.0996162891 0.0133610852 0.0795788020 240 1305031110.1434319019 0.0240003671 0.0331312799 0.0713751912 0.0119502882 0.3480800000 244041729 0 1784074240 -0.1112921089 0.0065168287 0.0830600783 241 1305031110.1756410599 0.0267338697 0.0331047346 0.0713751912 0.0119263731 0.4057940000 243980452 0 1782747136 -0.1183692515 0.0126067642 0.0834828839 242 1305031110.2116370201 0.0260841642 0.0330757240 0.0713751912 0.0119377159 0.2360070000 243786807 0 1784717312 -0.1337617338 0.0102383038 0.0860961080 243 1305031110.2433230877 0.0278440230 0.0330541944 0.0713751912 0.0119176873 0.5623270000 243717888 0 1781276672 -0.1432876438 0.0075623388 0.0883953869 244 1305031110.2793209553 0.0317236558 0.0330487413 0.0713751912 0.0119133772 0.3276760000 240564348 0 1781383168 -0.1513178647 0.0075767948 0.0878167301 245 1305031110.3114039898 0.0316736028 0.0330431285 0.0713751912 0.0118901226 0.4992410000 240544038 0 1782419456 -0.1605646014 0.0085898209 0.0871945694 246 1305031110.3433549404 0.0314387530 0.0330366067 0.0713751912 0.0118682967 0.4654570000 240545344 0 1783640064 -0.1706052423 0.0119129261 0.0858281627 247 1305031110.3792810440 0.0336209759 0.0330389726 0.0713751912 0.0118913345 0.4474660000 240546374 0 1785417728 -0.1828247160 0.0130260140 0.0862386897 248 1305031110.4114689827 0.0355872475 0.0330492479 0.0713751912 0.0118741978 0.4295580000 241625539 0 1787056128 -0.1905550212 0.0157578345 0.0825956613 249 1305031110.4432599545 0.0391446315 0.0330737273 0.0713751912 0.0118642256 0.3447260000 244858117 0 1785700352 -0.1989615709 0.0170533098 0.0839126855 250 1305031110.4793310165 0.0447517224 0.0331204393 0.0713751912 0.0118963549 0.3522000000 244538526 0 1784487936 -0.2095748633 0.0147095304 0.0872288868 251 1305031110.5114290714 0.0433647186 0.0331612531 0.0713751912 0.0118879139 0.2376190000 245112426 0 1784553472 -0.2204099745 0.0136334356 0.0836221129 252 1305031110.5434079170 0.0487679318 0.0332231844 0.0713751912 0.0118718699 0.4787180000 244359578 0 1776218112 -0.2262032926 0.0194903482 0.0845574811 253 1305031110.5794260502 0.0535054579 0.0333033515 0.0713751912 0.0118820834 0.2854870000 241035062 0 1778008064 -0.2359479815 0.0261959322 0.0856186599 254 1305031110.6113069057 0.0586732328 0.0334032329 0.0713751912 0.0118945511 0.4758060000 241044305 0 1777082368 -0.2438505590 0.0249319170 0.0942572504 255 1305031110.6434180737 0.0602113456 0.0335083628 0.0713751912 0.0118773480 0.4554820000 241025266 0 1778720768 -0.2525444329 0.0259460267 0.0970590264 256 1305031110.6796059608 0.0606508292 0.0336143880 0.0713751912 0.0118858189 0.4422370000 241026512 0 1780469760 -0.2599694133 0.0314973891 0.0920326114 257 1305031110.7114119530 0.0634236187 0.0337303773 0.0713751912 0.0118656359 0.4346700000 241083359 0 1782325248 -0.2655222118 0.0304179359 0.0965988934 258 1305031110.7432489395 0.0648409575 0.0338509609 0.0713751912 0.0118589890 0.4127240000 245189479 0 1784532992 -0.2700555623 0.0298925377 0.0985779688 259 1305031110.7791929245 0.0676174089 0.0339813333 0.0713751912 0.0118404137 0.3267500000 245500342 0 1785053184 -0.2731741071 0.0338918678 0.0989561006 260 1305031110.8113861084 0.0687582791 0.0341150908 0.0713751912 0.0118199212 0.2885930000 245981598 0 1787105280 -0.2755317986 0.0353755057 0.1000944376 261 1305031110.8432180882 0.0710619092 0.0342566495 0.0713751912 0.0118019200 0.5088880000 245254062 0 1779798016 -0.2759795189 0.0343884453 0.1033072472 262 1305031110.8793129921 0.0720338002 0.0344008371 0.0720338002 0.0117852783 0.3113060000 241145837 0 1780928512 -0.2757606208 0.0377131514 0.1035703719 263 1305031110.9113330841 0.0706844926 0.0345387977 0.0720338002 0.0117664734 0.1944140000 241157031 0 1781583872 -0.2749880552 0.0365369022 0.1030599251 264 1305031110.9438619614 0.0710970834 0.0346772761 0.0720338002 0.0117600774 0.2121730000 241150057 0 1783083008 -0.2723256648 0.0386302248 0.1038749963 265 1305031110.9793450832 0.0721594021 0.0348187181 0.0721594021 0.0117627339 0.2066420000 241114467 0 1784999936 -0.2657947540 0.0432320833 0.1040021926 266 1305031111.0114309788 0.0727023110 0.0349611376 0.0727023110 0.0117488202 0.1997250000 241087201 0 1786134528 -0.2579308748 0.0420162901 0.1044170558 267 1305031111.0433270931 0.0723896474 0.0351013193 0.0727023110 0.0117324113 0.2133900000 241093519 0 1784868864 -0.2522248030 0.0414594002 0.1065206528 268 1305031111.0792829990 0.0660823509 0.0352169201 0.0727023110 0.0117177742 0.2037030000 241066692 0 1786654720 -0.2470801324 0.0409963392 0.1037181765 269 1305031111.1115078926 0.0772291496 0.0353730994 0.0772291496 0.0118071115 0.2076680000 241090491 0 1783844864 -0.2233660817 0.0265744384 0.1057668850 270 1305031111.1432569027 0.0765965581 0.0355257789 0.0772291496 0.0117962245 0.2065570000 241070632 0 1785778176 -0.2148066461 0.0201220382 0.1050514579 271 1305031111.1793260574 0.0782428384 0.0356834064 0.0782428384 0.0118777775 0.2753850000 241565002 0 1784348672 -0.1983059943 0.0181410313 0.1019328237 272 1305031111.2114329338 0.0765568987 0.0358336766 0.0782428384 0.0118749056 0.4878320000 241521724 0 1779859456 -0.1884726733 0.0150253512 0.0974144787 273 1305031111.2432360649 0.0733049437 0.0359709340 0.0782428384 0.0118718969 0.4372780000 241560103 0 1781669888 -0.1838875115 0.0123738032 0.1007810831 274 1305031111.2793080807 0.0720598623 0.0361026454 0.0782428384 0.0119059287 0.4442350000 241524872 0 1783390208 -0.1702416092 0.0120372316 0.1005888209 275 1305031111.3115470409 0.0585529469 0.0361842829 0.0782428384 0.0119728105 0.4118640000 242724713 0 1785389056 -0.1699929237 0.0178970508 0.0931913853 276 1305031111.3433969021 0.0543345027 0.0362500446 0.0782428384 0.0119814038 0.3734220000 246043808 0 1783635968 -0.1651825756 0.0230369009 0.0980766192 277 1305031111.3791339397 0.0577198453 0.0363275529 0.0782428384 0.0120588948 0.4088200000 245779182 0 1783279616 -0.1488175690 0.0117648002 0.1025797278 278 1305031111.4112958908 0.0403132923 0.0363418901 0.0782428384 0.0121710014 0.2563520000 245634860 0 1785421824 -0.1522142291 0.0216036309 0.0959205404 279 1305031111.4433860779 0.0602693819 0.0364276517 0.0782428384 0.0122700801 0.5036430000 245581218 0 1778421760 -0.1210946366 0.0145726018 0.1028682142 280 1305031111.4792590141 0.0630926043 0.0365228837 0.0782428384 0.0123822306 0.2719870000 241950436 0 1778683904 -0.1008932963 0.0141424639 0.1044907197 281 1305031111.5112640858 0.0548896156 0.0365882457 0.0782428384 0.0124236857 0.4871690000 241945278 0 1779937280 -0.0943978429 0.0101467967 0.0986974239 282 1305031111.5432500839 0.0469815433 0.0366251014 0.0782428384 0.0124038885 0.4665080000 241947056 0 1782169600 -0.0878133625 0.0108197145 0.0958512947 283 1305031111.5792369843 0.0449741147 0.0366546032 0.0782428384 0.0124913647 0.4645060000 241949586 0 1783947264 -0.0701570362 0.0142079573 0.0946653038 284 1305031111.6112709045 0.0316490047 0.0366369778 0.0782428384 0.0125318541 0.4510380000 242111688 0 1785921536 -0.0727095157 0.0135782706 0.0971318707 285 1305031111.6433949471 0.0437383838 0.0366618950 0.0782428384 0.0126089145 0.4570770000 245489593 0 1783320576 -0.0476923324 0.0058689136 0.1001493558 286 1305031111.6793200970 0.0421631485 0.0366811302 0.0782428384 0.0127272475 0.2794890000 246797368 0 1784053760 -0.0269720741 0.0132788606 0.0958574116 287 1305031111.7117600441 0.0349984318 0.0366752671 0.0782428384 0.0127116069 0.3011010000 246305474 0 1786105856 -0.0211791843 0.0132153304 0.0970084295 288 1305031111.7433860302 0.0462310240 0.0367084468 0.0782428384 0.0127843927 0.5373670000 245875342 0 1780297728 0.0029248139 0.0123597840 0.1039518714 289 1305031111.7794229984 0.0326998308 0.0366945762 0.0782428384 0.0128333444 0.3298020000 242406634 0 1780559872 0.0087224934 0.0183502138 0.1008829847 290 1305031111.8114058971 0.0227816775 0.0366466007 0.0782428384 0.0128441262 0.4818010000 242385856 0 1778896896 0.0104425000 0.0118564591 0.0999955535 291 1305031111.8432989120 0.0202636309 0.0365903018 0.0782428384 0.0128497194 0.4629020000 242387950 0 1780363264 0.0207440667 0.0145059107 0.1008591801 292 1305031111.8794419765 0.0120361876 0.0365062124 0.0782428384 0.0128284531 0.4590790000 242389656 0 1782202368 0.0275191069 0.0122789480 0.0968592986 293 1305031111.9113540649 0.0161846150 0.0364368554 0.0782428384 0.0128270318 0.4611430000 242544042 0 1784152064 0.0316467993 0.0058054631 0.0955743268 294 1305031111.9433000088 0.0137465987 0.0363596777 0.0782428384 0.0128190863 0.4518340000 244091043 0 1784872960 0.0478611477 0.0090856664 0.0981090814 295 1305031111.9794490337 0.0142028444 0.0362845697 0.0782428384 0.0129052776 0.2996490000 246887073 0 1783218176 0.0707669407 0.0119246170 0.1003770456 296 1305031112.0114328861 0.0213497430 0.0362341142 0.0782428384 0.0128979182 0.3316720000 246717628 0 1783435264 0.0888784304 0.0074943458 0.1019935086 297 1305031112.0432701111 0.0197668150 0.0361786688 0.0782428384 0.0128834857 0.2078310000 246416485 0 1785733120 0.0995594040 0.0056550740 0.0947546512 298 1305031112.0793390274 0.0199988894 0.0361243742 0.0782428384 0.0129481096 0.4510020000 246347690 0 1783324672 0.1201376244 0.0093156826 0.0974234194 299 1305031112.1114230156 0.0139661841 0.0360502666 0.0782428384 0.0130386857 0.2996020000 242875746 0 1782910976 0.1144877374 0.0076439148 0.0960573703 300 1305031112.1443419456 0.0134210205 0.0359748358 0.0782428384 0.0130326986 0.4743780000 242854508 0 1781596160 0.1319464743 0.0083434340 0.0957970694 301 1305031112.1793899536 0.0147742806 0.0359044020 0.0782428384 0.0130582383 0.4252020000 242855886 0 1782591488 0.1462584287 0.0073073660 0.0931031257 302 1305031112.2112538815 0.0237782262 0.0358642491 0.0782428384 0.0130619311 0.3779920000 242858308 0 1784066048 0.1482608765 -0.0000940487 0.0963232964 303 1305031112.2433691025 0.0274451803 0.0358364634 0.0782428384 0.0130460710 0.3613050000 243005670 0 1786085376 0.1643357575 -0.0063679675 0.0948279947 304 1305031112.2793529034 0.0298470948 0.0358167615 0.0782428384 0.0130601221 0.3762910000 244986049 0 1782136832 0.1664475352 0.0000769887 0.0969765186 305 1305031112.3113119602 0.0315233618 0.0358026848 0.0782428384 0.0130393617 0.2338800000 247930805 0 1780490240 0.1782622337 -0.0030923756 0.0967101827 306 1305031112.3433229923 0.0296037588 0.0357824269 0.0782428384 0.0130209200 0.2922100000 247300568 0 1782358016 0.1887993664 0.0017501619 0.0974416584 307 1305031112.3793599606 0.0358868465 0.0357827670 0.0782428384 0.0130024543 0.2035120000 246963665 0 1784205312 0.1971978098 0.0022205492 0.0959788412 308 1305031112.4114420414 0.0365471728 0.0357852489 0.0782428384 0.0130030441 0.4481310000 247008668 0 1782435840 0.2085791081 0.0030876426 0.0905020908 309 1305031112.4433910847 0.0273803901 0.0357580487 0.0782428384 0.0130158329 0.3064120000 243389858 0 1783939072 0.2290613353 0.0034794486 0.0912178084 310 1305031112.4794180393 0.0346544087 0.0357544885 0.0782428384 0.0130016281 0.4645720000 243372036 0 1780678656 0.2332987338 0.0061086197 0.0920471400 311 1305031112.5115039349 0.0352467448 0.0357528559 0.0782428384 0.0129831921 0.4363350000 243395031 0 1782312960 0.2418216765 0.0052954853 0.0926093981 312 1305031112.5432119370 0.0351189822 0.0357508243 0.0782428384 0.0129669851 0.4279890000 243402173 0 1783836672 0.2505618930 0.0044574277 0.0945057943 313 1305031112.5792520046 0.0381035917 0.0357583411 0.0782428384 0.0129510911 0.4003250000 243563726 0 1785647104 0.2585823834 0.0064280191 0.0931536332 314 1305031112.6112608910 0.0285064206 0.0357352458 0.0782428384 0.0130147429 0.4023670000 246957351 0 1784193024 0.2771679163 0.0110690584 0.0901317894 315 1305031112.6432459354 0.0257915650 0.0357036786 0.0782428384 0.0130437002 0.2301200000 248606926 0 1783160832 0.2892055213 0.0115514128 0.0876421332 316 1305031112.6799519062 0.0348538011 0.0357009891 0.0782428384 0.0130405315 0.2769390000 248055088 0 1778724864 0.2849440277 0.0103036724 0.0944213271 317 1305031112.7112510204 0.0375434980 0.0357068014 0.0782428384 0.0130326601 0.5047680000 247624874 0 1771651072 0.2863990963 0.0110823270 0.0954290479 318 1305031112.7432448864 0.0373513401 0.0357119729 0.0782428384 0.0130187024 0.2664480000 243870000 0 1773281280 0.2884988785 0.0204525664 0.0951641202 319 1305031112.7793099880 0.0411008820 0.0357288661 0.0782428384 0.0130063190 0.4700750000 243864946 0 1769992192 0.2864656448 0.0128062861 0.0984725207 320 1305031112.8113100529 0.0566689409 0.0357943038 0.0782428384 0.0130564042 0.4359450000 243867588 0 1772003328 0.2704966068 0.0059928927 0.1031509712 321 1305031112.8432860374 0.0490246005 0.0358355197 0.0782428384 0.0130499454 0.4431010000 243869758 0 1773789184 0.2725857794 0.0164845306 0.1024675816 322 1305031112.8794209957 0.0403007381 0.0358493868 0.0782428384 0.0130575026 0.4267850000 244056428 0 1775058944 0.2773519754 0.0165357422 0.1022586673 323 1305031112.9114110470 0.0482024066 0.0358876314 0.0782428384 0.0130458010 0.4479130000 246239437 0 1782345728 0.2659517825 0.0125131290 0.1020827293 324 1305031112.9433209896 0.0522111915 0.0359380128 0.0782428384 0.0130333731 0.3171840000 249077751 0 1784635392 0.2573532760 0.0078132404 0.1047009826 325 1305031112.9792780876 0.0436589755 0.0359617696 0.0782428384 0.0130612359 0.3186770000 248582686 0 1783742464 0.2566336691 0.0093719494 0.1037632748 326 1305031113.0113530159 0.0378057025 0.0359674259 0.0782428384 0.0130434985 0.2128240000 248291663 0 1785901056 0.2532573640 0.0134870382 0.1007061526 327 1305031113.0432310104 0.0405785032 0.0359815270 0.0782428384 0.0130267667 0.5031820000 248222592 0 1784102912 0.2425246984 0.0096917180 0.1004649699 328 1305031113.0792510509 0.0435107350 0.0360044819 0.0782428384 0.0130535349 0.3019910000 244302832 0 1784639488 0.2302162796 0.0006871074 0.1053512394 329 1305031113.1113159657 0.0352369100 0.0360021489 0.0782428384 0.0130356298 0.4912500000 244295922 0 1778425856 0.2241021395 0.0066229450 0.1002425700 330 1305031113.1433060169 0.0279918984 0.0359778754 0.0782428384 0.0130229642 0.4408300000 244297348 0 1780457472 0.2180727124 0.0122948382 0.0963385031 331 1305031113.1793429852 0.0297194943 0.0359589679 0.0782428384 0.0130445987 0.4532250000 244295466 0 1782108160 0.2052367479 0.0020953873 0.0957784429 332 1305031113.2112588882 0.0376100764 0.0359639411 0.0782428384 0.0130414103 0.4245020000 244478544 0 1783885824 0.1850735545 -0.0011883304 0.0942049325 333 1305031113.2432270050 0.0334864408 0.0359565012 0.0782428384 0.0130246055 0.4195270000 246446609 0 1786806272 0.1733693928 0.0046102903 0.0900189430 334 1305031113.2793118954 0.0281497110 0.0359331275 0.0782428384 0.0130715605 0.2841570000 249349324 0 1784598528 0.1668235958 -0.0064787241 0.0901332349 335 1305031113.3114519119 0.0330889076 0.0359246373 0.0782428384 0.0130706242 0.3489740000 249185197 0 1786413056 0.1497271508 -0.0123569006 0.0930056572 336 1305031113.3432519436 0.0257772636 0.0358944368 0.0782428384 0.0130618827 0.2221200000 248797211 0 1783607296 0.1352041364 -0.0032446883 0.0878293514 337 1305031113.3793120384 0.0201905724 0.0358478378 0.0782428384 0.0130728432 0.5083470000 248728332 0 1783758848 0.1187382936 -0.0017302609 0.0859604329 338 1305031113.4116249084 0.0172030441 0.0357926757 0.0782428384 0.0130684820 0.2983680000 244310400 0 1774673920 0.1107241660 -0.0104178414 0.0887259766 339 1305031113.4432659149 0.0132305557 0.0357261208 0.0782428384 0.0130743311 0.1981150000 244312034 0 1776582656 0.0916611254 -0.0016935682 0.0880599990 340 1305031113.4793109894 0.0142515227 0.0356629602 0.0782428384 0.0131081151 0.2456780000 244775672 0 1778679808 0.0693270862 -0.0005320646 0.0848565176 341 1305031113.5115230083 0.0096278815 0.0355866110 0.0782428384 0.0130903662 0.5267490000 244744878 0 1781039104 0.0573627688 -0.0012479834 0.0879854858 342 1305031113.5432419777 0.0082822628 0.0355067737 0.0782428384 0.0130981134 0.5472190000 244747392 0 1782816768 0.0436718576 -0.0061323061 0.0868121237 343 1305031113.5793011189 0.0039832727 0.0354148685 0.0782428384 0.0130943729 0.4960560000 244748450 0 1784594432 0.0314568616 -0.0019645086 0.0877509415 344 1305031113.6112680435 0.0043744678 0.0353246347 0.0782428384 0.0130803560 0.4901420000 244911004 0 1786314752 0.0182359833 -0.0040160995 0.0856696665 345 1305031113.6432220936 0.0050861696 0.0352369870 0.0782428384 0.0130652608 0.5120010000 248118509 0 1783451648 0.0056243613 -0.0024736244 0.0864999294 346 1305031113.6792879105 0.0080579277 0.0351584348 0.0782428384 0.0130527246 0.2995840000 250475776 0 1784979456 -0.0078222081 -0.0045715664 0.0862749070 347 1305031113.7119309902 0.0097389109 0.0350851797 0.0782428384 0.0130403515 0.3328120000 249885794 0 1784164352 -0.0188924540 -0.0054379730 0.0874337479 348 1305031113.7435901165 0.0117427045 0.0350181036 0.0782428384 0.0130219652 0.6336530000 249391260 0 1778917376 -0.0304601789 -0.0025795344 0.0881477520 349 1305031113.7793200016 0.0135689890 0.0349566448 0.0782428384 0.0130128587 0.3137950000 244800359 0 1779290112 -0.0446134582 -0.0049864403 0.0891370401 350 1305031113.8112370968 0.0144877760 0.0348981624 0.0782428384 0.0129952535 0.2187140000 244845473 0 1780793344 -0.0560739674 -0.0036132201 0.0888905749 351 1305031113.8432950974 0.0165143423 0.0348457868 0.0782428384 0.0129793116 0.2310140000 244824291 0 1782824960 -0.0672764778 -0.0009994237 0.0897923037 352 1305031113.8792810440 0.0160080027 0.0347922704 0.0782428384 0.0130068578 0.2550970000 244762840 0 1784713216 -0.0837827101 -0.0070881248 0.0918075070 353 1305031113.9112899303 0.0207006354 0.0347523507 0.0782428384 0.0129965871 0.2224180000 244817267 0 1785999360 -0.0923112705 -0.0006970512 0.0928225517 354 1305031113.9432909489 0.0208421778 0.0347130564 0.0782428384 0.0129793290 0.2256230000 244821765 0 1784504320 -0.1047020704 -0.0008958946 0.0923633724 355 1305031113.9792931080 0.0230880976 0.0346803101 0.0782428384 0.0129649440 0.2226320000 244806179 0 1786675200 -0.1194577441 -0.0009828322 0.0920821428 356 1305031114.0112569332 0.0232232008 0.0346481272 0.0782428384 0.0129569504 0.2188780000 244771176 0 1782943744 -0.1324843466 0.0005515134 0.0915281773 357 1305031114.0433011055 0.0201991554 0.0346076539 0.0782428384 0.0129483933 0.2119980000 244773394 0 1784619008 -0.1503868997 0.0032278136 0.0938286334 358 1305031114.0792849064 0.0183336884 0.0345621959 0.0782428384 0.0129557651 0.2442080000 245234168 0 1786019840 -0.1699870378 0.0029123216 0.0941224322 359 1305031114.1112630367 0.0243795235 0.0345338319 0.0782428384 0.0129382261 0.5179050000 245209870 0 1780449280 -0.1787566245 0.0079695359 0.0954119787 360 1305031114.1432840824 0.0292114206 0.0345190474 0.0782428384 0.0129337569 0.4777810000 245212752 0 1782394880 -0.1853620112 0.0074510113 0.0973468795 361 1305031114.1793370247 0.0349800475 0.0345203244 0.0782428384 0.0129357054 0.4611290000 245214762 0 1783853056 -0.1941806525 0.0050243936 0.0983182341 362 1305031114.2113029957 0.0380394273 0.0345300457 0.0782428384 0.0129351773 0.4383270000 245229992 0 1785802752 -0.2052583098 0.0130104627 0.0964408144 363 1305031114.2433369160 0.0345472507 0.0345300931 0.0782428384 0.0129247873 0.4248440000 249736397 0 1784856576 -0.2205020487 0.0119134085 0.0994010568 364 1305031114.2793900967 0.0363383889 0.0345350609 0.0782428384 0.0129503754 0.2969320000 250484760 0 1780428800 -0.2319392562 0.0098292800 0.0972445607 365 1305031114.3114290237 0.0409176983 0.0345525476 0.0782428384 0.0129357216 0.3022390000 250449822 0 1782538240 -0.2395094037 0.0130161867 0.0998575017 366 1305031114.3433310986 0.0481463335 0.0345896891 0.0782428384 0.0129210547 0.2180150000 249881371 0 1783967744 -0.2435661852 0.0138085959 0.1045764834 367 1305031114.3793199062 0.0537682101 0.0346419467 0.0782428384 0.0129087919 0.5008810000 249915602 0 1781125120 -0.2518586218 0.0128384028 0.1088824496 368 1305031114.4113969803 0.0511245430 0.0346867363 0.0782428384 0.0129008721 0.3195970000 245636268 0 1781870592 -0.2652634680 0.0136320069 0.1097839028 369 1305031114.4433450699 0.0509397052 0.0347307823 0.0782428384 0.0128851844 0.4912680000 245638922 0 1778827264 -0.2748461962 0.0139540024 0.1100166589 370 1305031114.4793319702 0.0523439609 0.0347783855 0.0782428384 0.0128900958 0.4686100000 245640052 0 1780973568 -0.2844111323 0.0108241839 0.1102778688 371 1305031114.5112659931 0.0567896366 0.0348377150 0.0782428384 0.0128736422 0.4530840000 245641990 0 1782329344 -0.2894822061 0.0145631116 0.1133202463 372 1305031114.5432360172 0.0653187931 0.0349196534 0.0782428384 0.0128646609 0.4436780000 247095335 0 1785008128 -0.2919196486 0.0190132204 0.1232880726 373 1305031114.5792369843 0.0661470741 0.0350033730 0.0782428384 0.0128508835 0.3943260000 250773501 0 1783910400 -0.2981792986 0.0176054630 0.1245024502 374 1305031114.6113910675 0.0668814853 0.0350886086 0.0782428384 0.0128353065 0.3455550000 250571168 0 1782534144 -0.3021693826 0.0177441053 0.1243967563 375 1305031114.6441500187 0.0617260560 0.0351596418 0.0782428384 0.0128190773 0.2616880000 251208202 0 1784811520 -0.3101438582 0.0131429508 0.1230763569 376 1305031114.6792509556 0.0640856847 0.0352365728 0.0782428384 0.0128105994 0.5363270000 250308544 0 1782013952 -0.3138686121 0.0110305836 0.1279578209 377 1305031114.7113060951 0.0684361234 0.0353246352 0.0782428384 0.0127984895 0.2831630000 246111514 0 1777868800 -0.3138526976 0.0111544868 0.1318243742 378 1305031114.7432758808 0.0706225634 0.0354180160 0.0782428384 0.0127824758 0.5300780000 246167389 0 1780162560 -0.3143750727 0.0114133935 0.1332613677 379 1305031114.7792890072 0.0710487440 0.0355120285 0.0782428384 0.0127672784 0.4875570000 246196623 0 1781301248 -0.3150064051 0.0140140811 0.1319075823 380 1305031114.8113029003 0.0707045570 0.0356046404 0.0782428384 0.0127541207 0.4933350000 246210525 0 1783459840 -0.3140531182 0.0166336372 0.1288475394 381 1305031114.8432080746 0.0700630173 0.0356950823 0.0782428384 0.0127381043 0.4564260000 247669457 0 1786011648 -0.3124188185 0.0154684912 0.1288196594 382 1305031114.8792810440 0.0699453205 0.0357847426 0.0782428384 0.0127214577 0.3981560000 251304187 0 1784672256 -0.3088937998 0.0185201522 0.1286392212 383 1305031114.9128789902 0.0695669949 0.0358729470 0.0782428384 0.0127072958 0.4005060000 251032110 0 1779879936 -0.3051459193 0.0199462548 0.1286225170 384 1305031114.9432640076 0.0731778368 0.0359700951 0.0782428384 0.0126926987 0.2672030000 251452704 0 1781370880 -0.2983893752 0.0270438157 0.1310624927 385 1305031114.9792799950 0.0651321188 0.0360458406 0.0782428384 0.0126822132 0.5593040000 250785554 0 1775783936 -0.2946868837 0.0253407322 0.1274641752 386 1305031115.0113000870 0.0655186251 0.0361221950 0.0782428384 0.0126692753 0.2954340000 246117872 0 1773342720 -0.2867662311 0.0307682902 0.1265559196 387 1305031115.0435299873 0.0669747069 0.0362019172 0.0782428384 0.0126571217 0.2042550000 246156343 0 1775009792 -0.2786601782 0.0324479863 0.1336350590 388 1305031115.0792379379 0.0607087761 0.0362650792 0.0782428384 0.0126471012 0.2165400000 246122360 0 1776386048 -0.2696984410 0.0319423154 0.1318462938 389 1305031115.1112298965 0.0657866374 0.0363409701 0.0782428384 0.0126471738 0.2535380000 246581958 0 1778569216 -0.2550332844 0.0343454145 0.1386358440 390 1305031115.1432940960 0.0612152219 0.0364047503 0.0782428384 0.0126310635 0.4915780000 246561624 0 1780707328 -0.2462650388 0.0316200517 0.1389811635 391 1305031115.1794400215 0.0506233238 0.0364411149 0.0782428384 0.0126222886 0.4610310000 246563298 0 1782611968 -0.2369705886 0.0272531323 0.1349584013 392 1305031115.2113740444 0.0573088676 0.0364943490 0.0782428384 0.0126581494 0.4569000000 246565292 0 1784262656 -0.2161550373 0.0182104055 0.1413201690 393 1305031115.2432971001 0.0558942631 0.0365437126 0.0782428384 0.0126429545 0.4677480000 246730726 0 1785913344 -0.2026718557 0.0159732848 0.1429956853 394 1305031115.2799661160 0.0490002111 0.0365753281 0.0782428384 0.0126546628 0.4933290000 250284331 0 1784147968 -0.1889552325 0.0226336904 0.1428693086 395 1305031115.3117039204 0.0635335371 0.0366435767 0.0782428384 0.0127202222 0.2670970000 252750674 0 1784213504 -0.1596036404 0.0109122219 0.1507805139 396 1305031115.3434259892 0.0548691191 0.0366896008 0.0782428384 0.0127093204 0.3204620000 252029276 0 1785856000 -0.1512509137 0.0154120242 0.1480228752 397 1305031115.3791658878 0.0314598680 0.0366764277 0.0782428384 0.0128594998 0.2293990000 251574161 0 1785180160 -0.1559476256 0.0270398594 0.1511069536 398 1305031115.4112370014 0.0338980034 0.0366694467 0.0782428384 0.0128636306 0.5642790000 251522916 0 1781739520 -0.1384962648 0.0200184174 0.1566909850 399 1305031115.4431591034 0.0422054976 0.0366833216 0.0782428384 0.0128778044 0.2747580000 246575166 0 1783566336 -0.1148585975 0.0189592056 0.1619096696 400 1305031115.4792408943 0.0311918464 0.0366695929 0.0782428384 0.0128697584 0.2093760000 246576752 0 1783148544 -0.1047920510 0.0219561104 0.1642292142 401 1305031115.5112531185 0.0536080524 0.0367118334 0.0782428384 0.0130179106 0.2530330000 247036018 0 1785544704 -0.0657692775 0.0136335660 0.1659197509 402 1305031115.5436201096 0.0541851111 0.0367552993 0.0782428384 0.0130095656 0.5263810000 247011344 0 1780543488 -0.0482597128 0.0123689258 0.1681723148 403 1305031115.5793149471 0.0405643694 0.0367647511 0.0782428384 0.0130034373 0.4985780000 247013350 0 1782407168 -0.0404053852 0.0138115119 0.1684519202 404 1305031115.6114239693 0.0385458581 0.0367691597 0.0782428384 0.0129885109 0.5186090000 247015336 0 1783394304 -0.0271588601 0.0117807193 0.1681433767 405 1305031115.6432540417 0.0381955467 0.0367726817 0.0782428384 0.0129760905 0.4781760000 247170382 0 1785737216 -0.0121284612 0.0100053968 0.1681967825 406 1305031115.6792409420 0.0242918096 0.0367419406 0.0782428384 0.0129731616 0.4984450000 249559395 0 1784766464 -0.0094676726 0.0117460191 0.1665874571 407 1305031115.7113199234 0.0242129583 0.0367111569 0.0782428384 0.0130023577 0.3109730000 252991561 0 1784397824 0.0114936307 0.0162556842 0.1655200422 408 1305031115.7432498932 0.0372640342 0.0367125120 0.0782428384 0.0130314145 0.4074110000 252960747 0 1783758848 0.0388345458 0.0105841132 0.1688161939 409 1305031115.7794249058 0.0286952071 0.0366929098 0.0782428384 0.0130357046 0.2577860000 252259661 0 1785348096 0.0490925834 0.0108442809 0.1637884676 410 1305031115.8112769127 0.0297930427 0.0366760808 0.0782428384 0.0130488597 0.5822940000 252190338 0 1782571008 0.0684812218 0.0143690016 0.1642712355 411 1305031115.8432240486 0.0258691031 0.0366497865 0.0782428384 0.0130453982 0.3448260000 247462514 0 1777020928 0.0743117407 0.0143823177 0.1668124795 412 1305031115.8791980743 0.0261271652 0.0366242461 0.0782428384 0.0130342107 0.5037480000 247461864 0 1779191808 0.0792267770 0.0118680522 0.1684619784 413 1305031115.9111180305 0.0213344898 0.0365872249 0.0782428384 0.0130323624 0.4662330000 247463850 0 1780588544 0.0945501477 0.0179191157 0.1671820134 414 1305031115.9433109760 0.0226294547 0.0365535105 0.0782428384 0.0130270712 0.4377010000 247465952 0 1782808576 0.1074363962 0.0180789623 0.1673289239 415 1305031115.9807400703 0.0226427484 0.0365199906 0.0782428384 0.0130444120 0.4197470000 247614998 0 1784586240 0.1225113720 0.0209926516 0.1690645516 416 1305031116.0113790035 0.0257145911 0.0364940161 0.0782428384 0.0130761605 0.4279420000 249774423 0 1786257408 0.1412055790 0.0205767062 0.1678556800 417 1305031116.0431640148 0.0262421668 0.0364694313 0.0782428384 0.0130630358 0.3231390000 254192354 0 1784025088 0.1480679214 0.0222964268 0.1727409810 418 1305031116.0800299644 0.0259115025 0.0364441731 0.0782428384 0.0130944346 0.2839920000 253217918 0 1782919168 0.1457437426 0.0321386419 0.1752508134 419 1305031116.1112999916 0.0326506421 0.0364351193 0.0782428384 0.0131133418 0.2679450000 254098410 0 1784942592 0.1622281969 0.0237401016 0.1749156862 420 1305031116.1434469223 0.0400711074 0.0364437764 0.0782428384 0.0130992925 0.2117350000 252861899 0 1784455168 0.1691099256 0.0201680642 0.1775433868 421 1305031116.1795721054 0.0384683162 0.0364485853 0.0782428384 0.0131031876 0.4805020000 252793308 0 1777942528 0.1778936982 0.0276736673 0.1815315634 422 1305031116.2113199234 0.0337554142 0.0364422034 0.0782428384 0.0131039895 0.3823710000 247999804 0 1779363840 0.1935000122 0.0319802165 0.1786714792 423 1305031116.2433199883 0.0456425250 0.0364639536 0.0782428384 0.0131017010 0.4969380000 247998594 0 1775427584 0.2052955627 0.0202776678 0.1817894429 424 1305031116.2793850899 0.0455354974 0.0364853487 0.0782428384 0.0130990970 0.4233370000 248002268 0 1776926720 0.2109290808 0.0249025095 0.1818171740 425 1305031116.3113360405 0.0484049469 0.0365133948 0.0782428384 0.0131049449 0.4298590000 248000766 0 1778999296 0.2130300701 0.0263563264 0.1822237074 426 1305031116.3432919979 0.0593685769 0.0365670455 0.0782428384 0.0130986755 0.4206480000 248006768 0 1780547584 0.2203150690 0.0143015236 0.1859142482 427 1305031116.3793840408 0.0621208549 0.0366268905 0.0782428384 0.0130886187 0.4074330000 248196118 0 1782300672 0.2200944722 0.0148854945 0.1842995435 428 1305031116.4113330841 0.0541567206 0.0366678480 0.0782428384 0.0130990973 0.4454340000 250601307 0 1784360960 0.2198508233 0.0284079984 0.1787503958 429 1305031116.4433689117 0.0558412485 0.0367125413 0.0782428384 0.0130871748 0.2905790000 254277182 0 1783721984 0.2204225361 0.0273369290 0.1778916568 430 1305031116.4798500538 0.0602694564 0.0367673248 0.0782428384 0.0130734826 0.3212730000 253821279 0 1782853632 0.2207246274 0.0193794891 0.1787365973 431 1305031116.5112049580 0.0564367883 0.0368129616 0.0782428384 0.0130588434 0.2689230000 254500346 0 1783799808 0.2186522037 0.0216762647 0.1741092056 432 1305031116.5432620049 0.0578492731 0.0368616568 0.0782428384 0.0130494647 0.5321130000 253602416 0 1780543488 0.2096195519 0.0217409022 0.1732889265 433 1305031116.5793130398 0.0594597273 0.0369138463 0.0782428384 0.0130632583 0.3879050000 248018686 0 1780961280 0.1950245947 0.0216846317 0.1707359552 434 1305031116.6112608910 0.0629430786 0.0369738215 0.0782428384 0.0130631094 0.1889840000 248020512 0 1782382592 0.1845480800 0.0147609971 0.1674681753 435 1305031116.6433548927 0.0597231425 0.0370261188 0.0782428384 0.0130627647 0.1955170000 248022210 0 1784287232 0.1741548479 0.0164815616 0.1654515564 436 1305031116.6792809963 0.0490009151 0.0370535839 0.0782428384 0.0130675750 0.2024860000 248024780 0 1786064896 0.1650311649 0.0216066204 0.1629718393 437 1305031116.7116339207 0.0453637168 0.0370726002 0.0782428384 0.0130576880 0.2079630000 248026582 0 1783386112 0.1539684236 0.0225289017 0.1611714810 438 1305031116.7432909012 0.0439920053 0.0370883980 0.0782428384 0.0130509345 0.2423870000 248490180 0 1782771712 0.1409076601 0.0217664950 0.1577244699 439 1305031116.7792980671 0.0406017229 0.0370964010 0.0782428384 0.0130603264 0.5280360000 248474778 0 1780334592 0.1284996420 0.0187294632 0.1571007669 440 1305031116.8113429546 0.0445598885 0.0371133635 0.0782428384 0.0131298279 0.4767550000 248478732 0 1782026240 0.1069342792 0.0191684961 0.1602524966 441 1305031116.8460888863 0.0416424908 0.0371236336 0.0782428384 0.0132075545 0.4434130000 248479174 0 1783836672 0.0902370736 0.0183653571 0.1584773958 442 1305031116.8801651001 0.0345233902 0.0371177507 0.0782428384 0.0132030174 0.4351590000 248653164 0 1785626624 0.0827392712 0.0205447450 0.1551863998 443 1305031116.9120440483 0.0412810333 0.0371271486 0.0782428384 0.0132181788 0.4511230000 251064137 0 1783660544 0.0554694794 0.0215668716 0.1547591835 444 1305031116.9432959557 0.0319070965 0.0371153917 0.0782428384 0.0132195611 0.3388040000 255694368 0 1782611968 0.0495841876 0.0244350079 0.1528562456 445 1305031116.9793510437 0.0325091518 0.0371050406 0.0782428384 0.0133013636 0.3124440000 254690180 0 1780617216 0.0263293721 0.0258990061 0.1507465243 446 1305031117.0113821030 0.0292214528 0.0370873644 0.0782428384 0.0133059685 0.2991630000 255608364 0 1783070720 0.0158432573 0.0258156471 0.1458126158 447 1305031117.0432610512 0.0244682804 0.0370591338 0.0782428384 0.0132912560 0.5356170000 254220116 0 1777909760 0.0070605874 0.0306825154 0.1468436718 448 1305031117.0795199871 0.0225693788 0.0370267906 0.0782428384 0.0133297609 0.4166500000 248905156 0 1773785088 -0.0102486229 0.0345683992 0.1440147609 449 1305031117.1112380028 0.0250465162 0.0370001085 0.0782428384 0.0133280259 0.5192320000 248894542 0 1775226880 -0.0198829267 0.0334763564 0.1439800411 450 1305031117.1432180405 0.0224985089 0.0369678827 0.0782428384 0.0133145958 0.5072510000 248896988 0 1777246208 -0.0279108752 0.0369161852 0.1412556022 451 1305031117.1792640686 0.0243706238 0.0369399509 0.0782428384 0.0133173423 0.5059590000 248893558 0 1778421760 -0.0352521092 0.0392538607 0.1447400451 452 1305031117.2113609314 0.0269070845 0.0369177543 0.0782428384 0.0133179533 0.5144480000 249071400 0 1780731904 -0.0350062810 0.0424098372 0.1490780264 453 1305031117.2432770729 0.0296988524 0.0369018185 0.0782428384 0.0133156092 0.5086390000 251363821 0 1787023360 -0.0327598043 0.0479399562 0.1519776285 454 1305031117.2792990208 0.0353514254 0.0368984035 0.0782428384 0.0133041453 0.3658690000 256089036 0 1782951936 -0.0329941586 0.0440946445 0.1548015624 455 1305031117.3111999035 0.0359002016 0.0368962097 0.0782428384 0.0132962223 0.4265130000 255094322 0 1782022144 -0.0383201055 0.0405422524 0.1563331634 456 1305031117.3432428837 0.0385417305 0.0368998183 0.0782428384 0.0132882980 0.2806670000 256624734 0 1784197120 -0.0401238129 0.0356463715 0.1576142460 457 1305031117.3794538975 0.0387481637 0.0369038628 0.0782428384 0.0132803154 0.6471380000 254682166 0 1780281344 -0.0427417383 0.0306768641 0.1570387334 458 1305031117.4112210274 0.0397577696 0.0369100940 0.0782428384 0.0132662785 0.3412140000 248918913 0 1781436416 -0.0441233590 0.0258189626 0.1575272083 459 1305031117.4432740211 0.0380792581 0.0369126412 0.0782428384 0.0132524223 0.2178970000 248962091 0 1781252096 -0.0426957980 0.0246064290 0.1567466408 460 1305031117.4794030190 0.0365242809 0.0369117970 0.0782428384 0.0132471956 0.2384320000 248931157 0 1783521280 -0.0438365526 0.0183640271 0.1559915841 461 1305031117.5113248825 0.0376984589 0.0369135034 0.0782428384 0.0132337832 0.2285610000 248911510 0 1785282560 -0.0436401144 0.0104999039 0.1558771431 462 1305031117.5442850590 0.0324233249 0.0369037844 0.0782428384 0.0132240793 0.2314030000 248913572 0 1784299520 -0.0452788733 0.0101418784 0.1553092897 463 1305031117.5791549683 0.0289878231 0.0368866873 0.0782428384 0.0132119492 0.2341670000 248948803 0 1783648256 -0.0453553870 0.0048278123 0.1551251858 464 1305031117.6111590862 0.0254933555 0.0368621327 0.0782428384 0.0131984867 0.2347820000 248951609 0 1785573376 -0.0471852571 0.0005847681 0.1561294645 465 1305031117.6432840824 0.0246644747 0.0368359012 0.0782428384 0.0131862834 0.2269480000 248919682 0 1786822656 -0.0484386235 -0.0076006744 0.1578304917 466 1305031117.6792619228 0.0195806473 0.0367988727 0.0782428384 0.0131742567 0.2277270000 248975601 0 1783136256 -0.0491855852 -0.0119296312 0.1601728648 467 1305031117.7112150192 0.0205163155 0.0367640064 0.0782428384 0.0131613548 0.2273860000 248960331 0 1784954880 -0.0483479612 -0.0203391835 0.1643716544 468 1305031117.7431840897 0.0230194777 0.0367346378 0.0782428384 0.0131526292 0.2291620000 248925788 0 1786318848 -0.0476401523 -0.0318496451 0.1672570407 469 1305031117.7794671059 0.0180348624 0.0366947662 0.0782428384 0.0131397065 0.2369410000 249002539 0 1782628352 -0.0482866839 -0.0361246467 0.1704103947 470 1305031117.8113200665 0.0246190000 0.0366690731 0.0782428384 0.0131361186 0.2486740000 249341692 0 1784139776 -0.0440221690 -0.0493352860 0.1765268743 471 1305031117.8433070183 0.0238292906 0.0366418124 0.0782428384 0.0131269383 0.5390390000 249327254 0 1781166080 -0.0425900817 -0.0546153411 0.1805571616 472 1305031117.8794670105 0.0231063943 0.0366131357 0.0782428384 0.0131171868 0.5131620000 249376177 0 1782951936 -0.0427602679 -0.0624713898 0.1832369268 473 1305031117.9114069939 0.0228664633 0.0365840729 0.0782428384 0.0131038255 0.4949310000 249352631 0 1784754176 -0.0460140333 -0.0737124905 0.1870127022 474 1305031117.9432721138 0.0229890849 0.0365553915 0.0782428384 0.0130906618 0.4991580000 249495692 0 1786490880 -0.0462194830 -0.0795429051 0.1909164488 475 1305031117.9792630672 0.0231469292 0.0365271632 0.0782428384 0.0130825305 0.4898250000 252041033 0 1782435840 -0.0493097641 -0.0854004547 0.1938162893 476 1305031118.0112280846 0.0233921483 0.0364995686 0.0782428384 0.0130735749 0.3268770000 256466628 0 1780432896 -0.0486149117 -0.0971020982 0.2028592825 477 1305031118.0435490608 0.0252365284 0.0364759564 0.0782428384 0.0130610674 0.4286750000 255347806 0 1781563392 -0.0487613678 -0.1055854931 0.2070178837 478 1305031118.0793690681 0.0281643961 0.0364585682 0.0782428384 0.0130526637 0.2621390000 256658140 0 1784692736 -0.0467930958 -0.1144360155 0.2122288644 479 1305031118.1112170219 0.0305457879 0.0364462242 0.0782428384 0.0130409866 0.5892090000 255049118 0 1781260288 -0.0457978584 -0.1228007823 0.2163462937 480 1305031118.1432559490 0.0303248037 0.0364334712 0.0782428384 0.0130293318 0.4023770000 249765496 0 1783042048 -0.0489565954 -0.1300115883 0.2198334038 481 1305031118.1793229580 0.0315240212 0.0364232644 0.0782428384 0.0130219955 0.5316950000 249766210 0 1778216960 -0.0488147959 -0.1409303695 0.2259336561 482 1305031118.2112019062 0.0321759172 0.0364144525 0.0782428384 0.0130101887 0.4848880000 249767652 0 1779978240 -0.0547297187 -0.1502116024 0.2278969884 483 1305031118.2431728840 0.0340393148 0.0364095351 0.0782428384 0.0130008216 0.4923090000 249769310 0 1781637120 -0.0532625169 -0.1585051864 0.2311014533 484 1305031118.2791941166 0.0351096243 0.0364068493 0.0782428384 0.0130085856 0.4651420000 249770672 0 1783218176 -0.0536248386 -0.1677684188 0.2356754690 485 1305031118.3112990856 0.0382875912 0.0364107271 0.0782428384 0.0129956315 0.4658520000 251684077 0 1785421824 -0.0544481203 -0.1737526208 0.2361282259 486 1305031118.3433239460 0.0397517905 0.0364176017 0.0782428384 0.0129871922 0.4592610000 255398635 0 1783922688 -0.0509282015 -0.1759217829 0.2392458171 487 1305031118.3792080879 0.0421977676 0.0364294706 0.0782428384 0.0129748729 0.2450960000 257492390 0 1783439360 -0.0521997474 -0.1844204366 0.2416830361 488 1305031118.4112958908 0.0444997735 0.0364460082 0.0782428384 0.0129654307 0.3748530000 256676987 0 1786101760 -0.0555242524 -0.1853472739 0.2419913411 489 1305031118.4457030296 0.0433723330 0.0364601724 0.0782428384 0.0129530190 0.2427130000 255742046 0 1784938496 -0.0531148091 -0.1840033233 0.2476668060 490 1305031118.4792850018 0.0456607230 0.0364789490 0.0782428384 0.0129419859 0.5397840000 255679324 0 1780826112 -0.0525295399 -0.1899771988 0.2474726290 491 1305031118.5112550259 0.0478034765 0.0365020133 0.0782428384 0.0129289219 0.4458150000 250176582 0 1782116352 -0.0525141060 -0.1874938011 0.2466643006 492 1305031118.5451989174 0.0486045815 0.0365266120 0.0782428384 0.0129173872 0.5033530000 250190629 0 1777500160 -0.0523159504 -0.1835108846 0.2464658618 493 1305031118.5792849064 0.0461608656 0.0365461541 0.0782428384 0.0129069474 0.4918720000 250208611 0 1779511296 -0.0498112515 -0.1807638705 0.2487677038 494 1305031118.6161420345 0.0445658788 0.0365623883 0.0782428384 0.0128964102 0.4901850000 250177768 0 1780908032 -0.0499840491 -0.1764075011 0.2483150661 495 1305031118.6453309059 0.0450255908 0.0365794857 0.0782428384 0.0128862346 0.4551910000 250179430 0 1782964224 -0.0499680676 -0.1696036458 0.2459579855 496 1305031118.6792950630 0.0423413515 0.0365911024 0.0782428384 0.0128769485 0.4692660000 252425547 0 1786466304 -0.0509317033 -0.1633114815 0.2443875372 497 1305031118.7114210129 0.0395652615 0.0365970866 0.0782428384 0.0128699275 0.3954630000 257498101 0 1784868864 -0.0522093475 -0.1608639061 0.2433180362 498 1305031118.7468008995 0.0398031287 0.0366035244 0.0782428384 0.0128686932 0.3213530000 256413212 0 1780985856 -0.0553424284 -0.1535030305 0.2371931523 499 1305031118.7792770863 0.0393415689 0.0366090115 0.0782428384 0.0128755880 0.3197840000 257411049 0 1782984704 -0.0533346124 -0.1340162605 0.2314955443 500 1305031118.8112208843 0.0321957059 0.0366001849 0.0782428384 0.0128817410 0.2385650000 256083412 0 1784532992 -0.0509661175 -0.1321130544 0.2331076562 501 1305031118.8467741013 0.0302520860 0.0365875140 0.0782428384 0.0128749537 0.6030950000 256067550 0 1780879360 -0.0470027290 -0.1251400411 0.2275290638 502 1305031118.8792080879 0.0326628685 0.0365796960 0.0782428384 0.0129067603 0.3387710000 250190968 0 1782222848 -0.0480979532 -0.1007595584 0.2157759070 503 1305031118.9111769199 0.0265520811 0.0365597604 0.0782428384 0.0129243834 0.2315020000 250240547 0 1782734848 -0.0481406823 -0.0993767008 0.2143634409 504 1305031118.9470090866 0.0239900965 0.0365348206 0.0782428384 0.0129203790 0.2337980000 250220601 0 1784111104 -0.0489364006 -0.0876224935 0.2061993629 505 1305031118.9793939590 0.0234816130 0.0365089727 0.0782428384 0.0129116192 0.2282970000 250197418 0 1786015744 -0.0493490882 -0.0742143840 0.1985841095 506 1305031119.0113630295 0.0187272839 0.0364738310 0.0782428384 0.0129056501 0.2262560000 250199504 0 1784487936 -0.0509942211 -0.0661655515 0.1954469383 507 1305031119.0471799374 0.0146473246 0.0364307807 0.0782428384 0.0128964785 0.2314180000 250254947 0 1786269696 -0.0540736429 -0.0571723655 0.1891727448 508 1305031119.0792229176 0.0112045221 0.0363811227 0.0782428384 0.0128876113 0.2386650000 250250401 0 1783341056 -0.0572657250 -0.0472560823 0.1831277162 509 1305031119.1113278866 0.0111534419 0.0363315595 0.0782428384 0.0128797799 0.2369450000 250256063 0 1784999936 -0.0559883788 -0.0393581092 0.1774640679 510 1305031119.1476290226 0.0095091676 0.0362789665 0.0782428384 0.0128762155 0.2309330000 250207708 0 1784500224 -0.0567292832 -0.0273221508 0.1716470271 511 1305031119.1792619228 0.0147623001 0.0362368595 0.0782428384 0.0128838114 0.2324360000 250291479 0 1783595008 -0.0551366322 -0.0249486119 0.1661867946 512 1305031119.2113640308 0.0155067872 0.0361963711 0.0782428384 0.0128730576 0.2368430000 250281825 0 1785147392 -0.0525010712 -0.0126384627 0.1608851999 513 1305031119.2476599216 0.0164020546 0.0361577857 0.0782428384 0.0128627187 0.2355640000 250289019 0 1786793984 -0.0541634373 -0.0039451495 0.1544041485 514 1305031119.2792439461 0.0198211782 0.0361260024 0.0782428384 0.0128524901 0.2367270000 250355065 0 1783603200 -0.0507369488 0.0059787184 0.1501701623 515 1305031119.3112120628 0.0205379073 0.0360957343 0.0782428384 0.0128409543 0.2278510000 250346323 0 1785380864 -0.0512246490 0.0137062054 0.1461410820 516 1305031119.3477499485 0.0228769351 0.0360701165 0.0782428384 0.0128313801 0.2358990000 250370385 0 1784606720 -0.0528464429 0.0198984295 0.1414507180 517 1305031119.3792390823 0.0251406264 0.0360489762 0.0782428384 0.0128219412 0.2383170000 250338751 0 1783869440 -0.0493894927 0.0317001566 0.1368058324 518 1305031119.4114921093 0.0298670009 0.0360370419 0.0782428384 0.0128150306 0.2291430000 250333113 0 1785528320 -0.0459988639 0.0380809419 0.1331974119 519 1305031119.4477260113 0.0325196385 0.0360302647 0.0782428384 0.0128044143 0.2282220000 250363287 0 1784496128 -0.0483022220 0.0468260497 0.1308363676 520 1305031119.4792668819 0.0327598378 0.0360239754 0.0782428384 0.0127989793 0.2315220000 250311492 0 1783869440 -0.0489631444 0.0573884472 0.1267190278 521 1305031119.5112578869 0.0349284522 0.0360218726 0.0782428384 0.0127877799 0.2293110000 250313678 0 1785348096 -0.0486148484 0.0649671778 0.1228892729 522 1305031119.5474140644 0.0378983952 0.0360254675 0.0782428384 0.0127763354 0.2273380000 250315524 0 1784479744 -0.0497161523 0.0750714019 0.1194505170 523 1305031119.5795691013 0.0408400036 0.0360346731 0.0782428384 0.0127778029 0.2618140000 250771706 0 1783980032 -0.0460626930 0.0899028629 0.1168977916 524 1305031119.6150240898 0.0450057536 0.0360517935 0.0782428384 0.0127760778 0.5503690000 250748244 0 1781280768 -0.0476677492 0.0927200466 0.1161229536 525 1305031119.6488890648 0.0439440235 0.0360668263 0.0782428384 0.0127899756 0.5168070000 250749946 0 1782972416 -0.0517874993 0.1091568768 0.1121623889 526 1305031119.6792080402 0.0495834500 0.0360925233 0.0782428384 0.0127808931 0.5041810000 250751300 0 1784672256 -0.0477267839 0.1190397143 0.1119902357 527 1305031119.7152490616 0.0520186462 0.0361227437 0.0782428384 0.0127708642 0.4949020000 250809195 0 1786310656 -0.0506527871 0.1238636896 0.1117141172 528 1305031119.7471930981 0.0542829372 0.0361571380 0.0782428384 0.0127655320 0.5208720000 255460959 0 1782534144 -0.0566713288 0.1286890507 0.1096263751 529 1305031119.7791690826 0.0583888739 0.0361991640 0.0782428384 0.0127540828 0.2614750000 258811618 0 1783803904 -0.0561186150 0.1368179023 0.1100222841 530 1305031119.8145709038 0.0607019514 0.0362453956 0.0782428384 0.0127465163 0.4091210000 257047212 0 1786892288 -0.0547364652 0.1441614181 0.1077794507 531 1305031119.8474450111 0.0672987103 0.0363038764 0.0782428384 0.0127394556 0.2570920000 256744594 0 1784066048 -0.0523581132 0.1527743489 0.1084169671 532 1305031119.8792319298 0.0703973547 0.0363679619 0.0782428384 0.0127352600 0.6160360000 256765372 0 1779888128 -0.0540962964 0.1561262012 0.1070981473 533 1305031119.9114239216 0.0645131022 0.0364207671 0.0782428384 0.0127548127 0.4159950000 251155954 0 1774264320 -0.0575158820 0.1713094562 0.1017780676 534 1305031119.9474620819 0.0674620196 0.0364788968 0.0782428384 0.0127445459 0.5377960000 251154168 0 1776168960 -0.0597591251 0.1792121083 0.1012397707 535 1305031119.9795460701 0.0703851432 0.0365422729 0.0782428384 0.0127331644 0.4950680000 251155406 0 1778135040 -0.0600702688 0.1844433993 0.1013735458 536 1305031120.0152831078 0.0711660609 0.0366068695 0.0782428384 0.0127286453 0.4680550000 251157640 0 1779138560 -0.0601041242 0.1886584610 0.0989536494 537 1305031120.0473101139 0.0759954676 0.0366802189 0.0782428384 0.0127277740 0.4387940000 251333274 0 1781358592 -0.0633110479 0.1904407889 0.1012673602 538 1305031120.0794179440 0.0786672011 0.0367582616 0.0786672011 0.0127264327 0.4565980000 254113319 0 1785880576 -0.0667304695 0.1865061522 0.1007850692 539 1305031120.1152489185 0.0747016147 0.0368286574 0.0786672011 0.0127450873 0.2941320000 258745986 0 1785163776 -0.0649840310 0.1992382109 0.1004078388 540 1305031120.1481750011 0.0783083588 0.0369054717 0.0786672011 0.0127689394 0.3814830000 257562119 0 1784369152 -0.0640127435 0.1905186474 0.1014751568 541 1305031120.1792609692 0.0841851830 0.0369928649 0.0841851830 0.0127746638 0.2958160000 259122334 0 1783042048 -0.0608224720 0.1775931120 0.1023628265 542 1305031120.2152600288 0.0851202086 0.0370816607 0.0851202086 0.0127638329 0.5990760000 257339730 0 1777819648 -0.0594485812 0.1711641103 0.1028205231 543 1305031120.2480180264 0.0796803087 0.0371601113 0.0851202086 0.0127543709 0.3784390000 251147086 0 1779597312 -0.0586414076 0.1724287719 0.1036586612 544 1305031120.2794411182 0.0784345046 0.0372359833 0.0851202086 0.0127447622 0.2297290000 251148888 0 1779531776 -0.0582134463 0.1642708182 0.1041226685 545 1305031120.3152129650 0.0770420060 0.0373090219 0.0851202086 0.0127343464 0.2159930000 251150830 0 1781579776 -0.0585100912 0.1558818966 0.1058843732 546 1305031120.3477969170 0.0708961859 0.0373705368 0.0851202086 0.0127246068 0.2195680000 251153032 0 1783230464 -0.0566389337 0.1518488526 0.1077459455 547 1305031120.3794460297 0.0700260475 0.0374302361 0.0851202086 0.0127171591 0.2225840000 251154934 0 1784897536 -0.0568074062 0.1411172450 0.1112687513 548 1305031120.4154899120 0.0704921782 0.0374905681 0.0851202086 0.0127138211 0.2266620000 251157168 0 1786769408 -0.0568632483 0.1288259476 0.1158320159 549 1305031120.4474329948 0.0597158708 0.0375310514 0.0851202086 0.0127061485 0.2270150000 251159110 0 1783734272 -0.0566222481 0.1268323660 0.1174271405 550 1305031120.4794321060 0.0610398464 0.0375737946 0.0851202086 0.0127019637 0.2167950000 251161312 0 1785135104 -0.0537917577 0.1146547943 0.1216305569 551 1305031120.5148770809 0.0583058409 0.0376114209 0.0851202086 0.0126908668 0.2160300000 251163170 0 1784651776 -0.0562720597 0.1057436168 0.1262031198 552 1305031120.5478069782 0.0518490374 0.0376372136 0.0851202086 0.0126838342 0.2235740000 251165580 0 1783881728 -0.0551649220 0.1000877693 0.1297931671 553 1305031120.5795590878 0.0481477678 0.0376562201 0.0851202086 0.0126750655 0.2263710000 251167390 0 1785647104 -0.0544935241 0.0948521048 0.1324777752 554 1305031120.6152710915 0.0483061969 0.0376754439 0.0851202086 0.0126665148 0.2271490000 251169476 0 1784250368 -0.0548251905 0.0851743445 0.1378324777 555 1305031120.6473538876 0.0441539958 0.0376871169 0.0851202086 0.0126605886 0.2286530000 251171402 0 1783357440 -0.0498042181 0.0803560466 0.1409385651 556 1305031120.6793179512 0.0421853848 0.0376952073 0.0851202086 0.0126717756 0.2274780000 251173456 0 1785139200 -0.0482819527 0.0757310316 0.1454131752 557 1305031120.7145531178 0.0396373495 0.0376986941 0.0851202086 0.0126611867 0.2289250000 251175146 0 1786642432 -0.0494338870 0.0679176822 0.1497718394 558 1305031120.7473959923 0.0363311172 0.0376962433 0.0851202086 0.0126566542 0.2323820000 251177448 0 1783484416 -0.0477657169 0.0590494499 0.1527315825 559 1305031120.7799079418 0.0371252149 0.0376952218 0.0851202086 0.0126466720 0.2209000000 251179650 0 1785282560 -0.0464995429 0.0510987304 0.1591661125 560 1305031120.8149440289 0.0328472741 0.0376865647 0.0851202086 0.0126428882 0.2244410000 251226213 0 1786388480 -0.0482634418 0.0450014174 0.1608879864 561 1305031120.8479421139 0.0318588242 0.0376761766 0.0851202086 0.0126375375 0.2329240000 251183770 0 1784360960 -0.0453828909 0.0374221951 0.1649774313 562 1305031120.8834540844 0.0336792395 0.0376690646 0.0851202086 0.0126274368 0.2265070000 251185244 0 1786138624 -0.0439161472 0.0264945980 0.1693916172 563 1305031120.9154539108 0.0297275018 0.0376549588 0.0851202086 0.0126222150 0.2318650000 251253755 0 1785409536 -0.0449318811 0.0221800730 0.1705021262 564 1305031120.9475090504 0.0280054677 0.0376378498 0.0851202086 0.0126111050 0.2349730000 251272773 0 1784487936 -0.0450773984 0.0134535134 0.1742270738 565 1305031120.9833900928 0.0270150825 0.0376190484 0.0851202086 0.0126035387 0.2264150000 251246763 0 1782571008 -0.0465850607 0.0034195893 0.1772104204 566 1305031121.0150289536 0.0245823991 0.0375960155 0.0851202086 0.0125981090 0.2236030000 251225485 0 1784619008 -0.0486501083 -0.0049760938 0.1785535365 567 1305031121.0477550030 0.0210445486 0.0375668242 0.0851202086 0.0125873526 0.2557430000 251276067 0 1786142720 -0.0493403338 -0.0102598919 0.1802784353 568 1305031121.0831170082 0.0224099271 0.0375401395 0.0851202086 0.0125793607 0.2213210000 251197836 0 1784627200 -0.0493908077 -0.0219919123 0.1820116192 569 1305031121.1148779392 0.0221864469 0.0375131558 0.0851202086 0.0125702982 0.2240460000 251227255 0 1786671104 -0.0490440056 -0.0290827677 0.1830471009 570 1305031121.1473550797 0.0205933973 0.0374834721 0.0851202086 0.0125634883 0.2162080000 251223577 0 1783365632 -0.0507366769 -0.0376129560 0.1840635240 571 1305031121.1832809448 0.0212979149 0.0374551261 0.0851202086 0.0125528654 0.2175430000 251204314 0 1784369152 -0.0503356159 -0.0460360162 0.1869104952 572 1305031121.2114310265 0.0250310749 0.0374334057 0.0851202086 0.0125465309 0.2163550000 251205576 0 1786396672 -0.0463092253 -0.0550812408 0.1908065528 573 1305031121.2472009659 0.0216040276 0.0374057803 0.0851202086 0.0125402016 0.2154780000 251232515 0 1784279040 -0.0515413135 -0.0593439527 0.1904196739 574 1305031121.2828760147 0.0239735655 0.0373823792 0.0851202086 0.0125332164 0.2419170000 251647128 0 1785909248 -0.0503968224 -0.0722124055 0.1931188107 575 1305031121.3135879040 0.0253096204 0.0373613831 0.0851202086 0.0125244300 0.5221610000 251631054 0 1779875840 -0.0490796417 -0.0814063326 0.1970671713 576 1305031121.3475399017 0.0282976553 0.0373456474 0.0851202086 0.0125160366 0.4909030000 251631624 0 1781719040 -0.0510229319 -0.0893119350 0.1958675086 577 1305031121.3832480907 0.0297511034 0.0373324853 0.0851202086 0.0125167630 0.4736610000 251633386 0 1783275520 -0.0475505739 -0.0999075472 0.2016764730 578 1305031121.4143280983 0.0317188613 0.0373227732 0.0851202086 0.0125073475 0.4580040000 251827852 0 1784999936 -0.0487296283 -0.1064937040 0.2021507174 579 1305031121.4473190308 0.0311894324 0.0373121802 0.0851202086 0.0125006621 0.4563380000 253956677 0 1785171968 -0.0493315756 -0.1120739579 0.2076688111 580 1305031121.4830150604 0.0330605544 0.0373048498 0.0851202086 0.0125027575 0.3953590000 259089904 0 1784676352 -0.0477106050 -0.1248306334 0.2108766288 581 1305031121.5141639709 0.0383348316 0.0373066226 0.0851202086 0.0124986243 0.2533120000 257948946 0 1784442880 -0.0504765362 -0.1297358125 0.2067700773 582 1305031121.5472700596 0.0415791050 0.0373139636 0.0851202086 0.0124894043 0.3124380000 259051152 0 1786675200 -0.0499388352 -0.1351462603 0.2095395029 583 1305031121.5832130909 0.0379550271 0.0373150632 0.0851202086 0.0124794581 0.2487340000 257621382 0 1784078336 -0.0509644225 -0.1454017758 0.2169227749 584 1305031121.6147189140 0.0385707021 0.0373172133 0.0851202086 0.0124697840 0.5309880000 257524436 0 1779470336 -0.0505082943 -0.1522291154 0.2202636153 585 1305031121.6471829414 0.0434103310 0.0373276288 0.0851202086 0.0124642161 0.4466490000 252104886 0 1781260288 -0.0478735268 -0.1581819803 0.2217778414 586 1305031121.6832110882 0.0440918319 0.0373391719 0.0851202086 0.0124574225 0.5075360000 252112253 0 1776549888 -0.0523266569 -0.1652435064 0.2228267342 587 1305031121.7145280838 0.0444760993 0.0373513302 0.0851202086 0.0124479294 0.4711040000 252144679 0 1778315264 -0.0552678183 -0.1728525162 0.2247773856 588 1305031121.7471449375 0.0474577434 0.0373685179 0.0851202086 0.0124374504 0.4699520000 252146221 0 1779912704 -0.0553886965 -0.1775317937 0.2271950543 589 1305031121.7828710079 0.0477194190 0.0373860916 0.0851202086 0.0124271495 0.4660340000 252285134 0 1781829632 -0.0535619892 -0.1841990352 0.2306766212 590 1305031121.8115448952 0.0478979945 0.0374039084 0.0851202086 0.0124213890 0.4714550000 254664907 0 1786769408 -0.0505998954 -0.1875582188 0.2346767187 591 1305031121.8473351002 0.0495864190 0.0374245218 0.0851202086 0.0124139209 0.3923710000 260004789 0 1784086528 -0.0518326685 -0.1907825917 0.2357232124 592 1305031121.8821229935 0.0495968238 0.0374450831 0.0851202086 0.0124052639 0.2731230000 258787764 0 1780465664 -0.0525882915 -0.1944030970 0.2369406372 593 1305031121.9149429798 0.0494639464 0.0374653510 0.0851202086 0.0123948262 0.3218590000 259920994 0 1781858304 -0.0546179488 -0.1944277287 0.2374052405 594 1305031121.9473180771 0.0490134507 0.0374847923 0.0851202086 0.0123873672 0.2581930000 258445848 0 1784549376 -0.0487179980 -0.1953964233 0.2391964644 595 1305031121.9829349518 0.0487608574 0.0375037436 0.0851202086 0.0123796806 0.5665720000 258422494 0 1780092928 -0.0502872989 -0.1901666373 0.2382221818 596 1305031122.0144240856 0.0486040153 0.0375223682 0.0851202086 0.0123694162 0.4579300000 252143353 0 1780740096 -0.0511661954 -0.1890133023 0.2359687090 597 1305031122.0473060608 0.0477311686 0.0375394684 0.0851202086 0.0123605294 0.2478980000 252117870 0 1781354496 -0.0521175042 -0.1838371456 0.2327350378 598 1305031122.0829689503 0.0453845896 0.0375525873 0.0851202086 0.0123509956 0.2236730000 252153965 0 1784008704 -0.0514443740 -0.1768411994 0.2314403355 599 1305031122.1146879196 0.0471424684 0.0375685972 0.0851202086 0.0123430112 0.2193430000 252122090 0 1785147392 -0.0512762517 -0.1685473472 0.2256188542 600 1305031122.1507480145 0.0415966734 0.0375753106 0.0851202086 0.0123357328 0.2191230000 252124048 0 1786798080 -0.0505224653 -0.1604686081 0.2249055654 601 1305031122.1830520630 0.0412098281 0.0375813581 0.0851202086 0.0123351302 0.2166450000 252125974 0 1783533568 -0.0508387089 -0.1509235799 0.2203582227 602 1305031122.2149689198 0.0436955728 0.0375915146 0.0851202086 0.0123466289 0.2160440000 252128028 0 1785311232 -0.0551379472 -0.1325789839 0.2114262134 603 1305031122.2513549328 0.0352690183 0.0375876630 0.0851202086 0.0123382682 0.2180840000 252130018 0 1784401920 -0.0538683385 -0.1290983260 0.2124173790 604 1305031122.2838659286 0.0366732068 0.0375861490 0.0851202086 0.0123332641 0.2187310000 252132084 0 1783386112 -0.0567295924 -0.1177919209 0.2039826661 605 1305031122.3143088818 0.0368712582 0.0375849674 0.0851202086 0.0123493249 0.2459460000 252557450 0 1785167872 -0.0641635954 -0.0933768973 0.1970339268 606 1305031122.3513510227 0.0289644543 0.0375707421 0.0851202086 0.0123408880 0.5273710000 252543188 0 1781923840 -0.0623258278 -0.0881710425 0.1955583543 607 1305031122.3826780319 0.0265730713 0.0375526240 0.0851202086 0.0123337822 0.5278960000 252544638 0 1783635968 -0.0647959858 -0.0783236474 0.1905911267 608 1305031122.4150080681 0.0221432019 0.0375272796 0.0851202086 0.0123296623 0.5135780000 252546108 0 1785401344 -0.0647500455 -0.0727608725 0.1882517040 609 1305031122.4512720108 0.0187822171 0.0374964995 0.0851202086 0.0123301817 0.4791900000 252709738 0 1784545280 -0.0668943375 -0.0604677089 0.1816955805 610 1305031122.4833879471 0.0180581212 0.0374646333 0.0851202086 0.0123258555 0.5214630000 255876291 0 1780973568 -0.0647972152 -0.0526681542 0.1777977347 611 1305031122.5151350498 0.0189703144 0.0374343644 0.0851202086 0.0123179260 0.3673210000 260673826 0 1779970048 -0.0625417084 -0.0438412875 0.1730248183 612 1305031122.5515100956 0.0215756539 0.0374084515 0.0851202086 0.0123129806 0.5013750000 259431764 0 1781813248 -0.0582027547 -0.0346012935 0.1700231582 613 1305031122.5832169056 0.0232018083 0.0373852759 0.0851202086 0.0123034619 0.2839400000 261000470 0 1784553472 -0.0567030683 -0.0252537262 0.1661843061 614 1305031122.6150169373 0.0196468178 0.0373563859 0.0851202086 0.0122985618 0.6780190000 258998040 0 1784942592 -0.0615732595 -0.0192793235 0.1625542641 615 1305031122.6488099098 0.0226409193 0.0373324583 0.0851202086 0.0122887708 0.4479870000 252597695 0 1774227456 -0.0607324503 -0.0103807114 0.1573341340 616 1305031122.6834199429 0.0216742717 0.0373070391 0.0851202086 0.0122794425 0.2378970000 252554621 0 1774764032 -0.0622952655 -0.0003961418 0.1520004719 617 1305031122.7152190208 0.0227474086 0.0372834417 0.0851202086 0.0122726860 0.2334030000 252537066 0 1776431104 -0.0629462004 0.0094920583 0.1492480785 618 1305031122.7513089180 0.0258263741 0.0372649027 0.0851202086 0.0122713825 0.2341420000 252538972 0 1777840128 -0.0601568595 0.0242561772 0.1424540281 619 1305031122.7834379673 0.0288178977 0.0372512565 0.0851202086 0.0122623861 0.2276040000 252541050 0 1778843648 -0.0581032559 0.0348178744 0.1387092471 620 1305031122.8125650883 0.0348611288 0.0372474015 0.0851202086 0.0122548262 0.2289790000 252542728 0 1781002240 -0.0558806136 0.0405358076 0.1398353130 621 1305031122.8514859676 0.0408807881 0.0372532523 0.0851202086 0.0122573474 0.2279450000 252545110 0 1782779904 -0.0519640073 0.0507122502 0.1386313587 622 1305031122.8837749958 0.0383711681 0.0372550496 0.0851202086 0.0122531042 0.2216490000 252546392 0 1784684544 -0.0554081276 0.0586267039 0.1343084872 623 1305031122.9145851135 0.0382009782 0.0372565680 0.0851202086 0.0122493441 0.2245120000 252548698 0 1786445824 -0.0605526641 0.0612693578 0.1335533112 624 1305031122.9514129162 0.0413923077 0.0372631958 0.0851202086 0.0122403095 0.2354490000 252589697 0 1785450496 -0.0616338402 0.0677661896 0.1317465603 625 1305031122.9830000401 0.0412050635 0.0372695028 0.0851202086 0.0122317208 0.2307930000 252552506 0 1784434688 -0.0621284135 0.0756223500 0.1280908138 626 1305031123.0154619217 0.0442084819 0.0372805874 0.0851202086 0.0122223108 0.2215030000 252607181 0 1782902784 -0.0625997409 0.0801200867 0.1267666817 627 1305031123.0518379211 0.0496789068 0.0373003614 0.0851202086 0.0122145660 0.2339040000 252632507 0 1785085952 -0.0609524101 0.0851037875 0.1247396097 628 1305031123.0829920769 0.0471954867 0.0373161180 0.0851202086 0.0122105297 0.2735980000 252559028 0 1786462208 -0.0621428788 0.0976040363 0.1208386868 629 1305031123.1139390469 0.0478984974 0.0373329421 0.0851202086 0.0122028887 0.2390210000 252560774 0 1785344000 -0.0623084605 0.1055916473 0.1181528121 630 1305031123.1508400440 0.0542842411 0.0373598490 0.0851202086 0.0121935261 0.2243280000 252562788 0 1787138048 -0.0611287653 0.1123175696 0.1188590825 631 1305031123.1821761131 0.0553523041 0.0373883631 0.0851202086 0.0121992490 0.2517470000 253015758 0 1783705600 -0.0589924157 0.1244196147 0.1167355776 632 1305031123.2147240639 0.0571469069 0.0374196267 0.0851202086 0.0121905909 0.5659510000 252992776 0 1785274368 -0.0588776618 0.1321983635 0.1155230254 633 1305031123.2506411076 0.0565751642 0.0374498882 0.0851202086 0.0122108619 0.4902860000 252993958 0 1784557568 -0.0617957227 0.1457097381 0.1136409417 634 1305031123.2823629379 0.0632219464 0.0374905381 0.0851202086 0.0122095634 0.4702520000 252995036 0 1784446976 -0.0592381693 0.1504617929 0.1157346219 635 1305031123.3209919930 0.0689184368 0.0375400309 0.0851202086 0.0122047752 0.4634110000 253161110 0 1786277888 -0.0591844916 0.1557413936 0.1161922067 636 1305031123.3504929543 0.0712243840 0.0375929937 0.0851202086 0.0121974825 0.4798440000 255890479 0 1784606720 -0.0597458854 0.1638030112 0.1170388982 637 1305031123.3822629452 0.0738065913 0.0376498439 0.0851202086 0.0121895313 0.2935260000 260889726 0 1783238656 -0.0596833192 0.1718185842 0.1173869967 638 1305031123.4213430882 0.0791448131 0.0377148831 0.0851202086 0.0121802175 0.3167510000 259627832 0 1782419456 -0.0596443564 0.1770120114 0.1171354279 639 1305031123.4512660503 0.0773436055 0.0377768998 0.0851202086 0.0121826309 0.3030760000 260859842 0 1784299520 -0.0628644377 0.1856121719 0.1142717451 640 1305031123.4836049080 0.0782857910 0.0378401950 0.0851202086 0.0121743707 0.2244070000 259318371 0 1785937920 -0.0635140166 0.1945398450 0.1137619391 641 1305031123.5197250843 0.0861162245 0.0379155086 0.0861162245 0.0121673055 0.5533960000 259209548 0 1778708480 -0.0613680407 0.1960595399 0.1142331511 642 1305031123.5515730381 0.0866463929 0.0379914134 0.0866463929 0.0121594076 0.4643090000 252954796 0 1781493760 -0.0623992085 0.2038484514 0.1136321723 643 1305031123.5796160698 0.0910830721 0.0380739821 0.0910830721 0.0121534071 0.2260170000 253474750 0 1781350400 -0.0598161481 0.2089255005 0.1147740111 644 1305031123.6203870773 0.0937866569 0.0381604924 0.0937866569 0.0121479927 0.5319300000 253463572 0 1777139712 -0.0583780594 0.2137990594 0.1123959348 645 1305031123.6524300575 0.0948440880 0.0382483740 0.0948440880 0.0121395088 0.4781730000 253465890 0 1779171328 -0.0584508181 0.2210202664 0.1125964001 646 1305031123.6837849617 0.0956527293 0.0383372352 0.0956527293 0.0121314211 0.4630510000 253467728 0 1780822016 -0.0571990497 0.2260557115 0.1109873056 647 1305031123.7199749947 0.0974279046 0.0384285655 0.0974279046 0.0121254574 0.4562840000 253489282 0 1782206464 -0.0567404777 0.2343980074 0.1115075052 648 1305031123.7519800663 0.0997138321 0.0385231415 0.0997138321 0.0121168804 0.4832050000 256848261 0 1785167872 -0.0537953451 0.2389453202 0.1123705283 649 1305031123.7841379642 0.0998286903 0.0386176030 0.0998286903 0.0121100015 0.2929850000 261794390 0 1785040896 -0.0527703464 0.2431569695 0.1121858284 650 1305031123.8196959496 0.0988659114 0.0387102927 0.0998286903 0.0121015510 0.3689700000 260265216 0 1783066624 -0.0540370159 0.2447715402 0.1104199663 651 1305031123.8515510559 0.0988460556 0.0388026672 0.0998286903 0.0120927961 0.2722990000 261824953 0 1786175488 -0.0520790219 0.2464806736 0.1103414521 652 1305031123.8838191032 0.0961142778 0.0388905684 0.0998286903 0.0120837239 0.5029010000 260019204 0 1779081216 -0.0526319370 0.2499272674 0.1093889177 653 1305031123.9157938957 0.0934517607 0.0389741231 0.0998286903 0.0120758467 0.4862410000 253450258 0 1772355584 -0.0541604087 0.2479773611 0.1082990915 654 1305031123.9515299797 0.0973212793 0.0390633389 0.0998286903 0.0120682536 0.2103400000 253459224 0 1772617728 -0.0508929268 0.2392970622 0.1105012894 655 1305031123.9834210873 0.0922517553 0.0391445426 0.0998286903 0.0120593971 0.2056070000 253461678 0 1774268416 -0.0507903248 0.2448901981 0.1105798036 656 1305031124.0197370052 0.0901033059 0.0392222237 0.0998286903 0.0120655056 0.2056430000 253463944 0 1775501312 -0.0507773235 0.2413312048 0.1130114645 657 1305031124.0515310764 0.0908802301 0.0393008508 0.0998286903 0.0120594138 0.2109410000 253465622 0 1777799168 -0.0527192466 0.2284159213 0.1144976467 658 1305031124.0839018822 0.0867358521 0.0393729404 0.0998286903 0.0120520801 0.2133320000 253467908 0 1779486720 -0.0528620258 0.2288811952 0.1160520911 659 1305031124.1196689606 0.0828901380 0.0394389756 0.0998286903 0.0120505673 0.2077600000 253469674 0 1781227520 -0.0532671511 0.2253993154 0.1194938868 660 1305031124.1474580765 0.0828373358 0.0395047307 0.0998286903 0.0120447067 0.2209840000 253471744 0 1783009280 -0.0536830239 0.2107603103 0.1201646477 661 1305031124.1827070713 0.0818526745 0.0395687972 0.0998286903 0.0120416004 0.2156010000 253473978 0 1784655872 -0.0536989905 0.2035314888 0.1233974174 662 1305031124.2171790600 0.0756807476 0.0396233470 0.0998286903 0.0120367226 0.2150740000 253475752 0 1786433536 -0.0531785302 0.2002291828 0.1248456836 663 1305031124.2493400574 0.0772396028 0.0396800834 0.0998286903 0.0120328131 0.2187710000 253477522 0 1784815616 -0.0512823872 0.1860884875 0.1269115210 664 1305031124.2825551033 0.0793003738 0.0397397525 0.0998286903 0.0120434899 0.2207680000 253479832 0 1786449920 -0.0509359613 0.1714520454 0.1293575317 665 1305031124.3167819977 0.0827121511 0.0398043727 0.0998286903 0.0120591361 0.2541530000 253916038 0 1784004608 -0.0466225296 0.1558066010 0.1338589340 666 1305031124.3503708839 0.0796229541 0.0398641603 0.0998286903 0.0120539542 0.5589490000 253898864 0 1785794560 -0.0462631062 0.1490281820 0.1343731582 667 1305031124.3824319839 0.0781888738 0.0399216187 0.0998286903 0.0120475915 0.5191480000 253900618 0 1785106432 -0.0445548221 0.1409220695 0.1359723508 668 1305031124.4185550213 0.0745040849 0.0399733888 0.0998286903 0.0120430399 0.5091020000 253902232 0 1784729600 -0.0439543203 0.1322681606 0.1383387595 669 1305031124.4502561092 0.0693325177 0.0400172739 0.0998286903 0.0120352237 0.5155740000 256126553 0 1784987648 -0.0436156169 0.1269013882 0.1383141428 670 1305031124.4801259041 0.0687367022 0.0400601387 0.0998286903 0.0120272948 0.5101070000 260008871 0 1783836672 -0.0435586497 0.1153948009 0.1401244849 671 1305031124.5167369843 0.0593333319 0.0400888618 0.0998286903 0.0120193380 0.2754730000 262178674 0 1784573952 -0.0449271947 0.1101720035 0.1391035169 672 1305031124.5505030155 0.0556255579 0.0401119819 0.0998286903 0.0120109464 0.3881140000 261852648 0 1786519552 -0.0451064855 0.1026447713 0.1404205263 673 1305031124.5846059322 0.0542554259 0.0401329974 0.0998286903 0.0120025719 0.2601020000 260379330 0 1784532992 -0.0450095050 0.0913114026 0.1421911120 674 1305031124.6176528931 0.0496820994 0.0401471652 0.0998286903 0.0120069735 0.6265590000 260262098 0 1772081152 -0.0437533148 0.0818131492 0.1452687979 675 1305031124.6513130665 0.0440171845 0.0401528986 0.0998286903 0.0120037154 0.4104060000 253910698 0 1774206976 -0.0462967940 0.0748166591 0.1472570896 676 1305031124.6854729652 0.0457844362 0.0401612293 0.0998286903 0.0119986779 0.2152800000 253912464 0 1774358528 -0.0432386547 0.0633996204 0.1528218389 677 1305031124.7157909870 0.0407099277 0.0401620398 0.0998286903 0.0119908680 0.2305320000 253914682 0 1776119808 -0.0423939452 0.0556823052 0.1567030698 678 1305031124.7499411106 0.0382432789 0.0401592097 0.0998286903 0.0119824070 0.2288700000 253916916 0 1777770496 -0.0436283275 0.0444057062 0.1606382281 679 1305031124.7851779461 0.0342479572 0.0401505039 0.0998286903 0.0119745121 0.2269640000 253918590 0 1778524160 -0.0446421281 0.0349564329 0.1627663523 680 1305031124.8166410923 0.0290972795 0.0401342492 0.0998286903 0.0119669036 0.2317080000 253920936 0 1781071872 -0.0438368134 0.0255941041 0.1649307758 681 1305031124.8505589962 0.0287095699 0.0401174728 0.0998286903 0.0119588412 0.2332110000 253923054 0 1782722560 -0.0448038056 0.0131284595 0.1723365784 682 1305031124.8835940361 0.0309905764 0.0401040903 0.0998286903 0.0119549358 0.2235900000 253924780 0 1784483840 -0.0412174985 0.0027988339 0.1795239300 683 1305031124.9187700748 0.0248905737 0.0400818158 0.0998286903 0.0119577690 0.2407570000 253970899 0 1786261504 -0.0426271781 -0.0031251805 0.1831821054 684 1305031124.9507479668 0.0255893860 0.0400606280 0.0998286903 0.0119598432 0.2325070000 253966693 0 1785389056 -0.0417288654 -0.0142255928 0.1901393384 685 1305031124.9864599705 0.0255933739 0.0400395079 0.0998286903 0.0119793299 0.2185850000 253930874 0 1787043840 -0.0433817171 -0.0317088887 0.1953285486 686 1305031125.0194671154 0.0249766968 0.0400175505 0.0998286903 0.0119743836 0.2131420000 253933260 0 1783099392 -0.0447926819 -0.0399685502 0.1958234310 687 1305031125.0507979393 0.0249967072 0.0399956861 0.0998286903 0.0119722206 0.2201790000 253998491 0 1784721408 -0.0424880758 -0.0428295247 0.2003952265 688 1305031125.0834798813 0.0260807574 0.0399754609 0.0998286903 0.0119656390 0.2210160000 253936956 0 1786515456 -0.0423528776 -0.0545672886 0.2065644264 689 1305031125.1190290451 0.0273983534 0.0399572067 0.0998286903 0.0119657714 0.2510990000 253938638 0 1783599104 -0.0429368131 -0.0652175397 0.2101131082 690 1305031125.1510369778 0.0300773773 0.0399428881 0.0998286903 0.0119605614 0.2139140000 253940424 0 1785413632 -0.0409049392 -0.0738676786 0.2145273685 691 1305031125.1870639324 0.0284430776 0.0399262459 0.0998286903 0.0119611832 0.2184300000 254000715 0 1784229888 -0.0442287996 -0.0729151294 0.2169494331 692 1305031125.2190179825 0.0287073813 0.0399100336 0.0998286903 0.0119615822 0.2159120000 253945176 0 1783230464 -0.0461423583 -0.0863058940 0.2208089530 693 1305031125.2506420612 0.0302986410 0.0398961644 0.0998286903 0.0119537458 0.2084550000 253946854 0 1785028608 -0.0473182611 -0.0984567925 0.2242037207 694 1305031125.2863960266 0.0306908675 0.0398829003 0.0998286903 0.0119473297 0.2126940000 253989221 0 1786515456 -0.0487492308 -0.1014324576 0.2265095413 695 1305031125.3191399574 0.0338044800 0.0398741543 0.0998286903 0.0119464879 0.2064320000 253951138 0 1785249792 -0.0472888574 -0.1119529009 0.2294616848 696 1305031125.3488988876 0.0336762443 0.0398652493 0.0998286903 0.0119416022 0.2086460000 253974141 0 1787064320 -0.0506592393 -0.1165822148 0.2312109470 697 1305031125.3867919445 0.0369596072 0.0398610805 0.0998286903 0.0119426832 0.2116190000 253955214 0 1783336960 -0.0480771139 -0.1215122789 0.2346650809 698 1305031125.4195740223 0.0374845564 0.0398576757 0.0998286903 0.0119346257 0.2116160000 253957300 0 1785135104 -0.0488126203 -0.1247919202 0.2380966246 699 1305031125.4512319565 0.0351964086 0.0398510073 0.0998286903 0.0119303859 0.2114520000 253959010 0 1786642432 -0.0515077710 -0.1312783509 0.2421595901 700 1305031125.4869990349 0.0370285697 0.0398469752 0.0998286903 0.0119281722 0.2063870000 253961244 0 1783230464 -0.0506763011 -0.1408013552 0.2445209175 701 1305031125.5193541050 0.0370170251 0.0398429382 0.0998286903 0.0119252086 0.2045380000 254001003 0 1784614912 -0.0534963831 -0.1411383152 0.2447399497 702 1305031125.5510499477 0.0364437029 0.0398380960 0.0998286903 0.0119213336 0.2030690000 254002521 0 1786404864 -0.0544106737 -0.1412197202 0.2455544174 703 1305031125.5853030682 0.0348441787 0.0398309922 0.0998286903 0.0119130072 0.2134010000 254001259 0 1785376768 -0.0543948784 -0.1433336288 0.2472972125 704 1305031125.6178700924 0.0336629711 0.0398222309 0.0998286903 0.0119195137 0.2030250000 253969056 0 1786650624 -0.0548473820 -0.1509499401 0.2478195131 705 1305031125.6505749226 0.0370821618 0.0398183442 0.0998286903 0.0119147594 0.2040060000 253971426 0 1785122816 -0.0582710281 -0.1552640051 0.2416367829 706 1305031125.6846020222 0.0386804901 0.0398167325 0.0998286903 0.0119119573 0.2042130000 253973160 0 1786916864 -0.0626002848 -0.1457900554 0.2338821143 707 1305031125.7156689167 0.0366642736 0.0398122736 0.0998286903 0.0119478295 0.2091650000 253974978 0 1782718464 -0.0580088459 -0.1464925110 0.2337545604 708 1305031125.7512919903 0.0386233181 0.0398105943 0.0998286903 0.0119487190 0.2089420000 254005221 0 1779777536 -0.0550745204 -0.1359665841 0.2273396254 709 1305031125.7868049145 0.0348317102 0.0398035719 0.0998286903 0.0119423628 0.2090860000 254017927 0 1782591488 -0.0544327535 -0.1266730577 0.2257395685 710 1305031125.8194499016 0.0339542180 0.0397953334 0.0998286903 0.0119413030 0.2069950000 253980912 0 1783455744 -0.0535950288 -0.1168250665 0.2221195847 711 1305031125.8547739983 0.0326399803 0.0397852696 0.0998286903 0.0119392205 0.2101050000 253983350 0 1785229312 -0.0542414635 -0.1110438854 0.2185947597 712 1305031125.8866450787 0.0306282043 0.0397724085 0.0998286903 0.0119422009 0.2391500000 253985460 0 1783992320 -0.0565383881 -0.1046952382 0.2131098211 713 1305031125.9193339348 0.0330879577 0.0397630334 0.0998286903 0.0119455820 0.2128910000 253987402 0 1783103488 -0.0590472892 -0.0953928530 0.2047176212 714 1305031125.9552519321 0.0306741428 0.0397503039 0.0998286903 0.0119450046 0.2133910000 253989504 0 1784885248 -0.0595396571 -0.0924074873 0.2029443830 715 1305031125.9870939255 0.0281181540 0.0397340351 0.0998286903 0.0119460236 0.2093150000 253991666 0 1786134528 -0.0583782643 -0.0790346339 0.1991252750 716 1305031126.0195720196 0.0252426267 0.0397137958 0.0998286903 0.0119422368 0.2185970000 253993324 0 1784864768 -0.0542950444 -0.0650986955 0.1992826760 717 1305031126.0550379753 0.0252786726 0.0396936631 0.0998286903 0.0119390062 0.2161910000 253995526 0 1786662912 -0.0492114872 -0.0519130304 0.1983547956 718 1305031126.0870759487 0.0243677702 0.0396723178 0.0998286903 0.0119328678 0.2266530000 253997336 0 1785032704 -0.0480426513 -0.0415318199 0.1965856999 719 1305031126.1194519997 0.0222471021 0.0396480825 0.0998286903 0.0119267205 0.2292760000 253999722 0 1786662912 -0.0471991636 -0.0319299176 0.1984938085 720 1305031126.1549999714 0.0176569819 0.0396175393 0.0998286903 0.0119402026 0.2205800000 254001556 0 1785032704 -0.0496784449 -0.0114142243 0.1967451274 721 1305031126.1871740818 0.0159843657 0.0395847610 0.0998286903 0.0119366969 0.2657410000 254424090 0 1786642432 -0.0513102412 -0.0011052769 0.1942465901 722 1305031126.2194728851 0.0229308996 0.0395616947 0.0998286903 0.0119389918 0.5513860000 254406644 0 1786224640 -0.0468070172 0.0039595906 0.1941789240 723 1305031126.2552359104 0.0244537611 0.0395407985 0.0998286903 0.0119482881 0.5315300000 254407998 0 1785323520 -0.0445213057 0.0180744324 0.1921706498 724 1305031126.2871050835 0.0282187723 0.0395251603 0.0998286903 0.0119424877 0.5181280000 254406976 0 1785757696 -0.0447029583 0.0278602242 0.1902328730 725 1305031126.3197870255 0.0296680443 0.0395115643 0.0998286903 0.0119401477 0.4827980000 254577870 0 1785438208 -0.0437197462 0.0408814177 0.1881022751 726 1305031126.3554151058 0.0336831920 0.0395035363 0.0998286903 0.0119345313 0.5277260000 257694935 0 1785552896 -0.0435100272 0.0477897152 0.1871151924 727 1305031126.3874828815 0.0364047363 0.0394992738 0.0998286903 0.0119329196 0.3266520000 262423838 0 1784700928 -0.0454588830 0.0570005327 0.1840560734 728 1305031126.4197928905 0.0371623859 0.0394960638 0.0998286903 0.0119269954 0.4710440000 261123492 0 1786355712 -0.0463411883 0.0658601224 0.1806391478 729 1305031126.4553799629 0.0415115207 0.0394988285 0.0998286903 0.0119308281 0.2807650000 262869646 0 1783975936 -0.0477462187 0.0702715069 0.1796620190 730 1305031126.4903860092 0.0459976196 0.0395077309 0.0998286903 0.0119369470 0.6966480000 260887394 0 1771995136 -0.0499600619 0.0778628737 0.1770863384 731 1305031126.5223209858 0.0438997746 0.0395137392 0.0998286903 0.0119384188 0.4165490000 254420278 0 1773572096 -0.0480134040 0.0917305499 0.1723665893 732 1305031126.5582089424 0.0520642102 0.0395308847 0.0998286903 0.0119365976 0.2430970000 254422620 0 1773973504 -0.0455898866 0.0982645601 0.1737604588 733 1305031126.5901761055 0.0539355017 0.0395505362 0.0998286903 0.0119293639 0.2333770000 254424698 0 1775624192 -0.0442107543 0.1049292833 0.1716080457 734 1305031126.6186869144 0.0544653870 0.0395708562 0.0998286903 0.0119218191 0.2329300000 254426436 0 1777274880 -0.0453318506 0.1114017740 0.1696553677 735 1305031126.6544740200 0.0613459423 0.0396004822 0.0998286903 0.0119304222 0.2347280000 254428926 0 1778655232 -0.0413528606 0.1127967685 0.1705748141 736 1305031126.6900219917 0.0630671158 0.0396323662 0.0998286903 0.0119267252 0.2339990000 254430792 0 1780838400 -0.0436941087 0.1181892976 0.1688372046 737 1305031126.7157700062 0.0641840324 0.0396656792 0.0998286903 0.0119212852 0.2213440000 254432374 0 1782489088 -0.0414175689 0.1236774176 0.1668782830 738 1305031126.7553739548 0.0683070570 0.0397044886 0.0998286903 0.0119148182 0.2270210000 254480293 0 1783758848 -0.0410771333 0.1233870834 0.1661160439 739 1305031126.7875649929 0.0674264953 0.0397420015 0.0998286903 0.0119101999 0.2208140000 254459727 0 1785630720 -0.0401680358 0.1294397116 0.1623814106 740 1305031126.8199288845 0.0707021207 0.0397838395 0.0998286903 0.0119054807 0.2229450000 254438684 0 1784872960 -0.0361390896 0.1320915967 0.1621001214 741 1305031126.8583779335 0.0703809559 0.0398251311 0.0998286903 0.0118983783 0.2124650000 254440438 0 1784262656 -0.0365599133 0.1334766299 0.1578145474 742 1305031126.8881540298 0.0703721121 0.0398662996 0.0998286903 0.0118909328 0.2221750000 254475933 0 1786044416 -0.0373366699 0.1353357434 0.1565101296 743 1305031126.9194090366 0.0697638243 0.0399065385 0.0998286903 0.0118835627 0.2172140000 254487459 0 1784627200 -0.0375327617 0.1378273368 0.1558185369 744 1305031126.9555010796 0.0686513036 0.0399451739 0.0998286903 0.0118780084 0.2193050000 254500141 0 1786425344 -0.0384110063 0.1383405030 0.1535022259 745 1305031126.9873158932 0.0726407468 0.0399890606 0.0998286903 0.0118722605 0.2535490000 254507059 0 1783894016 -0.0362175517 0.1344298273 0.1536635160 746 1305031127.0195240974 0.0723206252 0.0400324005 0.0998286903 0.0118648677 0.2205860000 254500749 0 1785552896 -0.0364441648 0.1334942728 0.1523266137 747 1305031127.0533180237 0.0718005896 0.0400749282 0.0998286903 0.0118626898 0.2193490000 254516847 0 1784913920 -0.0342433527 0.1354752034 0.1526514441 748 1305031127.0886490345 0.0706862062 0.0401158524 0.0998286903 0.0118603723 0.2153570000 254503557 0 1784115200 -0.0349858589 0.1352656931 0.1531928778 749 1305031127.1209630966 0.0694908649 0.0401550714 0.0998286903 0.0118620810 0.2140820000 254456842 0 1786044416 -0.0376531705 0.1328086406 0.1523167044 750 1305031127.1576919556 0.0705129504 0.0401955485 0.0998286903 0.0118545955 0.2236300000 254459008 0 1785044992 -0.0366648026 0.1297687292 0.1533839107 751 1305031127.1875000000 0.0681525245 0.0402327749 0.0998286903 0.0118520250 0.2185790000 254500355 0 1786679296 -0.0352780335 0.1314907372 0.1534339339 752 1305031127.2218310833 0.0701448396 0.0402725515 0.0998286903 0.0118502092 0.2220490000 254500341 0 1783857152 -0.0328558907 0.1286212355 0.1552828997 753 1305031127.2597610950 0.0698619783 0.0403118469 0.0998286903 0.0118473049 0.2255120000 254464802 0 1785139200 -0.0322987475 0.1250054240 0.1565064043 754 1305031127.2870380878 0.0643106326 0.0403436756 0.0998286903 0.0118559140 0.2212810000 254526189 0 1784889344 -0.0344106182 0.1282352358 0.1559195817 755 1305031127.3204679489 0.0658833385 0.0403775029 0.0998286903 0.0118514963 0.2261710000 254515999 0 1784410112 -0.0346407481 0.1236449927 0.1583461910 756 1305031127.3534069061 0.0679726601 0.0404140045 0.0998286903 0.0118461468 0.2328450000 254471072 0 1786044416 -0.0355280787 0.1174346730 0.1605820358 757 1305031127.3837130070 0.0642571673 0.0404455014 0.0998286903 0.0118423987 0.2283110000 254536643 0 1784664064 -0.0353362598 0.1203719229 0.1615875065 758 1305031127.4196500778 0.0625209659 0.0404746247 0.0998286903 0.0118360064 0.2273360000 254551773 0 1786556416 -0.0364380628 0.1186702549 0.1627335697 759 1305031127.4542460442 0.0636542886 0.0405051644 0.0998286903 0.0118398091 0.2320970000 254500163 0 1783877632 -0.0362867415 0.1144222394 0.1643438637 760 1305031127.4872000217 0.0605394281 0.0405315253 0.0998286903 0.0118490583 0.2308470000 254559449 0 1785536512 -0.0377538837 0.1160587594 0.1654372215 761 1305031127.5218999386 0.0589649826 0.0405557480 0.0998286903 0.0118428868 0.2295820000 254557147 0 1784766464 -0.0380852744 0.1161615700 0.1657001227 762 1305031127.5537250042 0.0631384477 0.0405853841 0.0998286903 0.0118456291 0.2252700000 254536577 0 1783881728 -0.0373703539 0.1107078716 0.1694252193 763 1305031127.5866320133 0.0607464612 0.0406118075 0.0998286903 0.0118408064 0.2304920000 254578535 0 1785647104 -0.0378669724 0.1114662439 0.1692723334 764 1305031127.6206569672 0.0587800704 0.0406355879 0.0998286903 0.0118337090 0.2304370000 254566045 0 1784766464 -0.0384188630 0.1136445105 0.1704946756 765 1305031127.6546559334 0.0628723949 0.0406646557 0.0998286903 0.0118282764 0.2295330000 254563703 0 1784008704 -0.0366967246 0.1093304306 0.1733414084 766 1305031127.6871099472 0.0612993762 0.0406915939 0.0998286903 0.0118223915 0.2269360000 254572625 0 1785667584 -0.0372910686 0.1091766208 0.1730587035 767 1305031127.7232100964 0.0581517741 0.0407143582 0.0998286903 0.0118160425 0.2626480000 254580403 0 1784782848 -0.0388936736 0.1116077602 0.1726315320 768 1305031127.7546939850 0.0617445037 0.0407417412 0.0998286903 0.0118111549 0.2272920000 254590337 0 1784299520 -0.0367321409 0.1086582243 0.1751839966 769 1305031127.7876410484 0.0613095164 0.0407684873 0.0998286903 0.0118092938 0.2306210000 254567343 0 1786028032 -0.0379599966 0.1059104651 0.1742548496 770 1305031127.8201279640 0.0593407229 0.0407926071 0.0998286903 0.0118035348 0.2301600000 254597157 0 1785135104 -0.0383966416 0.1078581288 0.1739577651 771 1305031127.8551321030 0.0593752749 0.0408167091 0.0998286903 0.0117959527 0.2379290000 254604559 0 1786789888 -0.0389579684 0.1072408408 0.1740988195 772 1305031127.8871219158 0.0595644973 0.0408409938 0.0998286903 0.0117893301 0.2315490000 254591245 0 1783504896 -0.0397691280 0.1052435338 0.1738997698 773 1305031127.9225599766 0.0587940477 0.0408642190 0.0998286903 0.0117834233 0.2323990000 254603455 0 1785122816 -0.0401578471 0.1053506881 0.1737137437 774 1305031127.9550879002 0.0573535152 0.0408855230 0.0998286903 0.0117781634 0.2318100000 254589677 0 1786789888 -0.0408893786 0.1067399010 0.1743269563 775 1305031127.9870929718 0.0573934428 0.0409068235 0.0998286903 0.0117709769 0.2326690000 254606559 0 1782616064 -0.0410951898 0.1055583879 0.1760798693 776 1305031128.0217759609 0.0573324747 0.0409279906 0.0998286903 0.0117685413 0.2290270000 254586145 0 1784397824 -0.0389362499 0.1067857817 0.1781598628 777 1305031128.0557179451 0.0591243058 0.0409514093 0.0998286903 0.0117694446 0.2341420000 254601867 0 1785774080 -0.0385767445 0.1025541425 0.1806876212 778 1305031128.0872058868 0.0601730756 0.0409761158 0.0998286903 0.0117623201 0.2317700000 254608881 0 1783996416 -0.0391986296 0.1004013345 0.1834040582 779 1305031128.1247460842 0.0592708066 0.0409996007 0.0998286903 0.0117560645 0.2332260000 254619127 0 1783250944 -0.0391450226 0.1006353199 0.1848220676 780 1305031128.1577820778 0.0597274490 0.0410236107 0.0998286903 0.0117507847 0.2323720000 254610013 0 1784926208 -0.0377875566 0.0998122245 0.1867821217 781 1305031128.1872210503 0.0624553524 0.0410510521 0.0998286903 0.0117464196 0.2360620000 254575667 0 1786200064 -0.0373605266 0.0948723853 0.1879852563 782 1305031128.2254419327 0.0585484318 0.0410734273 0.0998286903 0.0117462947 0.2377130000 254622145 0 1785413632 -0.0384936407 0.0974447206 0.1866515130 783 1305031128.2560069561 0.0580686070 0.0410951325 0.0998286903 0.0117402595 0.2303840000 254616663 0 1784270848 -0.0372673608 0.0989027694 0.1877774000 784 1305031128.2912750244 0.0617612712 0.0411214924 0.0998286903 0.0117386920 0.2365010000 254592945 0 1782624256 -0.0360902622 0.0942355767 0.1890899837 785 1305031128.3241701126 0.0583917983 0.0411434928 0.0998286903 0.0117340215 0.2307860000 254627547 0 1784377344 -0.0375035107 0.0967852548 0.1875146031 786 1305031128.3552060127 0.0577662587 0.0411646413 0.0998286903 0.0117271489 0.2316600000 254626981 0 1785901056 -0.0385399535 0.0970472693 0.1876583397 787 1305031128.3913969994 0.0587358214 0.0411869681 0.0998286903 0.0117202571 0.2361200000 254629583 0 1784922112 -0.0393980145 0.0945877284 0.1877291948 788 1305031128.4236090183 0.0585667677 0.0412090237 0.0998286903 0.0117131191 0.2570410000 254620013 0 1786269696 -0.0394903198 0.0950234458 0.1880570352 789 1305031128.4554989338 0.0568258613 0.0412288169 0.0998286903 0.0117081940 0.2368390000 254633967 0 1785303040 -0.0407940112 0.0959728584 0.1874150783 790 1305031128.4895229340 0.0573935695 0.0412492786 0.0998286903 0.0117016908 0.2374200000 254636785 0 1784139776 -0.0413374528 0.0944744945 0.1877290308 791 1305031128.5236039162 0.0579039082 0.0412703338 0.0998286903 0.0116949132 0.2332620000 254638263 0 1782763520 -0.0399664938 0.0937915891 0.1878660768 792 1305031128.5556390285 0.0573226959 0.0412906019 0.0998286903 0.0116888902 0.2294660000 254636209 0 1784504320 -0.0408880264 0.0926649719 0.1875297427 793 1305031128.5914599895 0.0587245896 0.0413125868 0.0998286903 0.0116825006 0.2342290000 254615935 0 1786277888 -0.0406198129 0.0900555551 0.1878601015 794 1305031128.6233680248 0.0572270155 0.0413326301 0.0998286903 0.0116760061 0.2303310000 254641701 0 1784672256 -0.0410538912 0.0894317701 0.1858096868 795 1305031128.6555540562 0.0554771237 0.0413504219 0.0998286903 0.0116717071 0.2301280000 254639867 0 1786433536 -0.0424891710 0.0899221152 0.1847995073 796 1305031128.6904489994 0.0581582934 0.0413715373 0.0998286903 0.0116676927 0.2326950000 254642185 0 1783754752 -0.0401306227 0.0888789296 0.1865204424 797 1305031128.7229759693 0.0567930825 0.0413908868 0.0998286903 0.0116607297 0.2399500000 254651731 0 1785925632 -0.0403848365 0.0898936242 0.1857356429 798 1305031128.7546460629 0.0567468293 0.0414101299 0.0998286903 0.0116554345 0.2420980000 254651885 0 1785032704 -0.0396788605 0.0904585570 0.1856696159 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log ================================================ SLAMBench Report run started: 2018-02-18 06:52:57 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_rgbd_dataset_freiburg2_rpy.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_rpy.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867718.6419320107 0.0019026520 0.0019026520 0.0019026520 nan 0.2095920000 232662400 0 1771601920 0.0000000000 0.0000000000 0.0000000000 2 1311867718.6768438816 0.0018501661 0.0018764090 0.0019026520 0.0004229187 0.2139860000 245319745 0 1774141440 0.0003404527 -0.0003233516 0.0006755633 3 1311867718.7114279270 0.0022588139 0.0020038773 0.0022588139 0.0033990547 0.1939680000 245247371 0 1775763456 -0.0008074777 0.0016060069 0.0001717690 4 1311867718.7410299778 0.0028558373 0.0022168673 0.0028558373 0.0049081234 0.1736560000 245252313 0 1777795072 0.0000555765 -0.0001343128 0.0005003273 5 1311867718.7767970562 0.0031371734 0.0024009285 0.0031371734 0.0042834049 0.1760130000 245256643 0 1778937856 -0.0009316629 -0.0011110066 0.0002900098 6 1311867718.8094089031 0.0024581340 0.0024104628 0.0031371734 0.0039832625 0.1735720000 245261773 0 1780969472 -0.0014924901 0.0004859685 0.0006383846 7 1311867718.8408079147 0.0033563643 0.0025455916 0.0033563643 0.0037617615 0.1826480000 245265475 0 1783017472 -0.0024369524 0.0002874515 0.0001770417 8 1311867718.8767778873 0.0036966968 0.0026894797 0.0036966968 0.0035598952 0.1835120000 245270441 0 1785159680 -0.0015092113 0.0003336112 0.0004401972 9 1311867718.9088680744 0.0050272825 0.0029492356 0.0050272825 0.0036038386 0.1773130000 245275215 0 1783660544 -0.0014763392 -0.0001842402 -0.0002196411 10 1311867718.9438331127 0.0044128397 0.0030955960 0.0050272825 0.0034327525 0.1779060000 245281109 0 1778692096 -0.0005531940 -0.0000328156 0.0011225867 11 1311867718.9784109592 0.0046627694 0.0032380663 0.0050272825 0.0032854765 0.1778820000 245284491 0 1774399488 -0.0019191861 -0.0000207563 0.0008152474 12 1311867719.0091300011 0.0053739990 0.0034160607 0.0053739990 0.0031525641 0.2068770000 245769181 0 1776287744 -0.0020412654 0.0000292436 0.0003848035 13 1311867719.0441620350 0.0056012985 0.0035841559 0.0056012985 0.0030791548 0.2654850000 246160259 0 1778356224 -0.0016803226 0.0004103329 0.0003382948 14 1311867719.0776190758 0.0067450684 0.0038099354 0.0067450684 0.0030724048 0.3824020000 246648108 0 1782890496 -0.0003840957 0.0002673660 -0.0001071233 15 1311867719.1086950302 0.0067971251 0.0040090814 0.0067971251 0.0030299605 0.2150800000 246293730 0 1784922112 -0.0014452764 -0.0006728013 -0.0000574030 16 1311867719.1437010765 0.0061521130 0.0041430208 0.0067971251 0.0030101110 0.2002340000 246130349 0 1783656448 -0.0016274441 0.0001687459 0.0008305301 17 1311867719.1810290813 0.0071149962 0.0043178429 0.0071149962 0.0029520633 0.1907400000 246135235 0 1781739520 -0.0005560311 0.0004560992 0.0007813360 18 1311867719.2127099037 0.0064731636 0.0044375830 0.0071149962 0.0028818493 0.1875820000 246140713 0 1783386112 -0.0016234057 -0.0006953054 0.0015420397 19 1311867719.2412090302 0.0058602267 0.0045124589 0.0071149962 0.0028744928 0.2140670000 246587519 0 1784774656 -0.0015649697 -0.0002286822 0.0027415068 20 1311867719.2779469490 0.0072021340 0.0046469427 0.0072021340 0.0031306738 0.4034440000 247489996 0 1785589760 -0.0023722814 -0.0003179356 0.0014117927 21 1311867719.3104898930 0.0063434695 0.0047277297 0.0072021340 0.0031788764 0.2918540000 246817390 0 1783889920 -0.0020613633 0.0002812893 0.0028850450 22 1311867719.3413150311 0.0071636904 0.0048384552 0.0072021340 0.0032494900 0.1782840000 246542605 0 1784270848 -0.0019476770 -0.0008770773 0.0026375619 23 1311867719.3772718906 0.0073191067 0.0049463096 0.0073191067 0.0031907341 0.2024680000 246545875 0 1783664640 -0.0033598200 -0.0021015760 0.0023058658 24 1311867719.4105761051 0.0082021207 0.0050819684 0.0082021207 0.0031284646 0.1864970000 246549505 0 1780584448 -0.0028945708 -0.0015698129 0.0016057815 25 1311867719.4427709579 0.0078117670 0.0051911603 0.0082021207 0.0030842904 0.1922630000 246552735 0 1779703808 -0.0026141577 -0.0017501495 0.0024997096 26 1311867719.4787840843 0.0077160471 0.0052882714 0.0082021207 0.0030667229 0.2184960000 246988565 0 1781596160 -0.0037806202 -0.0039736782 0.0028764335 27 1311867719.5104370117 0.0081767347 0.0053952515 0.0082021207 0.0031694699 0.3906650000 246987155 0 1782149120 -0.0048705377 -0.0024001731 0.0017368557 28 1311867719.5449650288 0.0087931715 0.0055166058 0.0087931715 0.0032652922 0.3104140000 248016764 0 1784115200 -0.0049545267 -0.0020928867 0.0017553489 29 1311867719.5771939754 0.0082745580 0.0056117076 0.0087931715 0.0032176997 0.2240800000 247348830 0 1783046144 -0.0054159835 -0.0033660040 0.0028235943 30 1311867719.6112511158 0.0095275408 0.0057422353 0.0095275408 0.0031754375 0.1763680000 246961981 0 1783595008 -0.0046287007 -0.0020200359 0.0023120847 31 1311867719.6421909332 0.0106689837 0.0059011627 0.0106689837 0.0031506184 0.1885700000 246965123 0 1785131008 -0.0034585767 -0.0002232616 0.0026725226 32 1311867719.6770479679 0.0095608868 0.0060155291 0.0106689837 0.0031216192 0.1877050000 246967953 0 1783713792 -0.0048952959 -0.0013287936 0.0037491811 33 1311867719.7107939720 0.0118425051 0.0061921041 0.0118425051 0.0030788560 0.1862140000 246973471 0 1781321728 -0.0036686778 0.0001807273 0.0027322136 34 1311867719.7442650795 0.0121025247 0.0063659400 0.0121025247 0.0030380004 0.1838170000 246981653 0 1780191232 -0.0044147344 0.0006271420 0.0026112373 35 1311867719.7861878872 0.0114818718 0.0065121095 0.0121025247 0.0030175896 0.1797970000 246984219 0 1781956608 -0.0045977589 0.0002018210 0.0041369377 36 1311867719.8099169731 0.0117510781 0.0066576364 0.0121025247 0.0029925530 0.1847850000 246986721 0 1783070720 -0.0044514798 -0.0004898772 0.0045811320 37 1311867719.8454990387 0.0114462031 0.0067870571 0.0121025247 0.0029703910 0.1853740000 246989927 0 1784721408 -0.0055051218 -0.0015523551 0.0048508197 38 1311867719.8771090508 0.0117570292 0.0069178459 0.0121025247 0.0029301333 0.1843300000 246992549 0 1783840768 -0.0063318121 -0.0019961013 0.0045101307 39 1311867719.9114089012 0.0121632945 0.0070523445 0.0121632945 0.0029247554 0.1853300000 246995395 0 1780830208 -0.0067467708 -0.0025605385 0.0044706976 40 1311867719.9461970329 0.0112666031 0.0071577010 0.0121632945 0.0029073968 0.1827510000 246998321 0 1779920896 -0.0078848498 -0.0040242923 0.0053688274 41 1311867719.9807810783 0.0136415660 0.0073158441 0.0136415660 0.0028895385 0.2162690000 247468547 0 1781575680 -0.0069451099 -0.0025645366 0.0035284436 42 1311867720.0117020607 0.0123142442 0.0074348536 0.0136415660 0.0028915610 0.4086520000 247424005 0 1783713792 -0.0086189611 -0.0021425986 0.0045872475 43 1311867720.0452380180 0.0162188523 0.0076391326 0.0162188523 0.0029184268 0.3053380000 248665150 0 1784225792 -0.0077440985 -0.0024995820 0.0014783944 44 1311867720.0772819519 0.0166926850 0.0078448952 0.0166926850 0.0029109651 0.3065560000 247948616 0 1781780480 -0.0054162466 -0.0042318972 0.0033791785 45 1311867720.1172130108 0.0170915145 0.0080503756 0.0170915145 0.0029381719 0.1994330000 247436139 0 1782403072 -0.0035638879 -0.0023705524 0.0048541091 46 1311867720.1451559067 0.0174258184 0.0082541896 0.0174258184 0.0029081378 0.1857030000 247438169 0 1783009280 -0.0038225660 -0.0023018720 0.0043852297 47 1311867720.1781630516 0.0154870283 0.0084080798 0.0174258184 0.0029511110 0.1903800000 247440775 0 1783541760 -0.0061005359 -0.0010872849 0.0051507251 48 1311867720.2094950676 0.0171173122 0.0085895221 0.0174258184 0.0029366277 0.1879250000 247443485 0 1782165504 -0.0041062376 0.0000306428 0.0053838775 49 1311867720.2421469688 0.0176697075 0.0087748320 0.0176697075 0.0029595840 0.1885550000 247446003 0 1783816192 -0.0036504762 -0.0022714669 0.0059197834 50 1311867720.2770779133 0.0173400957 0.0089461373 0.0176697075 0.0029566134 0.1797950000 247448313 0 1783644160 -0.0057061226 -0.0018592807 0.0056182235 51 1311867720.3094570637 0.0187012292 0.0091374136 0.0187012292 0.0029713001 0.1843730000 247451135 0 1783287808 -0.0040628719 0.0026371719 0.0063084932 52 1311867720.3430728912 0.0172659103 0.0092937308 0.0187012292 0.0030096539 0.1844540000 247453797 0 1776795648 -0.0049103340 0.0010616186 0.0075316075 53 1311867720.3779859543 0.0195257068 0.0094867870 0.0195257068 0.0031505484 0.1820270000 247456275 0 1775681536 -0.0056082946 -0.0045843460 0.0060148588 54 1311867720.4096798897 0.0218643863 0.0097160018 0.0218643863 0.0035114127 0.1823480000 247459225 0 1777324032 -0.0042466065 -0.0032632202 0.0049858126 55 1311867720.4461109638 0.0230895318 0.0099591569 0.0230895318 0.0034884624 0.1787490000 247462071 0 1779097600 -0.0047020027 -0.0028314847 0.0030926745 56 1311867720.4799289703 0.0222831462 0.0101792281 0.0230895318 0.0034869593 0.1819170000 247464301 0 1780596736 -0.0052700564 -0.0036294404 0.0041050259 57 1311867720.5104389191 0.0247876476 0.0104355162 0.0247876476 0.0035472858 0.2078810000 247950635 0 1782374400 -0.0076495036 -0.0039901072 -0.0006759789 58 1311867720.5467319489 0.0259397682 0.0107028309 0.0259397682 0.0035824662 0.4120810000 247909177 0 1784668160 -0.0072038448 -0.0030056217 -0.0012048744 59 1311867720.5793280602 0.0257697925 0.0109582031 0.0259397682 0.0036123796 0.3736650000 248422978 0 1784958976 -0.0068304697 -0.0049058893 -0.0006517257 60 1311867720.6121249199 0.0255679470 0.0112016988 0.0259397682 0.0036062283 0.2743390000 249311688 0 1783447552 -0.0070780474 -0.0049557555 -0.0003123106 61 1311867720.6463210583 0.0256952066 0.0114392973 0.0259397682 0.0035967753 0.2289310000 248647446 0 1783562240 -0.0067624552 -0.0035303533 -0.0002241636 62 1311867720.6798269749 0.0258035343 0.0116709786 0.0259397682 0.0035857612 0.1992420000 247922553 0 1784545280 -0.0066010533 -0.0051117879 0.0004247049 63 1311867720.7102439404 0.0273957551 0.0119205782 0.0273957551 0.0035802012 0.1816740000 247924735 0 1783693312 -0.0078830766 -0.0069495700 -0.0016675479 64 1311867720.7451629639 0.0271682218 0.0121588226 0.0273957551 0.0036254921 0.1863560000 247927165 0 1781145600 -0.0066342251 -0.0042886315 -0.0003502043 65 1311867720.7790179253 0.0309904013 0.0124485392 0.0309904013 0.0036831354 0.1824800000 247935339 0 1779470336 -0.0040851217 -0.0049793590 -0.0022462332 66 1311867720.8115909100 0.0297149364 0.0127101513 0.0309904013 0.0036559197 0.1895480000 247947809 0 1778823168 -0.0046659796 -0.0057269731 -0.0001927192 67 1311867720.8467299938 0.0300616175 0.0129691284 0.0309904013 0.0036814640 0.2079670000 247950855 0 1780510720 -0.0067411382 -0.0032360069 -0.0025786306 68 1311867720.8813319206 0.0318230242 0.0132463916 0.0318230242 0.0036626024 0.1833480000 247953093 0 1782251520 -0.0069817808 -0.0034349447 -0.0048398599 69 1311867720.9149661064 0.0340216905 0.0135474829 0.0340216905 0.0036670095 0.1823730000 247955467 0 1783902208 -0.0043111779 -0.0049739880 -0.0050302665 70 1311867720.9500010014 0.0327443928 0.0138217244 0.0340216905 0.0036574634 0.1844570000 247958137 0 1785790464 -0.0046716006 -0.0055691642 -0.0034121217 71 1311867720.9797990322 0.0322364122 0.0140810862 0.0340216905 0.0036365718 0.1895810000 247960623 0 1784770560 -0.0053071468 -0.0039811824 -0.0035592187 72 1311867721.0093889236 0.0316351242 0.0143248923 0.0340216905 0.0036138969 0.1737280000 247962749 0 1782153216 -0.0056868200 -0.0045159096 -0.0029064158 73 1311867721.0478379726 0.0359456763 0.0146210674 0.0359456763 0.0036352055 0.1772080000 247965443 0 1779339264 -0.0040417509 -0.0050838673 -0.0068602399 74 1311867721.0794439316 0.0374517068 0.0149295896 0.0374517068 0.0036218038 0.1822160000 247967625 0 1778720768 -0.0024234648 -0.0048303427 -0.0072859749 75 1311867721.1103579998 0.0323222615 0.0151614919 0.0374517068 0.0036433889 0.1794520000 247969695 0 1775943680 -0.0049064932 -0.0045629339 -0.0023688758 76 1311867721.1467890739 0.0349814110 0.0154222803 0.0374517068 0.0036699130 0.1823780000 247972469 0 1775423488 -0.0047584167 -0.0039004216 -0.0053622564 77 1311867721.1774179935 0.0337905064 0.0156608287 0.0374517068 0.0037859205 0.1829270000 247974475 0 1774788608 -0.0049833287 -0.0027423282 -0.0048013311 78 1311867721.2112360001 0.0380955301 0.0159484531 0.0380955301 0.0038351976 0.2129420000 248453545 0 1776791552 -0.0047890735 -0.0049655605 -0.0097769415 79 1311867721.2469010353 0.0388489924 0.0162383333 0.0388489924 0.0038404785 0.3947650000 248398371 0 1778491392 -0.0051937373 -0.0060361517 -0.0109014809 80 1311867721.2800450325 0.0402315110 0.0165382480 0.0402315110 0.0038649824 0.3461290000 248412833 0 1779421184 -0.0018966401 -0.0056431852 -0.0098713171 81 1311867721.3099579811 0.0389167480 0.0168145258 0.0402315110 0.0038474490 0.3089950000 249896526 0 1784827904 -0.0026787270 -0.0044975458 -0.0089691766 82 1311867721.3483059406 0.0387689099 0.0170822622 0.0402315110 0.0038467173 0.3138410000 249230344 0 1784078336 -0.0021828602 -0.0039741741 -0.0083867125 83 1311867721.3790040016 0.0417998172 0.0173800641 0.0417998172 0.0038757837 0.1945150000 248411367 0 1783873536 -0.0032258311 -0.0066802800 -0.0125212353 84 1311867721.4092550278 0.0392883644 0.0176408772 0.0417998172 0.0038924774 0.1827290000 248413893 0 1779367936 -0.0042312001 -0.0036729695 -0.0103217075 85 1311867721.4478130341 0.0437226556 0.0179477216 0.0437226556 0.0039249021 0.1854620000 248416587 0 1778401280 -0.0019884636 -0.0064813877 -0.0133683542 86 1311867721.4768960476 0.0405565798 0.0182106153 0.0437226556 0.0039762379 0.1780760000 248418809 0 1780170752 -0.0040043085 -0.0017135964 -0.0114700161 87 1311867721.5093359947 0.0435301624 0.0185016446 0.0437226556 0.0040487971 0.1825450000 248421111 0 1781821440 -0.0037088594 -0.0060676765 -0.0141441468 88 1311867721.5451331139 0.0414260961 0.0187621497 0.0437226556 0.0040591448 0.1815440000 248423501 0 1783488512 -0.0041950135 -0.0035260702 -0.0122081665 89 1311867721.5769670010 0.0424898900 0.0190287535 0.0437226556 0.0040366955 0.1805770000 248425803 0 1784741888 -0.0032952791 -0.0031714549 -0.0128085380 90 1311867721.6129651070 0.0428275056 0.0192931841 0.0437226556 0.0040328335 0.1797750000 248428137 0 1784487936 -0.0019813685 -0.0037105416 -0.0117479237 91 1311867721.6496050358 0.0426180623 0.0195495015 0.0437226556 0.0040515502 0.1829760000 248430543 0 1782599680 -0.0019307954 -0.0045272312 -0.0114112953 92 1311867721.6800351143 0.0434598736 0.0198093968 0.0437226556 0.0040492591 0.1767650000 248432613 0 1779404800 -0.0037138797 -0.0006177440 -0.0146826608 93 1311867721.7162289619 0.0415238068 0.0200428851 0.0437226556 0.0040856976 0.1839250000 248435371 0 1778126848 -0.0044174930 -0.0020480966 -0.0126511212 94 1311867721.7467949390 0.0449326448 0.0203076698 0.0449326448 0.0041840868 0.1797150000 248437697 0 1774563328 -0.0003550509 -0.0036376170 -0.0123904040 95 1311867721.7787001133 0.0462318249 0.0205805556 0.0462318249 0.0041693405 0.1696500000 248439711 0 1776594944 -0.0003088969 -0.0017478340 -0.0143006220 96 1311867721.8154830933 0.0463363752 0.0208488454 0.0463363752 0.0041491870 0.1793710000 248442245 0 1777754112 -0.0022910614 -0.0033879227 -0.0159758404 97 1311867721.8485159874 0.0473814011 0.0211223769 0.0473814011 0.0041338514 0.1649900000 248444339 0 1779908608 -0.0008734949 -0.0038025016 -0.0159616340 98 1311867721.8778810501 0.0449618325 0.0213656367 0.0473814011 0.0041354306 0.1820010000 248446689 0 1781157888 -0.0039617633 -0.0027790091 -0.0158567578 99 1311867721.9146931171 0.0464666896 0.0216191826 0.0473814011 0.0041170064 0.1738640000 248449079 0 1782935552 -0.0006440459 -0.0018949007 -0.0150454706 100 1311867721.9467151165 0.0437431037 0.0218404219 0.0473814011 0.0041038799 0.1744070000 248451157 0 1784971264 -0.0037450623 -0.0028039750 -0.0143653043 101 1311867721.9773728848 0.0460247286 0.0220798704 0.0473814011 0.0040902901 0.1753780000 248453523 0 1783955456 -0.0021882411 -0.0037216151 -0.0162723735 102 1311867722.0166850090 0.0436884649 0.0222917194 0.0473814011 0.0040806624 0.1749790000 248455753 0 1780158464 -0.0017280411 -0.0018486559 -0.0122780399 103 1311867722.0475180149 0.0480474010 0.0225417746 0.0480474010 0.0040829371 0.1695620000 248457791 0 1778757632 0.0000816062 -0.0036686931 -0.0171898473 104 1311867722.0800709724 0.0456828251 0.0227642847 0.0480474010 0.0040707447 0.1671930000 248460165 0 1777102848 -0.0028221384 -0.0031026399 -0.0166387595 105 1311867722.1161251068 0.0460561588 0.0229861120 0.0480474010 0.0040569119 0.1765080000 248462419 0 1775820800 -0.0022012419 -0.0046673752 -0.0161055177 106 1311867722.1479530334 0.0446073189 0.0231900857 0.0480474010 0.0040739807 0.1738590000 248464753 0 1775316992 -0.0019606771 -0.0027523206 -0.0141333845 107 1311867722.1798410416 0.0493352637 0.0234344332 0.0493352637 0.0040991682 0.1739000000 248466895 0 1777094656 -0.0011478714 -0.0038792491 -0.0201738421 108 1311867722.2146399021 0.0482796952 0.0236644819 0.0493352637 0.0040835722 0.1741740000 248469269 0 1778745344 -0.0003126236 -0.0029493927 -0.0180287454 109 1311867722.2469589710 0.0435071997 0.0238465252 0.0493352637 0.0041199960 0.1698560000 248471403 0 1780776960 -0.0025519319 -0.0018922882 -0.0133188982 110 1311867722.2780389786 0.0499227941 0.0240835821 0.0499227941 0.0042325478 0.1738100000 248473713 0 1782046720 -0.0015467159 -0.0034764870 -0.0213322379 111 1311867722.3154170513 0.0474672914 0.0242942462 0.0499227941 0.0042389111 0.1723010000 248475751 0 1783934976 -0.0011571385 -0.0047537657 -0.0168124828 112 1311867722.3488469124 0.0443847664 0.0244736258 0.0499227941 0.0042650057 0.1704610000 248478261 0 1785839616 -0.0026359432 -0.0020188836 -0.0142721133 113 1311867722.3777940273 0.0499043092 0.0246986761 0.0499227941 0.0043061933 0.1744150000 248479987 0 1784995840 0.0004881886 -0.0044319886 -0.0183256324 114 1311867722.4150679111 0.0496324189 0.0249173932 0.0499227941 0.0042873727 0.1729790000 248482353 0 1783586816 0.0012072651 -0.0045174677 -0.0163929611 115 1311867722.4467909336 0.0488278978 0.0251253106 0.0499227941 0.0043348056 0.2414560000 248913275 0 1782214656 -0.0011252509 -0.0055348682 -0.0180968437 116 1311867722.4777851105 0.0502316430 0.0253417445 0.0502316430 0.0043818048 0.3542440000 248875529 0 1784557568 -0.0001685815 -0.0039845994 -0.0181452297 117 1311867722.5147399902 0.0508261211 0.0255595597 0.0508261211 0.0043654799 0.3228590000 248992635 0 1782476800 0.0009314534 -0.0058204518 -0.0167671405 118 1311867722.5469911098 0.0510423668 0.0257755157 0.0510423668 0.0043534401 0.2727080000 250136060 0 1778331648 0.0024214415 -0.0041338047 -0.0155371688 119 1311867722.5802359581 0.0484128259 0.0259657452 0.0510423668 0.0043452660 0.3391840000 249726982 0 1773887488 -0.0002970286 -0.0030243758 -0.0150480596 120 1311867722.6146309376 0.0488348752 0.0261563213 0.0510423668 0.0043286953 0.1990980000 248883945 0 1774043136 0.0001470638 -0.0045366171 -0.0149172600 121 1311867722.6560258865 0.0482431054 0.0263388567 0.0510423668 0.0043146404 0.1825850000 248886287 0 1775771648 0.0002187020 -0.0047638137 -0.0138900345 122 1311867722.6778230667 0.0480997525 0.0265172247 0.0510423668 0.0043022995 0.1792530000 248888517 0 1777422336 -0.0009994484 -0.0045086038 -0.0153146619 123 1311867722.7252709866 0.0484871864 0.0266958422 0.0510423668 0.0043822229 0.1742580000 248890987 0 1779363840 -0.0005594594 -0.0045318948 -0.0143909901 124 1311867722.7449109554 0.0488534607 0.0268745327 0.0510423668 0.0044002133 0.1882400000 248892905 0 1780850688 -0.0002298104 -0.0055180169 -0.0146894632 125 1311867722.7770080566 0.0540068969 0.0270915916 0.0540068969 0.0044048697 0.1698110000 248895415 0 1782738944 0.0017567244 -0.0076602139 -0.0196186844 126 1311867722.8162860870 0.0513679534 0.0272842612 0.0540068969 0.0044008043 0.1769870000 248897989 0 1784389632 -0.0013853502 -0.0066164434 -0.0184473954 127 1311867722.8466939926 0.0514327884 0.0274744071 0.0540068969 0.0043975614 0.1738880000 248900147 0 1785786368 -0.0013591531 -0.0081939073 -0.0176506564 128 1311867722.8819770813 0.0508099496 0.0276567160 0.0540068969 0.0044016199 0.1760150000 248902625 0 1784897536 -0.0017031333 -0.0070953295 -0.0166074671 129 1311867722.9150629044 0.0526912808 0.0278507824 0.0540068969 0.0043911179 0.1726740000 248914799 0 1784426496 -0.0023185229 -0.0090352288 -0.0186181031 130 1311867722.9485991001 0.0531208813 0.0280451677 0.0540068969 0.0043801069 0.1756230000 248937997 0 1785802752 0.0000794199 -0.0070161251 -0.0162738729 131 1311867722.9821140766 0.0530144908 0.0282357733 0.0540068969 0.0043666693 0.1767210000 248940547 0 1784926208 -0.0012189103 -0.0079412777 -0.0165615082 132 1311867723.0147259235 0.0573847406 0.0284565988 0.0573847406 0.0043618582 0.1711850000 248942489 0 1784692736 0.0011006622 -0.0067647616 -0.0203696787 133 1311867723.0460629463 0.0553845800 0.0286590648 0.0573847406 0.0043542607 0.1703740000 248944591 0 1784045568 0.0006701439 -0.0075657358 -0.0165223796 134 1311867723.0845439434 0.0565026589 0.0288668528 0.0573847406 0.0043478682 0.1709340000 248946805 0 1780391936 0.0002949480 -0.0072147883 -0.0183914173 135 1311867723.1140980721 0.0550521091 0.0290608177 0.0573847406 0.0043350682 0.1679440000 248948891 0 1779982336 -0.0011725589 -0.0090815146 -0.0164704528 136 1311867723.1505160332 0.0563431606 0.0292614231 0.0573847406 0.0043231616 0.1667290000 248951297 0 1778200576 -0.0004228004 -0.0100555643 -0.0166339744 137 1311867723.1811029911 0.0565839857 0.0294608579 0.0573847406 0.0043075088 0.1638870000 248953503 0 1777553408 -0.0005203625 -0.0101512047 -0.0167841092 138 1311867723.2201359272 0.0565768741 0.0296573508 0.0573847406 0.0042922876 0.1930160000 248955805 0 1779335168 -0.0009104162 -0.0095753158 -0.0171311591 139 1311867723.2486810684 0.0578103140 0.0298598901 0.0578103140 0.0042875537 0.1657580000 248957651 0 1781002240 -0.0010195374 -0.0126944380 -0.0176346675 140 1311867723.2846419811 0.0584085472 0.0300638091 0.0584085472 0.0042770242 0.1611070000 248959945 0 1782784000 -0.0005775206 -0.0130122295 -0.0174598210 141 1311867723.3132460117 0.0591324754 0.0302699698 0.0591324754 0.0042684560 0.1673790000 248962119 0 1784414208 -0.0011459338 -0.0134820547 -0.0190008860 142 1311867723.3499810696 0.0591200516 0.0304731394 0.0591324754 0.0042727673 0.1631180000 248964373 0 1783549952 -0.0019701831 -0.0118754571 -0.0199472960 143 1311867723.3822429180 0.0575897060 0.0306627657 0.0591324754 0.0042588753 0.1591490000 248966755 0 1782792192 -0.0022056913 -0.0115982890 -0.0173690915 144 1311867723.4193739891 0.0582908466 0.0308546274 0.0591324754 0.0042718961 0.1654390000 248969121 0 1780494336 -0.0019869218 -0.0109282285 -0.0181492213 145 1311867723.4455900192 0.0596419834 0.0310531609 0.0596419834 0.0042735565 0.1624630000 248971231 0 1779335168 -0.0024850136 -0.0137125337 -0.0194592271 146 1311867723.4825348854 0.0594688877 0.0312477892 0.0596419834 0.0042778134 0.1645160000 248973637 0 1781121024 -0.0032200189 -0.0151157835 -0.0184032843 147 1311867723.5147960186 0.0603996925 0.0314461014 0.0603996925 0.0042637179 0.1967820000 249371415 0 1783128064 -0.0031899335 -0.0143362209 -0.0196559280 148 1311867723.5451340675 0.0589813739 0.0316321506 0.0603996925 0.0042547409 0.3494910000 249329457 0 1784406016 -0.0041760216 -0.0127163827 -0.0185491331 149 1311867723.5809938908 0.0615148284 0.0318327055 0.0615148284 0.0042535825 0.3159250000 249471727 0 1784176640 -0.0047676340 -0.0138314739 -0.0223452933 150 1311867723.6132669449 0.0601443090 0.0320214495 0.0615148284 0.0042396160 0.2467730000 251069220 0 1782259712 -0.0059997821 -0.0145565439 -0.0206774175 151 1311867723.6453940868 0.0581675060 0.0321946022 0.0615148284 0.0042425690 0.2071220000 250992354 0 1779892224 -0.0043106508 -0.0129622808 -0.0155261755 152 1311867723.6809489727 0.0541064180 0.0323387589 0.0615148284 0.0042577268 0.2551200000 250184858 0 1778188288 -0.0087419692 -0.0096678017 -0.0157871209 153 1311867723.7130429745 0.0534695499 0.0324768686 0.0615148284 0.0042438928 0.1713510000 249345139 0 1778339840 -0.0091613885 -0.0106860213 -0.0143628828 154 1311867723.7471990585 0.0539412387 0.0326162476 0.0615148284 0.0042302812 0.1704940000 249347193 0 1780154368 -0.0081506018 -0.0091637960 -0.0139296437 155 1311867723.7809250355 0.0548886918 0.0327599408 0.0615148284 0.0042216075 0.1643620000 249349887 0 1782145024 -0.0079506682 -0.0104926201 -0.0143078323 156 1311867723.8157649040 0.0543958731 0.0328986327 0.0615148284 0.0042164313 0.1639730000 249352069 0 1783414784 -0.0098778289 -0.0120258443 -0.0152022298 157 1311867723.8468959332 0.0554427579 0.0330422258 0.0615148284 0.0042067269 0.1690970000 249354339 0 1785446400 -0.0096326992 -0.0102319084 -0.0173684768 158 1311867723.8826351166 0.0549383610 0.0331808090 0.0615148284 0.0041970379 0.1636420000 249356673 0 1784344576 -0.0103463763 -0.0098782415 -0.0172463935 159 1311867723.9172909260 0.0565663278 0.0333278877 0.0615148284 0.0041887385 0.1750220000 249358663 0 1780154368 -0.0091394912 -0.0115187382 -0.0173555426 160 1311867723.9490020275 0.0589838661 0.0334882376 0.0615148284 0.0041795899 0.1614020000 249360749 0 1778728960 -0.0081875362 -0.0104760053 -0.0201899689 161 1311867723.9839010239 0.0536737218 0.0336136133 0.0615148284 0.0041814778 0.1650560000 249362979 0 1777364992 -0.0113487458 -0.0113501670 -0.0146601424 162 1311867724.0132899284 0.0547300838 0.0337439618 0.0615148284 0.0041694626 0.1890640000 249365169 0 1778991104 -0.0111141717 -0.0083407182 -0.0174873229 163 1311867724.0475380421 0.0563799776 0.0338828331 0.0615148284 0.0041603072 0.1629440000 249367591 0 1781059584 -0.0098961582 -0.0098813232 -0.0176693071 164 1311867724.0824530125 0.0552405901 0.0340130633 0.0615148284 0.0041485452 0.1879390000 249748409 0 1782652928 -0.0107282642 -0.0094377045 -0.0168815255 165 1311867724.1132431030 0.0554317795 0.0341428737 0.0615148284 0.0041383307 0.3343510000 249700963 0 1784438784 -0.0113263726 -0.0106528522 -0.0172546059 166 1311867724.1547191143 0.0589493960 0.0342923106 0.0615148284 0.0041322982 0.3116000000 249864181 0 1783713792 -0.0098819165 -0.0119796116 -0.0200893134 167 1311867724.1810541153 0.0551996119 0.0344175040 0.0615148284 0.0041654983 0.2786390000 251562114 0 1781604352 -0.0107841212 -0.0086636674 -0.0158520322 168 1311867724.2139430046 0.0569199808 0.0345514473 0.0615148284 0.0041646092 0.2047770000 251482492 0 1780666368 -0.0110508744 -0.0106244953 -0.0180993471 169 1311867724.2507870197 0.0571611077 0.0346852323 0.0615148284 0.0041541287 0.2930040000 250675528 0 1781108736 -0.0138869882 -0.0098673701 -0.0215397887 170 1311867724.2855930328 0.0580660850 0.0348227667 0.0615148284 0.0041518965 0.1552220000 249716805 0 1781403648 -0.0127526913 -0.0084817968 -0.0219317898 171 1311867724.3144888878 0.0560707822 0.0349470241 0.0615148284 0.0041516517 0.1651060000 249718587 0 1782648832 -0.0140486779 -0.0091963578 -0.0199155472 172 1311867724.3517999649 0.0570316091 0.0350754229 0.0615148284 0.0041419520 0.1592540000 249720977 0 1784446976 -0.0152860284 -0.0097128162 -0.0226117130 173 1311867724.3888330460 0.0569437556 0.0352018294 0.0615148284 0.0041333239 0.1561550000 249723167 0 1783578624 -0.0142269842 -0.0104349414 -0.0208891593 174 1311867724.4160330296 0.0546393208 0.0353135392 0.0615148284 0.0041326794 0.1641940000 249725133 0 1783164928 -0.0139074409 -0.0090487767 -0.0175869316 175 1311867724.4509639740 0.0557425804 0.0354302765 0.0615148284 0.0041273825 0.1551720000 249727043 0 1779109888 -0.0142831029 -0.0112184994 -0.0194304250 176 1311867724.4830689430 0.0565034002 0.0355500102 0.0615148284 0.0041182286 0.1647750000 249729377 0 1777840128 -0.0165184941 -0.0110055041 -0.0234313458 177 1311867724.5208630562 0.0572163872 0.0356724191 0.0615148284 0.0041153791 0.1617250000 249731383 0 1779630080 -0.0154084750 -0.0130683454 -0.0225005448 178 1311867724.5523910522 0.0596400835 0.0358070689 0.0615148284 0.0041257435 0.1606270000 249733493 0 1780895744 -0.0155187091 -0.0132233985 -0.0265658200 179 1311867724.5861799717 0.0571785532 0.0359264627 0.0615148284 0.0041417560 0.1550530000 249735627 0 1782923264 -0.0147676030 -0.0123298261 -0.0218751766 180 1311867724.6193559170 0.0621726289 0.0360722747 0.0621726289 0.0041534729 0.1576710000 249737841 0 1784426496 -0.0158410370 -0.0134223243 -0.0308194719 181 1311867724.6529819965 0.0588083118 0.0361978882 0.0621726289 0.0041553347 0.1626990000 249739807 0 1783816192 -0.0150216371 -0.0133977216 -0.0244133249 182 1311867724.6818330288 0.0563847721 0.0363088051 0.0621726289 0.0041462992 0.1610180000 249742013 0 1783054336 -0.0187069066 -0.0136052277 -0.0244248472 183 1311867724.7153129578 0.0613263398 0.0364455130 0.0621726289 0.0041414727 0.1958070000 250107843 0 1779232768 -0.0180580616 -0.0123070832 -0.0309020914 184 1311867724.7518899441 0.0616778843 0.0365826454 0.0621726289 0.0041335919 0.3063720000 250060801 0 1781284864 -0.0196960084 -0.0135742314 -0.0317276344 185 1311867724.7853860855 0.0604487993 0.0367116517 0.0621726289 0.0041305113 0.2775610000 250234959 0 1782726656 -0.0197655261 -0.0155188199 -0.0288121309 186 1311867724.8179960251 0.0598875470 0.0368362532 0.0621726289 0.0041266978 0.2708490000 252007504 0 1785352192 -0.0194977708 -0.0151563492 -0.0273201857 187 1311867724.8547580242 0.0599705987 0.0369599663 0.0621726289 0.0041367470 0.1923930000 251885838 0 1784332288 -0.0202056710 -0.0151152369 -0.0281877704 188 1311867724.8830249310 0.0598663576 0.0370818088 0.0621726289 0.0041263246 0.2847380000 251114078 0 1783590912 -0.0211677644 -0.0151385600 -0.0288915671 189 1311867724.9137279987 0.0586113818 0.0371957219 0.0621726289 0.0041291501 0.1607890000 250075495 0 1784070144 -0.0206394680 -0.0151250884 -0.0258162767 190 1311867724.9535229206 0.0587050728 0.0373089290 0.0621726289 0.0041227329 0.1667910000 250077613 0 1785393152 -0.0205004178 -0.0146679338 -0.0259308293 191 1311867724.9843940735 0.0577923059 0.0374161718 0.0621726289 0.0041150666 0.1553820000 250080011 0 1784594432 -0.0230031051 -0.0170493145 -0.0260143727 192 1311867725.0159099102 0.0543023981 0.0375041209 0.0621726289 0.0041503720 0.1615250000 250082161 0 1783959552 -0.0223665517 -0.0132849868 -0.0224534050 193 1311867725.0518310070 0.0567151494 0.0376036599 0.0621726289 0.0041493992 0.1595470000 250084207 0 1781161984 -0.0216421410 -0.0158895906 -0.0240532346 194 1311867725.0813930035 0.0562373772 0.0376997100 0.0621726289 0.0041393143 0.1813970000 250451277 0 1780658176 -0.0240445212 -0.0148412110 -0.0262959506 195 1311867725.1151220798 0.0551854447 0.0377893805 0.0621726289 0.0041295495 0.3146840000 250413495 0 1783513088 -0.0232187156 -0.0156975128 -0.0233621132 196 1311867725.1557130814 0.0571687929 0.0378882550 0.0621726289 0.0041214431 0.2925720000 250411785 0 1785278464 -0.0239653047 -0.0166335311 -0.0266555808 197 1311867725.1843969822 0.0577706993 0.0379891811 0.0621726289 0.0041121638 0.2844900000 252406718 0 1785106432 -0.0231603514 -0.0153826289 -0.0272376351 198 1311867725.2150099277 0.0555349551 0.0380777961 0.0621726289 0.0041054127 0.2252400000 252345396 0 1784123392 -0.0267926585 -0.0167126805 -0.0267965626 199 1311867725.2516539097 0.0587382391 0.0381816175 0.0621726289 0.0041126727 0.3053650000 251538860 0 1783439360 -0.0263365302 -0.0167659353 -0.0303669851 200 1311867725.2816410065 0.0562915020 0.0382721669 0.0621726289 0.0041067999 0.1721620000 250425329 0 1783484416 -0.0262893159 -0.0162164960 -0.0268428065 201 1311867725.3196239471 0.0580754429 0.0383706906 0.0621726289 0.0040978641 0.1619240000 250427223 0 1785225216 -0.0267537627 -0.0158106927 -0.0298750587 202 1311867725.3517010212 0.0591753125 0.0384736838 0.0621726289 0.0040941100 0.1623760000 250429653 0 1784463360 -0.0275842324 -0.0193642620 -0.0302710459 203 1311867725.3837459087 0.0560488477 0.0385602610 0.0621726289 0.0041386047 0.1612720000 250431499 0 1783959552 -0.0277204178 -0.0142104058 -0.0282779410 204 1311867725.4178969860 0.0607594550 0.0386690806 0.0621726289 0.0041658744 0.1617910000 250433809 0 1780174848 -0.0261100624 -0.0195460729 -0.0306417104 205 1311867725.4492449760 0.0594810881 0.0387706026 0.0621726289 0.0041674355 0.1601280000 250435631 0 1779654656 -0.0278881602 -0.0180143341 -0.0304545313 206 1311867725.4836509228 0.0570441335 0.0388593090 0.0621726289 0.0041980694 0.1558560000 250438101 0 1781415936 -0.0285285749 -0.0163494293 -0.0273432378 207 1311867725.5178139210 0.0592637770 0.0389578813 0.0621726289 0.0042119796 0.1502570000 250440443 0 1783066624 -0.0281631537 -0.0155639313 -0.0298452228 208 1311867725.5497610569 0.0593510941 0.0390559256 0.0621726289 0.0042041155 0.1535910000 250442233 0 1784971264 -0.0295478031 -0.0171566438 -0.0299000293 209 1311867725.5815479755 0.0621565618 0.0391664550 0.0621726289 0.0042148815 0.1862400000 250444087 0 1784209408 -0.0276774373 -0.0169737134 -0.0311493743 210 1311867725.6194949150 0.0566698983 0.0392498047 0.0621726289 0.0042294119 0.1685760000 250446573 0 1783455744 -0.0303001888 -0.0145141054 -0.0261122659 211 1311867725.6515610218 0.0563937388 0.0393310556 0.0621726289 0.0042902471 0.1491610000 250448443 0 1781436416 -0.0312095452 -0.0163117182 -0.0258960333 212 1311867725.6834650040 0.0557124838 0.0394083265 0.0621726289 0.0042829121 0.1774220000 250811585 0 1780563968 -0.0333590619 -0.0140484851 -0.0275526661 213 1311867725.7201809883 0.0521098822 0.0394679582 0.0621726289 0.0042809902 0.3021470000 250761951 0 1782747136 -0.0361515246 -0.0133836633 -0.0249179527 214 1311867725.7515070438 0.0540249720 0.0395359816 0.0621726289 0.0042769119 0.2652720000 250943941 0 1783992320 -0.0341831520 -0.0147652626 -0.0250150785 215 1311867725.7835409641 0.0579399168 0.0396215813 0.0621726289 0.0042804488 0.2662260000 253139594 0 1785032704 -0.0333487839 -0.0158623643 -0.0292211920 216 1311867725.8211829662 0.0521594547 0.0396796270 0.0621726289 0.0043168069 0.2108950000 252794056 0 1784258560 -0.0377024971 -0.0129892547 -0.0255451463 217 1311867725.8517971039 0.0530048534 0.0397410336 0.0621726289 0.0043176608 0.2764940000 252026588 0 1783947264 -0.0355223566 -0.0141657554 -0.0235780906 218 1311867725.8837900162 0.0593896769 0.0398311650 0.0621726289 0.0043323314 0.1569940000 250777573 0 1784209408 -0.0334840976 -0.0181117542 -0.0281810109 219 1311867725.9192690849 0.0547394753 0.0398992395 0.0621726289 0.0043356771 0.1529430000 250779427 0 1785950208 -0.0363337398 -0.0148341190 -0.0250595864 220 1311867725.9511859417 0.0529132560 0.0399583941 0.0621726289 0.0043278882 0.1496280000 250781289 0 1785061376 -0.0387242883 -0.0140741663 -0.0246911943 221 1311867725.9829630852 0.0561658517 0.0400317310 0.0621726289 0.0043242177 0.1687150000 251144363 0 1784573952 -0.0369982347 -0.0149733219 -0.0269034468 222 1311867726.0219368935 0.0545411222 0.0400970886 0.0621726289 0.0043245340 0.2988860000 251100681 0 1784004608 -0.0343841463 -0.0119337179 -0.0219335631 223 1311867726.0504179001 0.0527699850 0.0401539177 0.0621726289 0.0043172535 0.2526620000 251276587 0 1783623680 -0.0384094119 -0.0128730955 -0.0232779682 224 1311867726.0845088959 0.0540708601 0.0402160470 0.0621726289 0.0043091628 0.2418130000 253364856 0 1783394304 -0.0368654057 -0.0104770362 -0.0246872306 225 1311867726.1199669838 0.0500886515 0.0402599252 0.0621726289 0.0043040835 0.1947360000 253236214 0 1782075392 -0.0408465378 -0.0117556592 -0.0222609676 226 1311867726.1506989002 0.0532411151 0.0403173641 0.0621726289 0.0042983977 0.2769770000 252469426 0 1778966528 -0.0377498455 -0.0118114064 -0.0237109549 227 1311867726.1824700832 0.0525782816 0.0403713769 0.0621726289 0.0042917344 0.1744660000 251110863 0 1779236864 -0.0406305119 -0.0127914231 -0.0254399292 228 1311867726.2198660374 0.0528254882 0.0404260002 0.0621726289 0.0042855733 0.1358670000 251113941 0 1780842496 -0.0383322090 -0.0117045939 -0.0237011425 229 1311867726.2506690025 0.0507021174 0.0404708741 0.0621726289 0.0042780861 0.1448570000 251115019 0 1782657024 -0.0399490185 -0.0118735256 -0.0218988061 230 1311867726.2845950127 0.0549458303 0.0405338087 0.0621726289 0.0042742009 0.1482270000 251116857 0 1784418304 -0.0379934721 -0.0092519540 -0.0270933174 231 1311867726.3187239170 0.0571212731 0.0406056159 0.0621726289 0.0042737416 0.1485220000 251119551 0 1785434112 -0.0374151915 -0.0121277478 -0.0282856748 232 1311867726.3524029255 0.0523128323 0.0406560780 0.0621726289 0.0042726621 0.1698310000 251121677 0 1785053184 -0.0412564091 -0.0138371568 -0.0237417687 233 1311867726.3835608959 0.0518402457 0.0407040788 0.0621726289 0.0042658950 0.1409550000 251123347 0 1784315904 -0.0425128341 -0.0109756105 -0.0252580903 234 1311867726.4218099117 0.0523772910 0.0407539643 0.0621726289 0.0042579042 0.1718700000 251434525 0 1783697408 -0.0423862524 -0.0098843742 -0.0257902201 235 1311867726.4504199028 0.0536660068 0.0408089092 0.0621726289 0.0042527808 0.2779140000 251421911 0 1785495552 -0.0424246863 -0.0108602382 -0.0270891599 236 1311867726.4843189716 0.0534500927 0.0408624735 0.0621726289 0.0042446176 0.2395640000 251565265 0 1784139776 -0.0451345332 -0.0138657512 -0.0280779693 237 1311867726.5207901001 0.0527487099 0.0409126264 0.0621726289 0.0042452002 0.2087130000 253760182 0 1785348096 -0.0446819589 -0.0082831532 -0.0283548553 238 1311867726.5524380207 0.0516234823 0.0409576300 0.0621726289 0.0042450665 0.1848480000 253630492 0 1784598528 -0.0440367237 -0.0085920058 -0.0254409648 239 1311867726.5874860287 0.0534236357 0.0410097890 0.0621726289 0.0042441881 0.2646230000 252865936 0 1784147968 -0.0458398238 -0.0089188814 -0.0293634459 240 1311867726.6204600334 0.0510856062 0.0410517716 0.0621726289 0.0042492464 0.1719560000 251436749 0 1784303616 -0.0441963673 -0.0060479599 -0.0254795607 241 1311867726.6509370804 0.0506614968 0.0410916459 0.0621726289 0.0042460243 0.1330100000 251439051 0 1785946112 -0.0458588116 -0.0058380617 -0.0268394072 242 1311867726.6916151047 0.0507076234 0.0411313814 0.0621726289 0.0042381658 0.1499380000 251440993 0 1785323520 -0.0460091680 -0.0073902477 -0.0270978324 243 1311867726.7201170921 0.0497204922 0.0411667275 0.0621726289 0.0042380660 0.1477980000 251442343 0 1784442880 -0.0446187146 -0.0062514730 -0.0245228205 244 1311867726.7513859272 0.0464957021 0.0411885676 0.0621726289 0.0042329153 0.1483010000 251445469 0 1782669312 -0.0454575904 -0.0082726534 -0.0200602300 245 1311867726.7880010605 0.0475003123 0.0412143298 0.0621726289 0.0042252076 0.1515780000 251447811 0 1781669888 -0.0443685800 -0.0083890967 -0.0209547132 246 1311867726.8198299408 0.0509422608 0.0412538742 0.0621726289 0.0042196392 0.1426380000 251449745 0 1783160832 -0.0443263724 -0.0074057165 -0.0273179766 247 1311867726.8500390053 0.0503084064 0.0412905323 0.0621726289 0.0042114872 0.1470120000 251451647 0 1784786944 -0.0437775888 -0.0083612250 -0.0255908109 248 1311867726.8927390575 0.0516017266 0.0413321097 0.0621726289 0.0042060075 0.1501650000 251453501 0 1784086528 -0.0449842289 -0.0102021620 -0.0285258666 249 1311867726.9216780663 0.0494524986 0.0413647217 0.0621726289 0.0042001612 0.1440590000 251455563 0 1783271424 -0.0460741557 -0.0094041703 -0.0268694889 250 1311867726.9543499947 0.0479064621 0.0413908886 0.0621726289 0.0041951021 0.1516940000 251457441 0 1782165504 -0.0454712771 -0.0097450446 -0.0234700702 251 1311867726.9902989864 0.0492368191 0.0414221473 0.0621726289 0.0041881477 0.1494170000 251459335 0 1783922688 -0.0439920425 -0.0103042740 -0.0238449313 252 1311867727.0208179951 0.0499086976 0.0414558241 0.0621726289 0.0041823881 0.1493280000 251461221 0 1785294848 -0.0435766242 -0.0092344675 -0.0251872465 253 1311867727.0536949635 0.0491148643 0.0414860970 0.0621726289 0.0041747794 0.1483580000 251462915 0 1784451072 -0.0433523841 -0.0080980407 -0.0246223416 254 1311867727.0911629200 0.0485822745 0.0415140347 0.0621726289 0.0041669448 0.1500340000 251465929 0 1783525376 -0.0431041680 -0.0090985438 -0.0238699429 255 1311867727.1196689606 0.0493465923 0.0415447506 0.0621726289 0.0041612710 0.1549400000 251467991 0 1782816768 -0.0436567217 -0.0116460323 -0.0252986662 256 1311867727.1514298916 0.0487448797 0.0415728761 0.0621726289 0.0041542993 0.1555420000 251469997 0 1784561664 -0.0418564454 -0.0099066971 -0.0235279836 257 1311867727.1904149055 0.0493568256 0.0416031639 0.0621726289 0.0041700827 0.1574530000 251492915 0 1783685120 -0.0412337109 -0.0106129106 -0.0248955786 258 1311867727.2208960056 0.0494620092 0.0416336245 0.0621726289 0.0041637079 0.1474910000 251535937 0 1782530048 -0.0430624373 -0.0123151187 -0.0267915931 259 1311867727.2544560432 0.0502153598 0.0416667586 0.0621726289 0.0041602065 0.1804120000 251538831 0 1781420032 -0.0402070507 -0.0113501502 -0.0256398953 260 1311867727.2870850563 0.0485003255 0.0416930416 0.0621726289 0.0041545065 0.1586190000 251540693 0 1783160832 -0.0416024290 -0.0109750498 -0.0253013708 261 1311867727.3192501068 0.0497298203 0.0417238338 0.0621726289 0.0041515053 0.1504280000 251542955 0 1784913920 -0.0393709652 -0.0126058459 -0.0248265974 262 1311867727.3502039909 0.0478923209 0.0417473777 0.0621726289 0.0041485910 0.1553200000 251544441 0 1784070144 -0.0395626314 -0.0107765114 -0.0235951133 263 1311867727.3894629478 0.0500275455 0.0417788612 0.0621726289 0.0041513126 0.1604040000 251547567 0 1782927360 -0.0383126959 -0.0096211117 -0.0270637926 264 1311867727.4182970524 0.0469456241 0.0417984323 0.0621726289 0.0041476516 0.1596430000 251549597 0 1779617792 -0.0392922312 -0.0103078112 -0.0238583833 265 1311867727.4495580196 0.0509844869 0.0418330966 0.0621726289 0.0041692028 0.1539370000 251551459 0 1778475008 -0.0376309305 -0.0150392726 -0.0268315002 266 1311867727.4858360291 0.0512308478 0.0418684265 0.0621726289 0.0041682827 0.1590160000 251553721 0 1780244480 -0.0359842926 -0.0133671230 -0.0268345885 267 1311867727.5198891163 0.0490395539 0.0418952847 0.0621726289 0.0041642314 0.1573170000 251555575 0 1781764096 -0.0354762115 -0.0111468798 -0.0245220345 268 1311867727.5494980812 0.0458549149 0.0419100594 0.0621726289 0.0041802007 0.1594140000 251557253 0 1783644160 -0.0363008715 -0.0108325165 -0.0219751671 269 1311867727.5905909538 0.0459284671 0.0419249977 0.0621726289 0.0041782178 0.1588450000 251559603 0 1785421824 -0.0364067182 -0.0109544005 -0.0243320502 270 1311867727.6176431179 0.0455695316 0.0419384960 0.0621726289 0.0041782463 0.1616670000 251561553 0 1784561664 -0.0351656526 -0.0106731644 -0.0236096662 271 1311867727.6497650146 0.0469343029 0.0419569307 0.0621726289 0.0041787883 0.1576230000 251563599 0 1783418880 -0.0347661898 -0.0126543371 -0.0253098793 272 1311867727.6884338856 0.0465389080 0.0419737762 0.0621726289 0.0041734685 0.1626320000 251566133 0 1779617792 -0.0338617973 -0.0093420194 -0.0264680460 273 1311867727.7184689045 0.0484903939 0.0419976466 0.0621726289 0.0041742567 0.1627160000 251568283 0 1778597888 -0.0334984176 -0.0135481926 -0.0281831902 274 1311867727.7523269653 0.0485392027 0.0420215209 0.0621726289 0.0041696252 0.1548250000 251570289 0 1780383744 -0.0333975255 -0.0138094183 -0.0284690168 275 1311867727.7856590748 0.0504959151 0.0420523369 0.0621726289 0.0041637890 0.1612550000 251572503 0 1782034432 -0.0341709182 -0.0148018571 -0.0321451016 276 1311867727.8181309700 0.0502599552 0.0420820746 0.0621726289 0.0041588665 0.1566590000 251574669 0 1783787520 -0.0344936140 -0.0152108995 -0.0323747024 277 1311867727.8548729420 0.0504478179 0.0421122759 0.0621726289 0.0041526813 0.1564420000 251576491 0 1785167872 -0.0334965959 -0.0142925680 -0.0320676863 278 1311867727.8882629871 0.0495194085 0.0421389202 0.0621726289 0.0041457309 0.1601140000 251578529 0 1784471552 -0.0340968296 -0.0136407623 -0.0318756290 279 1311867727.9193139076 0.0506327152 0.0421693639 0.0621726289 0.0041383738 0.1640860000 251580815 0 1783947264 -0.0339983739 -0.0119610401 -0.0342934914 280 1311867727.9556980133 0.0493194610 0.0421949000 0.0621726289 0.0041332094 0.1615890000 251582461 0 1779855360 -0.0318749212 -0.0119438097 -0.0305814706 281 1311867727.9869389534 0.0486604609 0.0422179091 0.0621726289 0.0041261331 0.1599640000 251584635 0 1778475008 -0.0328119025 -0.0118362373 -0.0314021818 282 1311867728.0179219246 0.0494012348 0.0422433819 0.0621726289 0.0041310816 0.1561060000 251586561 0 1779986432 -0.0307013001 -0.0092810830 -0.0313150696 283 1311867728.0555219650 0.0485624969 0.0422657109 0.0621726289 0.0041251755 0.1600100000 251588879 0 1781911552 -0.0296703689 -0.0089045111 -0.0296992641 284 1311867728.0892169476 0.0495609008 0.0422913982 0.0621726289 0.0041214904 0.1588590000 251590933 0 1783541760 -0.0295695905 -0.0106503842 -0.0314315856 285 1311867728.1177880764 0.0497448221 0.0423175506 0.0621726289 0.0041214650 0.1559070000 251593035 0 1785192448 -0.0293677598 -0.0103424406 -0.0327427611 286 1311867728.1556169987 0.0494010672 0.0423423181 0.0621726289 0.0041160532 0.1656550000 251595113 0 1784176640 -0.0291569643 -0.0101742325 -0.0329128392 287 1311867728.1882989407 0.0506572202 0.0423712899 0.0621726289 0.0041121836 0.1632000000 251597159 0 1784033280 -0.0283034928 -0.0120855719 -0.0339388363 288 1311867728.2182519436 0.0498724692 0.0423973357 0.0621726289 0.0041124511 0.1886910000 251599109 0 1781002240 -0.0293159187 -0.0112570915 -0.0347711816 289 1311867728.2558999062 0.0494567230 0.0424217626 0.0621726289 0.0041065209 0.1588260000 251601291 0 1782689792 -0.0282340515 -0.0107289506 -0.0338962339 290 1311867728.2875900269 0.0517540202 0.0424539428 0.0621726289 0.0041017249 0.1616850000 251603161 0 1784049664 -0.0261715166 -0.0110793803 -0.0355276316 291 1311867728.3226509094 0.0532115959 0.0424909107 0.0621726289 0.0041097214 0.1579590000 251605247 0 1785716736 -0.0265021008 -0.0110773835 -0.0380614288 292 1311867728.3597300053 0.0513244867 0.0425211627 0.0621726289 0.0041203770 0.1592690000 251607333 0 1784938496 -0.0257785507 -0.0098193875 -0.0355719663 293 1311867728.3861401081 0.0517063551 0.0425525114 0.0621726289 0.0041173111 0.1547830000 251609131 0 1784451072 -0.0255102329 -0.0119560063 -0.0356298611 294 1311867728.4175701141 0.0504811518 0.0425794796 0.0621726289 0.0041577121 0.1641200000 251611049 0 1782013952 -0.0264028218 -0.0132946279 -0.0357023776 295 1311867728.4568250179 0.0516297109 0.0426101584 0.0621726289 0.0041561623 0.1589690000 251613231 0 1781272576 -0.0254335739 -0.0103772338 -0.0381646752 296 1311867728.4875330925 0.0514866635 0.0426401465 0.0621726289 0.0041504152 0.1597310000 251615173 0 1780621312 -0.0237122755 -0.0108778831 -0.0363677144 297 1311867728.5187420845 0.0509416722 0.0426680978 0.0621726289 0.0041464580 0.1667300000 251617267 0 1777836032 -0.0240841955 -0.0107326685 -0.0365243815 298 1311867728.5550920963 0.0505276807 0.0426944723 0.0621726289 0.0041401434 0.1672820000 251619601 0 1777569792 -0.0247869864 -0.0121521978 -0.0367501564 299 1311867728.5878560543 0.0506044403 0.0427209270 0.0621726289 0.0041336982 0.1587780000 251621407 0 1779388416 -0.0236338824 -0.0105277915 -0.0369032733 300 1311867728.6187679768 0.0518956855 0.0427515095 0.0621726289 0.0041285258 0.1568930000 251623501 0 1781002240 -0.0222579036 -0.0118778991 -0.0374036841 301 1311867728.6580820084 0.0527490638 0.0427847240 0.0621726289 0.0041220364 0.1585490000 251625467 0 1783033856 -0.0220690165 -0.0123776654 -0.0389600918 302 1311867728.6893489361 0.0506708808 0.0428108371 0.0621726289 0.0041193297 0.1616620000 251627609 0 1784320000 -0.0229927134 -0.0104715377 -0.0379460342 303 1311867728.7210168839 0.0502052903 0.0428352412 0.0621726289 0.0041191124 0.1636300000 251629391 0 1784197120 -0.0222484469 -0.0097556924 -0.0368061364 304 1311867728.7584259510 0.0525488891 0.0428671940 0.0621726289 0.0041168521 0.1666230000 251631661 0 1783287808 -0.0224159025 -0.0120093683 -0.0406525917 305 1311867728.7858450413 0.0504568927 0.0428920783 0.0621726289 0.0041137569 0.1570220000 251633371 0 1780531200 -0.0221625268 -0.0112769604 -0.0379743092 306 1311867728.8203740120 0.0536948033 0.0429273813 0.0621726289 0.0041119899 0.1632080000 251635457 0 1779732480 -0.0212664157 -0.0117985308 -0.0430204719 307 1311867728.8545160294 0.0497593172 0.0429496352 0.0621726289 0.0041193321 0.1571310000 251637559 0 1781800960 -0.0231157709 -0.0099070203 -0.0404204205 308 1311867728.8860759735 0.0505439527 0.0429742920 0.0621726289 0.0041158578 0.1639840000 251639717 0 1783033856 -0.0210005194 -0.0117931869 -0.0390875190 309 1311867728.9193949699 0.0514916368 0.0430018563 0.0621726289 0.0041102054 0.1565320000 251641459 0 1785085952 -0.0206684209 -0.0100774365 -0.0417048186 310 1311867728.9585559368 0.0513602942 0.0430288190 0.0621726289 0.0041267710 0.1619120000 251643761 0 1783816192 -0.0206840225 -0.0105274338 -0.0423346311 311 1311867728.9886839390 0.0507532097 0.0430536562 0.0621726289 0.0041240701 0.1623950000 251645911 0 1783037952 -0.0196801350 -0.0100882584 -0.0411444604 312 1311867729.0231020451 0.0504971184 0.0430775135 0.0621726289 0.0041228287 0.1609350000 251647949 0 1779507200 -0.0200452991 -0.0099929571 -0.0417610779 313 1311867729.0583839417 0.0506442264 0.0431016883 0.0621726289 0.0041194997 0.1635230000 251649947 0 1778589696 -0.0191935990 -0.0089951325 -0.0414900929 314 1311867729.0882170200 0.0533290766 0.0431342596 0.0621726289 0.0041166186 0.1674410000 251651889 0 1777737728 -0.0188012868 -0.0106275678 -0.0442562513 315 1311867729.1263229847 0.0534624718 0.0431670476 0.0621726289 0.0041267859 0.1621870000 251653999 0 1776939008 -0.0197995417 -0.0083424458 -0.0453967117 316 1311867729.1556320190 0.0538230427 0.0432007691 0.0621726289 0.0041269557 0.1952760000 251656125 0 1776558080 -0.0178158879 -0.0096080285 -0.0425875746 317 1311867729.1888830662 0.0525899604 0.0432303880 0.0621726289 0.0041495364 0.1654950000 251658091 0 1776431104 -0.0203541089 -0.0089915656 -0.0427671671 318 1311867729.2240469456 0.0523127802 0.0432589489 0.0621726289 0.0041567740 0.1605720000 251660233 0 1777700864 -0.0199103504 -0.0071405154 -0.0418298617 319 1311867729.2579979897 0.0496523865 0.0432789911 0.0621726289 0.0041522789 0.1580480000 251662231 0 1779896320 -0.0198962688 -0.0073899087 -0.0375968292 320 1311867729.2880148888 0.0502182171 0.0433006761 0.0621726289 0.0041465354 0.1550300000 251664445 0 1781129216 -0.0192972310 -0.0087518608 -0.0375288725 321 1311867729.3236539364 0.0498633198 0.0433211205 0.0621726289 0.0041425060 0.1574880000 251666443 0 1783152640 -0.0193537921 -0.0083422419 -0.0377884544 322 1311867729.3580930233 0.0493412279 0.0433398165 0.0621726289 0.0041504779 0.1603610000 251668569 0 1784680448 -0.0201704539 -0.0089350548 -0.0386413075 323 1311867729.3882780075 0.0520781428 0.0433668701 0.0621726289 0.0041456621 0.1616760000 251670527 0 1784041472 -0.0165789947 -0.0084361164 -0.0396639146 324 1311867729.4253289700 0.0523511767 0.0433945995 0.0621726289 0.0041393144 0.1611080000 251672517 0 1783533568 -0.0173954815 -0.0088121584 -0.0416125804 325 1311867729.4572670460 0.0495346151 0.0434134918 0.0621726289 0.0041461801 0.1622200000 251674635 0 1780359168 -0.0158949941 -0.0071075475 -0.0370809063 326 1311867729.4887750149 0.0517266281 0.0434389923 0.0621726289 0.0041680738 0.1668180000 251676641 0 1779597312 -0.0146406991 -0.0095425369 -0.0390405282 327 1311867729.5223650932 0.0519162603 0.0434649166 0.0621726289 0.0041617665 0.1661720000 251678559 0 1779089408 -0.0142681720 -0.0090635521 -0.0396801531 328 1311867729.5603790283 0.0522300228 0.0434916395 0.0621726289 0.0041589687 0.1617280000 251680901 0 1780252672 -0.0136759197 -0.0103065446 -0.0398654491 329 1311867729.5890150070 0.0483388454 0.0435063727 0.0621726289 0.0041693416 0.1669550000 251682715 0 1782153216 -0.0140653243 -0.0090699559 -0.0350948460 330 1311867729.6254830360 0.0528625399 0.0435347247 0.0621726289 0.0041746261 0.1733740000 251684569 0 1783914496 -0.0121710999 -0.0105822142 -0.0400075689 331 1311867729.6614611149 0.0514470190 0.0435586289 0.0621726289 0.0041689021 0.1677010000 251686935 0 1785565184 -0.0127585568 -0.0111612268 -0.0386254638 332 1311867729.6888220310 0.0532232560 0.0435877392 0.0621726289 0.0041642140 0.1686690000 251688805 0 1784823808 -0.0129362978 -0.0112081338 -0.0414933451 333 1311867729.7230739594 0.0521449074 0.0436134364 0.0621726289 0.0041610989 0.1599310000 251690979 0 1784573952 -0.0117798969 -0.0103432108 -0.0390943550 334 1311867729.7570610046 0.0511764362 0.0436360801 0.0621726289 0.0041608308 0.1597840000 251692833 0 1781243904 -0.0118683511 -0.0128033422 -0.0377232358 335 1311867729.7899730206 0.0478098914 0.0436485393 0.0621726289 0.0041682897 0.1654210000 251695271 0 1779978240 -0.0111718755 -0.0112286136 -0.0324307084 336 1311867729.8264250755 0.0497647151 0.0436667422 0.0621726289 0.0041647571 0.1690400000 251697061 0 1779253248 -0.0104234396 -0.0099063050 -0.0354603156 337 1311867729.8550031185 0.0512082465 0.0436891205 0.0621726289 0.0041617001 0.1704080000 251699099 0 1778835456 -0.0082424413 -0.0124119530 -0.0347976200 338 1311867729.8881840706 0.0522568002 0.0437144687 0.0621726289 0.0041591849 0.1670240000 251701169 0 1780867072 -0.0088556865 -0.0127324425 -0.0371410921 339 1311867729.9233629704 0.0490441397 0.0437301904 0.0621726289 0.0041619511 0.1704640000 251703143 0 1782554624 -0.0095391013 -0.0129509419 -0.0330468491 340 1311867729.9569330215 0.0523769408 0.0437556221 0.0621726289 0.0041595678 0.1773220000 251705317 0 1784295424 -0.0076772710 -0.0125455204 -0.0362536013 341 1311867729.9865698814 0.0482701138 0.0437688610 0.0621726289 0.0041596222 0.1725590000 251707339 0 1783681024 -0.0104633644 -0.0124359569 -0.0333741605 342 1311867730.0230469704 0.0477129333 0.0437803934 0.0621726289 0.0041553008 0.1716140000 251709353 0 1779752960 -0.0088486094 -0.0127045484 -0.0308893714 343 1311867730.0557899475 0.0482224748 0.0437933441 0.0621726289 0.0041537498 0.1761820000 251711703 0 1778085888 -0.0083569633 -0.0101551898 -0.0319971219 344 1311867730.0871100426 0.0489272550 0.0438082682 0.0621726289 0.0041505123 0.1713370000 251713229 0 1779871744 -0.0092666103 -0.0109749641 -0.0341874734 345 1311867730.1231229305 0.0488869920 0.0438229892 0.0621726289 0.0041452472 0.1718210000 251715379 0 1781649408 -0.0087244576 -0.0117181409 -0.0335446522 346 1311867730.1568520069 0.0477881022 0.0438344490 0.0621726289 0.0041397740 0.1739630000 251717481 0 1782898688 -0.0088734161 -0.0116678430 -0.0319493487 347 1311867730.1882419586 0.0473905727 0.0438446972 0.0621726289 0.0041361447 0.1697470000 251719575 0 1784659968 -0.0095693190 -0.0110411821 -0.0323637687 348 1311867730.2224810123 0.0480026379 0.0438566453 0.0621726289 0.0041352845 0.1676530000 251721653 0 1784193024 -0.0094906650 -0.0118926074 -0.0328507163 349 1311867730.2575879097 0.0485635102 0.0438701321 0.0621726289 0.0041347214 0.1678440000 251723763 0 1783291904 -0.0084101949 -0.0093931882 -0.0328129120 350 1311867730.2914879322 0.0473812856 0.0438801639 0.0621726289 0.0041340004 0.1711240000 251725873 0 1780514816 -0.0095195454 -0.0107251834 -0.0318870246 351 1311867730.3230810165 0.0506767407 0.0438995274 0.0621726289 0.0041382565 0.1800000000 251727943 0 1777078272 -0.0078029167 -0.0113649033 -0.0346333385 352 1311867730.3554260731 0.0494471975 0.0439152878 0.0621726289 0.0041334371 0.1704310000 251730133 0 1775681536 -0.0082069961 -0.0107719302 -0.0332731344 353 1311867730.3982920647 0.0483790375 0.0439279330 0.0621726289 0.0041308832 0.1726700000 251732419 0 1777467392 -0.0085729500 -0.0079465006 -0.0326799825 354 1311867730.4225230217 0.0498137698 0.0439445597 0.0621726289 0.0041294442 0.1702310000 251734129 0 1779134464 -0.0071334867 -0.0080487039 -0.0330204442 355 1311867730.4600110054 0.0508590974 0.0439640372 0.0621726289 0.0041278340 0.1704080000 251736359 0 1780723712 -0.0078034755 -0.0107385814 -0.0345804617 356 1311867730.4948410988 0.0486707985 0.0439772585 0.0621726289 0.0041247732 0.1753170000 251738533 0 1782501376 -0.0091746682 -0.0102599123 -0.0329650044 357 1311867730.5300729275 0.0485720634 0.0439901291 0.0621726289 0.0041192393 0.1693490000 251740435 0 1783828480 -0.0083556175 -0.0102340607 -0.0318745226 358 1311867730.5597670078 0.0478578955 0.0440009329 0.0621726289 0.0041165888 0.1677650000 251742665 0 1785802752 -0.0078118015 -0.0086125648 -0.0304354113 359 1311867730.5940020084 0.0476952232 0.0440112234 0.0621726289 0.0041168727 0.1705440000 251744535 0 1784795136 -0.0084598865 -0.0088960286 -0.0309066512 360 1311867730.6230149269 0.0446929447 0.0440131171 0.0621726289 0.0041202889 0.1745210000 251746493 0 1783181312 -0.0087645324 -0.0068083424 -0.0271940902 361 1311867730.6614060402 0.0465896428 0.0440202543 0.0621726289 0.0041220717 0.1783600000 251748747 0 1778962432 -0.0074592587 -0.0095126797 -0.0286007226 362 1311867730.6922950745 0.0473043956 0.0440293265 0.0621726289 0.0041165802 0.1755370000 251750553 0 1776291840 -0.0061796652 -0.0081626270 -0.0289981775 363 1311867730.7275629044 0.0458727330 0.0440344047 0.0621726289 0.0041149106 0.1712730000 251752983 0 1777946624 -0.0076645222 -0.0088973930 -0.0288988762 364 1311867730.7572948933 0.0433499068 0.0440325242 0.0621726289 0.0041251961 0.1783770000 251755053 0 1779621888 -0.0084349234 -0.0068158647 -0.0268973261 365 1311867730.7932779789 0.0452544875 0.0440358721 0.0621726289 0.0041210088 0.1709460000 251757163 0 1781399552 -0.0072218096 -0.0063803256 -0.0291900858 366 1311867730.8240480423 0.0426083133 0.0440319716 0.0621726289 0.0041190414 0.1779310000 251759305 0 1782882304 -0.0074153971 -0.0078245178 -0.0251946226 367 1311867730.8591129780 0.0476068407 0.0440417124 0.0621726289 0.0041233956 0.1704890000 251761159 0 1784532992 -0.0052964669 -0.0068665827 -0.0312152114 368 1311867730.8922739029 0.0436347574 0.0440406066 0.0621726289 0.0041229247 0.1698490000 251763125 0 1783705600 -0.0062453635 -0.0052298633 -0.0267851762 369 1311867730.9270720482 0.0412106477 0.0440329373 0.0621726289 0.0041396121 0.1770970000 251765123 0 1779585024 -0.0064895824 -0.0035114579 -0.0240145326 370 1311867730.9611239433 0.0442099757 0.0440334158 0.0621726289 0.0041377213 0.1772110000 251767281 0 1777946624 -0.0053115832 -0.0037636175 -0.0277523287 371 1311867730.9928169250 0.0434835404 0.0440319337 0.0621726289 0.0041335953 0.2022550000 251769119 0 1779351552 -0.0037702564 -0.0019749098 -0.0257063489 372 1311867731.0221049786 0.0403818451 0.0440221216 0.0621726289 0.0041324296 0.1772420000 251771469 0 1781383168 -0.0044859517 -0.0021794313 -0.0221025180 373 1311867731.0609729290 0.0413668714 0.0440150030 0.0621726289 0.0041331166 0.1750170000 251773139 0 1782882304 -0.0038036918 -0.0035303067 -0.0231833439 374 1311867731.0900061131 0.0391928889 0.0440021096 0.0621726289 0.0041291597 0.1766380000 251775113 0 1784406016 -0.0044369176 -0.0032287333 -0.0211202074 375 1311867731.1276559830 0.0389496461 0.0439886364 0.0621726289 0.0041304714 0.1763840000 251777591 0 1783541760 -0.0059791012 -0.0055743866 -0.0221699812 376 1311867731.1551880836 0.0418400243 0.0439829220 0.0621726289 0.0041333015 0.1788780000 251779309 0 1781420032 -0.0027343659 -0.0023755264 -0.0238889847 377 1311867731.1935870647 0.0384634063 0.0439682813 0.0621726289 0.0041302500 0.1773640000 251781635 0 1776918528 -0.0048339893 -0.0041216556 -0.0207835175 378 1311867731.2235820293 0.0418640450 0.0439627146 0.0621726289 0.0041292607 0.1797070000 251783609 0 1774157824 -0.0003195014 -0.0044195149 -0.0209324043 379 1311867731.2602028847 0.0402991623 0.0439530482 0.0621726289 0.0041258325 0.1789860000 251785607 0 1775771648 -0.0009187851 -0.0047780266 -0.0198160410 380 1311867731.2900059223 0.0411433019 0.0439456541 0.0621726289 0.0041563424 0.1704160000 251787653 0 1777811456 -0.0010821698 -0.0046664164 -0.0237847306 381 1311867731.3230779171 0.0398604684 0.0439349319 0.0621726289 0.0041711165 0.1787420000 251789947 0 1779224576 0.0006894288 -0.0047704428 -0.0195856895 382 1311867731.3570859432 0.0411534272 0.0439276505 0.0621726289 0.0041678361 0.1771750000 251791641 0 1780723712 0.0022775782 -0.0033773610 -0.0212738756 383 1311867731.3915760517 0.0416190587 0.0439216228 0.0621726289 0.0041653402 0.1732710000 251793759 0 1782755328 0.0027162670 -0.0034442602 -0.0226250924 384 1311867731.4279849529 0.0372631140 0.0439042829 0.0621726289 0.0041733088 0.1725840000 251796125 0 1784553472 0.0003817766 -0.0042606890 -0.0196656920 385 1311867731.4602010250 0.0383763872 0.0438899248 0.0621726289 0.0041704935 0.1747310000 251798499 0 1783562240 0.0010925913 -0.0061116125 -0.0211573280 386 1311867731.4926180840 0.0334666111 0.0438629214 0.0621726289 0.0041795999 0.1763260000 251800465 0 1779085312 -0.0017775875 -0.0055464888 -0.0181984548 387 1311867731.5259540081 0.0372661017 0.0438458753 0.0621726289 0.0041797505 0.1792850000 251802359 0 1776930816 0.0013104924 -0.0045276149 -0.0221365672 388 1311867731.5589148998 0.0362484567 0.0438262943 0.0621726289 0.0041845249 0.1767160000 251804605 0 1778970624 0.0005269712 -0.0008594197 -0.0229691025 389 1311867731.5967359543 0.0380064398 0.0438113333 0.0621726289 0.0042216300 0.1759960000 251806947 0 1780387840 0.0018034209 -0.0037785424 -0.0235807672 390 1311867731.6247410774 0.0412169062 0.0438046809 0.0621726289 0.0042237445 0.1816750000 251808649 0 1781866496 0.0024453374 -0.0058093220 -0.0278982613 391 1311867731.6616659164 0.0373789035 0.0437882467 0.0621726289 0.0042445192 0.1797920000 251810807 0 1783898112 0.0011893595 -0.0044304533 -0.0244815983 392 1311867731.6925039291 0.0402912870 0.0437793259 0.0621726289 0.0042591331 0.1802690000 251812581 0 1785565184 0.0029641837 -0.0065862206 -0.0261018127 393 1311867731.7299311161 0.0387355573 0.0437664918 0.0621726289 0.0042581897 0.1790560000 251814627 0 1784561664 0.0039109434 -0.0054277247 -0.0236354098 394 1311867731.7615330219 0.0395343564 0.0437557504 0.0621726289 0.0042533573 0.1872710000 251816697 0 1783418880 0.0043355296 -0.0054045282 -0.0248688143 395 1311867731.7939310074 0.0437568910 0.0437557533 0.0621726289 0.0042674362 0.1781700000 251818751 0 1785085952 0.0062797545 -0.0074720629 -0.0291475281 396 1311867731.8252151012 0.0424666554 0.0437524980 0.0621726289 0.0042671576 0.1808380000 251820781 0 1783816192 0.0058175130 -0.0085533569 -0.0281781834 397 1311867731.8593230247 0.0394645371 0.0437416971 0.0621726289 0.0042973189 0.2039790000 251822883 0 1782636544 0.0065238709 -0.0047378326 -0.0257988572 398 1311867731.8910930157 0.0396285392 0.0437313625 0.0621726289 0.0043033710 0.1796360000 251824945 0 1784832000 0.0046508801 -0.0098162703 -0.0270040929 399 1311867731.9224479198 0.0360345766 0.0437120723 0.0621726289 0.0043113504 0.1792190000 251826943 0 1783685120 0.0042332313 -0.0071736937 -0.0241021141 400 1311867731.9598410130 0.0349173881 0.0436900856 0.0621726289 0.0043090951 0.1711450000 251829053 0 1779347456 0.0033929492 -0.0043192673 -0.0250954870 401 1311867731.9915709496 0.0401516408 0.0436812615 0.0621726289 0.0043204380 0.1801440000 251831299 0 1777438720 0.0066667683 -0.0067244424 -0.0296762958 402 1311867732.0239229202 0.0409111939 0.0436743708 0.0621726289 0.0043318924 0.1725320000 251833009 0 1779482624 0.0089700287 -0.0090987664 -0.0290865358 403 1311867732.0619950294 0.0352977999 0.0436535853 0.0621726289 0.0043450219 0.1815440000 251835575 0 1780768768 0.0064662360 -0.0093703996 -0.0248078480 404 1311867732.0918290615 0.0413012356 0.0436477626 0.0621726289 0.0043523985 0.1807390000 251837309 0 1782517760 0.0106544495 -0.0094600124 -0.0305062160 405 1311867732.1221950054 0.0329430066 0.0436213312 0.0621726289 0.0043941248 0.1795460000 251839515 0 1784025088 0.0062038125 -0.0041795098 -0.0246668905 406 1311867732.1605980396 0.0349359661 0.0435999386 0.0621726289 0.0043960739 0.1787660000 251841385 0 1783410688 0.0060870163 -0.0086071379 -0.0279405136 407 1311867732.1931400299 0.0368513465 0.0435833573 0.0621726289 0.0044080337 0.1834100000 251843199 0 1778851840 0.0088176038 -0.0078627449 -0.0298204515 408 1311867732.2232089043 0.0375568941 0.0435685866 0.0621726289 0.0044373975 0.1818830000 251845261 0 1777455104 0.0084954388 -0.0091810245 -0.0307324175 409 1311867732.2590498924 0.0381710753 0.0435553897 0.0621726289 0.0045057627 0.1791570000 251847307 0 1778847744 0.0080969213 -0.0073384345 -0.0341579691 410 1311867732.2903969288 0.0428887904 0.0435537639 0.0621726289 0.0045739354 0.1712130000 251849433 0 1780879360 0.0114779538 -0.0078454306 -0.0372930840 411 1311867732.3218240738 0.0403089747 0.0435458690 0.0621726289 0.0045709894 0.1831100000 251851303 0 1781993472 0.0107007455 -0.0107051441 -0.0350102298 412 1311867732.3607840538 0.0420353152 0.0435422026 0.0621726289 0.0045668910 0.1789030000 251853229 0 1784041472 0.0121944528 -0.0103753954 -0.0375029854 413 1311867732.3899528980 0.0424402989 0.0435395346 0.0621726289 0.0045647766 0.1792500000 251855475 0 1785421824 0.0121965148 -0.0101181436 -0.0390254930 414 1311867732.4218940735 0.0405398384 0.0435322889 0.0621726289 0.0045732854 0.1814170000 251857505 0 1784942592 0.0121183796 -0.0111064119 -0.0377527624 415 1311867732.4593050480 0.0419886634 0.0435285693 0.0621726289 0.0045768626 0.1831420000 251859431 0 1783672832 0.0129229138 -0.0104889935 -0.0398301929 416 1311867732.4918489456 0.0427289046 0.0435266471 0.0621726289 0.0045748517 0.1779420000 251861845 0 1785720832 0.0128924269 -0.0088787954 -0.0420406573 417 1311867732.5229809284 0.0411523841 0.0435209534 0.0621726289 0.0045712052 0.1822680000 251863603 0 1784561664 0.0141856689 -0.0115912296 -0.0397097990 418 1311867732.5698928833 0.0419082530 0.0435170953 0.0621726289 0.0045667030 0.1837430000 251865881 0 1783668736 0.0131593812 -0.0094898362 -0.0425150134 419 1311867732.5926280022 0.0441501625 0.0435186062 0.0621726289 0.0045631949 0.1852620000 251867591 0 1785065472 0.0146552259 -0.0092058219 -0.0445419438 420 1311867732.6242370605 0.0407050774 0.0435119073 0.0621726289 0.0045596584 0.1800850000 251869581 0 1784205312 0.0133038042 -0.0089578964 -0.0416583382 421 1311867732.6630299091 0.0410126746 0.0435059709 0.0621726289 0.0045666703 0.1818020000 251871675 0 1779470336 0.0163358077 -0.0105793756 -0.0402221605 422 1311867732.6922440529 0.0425832160 0.0435037842 0.0621726289 0.0045650019 0.1828380000 251873897 0 1777967104 0.0176828597 -0.0088086016 -0.0415318757 423 1311867732.7260940075 0.0404184200 0.0434964902 0.0621726289 0.0045669725 0.2025300000 251875655 0 1779990528 0.0108232256 -0.0081282724 -0.0436640680 424 1311867732.7601239681 0.0349965692 0.0434764433 0.0621726289 0.0045755081 0.2202500000 252325329 0 1781260288 0.0096544381 -0.0079895835 -0.0385012217 425 1311867732.7919039726 0.0378289372 0.0434631550 0.0621726289 0.0045742750 0.4180140000 252283639 0 1783017472 0.0121640228 -0.0081718871 -0.0406879745 426 1311867732.8280360699 0.0387785025 0.0434521582 0.0621726289 0.0045690966 0.3727210000 252281921 0 1784668160 0.0122280642 -0.0074563138 -0.0421916358 427 1311867732.8589270115 0.0361142382 0.0434349733 0.0621726289 0.0045685584 0.3665180000 253091730 0 1783963648 0.0107630119 -0.0077392654 -0.0400737524 428 1311867732.8912909031 0.0407786407 0.0434287670 0.0621726289 0.0045751914 0.2706930000 254718716 0 1784238080 0.0140253128 -0.0094233491 -0.0433386303 429 1311867732.9262781143 0.0354385152 0.0434101417 0.0621726289 0.0045997324 0.2621330000 254711734 0 1781346304 0.0098288544 -0.0050283694 -0.0398257487 430 1311867732.9602870941 0.0348914973 0.0433903309 0.0621726289 0.0046066043 0.3673270000 253889530 0 1780043776 0.0117401434 -0.0084998999 -0.0375502333 431 1311867732.9987640381 0.0328803845 0.0433659458 0.0621726289 0.0046062221 0.1849980000 252294859 0 1780166656 0.0098618688 -0.0073389290 -0.0361647345 432 1311867733.0276939869 0.0333560035 0.0433427747 0.0621726289 0.0046017202 0.1917180000 252296761 0 1781923840 0.0099446923 -0.0050838739 -0.0365875475 433 1311867733.0607628822 0.0320480391 0.0433166898 0.0621726289 0.0046157506 0.1930210000 252299031 0 1783566336 0.0108124521 -0.0086844936 -0.0342491642 434 1311867733.0977020264 0.0313796550 0.0432891851 0.0621726289 0.0046134376 0.1938270000 252300589 0 1785597952 0.0100582335 -0.0080176219 -0.0339289494 435 1311867733.1263020039 0.0370580517 0.0432748607 0.0621726289 0.0046164047 0.1902560000 252302795 0 1784086528 0.0125416750 -0.0072656022 -0.0391067192 436 1311867733.1625030041 0.0344315469 0.0432545779 0.0621726289 0.0046177599 0.1819610000 252304841 0 1779892224 0.0120293144 -0.0104507469 -0.0360712893 437 1311867733.1926651001 0.0363388509 0.0432387524 0.0621726289 0.0046143815 0.1925700000 252307071 0 1779519488 0.0140378922 -0.0100718895 -0.0371895283 438 1311867733.2259631157 0.0337102860 0.0432169979 0.0621726289 0.0046341068 0.1884990000 252308965 0 1780789248 0.0118217673 -0.0055831010 -0.0361590125 439 1311867733.2618060112 0.0340126269 0.0431960312 0.0621726289 0.0046353968 0.1943620000 252311075 0 1782566912 0.0116245188 -0.0069861850 -0.0364646092 440 1311867733.2919199467 0.0286337268 0.0431629351 0.0621726289 0.0046445250 0.1894690000 252313161 0 1784217600 0.0083745401 -0.0039310940 -0.0321631171 441 1311867733.3300418854 0.0320167243 0.0431376602 0.0621726289 0.0046670284 0.1847430000 252315119 0 1785978880 0.0114985192 -0.0062990687 -0.0341504700 442 1311867733.3602790833 0.0332042798 0.0431151865 0.0621726289 0.0046678230 0.1892790000 252317261 0 1785233408 0.0120329577 -0.0090796333 -0.0351910442 443 1311867733.3923840523 0.0308169946 0.0430874254 0.0621726289 0.0046746406 0.2235890000 252319163 0 1784360960 0.0089368373 -0.0077105057 -0.0346009918 444 1311867733.4289550781 0.0298208650 0.0430575457 0.0621726289 0.0046744035 0.1901920000 252321185 0 1783455744 0.0113628097 -0.0052178353 -0.0330052935 445 1311867733.4588150978 0.0296217557 0.0430273529 0.0621726289 0.0046701040 0.1887790000 252323343 0 1785106432 0.0111412723 -0.0069988249 -0.0328802168 446 1311867733.4956119061 0.0279865526 0.0429936292 0.0621726289 0.0046706009 0.1892440000 252325205 0 1784381440 0.0094241360 -0.0061035636 -0.0321143530 447 1311867733.5290400982 0.0303892884 0.0429654316 0.0621726289 0.0046792089 0.1930930000 252327043 0 1783836672 0.0114848930 -0.0071215173 -0.0334905162 448 1311867733.5630290508 0.0260372963 0.0429276455 0.0621726289 0.0046927416 0.1983940000 252329177 0 1785487360 0.0080826124 -0.0037981637 -0.0305321142 449 1311867733.5922229290 0.0244842470 0.0428865689 0.0621726289 0.0046889993 0.2026590000 252331159 0 1784635392 0.0095456094 -0.0063333311 -0.0283801816 450 1311867733.6283020973 0.0292827059 0.0428563381 0.0621726289 0.0047037886 0.1924380000 252333101 0 1783873536 0.0107900146 -0.0084036784 -0.0328506194 451 1311867733.6601879597 0.0281039253 0.0428236277 0.0621726289 0.0047055973 0.1897280000 252335203 0 1785466880 0.0110948365 -0.0049072537 -0.0316923335 452 1311867733.6917510033 0.0253424402 0.0427849525 0.0621726289 0.0047007382 0.2013070000 252337137 0 1784254464 0.0109708887 -0.0066299834 -0.0286321454 453 1311867733.7288239002 0.0282883514 0.0427529511 0.0621726289 0.0047023338 0.1888520000 252339031 0 1783709696 0.0125831347 -0.0091432352 -0.0310242772 454 1311867733.7597820759 0.0235282797 0.0427106061 0.0621726289 0.0047074319 0.1884740000 252340981 0 1785487360 0.0111966468 -0.0066502155 -0.0267847329 455 1311867733.7924160957 0.0238438584 0.0426691407 0.0621726289 0.0047268316 0.1855360000 252342971 0 1784635392 0.0103558917 -0.0066564665 -0.0268801972 456 1311867733.8282589912 0.0199367553 0.0426192890 0.0621726289 0.0047298173 0.1905060000 252345169 0 1783873536 0.0099777197 -0.0080792066 -0.0237565767 457 1311867733.8608579636 0.0188474208 0.0425672717 0.0621726289 0.0047316709 0.1915010000 252346855 0 1785487360 0.0109534413 -0.0055453987 -0.0224906243 458 1311867733.8918149471 0.0188004132 0.0425153790 0.0621726289 0.0047274401 0.1906260000 252348957 0 1784717312 0.0132901222 -0.0064175562 -0.0217011012 459 1311867733.9289460182 0.0184456091 0.0424629394 0.0621726289 0.0047225629 0.1877170000 252350955 0 1783828480 0.0127959158 -0.0077125737 -0.0221287049 460 1311867733.9595899582 0.0155660231 0.0424044679 0.0621726289 0.0047417275 0.1926510000 252353081 0 1785606144 0.0107685756 -0.0066909865 -0.0201337561 461 1311867733.9941790104 0.0159563422 0.0423470967 0.0621726289 0.0047545372 0.1981520000 252355723 0 1784627200 0.0122490637 -0.0068118810 -0.0205365811 462 1311867734.0275731087 0.0160741452 0.0422902288 0.0621726289 0.0047537448 0.1915600000 252357385 0 1783865344 0.0121849738 -0.0078184577 -0.0206842050 463 1311867734.0599920750 0.0146713564 0.0422305768 0.0621726289 0.0047500609 0.1954110000 252359319 0 1785479168 0.0126602743 -0.0084074102 -0.0193456560 464 1311867734.0956780910 0.0165212546 0.0421751688 0.0621726289 0.0047451894 0.1928550000 252361165 0 1784717312 0.0137222223 -0.0078869937 -0.0212427322 465 1311867734.1274170876 0.0145915998 0.0421158493 0.0621726289 0.0047409788 0.1898530000 252363715 0 1783828480 0.0141430702 -0.0110257035 -0.0193544980 466 1311867734.1618878841 0.0135464082 0.0420545415 0.0621726289 0.0047459403 0.1916390000 252365577 0 1785589760 0.0133393658 -0.0090430118 -0.0192319844 467 1311867734.1942350864 0.0143261403 0.0419951659 0.0621726289 0.0047417410 0.2143200000 252367431 0 1784717312 0.0143785169 -0.0090764593 -0.0200846195 468 1311867734.2291829586 0.0145497713 0.0419365219 0.0621726289 0.0047440304 0.1932560000 252369373 0 1783828480 0.0153930224 -0.0097660990 -0.0202653110 469 1311867734.2607750893 0.0117009422 0.0418720537 0.0621726289 0.0047428364 0.1926650000 252371419 0 1783357440 0.0126781529 -0.0102119055 -0.0183837581 470 1311867734.2941219807 0.0134972008 0.0418116817 0.0621726289 0.0047382290 0.1965850000 252373337 0 1782194176 0.0139219631 -0.0096343495 -0.0196671560 471 1311867734.3263280392 0.0133364629 0.0417512247 0.0621726289 0.0047373147 0.1914780000 252375295 0 1783955456 0.0154193807 -0.0108508682 -0.0190054365 472 1311867734.3610401154 0.0118374927 0.0416878482 0.0621726289 0.0047411951 0.1921650000 252377485 0 1785622528 0.0140159391 -0.0104768276 -0.0181186628 473 1311867734.3941841125 0.0131599568 0.0416275355 0.0621726289 0.0047430095 0.1920700000 252379603 0 1784954880 0.0156541970 -0.0081994878 -0.0185148381 474 1311867734.4276480675 0.0113154566 0.0415635860 0.0621726289 0.0047381753 0.1982210000 252381505 0 1783873536 0.0141654955 -0.0104588745 -0.0174004268 475 1311867734.4586091042 0.0109968390 0.0414992349 0.0621726289 0.0047347573 0.2011610000 252383703 0 1785741312 0.0139878811 -0.0116500035 -0.0169105977 476 1311867734.4938759804 0.0107713249 0.0414346805 0.0621726289 0.0047325602 0.1979710000 252385805 0 1784582144 0.0140635250 -0.0092316587 -0.0163031388 477 1311867734.5300569534 0.0112351477 0.0413713691 0.0621726289 0.0047287870 0.1954560000 252387707 0 1783439360 0.0144205159 -0.0089822421 -0.0164705887 478 1311867734.5595300198 0.0091392267 0.0413039379 0.0621726289 0.0047354828 0.1972330000 252389705 0 1785237504 0.0141623383 -0.0110202255 -0.0148090329 479 1311867734.5953910351 0.0110919653 0.0412408648 0.0621726289 0.0047317872 0.1985810000 252391655 0 1784352768 0.0134467706 -0.0119770002 -0.0166419037 480 1311867734.6285231113 0.0099888993 0.0411757566 0.0621726289 0.0047277041 0.1956950000 252393805 0 1783222272 0.0149342967 -0.0110782469 -0.0153090470 481 1311867734.6593229771 0.0095675178 0.0411100430 0.0621726289 0.0047235231 0.1962150000 252395731 0 1784836096 0.0136679299 -0.0112566985 -0.0152527895 482 1311867734.6947479248 0.0089399479 0.0410433001 0.0621726289 0.0047190591 0.1963790000 252397689 0 1783582720 0.0123671545 -0.0113177933 -0.0146316523 483 1311867734.7310240269 0.0094026783 0.0409777915 0.0621726289 0.0047198590 0.1959810000 252399799 0 1782968320 0.0144923953 -0.0110742934 -0.0149476686 484 1311867734.7607629299 0.0106849363 0.0409152030 0.0621726289 0.0047190510 0.1942200000 252401669 0 1784582144 0.0166775025 -0.0132050514 -0.0158731323 485 1311867734.7976419926 0.0103907231 0.0408522659 0.0621726289 0.0047164244 0.1919570000 252403987 0 1786097664 0.0156396646 -0.0125469398 -0.0157905016 486 1311867734.8298120499 0.0111602144 0.0407911712 0.0621726289 0.0047132284 0.2015460000 252405785 0 1784999936 0.0152127836 -0.0134839378 -0.0164200030 487 1311867734.8645250797 0.0092053823 0.0407263133 0.0621726289 0.0047104347 0.1939780000 252408047 0 1782956032 0.0161558650 -0.0113189677 -0.0139911100 488 1311867734.8943901062 0.0094528841 0.0406622284 0.0621726289 0.0047075536 0.1976190000 252409989 0 1781927936 0.0164451823 -0.0114851873 -0.0142338183 489 1311867734.9263660908 0.0088349264 0.0405971419 0.0621726289 0.0047031726 0.1926380000 252411923 0 1783455744 0.0164733510 -0.0131313615 -0.0137918126 490 1311867734.9631719589 0.0079392586 0.0405304931 0.0621726289 0.0047005706 0.1939690000 252413929 0 1785081856 0.0164334197 -0.0130511150 -0.0134279393 491 1311867734.9948470592 0.0084755085 0.0404652080 0.0621726289 0.0047017260 0.2170100000 252415791 0 1783951360 0.0145698031 -0.0137414988 -0.0141364299 492 1311867735.0292239189 0.0082413293 0.0403997123 0.0621726289 0.0047028766 0.1910150000 252417933 0 1783058432 0.0169611722 -0.0140997330 -0.0138035482 493 1311867735.0596508980 0.0090773562 0.0403361781 0.0621726289 0.0046990788 0.1950790000 252419659 0 1784328192 0.0177525077 -0.0122912722 -0.0142925279 494 1311867735.0952830315 0.0085587129 0.0402718513 0.0621726289 0.0046982610 0.1924000000 252421937 0 1785970688 0.0179597083 -0.0150363445 -0.0136855282 495 1311867735.1313030720 0.0079438509 0.0402065422 0.0621726289 0.0046972013 0.2013620000 252424111 0 1784602624 0.0158296488 -0.0151933320 -0.0135245807 496 1311867735.1603751183 0.0084123639 0.0401424410 0.0621726289 0.0046926368 0.1953890000 252425829 0 1786249216 0.0159583464 -0.0142867416 -0.0141344722 497 1311867735.1994349957 0.0079213986 0.0400776100 0.0621726289 0.0046916497 0.1975870000 252427611 0 1784582144 0.0163124837 -0.0162301250 -0.0132904844 498 1311867735.2263538837 0.0081642596 0.0400135269 0.0621726289 0.0046893750 0.1889120000 252429849 0 1786232832 0.0168242157 -0.0161108263 -0.0131483227 499 1311867735.2655019760 0.0077559110 0.0399488824 0.0621726289 0.0046862123 0.1968190000 252431767 0 1784582144 0.0155181503 -0.0142376702 -0.0126703670 500 1311867735.2961549759 0.0079783900 0.0398849414 0.0621726289 0.0046880681 0.1981120000 252434101 0 1786634240 0.0169372484 -0.0174284410 -0.0120302383 501 1311867735.3321089745 0.0079698786 0.0398212387 0.0621726289 0.0046853137 0.2384340000 252903443 0 1784344576 0.0171558335 -0.0144562256 -0.0120766470 502 1311867735.3666970730 0.0073431819 0.0397565414 0.0621726289 0.0046907428 0.4407890000 252862045 0 1786675200 0.0185636748 -0.0155731533 -0.0110425223 503 1311867735.3943350315 0.0072690723 0.0396919540 0.0621726289 0.0047006634 0.4046420000 252859263 0 1783255040 0.0192261264 -0.0152876619 -0.0111393947 504 1311867735.4322299957 0.0067935372 0.0396266793 0.0621726289 0.0047045395 0.3884430000 253699168 0 1785335808 0.0180731323 -0.0144779421 -0.0110745858 505 1311867735.4628560543 0.0057798242 0.0395596559 0.0621726289 0.0047161322 0.2949700000 255500694 0 1783635968 0.0163889043 -0.0156758260 -0.0100194402 506 1311867735.4973869324 0.0054465597 0.0394922387 0.0621726289 0.0047220972 0.2728040000 255450176 0 1782292480 0.0163559858 -0.0154691581 -0.0092718825 507 1311867735.5293200016 0.0058990940 0.0394259800 0.0621726289 0.0047182118 0.4142570000 254629372 0 1774235648 0.0162201449 -0.0151878363 -0.0094574271 508 1311867735.5632629395 0.0052965176 0.0393587960 0.0621726289 0.0047148566 0.2260240000 252872053 0 1774780416 0.0181363095 -0.0154575584 -0.0086599579 509 1311867735.5976569653 0.0054377192 0.0392921534 0.0621726289 0.0047111859 0.2319660000 252873803 0 1775857664 0.0159263127 -0.0169189870 -0.0084093297 510 1311867735.6363260746 0.0048301136 0.0392245808 0.0621726289 0.0047116275 0.1984340000 252876025 0 1777934336 0.0191122387 -0.0165393408 -0.0082359137 511 1311867735.6626520157 0.0043059546 0.0391562469 0.0621726289 0.0047081188 0.2020520000 252877799 0 1779585024 0.0192296728 -0.0177764669 -0.0072808582 512 1311867735.6952130795 0.0052620322 0.0390900473 0.0621726289 0.0047037551 0.1980470000 252879749 0 1781600256 0.0178716481 -0.0195839480 -0.0079733059 513 1311867735.7291250229 0.0041544838 0.0390219467 0.0621726289 0.0047062760 0.1989750000 252922859 0 1782996992 0.0181518160 -0.0178240258 -0.0084265796 514 1311867735.7631659508 0.0038996253 0.0389536154 0.0621726289 0.0047067848 0.2009400000 253009113 0 1784627200 0.0171164498 -0.0164211113 -0.0089250207 515 1311867735.7963778973 0.0052476167 0.0388881668 0.0621726289 0.0047045940 0.2016120000 253011095 0 1783754752 0.0155755896 -0.0184696205 -0.0087325443 516 1311867735.8277759552 0.0031480878 0.0388189031 0.0621726289 0.0047085474 0.2008980000 253013109 0 1783484416 0.0171954054 -0.0153363924 -0.0084517300 517 1311867735.8638889790 0.0032585375 0.0387501210 0.0621726289 0.0047071860 0.1968020000 253014603 0 1784864768 0.0185625032 -0.0156936496 -0.0085667307 518 1311867735.8951849937 0.0031949424 0.0386814816 0.0621726289 0.0047032451 0.1961890000 253016857 0 1784791040 0.0187645555 -0.0160714593 -0.0078211380 519 1311867735.9322230816 0.0026879951 0.0386121300 0.0621726289 0.0047018476 0.2030590000 253018831 0 1784119296 0.0179637112 -0.0147082973 -0.0072235493 520 1311867735.9623689651 0.0031252601 0.0385438860 0.0621726289 0.0047020240 0.1977830000 253020989 0 1785769984 0.0184114501 -0.0148819378 -0.0072330059 521 1311867735.9945859909 0.0028668246 0.0384754080 0.0621726289 0.0047008935 0.1987210000 253022819 0 1782992896 0.0180003252 -0.0149331437 -0.0065640896 522 1311867736.0290079117 0.0042336276 0.0384098107 0.0621726289 0.0047022146 0.2006210000 253024881 0 1782505472 0.0175910424 -0.0167415906 -0.0066335802 523 1311867736.0642199516 0.0033785987 0.0383428294 0.0621726289 0.0046978654 0.1970530000 253027183 0 1784246272 0.0174483601 -0.0161102973 -0.0059299106 524 1311867736.0946779251 0.0010070866 0.0382715780 0.0621726289 0.0046999562 0.1946160000 253029037 0 1783885824 0.0170854963 -0.0143438596 -0.0033567979 525 1311867736.1299190521 0.0014204286 0.0382013854 0.0621726289 0.0047119833 0.1930730000 253031227 0 1783214080 0.0186131783 -0.0151603399 -0.0035941587 526 1311867736.1631360054 0.0011519655 0.0381309492 0.0621726289 0.0047097730 0.1935060000 253033145 0 1784791040 0.0173638128 -0.0150826974 -0.0037037099 527 1311867736.1942429543 0.0025838504 0.0380634974 0.0621726289 0.0047111364 0.2448010000 253456235 0 1784246272 0.0157176647 -0.0157978162 -0.0042557511 528 1311867736.2298679352 0.0020833313 0.0379953531 0.0621726289 0.0047128433 0.4654430000 253458757 0 1783128064 0.0151499799 -0.0152826477 -0.0038527744 529 1311867736.2633900642 0.0021717106 0.0379276336 0.0621726289 0.0047191501 0.4364140000 253460447 0 1784930304 0.0163940769 -0.0162565410 -0.0041375151 530 1311867736.2995250225 0.0035327305 0.0378627375 0.0621726289 0.0047180637 0.4076670000 254807932 0 1783394304 0.0179324299 -0.0178305972 -0.0033513294 531 1311867736.3304500580 0.0024931864 0.0377961282 0.0621726289 0.0047203280 0.3134560000 255768230 0 1784901632 0.0145655274 -0.0164244715 -0.0039800564 532 1311867736.3637149334 0.0027880976 0.0377303237 0.0621726289 0.0047167298 0.2299880000 256196180 0 1783431168 0.0172455683 -0.0169203877 -0.0021471709 533 1311867736.3943159580 0.0030202204 0.0376652015 0.0621726289 0.0047124426 0.4224640000 255335612 0 1778745344 0.0160438977 -0.0174802747 -0.0021808343 534 1311867736.4313519001 0.0020535765 0.0375985131 0.0621726289 0.0047237473 0.2200040000 253449141 0 1778790400 0.0162488241 -0.0166582651 -0.0031900443 535 1311867736.4625089169 0.0025386147 0.0375329806 0.0621726289 0.0047221137 0.1952260000 253450859 0 1780568064 0.0159828141 -0.0171218179 -0.0029213964 536 1311867736.4987530708 0.0041100979 0.0374706244 0.0621726289 0.0047207987 0.1985010000 253452929 0 1782181888 0.0167580321 -0.0192829315 -0.0031132703 537 1311867736.5321619511 0.0022106804 0.0374049635 0.0621726289 0.0047317181 0.1985880000 253454903 0 1783959552 0.0154347233 -0.0173052307 -0.0036857796 538 1311867736.5634689331 0.0034594806 0.0373418678 0.0621726289 0.0047280576 0.1916900000 253456957 0 1785610240 0.0139457220 -0.0169353262 -0.0024479085 539 1311867736.5958600044 0.0046613109 0.0372812359 0.0621726289 0.0047297851 0.1975220000 253458971 0 1784721408 0.0149710141 -0.0193298310 -0.0020553484 540 1311867736.6320459843 0.0038747208 0.0372193720 0.0621726289 0.0047381940 0.2000560000 253460969 0 1784090624 0.0157143064 -0.0188514683 -0.0026128921 541 1311867736.6635379791 0.0036761360 0.0371573697 0.0621726289 0.0047454739 0.1951050000 253463087 0 1785847808 0.0151556581 -0.0186111387 -0.0022170688 542 1311867736.6945500374 0.0050548008 0.0370981399 0.0621726289 0.0047601251 0.2042880000 253465053 0 1784487936 0.0144392466 -0.0218324475 -0.0039830408 543 1311867736.7332150936 0.0045676222 0.0370382310 0.0621726289 0.0047624924 0.1945140000 253467043 0 1784086528 0.0133848535 -0.0204559360 -0.0032923340 544 1311867736.7636179924 0.0044372985 0.0369783028 0.0621726289 0.0047629897 0.1942740000 253468865 0 1783095296 0.0124507146 -0.0196420439 -0.0069616963 545 1311867736.7952749729 0.0044010547 0.0369185281 0.0621726289 0.0047759644 0.1965220000 253471039 0 1784848384 0.0144205336 -0.0221997220 -0.0070576388 546 1311867736.8325269222 0.0039250986 0.0368581005 0.0621726289 0.0047877528 0.1931820000 253472909 0 1784000512 0.0128018055 -0.0190494396 -0.0064515937 547 1311867736.8640279770 0.0042856988 0.0367985532 0.0621726289 0.0047858897 0.1872100000 253474971 0 1782091776 0.0131117050 -0.0187114459 -0.0091813914 548 1311867736.8945000172 0.0017064022 0.0367345164 0.0621726289 0.0047826571 0.1900740000 253477241 0 1781424128 0.0156636946 -0.0190792400 -0.0066060368 549 1311867736.9362800121 0.0039553102 0.0366748093 0.0621726289 0.0047843918 0.1822520000 253479071 0 1783050240 0.0140289953 -0.0200688690 -0.0068175346 550 1311867736.9632000923 0.0059912791 0.0366190211 0.0621726289 0.0047902230 0.1854000000 253481221 0 1784885248 0.0115955370 -0.0164186060 -0.0073307836 551 1311867736.9954400063 0.0045986744 0.0365609079 0.0621726289 0.0047892526 0.2539830000 253924447 0 1784107008 0.0141372057 -0.0190559179 -0.0042443597 552 1311867737.0307478905 0.0071148206 0.0365075636 0.0621726289 0.0047854145 0.4369100000 253927225 0 1782816768 0.0121278241 -0.0216827579 -0.0044889073 553 1311867737.0629029274 0.0059036654 0.0364522220 0.0621726289 0.0047819791 0.4092880000 253926067 0 1784557568 0.0122938277 -0.0195062235 -0.0054384023 554 1311867737.0977239609 0.0071526128 0.0363993346 0.0621726289 0.0047785389 0.4071250000 255304668 0 1784381440 0.0115988804 -0.0208136272 -0.0049309423 555 1311867737.1300530434 0.0070620398 0.0363464746 0.0621726289 0.0047755287 0.3340090000 256334354 0 1784565760 0.0120094856 -0.0200461559 -0.0037897725 556 1311867737.1655049324 0.0055224253 0.0362910357 0.0621726289 0.0047713420 0.2084840000 256581400 0 1786204160 0.0133646075 -0.0195245948 -0.0046375962 557 1311867737.1952710152 0.0065451316 0.0362376319 0.0621726289 0.0047683828 0.3948460000 255720840 0 1779912704 0.0138593270 -0.0193490237 -0.0026949677 558 1311867737.2333149910 0.0068392521 0.0361849466 0.0621726289 0.0047644056 0.2202770000 253940545 0 1780158464 0.0135541065 -0.0193674024 -0.0029128012 559 1311867737.2693018913 0.0057926588 0.0361305776 0.0621726289 0.0047661077 0.1983850000 253942479 0 1781968896 0.0142844375 -0.0187395979 -0.0038806710 560 1311867737.2957379818 0.0070250831 0.0360786035 0.0621726289 0.0047631208 0.2014980000 253944229 0 1783619584 0.0129055679 -0.0187644027 -0.0040341858 561 1311867737.3316531181 0.0074996348 0.0360276606 0.0621726289 0.0047591019 0.1932620000 253946563 0 1785270272 0.0126651246 -0.0196002480 -0.0039999122 562 1311867737.3659460545 0.0074179806 0.0359767537 0.0621726289 0.0047567423 0.1946880000 253948473 0 1784729600 0.0127734831 -0.0184619855 -0.0033174045 563 1311867737.3967239857 0.0074175075 0.0359260268 0.0621726289 0.0047556619 0.1994100000 253950599 0 1783861248 0.0131083140 -0.0196753219 -0.0031357757 564 1311867737.4355359077 0.0084509449 0.0358773121 0.0621726289 0.0047522032 0.1934570000 253952493 0 1785659392 0.0123274373 -0.0200349092 -0.0023690765 565 1311867737.4691100121 0.0086063556 0.0358290449 0.0621726289 0.0047496588 0.1928780000 253954659 0 1784987648 0.0132437721 -0.0200795326 -0.0007232925 566 1311867737.4959459305 0.0085884174 0.0357809166 0.0621726289 0.0047458579 0.1925390000 253956553 0 1786273792 0.0129306335 -0.0201413091 -0.0007061263 567 1311867737.5353999138 0.0104823057 0.0357362982 0.0621726289 0.0047444688 0.1937790000 253958343 0 1785131008 0.0113560297 -0.0207769144 0.0001340237 568 1311867737.5654399395 0.0100035127 0.0356909940 0.0621726289 0.0047420906 0.1846100000 253960469 0 1783857152 0.0134898573 -0.0193047281 0.0017415213 569 1311867737.5958089828 0.0103925429 0.0356465328 0.0621726289 0.0047386145 0.1903790000 253962723 0 1782480896 0.0143597824 -0.0199663285 0.0028521740 570 1311867737.6330978870 0.0098360945 0.0356012513 0.0621726289 0.0047355286 0.2295280000 253964489 0 1784496128 0.0142331757 -0.0203917436 0.0019190756 571 1311867737.6624519825 0.0124855768 0.0355607685 0.0621726289 0.0047326996 0.1849650000 253966647 0 1785868288 0.0137123959 -0.0200819280 0.0050902031 572 1311867737.7032339573 0.0128592784 0.0355210806 0.0621726289 0.0047296441 0.1898930000 253968725 0 1785024512 0.0140943611 -0.0203254931 0.0058988659 573 1311867737.7314720154 0.0124623962 0.0354808386 0.0621726289 0.0047268884 0.1955600000 253970827 0 1783631872 0.0135118011 -0.0212783422 0.0049019298 574 1311867737.7658560276 0.0117863892 0.0354395590 0.0621726289 0.0047235007 0.1874320000 253972585 0 1781989376 0.0154673746 -0.0199488904 0.0050363755 575 1311867737.8011269569 0.0111483410 0.0353973134 0.0621726289 0.0047204391 0.2239490000 254413043 0 1783607296 0.0160009135 -0.0204530843 0.0053579742 576 1311867737.8323190212 0.0110072540 0.0353549696 0.0621726289 0.0047169795 0.4173970000 254411173 0 1785622528 0.0172068588 -0.0210010931 0.0059703710 577 1311867737.8633110523 0.0121305911 0.0353147194 0.0621726289 0.0047214112 0.3964450000 254417335 0 1784430592 0.0175386723 -0.0205570646 0.0073819063 578 1311867737.9004418850 0.0115109812 0.0352735364 0.0621726289 0.0047179808 0.3893150000 255579668 0 1784799232 0.0174000803 -0.0213656723 0.0067299339 579 1311867737.9305500984 0.0134413335 0.0352358297 0.0621726289 0.0047168023 0.3126140000 257242158 0 1784037376 0.0164522380 -0.0227649286 0.0092199314 580 1311867737.9630560875 0.0138731301 0.0351989974 0.0621726289 0.0047153306 0.2298980000 257117916 0 1785815040 0.0140771717 -0.0242244694 0.0068107815 581 1311867737.9996941090 0.0139188459 0.0351623707 0.0621726289 0.0047123952 0.3960080000 256258196 0 1781313536 0.0151290046 -0.0222488698 0.0086291973 582 1311867738.0315399170 0.0149308462 0.0351276086 0.0621726289 0.0047140093 0.1923750000 254405289 0 1781227520 0.0159353651 -0.0217807572 0.0111757359 583 1311867738.0629770756 0.0144527191 0.0350921457 0.0621726289 0.0047106643 0.1970720000 254407295 0 1783025664 0.0140523314 -0.0217225067 0.0086004827 584 1311867738.0998299122 0.0132746464 0.0350547869 0.0621726289 0.0047092288 0.1938890000 254409197 0 1784766464 0.0166784208 -0.0226241276 0.0098977648 585 1311867738.1308510303 0.0166148581 0.0350232657 0.0621726289 0.0047059840 0.1958340000 254410971 0 1784295424 0.0162601620 -0.0231788419 0.0141014224 586 1311867738.1635079384 0.0171523932 0.0349927693 0.0621726289 0.0047032991 0.1945150000 254413225 0 1783738368 0.0159205757 -0.0246414412 0.0143480422 587 1311867738.1992070675 0.0159144346 0.0349602679 0.0621726289 0.0046997514 0.1931370000 254415055 0 1785163776 0.0185747575 -0.0239271652 0.0149082383 588 1311867738.2306089401 0.0162777994 0.0349284950 0.0621726289 0.0047018263 0.2062240000 254417341 0 1785020416 0.0172446519 -0.0256898440 0.0138265723 589 1311867738.2632689476 0.0162360594 0.0348967591 0.0621726289 0.0047016941 0.2264630000 254419323 0 1784549376 0.0180468876 -0.0256947875 0.0140183968 590 1311867738.3008689880 0.0170168318 0.0348664542 0.0621726289 0.0046985373 0.1934020000 254421217 0 1785909248 0.0196668878 -0.0244968086 0.0156247485 591 1311867738.3339769840 0.0183403902 0.0348384913 0.0621726289 0.0046964505 0.2006750000 254423239 0 1782865920 0.0200445354 -0.0247329976 0.0166999437 592 1311867738.3651630878 0.0197607465 0.0348130221 0.0621726289 0.0046952995 0.1952200000 254425365 0 1782353920 0.0194577724 -0.0248941444 0.0175027624 593 1311867738.3995900154 0.0179384612 0.0347845659 0.0621726289 0.0046922404 0.1950390000 254427259 0 1784532992 0.0202843584 -0.0263395011 0.0150623452 594 1311867738.4334011078 0.0180003550 0.0347563096 0.0621726289 0.0046904461 0.1901470000 254429185 0 1783902208 0.0204594526 -0.0250924882 0.0150788929 595 1311867738.4643430710 0.0177886132 0.0347277925 0.0621726289 0.0046889980 0.1875640000 254431199 0 1781219328 0.0205275249 -0.0268354714 0.0140127931 596 1311867738.5000250340 0.0181599632 0.0346999941 0.0621726289 0.0046870411 0.1862690000 254433317 0 1780477952 0.0209435243 -0.0257648081 0.0143881571 597 1311867738.5332009792 0.0181759857 0.0346723157 0.0621726289 0.0046844999 0.1920320000 254435243 0 1782091776 0.0219705869 -0.0253130198 0.0147080477 598 1311867738.5634350777 0.0185067505 0.0346452830 0.0621726289 0.0046822239 0.1908120000 254437425 0 1784242176 0.0229630247 -0.0246934704 0.0152672539 599 1311867738.6022439003 0.0224315673 0.0346248928 0.0621726289 0.0046794981 0.1893130000 254439375 0 1785528320 0.0218164325 -0.0262674093 0.0184066053 600 1311867738.6328980923 0.0196731333 0.0345999732 0.0621726289 0.0046773215 0.1919370000 254441629 0 1784758272 0.0229449347 -0.0258213412 0.0149803329 601 1311867738.6628730297 0.0168921389 0.0345705092 0.0621726289 0.0046786884 0.1916380000 254443163 0 1784016896 0.0246290006 -0.0250027739 0.0119952653 602 1311867738.6996099949 0.0197325759 0.0345458615 0.0621726289 0.0046785365 0.1916690000 254445345 0 1785536512 0.0259534605 -0.0261621736 0.0154926730 603 1311867738.7314729691 0.0187603049 0.0345196831 0.0621726289 0.0046803259 0.1911840000 254447191 0 1784287232 0.0272559300 -0.0256419834 0.0143290972 604 1311867738.7626600266 0.0208847728 0.0344971088 0.0621726289 0.0046793960 0.2172860000 254850549 0 1783128064 0.0258347075 -0.0263755638 0.0150029901 605 1311867738.8032259941 0.0228826385 0.0344779113 0.0621726289 0.0046790186 0.4048140000 254848667 0 1784807424 0.0269149616 -0.0257438794 0.0173328146 606 1311867738.8306779861 0.0233427621 0.0344595365 0.0621726289 0.0046784574 0.3663750000 254850337 0 1784102912 0.0260422118 -0.0271502472 0.0166193862 607 1311867738.8639259338 0.0231610145 0.0344409228 0.0621726289 0.0046752053 0.3519590000 256085030 0 1785774080 0.0260407366 -0.0266475808 0.0155613972 608 1311867738.9000120163 0.0216554739 0.0344198941 0.0621726289 0.0046750135 0.3057160000 257487632 0 1783848960 0.0290039349 -0.0259840563 0.0149013996 609 1311867738.9307610989 0.0234230310 0.0344018368 0.0621726289 0.0046792995 0.2235810000 257521810 0 1785569280 0.0282855462 -0.0272123516 0.0162133593 610 1311867738.9664750099 0.0253919587 0.0343870665 0.0621726289 0.0046862398 0.3664860000 256688144 0 1783275520 0.0282015074 -0.0245432407 0.0181325488 611 1311867738.9989941120 0.0231708940 0.0343687095 0.0621726289 0.0046847037 0.1815180000 254836439 0 1783513088 0.0308452230 -0.0240427405 0.0164685920 612 1311867739.0329539776 0.0258467197 0.0343547846 0.0621726289 0.0046811330 0.1825040000 254838261 0 1785417728 0.0296056252 -0.0256320648 0.0185598321 613 1311867739.0664470196 0.0243778825 0.0343385091 0.0621726289 0.0046819527 0.1919170000 254840251 0 1784295424 0.0288965479 -0.0265865363 0.0157747325 614 1311867739.0997900963 0.0216158498 0.0343177882 0.0621726289 0.0046786148 0.1910040000 254842313 0 1783115776 0.0318116285 -0.0228361152 0.0136893243 615 1311867739.1321549416 0.0262420345 0.0343046569 0.0621726289 0.0046767679 0.1837080000 254844399 0 1784913920 0.0322490707 -0.0231052674 0.0192218460 616 1311867739.1687150002 0.0223919749 0.0342853181 0.0621726289 0.0046775909 0.2221960000 255234269 0 1783914496 0.0327965096 -0.0237870179 0.0149832778 617 1311867739.1999289989 0.0237942599 0.0342683148 0.0621726289 0.0046799499 0.3896350000 255235871 0 1784045568 0.0319606662 -0.0223382507 0.0158509053 618 1311867739.2313010693 0.0238434784 0.0342514461 0.0621726289 0.0046769963 0.3599310000 255376633 0 1785716736 0.0328023471 -0.0230145045 0.0164227039 619 1311867739.2672259808 0.0252130590 0.0342368445 0.0621726289 0.0046740865 0.3615530000 257839378 0 1784311808 0.0318218358 -0.0238641705 0.0175420176 620 1311867739.2996931076 0.0261017177 0.0342237233 0.0621726289 0.0046777679 0.3214190000 257736172 0 1783619584 0.0309624393 -0.0243743956 0.0180880465 621 1311867739.3319859505 0.0262159295 0.0342108283 0.0621726289 0.0046761906 0.4002210000 256927396 0 1778614272 0.0311112646 -0.0223254338 0.0179613233 622 1311867739.3670029640 0.0281863566 0.0342011427 0.0621726289 0.0046833547 0.1823000000 255243777 0 1779335168 0.0309054367 -0.0219425745 0.0205328893 623 1311867739.3990058899 0.0285619013 0.0341920909 0.0621726289 0.0046803640 0.1923370000 255245871 0 1780994048 0.0292423740 -0.0221439004 0.0206257403 624 1311867739.4311320782 0.0254300050 0.0341780491 0.0621726289 0.0046821010 0.1943150000 255247869 0 1782226944 0.0313835070 -0.0204322804 0.0179408696 625 1311867739.4668490887 0.0237258300 0.0341613256 0.0621726289 0.0046813813 0.1925920000 255249963 0 1784123392 0.0315086767 -0.0229159594 0.0170316044 626 1311867739.4988598824 0.0251819827 0.0341469816 0.0621726289 0.0046846423 0.1851170000 255251865 0 1785901056 0.0308045074 -0.0247738939 0.0193633437 627 1311867739.5316400528 0.0241568480 0.0341310483 0.0621726289 0.0046811574 0.1840760000 255253551 0 1784266752 0.0332289189 -0.0225417223 0.0192173887 628 1311867739.5670249462 0.0236963239 0.0341144325 0.0621726289 0.0046799808 0.1784530000 255255645 0 1781862400 0.0334614851 -0.0225862991 0.0189503711 629 1311867739.5990490913 0.0253608450 0.0341005159 0.0621726289 0.0046765369 0.2103390000 255257747 0 1780211712 0.0324204788 -0.0235713106 0.0209509172 630 1311867739.6325490475 0.0261458308 0.0340878894 0.0621726289 0.0046737201 0.1830150000 255259569 0 1781739520 0.0318956189 -0.0219920520 0.0216756444 631 1311867739.6706740856 0.0260954909 0.0340752231 0.0621726289 0.0046711469 0.1871820000 255261887 0 1783488512 0.0323664770 -0.0229384024 0.0227109343 632 1311867739.7001221180 0.0255239513 0.0340616927 0.0621726289 0.0046683995 0.1823610000 255263829 0 1785266176 0.0336050838 -0.0223852415 0.0229362957 633 1311867739.7323939800 0.0236076936 0.0340451776 0.0621726289 0.0046654258 0.1829940000 255265563 0 1784156160 0.0328890756 -0.0222234689 0.0208574161 634 1311867739.7662999630 0.0224791039 0.0340269346 0.0621726289 0.0046656624 0.1853690000 255267713 0 1781501952 0.0322096571 -0.0238758307 0.0200906992 635 1311867739.8016180992 0.0257172659 0.0340138485 0.0621726289 0.0046630114 0.2249160000 255657483 0 1780211712 0.0314592384 -0.0248113703 0.0239150450 636 1311867739.8325679302 0.0231755003 0.0339968071 0.0621726289 0.0046604326 0.3790080000 255656653 0 1782034432 0.0315545946 -0.0232029241 0.0207251217 637 1311867739.8701560497 0.0232694577 0.0339799667 0.0621726289 0.0046579738 0.3562240000 255658291 0 1783947264 0.0297870487 -0.0230817683 0.0200833380 638 1311867739.9036860466 0.0250841379 0.0339660234 0.0621726289 0.0046545743 0.3531860000 257051256 0 1785090048 0.0293190312 -0.0261164531 0.0230834410 639 1311867739.9317240715 0.0247092377 0.0339515370 0.0621726289 0.0046532747 0.3000770000 257689726 0 1783926784 0.0307489522 -0.0226910133 0.0224540513 640 1311867739.9668979645 0.0233373661 0.0339349524 0.0621726289 0.0046517339 0.4292570000 257410728 0 1781923840 0.0302303098 -0.0229095109 0.0209227763 641 1311867739.9987080097 0.0256272834 0.0339219919 0.0621726289 0.0046487902 0.1803010000 255665447 0 1782566912 0.0298698805 -0.0234003700 0.0239623338 642 1311867740.0328791142 0.0295389872 0.0339151648 0.0621726289 0.0046532717 0.1902040000 255667125 0 1784344576 0.0276394263 -0.0235200003 0.0277368408 643 1311867740.0671849251 0.0254045334 0.0339019290 0.0621726289 0.0046508672 0.1882540000 255669099 0 1785966592 0.0283279754 -0.0225626472 0.0230589025 644 1311867740.0992529392 0.0261527393 0.0338898961 0.0621726289 0.0046501738 0.1889350000 255671193 0 1784451072 0.0281741135 -0.0227848440 0.0235399418 645 1311867740.1347720623 0.0271599218 0.0338794620 0.0621726289 0.0046481523 0.1870350000 255673423 0 1786499072 0.0273458585 -0.0258688238 0.0253223106 646 1311867740.1666491032 0.0274283718 0.0338694758 0.0621726289 0.0046503492 0.1895300000 255675109 0 1784832000 0.0268830433 -0.0236514825 0.0248329695 647 1311867740.1993310452 0.0241239220 0.0338544131 0.0621726289 0.0046503955 0.1857970000 255677131 0 1786249216 0.0264030211 -0.0230244584 0.0203673933 648 1311867740.2383539677 0.0249730255 0.0338407073 0.0621726289 0.0046489159 0.1845680000 255679449 0 1784700928 0.0246746093 -0.0256483685 0.0215150863 649 1311867740.2664349079 0.0269508660 0.0338300912 0.0621726289 0.0046583263 0.2052820000 255681263 0 1783697408 0.0255583711 -0.0232923105 0.0232808255 650 1311867740.2981588840 0.0233114716 0.0338139087 0.0621726289 0.0046612474 0.1829250000 255683389 0 1782046720 0.0211505610 -0.0232230630 0.0164197162 651 1311867740.3347120285 0.0257595442 0.0338015364 0.0621726289 0.0046597758 0.1826980000 255685067 0 1781194752 0.0227456130 -0.0236824434 0.0208944585 652 1311867740.3665161133 0.0296259057 0.0337951320 0.0621726289 0.0046733782 0.1840780000 255687185 0 1783062528 0.0243454985 -0.0210070107 0.0248767044 653 1311867740.3993780613 0.0266398638 0.0337841745 0.0621726289 0.0046794846 0.1826640000 255689159 0 1785094144 0.0235774219 -0.0224595908 0.0213773660 654 1311867740.4346680641 0.0215056799 0.0337654001 0.0621726289 0.0046995513 0.1774920000 255691189 0 1784332288 0.0226854812 -0.0246753767 0.0150482524 655 1311867740.4664289951 0.0234600008 0.0337496666 0.0621726289 0.0047016783 0.1823030000 255693307 0 1780920320 0.0216477737 -0.0236899927 0.0160020869 656 1311867740.4993040562 0.0239362698 0.0337347072 0.0621726289 0.0047003707 0.1857710000 255695033 0 1779650560 0.0225145221 -0.0237774886 0.0163142979 657 1311867740.5354259014 0.0236628149 0.0337193770 0.0621726289 0.0046991794 0.1831430000 255697351 0 1778872320 0.0247762352 -0.0238582492 0.0166771114 658 1311867740.5666589737 0.0233243313 0.0337035791 0.0621726289 0.0046963395 0.1827150000 255699525 0 1780305920 0.0232299902 -0.0240728240 0.0151349073 659 1311867740.6008880138 0.0237276591 0.0336884411 0.0621726289 0.0046929149 0.1801820000 255701491 0 1782046720 0.0249992535 -0.0228600707 0.0156001523 660 1311867740.6346809864 0.0259351563 0.0336766937 0.0621726289 0.0046981846 0.1790640000 255703553 0 1783971840 0.0247920528 -0.0219228026 0.0171599537 661 1311867740.6665890217 0.0247219559 0.0336631465 0.0621726289 0.0046961001 0.1786190000 255705263 0 1785712640 0.0230939053 -0.0220851470 0.0144650824 662 1311867740.6994900703 0.0247963648 0.0336497525 0.0621726289 0.0046950722 0.1812970000 255707117 0 1784840192 0.0214402694 -0.0247275159 0.0138157690 663 1311867740.7368240356 0.0220020525 0.0336321844 0.0621726289 0.0047008678 0.2189070000 256084239 0 1784078336 0.0208949186 -0.0258532353 0.0097225681 664 1311867740.7668819427 0.0201802906 0.0336119255 0.0621726289 0.0046983183 0.3734910000 256076989 0 1785790464 0.0213823002 -0.0255413894 0.0071473136 665 1311867740.7996399403 0.0223379377 0.0335949721 0.0621726289 0.0046957191 0.3401530000 256235363 0 1785016320 0.0199823305 -0.0252817255 0.0083935456 666 1311867740.8349099159 0.0198950078 0.0335744016 0.0621726289 0.0046959859 0.3470150000 257844904 0 1785765888 0.0205173641 -0.0265667792 0.0057860184 667 1311867740.8668210506 0.0198212061 0.0335537821 0.0621726289 0.0046932854 0.2999980000 258657334 0 1784254464 0.0196004529 -0.0258949827 0.0045016226 668 1311867740.8993830681 0.0282550342 0.0335458499 0.0621726289 0.0047262392 0.3819460000 257837186 0 1783103488 0.0210657716 -0.0243079010 0.0153033286 669 1311867740.9399120808 0.0264748130 0.0335352803 0.0621726289 0.0047250044 0.1894770000 256091179 0 1783230464 0.0211574528 -0.0222404599 0.0123358723 670 1311867740.9665501118 0.0251929071 0.0335228290 0.0621726289 0.0047224463 0.2118800000 256093001 0 1784479744 0.0201457106 -0.0211646426 0.0094982507 671 1311867741.0021579266 0.0263503343 0.0335121397 0.0621726289 0.0047195284 0.1843760000 256095295 0 1784373248 0.0203234460 -0.0233448409 0.0113842003 672 1311867741.0367169380 0.0257815514 0.0335006359 0.0621726289 0.0047163751 0.1807420000 256097349 0 1781104640 0.0194131434 -0.0233720616 0.0100802854 673 1311867741.0666699409 0.0262212697 0.0334898196 0.0621726289 0.0047175547 0.1856680000 256098907 0 1778413568 0.0193989463 -0.0206871722 0.0091130752 674 1311867741.1009640694 0.0275240950 0.0334809684 0.0621726289 0.0047174386 0.1853620000 256100849 0 1778053120 0.0199950226 -0.0216002278 0.0110957939 675 1311867741.1357901096 0.0271934848 0.0334716536 0.0621726289 0.0047140285 0.1825380000 256102919 0 1779331072 0.0179174058 -0.0226770081 0.0098944530 676 1311867741.1675300598 0.0264295358 0.0334612363 0.0621726289 0.0047116590 0.1825620000 256105053 0 1781092352 0.0165048745 -0.0232257843 0.0078571159 677 1311867741.2014830112 0.0270057507 0.0334517008 0.0621726289 0.0047110307 0.1816390000 256107091 0 1783103488 0.0174629074 -0.0232399981 0.0079342537 678 1311867741.2411060333 0.0281547736 0.0334438882 0.0621726289 0.0047101236 0.2129990000 256506097 0 1784770560 0.0177343935 -0.0243835449 0.0093363216 679 1311867741.2668209076 0.0274917744 0.0334351222 0.0621726289 0.0047089872 0.3741150000 256470199 0 1783914496 0.0176689923 -0.0233928822 0.0073866863 680 1311867741.2997009754 0.0266847797 0.0334251953 0.0621726289 0.0047061846 0.3297040000 256467477 0 1783386112 0.0173820890 -0.0237646867 0.0054819761 681 1311867741.3348419666 0.0268114675 0.0334154835 0.0621726289 0.0047033216 0.3499750000 257813566 0 1785221120 0.0183502659 -0.0231986772 0.0053454000 682 1311867741.3701419830 0.0255228914 0.0334039108 0.0621726289 0.0047001348 0.2923200000 259259316 0 1783975936 0.0174956061 -0.0213049427 0.0021591820 683 1311867741.4066278934 0.0273496360 0.0333950465 0.0621726289 0.0046979358 0.2155990000 259193110 0 1785315328 0.0186301973 -0.0199763551 0.0040919115 684 1311867741.4393060207 0.0277444143 0.0333867854 0.0621726289 0.0046962129 0.3513490000 258335190 0 1783853056 0.0203786660 -0.0201187674 0.0054506706 685 1311867741.4667329788 0.0255392194 0.0333753291 0.0621726289 0.0046942698 0.2283610000 256458643 0 1783869440 0.0212361813 -0.0219786875 0.0036788909 686 1311867741.5025069714 0.0262896214 0.0333650001 0.0621726289 0.0046947036 0.1829520000 256460937 0 1785884672 0.0201853514 -0.0204903968 0.0030534416 687 1311867741.5368049145 0.0297769923 0.0333597773 0.0621726289 0.0046929147 0.1818740000 256462727 0 1784836096 0.0216918066 -0.0195006542 0.0069682817 688 1311867741.5688209534 0.0279832706 0.0333519626 0.0621726289 0.0046903868 0.1822540000 256464781 0 1780776960 0.0210342146 -0.0202353746 0.0046403068 689 1311867741.6046030521 0.0289772041 0.0333456132 0.0621726289 0.0046991511 0.1750480000 256466795 0 1777098752 0.0220398940 -0.0188996512 0.0046721902 690 1311867741.6355440617 0.0292906333 0.0333397364 0.0621726289 0.0046962274 0.1763420000 256469009 0 1778876416 0.0231393967 -0.0195575226 0.0054264357 691 1311867741.6679561138 0.0288798995 0.0333332823 0.0621726289 0.0046941419 0.1797800000 256470743 0 1780424704 0.0243674424 -0.0193386208 0.0048557790 692 1311867741.7048020363 0.0304289367 0.0333290852 0.0621726289 0.0046932771 0.1802710000 256472829 0 1782202368 0.0243145656 -0.0195414126 0.0063854037 693 1311867741.7345991135 0.0300594810 0.0333243672 0.0621726289 0.0046911568 0.1773230000 256474923 0 1783685120 0.0261739902 -0.0181514900 0.0055284891 694 1311867741.7702169418 0.0305207111 0.0333203273 0.0621726289 0.0046880743 0.1738070000 256477081 0 1785335808 0.0257598460 -0.0200350862 0.0061399955 695 1311867741.8058650494 0.0334937833 0.0333205769 0.0621726289 0.0046903423 0.1760430000 256479127 0 1784582144 0.0249841213 -0.0186035726 0.0079613551 696 1311867741.8388509750 0.0297115259 0.0333153915 0.0621726289 0.0046904330 0.1775260000 256480965 0 1782059008 0.0273991898 -0.0186028183 0.0037222551 697 1311867741.8683021069 0.0291803703 0.0333094589 0.0621726289 0.0046897560 0.1786150000 256482771 0 1777721344 0.0278980695 -0.0200334508 0.0034438996 698 1311867741.9065721035 0.0318377502 0.0333073504 0.0621726289 0.0046892457 0.1801390000 256484849 0 1777352704 0.0279756561 -0.0195792224 0.0056957770 699 1311867741.9387769699 0.0319764055 0.0333054464 0.0621726289 0.0046864563 0.1787180000 256486935 0 1779015680 0.0293919314 -0.0180430487 0.0050241323 700 1311867741.9665379524 0.0321469605 0.0333037914 0.0621726289 0.0046835665 0.1774610000 256489109 0 1780645888 0.0290244222 -0.0183472745 0.0045967838 701 1311867742.0029959679 0.0322194956 0.0333022446 0.0621726289 0.0046809409 0.2137390000 256892827 0 1781907456 0.0291078631 -0.0203468669 0.0046947133 702 1311867742.0344839096 0.0308306012 0.0332987237 0.0621726289 0.0046785785 0.3656780000 256850765 0 1783693312 0.0307097211 -0.0201592222 0.0028603124 703 1311867742.0674400330 0.0337775797 0.0332994049 0.0621726289 0.0046785173 0.3382510000 256847523 0 1785597952 0.0327768177 -0.0200440977 0.0062225992 704 1311867742.1030650139 0.0329063945 0.0332988466 0.0621726289 0.0046763179 0.3312180000 258202624 0 1782091776 0.0316971876 -0.0192968827 0.0039666463 705 1311867742.1348879337 0.0343578905 0.0333003488 0.0621726289 0.0046732788 0.2845740000 258992998 0 1780834304 0.0323566794 -0.0193997435 0.0050727716 706 1311867742.1672229767 0.0345253460 0.0333020839 0.0621726289 0.0046714258 0.4003050000 258480894 0 1779933184 0.0369188190 -0.0187151432 0.0060915761 707 1311867742.2028279305 0.0367580615 0.0333069722 0.0621726289 0.0046693975 0.2279120000 256860147 0 1780371456 0.0372523032 -0.0176234096 0.0076487809 708 1311867742.2362670898 0.0344918147 0.0333086457 0.0621726289 0.0046717705 0.2212470000 257208485 0 1782104064 0.0384320989 -0.0190736670 0.0053974139 709 1311867742.2674059868 0.0381779186 0.0333155135 0.0621726289 0.0046710600 0.3655840000 257216835 0 1783889920 0.0401518196 -0.0182588827 0.0088253776 710 1311867742.3028159142 0.0374586843 0.0333213489 0.0621726289 0.0046685553 0.3355150000 257214913 0 1785159680 0.0408823490 -0.0189838260 0.0073332237 711 1311867742.3350739479 0.0393206030 0.0333297867 0.0621726289 0.0046697280 0.3399520000 258521894 0 1783971840 0.0401496664 -0.0176399779 0.0083267614 712 1311867742.3694241047 0.0373062454 0.0333353716 0.0621726289 0.0046693047 0.2833220000 260066400 0 1783431168 0.0405929200 -0.0195897669 0.0064293658 713 1311867742.4062991142 0.0423249006 0.0333479797 0.0621726289 0.0046786736 0.2295330000 259964914 0 1782415360 0.0409292690 -0.0168178231 0.0108102905 714 1311867742.4346439838 0.0418084674 0.0333598291 0.0621726289 0.0046756949 0.3494650000 259107654 0 1778683904 0.0425792895 -0.0159120653 0.0098856473 715 1311867742.4666969776 0.0383380018 0.0333667916 0.0621726289 0.0046800448 0.1819060000 257227735 0 1779019776 0.0421066433 -0.0183120929 0.0065210406 716 1311867742.5047059059 0.0398416631 0.0333758347 0.0621726289 0.0046780439 0.1828540000 257230045 0 1780064256 0.0433978811 -0.0180717222 0.0077526048 717 1311867742.5359389782 0.0412371866 0.0333867989 0.0621726289 0.0046795967 0.1860490000 257231883 0 1782079488 0.0424330905 -0.0172267668 0.0087396409 718 1311867742.5678529739 0.0396657623 0.0333955440 0.0621726289 0.0046787383 0.1803930000 257233745 0 1784082432 0.0443909280 -0.0156428479 0.0069779456 719 1311867742.6054639816 0.0414935164 0.0334068068 0.0621726289 0.0046756798 0.1808600000 257235895 0 1785749504 0.0445089824 -0.0172448829 0.0088085532 720 1311867742.6347279549 0.0408640020 0.0334171640 0.0621726289 0.0046725824 0.1805840000 257237821 0 1784492032 0.0445987843 -0.0169555657 0.0078171398 721 1311867742.6724960804 0.0417857468 0.0334287709 0.0621726289 0.0046706380 0.1892590000 257240011 0 1782820864 0.0454136692 -0.0164967738 0.0088551156 722 1311867742.7046229839 0.0411225259 0.0334394271 0.0621726289 0.0046679938 0.1820480000 257242033 0 1784999936 0.0448907390 -0.0177665632 0.0080620162 723 1311867742.7356119156 0.0398538075 0.0334482990 0.0621726289 0.0046651725 0.1842500000 257244063 0 1783836672 0.0460931137 -0.0173344184 0.0063537899 724 1311867742.7726070881 0.0454313010 0.0334648501 0.0621726289 0.0046669591 0.1820770000 257246085 0 1778765824 0.0451136827 -0.0181327295 0.0117192911 725 1311867742.8034689426 0.0436065532 0.0334788387 0.0621726289 0.0046654998 0.1839840000 257248147 0 1777115136 0.0463998988 -0.0175517499 0.0093360823 726 1311867742.8352251053 0.0424513891 0.0334911975 0.0621726289 0.0046643807 0.1732400000 257250081 0 1778921472 0.0464884900 -0.0181912072 0.0077167805 727 1311867742.8705639839 0.0436630808 0.0335051891 0.0621726289 0.0046626500 0.1785060000 257252031 0 1780572160 0.0463767089 -0.0182104055 0.0086502619 728 1311867742.9046700001 0.0465296656 0.0335230799 0.0621726289 0.0046619022 0.1777620000 257253917 0 1782067200 0.0467088073 -0.0177243743 0.0110066887 729 1311867742.9382069111 0.0445849113 0.0335382539 0.0621726289 0.0046840231 0.1779730000 257256227 0 1783828480 0.0477512963 -0.0170837548 0.0095343702 730 1311867742.9707310200 0.0446823724 0.0335535198 0.0621726289 0.0046886823 0.1792910000 257258073 0 1785479168 0.0475449935 -0.0166290645 0.0089242104 731 1311867743.0024189949 0.0434978232 0.0335671235 0.0621726289 0.0046925128 0.1783110000 257260079 0 1784365056 0.0476937965 -0.0169222262 0.0079448074 732 1311867743.0345149040 0.0439824238 0.0335813520 0.0621726289 0.0046929843 0.1825790000 257261917 0 1781583872 0.0474487767 -0.0173877310 0.0080948304 733 1311867743.0722420216 0.0453401320 0.0335973940 0.0621726289 0.0046911044 0.1819930000 257263947 0 1780424704 0.0486926064 -0.0160858501 0.0087291263 734 1311867743.1045989990 0.0449254289 0.0336128273 0.0621726289 0.0046894043 0.2137850000 257266009 0 1782079488 0.0499605313 -0.0176493358 0.0086431932 735 1311867743.1350400448 0.0471651629 0.0336312659 0.0621726289 0.0046918083 0.1801400000 257268039 0 1783447552 0.0506429076 -0.0153812636 0.0099411067 736 1311867743.1704380512 0.0490516834 0.0336522175 0.0621726289 0.0047002339 0.1787910000 257269837 0 1785225216 0.0496754572 -0.0173809920 0.0120171085 737 1311867743.2037980556 0.0488761738 0.0336728742 0.0621726289 0.0046993801 0.1785180000 257271971 0 1783980032 0.0523688421 -0.0160423405 0.0113798380 738 1311867743.2358140945 0.0491321310 0.0336938217 0.0621726289 0.0046991044 0.1847570000 257274049 0 1781186560 0.0507202595 -0.0176646691 0.0117392000 739 1311867743.2708129883 0.0493743792 0.0337150403 0.0621726289 0.0046986300 0.1777270000 257275959 0 1778532352 0.0517818779 -0.0167065747 0.0123878866 740 1311867743.3032529354 0.0484553911 0.0337349597 0.0621726289 0.0047035434 0.1803400000 257277765 0 1775484928 0.0521899909 -0.0149691887 0.0106548816 741 1311867743.3363931179 0.0499812663 0.0337568845 0.0621726289 0.0047022145 0.1815890000 257279923 0 1774178304 0.0520296916 -0.0168975871 0.0131469909 742 1311867743.3707330227 0.0458632894 0.0337732005 0.0621726289 0.0047040826 0.1766440000 257281753 0 1774321664 0.0540380478 -0.0152843306 0.0087084342 743 1311867743.4043838978 0.0487731658 0.0337933888 0.0621726289 0.0047026731 0.2170190000 257616655 0 1776111616 0.0525082275 -0.0163954105 0.0117712319 744 1311867743.4352641106 0.0489364937 0.0338137425 0.0621726289 0.0047056678 0.3491200000 257616705 0 1777790976 0.0543632731 -0.0173776299 0.0121932700 745 1311867743.4768960476 0.0530498289 0.0338395627 0.0621726289 0.0047155203 0.3336240000 257778423 0 1779785728 0.0550782606 -0.0153326569 0.0154267866 746 1311867743.5035250187 0.0519999452 0.0338639064 0.0621726289 0.0047132062 0.3249690000 259138272 0 1784139776 0.0540946834 -0.0140975546 0.0138440952 747 1311867743.5389750004 0.0535760149 0.0338902948 0.0621726289 0.0047107244 0.2676990000 259498132 0 1785421824 0.0538612679 -0.0157408137 0.0158170350 748 1311867743.5749680996 0.0498623885 0.0339116478 0.0621726289 0.0047198093 0.1915290000 260236216 0 1783754752 0.0554132760 -0.0157957226 0.0118604656 749 1311867743.6036109924 0.0523604453 0.0339362791 0.0621726289 0.0047334354 0.3298570000 259379260 0 1779507200 0.0542523563 -0.0151715204 0.0141347796 750 1311867743.6354589462 0.0543502234 0.0339634977 0.0621726289 0.0047317549 0.1924150000 257627397 0 1780023296 0.0533464849 -0.0159649607 0.0161397085 751 1311867743.6759150028 0.0534563027 0.0339894535 0.0621726289 0.0047288807 0.1828470000 257629555 0 1781710848 0.0539355464 -0.0157945529 0.0147841442 752 1311867743.7034959793 0.0543423370 0.0340165185 0.0621726289 0.0047260890 0.1790160000 257631601 0 1783304192 0.0540118068 -0.0166368540 0.0157092195 753 1311867743.7388861179 0.0563004687 0.0340461120 0.0621726289 0.0047246506 0.1784300000 257633503 0 1785081856 0.0534227863 -0.0143386293 0.0166061930 754 1311867743.7733619213 0.0584957525 0.0340785386 0.0621726289 0.0047228525 0.1775180000 257635589 0 1783971840 0.0533280931 -0.0150473015 0.0186513513 755 1311867743.8064749241 0.0547752194 0.0341059514 0.0621726289 0.0047217362 0.1803340000 257637459 0 1780027392 0.0537337810 -0.0159626342 0.0145586040 756 1311867743.8391659260 0.0606454350 0.0341410566 0.0621726289 0.0047354324 0.2184970000 257639305 0 1779380224 0.0524813831 -0.0137818055 0.0195723977 757 1311867743.8726658821 0.0537427105 0.0341669504 0.0621726289 0.0047498480 0.1939030000 257641407 0 1780924416 0.0530165061 -0.0166791603 0.0127347708 758 1311867743.9031310081 0.0549323894 0.0341943455 0.0621726289 0.0047474540 0.1790570000 257643733 0 1782685696 0.0521485880 -0.0169163495 0.0135419033 759 1311867743.9453630447 0.0537910275 0.0342201645 0.0621726289 0.0047465577 0.1731260000 257645731 0 1784336384 0.0524712801 -0.0166899990 0.0118915234 760 1311867743.9741249084 0.0535676070 0.0342456217 0.0621726289 0.0047452526 0.1790220000 257647497 0 1783595008 0.0532852374 -0.0158057325 0.0113012195 761 1311867744.0042529106 0.0539755486 0.0342715480 0.0621726289 0.0047493558 0.1791030000 257649399 0 1781813248 0.0517860577 -0.0160509795 0.0115783401 762 1311867744.0407259464 0.0558741055 0.0342998978 0.0621726289 0.0047469776 0.1758180000 257651405 0 1778614272 0.0515568294 -0.0150122978 0.0131754819 763 1311867744.0716118813 0.0532748811 0.0343247667 0.0621726289 0.0047447974 0.1753030000 257653587 0 1775964160 0.0517261848 -0.0167528316 0.0109034386 764 1311867744.1111290455 0.0539704561 0.0343504810 0.0621726289 0.0047418148 0.1722650000 257655561 0 1776472064 0.0523051172 -0.0158729125 0.0114209838 765 1311867744.1412119865 0.0530357882 0.0343749062 0.0621726289 0.0047387735 0.1793870000 257657519 0 1775202304 0.0519249216 -0.0161825903 0.0105148386 766 1311867744.1734991074 0.0529267266 0.0343991253 0.0621726289 0.0047366880 0.1758300000 257659317 0 1776992256 0.0525302663 -0.0150084412 0.0100923516 767 1311867744.2046771049 0.0529000834 0.0344232465 0.0621726289 0.0047374047 0.1820910000 257661339 0 1778659328 0.0522889271 -0.0139311124 0.0098047219 768 1311867744.2400228977 0.0525699966 0.0344468751 0.0621726289 0.0047353982 0.1765790000 257663601 0 1780310016 0.0519202799 -0.0170680135 0.0103205405 769 1311867744.2773048878 0.0526316650 0.0344705224 0.0621726289 0.0047345771 0.1715290000 257665375 0 1782071296 0.0534248650 -0.0134656103 0.0096688066 770 1311867744.3032519817 0.0527252145 0.0344942298 0.0621726289 0.0047325250 0.1747540000 257667437 0 1783701504 0.0525198095 -0.0138815539 0.0099530146 771 1311867744.3391230106 0.0527294651 0.0345178812 0.0621726289 0.0047366069 0.1737440000 257669339 0 1785479168 0.0528773628 -0.0160429552 0.0106393211 772 1311867744.3707659245 0.0518191233 0.0345402922 0.0621726289 0.0047335425 0.1769340000 257671521 0 1784590336 0.0544783100 -0.0139101893 0.0090105664 773 1311867744.4027431011 0.0528085418 0.0345639251 0.0621726289 0.0047315181 0.1784710000 257673391 0 1783222272 0.0525393188 -0.0156163601 0.0103577003 774 1311867744.4383800030 0.0527043268 0.0345873623 0.0621726289 0.0047302134 0.1776400000 257675445 0 1779658752 0.0522773862 -0.0171275344 0.0103733875 775 1311867744.4717690945 0.0570747182 0.0346163782 0.0621726289 0.0047356999 0.1795520000 257677499 0 1777119232 0.0527197644 -0.0157208256 0.0144863166 776 1311867744.5026860237 0.0542718843 0.0346417075 0.0621726289 0.0047335459 0.1784190000 257679329 0 1777741824 0.0522820279 -0.0143365990 0.0110648312 777 1311867744.5383169651 0.0539808348 0.0346665970 0.0621726289 0.0047344219 0.1800090000 257681423 0 1779384320 0.0538571477 -0.0154602900 0.0109084789 778 1311867744.5726189613 0.0558044612 0.0346937665 0.0621726289 0.0047330531 0.1748710000 257683349 0 1781198848 0.0529074483 -0.0144811878 0.0123551097 779 1311867744.6028740406 0.0551249869 0.0347199940 0.0621726289 0.0047308842 0.1762940000 257685363 0 1782849536 0.0538313910 -0.0130171850 0.0111206844 780 1311867744.6386809349 0.0557811968 0.0347469955 0.0621726289 0.0047300724 0.1777500000 257687393 0 1784479744 0.0529960133 -0.0140798157 0.0120701026 781 1311867744.6707758904 0.0543356724 0.0347720770 0.0621726289 0.0047273386 0.1769890000 257689431 0 1783726080 0.0531401299 -0.0137332901 0.0104876496 782 1311867744.7029349804 0.0546542145 0.0347975018 0.0621726289 0.0047277135 0.2055400000 257691141 0 1782312960 0.0533509031 -0.0131255798 0.0104758404 783 1311867744.7396171093 0.0534361675 0.0348213059 0.0621726289 0.0047288461 0.1777730000 257693171 0 1784070144 0.0528698117 -0.0130362436 0.0093304832 784 1311867744.7705199718 0.0536149628 0.0348452774 0.0621726289 0.0047265460 0.1775720000 257695033 0 1785606144 0.0530696400 -0.0139523111 0.0097945407 785 1311867744.8035891056 0.0582330972 0.0348750708 0.0621726289 0.0047284015 0.1778600000 257697159 0 1784582144 0.0531768911 -0.0138741396 0.0143170748 786 1311867744.8424170017 0.0563510731 0.0349023940 0.0621726289 0.0047268448 0.1784310000 257699213 0 1782583296 0.0530330092 -0.0153172147 0.0123439841 787 1311867744.8727390766 0.0545152538 0.0349273150 0.0621726289 0.0047290044 0.1802670000 257701243 0 1781309440 0.0541606136 -0.0143491281 0.0100896787 788 1311867744.9029939175 0.0578662269 0.0349564253 0.0621726289 0.0047274861 0.1764200000 257703129 0 1782960128 0.0534219295 -0.0151843848 0.0133710373 789 1311867744.9392940998 0.0567311570 0.0349840232 0.0621726289 0.0047298022 0.2135370000 258053815 0 1784590336 0.0535292849 -0.0159317628 0.0119058248 790 1311867744.9708900452 0.0551923811 0.0350096034 0.0621726289 0.0047290900 0.3474710000 258054673 0 1784352768 0.0537670925 -0.0149380956 0.0097536165 791 1311867745.0027489662 0.0549192727 0.0350347737 0.0621726289 0.0047336222 0.3305680000 258217223 0 1783869440 0.0540887751 -0.0162605904 0.0091255512 792 1311867745.0384869576 0.0589538999 0.0350649746 0.0621726289 0.0047394487 0.3359100000 259618264 0 1785171968 0.0530260801 -0.0159987286 0.0126801562 793 1311867745.0729780197 0.0581057109 0.0350940297 0.0621726289 0.0047402816 0.2731300000 260021736 0 1783742464 0.0544892140 -0.0172503255 0.0117897950 794 1311867745.1118760109 0.0572320111 0.0351219113 0.0621726289 0.0047414298 0.1923390000 260760180 0 1785458688 0.0538738444 -0.0170852132 0.0104821250 795 1311867745.1405589581 0.0562208705 0.0351484509 0.0621726289 0.0047392288 0.3317110000 259903964 0 1784487936 0.0545840971 -0.0159659088 0.0089832358 796 1311867745.1729030609 0.0551213473 0.0351735425 0.0621726289 0.0047377735 0.2026590000 258023309 0 1784512512 0.0559974164 -0.0163756423 0.0076073203 797 1311867745.2068369389 0.0581531711 0.0352023751 0.0621726289 0.0047357194 0.1771890000 258025443 0 1783762944 0.0560351759 -0.0166711062 0.0104264840 798 1311867745.2430789471 0.0537521541 0.0352256205 0.0621726289 0.0047338338 0.1765410000 258027161 0 1782009856 0.0558485389 -0.0174156949 0.0057112183 799 1311867745.2729060650 0.0553494804 0.0352508068 0.0621726289 0.0047341920 0.1683000000 258029519 0 1780969472 0.0561222211 -0.0157640763 0.0067397952 800 1311867745.3112850189 0.0588753633 0.0352803375 0.0621726289 0.0047324058 0.1695350000 258031349 0 1779720192 0.0554585196 -0.0151157053 0.0098423101 801 1311867745.3395059109 0.0580420792 0.0353087541 0.0621726289 0.0047302659 0.1709830000 258033491 0 1778302976 0.0563527681 -0.0168984253 0.0089696255 802 1311867745.3733940125 0.0588563047 0.0353381152 0.0621726289 0.0047279002 0.1722990000 258035265 0 1780105216 0.0560412258 -0.0152034219 0.0090428460 803 1311867745.4102098942 0.0597727448 0.0353685443 0.0621726289 0.0047254716 0.1740780000 258037503 0 1781747712 0.0562470183 -0.0157466475 0.0096026603 804 1311867745.4433169365 0.0589048043 0.0353978183 0.0621726289 0.0047229202 0.2096630000 258039429 0 1783508992 0.0562184006 -0.0156086162 0.0083839800 805 1311867745.4708619118 0.0572197773 0.0354249263 0.0621726289 0.0047216891 0.1744940000 258041235 0 1785016320 0.0575974025 -0.0158455223 0.0064099766 806 1311867745.5099780560 0.0575653240 0.0354523958 0.0621726289 0.0047193762 0.1711580000 258043401 0 1784168448 0.0572241098 -0.0164202340 0.0063919649 807 1311867745.5417380333 0.0606035739 0.0354835621 0.0621726289 0.0047171305 0.1642210000 258045303 0 1782640640 0.0571308769 -0.0155527759 0.0085802786 808 1311867745.5704059601 0.0597957373 0.0355136514 0.0621726289 0.0047144287 0.1742870000 258047325 0 1781387264 0.0581422746 -0.0157110076 0.0070489217 809 1311867745.6133821011 0.0619730949 0.0355463578 0.0621726289 0.0047134023 0.1670220000 258049499 0 1780371456 0.0570338815 -0.0157058723 0.0082140453 810 1311867745.6438291073 0.0618046746 0.0355787754 0.0621726289 0.0047130974 0.1822450000 258051433 0 1779101696 0.0581912547 -0.0156374257 0.0077168997 811 1311867745.6709001064 0.0608386174 0.0356099220 0.0621726289 0.0047146432 0.1691580000 258053335 0 1780731904 0.0582033694 -0.0143827256 0.0056767687 812 1311867745.7088780403 0.0595954359 0.0356394608 0.0621726289 0.0047170701 0.1717120000 258055493 0 1782747136 0.0564707518 -0.0181196798 0.0046092980 813 1311867745.7423269749 0.0610703118 0.0356707410 0.0621726289 0.0047188040 0.1692180000 258057627 0 1784524800 0.0564683117 -0.0158198997 0.0052668005 814 1311867745.7760419846 0.0595805459 0.0357001143 0.0621726289 0.0047276295 0.1749830000 258059665 0 1783545856 0.0583322309 -0.0162321031 0.0038131271 815 1311867745.8116889000 0.0613205321 0.0357315504 0.0621726289 0.0047364371 0.1706840000 258061463 0 1781624832 0.0574432872 -0.0162351392 0.0050122850 816 1311867745.8389890194 0.0571272448 0.0357577706 0.0621726289 0.0047368927 0.1664990000 258063365 0 1781010432 0.0577607304 -0.0174746420 0.0006782990 817 1311867745.8709759712 0.0623378865 0.0357903044 0.0623378865 0.0047454143 0.1737410000 258065315 0 1778061312 0.0587632731 -0.0168416388 0.0055408496 818 1311867745.9108459949 0.0591035560 0.0358188047 0.0623378865 0.0047487954 0.1689630000 258067553 0 1776934912 0.0580993295 -0.0148484521 0.0016025975 819 1311867745.9435789585 0.0619026273 0.0358506531 0.0623378865 0.0047465123 0.1705810000 258069639 0 1778720768 0.0582391247 -0.0153512340 0.0040861499 820 1311867745.9732220173 0.0632581115 0.0358840768 0.0632581115 0.0047439355 0.1615870000 258071501 0 1780482048 0.0586791784 -0.0155726410 0.0050019026 821 1311867746.0083909035 0.0630457476 0.0359171604 0.0632581115 0.0047432876 0.1972720000 258371567 0 1782005760 0.0590065122 -0.0164240301 0.0043078475 822 1311867746.0391409397 0.0639612228 0.0359512773 0.0639612228 0.0047413371 0.3121020000 258369641 0 1784152064 0.0616954938 -0.0156206600 0.0043481030 823 1311867746.0728518963 0.0647773892 0.0359863029 0.0647773892 0.0047388517 0.2861750000 258536923 0 1785929728 0.0611474440 -0.0163093135 0.0050228778 824 1311867746.1113359928 0.0646142140 0.0360210456 0.0647773892 0.0047370920 0.2608170000 260915560 0 1783238656 0.0616063252 -0.0156273730 0.0041829571 825 1311867746.1412689686 0.0637724772 0.0360546837 0.0647773892 0.0047355948 0.2199190000 260759030 0 1782050816 0.0605707467 -0.0165523775 0.0031550191 826 1311867746.1721889973 0.0665173382 0.0360915634 0.0665173382 0.0047385012 0.3180040000 259952854 0 1780809728 0.0628752634 -0.0157045275 0.0052049272 827 1311867746.2066209316 0.0593739860 0.0361197163 0.0665173382 0.0047425369 0.1754240000 258384807 0 1781231616 0.0623825155 -0.0165194515 -0.0024885032 828 1311867746.2386920452 0.0625551343 0.0361516431 0.0665173382 0.0047415826 0.1496440000 258386957 0 1782886400 0.0631737709 -0.0129358489 -0.0005926657 829 1311867746.2704648972 0.0646180958 0.0361859814 0.0665173382 0.0047389019 0.1867980000 258696399 0 1784553472 0.0622530058 -0.0169569999 0.0023445040 830 1311867746.3068819046 0.0633678287 0.0362187306 0.0665173382 0.0047364038 0.3021260000 258651785 0 1784045568 0.0627015159 -0.0176490061 0.0008818004 831 1311867746.3393440247 0.0593462400 0.0362465615 0.0665173382 0.0047435764 0.2742460000 259412210 0 1782411264 0.0636534691 -0.0168224387 -0.0038210750 832 1311867746.3797800541 0.0575533733 0.0362721707 0.0665173382 0.0047424893 0.2163150000 261225504 0 1783603200 0.0636434108 -0.0186325163 -0.0052572563 833 1311867746.4078478813 0.0634637251 0.0363048136 0.0665173382 0.0047546703 0.2175010000 261066374 0 1782280192 0.0630964264 -0.0164334718 -0.0003649015 834 1311867746.4389901161 0.0580178909 0.0363308485 0.0665173382 0.0047602067 0.2949990000 260259742 0 1782165504 0.0637030900 -0.0189001374 -0.0048738737 835 1311867746.4774639606 0.0621758625 0.0363618006 0.0665173382 0.0047597499 0.1818180000 258643087 0 1782128640 0.0640387759 -0.0170329232 -0.0012242440 836 1311867746.5066781044 0.0645437986 0.0363955111 0.0665173382 0.0047586244 0.1513270000 258645005 0 1783775232 0.0638398230 -0.0167453270 0.0012011770 837 1311867746.5406761169 0.0605550855 0.0364243756 0.0665173382 0.0047566316 0.1592860000 258646995 0 1785405440 0.0630084947 -0.0175073519 -0.0027422551 838 1311867746.5748629570 0.0657132491 0.0364593265 0.0665173382 0.0047607556 0.1626040000 258649289 0 1784430592 0.0642879456 -0.0154919792 0.0019398313 839 1311867746.6067559719 0.0623382665 0.0364901715 0.0665173382 0.0047635114 0.1621360000 258651095 0 1780498432 0.0636167228 -0.0183536150 -0.0006927606 840 1311867746.6396849155 0.0595027022 0.0365175674 0.0665173382 0.0047616164 0.1636950000 258653381 0 1778737152 0.0630341172 -0.0190479010 -0.0036227629 841 1311867746.6749529839 0.0615055785 0.0365472796 0.0665173382 0.0047598140 0.1640570000 258655459 0 1778073600 0.0634900331 -0.0181964934 -0.0016263817 842 1311867746.7095060349 0.0622725226 0.0365778322 0.0665173382 0.0047575661 0.1513750000 258657073 0 1779732480 0.0645852685 -0.0190511830 -0.0010464881 843 1311867746.7391049862 0.0620877929 0.0366080931 0.0665173382 0.0047558368 0.1651160000 258659239 0 1781489664 0.0654208958 -0.0187747534 -0.0017045271 844 1311867746.7751340866 0.0605604276 0.0366364726 0.0665173382 0.0047533198 0.1509590000 258661125 0 1783263232 0.0643518567 -0.0205572750 -0.0030839480 845 1311867746.8070099354 0.0617646463 0.0366662101 0.0665173382 0.0047507164 0.1580350000 258663275 0 1784770560 0.0641255230 -0.0204014126 -0.0021214131 846 1311867746.8401610851 0.0639783815 0.0366984940 0.0665173382 0.0047490509 0.1593140000 258664881 0 1784176640 0.0648984089 -0.0193050206 -0.0003987458 847 1311867746.8748359680 0.0640921816 0.0367308360 0.0665173382 0.0047482483 0.1620920000 258667287 0 1783398400 0.0650297105 -0.0209132750 -0.0003534500 848 1311867746.9086029530 0.0585758016 0.0367565966 0.0665173382 0.0047546949 0.1576060000 258668997 0 1778577408 0.0660536885 -0.0214635395 -0.0063303802 849 1311867746.9389610291 0.0632147342 0.0367877605 0.0665173382 0.0047588308 0.1582330000 258670907 0 1777672192 0.0644642264 -0.0194702987 -0.0019234959 850 1311867746.9748229980 0.0664816201 0.0368226944 0.0665173382 0.0047580169 0.1560410000 258673065 0 1779331072 0.0665506870 -0.0201441441 0.0011427328 851 1311867747.0066559315 0.0635020137 0.0368540450 0.0665173382 0.0047586260 0.1639270000 258674935 0 1780998144 0.0658580288 -0.0203293804 -0.0017846990 852 1311867747.0389339924 0.0571199507 0.0368778313 0.0665173382 0.0047724967 0.1613350000 258676829 0 1782644736 0.0667223558 -0.0226585735 -0.0080618802 853 1311867747.0749640465 0.0618193150 0.0369070710 0.0665173382 0.0047810546 0.1874390000 258679099 0 1784406016 0.0655024275 -0.0215651169 -0.0033614300 854 1311867747.1066820621 0.0666695610 0.0369419217 0.0666695610 0.0047975252 0.1671440000 258680985 0 1783795712 0.0683139712 -0.0196815319 0.0001449212 855 1311867747.1389479637 0.0580305234 0.0369665867 0.0666695610 0.0048040261 0.1604270000 258683031 0 1782996992 0.0674273521 -0.0201383587 -0.0087269098 856 1311867747.1744880676 0.0639241934 0.0369980792 0.0666695610 0.0048102172 0.1645580000 258684989 0 1778958336 0.0677746311 -0.0179248825 -0.0031720791 857 1311867747.2066030502 0.0674360171 0.0370335961 0.0674360171 0.0048075787 0.1679900000 258687019 0 1777401856 0.0680469349 -0.0187406819 0.0005261861 858 1311867747.2385439873 0.0655066222 0.0370667814 0.0674360171 0.0048102306 0.1599890000 258688953 0 1779204096 0.0670089126 -0.0205064472 -0.0011643060 859 1311867747.2745490074 0.0670837536 0.0371017255 0.0674360171 0.0048201481 0.1552990000 258691063 0 1781272576 0.0690967366 -0.0199374948 0.0000734329 860 1311867747.3064720631 0.0653447285 0.0371345662 0.0674360171 0.0048222227 0.1558160000 258693101 0 1782358016 0.0674198791 -0.0195427500 -0.0022709798 861 1311867747.3388469219 0.0682347491 0.0371706872 0.0682347491 0.0048292236 0.1605050000 258694939 0 1784389632 0.0690277740 -0.0208697803 0.0005560629 862 1311867747.3758800030 0.0677072704 0.0372061125 0.0682347491 0.0048289688 0.2334550000 258697009 0 1783521280 0.0692547858 -0.0211834889 -0.0003092028 863 1311867747.4068729877 0.0677522197 0.0372415078 0.0682347491 0.0048268244 0.1785930000 258699127 0 1779445760 0.0690411031 -0.0195613634 -0.0006559789 864 1311867747.4396450520 0.0648429543 0.0372734539 0.0682347491 0.0048270538 0.1583210000 258700941 0 1777803264 0.0699419975 -0.0187132992 -0.0046001058 865 1311867747.4756069183 0.0682514533 0.0373092666 0.0682514533 0.0048301404 0.1556780000 258702995 0 1779572736 0.0693109483 -0.0199511107 -0.0007166602 866 1311867747.5095520020 0.0666998997 0.0373432050 0.0682514533 0.0048277877 0.1567870000 258705105 0 1780473856 0.0688983798 -0.0184232946 -0.0026141293 867 1311867747.5405330658 0.0701350048 0.0373810271 0.0701350048 0.0048273512 0.1606800000 258706975 0 1783771136 0.0702358037 -0.0183267426 0.0005145445 868 1311867747.5766739845 0.0626647025 0.0374101558 0.0701350048 0.0048425759 0.1540560000 258708845 0 1784045568 0.0686928481 -0.0228438824 -0.0063793845 869 1311867747.6086390018 0.0654513687 0.0374424241 0.0701350048 0.0048437630 0.1534140000 258710939 0 1785913344 0.0689175874 -0.0210441798 -0.0038914662 870 1311867747.6432039738 0.0699971765 0.0374798434 0.0701350048 0.0048462318 0.1825900000 258988017 0 1785303040 0.0722947568 -0.0186337885 -0.0004184693 871 1311867747.6760280132 0.0671574101 0.0375139164 0.0701350048 0.0048575497 0.2857580000 258951191 0 1784606720 0.0726829171 -0.0191716049 -0.0033822022 872 1311867747.7068400383 0.0700267553 0.0375512017 0.0701350048 0.0048581605 0.2632950000 260198448 0 1781534720 0.0702399313 -0.0203401893 0.0002098754 873 1311867747.7480750084 0.0673980266 0.0375853906 0.0701350048 0.0048578705 0.2247500000 261291102 0 1783857152 0.0693683177 -0.0199470203 -0.0029761419 874 1311867747.7826869488 0.0685432553 0.0376208114 0.0701350048 0.0048552136 0.1721140000 261303080 0 1785610240 0.0702398568 -0.0191674978 -0.0023826919 875 1311867747.8149020672 0.0698325709 0.0376576249 0.0701350048 0.0048571426 0.2673770000 260448900 0 1785298944 0.0693331361 -0.0179210212 -0.0013902821 876 1311867747.8466539383 0.0675200745 0.0376917144 0.0701350048 0.0048581610 0.1828750000 258946933 0 1785556992 0.0692248270 -0.0182677023 -0.0036348552 877 1311867747.8827810287 0.0633711889 0.0377209955 0.0701350048 0.0048562562 0.1427230000 258949179 0 1784647680 0.0679306686 -0.0180800892 -0.0077502616 878 1311867747.9150440693 0.0676085278 0.0377550360 0.0701350048 0.0048596084 0.1835390000 258951057 0 1784430592 0.0678467304 -0.0188533515 -0.0031952206 879 1311867747.9477820396 0.0641201288 0.0377850304 0.0701350048 0.0048619615 0.1575880000 258953023 0 1783791616 0.0664291233 -0.0194327328 -0.0061068758 880 1311867747.9826579094 0.0673650652 0.0378186440 0.0701350048 0.0048670088 0.1605610000 258955293 0 1782751232 0.0662683696 -0.0163612030 -0.0031350944 881 1311867748.0146598816 0.0666106269 0.0378513251 0.0701350048 0.0048645897 0.1584290000 258957355 0 1780228096 0.0666693151 -0.0170377269 -0.0034416895 882 1311867748.0469269753 0.0634861365 0.0378803895 0.0701350048 0.0048632893 0.1592880000 258959313 0 1779830784 0.0646791980 -0.0181132369 -0.0053318013 883 1311867748.0828750134 0.0634812564 0.0379093825 0.0701350048 0.0048608574 0.1543630000 258961247 0 1781518336 0.0649812892 -0.0160672907 -0.0054038111 884 1311867748.1150569916 0.0639604256 0.0379388520 0.0701350048 0.0048582596 0.1687080000 258963117 0 1783386112 0.0642536134 -0.0160929915 -0.0043676216 885 1311867748.1486010551 0.0623537898 0.0379664395 0.0701350048 0.0048587484 0.1643520000 258964795 0 1785184256 0.0640417039 -0.0162221808 -0.0055675581 886 1311867748.1831040382 0.0633038133 0.0379950370 0.0701350048 0.0048563106 0.1651410000 258967073 0 1784422400 0.0629267544 -0.0178096853 -0.0037987102 887 1311867748.2148320675 0.0611797385 0.0380211754 0.0701350048 0.0048547790 0.1619870000 258968879 0 1783898112 0.0630706102 -0.0169855915 -0.0059740096 888 1311867748.2466599941 0.0643704906 0.0380508480 0.0701350048 0.0048615939 0.1599780000 258971029 0 1781264384 0.0618968569 -0.0165545139 -0.0028251950 889 1311867748.2827599049 0.0628066659 0.0380786948 0.0701350048 0.0048591029 0.1594390000 258973059 0 1779867648 0.0619682148 -0.0160949435 -0.0044451337 890 1311867748.3148829937 0.0636782199 0.0381074583 0.0701350048 0.0048610920 0.1678350000 258974793 0 1779216384 0.0618671514 -0.0161611121 -0.0031398069 891 1311867748.3470869064 0.0640815049 0.0381366099 0.0701350048 0.0048663640 0.1632700000 258977007 0 1778470912 0.0624417514 -0.0154091353 -0.0034061559 892 1311867748.3826999664 0.0612860546 0.0381625622 0.0701350048 0.0048650574 0.1627650000 258978917 0 1779613696 0.0616934299 -0.0170299746 -0.0056434087 893 1311867748.4148259163 0.0628530085 0.0381902111 0.0701350048 0.0048646982 0.1607130000 258980779 0 1781755904 0.0614571534 -0.0142571218 -0.0042730253 894 1311867748.4520189762 0.0619806051 0.0382168223 0.0701350048 0.0048763971 0.1622440000 258982817 0 1783386112 0.0605634376 -0.0154550690 -0.0045594685 895 1311867748.4831318855 0.0609769784 0.0382422526 0.0701350048 0.0048744481 0.1558650000 258984847 0 1785053184 0.0608494133 -0.0156485401 -0.0052255113 896 1311867748.5149960518 0.0604346879 0.0382670209 0.0701350048 0.0048736287 0.1593760000 258986813 0 1784274944 0.0602183193 -0.0141784111 -0.0051428266 897 1311867748.5467929840 0.0623455383 0.0382938643 0.0701350048 0.0048724940 0.1580900000 258988763 0 1783263232 0.0597807914 -0.0150035331 -0.0028828401 898 1311867748.5827159882 0.0612127036 0.0383193864 0.0701350048 0.0048700296 0.1571320000 258990857 0 1779716096 0.0599350818 -0.0147563610 -0.0037204120 899 1311867748.6147999763 0.0611727908 0.0383448073 0.0701350048 0.0048680145 0.1605040000 258992791 0 1779085312 0.0592416711 -0.0122071169 -0.0040729474 900 1311867748.6470849514 0.0600420013 0.0383689153 0.0701350048 0.0048843250 0.1639300000 258995173 0 1778561024 0.0585182011 -0.0144513659 -0.0034006834 901 1311867748.6827559471 0.0600313544 0.0383929580 0.0701350048 0.0048821738 0.1591850000 258996979 0 1780228096 0.0590202957 -0.0147079686 -0.0031132698 902 1311867748.7147359848 0.0613363236 0.0384183941 0.0701350048 0.0049025089 0.1640660000 258998745 0 1782153216 0.0579851605 -0.0158275254 -0.0019765701 903 1311867748.7499361038 0.0613647886 0.0384438054 0.0701350048 0.0049006335 0.1594060000 259000671 0 1783894016 0.0568645485 -0.0154308053 -0.0018820502 904 1311867748.7828259468 0.0608749613 0.0384686186 0.0701350048 0.0048980493 0.1584650000 259003077 0 1785683968 0.0565907285 -0.0162948575 -0.0020189099 905 1311867748.8151619434 0.0588025115 0.0384910870 0.0701350048 0.0048962623 0.1610230000 259005003 0 1784795136 0.0565361157 -0.0151206404 -0.0043363515 906 1311867748.8466329575 0.0574643016 0.0385120287 0.0701350048 0.0048940499 0.2006170000 259006953 0 1783894016 0.0546653718 -0.0155687751 -0.0053200312 907 1311867748.8829579353 0.0584149249 0.0385339724 0.0701350048 0.0048935108 0.1628280000 259009167 0 1785683968 0.0543701574 -0.0141899493 -0.0036103390 908 1311867748.9149119854 0.0589055084 0.0385564080 0.0701350048 0.0048909926 0.1607680000 259010845 0 1784893440 0.0544777960 -0.0146764079 -0.0024834368 909 1311867748.9472498894 0.0596098863 0.0385795692 0.0701350048 0.0048884455 0.1744790000 259012843 0 1780314112 0.0533611998 -0.0146303903 -0.0012604985 910 1311867748.9829359055 0.0564240105 0.0385991784 0.0701350048 0.0048884494 0.1614160000 259014865 0 1779707904 0.0534097068 -0.0136571862 -0.0043857321 911 1311867749.0159859657 0.0549887903 0.0386171692 0.0701350048 0.0048861641 0.1675090000 259017023 0 1778950144 0.0518000722 -0.0144369071 -0.0051002409 912 1311867749.0467190742 0.0571261160 0.0386374641 0.0701350048 0.0048845988 0.1652350000 259018949 0 1778208768 0.0525554456 -0.0137188546 -0.0026872158 913 1311867749.0828969479 0.0576488860 0.0386582871 0.0701350048 0.0048822218 0.1636040000 259020843 0 1779970048 0.0518224165 -0.0140155023 -0.0018067062 914 1311867749.1158421040 0.0545381084 0.0386756611 0.0701350048 0.0048800779 0.1667510000 259023033 0 1781219328 0.0507796481 -0.0132637722 -0.0049207881 915 1311867749.1485249996 0.0575382076 0.0386962759 0.0701350048 0.0048796270 0.1659650000 259024767 0 1782886400 0.0502644405 -0.0120565109 -0.0016097594 916 1311867749.1829619408 0.0576474816 0.0387169650 0.0701350048 0.0048774837 0.1595400000 259026773 0 1784885248 0.0501851514 -0.0124567496 -0.0010053851 917 1311867749.2156000137 0.0550866835 0.0387348164 0.0701350048 0.0048776009 0.1639180000 259028779 0 1784016896 0.0500221848 -0.0133360233 -0.0033347998 918 1311867749.2468719482 0.0584891886 0.0387563353 0.0701350048 0.0048755816 0.1728780000 259030921 0 1782386688 0.0510685816 -0.0142571758 0.0002600271 919 1311867749.2828478813 0.0575388782 0.0387767734 0.0701350048 0.0048743859 0.1638580000 259032783 0 1781387264 0.0498265177 -0.0127865635 -0.0010132082 920 1311867749.3148140907 0.0565661602 0.0387961096 0.0701350048 0.0048721810 0.1706470000 259034981 0 1777410048 0.0495003909 -0.0125445668 -0.0020980481 921 1311867749.3468968868 0.0592318848 0.0388182983 0.0701350048 0.0048708432 0.1662560000 259036803 0 1776156672 0.0496085621 -0.0109521132 0.0004054531 922 1311867749.3828470707 0.0564058535 0.0388373738 0.0701350048 0.0048700080 0.1688110000 259038921 0 1777688576 0.0484043360 -0.0128028495 -0.0016282015 923 1311867749.4147930145 0.0560519248 0.0388560244 0.0701350048 0.0048678512 0.1620400000 259040863 0 1779609600 0.0472313613 -0.0106149791 -0.0021410901 924 1311867749.4467489719 0.0548686683 0.0388733541 0.0701350048 0.0048658969 0.1636310000 259042829 0 1781329920 0.0471640155 -0.0110374251 -0.0025361665 925 1311867749.4829080105 0.0546976700 0.0388904615 0.0701350048 0.0048642763 0.1603260000 259044867 0 1782980608 0.0470201485 -0.0098963287 -0.0023471210 926 1311867749.5159850121 0.0589743815 0.0389121504 0.0701350048 0.0048681489 0.1614160000 259047081 0 1784504320 0.0452884957 -0.0110518932 0.0028526504 927 1311867749.5468530655 0.0598200597 0.0389347048 0.0701350048 0.0048664123 0.1764360000 259048783 0 1783910400 0.0449374355 -0.0089607406 0.0033244919 928 1311867749.5830268860 0.0565888435 0.0389537286 0.0701350048 0.0048667459 0.1674850000 259050701 0 1779961856 0.0445743054 -0.0107200490 0.0007203259 929 1311867749.6148250103 0.0570913590 0.0389732524 0.0701350048 0.0048647904 0.1684500000 259052715 0 1778438144 0.0420814827 -0.0119427759 0.0016186107 930 1311867749.6469049454 0.0542841069 0.0389897157 0.0701350048 0.0048632357 0.1676490000 259054985 0 1777659904 0.0414614417 -0.0119444439 -0.0013685692 931 1311867749.6829149723 0.0552891493 0.0390072232 0.0701350048 0.0048612767 0.1695100000 259056695 0 1779449856 0.0415160954 -0.0127859833 -0.0001987331 932 1311867749.7160799503 0.0566136912 0.0390261142 0.0701350048 0.0048604531 0.1748930000 259059029 0 1781116928 0.0394114405 -0.0118881827 0.0006805360 933 1311867749.7468609810 0.0552461520 0.0390434991 0.0701350048 0.0048584273 0.1974040000 259060931 0 1782726656 0.0389648676 -0.0119387759 -0.0011663083 934 1311867749.7828791142 0.0539061949 0.0390594120 0.0701350048 0.0048564185 0.1525320000 259062921 0 1784377344 0.0385131612 -0.0126242666 -0.0016256254 935 1311867749.8148949146 0.0519033037 0.0390731488 0.0701350048 0.0048651115 0.1650180000 259065079 0 1783783424 0.0392673910 -0.0123979105 -0.0033330722 936 1311867749.8469030857 0.0506228991 0.0390854883 0.0701350048 0.0048627060 0.1647160000 259067005 0 1783152640 0.0389725715 -0.0120340763 -0.0047034230 937 1311867749.8829030991 0.0558527894 0.0391033829 0.0701350048 0.0048952059 0.1706600000 259068931 0 1780613120 0.0366625115 -0.0113948034 -0.0000411216 938 1311867749.9149639606 0.0550185218 0.0391203500 0.0701350048 0.0049093281 0.1698060000 259070969 0 1777684480 0.0364162661 -0.0109381564 -0.0000247788 939 1311867749.9508709908 0.0515256524 0.0391335612 0.0701350048 0.0049085917 0.1671040000 259073071 0 1776521216 0.0370261148 -0.0107077044 -0.0036692200 940 1311867749.9827940464 0.0526097938 0.0391478976 0.0701350048 0.0049094930 0.1598910000 259075141 0 1778327552 0.0354926698 -0.0104170134 -0.0026574889 941 1311867750.0147750378 0.0519230142 0.0391614737 0.0701350048 0.0049082134 0.1624160000 259077139 0 1780088832 0.0353665352 -0.0106866583 -0.0030402718 942 1311867750.0470709801 0.0519702584 0.0391750712 0.0701350048 0.0049057243 0.1565910000 259078785 0 1781583872 0.0353886969 -0.0105786165 -0.0028599128 943 1311867750.0829339027 0.0512740314 0.0391879015 0.0701350048 0.0049032785 0.1684400000 259080903 0 1783234560 0.0338921249 -0.0103236958 -0.0033063637 944 1311867750.1156458855 0.0517773628 0.0392012378 0.0701350048 0.0049013932 0.1647810000 259083333 0 1785012224 0.0323222131 -0.0102361469 -0.0026644850 945 1311867750.1474790573 0.0496142656 0.0392122568 0.0701350048 0.0048998267 0.1606250000 259084979 0 1784008704 0.0327013321 -0.0101581896 -0.0045665978 946 1311867750.1828711033 0.0487072468 0.0392222938 0.0701350048 0.0048988487 0.1680300000 259086841 0 1779970048 0.0318353996 -0.0119881369 -0.0045533981 947 1311867750.2156589031 0.0485008620 0.0392320917 0.0701350048 0.0048971403 0.1707020000 259088895 0 1778044928 0.0307967365 -0.0091395490 -0.0054496769 948 1311867750.2469079494 0.0477875993 0.0392411165 0.0701350048 0.0048947841 0.1650140000 259090989 0 1779724288 0.0308669098 -0.0088080335 -0.0057620090 949 1311867750.2829968929 0.0475031175 0.0392498225 0.0701350048 0.0048927434 0.1692380000 259092963 0 1781485568 0.0307205059 -0.0084069427 -0.0054774806 950 1311867750.3150129318 0.0479762331 0.0392590082 0.0701350048 0.0048903776 0.1661080000 259094897 0 1783107584 0.0303772353 -0.0093773846 -0.0043181581 951 1311867750.3469090462 0.0450649224 0.0392651132 0.0701350048 0.0048909632 0.1786650000 259096903 0 1784758272 0.0293714739 -0.0107767256 -0.0067125368 952 1311867750.3828659058 0.0434572212 0.0392695167 0.0701350048 0.0048891605 0.1727550000 259098669 0 1784041472 0.0306152850 -0.0105534699 -0.0079442430 953 1311867750.4148640633 0.0472712740 0.0392779131 0.0701350048 0.0048904148 0.1693620000 259100883 0 1779822592 0.0293579735 -0.0095045287 -0.0039197383 954 1311867750.4469859600 0.0482607335 0.0392873290 0.0701350048 0.0048882157 0.1666800000 259102889 0 1777934336 0.0291835144 -0.0076607587 -0.0031750854 955 1311867750.4829618931 0.0477362424 0.0392961761 0.0701350048 0.0048866994 0.1702690000 259105087 0 1776648192 0.0274241008 -0.0085384306 -0.0034717489 956 1311867750.5148859024 0.0461105742 0.0393033041 0.0701350048 0.0048851046 0.1692310000 259106957 0 1775394816 0.0277282689 -0.0089754071 -0.0046317363 957 1311867750.5476069450 0.0424064808 0.0393065467 0.0701350048 0.0048857546 0.1679220000 259109027 0 1777053696 0.0272709336 -0.0102580702 -0.0081775915 958 1311867750.5827779770 0.0436818078 0.0393111138 0.0701350048 0.0048860542 0.1722030000 259110937 0 1778831360 0.0269784033 -0.0084443269 -0.0073416955 959 1311867750.6148829460 0.0422453098 0.0393141734 0.0701350048 0.0048836112 0.1727140000 259112839 0 1780441088 0.0268180892 -0.0084843375 -0.0084551685 960 1311867750.6469810009 0.0437143333 0.0393187569 0.0701350048 0.0048814500 0.1947440000 259114917 0 1782218752 0.0257213265 -0.0076130498 -0.0069386745 961 1311867750.6829319000 0.0427785926 0.0393223572 0.0701350048 0.0048794393 0.1687600000 259116963 0 1783869440 0.0268211830 -0.0052613062 -0.0079614595 962 1311867750.7149219513 0.0410619900 0.0393241655 0.0701350048 0.0048794048 0.1669350000 259119185 0 1785647104 0.0252720527 -0.0074504581 -0.0083566494 963 1311867750.7469151020 0.0427562669 0.0393277295 0.0701350048 0.0048823976 0.1788370000 259120559 0 1784803328 0.0254471544 -0.0075548370 -0.0059999968 964 1311867750.7832129002 0.0445140153 0.0393331095 0.0701350048 0.0048829215 0.2057440000 259420641 0 1783623680 0.0238626096 -0.0062021464 -0.0042559574 965 1311867750.8149549961 0.0397338904 0.0393335248 0.0701350048 0.0048867083 0.3317020000 259430035 0 1785462784 0.0236888826 -0.0077842111 -0.0082570221 966 1311867750.8468461037 0.0381840840 0.0393323349 0.0701350048 0.0048877373 0.3168940000 260315372 0 1786478592 0.0238522738 -0.0096889446 -0.0085393246 967 1311867750.8828840256 0.0412595719 0.0393343279 0.0701350048 0.0048902776 0.2502490000 262074806 0 1783840768 0.0235194080 -0.0065914183 -0.0058738687 968 1311867750.9147970676 0.0375537761 0.0393324885 0.0701350048 0.0048891184 0.2371900000 261962108 0 1782435840 0.0243847407 -0.0071612140 -0.0092565548 969 1311867750.9468770027 0.0387186222 0.0393318550 0.0701350048 0.0048869705 0.3294670000 261109928 0 1779163136 0.0241676308 -0.0068936553 -0.0074921474 970 1311867750.9830369949 0.0398136117 0.0393323516 0.0701350048 0.0048846047 0.1793130000 259440297 0 1779478528 0.0219840594 -0.0081155328 -0.0062309587 971 1311867751.0168409348 0.0421519391 0.0393352554 0.0701350048 0.0048857101 0.1743860000 259442175 0 1781198848 0.0235956758 -0.0051947930 -0.0042379955 972 1311867751.0470340252 0.0395081565 0.0393354333 0.0701350048 0.0048842141 0.1685390000 259444077 0 1782886400 0.0225142986 -0.0054224404 -0.0066425344 973 1311867751.0828599930 0.0354759656 0.0393314667 0.0701350048 0.0048907632 0.1668890000 259446075 0 1784647680 0.0214641541 -0.0074988734 -0.0103569366 974 1311867751.1174809933 0.0343076028 0.0393263088 0.0701350048 0.0048888700 0.1730610000 259448249 0 1783738368 0.0208286680 -0.0083364090 -0.0113006113 975 1311867751.1468789577 0.0333204791 0.0393201489 0.0701350048 0.0048866096 0.1671290000 259450215 0 1779572736 0.0207946636 -0.0066792034 -0.0132965408 976 1311867751.1835930347 0.0297834054 0.0393103777 0.0701350048 0.0048887545 0.1690050000 259452365 0 1778798592 0.0200862233 -0.0077613145 -0.0165294614 977 1311867751.2161049843 0.0349277854 0.0393058919 0.0701350048 0.0048948272 0.1673160000 259454227 0 1777016832 0.0192519389 -0.0079530319 -0.0106301196 978 1311867751.2468481064 0.0315069482 0.0392979175 0.0701350048 0.0048970984 0.1715930000 259456097 0 1776259072 0.0182739031 -0.0094961794 -0.0142974425 979 1311867751.2831909657 0.0323263891 0.0392907965 0.0701350048 0.0048984680 0.1685360000 259458151 0 1777913856 0.0192181766 -0.0065475623 -0.0136770029 980 1311867751.3149859905 0.0311669409 0.0392825068 0.0701350048 0.0048974777 0.1655560000 259460205 0 1779695616 0.0191794876 -0.0075650685 -0.0143774990 981 1311867751.3498640060 0.0308974385 0.0392739594 0.0701350048 0.0048953882 0.1670620000 259462243 0 1781362688 0.0178181101 -0.0095153647 -0.0141713526 982 1311867751.3834669590 0.0305378735 0.0392650631 0.0701350048 0.0048931815 0.1662160000 259464041 0 1782976512 0.0172401257 -0.0076284148 -0.0153609999 983 1311867751.4151160717 0.0277309641 0.0392533296 0.0701350048 0.0048975289 0.2095520000 259465999 0 1784754176 0.0173008982 -0.0099414606 -0.0179163441 984 1311867751.4513890743 0.0313389152 0.0392452865 0.0701350048 0.0049091024 0.1682470000 259468125 0 1783865344 0.0185017101 -0.0086828675 -0.0137533471 985 1311867751.4838130474 0.0289795045 0.0392348644 0.0701350048 0.0049082683 0.1690980000 259470115 0 1780940800 0.0184274707 -0.0076808552 -0.0170886945 986 1311867751.5149779320 0.0283979569 0.0392238736 0.0701350048 0.0049060587 0.1735610000 259472145 0 1780219904 0.0175305475 -0.0072201504 -0.0180852152 987 1311867751.5495769978 0.0270363931 0.0392115256 0.0701350048 0.0049039539 0.1736360000 259473967 0 1779040256 0.0162152778 -0.0084686084 -0.0195240602 988 1311867751.5829720497 0.0282450411 0.0392004259 0.0701350048 0.0049025155 0.1665990000 259475933 0 1777307648 0.0168648120 -0.0062721232 -0.0188254490 989 1311867751.6149520874 0.0284042042 0.0391895096 0.0701350048 0.0049009194 0.1734210000 259478599 0 1776369664 0.0166222397 -0.0075082527 -0.0178226829 990 1311867751.6501350403 0.0235321131 0.0391736940 0.0701350048 0.0049038142 0.1689990000 259480269 0 1778188288 0.0164237283 -0.0101754293 -0.0222219527 991 1311867751.6839730740 0.0238301102 0.0391582111 0.0701350048 0.0049013453 0.1752270000 259482259 0 1779949568 0.0164570194 -0.0094769020 -0.0219646357 992 1311867751.7150709629 0.0249408800 0.0391438791 0.0701350048 0.0048996889 0.1746250000 259484169 0 1781600256 0.0169651564 -0.0081388699 -0.0206388105 993 1311867751.7507519722 0.0259080585 0.0391305500 0.0701350048 0.0048975165 0.1701900000 259486215 0 1783341056 0.0158704687 -0.0092824213 -0.0191270262 994 1311867751.7830109596 0.0258448627 0.0391171841 0.0701350048 0.0048952957 0.2044120000 259820577 0 1784991744 0.0137609756 -0.0099462643 -0.0197285265 995 1311867751.8149600029 0.0235043317 0.0391014928 0.0701350048 0.0048957052 0.3571950000 259817115 0 1784500224 0.0141776390 -0.0087506659 -0.0228531770 996 1311867751.8509531021 0.0215631668 0.0390838840 0.0701350048 0.0048955528 0.3300550000 259960985 0 1783713792 0.0152933300 -0.0096188989 -0.0235684551 997 1311867751.8832330704 0.0244474113 0.0390692035 0.0701350048 0.0048976377 0.2914810000 262763006 0 1785892864 0.0144736068 -0.0090761976 -0.0198800787 998 1311867751.9149179459 0.0204184316 0.0390505154 0.0701350048 0.0049013403 0.2644770000 262585172 0 1785311232 0.0142048849 -0.0082644923 -0.0254264399 999 1311867751.9530611038 0.0227657892 0.0390342144 0.0701350048 0.0049028000 0.3691740000 261788428 0 1783480320 0.0129078012 -0.0112566724 -0.0202274900 1000 1311867751.9829521179 0.0217574369 0.0390169376 0.0701350048 0.0049014188 0.1962990000 259825109 0 1783312384 0.0129097383 -0.0087912362 -0.0223197453 1001 1311867752.0153670311 0.0239478834 0.0390018836 0.0701350048 0.0049026193 0.1782110000 259827119 0 1785491456 0.0119694714 -0.0081100445 -0.0192956161 1002 1311867752.0510330200 0.0231402349 0.0389860536 0.0701350048 0.0049006761 0.1873470000 259829277 0 1784836096 0.0120089110 -0.0102705434 -0.0189193320 1003 1311867752.0828928947 0.0252648070 0.0389723734 0.0701350048 0.0049011203 0.1778340000 259830955 0 1784094720 0.0130090006 -0.0080895675 -0.0154808629 1004 1311867752.1150529385 0.0272059981 0.0389606539 0.0701350048 0.0048995551 0.1823810000 259833025 0 1783603200 0.0141736474 -0.0066648405 -0.0124718938 1005 1311867752.1509859562 0.0229175482 0.0389446906 0.0701350048 0.0049019918 0.2017630000 259834999 0 1785217024 0.0124357054 -0.0076953503 -0.0172057953 1006 1311867752.1829679012 0.0223976318 0.0389282422 0.0701350048 0.0049003017 0.1802890000 259837261 0 1784745984 0.0128287356 -0.0077898293 -0.0166821498 1007 1311867752.2150039673 0.0260517430 0.0389154552 0.0701350048 0.0049050403 0.1809120000 259838939 0 1782292480 0.0136268446 -0.0060928501 -0.0116662309 1008 1311867752.2512340546 0.0271987114 0.0389038315 0.0701350048 0.0049028487 0.1776140000 259841085 0 1781825536 0.0128893889 -0.0068231057 -0.0094875284 1009 1311867752.2833271027 0.0290049501 0.0388940209 0.0701350048 0.0049032671 0.1782270000 259843387 0 1783586816 0.0125769190 -0.0085941823 -0.0067579728 1010 1311867752.3150799274 0.0290716738 0.0388842958 0.0701350048 0.0049012459 0.1845030000 259845057 0 1785217024 0.0126711791 -0.0086797802 -0.0064463248 1011 1311867752.3509979248 0.0300783254 0.0388755856 0.0701350048 0.0048999876 0.1764350000 259847015 0 1784598528 0.0117881335 -0.0081278058 -0.0058065886 1012 1311867752.3829851151 0.0292325951 0.0388660570 0.0701350048 0.0048980077 0.1846210000 259849005 0 1784090624 0.0113305040 -0.0091900714 -0.0068274820 1013 1311867752.4160280228 0.0283887032 0.0388557141 0.0701350048 0.0048961225 0.1829390000 259850979 0 1783955456 0.0128417062 -0.0096379854 -0.0070505226 1014 1311867752.4510710239 0.0278901123 0.0388448999 0.0701350048 0.0049004573 0.1813430000 259853017 0 1780391936 0.0116207190 -0.0098474370 -0.0078698080 1015 1311867752.4829080105 0.0285905134 0.0388347971 0.0701350048 0.0048993904 0.1809510000 259855039 0 1779625984 0.0101324087 -0.0106629869 -0.0081456499 1016 1311867752.5181159973 0.0296331216 0.0388257403 0.0701350048 0.0048981506 0.1783710000 259856781 0 1781407744 0.0107557531 -0.0100467289 -0.0066424059 1017 1311867752.5511059761 0.0284779165 0.0388155654 0.0701350048 0.0048971451 0.1828220000 259858867 0 1783058432 0.0125430096 -0.0094789341 -0.0076795341 1018 1311867752.5830090046 0.0290223937 0.0388059454 0.0701350048 0.0048953661 0.1855150000 259860937 0 1784983552 0.0123597682 -0.0088106943 -0.0073496494 1019 1311867752.6167891026 0.0272651352 0.0387946198 0.0701350048 0.0048949421 0.1831000000 259862975 0 1784492032 0.0109838257 -0.0121432487 -0.0096337060 1020 1311867752.6514921188 0.0260850880 0.0387821595 0.0701350048 0.0048956658 0.1747980000 259864725 0 1782423552 0.0114320982 -0.0098126596 -0.0112189539 1021 1311867752.6830079556 0.0283872709 0.0387719784 0.0701350048 0.0048989620 0.1839160000 259866779 0 1782079488 0.0104097510 -0.0112171331 -0.0093790982 1022 1311867752.7152869701 0.0271639284 0.0387606202 0.0701350048 0.0049012966 0.1788740000 259868897 0 1783693312 0.0096488269 -0.0142697245 -0.0115375267 1023 1311867752.7510609627 0.0272800028 0.0387493977 0.0701350048 0.0049004248 0.1730480000 259870879 0 1785634816 0.0120839914 -0.0109438561 -0.0110234227 1024 1311867752.7830440998 0.0279280692 0.0387388300 0.0701350048 0.0049035192 0.1847580000 259872837 0 1784709120 0.0106354635 -0.0101250475 -0.0116855921 1025 1311867752.8162839413 0.0269211158 0.0387273005 0.0701350048 0.0049014799 0.1851250000 259956971 0 1783934976 0.0099013392 -0.0103502227 -0.0133907814 1026 1311867752.8511059284 0.0274706874 0.0387163292 0.0701350048 0.0048992346 0.2175610000 260470289 0 1786114048 0.0098556820 -0.0113819139 -0.0127971536 1027 1311867752.8833000660 0.0278918426 0.0387057893 0.0701350048 0.0048970520 0.3841900000 260476939 0 1784877056 0.0098389890 -0.0107735684 -0.0122844167 1028 1311867752.9183809757 0.0257862154 0.0386932216 0.0701350048 0.0048956956 0.3447020000 260610021 0 1783357440 0.0115615577 -0.0102365706 -0.0140973115 1029 1311867752.9511129856 0.0268351715 0.0386816977 0.0701350048 0.0048960907 0.3637240000 262094622 0 1776500736 0.0106805619 -0.0116169304 -0.0129667856 1030 1311867752.9828579426 0.0274864640 0.0386708286 0.0701350048 0.0048940852 0.2779070000 263543924 0 1776766976 0.0101719741 -0.0105584208 -0.0127822869 1031 1311867753.0168170929 0.0263424404 0.0386588709 0.0701350048 0.0048919425 0.2199080000 263586574 0 1778536448 0.0129338205 -0.0089017134 -0.0133021977 1032 1311867753.0510199070 0.0270785298 0.0386476496 0.0701350048 0.0048897845 0.3747220000 262653670 0 1774170112 0.0105546508 -0.0116242561 -0.0135255428 1033 1311867753.0829060078 0.0259940960 0.0386354003 0.0701350048 0.0048876852 0.2152340000 260447519 0 1774444544 0.0101776868 -0.0113897184 -0.0151969530 1034 1311867753.1184310913 0.0267131105 0.0386238700 0.0701350048 0.0048863813 0.1914120000 260449637 0 1776082944 0.0119712502 -0.0081234071 -0.0139654092 1035 1311867753.1510760784 0.0274983943 0.0386131208 0.0701350048 0.0048851774 0.1880330000 260451699 0 1777844224 0.0091124345 -0.0138867395 -0.0140310079 1036 1311867753.1830070019 0.0269358493 0.0386018493 0.0701350048 0.0048836322 0.1902650000 260453529 0 1779585024 0.0098010423 -0.0107811093 -0.0142875705 1037 1311867753.2186999321 0.0241012182 0.0385878660 0.0701350048 0.0048815023 0.1841360000 260455663 0 1780998144 0.0113683539 -0.0081451433 -0.0170477442 1038 1311867753.2520470619 0.0266905427 0.0385764042 0.0701350048 0.0048803248 0.1835820000 260457605 0 1783140352 0.0092867799 -0.0097973906 -0.0145245260 1039 1311867753.2829909325 0.0251334924 0.0385634659 0.0701350048 0.0048808349 0.1870160000 260459387 0 1784918016 0.0084904702 -0.0115743261 -0.0160117932 1040 1311867753.3196740150 0.0245638136 0.0385500047 0.0701350048 0.0048842275 0.1884460000 260461705 0 1783922688 0.0089520253 -0.0075966739 -0.0161263030 1041 1311867753.3509368896 0.0231385175 0.0385352002 0.0701350048 0.0048828687 0.1902240000 260463487 0 1782657024 0.0093154348 -0.0090824412 -0.0169400871 1042 1311867753.3829340935 0.0226728823 0.0385199773 0.0701350048 0.0048837098 0.1897310000 260465565 0 1784561664 0.0084950682 -0.0128416661 -0.0175189096 1043 1311867753.4182109833 0.0228431169 0.0385049467 0.0701350048 0.0048815011 0.1845590000 260467603 0 1784090624 0.0063172379 -0.0119656222 -0.0188861433 1044 1311867753.4511721134 0.0218597185 0.0384890030 0.0701350048 0.0048794685 0.1867440000 260469481 0 1781514240 0.0070418157 -0.0128257489 -0.0194015335 1045 1311867753.4831509590 0.0219438542 0.0384731703 0.0701350048 0.0048779537 0.2000310000 260471431 0 1780752384 0.0060745068 -0.0106509430 -0.0197306443 1046 1311867753.5199849606 0.0214301255 0.0384568768 0.0701350048 0.0048759486 0.1885840000 260473525 0 1782280192 0.0066901688 -0.0094340881 -0.0197373461 1047 1311867753.5532789230 0.0204361528 0.0384396650 0.0701350048 0.0048739385 0.1864930000 260475547 0 1783664640 0.0054736184 -0.0103944270 -0.0213960987 1048 1311867753.5832290649 0.0202419255 0.0384223008 0.0701350048 0.0048716397 0.1823730000 260477489 0 1785552896 0.0046784710 -0.0107741766 -0.0218658689 1049 1311867753.6183180809 0.0185927413 0.0384033975 0.0701350048 0.0048697722 0.1855640000 260479543 0 1784418304 0.0057013854 -0.0106209256 -0.0224261731 1050 1311867753.6509299278 0.0191477798 0.0383850588 0.0701350048 0.0048676150 0.1886440000 260481725 0 1783275520 0.0047220727 -0.0121648554 -0.0219793227 1051 1311867753.6830120087 0.0185271893 0.0383661645 0.0701350048 0.0048656884 0.2150970000 260483371 0 1785040896 0.0042235805 -0.0115340296 -0.0227108859 1052 1311867753.7204821110 0.0191013981 0.0383478520 0.0701350048 0.0048640776 0.1886240000 260485545 0 1783820288 0.0031754435 -0.0102044512 -0.0222414285 1053 1311867753.7510209084 0.0190405082 0.0383295165 0.0701350048 0.0048643660 0.1875680000 260487463 0 1781424128 0.0013581258 -0.0119065624 -0.0229999460 1054 1311867753.7865459919 0.0173230153 0.0383095862 0.0701350048 0.0048635270 0.1841260000 260489581 0 1780408320 0.0017613266 -0.0109003093 -0.0238537025 1055 1311867753.8151860237 0.0153495632 0.0382878231 0.0701350048 0.0048639174 0.1869620000 260491451 0 1782149120 0.0023196517 -0.0098264478 -0.0259691197 1056 1311867753.8510670662 0.0161749497 0.0382668829 0.0701350048 0.0048629247 0.1895120000 260493817 0 1783767040 0.0006141816 -0.0121267270 -0.0254805740 1057 1311867753.8831698895 0.0171623956 0.0382469165 0.0701350048 0.0048624318 0.1926340000 260495383 0 1785290752 0.0004181033 -0.0132559352 -0.0232130215 1058 1311867753.9155960083 0.0160421915 0.0382259291 0.0701350048 0.0048609690 0.1937510000 260497673 0 1784446976 0.0007645730 -0.0109863747 -0.0233546868 1059 1311867753.9511620998 0.0150848888 0.0382040773 0.0701350048 0.0048592663 0.1946400000 260499503 0 1783648256 0.0012855567 -0.0093022957 -0.0232319422 1060 1311867753.9859020710 0.0151367383 0.0381823156 0.0701350048 0.0048601550 0.1923090000 260501605 0 1785171968 0.0001512193 -0.0129090454 -0.0233209319 1061 1311867754.0151760578 0.0136072384 0.0381591534 0.0701350048 0.0048584102 0.1915180000 260503379 0 1784193024 -0.0001089359 -0.0124037536 -0.0239155274 1062 1311867754.0510439873 0.0147123197 0.0381370754 0.0701350048 0.0048613435 0.1964220000 260505625 0 1783304192 -0.0022493033 -0.0108208219 -0.0235505532 1063 1311867754.0839149952 0.0149558373 0.0381152681 0.0701350048 0.0048598916 0.1967660000 260507671 0 1785081856 -0.0019598298 -0.0107184406 -0.0217813142 1064 1311867754.1166028976 0.0134123750 0.0380920511 0.0701350048 0.0048609735 0.1949020000 260509461 0 1783812096 -0.0028157316 -0.0121747423 -0.0236575902 1065 1311867754.1511039734 0.0128973657 0.0380683941 0.0701350048 0.0048648263 0.1947800000 260511299 0 1782906880 -0.0024710950 -0.0102895303 -0.0227556620 1066 1311867754.1832261086 0.0118445978 0.0380437939 0.0701350048 0.0048649712 0.1949480000 260513681 0 1784553472 -0.0025507445 -0.0089208679 -0.0231138170 1067 1311867754.2166349888 0.0124573866 0.0380198141 0.0701350048 0.0048650181 0.1995440000 260515359 0 1784066048 -0.0043663848 -0.0105628883 -0.0222598929 1068 1311867754.2522869110 0.0116818435 0.0379951531 0.0701350048 0.0048701670 0.1900080000 260517473 0 1783304192 -0.0050921682 -0.0113329664 -0.0224064142 1069 1311867754.2873370647 0.0103458827 0.0379692885 0.0701350048 0.0048770976 0.1959600000 260519735 0 1784791040 -0.0035970039 -0.0088598374 -0.0213817209 1070 1311867754.3188319206 0.0107462825 0.0379438464 0.0701350048 0.0048758779 0.1902170000 260521797 0 1783812096 -0.0055262148 -0.0093725529 -0.0207977686 1071 1311867754.3511719704 0.0102333678 0.0379179730 0.0701350048 0.0048750972 0.1911490000 260523571 0 1783033856 -0.0067844647 -0.0103356335 -0.0218879879 1072 1311867754.3868899345 0.0079000387 0.0378899712 0.0701350048 0.0048765827 0.1993570000 260525581 0 1784684544 -0.0055224635 -0.0107280351 -0.0223200135 1073 1311867754.4159760475 0.0070610754 0.0378612397 0.0701350048 0.0048748637 0.1944600000 260527611 0 1783279616 -0.0030889462 -0.0120929014 -0.0214257948 1074 1311867754.4545960426 0.0058354987 0.0378314206 0.0701350048 0.0048821819 0.1984720000 260529377 0 1782542336 -0.0029362529 -0.0118640512 -0.0208433308 1075 1311867754.4863700867 0.0068236343 0.0378025761 0.0701350048 0.0048918885 0.2223670000 260531631 0 1784430592 -0.0049033337 -0.0115946978 -0.0203604139 1076 1311867754.5164580345 0.0050743786 0.0377721596 0.0701350048 0.0048900952 0.1949000000 260533565 0 1783681024 -0.0027773355 -0.0109250396 -0.0212722067 1077 1311867754.5513699055 0.0056068087 0.0377422939 0.0701350048 0.0048886498 0.2045350000 260535667 0 1782542336 -0.0039007645 -0.0113443583 -0.0198402479 1078 1311867754.5835940838 0.0070834160 0.0377138534 0.0701350048 0.0048880864 0.1949110000 260537617 0 1784320000 -0.0032452287 -0.0126586389 -0.0180398412 1079 1311867754.6154909134 0.0055956729 0.0376840867 0.0701350048 0.0048859508 0.2083070000 260539371 0 1783681024 -0.0032793947 -0.0106564453 -0.0188703276 1080 1311867754.6510920525 0.0055689113 0.0376543505 0.0701350048 0.0048845593 0.1922110000 260541313 0 1782775808 -0.0025632514 -0.0113568734 -0.0183160529 1081 1311867754.6872758865 0.0052627646 0.0376243860 0.0701350048 0.0048833240 0.1979860000 260543551 0 1784430592 -0.0047315145 -0.0122505352 -0.0176111199 1082 1311867754.7162959576 0.0053577027 0.0375945647 0.0701350048 0.0048812186 0.2027460000 260545597 0 1783681024 -0.0052390695 -0.0111492174 -0.0168392546 1083 1311867754.7516000271 0.0039021235 0.0375634544 0.0701350048 0.0048791346 0.1954810000 260547507 0 1782906880 -0.0045432975 -0.0103288954 -0.0175778903 1084 1311867754.7865269184 0.0037078282 0.0375322223 0.0701350048 0.0048788515 0.1983880000 260549465 0 1784684544 -0.0053144912 -0.0131163411 -0.0167749114 1085 1311867754.8154470921 0.0029785312 0.0375003755 0.0701350048 0.0048781317 0.1963440000 260551343 0 1783828480 -0.0059688054 -0.0143672628 -0.0175903011 1086 1311867754.8510210514 0.0028538681 0.0374684727 0.0701350048 0.0048888232 0.2015060000 260553309 0 1782923264 -0.0056546559 -0.0114936959 -0.0168831982 1087 1311867754.8877389431 0.0029746669 0.0374367396 0.0701350048 0.0048866229 0.1998340000 260555515 0 1784684544 -0.0083344392 -0.0129276682 -0.0160218943 1088 1311867754.9201259613 0.0041297739 0.0374061266 0.0701350048 0.0048848738 0.1972460000 260557513 0 1784197120 -0.0104452157 -0.0148108583 -0.0155968387 1089 1311867754.9510319233 0.0024255484 0.0373740049 0.0701350048 0.0048826474 0.2016030000 260559399 0 1783160832 -0.0098305345 -0.0129749803 -0.0158135183 1090 1311867754.9837870598 0.0016228309 0.0373412056 0.0701350048 0.0048848448 0.1980110000 260561421 0 1784938496 -0.0090915924 -0.0138374511 -0.0164494365 1091 1311867755.0183880329 0.0057165935 0.0373122188 0.0701350048 0.0048842799 0.1985520000 260563555 0 1784066048 -0.0052285073 -0.0147867762 -0.0156578440 1092 1311867755.0540831089 0.0027349757 0.0372805547 0.0701350048 0.0048907554 0.2051060000 260565601 0 1783033856 -0.0089071915 -0.0130112860 -0.0145919994 1093 1311867755.0850980282 0.0023409496 0.0372485880 0.0701350048 0.0048910699 0.1985240000 260567591 0 1784664064 -0.0103107151 -0.0129749002 -0.0136541920 1094 1311867755.1156959534 0.0027199304 0.0372170261 0.0701350048 0.0048916693 0.2012860000 260569501 0 1783427072 -0.0103056272 -0.0134365475 -0.0136806406 1095 1311867755.1556220055 0.0028015308 0.0371855965 0.0701350048 0.0048897337 0.2042880000 260571547 0 1782272000 -0.0115273641 -0.0142705636 -0.0134648075 1096 1311867755.1847031116 0.0038336648 0.0371551659 0.0701350048 0.0048889778 0.2025480000 260573521 0 1784049664 -0.0115180453 -0.0158512685 -0.0141370930 1097 1311867755.2151238918 0.0034241455 0.0371244174 0.0701350048 0.0048867715 0.1977770000 260575303 0 1785544704 -0.0116196144 -0.0149299577 -0.0139755579 1098 1311867755.2512340546 0.0039895624 0.0370942400 0.0701350048 0.0048852274 0.2344930000 260577773 0 1784811520 -0.0123829246 -0.0159516912 -0.0136889331 1099 1311867755.2832889557 0.0029809591 0.0370631997 0.0701350048 0.0048838856 0.2037930000 260579291 0 1783431168 -0.0146876462 -0.0160141122 -0.0139977774 1100 1311867755.3192110062 0.0030430444 0.0370322723 0.0701350048 0.0048821367 0.2010150000 260581385 0 1785061376 -0.0129791647 -0.0154247526 -0.0148926768 1101 1311867755.3553090096 0.0033161454 0.0370016491 0.0701350048 0.0048807110 0.1966140000 260583695 0 1783812096 -0.0149584971 -0.0167668089 -0.0140019273 1102 1311867755.3900220394 0.0035424721 0.0369712869 0.0701350048 0.0048786921 0.2063360000 260585613 0 1783033856 -0.0154623678 -0.0179238971 -0.0148744024 1103 1311867755.4156589508 0.0035317733 0.0369409700 0.0701350048 0.0048770505 0.2003270000 260587467 0 1784811520 -0.0131190270 -0.0138204638 -0.0157173611 1104 1311867755.4549160004 0.0023574878 0.0369096444 0.0701350048 0.0048749117 0.1981260000 260589529 0 1785434112 -0.0157933682 -0.0167366248 -0.0150562115 1105 1311867755.4860870838 0.0023573623 0.0368783753 0.0701350048 0.0048727744 0.1996890000 260591455 0 1784430592 -0.0155372908 -0.0161293186 -0.0157164913 1106 1311867755.5161950588 0.0025875382 0.0368473710 0.0701350048 0.0048706633 0.2023850000 260593485 0 1783287808 -0.0153663773 -0.0152149564 -0.0148549117 1107 1311867755.5550999641 0.0039438205 0.0368176478 0.0701350048 0.0048690852 0.1957130000 260595259 0 1784938496 -0.0142705115 -0.0146705592 -0.0164400805 1108 1311867755.5854589939 0.0025833207 0.0367867504 0.0701350048 0.0048673031 0.1987740000 260597361 0 1783427072 -0.0158027466 -0.0147846984 -0.0157650691 1109 1311867755.6171119213 0.0048062457 0.0367579131 0.0701350048 0.0048651433 0.1988450000 260599287 0 1782652928 -0.0138509553 -0.0131954737 -0.0162780341 1110 1311867755.6542940140 0.0055544530 0.0367298019 0.0701350048 0.0048643475 0.2013160000 260601429 0 1784430592 -0.0135940444 -0.0159136336 -0.0166529827 1111 1311867755.6831719875 0.0038746903 0.0367002293 0.0701350048 0.0048627690 0.1961840000 260603195 0 1785036800 -0.0163945146 -0.0170625169 -0.0166249909 1112 1311867755.7182741165 0.0030102332 0.0366699326 0.0701350048 0.0048613183 0.2011890000 260605297 0 1784074240 -0.0167188942 -0.0159340855 -0.0165804736 1113 1311867755.7511448860 0.0027140784 0.0366394242 0.0701350048 0.0048596582 0.2047140000 260607215 0 1782923264 -0.0176239740 -0.0164644625 -0.0176186543 1114 1311867755.7863750458 0.0037385591 0.0366098902 0.0701350048 0.0048582156 0.2104300000 260609397 0 1784684544 -0.0174741484 -0.0176741499 -0.0183333121 1115 1311867755.8156878948 0.0026058634 0.0365793933 0.0701350048 0.0048562488 0.1993220000 260611243 0 1784049664 -0.0178953093 -0.0161512103 -0.0184844658 1116 1311867755.8554079533 0.0041396492 0.0365503254 0.0701350048 0.0048548501 0.2014820000 260613265 0 1783033856 -0.0165228453 -0.0141128898 -0.0187230501 1117 1311867755.8848359585 0.0029560719 0.0365202500 0.0701350048 0.0048528441 0.1966760000 260615391 0 1784811520 -0.0188840553 -0.0151682058 -0.0197592415 1118 1311867755.9156229496 0.0021558781 0.0364895126 0.0701350048 0.0048507181 0.2039240000 260617229 0 1783951360 -0.0189063810 -0.0158476345 -0.0174829233 1119 1311867755.9550359249 0.0034720080 0.0364600064 0.0701350048 0.0048486551 0.1988520000 260619203 0 1782882304 -0.0184290968 -0.0138523923 -0.0190496650 1120 1311867755.9855198860 0.0044310335 0.0364314091 0.0701350048 0.0048477774 0.1958730000 260621009 0 1784418304 -0.0171694160 -0.0142261712 -0.0185534842 1121 1311867756.0173881054 0.0041464255 0.0364026089 0.0701350048 0.0048457648 0.2248170000 260623127 0 1784037376 -0.0177820418 -0.0158926174 -0.0182624608 1122 1311867756.0554430485 0.0049918843 0.0363746136 0.0701350048 0.0048443480 0.1982010000 260625277 0 1783021568 -0.0176581647 -0.0128649510 -0.0194608923 1123 1311867756.0835959911 0.0041714152 0.0363459376 0.0701350048 0.0048426713 0.1988540000 260627187 0 1785217024 -0.0176935792 -0.0146133872 -0.0177624896 1124 1311867756.1196908951 0.0043279757 0.0363174519 0.0701350048 0.0048416750 0.2029390000 260629145 0 1784709120 -0.0183546934 -0.0165812429 -0.0187445171 1125 1311867756.1519339085 0.0053595440 0.0362899337 0.0701350048 0.0048396954 0.2061480000 260631263 0 1784037376 -0.0168788470 -0.0146778468 -0.0190830566 1126 1311867756.1836869717 0.0044119824 0.0362616229 0.0701350048 0.0048378710 0.1938060000 260633029 0 1785798656 -0.0176570863 -0.0143041685 -0.0184048284 1127 1311867756.2230648994 0.0045916932 0.0362335218 0.0701350048 0.0048406908 0.2054040000 260635179 0 1783693312 -0.0177658796 -0.0162334573 -0.0186654124 1128 1311867756.2552509308 0.0022968471 0.0362034361 0.0701350048 0.0048457683 0.2000800000 260636761 0 1783164928 -0.0197162498 -0.0147977676 -0.0177774876 1129 1311867756.2851591110 0.0041327709 0.0361750299 0.0701350048 0.0048472812 0.1956890000 260638823 0 1784799232 -0.0175243765 -0.0140391840 -0.0176917166 1130 1311867756.3200058937 0.0033766823 0.0361460048 0.0701350048 0.0048453619 0.1961020000 260641013 0 1784418304 -0.0188331287 -0.0162996314 -0.0175086129 1131 1311867756.3546419144 0.0031726563 0.0361168506 0.0701350048 0.0048432440 0.2011090000 260642907 0 1783930880 -0.0183571298 -0.0156113002 -0.0170565769 1132 1311867756.3843090534 0.0047213039 0.0360891160 0.0701350048 0.0048411887 0.2024300000 260644809 0 1785561088 -0.0168925691 -0.0150677655 -0.0179732125 1133 1311867756.4231688976 0.0051865214 0.0360618410 0.0701350048 0.0048393918 0.2070780000 260646711 0 1785053184 -0.0161013044 -0.0152056720 -0.0175810568 1134 1311867756.4510979652 0.0042099571 0.0360337529 0.0701350048 0.0048374865 0.2068140000 260648573 0 1784418304 -0.0169689059 -0.0156130586 -0.0168310665 1135 1311867756.4865350723 0.0053374250 0.0360067077 0.0701350048 0.0048405303 0.2006380000 260650635 0 1783808000 -0.0156520754 -0.0145154279 -0.0164914373 1136 1311867756.5264549255 0.0038167194 0.0359783715 0.0701350048 0.0048389104 0.2017670000 260652761 0 1783021568 -0.0170125011 -0.0159900747 -0.0163067691 1137 1311867756.5525779724 0.0058320230 0.0359518575 0.0701350048 0.0048378563 0.2040970000 260654695 0 1785053184 -0.0150016956 -0.0155975437 -0.0170801133 1138 1311867756.5897810459 0.0033711479 0.0359232277 0.0701350048 0.0048370444 0.2044260000 260656829 0 1784545280 -0.0171482805 -0.0155561417 -0.0156324990 1139 1311867756.6202929020 0.0026029730 0.0358939738 0.0701350048 0.0048354739 0.2033820000 260658795 0 1783656448 -0.0182894859 -0.0160535723 -0.0166458189 1140 1311867756.6518390179 0.0020246690 0.0358642639 0.0701350048 0.0048337301 0.1989310000 260660577 0 1785307136 -0.0187213775 -0.0160715729 -0.0160846245 1141 1311867756.6839349270 0.0033188837 0.0358357403 0.0701350048 0.0048319653 0.2045270000 260662575 0 1784799232 -0.0173626486 -0.0159231983 -0.0157133378 1142 1311867756.7217059135 0.0023100297 0.0358063833 0.0701350048 0.0048334422 0.2053000000 260664821 0 1784328192 -0.0186554808 -0.0162566155 -0.0150384614 1143 1311867756.7516939640 0.0031116714 0.0357777790 0.0701350048 0.0048322864 0.1980180000 260666427 0 1783783424 -0.0184668433 -0.0169922374 -0.0157727022 1144 1311867756.7872660160 0.0049129836 0.0357507993 0.0701350048 0.0048306732 0.2073310000 260668465 0 1783291904 -0.0166920349 -0.0153526925 -0.0171697177 1145 1311867756.8227219582 0.0042172461 0.0357232590 0.0701350048 0.0048288325 0.2046440000 260670679 0 1785053184 -0.0168578345 -0.0163235236 -0.0152734201 1146 1311867756.8542120457 0.0044252872 0.0356959484 0.0701350048 0.0048349780 0.1994630000 260672549 0 1784418304 -0.0178327058 -0.0180401560 -0.0154851014 1147 1311867756.8841960430 0.0035276024 0.0356679028 0.0701350048 0.0048433241 0.2051710000 260674707 0 1784180736 -0.0177060179 -0.0166260023 -0.0145142153 1148 1311867756.9223539829 0.0040054321 0.0356403222 0.0701350048 0.0048427520 0.2040800000 260676617 0 1785307136 -0.0192369595 -0.0188167840 -0.0149694663 1149 1311867756.9552440643 0.0043104170 0.0356130551 0.0701350048 0.0048406492 0.1987910000 260678687 0 1785053184 -0.0177269448 -0.0175294857 -0.0151713667 1150 1311867756.9841780663 0.0031814915 0.0355848538 0.0701350048 0.0048391088 0.2000840000 260680589 0 1784545280 -0.0185889099 -0.0166275501 -0.0146262590 1151 1311867757.0282740593 0.0054086591 0.0355586364 0.0701350048 0.0048422083 0.1974050000 260682555 0 1783783424 -0.0180732775 -0.0187623333 -0.0162599571 1152 1311867757.0552940369 0.0050475127 0.0355321511 0.0701350048 0.0048408991 0.1988840000 260684721 0 1783279616 -0.0181413479 -0.0189398862 -0.0155100385 1153 1311867757.0858569145 0.0062765228 0.0355067776 0.0701350048 0.0048388187 0.1990730000 260686719 0 1785069568 -0.0162256584 -0.0175589416 -0.0159442481 1154 1311867757.1283040047 0.0065409243 0.0354816772 0.0701350048 0.0048413011 0.2020150000 260688621 0 1784692736 -0.0176383629 -0.0216747187 -0.0150947161 1155 1311867757.1522068977 0.0051613213 0.0354554258 0.0701350048 0.0048444712 0.1963480000 260690483 0 1783771136 -0.0200269055 -0.0219325572 -0.0145996343 1156 1311867757.1851921082 0.0040952456 0.0354282976 0.0701350048 0.0048429818 0.2016450000 260692281 0 1785565184 -0.0182017852 -0.0197612159 -0.0147060407 1157 1311867757.2192370892 0.0047346572 0.0354017690 0.0701350048 0.0048417059 0.2002770000 260694495 0 1784782848 -0.0183947422 -0.0220218468 -0.0151405754 1158 1311867757.2523930073 0.0061548720 0.0353765126 0.0701350048 0.0048565239 0.1958460000 260696525 0 1784320000 -0.0171428192 -0.0231473055 -0.0166405439 1159 1311867757.2835690975 0.0058855433 0.0353510674 0.0701350048 0.0048554967 0.1961820000 260698491 0 1785962496 -0.0166344680 -0.0206016209 -0.0190584101 1160 1311867757.3233768940 0.0035111092 0.0353236191 0.0701350048 0.0048645841 0.2035210000 260700705 0 1785442304 -0.0176116172 -0.0213824809 -0.0173212234 1161 1311867757.3555359840 0.0045186342 0.0352970860 0.0701350048 0.0048625894 0.1994640000 260702519 0 1784307712 -0.0167063102 -0.0226394292 -0.0170873553 1162 1311867757.3833439350 0.0046090144 0.0352706763 0.0701350048 0.0048609262 0.2012970000 260704213 0 1783300096 -0.0158326998 -0.0199839417 -0.0178307313 1163 1311867757.4264349937 0.0043235891 0.0352440666 0.0701350048 0.0048599708 0.1939000000 260706371 0 1784573952 -0.0166245326 -0.0228224769 -0.0176158678 ================================================ FILE: icra2018_results/tegra/violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log ================================================ SLAMBench Report run started: 2018-02-18 06:58:45 Properties: ================= frame-limit: 0 log-file: output//violons_liborbslam2-original_rgbd_dataset_freiburg2_xyz.log input: datasets/TUM/freiburg2/rgbd_dataset_freiburg2_xyz.slam load-library: build/lib/liborbslam2-original-library.so dse: false help: false negative-focal-length: false realtime-mode: false realtime-multiplier: 1 file-output: Depth-intrinsics-parameters: 0.9075,1.212083,0.4825,0.52708 Depth-disparity-params: 0.001,0 Grey-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 RGB-intrinsics-parameters: 0.8139063,1.085417,0.5079687,0.5202 mode: auto settings: vocabulary: ./benchmarks/orbslam2/src/original/Vocabulary/ORBvoc.txt max-features: 1000 scale-levels: 8 scale-factor: 1.2 initial-fast-threshold: 20 second-fast-threshold: 7 camera-fps: 40 depth-threshold: 40 Statistics: ================= Frame Number Timestamp AbsoluteError MeanATE MaxATE RPE_RMSE Duration_Frame CPU_Memory GPU_Memory CUDA_Memory X Y Z 1 1311867170.4622900486 0.0582520440 0.0582520440 0.0582520440 nan 0.2025870000 232994048 0 1770569728 0.0000000000 0.0000000000 0.0000000000 2 1311867170.4941389561 0.0585756078 0.0584138259 0.0585756078 0.0034028764 0.2485680000 245650053 0 1770332160 -0.0037833005 -0.0009414774 -0.0018492915 3 1311867170.5264289379 0.0586280376 0.0584852298 0.0586280376 0.0026159889 0.1707880000 245579079 0 1772355584 -0.0067041628 -0.0009053058 -0.0039333063 4 1311867170.5623490810 0.0580519997 0.0583769223 0.0586280376 0.0037410649 0.1760540000 245584813 0 1774133248 -0.0078443661 -0.0005861038 -0.0060355649 5 1311867170.5942170620 0.0569400825 0.0580895543 0.0586280376 0.0045247200 0.1783270000 245590563 0 1775943680 -0.0106019322 -0.0027362446 -0.0084363036 6 1311867170.6260869503 0.0551154725 0.0575938740 0.0586280376 0.0044352901 0.1787690000 245595553 0 1777688576 -0.0094444454 -0.0038714861 -0.0113319103 7 1311867170.6621398926 0.0556503460 0.0573162272 0.0586280376 0.0041329494 0.1797820000 245599143 0 1779212288 -0.0115148863 -0.0041057542 -0.0124842860 8 1311867170.6942050457 0.0557987802 0.0571265463 0.0586280376 0.0038533002 0.1716910000 245602413 0 1781276672 -0.0117122177 -0.0034645684 -0.0142176896 9 1311867170.7263879776 0.0566393100 0.0570724089 0.0586280376 0.0036873131 0.1764790000 245606259 0 1783402496 -0.0149373086 -0.0052102045 -0.0146349268 10 1311867170.7620189190 0.0569225438 0.0570574224 0.0586280376 0.0035334542 0.1692800000 245611089 0 1784418304 -0.0180233605 -0.0073142066 -0.0159661341 11 1311867170.7941920757 0.0556345955 0.0569280745 0.0586280376 0.0037192422 0.1691150000 245615351 0 1783848960 -0.0187813304 -0.0093204537 -0.0190208256 12 1311867170.8262820244 0.0554144531 0.0568019394 0.0586280376 0.0037327077 0.1754470000 245619757 0 1779482624 -0.0190296154 -0.0125404121 -0.0211115703 13 1311867170.8622210026 0.0537745208 0.0565690610 0.0586280376 0.0039599583 0.1781130000 245623843 0 1776214016 -0.0180479512 -0.0146123292 -0.0249690209 14 1311867170.8943779469 0.0537642762 0.0563687193 0.0586280376 0.0038162331 0.1717330000 245627697 0 1776066560 -0.0180740319 -0.0165215451 -0.0278637968 15 1311867170.9263520241 0.0533844791 0.0561697699 0.0586280376 0.0038396594 0.1740780000 245632031 0 1777729536 -0.0189932398 -0.0195865873 -0.0310562793 16 1311867170.9621469975 0.0537181646 0.0560165446 0.0586280376 0.0037860931 0.1698830000 245635405 0 1779486720 -0.0208562482 -0.0206712913 -0.0340419859 17 1311867170.9942629337 0.0532430448 0.0558533975 0.0586280376 0.0036912124 0.1699390000 245640523 0 1781276672 -0.0205119327 -0.0211629272 -0.0378756672 18 1311867171.0262739658 0.0524694473 0.0556654003 0.0586280376 0.0036173519 0.1689490000 245646065 0 1782566912 -0.0206973143 -0.0255436413 -0.0403877273 19 1311867171.0623519421 0.0528631918 0.0555179156 0.0586280376 0.0043409314 0.1736280000 245650451 0 1784545280 -0.0228473246 -0.0273610782 -0.0431987941 20 1311867171.0942349434 0.0529033281 0.0553871863 0.0586280376 0.0044337013 0.2175470000 246101301 0 1784332288 -0.0206072778 -0.0261510015 -0.0456851944 21 1311867171.1262509823 0.0534034818 0.0552927241 0.0586280376 0.0043467862 0.2526040000 246454227 0 1783934976 -0.0215436425 -0.0281334110 -0.0469275601 22 1311867171.1622469425 0.0548955910 0.0552746726 0.0586280376 0.0047186689 0.3536440000 247151424 0 1785344000 -0.0223160461 -0.0278552379 -0.0476545058 23 1311867171.1942689419 0.0533635318 0.0551915796 0.0586280376 0.0056809159 0.2084850000 246422999 0 1784410112 -0.0176048949 -0.0264256783 -0.0493520498 24 1311867171.2262530327 0.0532327294 0.0551099608 0.0586280376 0.0057776981 0.1733950000 246425573 0 1784893440 -0.0145662557 -0.0281004515 -0.0506140552 25 1311867171.2622439861 0.0519217253 0.0549824314 0.0586280376 0.0056669731 0.1868800000 246428923 0 1783496704 -0.0096299639 -0.0262577981 -0.0532548502 26 1311867171.2943410873 0.0514647588 0.0548471363 0.0586280376 0.0055857640 0.1855930000 246432369 0 1781592064 -0.0066775009 -0.0263443571 -0.0540268533 27 1311867171.3263869286 0.0532566905 0.0547882309 0.0586280376 0.0059136040 0.1761090000 246436215 0 1783222272 -0.0075239688 -0.0265756547 -0.0537592098 28 1311867171.3622460365 0.0555086024 0.0548139584 0.0586280376 0.0058631719 0.1788230000 246439725 0 1785229312 -0.0076570068 -0.0229884014 -0.0534442030 29 1311867171.3941431046 0.0561696962 0.0548607080 0.0586280376 0.0058267872 0.1776770000 246442947 0 1783377920 -0.0092201363 -0.0222559776 -0.0543685071 30 1311867171.4262878895 0.0566066653 0.0549189066 0.0586280376 0.0057809835 0.1839330000 246445505 0 1780035584 -0.0117592309 -0.0255117193 -0.0550711267 31 1311867171.4622440338 0.0553963706 0.0549343087 0.0586280376 0.0057647761 0.1788430000 246447799 0 1774690304 -0.0109225772 -0.0243654437 -0.0587494858 32 1311867171.4944040775 0.0559186190 0.0549650684 0.0586280376 0.0057005443 0.1913760000 246449997 0 1776340992 -0.0109594921 -0.0233803745 -0.0603378080 33 1311867171.5261778831 0.0571522266 0.0550313459 0.0586280376 0.0056439578 0.1774040000 246454819 0 1777901568 -0.0134036699 -0.0237774625 -0.0606794544 34 1311867171.5622971058 0.0554901399 0.0550448398 0.0586280376 0.0056601755 0.1759620000 246462273 0 1779658752 -0.0132451952 -0.0224640891 -0.0637308359 35 1311867171.5942931175 0.0546066463 0.0550323200 0.0586280376 0.0056165127 0.1895330000 246464567 0 1781030912 -0.0121628195 -0.0234008320 -0.0646147206 36 1311867171.6263399124 0.0551943332 0.0550368204 0.0586280376 0.0055484718 0.1755100000 246466733 0 1782714368 -0.0157808568 -0.0243621804 -0.0648983195 37 1311867171.6622560024 0.0552971661 0.0550438567 0.0586280376 0.0054730007 0.1808600000 246469531 0 1784459264 -0.0169452149 -0.0234639794 -0.0659312382 38 1311867171.6943440437 0.0562303476 0.0550750802 0.0586280376 0.0055141470 0.1870180000 246471321 0 1783230464 -0.0200525951 -0.0230515804 -0.0660694987 39 1311867171.7262439728 0.0556562692 0.0550899825 0.0586280376 0.0054474518 0.1828860000 246474127 0 1779027968 -0.0229418110 -0.0238462556 -0.0672707260 40 1311867171.7621190548 0.0549087077 0.0550854506 0.0586280376 0.0053888581 0.1843810000 246476317 0 1777618944 -0.0233637597 -0.0251905192 -0.0680516586 41 1311867171.7941710949 0.0544141568 0.0550690776 0.0586280376 0.0053967183 0.1805810000 246478739 0 1779154944 -0.0236764662 -0.0255346894 -0.0689816102 42 1311867171.8262550831 0.0540433638 0.0550446558 0.0586280376 0.0053421069 0.1847590000 246481001 0 1781055488 -0.0253156163 -0.0249792021 -0.0710001141 43 1311867171.8623590469 0.0546001345 0.0550343181 0.0586280376 0.0052803308 0.1776970000 246483431 0 1782554624 -0.0302091148 -0.0262269136 -0.0712316707 44 1311867171.8944430351 0.0557282642 0.0550500896 0.0586280376 0.0054309886 0.1842960000 246486245 0 1784238080 -0.0333580039 -0.0238965787 -0.0719170123 45 1311867171.9262220860 0.0549921766 0.0550488027 0.0586280376 0.0054250231 0.1777720000 246488843 0 1783214080 -0.0367453545 -0.0244095717 -0.0729715824 46 1311867171.9624669552 0.0554217063 0.0550569093 0.0586280376 0.0054215143 0.2057820000 246920241 0 1782472704 -0.0396532789 -0.0234319158 -0.0727892220 47 1311867171.9946711063 0.0551735945 0.0550593919 0.0586280376 0.0055748560 0.3784110000 247713258 0 1786077184 -0.0420710817 -0.0233590733 -0.0726775825 48 1311867172.0262680054 0.0548444390 0.0550549137 0.0586280376 0.0057435022 0.2679770000 246868145 0 1785495552 -0.0454854108 -0.0219399836 -0.0728913918 49 1311867172.0622880459 0.0544618666 0.0550428107 0.0586280376 0.0056950503 0.2216790000 246871087 0 1785876480 -0.0484050177 -0.0217344314 -0.0721128955 50 1311867172.0941960812 0.0535078831 0.0550121122 0.0586280376 0.0056758420 0.1838640000 246873805 0 1784733696 -0.0506041162 -0.0220451169 -0.0715805739 51 1311867172.1263689995 0.0529379696 0.0549714427 0.0586280376 0.0057043417 0.1829410000 246876731 0 1783861248 -0.0548783876 -0.0220741797 -0.0716369003 52 1311867172.1623349190 0.0527513213 0.0549287481 0.0586280376 0.0057076842 0.1748570000 246879657 0 1785241600 -0.0572079048 -0.0209627021 -0.0711759105 53 1311867172.1944270134 0.0525198206 0.0548832966 0.0586280376 0.0056615296 0.1827320000 246882463 0 1783877632 -0.0595315322 -0.0207283385 -0.0704895109 54 1311867172.2264409065 0.0535034910 0.0548577447 0.0586280376 0.0058917567 0.1743090000 246885525 0 1779630080 -0.0607535206 -0.0193407219 -0.0694360957 55 1311867172.2622280121 0.0523236021 0.0548116693 0.0586280376 0.0058680513 0.1782000000 246888003 0 1778118656 -0.0617696978 -0.0195032116 -0.0691064745 56 1311867172.2944829464 0.0525142252 0.0547706436 0.0586280376 0.0058150231 0.1750950000 246890345 0 1779908608 -0.0653780997 -0.0195525717 -0.0684276372 57 1311867172.3263380527 0.0527473874 0.0547351478 0.0586280376 0.0058440213 0.1843720000 246892775 0 1781157888 -0.0684990659 -0.0183389056 -0.0678609833 58 1311867172.3624010086 0.0521652400 0.0546908391 0.0586280376 0.0057953508 0.1764890000 246895197 0 1783181312 -0.0734932199 -0.0197010767 -0.0679473504 59 1311867172.3942890167 0.0517012738 0.0546401685 0.0586280376 0.0057821625 0.1773370000 246898019 0 1784578048 -0.0741510615 -0.0187201165 -0.0679332763 60 1311867172.4265220165 0.0507618338 0.0545755296 0.0586280376 0.0057968736 0.1714610000 246900681 0 1783480320 -0.0767173618 -0.0201525092 -0.0692118704 61 1311867172.4623498917 0.0516688749 0.0545278795 0.0586280376 0.0059707056 0.1710650000 246903279 0 1779265536 -0.0781722590 -0.0175140668 -0.0693155378 62 1311867172.4952669144 0.0500323400 0.0544553708 0.0586280376 0.0060893747 0.2059980000 247352457 0 1777479680 -0.0788313299 -0.0203332826 -0.0700736120 63 1311867172.5263059139 0.0513028614 0.0544053310 0.0586280376 0.0061115292 0.3886810000 247355191 0 1778057216 -0.0839097649 -0.0212858096 -0.0695138350 64 1311867172.5624930859 0.0510750227 0.0543532949 0.0586280376 0.0060790217 0.3039310000 248326788 0 1783296000 -0.0840506032 -0.0193380900 -0.0710711703 65 1311867172.5945439339 0.0510876328 0.0543030539 0.0586280376 0.0060493295 0.2539350000 247326547 0 1783721984 -0.0861191675 -0.0196335651 -0.0715266690 66 1311867172.6263699532 0.0511813350 0.0542557552 0.0586280376 0.0060434222 0.1737010000 247339177 0 1785180160 -0.0882097557 -0.0191553831 -0.0723977312 67 1311867172.6624419689 0.0512056574 0.0542102313 0.0586280376 0.0060019083 0.1834010000 247341695 0 1784438784 -0.0896706581 -0.0184447803 -0.0728504956 68 1311867172.6945450306 0.0508587658 0.0541609451 0.0586280376 0.0060496944 0.1877270000 247344141 0 1783676928 -0.0920985341 -0.0191867892 -0.0732024610 69 1311867172.7263929844 0.0513890386 0.0541207725 0.0586280376 0.0060806599 0.1877530000 247346579 0 1785286656 -0.0943135098 -0.0164972208 -0.0742228329 70 1311867172.7623739243 0.0510089099 0.0540763173 0.0586280376 0.0060524683 0.1899480000 247348817 0 1784946688 -0.0987854078 -0.0184399895 -0.0737757757 71 1311867172.7944509983 0.0515469052 0.0540406918 0.0586280376 0.0060228737 0.1889400000 247351271 0 1784655872 -0.1033625528 -0.0176863242 -0.0739854500 72 1311867172.8263089657 0.0515756011 0.0540064544 0.0586280376 0.0060212939 0.1814920000 247353917 0 1783545856 -0.1051982790 -0.0168774333 -0.0752503201 73 1311867172.8632309437 0.0515257902 0.0539724727 0.0586280376 0.0059811103 0.2094100000 247356507 0 1783169024 -0.1099607274 -0.0180659853 -0.0755982772 74 1311867172.8944649696 0.0517481081 0.0539424137 0.0586280376 0.0059407002 0.2103640000 247799785 0 1785036800 -0.1124479026 -0.0175828617 -0.0760307163 75 1311867172.9263219833 0.0508968532 0.0539018063 0.0586280376 0.0059076535 0.4041410000 247761855 0 1783267328 -0.1139005199 -0.0194041263 -0.0766962022 76 1311867172.9623310566 0.0508265719 0.0538613427 0.0586280376 0.0058695402 0.3069720000 249035952 0 1781555200 -0.1144607812 -0.0187005512 -0.0777585134 77 1311867172.9945271015 0.0508356728 0.0538220483 0.0586280376 0.0058368145 0.3045840000 247959542 0 1779163136 -0.1160269603 -0.0193781555 -0.0779648572 78 1311867173.0262629986 0.0496484675 0.0537685408 0.0586280376 0.0058009955 0.1924290000 247771845 0 1779695616 -0.1171382740 -0.0203844309 -0.0790741369 79 1311867173.0624630451 0.0496507362 0.0537164167 0.0586280376 0.0057650162 0.1946450000 247774419 0 1781383168 -0.1171277761 -0.0205174088 -0.0792224407 80 1311867173.0945179462 0.0507921353 0.0536798632 0.0586280376 0.0058040582 0.1892530000 247776537 0 1782870016 -0.1187797561 -0.0192638431 -0.0789611489 81 1311867173.1267819405 0.0507540293 0.0536437418 0.0586280376 0.0058147959 0.1927050000 247778871 0 1784647680 -0.1196611151 -0.0187848415 -0.0790835023 82 1311867173.1622309685 0.0513078421 0.0536152552 0.0586280376 0.0057990018 0.1980850000 247781133 0 1783754752 -0.1218292043 -0.0169036929 -0.0792749599 83 1311867173.1943008900 0.0502775162 0.0535750415 0.0586280376 0.0057728745 0.1873780000 247783715 0 1782870016 -0.1230522841 -0.0176526103 -0.0798096806 84 1311867173.2264449596 0.0498599224 0.0535308139 0.0586280376 0.0057654072 0.1865400000 247785961 0 1784684544 -0.1239513233 -0.0181081202 -0.0793817118 85 1311867173.2622020245 0.0502103716 0.0534917498 0.0586280376 0.0057760831 0.1898060000 247788735 0 1783922688 -0.1258977056 -0.0168473851 -0.0796569660 86 1311867173.2942678928 0.0501195826 0.0534525386 0.0586280376 0.0057506279 0.1896900000 247790989 0 1783123968 -0.1272154897 -0.0171712860 -0.0793541521 87 1311867173.3262879848 0.0494566746 0.0534066091 0.0586280376 0.0057314447 0.1836340000 247793227 0 1784938496 -0.1294081211 -0.0176111907 -0.0798088014 88 1311867173.3623280525 0.0501474850 0.0533695736 0.0586280376 0.0057003941 0.1863820000 247795681 0 1784012800 -0.1327836812 -0.0166515876 -0.0796901956 89 1311867173.3942871094 0.0497859456 0.0533293081 0.0586280376 0.0056786264 0.1859720000 247798295 0 1783255040 -0.1349947900 -0.0166674685 -0.0800056607 90 1311867173.4262790680 0.0497143194 0.0532891416 0.0586280376 0.0056578526 0.1825350000 247800437 0 1784901632 -0.1386088133 -0.0170132462 -0.0801359862 91 1311867173.4622900486 0.0493073203 0.0532453853 0.0586280376 0.0056794759 0.1820020000 247802971 0 1784049664 -0.1397305429 -0.0169286393 -0.0805348456 92 1311867173.4943389893 0.0496722311 0.0532065467 0.0586280376 0.0057411649 0.1854130000 247805049 0 1782874112 -0.1395365000 -0.0172166210 -0.0810242966 93 1311867173.5263900757 0.0495891944 0.0531676504 0.0586280376 0.0057114845 0.1841500000 247807415 0 1784647680 -0.1418304890 -0.0174015686 -0.0813012421 94 1311867173.5624370575 0.0501278155 0.0531353117 0.0586280376 0.0057068637 0.1853400000 247809469 0 1783885824 -0.1446186453 -0.0159054883 -0.0813143104 95 1311867173.5943109989 0.0496615693 0.0530987460 0.0586280376 0.0057113468 0.2195400000 247811667 0 1783021568 -0.1483907551 -0.0175404064 -0.0815519020 96 1311867173.6263959408 0.0486157984 0.0530520487 0.0586280376 0.0057251681 0.1829380000 247814273 0 1784807424 -0.1486187130 -0.0186079890 -0.0820970610 97 1311867173.6623299122 0.0491134301 0.0530114443 0.0586280376 0.0057106923 0.1859160000 247816287 0 1783922688 -0.1485273689 -0.0172598623 -0.0828869343 98 1311867173.6943540573 0.0494843014 0.0529754531 0.0586280376 0.0056852983 0.1833160000 247818525 0 1781751808 -0.1534638703 -0.0176613331 -0.0832416564 99 1311867173.7267971039 0.0495278537 0.0529406289 0.0586280376 0.0056583060 0.1873870000 247821115 0 1780609024 -0.1530290097 -0.0183727331 -0.0835391358 100 1311867173.7623970509 0.0490812734 0.0529020353 0.0586280376 0.0056453972 0.1810750000 247823105 0 1782763520 -0.1530361623 -0.0163621753 -0.0856925696 101 1311867173.7943561077 0.0485302806 0.0528587506 0.0586280376 0.0056535498 0.2119510000 248281191 0 1784414208 -0.1554481983 -0.0208061002 -0.0849819481 102 1311867173.8265669346 0.0488638356 0.0528195848 0.0586280376 0.0056372401 0.4150790000 248248693 0 1784352768 -0.1579136848 -0.0184290297 -0.0866638124 103 1311867173.8635799885 0.0494459979 0.0527868315 0.0586280376 0.0056251865 0.3875500000 248862838 0 1784193024 -0.1577826142 -0.0177716725 -0.0871579126 104 1311867173.8946080208 0.0487408973 0.0527479283 0.0586280376 0.0056284694 0.2394740000 249606852 0 1784655872 -0.1632564068 -0.0216154344 -0.0872423574 105 1311867173.9266970158 0.0491167679 0.0527133458 0.0586280376 0.0056226679 0.2279380000 248508386 0 1783570432 -0.1677669436 -0.0196170472 -0.0886662751 106 1311867173.9625461102 0.0500686690 0.0526883960 0.0586280376 0.0056491586 0.1824380000 248261325 0 1784332288 -0.1660653204 -0.0157847796 -0.0894891992 107 1311867173.9944310188 0.0487398840 0.0526514940 0.0586280376 0.0056576637 0.1902890000 248263539 0 1783484416 -0.1691415459 -0.0180700831 -0.0902754664 108 1311867174.0264260769 0.0482564904 0.0526107996 0.0586280376 0.0056411877 0.1995150000 248265665 0 1782214656 -0.1697869301 -0.0186409224 -0.0914781019 109 1311867174.0624630451 0.0490624420 0.0525782458 0.0586280376 0.0056383103 0.2010670000 248267959 0 1784229888 -0.1675219238 -0.0148851713 -0.0924899355 110 1311867174.0945188999 0.0486836173 0.0525428401 0.0586280376 0.0056658586 0.1944880000 248270365 0 1783230464 -0.1708836406 -0.0161065366 -0.0926914737 111 1311867174.1264541149 0.0491463616 0.0525122412 0.0586280376 0.0056701477 0.1921030000 248272451 0 1782087680 -0.1740324795 -0.0158852562 -0.0927034318 112 1311867174.1624329090 0.0492260419 0.0524829001 0.0586280376 0.0056503396 0.1872760000 248274745 0 1783087104 -0.1739884913 -0.0137570482 -0.0941591859 113 1311867174.1943979263 0.0486271083 0.0524487781 0.0586280376 0.0056450283 0.1875070000 248277143 0 1784713216 -0.1769266129 -0.0147659518 -0.0939408690 114 1311867174.2267580032 0.0474382564 0.0524048261 0.0586280376 0.0056256334 0.1922430000 248279349 0 1784135680 -0.1815170795 -0.0165339969 -0.0945648253 115 1311867174.2626769543 0.0482735112 0.0523689017 0.0586280376 0.0056232359 0.1895660000 248281931 0 1783361536 -0.1797109097 -0.0137662757 -0.0949818790 116 1311867174.2945280075 0.0484228954 0.0523348844 0.0586280376 0.0056615910 0.1846060000 248283993 0 1785102336 -0.1821258515 -0.0150541160 -0.0947839916 117 1311867174.3265740871 0.0487000644 0.0523038175 0.0586280376 0.0056394303 0.2221620000 248286151 0 1783615488 -0.1846597344 -0.0152668189 -0.0946383774 118 1311867174.3624329567 0.0489035100 0.0522750014 0.0586280376 0.0056174645 0.1851770000 248288237 0 1779421184 -0.1860474944 -0.0138094649 -0.0948390067 119 1311867174.3946359158 0.0491850413 0.0522490353 0.0586280376 0.0056088190 0.1818670000 248290563 0 1778020352 -0.1881584376 -0.0142428633 -0.0941951871 120 1311867174.4266788960 0.0485411622 0.0522181364 0.0586280376 0.0055901604 0.1901270000 248292969 0 1779658752 -0.1927638501 -0.0148685249 -0.0948317274 121 1311867174.4630160332 0.0484489128 0.0521869858 0.0586280376 0.0056253696 0.1848720000 248295127 0 1781325824 -0.1912981272 -0.0136628924 -0.0950751156 122 1311867174.4945669174 0.0495993346 0.0521657755 0.0586280376 0.0056133203 0.1852780000 248297373 0 1782841344 -0.1931449920 -0.0133365877 -0.0940258503 123 1311867174.5267519951 0.0477987416 0.0521302712 0.0586280376 0.0056023889 0.1857080000 248299531 0 1784967168 -0.1985495090 -0.0139272995 -0.0956647843 124 1311867174.5623500347 0.0492904894 0.0521073697 0.0586280376 0.0055896745 0.1839680000 248301825 0 1784270848 -0.1950016618 -0.0127222463 -0.0944482014 125 1311867174.5944879055 0.0504444726 0.0520940665 0.0586280376 0.0056166423 0.1951740000 248303943 0 1783250944 -0.2006174028 -0.0097204512 -0.0943245217 126 1311867174.6265459061 0.0497451983 0.0520754247 0.0586280376 0.0056234476 0.1843200000 248306133 0 1784721408 -0.2018747479 -0.0115217883 -0.0935506225 127 1311867174.6624910831 0.0493346229 0.0520538436 0.0586280376 0.0056014890 0.1852350000 248308083 0 1783361536 -0.2050223351 -0.0108614657 -0.0941024423 128 1311867174.6945910454 0.0506570861 0.0520429314 0.0586280376 0.0055898811 0.1868500000 248310561 0 1781710848 -0.2043065280 -0.0083417576 -0.0933657065 129 1311867174.7265629768 0.0509385429 0.0520343703 0.0586280376 0.0055986594 0.1852590000 248323071 0 1783832576 -0.2071818113 -0.0119159650 -0.0912682712 130 1311867174.7623760700 0.0491453819 0.0520121473 0.0586280376 0.0056093469 0.2237470000 248812141 0 1785253888 -0.2075992823 -0.0113036903 -0.0936470181 131 1311867174.7944738865 0.0489027351 0.0519884113 0.0586280376 0.0055935110 0.4325700000 248779715 0 1784242176 -0.2077887952 -0.0115569066 -0.0938109457 132 1311867174.8273398876 0.0488703102 0.0519647893 0.0586280376 0.0055724798 0.3781970000 248878377 0 1783607296 -0.2113999426 -0.0124587510 -0.0935889930 133 1311867174.8624229431 0.0493225232 0.0519449227 0.0586280376 0.0055543425 0.3310770000 250268118 0 1783025664 -0.2138186693 -0.0114892554 -0.0938171893 134 1311867174.8944199085 0.0505144335 0.0519342474 0.0586280376 0.0055351831 0.3513240000 249254988 0 1778274304 -0.2155679017 -0.0108681396 -0.0930059254 135 1311867174.9270179272 0.0504376441 0.0519231614 0.0586280376 0.0055184312 0.1889540000 248787979 0 1778085888 -0.2155381292 -0.0112699131 -0.0933404788 136 1311867174.9626429081 0.0498481952 0.0519079043 0.0586280376 0.0054984786 0.1965610000 248790001 0 1780252672 -0.2200345546 -0.0126933809 -0.0938277990 137 1311867174.9943349361 0.0510302857 0.0519014984 0.0586280376 0.0054999180 0.1957530000 248792111 0 1781874688 -0.2220495194 -0.0089030117 -0.0946387649 138 1311867175.0265510082 0.0511520170 0.0518960673 0.0586280376 0.0054812540 0.2261170000 248794333 0 1783042048 -0.2233400792 -0.0094033005 -0.0940600783 139 1311867175.0633120537 0.0506553166 0.0518871411 0.0586280376 0.0054665800 0.1938620000 248796835 0 1784922112 -0.2274716496 -0.0085184183 -0.0946985260 140 1311867175.0947189331 0.0514058992 0.0518837036 0.0586280376 0.0054661700 0.1932650000 248798665 0 1784332288 -0.2266687006 -0.0070852949 -0.0941506624 141 1311867175.1265308857 0.0503550358 0.0518728620 0.0586280376 0.0054524859 0.1999330000 248801487 0 1783062528 -0.2274318039 -0.0074714809 -0.0944958329 142 1311867175.1625180244 0.0503181033 0.0518619130 0.0586280376 0.0054673327 0.1932690000 248803245 0 1784803328 -0.2297797650 -0.0078908522 -0.0939538181 143 1311867175.1946399212 0.0514586233 0.0518590928 0.0586280376 0.0054502442 0.2028560000 248805187 0 1783443456 -0.2299408466 -0.0057391538 -0.0934251845 144 1311867175.2270050049 0.0513360314 0.0518554604 0.0586280376 0.0054997906 0.1898970000 248807433 0 1782935552 -0.2307929546 -0.0037282743 -0.0934985355 145 1311867175.2624669075 0.0513678417 0.0518520975 0.0586280376 0.0055779283 0.1994190000 248809967 0 1784332288 -0.2362094373 -0.0050212210 -0.0918086916 146 1311867175.2944509983 0.0515406393 0.0518499643 0.0586280376 0.0055645266 0.1884680000 248811861 0 1783336960 -0.2359364182 -0.0035208012 -0.0914044678 147 1311867175.3267059326 0.0506208949 0.0518416032 0.0586280376 0.0055473086 0.1879160000 248814155 0 1782296576 -0.2353077531 -0.0019929656 -0.0921148658 148 1311867175.3625650406 0.0504676960 0.0518323201 0.0586280376 0.0055452281 0.1868430000 248816481 0 1784057856 -0.2384663224 -0.0034960099 -0.0909519345 149 1311867175.3945989609 0.0517518893 0.0518317803 0.0586280376 0.0055288562 0.1891760000 248818535 0 1785556992 -0.2418979853 -0.0018997993 -0.0897068754 150 1311867175.4266059399 0.0506608449 0.0518239741 0.0586280376 0.0055120080 0.1880360000 248820709 0 1784422400 -0.2454646528 -0.0027709780 -0.0897809118 151 1311867175.4625999928 0.0511103198 0.0518192479 0.0586280376 0.0054974437 0.1894900000 248822875 0 1783443456 -0.2486427277 -0.0026889476 -0.0885742456 152 1311867175.4945731163 0.0503824055 0.0518097950 0.0586280376 0.0054796362 0.2005870000 248825265 0 1785057280 -0.2520626187 -0.0017495328 -0.0893632919 153 1311867175.5264270306 0.0527013876 0.0518156224 0.0586280376 0.0054957887 0.2297750000 249268087 0 1784459264 -0.2528672218 0.0007741787 -0.0882551968 154 1311867175.5625700951 0.0524981841 0.0518200546 0.0586280376 0.0055040827 0.4314560000 249258465 0 1783943168 -0.2543051839 0.0013197050 -0.0880239159 155 1311867175.5946640968 0.0522946231 0.0518231163 0.0586280376 0.0055227157 0.3879550000 249256463 0 1786101760 -0.2603023946 0.0000845948 -0.0876845941 156 1311867175.6264801025 0.0528782420 0.0518298799 0.0586280376 0.0055383219 0.3418390000 251020212 0 1784508416 -0.2618990839 0.0020392486 -0.0871989131 157 1311867175.6624929905 0.0526793301 0.0518352904 0.0586280376 0.0055687085 0.2501320000 250934434 0 1781886976 -0.2650371194 0.0029678415 -0.0877500102 158 1311867175.6947000027 0.0499469414 0.0518233389 0.0586280376 0.0056286610 0.2706460000 249821932 0 1780785152 -0.2677502036 -0.0017408789 -0.0884060413 159 1311867175.7273120880 0.0511074513 0.0518188364 0.0586280376 0.0056125736 0.2071480000 249268531 0 1780957184 -0.2672592700 0.0009014136 -0.0886876434 160 1311867175.7624969482 0.0507690236 0.0518122751 0.0586280376 0.0056007781 0.1894560000 249270593 0 1782714368 -0.2694999874 0.0009432980 -0.0892072842 161 1311867175.7948620319 0.0518381819 0.0518124360 0.0586280376 0.0056021149 0.1910640000 249272911 0 1784119296 -0.2736531198 0.0016227118 -0.0881640315 162 1311867175.8287971020 0.0510441624 0.0518076936 0.0586280376 0.0055919371 0.1923130000 249275133 0 1783242752 -0.2763848603 0.0014595492 -0.0892399475 163 1311867175.8625519276 0.0509223491 0.0518022620 0.0586280376 0.0055823207 0.1911430000 249276979 0 1782349824 -0.2793553472 0.0017938949 -0.0896957293 164 1311867175.8946080208 0.0517114662 0.0518017084 0.0586280376 0.0055778412 0.1915350000 249279145 0 1784111104 -0.2824952006 0.0026130928 -0.0896662325 165 1311867175.9282429218 0.0504114702 0.0517932827 0.0586280376 0.0055820052 0.1854320000 249281239 0 1785516032 -0.2847860754 0.0007083402 -0.0906202346 166 1311867175.9629371166 0.0511870123 0.0517896305 0.0586280376 0.0055720383 0.1928990000 249283637 0 1784496128 -0.2863660753 0.0036076168 -0.0915201455 167 1311867175.9983000755 0.0509878695 0.0517848295 0.0586280376 0.0055612716 0.1883070000 249285723 0 1783332864 -0.2893092632 0.0029714378 -0.0915265083 168 1311867176.0268509388 0.0516154654 0.0517838214 0.0586280376 0.0055513149 0.1837640000 249287713 0 1785016320 -0.2918242514 0.0009176801 -0.0907260925 169 1311867176.0627059937 0.0519098155 0.0517845669 0.0586280376 0.0056027854 0.1858300000 249290079 0 1783873536 -0.2936294973 0.0041917227 -0.0919858664 170 1311867176.0946600437 0.0517277345 0.0517842326 0.0586280376 0.0056600368 0.1899940000 249292237 0 1782747136 -0.2952304184 0.0038231188 -0.0928153992 171 1311867176.1268119812 0.0517020673 0.0517837521 0.0586280376 0.0056470142 0.1883620000 249294587 0 1784889344 -0.2980208397 0.0054237614 -0.0941044241 172 1311867176.1625900269 0.0531573184 0.0517917380 0.0586280376 0.0057498022 0.1896290000 249296721 0 1784012800 -0.2955016494 0.0044316775 -0.0932553113 173 1311867176.1946918964 0.0527092703 0.0517970416 0.0586280376 0.0057681425 0.1874900000 249298735 0 1783472128 -0.2941573560 0.0058375075 -0.0958466008 174 1311867176.2265360355 0.0519697815 0.0517980344 0.0586280376 0.0057647956 0.1849020000 249300709 0 1785155584 -0.2996939719 0.0060437163 -0.0958279669 175 1311867176.2625019550 0.0530359112 0.0518051080 0.0586280376 0.0057543473 0.1874860000 249303243 0 1784610816 -0.3026886284 0.0071564559 -0.0954869911 176 1311867176.2946109772 0.0543160848 0.0518193749 0.0586280376 0.0057495122 0.2211010000 249766757 0 1784127488 -0.3042136133 0.0128751863 -0.0970507264 177 1311867176.3266019821 0.0548797809 0.0518366653 0.0586280376 0.0057361514 0.4307180000 249736167 0 1785044992 -0.3059845865 0.0107654780 -0.0958314985 178 1311867176.3624560833 0.0538793094 0.0518481408 0.0586280376 0.0057207416 0.4033930000 249734833 0 1782693888 -0.3079482019 0.0117318258 -0.0979340002 179 1311867176.3952438831 0.0540974289 0.0518607067 0.0586280376 0.0057089463 0.3898180000 250601202 0 1785020416 -0.3079080880 0.0135893449 -0.0992842764 180 1311867176.4268360138 0.0551753156 0.0518791212 0.0586280376 0.0056947565 0.3059830000 251542708 0 1785012224 -0.3080552518 0.0154830115 -0.0994773805 181 1311867176.4629659653 0.0533186011 0.0518870741 0.0586280376 0.0058024817 0.3589880000 250463052 0 1781719040 -0.3089811206 0.0121736508 -0.1005079523 182 1311867176.4945809841 0.0525494814 0.0518907137 0.0586280376 0.0058057600 0.1913290000 249746681 0 1782239232 -0.3120179176 0.0139896143 -0.1030737013 183 1311867176.5266211033 0.0540482812 0.0519025037 0.0586280376 0.0058399988 0.2005530000 249748663 0 1783640064 -0.3148927391 0.0162294134 -0.1029720604 184 1311867176.5636389256 0.0536947958 0.0519122444 0.0586280376 0.0058399394 0.1948830000 249750685 0 1783169024 -0.3168477416 0.0139563410 -0.1031822562 185 1311867176.5946090221 0.0542852879 0.0519250717 0.0586280376 0.0058241208 0.1985930000 249753171 0 1782132736 -0.3172932565 0.0160128772 -0.1044175774 186 1311867176.6283841133 0.0545166098 0.0519390047 0.0586280376 0.0058174152 0.2091380000 249755009 0 1783513088 -0.3183615208 0.0164531991 -0.1053537503 187 1311867176.6625781059 0.0555776432 0.0519584626 0.0586280376 0.0058041175 0.1971720000 249757391 0 1785581568 -0.3208960891 0.0166290794 -0.1047808826 188 1311867176.6945180893 0.0541777797 0.0519702675 0.0586280376 0.0057902816 0.1942950000 249759405 0 1784819712 -0.3244815767 0.0174086932 -0.1068849713 189 1311867176.7265889645 0.0537571050 0.0519797217 0.0586280376 0.0057762082 0.1936110000 249761691 0 1783918592 -0.3264694214 0.0183036327 -0.1084875241 190 1311867176.7632329464 0.0556106865 0.0519988320 0.0586280376 0.0057687701 0.1882190000 249763577 0 1785692160 -0.3295449615 0.0196698476 -0.1073042974 191 1311867176.7947680950 0.0552002713 0.0520155935 0.0586280376 0.0057583357 0.2005160000 249765903 0 1784655872 -0.3292163014 0.0185566805 -0.1084778160 192 1311867176.8266770840 0.0558660254 0.0520356478 0.0586280376 0.0057456592 0.1906660000 249767941 0 1783504896 -0.3312968612 0.0191864874 -0.1086839586 193 1311867176.8627309799 0.0558942519 0.0520556406 0.0586280376 0.0057360203 0.1850020000 249769875 0 1785278464 -0.3341108561 0.0201489776 -0.1093694866 194 1311867176.8949549198 0.0562211648 0.0520771124 0.0586280376 0.0057227028 0.1966420000 249771809 0 1784311808 -0.3382461965 0.0204625707 -0.1089588925 195 1311867176.9268178940 0.0552781671 0.0520935280 0.0586280376 0.0057357496 0.1897290000 249774079 0 1783513088 -0.3394055068 0.0196074285 -0.1099821329 196 1311867176.9650609493 0.0561256260 0.0521140999 0.0586280376 0.0057438120 0.1880110000 249776357 0 1785196544 -0.3416672051 0.0220923740 -0.1105906218 197 1311867176.9947481155 0.0565403812 0.0521365684 0.0586280376 0.0057297771 0.1876740000 249778459 0 1784311808 -0.3443710506 0.0206148401 -0.1094498187 198 1311867177.0267279148 0.0558188111 0.0521551656 0.0586280376 0.0057172248 0.1880250000 249780473 0 1783517184 -0.3485709429 0.0213624183 -0.1104649231 199 1311867177.0626339912 0.0571619831 0.0521803255 0.0586280376 0.0057051816 0.1892650000 249782471 0 1785290752 -0.3484818339 0.0228770394 -0.1106745452 200 1311867177.0946850777 0.0568132214 0.0522034899 0.0586280376 0.0056918154 0.1892050000 249784541 0 1784422400 -0.3509187102 0.0218063816 -0.1105962247 201 1311867177.1266150475 0.0565541275 0.0522251349 0.0586280376 0.0056776290 0.1890390000 249786763 0 1783791616 -0.3533209860 0.0218638219 -0.1111421585 202 1311867177.1627299786 0.0561782792 0.0522447049 0.0586280376 0.0056644610 0.1876140000 249788929 0 1785438208 -0.3554299772 0.0222066119 -0.1120364368 203 1311867177.1946458817 0.0571163893 0.0522687034 0.0586280376 0.0056536175 0.2098450000 249791103 0 1784422400 -0.3566293716 0.0233198255 -0.1118678153 204 1311867177.2264730930 0.0570996962 0.0522923847 0.0586280376 0.0056416800 0.1855640000 249793085 0 1783156736 -0.3584577441 0.0221332200 -0.1120305806 205 1311867177.2638640404 0.0578553118 0.0523195209 0.0586280376 0.0056299078 0.2205930000 250257195 0 1785200640 -0.3606182933 0.0243947674 -0.1129162461 206 1311867177.2946178913 0.0569463074 0.0523419811 0.0586280376 0.0056341476 0.4167690000 250211345 0 1785077760 -0.3642888665 0.0230192132 -0.1128342897 207 1311867177.3276090622 0.0574636459 0.0523667234 0.0586280376 0.0056236959 0.4039770000 250213823 0 1784410112 -0.3648753166 0.0245496687 -0.1138065457 208 1311867177.3627710342 0.0575388782 0.0523915895 0.0586280376 0.0056122039 0.3740910000 250227145 0 1784061952 -0.3685978353 0.0258573480 -0.1140717119 209 1311867177.3946089745 0.0568598099 0.0524129686 0.0586280376 0.0056071563 0.2981580000 252188282 0 1783590912 -0.3688923717 0.0250778962 -0.1156193390 210 1311867177.4312860966 0.0578473955 0.0524388468 0.0586280376 0.0055992951 0.2218270000 252196788 0 1780563968 -0.3711802363 0.0269674007 -0.1156633645 211 1311867177.4626040459 0.0568838380 0.0524599131 0.0586280376 0.0055867451 0.3129010000 251108590 0 1777238016 -0.3737312853 0.0260686912 -0.1163473576 212 1311867177.4946429729 0.0581631251 0.0524868151 0.0586280376 0.0055749479 0.2220770000 250227213 0 1778384896 -0.3746925294 0.0271768756 -0.1158144176 213 1311867177.5276319981 0.0573924817 0.0525098463 0.0586280376 0.0055620911 0.1930110000 250229283 0 1780047872 -0.3776760399 0.0286258440 -0.1171509326 214 1311867177.5626399517 0.0587376095 0.0525389480 0.0587376095 0.0055577190 0.1830150000 250231265 0 1781792768 -0.3797827661 0.0281354040 -0.1158399731 215 1311867177.5947310925 0.0591986813 0.0525699235 0.0591986813 0.0055464286 0.1933050000 250233167 0 1783443456 -0.3814454675 0.0301378705 -0.1163922921 216 1311867177.6311450005 0.0587521531 0.0525985450 0.0591986813 0.0055355545 0.1944450000 250235437 0 1784877056 -0.3832904398 0.0308559760 -0.1176575869 217 1311867177.6624829769 0.0597340688 0.0526314276 0.0597340688 0.0055242011 0.1916570000 250237443 0 1784352768 -0.3831121922 0.0312551931 -0.1174681336 218 1311867177.6945610046 0.0604514889 0.0526672994 0.0604514889 0.0055262932 0.1898900000 250239497 0 1783595008 -0.3855416179 0.0326679274 -0.1170268282 219 1311867177.7305839062 0.0605865121 0.0527034602 0.0605865121 0.0055167862 0.1890840000 250241919 0 1785368576 -0.3857857883 0.0333846807 -0.1179870814 220 1311867177.7625379562 0.0598158464 0.0527357892 0.0605865121 0.0055058958 0.1862150000 250243861 0 1784500224 -0.3877356350 0.0326630808 -0.1185672581 221 1311867177.7945590019 0.0598349273 0.0527679120 0.0605865121 0.0054946620 0.1895090000 250245475 0 1783611392 -0.3881036043 0.0334806927 -0.1197676212 222 1311867177.8309149742 0.0602945685 0.0528018159 0.0605865121 0.0054885161 0.1866130000 250248049 0 1785368576 -0.3896087110 0.0343367606 -0.1203716993 223 1311867177.8625319004 0.0606156960 0.0528368557 0.0606156960 0.0054762471 0.2069010000 250249871 0 1784336384 -0.3901646733 0.0345203578 -0.1207374260 224 1311867177.8946919441 0.0612487309 0.0528744087 0.0612487309 0.0054722621 0.1872690000 250251653 0 1783463936 -0.3912083805 0.0353219137 -0.1207986921 225 1311867177.9317860603 0.0613444559 0.0529120534 0.0613444559 0.0054605245 0.1851350000 250253915 0 1785221120 -0.3921459019 0.0360152796 -0.1217479408 226 1311867177.9627909660 0.0608214810 0.0529470509 0.0613444559 0.0054621887 0.1873820000 250256153 0 1784713216 -0.3939405978 0.0366656557 -0.1233216375 227 1311867177.9947769642 0.0592343546 0.0529747482 0.0613444559 0.0054530164 0.1840560000 250257903 0 1784201216 -0.3948491812 0.0361795314 -0.1256651580 228 1311867178.0306100845 0.0597259104 0.0530043586 0.0613444559 0.0054411299 0.1883060000 250260333 0 1783824384 -0.3975113034 0.0358926207 -0.1251506805 229 1311867178.0634479523 0.0603299849 0.0530363482 0.0613444559 0.0054330109 0.1864740000 250262491 0 1783353344 -0.3982277215 0.0377592221 -0.1263040602 230 1311867178.0951139927 0.0605472624 0.0530690044 0.0613444559 0.0054220357 0.1857560000 250264169 0 1784999936 -0.3989559114 0.0371526331 -0.1263351738 231 1311867178.1307909489 0.0597085394 0.0530977469 0.0613444559 0.0054145926 0.1847920000 250266295 0 1784459264 -0.4018068612 0.0355131440 -0.1269170046 232 1311867178.1627469063 0.0621766485 0.0531368801 0.0621766485 0.0054454968 0.1857540000 250268517 0 1783226368 -0.4025987387 0.0386375301 -0.1267615706 233 1311867178.1950459480 0.0586513728 0.0531605475 0.0621766485 0.0054358108 0.2200490000 250686231 0 1783971840 -0.4061552584 0.0377361104 -0.1302958429 234 1311867178.2307190895 0.0610006005 0.0531940520 0.0621766485 0.0054276613 0.4104130000 250681805 0 1782054912 -0.4072741270 0.0372599289 -0.1287263483 235 1311867178.2628939152 0.0607780330 0.0532263243 0.0621766485 0.0054188876 0.3804300000 250679747 0 1784270848 -0.4101172686 0.0392990522 -0.1298796237 236 1311867178.2954900265 0.0609688722 0.0532591317 0.0621766485 0.0054087244 0.3581080000 250693509 0 1783820288 -0.4113450944 0.0384304263 -0.1296772510 237 1311867178.3306670189 0.0595854297 0.0532858249 0.0621766485 0.0054097231 0.2748400000 252831642 0 1782861824 -0.4131702185 0.0367120765 -0.1311625242 238 1311867178.3627231121 0.0604399033 0.0533158841 0.0621766485 0.0054054214 0.2430450000 252789816 0 1783242752 -0.4150944650 0.0393060222 -0.1317053437 239 1311867178.3949439526 0.0609609894 0.0533478719 0.0621766485 0.0053966374 0.3326040000 251693454 0 1780826112 -0.4154801667 0.0381374061 -0.1314831376 240 1311867178.4306581020 0.0605979338 0.0533780805 0.0621766485 0.0053912854 0.1924020000 250693353 0 1781645312 -0.4178090394 0.0404175892 -0.1331917048 241 1311867178.4628739357 0.0630411431 0.0534181762 0.0630411431 0.0053824699 0.1902880000 250695439 0 1783422976 -0.4200755656 0.0403559953 -0.1298702955 242 1311867178.4946439266 0.0615899637 0.0534519439 0.0630411431 0.0053745673 0.1940150000 250697573 0 1784926208 -0.4216955900 0.0396726727 -0.1311506182 243 1311867178.5306270123 0.0607226267 0.0534818644 0.0630411431 0.0053671001 0.2278800000 250699707 0 1784307712 -0.4238248467 0.0407868735 -0.1327547133 244 1311867178.5626420975 0.0611695200 0.0535133712 0.0630411431 0.0053565746 0.1917260000 250701689 0 1783881728 -0.4268932343 0.0409324467 -0.1316505373 245 1311867178.5947000980 0.0612692088 0.0535450277 0.0630411431 0.0053507117 0.1874910000 250703991 0 1785581568 -0.4275736809 0.0407923721 -0.1320307851 246 1311867178.6306900978 0.0630411357 0.0535836298 0.0630411431 0.0053404392 0.1897770000 250706021 0 1784639488 -0.4264172316 0.0421438627 -0.1323308349 247 1311867178.6626410484 0.0634828731 0.0536237077 0.0634828731 0.0053417621 0.1912310000 250708259 0 1783918592 -0.4292642474 0.0418226197 -0.1305517554 248 1311867178.6946120262 0.0621345006 0.0536580254 0.0634828731 0.0053357818 0.1842720000 250710233 0 1785565184 -0.4312795401 0.0421810672 -0.1324959099 249 1311867178.7307450771 0.0625087172 0.0536935703 0.0634828731 0.0053293135 0.1997800000 250712175 0 1784791040 -0.4315610528 0.0435987078 -0.1334796846 250 1311867178.7632350922 0.0618968122 0.0537263833 0.0634828731 0.0053207961 0.1874340000 250714477 0 1784012800 -0.4338278770 0.0422522053 -0.1330252737 251 1311867178.8006799221 0.0633513480 0.0537647298 0.0634828731 0.0053111831 0.1836620000 250716275 0 1785692160 -0.4332374930 0.0427407660 -0.1326189041 252 1311867178.8309500217 0.0647061020 0.0538081479 0.0647061020 0.0053074463 0.1887040000 250718249 0 1784807424 -0.4337603450 0.0454881489 -0.1325982809 253 1311867178.8627939224 0.0648594201 0.0538518288 0.0648594201 0.0053007513 0.1978820000 250720175 0 1784012800 -0.4359388351 0.0431207903 -0.1305130273 254 1311867178.8952279091 0.0638660789 0.0538912550 0.0648594201 0.0052940552 0.1839580000 250722357 0 1785806848 -0.4353522062 0.0413979962 -0.1321342587 255 1311867178.9306209087 0.0654847026 0.0539367195 0.0654847026 0.0052896050 0.1820560000 250724603 0 1784901632 -0.4336828887 0.0431413874 -0.1332442164 256 1311867178.9627609253 0.0652707592 0.0539809931 0.0654847026 0.0052881408 0.1872050000 250726825 0 1784029184 -0.4385049641 0.0443876088 -0.1325224042 257 1311867178.9946830273 0.0630884618 0.0540164307 0.0654847026 0.0052806214 0.1888370000 250749135 0 1785331712 -0.4405048490 0.0435080118 -0.1348380297 258 1311867179.0309159756 0.0637745634 0.0540542530 0.0654847026 0.0052846805 0.1848390000 250793133 0 1784905728 -0.4423057139 0.0459841788 -0.1356371939 259 1311867179.0628120899 0.0635534227 0.0540909293 0.0654847026 0.0052839541 0.1910980000 250795515 0 1784033280 -0.4432584941 0.0434603542 -0.1353345215 260 1311867179.0968201160 0.0651289150 0.0541333831 0.0654847026 0.0052782095 0.1844230000 250797449 0 1785810944 -0.4437907636 0.0433285311 -0.1350242496 261 1311867179.1310369968 0.0671026409 0.0541830737 0.0671026409 0.0052712345 0.1770880000 250799655 0 1785290752 -0.4427206814 0.0447561443 -0.1355327666 262 1311867179.1627540588 0.0660614818 0.0542284112 0.0671026409 0.0053044449 0.1890870000 250801637 0 1783771136 -0.4457545280 0.0417118408 -0.1365131140 263 1311867179.1957008839 0.0659241527 0.0542728817 0.0671026409 0.0053002407 0.1880250000 250803619 0 1782419456 -0.4485364854 0.0444883183 -0.1386959553 264 1311867179.2307469845 0.0636950806 0.0543085718 0.0671026409 0.0052909101 0.1868760000 250805881 0 1784164352 -0.4505166709 0.0443864055 -0.1424697191 265 1311867179.2634611130 0.0638891831 0.0543447251 0.0671026409 0.0052901982 0.1935860000 250807855 0 1783291904 -0.4530666173 0.0428541079 -0.1417191774 266 1311867179.2959330082 0.0637937188 0.0543802476 0.0671026409 0.0052852126 0.1861230000 250810029 0 1780228096 -0.4514831901 0.0435005464 -0.1443408281 267 1311867179.3307149410 0.0677284598 0.0544302409 0.0677284598 0.0052896235 0.2609810000 251217099 0 1779224576 -0.4518681467 0.0466627069 -0.1422708333 268 1311867179.3629300594 0.0657632053 0.0544725281 0.0677284598 0.0052819708 0.4380470000 251221449 0 1779326976 -0.4535212219 0.0455613732 -0.1440739334 269 1311867179.3948490620 0.0648891255 0.0545112515 0.0677284598 0.0052735560 0.3850570000 251224087 0 1781174272 -0.4550570250 0.0438863300 -0.1441847980 270 1311867179.4308040142 0.0636921450 0.0545452548 0.0677284598 0.0052688495 0.3804960000 251390485 0 1783054336 -0.4554972947 0.0469343737 -0.1479279101 271 1311867179.4637460709 0.0625441745 0.0545747711 0.0677284598 0.0052731586 0.3550700000 253565350 0 1785786368 -0.4584140778 0.0460433252 -0.1473443508 272 1311867179.4949469566 0.0647717193 0.0546122599 0.0677284598 0.0052642525 0.2540930000 253416796 0 1784811520 -0.4570661485 0.0466849729 -0.1461539716 273 1311867179.5307800770 0.0663069338 0.0546550975 0.0677284598 0.0052634694 0.3936710000 252323284 0 1785094144 -0.4570819139 0.0481613800 -0.1455567479 274 1311867179.5627610683 0.0644495934 0.0546908439 0.0677284598 0.0052846712 0.1811090000 251233149 0 1785962496 -0.4592097104 0.0461966805 -0.1459399015 275 1311867179.5946741104 0.0664672479 0.0547336671 0.0677284598 0.0052853903 0.1953130000 251234963 0 1784819712 -0.4603108168 0.0498001277 -0.1449649930 276 1311867179.6306900978 0.0654123574 0.0547723581 0.0677284598 0.0052913040 0.1942180000 251237417 0 1783459840 -0.4607054889 0.0490634330 -0.1459366977 277 1311867179.6625750065 0.0657483861 0.0548119827 0.0677284598 0.0052845286 0.1919910000 251239303 0 1785339904 -0.4627332985 0.0479813069 -0.1440542936 278 1311867179.6946051121 0.0656869188 0.0548511012 0.0677284598 0.0053019169 0.1889240000 251241381 0 1784459264 -0.4625411630 0.0503367744 -0.1458176672 279 1311867179.7309470177 0.0668064803 0.0548939520 0.0677284598 0.0052941198 0.1913910000 251243715 0 1783582720 -0.4633455575 0.0502460673 -0.1440532207 280 1311867179.7627270222 0.0647027194 0.0549289833 0.0677284598 0.0053327726 0.1886680000 251245825 0 1784840192 -0.4635435641 0.0486238189 -0.1458333135 281 1311867179.7948911190 0.0650282875 0.0549649239 0.0677284598 0.0053547010 0.1895250000 251247575 0 1784094720 -0.4648597240 0.0527910776 -0.1469306499 282 1311867179.8307530880 0.0647681653 0.0549996872 0.0677284598 0.0053467576 0.1977350000 251249709 0 1783222272 -0.4650999904 0.0515380874 -0.1464349926 283 1311867179.8627979755 0.0648817345 0.0550346061 0.0677284598 0.0053388012 0.1881900000 251251931 0 1784729600 -0.4660047889 0.0508623123 -0.1456553936 284 1311867179.8948040009 0.0660251677 0.0550733052 0.0677284598 0.0053322830 0.1924170000 251253913 0 1783709696 -0.4659898877 0.0520534031 -0.1451381445 285 1311867179.9309051037 0.0674114674 0.0551165970 0.0677284598 0.0053599996 0.1875380000 251255975 0 1782419456 -0.4670655727 0.0534228608 -0.1437723190 286 1311867179.9635379314 0.0680897310 0.0551619576 0.0680897310 0.0053534475 0.2227550000 251257853 0 1784594432 -0.4679059684 0.0515145175 -0.1414269209 287 1311867179.9958879948 0.0666933730 0.0552021368 0.0680897310 0.0053445223 0.1874490000 251259891 0 1783431168 -0.4682132900 0.0533186272 -0.1439699680 288 1311867180.0309770107 0.0665397793 0.0552415036 0.0680897310 0.0053354629 0.1901430000 251261985 0 1782927360 -0.4688168466 0.0539828166 -0.1436880529 289 1311867180.0626471043 0.0659359321 0.0552785085 0.0680897310 0.0053272419 0.1874040000 251263943 0 1784991744 -0.4687410891 0.0530338734 -0.1439168900 290 1311867180.0947730541 0.0658061951 0.0553148109 0.0680897310 0.0053190137 0.1877090000 251266021 0 1784193024 -0.4697014987 0.0544801801 -0.1439791769 291 1311867180.1307730675 0.0692697018 0.0553627658 0.0692697018 0.0053114840 0.1848780000 251268091 0 1782325248 -0.4686717391 0.0541316867 -0.1397625655 292 1311867180.1636900902 0.0688603818 0.0554089906 0.0692697018 0.0053242554 0.1899900000 251270137 0 1781669888 -0.4675735533 0.0550506338 -0.1408330202 293 1311867180.1949090958 0.0671100765 0.0554489260 0.0692697018 0.0053162204 0.1840420000 251272055 0 1783336960 -0.4675259888 0.0545733906 -0.1427467465 294 1311867180.2308139801 0.0662549064 0.0554856810 0.0692697018 0.0053153691 0.1839720000 251274053 0 1785118720 -0.4660195112 0.0537806153 -0.1443993598 295 1311867180.2637619972 0.0654220805 0.0555193638 0.0692697018 0.0053329773 0.1875820000 251276211 0 1784573952 -0.4658032656 0.0533644184 -0.1454945803 296 1311867180.2947549820 0.0648630708 0.0555509303 0.0692697018 0.0053245378 0.1902990000 251278033 0 1784193024 -0.4671868384 0.0538785495 -0.1456031203 297 1311867180.3308670521 0.0666965991 0.0555884578 0.0692697018 0.0053169477 0.1920910000 251280159 0 1785372672 -0.4656931758 0.0548003837 -0.1445657015 298 1311867180.3658289909 0.0670840070 0.0556270335 0.0692697018 0.0053095414 0.2003760000 251282533 0 1785208832 -0.4639205039 0.0544331633 -0.1448637098 299 1311867180.3964109421 0.0663502961 0.0556628973 0.0692697018 0.0053012685 0.1899070000 251284331 0 1784213504 -0.4634409547 0.0539534017 -0.1456532031 300 1311867180.4309151173 0.0648982152 0.0556936816 0.0692697018 0.0052926282 0.1908500000 251286489 0 1783848960 -0.4632314444 0.0532358587 -0.1470620036 301 1311867180.4670670033 0.0656335950 0.0557267046 0.0692697018 0.0052867604 0.1918570000 251288423 0 1783435264 -0.4620743096 0.0542129949 -0.1468463242 302 1311867180.4947559834 0.0673263073 0.0557651139 0.0692697018 0.0052968231 0.1886070000 251290349 0 1784610816 -0.4603288472 0.0537541024 -0.1454568207 303 1311867180.5308880806 0.0658667833 0.0557984527 0.0692697018 0.0052884929 0.1898850000 251292419 0 1784446976 -0.4602434933 0.0539618991 -0.1466107517 304 1311867180.5629510880 0.0650801361 0.0558289846 0.0692697018 0.0052813197 0.1953590000 251294569 0 1783943168 -0.4592800736 0.0533307381 -0.1469797343 305 1311867180.5946910381 0.0653860345 0.0558603192 0.0692697018 0.0052734821 0.1867580000 251296671 0 1785245696 -0.4573093653 0.0535488874 -0.1469268203 306 1311867180.6308128834 0.0667003468 0.0558957441 0.0692697018 0.0052651722 0.1886200000 251298805 0 1784700928 -0.4558888376 0.0533386171 -0.1451325715 307 1311867180.6640911102 0.0654194802 0.0559267661 0.0692697018 0.0052875530 0.1906530000 251300723 0 1784209408 -0.4545609951 0.0528389700 -0.1459328085 308 1311867180.6957859993 0.0654432550 0.0559576637 0.0692697018 0.0052801734 0.1890090000 251302593 0 1785622528 -0.4553485811 0.0528411493 -0.1446171999 309 1311867180.7309739590 0.0670031235 0.0559934096 0.0692697018 0.0052761179 0.1810860000 251304567 0 1784963072 -0.4527628720 0.0543287471 -0.1437436044 310 1311867180.7650830746 0.0655265376 0.0560241616 0.0692697018 0.0052873921 0.2195470000 251306773 0 1783848960 -0.4533823431 0.0530750193 -0.1444610357 311 1311867180.7949280739 0.0654082224 0.0560543354 0.0692697018 0.0052857060 0.1872430000 251308523 0 1785626624 -0.4521056712 0.0543478876 -0.1455630660 312 1311867180.8309240341 0.0653365552 0.0560840861 0.0692697018 0.0052774451 0.2002680000 251310745 0 1784991744 -0.4524796307 0.0539826527 -0.1445660442 313 1311867180.8652698994 0.0645678714 0.0561111909 0.0692697018 0.0052748382 0.1930090000 251312567 0 1784340480 -0.4510163963 0.0532760248 -0.1449926645 314 1311867180.8966469765 0.0650508851 0.0561396612 0.0692697018 0.0052686671 0.1820580000 251314765 0 1785753600 -0.4494382441 0.0535431206 -0.1445480883 315 1311867180.9306049347 0.0657560378 0.0561701894 0.0692697018 0.0052795182 0.1932990000 251316891 0 1784954880 -0.4488596618 0.0541925281 -0.1440307796 316 1311867180.9631829262 0.0640349463 0.0561950779 0.0692697018 0.0052747686 0.1949050000 251318865 0 1784197120 -0.4477539659 0.0538251325 -0.1458274424 317 1311867180.9948179722 0.0641228333 0.0562200866 0.0692697018 0.0052672359 0.1911860000 251320511 0 1783435264 -0.4472926259 0.0546481535 -0.1453846097 318 1311867181.0308310986 0.0639012232 0.0562442411 0.0692697018 0.0052624093 0.1947450000 251322765 0 1782943744 -0.4453570247 0.0528587811 -0.1450971365 319 1311867181.0627830029 0.0640321672 0.0562686547 0.0692697018 0.0052610981 0.2011790000 251324747 0 1784700928 -0.4437679946 0.0527315140 -0.1446957141 320 1311867181.0948719978 0.0663883761 0.0563002788 0.0692697018 0.0052599029 0.1921400000 251326905 0 1784086528 -0.4389361739 0.0542811602 -0.1434195638 321 1311867181.1311910152 0.0649209842 0.0563271346 0.0692697018 0.0052531140 0.1919000000 251328687 0 1783054336 -0.4384934306 0.0538145304 -0.1435041726 322 1311867181.1629528999 0.0648557693 0.0563536210 0.0692697018 0.0052561851 0.1897600000 251330733 0 1784848384 -0.4357840419 0.0533271804 -0.1441321671 323 1311867181.1972830296 0.0634290203 0.0563755263 0.0692697018 0.0052492820 0.1930280000 251332899 0 1783959552 -0.4342553616 0.0522955507 -0.1449040771 324 1311867181.2342460155 0.0615813211 0.0563915935 0.0692697018 0.0052471449 0.1945450000 251335121 0 1782816768 -0.4325769544 0.0509347655 -0.1465851218 325 1311867181.2629361153 0.0650105923 0.0564181135 0.0692697018 0.0052482856 0.1904540000 251337031 0 1784610816 -0.4297801256 0.0532502756 -0.1440451443 326 1311867181.2948091030 0.0640475154 0.0564415166 0.0692697018 0.0052415741 0.1894700000 251338781 0 1783812096 -0.4280731082 0.0529326424 -0.1450285017 327 1311867181.3317139149 0.0634306595 0.0564628901 0.0692697018 0.0052419507 0.1951070000 251340883 0 1783181312 -0.4259310961 0.0514655150 -0.1450641751 328 1311867181.3626708984 0.0644294918 0.0564871786 0.0692697018 0.0052463280 0.1909990000 251342881 0 1784971264 -0.4249260426 0.0538477786 -0.1445536464 329 1311867181.3948218822 0.0620370544 0.0565040475 0.0692697018 0.0052435330 0.1912040000 251344855 0 1784197120 -0.4253082871 0.0510282107 -0.1449427009 330 1311867181.4308950901 0.0618164986 0.0565201458 0.0692697018 0.0052410680 0.1950020000 251346645 0 1783308288 -0.4224405289 0.0518563241 -0.1460091621 331 1311867181.4628310204 0.0637792647 0.0565420767 0.0692697018 0.0052339104 0.1902600000 251348835 0 1785081856 -0.4204593897 0.0522672907 -0.1435739994 332 1311867181.4963610172 0.0621379316 0.0565589317 0.0692697018 0.0052507163 0.1920210000 251350865 0 1784614912 -0.4176816344 0.0515201725 -0.1446043849 333 1311867181.5359110832 0.0618496984 0.0565748199 0.0692697018 0.0052489992 0.1854920000 251352807 0 1781825536 -0.4167061746 0.0499894433 -0.1437765658 334 1311867181.5671720505 0.0630184412 0.0565941121 0.0692697018 0.0052415720 0.2183540000 251354621 0 1780535296 -0.4141652584 0.0502831154 -0.1431151032 335 1311867181.5948610306 0.0620457083 0.0566103856 0.0692697018 0.0052338251 0.1835590000 251356643 0 1782169600 -0.4121720791 0.0515085869 -0.1453644633 336 1311867181.6313591003 0.0623027496 0.0566273271 0.0692697018 0.0052271175 0.1922500000 251358673 0 1783795712 -0.4117271006 0.0496998429 -0.1439827383 337 1311867181.6628570557 0.0616882704 0.0566423448 0.0692697018 0.0052204052 0.1941740000 251360887 0 1785446400 -0.4090712070 0.0481028929 -0.1450683326 338 1311867181.6949229240 0.0621153042 0.0566585369 0.0692697018 0.0052170323 0.2024610000 251362605 0 1784455168 -0.4074150324 0.0496337377 -0.1459989548 339 1311867181.7310829163 0.0617718324 0.0566736204 0.0692697018 0.0052386356 0.1936920000 251364787 0 1783963648 -0.4064444602 0.0472296737 -0.1455216408 340 1311867181.7634840012 0.0623966157 0.0566904528 0.0692697018 0.0052352201 0.1943010000 251366865 0 1785835520 -0.4049458802 0.0482700281 -0.1457046568 341 1311867181.7948980331 0.0622749999 0.0567068297 0.0692697018 0.0052368956 0.1881540000 251368639 0 1784348672 -0.4035328329 0.0485261828 -0.1459862143 342 1311867181.8308010101 0.0620267279 0.0567223850 0.0692697018 0.0052338615 0.1951760000 251370581 0 1782951936 -0.4017201066 0.0475534387 -0.1459519863 343 1311867181.8627979755 0.0620613508 0.0567379505 0.0692697018 0.0052335630 0.2003150000 251372779 0 1784692736 -0.3983276784 0.0464367755 -0.1466246545 344 1311867181.8949289322 0.0628761575 0.0567557941 0.0692697018 0.0052272375 0.2069990000 251374737 0 1783582720 -0.3964258730 0.0465910994 -0.1453347504 345 1311867181.9307990074 0.0609237216 0.0567678751 0.0692697018 0.0052298428 0.1983680000 251376799 0 1782824960 -0.3959605396 0.0448919274 -0.1464819312 346 1311867181.9629189968 0.0604658797 0.0567785629 0.0692697018 0.0052226785 0.1914710000 251378733 0 1784565760 -0.3934271932 0.0456903726 -0.1477206945 347 1311867181.9955599308 0.0614677519 0.0567920764 0.0692697018 0.0052391432 0.1927540000 251380611 0 1783455744 -0.3915179670 0.0452240743 -0.1455055326 348 1311867182.0320639610 0.0598920174 0.0568009843 0.0692697018 0.0052329053 0.1976740000 251382865 0 1782697984 -0.3906810284 0.0436792187 -0.1456898153 349 1311867182.0629000664 0.0582931750 0.0568052599 0.0692697018 0.0052264420 0.1927990000 251384703 0 1784561664 -0.3894733787 0.0433761030 -0.1470247507 350 1311867182.0948839188 0.0606717058 0.0568163069 0.0692697018 0.0052312495 0.2050560000 251387085 0 1785733120 -0.3861154318 0.0435070805 -0.1452043355 351 1311867182.1314840317 0.0601841733 0.0568259020 0.0692697018 0.0052240513 0.1986220000 251388955 0 1785237504 -0.3839581013 0.0432654172 -0.1458419114 352 1311867182.1629920006 0.0613443218 0.0568387384 0.0692697018 0.0052172247 0.1961560000 251390793 0 1783205888 -0.3818062544 0.0439400226 -0.1446313560 353 1311867182.1994500160 0.0612618513 0.0568512685 0.0692697018 0.0052124381 0.1944290000 251392743 0 1781936128 -0.3819703162 0.0432337038 -0.1434480250 354 1311867182.2307739258 0.0610619783 0.0568631631 0.0692697018 0.0052073725 0.1949990000 251394573 0 1783676928 -0.3797495961 0.0428024828 -0.1438767314 355 1311867182.2629120350 0.0598610751 0.0568716080 0.0692697018 0.0052056770 0.1922740000 251396587 0 1785192448 -0.3783560395 0.0416023731 -0.1446777284 356 1311867182.2973539829 0.0609446652 0.0568830491 0.0692697018 0.0051996587 0.1952490000 251398753 0 1784365056 -0.3772394955 0.0409522057 -0.1431279480 357 1311867182.3308460712 0.0593902469 0.0568900721 0.0692697018 0.0052072415 0.1992580000 251400743 0 1783570432 -0.3762567937 0.0403420366 -0.1446761191 358 1311867182.3629670143 0.0603054240 0.0568996122 0.0692697018 0.0052252645 0.1969660000 251402813 0 1785069568 -0.3746762574 0.0394118838 -0.1429239511 359 1311867182.3990368843 0.0594800040 0.0569067999 0.0692697018 0.0052256664 0.1994930000 251404875 0 1784496128 -0.3736123443 0.0388770327 -0.1434792578 360 1311867182.4308118820 0.0592831336 0.0569134008 0.0692697018 0.0052262787 0.1889190000 251406801 0 1783586816 -0.3715501726 0.0377309918 -0.1441901326 361 1311867182.4629440308 0.0595662892 0.0569207495 0.0692697018 0.0052283987 0.1962310000 251408855 0 1785348096 -0.3713788986 0.0379653089 -0.1436428428 362 1311867182.4969599247 0.0584111214 0.0569248666 0.0692697018 0.0052303138 0.1945860000 251410869 0 1783967744 -0.3678118289 0.0353265628 -0.1457207799 363 1311867182.5309500694 0.0598127358 0.0569328222 0.0692697018 0.0052338462 0.1915270000 251412939 0 1783439360 -0.3680585921 0.0350108109 -0.1438958049 364 1311867182.5629699230 0.0585401244 0.0569372378 0.0692697018 0.0052339148 0.1996270000 251415249 0 1784840192 -0.3669223487 0.0353081226 -0.1463741958 365 1311867182.6036369801 0.0589244701 0.0569426823 0.0692697018 0.0052298528 0.2066240000 251417311 0 1783607296 -0.3643022180 0.0339156091 -0.1458823979 366 1311867182.6308450699 0.0580639727 0.0569457459 0.0692697018 0.0052386429 0.2059520000 251419221 0 1782697984 -0.3626180887 0.0325149707 -0.1472719312 367 1311867182.6635921001 0.0592345558 0.0569519825 0.0692697018 0.0052333580 0.1983330000 251421115 0 1784459264 -0.3606719375 0.0337622724 -0.1471909434 368 1311867182.6970019341 0.0602742210 0.0569610103 0.0692697018 0.0052289837 0.1962080000 251423289 0 1783586816 -0.3582594097 0.0334980004 -0.1466342360 369 1311867182.7330639362 0.0575796664 0.0569626869 0.0692697018 0.0052305069 0.1902280000 251425359 0 1782554624 -0.3572451770 0.0306669474 -0.1482982039 370 1311867182.7631130219 0.0585969873 0.0569671039 0.0692697018 0.0052255290 0.1973050000 251427125 0 1784201216 -0.3548231423 0.0312770568 -0.1482106745 371 1311867182.7970550060 0.0579711311 0.0569698102 0.0692697018 0.0052187244 0.1979610000 251429307 0 1783713792 -0.3537340164 0.0305275451 -0.1487664431 372 1311867182.8306989670 0.0568076186 0.0569693742 0.0692697018 0.0052131192 0.1995220000 251431281 0 1782460416 -0.3507504463 0.0287951361 -0.1499700993 373 1311867182.8641169071 0.0559771731 0.0569667141 0.0692697018 0.0052136770 0.1975840000 251433247 0 1784602624 -0.3493729234 0.0291516948 -0.1505847275 374 1311867182.8969969749 0.0554677211 0.0569627061 0.0692697018 0.0052068381 0.1988950000 251435581 0 1783455744 -0.3476720750 0.0286512133 -0.1508080065 375 1311867182.9318990707 0.0565690845 0.0569616565 0.0692697018 0.0052023979 0.2011740000 251437227 0 1782460416 -0.3454467058 0.0303461030 -0.1501935869 376 1311867182.9630720615 0.0568070263 0.0569612452 0.0692697018 0.0051958510 0.1967000000 251439441 0 1784438784 -0.3423830867 0.0294910315 -0.1494158804 377 1311867182.9983949661 0.0568844639 0.0569610415 0.0692697018 0.0052074307 0.1969780000 251441599 0 1783226368 -0.3403423131 0.0283186305 -0.1487905681 378 1311867183.0308830738 0.0570272207 0.0569612166 0.0692697018 0.0052012170 0.1922850000 251443413 0 1781768192 -0.3390780687 0.0293020457 -0.1486003697 379 1311867183.0628600121 0.0570266508 0.0569613893 0.0692697018 0.0051960222 0.1968210000 251445427 0 1783058432 -0.3370052278 0.0288025234 -0.1481292844 380 1311867183.1000499725 0.0562972948 0.0569596416 0.0692697018 0.0052111633 0.1990730000 251447313 0 1784971264 -0.3368718624 0.0287813284 -0.1476563364 381 1311867183.1344780922 0.0571446046 0.0569601271 0.0692697018 0.0052060153 0.2000420000 251449151 0 1783721984 -0.3339950740 0.0296780225 -0.1472315937 382 1311867183.1673240662 0.0548623949 0.0569546357 0.0692697018 0.0052003400 0.2349470000 251451477 0 1783435264 -0.3327677846 0.0277304538 -0.1481762975 383 1311867183.2004919052 0.0542869195 0.0569476704 0.0692697018 0.0051960145 0.1977310000 251453579 0 1784954880 -0.3305921257 0.0256709103 -0.1475816965 384 1311867183.2311279774 0.0547601618 0.0569419737 0.0692697018 0.0051894454 0.2005280000 251455577 0 1784483840 -0.3292079866 0.0264163297 -0.1473414302 385 1311867183.2633349895 0.0544456914 0.0569354899 0.0692697018 0.0051832414 0.1960400000 251457335 0 1784225792 -0.3284505010 0.0260458365 -0.1470790952 386 1311867183.2991099358 0.0545286611 0.0569292546 0.0692697018 0.0051796550 0.1992010000 251459429 0 1783721984 -0.3273385763 0.0253430177 -0.1466004550 387 1311867183.3320920467 0.0548721254 0.0569239390 0.0692697018 0.0051763494 0.2021160000 251461547 0 1783214080 -0.3244395852 0.0257042777 -0.1472938508 388 1311867183.3695240021 0.0547044948 0.0569182188 0.0692697018 0.0051708537 0.2008730000 251463713 0 1784446976 -0.3227325380 0.0233003926 -0.1462663561 389 1311867183.3986210823 0.0530514717 0.0569082785 0.0692697018 0.0051652409 0.2052650000 251465687 0 1783934976 -0.3216114342 0.0214189962 -0.1475911587 390 1311867183.4311549664 0.0542866327 0.0569015564 0.0692697018 0.0051723167 0.2039070000 251467493 0 1783848960 -0.3192647398 0.0241300613 -0.1484321654 391 1311867183.4667448997 0.0546260513 0.0568957367 0.0692697018 0.0051746836 0.2003820000 251469539 0 1785626624 -0.3181780279 0.0235849246 -0.1472873986 392 1311867183.4988338947 0.0545424670 0.0568897334 0.0692697018 0.0051884347 0.1985580000 251471393 0 1785118720 -0.3174427152 0.0212022755 -0.1450221241 393 1311867183.5321829319 0.0550137050 0.0568849598 0.0692697018 0.0051865463 0.2040790000 251473487 0 1784446976 -0.3142365813 0.0222972259 -0.1456247270 394 1311867183.5661609173 0.0543207861 0.0568784518 0.0692697018 0.0051802644 0.2033590000 251476053 0 1784074240 -0.3127185404 0.0228072871 -0.1465128511 395 1311867183.5985479355 0.0546744987 0.0568728721 0.0692697018 0.0051747082 0.1949870000 251477731 0 1783455744 -0.3124558628 0.0202564243 -0.1435566992 396 1311867183.6310880184 0.0533340089 0.0568639356 0.0692697018 0.0051835401 0.1986270000 251479697 0 1785217024 -0.3105737865 0.0195253026 -0.1447166204 397 1311867183.6649260521 0.0535483696 0.0568555841 0.0692697018 0.0051774254 0.1958940000 251481663 0 1784745984 -0.3071612418 0.0190109443 -0.1441630572 398 1311867183.6993949413 0.0544812828 0.0568496185 0.0692697018 0.0051746113 0.2001360000 251483677 0 1783820288 -0.3062736988 0.0205508750 -0.1436619759 399 1311867183.7308928967 0.0555086248 0.0568462576 0.0692697018 0.0051717656 0.1904690000 251485667 0 1785634816 -0.3022990227 0.0189237613 -0.1417362094 400 1311867183.7676479816 0.0526076704 0.0568356611 0.0692697018 0.0051795127 0.2019140000 251487801 0 1785126912 -0.3021462858 0.0172809809 -0.1429531127 401 1311867183.7971870899 0.0537450500 0.0568279539 0.0692697018 0.0051736308 0.1988220000 251489535 0 1784475648 -0.2998900712 0.0176903177 -0.1417712420 402 1311867183.8309071064 0.0538277775 0.0568204907 0.0692697018 0.0051673841 0.1993440000 251491709 0 1783947264 -0.2982180417 0.0152278487 -0.1398038417 403 1311867183.8655049801 0.0545647815 0.0568148934 0.0692697018 0.0051614640 0.1980190000 251493723 0 1783189504 -0.2965171039 0.0154494140 -0.1391579509 404 1311867183.8970971107 0.0526324138 0.0568045408 0.0692697018 0.0051603860 0.2003520000 251495521 0 1784963072 -0.2941918373 0.0132097369 -0.1403939128 405 1311867183.9314939976 0.0536613092 0.0567967797 0.0692697018 0.0051563134 0.2296430000 251497591 0 1784455168 -0.2932159305 0.0148738101 -0.1397936344 406 1311867183.9658319950 0.0516789667 0.0567841743 0.0692697018 0.0051612931 0.2024810000 251499605 0 1783840768 -0.2913691103 0.0112772472 -0.1397959441 407 1311867183.9966781139 0.0507892556 0.0567694447 0.0692697018 0.0051562000 0.2001130000 251501763 0 1785507840 -0.2906269729 0.0111847650 -0.1406836957 408 1311867184.0309689045 0.0517936237 0.0567572491 0.0692697018 0.0051849225 0.2019510000 251503857 0 1784692736 -0.2891083658 0.0113992458 -0.1398666948 409 1311867184.0647850037 0.0523931496 0.0567465789 0.0692697018 0.0051792904 0.1956350000 251505703 0 1783971840 -0.2889141738 0.0111398399 -0.1382907629 410 1311867184.0968890190 0.0525324382 0.0567363005 0.0692697018 0.0051744907 0.2033530000 251507653 0 1785745408 -0.2861383259 0.0110708615 -0.1381278783 411 1311867184.1312260628 0.0530042909 0.0567272202 0.0692697018 0.0051684160 0.2015130000 251509515 0 1784836096 -0.2838353217 0.0122862700 -0.1383591294 412 1311867184.1650640965 0.0510858782 0.0567135276 0.0692697018 0.0051636900 0.2047150000 251511769 0 1784352768 -0.2835647464 0.0089445151 -0.1377583146 413 1311867184.1969559193 0.0513714328 0.0567005928 0.0692697018 0.0051582978 0.2027300000 251513567 0 1783820288 -0.2810977399 0.0105844662 -0.1383714527 414 1311867184.2309360504 0.0510273576 0.0566868893 0.0692697018 0.0051535926 0.1962060000 251515645 0 1783349248 -0.2793737948 0.0091654528 -0.1373654753 415 1311867184.2681369781 0.0510640778 0.0566733404 0.0692697018 0.0051484672 0.2022660000 251517995 0 1784999936 -0.2771046758 0.0079754815 -0.1364905238 416 1311867184.2983899117 0.0506444015 0.0566588477 0.0692697018 0.0051470975 0.2053920000 251519873 0 1784107008 -0.2763897181 0.0101048127 -0.1375921369 417 1311867184.3314700127 0.0482430607 0.0566386660 0.0692697018 0.0051460228 0.1949650000 251521943 0 1783349248 -0.2743969560 0.0078083244 -0.1384029090 418 1311867184.3697841167 0.0508308783 0.0566247718 0.0692697018 0.0051436853 0.1984980000 251523781 0 1785126912 -0.2723280489 0.0070144678 -0.1345436871 419 1311867184.4000220299 0.0510202609 0.0566113958 0.0692697018 0.0051676485 0.2028120000 251526059 0 1784582144 -0.2697766721 0.0090922834 -0.1354609430 420 1311867184.4310610294 0.0505971126 0.0565970761 0.0692697018 0.0051669938 0.1993480000 251528145 0 1784111104 -0.2657470107 0.0087243570 -0.1366032213 421 1311867184.4655809402 0.0500607714 0.0565815504 0.0692697018 0.0051652525 0.1961500000 251530055 0 1785716736 -0.2659786344 0.0059743910 -0.1350094378 422 1311867184.5037670135 0.0487952679 0.0565630995 0.0692697018 0.0052442505 0.2042930000 251532705 0 1785245696 -0.2600074410 0.0057838447 -0.1381950676 423 1311867184.5310881138 0.0489277318 0.0565450490 0.0692697018 0.0052813535 0.2044900000 251534415 0 1784737792 -0.2593843639 0.0055091525 -0.1386004388 424 1311867184.5682930946 0.0496793874 0.0565288564 0.0692697018 0.0052777675 0.2037630000 251536341 0 1784193024 -0.2561716437 0.0035244618 -0.1371985078 425 1311867184.6018071175 0.0484282523 0.0565097962 0.0692697018 0.0052716446 0.1985790000 251538595 0 1783574528 -0.2554321885 0.0019597434 -0.1375177056 426 1311867184.6367399693 0.0482553467 0.0564904195 0.0692697018 0.0052663270 0.2032630000 251540369 0 1785372672 -0.2530863583 0.0029467321 -0.1381384283 427 1311867184.6662440300 0.0469947904 0.0564681815 0.0692697018 0.0052745017 0.1962980000 251542583 0 1784827904 -0.2507635355 0.0006165360 -0.1380031258 428 1311867184.6994929314 0.0490102656 0.0564507565 0.0692697018 0.0052687338 0.2315410000 251544333 0 1783943168 -0.2461358160 0.0001787664 -0.1357885301 429 1311867184.7359158993 0.0489840321 0.0564333515 0.0692697018 0.0052670605 0.1955500000 251546379 0 1785864192 -0.2440079004 0.0003303201 -0.1356118917 430 1311867184.7690689564 0.0462589115 0.0564096901 0.0692697018 0.0052660241 0.2035690000 251548585 0 1785208832 -0.2437161058 -0.0030773003 -0.1361964643 431 1311867184.8001279831 0.0490840897 0.0563926933 0.0692697018 0.0052647669 0.1959050000 251550639 0 1784737792 -0.2390748113 -0.0009940616 -0.1341746449 432 1311867184.8348441124 0.0475165918 0.0563721468 0.0692697018 0.0052609396 0.2000230000 251552621 0 1784229888 -0.2371469736 -0.0025322535 -0.1343832612 433 1311867184.8690660000 0.0475293510 0.0563517246 0.0692697018 0.0052550699 0.1981590000 251554515 0 1783341056 -0.2345744520 -0.0047040703 -0.1321697384 434 1311867184.9055209160 0.0471083559 0.0563304265 0.0692697018 0.0052503288 0.2038720000 251556761 0 1785118720 -0.2313394994 -0.0042014620 -0.1321574450 435 1311867184.9332280159 0.0472364835 0.0563095209 0.0692697018 0.0052464268 0.2055620000 251558559 0 1784573952 -0.2294448465 -0.0046169762 -0.1303479820 436 1311867184.9656410217 0.0463783629 0.0562867430 0.0692697018 0.0052483436 0.2075860000 251560749 0 1783717888 -0.2265660912 -0.0073782247 -0.1285558045 437 1311867184.9983251095 0.0470826440 0.0562656810 0.0692697018 0.0052514617 0.2067430000 251562651 0 1785368576 -0.2242680490 -0.0080914404 -0.1258710772 438 1311867185.0360550880 0.0464356020 0.0562432379 0.0692697018 0.0052458759 0.2037170000 251564529 0 1784610816 -0.2193965614 -0.0085177515 -0.1253046244 439 1311867185.0652348995 0.0451498888 0.0562179683 0.0692697018 0.0052404639 0.2013510000 251566687 0 1783836672 -0.2177629173 -0.0115651842 -0.1238225847 440 1311867185.0991280079 0.0465851091 0.0561960755 0.0692697018 0.0052365965 0.2026920000 251568901 0 1785610240 -0.2156487256 -0.0099505233 -0.1214406937 441 1311867185.1360778809 0.0460164994 0.0561729925 0.0692697018 0.0052322796 0.2074650000 251571075 0 1785085952 -0.2117312700 -0.0100066941 -0.1206203103 442 1311867185.1648709774 0.0470431894 0.0561523369 0.0692697018 0.0052275668 0.2028240000 251572737 0 1784201216 -0.2081640810 -0.0116717443 -0.1170390248 443 1311867185.2000720501 0.0460079946 0.0561294377 0.0692697018 0.0052220680 0.2044450000 251575047 0 1785597952 -0.2037080079 -0.0116757937 -0.1170081422 444 1311867185.2342920303 0.0433141924 0.0561005745 0.0692697018 0.0052213159 0.2028840000 251577149 0 1784819712 -0.2015391737 -0.0148325209 -0.1167375594 445 1311867185.2663950920 0.0456379019 0.0560770629 0.0692697018 0.0052235149 0.2025610000 251579219 0 1783422976 -0.1994891018 -0.0147991572 -0.1127135977 446 1311867185.2970550060 0.0454960912 0.0560533387 0.0692697018 0.0052525730 0.2081020000 251581105 0 1785344000 -0.1963839382 -0.0140360417 -0.1118305176 447 1311867185.3360140324 0.0453635193 0.0560294241 0.0692697018 0.0052474719 0.2071630000 251583591 0 1784201216 -0.1937833726 -0.0159300733 -0.1093897298 448 1311867185.3681778908 0.0445381403 0.0560037740 0.0692697018 0.0052419584 0.2077150000 251585117 0 1783586816 -0.1906723827 -0.0176335759 -0.1084720045 449 1311867185.4036509991 0.0456890129 0.0559808012 0.0692697018 0.0052404453 0.1985240000 251587515 0 1784967168 -0.1873849779 -0.0163084120 -0.1070241928 450 1311867185.4386389256 0.0456079766 0.0559577505 0.0692697018 0.0052349684 0.2051690000 251589353 0 1784475648 -0.1828808635 -0.0169260986 -0.1059343144 451 1311867185.4655449390 0.0444692783 0.0559322772 0.0692697018 0.0052303251 0.2306250000 251591087 0 1783058432 -0.1823016703 -0.0190016404 -0.1057829559 452 1311867185.5013909340 0.0457265414 0.0559096981 0.0692697018 0.0052355278 0.2032590000 251593221 0 1785106432 -0.1795286983 -0.0181282721 -0.1042952985 453 1311867185.5336329937 0.0449305512 0.0558854616 0.0692697018 0.0052412980 0.2018940000 251595275 0 1783730176 -0.1764991730 -0.0189292207 -0.1041340679 454 1311867185.5666799545 0.0448582098 0.0558611725 0.0692697018 0.0052362607 0.1992900000 251597073 0 1783332864 -0.1757371277 -0.0212617647 -0.1024774387 455 1311867185.5970540047 0.0457524359 0.0558389555 0.0692697018 0.0052352908 0.2063940000 251599231 0 1784598528 -0.1695461273 -0.0215961151 -0.1015116274 456 1311867185.6329469681 0.0456325412 0.0558165730 0.0692697018 0.0052454971 0.2059010000 251601349 0 1784090624 -0.1674546450 -0.0218216050 -0.1011409461 457 1311867185.6664180756 0.0449474938 0.0557927894 0.0692697018 0.0052464407 0.1973050000 251603587 0 1783332864 -0.1648417413 -0.0232853666 -0.1005832404 458 1311867185.6973390579 0.0453742258 0.0557700415 0.0692697018 0.0052418072 0.2091280000 251605497 0 1785110528 -0.1614980549 -0.0244563036 -0.0989034176 459 1311867185.7351899147 0.0443195514 0.0557450949 0.0692697018 0.0052422778 0.2087960000 251607527 0 1783586816 -0.1606444716 -0.0232038759 -0.0996879563 460 1311867185.7649769783 0.0454196557 0.0557226483 0.0692697018 0.0052377231 0.2073520000 251609645 0 1782841344 -0.1563206911 -0.0262746327 -0.0960342586 461 1311867185.7989649773 0.0455123410 0.0557005001 0.0692697018 0.0052520959 0.2026780000 251611443 0 1784455168 -0.1546116173 -0.0261373743 -0.0958250463 462 1311867185.8327999115 0.0461190492 0.0556797610 0.0692697018 0.0052468806 0.1959470000 251613705 0 1783861248 -0.1517661512 -0.0253935736 -0.0948961377 463 1311867185.8649098873 0.0441414677 0.0556548403 0.0692697018 0.0052428930 0.2114180000 251615759 0 1782951936 -0.1511543989 -0.0288973972 -0.0942167193 464 1311867185.9030420780 0.0441198237 0.0556299804 0.0692697018 0.0052388530 0.2067090000 251617541 0 1783930880 -0.1482130438 -0.0287384931 -0.0934073478 465 1311867185.9396789074 0.0433147103 0.0556034959 0.0692697018 0.0052336034 0.2036430000 251619859 0 1783603200 -0.1471917182 -0.0300803669 -0.0923645571 466 1311867185.9650609493 0.0409179255 0.0555719818 0.0692697018 0.0052516230 0.1984950000 251621529 0 1782059008 -0.1428961307 -0.0347461216 -0.0919200778 467 1311867186.0039470196 0.0434356444 0.0555459939 0.0692697018 0.0052617980 0.2041120000 251623647 0 1784221696 -0.1410752684 -0.0315425247 -0.0906495452 468 1311867186.0396919250 0.0439584032 0.0555212341 0.0692697018 0.0052592048 0.2073770000 251625677 0 1785827328 -0.1382581890 -0.0321215540 -0.0888110772 469 1311867186.0653240681 0.0423767790 0.0554932076 0.0692697018 0.0052593126 0.2064760000 251627595 0 1785110528 -0.1384207904 -0.0349945724 -0.0884106606 470 1311867186.1047339439 0.0424117483 0.0554653747 0.0692697018 0.0052540546 0.2060630000 251629857 0 1784348672 -0.1377579868 -0.0350468606 -0.0879334509 471 1311867186.1361179352 0.0435951315 0.0554401725 0.0692697018 0.0052522667 0.2075970000 251631687 0 1786109952 -0.1352182627 -0.0347318538 -0.0867516622 472 1311867186.1649448872 0.0410969667 0.0554097843 0.0692697018 0.0052507835 0.2102500000 251633741 0 1785237504 -0.1340729594 -0.0375067703 -0.0878579691 473 1311867186.2044749260 0.0422162004 0.0553818909 0.0692697018 0.0052460304 0.2018380000 251635651 0 1783304192 -0.1323682070 -0.0373921953 -0.0864854902 474 1311867186.2359659672 0.0425336920 0.0553547850 0.0692697018 0.0052415370 0.2307120000 251637713 0 1782165504 -0.1286062896 -0.0383355469 -0.0853871033 475 1311867186.2674899101 0.0409758277 0.0553245135 0.0692697018 0.0052360901 0.1979450000 251639695 0 1783967744 -0.1287170351 -0.0403321497 -0.0858198926 476 1311867186.3030838966 0.0417109653 0.0552959136 0.0692697018 0.0052335909 0.1953150000 251641661 0 1785573376 -0.1267110109 -0.0400116779 -0.0847179741 477 1311867186.3349270821 0.0403307378 0.0552645401 0.0692697018 0.0052373966 0.1998060000 251643411 0 1785110528 -0.1224377975 -0.0413584746 -0.0847630650 478 1311867186.3670160770 0.0402763188 0.0552331840 0.0692697018 0.0052336192 0.2068980000 251645417 0 1783840768 -0.1225870028 -0.0434436537 -0.0831015483 479 1311867186.4019849300 0.0437322371 0.0552091736 0.0692697018 0.0052423967 0.2033160000 251647359 0 1785851904 -0.1202814281 -0.0401337929 -0.0806970447 480 1311867186.4360210896 0.0430242233 0.0551837883 0.0692697018 0.0052391282 0.1969420000 251649605 0 1784602624 -0.1183775663 -0.0417330600 -0.0793192834 481 1311867186.4659481049 0.0410781242 0.0551544626 0.0692697018 0.0052408053 0.1994030000 251651619 0 1783046144 -0.1154371873 -0.0466087013 -0.0780593082 482 1311867186.5031139851 0.0419418141 0.0551270505 0.0692697018 0.0052430357 0.1991100000 251653433 0 1781915648 -0.1154360548 -0.0443454981 -0.0777177736 483 1311867186.5363171101 0.0418035313 0.0550994656 0.0692697018 0.0052377777 0.1987090000 251655759 0 1783586816 -0.1131664887 -0.0440898836 -0.0771543980 484 1311867186.5651130676 0.0413196459 0.0550709949 0.0692697018 0.0052369043 0.1957290000 251657589 0 1785319424 -0.1117380112 -0.0480490029 -0.0750080273 485 1311867186.6014220715 0.0421623662 0.0550443791 0.0692697018 0.0052340463 0.2482700000 252059759 0 1783988224 -0.1110963672 -0.0470291674 -0.0749079734 486 1311867186.6362628937 0.0407211743 0.0550149075 0.0692697018 0.0052304666 0.4479800000 252067193 0 1779318784 -0.1084106192 -0.0480277017 -0.0761197805 487 1311867186.6650478840 0.0410121083 0.0549861543 0.0692697018 0.0052266128 0.4228440000 252064527 0 1781501952 -0.1070411578 -0.0476126969 -0.0762041137 488 1311867186.7043809891 0.0411988832 0.0549579017 0.0692697018 0.0052402226 0.4228570000 252214025 0 1782685696 -0.1043069810 -0.0477686413 -0.0758360401 489 1311867186.7337749004 0.0404276624 0.0549281875 0.0692697018 0.0052420709 0.3484780000 254464322 0 1783820288 -0.1030737534 -0.0451711528 -0.0784099698 490 1311867186.7673180103 0.0417724885 0.0549013392 0.0692697018 0.0052394039 0.2949250000 254349200 0 1782816768 -0.1027076915 -0.0449311286 -0.0768194646 491 1311867186.8047299385 0.0415376015 0.0548741218 0.0692697018 0.0052377053 0.3809230000 253241982 0 1781501952 -0.1014195830 -0.0481923185 -0.0755661502 492 1311867186.8340749741 0.0426313132 0.0548492380 0.0692697018 0.0052375773 0.2435620000 252076133 0 1782538240 -0.0987961665 -0.0433480293 -0.0769067854 493 1311867186.8775999546 0.0409818329 0.0548211094 0.0692697018 0.0052356595 0.2089390000 252078379 0 1784049664 -0.0956072956 -0.0446197279 -0.0777323768 494 1311867186.9052100182 0.0405068584 0.0547921332 0.0692697018 0.0052312232 0.2053720000 252080137 0 1785794560 -0.0956640691 -0.0448929369 -0.0781205669 495 1311867186.9334239960 0.0426345840 0.0547675725 0.0692697018 0.0052284719 0.2045690000 252082263 0 1785061376 -0.0930494294 -0.0425209515 -0.0767215937 496 1311867186.9663379192 0.0422528833 0.0547423413 0.0692697018 0.0052273874 0.2094250000 252084301 0 1783029760 -0.0884698406 -0.0409526117 -0.0777136460 497 1311867187.0017139912 0.0405025110 0.0547136897 0.0692697018 0.0052331750 0.2048440000 252086195 0 1782030336 -0.0862138048 -0.0445749089 -0.0778727531 498 1311867187.0336461067 0.0425144285 0.0546891932 0.0692697018 0.0052492988 0.1987090000 252088433 0 1784172544 -0.0853035897 -0.0413351581 -0.0775031447 499 1311867187.0749349594 0.0429702997 0.0546657084 0.0692697018 0.0052444100 0.2054270000 252090535 0 1785065472 -0.0819735155 -0.0391135737 -0.0778019875 500 1311867187.1016030312 0.0438924059 0.0546441618 0.0692697018 0.0052408298 0.2036650000 252092373 0 1784315904 -0.0784179941 -0.0403427184 -0.0759374201 501 1311867187.1342070103 0.0425476022 0.0546200170 0.0692697018 0.0052417010 0.2033400000 252094571 0 1782882304 -0.0780208707 -0.0431613177 -0.0767702684 502 1311867187.1710209846 0.0452446006 0.0546013409 0.0692697018 0.0052530435 0.1995930000 252096473 0 1784930304 -0.0752928555 -0.0386965126 -0.0760170966 503 1311867187.2041370869 0.0443502851 0.0545809610 0.0692697018 0.0052606420 0.2050960000 252098927 0 1783320576 -0.0735897496 -0.0401969552 -0.0770761371 504 1311867187.2331659794 0.0441983156 0.0545603606 0.0692697018 0.0052575034 0.2077370000 252100797 0 1782538240 -0.0723686516 -0.0417580009 -0.0770029649 505 1311867187.2707629204 0.0459587611 0.0545433277 0.0692697018 0.0052630096 0.2047250000 252102779 0 1784168448 -0.0708016530 -0.0387390777 -0.0765706152 506 1311867187.3015060425 0.0442547649 0.0545229946 0.0692697018 0.0052713543 0.1980970000 252104889 0 1783427072 -0.0690633953 -0.0404764712 -0.0776580051 507 1311867187.3336570263 0.0450194292 0.0545042498 0.0692697018 0.0052671890 0.1953540000 252106895 0 1781649408 -0.0681119412 -0.0407733694 -0.0772465914 508 1311867187.3707590103 0.0439414866 0.0544834570 0.0692697018 0.0052628161 0.2061300000 252108829 0 1784430592 -0.0679829493 -0.0412802324 -0.0789449960 509 1311867187.4033529758 0.0441720635 0.0544631989 0.0692697018 0.0052599250 0.2091360000 252111027 0 1783554048 -0.0680470988 -0.0416140407 -0.0792821869 510 1311867187.4335899353 0.0439732037 0.0544426302 0.0692697018 0.0052576857 0.2028660000 252112657 0 1782538240 -0.0657190531 -0.0409631282 -0.0800759271 511 1311867187.4763159752 0.0427440479 0.0544197367 0.0692697018 0.0052544095 0.2006800000 252114999 0 1784168448 -0.0603514947 -0.0406120755 -0.0820466951 512 1311867187.5056400299 0.0428556167 0.0543971506 0.0692697018 0.0052507979 0.2059480000 252117053 0 1783427072 -0.0576420873 -0.0431541130 -0.0817876607 513 1311867187.5342190266 0.0430292189 0.0543749909 0.0692697018 0.0052501525 0.1992910000 252159771 0 1782394880 -0.0567167625 -0.0424838960 -0.0833581761 514 1311867187.5709679127 0.0424980931 0.0543518841 0.0692697018 0.0052461400 0.2000120000 252245857 0 1784061952 -0.0520245582 -0.0429517776 -0.0846767202 515 1311867187.6045789719 0.0432847887 0.0543303945 0.0692697018 0.0052687128 0.1924630000 252247895 0 1783320576 -0.0507408306 -0.0420406312 -0.0851950720 516 1311867187.6353919506 0.0431832038 0.0543087915 0.0692697018 0.0052679760 0.2345660000 252249845 0 1782521856 -0.0491203554 -0.0438003242 -0.0861814991 517 1311867187.6707689762 0.0429646000 0.0542868491 0.0692697018 0.0052714510 0.2006730000 252252091 0 1784172544 -0.0434203520 -0.0400421545 -0.0884730965 518 1311867187.7035770416 0.0443142243 0.0542675969 0.0692697018 0.0052733429 0.2068160000 252254009 0 1785794560 -0.0437351651 -0.0415611826 -0.0879124552 519 1311867187.7345480919 0.0429758206 0.0542458402 0.0692697018 0.0052831709 0.2026510000 252255815 0 1785057280 -0.0412725471 -0.0458399951 -0.0882853791 520 1311867187.7707819939 0.0431055762 0.0542244166 0.0692697018 0.0052870158 0.1988770000 252257797 0 1783160832 -0.0391857103 -0.0395858362 -0.0914233103 521 1311867187.8017508984 0.0424834117 0.0542018811 0.0692697018 0.0052889658 0.2055920000 252259883 0 1782157312 -0.0353852510 -0.0418509841 -0.0913912877 522 1311867187.8339610100 0.0419523306 0.0541784145 0.0692697018 0.0052849873 0.1923100000 252261921 0 1783681024 -0.0335415117 -0.0411275476 -0.0928838179 523 1311867187.8708090782 0.0420289375 0.0541551841 0.0692697018 0.0052833233 0.1998200000 252263839 0 1785159680 -0.0328324847 -0.0403643735 -0.0936635584 524 1311867187.9038810730 0.0419128984 0.0541318210 0.0692697018 0.0052809275 0.2027200000 252266021 0 1784078336 -0.0281884354 -0.0381839648 -0.0946471691 525 1311867187.9363000393 0.0430324599 0.0541106793 0.0692697018 0.0052782745 0.1971000000 252267875 0 1782030336 -0.0258962270 -0.0397460870 -0.0931687579 526 1311867187.9713420868 0.0417290591 0.0540871401 0.0692697018 0.0052778646 0.2028840000 252270113 0 1785159680 -0.0240180120 -0.0413025320 -0.0953040645 527 1311867188.0047569275 0.0413978361 0.0540630618 0.0692697018 0.0053084922 0.1990450000 252272175 0 1783697408 -0.0192899033 -0.0385802463 -0.0976490825 528 1311867188.0333108902 0.0415027142 0.0540392732 0.0692697018 0.0053148345 0.2025950000 252273957 0 1782665216 -0.0165696777 -0.0393630117 -0.0980445966 529 1311867188.0698699951 0.0429608114 0.0540183310 0.0692697018 0.0053117408 0.2014500000 252275923 0 1784426496 -0.0147062214 -0.0417495817 -0.0972000360 530 1311867188.1088800430 0.0412404686 0.0539942218 0.0692697018 0.0053195101 0.1901100000 252278329 0 1785794560 -0.0093397275 -0.0413676873 -0.1001501083 531 1311867188.1359970570 0.0400574170 0.0539679754 0.0692697018 0.0053274075 0.1947630000 252280135 0 1784659968 -0.0074233711 -0.0415088162 -0.1012433916 532 1311867188.1703350544 0.0400504284 0.0539418146 0.0692697018 0.0053260486 0.2000960000 252282397 0 1783410688 -0.0067910142 -0.0436233617 -0.1038534492 533 1311867188.2026720047 0.0418968499 0.0539192162 0.0692697018 0.0053334684 0.2041160000 252284523 0 1784946688 -0.0036985585 -0.0433337763 -0.1031408757 534 1311867188.2352449894 0.0407865383 0.0538946232 0.0692697018 0.0053461351 0.2020710000 252286385 0 1784311808 0.0012944415 -0.0421551391 -0.1048320755 535 1311867188.2706460953 0.0415819027 0.0538716087 0.0692697018 0.0053473252 0.2033610000 252288471 0 1782161408 0.0028108628 -0.0418856367 -0.1063637212 536 1311867188.3047339916 0.0395239070 0.0538448406 0.0692697018 0.0053426074 0.2011090000 252290453 0 1785430016 0.0046099257 -0.0435225591 -0.1097544730 537 1311867188.3398799896 0.0409597605 0.0538208461 0.0692697018 0.0053386613 0.2021040000 252292451 0 1784320000 0.0092719030 -0.0407476462 -0.1098137125 538 1311867188.3718800545 0.0408648849 0.0537967644 0.0692697018 0.0053371543 0.1937520000 252294473 0 1783795712 0.0120329317 -0.0385343693 -0.1113436744 539 1311867188.4054470062 0.0411445759 0.0537732909 0.0692697018 0.0053383038 0.2646190000 252773255 0 1785556992 0.0126914503 -0.0389772132 -0.1116879359 540 1311867188.4398789406 0.0395655334 0.0537469803 0.0692697018 0.0053368013 0.4920270000 252736049 0 1785516032 0.0176062547 -0.0393469930 -0.1131388620 541 1311867188.4724500179 0.0394152477 0.0537204891 0.0692697018 0.0053352177 0.4333250000 252734063 0 1784709120 0.0204141792 -0.0373820849 -0.1144055501 542 1311867188.5049159527 0.0409463309 0.0536969205 0.0692697018 0.0053361707 0.4154170000 252874361 0 1784188928 0.0227382928 -0.0363152176 -0.1133651808 543 1311867188.5389990807 0.0383355878 0.0536686308 0.0692697018 0.0053399797 0.3369980000 255310046 0 1783549952 0.0263940468 -0.0383693725 -0.1151987538 544 1311867188.5723888874 0.0390368439 0.0536417341 0.0692697018 0.0053475960 0.2892860000 255147148 0 1782800384 0.0301371403 -0.0335095972 -0.1164684966 545 1311867188.6045958996 0.0409270637 0.0536184044 0.0692697018 0.0053429948 0.4364700000 254050982 0 1781403648 0.0332211442 -0.0349752046 -0.1133590415 546 1311867188.6398339272 0.0425435938 0.0535981209 0.0692697018 0.0053381497 0.2219640000 252745533 0 1782108160 0.0359570757 -0.0359058194 -0.1115822643 547 1311867188.6715080738 0.0428048968 0.0535783892 0.0692697018 0.0053372574 0.2117020000 252747539 0 1783922688 0.0393820778 -0.0337033942 -0.1128011793 548 1311867188.7038300037 0.0425450280 0.0535582554 0.0692697018 0.0053347084 0.2110880000 252749641 0 1783377920 0.0397080109 -0.0347186811 -0.1142772958 549 1311867188.7393829823 0.0426265746 0.0535383434 0.0692697018 0.0053408986 0.2140590000 252751927 0 1782775808 0.0444953814 -0.0368644819 -0.1139629334 550 1311867188.7721049786 0.0414300114 0.0535163282 0.0692697018 0.0053427747 0.2085240000 252753621 0 1784389632 0.0510275513 -0.0359599777 -0.1162704229 551 1311867188.8045220375 0.0432288833 0.0534976577 0.0692697018 0.0053451055 0.2088220000 252755755 0 1783668736 0.0526868030 -0.0349125415 -0.1164932624 552 1311867188.8402431011 0.0445338078 0.0534814189 0.0692697018 0.0053480937 0.2095980000 252758185 0 1783156736 0.0550412387 -0.0360745266 -0.1168746278 553 1311867188.8705990314 0.0455876142 0.0534671444 0.0692697018 0.0053447711 0.2035970000 252759775 0 1784934400 0.0586046837 -0.0348047316 -0.1176074743 554 1311867188.9016311169 0.0458951518 0.0534534765 0.0692697018 0.0053426766 0.2070630000 252761877 0 1784393728 0.0602444448 -0.0322727002 -0.1199024618 555 1311867188.9401769638 0.0473297425 0.0534424427 0.0692697018 0.0053385070 0.2390120000 253179743 0 1784049664 0.0620112494 -0.0358387679 -0.1190748811 556 1311867188.9709990025 0.0474886186 0.0534317344 0.0692697018 0.0053387467 0.4890450000 253197737 0 1784553472 0.0653297752 -0.0344706178 -0.1203738376 557 1311867189.0052258968 0.0463620685 0.0534190420 0.0692697018 0.0053343514 0.4402890000 253200243 0 1783894016 0.0701122656 -0.0336448103 -0.1223120317 558 1311867189.0400099754 0.0468845516 0.0534073315 0.0692697018 0.0053329816 0.4277170000 253342889 0 1783087104 0.0745866597 -0.0336175524 -0.1223427802 559 1311867189.0724329948 0.0480257757 0.0533977044 0.0692697018 0.0053341374 0.4029450000 255970106 0 1783017472 0.0751325488 -0.0350019671 -0.1211708486 560 1311867189.1026360989 0.0479898676 0.0533880475 0.0692697018 0.0053311372 0.3005840000 255801312 0 1782452224 0.0791767761 -0.0333087891 -0.1212050617 561 1311867189.1417639256 0.0484724492 0.0533792853 0.0692697018 0.0053278003 0.4699620000 254684392 0 1780670464 0.0807841271 -0.0335620977 -0.1204124242 562 1311867189.1717920303 0.0486455448 0.0533708623 0.0692697018 0.0053276819 0.2071520000 253208617 0 1780989952 0.0834151134 -0.0342289954 -0.1186316609 563 1311867189.2019069195 0.0491406843 0.0533633486 0.0692697018 0.0053232823 0.2076960000 253210831 0 1782730752 0.0853299648 -0.0340584628 -0.1173424870 564 1311867189.2390630245 0.0491606072 0.0533558970 0.0692697018 0.0053217717 0.2040940000 253212661 0 1784381440 0.0875867307 -0.0354758203 -0.1157633364 565 1311867189.2722640038 0.0492324345 0.0533485988 0.0692697018 0.0053197298 0.2123390000 253214651 0 1783910400 0.0871052071 -0.0361908898 -0.1156361103 566 1311867189.3046789169 0.0486758165 0.0533403430 0.0692697018 0.0053168673 0.2125380000 253216857 0 1783353344 0.0914524198 -0.0367479734 -0.1147523746 567 1311867189.3397970200 0.0483444184 0.0533315318 0.0692697018 0.0053200516 0.2104680000 253218567 0 1785016320 0.0922507122 -0.0386783630 -0.1139672548 568 1311867189.3720359802 0.0486158282 0.0533232296 0.0692697018 0.0053598642 0.2094730000 253220805 0 1784143872 0.0951206610 -0.0391726717 -0.1135196984 569 1311867189.4056949615 0.0485586524 0.0533148560 0.0692697018 0.0053622716 0.2080290000 253223035 0 1783386112 0.0993625149 -0.0384505019 -0.1125058755 570 1311867189.4405019283 0.0495680869 0.0533082827 0.0692697018 0.0053614953 0.2048420000 253224793 0 1785180160 0.1012763828 -0.0411762334 -0.1103150994 571 1311867189.4729130268 0.0491312258 0.0533009673 0.0692697018 0.0053578190 0.2061590000 253226935 0 1784295424 0.1055655107 -0.0427662246 -0.1104004756 572 1311867189.5060400963 0.0490763187 0.0532935816 0.0692697018 0.0053583191 0.1972730000 253228997 0 1783226368 0.1091206446 -0.0426698253 -0.1102941856 573 1311867189.5394289494 0.0497642457 0.0532874222 0.0692697018 0.0053557098 0.2289390000 253230979 0 1784913920 0.1125430986 -0.0439939424 -0.1097739860 574 1311867189.5720269680 0.0485951714 0.0532792475 0.0692697018 0.0053534217 0.2456670000 253616541 0 1783918592 0.1140183508 -0.0481686443 -0.1112960726 575 1311867189.6112909317 0.0490817577 0.0532719476 0.0692697018 0.0053502738 0.4716110000 253630315 0 1781915648 0.1200895905 -0.0468589030 -0.1120399386 576 1311867189.6424219608 0.0493260659 0.0532650971 0.0692697018 0.0053457480 0.4491900000 253631565 0 1783951360 0.1240585223 -0.0479918420 -0.1116525009 577 1311867189.6728401184 0.0476889946 0.0532554331 0.0692697018 0.0053430731 0.4387790000 253773467 0 1785438208 0.1291350871 -0.0518649556 -0.1115422696 578 1311867189.7065870762 0.0494753122 0.0532488931 0.0692697018 0.0053449592 0.3423160000 256492732 0 1782865920 0.1310838014 -0.0507916994 -0.1116672978 579 1311867189.7401719093 0.0497228280 0.0532428032 0.0692697018 0.0053403495 0.2836020000 256315618 0 1781944320 0.1360363960 -0.0505379438 -0.1106062382 580 1311867189.7729759216 0.0500298776 0.0532372637 0.0692697018 0.0053364353 0.4476380000 255197814 0 1780109312 0.1410556138 -0.0495906770 -0.1099819764 581 1311867189.8073968887 0.0500588566 0.0532317931 0.0692697018 0.0053387063 0.2014170000 253617647 0 1780166656 0.1435719430 -0.0523917712 -0.1079081893 582 1311867189.8405311108 0.0505085774 0.0532271140 0.0692697018 0.0053353806 0.1968840000 253619653 0 1781960704 0.1478736848 -0.0521024764 -0.1066541970 583 1311867189.8713529110 0.0496438071 0.0532209677 0.0692697018 0.0053324595 0.2087600000 253621691 0 1783570432 0.1513705254 -0.0543432981 -0.1058748066 584 1311867189.9102680683 0.0508603975 0.0532169256 0.0692697018 0.0053333587 0.2065250000 253623889 0 1785221120 0.1533152163 -0.0544248261 -0.1050076783 585 1311867189.9402260780 0.0496838316 0.0532108861 0.0692697018 0.0053289799 0.2079130000 253625847 0 1784250368 0.1569494605 -0.0543643944 -0.1059032455 586 1311867189.9727621078 0.0497903228 0.0532050490 0.0692697018 0.0053245571 0.2088360000 253627861 0 1783214080 0.1607324034 -0.0546864644 -0.1051699966 587 1311867190.0107009411 0.0501973294 0.0531999251 0.0692697018 0.0053224049 0.2033320000 253629883 0 1784991744 0.1646770984 -0.0558548681 -0.1042946503 588 1311867190.0402929783 0.0489047356 0.0531926204 0.0692697018 0.0053191536 0.2041100000 253631953 0 1783472128 0.1696669310 -0.0565331466 -0.1048792079 589 1311867190.0719039440 0.0503483564 0.0531877914 0.0692697018 0.0053166277 0.2042840000 253634071 0 1782345728 0.1703337580 -0.0576801300 -0.1041091233 590 1311867190.1096539497 0.0500213206 0.0531824245 0.0692697018 0.0053162927 0.2417310000 253636061 0 1783959552 0.1738290191 -0.0599478707 -0.1042949483 591 1311867190.1396369934 0.0495515466 0.0531762809 0.0692697018 0.0053123606 0.1978990000 253637835 0 1785126912 0.1782262772 -0.0599980131 -0.1047209352 592 1311867190.1706380844 0.0496024080 0.0531702439 0.0692697018 0.0053186350 0.2362430000 254079509 0 1784102912 0.1802814305 -0.0613714531 -0.1048579663 593 1311867190.2096021175 0.0498784967 0.0531646929 0.0692697018 0.0053159170 0.4527140000 254048183 0 1781989376 0.1814059019 -0.0640423074 -0.1053948700 594 1311867190.2394330502 0.0497559980 0.0531589544 0.0692697018 0.0053177396 0.4178260000 254050429 0 1784197120 0.1850981861 -0.0618621558 -0.1066967919 595 1311867190.2714810371 0.0496294908 0.0531530225 0.0692697018 0.0053204681 0.4171110000 254195555 0 1783791616 0.1879710853 -0.0638876036 -0.1060451120 596 1311867190.3072700500 0.0505919009 0.0531487253 0.0692697018 0.0053188174 0.3592830000 256927192 0 1782845440 0.1896136701 -0.0645089447 -0.1056065410 597 1311867190.3414731026 0.0497715548 0.0531430684 0.0692697018 0.0053154399 0.2919990000 256805426 0 1778343936 0.1937293112 -0.0635600165 -0.1064899862 598 1311867190.3716828823 0.0494477712 0.0531368890 0.0692697018 0.0053191269 0.4529820000 255634274 0 1776623616 0.1985022426 -0.0620937571 -0.1061380506 599 1311867190.4101090431 0.0492942035 0.0531304738 0.0692697018 0.0053157805 0.2055450000 254036919 0 1776967680 0.2013313174 -0.0627844706 -0.1060305536 600 1311867190.4394960403 0.0495626815 0.0531245275 0.0692697018 0.0053150685 0.2091530000 254039005 0 1778634752 0.2052152604 -0.0605175942 -0.1058140770 601 1311867190.4708199501 0.0507041290 0.0531205002 0.0692697018 0.0053126150 0.2066550000 254040923 0 1780113408 0.2060709894 -0.0621089824 -0.1041222438 602 1311867190.5097529888 0.0495741777 0.0531146093 0.0692697018 0.0053094800 0.2077400000 254043137 0 1781637120 0.2091649026 -0.0637238994 -0.1041562632 603 1311867190.5405189991 0.0499678180 0.0531093908 0.0692697018 0.0053094652 0.2098530000 254044999 0 1783668736 0.2125837803 -0.0618273914 -0.1041094661 604 1311867190.5708439350 0.0506390147 0.0531053007 0.0692697018 0.0053082495 0.2050180000 254047093 0 1785446400 0.2137981802 -0.0636136904 -0.1026386619 605 1311867190.6067750454 0.0495971069 0.0530995021 0.0692697018 0.0053041864 0.1940600000 254048955 0 1784348672 0.2171416432 -0.0651425272 -0.1024966910 606 1311867190.6389939785 0.0498004481 0.0530940581 0.0692697018 0.0053007224 0.2032210000 254051081 0 1782915072 0.2191290855 -0.0637436435 -0.1026994810 607 1311867190.6723659039 0.0500103869 0.0530889779 0.0692697018 0.0052968224 0.2349300000 254053015 0 1784692736 0.2231256962 -0.0653983280 -0.1008955687 608 1311867190.7114980221 0.0517952070 0.0530868500 0.0692697018 0.0052998526 0.2040860000 254055165 0 1783349248 0.2242616117 -0.0644116327 -0.0995726660 609 1311867190.7392649651 0.0503546000 0.0530823635 0.0692697018 0.0052989093 0.2017430000 254057075 0 1782427648 0.2269000560 -0.0654317364 -0.0999075249 610 1311867190.7751801014 0.0512259938 0.0530793203 0.0692697018 0.0052951951 0.2004970000 254059089 0 1784078336 0.2296385765 -0.0645910501 -0.0984409750 611 1311867190.8070900440 0.0509204492 0.0530757870 0.0692697018 0.0052915948 0.2043140000 254061311 0 1783459840 0.2312648743 -0.0660153702 -0.0978911147 612 1311867190.8414280415 0.0502191670 0.0530711193 0.0692697018 0.0052933750 0.2032350000 254063437 0 1782423552 0.2343349457 -0.0685029998 -0.0966380984 613 1311867190.8739249706 0.0505233593 0.0530669631 0.0692697018 0.0052904179 0.1988550000 254065187 0 1783840768 0.2377146333 -0.0682881474 -0.0955972522 614 1311867190.9076139927 0.0495700017 0.0530612677 0.0692697018 0.0052870652 0.1988530000 254067217 0 1785319424 0.2395667881 -0.0690680593 -0.0959616303 615 1311867190.9393599033 0.0503342822 0.0530568336 0.0692697018 0.0052829480 0.1982430000 254069039 0 1784856576 0.2410282493 -0.0707613677 -0.0944437534 616 1311867190.9741609097 0.0491263904 0.0530504530 0.0692697018 0.0052788929 0.2040320000 254071269 0 1783549952 0.2445030957 -0.0724027157 -0.0943417996 617 1311867191.0085949898 0.0499078669 0.0530453597 0.0692697018 0.0052799919 0.2054880000 254073099 0 1785348096 0.2473102510 -0.0690995976 -0.0941805691 618 1311867191.0396919250 0.0490998998 0.0530389754 0.0692697018 0.0052799518 0.2025130000 254075137 0 1784475648 0.2503961921 -0.0713899210 -0.0927381143 619 1311867191.0764329433 0.0510101393 0.0530356978 0.0692697018 0.0052829558 0.2073300000 254077431 0 1783443456 0.2505245507 -0.0734336749 -0.0903893262 620 1311867191.1103041172 0.0510336868 0.0530324688 0.0692697018 0.0052889209 0.1934580000 254079365 0 1785110528 0.2548325956 -0.0712556764 -0.0902849361 621 1311867191.1388139725 0.0494072326 0.0530266310 0.0692697018 0.0053123983 0.2321440000 254524579 0 1784348672 0.2579611838 -0.0733661875 -0.0900172442 622 1311867191.1742820740 0.0496985950 0.0530212805 0.0692697018 0.0053096750 0.4540870000 254498685 0 1782382592 0.2600101829 -0.0758241192 -0.0882642791 623 1311867191.2077920437 0.0503211878 0.0530169465 0.0692697018 0.0053058352 0.4095970000 254500763 0 1784033280 0.2634235919 -0.0743840560 -0.0870829821 624 1311867191.2408421040 0.0526607111 0.0530163756 0.0692697018 0.0053048762 0.4138520000 254503105 0 1785749504 0.2647178173 -0.0749666765 -0.0841966197 625 1311867191.2769579887 0.0523163341 0.0530152555 0.0692697018 0.0053019642 0.4231690000 255902454 0 1783775232 0.2677986920 -0.0763977170 -0.0835783109 626 1311867191.3085029125 0.0519077033 0.0530134863 0.0692697018 0.0053019800 0.3594260000 257181400 0 1783717888 0.2719583511 -0.0733376220 -0.0840068907 627 1311867191.3404779434 0.0527989604 0.0530131441 0.0692697018 0.0052992228 0.2440090000 257313418 0 1785806848 0.2724192441 -0.0761405975 -0.0819897279 628 1311867191.3794629574 0.0549767725 0.0530162709 0.0692697018 0.0052955909 0.4203100000 256148502 0 1783648256 0.2740022838 -0.0764556602 -0.0791342854 629 1311867191.4091579914 0.0529177673 0.0530161143 0.0692697018 0.0052938487 0.2015640000 254511907 0 1783504896 0.2785064280 -0.0785963237 -0.0790965706 630 1311867191.4415969849 0.0520721562 0.0530146160 0.0692697018 0.0052905008 0.2098940000 254513641 0 1785307136 0.2821655869 -0.0772697702 -0.0792919099 631 1311867191.4775309563 0.0525711998 0.0530139132 0.0692697018 0.0052902358 0.2074450000 254515527 0 1784324096 0.2835339308 -0.0794626549 -0.0774505362 632 1311867191.5075590611 0.0521294475 0.0530125138 0.0692697018 0.0052871685 0.2068730000 254517829 0 1782779904 0.2848594785 -0.0781524032 -0.0777809024 633 1311867191.5390620232 0.0516363159 0.0530103397 0.0692697018 0.0052833833 0.2026410000 254519683 0 1784520704 0.2881079018 -0.0796812624 -0.0764815211 634 1311867191.5764698982 0.0530254096 0.0530103634 0.0692697018 0.0052802557 0.2032450000 254521561 0 1783541760 0.2893889546 -0.0789562538 -0.0748936385 635 1311867191.6118669510 0.0531728454 0.0530106193 0.0692697018 0.0053016743 0.1979170000 254523911 0 1782525952 0.2919554114 -0.0784873068 -0.0736748725 636 1311867191.6451880932 0.0540650673 0.0530122773 0.0692697018 0.0052986673 0.2007990000 254525749 0 1784414208 0.2930691838 -0.0785715356 -0.0719128102 637 1311867191.6827919483 0.0535187386 0.0530130723 0.0692697018 0.0052963948 0.2367380000 254928487 0 1783414784 0.2955882251 -0.0786748827 -0.0711309910 638 1311867191.7119400501 0.0527407937 0.0530126456 0.0692697018 0.0052938788 0.4684980000 254940813 0 1781571584 0.2980816066 -0.0780720338 -0.0709994063 639 1311867191.7457199097 0.0525423512 0.0530119096 0.0692697018 0.0053070126 0.4459210000 254943143 0 1783742464 0.2988784015 -0.0797708184 -0.0692194402 640 1311867191.7763800621 0.0541810095 0.0530137363 0.0692697018 0.0053161024 0.4480710000 255093293 0 1785262080 0.2994467318 -0.0788571537 -0.0675172582 641 1311867191.8097250462 0.0528312810 0.0530134517 0.0692697018 0.0053139301 0.4230390000 258103182 0 1782665216 0.3016408384 -0.0786556229 -0.0677920878 642 1311867191.8395779133 0.0535691008 0.0530143172 0.0692697018 0.0053169942 0.3726390000 257976596 0 1782317056 0.3030093014 -0.0794994086 -0.0656044409 643 1311867191.8745219707 0.0540839322 0.0530159806 0.0692697018 0.0053185317 0.2315260000 257965626 0 1783967744 0.3037747145 -0.0786610469 -0.0645801798 644 1311867191.9077119827 0.0521742739 0.0530146736 0.0692697018 0.0053158959 0.4647200000 256801258 0 1780412416 0.3058305383 -0.0783339813 -0.0655073896 645 1311867191.9391601086 0.0523822792 0.0530136932 0.0692697018 0.0053119286 0.2068510000 254952571 0 1780912128 0.3072272539 -0.0795338824 -0.0641850680 646 1311867191.9755239487 0.0533225685 0.0530141713 0.0692697018 0.0053141652 0.2123950000 254954761 0 1782689792 0.3087862432 -0.0776488185 -0.0627471805 647 1311867192.0076289177 0.0518566743 0.0530123823 0.0692697018 0.0053133565 0.2118150000 254956503 0 1784033280 0.3096072674 -0.0804682150 -0.0625602752 648 1311867192.0447950363 0.0520904139 0.0530109595 0.0692697018 0.0053202137 0.2085130000 254958461 0 1783701504 0.3106674254 -0.0834730268 -0.0602031574 649 1311867192.0751929283 0.0527261421 0.0530105206 0.0692697018 0.0053211888 0.2031210000 254960779 0 1783066624 0.3121028841 -0.0805366337 -0.0598463304 650 1311867192.1073920727 0.0525036231 0.0530097408 0.0692697018 0.0053198342 0.2113170000 254962585 0 1784811520 0.3142999411 -0.0796741024 -0.0595555566 651 1311867192.1433029175 0.0524468012 0.0530088761 0.0692697018 0.0053263642 0.2023050000 254964495 0 1783959552 0.3141716123 -0.0841026530 -0.0576958396 652 1311867192.1754670143 0.0515663959 0.0530066637 0.0692697018 0.0053287676 0.2025200000 254966429 0 1783447552 0.3166925907 -0.0820417106 -0.0584004894 653 1311867192.2077538967 0.0521111116 0.0530052922 0.0692697018 0.0053254746 0.2037310000 254968435 0 1785061376 0.3184430897 -0.0821837485 -0.0568265617 654 1311867192.2451250553 0.0525736660 0.0530046323 0.0692697018 0.0053267808 0.2033720000 254970705 0 1784594432 0.3193656206 -0.0849391595 -0.0544181466 655 1311867192.2744629383 0.0519751683 0.0530030606 0.0692697018 0.0053227383 0.2049900000 254972527 0 1783828480 0.3220556676 -0.0833891183 -0.0544386059 656 1311867192.3067719936 0.0519856513 0.0530015096 0.0692697018 0.0053208735 0.2055770000 254974437 0 1785229312 0.3240432441 -0.0843858570 -0.0533480793 657 1311867192.3427391052 0.0533703305 0.0530020710 0.0692697018 0.0053171457 0.2064900000 254976707 0 1784938496 0.3241265714 -0.0859681591 -0.0516198650 658 1311867192.3755910397 0.0530709289 0.0530021756 0.0692697018 0.0053170630 0.2015180000 254978689 0 1784463360 0.3267443180 -0.0845253095 -0.0520459637 659 1311867192.4059340954 0.0538246334 0.0530034237 0.0692697018 0.0053132059 0.2000290000 254980759 0 1783959552 0.3290795684 -0.0854649097 -0.0502803065 660 1311867192.4447100163 0.0536557101 0.0530044120 0.0692697018 0.0053114014 0.1996580000 254982813 0 1783578624 0.3316988945 -0.0875983760 -0.0498282537 661 1311867192.4748210907 0.0530595593 0.0530044954 0.0692697018 0.0053086055 0.2050150000 254984899 0 1785229312 0.3346028328 -0.0868878812 -0.0503874049 662 1311867192.5077190399 0.0540076122 0.0530060107 0.0692697018 0.0053053154 0.2005960000 254986745 0 1784721408 0.3363451362 -0.0876619741 -0.0490869395 663 1311867192.5427820683 0.0541657694 0.0530077600 0.0692697018 0.0053022473 0.1996640000 254988839 0 1783812096 0.3377055228 -0.0891970471 -0.0485109948 664 1311867192.5787169933 0.0545779802 0.0530101248 0.0692697018 0.0053020375 0.2012690000 254990757 0 1785462784 0.3388004303 -0.0877850577 -0.0491661020 665 1311867192.6109929085 0.0541377924 0.0530118205 0.0692697018 0.0053009051 0.2298510000 254992835 0 1784684544 0.3401547670 -0.0891374797 -0.0491058603 666 1311867192.6435210705 0.0558130443 0.0530160265 0.0692697018 0.0052995321 0.2038630000 254995089 0 1784594432 0.3402513862 -0.0909128636 -0.0473465621 667 1311867192.6790139675 0.0545959435 0.0530183952 0.0692697018 0.0052960649 0.2050810000 254997047 0 1783930880 0.3435696363 -0.0891832933 -0.0485713258 668 1311867192.7113289833 0.0561775267 0.0530231245 0.0692697018 0.0052955973 0.1964190000 254999013 0 1783156736 0.3437665999 -0.0892644003 -0.0470893458 669 1311867192.7439620495 0.0545306206 0.0530253778 0.0692697018 0.0053020345 0.2052130000 255001043 0 1784827904 0.3448373377 -0.0922213420 -0.0478619374 670 1311867192.7760629654 0.0541897714 0.0530271157 0.0692697018 0.0053020056 0.1952040000 255003081 0 1783685120 0.3474277854 -0.0900923237 -0.0479724966 671 1311867192.8091869354 0.0551269911 0.0530302452 0.0692697018 0.0052984583 0.2009390000 255004967 0 1782943744 0.3485815823 -0.0905979872 -0.0464828908 672 1311867192.8422288895 0.0561334714 0.0530348631 0.0692697018 0.0052961947 0.2430160000 255418609 0 1784975360 0.3483082354 -0.0910894647 -0.0456318967 673 1311867192.8792889118 0.0555381142 0.0530385826 0.0692697018 0.0052940195 0.4758280000 255423931 0 1784459264 0.3504085541 -0.0902822316 -0.0457014143 674 1311867192.9092190266 0.0548843518 0.0530413212 0.0692697018 0.0052908272 0.4283580000 255429609 0 1786249216 0.3519818187 -0.0915486515 -0.0452810675 675 1311867192.9434111118 0.0567037240 0.0530467469 0.0692697018 0.0052871582 0.4274550000 255427747 0 1784619008 0.3512166142 -0.0926225036 -0.0437493697 676 1311867192.9776289463 0.0548288412 0.0530493832 0.0692697018 0.0052846380 0.4264950000 256785984 0 1783832576 0.3545961380 -0.0910096243 -0.0452972129 677 1311867193.0086810589 0.0551471263 0.0530524818 0.0692697018 0.0052830099 0.3118190000 258698802 0 1784086528 0.3555021584 -0.0924507231 -0.0437530130 678 1311867193.0430600643 0.0554218031 0.0530559763 0.0692697018 0.0052799067 0.3041330000 258617196 0 1783705600 0.3553818464 -0.0953193381 -0.0430577546 679 1311867193.0767369270 0.0559741929 0.0530602742 0.0692697018 0.0052863307 0.4610490000 257448580 0 1778737152 0.3572284281 -0.0917362943 -0.0435211733 680 1311867193.1105849743 0.0561605506 0.0530648334 0.0692697018 0.0052838961 0.2249220000 255438809 0 1778933760 0.3587656021 -0.0920742452 -0.0427234471 681 1311867193.1429219246 0.0560555607 0.0530692251 0.0692697018 0.0052830102 0.2377440000 255440831 0 1780588544 0.3591364026 -0.0953067914 -0.0413342044 682 1311867193.1767370701 0.0561483502 0.0530737399 0.0692697018 0.0052957666 0.2105710000 255442621 0 1782329344 0.3620169163 -0.0908637568 -0.0424090661 683 1311867193.2122681141 0.0573477596 0.0530799976 0.0692697018 0.0052978216 0.2107680000 255444971 0 1783980032 0.3621496260 -0.0938581228 -0.0401070863 684 1311867193.2432429790 0.0553005040 0.0530832440 0.0692697018 0.0052966631 0.2080620000 255447129 0 1785647104 0.3649616539 -0.0938267782 -0.0415669270 685 1311867193.2773900032 0.0572169498 0.0530892786 0.0692697018 0.0052954828 0.2097330000 255449191 0 1784868864 0.3656000197 -0.0918191522 -0.0403071605 686 1311867193.3139379025 0.0573452972 0.0530954827 0.0692697018 0.0052961965 0.2066120000 255450981 0 1784377344 0.3663648665 -0.0946447700 -0.0394138843 687 1311867193.3426671028 0.0562602840 0.0531000894 0.0692697018 0.0052962610 0.2003060000 255452955 0 1783582720 0.3686559796 -0.0938151628 -0.0403222702 688 1311867193.3788230419 0.0553120971 0.0531033045 0.0692697018 0.0052927530 0.2054300000 255454801 0 1782689792 0.3709200025 -0.0940500721 -0.0407559611 689 1311867193.4126739502 0.0556734391 0.0531070348 0.0692697018 0.0052975488 0.2052200000 255456703 0 1784483840 0.3721771836 -0.0952771381 -0.0400858149 690 1311867193.4440810680 0.0566309392 0.0531121419 0.0692697018 0.0053018477 0.2029930000 255458885 0 1783762944 0.3736481071 -0.0937514901 -0.0396581180 691 1311867193.4782969952 0.0570887104 0.0531178967 0.0692697018 0.0052983735 0.2072500000 255460899 0 1782603776 0.3751159608 -0.0922092274 -0.0399008282 692 1311867193.5199069977 0.0575523861 0.0531243049 0.0692697018 0.0052961922 0.1987400000 255463113 0 1784233984 0.3765597939 -0.0951206014 -0.0387019776 693 1311867193.5431120396 0.0562631600 0.0531288343 0.0692697018 0.0052950312 0.2004140000 255464919 0 1783492608 0.3786257803 -0.0941965133 -0.0400535762 694 1311867193.5765709877 0.0566997640 0.0531339797 0.0692697018 0.0052921443 0.2007660000 255467165 0 1782456320 0.3795370162 -0.0935572088 -0.0402279980 695 1311867193.6127800941 0.0569290742 0.0531394403 0.0692697018 0.0052889049 0.2055750000 255468979 0 1783709696 0.3807528019 -0.0959382951 -0.0394905955 696 1311867193.6461451054 0.0580491833 0.0531464945 0.0692697018 0.0052890612 0.2039680000 255471009 0 1785606144 0.3820373714 -0.0953797400 -0.0384458750 697 1311867193.6757860184 0.0582334436 0.0531537928 0.0692697018 0.0052855961 0.2426130000 255901027 0 1784143872 0.3837926686 -0.0933549404 -0.0389566049 698 1311867193.7122890949 0.0581447892 0.0531609433 0.0692697018 0.0052833067 0.4792170000 255917817 0 1782288384 0.3840927780 -0.0962109640 -0.0386226438 699 1311867193.7430191040 0.0588308387 0.0531690547 0.0692697018 0.0052819329 0.4567080000 255920439 0 1784020992 0.3862717152 -0.0942891315 -0.0379131958 700 1311867193.7760169506 0.0568548776 0.0531743202 0.0692697018 0.0052787935 0.4436470000 255921541 0 1785790464 0.3889135122 -0.0942794606 -0.0396071784 701 1311867193.8139710426 0.0588587187 0.0531824291 0.0692697018 0.0052752719 0.4256470000 257100998 0 1785077760 0.3881332278 -0.0966158584 -0.0379289910 702 1311867193.8436760902 0.0577244163 0.0531888992 0.0692697018 0.0052736675 0.2994640000 259495472 0 1783795712 0.3909922540 -0.0956863761 -0.0387114584 703 1311867193.8771181107 0.0588233583 0.0531969141 0.0692697018 0.0052706201 0.2904030000 259361262 0 1782976512 0.3924229741 -0.0945061892 -0.0381931588 704 1311867193.9151229858 0.0579802096 0.0532037085 0.0692697018 0.0052686270 0.5099520000 258170952 0 1778950144 0.3930192292 -0.0969713777 -0.0391511768 705 1311867193.9425311089 0.0593809001 0.0532124705 0.0692697018 0.0052701020 0.2591340000 255928667 0 1779478528 0.3935238719 -0.0950729623 -0.0385107957 706 1311867193.9781770706 0.0583598875 0.0532197615 0.0692697018 0.0052686867 0.2131060000 255930729 0 1780842496 0.3951791823 -0.0955195129 -0.0396957621 707 1311867194.0148570538 0.0589496270 0.0532278660 0.0692697018 0.0052652946 0.2070930000 255932943 0 1782906880 0.3968573213 -0.0971057191 -0.0385469161 708 1311867194.0433440208 0.0587845221 0.0532357143 0.0692697018 0.0052633545 0.2123890000 255934509 0 1784520704 0.3983183801 -0.0956822932 -0.0393476523 709 1311867194.0746119022 0.0586550385 0.0532433580 0.0692697018 0.0052602537 0.2124800000 255936835 0 1783783424 0.4003180265 -0.0957663506 -0.0388207063 710 1311867194.1131060123 0.0602404587 0.0532532130 0.0692697018 0.0052567694 0.2022780000 255938769 0 1782607872 0.4003076851 -0.0963764712 -0.0372362472 711 1311867194.1428558826 0.0587598719 0.0532609580 0.0692697018 0.0052538565 0.2064590000 255940967 0 1784651776 0.4017467499 -0.0960646719 -0.0386054777 712 1311867194.1758549213 0.0587554574 0.0532686750 0.0692697018 0.0052595225 0.2048350000 255942477 0 1783762944 0.4022915065 -0.0948904157 -0.0382435992 713 1311867194.2138450146 0.0591940880 0.0532769855 0.0692697018 0.0052566997 0.2043350000 255944875 0 1782751232 0.4024485350 -0.0969535112 -0.0371061116 714 1311867194.2451140881 0.0571952462 0.0532824733 0.0692697018 0.0052532370 0.2089040000 255946785 0 1784401920 0.4052815735 -0.0949808508 -0.0387355164 715 1311867194.2760241032 0.0584445372 0.0532896929 0.0692697018 0.0052498940 0.2081690000 255948743 0 1783296000 0.4048017561 -0.0956989899 -0.0372029655 716 1311867194.3139200211 0.0597661994 0.0532987383 0.0692697018 0.0052486770 0.2042530000 255950741 0 1782226944 0.4049558342 -0.0965214744 -0.0357926749 717 1311867194.3447821140 0.0590415001 0.0533067478 0.0692697018 0.0052477373 0.2045790000 255952891 0 1784004608 0.4058247209 -0.0949917138 -0.0365852192 718 1311867194.3802230358 0.0587978885 0.0533143956 0.0692697018 0.0052454446 0.2029050000 255954569 0 1785663488 0.4064536393 -0.0951859057 -0.0364632681 719 1311867194.4124519825 0.0596577525 0.0533232181 0.0692697018 0.0052429512 0.2066810000 255956751 0 1784930304 0.4053896368 -0.0973598510 -0.0352707058 720 1311867194.4447510242 0.0586540513 0.0533306220 0.0692697018 0.0052393414 0.2363830000 255958557 0 1783783424 0.4074845314 -0.0966643095 -0.0357970968 721 1311867194.4805839062 0.0596256070 0.0533393529 0.0692697018 0.0052368368 0.2055450000 255960651 0 1785528320 0.4074537754 -0.0960728899 -0.0352228396 722 1311867194.5174930096 0.0594504252 0.0533478170 0.0692697018 0.0052352596 0.2059250000 255962545 0 1784676352 0.4076409638 -0.0973761752 -0.0350951590 723 1311867194.5439500809 0.0595601127 0.0533564094 0.0692697018 0.0052345306 0.2028850000 255964583 0 1783369728 0.4082399011 -0.0962444171 -0.0350806825 724 1311867194.5795979500 0.0599777400 0.0533655549 0.0692697018 0.0052311847 0.2047370000 255966645 0 1785020416 0.4082112014 -0.0970632806 -0.0342314616 725 1311867194.6129479408 0.0597142614 0.0533743117 0.0692697018 0.0052278347 0.1986430000 255968635 0 1783660544 0.4087945819 -0.0975131840 -0.0340720862 726 1311867194.6493880749 0.0582294799 0.0533809993 0.0692697018 0.0052357385 0.1957720000 255970377 0 1782644736 0.4095309675 -0.0957274437 -0.0358006693 727 1311867194.6784319878 0.0586150028 0.0533881987 0.0692697018 0.0052357749 0.2033840000 255972735 0 1784258560 0.4103904963 -0.0969615206 -0.0339355357 728 1311867194.7133309841 0.0583024323 0.0533949490 0.0692697018 0.0052339334 0.2035670000 255974805 0 1783169024 0.4103748798 -0.0978653878 -0.0339537263 729 1311867194.7475099564 0.0582187846 0.0534015661 0.0692697018 0.0052305835 0.2018700000 255976419 0 1782132736 0.4112431705 -0.0969465077 -0.0338422954 730 1311867194.7784450054 0.0600845739 0.0534107209 0.0692697018 0.0052282690 0.2065010000 255978513 0 1783877632 0.4117164016 -0.0953789726 -0.0318945497 731 1311867194.8130390644 0.0582678728 0.0534173654 0.0692697018 0.0052259263 0.1979740000 255980567 0 1785536512 0.4117130637 -0.0972158611 -0.0333216935 732 1311867194.8476719856 0.0592164621 0.0534252877 0.0692697018 0.0052228914 0.2003190000 255982589 0 1784766464 0.4119094908 -0.0965226814 -0.0321594775 733 1311867194.8814148903 0.0591107905 0.0534330442 0.0692697018 0.0052195751 0.1974290000 255984707 0 1783386112 0.4112288952 -0.0964897051 -0.0322447941 734 1311867194.9104089737 0.0598825179 0.0534418309 0.0692697018 0.0052280594 0.2004680000 255986353 0 1785020416 0.4119596183 -0.0951439291 -0.0309322439 735 1311867194.9451448917 0.0594312884 0.0534499799 0.0692697018 0.0052251159 0.2028680000 255988655 0 1784291328 0.4102047682 -0.0964379534 -0.0313703381 736 1311867194.9787399769 0.0598063767 0.0534586163 0.0692697018 0.0052216493 0.2019870000 255990397 0 1783279616 0.4101518989 -0.0958471522 -0.0306207761 737 1311867195.0132799149 0.0593036413 0.0534665471 0.0692697018 0.0052207168 0.2152210000 255992451 0 1784893440 0.4093590081 -0.0952888653 -0.0307839029 738 1311867195.0464940071 0.0584626719 0.0534733169 0.0692697018 0.0052196684 0.2078410000 255994313 0 1783787520 0.4084633887 -0.0964000672 -0.0318462178 739 1311867195.0781710148 0.0590862557 0.0534809122 0.0692697018 0.0052196150 0.1997740000 255996399 0 1782788096 0.4076763988 -0.0959284306 -0.0312420763 740 1311867195.1115310192 0.0581829101 0.0534872663 0.0692697018 0.0052175019 0.2080800000 255998373 0 1784385536 0.4081200957 -0.0957766995 -0.0318232290 741 1311867195.1458311081 0.0596398301 0.0534955693 0.0692697018 0.0052149535 0.2122280000 256000419 0 1783660544 0.4059349597 -0.0962484702 -0.0307587981 742 1311867195.1780319214 0.0583682768 0.0535021363 0.0692697018 0.0052123722 0.1982960000 256002209 0 1782374400 0.4056793451 -0.0945425108 -0.0323678143 743 1311867195.2114748955 0.0595330931 0.0535102534 0.0692697018 0.0052109868 0.2304450000 256004399 0 1784004608 0.4040940702 -0.0940891653 -0.0308918469 744 1311867195.2436800003 0.0581714734 0.0535165184 0.0692697018 0.0052114392 0.2038470000 256006157 0 1785663488 0.4039037526 -0.0954980850 -0.0319531672 745 1311867195.2780399323 0.0575622953 0.0535219490 0.0692697018 0.0052085437 0.2065130000 256008467 0 1784930304 0.4033982158 -0.0952271447 -0.0324366651 746 1311867195.3123180866 0.0576770715 0.0535275189 0.0692697018 0.0052053101 0.2133140000 256010745 0 1784152064 0.4021111429 -0.0948777422 -0.0328456499 747 1311867195.3425979614 0.0577813610 0.0535332135 0.0692697018 0.0052055187 0.2032980000 256012479 0 1785798656 0.3999380469 -0.0978306830 -0.0326956362 748 1311867195.3782711029 0.0585796051 0.0535399600 0.0692697018 0.0052048062 0.2116780000 256014133 0 1785057280 0.3991246819 -0.0953442976 -0.0327459872 749 1311867195.4119830132 0.0569985770 0.0535445776 0.0692697018 0.0052021754 0.2084440000 256016299 0 1782775808 0.3985695541 -0.0957187116 -0.0343847834 750 1311867195.4435520172 0.0581717044 0.0535507471 0.0692697018 0.0051993978 0.2050110000 256018361 0 1781981184 0.3956962526 -0.0960379615 -0.0338404924 751 1311867195.4788239002 0.0579133853 0.0535565562 0.0692697018 0.0051964344 0.2068630000 256020223 0 1783795712 0.3947179317 -0.0938502625 -0.0347434953 752 1311867195.5113179684 0.0579770096 0.0535624345 0.0692697018 0.0051938089 0.2045660000 256022269 0 1785409536 0.3939766586 -0.0938105062 -0.0345656537 753 1311867195.5439620018 0.0579579398 0.0535682718 0.0692697018 0.0051910589 0.2076900000 256024395 0 1784647680 0.3911045790 -0.0960772559 -0.0341212340 754 1311867195.5782160759 0.0576497652 0.0535736849 0.0692697018 0.0051890122 0.2133490000 256026257 0 1784139776 0.3905378878 -0.0942025259 -0.0348062254 755 1311867195.6119859219 0.0574214980 0.0535787814 0.0692697018 0.0051883526 0.2104760000 256028271 0 1785790464 0.3883454800 -0.0951714292 -0.0350759290 756 1311867195.6430909634 0.0578658618 0.0535844521 0.0692697018 0.0051855654 0.2030440000 256030269 0 1784647680 0.3857981563 -0.0970813856 -0.0342327505 757 1311867195.6779129505 0.0584673695 0.0535909025 0.0692697018 0.0051842051 0.2090430000 256032299 0 1783885824 0.3846185505 -0.0947073326 -0.0342699811 758 1311867195.7107300758 0.0581325367 0.0535968941 0.0692697018 0.0051837706 0.2106070000 256034225 0 1785569280 0.3828524649 -0.0941295251 -0.0347499549 759 1311867195.7458300591 0.0586300306 0.0536035253 0.0692697018 0.0051806366 0.2182340000 256035999 0 1784897536 0.3801763654 -0.0950943232 -0.0341200642 760 1311867195.7821879387 0.0573604070 0.0536084686 0.0692697018 0.0051775708 0.2187580000 256038005 0 1784266752 0.3789183199 -0.0948400125 -0.0355260968 761 1311867195.8100500107 0.0577893108 0.0536139625 0.0692697018 0.0051747588 0.2122860000 256040123 0 1782906880 0.3774708509 -0.0949175283 -0.0349586792 762 1311867195.8458549976 0.0575741678 0.0536191596 0.0692697018 0.0051714664 0.2061810000 256042081 0 1784901632 0.3741603494 -0.0960027277 -0.0356889963 763 1311867195.8778660297 0.0566433854 0.0536231232 0.0692697018 0.0051689575 0.2170160000 256044167 0 1784430592 0.3740015626 -0.0944153517 -0.0362395272 764 1311867195.9098269939 0.0580642708 0.0536289362 0.0692697018 0.0051661755 0.2128320000 256046397 0 1783541760 0.3708547056 -0.0945219249 -0.0352589376 765 1311867195.9458460808 0.0574358180 0.0536339125 0.0692697018 0.0051630835 0.2450820000 256048011 0 1785319424 0.3689688444 -0.0950935483 -0.0357079469 766 1311867195.9778430462 0.0573683083 0.0536387877 0.0692697018 0.0051609395 0.2163920000 256050217 0 1784430592 0.3686941862 -0.0936156958 -0.0354125872 767 1311867196.0100569725 0.0571505502 0.0536433663 0.0692697018 0.0051588925 0.2163960000 256052071 0 1783631872 0.3671326041 -0.0935966969 -0.0357875824 768 1311867196.0498790741 0.0565746240 0.0536471830 0.0692697018 0.0051559023 0.2120780000 256054093 0 1785319424 0.3661062717 -0.0943005085 -0.0359157361 769 1311867196.0793108940 0.0569399036 0.0536514649 0.0692697018 0.0051575390 0.2161940000 256056379 0 1784520704 0.3642244637 -0.0916619077 -0.0366935283 770 1311867196.1113979816 0.0575845093 0.0536565727 0.0692697018 0.0051551725 0.2064640000 256058033 0 1783631872 0.3617959619 -0.0938825533 -0.0353871211 771 1311867196.1473290920 0.0564846955 0.0536602408 0.0692697018 0.0051520056 0.2160710000 256059959 0 1785446400 0.3615039289 -0.0930613056 -0.0363744386 772 1311867196.1811769009 0.0572927594 0.0536649462 0.0692697018 0.0051519447 0.2148600000 256062085 0 1784684544 0.3585552275 -0.0927240252 -0.0361194015 773 1311867196.2114949226 0.0579298809 0.0536704636 0.0692697018 0.0051503266 0.2164560000 256064179 0 1783762944 0.3563736975 -0.0941101313 -0.0354684480 774 1311867196.2462599277 0.0579787828 0.0536760299 0.0692697018 0.0051474994 0.2090980000 256065961 0 1785536512 0.3550317585 -0.0933133811 -0.0356195979 775 1311867196.2800569534 0.0578078590 0.0536813612 0.0692697018 0.0051443855 0.2173540000 256068039 0 1784774656 0.3538626432 -0.0928628743 -0.0356478877 776 1311867196.3111600876 0.0580674112 0.0536870134 0.0692697018 0.0051416064 0.2154990000 256069973 0 1783910400 0.3513090611 -0.0940657035 -0.0353632160 777 1311867196.3484730721 0.0574454106 0.0536918504 0.0692697018 0.0051396625 0.2131440000 256072051 0 1785683968 0.3503375351 -0.0931648836 -0.0361299627 778 1311867196.3842670918 0.0569551885 0.0536960450 0.0692697018 0.0051366591 0.2156000000 256074433 0 1784774656 0.3496144116 -0.0918874070 -0.0364152193 779 1311867196.4107549191 0.0582604222 0.0537019042 0.0692697018 0.0051342450 0.2169420000 256075991 0 1784020992 0.3463197947 -0.0929099321 -0.0353448689 780 1311867196.4463150501 0.0571987331 0.0537063873 0.0692697018 0.0051333132 0.2198280000 256078149 0 1785827328 0.3452242613 -0.0924926996 -0.0364822224 781 1311867196.4798319340 0.0563039668 0.0537097133 0.0692697018 0.0051304372 0.2183290000 256079891 0 1785065472 0.3441597521 -0.0926152468 -0.0369737744 782 1311867196.5113470554 0.0574177988 0.0537144551 0.0692697018 0.0051279976 0.2102170000 256082089 0 1784020992 0.3413840234 -0.0930909812 -0.0357159749 783 1311867196.5468420982 0.0563405715 0.0537178090 0.0692697018 0.0051255509 0.2097310000 256084007 0 1785921536 0.3408799469 -0.0910869092 -0.0360634588 784 1311867196.5795550346 0.0574218854 0.0537225336 0.0692697018 0.0051237998 0.2182490000 256086029 0 1784393728 0.3392124772 -0.0903366655 -0.0351682752 785 1311867196.6108930111 0.0558960736 0.0537253025 0.0692697018 0.0051249519 0.2161900000 256087979 0 1783402496 0.3370164633 -0.0923116952 -0.0361139253 786 1311867196.6521809101 0.0569059402 0.0537293491 0.0692697018 0.0051312426 0.2122730000 256090233 0 1785319424 0.3345764875 -0.0903182626 -0.0351606943 787 1311867196.6805100441 0.0564196296 0.0537327675 0.0692697018 0.0051434035 0.2418400000 256092055 0 1784905728 0.3336960971 -0.0889544487 -0.0346914120 788 1311867196.7112100124 0.0555817857 0.0537351139 0.0692697018 0.0051418061 0.2157760000 256094245 0 1784033280 0.3319232166 -0.0902775377 -0.0351634733 789 1311867196.7464900017 0.0555727258 0.0537374430 0.0692697018 0.0051385523 0.2042850000 256095995 0 1785446400 0.3294507861 -0.0894707814 -0.0351945050 790 1311867196.7783749104 0.0568826199 0.0537414242 0.0692697018 0.0051364461 0.2170520000 256098289 0 1785049088 0.3262476623 -0.0884665400 -0.0343262851 791 1311867196.8109180927 0.0554349609 0.0537435652 0.0692697018 0.0051370547 0.2114990000 256100231 0 1783930880 0.3252458274 -0.0897002518 -0.0346918888 792 1311867196.8488750458 0.0562017262 0.0537466690 0.0692697018 0.0051381118 0.2162910000 256102189 0 1785552896 0.3225089312 -0.0895621926 -0.0338230357 793 1311867196.8821749687 0.0553444177 0.0537486838 0.0692697018 0.0051351688 0.2133910000 256104187 0 1784655872 0.3212416470 -0.0882866159 -0.0347119756 794 1311867196.9115700722 0.0557784773 0.0537512402 0.0692697018 0.0051323869 0.2078770000 256105977 0 1783513088 0.3188006580 -0.0889962390 -0.0342289656 795 1311867196.9482440948 0.0559758358 0.0537540384 0.0692697018 0.0051294881 0.2128540000 256108327 0 1784758272 0.3166872263 -0.0888222530 -0.0338775031 796 1311867196.9809880257 0.0556418672 0.0537564101 0.0692697018 0.0051279005 0.2113800000 256110237 0 1784397824 0.3144204617 -0.0892418250 -0.0342844725 797 1311867197.0154891014 0.0560774915 0.0537593223 0.0692697018 0.0051258875 0.2127350000 256112267 0 1783660544 0.3116365671 -0.0896924511 -0.0343711376 798 1311867197.0490679741 0.0554499552 0.0537614409 0.0692697018 0.0051237535 0.2111120000 256114249 0 1785270272 0.3091375530 -0.0892080590 -0.0356278978 799 1311867197.0806479454 0.0558442883 0.0537640477 0.0692697018 0.0051211843 0.2142710000 256115975 0 1784160256 0.3073158860 -0.0889334679 -0.0354566500 800 1311867197.1148109436 0.0548038445 0.0537653475 0.0692697018 0.0051194754 0.2134040000 256118053 0 1783115776 0.3056491911 -0.0900685787 -0.0360727757 801 1311867197.1468429565 0.0562300608 0.0537684245 0.0692697018 0.0051195644 0.2179330000 256120211 0 1784893440 0.3028861880 -0.0880160034 -0.0357401483 802 1311867197.1792430878 0.0547145493 0.0537696042 0.0692697018 0.0051195818 0.2112250000 256122225 0 1784168448 0.3007792830 -0.0898717642 -0.0367076285 803 1311867197.2143619061 0.0552273206 0.0537714196 0.0692697018 0.0051192357 0.2148880000 256124367 0 1783042048 0.2984691560 -0.0902531445 -0.0359316841 804 1311867197.2459290028 0.0523500293 0.0537696517 0.0692697018 0.0051180696 0.2158330000 256126085 0 1784549376 0.2984298766 -0.0899749398 -0.0384766050 805 1311867197.2799959183 0.0572737344 0.0537740046 0.0692697018 0.0051194680 0.2159850000 256127931 0 1783787520 0.2944532037 -0.0875569731 -0.0343850888 806 1311867197.3157260418 0.0546834543 0.0537751329 0.0692697018 0.0051182602 0.2141090000 256130225 0 1782755328 0.2929405868 -0.0883639306 -0.0366415046 807 1311867197.3468708992 0.0554406270 0.0537771967 0.0692697018 0.0051155172 0.2134650000 256132327 0 1784262656 0.2902418375 -0.0882406086 -0.0360972546 808 1311867197.3784019947 0.0554501116 0.0537792672 0.0692697018 0.0051137513 0.2210570000 256134197 0 1783414784 0.2879848778 -0.0881242603 -0.0364691950 809 1311867197.4155099392 0.0545198806 0.0537801826 0.0692697018 0.0051114639 0.2439750000 256136171 0 1782509568 0.2864986658 -0.0886690915 -0.0374058783 810 1311867197.4478878975 0.0557943583 0.0537826693 0.0692697018 0.0051097483 0.2127040000 256138193 0 1784029184 0.2837877870 -0.0870795771 -0.0376274958 811 1311867197.4793179035 0.0557604060 0.0537851079 0.0692697018 0.0051075181 0.2142360000 256140287 0 1785909248 0.2813498974 -0.0890314877 -0.0375064425 812 1311867197.5150759220 0.0560979582 0.0537879563 0.0692697018 0.0051060639 0.2132910000 256142141 0 1784795136 0.2789523304 -0.0875479057 -0.0385364071 813 1311867197.5469260216 0.0551478341 0.0537896289 0.0692697018 0.0051032507 0.2180770000 256143939 0 1783885824 0.2784155905 -0.0868037120 -0.0399716832 814 1311867197.5802750587 0.0554091334 0.0537916185 0.0692697018 0.0051020168 0.2158000000 256146217 0 1785700352 0.2755850255 -0.0882799625 -0.0404936746 815 1311867197.6152749062 0.0545725264 0.0537925767 0.0692697018 0.0051001626 0.2222950000 256148055 0 1784557568 0.2739700973 -0.0883287117 -0.0420578495 816 1311867197.6470439434 0.0554120243 0.0537945613 0.0692697018 0.0050977900 0.2220110000 256150025 0 1783140352 0.2727097571 -0.0856437162 -0.0422987603 817 1311867197.6800849438 0.0556629822 0.0537968482 0.0692697018 0.0050970371 0.2187620000 256151895 0 1784938496 0.2691660821 -0.0863132551 -0.0430835672 818 1311867197.7143290043 0.0546010509 0.0537978313 0.0692697018 0.0050960379 0.2189600000 256153885 0 1782992896 0.2681067288 -0.0854465663 -0.0447520539 819 1311867197.7463419437 0.0542743094 0.0537984131 0.0692697018 0.0050957078 0.2169630000 256156307 0 1780367360 0.2667315602 -0.0847651586 -0.0456968695 820 1311867197.7793009281 0.0560627133 0.0538011745 0.0692697018 0.0050927771 0.2145330000 256157921 0 1782509568 0.2630146444 -0.0859784186 -0.0445637032 821 1311867197.8146750927 0.0545747988 0.0538021168 0.0692697018 0.0050922755 0.2150960000 256160087 0 1784147968 0.2623662055 -0.0843883231 -0.0472075418 822 1311867197.8467919827 0.0549179018 0.0538034742 0.0692697018 0.0050914871 0.2242720000 256161957 0 1783541760 0.2609658539 -0.0853305534 -0.0472294390 823 1311867197.8802978992 0.0552492887 0.0538052309 0.0692697018 0.0050900082 0.2093420000 256164051 0 1781907456 0.2582943141 -0.0857946351 -0.0477470905 824 1311867197.9148609638 0.0565389842 0.0538085486 0.0692697018 0.0050979694 0.2173260000 256165817 0 1783885824 0.2565581799 -0.0818511024 -0.0486206561 825 1311867197.9470140934 0.0546760522 0.0538096001 0.0692697018 0.0051089356 0.2157180000 256167911 0 1785655296 0.2547967136 -0.0834699869 -0.0504608490 826 1311867197.9812700748 0.0550929122 0.0538111537 0.0692697018 0.0051065849 0.2134380000 256169869 0 1784811520 0.2534193099 -0.0832890049 -0.0503316000 827 1311867198.0145471096 0.0550654568 0.0538126704 0.0692697018 0.0051047372 0.2132430000 256172347 0 1783377920 0.2509788573 -0.0819066465 -0.0515663475 828 1311867198.0463368893 0.0549963377 0.0538141000 0.0692697018 0.0051027828 0.2156620000 256173977 0 1785425920 0.2485829443 -0.0819942355 -0.0522788987 829 1311867198.0787069798 0.0550953560 0.0538156455 0.0692697018 0.0051026241 0.2153610000 256175719 0 1784430592 0.2469704747 -0.0809849426 -0.0531808734 830 1311867198.1143770218 0.0546287820 0.0538166252 0.0692697018 0.0050995629 0.2187070000 256177909 0 1783140352 0.2450416684 -0.0808327422 -0.0539725013 831 1311867198.1463611126 0.0537483580 0.0538165431 0.0692697018 0.0050980161 0.2332680000 256179827 0 1784430592 0.2430556417 -0.0810089633 -0.0554442480 832 1311867198.1822519302 0.0553995259 0.0538184457 0.0692697018 0.0050968125 0.2209870000 256181961 0 1783922688 0.2406799048 -0.0793631077 -0.0547920279 833 1311867198.2144989967 0.0544168465 0.0538191641 0.0692697018 0.0051032787 0.2079060000 256184239 0 1782906880 0.2394799441 -0.0782880709 -0.0567101389 834 1311867198.2464120388 0.0549316667 0.0538204980 0.0692697018 0.0051008892 0.2174600000 256186005 0 1784664064 0.2368046045 -0.0789172798 -0.0569104180 835 1311867198.2821578979 0.0550366528 0.0538219545 0.0692697018 0.0050998223 0.2175590000 256187843 0 1783152640 0.2341517508 -0.0768843889 -0.0582482778 836 1311867198.3159120083 0.0547054708 0.0538230113 0.0692697018 0.0050996281 0.2155820000 256190089 0 1782501376 0.2324391305 -0.0774706826 -0.0588893145 837 1311867198.3481218815 0.0544514097 0.0538237621 0.0692697018 0.0050967610 0.2182540000 256191951 0 1784000512 0.2303489894 -0.0769526437 -0.0601895303 838 1311867198.3828320503 0.0534450710 0.0538233102 0.0692697018 0.0051021765 0.2151190000 256193933 0 1783169024 0.2282345295 -0.0759315491 -0.0618703365 839 1311867198.4242680073 0.0533303656 0.0538227226 0.0692697018 0.0051063083 0.2113320000 256196027 0 1781866496 0.2258377969 -0.0745329931 -0.0631220266 840 1311867198.4497859478 0.0531887114 0.0538219679 0.0692697018 0.0051041598 0.2186710000 256197865 0 1783767040 0.2226146758 -0.0771174505 -0.0640143454 841 1311867198.4856219292 0.0525005907 0.0538203967 0.0692697018 0.0051082885 0.2181730000 256199911 0 1785536512 0.2198333740 -0.0758572221 -0.0665145814 842 1311867198.5190339088 0.0542643480 0.0538209239 0.0692697018 0.0051068118 0.2177830000 256201661 0 1784913920 0.2181230336 -0.0729815289 -0.0661064908 843 1311867198.5499279499 0.0541994385 0.0538213729 0.0692697018 0.0051057280 0.2171290000 256203795 0 1784041472 0.2137391716 -0.0756037384 -0.0666579008 844 1311867198.5824239254 0.0513704717 0.0538184690 0.0692697018 0.0051028888 0.2162830000 256205801 0 1785819136 0.2122267932 -0.0732262433 -0.0710111707 845 1311867198.6147489548 0.0528334826 0.0538173034 0.0692697018 0.0051027982 0.2158090000 256207655 0 1785020416 0.2097935677 -0.0727594569 -0.0700562522 846 1311867198.6482009888 0.0538539924 0.0538173467 0.0692697018 0.0051013009 0.2183940000 256209877 0 1784258560 0.2064170092 -0.0712988600 -0.0703495294 847 1311867198.6827540398 0.0524748266 0.0538157617 0.0692697018 0.0050985767 0.2215270000 256211667 0 1785671680 0.2038582265 -0.0714776069 -0.0725412071 848 1311867198.7146520615 0.0523567162 0.0538140411 0.0692697018 0.0050959525 0.2120400000 256213617 0 1784639488 0.2024701685 -0.0697694197 -0.0736927241 849 1311867198.7467699051 0.0521468371 0.0538120774 0.0692697018 0.0050934766 0.2178750000 256215639 0 1783660544 0.2006523460 -0.0707504377 -0.0743103549 850 1311867198.7842700481 0.0520866066 0.0538100474 0.0692697018 0.0050907036 0.2141190000 256217693 0 1785290752 0.1986406296 -0.0688055307 -0.0754759982 851 1311867198.8149418831 0.0532391444 0.0538093766 0.0692697018 0.0050884395 0.2181650000 256219635 0 1784016896 0.1962486804 -0.0683653951 -0.0751137584 852 1311867198.8464009762 0.0527966619 0.0538081879 0.0692697018 0.0050865089 0.2172180000 256221769 0 1783025664 0.1930009425 -0.0688971579 -0.0763682649 853 1311867198.8845369816 0.0526777059 0.0538068626 0.0692697018 0.0050849604 0.2158910000 256223711 0 1784635392 0.1926081181 -0.0670478940 -0.0774489790 854 1311867198.9147930145 0.0544057749 0.0538075639 0.0692697018 0.0050828353 0.2081480000 256225701 0 1783910400 0.1906242520 -0.0651988536 -0.0770301223 855 1311867198.9465179443 0.0538106523 0.0538075676 0.0692697018 0.0050801774 0.2189670000 256227411 0 1782874112 0.1881905496 -0.0647628158 -0.0786957964 856 1311867198.9839329720 0.0543847233 0.0538082418 0.0692697018 0.0050776743 0.2172510000 256229761 0 1784520704 0.1872251034 -0.0631588027 -0.0787473768 857 1311867199.0148730278 0.0536742918 0.0538080855 0.0692697018 0.0050827824 0.2282740000 256231815 0 1785827328 0.1858580858 -0.0624294877 -0.0801934972 858 1311867199.0468010902 0.0540025122 0.0538083121 0.0692697018 0.0050814901 0.2221520000 256233525 0 1781481472 0.1846358925 -0.0626091957 -0.0810816437 859 1311867199.0849320889 0.0532810055 0.0538076982 0.0692697018 0.0050800137 0.2147660000 256235675 0 1779851264 0.1845358610 -0.0605304651 -0.0830219314 860 1311867199.1149818897 0.0545239486 0.0538085311 0.0692697018 0.0050775716 0.2128790000 256237569 0 1781600256 0.1825487465 -0.0599522702 -0.0829727277 861 1311867199.1465420723 0.0538660958 0.0538085979 0.0692697018 0.0050749500 0.2154890000 256239599 0 1782779904 0.1815971285 -0.0595380068 -0.0848427564 862 1311867199.1823658943 0.0561573207 0.0538113227 0.0692697018 0.0050750033 0.2183700000 256241373 0 1784811520 0.1800390929 -0.0563076623 -0.0846097842 863 1311867199.2146680355 0.0547303371 0.0538123876 0.0692697018 0.0050731469 0.2182210000 256243555 0 1783795712 0.1792347431 -0.0572330803 -0.0868021920 864 1311867199.2467749119 0.0541870892 0.0538128213 0.0692697018 0.0050702945 0.2124230000 256245393 0 1783033856 0.1781867743 -0.0563730486 -0.0884660631 865 1311867199.2833590508 0.0546100140 0.0538137429 0.0692697018 0.0050678228 0.2219610000 256247519 0 1784684544 0.1761783212 -0.0549472272 -0.0897005647 866 1311867199.3159129620 0.0554177091 0.0538155950 0.0692697018 0.0050681030 0.2179690000 256249685 0 1783795712 0.1741146892 -0.0549482889 -0.0902357846 867 1311867199.3465209007 0.0553388074 0.0538173519 0.0692697018 0.0050652268 0.2172930000 256251171 0 1783414784 0.1720925868 -0.0545733422 -0.0918634012 868 1311867199.3829050064 0.0552003719 0.0538189453 0.0692697018 0.0050623881 0.2187360000 256253353 0 1785065472 0.1706785560 -0.0539738573 -0.0932150632 869 1311867199.4147589207 0.0547071099 0.0538199673 0.0692697018 0.0050595570 0.2205700000 256255551 0 1783758848 0.1697809696 -0.0538732037 -0.0945828259 870 1311867199.4512910843 0.0548396409 0.0538211394 0.0692697018 0.0050584234 0.2138530000 256257429 0 1783386112 0.1672510505 -0.0525909103 -0.0961671025 871 1311867199.4837360382 0.0546895079 0.0538221363 0.0692697018 0.0050569950 0.2261130000 256259323 0 1784897536 0.1659534425 -0.0521338955 -0.0972002149 872 1311867199.5150198936 0.0548525676 0.0538233180 0.0692697018 0.0050540958 0.2206940000 256261289 0 1784172544 0.1633838862 -0.0521736965 -0.0980699137 873 1311867199.5544059277 0.0574358553 0.0538274561 0.0692697018 0.0050577789 0.2220290000 256263575 0 1783513088 0.1611629725 -0.0505626090 -0.0964713395 874 1311867199.5835030079 0.0548650883 0.0538286433 0.0692697018 0.0050568404 0.2163610000 256265333 0 1785143296 0.1582900733 -0.0503465645 -0.1002002284 875 1311867199.6158308983 0.0545878857 0.0538295110 0.0692697018 0.0050548820 0.2438470000 256267107 0 1784397824 0.1562845260 -0.0498258844 -0.1007565632 876 1311867199.6538460255 0.0554356128 0.0538313445 0.0692697018 0.0050531559 0.2245180000 256269393 0 1783635968 0.1531110257 -0.0496178344 -0.1003722325 877 1311867199.6824479103 0.0536185913 0.0538311019 0.0692697018 0.0050510085 0.2168330000 256271439 0 1785430016 0.1498162746 -0.0503146388 -0.1030859351 878 1311867199.7146759033 0.0547270998 0.0538321224 0.0692697018 0.0050508096 0.2172690000 256273357 0 1784520704 0.1474061459 -0.0498433746 -0.1022083834 879 1311867199.7511539459 0.0542717539 0.0538326225 0.0692697018 0.0050503871 0.2135340000 256275339 0 1783631872 0.1450448930 -0.0491662025 -0.1031728908 880 1311867199.7826020718 0.0536075756 0.0538323668 0.0692697018 0.0050494221 0.2195360000 256277513 0 1785409536 0.1420668811 -0.0496362373 -0.1044078097 881 1311867199.8150150776 0.0538949408 0.0538324378 0.0692697018 0.0050552743 0.2151500000 256279807 0 1784303616 0.1398174763 -0.0498937964 -0.1041446626 882 1311867199.8519051075 0.0529592745 0.0538314478 0.0692697018 0.0050524430 0.2190630000 256281205 0 1783513088 0.1383564621 -0.0483397134 -0.1058008820 883 1311867199.8839609623 0.0532883964 0.0538308328 0.0692697018 0.0050528103 0.2204380000 256283403 0 1785556992 0.1355766058 -0.0488194712 -0.1057620421 884 1311867199.9148159027 0.0546703599 0.0538317825 0.0692697018 0.0050537602 0.2192740000 256285513 0 1784774656 0.1326274574 -0.0480688661 -0.1049417779 885 1311867199.9520709515 0.0525782816 0.0538303661 0.0692697018 0.0050532847 0.2209000000 256287351 0 1783128064 0.1316116899 -0.0478736497 -0.1074205562 886 1311867199.9828410149 0.0519300513 0.0538282213 0.0692697018 0.0050518775 0.2203900000 256289373 0 1785303040 0.1296898276 -0.0485474654 -0.1080213338 887 1311867200.0144031048 0.0520828776 0.0538262536 0.0692697018 0.0050492836 0.2212660000 256291419 0 1784430592 0.1269224882 -0.0481250100 -0.1082546636 888 1311867200.0539638996 0.0522583872 0.0538244880 0.0692697018 0.0050489491 0.2119660000 256293465 0 1783619584 0.1244546920 -0.0453240834 -0.1092891321 889 1311867200.0830330849 0.0520590469 0.0538225021 0.0692697018 0.0050464048 0.2185350000 256295231 0 1785298944 0.1217585653 -0.0476160310 -0.1086708605 890 1311867200.1174468994 0.0504564568 0.0538187201 0.0692697018 0.0050447457 0.2158490000 256297373 0 1784541184 0.1199567020 -0.0471583754 -0.1100413278 891 1311867200.1517000198 0.0508889332 0.0538154319 0.0692697018 0.0050437459 0.2226310000 256299419 0 1783529472 0.1183008105 -0.0456938632 -0.1096833497 892 1311867200.1853220463 0.0506625660 0.0538118972 0.0692697018 0.0050442129 0.2221710000 256301505 0 1785286656 0.1149332002 -0.0474590100 -0.1097172275 893 1311867200.2179059982 0.0513574220 0.0538091487 0.0692697018 0.0050455675 0.2176490000 256303543 0 1784270848 0.1135083660 -0.0451972298 -0.1092177853 894 1311867200.2522649765 0.0511734597 0.0538062005 0.0692697018 0.0050427696 0.2225780000 256305437 0 1783164928 0.1109766066 -0.0454418100 -0.1088196635 895 1311867200.2825429440 0.0506398082 0.0538026626 0.0692697018 0.0050407596 0.2172870000 256307355 0 1784782848 0.1082672179 -0.0462243594 -0.1086182445 896 1311867200.3148880005 0.0509445593 0.0537994728 0.0692697018 0.0050384879 0.2466930000 256309729 0 1783275520 0.1069710776 -0.0433722809 -0.1086947024 897 1311867200.3514990807 0.0514856540 0.0537968933 0.0692697018 0.0050374923 0.2252680000 256311359 0 1782349824 0.1032728255 -0.0446874648 -0.1074767113 898 1311867200.3837759495 0.0514986068 0.0537943339 0.0692697018 0.0050499484 0.2194230000 256313933 0 1784393728 0.1005183309 -0.0444266945 -0.1071778759 899 1311867200.4162800312 0.0509145819 0.0537911306 0.0692697018 0.0050482037 0.2193960000 256315331 0 1783668736 0.0985155404 -0.0439070649 -0.1077260226 900 1311867200.4522490501 0.0501698330 0.0537871070 0.0692697018 0.0050478142 0.2150440000 256317481 0 1782493184 0.0956779346 -0.0458684713 -0.1073755920 901 1311867200.4850699902 0.0497748330 0.0537826538 0.0692697018 0.0050507406 0.2192770000 256319247 0 1783779328 0.0927687436 -0.0443512276 -0.1081945002 902 1311867200.5143918991 0.0504395664 0.0537789475 0.0692697018 0.0050503307 0.2177150000 256321245 0 1785556992 0.0896013081 -0.0452639572 -0.1067450121 903 1311867200.5505030155 0.0499733016 0.0537747331 0.0692697018 0.0050566165 0.2236050000 256323635 0 1785069568 0.0862122029 -0.0455487296 -0.1062801480 904 1311867200.5832219124 0.0485423207 0.0537689450 0.0692697018 0.0050575006 0.2206550000 256325673 0 1784045568 0.0860282481 -0.0452174246 -0.1071852446 905 1311867200.6145610809 0.0484263897 0.0537630416 0.0692697018 0.0050560566 0.2236400000 256327287 0 1782648832 0.0832767785 -0.0463549271 -0.1062353551 906 1311867200.6504778862 0.0495357998 0.0537583758 0.0692697018 0.0050563497 0.2264040000 256329261 0 1783922688 0.0795145109 -0.0451180525 -0.1048749685 907 1311867200.6851279736 0.0493502840 0.0537535157 0.0692697018 0.0050537608 0.2236650000 256331763 0 1785683968 0.0773011670 -0.0444703326 -0.1046030447 908 1311867200.7189719677 0.0489236005 0.0537481964 0.0692697018 0.0050540551 0.2200080000 256333393 0 1785065472 0.0738786608 -0.0454917178 -0.1042489484 909 1311867200.7503669262 0.0486338995 0.0537425701 0.0692697018 0.0050533625 0.2262320000 256335335 0 1784266752 0.0728023276 -0.0452975743 -0.1035387814 910 1311867200.7832930088 0.0478468314 0.0537360913 0.0692697018 0.0050588042 0.2186750000 256337405 0 1783410688 0.0697219819 -0.0436448231 -0.1049160361 911 1311867200.8181068897 0.0486916304 0.0537305540 0.0692697018 0.0050577036 0.2200020000 256339355 0 1784647680 0.0660808980 -0.0436038561 -0.1032618955 912 1311867200.8501501083 0.0485626571 0.0537248875 0.0692697018 0.0050550448 0.2239980000 256341225 0 1783922688 0.0645137653 -0.0433315784 -0.1026389375 913 1311867200.8845369816 0.0485896543 0.0537192629 0.0692697018 0.0050545691 0.2138000000 256343503 0 1783398400 0.0625349134 -0.0438460112 -0.1016066596 914 1311867200.9194929600 0.0486342013 0.0537136994 0.0692697018 0.0050571883 0.2229520000 256345381 0 1785188352 0.0598025396 -0.0440531597 -0.1013127118 915 1311867200.9512679577 0.0480854139 0.0537075483 0.0692697018 0.0050581698 0.2261140000 256347395 0 1784414208 0.0582063496 -0.0446948558 -0.1008388847 916 1311867200.9856009483 0.0486322306 0.0537020075 0.0692697018 0.0050632997 0.2184840000 256349513 0 1783386112 0.0565979779 -0.0450069271 -0.1006593257 917 1311867201.0184400082 0.0496344455 0.0536975718 0.0692697018 0.0050610285 0.2432240000 256351559 0 1784934400 0.0549040958 -0.0444995761 -0.1000077799 918 1311867201.0555179119 0.0489832126 0.0536924363 0.0692697018 0.0050592794 0.2206630000 256353685 0 1784307712 0.0532144159 -0.0448429063 -0.1008125767 919 1311867201.0825428963 0.0490622409 0.0536873980 0.0692697018 0.0050603694 0.2168850000 256355555 0 1783111680 0.0500966087 -0.0460353121 -0.1009889171 920 1311867201.1193449497 0.0491025560 0.0536824145 0.0692697018 0.0050580081 0.2201770000 256357425 0 1784889344 0.0499162748 -0.0446660891 -0.1014854163 921 1311867201.1506710052 0.0497654676 0.0536781616 0.0692697018 0.0050553987 0.2246730000 256359447 0 1784016896 0.0487919673 -0.0439275615 -0.1012998074 922 1311867201.1830160618 0.0495741889 0.0536737104 0.0692697018 0.0050548880 0.2261990000 256361413 0 1783255040 0.0478997156 -0.0448392332 -0.1011363193 923 1311867201.2196528912 0.0497060381 0.0536694117 0.0692697018 0.0050536565 0.2263670000 256363355 0 1784897536 0.0450027250 -0.0456108600 -0.1010134444 924 1311867201.2503149509 0.0496287756 0.0536650388 0.0692697018 0.0050510062 0.2227970000 256365385 0 1784176640 0.0451936349 -0.0440644510 -0.1014172360 925 1311867201.2824099064 0.0495378599 0.0536605769 0.0692697018 0.0050487319 0.2203760000 256367151 0 1783128064 0.0437734947 -0.0440854654 -0.1015196592 926 1311867201.3180539608 0.0497128591 0.0536563137 0.0692697018 0.0050488322 0.2246170000 256369493 0 1785192448 0.0402956232 -0.0450300910 -0.1015066579 927 1311867201.3522200584 0.0502076261 0.0536525935 0.0692697018 0.0050485022 0.2355130000 256371387 0 1784430592 0.0378550217 -0.0441211648 -0.1015476435 928 1311867201.3842790127 0.0502850823 0.0536489647 0.0692697018 0.0050507471 0.2177740000 256373361 0 1783889920 0.0363900214 -0.0411481149 -0.1023953706 929 1311867201.4198760986 0.0497346446 0.0536447512 0.0692697018 0.0050763460 0.2216920000 256375207 0 1784901632 0.0329086930 -0.0434775762 -0.1015369073 930 1311867201.4558579922 0.0485261902 0.0536392474 0.0692697018 0.0050778611 0.2252620000 256377253 0 1784012800 0.0307256952 -0.0418035239 -0.1032783911 931 1311867201.4853110313 0.0498509221 0.0536351783 0.0692697018 0.0050786712 0.2270640000 256379259 0 1782984704 0.0283213891 -0.0389501937 -0.1027891263 932 1311867201.5198690891 0.0491822623 0.0536304005 0.0692697018 0.0050781209 0.2157100000 256381289 0 1784651776 0.0256495811 -0.0393549874 -0.1027942896 933 1311867201.5527739525 0.0496859960 0.0536261728 0.0692697018 0.0050771673 0.2257420000 256383239 0 1783918592 0.0219949167 -0.0393114425 -0.1021200120 934 1311867201.5840220451 0.0487115122 0.0536209109 0.0692697018 0.0050747276 0.2249860000 256385189 0 1783029760 0.0201254413 -0.0387539044 -0.1034218967 935 1311867201.6197049618 0.0486852787 0.0536156321 0.0692697018 0.0050725447 0.2202370000 256387235 0 1784770560 0.0182014462 -0.0393330231 -0.1032938585 936 1311867201.6515579224 0.0488884337 0.0536105817 0.0692697018 0.0050745359 0.2253270000 256389241 0 1783644160 0.0159593485 -0.0385018513 -0.1034779400 937 1311867201.6839449406 0.0486297160 0.0536052659 0.0692697018 0.0050722172 0.2180030000 256391183 0 1782251520 0.0142377289 -0.0384285152 -0.1036725640 938 1311867201.7189009190 0.0489553958 0.0536003087 0.0692697018 0.0050717202 0.2542520000 256393149 0 1784414208 0.0119687654 -0.0367275439 -0.1042261422 939 1311867201.7507290840 0.0480995700 0.0535944506 0.0692697018 0.0050703022 0.2298300000 256395083 0 1785274368 0.0096050613 -0.0368997343 -0.1050374955 940 1311867201.7858049870 0.0473067425 0.0535877616 0.0692697018 0.0050792404 0.2236460000 256397241 0 1784446976 0.0091835475 -0.0363969877 -0.1050203890 941 1311867201.8190178871 0.0477939062 0.0535816045 0.0692697018 0.0050876793 0.2176840000 256399415 0 1783414784 0.0077652307 -0.0339160562 -0.1056007296 942 1311867201.8505740166 0.0480982400 0.0535757835 0.0692697018 0.0050891472 0.2223120000 256401301 0 1785298944 0.0061892876 -0.0339443162 -0.1051208600 943 1311867201.8862850666 0.0472654179 0.0535690917 0.0692697018 0.0050867138 0.2248600000 256403299 0 1783775232 0.0043930057 -0.0355860628 -0.1054252163 944 1311867201.9195730686 0.0482097007 0.0535634144 0.0692697018 0.0050883658 0.2214750000 256405329 0 1782870016 0.0026739761 -0.0324832760 -0.1060258299 945 1311867201.9516520500 0.0480263531 0.0535575550 0.0692697018 0.0050871786 0.2223360000 256407055 0 1784537088 0.0024586674 -0.0331821814 -0.1059641019 946 1311867201.9894599915 0.0471982583 0.0535508327 0.0692697018 0.0050845673 0.2296480000 256409269 0 1784029184 0.0007847343 -0.0331181511 -0.1074546129 947 1311867202.0184879303 0.0476793759 0.0535446327 0.0692697018 0.0050819982 0.2316960000 256411315 0 1783033856 0.0002359552 -0.0328396410 -0.1072364524 948 1311867202.0507359505 0.0476709567 0.0535384368 0.0692697018 0.0050795890 0.2298770000 256413145 0 1784664064 0.0002694912 -0.0320672542 -0.1077805981 949 1311867202.0866351128 0.0471228808 0.0535316765 0.0692697018 0.0050769519 0.2212710000 256414999 0 1783521280 -0.0007158387 -0.0326641053 -0.1083558649 950 1311867202.1185920238 0.0481727496 0.0535260355 0.0692697018 0.0050772070 0.2264460000 256417045 0 1782775808 -0.0020259852 -0.0312600732 -0.1075909436 951 1311867202.1516621113 0.0481466688 0.0535203790 0.0692697018 0.0050756239 0.2251570000 256419203 0 1784012800 -0.0027858568 -0.0304301195 -0.1077529490 952 1311867202.1866259575 0.0485219061 0.0535151285 0.0692697018 0.0050730920 0.2281570000 256421329 0 1783402496 -0.0038504740 -0.0288867727 -0.1078826413 953 1311867202.2191269398 0.0484667234 0.0535098311 0.0692697018 0.0050705977 0.2259130000 256423015 0 1782353920 -0.0044972533 -0.0294441879 -0.1074167863 954 1311867202.2513220310 0.0483815223 0.0535044555 0.0692697018 0.0050683579 0.2227820000 256425477 0 1784385536 -0.0069503067 -0.0288757607 -0.1075319499 955 1311867202.2868280411 0.0481143221 0.0534988114 0.0692697018 0.0050677714 0.2218330000 256427323 0 1785696256 -0.0068410113 -0.0261975862 -0.1086464748 956 1311867202.3199880123 0.0484892987 0.0534935713 0.0692697018 0.0050676823 0.2262480000 256429057 0 1784164352 -0.0088398447 -0.0277961753 -0.1076454744 957 1311867202.3523900509 0.0478126667 0.0534876352 0.0692697018 0.0050654040 0.2294800000 256431143 0 1782534144 -0.0105285766 -0.0277319923 -0.1082497463 958 1311867202.3883628845 0.0471587293 0.0534810288 0.0692697018 0.0050627592 0.2297290000 256433101 0 1784295424 -0.0127916392 -0.0273103416 -0.1088374555 959 1311867202.4196391106 0.0470609218 0.0534743342 0.0692697018 0.0050622427 0.2525530000 256435203 0 1785901056 -0.0129785789 -0.0269083194 -0.1091484800 960 1311867202.4529430866 0.0474575162 0.0534680667 0.0692697018 0.0050609547 0.2250160000 256436977 0 1784438784 -0.0135447327 -0.0292859860 -0.1076549292 961 1311867202.4875710011 0.0475873165 0.0534619473 0.0692697018 0.0050618412 0.2225980000 256438847 0 1783656448 -0.0125048356 -0.0268773101 -0.1082279906 962 1311867202.5206449032 0.0480007790 0.0534562704 0.0692697018 0.0050806569 0.2260430000 256441061 0 1785438208 -0.0144200707 -0.0268174224 -0.1081008315 963 1311867202.5508940220 0.0479129963 0.0534505141 0.0692697018 0.0050781073 0.2211990000 256443115 0 1784422400 -0.0172332786 -0.0274218433 -0.1084295809 964 1311867202.5864949226 0.0476350524 0.0534444815 0.0692697018 0.0050963738 0.2257710000 256445121 0 1782988800 -0.0160956364 -0.0274619423 -0.1089408174 965 1311867202.6185030937 0.0483138226 0.0534391647 0.0692697018 0.0050998622 0.2161310000 256447047 0 1784655872 -0.0169029906 -0.0282481518 -0.1084665358 966 1311867202.6514449120 0.0482956544 0.0534338402 0.0692697018 0.0051041511 0.2258410000 256449093 0 1783656448 -0.0209170114 -0.0271935537 -0.1097215787 967 1311867202.6866559982 0.0483623035 0.0534285956 0.0692697018 0.0051022228 0.2218050000 256451515 0 1782370304 -0.0223664232 -0.0260916110 -0.1107404232 968 1311867202.7185359001 0.0489469841 0.0534239658 0.0692697018 0.0050999798 0.2294090000 256453089 0 1784143872 -0.0243478566 -0.0269099250 -0.1109995320 969 1311867202.7507350445 0.0477536283 0.0534181141 0.0692697018 0.0051003535 0.2180870000 256454823 0 1783398400 -0.0251132511 -0.0299302209 -0.1121324599 970 1311867202.7897169590 0.0484909005 0.0534130345 0.0692697018 0.0050990140 0.2244780000 256457229 0 1782366208 -0.0258763582 -0.0264999308 -0.1139239296 971 1311867202.8190000057 0.0485006496 0.0534079754 0.0692697018 0.0050976218 0.2249090000 256459323 0 1784012800 -0.0287992172 -0.0277407281 -0.1142702028 972 1311867202.8527579308 0.0500470065 0.0534045176 0.0692697018 0.0050962732 0.2240550000 256461185 0 1785700352 -0.0322500467 -0.0273821857 -0.1134813577 973 1311867202.8873219490 0.0478051379 0.0533987628 0.0692697018 0.0050942477 0.2237550000 256463167 0 1784938496 -0.0322369151 -0.0271316413 -0.1159145236 974 1311867202.9199879169 0.0484059192 0.0533936367 0.0692697018 0.0050930688 0.2198400000 256465229 0 1784160256 -0.0312039070 -0.0250299983 -0.1160315573 975 1311867202.9525690079 0.0482275747 0.0533883382 0.0692697018 0.0050957018 0.2207990000 256466971 0 1785278464 -0.0318821594 -0.0265959203 -0.1156039238 976 1311867202.9868710041 0.0484535433 0.0533832821 0.0692697018 0.0050988932 0.2263230000 256469217 0 1784684544 -0.0317303017 -0.0261079017 -0.1151910201 977 1311867203.0202019215 0.0491318554 0.0533789305 0.0692697018 0.0050969072 0.2290870000 256471343 0 1784172544 -0.0318693146 -0.0240266547 -0.1153733656 978 1311867203.0560851097 0.0483924374 0.0533738319 0.0692697018 0.0051013631 0.2232380000 256473333 0 1783508992 -0.0315802433 -0.0271279551 -0.1146724150 979 1311867203.0865778923 0.0482944436 0.0533686435 0.0692697018 0.0050994999 0.2265640000 256475347 0 1782616064 -0.0299473554 -0.0280282795 -0.1145136431 980 1311867203.1189930439 0.0483274646 0.0533634995 0.0692697018 0.0051047872 0.2504060000 256477153 0 1784266752 -0.0291237794 -0.0289517939 -0.1142164916 981 1311867203.1549820900 0.0479641147 0.0533579955 0.0692697018 0.0051148806 0.2267440000 256479311 0 1783537664 -0.0284367334 -0.0314363129 -0.1141321361 982 1311867203.1877939701 0.0484929420 0.0533530413 0.0692697018 0.0051496885 0.2292810000 256481229 0 1782747136 -0.0274832509 -0.0326515026 -0.1141296849 983 1311867203.2185909748 0.0500903763 0.0533497222 0.0692697018 0.0051521494 0.2270790000 256483323 0 1784410112 -0.0277979318 -0.0307749268 -0.1140090376 984 1311867203.2552030087 0.0493011214 0.0533456078 0.0692697018 0.0051519317 0.2290030000 256485217 0 1783668736 -0.0280133318 -0.0324475467 -0.1150378138 985 1311867203.2864799500 0.0490597636 0.0533412567 0.0692697018 0.0051518676 0.2210090000 256487279 0 1782747136 -0.0288508087 -0.0345507227 -0.1151680797 986 1311867203.3194670677 0.0492737778 0.0533371314 0.0692697018 0.0051498597 0.2199930000 256489173 0 1784139776 -0.0290163923 -0.0343210138 -0.1157816425 987 1311867203.3547461033 0.0490034334 0.0533327406 0.0692697018 0.0051480680 0.2189780000 256491259 0 1783541760 -0.0277458057 -0.0337666124 -0.1168198362 988 1311867203.3865599632 0.0491564572 0.0533285136 0.0692697018 0.0051505172 0.2308360000 256493217 0 1782652928 -0.0275238901 -0.0348458774 -0.1166140959 989 1311867203.4183609486 0.0486107990 0.0533237434 0.0692697018 0.0051557515 0.2278490000 256494951 0 1784557568 -0.0302408002 -0.0398626924 -0.1167036742 990 1311867203.4545118809 0.0488052703 0.0533191793 0.0692697018 0.0051542463 0.2259290000 256496973 0 1783795712 -0.0286437925 -0.0398965478 -0.1169890389 991 1311867203.4864439964 0.0486780107 0.0533144960 0.0692697018 0.0051542792 0.2188810000 256499091 0 1782894592 -0.0280177817 -0.0399897173 -0.1180676222 992 1311867203.5185539722 0.0478718393 0.0533090095 0.0692697018 0.0051611170 0.2277160000 256501161 0 1784901632 -0.0279309470 -0.0446575582 -0.1179962307 993 1311867203.5560259819 0.0489453040 0.0533046150 0.0692697018 0.0051595999 0.2218990000 256503103 0 1783758848 -0.0271906294 -0.0468169563 -0.1172701865 994 1311867203.5876550674 0.0481720716 0.0532994515 0.0692697018 0.0051583817 0.2265100000 256505029 0 1783001088 -0.0271613710 -0.0469481610 -0.1194796637 995 1311867203.6191980839 0.0489528179 0.0532950830 0.0692697018 0.0051571074 0.2244240000 256507059 0 1784643584 -0.0276645757 -0.0481821857 -0.1193348244 996 1311867203.6557719707 0.0483764298 0.0532901446 0.0692697018 0.0051546306 0.2249420000 256508993 0 1784303616 -0.0282791816 -0.0514038652 -0.1199762002 997 1311867203.6866750717 0.0485342629 0.0532853744 0.0692697018 0.0051520759 0.2260400000 256511207 0 1783128064 -0.0275847204 -0.0525290184 -0.1201349422 998 1311867203.7195260525 0.0470354408 0.0532791119 0.0692697018 0.0051510784 0.2207220000 256512909 0 1784901632 -0.0275596473 -0.0552987866 -0.1215305254 999 1311867203.7566421032 0.0482633337 0.0532740911 0.0692697018 0.0051495031 0.2231100000 256515091 0 1784045568 -0.0266638342 -0.0552876070 -0.1213448942 1000 1311867203.7867228985 0.0481661670 0.0532689832 0.0692697018 0.0051470151 0.2260220000 256516897 0 1783111680 -0.0273458399 -0.0573884472 -0.1215767860 1001 1311867203.8193860054 0.0474623144 0.0532631824 0.0692697018 0.0051454798 0.2502000000 256518791 0 1784287232 -0.0260489043 -0.0588722266 -0.1226806194 1002 1311867203.8572859764 0.0475355424 0.0532574661 0.0692697018 0.0051440301 0.2253960000 256521053 0 1783910400 -0.0274090841 -0.0611676835 -0.1230456308 1003 1311867203.8891890049 0.0477966666 0.0532520217 0.0692697018 0.0051419892 0.2190000000 256523019 0 1782874112 -0.0266501643 -0.0620885268 -0.1235709414 1004 1311867203.9188020229 0.0471835211 0.0532459774 0.0692697018 0.0051399274 0.2234740000 256524881 0 1784795136 -0.0265360065 -0.0636520460 -0.1247392148 1005 1311867203.9553489685 0.0486754403 0.0532414296 0.0692697018 0.0051381049 0.2267780000 256526783 0 1784033280 -0.0272322632 -0.0630174652 -0.1251639277 1006 1311867203.9866371155 0.0479162373 0.0532361361 0.0692697018 0.0051378765 0.2229610000 256528765 0 1782984704 -0.0279175267 -0.0653593093 -0.1264052838 1007 1311867204.0199849606 0.0477817319 0.0532307196 0.0692697018 0.0051364361 0.2263720000 256530995 0 1784393728 -0.0274755899 -0.0665735155 -0.1275949925 1008 1311867204.0551509857 0.0481664687 0.0532256956 0.0692697018 0.0051346496 0.2326420000 256533089 0 1783668736 -0.0281118974 -0.0674957111 -0.1286691725 1009 1311867204.0867509842 0.0475122705 0.0532200331 0.0692697018 0.0051338850 0.2194560000 256534943 0 1783128064 -0.0294122249 -0.0698258951 -0.1298666149 1010 1311867204.1191530228 0.0478427745 0.0532147091 0.0692697018 0.0051316149 0.2259340000 256536741 0 1784684544 -0.0271534435 -0.0712513402 -0.1302005500 1011 1311867204.1555769444 0.0476701371 0.0532092249 0.0692697018 0.0051293061 0.2231420000 256538819 0 1783922688 -0.0285219233 -0.0721958950 -0.1319931298 1012 1311867204.1876530647 0.0480751693 0.0532041517 0.0692697018 0.0051278737 0.2194480000 256540865 0 1783148544 -0.0281570833 -0.0743183494 -0.1315874755 1013 1311867204.2187769413 0.0477821194 0.0531987992 0.0692697018 0.0051258739 0.2229580000 256542927 0 1784430592 -0.0281526111 -0.0749763548 -0.1328463107 1014 1311867204.2566440105 0.0479819626 0.0531936544 0.0692697018 0.0051238229 0.2266730000 256544981 0 1783783424 -0.0268952064 -0.0758261383 -0.1337172389 1015 1311867204.2867140770 0.0487473980 0.0531892739 0.0692697018 0.0051213501 0.2223660000 256547131 0 1781874688 -0.0279356353 -0.0782268420 -0.1329940856 1016 1311867204.3204538822 0.0484368689 0.0531845963 0.0692697018 0.0051188442 0.2221060000 256548873 0 1783910400 -0.0279470496 -0.0797563344 -0.1340190321 1017 1311867204.3625741005 0.0480632558 0.0531795606 0.0692697018 0.0051166147 0.2201970000 256551247 0 1785520128 -0.0284351837 -0.0814678594 -0.1351413429 1018 1311867204.3869600296 0.0485935137 0.0531750556 0.0692697018 0.0051146648 0.2558760000 256912217 0 1784528896 -0.0285927728 -0.0823511630 -0.1350594163 1019 1311867204.4240970612 0.0490902625 0.0531710470 0.0692697018 0.0051132926 0.5063340000 256922923 0 1782554624 -0.0290669277 -0.0837863013 -0.1354158968 1020 1311867204.4549949169 0.0499620438 0.0531679009 0.0692697018 0.0051122990 0.4849580000 256924217 0 1784598528 -0.0290399455 -0.0837364644 -0.1355990171 1021 1311867204.4872748852 0.0490674078 0.0531638847 0.0692697018 0.0051114451 0.4523030000 257938738 0 1785085952 -0.0289044715 -0.0858948454 -0.1367653012 1022 1311867204.5237219334 0.0500327498 0.0531608210 0.0692697018 0.0051090317 0.3221710000 260419364 0 1778077696 -0.0293075405 -0.0876219794 -0.1359949857 1023 1311867204.5581860542 0.0500317365 0.0531577623 0.0692697018 0.0051079565 0.3087130000 260208286 0 1779486720 -0.0281273238 -0.0884303451 -0.1364520341 1024 1311867204.5878469944 0.0507635772 0.0531554242 0.0692697018 0.0051058680 0.5604270000 259157116 0 1776549888 -0.0309518240 -0.0895598382 -0.1363037676 1025 1311867204.6241528988 0.0497296490 0.0531520820 0.0692697018 0.0051041145 0.2388880000 256992031 0 1776627712 -0.0302155800 -0.0909878686 -0.1371769905 1026 1311867204.6541819572 0.0493988171 0.0531484238 0.0692697018 0.0051022038 0.2248840000 257161741 0 1778503680 -0.0295958370 -0.0935089141 -0.1368336380 1027 1311867204.6871540546 0.0488584228 0.0531442466 0.0692697018 0.0050999282 0.2173460000 257163667 0 1780277248 -0.0313963853 -0.0947478041 -0.1380198300 1028 1311867204.7225689888 0.0498514995 0.0531410436 0.0692697018 0.0050994516 0.2275240000 257165817 0 1781907456 -0.0300500412 -0.0946791768 -0.1372563392 1029 1311867204.7539510727 0.0497208089 0.0531377197 0.0692697018 0.0050973648 0.2193480000 257167735 0 1783177216 -0.0302274730 -0.0955690295 -0.1371309757 1030 1311867204.7878720760 0.0500396267 0.0531347119 0.0692697018 0.0050975076 0.2214230000 257170005 0 1785208832 -0.0330684185 -0.0985541120 -0.1351186633 1031 1311867204.8227200508 0.0511128791 0.0531327508 0.0692697018 0.0050958984 0.2191890000 257172027 0 1784070144 -0.0329494402 -0.0978665352 -0.1340399534 1032 1311867204.8542668819 0.0495334640 0.0531292631 0.0692697018 0.0050978589 0.2216310000 257174185 0 1783439360 -0.0324380547 -0.1002976373 -0.1338073164 1033 1311867204.8864960670 0.0494246632 0.0531256769 0.0692697018 0.0050965101 0.2240780000 257176023 0 1784729600 -0.0340715870 -0.1034583896 -0.1322372556 1034 1311867204.9220221043 0.0499713421 0.0531226263 0.0692697018 0.0050947033 0.2183100000 257177741 0 1783963648 -0.0359573066 -0.1049839705 -0.1310086250 1035 1311867204.9542920589 0.0505892374 0.0531201785 0.0692697018 0.0050925066 0.2174790000 257179651 0 1782951936 -0.0350606181 -0.1051479504 -0.1301401556 1036 1311867204.9865999222 0.0500381216 0.0531172036 0.0692697018 0.0050907238 0.2199810000 257181881 0 1784946688 -0.0361715630 -0.1079677567 -0.1296670735 1037 1311867205.0227239132 0.0494389012 0.0531136565 0.0692697018 0.0050934694 0.2221570000 257183999 0 1783857152 -0.0364648961 -0.1115874052 -0.1286865771 1038 1311867205.0550808907 0.0492868982 0.0531099699 0.0692697018 0.0051081848 0.2208270000 257185797 0 1783074816 -0.0369976126 -0.1116356999 -0.1285250485 1039 1311867205.0880999565 0.0498033278 0.0531067873 0.0692697018 0.0051058168 0.2483160000 257187835 0 1784438784 -0.0375593007 -0.1134247556 -0.1270802617 1040 1311867205.1232450008 0.0495800674 0.0531033963 0.0692697018 0.0051045013 0.2178320000 257189681 0 1784111104 -0.0365707316 -0.1163663343 -0.1258435100 1041 1311867205.1545319557 0.0501873642 0.0531005951 0.0692697018 0.0051160434 0.2178420000 257191647 0 1782968320 -0.0348903090 -0.1159640476 -0.1259696335 1042 1311867205.1863510609 0.0503948145 0.0530979984 0.0692697018 0.0051221504 0.2138920000 257193821 0 1784709120 -0.0366922915 -0.1180347651 -0.1249391586 1043 1311867205.2223129272 0.0493593886 0.0530944139 0.0692697018 0.0051236252 0.2132150000 257195739 0 1783967744 -0.0358732902 -0.1208855063 -0.1248035878 1044 1311867205.2541849613 0.0497711599 0.0530912307 0.0692697018 0.0051236997 0.2249720000 257197745 0 1782931456 -0.0342016369 -0.1216641665 -0.1237938926 1045 1311867205.2880499363 0.0502597354 0.0530885211 0.0692697018 0.0051219507 0.2218210000 257200063 0 1784565760 -0.0346156657 -0.1228868887 -0.1230905429 1046 1311867205.3218879700 0.0500178784 0.0530855855 0.0692697018 0.0051214055 0.2205030000 257201981 0 1783988224 -0.0359325409 -0.1254646778 -0.1225849912 1047 1311867205.3542900085 0.0507847257 0.0530833879 0.0692697018 0.0051247652 0.2492050000 257552251 0 1782824960 -0.0370190628 -0.1261927038 -0.1217922568 1048 1311867205.3862779140 0.0501235910 0.0530805637 0.0692697018 0.0051298633 0.4893080000 257569373 0 1782747136 -0.0366755873 -0.1285530478 -0.1212334260 1049 1311867205.4225649834 0.0508662350 0.0530784528 0.0692697018 0.0051319416 0.4739950000 257569391 0 1784082432 -0.0393569507 -0.1302835196 -0.1199921519 1050 1311867205.4540419579 0.0511777103 0.0530766426 0.0692697018 0.0051361802 0.4575180000 257582161 0 1785884672 -0.0378684551 -0.1313570291 -0.1187548786 1051 1311867205.4865119457 0.0508524664 0.0530745263 0.0692697018 0.0051410156 0.3594660000 261067578 0 1782870016 -0.0378468260 -0.1319327205 -0.1183034852 1052 1311867205.5230340958 0.0504096150 0.0530719932 0.0692697018 0.0051498469 0.3300890000 260852584 0 1782181888 -0.0400440767 -0.1356442869 -0.1164751798 1053 1311867205.5542900562 0.0505968779 0.0530696426 0.0692697018 0.0051733274 0.2410710000 260910662 0 1783832576 -0.0424241610 -0.1357359737 -0.1165590659 1054 1311867205.5866839886 0.0514652021 0.0530681204 0.0692697018 0.0051711211 0.4831390000 259836936 0 1780539392 -0.0432318933 -0.1354796737 -0.1153388172 1055 1311867205.6226179600 0.0506537259 0.0530658319 0.0692697018 0.0051763918 0.2402780000 257580491 0 1780731904 -0.0455652997 -0.1393529028 -0.1136568263 1056 1311867205.6555979252 0.0502842814 0.0530631978 0.0692697018 0.0051748877 0.2181320000 257582537 0 1782517760 -0.0445571542 -0.1408900917 -0.1129639596 1057 1311867205.6902959347 0.0497621968 0.0530600748 0.0692697018 0.0051727302 0.2205860000 257584527 0 1784012800 -0.0447875559 -0.1428902447 -0.1126954406 1058 1311867205.7222061157 0.0508158952 0.0530579537 0.0692697018 0.0051705758 0.2177350000 257586581 0 1783554048 -0.0472945012 -0.1455737352 -0.1110151559 1059 1311867205.7548348904 0.0503664203 0.0530554121 0.0692697018 0.0051682195 0.2192920000 257588403 0 1782136832 -0.0479389392 -0.1481282562 -0.1109190211 1060 1311867205.7906379700 0.0517992079 0.0530542270 0.0692697018 0.0051673206 0.2136790000 257590417 0 1783767040 -0.0491465963 -0.1472699642 -0.1110873446 1061 1311867205.8232109547 0.0514973626 0.0530527596 0.0692697018 0.0051811350 0.2135680000 257592639 0 1785393152 -0.0485624671 -0.1504017413 -0.1097610742 1062 1311867205.8554759026 0.0518649332 0.0530516412 0.0692697018 0.0051867544 0.2205980000 257594701 0 1784508416 -0.0497659296 -0.1519948840 -0.1092081219 1063 1311867205.8905880451 0.0529048108 0.0530515030 0.0692697018 0.0051878524 0.2159320000 257596803 0 1783873536 -0.0515944175 -0.1522282660 -0.1090207994 1064 1311867205.9223020077 0.0522027314 0.0530507053 0.0692697018 0.0051969961 0.2181310000 257598825 0 1785536512 -0.0513091534 -0.1547517478 -0.1084268987 1065 1311867205.9544939995 0.0514060855 0.0530491611 0.0692697018 0.0051946812 0.2233060000 257600607 0 1784393728 -0.0516871363 -0.1569865346 -0.1087771058 1066 1311867205.9905850887 0.0510450341 0.0530472810 0.0692697018 0.0052027960 0.2208470000 257602853 0 1784025088 -0.0539052188 -0.1585830152 -0.1091775894 1067 1311867206.0259850025 0.0533728302 0.0530475861 0.0692697018 0.0052094141 0.2180760000 257604971 0 1783513088 -0.0546606630 -0.1568773836 -0.1084722951 1068 1311867206.0604250431 0.0536880903 0.0530481858 0.0692697018 0.0052187180 0.2126540000 257606545 0 1783042048 -0.0548698418 -0.1591692716 -0.1073388979 1069 1311867206.0903289318 0.0513007715 0.0530465512 0.0692697018 0.0052183839 0.2114250000 257608495 0 1784692736 -0.0547960475 -0.1636530608 -0.1079485118 1070 1311867206.1227540970 0.0526559874 0.0530461862 0.0692697018 0.0052166407 0.2122220000 257610597 0 1784147968 -0.0543787628 -0.1638587415 -0.1072745919 1071 1311867206.1546130180 0.0527174622 0.0530458793 0.0692697018 0.0052143585 0.2193570000 257612691 0 1783930880 -0.0545971803 -0.1665633619 -0.1071338952 1072 1311867206.1903800964 0.0517500564 0.0530446705 0.0692697018 0.0052150305 0.2159460000 257614633 0 1785540608 -0.0569998808 -0.1704838574 -0.1074635610 1073 1311867206.2239561081 0.0518437661 0.0530435513 0.0692697018 0.0052134591 0.2163280000 257616519 0 1785073664 -0.0569586530 -0.1704576761 -0.1089389250 1074 1311867206.2553579807 0.0519634746 0.0530425456 0.0692697018 0.0052124329 0.2198970000 257618725 0 1784565760 -0.0561036989 -0.1718159318 -0.1088267192 1075 1311867206.2904770374 0.0510934368 0.0530407325 0.0692697018 0.0052102780 0.2147350000 257620547 0 1783635968 -0.0581734776 -0.1742786914 -0.1100913435 1076 1311867206.3222041130 0.0518787503 0.0530396526 0.0692697018 0.0052081589 0.2157060000 257622561 0 1783296000 -0.0584064722 -0.1751692295 -0.1096513048 1077 1311867206.3542530537 0.0518163331 0.0530385167 0.0692697018 0.0052065792 0.2126810000 257624839 0 1784909824 -0.0588878505 -0.1763421148 -0.1101485416 1078 1311867206.3900070190 0.0519486815 0.0530375058 0.0692697018 0.0052056722 0.2457670000 257626981 0 1784401920 -0.0590158254 -0.1785718799 -0.1095794141 1079 1311867206.4220259190 0.0516292304 0.0530362006 0.0692697018 0.0052043849 0.2084670000 257628507 0 1783672832 -0.0582027137 -0.1798317432 -0.1101779491 1080 1311867206.4542310238 0.0518353991 0.0530350887 0.0692697018 0.0052039358 0.2178200000 257630569 0 1785413632 -0.0596799888 -0.1809195280 -0.1108477935 1081 1311867206.4905378819 0.0522878654 0.0530343975 0.0692697018 0.0052138134 0.2160610000 257633015 0 1784909824 -0.0589428879 -0.1830505282 -0.1097489446 1082 1311867206.5250329971 0.0514917485 0.0530329718 0.0692697018 0.0052158222 0.2179000000 257634765 0 1784422400 -0.0606703497 -0.1866894960 -0.1098253354 1083 1311867206.5539300442 0.0517004542 0.0530317414 0.0692697018 0.0052190478 0.2473530000 257987823 0 1783894016 -0.0600629523 -0.1884390116 -0.1094900966 1084 1311867206.5921130180 0.0519190691 0.0530307149 0.0692697018 0.0052182190 0.4904410000 258012129 0 1781383168 -0.0590881780 -0.1890870333 -0.1105130389 1085 1311867206.6226360798 0.0520301089 0.0530297927 0.0692697018 0.0052287852 0.4691650000 258014155 0 1783496704 -0.0607937425 -0.1913344115 -0.1109055430 1086 1311867206.6566751003 0.0514959842 0.0530283804 0.0692697018 0.0052277117 0.4467790000 258168641 0 1784950784 -0.0613336302 -0.1933121085 -0.1110518575 1087 1311867206.6945209503 0.0507817827 0.0530263136 0.0692697018 0.0052263153 0.4501350000 261497538 0 1784369152 -0.0601506382 -0.1952356398 -0.1117780581 1088 1311867206.7248480320 0.0512751341 0.0530247040 0.0692697018 0.0052323786 0.3753150000 261468576 0 1783050240 -0.0596764088 -0.1961226612 -0.1116296276 1089 1311867206.7587969303 0.0514083952 0.0530232198 0.0692697018 0.0052725875 0.2691310000 261528898 0 1785126912 -0.0598208793 -0.1990536451 -0.1113465503 1090 1311867206.7902839184 0.0527668744 0.0530229846 0.0692697018 0.0052843364 0.4877410000 260472620 0 1781207040 -0.0606416054 -0.1976390779 -0.1122750044 1091 1311867206.8229770660 0.0520732552 0.0530221141 0.0692697018 0.0052840794 0.2459390000 257979775 0 1781469184 -0.0615706258 -0.2003007829 -0.1128792390 1092 1311867206.8605449200 0.0512433946 0.0530204853 0.0692697018 0.0052818472 0.2163400000 257981757 0 1783099392 -0.0609414876 -0.2029166967 -0.1141745225 1093 1311867206.8907771111 0.0511586405 0.0530187818 0.0692697018 0.0052804468 0.2432810000 257983715 0 1784496128 -0.0600951761 -0.2036241293 -0.1154453233 1094 1311867206.9225020409 0.0513602011 0.0530172658 0.0692697018 0.0052780688 0.2143170000 257985873 0 1783988224 -0.0605101064 -0.2048513591 -0.1161106080 1095 1311867206.9592480659 0.0517021567 0.0530160647 0.0692697018 0.0052761900 0.2167250000 257988087 0 1783263232 -0.0614114590 -0.2085235417 -0.1154046729 1096 1311867206.9948680401 0.0515799448 0.0530147544 0.0692697018 0.0052823816 0.2136780000 257990285 0 1785004032 -0.0631089360 -0.2112439573 -0.1158856452 1097 1311867207.0247550011 0.0518873259 0.0530137267 0.0692697018 0.0052833392 0.2162900000 257992251 0 1784152064 -0.0616344884 -0.2120121121 -0.1167946234 1098 1311867207.0597259998 0.0529026017 0.0530136255 0.0692697018 0.0052821413 0.2055250000 257994145 0 1783644160 -0.0624917373 -0.2142653167 -0.1155232638 1099 1311867207.0942800045 0.0522905774 0.0530129676 0.0692697018 0.0052860420 0.2132190000 257996215 0 1785290752 -0.0626536161 -0.2159014791 -0.1172345132 1100 1311867207.1229140759 0.0507089980 0.0530108730 0.0692697018 0.0052878923 0.2066430000 257997869 0 1784877056 -0.0603977144 -0.2181825638 -0.1182894260 1101 1311867207.1583549976 0.0518028736 0.0530097759 0.0692697018 0.0052926580 0.2132670000 258000347 0 1784258560 -0.0615953729 -0.2196076959 -0.1184727401 1102 1311867207.1904919147 0.0523212031 0.0530091510 0.0692697018 0.0052911200 0.2118720000 258002041 0 1783480320 -0.0606747977 -0.2202442139 -0.1181127727 1103 1311867207.2226181030 0.0507505536 0.0530071033 0.0692697018 0.0052928690 0.2139270000 258003967 0 1783136256 -0.0597589798 -0.2228833437 -0.1187019646 1104 1311867207.2604830265 0.0514374599 0.0530056816 0.0692697018 0.0052934063 0.2126730000 258006157 0 1784750080 -0.0599840656 -0.2236256748 -0.1184889153 1105 1311867207.2926900387 0.0507133417 0.0530036070 0.0692697018 0.0052934836 0.2174980000 258008323 0 1784659968 -0.0620344952 -0.2266935408 -0.1182257757 1106 1311867207.3235239983 0.0506118350 0.0530014445 0.0692697018 0.0052989163 0.2142830000 258010073 0 1783390208 -0.0621333010 -0.2289042324 -0.1174976677 1107 1311867207.3597478867 0.0523466989 0.0530008530 0.0692697018 0.0052971674 0.2169630000 258012063 0 1784406016 -0.0623882823 -0.2276376188 -0.1174504906 1108 1311867207.3901309967 0.0511222668 0.0529991576 0.0692697018 0.0052993285 0.2161990000 258013997 0 1782624256 -0.0625407845 -0.2303251177 -0.1171231717 1109 1311867207.4227840900 0.0503908470 0.0529968056 0.0692697018 0.0052982692 0.2115440000 258016227 0 1784623104 -0.0644142404 -0.2333395183 -0.1164872423 1110 1311867207.4586789608 0.0517274961 0.0529956621 0.0692697018 0.0053001651 0.2484720000 258355905 0 1783877632 -0.0640671775 -0.2338500321 -0.1147705093 1111 1311867207.4927639961 0.0526712872 0.0529953701 0.0692697018 0.0053005212 0.5035450000 258384967 0 1782034432 -0.0656253621 -0.2348038405 -0.1144634411 1112 1311867207.5237300396 0.0511514880 0.0529937120 0.0692697018 0.0053056222 0.4777900000 258386285 0 1783742464 -0.0671724007 -0.2388940156 -0.1139627695 1113 1311867207.5598409176 0.0511869192 0.0529920886 0.0692697018 0.0053036153 0.4596330000 258549007 0 1785286656 -0.0664191172 -0.2394866496 -0.1148048043 1114 1311867207.5944800377 0.0517116003 0.0529909392 0.0692697018 0.0053033612 0.4767510000 260887180 0 1785032704 -0.0687997341 -0.2414335161 -0.1144703776 1115 1311867207.6259219646 0.0512262248 0.0529893565 0.0692697018 0.0053009932 0.3714670000 260936230 0 1785413632 -0.0702355877 -0.2440375090 -0.1141044647 1116 1311867207.6592938900 0.0509487167 0.0529875279 0.0692697018 0.0052997130 0.2688350000 261769552 0 1783365632 -0.0715093762 -0.2462880611 -0.1143378019 1117 1311867207.6923089027 0.0528126732 0.0529873714 0.0692697018 0.0053004726 0.4766520000 260725026 0 1777250304 -0.0709153116 -0.2461274713 -0.1135118604 1118 1311867207.7238640785 0.0532050245 0.0529875661 0.0692697018 0.0053004243 0.2186260000 258396001 0 1777442816 -0.0725935698 -0.2485554665 -0.1126358807 1119 1311867207.7588050365 0.0525199212 0.0529871481 0.0692697018 0.0052992209 0.2192380000 258397919 0 1779019776 -0.0727647096 -0.2515049875 -0.1126552746 1120 1311867207.7921919823 0.0543653741 0.0529883787 0.0692697018 0.0052976387 0.2159840000 258399917 0 1780834304 -0.0753786042 -0.2519818246 -0.1119976938 1121 1311867207.8237760067 0.0534119122 0.0529887565 0.0692697018 0.0052961711 0.2074080000 258402075 0 1782448128 -0.0744796991 -0.2540090978 -0.1128089130 1122 1311867207.8608479500 0.0527827702 0.0529885729 0.0692697018 0.0052945135 0.2128970000 258403889 0 1784385536 -0.0743530020 -0.2569943964 -0.1126345992 1123 1311867207.8937089443 0.0540448837 0.0529895136 0.0692697018 0.0052926880 0.2121370000 258406095 0 1783742464 -0.0748237967 -0.2575501502 -0.1119350195 1124 1311867207.9244139194 0.0537896268 0.0529902254 0.0692697018 0.0052919164 0.2156830000 258408093 0 1782435840 -0.0761959255 -0.2593031526 -0.1123245806 1125 1311867207.9614970684 0.0519992113 0.0529893445 0.0692697018 0.0052906800 0.2109370000 258410187 0 1783980032 -0.0742773861 -0.2615531683 -0.1132062674 1126 1311867207.9914131165 0.0526062064 0.0529890042 0.0692697018 0.0053094425 0.2146040000 258411641 0 1783234560 -0.0746846497 -0.2620350420 -0.1134354174 1127 1311867208.0248498917 0.0533721410 0.0529893442 0.0692697018 0.0053271051 0.2045020000 258414023 0 1782329344 -0.0741512850 -0.2639921010 -0.1112302691 1128 1311867208.0618500710 0.0526198149 0.0529890166 0.0692697018 0.0053255875 0.2067180000 258415725 0 1783980032 -0.0753003061 -0.2671110928 -0.1109975949 1129 1311867208.0924620628 0.0525666140 0.0529886425 0.0692697018 0.0053234083 0.2073200000 258418011 0 1785749504 -0.0741249099 -0.2673103809 -0.1120935306 1130 1311867208.1276559830 0.0520501286 0.0529878119 0.0692697018 0.0053226039 0.2087840000 258419945 0 1784868864 -0.0755486265 -0.2700044513 -0.1119778678 1131 1311867208.1596069336 0.0524654724 0.0529873501 0.0692697018 0.0053203016 0.2404460000 258421655 0 1784090624 -0.0747728944 -0.2701284289 -0.1126291007 1132 1311867208.1905009747 0.0519792363 0.0529864595 0.0692697018 0.0053204882 0.2046510000 258423605 0 1785905152 -0.0735060573 -0.2714328468 -0.1132555455 1133 1311867208.2280850410 0.0507253893 0.0529844639 0.0692697018 0.0053195480 0.2130550000 258426107 0 1784741888 -0.0739724562 -0.2743631601 -0.1143120155 1134 1311867208.2581789494 0.0520213023 0.0529836145 0.0692697018 0.0053175001 0.2122520000 258427729 0 1783963648 -0.0754884928 -0.2754016221 -0.1130504161 1135 1311867208.2901990414 0.0521290600 0.0529828616 0.0692697018 0.0053153464 0.2093040000 258429767 0 1785380864 -0.0778777301 -0.2773950398 -0.1129777730 1136 1311867208.3270208836 0.0524800792 0.0529824190 0.0692697018 0.0053146382 0.2099050000 258431829 0 1784401920 -0.0747644156 -0.2773735821 -0.1143178269 1137 1311867208.3580970764 0.0524784625 0.0529819758 0.0692697018 0.0053147223 0.2074460000 258433883 0 1783091200 -0.0749249831 -0.2786293030 -0.1143798232 1138 1311867208.3910560608 0.0517003275 0.0529808496 0.0692697018 0.0053126584 0.2035330000 258436033 0 1784741888 -0.0750627965 -0.2800358534 -0.1158322841 1139 1311867208.4260230064 0.0534924828 0.0529812987 0.0692697018 0.0053108059 0.2049950000 258437687 0 1783377920 -0.0777968615 -0.2814366221 -0.1138474718 1140 1311867208.4577419758 0.0524887070 0.0529808666 0.0692697018 0.0053096357 0.2543510000 258775525 0 1782620160 -0.0771923140 -0.2833703160 -0.1149530038 1141 1311867208.4907650948 0.0522955582 0.0529802660 0.0692697018 0.0053074991 0.4504250000 258798399 0 1783025664 -0.0759076029 -0.2841496468 -0.1154834479 1142 1311867208.5257411003 0.0522118211 0.0529795931 0.0692697018 0.0053058374 0.4524350000 258800285 0 1784647680 -0.0765687823 -0.2861026227 -0.1145185456 1143 1311867208.5583798885 0.0528719202 0.0529794989 0.0692697018 0.0053039949 0.4391320000 258970827 0 1783443456 -0.0785955563 -0.2873260677 -0.1133281961 1144 1311867208.5904500484 0.0533119328 0.0529797895 0.0692697018 0.0053026420 0.4495940000 262299636 0 1782538240 -0.0771537051 -0.2867460847 -0.1139491796 1145 1311867208.6259779930 0.0535223484 0.0529802634 0.0692697018 0.0053008626 0.3677310000 262275118 0 1779167232 -0.0781628489 -0.2879511416 -0.1127645224 1146 1311867208.6582078934 0.0517779104 0.0529792142 0.0692697018 0.0052990048 0.2697680000 262338480 0 1781026816 -0.0786667913 -0.2900861800 -0.1135217920 1147 1311867208.6910300255 0.0518538356 0.0529782330 0.0692697018 0.0053002716 0.4726480000 261290798 0 1777676288 -0.0775400847 -0.2898996770 -0.1130947024 1148 1311867208.7262260914 0.0520314872 0.0529774084 0.0692697018 0.0053003065 0.2677410000 258810277 0 1777745920 -0.0784734190 -0.2908589542 -0.1128010601 1149 1311867208.7591009140 0.0515766665 0.0529761893 0.0692697018 0.0052981314 0.2121550000 258812067 0 1779507200 -0.0802619308 -0.2923386693 -0.1124834642 1150 1311867208.7909750938 0.0528683737 0.0529760955 0.0692697018 0.0052966049 0.2145250000 258814017 0 1781260288 -0.0803163424 -0.2920755744 -0.1108889282 1151 1311867208.8259930611 0.0517704822 0.0529750481 0.0692697018 0.0052973191 0.2178340000 258816007 0 1782910976 -0.0798961669 -0.2943778634 -0.1108574122 1152 1311867208.8588190079 0.0517045073 0.0529739452 0.0692697018 0.0053031908 0.2074900000 258817949 0 1784688640 -0.0797721297 -0.2955586910 -0.1102596670 1153 1311867208.8916258812 0.0529280901 0.0529739054 0.0692697018 0.0053126945 0.2126110000 258820395 0 1783861248 -0.0807906687 -0.2947641313 -0.1099050194 1154 1311867208.9275119305 0.0539983176 0.0529747931 0.0692697018 0.0053130073 0.2099180000 258822145 0 1782808576 -0.0832508132 -0.2966390848 -0.1084469110 1155 1311867208.9577760696 0.0527868159 0.0529746303 0.0692697018 0.0053122467 0.2135580000 258823935 0 1784459264 -0.0833832249 -0.2996205389 -0.1084239036 1156 1311867208.9911639690 0.0520663261 0.0529738446 0.0692697018 0.0053109042 0.2122330000 258826037 0 1783844864 -0.0821706280 -0.3006318510 -0.1100045815 1157 1311867209.0270779133 0.0542469323 0.0529749449 0.0692697018 0.0053119594 0.2016620000 258828323 0 1782824960 -0.0827680379 -0.3009608984 -0.1081979945 1158 1311867209.0579569340 0.0524585061 0.0529744990 0.0692697018 0.0053098659 0.2116280000 258829993 0 1784569856 -0.0837272108 -0.3033306003 -0.1106937453 1159 1311867209.0906980038 0.0532099940 0.0529747022 0.0692697018 0.0053100758 0.1996140000 258832295 0 1783590912 -0.0842584297 -0.3031810820 -0.1113083586 1160 1311867209.1260778904 0.0553142205 0.0529767190 0.0692697018 0.0053081696 0.2093150000 258834205 0 1782444032 -0.0853141025 -0.3024468720 -0.1108681485 1161 1311867209.1600620747 0.0547375716 0.0529782357 0.0692697018 0.0053074900 0.2073580000 258836203 0 1784336384 -0.0852325559 -0.3049883842 -0.1105895266 1162 1311867209.1917839050 0.0534154624 0.0529786119 0.0692697018 0.0053052998 0.2123800000 258838385 0 1785704448 -0.0850527957 -0.3060545325 -0.1130322888 1163 1311867209.2259531021 0.0562167801 0.0529813963 0.0692697018 0.0053035720 0.2065740000 258840239 0 1784950784 -0.0849274471 -0.3050288558 -0.1112972051 ================================================ FILE: icra2018_results/utils.py ================================================ ######################################################################################### # UTILS SYSTEM ######################################################################################### import sys class shellcolors: GREEN = '\033[92m' YELLOW = '\033[93m' RED = '\033[91m' ENDC = '\033[0m' BOLD = '\033[1m' UNDERLINE = '\033[4m' WARNING_CODE = shellcolors.YELLOW + "[ERROR]" + shellcolors.ENDC ERROR_CODE = shellcolors.RED + "[ERROR]" + shellcolors.ENDC INVALID = shellcolors.RED + "[INVALID]" + shellcolors.ENDC VALID = shellcolors.GREEN + "[VALID]" + shellcolors.ENDC verbose_level = False def setverbose(v) : global verbose_level verbose_level = v def printwarning(msg) : sys.stderr.write(WARNING_CODE + " " + msg) def printerr(err) : sys.stderr.write(ERROR_CODE + " " + err) def printinfo(err) : global verbose_level if verbose_level : sys.stderr.write(shellcolors.GREEN + "[INFO]" + shellcolors.ENDC + " " + err) ================================================ FILE: icra2018_results/violins.py ================================================ #!/usr/bin/python import math import sys import re import numpy as np import matplotlib import pylab as plot import datetime as datetime import os import argparse import pprint from slamlog import * from plotutils import * ######################################################################################### # rendering setting ######################################################################################### default_order = [ "KF-CUDA", "EF-CUDA", "IT-CPP", "OS2-CPP", ] ######################################################################################### # UTILS PLOT ######################################################################################### def generate_latex_doc (containt) : latex_str = "" latex_str += "\\documentclass[landscape]{article}\n" latex_str += "\\usepackage[table]{xcolor}\n" latex_str += "\\usepackage[ margin=0cm]{geometry}\n" latex_str += "\\setlength{\\arrayrulewidth}{0.2mm}\n" latex_str += "\\setlength{\\tabcolsep}{2pt}\n" latex_str += "\\renewcommand{\\arraystretch}{1}\n" latex_str += "\\begin{document}\n" latex_str += containt latex_str += "\\end{document}\n" return latex_str def generate_latex_table (data , table_title, value_name, value_type , precision = "%.2f", high_threshold = None , low_threshold = None) : dataset_labels = [] for a in data : dataset_labels = list ( set ( dataset_labels + data[a].keys() ) ) algorithm_labels = data.keys() latex_str = "" latex_str += table_title + "\\\\\n" latex_str += "{\\rowcolors{3}{black!10}{black!2}\n" latex_str += "\\tiny\n" latex_str += "\\begin{tabular}{%s}\n" % ( "|l|" + "|".join(["l" for x in dataset_labels]) + "|") latex_str += "\\hline\n" # latex_str += "Dataset name & \\multicolumn{4}{c|}{ICLNUIM Dataset} & \\multicolumn{19}{c|}{TUM Dataset} & \\multicolumn{11}{c|}{EuRoC MAV Dataset} \\\\\n" # latex_str += "\\hline\n" # latex_str += "Scene name & \\multicolumn{4}{c|}{Living Room} & \\multicolumn{7}{c|}{Freiburg 1} & \\multicolumn{12}{c|}{Freiburg 2} & \\multicolumn{5}{c|}{Machine Hall} & \\multicolumn{3}{c|}{Vicon Room 1} & \\multicolumn{3}{c|}{Vicon Room 2}\\\\\n" latex_str += "Algorithm & " + " & ".join([x.replace("_","\_") for x in dataset_labels]) + "\\\\\n" latex_str += "\\hline\n" for algorithm in data : latex_str += algorithm.replace("_","\_") for dataset in dataset_labels : accuracy = None if not dataset in data[algorithm].keys() : latex_str += "& - " continue if len(data[algorithm][dataset]) == 0 : printerr ("Cannot find any iteration in %s data.\n" % (dataset, algorithm)) exit(1) for it in data[algorithm][dataset] : if not STATISTICS_SECTION in it.keys() : printerr ("Invalid data (%s,%s), no STATISTICS_SECTION.\n" % (algorithm,dataset)) exit(1) if not ATE_COLUMN in it[STATISTICS_SECTION].keys() : printerr ("Invalid data(%s,%s), no ATE_COLUMN.\n" % (algorithm,dataset)) exit(1) for it in data[algorithm][dataset] : if accuracy == None : accuracy = 0.0 accuracy += float(it[STATISTICS_SECTION][value_name][value_type]) accuracy = accuracy / len(data[algorithm][dataset]) if accuracy == None : latex_str += "& - " elif high_threshold and accuracy > high_threshold : latex_str += "& $>$" + precision % high_threshold elif low_threshold and accuracy < low_threshold : latex_str += " & \\textbf{" + precision % accuracy + "} " else : latex_str += " & " + precision % accuracy latex_str += "\\\\\n" latex_str += "\\hline\n" latex_str += "\\end{tabular}\n" latex_str += "\n" return latex_str def generate_latex (data) : tables = "" tables += generate_latex_table (data , "ATE Mean" , ATE_COLUMN , MEAN_FIELD, precision = "%.2f" , high_threshold = 1 , low_threshold = 0.1) tables += generate_latex_table (data , "ATE Max" , ATE_COLUMN , MAX_FIELD, precision = "%.2f" , high_threshold = 1 , low_threshold = 0.1) tables += generate_latex_table (data , "Frame count" , ATE_COLUMN , COUNT_FIELD, precision= "%d") return generate_latex_doc (tables) ######################################################################################### # MAIN ######################################################################################### def main(): # GET ARGUMENTS parser = argparse.ArgumentParser() #parser.add_argument('-i','--input', action='append', help=' Set flag', required=True) parser.add_argument('files', metavar='N', type=str, nargs='+', help='Files to process') parser.add_argument('--latex', action="store_true", help='Generate the latex file') parser.add_argument('--violins', action="store_true", help='Generate the violins data') parser.add_argument('--plot', type=str, help='Generate the violins pdf file') args = parser.parse_args() #print "Input files: %s" % (str(args.input)) data = load_data_from_files (args.files) if args.latex : latex_str = generate_latex (data) print latex_str if args.violins : violins = generate_violins (data) print violins if args.plot : violins = generate_violins (data) plot_violins (violins, args.plot, default_order) main() ================================================ FILE: scripts/evaluate.py ================================================ #!/usr/bin/env python2 from __future__ import print_function import sys import argparse import math import os import numpy as np import matplotlib.pyplot as plt from tum_evaluate_tools import associate from tum_evaluate_tools import evaluate_ate from tf import transformations def parse_input(filename, remove_repeat=True, input=None): sequences = {} info = {} inputs = {} if input is None: seq = 0 # valid seq will start from 1 else: seq = 1 sequences[1] = {} sequences[1]['traj'] = {} inputs[1] = input with open(filename) as fp: last_pose = None for line in fp: if line.startswith('#') or len(line.strip()) is 0: continue elif line.startswith('seq:'): try: seq = int(line.lstrip('seq:')) sequences[seq] = {} sequences[seq]['traj'] = {} inputs[seq] = info['scene'] + '-%s' % seq except ValueError: exit('Invalid seq value:\n' + line) elif line.startswith('input:'): if input is not None: continue seq += 1 sequences[seq] = {} sequences[seq]['traj'] = {} inputs[seq] = line.lstrip('input:').strip() elif line.startswith('reloc:'): aided_reloc = line.lstrip('aided_reloc:') sequences[seq]['aided_reloc'] = bool(aided_reloc) \ if 'false' not in aided_reloc and 'False' not in aided_reloc else False elif ':' in line: key = line.split(':')[0].strip() value = line.split(':')[1].strip() if key not in info: info[key] = value else: s = line.split() if len(s) != 8 and len(s) != 9: exit('Invalid line:\n' + line) try: stamp = float(s[0]) pose = [float(v) for v in s[-7:]] except ValueError: exit('Invalid line:\n' + line) else: if np.isnan(sum(pose)): continue if remove_repeat and pose == last_pose: continue sequences[seq]['traj'][stamp] = pose last_pose = pose return info, sequences, inputs def tf_matrix_to_values(matrix): t = list(matrix[:3, 3]) q = list(transformations.quaternion_from_matrix(matrix)) return t + q def tf_values_to_matrix(values): angles = transformations.euler_from_quaternion(values[3:]) return transformations.compose_matrix(angles=angles, translate=values[:3]) def transform_target_frame(sequences, scene, tf_target_new): tf_target_new = tf_values_to_matrix(tf_target_new) for seq in sequences: for t in sequences[seq]['traj'].keys(): base_pose = np.dot(tf_values_to_matrix(sequences[seq]['traj'][t]), tf_target_new) sequences[seq]['traj'][t] = tf_matrix_to_values(base_pose) def transform_world_frame(sequences, gts, auto_scale): seq = min(sequences.keys()) traj0 = sequences[seq]['traj'] gt0 = gts[seq]['traj'] matches, ref_traj_interpolated = associate.associate_with_interpolation(gt0, traj0, 0, 0.5) if len(matches) < 1: sequences[seq]['ate'] = {} sequences[seq]['ate_rmse'] = float('nan') sequences[seq]['ate_num'] = 0 sequences[seq]['oe'] = {} sequences[seq]['aoe_rmse'] = float('nan') return first_xyz = np.matrix([[float(value) for value in ref_traj_interpolated[a][0:3]] for a,b in matches]).transpose() second_xyz = np.matrix([[float(value) for value in traj0[b][0:3]] for a,b in matches]).transpose() if auto_scale: rot, trans, scale, ate = evaluate_ate.umeyama_align(second_xyz, first_xyz) else: rot, trans, ate = evaluate_ate.align(second_xyz, first_xyz) scale = 1 sequences[seq]['ate'] = {m[1]: e for m, e in zip(matches, ate)} #print sequences[seq]['ate'] sequences[seq]['ate_rmse'] = np.sqrt(np.dot(ate, ate) / len(ate)) sequences[seq]['ate_num'] = len(ate) tf_matrix = evaluate_ate.compose_transform_matrix(rot, trans, scale) for seq in sequences: traj_trans = {t: tf_matrix_to_values(np.dot(tf_matrix, tf_values_to_matrix(p))) for t,p in sequences[seq]['traj'].items()} sequences[seq]['traj'] = traj_trans seq = min(sequences.keys()) sequences[seq]['oe'] = {b: angle_diff_from_quaternions(ref_traj_interpolated[a][3:], sequences[seq]['traj'][b][3:]) for a,b in matches} aoe = np.abs(np.array(sequences[seq]['oe'].values())) sequences[seq]['aoe_rmse'] = np.sqrt(np.dot(aoe, aoe) / len(aoe)) if len(aoe) > 0 else float('nan') #print(sequences[seq]['oe'].values()) def calculate_ate(sequences, gts): for seq in sequences: if 'ate' in sequences[seq]: continue matches, ref_traj_interpolated = associate.associate_with_interpolation(gts[seq]['traj'], sequences[seq]['traj'], 0, 0.5) first_xyz = np.matrix([[float(value) for value in ref_traj_interpolated[a][0:3]] for a,b in matches]).transpose() second_xyz = np.matrix([[float(value) for value in sequences[seq]['traj'][b][0:3]] for a,b in matches]).transpose() error = second_xyz - first_xyz ate = np.sqrt(np.sum(np.multiply(error, error), 0)).A[0] sequences[seq]['ate'] = {m[1]: e for m, e in zip(matches, ate)} sequences[seq]['oe'] = {b: angle_diff_from_quaternions(ref_traj_interpolated[a][3:], sequences[seq]['traj'][b][3:]) for a,b in matches} aoe = np.abs(np.array(sequences[seq]['oe'].values())) sequences[seq]['ate_rmse'] = np.sqrt(np.dot(ate, ate) / len(ate)) if len(ate) > 0 else float('nan') sequences[seq]['aoe_rmse'] = np.sqrt(np.dot(aoe, aoe) / len(aoe)) if len(aoe) > 0 else float('nan') sequences[seq]['ate_num'] = len(ate) #print(sequences[seq]['oe'].values()) def calculate_correctness(sequences, gts, ate_threshold, aoe_threshold, max_pose_interval, reloc_score_factor): is_pose_correct = lambda ate, oe: ate <= ate_threshold and abs(oe) <= aoe_threshold for seq in sequences: ate = sequences[seq]['ate'] oe = sequences[seq]['oe'] c_ate = [ate[t] for t in ate if is_pose_correct(ate[t], oe[t])] c_oe = [oe[t] for t in oe if is_pose_correct(ate[t], oe[t])] sequences[seq]['c_ate_rmse'] = np.sqrt(np.dot(c_ate, c_ate) / len(c_ate)) if len(c_ate) > 0 else float('nan') sequences[seq]['c_aoe_rmse'] = np.sqrt(np.dot(c_oe, c_oe) / len(c_oe)) if len(c_oe) > 0 else float('nan') sequences[seq]['c_ate_num'] = len(c_ate) if len(ate) is 0: sequences[seq]['reloc_correct'] = False sequences[seq]['reloc_time'] = float('inf') sequences[seq]['reloc_score'] = 0 sequences[seq]['track_time'] = 0 sequences[seq]['track_cr'] = 0 sequences[seq]['correct_time'] = 0 sequences[seq]['cr'] = 0 continue t0 = min(ate.keys()) tmin = min(gts[seq]['traj'].keys()) tmax = max(ate.keys() + gts[seq]['traj'].keys()) gt = gts[seq]['traj'] # re-localization metrics reloc_time = t0 - min(gt.keys()) if reloc_time < 0: reloc_time = 0 sequences[seq]['reloc_time'] = reloc_time sequences[seq]['reloc_correct'] = is_pose_correct(ate[t0], oe[t0]) sequences[seq]['reloc_score'] = math.exp(-reloc_time / reloc_score_factor) if sequences[seq]['reloc_correct'] else 0 # tracking metrics tracked = 0 # accumulated time of correct tracking stamps = sorted(ate.keys()) for t in stamps: next_t = tmax if t == stamps[-1] \ else stamps[stamps.index(t) + 1] if next_t <= t: break if is_pose_correct(ate[t], oe[t]): tracked += min(max_pose_interval, next_t - t) sequences[seq]['track_time'] = tmax - t0 sequences[seq]['track_cr'] = tracked / (tmax - t0) sequences[seq]['correct_time'] = tracked sequences[seq]['cr'] = tracked / (tmax - tmin) def angle_diff_from_quaternions(q1, q2): tf1 = transformations.compose_matrix(angles=transformations.euler_from_quaternion(q1)) tf2 = transformations.compose_matrix(angles=transformations.euler_from_quaternion(q2)) angle,_,_ = transformations.rotation_from_matrix(np.dot(np.linalg.inv(tf1), tf2)) return angle / np.pi * 180. def plot_all_traj(sequences, gts): fig = plt.figure() traj_num = max(sequences.keys()) for seq in sequences: ax = fig.add_subplot(traj_num * 10 + 100 + seq) traj = sequences[seq]['traj'] tt = sorted(traj.keys()) tx = [traj[t][0] for t in tt] ty = [traj[t][1] for t in tt] ax.plot(tx, ty, '-r') ax.hold(True) if len(tx) > 0: ax.plot(tx[0], ty[0], 'or') traj = gts[seq]['traj'] tt = sorted(traj.keys()) tx = [traj[t][0] for t in tt] ty = [traj[t][1] for t in tt] ax.plot(tx, ty, '-g') ax.plot(tx[0], ty[0], 'og') plt.show() def evaluate(sequences, inputs, gts, gt_info, ate_threshold, aoe_threshold, max_pose_interval, reloc_score_factor, auto_scale, print_results=True): seqs = sorted(sequences.keys()) res = [] print_str = lambda s: [print(s) if print_results else None, res.append(s)] column1 = '%-12s' print_str(column1 % 'inputs' + ' '.join(['%8s' % inputs[seq].rstrip('.slam') for seq in seqs])) print_str(column1 % 'poses' + ' '.join(['%8d' % len(sequences[seq]['traj']) for seq in seqs])) #transform_target_frame(gts, info['scene'], gt_info['frame'], info['frame']) transform_world_frame(sequences, gts, auto_scale) calculate_ate(sequences, gts) print_str(column1 % 'matches' + ' '.join(['%8d' % sequences[seq]['ate_num'] for seq in seqs])) print_str(column1 % 'ATE RMSE' + ' '.join(['%8.3f' % sequences[seq]['ate_rmse'] for seq in seqs])) calculate_correctness(sequences, gts, ate_threshold, aoe_threshold, max_pose_interval, reloc_score_factor) print_str(column1 % 'C-ATE RMSE' + ' '.join(['%8.3f' % sequences[seq]['c_ate_rmse'] for seq in seqs])) print_str(column1 % 'AOE RMSE' + ' '.join(['%8.3f' % sequences[seq]['aoe_rmse'] for seq in seqs])) print_str(column1 % 'C-AOE RMSE' + ' '.join(['%8.3f' % sequences[seq]['c_aoe_rmse'] for seq in seqs])) print_str(column1 % 'correct time' + ' '.join(['%8.3f' % sequences[seq]['correct_time'] for seq in seqs])) print_str(column1 % 'correct rate' + ' '.join(['%8.3f' % sequences[seq]['cr'] for seq in seqs])) #print_str(column1 % ('CR-T') + ' '.join(['%8.3f' % sequences[seq]['track_cr'] for seq in seqs])) #print_str(column1 % 'reloc time' + ' '.join(['%8.3f' % sequences[seq]['reloc_time'] for seq in seqs])) print_str(column1 % 'reloc score' + ' '.join(['%8.3f' % sequences[seq]['reloc_score'] for seq in seqs])) print_str('(ATE threshold: %.1f m. AOE threshold: %.1f deg. Reloc time factor: %.1f s.)' % (ate_threshold, aoe_threshold, reloc_score_factor)) return '\n'.join(res) def main(): parser = argparse.ArgumentParser(usage='%(prog)s [options] RESULT_FILE.txt [RESULT_FILE2.txt ...]') parser.add_argument('-g', '--gt-path', help='path to ground-truth files, default is the same folder with results', type=str, default='') group = parser.add_mutually_exclusive_group() group.add_argument('-r', '--remove-repeated-pose', help='ignore repeated poses', dest='remove_repeat', action='store_true') group.add_argument('-k', '--keep-repeated-pose', help='keep repeated poses', dest='remove_repeat', action='store_false') parser.add_argument('-t', '--ate-threshold', type=float, help='ATE threshold of correctness (meter)', default=float('inf')) parser.add_argument('-o', '--aoe-threshold', type=float, help='AOE threshold of correctness (degree)', default=float('inf')) parser.add_argument('-m', '--max-pose-interval', help='consider lost after no pose for such time (sec)', type=float, default=1.) parser.add_argument('-f', '--reloc-score-factor', help='a factor to score time for re-localization (sec)', type=float, default=60.) parser.add_argument('-s', '--scale', help='find optimal scale', dest='scale', action='store_true') group = parser.add_mutually_exclusive_group() group.add_argument('-p', '--plot', help='plot trajectories', dest='plot', action='store_true') group.add_argument('-np', '--no-plot', help='not plot trajectories', dest='plot', action='store_false') parser.set_defaults(remove_repeat=True) parser.set_defaults(scale=False) parser.set_defaults(plot=True) args, left = parser.parse_known_args() if len(left) < 1: parser.print_help(sys.stderr) for filename in left: info, sequences, inputs = parse_input(filename, args.remove_repeat) print('%s: %d trajectories' % (filename, len(sequences))) gt_path = args.gt_path if args.gt_path != '' else os.path.dirname(filename) gts = {} for seq, input in inputs.items(): gt_file = gt_path + '/%s.gt' % input.rstrip('.slam') gt_info, gt_sequences, _ = parse_input(gt_file, input=input) gts[seq] = gt_sequences[1] # assume only one sequence in each gt file evaluate(sequences, inputs, gts, gt_info, args.ate_threshold, args.aoe_threshold, args.max_pose_interval, args.reloc_score_factor, args.scale) if args.plot: plot_all_traj(sequences, gts) if __name__ == "__main__": main() ================================================ FILE: scripts/tum_evaluate_tools/__init__.py ================================================ ================================================ FILE: scripts/tum_evaluate_tools/associate.py ================================================ #!/usr/bin/python # Software License Agreement (BSD License) # # Copyright (c) 2013, Juergen Sturm, TUM # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of TUM nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Requirements: # sudo apt-get install python-argparse """ The Kinect provides the color and depth images in an un-synchronized way. This means that the set of time stamps from the color images do not intersect with those of the depth images. Therefore, we need some way of associating color images to depth images. For this purpose, you can use the ''associate.py'' script. It reads the time stamps from the rgb.txt file and the depth.txt file, and joins them by finding the best matches. """ import argparse import sys import os import numpy import math def read_file_list(filename): """ Reads a trajectory from a text file. File format: The file format is "stamp d1 d2 d3 ...", where stamp denotes the time stamp (to be matched) and "d1 d2 d3.." is arbitary data (e.g., a 3D position and 3D orientation) associated to this timestamp. Input: filename -- File name Output: dict -- dictionary of (stamp,data) tuples """ file = open(filename) data = file.read() lines = data.replace(","," ").replace("\t"," ").split("\n") list = [[float(v.strip()) for v in line.split(" ") if v.strip()!=""] for line in lines if len(line)>0 and line[0]!="#"] list = [(float(l[0]),l[1:]) for l in list if len(l)>1] return dict(list) def associate(first_list, second_list,offset,max_difference): """ Associate two dictionaries of (stamp,data). As the time stamps never match exactly, we aim to find the closest match for every input tuple. Input: first_list -- first dictionary of (stamp,data) tuples second_list -- second dictionary of (stamp,data) tuples offset -- time offset between both dictionaries (e.g., to model the delay between the sensors) max_difference -- search radius for candidate generation Output: matches -- list of matched tuples ((stamp1,data1),(stamp2,data2)) """ first_keys = first_list.keys() second_keys = second_list.keys() potential_matches = [(abs(a - (b + offset)), a, b) for a in first_keys for b in second_keys if abs(a - (b + offset)) < max_difference] potential_matches.sort() matches = [] for diff, a, b in potential_matches: if a in first_keys and b in second_keys: first_keys.remove(a) second_keys.remove(b) matches.append((a, b)) matches.sort() return matches def slerp(q1, q2, w1, w2): q1_dot_q2 = q1[0]*q2[0] + q1[1]*q2[1] + q1[2]*q2[2] + q2[3]*q2[3] if (q1_dot_q2 < 0.0): q2 = [-v for v in q2] q1_dot_q2 = -q1_dot_q2 if (q1_dot_q2 > 0.99999): k1 = w1 k2 = w2 else: sin_theta = math.sqrt(1.0 - q1_dot_q2 * q1_dot_q2) theta = math.atan2(sin_theta, q1_dot_q2) k1 = math.sin(w2 * theta) / sin_theta k2 = math.sin(w1 * theta) / sin_theta q = [k1 * q1[0] + k2 * q2[0], k1 * q1[1] + k2 * q2[1], k1 * q1[2] + k2 * q2[2], k1 * q1[3] + k2 * q2[3]] return q def associate_with_interpolation(first_list, second_list, offset, max_difference): """ Interpolate first_list according to keys in second_list """ interpolated_first_list = {} matches = [] first_keys = first_list.keys() second_keys = second_list.keys() first_keys.sort() second_keys.sort() idx1 = 0 for i in range(len(second_keys)): key = second_keys[i] + offset if key < first_keys[0]: continue elif key > first_keys[-1]: break idx1 = next(i for i in range(idx1, len(first_keys) - 1) if first_keys[i] <= key and first_keys[i + 1] >= key) key1 = first_keys[idx1] key2 = first_keys[idx1 + 1] if max((key - key1), (key2 - key)) < max_difference: w2 = float(key - key1) / (key2 - key1) w1 = 1 - w2 x1 = first_list.get(key1) x2 = first_list.get(key2) interpolated = [w1 * x1[0] + w2 * x2[0], w1 * x1[1] + w2 * x2[1], w1 * x1[2] + w2 * x2[2]] interpolated += slerp(x1[3:], x2[3:], w1, w2) interpolated_first_list.update({key: interpolated}) matches.append((key, second_keys[i])) matches.sort() return matches, interpolated_first_list if __name__ == '__main__': # parse command line parser = argparse.ArgumentParser(description=''' This script takes two data files with timestamps and associates them ''') parser.add_argument('first_file', help='first text file (format: timestamp data)') parser.add_argument('second_file', help='second text file (format: timestamp data)') parser.add_argument('--first_only', help='only output associated lines from first file', action='store_true') parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0) parser.add_argument('--max_difference', help='maximally allowed time difference for matching entries (default: 0.02)',default=0.02) args = parser.parse_args() first_list = read_file_list(args.first_file) second_list = read_file_list(args.second_file) matches = associate(first_list, second_list,float(args.offset),float(args.max_difference)) if args.first_only: for a,b in matches: print("%f %s"%(a," ".join(first_list[a]))) else: for a,b in matches: print("%f %s %f %s"%(a," ".join(first_list[a]),b-float(args.offset)," ".join(second_list[b]))) ================================================ FILE: scripts/tum_evaluate_tools/evaluate_ate.py ================================================ #!/usr/bin/python # Software License Agreement (BSD License) # # Copyright (c) 2013, Juergen Sturm, TUM # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of TUM nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # # Requirements: # sudo apt-get install python-argparse """ This script computes the absolute trajectory error from the ground truth trajectory and the estimated trajectory. """ import sys import numpy import argparse import associate def umeyama_align(x, y, with_scale=True): """ Computes the least squares solution parameters of an Sim(m) matrix that minimizes the distance between a set of registered points. Umeyama, Shinji: Least-squares estimation of transformation parameters between two point patterns. IEEE PAMI, 1991 :param x: mxn matrix of points, m = dimension, n = nr. of data points :param y: mxn matrix of points, m = dimension, n = nr. of data points :param with_scale: set to True to align also the scale (default: 1.0 scale) :return: r, t, c - rotation matrix, translation vector and scale factor """ if x.shape != y.shape: print x.shape, y.shape raise RuntimeError("data matrices must have the same shape") # m = dimension, n = nr. of data points m, n = x.shape # means, eq. 34 and 35 mean_x = x.mean(axis=1) mean_y = y.mean(axis=1) # variance, eq. 36 # "transpose" for column subtraction # mean_x_ = mean_x[:, numpy.newaxis] # print mean_x.shape # print mean_x_.shape temp = x - mean_x # temp = numpy.array(temp) # print temp.shape sigma_x = 1.0 / n * (numpy.linalg.norm(temp)**2) # covariance matrix, eq. 38 outer_sum = numpy.zeros((m, m)) for i in range(n): outer_sum += numpy.outer((y[:, i] - mean_y), (x[:, i] - mean_x)) cov_xy = numpy.multiply(1.0 / n, outer_sum) # SVD (text betw. eq. 38 and 39) u, d, v = numpy.linalg.svd(cov_xy) # S matrix, eq. 43 s = numpy.eye(m) if numpy.linalg.det(u) * numpy.linalg.det(v) < 0.0: # Ensure a RHS coordinate system (Kabsch algorithm). s[m - 1, m - 1] = -1 # rotation, eq. 40 r = u.dot(s).dot(v) # scale & translation, eq. 42 and 41 c = 1 / sigma_x * numpy.trace(numpy.diag(d).dot(s)) if with_scale else 1.0 t = mean_y - numpy.multiply(c, r.dot(mean_x)) model_aligned = r * (c * x) + t alignment_error = model_aligned - y alignment_error_t = alignment_error.T count = 0 count_ex = 0 for i in range(alignment_error_t.shape[0]): count = count + 1 err = alignment_error_t[i] err = err * err.T if err > 0.1: count_ex = count_ex + 1 # print i print count_ex, count trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error, alignment_error), 0)).A[0] return r, t, c, trans_error def align(model,data): """Align two trajectories using the method of Horn (closed-form). Input: model -- first trajectory (3xn) data -- second trajectory (3xn) Output: rot -- rotation matrix (3x3) trans -- translation vector (3x1) trans_error -- translational error per point (1xn) """ numpy.set_printoptions(precision=3,suppress=True) model_zerocentered = model - model.mean(1) data_zerocentered = data - data.mean(1) W = numpy.zeros( (3,3) ) for column in range(model.shape[1]): W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column]) U,d,Vh = numpy.linalg.linalg.svd(W.transpose()) S = numpy.matrix(numpy.identity( 3 )) if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0): S[2,2] = -1 rot = U*S*Vh trans = data.mean(1) - rot * model.mean(1) model_aligned = rot * model + trans alignment_error = model_aligned - data trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0] return rot,trans,trans_error def compose_transform_matrix(rot, trans, scale=1): M = numpy.identity(4) M[:3, :3] = rot M[:3, 3:] = trans if scale is not 1: S = numpy.identity(4) * scale S[3, 3] = 1 M = numpy.dot(M, S) M /= M[3, 3] return M def plot_traj(ax,stamps,traj,style,color,label): """ Plot a trajectory using matplotlib. Input: ax -- the plot stamps -- time stamps (1xn) traj -- trajectory (3xn) style -- line style color -- line color label -- plot legend """ stamps.sort() interval = numpy.median([s-t for s,t in zip(stamps[1:],stamps[:-1])]) x = [] y = [] last = stamps[0] for i in range(len(stamps)): if stamps[i]-last < 2*interval: x.append(traj[i][0]) y.append(traj[i][1]) elif len(x)>0: ax.plot(x,y,style,color=color,label=label) label="" x=[] y=[] last= stamps[i] if len(x)>0: ax.plot(x,y,style,color=color,label=label) if __name__=="__main__": # parse command line parser = argparse.ArgumentParser(description=''' This script computes the absolute trajectory error from the ground truth trajectory and the estimated trajectory. ''') parser.add_argument('first_file', help='ground truth trajectory (format: timestamp tx ty tz qx qy qz qw)') parser.add_argument('second_file', help='estimated trajectory (format: timestamp tx ty tz qx qy qz qw)') parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0) parser.add_argument('--scale', help='scaling factor for the second trajectory (default: 1.0)',default=1.0) parser.add_argument('--max_difference', help='maximally allowed time difference for matching entries (default: 0.02)',default=0.02) parser.add_argument('--save', help='save aligned second trajectory to disk (format: stamp2 x2 y2 z2)') parser.add_argument('--save_associations', help='save associated first and aligned second trajectory to disk (format: stamp1 x1 y1 z1 stamp2 x2 y2 z2)') parser.add_argument('--plot', help='plot the first and the aligned second trajectory to an image (format: png)') parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the RMSE absolute translational error in meters after alignment will be printed)', action='store_true') args = parser.parse_args() first_list = associate.read_file_list(args.first_file) second_list = associate.read_file_list(args.second_file) matches = associate.associate(first_list, second_list,float(args.offset),float(args.max_difference)) if len(matches)<2: sys.exit("Couldn't find matching timestamp pairs between groundtruth and estimated trajectory! Did you choose the correct sequence?") first_xyz = numpy.matrix([[float(value) for value in first_list[a][0:3]] for a,b in matches]).transpose() second_xyz = numpy.matrix([[float(value)*float(args.scale) for value in second_list[b][0:3]] for a,b in matches]).transpose() rot,trans,trans_error = align(second_xyz,first_xyz) second_xyz_aligned = rot * second_xyz + trans first_stamps = first_list.keys() first_stamps.sort() first_xyz_full = numpy.matrix([[float(value) for value in first_list[b][0:3]] for b in first_stamps]).transpose() second_stamps = second_list.keys() second_stamps.sort() second_xyz_full = numpy.matrix([[float(value)*float(args.scale) for value in second_list[b][0:3]] for b in second_stamps]).transpose() second_xyz_full_aligned = rot * second_xyz_full + trans if args.verbose: print ("compared_pose_pairs %d pairs"%(len(trans_error))) print ("absolute_translational_error.rmse %f m"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))) print ("absolute_translational_error.mean %f m"%numpy.mean(trans_error)) print ("absolute_translational_error.median %f m"%numpy.median(trans_error)) print ("absolute_translational_error.std %f m"%numpy.std(trans_error)) print ("absolute_translational_error.min %f m"%numpy.min(trans_error)) print ("absolute_translational_error.max %f m"%numpy.max(trans_error)) else: print ("%f"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error))) if args.save_associations: file = open(args.save_associations,"w") file.write("\n".join(["%f %f %f %f %f %f %f %f"%(a,x1,y1,z1,b,x2,y2,z2) for (a,b),(x1,y1,z1),(x2,y2,z2) in zip(matches,first_xyz.transpose().A,second_xyz_aligned.transpose().A)])) file.close() if args.save: file = open(args.save,"w") file.write("\n".join(["%f "%stamp+" ".join(["%f"%d for d in line]) for stamp,line in zip(second_stamps,second_xyz_full_aligned.transpose().A)])) file.close() if args.plot: import matplotlib matplotlib.use('Agg') import matplotlib.pyplot as plt import matplotlib.pylab as pylab from matplotlib.patches import Ellipse fig = plt.figure() ax = fig.add_subplot(111) plot_traj(ax,first_stamps,first_xyz_full.transpose().A,'-',"black","ground truth") plot_traj(ax,second_stamps,second_xyz_full_aligned.transpose().A,'-',"blue","estimated") label="difference" for (a,b),(x1,y1,z1),(x2,y2,z2) in zip(matches,first_xyz.transpose().A,second_xyz_aligned.transpose().A): ax.plot([x1,x2],[y1,y2],'-',color="red",label=label) label="" ax.legend() ax.set_xlabel('x [m]') ax.set_ylabel('y [m]') plt.savefig(args.plot,dpi=90)